From 33e9c5446d534eb136083aeb9d596c93ca4e6ed7 Mon Sep 17 00:00:00 2001 From: liang <2303335747@qq.com> Date: Sat, 24 Sep 2022 16:54:35 +0800 Subject: [PATCH] add b1_description --- robots/b1_description/CMakeLists.txt | 19 + .../b1_description/config/robot_control.yaml | 70 ++ robots/b1_description/launch/b1_rviz.launch | 25 + robots/b1_description/launch/check_joint.rviz | 252 +++++ robots/b1_description/meshes/calf.dae | 63 ++ robots/b1_description/meshes/hip.dae | 63 ++ robots/b1_description/meshes/thigh.dae | 63 ++ robots/b1_description/meshes/thigh_mirror.dae | 63 ++ robots/b1_description/meshes/trunk.dae | 63 ++ robots/b1_description/package.xml | 14 + robots/b1_description/xacro/b1.urdf | 965 ++++++++++++++++++ robots/b1_description/xacro/const.xacro | 104 ++ robots/b1_description/xacro/gazebo.xacro | 266 +++++ robots/b1_description/xacro/leg.xacro | 176 ++++ robots/b1_description/xacro/materials.xacro | 40 + robots/b1_description/xacro/robot.xacro | 144 +++ robots/b1_description/xacro/stairs.xacro | 46 + .../b1_description/xacro/transmission.xacro | 42 + 18 files changed, 2478 insertions(+) create mode 100644 robots/b1_description/CMakeLists.txt create mode 100644 robots/b1_description/config/robot_control.yaml create mode 100644 robots/b1_description/launch/b1_rviz.launch create mode 100644 robots/b1_description/launch/check_joint.rviz create mode 100644 robots/b1_description/meshes/calf.dae create mode 100644 robots/b1_description/meshes/hip.dae create mode 100644 robots/b1_description/meshes/thigh.dae create mode 100644 robots/b1_description/meshes/thigh_mirror.dae create mode 100644 robots/b1_description/meshes/trunk.dae create mode 100644 robots/b1_description/package.xml create mode 100644 robots/b1_description/xacro/b1.urdf create mode 100644 robots/b1_description/xacro/const.xacro create mode 100644 robots/b1_description/xacro/gazebo.xacro create mode 100644 robots/b1_description/xacro/leg.xacro create mode 100644 robots/b1_description/xacro/materials.xacro create mode 100644 robots/b1_description/xacro/robot.xacro create mode 100644 robots/b1_description/xacro/stairs.xacro create mode 100644 robots/b1_description/xacro/transmission.xacro diff --git a/robots/b1_description/CMakeLists.txt b/robots/b1_description/CMakeLists.txt new file mode 100644 index 0000000..af116cb --- /dev/null +++ b/robots/b1_description/CMakeLists.txt @@ -0,0 +1,19 @@ +cmake_minimum_required(VERSION 2.8.3) +project(b1_description) + +find_package(catkin REQUIRED COMPONENTS + genmsg + roscpp + std_msgs + tf +) + +catkin_package( + CATKIN_DEPENDS +) + +include_directories( + # include + ${Boost_INCLUDE_DIR} + ${catkin_INCLUDE_DIRS} +) diff --git a/robots/b1_description/config/robot_control.yaml b/robots/b1_description/config/robot_control.yaml new file mode 100644 index 0000000..116d765 --- /dev/null +++ b/robots/b1_description/config/robot_control.yaml @@ -0,0 +1,70 @@ +b1_gazebo: + # Publish all joint states ----------------------------------- + joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 1000 + + # FL Controllers --------------------------------------- + FL_hip_controller: + type: unitree_legged_control/UnitreeJointController + joint: FL_hip_joint + pid: {p: 100.0, i: 0.0, d: 5.0} + + FL_thigh_controller: + type: unitree_legged_control/UnitreeJointController + joint: FL_thigh_joint + pid: {p: 300.0, i: 0.0, d: 8.0} + + FL_calf_controller: + type: unitree_legged_control/UnitreeJointController + joint: FL_calf_joint + pid: {p: 300.0, i: 0.0, d: 8.0} + + # FR Controllers --------------------------------------- + FR_hip_controller: + type: unitree_legged_control/UnitreeJointController + joint: FR_hip_joint + pid: {p: 100.0, i: 0.0, d: 5.0} + + FR_thigh_controller: + type: unitree_legged_control/UnitreeJointController + joint: FR_thigh_joint + pid: {p: 300.0, i: 0.0, d: 8.0} + + FR_calf_controller: + type: unitree_legged_control/UnitreeJointController + joint: FR_calf_joint + pid: {p: 300.0, i: 0.0, d: 8.0} + + # RL Controllers --------------------------------------- + RL_hip_controller: + type: unitree_legged_control/UnitreeJointController + joint: RL_hip_joint + pid: {p: 100.0, i: 0.0, d: 5.0} + + RL_thigh_controller: + type: unitree_legged_control/UnitreeJointController + joint: RL_thigh_joint + pid: {p: 300.0, i: 0.0, d: 8.0} + + RL_calf_controller: + type: unitree_legged_control/UnitreeJointController + joint: RL_calf_joint + pid: {p: 300.0, i: 0.0, d: 8.0} + + # RR Controllers --------------------------------------- + RR_hip_controller: + type: unitree_legged_control/UnitreeJointController + joint: RR_hip_joint + pid: {p: 100.0, i: 0.0, d: 5.0} + + RR_thigh_controller: + type: unitree_legged_control/UnitreeJointController + joint: RR_thigh_joint + pid: {p: 300.0, i: 0.0, d: 8.0} + + RR_calf_controller: + type: unitree_legged_control/UnitreeJointController + joint: RR_calf_joint + pid: {p: 300.0, i: 0.0, d: 8.0} + diff --git a/robots/b1_description/launch/b1_rviz.launch b/robots/b1_description/launch/b1_rviz.launch new file mode 100644 index 0000000..6609465 --- /dev/null +++ b/robots/b1_description/launch/b1_rviz.launch @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/robots/b1_description/launch/check_joint.rviz b/robots/b1_description/launch/check_joint.rviz new file mode 100644 index 0000000..1e095df --- /dev/null +++ b/robots/b1_description/launch/check_joint.rviz @@ -0,0 +1,252 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /TF1/Frames1 + Splitter Ratio: 0.5 + Tree Height: 530 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: "" +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Alpha: 1 + Class: rviz/RobotModel + Collision Enabled: false + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + FL_calf: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + FL_foot: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + FL_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + FL_thigh: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + FR_calf: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + FR_foot: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + FR_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + FR_thigh: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Link Tree Style: Links in Alphabetic Order + RL_calf: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RL_foot: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RL_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RL_thigh: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RR_calf: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RR_foot: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RR_hip: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + RR_thigh: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + imu_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + trunk: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Name: RobotModel + Robot Description: robot_description + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true + - Class: rviz/Axes + Enabled: false + Length: 1 + Name: Axes + Radius: 0.10000000149011612 + Reference Frame: + Value: false + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: false + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + {} + Update Interval: 0 + Value: false + Enabled: true + Global Options: + Background Color: 238; 238; 238 + Default Light: true + Fixed Frame: base + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 9.812193870544434 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.041462767869234085 + Y: -0.411843866109848 + Z: 0.29937663674354553 + Focal Shape Fixed Size: false + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.03979745879769325 + Target Frame: + Value: Orbit (rviz) + Yaw: 1.2935912609100342 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 759 + Hide Left Dock: false + Hide Right Dock: true + QMainWindow State: 000000ff00000000fd0000000400000000000001b90000029dfc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d0000029d000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000c00430061006d00650072006101000001be000001900000000000000000000000010000010f000002e2fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a005600690065007700730000000028000002e2000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000006400000003efc0100000002fb0000000800540069006d0065000000000000000640000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000003ae0000029d00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1389 + X: 472 + Y: 233 diff --git a/robots/b1_description/meshes/calf.dae b/robots/b1_description/meshes/calf.dae new file mode 100644 index 0000000..3401990 --- /dev/null +++ b/robots/b1_description/meshes/calf.dae @@ -0,0 +1,63 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + 周四 2月 24 05:14:32 2022 + 周四 2月 24 05:14:32 2022 + + + + + + + + + -0.0125551 -0.0135382 -0.335592 -0.0120732 -0.0137133 -0.335969 -0.0163457 0.00925657 -0.332628 -0.0155834 -0.0108107 -0.333224 -0.0163824 -0.00919656 -0.3326 -0.0161391 -0.00975288 -0.33279 -0.0165265 -0.00875569 -0.332487 -0.016536 -0.00876069 -0.332479 -0.0166702 -0.00831457 -0.332375 -0.0150823 -0.0115225 -0.333616 -0.0144164 -0.0122464 -0.334137 -0.0139081 -0.0127111 -0.334534 -0.0136882 -0.0128641 -0.334706 -0.0129065 -0.0133679 -0.335317 -0.0132499 -0.0131729 -0.335049 -0.0133017 -0.0131263 -0.335008 0.0213369 -0.00770284 -0.362092 -0.0156525 0.0106716 -0.33317 -0.0170465 0.00549712 -0.33208 -0.0166702 0.00830881 -0.332375 -0.0170044 -0.00645604 -0.332113 -0.016979 -0.00661236 -0.332133 -0.0168784 -0.00739722 -0.332212 -0.0166809 -0.00823512 -0.332366 0.0201123 -0.0108107 -0.361134 0.0210554 -0.00875569 -0.361872 0.0210649 -0.00876069 -0.361879 0.020668 -0.00975288 -0.361569 -0.0103401 -0.014016 -0.337324 0.0214072 -0.00739722 -0.362147 0.0215754 -0.00550288 -0.362278 0.0215754 -2.88296e-06 -0.362278 0.0215651 0.00549712 -0.36227 0.0148689 -0.014016 -0.357034 0.0156198 -0.0139624 -0.357622 0.015743 -0.0139302 -0.357718 0.0163613 -0.0138025 -0.358201 0.0170839 -0.0135382 -0.358766 0.016602 -0.0137133 -0.35839 0.0196038 -0.0115133 -0.360737 0.0189453 -0.0122464 -0.360222 0.018437 -0.0127111 -0.359824 0.018217 -0.0128641 -0.359652 0.0177788 -0.0131729 -0.35931 0.0214826 0.00682681 -0.362206 0.0214072 0.00739145 -0.362147 0.021199 0.00830881 -0.361984 0.0211512 0.00843911 -0.361946 0.0209112 0.0091908 -0.361759 0.0205474 0.0100263 -0.361474 0.0202862 0.0104933 -0.36127 0.0196111 0.0115168 -0.360742 -0.015075 0.0115075 -0.333622 -0.0145215 0.0121529 -0.334055 -0.0139081 0.0127053 -0.334534 -0.0144164 0.0122406 -0.334137 -0.0136882 0.0128583 -0.334706 -0.0132499 0.0131671 -0.335049 -0.0129065 0.0133622 -0.335317 0.0188048 0.0123738 -0.360112 0.018437 0.0127053 -0.359824 0.0177788 0.0131671 -0.35931 0.0174354 0.0133622 -0.359041 0.0176723 0.0132163 -0.359226 0.0174314 0.0133501 -0.359038 0.0169382 0.0135811 -0.358652 0.0163613 0.0137967 -0.358201 0.0159164 0.0138925 -0.357853 0.0148689 0.0139971 -0.357034 0.0148689 0.0140102 -0.357034 -0.0103401 0.0139971 -0.337324 -0.010778 0.0139789 -0.336981 -0.0112141 0.0139244 -0.336641 -0.0120732 0.0137075 -0.335969 -0.0124925 0.013546 -0.335641 -0.015075 -0.0115133 -0.333622 -0.0159851 -0.00965721 -0.332862 -0.0170362 -0.00550288 -0.332088 -0.0133161 -0.012464 -0.334605 -0.01015 -0.0135409 -0.337081 -0.0119109 -0.0133717 -0.33591 -0.0116633 -0.0132303 -0.335655 -0.0117889 -0.0132671 -0.335799 -0.0134587 -0.0125579 -0.3347 -0.0135894 -0.0126984 -0.334735 -0.0101861 -0.0135699 -0.337127 -0.0102499 -0.0136493 -0.337209 -0.0102988 -0.0137529 -0.337271 -0.0170219 -0.00605881 -0.3321 -0.0161196 -0.00757344 -0.33217 -0.0166675 -0.00550288 -0.332191 -0.0168621 -0.00550288 -0.332176 -0.0168081 -0.00770284 -0.332267 -0.0162664 -0.00758329 -0.332298 -0.0164488 -0.00761134 -0.332362 -0.016639 -0.00765332 -0.332351 -0.0158077 -0.00957611 -0.332863 -0.014945 -0.011378 -0.333675 -0.0156525 -0.0106774 -0.33317 -0.0147878 -0.0112633 -0.33366 -0.0156339 -0.00952191 -0.332793 -0.0151307 -0.0102052 -0.332943 -0.0146275 -0.0111867 -0.33358 -0.0129026 -0.0133559 -0.33532 -0.0120107 -0.0135284 -0.335969 0.0148689 -0.0140029 -0.357034 -0.0103401 -0.0140029 -0.337324 -0.0103166 -0.0138115 -0.337294 0.0149591 -0.0136493 -0.356919 0.0150229 -0.0135699 -0.356837 0.0151769 -0.0135029 -0.356641 -0.0100321 -0.0135029 -0.33693 0.0195207 -0.011378 -0.360623 0.0153069 -0.0139847 -0.357377 0.0188813 -0.011975 -0.359537 0.0196333 -0.0111597 -0.360125 0.0150591 -0.0135409 -0.356791 0.016698 -0.0132671 -0.358073 0.0149102 -0.0137529 -0.356982 0.0148924 -0.0138115 -0.357004 0.0174314 -0.0133559 -0.359038 0.0165865 -0.0135284 -0.358329 0.0170213 -0.0135518 -0.358717 0.0182252 -0.012464 -0.359267 0.0166201 -0.0133717 -0.358218 0.018168 -0.0125579 -0.359428 0.0195366 -0.0111867 -0.360292 0.0181651 -0.0126984 -0.359563 0.0205429 -0.00952191 -0.361079 0.0194971 -0.0112633 -0.360467 0.0205609 -0.00965721 -0.361437 0.0208745 -0.00926234 -0.36173 0.0201814 -0.0106774 -0.361188 0.0212644 -0.00757344 -0.3614 0.0211755 -0.00758329 -0.361574 0.020517 -0.00957611 -0.361265 0.0211581 -0.00761134 -0.361766 0.0213913 -0.00550288 -0.361742 0.0212148 -0.00765332 -0.361948 0.0214378 -0.00550288 -0.362122 0.0215651 -0.00550288 -0.36227 0.0214094 0.00549712 -0.362063 0.0213768 0.00549712 -0.361937 0.0213768 -0.00550288 -0.361937 0.0214792 -0.00550288 -0.361568 0.0212997 0.00675907 -0.361745 0.0214792 0.00549712 -0.361568 0.0214016 0.00674859 -0.361508 0.0212374 0.00812376 -0.362014 0.0213801 0.0074814 -0.362125 0.0215444 0.00616402 -0.362254 0.0210913 0.00804651 -0.361815 0.0210554 0.00874993 -0.361872 0.020701 0.00924254 -0.361509 0.0208353 0.00935604 -0.361699 0.0201682 0.0103463 -0.361093 0.0178608 0.0128479 -0.359289 0.0179089 0.0130707 -0.359411 0.0187303 0.0121715 -0.359969 0.0192177 0.0119606 -0.360435 0.0196038 0.0115075 -0.360737 0.0199607 0.0110174 -0.361016 0.021378 0.00549712 -0.361806 0.0211707 0.00796925 -0.361327 0.0207923 0.00912904 -0.361031 0.0206853 0.00915945 -0.361265 0.0202756 0.0101994 -0.360627 0.0196333 0.011154 -0.360125 0.0188813 0.0119693 -0.359537 0.0187583 0.0120234 -0.359758 0.0180381 0.0126252 -0.358878 0.0179081 0.0126849 -0.359093 0.0213294 0.0067877 -0.362001 0.0210669 0.00798995 -0.361563 0.0201643 0.0102388 -0.360857 0.0195166 0.0112013 -0.360351 0.0195058 0.0113307 -0.360575 0.0169867 0.0131693 -0.358373 0.0169186 0.0133433 -0.358552 0.0164321 0.0137623 -0.358257 0.0161628 0.0133986 -0.357411 0.0160171 0.0134648 -0.357615 0.0159269 0.0136455 -0.357777 0.0149102 0.0137471 -0.356982 0.0149591 0.0136436 -0.356919 -0.0102499 0.0136436 -0.337209 0.0150229 0.0135641 -0.356837 -0.01015 0.0135352 -0.337081 -0.0144885 0.011154 -0.333446 -0.0103166 0.0138058 -0.337294 -0.0100321 0.0134971 -0.33693 -0.0119109 0.013366 -0.33591 -0.0129026 0.0133501 -0.33532 -0.0116633 0.0132245 -0.335655 -0.0117889 0.0132613 -0.335799 -0.0134587 0.0125521 -0.3347 -0.0120107 0.0135227 -0.335969 -0.0135894 0.0126926 -0.334735 -0.0137365 0.0119693 -0.334034 -0.0146275 0.0111809 -0.33358 -0.0133161 0.0124583 -0.334605 -0.0156339 0.00951615 -0.332793 -0.0147878 0.0112575 -0.33366 -0.014945 0.0113722 -0.333675 -0.0165265 0.00874993 -0.332487 -0.0161391 0.00974712 -0.33279 -0.0164488 0.00760557 -0.332362 -0.0158077 0.00957034 -0.332863 -0.0159851 0.00965145 -0.332862 -0.016639 0.00764756 -0.332351 -0.0162664 0.00757752 -0.332298 -0.0164822 0.00549712 -0.33213 -0.0168081 0.00769708 -0.332267 -0.0170362 0.00549712 -0.332088 -0.0168621 0.00549712 -0.332176 -0.0166675 0.00549712 -0.332191 -0.0164822 -0.00550288 -0.33213 -0.00707553 -0.0135029 -0.333149 -0.0131832 -0.0124311 -0.334466 -0.0137365 -0.011975 -0.334034 -0.0144885 -0.0111597 -0.333446 -0.0130693 -0.00797502 -0.328462 -0.01549 -0.00950288 -0.332663 -0.0163344 -0.00550288 -0.332002 0.0244358 -0.00550288 -0.357787 0.0206348 -0.00950288 -0.360908 0.0232321 -0.0102052 -0.356846 0.0202756 -0.0102052 -0.360627 0.018328 -0.0124311 -0.359104 0.020081 -0.0131113 -0.354382 0.0168081 -0.0132303 -0.357916 0.0181335 0.0134971 -0.352859 0.0171244 0.0131056 -0.358163 0.0218379 0.0119693 -0.355756 0.0232321 0.0101994 -0.356846 0.0241273 0.00796925 -0.357546 0.0151769 0.0134971 -0.356641 -0.0133778 0.00549712 -0.328221 -0.0161196 0.00756767 -0.33217 -0.01549 0.00949712 -0.332663 -0.0151307 0.0101994 -0.332943 -0.0131832 0.0124253 -0.334466 -0.0163344 0.00549712 -0.332002 0.0217347 -0.00550288 -0.363304 0.0217347 -2.88296e-06 -0.363304 0.0218717 -0.00550288 -0.363624 0.0221463 -2.88296e-06 -0.363839 0.0221463 -0.00550288 -0.363839 0.0224904 -2.88296e-06 -0.363895 0.0216826 -0.00763368 -0.363476 0.0224904 -0.00550288 -0.363895 0.0228187 -0.00550288 -0.363777 0.0226129 -0.00782067 -0.363617 0.0222883 -0.00777919 -0.363737 0.0210285 -0.0119972 -0.362378 0.0194562 -0.0135007 -0.361522 0.0197292 -0.0136465 -0.361362 0.016439 -0.0156578 -0.358789 0.0219503 -0.00771124 -0.363686 0.0216923 -0.00994134 -0.363271 0.0207322 -0.0118809 -0.36252 0.0204406 -0.0116906 -0.362505 0.0192027 -0.013262 -0.361537 0.0179282 -0.0147194 -0.360328 0.0162249 -0.015476 -0.358996 0.0160679 -0.0151783 -0.359086 0.0144317 -0.0157325 -0.357594 0.0213721 -0.00980886 -0.363234 0.020226 -0.0114733 -0.362337 0.0190315 -0.0129895 -0.361404 0.0177203 -0.0144443 -0.360378 0.0176012 -0.0141303 -0.360285 0.0160068 -0.0148385 -0.359039 0.0211247 -0.00965764 -0.36304 0.0189851 -0.0127508 -0.361154 0.0215516 -0.00756574 -0.363161 0.0210115 -0.00952515 -0.362738 0.0201414 -0.0112829 -0.362058 0.020208 -0.0111666 -0.361736 0.0190749 -0.012605 -0.36085 0.0176004 -0.0138552 -0.360071 0.017718 -0.0136872 -0.359789 0.0160568 -0.0145408 -0.358864 0.0146131 -0.0145868 -0.357362 -0.0105959 -0.0145868 -0.337651 -0.0107773 -0.0147733 -0.337883 0.0144317 -0.0147733 -0.357594 0.0143282 -0.0150786 -0.357726 0.0143282 -0.0154272 -0.357726 -0.0108809 -0.0154272 -0.338016 -0.0107773 -0.0157325 -0.337883 -0.0105959 -0.0159189 -0.337651 -0.0124024 -0.0145408 -0.336613 -0.0125706 -0.015476 -0.336481 -0.015712 -0.0136465 -0.333651 -0.0170113 -0.0119972 -0.332635 -0.0170779 -0.0118809 -0.332957 -0.018038 -0.00994134 -0.332206 -0.0185958 -0.00782067 -0.331396 -0.0126206 -0.0151783 -0.336655 -0.0142739 -0.0147194 -0.335149 -0.0158019 -0.0135007 -0.333955 -0.0179248 -0.00980886 -0.332508 -0.018634 -0.00777919 -0.33174 -0.018836 -0.00550288 -0.331582 -0.0108809 -0.0150786 -0.338016 -0.0125595 -0.0148385 -0.336703 -0.014273 -0.0144443 -0.335363 -0.0157554 -0.013262 -0.334204 -0.0141539 -0.0141303 -0.335456 -0.0169934 -0.0116906 -0.333236 -0.0167787 -0.0114733 -0.333404 -0.0176774 -0.00965764 -0.332701 -0.018503 -0.00771124 -0.332056 -0.0155842 -0.0129895 -0.334338 -0.0164871 -0.0112829 -0.333419 -0.0178973 -0.00756574 -0.332316 -0.0182353 -0.00763368 -0.332265 -0.0184245 -0.00550288 -0.332117 -0.0121883 -0.0143591 -0.336406 -0.013946 -0.0138552 -0.335406 -0.0137009 -0.0136872 -0.335223 -0.0150578 -0.012605 -0.334163 -0.0153307 -0.0127508 -0.334323 -0.0161909 -0.0111666 -0.333277 -0.0173572 -0.00952515 -0.332738 -0.0170434 -0.00944427 -0.33261 -0.0177521 -0.00550288 -0.332056 -0.0180804 0.00549712 -0.332173 -0.0180804 -0.00550288 -0.332173 -0.018699 -0.00550288 -0.331903 -0.018699 0.00549712 -0.331903 -0.018836 0.00549712 -0.331582 -0.0188015 -0.00550288 -0.331235 -0.0188015 0.00549712 -0.331235 -0.0184245 0.00549712 -0.332117 -0.0182353 0.00762792 -0.332265 -0.0185958 0.0078149 -0.331396 -0.0179889 0.0100165 -0.331871 -0.0170113 0.0119914 -0.332635 -0.0170779 0.0118752 -0.332957 -0.0158019 0.0134949 -0.333955 -0.015712 0.0136407 -0.333651 -0.0141562 0.0148816 -0.334867 -0.0124219 0.015652 -0.336223 -0.0105959 0.0159132 -0.337651 -0.018634 0.00777342 -0.33174 -0.018038 0.00993558 -0.332206 -0.0157554 0.0132562 -0.334204 -0.0142739 0.0147137 -0.335149 -0.014273 0.0144386 -0.335363 -0.0125706 0.0154702 -0.336481 -0.0107773 0.0157267 -0.337883 -0.0126206 0.0151726 -0.336655 -0.018503 0.00770548 -0.332056 -0.0179248 0.0098031 -0.332508 -0.0176774 0.00965187 -0.332701 -0.0169934 0.0116848 -0.333236 -0.0167787 0.0114675 -0.333404 -0.0141539 0.0141245 -0.335456 -0.0125595 0.0148328 -0.336703 -0.0108809 0.0154214 -0.338016 -0.0178973 0.00755997 -0.332316 -0.0173572 0.00951939 -0.332738 -0.0164871 0.0112771 -0.333419 -0.0155842 0.0129837 -0.334338 -0.0153307 0.012745 -0.334323 -0.0124024 0.0145351 -0.336613 -0.0108809 0.0150728 -0.338016 -0.0175727 0.00751849 -0.332196 -0.0170434 0.0094385 -0.33261 -0.0150578 0.0125992 -0.334163 -0.0137009 0.0136815 -0.335223 -0.013946 0.0138495 -0.335406 -0.0107773 0.0147675 -0.337883 -0.0105959 0.0145811 -0.337651 0.0146131 0.0145811 -0.357362 0.0144317 0.0147675 -0.357594 0.0143282 0.0150728 -0.357726 0.0160068 0.0148328 -0.359039 0.0144317 0.0157267 -0.357594 0.016439 0.015652 -0.358789 0.0181733 0.0148816 -0.360145 0.0197292 0.0136407 -0.361362 0.0210285 0.0119914 -0.362378 0.0207322 0.0118752 -0.36252 0.0143282 0.0154214 -0.357726 0.0162249 0.0154702 -0.358996 0.0179282 0.0147137 -0.360328 0.0177203 0.0144386 -0.360378 0.0194562 0.0134949 -0.361522 0.0192027 0.0132562 -0.361537 0.0216923 0.00993558 -0.363271 0.0222883 0.00777342 -0.363737 0.0160679 0.0151726 -0.359086 0.0176012 0.0141245 -0.360285 0.020226 0.0114675 -0.362337 0.0204406 0.0116848 -0.362505 0.0213721 0.0098031 -0.363234 0.0211247 0.00965187 -0.36304 0.0219503 0.00770548 -0.363686 0.0216826 0.00762792 -0.363476 0.0190315 0.0129837 -0.361404 0.0201414 0.0112771 -0.362058 0.0210115 0.00951939 -0.362738 0.0218717 0.00549712 -0.363624 0.0160568 0.0145351 -0.358864 0.0176004 0.0138495 -0.360071 0.0189851 0.012745 -0.361154 0.017718 0.0136815 -0.359789 0.0190749 0.0125992 -0.36085 0.020208 0.0111609 -0.361736 0.0215516 0.00755997 -0.363161 0.0217347 0.00549712 -0.363304 0.0218717 -2.88296e-06 -0.363624 0.0221463 0.00549712 -0.363839 0.0224904 0.00549712 -0.363895 -0.0232302 0.0104732 -0.330599 0.0189074 0.0181548 -0.365983 0.0162792 0.0184311 -0.368093 -0.0187459 0.0202623 -0.34453 -0.019329 0.0202623 -0.347133 -0.0170125 0.0204971 -0.34983 -0.0195524 0.0202623 -0.34979 -0.0168902 0.0204971 -0.352147 -0.0194118 0.0202623 -0.352453 -0.0164535 0.0204971 -0.354425 -0.0180559 0.0202623 -0.357599 -0.0157106 0.0204971 -0.356624 -0.0146753 0.0204971 -0.3587 -0.0133669 0.0204971 -0.360616 -0.0135722 0.0202623 -0.364166 -0.0100329 0.0204971 -0.363828 -0.0115298 0.0202623 -0.365881 -0.00806944 0.0204971 -0.365065 -0.00595591 0.0204971 -0.366022 -0.00428712 0.0202623 -0.369161 -0.00143827 0.0204971 -0.367034 0.00101561 0.0202623 -0.369607 0.00366303 0.0202623 -0.369285 0.00542862 0.0204971 -0.366199 0.00624194 0.0202623 -0.368605 0.00870431 0.0202623 -0.367581 0.0130041 0.0204971 -0.361026 -0.0149786 0.0202623 -0.337528 -0.0165502 0.0202623 -0.339683 -0.0178138 0.0202623 -0.342031 -0.0210984 0.0195658 -0.343831 -0.0217547 0.0195658 -0.346761 -0.0220061 0.0195658 -0.349752 -0.0218478 0.0195658 -0.35275 -0.0212829 0.0195658 -0.355698 -0.0189098 0.0202623 -0.355073 -0.0168659 0.0202623 -0.359986 -0.015362 0.0202623 -0.362188 -0.00927299 0.0202623 -0.367301 -0.00684366 0.0202623 -0.368402 -0.00482371 0.0195658 -0.371556 -0.001651 0.0202623 -0.369565 -0.00185651 0.0195658 -0.372011 0.0070277 0.0195658 -0.37093 0.00979931 0.0195658 -0.369777 0.0110043 0.0202623 -0.366231 0.0130989 0.0202623 -0.36458 0.0147459 0.0195658 -0.3664 -0.0168579 0.0195658 -0.33595 -0.0186269 0.0195658 -0.338375 -0.0205603 0.0184311 -0.337158 -0.0200492 0.0195658 -0.341019 -0.0221304 0.0184311 -0.340076 -0.0232885 0.0184311 -0.343181 -0.0240131 0.0184311 -0.346414 -0.0241159 0.0184311 -0.353026 -0.0234922 0.0184311 -0.35628 -0.0203217 0.0195658 -0.358542 -0.0224312 0.0184311 -0.359419 -0.0189822 0.0195658 -0.361228 -0.0209526 0.0184311 -0.362385 -0.0172895 0.0195658 -0.363707 -0.0152749 0.0195658 -0.365933 -0.012976 0.0195658 -0.367863 -0.0104357 0.0195658 -0.369463 -0.00770132 0.0195658 -0.370701 -0.00849981 0.0184311 -0.372842 -0.00532327 0.0184311 -0.373785 0.001145 0.0195658 -0.372058 0.00126546 0.0184311 -0.374339 0.0041249 0.0195658 -0.371695 0.00455492 0.0184311 -0.373939 0.0123881 0.0195658 -0.368258 0.0108188 0.0184311 -0.371822 0.0168287 0.0195658 -0.364238 -0.022285 0.0168969 -0.336072 -0.0239869 0.0168969 -0.339235 -0.0252422 0.0168969 -0.342601 -0.0242906 0.0184311 -0.349717 -0.019084 0.0184311 -0.365121 -0.0168601 0.0184311 -0.367578 -0.0182742 0.0168969 -0.369046 -0.0143225 0.0184311 -0.369709 -0.0155235 0.0168969 -0.371356 -0.0115183 0.0184311 -0.371475 -0.0124839 0.0168969 -0.373269 -0.00921207 0.0168969 -0.374751 -0.00204785 0.0184311 -0.374288 0.00137291 0.0168969 -0.376374 0.00775925 0.0184311 -0.373095 0.0084118 0.0168969 -0.375025 0.0117281 0.0168969 -0.373646 0.0136765 0.0184311 -0.370144 0.0176469 0.0168969 -0.369604 0.0201391 0.0168969 -0.367018 -0.0201683 0.0168969 -0.33317 -0.0255556 0.015015 -0.338525 -0.0268931 0.015015 -0.34211 -0.0260276 0.0168969 -0.346106 -0.0263284 0.0168969 -0.349685 -0.0280504 0.015015 -0.349658 -0.026139 0.0168969 -0.353272 -0.025463 0.0168969 -0.356799 -0.0271283 0.015015 -0.357238 -0.0243129 0.0168969 -0.360202 -0.0227102 0.0168969 -0.363417 -0.0206847 0.0168969 -0.366383 -0.0241954 0.015015 -0.364288 -0.0220374 0.015015 -0.367449 -0.0165384 0.015015 -0.372747 -0.00981397 0.015015 -0.376365 -0.00614546 0.015015 -0.377455 -0.00576889 0.0168969 -0.375774 -0.00221852 0.0168969 -0.376318 0.00493849 0.0168969 -0.375941 0.0124966 0.015015 -0.375187 0.0148258 0.0168969 -0.371827 0.0188027 0.015015 -0.370881 0.0214579 0.015015 -0.368125 -0.0225195 0.0128493 -0.331196 -0.0248831 0.0128493 -0.334436 -0.0237424 0.015015 -0.335155 -0.0277299 0.015015 -0.345845 -0.0290623 0.0128493 -0.34564 -0.0278486 0.015015 -0.35348 -0.025903 0.015015 -0.360864 -0.0271476 0.0128493 -0.361381 -0.0194691 0.015015 -0.370286 -0.0230961 0.0128493 -0.368283 -0.0132999 0.015015 -0.374786 -0.0139386 0.0128493 -0.375973 -0.0102851 0.0128493 -0.377628 -0.00236275 0.015015 -0.378035 -0.00644021 0.0128493 -0.37877 0.00146371 0.015015 -0.378094 0.00526262 0.015015 -0.377632 0.00153478 0.0128493 -0.37944 0.00896323 0.015015 -0.376657 0.00939485 0.0128493 -0.377934 0.0165571 0.0128493 -0.374363 0.0157969 0.015015 -0.37325 0.0197074 0.0128493 -0.37188 0.0224902 0.0128493 -0.368992 -0.0256685 0.0104732 -0.333942 -0.0267835 0.0128493 -0.337968 -0.0281853 0.0128493 -0.341726 -0.0293982 0.0128493 -0.349637 -0.0299797 0.0104732 -0.3455 -0.0291867 0.0128493 -0.353642 -0.0284318 0.0128493 -0.357582 -0.0253579 0.0128493 -0.364971 -0.0204044 0.0128493 -0.371257 -0.0173328 0.0128493 -0.373836 -0.0210483 0.0104732 -0.371925 -0.0178798 0.0104732 -0.374586 -0.0143784 0.0104732 -0.37679 -0.00247564 0.0128493 -0.379378 -0.00255336 0.0104732 -0.380303 0.00551633 0.0128493 -0.378956 0.0135122 0.0104732 -0.377224 0.0130981 0.0128493 -0.376393 0.0170805 0.0104732 -0.375129 0.0203302 0.0104732 -0.372568 -0.0235953 0.00796715 -0.330292 -0.027629 0.0104732 -0.337585 -0.029075 0.0104732 -0.341462 -0.0295321 0.00796715 -0.341326 -0.0303262 0.0104732 -0.349623 -0.030451 0.00796715 -0.345427 -0.0301081 0.0104732 -0.353754 -0.0308029 0.00796715 -0.349615 -0.0293293 0.0104732 -0.357818 -0.0305814 0.00796715 -0.353812 -0.0280045 0.0104732 -0.361738 -0.0261583 0.0104732 -0.365441 -0.0265695 0.00796715 -0.365682 -0.0238251 0.0104732 -0.368858 -0.0106095 0.0104732 -0.378498 -0.0107761 0.00796715 -0.378944 -0.00664315 0.0104732 -0.379676 0.00158371 0.0104732 -0.380367 0.00569101 0.0104732 -0.379867 0.00160885 0.00796715 -0.380843 0.00969203 0.0104732 -0.378813 0.00984469 0.00796715 -0.379265 0.0206502 0.00796715 -0.372922 0.023201 0.0104732 -0.369589 -0.026072 0.00796715 -0.333688 -0.0238293 0.00398654 -0.330096 -0.0280633 0.00796715 -0.337389 -0.0263306 0.00398654 -0.333525 -0.0283416 0.00398654 -0.337263 -0.029825 0.00398654 -0.341239 -0.0308847 0.00398654 -0.353849 -0.0297904 0.00796715 -0.35794 -0.0284447 0.00796715 -0.361921 -0.0241996 0.00796715 -0.369153 -0.0213792 0.00796715 -0.372268 -0.0181607 0.00796715 -0.374971 -0.0146043 0.00796715 -0.37721 -0.0108829 0.00398654 -0.379231 -0.0067474 0.00796715 -0.380141 -0.00681421 0.00398654 -0.380439 -0.00259329 0.00796715 -0.380778 -0.00261888 0.00398654 -0.381082 0.00578075 0.00796715 -0.380336 0.0138613 0.00398654 -0.377924 0.013725 0.00796715 -0.377651 0.0173493 0.00796715 -0.375523 0.0208553 0.00398654 -0.373148 -0.0284804 -2.88296e-06 -0.3372 -0.030753 0.00398654 -0.345381 -0.0311085 0.00398654 -0.34961 -0.0300859 0.00398654 -0.358017 -0.0287269 0.00398654 -0.362038 -0.0302332 -2.88296e-06 -0.358056 -0.0269644 -2.88296e-06 -0.365914 -0.026833 0.00398654 -0.365837 -0.0244396 0.00398654 -0.369342 -0.0215912 0.00398654 -0.372488 -0.0183408 0.00398654 -0.375218 -0.0147491 0.00398654 -0.377479 -0.0148213 -2.88296e-06 -0.377614 -0.0109361 -2.88296e-06 -0.379373 0.00162496 0.00398654 -0.381148 0.00583826 0.00398654 -0.380636 0.00586694 -2.88296e-06 -0.380785 0.00994253 0.00398654 -0.379554 0.00999132 -2.88296e-06 -0.379699 0.0139293 -2.88296e-06 -0.378061 0.0175216 0.00398654 -0.375776 0.0176076 -2.88296e-06 -0.375901 0.0239168 -2.88296e-06 -0.37019 -0.0264595 -2.88296e-06 -0.333444 -0.0263306 -0.0039923 -0.333525 -0.0299711 -2.88296e-06 -0.341196 -0.0283416 -0.0039923 -0.337263 -0.029825 -0.0039923 -0.341239 -0.030753 -0.0039923 -0.345381 -0.0309036 -2.88296e-06 -0.345358 -0.0312608 -2.88296e-06 -0.349608 -0.0311085 -0.0039923 -0.34961 -0.031036 -2.88296e-06 -0.353867 -0.0300859 -0.0039923 -0.358017 -0.0287269 -0.0039923 -0.362038 -0.0288676 -2.88296e-06 -0.362097 -0.0244396 -0.0039923 -0.369342 -0.0245593 -2.88296e-06 -0.369436 -0.0216969 -2.88296e-06 -0.372598 -0.0215912 -0.0039923 -0.372488 -0.0184306 -2.88296e-06 -0.375341 -0.0183408 -0.0039923 -0.375218 -0.0147491 -0.0039923 -0.377479 -0.0108829 -0.0039923 -0.379231 -0.00684753 -2.88296e-06 -0.380588 -0.00263164 -2.88296e-06 -0.381234 0.00163299 -2.88296e-06 -0.381301 0.00162496 -0.0039923 -0.381148 0.0175216 -0.0039923 -0.375776 0.0209575 -2.88296e-06 -0.373261 0.0238001 -0.0039923 -0.370092 -0.026072 -0.00797292 -0.333688 -0.0280633 -0.00797292 -0.337389 -0.030451 -0.00797292 -0.345427 -0.0308847 -0.0039923 -0.353849 -0.0305814 -0.00797292 -0.353812 -0.0284447 -0.00797292 -0.361921 -0.026833 -0.0039923 -0.365837 -0.0213792 -0.00797292 -0.372268 -0.0146043 -0.00797292 -0.37721 -0.0107761 -0.00797292 -0.378944 -0.00681421 -0.0039923 -0.380439 -0.0067474 -0.00797292 -0.380141 -0.00261888 -0.0039923 -0.381082 0.00160885 -0.00797292 -0.380843 0.00583826 -0.0039923 -0.380636 0.00994253 -0.0039923 -0.379554 0.0138613 -0.0039923 -0.377924 0.0173493 -0.00797292 -0.375523 0.0208553 -0.0039923 -0.373148 0.0206502 -0.00797292 -0.372922 0.0168287 -0.0195715 -0.364238 0.0147459 -0.0195715 -0.3664 0.0189074 -0.0181605 -0.365983 -0.0225195 -0.0128551 -0.331196 0.0203302 -0.0104789 -0.372568 -0.0235953 -0.00797292 -0.330292 -0.0295321 -0.00797292 -0.341326 -0.0299797 -0.0104789 -0.3455 -0.0308029 -0.00797292 -0.349615 -0.0297904 -0.00797292 -0.35794 -0.0301081 -0.0104789 -0.353754 -0.0293293 -0.0104789 -0.357818 -0.0265695 -0.00797292 -0.365682 -0.0241996 -0.00797292 -0.369153 -0.0238251 -0.0104789 -0.368858 -0.0210483 -0.0104789 -0.371925 -0.0181607 -0.00797292 -0.374971 -0.0106095 -0.0104789 -0.378498 -0.00664315 -0.0104789 -0.379676 -0.00259329 -0.00797292 -0.380778 0.00158371 -0.0104789 -0.380367 0.00578075 -0.00797292 -0.380336 0.00984469 -0.00797292 -0.379265 0.013725 -0.00797292 -0.377651 0.00969203 -0.0104789 -0.378813 0.0170805 -0.0104789 -0.375129 0.023201 -0.0104789 -0.369589 -0.0256685 -0.0104789 -0.333942 -0.0228439 -0.0119255 -0.330923 -0.027629 -0.0104789 -0.337585 -0.029075 -0.0104789 -0.341462 -0.0293982 -0.0128551 -0.349637 -0.0303262 -0.0104789 -0.349623 -0.0280045 -0.0104789 -0.361738 -0.0261583 -0.0104789 -0.365441 -0.0253579 -0.0128551 -0.364971 -0.0178798 -0.0104789 -0.374586 -0.0173328 -0.0128551 -0.373836 -0.0143784 -0.0104789 -0.37679 -0.0139386 -0.0128551 -0.375973 -0.00644021 -0.0128551 -0.37877 -0.00255336 -0.0104789 -0.380303 0.00569101 -0.0104789 -0.379867 0.00551633 -0.0128551 -0.378956 0.0135122 -0.0104789 -0.377224 0.00939485 -0.0128551 -0.377934 0.0165571 -0.0128551 -0.374363 -0.0248831 -0.0128551 -0.334436 -0.0237424 -0.0150208 -0.335155 -0.0267835 -0.0128551 -0.337968 -0.0281853 -0.0128551 -0.341726 -0.0268931 -0.0150208 -0.34211 -0.0290623 -0.0128551 -0.34564 -0.0277299 -0.0150208 -0.345845 -0.0291867 -0.0128551 -0.353642 -0.0278486 -0.0150208 -0.35348 -0.0284318 -0.0128551 -0.357582 -0.0271283 -0.0150208 -0.357238 -0.0271476 -0.0128551 -0.361381 -0.0241954 -0.0150208 -0.364288 -0.0220374 -0.0150208 -0.367449 -0.0230961 -0.0128551 -0.368283 -0.0204044 -0.0128551 -0.371257 -0.0132999 -0.0150208 -0.374786 -0.00981397 -0.0150208 -0.376365 -0.0102851 -0.0128551 -0.377628 -0.00614546 -0.0150208 -0.377455 -0.00247564 -0.0128551 -0.379378 0.00153478 -0.0128551 -0.37944 0.00146371 -0.0150208 -0.378094 0.00526262 -0.0150208 -0.377632 0.00896323 -0.0150208 -0.376657 0.0130981 -0.0128551 -0.376393 0.0124966 -0.0150208 -0.375187 0.0197074 -0.0128551 -0.37188 0.0188027 -0.0150208 -0.370881 -0.021245 -0.0154221 -0.332266 -0.022285 -0.0169027 -0.336072 -0.0255556 -0.0150208 -0.338525 -0.0239869 -0.0169027 -0.339235 -0.0263284 -0.0169027 -0.349685 -0.0280504 -0.0150208 -0.349658 -0.025903 -0.0150208 -0.360864 -0.0182742 -0.0169027 -0.369046 -0.0194691 -0.0150208 -0.370286 -0.0165384 -0.0150208 -0.372747 -0.0155235 -0.0169027 -0.371356 -0.00921207 -0.0169027 -0.374751 -0.00576889 -0.0169027 -0.375774 -0.00221852 -0.0169027 -0.376318 -0.00236275 -0.0150208 -0.378035 0.0084118 -0.0169027 -0.375025 0.0117281 -0.0169027 -0.373646 0.0148258 -0.0169027 -0.371827 0.0157969 -0.0150208 -0.37325 0.0201391 -0.0169027 -0.367018 -0.0189366 -0.0181605 -0.334205 -0.0205603 -0.0184369 -0.337158 -0.0232885 -0.0184369 -0.343181 -0.0252422 -0.0169027 -0.342601 -0.0260276 -0.0169027 -0.346106 -0.026139 -0.0169027 -0.353272 -0.025463 -0.0169027 -0.356799 -0.0243129 -0.0169027 -0.360202 -0.0209526 -0.0184369 -0.362385 -0.0227102 -0.0169027 -0.363417 -0.0206847 -0.0169027 -0.366383 -0.019084 -0.0184369 -0.365121 -0.0124839 -0.0169027 -0.373269 -0.00849981 -0.0184369 -0.372842 -0.00532327 -0.0184369 -0.373785 0.00137291 -0.0169027 -0.376374 0.00126546 -0.0184369 -0.374339 0.00455492 -0.0184369 -0.373939 0.00493849 -0.0169027 -0.375941 0.00775925 -0.0184369 -0.373095 0.0176469 -0.0169027 -0.369604 -0.0168579 -0.0195715 -0.33595 -0.0186269 -0.0195715 -0.338375 -0.0221304 -0.0184369 -0.340076 -0.0200492 -0.0195715 -0.341019 -0.0240131 -0.0184369 -0.346414 -0.0220061 -0.0195715 -0.349752 -0.0242906 -0.0184369 -0.349717 -0.0241159 -0.0184369 -0.353026 -0.0218478 -0.0195715 -0.35275 -0.0234922 -0.0184369 -0.35628 -0.0224312 -0.0184369 -0.359419 -0.0168601 -0.0184369 -0.367578 -0.0143225 -0.0184369 -0.369709 -0.012976 -0.0195715 -0.367863 -0.0115183 -0.0184369 -0.371475 -0.00770132 -0.0195715 -0.370701 -0.00482371 -0.0195715 -0.371556 -0.00204785 -0.0184369 -0.374288 0.0108188 -0.0184369 -0.371822 0.0136765 -0.0184369 -0.370144 0.0162792 -0.0184369 -0.368093 -0.0165502 -0.0202681 -0.339683 -0.0210984 -0.0195715 -0.343831 -0.0217547 -0.0195715 -0.346761 -0.0195524 -0.0202681 -0.34979 -0.0212829 -0.0195715 -0.355698 -0.0203217 -0.0195715 -0.358542 -0.0189822 -0.0195715 -0.361228 -0.0172895 -0.0195715 -0.363707 -0.0152749 -0.0195715 -0.365933 -0.0104357 -0.0195715 -0.369463 -0.00927299 -0.0202681 -0.367301 -0.00684366 -0.0202681 -0.368402 -0.00428712 -0.0202681 -0.369161 -0.00185651 -0.0195715 -0.372011 0.001145 -0.0195715 -0.372058 -0.001651 -0.0202681 -0.369565 0.0041249 -0.0195715 -0.371695 0.0070277 -0.0195715 -0.37093 0.00979931 -0.0195715 -0.369777 0.0123881 -0.0195715 -0.368258 0.0110043 -0.0202681 -0.366231 0.0130989 -0.0202681 -0.36458 0.016089 -0.0199044 -0.363617 -0.0149786 -0.0202681 -0.337528 -0.0178138 -0.0202681 -0.342031 -0.0163109 -0.0205029 -0.345253 -0.0187459 -0.0202681 -0.34453 -0.019329 -0.0202681 -0.347133 -0.0170125 -0.0205029 -0.34983 -0.0194118 -0.0202681 -0.352453 -0.0164535 -0.0205029 -0.354425 -0.0189098 -0.0202681 -0.355073 -0.0157106 -0.0205029 -0.356624 -0.0180559 -0.0202681 -0.357599 -0.0168659 -0.0202681 -0.359986 -0.0133669 -0.0205029 -0.360616 -0.015362 -0.0202681 -0.362188 -0.0135722 -0.0202681 -0.364166 -0.0118098 -0.0205029 -0.362336 -0.0115298 -0.0202681 -0.365881 -0.00806944 -0.0205029 -0.365065 -0.00595591 -0.0205029 -0.366022 -0.00373171 -0.0205029 -0.366683 0.00088169 -0.0205029 -0.36707 0.00101561 -0.0202681 -0.369607 0.00366303 -0.0202681 -0.369285 0.00318496 -0.0205029 -0.36679 0.00624194 -0.0202681 -0.368605 0.00542862 -0.0205029 -0.366199 0.00870431 -0.0202681 -0.367581 0.00757089 -0.0205029 -0.365308 0.00957185 -0.0205029 -0.364133 0.0113942 -0.0205029 -0.362697 0.0235661 -0.00797292 -0.369895 0.0271309 -0.00797292 -0.36565 0.0273727 -0.00396835 -0.36584 0.0238001 0.00398654 -0.370092 0.0235661 0.00796715 -0.369895 0.0271309 0.00796715 -0.36565 0.016089 0.0198986 -0.363617 0.0149493 0.0202623 -0.36266 0.0162814 0.0204971 -0.357123 0.0185783 0.0184311 -0.365707 0.0247165 0.0154163 -0.363753 0.0212158 0.0154163 -0.367922 0.0247596 0.015349 -0.363787 0.026359 0.0119197 -0.365044 0.0228147 0.0119197 -0.369265 -0.0130333 0.0204971 -0.339162 -0.0144006 0.0204971 -0.341036 -0.00373171 0.0204971 -0.366683 0.00088169 0.0204971 -0.36707 0.00318496 0.0204971 -0.36679 -0.0155 0.0204971 -0.34308 -0.0163109 0.0204971 -0.345253 -0.0168182 0.0204971 -0.347518 -0.0118098 0.0204971 -0.362336 0.00757089 0.0204971 -0.365308 0.00957185 0.0204971 -0.364133 0.0113942 0.0204971 -0.362697 -0.0228439 0.0119197 -0.330923 -0.0205884 0.0119462 -0.328254 -0.0214871 0.015015 -0.332063 -0.021245 0.0154163 -0.332266 -0.0165834 0.0181548 -0.331402 -0.0165271 0.0182024 -0.331446 -0.0136018 0.0199315 -0.333746 -0.0161182 0.0198986 -0.336571 -0.0186075 0.0184311 -0.334481 -0.0189366 0.0181548 -0.334205 -0.0217298 -2.88296e-06 -0.327359 -0.0216108 0.00396262 -0.327452 -0.0213689 -0.00797292 -0.327641 -0.0216108 -0.00396839 -0.327452 -0.0238293 -0.0039923 -0.330096 -0.023946 -2.88296e-06 -0.329998 -0.0161182 -0.0199044 -0.336571 -0.0186075 -0.0184369 -0.334481 -0.0166211 -0.0181283 -0.331373 -0.0201683 -0.0169027 -0.33317 -0.0189546 -0.0154221 -0.329539 -0.0189976 -0.0153548 -0.329505 -0.0206313 -0.0118186 -0.328221 -0.0232302 -0.0104789 -0.330599 -0.020597 -0.0119255 -0.328248 -0.0214871 -0.0150208 -0.332063 0.0130041 -0.0205029 -0.361026 -0.0130333 -0.0205029 -0.339162 -0.00143827 -0.0205029 -0.367034 -0.0144006 -0.0205029 -0.341036 -0.0100329 -0.0205029 -0.363828 -0.0146753 -0.0205029 -0.3587 -0.0168902 -0.0205029 -0.352147 -0.0168182 -0.0205029 -0.347518 -0.0155 -0.0205029 -0.34308 0.0228147 -0.0119255 -0.369265 0.0224902 -0.0128551 -0.368992 0.0263504 -0.011952 -0.365037 0.0214579 -0.0150208 -0.368125 0.0246879 -0.0154663 -0.36373 0.0212158 -0.0154221 -0.367922 0.022289 -0.0182082 -0.361845 0.0185783 -0.0184369 -0.365707 0.0149493 -0.0202681 -0.36266 0.0193638 -0.0199373 -0.359546 0.0274917 -2.88296e-06 -0.365933 0.0277256 -2.88296e-06 -0.365314 0.0276771 -2.88296e-06 -0.364981 0.0273669 -2.88296e-06 -0.364522 0.0275632 -0.00396459 -0.365489 0.0273214 -0.00796662 -0.3653 0.0276018 -0.00395234 -0.365093 0.0274825 -0.00393355 -0.364713 0.0272419 -0.00791465 -0.364525 0.0272241 0.00390545 -0.36441 0.0275214 -2.88296e-06 -0.364684 0.0277204 -2.88296e-06 -0.365185 0.0276614 -2.88296e-06 -0.365643 0.0273727 0.00396258 -0.36584 0.0275632 0.00395882 -0.365489 0.0273605 0.00794034 -0.364904 0.0276018 0.00394657 -0.365093 0.0274825 0.00392779 -0.364713 0.0272419 0.00790888 -0.364525 0.0265864 0.0117879 -0.364723 0.0263933 0.0118128 -0.365071 0.0273214 0.00796085 -0.3653 0.0249586 0.0153062 -0.363446 0.0223454 0.0181548 -0.361889 0.0223831 0.0181225 -0.361919 0.0196928 0.0198202 -0.359314 0.0225914 0.0180642 -0.361588 0.0227004 0.0178856 -0.361253 0.0250325 0.0151711 -0.36308 0.0265351 0.0115853 -0.363972 0.0262988 0.0114396 -0.363686 0.0247798 0.0147206 -0.362499 0.022693 0.0176148 -0.360966 0.0198638 0.018934 -0.358655 0.0168505 0.0198798 -0.356396 0.0199051 0.0193022 -0.358785 0.0249696 0.0149651 -0.362747 0.0266363 0.0117078 -0.364337 0.019472 0.0198902 -0.359631 0.016717 0.0202042 -0.356566 0.019845 0.0196136 -0.359017 0.0168149 0.0199971 -0.356441 0.0165894 0.0203631 -0.356729 -0.0102115 0.0203631 -0.335774 0.0165172 0.020421 -0.356822 -0.0105195 0.0204971 -0.336168 -0.018926 0.0154606 -0.329561 -0.0129615 0.0194492 -0.333157 -0.00998605 0.0199971 -0.335486 -0.00990352 0.0194971 -0.33538 -0.0136883 0.0198986 -0.333678 -0.0132658 0.0197999 -0.333379 -0.0161632 0.0180853 -0.331107 -0.0185383 0.0153697 -0.329244 -0.0157842 0.0177806 -0.330948 -0.015489 0.017368 -0.331013 -0.0189546 0.0154163 -0.329539 -0.0180981 0.0151375 -0.329138 -0.0177194 0.0148241 -0.329269 -0.0213689 0.00796715 -0.327641 -0.0209562 0.00795326 -0.327348 -0.0201839 0.0118909 -0.327954 -0.0197013 0.0117513 -0.327883 -0.0204538 0.00791838 -0.327294 -0.0213165 -2.88296e-06 -0.327066 -0.0208247 -2.88296e-06 -0.327012 -0.0203736 -2.88296e-06 -0.327195 -0.0211977 0.00395432 -0.327159 -0.0206945 0.00393349 -0.327106 -0.0206945 -0.00393926 -0.327106 -0.0211603 -2.88296e-06 -0.327021 -0.0214738 -2.88296e-06 -0.327142 -0.0209562 -0.00795902 -0.327348 -0.0211977 -0.00396008 -0.327159 -0.0204538 -0.00792415 -0.327294 -0.0202302 -0.00391125 -0.327306 -0.0202263 -0.0117646 -0.32792 -0.0181672 -0.0150358 -0.329083 -0.0165834 -0.0181605 -0.331402 -0.0186093 -0.015265 -0.329188 -0.0137101 -0.0198959 -0.333661 -0.0162564 -0.0180119 -0.331034 -0.0128699 -0.0189397 -0.333061 -0.0158749 -0.0177094 -0.330877 -0.0155765 -0.0172997 -0.330945 -0.017786 -0.0147264 -0.329217 -0.0197426 -0.0116285 -0.327851 -0.0102115 -0.0203689 -0.335774 -0.0133731 -0.0197646 -0.333295 -0.0100839 -0.02021 -0.335611 -0.013066 -0.019415 -0.333076 -0.00990352 -0.0195029 -0.33538 -0.00998605 -0.0200029 -0.335486 -0.0105195 -0.0205029 -0.336168 0.0247165 -0.0154221 -0.363753 0.0197632 -0.0189781 -0.358576 0.0168505 -0.0198856 -0.356396 0.0162814 -0.0205029 -0.357123 0.0224977 -0.0181493 -0.361515 0.0194503 -0.0199044 -0.359614 0.019585 -0.019867 -0.359229 0.0197388 -0.0196597 -0.358933 0.0165172 -0.0204268 -0.356822 0.0223454 -0.0181605 -0.361889 0.0226081 -0.0179695 -0.361181 0.0198014 -0.0193474 -0.358704 0.016717 -0.02021 -0.356566 0.0224829 -0.0173738 -0.360703 0.0247132 -0.0148298 -0.362447 0.0226029 -0.0176969 -0.360896 0.0249622 -0.0152861 -0.363025 0.024901 -0.0150774 -0.362693 0.0265942 -0.0118443 -0.364304 0.0248873 -0.0154229 -0.36339 0.0273605 -0.0079461 -0.364904 0.0265437 -0.0119264 -0.36469 0.026494 -0.0117185 -0.36394 -0.00923137 -0.0175029 -0.335906 0.0168974 -0.0195029 -0.356336 -0.0193049 -0.0114453 -0.32803 -0.0159159 -0.0139882 -0.330679 -0.0135231 -0.016195 -0.33255 0.0269845 0.00787148 -0.364222 0.0253147 0.00737433 -0.362917 0.0249684 0.00920532 -0.362646 -0.0199906 -0.00787724 -0.327493 -0.0203479 -2.88296e-06 -0.327214 -0.0202302 0.00390549 -0.327306 -0.0199906 0.00787148 -0.327493 -0.0184477 0.00816737 -0.3287 -0.0177486 0.0107037 -0.329246 -0.019265 0.0115633 -0.328061 -0.0166223 0.012979 -0.330127 -0.0151255 0.0148791 -0.331297 0.0262589 -0.0115691 -0.363655 0.0233686 -0.0129848 -0.361395 0.0269845 -0.00787724 -0.364222 0.0244949 -0.0107095 -0.362276 0.025194 -0.00817313 -0.362823 0.0272241 -0.00391122 -0.36441 0.0273417 -2.88296e-06 -0.364502 0.0236256 0.0125505 -0.361596 0.0225703 0.0172939 -0.360771 0.0202694 0.0161892 -0.358972 0.0168974 0.0194971 -0.356336 -0.0127693 0.0189723 -0.33314 -0.0113349 0.0171963 -0.334261 0.0157875 -0.0170409 -0.35586 0.0178101 -0.0167517 -0.357441 0.0197313 -0.0158983 -0.358943 0.0184692 -0.01644 -0.358199 0.0214547 -0.0145237 -0.360291 0.0227527 -0.012673 -0.361548 0.022894 -0.0126967 -0.361416 0.0239769 -0.0105091 -0.362263 0.024877 -0.00550288 -0.362967 0.0246491 -0.00807034 -0.362788 0.0242858 -0.00905658 -0.362747 0.022999 -0.0122624 -0.361741 0.0241537 -0.0105561 -0.362195 0.0230607 -0.0127643 -0.36134 0.0198683 -0.015996 -0.358844 0.0179291 -0.0168573 -0.357328 0.0158237 -0.0170699 -0.355813 0.0158875 -0.0171493 -0.355732 0.0248323 -0.00809446 -0.362726 0.0216079 -0.0146084 -0.360205 0.0217543 -0.0147353 -0.360181 0.0180242 -0.0170155 -0.357265 0.0159364 -0.0172529 -0.355669 0.0250236 -0.00813056 -0.362738 0.025431 -0.00550288 -0.363008 0.0243356 -0.0106265 -0.3622 0.0232273 -0.0128655 -0.361333 0.0199905 -0.0161421 -0.358802 0.0218717 -0.0148849 -0.360225 0.0200793 -0.0163145 -0.358823 0.0180812 -0.017202 -0.357261 0.0249359 0.00549712 -0.362938 0.0250623 -0.00550288 -0.362905 0.0251928 0.00549712 -0.362907 0.0252569 -0.00550288 -0.36292 0.025431 0.00549712 -0.363008 0.0248237 0.00730659 -0.36285 0.0173844 0.0171025 -0.356801 0.0159364 0.0172471 -0.355669 0.0174565 0.0173494 -0.356773 0.0188989 0.0169098 -0.357901 0.0215342 0.0152053 -0.359961 0.0224817 0.0138056 -0.360787 0.023425 0.0124036 -0.361524 0.0226622 0.0139824 -0.360843 0.0244007 0.010945 -0.362202 0.0247398 0.00912807 -0.362552 0.0250789 0.00733522 -0.362818 0.0250623 0.00549712 -0.362905 0.0239428 0.0107484 -0.362162 0.0241839 0.0108315 -0.362118 0.0231956 0.012296 -0.361577 0.022267 0.0136762 -0.360851 0.0213772 0.0150031 -0.359923 0.0201387 0.0159664 -0.358955 0.0187968 0.016672 -0.357906 0.0172491 0.0169217 -0.356928 0.0156697 0.0169971 -0.35601 0.0184692 0.0164343 -0.358199 0.0186395 0.016498 -0.358015 0.0199606 0.0158034 -0.359048 0.0211797 0.014855 -0.360001 0.0220757 0.0136288 -0.361019 0.022999 0.0122566 -0.361741 0.02449 0.00907151 -0.362589 0.0246176 0.00729611 -0.363007 0.0158237 0.0170641 -0.355813 0.0158875 0.0171436 -0.355732 -0.00932158 0.0171436 -0.336021 -0.00925482 0.0173058 -0.335936 -0.00923137 0.0174971 -0.335906 0.0159777 0.0174971 -0.355616 -0.0185575 0.00549712 -0.328662 -0.0183242 0.00812479 -0.328845 -0.0177017 0.0104868 -0.329918 -0.00953935 0.0169971 -0.3363 -0.0114441 0.0167459 -0.334568 -0.0123389 0.0164343 -0.334111 -0.0133653 0.0158926 -0.333065 -0.0134701 0.0158583 -0.333226 -0.0166223 0.0126672 -0.330762 -0.0151879 0.0144882 -0.331883 -0.0176108 0.0105033 -0.329746 -0.0182831 0.00806458 -0.32922 -0.00942149 0.0170352 -0.336149 -0.0113632 0.0168516 -0.334425 -0.0133024 0.0159902 -0.332909 -0.015042 0.0146027 -0.331549 -0.0150887 0.0145179 -0.331718 -0.0164948 0.0127586 -0.330413 -0.0165279 0.012691 -0.330593 -0.0181554 0.00905081 -0.329563 -0.0184964 0.00549712 -0.328848 -0.0132911 0.0161364 -0.33278 -0.0150549 0.0147295 -0.331401 -0.0165279 0.0128597 -0.330249 -0.0175878 0.0105503 -0.329558 -0.0176362 0.0106207 -0.329383 -0.0182664 0.00808869 -0.329027 -0.0186848 0.00549712 -0.328514 -0.013333 0.0163087 -0.332699 -0.0113249 0.0170097 -0.334317 -0.0185988 0.00549712 -0.329216 -0.018511 0.00549712 -0.329042 -0.0184976 -0.00550288 -0.328978 -0.0184976 0.00549712 -0.328978 -0.0185291 0.00549712 -0.328721 -0.0185291 -0.00550288 -0.328721 -0.0107102 -0.0173551 -0.33475 -0.0121526 -0.0169156 -0.333622 -0.0147879 -0.0152111 -0.331561 -0.0167613 -0.0124094 -0.330103 -0.0168793 -0.0125563 -0.329926 -0.018076 -0.00913383 -0.329075 -0.0176544 -0.0109508 -0.32932 -0.0182221 -0.00921109 -0.328876 -0.0184151 -0.00734099 -0.32881 -0.0185684 -0.0073801 -0.328605 -0.0186848 -0.00550288 -0.328514 -0.00938536 -0.0170699 -0.336103 -0.00927263 -0.0172529 -0.335959 -0.0108108 -0.0169275 -0.334988 -0.0107207 -0.0171082 -0.334826 -0.012133 -0.0166778 -0.333722 -0.0135222 -0.0158091 -0.332868 -0.013475 -0.0159722 -0.332673 -0.0147134 -0.0150088 -0.331705 -0.0158179 -0.0138114 -0.330841 -0.0175202 -0.0108373 -0.32951 -0.0183854 -0.00731236 -0.329066 -0.0109566 -0.0168613 -0.335192 -0.0122012 -0.0165037 -0.333901 -0.0136523 -0.0157495 -0.333084 -0.0147414 -0.0148608 -0.331915 -0.0158287 -0.013682 -0.331065 -0.0167573 -0.0123018 -0.330339 -0.0176114 -0.0107238 -0.329988 -0.0175044 -0.0107542 -0.329755 -0.0180516 -0.00907728 -0.329327 0.0159542 -0.0173115 -0.355646 0.0159777 -0.0175029 -0.355616 0.0151769 -0.0170029 -0.356641 0.0176856 -0.0167146 -0.357587 0.0165941 -0.0168613 -0.357749 0.0179765 -0.01644 -0.358829 0.0196004 -0.015864 -0.359084 0.0209947 -0.0148066 -0.360174 0.0192898 -0.0157495 -0.359856 0.0213182 -0.0144939 -0.360427 0.0242364 -0.00550288 -0.363724 0.0247292 -0.00550288 -0.363094 0.024502 -0.00806187 -0.362916 0.0241249 -0.00730188 -0.363637 0.023793 -0.00905658 -0.363377 0.023832 -0.0104925 -0.362392 0.0242364 0.00549712 -0.363724 0.0247292 0.00549712 -0.363094 0.0242858 0.00905081 -0.362747 0.0240093 0.00805611 -0.363546 0.023793 0.00905081 -0.363377 0.0233392 0.0104868 -0.363023 0.0237418 0.010718 -0.362322 0.0209947 0.0148008 -0.360174 0.020502 0.0148008 -0.360804 0.0197826 0.0157437 -0.359226 0.0170869 0.0168555 -0.357118 0.0151769 0.0169971 -0.356641 -0.0164381 0.0136288 -0.331921 -0.0153572 0.0148008 -0.332766 -0.0148644 0.0148008 -0.332136 -0.0114493 0.0168555 -0.335822 -0.0100321 0.0169971 -0.33693 -0.0115553 0.0167088 -0.334724 -0.0189801 0.00729611 -0.329934 -0.0186482 0.00905081 -0.330193 -0.0183717 0.00805611 -0.329394 -0.0168686 0.0122566 -0.330569 -0.0185988 -0.00550288 -0.329216 -0.0184873 -0.00730188 -0.329304 -0.0190916 -0.00550288 -0.329847 -0.0181554 -0.00905658 -0.329563 -0.0173614 -0.0122624 -0.331199 -0.0168686 -0.0122624 -0.330569 -0.0159454 -0.0136346 -0.331291 -0.0153572 -0.0148066 -0.332766 -0.0148644 -0.0148066 -0.332136 -0.014145 -0.0157495 -0.333714 -0.0128317 -0.01644 -0.334741 -0.0123389 -0.01644 -0.334111 -0.0114493 -0.0168613 -0.335822 -0.00953935 -0.0170029 -0.3363 -0.0100321 -0.0170029 -0.33693 0.0156697 -0.0170029 -0.35601 0.0150229 -0.0169359 -0.356837 0.0164319 -0.0167951 -0.357939 0.0155488 -0.016469 -0.357566 0.0162245 -0.0163675 -0.358094 0.0168919 -0.016199 -0.358616 0.0175468 -0.0159645 -0.359128 0.0189337 -0.0155267 -0.360128 0.0220802 -0.0121155 -0.362588 0.0201195 -0.0146043 -0.361055 0.0204968 -0.0138673 -0.361435 0.0214583 -0.0126468 -0.362187 0.0232951 -0.00807078 -0.363623 0.023339 -0.00897932 -0.363572 0.0234279 -0.00722366 -0.363727 0.0236636 -0.00726277 -0.363826 0.0162966 -0.0166144 -0.358066 0.0176489 -0.0162023 -0.359123 0.0178062 -0.0163763 -0.359014 0.021177 -0.0134578 -0.361882 0.0213916 -0.0135872 -0.361817 0.0223095 -0.012223 -0.362535 0.023048 -0.0106934 -0.363112 0.0228068 -0.0106103 -0.363156 0.0239188 -0.0072914 -0.363793 0.0240297 -0.00550288 -0.36388 0.0191119 -0.0156898 -0.360035 0.020502 -0.0148066 -0.360804 0.0203169 -0.0147524 -0.360977 0.0215829 -0.0136346 -0.361649 0.0225062 -0.0122624 -0.362371 0.023249 -0.0107238 -0.362952 0.0235888 -0.00903588 -0.363535 0.0240886 0.00549712 -0.363851 0.0239033 -0.00550288 -0.363912 0.0237728 -0.00550288 -0.363911 0.0239033 0.00549712 -0.363912 0.0237087 0.00549712 -0.363898 0.0235345 -0.00550288 -0.36381 0.0189768 0.015824 -0.359855 0.0225062 0.0122566 -0.362371 0.0187177 0.0155802 -0.359995 0.0205357 0.0143737 -0.361279 0.0188399 0.0157263 -0.359953 0.0235345 0.00549712 -0.36381 0.023679 0.00802352 -0.363737 0.0238622 0.00804764 -0.363674 0.0234877 0.00798742 -0.363725 0.0230175 0.0104232 -0.36322 0.0231944 0.0104703 -0.363152 0.0221186 0.0126435 -0.362311 0.0228356 0.0103529 -0.363215 0.0226764 0.0102698 -0.363139 0.021644 0.0123555 -0.362332 0.0217853 0.0124748 -0.362394 0.0203893 0.0142469 -0.361302 0.0219519 0.0125759 -0.362387 0.0222599 0.0126672 -0.362179 0.0206889 0.0144584 -0.361193 0.0191077 0.0158583 -0.359714 0.0208254 0.0144882 -0.361057 0.0171928 0.0167088 -0.358217 0.0179765 0.0164343 -0.358829 0.0170683 0.0166717 -0.358362 0.0168542 0.0164079 -0.358538 0.0167972 0.0162213 -0.358542 0.0148689 0.0164971 -0.357034 0.0148924 0.0166885 -0.357004 0.0169494 0.016566 -0.358475 0.0150591 0.0169591 -0.356791 -0.0101861 0.0169301 -0.337127 0.0149591 0.0168507 -0.356919 -0.0102499 0.0168507 -0.337209 -0.0103401 0.0164971 -0.337324 -0.0102988 0.0167471 -0.337271 -0.0116852 0.0166086 -0.336187 -0.0130375 0.0161965 -0.33513 -0.0136563 0.0156598 -0.334731 -0.0142742 0.0152982 -0.334248 -0.0155081 0.0145986 -0.333198 -0.015968 0.0138616 -0.332924 -0.0165656 0.0134521 -0.332371 -0.0174688 0.0121097 -0.331665 -0.0177287 0.0112446 -0.331547 -0.0180612 0.010491 -0.331287 -0.0187276 0.00897356 -0.330681 -0.0191614 0.00549712 -0.330342 -0.0115951 0.0167894 -0.336025 -0.0129693 0.0163706 -0.334951 -0.0143223 0.0155209 -0.334125 -0.0181954 0.0106045 -0.331097 -0.0182112 0.0106876 -0.330852 -0.0190819 0.00728563 -0.330171 -0.0190523 0.007257 -0.330427 -0.0191928 0.00549712 -0.330085 -0.0128317 0.0164343 -0.334741 -0.0142751 0.015684 -0.33393 -0.0154801 0.0147466 -0.332988 -0.014145 0.0157437 -0.333714 -0.0165548 0.0135815 -0.332147 -0.0174727 0.0122173 -0.33143 -0.0173614 0.0122566 -0.331199 -0.0181042 0.010718 -0.330619 -0.018752 0.00903011 -0.330429 -0.0190916 0.00549712 -0.329847 -0.0191614 -0.00550288 -0.330342 -0.0190057 -0.00550288 -0.330548 -0.0191928 -0.00550288 -0.330085 -0.018979 -0.00636593 -0.330569 -0.018899 -0.00722366 -0.330632 -0.0190523 -0.00726277 -0.330427 -0.0187276 -0.00897932 -0.330681 -0.0185816 -0.00890207 -0.33088 -0.0181954 -0.0106103 -0.331097 -0.0180612 -0.0104968 -0.331287 -0.0177287 -0.0112504 -0.331547 -0.0169295 -0.0126468 -0.332172 -0.0174688 -0.0121155 -0.331665 -0.0164676 -0.0132811 -0.332533 -0.0154336 -0.0144021 -0.333341 -0.0142742 -0.015304 -0.334248 -0.0136563 -0.0156656 -0.334731 -0.0130375 -0.0162023 -0.33513 -0.0116852 -0.0166144 -0.336187 -0.0182112 -0.0106934 -0.330852 -0.0165656 -0.0134578 -0.332371 -0.0154801 -0.0147524 -0.332988 -0.0155081 -0.0146043 -0.333198 -0.0142751 -0.0156898 -0.33393 -0.0143223 -0.0155267 -0.334125 -0.0129693 -0.0163763 -0.334951 -0.0102988 -0.0167529 -0.337271 -0.0115951 -0.0167951 -0.336025 -0.0190819 -0.0072914 -0.330171 -0.0189801 -0.00730188 -0.329934 -0.018752 -0.00903588 -0.330429 -0.0186482 -0.00905658 -0.330193 -0.0181042 -0.0107238 -0.330619 -0.0174727 -0.012223 -0.33143 -0.0165548 -0.0135872 -0.332147 -0.0164381 -0.0136346 -0.331921 -0.0101861 -0.0169359 -0.337127 0.0149102 -0.0167529 -0.356982 -0.0103401 -0.0165029 -0.337324 -0.0190057 0.00549712 -0.330548 -0.018899 0.0072179 -0.330632 -0.0116957 -0.0163675 -0.336264 0.0209964 -0.0132811 -0.361825 -0.0189954 -0.00550288 -0.330556 -0.0189818 -0.00611893 -0.330567 -0.0171071 -0.0123531 -0.332033 -0.0173507 -0.0119685 -0.331842 -0.0179154 -0.0108175 -0.331401 -0.0183461 -0.0097124 -0.331064 -0.0187663 -0.00807078 -0.330736 0.0148689 -0.0164898 -0.357034 0.0148689 -0.0165029 -0.357034 0.0153542 -0.0164725 -0.357414 0.015838 -0.0164207 -0.357792 0.0167949 -0.0162144 -0.35854 -0.0108254 0.0164668 -0.336944 -0.01102 0.0164632 -0.336792 -0.0122661 -0.0162144 -0.335818 -0.012363 -0.016199 -0.335742 -0.0130179 -0.0159645 -0.33523 -0.0140955 -0.0154018 -0.334388 -0.014945 -0.0148058 -0.333723 -0.0148679 -0.0148819 -0.333784 -0.0157366 -0.0140928 -0.333104 -0.015968 -0.0138673 -0.332924 -0.0164603 -0.0132718 -0.332539 0.0222576 -0.0112504 -0.362812 0.0221976 -0.0113483 -0.362765 0.0225901 -0.0104968 -0.363071 0.0228749 -0.0097124 -0.363294 0.0231104 -0.00890207 -0.363478 0.0235243 -2.88296e-06 -0.363802 0.0233072 0.00794194 -0.363632 0.0233173 0.00794485 -0.36364 0.0202719 0.0140973 -0.361259 0.0186288 0.0154078 -0.359974 0.0186243 0.015396 -0.359971 0.0199625 -0.0144021 -0.361017 0.0202654 -0.0140928 -0.361254 0.0190557 -0.0151189 -0.360308 0.0193967 -0.0148819 -0.360575 0.018803 -0.015304 -0.36011 0.0186243 -0.0154018 -0.359971 0.0181851 -0.0156656 -0.359627 0.0216359 -0.0123531 -0.362325 0.0218796 -0.0119685 -0.362516 -0.0154336 0.0143963 -0.333341 -0.0148679 0.0148762 -0.333784 -0.0122661 0.0162086 -0.335818 -0.0130179 0.0159587 -0.33523 -0.012363 0.0161932 -0.335742 -0.0116957 0.0163617 -0.336264 -0.0187663 0.00806502 -0.330736 -0.0187784 0.00794194 -0.330726 -0.0185816 0.0088963 -0.33088 -0.0185097 0.00912587 -0.330936 -0.0183461 0.00970664 -0.331064 -0.0181383 0.0102642 -0.331227 -0.0173507 0.0119628 -0.331842 -0.0169295 0.012641 -0.332172 -0.0164676 0.0132753 -0.332533 0.0228187 -2.88296e-06 -0.363777 0.0228187 0.00549712 -0.363777 0.0230502 -2.88296e-06 -0.363684 0.0230502 0.00549712 -0.363684 0.0146131 0.0159132 -0.357362 0.0147464 0.0160378 -0.357191 0.0165942 0.0157735 -0.358636 0.0183493 0.0149939 -0.360008 0.022006 0.0100165 -0.363142 0.0226129 0.0078149 -0.363617 0.0148369 0.0162398 -0.357075 0.0167201 0.0159704 -0.358548 0.0201134 0.013896 -0.361201 0.0199237 0.0137381 -0.361239 0.0214534 0.012195 -0.362249 0.0212385 0.0120691 -0.362267 0.0222278 0.0100705 -0.363041 0.022842 0.00784264 -0.363521 0.0224617 0.0101582 -0.363037 0.0148689 0.016484 -0.357034 0.0185088 0.0151759 -0.359946 0.0167949 0.0162086 -0.35854 0.0202654 0.014087 -0.361254 0.0216359 0.0123474 -0.362325 0.0230876 0.00788758 -0.363526 0.0226671 0.0102642 -0.363132 0.0232998 0.00549712 -0.363692 0.0235243 0.00549712 -0.363802 0.0232998 -0.00550288 -0.363692 0.0232998 -2.88296e-06 -0.363692 0.0235243 -0.00550288 -0.363802 -0.0103721 0.0162398 -0.337365 -0.0103401 0.016484 -0.337324 0.022842 -0.0078484 -0.363521 0.0146131 -0.0159189 -0.357362 0.022006 -0.0100222 -0.363142 0.0222278 -0.0100763 -0.363041 0.0177276 -0.0158733 -0.35927 0.0148369 -0.0162455 -0.357075 0.0147464 -0.0160436 -0.357191 0.0167201 -0.0159762 -0.358548 0.0185088 -0.0151817 -0.359946 0.0194738 -0.0148058 -0.360635 0.0165942 -0.0157793 -0.358636 0.0201134 -0.0139018 -0.361201 0.0181733 -0.0148874 -0.360145 0.0183493 -0.0149997 -0.360008 0.0219279 -0.0118607 -0.362554 0.0214534 -0.0122008 -0.362249 0.0209892 -0.0132718 -0.36182 0.0199237 -0.0137439 -0.361239 0.0212385 -0.0120749 -0.362267 0.0224617 -0.0101639 -0.363037 0.0230385 -0.00913164 -0.363422 0.0226671 -0.0102699 -0.363132 0.0230502 -0.00550288 -0.363684 0.0230876 -0.00789334 -0.363526 0.0233072 -0.00794771 -0.363632 -0.0157366 0.014087 -0.333104 -0.017944 0.0100705 -0.331631 -0.0169548 0.0120691 -0.332405 -0.0104626 0.0160378 -0.337481 -0.0113092 0.016415 -0.336566 -0.014044 0.0151759 -0.334494 -0.0122553 0.0159704 -0.335892 -0.0131988 0.0158675 -0.335089 -0.0145268 0.0151131 -0.33405 -0.0140955 0.015396 -0.334388 -0.0123104 0.0157735 -0.336036 -0.014945 0.0148 -0.333723 -0.0156486 0.013896 -0.333239 -0.0140655 0.0149939 -0.334664 -0.0164603 0.0132661 -0.332539 -0.017399 0.0118549 -0.331805 -0.0171071 0.0123474 -0.332033 -0.0156399 0.0137381 -0.333433 -0.0169886 0.012195 -0.332192 -0.0176688 0.0113425 -0.331594 -0.0186228 0.00788758 -0.330914 -0.0179969 0.0101582 -0.331403 -0.0187664 0.00549712 -0.330988 -0.0185582 0.00784264 -0.331151 -0.0189954 0.00549712 -0.330556 -0.0104626 -0.0160436 -0.337481 -0.0103721 -0.0162455 -0.337365 -0.0103401 -0.0164898 -0.337324 -0.018835 0.00549712 -0.330748 -0.018835 -0.00550288 -0.330748 -0.0169886 -0.0122008 -0.332192 -0.0187664 -0.00550288 -0.330988 -0.0124219 -0.0156578 -0.336223 -0.0141562 -0.0148874 -0.334867 -0.0187784 -0.00794771 -0.330726 -0.018941 -0.00673303 -0.330599 -0.0186228 -0.00789334 -0.330914 -0.0179969 -0.0101639 -0.331403 -0.0176688 -0.0113483 -0.331594 -0.0181383 -0.0102699 -0.331227 -0.0185097 -0.00913164 -0.330936 -0.0185582 -0.0078484 -0.331151 -0.017944 -0.0100763 -0.331631 -0.0169548 -0.0120749 -0.332405 -0.0153487 -0.0144634 -0.333408 -0.0156486 -0.0139018 -0.333239 -0.0179889 -0.0100222 -0.331871 -0.0156399 -0.0137439 -0.333433 -0.0140655 -0.0149997 -0.334664 -0.014044 -0.0151817 -0.334494 -0.0131988 -0.0158733 -0.335089 -0.0123104 -0.0157793 -0.336036 -0.0122553 -0.0159762 -0.335892 0.0217358 -0.00550288 -0.36247 0.0218044 -2.88296e-06 -0.36271 0.0217693 -0.00550288 -0.362957 0.0205474 -0.0100321 -0.361474 0.0210526 -0.00930256 -0.361935 0.0162055 -0.0143591 -0.358607 0.0216274 -0.00749652 -0.362571 0.0218044 -0.00550288 -0.36271 0.0209112 -0.00919656 -0.361759 0.021199 -0.00831457 -0.361984 0.0215628 -0.00745158 -0.362334 0.0202307 -0.010963 -0.361293 0.0211054 -0.00939019 -0.362163 0.0215898 -0.00752425 -0.362817 0.0210606 -0.00944427 -0.362403 0.0202646 -0.0110889 -0.361506 0.0196111 -0.0115225 -0.360742 0.0191383 -0.0123497 -0.360439 0.0174354 -0.0133679 -0.359041 0.019147 -0.0125076 -0.360632 0.0178302 -0.013393 -0.359416 0.0190503 -0.0121587 -0.360304 0.016317 -0.0142376 -0.358419 0.0178088 -0.013575 -0.359586 0.0163721 -0.0140407 -0.358276 0.0215754 0.00549712 -0.362278 0.0217358 -2.88296e-06 -0.36247 0.0217693 -2.88296e-06 -0.362957 0.0217693 0.00549712 -0.362957 -0.0103721 -0.0142602 -0.337365 -0.0104626 -0.0144622 -0.337481 0.0148369 -0.0142602 -0.357075 0.0147464 -0.0144622 -0.357191 0.0210649 0.00875493 -0.361879 0.0201123 0.0108049 -0.361134 0.0211054 0.00938442 -0.362163 0.0215898 0.00751849 -0.362817 0.0218044 0.00549712 -0.36271 0.0163721 0.0140349 -0.358276 0.0156198 0.0139567 -0.357622 0.0170839 0.0135325 -0.358766 0.0162055 0.0143533 -0.358607 0.016317 0.0142318 -0.358419 0.0178302 0.0133872 -0.359416 0.0191383 0.0123439 -0.360439 0.0190503 0.0121529 -0.360304 0.019147 0.0125018 -0.360632 0.0178088 0.0135692 -0.359586 0.0202307 0.0109572 -0.361293 0.0202646 0.0110832 -0.361506 0.0210606 0.0094385 -0.362403 0.0216274 0.00749076 -0.362571 0.0210526 0.0092968 -0.361935 0.0217358 0.00549712 -0.36247 0.0215628 0.00744581 -0.362334 0.0215332 0.00645028 -0.362245 -0.0160186 -0.0100321 -0.332884 -0.0175206 -0.00550288 -0.331962 -0.0173437 -0.00749652 -0.3321 -0.0175727 -0.00752425 -0.332196 -0.0120332 -0.0142376 -0.336253 -0.0119073 -0.0140407 -0.336165 -0.0118324 -0.0138025 -0.336157 -0.013525 -0.013575 -0.335086 -0.0133654 -0.013393 -0.335024 -0.0145215 -0.0121587 -0.334055 -0.0148632 -0.0125076 -0.33404 -0.0146735 -0.0123497 -0.334002 -0.0157659 -0.010963 -0.333148 -0.017098 -0.00745158 -0.332106 -0.0165878 -0.00930256 -0.332505 -0.0168217 -0.00939019 -0.332509 -0.0159808 -0.0110889 -0.333166 -0.0103401 0.0140102 -0.337324 0.0148369 0.0142545 -0.357075 0.0147464 0.0144564 -0.357191 -0.017271 0.00549712 -0.331971 -0.0170465 -0.00550288 -0.33208 -0.017271 -0.00550288 -0.331971 -0.0175206 0.00549712 -0.331962 -0.0177521 0.00549712 -0.332056 -0.0150823 0.0115168 -0.333616 -0.0160186 0.0100263 -0.332884 -0.0163824 0.0091908 -0.3326 -0.0121883 0.0143533 -0.336406 -0.013525 0.0135692 -0.335086 -0.0173437 0.00749076 -0.3321 -0.016536 0.00875493 -0.332479 -0.0165878 0.0092968 -0.332505 -0.017098 0.00744581 -0.332106 -0.0168784 0.00739145 -0.332212 -0.0168217 0.00938442 -0.332509 -0.0155834 0.0108049 -0.333224 -0.0157659 0.0109572 -0.333148 -0.0159808 0.0110832 -0.333166 -0.0161909 0.0111609 -0.333277 -0.0148632 0.0125018 -0.33404 -0.0146735 0.0123439 -0.334002 -0.0133654 0.0133872 -0.335024 -0.0118324 0.0137967 -0.336157 -0.0119073 0.0140349 -0.336165 -0.0125551 0.0135325 -0.335592 -0.0103721 0.0142545 -0.337365 -0.0104626 0.0144564 -0.337481 -0.0120332 0.0142318 -0.336253 -0.011091 0.0139567 -0.336737 -0.0270655 0.0204971 -0.328206 -0.0270847 0.0208631 -0.328668 -0.0272928 0.0205064 -0.328501 -0.0272416 0.0199971 -0.327883 -0.0276845 0.0189971 -0.327512 -0.0281261 0.01829 -0.327523 0.0266994 0.0179971 -0.374485 0.027107 0.0186144 -0.373621 0.026869 0.0185024 -0.373971 0.0270122 0.0189971 -0.373442 0.0265694 0.0199971 -0.37307 -0.0271711 0.0209615 -0.328903 -0.0296845 0.0195611 -0.330775 -0.0309889 0.0209971 -0.335089 -0.0335653 0.0195611 -0.338786 -0.0337526 0.0209971 -0.343288 -0.0343405 0.0209971 -0.347584 -0.0353254 0.0195611 -0.347511 -0.0338818 0.0209971 -0.356224 -0.0348536 0.0195611 -0.3564 -0.0337845 0.0195611 -0.36073 -0.0312824 0.0209971 -0.364478 -0.0300644 0.0195611 -0.368816 -0.0237635 0.0209971 -0.375005 -0.0210299 0.0195611 -0.378588 -0.0132589 0.0195611 -0.382929 -0.0128894 0.0209971 -0.382013 -0.00902626 0.0195611 -0.384333 -0.00452138 0.0209971 -0.384215 0.00863491 0.0195611 -0.384426 0.0125224 0.0209971 -0.382147 0.0201208 0.0209971 -0.378007 0.0206985 0.0195611 -0.378808 0.0234699 0.0209971 -0.375254 0.02597 0.0205064 -0.373227 0.0256565 0.020921 -0.37311 0.0259997 0.0207042 -0.372974 0.0270771 0.01829 -0.373879 0.0246686 0.0179971 -0.376539 0.0241437 0.0195611 -0.375976 0.0169247 0.0195611 -0.381184 0.0128821 0.0195611 -0.383067 0.00882282 0.0179971 -0.385172 0.00425049 0.0195611 -0.385241 -0.000201587 0.0195611 -0.385499 -0.0046507 0.0195611 -0.385194 -0.0135466 0.0179971 -0.383642 -0.0172813 0.0195611 -0.381003 -0.0176564 0.0179971 -0.381675 -0.0214864 0.0179971 -0.379207 -0.024445 0.0195611 -0.37572 -0.028069 0.0179971 -0.372931 -0.0307172 0.0179971 -0.369223 -0.0274725 0.0195611 -0.372445 -0.0321796 0.0195611 -0.36489 -0.03537 0.0195611 -0.351971 -0.0347207 0.0195611 -0.343093 -0.0325699 0.0179971 -0.334323 -0.0318777 0.0195611 -0.334658 -0.0281809 0.0185024 -0.327744 -0.02976 0.00549719 -0.326421 -0.0296413 0.00529001 -0.326251 -0.0293846 0.0073798 -0.326183 -0.0294996 0.00770422 -0.32637 -0.0296873 0.007921 -0.326636 -0.0296432 0.00749721 -0.326521 -0.0300941 0.00499712 -0.326794 -0.029918 0.00799712 -0.326942 0.0284506 0.00770422 -0.375033 0.0281357 0.00499712 -0.375691 0.0279595 0.00799712 -0.375543 0.028327 0.00749721 -0.3752 0.0286885 0.00699712 -0.37485 0.028445 0.00549719 -0.375298 0.028718 0.00561443 -0.374974 0.0285923 0.00529001 -0.375151 0.0258113 0.00799712 -0.377721 0.0259683 0.00499712 -0.377889 0.0222662 0.00499712 -0.380936 0.0182102 0.00499712 -0.383493 0.00929884 0.00499712 -0.386985 0.00455728 0.00799712 -0.387635 0.00458506 0.00499712 -0.387863 -0.00498563 0.00499712 -0.387816 -0.00969054 0.00499712 -0.386891 -0.00963209 0.00799712 -0.386669 -0.0185671 0.00499712 -0.383313 -0.0261111 0.00799712 -0.377466 -0.0295247 0.00499712 -0.374111 -0.0323111 0.00499712 -0.370209 -0.032116 0.00799712 -0.370087 -0.0345845 0.00499712 -0.365987 -0.0360896 0.00799712 -0.361444 -0.0372307 0.00799712 -0.356817 -0.0374569 0.00499712 -0.356857 -0.0377807 0.00799712 -0.352082 -0.0373074 0.00499712 -0.34255 -0.0358446 0.00799712 -0.337993 -0.0340381 0.00799712 -0.333582 -0.0291667 0.0117903 -0.326649 -0.0290471 0.0119971 -0.326542 -0.0292759 0.0119973 -0.326827 -0.0296328 0.0114971 -0.327181 -0.0290682 0.0139973 -0.327004 -0.028915 0.0142042 -0.326861 0.0252723 0.0144971 -0.377156 0.027866 0.0142042 -0.374542 0.0279236 0.0115732 -0.375014 0.0273611 0.0144971 -0.375041 0.0277515 0.0139973 -0.374717 0.0279614 0.0119973 -0.374891 0.0282407 0.0124971 -0.374474 0.0255514 0.0114971 -0.377455 0.0216684 0.0144971 -0.380121 0.00904643 0.0144971 -0.386006 0.00450779 0.0114971 -0.387266 0.00445842 0.0144971 -0.38686 -0.000202651 0.0114971 -0.38754 -0.000200598 0.0144971 -0.387131 -0.00485667 0.0144971 -0.386814 -0.00491011 0.0114971 -0.387219 -0.00953984 0.0114971 -0.386309 -0.00943586 0.0144971 -0.385913 -0.0140183 0.0114971 -0.384823 -0.0138655 0.0144971 -0.384444 -0.0182745 0.0114971 -0.382787 -0.0180752 0.0144971 -0.38243 -0.0222407 0.0114971 -0.380231 -0.0219981 0.0144971 -0.379902 -0.0317992 0.0114971 -0.369892 -0.0336652 0.0144971 -0.365567 -0.0340366 0.0114971 -0.365738 -0.0357338 0.0114971 -0.361335 -0.0368639 0.0114971 -0.356754 -0.0374089 0.0114971 -0.352067 -0.0370007 0.0144971 -0.352046 -0.0369526 0.0144971 -0.347379 -0.0367186 0.0114971 -0.342675 -0.0337066 0.0114971 -0.333751 -0.0310416 0.0144971 -0.329868 -0.0272416 -0.0200029 -0.327883 -0.0281809 -0.0185081 -0.327744 0.02597 -0.0205121 -0.373227 0.026869 -0.0185081 -0.373971 0.0270771 -0.0182958 -0.373879 -0.0271227 -0.0209268 -0.328789 -0.0273113 -0.0210029 -0.329131 -0.0272928 -0.0205121 -0.328501 -0.0288569 -0.0210029 -0.331314 -0.0309889 -0.0210029 -0.335089 -0.0326295 -0.0210029 -0.339101 -0.0347207 -0.0195668 -0.343093 -0.0337526 -0.0210029 -0.343288 -0.0343405 -0.0210029 -0.347583 -0.03537 -0.0195668 -0.351971 -0.0338818 -0.0210029 -0.356224 -0.0328425 -0.0210029 -0.360433 -0.0337845 -0.0195668 -0.36073 -0.0321796 -0.0195668 -0.36489 -0.0300645 -0.0195668 -0.368816 -0.0267067 -0.0210029 -0.371822 -0.024445 -0.0195668 -0.37572 -0.0237636 -0.0210029 -0.375005 -0.0132589 -0.0195668 -0.382929 -0.0167998 -0.0210029 -0.380141 -0.0128895 -0.0210029 -0.382013 -0.00902634 -0.0195668 -0.384333 -0.00465078 -0.0195668 -0.385194 0.00425042 -0.0195668 -0.385241 -0.000196448 -0.0210029 -0.384511 0.0125223 -0.0210029 -0.382147 0.0206985 -0.0195668 -0.378808 0.0201207 -0.0210029 -0.378007 0.0241437 -0.0195668 -0.375976 0.0234698 -0.0210029 -0.375254 0.0259997 -0.02071 -0.372974 -0.0281261 -0.0182958 -0.327523 -0.0296845 -0.0195668 -0.330775 -0.0318777 -0.0195668 -0.334658 -0.0335653 -0.0195668 -0.338786 -0.0360925 -0.0180029 -0.347455 -0.0353254 -0.0195668 -0.347511 -0.036138 -0.0180029 -0.352011 -0.0356104 -0.0180029 -0.356537 -0.0348536 -0.0195668 -0.3564 -0.0307173 -0.0180029 -0.369223 -0.0274726 -0.0195668 -0.372445 -0.0214865 -0.0180029 -0.379206 -0.0210299 -0.0195668 -0.378587 -0.0172814 -0.0195668 -0.381003 -0.00922212 -0.0180029 -0.385077 -0.00020573 -0.0180029 -0.386268 -0.000201666 -0.0195668 -0.385499 0.00863483 -0.0195668 -0.384426 0.00882274 -0.0180029 -0.385172 0.012882 -0.0195668 -0.383067 0.0169246 -0.0195668 -0.381184 0.0211484 -0.0180029 -0.379432 0.0266994 -0.0180029 -0.374485 0.0269323 -0.018079 -0.374181 -0.0294195 -0.00600288 -0.326055 -0.029918 -0.00800288 -0.326942 -0.0300941 -0.00500288 -0.326794 -0.0298544 -0.005079 -0.326496 0.0283029 -0.00786891 -0.375179 0.0279595 -0.00800288 -0.375543 0.028445 -0.00550296 -0.375298 0.0281357 -0.00500288 -0.375691 0.0259683 -0.00500288 -0.377889 0.0221315 -0.00800288 -0.38075 0.0181 -0.00800288 -0.383292 0.0182101 -0.00500288 -0.383493 0.0138647 -0.00500288 -0.38552 0.00924255 -0.00800288 -0.386762 0.00929881 -0.00500288 -0.386985 0.00458503 -0.00500288 -0.387863 -0.000200674 -0.00800288 -0.387912 -0.00969058 -0.00500288 -0.386891 -0.0142418 -0.00500288 -0.385382 -0.0224613 -0.00800288 -0.38053 -0.0185671 -0.00500288 -0.383313 -0.0261111 -0.00800288 -0.377466 -0.0323111 -0.00500288 -0.370209 -0.0343757 -0.00800288 -0.365891 -0.0345845 -0.00500288 -0.365987 -0.0374569 -0.00500288 -0.356857 -0.0380102 -0.00500288 -0.352095 -0.0370821 -0.00800288 -0.342595 -0.0360623 -0.00500288 -0.337919 -0.0340381 -0.00800288 -0.333582 -0.0342448 -0.00500288 -0.333482 -0.0318837 -0.00500288 -0.329309 -0.02976 -0.00550296 -0.326421 -0.0294882 -0.0056202 -0.326096 -0.028915 -0.01421 -0.326861 -0.0293195 -0.0145029 -0.327444 -0.0290925 -0.0144268 -0.327135 -0.0296328 -0.0115029 -0.327181 -0.0290682 -0.014003 -0.327004 -0.0288086 -0.0135029 -0.326568 -0.0289991 -0.0121202 -0.326507 -0.0292759 -0.012003 -0.326827 0.0276744 -0.0115029 -0.375304 0.0279236 -0.011579 -0.375014 0.0279614 -0.012003 -0.374891 0.028118 -0.0117958 -0.374753 0.0280447 -0.0138856 -0.374409 0.027866 -0.01421 -0.374542 0.0282407 -0.0125029 -0.374474 0.0277515 -0.014003 -0.374717 -0.0310415 -0.0145029 -0.329867 -0.0337066 -0.0115029 -0.333751 -0.0333388 -0.0145029 -0.33393 -0.0363179 -0.0145029 -0.342756 -0.0369526 -0.0145029 -0.347379 -0.0370007 -0.0145029 -0.352046 -0.0364616 -0.0145029 -0.356682 -0.0353439 -0.0145029 -0.361213 -0.0357338 -0.0115029 -0.361335 -0.0317993 -0.0115029 -0.369892 -0.0336652 -0.0145029 -0.365567 -0.0287402 -0.0145029 -0.373474 -0.0255721 -0.0145029 -0.376901 -0.0222408 -0.0115029 -0.380231 -0.0182746 -0.0115029 -0.382787 -0.0180752 -0.0145029 -0.38243 -0.0140184 -0.0115029 -0.384823 -0.0138655 -0.0145029 -0.384444 -0.0095399 -0.0115029 -0.386309 -0.00485673 -0.0145029 -0.386814 0.00904637 -0.0145029 -0.386006 0.00914637 -0.0115029 -0.386402 0.017916 -0.0115029 -0.382968 -0.0299863 -0.00142676 -0.326385 -0.0299228 -0.00100291 -0.326285 -0.029618 -0.000502883 -0.325888 -0.0296591 -0.000885566 -0.325953 0.0289458 -0.000502883 -0.375066 0.0287398 -0.00120999 -0.375275 0.0286071 -0.00100291 -0.375435 0.0261084 -2.88296e-06 -0.378034 -0.0320201 -0.00150288 -0.329216 -0.0344251 -2.88296e-06 -0.333391 -0.0375047 -2.88296e-06 -0.342507 -0.0381612 -2.88296e-06 -0.347283 -0.0374686 -0.00150288 -0.342515 -0.0381245 -0.00150288 -0.347286 -0.038175 -0.00150288 -0.352101 -0.0376557 -2.88296e-06 -0.356892 -0.0347682 -2.88296e-06 -0.36607 -0.0324515 -0.00150288 -0.370295 -0.0263837 -0.00150288 -0.377751 -0.0186651 -2.88296e-06 -0.383489 -0.0143166 -2.88296e-06 -0.38557 -0.00974092 -2.88296e-06 -0.387087 -0.00501076 -2.88296e-06 -0.388016 -0.000201062 -0.00150288 -0.388307 0.0139271 -0.00150288 -0.385673 0.0282621 -0.00150288 -0.375798 -0.0296591 0.0008798 -0.325953 -0.0299863 0.001421 -0.326385 -0.029618 0.000497117 -0.325888 -0.0299228 0.000997147 -0.326285 -0.0296257 -2.88296e-06 -0.325881 -0.0302205 0.00149712 -0.326688 -0.032051 -2.88296e-06 -0.329196 0.0286071 0.000997147 -0.375435 0.0260833 0.00149712 -0.378007 0.0223867 -2.88296e-06 -0.381098 0.0223651 0.00149712 -0.381068 0.0182915 0.00149712 -0.383637 0.0183091 -2.88296e-06 -0.383669 0.0139405 -2.88296e-06 -0.385707 0.00934124 0.00149712 -0.387144 0.00935025 -2.88296e-06 -0.38718 0.00461124 -2.88296e-06 -0.388063 -0.000201242 -2.88296e-06 -0.388344 0.00460679 0.00149712 -0.388027 -0.000201062 0.00149712 -0.388307 -0.00500595 0.00149712 -0.38798 -0.00973156 0.00149712 -0.387051 -0.0186472 0.00149712 -0.383457 -0.0226955 0.00149712 -0.380848 -0.0227174 -2.88296e-06 -0.380878 -0.0264091 -2.88296e-06 -0.377778 -0.0263837 0.00149712 -0.377751 -0.0296815 -2.88296e-06 -0.374238 -0.0324827 -2.88296e-06 -0.370315 -0.0296529 0.00149712 -0.374215 -0.0347348 0.00149712 -0.366055 -0.0365017 -2.88296e-06 -0.361572 -0.0382118 -2.88296e-06 -0.352103 -0.038175 0.00149712 -0.352101 -0.0362527 -2.88296e-06 -0.337852 -0.034392 0.00149712 -0.333407 -0.029048 0.0209622 -0.32733 -0.0291921 0.0209971 -0.327551 -0.0273113 0.0209971 -0.329131 -0.0204437 0.0209971 -0.377793 -0.0167997 0.0209971 -0.380141 -0.0087749 0.0209971 -0.383378 -0.00751402 0.0209971 -0.386194 0.0015341 0.0209971 -0.386933 -0.000196371 0.0209971 -0.384511 0.00413152 0.0209971 -0.384261 0.00839364 0.0209971 -0.383469 0.00605741 0.0209971 -0.386462 0.0104883 0.0209971 -0.385438 0.0164522 0.0209971 -0.380317 0.0147595 0.0209971 -0.383876 0.0188059 0.0209971 -0.3818 0.022566 0.0209971 -0.379242 0.0259825 0.0209971 -0.37624 0.0253529 0.0209971 -0.373355 -0.0288569 0.0209971 -0.331314 -0.0302626 0.0209971 -0.32901 -0.0326295 0.0209971 -0.339101 -0.0358423 0.0209971 -0.341384 -0.0343838 0.0209971 -0.351918 -0.0328425 0.0209971 -0.360433 -0.0356917 0.0209971 -0.359402 -0.0292262 0.0209971 -0.368294 -0.0267066 0.0209971 -0.371822 -0.0270212 0.0209971 -0.375196 0.0275269 0.020921 -0.37468 0.0278437 0.0207042 -0.374523 0.0281309 0.0203798 -0.374481 0.0263226 0.0203798 -0.372962 0.0287038 0.0189971 -0.374863 0.0285699 0.0180732 -0.375556 0.0269323 0.0180732 -0.374181 0.0211485 0.0179971 -0.379432 0.0172927 0.0179971 -0.381859 0.0195386 0.0179971 -0.383034 0.0131623 0.0179971 -0.383783 0.0108972 0.0179971 -0.386814 0.00434315 0.0179971 -0.386005 -0.000205649 0.0179971 -0.386268 -0.00475142 0.0179971 -0.385957 -0.00922204 0.0179971 -0.385077 -0.00780599 0.0179971 -0.3876 -0.012364 0.0179971 -0.386356 -0.0167341 0.0179971 -0.384559 -0.0249757 0.0179971 -0.376276 -0.0280726 0.0179971 -0.376174 -0.0310698 0.0179971 -0.372521 -0.0335945 0.0179971 -0.368528 -0.0328784 0.0179971 -0.365212 -0.0356084 0.0179971 -0.364253 -0.0345181 0.0179971 -0.360961 -0.0379892 0.0179971 -0.355127 -0.0356104 0.0179971 -0.356537 -0.036138 0.0179971 -0.352012 -0.038068 0.0179971 -0.345696 -0.0360925 0.0179971 -0.347455 -0.0354747 0.0179971 -0.342941 -0.0372371 0.0179971 -0.341045 -0.0342942 0.0179971 -0.33854 -0.03584 0.0179971 -0.336531 -0.0338978 0.0179971 -0.332224 -0.0303291 0.0179971 -0.330355 -0.0286579 0.0179971 -0.328 -0.0283986 0.0180732 -0.327718 -0.0278772 0.0186144 -0.327449 -0.0293761 0.0189971 -0.326091 -0.0311912 0.0008798 -0.324666 -0.0313211 0.00120422 -0.32484 -0.0297888 0.00120422 -0.326127 -0.031519 0.001421 -0.325098 0.0168792 0.00149712 -0.386587 0.0210978 0.00149712 -0.38432 0.0250169 0.00149712 -0.381567 -0.0328078 0.00149712 -0.326818 -0.0320201 0.00149712 -0.329216 -0.0362178 0.00149712 -0.337864 -0.0374686 0.00149712 -0.342515 -0.0381245 0.00149712 -0.347286 -0.0402192 0.00149712 -0.349232 -0.0376195 0.00149712 -0.356885 -0.0392863 0.00149712 -0.358748 -0.0364666 0.00149712 -0.361561 -0.037979 0.00149712 -0.363355 -0.0361332 0.00149712 -0.367774 -0.0324515 0.00149712 -0.370295 -0.0337752 0.00149712 -0.371943 -0.0276629 0.00149712 -0.379295 -0.0239953 0.00149712 -0.382375 -0.0143028 0.00149712 -0.385535 -0.0199876 0.00149712 -0.384997 -0.0111832 0.00149712 -0.388726 -0.00651132 0.00149712 -0.38978 -0.00174735 0.00149712 -0.39027 0.0030412 0.00149712 -0.390192 0.0139271 0.00149712 -0.385673 0.0282621 0.00149712 -0.375798 0.0302721 0.00120422 -0.376562 0.0285201 0.001421 -0.375514 0.0287398 0.00120422 -0.375275 0.028889 0.0008798 -0.375118 -0.0310371 0.00770422 -0.325079 -0.0316912 0.00799712 -0.329434 -0.0324916 0.00799712 -0.327043 0.0247755 0.00799712 -0.381264 0.0221316 0.00799712 -0.38075 0.0208942 0.00799712 -0.38399 0.0181001 0.00799712 -0.383292 -0.0370821 0.00799712 -0.342595 -0.0394477 0.00799712 -0.344513 -0.0377309 0.00799712 -0.347317 -0.0396506 0.00799712 -0.35398 -0.0389076 0.00799712 -0.358664 -0.0343757 0.00799712 -0.365891 -0.0376129 0.00799712 -0.363227 -0.0334497 0.00799712 -0.371732 -0.0293465 0.00799712 -0.373966 -0.0273963 0.00799712 -0.379014 -0.0224613 0.00799712 -0.38053 -0.018455 0.00799712 -0.383112 -0.0237641 0.00799712 -0.382064 -0.0141558 0.00799712 -0.385169 -0.0155454 0.00799712 -0.386767 -0.0110755 0.00799712 -0.388353 -0.0049556 0.00799712 -0.387588 -0.00020064 0.00799712 -0.387912 0.00301174 0.00799712 -0.389805 0.00924258 0.00799712 -0.386762 0.00771119 0.00799712 -0.389163 0.0137809 0.00799712 -0.385306 0.0167163 0.00799712 -0.386235 0.0297591 0.007921 -0.376555 0.028221 0.007921 -0.375263 0.0301514 0.0073798 -0.376178 0.0286144 0.0073798 -0.374887 0.030225 0.00699712 -0.37614 0.0302826 0.00599712 -0.376188 0.0287472 0.00599712 -0.374899 0.0302531 0.00561443 -0.376263 0.0301272 0.00529001 -0.37644 0.0299232 0.00507324 -0.376693 0.0283882 0.00507324 -0.375404 -0.0326757 0.00499712 -0.326912 -0.0318837 0.00499712 -0.329309 -0.0342449 0.00499712 -0.333482 -0.0372252 0.00499712 -0.335278 -0.0360624 0.00499712 -0.337919 0.0123709 0.00499712 -0.388183 0.0138647 0.00499712 -0.38552 0.00775498 0.00499712 -0.389385 0.00302889 0.00499712 -0.39003 -0.00174037 0.00499712 -0.390109 -0.000201771 0.00499712 -0.388142 -0.00648515 0.00499712 -0.38962 -0.0142418 0.00499712 -0.385382 -0.0156334 0.00499712 -0.386975 -0.0225977 0.00499712 -0.380715 -0.0262697 0.00499712 -0.377632 -0.0238987 0.00499712 -0.382245 -0.0275515 0.00499712 -0.379178 -0.0336392 0.00499712 -0.371855 -0.0363089 0.00499712 -0.361513 -0.039128 0.00499712 -0.358713 -0.0380102 0.00499712 -0.352095 -0.0379601 0.00499712 -0.3473 -0.0298544 0.00507324 -0.326496 -0.0310233 0.00561443 -0.324807 -0.0294882 0.00561443 -0.326096 -0.0309549 0.00599712 -0.324765 -0.0294195 0.00599712 -0.326055 -0.0293608 0.00699712 -0.326104 -0.030355 0.0134971 -0.325269 -0.0288086 0.0134971 -0.326568 -0.0288149 0.0138798 -0.326662 -0.0290925 0.014421 -0.327135 0.02776 0.0144971 -0.377557 0.0204916 0.0144971 -0.383337 0.0177203 0.0144971 -0.382609 -0.0293195 0.0144971 -0.327444 -0.030869 0.0144971 -0.326143 -0.0333388 0.0144971 -0.33393 -0.035107 0.0144971 -0.338249 -0.0363031 0.0144971 -0.335645 -0.0377635 0.0144971 -0.340062 -0.0386885 0.0144971 -0.34462 -0.0363179 0.0144971 -0.342756 -0.0390649 0.0144971 -0.349257 -0.0388875 0.0144971 -0.353905 -0.0364616 0.0144971 -0.356682 -0.0353439 0.0144971 -0.361213 -0.036889 0.0144971 -0.362974 -0.0314523 0.0144971 -0.369676 -0.0287402 0.0144971 -0.373474 -0.0328059 0.0144971 -0.371316 -0.025572 0.0144971 -0.376901 -0.0268691 0.0144971 -0.378457 -0.0108625 0.0144971 -0.387617 -0.0016976 0.0144971 -0.389117 0.00295347 0.0144971 -0.38904 0.0134906 0.0144971 -0.384582 0.00756244 0.0144971 -0.388411 0.012064 0.0144971 -0.387239 0.0291751 0.014421 -0.376064 0.0276263 0.014421 -0.374764 0.0295919 0.0138798 -0.375708 0.0280447 0.0138798 -0.374409 0.0296827 0.0134971 -0.375685 0.0281363 0.0134971 -0.374386 0.0282289 0.0121144 -0.374563 0.0296614 0.01179 -0.376049 0.028118 0.01179 -0.374753 0.0276744 0.0114971 -0.375304 0.0292182 0.0114971 -0.3766 0.0280454 0.0114971 -0.377839 0.0219077 0.0114971 -0.380452 0.017916 0.0114971 -0.382968 0.0136396 0.0114971 -0.384962 -0.0321936 0.0114971 -0.327254 -0.031384 0.0114971 -0.329644 -0.0346807 0.0114971 -0.331242 -0.036676 0.0114971 -0.335497 -0.0381514 0.0114971 -0.339958 -0.0354943 0.0114971 -0.338118 0.0165628 0.0114971 -0.385904 0.00764031 0.0114971 -0.388805 0.00914643 0.0114971 -0.386402 -0.0017149 0.0114971 -0.389518 -0.00638965 0.0114971 -0.389036 -0.010974 0.0114971 -0.388002 -0.0154029 0.0114971 -0.386431 -0.0258541 0.0114971 -0.377197 -0.0290572 0.0114971 -0.373732 -0.0303592 0.0114971 -0.37532 -0.0331429 0.0114971 -0.371534 -0.037268 0.0114971 -0.363107 -0.0385508 0.0114971 -0.358586 -0.0373602 0.0114971 -0.347349 -0.0394662 0.0114971 -0.349248 -0.0294706 0.0115311 -0.32698 -0.0293115 0.0116311 -0.326798 -0.0307103 0.0117901 -0.325353 -0.0304574 0.0124971 -0.325183 -0.028913 0.0124971 -0.32648 -0.0276845 -0.0190029 -0.327512 -0.0278772 -0.0186202 -0.327449 -0.0300362 -0.018079 -0.326343 -0.0283986 -0.018079 -0.327718 0.0269946 -0.0180029 -0.377258 0.0246685 -0.0180029 -0.376539 0.0172926 -0.0180029 -0.381859 0.0131622 -0.0180029 -0.383783 0.0153347 -0.0180029 -0.385191 0.00434307 -0.0180029 -0.386005 -0.00312949 -0.0180029 -0.388274 -0.0047515 -0.0180029 -0.385957 -0.00780599 -0.0180029 -0.3876 -0.0135467 -0.0180029 -0.383642 -0.0176565 -0.0180029 -0.381675 -0.0286579 -0.0180029 -0.328 -0.0302922 -0.0180029 -0.326628 -0.0314402 -0.0180029 -0.328189 -0.0303291 -0.0180029 -0.330355 -0.0325699 -0.0180029 -0.334323 -0.0342942 -0.0180029 -0.33854 -0.03584 -0.0180029 -0.336531 -0.0354746 -0.0180029 -0.342941 -0.0372371 -0.0180029 -0.341045 -0.0379892 -0.0180029 -0.355127 -0.0345181 -0.0180029 -0.360961 -0.0328784 -0.0180029 -0.365212 -0.0280691 -0.0180029 -0.372931 -0.0249758 -0.0180029 -0.376276 -0.0280726 -0.0180029 -0.376174 0.0285699 -0.018079 -0.375556 0.027107 -0.0186202 -0.373621 0.0287741 -0.0186202 -0.375021 0.0287038 -0.0190029 -0.374863 0.0270122 -0.0190029 -0.373442 0.0283402 -0.0200029 -0.374557 0.0265694 -0.0200029 -0.37307 0.0281309 -0.0203856 -0.374481 0.0263226 -0.0203856 -0.372962 0.0275269 -0.0209268 -0.37468 0.0256565 -0.0209268 -0.37311 0.0253529 -0.0210029 -0.373355 0.022566 -0.0210029 -0.379242 0.0164521 -0.0210029 -0.380317 0.0147595 -0.0210029 -0.383876 0.00839357 -0.0210029 -0.383469 0.00413145 -0.0210029 -0.384261 0.0015341 -0.0210029 -0.386933 -0.00301277 -0.0210029 -0.386843 -0.00452146 -0.0210029 -0.384215 -0.00877497 -0.0210029 -0.383378 -0.0119012 -0.0210029 -0.384997 -0.0204437 -0.0210029 -0.377793 -0.0326281 -0.0210029 -0.332894 -0.0344975 -0.0210029 -0.33704 -0.036642 -0.0210029 -0.345861 -0.0368846 -0.0210029 -0.350402 -0.0365662 -0.0210029 -0.354939 -0.0343838 -0.0210029 -0.351918 -0.0356917 -0.0210029 -0.359402 -0.0312824 -0.0210029 -0.364478 -0.0342745 -0.0210029 -0.363723 -0.0292263 -0.0210029 -0.368294 -0.029906 -0.0210029 -0.371681 -0.0161075 -0.0210029 -0.383268 -0.0289931 -0.0209268 -0.327219 -0.0288927 -0.02071 -0.32688 -0.0270487 -0.02071 -0.328428 -0.0270928 -0.0203856 -0.328108 -0.0290124 -0.0200029 -0.326396 -0.0293761 -0.0190029 -0.326091 -0.0310233 -0.0056202 -0.324807 -0.0311762 -0.00529578 -0.324962 -0.0296413 -0.00529578 -0.326251 0.0296712 -0.00500288 -0.376981 0.0222661 -0.00500288 -0.380936 0.0210127 -0.00500288 -0.384182 0.0168111 -0.00500288 -0.38644 -0.0352 -0.00500288 -0.330959 -0.0373074 -0.00500288 -0.34255 -0.0396712 -0.00500288 -0.344481 -0.0379601 -0.00500288 -0.3473 -0.0398753 -0.00500288 -0.354002 -0.0363089 -0.00500288 -0.361513 -0.0359877 -0.00500288 -0.367703 -0.0295247 -0.00500288 -0.374111 -0.0336392 -0.00500288 -0.371855 -0.0262697 -0.00500288 -0.377632 -0.0308138 -0.00500288 -0.375698 -0.0225977 -0.00500288 -0.380715 -0.0275515 -0.00500288 -0.379178 -0.0156334 -0.00500288 -0.386975 -0.00498566 -0.00500288 -0.387816 -0.0111382 -0.00500288 -0.38857 -0.000201805 -0.00500288 -0.388142 0.00302889 -0.00500288 -0.39003 0.00775498 -0.00500288 -0.389385 0.0299232 -0.005079 -0.376693 0.0301272 -0.00529578 -0.37644 0.0283882 -0.005079 -0.375404 0.0285923 -0.00529578 -0.375151 0.028718 -0.0056202 -0.374974 0.0302826 -0.00600288 -0.376188 0.0287472 -0.00600288 -0.374899 0.0286885 -0.00700288 -0.37485 0.0296736 -0.00796885 -0.376645 0.0285689 -0.00750288 -0.374924 0.0258113 -0.00800288 -0.377721 0.0294982 -0.00800288 -0.376836 0.0283053 -0.00800288 -0.378096 0.0137808 -0.00800288 -0.385306 0.00301174 -0.00800288 -0.389805 0.00455724 -0.00800288 -0.387635 -0.00495564 -0.00800288 -0.387588 -0.00963213 -0.00800288 -0.386669 -0.00644868 -0.00800288 -0.389397 -0.0110755 -0.00800288 -0.388353 -0.0141559 -0.00800288 -0.385169 -0.0155454 -0.00800288 -0.386767 -0.018455 -0.00800288 -0.383112 -0.019795 -0.00800288 -0.384661 -0.0237641 -0.00800288 -0.382064 -0.0273963 -0.00800288 -0.379014 -0.0293465 -0.00800288 -0.373966 -0.032116 -0.00800288 -0.370087 -0.0334497 -0.00800288 -0.371732 -0.035785 -0.00800288 -0.367604 -0.0360896 -0.00800288 -0.361444 -0.0372307 -0.00800288 -0.356817 -0.0389076 -0.00800288 -0.358664 -0.0377807 -0.00800288 -0.352082 -0.0377309 -0.00800288 -0.347317 -0.0324916 -0.00800288 -0.327043 -0.0316912 -0.00800288 -0.329434 -0.0350017 -0.00800288 -0.331067 -0.0385045 -0.00800288 -0.339865 -0.0358446 -0.00800288 -0.337993 -0.0394477 -0.00800288 -0.344513 -0.0312987 -0.00796852 -0.325443 -0.0296183 -0.00786891 -0.326541 -0.0294135 -0.00750288 -0.326235 -0.0293608 -0.00700288 -0.326104 -0.0304574 -0.0125029 -0.325183 -0.028913 -0.0125029 -0.32648 -0.030543 -0.0121202 -0.325211 -0.0291669 -0.0117958 -0.326649 -0.0309332 -0.011579 -0.32559 -0.0293898 -0.011579 -0.326886 0.0219077 -0.0115029 -0.380453 0.0255514 -0.0115029 -0.377455 0.0280454 -0.0115029 -0.377839 -0.031384 -0.0115029 -0.329644 -0.0346807 -0.0115029 -0.331242 -0.0354942 -0.0115029 -0.338118 -0.0381514 -0.0115029 -0.339958 -0.0390859 -0.0115029 -0.344564 -0.0367186 -0.0115029 -0.342675 -0.0373602 -0.0115029 -0.347349 -0.0374089 -0.0115029 -0.352067 -0.0385508 -0.0115029 -0.358586 -0.0368639 -0.0115029 -0.356754 -0.037268 -0.0115029 -0.363107 -0.0340366 -0.0115029 -0.365738 -0.0354568 -0.0115029 -0.367443 -0.0331429 -0.0115029 -0.371534 -0.0290573 -0.0115029 -0.373732 -0.0303592 -0.0115029 -0.37532 -0.0258542 -0.0115029 -0.377196 -0.0235462 -0.0115029 -0.381771 -0.0196135 -0.0115029 -0.384343 -0.0154029 -0.0115029 -0.386431 -0.00491017 -0.0115029 -0.387219 -0.000202711 -0.0115029 -0.38754 0.00450773 -0.0115029 -0.387266 0.0136396 -0.0115029 -0.384962 0.0121881 -0.0115029 -0.387621 0.0297728 -0.0121202 -0.37586 0.0282289 -0.0121202 -0.374563 0.0281363 -0.0135029 -0.374386 0.0276263 -0.0144268 -0.374764 0.0289106 -0.0145029 -0.376342 0.0273611 -0.0145029 -0.375041 0.0252723 -0.0145029 -0.377156 0.02776 -0.0145029 -0.377557 0.0216684 -0.0145029 -0.380121 0.0242982 -0.0145029 -0.380664 0.0177202 -0.0145029 -0.382609 0.0204916 -0.0145029 -0.383337 0.0134905 -0.0145029 -0.384582 0.00445836 -0.0145029 -0.38686 0.00295347 -0.0145029 -0.38904 -0.000200658 -0.0145029 -0.387131 -0.0063248 -0.0145029 -0.38864 -0.0108625 -0.0145029 -0.387617 -0.00943592 -0.0145029 -0.385913 -0.0152463 -0.0145029 -0.386061 -0.0219982 -0.0145029 -0.379902 -0.0233068 -0.0145029 -0.381448 -0.0268691 -0.0145029 -0.378457 -0.0314523 -0.0145029 -0.369676 -0.0350963 -0.0145029 -0.367267 -0.0388875 -0.0145029 -0.353905 -0.0318663 -0.0145029 -0.327487 -0.0363031 -0.0145029 -0.335645 -0.0351069 -0.0145029 -0.338249 -0.0306413 -0.0144268 -0.325835 -0.0288149 -0.0138856 -0.326662 0.0289534 -2.88296e-06 -0.375072 0.0289458 0.000497117 -0.375066 0.0304847 -3.79824e-05 -0.376358 0.0304852 -2.88296e-06 -0.376359 0.028889 -0.000885566 -0.375118 0.0285201 -0.00142676 -0.375514 0.0260833 -0.00150288 -0.378007 0.0223651 -0.00150288 -0.381068 0.0182915 -0.00150288 -0.383637 0.0168792 -0.00150288 -0.386587 0.00934124 -0.00150288 -0.387144 0.00460679 -0.00150288 -0.388027 -0.00500595 -0.00150288 -0.38798 -0.00973156 -0.00150288 -0.387051 -0.0143028 -0.00150288 -0.385535 -0.0186472 -0.00150288 -0.383457 -0.0199876 -0.00150288 -0.384997 -0.0226955 -0.00150288 -0.380848 -0.0239953 -0.00150288 -0.382375 -0.0296529 -0.00150288 -0.374215 -0.0347348 -0.00150288 -0.366055 -0.0361332 -0.00150288 -0.367774 -0.0364666 -0.00150288 -0.361561 -0.0376195 -0.00150288 -0.356885 -0.034392 -0.00150288 -0.333407 -0.0373758 -0.00150288 -0.335218 -0.0362178 -0.00150288 -0.337864 -0.0388793 -0.00150288 -0.339765 -0.0302205 -0.00150288 -0.326688 -0.0313211 -0.00120999 -0.32484 -0.0297888 -0.00120999 -0.326127 -0.0136392 0.0274971 -0.371114 -0.0191978 0.0274971 -0.333985 -0.0221716 0.0274971 -0.338408 0.0176474 0.0274971 -0.367857 -0.0234417 0.0274971 -0.341225 -0.0183624 0.0274971 -0.367148 -0.0203223 0.0274971 -0.36476 -0.0219733 0.0274971 -0.362148 -0.0232902 0.0274971 -0.359353 -0.00510957 0.0274971 -0.37462 -0.024253 0.0274971 -0.356417 -0.00246394 0.0274971 -0.348037 -0.0250634 0.0274971 -0.350303 -0.0154703 0.0274971 -0.337115 -0.0248986 0.0274971 -0.347218 -0.0243553 0.0274971 -0.344177 0.0100227 0.0274971 -0.373045 0.00411061 0.0274971 -0.374802 -0.00809014 0.0274971 -0.373806 -1.46038e-05 0.0274971 -0.350094 0.0256902 0.0246091 -0.371679 0.0261315 0.0241428 -0.37205 0.0240581 0.0241428 -0.374305 -0.0294992 0.0173766 -0.325335 -0.0289478 0.0208631 -0.327104 0.0272336 0.0209971 -0.374934 0.0253873 0.022186 -0.375642 0.0102479 0.022186 -0.384628 0.00149864 0.022186 -0.386089 -0.00301277 0.0209971 -0.386843 -0.00294412 0.022186 -0.386002 -0.0119012 0.0209971 -0.384997 -0.0161075 0.0209971 -0.383268 -0.020069 0.0209971 -0.381034 -0.0237255 0.0209971 -0.37833 -0.0231826 0.022186 -0.377684 -0.029906 0.0209971 -0.371681 -0.0292216 0.022186 -0.371187 -0.0323361 0.0209971 -0.367837 -0.0315961 0.022186 -0.367431 -0.0342745 0.0209971 -0.363723 -0.0365662 0.0209971 -0.354939 -0.0357293 0.022186 -0.354828 -0.0368846 0.0209971 -0.350402 -0.0360404 0.022186 -0.350395 -0.036642 0.0209971 -0.345861 -0.0358034 0.022186 -0.345958 -0.0344975 0.0209971 -0.33704 -0.0326281 0.0209971 -0.332894 -0.02957 0.022186 -0.329492 0.0283338 0.0179971 -0.375858 0.02947 0.0173766 -0.374853 0.0269946 0.0179971 -0.377258 0.0287258 0.01829 -0.375264 0.0287741 0.0186144 -0.375021 0.0288439 0.0195284 -0.374327 0.0283402 0.0199971 -0.374557 -0.0124267 0.0173766 -0.38654 -0.016819 0.0173766 -0.384735 -0.0209557 0.0173766 -0.382402 -0.0208498 0.0179971 -0.382239 -0.0246486 0.0179971 -0.379429 -0.0282152 0.0173766 -0.376306 -0.0337652 0.0173766 -0.368621 -0.0370807 0.0179971 -0.359764 -0.03832 0.0179971 -0.350414 -0.0382614 0.0173766 -0.345674 -0.0360221 0.0173766 -0.336462 -0.0288862 0.0204971 -0.326677 -0.0287313 0.0199019 -0.32598 -0.0290124 0.0199971 -0.326396 -0.0295443 0.0186144 -0.326049 -0.0297748 0.01829 -0.326139 -0.0300362 0.0180732 -0.326343 -0.0302922 0.0179971 -0.326628 -0.0315999 0.0173766 -0.328077 -0.0314402 0.0179971 -0.328189 -0.0317179 0.0156872 -0.327592 -0.03407 0.0173766 -0.332133 -0.036134 0.0156872 -0.335712 -0.0374263 0.0173766 -0.340999 -0.0375876 0.0156872 -0.340108 -0.0385083 0.0156872 -0.344646 -0.0385147 0.0173766 -0.350416 -0.0381822 0.0173766 -0.355153 -0.038883 0.0156872 -0.349261 -0.0387064 0.0156872 -0.353887 -0.0372691 0.0173766 -0.359813 -0.0357893 0.0173766 -0.364325 -0.0312276 0.0173766 -0.372635 -0.0315323 0.0156872 -0.372855 -0.026744 0.0156872 -0.378325 -0.0284905 0.0156872 -0.376562 -0.0247738 0.0173766 -0.379579 -0.0231983 0.0156872 -0.381302 -0.0125479 0.0156872 -0.386896 -0.0169831 0.0156872 -0.385073 -0.00792204 0.0156872 -0.388159 -0.010812 0.0156872 -0.387442 0.0015944 0.0179971 -0.388367 0.00629381 0.0179971 -0.387878 0.00160257 0.0173766 -0.388561 0.00632587 0.0173766 -0.38807 0.0153347 0.0179971 -0.385191 0.019638 0.0173766 -0.383202 0.0234451 0.0179971 -0.380377 -0.00312949 0.0179971 -0.388274 -0.00784559 0.0173766 -0.387791 -0.00314532 0.0173766 -0.388468 -0.00168976 0.0156872 -0.388935 0.00293964 0.0156872 -0.388859 0.0120077 0.0156872 -0.387066 0.0109527 0.0173766 -0.387 0.0154127 0.0173766 -0.385369 0.0163177 0.0156872 -0.385374 0.0235643 0.0173766 -0.380531 0.0241849 0.0156872 -0.380521 0.0271319 0.0173766 -0.377396 0.0296862 0.0162131 -0.375035 0.0276306 0.0156872 -0.377429 0.0275751 0.022186 -0.373262 0.0204914 0.0273901 -0.367314 0.0188653 0.0273901 -0.369082 0.0153262 0.0274971 -0.369897 0.0127717 0.0274971 -0.371635 0.0107148 0.0273901 -0.374627 0.00761297 0.0273901 -0.375762 0.00712091 0.0274971 -0.374106 0.00103756 0.0274971 -0.375122 -0.00219196 0.0273901 -0.376782 -0.0020515 0.0274971 -0.375061 -0.00864701 0.0273901 -0.375441 -0.0117018 0.0273901 -0.374186 -0.0109478 0.0274971 -0.372632 -0.0172342 0.0273901 -0.3706 -0.0161233 0.0274971 -0.369277 -0.0196276 0.0273901 -0.368324 -0.0217227 0.0273901 -0.365771 -0.0234875 0.0273901 -0.362979 -0.0259245 0.0273901 -0.356853 -0.0265595 0.0273901 -0.353612 -0.0248471 0.0274971 -0.353385 -0.0267907 0.0273901 -0.350318 -0.0266146 0.0273901 -0.34702 -0.0205645 0.0274971 -0.33577 -0.0219816 0.0273901 -0.334782 -0.0241565 0.0267948 -0.333266 -0.0261607 0.0241428 -0.328138 0.0180077 0.0267948 -0.373358 0.0163841 0.0273901 -0.371262 0.0136534 0.0273901 -0.37312 0.00836814 0.0267948 -0.378303 0.00439508 0.0273901 -0.376505 0.00111012 0.0273901 -0.376847 -0.00240754 0.0267948 -0.379425 -0.00546092 0.0273901 -0.376311 -0.00950168 0.0267948 -0.377951 -0.0145788 0.0273901 -0.372564 -0.018939 0.0267948 -0.37263 -0.0238719 0.0267948 -0.367323 -0.0258115 0.0267948 -0.364255 -0.0273586 0.0267948 -0.360972 -0.0248952 0.0273901 -0.359992 -0.0284897 0.0267948 -0.357523 -0.0291876 0.0267948 -0.353961 -0.0286099 0.0267948 -0.343142 -0.0260338 0.0273901 -0.343768 -0.0275365 0.0267948 -0.339675 -0.0250572 0.0273901 -0.340613 -0.0236995 0.0273901 -0.337603 -0.0205206 0.0273901 -0.332874 0.0225216 0.0267948 -0.369018 0.0207346 0.0267948 -0.370962 0.0195303 0.0256986 -0.375323 0.0150066 0.0267948 -0.3754 0.0117771 0.0267948 -0.377056 0.0127733 0.0256986 -0.379334 0.0052411 0.0256986 -0.381573 0.00483167 0.0267948 -0.37912 0.0013259 0.0256986 -0.38198 -0.0026097 0.0256986 -0.381903 0.00122147 0.0267948 -0.379496 -0.00600014 0.0267948 -0.378907 -0.017373 0.0256986 -0.376875 -0.0128589 0.0267948 -0.376571 -0.0160207 0.0267948 -0.374789 -0.0233904 0.0256986 -0.371822 -0.0215694 0.0267948 -0.370129 -0.0296687 0.0256986 -0.361891 -0.0316522 0.0256986 -0.354287 -0.0319278 0.0256986 -0.350361 -0.0294417 0.0267948 -0.35034 -0.0292482 0.0267948 -0.346715 -0.0282436 0.0256986 -0.335206 -0.0260445 0.0267948 -0.336366 -0.0230829 0.0265456 -0.330723 0.0224875 0.0256986 -0.372725 0.0208945 0.0241428 -0.377084 0.0162757 0.0256986 -0.377538 0.0136659 0.0241428 -0.381375 0.00907634 0.0256986 -0.380686 0.00971089 0.0241428 -0.382821 0.00560794 0.0241428 -0.38377 -0.00650581 0.0256986 -0.381341 -0.0110213 0.0241428 -0.382413 -0.0103032 0.0256986 -0.380304 -0.0149163 0.0241428 -0.380812 -0.013944 0.0256986 -0.378808 -0.0185846 0.0241428 -0.378744 -0.0219703 0.0241428 -0.37624 -0.0205378 0.0256986 -0.374534 -0.0258875 0.0256986 -0.368779 -0.0279909 0.0256986 -0.365451 -0.0317385 0.0241428 -0.362714 -0.0308954 0.0256986 -0.35815 -0.0317179 0.0256986 -0.34643 -0.0310257 0.0256986 -0.342555 -0.031945 0.0241428 -0.338006 -0.0298617 0.0256986 -0.338795 -0.0280235 0.0241428 -0.33057 -0.0261961 0.0256986 -0.331844 -0.0248294 0.0254102 -0.329256 0.022049 0.022186 -0.378575 0.018375 0.022186 -0.381074 0.0174127 0.0241428 -0.379453 0.0144212 0.022186 -0.383102 0.00591839 0.022186 -0.385629 0.00141946 0.0241428 -0.384206 -0.00279083 0.0241428 -0.384123 -0.00734232 0.022186 -0.385368 -0.0069589 0.0241428 -0.383522 -0.011629 0.022186 -0.384198 -0.0157391 0.022186 -0.382508 -0.0196099 0.022186 -0.380326 -0.0264028 0.022186 -0.374622 -0.0250221 0.0241428 -0.373338 -0.0276934 0.0241428 -0.370083 -0.0299436 0.0241428 -0.366523 -0.0334901 0.022186 -0.363411 -0.0330508 0.0241428 -0.358713 -0.0348749 0.022186 -0.359188 -0.0338605 0.0241428 -0.35458 -0.0341553 0.0241428 -0.350379 -0.0339308 0.0241428 -0.346174 -0.035022 0.022186 -0.341583 -0.0331902 0.0241428 -0.342029 -0.033708 0.022186 -0.337338 -0.030214 0.0241428 -0.334167 -0.0318814 0.022186 -0.333288 0.0304776 0.000497117 -0.376352 0.0296712 0.00499712 -0.376981 0.0300528 0.001421 -0.376802 0.0284658 0.00499712 -0.378255 0.030421 0.0008798 -0.376404 0.0299881 0.00770422 -0.376324 0.0294982 0.00799712 -0.376836 0.0304933 0.00786613 -0.375712 0.029467 0.0115732 -0.37631 0.029414 0.0142042 -0.375841 0.0297728 0.0121144 -0.37586 0.0297851 0.0124971 -0.375771 0.0289106 0.0144971 -0.376342 -0.0297871 0.0156872 -0.325093 -0.0306413 0.014421 -0.325835 -0.0304629 0.0142042 -0.325561 -0.0303621 0.0138798 -0.325363 -0.0308548 0.0116311 -0.325502 -0.0305907 0.0119971 -0.325246 -0.0313895 0.00507324 -0.325206 -0.0311766 0.0114971 -0.325885 -0.0310133 0.0115315 -0.325683 -0.0314566 0.00799712 -0.32565 -0.0312253 0.007921 -0.325344 -0.0305225 0.00786613 -0.324476 -0.0309215 0.0073798 -0.324893 -0.0308972 0.00699712 -0.324814 -0.0311762 0.00529001 -0.324962 -0.0317538 0.00149712 -0.3254 -0.0308383 -2.88296e-06 -0.32421 -0.0311499 0.000497117 -0.324602 -0.0311574 -2.88296e-06 -0.324595 0.0297954 0.00149712 -0.377085 0.028581 0.00149712 -0.378368 0.024916 0.00499712 -0.381441 0.0210127 0.00499712 -0.384182 0.0168111 0.00499712 -0.38644 0.012421 0.00149712 -0.388337 0.00778641 0.00149712 -0.389544 -0.0111382 0.00499712 -0.38857 -0.0156966 0.00149712 -0.387124 -0.0199071 0.00499712 -0.384857 -0.0309384 0.00149712 -0.375801 -0.0308138 0.00499712 -0.375698 -0.0359877 0.00499712 -0.367703 -0.037826 0.00499712 -0.363302 -0.0400366 0.00149712 -0.354018 -0.0398753 0.00499712 -0.354002 -0.0400572 0.00499712 -0.349236 -0.0398316 0.00149712 -0.344459 -0.0396712 0.00499712 -0.344481 -0.0388793 0.00149712 -0.339765 -0.0387227 0.00499712 -0.339807 -0.0373758 0.00149712 -0.335218 -0.0352 0.00499712 -0.330959 -0.0353423 0.00149712 -0.330882 -0.0316296 0.00499712 -0.325505 0.0283053 0.00799712 -0.378096 0.0245481 0.0114971 -0.380978 0.0207023 0.0114971 -0.383679 0.0123011 0.00799712 -0.387968 0.0121881 0.0114971 -0.387621 0.00298397 0.0114971 -0.389441 -0.00173064 0.00799712 -0.389883 -0.00644868 0.00799712 -0.389397 -0.019795 0.00799712 -0.384661 -0.0196135 0.0114971 -0.384343 -0.0235462 0.0114971 -0.381771 -0.0271451 0.0114971 -0.378749 -0.0306402 0.00799712 -0.375554 -0.035785 0.00799712 -0.367604 -0.0354568 0.0114971 -0.367443 -0.039287 0.0114971 -0.353944 -0.0398315 0.00799712 -0.34924 -0.0390859 0.0114971 -0.344564 -0.0385045 0.00799712 -0.339865 -0.0370155 0.00799712 -0.335361 -0.0350017 0.00799712 -0.331067 -0.0318663 0.0144971 -0.327487 -0.0341682 0.0156872 -0.33152 -0.034328 0.0144971 -0.331433 -0.037981 0.0156872 -0.35846 -0.0381588 0.0144971 -0.358499 -0.0367172 0.0156872 -0.362914 -0.0350963 0.0144971 -0.367267 -0.0361385 0.0156872 -0.364464 -0.0349328 0.0156872 -0.367187 -0.0340947 0.0156872 -0.368802 -0.0326532 0.0156872 -0.371217 -0.0299106 0.0156872 -0.374947 -0.0300505 0.0144971 -0.375063 -0.0250155 0.0156872 -0.379866 -0.0233068 0.0144971 -0.381448 -0.0194142 0.0144971 -0.383995 -0.0211601 0.0156872 -0.382718 -0.0193238 0.0156872 -0.383837 -0.0152463 0.0144971 -0.386061 -0.0151754 0.0156872 -0.385893 0.0242982 0.0144971 -0.380664 0.0203961 0.0156872 -0.383182 0.0163941 0.0144971 -0.385539 0.00752714 0.0156872 -0.388233 -0.0063248 0.0144971 -0.38864 -0.0062954 0.0156872 -0.388461 0.0191686 -0.0275029 -0.366203 0.0176474 -0.0275029 -0.367857 -0.00246394 -0.0275029 -0.348037 -0.0191978 -0.0275029 -0.333985 -0.0136392 -0.0275029 -0.371114 -0.0234417 -0.0275029 -0.341225 -0.0154703 -0.0275029 -0.337115 -1.46038e-05 -0.0275029 -0.350094 -0.0248471 -0.0275029 -0.353385 0.00411061 -0.0275029 -0.374802 0.00712091 -0.0275029 -0.374106 -0.0243553 -0.0275029 -0.344177 -0.024253 -0.0275029 -0.356417 -0.0232902 -0.0275029 -0.359353 0.0100227 -0.0275029 -0.373045 0.0127717 -0.0275029 -0.371635 0.0153262 -0.0275029 -0.369897 0.0287258 -0.0182958 -0.375264 0.0283338 -0.0180029 -0.375858 0.0272336 -0.0210029 -0.374934 0.0275751 -0.0221918 -0.373262 0.0278437 -0.02071 -0.374523 0.0288439 -0.0195342 -0.374327 -0.0302626 -0.0210029 -0.32901 -0.02957 -0.0221918 -0.329492 -0.0358423 -0.0210029 -0.341384 -0.0360404 -0.0221918 -0.350395 -0.0323361 -0.0210029 -0.367837 -0.0315961 -0.0221918 -0.367431 -0.0270212 -0.0210029 -0.375196 -0.0237255 -0.0210029 -0.37833 -0.020069 -0.0210029 -0.381034 -0.0231826 -0.0221918 -0.377684 -0.0157391 -0.0221918 -0.382508 -0.011629 -0.0221918 -0.384198 -0.00751402 -0.0210029 -0.386194 -0.00734232 -0.0221918 -0.385368 0.00591839 -0.0221918 -0.385629 0.00605741 -0.0210029 -0.386462 0.0104883 -0.0210029 -0.385438 0.0144212 -0.0221918 -0.383102 0.018375 -0.0221918 -0.381074 0.0188059 -0.0210029 -0.3818 0.0259825 -0.0210029 -0.37624 -0.0297748 -0.0182958 -0.326139 -0.0295443 -0.0186202 -0.326049 -0.0287313 -0.0199077 -0.32598 -0.028901 -0.0203856 -0.326589 -0.0205645 -0.0275029 -0.33577 -0.0236995 -0.0273959 -0.337603 -0.0250572 -0.0273959 -0.340613 -0.0221716 -0.0275029 -0.338408 -0.0248986 -0.0275029 -0.347218 -0.0250634 -0.0275029 -0.350303 -0.0248952 -0.0273959 -0.359992 -0.0219733 -0.0275029 -0.362148 -0.0203223 -0.0275029 -0.36476 -0.0217227 -0.0273959 -0.365771 -0.0183624 -0.0275029 -0.367148 -0.0161233 -0.0275029 -0.369277 -0.0145788 -0.0273959 -0.372564 -0.0109478 -0.0275029 -0.372632 -0.00864701 -0.0273959 -0.375441 -0.00809014 -0.0275029 -0.373806 -0.00510957 -0.0275029 -0.37462 -0.0020515 -0.0275029 -0.375061 0.00103756 -0.0275029 -0.375122 0.00439508 -0.0273959 -0.376505 0.0163841 -0.0273959 -0.371262 0.0296862 -0.0162189 -0.375035 -0.0169831 -0.015693 -0.385073 -0.0125479 -0.015693 -0.386896 -0.0124267 -0.0173824 -0.38654 0.0109527 -0.0173824 -0.387 0.0154127 -0.0173824 -0.385369 0.0198299 -0.015693 -0.383525 0.019638 -0.0173824 -0.383202 0.0235643 -0.0173824 -0.380531 0.0237945 -0.015693 -0.380828 0.0273969 -0.015693 -0.377663 0.0271319 -0.0173824 -0.377396 -0.0209557 -0.0173824 -0.382402 -0.026744 -0.015693 -0.378325 -0.0284905 -0.015693 -0.376562 -0.0282152 -0.0173824 -0.376306 -0.0312276 -0.0173824 -0.372635 -0.0315323 -0.015693 -0.372855 -0.0337652 -0.0173824 -0.368621 -0.0340947 -0.015693 -0.368802 -0.0381822 -0.0173824 -0.355153 -0.0385548 -0.015693 -0.355202 -0.0388905 -0.015693 -0.350419 -0.0385147 -0.0173824 -0.350416 -0.0382614 -0.0173824 -0.345674 -0.0377916 -0.015693 -0.34091 -0.0374263 -0.0173824 -0.340999 -0.0363736 -0.015693 -0.336329 -0.0315999 -0.0173824 -0.328077 -0.0319083 -0.015693 -0.327863 0.0234451 -0.0180029 -0.380377 0.0195386 -0.0180029 -0.383034 0.0108972 -0.0180029 -0.386814 0.00629381 -0.0180029 -0.387878 0.00632587 -0.0173824 -0.38807 0.0015944 -0.0180029 -0.388367 0.00160257 -0.0173824 -0.388561 -0.00314532 -0.0173824 -0.388468 -0.00784559 -0.0173824 -0.387791 -0.012364 -0.0180029 -0.386356 -0.016819 -0.0173824 -0.384735 -0.0167341 -0.0180029 -0.384559 -0.0208498 -0.0180029 -0.382239 -0.0246486 -0.0180029 -0.379429 -0.0247738 -0.0173824 -0.379579 -0.0310698 -0.0180029 -0.372521 -0.0335945 -0.0180029 -0.368528 -0.0356084 -0.0180029 -0.364253 -0.0357893 -0.0173824 -0.364325 -0.0370807 -0.0180029 -0.359764 -0.0372691 -0.0173824 -0.359813 -0.03832 -0.0180029 -0.350414 -0.038068 -0.0180029 -0.345696 -0.0338978 -0.0180029 -0.332224 -0.0360221 -0.0173824 -0.336462 -0.03407 -0.0173824 -0.332133 -0.0294992 -0.0173824 -0.325335 -0.0291921 -0.0210029 -0.327551 -0.0230829 -0.0265513 -0.330723 -0.0210072 -0.0273021 -0.332466 -0.0219816 -0.0273959 -0.334782 -0.0275365 -0.0268006 -0.339675 -0.0286099 -0.0268006 -0.343142 -0.0260338 -0.0273959 -0.343768 -0.0266146 -0.0273959 -0.34702 -0.0292482 -0.0268006 -0.346715 -0.0267907 -0.0273959 -0.350318 -0.0265595 -0.0273959 -0.353612 -0.0291876 -0.0268006 -0.353961 -0.0284897 -0.0268006 -0.357523 -0.0259245 -0.0273959 -0.356853 -0.0273586 -0.0268006 -0.360972 -0.0258115 -0.0268006 -0.364255 -0.0234875 -0.0273959 -0.362979 -0.0238719 -0.0268006 -0.367323 -0.0215694 -0.0268006 -0.370129 -0.0196276 -0.0273959 -0.368324 -0.018939 -0.0268006 -0.37263 -0.0172342 -0.0273959 -0.3706 -0.0160207 -0.0268006 -0.374789 -0.0128589 -0.0268006 -0.376571 -0.0117018 -0.0273959 -0.374186 -0.00546092 -0.0273959 -0.376311 -0.00240754 -0.0268006 -0.379425 -0.00219196 -0.0273959 -0.376782 0.00111012 -0.0273959 -0.376847 0.00836814 -0.0268006 -0.378303 0.00761297 -0.0273959 -0.375762 0.0117771 -0.0268006 -0.377056 0.0150066 -0.0268006 -0.3754 0.0107148 -0.0273959 -0.374627 0.0136534 -0.0273959 -0.37312 0.0207346 -0.0268006 -0.370962 0.0188653 -0.0273959 -0.369082 -0.0241565 -0.0268006 -0.333266 -0.0260445 -0.0268006 -0.336366 -0.0298617 -0.0257044 -0.338795 -0.0310257 -0.0257044 -0.342555 -0.0317179 -0.0257044 -0.34643 -0.0319278 -0.0257044 -0.350361 -0.0294417 -0.0268006 -0.35034 -0.0316522 -0.0257044 -0.354287 -0.0308954 -0.0257044 -0.35815 -0.0296687 -0.0257044 -0.361891 -0.0279909 -0.0257044 -0.365451 -0.0258875 -0.0257044 -0.368779 -0.0205378 -0.0257044 -0.374534 -0.00650581 -0.0257044 -0.381341 -0.00950168 -0.0268006 -0.377951 -0.0026097 -0.0257044 -0.381903 -0.00600014 -0.0268006 -0.378907 0.00122147 -0.0268006 -0.379496 0.0052411 -0.0257044 -0.381573 0.00907634 -0.0257044 -0.380686 0.00483167 -0.0268006 -0.37912 0.0162757 -0.0257044 -0.377538 0.0180077 -0.0268006 -0.373358 0.0224875 -0.0257044 -0.372725 -0.0248294 -0.025416 -0.329256 -0.0261961 -0.0257044 -0.331844 -0.0280235 -0.0241486 -0.33057 -0.030214 -0.0241486 -0.334167 -0.0282436 -0.0257044 -0.335206 -0.031945 -0.0241486 -0.338006 -0.0331902 -0.0241486 -0.342029 -0.0339308 -0.0241486 -0.346174 -0.0341553 -0.0241486 -0.350379 -0.0317385 -0.0241486 -0.362714 -0.0299436 -0.0241486 -0.366523 -0.0276934 -0.0241486 -0.370083 -0.0250221 -0.0241486 -0.373338 -0.0233904 -0.0257044 -0.371822 -0.017373 -0.0257044 -0.376875 -0.0149163 -0.0241486 -0.380812 -0.013944 -0.0257044 -0.378808 -0.0110213 -0.0241486 -0.382413 -0.0103032 -0.0257044 -0.380304 -0.0069589 -0.0241486 -0.383522 0.00141946 -0.0241486 -0.384206 0.0013259 -0.0257044 -0.38198 0.0136659 -0.0241486 -0.381375 0.0127733 -0.0257044 -0.379334 0.0240581 -0.0241486 -0.374305 0.0195303 -0.0257044 -0.375323 -0.0318814 -0.0221918 -0.333288 -0.033708 -0.0221918 -0.337338 -0.035022 -0.0221918 -0.341583 -0.0358034 -0.0221918 -0.345958 -0.0338605 -0.0241486 -0.35458 -0.0357293 -0.0221918 -0.354828 -0.0330508 -0.0241486 -0.358713 -0.0348749 -0.0221918 -0.359188 -0.0334901 -0.0221918 -0.363411 -0.0292216 -0.0221918 -0.371187 -0.0264028 -0.0221918 -0.374622 -0.0219703 -0.0241486 -0.37624 -0.0185846 -0.0241486 -0.378744 -0.0196099 -0.0221918 -0.380326 -0.00294412 -0.0221918 -0.386002 -0.00279083 -0.0241486 -0.384123 0.00149864 -0.0221918 -0.386089 0.0102479 -0.0221918 -0.384628 0.00560794 -0.0241486 -0.38377 0.00971089 -0.0241486 -0.382821 0.022049 -0.0221918 -0.378575 0.0174127 -0.0241486 -0.379453 0.0208945 -0.0241486 -0.377084 0.0253873 -0.0221918 -0.375642 0.0261315 -0.0241486 -0.37205 -0.0311561 -0.00786891 -0.325249 -0.031157 -3.79824e-05 -0.324596 -0.0311499 -0.000502883 -0.324602 -0.0311912 -0.000885566 -0.324666 -0.031519 -0.00142676 -0.325098 -0.0316296 -0.00500288 -0.325505 -0.0313895 -0.005079 -0.325206 -0.0309549 -0.00600288 -0.324765 -0.0305225 -0.00787189 -0.324476 -0.0308972 -0.00700288 -0.324814 -0.0309506 -0.00750288 -0.324944 -0.0317538 -0.00150288 -0.3254 -0.0328078 -0.00150288 -0.326818 -0.0326757 -0.00500288 -0.326912 -0.0353423 -0.00150288 -0.330882 -0.0372252 -0.00500288 -0.335278 -0.0387227 -0.00500288 -0.339807 -0.0398316 -0.00150288 -0.344459 -0.0400572 -0.00500288 -0.349236 -0.0402192 -0.00150288 -0.349232 -0.0400366 -0.00150288 -0.354018 -0.0392863 -0.00150288 -0.358748 -0.039128 -0.00500288 -0.358713 -0.037826 -0.00500288 -0.363302 -0.037979 -0.00150288 -0.363355 -0.0337752 -0.00150288 -0.371943 -0.0309384 -0.00150288 -0.375801 -0.0276629 -0.00150288 -0.379295 -0.0238987 -0.00500288 -0.382245 -0.0199071 -0.00500288 -0.384857 -0.0156966 -0.00150288 -0.387124 -0.0111832 -0.00150288 -0.388726 -0.00651132 -0.00150288 -0.38978 -0.00174735 -0.00150288 -0.39027 -0.00648515 -0.00500288 -0.38962 -0.00174037 -0.00500288 -0.390109 0.0030412 -0.00150288 -0.390192 0.00778641 -0.00150288 -0.389544 0.012421 -0.00150288 -0.388337 0.0123709 -0.00500288 -0.388183 0.0210978 -0.00150288 -0.38432 0.0250169 -0.00150288 -0.381567 0.028581 -0.00150288 -0.378368 0.024916 -0.00500288 -0.381441 0.0284658 -0.00500288 -0.378255 0.0298408 -0.00786891 -0.37647 0.030106 -0.00750288 -0.376215 0.030225 -0.00700288 -0.37614 0.0304933 -0.00787189 -0.375712 0.0302531 -0.0056202 -0.376263 0.0297954 -0.00150288 -0.377085 0.0300528 -0.00142676 -0.376802 0.0302721 -0.00120999 -0.376562 0.030421 -0.000885566 -0.376404 0.0304776 -0.000502883 -0.376352 0.0291751 -0.0144268 -0.376064 0.0297579 -0.015693 -0.375095 0.029414 -0.01421 -0.375841 0.0295919 -0.0138856 -0.375708 0.0296827 -0.0135029 -0.375685 0.0297851 -0.0125029 -0.375771 0.0292182 -0.0115029 -0.3766 0.029467 -0.011579 -0.37631 0.0296614 -0.0117958 -0.376049 -0.0370155 -0.00800288 -0.335361 -0.036676 -0.0115029 -0.335497 -0.0398315 -0.00800288 -0.34924 -0.0394662 -0.0115029 -0.349248 -0.0396506 -0.00800288 -0.35398 -0.039287 -0.0115029 -0.353944 -0.0376129 -0.00800288 -0.363227 -0.0306402 -0.00800288 -0.375554 -0.0271451 -0.0115029 -0.378749 -0.010974 -0.0115029 -0.388002 -0.00638965 -0.0115029 -0.389036 -0.00173064 -0.00800288 -0.389883 -0.0017149 -0.0115029 -0.389518 0.00298397 -0.0115029 -0.389441 0.00771119 -0.00800288 -0.389163 0.00764031 -0.0115029 -0.388805 0.0123011 -0.00800288 -0.387968 0.0167163 -0.00800288 -0.386235 0.0208942 -0.00800288 -0.38399 0.0165628 -0.0115029 -0.385904 0.0207023 -0.0115029 -0.383679 0.0247755 -0.00800288 -0.381264 0.0245481 -0.0115029 -0.380978 -0.0311766 -0.0115029 -0.325885 -0.0314566 -0.00800288 -0.32565 -0.0321936 -0.0115029 -0.327254 -0.0303621 -0.0138856 -0.325363 -0.0307104 -0.0117958 -0.325353 -0.030355 -0.0135029 -0.325269 -0.0304629 -0.01421 -0.325561 -0.030869 -0.0145029 -0.326143 -0.0211601 -0.015693 -0.382718 -0.00792204 -0.015693 -0.388159 -0.00317589 -0.015693 -0.388843 -0.0016976 -0.0145029 -0.389117 0.00161836 -0.015693 -0.388937 0.00756244 -0.0145029 -0.388411 0.00638777 -0.015693 -0.38844 0.012064 -0.0145029 -0.387239 0.0163941 -0.0145029 -0.385539 0.0110598 -0.015693 -0.387361 0.0155633 -0.015693 -0.385714 -0.0231983 -0.015693 -0.381302 -0.0194142 -0.0145029 -0.383995 -0.034328 -0.0145029 -0.331433 -0.0344025 -0.015693 -0.331958 -0.0377635 -0.0145029 -0.340062 -0.0386885 -0.0145029 -0.34462 -0.0386348 -0.015693 -0.34563 -0.0390649 -0.0145029 -0.349257 -0.0376328 -0.015693 -0.359908 -0.0381588 -0.0145029 -0.358499 -0.036889 -0.0145029 -0.362974 -0.0361385 -0.015693 -0.364464 -0.0328059 -0.0145029 -0.371316 -0.0300505 -0.0145029 -0.375063 -0.0250155 -0.015693 -0.379866 -0.0210072 0.0272963 -0.332466 -0.0241443 0.021985 -0.322942 -0.0148523 0.0261969 -0.323794 -0.0132941 0.0266051 -0.32502 0.0288579 0.0265391 -0.357998 0.0354107 0.0122464 -0.36808 0.0375576 0.0105951 -0.364769 0.0369819 0.0158791 -0.364319 0.0365843 0.0177406 -0.364007 0.0341211 0.0193023 -0.367082 0.0347241 0.021933 -0.362557 0.0326815 0.0221357 -0.366024 0.0360155 0.019435 -0.363563 0.0361539 0.0190774 -0.363671 0.0338741 0.0230925 -0.361895 0.0327659 0.0242662 -0.361033 0.0284293 0.026106 -0.362921 0.0277564 0.0267979 -0.357258 0.0246556 0.0269217 -0.35502 0.0258224 0.0269193 -0.355644 0.0180804 0.0269251 -0.350159 0.00167847 0.0268306 -0.336751 -0.0226937 0.0238245 -0.32393 -0.023467 0.0229543 -0.323418 -0.0218324 0.0190856 -0.318346 -0.0260557 0.0172214 -0.32147 -0.026929 0.0101342 -0.320781 -0.0235223 0.00850384 -0.317039 -0.0272696 0.00530688 -0.320526 0.0291827 0.0264338 -0.358261 0.0257195 0.0270747 -0.360903 0.0226345 0.0272304 -0.35856 0.0160193 0.027232 -0.353465 0.00423978 0.0269235 -0.339759 0.00202495 0.0272313 -0.34257 0.0287021 0.0199019 -0.374208 0.026092 0.0262548 -0.366477 0.0244256 0.0256986 -0.370617 0.0234421 0.0272507 -0.364376 0.0191686 0.0274971 -0.366203 0.0137947 0.0274281 -0.356642 0.031593 0.0194697 -0.370809 0.0335771 -2.88296e-06 -0.372418 0.0308091 -2.88296e-06 -0.375978 0.0332172 0.00841962 -0.372125 0.0328769 0.0124049 -0.371845 0.0297579 0.0156872 -0.375095 0.0324489 0.016147 -0.371495 -0.0239284 -2.88296e-06 -0.316726 -0.0265332 0.0140504 -0.321086 -0.0252496 0.019797 -0.32211 -0.0276043 0.022186 -0.326926 -0.0225509 0.0267948 -0.33117 -0.0168135 0.0270353 -0.327981 -0.0190311 0.0263259 -0.326385 -0.0159673 0.0257482 -0.322922 -0.0209645 0.0252471 -0.325061 -0.0173224 0.0250156 -0.321867 -0.0244548 0.0256986 -0.329571 0.0346981 -2.88296e-06 -0.37081 0.0357476 0.00830739 -0.36835 0.0349874 0.0159599 -0.367742 0.0301985 0.0222807 -0.369708 0.0307616 0.0244257 -0.364629 0.028349 0.0245619 -0.368254 0.0271213 0.0266885 -0.361952 0.024817 0.0268499 -0.365468 0.0203903 0.0274277 -0.361939 -0.000213737 0.0274279 -0.345329 -0.0111245 0.0272305 -0.332319 -0.014111 0.0272287 -0.330021 -0.0183951 0.0274971 -0.334659 0.026092 -0.0262606 -0.366477 -0.0228844 -0.0148578 -0.317534 -0.0231558 -0.012464 -0.317324 -0.0252496 -0.0198028 -0.32211 -0.0241443 -0.0219907 -0.322942 -0.0226937 -0.0238303 -0.32393 -0.0187972 -0.0239431 -0.320724 -0.0111245 -0.0272363 -0.332319 -0.0110146 -0.0267776 -0.326817 0.0284293 -0.0261117 -0.362921 0.0271213 -0.0266943 -0.361952 0.0326815 -0.0221415 -0.366024 0.0347241 -0.0219388 -0.362557 0.0307616 -0.0244315 -0.364629 0.0334897 -0.0235424 -0.361596 0.0361866 -0.0189946 -0.363697 0.0341211 -0.019308 -0.367082 0.0349874 -0.0159656 -0.367742 0.0370071 -0.015719 -0.364339 0.0377573 -0.00810702 -0.364926 0.00423978 -0.0269293 -0.339759 0.0160193 -0.0272378 -0.353465 0.0226345 -0.0272362 -0.35856 0.0291827 -0.0264395 -0.358261 0.029307 -0.0263966 -0.358347 0.0137947 -0.0274339 -0.356642 0.0244256 -0.0257044 -0.370617 0.0225216 -0.0268006 -0.369018 0.024817 -0.0268556 -0.365468 0.0204914 -0.0273959 -0.367314 0.0234421 -0.0272564 -0.364376 0.0203903 -0.0274335 -0.361939 0.0301985 -0.0222865 -0.369708 0.0256902 -0.0246149 -0.371679 0.0287021 -0.0199077 -0.374208 0.0324489 -0.0161528 -0.371495 0.02947 -0.0173824 -0.374853 0.031593 -0.0194754 -0.370809 -0.0274699 -2.88296e-06 -0.320413 -0.0209645 -0.0252529 -0.325061 -0.0177739 -0.024727 -0.321517 -0.0190311 -0.0263316 -0.326385 -0.0205206 -0.0273959 -0.332874 -0.014111 -0.0272345 -0.330021 -0.0156151 -0.0259102 -0.323197 -0.0244548 -0.0257044 -0.329571 -0.0225509 -0.0268006 -0.33117 -0.0168135 -0.0270411 -0.327981 -0.0183951 -0.0275029 -0.334659 -0.0261607 -0.0241486 -0.328138 -0.0276043 -0.0221918 -0.326926 -0.023467 -0.02296 -0.323418 -0.0297871 -0.015693 -0.325093 -0.0260557 -0.0172272 -0.32147 -0.0265332 -0.0140561 -0.321086 -0.026929 -0.01014 -0.320781 -0.0272696 -0.00531265 -0.320526 -0.0237545 -0.0050042 -0.31686 0.0332172 -0.00842538 -0.372125 0.0328769 -0.0124106 -0.371845 0.0357476 -0.00831315 -0.36835 0.0354107 -0.0122521 -0.36808 0.028349 -0.0245676 -0.368254 0.0257195 -0.0270805 -0.360903 -0.000213737 -0.0274337 -0.345329 0.00202495 -0.0272371 -0.34257 0.0277564 -0.0268037 -0.357258 0.0255838 -0.0269204 -0.355457 0.0246556 -0.0269275 -0.35502 0.0180804 -0.0269309 -0.350159 0.0143369 -0.0268902 -0.346657 0.0366093 0.0176529 -0.363565 -0.0233874 0.0033541 -0.31666 0.0321738 0.0247748 -0.360573 0.0308816 0.0256588 -0.359569 0.0295102 0.0263153 -0.358504 0.0296286 0.0262341 -0.358313 0.0289812 0.0264574 -0.357809 0.0275253 0.0267708 -0.356676 0.027391 0.0268524 -0.356861 0.0171289 0.0268852 -0.34884 0.0150622 0.0268856 -0.347224 0.0152035 0.0268041 -0.347043 -0.0115682 0.0266787 -0.3261 -0.011706 0.0267643 -0.326275 -0.0131501 0.0265177 -0.324856 -0.0158106 0.025664 -0.322771 -0.0185501 0.0241443 -0.320915 -0.0191257 0.0236387 -0.320469 -0.0198547 0.0225364 -0.319619 -0.0200408 0.0225951 -0.319755 -0.0208381 0.0213183 -0.319128 -0.0210797 0.0208512 -0.318938 -0.0208863 0.0208048 -0.31881 -0.0216351 0.0190486 -0.318223 -0.022419 0.0171962 -0.317888 -0.0227313 0.0157965 -0.317649 -0.0230302 0.0136136 -0.317422 -0.0238316 0.00336771 -0.3168 -0.0236268 0.00336336 -0.316675 -0.0234836 -8.26595e-06 -0.316585 -0.0231686 0.00334207 -0.316758 -0.0228625 0.0084547 -0.316997 -0.0230799 0.0084777 -0.3169 -0.0225893 0.0135766 -0.317283 -0.0220847 0.015684 -0.317605 -0.0214128 0.0189735 -0.318201 -0.0204841 0.0205871 -0.318857 -0.0202504 0.0210373 -0.319039 -0.0204343 0.0211679 -0.318967 -0.0194872 0.0222576 -0.319636 -0.0196552 0.0224147 -0.319576 -0.0186236 0.0232432 -0.320311 -0.0187677 0.0234271 -0.32027 -0.0170023 0.0247765 -0.321649 -0.0168893 0.0245722 -0.321667 -0.015575 0.0252844 -0.322695 -0.0156696 0.0254973 -0.32269 -0.0145717 0.0259392 -0.323548 -0.0114695 0.0264998 -0.325977 0.00191794 0.0265678 -0.336446 0.0153412 0.0263878 -0.346868 0.0174072 0.0263874 -0.348483 0.0173709 0.0266236 -0.34853 0.0276115 0.0265917 -0.356537 0.02904 0.0260559 -0.357579 0.0327996 0.0238661 -0.360518 0.0338656 0.0227356 -0.361352 0.0328714 0.0240509 -0.360644 0.0339558 0.0228999 -0.361492 0.0349128 0.0215667 -0.362239 0.0352143 0.0207274 -0.362406 0.0359268 0.0192112 -0.362963 -0.023318 0.00849543 -0.316915 -0.022296 0.0157363 -0.317511 -0.0228263 0.0136017 -0.317298 -0.0225289 0.0157768 -0.317527 -0.0222186 0.017169 -0.317767 -0.0219901 0.0171135 -0.31775 -0.0206717 0.0207097 -0.318781 -0.020646 0.0212691 -0.318999 -0.0189486 0.0235696 -0.320327 -0.0182063 0.0239208 -0.320708 -0.0183777 0.0240709 -0.320771 -0.017158 0.0249359 -0.32172 -0.0147013 0.0261105 -0.323639 -0.0130359 0.0263416 -0.32475 0.00181824 0.0267475 -0.336573 0.0153046 0.026624 -0.346914 0.0172702 0.0268038 -0.348659 0.0260707 0.0266588 -0.355333 0.0259662 0.0268393 -0.355462 0.029047 0.0262829 -0.357657 0.0296853 0.0260627 -0.358156 0.0310275 0.0254176 -0.359204 0.032292 0.0245499 -0.360192 0.0309895 0.0255801 -0.359373 0.0322718 0.0247006 -0.360372 0.0328593 0.0241949 -0.36083 0.0339588 0.0230282 -0.361687 0.0353276 0.0208561 -0.362564 0.0352758 0.021008 -0.362987 0.0353497 0.0209569 -0.362772 0.034852 0.0217328 -0.362657 0.0349291 0.021677 -0.362444 0.036084 0.0193941 -0.363345 0.0368584 0.0157825 -0.363692 0.0369996 0.0158267 -0.363871 0.0370936 0.013874 -0.363876 0.0374291 0.0105399 -0.364138 0.0377998 0.00527641 -0.364428 0.0379442 0.00529134 -0.364609 0.0379781 -1.2529e-05 -0.364567 0.037044 0.0158614 -0.364096 0.0372366 0.0139058 -0.364056 0.037511 0.0117459 -0.364461 0.037465 0.0117243 -0.364235 0.0375727 0.0105652 -0.364319 0.0376189 0.010585 -0.364546 0.0364745 0.0175788 -0.363392 0.0360521 0.0193137 -0.36313 0.0366487 0.017711 -0.363787 0.0372206 0.0139433 -0.364506 0.0372822 0.0139307 -0.364282 0.0374496 0.011757 -0.364685 0.0379909 0.00530305 -0.364836 0.0379298 0.005309 -0.365061 0.0381088 -2.88296e-06 -0.365201 -0.0232641 -1.30303e-05 -0.316683 0.0372004 -0.0146547 -0.364219 0.0380045 -0.00371189 -0.365119 0.0381699 -4.64331e-06 -0.364977 0.0362538 -0.0189566 -0.363478 0.0367944 -0.0168888 -0.364172 0.0371387 -0.0146678 -0.364442 0.0345942 -0.0221343 -0.362456 0.0353875 -0.0208928 -0.362802 0.0353138 -0.0209435 -0.363016 0.0294183 -0.0263559 -0.358433 0.0307079 -0.0257626 -0.359434 0.0317753 -0.025084 -0.360263 0.0328101 -0.024231 -0.361068 0.0335775 -0.0234754 -0.36139 0.0380187 -0.003698 -0.364668 0.037772 -0.00808288 -0.364475 0.0371549 -0.0146289 -0.363992 0.0368154 -0.0168176 -0.363726 0.035251 -0.0206655 -0.362435 0.0362196 -0.0188821 -0.363261 0.0353649 -0.0207929 -0.362593 0.0346605 -0.0219605 -0.362042 0.0318466 -0.0246543 -0.359773 0.031902 -0.0248535 -0.359887 0.0308575 -0.0255196 -0.359071 0.0277396 -0.0263483 -0.356562 0.0258713 -0.0264222 -0.355101 0.0220827 -0.0266237 -0.352214 0.0145794 -0.0266286 -0.346347 -0.000390494 -0.0263315 -0.334567 -0.0107416 -0.0262814 -0.326474 -0.0130623 -0.0263425 -0.32473 -0.0153229 -0.0256569 -0.322961 -0.0183108 -0.0235344 -0.320556 -0.0193619 -0.022797 -0.319806 -0.0192019 -0.0226297 -0.319859 -0.0202424 -0.0215156 -0.319117 -0.0222305 -0.0147739 -0.317491 -0.0227148 -0.0124288 -0.317185 -0.0228009 -0.00921956 -0.317045 -0.0237235 -4.59957e-06 -0.3166 0.038123 -8.10979e-06 -0.364749 0.0378741 -0.00368626 -0.364486 0.0380655 -0.00370721 -0.364895 0.0378184 -0.00809888 -0.364702 0.0368575 -0.0168647 -0.36395 0.0335797 -0.0233411 -0.361198 0.0346734 -0.0220761 -0.362244 0.0318763 -0.0250083 -0.360064 0.0308172 -0.0256835 -0.359239 0.0295953 -0.0261027 -0.358086 0.0277238 -0.0265822 -0.356624 0.0258315 -0.0266598 -0.355146 0.0276393 -0.0267611 -0.356765 0.0144783 -0.0268087 -0.346476 -0.000426749 -0.0265654 -0.334613 -0.000526154 -0.026745 -0.334739 -0.0107782 -0.0265133 -0.326518 -0.0131768 -0.0265186 -0.324835 -0.0174457 -0.0244928 -0.321302 -0.0176068 -0.0246494 -0.321371 -0.0184477 -0.0237242 -0.32052 -0.0195553 -0.0229266 -0.319853 -0.0204516 -0.0216217 -0.319151 -0.0213473 -0.0191557 -0.318252 -0.0221195 -0.016591 -0.317649 -0.0223496 -0.016641 -0.317665 -0.0224451 -0.0148131 -0.317395 -0.023256 -0.00926307 -0.316963 -0.0230181 -0.00924412 -0.316948 -0.0233109 -0.00498644 -0.316719 -0.0235499 -0.00499851 -0.316735 -0.0234602 -0.00927207 -0.317087 -0.0229518 -0.0124526 -0.3172 -0.0226809 -0.0148433 -0.317411 -0.0225508 -0.0166655 -0.317786 -0.0215689 -0.0192327 -0.318275 -0.0217659 -0.0192706 -0.318398 -0.0206424 -0.0216732 -0.319282 -0.0197385 -0.0229891 -0.319991 -0.0186229 -0.0238714 -0.32058 -0.0154602 -0.0258251 -0.323045 -0.0133209 -0.0266059 -0.324999 -0.0108766 -0.0266923 -0.326642 -0.000665607 -0.0268284 -0.334917 0.0218398 -0.0268851 -0.352524 0.0219814 -0.0268039 -0.352343 0.0257274 -0.0268403 -0.355275 0.0275058 -0.0268428 -0.35695 0.0277984 -0.0267966 -0.357177 0.0295373 -0.0262746 -0.358242 0.0291866 -0.0264389 -0.358253 0.0366771 -0.0167576 -0.36355 0.0360914 -0.0187871 -0.363092 -0.0180743 0.0237275 -0.320741 0.0363439 -0.0144408 -0.363289 0.037012 -0.014596 -0.363812 0.0376279 -0.00806248 -0.364293 0.0371885 -0.00382746 -0.36395 0.0372992 -2.88307e-06 -0.364036 -0.0200618 -0.0213787 -0.319187 -0.0194332 -0.0210129 -0.319678 0.035816 0.017358 -0.362877 0.0348064 0.0214258 -0.362087 0.0342076 0.0209971 -0.361619 0.0332857 0.0222472 -0.360898 0.03223 0.0243561 -0.360073 0.0309868 0.0252078 -0.359101 0.0368064 0.00984456 -0.363651 0.0373216 0.0116966 -0.364054 0.0345035 -0.0205159 -0.36185 0.0345584 -0.0218128 -0.361893 0.0336318 -0.0218242 -0.361169 0.0334959 -0.0231691 -0.361063 0.032771 -0.0228176 -0.360496 0.0316707 -0.0237902 -0.359636 0.0308197 -0.025308 -0.35897 0.0295789 -0.0258797 -0.358 0.0294406 -0.0250386 -0.357892 0.0281096 -0.0254235 -0.356851 0.0267094 -0.0255778 -0.355756 0.0221195 -0.0263873 -0.352168 -0.0130025 -0.0261165 -0.324706 -0.0152328 -0.025442 -0.322962 -0.0148581 -0.0246916 -0.323255 -0.0173262 -0.0242919 -0.321326 -0.0178316 -0.0229096 -0.320931 -0.0202541 -0.0193954 -0.319036 -0.0211504 -0.0190567 -0.318336 -0.0219116 -0.0165267 -0.31774 -0.0210308 -0.0171902 -0.318429 -0.0214541 -0.0153422 -0.318098 -0.0224987 -0.0123979 -0.317281 0.0296674 0.0258404 -0.358069 0.0278984 0.0254569 -0.356686 0.0276292 0.0263574 -0.356476 0.0261107 0.0264211 -0.355288 0.0146161 -0.0263925 -0.346301 0.00744779 -0.0255077 -0.340696 -0.0123684 -0.0253494 -0.325202 -0.0138529 -0.025041 -0.324041 -0.0217115 -0.0133727 -0.317897 -0.0219392 -0.0112167 -0.317719 -0.0230925 -0.00497076 -0.316817 -0.0220838 -0.00966769 -0.317606 -0.0224401 -0.00451798 -0.317327 -0.0225899 -2.88307e-06 -0.31721 -0.0223733 0.0135442 -0.317379 -0.0217843 0.0170421 -0.31784 -0.0211508 0.0167383 -0.318335 -0.0212151 0.018877 -0.318285 -0.0206007 0.0185172 -0.318765 -0.0202461 0.0194082 -0.319043 -0.0196285 0.0206696 -0.319526 -0.0186992 0.022047 -0.320252 -0.0165132 0.023848 -0.321961 -0.0151024 0.0245832 -0.323064 -0.0144917 0.0257202 -0.323542 -0.0129765 0.0261154 -0.324727 -0.0124635 0.0253311 -0.325128 -0.0108219 0.0254182 -0.326411 -0.0114325 0.0262683 -0.325934 0.00195435 0.0263335 -0.336401 0.0154961 0.0255341 -0.346989 0.00759999 0.0255027 -0.340815 0.00400899 0.0254864 -0.338007 -0.0224456 -2.88299e-06 -0.317817 -0.0222514 0.00445439 -0.317688 -0.0224772 -2.88307e-06 -0.317334 -0.0223078 0.00446508 -0.317486 -0.0225729 -2.88307e-06 -0.317224 0.0365496 0.00453674 -0.363917 0.0360612 0.00979195 -0.363808 0.0350904 0.0171937 -0.36305 0.0347119 0.018712 -0.36248 0.0345717 0.018707 -0.362644 0.0344282 0.0193532 -0.362258 0.0342883 0.0193475 -0.362421 0.0336877 0.0206935 -0.361677 0.0319106 0.022685 -0.360552 0.0308295 0.023571 -0.359701 0.0289199 0.0246481 -0.35793 0.0261603 0.0250763 -0.356016 0.0152856 0.0250597 -0.347259 0.015159 0.0250364 -0.347421 0.00726202 0.0250053 -0.341251 0.00379697 0.0250106 -0.338281 0.0036695 0.0249892 -0.338444 -0.0127739 0.0248392 -0.325611 -0.0137954 0.0246212 -0.324548 -0.0165722 0.0234149 -0.322376 -0.0205995 0.0183087 -0.319492 -0.0201357 0.0191777 -0.319584 -0.0196595 0.0203837 -0.320222 -0.0190053 0.0214035 -0.320731 -0.01954 0.0203932 -0.320047 -0.0188853 0.0214152 -0.320558 -0.0187815 0.0216845 -0.320906 -0.018434 0.0220619 -0.321179 -0.0177841 0.0225537 -0.321422 -0.0179076 0.0225405 -0.321594 -0.0166992 0.0234031 -0.322548 0.0371551 0.00456581 -0.363924 0.0360828 0.01499 -0.363144 0.036275 0.015022 -0.363236 0.0361805 0.0156896 -0.363162 0.035631 0.0172879 -0.362791 0.035275 0.0189352 -0.362454 0.0349795 0.0196023 -0.362223 0.0324976 0.023081 -0.360282 0.0313688 0.0240046 -0.3594 0.0301363 0.024731 -0.358436 0.0312622 0.023823 -0.359373 0.0300508 0.0245386 -0.358425 0.0292366 0.0251078 -0.357732 0.0264943 0.0255744 -0.355588 0.0264685 0.0253732 -0.355622 -0.0136493 0.025092 -0.324201 -0.0150774 0.0243848 -0.323143 -0.0164699 0.0236598 -0.322053 -0.0177697 0.0229554 -0.320979 -0.0177083 0.0227817 -0.321084 -0.0188491 0.021603 -0.320192 -0.0189393 0.0217455 -0.320064 -0.0201304 0.0193085 -0.31919 -0.021533 0.0148489 -0.318036 -0.0218637 0.0119551 -0.317778 -0.0220683 0.00821091 -0.317674 -0.0222021 0.008231 -0.317513 -0.0224418 0.00447804 -0.317326 -0.0216751 0.0119061 -0.31814 -0.0217303 0.0119282 -0.317938 -0.0213469 0.0147794 -0.318398 -0.0214007 0.0148108 -0.318196 -0.021023 0.016674 -0.318493 -0.0204801 0.0184296 -0.318917 -0.0200913 0.0192267 -0.319382 -0.019523 0.0205502 -0.319665 -0.0186022 0.0217719 -0.320544 -0.0186158 0.021896 -0.320374 -0.0164908 0.0235061 -0.322201 -0.0136436 0.0248873 -0.324263 -0.012538 0.0249553 -0.325289 -0.0124738 0.0251245 -0.325177 -0.0108479 0.0252125 -0.326447 0.00390781 0.0251145 -0.338139 0.00398282 0.0252828 -0.338042 0.0074995 0.0251315 -0.340946 0.0153954 0.0251641 -0.347118 0.00757407 0.0252996 -0.34085 0.0154698 0.0253318 -0.347023 0.0263949 0.025206 -0.355716 0.0278503 0.0252554 -0.356703 0.0290541 0.0247475 -0.357803 0.0291663 0.0249103 -0.357733 0.0323713 0.022914 -0.360241 0.0331454 0.022094 -0.360847 0.0338662 0.020757 -0.361576 0.0340509 0.0208649 -0.361555 0.0348092 0.0194937 -0.362148 0.0348994 0.0187585 -0.362385 0.0350995 0.0188378 -0.362375 0.0354231 0.0172308 -0.362795 0.0359895 0.0156471 -0.363071 0.0357769 0.0156125 -0.363071 0.036613 0.00982211 -0.363559 0.0369611 0.00455313 -0.363831 0.036746 0.0045428 -0.363828 -0.0224005 -2.88303e-06 -0.317656 -0.0222825 0.00444786 -0.317895 -0.0220124 0.00819437 -0.317876 -0.0217077 0.0118927 -0.318347 -0.0210127 0.0165898 -0.318899 -0.0209741 0.0166213 -0.318693 -0.0204794 0.018315 -0.319317 -0.020437 0.0183579 -0.319113 -0.0194916 0.0204522 -0.31985 -0.01883 0.021486 -0.320366 -0.0186609 0.021697 -0.320733 -0.0177134 0.0226392 -0.321241 -0.0152049 0.0241276 -0.323449 -0.0151137 0.0242229 -0.323279 -0.0136955 0.0247201 -0.324387 -0.0126444 0.024854 -0.325443 -0.0109238 0.0250432 -0.326546 -0.0110361 0.0249404 -0.326692 0.00738913 0.0250274 -0.341088 0.026286 0.0251011 -0.355856 0.0276355 0.0249857 -0.356919 0.0277573 0.0250888 -0.356786 0.0299257 0.0243804 -0.358487 0.0297833 0.0242845 -0.358609 0.0311193 0.0236741 -0.359423 0.0309659 0.0235847 -0.359539 0.0320484 0.0226962 -0.36039 0.0322118 0.0227775 -0.360279 0.0328039 0.0218946 -0.360983 0.0329743 0.0219688 -0.360877 0.0346133 0.0194052 -0.362161 0.035231 0.0171973 -0.362887 0.035582 0.0155922 -0.36316 0.0356735 0.0149487 -0.363231 0.035869 0.014964 -0.363143 0.0362023 0.00979312 -0.363645 0.0363984 0.00980383 -0.363557 -0.0220442 0.00818428 -0.318083 -0.0217184 0.012866 -0.318605 -0.021381 0.0147604 -0.318605 -0.0214971 0.0147572 -0.318782 -0.0213089 0.0158237 -0.318934 -0.0223989 -2.88304e-06 -0.317572 -0.0224114 -2.88306e-06 -0.317488 0.036656 -2.883e-06 -0.364059 0.0368898 -2.88305e-06 -0.363941 0.0371281 -2.88307e-06 -0.363949 0.0369612 -2.88306e-06 -0.363931 0.0362626 -0.00906352 -0.363692 0.0356008 -0.0143691 -0.363448 0.0357419 -0.0143707 -0.363285 0.0352351 -0.0166352 -0.363163 0.034911 -0.018203 -0.362636 0.0346592 -0.0188442 -0.362439 0.0339714 -0.0202313 -0.3619 0.0331357 -0.0214883 -0.361244 0.0321725 -0.0224325 -0.360758 0.0311187 -0.0233655 -0.359929 0.0299591 -0.0241146 -0.359015 0.0300941 -0.0241303 -0.358854 0.0291156 -0.0245814 -0.358084 0.0277081 -0.0249323 -0.357239 0.0278382 -0.0249535 -0.357078 0.0275239 -0.0249667 -0.357094 0.0263667 -0.0250799 -0.35618 0.022198 -0.0250369 -0.352923 0.0150068 -0.025042 -0.347302 0.00723688 -0.0250324 -0.340969 0.00710975 -0.0250103 -0.341132 0.000214685 -0.0249824 -0.335745 -0.00805837 -0.0249518 -0.329282 -0.0110261 -0.0249293 -0.326965 -0.0108971 -0.0249476 -0.3268 -0.0141225 -0.0245596 -0.324565 -0.0150971 -0.0242215 -0.323805 -0.0139929 -0.0245719 -0.324394 -0.0149679 -0.0242329 -0.323634 -0.0177589 -0.0226672 -0.321711 -0.0176349 -0.0226803 -0.321539 -0.0178431 -0.0225101 -0.321375 -0.0193528 -0.0207222 -0.320193 -0.0194722 -0.0207121 -0.320367 -0.0195758 -0.0205368 -0.320287 -0.0194563 -0.0205466 -0.320113 -0.0196554 -0.0203968 -0.320225 -0.0207193 -0.0176192 -0.319129 -0.0206192 -0.0182604 -0.319477 -0.0208393 -0.0176137 -0.319305 -0.021016 -0.0170236 -0.319167 -0.0208964 -0.0170286 -0.318991 -0.0214224 -0.0152344 -0.318843 -0.021556 -0.013306 -0.318466 -0.022041 -0.00961272 -0.318352 -0.0223939 -0.00448639 -0.318073 -0.0219267 -0.00961478 -0.318175 -0.0222808 -0.00448763 -0.317896 -0.0218945 -0.00962619 -0.317968 -0.0217828 -0.0111572 -0.318288 -0.0213052 -0.015238 -0.318667 -0.0212699 -0.0152603 -0.318459 -0.0208568 -0.0170629 -0.318785 -0.0206785 -0.0176574 -0.318924 -0.0200991 -0.0192143 -0.319376 -0.0194072 -0.020607 -0.319916 -0.0201435 -0.0191655 -0.319578 -0.0193028 -0.0207843 -0.319997 -0.0186506 -0.0217149 -0.320741 -0.0177731 -0.0225952 -0.321194 -0.0175626 -0.0227668 -0.321359 -0.0163504 -0.0235532 -0.322551 -0.0138942 -0.0246703 -0.324232 -0.0124452 -0.0249734 -0.325361 -0.0125521 -0.0248721 -0.325514 -0.0107848 -0.0250505 -0.326655 0.000453694 -0.025107 -0.335439 0.000342456 -0.0250033 -0.335581 0.00734727 -0.0251364 -0.340827 0.0151334 -0.0250653 -0.34714 0.0152433 -0.0251697 -0.346999 0.0224339 -0.0251649 -0.352621 0.0223244 -0.0250604 -0.352762 0.0266039 -0.0252089 -0.35588 0.0264931 -0.0251042 -0.356019 0.0292517 -0.0246801 -0.357958 0.0302394 -0.0242247 -0.358733 0.0314116 -0.0234659 -0.359652 0.0312555 -0.0233785 -0.359767 0.0324764 -0.0225221 -0.360487 0.0323105 -0.0224431 -0.360596 0.0353758 -0.0166383 -0.363 0.0356744 -0.0149466 -0.363232 0.0359376 -0.0143853 -0.363196 0.0367794 -0.00380698 -0.363855 0.036583 -0.00380159 -0.363943 0.0367977 -2.88303e-06 -0.363969 -0.0223061 -0.00450495 -0.317488 -0.0222497 -0.0044942 -0.317689 -0.0217503 -0.01117 -0.318081 -0.0215233 -0.0133204 -0.318259 -0.0213227 -0.0152972 -0.318258 -0.0209045 -0.0171202 -0.318585 -0.0201384 -0.0192959 -0.319184 -0.0194374 -0.0207072 -0.319732 -0.018605 -0.0219145 -0.320382 -0.0185917 -0.0217901 -0.320553 -0.0175553 -0.0229111 -0.321204 -0.0162437 -0.0238004 -0.32223 -0.0162672 -0.0236451 -0.322376 -0.0148752 -0.0243289 -0.323466 -0.0138445 -0.0248369 -0.324106 -0.01238 -0.0251428 -0.32525 -0.0107089 -0.0252197 -0.326556 0.00742186 -0.0253045 -0.340731 0.028058 -0.0252224 -0.356866 0.027962 -0.0250561 -0.356946 0.0303691 -0.0243809 -0.358674 0.0315589 -0.0236119 -0.359605 0.0333092 -0.0215588 -0.361139 0.0341525 -0.0202908 -0.3618 0.0348463 -0.0188918 -0.362343 0.0351003 -0.0182451 -0.362542 0.035779 -0.0167159 -0.362907 0.0360837 -0.0149877 -0.363145 0.0355691 -0.016667 -0.362909 0.03587 -0.0149618 -0.363143 0.0364587 -0.00907358 -0.363604 0.0369945 -0.00381618 -0.363857 0.0372812 -2.88307e-06 -0.364023 0.0366734 -0.00909074 -0.363606 0.0368669 -0.00911182 -0.363698 0.0361514 -0.0144102 -0.363198 0.036276 -0.0150195 -0.363236 0.0353034 -0.0183169 -0.362535 0.0359666 -0.016776 -0.362994 0.0354825 -0.0184051 -0.362616 0.0350456 -0.0189729 -0.362333 0.0352201 -0.0190725 -0.362411 0.0343415 -0.0203918 -0.361782 0.0334853 -0.0216781 -0.361113 0.0326399 -0.022655 -0.360451 0.0304601 -0.0245709 -0.358689 0.0293668 -0.024842 -0.35789 0.0266803 -0.0253763 -0.355788 0.0225079 -0.0253326 -0.352526 0.0225338 -0.0255347 -0.352492 0.0153438 -0.0255397 -0.34687 0.0153177 -0.0253374 -0.346904 0.000529048 -0.0252754 -0.335342 0.000555407 -0.0254794 -0.335307 -0.0106829 -0.0254254 -0.32652 -0.0148362 -0.0244918 -0.323331 -0.0162841 -0.0239906 -0.32214 -0.017769 -0.0227369 -0.321037 -0.017614 -0.0230871 -0.321101 -0.0186881 -0.0220659 -0.320261 -0.0193313 -0.0208874 -0.319815 -0.0195413 -0.0208294 -0.319594 -0.0207242 -0.0177212 -0.318726 -0.0208482 -0.0177992 -0.318572 -0.0215784 -0.013344 -0.318057 -0.0218057 -0.0111911 -0.317879 -0.0219502 -0.00964493 -0.317766 0.00466241 0.0249933 -0.339221 -0.00907243 0.0251569 -0.330888 -0.0223956 0.00444662 -0.318071 -0.0225417 -2.88296e-06 -0.317955 -0.0238713 -2.88296e-06 -0.319314 -0.0226524 -2.88296e-06 -0.318067 -0.0238545 0.000872415 -0.319327 -0.0221582 0.00818243 -0.318259 -0.0218225 0.0118903 -0.318524 -0.0228228 0.0148826 -0.320126 -0.021132 0.0165851 -0.319075 -0.0224497 0.0167572 -0.320409 -0.0202556 0.0191703 -0.31976 -0.0208775 0.0206854 -0.321644 -0.0207136 0.020956 -0.321773 -0.0199534 0.0219856 -0.322369 -0.0190046 0.0228845 -0.323105 -0.0182669 0.0234338 -0.323677 -0.0169266 0.0232593 -0.322369 -0.0153339 0.0241163 -0.32362 -0.0161383 0.0245515 -0.325337 -0.0153165 0.0248221 -0.325983 -0.013925 0.0246087 -0.324718 -0.0138781 0.0250955 -0.327118 -0.0111651 0.0249221 -0.326857 -0.0108169 0.0251504 -0.329522 0.0184881 0.0252015 -0.352449 0.0249365 0.025229 -0.357497 0.0275059 0.0249641 -0.35708 0.0287872 0.0246295 -0.358091 0.0296489 0.024268 -0.358771 0.0284859 0.0245097 -0.36025 0.0297311 0.0238112 -0.361217 0.0308866 0.0228917 -0.362116 0.0326653 0.0218852 -0.361146 0.0312513 0.0225346 -0.362399 0.0335484 0.020686 -0.36184 0.0330752 0.0200196 -0.363819 0.0333203 0.0195394 -0.36401 0.035441 0.01559 -0.363323 0.0355324 0.014947 -0.363394 0.0364451 -2.88296e-06 -0.364387 0.0364085 0.00453607 -0.364079 0.0350734 0.0106607 -0.365381 0.0348232 0.013171 -0.365185 0.0365521 -2.88296e-06 -0.364191 0.0364418 -0.003801 -0.364105 0.0354921 -0.00460174 -0.365709 0.0361215 -0.00906242 -0.363855 0.0358768 -0.0118071 -0.363664 0.0351457 -0.00984174 -0.365437 0.0347322 -0.0139942 -0.365114 0.0355333 -0.0149449 -0.363395 0.0338318 -0.0202245 -0.362063 0.0336033 -0.0189188 -0.364231 0.034519 -0.018839 -0.362602 0.0347707 -0.0181985 -0.3628 0.0316864 -0.0220633 -0.362738 0.0329969 -0.0214796 -0.361407 0.0259819 -0.0251982 -0.358308 0.0289825 -0.0245634 -0.358245 0.0290415 -0.024237 -0.360681 0.0299756 -0.0236464 -0.361407 0.00617504 -0.0251949 -0.342818 -0.0134251 -0.0251349 -0.327477 -0.0126815 -0.0248569 -0.325682 -0.0148826 -0.0249368 -0.326325 -0.0163004 -0.0244938 -0.32521 -0.0164778 -0.0235415 -0.322722 -0.0179664 -0.0224969 -0.321547 -0.0187712 -0.0217025 -0.320914 -0.0190746 -0.0213153 -0.320677 -0.0211533 -0.0201933 -0.321426 -0.0204012 -0.021429 -0.322019 -0.0218975 -0.0111549 -0.318465 -0.0216708 -0.0133035 -0.318642 -0.0225847 -0.0162011 -0.320306 -0.0213089 -0.0158294 -0.318934 -0.0220142 -0.0181989 -0.320749 -0.0218828 -0.018559 -0.320852 -0.0202634 -0.0191581 -0.319754 -0.0235119 -0.00794676 -0.319592 -0.0237989 -0.00277701 -0.31937 -0.0240111 -2.88296e-06 -0.319697 -0.0238202 -2.88296e-06 -0.320056 0.0352986 -2.88296e-06 -0.366062 0.035385 -2.88296e-06 -0.366037 0.0353481 0.00462247 -0.365865 0.035529 -2.88296e-06 -0.365951 0.0356363 -2.88296e-06 -0.365822 -0.0238684 0.000172724 -0.319316 -0.0236434 0.00599141 -0.31949 -0.0229364 0.0148793 -0.320302 -0.0223656 0.0174721 -0.320742 -0.0225846 0.0161958 -0.320306 -0.0232388 0.0111174 -0.319804 -0.0197367 0.0222183 -0.322538 -0.020072 0.0219712 -0.322542 -0.0208309 0.0209443 -0.321947 -0.0209948 0.0206743 -0.321818 -0.0216344 0.019171 -0.321047 -0.0217523 0.0191629 -0.321222 -0.0218828 0.0185534 -0.320852 -0.0222479 0.0174781 -0.320566 -0.0191265 0.0228697 -0.323277 0.0253642 0.0252301 -0.357829 0.024812 0.0252023 -0.357656 0.0058886 0.0251883 -0.342594 -0.00507464 0.0251655 -0.334016 0.00576261 0.025164 -0.342755 -0.00715942 0.0251617 -0.332385 -0.00728638 0.0251393 -0.332547 -0.00919955 0.0251347 -0.33105 -0.0109442 0.0251287 -0.329685 -0.0124012 0.0251419 -0.328282 -0.0162655 0.0245371 -0.325507 -0.0175175 0.0239003 -0.324259 -0.0189282 0.023028 -0.323431 -0.0188056 0.0230426 -0.323259 -0.0238038 0.000858384 -0.320069 -0.0239375 0.00086413 -0.31991 -0.023595 0.0059536 -0.320232 -0.0231937 0.0110565 -0.320546 -0.022782 0.0147969 -0.320868 -0.022914 0.0148323 -0.320709 -0.0224271 0.0166039 -0.321146 -0.0225543 0.0166678 -0.320989 -0.0222327 0.0173006 -0.321298 -0.0223572 0.0173746 -0.321143 -0.0216399 0.0189343 -0.321761 -0.0209103 0.0203885 -0.322331 -0.0191404 0.0224679 -0.323715 -0.0189498 0.0226201 -0.323864 -0.017749 0.0236381 -0.324746 -0.0155838 0.0243382 -0.326496 -0.0127403 0.0246448 -0.328719 -0.00938478 0.0248626 -0.331288 -0.00747139 0.0248671 -0.332785 -0.00541242 0.024668 -0.334449 0.0055798 0.0248919 -0.34299 0.018154 0.0247033 -0.352875 0.0246102 0.0247305 -0.357923 0.0263458 0.0245857 -0.35928 0.0277063 0.0243981 -0.360289 0.028093 0.0242338 -0.360591 0.0292031 0.0233727 -0.361514 0.0303085 0.0224919 -0.362379 0.0307871 0.0223098 -0.362696 0.0324023 0.0197406 -0.364016 0.032637 0.0192804 -0.364199 0.0325649 0.0198574 -0.364086 0.0334098 0.0179079 -0.364746 0.0332318 0.0178259 -0.364664 0.0336582 0.0162642 -0.364998 0.0343349 0.0106042 -0.365527 0.0345655 0.00773277 -0.365707 0.034756 0.00775115 -0.365799 0.0349414 0.00460598 -0.365944 0.0347506 0.00459341 -0.365852 0.0350542 -2.88296e-06 -0.366048 0.0349676 0.00776621 -0.365803 0.034525 0.0106279 -0.365618 0.0342754 0.0131317 -0.365423 0.0347363 0.0106473 -0.365622 0.0340372 0.0151901 -0.365237 0.0342475 0.0152184 -0.36524 0.0338439 0.016318 -0.365086 0.0340517 0.016362 -0.365087 0.0336112 0.0179752 -0.364742 0.032804 0.0193889 -0.364273 0.0329963 0.0194778 -0.364262 0.0317432 0.0211699 -0.363444 0.0319194 0.0212849 -0.363421 0.0309487 0.0224413 -0.362663 0.0304318 0.0226579 -0.362419 0.0305878 0.0227944 -0.362382 0.0293059 0.0235538 -0.361539 0.027821 0.0245587 -0.360224 0.0263971 0.0247852 -0.359266 0.0250543 0.0249319 -0.358217 0.0251295 0.0250986 -0.358126 0.0247053 0.0250969 -0.357795 0.0246341 0.0249303 -0.357889 0.0181802 0.0249042 -0.352842 0.0182539 0.0250712 -0.352748 0.0056535 0.0250593 -0.342895 -0.00538619 0.0248706 -0.334415 -0.0053116 0.0250385 -0.334319 -0.00931002 0.0250307 -0.331192 -0.0111296 0.0248565 -0.329924 -0.0110548 0.0250247 -0.329827 -0.0127144 0.0248485 -0.328685 -0.0141779 0.0248054 -0.32754 -0.0141119 0.0249739 -0.327433 -0.0155909 0.0245406 -0.326434 -0.0163974 0.0242765 -0.325803 -0.0177253 0.0237934 -0.324603 -0.0190074 0.0227961 -0.323763 -0.0189997 0.0229406 -0.323609 -0.0191962 0.0227835 -0.323456 -0.0192011 0.0226411 -0.323611 -0.0201186 0.0217678 -0.322895 -0.0201305 0.0218941 -0.322728 -0.0208528 0.0207746 -0.32232 -0.0210128 0.0205115 -0.322195 -0.0217553 0.0190329 -0.321614 -0.0217952 0.019114 -0.321423 -0.0233266 0.0110815 -0.320387 -0.0237284 0.00596912 -0.320073 -0.0239512 0.000166389 -0.319899 -0.0239977 -2.88296e-06 -0.319782 0.0351533 0.00461629 -0.365948 0.0351623 0.00777525 -0.365719 0.0344863 0.0131549 -0.365427 0.0346806 0.0131689 -0.365342 0.0344414 0.0152355 -0.365156 0.034244 0.0163884 -0.365 0.0327537 0.0199532 -0.364072 0.0329347 0.0200107 -0.363978 0.0320928 0.0213542 -0.363321 0.0294448 0.023703 -0.36149 0.0282136 0.0243923 -0.36053 0.0295953 0.0237941 -0.361376 0.0264921 0.0249506 -0.359188 0.0252389 0.0252038 -0.357989 0.0183626 0.0251762 -0.35261 -0.00520144 0.0251428 -0.334178 -0.00739669 0.0250351 -0.332689 -0.0126395 0.0250168 -0.328588 -0.0125287 0.0251206 -0.328445 -0.0155413 0.0247067 -0.326311 -0.0140057 0.0250767 -0.327284 -0.015444 0.0248065 -0.326152 -0.0163574 0.0244395 -0.325672 -0.0176431 0.0238864 -0.32443 -0.0208802 0.0208801 -0.322141 -0.0210428 0.0206127 -0.322013 -0.0224043 0.0174354 -0.320946 -0.0226038 0.0167203 -0.320791 -0.0229687 0.0148615 -0.320509 -0.0225667 0.016752 -0.320585 -0.0233824 0.0111022 -0.320186 -0.0233513 0.0111149 -0.31998 -0.023785 0.00598194 -0.319872 -0.0237549 0.00598983 -0.319666 -0.0239946 0.000868881 -0.319709 -0.0239652 0.000871812 -0.319503 -0.023979 0.000172262 -0.319493 -0.0240083 0.000170021 -0.319699 -0.0239662 -2.88296e-06 -0.319453 0.0354908 0.00462342 -0.365707 0.035305 0.00777664 -0.365562 0.0349308 0.0106589 -0.365538 0.0345839 0.0152381 -0.364998 0.0343862 0.0163924 -0.364843 0.0339414 0.0180216 -0.364495 0.0337998 0.0180155 -0.364653 0.0331795 0.0195312 -0.364169 0.0322324 0.0213654 -0.363163 0.0311131 0.022521 -0.362558 0.030749 0.0228772 -0.362274 0.0280888 0.0246786 -0.359942 0.0283526 0.0244899 -0.360409 0.0279563 0.0246579 -0.360101 0.0266147 0.0250539 -0.359058 0.0278118 0.0247821 -0.359727 0.026744 0.0250774 -0.358898 -0.0238375 -2.88296e-06 -0.320042 0.0352206 -2.88296e-06 -0.366071 0.0349137 -2.88296e-06 -0.365979 -0.023139 -0.0131562 -0.320145 -0.0230261 -0.013159 -0.319969 -0.0227321 -0.0154609 -0.320194 -0.0225233 -0.0164669 -0.320353 -0.02264 -0.016462 -0.320529 -0.0213297 -0.0198444 -0.321287 -0.0214474 -0.0198351 -0.321462 -0.0195302 -0.0224283 -0.322698 -0.0191002 -0.0228113 -0.323031 -0.0192219 -0.0227965 -0.323203 -0.0196502 -0.0224135 -0.32287 -0.0182669 -0.0234395 -0.323677 -0.0179226 -0.0236645 -0.323944 -0.0180475 -0.0236505 -0.324115 -0.0166282 -0.024355 -0.324954 -0.0164275 -0.0244795 -0.32538 -0.0135527 -0.0251148 -0.327641 -0.0100921 -0.0251377 -0.330352 -0.00996488 -0.0251596 -0.330189 -0.00479212 -0.0251718 -0.334237 0.017439 -0.0252095 -0.351629 0.024319 -0.0252264 -0.357012 0.0241943 -0.0252 -0.357172 0.0258548 -0.0251732 -0.358467 0.0273504 -0.0249353 -0.359369 0.0276209 -0.0247872 -0.35984 0.0277527 -0.0248085 -0.359681 0.030119 -0.0234201 -0.361784 0.0302556 -0.0234361 -0.361625 0.0306304 -0.0231276 -0.361916 0.0315476 -0.0220507 -0.362897 0.032614 -0.0208111 -0.36346 0.032474 -0.0208009 -0.363619 0.0328849 -0.0203662 -0.363671 0.0334621 -0.0189115 -0.364389 0.0341529 -0.0173462 -0.36466 0.0345018 -0.015789 -0.364934 0.034011 -0.017341 -0.364818 0.0345896 -0.013992 -0.365271 0.0349499 -0.0119619 -0.365284 0.0353494 -0.00460079 -0.365866 0.0350031 -0.00984007 -0.365595 0.0348085 -0.00982917 -0.365679 0.0348074 -0.0119599 -0.365442 0.034613 -0.0119471 -0.365526 0.0343594 -0.0157857 -0.365091 0.0327445 -0.0203568 -0.36383 0.0304932 -0.0231125 -0.362075 0.0289071 -0.0242184 -0.36084 0.0299636 -0.0233324 -0.361895 0.0272197 -0.024913 -0.359528 0.0173135 -0.0251842 -0.351789 0.0172047 -0.0250792 -0.351928 0.00604907 -0.0251706 -0.342979 -0.0049189 -0.025149 -0.334399 -0.00502903 -0.0250447 -0.33454 -0.0151102 -0.0248195 -0.32665 -0.0150102 -0.0249203 -0.326493 -0.0165183 -0.0243824 -0.325546 -0.016755 -0.0243409 -0.325124 -0.0181265 -0.023559 -0.32429 -0.0192906 -0.0227108 -0.323382 -0.0205187 -0.0214161 -0.322192 -0.0212708 -0.0201834 -0.321601 -0.0213168 -0.0201263 -0.321798 -0.0221322 -0.0181921 -0.320924 -0.0228469 -0.015457 -0.32037 -0.0228806 -0.0154349 -0.320576 -0.0231704 -0.0131418 -0.320352 -0.0236238 -0.00794484 -0.319768 -0.0239098 -0.00277604 -0.319546 -0.02401 -2.88296e-06 -0.319615 0.0351546 -0.00459463 -0.365949 0.0349427 -0.00458436 -0.365945 0.0345971 -0.009811 -0.365675 0.0343954 -0.0139774 -0.365356 0.0344019 -0.0119257 -0.365522 0.0341661 -0.0157643 -0.365176 0.0338207 -0.0173066 -0.364906 0.0332765 -0.0188635 -0.364481 0.0325653 -0.0202963 -0.363925 0.0323793 -0.0201957 -0.363941 0.0322972 -0.0207365 -0.363716 0.0321152 -0.0206295 -0.363734 0.0313791 -0.0219753 -0.362999 0.0303344 -0.0230276 -0.362184 0.0287629 -0.0241234 -0.360958 0.0274888 -0.0246867 -0.359964 0.027379 -0.0245245 -0.360033 0.0270913 -0.0248113 -0.359655 0.0269875 -0.0246476 -0.359728 0.0257395 -0.0250686 -0.358601 0.0256555 -0.024902 -0.358687 0.0240155 -0.024928 -0.357405 0.0240872 -0.0250947 -0.357311 0.00593999 -0.0250659 -0.343119 0.017131 -0.0249121 -0.352022 0.00586632 -0.0248985 -0.343214 -0.00510361 -0.0248768 -0.334636 -0.0102026 -0.0250337 -0.330494 -0.0102774 -0.0248655 -0.33059 -0.0136618 -0.0250114 -0.327787 -0.0151648 -0.0246523 -0.326767 -0.0168436 -0.0242449 -0.325292 -0.0165564 -0.0242201 -0.325678 -0.0168778 -0.0240842 -0.325427 -0.0197142 -0.0223312 -0.323052 -0.0205712 -0.0213466 -0.322383 -0.021283 -0.0200322 -0.321984 -0.0214921 -0.0197809 -0.321661 -0.0214561 -0.0196915 -0.321848 -0.0221726 -0.0181504 -0.321127 -0.0221283 -0.0180811 -0.321322 -0.0226763 -0.0164324 -0.320734 -0.0226259 -0.0163834 -0.320934 -0.0236543 -0.00793514 -0.319974 -0.023598 -0.00791934 -0.320175 -0.0239394 -0.00277131 -0.319752 -0.0239307 -2.88296e-06 -0.319936 -0.0238824 -0.00276364 -0.319953 -0.0237488 -0.00275436 -0.320112 -0.0231149 -0.0131183 -0.320552 -0.0229823 -0.0130898 -0.320711 -0.0228273 -0.0153987 -0.320777 -0.0211754 -0.0199178 -0.322124 -0.0205494 -0.0212327 -0.322558 -0.0197108 -0.0221961 -0.323213 -0.0204571 -0.0210945 -0.322686 -0.0192941 -0.0225695 -0.323539 -0.0192319 -0.0223977 -0.323644 -0.0181453 -0.0234067 -0.324436 -0.0168515 -0.023888 -0.325505 -0.0165349 -0.024022 -0.325753 -0.0137332 -0.0248428 -0.327888 -0.0137546 -0.0246384 -0.327926 -0.00512984 -0.0246742 -0.33467 0.00584056 -0.0246969 -0.343248 0.0171048 -0.0247112 -0.352055 0.0286342 -0.0239685 -0.361014 0.0298169 -0.0231884 -0.361938 0.0297049 -0.0230136 -0.361907 0.0301821 -0.0228879 -0.362224 0.0300634 -0.022718 -0.362187 0.0310735 -0.0216986 -0.362977 0.0312111 -0.0218505 -0.363028 0.0319609 -0.0204992 -0.363671 0.0329081 -0.0186857 -0.364411 0.03308 -0.0187834 -0.364488 0.0336162 -0.0172491 -0.364908 0.0339569 -0.0157286 -0.365174 0.0341847 -0.013953 -0.365352 0.0339953 -0.0139234 -0.365261 0.0344069 -0.00978884 -0.365583 -0.0163783 0.0240775 -0.325875 0.0340858 0.0131034 -0.365332 0.0322201 -0.020073 -0.363873 -0.0234646 -0.00790021 -0.320334 -0.0226963 -0.0153547 -0.320935 -0.0121742 -0.0102052 -0.329162 -0.0224977 -0.0163239 -0.32109 0.0338484 0.0151555 -0.365146 0.0285434 -0.0237809 -0.360999 0.0239912 -0.0247279 -0.357439 0.0218379 -0.011975 -0.355756 0.025617 -0.0247016 -0.35871 0.0269259 -0.0244499 -0.359734 0.0273105 -0.0243286 -0.360035 -0.0196406 -0.0220321 -0.323324 -0.01771 0.0234485 -0.324834 0.034212 -0.0118996 -0.365431 0.0241273 -0.00797502 -0.357546 0.0334344 -0.0171791 -0.364823 0.0337693 -0.0156851 -0.365085 -0.00902304 -0.0131113 -0.331626 -0.0151642 -0.0244487 -0.326824 -0.0181005 -0.0232208 -0.324528 -0.0133778 -0.00550288 -0.328221 -0.0238175 0.000161996 -0.320058 -0.0141921 0.0246008 -0.327584 -0.0107799 0.0119693 -0.330252 0.0347519 -0.00457184 -0.365853 0.0244358 0.00549712 -0.357787 0.0348955 -2.88296e-06 -0.365965 -0.0103035 -0.0246623 -0.330625 0.0181335 -0.0135029 -0.352859 -0.0220071 -0.0179968 -0.321474 -0.0213455 -0.0195827 -0.321991 -0.0107799 -0.011975 -0.330252 -0.0130693 0.00796925 -0.328462 0.0315958 0.0210299 -0.363385 -0.0121742 0.0101994 -0.329162 -0.0200384 0.0216145 -0.323013 -0.0207534 0.0206466 -0.322454 0.027632 0.0242038 -0.360286 0.0250258 0.0247316 -0.358248 0.020081 0.0131056 -0.354382 -0.00749762 0.0246642 -0.332819 -0.00941096 0.0246595 -0.331323 -0.00902304 0.0131056 -0.331626 -0.0111557 0.0246531 -0.329958 0.0306573 0.0221498 -0.362651 0.0280118 0.024042 -0.360583 0.00555402 0.0246903 -0.343024 -0.00707553 0.0134971 -0.333149 0.0104107 0.00549707 0.0100882 0.0202323 -0.00333798 -0.0262686 0.0201507 -0.00393017 -0.0253101 0.0131873 -0.00365093 -0.00602166 0.014047 -0.00527452 -0.00358305 0.019692 -0.00528451 -0.0194697 0.0135604 -0.0046242 -0.00512616 0.0144419 -0.00550288 -0.00125676 0.0193598 -0.00550288 -0.0151608 0.0195404 -0.00544013 -0.017502 0.0146942 -0.0155029 -0.0166935 0.0146998 -0.0180029 -0.0155976 -0.00244189 -0.00590432 -0.0995141 -0.00292594 -0.00590288 -0.097236 -0.00356819 -0.00250288 -0.0941956 -0.00244201 -0.00450288 -0.0995135 -0.00356819 -0.00260288 -0.0941956 -0.00358715 -0.00450288 -0.0941055 0.000806167 0.00249712 -0.0994024 0.00116478 0.00249712 -0.0992486 0.00158213 0.00249712 -0.0986071 0.00157732 0.00249712 -0.0982169 -0.00244132 -0.00590633 -0.0995168 -0.00518128 -0.00696354 -0.088624 -0.00253373 -0.00740288 -0.106248 -0.00439333 -0.00740288 -0.097547 -0.0016927 -0.00590288 -0.10302 -0.00117893 -0.00647691 -0.105956 -0.00312253 -0.00665288 -0.0972777 -0.00126377 -0.00665288 -0.105974 -0.00365963 -0.00720192 -0.0973915 -0.00149681 -0.00696354 -0.106025 -0.00232516 0.00159712 -0.100065 -0.0063623 0.00209712 -0.100783 -0.00234092 0.0019798 -0.0999909 -0.00238583 0.00230422 -0.0997789 -0.00643812 0.00246314 -0.100425 -0.00244201 0.00249712 -0.0995135 -0.00253277 0.00259712 -0.0990872 -0.00643812 -0.00246891 -0.100425 -0.00244201 -0.00250288 -0.0995135 -0.00253277 -0.00260288 -0.0990872 -0.0063623 -0.00210288 -0.100783 -0.00869661 0.0154971 -0.0177907 -0.00441671 0.0241971 -0.0193029 -0.00302083 0.0154588 -0.0195698 -0.00315719 0.0154186 -0.0195483 0.0144524 0.0184971 -0.0135311 0.0123357 0.0241971 -0.0154859 0.0139788 0.0181687 -0.01402 0.00439511 0.0241971 -0.0193062 0.0138546 0.0179971 -0.0141428 0.0187025 0.0180985 -0.00649106 0.0184902 0.0182103 -0.00707335 0.0197964 0.0241971 -8.35981e-06 0.0197964 0.0169304 -7.63116e-06 0.0197438 0.0170466 -0.00144272 -0.0123545 0.0241971 -0.0154767 -0.017846 0.0241971 -0.00858529 -0.017846 0.0154971 -0.00858529 -0.0198036 0.0154971 6.3362e-06 -0.0198036 0.0241971 6.3362e-06 -0.0178396 0.0154971 0.00859651 -0.012343 0.0241971 0.0154838 -0.00440239 0.0241971 0.0193042 0.00440944 0.0154971 0.0193009 0.0178387 0.0154971 0.00858327 0.0178387 0.0241971 0.00858327 0.0194366 0.0154971 0.00375601 0.0196983 0.0170665 0.00196667 -0.00884101 0.0154971 0.0412143 -0.0213398 0.0179971 0.00803687 -0.0104831 0.0176692 0.0368554 0.0196536 -0.0154727 0.00237204 0.0178324 -0.0242029 -0.00859853 0.0189587 -0.017937 -0.00569935 0.0178387 -0.0242029 0.00858327 0.0197964 -0.0242029 -8.35981e-06 0.0142365 -0.0184315 -0.0137581 0.0138546 -0.0180029 -0.0141428 0.0138569 -0.0180061 -0.0141406 0.0123357 -0.0242029 -0.0154859 0.0140562 -0.0182694 -0.0139423 0.0144524 -0.0185029 -0.0135311 0.0178357 -0.0184377 -0.00859159 -0.00331416 -0.0153564 -0.0195223 -0.00441671 -0.0148939 -0.0193029 -0.00701051 -0.0149815 -0.0185198 -0.00441671 -0.0242029 -0.0193029 -0.00830997 -0.0154679 -0.0179745 0.00440944 -0.0242029 0.0193009 0.00440944 -0.0155029 0.0193009 -0.012343 -0.0242029 0.0154838 -0.0178396 -0.0155029 0.00859651 -0.0178396 -0.0242029 0.00859651 -0.0198036 -0.0155029 6.3362e-06 -0.0198036 -0.0242029 6.3362e-06 -0.0123545 -0.0155029 -0.0154767 -0.0213398 -0.0155029 0.00803687 -0.0110046 -0.0180029 0.0354712 0.016107 -0.00250288 -0.272585 0.0152035 -0.00250288 -0.272673 0.0148796 -0.00250288 -0.273009 0.0342776 -0.00250288 -0.301544 0.0173215 -0.00250288 -0.292213 0.0369882 -0.00250288 -0.300116 0.0177088 -0.00250288 -0.29187 0.0178726 -0.00250288 -0.291379 0.0181129 -0.00250288 -0.287386 0.0367844 -0.00250288 -0.295722 0.0180092 -0.00250288 -0.286879 0.0168143 -0.00250288 -0.292317 0.0144187 -0.00250288 -0.292173 0.0135101 -0.00250288 -0.293952 0.0136201 -0.00250288 -0.292125 0.0141084 -0.00250288 -0.302184 0.0131392 -0.00250288 -0.301533 0.0133662 -0.00250288 -0.296343 -0.0114785 -0.00250288 -0.054192 -0.0130852 -0.00250288 -0.0396851 -0.013825 -0.00250288 -0.0403303 -0.0138676 -0.00250288 -0.0408358 0.00515192 -0.00250288 -0.0491025 -0.0125785 -0.00250288 -0.0397116 -0.0100012 -0.00250288 -0.044277 -0.00961113 -0.00250288 -0.0442845 -0.00925361 -0.00250288 -0.0444408 -0.00813645 -0.00250288 -0.0490228 -0.00966484 -0.00250288 -0.0548142 0.00504027 -0.00250288 -0.045331 0.0141084 0.00249712 -0.302184 0.0148796 0.00249712 -0.273009 0.0152035 0.00249712 -0.272673 0.0139806 0.00249712 -0.286136 0.016107 0.00249712 -0.272585 0.0133596 0.00249712 -0.301882 0.0131392 0.00249712 -0.301533 0.0367844 0.00249712 -0.295722 0.0181129 0.00249712 -0.287386 0.0164898 0.00249712 -0.272852 -0.0130526 0.00249712 -0.0453921 -0.0138676 0.00249712 -0.0408358 0.00638569 0.00249712 -0.0476668 -0.0120947 0.00249712 -0.0507467 0.00515192 0.00249712 -0.0491025 -0.00894475 0.00249712 -0.0501832 -0.00847615 0.00249712 -0.0499633 -0.00818029 0.00249712 -0.0495386 -0.0108361 0.00249712 -0.0549514 -0.0121941 0.00249712 -0.0501914 -0.0089831 0.00249712 -0.044722 -0.0130852 0.00249712 -0.0396851 0.0190522 0.00249712 -0.200819 0.0190522 -0.00250288 -0.200819 0.0193827 0.00249712 -0.200421 0.0193827 -0.00250288 -0.200421 -0.0169498 -0.00242886 -0.0511719 -0.0122071 -0.00250288 -0.0501937 -0.0121082 -0.00198557 -0.0506718 -0.0161411 -0.00160288 -0.0514705 -0.0162545 -0.00194724 -0.0514287 -0.016493 -0.00218907 -0.0513406 -0.016151 0.00170032 -0.0514669 -0.0162545 0.00194148 -0.0514287 -0.016493 0.0021833 -0.0513406 -0.0169498 0.00242309 -0.0511719 -0.0122071 0.00249712 -0.0501937 -0.0122845 0.00259712 -0.0497648 -0.0179883 0.00259711 -0.0507891 0.0136571 -0.00252676 -0.291509 0.013654 -0.00250288 -0.291562 0.00789326 -0.00259154 -0.290929 0.00587355 -0.00209759 -0.291527 0.0136377 -0.00230999 -0.291833 0.00632286 -0.00229695 -0.291405 0.0064515 -0.00233963 -0.291369 0.0136201 -0.00160288 -0.292125 0.00553019 -0.0018047 -0.291617 0.0136247 -0.00198557 -0.292049 0.0136201 0.00159712 -0.292125 0.00632286 0.00229119 -0.291405 0.0136247 0.0019798 -0.292049 0.0057708 0.002028 -0.291555 0.00553019 0.00179893 -0.291617 0.013654 0.00249712 -0.291562 0.00705104 0.00248203 -0.291194 0.00827137 0.00259712 -0.290801 0.004131 0.00231306 -0.285845 0.013963 0.00230422 -0.286428 0.0139204 0.00259712 -0.287134 0.013976 0.0019798 -0.286212 0.00481591 0.00173083 -0.285593 0.00335794 -0.00253186 -0.286127 0.004131 -0.00231882 -0.285845 0.013963 -0.00230999 -0.286428 0.0044486 -0.0021551 -0.285729 0.013976 -0.00198557 -0.286212 0.00469296 -0.00194871 -0.285639 0.0139466 -0.00250288 -0.286699 0.017592 -0.00606877 -0.211765 0.0187424 -0.0170357 -0.210543 0.0174792 -0.00625728 -0.211884 0.0225487 -0.0170796 -0.206503 0.0170452 -0.00681958 -0.212345 0.0290841 -0.0171545 -0.199566 0.0179848 -0.00530288 -0.211348 0.0180106 -0.00250288 -0.195025 0.0187418 -0.00250288 -0.195251 0.0167252 -0.00250288 -0.211509 0.017606 -0.00250288 -0.211599 0.014318 -0.00250288 -0.185398 0.0289219 -0.00250288 -0.196669 0.0194698 -0.00250288 -0.19991 0.0179848 -0.00250288 -0.211348 0.0162612 -0.00250288 -0.210755 0.0290841 -0.00250288 -0.199566 0.0295072 -0.00250288 -0.19888 0.0296252 -0.00250288 -0.198083 0.0162584 0.00249712 -0.210724 0.0139818 0.00249712 -0.186272 0.0139818 0.00259712 -0.186272 -0.0145742 0.0116687 -0.0257693 -0.0145742 0.00259712 -0.0257693 -0.0140471 0.0116687 -0.0265054 -0.0132681 0.0116687 -0.026967 -0.0123692 0.0116687 -0.0270757 -0.0128431 0.00259712 -0.0270657 -0.0147602 0.0116687 -0.0248832 -0.0147171 0.00255484 -0.0227664 -0.0144644 0.0116687 -0.0220956 -0.0145917 0.00242965 -0.0223537 -0.0141146 0.00195275 -0.0216401 -0.0136588 0.0116687 -0.0212907 -0.0125587 0.0116687 -0.0209964 -0.0125587 -0.0116745 -0.0209964 -0.0136588 -0.0116745 -0.0212907 -0.0125587 -0.000402883 -0.0209964 -0.0134007 -0.00124479 -0.0211635 -0.0141146 -0.0116745 -0.0216401 -0.0141146 -0.00195852 -0.0216401 -0.0147595 -0.0116745 -0.0231955 -0.0147595 -0.00260288 -0.0231955 -0.0147602 -0.0116745 -0.0248832 -0.0140471 -0.0116745 -0.0265054 -0.0140471 -0.00260288 -0.0265054 -0.0132681 -0.00260288 -0.026967 -0.0132681 -0.0116745 -0.026967 0.00123507 -0.00260288 -0.293491 -0.00338454 -0.00260288 -0.292927 -0.00666527 -0.00260288 -0.298456 -0.0179941 -0.00260288 -0.0507861 -0.0135162 -0.00260288 -0.0744789 0.0024778 -0.00260288 -0.286445 0.0136801 -0.00260288 -0.291127 0.00454671 -0.00260288 -0.291342 -0.00306114 -0.00260288 -0.137353 0.00290356 -0.00260288 -0.16887 0.0149171 -0.00260288 -0.196317 0.00323749 -0.00260288 -0.301014 -0.0166515 -0.00260288 -0.310095 0.00499451 -0.00260288 -0.303397 -0.0147602 -0.00260288 -0.0248832 -0.0145742 -0.00260288 -0.0257693 -0.0126677 -0.00260288 -0.0476327 -0.0246091 -0.00260288 -0.028593 -0.0157363 -0.00260288 -0.0290761 -0.0128431 -0.00260288 -0.0270657 -0.0237097 -0.00260288 -0.0339913 -0.00938659 -0.00260288 -0.0947121 0.0111439 -0.00260288 -0.20169 0.0108003 -0.00260288 -0.201776 0.0109951 -0.00260288 -0.196682 0.0101329 -0.00260288 -0.196537 0.0104226 -0.00260288 -0.201988 0.00531463 -0.00260288 -0.291183 0.00339601 -0.00260288 -0.291692 0.00320135 -0.00260288 -0.291769 0.00287153 -0.00260288 -0.291914 -0.00863553 -0.00260288 -0.0950541 -0.0065417 -0.00260288 -0.0999361 0.00100435 -0.00260288 -0.294437 0.00134175 -0.00260288 -0.296574 -0.00992796 -0.00260288 -0.30276 0.00697955 -0.00260288 -0.200715 0.0083254 -0.00260288 -0.224147 0.010171 -0.00260288 -0.206667 0.011004 -0.00260288 -0.223314 0.0109433 -0.00260288 -0.238769 0.00772587 -0.00260288 -0.247566 0.00774731 -0.00260288 -0.268054 0.00113672 -0.00260288 -0.282065 0.00671469 -0.00260288 -0.290978 0.00645569 -0.00260288 -0.291011 0.00592847 -0.00260288 -0.291083 -0.00910759 -0.00260288 -0.0948571 0.000915035 -0.00260288 -0.143034 0.00485961 -0.00260288 -0.164009 0.00305023 -0.00260288 -0.300625 0.00323081 -0.00260288 -0.301 0.00945705 -0.00260288 -0.195982 0.00827137 -0.00260288 -0.290801 0.0130784 -0.00590288 -0.301125 0.0139204 -0.00260288 -0.287134 0.0147436 -0.00590288 -0.273456 0.0130784 -0.00250288 -0.301125 0.0147436 0.00249712 -0.273456 0.0136571 0.002521 -0.291509 0.0130784 0.00589712 -0.301125 0.0120037 -0.00160288 -0.22329 0.0120731 -0.00160288 -0.232914 0.0120731 0.00159712 -0.232914 0.0119427 -0.00160288 -0.238803 0.0113299 -0.00160288 -0.249388 0.0113299 0.00159712 -0.249388 0.00982602 -0.00160288 -0.262096 0.00982602 0.00159712 -0.262096 0.00872539 0.00159712 -0.268263 0.00630459 -0.00160288 -0.278218 0.00630156 0.00159712 -0.278229 0.0042206 -0.00160288 -0.284649 0.0042206 0.00159712 -0.284649 -0.0187601 -0.00160288 -0.0407181 -0.0187568 0.00159712 -0.0407372 -0.0104576 -0.00160288 -0.0846221 -0.0124654 -0.00160288 -0.0746382 0.00893187 0.00159712 -0.184557 0.00859828 0.00159712 -0.181981 0.00859828 -0.00160288 -0.181981 0.00312817 0.00159712 -0.149027 0.00189507 -0.00160288 -0.142835 0.00189507 0.00159712 -0.142835 -0.000436742 -0.00250288 -0.0935325 0.0003157 -0.00250288 -0.0936726 0.0124777 -0.00250288 -0.0954426 0.00143726 -0.00250288 -0.0989694 0.000441602 -0.00250288 -0.106569 0.00116478 -0.00250288 -0.0992486 0.000806167 -0.00250288 -0.0994024 -0.00085984 -0.00250288 -0.10636 0.0126365 -0.00250288 -0.0989211 0.00158213 -0.00250288 -0.0986071 -0.00106731 -0.00250288 -0.105932 -0.00454113 -0.00250288 -0.0876927 -0.00474222 -0.00250288 -0.0880898 -0.00332002 -0.00250288 -0.0874397 -0.00358715 -0.00250288 -0.0941055 0.000748719 -0.00250288 -0.0943037 0.00157732 -0.00250288 -0.0982169 0.0131298 -0.00250288 -0.0959701 0.0135082 -0.00250288 -0.0967186 0.0003157 0.00249712 -0.0936726 -4.65907e-05 0.00249712 -0.0935277 -0.00454113 0.00249712 -0.0876927 -0.00418767 0.00249712 -0.0874223 -0.00375186 0.00249712 -0.0873319 -0.00475109 0.00249712 -0.0885348 -0.00332002 0.00249712 -0.0874397 -0.00356819 0.00249712 -0.0941956 0.00143726 0.00249712 -0.0989694 0.0126365 0.00249712 -0.0989211 -0.0120909 0.0154971 -0.0302707 -0.0166344 0.0154971 -0.0332595 -0.0143001 0.0154971 -0.0300035 -0.0169809 -0.0155029 -0.032354 -0.0143001 -0.0155029 -0.0300035 -0.0140218 -0.0155029 -0.0338605 -0.00101098 0.0154971 -0.0235386 0.0142109 0.0154971 -0.0179863 0.00439511 0.0154971 -0.0193062 0.0146942 0.0154971 -0.0166935 0.0123357 0.0154971 -0.0154859 0.0138546 0.0154971 -0.0141428 0.0140543 0.0154971 -0.014023 -0.0020558 -0.0155029 -0.0271921 -0.00164532 -0.0155029 -0.0264964 0.00439511 -0.0155029 -0.0193062 -0.0027 -0.0155029 -0.0196166 0.0136679 -0.0155029 -0.0184296 0.0123357 -0.0155029 -0.0154859 0.0145676 -0.0155029 -0.0173829 0.0146998 -0.0155029 -0.0155976 0.0147046 -0.0155029 -0.0145018 0.0140543 -0.0155029 -0.014023 0.0138546 -0.0155029 -0.0141428 -0.017846 -0.0155029 -0.00858529 -0.0125575 -0.0155029 -0.0177892 -0.00869661 -0.0155029 -0.0177907 -0.0120007 -0.0155029 0.048546 -0.00557231 -0.0155029 0.0478534 -0.00928331 -0.0155029 0.0531966 -0.00194211 -0.0155029 0.0514809 -0.000152566 -0.0155029 0.0586195 0.00301549 -0.0155029 0.0528073 0.00785233 -0.0155029 0.0589828 0.0079721 -0.0155029 0.0514772 0.0115132 -0.0155029 0.0583969 0.0115996 -0.0155029 0.047847 0.0190037 -0.0155029 0.0480523 -0.012343 -0.0155029 0.0154838 -0.00877592 -0.0155029 0.0414085 -0.0152613 -0.0155029 -0.0185127 -0.0221098 -0.0155029 -0.00558287 -0.00884101 -0.0155029 0.0412143 0.0178387 -0.0155029 0.00858327 0.0123472 -0.0155029 0.0154747 0.00300813 -0.0155029 0.0329789 -0.00440239 -0.0155029 0.0193042 -0.0040012 -0.0155029 0.0358853 -0.00865385 -0.0155029 0.0420068 -0.00861399 -0.0155029 0.0424033 -0.00656554 -0.0155029 0.0403307 -0.00859979 -0.0155029 0.0426386 -0.0069024 -0.0155029 0.0428968 0.0121291 -0.0185029 -0.0487708 0.0111421 -0.0185029 -0.0229281 -0.001172 -0.0185029 -0.0272719 -0.00657362 -0.0185029 -0.0328007 0.0149258 -0.0185029 -0.0239668 0.015036 -0.0185029 -0.017558 0.01459 -0.0185029 -0.0183123 0.0139113 -0.0185029 -0.0188663 0.0172723 -0.0185029 -0.0542503 0.0155739 -0.0185029 -0.0500059 0.0171801 -0.0185029 -0.0190625 0.0145179 -0.0185029 -0.0448047 0.00442916 -0.0185029 -0.0442963 0.00723252 -0.0185029 -0.0472253 0.0134348 -0.0185029 -0.0485993 0.0146745 -0.0185029 -0.0490438 0.0172144 -0.0185029 -0.00977747 0.0150966 0.0184971 -0.014048 0.0161593 0.0184971 -0.056552 0.0125307 0.0184971 -0.0225741 -0.00657362 0.0184971 -0.0328007 0.0111421 0.0184971 -0.0229281 0.0139113 0.0184971 -0.0188663 0.0171801 0.0184971 -0.0190625 0.0145179 0.0184971 -0.0448047 0.0133026 0.0184971 -0.0453287 0.0153569 0.0184971 -0.0437812 0.015305 0.0184971 -0.0253488 0.0149258 0.0184971 -0.0239668 0.0151998 0.0184971 -0.0156 0.0152046 0.0184971 -0.0145038 0.0146745 0.0184971 -0.0490438 -0.0221098 0.0154971 -0.00558287 -0.0227808 0.0179971 -0.00102197 -0.0227673 0.0154971 0.00128594 -0.0180528 -0.0181928 -0.0231337 -0.0177205 -0.0186432 -0.0260764 -0.00735364 -0.0160029 1.71586e-06 -0.0125583 -0.0160029 0.00725365 -0.00637029 -0.0160029 -0.00367365 -0.0145036 -0.0160029 4.36931e-06 -0.003681 -0.0160029 -0.00636493 -9.0182e-06 -0.0160029 -0.014501 -6.36475e-06 -0.0160029 -0.00735101 0.012551 -0.0160029 -0.00725567 0.00734636 -0.0160029 -3.73948e-06 0.0144964 -0.0160029 -6.39292e-06 0.00636301 -0.0160029 0.00367163 0.0125564 -0.0160029 0.00724433 0.00367372 -0.0160029 0.00636291 0.0152785 -0.0242353 -0.0668541 0.0156143 -0.0248828 -0.0685118 0.0144169 -0.0247477 -0.0671451 0.0155691 -0.0250605 -0.068941 0.0128574 -0.0251655 -0.067076 0.0118411 -0.0252459 -0.0667603 0.00963276 -0.0185029 -0.049733 0.00767649 -0.0189713 -0.0503401 0.00418123 -0.0211451 -0.0516037 0.00288434 -0.0212332 -0.0506048 -0.0023655 -0.0241544 -0.054264 0.00615537 -0.0206244 -0.144854 -0.00260376 -0.0232454 -0.111554 -0.00142051 -0.0230698 -0.113694 0.000911072 -0.0231084 -0.113255 0.0176302 -0.0222687 -0.123684 0.0181378 -0.0223598 -0.122577 -0.000424828 -0.0233742 -0.11002 -0.000482802 -0.0230708 -0.113693 0.00453644 -0.0208512 -0.141721 0.00383695 -0.0210807 -0.138632 0.00541363 -0.0210605 -0.138905 0.00501108 -0.021125 -0.138047 0.0111775 -0.0215261 -0.13287 0.00563131 -0.0210758 -0.138701 0.0173434 -0.0219424 -0.127693 0.017818 -0.0219842 -0.127181 0.0182308 -0.0220533 -0.126333 0.0195012 -0.022159 -0.125047 0.0190756 -0.0223607 -0.122576 0.0142886 -0.024356 -0.0979759 0.0153515 -0.0245902 -0.094875 0.0171005 -0.0242725 -0.0990343 0.0169263 -0.0244399 -0.096865 0.0162891 -0.0245918 -0.0948411 0.0160044 -0.0242706 -0.0990635 0.0151377 -0.0242427 -0.099422 0.0139062 -0.0242888 -0.0988389 -0.00153676 -0.0234725 -0.108819 -0.00508984 -0.0253301 -0.0831928 -0.00693088 -0.0254039 -0.0811363 0.00544566 -0.0249429 -0.0900257 -0.00399051 -0.0254122 -0.0806995 -0.00357004 -0.0254187 -0.0804355 0.0037501 -0.025477 -0.0767005 0.0095169 -0.0254686 -0.0727427 0.0138921 -0.0254693 -0.0725857 -0.013568 -0.0249348 -0.0619464 -0.00976283 -0.0247624 -0.0598587 0.00589211 -0.0251325 -0.0644456 -0.000232986 -0.0250765 -0.0637392 0.00930003 -0.0253183 -0.0676256 0.0100996 -0.0253416 -0.068123 0.0155025 -0.0254375 -0.0707837 0.0110102 -0.0254304 -0.0706947 0.0107028 -0.0254504 -0.071588 0.0101187 -0.0254631 -0.0723283 -0.00577753 -0.0246823 -0.0590294 -0.00997914 -0.0247556 -0.059781 -0.0109077 -0.0247451 -0.0596547 -0.0149203 -0.0245427 -0.0574124 -0.0107815 -0.0243637 -0.0557617 -0.0093739 -0.0243274 -0.0554742 -0.00609826 -0.0244999 -0.0571964 -0.0144762 -0.0241764 -0.0538779 -0.0159831 -0.0240445 -0.0526142 -0.0150737 -0.0240333 -0.0525655 -0.0151755 -0.0239765 -0.0520624 -0.0189666 -0.0223337 -0.0389152 -0.0158943 -0.0233496 -0.0468627 -0.0165996 -0.0225893 -0.0411038 -0.00578918 -0.0244037 -0.0563 -0.00519986 -0.0243194 -0.0555566 -0.00434079 -0.0242554 -0.0550294 -0.002939 -0.0240934 -0.0537338 0.0173802 0.0184971 -0.0578275 0.0163887 0.0186125 -0.0578764 0.0173277 0.0188401 -0.0596766 0.0167366 0.0197291 -0.0610788 0.0155025 0.0254317 -0.0707837 -0.00581117 0.0246707 -0.0589674 -0.00523502 0.0247407 -0.0597187 -0.0149203 0.024537 -0.0574124 -0.00438957 0.0247891 -0.0602569 -0.000232519 0.0250707 -0.0637394 -0.00976283 0.0247566 -0.0598587 -0.0106774 0.0247393 -0.0596564 -0.0116077 0.0247499 -0.0597684 -0.0135113 0.0249104 -0.0617036 -0.0136106 0.0249809 -0.0626443 -0.0135838 0.0249988 -0.0628928 -0.01345 0.0250592 -0.0637655 -0.00908909 0.0253157 -0.0835874 -0.00782821 0.0253911 -0.0814164 -0.00616628 0.0252322 -0.0853159 0.0124493 0.0254619 -0.0725335 0.015535 0.0254571 -0.0720625 0.0102714 0.0254551 -0.0721796 0.0095169 0.0254628 -0.0727427 0.0110708 0.0254664 -0.072964 0.00129263 0.0254703 -0.0769404 0.00375053 0.0254712 -0.0767003 0.0142141 0.024475 -0.0963532 0.0143743 0.0244038 -0.0972831 0.0151377 0.0242369 -0.099422 0.0167581 0.0245959 -0.0946999 0.0169412 0.0242686 -0.0990115 0.0153515 0.0245845 -0.094875 0.0160044 0.0242648 -0.0990635 0.0130477 0.0245847 -0.0949045 0.01284 0.0245935 -0.0947879 0.00544545 0.0249372 -0.0900256 0.00378636 0.0249291 -0.0901945 -0.00356624 0.0252205 -0.0854482 -0.00398852 0.0252344 -0.0851838 -0.0046335 0.025268 -0.084496 0.0079565 0.0238749 -0.103927 0.00576214 0.0238484 -0.104241 0.0130617 0.0242184 -0.099662 -0.00153676 0.0234668 -0.108819 0.000775878 0.0235008 -0.108431 7.41729e-05 0.0234484 -0.109058 -0.00240323 0.0234364 -0.109178 -0.00260376 0.0232396 -0.111554 -0.000376094 0.0232266 -0.111738 0.0192474 0.0223579 -0.122542 -0.00142051 0.0230641 -0.113694 0.0181378 0.022354 -0.122577 0.0180265 0.0222164 -0.124258 0.0174562 0.0222773 -0.123506 0.0172528 0.0223785 -0.122268 0.0168947 0.0223102 -0.123098 0.000402175 0.0230405 -0.114002 8.43018e-05 0.023159 -0.112562 0.00383695 0.021075 -0.138632 0.00563131 0.02107 -0.138701 0.00445332 0.0210916 -0.138412 0.00501108 0.0211192 -0.138047 0.0111775 0.0215203 -0.13287 0.018943 0.0219348 -0.12773 0.0182884 0.0220667 -0.126097 0.0229398 0.0197869 -0.157189 0.0135658 0.0203279 -0.148984 0.0222214 0.0199049 -0.155323 0.00644292 0.0206132 -0.144929 0.00522448 0.0206212 -0.144819 0.00551736 0.0207604 -0.142886 -0.0158943 0.0233438 -0.0468626 -0.0147343 0.0241241 -0.0534442 -0.0138581 0.0242465 -0.0546025 -0.00434079 0.0242497 -0.0550294 -0.00334717 0.0241997 -0.0546443 -0.00575184 0.0243906 -0.0562339 -0.0093739 0.0243217 -0.0554742 -0.00644299 0.0241804 -0.054339 -0.00351243 0.0240262 -0.0532037 -0.000979739 0.0234364 -0.052126 -9.65884e-05 0.0236423 -0.0532902 -0.002939 0.0240876 -0.0537338 0.000595125 0.0233503 -0.0530058 0.00200806 0.0218141 -0.0509396 0.00249117 0.0214935 -0.0507544 0.00594072 0.0199311 -0.0509509 0.00571924 0.019397 -0.0495619 0.00822085 0.0187525 -0.0501601 0.00963276 0.0184971 -0.049733 0.00702065 0.0186455 -0.0484683 0.000441602 0.00589712 -0.106569 0.0126365 0.0234209 -0.0989211 -0.00149954 0.00739712 -0.107786 -0.000430639 0.0069537 -0.107116 -2.11947e-05 0.00652877 -0.106859 4.43602e-05 0.00644713 -0.106818 0.000437452 0.00590312 -0.106571 -0.00478699 0.00728239 -0.0866965 0.00342341 0.0241308 -0.0908558 -0.00536399 0.00739712 -0.0864042 -0.00563232 0.0244176 -0.0862683 -0.0037383 0.00644713 -0.0872278 -0.00417617 0.00690166 -0.087006 -0.00423846 0.0069537 -0.0869744 0.0132378 0.00249712 -0.0983364 0.0134621 0.0235344 -0.097886 0.0135465 0.00249712 -0.0975565 0.0135739 0.0236061 -0.0972231 0.0135082 0.00249712 -0.0967186 0.0131298 0.00249712 -0.0959701 0.012626 0.0237868 -0.0955258 0.0124777 0.00249712 -0.0954426 0.0124777 0.0237957 -0.0954426 -0.00106731 0.00589712 -0.105932 -0.0143889 0.00739712 -0.0520411 -0.0122173 0.00726954 -0.0548006 -0.0123312 0.0235312 -0.054753 -0.0128814 0.00739531 -0.0544497 -0.0129672 0.00739712 -0.05439 -0.0138311 0.023373 -0.0534971 -0.0138308 0.00739712 -0.0534975 -0.0100278 0.0235437 -0.0549318 -0.0112326 0.00674342 -0.0550348 -0.0110585 0.00660588 -0.0550458 -0.00966484 0.0235263 -0.0548142 -0.0103234 0.00249712 -0.0549966 -0.0107396 0.00631992 -0.0550436 -0.0157911 0.0217481 -0.0410618 -0.0155543 0.0215773 -0.040414 -0.0151073 0.021361 -0.0398815 -0.0151042 0.00739024 -0.0398789 -0.0142074 0.00722178 -0.0394515 -0.0138737 0.0209102 -0.0394148 -0.0125832 0.00590312 -0.0397101 -0.0125785 0.00589712 -0.0397116 -0.0132147 0.00664964 -0.0395087 -0.00453472 0.0190766 -0.0422771 -0.00966484 0.00249712 -0.0548142 -0.006735 0.0233858 -0.0536848 0.00643253 0.0176971 -0.0472285 0.00594943 0.00249712 -0.0485399 0.00594492 0.0180543 -0.0485451 0.00578306 0.0181875 -0.0487116 0.00635681 0.0176971 -0.0466912 0.00635681 0.00249712 -0.0466912 0.00586966 0.00249712 -0.0458455 0.00504027 0.00249712 -0.045331 -0.0114785 0.00589712 -0.054192 -0.0126885 0.00589712 -0.0475167 -0.0138676 0.00589712 -0.0408358 -0.0138676 0.00449712 -0.0408358 -0.000970051 -0.00729576 -0.107454 -0.00196112 -0.00740288 -0.108076 0.000441602 -0.00590288 -0.106569 0.000437452 -0.00590888 -0.106571 4.43602e-05 -0.00645289 -0.106818 0.00533746 -0.0230568 -0.103499 -0.000780581 -0.00720499 -0.107335 -0.00563232 -0.0244234 -0.0862683 -0.00332002 -0.00590288 -0.0874397 -0.00536399 -0.00740288 -0.0864042 -0.00480645 -0.00729576 -0.0866867 -0.00445051 -0.00711348 -0.086867 -0.00376991 -0.00649071 -0.0872118 0.0124777 -0.0238014 -0.0954426 -0.00332439 -0.00590888 -0.0874375 0.0130173 -0.0237591 -0.0958423 0.0133938 -0.0237003 -0.0963975 0.0135083 -0.023666 -0.0967187 0.0135465 -0.00250288 -0.0975565 0.0127777 -0.0234374 -0.0988238 0.0132378 -0.00250288 -0.0983364 0.0132396 -0.0234913 -0.0983336 -0.00106731 -0.00590288 -0.105932 -0.00106731 -0.00450288 -0.105932 0.013496 -0.00250288 -0.170856 0.0227301 -0.0187445 -0.160721 0.013496 -0.00590288 -0.170856 0.0126398 -0.00711587 -0.171796 0.0134927 -0.00590888 -0.17086 0.0128497 -0.00690742 -0.171566 0.014625 -0.0193795 -0.15186 0.0224573 -0.0189942 -0.157778 0.0091735 -0.00653348 -0.147741 0.0156218 -0.00250288 -0.185389 0.0289219 -0.0171998 -0.196669 0.0156218 -0.00530288 -0.185389 0.0156179 -0.00531019 -0.185386 0.0129596 -0.00730288 -0.183131 0.0134647 -0.00730288 -0.18356 0.0171918 -0.017578 -0.186721 0.0140367 -0.00717879 -0.184045 0.0143079 -0.00703028 -0.184275 0.0145768 -0.00681958 -0.184503 0.0151692 -0.00609338 -0.185005 0.0276332 -0.0173112 -0.195576 0.0282742 -0.0172767 -0.19612 0.0266982 -0.0174461 -0.249412 0.0179671 -0.0176673 -0.256266 0.0163784 -0.00714436 -0.257513 0.0144405 -0.0176189 -0.259034 0.0176637 -0.0176759 -0.256504 0.0174188 -0.00590288 -0.256696 0.017415 -0.00590888 -0.256699 0.0184897 -0.00250288 -0.225374 0.0160005 -0.00740288 -0.223342 0.0167148 -0.00740288 -0.223925 0.0166187 -0.0170068 -0.223847 0.0173869 -0.00719596 -0.224474 0.0295182 -0.0171039 -0.234378 0.0177463 -0.00690742 -0.224767 0.0180836 -0.00651176 -0.225043 0.0126505 -0.00740288 -0.268526 0.0146293 -0.0181549 -0.270755 0.014969 -0.00740288 -0.271138 0.0153838 -0.00729576 -0.271606 0.0155692 -0.00717791 -0.271815 0.0158064 -0.00695947 -0.272082 0.0164898 -0.00250288 -0.272852 0.0294191 -0.0188308 -0.287422 0.0137222 -0.0200939 -0.302197 0.0342776 -0.0195388 -0.301544 0.0131491 -0.00690742 -0.302215 0.0126854 -0.00719596 -0.302229 0.0118182 -0.00740288 -0.302257 -0.000322399 -0.0205681 -0.302642 0.0141084 -0.00590288 -0.302184 0.0136415 -0.00645091 -0.302199 0.0231624 -0.0197716 -0.301897 -0.0143057 -0.0232384 -0.0524497 -0.0138308 -0.00740288 -0.0534975 -0.0119596 -0.0071773 -0.0548916 -0.0122173 -0.0072753 -0.0548006 -0.0128814 -0.00740108 -0.0544497 -0.0126958 -0.0235144 -0.0545667 -0.0130096 -0.0234888 -0.054359 -0.0109015 -0.00647606 -0.0550484 -0.0112085 -0.0235687 -0.0550368 -0.0110585 -0.00661165 -0.0550458 -0.0132147 -0.020759 -0.0395087 -0.013675 -0.00699866 -0.0394196 -0.0142074 -0.00722754 -0.0394515 -0.014094 -0.0209835 -0.0394326 -0.014208 -0.0210208 -0.0394517 -0.0146779 -0.00734405 -0.0396063 -0.0151044 -0.0213655 -0.039879 -0.0153134 -0.00740288 -0.0400812 -0.0158173 -0.021797 -0.041271 -0.0152865 -0.0214477 -0.0400517 0.00228653 -0.0205834 -0.0502071 -0.000526403 -0.0223023 -0.0512914 0.00418607 -0.0177029 -0.0450585 -0.00847161 -0.0199652 -0.0410215 -0.0132147 -0.00665541 -0.0395087 -0.00178535 -0.0184603 -0.043154 0.00267498 -0.0177641 -0.0445766 -0.0125832 -0.00590888 -0.0397101 0.00504027 -0.0177029 -0.045331 0.00586966 -0.00250288 -0.0458455 0.00635681 -0.00250288 -0.0466912 0.00638569 -0.00250288 -0.0476668 0.00594943 -0.00250288 -0.0485399 0.00626628 -0.0178107 -0.0480348 -0.0114785 -0.00450288 -0.054192 0.0416493 -2.88296e-06 -0.357492 -0.0197263 0.00112713 -0.312345 -0.0233386 -2.88296e-06 -0.315916 -0.0221422 0.015681 -0.316837 -0.0177921 0.0176843 -0.313627 -0.0165321 0.0204636 -0.314305 -0.019297 0.0227232 -0.319063 -0.014349 0.0228054 -0.315201 -0.0160228 0.0252979 -0.321606 -0.011713 0.0240213 -0.316239 -0.00660242 0.0251438 -0.318686 -0.00449338 0.0256 -0.321911 -0.0114894 0.0266179 -0.325165 -0.00414371 0.0257258 -0.322966 -0.00268211 0.0258442 -0.324742 -0.00188017 0.0267007 -0.332693 0.00771581 0.0267478 -0.340202 0.00607542 0.0259566 -0.331604 0.0251181 0.0261181 -0.346513 0.0169508 0.0267875 -0.347428 0.0242868 0.0267959 -0.353167 0.0268042 0.0261021 -0.347428 0.0295216 0.0263619 -0.357241 0.0386093 0.0230114 -0.346916 0.0320355 0.0250814 -0.359192 0.0406001 0.0149942 -0.35673 0.0376956 0.0129136 -0.3636 0.0384741 -2.88296e-06 -0.364209 0.0509418 -2.88296e-06 -0.302646 0.0496735 0.013695 -0.302416 0.0492855 0.0144875 -0.302345 0.0472785 0.0171458 -0.301981 0.0429324 0.0203536 -0.312348 0.0453737 0.0186241 -0.301635 0.0459278 0.0182616 -0.301736 0.0407559 0.0203555 -0.304429 0.0419949 0.0202058 -0.305543 0.0439811 0.0193423 -0.301382 0.0240777 0.0206151 -0.303365 0.0322512 0.0204855 -0.30375 0.0218169 0.0205978 -0.302662 0.0164163 0.0207782 -0.302817 -0.000363798 0.0213371 -0.303254 0.00734041 0.0212843 -0.30387 0.00532746 0.0213046 -0.303148 0.00775131 0.0211419 -0.303076 0.0139895 0.0208723 -0.302884 -0.00325642 0.0184632 -0.298813 -0.00255824 0.0206853 -0.302369 -0.00472953 0.0226205 -0.309437 -0.000213214 0.0179977 -0.29336 -0.00167932 0.0181539 -0.29612 -0.0035454 0.0163473 -0.296792 -0.00486675 0.0127127 -0.296493 -0.00359978 0.00855845 -0.292745 -0.00772252 0.00995271 -0.299939 -0.0192898 0.00816164 -0.312606 -0.0194386 0.00174631 -0.312091 -0.018837 0.00244027 -0.311535 -0.00423017 0.0252615 -0.319951 -0.013162 0.0263706 -0.323845 0.0124092 0.0211846 -0.304645 0.044957 0.0194745 -0.316595 0.0408108 0.0222336 -0.329531 0.0391608 0.0230495 -0.332952 0.0424807 0.0213268 -0.331968 0.0329543 0.0253152 -0.343959 0.031038 0.0257564 -0.346313 0.0303423 0.0258869 -0.347061 0.0295682 0.0259702 -0.347461 -0.0121651 0.0154421 -0.307057 -0.0134208 0.006132 -0.306345 -0.00239575 0.0180568 -0.29704 -0.0045219 0.018787 -0.300824 -0.00572506 0.017061 -0.300524 -0.00546386 0.00924662 -0.296345 -0.00709094 0.0134231 -0.300147 -0.00369777 0.00699712 -0.292728 0.0499098 0.0106829 -0.317861 0.0491851 0.014027 -0.317648 0.0474729 0.0170887 -0.317217 0.0450157 0.0189213 -0.33284 0.0417956 0.0216336 -0.325945 0.043456 0.0141525 -0.34936 0.0425861 0.017636 -0.348859 0.00146199 0.023697 -0.314285 0.00113674 0.0231245 -0.311561 -0.00808272 0.0215543 -0.308425 -0.0108098 0.0187595 -0.30759 -0.0128686 0.0121677 -0.306708 -0.018558 0.0147422 -0.313132 0.0476146 0.0122816 -0.333825 0.0467926 0.015801 -0.333472 0.0409179 0.0206496 -0.348029 0.0358877 0.0245801 -0.345553 -0.0192813 -0.00816465 -0.312597 0.0137754 -0.0208864 -0.30289 0.000989425 -0.0214175 -0.30324 -0.00354449 -0.0163528 -0.29679 -0.0170072 -0.00313291 -0.309745 -0.0182477 -0.00283353 -0.310973 -0.0038312 -0.00311963 -0.292703 -0.00356109 -0.00896255 -0.292752 -0.0048658 -0.0127182 -0.296491 -0.0054629 -0.00925215 -0.296343 -0.00167932 -0.0181597 -0.29612 -0.00360717 -0.01918 -0.300306 -0.00128267 -0.0212025 -0.303116 -0.00807721 -0.0215587 -0.308418 0.0257132 -0.0206453 -0.303939 0.0146212 -0.0210398 -0.304261 0.0240784 -0.0206206 -0.303362 0.0343207 -0.0203373 -0.302298 0.0409046 -0.0203494 -0.304527 0.0425652 -0.019837 -0.301125 0.0439811 -0.019348 -0.301382 0.0456534 -0.0184528 -0.301686 0.0474737 -0.0170936 -0.31721 0.0493515 -0.0143691 -0.302357 0.0506007 -2.88296e-06 -0.316066 0.0373799 -0.0156446 -0.363353 0.0406104 -0.0149975 -0.356707 0.0365011 -0.0190872 -0.362665 0.040925 -0.0206532 -0.348008 0.0345138 -0.0226937 -0.361118 0.0338375 -0.0234985 -0.360592 0.0315938 -0.0253807 -0.358849 0.0281142 -0.0267194 -0.356151 0.0204696 -0.0267865 -0.350179 0.0253831 -0.0261255 -0.34671 0.0251181 -0.0261239 -0.346513 0.0163572 -0.0261017 -0.339659 -0.00151982 -0.026708 -0.332975 -0.012093 -0.0265665 -0.324688 -0.00446715 -0.0256236 -0.322044 -0.00452654 -0.0254566 -0.320939 -0.0200101 -0.0216711 -0.318505 -0.0185497 -0.0147445 -0.313123 -0.0165237 -0.0204672 -0.314295 -0.0213781 -0.0186052 -0.317429 -0.0216062 -2.88296e-06 -0.314177 -0.0198545 -0.000417188 -0.312441 -0.0233331 -0.000307757 -0.31592 -0.0232321 -0.00355364 -0.315997 -0.0224972 -0.0130176 -0.316567 0.00734273 -0.0212893 -0.303866 0.0391608 -0.0230553 -0.332952 0.035894 -0.0245836 -0.345533 0.0329604 -0.0253184 -0.34394 0.0449579 -0.0194795 -0.316588 0.0424836 -0.0213309 -0.331954 -0.0033278 -0.0199304 -0.301322 -0.0108047 -0.0187636 -0.307584 -0.00572291 -0.0170661 -0.30052 -0.00708877 -0.0134281 -0.300143 -0.00451978 -0.018792 -0.30082 -0.00239487 -0.0180623 -0.297038 0.0476176 -0.0122857 -0.333811 0.0499105 -0.0106881 -0.317853 0.0491858 -0.014032 -0.317641 0.0417956 -0.0216393 -0.325945 0.0444514 -2.88296e-06 -0.349949 0.0416594 -2.88296e-06 -0.357468 0.0434633 -0.0141557 -0.349339 0.0383367 -0.00444811 -0.364101 -0.00419506 -0.0252528 -0.319885 -0.00659101 -0.0251469 -0.318676 0.00114345 -0.0231283 -0.311554 -0.0117027 -0.0240252 -0.316229 -0.00472346 -0.0226249 -0.30943 -0.0143398 -0.0228096 -0.315192 -0.017784 -0.017687 -0.313618 -0.01216 -0.0154458 -0.307051 -0.0134155 -0.00613591 -0.306339 -0.00772032 -0.00995767 -0.299935 -0.0128634 -0.0121711 -0.306701 0.0483916 -2.88296e-06 -0.334237 0.0425934 -0.0176394 -0.348838 0.0467956 -0.015805 -0.333457 0.0450187 -0.0189253 -0.332826 0.038616 -0.023015 -0.346895 0.0401425 -0.0225894 -0.331085 -0.0242027 0.00310592 -0.0340742 -0.0251023 0.0031059 -0.0286743 -0.0258086 0.0167087 -0.0228554 -0.0259833 0.00310589 -0.0232712 -0.0277442 0.0155495 -0.0106817 -0.026425 0.00129261 -0.02072 -0.00450855 0.0149239 -0.131956 -0.0238904 0.0178736 -0.0343629 -0.0208158 0.00310578 -0.0534173 -0.0175438 0.00310557 -0.070811 -0.0141756 0.019591 -0.0862565 0.00345036 0.00311045 -0.175624 0.000323047 0.00310712 -0.156972 0.00559405 0.00311356 -0.192024 0.00646825 0.00311466 -0.20061 0.00586717 0.0103373 -0.192325 -0.0038312 0.00311386 -0.292703 0.00650082 0.0100427 -0.198392 0.00749444 0.00311509 -0.214945 0.00698569 0.00813409 -0.251308 0.00180254 0.00310077 -0.278362 0.00187626 0.00740026 -0.278226 0.0138916 0.00739712 -0.262643 0.0144952 0.00728294 -0.262169 0.0154179 0.00649562 -0.261445 0.0268515 0.0174917 -0.25247 0.0154502 0.00645199 -0.26142 0.0158187 0.00590312 -0.26113 0.0312173 0.0173928 -0.249043 0.0355831 0.0173051 -0.245616 0.0158226 0.00249712 -0.261127 0.0370687 0.0171943 -0.24445 0.0404778 0.0192078 -0.296118 0.0153727 0.00590312 -0.267827 0.0360339 0.0190074 -0.29111 0.0150742 0.00643177 -0.26749 0.0147115 0.0069328 -0.267082 0.0142321 0.00728294 -0.266541 0.0134634 0.0177173 -0.265675 0.0153759 0.00249712 -0.26783 0.0151788 0.00249712 -0.267493 0.0440659 0.00249712 -0.298824 0.0431003 0.00249712 -0.298718 0.0449674 0.00249712 -0.298462 0.0455922 0.00249712 -0.297718 0.045793 0.00249712 -0.296768 0.0398652 0.00249712 -0.244774 0.0380146 0.00249712 -0.244044 0.0402798 0.00249712 -0.245716 0.0370687 0.00249712 -0.24445 0.0438067 0.00249712 -0.271474 0.014969 0.00739712 -0.271138 0.0164898 0.00589712 -0.272852 0.0367844 0.019159 -0.295722 0.0294191 0.018825 -0.287422 0.0220537 0.0184938 -0.279122 0.0164865 0.00590312 -0.272848 0.0161786 0.00644713 -0.272501 0.0158064 0.0069537 -0.272082 0.0165892 0.018254 -0.272964 0.0153983 0.00728239 -0.271622 0.0141084 0.00589712 -0.302184 -0.000322399 0.00739712 -0.302642 0.00525724 0.0205144 -0.302465 0.0118182 0.00739712 -0.302257 0.0163632 0.0199844 -0.302113 0.0124429 0.00729 -0.302237 0.0126854 0.00719019 -0.302229 0.0141035 0.00590312 -0.302184 0.0144405 0.00739712 -0.259034 0.0160619 0.017682 -0.257761 0.0156165 0.00739712 -0.258111 0.0176637 0.0176701 -0.256504 0.0161081 0.00729 -0.257725 0.0161253 0.00728239 -0.257712 0.0163784 0.0071386 -0.257513 0.0174188 0.00249712 -0.256696 0.0174188 0.00589712 -0.256696 0.017415 0.00590312 -0.256699 0.0166639 0.00690166 -0.257289 0.0266982 0.0174403 -0.249412 0.017012 0.00649849 -0.257016 0.01705 0.00644713 -0.256986 0.0355591 0.0172271 -0.242457 0.0168854 0.00589712 -0.230644 0.0164551 0.00589712 -0.245017 0.0168574 -0.00450288 -0.226163 0.0168574 -0.00590288 -0.226163 0.0138916 -0.00740288 -0.262643 0.0158226 -0.00590288 -0.261127 0.0360027 -0.017303 -0.245287 0.0355831 -0.0173108 -0.245616 0.0312173 -0.0173986 -0.249043 0.0268515 -0.0174974 -0.25247 0.0197118 -0.0176838 -0.258075 0.0158187 -0.00590888 -0.26113 0.0370687 -0.0172001 -0.24445 0.0154304 -0.00648458 -0.261435 0.0422985 -0.0191188 -0.29817 0.0422985 -0.00250288 -0.29817 0.0153759 -0.00590288 -0.26783 0.021303 -0.0183544 -0.27451 0.0147115 -0.00693856 -0.267082 0.0143972 -0.00720192 -0.266727 0.0136935 -0.00740288 -0.265934 0.0286685 -0.0186809 -0.28281 0.0397166 -0.0191794 -0.29526 0.0449674 -0.00250288 -0.298462 0.0438067 -0.00250288 -0.271474 0.0153759 -0.00250288 -0.26783 0.0431003 -0.00250288 -0.298718 0.0455922 -0.00250288 -0.297718 0.0151257 -0.00250288 -0.267107 0.0155543 -0.00250288 -0.26145 0.0398652 -0.00250288 -0.244774 0.0370687 -0.00250288 -0.24445 0.0119418 -0.0179926 -0.176275 0.0234828 -0.00250288 -0.163607 0.0278642 -0.0173605 -0.192494 0.0134741 -0.00740288 -0.18029 0.0124723 -0.017807 -0.17944 0.0125046 -0.00740288 -0.179467 0.0121266 -0.017811 -0.179147 0.013244 -0.00250288 -0.180008 0.0269373 -0.00250288 -0.164645 0.0128811 -0.00250288 -0.177857 0.0128773 -0.00250288 -0.175248 0.0287296 -0.00250288 -0.192923 0.0311311 -0.00250288 -0.190643 0.0305349 -0.00250288 -0.192419 0.0266069 -0.00250288 -0.163817 0.00677964 -0.00740288 -0.142799 0.014048 -0.0195356 -0.148291 0.0218702 -0.00250288 -0.154201 0.00708809 -0.00740288 -0.143032 0.00671078 -0.00250288 -0.142432 0.0064537 -0.00250288 -0.141166 0.0236654 -0.00250288 -0.154516 0.0216313 -0.00250288 -0.129225 0.0210389 -0.00250288 -0.128617 0.021918 -0.00250288 -0.130024 0.0202476 -0.00250288 -0.128309 0.0298372 -0.00250288 -0.202412 0.0267392 -0.0171059 -0.205701 0.022933 -0.0170542 -0.209741 0.0172231 -0.0170081 -0.215802 0.0170417 -0.0170073 -0.215995 0.0304326 -0.0170871 -0.231897 0.0347587 -0.0171371 -0.235429 0.0351338 -0.0171354 -0.235735 0.0160983 -0.00740288 -0.220194 0.0160582 -0.0168824 -0.220162 0.0167942 -0.0169719 -0.220763 0.0168579 -0.00250288 -0.21619 0.0383719 -0.00250288 -0.23386 0.0351338 -0.00250288 -0.235735 0.0329322 -0.00250288 -0.202638 0.0369571 -0.00250288 -0.236107 0.0332654 -0.00250288 -0.203453 0.0357802 -0.00250288 -0.218404 -0.00590513 -0.00663792 -0.0796938 0.00915494 -0.0246687 -0.07204 -0.00659671 -0.00719675 -0.0800452 -0.0127926 -0.00740288 -0.0628281 -0.0126586 -0.0242667 -0.0636965 0.00984896 -0.00250288 -0.0714569 0.0102143 -0.00250288 -0.0706273 0.00900057 -0.00250288 -0.0684037 0.00915494 -0.00250288 -0.07204 -0.00993858 -0.00250288 -0.0619556 -0.00942228 -0.00250288 -0.061304 -0.00532608 -0.00250288 -0.0793995 -0.0143889 -0.00740288 -0.0520411 -0.00256388 -0.0213195 -0.118403 -0.00290545 -0.00740288 -0.116805 -0.00290545 -0.0214655 -0.116805 0.00551525 -0.00729054 -0.136519 0.00449672 -0.0203273 -0.137374 0.00550372 -0.00729576 -0.136528 0.00449672 -0.00740288 -0.137374 0.00677968 -0.00590288 -0.135457 0.0168295 -0.021145 -0.127016 0.00642063 -0.00645289 -0.135758 0.0106634 -0.0207285 -0.132195 0.00552042 -0.00728816 -0.136514 1.664e-05 -0.00740288 -0.114637 0.0020077 -0.00690742 -0.115735 0.0165091 -0.0215186 -0.123733 0.0022838 -0.00663296 -0.115888 0.00238481 -0.00651669 -0.115943 0.00284809 -0.00250288 -0.116199 0.0028438 -0.00590888 -0.116196 0.0172139 -0.00250288 -0.124385 0.00160155 -0.00250288 -0.116429 0.00139484 -0.00250288 -0.116832 0.0175337 -0.00250288 -0.12529 0.00331534 -0.00250288 -0.126217 0.00241152 -0.00250288 -0.116075 0.00580979 -0.00250288 -0.135636 0.00515779 -0.00250288 -0.134896 0.00677968 -0.00250288 -0.135457 -0.00850397 -0.0240744 -0.0884097 -0.0149579 -0.0155029 -0.0341131 -0.0159028 -0.0155029 -0.0338957 -0.0166353 -0.0203744 -0.0332583 -0.0166344 -0.0155029 -0.0332595 -0.0168213 -0.0203041 -0.0329297 -0.00276456 -0.021853 -0.115549 -0.000855076 -0.00740288 -0.114391 -0.00085508 -0.0222762 -0.114391 -0.000615489 -0.0222736 -0.114416 -0.00196112 -0.0226752 -0.108076 -0.00311926 -0.0226387 -0.108379 -0.00286953 -0.00740288 -0.108375 -0.0045763 -0.00740288 -0.107642 -0.00476377 -0.0223858 -0.107367 -0.00457563 -0.0224183 -0.107643 -0.00437289 -0.0224635 -0.107858 -0.00846671 -0.00740288 -0.08753 -0.00851182 -0.0241831 -0.0877414 -0.00846673 -0.0242295 -0.0875301 -0.00805532 -0.00740288 -0.0867516 -0.00830104 -0.0243255 -0.0871116 -0.0079545 -0.0244031 -0.0866424 -0.00756795 -0.0244238 -0.0863391 -0.00648606 -0.00740288 -0.086053 -0.0102186 -0.0239588 -0.0606153 -0.0108819 -0.0239482 -0.0605252 -0.0115395 -0.0239655 -0.0606596 -0.0108886 -0.00740288 -0.0605254 -0.0117004 -0.00740288 -0.0607303 -0.012117 -0.0240076 -0.0610052 -0.0127438 -0.00740288 -0.0619922 -0.0123573 -0.0240364 -0.0612497 -0.0127814 -0.0241371 -0.0621549 -0.0101719 -0.00740288 -0.0789545 -0.0101719 -0.0245733 -0.0789545 -0.0098078 -0.00740288 -0.0798072 -0.00995153 -0.0245756 -0.0795834 -0.00729445 -0.00740095 -0.0803998 -0.00793543 -0.0245972 -0.0805992 -0.00819588 -0.024597 -0.0806169 -0.00150189 -0.0201877 -0.302303 -0.00116723 -0.0203599 -0.302485 -0.00237177 -0.00740288 -0.300406 -0.00237289 -0.018395 -0.300416 0.00956013 -0.00740288 -0.268646 0.0102216 -0.0169446 -0.268084 0.0116037 -0.0175797 -0.267904 0.0122469 -0.0177877 -0.268178 0.0129613 -0.0174446 -0.264436 0.0130596 -0.00740288 -0.264973 0.0129673 -0.0174157 -0.264169 0.0130449 -0.0173971 -0.263769 0.0132018 -0.00740288 -0.263393 0.0125803 -0.0171333 -0.259361 0.0120043 -0.0168055 -0.25906 0.0118399 -0.016685 -0.258922 0.0118404 -0.00740288 -0.258922 0.0115358 -0.016415 -0.258562 0.0112212 -0.0159048 -0.257211 0.012736 -0.00740288 -0.224928 0.012923 -0.00740288 -0.224046 0.0134111 -0.0158838 -0.223393 0.0134785 -0.00740288 -0.223336 0.0140104 -0.0163154 -0.223027 0.0147491 -0.0166863 -0.222891 0.0151871 -0.0168342 -0.222943 0.0151914 -0.00740288 -0.222944 0.0154421 -0.016898 -0.22302 0.0160005 -0.016985 -0.223342 0.0158673 -0.00740288 -0.217241 0.0155451 -0.00740288 -0.219528 0.0156166 -0.0167622 -0.219656 0.0160512 -0.00740288 -0.220156 0.0157869 -0.00740288 -0.219893 0.0153273 -0.00740288 -0.218743 0.0153381 -0.01669 -0.218367 0.015441 -0.00740288 -0.217936 0.0125214 -0.00730288 -0.21339 0.0157097 -0.00730288 -0.213763 0.0149388 -0.00730288 -0.21427 0.0151996 -0.0169627 -0.214153 0.014022 -0.00730288 -0.214378 0.0131552 -0.0160342 -0.214062 0.0133785 -0.0161934 -0.214189 0.012268 -0.0152972 -0.212627 0.00968156 -0.01623 -0.184906 0.00969572 -0.0163657 -0.184313 0.00968156 -0.00730288 -0.184906 0.00987071 -0.0166391 -0.183775 0.00979047 -0.00730288 -0.183962 0.010323 -0.00730288 -0.183175 0.0120829 -0.0177325 -0.182701 0.0114154 -0.0176558 -0.182672 0.0111535 -0.0175762 -0.182723 0.0120388 -0.00740288 -0.179068 0.0115228 -0.0179093 -0.176989 0.0114253 -0.00740288 -0.17748 0.0115329 -0.00740288 -0.17696 0.0118392 -0.0179844 -0.176397 0.0118535 -0.00740288 -0.176378 0.0118814 -0.0179882 -0.176344 0.0113571 -0.0180845 -0.173204 0.0113571 -0.00740288 -0.173204 0.0106239 -0.00740288 -0.173713 0.00974219 -0.00740288 -0.173853 0.00948219 -0.0177702 -0.173818 0.00883895 -0.0174491 -0.173566 0.00807167 -0.0169998 -0.172714 0.00823058 -0.00740288 -0.17299 0.00823287 -0.0170858 -0.172994 0.00888767 -0.00740288 -0.173594 0.00362535 -0.00740288 -0.147924 0.00360267 -0.0189028 -0.147295 0.00367137 -0.0190376 -0.146967 0.00376732 -0.0191642 -0.14671 0.00415304 -0.00740288 -0.146145 0.00496084 -0.0197965 -0.145639 0.00532824 -0.019829 -0.145555 0.00591571 -0.00740288 -0.145566 0.00599316 -0.0198264 -0.14558 0.00679351 -0.00740288 -0.145943 0.00615392 -0.00740288 -0.142323 0.00622653 -0.0199544 -0.142381 0.00593614 -0.00740288 -0.142113 0.0056534 -0.00740288 -0.1417 0.00565335 -0.0200239 -0.141699 0.00549377 -0.0200672 -0.141278 0.00543287 -0.0201127 -0.140837 0.00544013 -0.0201364 -0.140608 0.00561204 -0.0202042 -0.139956 0.00560867 -0.00740288 -0.139964 0.00567198 -0.00740288 -0.139836 0.00599045 -0.0202627 -0.139399 0.00594712 -0.00740288 -0.139446 0.00614594 -0.00740288 -0.139254 0.00365801 -0.020283 -0.137792 0.00170934 -0.00740288 -0.137164 0.00143021 -0.0197262 -0.136754 0.00255655 -0.00740288 -0.137733 -0.000482654 0.0176165 -0.29683 0.00100788 0.0174378 -0.293984 0.00395028 0.0171975 -0.287344 0.0128773 0.00249712 -0.175248 0.0119418 0.00739712 -0.176275 0.0128773 0.00739712 -0.175248 0.0151669 0.0177103 -0.181725 0.0131793 0.00739712 -0.18004 0.0124723 0.0178012 -0.17944 0.0125046 0.00739712 -0.179467 0.0131301 0.00249712 -0.179662 0.0128811 0.00249712 -0.177857 0.0305349 0.00249712 -0.192419 0.0134741 0.00249712 -0.18029 0.0289769 0.00249712 -0.177476 0.0250956 0.00249712 -0.162958 0.0269373 0.00249712 -0.164645 0.0234828 0.00249712 -0.163607 0.00968156 0.00739712 -0.184906 0.0111777 0.00739712 -0.198429 0.0114318 0.015556 -0.201209 0.0179813 0.00540442 -0.211351 0.0160453 0.00739712 -0.213406 0.0168388 0.0170143 -0.212564 0.0225487 0.0170739 -0.206503 0.0165596 0.00727303 -0.21286 0.0168035 0.00712451 -0.212602 0.0263548 0.0171344 -0.202463 0.0174792 0.00635151 -0.211884 0.0176024 0.00614464 -0.211753 0.0134647 0.00739712 -0.18356 0.0152435 0.00606907 -0.185068 0.0146022 0.00689036 -0.184525 0.0145768 0.00691382 -0.184503 0.0171918 0.0175722 -0.186721 0.0256569 0.0173498 -0.1939 0.0218702 0.0191345 -0.154201 0.0140479 0.0195298 -0.148291 0.00677964 0.00739712 -0.142799 0.0234245 0.00249712 -0.141079 0.0064537 0.00249712 -0.141166 0.00619447 0.00249712 -0.139897 0.00618624 0.00249712 -0.139541 0.00630336 0.00249712 -0.139204 0.0227298 0.00249712 -0.154575 0.00708809 0.00249712 -0.143032 0.0186488 0.00249712 -0.128753 0.00588205 0.00739712 -0.159967 0.00596568 0.0177713 -0.16044 0.0113571 0.00739712 -0.173204 0.0119529 0.00739712 -0.17255 0.017044 0.0183908 -0.166962 0.0123885 0.00728239 -0.172072 0.0126398 0.0071101 -0.171796 0.0128026 0.0069537 -0.171617 0.0128497 0.00690166 -0.171566 0.0227301 0.0187388 -0.160721 0.00827907 0.00729 -0.147065 0.0077804 0.00739712 -0.146688 0.014625 0.0193738 -0.15186 0.0298372 0.0171536 -0.202412 0.0168579 0.00249712 -0.21619 0.0298372 0.00249712 -0.202412 0.0286426 0.0171322 -0.20368 0.0170417 0.0170015 -0.215995 0.0168579 0.00739712 -0.21619 0.022933 0.0170485 -0.209741 0.0170831 0.00249712 -0.220998 0.0351338 0.00249712 -0.235735 0.0160582 0.00739712 -0.220162 0.0160983 0.00739712 -0.220194 0.0167942 0.0169661 -0.220763 0.0167836 0.00739712 -0.220754 0.021833 0.0170131 -0.224876 0.0170831 0.00739712 -0.220998 0.0304326 0.0170813 -0.231897 0.0347587 0.0171314 -0.235429 0.0166557 0.00249712 -0.218587 0.0377864 0.00249712 -0.235626 0.0165868 0.00249712 -0.216919 0.0383719 0.00249712 -0.23386 0.0329322 0.00249712 -0.202638 0.0332654 0.00249712 -0.203453 0.0125808 0.0153964 -0.240445 0.0116922 0.0157516 -0.253071 0.0125479 0.00739712 -0.241215 0.0112212 0.00739712 -0.257211 0.0209186 0.0170219 -0.227357 0.0160005 0.00739712 -0.223342 0.0167148 0.00739712 -0.223925 0.0166187 0.017001 -0.223847 0.017199 0.00729 -0.22432 0.0173869 0.00719019 -0.224474 0.0184897 0.00589712 -0.225374 0.035589 0.00249712 -0.239334 -0.00729445 0.00739518 -0.0803998 -0.00675854 0.00726863 -0.0801275 -0.00651824 0.00714644 -0.0800054 -0.00532608 0.00589712 -0.0793995 -0.00533045 0.00590312 -0.0794017 -0.0127926 0.0242008 -0.0628281 -0.0127926 0.00739712 -0.0628281 -0.0125255 0.0243166 -0.0645543 -0.0116665 0.0245646 -0.0699713 -0.0101719 0.00739712 -0.0789545 -0.0101719 0.0245675 -0.0789545 -0.00859168 0.00249712 -0.061268 -0.0090109 0.00249712 -0.0611956 0.00974151 0.00249712 -0.068926 -0.00656968 0.00249712 -0.0791204 0.00900057 0.00249712 -0.0684037 0.00915494 0.00249712 -0.07204 -0.00834179 0.00249712 -0.07073 -0.00532608 0.00249712 -0.0793995 -0.00995005 0.00249712 -0.0623809 -0.00975136 0.00249712 -0.0615736 -0.0158054 0.0218692 -0.0416741 -0.0158054 0.00739712 -0.0416741 -0.000445319 0.00739712 -0.128234 0.00502513 0.00739712 -0.13693 0.0106634 0.0207227 -0.132195 0.00550372 0.00729 -0.136528 0.0168295 0.0211393 -0.127016 0.00551525 0.00728478 -0.136519 0.00552042 0.00728239 -0.136514 0.00604476 0.00690166 -0.136074 0.00642063 0.00644713 -0.135758 0.0168295 0.00249712 -0.127016 0.00677968 0.00589712 -0.135457 0.00677593 0.00590312 -0.13546 0.00138902 0.00729 -0.115394 1.664e-05 0.0222432 -0.114637 1.664e-05 0.00739712 -0.114637 0.00284809 0.00249712 -0.116199 0.0028438 0.00590312 -0.116196 0.0013878 0.00249712 -0.117286 0.0175337 0.00249712 -0.12529 0.00331534 0.00249712 -0.126217 0.0165091 0.00249712 -0.123733 0.00538619 0.00249712 -0.135352 0.00160155 0.00249712 -0.116429 -0.00850397 0.00739712 -0.0884097 -0.00498422 0.022401 -0.106777 -0.0169809 0.0154971 -0.032354 -0.0176469 0.0154971 -0.0267175 -0.0177205 0.0186375 -0.0260764 -0.0183419 0.0154971 -0.0205053 -0.0180528 0.018187 -0.0231337 -0.0178581 0.0154971 -0.0248678 -0.0167972 0.0203108 -0.0329815 -0.0166354 0.0203686 -0.0332582 -0.0158876 0.0204055 -0.0339034 -0.0159028 0.0154971 -0.0338957 -0.0149579 0.0154971 -0.0341131 -0.0146752 0.0201168 -0.0340876 -0.00085508 0.0222704 -0.114391 -0.00128528 0.0222668 -0.114417 -0.00180422 0.022246 -0.11458 -0.00288798 0.0217028 -0.115897 -0.00293591 0.02161 -0.116157 -0.00476377 0.02238 -0.107367 -0.00437289 0.0224577 -0.107858 -0.00311926 0.0226329 -0.108379 -0.00381321 0.00739712 -0.108219 -0.00316842 0.0226328 -0.108376 -0.00382807 0.0225707 -0.108212 -0.00258001 0.0226391 -0.108332 -0.00286953 0.00739712 -0.108375 -0.00196112 0.00739712 -0.108076 -0.00196112 0.0226695 -0.108076 -0.00648606 0.00739712 -0.086053 -0.00694355 0.0244334 -0.0860943 -0.00756795 0.0244181 -0.0863391 -0.0079545 0.0243973 -0.0866424 -0.00830104 0.0243198 -0.0871116 -0.00850397 0.0240687 -0.0884097 -0.00846671 0.00739712 -0.08753 -0.012741 0.0241128 -0.0619821 -0.0127438 0.00739712 -0.0619922 -0.010431 0.00736535 -0.0605614 -0.0108275 0.00739712 -0.0605241 -0.0119825 0.0239892 -0.0608996 -0.0117005 0.0239685 -0.0607304 -0.0108886 0.00739712 -0.0605254 -0.0108886 0.0239425 -0.0605254 -0.0107174 0.0239425 -0.0605265 -0.0073702 0.00739712 -0.0804364 -0.00819588 0.0245912 -0.0806169 -0.00909831 0.00739712 -0.0804041 -0.00923138 0.0246049 -0.0803308 -0.00924611 0.0246053 -0.0803218 -0.0098078 0.00739712 -0.0798072 -0.0098078 0.0245823 -0.0798072 -0.00209179 0.0179421 -0.299599 -0.00209179 0.00739712 -0.299599 -0.00237177 0.00739712 -0.300406 -0.00237311 0.0183908 -0.300418 -0.00238427 0.0186554 -0.300723 -0.00229036 0.0191664 -0.301254 -0.00219137 0.0194131 -0.301504 -0.00178667 0.0199637 -0.302071 -0.00186031 0.00739712 -0.301995 -0.00115828 0.0203578 -0.302488 0.0126505 0.0178947 -0.268526 0.0115 0.017536 -0.267883 0.0108395 0.0172593 -0.267878 0.0101997 0.0169264 -0.268096 0.0096443 0.0165945 -0.268542 0.00956013 0.00739712 -0.268646 0.00919695 0.0164008 -0.269444 0.0137244 0.0175002 -0.262774 0.0132018 0.00739712 -0.263393 0.0130159 0.0173932 -0.263875 0.0129674 0.00739712 -0.264168 0.0131278 0.0175736 -0.265151 0.0130596 0.00739712 -0.264973 0.0134634 0.00739712 -0.265675 0.0112212 0.015899 -0.257211 0.0112361 0.0160216 -0.257809 0.0114153 0.0162777 -0.258353 0.0113249 0.00739712 -0.258141 0.0123703 0.0170224 -0.259278 0.0126547 0.00739712 -0.259384 0.0126501 0.0171595 -0.259382 0.0151879 0.0168287 -0.222943 0.0142896 0.00739712 -0.222942 0.0141938 0.0164171 -0.222966 0.0134785 0.00739712 -0.223336 0.0136078 0.016034 -0.22324 0.012736 0.0152041 -0.224928 0.0128268 0.0153146 -0.224295 0.0129258 0.0154227 -0.22404 0.0157785 0.00739712 -0.217342 0.0157064 0.00739712 -0.217435 0.0153273 0.0166691 -0.218743 0.0153868 0.0166833 -0.219113 0.0155451 0.00739712 -0.219528 0.0156451 0.0167652 -0.219701 0.015765 0.00739712 -0.219866 0.0122573 0.00739712 -0.212506 0.0125238 0.0155044 -0.213394 0.0126268 0.015596 -0.213554 0.0131547 0.00739712 -0.214062 0.0143986 0.0167316 -0.214386 0.0156202 0.0170037 -0.213852 0.0149388 0.00739712 -0.21427 0.0157097 0.0170068 -0.213763 0.0121093 0.00739712 -0.182706 0.012048 0.0177269 -0.182693 0.0108261 0.0174267 -0.182842 0.00969572 0.01636 -0.184313 0.010323 0.00739712 -0.183175 0.00987071 0.0166334 -0.183775 0.0119418 0.0179868 -0.176275 0.0118814 0.0179824 -0.176344 0.0118535 0.00739712 -0.176378 0.0115415 0.00739712 -0.176936 0.0114394 0.0178544 -0.177345 0.0115329 0.00739712 -0.17696 0.0114243 0.00739712 -0.17775 0.0116953 0.0177867 -0.178634 0.0121266 0.0178052 -0.179147 0.0120388 0.00739712 -0.179068 0.00888767 0.00739712 -0.173594 0.00974219 0.00739712 -0.173853 0.00973726 0.0178618 -0.173852 0.0106239 0.00739712 -0.173713 0.00679351 0.00739712 -0.145943 0.00591571 0.00739712 -0.145566 0.00553462 0.0198248 -0.145539 0.00532824 0.0198232 -0.145555 0.00496309 0.00739712 -0.145639 0.00367041 0.00739712 -0.14697 0.00363704 0.0189741 -0.147098 0.00362535 0.00739712 -0.147924 0.00607291 0.00739712 -0.139318 0.00565763 0.0200173 -0.141708 0.00543287 0.00739712 -0.140837 0.00543287 0.0201069 -0.140837 0.00547088 0.0201529 -0.140394 0.00560863 0.0201977 -0.139964 0.00606444 0.0199625 -0.142244 0.00146714 0.0197281 -0.136823 0.00170934 0.00739712 -0.137164 0.00183828 0.0198475 -0.137298 0.00255655 0.00739712 -0.137733 0.00255497 0.0200918 -0.137732 0.00449672 0.00739712 -0.137374 0.00357393 0.00739712 -0.137809 -0.0103456 -0.00330288 -0.330592 -0.00904574 -0.00286077 -0.331608 0.0260055 -0.0244808 -0.359014 -0.00809419 0.00164712 -0.332352 -0.0225902 -0.0158891 -0.321018 -0.0116454 -0.00286077 -0.329576 -0.0228013 -0.0146461 -0.320853 -0.012597 -0.00165288 -0.328832 -0.0236066 -0.00575889 -0.320223 -0.0129453 -2.88298e-06 -0.328559 -0.0238203 -2.883e-06 -0.320056 -0.012597 0.00164712 -0.328832 -0.0116454 0.002855 -0.329576 -0.0168136 -0.0237962 -0.325535 -0.0200059 -0.0215875 -0.323039 -0.017294 -0.0235743 -0.325159 0.0214023 0.0245534 -0.355415 0.00828547 0.0063191 -0.345159 -0.00809419 -0.00165288 -0.332352 -0.0188039 0.0226447 -0.323978 -0.021611 0.0189616 -0.321784 -0.0192716 0.0222771 -0.323613 0.0204221 -0.0245569 -0.354649 0.00828547 -0.00632487 -0.345159 0.013355 -0.0245647 -0.349123 0.00541006 -0.00730288 -0.342911 0.00559037 -0.0245459 -0.343052 0.00253466 -0.00632487 -0.340663 0.000429716 -0.00365288 -0.339017 0.0308318 -0.0216361 -0.362788 0.0288659 -0.023352 -0.361251 0.0103904 -0.00365288 -0.346805 0.0287276 0.023433 -0.361143 0.0329994 -0.0177831 -0.364483 0.0311536 0.0212398 -0.363039 0.00541006 0.00729712 -0.342911 0.00253466 0.0063191 -0.340663 0.00489282 0.0245381 -0.342507 -0.00346959 0.0245205 -0.335968 -0.0103456 0.00329712 -0.330592 0.0328807 0.018111 -0.36439 0.033725 0.0141852 -0.36505 -0.0172412 0.0154971 -0.0204911 0.00796573 0.0154971 0.0343053 0.0100196 0.0154971 0.0358801 0.0115959 0.0154971 0.0379328 0.0123472 0.0154971 0.0154747 -0.0132971 0.0154971 0.0451049 -0.00656363 0.0154971 0.0454627 -0.00857946 0.0154971 0.043315 -0.0123545 0.0154971 -0.0154767 -0.0125575 0.0154971 -0.0177892 -0.0152613 0.0154971 -0.0185127 -0.0213398 0.0154971 0.00803687 -0.012343 0.0154971 0.0154838 -0.00656554 0.0154971 0.0403307 -0.0040012 0.0154971 0.0358853 -0.00440239 0.0154971 0.0193042 0.000442269 0.0154971 0.0333177 0.00300813 0.0154971 0.0329789 0.00557424 0.0154971 0.0333158 0.012926 0.0154971 0.0428894 0.0186454 0.0154971 0.0507341 0.0168273 0.0154971 0.0545247 0.0115996 0.0154971 0.047847 0.0137217 0.0154971 0.0573625 -0.00194211 0.0154971 0.0514809 -0.00612228 0.0154971 0.0560803 -0.00179223 0.0154971 0.0581985 0.00301549 0.0154971 0.0528073 -0.00859711 0.0154971 0.0426962 -0.00048819 -0.0142029 0.0428944 0.00126293 -0.0142029 0.0459249 0.00301311 -0.0142029 0.0463931 0.00476293 -0.0142029 0.0459236 0.00651181 -0.00550288 0.0428918 0.00604225 -0.00550288 0.041142 0.00476068 -0.00550288 0.0398614 0.00301051 -0.00550288 0.0393931 -1.99281e-05 -0.0142029 0.0411443 -1.86293e-05 0.00549712 0.0446443 0.00126293 0.0141971 0.0459249 0.00604225 0.0141971 0.041142 0.00476068 0.0141971 0.0398614 0.00476068 0.00549712 0.0398614 0.00126069 0.00549712 0.0398627 0.00301051 0.0141971 0.0393931 0.00126069 0.0141971 0.0398627 -0.00048819 0.0141971 0.0428944 0.0117382 -0.0148151 0.0590596 0.0148114 -0.0106677 0.0575679 0.0152055 -0.0148151 0.0571832 0.0174509 -0.0106677 0.0549804 0.0191615 -0.0106677 0.0517039 0.0193914 -0.0148151 0.0506336 0.019776 -0.0106677 0.0480591 0.0197036 -0.0148151 0.0480591 0.0115016 -0.0106677 0.0592131 0.0141635 -0.00652033 0.0580824 0.0191586 -0.00652033 0.0519335 0.0198484 -0.00652033 0.0480591 0.00784536 -0.0106677 0.059755 0.0028456 -0.0106677 0.0597062 -0.0055371 -0.0148151 0.0572873 -0.000290627 -0.0148151 0.0593056 -0.0066647 -0.00652033 0.0567319 -0.00273417 -0.00652033 0.0587717 -0.00662382 -0.0106677 0.0566721 -0.00211853 -0.0106677 0.0589052 -0.00766616 -0.00652033 0.0559746 -0.0102673 -0.0106677 0.0532067 -0.0183282 -0.00594581 0.0341746 -0.0190918 -0.00254119 0.0323161 -0.0274225 -2.88296e-06 0.0103284 -0.0191284 -2.88296e-06 0.0323446 -0.0146451 -0.0152555 0.0434902 -0.0127907 -0.00652033 0.0488451 -0.0127232 -0.0106677 0.0488189 -0.013952 -0.0148151 0.0453517 0.0203443 -2.88296e-06 -0.0326785 0.0203416 -0.00252033 -0.027114 0.0203335 -0.00304836 -0.0269861 0.0203239 -0.00546844 -0.0231757 0.0203274 -0.00574578 -0.0221724 0.0203703 -0.00652033 -0.00830286 0.0203596 -0.00652033 -0.0151652 0.0202016 -0.0148151 -0.00307213 -0.0140263 -0.0185029 0.0366095 -0.0243624 -0.0185029 0.00917291 -0.0255965 -0.0185029 0.00474418 -0.0190424 -0.0185029 -0.0197734 -0.0225946 -0.0185029 -0.00570528 -0.0257454 -0.0185029 -0.00385725 -0.0260294 -0.0185029 0.000410813 -0.025752 -0.0181096 0.00969625 -0.0140322 -0.0185029 0.0366212 -0.0149405 -0.0180996 0.0384443 -0.0153174 -0.0173134 0.0399675 0.0197964 -0.0169361 -7.63116e-06 0.0196983 -0.0170723 0.00196667 0.0201832 -0.0156668 -0.0028881 0.0197554 -0.017033 -0.0014426 0.0197605 -0.017033 -0.0190802 0.0201266 -0.016082 -0.00232105 0.0204989 -0.0155552 -0.061086 0.0202707 -0.0155552 -0.0541689 0.0196771 -0.0175305 -0.060227 0.0187566 -0.0181096 -0.05421 0.0178895 -0.0184625 -0.0583598 0.018882 -0.018131 -0.0593962 0.0186649 -0.0181096 -0.0190727 0.0186142 -0.0181535 -0.00674007 0.0196959 -0.0171371 -0.00199295 0.0197438 -0.0170523 -0.00144272 0.0198518 -0.017033 -0.0541802 0.0201795 -0.0155552 -0.0190831 0.0198484 0.00651457 0.0480591 0.0201873 0.0148093 -0.00143851 0.0148114 0.010662 0.0575679 0.017979 0.00651457 0.0543415 0.019776 0.010662 0.0480591 0.0115016 0.010662 0.0592131 0.0140867 0.0148093 0.0579597 0.0173892 0.0148093 0.054942 0.0174509 0.010662 0.0549804 0.0191615 0.010662 0.0517039 0.0028456 0.010662 0.0597062 0.00784536 0.010662 0.059755 -0.0127232 0.010662 0.0488189 -0.0102673 0.010662 0.0532067 -0.0103857 0.00651457 0.0531718 -0.00662382 0.010662 0.0566721 -0.00211853 0.010662 0.0589052 -0.00200183 0.0148093 0.0588662 0.00284557 0.0148093 0.0596338 -0.0127907 0.00651457 0.0488451 -0.013952 0.0148093 0.0453517 -0.0183353 0.00592851 0.0341561 0.0203845 -2.88296e-06 -0.0272353 0.0201795 0.0155495 -0.0190831 0.0202707 0.0155495 -0.0541689 0.0203357 0.0028837 -0.0270462 0.0203632 0.00124829 -0.027175 0.0203703 0.00651457 -0.00830286 0.0206405 0.00777488 -0.061234 -0.0114725 0.0184971 0.0356474 -0.0218077 0.0184971 0.00821314 -0.0232803 0.0184971 -0.00104436 -0.0249424 0.0184971 -0.00916255 -0.0241229 0.0184971 -0.0144653 -0.0165996 0.0225835 -0.0411038 -0.0171481 0.0207813 -0.0330619 -0.016555 0.0225389 -0.0408024 -0.0128016 0.0214969 -0.0385056 -0.0144782 0.0205798 -0.0344328 -0.0160067 0.0208737 -0.0342096 -0.00892342 0.0201338 -0.0377691 -0.00761263 0.0200304 -0.0386443 -0.00403896 0.0197847 -0.0412415 -0.00218923 0.018933 -0.0404542 0.00240467 0.0184971 -0.0421812 0.00200131 0.0186406 -0.043342 -0.0181244 0.0191181 -0.0260314 -0.0173753 0.0206026 -0.0322779 -0.0217157 0.0199993 -0.0267331 -0.0230176 0.0189407 -0.0206312 0.0128574 0.0251598 -0.067076 0.0157382 0.0244182 -0.0676294 0.0153254 0.0241939 -0.0668305 0.0137263 0.0249939 -0.0672099 0.0155691 0.0250547 -0.068941 0.00659524 0.0132755 -0.192372 0.0039054 0.0155172 -0.278444 -0.0138669 0.0250228 -0.0710685 -0.0174945 0.0238258 -0.0537121 -0.0159831 0.0240387 -0.0526142 -0.0189666 0.0223279 -0.0389152 -0.0220132 0.0211482 -0.0360985 -0.0234298 0.0195527 -0.0347888 -0.0200899 0.0213166 -0.0536684 -0.000725984 0.01743 -0.293267 0.00271607 0.0177914 -0.286834 0.00862063 0.0172662 -0.267904 0.0120414 0.018166 -0.263623 0.0104489 0.0180096 -0.267005 0.0119799 0.0182256 -0.264531 0.0123777 0.018532 -0.267346 0.0114448 0.0183091 -0.267025 0.0122296 0.0183539 -0.265411 0.0131538 0.0186873 -0.267943 0.0124231 0.018192 -0.262771 0.0130782 0.0182838 -0.262092 0.0156336 0.0185039 -0.26018 0.0148464 0.0184073 -0.259624 0.0165197 0.0184806 -0.25836 0.00995783 0.0165413 -0.257029 0.00894547 0.0165736 -0.262466 0.0102894 0.0169599 -0.258628 0.0109477 0.0177291 -0.262657 0.0108669 0.0173503 -0.25935 0.0162853 0.0178067 -0.214316 0.0151483 0.0176736 -0.216706 0.015806 0.0177681 -0.216075 0.0153012 0.0177268 -0.214954 0.0164594 0.0178015 -0.215449 0.0161447 0.0178033 -0.214442 0.0127832 0.0167414 -0.222591 0.0109578 0.0159126 -0.212591 0.0143918 0.0174522 -0.219328 0.013684 0.0171614 -0.222208 0.0147854 0.0175426 -0.220148 0.0154172 0.0176651 -0.220789 0.0162211 0.0177633 -0.221386 0.0164517 0.0177773 -0.222723 0.0171247 0.017801 -0.223224 0.00665396 0.0176074 -0.172393 0.00737321 0.0178481 -0.173819 0.00807499 0.0181577 -0.174342 0.00872078 0.0173008 -0.183512 0.00690256 0.0176489 -0.173166 0.00843973 0.0170022 -0.184268 0.0084064 0.0168564 -0.185099 0.0110265 0.0188467 -0.174448 0.0112661 0.0187816 -0.175869 0.0102248 0.0187805 -0.174675 0.0108641 0.0187392 -0.176395 0.0090817 0.0185231 -0.174678 0.0111822 0.0184372 -0.18193 0.0119552 0.0186005 -0.180083 0.01225 0.0185261 -0.181949 0.00928808 0.0177204 -0.182793 0.000100248 0.0204244 -0.136553 0.000415688 0.0204328 -0.137349 0.00399663 0.0204659 -0.145226 0.00453644 0.0208455 -0.141721 -0.00368335 0.0220261 -0.118708 -0.00102398 0.0209003 -0.131175 -0.00966977 0.0225613 -0.0992913 -0.00428641 0.023353 -0.109042 -0.00514314 0.0232148 -0.108565 -0.00781109 0.0240047 -0.0980373 -0.0107846 0.0248188 -0.0854536 -0.0133132 0.0251158 -0.0646401 -0.0101304 0.0253988 -0.0807339 -0.00966248 0.025405 -0.0810266 0.00474926 0.0184352 -0.160704 0.00326891 0.0174642 -0.159704 0.0058556 0.0103425 -0.192222 0.00258516 0.0117384 -0.168743 0.0101367 0.0161787 -0.201342 0.0083747 0.0157288 -0.192382 0.00819352 0.0126963 -0.209879 0.0100876 0.0153354 -0.209875 0.00973593 0.0139894 -0.227636 0.00831845 0.0123668 -0.245221 0.00274963 0.0128542 -0.278306 0.00187169 0.00739985 -0.278242 0.00636167 0.0125421 -0.262267 0.00740941 0.0147908 -0.262336 0.00927537 0.0142505 -0.245246 0.0106128 0.0158062 -0.245302 0.0109153 0.0153603 -0.227646 0.0114403 0.0158318 -0.224951 0.00390837 0.00760785 -0.270472 0.00552482 0.00782907 -0.26226 0.00553036 0.00782998 -0.262227 0.008853 0.0123968 -0.227633 0.00804354 0.00895253 -0.225352 0.00742426 0.00954412 -0.209772 -0.0184184 0.0200823 -0.0647277 -0.00459761 0.0177916 -0.128956 -0.0126281 0.0236103 -0.0854588 -0.013876 0.0217979 -0.0854544 -0.0155946 0.0238913 -0.0710845 -0.00773006 0.0238244 -0.0992916 -0.000753408 0.00718996 -0.285947 -0.00232708 0.0145159 -0.292976 0.00164154 0.0151555 -0.15969 -0.00312093 0.0199462 -0.128947 -0.0109833 0.0206561 -0.09929 -0.0167619 0.0221909 -0.0710912 -0.0190398 0.0228292 -0.0536846 0.0233217 0.0195374 -0.161306 0.0228916 0.0194327 -0.163113 0.0171216 0.0190906 -0.169442 0.0176356 0.0191897 -0.167543 0.0112083 0.0188508 -0.174359 0.0192196 0.0184776 -0.257419 0.0263588 0.0182913 -0.251818 0.0315588 0.0181466 -0.246595 0.034253 0.0179313 -0.236036 0.0291554 0.0179524 -0.201984 0.0185444 0.0178135 -0.213238 0.0223508 0.0178484 -0.209201 0.0382979 0.0201437 -0.299223 0.0384676 0.020074 -0.297789 0.0354413 0.0198065 -0.291604 0.0225498 0.0192286 -0.27708 0.0171913 0.0190533 -0.272399 0.0273469 0.0181544 -0.193126 0.0231142 0.0182596 -0.189539 0.0188818 0.018378 -0.185953 0.0177093 0.0183717 -0.186138 0.0126686 0.0185213 -0.182073 0.0176171 0.0245599 -0.0942536 0.0180279 0.024177 -0.0992935 0.0169263 0.0244341 -0.096865 0.0236355 0.0206192 -0.121343 0.0216847 0.021964 -0.120315 0.0215333 0.0219903 -0.12135 0.019472 0.0237082 -0.100603 0.0189046 0.0239441 -0.0998623 0.0195012 0.0221532 -0.125047 0.0227966 0.0211727 -0.129074 0.0222319 0.0214399 -0.128363 0.026235 0.0191059 -0.153035 0.0281558 0.018161 -0.164502 0.0273395 0.0185976 -0.163 0.0253664 0.0194979 -0.154563 0.023591 0.0195598 -0.160925 0.0235241 0.0195917 -0.160388 0.0234074 0.0196481 -0.159449 0.0243608 0.0194571 -0.162271 0.0233712 0.0196658 -0.159156 0.0232365 0.0197325 -0.158066 0.0231622 0.0197698 -0.157463 0.0230329 0.0198359 -0.156407 0.0234451 0.0198787 -0.155432 0.0307894 0.0176474 -0.193397 0.0330357 0.0169932 -0.201302 0.030015 0.0174096 -0.176093 0.0323846 0.0166695 -0.190463 0.0289908 0.0179738 -0.200847 0.0297467 0.0179447 -0.200119 0.0293666 0.0179701 -0.200485 0.0305262 0.0178026 -0.197478 0.0301301 0.0178841 -0.19665 0.0288507 0.0180686 -0.195521 0.0279417 0.0181438 -0.193513 0.0286667 0.0181093 -0.193725 0.0356123 0.0155009 -0.205107 0.0345321 0.0162037 -0.203259 0.0342617 0.0163275 -0.202473 0.0374147 0.0174265 -0.236831 0.0382962 0.0170326 -0.236452 0.0360955 0.0180644 -0.244216 0.0392402 0.017191 -0.243223 0.0378243 0.0172892 -0.237049 0.0364958 0.0177984 -0.238901 0.0408334 0.0153479 -0.237098 0.0373131 0.0176937 -0.240524 0.0402166 0.0167019 -0.243582 0.0408841 0.016321 -0.244107 0.0444319 0.0190689 -0.299599 0.0456534 0.0184471 -0.301686 0.0462732 0.0179015 -0.298782 0.0453775 0.0185403 -0.299362 0.0468578 0.0173879 -0.298004 0.0471038 0.017129 -0.297274 0.0461094 0.0167346 -0.280943 0.0454644 0.0160336 -0.270134 0.0457464 0.0166428 -0.277124 0.0432392 0.0161715 -0.25665 0.0398857 0.0200069 -0.296611 0.039796 0.0201975 -0.300623 0.0408654 0.0200001 -0.297632 0.0426904 0.0197967 -0.301148 0.019138 0.0241757 -0.0741449 0.0198947 0.0237205 -0.0822851 0.0180542 0.0249162 -0.082293 0.0172052 0.0252461 -0.0751168 0.0163217 0.0254262 -0.0739216 0.0176992 0.0250269 -0.0728146 0.0155717 0.0254721 -0.0733408 0.0209079 0.0228903 -0.0951879 0.0187339 0.0243392 -0.0927183 0.0183287 0.0244403 -0.0935476 0.0189895 0.0241371 -0.0951864 0.018821 0.024338 -0.0918229 0.0180003 0.0249419 -0.0820094 0.0506125 0.00958144 -0.302586 0.0493148 0.00914438 -0.277908 0.0486097 0.00905177 -0.271178 0.0476651 0.0128443 -0.270294 0.0428911 0.0124086 -0.237122 0.0457069 0.00888276 -0.24971 0.0375328 0.0127893 -0.205112 0.0338979 0.0109094 -0.178433 0.032741 0.0140826 -0.175409 0.0297618 0.0130031 -0.151667 0.0286013 0.0160833 -0.147796 0.0250569 0.0185484 -0.121331 0.0233872 0.0180941 -0.102231 0.022207 0.0210083 -0.0951924 0.0211405 0.021917 -0.0822872 0.0204828 0.0229407 -0.108618 0.0309794 0.0165849 -0.175385 0.0468662 0.016563 -0.286349 0.0491546 0.0132437 -0.286628 0.0195745 -0.0237867 -0.0745485 0.0172601 -0.0191134 -0.060316 0.0169092 -0.0210266 -0.0633867 0.0174943 -0.0239356 -0.0688794 0.015889 -0.0238878 -0.0667924 0.017381 -0.0247764 -0.0706282 0.0157382 -0.024424 -0.0676294 0.0164818 -0.0249974 -0.06979 0.0193823 -0.0189581 -0.0636499 0.017864 -0.0188164 -0.0602353 0.0182735 -0.0183766 -0.0587609 0.0183952 -0.0186997 -0.0607846 0.0189094 -0.018487 -0.0613196 0.0208369 -0.0218295 -0.0757159 0.0210226 -0.0197753 -0.0734199 0.0203604 -0.0215502 -0.0715988 0.0203089 -0.0197223 -0.0680728 0.0206876 -0.0167261 -0.0660128 0.0173277 -0.0188459 -0.0596766 0.0173802 -0.0185029 -0.0578275 0.0200486 -0.0170544 -0.0606154 0.0192248 -0.0210183 -0.0670142 0.017885 -0.0217381 -0.0657093 0.0182793 -0.0195397 -0.0625373 0.0193964 -0.018173 -0.0618273 0.0193472 -0.0178294 -0.0598826 0.0188949 -0.0181241 -0.0594098 0.019138 -0.0241815 -0.0741449 0.0190735 -0.0238455 -0.0722021 0.0204368 -0.0222083 -0.0734769 0.0190771 -0.023071 -0.0703797 0.0202733 -0.0178806 -0.064551 0.0202156 -0.0172014 -0.0626763 0.0203173 -0.0165116 -0.0608962 -0.00836647 -0.018794 -0.0337382 -0.00761263 -0.0200362 -0.0386443 -0.00541761 -0.0195677 -0.0393575 -0.00957654 -0.0197653 -0.0361233 -0.013655 -0.0202788 -0.0341479 0.00240467 -0.0185029 -0.0421812 0.00300734 -0.0185543 -0.0437275 -0.00899693 -0.0201298 -0.0376781 -0.0130622 -0.0215405 -0.0384404 -0.0153415 -0.0207942 -0.0344269 -0.0217157 -0.0200051 -0.0267331 -0.0163441 -0.0224297 -0.040154 -0.0150089 -0.0219855 -0.0387354 -0.0188206 -0.0185111 -0.0205797 -0.0230176 -0.0189465 -0.0206312 -0.017178 -0.0207747 -0.0329972 -0.0184894 -0.0186852 -0.0231272 0.0165253 -0.018855 -0.0588909 0.0168487 -0.0205851 -0.0626359 0.0181245 -0.0185148 -0.258278 0.0192196 -0.0184834 -0.257419 0.0350898 -0.0181106 -0.244969 0.0166408 -0.0178081 -0.215257 0.026157 -0.0179058 -0.205164 0.0291554 -0.0179582 -0.201984 0.0299269 -0.017887 -0.232507 0.0214246 -0.0178276 -0.226731 0.0213271 -0.0178188 -0.225491 0.0171247 -0.0178068 -0.223224 0.0170272 -0.0178025 -0.221983 0.0381529 -0.0200156 -0.29638 0.0378362 -0.0202033 -0.300267 0.0378326 -0.0202033 -0.300266 0.0207086 -0.0191537 -0.275006 0.0391245 -0.0199784 -0.295754 0.0176357 -0.0191954 -0.167543 0.0113505 -0.0187917 -0.175772 0.0228916 -0.0194385 -0.163113 0.0236318 -0.0194715 -0.162535 0.0110265 -0.0188525 -0.174448 0.0136885 -0.025063 -0.348696 -0.0233866 -0.00950176 -0.319689 -0.0216255 -0.0136954 -0.318677 -0.021388 -0.0154078 -0.318871 -0.02262 -0.0160174 -0.320278 -0.0213133 -0.015787 -0.318931 -0.0225894 -0.0161577 -0.320302 -0.0202739 -0.019094 -0.319745 -0.0216088 -0.0191967 -0.321067 -0.01909 -0.0212346 -0.320665 -0.0192458 -0.0226069 -0.322918 -0.0170835 -0.0240352 -0.324598 -0.016586 -0.024265 -0.324987 -0.0142705 -0.0243953 -0.324449 -0.0129393 -0.024686 -0.325482 -0.00886487 -0.0247965 -0.328652 -0.0116037 -0.0250021 -0.328906 0.00337918 -0.0248434 -0.338217 0.0148355 -0.0248913 -0.347168 0.0211154 -0.0248843 -0.352077 0.0294645 -0.0241437 -0.358627 0.0301496 -0.023772 -0.359167 0.0321482 -0.0221365 -0.36074 0.0293865 -0.0237951 -0.360948 0.0314428 -0.0220029 -0.362547 0.0319802 -0.021331 -0.362966 0.0341699 -0.0190518 -0.362329 0.0345051 -0.0182374 -0.362592 0.0337089 -0.0179793 -0.364313 0.0352416 -0.0153268 -0.363167 0.0353492 -0.0144686 -0.363251 0.0361628 -0.00468045 -0.363887 0.0343902 -0.0148725 -0.364847 0.0353981 -2.88296e-06 -0.365635 0.0350484 0.00802816 -0.365361 0.0363133 -2.88296e-06 -0.364005 0.0361744 0.00443223 -0.363897 0.0343124 0.0154611 -0.364786 0.0352758 0.0150754 -0.363194 0.0338299 0.0176003 -0.364407 0.0335849 0.0183221 -0.364216 0.0322309 0.0209705 -0.363161 0.0317794 0.0215893 -0.362809 0.0298023 0.023506 -0.361272 0.0292418 0.02388 -0.360836 0.0268494 0.0248754 -0.358979 0.0272989 0.0248267 -0.356917 0.0250112 0.0250813 -0.357555 0.0206046 0.0248785 -0.351678 0.0070797 0.0248542 -0.341108 -0.00313226 0.0250182 -0.335536 0.00330996 0.0248374 -0.338163 -0.0148252 0.0248154 -0.326371 -0.0112444 0.0247713 -0.326795 -0.0161451 0.0244356 -0.325332 -0.0152656 0.0240357 -0.323673 -0.018651 0.023073 -0.323378 -0.0177153 0.0226109 -0.321746 -0.0225848 0.0161725 -0.320305 -0.0197619 0.020149 -0.320142 -0.019472 0.0206546 -0.320367 -0.0197804 0.0221012 -0.322504 -0.0191392 0.0226912 -0.323 -0.0220855 0.00907786 -0.318317 -0.0227167 0.0155228 -0.320205 -0.0232295 0.0112023 -0.319811 -0.0234311 0.0089666 -0.319654 -0.0225417 -2.88296e-06 -0.317955 -0.0217785 -0.017062 -0.317844 -0.0224574 -0.0129499 -0.317314 -0.0231864 -0.00352671 -0.316744 0.00737633 0.0262508 -0.34064 0.0150774 0.0253831 -0.346662 0.0166116 0.0262901 -0.347861 0.0239529 0.0262982 -0.353601 -0.0232913 -2.88271e-06 -0.316662 -0.0225757 0.000732831 -0.317221 -0.0221287 0.00913053 -0.317571 -0.0226395 0.0111948 -0.317171 -0.0210584 0.0170581 -0.318408 0.00364958 0.0253345 -0.337726 -0.0219512 0.0163527 -0.317709 -0.0208655 0.019735 -0.318558 -0.0206586 0.020199 -0.31872 -0.0194318 0.0209574 -0.319679 -0.017947 0.0227245 -0.32084 -0.017566 0.0230339 -0.321138 -0.0170309 0.0243839 -0.321557 -0.0118219 0.0261235 -0.325629 -0.00222345 0.0262043 -0.333134 -0.0200481 -0.0213748 -0.319198 -0.0187673 -0.0219059 -0.320199 -0.0181881 -0.0235679 -0.320652 -0.0166476 -0.0236755 -0.321856 -0.0126307 -0.0251776 -0.324997 -0.00924793 -0.0261698 -0.327642 0.00371876 -0.0253406 -0.33778 0.0126064 -0.026287 -0.34473 0.0201302 -0.026289 -0.350612 0.0214523 -0.0253821 -0.351646 0.0268518 -0.0263263 -0.355868 0.0310681 -0.0249375 -0.359164 0.0332259 -0.0231244 -0.360852 0.0306665 -0.0242196 -0.35885 0.0327544 -0.0225139 -0.360483 0.0338764 -0.0223494 -0.36136 0.0333652 -0.0217982 -0.360961 0.0348658 -0.0192972 -0.362134 0.0359824 -0.0154171 -0.363007 0.0276883 0.02532 -0.356522 0.0290749 0.0258824 -0.357606 0.0308411 0.024106 -0.358987 0.0329001 0.0223486 -0.360597 0.0322724 0.0240426 -0.360106 0.0349575 0.019084 -0.362205 0.0352915 0.0182333 -0.362467 0.0348058 0.0209513 -0.362087 0.036057 0.0180955 -0.363065 0.0363486 0.0170443 -0.363293 0.0360179 0.0151562 -0.363035 0.0369489 0.0128484 -0.363762 0.0376572 0.00267978 -0.364316 0.0370605 -2.8832e-06 -0.36385 0.0369094 -0.00471084 -0.363732 0.0377243 -2.88271e-06 -0.364369 0.0370199 -0.0121645 -0.363818 0.0360923 -0.0145406 -0.363093 -0.0289807 -2.88296e-06 -0.0043391 -0.0291615 0.00777329 0.000610743 -0.0292972 -2.88296e-06 0.000614973 -0.0286397 0.00777329 0.00552429 -0.0287727 -2.88296e-06 0.00555136 -0.0288463 0.00777329 -0.00432037 -0.0285457 0.0155495 0.00529101 -0.027296 0.00777329 0.0102792 -0.0282974 0.0170272 -0.00423949 -0.0275141 0.0181039 0.000434307 -0.0272139 0.0181039 -0.00407718 -0.0281337 0.0170272 0.00521461 -0.0270564 0.0181039 0.00501488 -0.025752 0.0181039 0.00969625 -0.0255965 0.0184971 0.00474418 -0.0243624 0.0184971 0.00917291 -0.0290285 0.0155495 0.000458272 -0.0286095 0.0170272 0.000451641 -0.0260294 0.0184971 0.000410813 -0.0271694 0.0155495 0.0102301 -0.0267772 0.0170272 0.0100824 -0.0140263 0.0184971 0.0366095 0.0197554 0.0170272 -0.0014426 -0.0287118 0.0155495 -0.00430163 0.0187566 0.0181039 -0.05421 0.018882 0.0181252 -0.0593962 0.0201266 0.0160762 -0.00232105 0.0172144 0.0184971 -0.00977747 0.0190724 0.0178436 -0.0053061 0.017835 0.018432 -0.00859313 0.0197605 0.0170272 -0.0190802 0.0198518 0.0170272 -0.0541802 0.0186649 0.0181039 -0.0190727 0.0172723 0.0184971 -0.0542503 -0.0257454 0.0184971 -0.00385725 -0.0274932 0.0170273 -0.0095527 -0.0279075 0.0155495 -0.00961607 -0.0264102 0.0181039 -0.00938705 -0.0258683 0.0181265 -0.0126421 -0.0263267 0.0178788 -0.0121628 -0.0270038 0.0173164 -0.0114556 -0.0272248 0.0170467 -0.0112245 -0.0252469 0.0183494 -0.0132909 0.0213667 0.0100329 -0.0762052 0.0211758 0.0200687 -0.076029 0.0207821 -2.88296e-06 -0.0613818 0.0209415 -2.06829e-07 -0.0651335 0.0211242 -1.2971e-06 -0.0688843 0.0206458 0.0163034 -0.0649328 0.015889 0.023882 -0.0667924 0.0174943 0.0239298 -0.0688794 0.0156143 0.024877 -0.0685118 0.017885 0.0217324 -0.0657093 0.0168045 0.0223311 -0.0652648 0.0182793 0.0195339 -0.0625373 0.0172601 0.0191077 -0.060316 0.0203173 0.0165058 -0.0608962 0.0202156 0.0171956 -0.0626763 0.0203089 0.0197165 -0.0680728 0.0192248 0.0210125 -0.0670142 0.0190771 0.0230653 -0.0703797 0.0160681 0.0234901 -0.0663103 0.0204368 0.0222026 -0.0734769 0.0208369 0.0218238 -0.0757159 0.0206847 0.0166902 -0.0659395 0.0209998 0.0196571 -0.0729937 0.0203604 0.0215444 -0.0715988 0.0190735 0.0238398 -0.0722021 0.0195745 0.0237809 -0.0745485 0.017864 0.0188106 -0.0602353 0.0178895 0.0184567 -0.0583598 0.0182735 0.0183708 -0.0587609 0.0188949 0.0181183 -0.0594098 0.0193472 0.0178236 -0.0598826 0.0183952 0.018694 -0.0607846 0.0189094 0.0184812 -0.0613196 0.0193823 0.0189524 -0.0636499 0.0193964 0.0181672 -0.0618273 0.0196771 0.0175248 -0.060227 0.0200486 0.0170487 -0.0606154 0.0164818 0.0249917 -0.06979 0.0164502 0.02537 -0.0716599 0.017381 0.0247706 -0.0706282 0.0202733 0.0178748 -0.064551 0.0204989 0.0155495 -0.061086 -0.0231414 0.0202546 -0.0301318 -0.0247502 0.0185119 -0.0163594 -0.0252373 0.0183519 -0.013301 -0.0242079 0.0188691 -0.0194076 -0.0207593 0.0218588 -0.0372579 -0.0275812 0.0163901 -0.0108521 -0.0263374 0.0175572 -0.0171473 -0.0258782 0.018062 -0.0176396 -0.0268254 0.0174955 -0.011642 -0.0258535 0.0180691 -0.0151875 -0.0268136 0.0161182 -0.0166061 -0.02571 0.017545 -0.0227018 -0.0253412 0.0182774 -0.0230886 -0.0238663 0.0181986 -0.0343853 -0.0203283 0.0212645 -0.0328137 -0.0205345 0.0219486 -0.0374657 -0.0217721 0.0209588 -0.0314419 -0.0230215 0.0198397 -0.0254451 -0.0242722 0.0192939 -0.0241786 -0.0232682 0.0198268 -0.0349382 -0.0253534 0.0184363 -0.0181965 -0.026676 0.0169028 -0.0167721 0.0342489 -2.88296e-06 -0.178749 0.0344722 -2.88296e-06 -0.180123 0.03782 0.00966485 -0.202346 0.0390481 -2.88296e-06 -0.207701 0.0234741 -2.88296e-06 -0.0999463 0.0261027 0.0156499 -0.125406 0.0257472 -2.88296e-06 -0.120488 0.049641 -2.88296e-06 -0.279304 0.0442216 -2.88296e-06 -0.238654 -0.0291615 -0.00777906 0.000610743 -0.0286397 -0.00777906 0.00552429 -0.0285457 -0.0155552 0.00529101 -0.0288463 -0.00777906 -0.00432037 -0.027296 -0.00777906 0.0102792 -0.0275141 -0.0181096 0.000434307 -0.0272139 -0.0181096 -0.00407718 -0.0286095 -0.017033 0.000451641 -0.0282974 -0.017033 -0.00423949 -0.0287118 -0.0155552 -0.00430163 -0.0281337 -0.017033 0.00521461 -0.0267772 -0.017033 0.0100824 -0.0271694 -0.0155552 0.0102301 -0.0270564 -0.0181096 0.00501488 -0.0290285 -0.0155552 0.000458272 -0.0280715 -2.88296e-06 -0.0103397 -0.0249424 -0.0185029 -0.00916255 -0.0268254 -0.0175012 -0.011642 -0.0263267 -0.0178845 -0.0121628 -0.0258683 -0.0181323 -0.0126421 -0.0252469 -0.0183551 -0.0132909 -0.0279075 -0.0155553 -0.00961607 -0.0274932 -0.017033 -0.0095527 -0.0264102 -0.0181096 -0.00938705 0.0209572 -0.019406 -0.0721723 0.0206458 -0.0163091 -0.0649328 0.0206405 -0.00778065 -0.061234 0.0211758 -0.0200745 -0.076029 0.0213298 -2.38738e-06 -0.0726339 0.0215577 -2.88296e-06 -0.0763821 -0.0258535 -0.0180749 -0.0151875 -0.0247502 -0.0185177 -0.0163594 -0.0252373 -0.0183577 -0.013301 -0.0241229 -0.0185029 -0.0144653 -0.0238663 -0.0182044 -0.0343853 -0.0268136 -0.0161239 -0.0166061 -0.0275812 -0.0163958 -0.0108521 -0.026676 -0.0169085 -0.0167721 -0.0272248 -0.0170524 -0.0112245 -0.0270038 -0.0173221 -0.0114556 -0.0258782 -0.0180678 -0.0176396 -0.0217721 -0.0209646 -0.0314419 -0.0207593 -0.0218645 -0.0372579 -0.0232682 -0.0198325 -0.0349382 -0.0231414 -0.0202604 -0.0301318 -0.0203283 -0.0212703 -0.0328137 -0.0230215 -0.0198455 -0.0254451 -0.0242079 -0.0188748 -0.0194076 -0.0242722 -0.0192997 -0.0241786 -0.02571 -0.0175508 -0.0227018 -0.0263374 -0.017563 -0.0171473 -0.0253412 -0.0182832 -0.0230886 -0.0253534 -0.0184421 -0.0181965 -0.0264646 -0.00041165 -0.0205701 -0.0262682 -0.00250555 -0.0215659 -0.0277442 -0.0155553 -0.0106817 -0.0258086 -0.0167144 -0.0228554 0.000663651 -0.00310786 -0.281903 0.00187169 -0.00740561 -0.278242 0.00382533 -0.0031061 -0.270705 0.00594915 -0.00310888 -0.259197 0.00787538 -0.00311919 -0.227615 0.00804354 -0.00895829 -0.225352 0.00698569 -0.00813986 -0.251308 0.00781201 -0.00311708 -0.235846 0.00782579 -0.00311985 -0.224157 0.00650082 -0.0100485 -0.198392 0.00472475 -0.00311806 -0.184808 0.0058556 -0.0103483 -0.192222 0.0024102 -0.00311489 -0.16895 0.00258516 -0.0117442 -0.168743 -0.0117776 -0.00311141 -0.0991052 -0.014683 -0.0031113 -0.0851619 -0.0184184 -0.020088 -0.0647277 -0.0208158 -0.00311155 -0.0534173 0.014 -0.0183243 -0.260062 -0.00514314 -0.0232206 -0.108565 0.0120829 -0.0181701 -0.263474 0.0119695 -0.0182184 -0.264407 0.0173131 -0.0190072 -0.271181 0.0131538 -0.0186931 -0.267943 0.0105164 -0.018038 -0.266996 0.0109477 -0.0177349 -0.262657 0.00950641 -0.0176612 -0.267278 -0.000213214 -0.0180034 -0.29336 -0.00072588 -0.0174357 -0.293267 0.0039054 -0.015523 -0.278444 -0.00227515 -0.0146562 -0.292986 -0.0234298 -0.0195585 -0.0347888 -0.0238904 -0.0178794 -0.0343629 -0.0200899 -0.0213223 -0.0536684 -0.0205345 -0.0219544 -0.0374657 -0.0133154 -0.0251208 -0.0646271 -0.0138669 -0.0250286 -0.0710685 -0.0133189 -0.02512 -0.0646146 -0.0101304 -0.0254046 -0.0807339 -0.0125205 -0.0253676 -0.0700864 -0.00950787 -0.0248385 -0.0886487 -0.00607413 -0.0231343 -0.107066 -0.00908909 -0.0253215 -0.0835874 -0.00334151 -0.021886 -0.120307 -0.00368335 -0.0220319 -0.118708 -0.00404171 -0.0223408 -0.116197 -0.00374037 -0.0226034 -0.115333 -0.00428641 -0.0233588 -0.109042 -0.00309408 -0.0228873 -0.114525 -0.00216265 -0.0230486 -0.113927 -0.00323661 -0.0234356 -0.109242 0.000998072 -0.0205858 -0.138018 0.00243173 -0.0195962 -0.147329 -0.00237792 -0.0214788 -0.124803 0.000100248 -0.0204301 -0.136553 0.00326891 -0.0174699 -0.159704 0.002444 -0.0194334 -0.148212 0.0042653 -0.0205319 -0.145093 0.00281889 -0.0209969 -0.138715 0.00665396 -0.0176132 -0.172393 0.0119552 -0.0186063 -0.180083 0.0106516 -0.0185766 -0.178623 0.00807499 -0.0181634 -0.174342 0.0106697 -0.0187021 -0.176787 0.0102248 -0.0187863 -0.174675 0.0090817 -0.0185289 -0.174678 0.0111822 -0.018443 -0.18193 0.0115659 -0.0186088 -0.179797 0.0111571 -0.0185952 -0.179431 0.00872078 -0.0173066 -0.183512 0.00737321 -0.0178538 -0.173819 0.00843973 -0.017008 -0.184268 0.00690256 -0.0176547 -0.173166 0.00959106 -0.0163866 -0.195574 0.0136027 -0.0173034 -0.215189 0.014742 -0.0175387 -0.220085 0.0162211 -0.017769 -0.221386 0.0145369 -0.0174561 -0.222101 0.0164594 -0.0178073 -0.215449 0.015806 -0.0177738 -0.216075 0.0145548 -0.0175889 -0.215167 0.0134021 -0.0170492 -0.222294 0.0106128 -0.015812 -0.245302 0.0114929 -0.0158802 -0.231 0.0114403 -0.0158376 -0.224951 0.0115535 -0.0159365 -0.224151 0.0118068 -0.0164361 -0.214371 0.00995783 -0.0165471 -0.257029 0.0130782 -0.0182895 -0.262092 0.0120961 -0.0178958 -0.260059 0.0104819 -0.0171112 -0.258923 0.0156336 -0.0185096 -0.26018 0.00586717 -0.0103431 -0.192325 0.00927537 -0.0142563 -0.245246 0.00894547 -0.0165794 -0.262466 0.00973593 -0.0139952 -0.227636 0.0109153 -0.0153661 -0.227646 -0.00275318 -0.0132404 -0.292899 0.00636167 -0.0125478 -0.262267 0.00740941 -0.0147966 -0.262336 0.00831845 -0.0123726 -0.245221 0.0111766 -0.0160368 -0.213488 -0.013876 -0.0218036 -0.0854544 -0.0167619 -0.0221967 -0.0710912 -0.0141756 -0.0195968 -0.0862565 -0.0155946 -0.0238971 -0.0710845 0.00390837 -0.00761361 -0.270472 0.00552482 -0.00783484 -0.26226 0.008853 -0.0124025 -0.227633 0.00819352 -0.0127021 -0.209879 0.0100876 -0.0153412 -0.209875 0.0083747 -0.0157345 -0.192382 -0.00459761 -0.0177973 -0.128956 -0.0220132 -0.0211539 -0.0360985 -0.0174945 -0.0238316 -0.0537121 -0.0190398 -0.022835 -0.0536846 -0.0107846 -0.0248245 -0.0854536 -0.0126281 -0.0236161 -0.0854588 -0.00773006 -0.0238302 -0.0992916 0.00274963 -0.0128599 -0.278306 0.00187626 -0.00740603 -0.278226 -0.000753408 -0.00719573 -0.285947 -0.00369777 -0.00700288 -0.292728 -0.00574755 -0.0231212 -0.107889 -0.00402206 -0.0221795 -0.117108 -0.00966977 -0.0225671 -0.0992913 -0.0109833 -0.0206619 -0.09929 -0.00312093 -0.0199519 -0.128947 0.00164154 -0.0151613 -0.15969 -0.00450855 -0.0149296 -0.131956 0.00659524 -0.0132812 -0.192372 0.0261745 -0.0181553 -0.193312 0.0177093 -0.0183775 -0.186138 0.0273469 -0.0181602 -0.193126 0.022207 -0.021014 -0.0951924 0.0250569 -0.0185541 -0.121331 0.032741 -0.0140883 -0.175409 0.0176992 -0.0250327 -0.0728146 0.0470572 -0.0171886 -0.297483 0.0471438 -0.0170678 -0.296708 0.0468662 -0.0165688 -0.286349 0.0472785 -0.0171516 -0.301981 0.0459278 -0.0182674 -0.301736 0.0460951 -0.0180467 -0.298936 0.0415106 -0.0159941 -0.245208 0.0415753 -0.0159833 -0.245505 0.0440311 -0.0163005 -0.262439 0.0459263 -0.0166931 -0.278967 0.0454644 -0.0160394 -0.270134 0.0372662 -0.0176955 -0.240242 0.0375731 -0.017796 -0.243336 0.0364294 -0.0179862 -0.242809 0.0361264 -0.018029 -0.243059 0.0353627 -0.01808 -0.243611 0.0360955 -0.0180702 -0.244216 0.0366871 -0.0179914 -0.243787 0.0370127 -0.0175675 -0.236912 0.0359226 -0.0178198 -0.236886 0.034996 -0.0179209 -0.236553 0.0346598 -0.0179346 -0.236337 0.0344497 -0.0179587 -0.237358 0.034253 -0.017937 -0.236036 0.0370692 -0.0159062 -0.218258 0.0408334 -0.0153537 -0.237098 0.0396598 -0.0158651 -0.233644 0.0394349 -0.0162381 -0.235199 0.0378243 -0.0172949 -0.237049 0.0309794 -0.0165907 -0.175385 0.0316306 -0.0172695 -0.192773 0.0323869 -0.0167343 -0.191283 0.0337278 -0.0166343 -0.201782 0.0328623 -0.0170823 -0.201222 0.0323846 -0.0166753 -0.190463 0.0356123 -0.0155067 -0.205107 0.0345321 -0.0162095 -0.203259 0.0286667 -0.0181151 -0.193725 0.0288507 -0.0180744 -0.195521 0.0307894 -0.0176532 -0.193397 0.0297218 -0.0179606 -0.193738 0.0281507 -0.018111 -0.194987 0.0295573 -0.017991 -0.196061 0.0305672 -0.0178006 -0.197651 0.030057 -0.0179123 -0.201321 0.0302638 -0.0178798 -0.199455 0.0227966 -0.0211784 -0.129074 0.026235 -0.0191117 -0.153035 0.0230791 -0.0210165 -0.129935 0.0229163 -0.0199023 -0.155452 0.0243608 -0.0194629 -0.162271 0.0230329 -0.0198416 -0.156407 0.0231503 -0.0197816 -0.157365 0.0232792 -0.0197169 -0.158412 0.0244864 -0.0197455 -0.155145 0.0234451 -0.0198844 -0.155432 0.0202873 -0.0219339 -0.127557 0.0215333 -0.0219961 -0.12135 0.0197556 -0.0223546 -0.122391 0.0197354 -0.0235651 -0.101485 0.0208085 -0.0226862 -0.111554 0.0217354 -0.021975 -0.119438 0.021331 -0.0220826 -0.12114 0.0167581 -0.0246016 -0.0946999 0.0189895 -0.0241428 -0.0951864 0.0187339 -0.024345 -0.0927183 0.018821 -0.0243438 -0.0918229 0.0164502 -0.0253758 -0.0716599 0.015535 -0.0254629 -0.0720625 0.0155366 -0.0254638 -0.0721206 0.0163217 -0.025432 -0.0739216 0.0175838 -0.025136 -0.0765046 0.0189061 -0.0244942 -0.0813028 0.0209079 -0.0228961 -0.0951879 0.039796 -0.0202033 -0.300623 0.0451807 -0.0186673 -0.299437 0.0453737 -0.0186299 -0.301635 0.0418567 -0.0199025 -0.298667 0.0506125 -0.0095872 -0.302586 0.050038 -0.00929184 -0.286708 0.0211405 -0.0219228 -0.0822872 0.0338979 -0.0109152 -0.178433 0.0261027 -0.0156557 -0.125406 0.0233872 -0.0180998 -0.102231 0.0491546 -0.0132495 -0.286628 0.0428911 -0.0124144 -0.237122 0.0375328 -0.0127951 -0.205112 0.0198947 -0.0237262 -0.0822851 0.0236355 -0.020625 -0.121343 0.0286013 -0.0160891 -0.147796 0.0457069 -0.00888853 -0.24971 0.0476651 -0.0128501 -0.270294 0.0493148 -0.00915015 -0.277908 0.0487709 -2.88296e-06 -0.270876 0.0459564 -2.88296e-06 -0.24976 0.03782 -0.00967062 -0.202346 0.0486097 -0.00905754 -0.271178 0.0297618 -0.0130089 -0.151667 0.0263482 -2.88296e-06 -0.125298 0.0213667 -0.0100387 -0.0762052 0.0402798 -0.00250288 -0.245716 0.0438067 -0.015906 -0.271474 0.045793 -0.00250288 -0.296768 0.037406 -0.0192165 -0.29672 0.0375371 -0.0192374 -0.297103 0.037662 -0.0192807 -0.297867 0.0375371 -0.00250288 -0.297102 0.0376099 -0.0193282 -0.298673 0.0376099 -0.00250288 -0.298673 0.0375237 -0.0193504 -0.299035 0.0371469 -0.019404 -0.299881 0.036439 -0.0194495 -0.300707 0.0357974 -0.00250288 -0.301142 0.0357974 -0.0194812 -0.301142 0.0354296 -0.0194972 -0.30131 -0.000482654 -0.0176223 -0.29683 0.00426502 -0.0171698 -0.286534 0.00426472 -0.00740288 -0.286535 0.0058616 -0.0169749 -0.282033 0.00919695 -0.0164065 -0.269444 0.0289769 -0.00250288 -0.177476 0.0290106 -0.0166698 -0.177685 0.0186488 -0.00250288 -0.128753 0.0186488 -0.0211043 -0.128753 0.0123977 -0.0206831 -0.134003 0.00652491 -0.00740288 -0.138935 0.00623493 -0.00740288 -0.139179 0.0234588 -0.0193118 -0.141323 0.0234245 -0.00250288 -0.141079 0.025054 -0.0184064 -0.15231 0.00541671 -0.0180064 -0.157377 0.0357908 -0.0152781 -0.218467 0.0125479 -0.00740288 -0.241215 0.012736 -0.0152098 -0.224928 0.0176399 -0.00250288 -0.121502 0.000500737 -0.00250288 -0.109794 0.000264959 -0.00250288 -0.110794 0.018268 -0.00250288 -0.100591 0.0186154 -0.00250288 -0.101534 0.000556421 -0.00250288 -0.111779 0.00120157 -0.00250288 -0.109043 0.0205914 -0.00250288 -0.119511 0.00129826 -0.00250288 -0.112489 0.0114337 -0.00250288 -0.0736863 0.017211 -0.0240034 -0.0859007 0.0147452 -0.00250288 -0.0737615 0.0125558 -0.0246677 -0.0733373 0.0130989 -0.00250288 -0.0733074 0.0148244 -0.0246759 -0.0738078 0.0137301 -0.0246693 -0.0733794 0.0156199 -0.0246393 -0.074464 0.0159809 -0.0245638 -0.0749411 0.016511 -0.0243847 -0.076564 0.0162402 -0.0244853 -0.0754367 0.0148164 -0.0238137 -0.0938248 0.00580576 -0.0241446 -0.0892602 0.017607 -0.00250288 -0.092704 0.0159806 -0.00250288 -0.0749407 -0.00320862 -0.00250288 -0.0811277 0.0177126 -0.00250288 -0.0918661 0.016511 -0.00250288 -0.076564 0.0157217 -0.0204398 -0.0638105 0.0157628 -0.00250288 -0.0645609 0.0156435 -0.0195727 -0.0623467 -0.00306957 -0.0234113 -0.055487 -0.00405686 -0.00250288 -0.0558676 0.0133495 -0.00250288 -0.0493948 0.0148774 -0.00250288 -0.0503994 0.0124168 -0.00250288 -0.0495172 0.0151346 -0.00250288 -0.0513043 -0.000532838 -0.0242784 -0.0645368 -0.0100641 -0.0239655 -0.0606707 0.00900057 -0.0245192 -0.0684037 -0.00859168 -0.00250288 -0.061268 0.00125276 -0.00740288 -0.136252 0.00125276 -0.019734 -0.136252 -0.000445319 -0.00740288 -0.128234 -0.00221956 -0.021175 -0.12 -0.00838907 -0.0180029 -0.0307215 -0.00674442 -0.0155029 -0.0298049 -0.00398263 -0.0151008 -0.0282658 -0.0014154 -0.0180029 -0.0268352 -0.00797236 -0.0179764 -0.034496 0.00264776 -0.0177029 -0.041419 0.0122255 -0.00250288 -0.0444737 -0.00219678 -0.0181989 -0.0398739 0.0148323 -0.00250288 -0.0425099 -0.00797236 -0.00250288 -0.034496 0.014505 -0.00250288 -0.025356 -0.0076065 -0.00250288 -0.0381485 -0.00898121 -0.00250288 -0.0359786 -0.00888938 -0.00250288 -0.0368954 0.0142342 -0.00250288 -0.0243689 0.0115315 -0.00250288 -0.0236269 0.0155626 -0.00250288 -0.100037 0.016521 -0.023478 -0.099734 0.016521 -0.00250288 -0.099734 0.0169646 -0.0234749 -0.0997604 0.0180879 -0.0231852 -0.100367 0.0175057 -0.00250288 -0.0999356 0.0171651 -0.00250288 -0.0934235 0.0176067 -0.0236194 -0.0927047 0.0154563 -0.0237924 -0.0940232 0.016126 -0.0237939 -0.0939991 0.0164656 -0.00250288 -0.0938966 0.0156332 -0.00250288 -0.0940388 0.0148164 -0.00250288 -0.0938248 0.0155688 -0.00250288 -0.0655369 0.0149285 -0.00250288 -0.0662986 0.0140003 -0.00250288 -0.0666574 0.0130141 -0.00250288 -0.0665245 0.0130141 -0.0244018 -0.0665245 0.0457364 -0.0166026 -0.29732 0.0451007 -0.0174013 -0.298357 0.0449677 -0.0175403 -0.298462 0.0440659 -0.00250288 -0.298824 0.044075 -0.0183034 -0.298822 0.042397 -0.0190965 -0.298273 0.0380146 -0.00250288 -0.244044 0.0382697 -0.0167396 -0.244024 0.0402798 -0.0153691 -0.245716 0.0398596 -0.015645 -0.244767 0.039037 -0.00250288 -0.244163 0.035589 -0.0170561 -0.239334 0.0361352 -0.00250288 -0.240035 0.0363241 -0.00250288 -0.240903 0.0363112 -0.0169649 -0.241112 0.038297 -0.00250288 -0.234815 0.0382398 -0.0155876 -0.234967 0.0377864 -0.00250288 -0.235626 0.0369639 -0.0166642 -0.236105 0.0359997 -0.00250288 -0.236146 0.0353551 -0.0171233 -0.235892 0.0303439 -0.0171177 -0.202023 0.0305703 -0.0170735 -0.201919 0.0305674 -0.00250288 -0.20192 0.0309397 -0.0169702 -0.201815 0.0314383 -0.00250288 -0.201789 0.032281 -0.00250288 -0.202045 0.0315525 -0.0167167 -0.201801 0.0327282 -0.0159588 -0.202391 0.029419 -0.00250288 -0.197304 0.0296252 -0.0170171 -0.198083 0.0296085 -0.0170294 -0.198475 0.0294128 -0.0170916 -0.199098 0.0311411 -0.0160763 -0.191227 0.0305358 -0.0166531 -0.192418 0.0309886 -0.0162665 -0.191774 0.031054 -0.00250288 -0.191605 0.0310528 -0.0161952 -0.191609 0.03013 -0.0169005 -0.192717 0.0296949 -0.00250288 -0.192895 0.0294428 -0.0171778 -0.192949 0.0282891 -0.0173499 -0.19277 0.0278642 -0.00250288 -0.192494 0.0241198 -0.0186772 -0.163139 0.024215 -0.00250288 -0.163098 0.0250956 -0.00250288 -0.162958 0.0251778 -0.0185213 -0.162965 0.0267468 -0.0176333 -0.164053 0.0266047 -0.0177419 -0.163814 0.0259495 -0.00250288 -0.163215 0.0258722 -0.0182208 -0.163173 0.022999 -0.00250288 -0.158401 0.0227921 -0.0189981 -0.158098 0.0232431 -0.00250288 -0.159189 0.0232266 -0.0192393 -0.159058 0.0231481 -0.00250288 -0.160009 0.025054 -0.00250288 -0.15231 0.024971 -0.00250288 -0.153244 0.0248725 -0.0185476 -0.153484 0.0244715 -0.00250288 -0.154038 0.0239599 -0.0189649 -0.154399 0.0245147 -0.0187529 -0.153994 0.0227298 -0.00250288 -0.154575 0.0224653 -0.0191123 -0.15451 0.0192269 -0.0211432 -0.128414 0.0194 -0.00250288 -0.128357 0.0208197 -0.0209675 -0.128491 0.0213703 -0.0206997 -0.128892 0.0210407 -0.0208741 -0.128618 0.0165091 -0.00250288 -0.123733 0.0170344 -0.0214713 -0.124152 0.0173912 -0.0214068 -0.12472 0.0168295 -0.00250288 -0.127016 0.0173949 -0.00250288 -0.12624 0.0171685 -0.0211868 -0.12665 0.017395 -0.0212336 -0.12624 0.0174634 -0.0212559 -0.126044 0.020505 -0.00250288 -0.120378 0.0200585 -0.00250288 -0.121125 0.0199553 -0.0214652 -0.121227 0.0203555 -0.0213323 -0.12072 0.0182721 -0.0215624 -0.121723 0.0190642 -0.0215664 -0.121698 0.0193364 -0.00250288 -0.121613 0.0184759 -0.00250288 -0.121747 0.000416174 -0.0224239 -0.111502 0.000556333 -0.0223922 -0.111778 0.000343982 -0.0225769 -0.110178 0.000267181 -0.0224994 -0.110847 0.00120157 -0.0227092 -0.109043 0.00111815 -0.0227028 -0.109099 0.000638907 -0.0226474 -0.109572 0.000500669 -0.0226216 -0.109794 -0.00320631 -0.00250288 -0.0846948 -0.00388077 -0.00250288 -0.0841391 -0.00320631 -0.0244273 -0.0846948 -0.0042539 -0.00250288 -0.0833489 -0.00425389 -0.024516 -0.0833489 -0.00425446 -0.00250288 -0.082475 -0.00429447 -0.0245308 -0.0830896 -0.00424125 -0.0245657 -0.0824195 -0.00388235 -0.00250288 -0.0816843 -0.00350898 -0.0246125 -0.0813155 0.00957169 -0.0245423 -0.0687571 0.00974151 -0.00250288 -0.068926 0.00999357 -0.0245726 -0.0692794 0.0101758 -0.024595 -0.0697216 0.0101758 -0.00250288 -0.0697216 0.0100022 -0.0246506 -0.0712192 0.00984896 -0.0246567 -0.0714569 0.00958487 -0.0246632 -0.0717454 -0.00465982 -0.0239537 -0.0592342 -0.00408924 -0.00250288 -0.0595871 -0.00485709 -0.00250288 -0.059034 -0.00508108 -0.023886 -0.0587135 -0.00528477 -0.00250288 -0.0581899 -0.00530694 -0.0238002 -0.058082 -0.00527653 -0.00250288 -0.0572437 -0.00527654 -0.0236799 -0.0572437 -0.00483422 -0.00250288 -0.0564071 0.014235 -0.0177029 -0.0497123 0.014235 -0.00250288 -0.0497123 0.0148774 -0.0177029 -0.0503994 0.0146358 -0.00250288 -0.0434346 0.0140366 -0.00250288 -0.0441658 0.0131685 -0.00250288 -0.04454 0.0131685 -0.0177029 -0.04454 -0.0076065 -0.01932 -0.0381485 -0.00839625 -0.00250288 -0.0376738 -0.00887639 -0.0192732 -0.0369319 -0.00899679 -0.0190359 -0.0363321 -0.00891984 -0.0187137 -0.0356867 -0.00865227 -0.00250288 -0.0351179 -0.0086117 -0.0183485 -0.0350605 0.0115315 -0.0177029 -0.0236269 0.0125234 -0.0177029 -0.023374 0.0125234 -0.00250288 -0.023374 0.0135105 -0.0177029 -0.023645 0.0135105 -0.00250288 -0.023645 0.0447814 0.0161395 -0.281076 0.0342776 0.00249712 -0.301544 0.0357974 0.00249712 -0.301142 0.0357974 0.0194755 -0.301142 0.036439 0.0194438 -0.300707 0.0369882 0.00249712 -0.300116 0.0375371 0.00249712 -0.297102 0.0375371 0.0192317 -0.297103 0.0376099 0.00249712 -0.298673 0.0311311 0.00249712 -0.190643 0.00614594 0.00739712 -0.139254 0.00614594 0.0202723 -0.139254 0.025054 0.0184006 -0.15231 0.025054 0.00249712 -0.15231 0.0383719 0.0152397 -0.23386 0.0357802 0.00249712 -0.218404 0.035627 0.0152833 -0.217496 0.0176399 0.0215811 -0.121502 0.00838185 0.0230775 -0.10454 0.0155626 0.00249712 -0.100037 0.0176399 0.00249712 -0.121502 0.0193364 0.00249712 -0.121613 0.0205914 0.00249712 -0.119511 0.0200585 0.00249712 -0.121125 0.0175057 0.00249712 -0.0999356 0.0186154 0.00249712 -0.101534 0.00120157 0.00249712 -0.109043 0.00129826 0.00249712 -0.112489 -0.00320862 0.0246133 -0.0811277 0.0169104 0.0241973 -0.0820586 0.016511 0.00249712 -0.076564 -0.00320631 0.0244215 -0.0846948 0.016511 0.0243789 -0.076564 0.0156199 0.0246335 -0.074464 0.0159806 0.00249712 -0.0749407 0.0130989 0.00249712 -0.0733074 0.0114337 0.0246665 -0.0736863 0.0125558 0.024662 -0.0733373 -0.00320631 0.00249712 -0.0846948 -0.00388235 0.00249712 -0.0816843 -0.0042539 0.00249712 -0.0833489 -0.00320862 0.00249712 -0.0811277 0.0147452 0.00249712 -0.0737615 0.0114337 0.00249712 -0.0736863 0.0130141 0.00249712 -0.0665245 0.0153602 0.0176971 -0.0565886 0.0154293 0.0178444 -0.0580707 0.0157628 0.00249712 -0.0645609 0.0154559 0.0179695 -0.0586246 0.0155975 0.0190918 -0.0614637 0.0099205 0.0176971 -0.0504795 -0.00405686 0.023455 -0.0558676 -0.00405686 0.00249712 -0.0558676 1.94568e-05 0.0229053 -0.0542962 0.000671099 0.0226365 -0.054045 0.00347688 0.020969 -0.0529634 0.0133495 0.00249712 -0.0493948 0.0151346 0.00249712 -0.0513043 0.0124168 0.00249712 -0.0495172 -0.00528477 0.00249712 -0.0581899 -0.00485709 0.00249712 -0.059034 -0.00527653 0.00249712 -0.0572437 -0.00967421 0.0070478 -0.0608289 -0.000532371 0.0242727 -0.064537 0.00900057 0.0245134 -0.0684037 -0.00859622 0.00590312 -0.0612661 -0.00903155 0.00645335 -0.0610895 0.0136679 0.0179971 -0.0184296 -0.0140218 0.0154971 -0.0338605 -0.00838907 0.0179971 -0.0307215 -0.00651525 0.0190799 -0.0384965 0.0122255 0.00249712 -0.0444737 0.0122255 0.0176971 -0.0444737 -0.00214224 0.0181835 -0.0398913 0.0115315 0.00249712 -0.0236269 -0.00708554 0.0177716 -0.0340018 0.0140366 0.00249712 -0.0441658 -0.00797236 0.00249712 -0.034496 -0.00839625 0.00249712 -0.0376738 -0.00865227 0.00249712 -0.0351179 0.0125234 0.00249712 -0.023374 0.0135105 0.00249712 -0.023645 0.0186154 0.0228284 -0.101534 0.0180879 0.0231795 -0.100367 0.018268 0.00249712 -0.100591 0.0182674 0.0230812 -0.10059 0.018445 0.0229669 -0.100902 0.0168507 0.023471 -0.0997441 0.016521 0.00249712 -0.099734 0.0175405 0.0233879 -0.0999531 0.016521 0.0234722 -0.099734 0.0161816 0.0234672 -0.0997811 0.0148164 0.00249712 -0.0938248 0.0156332 0.00249712 -0.0940388 0.016126 0.0237881 -0.0939991 0.0154563 0.0237866 -0.0940232 0.0169885 0.0237706 -0.0935871 0.0164614 0.023798 -0.0938983 0.0164656 0.00249712 -0.0938966 0.0174226 0.0236735 -0.0930904 0.0171651 0.00249712 -0.0934235 0.017607 0.00249712 -0.092704 0.0177126 0.00249712 -0.0918661 0.0135896 0.0242629 -0.0666634 0.0140072 0.0240694 -0.0666566 0.0141529 0.0239779 -0.0666334 0.0149337 0.0232115 -0.0662948 0.0140003 0.00249712 -0.0666574 0.0156421 0.0217578 -0.0653639 0.0155681 0.0219913 -0.0655384 0.0155688 0.00249712 -0.0655369 0.0149285 0.00249712 -0.0662986 0.015154 0.0228823 -0.066111 0.0150917 0.0229825 -0.0661686 0.0422985 0.00249712 -0.29817 0.0427989 0.0189706 -0.298577 0.0446257 0.0178595 -0.298661 0.0440002 0.0183497 -0.298832 0.045793 0.0164832 -0.296768 0.0449668 0.0175354 -0.298463 0.0402798 0.0153633 -0.245716 0.0390382 0.016266 -0.244163 0.0393732 0.0160226 -0.244333 0.039037 0.00249712 -0.244163 0.0398636 0.015636 -0.244772 0.0387314 0.0164686 -0.24407 0.0372986 0.0171318 -0.244294 0.0363241 0.0169376 -0.240904 0.0361186 0.00249712 -0.241767 0.0363116 0.0169222 -0.240659 0.0363241 0.00249712 -0.240903 0.0351338 0.0171296 -0.235735 0.0356947 0.0170774 -0.236058 0.0359997 0.00249712 -0.236146 0.0360027 0.0170169 -0.236147 0.0369363 0.0166729 -0.236113 0.0375077 0.0163135 -0.23585 0.0369571 0.00249712 -0.236107 0.038297 0.00249712 -0.234815 0.0377868 0.0160822 -0.235626 0.0330818 0.0156788 -0.20289 0.0329292 0.0157963 -0.202634 0.032281 0.00249712 -0.202045 0.0314383 0.00249712 -0.201789 0.0305704 0.0170677 -0.201919 0.0305674 0.00249712 -0.20192 0.0296219 0.0170173 -0.198354 0.0294562 0.0170743 -0.199006 0.0296252 0.00249712 -0.198083 0.029419 0.00249712 -0.197304 0.0295635 0.0170252 -0.197689 0.0278642 0.0173547 -0.192494 0.0278642 0.00249712 -0.192494 0.0294428 0.0171721 -0.192949 0.0287296 0.00249712 -0.192923 0.0287598 0.0173121 -0.192929 0.0282891 0.0173441 -0.19277 0.0306672 0.0165499 -0.192281 0.0305358 0.0166473 -0.192418 0.03013 0.0168948 -0.192717 0.0296949 0.00249712 -0.192895 0.0311311 0.0160198 -0.190643 0.0311411 0.0160705 -0.191227 0.031054 0.00249712 -0.191605 0.0309886 0.0162608 -0.191774 0.0266069 0.00249712 -0.163817 0.0259495 0.00249712 -0.163215 0.0258722 0.018215 -0.163173 0.0244871 0.0186605 -0.16301 0.024215 0.00249712 -0.163098 0.0240115 0.018667 -0.163193 0.0231391 0.0188878 -0.160035 0.0229401 0.0187618 -0.160446 0.0231481 0.00249712 -0.160009 0.0229827 0.0190702 -0.158372 0.0224573 0.00249712 -0.157778 0.0218702 0.00249712 -0.154201 0.0224653 0.0191066 -0.15451 0.0232986 0.0190819 -0.154593 0.0236654 0.00249712 -0.154516 0.0236678 0.0190291 -0.154516 0.0244715 0.00249712 -0.154038 0.024971 0.00249712 -0.153244 0.021918 0.00249712 -0.130024 0.021918 0.0203005 -0.130024 0.0216313 0.00249712 -0.129225 0.0217318 0.0204517 -0.129406 0.0213703 0.0206939 -0.128892 0.0210389 0.00249712 -0.128617 0.0208197 0.0209617 -0.128491 0.020141 0.0211328 -0.128295 0.0198099 0.0211523 -0.128288 0.0202476 0.00249712 -0.128309 0.0194 0.00249712 -0.128357 0.0173949 0.00249712 -0.12624 0.0175233 0.021346 -0.125203 0.0172139 0.00249712 -0.124385 0.017214 0.0214391 -0.124385 0.0169101 0.02148 -0.124025 0.0182721 0.0215567 -0.121723 0.0184759 0.00249712 -0.121747 0.0189419 0.0215576 -0.121722 0.0190642 0.0215606 -0.121698 0.0193808 0.0215536 -0.121595 0.020505 0.00249712 -0.120378 0.0203555 0.0213265 -0.12072 0.000556421 0.00249712 -0.111779 0.00070038 0.0226511 -0.109491 0.000500737 0.00249712 -0.109794 0.000375966 0.0225828 -0.110078 0.000264959 0.00249712 -0.110794 0.00121283 0.022311 -0.112439 -0.00425446 0.00249712 -0.082475 -0.00425447 0.0245572 -0.082475 -0.00429462 0.0245441 -0.0827333 -0.00388077 0.00249712 -0.0841391 0.00984896 0.00249712 -0.0714569 0.0100701 0.024641 -0.0710835 0.0102143 0.00249712 -0.0706273 0.0102143 0.0246264 -0.0706273 0.0101758 0.00249712 -0.0697216 0.0101873 0.0245912 -0.069765 0.0094547 0.0245306 -0.0686615 0.0099151 0.0245598 -0.0691509 -0.00483422 0.00249712 -0.0564071 -0.00530093 0.0236902 -0.0573531 -0.00510513 0.0238743 -0.0586694 -0.00485725 0.0239222 -0.0590338 -0.00408924 0.00249712 -0.0595871 -0.00408924 0.0239923 -0.0595871 0.0151346 0.0176971 -0.0513043 0.0148774 0.00249712 -0.0503994 0.014235 0.00249712 -0.0497123 0.014235 0.0176971 -0.0497123 0.0124168 0.0176971 -0.0495172 0.0131685 0.0176971 -0.04454 0.0131685 0.00249712 -0.04454 0.0146358 0.00249712 -0.0434346 0.0148323 0.0176971 -0.0425099 0.0148323 0.00249712 -0.0425099 -0.00851467 0.0182661 -0.0349384 -0.00885789 0.0186073 -0.0355057 -0.00898095 0.0188601 -0.0359766 -0.00898121 0.00249712 -0.0359786 -0.00899837 0.0189705 -0.0362029 -0.00888938 0.00249712 -0.0368954 -0.0080593 0.0194134 -0.0379387 -0.0076065 0.00249712 -0.0381485 0.014505 0.0176971 -0.025356 0.0142342 0.0176971 -0.0243689 0.014505 0.00249712 -0.025356 0.0142342 0.00249712 -0.0243689 0.00289774 0.00549712 0.0205794 -0.0166212 0.00549712 0.035841 0.010506 0.00549712 0.0585269 0.0171364 0.00549712 0.0538032 0.00476293 0.00549712 0.0459236 0.0188486 0.00549712 0.0480492 0.00604355 0.00549712 0.044642 -1.99281e-05 0.00549712 0.0411443 -0.00048819 0.00549712 0.0428944 0.00285547 0.00549712 0.0587788 0.00301311 0.00549712 0.0463931 -0.00187962 0.00549712 0.0580077 0.00126293 0.00549712 0.0459249 -0.00615056 0.00549712 0.0558711 0.00301051 0.00549712 0.0393931 0.00795985 0.00549712 0.0150796 0.00651181 0.00549712 0.0428918 0.00604225 0.00549712 0.041142 0.0104144 0.00549712 0.0101299 0.0202846 -0.00250288 -0.0267721 -1.86293e-05 -0.00550288 0.0446443 0.0136419 -0.00550288 0.0572294 0.016396 -0.00550288 0.054826 -0.011855 -0.00550288 0.0484926 -0.0166212 -0.00550288 0.035841 -0.00048819 -0.00550288 0.0428944 -1.99281e-05 -0.00550288 0.0411443 0.00301311 -0.00550288 0.0463931 0.00476293 -0.00550288 0.0459236 -0.0105413 -0.00550288 0.0511811 0.00126293 -0.00550288 0.0459249 0.00785516 -0.00550288 0.0588276 0.00126069 -0.00550288 0.0398627 0.0135295 -0.00550288 0.00520508 0.0193323 -0.00550288 -0.00144834 0.0144838 -0.00550288 -0.000605127 0.00604355 -0.00550288 0.044642 0.0182169 -0.00550288 0.0515977 0.0188486 -0.00550288 0.0480492 -0.0233082 -2.88271e-06 -0.316648 -0.0232861 -0.000295838 -0.316666 -0.0234048 -2.88272e-06 -0.316537 -0.0234824 -2.88277e-06 -0.316299 -0.0234701 -2.88275e-06 -0.316382 0.0383717 -2.88287e-06 -0.364342 0.0382311 -2.8828e-06 -0.364434 0.0381963 -0.00444758 -0.364266 0.0379993 -0.00444172 -0.364356 0.0381365 -2.88277e-06 -0.364464 0.038068 -2.88275e-06 -0.364474 0.0379009 -2.88271e-06 -0.364457 0.0377422 -2.88271e-06 -0.364382 -0.0219151 -0.0172143 -0.31728 -0.0226127 -0.0130152 -0.316743 -0.0233457 -0.0035526 -0.316174 -0.0177054 -0.0242489 -0.320301 -0.0180462 -0.0239846 -0.320037 -0.0181705 -0.023972 -0.320209 -0.0197459 -0.0220991 -0.318712 -0.0198663 -0.0220889 -0.318886 -0.0201303 -0.0216616 -0.318679 -0.0214988 -0.0185996 -0.317605 -0.0201992 -0.0213373 -0.318356 -0.021795 -0.0172189 -0.317104 -0.0213737 -0.0184097 -0.318161 -0.0214964 -0.0184921 -0.318007 -0.0197954 -0.0217836 -0.319395 -0.0182485 -0.0237429 -0.320547 -0.0178609 -0.0238229 -0.320908 -0.0152866 -0.0252952 -0.32292 -0.0124091 -0.0260745 -0.32517 -0.00922173 -0.026376 -0.327606 -0.00186299 -0.0262115 -0.333416 0.00737227 -0.0262565 -0.340637 0.0201569 -0.026492 -0.350579 0.0277216 -0.0262266 -0.356548 0.0277693 -0.0264288 -0.35653 0.0302673 -0.0253895 -0.358538 0.030355 -0.0255822 -0.35855 0.0311688 -0.0251239 -0.359186 0.0354283 -0.0197438 -0.362574 0.0340237 -0.0224965 -0.361416 0.035789 -0.0188744 -0.362856 0.0366091 -0.0157338 -0.363497 -0.0234204 -0.000300754 -0.316505 -0.0233207 -0.00353783 -0.316583 -0.0225909 -0.012978 -0.317153 -0.0233771 -0.003547 -0.316381 -0.0226459 -0.0130011 -0.316951 -0.0219545 -0.0171821 -0.317487 -0.0219061 -0.017128 -0.317687 -0.0201512 -0.0214988 -0.31906 -0.0198935 -0.0219156 -0.319261 -0.0199187 -0.0220238 -0.319081 -0.0179162 -0.0240023 -0.320807 -0.0182423 -0.0238863 -0.32039 -0.0153102 -0.0254951 -0.322843 -0.012397 -0.026282 -0.325122 -0.00914542 -0.0265454 -0.327506 -0.00183645 -0.0264165 -0.333381 0.00739825 -0.0264604 -0.340602 0.0126324 -0.0264901 -0.344695 0.0268863 -0.0265287 -0.35584 0.020232 -0.02666 -0.350483 0.0313071 -0.0252765 -0.359132 0.0333623 -0.0232837 -0.3609 0.0335305 -0.0234135 -0.360866 0.0356017 -0.0198494 -0.36265 0.0359684 -0.018966 -0.362936 0.0368016 -0.0157753 -0.363588 0.0370158 -0.015809 -0.363587 -0.0234771 -0.000304808 -0.316303 -0.0234462 -0.000307288 -0.316096 -0.0215408 -0.0185595 -0.31781 -0.0201804 -0.0216005 -0.318876 -0.0178307 -0.0242366 -0.320473 -0.0179055 -0.0241491 -0.320652 -0.0152721 -0.0256577 -0.322707 -0.012331 -0.0264517 -0.325011 -0.00176045 -0.0265854 -0.333283 0.0074732 -0.0266288 -0.340505 -0.00164833 -0.0266887 -0.333139 0.012707 -0.0266582 -0.344599 0.00758413 -0.0267325 -0.340362 0.0128174 -0.0267623 -0.344457 0.0269677 -0.0266964 -0.35575 0.0270821 -0.0268005 -0.355612 0.0278622 -0.0265958 -0.356447 0.0306264 -0.0258351 -0.358365 0.0304824 -0.0257402 -0.358489 0.0336993 -0.0234898 -0.360756 0.034201 -0.0226162 -0.361389 0.0358004 -0.0199351 -0.362637 0.035987 -0.0199848 -0.362539 0.036172 -0.0190403 -0.362927 0.0363614 -0.0190834 -0.362831 0.0361265 -0.0199893 -0.362373 0.0343751 -0.0226863 -0.361283 0.0314578 -0.0253676 -0.359012 0.0307613 -0.02585 -0.358202 0.0272099 -0.0268232 -0.35545 0.0279842 -0.0266987 -0.356312 0.0203426 -0.0267641 -0.350341 0.0129446 -0.0267843 -0.344294 0.00771175 -0.0267536 -0.340199 -0.00890324 -0.0266657 -0.327195 -0.00903256 -0.0266481 -0.327361 -0.0122232 -0.0265527 -0.324857 -0.0128415 -0.0264452 -0.324098 -0.0150495 -0.0257632 -0.322365 -0.0151795 -0.025753 -0.322537 0.0377669 -0.0122268 -0.363655 0.0372114 -0.0158285 -0.363496 0.0373517 -0.0158302 -0.36333 0.0375874 -0.00441919 -0.364262 0.0377827 -0.00443163 -0.364355 0.0372142 -0.0121913 -0.36391 0.03743 -0.012213 -0.363911 0.0376265 -0.0122257 -0.36382 0.0380693 0.00269643 -0.364411 -0.023435 -2.88287e-06 -0.316053 -0.0234806 -2.8828e-06 -0.316215 -0.0230768 0.0056653 -0.316829 0.0384068 0.00270116 -0.364156 0.0362408 0.0181744 -0.363149 0.0349688 0.0210762 -0.362155 0.0342086 0.0218905 -0.36162 0.0323929 0.024216 -0.360142 0.0314929 0.0246489 -0.359497 0.0291437 0.0260812 -0.357603 0.0269353 0.0263148 -0.355933 0.0239778 0.0265006 -0.353566 -0.0021969 0.0264093 -0.333099 -0.0134503 0.0258849 -0.324356 -0.0162324 0.0248422 -0.322181 -0.0170753 0.0245718 -0.321463 -0.0190319 0.0227732 -0.319992 -0.0191106 0.0229303 -0.319873 -0.0194586 0.0225197 -0.319601 -0.0193707 0.0223735 -0.319727 -0.0207718 0.0203046 -0.318574 -0.0220807 0.0164103 -0.317551 -0.0221133 0.0155675 -0.317583 -0.0222446 0.015615 -0.317423 -0.0227731 0.0112204 -0.31701 -0.023211 0.0056807 -0.316668 -0.0232671 0.00569339 -0.316466 -0.0228284 0.0112415 -0.316808 -0.022131 0.0164575 -0.317349 -0.0209816 0.0198342 -0.31841 -0.0208087 0.0203911 -0.318384 -0.0194754 0.0226396 -0.319428 -0.0162386 0.0251945 -0.321952 -0.0162672 0.0250363 -0.322095 -0.0134512 0.0260914 -0.324297 -0.00212087 0.0265782 -0.333001 -0.011802 0.0263308 -0.325588 0.00747726 0.026623 -0.340508 0.0074023 0.0264546 -0.340605 0.0167132 0.026661 -0.347731 0.0166382 0.026493 -0.347827 0.0240512 0.0266683 -0.35347 0.0270535 0.0266849 -0.355817 0.026971 0.0265173 -0.355906 0.0292549 0.0262449 -0.357532 0.0317447 0.0249804 -0.359473 0.0316005 0.0248313 -0.359523 0.0325478 0.0243575 -0.360099 0.0345434 0.0221442 -0.361656 0.035159 0.0211777 -0.362136 0.0343616 0.0220304 -0.36168 0.036448 0.0182385 -0.363143 0.0367483 0.0171562 -0.363378 0.0365372 0.0171061 -0.363381 0.0373587 0.0128992 -0.363855 0.0371431 0.0128764 -0.363855 0.0378527 0.00268897 -0.36441 -0.0227954 0.0112543 -0.316601 -0.0222967 0.015654 -0.317221 -0.0210208 0.0199155 -0.318217 -0.0209761 0.019964 -0.318015 -0.0191198 0.0230592 -0.319705 -0.0190579 0.0231366 -0.319518 -0.0169736 0.0248158 -0.321139 -0.017055 0.0247252 -0.321315 -0.0161518 0.0252874 -0.321778 -0.0116193 0.0266025 -0.325333 -0.0133952 0.0262597 -0.324176 -0.0117302 0.0265007 -0.325482 0.0168238 0.0267651 -0.34759 0.0271687 0.026789 -0.355679 0.0293888 0.0263443 -0.357403 0.031899 0.0250692 -0.359355 0.0327086 0.0244413 -0.359985 0.0353407 0.0212368 -0.362035 0.0366396 0.0182756 -0.363048 0.0369421 0.0171853 -0.363285 0.0382663 0.00270077 -0.364321 -0.0231213 0.00570252 -0.316083 -0.0226801 0.0112565 -0.316424 -0.0232353 0.00570111 -0.316259 -0.0222605 0.0156773 -0.317013 -0.0219734 0.0164899 -0.316966 -0.0208555 0.019971 -0.31784 -0.0220929 0.0164857 -0.317142 -0.0206424 0.0204505 -0.318007 -0.0207628 0.0204428 -0.318182 -0.0194181 0.0227118 -0.319237 -0.018936 0.0231488 -0.319345 -0.0168462 0.0248271 -0.320967 -0.0132925 0.0263589 -0.324015 -0.00200872 0.0266814 -0.332857 0.00758818 0.0267268 -0.340365 0.0241604 0.0267727 -0.353329 0.0272967 0.0268115 -0.355518 0.032846 0.0244519 -0.359821 0.0347203 0.0222107 -0.361551 0.0348592 0.0222175 -0.361386 0.0354799 0.0212425 -0.361869 0.0367794 0.0182788 -0.362882 0.0370822 0.0171878 -0.363119 0.0373799 0.0156386 -0.363353 0.0375552 0.0129124 -0.363765 -0.0223848 0.000722403 -0.317583 -0.0225729 -2.8832e-06 -0.317224 0.0364172 -2.88304e-06 -0.363873 0.0370425 -2.8832e-06 -0.363836 0.0363155 0.00443288 -0.363734 0.0353751 0.014239 -0.363271 0.0355161 0.0142406 -0.363109 0.0354168 0.0150772 -0.363031 0.0345781 0.018031 -0.362649 0.0347184 0.0180354 -0.362486 0.0342579 0.0188469 -0.362398 0.034398 0.0188521 -0.362235 0.0328574 0.0212818 -0.361298 0.0322876 0.0219778 -0.36085 0.0303167 0.0236628 -0.359298 0.0304525 0.0236773 -0.359136 0.0296502 0.0240452 -0.358773 0.0297849 0.0240612 -0.358611 0.0274284 0.0248485 -0.356756 0.0250734 0.0249309 -0.354908 0.0249477 0.0249063 -0.355069 0.0207311 0.0249018 -0.351516 0.0147405 0.0248854 -0.347093 0.014867 0.0249086 -0.346932 0.00720683 0.0248763 -0.340945 -0.0134314 0.0245966 -0.325101 -0.0140502 0.0244518 -0.324621 -0.0151364 0.024047 -0.323502 -0.017591 0.0226239 -0.321574 -0.0180788 0.0223142 -0.321459 -0.0179557 0.0223275 -0.321287 -0.0184791 0.0219431 -0.321144 -0.0193526 0.0206648 -0.320193 -0.0196424 0.0201581 -0.319968 -0.0207853 0.0173718 -0.319078 -0.0209052 0.0173665 -0.319254 -0.0210429 0.0168938 -0.319146 -0.0209233 0.0168987 -0.31897 -0.0213133 0.0157813 -0.318931 -0.0216569 0.0134097 -0.318653 -0.0215422 0.0134123 -0.318477 -0.0225279 0.000718956 -0.317966 0.034908 0.0180766 -0.362392 0.0345848 0.0189004 -0.362139 0.0331705 0.02136 -0.361031 0.0329964 0.0212903 -0.361135 0.032426 0.0219876 -0.360687 0.0325948 0.0220636 -0.36058 0.0306028 0.0237687 -0.359018 0.0208411 0.0250062 -0.351376 0.0149769 0.025013 -0.346791 0.00354835 0.0249626 -0.337858 0.00343747 0.0248587 -0.338 -0.0111154 0.0247896 -0.32663 -0.0139206 0.0244643 -0.324451 -0.0178863 0.0224121 -0.321106 -0.0195946 0.0202158 -0.31977 -0.0208839 0.0169325 -0.318763 -0.0219713 0.00907985 -0.31814 -0.0224154 0.000719514 -0.31779 -0.0224456 -2.88304e-06 -0.317817 -0.0219392 0.00909078 -0.317933 -0.0215095 0.0134267 -0.31827 -0.0215645 0.0134505 -0.318068 -0.0207449 0.0174087 -0.318872 -0.0193024 0.0207273 -0.319998 -0.0175177 0.022711 -0.321395 -0.0150443 0.0241427 -0.323333 -0.0150063 0.0243053 -0.323198 -0.0138209 0.0245631 -0.324289 -0.011003 0.0248924 -0.326485 0.00362339 0.0251309 -0.337761 0.00731721 0.0249803 -0.340804 0.0073918 0.0251484 -0.340707 0.0209156 0.0251739 -0.351281 0.0251814 0.0250357 -0.354768 0.0275495 0.0249517 -0.356623 0.0299288 0.0241563 -0.35849 0.0276414 0.0251184 -0.35654 0.0300564 0.0243134 -0.35843 0.0351117 0.0181469 -0.362385 0.0356123 0.0150937 -0.362942 0.0358258 0.0151217 -0.362943 0.0357118 0.0142552 -0.36302 0.0365119 0.00443886 -0.363645 0.0367223 -2.88317e-06 -0.363745 0.036727 0.00444904 -0.363648 0.036921 0.00446155 -0.363741 0.0359258 0.0142799 -0.363021 0.0361183 0.0143103 -0.363113 0.0347836 0.0189828 -0.362128 0.0333477 0.021478 -0.361005 0.0334954 0.0216226 -0.361062 0.0327631 0.0221917 -0.360548 0.0307406 0.0239207 -0.358965 0.0301449 0.0245047 -0.358443 0.0252536 0.025203 -0.354672 0.0252777 0.0254044 -0.354637 0.0209419 0.0253762 -0.351247 0.0150513 0.0251807 -0.346695 0.00741773 0.0253516 -0.340673 -0.0109011 0.0252674 -0.326349 -0.0109271 0.0250617 -0.326385 -0.0137693 0.0247302 -0.324165 -0.0137755 0.0249348 -0.324102 -0.0150293 0.0245046 -0.323122 -0.0175089 0.0228564 -0.32124 -0.0178833 0.0225529 -0.320947 -0.0193305 0.020831 -0.319815 -0.0197342 0.0204282 -0.319443 -0.0196272 0.0203115 -0.319584 -0.0207912 0.0174705 -0.318674 -0.020916 0.0175459 -0.318519 -0.0209318 0.0169891 -0.318564 -0.0216977 0.0134793 -0.317908 -0.0219949 0.00910874 -0.317731 -0.0224416 0.000727117 -0.317382 -0.0224771 -2.8832e-06 -0.317334 -0.0224005 -2.88311e-06 -0.317656 0.0368892 -2.8832e-06 -0.363763 0.0365588 -2.88311e-06 -0.363783 -0.020154 -0.0191013 -0.31957 -0.0188474 -0.0215459 -0.320855 -0.018727 -0.0215583 -0.320681 -0.0170573 -0.0230149 -0.321995 -0.0171833 -0.0230026 -0.322167 -0.0168314 -0.0232317 -0.322444 -0.0167045 -0.0232437 -0.322272 -0.0128098 -0.0247007 -0.325314 -0.00873625 -0.0248156 -0.328488 0.00717486 -0.0248605 -0.341182 0.00350667 -0.0248648 -0.338054 0.0149621 -0.0249145 -0.347006 0.0255485 -0.0249227 -0.355538 0.0256739 -0.0249477 -0.355377 0.0271071 -0.0248611 -0.356766 0.027236 -0.0248833 -0.356605 0.0295988 -0.0241601 -0.358465 0.0322864 -0.0221466 -0.360578 0.0327328 -0.0214503 -0.3612 0.0328716 -0.0214591 -0.361037 0.03431 -0.0190572 -0.362166 0.0346454 -0.0182421 -0.362429 0.0353826 -0.0153288 -0.363005 0.0354903 -0.0144702 -0.363088 0.0358998 -0.0145099 -0.363001 0.0357909 -0.0153786 -0.362916 0.0352154 -0.0184484 -0.362407 0.030569 -0.0240327 -0.358831 0.0299509 -0.0246071 -0.358291 0.0274879 -0.0253557 -0.356365 0.0258766 -0.0254209 -0.355105 0.0258531 -0.0252197 -0.35514 0.0214261 -0.0251798 -0.35168 0.0151726 -0.025389 -0.346736 0.00751285 -0.0253578 -0.340747 -0.00852196 -0.0252929 -0.32821 -0.0126401 -0.024971 -0.325047 -0.0139934 -0.0246722 -0.32399 -0.0140026 -0.0248761 -0.323924 -0.0166034 -0.0234879 -0.321949 -0.0170123 -0.0234391 -0.321571 -0.0186829 -0.0217559 -0.320322 -0.0190277 -0.0215717 -0.319995 -0.0189359 -0.0214312 -0.320124 -0.0202645 -0.0193315 -0.319028 -0.0204545 -0.0188713 -0.31888 -0.020336 -0.0187781 -0.31903 -0.0214177 -0.0155229 -0.318127 -0.0216663 -0.0137655 -0.317932 -0.0215332 -0.0137364 -0.318092 -0.0222062 -0.00817401 -0.31751 -0.0225899 -2.8832e-06 -0.31721 -0.0224114 -2.88317e-06 -0.317488 -0.0220724 -0.00815401 -0.317671 -0.0220165 -0.00813753 -0.317872 -0.0214781 -0.0137125 -0.318294 -0.0212868 -0.0154748 -0.318286 -0.0201488 -0.0192319 -0.319176 -0.0201096 -0.0191502 -0.319368 -0.0186687 -0.0216327 -0.320493 -0.0169632 -0.0232551 -0.321667 -0.00854824 -0.0250878 -0.328245 -0.0127037 -0.0248018 -0.32516 0.00369258 -0.025137 -0.337815 -0.00862413 -0.0249188 -0.328343 0.00748693 -0.0251547 -0.340781 0.0151464 -0.0251866 -0.34677 0.015072 -0.0250189 -0.346865 0.0274444 -0.0251539 -0.356386 0.0298658 -0.0244145 -0.358281 0.029741 -0.0242561 -0.358342 0.0304338 -0.0238793 -0.358886 0.03262 -0.0223543 -0.360436 0.0332198 -0.0216507 -0.360905 0.0330446 -0.0215303 -0.360932 0.0346935 -0.0191925 -0.362058 0.034496 -0.0191072 -0.362069 0.0350369 -0.0183583 -0.362327 0.0356859 -0.0144849 -0.363 0.0365003 -0.00468731 -0.363636 0.0367154 -0.00469787 -0.363639 0.036651 -2.88315e-06 -0.363754 -0.0223988 -2.88314e-06 -0.317572 -0.0212346 -0.0154353 -0.318487 -0.0215108 -0.013698 -0.318501 -0.0202947 -0.0187018 -0.319224 -0.0212705 -0.0154116 -0.318695 -0.020338 -0.0186561 -0.319427 -0.0189155 -0.0213159 -0.3203 -0.0189702 -0.0212462 -0.320491 -0.0169792 -0.0231045 -0.321818 -0.0166236 -0.0233346 -0.322097 -0.0140425 -0.0245058 -0.324116 -0.0141409 -0.0244074 -0.324279 0.00361754 -0.0249686 -0.337912 0.00730198 -0.0248825 -0.34102 0.00741235 -0.0249866 -0.340878 0.0213517 -0.0250121 -0.351775 0.0212419 -0.0249077 -0.351916 0.0257814 -0.0250526 -0.355236 0.0273553 -0.0249869 -0.35647 0.0302851 -0.0237869 -0.359005 0.0324539 -0.022224 -0.360469 0.0348343 -0.018285 -0.362334 0.0355778 -0.0153472 -0.362915 0.0363039 -0.00468112 -0.363725 -0.0221624 -0.00812565 -0.318256 -0.0220484 -0.00812749 -0.31808 -0.0204581 -0.0186493 -0.319602 0.0201918 0.0149097 -0.0029743 0.0201989 0.0148575 -0.00304496 0.0202006 0.0148343 -0.00306259 0.0201876 0.0155495 -0.00293187 0.0201714 0.0158004 -0.0027696 0.0197945 0.0154139 0.00100393 0.0200386 0.0163912 -0.00143984 0.0196983 0.0154531 0.00196667 0.0201832 0.0156611 -0.0028881 0.0200386 0.0152287 -0.00143997 0.0202006 -0.01484 -0.00306259 0.0201876 -0.0155552 -0.00293187 0.0200386 -0.016397 -0.00143984 0.0196983 -0.0154589 0.00196667 0.0201714 -0.0158062 -0.0027696 -0.0227673 -0.0155029 0.00128594 -0.0225206 -0.0180029 0.00358066 -0.0146908 0.0175196 0.0400475 -0.0108766 -0.0181281 0.0372294 -0.0146908 -0.0175254 0.0400475 -0.0085792 0.0154971 0.0433276 -0.0140294 0.0184971 0.0366221 -0.0145082 0.0181223 0.0385975 -0.0145082 -0.0181281 0.0385975 -0.0085792 -0.0155029 0.0433276 -0.0103443 -0.0155029 0.0439926 -0.00917515 -0.0158777 0.0417457 -0.0132971 -0.0155029 0.0451049 -0.0136005 -0.0155977 0.0442941 0.00104988 0.00249712 0.0182161 0.00545171 0.00249712 0.0134336 0.00496662 -0.00250288 0.0141394 0.014047 0.00526876 -0.00358305 0.0196942 0.00527573 -0.0194983 0.0144419 0.00549712 -0.00125676 0.0202846 0.00249712 -0.0267721 0.0130491 0.00249712 -0.00631572 0.0130856 0.00309286 -0.00623973 0.0202468 0.00318163 -0.0264279 0.020204 0.00357321 -0.0259457 0.0131873 0.00364517 -0.00602166 0.0199608 0.00470971 -0.0229355 0.00129745 0.00399712 0.0185327 0.00374211 0.00399712 0.016277 0.00344638 0.00249712 0.0160049 0.00578774 0.00399712 0.0136541 0.00455005 0.00509519 0.0170207 0.00670578 0.00509519 0.0142566 0.00566382 0.00337032 0.0133455 0.00565371 0.00549712 0.0180365 -0.0175405 0.00249712 0.0327516 -0.0174063 0.00394159 0.0331171 0.00197381 0.00509519 0.0193977 -0.0166262 0.00549707 0.035823 0.0103815 -0.00550268 0.0101183 0.0104144 -0.00550288 0.0101299 0.00104988 -0.00250288 0.0182161 0.00119054 -0.00365093 0.018396 0.00566569 -0.00337985 0.0133447 0.00740199 -0.00550288 0.0158912 0.00618896 -0.00408327 0.0131101 0.005152 -0.00365093 0.0142727 0.00567992 -0.0046242 0.0146525 0.00159111 -0.0046242 0.0189083 0.00647001 -0.00527452 0.0152208 0.00289774 -0.00550288 0.0205794 -0.0170744 -0.00507199 0.0342289 0.0021906 -0.00527452 0.019675 -0.0175405 -0.00250288 0.0327516 0.00996863 -2.88296e-06 -0.342032 0.00964673 0.00152212 -0.341781 0.0139723 -2.88296e-06 -0.336912 0.0136504 0.00152212 -0.33666 0.012771 0.00263849 -0.335972 0.0115696 0.00304712 -0.335033 0.00548507 0.00152212 -0.338527 0.00516316 -2.88296e-06 -0.338275 0.00948877 0.00152212 -0.333406 0.00636453 -0.00264426 -0.339214 0.0115696 -0.00305288 -0.335033 0.0136504 -0.00152788 -0.33666 0.00964673 -0.00152788 -0.341781 0.0122051 -0.00340288 -0.343781 0.00876727 -0.00264426 -0.341093 0.0075659 -0.00305288 -0.340154 0.00548507 -0.00152788 -0.338527 0.00292667 0.00339712 -0.336526 0.00636453 0.00263849 -0.339214 0.0075659 0.00304712 -0.340154 0.0075659 0.00679712 -0.340154 0.00876727 0.00263849 -0.341093 0.0122051 0.00339712 -0.343781 0.00220898 -2.8818e-06 -0.335965 0.000361121 -2.88208e-06 -0.338329 0.00107881 0.00339712 -0.33889 0.00488744 0.00588609 -0.338059 0.0102444 0.00588609 -0.342248 0.011075 -2.88208e-06 -0.346706 0.0129228 -2.8818e-06 -0.344342 0.0102444 -0.00589185 -0.342248 0.0075659 -0.00680288 -0.340154 0.00488744 -0.00589185 -0.338059 0.00303958 -0.00589185 -0.340423 0.00292667 -0.00340288 -0.336526 -0.00479924 0.0144971 0.0408033 0.0108213 0.0144971 0.0407975 -0.00399219 0.0144971 0.0388528 -0.000279791 0.0144971 0.0409943 0.0100128 0.0144971 0.0388476 0.006302 0.0144971 0.0409919 0.0087272 0.0144971 0.0371735 -0.00270358 0.0144971 0.0486128 -0.00479768 0.0144971 0.0449888 0.000916156 0.0144971 0.0350836 -0.00270783 0.0144971 0.0371777 -0.00102848 0.0144971 0.0498971 0.00111303 0.0144971 0.0461847 0.00301322 0.0144971 0.0466931 0.00301481 0.0144971 0.0509789 0.00510746 0.0144971 0.0507026 0.0100158 0.0144971 0.0469334 0.0108229 0.0144971 0.044983 0.00681181 0.0144971 0.0428917 0.006302 -0.0145029 0.0409919 0.0108213 -0.0145029 0.0407975 0.0070521 -0.0145029 0.0358891 0.000916156 -0.0145029 0.0350836 0.00300881 -0.0145029 0.0348073 0.00510167 -0.0145029 0.0350821 -0.00479924 -0.0145029 0.0408033 -0.00399219 -0.0145029 0.0388528 -0.00270783 -0.0145029 0.0371777 -0.00103368 -0.0145029 0.0358921 -0.00078819 -0.0145029 0.0428945 -0.00507398 -0.0145029 0.0428961 0.00111303 -0.0145029 0.0461847 -0.00270358 -0.0145029 0.0486128 -0.000278381 -0.0145029 0.0447943 0.000921953 -0.0145029 0.0507042 -0.00102848 -0.0145029 0.0498971 0.0110976 -0.0145029 0.0428901 0.00681181 -0.0145029 0.0428917 0.00510746 -0.0145029 0.0507026 0.00301481 -0.0145029 0.0509789 0.0108229 -0.0145029 0.044983 0.0100158 -0.0145029 0.0469334 0.00873145 -0.0145029 0.0486085 0.0070573 -0.0145029 0.0498941 0.0201918 -0.0149155 -0.0029743 0.0201989 -0.0148633 -0.00304496 0.0201467 -0.0150382 -0.00143891 0.0200386 -0.0152345 -0.00143997 0.0201758 -0.0149842 -0.00281363 0.0201943 -0.0148151 -0.00219005 0.0201537 -0.0150382 -0.00219041 0.0197945 -0.0154197 0.00100393 0.0194366 -0.0155029 0.00375601 0.0201873 -0.0148151 -0.00143851 0.0200884 -0.0151618 -0.00143948 0.0196058 -0.0151599 0.0480582 0.0193464 -0.0154133 0.0480556 0.0196047 -0.0151618 0.0480582 0.0187102 -0.0155029 0.0504731 0.0178562 -0.0148151 0.0542648 0.0177738 -0.0151599 0.0542122 0.0192963 -0.0151599 0.0506112 0.0175584 -0.0154111 0.0540745 0.0151452 -0.0151599 0.0571062 0.0149875 -0.0154111 0.056905 0.0117068 -0.0151599 0.058967 0.00784631 -0.0151599 0.0595848 0.0190474 -0.0154111 0.0505526 0.0172664 -0.0155029 0.0538879 0.0116246 -0.0154111 0.058725 0.0147738 -0.0155029 0.0566323 0.00784887 -0.0154111 0.0593292 0.00284654 -0.0151618 0.0595349 0.00784534 -0.0148151 0.0596826 0.00284557 -0.0148151 0.0596338 -0.0126557 -0.0148151 0.0487927 0.00284907 -0.0154133 0.0592766 0.00285241 -0.0155029 0.0589339 -0.000271338 -0.0151599 0.0592098 -0.00209715 -0.0148151 0.058836 -0.00548716 -0.0151599 0.0572032 -0.00974479 -0.0151599 0.0535834 -0.00658295 -0.0148151 0.0566124 -0.00981975 -0.0148151 0.0536462 -0.00535662 -0.0154111 0.0569834 -0.0125642 -0.0151599 0.0487582 -0.00022091 -0.0154111 0.0589592 -0.0051797 -0.0155029 0.0566856 -0.00954886 -0.0154111 0.0534192 -0.0138605 -0.0151599 0.0453172 -0.012325 -0.0154111 0.0486681 -0.0136213 -0.0154111 0.0452271 -0.0139322 -0.0155084 0.0443965 -0.0143088 -0.0149265 0.044399 -0.0138859 -0.0158777 0.0435203 -0.0142249 -0.0157954 0.043604 -0.0145023 -0.0155681 0.043593 -0.014191 -0.0152632 0.0444348 -0.0141076 -0.0161774 0.0429168 -0.0153305 -0.0170096 0.0405062 -0.0144466 -0.0160952 0.0430006 -0.0149212 -0.0175203 0.0400501 -0.0151379 -0.017447 0.0400224 -0.014724 -0.0158679 0.0429896 -0.0148668 -0.0155552 0.0428867 -0.0140294 -0.0185029 0.0366221 -0.0148035 -0.0181413 0.0385053 -0.0146569 -0.018151 0.0385573 -0.0140322 0.0184971 0.0366212 -0.0148035 0.0181356 0.0385053 -0.0149405 0.0180938 0.0384443 -0.0153305 0.0170039 0.0405062 -0.0144466 0.0160894 0.0430006 -0.0153174 0.0173077 0.0399675 -0.0151379 0.0174412 0.0400224 -0.0147309 0.0181445 0.0385326 -0.0149212 0.0175145 0.0400501 -0.0148668 0.0155495 0.0428867 -0.014724 0.0158621 0.0429896 -0.0145023 0.0155623 0.043593 -0.0138859 0.0158719 0.0435203 -0.0141076 0.0161717 0.0429168 -0.0136005 0.0155919 0.0442941 -0.0142249 0.0157896 0.043604 -0.0139322 0.0155026 0.0443965 -0.0146451 0.0152497 0.0434902 -0.0136213 0.0154054 0.0452271 -0.0138605 0.0151541 0.0453172 -0.014191 0.0152574 0.0444348 -0.0143088 0.0149207 0.044399 -0.0120007 0.0154971 0.048546 -0.0125642 0.0151541 0.0487582 -0.0126557 0.0148093 0.0487927 -0.00189599 0.0154054 0.058529 0.00284907 0.0154075 0.0592766 -0.0101802 0.0148093 0.0532008 -0.012325 0.0154054 0.0486681 -0.0099017 0.0154054 0.0529832 -0.0101031 0.0151541 0.0531406 -0.00646512 0.0151541 0.0565752 -0.0065208 0.0148093 0.0566556 -0.00197254 0.0151541 0.0587729 0.00284654 0.015156 0.0595349 -0.00962869 0.0154971 0.0527699 -0.00631956 0.0154054 0.0563651 0.00285241 0.0154971 0.0589339 0.00284903 0.0154054 0.0592804 0.00284653 0.0151541 0.059536 0.00784534 0.0148093 0.0596826 0.00784631 0.0151541 0.0595848 0.0193225 0.0148093 0.0509111 0.0197036 0.0148093 0.0480591 0.0196058 0.0151541 0.0480582 0.0110974 0.0148093 0.059257 0.0110713 0.0151541 0.0591628 0.0140357 0.0151541 0.0578762 0.0173107 0.0151541 0.0548837 0.0196047 0.015156 0.0480582 0.0192279 0.0151541 0.0508864 0.0139024 0.0154054 0.0576581 0.0189806 0.0154054 0.0508217 0.0171055 0.0154054 0.0547313 0.0109105 0.0154971 0.0585826 0.00785233 0.0154971 0.0589828 0.011003 0.0154054 0.0589164 0.00784887 0.0154054 0.0593292 0.0193464 0.0154075 0.0480556 0.0196536 0.0154669 0.00237204 0.0190037 0.0154971 0.0480523 0.0200884 0.015156 -0.00143948 0.0202016 0.0148093 -0.00307213 0.0201943 0.0148093 -0.00219005 0.0201758 0.0149785 -0.00281363 0.0201467 0.0150324 -0.00143891 0.0201537 0.0150324 -0.00219041 0.0203061 0.00123084 -0.0268331 0.0203416 0.00251457 -0.027114 0.020328 0.00250598 -0.0269406 0.02031 0.00250156 -0.0268554 0.0203386 0.00251032 -0.027027 0.0203287 0.00342725 -0.0267611 0.0203238 0.00394936 -0.0262655 0.0203208 0.00489416 -0.0247018 0.0203077 0.00472842 -0.0246269 0.020303 0.00525112 -0.0231033 0.0203239 0.0054647 -0.0231691 0.0202975 0.00591979 -0.0195897 0.0203386 0.00621938 -0.0196311 0.0202886 0.00612656 -0.0151649 0.0203328 0.00285591 -0.0269594 0.0203249 0.00336437 -0.0266755 0.020318 0.00385177 -0.0261824 0.0202958 0.0037555 -0.0261005 0.0202328 0.00504742 -0.0230404 0.0201671 0.00564648 -0.0195515 0.0203216 0.0028282 -0.0268733 0.0203098 0.00330201 -0.0265908 0.0202837 0.00324087 -0.026508 0.0202576 0.00366213 -0.0260211 0.0201846 0.00441707 -0.0244863 0.0202618 0.0045676 -0.0245543 0.0199596 0.00542491 -0.01952 0.0203021 0.00280081 -0.0267885 0.0202747 0.00277397 -0.0267057 0.0200788 0.00428181 -0.0244251 0.0201167 0.00486387 -0.0229835 0.0203272 -2.88296e-06 -0.0268926 0.0203336 -2.88296e-06 -0.0269113 0.0203061 -0.0012366 -0.0268331 0.02031 -0.00250733 -0.0268554 0.0203632 -0.00125406 -0.027175 0.0193598 0.00549712 -0.0151608 0.0197465 0.00557492 -0.0151625 0.0200837 0.00579621 -0.00830333 0.020073 0.00579621 -0.0151639 0.0202993 0.00612656 -0.00830297 0.0203596 0.00651457 -0.0151652 0.0193705 0.00549712 -0.00830452 0.019719 0.00557492 -0.00144456 0.0197572 0.00557492 -0.00830388 0.0202611 0.00612656 -0.00143926 0.0202886 -0.00613233 -0.0151649 0.0201262 -0.00579173 -0.0175295 0.0203484 -0.00643667 -0.0175759 0.0203125 -0.00429317 -0.0255322 0.0203212 -0.00442338 -0.025612 0.0203266 -0.0036338 -0.0265974 0.0203221 -0.00355773 -0.0265127 0.0202943 -0.00609464 -0.0175516 0.0203011 -0.00550552 -0.0221129 0.020303 -0.00525505 -0.0231098 0.0202329 -0.00505151 -0.0230468 0.0203304 -0.00301038 -0.0268995 0.0203184 -0.00297259 -0.0268136 0.0203386 -0.00251609 -0.027027 0.0202145 -0.00527906 -0.0220566 0.0202806 -0.0041656 -0.0254541 0.0202262 -0.00404364 -0.0253795 0.0203047 -0.00348242 -0.0264289 0.0202976 -0.00293531 -0.0267292 0.020328 -0.00251174 -0.0269406 0.0198644 -0.00556443 -0.0175123 0.0198851 -0.00492197 -0.021967 0.0200729 -0.00508045 -0.0220069 0.020117 -0.00486807 -0.0229899 0.0199613 -0.00471396 -0.0229419 0.0202747 -0.00340886 -0.0263472 0.0202682 -0.0028989 -0.0266471 0.0193323 0.00549712 -0.00144834 0.0195618 0.00579621 0.0480562 0.0200455 0.00579621 -0.00144137 0.0197773 0.00612656 0.0480584 0.0203321 0.00651457 -0.00143857 0.0193705 -0.00550288 -0.00830452 0.019719 -0.00558068 -0.00144456 0.0200455 -0.00580197 -0.00144137 0.0203321 -0.00652033 -0.00143857 0.0197465 -0.00558068 -0.0151625 0.0197572 -0.00558068 -0.00830388 0.020073 -0.00580197 -0.0151639 0.0200837 -0.00580197 -0.00830333 0.0202993 -0.00613233 -0.00830297 0.0106726 0.00579621 0.0592204 0.00784539 0.00651457 0.0598274 0.0193522 0.00651457 0.051342 0.0192842 0.00612656 0.0513217 0.0148583 0.00651457 0.0576234 0.0107229 0.00612656 0.05943 0.0107395 0.00651457 0.0594991 0.00784608 0.00612656 0.0597564 0.0148171 0.00612656 0.0575655 0.0179191 0.00612656 0.0543033 0.0190776 0.00579621 0.05126 0.0105963 0.00557492 0.0589029 0.014692 0.00579621 0.0573899 0.0177375 0.00579621 0.0541872 0.0192353 0.00557492 0.048053 0.0145026 0.00557492 0.057124 0.0142782 0.00549712 0.056809 0.0174623 0.00557492 0.0540114 0.0183942 0.00549712 0.051056 0.0187647 0.00557492 0.0511666 0.0202611 -0.00613232 -0.00143926 0.0197773 -0.00613232 0.0480583 0.00785516 0.00549712 0.0588276 0.00785138 0.00557492 0.0592143 0.00285166 0.00557492 0.0591654 0.00784819 0.00579621 0.0595408 0.00284633 0.00612656 0.0597075 0.00284563 0.00651457 0.0597786 0.00785135 -0.00558068 0.0592143 0.0192353 -0.00558068 0.048053 0.0188887 -0.00580197 0.0518373 0.00784539 -0.00652033 0.0598274 0.0104574 -0.00652033 0.0595633 0.0171706 -0.00652033 0.0554583 0.0195618 -0.00580197 0.0480562 0.0190917 -0.00613232 0.0519096 0.0171156 -0.00613232 0.0554133 0.0141265 -0.00613232 0.0580218 0.0104425 -0.00613232 0.0594938 0.0185811 -0.00558068 0.0517276 0.0166956 -0.00558068 0.0550705 0.0169486 -0.00580197 0.055277 0.0138437 -0.00558068 0.0575593 0.014014 -0.00580197 0.0578379 0.0103287 -0.00558068 0.0589638 0.0103972 -0.00580197 0.059283 0.00784605 -0.00613232 0.0597564 0.0102475 -0.00550288 0.0585857 0.00784815 -0.00580197 0.0595408 -0.00959244 0.00549712 0.0525632 -0.00989926 0.00557492 0.0527986 -0.0127242 0.00612656 0.0488201 -0.0103294 0.00612656 0.0531286 -0.00199869 0.00557492 0.0583757 0.00284845 0.00579621 0.059492 -0.0021656 0.00612656 0.0588914 -0.00218747 0.00651457 0.058959 -0.0063736 0.00557492 0.056187 -0.00209923 0.00579621 0.0586863 -0.00672722 0.00651457 0.0566879 -0.0101583 0.00579621 0.0529974 -0.00656193 0.00579621 0.0564538 -0.00668625 0.00612656 0.0566299 0.00284848 -0.00580197 0.059492 -0.011855 0.00549712 0.0484926 -0.0122169 0.00557492 0.0486289 -0.0125225 0.00579621 0.0487441 -0.0174904 0.00612656 0.0361684 -0.0175569 0.00651457 0.0361935 0.00285547 -0.00550288 0.0587788 -0.0111498 -0.00580197 0.0515532 -0.0125225 -0.00580197 0.048744 -0.0108712 -0.00558068 0.0513829 0.00285168 -0.00558068 0.0591654 -0.00252554 -0.00558068 0.0581951 -0.00271 -0.00613232 0.0587049 0.00284635 -0.00613232 0.0597075 0.00284563 -0.00652033 0.0597786 -0.00748493 -0.00580197 0.0557526 -0.00762124 -0.00613232 0.0559196 -0.0113337 -0.00613232 0.0516657 -0.0103241 -0.00652033 0.0532517 -0.0113943 -0.00652033 0.0517028 -0.00239395 -0.00550288 0.0578315 -0.00703391 -0.00550288 0.0552001 -0.00727845 -0.00558068 0.0554997 -0.00263665 -0.00580197 0.0585022 -0.0172952 0.00579554 0.0360734 -0.0169831 0.00557492 0.0359773 -0.0172887 0.00579621 0.0360924 -0.017498 0.0061261 0.0361479 -0.0175654 0.0065145 0.036171 -0.0170787 0.00505757 0.0342142 -0.0169887 0.00557437 0.0359592 -0.0181789 0.00556271 0.0343247 -0.0178277 0.00393983 0.0332941 -0.0174859 0.00508241 0.0343567 -0.0178769 0.00526196 0.034396 -0.0179626 0.00250537 0.0329448 -0.0184264 0.00251185 0.0329266 -0.0182738 0.004039 0.0332899 -0.0186515 0.00421839 0.0331054 -0.0188818 0.00444053 0.0327792 -0.0169831 -0.00558068 0.0359773 -0.0122169 -0.00558068 0.0486289 -0.0127242 -0.00613232 0.04882 -0.0179987 -2.88296e-06 0.032973 -0.0188321 0.00251515 0.0327009 -0.0190921 0.00251457 0.0323163 -0.0184261 -0.00253407 0.0329264 -0.0188318 -0.00253931 0.0327007 -0.0184264 -0.00251762 0.0329266 -0.0188321 -0.00252092 0.0327009 -0.0188778 -0.00446487 0.032789 -0.018648 -0.00424071 0.0331141 -0.0182709 -0.00405968 0.0332977 -0.0179623 -0.00252661 0.0329446 -0.0172457 -0.00462988 0.0336436 -0.0174038 -0.00396129 0.033125 -0.0175402 -0.00251852 0.0327514 -0.0174813 -0.00509731 0.0343712 -0.0172887 -0.00580197 0.0360924 -0.0178716 -0.00527756 0.0344111 -0.0174904 -0.00613232 0.0361684 -0.0175569 -0.00652033 0.0361935 -0.0181726 -0.00557913 0.0343413 -0.0178251 -0.00395958 0.0333016 -0.0190921 -0.00252033 0.0323163 -0.0188684 -2.88296e-06 0.0327292 -0.0184626 -2.88296e-06 0.0329549 -0.0179626 -0.00251114 0.0329448 -0.0175765 -2.88296e-06 0.0327797 -0.000278381 0.0144971 0.0447943 0.00301311 0.0141971 0.0463931 0.00476293 0.0141971 0.0459236 0.00491303 0.0144971 0.0461833 0.00604355 0.0141971 0.044642 0.00630341 0.0144971 0.0447919 0.00651181 0.0141971 0.0428918 0.00491059 0.0144971 0.0396015 0.0030104 0.0144971 0.0390931 0.00111059 0.0144971 0.0396029 -1.99281e-05 0.0141971 0.0411443 -0.00078819 0.0144971 0.0428945 -1.86293e-05 0.0141971 0.0446443 0.00630341 -0.0145029 0.0447919 0.00491303 -0.0145029 0.0461833 0.00301322 -0.0145029 0.0466931 -1.86293e-05 -0.0142029 0.0446443 -0.000279791 -0.0145029 0.0409943 0.00111059 -0.0145029 0.0396029 0.00126069 -0.0142029 0.0398627 0.00301051 -0.0142029 0.0393931 0.0030104 -0.0145029 0.0390931 0.00476068 -0.0142029 0.0398614 0.00491059 -0.0145029 0.0396015 0.00604225 -0.0142029 0.041142 0.00651181 -0.0142029 0.0428918 0.00604355 -0.0142029 0.044642 0.0346572 -2.883e-06 -0.365779 0.0344994 0.008002 -0.365598 -0.0240101 -2.88299e-06 -0.319615 0.0349058 0.00802675 -0.365518 -0.00325894 0.0249952 -0.335698 0.00522762 0.0250361 -0.342076 0.00510158 0.0250119 -0.342238 0.0217343 0.0250517 -0.354988 0.0248866 0.0250546 -0.357714 0.0267195 0.0248524 -0.359138 0.0320911 0.0209598 -0.36332 0.0343193 0.0142548 -0.36506 0.0344619 0.0142571 -0.364903 -0.0187742 0.0230586 -0.32355 -0.0151097 0.0247519 -0.326146 -0.0152374 0.0247358 -0.326314 -0.0123324 0.0249716 -0.328599 -0.0122049 0.024993 -0.328436 0.0343089 0.00798313 -0.365507 0.0331152 0.01742 -0.364573 0.0315852 0.0206475 -0.363377 0.0292635 0.0230749 -0.361562 0.0293707 0.0232532 -0.361589 0.0288248 0.0236173 -0.361163 0.0264405 0.024386 -0.359354 0.0264959 0.0245849 -0.359343 0.0247074 0.0247827 -0.357946 0.0246827 0.0245827 -0.35798 0.0214278 0.0247541 -0.355382 0.00491863 0.0247398 -0.342473 -0.0034434 0.024723 -0.335934 -0.0125181 0.0246995 -0.328838 -0.012544 0.0244958 -0.328873 -0.0153871 0.0242651 -0.32665 -0.0163877 0.0239606 -0.325868 -0.0207783 0.0205539 -0.322435 -0.0208776 0.0206819 -0.322301 -0.0225567 0.0160382 -0.321044 -0.0217257 0.0190618 -0.321637 -0.022682 0.0154127 -0.320946 -0.0228127 0.0154583 -0.320788 -0.0231845 0.011141 -0.320553 -0.0233845 0.00891535 -0.320397 -0.0235177 0.00893643 -0.320237 -0.0238376 -2.883e-06 -0.320042 -0.0235739 0.00895382 -0.320037 -0.0233174 0.0111662 -0.320394 -0.0226857 0.0160941 -0.320887 -0.0227369 0.01614 -0.320687 -0.021765 0.0191441 -0.321447 -0.0193336 0.0224492 -0.323508 -0.0188582 0.0228234 -0.323879 -0.0163648 0.0243233 -0.325666 -0.0164057 0.02416 -0.325796 -0.0153366 0.0246352 -0.326472 -0.0153897 0.0244684 -0.326591 -0.0124432 0.0248678 -0.328741 -0.00336893 0.0248908 -0.335839 0.00499239 0.0249072 -0.342378 0.0247794 0.0249492 -0.357853 0.0289591 0.0237693 -0.361111 0.0295133 0.0234 -0.361543 0.0312966 0.0213856 -0.363094 0.0314691 0.0215053 -0.363069 0.0319158 0.0208932 -0.363418 0.0317365 0.0207824 -0.363438 0.033256 0.018272 -0.364464 0.0330564 0.0181995 -0.36447 0.0332953 0.0174956 -0.364657 0.0341252 0.01424 -0.365144 0.0339144 0.0142153 -0.365141 0.0347111 0.00801747 -0.365602 -0.0233421 0.0111998 -0.319987 -0.0233732 0.011187 -0.320193 -0.0228658 0.0154959 -0.320588 -0.0217219 0.0191938 -0.321246 -0.0209051 0.0207874 -0.322121 -0.0208558 0.0208516 -0.321928 -0.0193298 0.0225907 -0.323352 -0.0188477 0.0229701 -0.323727 -0.0162723 0.0244211 -0.325502 0.021609 0.0250262 -0.355149 0.0215008 0.024921 -0.355287 0.0265945 0.0247497 -0.359267 0.0291067 0.0238623 -0.360995 0.0296662 0.0234895 -0.361431 0.0316402 0.0215775 -0.362968 0.0334434 0.0183155 -0.364374 0.0336881 0.0175947 -0.364566 0.0334985 0.0175576 -0.364654 0.0351469 -2.88299e-06 -0.365851 0.0350604 -2.88299e-06 -0.365876 -0.0235432 0.0089645 -0.31983 -0.0228318 0.0155187 -0.320381 -0.0216039 0.0192021 -0.321071 -0.0227011 0.0161678 -0.320481 -0.0207385 0.0208633 -0.321754 -0.0192609 0.0226764 -0.323172 -0.02374 -0.00577406 -0.320064 -0.0239308 -2.883e-06 -0.319936 -0.0240112 -2.88299e-06 -0.319697 -0.0239978 -2.883e-06 -0.319782 0.0352908 -2.88297e-06 -0.365764 0.0348208 -0.00915274 -0.365452 0.0349825 -2.883e-06 -0.365885 0.0344146 -0.00912529 -0.365532 0.0348161 -2.883e-06 -0.365862 0.0346754 -2.883e-06 -0.365792 0.0342243 -0.00910436 -0.36544 -0.0238713 -2.88296e-06 -0.319314 -0.0239663 -2.88297e-06 -0.319453 -0.0237666 -0.00579429 -0.319657 -0.0236551 -0.00579584 -0.319481 -0.0228431 -0.0147272 -0.320111 -0.0217267 -0.0191885 -0.321242 -0.0214153 -0.019856 -0.321487 -0.0212977 -0.0198654 -0.321313 -0.0199156 -0.0219643 -0.322398 -0.016713 -0.0242509 -0.325157 -0.0183278 -0.0233071 -0.323629 -0.0216157 -0.0189566 -0.32178 -0.0213153 -0.0195998 -0.322015 -0.021425 -0.0197102 -0.321873 -0.0193734 -0.0221965 -0.323533 -0.0194371 -0.0223669 -0.323427 -0.0173257 -0.0237679 -0.325077 -0.0142418 -0.0244617 -0.327545 -0.0142267 -0.0246664 -0.327501 -0.0119427 -0.0245049 -0.329343 -0.00534698 -0.0245233 -0.3345 0.0254311 -0.0245571 -0.358565 0.0254686 -0.0247575 -0.358541 0.0260532 -0.0246807 -0.358998 0.0283331 -0.0236664 -0.360834 0.0284231 -0.0238544 -0.360849 0.0289657 -0.0235348 -0.361273 0.0309686 -0.0217889 -0.362838 0.0313455 -0.0209928 -0.363189 0.0327199 -0.0185278 -0.364264 0.0328926 -0.0186239 -0.364342 0.0331773 -0.0178654 -0.364564 -0.0229334 -0.0146795 -0.320694 -0.0229883 -0.0147071 -0.320494 -0.0227197 -0.0159425 -0.32086 -0.0217698 -0.0191388 -0.321443 -0.0217305 -0.0190566 -0.321634 -0.020084 -0.0217432 -0.322922 -0.0194349 -0.022507 -0.32327 -0.0168381 -0.0239932 -0.325458 -0.0119167 -0.0247084 -0.329308 -0.00532075 -0.024726 -0.334466 0.00561614 -0.0247476 -0.343018 0.0133809 -0.0247656 -0.34909 0.0134544 -0.0249327 -0.348996 0.0204479 -0.0247578 -0.354615 0.0205212 -0.0249248 -0.354521 0.0285511 -0.0240096 -0.360793 0.0291021 -0.0236855 -0.361222 0.031136 -0.0219144 -0.362809 0.0316677 -0.0212498 -0.363224 0.0314922 -0.021134 -0.363247 0.0330896 -0.0187027 -0.364334 0.0333788 -0.0179328 -0.36456 -0.0237967 -0.00578659 -0.319863 -0.0229564 -0.014724 -0.320287 -0.0227713 -0.0159863 -0.320661 -0.022736 -0.0160129 -0.320455 -0.0214604 -0.019801 -0.321686 -0.0200941 -0.0218715 -0.322756 -0.0200344 -0.0219498 -0.322571 -0.0193672 -0.0225921 -0.323089 -0.0172959 -0.0239265 -0.324938 -0.01721 -0.0240213 -0.324768 -0.0168024 -0.0241545 -0.325324 -0.0141599 -0.024835 -0.327396 -0.0118419 -0.0248767 -0.329212 -0.00524616 -0.0248938 -0.33437 0.00568984 -0.0249149 -0.342923 -0.00513601 -0.0249981 -0.334229 0.00579894 -0.0250197 -0.342783 0.0255517 -0.0249241 -0.358454 0.0261452 -0.0248466 -0.358917 0.0286949 -0.0241048 -0.360675 0.0292511 -0.0237777 -0.361107 0.0313041 -0.0219903 -0.362706 0.0318407 -0.0213197 -0.363124 0.0332756 -0.0187499 -0.364243 0.0343124 -0.0154669 -0.364786 0.0334168 -0.018757 -0.364085 0.0288292 -0.0241235 -0.360516 0.0263944 -0.0249742 -0.358626 0.0262657 -0.0249503 -0.358786 0.0256664 -0.0250289 -0.35832 0.0257934 -0.025054 -0.358161 0.0206297 -0.0250298 -0.354382 0.0207551 -0.0250552 -0.354222 0.013563 -0.0250377 -0.348857 0.00592493 -0.0250439 -0.342622 -0.00500921 -0.0250209 -0.334067 -0.0139257 -0.0249567 -0.327082 -0.0117311 -0.0249806 -0.329069 -0.0140533 -0.0249378 -0.327247 -0.0148254 -0.0248211 -0.326371 0.0335673 -0.0179732 -0.364471 0.0338429 -0.0148294 -0.365085 0.0336536 -0.0147984 -0.364994 0.0349634 -0.00915431 -0.365295 0.0342476 -0.0148701 -0.365004 0.0340535 -0.0148549 -0.365088 0.0346262 -0.00914245 -0.365536 -0.0125583 0.0159971 0.00725365 -0.0125583 0.0241971 0.00725365 -0.00724898 0.0241971 0.012559 0.00725102 0.0159971 0.0125537 0.00725102 0.0241971 0.0125537 0.0144964 0.0159971 -6.39292e-06 0.0144964 0.0241971 -6.39292e-06 0.012551 0.0159971 -0.00725567 0.012551 0.0241971 -0.00725567 0.0072417 0.0241971 -0.0125611 -0.0072583 0.0241971 -0.0125557 0.00636301 0.0159971 0.00367163 0.0125564 0.0159971 0.00724433 0.0072417 0.0159971 -0.0125611 -6.36475e-06 0.0159971 -0.00735101 -9.0182e-06 0.0159971 -0.014501 -0.0072583 0.0159971 -0.0125557 -0.0125637 0.0159971 -0.00724635 -0.00637029 0.0159971 -0.00367365 -0.0145036 0.0159971 4.36931e-06 -0.00735364 0.0159971 1.71586e-06 -0.00636756 0.0159971 0.00367635 -0.00367627 0.0159971 0.00636564 -0.00724898 0.0159971 0.012559 -9.09413e-07 0.0159971 0.00734899 1.74403e-06 0.0159971 0.014499 -0.0125583 -0.0242029 0.00725365 -0.00724898 -0.0242029 0.012559 -0.00724898 -0.0160029 0.012559 1.74403e-06 -0.0160029 0.014499 0.00725102 -0.0160029 0.0125537 0.0125564 -0.0242029 0.00724433 0.0144964 -0.0242029 -6.39292e-06 0.0072417 -0.0160029 -0.0125611 -9.0182e-06 -0.0242029 -0.014501 -0.0072583 -0.0242029 -0.0125557 -0.0125637 -0.0242029 -0.00724635 -0.0072583 -0.0160029 -0.0125557 -0.0145036 -0.0242029 4.36931e-06 -0.0125637 -0.0160029 -0.00724635 0.00303958 0.00588609 -0.340423 0.00571804 0.00679712 -0.342517 0.0083965 0.00588609 -0.344611 0.0103573 0.00339712 -0.346144 0.0103904 0.00364712 -0.346805 0.0111609 -2.88213e-06 -0.347407 0.0103573 -0.00340288 -0.346144 0.0083965 -0.00589185 -0.344611 0.00571804 -0.00680288 -0.342517 0.00107881 -0.00340288 -0.33889 -0.000340747 -2.88213e-06 -0.338414 0.000429715 0.00364712 -0.339017 0.0416589 0.00542388 -0.316235 0.0411104 0.0175027 -0.322494 0.0412685 0.0203902 -0.321061 0.0414063 0.0136202 -0.319637 0.0403485 0.0212574 -0.327408 0.039893 0.0216641 -0.328954 0.0392773 0.0198691 -0.328471 0.0407927 0.00493053 -0.318447 0.0413222 0.00841174 -0.318403 0.0415939 0.00883386 -0.317264 0.0414442 0.0129039 -0.319207 0.0406631 0.0209107 -0.325858 0.0404715 0.0117305 -0.321219 0.0411462 0.0122856 -0.320286 0.0411027 0.0129673 -0.320703 0.0404187 0.0123818 -0.321621 0.0400285 0.0159113 -0.32429 0.0407717 0.0166601 -0.323472 0.0402665 0.0200099 -0.326864 0.0401061 0.020797 -0.327808 0.0412685 -0.020396 -0.321061 0.0409921 -0.0185911 -0.323467 0.0383699 -0.0227592 -0.332584 0.0399717 -0.0163092 -0.324643 0.023422 0.00398815 -0.340492 0.0246757 -0.0118383 -0.341472 0.0406161 -0.00953933 -0.32005 0.0234229 -0.00400497 -0.340493 0.0271305 -0.019199 -0.343392 0.0259938 -0.0162858 -0.342503 0.0271263 0.0191835 -0.343388 0.0394556 0.0191157 -0.32756 0.0408476 0.00102594 -0.317903 0.04069 0.00803052 -0.319406 0.0416589 -0.00542964 -0.316235 0.0418389 0.0196129 -0.312396 0.0183274 0.0133681 -0.305052 0.0322518 0.0196881 -0.30461 0.0198206 -0.00901951 -0.305004 0.00190794 0.0233829 -0.314841 -0.000929234 -0.0206014 -0.321452 0.0154523 0.0121526 -0.306702 0.00328245 0.00539028 -0.324745 0.00357018 -2.88296e-06 -0.32497 0.00328245 -0.00539605 -0.324745 0.0179434 0.0020089 -0.306505 0.0024245 -0.0106907 -0.324075 0.0123198 -0.017859 -0.30695 0.0378105 0.0195596 -0.304433 0.03899 0.0195822 -0.304572 0.0391333 -0.0195938 -0.304614 0.0402096 0.0195625 -0.305139 0.0407423 -0.0195064 -0.305579 0.0407424 0.0195006 -0.305579 0.0411621 0.0194296 -0.306064 0.0417923 -0.0193128 -0.307363 0.041937 0.0193282 -0.308491 0.041937 -0.019334 -0.308491 0.011995 -0.0206977 -0.305728 0.0113918 -0.0208317 -0.305998 0.0146132 -0.020248 -0.30517 0.0105131 0.0210493 -0.306511 0.0135896 -0.015839 -0.30685 0.0134784 -0.018638 -0.305658 0.0168633 -0.00819982 -0.306591 0.0175146 -0.005413 -0.306539 0.0175098 0.00543273 -0.30654 0.0167108 0.0126908 -0.305514 0.0135721 0.0158631 -0.306851 0.0150126 -0.0196446 -0.305157 0.0181674 -0.00856512 -0.305449 0.0192826 0.00209899 -0.3054 0.0209636 0.00221008 -0.304968 0.0126327 0.0205642 -0.305503 0.0392145 -0.022193 -0.330752 0.0393286 -0.0196668 -0.328213 0.0401524 -0.0205854 -0.327541 0.0403279 -0.0133821 -0.322286 0.0398798 -0.0169013 -0.325199 0.0415448 -0.010493 -0.317954 0.0416469 -0.00625748 -0.316438 0.0413397 -0.0147201 -0.32035 0.0406424 -0.0176951 -0.324415 0.041027 -0.0140139 -0.321393 0.0412635 -0.00999138 -0.319072 0.0413868 -0.00595905 -0.317603 0.0407732 -0.00568888 -0.318636 0.0192226 0.00428748 -0.341017 0.0205703 -0.0127259 -0.342071 0.012771 -0.00264426 -0.335972 0.0103682 -0.00264426 -0.334094 -0.00226031 -0.0250605 -0.32422 0.0255532 -0.0253303 -0.345967 0.0205675 0.0127088 -0.342068 0.0103682 0.00263849 -0.334094 -0.00226031 0.0250547 -0.32422 0.00285406 0.0114865 -0.328219 0.00377635 0.00579477 -0.32894 0.00916686 -2.88296e-06 -0.333154 0.00948877 -0.00152788 -0.333406 0.00377635 -0.00580054 -0.32894 0.0414017 -0.00517078 -0.317408 0.0407927 -0.0049363 -0.318447 0.0416821 -0.00310548 -0.315829 0.0416915 0.00112882 -0.315659 0.0414303 -0.0029576 -0.317011 0.0414017 0.00516501 -0.317408 0.0408316 -0.00282343 -0.318063 0.041442 0.00107489 -0.316846 -0.00158175 0.0208026 -0.322846 -0.00320644 0.0247797 -0.319672 -0.000929234 0.0205956 -0.321452 -0.00383925 -0.0251706 -0.321966 -0.00354851 -0.0251823 -0.322708 -0.00391598 -0.0250892 -0.321022 -0.00158175 -0.0208084 -0.322846 -0.00287663 0.0251271 -0.323652 0.000379001 0.0159431 -0.324379 0.00101201 0.0157844 -0.32297 0.0024245 0.010685 -0.324075 0.00296288 -2.88296e-06 -0.3264 0.000379001 -0.0159488 -0.324379 0.00101201 -0.0157902 -0.32297 -0.00366832 -0.02495 -0.320238 -0.00151658 0.0213681 -0.324291 -0.00386526 0.0251594 -0.321858 0.000497454 0.0163765 -0.325866 0.00196292 0.0110858 -0.327012 0.00180569 0.0107924 -0.325495 0.00267225 0.00544447 -0.326172 0.00315156 -2.88296e-06 -0.327941 0.00267225 -0.00545024 -0.326172 0.00196292 -0.0110915 -0.327012 0.00180569 -0.0107981 -0.325495 -0.00151658 -0.0213738 -0.324291 0.000497454 -0.0163822 -0.325866 -0.000751206 -0.0221463 -0.3254 0.00133563 -0.0169743 -0.327031 0.00285304 -0.00559829 -0.327708 0.00285406 -0.0114923 -0.328219 0.00408567 -2.88296e-06 -0.329182 0.00285304 0.00559253 -0.327708 0.00133563 0.0169685 -0.327031 -0.000751206 0.0221405 -0.3254 0.0270056 0.0255049 -0.34678 0.0304823 0.0254728 -0.346013 0.0299531 0.025585 -0.346612 0.0262613 0.019293 -0.344169 0.0255532 0.0253245 -0.345967 0.0232047 0.0206225 -0.34413 0.0241389 0.0200718 -0.344571 0.0215722 0.0123694 -0.342564 0.0202631 0.00417293 -0.341541 0.0192235 -0.00430513 -0.341018 0.0215749 -0.0123862 -0.342566 0.0241433 -0.0200878 -0.344574 0.0232092 -0.0206387 -0.344134 0.028306 -0.0256059 -0.347049 0.020264 -0.00419026 -0.341541 0.0227079 -0.0120983 -0.342627 0.0214266 0.00407583 -0.341625 0.0227052 0.0120817 -0.342624 0.0282995 0.0255999 -0.347049 0.0252166 -0.0196207 -0.344588 0.0262655 -0.0193086 -0.344173 0.0214275 -0.00409288 -0.341625 0.0225358 0.00401094 -0.341257 0.0252123 0.019605 -0.344585 0.0292702 0.0256245 -0.346944 0.0259938 0.0162801 -0.342503 0.0237941 0.0118894 -0.34224 0.0246731 0.0118219 -0.34147 0.0225367 -0.00402782 -0.341257 0.0237967 -0.0119059 -0.342242 0.0304823 -0.0254786 -0.346013 0.0146132 0.0202423 -0.30517 0.0146263 0.0205729 -0.305098 0.0146325 0.0208443 -0.304895 0.0237739 0.0206852 -0.303997 0.0146307 0.0210078 -0.304598 0.0322604 0.0200078 -0.304543 0.0378031 0.0201422 -0.304181 0.0322633 0.0202741 -0.304353 0.0377843 0.0203581 -0.303585 0.03226 0.0204427 -0.304074 0.0389971 0.0198998 -0.304506 0.0390376 0.0201652 -0.304323 0.0378087 0.019877 -0.304367 0.039105 0.0203346 -0.304055 0.0391881 0.0203801 -0.303744 0.0377945 0.0203119 -0.303905 0.0405647 0.0203247 -0.304702 0.0412452 0.0197757 -0.306043 0.0402652 0.0198899 -0.305092 0.0403909 0.0201598 -0.304937 0.0417075 0.0202066 -0.305754 0.041747 0.0193141 -0.307212 0.0418353 0.0196779 -0.3072 0.0414399 0.020053 -0.305932 0.0422791 0.0199823 -0.308452 0.0420713 0.019962 -0.307137 0.0424032 0.020104 -0.307037 0.0427583 0.0200728 -0.306922 0.0103526 0.0213893 -0.306217 0.010226 0.0214708 -0.306028 0.0100829 0.0214815 -0.305834 0.00920611 0.021658 -0.3066 0.00969984 0.0212974 -0.307158 0.0104513 0.0212444 -0.306383 0.0120005 0.0206908 -0.305725 0.0125731 0.0210461 -0.305185 0.0124997 0.0211681 -0.304926 0.0126196 0.0208352 -0.305386 0.0146212 0.0210341 -0.304261 0.0418399 0.0196107 -0.312367 0.0419334 0.0199831 -0.312341 0.0420279 0.019697 -0.308467 0.0425511 0.0204031 -0.31233 0.0426339 0.0201197 -0.308448 0.043012 0.020078 -0.308457 0.0417552 0.0203076 -0.316208 0.0421903 0.0202693 -0.312328 0.0423841 0.0207249 -0.316209 0.0427679 0.0206676 -0.316236 0.00164475 0.0236746 -0.314483 0.00334255 0.0231788 -0.312468 0.00936079 0.0216474 -0.306752 0.00950121 0.0215798 -0.306902 0.00179926 0.0235658 -0.314675 0.00961706 0.0214602 -0.307041 0.00958174 0.0215054 -0.306997 0.0416589 0.0199317 -0.316235 0.0420176 0.0205947 -0.316199 0.0423929 0.0211185 -0.321103 0.0413685 0.0207694 -0.321033 0.0407662 0.0212919 -0.32583 0.0416366 0.021057 -0.321031 0.0420079 0.0211836 -0.321057 -0.00231748 0.0254168 -0.324285 -0.00339434 0.0258162 -0.324074 -0.00452376 0.0254469 -0.320916 -0.00402112 0.0252247 -0.320066 -0.00362946 0.0250689 -0.319148 -0.00297069 0.0254478 -0.323717 -0.00315435 0.0256922 -0.323867 -0.00388714 0.0256296 -0.32285 -0.00367593 0.0254376 -0.322766 -0.00424001 0.0255266 -0.321875 -0.00402262 0.0253741 -0.321857 -0.00428629 0.0253929 -0.320955 -0.00407821 0.0252692 -0.321002 -0.00383763 0.0251197 -0.320183 -0.0034595 0.0250451 -0.319333 -0.00331364 0.0249454 -0.319514 -0.00353931 0.0251763 -0.322726 -0.00391931 0.0250876 -0.321054 -0.00369638 0.0249562 -0.32029 0.0406332 0.0209493 -0.326049 0.0410379 0.0215797 -0.325838 0.0402165 0.0222132 -0.329312 0.0399612 0.0220226 -0.329256 0.0414115 0.0217037 -0.325879 0.0385375 0.0229239 -0.332634 0.039792 0.0217469 -0.329249 0.0387379 0.023036 -0.332718 0.0388806 0.0230729 -0.332789 0.040516 0.0222876 -0.329409 0.0389524 0.0230792 -0.332827 0.00644476 0.0255308 -0.331138 0.00629126 0.0258156 -0.33133 0.0253381 0.0259811 -0.346234 0.00650196 0.0251652 -0.331071 -0.00246903 0.0257005 -0.324473 0.0383699 0.0227534 -0.332584 0.0368248 0.0240037 -0.336915 0.0361158 0.0237053 -0.336569 0.0308354 0.0257264 -0.346192 0.0363226 0.0239 -0.336647 0.0365701 0.0240042 -0.336767 0.0300684 0.0257413 -0.346732 0.0294785 0.0259771 -0.347493 0.0294029 0.0259196 -0.347278 0.0283235 0.0260466 -0.347679 0.0283189 0.0259726 -0.347422 0.0306446 0.0256291 -0.346089 0.0302017 0.0258447 -0.346886 0.0293314 0.0257986 -0.347089 0.0268975 0.0260016 -0.347141 0.0283635 0.0256029 -0.347051 0.0283106 0.0258179 -0.347204 0.0269683 0.0257914 -0.346913 0.025495 0.0256949 -0.346037 0.0135455 -0.0204085 -0.305283 0.0135476 -0.0207084 -0.305183 0.0146325 -0.0208501 -0.304895 0.0134822 -0.0210881 -0.304698 0.0146307 -0.0210136 -0.304598 0.0113518 -0.0210598 -0.305868 0.0111663 -0.0213298 -0.305461 0.0135254 -0.0209473 -0.304978 0.0110411 -0.0213421 -0.305227 0.0134248 -0.0211087 -0.304388 0.0112738 -0.0212321 -0.305682 0.00936079 -0.0216531 -0.306752 0.00920611 -0.0216638 -0.3066 0.00424826 -0.0229371 -0.311584 0.00443888 -0.0229143 -0.311785 0.00969984 -0.0213032 -0.307158 0.00961706 -0.021466 -0.307041 0.00459949 -0.0227997 -0.311981 0.00950121 -0.0215855 -0.306902 0.00471064 -0.0226071 -0.312148 -0.00362946 -0.0250747 -0.319148 0.0257242 -0.0198493 -0.304817 0.0378105 -0.0195654 -0.304433 0.0378087 -0.0198827 -0.304367 0.0257284 -0.0204417 -0.304554 0.0257229 -0.0206086 -0.304268 0.0378031 -0.020148 -0.304181 0.0146263 -0.0205787 -0.305098 0.0257289 -0.0201732 -0.304748 -0.0034595 -0.0250509 -0.319333 -0.00331364 -0.0249511 -0.319514 -0.00398859 -0.0252171 -0.320005 -0.00320644 -0.0247854 -0.319672 -0.0038075 -0.025113 -0.320126 -0.00428856 -0.0254021 -0.320976 -0.00421259 -0.0255475 -0.321998 -0.00392103 -0.0250957 -0.321072 -0.0040801 -0.0252779 -0.321022 -0.00350607 -0.0254529 -0.32305 -0.00399505 -0.0253905 -0.321971 -0.00396587 -0.0257632 -0.323296 -0.00337984 -0.0251751 -0.322999 -0.00231748 -0.0254226 -0.324285 -0.00268211 -0.02585 -0.324742 -0.00371166 -0.0256592 -0.323154 0.0382212 -0.0203656 -0.30359 0.0377843 -0.0203639 -0.303585 0.0420279 -0.0197027 -0.308467 0.0412211 -0.0194241 -0.306147 0.0418806 -0.0196782 -0.307351 0.0415042 -0.0200496 -0.30602 0.0421198 -0.0199628 -0.307294 0.0403241 -0.0195578 -0.305221 0.0403839 -0.0198869 -0.305177 0.0413053 -0.0197717 -0.306127 0.0407025 -0.0203214 -0.304796 0.0391447 -0.0199117 -0.304548 0.040518 -0.0201575 -0.305026 0.0391937 -0.0201773 -0.304368 0.0377945 -0.0203177 -0.303905 0.0392721 -0.0203466 -0.304102 0.0393671 -0.0203918 -0.303795 0.041778 -0.0202022 -0.305847 0.042457 -0.0201038 -0.307205 0.0420718 -0.0201988 -0.305642 0.0428177 -0.0200698 -0.307104 0.0167904 -0.0253086 -0.339115 -0.00246903 -0.0257062 -0.324473 0.0253381 -0.0259868 -0.346234 0.0167324 -0.0256779 -0.339185 0.0165763 -0.0259638 -0.339381 0.0418389 -0.0196187 -0.312396 0.0416589 -0.0199374 -0.316235 0.0418399 -0.0196164 -0.312367 0.0419334 -0.0199889 -0.312341 0.0421903 -0.0202751 -0.312328 0.0429324 -0.0203593 -0.312348 0.0423841 -0.0207307 -0.316209 0.0422791 -0.0199881 -0.308452 0.0426339 -0.0201255 -0.308448 0.043012 -0.0200838 -0.308457 0.0425511 -0.0204089 -0.31233 0.031038 -0.0257621 -0.346313 0.0308354 -0.0257322 -0.346192 0.025495 -0.0257006 -0.346037 0.0255813 -0.0259948 -0.346425 0.0267977 -0.0261081 -0.347425 0.0283312 -0.026052 -0.347679 0.0268914 -0.0260074 -0.347138 0.0295201 -0.0259797 -0.347478 0.0295682 -0.025976 -0.347461 0.0302451 -0.0258445 -0.346854 0.0303895 -0.0258857 -0.347026 0.0269626 -0.025797 -0.346911 0.0283261 -0.0259781 -0.347422 0.0294419 -0.0259228 -0.347265 0.0301081 -0.0257418 -0.346702 0.0306446 -0.0256348 -0.346089 0.0257248 -0.0257218 -0.346219 0.0257828 -0.0253651 -0.346137 0.027 -0.0255102 -0.346778 0.0283174 -0.0258237 -0.347204 0.0293681 -0.0258028 -0.347078 0.0293049 -0.0256301 -0.346934 0.0299896 -0.025586 -0.346584 0.0416366 -0.0210628 -0.321031 0.0407662 -0.0212976 -0.32583 0.0410379 -0.0215854 -0.325838 0.0414115 -0.0217095 -0.325879 0.0417552 -0.0203134 -0.316208 0.0413685 -0.0207752 -0.321033 0.0420176 -0.0206004 -0.316199 0.0420079 -0.0211894 -0.321057 0.0427679 -0.0206734 -0.316236 0.0423929 -0.0211243 -0.321103 0.0334958 -0.0251046 -0.34238 0.0387379 -0.0230418 -0.332718 0.0332742 -0.0250833 -0.34225 0.0330636 -0.0249824 -0.342141 0.0328859 -0.0248123 -0.342064 0.0386016 -0.0229742 -0.332659 0.0388806 -0.0230786 -0.332789 0.0396245 -0.0225739 -0.330851 0.0385375 -0.0229297 -0.332634 0.039998 -0.0220011 -0.329145 0.0393902 -0.0224206 -0.33078 0.0402545 -0.0221946 -0.3292 0.0398866 -0.0226327 -0.330958 0.0405567 -0.0222702 -0.329297 0.0408543 -0.0222155 -0.329418 0.0406631 -0.0209165 -0.325858 0.0398297 -0.0217219 -0.32914 -0.0156855 0.00739712 -0.0406869 -0.0153453 0.00739712 -0.0410932 -0.014165 0.00739712 -0.0477809 0.000465068 0.00739712 -0.11545 -0.000855076 0.00739712 -0.114391 -0.00174612 0.00739712 -0.114554 -0.00290545 0.00739712 -0.116805 -5.89462e-05 0.00739712 -0.116463 -0.00288849 0.00739712 -0.115899 -0.00247368 0.00739712 -0.115094 0.00182062 0.00739712 -0.1264 0.00125276 0.00739712 -0.136252 -0.00221956 0.00739712 -0.12 0.00515779 0.00249712 -0.134896 0.00619447 0.00610991 -0.139897 0.00637845 0.00599869 -0.140797 0.00661246 0.00739712 -0.148145 0.0115329 0.00739712 -0.172363 0.00823058 0.00739712 -0.17299 0.0107032 0.00739712 -0.171609 0.0079018 0.00739712 -0.17216 0.0085174 0.00739712 -0.159938 0.00415304 0.00739712 -0.146145 0.0117687 0.00589712 -0.170337 0.00999454 0.00589712 -0.159677 0.00998613 0.00449712 -0.15963 0.00802397 0.00589712 -0.149058 0.0127044 0.00593683 -0.176606 0.0126267 0.00249712 -0.176063 0.0126267 0.00604309 -0.176063 0.0130842 0.00603956 -0.179326 0.0129596 0.00739712 -0.183131 0.0142699 0.00739712 -0.21094 0.0111589 0.00739712 -0.182722 0.014022 0.00739712 -0.214378 0.014706 0.00739712 -0.212241 0.0156756 0.00739712 -0.213211 0.0157097 0.00739712 -0.213763 0.0125214 0.00739712 -0.21339 0.0119879 0.00739712 -0.18643 0.00979047 0.00739712 -0.183962 0.0167161 0.00249712 -0.220257 0.0166615 0.00590657 -0.218738 0.016591 0.00607335 -0.217016 0.0118404 0.00739712 -0.258922 0.0151778 0.00739712 -0.257811 0.012923 0.00739712 -0.224046 0.0163017 0.00739712 -0.224192 0.0151914 0.00739712 -0.222944 0.0135896 0.00739712 -0.259424 0.0143059 0.00739712 -0.255759 0.0149578 0.00739712 -0.244927 0.0153854 0.00739712 -0.230641 0.012736 0.00739712 -0.224928 0.0155982 0.00739712 -0.225078 0.0137244 0.00739712 -0.262774 0.0136935 0.00739712 -0.265934 -0.00116213 0.00739712 -0.302487 0.0126505 0.00739712 -0.268526 0.0119391 0.00739712 -0.268013 0.014408 0.00739712 -0.271401 0.0110769 0.00739712 -0.267855 0.01359 0.00739712 -0.272243 0.0102297 0.00739712 -0.26808 0.00426472 0.00739712 -0.286535 0.0132463 0.00739712 -0.273366 0.00919695 0.00739712 -0.269444 -0.00228962 0.00739712 -0.301256 -0.00775124 0.00739712 -0.0800445 -0.00819587 0.00739712 -0.0806169 -0.0114238 0.00739712 -0.0626604 -0.0123572 0.00739712 -0.0612496 -0.0117004 0.00739712 -0.0607303 -0.00995005 0.00589712 -0.0623809 -0.00805532 0.00739712 -0.0867516 -0.00619602 0.00739712 -0.0877204 -0.0073495 0.00739712 -0.0862253 -0.00568631 0.00739712 -0.0867239 -0.00563232 0.00739712 -0.0862683 -0.00498422 0.00739712 -0.106777 -0.0045763 0.00739712 -0.107642 -0.00253373 0.00739712 -0.106248 -0.0156855 -0.00740288 -0.0406869 -0.0153453 -0.00740288 -0.0410932 -0.014165 -0.00740288 -0.0477809 -0.0158054 -0.00740288 -0.0416741 -0.0129672 -0.00740288 -0.05439 0.00502513 -0.00740288 -0.13693 -0.00247368 -0.00740288 -0.115094 -0.00174612 -0.00740288 -0.114554 0.000456175 -0.00740288 -0.11546 0.00426577 -0.00740288 -0.136349 0.00357393 -0.00740288 -0.137809 -0.00288849 -0.00740288 -0.115899 -0.00221956 -0.00740288 -0.12 0.00368964 -0.00740288 -0.135203 0.0013878 -0.00590288 -0.117286 0.00637845 -0.00600446 -0.140797 0.0119529 -0.00740288 -0.17255 0.0107032 -0.00740288 -0.171609 0.00496309 -0.00740288 -0.145639 0.00655137 -0.00740288 -0.149343 0.00367041 -0.00740288 -0.14697 0.00588205 -0.00740288 -0.159967 0.0079018 -0.00740288 -0.17216 0.0117687 -0.00450288 -0.170337 0.00802397 -0.00450288 -0.149058 0.00802397 -0.00590288 -0.149058 0.0131127 -0.00611758 -0.179534 0.0126267 -0.00250288 -0.176063 0.0127044 -0.00594259 -0.176606 0.0127974 -0.00590718 -0.177262 0.0131301 -0.00250288 -0.179662 0.0167145 -0.00606344 -0.220209 0.0166557 -0.00250288 -0.218587 0.0166615 -0.00591234 -0.218738 0.0156165 -0.00740288 -0.258111 0.0126547 -0.00740288 -0.259384 0.0135896 -0.00740288 -0.259424 0.0144405 -0.00740288 -0.259034 0.0153576 -0.00740288 -0.226184 0.0142896 -0.00740288 -0.222942 0.0113249 -0.00740288 -0.258141 0.0145006 -0.00740288 -0.256888 0.0112212 -0.00740288 -0.257211 0.0143059 -0.00740288 -0.255759 0.0153854 -0.00740288 -0.230641 0.0137244 -0.00740288 -0.262774 0.0129674 -0.00740288 -0.264168 0.0134634 -0.00740288 -0.265675 0.01359 -0.00740288 -0.272243 0.014408 -0.00740288 -0.271401 0.0119391 -0.00740288 -0.268013 0.0117352 -0.00740288 -0.302061 0.00919695 -0.00740288 -0.269444 0.0102297 -0.00740288 -0.26808 0.0110769 -0.00740288 -0.267855 -0.00209179 -0.00740288 -0.299599 -0.00116213 -0.00740288 -0.302487 -0.00186031 -0.00740288 -0.301995 -0.000322399 -0.00740288 -0.302642 0.0115811 -0.00740288 -0.301035 -0.00228962 -0.00740288 -0.301256 -0.00909831 -0.00740288 -0.0804041 -0.00819587 -0.00740288 -0.0806169 -0.0073702 -0.00740288 -0.0804364 -0.0113936 -0.00740288 -0.0615909 -0.0123572 -0.00740288 -0.0612496 -0.0114238 -0.00740288 -0.0626604 -0.00823006 -0.00740288 -0.079001 -0.00675951 -0.00250288 -0.0787052 -0.00675951 -0.00590288 -0.0787052 -0.00837751 -0.00590288 -0.0705473 -0.00834179 -0.00250288 -0.07073 -0.00995005 -0.00250288 -0.0623809 -0.00201046 -0.00740288 -0.107322 -0.00563232 -0.00740288 -0.0862683 -0.0073495 -0.00740288 -0.0862253 -0.00850397 -0.00740288 -0.0884097 -0.00498422 -0.00740288 -0.106777 -0.00381321 -0.00740288 -0.108219 0.0164551 -0.00590288 -0.245017 0.0164551 -0.00450288 -0.245017 0.0151257 0.00249712 -0.267107 -0.0195008 0.000397117 -0.312294 0.00141645 -2.88296e-06 -0.312302 -0.0195159 -2.88296e-06 -0.312294 0.00292711 0.000397117 -0.297591 0.00292711 -0.000402883 -0.297591 0.00529414 0.000397117 -0.29996 0.00698858 0.000397117 -0.311659 0.00746575 0.000397117 -0.310946 0.00711682 -0.000402883 -0.31152 0.00750017 -0.000402883 -0.310857 0.00763352 0.000397117 -0.310104 0.00763352 -0.000402883 -0.310104 0.00763519 -0.000402883 -0.305618 0.00763519 0.000397117 -0.305618 -0.00676947 -0.0116745 -0.0265878 -0.00930502 -0.00197875 -0.0268087 -0.011822 -0.00252115 -0.027028 -0.0119937 0.00253676 -0.027043 -0.00800237 0.00160319 -0.0266953 -0.0079814 -0.00160288 -0.0266934 -0.00800237 -0.00160896 -0.0266953 -0.00564698 0.0116687 -0.0213539 -0.0046288 -0.0116745 -0.0223294 -0.0046288 0.0116687 -0.0223294 -0.00451076 -0.0116745 -0.025056 -0.00544084 -0.0116745 -0.0261157 -0.00451076 0.0116687 -0.025056 -0.0259782 5.8812e-06 -0.0209914 -0.0166515 0.00259712 -0.310095 -0.0108102 0.00259712 -0.303809 0.00945705 0.00259712 -0.195982 0.0101329 0.00259712 -0.196537 0.0109951 0.00259712 -0.196682 -0.017781 0.00259712 -0.0669453 -0.0135162 0.00259712 -0.0744789 0.00144406 0.00259712 -0.293097 0.00208607 0.00259712 -0.292381 0.00969201 0.00259712 -0.200821 0.0142922 0.00259712 -0.200392 -0.0179941 0.00259712 -0.0507861 -0.00338454 0.00259712 -0.292927 0.00126951 0.00259712 -0.281674 0.00534095 0.00259712 -0.277951 0.00433345 0.00259712 -0.270726 0.00630844 0.00259712 -0.260191 0.00883811 0.00259712 -0.261941 0.0103334 0.00259712 -0.249305 0.00750249 0.00259712 -0.250212 0.00154296 0.00259712 -0.29721 0.00138512 0.00259712 -0.296722 -0.0237097 0.00259712 -0.0339913 -0.0147602 0.00259712 -0.0248832 -0.0140471 0.00259712 -0.0265054 -0.0132681 0.00259712 -0.026967 0.00837891 0.00259712 -0.231396 0.0109433 0.00259712 -0.238769 0.0110026 0.00259712 -0.223257 0.00799347 0.00259712 -0.21492 -0.00288406 0.00259712 -0.0974335 -0.00867566 0.00259712 -0.0950411 0.00453243 0.00259712 -0.291345 -0.00715193 0.00259712 -0.100198 0.00323081 0.00259712 -0.301 0.00305023 0.00259712 -0.300625 0.00592847 0.00259712 -0.291083 0.00696588 0.00259712 -0.200564 0.00485961 0.00259712 -0.164009 0.000814606 0.00259712 -0.156881 -0.0107987 0.00259712 -0.101307 -0.00786122 0.00259712 -0.10129 -0.00761533 0.00259712 -0.100673 0.0024778 0.00259712 -0.286445 0.00771358 0.00259712 -0.290863 0.0136801 0.00259712 -0.291127 0.00825598 0.00259712 -0.290803 0.00702736 0.000397117 -0.302556 -0.00912306 -0.00100288 -0.326216 0.00182167 0.000997117 -0.312218 -0.00912306 0.000997117 -0.326216 0.00209595 0.00123902 -0.312134 -0.00854636 0.00172917 -0.326667 0.00392655 0.00195275 -0.311658 0.0054329 0.00180757 -0.311792 0.00640085 0.000997117 -0.311986 0.00557935 0.00172917 -0.311848 -0.0063941 -0.00100288 -0.32835 0.00648123 -0.000900572 -0.311973 -0.00618302 -2.88296e-06 -0.328515 0.00664886 -2.88296e-06 -0.312104 -0.00854636 -0.00173493 -0.326667 0.00209595 -0.00124479 -0.312134 0.00160771 0.000721731 -0.312278 0.00146773 0.000397117 -0.312302 -0.00933414 -2.88296e-06 -0.326051 0.00652983 0.000397117 -0.312011 -0.00570321 -2.88296e-06 -0.329525 -0.00811408 0.00149712 -0.331956 -0.00601984 0.00149712 -0.329277 -0.00897912 0.00259519 -0.331279 -0.0101608 0.00299712 -0.330356 -0.0113425 0.00259519 -0.329432 -0.0125241 -2.88296e-06 -0.328508 -0.0122075 -0.00150288 -0.328755 -0.0104299 -2.88296e-06 -0.325829 -0.0101133 -0.00150288 -0.326077 -0.0101608 -0.00300288 -0.330356 -0.00806656 -0.00300288 -0.327677 -0.00811408 -0.00150288 -0.331956 -0.00688488 -0.00260096 -0.328601 -0.00601984 -0.00150288 -0.329277 -0.00779745 -2.88293e-06 -0.332203 -0.0063941 0.000997117 -0.32835 -0.0069708 -0.00173493 -0.327899 -0.00605298 -0.00125288 -0.328617 -0.00775858 -0.00200288 -0.327283 -0.00775858 -0.00250288 -0.327283 -0.00946418 0.00124712 -0.32595 -0.00874331 0.00216218 -0.326513 -0.00775858 0.00199712 -0.327283 -0.00775858 0.00249712 -0.327283 -0.0069708 0.00172917 -0.327899 -0.00688488 0.00259519 -0.328601 -0.00675728 0.00253718 -0.328383 -0.00806656 0.00299712 -0.327677 -0.00924823 0.00259519 -0.326753 -0.00906786 0.00253718 -0.326577 -0.0101133 0.00149712 -0.326077 -0.00991359 0.00146362 -0.325916 -0.0102231 -2.88296e-06 -0.325674 -0.00924823 -0.00260096 -0.326753 -0.00906786 -0.00254295 -0.326577 -0.00591155 -0.00146939 -0.329045 -0.00560199 -2.88296e-06 -0.329287 -0.00592368 0.00137212 -0.328803 -0.00671664 0.00237869 -0.328183 -0.00791257 0.00293013 -0.32748 -0.00888304 0.00237869 -0.326489 -0.00991359 -0.00146939 -0.325916 -0.00791257 -0.0029359 -0.32748 -0.00779984 -0.00275288 -0.327336 -0.00675728 -0.00254295 -0.328383 -0.00563344 -2.88296e-06 -0.32903 -0.00591155 0.00146362 -0.329045 -0.00677385 0.00216218 -0.328053 -0.00779984 0.00274712 -0.327336 -0.009676 0.00137212 -0.325869 -0.00996624 -2.88296e-06 -0.325642 -0.00972803 -2.88296e-06 -0.325743 -0.009676 -0.00137788 -0.325869 -0.00946418 -0.00125288 -0.32595 -0.00888304 -0.00238445 -0.326489 -0.00874331 -0.00216795 -0.326513 -0.00671664 -0.00238445 -0.328183 -0.00677385 -0.00216795 -0.328053 -0.00592368 -0.00137788 -0.328803 -0.00578912 -2.88296e-06 -0.328823 -0.00605298 0.00124712 -0.328617 -0.00904574 0.002855 -0.331608 -0.0124699 0.00157212 -0.32888 -0.00908007 -0.00273086 -0.33153 -0.00783931 -2.88298e-06 -0.3325 -0.0077459 -2.88298e-06 -0.332625 -0.00817177 0.00157212 -0.332241 -0.00908007 0.0027251 -0.33153 -0.00905568 0.00263 -0.33141 -0.0103208 0.00314712 -0.33056 -0.0115616 0.0027251 -0.32959 -0.0114507 0.00263 -0.329537 -0.0123273 0.00151721 -0.328852 -0.0128023 -2.88298e-06 -0.32862 -0.0124699 -0.00157788 -0.32888 -0.0123273 -0.00152298 -0.328852 -0.0115616 -0.00273086 -0.32959 -0.0114507 -0.00263577 -0.329537 -0.0102532 -0.00304308 -0.330474 -0.0103208 -0.00315288 -0.33056 -0.00817905 -0.00152298 -0.332095 -0.00817177 -0.00157788 -0.332241 -0.00817905 0.00151721 -0.332095 -0.0102532 0.00303731 -0.330474 -0.0122075 0.00149712 -0.328755 -0.0126482 -2.88297e-06 -0.328601 -0.0113425 -0.00260096 -0.329432 -0.00897912 -0.00260096 -0.331279 -0.00905568 -0.00263577 -0.33141 -0.00785818 -2.88297e-06 -0.332346 0.0133596 -0.00250288 -0.301882 0.013709 -0.00590288 -0.302115 0.0137021 -0.00250288 -0.302112 0.0147436 -0.00250288 -0.273456 0.0148811 -0.00590288 -0.273007 0.0156447 -0.00250288 -0.272521 0.0156531 -0.00590288 -0.27252 0.0164898 -0.00590288 -0.272852 0.0151788 -0.00250288 -0.267493 0.0154418 -0.00250288 -0.261854 0.0158226 -0.00250288 -0.261127 0.0158811 -0.00590288 -0.256301 0.0161478 -0.00250288 -0.256666 0.0169525 -0.00250288 -0.225723 0.0172308 -0.00590288 -0.225369 0.017636 -0.00250288 -0.225174 0.018086 -0.00250288 -0.225175 0.0184897 -0.00590288 -0.225374 0.0170831 -0.00740288 -0.220998 0.0167161 -0.00250288 -0.220257 0.0167161 -0.00607812 -0.220257 0.0168194 -0.00250288 -0.220668 0.0167171 -0.00609737 -0.220281 0.016769 -0.00640644 -0.220546 0.0167771 -0.00644295 -0.220569 0.0170831 -0.00250288 -0.220998 0.0165868 -0.00250288 -0.216919 0.0167607 -0.00710403 -0.21631 0.0166485 -0.00250288 -0.216527 0.013364 -0.00710403 -0.180181 0.0134741 -0.00250288 -0.18029 0.0126606 -0.00250288 -0.175628 0.0126178 -0.00623136 -0.175871 0.0128752 -0.00739676 -0.17525 0.012782 -0.00710403 -0.17537 0.0119338 -0.00250288 -0.170751 0.0117687 -0.00250288 -0.170337 0.0122672 -0.00590288 -0.171055 0.0126976 -0.00590288 -0.171181 0.0126895 -0.00250288 -0.171181 0.0131398 -0.00590288 -0.171107 0.00960853 -0.00590288 -0.14807 0.0080484 -0.00590288 -0.148578 0.00917014 -0.00250288 -0.147881 0.00828937 -0.00250288 -0.14817 0.00684455 -0.00250288 -0.142767 0.00708809 -0.00250288 -0.143032 0.00708557 -0.00739676 -0.14303 0.00619447 -0.00250288 -0.139897 0.00618624 -0.00250288 -0.139541 0.00630336 -0.00250288 -0.139204 0.00642029 -0.00710403 -0.139039 0.00653097 -0.00250288 -0.13893 0.00634952 -0.00689914 -0.13913 0.00538619 -0.00250288 -0.135352 0.00581564 -0.00590288 -0.135638 0.00632751 -0.00590288 -0.135673 0.00631839 -0.00250288 -0.135674 0.00284809 -0.00590288 -0.116199 0.00196541 -0.00250288 -0.116158 0.00196541 -0.00590288 -0.116158 0.00160155 -0.00590288 -0.116429 0.0013878 -0.00250288 -0.117286 -0.000478501 -0.00250288 -0.106643 -7.79195e-07 -0.00590288 -0.106718 -9.3834e-06 -0.00250288 -0.106718 -0.00475109 -0.00450288 -0.0885348 -0.00375186 -0.00250288 -0.0873319 -0.00374109 -0.00590288 -0.0873322 -0.00418767 -0.00250288 -0.0874223 -0.00453768 -0.00590288 -0.0876886 -0.00475109 -0.00250288 -0.0885348 -0.00656968 -0.00250288 -0.0791204 -0.00621506 -0.00250288 -0.079408 -0.00576957 -0.00250288 -0.079508 -0.00576957 -0.00590288 -0.079508 -0.00532608 -0.00590288 -0.0793995 -0.00900062 -0.00590288 -0.0611952 -0.0090109 -0.00250288 -0.0611956 -0.00975136 -0.00250288 -0.0615736 -0.00995005 -0.00590288 -0.0623809 -0.0103234 -0.00250288 -0.0549966 -0.0108361 -0.00250288 -0.0549514 -0.0112584 -0.00590288 -0.0546572 -0.0112584 -0.00250288 -0.0546572 -0.0125785 -0.00590288 -0.0397116 -0.0138239 -0.00590288 -0.0403274 -0.0135397 -0.00250288 -0.0399107 0.0158032 0.00589712 -0.25585 0.0158811 0.00589712 -0.256301 0.016559 0.00589712 -0.25688 0.016551 0.00249712 -0.256878 0.0170061 0.00249712 -0.256888 0.0170169 0.00589712 -0.256886 0.017636 0.00249712 -0.225174 0.0180966 0.00589712 -0.225178 0.018086 0.00249712 -0.225175 0.0184897 0.00249712 -0.225374 0.0168574 0.00449712 -0.226163 0.0169537 0.00589712 -0.225721 0.0167171 0.0060916 -0.220281 0.0168194 0.00249712 -0.220668 0.0170807 0.00739099 -0.220996 0.0169709 0.00709826 -0.220891 0.0167771 0.00643719 -0.220569 0.0165955 0.00631653 -0.216736 0.0166485 0.00249712 -0.216527 0.0167607 0.00709826 -0.21631 0.0168558 0.00739099 -0.216192 0.0131301 0.0061676 -0.179662 0.013364 0.00709826 -0.180181 0.013244 0.00249712 -0.180008 0.0128752 0.00739099 -0.17525 0.0126178 0.00622559 -0.175871 0.0126375 0.00643719 -0.175717 0.0126606 0.00249712 -0.175628 0.012782 0.00709826 -0.17537 0.0119338 0.00249712 -0.170751 0.0122625 0.00249712 -0.171052 0.0131398 0.00589712 -0.171107 0.013496 0.00249712 -0.170856 0.013496 0.00589712 -0.170856 0.00960853 0.00589712 -0.14807 0.00869429 0.00249712 -0.147917 0.00828937 0.00249712 -0.14817 0.00804757 0.00249712 -0.148581 0.0080484 0.00589712 -0.148578 0.00802397 0.00249712 -0.149058 0.00671078 0.00249712 -0.142432 0.00684455 0.00249712 -0.142767 0.00697196 0.00709826 -0.142929 0.0068026 0.00657518 -0.142693 0.00653097 0.00249712 -0.13893 0.00634952 0.00689337 -0.13913 0.00652855 0.00739099 -0.138932 0.00653097 0.00739712 -0.13893 0.00628562 0.00672092 -0.139237 0.00515779 0.00589712 -0.134896 0.00538824 0.00589712 -0.135354 0.00580979 0.00249712 -0.135636 0.00632751 0.00589712 -0.135673 0.00631839 0.00249712 -0.135674 0.00677968 0.00249712 -0.135457 0.00284809 0.00589712 -0.116199 0.00241152 0.00249712 -0.116075 0.00196541 0.00249712 -0.116158 0.00139484 0.00249712 -0.116832 0.0013955 0.00589712 -0.11683 0.0013878 0.00589712 -0.117286 -0.00106731 0.00249712 -0.105932 -0.00085984 0.00249712 -0.10636 -0.000858001 0.00589712 -0.106362 -0.000478501 0.00249712 -0.106643 -0.000473191 0.00589712 -0.106645 -9.3834e-06 0.00249712 -0.106718 -7.79195e-07 0.00589712 -0.106718 0.000441602 0.00249712 -0.106569 -0.00475109 0.00589712 -0.0885348 -0.00418031 0.00589712 -0.0874189 -0.00332002 0.00589712 -0.0874397 -0.00475109 0.00449712 -0.0885348 -0.00474222 0.00249712 -0.0880898 -0.00675951 0.00249712 -0.0787052 -0.00621506 0.00249712 -0.079408 -0.00576957 0.00249712 -0.079508 -0.00576128 0.00589712 -0.0795079 0.0151788 0.00589712 -0.267493 0.0153759 0.00589712 -0.26783 0.0154418 0.00249712 -0.261854 0.0155555 0.00589712 -0.261448 0.0155543 0.00249712 -0.26145 0.0131392 0.00589712 -0.301533 0.0130784 0.00249712 -0.301125 0.0133596 0.00589712 -0.301882 0.0137021 0.00249712 -0.302112 0.0147436 0.00589712 -0.273456 0.0148811 0.00589712 -0.273007 0.0152083 0.00589712 -0.27267 0.0156531 0.00589712 -0.27252 0.0156447 0.00249712 -0.272521 0.0161175 0.00589712 -0.272589 -0.00942228 0.00249712 -0.061304 -0.00993858 0.00249712 -0.0619556 -0.00993796 0.00589712 -0.0619532 -0.0112584 0.00249712 -0.0546572 -0.0110626 0.00589712 -0.0548346 -0.0107043 0.00589712 -0.0549892 -0.0125785 0.00249712 -0.0397116 -0.0135397 0.00249712 -0.0399107 -0.013825 0.00249712 -0.0403303 0.0125572 -0.0185755 -0.26745 0.0128303 -0.0185293 -0.268258 0.0127694 -0.0184485 -0.268326 0.0127196 -0.018355 -0.268386 0.0126505 -0.0179004 -0.268526 0.0129796 -0.0186456 -0.268105 0.0124313 -0.018532 -0.267657 0.0115999 -0.0183554 -0.267056 0.0115508 -0.0183236 -0.267305 0.00875864 -0.0173343 -0.267771 0.00896318 -0.017418 -0.26801 0.0123293 -0.0184179 -0.26785 0.0115254 -0.0182161 -0.267535 0.0105555 -0.0180315 -0.267267 0.009634 -0.0176961 -0.267547 0.00979166 -0.0176257 -0.267792 0.0122609 -0.0182443 -0.26801 0.0106203 -0.0179378 -0.267516 0.0115262 -0.0180438 -0.267723 0.00995726 -0.0174598 -0.267979 0.00920126 -0.0173754 -0.268227 0.0115533 -0.0178242 -0.267851 0.0107033 -0.0177679 -0.267713 0.0101076 -0.0172216 -0.268081 0.00956262 -0.0165517 -0.268642 0.00973418 -0.0166548 -0.268445 0.00962153 -0.0169594 -0.268465 0.0107948 -0.0175418 -0.267836 0.010884 -0.0172857 -0.267871 0.0119367 -0.0176928 -0.268012 0.0122326 -0.0180273 -0.268123 0.00939766 -0.0164608 -0.268897 0.0093054 -0.0167931 -0.268911 0.00909949 -0.0170636 -0.268851 0.00943352 -0.0172136 -0.268388 0.00881827 -0.0172218 -0.268729 0.00851408 -0.0172384 -0.268567 0.00824355 -0.0171103 -0.268395 0.00912402 -0.01675 -0.269413 0.00891326 -0.0170268 -0.269357 0.0082607 -0.0171889 -0.269213 0.00794555 -0.0170427 -0.269154 0.00100788 -0.0174435 -0.293984 0.000933519 -0.0178082 -0.293936 0.00578845 -0.0173272 -0.281993 0.000718041 -0.0180925 -0.293821 0.000408816 -0.0182343 -0.293662 0.00462107 -0.0175873 -0.281599 0.0055746 -0.0176074 -0.28191 0.00526385 -0.017758 -0.281802 0.00860558 -0.0171832 -0.269285 0.00491985 -0.0177483 -0.281689 0.0166681 -0.0185525 -0.272883 0.0152086 -0.0189538 -0.270186 0.0149791 -0.0188962 -0.270394 0.014788 -0.0187238 -0.270575 0.016734 -0.0187967 -0.272815 0.0126578 -0.0181387 -0.268478 0.0146651 -0.0184633 -0.270702 7.38144e-05 -0.0182022 -0.293497 -0.000547288 -0.0179907 -0.29676 -0.00234746 -0.0186033 -0.299351 -0.000755875 -0.0182758 -0.296618 -0.0010612 -0.0184129 -0.296437 -0.0029744 -0.0186884 -0.298955 -0.00325642 -0.0184689 -0.298813 -0.00139413 -0.018371 -0.296257 0.0220951 -0.0188117 -0.279073 0.0165892 -0.0182597 -0.272964 0.0220537 -0.0184995 -0.279122 0.0222249 -0.0190744 -0.278948 0.0168165 -0.0188996 -0.272738 0.0224225 -0.0192458 -0.278766 0.0169929 -0.0190223 -0.272577 0.0171913 -0.019059 -0.272399 0.0297884 -0.0195775 -0.287065 0.0226565 -0.0192987 -0.278556 0.0295905 -0.0194062 -0.287247 0.0294605 -0.0191434 -0.287373 0.0300228 -0.0196299 -0.286855 0.0369561 -0.0197406 -0.295547 0.0368259 -0.0194776 -0.295673 -0.00264616 -0.0187369 -0.299149 -0.00214726 -0.0183183 -0.299513 -0.00235332 -0.0184943 -0.299938 -0.00231039 -0.018165 -0.300099 -0.00209179 -0.0179479 -0.299599 -0.00245834 -0.0188829 -0.300485 -0.00278975 -0.019872 -0.301155 -0.00254341 -0.0197235 -0.301165 -0.00239259 -0.0203796 -0.301872 -0.00220118 -0.0202234 -0.301825 -0.00169833 -0.0205931 -0.302324 -0.00286138 -0.0188874 -0.299616 -0.00329003 -0.0192739 -0.300242 -0.00295441 -0.0192494 -0.300255 -0.00265978 -0.0191109 -0.300341 -0.00255101 -0.0187535 -0.299765 -0.00235586 -0.0195176 -0.301238 -0.00238579 -0.0186058 -0.300662 -0.00225139 -0.0192812 -0.301364 -0.00204556 -0.020026 -0.301835 -0.00194112 -0.019807 -0.301901 -0.000948461 -0.0204396 -0.302563 -0.0015854 -0.020399 -0.302286 -0.00183152 -0.0207544 -0.302414 -0.00197419 -0.0208697 -0.30255 -0.00260087 -0.0204792 -0.301972 -0.00211476 -0.0209297 -0.302718 -0.00280542 -0.0205123 -0.302114 -0.00306301 -0.0199441 -0.30121 -0.00321833 -0.0188675 -0.299524 -0.00354588 -0.018698 -0.299509 -0.000999933 -0.0206481 -0.302578 -0.000350638 -0.020973 -0.302754 -0.00106398 -0.0208416 -0.302647 -0.00113596 -0.0210059 -0.302767 -0.000361546 -0.0211866 -0.302939 -0.000364029 -0.0212657 -0.303056 -0.00121066 -0.0211292 -0.302927 -0.000363798 -0.0213428 -0.303254 0.0382979 -0.0201494 -0.299223 0.0380046 -0.0200874 -0.29914 0.0377547 -0.0199139 -0.299075 0.037406 -0.0200193 -0.300012 0.0374967 -0.0200928 -0.300064 0.0376068 -0.0201535 -0.300129 0.0375859 -0.0196552 -0.299038 0.0371491 -0.0194511 -0.29988 0.0377229 -0.0195884 -0.29785 0.0374594 -0.0195271 -0.296685 0.0376207 -0.0197889 -0.296607 0.0378977 -0.0198487 -0.297829 0.0378646 -0.0199607 -0.2965 0.0381593 -0.0200214 -0.297807 0.0384676 -0.0200798 -0.297789 0.0367844 -0.0191648 -0.295722 0.0371544 -0.0199118 -0.295364 0.0373891 -0.0199639 -0.295154 -0.000359537 -0.0211395 -0.302886 0.000982782 -0.0212666 -0.302912 -0.000337961 -0.0207779 -0.302671 0.00650117 -0.0212338 -0.303115 0.0217189 -0.0206062 -0.302665 0.0137587 -0.0207486 -0.302536 0.0231899 -0.0204379 -0.302254 0.0232047 -0.0205678 -0.302621 0.000982563 -0.0209864 -0.302683 0.00648044 -0.0210947 -0.302764 0.0137396 -0.0204629 -0.302286 0.0231746 -0.0201497 -0.301991 0.0343057 -0.0202159 -0.301917 0.03429 -0.0199256 -0.301643 0.000988813 -0.0206342 -0.302601 0.00645298 -0.02081 -0.302517 0.00642492 -0.0204434 -0.302428 0.0354779 -0.0198874 -0.3014 0.0369645 -0.0202488 -0.301282 0.0372039 -0.0197067 -0.299902 0.0365163 -0.0198429 -0.300778 0.0372527 -0.0198157 -0.299927 0.0372449 -0.0198007 -0.299922 0.03573 -0.0202962 -0.302016 0.036708 -0.0201345 -0.300987 0.0355873 -0.0201784 -0.301657 0.0121929 0.0180971 -0.0445758 0.0140366 0.0176971 -0.0441658 0.0141011 0.0180971 -0.0442514 0.0146358 0.0176971 -0.0434346 0.0131864 0.0180971 -0.0446457 0.0142772 0.0183899 -0.0444852 0.0147324 0.0180971 -0.043481 0.0149395 0.0180971 -0.0425068 0.0132355 0.0183899 -0.0449343 0.0149963 0.0183899 -0.0436079 0.0152322 0.0183899 -0.0424983 0.015632 0.0184971 -0.0424866 0.014905 0.0183899 -0.0253524 0.0121039 0.0183899 -0.0448548 0.00261519 0.0180971 -0.0415211 0.00252622 0.0183899 -0.0418001 0.0119824 0.0184971 -0.0452359 0.0145659 0.0180033 -0.0253555 0.0144368 0.0182628 -0.0242511 0.0146122 0.0180971 -0.025355 0.0147393 0.0182628 -0.0253539 0.0146612 0.0184362 -0.0241207 0.0135105 0.0176971 -0.023645 0.0142869 0.0180033 -0.0243383 0.0136283 0.0182628 -0.0234425 0.0137587 0.0184362 -0.0232181 0.0125234 0.0176971 -0.023374 0.0135411 0.0180033 -0.0235924 0.0125239 0.0180033 -0.0233131 0.0125279 0.0184362 -0.0228802 0.0139126 0.0184971 -0.0229534 0.0125255 0.0182628 -0.0231397 0.00264776 0.0176971 -0.041419 -0.00212838 0.0187687 -0.0401723 -0.00647521 0.0193746 -0.0385709 -0.00211177 0.0185036 -0.0399733 -0.00647673 0.0196259 -0.0387463 -0.00651959 0.0197972 -0.0389969 0.0115315 0.0176971 -0.0236269 0.0115019 0.0180033 -0.0235737 0.0114174 0.0182628 -0.0234222 -0.00629825 0.0182628 -0.0332948 -0.00642459 0.0184362 -0.0330681 0.0112911 0.0184362 -0.0231955 -0.00865314 0.018379 -0.0351192 -0.0076065 0.0193142 -0.0381485 -0.00857257 0.0196354 -0.0375277 -0.00839624 0.0194291 -0.0376738 -0.00853745 0.0194139 -0.0375207 -0.00888068 0.0192635 -0.0369201 -0.00815987 0.0200065 -0.0381886 -0.00877346 0.0200101 -0.037657 -0.00940865 0.0199877 -0.0369359 -0.00920732 0.0198708 -0.0368916 -0.00958032 0.0197014 -0.0359453 -0.00934577 0.0195985 -0.0359846 -0.00809532 0.0198364 -0.0380598 -0.00904338 0.0197006 -0.0368735 -0.00915669 0.0192661 -0.0351203 -0.00915868 0.0194298 -0.0360452 -0.00824955 0.0201306 -0.0383506 -0.00756977 0.0198587 -0.0383957 -0.00756762 0.0196079 -0.038222 -0.00806091 0.0196334 -0.0379743 -0.00865336 0.0198395 -0.0375743 -0.00893122 0.0194921 -0.0368833 -0.0088687 0.01887 -0.035395 -0.00903869 0.0192129 -0.0361206 -0.00849553 0.0185525 -0.0348249 -0.0085695 0.0187962 -0.0346506 -0.0089727 0.0190993 -0.0352608 -0.0089405 0.0190224 -0.0342286 -0.00939724 0.019349 -0.0349913 -0.00793762 0.0182802 -0.0344007 -0.00797322 0.0185385 -0.0342054 -0.00807325 0.0187025 -0.0339423 -0.00872557 0.0189611 -0.0344415 -0.00797236 0.0179706 -0.034496 -0.00707883 0.0180818 -0.033925 -0.00739326 0.0185634 -0.0332228 -0.00822112 0.0187453 -0.0336552 -0.00618419 0.0176971 -0.0334995 -0.00621383 0.0180033 -0.0334463 -0.00713533 0.0183424 -0.0337489 -0.00724603 0.018512 -0.0335017 -0.0037546 0.0236056 -0.0526352 0.00189835 0.0208414 -0.0503567 0.00230198 0.0213569 -0.0505025 -0.000392204 0.023184 -0.0518862 -0.00114331 0.0232899 -0.0518484 -0.00144743 0.022704 -0.0516465 -0.00131009 0.0230287 -0.0516775 0.00142388 0.0211568 -0.0505396 0.00209145 0.0211253 -0.0503613 0.00533316 0.0190147 -0.0491193 0.00182067 0.0216762 -0.0506875 0.00161323 0.0214428 -0.0505455 0.0063977 0.0177171 -0.0476081 0.00649343 0.0180033 -0.0472282 0.00665242 0.0182966 -0.0476092 0.00646653 0.0180326 -0.0475955 0.00646891 0.018441 -0.048218 0.00627063 0.0181836 -0.0481847 0.00610336 0.0187012 -0.0487291 0.00591266 0.018465 -0.0486736 0.00617182 0.0178748 -0.0482238 0.00723986 0.0185133 -0.0477027 0.00692503 0.0184661 -0.0476469 0.00654969 0.0189205 -0.0490748 0.00632679 0.018861 -0.0488698 0.00673363 0.018604 -0.0483181 0.00692638 0.0184362 -0.0472265 0.00515192 0.0187046 -0.0491025 0.00528427 0.0189408 -0.0491006 0.00543441 0.0191499 -0.0491844 0.00553593 0.0192622 -0.0492835 -0.00668501 0.0237607 -0.0537657 -0.00380573 0.0232323 -0.0525556 -0.00364862 0.0238923 -0.0528693 -0.00657945 0.0240479 -0.0540022 0.00576346 0.0176971 -0.0457435 0.00631152 0.0180033 -0.0463898 0.00586966 0.0176971 -0.0458455 0.006256 0.0176971 -0.0464148 0.00723252 0.0184971 -0.0472253 0.00646963 0.0182628 -0.0463185 0.00666684 0.0182628 -0.0472275 0.00591939 0.0182628 -0.0455686 0.0060921 0.0184362 -0.0453749 0.00670626 0.0184362 -0.0462119 0.00698538 0.0184971 -0.0460862 0.00504027 0.0176971 -0.045331 0.00580398 0.0180033 -0.0456981 0.00519033 0.0184362 -0.0448605 0.00629583 0.0184971 -0.0451464 0.00528336 0.0184971 -0.0445688 -0.00951063 0.0241905 -0.0551352 -0.0126959 0.0235087 -0.0545666 -0.0111926 0.023563 -0.0550381 -0.00981994 0.0243391 -0.0556195 -0.0112512 0.0243586 -0.0557515 -0.0112227 0.0242261 -0.0553892 -0.0124979 0.0241959 -0.0550681 -0.0126498 0.0243267 -0.0554011 -0.0151755 0.0239707 -0.0520624 -0.00961589 0.0239028 -0.0548964 -0.00999239 0.0239196 -0.0550196 -0.00991723 0.0242072 -0.0552683 -0.0112015 0.0239384 -0.0551312 -0.0135974 0.0241195 -0.0543371 -0.0134006 0.0238312 -0.0541564 -0.0141346 0.0237143 -0.0531766 -0.014391 0.0240034 -0.0532787 -0.0133151 0.0234511 -0.0541041 -0.0123827 0.023908 -0.0548335 -0.0140289 0.023329 -0.0531633 0.00442916 0.0184971 -0.0442963 0.00433613 0.0184362 -0.044588 0.00511147 0.0182628 -0.0451077 0.00505877 0.0180033 -0.0452729 -0.0151117 0.0225504 -0.0468561 -0.0143889 0.023176 -0.0520411 -0.0152207 0.0229404 -0.0468216 -0.0144982 0.0235682 -0.052012 -0.0147854 0.0238583 -0.0520197 -0.0159137 0.0222572 -0.0416356 -0.0161972 0.0225459 -0.0416336 -0.0165835 0.0226615 -0.0416686 -0.0155061 0.0232298 -0.046824 -0.00195624 0.0193177 -0.0419345 -0.00579054 0.0193692 -0.0418766 -0.00568127 0.0197463 -0.0418071 -0.00553875 0.0200297 -0.0415656 -0.00442516 0.019452 -0.0422086 -0.00428272 0.019735 -0.0419694 -0.0053984 0.0201491 -0.041212 -0.00529507 0.0200747 -0.0408341 0.00168206 0.0182077 -0.0441775 0.00177947 0.0184836 -0.0439775 0.00189333 0.018638 -0.0436795 -0.00414247 0.0198558 -0.0416182 0.00418607 0.0176971 -0.0450585 0.00162023 0.0178644 -0.0442402 0.00420457 0.0180033 -0.0450005 0.00425727 0.0182628 -0.0448353 -0.0158743 0.0220927 -0.0412246 -0.0162049 0.0224748 -0.0411473 -0.0160427 0.0223488 -0.0411766 -0.0160059 0.0223064 -0.0409367 -0.016256 0.022478 -0.0408653 -0.0162973 0.022521 -0.0411341 -0.0158427 0.0220502 -0.0410057 -0.0161924 0.0223614 -0.0398648 -0.0155308 0.0221351 -0.0390879 -0.0153252 0.0221002 -0.039346 -0.0146723 0.0218868 -0.0385815 -0.0145531 0.0218767 -0.0389098 -0.0159253 0.0223095 -0.040031 -0.0151707 0.0219381 -0.0395908 -0.0159189 0.0221851 -0.0412084 -0.0157093 0.0221414 -0.0401945 -0.0150936 0.0216767 -0.0397802 -0.0144804 0.0217231 -0.0392151 -0.0144679 0.0214552 -0.039439 -0.0142087 0.0210153 -0.0394518 -0.0145181 0.0211243 -0.039539 -0.015685 0.0216573 -0.0406857 -0.0155788 0.0218837 -0.0403292 -0.0158173 0.0217912 -0.041271 -0.0137515 0.0215365 -0.0390918 -0.0137301 0.0216806 -0.0387546 -0.0137434 0.0216623 -0.0383878 -0.0132147 0.0207533 -0.0395087 -0.013145 0.0211218 -0.0394351 -0.013803 0.0212603 -0.0393286 -0.0130357 0.0214063 -0.0392042 -0.0129118 0.0215416 -0.0388689 0.0108201 0.0252562 -0.0664546 0.0129565 0.0249966 -0.0667965 0.013012 0.0247259 -0.066601 0.0119641 0.0250937 -0.0664454 0.0130141 0.0243961 -0.0665245 0.0120452 0.0248113 -0.0662231 0.0120672 0.0244529 -0.0661404 0.0118411 0.0252401 -0.0667603 0.0148646 0.0238364 -0.0664481 0.0156611 0.0235018 -0.0661602 0.0151046 0.024067 -0.0665792 0.0153417 0.0232788 -0.0660793 0.0152294 0.0231653 -0.0660949 0.0143023 0.024271 -0.0666739 0.0146534 0.0235481 -0.0664635 0.0136614 0.0245721 -0.0667363 0.0145779 0.0246646 -0.0671095 0.0144525 0.0245138 -0.0668423 0.0137097 0.02483 -0.0669291 0.01112 0.0244575 -0.0657562 0.00619385 0.0243285 -0.0637581 -0.00411877 0.0242829 -0.0596341 0.0110746 0.0248453 -0.0658463 0.010965 0.0251359 -0.0660999 0.00589211 0.0251267 -0.0644456 0.00603832 0.0250027 -0.0640939 0.00614814 0.0247096 -0.0638439 -0.00413619 0.0243684 -0.0596695 0.0157625 0.0219819 -0.0652019 0.0154025 0.0233315 -0.0660819 0.0154732 0.0232343 -0.0660084 0.015294 0.023067 -0.0660286 0.0159707 0.0235965 -0.0663915 0.0158794 0.0234563 -0.0661563 0.0156747 0.0233682 -0.0660523 0.0157908 0.0235572 -0.0662372 0.0155954 0.0234662 -0.0661308 0.0165334 0.0223621 -0.0651362 0.0162423 0.0223072 -0.0650793 0.0159726 0.0221741 -0.0651023 0.0163107 0.0215481 -0.0641277 0.0158249 0.0211776 -0.0643834 0.0157628 0.0208957 -0.0645609 -0.00418537 0.0245337 -0.0597761 -0.00424524 0.0246602 -0.0599125 -0.00486414 0.0244891 -0.0593395 -0.00469332 0.0239441 -0.059204 -0.00554789 0.0246 -0.0588348 -0.00610558 0.0245829 -0.0580654 -0.00608415 0.0244859 -0.0571177 -0.00503563 0.0246652 -0.0595094 -0.00580586 0.0245186 -0.0580273 -0.00555106 0.0243451 -0.0580067 -0.0057806 0.0244293 -0.0571824 -0.0055246 0.0242577 -0.0572501 -0.00516756 0.024171 -0.0586742 -0.00532257 0.024425 -0.0587321 -0.00537916 0.0240885 -0.0580068 -0.00535597 0.0239979 -0.0573101 -0.00510488 0.0239095 -0.0566655 -0.00506403 0.0235953 -0.0567242 -0.0053158 0.0237868 -0.0580275 -0.0052848 0.0238094 -0.0581898 -0.00474447 0.024237 -0.0592327 -0.00483441 0.0235453 -0.0564074 -0.00476708 0.0241002 -0.0559852 -0.00525117 0.0241728 -0.0565508 -0.00514896 0.0243084 -0.055512 -0.00547916 0.0243423 -0.0563987 -0.00463382 0.0235134 -0.0562107 -0.0040678 0.0237802 -0.0557976 -0.00465889 0.0238338 -0.0561436 -0.00494015 0.0242678 -0.0557621 0.0157217 0.020434 -0.0638104 0.0160191 0.0214089 -0.0642298 0.0169092 0.0210208 -0.0633867 0.0169684 0.0214715 -0.0641387 0.0166472 0.0215703 -0.0640954 0.0162579 0.0210848 -0.0633829 0.0157824 0.0207132 -0.0636362 0.0159721 0.0209436 -0.0634849 0.0159254 0.0204862 -0.0627408 0.0160559 0.0205708 -0.0626833 0.0162049 0.02063 -0.0626401 0.0165896 0.0211121 -0.0633482 -0.00208235 0.0233543 -0.0551064 -0.00307419 0.0237308 -0.0554144 -0.00313284 0.0239999 -0.0552267 -0.00215098 0.0239496 -0.0548475 -0.00224754 0.0241153 -0.0545744 -0.0023655 0.0241486 -0.054264 -0.00306365 0.0234052 -0.0554847 -0.00322942 0.0241658 -0.0549543 -0.00412664 0.0240491 -0.0556105 -0.00422321 0.0242152 -0.0553388 0.0165312 0.0206629 -0.062603 0.0157597 0.0183899 -0.0565703 0.016461 0.0187156 -0.0583838 0.0160961 0.0187306 -0.0583975 0.0168487 0.0205794 -0.0626359 0.0157204 0.0184552 -0.0579386 0.0155042 0.0181829 -0.0580016 0.0160358 0.0186084 -0.057894 0.0157644 0.0185868 -0.0584506 0.0163415 0.0198034 -0.0610612 0.0164481 0.0206658 -0.0626058 0.0159603 0.0196976 -0.0611349 0.0156894 0.0194386 -0.0612815 0.0157756 0.0203196 -0.062848 0.0157403 0.0202559 -0.0628879 0.015535 0.0183141 -0.0585319 0.0156811 0.0199782 -0.0630563 9.6409e-05 0.0232341 -0.0541813 -0.00209255 0.0236803 -0.0550358 0.000727677 0.0233574 -0.0533413 0.00364016 0.0216295 -0.0522006 0.00349997 0.0216153 -0.0518625 0.00833481 0.0187279 -0.0504785 0.000790195 0.0232178 -0.0536681 0.00607266 0.0199358 -0.0512853 0.00839349 0.0185728 -0.0507741 0.00977663 0.0183899 -0.0501063 0.00368578 0.0215052 -0.0525422 0.00362726 0.0212685 -0.0528156 0.00611541 0.0198058 -0.0516176 0.00988195 0.0180971 -0.0503795 3.19846e-05 0.0236432 -0.0536228 0.000100881 0.0234975 -0.053941 0.000769964 0.0229601 -0.0539197 0.00591857 0.0192689 -0.0520222 0.00606034 0.0195675 -0.051881 0.00838636 0.0183148 -0.0509939 0.0098986 0.0180033 -0.0504227 0.0083147 0.0180005 -0.0510985 0.015421 0.0180033 -0.0565858 0.0154672 0.0180971 -0.0565837 0.0151955 0.0180033 -0.0513019 0.0155942 0.0182628 -0.0565778 0.015934 0.0184971 -0.0512727 0.0158535 0.0184362 -0.056566 0.0123949 0.0180033 -0.0494604 0.0123783 0.0180971 -0.0494172 0.00983622 0.0182628 -0.0502609 0.00974287 0.0184362 -0.0500187 0.0121291 0.0184971 -0.0487708 0.0122392 0.0184362 -0.0490564 0.0134022 0.0184362 -0.0489037 0.0152417 0.0180971 -0.0513001 0.0149304 0.0180033 -0.0503695 0.0148774 0.0176971 -0.0503994 0.0133495 0.0176971 -0.0493948 0.0142685 0.0180033 -0.0496614 0.0150814 0.0182628 -0.0502842 0.013356 0.0180033 -0.0493342 0.0153074 0.0184362 -0.0501565 0.0155343 0.0183899 -0.0512885 0.0153688 0.0182628 -0.051295 0.0143637 0.0182628 -0.0495165 0.0133745 0.0182628 -0.0491618 0.0123325 0.0182628 -0.0492986 0.0122729 0.0183899 -0.049144 0.0145063 0.0184362 -0.0492996 0.0155739 0.0184971 -0.0500059 0.0134348 0.0184971 -0.0485993 -0.00959003 0.025396 -0.0809072 -0.00948264 0.0253492 -0.0807711 -0.00941898 0.0252653 -0.0806241 -0.00936403 0.0251771 -0.0805317 -0.00928976 0.0249802 -0.0804045 -0.00964261 0.0254046 -0.0810387 -0.00934791 0.0251771 -0.0805419 -0.00861682 0.0249053 -0.0806376 -0.00925954 0.0249154 -0.080387 -0.00876744 0.0253934 -0.0813826 -0.00786963 0.0253373 -0.0811057 -0.00870429 0.0253394 -0.0810759 -0.00790469 0.0251656 -0.0808402 -0.0086513 0.0251676 -0.0808137 -0.00792784 0.0249032 -0.080662 -0.0086063 0.0245938 -0.0805753 -0.00693088 0.0253981 -0.0811363 -0.00729445 0.0245984 -0.0803998 -0.00793543 0.0245914 -0.0805992 0.00915494 0.0246629 -0.07204 0.00918358 0.0249668 -0.0720928 0.0010352 0.0252383 -0.076432 0.00926227 0.0252252 -0.0722445 0.000929826 0.0246703 -0.0762202 -0.00726924 0.0249095 -0.0804576 -0.00719096 0.0251715 -0.0806186 0.000956709 0.0249779 -0.0762755 0.00115322 0.0254112 -0.0766656 -0.00707193 0.0253434 -0.0808573 -0.00958838 0.0249226 -0.080149 -0.00950041 0.0253493 -0.0807595 -0.00972073 0.0251895 -0.0802861 -0.0095373 0.0246017 -0.0801046 -0.0102092 0.0251817 -0.0797061 -0.0104797 0.0253419 -0.0798503 -0.00991212 0.0253577 -0.0804926 -0.00995153 0.0245699 -0.0795834 -0.0100215 0.0249073 -0.0796113 -0.0107823 0.0253578 -0.0800168 0.00930003 0.0253125 -0.0676256 0.00993582 0.0253298 -0.0679884 0.00918201 0.0252617 -0.0679191 0.00974153 0.0245468 -0.068926 0.0102444 0.0248985 -0.0697402 0.010241 0.0246194 -0.0704342 0.00974744 0.0252769 -0.0682401 0.0105804 0.0253592 -0.0686774 0.0103223 0.025303 -0.068851 0.0109617 0.0253908 -0.0695417 0.0110369 0.0254191 -0.0704836 0.0107327 0.0253575 -0.0704582 0.0107979 0.0254408 -0.0713971 0.0105207 0.0253778 -0.0712727 0.00908313 0.0250908 -0.0681714 0.00958917 0.0251055 -0.0684573 0.0106638 0.0253315 -0.0696193 0.0104118 0.0251586 -0.069689 0.00948614 0.0248428 -0.0686057 0.00996144 0.0248695 -0.0691078 0.0101046 0.0251309 -0.0690024 0.0104747 0.0251839 -0.0704399 0.0103021 0.0249248 -0.0704315 0.0102854 0.0252039 -0.0711695 0.0101273 0.0249453 -0.0711031 0.00984897 0.0246509 -0.0714569 0.00973971 0.0249591 -0.0716786 0.00986527 0.0252174 -0.0717947 0.0100518 0.0253915 -0.0719705 0.00969398 0.0246552 -0.0716396 0.00937923 0.0253992 -0.0724726 -0.0133154 0.025115 -0.0646271 -0.0128215 0.0249348 -0.0645617 -0.0126883 0.0247959 -0.0645496 -0.0126244 0.0246078 -0.0645515 -0.0119223 0.0251513 -0.0699958 -0.0129234 0.0250058 -0.0645731 -0.0121999 0.0253198 -0.0700359 -0.01111 0.025352 -0.0791366 -0.0125205 0.0253619 -0.0700864 -0.0107648 0.0253432 -0.0790773 -0.0104571 0.0251855 -0.0790203 -0.010246 0.0249093 -0.0789765 -0.011734 0.0248847 -0.0699731 -0.0100641 0.0239598 -0.0606707 -0.000515682 0.0245907 -0.0644726 -0.0100485 0.0242809 -0.0606044 -0.000352285 0.0250255 -0.0640379 -0.00988402 0.0247159 -0.0601611 0.00901923 0.0248272 -0.0683421 -0.000452162 0.0248562 -0.0642966 -0.013317 0.0251146 -0.0646209 -0.0133189 0.0251143 -0.0646146 -0.0130536 0.0250672 -0.0645895 -0.0127673 0.024658 -0.0636868 -0.0126577 0.0247059 -0.0645505 -0.0126586 0.024261 -0.0636965 -0.0130567 0.0249498 -0.063712 -0.0130274 0.0247622 -0.0628241 -0.0131907 0.0248892 -0.0628401 -0.0133058 0.0249192 -0.0626293 -0.0131081 0.0248425 -0.060851 -0.0130471 0.0247461 -0.0626254 -0.0132127 0.0248546 -0.0617919 -0.0129608 0.0246828 -0.0618761 -0.0128501 0.0247929 -0.061036 -0.0122623 0.0247422 -0.060445 -0.0126338 0.0246226 -0.0612017 -0.0124532 0.0240452 -0.0613756 -0.0124939 0.0243592 -0.0613213 -0.0127949 0.024422 -0.061943 -0.0128736 0.0244876 -0.0626331 -0.0128118 0.024183 -0.0626513 -0.0129014 0.0245975 -0.0628165 -0.0113818 0.023953 -0.0606058 -0.0120081 0.0243076 -0.0608364 -0.0121069 0.0245733 -0.060676 -0.0115164 0.0247097 -0.0600815 -0.0124488 0.0247863 -0.0601816 -0.0107152 0.0242649 -0.0604586 -0.011393 0.0242745 -0.0605388 -0.0107067 0.0245327 -0.0602667 -0.0106934 0.0247003 -0.0599833 -0.0114406 0.0245417 -0.0603536 -0.0099849 0.0245479 -0.0604244 0.0170039 0.0245703 -0.0820683 0.0176201 0.0249913 -0.0820405 0.0175838 0.0251302 -0.0765046 0.0177126 0.0236017 -0.0918661 0.0172602 0.0248571 -0.0820618 0.0180718 0.0242656 -0.0918833 0.0184379 0.0243958 -0.0918607 0.0153894 0.0254124 -0.0735882 0.0151803 0.025128 -0.0738741 0.0160738 0.0253919 -0.074141 0.0158502 0.0252262 -0.0743237 0.0162402 0.0244796 -0.0754367 0.0159809 0.0245581 -0.0749411 0.0156896 0.024958 -0.0744379 0.0168703 0.0252605 -0.0752609 0.0166017 0.0247484 -0.0765651 0.0163318 0.0248327 -0.0754394 0.0165575 0.0251125 -0.0753765 0.0168525 0.0250343 -0.0765534 0.0172066 0.025172 -0.0765316 0.0175141 0.0240261 -0.0931001 0.0164866 0.0241733 -0.093989 0.0166396 0.0245515 -0.0944 0.0174005 0.0245358 -0.0939925 0.0172011 0.0243733 -0.0937699 0.0171655 0.0237392 -0.0934231 0.0170549 0.0241019 -0.0936262 0.0180196 0.0244539 -0.0933552 0.018012 0.0242532 -0.0925511 0.0177278 0.0243055 -0.0931949 0.0177601 0.0239666 -0.0925062 0.0176659 0.0235941 -0.0925034 0.0183637 0.0243877 -0.0926277 0.0178093 0.0239782 -0.0918852 0.0130989 0.0246619 -0.0733074 0.0151049 0.0248168 -0.0739793 0.0150977 0.0246722 -0.0739904 0.0152366 0.0254701 -0.073115 0.0153492 0.0253809 -0.0736429 0.0138921 0.0254635 -0.0725857 0.015078 0.025411 -0.073379 0.0138295 0.0254055 -0.0728885 0.0149438 0.025238 -0.0736037 0.0137417 0.024972 -0.0733186 0.0137301 0.0246636 -0.0733794 0.0125479 0.0249706 -0.0732759 0.0137766 0.0252328 -0.0731461 0.0148547 0.0249777 -0.0737543 0.0148244 0.0246701 -0.0738078 0.0151327 0.0249793 -0.07394 0.0124902 0.0254041 -0.0728402 0.0125249 0.0252315 -0.0731011 0.0166907 0.0245874 -0.0945304 0.0162891 0.024586 -0.0948411 0.0162241 0.0245426 -0.0945243 0.0165626 0.0244351 -0.0941986 0.0164778 0.0241165 -0.093963 0.0161351 0.0241075 -0.0940652 0.0161697 0.0243738 -0.0942505 0.0153937 0.0245413 -0.0945542 0.0147962 0.0241259 -0.0938886 0.0154509 0.0241061 -0.0940897 0.0154288 0.0243725 -0.0942771 0.0145997 0.0245606 -0.0943093 -0.00343339 0.0253467 -0.0807028 0.00411265 0.0246713 -0.0774069 0.011407 0.0249746 -0.0736306 0.00408441 0.024976 -0.0773536 0.0113285 0.0252351 -0.0734736 0.0112104 0.025408 -0.0732393 0.00400577 0.0252348 -0.0772008 0.00388858 0.0254086 -0.0769715 0.00580555 0.0241389 -0.0892601 0.0148164 0.023808 -0.0938248 0.00578477 0.0244554 -0.0893228 0.0147198 0.0243914 -0.0940595 0.0144557 0.0246058 -0.094597 -0.00330531 0.0249992 -0.0849212 0.00570832 0.0247202 -0.0894918 0.0055887 0.02489 -0.0897396 -0.00353867 0.0247482 -0.0845633 -0.00364142 0.0250112 -0.0847128 -0.00322856 0.0247356 -0.0847556 -0.00342424 0.02517 -0.0851652 -0.00379979 0.0251824 -0.0849312 -0.0039686 0.0244688 -0.084017 -0.00350792 0.0244353 -0.0845066 -0.00401415 0.0247791 -0.0840618 -0.00429757 0.0248145 -0.0834301 -0.00415704 0.0250407 -0.084169 -0.00437488 0.0252127 -0.0843217 -0.00501494 0.0253064 -0.0836329 -0.0050901 0.0253436 -0.0826921 -0.00471679 0.0252475 -0.0835547 -0.00446474 0.0250747 -0.0834835 -0.00478618 0.0252816 -0.0827169 -0.00424101 0.0245071 -0.0834028 -0.00412371 0.0245756 -0.0820841 -0.00435589 0.0248492 -0.0827392 -0.00457477 0.0253109 -0.081903 -0.00432457 0.0253985 -0.0809982 -0.00410621 0.0253328 -0.0812053 -0.00392039 0.0251584 -0.0813782 -0.00379465 0.024901 -0.0814914 -0.00331708 0.0251721 -0.0809275 -0.00357004 0.025413 -0.0804355 -0.00485097 0.0253751 -0.0817797 -0.00452845 0.025108 -0.0827334 -0.00434002 0.0251368 -0.082004 -0.00418179 0.0248788 -0.0820675 -0.00323827 0.0249149 -0.0810765 -0.00374763 0.0245988 -0.0815281 -0.00315802 0.0234302 -0.109244 -0.00286951 0.0226337 -0.108375 -0.00257112 0.02296 -0.108398 -0.00170658 0.0234228 -0.108545 -0.00247462 0.0233952 -0.10886 -0.00193794 0.0229881 -0.108139 -0.00253391 0.0232269 -0.108585 0.00536085 0.0233695 -0.103562 0.0126603 0.0237392 -0.0989842 0.0128921 0.0241738 -0.099388 0.00533745 0.023051 -0.103499 -0.00184813 0.0232539 -0.108305 0.00545079 0.0236353 -0.103727 0.00559237 0.0238042 -0.103967 -0.00446335 0.0228169 -0.107892 -0.00323661 0.0234298 -0.109242 -0.00314264 0.0233895 -0.108919 -0.00312972 0.0232214 -0.108637 -0.00319111 0.0232223 -0.108634 -0.00312146 0.0229542 -0.108446 -0.00389239 0.0229079 -0.108267 -0.00317547 0.0229548 -0.108443 -0.00321271 0.0233901 -0.108917 -0.00400528 0.0231814 -0.108449 -0.00414543 0.0233398 -0.108724 -0.00489518 0.0232414 -0.108289 -0.00457563 0.0224126 -0.107643 -0.00485456 0.0227585 -0.107401 -0.00465097 0.0230985 -0.108047 -0.00541304 0.023176 -0.107697 -0.00574755 0.0231155 -0.107889 -0.00532906 0.0230691 -0.10691 -0.00569238 0.0231951 -0.106995 -0.00508967 0.0230468 -0.10752 -0.00607413 0.0231286 -0.107066 0.0127587 0.0243342 -0.0953528 0.0127068 0.0245185 -0.0950452 0.0126656 0.02447 -0.0951228 0.0128923 0.0245103 -0.0951501 0.012512 0.0240895 -0.0953972 0.0135222 0.0244665 -0.0957105 0.0137542 0.0245375 -0.0955288 0.0139296 0.0244087 -0.0964488 0.0138084 0.0241703 -0.0972661 0.0131864 0.0240368 -0.0959488 0.0133235 0.0242912 -0.0958575 0.013687 0.0242345 -0.0965214 0.0134593 0.0236772 -0.0965595 0.0135221 0.0239781 -0.0965602 0.0131307 0.0237397 -0.0959713 0.0126655 0.0240812 -0.0954842 0.013514 0.0238445 -0.0979282 0.0135465 0.0235702 -0.0975564 0.0136348 0.0239115 -0.0972465 0.0140681 0.0243432 -0.097279 0.0142177 0.024332 -0.0982118 0.0131762 0.0237848 -0.098529 0.0133097 0.0240485 -0.0986561 0.0135166 0.0242187 -0.0988344 0.0136765 0.0241059 -0.0980053 0.0137634 0.0242677 -0.099035 0.013924 0.0242773 -0.098105 0.0131376 0.0234702 -0.0984736 0.0127505 0.0240048 -0.0991489 -0.00675748 0.0232608 -0.0977652 -0.00507225 0.0227811 -0.106831 -0.00708642 0.0239171 -0.0978901 -0.00858314 0.024427 -0.0884507 -0.0068413 0.0236315 -0.0978162 -0.00914492 0.0248546 -0.0885844 -0.0074365 0.0240518 -0.0979699 0.0034792 0.0245173 -0.0907724 0.00361114 0.0248074 -0.090532 -0.00544577 0.0250982 -0.0859369 0.0125921 0.0243423 -0.0952582 0.012534 0.0241803 -0.0953606 -0.00821674 0.0250559 -0.0864147 -0.00803674 0.0247882 -0.0865802 -0.0080298 0.0247713 -0.0865863 -0.00800313 0.0246962 -0.086609 -0.00856537 0.0249013 -0.0870621 -0.00882384 0.0250682 -0.0869505 -0.00852008 0.0251962 -0.0861202 -0.00846673 0.0242238 -0.0875301 -0.00948752 0.0249506 -0.0877041 -0.00913782 0.0249473 -0.0877587 -0.00911296 0.0251098 -0.0868029 -0.00859705 0.0245187 -0.0877794 -0.00838081 0.0246371 -0.0871189 -0.00950787 0.0248327 -0.0886487 -0.00881312 0.024709 -0.0885134 -0.00882028 0.0247933 -0.0877855 -0.00851182 0.0241773 -0.0877414 -0.00824283 0.0250793 -0.0863899 -0.008308 0.0251268 -0.0863275 -0.00847576 0.0251914 -0.0861639 -0.00797907 0.025217 -0.0856942 -0.00777804 0.0250986 -0.0860224 -0.00734954 0.0244254 -0.0862253 -0.00762836 0.0248077 -0.0862572 -0.00702587 0.0251129 -0.0857256 -0.00621771 0.0251128 -0.0856959 -0.00696715 0.0248221 -0.0859963 -0.00625658 0.024822 -0.0859703 -0.0052692 0.0252166 -0.0855948 -0.00710492 0.0252324 -0.0853504 -0.00627309 0.0244332 -0.0860698 -0.00557798 0.0248073 -0.0861821 0.0193541 0.022214 -0.108676 0.0194544 0.022595 -0.108699 0.0187142 0.0232073 -0.101556 0.0189807 0.0234952 -0.101554 0.0193507 0.0236227 -0.101528 0.0197354 0.0235593 -0.101485 0.0205914 0.0212501 -0.119511 0.0206943 0.0216349 -0.119533 0.0197239 0.0228833 -0.108695 0.0213475 0.0220455 -0.119492 0.020097 0.0230087 -0.108666 0.0170369 0.0241456 -0.0993943 0.0169884 0.0238717 -0.0996542 0.018198 0.0235085 -0.100375 0.0176139 0.0236921 -0.0999213 0.0186487 0.0239305 -0.100096 0.0177325 0.0239492 -0.0997846 0.017878 0.0241197 -0.0995639 0.0183974 0.0237756 -0.100279 0.0185564 0.0233251 -0.100933 0.0188043 0.023604 -0.100883 0.0191338 0.0237419 -0.100765 0.0190737 0.0218813 -0.121764 0.0190641 0.021683 -0.121707 0.0195082 0.022146 -0.121826 0.0196264 0.0223126 -0.122087 0.0199553 0.0214594 -0.121227 0.0200417 0.0217987 -0.121252 0.0204573 0.0216885 -0.120718 0.0205046 0.0212633 -0.120379 0.0205684 0.0212363 -0.120136 0.0190915 0.022037 -0.121853 0.0194214 0.0218776 -0.121652 0.0202153 0.0220727 -0.121386 0.0206681 0.0216186 -0.120135 0.0209349 0.0219076 -0.120171 0.0209691 0.021924 -0.119526 0.0191865 0.022334 -0.122281 0.0206912 0.0219705 -0.120803 0.0204429 0.0222286 -0.121604 0.0197556 0.0223489 -0.122391 0.0206805 0.0222364 -0.121862 0.0210056 0.0221103 -0.120955 0.021331 0.0220769 -0.12114 0.0213037 0.022033 -0.120237 0.0217354 0.0219692 -0.119438 0.0169779 0.023761 -0.0997067 0.0169652 0.0235035 -0.0997597 0.0169646 0.0234692 -0.0997604 0.0171005 0.0242667 -0.0990343 0.0168979 0.0241422 -0.0993823 0.017008 0.0240126 -0.0995517 0.0160894 0.0241387 -0.0994275 0.0168651 0.023853 -0.099648 0.0153424 0.0241132 -0.0997387 0.0154967 0.0238235 -0.099962 0.0161537 0.0238494 -0.0996878 0.0191123 0.0221482 -0.121951 0.0191325 0.0222228 -0.122042 0.0190215 0.0223137 -0.122256 0.0189767 0.0221455 -0.121978 0.0184759 0.0215542 -0.121747 0.0182649 0.0218776 -0.12179 0.0189485 0.0218785 -0.121789 0.0182365 0.0221447 -0.121978 0.0181916 0.0223129 -0.122256 0.0190756 0.0223549 -0.122576 0.0083155 0.0234612 -0.104466 0.00106674 0.0232487 -0.108874 0.00116092 0.0229965 -0.109003 0.0155626 0.0234394 -0.100037 0.00816108 0.0237507 -0.104243 0.00944778 0.0222621 -0.11706 0.0176186 0.0219003 -0.121566 0.0175366 0.0221664 -0.121736 0.0174075 0.0223351 -0.121984 0.00908189 0.0227402 -0.117762 0.00127699 0.0226246 -0.112553 0.00946908 0.0219429 -0.116995 0.00119497 0.0228908 -0.112723 0.00936575 0.0225282 -0.11723 0.00923662 0.0226969 -0.117478 0.000911072 0.0231027 -0.113255 0.00129826 0.0223054 -0.112489 0.00118944 0.0226299 -0.112503 0.000791467 0.0231083 -0.113185 0.00106583 0.0230595 -0.112971 0.00095969 0.0230646 -0.11291 0.00110012 0.0228958 -0.112669 0.000536779 0.0229409 -0.112179 0.000669721 0.0226769 -0.11205 0.000556338 0.0223864 -0.111778 0.000707699 0.0223618 -0.111994 -0.000536585 0.0233032 -0.110809 -8.23869e-05 0.0231725 -0.111629 -0.000230177 0.0232428 -0.110803 0.000165121 0.0230013 -0.111528 2.9634e-05 0.02307 -0.110788 -0.000380044 0.0233801 -0.10988 0.00020324 0.0228112 -0.110767 0.000147356 0.0231393 -0.110045 0.000330468 0.0231108 -0.112359 0.000378831 0.0224293 -0.111405 0.000327391 0.0227398 -0.111449 0.000500664 0.0226158 -0.109794 0.000264176 0.0225059 -0.110741 0.000980429 0.0233764 -0.108747 0.000505901 0.0232011 -0.109382 0.00113496 0.023087 -0.108969 -9.54437e-05 0.0233135 -0.109974 0.000306568 0.0233765 -0.109237 0.000643727 0.0229473 -0.10947 0.000312604 0.0228831 -0.110081 0.00120157 0.0227035 -0.109043 0.00365801 0.0202772 -0.137792 0.0040983 0.0202939 -0.137635 0.00370549 0.0208631 -0.138043 0.00419333 0.0208779 -0.137871 0.00376524 0.0210319 -0.138316 0.00411809 0.0206122 -0.137699 0.00449672 0.0203215 -0.137374 0.00452696 0.0206379 -0.137434 0.00463636 0.0209026 -0.137584 0.0043116 0.0210471 -0.138122 0.00286418 0.0209624 -0.138383 0.00282838 0.0209925 -0.138716 0.00291426 0.020799 -0.138094 0.00194285 0.0207973 -0.138159 0.00211027 0.0206488 -0.137876 0.00179075 0.0207903 -0.138485 0.00098264 0.0205757 -0.138005 0.00150625 0.0204998 -0.13747 0.00235894 0.0200312 -0.137652 0.00225904 0.0203749 -0.137695 0.0029698 0.020531 -0.1379 0.00302101 0.0202057 -0.137834 0.00366764 0.0205968 -0.137858 0.00357321 0.0202741 -0.137809 0.00171051 0.0198019 -0.137166 0.00172316 0.020217 -0.137318 0.000757536 0.0205253 -0.137149 0.00123847 0.0206295 -0.137719 0.00125276 0.0197282 -0.136252 0.000878128 0.0204156 -0.13639 0.00136144 0.0201205 -0.136846 0.00110256 0.0204114 -0.136965 0.0108024 0.0213043 -0.132407 0.0169681 0.0217212 -0.127229 0.0171389 0.0218906 -0.127446 0.0173434 0.0219367 -0.127693 0.0106932 0.0210395 -0.132255 0.0109732 0.0214738 -0.132623 0.00480703 0.0210723 -0.137801 0.00115615 0.0201242 -0.136306 -0.000251821 0.0208832 -0.13101 0.000492158 0.0205253 -0.13648 -0.00221956 0.0211693 -0.12 0.00011735 0.0201988 -0.130871 2.2403e-05 0.0205923 -0.130926 -0.00257948 0.0218483 -0.120139 -0.00295452 0.0219655 -0.120231 -0.000633818 0.0209957 -0.131101 0.0165693 0.0218958 -0.123655 0.016753 0.0222338 -0.123349 0.0167093 0.0221852 -0.123424 0.0166311 0.0220574 -0.123556 0.0165091 0.0215128 -0.123733 0.017761 0.0221471 -0.12439 0.0183147 0.0221434 -0.125156 0.0170809 0.0220275 -0.123887 0.0172543 0.0222034 -0.123716 0.0180139 0.0220799 -0.125193 0.0179855 0.0220095 -0.126032 0.0177582 0.0219064 -0.125216 0.0175342 0.0219723 -0.124494 0.0173788 0.0217173 -0.124554 0.0177297 0.0218375 -0.125967 0.017395 0.0212278 -0.12624 0.0175045 0.0212693 -0.125876 0.0175606 0.0215773 -0.125912 0.0175861 0.0216489 -0.125219 0.0173175 0.021419 -0.124562 0.0169605 0.0217745 -0.123995 0.0172644 0.0211978 -0.126503 0.0174554 0.0217734 -0.126663 0.0176822 0.021944 -0.126811 0.0179522 0.0219952 -0.126975 0.016859 0.0214563 -0.127077 0.0173083 0.0215107 -0.126555 -0.00256388 0.0213138 -0.118403 -0.00265575 0.021702 -0.118458 -0.00231179 0.0215583 -0.120055 -0.00292257 0.0219919 -0.118541 -0.00334151 0.0218802 -0.120307 -0.00299692 0.0218472 -0.11686 -0.00329671 0.0221099 -0.118632 -0.00402206 0.0221737 -0.117108 0.0086484 0.022675 -0.11855 0.00846298 0.0225499 -0.118876 0.000216779 0.0229154 -0.114328 0.00832307 0.0222606 -0.119107 0.0165458 0.0218054 -0.12369 0.00826286 0.0218776 -0.119185 -0.00192365 0.0227908 -0.114399 -0.00184282 0.0225388 -0.114537 -0.00237574 0.0221016 -0.114986 -0.00276456 0.0218472 -0.115549 -0.00290545 0.0214598 -0.116805 -0.00178084 0.0226333 -0.114463 -0.00246972 0.0224085 -0.11499 -0.00264041 0.0226659 -0.114903 -0.00287619 0.0221806 -0.115602 -0.0031092 0.0224481 -0.115578 -0.0030379 0.0219746 -0.11623 -0.00183112 0.0227947 -0.114358 -0.00203544 0.022967 -0.114186 -0.00341756 0.0225969 -0.115483 -0.00330076 0.0222545 -0.116265 -0.00326274 0.0221368 -0.116943 -0.00363583 0.0222557 -0.117033 -0.00216265 0.0230429 -0.113927 -0.00286033 0.0228326 -0.114739 -0.00309408 0.0228816 -0.114525 -0.00374037 0.0225976 -0.115333 -0.00404171 0.0223351 -0.116197 -0.00366344 0.0223848 -0.116253 -0.00204463 0.0230483 -0.113877 -0.00173109 0.022251 -0.114547 -0.00189458 0.0229225 -0.11422 -0.000594581 0.0226488 -0.114322 -0.00130711 0.0226479 -0.114322 -0.00054648 0.0229379 -0.11406 -0.00135613 0.0229369 -0.11406 7.68753e-05 0.0226261 -0.114559 -0.000615489 0.0222678 -0.114416 -0.000482802 0.0230651 -0.113693 0.023257 0.0194295 -0.139887 0.0244347 0.0201305 -0.139783 0.023801 0.0201834 -0.139876 0.0223044 0.0209798 -0.130034 0.0241242 0.0202239 -0.139834 0.0226889 0.0210967 -0.129994 0.0233276 0.0197497 -0.139905 0.0235197 0.0200159 -0.139901 0.025324 0.0189945 -0.152317 0.0219756 0.0214431 -0.128613 0.0197763 0.0218834 -0.127814 0.020251 0.0218538 -0.127845 0.0197911 0.0217347 -0.128037 0.0198018 0.0215335 -0.128192 0.0198084 0.0212907 -0.128276 0.0202873 0.0219282 -0.127557 0.0213636 0.0217377 -0.127816 0.0202107 0.0216782 -0.128085 0.0210542 0.021527 -0.128327 0.0201723 0.0214261 -0.128242 0.0209159 0.0212695 -0.128465 0.0210407 0.0208684 -0.128618 0.0221165 0.0210981 -0.129387 0.0230791 0.0210107 -0.129935 0.0227698 0.0210958 -0.129984 0.0224509 0.0210501 -0.130021 0.0224573 0.0212264 -0.129254 0.0221748 0.0208812 -0.130042 0.0220236 0.0206897 -0.130045 0.0218541 0.0208179 -0.129442 0.0212121 0.021692 -0.128098 0.021713 0.0212962 -0.128807 0.0214968 0.0210286 -0.128907 0.0219869 0.0206169 -0.130043 0.0229345 0.019851 -0.155131 0.02332 0.0193381 -0.154633 0.0239599 0.0189591 -0.154399 0.024023 0.0192214 -0.154419 0.0245999 0.019026 -0.153983 0.0245147 0.0187472 -0.153994 0.0248725 0.0185418 -0.153484 0.0249557 0.0188431 -0.153454 0.0249702 0.0184731 -0.153247 0.0250516 0.0184091 -0.152915 0.0251368 0.019098 -0.153483 0.0253175 0.0189972 -0.152901 0.0251235 0.0187305 -0.152896 0.0251265 0.0187258 -0.152325 0.0233812 0.0197449 -0.15494 0.024238 0.0196294 -0.154687 0.0241194 0.0194536 -0.154519 0.0247504 0.0192677 -0.154046 0.0249461 0.0194402 -0.154177 0.0253879 0.0192672 -0.153566 0.0256007 0.019164 -0.15293 0.0229617 0.0190981 -0.154602 0.0233485 0.0195671 -0.154753 0.0243651 0.0197285 -0.154904 0.0251609 0.0195205 -0.154357 0.0256704 0.0193246 -0.153691 0.025612 0.01916 -0.152287 0.0259406 0.0191934 -0.152241 0.0229163 0.0198965 -0.155452 0.0234146 0.0198525 -0.155175 0.0244864 0.0197397 -0.155145 0.0259406 0.0192615 -0.153837 0.0259249 0.0192024 -0.152977 0.0262526 0.0190891 -0.152186 0.0192269 0.0211374 -0.128414 0.0198023 0.0215203 -0.128199 0.0197836 0.0218226 -0.127926 0.0197597 0.0219497 -0.127554 0.0190789 0.0218091 -0.128079 0.0185695 0.0214838 -0.12869 0.0191819 0.0215198 -0.128327 0.0227298 0.0191006 -0.154575 0.0229592 0.019416 -0.154668 0.0224513 0.0194238 -0.154574 0.0217381 0.019714 -0.154413 0.0213881 0.0199329 -0.15489 0.0223184 0.0198587 -0.155017 0.0229496 0.0196815 -0.154854 0.0223995 0.019689 -0.154753 0.0118828 0.0214749 -0.133453 0.0123188 0.021063 -0.13394 0.0060675 0.0206585 -0.13919 0.0186488 0.0210985 -0.128753 0.0123977 0.0206773 -0.134003 0.0121317 0.0213529 -0.13374 0.0183824 0.0217735 -0.128491 0.0181337 0.0218959 -0.128205 0.0140191 0.0198457 -0.148351 0.0218409 0.0194498 -0.15426 0.0139165 0.0201102 -0.148505 0.0215786 0.0198842 -0.154635 0.00609558 0.0205299 -0.142597 0.00593557 0.0206996 -0.142821 0.0137567 0.0202802 -0.148728 0.00574429 0.0207465 -0.143077 0.00573369 0.0207123 -0.142652 0.00545205 0.0200832 -0.141066 0.00622653 0.0199486 -0.142381 0.00619816 0.0202651 -0.142442 0.0049478 0.0208152 -0.142135 0.00465996 0.0208811 -0.141238 0.00522511 0.0207623 -0.141987 0.00496498 0.0208227 -0.14119 0.00468628 0.0209507 -0.140297 0.00545839 0.0205912 -0.141853 0.00522297 0.0206503 -0.141141 0.00498393 0.0208867 -0.140351 0.00528018 0.0209469 -0.139566 0.00523709 0.020713 -0.140389 0.00502257 0.0210161 -0.139419 0.00588042 0.0209485 -0.138989 0.00598515 0.0208208 -0.139104 0.00591487 0.0205422 -0.142446 0.00603143 0.020278 -0.142303 0.00561062 0.020329 -0.141755 0.00539412 0.0203905 -0.141097 0.00540792 0.0204555 -0.140404 0.00550043 0.020772 -0.139683 0.00565137 0.0205168 -0.139754 0.0057111 0.0202183 -0.139767 0.00609858 0.0205674 -0.13922 0.00532145 0.0200596 -0.14552 0.00439184 0.0201445 -0.145745 0.00531204 0.0202068 -0.145459 0.00426745 0.0203172 -0.145613 0.00413127 0.020428 -0.145434 0.00527438 0.0204964 -0.145192 0.00362535 0.0187456 -0.147924 0.00336694 0.0195228 -0.147202 0.0030973 0.019688 -0.14719 0.00308513 0.0195072 -0.148092 0.0024932 0.019675 -0.14705 0.002444 0.0194276 -0.148212 0.00396468 0.0193495 -0.14637 0.00387178 0.0196119 -0.146414 0.00355675 0.0192717 -0.147169 0.0032652 0.0200972 -0.146183 0.00303774 0.0200911 -0.146016 0.00279004 0.0197416 -0.147137 0.0034989 0.0200105 -0.146314 0.00370982 0.0198418 -0.146395 0.00495824 0.0197903 -0.14564 0.00449221 0.0199267 -0.145818 0.00455873 0.0196852 -0.145824 0.00414936 0.0194834 -0.146149 0.0079018 0.0169604 -0.17216 0.0058976 0.0181052 -0.160477 0.00782997 0.0173 -0.172193 0.00762157 0.0175751 -0.172243 0.0054019 0.0185391 -0.160596 0.00506525 0.0185594 -0.160657 0.00356117 0.0190731 -0.147963 0.00336984 0.0193428 -0.148023 0.00569743 0.0183778 -0.160532 0.00275723 0.0195372 -0.148159 0.00591575 0.0198221 -0.145566 0.00623658 0.0201994 -0.145543 0.00553133 0.0202082 -0.145441 0.00552363 0.0204978 -0.145172 0.00551342 0.0206228 -0.144797 0.00619855 0.0198152 -0.145634 0.00704227 0.020461 -0.145662 0.00727587 0.0205823 -0.145361 0.0063253 0.0204891 -0.145287 0.00823287 0.01708 -0.172994 0.0101877 0.0187511 -0.174422 0.0108726 0.0187693 -0.174102 0.0106984 0.0180476 -0.173682 0.0102011 0.0179894 -0.173831 0.00939839 0.0180241 -0.173849 0.0101724 0.018241 -0.173878 0.0101601 0.0184666 -0.174001 0.00921527 0.0184246 -0.174163 0.0101654 0.0186427 -0.174189 0.00883895 0.0174434 -0.173566 0.00948219 0.0177644 -0.173818 0.00856913 0.0179643 -0.17366 0.00930578 0.0182531 -0.173969 0.00913752 0.0185183 -0.174409 0.00838296 0.0171698 -0.173185 0.00872568 0.0177239 -0.173564 0.00808279 0.0177338 -0.173233 0.00784185 0.0178957 -0.173385 0.00839168 0.0181302 -0.17384 0.00821872 0.0181979 -0.174079 0.00807167 0.016994 -0.172714 0.00827381 0.0174775 -0.173163 0.00718361 0.0177755 -0.173013 0.00759135 0.017936 -0.173591 0.00798456 0.0173268 -0.172703 0.00777978 0.017598 -0.172758 0.00749524 0.0177574 -0.172868 0.00731621 0.0177334 -0.1723 0.00697187 0.0177449 -0.172353 0.00679351 0.0197843 -0.145943 0.0068669 0.0201709 -0.145873 0.014698 0.0197611 -0.15179 0.0151075 0.020172 -0.151275 0.0225297 0.0193767 -0.157706 0.0148735 0.0200514 -0.151577 0.0110592 0.0187997 -0.17408 0.0108283 0.0180517 -0.173617 0.0107032 0.0182203 -0.1737 0.0108527 0.0183654 -0.173677 0.0107194 0.0183615 -0.173742 0.0107679 0.0185664 -0.17386 0.0113967 0.0183906 -0.173255 0.010934 0.0186288 -0.17384 0.0113571 0.0180787 -0.173204 0.0231503 0.0197759 -0.157365 0.0224573 0.0189884 -0.157778 0.0227751 0.0195296 -0.157756 0.0227053 0.0196672 -0.157492 0.0170829 0.0187033 -0.167014 0.0172097 0.0189661 -0.167143 0.0228949 0.019315 -0.160904 0.0115236 0.018653 -0.173383 0.0174042 0.0191373 -0.16733 0.0117179 0.0188245 -0.173568 0.0119487 0.0188778 -0.173781 0.0228859 0.0196572 -0.157644 0.0229679 0.0196837 -0.157657 0.0226076 0.0189774 -0.157903 0.0229482 0.019705 -0.15758 0.0233407 0.019543 -0.159427 0.0232723 0.0195799 -0.158862 0.0233317 0.0196852 -0.158837 0.0235947 0.019558 -0.160954 0.0231153 0.0196073 -0.158166 0.0230294 0.0194483 -0.158254 0.0232918 0.0194291 -0.159402 0.0233503 0.0194745 -0.160291 0.0233331 0.0195008 -0.160756 0.0233334 0.0195049 -0.16078 0.0226884 0.0193665 -0.15784 0.0228091 0.0195059 -0.157819 0.0229842 0.0192654 -0.158324 0.0232296 0.0194661 -0.158883 0.0232046 0.0193466 -0.1589 0.0232618 0.019309 -0.159377 0.0232218 0.0193085 -0.160194 0.0231187 0.0193283 -0.160606 0.0229806 0.0190686 -0.160497 0.0231134 0.0193336 -0.160626 0.0227062 0.0192593 -0.157926 0.0226728 0.0189759 -0.157966 0.023198 0.0192242 -0.158914 0.0232515 0.019186 -0.15935 0.0231494 0.0191073 -0.160107 0.0227683 0.0190519 -0.160774 0.0229251 0.0187594 -0.160469 0.0229697 0.0190712 -0.160516 0.0230898 0.019486 -0.161092 0.0312081 0.0163592 -0.190644 0.0287681 0.0177802 -0.193086 0.0287475 0.0179565 -0.193262 0.0287723 0.0175582 -0.192971 0.0296994 0.0170864 -0.192894 0.0302256 0.0171505 -0.192717 0.0307762 0.016827 -0.192242 0.0310862 0.0165652 -0.191716 0.0310528 0.0161895 -0.191609 0.0282526 0.0177191 -0.192856 0.0294995 0.0174179 -0.192981 0.0309549 0.017065 -0.192282 0.0312206 0.0164008 -0.191184 0.0295619 0.0176389 -0.193091 0.0296239 0.0178127 -0.193266 0.0303554 0.0173765 -0.192798 0.0305042 0.0175463 -0.192952 0.0312886 0.0168194 -0.191721 0.0315624 0.0169814 -0.191787 0.031431 0.0166705 -0.191168 0.0287125 0.0180699 -0.193482 0.0311781 0.0172304 -0.192396 0.0317335 0.0168304 -0.191181 0.0320729 0.0168509 -0.191222 0.029679 0.0179217 -0.193489 0.0297218 0.0179549 -0.193738 0.0306547 0.0176403 -0.19316 0.0316306 0.0172637 -0.192773 0.0314145 0.0172999 -0.192568 0.0318622 0.0170245 -0.191905 0.0321388 0.0169416 -0.192054 0.0323869 0.0167285 -0.191283 0.0287796 0.0167461 -0.176253 0.0288553 0.0170806 -0.17626 0.0270116 0.0178156 -0.164656 0.0290623 0.0173536 -0.176243 0.0293626 0.0175149 -0.176204 0.0297009 0.0175348 -0.17615 0.0275087 0.0182499 -0.164609 0.0278425 0.0182763 -0.164558 0.0314199 0.0166344 -0.190621 0.0317264 0.0167932 -0.190577 0.0320696 0.0168057 -0.190521 0.0280015 0.0181352 -0.193388 0.0280767 0.0180886 -0.193231 0.0281449 0.0180042 -0.193087 0.0275474 0.0180984 -0.192888 0.0281904 0.0179166 -0.192991 0.0277166 0.0179261 -0.192684 0.0266047 0.0177361 -0.163814 0.0240608 0.01909 -0.163036 0.0239409 0.0193577 -0.162793 0.024455 0.0192875 -0.162705 0.0240991 0.0189106 -0.163108 0.0244827 0.0191127 -0.162867 0.0244938 0.0188973 -0.162972 0.0241198 0.0186714 -0.163139 0.0252367 0.0187559 -0.162932 0.0244131 0.0194058 -0.1625 0.0254415 0.0192953 -0.162192 0.0251778 0.0185155 -0.162965 0.0261041 0.0186972 -0.163085 0.0252983 0.0189729 -0.162825 0.0262513 0.018866 -0.162925 0.0253566 0.0191453 -0.162655 0.0263968 0.0189579 -0.162711 0.0265234 0.0189618 -0.162466 0.0254059 0.0192564 -0.162436 0.0263991 0.0178859 -0.163563 0.0259725 0.0184712 -0.163171 0.026509 0.0181678 -0.163594 0.0266862 0.018409 -0.16354 0.0269049 0.0185746 -0.163408 0.0268412 0.0179381 -0.164091 0.027039 0.0181968 -0.164063 0.0276012 0.0184018 -0.163837 0.0278718 0.0183138 -0.163676 0.0271337 0.0186407 -0.163219 0.0269373 0.0174854 -0.164645 0.0267468 0.0176275 -0.164053 0.0272141 0.0180866 -0.164643 0.0273073 0.0183604 -0.163974 0.0150209 0.018284 -0.18192 0.0120645 0.0185877 -0.179953 0.0146496 0.0185097 -0.182366 0.0192526 0.0181514 -0.185508 0.0148512 0.0184557 -0.182126 0.0193638 0.0178894 -0.185367 0.015132 0.0180217 -0.181779 0.0233151 0.0182042 -0.189301 0.019083 0.0183233 -0.185714 0.0235958 0.0177704 -0.188956 0.0236316 0.01746 -0.188904 0.0193991 0.0175785 -0.185315 0.0234845 0.0180322 -0.189096 0.027828 0.0176646 -0.192545 0.024118 0.0187236 -0.163138 0.0237833 0.0194701 -0.16246 0.0240691 0.0190591 -0.163052 0.0236318 0.0194657 -0.162535 0.0231809 0.0193157 -0.16337 0.0238164 0.0193457 -0.162871 0.0239545 0.0190551 -0.16311 0.0121569 0.018547 -0.179843 0.0119574 0.0183911 -0.179338 0.0122889 0.018428 -0.179682 0.0124195 0.0181761 -0.179518 0.0120813 0.0181247 -0.179196 0.017627 0.0186833 -0.169882 0.0174115 0.0189745 -0.1697 0.0234828 0.018634 -0.163607 0.0177128 0.0182916 -0.16994 0.0233962 0.0190247 -0.16355 0.011148 0.0186886 -0.176535 0.0115687 0.018667 -0.176115 0.0113194 0.0187766 -0.175913 0.0116385 0.0179429 -0.176713 0.0115329 0.0179078 -0.17696 0.0113638 0.0181853 -0.177364 0.0114577 0.0177933 -0.178007 0.0113855 0.0181333 -0.178033 0.0116292 0.0181213 -0.178666 0.0118016 0.0183566 -0.176295 0.011569 0.0182557 -0.176708 0.0113963 0.0185183 -0.176645 0.011178 0.0184087 -0.178084 0.0114488 0.0183945 -0.178767 0.0111586 0.0184565 -0.17736 0.0108611 0.0186188 -0.177334 0.0111871 0.0185563 -0.178917 0.0105249 0.0186431 -0.177289 0.0108745 0.0185673 -0.17815 0.0105326 0.0185789 -0.178217 0.010892 0.018577 -0.17909 0.0117755 0.0185599 -0.17955 0.0115659 0.018603 -0.179797 0.0113505 0.018786 -0.175772 0.0116411 0.018671 -0.176032 0.0116951 0.0185395 -0.176214 0.0116001 0.0186412 -0.17614 0.0114977 0.0187142 -0.176058 0.0118567 0.0183795 -0.176215 0.00968156 0.0162242 -0.184906 0.00960839 0.0166836 -0.184385 0.0122369 0.0185213 -0.182011 0.0120829 0.0177267 -0.182701 0.012055 0.0179679 -0.182657 0.0114154 0.0176501 -0.182672 0.0113694 0.0178871 -0.182641 0.0111535 0.0175704 -0.182723 0.0102278 0.0170131 -0.183267 0.0101093 0.0172749 -0.183313 0.00979213 0.0165255 -0.183957 0.0107346 0.0176688 -0.182838 0.0113184 0.0181022 -0.182539 0.00993033 0.017502 -0.18328 0.00976068 0.0169249 -0.183853 0.00939222 0.0169478 -0.184419 0.00960617 0.0165687 -0.184933 0.00939039 0.0168459 -0.184974 0.0121054 0.018101 -0.18261 0.0121078 0.0183624 -0.182385 0.0120756 0.0181865 -0.182551 0.0112671 0.0182754 -0.182375 0.0106175 0.0178855 -0.182758 0.0104872 0.0180542 -0.182612 0.00955267 0.0171694 -0.183861 0.00971457 0.0176644 -0.183171 0.00928019 0.0173275 -0.183799 0.00908696 0.0171039 -0.184408 0.0121684 0.0184092 -0.182328 0.0112202 0.0183906 -0.182166 0.0094906 0.0177405 -0.183001 0.0121487 0.0184793 -0.182175 0.0121944 0.0185263 -0.18194 0.0103571 0.0181573 -0.182413 0.0102409 0.0181839 -0.182183 0.00898715 0.0173738 -0.183676 0.00874874 0.0171232 -0.184355 0.00872554 0.0170053 -0.185066 0.0121607 0.0183857 -0.182363 0.0123821 0.0177219 -0.182789 0.0129596 0.0177033 -0.183131 0.0124238 0.0181135 -0.182696 0.0125283 0.0184048 -0.182435 0.0134771 0.0185027 -0.182552 0.0121781 0.0156378 -0.212516 0.0111323 0.0161821 -0.201254 0.0119558 0.0159164 -0.212533 0.0116345 0.0160704 -0.212554 0.0104567 0.0163349 -0.201319 0.0112782 0.016069 -0.212575 0.0113535 0.0159036 -0.201226 0.00907639 0.0170015 -0.185022 0.0108121 0.0163361 -0.201287 0.0257298 0.017745 -0.193825 0.0259187 0.0180369 -0.19361 0.0261745 0.0181495 -0.193312 0.0214242 0.0174544 -0.19031 0.0172656 0.017966 -0.186647 0.0214976 0.0178489 -0.190236 0.0130338 0.0180965 -0.183059 0.0132226 0.018388 -0.182847 0.0281014 0.0181001 -0.195045 0.0219418 0.018254 -0.189725 0.0216865 0.0181407 -0.190022 0.0174544 0.0182577 -0.186435 0.01583 0.017647 -0.2141 0.0159783 0.0177616 -0.214263 0.0161059 0.0177672 -0.214147 0.0157364 0.0172537 -0.213791 0.0156419 0.0172488 -0.213884 0.0158759 0.0175719 -0.213927 0.0150804 0.0169345 -0.214212 0.0157142 0.0174704 -0.21397 0.0143352 0.0169706 -0.21443 0.0142837 0.0171861 -0.214548 0.0150668 0.0171733 -0.214259 0.0150852 0.0173899 -0.21437 0.0151337 0.0175642 -0.214533 0.0142353 0.0174657 -0.214955 0.0152081 0.0176801 -0.214734 0.0135413 0.0166135 -0.214313 0.0140152 0.0165617 -0.214377 0.0132874 0.0169996 -0.214593 0.0142493 0.0173567 -0.21473 0.0130907 0.0170952 -0.215088 0.0142431 0.0175024 -0.215204 0.0136529 0.0163633 -0.214299 0.0129031 0.0162102 -0.213949 0.01272 0.0164442 -0.214017 0.0134144 0.0168342 -0.214415 0.0131751 0.0170902 -0.214827 0.0121398 0.0166244 -0.214641 0.0123084 0.0166676 -0.21439 0.0125116 0.0166045 -0.214172 0.0120288 0.016309 -0.21366 0.0130345 0.0159363 -0.213976 0.0125063 0.0159002 -0.213503 0.0122763 0.0157036 -0.213028 0.0120551 0.0159739 -0.213047 0.0115166 0.0162501 -0.214053 0.0117536 0.0163436 -0.213841 0.011129 0.0160009 -0.213374 0.0114209 0.0161382 -0.213239 0.0122948 0.0161523 -0.213541 0.0117506 0.0161286 -0.213123 0.0123717 0.0153694 -0.213067 0.0122573 0.01529 -0.212506 0.0281507 0.0181052 -0.194987 0.027955 0.0180399 -0.195216 0.0278948 0.017993 -0.195285 0.0278659 0.0179647 -0.195319 0.0284613 0.0178457 -0.195958 0.0277883 0.0178656 -0.195408 0.0276981 0.0176799 -0.195509 0.0283311 0.0175832 -0.196085 0.0276332 0.0173055 -0.195576 0.0289219 0.017194 -0.196669 0.0282742 0.0172709 -0.19612 0.0289944 0.0175152 -0.196641 0.0291427 0.0177816 -0.196514 0.0293416 0.0179477 -0.196309 0.0286443 0.0180166 -0.195759 0.0163463 0.0178073 -0.214258 0.0159447 0.0176535 -0.213993 0.0158174 0.0174765 -0.213871 0.0158077 0.0173142 -0.213748 0.015764 0.0170074 -0.213705 0.0296252 0.0170113 -0.198083 0.0296452 0.0173735 -0.197686 0.029574 0.0177102 -0.196993 0.0295573 0.0179853 -0.196061 0.0292987 0.0171009 -0.197095 0.0293815 0.0174371 -0.197084 0.0301801 0.0178054 -0.197568 0.0298402 0.0178691 -0.196839 0.0297022 0.017365 -0.19835 0.0298654 0.0176522 -0.197642 0.0295348 0.0174095 -0.199012 0.0299252 0.0176436 -0.198359 0.0303326 0.017861 -0.199326 0.0302465 0.0177974 -0.19838 0.0306023 0.017796 -0.198408 0.0291471 0.0174684 -0.199597 0.0292969 0.0177345 -0.199714 0.0297344 0.0176826 -0.199076 0.0300178 0.017843 -0.199188 0.0285763 0.0177434 -0.200452 0.026523 0.0177034 -0.202631 0.0284163 0.0173156 -0.200293 0.0284085 0.017174 -0.200283 0.0157733 0.0171524 -0.213714 0.0158661 0.0174623 -0.213804 0.0170085 0.0175813 -0.212728 0.0159338 0.0175741 -0.213868 0.0171977 0.0177545 -0.212907 0.0160736 0.0177156 -0.214 0.0263972 0.0174427 -0.202508 0.022907 0.017815 -0.20685 0.0267128 0.0178761 -0.202813 0.023131 0.0178738 -0.207062 0.0269372 0.0179343 -0.203025 0.0168824 0.0173213 -0.212607 0.0225915 0.0173817 -0.206548 0.0227174 0.0176421 -0.206669 0.0174212 0.0178143 -0.213118 0.0287442 0.0171712 -0.199927 0.0287965 0.0174856 -0.199965 0.0284506 0.0174825 -0.200329 0.0285104 0.0176348 -0.200388 0.0291349 0.01792 -0.200269 0.0287179 0.0178856 -0.200588 0.0295086 0.0179027 -0.199898 0.0289341 0.0177493 -0.200086 0.0290841 0.0171488 -0.199566 0.0384766 0.0156102 -0.234105 0.0386713 0.0158675 -0.233807 0.0390175 0.0160399 -0.234042 0.0393732 0.0160403 -0.234036 0.0393432 0.0160179 -0.233695 0.0396942 0.0158877 -0.234048 0.0396598 0.0158593 -0.233644 0.0384276 0.0157599 -0.234622 0.0383983 0.015266 -0.234149 0.0386473 0.0160199 -0.234596 0.0386975 0.0158864 -0.234067 0.0392813 0.0161958 -0.234707 0.0395801 0.0160796 -0.234825 0.0390633 0.0165463 -0.235784 0.0389503 0.0161746 -0.234625 0.0385746 0.0165377 -0.235425 0.0383265 0.0163793 -0.235331 0.0381258 0.0161448 -0.235315 0.0380025 0.0158691 -0.235381 0.0383311 0.0154419 -0.234701 0.0381421 0.0170323 -0.236221 0.0371324 0.0171223 -0.236221 0.0376275 0.016563 -0.235828 0.0373359 0.0173945 -0.236591 0.0364716 0.0177065 -0.236944 0.0372386 0.0172895 -0.236381 0.0370281 0.0169095 -0.236129 0.0364181 0.0173715 -0.23633 0.0388331 0.0165963 -0.235584 0.0379651 0.0169455 -0.236026 0.0377864 0.0167825 -0.235889 0.0363737 0.0171604 -0.236223 0.0363218 0.0169282 -0.236185 0.034902 0.0178108 -0.236038 0.0356902 0.017525 -0.236205 0.0364694 0.0176576 -0.236708 0.0355133 0.0178706 -0.236779 0.0355898 0.0178174 -0.23656 0.036451 0.0175424 -0.236497 0.0356505 0.0176987 -0.236362 0.0357054 0.0173115 -0.2361 0.0345041 0.0178208 -0.23573 0.0348103 0.0178816 -0.236152 0.0346598 0.0179288 -0.236337 0.0351135 0.0173704 -0.235767 0.0350747 0.0175198 -0.235818 0.0346889 0.0175285 -0.235508 0.0350482 0.0175888 -0.235853 0.0349439 0.0177646 -0.235985 0.0332654 0.015565 -0.203453 0.0357053 0.0156294 -0.217487 0.0333432 0.0159079 -0.20345 0.0384505 0.0155885 -0.233845 0.0359236 0.0159074 -0.217453 0.0389902 0.0160208 -0.233753 0.0362387 0.0160625 -0.217402 0.0365888 0.0160641 -0.217343 0.0369048 0.0159121 -0.217288 0.0172205 0.0177353 -0.221747 0.0215793 0.0177045 -0.225183 0.0299269 0.0178812 -0.232507 0.0301783 0.0177714 -0.2322 0.0213271 0.017813 -0.225491 0.0303632 0.0174789 -0.231977 0.0217644 0.0174119 -0.224958 0.0301851 0.017583 -0.201949 0.030004 0.0178755 -0.201618 0.0297284 0.0176182 -0.202311 0.0301083 0.017758 -0.201801 0.0297608 0.0175486 -0.202341 0.0298092 0.0173975 -0.202387 0.0298816 0.0179247 -0.201415 0.0308543 0.0177721 -0.201041 0.0308972 0.0177275 -0.201278 0.0319936 0.0174393 -0.20099 0.0329012 0.0170176 -0.201562 0.0337735 0.0166029 -0.201826 0.0309202 0.0176137 -0.201494 0.0319467 0.0174194 -0.201249 0.0327352 0.0169433 -0.201793 0.0335644 0.0166775 -0.202059 0.0318749 0.0173201 -0.201482 0.0317859 0.0171521 -0.201665 0.030921 0.0174415 -0.201668 0.0325599 0.0167802 -0.201963 0.0323991 0.0165502 -0.20205 0.0327583 0.0159297 -0.202423 0.0328813 0.0162245 -0.20246 0.0322744 0.0162844 -0.202041 0.0315962 0.016689 -0.201807 0.0316895 0.0169339 -0.201777 0.0308582 0.0169905 -0.201832 0.0308997 0.0172271 -0.201784 0.030231 0.0171283 -0.202089 0.0302273 0.0173665 -0.202048 0.033182 0.016004 -0.202926 0.033079 0.0164717 -0.202404 0.0336813 0.0164272 -0.20279 0.0333197 0.0166313 -0.202262 0.0335585 0.0161846 -0.203422 0.0333948 0.0162697 -0.202891 0.0338697 0.0163415 -0.203374 0.0342165 0.0163483 -0.203316 0.0339891 0.0164477 -0.202641 0.0170272 0.0177967 -0.221983 0.0172798 0.0176889 -0.221674 0.0166076 0.0175463 -0.220934 0.0167376 0.017282 -0.220801 0.0175331 0.0169967 -0.221366 0.0174649 0.0173962 -0.221448 0.0173845 0.0175618 -0.221546 0.0159822 0.0172012 -0.22019 0.015631 0.0176333 -0.220534 0.0164256 0.017716 -0.22114 0.0292668 0.0179534 -0.201877 0.0294437 0.01791 -0.202043 0.0294281 0.0178546 -0.202239 0.0295526 0.0178405 -0.202146 0.0294444 0.017842 -0.202254 0.0296026 0.0177946 -0.202193 0.0296354 0.0175971 -0.20243 0.0296572 0.0175496 -0.20245 0.0297339 0.0172335 -0.202516 0.0160582 0.0168766 -0.220162 0.015831 0.0174691 -0.220322 0.0153568 0.0173819 -0.2198 0.015301 0.017039 -0.219116 0.0155577 0.0171068 -0.219709 0.0150712 0.0173202 -0.219159 0.0147454 0.0174683 -0.219235 0.0150816 0.0175373 -0.219956 0.0153292 0.0166781 -0.218455 0.0150088 0.0173169 -0.218458 0.0143076 0.0174459 -0.218408 0.0154067 0.0171034 -0.217806 0.015244 0.0170351 -0.218464 0.0148929 0.0175334 -0.217635 0.0146731 0.0174641 -0.218438 0.0145687 0.0175357 -0.217491 0.0157873 0.0172096 -0.217224 0.0154954 0.0167601 -0.2178 0.0156196 0.0174772 -0.217114 0.0151918 0.0173792 -0.217747 0.0285624 0.0175295 -0.203612 0.0297376 0.0171525 -0.202518 0.0169631 0.0174008 -0.215922 0.0280604 0.0179321 -0.203145 0.0226406 0.0177393 -0.209473 0.0228536 0.0174467 -0.20967 0.0283496 0.0178218 -0.203416 0.0188348 0.0177051 -0.213511 0.0168705 0.0175663 -0.215836 0.0190478 0.0174124 -0.21371 0.0191267 0.0170135 -0.213781 0.0164577 0.0169711 -0.216614 0.0170314 0.0171491 -0.215985 0.0163955 0.0172868 -0.216585 0.0162486 0.017551 -0.216471 0.0169395 0.0174522 -0.2159 0.01675 0.0176935 -0.215723 0.0167321 0.0177072 -0.215706 0.0160408 0.0177206 -0.216291 0.0153934 0.0176414 -0.216931 0.0158673 0.0168854 -0.217241 0.0349373 0.0176705 -0.243078 0.0349552 0.0177162 -0.2431 0.0348681 0.0172744 -0.242999 0.0177347 0.0180643 -0.25658 0.0178893 0.0183292 -0.256768 0.0313143 0.0180346 -0.246287 0.0271933 0.01824 -0.25002 0.0184628 0.0184611 -0.256869 0.018219 0.0183476 -0.256562 0.0181147 0.0184646 -0.25705 0.0179157 0.0183561 -0.2568 0.0180381 0.0180558 -0.256342 0.0267683 0.0178355 -0.24949 0.026949 0.0181275 -0.249712 0.0350161 0.0178353 -0.243175 0.0348713 0.0173524 -0.243002 0.031064 0.0173468 -0.245985 0.0311336 0.0177425 -0.246064 0.0179671 0.0176616 -0.256266 0.0181594 0.0184697 -0.257107 0.0161198 0.0180685 -0.257843 0.0177276 0.0180444 -0.256572 0.0162862 0.0183588 -0.25806 0.035621 0.0175373 -0.242489 0.0351313 0.0179749 -0.243319 0.035929 0.0179695 -0.242815 0.0361264 0.0180233 -0.243059 0.0353627 0.0180742 -0.243611 0.0130789 0.0173265 -0.259457 0.0144814 0.0179877 -0.259121 0.0146117 0.0183406 -0.259515 0.013807 0.0182422 -0.259882 0.0145023 0.0182196 -0.259348 0.014421 0.0180464 -0.259214 0.0137667 0.0181226 -0.259685 0.0144405 0.0176132 -0.259034 0.0143746 0.0178357 -0.259125 0.0143671 0.0176053 -0.259089 0.0137672 0.0175108 -0.25938 0.0138632 0.018299 -0.260102 0.012871 0.0180554 -0.259965 0.0129119 0.0179408 -0.259756 0.0137457 0.0179504 -0.259527 0.0147398 0.018399 -0.259701 0.0146281 0.0182748 -0.259334 0.0129634 0.0177702 -0.259593 0.0137459 0.0177404 -0.259422 0.0130208 0.017559 -0.25949 0.0135873 0.0174712 -0.259424 0.012276 0.0172647 -0.259281 0.0120242 0.0176496 -0.259509 0.0118932 0.0177516 -0.259709 0.0117773 0.0177766 -0.25994 0.0128445 0.0181033 -0.260201 0.0116677 0.0168942 -0.258824 0.0121565 0.0174814 -0.259361 0.0110675 0.0173666 -0.259143 0.0112866 0.0172872 -0.258973 0.0114957 0.0171226 -0.258862 0.0113264 0.0161652 -0.258146 0.0117802 0.0166316 -0.258864 0.0109339 0.0165169 -0.257152 0.0109394 0.0166082 -0.257714 0.00999548 0.0166758 -0.257864 0.0105551 0.0170265 -0.258468 0.0103043 0.0167906 -0.257781 0.0108435 0.0169753 -0.258345 0.0111092 0.0168144 -0.25828 0.0106391 0.0167666 -0.257728 0.0113103 0.0165689 -0.258283 0.0111511 0.016344 -0.257743 0.0361184 0.0170706 -0.241767 0.036016 0.0178135 -0.238941 0.0356623 0.0173808 -0.239301 0.0358138 0.0176515 -0.239161 0.035589 0.0170504 -0.239334 0.0357629 0.0170149 -0.239494 0.0362133 0.0172874 -0.24001 0.0361314 0.0169369 -0.240027 0.0362457 0.0177835 -0.23914 0.0370497 0.0177115 -0.239641 0.0369515 0.017707 -0.240564 0.0360131 0.0176245 -0.239342 0.0367243 0.0177184 -0.239795 0.0366219 0.0175577 -0.240606 0.0368939 0.0177651 -0.241395 0.0358414 0.0173513 -0.239468 0.0364253 0.0175668 -0.239928 0.0363574 0.0173346 -0.241318 0.0362722 0.0169905 -0.241337 0.0363928 0.0172767 -0.24064 0.0360116 0.0171123 -0.241957 0.0360953 0.0174384 -0.241958 0.0365792 0.0176109 -0.241339 0.0368288 0.0178987 -0.24235 0.0372397 0.0177669 -0.241475 0.0357511 0.0177986 -0.242615 0.0362838 0.0177068 -0.242034 0.0365436 0.0178698 -0.242173 0.011617 0.0160935 -0.253051 0.0111466 0.0162408 -0.257189 0.0106241 0.0166744 -0.257107 0.0110924 0.0165272 -0.252983 0.0107437 0.0165358 -0.252947 0.0102765 0.0166832 -0.257063 0.0104244 0.0163938 -0.252919 0.0125036 0.0157399 -0.240434 0.0122864 0.0160168 -0.240419 0.0114034 0.0163697 -0.25302 0.0119713 0.0161734 -0.240403 0.0116194 0.0161794 -0.240388 0.011299 0.0160336 -0.240378 0.0126571 0.0155505 -0.224929 0.012436 0.0158286 -0.224933 0.0353363 0.01793 -0.238015 0.0351294 0.0178882 -0.238265 0.0344497 0.017953 -0.237358 0.0340895 0.0177225 -0.237803 0.0340322 0.017614 -0.237875 0.0339503 0.0172947 -0.23798 0.0348157 0.0174534 -0.238617 0.0347614 0.0171333 -0.238659 0.0349456 0.0177199 -0.238478 0.0362326 0.0178377 -0.23868 0.0125125 0.0162976 -0.223664 0.0115811 0.015953 -0.224066 0.0121163 0.0159835 -0.224938 0.0122081 0.0160657 -0.22429 0.0133137 0.0165211 -0.223194 0.0139785 0.0168766 -0.222851 0.0125119 0.01591 -0.224346 0.012773 0.0161396 -0.22377 0.0127319 0.015643 -0.224348 0.0129804 0.0158936 -0.223797 0.013101 0.0155998 -0.223739 0.0134822 0.0162947 -0.223262 0.0140924 0.01666 -0.222949 0.0148122 0.016705 -0.222893 0.0154379 0.0168913 -0.223019 0.0147501 0.0169404 -0.222852 0.0154181 0.0171265 -0.222973 0.0154255 0.0173404 -0.222863 0.0146968 0.0171535 -0.222739 0.0146575 0.0173238 -0.222565 0.0120037 0.0162656 -0.22329 0.0137626 0.0171417 -0.222459 0.0146337 0.0174771 -0.222103 0.0155923 0.0176812 -0.222275 0.0163028 0.0177298 -0.22291 0.0155167 0.0176309 -0.222498 0.0146357 0.0174352 -0.222346 0.0138644 0.0170431 -0.222681 0.0131245 0.0166833 -0.223045 0.0129396 0.0167601 -0.222835 0.0122414 0.0163421 -0.223494 0.0118772 0.016081 -0.224191 0.011761 0.0159847 -0.224945 0.0154594 0.0175138 -0.2227 0.0342545 0.0178952 -0.237598 0.0342126 0.0178647 -0.23765 0.0339801 0.0174617 -0.237941 0.0295182 0.0170981 -0.234378 0.0339435 0.0171531 -0.237991 0.0300244 0.0178981 -0.233747 0.0212303 0.0177624 -0.22697 0.0298294 0.0178397 -0.233987 0.0296645 0.0176669 -0.234191 0.0209563 0.0173292 -0.227309 0.0295552 0.0174063 -0.234329 0.0214246 0.0178219 -0.226731 0.0169307 0.0177409 -0.223462 0.0210657 0.0175893 -0.227173 0.0161726 0.0176128 -0.223079 0.0160005 0.0169792 -0.223342 0.0160142 0.0172193 -0.223305 0.0160734 0.0174373 -0.223215 0.0166568 0.0173078 -0.223799 0.0167663 0.0175676 -0.223664 0.0161185 0.0175315 -0.223152 0.0464342 0.0173165 -0.297124 0.0464556 0.0172713 -0.29673 0.0468245 0.0172485 -0.296717 0.0456049 0.0167881 -0.297692 0.0457671 0.0165465 -0.297172 0.0458611 0.0168951 -0.297115 0.0461001 0.0171709 -0.297098 0.0465902 0.0175142 -0.297821 0.0467938 0.0173015 -0.297187 0.0462732 0.0175029 -0.297677 0.0458363 0.0179136 -0.298341 0.0455876 0.0177638 -0.298215 0.0459668 0.0173562 -0.297601 0.045729 0.0171019 -0.297606 0.0453703 0.017536 -0.298182 0.0452185 0.0172659 -0.298247 0.0452627 0.0185433 -0.299107 0.0441126 0.0185733 -0.29886 0.0435009 0.019466 -0.299553 0.04439 0.0190354 -0.299353 0.0435277 0.0194107 -0.299328 0.0443177 0.018934 -0.299134 0.0435285 0.0192964 -0.299125 0.0442221 0.0187747 -0.298964 0.0435032 0.019133 -0.29896 0.0460774 0.0179621 -0.29854 0.0451106 0.0184626 -0.298886 0.0449398 0.0183079 -0.298727 0.0447713 0.0180983 -0.298649 0.043454 0.0189343 -0.298849 0.0431053 0.0188495 -0.29872 0.043385 0.0187171 -0.2988 0.0426142 0.0197409 -0.299238 0.0418567 0.0198968 -0.298667 0.0421001 0.0197511 -0.298431 0.042777 0.0195531 -0.298872 0.0422899 0.0193322 -0.298207 0.0428245 0.0191869 -0.298628 0.0422586 0.01947 -0.298253 0.042817 0.0193862 -0.298729 0.0427076 0.0196745 -0.299046 0.0422985 0.019113 -0.29817 0.0402055 0.0198666 -0.296333 0.0413209 0.0195801 -0.297209 0.041134 0.0198674 -0.297388 0.0399332 0.0200021 -0.29657 0.0413823 0.0192051 -0.297137 0.04214 0.0197042 -0.298389 0.0422357 0.0195345 -0.298282 0.0420104 0.0198281 -0.298521 0.0420151 0.0159138 -0.256828 0.0403589 0.0157136 -0.245698 0.0422398 0.0161938 -0.256791 0.0405815 0.0159931 -0.24566 0.0425638 0.0163452 -0.256742 0.0412581 0.0161399 -0.245552 0.044423 0.0160449 -0.27727 0.0419355 0.0155622 -0.256847 0.0445047 0.0163995 -0.277253 0.0429212 0.0163372 -0.256692 0.0447345 0.0166806 -0.277223 0.0450948 0.0167762 -0.281033 0.0454266 0.0169249 -0.281 0.0450649 0.0168299 -0.277187 0.0454272 0.0168163 -0.277151 0.0448637 0.0164949 -0.28106 0.0458782 0.0168429 -0.296759 0.046116 0.0171258 -0.296745 0.0471438 0.0170621 -0.296708 0.0457901 0.01691 -0.280968 0.0401777 0.0198903 -0.296357 0.0359495 0.0193988 -0.291169 0.0404008 0.0195819 -0.296171 0.0177912 0.0185779 -0.270773 0.0179079 0.0182022 -0.270684 0.017511 0.0189482 -0.271008 0.0357336 0.01969 -0.291349 0.0280751 0.0194743 -0.283305 0.0283677 0.0193583 -0.28305 0.0176065 0.0188863 -0.270925 0.0230595 0.0188216 -0.276644 0.0228429 0.0191129 -0.276825 0.028584 0.019067 -0.282869 0.023144 0.0184294 -0.276584 0.0286685 0.0186752 -0.28281 0.0403935 0.0195991 -0.296177 0.0399425 0.0159808 -0.244754 0.0368279 0.0179368 -0.243978 0.037042 0.0179176 -0.243565 0.0366871 0.0179857 -0.243787 0.0370718 0.0174311 -0.244401 0.0372982 0.0175814 -0.244128 0.0369924 0.0177394 -0.244231 0.0373177 0.0173674 -0.244241 0.0380929 0.0173284 -0.243873 0.0381167 0.0174972 -0.243687 0.0372418 0.0177541 -0.243968 0.0381134 0.0176043 -0.243459 0.0371537 0.0178697 -0.243774 0.0388485 0.0167187 -0.244046 0.0379759 0.0168771 -0.24405 0.0380443 0.0171145 -0.243999 0.0390874 0.0171024 -0.24374 0.0391805 0.01719 -0.243494 0.0380834 0.017639 -0.24321 0.0395111 0.0162973 -0.24435 0.0396919 0.0165314 -0.244265 0.0389722 0.0169388 -0.243932 0.039889 0.0166901 -0.244089 0.0400729 0.0167499 -0.24385 0.0398148 0.0156751 -0.244713 0.0401533 0.0162332 -0.244697 0.0404104 0.0163885 -0.244551 0.040669 0.0164195 -0.244342 0.0401128 0.0154449 -0.245171 0.0402135 0.015781 -0.245202 0.040435 0.016052 -0.245162 0.0410535 0.016211 -0.244908 0.0409029 0.0161455 -0.245607 0.0407343 0.0162052 -0.245057 0.0415753 0.0159776 -0.245505 0.0413306 0.0160681 -0.244744 0.0173131 0.0190015 -0.271181 0.0169511 0.0187254 -0.269947 0.0177398 0.0187435 -0.270812 0.0170819 0.0184688 -0.269841 0.0171323 0.018168 -0.26981 0.0132088 0.0182963 -0.265774 0.0129811 0.0184627 -0.26594 0.016759 0.0189001 -0.27011 0.0127341 0.0185045 -0.26615 0.0165337 0.0189673 -0.270307 0.0359966 0.0174374 -0.245276 0.0355093 0.018097 -0.24464 0.0362779 0.0179996 -0.244456 0.0369457 0.0178201 -0.244154 0.0364248 0.0178258 -0.244664 0.0365331 0.0172668 -0.244871 0.0370295 0.0176462 -0.244299 0.0365143 0.0175688 -0.24481 0.0129673 0.0174099 -0.264169 0.0129672 0.0174512 -0.264525 0.0128844 0.0177979 -0.264496 0.013379 0.0180332 -0.265681 0.0125447 0.0183346 -0.265276 0.0130394 0.0179049 -0.265133 0.0128323 0.0181751 -0.265177 0.0129374 0.0177469 -0.263849 0.0127149 0.0180276 -0.263789 0.012659 0.0180752 -0.264487 0.012336 0.018228 -0.264499 0.0127238 0.0181952 -0.262965 0.0123942 0.0181776 -0.263708 0.0132784 0.0174155 -0.263264 0.0131991 0.0177638 -0.263239 0.013001 0.0180423 -0.263132 0.0134956 0.0181082 -0.262592 0.0360027 0.0172972 -0.245287 0.0194114 0.0184225 -0.257665 0.0181245 0.018509 -0.258278 0.0185833 0.0180202 -0.25888 0.0184777 0.0182821 -0.258736 0.0359678 0.0176065 -0.245235 0.0358615 0.0178677 -0.245094 0.0350898 0.0181048 -0.244969 0.0355483 0.0176144 -0.245564 0.0268175 0.0178017 -0.252417 0.0197118 0.0176781 -0.258075 0.0186117 0.0178468 -0.258923 0.0196785 0.0179887 -0.258021 0.0267116 0.0180633 -0.252274 0.035442 0.0178756 -0.245423 0.0311828 0.0177025 -0.248991 0.0359167 0.0177606 -0.245166 0.0195728 0.0182506 -0.257877 0.0265502 0.0182355 -0.252064 0.0309154 0.0181362 -0.248639 0.0310767 0.0179639 -0.248849 0.0352808 0.018048 -0.245213 0.0357408 0.0180102 -0.244936 0.0307242 0.0181925 -0.248393 0.0186165 0.0177095 -0.258934 0.0161837 0.0177066 -0.260844 0.0161352 0.0180269 -0.260797 0.0160121 0.0182936 -0.260652 0.0185314 0.0181777 -0.258809 0.015835 0.018462 -0.260434 0.0183559 0.0184251 -0.258576 0.0132927 0.0182675 -0.262362 0.0136491 0.0178354 -0.262739 0.0090341 0.0170353 -0.268986 0.00912402 0.0167442 -0.269413 0.00891326 0.017021 -0.269357 0.0084239 0.0172041 -0.268736 0.00813783 0.0170669 -0.268591 0.0082607 0.0171831 -0.269213 0.00932772 0.0164234 -0.269039 0.00924224 0.0167615 -0.269044 0.00909619 0.017325 -0.268339 0.00874286 0.0171929 -0.268877 0.0100853 0.0172044 -0.268094 0.00953512 0.0169059 -0.268563 0.00993314 0.0174431 -0.267992 0.00934139 0.0171641 -0.268492 0.00884143 0.017361 -0.268131 0.00947294 0.0176415 -0.267294 0.00960369 0.0176783 -0.267563 0.0104936 0.0180052 -0.267276 0.00976466 0.0176089 -0.267807 0.0110743 0.017365 -0.267855 0.0107481 0.0175163 -0.267845 0.0121048 0.0179862 -0.268049 0.0114438 0.0177817 -0.267831 0.0114076 0.0180019 -0.267703 0.0121229 0.0182035 -0.267932 0.0114081 0.01828 -0.267278 0.0122662 0.0184901 -0.267563 0.0127196 0.0183492 -0.268386 0.0121785 0.018377 -0.267765 0.0105643 0.0179127 -0.267525 0.0106526 0.0177431 -0.267722 0.0113953 0.018174 -0.267512 0.0121259 0.017746 -0.268105 0.0126578 0.0181329 -0.268478 0.00300844 0.0179649 -0.286942 0.000408816 0.0182285 -0.293662 0.00335025 0.017984 -0.287076 0.00387674 0.0175549 -0.287301 0.00426475 0.017164 -0.286535 0.00860558 0.0171774 -0.269285 0.00545448 0.0176687 -0.280028 0.00794555 0.0170369 -0.269154 0.00515415 0.0175109 -0.279942 0.00366159 0.0178369 -0.287204 0.005799 0.0176761 -0.280134 0.00610959 0.0175246 -0.280237 0.00632315 0.0172449 -0.280316 0.00639629 0.0168939 -0.280355 0.0168165 0.0188939 -0.272738 0.0149791 0.0188904 -0.270394 0.0146293 0.0181492 -0.270755 0.0146651 0.0184575 -0.270702 0.0152086 0.018948 -0.270186 0.0129796 0.0186398 -0.268105 0.014788 0.018718 -0.270575 0.0128303 0.0185235 -0.268258 0.0127694 0.0184427 -0.268326 -0.00214726 0.0183126 -0.299513 -0.000755875 0.01827 -0.296618 -0.0010612 0.0184071 -0.296437 -0.00234746 0.0185975 -0.299351 0.000933519 0.0178024 -0.293936 -0.000547288 0.017985 -0.29676 0.000718041 0.0180868 -0.293821 7.38144e-05 0.0181965 -0.293497 -0.00139413 0.0183653 -0.296257 0.0224225 0.01924 -0.278766 0.0169929 0.0190165 -0.272577 0.016734 0.0187909 -0.272815 0.0222249 0.0190686 -0.278948 0.0220951 0.018806 -0.279073 0.0166681 0.0185467 -0.272883 0.0294605 0.0191376 -0.287373 0.0295905 0.0194004 -0.287247 0.0300228 0.0196242 -0.286855 0.0226565 0.019293 -0.278556 0.0368259 0.0194719 -0.295673 0.0369561 0.0197348 -0.295547 0.0371544 0.019906 -0.295364 0.0297884 0.0195717 -0.287065 -0.000364029 0.02126 -0.303056 -0.000346794 0.0209047 -0.302721 -0.000322399 0.0205623 -0.302642 -0.000500598 0.0205384 -0.30264 -0.000526012 0.0207475 -0.302667 -0.00122211 0.0205668 -0.302494 -0.000623459 0.0213105 -0.303244 -0.00159512 0.0211145 -0.303 -0.00322209 0.0200776 -0.301527 -0.00297113 0.0200779 -0.301407 -0.00328491 0.0193214 -0.300324 -0.000603372 0.0212337 -0.303047 -0.00149798 0.0210447 -0.302817 -0.0023778 0.0206399 -0.302216 -0.00271322 0.019998 -0.30134 -0.000552869 0.0209419 -0.302748 -0.000579276 0.0211079 -0.302878 -0.00130424 0.0207603 -0.302554 -0.00139854 0.0209236 -0.302665 -0.00219456 0.0205331 -0.302101 -0.00247951 0.0198473 -0.301335 -0.00202516 0.0203747 -0.302036 -0.00188495 0.020179 -0.302025 -0.00229826 0.0196442 -0.301392 -0.00231112 0.0181609 -0.300102 -0.00246053 0.0189279 -0.300548 -0.00266188 0.0191532 -0.300409 -0.00286218 0.0188828 -0.299619 -0.00295349 0.0192924 -0.30033 -0.00354676 0.018694 -0.299512 -0.00359881 0.0192352 -0.300393 -0.00235412 0.0184899 -0.29994 -0.00255183 0.0187489 -0.299767 -0.00264616 0.0187311 -0.299149 -0.0029744 0.0186826 -0.298955 -0.00321914 0.0188631 -0.299528 0.037406 0.0192108 -0.29672 0.0372527 0.0198099 -0.299927 0.0377547 0.0199081 -0.299075 0.0375859 0.0196494 -0.299038 0.0372039 0.0197009 -0.299902 0.0374967 0.020087 -0.300064 0.0380046 0.0200816 -0.29914 0.0376068 0.0201478 -0.300129 0.0381593 0.0200156 -0.297807 0.0375237 0.0193446 -0.299035 0.037662 0.0192749 -0.297867 0.0378977 0.019843 -0.297829 0.0376207 0.0197831 -0.296607 0.0374594 0.0195213 -0.296685 0.0377229 0.0195827 -0.29785 0.0376099 0.0193225 -0.298673 0.0373891 0.0199581 -0.295154 0.0381529 0.0200099 -0.29638 0.0378646 0.0199549 -0.2965 0.00530776 0.0211645 -0.302799 0.03429 0.0199198 -0.301643 0.0253572 0.0205159 -0.302557 0.0343057 0.0202101 -0.301917 0.0343207 0.0203316 -0.302298 0.025343 0.0203871 -0.302188 0.0253292 0.0200985 -0.301924 0.0163805 0.0203565 -0.302204 0.0163997 0.020643 -0.302458 -0.000361546 0.0211808 -0.302939 -0.000359537 0.0211337 -0.302886 -0.000350638 0.0209672 -0.302754 -0.000337961 0.0207722 -0.302671 0.0253189 0.0197192 -0.301828 0.00528248 0.02088 -0.302553 0.0378326 0.0201975 -0.300266 0.0378362 0.0201975 -0.300267 0.037406 0.0200135 -0.300012 0.036708 0.0201287 -0.300987 0.0371491 0.0194453 -0.29988 0.0372449 0.0197949 -0.299922 0.0369645 0.020243 -0.301282 0.03573 0.0202904 -0.302016 0.0355873 0.0201726 -0.301657 0.0371469 0.0193982 -0.299881 0.0365163 0.0198371 -0.300778 0.0354779 0.0198817 -0.3014 0.0354296 0.0194915 -0.30131 0.0342776 0.0195331 -0.301544 0.0358615 -0.0178735 -0.245094 0.0195728 -0.0182563 -0.257877 0.0307242 -0.0181983 -0.248393 0.0309154 -0.0181419 -0.248639 0.0265502 -0.0182412 -0.252064 0.0263588 -0.0182971 -0.251818 0.0183163 -0.0184598 -0.258524 0.0194114 -0.0184283 -0.257665 0.0352808 -0.0180538 -0.245213 0.0355093 -0.0181028 -0.24464 0.0268175 -0.0178075 -0.252417 0.0267116 -0.0180691 -0.252274 0.0310767 -0.0179696 -0.248849 0.0355483 -0.0176202 -0.245564 0.035442 -0.0178814 -0.245423 0.0196785 -0.0179945 -0.258021 0.0311828 -0.0177083 -0.248991 0.0359966 -0.0174432 -0.245276 0.0362779 -0.0180054 -0.244456 0.0357408 -0.018016 -0.244936 0.0364248 -0.0178315 -0.244664 0.0359167 -0.0177663 -0.245166 0.0359678 -0.0176123 -0.245235 0.0365331 -0.0172726 -0.244871 0.0365143 -0.0175745 -0.24481 0.0182094 -0.0185063 -0.258386 0.015835 -0.0184678 -0.260434 0.0184134 -0.0183752 -0.258651 0.0161352 -0.0180327 -0.260797 0.0184777 -0.0182878 -0.258736 0.0161837 -0.0177124 -0.260844 0.0185656 -0.0180901 -0.258856 0.0186165 -0.0177152 -0.258934 0.0137244 -0.0175059 -0.262774 0.0160121 -0.0182994 -0.260652 0.0395213 -0.0159143 -0.244437 0.0403192 -0.0157268 -0.245508 0.0403589 -0.0157193 -0.245698 0.0405419 -0.0160053 -0.24547 0.0405815 -0.0159988 -0.24566 0.0408579 -0.0161578 -0.245396 0.0409029 -0.0161512 -0.245607 0.0400254 -0.0155148 -0.245006 0.0402348 -0.0153784 -0.245503 0.0401361 -0.0158413 -0.245045 0.0403556 -0.0161064 -0.245 0.041204 -0.0161538 -0.245303 0.0412002 -0.0161444 -0.244513 0.0409429 -0.0162737 -0.244707 0.0402752 -0.0166457 -0.243986 0.0406425 -0.0162602 -0.24488 0.039851 -0.0164369 -0.244387 0.0390371 -0.0162725 -0.244163 0.0390293 -0.0166181 -0.244102 0.0396588 -0.0161978 -0.244463 0.0391692 -0.0168409 -0.243993 0.0400678 -0.0165945 -0.244219 0.0395032 -0.0170746 -0.243285 0.040441 -0.0165827 -0.243724 0.0385337 -0.0174878 -0.243167 0.0385292 -0.0174637 -0.243427 0.0394221 -0.0170846 -0.243557 0.0393059 -0.0170032 -0.243804 0.0384956 -0.0173628 -0.243664 0.0384367 -0.0171958 -0.243856 0.0389039 -0.016363 -0.244116 0.0380192 -0.016863 -0.244044 0.0383586 -0.0169805 -0.24398 0.0370654 -0.0174935 -0.24438 0.0370295 -0.017652 -0.244299 0.0369924 -0.0177452 -0.244231 0.03686 -0.0179194 -0.244024 0.0376426 -0.0177529 -0.243568 0.0376872 -0.0176407 -0.243782 0.0377028 -0.0174698 -0.243958 0.0376436 -0.017021 -0.244135 0.0376878 -0.0172565 -0.24408 0.0133321 -0.0174304 -0.263185 0.0130599 -0.0180548 -0.263046 0.0136491 -0.0178412 -0.262739 0.0134956 -0.018114 -0.262592 0.0127918 -0.0182086 -0.262869 0.0132927 -0.0182733 -0.262362 0.0129665 -0.0177507 -0.263744 0.0132527 -0.017777 -0.263159 0.0125017 -0.0182078 -0.262661 0.0128794 -0.0177928 -0.264407 0.0126531 -0.018071 -0.26439 0.0127465 -0.0180315 -0.263676 0.0124303 -0.0181816 -0.263579 0.0128088 -0.0181709 -0.265121 0.012517 -0.0183298 -0.265213 0.012328 -0.018223 -0.26439 0.0134634 -0.0177231 -0.265675 0.013379 -0.018039 -0.265681 0.0131064 -0.0175673 -0.2651 0.0130182 -0.0179 -0.265081 0.0132088 -0.0183021 -0.265774 0.0127341 -0.0185103 -0.26615 0.012197 -0.018347 -0.26534 0.0465509 -0.0168644 -0.286313 0.0458782 -0.0168487 -0.296759 0.0460296 -0.0170929 -0.294673 0.046368 -0.017239 -0.294655 0.046116 -0.0171315 -0.296745 0.0467361 -0.0172174 -0.294639 0.0468245 -0.0172542 -0.296717 0.0470554 -0.0170328 -0.294628 0.0446008 -0.0160965 -0.279107 0.0457081 -0.0164512 -0.2947 0.0457928 -0.0168103 -0.294689 0.0452443 -0.0168817 -0.279027 0.0456071 -0.0168675 -0.278993 0.0433542 -0.0164775 -0.262524 0.0449132 -0.0167327 -0.279062 0.0446828 -0.0164515 -0.27909 0.0430286 -0.0163266 -0.26257 0.0427226 -0.015694 -0.262625 0.0428027 -0.0160463 -0.262606 0.0412581 -0.0161457 -0.245552 0.0437128 -0.0164681 -0.262477 0.0179079 -0.0182079 -0.270684 0.0170819 -0.0184746 -0.269841 0.0177398 -0.0187492 -0.270812 0.0176065 -0.0188921 -0.270925 0.0169511 -0.0187312 -0.269947 0.0129811 -0.0184685 -0.26594 0.0165337 -0.018973 -0.270307 0.016759 -0.0189059 -0.27011 0.0171323 -0.0181738 -0.26981 0.0444955 -0.0179778 -0.298715 0.0437043 -0.0185456 -0.29884 0.0422357 -0.0195403 -0.298282 0.0421473 -0.0198092 -0.298655 0.0422649 -0.0196855 -0.298512 0.0421001 -0.0197569 -0.298431 0.0423947 -0.0193148 -0.298314 0.0423495 -0.0195163 -0.298396 0.0420059 -0.0198779 -0.298812 0.042859 -0.0196806 -0.299356 0.0439842 -0.01928 -0.29961 0.0429337 -0.0196163 -0.299153 0.0429841 -0.0194965 -0.298969 0.0439755 -0.0192346 -0.299373 0.0430062 -0.0193305 -0.298818 0.0438771 -0.0189649 -0.298991 0.0431058 -0.0188551 -0.29872 0.0429982 -0.0191316 -0.298712 0.0429607 -0.0189155 -0.29866 0.0437966 -0.0187653 -0.298881 0.0447923 -0.0184197 -0.298798 0.0439386 -0.0191263 -0.29916 0.0450817 -0.0186613 -0.299183 0.0452545 -0.017663 -0.298303 0.0446357 -0.0182125 -0.298713 0.0454631 -0.0178858 -0.298346 0.0456955 -0.0180366 -0.298482 0.0459172 -0.0180931 -0.298689 0.044947 -0.0185754 -0.298961 0.0456773 -0.0171778 -0.297721 0.0459132 -0.0174265 -0.297722 0.0462102 -0.0175737 -0.297809 0.0467687 -0.0174787 -0.298166 0.0458378 -0.0169429 -0.297251 0.0455461 -0.016873 -0.297807 0.046514 -0.0175922 -0.297967 0.045793 -0.0164889 -0.296768 0.0460772 -0.0172136 -0.297235 0.0464556 -0.0172771 -0.29673 0.0464058 -0.0173593 -0.297275 0.0467563 -0.0173504 -0.297364 0.017511 -0.018954 -0.271008 0.0177912 -0.0185837 -0.270773 0.0398857 -0.0200127 -0.296611 0.0210018 -0.0190382 -0.274751 0.0280751 -0.0194801 -0.283305 0.0394166 -0.0198618 -0.295499 0.0399332 -0.0200078 -0.29657 0.0401777 -0.019896 -0.296357 0.0396323 -0.0195706 -0.295319 0.0283677 -0.019364 -0.28305 0.0212185 -0.0187468 -0.274569 0.028584 -0.0190727 -0.282869 0.0404778 -0.0192136 -0.296118 0.0408654 -0.0200059 -0.297632 0.0404008 -0.0195877 -0.296171 0.0413209 -0.0195858 -0.297209 0.0413823 -0.0192109 -0.297137 0.0420104 -0.0198339 -0.298521 0.04214 -0.01971 -0.298389 0.041134 -0.0198732 -0.297388 0.0402055 -0.0198724 -0.296333 0.0403935 -0.0196048 -0.296177 0.0422899 -0.019338 -0.298207 0.0422586 -0.0194757 -0.298253 0.0155986 -0.017688 -0.222277 0.0164517 -0.0177831 -0.222723 0.0154225 -0.0171332 -0.222974 0.0160142 -0.0172251 -0.223305 0.0160734 -0.017443 -0.223215 0.0161185 -0.0175372 -0.223152 0.0155225 -0.0176377 -0.2225 0.0145466 -0.0174158 -0.222346 0.0154647 -0.0175205 -0.222702 0.0145764 -0.0173053 -0.222566 0.0154303 -0.0173472 -0.222865 0.0146232 -0.0171353 -0.22274 0.0142835 -0.0164716 -0.222943 0.0137678 -0.0167811 -0.222931 0.0146827 -0.0169222 -0.222852 0.0136308 -0.0169464 -0.222765 0.0138994 -0.0165624 -0.223021 0.0130982 -0.0163866 -0.223377 0.0128823 -0.0165473 -0.22324 0.013504 -0.0170393 -0.222545 0.0124808 -0.0165762 -0.222806 0.0126663 -0.0166136 -0.223041 0.0121453 -0.0162823 -0.223633 0.0132832 -0.0161544 -0.22343 0.0129252 -0.0154278 -0.224042 0.0129135 -0.0158365 -0.223908 0.0130297 -0.0155354 -0.223847 0.0121163 -0.0159893 -0.224938 0.0124964 -0.0159004 -0.224405 0.011894 -0.0161945 -0.223441 0.0118541 -0.0160688 -0.224264 0.0124307 -0.0162443 -0.223791 0.0121895 -0.016056 -0.224355 0.012702 -0.0160868 -0.223888 0.0128089 -0.0153001 -0.224355 0.0127167 -0.0156315 -0.224405 0.0163028 -0.0177356 -0.22291 0.0161726 -0.0176186 -0.223079 0.0169307 -0.0177466 -0.223462 0.0166568 -0.0173135 -0.223799 0.012784 -0.0152487 -0.23101 0.0126571 -0.0155563 -0.224929 0.0124859 -0.0158717 -0.231003 0.012436 -0.0158344 -0.224933 0.011761 -0.0159904 -0.224945 0.0123482 -0.0155123 -0.244999 0.0127057 -0.015594 -0.231007 0.0122717 -0.015855 -0.244985 0.0120559 -0.0161316 -0.244964 0.0121678 -0.0160273 -0.231 0.0118137 -0.0160303 -0.230999 0.0117423 -0.0162887 -0.244941 0.0113916 -0.0162959 -0.244919 0.0110714 -0.0161519 -0.244903 0.0300244 -0.0179038 -0.233747 0.0340322 -0.0176198 -0.237875 0.0296645 -0.0176727 -0.234191 0.0298294 -0.0178455 -0.233987 0.0339801 -0.0174674 -0.237941 0.0339503 -0.0173005 -0.23798 0.0339435 -0.0171588 -0.237991 0.0295552 -0.0174121 -0.234329 0.0210657 -0.017595 -0.227173 0.0212303 -0.0177681 -0.22697 0.0209186 -0.0170277 -0.227357 0.0209563 -0.0173349 -0.227309 0.0167663 -0.0175734 -0.223664 0.0102765 -0.0166889 -0.257063 0.0102639 -0.0166964 -0.257192 0.0112503 -0.0160541 -0.257882 0.0111628 -0.0163727 -0.257813 0.0112105 -0.0159136 -0.25732 0.0111466 -0.0162465 -0.257189 0.0113272 -0.016172 -0.258148 0.0118962 -0.0170582 -0.259038 0.012496 -0.0173716 -0.259375 0.0132161 -0.0173765 -0.259461 0.00994354 -0.0165563 -0.25718 0.0100197 -0.0167112 -0.257966 0.0103243 -0.0168204 -0.257871 0.0112155 -0.0175403 -0.259628 0.0121847 -0.017862 -0.259824 0.0130487 -0.0181561 -0.260208 0.0111361 -0.0162539 -0.257288 0.0114253 -0.0166941 -0.258501 0.0131654 -0.017608 -0.259497 0.0138512 -0.0179745 -0.259496 0.0135873 -0.017477 -0.259424 0.0138439 -0.0177645 -0.259393 0.0139327 -0.0182668 -0.259845 0.0147094 -0.0183548 -0.259445 0.0106241 -0.0166802 -0.257107 0.0109873 -0.0170946 -0.258597 0.0107241 -0.0171573 -0.258741 0.0113821 -0.0175371 -0.259409 0.0130586 -0.0181057 -0.259974 0.0138817 -0.0181468 -0.259651 0.013083 -0.0179897 -0.259766 0.0131197 -0.0178187 -0.259602 0.0123952 -0.0175861 -0.259464 0.0117439 -0.0172809 -0.259095 0.0122878 -0.0177552 -0.259619 0.0115655 -0.0174471 -0.259224 0.0112331 -0.0169323 -0.258513 0.0109517 -0.0166346 -0.257787 0.0109232 -0.0165292 -0.257252 0.0106546 -0.0167932 -0.257807 0.0109339 -0.0165227 -0.257152 0.0106127 -0.0166867 -0.257217 0.0138604 -0.0175349 -0.259351 0.014503 -0.0180604 -0.259155 0.0347614 -0.0171391 -0.238659 0.0348157 -0.0174592 -0.238617 0.0340895 -0.0177283 -0.237803 0.0349456 -0.0177257 -0.238478 0.0351294 -0.0178939 -0.238265 0.0342126 -0.0178705 -0.23765 0.0342545 -0.0179009 -0.237598 0.0353363 -0.0179357 -0.238015 0.036016 -0.0178193 -0.238941 0.0358138 -0.0176573 -0.239161 0.0356623 -0.0173865 -0.239301 0.0160619 -0.0176877 -0.257761 0.0181594 -0.0184754 -0.257107 0.0181147 -0.0184704 -0.25705 0.0165197 -0.0184863 -0.25836 0.0178893 -0.018335 -0.256768 0.0161198 -0.0180742 -0.257843 0.0177347 -0.0180701 -0.25658 0.0145916 -0.0182338 -0.259283 0.0162862 -0.0183645 -0.25806 0.0144814 -0.0179935 -0.259121 0.0144512 -0.0178495 -0.259069 0.0148464 -0.0184131 -0.259624 0.0146281 -0.0182806 -0.259334 0.035621 -0.0175431 -0.242489 0.0357548 -0.0171934 -0.242281 0.0361346 -0.0170692 -0.241734 0.0362206 -0.0174024 -0.241725 0.0363948 -0.0173138 -0.241091 0.035929 -0.0179753 -0.242815 0.0370214 -0.0178515 -0.242034 0.0373037 -0.0177388 -0.241158 0.0369468 -0.0177442 -0.241117 0.0357511 -0.0178043 -0.242615 0.0361957 -0.0179411 -0.242588 0.0359836 -0.0177729 -0.242409 0.0367093 -0.0178334 -0.24189 0.0369104 -0.0177091 -0.24032 0.0358281 -0.0175091 -0.242301 0.0364248 -0.0176738 -0.24178 0.0366219 -0.0175923 -0.241093 0.0362783 -0.0169238 -0.240458 0.0363241 -0.0169433 -0.240903 0.03611 -0.01731 -0.239818 0.036135 -0.016942 -0.240034 0.0363594 -0.0172786 -0.24044 0.0365857 -0.0175598 -0.240391 0.036028 -0.0169635 -0.239836 0.0363111 -0.0175877 -0.23972 0.0365914 -0.0177414 -0.239562 0.0362326 -0.0178434 -0.23868 0.036895 -0.0177406 -0.239375 0.0179156 -0.0183619 -0.2568 0.018219 -0.0183534 -0.256562 0.0184628 -0.0184669 -0.256869 0.0351755 -0.0180153 -0.243374 0.0353145 -0.0180749 -0.24355 0.031064 -0.0173526 -0.245985 0.0267683 -0.0178412 -0.24949 0.0180381 -0.0180616 -0.256342 0.0177276 -0.0180502 -0.256572 0.026949 -0.0181332 -0.249712 0.0313143 -0.0180403 -0.246287 0.0311336 -0.0177482 -0.246064 0.0350897 -0.0179395 -0.243267 0.0315588 -0.0181523 -0.246595 0.0271933 -0.0182458 -0.25002 0.035118 -0.0179684 -0.243302 0.0350161 -0.0178411 -0.243175 0.0355591 -0.0172329 -0.242457 0.0349297 -0.0176547 -0.243069 0.0348681 -0.0172802 -0.242999 0.0294445 -0.0178477 -0.202254 0.0297339 -0.0172392 -0.202516 0.0297376 -0.0171583 -0.202518 0.0171445 -0.0174074 -0.21573 0.0169631 -0.0174066 -0.215922 0.0226406 -0.017745 -0.209473 0.0223508 -0.0178542 -0.209201 0.0169315 -0.0177001 -0.21553 0.0228536 -0.0174525 -0.20967 0.0266592 -0.0175035 -0.205631 0.0264464 -0.0177959 -0.205435 0.0169731 -0.0173819 -0.215931 0.0298372 -0.0171594 -0.202412 0.0298092 -0.0174033 -0.202387 0.0297608 -0.0175543 -0.202341 0.0296573 -0.0175554 -0.20245 0.0296354 -0.0176028 -0.20243 0.0295526 -0.0178463 -0.202146 0.0294281 -0.0178604 -0.202239 0.0165668 -0.0177931 -0.21555 0.0166818 -0.0177457 -0.215659 0.0167501 -0.0176993 -0.215723 0.0162486 -0.0175567 -0.216471 0.0167874 -0.0176669 -0.215758 0.0168705 -0.0175721 -0.215836 0.0164577 -0.0169769 -0.216614 0.0163955 -0.0172926 -0.216585 0.0156196 -0.017483 -0.217114 0.0153934 -0.0176472 -0.216931 0.0160408 -0.0177264 -0.216291 0.0151483 -0.0176793 -0.216706 0.0335585 -0.0161904 -0.203422 0.0332654 -0.0155707 -0.203453 0.0329286 -0.0158025 -0.202633 0.0330889 -0.0156793 -0.202904 0.0324334 -0.0168541 -0.201891 0.0325939 -0.0170181 -0.201717 0.0317351 -0.0171786 -0.201656 0.0318187 -0.0173468 -0.201473 0.0310169 -0.0174217 -0.201651 0.0336888 -0.0164289 -0.202805 0.0334013 -0.0162714 -0.202905 0.033048 -0.016497 -0.202368 0.0331883 -0.0160052 -0.20294 0.0328522 -0.0162513 -0.202427 0.0322827 -0.0166269 -0.201983 0.0321611 -0.0163659 -0.201982 0.0316431 -0.0169607 -0.201769 0.0303479 -0.017355 -0.20198 0.030317 -0.0175708 -0.201876 0.0309873 -0.0172072 -0.201768 0.0339981 -0.0164488 -0.202659 0.0342723 -0.0163275 -0.202493 0.0335238 -0.0167052 -0.202018 0.0318848 -0.0174473 -0.20124 0.0319263 -0.0174693 -0.200982 0.0309803 -0.0177491 -0.201016 0.0301646 -0.0178627 -0.201531 0.0292668 -0.0179592 -0.201877 0.030254 -0.0177453 -0.201722 0.0310259 -0.0175935 -0.201475 0.0310133 -0.0177062 -0.201256 0.0327433 -0.0170976 -0.201484 0.0332845 -0.0166568 -0.202224 0.0338697 -0.0163473 -0.203374 0.0152525 -0.0170459 -0.218377 0.0155178 -0.0167751 -0.217752 0.0158673 -0.0168912 -0.217241 0.0154291 -0.0171169 -0.217756 0.0157873 -0.0172154 -0.217224 0.0149228 -0.0175471 -0.217574 0.0146038 -0.0175516 -0.217423 0.015217 -0.0173921 -0.217693 0.0146849 -0.0174751 -0.218331 0.0153273 -0.0166749 -0.218743 0.0152814 -0.01704 -0.219031 0.0150184 -0.0173273 -0.218364 0.0143615 -0.0174515 -0.219209 0.0143219 -0.0174583 -0.218285 0.0153667 -0.0166833 -0.219028 0.0153249 -0.0173809 -0.21975 0.0150442 -0.0175356 -0.2199 0.0150494 -0.0173217 -0.219068 0.0147197 -0.0174692 -0.219132 0.0159822 -0.017207 -0.22019 0.015831 -0.0174749 -0.220322 0.015529 -0.0171052 -0.219662 0.015631 -0.017639 -0.220534 0.0154172 -0.0176708 -0.220789 0.0383719 -0.0152455 -0.23386 0.0384505 -0.0155942 -0.233845 0.0360875 -0.0159024 -0.218424 0.0389902 -0.0160266 -0.233753 0.0367532 -0.0160587 -0.218313 0.0393432 -0.0160237 -0.233695 0.0333432 -0.0159137 -0.20345 0.0358691 -0.0156244 -0.218458 0.0342165 -0.0163541 -0.203316 0.0364029 -0.0160574 -0.218372 0.0172205 -0.0177411 -0.221747 0.0164256 -0.0177217 -0.22114 0.0174943 -0.0173082 -0.221413 0.0167376 -0.0172877 -0.220801 0.0166076 -0.0175521 -0.220934 0.0174649 -0.017402 -0.221448 0.0172798 -0.0176947 -0.221674 0.0382956 -0.0155057 -0.23482 0.0383485 -0.015889 -0.234886 0.0377872 -0.0160875 -0.235625 0.0349439 -0.0177704 -0.235985 0.0348103 -0.0178873 -0.236152 0.0351135 -0.0173761 -0.235767 0.0352999 -0.017577 -0.236024 0.0350482 -0.0175945 -0.235853 0.0359908 -0.0172645 -0.236181 0.035346 -0.0173609 -0.235929 0.0352211 -0.0177521 -0.236169 0.0351166 -0.0178703 -0.236351 0.0366747 -0.0168019 -0.236167 0.0359628 -0.0170318 -0.236138 0.0368289 -0.0172473 -0.236296 0.0369035 -0.0174163 -0.236461 0.0360007 -0.0174765 -0.236289 0.0359919 -0.0176491 -0.236452 0.0359651 -0.017767 -0.236657 0.0369667 -0.0175265 -0.236673 0.0381182 -0.01713 -0.236554 0.0379799 -0.0171217 -0.23632 0.0378198 -0.0170303 -0.23612 0.0376562 -0.0168664 -0.235978 0.0367501 -0.0170358 -0.236195 0.037508 -0.0166489 -0.235909 0.0373925 -0.016403 -0.235922 0.0380564 -0.0162193 -0.235411 0.0382517 -0.0164507 -0.235435 0.0387347 -0.0166737 -0.235704 0.0379315 -0.0159489 -0.235471 0.0388506 -0.0162948 -0.234927 0.0384892 -0.0166098 -0.235537 0.0389528 -0.0166331 -0.235912 0.0384685 -0.015676 -0.234369 0.0385644 -0.016139 -0.234872 0.0396649 -0.0159714 -0.234451 0.0391583 -0.0163299 -0.235043 0.038383 -0.0153433 -0.234436 0.0386713 -0.0158732 -0.233807 0.0386894 -0.015945 -0.234335 0.0390036 -0.016099 -0.234338 0.0393509 -0.0161084 -0.23438 0.0303632 -0.0174847 -0.231977 0.0301783 -0.0177771 -0.2322 0.021833 -0.0170188 -0.224876 0.0217644 -0.0174177 -0.224958 0.0175331 -0.0170025 -0.221366 0.0173845 -0.0175675 -0.221546 0.0215793 -0.0177103 -0.225183 0.034902 -0.0178166 -0.236038 0.0345041 -0.0178265 -0.23573 0.0350747 -0.0175255 -0.235818 0.0346889 -0.0175342 -0.235508 0.0121719 -0.0184248 -0.182311 0.0121078 -0.0183682 -0.182385 0.0121124 -0.0181606 -0.18258 0.0121075 -0.0181237 -0.182601 0.0121944 -0.018532 -0.18194 0.0121487 -0.018485 -0.182175 0.0112202 -0.0183964 -0.182166 0.0120756 -0.0181923 -0.182551 0.012055 -0.0179737 -0.182657 0.0113694 -0.0178929 -0.182641 0.012048 -0.0177327 -0.182693 0.0103571 -0.0181631 -0.182413 0.00928808 -0.0177261 -0.182793 0.00971457 -0.0176701 -0.183171 0.0094906 -0.0177463 -0.183001 0.00898715 -0.0173796 -0.183676 0.00993033 -0.0175078 -0.18328 0.0102409 -0.0181896 -0.182183 0.0112671 -0.0182811 -0.182375 0.0104872 -0.01806 -0.182612 0.0113184 -0.0181079 -0.182539 0.0106175 -0.0178913 -0.182758 0.0107346 -0.0176746 -0.182838 0.0108261 -0.0174325 -0.182842 0.0101093 -0.0172806 -0.183313 0.0102278 -0.0170188 -0.183267 0.00976068 -0.0169306 -0.183853 0.00979213 -0.0165312 -0.183957 0.00939222 -0.0169535 -0.184419 0.00908696 -0.0171096 -0.184408 0.00872554 -0.0170111 -0.185066 0.0084064 -0.0168622 -0.185099 0.00874874 -0.0171289 -0.184355 0.00928019 -0.0173333 -0.183799 0.00955267 -0.0171752 -0.183861 0.00960839 -0.0166894 -0.184385 0.00960617 -0.0165745 -0.184933 0.0123821 -0.0177276 -0.182789 0.012084 -0.0177953 -0.182698 0.01225 -0.0185319 -0.181949 0.0124238 -0.0181192 -0.182696 0.0134771 -0.0185085 -0.182552 0.0126686 -0.018527 -0.182073 0.0125283 -0.0184105 -0.182435 0.0130338 -0.0181022 -0.183059 0.0129596 -0.0177091 -0.183131 0.0108035 -0.0161087 -0.195439 0.00939039 -0.0168516 -0.184974 0.00907639 -0.0170073 -0.185022 0.00991077 -0.0165411 -0.195547 0.0122573 -0.0152957 -0.212506 0.0121781 -0.0156436 -0.212516 0.010881 -0.0157618 -0.195418 0.0105837 -0.0163869 -0.195472 0.010265 -0.0165412 -0.195511 0.0109578 -0.0159184 -0.212591 0.0277241 -0.0177513 -0.19548 0.0259187 -0.0180427 -0.19361 0.0276755 -0.0176137 -0.195534 0.0277059 -0.0177067 -0.195501 0.0219418 -0.0182598 -0.189725 0.0174544 -0.0182635 -0.186435 0.0216865 -0.0181465 -0.190022 0.0132226 -0.0183938 -0.182847 0.0257298 -0.0177507 -0.193825 0.0256569 -0.0173556 -0.1939 0.0214976 -0.0178546 -0.190236 0.0214242 -0.0174601 -0.19031 0.0172656 -0.0179718 -0.186647 0.0119558 -0.0159222 -0.212533 0.0123036 -0.0157325 -0.213105 0.0124032 -0.0154026 -0.213149 0.0119654 -0.0159231 -0.212642 0.0120832 -0.0160002 -0.213127 0.0124882 -0.0162959 -0.213792 0.0131014 -0.0166771 -0.214276 0.0137135 -0.017181 -0.214699 0.0145104 -0.0174355 -0.214705 0.0121876 -0.0156447 -0.212625 0.0137988 -0.0170131 -0.214516 0.0145203 -0.0172637 -0.214527 0.0149358 -0.0169078 -0.214271 0.0145999 -0.0168104 -0.214361 0.0139846 -0.0165522 -0.214373 0.0138925 -0.0167957 -0.214404 0.0132545 -0.0164518 -0.214186 0.0126879 -0.0160536 -0.21374 0.0128169 -0.0157657 -0.213782 0.012526 -0.0155121 -0.213398 0.0151944 -0.0172023 -0.214198 0.0145512 -0.0170485 -0.214408 0.0109733 -0.0159204 -0.21276 0.0126679 -0.016907 -0.214937 0.012788 -0.0169203 -0.214677 0.0154869 -0.0177574 -0.21487 0.0153782 -0.0177107 -0.214657 0.0162853 -0.0178125 -0.214316 0.0145223 -0.0175475 -0.214925 0.0136457 -0.0172813 -0.214931 0.012939 -0.0168402 -0.214446 0.0122496 -0.0164543 -0.213931 0.0120098 -0.0165036 -0.214135 0.0117835 -0.0161552 -0.213209 0.0116454 -0.0160772 -0.212675 0.011461 -0.0161682 -0.213338 0.0112912 -0.0160762 -0.212717 0.0116345 -0.0160761 -0.212554 0.0112782 -0.0160748 -0.212575 0.0158174 -0.0174823 -0.213871 0.0158759 -0.0175777 -0.213927 0.0152248 -0.0174197 -0.214305 0.015288 -0.0175946 -0.214462 0.0276365 -0.0173874 -0.195574 0.0286443 -0.0180223 -0.195759 0.0277883 -0.0178713 -0.195408 0.0279084 -0.0180107 -0.19527 0.0284613 -0.0178514 -0.195958 0.0291427 -0.0177873 -0.196514 0.0283311 -0.0175889 -0.196085 0.0162407 -0.0178004 -0.214158 0.0161059 -0.017773 -0.214147 0.0159447 -0.0176592 -0.213993 0.0159456 -0.0175654 -0.213879 0.0157364 -0.0172595 -0.213791 0.0157097 -0.0170126 -0.213763 0.0291471 -0.0174742 -0.199597 0.0292969 -0.0177403 -0.199714 0.0295086 -0.0179085 -0.199898 0.0294904 -0.0174244 -0.199106 0.0296841 -0.0176965 -0.199179 0.0302272 -0.0178082 -0.198529 0.0299586 -0.0178581 -0.199303 0.0296888 -0.0173756 -0.198471 0.0299095 -0.0176535 -0.19849 0.0298956 -0.017652 -0.197776 0.0302151 -0.0178048 -0.19772 0.030579 -0.0178092 -0.198579 0.0295917 -0.0170236 -0.197814 0.0294368 -0.0174299 -0.197175 0.0296729 -0.0173729 -0.19781 0.0299116 -0.0178619 -0.196948 0.0302129 -0.0178731 -0.196772 0.0293536 -0.0170912 -0.197183 0.0289944 -0.0175209 -0.196641 0.0296354 -0.0177042 -0.197091 0.0293416 -0.0179535 -0.196309 0.016123 -0.0177531 -0.214047 0.0193248 -0.0178357 -0.211099 0.0163463 -0.0178131 -0.214258 0.015764 -0.0170131 -0.213705 0.0158308 -0.0173878 -0.21377 0.0284727 -0.0175545 -0.200351 0.0288877 -0.0179688 -0.20075 0.0288406 -0.0179765 -0.201007 0.0287662 -0.0179218 -0.200634 0.0191011 -0.0177762 -0.210888 0.023131 -0.0178796 -0.207062 0.022907 -0.0178207 -0.20685 0.0225915 -0.0173874 -0.206548 0.028616 -0.0179187 -0.200794 0.0227174 -0.0176478 -0.206669 0.0284261 -0.017746 -0.200612 0.0282582 -0.0171767 -0.200443 0.0283003 -0.0174852 -0.200488 0.0187857 -0.017343 -0.210587 0.0189117 -0.0176031 -0.210708 0.0160152 -0.0176729 -0.213945 0.0293666 -0.0179759 -0.200485 0.0291349 -0.0179258 -0.200269 0.0289908 -0.0179796 -0.200847 0.0286553 -0.0178396 -0.200528 0.0289341 -0.0177551 -0.200086 0.0285763 -0.0177491 -0.200452 0.0287442 -0.017177 -0.199927 0.0284085 -0.0171797 -0.200283 0.0287965 -0.0174913 -0.199965 0.0297467 -0.0179505 -0.200119 0.0177127 -0.0182974 -0.16994 0.0176269 -0.0186891 -0.169882 0.0171215 -0.0190963 -0.169442 0.0116411 -0.0186767 -0.176032 0.0174114 -0.0189803 -0.169701 0.0240608 -0.0190957 -0.163036 0.0240691 -0.0190649 -0.163052 0.024118 -0.0187294 -0.163138 0.0234828 -0.0186398 -0.163607 0.0240115 -0.0186728 -0.163193 0.0233962 -0.0190305 -0.16355 0.0239545 -0.0190609 -0.16311 0.0238164 -0.0193514 -0.162871 0.0231809 -0.0193215 -0.16337 0.0115687 -0.0186728 -0.176115 0.0116001 -0.018647 -0.17614 0.0118567 -0.0183853 -0.176215 0.0118016 -0.0183623 -0.176295 0.0112661 -0.0187874 -0.175869 0.0113194 -0.0187824 -0.175913 0.0240991 -0.0189163 -0.163108 0.0244827 -0.0191185 -0.162867 0.0252367 -0.0187617 -0.162932 0.0244938 -0.018903 -0.162972 0.0244871 -0.0186663 -0.16301 0.0263991 -0.0178917 -0.163563 0.0268412 -0.0179438 -0.164091 0.0269373 -0.0174912 -0.164645 0.0252983 -0.0189787 -0.162825 0.0259725 -0.018477 -0.163171 0.026509 -0.0181736 -0.163594 0.0270116 -0.0178214 -0.164656 0.024455 -0.0192933 -0.162705 0.0253566 -0.0191511 -0.162655 0.0261041 -0.0187029 -0.163085 0.0262513 -0.0188718 -0.162925 0.0266862 -0.0184148 -0.16354 0.0273073 -0.0183662 -0.163974 0.027039 -0.0182025 -0.164063 0.0239409 -0.0193635 -0.162793 0.0244131 -0.0194116 -0.1625 0.0254059 -0.0192622 -0.162436 0.0263968 -0.0189636 -0.162711 0.0269049 -0.0185804 -0.163408 0.0271337 -0.0186464 -0.163219 0.0275087 -0.0182557 -0.164609 0.0237833 -0.0194758 -0.16246 0.0254415 -0.0193011 -0.162192 0.0265234 -0.0189676 -0.162466 0.0276012 -0.0184075 -0.163837 0.0273395 -0.0186034 -0.163 0.0278718 -0.0183196 -0.163676 0.0278425 -0.0182821 -0.164558 0.0116428 -0.0185442 -0.176276 0.0114977 -0.01872 -0.176058 0.0111969 -0.0187835 -0.175944 0.010982 -0.018664 -0.176887 0.0104847 -0.0186131 -0.177704 0.0112571 -0.0184975 -0.176962 0.0108299 -0.018597 -0.177699 0.0109784 -0.0185635 -0.178506 0.0114176 -0.0185651 -0.179221 0.0116476 -0.0184003 -0.179039 0.0116951 -0.0185452 -0.176214 0.011437 -0.0187184 -0.176127 0.0114482 -0.0182307 -0.176998 0.011136 -0.0184371 -0.177685 0.0113459 -0.0181633 -0.177664 0.0112688 -0.0184043 -0.1784 0.0119574 -0.0183969 -0.179338 0.0117839 -0.0182868 -0.176371 0.0114203 -0.0178267 -0.17764 0.0114679 -0.0181291 -0.178326 0.011538 -0.0177897 -0.178298 0.0118064 -0.0181298 -0.178919 0.011866 -0.0178013 -0.17888 0.0120813 -0.0181305 -0.179196 0.0290864 -0.0170048 -0.177691 0.0312081 -0.016365 -0.190644 0.029294 -0.0172781 -0.177673 0.0314199 -0.0166401 -0.190621 0.0317264 -0.016799 -0.190577 0.0299337 -0.0174582 -0.17758 0.0320696 -0.0168115 -0.190521 0.0272141 -0.0180924 -0.164643 0.0295949 -0.0174391 -0.177634 0.0281558 -0.0181668 -0.164502 0.030248 -0.0173319 -0.177522 0.0124195 -0.0181819 -0.179518 0.0117755 -0.0185657 -0.17955 0.0281046 -0.0180654 -0.193172 0.0287681 -0.017786 -0.193086 0.0282652 -0.0176605 -0.192829 0.0282285 -0.0178176 -0.192909 0.0282854 -0.0174876 -0.192782 0.0287598 -0.0173179 -0.192929 0.0287723 -0.017564 -0.192971 0.0295619 -0.0176446 -0.193091 0.0296239 -0.0178184 -0.193266 0.0287475 -0.0179623 -0.193262 0.0287125 -0.0180757 -0.193482 0.029679 -0.0179274 -0.193489 0.0305042 -0.0175521 -0.192952 0.0294995 -0.0174237 -0.192981 0.0303554 -0.0173823 -0.192798 0.0302256 -0.0171563 -0.192717 0.0296994 -0.0170922 -0.192894 0.0306672 -0.0165557 -0.192281 0.0306547 -0.0176461 -0.19316 0.0314145 -0.0173057 -0.192568 0.0321388 -0.0169474 -0.192054 0.0311781 -0.0172362 -0.192396 0.0318622 -0.0170303 -0.191905 0.0309549 -0.0170708 -0.192282 0.0307762 -0.0168328 -0.192242 0.0310862 -0.016571 -0.191716 0.0312206 -0.0164065 -0.191184 0.0317335 -0.0168361 -0.191181 0.0320729 -0.0168567 -0.191222 0.0315624 -0.0169872 -0.191787 0.0312886 -0.0168252 -0.191721 0.031431 -0.0166763 -0.191168 0.0311311 -0.0160256 -0.190643 0.0152632 -0.0184956 -0.182886 0.0120645 -0.0185935 -0.179953 0.0121569 -0.0185527 -0.179843 0.0122889 -0.0184338 -0.179682 0.0157806 -0.0176961 -0.182246 0.0200128 -0.0175662 -0.185835 0.0157456 -0.0180075 -0.182299 0.0156345 -0.0182697 -0.18244 0.0154648 -0.0184415 -0.182647 0.0194955 -0.0183658 -0.186473 0.0199774 -0.0178771 -0.185888 0.0198662 -0.0181391 -0.186028 0.0240981 -0.0180217 -0.189616 0.0196967 -0.018311 -0.186234 0.0242453 -0.0174497 -0.189425 0.0242095 -0.01776 -0.189477 0.0239288 -0.0181938 -0.189821 0.0275474 -0.0181041 -0.192888 0.023728 -0.0182493 -0.190059 0.0279417 -0.0181496 -0.193513 0.027828 -0.0176704 -0.192545 0.0277166 -0.0179319 -0.192684 0.0281904 -0.0179223 -0.192991 0.0101601 -0.0184724 -0.174001 0.0108136 -0.0186836 -0.173967 0.010711 -0.018307 -0.173721 0.0106984 -0.0180533 -0.173682 0.0102011 -0.0179951 -0.173831 0.00939839 -0.0180298 -0.173849 0.00973726 -0.0178676 -0.173852 0.00838296 -0.0171755 -0.173185 0.00872568 -0.0177297 -0.173564 0.0079018 -0.0169662 -0.17216 0.0101724 -0.0182468 -0.173878 0.00930578 -0.0182589 -0.173969 0.00827381 -0.0174833 -0.173163 0.00798456 -0.0173326 -0.172703 0.00777978 -0.0176038 -0.172758 0.0107303 -0.0184284 -0.17377 0.00856913 -0.0179701 -0.17366 0.00839168 -0.018136 -0.17384 0.00808279 -0.0177396 -0.173233 0.00784185 -0.0179014 -0.173385 0.00762157 -0.0175809 -0.172243 0.00731621 -0.0177392 -0.1723 0.0101654 -0.0186485 -0.174189 0.00921527 -0.0184304 -0.174163 0.00821872 -0.0182037 -0.174079 0.00749524 -0.0177632 -0.172868 0.0101877 -0.0187569 -0.174422 0.00913752 -0.018524 -0.174409 0.00759135 -0.0179418 -0.173591 0.00718361 -0.0177813 -0.173013 0.00534963 -0.0183387 -0.157415 0.00356117 -0.0190789 -0.147963 0.00336984 -0.0193486 -0.148023 0.00420896 -0.0186748 -0.157648 0.00782997 -0.0173058 -0.172193 0.00515168 -0.0186106 -0.157471 0.00485883 -0.0187727 -0.157537 0.00697187 -0.0177507 -0.172353 0.00452433 -0.0187954 -0.1576 0.0109557 -0.0188409 -0.17429 0.0112083 -0.0188566 -0.174359 0.0108977 -0.0188017 -0.174159 0.0108283 -0.0180575 -0.173617 0.0108527 -0.0183711 -0.173677 0.0115236 -0.0186588 -0.173383 0.010934 -0.0186345 -0.17384 0.0110592 -0.0188055 -0.17408 0.0117179 -0.0188302 -0.173568 0.00367683 -0.0194426 -0.146774 0.00522448 -0.0206269 -0.144819 0.00527437 -0.0205021 -0.145192 0.00467182 -0.0199837 -0.145718 0.00532144 -0.0200654 -0.14552 0.00472659 -0.0197448 -0.145733 0.00390732 -0.0199616 -0.146146 0.00458973 -0.0202001 -0.145636 0.00448807 -0.0203736 -0.145494 0.00332352 -0.0202398 -0.145712 0.00437642 -0.0204878 -0.145308 0.00414054 -0.0194835 -0.146158 0.00405182 -0.019737 -0.146185 0.00349691 -0.019682 -0.146782 0.00372346 -0.0201318 -0.146046 0.00352119 -0.0202282 -0.145896 0.00352835 -0.0192098 -0.147365 0.00333644 -0.0194666 -0.147407 0.00325279 -0.0198488 -0.146734 0.00297871 -0.0199196 -0.146636 0.0027131 -0.0198844 -0.146502 0.00362535 -0.0187514 -0.147924 0.00308513 -0.0195129 -0.148092 0.00305829 -0.0196313 -0.147415 0.00275723 -0.019543 -0.148159 0.00273936 -0.019677 -0.147387 0.0113967 -0.0183963 -0.173255 0.0172098 -0.0189719 -0.167143 0.0119487 -0.0188836 -0.173781 0.0170441 -0.0183966 -0.166962 0.0227683 -0.0190577 -0.160774 0.017083 -0.0187091 -0.167014 0.0230898 -0.0194917 -0.161092 0.0233217 -0.0195431 -0.161306 0.0174043 -0.0191431 -0.167329 0.00531203 -0.0202125 -0.145459 0.00607739 -0.0204998 -0.145221 0.00679351 -0.0197901 -0.145943 0.00601851 -0.0202102 -0.145485 0.0068669 -0.0201766 -0.145873 0.00727587 -0.0205881 -0.145361 0.0229251 -0.0187652 -0.160469 0.0229697 -0.019077 -0.160516 0.0231134 -0.0193393 -0.160626 0.0228949 -0.0193208 -0.160904 0.0233334 -0.0195107 -0.16078 0.0235947 -0.0195638 -0.160954 0.0151075 -0.0201778 -0.151275 0.00704227 -0.0204667 -0.145662 0.0146979 -0.0197669 -0.15179 0.0148734 -0.0200572 -0.151577 0.0233417 -0.0194811 -0.160479 0.0230754 -0.0188303 -0.160195 0.0231828 -0.0193074 -0.160364 0.0232924 -0.0194022 -0.159606 0.0233008 -0.0195772 -0.159048 0.0231943 -0.0195976 -0.158474 0.0231349 -0.0194608 -0.15853 0.0230146 -0.0196545 -0.157821 0.0228832 -0.0194776 -0.157954 0.0231868 -0.0197632 -0.157662 0.0233712 -0.0196715 -0.159156 0.0234369 -0.0196395 -0.159687 0.0233533 -0.0195274 -0.159647 0.0235505 -0.0195848 -0.160599 0.0228859 -0.019663 -0.157644 0.0227751 -0.0195354 -0.157756 0.0230907 -0.0190824 -0.160265 0.0232599 -0.0194686 -0.159054 0.0232462 -0.0191293 -0.159522 0.0232435 -0.0192281 -0.159194 0.0232563 -0.0192681 -0.159563 0.023235 -0.0193552 -0.159057 0.0231035 -0.019312 -0.158577 0.0231013 -0.0191571 -0.158613 0.0228064 -0.019251 -0.15805 0.0229482 -0.0197108 -0.15758 0.0229398 -0.0197926 -0.157189 0.0227053 -0.019673 -0.157492 0.0226076 -0.0189832 -0.157903 0.0226559 -0.0192806 -0.15787 0.0225297 -0.0193824 -0.157706 0.0226884 -0.0193723 -0.15784 0.0197763 -0.0218892 -0.127814 0.0197597 -0.0219554 -0.127554 0.0198099 -0.021158 -0.128288 0.0198084 -0.0212965 -0.128276 0.0191819 -0.0215255 -0.128327 0.0198023 -0.0215261 -0.128199 0.0197836 -0.0218284 -0.127926 0.0190789 -0.0218148 -0.128079 0.0181337 -0.0219017 -0.128205 0.018943 -0.0219406 -0.12773 0.0198018 -0.0215393 -0.128192 0.020141 -0.0211386 -0.128295 0.0214968 -0.0210343 -0.128907 0.0217318 -0.0204574 -0.129406 0.021918 -0.0203063 -0.130024 0.0197911 -0.0217405 -0.128037 0.0202107 -0.021684 -0.128085 0.0201723 -0.0214319 -0.128242 0.0209159 -0.0212753 -0.128465 0.0218541 -0.0208237 -0.129442 0.021713 -0.021302 -0.128807 0.0221165 -0.0211039 -0.129387 0.0220236 -0.0206955 -0.130045 0.0210542 -0.0215327 -0.128327 0.0219756 -0.0214489 -0.128613 0.0224573 -0.0212322 -0.129254 0.0223044 -0.0209855 -0.130034 0.020251 -0.0218595 -0.127845 0.0212121 -0.0216978 -0.128098 0.0213636 -0.0217435 -0.127816 0.0222319 -0.0214457 -0.128363 0.0183824 -0.0217793 -0.128491 0.0118828 -0.0214807 -0.133453 0.0121317 -0.0213586 -0.13374 0.0185695 -0.0214896 -0.12869 0.0123188 -0.0210688 -0.13394 0.00614594 -0.020278 -0.139254 0.0060675 -0.0206642 -0.13919 0.00588042 -0.0209542 -0.138989 0.0237223 -0.0198991 -0.141336 0.025612 -0.0191657 -0.152287 0.0259406 -0.0191992 -0.152241 0.024639 -0.0200114 -0.141216 0.0262526 -0.0190948 -0.152186 0.0235296 -0.0196326 -0.14134 0.0221748 -0.020887 -0.130042 0.0240044 -0.0200663 -0.141311 0.0226889 -0.0211025 -0.129994 0.0243282 -0.020106 -0.141268 0.00543882 -0.0203759 -0.141314 0.00488389 -0.021002 -0.139684 0.00464324 -0.0209343 -0.140595 0.00471838 -0.0208651 -0.141533 0.00494699 -0.020872 -0.140618 0.00501839 -0.0208085 -0.141453 0.00598515 -0.0208266 -0.139104 0.0056277 -0.0209883 -0.139105 0.00515746 -0.0209344 -0.139804 0.005391 -0.0207599 -0.139897 0.00520488 -0.0206988 -0.140628 0.00581129 -0.0208127 -0.139268 0.00593823 -0.0205588 -0.139371 0.0055503 -0.020504 -0.139951 0.00537797 -0.0204406 -0.140624 0.00572319 -0.0203173 -0.141943 0.00558057 -0.0205802 -0.142057 0.00527168 -0.0206365 -0.141376 0.005766 -0.0200043 -0.141892 0.00619816 -0.0202709 -0.142442 0.00536097 -0.0207509 -0.142215 0.00509952 -0.0208022 -0.142392 0.0236678 -0.0190349 -0.154516 0.0234146 -0.0198583 -0.155175 0.0233485 -0.0195729 -0.154753 0.0229377 -0.0198328 -0.155072 0.02332 -0.0193438 -0.154633 0.0229613 -0.0192836 -0.154622 0.0232986 -0.0190877 -0.154593 0.0241194 -0.0194594 -0.154519 0.024238 -0.0196351 -0.154687 0.0233812 -0.0197507 -0.15494 0.0243651 -0.0197343 -0.154904 0.0245999 -0.0190317 -0.153983 0.024023 -0.0192271 -0.154419 0.0249461 -0.0194459 -0.154177 0.0253664 -0.0195037 -0.154563 0.0251609 -0.0195262 -0.154357 0.0247504 -0.0192735 -0.154046 0.0251368 -0.0191038 -0.153483 0.0249702 -0.0184788 -0.153247 0.0249557 -0.0188489 -0.153454 0.0251235 -0.0187363 -0.152896 0.025324 -0.0190003 -0.152317 0.0253175 -0.019003 -0.152901 0.0259249 -0.0192081 -0.152977 0.0259406 -0.0192672 -0.153837 0.0256704 -0.0193304 -0.153691 0.0253879 -0.0192729 -0.153566 0.0256007 -0.0191697 -0.15293 0.0250516 -0.0184149 -0.152915 0.0251265 -0.0187316 -0.152325 0.0139165 -0.020116 -0.148505 0.00609558 -0.0205356 -0.142597 0.00593557 -0.0207053 -0.142821 0.0135659 -0.0203337 -0.148984 0.00574429 -0.0207523 -0.143077 0.0140192 -0.0198515 -0.148351 0.0215786 -0.01989 -0.154635 0.0137568 -0.0202859 -0.148728 0.0213881 -0.0199386 -0.15489 0.0224513 -0.0194296 -0.154574 0.0229619 -0.0191039 -0.154602 0.0227298 -0.0191064 -0.154575 0.0229593 -0.0194218 -0.154668 0.0229526 -0.0196284 -0.154798 0.0223995 -0.0196948 -0.154753 0.0223184 -0.0198645 -0.155017 0.0222214 -0.0199107 -0.155323 0.0217381 -0.0197198 -0.154413 0.0218409 -0.0194556 -0.15426 0.0218702 -0.0191403 -0.154201 -0.00265575 -0.0217078 -0.118458 -0.00292257 -0.0219976 -0.118541 -0.00363583 -0.0222614 -0.117033 -0.00329671 -0.0221156 -0.118632 -0.0012484 -0.0207716 -0.124496 -0.00231179 -0.021564 -0.120055 -0.0016119 -0.0214528 -0.124635 -0.00257948 -0.021854 -0.120139 -0.00198967 -0.0215681 -0.124727 -0.00295452 -0.0219713 -0.120231 -0.00134167 -0.0211624 -0.124551 0.000878128 -0.0204214 -0.13639 0.000492158 -0.0205311 -0.13648 -0.00204463 -0.0230541 -0.113877 -0.00189799 -0.0229335 -0.114212 -0.00203544 -0.0229728 -0.114186 -0.00184282 -0.0225446 -0.114537 -0.00173122 -0.0222568 -0.114548 -0.00180422 -0.0222518 -0.11458 -0.00246972 -0.0224142 -0.11499 -0.00264041 -0.0226717 -0.114903 -0.00192365 -0.0227966 -0.114399 -0.00286033 -0.0228383 -0.114739 -0.00237574 -0.0221074 -0.114986 -0.00287619 -0.0221863 -0.115602 -0.0031092 -0.0224538 -0.115578 -0.00341756 -0.0226027 -0.115483 -0.00293591 -0.0216158 -0.116157 -0.00288798 -0.0217085 -0.115897 -0.00330076 -0.0222603 -0.116265 -0.00366344 -0.0223905 -0.116253 -0.00299692 -0.0218529 -0.11686 -0.00326274 -0.0221426 -0.116943 -0.0030379 -0.0219804 -0.11623 0.000711052 -0.0205245 -0.137068 0.00115615 -0.02013 -0.136306 0.00132634 -0.0201205 -0.13678 0.0017108 -0.0198078 -0.137166 0.00173317 -0.0202258 -0.137328 0.00184829 -0.0198569 -0.137307 0.00230327 -0.0203925 -0.137716 0.000360161 -0.0204287 -0.137254 0.00185614 -0.0208118 -0.138511 0.00106379 -0.020412 -0.136895 0.00125174 -0.0206385 -0.13773 0.00200051 -0.0208157 -0.138183 0.00216025 -0.0206659 -0.137899 0.00285571 -0.020967 -0.138383 0.00290683 -0.0208037 -0.138094 0.0015175 -0.0205084 -0.137481 0.00296324 -0.0205357 -0.137899 0.00301498 -0.0202103 -0.137833 0.0025553 -0.0200976 -0.137732 0.00240085 -0.0200504 -0.137671 0.0035732 -0.0202799 -0.137809 0.00366764 -0.0206025 -0.137858 0.00370549 -0.0208689 -0.138043 -0.00173261 -0.0222922 -0.114547 -0.00135613 -0.0229427 -0.11406 -0.0018312 -0.0228004 -0.114358 -0.00130711 -0.0226537 -0.114322 -0.0017862 -0.0226601 -0.114452 -0.00054648 -0.0229436 -0.11406 -0.000594581 -0.0226546 -0.114322 -0.00128528 -0.0222725 -0.114417 -0.00178092 -0.0226391 -0.114463 0.000216779 -0.0229212 -0.114328 7.68753e-05 -0.0226318 -0.114559 1.664e-05 -0.022249 -0.114637 0.00420147 -0.0210891 -0.138521 0.00376524 -0.0210377 -0.138316 0.00393391 -0.0206103 -0.137778 0.00391841 -0.0202913 -0.137713 0.00399384 -0.0208763 -0.137957 0.00408825 -0.0210453 -0.138219 0.00480703 -0.021078 -0.137801 0.0168947 -0.0223159 -0.123098 0.0086484 -0.0226807 -0.11855 0.0167093 -0.0221909 -0.123424 0.00832307 -0.0222663 -0.119107 0.00826286 -0.0218834 -0.119185 0.00846298 -0.0225557 -0.118876 0.000402175 -0.0230463 -0.114002 0.00452696 -0.0206437 -0.137434 0.00463636 -0.0209083 -0.137584 0.0109732 -0.0214796 -0.132623 0.0106932 -0.0210452 -0.132255 0.0108025 -0.0213101 -0.132406 0.0169681 -0.021727 -0.127229 0.0173474 -0.0217642 -0.126826 0.016859 -0.021462 -0.127077 0.0175167 -0.0215652 -0.126085 0.0176019 -0.0216364 -0.125396 0.0175402 -0.0213322 -0.125375 0.0172088 -0.0215008 -0.126705 0.0176818 -0.021826 -0.126154 0.0176154 -0.0219618 -0.124672 0.0174538 -0.0217062 -0.124718 0.0170886 -0.0217668 -0.124127 0.017214 -0.0214448 -0.124385 0.017562 -0.0219345 -0.126993 0.0183383 -0.0221296 -0.125396 0.0181297 -0.0222042 -0.124479 0.0174092 -0.0221959 -0.123876 0.0177752 -0.0218945 -0.125408 0.0178522 -0.0221363 -0.124588 0.0180337 -0.0220677 -0.125408 0.017933 -0.0219977 -0.126241 0.0171389 -0.0218964 -0.127446 0.0165458 -0.0218112 -0.12369 0.0165693 -0.0219016 -0.123655 0.0166311 -0.0220632 -0.123556 0.0172197 -0.0220203 -0.124031 0.0168651 -0.0238587 -0.099648 0.0168979 -0.024148 -0.0993823 0.0168507 -0.0234768 -0.0997441 0.0161816 -0.023473 -0.0997811 0.0154967 -0.0238293 -0.099962 0.0161537 -0.0238552 -0.0996878 0.0153424 -0.0241189 -0.0997387 0.0169412 -0.0242743 -0.0990115 0.0160894 -0.0241445 -0.0994275 0.0155626 -0.0234451 -0.100037 0.0169884 -0.0238775 -0.0996542 0.0169779 -0.0237668 -0.0997067 0.0175405 -0.0233937 -0.0999531 0.017008 -0.0240184 -0.0995517 0.0176139 -0.0236979 -0.0999213 0.0169652 -0.0235093 -0.0997597 0.0185564 -0.0233309 -0.100933 0.0182674 -0.023087 -0.10059 0.018445 -0.0229727 -0.100902 0.0177325 -0.023955 -0.0997846 0.018198 -0.0235142 -0.100375 0.0183974 -0.0237813 -0.100279 0.017878 -0.0241254 -0.0995639 0.0188043 -0.0236098 -0.100883 0.0191338 -0.0237477 -0.100765 0.0170369 -0.0241514 -0.0993943 0.0180279 -0.0241827 -0.0992935 0.0186487 -0.0239363 -0.100096 0.0189046 -0.0239499 -0.0998623 0.019472 -0.0237139 -0.100603 0.00816106 -0.0237565 -0.104243 0.000775878 -0.0235065 -0.108431 0.00795648 -0.0238807 -0.103927 0.00838184 -0.0230833 -0.10454 0.00831549 -0.023467 -0.104466 0.0196759 -0.0219614 -0.111616 0.0197769 -0.0223433 -0.111639 0.0206943 -0.0216407 -0.119533 0.0200477 -0.0226318 -0.111634 0.0204221 -0.0227563 -0.111603 0.0213475 -0.0220513 -0.119492 0.0186154 -0.0228342 -0.101534 0.0187142 -0.0232131 -0.101556 0.0189807 -0.023501 -0.101554 0.0193507 -0.0236285 -0.101528 0.00107459 -0.0229961 -0.109061 0.00113496 -0.0230927 -0.108969 0.00106674 -0.0232544 -0.108874 0.000980429 -0.0233822 -0.108747 0.000827822 -0.0234247 -0.108744 0.000659074 -0.0235 -0.108509 -1.18947e-05 -0.0234447 -0.109172 0.000230104 -0.0233736 -0.109339 0.000437519 -0.0231983 -0.109473 0.000973092 -0.0232485 -0.108937 0.000580623 -0.0229441 -0.109555 -0.000225625 -0.0232373 -0.110935 0.000112587 -0.0231346 -0.110157 3.42273e-05 -0.0230648 -0.110907 -0.000532382 -0.0232967 -0.110957 -0.000323817 -0.0232212 -0.111874 -0.000134701 -0.0233085 -0.110099 0.00028043 -0.022878 -0.110185 0.000207341 -0.0228056 -0.110876 0.000366629 -0.0227351 -0.111548 0.000737161 -0.0226745 -0.112128 0.00119497 -0.0228965 -0.112723 0.00106583 -0.0230652 -0.112971 -3.52125e-05 -0.0231681 -0.11175 0.000175697 -0.023156 -0.112669 0.000412009 -0.0231086 -0.112454 0.000207774 -0.022997 -0.111636 0.000609921 -0.0229388 -0.112264 0.000772983 -0.0223587 -0.11207 0.0205046 -0.0212691 -0.120379 0.0191123 -0.022154 -0.121951 0.0195082 -0.0221518 -0.121826 0.0192474 -0.0223637 -0.122542 0.0193808 -0.0215594 -0.121595 0.0194214 -0.0218834 -0.121652 0.0193365 -0.0215622 -0.121613 0.0200417 -0.0218045 -0.121252 0.0202153 -0.0220785 -0.121386 0.0206805 -0.0222422 -0.121862 0.0196264 -0.0223184 -0.122087 0.0204573 -0.0216943 -0.120718 0.0204429 -0.0222344 -0.121604 0.0205684 -0.0212421 -0.120136 0.0206681 -0.0216244 -0.120135 0.0206912 -0.0219763 -0.120803 0.0213037 -0.0220388 -0.120237 0.0210056 -0.022116 -0.120955 0.0216847 -0.0219698 -0.120315 0.0205914 -0.0212559 -0.119511 0.0209691 -0.0219298 -0.119526 0.0209349 -0.0219134 -0.120171 0.00946908 -0.0219487 -0.116995 0.00129826 -0.0223111 -0.112489 0.00127699 -0.0226304 -0.112553 0.00908189 -0.022746 -0.117762 0.0176186 -0.0219061 -0.121566 0.00944778 -0.0222679 -0.11706 0.00936575 -0.022534 -0.11723 0.00923662 -0.0227027 -0.117478 0.0172528 -0.0223842 -0.122268 0.0190737 -0.0218871 -0.121764 0.0190641 -0.0216887 -0.121707 0.0189419 -0.0215634 -0.121722 0.0191325 -0.0222286 -0.122042 0.0190915 -0.0220428 -0.121853 0.0190215 -0.0223195 -0.122256 0.0191865 -0.0223398 -0.122281 0.0189767 -0.0221513 -0.121978 0.0189485 -0.0218843 -0.121789 0.0174075 -0.0223409 -0.121984 0.0181916 -0.0223187 -0.122256 0.0175366 -0.0221722 -0.121736 0.0182365 -0.0221504 -0.121978 0.0176399 -0.0215869 -0.121502 0.0182649 -0.0218834 -0.12179 -0.00764733 -0.0241624 -0.096843 -0.00697245 -0.0233719 -0.0966408 -0.00507225 -0.0227869 -0.106831 -0.00705572 -0.0237413 -0.0966911 -0.00729918 -0.0240265 -0.096764 -0.00802078 -0.0241181 -0.09691 -0.00852008 -0.025202 -0.0861202 -0.00805319 -0.0248307 -0.0865657 -0.0082547 -0.0250948 -0.0863786 -0.00824283 -0.025085 -0.0863899 -0.00803674 -0.024794 -0.0865802 -0.00838081 -0.0246428 -0.0871189 -0.00859705 -0.0245245 -0.0877794 -0.00856537 -0.024907 -0.0870621 -0.00882384 -0.0250739 -0.0869505 -0.00911296 -0.0251156 -0.0868029 -0.00858314 -0.0244328 -0.0884507 -0.00881312 -0.0247147 -0.0885134 -0.00914492 -0.0248603 -0.0885844 -0.00882028 -0.0247991 -0.0877855 -0.00913782 -0.0249531 -0.0877587 -0.00948752 -0.0249564 -0.0877041 -0.00312146 -0.02296 -0.108446 -0.00314264 -0.0233953 -0.108919 -0.00317547 -0.0229606 -0.108443 -0.00316842 -0.0226386 -0.108376 -0.00382807 -0.0225765 -0.108212 -0.00389239 -0.0229137 -0.108267 -0.00498422 -0.0224067 -0.106777 -0.00319111 -0.0232281 -0.108634 -0.00400528 -0.0231872 -0.108449 -0.00446335 -0.0228227 -0.107892 -0.00465097 -0.0231043 -0.108047 -0.00485456 -0.0227643 -0.107401 -0.00508967 -0.0230525 -0.10752 -0.00312972 -0.0232272 -0.108637 -0.00414543 -0.0233455 -0.108724 -0.00532906 -0.0230748 -0.10691 -0.00321271 -0.0233959 -0.108917 -0.00489518 -0.0232472 -0.108289 -0.00541304 -0.0231818 -0.107697 -0.00569238 -0.0232008 -0.106995 -0.0079578 -0.0244655 -0.0866422 -0.00777804 -0.0251043 -0.0860224 -0.008308 -0.0251326 -0.0863275 -0.00800313 -0.0247019 -0.086609 -0.00734954 -0.0244312 -0.0862253 -0.00762836 -0.0248134 -0.0862572 -0.00694355 -0.0244391 -0.0860943 -0.00696715 -0.0248279 -0.0859963 -0.00627309 -0.024439 -0.0860698 -0.00702587 -0.0251187 -0.0857256 -0.00625658 -0.0248277 -0.0859703 -0.00797907 -0.0252228 -0.0856942 -0.00710492 -0.0252382 -0.0853504 -0.00621771 -0.0251185 -0.0856959 -0.00544577 -0.025104 -0.0859369 -0.00616628 -0.025238 -0.0853159 -0.00247462 -0.0234009 -0.10886 -0.00315802 -0.023436 -0.109244 -0.00253391 -0.0232327 -0.108585 -0.00257112 -0.0229657 -0.108398 -0.00286951 -0.0226394 -0.108375 -0.00258001 -0.0226449 -0.108332 -0.00170658 -0.0234285 -0.108545 -0.00240323 -0.0234421 -0.109178 0.00378615 -0.0249349 -0.0901944 0.0125921 -0.024348 -0.0952582 0.00347899 -0.024523 -0.0907723 0.012512 -0.0240953 -0.0953972 0.0034232 -0.0241366 -0.0908557 -0.00557798 -0.0248131 -0.0861821 0.00361093 -0.0248132 -0.0905319 -0.0052692 -0.0252224 -0.0855948 -0.00193794 -0.0229939 -0.108139 -0.00184813 -0.0232596 -0.108305 0.00576215 -0.0238542 -0.104241 0.0126365 -0.0234267 -0.0989211 0.00536086 -0.0233753 -0.103562 0.0054508 -0.0236411 -0.103727 0.00559238 -0.02381 -0.103967 0.0138489 -0.0244304 -0.0962456 0.0128053 -0.0237549 -0.0988854 0.0126603 -0.0237449 -0.0989842 0.0129076 -0.02402 -0.099042 0.0127505 -0.0240105 -0.0991489 0.0128921 -0.0241796 -0.099388 0.0130617 -0.0242242 -0.099662 0.0132819 -0.0238048 -0.0983862 0.0134244 -0.024068 -0.0985015 0.0136443 -0.0242384 -0.0986609 0.0130678 -0.0241894 -0.0992678 0.0132594 -0.0242349 -0.0995257 0.0139882 -0.0242999 -0.0978955 0.0137347 -0.024128 -0.097818 0.0135675 -0.0238673 -0.0977555 0.013628 -0.023935 -0.0970645 0.0135657 -0.0236309 -0.0970467 0.0135127 -0.0235584 -0.0977176 0.0134557 -0.0240001 -0.096392 0.0133809 -0.0244849 -0.0955484 0.0135954 -0.0245569 -0.0953481 0.01284 -0.0245993 -0.0947879 0.0131969 -0.0243094 -0.0957116 0.0130696 -0.0240554 -0.0958145 0.012534 -0.024186 -0.0953606 0.0126656 -0.0244758 -0.0951228 0.014363 -0.0244285 -0.0970359 0.0141225 -0.024498 -0.0961261 0.0140592 -0.0243664 -0.0970586 0.0138012 -0.0241932 -0.0970686 0.0136152 -0.0242559 -0.0963388 0.017306 -0.0243781 -0.0859149 0.0177126 -0.0236074 -0.0918661 0.017928 -0.0247976 -0.0858894 0.0183096 -0.0247443 -0.0858555 0.0166017 -0.0247542 -0.0765651 0.0175652 -0.0246652 -0.0859109 0.0174226 -0.0236793 -0.0930904 0.0166395 -0.0245572 -0.0943998 0.0166184 -0.0245337 -0.0943451 0.0172011 -0.0243791 -0.0937699 0.0165211 -0.0243292 -0.0940865 0.0169885 -0.0237764 -0.0935871 0.0170549 -0.0241077 -0.0936262 0.0175141 -0.0240319 -0.0931001 0.0180196 -0.0244596 -0.0933552 0.0174005 -0.0245416 -0.0939925 0.0176171 -0.0245657 -0.0942536 0.0177601 -0.0239724 -0.0925062 0.0183637 -0.0243935 -0.0926277 0.0177278 -0.0243113 -0.0931949 0.0183287 -0.0244461 -0.0935476 0.0178093 -0.023984 -0.0918852 0.0176659 -0.0235999 -0.0925034 0.0180718 -0.0242714 -0.0918833 0.018012 -0.0242589 -0.0925511 0.0184379 -0.0244016 -0.0918607 0.0163318 -0.0248385 -0.0754394 0.0156896 -0.0249637 -0.0744379 0.0151514 -0.0250527 -0.0739141 0.0158502 -0.025232 -0.0743237 0.0153011 -0.0253377 -0.0737085 0.0155717 -0.0254779 -0.0733408 0.0160738 -0.0253976 -0.074141 0.0165575 -0.0251182 -0.0753765 0.0150977 -0.0246779 -0.0739904 0.0172066 -0.0251778 -0.0765316 0.0172052 -0.0252519 -0.0751168 0.0168703 -0.0252663 -0.0752609 0.0168525 -0.0250401 -0.0765534 0.0164614 -0.0238038 -0.0938983 0.0164645 -0.0239848 -0.0939194 0.0164778 -0.0241223 -0.093963 0.0161351 -0.0241133 -0.0940652 0.0161697 -0.0243795 -0.0942505 0.0162241 -0.0245484 -0.0945243 0.0153937 -0.024547 -0.0945542 0.0154288 -0.0243782 -0.0942771 0.0154509 -0.0241119 -0.0940897 0.0147198 -0.0243971 -0.0940595 0.0147962 -0.0241316 -0.0938886 0.0154858 -0.0254655 -0.0734572 0.0153897 -0.0254184 -0.0735878 0.0152353 -0.0252453 -0.0737985 0.0148547 -0.0249834 -0.0737543 0.0137417 -0.0249778 -0.0733186 0.0137766 -0.0252385 -0.0731461 0.0149438 -0.0252437 -0.0736037 0.015078 -0.0254167 -0.073379 0.0152366 -0.0254758 -0.073115 0.0125479 -0.0249764 -0.0732759 0.0130989 -0.0246677 -0.0733074 0.0138295 -0.0254113 -0.0728885 0.0113285 -0.0252409 -0.0734736 0.0125249 -0.0252372 -0.0731011 0.0112104 -0.0254137 -0.0732393 0.0124902 -0.0254099 -0.0728402 0.0110708 -0.0254722 -0.072964 0.0124493 -0.0254677 -0.0725335 -0.00322856 -0.0247413 -0.0847556 0.00570853 -0.024726 -0.0894919 -0.00330531 -0.0250049 -0.0849212 0.00558891 -0.0248958 -0.0897397 -0.00342424 -0.0251757 -0.0851652 -0.00356624 -0.0252263 -0.0854482 0.00578498 -0.0244611 -0.0893229 0.0145997 -0.0245664 -0.0943093 0.0144557 -0.0246116 -0.094597 0.0114337 -0.0246723 -0.0736863 0.011407 -0.0249803 -0.0736306 0.00400534 -0.0252406 -0.077201 0.00388815 -0.0254144 -0.0769717 -0.00323827 -0.0249207 -0.0810765 0.00411222 -0.024677 -0.0774071 0.00408398 -0.0249818 -0.0773538 -0.00320862 -0.024619 -0.0811277 -0.00331708 -0.0251779 -0.0809275 -0.00343339 -0.0253525 -0.0807028 -0.00354841 -0.0249144 -0.0812712 -0.00416777 -0.0251537 -0.0816899 -0.00365339 -0.0251717 -0.081139 -0.0038084 -0.0253462 -0.0809385 -0.00438231 -0.025328 -0.0815528 -0.00463455 -0.025393 -0.0813874 -0.00396909 -0.0245934 -0.081805 -0.00402284 -0.0248961 -0.0817784 -0.00430203 -0.0248698 -0.0824146 -0.00447024 -0.0251281 -0.082381 -0.00501545 -0.0253652 -0.0822511 -0.00472059 -0.025302 -0.0823236 -0.00452634 -0.0250965 -0.0831329 -0.00484943 -0.0252916 -0.0841056 -0.0045681 -0.0252346 -0.083975 -0.00409671 -0.0252015 -0.0846679 -0.00390746 -0.02503 -0.084478 -0.00432185 -0.025255 -0.0848865 -0.00478471 -0.0252697 -0.083163 -0.00433072 -0.0250622 -0.0838593 -0.00435418 -0.024837 -0.0831071 -0.00417418 -0.0248013 -0.0837764 -0.00412281 -0.0244924 -0.0837392 -0.00374601 -0.0244559 -0.0842949 -0.00378405 -0.0247677 -0.0843468 -0.00966248 -0.0254108 -0.0810266 -0.00946665 -0.0253258 -0.0807035 -0.00931814 -0.0250774 -0.0804536 -0.00927463 -0.0249215 -0.0803779 -0.00925053 -0.0247496 -0.0803333 -0.00923138 -0.0246107 -0.0803308 -0.0086063 -0.0245996 -0.0805753 -0.00925954 -0.0249211 -0.080387 -0.00934791 -0.0251829 -0.0805419 -0.00948264 -0.025355 -0.0807711 -0.00876744 -0.0253992 -0.0813826 -0.00964261 -0.0254104 -0.0810387 -0.00861682 -0.0249111 -0.0806376 -0.00790469 -0.0251714 -0.0808402 -0.0086513 -0.0251734 -0.0808137 -0.00870429 -0.0253451 -0.0810759 -0.00726924 -0.0249152 -0.0804576 -0.00792784 -0.0249089 -0.080662 -0.00786963 -0.025343 -0.0811057 -0.00782821 -0.0253968 -0.0814164 -0.00924611 -0.0246111 -0.0803218 -0.00972073 -0.0251953 -0.0802861 -0.00936419 -0.0251832 -0.080532 -0.0098078 -0.0245881 -0.0798072 -0.0100215 -0.0249131 -0.0796113 -0.0107823 -0.0253635 -0.0800168 -0.0104797 -0.0253476 -0.0798503 -0.00991212 -0.0253635 -0.0804926 -0.0102092 -0.0251875 -0.0797061 -0.00958838 -0.0249284 -0.080149 -0.0095373 -0.0246075 -0.0801046 -0.01111 -0.0253578 -0.0791366 -0.010246 -0.0249151 -0.0789765 0.000957321 -0.0249837 -0.0762752 -0.00729445 -0.0246042 -0.0803998 -0.00719096 -0.0251773 -0.0806186 -0.00707193 -0.0253492 -0.0808573 0.000930438 -0.0246761 -0.0762198 0.00103581 -0.025244 -0.0764317 0.00926227 -0.0252309 -0.0722445 0.00937923 -0.025405 -0.0724726 0.00115383 -0.025417 -0.0766653 0.00129324 -0.025476 -0.0769401 -0.0133132 -0.0251216 -0.0646401 -0.0126577 -0.0247117 -0.0645505 -0.0126883 -0.0248017 -0.0645496 -0.0128215 -0.0249406 -0.0645617 -0.0129234 -0.0250116 -0.0645731 -0.0125255 -0.0243224 -0.0645543 -0.0116665 -0.0245703 -0.0699713 -0.011734 -0.0248905 -0.0699731 -0.0104571 -0.0251913 -0.0790203 -0.0119223 -0.0251571 -0.0699958 -0.0107648 -0.0253489 -0.0790773 -0.0121999 -0.0253255 -0.0700359 0.00974152 -0.0245526 -0.068926 0.0102219 -0.0246307 -0.0705843 0.0102828 -0.0249358 -0.0705866 0.0107092 -0.0253683 -0.0706464 0.0110059 -0.0254033 -0.069749 0.00991571 -0.0253994 -0.0721031 0.0104362 -0.0253872 -0.0714429 0.00974324 -0.0252254 -0.0719135 0.0102097 -0.0252132 -0.0713221 0.0104539 -0.0251947 -0.0706084 0.0107036 -0.0253434 -0.0698038 0.00918358 -0.0249726 -0.0720928 0.00962716 -0.0249671 -0.071788 0.0100574 -0.0249548 -0.0712435 0.0104478 -0.0251703 -0.0698541 0.0102775 -0.0249105 -0.0698922 0.0100428 -0.0248817 -0.0692399 0.0102189 -0.0246037 -0.0699123 0.00960669 -0.0248541 -0.0687035 0.0101929 -0.0251428 -0.0691458 0.00989333 -0.025288 -0.0683593 0.0104205 -0.0253151 -0.0690116 0.0106903 -0.025372 -0.0688582 0.00901923 -0.024833 -0.0683421 0.00971987 -0.0251165 -0.0685636 -0.0127673 -0.0246637 -0.0636868 -0.013317 -0.0251204 -0.0646209 -0.0127926 -0.0242066 -0.0628281 -0.0128553 -0.0245101 -0.062816 -0.0126244 -0.0246136 -0.0645515 -0.0130567 -0.0249556 -0.063712 -0.01345 -0.025065 -0.0637655 -0.0130536 -0.025073 -0.0645895 -0.000516148 -0.0245964 -0.0644724 -0.000352751 -0.0250313 -0.0640377 0.00908313 -0.0250965 -0.0681714 0.00918201 -0.0252674 -0.0679191 -0.0100485 -0.0242866 -0.0606044 -0.000452628 -0.0248619 -0.0642964 -0.0127402 -0.0246433 -0.0613656 -0.0129685 -0.024814 -0.06122 -0.0132644 -0.0248774 -0.0620078 -0.0099849 -0.0245537 -0.0604244 -0.00988402 -0.0247217 -0.0601611 -0.0102064 -0.0242804 -0.0605484 -0.0108883 -0.0245384 -0.0602653 -0.0101559 -0.0245478 -0.0603638 -0.0100756 -0.0247156 -0.0600927 -0.0115542 -0.0242864 -0.0605932 -0.0108829 -0.0242707 -0.0604573 -0.010897 -0.0247061 -0.0599817 -0.0118285 -0.0247625 -0.0598441 -0.011712 -0.0247215 -0.060148 -0.0116151 -0.0245534 -0.0604125 -0.0122569 -0.0245902 -0.0607924 -0.0125475 -0.0240678 -0.0615235 -0.0121465 -0.024325 -0.0609438 -0.0128381 -0.024445 -0.0621208 -0.012592 -0.0243806 -0.0614725 -0.0135838 -0.0250045 -0.0628928 -0.0131907 -0.024895 -0.0628401 -0.0129014 -0.0246032 -0.0628165 -0.0130274 -0.024768 -0.0628241 -0.0130079 -0.0247052 -0.0620691 -0.0126372 -0.0248048 -0.0603302 -0.0132402 -0.0248652 -0.0610588 -0.01243 -0.0247594 -0.0605759 0.00515192 -0.0187104 -0.0491025 0.00533316 -0.0190205 -0.0491193 0.00248179 -0.0208666 -0.0502111 -0.00282877 -0.0234873 -0.0522711 -0.0029167 -0.0231317 -0.0522129 -0.00380573 -0.0232381 -0.0525556 -8.70287e-06 -0.0230047 -0.0517315 0.00269414 -0.0210974 -0.0503524 0.00571924 -0.0194028 -0.0495619 -0.000182201 -0.0228602 -0.0514672 0.00553593 -0.019268 -0.0492835 -0.00255221 -0.0239092 -0.052787 -0.0037546 -0.0236113 -0.0526352 -0.0026979 -0.0237665 -0.0524773 -0.000366358 -0.0226103 -0.0513107 -0.006735 -0.0233916 -0.0536848 -0.00951063 -0.0241963 -0.0551352 -0.00668501 -0.0237664 -0.0537657 -0.00364862 -0.0238981 -0.0528693 -0.00351243 -0.024032 -0.0532037 -0.00657945 -0.0240537 -0.0540022 -0.00644299 -0.0241862 -0.054339 0.00638502 -0.0177306 -0.0476698 0.00583878 -0.0188894 -0.0489551 0.00552528 -0.0184074 -0.0489115 0.00528427 -0.0189465 -0.0491006 0.00566183 -0.0186658 -0.0488866 0.00543441 -0.0191556 -0.0491844 0.00627525 -0.0185858 -0.048531 0.00651862 -0.0187466 -0.048658 0.00603233 -0.0190483 -0.0491078 0.00621649 -0.019121 -0.0493242 0.00595966 -0.0180481 -0.0485279 0.00635362 -0.0181253 -0.0480027 0.00607856 -0.0183401 -0.0484852 0.00654963 -0.018387 -0.0480297 0.00712307 -0.0185919 -0.0482337 0.00677019 -0.0187969 -0.048846 0.00649019 -0.018017 -0.0473845 0.00724742 -0.0185055 -0.0474278 0.00682135 -0.0185518 -0.0481113 0.00643253 -0.0177029 -0.0472285 0.00642672 -0.0177061 -0.0473889 0.00666684 -0.0182686 -0.0472275 0.00666921 -0.018279 -0.0473903 0.00693559 -0.0184509 -0.0474056 -0.0147854 -0.0238641 -0.0520197 -0.0139191 -0.0237644 -0.0535431 -0.0138186 -0.0233812 -0.0535156 -0.0144982 -0.023574 -0.052012 -0.0134829 -0.0242843 -0.0549163 -0.0132565 -0.0241558 -0.0546241 -0.0120922 -0.0242168 -0.0552211 -0.0122047 -0.0243485 -0.0555682 -0.0107942 -0.0242311 -0.0553985 -0.0144156 -0.023628 -0.0524354 -0.0146955 -0.0239177 -0.0524776 -0.0141579 -0.0240532 -0.0536747 -0.013085 -0.0238676 -0.0544223 -0.0120069 -0.0239291 -0.0549754 -0.0119688 -0.0235529 -0.0548888 -0.0108103 -0.0235682 -0.0550466 -0.0108046 -0.0239435 -0.05514 -0.00961589 -0.0239086 -0.0548964 -0.00966484 -0.0235321 -0.0548142 0.006256 -0.0177029 -0.0464148 0.00576346 -0.0177029 -0.0457435 0.00580398 -0.018009 -0.0456981 0.0060921 -0.018442 -0.0453749 0.00528336 -0.0185029 -0.0445688 0.00586966 -0.0177029 -0.0458455 0.00591939 -0.0182686 -0.0455686 0.00646963 -0.0182686 -0.0463185 0.00670626 -0.018442 -0.0462119 0.00629583 -0.0185029 -0.0451464 0.00635681 -0.0177029 -0.0466912 0.00631152 -0.018009 -0.0463898 0.00649343 -0.018009 -0.0472282 0.00692638 -0.018442 -0.0472265 0.00698538 -0.0185029 -0.0460862 -0.0155061 -0.0232356 -0.046824 -0.0161972 -0.0225517 -0.0416336 -0.0165835 -0.0226673 -0.0416686 -0.0143889 -0.0231817 -0.0520411 -0.0151117 -0.0225561 -0.0468561 -0.0152207 -0.0229462 -0.0468216 0.00519033 -0.018442 -0.0448605 0.00511147 -0.0182686 -0.0451077 0.00505877 -0.018009 -0.0452729 -0.0162973 -0.0225268 -0.0411341 -0.0162049 -0.0224805 -0.0411473 -0.0159137 -0.022263 -0.0416356 -0.0158054 -0.0218749 -0.0416741 -0.0159189 -0.0221909 -0.0412084 -0.0160427 -0.0223546 -0.0411766 0.00280096 -0.0183657 -0.0443285 0.00420457 -0.018009 -0.0450005 0.00425727 -0.0182686 -0.0448353 0.00433613 -0.018442 -0.044588 -0.00155375 -0.0191094 -0.0428593 0.00272019 -0.0180946 -0.0445155 0.00290278 -0.0185287 -0.0440491 -0.00131206 -0.0191887 -0.0421543 -0.00168633 -0.0188276 -0.0430877 -0.00837123 -0.0203428 -0.0409499 -0.00823567 -0.0206273 -0.0407081 -0.00809834 -0.0207486 -0.0403556 -0.00141848 -0.0192399 -0.0425219 -0.00799311 -0.0206767 -0.0399794 -0.013145 -0.0211276 -0.0394351 -0.0130357 -0.021412 -0.0392042 -0.0129118 -0.0215474 -0.0388689 -0.0128016 -0.0215027 -0.0385056 -0.0133976 -0.0207947 -0.0394598 -0.0133255 -0.0211586 -0.0393837 -0.0157945 -0.0222257 -0.0393371 -0.0140089 -0.0217475 -0.0387765 -0.0140599 -0.0217389 -0.0384188 -0.0131367 -0.0215785 -0.0388097 -0.0132316 -0.021441 -0.0391495 -0.0139974 -0.0216002 -0.0391065 -0.0147495 -0.0218083 -0.0393261 -0.0148548 -0.0219653 -0.0390406 -0.0155641 -0.0221837 -0.0395646 -0.0158333 -0.0222047 -0.0404224 -0.0160634 -0.0223742 -0.0402878 -0.0140279 -0.0213269 -0.0393411 -0.0153849 -0.0220192 -0.0397824 -0.0147123 -0.0215432 -0.0395398 -0.0158743 -0.0220985 -0.0412246 -0.0147501 -0.0212186 -0.0396423 -0.015287 -0.0217594 -0.0399543 -0.015655 -0.0216431 -0.0406132 -0.0156897 -0.0219477 -0.0405368 0.00772597 -0.0182459 -0.0513255 -0.00208235 -0.0233602 -0.0551064 0.000543147 -0.0226994 -0.0540943 -0.00209249 -0.0236863 -0.0550357 0.000591651 -0.0234237 -0.053396 0.00974287 -0.018442 -0.0500187 0.0098986 -0.018009 -0.0504227 0.00988195 -0.0181029 -0.0503795 0.00983622 -0.0182686 -0.0502609 0.00782231 -0.0185567 -0.0512082 0.00436414 -0.021034 -0.0522823 0.00784685 -0.0188094 -0.0509733 0.00779502 -0.0189568 -0.0506647 0.00415015 -0.0205023 -0.0527039 0.000637998 -0.0230241 -0.0539709 0.000655336 -0.0232831 -0.0537213 0.00430313 -0.0207991 -0.0525555 0.00432047 -0.0211579 -0.0519413 0.000459843 -0.0234177 -0.053061 0.0099205 -0.0177029 -0.0504795 0.0123783 -0.0181029 -0.0494172 0.0122729 -0.0183957 -0.049144 0.00977663 -0.0183957 -0.0501063 -0.0033531 -0.0242057 -0.0546466 -0.00224754 -0.0241212 -0.0545743 -0.00308012 -0.0237369 -0.0554167 -0.00215095 -0.0239555 -0.0548475 -0.00313877 -0.024006 -0.055229 -0.00405686 -0.0234607 -0.0558676 -0.0040678 -0.0237859 -0.0557976 -0.00412664 -0.0240548 -0.0556105 -0.00422321 -0.0242209 -0.0553388 -0.00323535 -0.0241718 -0.0549566 0.0124168 -0.0177029 -0.0495172 0.0133495 -0.0177029 -0.0493948 0.0133609 -0.0181029 -0.0492882 0.0151346 -0.0177029 -0.0513043 0.0144548 -0.0183957 -0.049378 0.0142939 -0.0181029 -0.0496227 0.0149707 -0.0181029 -0.0503467 0.0152257 -0.0183957 -0.0502027 0.0152417 -0.0181029 -0.0513001 0.0155343 -0.0183957 -0.0512885 0.0133922 -0.0183957 -0.048997 -0.00467015 -0.0235244 -0.0562424 -0.00483439 -0.0235511 -0.0564073 -0.00469632 -0.0238444 -0.0561757 -0.00509066 -0.0236084 -0.0567712 -0.00513277 -0.023922 -0.0567135 -0.005367 -0.0240114 -0.0573678 -0.00531097 -0.0237042 -0.0574091 -0.00514302 -0.0241823 -0.0587202 -0.00551275 -0.0243547 -0.0564571 -0.00609322 -0.0245963 -0.0581419 -0.0057953 -0.0245314 -0.0580957 -0.00480767 -0.0241106 -0.0560199 -0.00528148 -0.024185 -0.0566028 -0.0053706 -0.0241014 -0.0580633 -0.00470988 -0.0242465 -0.0592643 -0.00485726 -0.0239279 -0.0590338 -0.00518814 -0.0247503 -0.0597611 -0.00438957 -0.0247949 -0.0602569 -0.00499381 -0.0246746 -0.0595475 -0.00529601 -0.0244361 -0.0587821 -0.00551812 -0.0246112 -0.0588903 -0.00554187 -0.0243578 -0.0580681 -0.0057937 -0.0244426 -0.0572525 -0.00553667 -0.0242709 -0.0573127 -0.00498547 -0.0242783 -0.0558013 -0.00413619 -0.0243742 -0.0596695 -0.00482663 -0.0244985 -0.0593739 -0.00424524 -0.024666 -0.0599125 0.015934 -0.0185029 -0.0512727 0.0157597 -0.0183957 -0.0565703 0.0155942 -0.0182686 -0.0565778 0.0154672 -0.0181029 -0.0565837 -0.00408924 -0.0239981 -0.0595871 -0.00411877 -0.0242887 -0.0596341 0.00619385 -0.0243343 -0.0637581 0.0108201 -0.0252619 -0.0664546 -0.00418537 -0.0245395 -0.0597761 0.00614814 -0.0247154 -0.0638439 0.010965 -0.0251416 -0.0660999 -0.00427995 -0.0247163 -0.0599936 0.00603832 -0.0250085 -0.0640939 0.0159254 -0.020492 -0.0627408 0.0160559 -0.0205766 -0.0626834 0.0160141 -0.0201708 -0.0619902 0.0168011 -0.0201875 -0.0619394 0.0164024 -0.0202697 -0.061914 0.0161593 -0.0185029 -0.056552 0.0161511 -0.0188865 -0.0588992 0.0158535 -0.018442 -0.056566 0.0158057 -0.0187517 -0.0589588 0.0156811 -0.019984 -0.0630563 0.0157371 -0.0199164 -0.0621481 0.0155651 -0.0184803 -0.0590565 0.0154824 -0.0181322 -0.0591707 0.015421 -0.018009 -0.0565858 0.0153602 -0.0177029 -0.0565886 0.0120672 -0.0244587 -0.0661404 0.01112 -0.0244632 -0.0657562 0.0110746 -0.0248511 -0.0658463 0.0120452 -0.0248171 -0.0662231 0.0119641 -0.0250994 -0.0664454 0.013012 -0.0247316 -0.066601 0.0158249 -0.0211833 -0.0643834 0.0166472 -0.0215761 -0.0640954 0.0157756 -0.0203253 -0.062848 0.0157824 -0.020719 -0.0636363 0.0159721 -0.0209494 -0.0634849 0.0162579 -0.0210906 -0.063383 0.0164481 -0.0206716 -0.0626059 0.0165896 -0.0211179 -0.0633482 0.0153417 -0.0232846 -0.0660793 0.0156611 -0.0235076 -0.0661602 0.0159707 -0.0236022 -0.0663915 0.0134149 -0.0250764 -0.0671919 0.0143118 -0.0245933 -0.0668749 0.0157908 -0.023563 -0.0662372 0.0148296 -0.0238752 -0.0664678 0.0150639 -0.0241065 -0.0666017 0.0134283 -0.0246482 -0.0667118 0.0134391 -0.0249112 -0.0669087 0.0129565 -0.0250023 -0.0667965 0.0149343 -0.0232164 -0.0662944 0.0146218 -0.023587 -0.0664788 0.014046 -0.0240521 -0.0666515 0.0141808 -0.0243476 -0.0667005 0.0133842 -0.0243318 -0.0666344 0.0163258 -0.0216421 -0.0642588 0.0166591 -0.0216687 -0.0642422 0.0157628 -0.0209015 -0.0645609 0.0160191 -0.0214146 -0.0642298 0.0160346 -0.0215039 -0.064349 0.0169684 -0.0214773 -0.0641387 0.0157659 -0.0210053 -0.0646771 0.0158364 -0.0212785 -0.0644971 0.0156834 -0.0222554 -0.0654262 0.015891 -0.0224392 -0.0653462 0.0163107 -0.0215539 -0.0641277 0.0155515 -0.0220442 -0.065572 0.0150917 -0.0229883 -0.0661686 0.0152294 -0.023171 -0.0660949 0.0154025 -0.0233372 -0.0660819 0.0161475 -0.0225715 -0.0653425 0.0155954 -0.0234719 -0.0661308 0.016976 -0.0215793 -0.0643021 0.0164193 -0.0226352 -0.0654156 0.0166711 -0.0226221 -0.0655559 0.0024977 -0.018442 -0.0418895 0.00252622 -0.0183957 -0.0418001 -0.00537317 -0.0193972 -0.0391029 -0.0021822 -0.0187833 -0.0401543 -0.0022426 -0.0189478 -0.0404355 -0.002166 -0.0185185 -0.0399557 -0.00541082 -0.0188466 -0.0388488 -0.00537079 -0.0191442 -0.0389244 0.00261519 -0.0181029 -0.0415211 -0.0085988 -0.0186292 -0.0349455 -0.00804849 -0.0183287 -0.0344624 -0.00808215 -0.0180227 -0.0345619 -0.00793762 -0.018286 -0.0344007 -0.00893963 -0.0189703 -0.0355812 -0.00898091 -0.0188657 -0.0359763 -0.00862781 -0.0196315 -0.0374574 -0.00858955 -0.0194094 -0.0374552 -0.00809121 -0.0185847 -0.0342692 -0.00904992 -0.0191959 -0.0354616 -0.00904073 -0.0192753 -0.0362571 -0.00892688 -0.0195016 -0.0368959 -0.00815748 -0.0196491 -0.037911 -0.00814917 -0.0194292 -0.0378791 -0.00839662 -0.0194348 -0.0376734 -0.00807325 -0.0187083 -0.0339423 -0.00820331 -0.0187487 -0.0340139 -0.0090696 -0.0191011 -0.034391 -0.00947934 -0.019452 -0.0352377 -0.00940256 -0.0199973 -0.0369522 -0.00837612 -0.0201467 -0.0382675 -0.00827551 -0.0200223 -0.0381131 -0.00756762 -0.0196136 -0.038222 -0.00756977 -0.0198645 -0.0383957 -0.00820071 -0.019852 -0.0379911 -0.00871354 -0.019836 -0.0374979 -0.00903868 -0.01971 -0.0368872 -0.00883992 -0.0200066 -0.0375735 -0.009202 -0.0198802 -0.0369066 -0.00916123 -0.0194904 -0.0361932 -0.00934608 -0.0196594 -0.0361471 -0.00923738 -0.0193632 -0.0353423 -0.00884552 -0.0190347 -0.0345848 -0.00868068 -0.0188694 -0.0347789 0.0122255 -0.0177029 -0.0444737 0.00262926 -0.018009 -0.041477 0.0121543 -0.0182686 -0.044697 0.00257656 -0.0182686 -0.0416422 0.0119824 -0.0185029 -0.0452359 -0.00618419 -0.0177029 -0.0334995 -0.00707883 -0.0180875 -0.033925 -0.00713533 -0.0183482 -0.0337489 -0.00621383 -0.018009 -0.0334463 -0.00642459 -0.018442 -0.0330681 -0.00739326 -0.0185692 -0.0332228 -0.00708554 -0.0177774 -0.0340018 -0.00797322 -0.0185442 -0.0342054 -0.00822112 -0.018751 -0.0336552 -0.00724603 -0.0185177 -0.0335017 0.0149963 -0.0183957 -0.0436079 0.0121039 -0.0183957 -0.0448548 0.0132355 -0.0183957 -0.0449343 0.0149395 -0.0181029 -0.0425068 0.0146358 -0.0177029 -0.0434346 0.0147324 -0.0181029 -0.043481 0.0140366 -0.0177029 -0.0441658 0.0131864 -0.0181029 -0.0446457 0.012207 -0.018009 -0.0445317 0.0152322 -0.0183957 -0.0424983 0.0141011 -0.0181029 -0.0442514 0.0142772 -0.0183957 -0.0444852 0.0121929 -0.0181029 -0.0445758 0.015632 -0.0185029 -0.0424866 0.0153569 -0.0185029 -0.0437812 0.0133026 -0.0185029 -0.0453287 0.0120754 -0.018442 -0.0449442 0.0114793 -0.0181029 -0.0235333 -0.00629825 -0.0182686 -0.0332948 0.0113368 -0.0183957 -0.0232775 0.015305 -0.0185029 -0.0253488 0.014905 -0.0183957 -0.0253524 0.0146122 -0.0181029 -0.025355 0.0148323 -0.0177029 -0.0425099 0.0125244 -0.0181029 -0.0232669 0.0142342 -0.0177029 -0.0243689 0.014505 -0.0177029 -0.025356 0.0114174 -0.0182686 -0.0234222 0.0135643 -0.0181029 -0.0235524 0.0143269 -0.0181029 -0.024315 0.012527 -0.0183957 -0.0229741 0.0125307 -0.0185029 -0.0225741 0.0137115 -0.0183957 -0.0232992 0.0139126 -0.0185029 -0.0229534 0.01458 -0.0183957 -0.0241679 -0.00232445 -0.00450288 -0.100065 -0.0016927 -0.00450288 -0.10302 -0.0016927 -0.00250288 -0.10302 0.00998613 -0.00450288 -0.15963 0.00998613 -0.00250288 -0.15963 0.00804757 -0.00250288 -0.148581 0.0227301 -0.00250288 -0.160721 0.00869429 -0.00250288 -0.147917 0.00960853 -0.00250288 -0.14807 0.00802397 -0.00250288 -0.149058 0.0224573 -0.00250288 -0.157778 0.0122625 -0.00250288 -0.171052 0.0131298 -0.00250288 -0.171111 0.0168574 -0.00250288 -0.226163 0.0168306 -0.00450288 -0.235606 0.0361186 -0.00250288 -0.241767 0.016551 -0.00250288 -0.256878 0.0170061 -0.00250288 -0.256888 0.0172308 -0.00250288 -0.225369 0.035589 -0.00250288 -0.239334 0.0168306 -0.00250288 -0.235606 0.01588 -0.00250288 -0.256298 0.0158032 -0.00250288 -0.25585 0.0174188 -0.00250288 -0.256696 0.0164551 -0.00250288 -0.245017 0.0355591 -0.00250288 -0.242457 -0.0122845 -0.00260288 -0.0497648 -0.0126677 -0.00450288 -0.0476327 -0.0130665 -0.00250288 -0.045394 -0.0130482 -0.00254644 -0.0454972 -0.0138676 -0.00450288 -0.0408358 -0.00246386 0.00254075 -0.099411 -0.00288406 0.00449712 -0.0974335 -0.00106731 0.00449712 -0.105932 0.0117687 0.00449712 -0.170337 0.00998613 0.00249712 -0.15963 0.00802397 0.00449712 -0.149058 0.00960853 0.00249712 -0.14807 0.00917014 0.00249712 -0.147881 0.0232431 0.00249712 -0.159189 0.0227301 0.00249712 -0.160721 0.022999 0.00249712 -0.158401 0.0126895 0.00249712 -0.171181 0.0117687 0.00249712 -0.170337 0.0131298 0.00249712 -0.171111 0.015418 0.00249712 -0.201875 0.0289219 0.00249712 -0.196669 0.019099 0.00249712 -0.195928 0.0156218 0.00249712 -0.185389 0.0139821 0.00249712 -0.186275 0.0185668 0.00249712 -0.200999 0.0295072 0.00249712 -0.19888 0.0290841 0.00249712 -0.199566 0.0194698 0.00249712 -0.19991 0.0167059 0.00249712 -0.211496 0.0176696 0.00249712 -0.211573 0.0163712 0.00249712 -0.211126 0.016261 0.00249712 -0.210755 0.0179848 0.00249712 -0.211348 0.0140225 0.00249712 -0.185847 0.0164551 0.00449712 -0.245017 0.0168306 0.00449712 -0.235606 0.0158032 0.00249712 -0.25585 0.0164551 0.00249712 -0.245017 0.0361352 0.00249712 -0.240035 0.0355591 0.00249712 -0.242457 0.0169525 0.00249712 -0.225723 0.0172308 0.00249712 -0.225369 0.0168574 0.00249712 -0.226163 0.0168306 0.00249712 -0.235606 0.0161478 0.00249712 -0.256666 0.01588 0.00249712 -0.256298 -0.0114785 0.00249712 -0.054192 -0.0122257 0.00254075 -0.0500905 -0.0114785 0.00449712 -0.054192 -0.0126677 0.00449712 -0.0476327 -0.0129903 0.00259712 -0.0458235 -0.0126677 0.00259712 -0.0476327 -0.0183419 -0.0155029 -0.0205053 0.0146998 0.0154971 -0.0155976 0.0147046 0.0154971 -0.0145018 0.0147046 -0.0180029 -0.0145018 0.0146512 -0.0155029 -0.0142752 0.0146512 -0.0180029 -0.0142752 0.014501 -0.0155029 -0.0140972 0.0142866 -0.0155029 -0.0140066 0.0142866 -0.0180029 -0.0140066 0.0142109 -0.0155029 -0.0179863 -0.00652182 0.0153507 -0.0294306 -0.0121216 0.0153507 -0.0299185 -0.0153459 0.0130829 -0.0248829 -0.0151104 0.0130829 -0.026005 -0.0123184 0.0130829 -0.0276592 -0.014443 0.0130829 -0.0269372 -0.00591978 0.0153507 -0.0293454 -0.00398738 0.0130829 -0.0253191 -0.00398263 0.0150951 -0.0282658 -0.00576862 0.0147092 -0.0189432 -0.00449163 0.0148662 -0.0192857 -0.00286992 0.0153507 -0.0276457 -0.0153453 0.0130829 -0.0231953 -0.0176133 0.0153507 -0.0239026 -0.00701051 0.0149758 -0.0185198 -0.00793164 0.0153507 -0.0181445 -0.0139515 0.0130829 -0.0207833 -0.0125577 -0.0153564 -0.0181428 -0.0139515 -0.0130887 -0.0207833 -0.0150847 -0.0153564 -0.0188189 -0.0169351 -0.0153564 -0.020668 -0.0153453 -0.0130887 -0.0231953 -0.0123184 -0.0130887 -0.0276592 -0.0159757 -0.0153564 -0.0286086 -0.0151104 -0.0130887 -0.026005 -0.0173143 -0.0153564 -0.0265976 -0.0053613 -0.0130887 -0.0208425 -0.00577399 -0.0147152 -0.0189415 -0.00591978 -0.0153564 -0.0293454 -0.00511204 -0.0130887 -0.0266005 -0.00286992 -0.0153564 -0.0276457 -0.00196121 -0.0153564 -0.0263376 -0.00136421 -0.0153564 -0.0235539 -0.00362985 -0.0130887 -0.023652 -0.00219953 -0.0153564 -0.0208322 -0.00671863 -0.0130887 -0.0271714 -0.00652182 -0.0153564 -0.0294306 -0.0125576 -0.0154648 -0.0179806 -0.00793164 -0.0153564 -0.0181445 -0.0179666 -0.0155029 -0.0231943 -0.0170755 -0.0154648 -0.0205868 -0.0176131 -0.0153564 -0.0231945 -0.0151657 -0.0154648 -0.0186784 -0.0172412 -0.0155029 -0.0204911 -0.0176133 -0.0153564 -0.0239026 -0.0177753 -0.0154648 -0.0231944 -0.0179669 -0.0155029 -0.0239025 -0.0177756 -0.0154648 -0.0239026 -0.0177352 -0.015453 -0.0248747 -0.0178048 -0.0155029 -0.025338 -0.0176469 -0.0155029 -0.0267175 -0.0174669 -0.0154648 -0.0266526 -0.0178581 -0.0155029 -0.0248678 -0.0177091 -0.015455 -0.0253318 -0.0176299 -0.0153726 -0.0248821 -0.0176257 -0.0153878 -0.0253269 -0.0120909 -0.0155029 -0.0302707 -0.0121216 -0.0153564 -0.0299185 -0.0121075 -0.0154648 -0.0300801 -0.0142385 -0.0154648 -0.0298223 -0.0141863 -0.0153564 -0.0296687 -0.0160853 -0.0154648 -0.0287281 -0.0162146 -0.0155029 -0.0288692 -0.00651217 -0.0154402 -0.0295414 -0.00650103 -0.0154897 -0.0296693 -0.00620672 -0.0154395 -0.0295053 -0.00247264 -0.0154624 -0.0274243 -0.00189855 -0.0155029 -0.0206467 -0.00181628 -0.0154648 -0.0264105 -0.00101098 -0.0155029 -0.0235386 -0.00120215 -0.0154648 -0.0235469 -0.00206144 -0.0154648 -0.0207471 -0.0029189 -0.0154849 -0.0195852 0.0142866 0.0154971 -0.0140066 0.014501 0.0154971 -0.0140972 0.0146506 0.0179971 -0.0142739 0.0146512 0.0154971 -0.0142752 -0.0125576 0.0154591 -0.0179806 -0.00830997 0.0154622 -0.0179745 -0.0125577 0.0153507 -0.0181428 -0.0151657 0.0154591 -0.0186784 -0.0150847 0.0153507 -0.0188189 -0.0170755 0.0154591 -0.0205868 -0.0169351 0.0153507 -0.020668 -0.0176131 0.0153507 -0.0231945 -0.0179666 0.0154971 -0.0231943 -0.0177753 0.0154591 -0.0231944 -0.0179669 0.0154971 -0.0239025 -0.0176299 0.0153668 -0.0248821 -0.0177352 0.0154473 -0.0248747 -0.0177756 0.0154591 -0.0239026 -0.0176257 0.015382 -0.0253269 -0.0173143 0.0153507 -0.0265976 -0.0174669 0.0154591 -0.0266526 -0.0178048 0.0154971 -0.025338 -0.0177091 0.0154492 -0.0253318 -0.0160853 0.0154591 -0.0287281 -0.0159757 0.0153507 -0.0286086 -0.0141863 0.0153507 -0.0296687 -0.0121075 0.0154591 -0.0300801 -0.0162146 0.0154971 -0.0288692 -0.0142385 0.0154591 -0.0298223 -0.00650103 0.0154839 -0.0296693 -0.00674442 0.0154971 -0.0298049 -0.00620672 0.0154337 -0.0295053 -0.00651217 0.0154345 -0.0295414 -0.0027 0.0154971 -0.0196166 -0.00331416 0.0153507 -0.0195223 -0.0020558 0.0154971 -0.0271921 -0.00196121 0.0153507 -0.0263376 -0.00136421 0.0153507 -0.0235539 -0.00181628 0.0154591 -0.0264105 -0.00219953 0.0153507 -0.0208322 -0.00189855 0.0154971 -0.0206467 -0.00206144 0.0154591 -0.0207471 -0.00120215 0.0154591 -0.0235469 -0.00164532 0.0154971 -0.0264964 -0.00247264 0.0154567 -0.0274243 -0.00701143 -0.0116745 -0.0209984 -0.0125587 -0.0124398 -0.0208441 -0.0125585 -0.0130887 -0.0204106 -0.0144644 -0.0116745 -0.0220956 -0.0137349 -0.0124398 -0.0211588 -0.0149716 -0.0130887 -0.0218026 -0.0145962 -0.0124398 -0.0220195 -0.00535539 -0.0124398 -0.0262417 -0.00398738 -0.0130887 -0.0253191 -0.00413011 -0.0130887 -0.022022 -0.00406299 -0.0124398 -0.0236707 -0.00449919 -0.0124398 -0.0222495 -0.00557273 -0.0124398 -0.021221 -0.00701121 -0.0130887 -0.0204126 -0.00701137 -0.0124398 -0.0208462 -0.00437474 -0.0124398 -0.0251244 -0.00421509 -0.0116745 -0.0236773 -0.00564698 -0.0116745 -0.0213539 -0.0149118 -0.0124398 -0.0231955 -0.00675626 -0.0124398 -0.0267395 -0.012356 -0.0124398 -0.0272273 -0.0147135 -0.0124398 -0.0258305 -0.0149124 -0.0124398 -0.0248831 -0.0153459 -0.0130887 -0.0248829 -0.014443 -0.0130887 -0.0269372 -0.0134566 -0.0130887 -0.0275216 -0.0141499 -0.0124398 -0.0266176 -0.0145742 -0.0116745 -0.0257693 -0.0133171 -0.0124398 -0.0271111 -0.0123692 -0.0116745 -0.0270757 -0.0145962 0.0124341 -0.0220195 -0.0137349 0.0124341 -0.0211588 -0.0125587 0.0124341 -0.0208441 -0.0149118 0.0124341 -0.0231955 -0.0149716 0.0130829 -0.0218026 -0.0147595 0.0116687 -0.0231955 -0.0141146 0.0116687 -0.0216401 -0.012356 0.0124341 -0.0272273 -0.0134566 0.0130829 -0.0275216 -0.0141499 0.0124341 -0.0266176 -0.0133171 0.0124341 -0.0271111 -0.0147135 0.0124341 -0.0258305 -0.0149124 0.0124341 -0.0248831 -0.00701137 0.0124341 -0.0208462 -0.0125585 0.0130829 -0.0204106 -0.00675626 0.0124341 -0.0267395 -0.00671863 0.0130829 -0.0271714 -0.00701143 0.0116687 -0.0209984 -0.00701121 0.0130829 -0.0204126 -0.0053613 0.0130829 -0.0208425 -0.00413011 0.0130829 -0.022022 -0.00362985 0.0130829 -0.023652 -0.00406299 0.0124341 -0.0236707 -0.00511204 0.0130829 -0.0266005 -0.00557273 0.0124341 -0.021221 -0.00449919 0.0124341 -0.0222495 -0.00421509 0.0116687 -0.0236773 -0.00437474 0.0124341 -0.0251244 -0.00544084 0.0116687 -0.0261157 -0.00535539 0.0124341 -0.0262417 -0.00676947 0.0116687 -0.0265878 0.0136679 0.0154971 -0.0184296 0.0142109 0.0179971 -0.0179863 0.0145676 0.0179971 -0.0173829 0.0145676 0.0154971 -0.0173829 0.0146942 0.0179971 -0.0166935 -0.0120947 0.00159712 -0.0507467 -0.0161411 0.00159712 -0.0514705 -0.0120947 -0.00160288 -0.0507467 -0.00884078 -0.00250288 -0.0450853 -0.00884078 0.00249712 -0.0450853 -0.0131512 0.00168845 -0.0448405 -0.01295 0.00159712 -0.0448045 -0.0100012 0.00249712 -0.044277 -0.01295 -0.00160288 -0.0448045 -0.0131512 -0.00169421 -0.0448405 0.0171748 -0.00250288 -0.286328 0.0171748 0.00249712 -0.286328 0.0139806 -0.00250288 -0.286136 0.0139806 -0.00160288 -0.286136 0.00483683 0.00159712 -0.285585 0.0168143 0.00249712 -0.292317 0.0152172 -0.00250288 -0.292221 0.0139793 0.00539712 -0.186245 0.0154484 0.00259712 -0.202024 0.0162584 0.00259712 -0.210724 0.0139821 0.00259712 -0.186275 0.0139791 0.00259712 -0.186245 0.0147854 0.00300465 -0.194902 0.0153806 0.00332917 -0.201295 0.0113723 -0.00216558 -0.201669 0.0153806 -0.00260288 -0.201295 0.0114677 -0.00160288 -0.20166 0.0185668 -0.00250288 -0.200999 0.0114677 0.00159712 -0.20166 0.0138287 0.00159712 -0.195414 0.0180106 0.00249712 -0.195025 0.0145265 0.00240681 -0.195349 0.014188 0.00197035 -0.195381 0.0142403 0.00202943 -0.195376 -0.00232445 -0.00590288 -0.100065 -0.00232445 -0.00250288 -0.100065 -0.00232516 -0.00160288 -0.100065 0.000748719 0.00249712 -0.0943037 -0.00789663 0.00259712 -0.0951121 -0.00356819 0.00259712 -0.0941956 -0.00757846 -0.00160288 -0.0950447 -0.00767221 -0.00216559 -0.0950646 0.0173215 0.00249712 -0.292213 0.0177088 0.00249712 -0.29187 0.0178726 0.00249712 -0.291379 0.0176658 -0.00250288 -0.286492 0.0176658 0.00249712 -0.286492 0.0180092 0.00249712 -0.286879 0.019099 -0.00250288 -0.195928 0.0189877 -0.00250288 -0.195554 0.0189877 0.00249712 -0.195554 0.0187418 0.00249712 -0.195251 0.0183987 0.00249712 -0.195065 0.0183987 -0.00250288 -0.195065 0.000594976 0.00249712 -0.0939451 0.000594976 -0.00250288 -0.0939451 -0.000436742 0.00249712 -0.0935325 -4.65907e-05 -0.00250288 -0.0935277 -0.00894475 -0.00250288 -0.0501832 -0.00847615 -0.00250288 -0.0499633 -0.00818029 -0.00250288 -0.0495386 -0.00813645 0.00249712 -0.0490228 -0.0089831 -0.00250288 -0.044722 -0.00925361 0.00249712 -0.0444408 -0.00961113 0.00249712 -0.0442845 0.0153727 -0.00590888 -0.267827 0.0151796 -0.00590288 -0.267496 0.0151257 -0.00590288 -0.267107 0.0150783 -0.00643067 -0.267495 0.0150742 -0.00643753 -0.26749 0.0149358 -0.00702709 -0.261824 0.0146802 -0.00720192 -0.262024 0.015017 -0.00646392 -0.2671 0.0153079 -0.00652297 -0.261846 0.0149251 -0.00665288 -0.267094 0.0152412 -0.00665288 -0.261842 0.0154274 -0.00648867 -0.261438 0.0154418 -0.00590288 -0.261854 0.0155543 -0.00590288 -0.26145 0.015017 0.00645815 -0.2671 0.0150764 0.00642808 -0.267493 0.0151257 0.00589712 -0.267107 0.0154418 0.00589712 -0.261854 0.0156393 0.00617924 -0.261271 0.0158226 0.00589712 -0.261127 0.0153079 0.0065172 -0.261846 0.0149358 0.00702133 -0.261824 0.011733 0.00739712 -0.302055 0.0136323 0.00645512 -0.302199 0.0134643 0.0066272 -0.302205 0.0137021 0.00589712 -0.302112 0.0131491 0.00690166 -0.302215 0.0129909 0.00701515 -0.30222 0.0132155 0.00664712 -0.302022 0.0124361 0.00719616 -0.301794 0.0123298 0.00719616 -0.30108 0.0129508 0.00664712 -0.301603 0.0115811 0.00739712 -0.301035 0.0128778 0.00664712 -0.301113 0.014543 0.00664712 -0.273444 0.0143051 0.00695778 -0.273429 0.0138193 0.00728294 -0.2734 0.0158528 0.00690166 -0.272134 0.0153838 0.00729 -0.271606 0.0147143 0.00728294 -0.271887 0.014084 0.00728294 -0.272535 0.0156142 0.00695778 -0.272082 0.0155692 0.00717214 -0.271815 0.0145029 0.00695778 -0.272783 0.013995 0.00719616 -0.273411 0.0151474 0.00647114 -0.272573 0.0149739 0.00695778 -0.272298 0.015643 0.00647114 -0.272406 0.0147828 0.00647114 -0.272949 0.0146296 0.00647114 -0.273449 0.0134643 -0.00663296 -0.302205 0.013363 -0.00590288 -0.301885 0.0141035 -0.00590888 -0.302184 0.0124376 -0.00720192 -0.301798 0.0132196 -0.00665288 -0.302026 0.01314 -0.00590288 -0.301535 0.0130032 -0.00701265 -0.302219 0.0124429 -0.00729576 -0.302237 0.0129518 -0.00665288 -0.301606 0.0128778 -0.00665288 -0.301113 0.0132463 -0.00740288 -0.273366 0.0138193 -0.0072887 -0.2734 0.0143051 -0.00696354 -0.273429 0.0123298 -0.00720192 -0.30108 0.0152083 -0.00590288 -0.27267 0.0158528 -0.00690742 -0.272134 0.0161786 -0.00645289 -0.272501 0.0164865 -0.00590888 -0.272848 0.0161175 -0.00590288 -0.272589 0.015643 -0.00647691 -0.272406 0.0146296 -0.00647691 -0.273449 0.014543 -0.00665288 -0.273444 0.0147828 -0.00647691 -0.272949 0.0161367 -0.00651961 -0.272454 0.0156142 -0.00696354 -0.272082 0.0149739 -0.00696354 -0.272298 0.0147143 -0.0072887 -0.271887 0.0153983 -0.00728816 -0.271622 0.013995 -0.00720192 -0.273411 0.0151474 -0.00647691 -0.272573 0.0145029 -0.00696354 -0.272783 0.014084 -0.0072887 -0.272535 0.000841741 -0.00740288 -0.115092 0.00167816 -0.00715157 -0.115553 0.00119139 -0.00665288 -0.117329 0.00066711 -0.00720192 -0.116651 0.00139484 -0.00590288 -0.116832 0.00119984 -0.00665288 -0.116784 0.0014481 -0.00665288 -0.116299 -6.06158e-05 -0.00740288 -0.11647 0.00102886 -0.00720192 -0.115944 0.00241152 -0.00590288 -0.116075 0.00188508 -0.00665288 -0.115974 0.00160148 -0.00719596 -0.115511 0.00138902 -0.00729576 -0.115394 -7.82079e-05 -0.00740288 -0.117604 0.000654795 -0.00720192 -0.117445 0.00182062 -0.00740288 -0.1264 0.00442371 -0.00720192 -0.13505 0.00255393 -0.00720192 -0.126243 0.00472778 -0.00696354 -0.134986 0.00309074 -0.00665288 -0.126128 0.00504603 -0.00647691 -0.134919 0.00328723 -0.00590288 -0.126086 0.00634931 -0.00647691 -0.135785 0.00538824 -0.00590288 -0.135354 0.00515779 -0.00590288 -0.134896 0.00530279 -0.00647691 -0.13543 0.00496109 -0.00665288 -0.134937 0.00567465 -0.00696354 -0.136054 0.00599128 -0.00695947 -0.136119 0.005779 -0.00647691 -0.135746 0.00604476 -0.00690742 -0.136074 0.00677593 -0.00590888 -0.13546 0.00505947 -0.00696354 -0.135646 0.00469532 -0.0072887 -0.135969 0.0063901 -0.00701475 -0.139075 0.00653097 -0.00740288 -0.13893 0.00652855 -0.00739676 -0.138932 0.00632173 -0.00714623 -0.139147 0.00607291 -0.00740288 -0.139318 0.00624001 -0.00727613 -0.139207 0.00593627 -0.00710679 -0.139769 0.00547765 -0.00740288 -0.140361 0.00618528 -0.00724017 -0.139273 0.00609662 -0.00718949 -0.139402 0.00587625 -0.00707848 -0.140153 0.00611179 -0.00675861 -0.139669 0.00611798 -0.00663941 -0.14 0.00587527 -0.00707845 -0.1402 0.00627805 -0.00707123 -0.13921 0.00621063 -0.00696173 -0.139332 0.00628562 -0.00672669 -0.139237 0.00618589 -0.00638341 -0.139543 0.00618754 -0.00613929 -0.13986 0.00612491 -0.00663015 -0.140038 0.00659299 -0.00668429 -0.142271 0.00619447 -0.00611568 -0.139897 0.00593794 -0.0070813 -0.14092 0.00543287 -0.00740288 -0.140837 0.00623893 -0.00707916 -0.141959 0.00626564 -0.00658918 -0.140838 0.00652937 -0.00663442 -0.142016 0.00664843 -0.00612507 -0.142124 0.00655301 -0.00697942 -0.142415 0.00622653 -0.00740288 -0.142381 0.00658526 -0.00701973 -0.14248 0.00677407 -0.00647873 -0.142633 0.00671078 -0.00622589 -0.142432 0.00632484 -0.00709172 -0.14216 0.00647621 -0.0068974 -0.142208 0.00708368 -0.00739982 -0.143029 0.00697196 -0.00710403 -0.142929 0.0068026 -0.00658095 -0.142693 0.00708178 -0.00740288 -0.143027 0.00688371 -0.00725466 -0.142855 0.00821208 -0.00647691 -0.148086 0.00870255 -0.00590288 -0.147915 0.00884279 -0.00690742 -0.147491 0.00878708 -0.00695947 -0.147449 0.0077804 -0.00740288 -0.146688 0.00918154 -0.00590288 -0.147883 0.00960463 -0.00590888 -0.148067 0.00923442 -0.00645289 -0.147787 0.00798048 -0.00696354 -0.147857 0.00866794 -0.00647691 -0.147806 0.00856937 -0.00696354 -0.147496 0.00845449 -0.00720676 -0.147198 0.00829647 -0.00728816 -0.147078 0.00827907 -0.00729576 -0.147065 0.00791187 -0.00647691 -0.14908 0.00782667 -0.00665288 -0.149096 0.00793909 -0.00647691 -0.148545 0.00716197 -0.0072887 -0.148311 0.00759265 -0.00696354 -0.149141 0.00829341 -0.00590288 -0.148166 0.00762782 -0.00696354 -0.148451 0.00763386 -0.0072887 -0.147516 0.00661246 -0.00740288 -0.148145 0.00722499 -0.00740288 -0.147113 0.00728767 -0.00720192 -0.149201 0.0085174 -0.00740288 -0.159938 0.00999454 -0.00590288 -0.159677 0.00925597 -0.00720192 -0.159808 0.0102866 -0.00740288 -0.170568 0.0116559 -0.00647691 -0.170354 0.00979664 -0.00665288 -0.159712 0.0128026 -0.00695947 -0.171617 0.0123738 -0.00729576 -0.172088 0.0115329 -0.00740288 -0.172363 0.0126908 -0.00647691 -0.171295 0.0131802 -0.00645289 -0.171203 0.0120522 -0.00696354 -0.171438 0.0126716 -0.00696354 -0.17162 0.0118139 -0.0072887 -0.171862 0.0123885 -0.00728816 -0.172072 0.0119354 -0.00590288 -0.170753 0.0117687 -0.00590288 -0.170337 0.0118416 -0.00647691 -0.170818 0.0122113 -0.00647691 -0.171154 0.0115745 -0.00696354 -0.171004 0.0111748 -0.0072887 -0.171281 0.0115701 -0.00665288 -0.170368 0.0113346 -0.00696354 -0.170405 0.0110277 -0.00720192 -0.170452 0.0128773 -0.00740288 -0.175248 0.012872 -0.00740288 -0.175254 0.0126169 -0.00740288 -0.175534 0.0127089 -0.00725466 -0.175459 0.0120211 -0.00740288 -0.176188 0.0128736 -0.00739982 -0.175252 0.0126375 -0.00644295 -0.175717 0.012442 -0.00696952 -0.176005 0.0126277 -0.00636041 -0.175772 0.0119418 -0.00740288 -0.176275 0.012253 -0.00709915 -0.176257 0.0124202 -0.00694357 -0.17608 0.0126267 -0.00604886 -0.176063 0.0125282 -0.00662116 -0.17625 0.0125183 -0.00669258 -0.176081 0.0116978 -0.00740288 -0.176605 0.0115415 -0.00740288 -0.176936 0.0122005 -0.00709883 -0.176441 0.01219 -0.00717721 -0.178009 0.0114243 -0.00740288 -0.17775 0.0116333 -0.00740288 -0.17852 0.0123684 -0.00713338 -0.178621 0.0121266 -0.00740288 -0.179147 0.012147 -0.00712141 -0.176818 0.0121201 -0.0071675 -0.177378 0.0127027 -0.00663232 -0.177941 0.012569 -0.00709891 -0.179085 0.012563 -0.00659907 -0.1767 0.0126179 -0.00662482 -0.177299 0.0128897 -0.00590493 -0.177918 0.0128207 -0.00660325 -0.178599 0.0129881 -0.00592704 -0.178627 0.0130842 -0.00604532 -0.179326 0.012938 -0.00661986 -0.179176 0.0129708 -0.00664979 -0.179337 0.0126688 -0.0071035 -0.179286 0.0121995 -0.00740288 -0.179209 0.0126246 -0.00710109 -0.179201 0.0134717 -0.00739676 -0.180288 0.0131762 -0.00644295 -0.179855 0.0131301 -0.00617337 -0.179662 0.0133099 -0.0072046 -0.180126 0.0134693 -0.00740084 -0.180286 0.0132482 -0.00730445 -0.180079 0.0130485 -0.00679994 -0.179668 0.0128186 -0.00712861 -0.179536 0.0129942 -0.00667354 -0.179444 0.0134681 -0.00740288 -0.180285 0.0131793 -0.00740288 -0.18004 0.0134705 -0.0073988 -0.180287 0.01641 -0.00696952 -0.216939 0.0168525 -0.00740288 -0.216195 0.0168542 -0.00739982 -0.216194 0.0165928 -0.00740288 -0.216471 0.0159862 -0.00740288 -0.217115 0.0162351 -0.00711146 -0.217129 0.0168579 -0.00740288 -0.21619 0.0168558 -0.00739676 -0.216192 0.016686 -0.00725466 -0.216398 0.0166104 -0.00644295 -0.216655 0.0163773 -0.00693287 -0.217049 0.0164826 -0.00667882 -0.217046 0.0165955 -0.00632229 -0.216736 0.0162013 -0.00709803 -0.217222 0.0165868 -0.00611247 -0.216919 0.0165866 -0.00619855 -0.216835 0.0157064 -0.00740288 -0.217435 0.0157785 -0.00740288 -0.217342 0.0164846 -0.00664342 -0.21712 0.0161759 -0.00709586 -0.217301 0.0156741 -0.00740288 -0.217481 0.016161 -0.0070942 -0.217361 0.0160067 -0.00715166 -0.218756 0.0161037 -0.00712084 -0.219405 0.0157473 -0.00740288 -0.219844 0.0162506 -0.00709395 -0.219919 0.015765 -0.00740288 -0.219866 0.0160375 -0.00712501 -0.217976 0.0164726 -0.00659832 -0.217922 0.0164832 -0.00662904 -0.217197 0.016591 -0.00607911 -0.217016 0.0164877 -0.00661322 -0.218741 0.0166271 -0.00593272 -0.217871 0.0165338 -0.00659685 -0.219432 0.016689 -0.00593809 -0.219479 0.0165908 -0.00662274 -0.220047 0.0165945 -0.00662864 -0.220086 0.0167668 -0.00639657 -0.22054 0.0166342 -0.00677529 -0.22035 0.0166359 -0.00678066 -0.220356 0.0162692 -0.00709307 -0.21997 0.0163885 -0.00712082 -0.220218 0.0165955 -0.0066352 -0.220106 0.0162603 -0.00709417 -0.219948 0.0170807 -0.00739676 -0.220996 0.0170788 -0.00739982 -0.220995 0.0169709 -0.00710403 -0.220891 0.0165267 -0.00695761 -0.220282 0.016392 -0.00712262 -0.220224 0.017077 -0.00740288 -0.220993 0.0168855 -0.00725466 -0.220814 0.0165414 -0.00696952 -0.220313 0.0167836 -0.00740288 -0.220754 0.0160582 -0.00740288 -0.220162 0.017636 -0.00590288 -0.225174 0.017199 -0.00729576 -0.22432 0.0175915 -0.00665288 -0.224978 0.0179905 -0.00663296 -0.224967 0.0169525 -0.00590288 -0.225723 0.0161075 -0.00720192 -0.226173 0.0162739 -0.00720192 -0.225404 0.0155953 -0.00740288 -0.225084 0.0167707 -0.00665288 -0.225638 0.0167609 -0.00720192 -0.224785 0.0162911 -0.00740288 -0.2242 0.018086 -0.00590288 -0.225175 0.0184859 -0.00590888 -0.225371 0.0171049 -0.00665288 -0.225213 0.0174704 -0.00714073 -0.224542 0.0166565 -0.00665288 -0.226166 0.0168854 -0.00590288 -0.230644 0.0166844 -0.00665288 -0.230644 0.0157065 -0.00720192 -0.244972 0.0149578 -0.00740288 -0.244927 0.0161354 -0.00720192 -0.230643 0.0162545 -0.00665288 -0.245005 0.0158032 -0.00590288 -0.25585 0.0170169 -0.00590288 -0.256886 0.0166639 -0.00690742 -0.257289 0.0169119 -0.00663296 -0.257094 0.017012 -0.00650426 -0.257016 0.0151778 -0.00740288 -0.257811 0.016559 -0.00590288 -0.25688 0.0165103 -0.00665288 -0.257075 0.0156649 -0.00720192 -0.25724 0.016299 -0.00719596 -0.257575 0.0161081 -0.00729576 -0.257725 0.016152 -0.00590288 -0.25667 0.0156961 -0.00665288 -0.256379 0.0160214 -0.00665288 -0.256823 0.0151908 -0.00720192 -0.256594 0.0156026 -0.00665288 -0.255837 0.0150545 -0.00720192 -0.255804 -0.0146781 0.00733831 -0.0396064 -0.014131 0.00719617 -0.0394381 -0.0153134 0.00739712 -0.0400812 -0.0130762 0.00589712 -0.0396832 -0.0132121 0.00664702 -0.0395095 -0.0136748 0.00699279 -0.0394196 -0.0139554 0.00712899 -0.0394186 -0.0145301 0.00719616 -0.0400747 -0.0128888 0.0062875 -0.0396126 -0.0131083 0.00653882 -0.0395426 -0.0136662 0.00664712 -0.0397544 -0.013535 0.00589712 -0.0399066 -0.0138239 0.00589712 -0.0403274 -0.0140131 0.00664712 -0.0402596 -0.0134267 0.00719616 -0.0476488 -0.0146065 0.00719616 -0.0409645 -0.0128863 0.00664712 -0.0475521 -0.0140656 0.00664712 -0.0408703 -0.0121824 0.00717573 -0.0543213 -0.0116761 0.00664712 -0.0542283 -0.0119596 0.00717153 -0.0548916 -0.0122161 0.00719616 -0.0543275 -0.0111711 0.00662976 -0.0549919 -0.0114949 0.00662976 -0.0546585 -0.0115474 0.00695724 -0.0549924 -0.0118997 0.00714485 -0.0549096 -0.0103234 0.00589712 -0.0549966 -0.0103287 0.00590269 -0.0549975 -0.0108361 0.00589712 -0.0549514 -0.0112584 0.00589712 -0.0546572 -0.0113344 0.00589712 -0.0545547 -0.0116664 0.00662976 -0.0542265 -0.00859168 0.00589712 -0.061268 -0.00900062 0.00589712 -0.0611952 -0.0100641 0.0072618 -0.0606707 -0.00991358 0.00719156 -0.0607318 -0.0109191 0.00739712 -0.0606321 -0.0113936 0.00739712 -0.0615909 -0.00942053 0.00685013 -0.0609318 -0.00990503 0.00664712 -0.061444 -0.0103336 0.00719616 -0.0611008 -0.010133 0.00664712 -0.0619046 -0.0106658 0.00719616 -0.061772 -0.00919331 0.00663186 -0.0610239 -0.0094154 0.00589712 -0.0613005 -0.00974816 0.00589712 -0.0615696 -0.0095054 0.00664712 -0.0611208 -0.0106869 0.00719616 -0.0625207 -0.0101475 0.00664712 -0.0624184 -0.00837751 0.00589712 -0.0705473 -0.00749478 0.00719616 -0.0788531 -0.00984965 0.00739712 -0.0708351 -0.00911358 0.00719616 -0.0706912 -0.00695653 0.00664712 -0.0787448 -0.00675951 0.00589712 -0.0787052 -0.00857474 0.00664712 -0.0705859 -0.00715961 0.00719616 -0.0795836 -0.00659671 0.00719099 -0.0800452 -0.00629668 0.00664712 -0.0795917 -0.00590513 0.00663215 -0.0796938 -0.00611978 0.00684677 -0.0798029 -0.00621008 0.00589712 -0.0794104 -0.00578641 0.00649763 -0.0796334 -0.00672651 0.00664712 -0.0792461 -0.00823006 0.00739712 -0.079001 -0.00656798 0.00589712 -0.0791226 -0.00422694 0.00647114 -0.0873147 -0.00332439 0.00590312 -0.0874375 -0.00374109 0.00589712 -0.0873322 -0.00621985 0.00739712 -0.0888394 -0.00563942 0.00728294 -0.0878607 -0.00524675 0.00728294 -0.0870931 -0.00480645 0.00729 -0.0866867 -0.00445051 0.00710772 -0.086867 -0.00516756 0.00695778 -0.0879797 -0.00435973 0.00695778 -0.0870179 -0.0048741 0.00695778 -0.087406 -0.00462511 0.00647114 -0.0876152 -0.00485227 0.00647114 -0.0880593 -0.00486289 0.00647114 -0.088558 -0.00494787 0.00664712 -0.0885756 -0.00453768 0.00589712 -0.0876886 -0.00474156 0.00589712 -0.0880872 -0.00312253 0.00664712 -0.0972777 -0.00439333 0.00739712 -0.097547 -0.00548547 0.00719616 -0.0886871 -0.00292594 0.00589712 -0.097236 -0.00126377 0.00664712 -0.105974 -0.00518128 0.00695778 -0.088624 -0.00365963 0.00719616 -0.0973915 -0.00180052 0.00719616 -0.10609 -0.000970051 0.00729 -0.107454 -0.000780581 0.00719922 -0.107335 -0.000951572 0.00728239 -0.107443 -0.00156943 0.00728294 -0.106954 -0.000371481 0.00690166 -0.107079 -0.000516978 0.00647114 -0.106751 -0.000641675 0.00695778 -0.107051 -0.00119555 0.00695778 -0.106643 -0.00117893 0.00647114 -0.105956 -0.000945727 0.00647114 -0.106435 -0.00149681 0.00695778 -0.106025 -0.00201046 0.00739712 -0.107322 0.00194655 0.0069537 -0.115701 0.0020077 0.00690166 -0.115735 0.00243751 0.00644713 -0.115972 0.00242249 0.00589712 -0.116076 0.000841741 0.00739712 -0.115092 0.000901343 0.00728294 -0.115823 0.00140812 0.00728239 -0.115405 0.00180068 0.00695778 -0.11575 0.00169768 0.00713378 -0.115564 0.0012712 0.00695778 -0.116139 0.000969505 0.00695778 -0.116722 0.000497648 0.00728294 -0.116603 0.00151833 0.00647114 -0.11635 0.00127621 0.00647114 -0.11731 0.00197297 0.00589712 -0.116154 0.00160511 0.00589712 -0.116424 0.00192819 0.00647114 -0.116049 0.00128479 0.00647114 -0.116802 -7.82079e-05 0.00739712 -0.117604 0.00328723 0.00589712 -0.126086 0.00309074 0.00664712 -0.126128 0.000958415 0.00695778 -0.117379 0.000654795 0.00719616 -0.117445 0.00255393 0.00719616 -0.126243 0.00119139 0.00664712 -0.117329 0.00368964 0.00739712 -0.135203 0.00442371 0.00719616 -0.13505 0.00496109 0.00664712 -0.134937 0.00426577 0.00739712 -0.136349 0.00599128 0.0069537 -0.136119 0.00567465 0.00695778 -0.136054 0.00634931 0.00647114 -0.135785 0.00505947 0.00695778 -0.135646 0.005779 0.00647114 -0.135746 0.00581564 0.00589712 -0.135638 0.00504603 0.00647114 -0.134919 0.00530279 0.00647114 -0.13543 0.00472778 0.00695778 -0.134986 0.00469532 0.00728294 -0.135969 0.00642029 0.00709826 -0.139039 0.00652491 0.00739712 -0.138935 0.00623493 0.00739712 -0.139179 0.0063901 0.00700898 -0.139075 0.00632173 0.00714047 -0.139147 0.00627805 0.00706546 -0.13921 0.00618589 0.00637764 -0.139543 0.00618754 0.00613352 -0.13986 0.00611798 0.00663364 -0.14 0.00611179 0.00675285 -0.139669 0.00609662 0.00718372 -0.139402 0.00621063 0.00695597 -0.139332 0.00618528 0.0072344 -0.139273 0.00624001 0.00727037 -0.139207 0.00587625 0.00707271 -0.140153 0.00593627 0.00710103 -0.139769 0.00560867 0.00739712 -0.139964 0.00594712 0.00739712 -0.139446 0.00547765 0.00739712 -0.140361 0.00587527 0.00707268 -0.1402 0.00593794 0.00707553 -0.14092 0.00626564 0.00658341 -0.140838 0.00612491 0.00662439 -0.140038 0.00623893 0.0070734 -0.141959 0.00664843 0.00611931 -0.142124 0.00593614 0.00739712 -0.142113 0.0056534 0.00739712 -0.1417 0.00652937 0.00662866 -0.142016 0.00659299 0.00667852 -0.142271 0.00671078 0.00622012 -0.142432 0.00655301 0.00697365 -0.142415 0.00615392 0.00739712 -0.142323 0.00677407 0.00647296 -0.142633 0.00647621 0.00689163 -0.142208 0.00632484 0.00708595 -0.14216 0.00708809 0.00739712 -0.143032 0.00708178 0.00739712 -0.143027 0.00622653 0.00739712 -0.142381 0.00708557 0.00739099 -0.14303 0.00708368 0.00739406 -0.143029 0.00688371 0.00724889 -0.142855 0.00658526 0.00701397 -0.14248 0.00960463 0.00590312 -0.148067 0.00909436 0.0066272 -0.147681 0.0077592 0.00719616 -0.147639 0.00847265 0.00719019 -0.147212 0.00864163 0.00664712 -0.147723 0.00884279 0.00690166 -0.147491 0.00722499 0.00739712 -0.147113 0.00728767 0.00719616 -0.149201 0.00733043 0.00719616 -0.148362 0.00785602 0.00664712 -0.14852 0.00918154 0.00589712 -0.147883 0.0091735 0.00652771 -0.147741 0.00870255 0.00589712 -0.147915 0.00829341 0.00589712 -0.148166 0.00815027 0.00664712 -0.148025 0.00925597 0.00719616 -0.159808 0.00655137 0.00739712 -0.149343 0.00782667 0.00664712 -0.149096 0.0102866 0.00739712 -0.170568 0.0113346 0.00695778 -0.170405 0.0115701 0.00664712 -0.170368 0.00979664 0.00664712 -0.159712 0.0123738 0.00729 -0.172088 0.0131557 0.00648598 -0.17123 0.0131802 0.00644713 -0.171203 0.0126908 0.00647114 -0.171295 0.0126976 0.00589712 -0.171181 0.0134927 0.00590312 -0.17086 0.0120522 0.00695778 -0.171438 0.0126716 0.00695778 -0.17162 0.0122113 0.00647114 -0.171154 0.0118139 0.00728294 -0.171862 0.0122672 0.00589712 -0.171055 0.0116559 0.00647114 -0.170354 0.0119354 0.00589712 -0.170753 0.0118416 0.00647114 -0.170818 0.0115745 0.00695778 -0.171004 0.0111748 0.00728294 -0.171281 0.0110277 0.00719616 -0.170452 0.0128736 0.00739406 -0.175252 0.012442 0.00696376 -0.176005 0.012872 0.00739712 -0.175254 0.0127089 0.00724889 -0.175459 0.0126169 0.00739712 -0.175534 0.0120211 0.00739712 -0.176188 0.0124202 0.0069378 -0.17608 0.0126277 0.00635464 -0.175772 0.0125183 0.00668682 -0.176081 0.0122005 0.00709306 -0.176441 0.012253 0.00709339 -0.176257 0.0116978 0.00739712 -0.176605 0.012563 0.00659331 -0.1767 0.0125282 0.00661539 -0.17625 0.012147 0.00711565 -0.176818 0.0121201 0.00716173 -0.177378 0.0114253 0.00739712 -0.17748 0.0129881 0.00592127 -0.178627 0.0128207 0.00659749 -0.178599 0.0123684 0.00712761 -0.178621 0.012938 0.00661409 -0.179176 0.0129708 0.00664402 -0.179337 0.0127974 0.00590141 -0.177262 0.0128897 0.00589916 -0.177918 0.0126179 0.00661906 -0.177299 0.0127027 0.00662656 -0.177941 0.01219 0.00717145 -0.178009 0.0116333 0.00739712 -0.17852 0.011729 0.00739712 -0.178689 0.012569 0.00709315 -0.179085 0.0126246 0.00709532 -0.179201 0.0121266 0.00739712 -0.179147 0.0129942 0.00666778 -0.179444 0.0131127 0.00611182 -0.179534 0.0134681 0.00739712 -0.180285 0.0132482 0.00729869 -0.180079 0.0128186 0.00712284 -0.179536 0.0121995 0.00739712 -0.179209 0.0134741 0.00739712 -0.18029 0.0133099 0.00719883 -0.180126 0.0126688 0.00709774 -0.179286 0.0134705 0.00739303 -0.180287 0.0134717 0.00739099 -0.180288 0.0130485 0.00679417 -0.179668 0.0131762 0.00643719 -0.179855 0.0134693 0.00739508 -0.180286 0.0166104 0.00643719 -0.216655 0.0163773 0.00692711 -0.217049 0.0168542 0.00739406 -0.216194 0.016686 0.00724889 -0.216398 0.0168525 0.00739712 -0.216195 0.0165928 0.00739712 -0.216471 0.01641 0.00696376 -0.216939 0.0159862 0.00739712 -0.217115 0.0158673 0.00739712 -0.217241 0.0162013 0.00709226 -0.217222 0.0162351 0.00710569 -0.217129 0.0164826 0.00667305 -0.217046 0.0165866 0.00619278 -0.216835 0.0161759 0.00709009 -0.217301 0.0165868 0.00610671 -0.216919 0.0164846 0.00663766 -0.21712 0.016161 0.00708843 -0.217361 0.0164832 0.00662327 -0.217197 0.0166271 0.00592696 -0.217871 0.0164726 0.00659255 -0.217922 0.0164877 0.00660745 -0.218741 0.016689 0.00593232 -0.219479 0.0167145 0.00605768 -0.220209 0.0160375 0.00711924 -0.217976 0.0161037 0.00711507 -0.219405 0.0165338 0.00659108 -0.219432 0.0162506 0.00708819 -0.219919 0.0165908 0.00661697 -0.220047 0.0156741 0.00739712 -0.217481 0.015441 0.00739712 -0.217936 0.0153273 0.00739712 -0.218743 0.0160067 0.0071459 -0.218756 0.0157473 0.00739712 -0.219844 0.0162603 0.00708841 -0.219948 0.016392 0.00711686 -0.220224 0.0160512 0.00739712 -0.220156 0.0163885 0.00711505 -0.220218 0.0165267 0.00695184 -0.220282 0.0167668 0.0063908 -0.22054 0.0166342 0.00676952 -0.22035 0.0157869 0.00739712 -0.219893 0.0167161 0.00607236 -0.220257 0.0165945 0.00662287 -0.220086 0.0165955 0.00662944 -0.220106 0.0162692 0.0070873 -0.21997 0.0170788 0.00739406 -0.220995 0.017077 0.00739712 -0.220993 0.0166359 0.00677489 -0.220356 0.0168855 0.00724889 -0.220814 0.0165414 0.00696376 -0.220313 0.016769 0.00640068 -0.220546 0.0184859 0.00590312 -0.225371 0.0180942 0.00649153 -0.225051 0.0179905 0.0066272 -0.224967 0.0177463 0.00690166 -0.224767 0.0174873 0.00712286 -0.224556 0.01711 0.00664712 -0.225209 0.0167684 0.00719616 -0.224779 0.0167721 0.00664712 -0.225635 0.0166565 0.00664712 -0.226166 0.0162759 0.00719616 -0.225399 0.0161075 0.00719616 -0.226173 0.0176011 0.00664712 -0.224976 0.017644 0.00589712 -0.225172 0.0172351 0.00589712 -0.225366 0.0153576 0.00739712 -0.226184 0.0166844 0.00664712 -0.230644 0.0168574 0.00589712 -0.226163 0.0161354 0.00719616 -0.230643 0.0160166 0.00695778 -0.24499 0.0162545 0.00664712 -0.245005 0.0148789 0.00728294 -0.255794 0.0157065 0.00719616 -0.244972 0.0158666 0.00695778 -0.257004 0.016609 0.0069537 -0.257332 0.0164526 0.00695778 -0.257306 0.0160778 0.00647114 -0.256757 0.0165314 0.00647114 -0.256991 0.0150289 0.00728294 -0.256663 0.0155506 0.00728294 -0.257374 0.016152 0.00589712 -0.25667 0.0145006 0.00739712 -0.256888 0.0154767 0.00695778 -0.256473 0.0153646 0.00695778 -0.255823 0.015776 0.00647114 -0.256345 0.0156892 0.00647114 -0.255843 -0.00423846 -0.00695947 -0.0869744 -0.00422694 -0.00647691 -0.0873147 -0.0037383 -0.00645289 -0.0872278 -0.00418031 -0.00590288 -0.0874189 -0.00417617 -0.00690742 -0.087006 -0.00435973 -0.00696354 -0.0870179 -0.0048741 -0.00696354 -0.087406 -0.00478699 -0.00728816 -0.0866965 -0.00475109 -0.00590288 -0.0885348 -0.00486289 -0.00647691 -0.088558 -0.00474156 -0.00590288 -0.0880872 -0.00494787 -0.00665288 -0.0885756 -0.00548547 -0.00720192 -0.0886871 -0.00621985 -0.00740288 -0.0888394 -0.00462511 -0.00647691 -0.0876152 -0.00485227 -0.00647691 -0.0880593 -0.00516756 -0.00696354 -0.0879797 -0.00563942 -0.0072887 -0.0878607 -0.00524675 -0.0072887 -0.0870931 -0.00619602 -0.00740288 -0.0877204 -0.00568631 -0.00740288 -0.0867239 -0.000951572 -0.00728816 -0.107443 -0.00149954 -0.00740288 -0.107786 -0.000430639 -0.00695947 -0.107116 -0.000371481 -0.00690742 -0.107079 -0.000473191 -0.00590288 -0.106645 -0.000516978 -0.00647691 -0.106751 -0.000858001 -0.00590288 -0.106362 -0.000641675 -0.00696354 -0.107051 -0.000945727 -0.00647691 -0.106435 -0.00119555 -0.00696354 -0.106643 -0.00156943 -0.0072887 -0.106954 -0.00180052 -0.00720192 -0.10609 -0.00974816 -0.00590288 -0.0615696 -0.00908378 -0.00651874 -0.0610684 -0.00946653 -0.00647691 -0.0611984 -0.0108275 -0.00740288 -0.0605241 -0.0109191 -0.00740288 -0.0606321 -0.010471 -0.0072887 -0.0609908 -0.00859168 -0.00590288 -0.061268 -0.00859622 -0.00590888 -0.0612661 -0.00899324 -0.00641425 -0.0611051 -0.0094154 -0.00590288 -0.0613005 -0.00948605 -0.00691156 -0.0609052 -0.00983729 -0.00647691 -0.0614982 -0.0100911 -0.00696354 -0.061295 -0.00975566 -0.00710702 -0.0607958 -0.0100641 -0.00726756 -0.0606707 -0.0104337 -0.00737157 -0.0605609 -0.0100488 -0.00647691 -0.0619256 -0.0101475 -0.00665288 -0.0624184 -0.0103643 -0.00696354 -0.0618471 -0.0103817 -0.00696354 -0.0624628 -0.0106869 -0.00720192 -0.0625207 -0.00993796 -0.00590288 -0.0619532 -0.0108365 -0.0072887 -0.0617296 -0.00911358 -0.00720192 -0.0706912 -0.00984965 -0.00740288 -0.0708351 -0.00857474 -0.00665288 -0.0705859 -0.0100622 -0.00647691 -0.0624022 -0.00695653 -0.00665288 -0.0787448 -0.00533045 -0.00590888 -0.0794017 -0.00675854 -0.0072744 -0.0801275 -0.00716258 -0.00720192 -0.0795797 -0.00621506 -0.00590288 -0.079408 -0.00611978 -0.00685254 -0.0798029 -0.00579567 -0.00651427 -0.0796381 -0.00630266 -0.00665288 -0.0795889 -0.00653118 -0.00715987 -0.0800119 -0.00656968 -0.00590288 -0.0791204 -0.00672854 -0.00665288 -0.0792435 -0.00749478 -0.00720192 -0.0788531 -0.00775548 -0.00740288 -0.0800391 -0.0139314 -0.00647691 -0.0402889 -0.0130762 -0.00590288 -0.0396832 -0.0136148 -0.0069638 -0.0394249 -0.0138218 -0.00696354 -0.0395738 -0.0130983 -0.00647691 -0.0395712 -0.013535 -0.00590288 -0.0399066 -0.0136096 -0.00647691 -0.0398201 -0.0130394 -0.0064688 -0.0395646 -0.0142376 -0.00696354 -0.0401793 -0.015105 -0.00739606 -0.0398796 -0.0138676 -0.00590288 -0.0408358 -0.0139801 -0.00647691 -0.0408554 -0.0140656 -0.00665288 -0.0408703 -0.0146958 -0.0072887 -0.0400154 -0.0146065 -0.00720192 -0.0409645 -0.0128863 -0.00665288 -0.0475521 -0.0143004 -0.00696354 -0.0409112 -0.0134267 -0.00720192 -0.0476488 -0.0122161 -0.00720192 -0.0543275 -0.0116664 -0.00663553 -0.0542265 -0.0126885 -0.00590288 -0.0475167 -0.0114785 -0.00590288 -0.054192 -0.0115474 -0.006963 -0.0549924 -0.0103234 -0.00590288 -0.0549966 -0.0103287 -0.00590845 -0.0549975 -0.0108361 -0.00590288 -0.0549514 -0.0116761 -0.00665288 -0.0542283 -0.0116395 -0.00701722 -0.0549745 -0.0121824 -0.0071815 -0.0543213 -0.0114043 -0.00663553 -0.0547807 -0.00857946 -0.0155029 0.043315 -0.00897192 -0.0158288 0.0416448 -0.00880719 -0.0156511 0.0414941 -0.0105086 -0.0179015 0.0369779 -0.00882853 -0.0156929 0.041523 -0.00895118 -0.0158169 0.041631 -0.0106526 -0.0180674 0.0371148 -0.0104831 -0.017675 0.0368554 -0.0114725 -0.0185029 0.0356474 -0.0110673 -0.0182529 0.0354948 -0.0111417 -0.0183564 0.0355228 -0.0213754 -0.0181942 0.00805029 -0.0112386 -0.0184359 0.0355593 -0.0218077 -0.0185029 0.00821314 -0.0221098 -0.0180029 -0.00558287 -0.0227808 -0.0180029 -0.00102197 -0.0222518 -0.0183564 -0.00561872 -0.0228188 -0.0181942 -0.00102368 -0.0229271 -0.0183564 -0.00102853 -0.0224091 -0.0184648 -0.00565843 -0.0232803 -0.0185029 -0.00104436 -0.0225581 -0.0181942 0.00358664 -0.0226652 -0.0183564 0.00360367 -0.0230891 -0.0184648 -0.00103579 -0.0228254 -0.0184648 0.00362915 -0.0213398 -0.0180029 0.00803687 -0.0214769 -0.0183564 0.0080885 -0.0230143 -0.0185029 0.00365921 -0.0216287 -0.0184648 0.00814569 -0.0185576 -0.0180029 -0.019651 -0.0221467 -0.0181942 -0.00559219 -0.0186225 -0.0182529 -0.0196674 -0.0186996 -0.0183564 -0.0196868 -0.0183705 -0.0181773 -0.0205066 -0.0185752 -0.0184352 -0.0205374 -0.0188 -0.0184359 -0.0197122 -0.0185808 -0.0184387 -0.0205383 -0.0181115 -0.0184218 -0.0231146 -0.0183419 -0.0180122 -0.0205053 -0.0184064 -0.0182568 -0.0205112 -0.0184513 -0.0183238 -0.0205177 -0.0182689 -0.0185992 -0.0231123 -0.0188088 -0.0185105 -0.0205776 -0.0179198 -0.0190304 -0.0260257 -0.0181244 -0.0191239 -0.0260314 -0.0169809 -0.0201382 -0.032354 -0.0170357 -0.0203461 -0.0323058 -0.0171762 -0.0205137 -0.0322787 -0.0177754 -0.0188587 -0.0260418 -0.0173753 -0.0206083 -0.0322779 -0.0170029 -0.0206735 -0.0329387 -0.0167514 -0.0208748 -0.0336507 -0.0161309 -0.0208873 -0.0341444 -0.0153271 -0.0206908 -0.0342502 -0.0166167 -0.0207695 -0.0335398 -0.0165209 -0.0206036 -0.0334702 -0.01605 -0.020781 -0.0339936 -0.0153597 -0.0203283 -0.03408 -0.0153335 -0.0205262 -0.0341277 -0.0159862 -0.0204187 -0.0338508 -0.01648 -0.0204047 -0.0334536 -0.0159991 -0.0206158 -0.0338901 -0.0168765 -0.0205067 -0.0329148 -0.0149541 -0.0202195 -0.034113 -0.0145915 -0.0203199 -0.0341214 -0.01452 -0.0204845 -0.0342439 -0.0140218 -0.0198179 -0.0338605 -0.0139217 -0.0200315 -0.0338684 -0.0146602 -0.0201168 -0.0340851 -0.0144592 -0.0205797 -0.0344296 -0.0106947 -0.0186839 -0.032075 -0.0137896 -0.0201974 -0.0339719 -0.010437 -0.0189339 -0.0323862 -0.0107825 -0.018456 -0.0320552 -0.00835646 -0.0182529 -0.03078 -0.00826737 -0.0184359 -0.0309398 -0.0105695 -0.018857 -0.032195 -0.00138279 -0.0182529 -0.0268937 -0.00814568 -0.0185029 -0.0311582 0.0137005 -0.0182529 -0.0184881 -0.0012937 -0.0184359 -0.0270535 0.0137896 -0.0184359 -0.018648 0.0145676 -0.0180029 -0.0173829 0.0149442 -0.0184359 -0.0166949 0.0142109 -0.0180029 -0.0179863 0.0146304 -0.0182529 -0.0174064 0.0148018 -0.0184359 -0.0174705 0.0142617 -0.0182529 -0.01803 0.0144005 -0.0184359 -0.0181493 0.0136679 -0.0180029 -0.0184296 0.0146942 -0.0180029 -0.0166935 0.0147612 -0.0182529 -0.0166939 0.0147668 -0.0182529 -0.015598 0.0151942 -0.0185029 -0.0166962 0.0147716 -0.0182529 -0.0145021 0.0149498 -0.0184359 -0.0155988 0.0152046 -0.0185029 -0.0145038 0.0151998 -0.0185029 -0.0156 0.0140543 -0.0180029 -0.014023 0.0143276 -0.0184359 -0.01376 0.0142804 -0.0184571 -0.0137125 0.0142975 -0.0182529 -0.0139406 0.0140237 -0.018231 -0.0139751 0.0146493 -0.0184359 -0.0138959 0.0147111 -0.0182529 -0.0142451 0.0149546 -0.0184359 -0.0145028 0.014501 -0.0180029 -0.0140972 0.0145408 -0.0182529 -0.0140433 0.0147975 -0.0185029 -0.0136946 0.0150979 -0.0185029 -0.0140505 0.0148746 -0.0184359 -0.0141628 0.0142824 0.0179971 -0.014006 0.0140489 0.0179971 -0.0140247 0.0140371 0.0181885 -0.0139885 0.0140508 0.0182574 -0.0139478 0.0138569 0.0180003 -0.0141406 0.0142883 0.0181885 -0.0139684 0.0143052 0.0183507 -0.0138613 0.0141226 0.0183336 -0.0138751 0.0144988 0.0179971 -0.0140956 0.0145212 0.0181885 -0.0140648 0.0143304 0.0184591 -0.0137011 0.0142804 0.0184513 -0.0137125 0.0147046 0.0179971 -0.0145018 0.0147426 0.0181885 -0.014502 0.0146846 0.0181885 -0.0142567 0.014851 0.0183507 -0.0145024 0.0149546 0.0184301 -0.0145028 0.014926 0.0184591 -0.0141344 0.0147812 0.0183507 -0.0142077 0.0145849 0.0183507 -0.0139772 0.0146804 0.0184591 -0.013846 0.014793 0.0184971 -0.0136913 0.0151942 0.0184971 -0.0166962 0.0149442 0.0184301 -0.0166949 0.0147668 0.0182471 -0.015598 0.0146998 0.0179971 -0.0155976 0.0147716 0.0182471 -0.0145021 0.0149498 0.0184301 -0.0155988 -0.00877592 0.0154971 0.0414085 -0.00882853 0.0156871 0.041523 -0.00864801 0.0154971 0.0420522 -0.00917515 0.0158719 0.0417457 0.0142617 0.0182471 -0.01803 0.0146304 0.0182471 -0.0174064 0.0144005 0.0184301 -0.0181493 0.01459 0.0184971 -0.0183123 0.0147612 0.0182471 -0.0166939 0.0148018 0.0184301 -0.0174705 0.015036 0.0184971 -0.017558 -0.00878886 0.0155921 0.0414607 -0.00897192 0.0158231 0.0416448 0.0137005 0.0182471 -0.0184881 -0.00835646 0.0182471 -0.03078 0.0137896 0.0184301 -0.018648 -0.00826737 0.0184301 -0.0309398 -0.00814568 0.0184971 -0.0311582 -0.0108766 0.0181223 0.0372294 -0.0107032 0.0180879 0.0371469 -0.0105675 0.0179896 0.0370468 -0.0104903 0.0178426 0.0369445 -0.00932708 0.0180763 -0.0312442 -0.00926611 0.0183183 -0.0312832 -0.0107388 0.0189085 -0.0322879 -0.0106058 0.0189857 -0.0324777 -0.00915858 0.0184985 -0.0314238 -0.00903193 0.018571 -0.03163 -0.0139217 0.0200257 -0.0338684 -0.0109552 0.0185097 -0.0321515 -0.0108653 0.0187361 -0.0321697 -0.0110046 0.0179971 0.0354712 -0.0213754 0.0181885 0.00805029 -0.0110402 0.0181885 0.0354846 -0.0214769 0.0183507 0.0080885 -0.0111417 0.0183507 0.0355228 -0.0216287 0.0184591 0.00814569 -0.0112935 0.0184591 0.03558 -0.013655 0.0202731 -0.0341479 -0.0137896 0.0201917 -0.0339719 -0.0146075 0.0203197 -0.0341244 -0.0149548 0.020214 -0.034113 -0.0140218 0.0198121 -0.0338605 -0.0159364 0.0207676 -0.0340533 -0.0166666 0.0208771 -0.0337395 -0.0158944 0.0206026 -0.0339454 -0.0145374 0.0204843 -0.0342471 -0.0152561 0.0207726 -0.0344406 -0.0152489 0.0206697 -0.0342622 -0.0152616 0.0205052 -0.0341388 -0.015292 0.020307 -0.0340913 -0.0164124 0.0204071 -0.0335248 -0.0164498 0.0206057 -0.0335458 -0.016976 0.0206796 -0.0329982 -0.0165395 0.0207714 -0.0336215 -0.0168518 0.020513 -0.0329697 -0.0171762 0.0205079 -0.0322787 -0.0225206 0.0179971 0.00358066 -0.0225581 0.0181885 0.00358664 -0.0226652 0.0183507 0.00360367 -0.0230891 0.0184591 -0.00103579 -0.0228254 0.0184591 0.00362915 -0.0230143 0.0184971 0.00365921 -0.0221098 0.0179971 -0.00558287 -0.0228188 0.0181885 -0.00102368 -0.0229271 0.0183507 -0.00102853 -0.0221467 0.0181885 -0.00559219 -0.0222518 0.0183507 -0.00561872 -0.0224091 0.0184591 -0.00565843 -0.0185807 0.0184329 -0.0205383 -0.0182689 0.0185935 -0.0231123 -0.0184513 0.018318 -0.0205177 -0.0181115 0.018416 -0.0231146 -0.0183705 0.0181716 -0.0205066 -0.0185752 0.0184294 -0.0205374 -0.0188206 0.0185053 -0.0205797 -0.0184894 0.0186795 -0.0231272 -0.0179198 0.0190247 -0.0260257 -0.0170357 0.0203404 -0.0323058 -0.0169809 0.0201324 -0.032354 -0.0177754 0.0188529 -0.0260418 -0.0185945 0.0181885 -0.0196603 -0.0225946 0.0184971 -0.00570528 -0.0188088 0.0185048 -0.0205776 -0.0190424 0.0184971 -0.0197734 -0.0186996 0.0183507 -0.0196868 -0.0188568 0.0184591 -0.0197266 -0.0186368 0.0184626 -0.0205477 -0.0184061 0.0182505 -0.0205112 -0.0185576 0.0179971 -0.019651 -0.0183419 0.0180049 -0.0205053 0.0176163 0.00539712 -0.211595 0.0171779 0.00249712 -0.211659 0.0164066 0.00539712 -0.211188 0.016261 0.00259712 -0.210755 0.0156218 0.00539712 -0.185389 0.0152715 0.00539712 -0.185197 0.0152715 0.00249712 -0.185197 0.014757 0.00539712 -0.185176 0.014757 0.00249712 -0.185176 0.0143003 0.00539712 -0.185414 0.0140225 0.00539712 -0.185847 0.0143003 0.00249712 -0.185414 0.0139764 0.00259712 -0.186214 0.0139769 0.00249712 -0.186213 0.017155 -0.00530288 -0.211657 0.017155 -0.00250288 -0.211657 0.0164052 -0.00530288 -0.211186 0.0164052 -0.00250288 -0.211186 0.0148244 -0.00160288 -0.195321 0.0139793 -0.00250288 -0.186245 0.0148244 -0.00250288 -0.195321 0.0162612 -0.00530288 -0.210755 0.0153806 -0.00250288 -0.201295 0.0140465 -0.00530288 -0.18578 0.0140465 -0.00250288 -0.18578 0.014318 -0.00530288 -0.185398 0.014734 -0.00250288 -0.185181 0.015203 -0.00530288 -0.185178 0.015203 -0.00250288 -0.185178 0.0111589 -0.00730288 -0.182722 0.0121896 -0.00730288 -0.185038 0.0121093 -0.00730288 -0.182706 0.0156616 -0.00730288 -0.213203 0.0111777 -0.00730288 -0.198429 0.0142699 -0.00730288 -0.21094 0.0122573 -0.00730288 -0.212506 0.0147017 -0.00730288 -0.212234 0.0131547 -0.00730288 -0.214062 0.014142 -0.00630288 -0.185196 0.0150595 -0.00625728 -0.184912 0.0137125 -0.00630288 -0.186269 0.0131181 -0.00703493 -0.185409 0.0137978 -0.00630288 -0.185681 0.013661 -0.00703493 -0.184644 0.013004 -0.00730288 -0.18389 0.014734 -0.00530288 -0.185181 0.0146694 -0.00630288 -0.184921 0.0145596 -0.0068351 -0.184488 0.0119879 -0.00730288 -0.18643 0.0152655 -0.00703493 -0.210847 0.0129836 -0.00703493 -0.186337 0.0159944 -0.00630288 -0.210779 0.0139793 -0.00530288 -0.186245 0.0179813 -0.00531019 -0.211351 0.0170758 -0.00678803 -0.212312 0.0171278 -0.00630288 -0.211923 0.0165827 -0.00630288 -0.211736 0.0168035 -0.00703028 -0.212602 0.0165596 -0.00717879 -0.21286 0.0161934 -0.00703493 -0.212356 0.0160453 -0.00730288 -0.213406 0.017606 -0.00530288 -0.211599 0.0167252 -0.00530288 -0.211509 0.0161769 -0.00630288 -0.211326 0.0155534 -0.00703493 -0.21171 0.0171382 0.00639712 -0.211924 0.0170867 0.00687081 -0.212301 0.0170452 0.00691382 -0.212345 0.0162027 0.00712917 -0.212361 0.0179848 0.00539712 -0.211348 0.0171633 0.00539712 -0.211657 0.0150319 0.00724488 -0.210869 0.0152655 0.00712917 -0.210847 0.0155563 0.00712917 -0.211714 0.0161788 0.00639712 -0.211329 0.0167298 0.00539712 -0.211512 0.0165886 0.00639712 -0.211739 0.01275 0.00724488 -0.186359 0.015678 0.00681133 -0.210809 0.0159944 0.00639712 -0.210779 0.0161097 0.00616248 -0.210769 0.0162612 0.00539712 -0.210755 0.0138277 0.00616248 -0.186259 0.013396 0.00681133 -0.186299 0.0156179 0.00540442 -0.185386 0.0146986 0.00639712 -0.184914 0.0141196 0.00639712 -0.185216 0.0140367 0.00727303 -0.184045 0.0129511 0.00739712 -0.183937 0.0121176 0.00739712 -0.185238 0.0130701 0.00712917 -0.185543 0.0129836 0.00712917 -0.186337 0.0143079 0.00712451 -0.184275 0.0136257 0.00712917 -0.184676 0.0137125 0.00639712 -0.186269 0.0150595 0.00635151 -0.184912 0.0137673 0.00639712 -0.185766 0.00183441 -0.0010161 -0.312215 0.00160736 -0.000726914 -0.312278 0.00146773 -0.000402883 -0.312302 -0.0195008 -0.000402883 -0.312294 0.0054329 -0.00181333 -0.311792 0.00498978 -0.00195852 -0.311659 0.00543312 -0.00230814 -0.311203 0.00445818 -0.00200269 -0.311613 0.00392655 -0.00195852 -0.311658 0.00305067 -0.00173998 -0.311849 -0.0187258 -0.00186236 -0.31174 0.00644964 -0.00230814 -0.310524 0.00621105 -0.00230814 -0.310881 0.00733878 -0.00150288 -0.310104 0.00698916 -0.00195852 -0.310104 0.00746575 -0.000402883 -0.310946 0.00719348 -0.00150288 -0.310833 0.00678024 -0.00150288 -0.311451 0.00698858 -0.000402883 -0.311659 0.00652983 -0.000402883 -0.312011 0.00640085 -0.00100288 -0.311986 0.00616198 -0.00150288 -0.311864 0.00557935 -0.00173493 -0.311848 0.0058541 -0.00230814 -0.31112 0.00653352 -0.00230814 -0.310104 0.00746772 -0.00124479 -0.305618 0.00699082 -0.00195852 -0.305617 0.00627709 -0.00243542 -0.305617 0.00543352 -0.00260288 -0.310103 0.00373793 -0.00260288 -0.301515 0.00543519 -0.00260288 -0.305617 0.00577245 -0.00243542 -0.303075 0.00643195 -0.00195852 -0.302802 0.00687262 -0.00124479 -0.30262 0.00483834 -0.00195852 -0.300415 0.00529414 -0.000402883 -0.29996 0.00702736 -0.000402883 -0.302556 0.00433347 -0.00243542 -0.30092 0.00293668 -0.000781898 -0.297647 0.003095 -0.00199405 -0.298722 0.00517568 -0.00124479 -0.300078 0.00307069 -0.0018736 -0.298533 0.00299889 -0.00144158 -0.298032 0.00323753 -0.00259491 -0.300749 -0.0184836 0.00204167 -0.311556 0.00445818 0.00199692 -0.311613 0.00498978 0.00195275 -0.311659 0.00305067 0.00173421 -0.311849 0.00543321 0.00242965 -0.310945 -0.0174781 0.0024918 -0.310767 0.00543295 0.00195275 -0.311659 0.00630985 0.00136965 -0.311871 0.00648123 0.000894806 -0.311973 0.00750017 0.000397117 -0.310857 0.00602831 0.00195275 -0.311541 0.00575542 0.00242965 -0.310881 0.00621122 0.00242965 -0.310426 0.00653312 0.00195275 -0.311204 0.00687052 0.00195275 -0.310699 0.00687021 0.00123902 -0.311541 0.00711682 0.000397117 -0.31152 0.00731105 0.00123902 -0.310882 0.00543352 0.00259712 -0.310103 0.00627543 0.00242965 -0.310103 0.00746606 0.00123902 -0.310104 0.00602862 0.00242965 -0.310699 0.00543519 0.00259712 -0.305617 0.00653519 0.00230237 -0.305617 0.00699082 0.00195275 -0.305617 0.00698916 0.00195275 -0.310104 0.00517568 0.00123902 -0.300078 0.00675501 0.00149712 -0.302669 0.00734044 0.00149712 -0.305618 0.00451604 0.00230237 -0.300737 0.00601094 0.00230237 -0.302977 0.00508565 0.00149712 -0.300168 0.00373793 0.00259712 -0.301515 0.00499451 0.00259712 -0.303397 0.00323749 0.00259712 -0.301014 0.00323156 0.00256061 -0.300444 0.0031899 0.00239556 -0.299665 0.00483834 0.00195275 -0.300415 0.003095 0.00198829 -0.298722 0.00307069 0.00186784 -0.298533 0.00297793 0.00127089 -0.297898 0.00293668 0.000776132 -0.297647 -0.0147171 -0.00256061 -0.0227664 -0.0145917 -0.00243542 -0.0223537 -0.0257747 -0.00210902 -0.0218025 -0.0147595 0.00259712 -0.0231955 -0.0256598 0.00242978 -0.0223499 -0.0258487 0.00175993 -0.0214644 -0.0134007 0.00123902 -0.0211635 -0.0125587 0.000397117 -0.0209964 -0.0259711 0.000397117 -0.0209914 0.0138857 0.00252009 -0.196027 0.0109488 0.00246314 -0.196184 0.013875 0.00246314 -0.195912 0.0138555 0.00230088 -0.195702 0.0138355 0.00197326 -0.195487 0.0109149 0.00209712 -0.19582 0.0143849 0.00159712 -0.201388 0.0114584 0.00169946 -0.201655 0.0143577 0.00230422 -0.201097 0.0111299 0.00218429 -0.2015 0.0106933 0.0024233 -0.201293 0.0143277 0.002521 -0.200774 0.0105008 0.00248763 -0.201202 0.00180073 0.000397117 -0.296025 0.00323753 0.00258914 -0.300749 0.00283546 0.00259712 -0.300181 0.00229997 0.00259712 -0.299056 0.00212952 0.00259712 -0.298679 0.00164748 0.00259712 -0.297503 0.00114908 0.00259712 -0.295795 0.00174044 0.00187812 -0.296593 0.00136762 0.0017903 -0.295512 0.0017659 0.00165043 -0.296435 0.00202129 0.00259712 -0.298432 0.00316873 0.00231086 -0.29941 0.00299889 0.00143582 -0.298032 0.0016447 0.00244615 -0.297172 0.00181344 0.000946757 -0.296138 0.00182404 0.000397117 -0.296072 0.00287153 0.00259712 -0.291914 0.00340616 0.00186433 -0.291856 0.0039219 0.00178901 -0.291732 0.00311586 0.0021167 -0.29192 0.00328321 0.00259712 -0.291736 0.00396568 0.00197701 -0.291698 0.00418129 0.00239163 -0.291531 0.00365369 0.00259712 -0.291599 0.004273 0.00250102 -0.29146 0.00507296 0.00259712 -0.291228 0.0064515 0.00233387 -0.291369 0.00544519 0.00259712 -0.29116 0.00557434 0.00259712 -0.291138 0.00722655 0.00251275 -0.291141 0.00671469 0.00259712 -0.290978 0.00645569 0.00259712 -0.291011 0.00810955 0.002595 -0.290856 0.00796281 0.00259712 -0.290836 0.00789326 0.00258577 -0.290929 0.00587355 0.00209182 -0.291527 0.0054815 0.00169865 -0.29163 0.00390717 0.00159712 -0.291744 0.00546512 0.00159712 -0.291634 0.0016447 -0.00245191 -0.297172 0.0017659 -0.00165619 -0.296435 0.00180073 -0.000402883 -0.296025 0.00150812 -0.00260288 -0.297108 0.00283546 -0.00260288 -0.300181 0.00323156 -0.00256638 -0.300444 0.00229997 -0.00260288 -0.299056 0.0031899 -0.00240132 -0.299665 0.00316873 -0.00231662 -0.29941 0.00212952 -0.00260288 -0.298679 0.00202129 -0.00260288 -0.298432 0.00166563 -0.00260288 -0.297552 0.00174044 -0.00188388 -0.296593 0.00297793 -0.00127666 -0.297898 0.00181344 -0.000952523 -0.296138 0.00182404 -0.000402883 -0.296072 0.00381469 0.00099935 -0.291764 0.00386738 -0.000402883 -0.291752 0.00390717 -0.00160288 -0.291744 0.00825598 -0.00260288 -0.290803 0.00810955 -0.00260077 -0.290856 0.00796281 -0.00260288 -0.290836 0.00722655 -0.00251851 -0.291141 0.00771358 -0.00260288 -0.290863 0.00705104 -0.00248779 -0.291194 0.00498211 -0.00260288 -0.291246 0.0025897 -0.00260288 -0.292053 0.00372287 -0.00260288 -0.291576 0.00418129 -0.00239739 -0.291531 0.00396568 -0.00198277 -0.291698 0.004273 -0.00250678 -0.29146 0.0057708 -0.00203377 -0.291555 0.0039219 -0.00179478 -0.291732 0.0054815 -0.00170441 -0.29163 0.00546512 -0.00160288 -0.291634 0.00340607 -0.00187017 -0.291856 0.00366276 -0.00160288 -0.291799 0.00222346 -0.00188942 -0.292503 0.00158621 -0.00174703 -0.293377 0.00178902 -0.00260288 -0.292655 0.00128763 -0.00171476 -0.294426 0.00101485 -0.00260288 -0.294947 0.00167421 -0.00110551 -0.295899 0.00136723 -0.00179687 -0.295511 0.00142458 -0.00111622 -0.294629 0.00311512 -0.0021231 -0.29192 0.00176793 -0.00074657 -0.295992 0.00172543 -0.00121746 -0.293375 0.00252082 -0.00139041 -0.292369 0.00260784 -0.000889388 -0.292336 0.00147092 -0.000745773 -0.294685 0.00148608 -0.000402883 -0.294705 0.00177086 -0.000796774 -0.293379 0.00381469 -0.00100512 -0.291764 0.0017853 -0.000402883 -0.293382 0.0017853 0.000397117 -0.293382 0.00263718 -0.000402883 -0.292325 0.00386738 0.000397117 -0.291752 0.00176793 0.000740804 -0.295992 0.00147092 0.000740007 -0.294685 0.00148608 0.000397117 -0.294705 0.00177086 0.000791008 -0.293379 0.00263718 0.000397117 -0.292325 0.00167421 0.00109974 -0.295899 0.00142458 0.00111045 -0.294629 0.00260784 0.000883622 -0.292336 0.00222389 0.00188296 -0.292503 0.00101485 0.00259712 -0.294947 0.00128785 0.0017082 -0.294427 0.00107156 0.00259712 -0.293986 0.0025897 0.00259712 -0.292053 0.00366276 0.00159712 -0.291799 0.00252082 0.00138464 -0.292369 0.00172543 0.0012117 -0.293375 0.00158644 0.00174051 -0.293377 -0.0187841 0.00159712 -0.0367201 -0.0185898 0.00159712 -0.0357704 -0.0185898 -0.00160288 -0.0357704 -0.0175025 -0.00160288 -0.0329532 -0.0150597 0.00159712 -0.0298124 -0.0117241 0.00159712 -0.0276431 -0.0117241 -0.00160288 -0.0276431 -0.0148722 0.00159712 -0.0447728 -0.0166795 0.00159712 -0.0439914 -0.0166989 -0.00160288 -0.0439779 -0.0180512 0.00159712 -0.0425629 -0.0180512 -0.00160288 -0.0425629 -0.0187634 -0.00160288 -0.0406989 -0.0150597 -0.00160288 -0.0298124 -0.0119898 -0.00254207 -0.0270426 -0.0123692 -0.002579 -0.0270757 -0.0117545 -0.00198557 -0.0275733 -0.0175695 -0.00198557 -0.032917 -0.0164486 -0.00160288 -0.031328 -0.0187841 -0.00160288 -0.0367201 -0.0188592 -0.00198557 -0.0367078 -0.0188384 -0.00198557 -0.0407119 -0.019052 -0.00230999 -0.040749 -0.0119702 -0.00252676 -0.0270769 -0.0177603 -0.00230999 -0.0328142 -0.0190731 -0.00230999 -0.036673 -0.0193934 -0.00252676 -0.0366209 -0.0197487 -0.00260288 -0.0408698 -0.0154774 -0.00252676 -0.0293579 -0.0183827 -0.00260288 -0.0324786 -0.0180459 -0.00252676 -0.0326602 -0.0152579 -0.00230999 -0.0295967 -0.0118409 -0.00230999 -0.0273745 -0.0103956 -0.00225543 -0.0269037 -0.0127016 -0.00160288 -0.0281218 -0.0151112 -0.00198557 -0.0297564 -0.0197711 -0.00260288 -0.0365594 -0.0192561 -0.00246891 -0.0407844 -0.0190454 -0.00230999 -0.0407873 -0.0188954 -0.00210288 -0.0407218 -0.0188318 -0.00198557 -0.0407502 -0.0148722 -0.00160288 -0.0447728 -0.0187568 -0.00160288 -0.0407372 -0.0180449 -0.00160288 -0.0425729 -0.0166795 -0.00160288 -0.0439914 -0.0149069 -0.00160288 -0.0447653 -0.0148881 -0.00198557 -0.0448473 -0.0167228 -0.00198557 -0.044054 -0.0168464 -0.00230999 -0.0442321 -0.0181091 -0.00198557 -0.0426139 -0.0182918 -0.00230999 -0.0427305 -0.0188888 -0.00210288 -0.0407601 -0.0149333 -0.00230999 -0.0450593 -0.0150009 -0.00252676 -0.0453766 -0.0170312 -0.00252676 -0.0444987 -0.0185652 -0.00252676 -0.0429051 -0.0192494 -0.00246891 -0.0408227 -0.0129903 -0.00260288 -0.0458235 -0.0150806 -0.00260288 -0.0457509 -0.0172493 -0.00260288 -0.0448132 -0.0188878 -0.00260288 -0.043111 -0.0197421 -0.00260288 -0.0409081 -0.0127016 0.00159712 -0.0281218 -0.0197711 0.00259712 -0.0365594 -0.0183827 0.00259712 -0.0324786 -0.0157363 0.00259712 -0.0290761 -0.0117776 0.00250942 -0.0270241 -0.0118409 0.00230422 -0.0273745 -0.0123692 0.00257324 -0.0270757 -0.0079814 0.00159712 -0.0266934 -0.00921694 0.0019489 -0.0268011 -0.0117545 0.0019798 -0.0275733 -0.0104758 0.00226799 -0.0269107 -0.0154774 0.002521 -0.0293579 -0.0119702 0.002521 -0.0270769 -0.0164486 0.00159712 -0.031328 -0.0152579 0.00230422 -0.0295967 -0.0151112 0.0019798 -0.0297564 -0.0180459 0.002521 -0.0326602 -0.0177603 0.00230422 -0.0328142 -0.0190731 0.00230422 -0.036673 -0.0188592 0.0019798 -0.0367078 -0.0175695 0.0019798 -0.032917 -0.0175025 0.00159712 -0.0329532 -0.0193934 0.002521 -0.0366209 -0.0187634 0.00159712 -0.0406989 -0.0187601 0.00159712 -0.0407181 -0.0188318 0.0019798 -0.0407502 -0.0188384 0.0019798 -0.0407119 -0.019052 0.00230422 -0.040749 -0.019365 0.002521 -0.0408427 -0.0193717 0.002521 -0.0408044 -0.0197421 0.00259712 -0.0409081 -0.0197487 0.00259712 -0.0408698 -0.0170312 0.002521 -0.0444987 -0.0188878 0.00259712 -0.043111 -0.0130556 0.00248866 -0.0453753 -0.0130665 0.00249712 -0.045394 -0.0130101 0.00259069 -0.0457119 -0.0150806 0.00259712 -0.0457509 -0.0148881 0.0019798 -0.0448473 -0.0131362 0.00201071 -0.0449246 -0.0182918 0.00230422 -0.0427305 -0.0190454 0.00230422 -0.0407873 -0.0181091 0.0019798 -0.0426139 -0.0185652 0.002521 -0.0429051 -0.0168464 0.00230422 -0.0442321 -0.0166989 0.00159712 -0.0439779 -0.0180449 0.00159712 -0.0425729 -0.0172493 0.00259712 -0.0448132 -0.0150009 0.002521 -0.0453766 -0.0149333 0.00230422 -0.0450593 -0.0167228 0.0019798 -0.044054 -0.0149069 0.00159712 -0.0447653 0.0110346 -0.00210288 -0.206603 0.0100584 -0.00257848 -0.202493 0.00349164 -0.00241979 -0.285406 0.0033444 -0.0024734 -0.285558 0.0111682 -0.00160288 -0.206593 0.0111964 -0.00210288 -0.249377 0.0107691 -0.00160288 -0.255101 0.00969366 -0.00210288 -0.262076 0.0087277 -0.00160288 -0.268251 0.00859635 -0.00210288 -0.268225 0.00617588 -0.00210288 -0.278181 0.0108316 -0.00246891 -0.249346 0.0118088 -0.00210288 -0.238799 0.011443 -0.00246891 -0.238786 0.0118698 -0.00210288 -0.223293 0.0106171 -0.00222756 -0.202438 0.0106696 -0.00246891 -0.20663 0.0115039 -0.00246891 -0.223302 0.0103334 -0.00260288 -0.249305 0.00883811 -0.00260288 -0.261941 0.00933206 -0.00246891 -0.262019 0.00823751 -0.00246891 -0.268153 0.00582426 -0.00246891 -0.278079 0.00534394 -0.00260288 -0.27794 0.00370187 0.00231312 -0.285188 0.0105437 0.002521 -0.206519 0.00969595 0.00259711 -0.200826 0.0101621 0.00259712 -0.206548 0.010213 0.00248763 -0.201547 0.0108292 0.00169946 -0.202408 0.00393563 0.00214933 -0.284945 0.00622844 0.0019798 -0.278207 0.0111593 0.00159712 -0.206474 0.0120023 0.00159712 -0.223233 0.0119262 0.0019798 -0.223235 0.0119427 0.00159712 -0.238803 0.0118667 0.0019798 -0.238801 0.0112541 0.0019798 -0.249381 0.00774503 0.00259712 -0.268065 0.00570856 0.002521 -0.278057 0.00313036 0.00252629 -0.285778 0.0060202 0.00230422 -0.278147 0.0081202 0.002521 -0.268141 0.00843825 0.00230422 -0.268205 0.00921616 0.002521 -0.262001 0.0107147 0.002521 -0.249337 0.011038 0.00230422 -0.249364 0.0113258 0.002521 -0.238782 0.0113852 0.002521 -0.223248 0.0117095 0.00230422 -0.22324 0.0108672 0.00230422 -0.206495 0.00865077 0.0019798 -0.268248 0.00953667 0.00230422 -0.262051 0.00975082 0.0019798 -0.262084 0.01165 0.00230422 -0.238793 0.0110834 0.0019798 -0.206479 0.0107691 0.00159712 -0.255101 0.00420526 0.00173083 -0.284665 -0.0167854 -0.00194724 -0.052193 -0.0167134 -0.00170609 -0.0522767 -0.0169511 -0.00218907 -0.0520001 -0.0168832 -0.0021083 -0.0520791 -0.0126666 -0.00210288 -0.0743111 -0.00862283 -0.00222758 -0.0945495 -0.00886813 -0.00245083 -0.0946017 -0.0084085 -0.00160288 -0.0945039 -0.00846364 -0.00193389 -0.0945156 -0.00889755 -0.00246891 -0.094608 -0.0114374 -0.00260288 -0.0848224 -0.0125352 -0.00160288 -0.0742852 -0.0167065 -0.00160288 -0.0522847 -0.0130257 -0.00246891 -0.0743821 -0.0109475 -0.00246891 -0.0847223 -0.0105889 -0.00210288 -0.084649 -0.0172686 0.00242309 -0.0516307 -0.0174066 0.00248685 -0.05147 -0.0124654 0.00159712 -0.0746382 -0.0125352 0.00159712 -0.0742852 -0.0167854 0.00194148 -0.052193 -0.0126099 0.0019798 -0.0742999 -0.00846364 0.00192812 -0.0945156 -0.0084085 0.00159712 -0.0945039 -0.0104576 0.00159712 -0.0846221 -0.00901229 0.002521 -0.0946324 -0.00938659 0.00259712 -0.0947121 -0.0110624 0.002521 -0.0847458 -0.0114374 0.00259712 -0.0848224 -0.0107446 0.00230422 -0.0846808 -0.0131408 0.002521 -0.0744048 -0.0128225 0.00230422 -0.0743419 -0.0105322 0.0019798 -0.0846374 -0.0195328 -2.88296e-06 -0.312294 -0.0197077 -2.88296e-06 -0.312332 -0.0196923 0.00040486 -0.312332 -0.0195984 -0.000406831 -0.312303 -0.0198701 -2.88296e-06 -0.312441 -0.0169865 0.00292678 -0.309765 -0.0167928 0.0026381 -0.309956 -0.0169109 0.00275434 -0.30984 -0.0178324 0.0029964 -0.310568 -0.0196523 0.00108653 -0.312284 -0.0198545 0.000411422 -0.312441 -0.0197787 0.000408358 -0.312378 -0.0177907 0.00282658 -0.310556 -0.0177106 0.00267413 -0.310589 -0.0186925 0.00220922 -0.311483 -0.0187762 0.00232104 -0.311493 -0.0193686 0.00167136 -0.312036 -0.0195661 0.00104692 -0.312241 -0.0185923 0.0021136 -0.311504 -0.019187 0.00153414 -0.311994 -0.0192832 0.00159933 -0.312003 -0.017602 0.00255776 -0.310662 -0.0190853 0.00147934 -0.312009 -0.0194716 0.00101001 -0.312218 -0.0195984 0.000401065 -0.312303 -0.0193729 0.000977398 -0.312216 -0.0197787 -0.000414124 -0.312378 -0.0197931 -0.000887222 -0.3124 -0.0195546 -0.00154704 -0.312195 -0.0190145 -0.00211402 -0.311714 -0.0190792 -0.00221758 -0.311761 -0.0196923 -0.000410626 -0.312332 -0.0197181 -0.000859652 -0.312338 -0.0194829 -0.00148379 -0.312138 -0.0181974 -0.00268252 -0.310947 -0.0181156 -0.00254436 -0.310961 -0.0196318 -0.000832528 -0.312293 -0.0193972 -0.0014227 -0.312101 -0.0193017 -0.00136681 -0.312086 -0.01893 -0.00201596 -0.311694 -0.0180108 -0.0024334 -0.311013 -0.0194396 -0.000783982 -0.312261 -0.0195377 -0.000806957 -0.312267 -0.0188315 -0.0019301 -0.311703 -0.0192013 -0.00131891 -0.312094 -0.0178938 -0.00236118 -0.311097 -0.00535349 0.00263744 -0.29607 -0.00558547 0.00292208 -0.295929 -0.00896298 0.00263839 -0.301245 -0.00518547 0.00259712 -0.296172 -0.00909372 0.00275538 -0.301142 -0.0054944 0.00275192 -0.295984 -0.00917702 0.00292879 -0.301077 -0.00561203 0.00312048 -0.295913 -0.00880638 0.00259712 -0.301367 -0.0109615 0.00263851 -0.303679 -0.0110877 0.00275584 -0.303571 -0.00919915 0.00312999 -0.30106 -0.011168 0.00292968 -0.303502 -0.0170072 0.00312714 -0.309745 -0.0111891 0.00313125 -0.303484 -0.0100815 -0.00264425 -0.302634 -0.0167928 -0.00264387 -0.309956 -0.0102096 -0.00276152 -0.302528 -0.0169109 -0.00276011 -0.30984 -0.0102911 -0.00293527 -0.30246 -0.0169865 -0.00293254 -0.309765 -0.0103125 -0.00313677 -0.302443 -0.00682838 -0.0026437 -0.298344 -0.00696486 -0.00275949 -0.298251 -0.00355901 -0.00264256 -0.29284 -0.0037058 -0.0027553 -0.292766 -0.00705242 -0.00293135 -0.298191 -0.00707678 -0.00313121 -0.298174 0.000830518 0.0029091 -0.281526 -0.0179709 0.00263599 -0.0669817 -0.018272 0.00310562 -0.0670394 -0.0182371 0.00291168 -0.0670327 -0.0146831 0.00310553 -0.0851615 -0.0112528 0.00291171 -0.101404 -0.0117777 0.00310564 -0.0991044 -0.0112876 0.00310565 -0.101411 -0.00530653 0.00310548 -0.129164 -0.00527169 0.00291159 -0.129156 0.00787916 0.00311254 -0.231393 0.00700465 0.00310639 -0.250166 0.005814 0.00310281 -0.260116 0.003846 0.00310034 -0.270614 0.000795767 0.0031019 -0.281514 -0.0241676 0.00291189 -0.0340684 -0.0181312 0.00274658 -0.0670124 -0.00516627 0.00274653 -0.129134 0.000463492 0.00274712 -0.156946 0.000357603 0.00291273 -0.156966 0.00348414 0.00291505 -0.175619 0.00650099 0.002918 -0.200607 0.00752714 0.0029183 -0.214944 0.00763409 0.00274998 -0.214938 0.00791268 0.00291652 -0.231393 0.00703986 0.00291222 -0.250169 0.00714716 0.00274686 -0.250179 0.00585001 0.00290973 -0.260122 0.0038822 0.00290801 -0.270623 0.00595681 0.00274558 -0.260138 -0.0038016 0.00291744 -0.292718 -0.0240613 0.00274669 -0.0340505 -0.0111474 0.00274659 -0.101382 -0.0109877 0.002636 -0.101348 0.000624188 0.00263614 -0.156917 0.00359041 0.00274831 -0.175604 0.00660766 0.00274982 -0.200597 0.0067713 0.00263687 -0.200582 0.00779824 0.00263692 -0.21493 0.00801995 0.00274906 -0.231394 0.00398765 0.0027447 -0.270647 0.00414618 0.00263549 -0.270683 0.000932907 0.00274526 -0.28156 0.00108716 0.00263564 -0.281612 -0.0037058 0.00274953 -0.292766 -0.00355901 0.0026368 -0.29284 -0.0239003 0.00263602 -0.0340234 -0.00500666 0.00263598 -0.129099 -0.00481767 0.00259712 -0.129059 0.00375244 0.00263646 -0.175579 0.00394474 0.00259712 -0.175551 0.00818402 0.00263667 -0.231395 0.00730981 0.00263607 -0.250194 0.00611791 0.00263572 -0.260162 -0.0164944 -0.00264175 -0.0745744 -0.0240613 -0.00275246 -0.0340505 -0.0241676 -0.00291766 -0.0340684 -0.0038016 -0.00292321 -0.292718 0.0006983 -0.002915 -0.281915 0.00180254 -0.00310653 -0.278362 0.00386152 -0.00291377 -0.270713 0.00722747 -0.00311313 -0.247528 0.00784588 -0.00292142 -0.235847 0.00785883 -0.00292336 -0.224156 -0.00355049 -0.00311131 -0.137455 0.000766491 -0.00311323 -0.159396 0.00475807 -0.00292211 -0.184803 0.00651464 -0.00292378 -0.200757 0.0064819 -0.00312044 -0.20076 -0.00536472 -0.00311125 -0.128892 -0.0167953 -0.0031113 -0.0746337 -0.0167604 -0.00291739 -0.0746268 -0.0166546 -0.00275232 -0.074606 -0.00341012 -0.00275232 -0.137426 0.00255044 -0.0027536 -0.168927 -0.00351564 -0.0029174 -0.137448 0.0024443 -0.00291989 -0.168945 0.00486449 -0.00275474 -0.18479 0.00736978 -0.00275297 -0.247539 0.00726243 -0.00291867 -0.24753 0.0059851 -0.00291571 -0.259203 -0.0239003 -0.00264179 -0.0340234 0.00502719 -0.00264241 -0.184769 0.00662131 -0.00275559 -0.200747 0.00678495 -0.00264264 -0.200732 0.00796597 -0.00275538 -0.224154 0.00813018 -0.00264258 -0.224151 0.0081171 -0.00264231 -0.235854 0.00795322 -0.00275439 -0.23585 0.00753274 -0.00264193 -0.247551 0.00625325 -0.00264152 -0.259241 0.00609197 -0.00275146 -0.259218 0.00095459 -0.00264142 -0.282002 0.00396696 -0.00275047 -0.270737 0.000800533 -0.00275109 -0.28195 -0.0163048 -0.00260288 -0.074537 -0.00325033 -0.00264175 -0.137393 0.00271197 -0.0026421 -0.168901 0.00522044 -0.00260288 -0.184744 0.00831166 -0.00260288 -0.235858 0.00644401 -0.00260288 -0.259269 0.00412546 -0.00264125 -0.270774 0.00431269 -0.00260288 -0.270816 -0.0246091 0.00259712 -0.028593 -0.0254898 0.00259712 -0.0231916 -0.0258419 0.00274668 -0.0232483 -0.0250673 0.00291188 -0.0286685 -0.0259483 0.00291187 -0.0232655 -0.0247999 0.00263602 -0.0286244 -0.024961 0.00274668 -0.028651 -0.0242027 -0.00311168 -0.0340742 -0.0251023 -0.00311167 -0.0286743 -0.0250673 -0.00291765 -0.0286685 -0.0256807 -0.00264179 -0.0232223 -0.0247999 -0.00264179 -0.0286244 -0.024961 -0.00275245 -0.028651 -0.0264069 0.000404859 -0.020736 -0.026369 0.00123367 -0.0208777 -0.0261979 0.000401144 -0.0209369 -0.0255907 0.00253872 -0.022688 -0.0256807 0.00263602 -0.0232223 -0.0257774 0.00258175 -0.0227087 -0.0259124 0.00229468 -0.0220107 -0.0257312 0.00225124 -0.0220073 -0.0259315 0.00111963 -0.0211134 -0.026144 0.000400187 -0.0209605 -0.0259363 0.0026907 -0.0227093 -0.0260257 0.00179599 -0.021451 -0.0261056 0.00114138 -0.0210876 -0.0262579 0.00118106 -0.0210056 -0.0260685 0.00239065 -0.0219762 -0.0261794 0.00186798 -0.0213878 -0.0262897 0.00196643 -0.0212832 -0.0262955 0.000402878 -0.0208717 -0.0263752 0.000404295 -0.0207855 -0.0260439 0.00284938 -0.0226898 -0.0260842 0.00303422 -0.022653 -0.0261776 0.00252582 -0.0219086 -0.0262247 0.0026814 -0.0218173 -0.0263422 0.00207843 -0.0211508 -0.0264646 0.000405884 -0.0205701 -0.0259711 -0.000402883 -0.0209914 -0.0263752 -0.000410061 -0.0207855 -0.0262775 -0.000894544 -0.0209232 -0.0262955 -0.000408644 -0.0208717 -0.0259522 -0.000853827 -0.0210381 -0.0261256 -0.00086873 -0.0210093 -0.0258836 -0.00154475 -0.0213109 -0.0260594 -0.00157626 -0.0212923 -0.0256381 -0.00247601 -0.0224552 -0.0258229 -0.00252 -0.0224705 -0.0254898 -0.00260288 -0.0231916 -0.0259544 -0.0021508 -0.0217999 -0.0259809 -0.00262606 -0.0224592 -0.0258419 -0.00275245 -0.0232483 -0.0263888 -0.000928053 -0.0207904 -0.0262125 -0.00163718 -0.0212209 -0.0261095 -0.00223968 -0.0217547 -0.0262191 -0.00236354 -0.021673 -0.0264456 -0.000965082 -0.0206275 -0.0263231 -0.00171965 -0.021106 -0.0263771 -0.00181303 -0.0209625 -0.026089 -0.00277877 -0.022423 -0.0261316 -0.00295595 -0.0223672 -0.0259483 -0.00291764 -0.0232655 -0.0259833 -0.00311166 -0.0232712 -0.0264719 -2.88296e-06 -0.0205701 -0.0264069 -0.000410625 -0.020736 -0.0263825 -1.29355e-06 -0.0207855 -0.0262051 1.85723e-06 -0.0209369 -0.0261979 -0.00040691 -0.0209369 -0.026144 -0.000405953 -0.0209605 -0.00862283 0.00222181 -0.0945495 -0.00886813 0.00244507 -0.0946017 -0.00767221 0.00215983 -0.0950646 -0.00904836 0.00259712 -0.0948862 -0.00878506 0.00249011 -0.0948581 -0.00863553 0.00259712 -0.0950541 -0.0082501 0.00259712 -0.0951324 -0.00815874 0.00249163 -0.0951131 -0.00910759 0.00259712 -0.0948571 -0.00917188 0.00257273 -0.0946664 -0.00938101 0.00259712 -0.0947151 -0.00835916 0.00194566 -0.0947676 -0.00852677 0.00225495 -0.0948032 -0.00836379 0.0023497 -0.0950012 -0.00793078 0.00207108 -0.0950648 -0.00817203 0.00199587 -0.0949605 -0.00785183 0.00159712 -0.0950481 -0.00757846 0.00159712 -0.0950447 -0.00810562 0.00159712 -0.0949464 -0.00830112 0.00159712 -0.0947553 -0.00835916 -0.00195143 -0.0947676 -0.00938101 -0.00260288 -0.0947151 -0.00917188 -0.00257849 -0.0946664 -0.00904836 -0.00260288 -0.0948862 -0.00867566 -0.00260288 -0.0950411 -0.0082501 -0.00260288 -0.0951324 -0.00815874 -0.0024974 -0.0951131 -0.00878506 -0.00249588 -0.0948581 -0.00836379 -0.00235547 -0.0950012 -0.00852677 -0.00226071 -0.0948032 -0.00853954 -0.00210288 -0.0945318 -0.00817203 -0.00200163 -0.0949605 -0.00789663 -0.00260288 -0.0951121 -0.00785183 -0.00160288 -0.0950481 -0.00793078 -0.00207685 -0.0950648 -0.00810562 -0.00160288 -0.0949464 -0.00830112 -0.00160288 -0.0947553 0.00469296 0.00194295 -0.285639 0.0042549 0.00205047 -0.285596 0.0044486 0.00214933 -0.285729 0.00411508 0.00194295 -0.284759 0.00417572 0.00168643 -0.284978 0.00412009 0.00185057 -0.285039 0.0039802 0.00205047 -0.285176 0.00355818 0.00235911 -0.28555 0.00428704 0.00167053 -0.285276 0.00423429 0.00181783 -0.28531 0.00451621 0.00168643 -0.285496 0.00443732 0.00185057 -0.285522 0.00409155 0.00201599 -0.285403 0.00364275 0.00234045 -0.285695 0.00349164 0.00241403 -0.285406 0.00248435 0.00259711 -0.286442 0.00335794 0.00252609 -0.286127 0.00384564 0.00241403 -0.28595 0.00374045 0.00235911 -0.28583 0.00248301 0.00259711 -0.28644 0.00429407 0.00159712 -0.285271 0.00452832 0.00159712 -0.285493 0.0041837 0.00159712 -0.284969 0.0041837 -0.00160288 -0.284969 0.00452832 -0.00160288 -0.285493 0.00483683 -0.00160288 -0.285585 0.00429407 -0.00160288 -0.285271 0.00451621 -0.00169219 -0.285496 0.00420526 -0.00173659 -0.284665 0.00411508 -0.00194871 -0.284759 0.00481591 -0.00173659 -0.285593 0.00443732 -0.00185633 -0.285522 0.0042549 -0.00205623 -0.285596 0.00398685 -0.00210721 -0.284892 0.00412009 -0.00185633 -0.285039 0.00393563 -0.0021551 -0.284945 0.0039802 -0.00205623 -0.285176 0.00384564 -0.00241979 -0.28595 0.00248435 -0.00260288 -0.286442 0.00428704 -0.0016763 -0.285276 0.00417572 -0.00169219 -0.284978 0.00409155 -0.00202175 -0.285403 0.00355818 -0.00236488 -0.28555 0.00423429 -0.0018236 -0.28531 0.00374045 -0.00236488 -0.28583 0.00364275 -0.00234621 -0.285695 0.00248301 -0.00260288 -0.28644 0.0096974 0.00259711 -0.200825 0.010397 0.00245673 -0.201309 0.010559 0.00237729 -0.20142 0.0109047 0.00210512 -0.201649 0.011064 0.00187061 -0.201747 0.0113592 0.00194166 -0.201608 0.0111241 0.00167404 -0.201782 0.0111294 0.00159712 -0.201785 0.0108498 0.00187061 -0.202003 0.0102996 0.00245673 -0.201426 0.010337 0.0024233 -0.20172 0.0104372 0.00237729 -0.201566 0.0107243 0.00210512 -0.201865 0.0106179 0.00218429 -0.202113 0.0107654 0.00194166 -0.202319 0.0108943 0.00167404 -0.202056 0.0108351 0.00159712 -0.202416 0.0108981 0.00159712 -0.202061 0.0109956 -0.00160288 -0.201908 0.0112072 -0.00160288 -0.201737 0.0103675 -0.00245082 -0.202462 0.0103375 -0.00246891 -0.202465 0.00983988 -0.00260288 -0.202514 0.00984434 -0.00260288 -0.20251 0.0100636 -0.00260288 -0.202293 0.010112 -0.00260288 -0.202247 0.010456 -0.00260288 -0.201964 0.0103713 -0.00249671 -0.202194 0.0107018 -0.00210288 -0.202429 0.0106347 -0.00226161 -0.202168 0.0111266 -0.00207731 -0.201745 0.0111294 -0.00160288 -0.201785 0.0109278 -0.00200235 -0.201914 0.0108981 -0.00160288 -0.202061 0.0108651 -0.00160288 -0.202146 0.0108942 -0.00249812 -0.201766 0.010732 -0.00235658 -0.201933 0.0108058 -0.00195201 -0.202152 0.010779 -0.00193388 -0.202422 0.0108351 -0.00160288 -0.202416 0.0109024 -0.00160288 -0.195686 0.0105474 -0.00160288 -0.195627 0.0102691 -0.00160288 -0.195398 -0.0167065 0.00159712 -0.0522847 -0.0167019 0.00159712 -0.0520111 -0.0167134 0.00170032 -0.0522767 -0.0167576 0.00188096 -0.0519488 -0.0167064 0.00167847 -0.0520059 -0.0165972 0.0016708 -0.0517572 -0.0164023 0.00167847 -0.051568 -0.0164736 0.00188096 -0.0515399 -0.0166489 0.00185987 -0.0517212 -0.0167947 0.00209271 -0.0516199 -0.0170918 0.00231035 -0.0518364 -0.0169511 0.0021833 -0.0520001 -0.0179897 0.00259711 -0.0507912 -0.0173508 0.00246043 -0.051373 -0.0172881 0.00245155 -0.051277 -0.0166955 0.00231035 -0.0512659 -0.0170433 0.00238395 -0.0512734 -0.01722 0.00246043 -0.0511847 -0.0171485 0.00248685 -0.0510986 -0.016656 0.00211589 -0.0514599 -0.0171299 0.00237072 -0.0513869 -0.0168962 0.00211589 -0.0518057 -0.0172061 0.00238395 -0.0515077 -0.0165927 0.00159712 -0.0517603 -0.0163958 0.00159712 -0.0515704 -0.0163958 -0.00160288 -0.0515704 -0.0165927 -0.00160288 -0.0517603 -0.0167019 -0.00160288 -0.0520111 -0.016151 -0.00170609 -0.0514669 -0.0164023 -0.00168424 -0.051568 -0.0164736 -0.00188673 -0.0515399 -0.0167576 -0.00188673 -0.0519488 -0.0165972 -0.00167657 -0.0517572 -0.0167064 -0.00168424 -0.0520059 -0.0166489 -0.00186564 -0.0517212 -0.0167947 -0.00209847 -0.0516199 -0.016656 -0.00212166 -0.0514599 -0.0166955 -0.00231611 -0.0512659 -0.0172686 -0.00242886 -0.0516307 -0.0173514 -0.00246928 -0.0515343 -0.0172061 -0.00238972 -0.0515077 -0.0173508 -0.0024662 -0.051373 -0.0179897 -0.00260288 -0.0507912 -0.01722 -0.0024662 -0.0511847 -0.0172881 -0.00245731 -0.051277 -0.0174066 -0.00249261 -0.05147 -0.0168962 -0.00212166 -0.0518057 -0.0171299 -0.00237648 -0.0513869 -0.0170433 -0.00238972 -0.0512734 -0.0171485 -0.00249261 -0.0510986 -0.0179883 -0.00260288 -0.0507891 -0.00687412 0.00159712 -0.101745 -0.00658582 -0.00160288 -0.101022 -0.0131031 0.00228859 -0.0451098 -0.0131386 0.0019798 -0.0449113 -0.0131512 0.00249712 -0.0448405 -0.0130526 -0.00250288 -0.0453921 -0.0131512 -0.00250288 -0.0448405 -0.0131004 -0.00231 -0.0451249 -0.0131191 -0.00218451 -0.0450201 -0.0131386 -0.00198557 -0.0449113 -0.013145 -0.00188235 -0.0448756 0.0139806 0.00159712 -0.286136 0.0139466 0.00249712 -0.286699 0.0136201 0.00249712 -0.292125 0.0136377 0.00230422 -0.291833 -0.0121463 0.00230422 -0.0504584 -0.0121082 0.0019798 -0.0506718 -0.0120947 -0.00250288 -0.0507467 -0.0121463 -0.00230999 -0.0504584 -0.0121941 -0.00250288 -0.0501914 -0.00716055 0.00230422 -0.101806 -0.00785208 0.00259712 -0.101954 -0.00639522 0.00230422 -0.100628 -0.00686887 0.00246314 -0.10061 -0.0065417 0.00259712 -0.0999361 -0.00736955 0.00246314 -0.101381 -0.00700962 0.00209712 -0.101448 -0.00719598 0.00246314 -0.100946 -0.00687788 0.00159712 -0.101472 -0.006889 0.00209712 -0.101145 -0.00677663 0.00159712 -0.101218 -0.00666166 0.00209712 -0.100912 -0.00658582 0.00159712 -0.101022 -0.00633455 0.00159712 -0.100914 -0.00700514 0.00209712 -0.101773 -0.0073631 0.00246314 -0.10185 -0.00747783 0.002521 -0.101874 0.00182047 0.0019798 -0.14285 -0.00694856 0.0019798 -0.101761 0.00577037 0.0019798 -0.163854 0.00160802 0.00230422 -0.142893 0.0058454 0.00159712 -0.163841 0.000915035 0.00259712 -0.143034 0.00831945 0.002521 -0.184634 0.0079398 0.00259712 -0.184682 0.00914654 0.00259712 -0.195164 0.0095272 0.002521 -0.195125 0.00523686 0.002521 -0.163945 0.00555667 0.00230422 -0.163891 0.00129008 0.002521 -0.142958 0.0101412 0.00159712 -0.195061 0.0100655 0.0019798 -0.195069 0.00885636 0.0019798 -0.184566 0.0098499 0.00230422 -0.195091 0.0086413 0.00230422 -0.184593 0.0102691 0.00159712 -0.195398 0.010008 0.00209712 -0.195075 0.00964389 0.00246314 -0.195113 0.00986308 0.00246314 -0.19569 0.0101603 0.00209712 -0.195476 0.0103401 0.00246314 -0.196082 0.0104918 0.00209712 -0.195748 0.0109024 0.00159712 -0.195686 0.0105474 0.00159712 -0.195627 0.0143725 0.00209712 -0.201255 0.0143385 0.00246314 -0.20089 0.0147231 0.00252906 -0.200893 0.0149391 0.00220303 -0.201337 0.0147442 0.00197035 -0.201355 0.0143893 0.00160159 -0.201388 0.0154534 0.00249712 -0.202078 0.0153102 0.00249712 -0.201589 0.0151376 0.00249712 -0.201318 0.0150827 0.00240681 -0.201323 0.0150562 0.0027168 -0.200971 0.0147596 0.00213518 -0.201285 0.015287 0.00299775 -0.201112 0.0149962 0.00289001 -0.200327 0.0146732 0.00267324 -0.200357 0.0152879 0.00359712 -0.2003 0.0152121 0.00321443 -0.200307 0.0139214 0.00259712 -0.19641 0.0138331 0.00160159 -0.195414 0.0147515 0.00249712 -0.194539 0.014741 0.00249712 -0.194863 0.0147348 0.00273533 -0.19518 0.0145814 0.00249712 -0.195344 0.0145403 0.00250701 -0.19543 0.0138411 0.00209712 -0.195547 0.0142315 0.00235445 -0.195613 0.0148457 0.00344307 -0.195551 0.014264 0.00259035 -0.195962 0.0145793 0.00279043 -0.195849 0.0143024 0.00267324 -0.196374 0.0147836 0.00308986 -0.195704 0.0146254 0.00289001 -0.196344 0.0148413 0.00321443 -0.196324 0.0149171 0.00359712 -0.196317 0.0109488 -0.00246891 -0.196184 0.0148707 -0.00246891 -0.195819 0.0148368 -0.00210288 -0.195455 0.0109149 -0.00210288 -0.19582 0.010426 -0.00230999 -0.195893 0.010008 -0.00210288 -0.195075 0.0100655 -0.00198557 -0.195069 0.0102073 -0.00198557 -0.195442 0.0105158 -0.00198557 -0.195696 0.0109095 -0.00198557 -0.195762 0.00976781 -0.00252676 -0.195758 0.0102915 -0.00252676 -0.196188 0.0100313 -0.00230999 -0.195569 0.0109296 -0.00230999 -0.195978 0.0109597 -0.00252676 -0.196301 0.00964389 -0.00246891 -0.195113 0.00176377 -0.00210288 -0.142862 0.00312817 -0.00160288 -0.149027 0.0101412 -0.00160288 -0.195061 0.00893187 -0.00160288 -0.184557 0.00879896 -0.00210288 -0.184573 0.0058454 -0.00160288 -0.163841 0.0098499 -0.00230999 -0.195091 0.00571333 -0.00210288 -0.163864 0.00535251 -0.00246891 -0.163925 0.00140505 -0.00246891 -0.142935 -0.00785208 -0.00260288 -0.101954 0.00843584 -0.00246891 -0.184619 0.0079398 -0.00260288 -0.184682 0.00914654 -0.00260288 -0.195164 -0.00639522 -0.00230999 -0.100628 -0.00687412 -0.00160288 -0.101745 -0.00700514 -0.00210288 -0.101773 -0.00700962 -0.00210288 -0.101448 -0.00687788 -0.00160288 -0.101472 -0.00677663 -0.00160288 -0.101218 -0.006889 -0.00210288 -0.101145 -0.00633455 -0.00160288 -0.100914 -0.00666166 -0.00210288 -0.100912 -0.0073631 -0.00246891 -0.10185 -0.00736955 -0.00246891 -0.101381 -0.00686887 -0.00246891 -0.10061 -0.00719598 -0.00246891 -0.100946 -0.00786122 -0.00260288 -0.10129 -0.00761533 -0.00260288 -0.100673 -0.00715193 -0.00260288 -0.100198 -0.00234092 -0.00198557 -0.0999909 -0.00238583 -0.00230999 -0.0997789 -0.00232516 -0.00594948 -0.100065 -0.00232516 0.00249712 -0.100065 -0.00460143 0.01479 0.0472924 -0.0032034 0.01479 0.0491129 -0.00349618 0.0152042 0.049406 -0.00138181 0.01479 0.0505096 0.00301507 0.01479 0.051686 0.000632136 0.0152042 0.0517874 0.00301523 0.0152042 0.0521002 0.00761832 0.0152042 0.050865 0.00923163 0.01479 0.0491083 0.00952463 0.0152042 0.0494011 0.0109871 0.0152042 0.0474937 0.0119061 0.0152042 0.0452728 0.0118047 0.01479 0.0428899 0.0122189 0.0152042 0.0428897 0.0115042 0.01479 0.0406142 0.0119043 0.0152042 0.0405069 0.010625 0.01479 0.0384939 0.00922702 0.01479 0.0366733 0.00740543 0.01479 0.0352766 0.00528443 0.01479 0.034399 0.0076124 0.0152042 0.0349178 0.00300855 0.01479 0.0341002 0.00539148 0.0152042 0.0339989 0.00300839 0.0152042 0.033686 -0.00138746 0.01479 0.0352799 -0.00320801 0.01479 0.0366779 -0.00350101 0.0152042 0.0363851 -0.00460469 0.01479 0.0384995 -0.00496349 0.0152042 0.0382925 -0.0061953 0.0152042 0.0428965 -0.00548063 0.01479 0.045172 0.0119061 -0.01521 0.0452728 0.0109871 -0.01521 0.0474937 0.00923163 -0.0147958 0.0491083 0.00761832 -0.01521 0.050865 0.00539808 -0.01521 0.0517856 0.00301523 -0.01521 0.0521002 0.000739194 -0.0147958 0.0513873 -0.00138181 -0.0147958 0.0505096 -0.0032034 -0.0147958 0.0491129 -0.00460143 -0.0147958 0.0472924 -0.00548063 -0.0147958 0.045172 -0.00588069 -0.01521 0.0452794 -0.00588246 -0.01521 0.0405135 -0.00496349 -0.01521 0.0382925 -0.00138746 -0.0147958 0.0352799 0.00528443 -0.0147958 0.034399 0.00300839 -0.01521 0.033686 0.00539148 -0.01521 0.0339989 0.0095198 -0.01521 0.0363803 0.0109837 -0.01521 0.0382866 0.010625 -0.0147958 0.0384939 0.0115042 -0.0147958 0.0406142 0.0118047 -0.0147958 0.0428899 0.0119043 -0.01521 0.0405069 -0.00588069 0.0152042 0.0452794 -0.00496007 0.0152042 0.0474996 -0.00158878 0.0152042 0.0508684 0.00301535 0.015421 0.0524247 0.00539808 0.0152042 0.0517856 0.00778064 0.015421 0.0511459 0.00975412 0.015421 0.0496304 0.0122176 0.015421 0.0404228 0.0109837 0.0152042 0.0382866 0.0112646 0.015421 0.0381243 0.00974912 0.015421 0.0361508 0.0095198 0.0152042 0.0363803 0.00777451 0.015421 0.0346368 0.00547533 0.015421 0.0336855 0.00300827 0.015421 0.0333616 0.000541452 0.015421 0.0336873 0.000625535 0.0152042 0.0340006 -0.0015947 0.0152042 0.0349212 -0.00619586 0.015421 0.0404296 -0.00588246 0.0152042 0.0405135 -0.00651972 0.015421 0.0428967 -0.00557231 0.0154971 0.0478534 -0.00619402 0.015421 0.0453635 -0.00524097 0.015421 0.047662 -0.0037255 0.015421 0.0496354 -0.003996 0.0154971 0.0499061 -0.00175089 0.015421 0.0511494 0.000449377 0.0154971 0.0524705 0.000548285 0.015421 0.0521008 0.00548217 0.015421 0.052099 0.00558135 0.0154971 0.0524686 0.0079721 0.0154971 0.0514772 0.0100248 0.0154971 0.0499009 0.0125892 0.0154971 0.0454556 0.0112681 0.015421 0.0476558 0.0122195 0.015421 0.0453566 0.0125433 0.015421 0.0428896 0.0125873 0.0154971 0.0403236 -0.00194848 0.0154971 0.034309 -0.00175702 0.015421 0.0346403 -0.00557599 0.0154971 0.0379392 -0.0037305 0.015421 0.0361558 -0.00524451 0.015421 0.0381304 -0.0069024 0.0154971 0.0428968 -0.00432053 0.0145732 0.0471301 -0.00297408 0.0145732 0.0488835 0.000739194 0.01479 0.0513873 0.00520665 0.0145732 0.0510722 0.00724877 0.0145732 0.0502255 0.00529073 0.01479 0.0513856 0.00741108 0.01479 0.0505064 0.00900214 0.0145732 0.048879 0.0106283 0.01479 0.0472867 0.0111925 0.0145732 0.0450819 0.0115059 0.01479 0.0451657 0.0114803 0.0145732 0.04289 0.0111909 0.0145732 0.0406983 0.0089977 0.0145732 0.0369028 0.00520058 0.0145732 0.0347124 0.00073289 0.01479 0.0344007 -0.00297852 0.0145732 0.0369072 -0.00516892 0.0145732 0.0407044 -0.00548232 0.01479 0.0406205 -0.00578108 0.01479 0.0428964 -0.00545666 0.0145732 0.0428963 -0.00398919 0.0144971 0.0469386 -0.00516729 0.0145732 0.045088 -0.0012197 0.0145732 0.0502286 0.000921953 0.0144971 0.0507042 0.000823045 0.0145732 0.0510739 0.00301495 0.0145732 0.0513616 0.0070573 0.0144971 0.0498941 0.00873145 0.0144971 0.0486085 0.0103473 0.0145732 0.0471246 0.0110976 0.0144971 0.0428901 0.0103441 0.0145732 0.0386562 0.0070521 0.0144971 0.0358891 0.00724332 0.0145732 0.0355576 0.00510167 0.0144971 0.0350821 0.00300881 0.0144971 0.0348073 0.00300867 0.0145732 0.0344247 -0.00103368 0.0144971 0.0358921 0.000816973 0.0145732 0.034714 -0.00122515 0.0145732 0.0355608 -0.00432367 0.0145732 0.0386616 -0.00507398 0.0144971 0.0428961 0.0103473 -0.014579 0.0471246 0.0115059 -0.0147958 0.0451657 0.0106283 -0.0147958 0.0472867 0.00900214 -0.014579 0.048879 0.00741108 -0.0147958 0.0505064 0.00529073 -0.0147958 0.0513856 0.00301507 -0.0147958 0.051686 -0.00578108 -0.0147958 0.0428964 -0.00548232 -0.0147958 0.0406205 -0.00460469 -0.0147958 0.0384995 -0.00320801 -0.0147958 0.0366779 -0.00297852 -0.014579 0.0369072 0.00073289 -0.0147958 0.0344007 0.00300855 -0.0147958 0.0341002 0.00520058 -0.014579 0.0347124 0.00740543 -0.0147958 0.0352766 0.0089977 -0.014579 0.0369028 0.00922702 -0.0147958 0.0366733 0.0103441 -0.014579 0.0386562 0.0114803 -0.014579 0.04289 0.0111925 -0.014579 0.0450819 0.00724877 -0.014579 0.0502255 0.00520665 -0.014579 0.0510722 0.00301495 -0.014579 0.0513616 0.000823045 -0.014579 0.0510739 -0.0012197 -0.014579 0.0502286 -0.00297408 -0.014579 0.0488835 -0.00398919 -0.0145029 0.0469386 -0.00432053 -0.014579 0.0471301 -0.00479768 -0.0145029 0.0449888 -0.00516729 -0.014579 0.045088 -0.00545666 -0.014579 0.0428963 -0.00516892 -0.014579 0.0407044 -0.00432367 -0.014579 0.0386616 -0.00122515 -0.014579 0.0355608 0.000816973 -0.014579 0.034714 0.00300867 -0.014579 0.0344247 0.00724332 -0.014579 0.0355576 0.0087272 -0.0145029 0.0371735 0.0100128 -0.0145029 0.0388476 0.0111909 -0.014579 0.0406983 0.0112681 -0.0154268 0.0476558 0.00975412 -0.0154268 0.0496304 0.00952463 -0.01521 0.0494011 0.00301535 -0.0154268 0.0524247 0.000548285 -0.0154268 0.0521008 0.000632136 -0.01521 0.0517874 -0.00175089 -0.0154268 0.0511494 -0.00158878 -0.01521 0.0508684 -0.0037255 -0.0154268 0.0496354 -0.00349618 -0.01521 0.049406 -0.00496007 -0.01521 0.0474996 -0.00619402 -0.0154268 0.0453635 -0.00651972 -0.0154268 0.0428967 -0.0061953 -0.01521 0.0428965 -0.00524451 -0.0154268 0.0381304 -0.00350101 -0.01521 0.0363851 -0.0015947 -0.01521 0.0349212 -0.00175702 -0.0154268 0.0346403 0.000625535 -0.01521 0.0340006 0.00300827 -0.0154268 0.0333616 0.00547533 -0.0154268 0.0336855 0.0076124 -0.01521 0.0349178 0.00777451 -0.0154268 0.0346368 0.0122176 -0.0154268 0.0404228 0.0122189 -0.01521 0.0428897 0.0125433 -0.0154268 0.0428896 0.0122195 -0.0154268 0.0453566 0.0100248 -0.0155029 0.0499009 0.00558135 -0.0155029 0.0524686 0.00778064 -0.0154268 0.0511459 0.00548217 -0.0154268 0.052099 0.000449377 -0.0155029 0.0524705 -0.003996 -0.0155029 0.0499061 -0.00656363 -0.0155029 0.0454627 -0.00524097 -0.0154268 0.047662 -0.00619586 -0.0154268 0.0404296 -0.00557599 -0.0155029 0.0379392 -0.0037305 -0.0154268 0.0361558 -0.00194848 -0.0155029 0.034309 0.000442269 -0.0155029 0.0333177 0.000541452 -0.0154268 0.0336873 0.00557424 -0.0155029 0.0333158 0.00796573 -0.0155029 0.0343053 0.0100196 -0.0155029 0.0358801 0.00974912 -0.0154268 0.0361508 0.0115959 -0.0155029 0.0379328 0.0112646 -0.0154268 0.0381243 0.0125873 -0.0155029 0.0403236 0.012926 -0.0155029 0.0428894 0.0125892 -0.0155029 0.0454556 -0.00440239 -0.0242029 0.0193042 -0.017846 -0.0242029 -0.00858529 -0.0123545 -0.0242029 -0.0154767 0.00439511 -0.0242029 -0.0193062 0.0072417 -0.0242029 -0.0125611 0.012551 -0.0242029 -0.00725567 0.0123472 -0.0242029 0.0154747 0.00725102 -0.0242029 0.0125537 1.74403e-06 -0.0242029 0.014499 0.00440944 0.0241971 0.0193009 0.0123472 0.0241971 0.0154747 0.0125564 0.0241971 0.00724433 0.0178324 0.0241971 -0.00859853 -9.0182e-06 0.0241971 -0.014501 -0.0125637 0.0241971 -0.00724635 -0.0145036 0.0241971 4.36931e-06 -0.0178396 0.0241971 0.00859651 1.74403e-06 0.0241971 0.014499 0.0135295 0.00549712 0.00520508 0.0144838 0.00549712 -0.000605127 0.0130855 -0.0030981 -0.00623986 0.0139762 -0.00400288 -0.00384977 0.0139762 0.00399712 -0.00384977 0.0135604 0.00461844 -0.00512616 0.0130491 -0.00250288 -0.00631572 0.00880178 0.00533273 0.0115192 0.00545171 -0.00250288 0.0134336 0.0061106 0.00399791 0.0131468 0.00630981 0.00362666 0.0130524 0.00714143 0.00475621 0.0126164 0.00694272 -0.00465147 0.0127268 0.00797553 0.00511044 0.0121061 0.00756953 -0.0049632 0.0123641 0.0086133 -0.00529709 0.0116608 0.0103437 -0.00550233 0.0101568 0.0103815 0.00549691 0.0101183 0.0104398 0.00549712 0.010058 0.0104107 -0.00550283 0.0100882 0.0104398 -0.00550288 0.010058 0.00367372 0.0159971 0.00636291 -9.09413e-07 -0.0160029 0.00734899 -0.00367627 -0.0160029 0.00636564 -0.00636756 -0.0160029 0.00367635 -0.003681 0.0159971 -0.00636493 0.003669 0.0159971 -0.00636766 0.00636029 0.0159971 -0.00367837 0.003669 -0.0160029 -0.00636766 0.00636029 -0.0160029 -0.00367837 0.00734636 0.0159971 -3.73948e-06 -0.0196344 -2.88296e-06 -0.311105 -0.0177582 -0.000102883 -0.311106 -0.0193087 -2.88296e-06 -0.310778 -0.0196306 -0.000102889 -0.311105 -0.0192979 -0.0011865 -0.31082 -0.0180063 -0.00219583 -0.309584 -0.0173289 -0.00230288 -0.308906 -0.0107436 -0.00230288 -0.301768 -0.00916791 -2.88296e-06 -0.299633 -0.00654489 -0.00230288 -0.296186 -0.00571657 -2.88296e-06 -0.294695 -0.00122255 -0.00230288 -0.285784 0.00318212 -2.88296e-06 -0.272161 0.00149654 -0.00230288 -0.278205 0.00126486 -2.88296e-06 -0.278868 -0.00104423 -2.88296e-06 -0.285236 0.00720052 -2.88296e-06 -0.210395 0.00770246 -2.88296e-06 -0.221935 0.0076062 -0.00230288 -0.216488 0.00778033 -2.88296e-06 -0.226434 0.00786179 -0.00230288 -0.226416 0.00787079 -0.00230288 -0.229169 0.00757055 -0.00230288 -0.240875 0.00775898 -2.88296e-06 -0.233151 0.00733074 -2.88296e-06 -0.244035 0.00737819 -0.00230288 -0.244161 0.00675394 -0.00230288 -0.251505 0.00595071 -2.88296e-06 -0.257789 0.0054999 -0.00230288 -0.26095 0.00473615 -2.88296e-06 -0.26513 0.00548425 -2.88296e-06 -0.190706 0.00611436 -2.88296e-06 -0.196743 0.00671497 -0.00230288 -0.202418 0.00716748 -0.00230288 -0.208456 0.00290571 -0.00230288 -0.170911 0.00515303 -0.00230288 -0.187145 0.00330019 -2.88296e-06 -0.17393 0.00430627 -2.88296e-06 -0.181075 -8.56619e-05 -0.00230288 -0.153611 -0.000993134 -2.88296e-06 -0.149118 -0.00436795 -2.88296e-06 -0.132582 -0.0045291 -0.00230288 -0.131619 -0.0119855 -2.88296e-06 -0.0971385 -0.0127563 -0.00230288 -0.0932729 -0.0190921 -2.88296e-06 -0.0617704 -0.0132716 -2.88296e-06 -0.0910161 -0.0150542 0.00229712 -0.0821491 0.000121725 0.00229712 -0.154717 -0.00466191 0.00229712 -0.130994 -0.00807445 -2.88296e-06 -0.115348 0.00192586 -2.88296e-06 -0.165216 0.00716749 0.00229712 -0.208456 0.00707498 -2.88296e-06 -0.208427 0.00671914 0.00229712 -0.202468 0.00628471 -2.88296e-06 -0.198537 0.00518395 0.00229712 -0.187402 0.00787127 0.00229712 -0.228624 0.00761622 0.00229712 -0.216727 0.00761307 0.00229712 -0.240005 0.006846 -2.88296e-06 -0.250149 0.0038138 -2.88296e-06 -0.269528 -0.000919849 0.00229712 -0.285034 -0.0241353 0.00216993 -0.0212661 -0.0240164 0.00229712 -0.0220034 -0.0242656 0.00166036 -0.0204553 -0.0222328 0.00229712 -0.0328124 -0.0200627 0.00149712 -0.0453613 -0.0200627 0.00229712 -0.0453613 -0.00209086 0.00149712 -0.133685 0.00425758 0.00229712 -0.167068 0.00953484 0.00149712 -0.2404 0.00804982 0.00229712 -0.257206 0.00538603 0.00229712 -0.271572 0.00538603 0.00149712 -0.271572 0.00132086 0.00229712 -0.284698 -0.00209086 -0.00230288 -0.133685 -0.00209086 -0.00150288 -0.133685 0.00425758 -0.00230288 -0.167068 0.00968187 -0.00230288 -0.221086 0.00968187 -0.00150288 -0.221086 0.00953484 -0.00230288 -0.2404 0.00804982 -0.00230288 -0.257206 0.00804982 -0.00150288 -0.257206 -0.0148393 -0.00214188 -0.309733 -0.0153569 -0.00183616 -0.310261 -0.00210501 -0.00230288 -0.292366 -0.000749215 -0.00150288 -0.289582 -0.0263224 -0.0012452 -0.0201223 -0.0263938 -0.000102883 -0.0198025 -0.0244223 -2.88296e-06 -0.0318533 -0.0261977 -0.00119647 -0.0209056 -0.0259996 -0.0023033 -0.0220029 -0.0263615 0.000819615 -0.0199245 -0.0263938 9.7117e-05 -0.0198025 -0.0263956 -2.88296e-06 -0.0198025 -0.0242646 -2.88296e-06 -0.0327916 -0.00395389 -2.88296e-06 -0.291587 -0.00712441 -2.88296e-06 -0.296847 -0.0196306 9.71235e-05 -0.311105 -0.0136102 -2.88296e-06 -0.304863 -0.0173289 0.00229712 -0.308906 -0.0183361 0.00205617 -0.309907 -0.014735 -2.88296e-06 -0.306076 -0.014867 0.00189712 -0.309761 -0.0140431 0.00229712 -0.308907 -0.00210501 0.00229712 -0.292366 -0.000749215 0.00229712 -0.289582 -0.000749215 0.00149712 -0.289582 -0.00800801 0.00149712 -0.300857 -0.012945 0.00149712 -0.306851 -0.00768522 0.00149712 -0.301432 -0.0156949 0.00149712 -0.310604 -0.00210501 0.00149712 -0.292366 -0.00373332 0.00149712 -0.294144 -0.000170931 0.00149712 -0.286786 0.00804982 0.00149712 -0.257206 0.00676982 0.00149712 -0.261698 0.00502884 0.00149712 -0.270481 0.00273216 0.00149712 -0.278871 0.00797729 0.00149712 -0.195254 0.00533003 0.00149712 -0.178211 0.00744458 0.00149712 -0.19596 0.00883827 0.00149712 -0.214694 0.00968187 0.00149712 -0.221086 0.00878114 0.00149712 -0.243273 0.00800424 0.00149712 -0.252602 -0.010409 0.00149712 -0.0949254 -0.0222328 0.00149712 -0.0328124 0.00425758 0.00149712 -0.167068 -0.00937251 0.00149712 -0.0998168 -0.0146915 0.00149712 -0.0739944 -0.0231892 0.00149712 -0.0307397 -0.0243805 0.00149712 -0.0235087 -0.0248972 0.00149712 -0.020306 -0.0168038 0.00146796 -0.310627 -0.013244 0.00129101 -0.306578 -0.0171086 0.00137121 -0.310699 -0.017416 0.00118412 -0.310819 -0.0132965 0.00115163 -0.306531 -0.0133146 0.000997117 -0.306514 -0.0175633 0.000997117 -0.310913 -0.024533 0.00147265 -0.0235335 -0.0233416 0.00147265 -0.0307651 -0.0208314 0.00149712 -0.0444606 -0.0209835 0.00147265 -0.0444875 -0.016237 0.00149712 -0.0692313 -0.0163887 0.00147265 -0.0692608 -0.00770618 0.00149712 -0.110432 -0.000381448 0.00149712 -0.144982 0.00270199 0.00149712 -0.16143 0.00254971 0.00147265 -0.161456 0.0072908 0.00147265 -0.195975 0.00914823 0.00149712 -0.233791 0.00862689 0.00147265 -0.243264 0.00785062 0.00147265 -0.252585 0.00258488 0.00147265 -0.278824 -0.000313323 0.00147265 -0.286726 -0.00813277 0.00147265 -0.300766 -0.0251874 0.00141395 -0.0202406 -0.0246706 0.00140163 -0.0235558 -0.023479 0.00140163 -0.0307881 -0.0211208 0.00140163 -0.0445118 -0.0165255 0.00140163 -0.0692874 -0.0078572 0.00147265 -0.110464 -0.00799344 0.00140163 -0.110494 -0.000533025 0.00147265 -0.145012 0.00517698 0.00147265 -0.178232 0.00503892 0.00140163 -0.178251 0.00715207 0.00140163 -0.195989 0.00868384 0.00147265 -0.214702 0.00899369 0.00147265 -0.233788 -0.00824532 0.00140163 -0.300684 -0.00386844 0.00147265 -0.294069 0.00474262 0.00140163 -0.270414 0.00487836 0.00147265 -0.270446 0.0064798 0.00140163 -0.26165 -0.0253169 0.00130732 -0.0201656 -0.0247798 0.00129101 -0.0235736 -0.0212297 0.00129101 -0.044531 -0.000669765 0.00140163 -0.145039 -0.000778283 0.00129101 -0.14506 0.00241235 0.00140163 -0.16148 0.00704197 0.00129101 -0.196 0.00854453 0.00140163 -0.214708 0.00885427 0.00140163 -0.233786 -0.00833463 0.00129101 -0.300619 -0.00399034 0.00140163 -0.294001 -0.000441777 0.00140163 -0.286672 0.00245203 0.00140163 -0.278782 0.00234659 0.00129101 -0.278748 0.00637064 0.00129101 -0.261632 -0.0254215 0.0011387 -0.020065 -0.0248499 0.00115163 -0.0235849 -0.0235881 0.00129101 -0.0308064 -0.0212997 0.00115163 -0.0445433 -0.0166341 0.00129101 -0.0693085 -0.0166057 0.00128972 -0.0694595 -0.00810156 0.00129101 -0.110517 -0.00817098 0.00115163 -0.110532 0.00230333 0.00129101 -0.161499 0.00492935 0.00129101 -0.178266 0.00697128 0.00115163 -0.196007 0.00843397 0.00129101 -0.214714 0.00874364 0.00129101 -0.233784 -0.00414919 0.00115163 -0.293913 -0.00408708 0.00129101 -0.293948 -0.000543718 0.00129101 -0.286629 0.0046349 0.00129101 -0.270389 0.00760206 0.00129101 -0.252558 0.00721999 0.000997117 -0.198875 0.004859 0.00115163 -0.178276 -0.000871962 0.000997117 -0.145079 0.00223334 0.00115163 -0.161511 -0.000847955 0.00115163 -0.145074 -0.013147 0.000997117 -0.0871863 -0.0218212 0.000997117 -0.0417152 -0.0236582 0.00115163 -0.0308181 -0.024874 0.000997117 -0.0235889 -0.0254534 0.000997117 -0.0199953 0.00836299 0.00115163 -0.214717 0.00837732 0.00129101 -0.243249 0.00771204 0.00140163 -0.25257 0.00848775 0.00140163 -0.243255 0.00661735 0.00147265 -0.261673 0.0086726 0.00115163 -0.233783 0.00845398 0.000997117 -0.239952 0.00830643 0.00115163 -0.243244 0.00699777 0.000997117 -0.256774 0.00753145 0.00115163 -0.252551 0.00630056 0.00115163 -0.26162 0.00456574 0.00115163 -0.270373 0.0022789 0.00115163 -0.278727 -0.000609168 0.00115163 -0.286601 0.000639291 0.000997117 -0.283397 -0.00411893 0.000997117 -0.293808 -0.00841174 0.000997117 -0.300562 -0.00839198 0.00115163 -0.300577 -0.0130592 0.00147265 -0.306747 -0.0131623 0.00140163 -0.306653 -0.0254534 -0.00100288 -0.0199953 -0.0177243 -0.0004853 -0.311072 -0.0177582 9.7117e-05 -0.311106 -0.0254828 0.000290297 -0.0198113 -0.0254842 9.7117e-05 -0.0198028 -0.0213238 0.000997117 -0.0445476 -0.0218212 -0.00100288 -0.0417152 -0.0213238 -0.00100288 -0.0445476 -0.0133146 -0.00100288 -0.306514 -0.00991092 0.000997117 -0.30253 -0.000631721 -0.00100288 -0.286592 -0.000631721 0.000997117 -0.286592 0.000639291 -0.00100288 -0.283397 0.00225557 0.000997117 -0.278719 0.00434464 0.000997117 -0.271198 0.00627641 -0.00100288 -0.261616 0.00627641 0.000997117 -0.261616 0.00699777 -0.00100288 -0.256774 0.008282 -0.00100288 -0.243243 0.008282 0.000997117 -0.243243 0.00864813 0.000997117 -0.233782 0.00856721 0.000997117 -0.220613 0.00833853 -0.00100288 -0.214718 0.00721999 -0.00100288 -0.198875 0.00833853 0.000997117 -0.214718 0.00483476 -0.00100288 -0.178279 0.00483476 0.000997117 -0.178279 0.00376516 -0.00100288 -0.170989 0.00376516 0.000997117 -0.170989 -0.00211605 0.000997117 -0.138953 -0.017314 -0.00126705 -0.310773 -0.024874 -0.00100288 -0.0235889 -0.0254048 -0.00118302 -0.0200863 0.00836299 -0.00115739 -0.214717 0.004859 -0.00115739 -0.178276 -0.000847955 -0.00115739 -0.145074 -0.000871962 -0.00100288 -0.145079 -0.00211605 -0.00100288 -0.138953 -0.013147 -0.00100288 -0.0871863 -0.0166057 -0.00129548 -0.0694595 -0.0212997 -0.00115739 -0.0445433 -0.0236582 -0.00115739 -0.0308181 0.00434464 -0.00100288 -0.271198 0.00630056 -0.00115739 -0.26162 0.00753145 -0.00115739 -0.252551 0.00830643 -0.00115739 -0.243244 0.00845398 -0.00100288 -0.239952 0.00864813 -0.00100288 -0.233782 0.00856721 -0.00100288 -0.220613 0.0022789 -0.00115739 -0.278727 0.00225557 -0.00100288 -0.278719 -0.00991092 -0.00100288 -0.30253 -0.00414919 -0.00115739 -0.293913 -0.00841174 -0.00100288 -0.300562 -0.000609168 -0.00115739 -0.286601 -0.00411893 -0.00100288 -0.293808 -0.0247798 -0.00129678 -0.0235736 -0.0235881 -0.00129678 -0.0308064 -0.0212297 -0.00129678 -0.044531 -0.0166341 -0.00129678 -0.0693085 -0.00817098 -0.00115739 -0.110532 -0.00810156 -0.00129678 -0.110517 -0.000778283 -0.00129678 -0.14506 0.00223334 -0.00115739 -0.161511 0.00492935 -0.00129678 -0.178266 0.00697128 -0.00115739 -0.196007 0.00843397 -0.00129678 -0.214714 0.0086726 -0.00115739 -0.233783 0.00837732 -0.00129678 -0.243249 0.00760206 -0.00129678 -0.252558 0.00456574 -0.00115739 -0.270373 0.0046349 -0.00129678 -0.270389 0.00234659 -0.00129678 -0.278748 -0.000543718 -0.00129678 -0.286629 -0.00839198 -0.00115739 -0.300577 -0.0132965 -0.00115739 -0.306531 -0.013244 -0.00129678 -0.306578 -0.0246706 -0.00140739 -0.0235558 -0.0211208 -0.00140739 -0.0445118 -0.00799344 -0.00140739 -0.110494 0.00230333 -0.00129678 -0.161499 0.00241235 -0.00140739 -0.16148 0.00704197 -0.00129678 -0.196 0.00715207 -0.00140739 -0.195989 0.00874364 -0.00129678 -0.233784 0.00885427 -0.00140739 -0.233786 0.00771204 -0.00140739 -0.25257 0.00637064 -0.00129678 -0.261632 0.00245203 -0.00140739 -0.278782 -0.00408708 -0.00129678 -0.293948 -0.000441777 -0.00140739 -0.286672 -0.00399034 -0.00140739 -0.294001 -0.00833463 -0.00129678 -0.300619 -0.0168728 -0.00145757 -0.310639 -0.0248499 -0.00115739 -0.0235849 -0.023479 -0.00140739 -0.0307881 -0.0233416 -0.00147841 -0.0307651 -0.0209835 -0.00147841 -0.0444875 -0.0165255 -0.00140739 -0.0692874 -0.0163887 -0.00147841 -0.0692608 -0.000669765 -0.00140739 -0.145039 -0.000533025 -0.00147841 -0.145012 0.00503892 -0.00140739 -0.178251 0.00854453 -0.00140739 -0.214708 0.00868384 -0.00147841 -0.214702 0.00899369 -0.00147841 -0.233788 0.00862689 -0.00147841 -0.243264 0.00848775 -0.00140739 -0.243255 0.0064798 -0.00140739 -0.26165 0.00474262 -0.00140739 -0.270414 -0.00386844 -0.00147841 -0.294069 -0.00824532 -0.00140739 -0.300684 -0.0131623 -0.00140739 -0.306653 -0.0130592 -0.00147841 -0.306747 -0.00800801 -0.00150288 -0.300857 -0.00813277 -0.00147841 -0.300766 -0.000313323 -0.00147841 -0.286726 -0.000170931 -0.00150288 -0.286786 0.00258488 -0.00147841 -0.278824 0.00502884 -0.00150288 -0.270481 0.00487836 -0.00147841 -0.270446 0.00661735 -0.00147841 -0.261673 0.00785062 -0.00147841 -0.252585 0.00800424 -0.00150288 -0.252602 0.00878114 -0.00150288 -0.243273 0.00883827 -0.00150288 -0.214694 0.0072908 -0.00147841 -0.195975 0.00744458 -0.00150288 -0.19596 0.00533003 -0.00150288 -0.178211 0.00517698 -0.00147841 -0.178232 0.00254971 -0.00147841 -0.161456 -0.0078572 -0.00147841 -0.110464 -0.0231892 -0.00150288 -0.0307397 -0.024533 -0.00147841 -0.0235335 -0.0248972 -0.00150288 -0.020306 -0.0156949 -0.00150288 -0.310604 -0.012945 -0.00150288 -0.306851 -0.00768522 -0.00150288 -0.301432 -0.00210501 -0.00150288 -0.292366 -0.00373332 -0.00150288 -0.294144 0.00132086 -0.00150288 -0.284698 0.00914823 -0.00150288 -0.233791 0.00273216 -0.00150288 -0.278871 0.00538603 -0.00150288 -0.271572 0.00676982 -0.00150288 -0.261698 0.00953484 -0.00150288 -0.2404 -0.0191814 -0.00150288 -0.050283 -0.0208314 -0.00150288 -0.0444606 -0.0146915 -0.00150288 -0.0739944 -0.016237 -0.00150288 -0.0692313 -0.0243805 -0.00150288 -0.0235087 0.00270199 -0.00150288 -0.16143 0.00425758 -0.00150288 -0.167068 -0.000381448 -0.00150288 -0.144982 -0.00770618 -0.00150288 -0.110432 -0.00937251 -0.00150288 -0.0998168 -0.010409 -0.00150288 -0.0949254 -0.0240894 -0.00225584 -0.0215508 -0.0222328 -0.00150288 -0.0328124 -0.02417 -0.00190288 -0.0210503 -0.0241998 -0.0019856 -0.0208651 -0.0240164 -0.00230288 -0.0220034 -0.0107436 0.00229712 -0.301768 -0.00768522 0.00229712 -0.301432 -0.0159305 0.00229712 -0.307474 -0.00994208 0.00229712 -0.300796 -0.00654489 0.00229712 -0.296186 -0.00386908 0.00229715 -0.2916 0.00161713 0.00229712 -0.277817 0.00377579 0.00229712 -0.269766 0.00552385 0.00229712 -0.260803 0.00685066 0.00229712 -0.250556 0.00953484 0.00229712 -0.2404 0.00737819 0.00229712 -0.244161 -0.0146915 0.00229712 -0.0739944 0.00968187 0.00229712 -0.221086 0.00844683 0.00229712 -0.200232 -0.0242142 0.00229716 -0.0328382 -0.0191814 0.00229712 -0.050283 -0.0206022 0.00229712 -0.0534068 0.00301804 0.00229712 -0.171635 -0.00209086 0.00229712 -0.133685 -0.00937251 0.00229712 -0.0998168 -0.010409 0.00229712 -0.0949254 0.00132086 -0.00230288 -0.284698 0.00538603 -0.00230288 -0.271572 0.00379829 -0.00230288 -0.269668 -0.0140431 -0.00230288 -0.308907 -0.0159305 -0.00230288 -0.307474 -0.000772154 -0.00230288 -0.28466 -0.000749215 -0.00230288 -0.289582 -0.00386909 -0.00230292 -0.2916 -0.00768522 -0.00230288 -0.301432 -0.00994208 -0.00230288 -0.300796 0.00844683 -0.00230288 -0.200232 0.00797729 -0.00230288 -0.195254 -0.00937251 -0.00230288 -0.0998168 -0.0146915 -0.00230288 -0.0739944 -0.0191814 -0.00230288 -0.050283 -0.0187623 -0.00230288 -0.063283 -0.0200627 -0.00230288 -0.0453613 -0.0242142 -0.00230293 -0.0328382 -0.0222328 -0.00230288 -0.0328124 -0.0242895 0.00149712 -0.0203062 -0.0250514 0.0014743 -0.0202874 -0.0261982 0.00195121 -0.0208183 -0.0260836 0.00223871 -0.021499 -0.0242403 0.00180206 -0.0206129 -0.0259996 0.00229754 -0.0220029 -0.0262616 0.00166051 -0.0204547 -0.0262939 0.00145989 -0.0202754 -0.0262336 -0.00180936 -0.020614 -0.025122 -0.00145397 -0.0202667 -0.0242895 -0.00150288 -0.0203062 -0.0242656 -0.00166627 -0.0204554 -0.0261222 -0.0021762 -0.0212668 -0.0254842 -0.000102883 -0.0198028 -0.0254648 -0.000823446 -0.0199242 -0.0263783 -0.000554316 -0.0198493 -0.0252976 -0.00133335 -0.0201792 -0.0190058 0.00156047 -0.310548 -0.016542 0.00149712 -0.310603 -0.0155491 0.00165864 -0.310456 -0.0151206 0.00199409 -0.310021 -0.014233 0.00228814 -0.309106 -0.0193899 0.00101704 -0.310904 -0.019582 0.000481186 -0.311071 -0.0176863 0.000651376 -0.311035 -0.0188144 -0.00174718 -0.310367 -0.0172646 -0.00129792 -0.310753 -0.016542 -0.00150288 -0.310603 -0.0195293 -0.000683532 -0.311027 -0.0175633 -0.00100288 -0.310913 -0.0174926 -0.0011125 -0.31086 0.00797729 -0.00150288 -0.195254 0.00844683 -0.00150288 -0.200232 -0.010409 -0.00230288 -0.0949254 -0.0200627 -0.00150288 -0.0453613 0.00132086 0.00149712 -0.284698 0.00797729 0.00229712 -0.195254 0.00844683 0.00149712 -0.200232 -0.0191814 0.00149712 -0.050283 + + + + + + + + + + -0.617237 0.000215055 -0.786777 -0.604665 -0.0040976 -0.796469 -0.617237 0 -0.786777 -0.61908 -0.01405 -0.785202 -0.615946 -2.92351e-05 -0.787789 -0.615971 -4.14998e-05 -0.787769 -0.61586 -8.90293e-05 -0.787856 -0.616044 -0.000288729 -0.787712 -0.615873 7.39017e-05 -0.787846 -0.615996 -2.9137e-05 -0.78775 -0.616046 -7.50763e-05 -0.78771 -0.616602 -0.000464637 -0.787275 -0.615784 0.000114613 -0.787915 -0.615218 0.000412331 -0.788357 -0.615209 0.00038213 -0.788364 -0.615988 -2.01969e-05 -0.787756 -0.615491 0.000666246 -0.788144 -0.614579 0.00242037 -0.788851 -0.615947 1.46499e-05 -0.787788 -0.615878 0.000179422 -0.787841 -0.615759 0.000589013 -0.787935 -0.615763 0.000590524 -0.787931 -0.616109 -0.000468513 -0.787661 -0.61634 -0.000882526 -0.78748 -0.615764 -9.07187e-05 -0.787931 -0.616094 0.000103854 -0.787673 -0.616602 0.000464637 -0.787275 -0.616046 7.49618e-05 -0.78771 -0.615996 2.91393e-05 -0.78775 -0.615872 -7.37583e-05 -0.787846 -0.616003 -6.49965e-07 -0.787744 -0.620862 0.00180673 -0.783918 -0.616013 4.00234e-05 -0.787736 -0.615209 -0.00038213 -0.788364 -0.615218 -0.000412331 -0.788357 -0.617237 0 -0.786777 -0.617237 -5.90277e-05 -0.786777 -0.734588 -0.00901598 -0.678454 -0.615429 3.20713e-05 -0.788193 -0.613705 0.000482711 -0.789535 -0.615953 1.91286e-05 -0.787783 -0.620864 -0.00180661 -0.783916 -0.616542 -0.000231939 -0.787322 -0.616265 -0.000171924 -0.787539 -0.615919 -3.93962e-05 -0.78781 -0.616019 5.20705e-05 -0.787732 -0.615922 -1.60043e-05 -0.787808 -0.61658 0.000337827 -0.787292 -0.61659 0.000310022 -0.787285 -0.615899 -5.38721e-05 -0.787825 -0.616015 5.01792e-05 -0.787735 -0.615978 -0.000277775 -0.787764 -0.615947 0 -0.787787 -0.615954 0 -0.787782 -0.615649 -5.12432e-05 -0.788021 -0.615755 -3.2748e-05 -0.787938 -0.615755 0 -0.787938 -0.615755 0 -0.787938 -0.615755 0 -0.787938 -0.615755 2.57077e-05 -0.787938 -0.614558 0.000115093 -0.788872 -0.615509 5.49962e-05 -0.78813 -0.554788 0.0128056 -0.831893 -0.615954 0 -0.787782 -0.615958 0 -0.787779 -0.613744 -0.0394042 -0.788521 -0.615978 0.000601721 -0.787763 -0.616276 0.00244419 -0.787527 -0.615955 -7.78277e-05 -0.787782 -0.61481 -0.00501705 -0.788659 -0.615874 -0.000334731 -0.787845 -0.615896 -0.000171653 -0.787828 -0.615972 4.10719e-05 -0.787768 -0.615975 3.72035e-05 -0.787766 -0.616045 0.000133815 -0.787711 -0.616186 0.000405845 -0.787601 -0.61594 -2.65527e-05 -0.787793 -0.615754 -0.000461277 -0.787938 -0.615957 6.61894e-06 -0.78778 -0.615735 -0.000671135 -0.787953 -0.615733 -0.000669964 -0.787954 -0.615148 0.000200011 -0.788412 -0.614256 0.000633065 -0.789106 -0.616589 -0.000238874 -0.787285 -0.616111 -7.87558e-05 -0.78766 -0.616403 -0.000251533 -0.787431 -0.616583 -0.000330969 -0.78729 -0.61659 -0.000310022 -0.787285 -0.615466 0.000281787 -0.788163 -0.614118 0.00127927 -0.789214 -0.6159 4.77932e-05 -0.787824 -0.603854 0.0107793 -0.797022 -0.615809 0.000150262 -0.787895 -0.61636 -0.000485823 -0.787464 -0.615972 4.10719e-05 -0.787768 -0.615988 2.01969e-05 -0.787756 -0.615491 -0.000667119 -0.788144 -0.614579 -0.00242103 -0.788851 -0.615947 -1.46499e-05 -0.787788 -0.615879 -0.000179464 -0.787841 -0.615961 1.57205e-05 -0.787776 -0.615763 -0.000590524 -0.787931 -0.615759 -0.00058839 -0.787934 -0.617302 -0.0104642 -0.786657 -0.615971 -4.32109e-05 -0.787769 -0.615991 -1.67643e-05 -0.787753 -0.621485 -0.00790953 -0.783386 -0.616257 -0.000533577 -0.787545 -0.616337 -0.000669089 -0.787483 -0.615951 1.37527e-05 -0.787785 -0.616186 -0.000530317 -0.787601 -0.61608 -0.000303558 -0.787683 -0.616084 -0.000315941 -0.787681 -0.615711 0.000658427 -0.787972 -0.615733 0.000669964 -0.787954 -0.616099 -0.000453144 -0.787669 -0.616505 -0.00242493 -0.787347 -0.615966 -8.98039e-05 -0.787773 -0.615966 -9.07765e-05 -0.787773 -0.61596 -0.00010426 -0.787777 -0.615953 0 -0.787783 -0.615954 0 -0.787782 -0.615954 0 -0.787782 -0.615958 0 -0.787779 -0.613744 -0.0394042 -0.788521 -0.615979 0.00062608 -0.787762 -0.616287 0.00252765 -0.787518 -0.616029 0.000501262 -0.787724 -0.61908 0.01405 -0.785202 -0.616419 0.00195451 -0.787416 -0.616302 0.00108067 -0.787509 -0.531678 0.172071 -0.829283 -0.502584 0.146909 -0.851955 -0.476042 0.108596 -0.872692 -0.450349 0.00638252 -0.89283 0.300795 0.822595 -0.482556 0.467742 0.637034 -0.612703 -0.0182816 0.972715 -0.231283 -0.0183114 0.972704 -0.231327 -0.254448 0.826531 -0.502099 0.176579 0.906414 -0.383711 0.176623 0.90643 -0.383653 -0.0888352 0.770219 -0.631562 -0.0888512 0.770205 -0.631577 -0.342283 0.516353 -0.784998 -0.342319 0.516298 -0.785018 -0.187825 0.891915 -0.411352 -0.291121 0.789039 -0.540986 -0.453327 0.55406 -0.698221 -0.428991 0.607163 -0.66882 -0.50578 0.441352 -0.741212 -0.477584 0.016198 -0.878437 0.647089 0.12806 -0.751582 0.647104 0.128062 -0.75157 0.310994 0.108821 -0.944161 0.310949 0.108813 -0.944177 -0.074349 0.0729386 -0.994561 -0.0743843 0.0729315 -0.994559 -0.497486 0.0187286 -0.86727 -0.485317 0.0583233 -0.872391 -0.456858 0.0566882 -0.887731 -0.452924 0.0381813 -0.890731 0.594883 0.375453 -0.710738 0.594836 0.375442 -0.710784 0.266577 0.319022 -0.909484 0.266605 0.319032 -0.909473 -0.104125 0.213834 -0.971305 -0.103977 0.213898 -0.971307 -0.505128 0.0549296 -0.861295 -0.465974 0.0864578 -0.880564 -0.48834 0.128826 -0.863092 -0.519877 0.0873703 -0.849761 -0.16142 0.340262 -0.926372 -0.161446 0.340244 -0.926374 0.18088 0.507509 -0.842447 0.180878 0.507508 -0.842448 0.707475 0.602365 -0.369642 0.527974 0.534195 -0.660212 -0.518561 0.16247 -0.839463 -0.540784 0.113813 -0.833426 -0.242739 0.443403 -0.862827 -0.242706 0.443438 -0.862819 0.0596465 0.661404 -0.747654 0.0596429 0.661401 -0.747657 0.563599 0.785016 -0.257112 0.382006 0.745874 -0.545659 -0.553643 0.150739 -0.818998 -0.56632 0.132564 -0.813455 -0.554557 0.185176 -0.811281 -0.583678 0.19508 -0.788203 -0.583688 0.195017 -0.788211 -0.60412 0.195082 -0.772646 -0.60412 0.195082 -0.772646 -0.552399 0.442398 -0.706498 -0.552484 0.442119 -0.706607 -0.488691 0.608714 -0.625018 -0.488642 0.608819 -0.624954 -0.374931 0.793401 -0.479523 -0.374986 0.793332 -0.479594 -0.272476 0.896835 -0.348487 -0.272386 0.896908 -0.348371 -0.120165 0.980786 -0.153686 -0.120179 0.980781 -0.153705 -0.719878 0.128943 -0.682018 -0.68965 0.162598 -0.705652 -0.609142 0.195078 -0.768694 -0.768033 0.534203 0.353202 -0.62166 0.745883 0.23916 -0.220059 0.97271 -0.0735434 -0.220059 0.972711 -0.0735419 -0.362961 0.890656 -0.273845 -0.422631 0.827193 -0.370318 -0.454745 0.789102 -0.412947 -0.550055 0.606772 -0.573817 -0.56504 0.554976 -0.610517 -0.597269 0.441645 -0.669492 -0.624332 0.142263 -0.768095 -0.620216 0.164773 -0.76693 -0.653389 0.154948 -0.740995 -0.648747 0.186828 -0.737714 -0.634127 0.191776 -0.749069 -0.414957 0.90642 0.0788296 -0.414952 0.906421 0.0788398 -0.591506 0.770195 -0.238579 -0.591499 0.770207 -0.238559 -0.679265 0.516345 -0.521523 -0.679267 0.516308 -0.521558 -0.652851 0.132637 -0.745784 -0.672199 0.17539 -0.719296 -0.540839 0.822601 0.17556 -0.385434 0.785012 0.484971 -0.739975 0.661391 -0.12247 -0.739975 0.661391 -0.122469 -0.778801 0.443364 -0.443731 -0.778799 0.443354 -0.443745 -0.67843 0.113912 -0.725781 -0.705635 0.147025 -0.693155 -0.707402 0.637043 0.306201 -0.529345 0.60236 0.597457 -0.861205 0.507503 -0.0276833 -0.861206 0.507502 -0.0276859 -0.860064 0.340202 -0.380201 -0.860066 0.340206 -0.380193 -0.699282 0.0873776 -0.709485 -0.726196 0.0682697 -0.68409 -0.739723 0.0920249 -0.666589 -0.732129 0.108617 -0.67245 -0.833236 0.375453 0.405897 -0.833247 0.375453 0.405874 -0.946928 0.319029 0.0393377 -0.946927 0.31903 0.0393477 -0.917531 0.213864 -0.335259 -0.917546 0.213876 -0.33521 -0.714045 0.0549213 -0.697942 -0.749906 0.0628335 -0.658554 -0.88547 0.12806 0.446703 -0.885444 0.128056 0.446756 -0.9913 0.108815 0.0740461 -0.991302 0.108815 0.0740287 -0.947293 0.072951 -0.311953 -0.947291 0.0729509 -0.311958 -0.757559 0.025679 -0.652261 -0.757578 0.0256801 -0.652239 -0.757828 0 -0.652454 -0.798872 0.00115983 -0.6015 -0.949822 -0.0007762 -0.312792 -0.968247 0 -0.249995 -0.997223 0 0.0744709 -0.999958 -0.00115994 0.00909131 -0.892793 0.00153985 0.450464 -0.92036 0 0.391071 -0.998015 -0.0623162 0.00907364 -0.917712 -0.0758051 0.389946 -0.967138 -0.0478585 -0.249709 -0.793642 -0.0605837 -0.605362 -0.766142 -0.0590274 -0.639955 -0.795052 -0.0505313 -0.604432 -0.798691 -0.0203685 -0.601396 -0.771337 -0.0255693 -0.635913 -0.798831 -0.0101572 -0.601469 -0.756785 -0.0910428 -0.647292 -0.778096 -0.090057 -0.621656 -0.7876 -0.0848016 -0.610324 -0.78378 -0.0993338 -0.613043 -0.769207 -0.13564 -0.624437 -0.769197 -0.135623 -0.624454 -0.68397 -0.232947 -0.691318 -0.701696 -0.22135 -0.67722 -0.701693 -0.221325 -0.677231 -0.721245 -0.203428 -0.662135 -0.719401 -0.179689 -0.67095 -0.733465 -0.190214 -0.65257 -0.750352 -0.168602 -0.639176 -0.727002 -0.14762 -0.67058 -0.755176 -0.16035 -0.635608 -0.917715 -0.0758035 0.389939 -0.899032 -0.225539 0.375332 -0.899026 -0.225542 0.375343 -0.862121 -0.369721 0.346487 -0.862124 -0.369719 0.346481 -0.807906 -0.504795 0.304089 -0.807897 -0.5048 0.304103 -0.7377 -0.627449 0.249213 -0.7377 -0.627449 0.249213 -0.653252 -0.734648 0.18318 -0.653251 -0.734648 0.18318 -0.55663 -0.823759 0.107632 -0.556627 -0.82376 0.107635 -0.45022 -0.892584 0.0244255 -0.450219 -0.892584 0.0244262 -0.99188 -0.0423472 -0.119923 -0.977363 -0.165325 -0.132016 -0.977364 -0.165328 -0.132011 -0.950311 -0.271019 -0.153161 -0.950311 -0.271015 -0.153169 -0.910565 -0.370033 -0.184245 -0.910565 -0.370034 -0.184244 -0.859106 -0.459942 -0.224479 -0.859107 -0.459934 -0.22449 -0.797202 -0.538514 -0.272894 -0.797201 -0.538518 -0.272889 -0.726381 -0.603834 -0.328262 -0.72638 -0.603835 -0.328261 -0.648372 -0.654291 -0.389253 -0.648365 -0.654303 -0.389242 -0.634633 -0.213295 -0.742796 -0.650311 -0.249252 -0.717613 -0.673083 -0.239781 -0.699618 -0.660532 -0.20411 -0.722521 -0.674855 -0.226419 -0.702357 -0.218674 -0.963148 -0.156616 -0.218681 -0.963145 -0.156622 -0.478629 -0.706041 -0.521938 -0.40323 -0.792877 -0.456892 -0.525831 -0.608019 -0.594824 -0.336637 -0.939431 -0.0643847 -0.336636 -0.939431 -0.0643837 -0.565108 -0.688644 -0.454337 -0.565103 -0.688653 -0.454331 -0.642578 -0.252391 -0.723459 -0.610889 -0.258762 -0.748236 -0.610882 -0.25879 -0.748232 -0.594962 -0.258841 -0.760934 -0.603703 -0.195082 -0.772972 -0.489005 -0.608714 -0.624773 -0.512148 -0.555568 -0.655018 -0.374933 -0.793399 -0.479525 -0.34241 -0.831476 -0.437497 -0.159112 -0.965923 -0.204145 -0.120179 -0.980781 -0.153704 -0.48834 -0.128826 -0.863092 -0.518561 -0.16247 -0.839463 -0.599081 -0.195078 -0.776561 0.527974 -0.534195 -0.660212 0.382004 -0.745873 -0.545662 -0.594673 -0.164614 -0.786934 -0.0183154 -0.972704 -0.231324 -0.0182778 -0.972714 -0.231286 -0.25444 -0.826539 -0.50209 -0.254449 -0.826531 -0.502098 -0.453313 -0.554087 -0.698208 -0.45333 -0.55406 -0.698219 -0.594809 -0.142336 -0.791165 -0.56151 -0.155027 -0.812818 -0.559449 -0.186839 -0.807532 -0.574005 -0.19179 -0.796074 0.176628 -0.906427 -0.383657 0.176574 -0.906416 -0.383707 -0.088853 -0.770206 -0.631576 -0.0888333 -0.770218 -0.631564 -0.342324 -0.5163 -0.785015 -0.342279 -0.51635 -0.785002 -0.56632 -0.132564 -0.813455 -0.535998 -0.175251 -0.825829 0.300795 -0.822595 -0.482556 0.563599 -0.785016 -0.257112 0.0596468 -0.661404 -0.747655 0.0596425 -0.661402 -0.747657 -0.242742 -0.443406 -0.862825 -0.242704 -0.443435 -0.862821 -0.540784 -0.113813 -0.833426 -0.502584 -0.146909 -0.851955 0.46774 -0.637034 -0.612705 0.707475 -0.602365 -0.369642 0.18088 -0.507509 -0.842447 0.180878 -0.507508 -0.842448 -0.161418 -0.34026 -0.926373 -0.161445 -0.340247 -0.926373 -0.519878 -0.0873702 -0.849761 -0.488669 -0.0683468 -0.869788 -0.468516 -0.0919902 -0.878652 -0.476043 -0.108596 -0.872692 0.594834 -0.375448 -0.710783 0.594884 -0.375447 -0.710741 0.266605 -0.319029 -0.909474 0.266577 -0.319025 -0.909483 -0.10397 -0.213886 -0.97131 -0.104128 -0.213848 -0.971301 -0.505128 -0.0549296 -0.861295 -0.458134 -0.0628612 -0.886657 0.647104 -0.12806 -0.75157 0.647089 -0.128061 -0.751582 0.310948 -0.108818 -0.944177 0.310994 -0.108817 -0.944162 -0.0743849 -0.0729347 -0.994559 -0.0743491 -0.0729354 -0.994562 -0.450176 -0.0256868 -0.89257 -0.450209 -0.0256853 -0.892554 -0.450358 0 -0.892848 -0.450358 0 -0.892848 -0.0745476 0 -0.997217 -0.0745476 0 -0.997217 0.312852 0 -0.949802 0.312852 0 -0.949802 0.652461 0 -0.757822 0.652461 0 -0.757822 0.778083 0.156431 -0.608372 0.102826 0.991445 -0.0803972 0.116213 0.987624 -0.105322 0.307078 0.92384 -0.228522 0.346358 0.890857 -0.293955 0.429054 0.838673 -0.335471 0.511624 0.760405 -0.400031 0.544291 0.70696 -0.451613 0.599037 0.649446 -0.468374 0.660691 0.544639 -0.516581 0.690574 0.453913 -0.56309 0.733404 0.382668 -0.561857 0.772564 0.130514 -0.621378 0 1 0 0 1 0 -0.123236 0.987688 0.0963565 -0.781042 0.130527 0.610685 -0.785048 0.156428 0.599358 -0.722168 0.382668 0.576227 -0.713034 0.453913 0.534365 -0.660689 0.54464 0.516583 -0.599036 0.649446 0.468377 -0.569564 0.70696 0.41929 -0.511625 0.760405 0.400029 -0.429055 0.838673 0.335469 -0.368818 0.890858 0.265228 -0.29584 0.923841 0.24289 -0.111224 0.991352 0.0696387 -0.787782 0 0.615955 -0.787782 0 0.615955 -0.0618089 -0.996917 0.0483274 -0.135847 -0.987481 0.0801749 -0.183903 -0.97237 0.143791 -0.301469 -0.923881 0.235714 -0.370208 -0.890818 0.263417 -0.411616 -0.85264 0.321834 -0.511626 -0.760405 0.400029 -0.569564 -0.70696 0.41929 -0.599035 -0.649446 0.468377 -0.671697 -0.522493 0.52519 -0.714408 -0.453893 0.532544 -0.785353 -0.0784647 0.614055 -0.790555 -0.156405 0.592081 -0.766015 -0.233448 0.598935 -0.727815 -0.382685 0.569067 0 -1 0 0 -1 0 0.123237 -0.987688 -0.096356 0.781042 -0.130527 -0.610685 0.771019 -0.156421 -0.617302 0.733404 -0.382668 -0.561857 0.690574 -0.453913 -0.56309 0.660691 -0.544639 -0.51658 0.599037 -0.649446 -0.468374 0.544291 -0.70696 -0.451613 0.511624 -0.760405 -0.400031 0.429054 -0.838673 -0.335471 0.346358 -0.890857 -0.293955 0.307078 -0.92384 -0.228522 0.0944088 -0.991353 -0.0911422 0.787782 0 -0.615955 0.787782 0 -0.615955 -0.995082 0 0.099055 -0.995082 0 0.099055 -0.919491 0 -0.393112 -0.919491 0 -0.393112 -0.61597 0 -0.787769 -0.61597 0 -0.787769 -0.159724 0 -0.987162 -0.159724 0 -0.987162 0.3362 0 -0.941791 0.3362 0 -0.941791 -0.990603 0.094772 0.0986092 -0.918137 0.0542539 -0.392533 -0.61597 -1.42622e-06 -0.787769 -0.159488 -0.0542546 -0.985708 0.334687 -0.094769 -0.937552 0.334641 -0.0947733 -0.937568 0.301415 -0.279565 -0.911588 0.301415 -0.279566 -0.911588 0.236628 -0.450339 -0.860931 0.236623 -0.450338 -0.860933 0.143529 -0.598522 -0.788144 0.143524 -0.59852 -0.788146 0.0267802 -0.716701 -0.696866 0.0267504 -0.716688 -0.696881 -0.107772 -0.798927 -0.591694 -0.107748 -0.79894 -0.591679 -0.253325 -0.841119 -0.477854 -0.253338 -0.84111 -0.477865 -0.159508 -0.0542557 -0.985705 -0.178527 -0.160035 -0.970833 -0.178505 -0.160039 -0.970837 -0.215595 -0.257805 -0.941836 -0.215505 -0.257836 -0.941848 -0.268815 -0.342687 -0.900169 -0.268899 -0.342638 -0.900162 -0.335725 -0.410288 -0.84791 -0.335701 -0.41031 -0.84791 -0.412716 -0.457389 -0.787693 -0.41271 -0.457396 -0.787692 -0.496061 -0.481544 -0.722523 -0.496068 -0.481531 -0.722526 -0.615947 -9.80651e-08 -0.787787 -0.615948 -1.65241e-06 -0.787787 -0.615937 -4.13314e-06 -0.787796 -0.615937 -3.39717e-06 -0.787796 -0.615999 3.0461e-05 -0.787747 -0.615994 3.88808e-05 -0.787751 -0.615936 -1.45427e-05 -0.787796 -0.615943 -2.21001e-05 -0.787791 -0.615938 -2.98506e-05 -0.787795 -0.61594 -3.12393e-05 -0.787793 -0.615953 -3.06154e-07 -0.787783 -0.615959 -2.11396e-06 -0.787778 -0.61596 0 -0.787778 -0.91814 0.0542534 -0.392525 -0.899118 0.160043 -0.407398 -0.899128 0.160046 -0.407374 -0.862039 0.257813 -0.436374 -0.862023 0.257799 -0.436413 -0.808728 0.342628 -0.478085 -0.808742 0.342653 -0.478043 -0.741904 0.410316 -0.530302 -0.7419 0.4103 -0.530319 -0.664886 0.457378 -0.590535 -0.664889 0.457414 -0.590504 -0.581542 0.481566 -0.65567 -0.581546 0.48153 -0.655693 -0.990602 0.094771 0.0986184 -0.957376 0.279563 0.0726387 -0.957376 0.279563 0.0726361 -0.892589 0.450335 0.0219803 -0.892589 0.450335 0.0219813 -0.79949 0.598526 -0.0508112 -0.799491 0.598525 -0.0508154 -0.682748 0.716704 -0.142094 -0.682745 0.716709 -0.142083 -0.548213 0.798951 -0.247265 -0.548222 0.798936 -0.247295 -0.402654 0.841107 -0.361122 -0.40265 0.841113 -0.361112 -0.329475 0.844915 -0.421385 -0.329456 0.844934 -0.421362 -0.539599 0.482241 -0.690128 -0.5396 0.48224 -0.690128 -0.615954 0 -0.787782 -0.615954 0 -0.787782 -0.539599 -0.482242 -0.690127 -0.539599 -0.482241 -0.690128 -0.329475 -0.844914 -0.421387 -0.329457 -0.844933 -0.421363 -0.253311 0.841132 -0.477839 -0.496061 0.48153 -0.722533 -0.615951 0 -0.787784 -0.581549 -0.481531 -0.65569 -0.402635 -0.841128 -0.361093 -0.402642 -0.841122 -0.3611 -0.548214 -0.798945 -0.24728 -0.548218 -0.798941 -0.247286 -0.682751 -0.716701 -0.142094 -0.682748 -0.716705 -0.142089 -0.79949 -0.598527 -0.0508119 -0.79949 -0.598526 -0.0508129 -0.892589 -0.450335 0.0219799 -0.892589 -0.450335 0.0219801 -0.957376 -0.279563 0.0726362 -0.957376 -0.279562 0.0726341 -0.990603 -0.094771 0.0986132 -0.990603 -0.0947702 0.0986092 -0.581535 -0.481566 -0.655676 -0.664881 -0.457416 -0.590512 -0.664889 -0.457378 -0.590532 -0.741905 -0.410298 -0.530313 -0.741905 -0.410314 -0.530302 -0.808737 -0.342658 -0.478047 -0.808737 -0.342652 -0.478053 -0.862036 -0.257811 -0.436379 -0.862037 -0.257812 -0.436378 -0.899126 -0.160046 -0.407378 -0.899131 -0.160052 -0.407367 -0.918152 -0.0542617 -0.392495 -0.918137 -0.0542511 -0.392533 -0.615951 -3.67387e-06 -0.787784 -0.615958 -1.75395e-06 -0.787779 -0.615961 -2.69414e-05 -0.787776 -0.615966 -2.40565e-05 -0.787773 -0.615969 -3.35234e-05 -0.78777 -0.615974 -2.86904e-05 -0.787767 -0.615952 8.72538e-06 -0.787783 -0.61595 5.42801e-06 -0.787785 -0.615943 1.33944e-05 -0.787791 -0.61594 5.02192e-06 -0.787793 -0.61595 -1.56905e-06 -0.787786 -0.615951 4.25566e-06 -0.787785 -0.61597 -2.67881e-06 -0.787769 -0.496057 0.481545 -0.722525 -0.412714 0.457399 -0.787689 -0.412718 0.457389 -0.787692 -0.3357 0.410308 -0.847911 -0.335677 0.410342 -0.847903 -0.268836 0.342683 -0.900164 -0.268877 0.34264 -0.900168 -0.215584 0.257811 -0.941837 -0.215593 0.257805 -0.941837 -0.178503 0.160036 -0.970837 -0.178524 0.160026 -0.970835 -0.159506 0.0542507 -0.985705 -0.159488 0.0542555 -0.985708 -0.253322 0.841118 -0.477858 -0.10775 0.798941 -0.591678 -0.107738 0.798954 -0.591663 0.0267961 0.716716 -0.69685 0.0267796 0.716702 -0.696866 0.143523 0.598521 -0.788146 0.143528 0.598525 -0.788142 0.236624 0.450338 -0.860933 0.236629 0.45034 -0.86093 0.30142 0.279557 -0.911589 0.301418 0.279556 -0.91159 0.334643 0.0947745 -0.937567 0.334687 0.0947853 -0.93755 0.3362 0 -0.941791 0.3362 0 -0.941791 -0.159724 0 -0.987162 -0.159724 0 -0.987162 -0.61597 0 -0.787769 -0.61597 0 -0.787769 -0.919491 0 -0.393112 -0.919491 0 -0.393112 -0.995082 0 0.099055 -0.995082 0 0.099055 0.334687 -0.0947773 -0.937551 -0.159488 -0.0542525 -0.985708 -0.61597 -1.42622e-06 -0.787769 -0.918136 0.0542576 -0.392533 -0.990603 0.0947708 0.0986092 -0.990603 0.0947704 0.0986133 -0.957376 0.279562 0.0726341 -0.957376 0.279562 0.0726364 -0.892589 0.450336 0.0219801 -0.892589 0.450336 0.0219811 -0.79949 0.598527 -0.0508116 -0.79949 0.598527 -0.0508116 -0.682749 0.716704 -0.142089 -0.68275 0.716702 -0.142095 -0.548217 0.798941 -0.247287 -0.548214 0.798946 -0.247278 -0.40264 0.841124 -0.361099 -0.402635 0.841131 -0.361088 -0.918153 0.0542553 -0.392494 -0.899131 0.16005 -0.407366 -0.899126 0.160048 -0.407379 -0.862037 0.257812 -0.436378 -0.862036 0.257811 -0.43638 -0.808736 0.342653 -0.478054 -0.808738 0.342657 -0.478047 -0.741907 0.410312 -0.530301 -0.741903 0.410299 -0.530315 -0.664884 0.457381 -0.590536 -0.664885 0.457414 -0.590508 -0.58154 0.481565 -0.655672 -0.581544 0.48153 -0.655695 -0.61595 -2.52339e-07 -0.787785 -0.61595 -5.63113e-07 -0.787785 -0.615939 -3.02333e-06 -0.787794 -0.615943 -1.1687e-05 -0.787791 -0.615951 -6.965e-06 -0.787784 -0.615949 -3.08326e-06 -0.787786 -0.615979 2.41856e-05 -0.787763 -0.61597 3.24937e-05 -0.787769 -0.615965 2.47982e-05 -0.787774 -0.615964 2.52197e-05 -0.787774 -0.615955 2.44924e-06 -0.787782 -0.615952 3.48022e-06 -0.787784 -0.615951 0 -0.787785 -0.159507 -0.0542537 -0.985705 -0.178525 -0.16003 -0.970834 -0.178502 -0.160033 -0.970838 -0.215594 -0.257806 -0.941836 -0.215583 -0.25781 -0.941838 -0.268881 -0.342648 -0.900164 -0.26883 -0.342677 -0.900168 -0.335673 -0.410338 -0.847907 -0.335705 -0.410311 -0.847907 -0.41272 -0.45739 -0.787691 -0.412712 -0.457399 -0.78769 -0.496054 -0.481544 -0.722527 -0.496063 -0.481531 -0.72253 0.334642 -0.0947824 -0.937567 0.301418 -0.279556 -0.91159 0.30142 -0.279556 -0.911589 0.236629 -0.450339 -0.860931 0.236624 -0.450339 -0.860932 0.143529 -0.598524 -0.788143 0.143522 -0.598522 -0.788145 0.0267768 -0.716704 -0.696863 0.0267993 -0.716713 -0.696853 -0.107735 -0.798953 -0.591666 -0.107753 -0.798942 -0.591676 -0.253325 -0.841119 -0.477855 -0.253307 -0.841132 -0.477842 -0.329456 -0.844934 -0.421361 -0.329474 -0.844915 -0.421386 -0.539599 -0.482242 -0.690127 -0.539599 -0.482241 -0.690128 -0.615954 0 -0.787782 -0.615954 0 -0.787782 -0.539599 0.482241 -0.690128 -0.5396 0.48224 -0.690128 -0.329454 0.844935 -0.42136 -0.329473 0.844916 -0.421384 -0.402649 -0.841113 -0.361113 -0.581551 -0.481531 -0.655688 -0.61596 0 -0.787778 -0.496067 0.48153 -0.722528 -0.253333 0.841112 -0.477864 -0.253326 0.841121 -0.477851 -0.107751 0.798943 -0.591675 -0.107768 0.798925 -0.591697 0.0267541 0.716685 -0.696883 0.0267769 0.716704 -0.696863 0.143524 0.59852 -0.788147 0.143529 0.598523 -0.788143 0.236624 0.450338 -0.860932 0.236627 0.45034 -0.860931 0.301415 0.279566 -0.911588 0.301415 0.279565 -0.911588 0.334642 0.0947661 -0.937568 0.334687 0.0947762 -0.937551 -0.496063 0.481544 -0.722521 -0.412711 0.457396 -0.787692 -0.412715 0.457389 -0.787694 -0.335704 0.410312 -0.847907 -0.335722 0.410286 -0.847913 -0.26889 0.342629 -0.900169 -0.268822 0.342699 -0.900162 -0.215512 0.257848 -0.941843 -0.21559 0.257791 -0.941841 -0.178507 0.160042 -0.970836 -0.178527 0.160032 -0.970834 -0.159507 0.0542527 -0.985705 -0.159488 0.0542576 -0.985708 -0.61596 2.14307e-06 -0.787778 -0.615949 -8.7698e-07 -0.787786 -0.615944 3.36773e-05 -0.78779 -0.615939 3.05192e-05 -0.787794 -0.615942 2.1125e-05 -0.787791 -0.615945 2.35402e-05 -0.78779 -0.615987 -5.00547e-05 -0.787757 -0.615992 -4.11332e-05 -0.787752 -0.615941 1.5614e-05 -0.787792 -0.615938 6.11122e-06 -0.787795 -0.615947 -4.97502e-07 -0.787787 -0.615948 4.62489e-06 -0.787787 -0.61597 -3.21457e-06 -0.787769 -0.581536 -0.481567 -0.655674 -0.664883 -0.457416 -0.590509 -0.664892 -0.457375 -0.590531 -0.741902 -0.410298 -0.530317 -0.741901 -0.410318 -0.530304 -0.808737 -0.342659 -0.478047 -0.808732 -0.342621 -0.478082 -0.862026 -0.257793 -0.436411 -0.862036 -0.25782 -0.436375 -0.899127 -0.16005 -0.407375 -0.899119 -0.160039 -0.407397 -0.91814 -0.0542547 -0.392525 -0.918137 -0.0542525 -0.392533 -0.402656 -0.841106 -0.361121 -0.548226 -0.798934 -0.247292 -0.548208 -0.798953 -0.247268 -0.682744 -0.716709 -0.142084 -0.682749 -0.716703 -0.142093 -0.799491 -0.598524 -0.0508151 -0.79949 -0.598527 -0.0508114 -0.892589 -0.450335 0.0219812 -0.892589 -0.450335 0.0219803 -0.957376 -0.279563 0.0726362 -0.957375 -0.279564 0.0726385 -0.990602 -0.0947725 0.0986182 -0.990603 -0.0947704 0.0986092 -0.995082 0 0.099055 -0.995082 0 0.099055 -0.919491 0 -0.393112 -0.919491 0 -0.393112 -0.61597 0 -0.787769 -0.61597 0 -0.787769 -0.159724 0 -0.987162 -0.159724 0 -0.987162 0.3362 0 -0.941791 0.3362 0 -0.941791 0.763052 -0.328565 -0.556593 -0.655533 -0.413967 0.631592 0.635137 -0.618035 -0.463286 -0.522778 -0.687755 0.503683 0.498444 -0.786996 -0.363582 -0.390201 -0.840478 0.375952 0.263775 -0.9452 -0.192406 -0.171335 -0.971285 0.165077 0.074544 -0.995734 -0.0543747 0.0745436 -0.995734 -0.0543748 0.0812533 -0.995734 -0.0437181 0.0812539 -0.995734 -0.043718 0.0864499 -0.995734 -0.0322467 0.0864502 -0.995734 -0.0322466 0.0900358 -0.995734 -0.0201747 0.0900357 -0.995734 -0.0201748 0.0919442 -0.995734 -0.00772702 0.0919442 -0.995734 -0.00772702 0.0921399 -0.995734 0.00486471 0.0921399 -0.995734 0.00486467 0.0906193 -0.995734 0.0173658 0.0906193 -0.995734 0.0173658 0.0874106 -0.995734 0.0295431 0.0874108 -0.995734 0.0295435 0.0825738 -0.995734 0.0411708 0.0825737 -0.995734 0.0411706 0.0761986 -0.995734 0.052031 0.0761985 -0.995734 0.0520309 0.0684039 -0.995734 0.061922 0.0684039 -0.995734 0.0619222 0.0593353 -0.995734 0.0706597 0.0593353 -0.995734 0.0706595 0.0491608 -0.995734 0.0780811 0.0491608 -0.995734 0.0780812 0.0380714 -0.995734 0.0840478 0.0380714 -0.995734 0.0840477 0.0262722 -0.995734 0.088449 0.0262719 -0.995734 0.0884494 0.0139835 -0.995734 0.0912029 0.0139835 -0.995734 0.0912029 0.00143403 -0.995734 0.0922576 0.00143525 -0.995734 0.0922564 -0.0111402 -0.995734 0.0915924 -0.0111419 -0.995734 0.0915937 -0.0235097 -0.995734 0.0892236 -0.0235097 -0.995734 0.0892235 -0.0354405 -0.995734 0.0851911 -0.035439 -0.995734 0.0851905 -0.0467087 -0.995734 0.0795716 -0.0467099 -0.995734 0.0795719 -0.0571097 -0.995734 0.0724705 -0.0571094 -0.995734 0.0724705 -0.0664459 -0.995734 0.0640187 -0.0664456 -0.995734 0.0640187 0.192215 -0.971285 -0.140208 0.23162 -0.962 -0.144594 0.240971 -0.961833 -0.129652 0.240971 -0.961833 -0.129652 0.256381 -0.961833 -0.0956321 0.25638 -0.961834 -0.0956326 0.267014 -0.961834 -0.0598314 0.267014 -0.961833 -0.0598313 0.272675 -0.961833 -0.0229157 0.272675 -0.961833 -0.0229157 0.273255 -0.961833 0.014427 0.273256 -0.961833 0.014427 0.268746 -0.961833 0.0515011 0.268746 -0.961833 0.0515008 0.25923 -0.961833 0.0876158 0.25923 -0.961833 0.0876146 0.244885 -0.961833 0.122098 0.244885 -0.961833 0.122099 0.225979 -0.961833 0.154306 0.225979 -0.961833 0.154305 0.202862 -0.961833 0.183639 0.202862 -0.961834 0.183639 0.175967 -0.961834 0.209551 0.175967 -0.961833 0.209552 0.145794 -0.961833 0.231561 0.145794 -0.961833 0.231561 0.112907 -0.961833 0.249256 0.112906 -0.961833 0.249257 0.0779133 -0.961833 0.26231 0.0779133 -0.961833 0.26231 0.0414702 -0.961833 0.270476 0.0414719 -0.961834 0.270473 0.00425645 -0.961834 0.273601 0.00425426 -0.961833 0.273603 -0.0330428 -0.961833 0.271634 -0.0330424 -0.961833 0.271634 -0.0697213 -0.961833 0.264605 -0.0697195 -0.961834 0.264604 -0.1051 -0.961834 0.252646 -0.105101 -0.961833 0.252646 -0.138525 -0.961833 0.235982 -0.138523 -0.961834 0.235981 -0.169366 -0.961834 0.214921 -0.169369 -0.961833 0.214922 -0.182468 -0.962 0.203128 -0.235114 -0.945202 0.226528 0.360014 -0.895225 -0.262606 0.360016 -0.895225 -0.262606 0.39242 -0.895225 -0.211138 0.392419 -0.895225 -0.211139 0.417514 -0.895225 -0.155738 0.417515 -0.895225 -0.155737 0.434832 -0.895225 -0.097435 0.434832 -0.895225 -0.0974352 0.444049 -0.895225 -0.0373181 0.444049 -0.895225 -0.0373179 0.444994 -0.895225 0.0234943 0.444994 -0.895225 0.0234943 0.43765 -0.895225 0.0838685 0.43765 -0.895226 0.083868 0.422153 -0.895226 0.142679 0.422155 -0.895225 0.142682 0.398795 -0.895224 0.198838 0.398793 -0.895225 0.198835 0.368005 -0.895226 0.251284 0.368005 -0.895225 0.251284 0.330359 -0.895225 0.299055 0.330359 -0.895225 0.299056 0.286562 -0.895225 0.341254 0.286562 -0.895226 0.341253 0.237424 -0.895226 0.377095 0.237424 -0.895226 0.377095 0.183866 -0.895226 0.405911 0.183865 -0.895225 0.405913 0.126881 -0.895225 0.427169 0.126883 -0.895227 0.427165 0.0675365 -0.895227 0.440463 0.0675338 -0.895225 0.440467 0.00692802 -0.895225 0.44556 0.0069293 -0.895226 0.445559 -0.0538092 -0.895226 0.442352 -0.053807 -0.895227 0.44235 -0.113537 -0.895227 0.430904 -0.113542 -0.895225 0.430907 -0.171157 -0.895225 0.411434 -0.171158 -0.895224 0.411435 -0.225586 -0.895225 0.384297 -0.225587 -0.895224 0.384297 -0.275816 -0.895224 0.349998 -0.275814 -0.895225 0.349998 -0.320902 -0.895225 0.309183 -0.320902 -0.895225 0.309183 0.437746 -0.84049 -0.319305 0.492781 -0.798562 -0.345638 0.530429 -0.798245 -0.285394 0.530429 -0.798245 -0.285394 0.56435 -0.798245 -0.210508 0.56435 -0.798245 -0.210508 0.587759 -0.798245 -0.131702 0.587759 -0.798244 -0.131702 0.600219 -0.798244 -0.0504424 0.600218 -0.798244 -0.0504427 0.601497 -0.798244 0.0317572 0.601496 -0.798244 0.0317566 0.591569 -0.798245 0.113364 0.59157 -0.798244 0.113365 0.570623 -0.798244 0.192863 0.570623 -0.798244 0.192862 0.539047 -0.798244 0.268764 0.539047 -0.798244 0.268764 0.497431 -0.798244 0.33966 0.497431 -0.798242 0.339664 0.446547 -0.798242 0.404234 0.446547 -0.798244 0.404231 0.387345 -0.798244 0.461271 0.387345 -0.798243 0.461271 0.320926 -0.798243 0.50972 0.320926 -0.798244 0.509719 0.24853 -0.798244 0.548671 0.24853 -0.798243 0.548672 0.171508 -0.798243 0.577402 0.17151 -0.798245 0.577399 0.0912849 -0.798245 0.595376 0.0912828 -0.798243 0.595379 0.00936634 -0.798243 0.602263 0.0093657 -0.798242 0.602264 -0.0727314 -0.798242 0.597929 -0.0727314 -0.798242 0.597929 -0.153475 -0.798242 0.582456 -0.153468 -0.798247 0.582451 -0.231351 -0.798247 0.556129 -0.231351 -0.798246 0.556129 -0.304921 -0.798246 0.519448 -0.304928 -0.798243 0.51945 -0.372817 -0.798243 0.473092 -0.372812 -0.798246 0.473091 -0.425643 -0.798563 0.425588 -0.444291 -0.786999 0.428063 0.586489 -0.68776 -0.427805 0.602215 -0.674563 -0.426968 0.650337 -0.674258 -0.349911 0.650339 -0.674257 -0.34991 0.691928 -0.674257 -0.258096 0.691925 -0.674259 -0.258097 0.720625 -0.674259 -0.161474 0.720625 -0.67426 -0.161474 0.7359 -0.67426 -0.0618455 0.7359 -0.674259 -0.0618452 0.737467 -0.67426 0.0389353 0.737468 -0.674259 0.0389359 0.725298 -0.674259 0.138992 0.725297 -0.67426 0.138991 0.699615 -0.67426 0.236459 0.699615 -0.67426 0.236459 0.660901 -0.67426 0.329519 0.660902 -0.674259 0.32952 0.609876 -0.674259 0.416445 0.609876 -0.674261 0.416442 0.547489 -0.674261 0.495608 0.547489 -0.67426 0.495609 0.474905 -0.67426 0.565542 0.474905 -0.67426 0.565543 0.393472 -0.67426 0.624942 0.393472 -0.674259 0.624944 0.304711 -0.674259 0.672701 0.304713 -0.674262 0.672696 0.21028 -0.674263 0.707921 0.210277 -0.674258 0.707926 0.111918 -0.674258 0.729966 0.111921 -0.674262 0.729962 0.0114827 -0.674263 0.738402 0.0114792 -0.674259 0.738406 -0.0891725 -0.674259 0.733092 -0.0891702 -0.674261 0.73309 -0.188161 -0.674261 0.71412 -0.188164 -0.674258 0.714122 -0.283651 -0.674258 0.681849 -0.283655 -0.674255 0.681851 -0.373859 -0.674255 0.636875 -0.373847 -0.674264 0.636872 -0.457086 -0.674264 0.580034 -0.457095 -0.674258 0.580035 -0.524673 -0.674563 0.51931 -0.566136 -0.618035 0.545456 0.686341 -0.527542 -0.500635 0.686338 -0.527545 -0.500636 0.748115 -0.527544 -0.402518 0.748114 -0.527546 -0.402518 0.795956 -0.527546 -0.296901 0.795958 -0.527543 -0.2969 0.828972 -0.527543 -0.185752 0.828972 -0.527543 -0.185752 0.846544 -0.527543 -0.0711436 0.846544 -0.527543 -0.0711436 0.848347 -0.527543 0.04479 0.848346 -0.527544 0.0447896 0.834346 -0.527544 0.159888 0.834347 -0.527542 0.15989 0.804804 -0.527541 0.272012 0.804804 -0.527543 0.272011 0.760269 -0.527542 0.379064 0.760269 -0.527543 0.379064 0.701572 -0.527543 0.479056 0.701573 -0.527542 0.479057 0.629807 -0.527542 0.570126 0.629807 -0.527543 0.570125 0.546308 -0.527543 0.650573 0.546308 -0.527543 0.650573 0.452631 -0.527543 0.718905 0.452632 -0.527549 0.7189 0.350527 -0.527549 0.773837 0.350523 -0.527539 0.773845 0.241892 -0.527539 0.814365 0.241893 -0.527541 0.814364 0.128749 -0.527541 0.839717 0.128751 -0.527544 0.839715 0.013205 -0.527544 0.849425 0.0132053 -0.527544 0.849425 -0.102577 -0.527544 0.843312 -0.102581 -0.52754 0.843314 -0.216455 -0.52754 0.821492 -0.216455 -0.527539 0.821492 -0.326302 -0.527539 0.784366 -0.326294 -0.527548 0.784363 -0.430057 -0.527548 0.732628 -0.430062 -0.527543 0.732629 -0.525819 -0.527543 0.667243 -0.525818 -0.527543 0.667243 -0.611777 -0.527543 0.58943 -0.611773 -0.527547 0.58943 0.735431 -0.413966 -0.536445 0.760763 -0.363383 -0.537765 0.820523 -0.363098 -0.441478 0.820522 -0.363098 -0.441478 0.872995 -0.363098 -0.325636 0.872997 -0.363096 -0.325635 0.909206 -0.363097 -0.20373 0.909205 -0.363099 -0.203732 0.928478 -0.363098 -0.0780293 0.928477 -0.363099 -0.0780299 0.930455 -0.363098 0.0491247 0.930455 -0.363098 0.0491247 0.9151 -0.363097 0.175365 0.9151 -0.363098 0.175364 0.882697 -0.363098 0.298337 0.882697 -0.363099 0.298337 0.833852 -0.3631 0.415751 0.833852 -0.363099 0.415752 0.769474 -0.3631 0.525422 0.769474 -0.363098 0.525423 0.690763 -0.363099 0.625305 0.690763 -0.363097 0.625305 0.599184 -0.363097 0.71354 0.599183 -0.363094 0.713542 0.496444 -0.363094 0.788484 0.496445 -0.363096 0.788482 0.384448 -0.363096 0.848741 0.384449 -0.363098 0.84874 0.265305 -0.363098 0.893182 0.265303 -0.363095 0.893183 0.141213 -0.363095 0.920989 0.141212 -0.363093 0.92099 0.0144834 -0.363093 0.93164 0.0144829 -0.363093 0.931641 -0.112509 -0.363093 0.924935 -0.112501 -0.363105 0.924932 -0.237403 -0.363105 0.900996 -0.237403 -0.363105 0.900996 -0.357875 -0.363105 0.860279 -0.357885 -0.363092 0.860281 -0.471687 -0.363092 0.803539 -0.471682 -0.363098 0.803539 -0.57671 -0.363098 0.731823 -0.576711 -0.363098 0.731823 -0.661213 -0.363384 0.656315 -0.680154 -0.328565 0.655314 0.793734 -0.186482 -0.578974 0.793734 -0.186483 -0.578974 0.865176 -0.186483 -0.465504 0.865177 -0.186482 -0.465504 0.920506 -0.186482 -0.343356 0.920504 -0.186486 -0.343358 0.958685 -0.186485 -0.214819 0.958686 -0.186481 -0.214817 0.979007 -0.186482 -0.0822764 0.979007 -0.186482 -0.0822764 0.981092 -0.186483 0.0517981 0.981092 -0.186483 0.0517984 0.964901 -0.186484 0.184908 0.9649 -0.186485 0.184907 0.930735 -0.186486 0.314572 0.930735 -0.186483 0.314574 0.879232 -0.186484 0.438378 0.879232 -0.186484 0.438378 0.81135 -0.186484 0.554017 0.811349 -0.186482 0.554018 0.728355 -0.186482 0.659335 0.728356 -0.186484 0.659334 0.63179 -0.186484 0.752373 0.63179 -0.186482 0.752374 0.523462 -0.186482 0.831392 0.52346 -0.186479 0.831394 0.405371 -0.186478 0.89493 0.405376 -0.186489 0.894926 0.279741 -0.186489 0.941789 0.279736 -0.186482 0.941792 0.148897 -0.186482 0.97111 0.148897 -0.186482 0.97111 0.0152711 -0.186482 0.98234 0.0152715 -0.186483 0.98234 -0.118623 -0.186483 0.975271 -0.118626 -0.186479 0.975271 -0.250324 -0.186479 0.950033 -0.250322 -0.186483 0.950033 -0.37736 -0.186483 0.907096 -0.377356 -0.18649 0.907097 -0.497351 -0.18649 0.847268 -0.497361 -0.186474 0.847266 -0.608097 -0.186475 0.771651 -0.608094 -0.186479 0.771652 -0.707503 -0.18648 0.681664 -0.707501 -0.186483 0.681665 0.805547 -0.0763562 -0.587591 0.805546 -0.0763583 -0.587593 0.878053 -0.076358 -0.472432 0.878054 -0.0763558 -0.47243 0.934205 -0.0763561 -0.348469 0.934205 -0.076356 -0.348469 0.972954 -0.0763562 -0.218014 0.972954 -0.0763572 -0.218015 0.993578 -0.076357 -0.083501 0.993578 -0.0763568 -0.0835008 0.995694 -0.0763562 0.0525693 0.995694 -0.0763566 0.0525689 0.979262 -0.0763567 0.187659 0.979262 -0.0763561 0.18766 0.944587 -0.0763559 0.319256 0.944588 -0.076357 0.319255 0.892318 -0.0763571 0.444902 0.892318 -0.0763562 0.444903 0.823425 -0.076356 0.562264 0.823426 -0.0763574 0.562263 0.739196 -0.0763576 0.669148 0.739195 -0.0763554 0.669149 0.641193 -0.0763553 0.763572 0.641194 -0.0763563 0.763571 0.53125 -0.0763562 0.843767 0.531252 -0.076359 0.843765 0.41141 -0.0763592 0.908246 0.411408 -0.0763566 0.908247 0.2839 -0.0763566 0.955809 0.283903 -0.0763607 0.955808 0.151113 -0.0763608 0.985563 0.151113 -0.0763603 0.985563 0.0154988 -0.0763603 0.99696 0.0155005 -0.0763621 0.99696 -0.120391 -0.0763621 0.989785 -0.120399 -0.0763545 0.989785 -0.254047 -0.0763545 0.964173 -0.254051 -0.0763512 0.964173 -0.382973 -0.0763514 0.920599 -0.38297 -0.0763546 0.9206 -0.504763 -0.0763547 0.859875 -0.504761 -0.0763573 0.859876 -0.617144 -0.0763572 0.783136 -0.617144 -0.0763576 0.783136 -0.718031 -0.0763574 0.69181 -0.718032 -0.0763561 0.691809 0.807319 -0.0380806 -0.588886 0.807319 -0.03808 -0.588886 0.879987 -0.0380804 -0.47347 0.879986 -0.0380821 -0.473471 0.936261 -0.038082 -0.349235 0.936261 -0.0380815 -0.349235 0.975095 -0.0380814 -0.218494 0.975095 -0.0380816 -0.218495 0.995764 -0.0380815 -0.0836845 0.995764 -0.0380811 -0.0836841 0.997885 -0.0380816 0.0526845 0.997885 -0.0380815 0.0526846 0.981417 -0.0380821 0.188073 0.981417 -0.0380818 0.188073 0.946666 -0.038082 0.319957 0.946666 -0.0380813 0.319958 0.894281 -0.0380813 0.445882 0.894282 -0.038083 0.445881 0.825238 -0.0380834 0.5635 0.825237 -0.0380818 0.563501 0.740821 -0.0380819 0.670622 0.74082 -0.0380803 0.670623 0.642604 -0.03808 0.765251 0.642609 -0.038087 0.765247 0.532421 -0.0380875 0.845622 0.532417 -0.038082 0.845625 0.412313 -0.0380821 0.910246 0.412314 -0.0380824 0.910246 0.284528 -0.0380825 0.957911 0.284524 -0.0380774 0.957913 0.151445 -0.0380772 0.987732 0.151447 -0.0380789 0.987732 0.0155346 -0.0380789 0.999154 0.0155357 -0.03808 0.999154 -0.120664 -0.03808 0.991963 -0.120662 -0.038082 0.991963 -0.254609 -0.038082 0.966294 -0.254611 -0.0380807 0.966294 -0.383813 -0.0380807 0.922625 -0.383812 -0.0380811 0.922626 -0.505872 -0.0380811 0.861768 -0.50587 -0.038083 0.861769 -0.618502 -0.0380829 0.78486 -0.618502 -0.0380828 0.78486 -0.719612 -0.0380827 0.693332 -0.719613 -0.0380804 0.69333 0.807319 0.0380806 -0.588886 0.807319 0.03808 -0.588886 0.879986 0.0380804 -0.473471 0.879987 0.0380821 -0.47347 0.936261 0.038082 -0.349235 0.936261 0.0380815 -0.349235 0.975095 0.0380814 -0.218495 0.975095 0.0380816 -0.218494 0.995764 0.0380815 -0.0836841 0.995764 0.0380811 -0.0836845 0.997885 0.0380816 0.0526846 0.997885 0.0380815 0.0526845 0.981417 0.0380821 0.188073 0.981417 0.0380818 0.188072 0.946666 0.038082 0.319958 0.946666 0.0380813 0.319957 0.894282 0.0380813 0.445881 0.894281 0.038083 0.445882 0.825237 0.0380834 0.563501 0.825238 0.0380818 0.5635 0.74082 0.0380819 0.670623 0.740821 0.0380802 0.670622 0.642609 0.03808 0.765247 0.642604 0.038087 0.765251 0.532417 0.0380875 0.845625 0.532422 0.038082 0.845622 0.412314 0.0380821 0.910246 0.412313 0.0380824 0.910246 0.284523 0.0380825 0.957912 0.284528 0.0380773 0.957911 0.151447 0.0380772 0.987732 0.151445 0.0380789 0.987732 0.0155357 0.0380789 0.999154 0.0155346 0.03808 0.999154 -0.120662 0.03808 0.991963 -0.120664 0.038082 0.991963 -0.254611 0.038082 0.966294 -0.254609 0.0380807 0.966294 -0.383812 0.0380807 0.922626 -0.383813 0.0380811 0.922625 -0.50587 0.0380811 0.861769 -0.505872 0.038083 0.861768 -0.618502 0.0380829 0.78486 -0.618502 0.0380828 0.78486 -0.719613 0.0380827 0.69333 -0.719612 0.0380804 0.693332 0.805546 0.0763562 -0.587593 0.805547 0.0763584 -0.587591 0.878054 0.076358 -0.47243 0.878053 0.0763557 -0.472432 0.934205 0.0763561 -0.348469 0.934205 0.0763559 -0.348469 0.972954 0.0763562 -0.218015 0.972954 0.0763572 -0.218014 0.993578 0.076357 -0.0835008 0.993578 0.0763568 -0.083501 0.995694 0.0763562 0.0525689 0.995694 0.0763566 0.0525693 0.979262 0.0763567 0.18766 0.979262 0.0763561 0.187659 0.944588 0.0763559 0.319255 0.944587 0.0763571 0.319256 0.892318 0.0763571 0.444903 0.892318 0.0763562 0.444902 0.823426 0.076356 0.562263 0.823425 0.0763574 0.562264 0.739195 0.0763576 0.669149 0.739196 0.0763554 0.669148 0.641194 0.0763553 0.763571 0.641193 0.0763563 0.763572 0.531253 0.0763563 0.843766 0.53125 0.076359 0.843767 0.411408 0.0763592 0.908247 0.41141 0.0763566 0.908246 0.283903 0.0763566 0.955808 0.2839 0.0763607 0.955809 0.151113 0.0763608 0.985563 0.151113 0.0763603 0.985563 0.0155005 0.0763603 0.99696 0.0154988 0.0763621 0.99696 -0.120399 0.0763621 0.989784 -0.120391 0.0763544 0.989786 -0.25405 0.0763545 0.964172 -0.254047 0.0763512 0.964173 -0.38297 0.0763514 0.9206 -0.382973 0.0763546 0.920599 -0.504761 0.0763547 0.859876 -0.504763 0.0763573 0.859874 -0.617144 0.0763572 0.783136 -0.617144 0.0763576 0.783136 -0.718032 0.0763574 0.691809 -0.718031 0.0763561 0.69181 0.192215 0.971285 -0.140208 -0.235114 0.945202 0.226528 0.437746 0.84049 -0.319305 -0.444291 0.786999 0.428063 0.586489 0.68776 -0.427805 -0.566136 0.618036 0.545456 0.735431 0.413966 -0.536445 -0.680154 0.328565 0.655314 0.793734 0.186482 -0.578974 0.793734 0.186483 -0.578974 0.865177 0.186483 -0.465504 0.865176 0.186482 -0.465504 0.920505 0.186482 -0.343358 0.920505 0.186486 -0.343356 0.958685 0.186485 -0.214817 0.958685 0.186481 -0.214819 0.979007 0.186482 -0.0822764 0.979007 0.186482 -0.0822764 0.981092 0.186483 0.0517983 0.981092 0.186483 0.0517981 0.964901 0.186484 0.184907 0.9649 0.186485 0.184908 0.930734 0.186486 0.314574 0.930735 0.186483 0.314573 0.879232 0.186484 0.438378 0.879232 0.186484 0.438378 0.811349 0.186484 0.554018 0.81135 0.186482 0.554018 0.728356 0.186482 0.659335 0.728355 0.186484 0.659335 0.631789 0.186484 0.752374 0.63179 0.186482 0.752373 0.52346 0.186482 0.831393 0.523462 0.186479 0.831392 0.405377 0.186478 0.894927 0.40537 0.186489 0.894928 0.279736 0.186489 0.941791 0.279741 0.186482 0.941791 0.148897 0.186482 0.97111 0.148897 0.186482 0.97111 0.0152715 0.186482 0.98234 0.0152711 0.186483 0.98234 -0.118626 0.186483 0.97527 -0.118623 0.186479 0.975271 -0.250322 0.186479 0.950034 -0.250324 0.186483 0.950033 -0.377356 0.186483 0.907098 -0.37736 0.18649 0.907095 -0.49736 0.18649 0.847263 -0.497353 0.186474 0.847271 -0.608095 0.186475 0.771653 -0.608096 0.186479 0.77165 -0.707501 0.18648 0.681665 -0.707502 0.186483 0.681663 0.763052 0.328565 -0.556593 0.760763 0.363383 -0.537765 0.820522 0.363098 -0.441478 0.820522 0.363099 -0.441478 0.872996 0.363098 -0.325634 0.872996 0.363096 -0.325636 0.909205 0.363097 -0.203732 0.909205 0.363099 -0.20373 0.928478 0.363098 -0.0780299 0.928478 0.363099 -0.0780292 0.930455 0.363098 0.0491247 0.930455 0.363098 0.0491247 0.9151 0.363097 0.175364 0.9151 0.363098 0.175365 0.882698 0.363098 0.298337 0.882697 0.363099 0.298337 0.833852 0.3631 0.415752 0.833852 0.363099 0.415751 0.769474 0.3631 0.525423 0.769474 0.363098 0.525423 0.690763 0.363099 0.625305 0.690763 0.363097 0.625305 0.599182 0.363097 0.713541 0.599184 0.363094 0.713541 0.496445 0.363094 0.788483 0.496443 0.363096 0.788483 0.384449 0.363096 0.84874 0.384447 0.363098 0.84874 0.265303 0.363098 0.893182 0.265305 0.363095 0.893183 0.141212 0.363095 0.920989 0.141213 0.363093 0.92099 0.0144829 0.363093 0.93164 0.0144834 0.363093 0.931641 -0.112501 0.363093 0.924936 -0.112509 0.363105 0.924931 -0.237403 0.363105 0.900996 -0.237403 0.363105 0.900996 -0.357883 0.363105 0.860276 -0.357877 0.363092 0.860284 -0.471684 0.363092 0.803541 -0.471686 0.363098 0.803537 -0.576711 0.363098 0.731823 -0.57671 0.363098 0.731823 -0.661213 0.363384 0.656315 -0.655533 0.413967 0.631592 0.68634 0.527542 -0.500637 0.68634 0.527545 -0.500634 0.748115 0.527544 -0.402519 0.748114 0.527546 -0.402517 0.795956 0.527545 -0.2969 0.795957 0.527543 -0.296902 0.828972 0.527543 -0.185752 0.828972 0.527543 -0.185752 0.846544 0.527543 -0.0711436 0.846544 0.527543 -0.0711437 0.848347 0.527543 0.0447897 0.848346 0.527543 0.04479 0.834346 0.527544 0.159889 0.834347 0.527542 0.159888 0.804805 0.527541 0.272011 0.804803 0.527543 0.272012 0.76027 0.527542 0.379064 0.760269 0.527543 0.379064 0.701572 0.527543 0.479057 0.701573 0.527542 0.479056 0.629807 0.527542 0.570125 0.629806 0.527543 0.570125 0.546308 0.527543 0.650573 0.546308 0.527543 0.650573 0.452634 0.527543 0.718902 0.452629 0.527548 0.718902 0.35052 0.527549 0.77384 0.350529 0.527539 0.773842 0.241893 0.527539 0.814365 0.241892 0.527541 0.814364 0.128752 0.527541 0.839717 0.128749 0.527544 0.839715 0.0132053 0.527544 0.849425 0.013205 0.527544 0.849425 -0.102581 0.527544 0.843312 -0.102578 0.527539 0.843315 -0.216455 0.527539 0.821492 -0.216455 0.527539 0.821493 -0.326296 0.527539 0.784368 -0.3263 0.527548 0.78436 -0.43006 0.527548 0.732626 -0.430059 0.527542 0.732631 -0.525819 0.527542 0.667243 -0.525819 0.527543 0.667243 -0.611775 0.527543 0.589432 -0.611775 0.527547 0.589428 0.635137 0.618036 -0.463285 0.602215 0.674563 -0.426968 0.650338 0.674258 -0.349909 0.650338 0.674257 -0.349911 0.691927 0.674258 -0.258097 0.691926 0.67426 -0.258095 0.720625 0.67426 -0.161474 0.720624 0.67426 -0.161474 0.7359 0.67426 -0.0618451 0.7359 0.67426 -0.0618454 0.737467 0.67426 0.0389359 0.737467 0.674259 0.0389353 0.725298 0.674259 0.138991 0.725296 0.67426 0.138992 0.699614 0.67426 0.236459 0.699614 0.67426 0.236459 0.660901 0.67426 0.32952 0.660902 0.67426 0.329519 0.609877 0.674259 0.416443 0.609874 0.674261 0.416443 0.547489 0.674262 0.495608 0.54749 0.674261 0.495608 0.474905 0.674261 0.565542 0.474905 0.67426 0.565542 0.393471 0.67426 0.624943 0.393473 0.674259 0.624943 0.304714 0.674259 0.672699 0.30471 0.674263 0.672697 0.210275 0.674263 0.707922 0.210281 0.674258 0.707925 0.111922 0.674259 0.729965 0.111917 0.674263 0.729962 0.0114791 0.674263 0.738402 0.0114828 0.674259 0.738406 -0.0891704 0.674259 0.733092 -0.0891722 0.674261 0.73309 -0.188163 0.674261 0.714119 -0.188161 0.674258 0.714122 -0.283654 0.674259 0.681847 -0.283652 0.674255 0.681852 -0.373851 0.674255 0.636879 -0.373855 0.674265 0.636867 -0.457091 0.674264 0.580031 -0.45709 0.674258 0.580039 -0.524672 0.674564 0.51931 -0.522778 0.687755 0.503682 0.498444 0.786995 -0.363582 0.492781 0.798562 -0.345638 0.53043 0.798244 -0.285395 0.530429 0.798245 -0.285394 0.564351 0.798245 -0.210508 0.564351 0.798245 -0.210509 0.587759 0.798244 -0.131702 0.58776 0.798244 -0.131703 0.600219 0.798244 -0.0504427 0.600219 0.798244 -0.0504425 0.601497 0.798243 0.0317566 0.601497 0.798244 0.0317572 0.59157 0.798244 0.113365 0.591571 0.798243 0.113364 0.570624 0.798243 0.192862 0.570623 0.798244 0.192863 0.539048 0.798244 0.268764 0.539048 0.798244 0.268764 0.497429 0.798244 0.339662 0.497434 0.798242 0.339662 0.446549 0.798242 0.404233 0.446546 0.798243 0.404233 0.387345 0.798243 0.461271 0.387346 0.798243 0.461272 0.320927 0.798243 0.50972 0.320926 0.798243 0.50972 0.24853 0.798243 0.548672 0.248531 0.798243 0.548672 0.17151 0.798243 0.577402 0.171508 0.798245 0.5774 0.0912825 0.798245 0.595377 0.0912853 0.798243 0.595379 0.00936567 0.798243 0.602263 0.00936638 0.798242 0.602264 -0.0727315 0.798242 0.59793 -0.0727315 0.798242 0.59793 -0.153469 0.798242 0.582457 -0.153473 0.798247 0.58245 -0.231351 0.798246 0.556129 -0.231351 0.798246 0.556129 -0.304926 0.798246 0.519446 -0.304924 0.798242 0.519453 -0.372815 0.798242 0.473095 -0.372815 0.798245 0.473089 -0.425644 0.798562 0.425589 -0.390201 0.840478 0.375952 0.360014 0.895226 -0.262605 0.360014 0.895225 -0.262607 0.392419 0.895225 -0.211139 0.392419 0.895225 -0.211138 0.417514 0.895225 -0.155737 0.417514 0.895225 -0.155738 0.434831 0.895225 -0.0974352 0.434831 0.895225 -0.0974348 0.444048 0.895226 -0.0373179 0.444048 0.895225 -0.037318 0.444993 0.895226 0.0234943 0.444993 0.895226 0.0234942 0.437649 0.895226 0.083868 0.437649 0.895226 0.0838683 0.422152 0.895226 0.142681 0.422155 0.895225 0.14268 0.398795 0.895225 0.198836 0.398792 0.895226 0.198836 0.368004 0.895226 0.251284 0.368005 0.895226 0.251284 0.330359 0.895226 0.299055 0.330359 0.895226 0.299055 0.286562 0.895226 0.341253 0.286561 0.895226 0.341253 0.237424 0.895226 0.377095 0.237423 0.895226 0.377095 0.183865 0.895226 0.405911 0.183866 0.895226 0.405912 0.126883 0.895226 0.427167 0.12688 0.895227 0.427165 0.0675332 0.895227 0.440463 0.067537 0.895225 0.440466 0.00692931 0.895225 0.44556 0.00692797 0.895226 0.445558 -0.0538072 0.895226 0.442352 -0.0538088 0.895227 0.442349 -0.113541 0.895227 0.430903 -0.113538 0.895225 0.430908 -0.171157 0.895225 0.411434 -0.171157 0.895225 0.411434 -0.225586 0.895225 0.384296 -0.225586 0.895225 0.384296 -0.275814 0.895225 0.349999 -0.275815 0.895225 0.349997 -0.320901 0.895225 0.309183 -0.320901 0.895225 0.309182 0.263775 0.9452 -0.192406 0.23162 0.962 -0.144594 0.240971 0.961833 -0.129652 0.240971 0.961833 -0.129652 0.256381 0.961833 -0.095633 0.25638 0.961834 -0.0956316 0.267014 0.961834 -0.0598312 0.267014 0.961833 -0.0598314 0.272675 0.961833 -0.0229157 0.272675 0.961833 -0.0229156 0.273255 0.961833 0.014427 0.273256 0.961833 0.014427 0.268746 0.961833 0.0515009 0.268746 0.961833 0.051501 0.259231 0.961833 0.0876149 0.25923 0.961833 0.0876155 0.244884 0.961834 0.122098 0.244886 0.961833 0.122098 0.22598 0.961833 0.154305 0.225978 0.961833 0.154305 0.202862 0.961833 0.183639 0.202862 0.961834 0.183639 0.175967 0.961834 0.209551 0.175968 0.961833 0.209552 0.145794 0.961833 0.231561 0.145794 0.961833 0.231561 0.112906 0.961833 0.249256 0.112907 0.961833 0.249257 0.0779133 0.961833 0.26231 0.0779133 0.961833 0.26231 0.0414722 0.961833 0.270475 0.0414699 0.961834 0.270474 0.00425422 0.961834 0.273601 0.00425649 0.961833 0.273603 -0.0330425 0.961833 0.271634 -0.0330428 0.961833 0.271634 -0.0697199 0.961833 0.264605 -0.0697209 0.961834 0.264603 -0.105101 0.961834 0.252646 -0.1051 0.961833 0.252647 -0.138524 0.961833 0.235982 -0.138524 0.961834 0.235981 -0.169367 0.961834 0.21492 -0.169367 0.961833 0.214923 -0.182468 0.962 0.203128 -0.171335 0.971285 0.165077 0.0745438 0.995734 -0.0543749 0.0745438 0.995734 -0.0543746 0.0812535 0.995734 -0.0437178 0.0812537 0.995734 -0.0437183 0.08645 0.995734 -0.0322465 0.0864502 0.995734 -0.0322468 0.0900358 0.995734 -0.0201748 0.0900357 0.995734 -0.0201746 0.0919442 0.995734 -0.00772701 0.0919442 0.995734 -0.00772702 0.0921399 0.995734 0.00486467 0.0921399 0.995734 0.0048647 0.0906193 0.995734 0.0173658 0.0906193 0.995734 0.0173658 0.0874105 0.995734 0.0295434 0.0874109 0.995734 0.0295432 0.0825739 0.995734 0.0411707 0.0825737 0.995734 0.0411708 0.0761986 0.995734 0.0520309 0.0761985 0.995734 0.0520309 0.0684038 0.995734 0.0619221 0.068404 0.995734 0.0619221 0.0593353 0.995734 0.0706596 0.0593352 0.995734 0.0706596 0.0491608 0.995734 0.0780811 0.0491609 0.995734 0.0780811 0.0380714 0.995734 0.0840477 0.0380714 0.995734 0.0840477 0.0262718 0.995734 0.0884491 0.0262723 0.995734 0.0884493 0.0139835 0.995734 0.0912029 0.0139835 0.995734 0.0912029 0.00143526 0.995734 0.0922575 0.00143401 0.995734 0.0922563 -0.0111417 0.995734 0.0915923 -0.0111404 0.995734 0.091594 -0.0235097 0.995734 0.0892236 -0.0235097 0.995734 0.0892235 -0.0354394 0.995734 0.0851915 -0.03544 0.995734 0.0851899 -0.0467095 0.995734 0.0795711 -0.0467091 0.995734 0.0795724 -0.0571096 0.995734 0.0724706 -0.0571096 0.995734 0.0724704 -0.0664457 0.995734 0.0640189 -0.0664457 0.995734 0.0640185 -0.76356 0.0765335 0.641185 -0.76362 0.076419 0.641127 -0.765195 0.0381693 0.642666 -0.765252 0.0380534 0.642605 -0.765248 -0.0381693 0.642602 -0.765198 -0.0380532 0.642669 -0.763614 -0.0765335 0.641121 -0.763567 -0.0764188 0.641191 -0.182 -0.971413 0.152424 -0.130457 -0.988739 0.0733274 -0.0704962 -0.995754 0.0591979 -0.249377 -0.945437 0.209668 -0.356102 -0.895376 0.267381 -0.336228 -0.903327 0.266367 -0.414263 -0.841054 0.347872 -0.427408 -0.829763 0.35891 -0.471285 -0.787697 0.396766 -0.532995 -0.738923 0.412201 -0.555316 -0.688601 0.466319 -0.594206 -0.630826 0.498976 -0.601345 -0.618927 0.505287 -0.665066 -0.51012 0.545403 -0.752312 -0.186904 0.631739 -0.758949 -0.236992 0.606491 -0.722419 -0.329249 0.608035 -0.709285 -0.377046 0.595609 -0.696828 -0.414768 0.585148 -0.665302 -0.528285 0.52753 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.72281 -0.32925 -0.607569 0.715977 -0.241411 -0.655055 0.752312 -0.186903 -0.631739 0.697017 -0.414767 -0.584923 0.626407 -0.528083 -0.57336 0.645301 -0.513228 -0.565848 0.601501 -0.618926 -0.5051 0.5916 -0.634991 -0.496786 0.556053 -0.688605 -0.465434 0.487882 -0.74029 -0.462538 0.471786 -0.787694 -0.396177 0.424132 -0.832624 -0.356159 0.0704962 -0.995754 -0.0591978 0.0882615 -0.989011 -0.118605 0.182796 -0.971412 -0.151473 0.219631 -0.957991 -0.184433 0.249508 -0.945435 -0.209522 0.307418 -0.904261 -0.296321 0.332583 -0.89557 -0.295539 0.414482 -0.841065 -0.347584 0.765252 -0.038053 -0.642606 0.765334 -0.0381693 -0.6425 0.763482 -0.0764192 -0.641292 0.76356 -0.0765335 -0.641185 0.763567 0.0764195 -0.641191 0.763475 0.0765335 -0.641287 0.765338 0.0380532 -0.642502 0.765248 0.0381693 -0.642603 0.0704962 0.995754 -0.0591978 0.0900421 0.988113 -0.124597 0.18152 0.971413 -0.152992 0.249685 0.945435 -0.209311 0.310294 0.902487 -0.298722 0.330664 0.895533 -0.297794 0.414249 0.841065 -0.347861 0.427299 0.829858 -0.358819 0.472515 0.787693 -0.395309 0.490239 0.737499 -0.4645 0.555314 0.688606 -0.466315 0.594213 0.630816 -0.49898 0.752312 0.186903 -0.631739 0.71947 0.236437 -0.653039 0.724193 0.32925 -0.605921 0.709283 0.377056 -0.595606 0.696829 0.414767 -0.585148 0.638539 0.509311 -0.576949 0.641875 0.528387 -0.555701 0.601739 0.618927 -0.504816 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.723296 0.329249 0.606991 -0.759489 0.242046 0.603813 -0.752312 0.186904 0.631739 -0.696708 0.414768 0.58529 -0.664768 0.528296 0.528193 -0.664662 0.513711 0.542518 -0.6015 0.618927 0.505101 -0.591614 0.634968 0.496799 -0.554832 0.688601 0.466895 -0.530643 0.741715 0.410216 -0.471785 0.787697 0.396173 -0.424127 0.832629 0.356153 -0.414104 0.841054 0.34806 -0.332132 0.905093 0.265509 -0.0704962 0.995754 0.0591979 -0.124958 0.989543 0.0720384 -0.181077 0.971412 0.153524 -0.21962 0.957996 0.184422 -0.249504 0.945437 0.209517 -0.35668 0.895356 0.266676 -0.87808 0.0375522 0.477038 -0.862165 0.0409651 0.504969 -0.981043 0.031739 0.191171 -0.994736 0.0365362 0.0957344 -0.998765 0.0290562 -0.0402981 -0.977946 0.024505 -0.207417 -0.953333 0.0266679 -0.30074 -0.885916 0.0121949 -0.463685 -0.7228 0.0122513 -0.690949 -0.760477 0.00912358 -0.649301 -0.628818 0.000631119 -0.777552 -0.876369 0.0754112 0.475701 -0.876416 0.0754199 0.475612 -0.993411 0.0644886 0.0947423 -0.993417 0.0644923 0.094679 -0.952541 0.0433118 -0.301314 -0.952531 0.043313 -0.301346 -0.760197 0.0152439 -0.649513 -0.760208 0.0152435 -0.649501 -0.628818 -0.000631119 -0.777552 -0.760477 -0.00912358 -0.649301 -0.7228 -0.0122513 -0.690949 -0.885916 -0.0121949 -0.463685 -0.953333 -0.0266679 -0.30074 -0.977946 -0.024505 -0.207417 -0.998765 -0.0290562 -0.0402981 -0.994736 -0.0365362 0.0957344 -0.981043 -0.031739 0.191171 -0.877999 -0.0402713 0.476965 -0.862274 -0.0377352 0.505034 -0.876417 -0.0754099 0.475612 -0.876368 -0.0754212 0.4757 -0.993417 -0.064486 0.0946793 -0.993411 -0.0644949 0.0947421 -0.952531 -0.0433096 -0.301346 -0.952541 -0.0433152 -0.301314 -0.760208 -0.0152451 -0.649501 -0.760197 -0.0152422 -0.649513 -0.62049 -0.756137 -0.207965 -0.757438 -0.0477259 -0.651161 -0.942442 -0.135209 -0.305813 -0.791311 -0.495938 0.357591 -0.822359 -0.371765 0.430717 -0.856769 -0.233632 0.459742 -0.855743 -0.233914 0.461506 -0.976105 -0.200205 0.0844839 -0.903316 -0.428066 0.0279178 -0.903698 -0.427455 0.0247319 -0.780249 -0.621334 -0.071802 -0.542525 -0.816405 0.197861 -0.63135 -0.727114 0.269634 -0.645141 -0.722044 0.249892 -0.707955 -0.621458 0.335545 -0.772469 -0.502587 0.388199 -0.44599 -0.887661 0.114674 -0.4539 -0.884877 0.104726 -0.618958 -0.758738 -0.202997 -0.781082 -0.61976 -0.0762162 -0.757245 -0.0476195 -0.651392 -0.740001 -0.101926 -0.664838 -0.739682 -0.101554 -0.66525 -0.710247 -0.147776 -0.688267 -0.709906 -0.146983 -0.688788 -0.671291 -0.180079 -0.718985 -0.671135 -0.179031 -0.719393 -0.626827 -0.19624 -0.754041 -0.626936 -0.194998 -0.754273 -0.603171 -0.441429 -0.664324 -0.578124 -0.555772 -0.597403 -0.700047 -0.508148 -0.501718 -0.700053 -0.5106 -0.499212 -0.809175 -0.417058 -0.413882 -0.809589 -0.418584 -0.411526 -0.892767 -0.28796 -0.346477 -0.893253 -0.288611 -0.344677 -0.942211 -0.134945 -0.306639 -0.975912 -0.200537 0.0859097 -0.233597 -0.970332 -0.0623586 -0.227769 -0.97211 -0.0558927 -0.374837 -0.888895 -0.263368 -0.437463 -0.827726 -0.35142 -0.465067 -0.787825 -0.403788 -0.558203 -0.606256 -0.566448 -0.604119 -0.195082 -0.772647 -0.550057 -0.442396 -0.708324 -0.594969 -0.258803 -0.760943 -0.488663 -0.608774 -0.624982 -0.434762 -0.707096 -0.557671 -0.374986 -0.793332 -0.479593 -0.272433 -0.89687 -0.348431 -0.158828 -0.965926 -0.204353 -0.120165 -0.980786 -0.153686 0.411056 -0.610074 -0.677379 0.250122 -0.801115 -0.54374 -0.565768 -0.257116 -0.783453 -0.565164 -0.25862 -0.783393 0.0528703 -0.923498 -0.379943 -0.0547472 -0.954683 -0.292547 -0.0488227 -0.956626 -0.2872 0.154626 -0.871334 -0.465691 0.136684 -0.866718 -0.479706 -0.200721 -0.641745 -0.740185 -0.356231 -0.700085 -0.618854 -0.353174 -0.70343 -0.61681 0.336245 -0.712902 -0.615394 0.322367 -0.710768 -0.625211 -0.0667335 -0.524016 -0.84909 -0.203396 -0.638536 -0.742228 -0.509393 -0.234427 -0.827987 -0.508505 -0.235696 -0.828173 -0.421703 -0.13256 -0.896992 -0.422446 -0.132227 -0.896691 0.0321335 -0.360594 -0.932169 0.474706 -0.493257 -0.728939 0.465202 -0.492819 -0.735334 0.0344522 -0.361872 -0.931591 -0.0695172 -0.52169 -0.850298 -0.459958 -0.191372 -0.867073 -0.458994 -0.19219 -0.867403 0.558108 -0.232267 -0.796598 0.559842 -0.232157 -0.795412 0.0933713 -0.169231 -0.981144 0.0946248 -0.169294 -0.981013 -0.399858 -0.0619928 -0.914478 -0.399517 -0.0620328 -0.914625 0.646508 -0.0372925 -0.761995 0.577269 -0.0438614 -0.815375 0.432669 -0.0341512 -0.900906 0.275159 -0.0308319 -0.960904 0.103584 -0.0336076 -0.994053 0.0288385 -0.0248756 -0.999274 -0.376018 -0.00974912 -0.926561 -0.396589 -0.0116211 -0.917923 -0.603149 -0.000613293 -0.797628 0.575878 -0.0732615 -0.814247 0.575961 -0.0732511 -0.814189 0.102696 -0.0531276 -0.993293 0.102732 -0.053125 -0.993289 -0.396936 -0.0193687 -0.917642 -0.396908 -0.0193671 -0.917654 -0.603149 0.000613294 -0.797628 -0.396589 0.0116211 -0.917923 -0.376018 0.00974912 -0.926561 0.0288385 0.0248756 -0.999274 0.103584 0.0336076 -0.994053 0.275159 0.0308319 -0.960904 0.432669 0.0341512 -0.900906 0.577269 0.0438614 -0.815375 0.646508 0.0372925 -0.761995 0.57596 0.0732638 -0.814188 0.575878 0.0732489 -0.814247 0.102732 0.0531297 -0.993289 0.102696 0.053123 -0.993293 -0.396908 0.0193709 -0.917654 -0.396936 0.0193649 -0.917642 -0.195129 0.638316 -0.744632 0.0936967 0.165482 -0.981752 0.453547 0.481265 -0.750119 0.523895 0.361843 -0.771106 0.560473 0.227538 -0.796302 0.558921 0.227158 -0.7975 0.0948241 0.165831 -0.981585 0.0348972 0.354617 -0.93436 0.0374456 0.355282 -0.934009 -0.0656032 0.517076 -0.853422 0.253014 0.798471 -0.546286 0.343063 0.711445 -0.613314 0.32325 0.702662 -0.633858 0.413533 0.605985 -0.679539 0.479505 0.490406 -0.72772 0.162613 0.871439 -0.462765 0.148722 0.864379 -0.480344 -0.198694 0.6356 -0.746012 -0.0623017 0.518708 -0.852678 -0.564521 0.256984 -0.784395 -0.506769 0.234554 -0.82956 -0.507366 0.23315 -0.829591 -0.45756 0.190463 -0.86854 -0.458348 0.18941 -0.868355 -0.420722 0.130325 -0.89778 -0.42137 0.129814 -0.89755 -0.399483 0.0607305 -0.914727 -0.399773 0.0606109 -0.914608 -0.0456517 0.95609 -0.289497 -0.0501033 0.953766 -0.296345 -0.279732 0.787828 -0.548705 -0.346892 0.697747 -0.62675 -0.415128 0.606259 -0.67832 -0.564236 0.258609 -0.784066 -0.604119 0.195081 -0.772647 -0.594377 0.258801 -0.761405 -0.512526 0.55561 -0.654687 -0.488664 0.608772 -0.624983 -0.342219 0.831456 -0.437685 -0.375573 0.793336 -0.479126 -0.119378 0.980786 -0.154296 -0.159419 0.965927 -0.203891 -0.705458 0.625471 0.33334 -0.539339 0.819191 0.195039 -0.626127 0.196187 -0.754636 -0.626042 0.195006 -0.755013 -0.337118 0.941084 0.026706 -0.224727 0.972643 -0.0588492 -0.229067 0.971164 -0.066104 -0.438863 0.890673 0.118749 -0.461641 0.883814 0.0759026 -0.614753 0.75952 -0.212623 -0.431095 0.82883 -0.356649 -0.433416 0.825565 -0.361376 -0.62567 0.730692 0.273179 -0.642407 0.7279 0.23974 -0.776295 0.625257 -0.0801199 -0.612392 0.762622 -0.208284 -0.696141 0.510404 -0.504852 -0.572701 0.556793 -0.601661 -0.57334 0.553836 -0.603777 -0.738777 0.103365 -0.665976 -0.739162 0.103643 -0.665505 -0.890783 0.29386 -0.34663 -0.708633 0.148429 -0.689789 -0.709059 0.149053 -0.689216 -0.805979 0.422719 -0.414374 -0.890457 0.292848 -0.348319 -0.899658 0.435879 0.0249951 -0.768616 0.506496 0.390756 -0.779862 0.506295 0.368076 -0.900315 0.434685 0.0219607 -0.774897 0.62749 -0.0761018 -0.805905 0.420766 -0.416502 -0.695632 0.513187 -0.502728 -0.669894 0.180895 -0.720083 -0.669577 0.17992 -0.720621 -0.854757 0.238699 0.460884 -0.855758 0.238816 0.45896 -0.975072 0.204706 0.085611 -0.975219 0.204652 0.0840579 -0.941996 0.138068 -0.305911 -0.941716 0.137971 -0.306813 -0.757338 0.0487441 -0.651202 -0.757111 0.0486956 -0.651469 -0.615953 3.64913e-06 -0.787783 -0.615954 2.27374e-07 -0.787782 -0.615954 -5.76492e-08 -0.787782 -0.615964 5.29426e-06 -0.787775 -0.615963 4.21695e-07 -0.787775 -0.615952 -2.58321e-06 -0.787784 -0.615951 -3.43803e-06 -0.787784 -0.615952 3.19525e-06 -0.787783 -0.615955 3.36287e-06 -0.787781 -0.615949 -8.45712e-07 -0.787786 -0.615949 8.34003e-08 -0.787786 -0.615945 -5.39324e-06 -0.787789 -0.61596 -1.68589e-06 -0.787777 -0.615954 -5.47719e-06 -0.787782 -0.615956 2.14126e-06 -0.78778 -0.615956 2.22471e-06 -0.78778 -0.615955 1.27175e-06 -0.787782 -0.615955 2.93818e-07 -0.787781 -0.615951 2.5635e-06 -0.787784 -0.615946 -1.1019e-06 -0.787788 -0.615965 6.29221e-06 -0.787773 -0.615954 -4.74953e-06 -0.787782 -0.615955 1.18066e-06 -0.787782 -0.615956 -1.37503e-06 -0.787781 -0.615958 -3.8253e-06 -0.787779 -0.61595 0 -0.787785 -0.615958 3.8253e-06 -0.787779 -0.615957 2.81846e-06 -0.78778 -0.615955 1.24385e-06 -0.787782 -0.615955 6.16165e-07 -0.787782 -0.615953 -1.52571e-06 -0.787783 -0.615953 -1.68237e-06 -0.787783 -0.615952 -3.78917e-06 -0.787784 -0.615956 -6.94855e-06 -0.787781 -0.615956 3.72013e-06 -0.787781 -0.615954 4.1895e-06 -0.787782 -0.615956 -2.11194e-06 -0.787781 -0.615955 -2.13371e-06 -0.787781 -0.615955 -5.99577e-06 -0.787781 -0.615951 -1.33235e-08 -0.787784 -0.615957 9.638e-07 -0.78778 -0.615958 -3.99545e-06 -0.787779 -0.615952 -1.7015e-06 -0.787784 -0.615952 1.14546e-06 -0.787784 -0.615955 -1.6337e-06 -0.787782 -0.615955 7.19097e-07 -0.787781 -0.615954 5.15802e-06 -0.787782 -0.615949 -2.52084e-06 -0.787786 -0.615948 -5.01614e-06 -0.787787 -0.615959 3.08637e-06 -0.787778 -0.615959 3.59448e-06 -0.787778 -0.615953 0 -0.787783 -0.615959 -3.59448e-06 -0.787778 -0.615955 4.3915e-06 -0.787782 -0.615958 1.66257e-06 -0.787779 -0.615952 -3.44528e-06 -0.787784 -0.615952 -2.73224e-06 -0.787784 -0.615961 -3.15951e-06 -0.787777 -0.615959 -4.8239e-06 -0.787778 -0.615951 1.2388e-06 -0.787785 -0.615957 -3.35584e-07 -0.78778 -0.615943 1.31257e-05 -0.787791 -0.615961 5.35584e-06 -0.787777 -0.615953 -3.47536e-07 -0.787783 -0.615954 -3.75167e-06 -0.787782 -0.615953 -3.63586e-06 -0.787783 -0.615955 -9.88503e-06 -0.787781 -0.61595 -3.87272e-06 -0.787785 -0.433646 -0.607285 -0.6657 -0.191905 -0.892286 -0.408654 -0.0329117 -0.974851 -0.220414 -0.0329263 -0.974846 -0.220435 0.0854832 -0.945471 -0.31429 0.357056 -0.931274 -0.0723848 0.167758 -0.910355 -0.378301 0.29171 -0.830648 -0.474268 0.466091 -0.853767 -0.232036 0.347911 -0.780334 -0.519651 0.42701 -0.693678 -0.580063 0.427043 -0.693688 -0.580028 0.494606 -0.594171 -0.634292 0.69355 -0.531516 -0.486291 0.648514 -0.109838 -0.753237 0.648535 -0.10984 -0.753218 0.624783 -0.260939 -0.735906 0.833982 -0.325868 -0.445291 0.597251 -0.365172 -0.714101 0.543669 -0.503118 -0.671786 0.311488 -0.0932794 -0.945661 0.311465 -0.0932761 -0.945669 0.278762 -0.275154 -0.920099 0.278801 -0.275165 -0.920084 0.215031 -0.443248 -0.870226 0.214932 -0.443207 -0.870271 0.123311 -0.589055 -0.798629 0.123339 -0.589071 -0.798613 0.0084408 -0.705384 -0.708775 0.00846037 -0.705398 -0.708761 -0.123947 -0.786338 -0.605236 -0.123919 -0.786363 -0.605209 -0.269659 -0.828345 -0.491049 -0.303292 -0.790258 -0.532453 -0.0744013 -0.0624683 -0.99527 -0.0742608 -0.062492 -0.995279 -0.0961677 -0.184318 -0.978151 -0.0963018 -0.184269 -0.978147 -0.139005 -0.296837 -0.944757 -0.138932 -0.296879 -0.944754 -0.200305 -0.394568 -0.896769 -0.200288 -0.394582 -0.896766 -0.277254 -0.472492 -0.836589 -0.277311 -0.472426 -0.836607 -0.365992 -0.526642 -0.767267 -0.365968 -0.526681 -0.767251 -0.464335 -0.555093 -0.690119 -0.512497 -0.441848 -0.736286 -0.450253 -0.0219931 -0.89263 -0.450389 -0.021965 -0.892562 -0.45809 -0.0647965 -0.886541 -0.45803 -0.0648247 -0.88657 -0.473053 -0.104425 -0.874823 -0.473071 -0.104412 -0.874816 -0.494655 -0.13877 -0.857939 -0.494671 -0.138751 -0.857933 -0.521733 -0.166147 -0.836774 -0.521657 -0.166282 -0.836794 -0.552869 -0.185359 -0.81239 -0.552904 -0.185255 -0.81239 -0.586664 -0.195037 -0.785994 -0.586664 -0.195035 -0.785994 0.601527 0 -0.798853 0.652461 -0.0015381 -0.757821 0.250016 0.00116081 -0.968241 0.312852 0 -0.949802 -0.00913295 0 -0.999958 -0.0745469 0.00077647 -0.997217 -0.391046 -0.00115907 -0.920371 -0.450362 0 -0.892846 0.24953 0.0623119 -0.96636 -0.450433 0.608022 -0.653773 -0.339897 0.792631 -0.506168 -0.578794 0.25879 -0.773321 -0.578814 0.258734 -0.773325 -0.547114 0.252359 -0.798111 -0.547099 0.252391 -0.798111 -0.516594 0.239809 -0.821962 -0.516592 0.239812 -0.821963 -0.488 0.22132 -0.844318 -0.487979 0.221344 -0.844324 -0.462018 0.197402 -0.864623 -0.462053 0.197371 -0.864611 -0.439364 0.16857 -0.882351 -0.439316 0.168601 -0.882369 -0.420453 0.135647 -0.897117 -0.420486 0.135632 -0.897104 -0.405916 0.0993347 -0.908496 -0.40589 0.0993414 -0.908507 -0.395975 0.0606038 -0.916259 -0.396045 0.0605968 -0.916229 -0.391026 0.0203644 -0.920155 -0.390965 0.0203603 -0.92018 -0.00912249 0.0478555 -0.998813 0.122424 0.0463158 -0.991397 0.107646 0.16533 -0.980346 0.107582 0.165328 -0.980353 0.0805332 0.271005 -0.959203 0.080518 0.271003 -0.959205 0.0407771 0.370014 -0.928131 0.0407651 0.370011 -0.928133 -0.0106885 0.459914 -0.887899 -0.010639 0.459932 -0.88789 -0.0725441 0.538515 -0.839488 -0.0725725 0.5385 -0.839494 -0.143393 0.603818 -0.784119 -0.143324 0.603862 -0.784097 -0.221344 0.65432 -0.723099 -0.22137 0.6543 -0.723109 -0.304622 0.688636 -0.658017 -0.30463 0.688628 -0.658021 -0.391099 0.706013 -0.590413 -0.0992524 0.963145 -0.250002 -0.0992442 0.963148 -0.249994 0.0187162 0.939432 -0.342223 0.0187266 0.939435 -0.342214 0.132317 0.892587 -0.431022 0.132264 0.892575 -0.431064 0.238671 0.823748 -0.514272 0.238728 0.823758 -0.514229 0.335345 0.734655 -0.589768 0.335359 0.734657 -0.589758 0.419816 0.627454 -0.655787 0.419819 0.627454 -0.655785 0.490023 0.504802 -0.710671 0.48999 0.504801 -0.710694 0.54421 0.369724 -0.753087 0.54422 0.369724 -0.753079 0.581127 0.225543 -0.781935 0.581106 0.225545 -0.78195 0.59979 0.0757985 -0.796559 0.599796 0.0757976 -0.796554 -0.120161 0.980787 -0.153682 -0.159738 0.965924 -0.203652 -0.341992 0.831474 -0.437828 -0.374934 0.793397 -0.479527 -0.512145 0.555573 -0.655016 -0.488374 0.608721 -0.62526 -0.604536 0.195082 -0.772321 -0.594962 0.258843 -0.760934 -0.899754 0.0497753 -0.43355 -0.887427 0.109837 0.447671 -0.783089 0.503118 0.365573 -0.205965 0.974852 -0.0850979 -0.205968 0.974851 -0.0851006 -0.325609 0.945477 0.00718479 -0.156361 0.931274 0.329059 -0.40758 0.91036 0.071575 -0.530608 0.830653 0.168731 -0.665913 0.693686 0.274519 -0.665928 0.69368 0.274495 -0.588216 0.780339 0.212304 -0.33763 0.853768 0.396341 -0.83708 0.36517 0.407366 -0.633327 0.32587 0.70193 -0.960172 0.275151 0.0485908 -0.414194 0.827847 -0.378303 -0.414177 0.827865 -0.378282 -0.557463 0.786346 -0.266261 -0.55747 0.786337 -0.266273 -0.689877 0.705395 -0.162749 -0.689884 0.705384 -0.162766 -0.804781 0.589075 -0.0729223 -0.804779 0.58908 -0.0729124 -0.89641 0.443225 -0.00127734 -0.864887 0.260936 0.428816 -0.887417 0.10984 0.44769 -0.992874 0.0932765 0.0741624 -0.974915 0.0908517 0.203192 -0.995987 0.0890349 0.00906727 -0.560364 0.554487 -0.615253 -0.560367 0.554481 -0.615256 -0.656328 0.526679 -0.540225 -0.656337 0.526639 -0.540252 -0.745017 0.472434 -0.47091 -0.745013 0.472504 -0.470846 -0.82198 0.394586 -0.410671 -0.821976 0.394555 -0.410709 -0.883347 0.296868 -0.362723 -0.883352 0.296882 -0.3627 -0.926062 0.184301 -0.329307 -0.734875 0.594162 0.327001 -0.639227 0.531518 0.555768 -0.896409 0.443226 -0.00127501 -0.960173 0.275149 0.0485819 -0.926062 0.184302 -0.329305 -0.947967 0.0624743 -0.312178 -0.966269 0.0636041 -0.249558 -0.75764 0.0219797 -0.652302 -0.75765 0.0219824 -0.652291 -0.749944 0.0648432 -0.658316 -0.749916 0.0648247 -0.658349 -0.734894 0.104422 -0.670095 -0.734897 0.104425 -0.670091 -0.713308 0.13879 -0.686971 -0.713279 0.138732 -0.687013 -0.686217 0.166124 -0.708173 -0.686238 0.166199 -0.708136 -0.65504 0.18527 -0.732528 -0.655039 0.185258 -0.732532 -0.621287 0.195037 -0.758922 -0.621287 0.195035 -0.758923 -0.892829 0 0.450396 -0.920362 0.00115951 0.391065 -0.978963 0 0.204036 -0.999959 0 0.0091035 -0.99259 0.00154909 -0.121504 -0.968229 0 -0.250064 -0.900871 0 -0.434088 -0.798872 0.00115996 -0.6015 -0.757823 0 -0.65246 -0.610884 -0.258789 -0.748231 -0.610884 -0.258766 -0.748239 -0.642582 -0.252393 -0.723454 -0.642578 -0.252362 -0.723469 -0.673085 -0.239781 -0.699616 -0.673102 -0.239843 -0.699578 -0.701694 -0.221349 -0.677223 -0.701685 -0.221329 -0.677238 -0.727646 -0.197386 -0.65694 -0.727663 -0.197412 -0.656914 -0.750355 -0.168606 -0.639172 -0.750332 -0.168582 -0.639204 -0.769194 -0.135626 -0.624456 -0.769209 -0.135637 -0.624436 -0.783776 -0.099344 -0.613047 -0.783763 -0.0993385 -0.613064 -0.793679 -0.060597 -0.605311 -0.793672 -0.0605959 -0.605321 -0.798692 -0.0203639 -0.601396 -0.798707 -0.0203623 -0.601376 -0.478659 -0.705986 -0.521985 -0.478654 -0.705999 -0.521973 -0.565117 -0.688618 -0.454366 -0.565108 -0.688646 -0.454334 -0.648372 -0.654301 -0.389235 -0.648379 -0.654265 -0.389283 -0.726379 -0.60382 -0.328291 -0.726377 -0.603839 -0.32826 -0.797204 -0.538518 -0.272882 -0.797204 -0.538509 -0.2729 -0.859106 -0.459932 -0.224498 -0.859107 -0.45994 -0.224476 -0.910565 -0.370034 -0.184243 -0.910565 -0.370032 -0.18425 -0.950309 -0.271016 -0.153175 -0.95031 -0.271016 -0.153171 -0.977363 -0.165325 -0.132018 -0.977362 -0.165324 -0.132031 -0.991057 -0.0555646 -0.121323 -0.991057 -0.0555641 -0.121317 -0.218673 -0.963149 -0.15661 -0.218677 -0.963147 -0.156618 -0.336637 -0.939431 -0.0643865 -0.33664 -0.939429 -0.0643908 -0.450222 -0.892583 0.0244206 -0.450221 -0.892583 0.024423 -0.556635 -0.823756 0.107626 -0.556635 -0.823756 0.107627 -0.653253 -0.734648 0.183173 -0.65325 -0.734649 0.183181 -0.737698 -0.62745 0.249214 -0.737699 -0.62745 0.249212 -0.807898 -0.504799 0.304103 -0.807903 -0.504799 0.304091 -0.862122 -0.369721 0.346485 -0.862121 -0.369721 0.346487 -0.899027 -0.225539 0.375343 -0.899032 -0.22554 0.375331 -0.917716 -0.0757993 0.389939 -0.917715 -0.0757992 0.38994 -0.120168 -0.980785 -0.15369 -0.1591 -0.965929 -0.20413 -0.272474 -0.896837 -0.348485 -0.37493 -0.793402 -0.479521 -0.435144 -0.707076 -0.557398 -0.488691 -0.608714 -0.625018 -0.594962 -0.258843 -0.760934 -0.551153 -0.442404 -0.707467 -0.604119 -0.195083 -0.772647 0.0882037 -0.993712 -0.0689645 0.127787 -0.991119 0.0367975 0.162357 -0.961198 -0.22302 0.183905 -0.97237 -0.143792 0.293288 -0.928114 -0.229316 0.28804 -0.923662 -0.25275 0.419507 -0.858175 -0.295889 0.411615 -0.852641 -0.321833 0.477236 -0.795621 -0.37314 0.48903 -0.759906 -0.428243 0.610231 -0.704236 -0.362862 0.576379 -0.649029 -0.496537 0.785355 -0.0784563 -0.614054 0.82721 -0.111643 -0.55069 0.738584 -0.233229 -0.632533 0.759394 -0.26604 -0.593754 0.727817 -0.382685 -0.569064 0.715334 -0.372175 -0.591424 0.689218 -0.522277 -0.502201 0.676273 -0.512898 -0.528763 0.626774 -0.605801 -0.490061 0.787783 0 -0.615953 0.787783 0 -0.615953 0.785355 0.0784572 -0.614054 0.733959 0.111642 -0.669956 0.792009 0.233228 -0.564204 0.759394 0.26604 -0.593754 0.727817 0.382685 -0.569064 0.746506 0.372175 -0.551557 0.653618 0.522277 -0.547732 0.676273 0.512898 -0.528763 0.599037 0.649446 -0.468374 0.699096 0.601012 -0.387362 0.369765 0.743205 -0.557602 0.608106 0.704471 -0.365961 0.477236 0.795621 -0.37314 0.411615 0.852641 -0.321832 0.38834 0.858175 -0.335749 0.314765 0.923661 -0.218571 0.293288 0.928114 -0.229317 0.183904 0.97237 -0.143791 0.255599 0.961198 -0.103767 -0.00489047 0.991119 -0.132892 0.0882043 0.993712 -0.068965 0 1 0 0 1 0 -0.620905 0.649023 0.439598 -0.499329 0.704236 0.504701 -0.53355 0.759911 0.371294 -0.477236 0.795621 0.37314 -0.411618 0.852639 0.321835 -0.388343 0.858173 0.335753 -0.314763 0.923663 0.218568 -0.293285 0.928116 0.229314 -0.183904 0.97237 0.143791 -0.255599 0.961198 0.103767 0.00489047 0.991119 0.132892 -0.0882043 0.993712 0.068965 -0.785356 0.0784563 0.614053 -0.733959 0.111642 0.669956 -0.792009 0.233228 0.564204 -0.759394 0.26604 0.593754 -0.727817 0.382685 0.569064 -0.746506 0.372175 0.551557 -0.653618 0.522277 0.547732 -0.676273 0.512898 0.528763 -0.626774 0.605801 0.490061 -0.787784 0 0.615951 -0.787784 0 0.615951 -0.785356 -0.0784563 0.614053 -0.785356 -0.0784563 0.614053 -0.766017 -0.233448 0.598932 -0.766017 -0.233448 0.598932 -0.727817 -0.382685 0.569064 -0.727817 -0.382685 0.569064 -0.671698 -0.522495 0.525186 -0.671698 -0.522495 0.525186 -0.599037 -0.649447 0.468374 -0.599037 -0.649447 0.468374 -0.511623 -0.760408 0.400027 -0.511623 -0.760408 0.400027 -0.411618 -0.852638 0.321835 -0.411618 -0.852638 0.321835 -0.30147 -0.92388 0.235713 -0.30147 -0.92388 0.235713 -0.183905 -0.97237 0.143792 -0.183905 -0.97237 0.143791 -0.0618083 -0.996917 0.0483265 -0.0618083 -0.996917 0.0483265 0 -1 0 0 -1 0 -0.0992512 -0.963145 -0.250003 -0.391086 -0.70603 -0.590401 -0.586909 -0.25883 -0.767167 -0.533514 -0.288873 -0.794931 -0.569786 -0.29614 -0.76658 -0.57095 -0.257259 -0.779637 -0.555108 -0.254075 -0.792023 -0.53955 -0.249279 -0.804205 -0.524316 -0.242996 -0.816116 -0.498608 -0.274435 -0.822238 -0.50952 -0.235224 -0.827683 -0.495231 -0.225982 -0.838855 -0.46587 -0.253286 -0.847827 -0.410267 -0.192877 -0.891336 -0.481598 -0.215292 -0.849537 -0.468657 -0.203356 -0.859655 -0.436204 -0.225845 -0.871045 -0.456446 -0.190194 -0.869185 -0.445104 -0.175797 -0.878054 -0.371917 -0.113699 -0.921276 -0.434747 -0.160324 -0.886167 -0.425333 -0.143875 -0.893528 -0.388586 -0.155218 -0.908245 -0.416896 -0.126547 -0.900102 -0.409632 -0.108451 -0.905782 -0.394752 -0.0505553 -0.917396 -0.360586 -0.0693427 -0.930145 -0.398617 -0.0703013 -0.914419 -0.403558 -0.0896057 -0.910556 -0.390925 -0.0203702 -0.920197 -0.390965 -0.0203732 -0.92018 -0.00912248 -0.0478595 -0.998812 -0.391096 -0.706019 -0.590408 -0.304631 -0.688635 -0.658014 -0.304625 -0.688641 -0.65801 -0.221365 -0.654302 -0.723109 -0.221343 -0.654319 -0.7231 -0.143329 -0.603866 -0.784094 -0.143323 -0.603869 -0.784092 -0.0724928 -0.53855 -0.839469 -0.0725514 -0.538521 -0.839483 -0.0106459 -0.459939 -0.887887 -0.0105981 -0.459957 -0.887878 0.0408683 -0.370039 -0.928117 0.0407761 -0.370016 -0.92813 0.080515 -0.271009 -0.959203 0.0806412 -0.271027 -0.959188 0.107697 -0.165331 -0.98034 0.107646 -0.16533 -0.980346 0.120219 -0.065068 -0.990613 0.24953 -0.0623292 -0.966359 -0.0992638 -0.963141 -0.250014 0.01869 -0.939423 -0.342251 0.0187005 -0.939426 -0.342242 0.132279 -0.892578 -0.431054 0.132303 -0.892583 -0.431035 0.238716 -0.823757 -0.514237 0.238682 -0.823751 -0.514262 0.335296 -0.734643 -0.58981 0.335363 -0.734652 -0.589761 0.419815 -0.627455 -0.655787 0.419758 -0.627451 -0.655827 0.48996 -0.504797 -0.710718 0.489995 -0.504797 -0.710693 0.544217 -0.369714 -0.753087 0.544152 -0.369717 -0.753132 0.581056 -0.225534 -0.78199 0.581039 -0.225536 -0.782002 0.59972 -0.0758097 -0.796611 0.599796 -0.075798 -0.796554 0.601527 0 -0.798853 0.652461 -0.0015381 -0.757821 0.250016 0.00116081 -0.968241 0.312852 0 -0.949802 -0.00913295 0 -0.999958 -0.0745469 0.00077647 -0.997217 -0.391046 -0.00115907 -0.920371 -0.450362 0 -0.892846 0.16779 0.910363 -0.378267 0.543667 0.503117 -0.671788 0.624783 0.260939 -0.735906 -0.521667 0.166264 -0.836791 -0.52172 0.166168 -0.836777 -0.277341 0.472397 -0.836614 -0.277313 0.47243 -0.836605 0.00844064 0.705384 -0.708775 0.00846044 0.705398 -0.708761 -0.450253 0.0219837 -0.89263 -0.450271 0.0219798 -0.892621 -0.0744013 0.0624663 -0.99527 -0.0742595 0.0624906 -0.995279 0.311487 0.0932861 -0.94566 0.311331 0.0932631 -0.945714 0.648514 0.109835 -0.753237 0.648535 0.109838 -0.753218 -0.45798 0.0648501 -0.886594 -0.45803 0.0648258 -0.88657 -0.0961653 0.184315 -0.978151 -0.0963004 0.184265 -0.978148 0.278635 0.275119 -0.920148 0.278803 0.275166 -0.920083 0.347522 0.288122 -0.892308 0.597248 0.365171 -0.714104 0.494606 0.594171 -0.634292 0.362842 0.48707 -0.794423 0.214931 0.443209 -0.87027 0.215032 0.443252 -0.870224 -0.138935 0.296885 -0.944752 -0.139007 0.296843 -0.944755 -0.473072 0.104413 -0.874815 -0.473054 0.104427 -0.874823 -0.494652 0.138765 -0.857942 -0.494582 0.138849 -0.857968 -0.200307 0.394571 -0.896767 -0.200396 0.394496 -0.89678 0.123312 0.589054 -0.79863 0.123339 0.589069 -0.798615 0.427044 0.693685 -0.580029 0.427071 0.693693 -0.580001 0.291751 0.830659 -0.474223 0.0864731 0.768106 -0.634457 0.347966 0.780346 -0.519595 0.0855125 0.94548 -0.314254 -0.0741752 0.823383 -0.562618 -0.123976 0.786318 -0.605255 -0.123952 0.78634 -0.605231 -0.365971 0.526677 -0.767252 -0.365992 0.526645 -0.767265 -0.55291 0.185252 -0.812387 -0.552915 0.185238 -0.812387 -0.586658 0.19503 -0.786 -0.586657 0.195034 -0.785999 -0.461928 0.554478 -0.692225 -0.461928 0.55448 -0.692225 -0.267243 0.827832 -0.49323 -0.267223 0.827854 -0.493204 -0.032905 0.974852 -0.220409 -0.0329095 0.974851 -0.220415 -0.120167 0.980785 -0.153689 -0.159742 0.965923 -0.203657 -0.341988 0.831478 -0.437823 -0.374982 0.793337 -0.479588 -0.512148 0.555569 -0.655018 -0.488324 0.608827 -0.625195 -0.604536 0.195082 -0.772321 -0.594976 0.258759 -0.760952 -0.602944 0.258746 -0.754659 -0.606515 0.296156 -0.737856 -0.525788 0.608126 -0.594751 -0.218682 0.963144 -0.156625 -0.423342 0.791797 -0.440271 -0.618926 0.257208 -0.742142 -0.634736 0.25403 -0.72978 -0.642773 0.288848 -0.709513 -0.650318 0.249251 -0.717608 -0.665555 0.242966 -0.705694 -0.677706 0.274429 -0.682204 -0.740135 0.225894 -0.633382 -0.680357 0.235255 -0.694096 -0.694655 0.226006 -0.682917 -0.710414 0.253257 -0.656638 -0.708286 0.215379 -0.672267 -0.721261 0.203412 -0.662122 -0.733433 0.190168 -0.652619 -0.744749 0.175803 -0.643771 -0.766111 0.19294 -0.613064 -0.755178 0.160345 -0.635606 -0.764594 0.143894 -0.628244 -0.78768 0.155208 -0.596214 -0.772972 0.126581 -0.621684 -0.780253 0.10844 -0.615992 -0.804344 0.113679 -0.583188 -0.786365 0.0896623 -0.61122 -0.791322 0.0702988 -0.607345 -0.815704 0.0693425 -0.574299 -0.795089 0.0505534 -0.604383 -0.79873 0.0203705 -0.601345 -0.798707 0.0203732 -0.601376 -0.486343 0.704841 -0.516401 -0.565116 0.688615 -0.454371 -0.565108 0.688643 -0.454339 -0.648372 0.654299 -0.389239 -0.648374 0.654291 -0.38925 -0.726376 0.60384 -0.328262 -0.726376 0.603839 -0.328263 -0.797203 0.538518 -0.272885 -0.797203 0.538513 -0.272895 -0.859108 0.459932 -0.224491 -0.859109 0.459938 -0.224475 -0.910565 0.370034 -0.184243 -0.910562 0.370027 -0.184272 -0.950308 0.271012 -0.153193 -0.95031 0.271015 -0.153171 -0.977363 0.165325 -0.132018 -0.977363 0.165325 -0.132024 -0.991058 0.0555653 -0.121316 -0.991057 0.0555654 -0.121317 -0.218675 0.963148 -0.156611 -0.336633 0.939432 -0.0643813 -0.336636 0.939431 -0.0643857 -0.450219 0.892584 0.0244264 -0.450219 0.892584 0.0244274 -0.556633 0.823757 0.107629 -0.556632 0.823757 0.107631 -0.653252 0.734648 0.183178 -0.653259 0.734646 0.183163 -0.737709 0.627448 0.249188 -0.7377 0.627449 0.249212 -0.807899 0.504798 0.304104 -0.807903 0.504798 0.304093 -0.862121 0.369722 0.346486 -0.862121 0.369722 0.346487 -0.899027 0.225537 0.375344 -0.899032 0.225538 0.375331 -0.917715 0.0758003 0.389939 -0.917713 0.0757994 0.389946 -0.92036 0 0.391071 -0.92036 0 0.391071 -0.992591 0 -0.121505 -0.992591 0 -0.121505 -0.798872 0 -0.6015 -0.798872 0 -0.6015 -0.917713 -0.0758005 0.389946 -0.991057 -0.0555652 -0.121317 -0.798831 -0.0101876 -0.601469 -0.815704 -0.0693425 -0.574299 -0.821436 -0.0233116 -0.569823 -0.797599 -0.0304329 -0.60242 -0.795089 -0.0505534 -0.604383 -0.78768 -0.155208 -0.596214 -0.791322 -0.0702988 -0.607345 -0.786365 -0.0896624 -0.61122 -0.804344 -0.113679 -0.583188 -0.780253 -0.10844 -0.615992 -0.772972 -0.126581 -0.621685 -0.740135 -0.225894 -0.633382 -0.764594 -0.143894 -0.628244 -0.755178 -0.160345 -0.635606 -0.766111 -0.19294 -0.613064 -0.744749 -0.175803 -0.643771 -0.733433 -0.190168 -0.652619 -0.721261 -0.203412 -0.662122 -0.708286 -0.215379 -0.672267 -0.710414 -0.253257 -0.656638 -0.642773 -0.288846 -0.709514 -0.694655 -0.226006 -0.682917 -0.680356 -0.235256 -0.694097 -0.677706 -0.274428 -0.682205 -0.665555 -0.242965 -0.705695 -0.650317 -0.249249 -0.717609 -0.634736 -0.254028 -0.729781 -0.610886 -0.258764 -0.748238 -0.610898 -0.258706 -0.748248 -0.991058 -0.0555654 -0.121316 -0.977363 -0.165324 -0.132024 -0.977363 -0.165326 -0.132018 -0.950309 -0.271018 -0.153171 -0.950309 -0.271009 -0.153192 -0.910564 -0.370023 -0.184271 -0.910564 -0.370038 -0.184244 -0.859108 -0.45994 -0.224476 -0.859109 -0.459931 -0.224489 -0.797204 -0.538512 -0.272894 -0.797202 -0.538519 -0.272886 -0.726376 -0.603839 -0.328263 -0.726375 -0.603842 -0.32826 -0.648375 -0.654291 -0.389247 -0.64837 -0.654303 -0.389237 -0.565101 -0.688648 -0.454339 -0.565119 -0.688617 -0.454364 -0.478658 -0.705999 -0.52197 -0.478637 -0.706028 -0.521949 -0.917715 -0.0757993 0.389939 -0.899032 -0.225537 0.375332 -0.899027 -0.225539 0.375343 -0.862121 -0.369722 0.346487 -0.862121 -0.369722 0.346486 -0.807903 -0.504796 0.304094 -0.807898 -0.504799 0.304103 -0.737697 -0.627452 0.249211 -0.737711 -0.627445 0.249189 -0.65326 -0.734644 0.183164 -0.653251 -0.734649 0.183177 -0.556632 -0.823758 0.10763 -0.556636 -0.823756 0.107625 -0.450222 -0.892582 0.024422 -0.450219 -0.892584 0.024426 -0.336636 -0.939431 -0.0643853 -0.336637 -0.939431 -0.0643865 -0.218678 -0.963147 -0.156617 -0.218679 -0.963146 -0.156619 -0.159425 -0.965924 -0.203898 -0.159424 -0.965924 -0.203897 -0.435536 -0.707121 -0.557035 -0.435536 -0.707122 -0.557034 -0.594976 -0.258755 -0.760953 -0.594962 -0.258843 -0.760934 -0.615755 0 -0.787938 -0.615755 -1.92846e-05 -0.787938 -0.615877 -8.21868e-06 -0.787842 -0.615954 0 -0.787782 -0.615953 0 -0.787783 -0.615959 -0.000109224 -0.787778 -0.615937 -3.88992e-05 -0.787796 -0.615755 0 -0.787938 -0.615755 -1.40667e-06 -0.787938 -0.616707 -6.09771e-05 -0.787193 -0.61623 -5.22789e-05 -0.787566 -0.614229 0.000281274 -0.789128 -0.615525 0.000102824 -0.788118 -0.615822 0.000141349 -0.787885 -0.615989 -1.98687e-05 -0.787755 -0.616026 -5.81318e-05 -0.787726 -0.616412 -0.000377685 -0.787424 -0.616371 -0.000336651 -0.787456 -0.617912 -0.00140916 -0.786246 -0.615853 0.000100625 -0.787861 -0.615078 0.000525021 -0.788466 -0.615914 2.2611e-05 -0.787813 -0.614325 0.000743648 -0.789053 -0.615476 0.000163545 -0.788156 -0.616231 -8.71863e-05 -0.787566 -0.616236 -8.79511e-05 -0.787562 -0.615954 0 -0.787782 -0.615944 0 -0.78779 -0.615941 -6.96214e-05 -0.787792 -0.615941 -4.75443e-05 -0.787792 -0.616121 0.00170027 -0.78765 -0.616015 0.000444855 -0.787734 -0.616401 0.000366373 -0.787432 -0.615944 2.14286e-05 -0.78779 -0.615943 -2.77919e-05 -0.78779 -0.616121 0.00169998 -0.78765 -0.616014 0.00043705 -0.787735 -0.61606 -0.000712826 -0.787699 -0.616019 -0.000297836 -0.787731 -0.615917 0.00019701 -0.787811 -0.615655 0.00103544 -0.788015 -0.615932 5.16817e-05 -0.787799 -0.615597 0.000949789 -0.788061 -0.615817 0.000302956 -0.787889 -0.616372 -0.000901077 -0.787455 -0.616839 -0.0016651 -0.787088 -0.615674 0.000493654 -0.788001 -0.615746 0.000332133 -0.787945 -0.615958 -1.72808e-06 -0.787779 -0.615918 6.35614e-05 -0.78781 -0.615984 -2.46879e-05 -0.787758 -0.615973 -3.97689e-05 -0.787768 -0.616281 0.000248295 -0.787526 -0.61572 -0.00016824 -0.787965 -0.615173 -0.000468135 -0.788392 -0.615914 -2.26585e-05 -0.787813 -0.614325 -0.000743648 -0.789052 -0.615469 -0.000167101 -0.788161 -0.616237 8.82657e-05 -0.787561 -0.616531 0.000134873 -0.787331 -0.616063 9.22282e-06 -0.787697 -0.615824 -1.23641e-05 -0.787884 -0.615824 0 -0.787884 -0.615824 0 -0.787884 -0.615824 0 -0.787884 -0.615824 1.78597e-05 -0.787884 -0.616876 -0.000125585 -0.78706 -0.61683 -0.000383759 -0.787097 -0.615532 0.000183006 -0.788112 -0.615578 0.000303941 -0.788076 -0.615767 0.000155479 -0.787929 -0.615792 0.000196408 -0.787909 -0.61656 -0.000768303 -0.787308 -0.616412 -0.000917993 -0.787423 -0.615812 0.000281712 -0.787893 -0.615868 0.000316003 -0.787849 -0.615905 0.000183589 -0.78782 -0.615932 0.000191336 -0.787799 -0.61595 0 -0.787786 -0.615954 0 -0.787782 -0.615954 0 -0.787782 -0.615943 0 -0.787791 -0.615918 -6.35614e-05 -0.78781 -0.615933 -3.88802e-05 -0.787798 -0.615926 -5.0553e-05 -0.787804 -0.616627 0.00131915 -0.787254 -0.616252 0.000705768 -0.787549 -0.615865 -0.000193541 -0.787852 -0.616146 0.000426489 -0.787632 -0.616524 0.00154051 -0.787335 -0.615935 -4.18015e-05 -0.787797 -0.615637 -0.00109702 -0.788029 -0.615915 -0.000211355 -0.787813 -0.616033 0.000361572 -0.78772 -0.616079 0.000831963 -0.787684 -0.615922 -2.08081e-05 -0.787807 -0.615839 -0.00012107 -0.787872 -0.616074 0.000107133 -0.787688 -0.61632 0.000358957 -0.787495 -0.616887 0.000768213 -0.787052 -0.615918 -6.35614e-05 -0.78781 -0.615958 1.72808e-06 -0.787779 -0.61593 -4.12205e-05 -0.787801 -0.616627 0.00131915 -0.787254 -0.616396 0.000941132 -0.787436 -0.616695 0.00163511 -0.787201 -0.615824 -0.000283301 -0.787884 -0.615597 -0.000949751 -0.788061 -0.615932 -5.09209e-05 -0.787799 -0.615655 -0.00103544 -0.788015 -0.615917 -0.000197008 -0.787811 -0.616019 0.000297808 -0.787731 -0.61606 0.000714526 -0.787699 -0.616236 8.80359e-05 -0.787562 -0.616231 8.71851e-05 -0.787566 -0.615476 -0.000163485 -0.788155 -0.614325 -0.000743648 -0.789053 -0.615914 -2.2706e-05 -0.787813 -0.615078 -0.000525021 -0.788466 -0.615695 -0.000187543 -0.787985 -0.616281 0.000248295 -0.787526 -0.616324 0.000290383 -0.787493 -0.616874 0.000769673 -0.787062 -0.616356 0.000395285 -0.787468 -0.615989 1.98687e-05 -0.787755 -0.615823 -0.000141349 -0.787885 -0.615973 3.97689e-05 -0.787768 -0.615984 2.46879e-05 -0.787758 0.375276 0 -0.926913 0.375276 0 -0.926913 -0.0346028 0 -0.999401 -0.0346028 0 -0.999401 -0.438503 0 -0.89873 -0.438503 0 -0.89873 -0.229333 0.862514 -0.451083 -0.229361 0.862494 -0.451107 -0.080087 0.819243 -0.567827 -0.0800627 0.819257 -0.56781 0.0578895 0.734927 -0.675671 0.0579176 0.73494 -0.675655 0.177636 0.613755 -0.769253 0.177541 0.613725 -0.769299 0.273 0.461769 -0.843943 0.273084 0.461785 -0.843908 0.339518 0.286676 -0.895848 0.339468 0.286673 -0.895868 0.373541 0.0971739 -0.92251 0.3735 0.0971761 -0.922526 -0.444886 0.587034 -0.676364 -0.444851 0.587087 -0.67634 -0.343237 0.557651 -0.755787 -0.343279 0.557604 -0.755802 -0.249382 0.500201 -0.829221 -0.249425 0.500166 -0.829229 -0.167964 0.417693 -0.892928 -0.167876 0.417743 -0.892921 -0.102894 0.31431 -0.943728 -0.10297 0.314282 -0.943729 -0.0577612 0.195109 -0.979079 -0.057677 0.195124 -0.979081 -0.0344859 0.0661461 -0.997214 -0.034527 0.0661467 -0.997212 -0.583832 0.208066 -0.78476 -0.583817 0.208116 -0.784758 -0.547804 0.197683 -0.812916 -0.547797 0.197698 -0.812917 -0.514505 0.177348 -0.838947 -0.514485 0.177373 -0.838954 -0.485591 0.148127 -0.861545 -0.485628 0.148096 -0.86153 -0.462591 0.111429 -0.879541 -0.462629 0.111409 -0.879524 -0.4466 0.0691573 -0.892057 -0.446565 0.0691664 -0.892074 -0.438345 0.023452 -0.898501 -0.438382 0.0234517 -0.898483 0.375276 0 -0.926913 0.375276 0 -0.926913 -0.0346028 0 -0.999401 -0.0346028 0 -0.999401 -0.438503 0 -0.89873 -0.438503 0 -0.89873 -0.307348 0.866614 -0.393086 -0.307373 0.86659 -0.393119 -0.498076 0.588324 -0.637021 -0.498076 0.588323 -0.637021 -0.602466 0.208123 -0.770532 -0.602455 0.208212 -0.770517 -0.492947 -0.155502 -0.856051 -0.102967 -0.314275 -0.943731 0.3735 -0.0971714 -0.922527 0.339469 -0.286668 -0.89587 -0.229333 -0.862518 -0.451076 0.27308 -0.461793 -0.843904 0.273006 -0.461761 -0.843946 0.177549 -0.613717 -0.769303 -0.44488 -0.587034 -0.676368 -0.556959 -0.200341 -0.806015 -0.574908 -0.205541 -0.791981 -0.593059 -0.163436 -0.788397 -0.593279 -0.183159 -0.783883 -0.597846 -0.208118 -0.774124 -0.444855 -0.587092 -0.676334 -0.34324 -0.557656 -0.755782 -0.564788 -0.155211 -0.810509 -0.531896 -0.15825 -0.831892 -0.527157 -0.185046 -0.829375 -0.539553 -0.192631 -0.819619 -0.229357 -0.862493 -0.45111 -0.080084 -0.819242 -0.567829 -0.343274 -0.557602 -0.755806 -0.249386 -0.500204 -0.829218 -0.538615 -0.139289 -0.830959 -0.507345 -0.170076 -0.844793 -0.080065 -0.819258 -0.567808 0.0578919 -0.734925 -0.675673 -0.249422 -0.500162 -0.829232 -0.167957 -0.417686 -0.892933 -0.515956 -0.116285 -0.848686 -0.484986 -0.102197 -0.86853 -0.471358 -0.125222 -0.873007 -0.479946 -0.138922 -0.866229 0.0579132 -0.734941 -0.675654 0.177627 -0.613762 -0.76925 -0.167881 -0.417751 -0.892917 -0.102899 -0.314316 -0.943725 -0.497878 -0.0874912 -0.862823 -0.458704 -0.100834 -0.882849 -0.444594 -0.0577054 -0.893871 0.339516 -0.286682 -0.895847 -0.0576785 -0.195132 -0.979079 -0.0577581 -0.195101 -0.979081 -0.48531 -0.0543047 -0.872654 -0.450714 -0.0797707 -0.889097 0.37354 -0.0971786 -0.92251 -0.034527 -0.0661424 -0.997213 -0.0344867 -0.0661503 -0.997214 -0.438382 -0.0234475 -0.898483 -0.438346 -0.0234562 -0.8985 -0.711844 0.155411 -0.684928 -0.891039 0.314311 -0.327503 -0.985366 0.0971806 0.140035 -0.951295 0.286671 0.113394 -0.382472 0.862491 -0.331398 -0.884861 0.461785 0.0614449 -0.884863 0.461782 0.0614388 -0.789396 0.613742 -0.0132003 -0.549091 0.587037 -0.594884 -0.647893 0.200329 -0.734917 -0.629932 0.205533 -0.748961 -0.622073 0.163415 -0.765716 -0.617618 0.18323 -0.764836 -0.607035 0.208209 -0.766914 -0.549087 0.587045 -0.594879 -0.650691 0.55761 -0.515435 -0.650363 0.155247 -0.74359 -0.679026 0.158295 -0.716845 -0.677732 0.185003 -0.711656 -0.665263 0.192595 -0.721341 -0.382475 0.862489 -0.331401 -0.531745 0.819244 -0.214678 -0.650695 0.557597 -0.515444 -0.744584 0.500205 -0.44203 -0.676485 0.13922 -0.723178 -0.697443 0.169989 -0.696188 -0.531724 0.819265 -0.214647 -0.669683 0.734929 -0.106791 -0.744581 0.500225 -0.442011 -0.826062 0.417741 -0.378304 -0.699178 0.116294 -0.705426 -0.725854 0.102094 -0.68023 -0.733522 0.125224 -0.66803 -0.724876 0.13892 -0.674726 -0.66969 0.734921 -0.106804 -0.789397 0.613742 -0.0132007 -0.826061 0.417715 -0.378335 -0.891035 0.314295 -0.327529 -0.717273 0.087502 -0.691277 -0.74618 0.100855 -0.658061 -0.760231 0.0577212 -0.647084 -0.951295 0.28667 0.113391 -0.936261 0.195124 -0.292135 -0.936258 0.195119 -0.292147 -0.729873 0.0543271 -0.68142 -0.754171 0.0797907 -0.651813 -0.985366 0.097181 0.140037 -0.959452 0.0661464 -0.274002 -0.959451 0.0661462 -0.274003 -0.76621 0.0234416 -0.642162 -0.766234 0.0234494 -0.642134 -0.30737 -0.866594 -0.393114 -0.307343 -0.866619 -0.39308 -0.498076 -0.588324 -0.637021 -0.498076 -0.588323 -0.637021 -0.602454 -0.208211 -0.770517 -0.602467 -0.20812 -0.770532 -0.990052 0 0.140701 -0.990052 0 0.140701 -0.961558 0 -0.274603 -0.961558 0 -0.274603 -0.766421 0 -0.642339 -0.766421 0 -0.642339 -0.665263 -0.192595 -0.721341 -0.724877 -0.13892 -0.674726 -0.650692 -0.557612 -0.515431 -0.382469 -0.862494 -0.331393 -0.985366 -0.0971809 0.140035 -0.531742 -0.819245 -0.214681 -0.531728 -0.819264 -0.214644 -0.669684 -0.734928 -0.10679 -0.959452 -0.0661463 -0.274002 -0.760231 -0.0577212 -0.647084 -0.764332 -0.034912 -0.643877 -0.736325 -0.0184141 -0.676378 -0.749729 -0.0154661 -0.661564 -0.766408 -0.00584596 -0.642328 -0.959451 -0.0661463 -0.274003 -0.936261 -0.195122 -0.292135 -0.729873 -0.0543272 -0.68142 -0.730154 -0.0933884 -0.676871 -0.748225 -0.0955696 -0.656525 -0.754171 -0.0797907 -0.651813 -0.985366 -0.0971808 0.140037 -0.951295 -0.286671 0.113394 -0.936257 -0.19512 -0.292147 -0.89104 -0.314308 -0.327502 -0.717273 -0.0875019 -0.691277 -0.736364 -0.120635 -0.665744 -0.951295 -0.286671 0.113391 -0.884862 -0.461784 0.0614451 -0.891034 -0.314298 -0.32753 -0.826059 -0.417718 -0.378337 -0.699178 -0.116294 -0.705426 -0.685924 -0.152856 -0.711438 -0.701075 -0.166358 -0.693411 -0.711844 -0.155412 -0.684927 -0.884862 -0.461783 0.0614405 -0.789396 -0.613742 -0.0131981 -0.826064 -0.417739 -0.378302 -0.744583 -0.500223 -0.442011 -0.676485 -0.13922 -0.723178 -0.681855 -0.182451 -0.708368 -0.789397 -0.613741 -0.0132029 -0.669689 -0.734921 -0.106808 -0.744582 -0.500206 -0.442031 -0.650693 -0.557598 -0.515444 -0.650363 -0.155247 -0.74359 -0.647893 -0.200327 -0.734918 -0.382474 -0.862489 -0.331402 -0.54909 -0.587037 -0.594885 -0.549087 -0.587049 -0.594876 -0.620765 -0.208153 -0.755859 -0.620763 -0.208108 -0.755873 -0.766421 0 -0.642339 -0.766421 0 -0.642339 -0.961558 0 -0.274603 -0.961558 0 -0.274603 -0.990052 0 0.140701 -0.990052 0 0.140701 -0.724872 0.138928 -0.674729 -0.74618 0.100866 -0.658059 -0.826062 0.417745 -0.378299 -0.382453 0.862512 -0.331365 -0.531731 0.819258 -0.21466 -0.669687 0.734924 -0.1068 -0.985366 0.0971822 0.140035 -0.789397 0.613741 -0.013203 -0.789397 0.613741 -0.0132037 -0.884864 0.46178 0.0614345 -0.959452 0.0661461 -0.274002 -0.95945 0.0661443 -0.274009 -0.936259 0.195122 -0.292142 -0.752226 0.085034 -0.653395 -0.770626 0.0832071 -0.631832 -0.79094 0.087505 -0.605605 -0.760235 0.0577187 -0.647079 -0.766238 0.0234474 -0.642129 -0.76621 0.0234371 -0.642162 -0.736364 0.120634 -0.665744 -0.770665 0.140949 -0.621457 -0.89104 0.314303 -0.327508 -0.936256 0.195117 -0.292153 -0.951297 0.286669 0.113382 -0.985368 0.0971796 0.140021 -0.951295 0.286671 0.113391 -0.884861 0.461785 0.0614449 -0.891042 0.314311 -0.327495 -0.826062 0.417744 -0.378301 -0.741504 0.187306 -0.644273 -0.711837 0.155419 -0.684933 -0.669466 0.190054 -0.718119 -0.681858 0.182448 -0.708366 -0.669691 0.73492 -0.106807 -0.744586 0.500202 -0.442029 -0.744582 0.500227 -0.442007 -0.704977 0.224306 -0.672825 -0.697446 0.169987 -0.696185 -0.647888 0.200324 -0.734923 -0.531735 0.819254 -0.214665 -0.650686 0.557615 -0.515435 -0.650691 0.557597 -0.515447 -0.662874 0.250048 -0.705744 -0.6645 0.218074 -0.714761 -0.611633 0.208108 -0.763279 -0.382457 0.862509 -0.33137 -0.549094 0.587037 -0.594881 -0.549089 0.587048 -0.594875 -0.617318 0.26323 -0.741369 -0.629927 0.205529 -0.748966 -0.766421 0 -0.642339 -0.766421 0 -0.642339 -0.961558 0 -0.274603 -0.961558 0 -0.274603 -0.990052 0 0.140701 -0.990052 0 0.140701 -0.602455 0.208212 -0.770517 -0.602466 0.208121 -0.770533 -0.498076 0.588324 -0.637021 -0.498076 0.588323 -0.637021 -0.307371 0.866592 -0.393116 -0.307347 0.866615 -0.393085 -0.752226 -0.085034 -0.653395 -0.736364 -0.120634 -0.665744 -0.711837 -0.155419 -0.684933 -0.891039 -0.314305 -0.327508 -0.985366 -0.0971804 0.140035 -0.951297 -0.28667 0.113382 -0.884862 -0.461783 0.0614453 -0.884864 -0.461781 0.0614322 -0.789398 -0.61374 -0.0132058 -0.549093 -0.587037 -0.594882 -0.611633 -0.208108 -0.763279 -0.617318 -0.263231 -0.741369 -0.629927 -0.205529 -0.748966 -0.647888 -0.200324 -0.734923 -0.681858 -0.182447 -0.708366 -0.669466 -0.190054 -0.718119 -0.6645 -0.218074 -0.714761 -0.662874 -0.250048 -0.705744 -0.650688 -0.557614 -0.515434 -0.549091 -0.587048 -0.594874 -0.382453 -0.862512 -0.331365 -0.382456 -0.862509 -0.33137 -0.531732 -0.819257 -0.214659 -0.650689 -0.5576 -0.515447 -0.744583 -0.500205 -0.44203 -0.704977 -0.224306 -0.672825 -0.697446 -0.169987 -0.696185 -0.724872 -0.138927 -0.67473 -0.741504 -0.187306 -0.644273 -0.826062 -0.417745 -0.378299 -0.744585 -0.500225 -0.442005 -0.669688 -0.734923 -0.106802 -0.531736 -0.819253 -0.214668 -0.66969 -0.73492 -0.106807 -0.789397 -0.613741 -0.0132028 -0.826062 -0.417745 -0.3783 -0.891043 -0.31431 -0.327493 -0.770665 -0.140949 -0.621457 -0.74618 -0.100866 -0.658059 -0.760235 -0.0577187 -0.647079 -0.951295 -0.28667 0.113391 -0.936259 -0.195121 -0.292142 -0.936256 -0.195119 -0.292154 -0.79094 -0.087505 -0.605605 -0.770626 -0.0832071 -0.631832 -0.766369 -0.0116748 -0.642295 -0.985368 -0.0971814 0.140021 -0.959452 -0.066145 -0.274002 -0.95945 -0.0661453 -0.27401 -0.801344 -0.0296631 -0.597467 -0.764334 -0.0349213 -0.643874 -0.440589 0.0349039 -0.89703 -0.468549 0.120594 -0.875168 -0.493018 0.155436 -0.856021 -0.522961 0.18249 -0.832592 -0.0344081 0.0661447 -0.997217 -0.229365 0.862489 -0.451114 0.373499 0.0971874 -0.922525 0.373643 0.0971771 -0.922468 0.339569 0.286676 -0.895829 -0.444883 0.587034 -0.676365 -0.44489 0.587024 -0.67637 -0.343291 0.557583 -0.755813 -0.535448 0.190115 -0.822893 -0.533401 0.217943 -0.817303 -0.524994 0.250104 -0.813529 -0.556954 0.200339 -0.806019 -0.583825 0.208115 -0.784753 -0.583811 0.208156 -0.784752 -0.22932 0.862521 -0.451076 -0.0800367 0.819275 -0.567787 -0.343275 0.5576 -0.755807 -0.249386 0.500201 -0.82922 -0.482872 0.224368 -0.846459 -0.507389 0.169984 -0.844785 -0.0800661 0.819258 -0.567807 0.0578933 0.734924 -0.675673 -0.249351 0.500228 -0.829214 -0.167878 0.417755 -0.892915 -0.446355 0.187355 -0.875023 -0.480014 0.138846 -0.866204 0.0578526 0.734907 -0.675696 0.17755 0.613731 -0.769292 -0.167882 0.417753 -0.892915 -0.102895 0.314309 -0.943728 -0.417254 0.140926 -0.897797 -0.427297 0.0832042 -0.900275 -0.452736 0.0850367 -0.88758 -0.458703 0.100822 -0.882851 -0.444685 0.0576819 -0.893828 -0.396985 0.0874968 -0.913645 -0.0577614 0.19511 -0.979079 -0.10297 0.314284 -0.943728 0.273091 0.461796 -0.843899 0.177623 0.613752 -0.769258 0.273078 0.461793 -0.843905 0.339516 0.286673 -0.89585 -0.0576769 0.195123 -0.979082 -0.0344861 0.0661473 -0.997214 -0.386666 0.0296496 -0.921743 -0.438473 0.0117067 -0.898668 -0.602467 -0.208122 -0.770532 -0.602454 -0.208211 -0.770517 -0.498076 -0.588324 -0.637021 -0.498076 -0.588323 -0.637021 -0.307346 -0.866616 -0.393084 -0.30737 -0.866594 -0.393115 -0.438503 0 -0.89873 -0.438503 0 -0.89873 -0.0344836 0 -0.999405 -0.0344836 0 -0.999405 0.375276 0 -0.926913 0.375276 0 -0.926913 -0.535448 -0.190114 -0.822893 -0.507389 -0.169984 -0.844785 -0.480014 -0.138845 -0.866203 -0.458703 -0.100822 -0.882851 -0.24938 -0.5002 -0.829222 -0.229359 -0.862489 -0.451119 -0.0800405 -0.819277 -0.567785 0.3735 -0.0971684 -0.922527 0.057887 -0.734926 -0.675672 0.0578561 -0.734904 -0.675699 0.177556 -0.613724 -0.769296 -0.0344081 -0.0661544 -0.997216 -0.0344844 -0.0661377 -0.997214 -0.0576787 -0.195133 -0.979079 -0.452736 -0.0850368 -0.88758 -0.427297 -0.0832042 -0.900275 -0.396985 -0.0874968 -0.913645 -0.444685 -0.0576819 -0.893828 -0.438438 -0.023438 -0.898456 -0.438382 -0.023453 -0.898483 0.373641 -0.097196 -0.922467 0.339567 -0.286682 -0.895828 -0.0577577 -0.1951 -0.979081 -0.102967 -0.314275 -0.943731 -0.417254 -0.140926 -0.897797 -0.468549 -0.120594 -0.875168 0.339519 -0.286667 -0.895851 0.273079 -0.461792 -0.843905 -0.102899 -0.314318 -0.943725 -0.167881 -0.417753 -0.892916 -0.446355 -0.187355 -0.875023 -0.493018 -0.155436 -0.856021 0.273089 -0.461797 -0.843899 0.177616 -0.613759 -0.769255 -0.167879 -0.417755 -0.892915 -0.249354 -0.500232 -0.829211 -0.482872 -0.224368 -0.846459 -0.522962 -0.182489 -0.832592 -0.556954 -0.200339 -0.806019 -0.0800644 -0.819255 -0.567812 -0.343288 -0.557582 -0.755814 -0.343276 -0.557603 -0.755805 -0.524994 -0.250104 -0.813529 -0.533401 -0.217943 -0.817303 -0.593204 -0.208199 -0.777665 -0.229326 -0.862522 -0.45107 -0.444884 -0.587034 -0.676365 -0.444889 -0.587023 -0.676371 -0.570565 -0.263323 -0.777893 -0.574904 -0.205538 -0.791985 -0.62479 0.59905 0.500776 -0.637342 0.598915 0.484867 -0.739122 0.453375 0.498147 -0.646659 0.561336 0.516463 -0.683782 0.53415 0.497117 -0.697313 0.499846 0.513721 -0.713124 0.471756 0.518556 -0.694942 0.424429 0.580444 0.671226 0.411113 -0.6168 0.6864 0.412824 -0.598692 0.565825 0.540354 -0.622784 0.668271 0.444509 -0.596511 0.63406 0.471744 -0.61272 0.62656 0.499846 -0.597977 0.607863 0.534156 -0.58752 0.627043 0.576289 -0.524125 -0.636067 0.599459 0.485868 -0.665301 0.579261 0.47099 -0.674332 0.566409 0.473769 -0.71789 0.565884 0.405475 -0.717888 0.565885 0.405475 -0.763166 0.565885 0.312015 -0.763166 0.565884 0.312014 -0.796335 0.565884 0.213605 -0.796335 0.565884 0.213605 -0.81687 0.565883 0.111807 -0.81687 0.565882 0.111806 -0.824445 0.565882 0.00823278 -0.824445 0.565883 0.00823321 -0.81894 0.565882 -0.0954702 -0.818941 0.565881 -0.0954705 -0.800443 0.565881 -0.19766 -0.800442 0.565883 -0.197659 -0.769245 0.565884 -0.296711 -0.769246 0.565882 -0.296712 -0.725845 0.565882 -0.391059 -0.725843 0.565885 -0.391057 -0.670927 0.565885 -0.479197 -0.670928 0.565882 -0.4792 -0.605368 0.565882 -0.559738 -0.605368 0.565885 -0.559736 -0.530203 0.565885 -0.631395 -0.530204 0.565875 -0.631403 -0.446628 0.565874 -0.693044 -0.446628 0.565883 -0.693037 -0.355963 0.565883 -0.743684 -0.355963 0.565883 -0.743684 -0.259653 0.565883 -0.782532 -0.259654 0.565889 -0.782528 -0.159225 0.565889 -0.80896 -0.159225 0.565888 -0.808961 -0.0562719 0.565888 -0.822559 -0.0562676 0.565878 -0.822567 0.0475776 0.565878 -0.823115 0.0475785 0.565877 -0.823116 0.150674 0.565877 -0.810605 0.150669 0.565885 -0.8106 0.251376 0.565885 -0.785228 0.251379 0.565881 -0.785231 0.348086 0.565881 -0.747405 0.348085 0.565883 -0.747405 0.439283 0.565883 -0.697716 0.439284 0.565881 -0.697716 0.523505 0.565881 -0.636962 0.523504 0.565883 -0.636962 0.585344 0.566356 -0.580183 0.576677 0.574636 -0.580721 0.588323 0.599003 -0.543206 0.591489 0.600079 -0.538559 0.67952 0.398608 -0.615925 0.641745 0.43043 -0.634739 0.636703 0.441066 -0.632511 0.569989 0.440613 -0.693522 0.56999 0.440613 -0.693522 0.47829 0.440613 -0.75967 0.47829 0.440613 -0.75967 0.378997 0.440613 -0.81377 0.378992 0.44062 -0.813768 0.273693 0.44062 -0.854954 0.273702 0.440605 -0.854959 0.164054 0.440605 -0.882583 0.164047 0.440618 -0.882578 0.0517994 0.440618 -0.896199 0.0518031 0.44061 -0.896203 -0.0612647 0.44061 -0.895606 -0.0612639 0.440608 -0.895607 -0.173366 0.440608 -0.8808 -0.173365 0.440605 -0.880802 -0.282709 0.440606 -0.852023 -0.282711 0.440616 -0.852017 -0.387574 0.440615 -0.809719 -0.387573 0.440609 -0.809723 -0.486284 0.440609 -0.75458 -0.486285 0.44062 -0.754573 -0.577283 0.440619 -0.687458 -0.577283 0.440603 -0.687469 -0.659124 0.440604 -0.609445 -0.659124 0.440612 -0.60944 -0.730504 0.440612 -0.521752 -0.730503 0.440615 -0.52175 -0.790297 0.440614 -0.425781 -0.790297 0.440613 -0.425782 -0.837552 0.440613 -0.323059 -0.837552 0.440613 -0.323059 -0.871519 0.440612 -0.21521 -0.871519 0.440613 -0.21521 -0.891659 0.440613 -0.103948 -0.891659 0.440612 -0.103948 -0.897653 0.440612 0.00896456 -0.897653 0.440612 0.00896429 -0.889406 0.440611 0.121734 -0.889405 0.440613 0.121734 -0.867047 0.440612 0.232573 -0.867047 0.440612 0.232573 -0.830934 0.440612 0.33972 -0.830933 0.440613 0.33972 -0.781637 0.440613 0.44148 -0.781635 0.440616 0.44148 -0.731957 0.441039 0.519349 -0.737427 0.434094 0.517458 -0.725479 0.401932 0.558687 -0.722021 0.40051 0.564161 -0.786217 0.0675079 0.614252 -0.780185 0.0647734 0.622187 -0.776659 0.069949 0.626025 -0.780419 0.0725118 0.621039 -0.777143 0.081087 0.624078 -0.776501 0.0837768 0.624522 -0.780868 0.0915966 0.617944 -0.788434 0.0679268 0.611358 -0.780329 0.0763602 0.62069 -0.780376 0.0763862 0.620627 -0.791151 0.0763302 0.606839 -0.791279 0.0763719 0.606668 -0.812382 0.0762037 0.578125 0.709807 0.0762091 -0.700262 0.745969 0.0801392 -0.661142 0.739823 0.0852931 -0.667373 0.746327 0.0880612 -0.659728 0.73772 0.0846029 -0.669785 0.734334 0.0763777 -0.674477 0.7345 0.0763305 -0.674302 0.745533 0.0611293 -0.663659 0.750126 0.0828441 -0.656085 0.746217 0.0763599 -0.661309 0.746268 0.0763867 -0.661248 0.749719 0.0716071 -0.65787 0.750348 0.0689467 -0.657437 0.709882 0.0763278 -0.700172 0.633659 0.0762395 -0.769847 0.633657 0.0762423 -0.769848 0.531797 0.0762426 -0.843433 0.531798 0.0762396 -0.843432 0.421496 0.0762397 -0.90362 0.421501 0.0762321 -0.903618 0.304498 0.0762317 -0.949458 0.304497 0.0762335 -0.949458 0.182671 0.0762334 -0.980214 0.182665 0.0762426 -0.980214 0.0579322 0.0762426 -0.995405 0.0579352 0.076238 -0.995405 -0.067724 0.076238 -0.994787 -0.0677241 0.0762381 -0.994787 -0.192302 0.0762381 -0.97837 -0.192304 0.0762424 -0.978369 -0.313825 0.0762423 -0.946415 -0.313824 0.0762413 -0.946415 -0.430365 0.0762411 -0.89943 -0.430367 0.0762454 -0.899428 -0.540074 0.0762449 -0.838157 -0.540067 0.076232 -0.838162 -0.641198 0.0762325 -0.763579 -0.641201 0.0762402 -0.763576 -0.732146 0.07624 -0.676867 -0.732145 0.0762375 -0.676869 -0.811462 0.0762376 -0.579411 -0.811462 0.0762373 -0.579411 -0.877893 0.0762374 -0.472749 -0.877893 0.0762366 -0.47275 -0.930379 0.0762371 -0.358583 -0.93038 0.07624 -0.358582 -0.968091 0.0762395 -0.238719 -0.968091 0.076238 -0.23872 -0.990428 0.0762379 -0.115064 -0.990428 0.0762369 -0.115064 -0.997035 0.0762376 0.0104177 -0.997035 0.0762378 0.0104178 -0.987808 0.0762374 0.135733 -0.987808 0.0762394 0.135735 -0.962892 0.0762404 0.258895 -0.962892 0.0762387 0.258894 -0.922684 0.076239 0.377944 -0.922684 0.0762378 0.377944 -0.867822 0.0762377 0.490992 -0.867822 0.0762378 0.490992 -0.812444 0.0763266 0.578021 -0.807571 0.134691 0.574185 -0.775415 0.124316 0.619094 -0.776561 0.131501 0.616166 -0.779165 0.124307 0.614369 -0.782845 0.127607 0.608991 -0.786631 0.134899 0.602507 -0.786892 0.134984 0.602146 -0.775608 0.150278 0.613065 -0.784468 0.126298 0.607172 -0.772305 0.128552 0.622109 -0.77573 0.134959 0.616465 -0.775804 0.135 0.616364 -0.772322 0.1397 0.61968 -0.771535 0.142438 0.620037 0.705025 0.134689 -0.696275 0.740829 0.138753 -0.657206 0.734286 0.143867 -0.66342 0.740776 0.146651 -0.655549 0.732253 0.14334 -0.665777 0.729134 0.134983 -0.670927 0.729437 0.134901 -0.670614 0.741237 0.119758 -0.660473 0.744862 0.141426 -0.652058 0.741203 0.134958 -0.657574 0.741286 0.135002 -0.657472 0.745011 0.130205 -0.654221 0.745761 0.127561 -0.653888 0.705158 0.134903 -0.696099 0.629553 0.134747 -0.765183 0.629554 0.134747 -0.765183 0.528333 0.134747 -0.838277 0.52833 0.134751 -0.838278 0.41872 0.134751 -0.898062 0.418722 0.134749 -0.898062 0.30246 0.134749 -0.943589 0.302463 0.134743 -0.943589 0.1814 0.134743 -0.974135 0.181402 0.13474 -0.974135 0.0574604 0.13474 -0.989214 0.0574554 0.134747 -0.989213 -0.0673927 0.134747 -0.988586 -0.0673899 0.134743 -0.988586 -0.191176 0.134743 -0.972264 -0.191178 0.134747 -0.972262 -0.311923 0.134747 -0.940504 -0.311923 0.134747 -0.940504 -0.42772 0.134747 -0.893812 -0.427715 0.134739 -0.893815 -0.536722 0.134739 -0.832932 -0.536726 0.134749 -0.832927 -0.637207 0.134748 -0.758821 -0.637206 0.134744 -0.758824 -0.727572 0.134744 -0.672669 -0.727574 0.134751 -0.672665 -0.806388 0.13475 -0.575831 -0.806386 0.134742 -0.575836 -0.872398 0.134742 -0.469858 -0.872399 0.134746 -0.469855 -0.924559 0.134746 -0.356418 -0.924559 0.134747 -0.356417 -0.96204 0.134746 -0.237322 -0.96204 0.134745 -0.237323 -0.984247 0.134745 -0.114458 -0.984247 0.134745 -0.114458 -0.990827 0.134746 0.0102227 -0.990828 0.134746 0.0102224 -0.981676 0.134746 0.134741 -0.981676 0.134747 0.134742 -0.956939 0.134748 0.257122 -0.956939 0.134745 0.25712 -0.917009 0.134744 0.375417 -0.917008 0.134747 0.375418 -0.862519 0.134747 0.487755 -0.862517 0.134749 0.487756 -0.807674 0.134906 0.573988 -0.723559 -0.411193 0.554421 -0.711209 -0.540365 0.449652 -0.632732 -0.600074 0.48945 -0.624664 -0.576282 0.526967 -0.683782 -0.53415 0.497117 -0.697313 -0.499845 0.513721 -0.713123 -0.471757 0.518556 -0.70307 -0.444509 0.555072 -0.708358 -0.412782 0.572573 0.61016 -0.587842 -0.531175 0.618484 -0.453373 -0.641819 0.617751 -0.555259 -0.556841 0.607863 -0.534156 -0.58752 0.62656 -0.499845 -0.597978 0.634059 -0.471745 -0.612719 0.691827 -0.424456 -0.584134 -0.636759 -0.598998 0.485529 -0.671692 -0.574635 0.467573 -0.672662 -0.566351 0.476207 -0.717892 -0.565878 0.405479 -0.717892 -0.565879 0.405478 -0.763168 -0.56588 0.312019 -0.763167 -0.565882 0.312017 -0.796336 -0.565882 0.213606 -0.796337 -0.56588 0.213607 -0.816871 -0.565881 0.111808 -0.816871 -0.565881 0.111808 -0.824446 -0.565881 0.00823528 -0.824445 -0.565882 0.00823496 -0.81894 -0.565883 -0.0954684 -0.818939 -0.565884 -0.0954687 -0.800441 -0.565884 -0.197658 -0.800445 -0.56588 -0.197657 -0.769249 -0.565879 -0.296711 -0.769246 -0.565883 -0.296712 -0.725846 -0.565883 -0.391054 -0.725845 -0.565884 -0.391054 -0.670927 -0.565885 -0.479198 -0.670931 -0.565881 -0.479198 -0.60537 -0.565881 -0.559737 -0.605368 -0.565884 -0.559736 -0.530203 -0.565884 -0.631395 -0.530204 -0.565884 -0.631395 -0.446628 -0.565884 -0.693036 -0.446629 -0.565883 -0.693036 -0.355964 -0.565883 -0.743684 -0.355964 -0.565883 -0.743684 -0.259655 -0.565883 -0.782532 -0.259659 -0.565877 -0.782534 -0.159227 -0.565877 -0.808968 -0.159227 -0.565876 -0.808969 -0.0562732 -0.565876 -0.822568 -0.0562724 -0.565878 -0.822567 0.0475784 -0.565878 -0.823115 0.0475777 -0.565876 -0.823116 0.15067 -0.565876 -0.810606 0.150673 -0.565885 -0.8106 0.251373 -0.565885 -0.78523 0.251372 -0.56588 -0.785234 0.348085 -0.56588 -0.747406 0.348086 -0.565882 -0.747405 0.43928 -0.565882 -0.697719 0.439279 -0.56588 -0.69772 0.523505 -0.56588 -0.636964 0.523504 -0.565882 -0.636962 0.583239 -0.566407 -0.582251 0.578938 -0.579264 -0.573833 0.589431 -0.601397 -0.539344 0.59046 -0.592662 -0.547822 -0.724137 -0.39857 0.56282 -0.736149 -0.430423 0.522322 -0.73308 -0.441069 0.517737 -0.781635 -0.440615 0.44148 -0.781636 -0.440612 0.441483 -0.830932 -0.440612 0.339724 -0.830932 -0.440612 0.339724 -0.867047 -0.440612 0.232575 -0.867045 -0.440616 0.232573 -0.889404 -0.440614 0.121736 -0.889404 -0.440614 0.121736 -0.897652 -0.440614 0.00896595 -0.897653 -0.440612 0.00896654 -0.891659 -0.440612 -0.103946 -0.89166 -0.440611 -0.103946 -0.871521 -0.44061 -0.215209 -0.871519 -0.440613 -0.21521 -0.837553 -0.440613 -0.323057 -0.837553 -0.440613 -0.323057 -0.790298 -0.440613 -0.42578 -0.790301 -0.440609 -0.42578 -0.730508 -0.440608 -0.52175 -0.730505 -0.440613 -0.52175 -0.659125 -0.440613 -0.609438 -0.659124 -0.440614 -0.609438 -0.577282 -0.440614 -0.687462 -0.577285 -0.440609 -0.687463 -0.486289 -0.440609 -0.754577 -0.486289 -0.440609 -0.754577 -0.387575 -0.440609 -0.809721 -0.387572 -0.440616 -0.80972 -0.282713 -0.440616 -0.852016 -0.282711 -0.440619 -0.852015 -0.173365 -0.440619 -0.880795 -0.173364 -0.440622 -0.880794 -0.0612643 -0.440622 -0.8956 -0.0612698 -0.44061 -0.895605 0.0517996 -0.44061 -0.896203 0.0518028 -0.440618 -0.896199 0.164047 -0.440618 -0.882578 0.164047 -0.440619 -0.882578 0.273693 -0.440618 -0.854955 0.273694 -0.44062 -0.854954 0.378995 -0.440619 -0.813767 0.378994 -0.440612 -0.813772 0.478286 -0.440612 -0.759673 0.478286 -0.440612 -0.759673 0.569989 -0.440613 -0.693523 0.569989 -0.440613 -0.693522 0.638095 -0.441035 -0.631128 0.637179 -0.434096 -0.636838 0.675718 -0.401935 -0.617943 0.680464 -0.400527 -0.613634 -0.813632 -0.0539936 0.578867 -0.787752 -0.0707084 0.611921 -0.784678 -0.0781122 0.614963 -0.785882 -0.0763391 0.613647 -0.809666 -0.111544 0.576193 -0.782606 -0.0611801 0.619504 -0.787294 -0.08469 0.610734 0.746599 -0.0725181 -0.66131 0.750936 -0.0699102 -0.656665 0.747754 -0.064717 -0.660814 0.744182 -0.0792766 -0.663256 0.739457 -0.0749844 -0.669015 0.74029 -0.0763388 -0.667939 0.720763 -0.0613929 -0.690458 0.703797 -0.131474 -0.698129 0.707517 -0.111546 -0.697838 0.740992 -0.0674474 -0.668118 0.709801 -0.0763282 -0.700255 0.633657 -0.0762395 -0.769848 0.633655 -0.0762347 -0.76985 0.531798 -0.0762343 -0.843433 0.531801 -0.0762396 -0.843431 0.421495 -0.0762397 -0.90362 0.421496 -0.0762409 -0.90362 0.304497 -0.076241 -0.949457 0.304498 -0.0762429 -0.949457 0.182665 -0.0762431 -0.980214 0.182665 -0.0762426 -0.980215 0.0579352 -0.0762426 -0.995405 0.0579323 -0.076238 -0.995405 -0.0677241 -0.076238 -0.994787 -0.067724 -0.0762381 -0.994787 -0.192305 -0.0762381 -0.978369 -0.192302 -0.0762424 -0.97837 -0.313824 -0.0762423 -0.946415 -0.31383 -0.076232 -0.946414 -0.430368 -0.0762324 -0.899429 -0.430365 -0.0762368 -0.89943 -0.540072 -0.076237 -0.838159 -0.54007 -0.0762402 -0.83816 -0.641202 -0.0762401 -0.763576 -0.641202 -0.0762403 -0.763576 -0.732145 -0.07624 -0.676868 -0.732147 -0.0762376 -0.676867 -0.811462 -0.0762376 -0.579411 -0.811462 -0.0762373 -0.579411 -0.877893 -0.0762374 -0.472749 -0.877894 -0.0762355 -0.472748 -0.93038 -0.076236 -0.358581 -0.930379 -0.07624 -0.358583 -0.968091 -0.0762395 -0.238718 -0.968092 -0.0762369 -0.238717 -0.990428 -0.076238 -0.115064 -0.990428 -0.0762382 -0.115064 -0.997035 -0.0762388 0.0104186 -0.997035 -0.0762378 0.0104192 -0.987808 -0.0762373 0.135735 -0.987808 -0.0762381 0.135734 -0.962892 -0.0762378 0.258896 -0.962892 -0.0762388 0.258896 -0.922684 -0.076239 0.377944 -0.922684 -0.0762378 0.377945 -0.867821 -0.0762377 0.490993 -0.867821 -0.0762378 0.490993 -0.806024 -0.0762881 0.586946 -0.80931 -0.131446 0.572485 -0.77762 -0.0716165 0.624643 -0.777308 -0.0690023 0.625325 -0.807697 -0.134689 0.574008 -0.775453 -0.138737 0.615975 -0.7804 -0.143853 0.608508 -0.773735 -0.146651 0.616302 -0.782333 -0.143093 0.606201 -0.786892 -0.134984 0.602146 -0.786631 -0.134899 0.602507 -0.778705 -0.119798 0.615847 -0.771015 -0.14145 0.620908 -0.775834 -0.134959 0.616335 -0.775752 -0.135 0.616429 -0.773229 -0.13027 0.620601 -0.773026 -0.127566 0.621415 0.736333 -0.126113 -0.664763 0.743343 -0.123373 -0.657435 0.74631 -0.12852 -0.653072 0.741833 -0.131104 -0.657645 0.743892 -0.139701 -0.653536 0.744104 -0.142399 -0.652711 0.737927 -0.150259 -0.657941 0.733678 -0.126402 -0.667637 0.741319 -0.134959 -0.657443 0.741228 -0.135001 -0.657538 0.729437 -0.134901 -0.670614 0.729135 -0.134983 -0.670927 0.70518 -0.134691 -0.696117 -0.807546 -0.134905 0.57417 -0.862518 -0.134749 0.487756 -0.862517 -0.134747 0.487758 -0.917008 -0.134747 0.375418 -0.917008 -0.134744 0.37542 -0.956939 -0.134745 0.257123 -0.956939 -0.134747 0.257121 -0.981676 -0.134746 0.134743 -0.981676 -0.134746 0.134743 -0.990827 -0.134746 0.0102242 -0.990827 -0.134746 0.010224 -0.984248 -0.134745 -0.114457 -0.984248 -0.134745 -0.114457 -0.962041 -0.134745 -0.237321 -0.96204 -0.134748 -0.237322 -0.924559 -0.134748 -0.356417 -0.92456 -0.134745 -0.356415 -0.8724 -0.134745 -0.469853 -0.872399 -0.134748 -0.469855 -0.806387 -0.134748 -0.575833 -0.806388 -0.134745 -0.575831 -0.727575 -0.134745 -0.672665 -0.727572 -0.134751 -0.672668 -0.637208 -0.134752 -0.758821 -0.637209 -0.134748 -0.75882 -0.536721 -0.134749 -0.83293 -0.536727 -0.134739 -0.832928 -0.42772 -0.134739 -0.893812 -0.427721 -0.134739 -0.893812 -0.311929 -0.134738 -0.940503 -0.311924 -0.134747 -0.940504 -0.191176 -0.134747 -0.972263 -0.191178 -0.134743 -0.972263 -0.0673928 -0.134743 -0.988586 -0.0673899 -0.134747 -0.988586 0.0574541 -0.134747 -0.989213 0.0574554 -0.134749 -0.989213 0.1814 -0.134749 -0.974134 0.181402 -0.134753 -0.974133 0.302465 -0.134753 -0.943587 0.302458 -0.134739 -0.943591 0.418715 -0.13474 -0.898066 0.418721 -0.134751 -0.898062 0.528332 -0.134751 -0.838277 0.52833 -0.134747 -0.838278 0.629549 -0.134747 -0.765187 0.629549 -0.134747 -0.765187 0.705007 -0.134903 -0.696251 -0.787615 -0.0266622 0.61559 -0.781382 -0.0294199 0.62336 -0.814626 0.0113411 0.579876 -0.802617 -0.00235138 0.59649 -0.78094 -0.0200147 0.624285 -0.778238 -0.0242185 0.627503 -0.782355 -0.0215197 0.622461 0.751495 -0.0224682 -0.659356 0.751939 -0.0251656 -0.658752 0.746587 -0.0329949 -0.664469 0.740449 -0.00947597 -0.672045 0.749915 -0.0200146 -0.661231 0.726281 -0.00234712 -0.687394 0.721183 0.00258757 -0.69274 -0.80677 -0.0244974 0.590357 -0.870055 -0.0244835 0.492347 -0.870054 -0.02448 0.492348 -0.925072 -0.0244807 0.379001 -0.925072 -0.0244785 0.379001 -0.965396 -0.024479 0.259638 -0.965396 -0.0244821 0.259637 -0.990386 -0.024482 0.136147 -0.990386 -0.0244835 0.136147 -0.999645 -0.024483 0.0104966 -0.999645 -0.0244827 0.0104967 -0.993026 -0.024483 -0.115321 -0.993026 -0.0244855 -0.115322 -0.970635 -0.0244867 -0.239308 -0.970635 -0.0244838 -0.239307 -0.932826 -0.0244848 -0.359494 -0.932826 -0.0244848 -0.359494 -0.880202 -0.0244851 -0.473968 -0.880202 -0.0244832 -0.473967 -0.813594 -0.0244834 -0.580917 -0.813596 -0.0244757 -0.580915 -0.734068 -0.0244746 -0.678635 -0.734066 -0.0244839 -0.678637 -0.642882 -0.024484 -0.765574 -0.642882 -0.0244827 -0.765574 -0.541477 -0.0244827 -0.840359 -0.541478 -0.0244772 -0.840358 -0.431483 -0.0244769 -0.901789 -0.431478 -0.0244919 -0.901791 -0.314625 -0.0244923 -0.9489 -0.31463 -0.0244736 -0.948899 -0.192778 -0.0244733 -0.980937 -0.192772 -0.0244926 -0.980938 -0.0678606 -0.0244927 -0.997394 -0.0678641 -0.0244814 -0.997394 0.0581265 -0.0244814 -0.998009 0.0581268 -0.0244824 -0.998009 0.183193 -0.0244824 -0.982772 0.183196 -0.0244926 -0.982771 0.305354 -0.0244923 -0.951924 0.305351 -0.0244837 -0.951925 0.422658 -0.0244836 -0.905958 0.422657 -0.0244798 -0.905959 0.533255 -0.02448 -0.8456 0.533255 -0.0244807 -0.8456 0.635375 -0.0244809 -0.771815 0.635375 -0.02448 -0.771815 0.711839 -0.0245087 -0.701915 -0.779366 0.0224688 0.626166 -0.77884 0.0252093 0.626716 -0.783534 0.0330213 0.620471 -0.789976 0.00934823 0.613066 -0.78094 0.0200147 0.624285 -0.802617 0.00235138 0.59649 -0.80701 -0.00259282 0.590532 0.742513 0.0266771 -0.669301 0.749045 0.0294167 -0.661866 0.712007 -0.0113331 -0.702081 0.726281 0.00234712 -0.687394 0.749915 0.0200146 -0.661231 0.752599 0.0241904 -0.658035 0.748411 0.0215336 -0.662885 0.720969 0.0244936 -0.692534 0.635375 0.02448 -0.771815 0.635375 0.0244808 -0.771815 0.533255 0.0244807 -0.8456 0.533255 0.02448 -0.8456 0.422658 0.0244799 -0.905959 0.422657 0.0244836 -0.905959 0.305354 0.0244837 -0.951924 0.305351 0.0244923 -0.951925 0.183193 0.0244926 -0.982772 0.183196 0.0244824 -0.982772 0.0581265 0.0244824 -0.998009 0.0581268 0.0244814 -0.998009 -0.0678606 0.0244814 -0.997394 -0.0678641 0.0244927 -0.997394 -0.192778 0.0244925 -0.980937 -0.192773 0.0244733 -0.980938 -0.314625 0.0244737 -0.948901 -0.31463 0.0244923 -0.948898 -0.431483 0.0244918 -0.901789 -0.431479 0.0244769 -0.901791 -0.541477 0.0244772 -0.840359 -0.541478 0.0244827 -0.840358 -0.642882 0.0244827 -0.765574 -0.642882 0.024484 -0.765574 -0.734068 0.0244838 -0.678635 -0.734066 0.0244745 -0.678637 -0.813594 0.0244758 -0.580917 -0.813596 0.0244834 -0.580915 -0.880202 0.0244833 -0.473968 -0.880202 0.024485 -0.473967 -0.932826 0.0244849 -0.359494 -0.932826 0.0244848 -0.359494 -0.970635 0.0244839 -0.239308 -0.970635 0.0244867 -0.239307 -0.993026 0.0244855 -0.115321 -0.993026 0.024483 -0.115322 -0.999645 0.0244827 0.0104966 -0.999645 0.024483 0.0104967 -0.990386 0.0244836 0.136147 -0.990386 0.024482 0.136147 -0.965396 0.0244821 0.259638 -0.965396 0.024479 0.259637 -0.925073 0.0244784 0.379001 -0.925072 0.0244806 0.379001 -0.870055 0.0244799 0.492347 -0.870054 0.0244835 0.492348 -0.814433 0.0245125 0.579739 -0.621161 -0.258804 -0.739716 -0.621162 -0.258826 -0.739708 -0.454717 -0.707116 -0.541497 -0.454724 -0.707097 -0.541517 -0.24707 -0.923248 -0.294228 -0.247698 -0.922774 -0.295184 -0.0850956 -0.991229 -0.101115 -0.0858141 -0.991056 -0.102194 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.125454 -0.980786 -0.1494 -0.125451 -0.980787 -0.149394 -0.357285 -0.831455 -0.425476 -0.357273 -0.831472 -0.425454 -0.53469 -0.555593 -0.636729 -0.534704 -0.555544 -0.636759 -0.630714 -0.195085 -0.751094 -0.630714 -0.195096 -0.751091 -0.643071 -3.19577e-07 -0.765807 -0.643071 -1.85285e-06 -0.765806 -0.63071 0.195126 -0.751086 -0.630716 0.195103 -0.751087 -0.5347 0.555563 -0.636747 -0.534696 0.555569 -0.636744 -0.35727 0.831472 -0.425456 -0.357276 0.831467 -0.425461 -0.12546 0.980785 -0.149404 -0.125457 0.980785 -0.149401 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.125463 0.980784 -0.149408 -0.125458 0.980785 -0.149404 -0.357265 0.831473 -0.425457 -0.357281 0.83146 -0.425469 -0.534684 0.555596 -0.63673 -0.534688 0.555591 -0.636732 -0.630722 0.195056 -0.751095 -0.630717 0.195075 -0.751094 -0.643071 5.6615e-07 -0.765807 -0.643071 1.52414e-06 -0.765807 -0.630712 -0.195106 -0.75109 -0.630711 -0.195068 -0.751101 -0.534705 -0.555532 -0.636769 -0.53469 -0.555594 -0.636728 -0.357274 -0.83147 -0.425455 -0.357277 -0.831467 -0.42546 -0.125453 -0.980787 -0.149394 -0.125459 -0.980785 -0.149405 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.125455 -0.980786 -0.149397 -0.125455 -0.980786 -0.149398 -0.357272 -0.831471 -0.425456 -0.357282 -0.831457 -0.425475 -0.534685 -0.555588 -0.636738 -0.53469 -0.555568 -0.636751 -0.63071 -0.195072 -0.7511 -0.630711 -0.195113 -0.751089 -0.630712 -0.195114 -0.751088 -0.630711 -0.195095 -0.751093 -0.534687 -0.55558 -0.636742 -0.534688 -0.555578 -0.636743 -0.357277 -0.831462 -0.425469 -0.357268 -0.831474 -0.425453 -0.125459 -0.980785 -0.149403 -0.125459 -0.980785 -0.149403 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.125457 -0.980785 -0.149401 -0.125457 -0.980786 -0.1494 -0.357281 -0.831461 -0.425468 -0.357276 -0.831468 -0.425458 -0.534693 -0.555584 -0.636734 -0.534703 -0.555544 -0.63676 -0.630715 -0.195064 -0.751098 -0.630716 -0.195086 -0.751092 -0.643072 -1.65744e-05 -0.765806 -0.643067 -3.3774e-06 -0.76581 -0.630705 0.195132 -0.751089 -0.630724 0.195065 -0.751091 -0.534712 0.555541 -0.636756 -0.534691 0.555576 -0.636743 -0.357263 0.831478 -0.425451 -0.357276 0.831467 -0.42546 -0.125456 0.980786 -0.149399 -0.125453 0.980787 -0.149396 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.125452 0.980787 -0.149395 -0.125455 0.980786 -0.149398 -0.357279 0.831464 -0.425465 -0.357266 0.831474 -0.425455 -0.534688 0.555581 -0.63674 -0.534709 0.555547 -0.636752 -0.630726 0.19505 -0.751093 -0.630707 0.195115 -0.751091 -0.643071 3.81778e-06 -0.765806 -0.643067 1.48988e-05 -0.76581 -0.630715 -0.195067 -0.751097 -0.630716 -0.195093 -0.75109 -0.534687 -0.555591 -0.636733 -0.534686 -0.555593 -0.636731 -0.357284 -0.831458 -0.425472 -0.357283 -0.831459 -0.42547 -0.125451 -0.980787 -0.149393 -0.125455 -0.980786 -0.149399 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.125458 -0.980785 -0.1494 -0.12546 -0.980784 -0.149404 -0.357277 -0.831466 -0.425462 -0.357277 -0.831464 -0.425464 -0.534696 -0.555571 -0.636743 -0.534697 -0.555568 -0.636744 -0.630713 -0.195115 -0.751086 -0.630713 -0.195087 -0.751094 -0.643069 -1.86499e-06 -0.765808 -0.643069 -3.33288e-06 -0.765808 -0.63071 0.195117 -0.751089 -0.630727 0.195053 -0.751091 -0.534705 0.555561 -0.636744 -0.534695 0.555577 -0.636738 -0.357274 0.83147 -0.425457 -0.357258 0.831482 -0.425446 -0.125461 0.980784 -0.149407 -0.12546 0.980784 -0.149406 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0838615 0.99146 -0.0998678 -0.0841948 0.991379 -0.10039 -0.24608 0.923928 -0.292918 -0.246388 0.92369 -0.293409 -0.391509 0.793319 -0.466225 -0.39158 0.793248 -0.466286 -0.510182 0.608727 -0.60759 -0.510256 0.608608 -0.607647 -0.621158 0.258811 -0.739716 -0.62116 0.258806 -0.739716 -0.643069 3.2303e-06 -0.765808 -0.643069 1.95886e-06 -0.765808 -0.630719 -0.195055 -0.751097 -0.630719 -0.195078 -0.751091 -0.534685 -0.555597 -0.636729 -0.534687 -0.55559 -0.636733 -0.35727 -0.831471 -0.425456 -0.35728 -0.831458 -0.425475 -0.125462 -0.980784 -0.149409 -0.125458 -0.980785 -0.149403 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.12546 -0.980785 -0.149404 -0.125457 -0.980785 -0.1494 -0.357273 -0.83147 -0.425457 -0.357277 -0.831465 -0.425464 -0.534699 -0.555563 -0.636747 -0.534697 -0.555569 -0.636743 -0.630713 -0.195125 -0.751084 -0.630713 -0.195106 -0.751089 -0.643071 5.66148e-07 -0.765806 -0.643071 1.52413e-06 -0.765807 -0.630715 0.195086 -0.751093 -0.630713 0.195095 -0.751092 -0.534684 0.555591 -0.636735 -0.534708 0.555551 -0.63675 -0.357288 0.831456 -0.425472 -0.357271 0.83147 -0.425458 -0.125458 0.980785 -0.149402 -0.125453 0.980786 -0.149398 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.125456 0.980785 -0.149402 -0.125462 0.980784 -0.149407 -0.357273 0.831468 -0.425461 -0.357268 0.831472 -0.425457 -0.534693 0.555572 -0.636744 -0.53469 0.555577 -0.636742 -0.630712 0.195095 -0.751092 -0.630715 0.195085 -0.751093 -0.643071 -1.85285e-06 -0.765806 -0.643071 -2.94994e-07 -0.765807 -0.630716 -0.195049 -0.751102 -0.630717 -0.195116 -0.751083 -0.534694 -0.555581 -0.636735 -0.534703 -0.555546 -0.636758 -0.357276 -0.831463 -0.425467 -0.357269 -0.831474 -0.425452 -0.125453 -0.980787 -0.149395 -0.125455 -0.980786 -0.149399 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.125456 -0.980786 -0.1494 -0.125453 -0.980787 -0.149396 -0.357265 -0.831478 -0.425448 -0.357273 -0.831467 -0.425463 -0.534706 -0.555541 -0.636761 -0.534697 -0.555575 -0.636738 -0.630715 -0.195132 -0.751081 -0.630714 -0.195066 -0.751099 -0.643067 1.60967e-05 -0.76581 -0.643072 3.86382e-06 -0.765806 -0.0838822 0.991456 -0.0998913 -0.153996 0.965544 -0.209786 -0.246054 0.923906 -0.29301 -0.454733 0.707094 -0.541512 -0.454712 0.707117 -0.5415 -0.621158 0.258815 -0.739715 -0.621162 0.258804 -0.739715 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.166441 0.965925 -0.198206 -0.110916 0.990612 -0.0799076 -0.24642 0.923669 -0.293452 -0.45471 0.707121 -0.541497 -0.454709 0.707123 -0.541496 -0.621157 0.25882 -0.739713 -0.62116 0.258811 -0.739714 -0.643067 -3.3774e-06 -0.76581 -0.643071 -1.53313e-05 -0.765806 -0.630716 -0.195064 -0.751097 -0.630717 -0.19507 -0.751095 -0.534698 -0.55556 -0.636751 -0.534692 -0.555584 -0.636734 -0.357272 -0.831472 -0.425455 -0.357268 -0.831477 -0.425447 -0.125453 -0.980787 -0.149394 -0.12546 -0.980784 -0.149406 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.125459 -0.980784 -0.149405 -0.125458 -0.980785 -0.149404 -0.35727 -0.83147 -0.42546 -0.357262 -0.831482 -0.425443 -0.534702 -0.555561 -0.636746 -0.534698 -0.555577 -0.636736 -0.630719 -0.195116 -0.751081 -0.630718 -0.195055 -0.751099 -0.643069 1.95182e-06 -0.765808 -0.643069 3.2303e-06 -0.765808 -0.630709 0.195114 -0.75109 -0.630717 0.195088 -0.751091 -0.534696 0.555571 -0.636743 -0.534697 0.555568 -0.636744 -0.357276 0.831466 -0.425463 -0.357278 0.831465 -0.425464 -0.125457 0.980785 -0.149401 -0.125461 0.980784 -0.149404 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.12545 0.980787 -0.149394 -0.125456 0.980786 -0.149399 -0.357285 0.831458 -0.425472 -0.357283 0.831459 -0.425471 -0.534687 0.555591 -0.636733 -0.534686 0.555594 -0.636732 -0.63072 0.195066 -0.751094 -0.630712 0.195094 -0.751093 -0.643069 -3.32584e-06 -0.765808 -0.643069 -1.86499e-06 -0.765808 -0.643071 -3.33011e-06 -0.765807 -0.643071 -4.36946e-06 -0.765807 -0.643072 3.41018e-06 -0.765806 -0.643069 0.000215005 -0.765808 -0.643069 -1.09939e-05 -0.765808 -0.630717 0.195072 -0.751095 -0.630705 0.195113 -0.751094 -0.534681 0.555587 -0.636741 -0.534693 0.555568 -0.636748 -0.357269 0.831471 -0.425459 -0.357286 0.831457 -0.425472 -0.125455 0.980786 -0.149397 -0.125455 0.980786 -0.149398 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.125451 0.980787 -0.149396 -0.125461 0.980784 -0.149404 -0.357273 0.83147 -0.425456 -0.357277 0.831467 -0.425459 -0.534716 0.555531 -0.63676 -0.534678 0.555594 -0.636737 -0.630706 0.195106 -0.751095 -0.630717 0.195068 -0.751096 -0.64307 1.10204e-05 -0.765807 -0.643069 3.41034e-06 -0.765808 -0.643069 -0.000214994 -0.765808 -0.643072 -3.41018e-06 -0.765806 -0.64307 4.38188e-06 -0.765807 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.463403 0.777027 -0.426013 -0.774974 0.216969 0.593582 -0.0187928 0.298795 -0.954132 -0.63574 0.582633 0.506334 -0.64018 0.607682 0.469992 -0.630509 0.569515 0.527362 -0.616804 0.550921 0.562174 -0.596722 0.540264 0.593327 0.588965 0.578843 -0.563969 0.538483 0.578225 -0.612937 0.538482 0.578226 -0.612937 0.458927 0.578226 -0.674567 0.458929 0.578224 -0.674568 0.372397 0.578223 -0.725933 0.372395 0.578226 -0.725932 0.280194 0.578226 -0.766254 0.280193 0.578228 -0.766253 0.183735 0.578228 -0.794917 0.183734 0.578231 -0.794916 0.0844707 0.578231 -0.811489 0.0844753 0.578221 -0.811495 -0.0160666 0.578221 -0.815722 -0.0160656 0.578218 -0.815724 -0.116364 0.578218 -0.807541 -0.116365 0.578222 -0.807538 -0.214896 0.578222 -0.787069 -0.214897 0.578226 -0.787067 -0.310151 0.578226 -0.754627 -0.310152 0.578228 -0.754625 -0.40069 0.578228 -0.710704 -0.40069 0.578226 -0.710705 -0.485135 0.578226 -0.655971 -0.485135 0.578232 -0.655967 -0.562198 0.578231 -0.591255 -0.562199 0.578226 -0.591259 -0.630712 0.578226 -0.517549 -0.63071 0.578234 -0.517543 -0.689625 0.578232 -0.435964 -0.689627 0.578227 -0.435968 -0.738052 0.578227 -0.347754 -0.738051 0.57823 -0.347752 -0.775248 0.578229 -0.254248 -0.77525 0.578225 -0.25425 -0.800653 0.578226 -0.156876 -0.800653 0.578225 -0.156877 -0.813875 0.578226 -0.057118 -0.813875 0.578226 -0.0571181 -0.814716 0.578226 0.04351 -0.814716 0.578225 0.0435098 -0.803163 0.578225 0.143475 -0.803161 0.578228 0.143476 -0.779388 0.578229 0.241259 -0.779388 0.578229 0.241259 -0.743758 0.578231 0.335371 -0.743758 0.578231 0.335371 -0.696813 0.578232 0.42438 -0.696813 0.578233 0.42438 -0.647515 0.57858 0.495954 0.64304 0.560564 -0.521792 0.717695 0.286655 -0.634621 0.708119 0.200433 -0.677048 0.723076 0.31222 -0.616181 0.734509 0.332634 -0.591482 0.761212 0.354193 -0.543235 0.742169 0.368321 -0.559933 0.65479 0.443694 -0.611871 0.682908 0.428898 -0.59134 0.652935 0.541561 -0.529516 0.773294 0.500569 -0.389161 0.683015 0.541192 -0.490512 -0.251357 0.298833 -0.920608 -0.362779 0.298814 -0.882667 -0.468677 0.298814 -0.831296 -0.468676 0.29884 -0.831287 -0.567448 0.298843 -0.767266 -0.657587 0.298841 -0.691573 -0.657586 0.298847 -0.691572 -0.737727 0.298815 -0.605367 -0.806641 0.298817 -0.509941 -0.80664 0.298819 -0.50994 -0.863281 0.298821 -0.406757 -0.863282 0.298816 -0.406758 -0.906789 0.298819 -0.297389 -0.906787 0.298829 -0.297387 -0.936499 0.298829 -0.183495 -0.936499 0.298832 -0.183494 -0.951965 0.298829 -0.0668092 -0.951964 0.298832 -0.0668087 -0.952949 0.29883 0.0508921 -0.952949 0.298829 0.0508921 -0.939435 0.298829 0.167819 -0.939434 0.298831 0.167819 -0.911629 0.29883 0.282194 -0.911629 0.298829 0.282193 -0.869954 0.29883 0.392276 -0.869958 0.298819 0.392276 -0.815051 0.298818 0.496387 -0.669684 0.485011 0.562394 -0.700515 0.428898 0.570372 -0.6324 0.366552 0.68243 -0.653698 0.360267 0.665497 -0.709608 0.332629 0.62114 -0.731939 0.312232 0.605621 -0.749126 0.286734 0.597155 -0.76977 0.244603 0.589596 -0.768719 0.299269 0.565251 -0.815045 0.298836 0.496387 -0.770982 0.225088 0.595753 -0.835983 0.20473 0.509136 -0.82482 0.234553 0.514448 -0.893546 0.19808 0.402914 -0.878663 0.241163 0.412058 -0.937692 0.191003 0.290261 -0.919752 0.248117 0.304128 -0.9677 0.183504 0.172868 -0.947526 0.255409 0.192253 -0.983065 0.175579 0.0525004 -0.961626 0.263019 0.0780787 -0.983501 0.167218 -0.0690224 -0.961893 0.270952 -0.0367103 -0.968947 0.158424 -0.189852 -0.948379 0.279191 -0.150433 -0.945663 0.183641 -0.268323 -0.919258 0.253133 -0.301478 -0.91448 0.217138 -0.341433 -0.892548 0.217033 -0.395291 -0.874794 0.254642 -0.412181 -0.866452 0.217125 -0.449575 -0.83816 0.217047 -0.500378 -0.817144 0.255772 -0.516581 -0.805692 0.217116 -0.551109 -0.737723 0.298844 -0.605357 -0.747181 0.256526 -0.613119 -0.771458 0.217064 -0.598111 -0.605196 0.217084 -0.765907 -0.649725 0.217084 -0.728513 -0.66595 0.256892 -0.700369 -0.693417 0.217071 -0.687061 -0.733092 0.217098 -0.64455 -0.567448 0.298839 -0.767267 -0.58048 0.216781 -0.784888 -0.545419 0.29271 -0.785391 -0.371106 0.216789 -0.90293 -0.362779 0.298803 -0.882671 -0.251355 0.298802 -0.920618 -0.341919 0.282179 -0.896363 -0.40349 0.217121 -0.88885 -0.479435 0.216795 -0.850378 -0.44713 0.287455 -0.847021 -0.508079 0.217096 -0.833502 -0.0981641 0.287737 -0.952665 -0.178159 0.21714 -0.959744 -0.257128 0.216793 -0.941746 -0.231331 0.276862 -0.932649 -0.292983 0.217127 -0.931138 -0.0187936 0.298801 -0.95413 0.0988096 0.298801 -0.949186 0.0988065 0.298818 -0.949181 0.214912 0.298819 -0.929796 0.214908 0.298837 -0.929791 0.327732 0.298837 -0.896263 0.327735 0.298825 -0.896266 0.435578 0.298825 -0.849103 0.43558 0.298816 -0.849105 0.5368 0.298816 -0.789021 0.536798 0.298824 -0.78902 0.629848 0.298825 -0.716935 0.62984 0.298848 -0.716932 0.702487 0.29909 -0.645799 0.715473 0.235546 -0.657737 -0.136111 0.298834 -0.944549 -0.136107 0.298796 -0.944561 -0.141026 0.149193 -0.9787 -0.0190616 0.251244 -0.967736 0.0161912 0.185799 -0.982454 0.100277 0.248977 -0.963304 0.13281 0.188335 -0.973084 0.21826 0.246318 -0.944293 0.247403 0.191275 -0.949845 0.333109 0.243289 -0.910961 0.358335 0.194583 -0.91309 0.44311 0.239855 -0.863784 0.463992 0.198276 -0.863365 0.546606 0.236036 -0.803436 0.56286 0.202356 -0.801399 0.642021 0.231828 -0.730797 0.653521 0.206798 -0.72811 0.714673 0.223603 -0.662755 0.727637 0.175113 -0.663235 0.61416 0.578493 -0.536799 0.591691 0.594999 -0.543947 0.530437 0.693432 -0.487635 0.405694 0.834455 -0.372958 0.29726 0.914854 -0.273274 0.161453 0.975655 -0.148426 0.0455499 0.998084 -0.0418744 0.0455497 0.998084 -0.0418744 0.0408728 0.998081 -0.0465244 0.0408731 0.998081 -0.0465245 0.0348349 0.998081 -0.0512023 0.0348343 0.998081 -0.051202 0.0282659 0.998081 -0.055101 0.0282659 0.998081 -0.055101 0.0212678 0.998081 -0.0581615 0.021268 0.998081 -0.0581617 0.0139463 0.998081 -0.0603374 0.0139463 0.998081 -0.0603374 0.00641183 0.998081 -0.0615954 0.00641196 0.998081 -0.0615956 -0.00121934 0.998081 -0.0619164 -0.00121977 0.998081 -0.0619156 -0.00883252 0.998081 -0.0612945 -0.00883237 0.998081 -0.0612949 -0.0163112 0.998081 -0.0597413 -0.0163111 0.998081 -0.0597413 -0.0235416 0.998081 -0.0572789 -0.0235417 0.998081 -0.0572781 -0.0304136 0.998081 -0.0539445 -0.0304136 0.998081 -0.0539445 -0.0368235 0.998081 -0.0497899 -0.0368236 0.998081 -0.0497908 -0.0426732 0.998081 -0.0448787 -0.0426732 0.998081 -0.0448785 -0.0478734 0.998081 -0.0392838 -0.0478735 0.998081 -0.0392842 -0.0523454 0.998081 -0.0330918 -0.0523451 0.998081 -0.0330913 -0.0560207 0.998081 -0.0263957 -0.0560207 0.998081 -0.0263956 -0.0588441 0.998081 -0.0192983 -0.0588444 0.998081 -0.0192986 -0.0607725 0.998081 -0.0119076 -0.0607724 0.998081 -0.0119075 -0.061776 0.998081 -0.00433546 -0.061776 0.998081 -0.00433544 -0.0618399 0.998081 0.00330252 -0.0618398 0.998081 0.00330255 -0.0609628 0.998081 0.0108904 -0.0609629 0.998081 0.0108904 -0.0591586 0.998081 0.0183124 -0.0591587 0.998081 0.0183124 -0.0564544 0.998081 0.0254559 -0.0564541 0.998081 0.0254559 -0.0528907 0.998081 0.0322124 -0.0528911 0.998081 0.0322124 -0.0491201 0.998084 0.0376229 -0.04912 0.998084 0.0376229 -0.191844 0.970363 0.14694 -0.339608 0.903883 0.26012 -0.467989 0.807775 0.35845 0.161454 0.975655 -0.148426 0.144871 0.975613 -0.164901 0.14487 0.975613 -0.164901 0.123467 0.975613 -0.181481 0.123469 0.975613 -0.181482 0.100188 0.975613 -0.195301 0.100186 0.975613 -0.1953 0.0753817 0.975613 -0.206148 0.0753819 0.975613 -0.206148 0.0494297 0.975613 -0.21386 0.0494317 0.975612 -0.213862 0.0227281 0.975612 -0.21832 0.022726 0.975613 -0.218318 -0.00432353 0.975613 -0.219455 -0.00432184 0.975613 -0.219458 -0.0313067 0.975612 -0.217256 -0.0313066 0.975612 -0.217256 -0.0578124 0.975612 -0.21175 -0.0578135 0.975613 -0.211748 -0.0834413 0.975613 -0.20302 -0.0834412 0.975613 -0.20302 -0.1078 0.975613 -0.191203 -0.1078 0.975613 -0.191204 -0.130519 0.975613 -0.176478 -0.130519 0.975613 -0.176478 -0.151251 0.975613 -0.159069 -0.151251 0.975613 -0.159068 -0.169683 0.975613 -0.139238 -0.169683 0.975613 -0.139238 -0.185533 0.975613 -0.117291 -0.185533 0.975613 -0.11729 -0.198561 0.975613 -0.093557 -0.198562 0.975613 -0.0935576 -0.208569 0.975613 -0.0684018 -0.208568 0.975613 -0.0684012 -0.215403 0.975613 -0.0422052 -0.215403 0.975613 -0.0422056 -0.21896 0.975613 -0.0153667 -0.21896 0.975613 -0.0153667 -0.219186 0.975613 0.0117056 -0.219186 0.975613 0.0117055 -0.216078 0.975613 0.0386001 -0.216078 0.975613 0.0386002 -0.209683 0.975613 0.0649065 -0.209682 0.975613 0.0649067 -0.200096 0.975613 0.0902266 -0.200098 0.975613 0.0902263 -0.187468 0.975613 0.114174 -0.187466 0.975613 0.114174 -0.185196 0.975658 0.117449 -0.11611 0.989247 0.0889332 0.297259 0.914854 -0.273274 0.266698 0.91472 -0.303577 0.266702 0.914719 -0.303577 0.2273 0.914719 -0.334101 0.227299 0.914719 -0.334101 0.184441 0.914719 -0.359541 0.184443 0.914719 -0.359542 0.138777 0.914719 -0.379514 0.138776 0.914719 -0.379513 0.0910012 0.914719 -0.39371 0.0909979 0.914721 -0.393707 0.0418367 0.914721 -0.401915 0.0418416 0.914718 -0.40192 -0.00795751 0.914718 -0.404014 -0.0079595 0.91472 -0.404011 -0.0576326 0.914719 -0.399958 -0.0576339 0.91472 -0.399956 -0.106432 0.91472 -0.389819 -0.10643 0.914719 -0.389823 -0.153615 0.914719 -0.373754 -0.153614 0.914718 -0.373756 -0.198457 0.914718 -0.352002 -0.198458 0.914719 -0.352001 -0.240279 0.914719 -0.324893 -0.240279 0.914721 -0.324888 -0.278447 0.91472 -0.292837 -0.278448 0.914719 -0.29284 -0.312381 0.914719 -0.256333 -0.312381 0.91472 -0.256332 -0.341561 0.91472 -0.215927 -0.341561 0.914719 -0.215929 -0.365546 0.914719 -0.172237 -0.365545 0.91472 -0.172235 -0.383967 0.91472 -0.125925 -0.383967 0.91472 -0.125925 -0.396549 0.914719 -0.077698 -0.39655 0.914719 -0.0776985 -0.403098 0.914719 -0.0282897 -0.403098 0.914719 -0.0282896 -0.403515 0.914719 0.0215495 -0.403514 0.91472 0.0215497 -0.397793 0.914719 0.0710613 -0.397792 0.914719 0.0710614 -0.386018 0.914719 0.119491 -0.386019 0.914719 0.119491 -0.368372 0.914719 0.166104 -0.368372 0.914719 0.166105 -0.345122 0.914719 0.210189 -0.345121 0.91472 0.210189 -0.331675 0.915003 0.229698 -0.268321 0.941152 0.205516 0.409602 0.81981 -0.400172 0.3784 0.819326 -0.430719 0.378394 0.819329 -0.430718 0.322494 0.819329 -0.474023 0.322493 0.81933 -0.474023 0.261685 0.81933 -0.510118 0.261685 0.81933 -0.510118 0.196895 0.81933 -0.538452 0.196896 0.819329 -0.538453 0.129108 0.819329 -0.558597 0.129114 0.819325 -0.558602 0.0593611 0.819325 -0.570248 0.0593588 0.819327 -0.570246 -0.0112879 0.819327 -0.573215 -0.0112901 0.819329 -0.573213 -0.0817738 0.819329 -0.567462 -0.0817702 0.819325 -0.567468 -0.151008 0.819325 -0.553085 -0.151008 0.819326 -0.553084 -0.217948 0.819326 -0.530287 -0.217949 0.819328 -0.530283 -0.281571 0.819328 -0.499419 -0.281571 0.819327 -0.49942 -0.340909 0.819327 -0.460959 -0.340909 0.819327 -0.46096 -0.395066 0.819327 -0.415482 -0.395066 0.819327 -0.415483 -0.44321 0.819327 -0.363688 -0.44321 0.819327 -0.363688 -0.48461 0.819327 -0.306361 -0.484609 0.819328 -0.306359 -0.518638 0.819328 -0.244369 -0.51864 0.819326 -0.244372 -0.544778 0.819326 -0.178664 -0.544778 0.819326 -0.178664 -0.562629 0.819327 -0.110239 -0.562628 0.819327 -0.110239 -0.57192 0.819327 -0.0401374 -0.57192 0.819327 -0.0401378 -0.572511 0.819327 0.0305752 -0.572511 0.819327 0.0305748 -0.564392 0.819327 0.100822 -0.564392 0.819327 0.100822 -0.547687 0.819327 0.169535 -0.547688 0.819327 0.169535 -0.522651 0.819327 0.23567 -0.522649 0.819328 0.23567 -0.48966 0.819328 0.29822 -0.489663 0.819326 0.298219 -0.463597 0.819792 0.336184 -0.403516 0.861192 0.309069 0.530434 0.693434 -0.487636 0.475751 0.693111 -0.541532 0.475753 0.69311 -0.541533 0.405465 0.69311 -0.595983 0.405468 0.693108 -0.595984 0.329014 0.693108 -0.641367 0.329014 0.693107 -0.641367 0.247554 0.693107 -0.676993 0.247556 0.693105 -0.676994 0.162332 0.693105 -0.70232 0.162326 0.693111 -0.702316 0.074634 0.693111 -0.716957 0.0746329 0.693112 -0.716956 -0.0141939 0.693112 -0.72069 -0.014192 0.69311 -0.720692 -0.102809 0.69311 -0.713463 -0.102812 0.693114 -0.713458 -0.189862 0.693114 -0.695374 -0.189858 0.693108 -0.695381 -0.274022 0.693108 -0.666718 -0.274021 0.693107 -0.666719 -0.354013 0.693108 -0.627914 -0.354014 0.693111 -0.62791 -0.428621 0.693111 -0.579553 -0.428621 0.693107 -0.579558 -0.496708 0.693107 -0.522383 -0.496708 0.693112 -0.522377 -0.557239 0.693111 -0.457255 -0.557239 0.693108 -0.457259 -0.609292 0.693108 -0.385181 -0.609292 0.693107 -0.385183 -0.652076 0.693108 -0.307243 -0.652076 0.693109 -0.307242 -0.684939 0.693109 -0.224632 -0.684938 0.69311 -0.224631 -0.707381 0.69311 -0.138602 -0.707381 0.69311 -0.138602 -0.719064 0.693109 -0.0504643 -0.719064 0.69311 -0.050464 -0.719807 0.693109 0.0384412 -0.719806 0.69311 0.0384415 -0.709599 0.693109 0.126762 -0.709599 0.693109 0.126762 -0.688596 0.69311 0.213154 -0.688597 0.693108 0.213153 -0.657119 0.693108 0.296304 -0.65712 0.693108 0.296304 -0.615644 0.693107 0.374946 -0.615642 0.693109 0.374947 -0.572013 0.693432 0.438125 -0.572013 0.693432 0.438125 0.753205 0.102526 -0.649747 0.761646 0.0196586 -0.647695 0.765843 0.0263417 -0.642488 0.757052 0.0462618 -0.651715 0.745703 0.0462452 -0.664672 0.74579 0.0462593 -0.664574 0.725536 0.046198 -0.686632 0.759445 0.0410625 -0.649275 0.78942 0.0515898 -0.611682 0.774999 0.0486105 -0.630091 0.756064 0.088731 -0.648456 0.774409 0.0445784 -0.631112 0.812049 0.0508314 -0.581372 0.821288 0.0521074 -0.568129 0.768922 0.0750211 -0.634926 0.759738 0.0827835 -0.644938 0.742364 0.10386 -0.661898 0.722207 0.103722 -0.683856 0.753059 0.105636 -0.649417 0.743129 0.0991297 -0.661765 0.753486 0.104024 -0.649183 0.752618 0.148438 -0.641508 0.765392 0.107811 -0.63447 0.792713 0.113677 -0.598902 0.834882 0.120904 -0.536986 0.794322 0.132402 -0.592894 0.763959 0.143213 -0.629172 0.745228 0.153834 -0.648822 0.736262 0.163881 -0.656553 0.727392 0.176966 -0.663011 -0.786708 0.199738 0.58412 -0.773993 0.163921 0.611609 -0.767891 0.153812 0.62184 -0.762002 0.14845 0.63033 -0.774896 0.101732 0.623848 -0.767778 0.104616 0.632118 -0.75179 0.143213 0.643663 -0.721307 0.132401 0.679842 -0.673258 0.120905 0.729456 -0.736424 0.112271 0.66714 -0.7596 0.107108 0.641511 -0.798339 0.103723 0.593209 -0.77082 0.0410624 0.635728 -0.782117 0.10385 0.614417 -0.78034 0.103648 0.616707 -0.770004 0.104238 0.629466 -0.770203 0.102465 0.629515 -0.76943 0.0887511 0.632536 -0.766592 0.0827859 0.636775 -0.758314 0.0750195 0.647558 -0.701591 0.0521096 0.710671 -0.713017 0.0508358 0.699301 -0.755494 0.044584 0.653637 -0.801701 0.0461985 0.595937 -0.783549 0.0462596 0.619606 -0.783635 0.0462447 0.619498 -0.77281 0.0462614 0.632949 -0.754582 0.0486142 0.654402 -0.738997 0.0515834 0.671731 -0.765258 0.0263373 0.643185 -0.769657 0.0196588 0.638155 0.725579 0.0462306 -0.686584 0.66725 0.0461595 -0.743402 0.667244 0.0461689 -0.743407 0.574138 0.0461694 -0.817455 0.574139 0.0461682 -0.817455 0.472884 0.0461686 -0.879914 0.472887 0.0461646 -0.879913 0.364927 0.0461646 -0.929891 0.364925 0.0461682 -0.929892 0.251793 0.0461684 -0.966679 0.251794 0.0461667 -0.966679 0.135084 0.0461667 -0.989758 0.135081 0.0461704 -0.989758 0.0164604 0.0461705 -0.998798 0.0164646 0.0461648 -0.998798 -0.102393 0.0461648 -0.993672 -0.102395 0.0461679 -0.993672 -0.219798 0.0461679 -0.974452 -0.219795 0.0461635 -0.974453 -0.334083 0.0461635 -0.941413 -0.334086 0.0461678 -0.941411 -0.443635 0.0461676 -0.895018 -0.443633 0.0461646 -0.895019 -0.546887 0.0461647 -0.835933 -0.546885 0.0461609 -0.835934 -0.642386 0.0461612 -0.764989 -0.642388 0.0461638 -0.764988 -0.728774 0.0461639 -0.683197 -0.728775 0.0461659 -0.683196 -0.804826 0.0461657 -0.591712 -0.804826 0.0461642 -0.591713 -0.869461 0.0461642 -0.49184 -0.869462 0.0461671 -0.491838 -0.921767 0.0461667 -0.384986 -0.921766 0.0461646 -0.384988 -0.960999 0.0461645 -0.272673 -0.960999 0.0461644 -0.272673 -0.986599 0.0461644 -0.156496 -0.986599 0.0461646 -0.156496 -0.998207 0.046164 -0.0380967 -0.998207 0.0461645 -0.0380963 -0.995657 0.046164 0.0808421 -0.995657 0.0461646 0.0808426 -0.978986 0.0461647 0.198635 -0.978986 0.0461638 0.198634 -0.948429 0.0461633 0.313611 -0.948429 0.0461642 0.313611 -0.904421 0.0461639 0.424136 -0.90442 0.046167 0.424138 -0.847584 0.0461673 0.52865 -0.847585 0.0461649 0.528648 -0.801745 0.0462358 0.595876 0.722318 0.103805 -0.683727 0.664361 0.103647 -0.740191 0.664362 0.103645 -0.74019 0.571655 0.103645 -0.813922 0.571655 0.103644 -0.813922 0.470842 0.103643 -0.876108 0.470838 0.103649 -0.87611 0.363349 0.103649 -0.925869 0.363352 0.103646 -0.925869 0.250701 0.103646 -0.9625 0.250702 0.103646 -0.9625 0.134503 0.103646 -0.985478 0.1345 0.103651 -0.985478 0.0163864 0.103651 -0.994479 0.016393 0.103642 -0.99448 -0.101949 0.103642 -0.989376 -0.101953 0.103647 -0.989375 -0.218847 0.103647 -0.970239 -0.218849 0.103649 -0.970238 -0.332639 0.103649 -0.937341 -0.332636 0.103644 -0.937343 -0.441713 0.103644 -0.89115 -0.441715 0.103647 -0.891148 -0.544524 0.103647 -0.832317 -0.544521 0.103643 -0.832319 -0.639607 0.103643 -0.761683 -0.63961 0.103649 -0.76168 -0.725623 0.103649 -0.680241 -0.725622 0.103645 -0.680243 -0.801345 0.103646 -0.589155 -0.801346 0.103647 -0.589154 -0.865702 0.103647 -0.489711 -0.865702 0.103647 -0.489711 -0.917781 0.103647 -0.383321 -0.917781 0.103647 -0.383321 -0.956843 0.103647 -0.271494 -0.956843 0.103647 -0.271494 -0.982333 0.103647 -0.155819 -0.982333 0.103648 -0.155819 -0.993891 0.103648 -0.0379316 -0.993891 0.103647 -0.037932 -0.991352 0.103648 0.080493 -0.991352 0.103648 0.0804931 -0.974752 0.103648 0.197776 -0.974752 0.103647 0.197776 -0.944328 0.103647 0.312254 -0.944328 0.103647 0.312254 -0.90051 0.103646 0.422302 -0.900509 0.103651 0.422304 -0.843918 0.103651 0.526364 -0.84392 0.103647 0.526362 -0.798433 0.103805 0.593067 -0.782211 0.151036 0.604429 -0.838775 0.150897 0.523152 -0.838771 0.150911 0.523153 -0.895017 0.150909 0.419727 -0.895019 0.150903 0.419726 -0.938569 0.150903 0.31035 -0.938568 0.150908 0.310351 -0.968807 0.150906 0.196571 -0.968808 0.150901 0.196569 -0.985306 0.150903 0.0800014 -0.985306 0.150905 0.0800019 -0.987829 0.150905 -0.0377002 -0.987829 0.150905 -0.0377002 -0.976342 0.150905 -0.154869 -0.976342 0.150906 -0.154869 -0.951006 0.150909 -0.26984 -0.951007 0.150905 -0.269841 -0.926071 0.151134 -0.345761 -0.918224 0.0989315 -0.383506 -0.90385 0.151059 -0.400296 -0.877432 0.151127 -0.455273 -0.866295 0.0968928 -0.490046 -0.848774 0.151071 -0.506715 -0.815902 0.151119 -0.558093 -0.802008 0.0954361 -0.589639 -0.781228 0.151084 -0.605686 -0.742379 0.151113 -0.652716 -0.726282 0.0945659 -0.680861 -0.702199 0.151102 -0.695762 -0.657955 0.151112 -0.73774 -0.640208 0.094272 -0.762395 -0.612862 0.151099 -0.775609 -0.541201 0.150903 -0.827242 -0.569832 0.0447088 -0.820544 -0.514516 0.151105 -0.844062 -0.439018 0.1509 -0.885716 -0.466178 0.0529685 -0.883104 -0.408603 0.151115 -0.900115 -0.33061 0.1509 -0.931626 -0.355734 0.0612305 -0.932579 -0.296696 0.151117 -0.94294 -0.217514 0.150895 -0.964323 -0.240161 0.0694567 -0.968245 0.717643 0.15114 -0.679813 0.660307 0.150912 -0.735676 0.660312 0.150898 -0.735676 0.568173 0.150897 -0.808956 0.568168 0.150916 -0.808956 0.467967 0.150917 -0.870764 0.467969 0.150912 -0.870764 0.36113 0.150912 -0.920223 0.361134 0.150897 -0.920224 0.249175 0.150897 -0.956631 0.24917 0.150913 -0.956629 0.133679 0.150913 -0.979467 0.133681 0.150905 -0.979468 0.0162895 0.150905 -0.988414 0.0162894 0.150905 -0.988414 -0.101328 0.150905 -0.983341 -0.101325 0.150894 -0.983343 -0.180418 0.151123 -0.971911 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.467989 -0.807775 0.35845 -0.789291 -0.200452 0.580378 -0.749126 -0.286735 0.597155 -0.73194 -0.312231 0.60562 0.723076 -0.312219 -0.616183 0.717694 -0.286655 -0.634621 0.713825 -0.244598 -0.656222 0.614162 -0.578492 -0.536798 0.573613 -0.607677 -0.549269 0.64304 -0.560564 -0.521792 0.683013 -0.541193 -0.490513 0.685149 -0.540415 -0.488388 0.671086 -0.479792 -0.565193 0.679639 -0.444171 -0.583783 0.673619 -0.428772 -0.60199 0.756369 -0.354395 -0.549827 0.768513 -0.36026 -0.528773 0.734509 -0.332634 -0.591482 -0.657311 -0.578852 0.482569 -0.696813 -0.578233 0.42438 -0.696813 -0.578233 0.42438 -0.743757 -0.578232 0.33537 -0.743758 -0.578231 0.335371 -0.779387 -0.57823 0.241259 -0.779388 -0.57823 0.241259 -0.80316 -0.578229 0.143474 -0.803163 -0.578225 0.143476 -0.814716 -0.578225 0.04351 -0.814716 -0.578226 0.0435098 -0.813874 -0.578227 -0.057118 -0.813874 -0.578227 -0.0571181 -0.800653 -0.578225 -0.156877 -0.800652 -0.578227 -0.156877 -0.77525 -0.578226 -0.254249 -0.775247 -0.578229 -0.25425 -0.73805 -0.57823 -0.347753 -0.738052 -0.578228 -0.347753 -0.689628 -0.578228 -0.435966 -0.689624 -0.578233 -0.435965 -0.630708 -0.578234 -0.517545 -0.630714 -0.578226 -0.517547 -0.562201 -0.578226 -0.591257 -0.562196 -0.578232 -0.591256 -0.485133 -0.578232 -0.655968 -0.485137 -0.578227 -0.65597 -0.40069 -0.578227 -0.710705 -0.400689 -0.578228 -0.710704 -0.310151 -0.578228 -0.754625 -0.310152 -0.578226 -0.754626 -0.214896 -0.578226 -0.787067 -0.214898 -0.578223 -0.787069 -0.116364 -0.578223 -0.807538 -0.116366 -0.578219 -0.807541 -0.0160666 -0.578219 -0.815724 -0.0160655 -0.578221 -0.815722 0.0844714 -0.578222 -0.811495 0.0844746 -0.578232 -0.811488 0.183735 -0.578231 -0.794915 0.183734 -0.578229 -0.794917 0.280194 -0.578229 -0.766253 0.280193 -0.578227 -0.766254 0.372396 -0.578227 -0.725931 0.372395 -0.578224 -0.725933 0.458928 -0.578224 -0.674568 0.458927 -0.578227 -0.674566 0.538482 -0.578227 -0.612936 0.538482 -0.578226 -0.612937 0.600456 -0.578571 -0.552004 -0.625113 -0.56055 0.543155 -0.709608 -0.332629 0.62114 -0.653696 -0.360268 0.665498 -0.632401 -0.366552 0.682429 -0.700516 -0.428898 0.570372 -0.63444 -0.541561 0.551541 -0.517012 -0.500569 0.694355 -0.601242 -0.5412 0.587887 -0.052891 -0.998081 0.0322125 -0.0528908 -0.998081 0.0322122 -0.0564541 -0.998081 0.0254558 -0.0564543 -0.998081 0.0254561 -0.0591587 -0.998081 0.0183125 -0.0591586 -0.998081 0.0183124 -0.0609629 -0.998081 0.0108904 -0.0609628 -0.998081 0.0108903 -0.0618398 -0.998081 0.00330251 -0.0618399 -0.998081 0.00330255 -0.061776 -0.998081 -0.00433546 -0.061776 -0.998081 -0.00433544 -0.0607723 -0.998081 -0.0119076 -0.0607725 -0.998081 -0.0119076 -0.0588444 -0.998081 -0.0192984 -0.058844 -0.998081 -0.0192984 -0.0560207 -0.998081 -0.0263957 -0.0560208 -0.998081 -0.0263956 -0.052345 -0.998081 -0.0330915 -0.0523456 -0.998081 -0.0330916 -0.0478736 -0.998081 -0.039284 -0.0478733 -0.998081 -0.0392839 -0.0426731 -0.998081 -0.0448786 -0.0426733 -0.998081 -0.0448786 -0.036824 -0.998081 -0.0497905 -0.0368231 -0.998081 -0.0497901 -0.0304136 -0.998081 -0.0539445 -0.0304136 -0.998081 -0.0539445 -0.0235414 -0.998081 -0.0572782 -0.023542 -0.998081 -0.0572787 -0.0163112 -0.998081 -0.0597413 -0.0163111 -0.998081 -0.0597413 -0.00883257 -0.998081 -0.0612948 -0.00883231 -0.998081 -0.0612945 -0.00121932 -0.998081 -0.0619156 -0.00121979 -0.998081 -0.0619164 0.00641185 -0.998081 -0.0615956 0.00641194 -0.998081 -0.0615954 0.0139463 -0.998081 -0.0603374 0.0139463 -0.998081 -0.0603374 0.0212679 -0.998081 -0.0581617 0.0212679 -0.998081 -0.0581615 0.0282659 -0.998081 -0.055101 0.0282659 -0.998081 -0.0551009 0.0348345 -0.998081 -0.0512018 0.0348346 -0.998081 -0.0512025 0.040873 -0.998081 -0.0465246 0.0408729 -0.998081 -0.0465242 0.0455498 -0.998084 -0.0418744 0.0455498 -0.998084 -0.0418745 0.463403 -0.777027 -0.426013 0.724815 -0.175082 -0.666326 -0.479435 -0.216795 -0.850378 -0.371103 -0.216795 -0.90293 -0.371106 -0.216789 -0.90293 -0.25713 -0.216789 -0.941747 -0.257128 -0.216793 -0.941746 -0.139231 -0.216793 -0.966238 -0.13923 -0.216795 -0.966237 -0.0192271 -0.216795 -0.976028 -0.0192249 -0.216801 -0.976026 0.10108 -0.216801 -0.970969 0.101075 -0.216786 -0.970973 0.219841 -0.216786 -0.951143 0.219843 -0.216791 -0.951142 0.335258 -0.216791 -0.916844 0.335259 -0.216795 -0.916843 0.445579 -0.216795 -0.868596 0.445579 -0.216796 -0.868596 0.549122 -0.216795 -0.807134 0.549122 -0.216796 -0.807134 0.644306 -0.216795 -0.733396 0.644306 -0.216792 -0.733397 0.714183 -0.217036 -0.665461 0.715473 -0.235546 -0.657737 -0.574663 -0.2569 -0.777023 -0.556802 -0.21707 -0.801781 -0.479441 -0.216781 -0.850378 -0.679246 -0.292695 -0.673019 -0.649725 -0.217084 -0.728513 -0.605196 -0.217084 -0.765907 -0.672689 -0.216782 -0.707456 -0.754666 -0.216783 -0.619261 -0.754664 -0.216789 -0.619262 -0.825158 -0.21679 -0.521647 -0.825159 -0.216788 -0.521647 -0.883101 -0.216788 -0.416096 -0.8831 -0.216791 -0.416096 -0.927607 -0.216791 -0.304217 -0.927606 -0.216791 -0.304217 -0.958002 -0.216791 -0.187708 -0.958002 -0.21679 -0.187707 -0.973823 -0.21679 -0.0683432 -0.973823 -0.21679 -0.068343 -0.974829 -0.21679 0.0520606 -0.974829 -0.216792 0.0520599 -0.961004 -0.216794 0.171672 -0.961004 -0.216792 0.171673 -0.93256 -0.216793 0.288673 -0.93256 -0.216793 0.288673 -0.889929 -0.216794 0.401282 -0.889929 -0.216794 0.401282 -0.833761 -0.216795 0.507782 -0.833761 -0.216788 0.507785 0.689658 -0.299278 -0.659397 0.629843 -0.298848 -0.716929 0.629845 -0.298826 -0.716937 0.536799 -0.298825 -0.789019 0.536799 -0.298817 -0.789021 0.435579 -0.298817 -0.849105 0.435579 -0.298826 -0.849102 0.327734 -0.298826 -0.896267 0.327734 -0.298838 -0.896263 0.21491 -0.298838 -0.92979 0.214909 -0.298819 -0.929796 0.098809 -0.298819 -0.949181 0.098807 -0.298802 -0.949186 -0.0187928 -0.298802 -0.95413 -0.0187936 -0.298796 -0.954132 -0.136112 -0.298796 -0.94456 -0.136105 -0.298834 -0.944549 -0.251352 -0.298834 -0.920609 -0.251359 -0.298803 -0.920617 -0.362781 -0.298804 -0.88267 -0.362778 -0.298814 -0.882668 -0.46868 -0.298815 -0.831294 -0.468673 -0.298841 -0.831288 -0.567448 -0.29884 -0.767266 -0.567447 -0.298843 -0.767266 -0.657587 -0.298842 -0.691573 -0.657585 -0.298848 -0.691572 -0.73772 -0.298845 -0.605361 -0.73773 -0.298815 -0.605363 -0.806641 -0.298818 -0.50994 -0.80664 -0.298819 -0.50994 -0.863281 -0.298821 -0.406758 -0.863282 -0.298817 -0.406758 -0.906789 -0.29882 -0.297388 -0.906786 -0.298829 -0.297388 -0.936499 -0.298829 -0.183494 -0.936498 -0.298833 -0.183494 -0.951965 -0.298829 -0.0668088 -0.951964 -0.298833 -0.0668092 -0.952948 -0.29883 0.050892 -0.952948 -0.29883 0.0508921 -0.939435 -0.29883 0.167819 -0.939434 -0.298832 0.167819 -0.911629 -0.298831 0.282193 -0.911629 -0.29883 0.282194 -0.869955 -0.298831 0.392274 -0.869957 -0.29882 0.392277 -0.815049 -0.298819 0.496389 -0.815046 -0.298836 0.496384 -0.757547 -0.299083 0.580234 -0.774973 -0.216974 0.593581 -0.774973 -0.216969 0.593584 -0.634908 -0.578494 0.51209 -0.638064 -0.595006 0.488715 -0.572013 -0.693432 0.438125 -0.339608 -0.903883 0.26012 -0.403516 -0.861192 0.309069 -0.191844 -0.970363 0.14694 -0.268319 -0.941153 0.205515 -0.0491201 -0.998084 0.0376229 -0.04912 -0.998084 0.0376228 -0.116113 -0.989246 0.0889349 -0.185196 -0.975658 0.11745 -0.187468 -0.975613 0.114173 -0.187468 -0.975613 0.114175 -0.200098 -0.975613 0.0902273 -0.200097 -0.975613 0.0902261 -0.209683 -0.975613 0.0649066 -0.209683 -0.975613 0.064907 -0.216079 -0.975613 0.0386002 -0.216079 -0.975613 0.0386003 -0.219187 -0.975613 0.0117057 -0.219187 -0.975613 0.0117055 -0.218961 -0.975613 -0.0153668 -0.218961 -0.975613 -0.0153668 -0.215404 -0.975613 -0.0422054 -0.215403 -0.975613 -0.0422056 -0.208569 -0.975613 -0.0684018 -0.208569 -0.975613 -0.0684016 -0.198562 -0.975613 -0.0935575 -0.198562 -0.975613 -0.0935577 -0.185533 -0.975613 -0.117291 -0.185533 -0.975613 -0.117291 -0.169683 -0.975613 -0.139238 -0.169683 -0.975613 -0.139238 -0.151251 -0.975613 -0.159069 -0.151252 -0.975613 -0.159069 -0.13052 -0.975613 -0.176479 -0.13052 -0.975613 -0.176479 -0.107801 -0.975613 -0.191205 -0.1078 -0.975613 -0.191204 -0.0834416 -0.975613 -0.203021 -0.0834414 -0.975613 -0.20302 -0.0578121 -0.975613 -0.211749 -0.0578142 -0.975612 -0.21175 -0.0313069 -0.975612 -0.217257 -0.0313066 -0.975612 -0.217257 -0.0043236 -0.975612 -0.219458 -0.0043218 -0.975613 -0.219456 0.0227279 -0.975613 -0.218319 0.0227264 -0.975612 -0.218321 0.0494303 -0.975612 -0.213863 0.0494314 -0.975613 -0.21386 0.075382 -0.975613 -0.206149 0.075382 -0.975613 -0.206149 0.100188 -0.975613 -0.1953 0.100187 -0.975612 -0.195303 0.123468 -0.975612 -0.181483 0.123469 -0.975613 -0.181481 0.144871 -0.975613 -0.164901 0.144871 -0.975613 -0.164902 0.161454 -0.975655 -0.148427 0.161454 -0.975655 -0.148426 -0.331675 -0.915003 0.229697 -0.345121 -0.91472 0.210189 -0.345121 -0.91472 0.210189 -0.368371 -0.91472 0.166104 -0.368371 -0.91472 0.166104 -0.386018 -0.91472 0.119491 -0.386018 -0.91472 0.119491 -0.397792 -0.91472 0.0710612 -0.397792 -0.91472 0.0710614 -0.403514 -0.91472 0.0215495 -0.403514 -0.91472 0.0215497 -0.403098 -0.91472 -0.0282897 -0.403098 -0.91472 -0.0282896 -0.396549 -0.91472 -0.077698 -0.396549 -0.91472 -0.0776983 -0.383967 -0.91472 -0.125925 -0.383967 -0.91472 -0.125925 -0.365544 -0.91472 -0.172236 -0.365546 -0.914719 -0.172236 -0.341562 -0.914719 -0.215928 -0.341559 -0.91472 -0.215928 -0.31238 -0.91472 -0.256332 -0.312381 -0.91472 -0.256332 -0.278449 -0.91472 -0.292839 -0.278445 -0.914721 -0.292838 -0.240277 -0.914721 -0.32489 -0.240282 -0.914719 -0.324891 -0.198456 -0.914719 -0.352001 -0.198458 -0.914718 -0.352001 -0.153615 -0.914718 -0.373755 -0.153613 -0.914719 -0.373754 -0.106433 -0.914719 -0.389822 -0.106429 -0.914721 -0.389819 -0.0576322 -0.914721 -0.399956 -0.0576342 -0.91472 -0.399958 -0.00795741 -0.91472 -0.404011 -0.00795955 -0.914719 -0.404013 0.0418372 -0.914719 -0.40192 0.0418409 -0.914721 -0.401914 0.0910004 -0.914721 -0.393706 0.0909986 -0.914719 -0.39371 0.138776 -0.914719 -0.379512 0.138776 -0.914719 -0.379514 0.184441 -0.914719 -0.359542 0.184442 -0.91472 -0.35954 0.227299 -0.91472 -0.3341 0.227299 -0.914719 -0.334101 0.266699 -0.914719 -0.303578 0.266699 -0.914721 -0.303575 0.297259 -0.914855 -0.273273 0.297259 -0.914854 -0.273274 -0.463597 -0.819792 0.336184 -0.489662 -0.819326 0.298221 -0.489661 -0.819328 0.298218 -0.522649 -0.819328 0.235669 -0.52265 -0.819327 0.235671 -0.547688 -0.819327 0.169535 -0.547687 -0.819327 0.169535 -0.564392 -0.819327 0.100822 -0.564392 -0.819327 0.100823 -0.572511 -0.819327 0.0305752 -0.572511 -0.819327 0.0305747 -0.57192 -0.819327 -0.0401375 -0.57192 -0.819327 -0.0401378 -0.562628 -0.819327 -0.110239 -0.562629 -0.819327 -0.110239 -0.544778 -0.819326 -0.178664 -0.544778 -0.819327 -0.178664 -0.51864 -0.819326 -0.24437 -0.518638 -0.819328 -0.244371 -0.484608 -0.819328 -0.30636 -0.484611 -0.819327 -0.30636 -0.44321 -0.819327 -0.363688 -0.443209 -0.819327 -0.363688 -0.395067 -0.819327 -0.415483 -0.395066 -0.819327 -0.415483 -0.340909 -0.819327 -0.46096 -0.340909 -0.819327 -0.46096 -0.281572 -0.819327 -0.49942 -0.28157 -0.819328 -0.499419 -0.217946 -0.819328 -0.530284 -0.21795 -0.819326 -0.530286 -0.151007 -0.819326 -0.553084 -0.151009 -0.819325 -0.553085 -0.0817746 -0.819325 -0.567468 -0.0817694 -0.819329 -0.567463 -0.0112878 -0.819329 -0.573213 -0.0112901 -0.819327 -0.573216 0.0593608 -0.819327 -0.570245 0.0593591 -0.819325 -0.570248 0.129109 -0.819325 -0.558603 0.129113 -0.819329 -0.558596 0.196896 -0.819329 -0.538453 0.196896 -0.81933 -0.538452 0.261685 -0.81933 -0.510118 0.261685 -0.81933 -0.510118 0.322494 -0.81933 -0.474022 0.322493 -0.819329 -0.474023 0.378397 -0.819329 -0.430716 0.378397 -0.819325 -0.430722 0.409602 -0.81981 -0.400172 0.405694 -0.834455 -0.372958 -0.572013 -0.693431 0.438125 -0.615643 -0.693108 0.374946 -0.615644 -0.693107 0.374948 -0.65712 -0.693107 0.296304 -0.657119 -0.693108 0.296304 -0.688597 -0.693108 0.213155 -0.688597 -0.693109 0.213153 -0.709599 -0.693109 0.126762 -0.709599 -0.693109 0.126762 -0.719807 -0.693109 0.0384412 -0.719807 -0.693109 0.0384416 -0.719064 -0.693109 -0.0504642 -0.719064 -0.693109 -0.0504641 -0.707382 -0.693109 -0.138602 -0.707382 -0.693109 -0.138602 -0.684938 -0.69311 -0.224632 -0.684939 -0.693108 -0.224631 -0.652076 -0.693108 -0.307243 -0.652077 -0.693107 -0.307242 -0.609293 -0.693107 -0.385182 -0.609291 -0.693108 -0.385182 -0.557241 -0.693108 -0.457257 -0.557237 -0.693111 -0.457257 -0.496706 -0.693111 -0.52238 -0.496711 -0.693107 -0.52238 -0.428624 -0.693106 -0.579556 -0.428618 -0.69311 -0.579555 -0.354012 -0.69311 -0.627912 -0.354016 -0.693107 -0.627913 -0.274022 -0.693107 -0.666719 -0.274021 -0.693108 -0.666719 -0.189863 -0.693108 -0.69538 -0.189857 -0.693114 -0.695376 -0.102809 -0.693114 -0.713459 -0.102813 -0.69311 -0.713462 -0.0141939 -0.69311 -0.720692 -0.014192 -0.693112 -0.72069 0.074634 -0.693112 -0.716956 0.0746331 -0.693111 -0.716957 0.162331 -0.693111 -0.702315 0.162327 -0.693105 -0.702322 0.247554 -0.693105 -0.676995 0.247555 -0.693107 -0.676993 0.329014 -0.693107 -0.641368 0.329014 -0.693107 -0.641367 0.405467 -0.693107 -0.595986 0.405467 -0.69311 -0.595982 0.475752 -0.69311 -0.541533 0.475752 -0.693111 -0.541532 0.530436 -0.693434 -0.487634 0.530436 -0.693432 -0.487638 0.761678 -0.0174164 -0.647722 -0.770455 -0.0933752 0.630619 -0.769689 -0.0174191 0.638181 -0.769547 -0.0198279 0.638283 -0.765258 -0.0263373 0.643185 -0.77281 -0.0462614 0.632949 -0.783635 -0.0462447 0.619498 -0.783549 -0.0462596 0.619606 -0.801746 -0.0461983 0.595877 -0.77082 -0.0410624 0.635728 -0.738997 -0.0515834 0.671731 -0.754582 -0.0486142 0.654402 -0.755494 -0.044584 0.653637 -0.713017 -0.0508358 0.699301 -0.701591 -0.0521096 0.710671 -0.758314 -0.0750194 0.647558 -0.767491 -0.0836386 0.63558 -0.8017 -0.0462357 0.595936 -0.847584 -0.046165 0.52865 -0.847585 -0.0461673 0.528648 -0.904421 -0.046167 0.424136 -0.90442 -0.0461638 0.424138 -0.948429 -0.0461641 0.313611 -0.948429 -0.0461633 0.313611 -0.978986 -0.0461638 0.198635 -0.978986 -0.0461647 0.198634 -0.995657 -0.0461646 0.0808421 -0.995657 -0.046164 0.0808426 -0.998207 -0.0461645 -0.0380967 -0.998207 -0.046164 -0.0380963 -0.986599 -0.0461645 -0.156496 -0.986599 -0.0461644 -0.156496 -0.960999 -0.0461644 -0.272673 -0.960999 -0.0461646 -0.272673 -0.921767 -0.0461646 -0.384986 -0.921766 -0.0461666 -0.384988 -0.869461 -0.0461671 -0.49184 -0.869462 -0.0461642 -0.491838 -0.804826 -0.0461642 -0.591712 -0.804826 -0.0461657 -0.591713 -0.728774 -0.0461659 -0.683197 -0.728775 -0.0461639 -0.683196 -0.642386 -0.0461638 -0.764989 -0.642388 -0.0461612 -0.764988 -0.546887 -0.0461609 -0.835933 -0.546885 -0.0461646 -0.835934 -0.443635 -0.0461646 -0.895018 -0.443633 -0.0461676 -0.895018 -0.334083 -0.0461678 -0.941413 -0.334086 -0.0461635 -0.941412 -0.219798 -0.0461635 -0.974453 -0.219795 -0.0461679 -0.974453 -0.102393 -0.0461679 -0.993672 -0.102395 -0.0461648 -0.993672 0.0164605 -0.0461648 -0.998798 0.0164646 -0.0461705 -0.998798 0.135084 -0.0461704 -0.989758 0.135081 -0.0461667 -0.989758 0.251793 -0.0461667 -0.966679 0.251794 -0.0461684 -0.966679 0.364927 -0.0461682 -0.929891 0.364925 -0.0461646 -0.929892 0.472884 -0.0461646 -0.879915 0.472887 -0.0461686 -0.879913 0.574139 -0.0461683 -0.817456 0.574139 -0.0461694 -0.817455 0.667249 -0.0461689 -0.743402 0.667245 -0.0461595 -0.743407 0.751711 -0.124448 -0.647644 0.754355 -0.0933349 -0.649798 0.759445 -0.0410625 -0.649275 0.75871 -0.0836412 -0.646037 0.768922 -0.0750211 -0.634926 0.821288 -0.0521074 -0.568129 0.812049 -0.0508314 -0.581371 0.77441 -0.0445784 -0.631112 0.745703 -0.0462452 -0.664672 0.725535 -0.0462307 -0.686631 0.72558 -0.0461982 -0.686585 0.74579 -0.0462593 -0.664573 0.757052 -0.0462618 -0.651715 0.774999 -0.0486105 -0.630091 0.78942 -0.0515898 -0.611682 0.765843 -0.0263417 -0.642488 0.761753 -0.019828 -0.647564 0.711352 -0.199748 -0.673854 0.736262 -0.163881 -0.656553 0.745228 -0.153834 -0.648822 0.752618 -0.148438 -0.641508 0.763959 -0.143213 -0.629172 0.794321 -0.132402 -0.592894 0.834882 -0.120904 -0.536986 0.792713 -0.113677 -0.598902 0.722324 -0.103723 -0.683732 0.740586 -0.103851 -0.663888 0.742101 -0.104025 -0.662166 0.752447 -0.10353 -0.650465 0.753486 -0.104024 -0.649183 0.765392 -0.107811 -0.63447 -0.843919 -0.103651 0.526362 -0.90051 -0.103651 0.422302 -0.900509 -0.103646 0.422305 -0.944328 -0.103647 0.312254 -0.944328 -0.103647 0.312254 -0.974752 -0.103647 0.197776 -0.974752 -0.103648 0.197776 -0.991352 -0.103648 0.080493 -0.991352 -0.103647 0.0804931 -0.993891 -0.103647 -0.0379316 -0.993891 -0.103648 -0.037932 -0.982333 -0.103647 -0.155819 -0.982333 -0.103647 -0.155819 -0.956843 -0.103647 -0.271494 -0.956843 -0.103647 -0.271494 -0.917781 -0.103647 -0.383321 -0.917781 -0.103647 -0.383321 -0.865702 -0.103647 -0.489711 -0.865702 -0.103647 -0.489711 -0.801345 -0.103647 -0.589155 -0.801346 -0.103646 -0.589154 -0.725624 -0.103645 -0.680241 -0.725621 -0.103649 -0.680243 -0.639607 -0.103649 -0.761683 -0.63961 -0.103643 -0.76168 -0.544524 -0.103643 -0.832317 -0.544521 -0.103647 -0.832318 -0.441713 -0.103647 -0.891149 -0.441715 -0.103644 -0.891148 -0.332639 -0.103644 -0.937341 -0.332635 -0.103649 -0.937342 -0.218847 -0.103649 -0.970239 -0.218849 -0.103647 -0.970238 -0.101949 -0.103647 -0.989375 -0.101953 -0.103642 -0.989376 0.0163864 -0.103642 -0.99448 0.016393 -0.103651 -0.994479 0.134503 -0.10365 -0.985477 0.1345 -0.103646 -0.985478 0.250701 -0.103646 -0.9625 0.250702 -0.103646 -0.9625 0.36335 -0.103646 -0.92587 0.363352 -0.103649 -0.925869 0.470842 -0.103649 -0.876108 0.470838 -0.103643 -0.87611 0.571655 -0.103644 -0.813922 0.571655 -0.103645 -0.813921 0.664361 -0.103645 -0.740191 0.664362 -0.103647 -0.740189 0.722201 -0.103806 -0.68385 -0.780511 -0.10402 0.616428 -0.7819 -0.103851 0.614692 -0.79844 -0.103722 0.593072 -0.798332 -0.103805 0.593204 -0.843918 -0.103647 0.526365 -0.769697 -0.10402 0.629878 -0.769657 -0.104038 0.629924 -0.775143 -0.103752 0.623208 -0.762002 -0.14845 0.63033 -0.75724 -0.107814 0.644177 -0.726943 -0.113679 0.677223 -0.673258 -0.120905 0.729456 -0.721308 -0.132401 0.679842 -0.75179 -0.143213 0.643663 -0.767892 -0.153812 0.62184 -0.773993 -0.163921 0.611609 -0.78062 -0.182035 0.597909 -0.569832 -0.0447088 -0.820544 -0.424174 -0.296212 -0.855766 -0.491109 -0.0065946 -0.871073 -0.320819 -0.282479 -0.904036 -0.380052 -0.0220186 -0.924703 -0.211917 -0.269103 -0.939508 -0.263215 -0.0368107 -0.964035 -0.0990834 -0.256095 -0.96156 -0.142437 -0.0510272 -0.988488 0.0159822 -0.243495 -0.96977 -0.0196544 -0.0645988 -0.997718 0.13156 -0.231307 -0.963944 0.103231 -0.077583 -0.991627 0.245909 -0.219579 -0.944094 0.224284 -0.0899085 -0.970367 0.357302 -0.208278 -0.91047 0.341648 -0.101617 -0.934318 0.464069 -0.197458 -0.863511 0.453526 -0.112708 -0.884088 0.564602 -0.187128 -0.803871 0.558217 -0.123165 -0.820503 0.657377 -0.177281 -0.732412 0.654138 -0.133019 -0.744587 0.726468 -0.161945 -0.667846 -0.619569 -0.0364257 -0.784097 -0.635708 -0.150902 -0.757036 -0.541201 -0.150903 -0.827242 -0.7928 -0.158013 0.588643 -0.840605 -0.135998 0.524297 -0.841171 -0.173154 0.512298 -0.897777 -0.129381 0.42102 -0.896823 -0.179377 0.404391 -0.942195 -0.123311 0.31155 -0.938784 -0.185032 0.290599 -0.973205 -0.117817 0.197462 -0.966465 -0.190098 0.172648 -0.990349 -0.112887 0.0804114 -0.979488 -0.194595 0.0523087 -0.993369 -0.108536 -0.0379116 -0.977692 -0.198519 -0.0686145 -0.982218 -0.104756 -0.155801 -0.961136 -0.201872 -0.188321 -0.95705 -0.101553 -0.271555 -0.930092 -0.20466 -0.305032 -0.918224 -0.0989314 -0.383506 -0.885041 -0.206892 -0.417011 -0.866295 -0.0968927 -0.490046 -0.826673 -0.208561 -0.522604 -0.802008 -0.0954359 -0.589639 -0.755863 -0.209681 -0.620246 -0.726282 -0.0945658 -0.680861 -0.702199 -0.151102 -0.695762 -0.657955 -0.151112 -0.73774 -0.0796998 0.988039 0.132014 -0.747037 0.0523174 0.66272 -0.583098 0.54655 0.601065 -0.0740917 0.970581 0.229091 -0.172008 0.821872 -0.543083 0.853541 0.0458643 -0.519002 0.85813 0.130484 -0.496575 0.858771 0.1161 -0.499033 0.857808 0.107839 -0.502529 0.865182 0.0881168 -0.493656 0.849969 0.0425344 -0.525112 0.85023 0.153541 -0.503522 0.856623 0.142775 -0.495794 0.837089 0.259393 -0.481661 0.812663 0.308264 -0.494521 0.807093 0.374637 -0.456342 0.688866 0.623735 -0.369348 0.708794 0.590312 -0.386191 0.731477 0.531206 -0.427506 0.750276 0.507981 -0.423133 0.785284 0.436306 -0.439278 0.652323 0.674959 -0.344826 0.607244 0.717321 -0.341622 0.580471 0.760946 -0.289853 0.325524 0.937355 -0.124098 0.345265 0.929658 -0.128565 0.458602 0.860809 -0.220665 0.425872 0.876679 -0.223757 0.512278 0.821892 -0.24913 0.344099 0.91939 0.190572 -0.166823 0.944375 -0.283417 -0.0861896 0.982513 -0.165047 0.0150986 0.999591 0.024299 0.0489285 0.996653 0.0654837 0.0545673 0.996086 0.0695359 0.0439098 0.997316 0.0585911 0.0598109 0.994864 0.0816577 0.060962 0.994584 0.0841838 -0.170441 0.947752 0.269657 -0.377754 0.816232 0.437112 -0.382554 0.813479 0.438069 -0.465089 0.717874 0.518024 -0.454462 0.738887 0.497504 -0.62893 0.474622 0.615777 -0.576514 0.528333 0.623295 -0.654378 0.363819 0.662891 -0.651076 0.368497 0.663559 -0.675104 0.26819 0.687247 -0.704914 0.188995 0.68365 -0.702468 0.168024 0.691598 -0.709562 0.125716 0.693338 -0.70744 0.120329 0.696455 -0.717449 0.087197 0.691132 -0.71294 0.0753307 0.697167 0.566155 0.71235 0.414761 0.278935 0.956103 -0.0897869 0.212876 0.975719 -0.051543 0.227817 0.972234 -0.0534832 0.0673063 0.997005 0.0380981 0.0810786 0.995882 0.0405597 0.0455708 0.9971 0.0609421 0.04831 0.99688 0.062419 0.0472725 0.996889 0.0630666 0.0526113 0.996322 0.0676423 0.0477737 0.996299 0.0714525 0.0559991 0.995838 0.0719106 0.0570081 0.995564 0.07485 0.676312 0.534181 -0.5072 0.66963 0.54116 -0.508667 0.570727 0.693477 -0.439728 0.563909 0.717618 -0.408695 0.502477 0.776923 -0.379352 0.406824 0.861465 -0.303929 0.465921 0.832642 -0.299375 0.256644 0.938883 -0.22942 0.333487 0.914326 -0.22977 0.179872 0.974875 -0.131399 0.176277 0.975617 -0.13076 0.053147 0.998569 -0.00597877 0.0759815 0.997094 -0.005539 0.0106795 0.999856 0.0132174 0.011474 0.999841 0.0136639 0.0121188 0.999814 0.0150238 0.012634 0.999807 0.0150453 0.012634 0.999807 0.0150452 0.76446 0.313291 -0.563427 0.739577 0.354902 -0.571901 0.709702 0.443883 -0.547075 0.78826 0.0549788 -0.612882 0.791451 0.052287 -0.608992 0.783392 0.109821 -0.611749 0.774691 0.121838 -0.620491 0.783301 0.146124 -0.604224 0.777704 0.175128 -0.603744 0.768242 0.235597 -0.59523 -0.720768 0.0359691 0.692242 -0.723281 0.0418531 0.689284 -0.757601 0.0423465 0.651343 -0.740403 0.0875091 0.666442 -0.747844 0.121849 0.652597 -0.744195 0.126303 0.655913 -0.712575 0.216874 0.667235 -0.729277 0.18949 0.657456 -0.686571 0.368769 0.626601 -0.68558 0.370182 0.626853 -0.617781 0.541192 0.570489 -0.625426 0.532796 0.570062 -0.526422 0.693283 0.492177 -0.0115226 0.996545 0.0822483 -0.0106751 0.996709 0.0803538 0.0147427 0.993405 0.113711 0.0074607 0.990804 0.1351 -0.149814 0.968998 0.196464 -0.157333 0.964893 0.210304 -0.116924 0.957625 0.263217 -0.247615 0.896013 0.368574 -0.23424 0.913262 0.333292 -0.299733 0.864071 0.404402 -0.224378 0.939954 0.257178 -0.290798 0.90263 0.317325 -0.289249 0.904155 0.314387 -0.357667 0.860425 0.362963 -0.406852 0.818001 0.406628 -0.424018 0.807359 0.410342 -0.504179 0.724434 0.470105 -0.579965 0.647738 0.494041 -0.527658 0.641827 0.556448 -0.537772 0.617377 0.574149 0.818426 0.0656488 -0.570849 0.830152 0.0547512 -0.554842 0.827226 0.108569 -0.55128 0.826805 0.109321 -0.551763 0.823821 0.143816 -0.548302 0.822873 0.145507 -0.549279 0.794853 0.309107 -0.522171 0.792629 0.312328 -0.523632 0.711356 0.53259 -0.458608 0.711397 0.532547 -0.458593 0.589223 0.718839 -0.3689 0.593513 0.715732 -0.368064 0.434263 0.863482 -0.256545 0.443313 0.859199 -0.255441 0.301222 0.940265 -0.158641 0.31036 0.936988 -0.160405 0.202734 0.975262 -0.0881107 0.212302 0.973061 -0.0898938 0.0592795 0.998173 0.0117074 0.0682032 0.997588 0.0129444 0.0298703 0.998813 0.0384727 0.0317282 0.998719 0.0394289 0.0310272 0.998721 0.0399198 0.034707 0.998472 0.042994 0.0339417 0.998472 0.0436148 0.0231414 0.999134 0.0345671 0.0248278 0.999146 0.0330396 0.0273388 0.999096 0.0325566 0.0273387 0.999096 0.0325566 -0.418319 -0.80704 0.416767 0.421209 -0.86096 -0.285185 -0.121648 -0.958691 0.257127 -0.708293 -0.125689 0.694639 -0.716063 -0.0862996 0.69268 -0.704649 -0.224071 0.673248 -0.706318 -0.141045 0.693701 -0.713262 -0.119195 0.690688 -0.696934 -0.188786 0.69184 -0.644951 -0.368111 0.669726 -0.655992 -0.354178 0.666508 -0.579749 -0.528704 0.61997 -0.599898 -0.50799 0.618117 -0.525668 -0.641527 0.558673 -0.515276 -0.652936 0.555126 -0.473044 -0.719407 0.508609 -0.414637 -0.775142 0.476688 0.0214074 -0.992441 0.120844 0.0622656 -0.994712 0.0816814 0.0591074 -0.994898 0.08176 0.28167 -0.956965 -0.0698648 0.222525 -0.974234 -0.0367525 0.226025 -0.973593 -0.0320711 0.461126 -0.860431 -0.216845 0.331777 -0.934813 -0.126688 0.328001 -0.936959 -0.120515 0.420314 -0.888168 -0.185725 0.475173 -0.835802 -0.275038 0.707121 -0.595173 -0.381771 0.679003 -0.63829 -0.362685 0.615578 -0.716331 -0.328532 0.619906 -0.701226 -0.352136 0.565829 -0.774837 -0.281897 0.742964 -0.491386 -0.454472 0.744917 -0.529808 -0.405465 0.816231 -0.340828 -0.46648 0.814309 -0.308167 -0.491868 0.84527 -0.223091 -0.485539 0.855624 -0.142817 -0.497504 0.848085 -0.155895 -0.506407 0.868477 -0.107476 -0.483939 0.85953 -0.117683 -0.497352 0.862145 -0.0705777 -0.501722 0.849728 -0.0481276 -0.52502 0.853902 -0.0355089 -0.519222 0.0514174 -0.99632 0.068583 0.048468 -0.996879 0.0623204 0.0471829 -0.99689 0.0631225 0.046683 -0.997088 0.0603064 0.072584 -0.996326 0.0454496 0.0756692 -0.996574 0.0333918 0.21614 -0.975244 -0.0467291 0.22443 -0.972751 -0.0582004 0.27147 -0.958647 -0.0854426 0.2795 -0.955867 -0.0905404 0.011474 -0.999841 0.0136639 0.0121188 -0.999814 0.0150238 0.0126339 -0.999807 0.0150453 0.316579 -0.91494 -0.250326 0.282264 -0.938884 -0.197036 0.177185 -0.975597 -0.129673 0.178547 -0.974891 -0.133073 0.0653407 -0.997696 -0.0182688 0.0576878 -0.998335 -0.000276985 0.0106795 -0.999856 0.0132174 0.676312 -0.534181 -0.5072 0.440974 -0.834328 -0.330814 0.502478 -0.776923 -0.379351 0.563909 -0.717618 -0.408694 0.570727 -0.693476 -0.439729 0.669629 -0.54116 -0.508667 0.788373 -0.0522975 -0.61297 0.791135 -0.0549725 -0.609166 0.781372 -0.121801 -0.612064 0.770193 -0.109853 -0.628279 0.792619 -0.174911 -0.58409 0.781162 -0.146138 -0.606984 0.768242 -0.235597 -0.59523 0.76446 -0.313291 -0.563427 0.739577 -0.354902 -0.571901 0.709702 -0.443882 -0.547075 -0.720604 -0.0418113 0.692085 -0.747395 -0.0422085 0.663038 -0.75397 -0.0523294 0.654821 -0.357667 -0.860425 0.362963 -0.289249 -0.904155 0.314387 -0.253397 -0.897382 0.361242 -0.220367 -0.908043 0.356226 -0.0106747 -0.996709 0.0803534 0.0203256 -0.992443 0.121014 -0.094682 -0.96323 0.251444 -0.290798 -0.90263 0.317325 -0.224377 -0.939955 0.257177 -0.157334 -0.964893 0.210304 -0.149814 -0.968998 0.196464 -0.0797021 -0.988038 0.132015 0.0264842 -0.999152 0.0315389 0.0256535 -0.999089 0.0341131 0.0273389 -0.999096 0.0325568 -0.0115225 -0.996545 0.0822485 -0.325217 -0.847964 0.418559 -0.383251 -0.813625 0.437187 -0.411293 -0.818697 0.400717 -0.504179 -0.724434 0.470105 -0.536451 -0.693608 0.480759 -0.55993 -0.645936 0.518888 -0.621122 -0.541293 0.566753 -0.62198 -0.532566 0.574033 -0.686021 -0.368757 0.627211 -0.686117 -0.370201 0.626255 -0.724453 -0.217042 0.654264 -0.722954 -0.189383 0.664433 -0.745564 -0.121841 0.655202 -0.748744 -0.126357 0.650705 -0.740403 -0.0875091 0.666442 -0.715389 -0.0871647 0.693268 -0.719294 -0.0435346 0.693341 0.818961 -0.0548425 -0.571222 0.829996 -0.0593767 -0.554599 0.827169 -0.109314 -0.551219 0.826859 -0.108576 -0.55183 0.823651 -0.145487 -0.548117 0.823037 -0.143834 -0.549474 0.794071 -0.312257 -0.521485 0.793422 -0.309159 -0.524312 0.711376 -0.532548 -0.458624 0.711376 -0.532589 -0.458577 0.591678 -0.715905 -0.370671 0.590995 -0.718726 -0.366276 0.439736 -0.859568 -0.260335 0.437698 -0.863207 -0.251582 0.308153 -0.937212 -0.163325 0.303343 -0.940081 -0.155665 0.209954 -0.973285 -0.0929329 0.205003 -0.975063 -0.0850078 0.0644917 -0.997884 0.00827487 0.0628951 -0.997884 0.0164868 0.0305811 -0.99881 0.0380005 0.0309997 -0.998721 0.0399397 0.0317922 -0.998718 0.0393847 0.0339187 -0.998472 0.0436334 0.158824 -0.987299 0.00391783 -0.151968 -0.957447 -0.245359 -0.0522471 -0.9905 -0.127203 0.0333283 -0.997955 0.0545356 0.0780593 -0.991416 0.104887 0.0592176 -0.995434 0.0748647 0.0436494 -0.997348 0.0582444 0.0584934 -0.995078 0.0799878 0.0490504 -0.996309 0.0704473 0.0570155 -0.995685 0.0732145 0.0339417 -0.998472 0.0436148 0.0231414 -0.999134 0.0345671 0.012634 -0.999807 0.0150452 0.961599 0.169442 0.215909 0.408753 0.00866906 0.912604 -0.0643364 0.0240882 0.997638 0.699146 0.711401 -0.0714395 0.640258 0.767763 -0.0246942 0.639435 0.768329 -0.0281694 0.57558 0.817475 0.0210338 0.572712 0.819646 0.0134774 0.482577 0.87182 0.0839632 0.478803 0.874705 0.0750936 0.410168 0.902777 0.129446 0.408635 0.904191 0.124321 0.336779 0.92426 0.179788 0.331265 0.928307 0.16885 0.231572 0.940997 0.246776 0.225874 0.944935 0.236808 0.198633 0.94536 0.258533 0.203566 0.942478 0.265136 0.206014 0.942481 0.263225 0.206126 0.942407 0.263401 0.203714 0.942403 0.265287 0.209809 0.938767 0.273306 0.209476 0.938766 0.273567 0.218026 0.933462 0.284803 0.164311 0.930995 0.325959 0.17342 0.924278 0.340051 0.0843053 0.908282 0.409776 0.0893067 0.904647 0.416699 0.0165318 0.880388 0.473967 0.0169874 0.88004 0.474595 -0.0492901 0.848938 0.52619 -0.0528993 0.851366 0.521898 -0.124484 0.806599 0.577843 -0.131236 0.81085 0.57035 -0.191009 0.763009 0.617521 -0.193584 0.765092 0.614133 -0.266825 0.692518 0.670242 -0.268291 0.693326 0.668819 -0.351936 0.580047 0.734634 -0.349071 0.578709 0.737052 -0.386298 0.512328 0.767003 -0.385195 0.511357 0.768205 -0.417634 0.443918 0.792792 -0.413734 0.442532 0.795606 -0.451309 0.340061 0.825033 -0.452163 0.340319 0.824458 -0.475733 0.25039 0.843198 -0.480842 0.252006 0.839812 -0.497976 0.156782 0.8529 -0.505289 0.158254 0.848315 -0.510443 0.113045 0.852449 -0.512511 0.113263 0.851178 -0.515831 0.0707426 0.853764 -0.519264 0.0710393 0.851656 -0.520861 0.0337711 0.852973 -0.522434 0.0339267 0.852004 0.408877 0.00865452 0.912549 0.409262 0.018205 0.912235 0.410097 0.0180944 0.911862 0.41095 0.0289759 0.911197 0.411369 0.0288998 0.911011 0.412634 0.0403116 0.910004 0.413999 0.0398927 0.909403 0.418467 0.0641202 0.905966 0.419532 0.063588 0.905511 0.425437 0.0865266 0.900842 0.425571 0.0864507 0.900786 0.435126 0.112557 0.893306 0.434348 0.113129 0.893613 0.442849 0.130161 0.887098 0.442586 0.130557 0.887171 0.451824 0.147662 0.879802 0.451238 0.148291 0.879997 0.472527 0.177388 0.86328 0.472858 0.176904 0.863198 0.491712 0.194931 0.848659 0.492074 0.194074 0.848645 0.507168 0.206381 0.836772 0.508141 0.204297 0.836693 0.526263 0.215621 0.82253 0.526657 0.214564 0.822554 0.54345 0.222341 0.809461 0.543388 0.222577 0.809437 0.561856 0.228895 0.794937 0.561498 0.230576 0.794704 0.584224 0.234682 0.776921 0.583809 0.238286 0.776136 0.597457 0.238503 0.765612 0.59704 0.241401 0.765029 0.597129 0.241401 0.764959 0.596823 0.243513 0.764528 0.597444 0.243517 0.764042 0.597441 0.24355 0.764033 0.596823 0.243551 0.764517 0.596593 0.245192 0.764171 0.603492 0.245317 0.758694 0.603548 0.243245 0.759317 0.629267 0.239962 0.739217 0.62906 0.237552 0.740171 0.647373 0.232064 0.725986 0.647083 0.231145 0.726537 0.664721 0.224297 0.712627 0.664289 0.222609 0.713559 0.687269 0.209316 0.695592 0.686769 0.208031 0.696471 0.702823 0.19526 0.684042 0.70248 0.194772 0.684533 0.717587 0.180749 0.672606 0.717115 0.180016 0.673306 0.735268 0.157962 0.659113 0.734802 0.157433 0.659758 0.746514 0.138845 0.650722 0.746264 0.138691 0.651042 0.756689 0.119409 0.642778 0.756493 0.119276 0.643033 -0.0632938 0.0239851 0.997707 -0.0622122 0.050426 0.996788 -0.0598969 0.0501851 0.996942 -0.0575348 0.0803317 0.995106 -0.0559906 0.0801179 0.995212 -0.0524318 0.112014 0.992322 -0.0477586 0.110889 0.992685 -0.0354368 0.178114 0.983372 -0.0318835 0.176743 0.98374 -0.0154616 0.240257 0.970586 -0.0148618 0.240007 0.970657 0.0116379 0.312371 0.949889 0.0089736 0.313771 0.949456 0.0324335 0.361244 0.931907 0.0317458 0.361987 0.931643 0.0575471 0.409259 0.910602 0.0554164 0.410815 0.910033 0.11445 0.491277 0.863451 0.115437 0.490357 0.863843 0.167791 0.541013 0.824106 0.169329 0.538914 0.825167 0.211265 0.572885 0.791941 0.215264 0.568064 0.794333 0.265621 0.599536 0.754985 0.267609 0.596797 0.756451 0.314262 0.618513 0.720196 0.314029 0.618903 0.719962 0.36516 0.636214 0.679624 0.362775 0.640439 0.676928 0.425728 0.651778 0.627647 0.421814 0.660019 0.621649 0.460079 0.661162 0.592615 0.456446 0.667937 0.587807 0.456697 0.667938 0.587612 0.454111 0.672691 0.584183 0.455838 0.672695 0.582832 0.455805 0.672767 0.582775 0.454069 0.672767 0.584127 0.451967 0.676645 0.581271 0.47123 0.676685 0.56572 0.473267 0.671656 0.569998 0.544299 0.662604 0.514484 0.545939 0.65712 0.519754 0.596915 0.642384 0.480661 0.597035 0.640359 0.483208 0.645621 0.620963 0.444498 0.646234 0.617026 0.449067 0.709945 0.580161 0.399239 0.710109 0.577164 0.40327 0.755015 0.542103 0.368886 0.754797 0.541098 0.370802 0.796395 0.501796 0.337574 0.796181 0.500008 0.340718 0.846601 0.438742 0.301282 0.846299 0.437598 0.303787 0.879302 0.386201 0.278708 0.8791 0.385962 0.279671 0.907645 0.33212 0.256667 0.90741 0.33173 0.257997 0.861848 0.472523 -0.184229 0.821511 0.549565 -0.15198 0.821169 0.549601 -0.153692 0.801947 0.58113 -0.138452 0.792768 0.605994 -0.0655044 0.767661 0.629946 -0.117748 0.700942 0.710173 -0.0658371 0.93543 0.331841 -0.121869 0.890946 0.405996 -0.203426 0.862425 0.472323 -0.182026 0.77587 0.0608762 0.627949 0.77596 0.0608958 0.627836 0.779951 0.0359276 0.624809 0.779931 0.0359265 0.624834 0.780528 0.0306038 0.624371 0.780514 0.0306033 0.624389 0.780843 0.0272226 0.624134 0.780819 0.0272259 0.624164 0.781389 0.0206848 0.623701 0.781435 0.0206879 0.623644 0.781995 0.00993624 0.623205 0.781995 0.00993625 0.623205 0.961695 0.16948 0.215452 0.973204 0.100081 0.207023 0.973193 0.100081 0.207075 0.974881 0.0852108 0.205781 0.974847 0.0852115 0.205942 0.975775 0.0757886 0.205229 0.975771 0.0757907 0.205248 0.977283 0.0575979 0.203964 0.977309 0.0576011 0.203834 0.978867 0.0276885 0.202613 0.978986 0.027682 0.202039 0.767745 0.09121 0.634231 0.76759 0.0911428 0.634428 0.938677 0.253681 0.233518 0.938597 0.253606 0.233921 0.907144 0.361052 -0.216175 0.939849 0.241302 -0.241779 0.939639 0.241289 -0.242605 0.956342 0.142644 -0.255075 0.956284 0.142631 -0.2553 0.95871 0.121407 -0.25717 0.958773 0.12142 -0.256928 0.960102 0.107998 -0.257954 0.960106 0.108 -0.257938 0.962201 0.08207 -0.259682 0.962138 0.0820678 -0.259914 0.964356 0.0394539 -0.261651 0.964107 0.0394282 -0.262572 0.408397 -0.0105692 0.912743 0.964189 -0.0329423 -0.263162 0.78175 -0.0165611 0.623372 0.959923 -0.109499 -0.257988 0.963243 -0.0656366 -0.260489 0.963132 -0.0656701 -0.26089 0.964517 -0.0330035 -0.26195 0.979252 -0.0231646 0.201319 0.870287 -0.455149 -0.188256 0.920659 -0.317101 -0.22767 0.920748 -0.317034 -0.227403 0.946656 -0.207403 -0.246628 0.980012 -0.165494 -0.110397 0.955957 -0.144732 -0.25534 0.959791 -0.109539 -0.258463 0.752034 -0.651202 -0.101885 0.792765 -0.594921 -0.132638 0.828074 -0.550258 -0.107288 0.818729 -0.554281 -0.149849 0.869447 -0.455835 -0.190462 0.421731 -0.898782 0.119725 0.468617 -0.879556 0.082335 0.474118 -0.875921 0.089297 0.551982 -0.833366 0.0285972 0.555882 -0.83057 0.0338787 0.626123 -0.77944 -0.0210826 0.725481 -0.670389 0.155743 0.688109 -0.723321 -0.0575532 0.749734 -0.653116 -0.106486 0.78167 -0.0165454 0.623473 0.78087 -0.0276127 0.624083 0.78091 -0.0276226 0.624032 0.778874 -0.0448962 0.625572 0.778894 -0.044906 0.625546 0.771227 -0.0800707 0.631505 0.771281 -0.0801139 0.631433 0.758536 -0.115005 0.641402 0.758809 -0.11533 0.641021 0.744711 -0.141722 0.652166 0.744937 -0.142139 0.651817 0.729502 -0.164893 0.663806 0.729871 -0.165752 0.663185 0.705939 -0.192007 0.68175 0.706385 -0.19358 0.680842 0.682011 -0.211407 0.70012 0.682137 -0.212815 0.699571 0.662234 -0.223789 0.715098 0.662252 -0.225563 0.714523 0.63516 -0.235629 0.735561 0.634912 -0.238823 0.734745 0.603404 -0.243275 0.759422 0.602986 -0.245245 0.75912 0.595744 -0.245124 0.764855 0.596048 -0.24363 0.765096 0.597498 -0.243633 0.763962 0.597531 -0.243446 0.763996 0.596808 -0.243444 0.764562 0.597202 -0.241083 0.765002 0.597063 -0.24108 0.765112 0.597447 -0.238823 0.76552 0.587282 -0.238706 0.773382 0.58813 -0.235499 0.773721 0.555489 -0.229514 0.799222 0.556297 -0.227559 0.799219 0.525712 -0.214578 0.823154 0.524713 -0.216275 0.823347 0.502655 -0.201133 0.840764 0.501375 -0.202607 0.841174 0.481544 -0.185387 0.85659 0.480731 -0.186126 0.856887 0.456483 -0.156914 0.875786 0.457103 -0.156499 0.875537 0.436898 -0.121859 0.891219 0.438379 -0.121114 0.890593 0.42451 -0.0843456 0.901486 0.424086 -0.0844732 0.901674 0.416931 -0.0532126 0.907379 0.41494 -0.0534123 0.90828 0.412316 -0.0338155 0.910413 0.411929 -0.0338323 0.910588 0.411376 -0.0286173 0.911016 0.41107 -0.0286315 0.911154 0.410407 -0.0207476 0.911666 0.409766 -0.0207676 0.911954 0.409217 -0.0104874 0.912377 -0.0651394 -0.0292509 0.997447 0.782223 -0.00834708 0.622943 0.78209 -0.00832609 0.62311 0.979022 -0.0232047 0.202428 0.978061 -0.0460933 0.203157 0.978006 -0.0460639 0.203424 0.975713 -0.0768569 0.205125 0.975769 -0.0768924 0.20485 0.969852 -0.125069 0.209151 0.969834 -0.125043 0.209253 0.948366 -0.222735 0.22581 0.948396 -0.222814 0.225608 0.912983 -0.319828 0.253323 0.913099 -0.32049 0.252066 0.874403 -0.39407 0.283068 0.874406 -0.395136 0.281571 0.831238 -0.458164 0.314848 0.831099 -0.460167 0.312283 0.764242 -0.532595 0.363698 0.763548 -0.536587 0.359262 0.696649 -0.586683 0.412896 0.695603 -0.589794 0.41022 0.640413 -0.620073 0.453189 0.638638 -0.624405 0.449732 0.56343 -0.651751 0.507708 0.55981 -0.659049 0.502262 0.473036 -0.671488 0.570387 0.469949 -0.676303 0.56724 0.449795 -0.676234 0.583431 0.451722 -0.673148 0.585508 0.455777 -0.67316 0.582343 0.456118 -0.672579 0.582747 0.454099 -0.672576 0.584325 0.457233 -0.667096 0.58815 0.456831 -0.667096 0.588462 0.459754 -0.661973 0.591962 0.431106 -0.661327 0.613836 0.436538 -0.653298 0.618576 0.34611 -0.636628 0.689139 0.349794 -0.632222 0.691331 0.265043 -0.596316 0.757734 0.26082 -0.600352 0.756009 0.199684 -0.558892 0.804839 0.195053 -0.562094 0.803744 0.139969 -0.513999 0.846294 0.137217 -0.51554 0.845807 0.0700797 -0.434473 0.897955 0.07196 -0.433679 0.898189 0.0160342 -0.33741 0.941221 0.0209398 -0.335803 0.9417 -0.0175325 -0.233995 0.97208 -0.0191014 -0.234298 0.971977 -0.0390189 -0.147948 0.988225 -0.045637 -0.148245 0.987897 -0.0530359 -0.0938069 0.994177 -0.0543092 -0.0938182 0.994107 -0.055838 -0.0793537 0.995281 -0.0571334 -0.0793745 0.995206 -0.0589609 -0.0575457 0.9966 -0.0609563 -0.0575644 0.996479 -0.0624706 -0.0290341 0.997624 -0.52275 -0.0410997 0.851495 -0.51972 -0.0408734 0.853359 -0.517624 -0.0810967 0.851756 -0.514703 -0.0811806 0.853516 -0.512163 -0.111932 0.851563 -0.510321 -0.111998 0.85266 -0.508185 -0.13241 0.851009 -0.506267 -0.132512 0.852135 -0.495354 -0.209172 0.843132 -0.485566 -0.20962 0.848696 -0.456771 -0.331494 0.825513 -0.454698 -0.331367 0.826708 -0.399948 -0.475398 0.783606 -0.406743 -0.476302 0.779549 -0.328312 -0.612702 0.718894 -0.330795 -0.613093 0.717421 -0.236373 -0.727661 0.643923 -0.232277 -0.726755 0.646432 -0.154744 -0.795165 0.586317 -0.146991 -0.792936 0.591309 -0.0598352 -0.850763 0.522133 -0.0523938 -0.84759 0.528059 0.0680792 -0.898473 0.433719 0.0609879 -0.902018 0.427369 0.189145 -0.925792 0.327312 0.17668 -0.932634 0.314607 0.217234 -0.934074 0.283399 0.210409 -0.938125 0.275044 0.210999 -0.938128 0.274583 0.203745 -0.942312 0.265587 0.206589 -0.942317 0.263363 0.205843 -0.942732 0.26246 0.200183 -0.94271 0.26688 0.195725 -0.945065 0.26181 0.224048 -0.944744 0.239293 0.231828 -0.940732 0.247547 0.299239 -0.933834 0.195984 0.40798 -0.882614 0.23355 0.406607 -0.884017 0.23062 0.417076 -0.899425 0.130701 0.615944 -1.52835e-05 0.78779 0.615939 -1.85412e-06 0.787794 0.615969 9.14626e-06 0.787771 0.615969 -4.28649e-06 0.787771 0.615954 2.18883e-05 0.787782 0.615952 1.86869e-07 0.787784 0.61595 3.35367e-07 0.787785 0.61595 1.9583e-06 0.787785 0.615964 1.21448e-05 0.787774 0.615946 1.72776e-06 0.787788 0.615944 1.61097e-06 0.78779 0.615944 1.49203e-06 0.78779 0.615934 -3.77492e-08 0.787797 0.615934 9.70663e-07 0.787798 0.615944 3.47321e-06 0.78779 0.615944 -1.26038e-06 0.78779 0.615955 1.95626e-06 0.787781 0.615959 -2.8117e-06 0.787779 0.615961 1.36777e-05 0.787776 0.615959 -5.76624e-06 0.787778 0.615955 -1.19144e-07 0.787781 0.615963 2.43428e-05 0.787775 0.615971 2.02345e-06 0.787769 0.615956 -8.75525e-06 0.78778 0.615967 2.64924e-06 0.787772 0.615966 9.31883e-06 0.787773 0.615955 -6.26516e-06 0.787782 0.615949 1.64569e-05 0.787786 0.615944 -7.64063e-07 0.78779 0.615956 -4.5399e-06 0.787781 0.615955 -6.79634e-06 0.787781 0.615955 -5.442e-06 0.787782 0.615955 -4.81208e-06 0.787781 0.615953 -4.89898e-07 0.787783 0.615954 8.09458e-06 0.787782 0.615955 7.57151e-06 0.787782 0.615952 -3.49803e-05 0.787784 0.615947 -1.43374e-05 0.787788 0.615949 4.07996e-07 0.787786 0.615954 -1.33253e-05 0.787783 0.615963 -1.43766e-06 0.787776 0.61596 1.68971e-06 0.787777 0.615962 1.17734e-06 0.787776 0.615953 -3.12138e-06 0.787783 0.615964 9.39164e-06 0.787774 0.615962 -4.92303e-06 0.787776 0.615956 -2.17e-05 0.787781 0.61595 8.17558e-06 0.787785 0.615957 8.4204e-06 0.78778 0.615955 -5.4505e-06 0.787781 0.615954 -5.54216e-06 0.787782 0.615953 4.31722e-06 0.787783 0.615946 5.54472e-06 0.787788 0.615946 5.05609e-06 0.787789 0.615966 -1.15166e-05 0.787773 0.615966 -1.16949e-05 0.787773 0.615953 -2.86276e-07 0.787783 0.615951 -2.09872e-06 0.787785 0.615959 -1.06467e-05 0.787779 0.61596 -1.03417e-05 0.787778 0.615939 3.29897e-05 0.787794 0.615954 2.34352e-05 0.787782 0.615961 -2.97699e-06 0.787777 0.615952 1.13165e-05 0.787784 0.615953 5.95711e-06 0.787783 0.615955 4.06104e-06 0.787781 0.615954 1.61457e-05 0.787782 0.615959 -1.37093e-05 0.787778 0.615949 -5.83851e-06 0.787786 0.61595 -2.62462e-06 0.787786 0.615954 -2.84921e-05 0.787782 0.615961 1.87268e-05 0.787777 0.615964 9.82681e-06 0.787774 0.615949 -1.02522e-05 0.787786 0.615949 -7.07458e-06 0.787786 0.615946 -5.74748e-06 0.787788 0.615968 2.31891e-05 0.787772 0.615958 2.15117e-06 0.787779 0.615958 2.28733e-06 0.787779 0.615955 -3.10935e-06 0.787781 0.615953 1.22151e-05 0.787783 0.615963 2.62444e-06 0.787775 0.615961 2.16411e-06 0.787776 0.615961 3.23823e-06 0.787777 0.615954 -2.72445e-07 0.787782 0.615946 1.76096e-05 0.787788 0.615953 2.3025e-05 0.787783 0.615955 7.95121e-06 0.787781 0.615954 9.7029e-06 0.787782 0.615954 1.42848e-05 0.787782 0.615954 1.85212e-05 0.787782 0.615954 1.74536e-05 0.787782 0.615955 8.83156e-06 0.787782 0.615957 8.59262e-06 0.78778 0.615959 -3.47278e-06 0.787778 0.615949 1.00187e-05 0.787786 0.615947 -8.13404e-06 0.787788 0.615957 5.63095e-06 0.78778 0.615961 2.61613e-06 0.787777 0.61596 1.92651e-06 0.787777 0.61596 2.00775e-06 0.787777 0.615949 -1.86976e-06 0.787786 0.615949 -1.83048e-06 0.787786 0.615953 -6.0287e-07 0.787783 0.615953 -2.23316e-06 0.787783 0.61596 -4.71222e-07 0.787778 0.615958 1.45587e-06 0.787779 0.615957 1.31747e-06 0.78778 0.615956 -1.72892e-06 0.78778 0.615955 -1.79256e-06 0.787781 0.615956 -1.09479e-06 0.78778 0.615966 -1.94268e-07 0.787773 0.615962 -4.3988e-06 0.787776 0.615947 -7.1024e-06 0.787788 0.61595 3.40374e-06 0.787785 0.61595 3.40817e-06 0.787785 0.615948 -1.12489e-06 0.787786 0.615951 -1.35232e-06 0.787784 0.615957 5.11966e-07 0.78778 0.615962 5.33783e-07 0.787776 0.615962 5.59953e-07 0.787776 0.615949 2.44719e-06 0.787786 0.615953 1.01783e-05 0.787783 0.615958 6.95259e-06 0.787779 0.615951 1.29428e-05 0.787784 0.615947 9.1614e-06 0.787788 0.615961 -5.4107e-06 0.787777 0.615952 -1.51666e-05 0.787784 0.615958 -2.03632e-05 0.787779 0.615963 -9.48047e-06 0.787775 0.61595 4.04123e-06 0.787785 0.615947 1.21559e-06 0.787787 0.615955 -1.24268e-05 0.787781 0.615954 -1.32384e-05 0.787782 0.615955 -1.24568e-05 0.787781 0.615956 -1.53292e-05 0.787781 0.615955 -1.55334e-05 0.787781 0.615954 4.51367e-06 0.787782 0.615953 -6.98821e-06 0.787783 0.615954 -2.36861e-06 0.787782 -0.295934 -0.0329287 0.954641 0.108435 -0.0218668 0.993863 0.5983 -0.000890789 0.801271 0.433297 -0.00762052 0.901219 -0.784692 -0.0400544 0.61859 0.962436 -0.0399554 -0.268551 0.819287 -0.0399953 -0.571986 0.988473 -0.0288362 0.148623 0.999249 -0.033567 -0.0193835 0.919856 -0.0214938 0.391667 0.753677 -0.00612086 0.657216 -0.754547 -0.038248 0.655131 -0.752374 -0.0834474 0.65343 -0.75268 -0.0834305 0.65308 -0.748837 -0.129008 0.650077 -0.748326 -0.129035 0.650659 -0.742489 -0.176847 0.646092 -0.743263 -0.176499 0.645297 -0.727092 -0.266915 0.63253 -0.727665 -0.266821 0.63191 -0.69088 -0.398625 0.603144 -0.690225 -0.398719 0.603831 -0.654648 -0.489383 0.576143 -0.653938 -0.489597 0.576766 -0.612141 -0.573922 0.543964 -0.609614 -0.574199 0.546504 -0.540493 -0.682168 0.492458 -0.536703 -0.682468 0.496172 -0.466516 -0.766518 0.441376 -0.46268 -0.766837 0.444846 -0.385915 -0.838478 0.384741 -0.379986 -0.838586 0.390365 -0.285991 -0.904326 0.316866 -0.278703 -0.904165 0.323744 -0.195043 -0.946127 0.258462 -0.188753 -0.945923 0.263823 -0.102124 -0.975281 0.195952 -0.0923159 -0.974336 0.205298 0.0124082 -0.992278 0.123413 0.023596 -0.990649 0.134379 0.0766146 -0.99269 0.0932541 0.0715063 -0.993647 0.086909 0.0717995 -0.993646 0.0866796 0.0678813 -0.994329 0.0818711 0.0683413 -0.994327 0.0815115 0.0661365 -0.994683 0.0789396 0.0662926 -0.994682 0.0788175 0.0562018 -0.996223 0.0661847 0.0864219 -0.995352 0.0424949 0.0750178 -0.996716 0.0305 0.167094 -0.985071 -0.0414023 0.159484 -0.985988 -0.0489064 0.246023 -0.962223 -0.116617 0.243003 -0.962599 -0.119803 0.332565 -0.92378 -0.18982 0.336827 -0.923167 -0.185231 0.774522 -0.364546 -0.516936 0.744394 -0.450072 -0.493267 0.745813 -0.44957 -0.491579 0.711588 -0.526788 -0.464906 0.714801 -0.525945 -0.460913 0.656938 -0.628976 -0.415718 0.659112 -0.628392 -0.413153 0.601945 -0.708596 -0.368176 0.601888 -0.708624 -0.368215 0.559787 -0.757749 -0.335344 0.440371 -0.791512 -0.423772 0.502369 -0.811504 -0.298473 0.428867 -0.870591 -0.241132 0.373396 -0.86651 -0.331265 0.387701 -0.893936 -0.224871 0.720793 -0.249045 -0.646865 0.797114 -0.28378 -0.53299 0.775219 -0.364391 -0.515999 0.431909 -0.00761609 0.901885 0.432404 -0.0179999 0.9015 0.432299 -0.0180046 0.90155 0.433131 -0.0278411 0.900901 0.43329 -0.0278261 0.900825 0.434531 -0.03808 0.899852 0.43437 -0.0380557 0.89993 0.437525 -0.0577111 0.897352 0.437293 -0.0577472 0.897463 0.445238 -0.0862887 0.891245 0.445387 -0.0862422 0.891175 0.453411 -0.105653 0.885018 0.453587 -0.105608 0.884933 0.462328 -0.124065 0.877987 0.462724 -0.123845 0.877809 0.477653 -0.147181 0.866133 0.478213 -0.146758 0.865895 0.493473 -0.164713 0.854022 0.494007 -0.164238 0.853805 0.510396 -0.179796 0.840933 0.511206 -0.178831 0.840647 0.531307 -0.192897 0.824927 0.53209 -0.191694 0.824702 0.549996 -0.200404 0.810767 0.550581 -0.199388 0.81062 0.568885 -0.205848 0.796239 0.56957 -0.204156 0.796185 0.591628 -0.207943 0.778933 0.592246 -0.20573 0.779051 0.603245 -0.20573 0.770565 0.603107 -0.206719 0.770408 0.603162 -0.206719 0.770366 0.603021 -0.207693 0.770214 0.603108 -0.207691 0.770146 0.603026 -0.208189 0.770076 0.603051 -0.208189 0.770056 0.602746 -0.210401 0.769694 0.609073 -0.21033 0.764717 0.608598 -0.212949 0.76437 0.628142 -0.210288 0.749144 0.62796 -0.211787 0.748874 0.646549 -0.206809 0.734305 0.646541 -0.207401 0.734145 0.665897 -0.198995 0.719015 0.66583 -0.198195 0.719298 0.684096 -0.187003 0.705013 0.683821 -0.185476 0.705682 0.704124 -0.168656 0.689757 0.703949 -0.168052 0.690083 0.719137 -0.150255 0.678428 0.719134 -0.150229 0.678437 0.731476 -0.133667 0.668638 0.731608 -0.133915 0.668444 0.743852 -0.111953 0.658901 0.744182 -0.112407 0.658451 0.751356 -0.0958692 0.652896 0.751531 -0.0960988 0.652661 0.758142 -0.0779094 0.647418 0.758024 -0.077811 0.647568 0.76438 -0.0529903 0.642585 0.763375 -0.0523991 0.643827 0.766692 -0.0303153 0.641299 0.766158 -0.0301339 0.641946 0.766783 -0.0241005 0.641454 0.766526 -0.0240322 0.641764 0.767073 -0.0169695 0.641336 0.766831 -0.0169182 0.641626 0.767235 -0.00878436 0.641306 0.632797 0.00792683 0.774277 0.962398 -0.0224313 0.270716 0.961189 -0.0477857 0.271723 0.96156 -0.0479556 0.270376 0.960018 -0.0678868 0.271584 0.960333 -0.0680671 0.27042 0.958581 -0.0851007 0.271809 0.959191 -0.0855544 0.269504 0.949521 -0.147941 0.276628 0.950586 -0.149422 0.27214 0.932772 -0.219211 0.286153 0.932873 -0.219431 0.285653 0.914591 -0.270679 0.300428 0.914478 -0.270142 0.301254 0.894052 -0.316637 0.316879 0.893829 -0.315496 0.318641 0.859213 -0.377324 0.345515 0.859167 -0.376675 0.346335 0.82482 -0.42387 0.374174 0.824822 -0.423861 0.37418 0.781095 -0.473613 0.406917 0.780939 -0.475101 0.40548 0.723943 -0.522573 0.45036 0.723174 -0.526567 0.44693 0.671886 -0.557997 0.48704 0.671294 -0.560132 0.485404 0.616935 -0.583727 0.527877 0.617481 -0.582235 0.528885 0.565305 -0.59635 0.569909 0.567037 -0.592673 0.572021 0.511756 -0.600011 0.614892 0.515087 -0.59364 0.618285 0.497192 -0.593944 0.63248 0.499767 -0.588337 0.635682 0.499692 -0.58834 0.635739 0.50027 -0.587158 0.636377 0.500018 -0.58716 0.636573 0.501 -0.58504 0.637752 0.500844 -0.585041 0.637874 0.50216 -0.582144 0.639487 0.470657 -0.581762 0.663351 0.467328 -0.587126 0.660975 0.405134 -0.576447 0.70963 0.401645 -0.580987 0.707909 0.350111 -0.56299 0.748642 0.347694 -0.565435 0.747926 0.297187 -0.540688 0.786979 0.294017 -0.543635 0.786139 0.237374 -0.504013 0.830436 0.234657 -0.506067 0.829959 0.188542 -0.462428 0.866379 0.186665 -0.46351 0.866207 0.143748 -0.41286 0.899379 0.14173 -0.413869 0.899236 0.0997691 -0.348278 0.932067 0.0983474 -0.348806 0.93202 0.0737345 -0.297148 0.95198 0.0732668 -0.29721 0.951997 0.0507675 -0.242425 0.968841 0.0503744 -0.242505 0.968842 0.0280474 -0.162309 0.986341 0.0284741 -0.162271 0.986335 0.019535 -0.107227 0.994043 0.0198581 -0.107283 0.99403 0.0163496 -0.0783211 0.996794 0.0160832 -0.0783375 0.996797 0.0137435 -0.0506605 0.998621 0.0139162 -0.050656 0.998619 0.0126609 -0.0242741 0.999625 -0.13155 -0.0218123 0.99107 0.988503 -0.0341295 -0.1473 0.986801 -0.0702585 -0.145905 0.986446 -0.0704798 -0.148181 0.984182 -0.0997534 -0.146408 0.98386 -0.0999811 -0.148401 0.981304 -0.124964 -0.146378 0.980685 -0.125495 -0.150026 0.966207 -0.216904 -0.139271 0.964642 -0.218758 -0.147009 0.938652 -0.320794 -0.126582 0.938451 -0.321047 -0.127428 0.911995 -0.396234 -0.106127 0.912453 -0.395567 -0.104675 0.882325 -0.46352 -0.0815629 0.883328 -0.462162 -0.0783494 0.832502 -0.552657 -0.0388559 0.83317 -0.551772 -0.0370789 0.78325 -0.621699 0.0032432 0.783227 -0.621727 0.0032163 0.718472 -0.693613 0.0519548 0.716889 -0.695476 0.048819 0.633709 -0.765088 0.114253 0.629753 -0.769339 0.10737 0.554937 -0.815188 0.165874 0.552776 -0.817315 0.162588 0.473498 -0.851692 0.224544 0.475156 -0.850186 0.226738 0.398928 -0.871031 0.286637 0.403443 -0.867295 0.291605 0.322418 -0.877703 0.354521 0.329872 -0.871679 0.362436 0.303578 -0.872326 0.38326 0.309893 -0.866578 0.391164 0.309776 -0.866579 0.391255 0.311136 -0.86538 0.392825 0.310754 -0.865382 0.393123 0.313186 -0.863146 0.396098 0.312946 -0.863147 0.396286 0.316141 -0.860149 0.400247 0.269705 -0.85883 0.435511 0.262348 -0.864397 0.428941 0.170908 -0.848719 0.500466 0.164023 -0.853165 0.495183 0.0883166 -0.827181 0.554953 0.0836798 -0.829554 0.552121 0.00985613 -0.792903 0.609268 0.00421472 -0.795637 0.605759 -0.0786186 -0.737699 0.670537 -0.0834194 -0.739605 0.667852 -0.150958 -0.676167 0.721117 -0.154186 -0.677093 0.719564 -0.216574 -0.602904 0.767856 -0.21997 -0.603769 0.766209 -0.281182 -0.508133 0.814087 -0.283421 -0.508531 0.813062 -0.319852 -0.433587 0.842435 -0.320499 -0.433569 0.842198 -0.352707 -0.353365 0.866448 -0.353332 -0.35341 0.866175 -0.385905 -0.236554 0.891695 -0.385338 -0.236554 0.89194 -0.399003 -0.156382 0.903516 -0.39813 -0.156602 0.903863 -0.403278 -0.114261 0.907916 -0.403791 -0.114272 0.907686 -0.407199 -0.0739048 0.910344 -0.40702 -0.0739051 0.910425 -0.408759 -0.0382006 0.911843 -0.5359 -0.0322238 0.843666 0.841029 -0.0417018 -0.539381 0.839161 -0.0803833 -0.537911 0.83743 -0.0805852 -0.540571 0.834844 -0.114019 -0.538549 0.833285 -0.114208 -0.540919 0.831364 -0.13371 -0.539403 0.805316 -0.143481 -0.575221 0.827256 -0.147386 -0.542149 0.816431 -0.220504 -0.533684 0.999244 0.0336974 -0.0193834 0.919855 0.0215636 0.391666 0.632817 0.000908594 0.774301 0.98862 0.0231468 0.148645 0.962638 0.0343253 -0.268607 0.81922 0.0420025 -0.571939 -0.784867 0.0340615 0.618728 -0.295959 0.0302096 0.954723 0.4333 0.00664502 0.901225 0.108439 0.0202724 0.993896 0.5983 0.000816506 0.801271 -0.754517 0.0366955 0.655254 -0.752716 0.0769155 0.653837 -0.753046 0.0769382 0.653454 -0.750389 0.112294 0.651388 -0.835646 0.123072 0.535303 -0.747762 0.135398 0.650015 -0.746437 0.147149 0.648983 -0.74628 0.147053 0.649186 -0.736 0.217777 0.640998 -0.737188 0.218027 0.639546 -0.705543 0.352477 0.614793 -0.705349 0.352433 0.61504 -0.673045 0.446104 0.589916 -0.672686 0.445912 0.590471 -0.63426 0.532708 0.560301 -0.632555 0.532312 0.5626 -0.567476 0.645079 0.511707 -0.564763 0.644452 0.515484 -0.492904 0.738949 0.459348 -0.489903 0.73817 0.463788 -0.40973 0.819316 0.401052 -0.405446 0.818337 0.407356 -0.311594 0.889589 0.333978 -0.306347 0.88841 0.341876 -0.21658 0.937671 0.271784 -0.2119 0.936476 0.279485 -0.118382 0.971312 0.206249 -0.111314 0.969722 0.217367 -0.0498765 0.984245 0.169629 -0.0460599 0.995474 0.0831269 0.0133099 0.990152 0.139362 0.0790795 0.992965 0.0881311 0.0766127 0.993457 0.0846977 0.0697189 0.99349 0.0900889 0.0688522 0.993656 0.0889268 0.0717161 0.993651 0.0866876 0.06794 0.994344 0.0816385 0.0678553 0.994344 0.0817047 0.0641683 0.994984 0.0767424 0.0638399 0.994985 0.0769993 0.0341949 0.998714 0.0374342 0.0582613 0.996185 0.0649649 0.0804075 0.995624 0.0476101 0.0720771 0.996812 0.0342177 0.170178 0.984497 -0.0424776 0.163525 0.985078 -0.0536731 0.243512 0.962919 -0.11614 0.242009 0.962952 -0.118975 0.318346 0.930974 -0.178728 0.320679 0.930915 -0.174819 0.408385 0.879757 -0.243411 0.414938 0.879686 -0.232336 0.470341 0.838394 -0.275455 0.470658 0.839081 -0.272807 0.527709 0.787789 -0.317667 0.530383 0.787999 -0.312653 0.60632 0.703002 -0.371705 0.552855 0.666826 -0.499694 0.651134 0.639158 -0.409269 0.677276 0.597263 -0.429622 0.677193 0.596708 -0.430521 0.685325 0.582639 -0.436877 0.683199 0.533018 -0.499131 0.711748 0.526435 -0.46506 0.746593 0.447579 -0.492211 0.685923 0.426585 -0.58952 0.764272 0.395419 -0.509444 0.777262 0.354801 -0.519596 0.684092 0.297302 -0.666056 0.797617 0.278935 -0.534791 0.777581 0.354998 -0.518984 0.811241 0.23696 -0.534545 0.823203 0.16238 -0.544031 0.827884 0.163171 -0.53664 0.831543 0.132321 -0.53947 0.831742 0.132352 -0.539156 0.833252 0.117169 -0.540336 0.833905 0.117321 -0.539295 0.836353 0.0870434 -0.541237 0.838728 0.0871853 -0.537527 0.841096 0.040401 -0.539375 0.988348 0.0389139 -0.147155 0.986395 0.0761795 -0.145679 0.985928 0.0761881 -0.1488 0.983794 0.102652 -0.147012 0.983673 0.102587 -0.147861 0.982353 0.115854 -0.146833 0.982322 0.115847 -0.147049 0.979115 0.142841 -0.144672 0.97813 0.142674 -0.151348 0.959825 0.244727 -0.137274 0.958911 0.244888 -0.143249 0.941176 0.312487 -0.12861 0.941132 0.312421 -0.129086 0.919988 0.37524 -0.113216 0.92028 0.37507 -0.111389 0.879996 0.468193 -0.0800131 0.880666 0.4676 -0.0760174 0.850178 0.52401 -0.0511003 0.850059 0.524271 -0.0504042 0.810806 0.584932 -0.021156 0.810966 0.584743 -0.0202543 0.720269 0.691832 0.0507984 0.71953 0.692841 0.0474074 0.669748 0.737407 0.0875765 0.669926 0.737478 0.085588 0.621126 0.77404 0.122736 0.618535 0.777342 0.11469 0.541166 0.822453 0.175246 0.540109 0.823737 0.172452 0.472701 0.851856 0.225599 0.473417 0.850938 0.227556 0.402408 0.870751 0.282597 0.406032 0.866581 0.290131 0.319506 0.877459 0.357746 0.324761 0.871784 0.366774 0.30391 0.872221 0.383236 0.308752 0.867652 0.389683 0.308472 0.867653 0.389901 0.310745 0.865445 0.392993 0.310801 0.865445 0.392948 0.313155 0.863145 0.396125 0.310657 0.863149 0.398078 0.311167 0.862647 0.398767 0.317134 0.86262 0.394098 0.318593 0.861132 0.396171 0.253547 0.858327 0.446081 0.248322 0.863948 0.438097 0.154757 0.845357 0.511295 0.149762 0.850168 0.504764 0.0682884 0.819569 0.568896 0.0647721 0.822823 0.564595 -0.0140767 0.779835 0.625827 -0.0183196 0.78314 0.621576 -0.100812 0.720495 0.686094 -0.104526 0.723054 0.682838 -0.175027 0.651438 0.738238 -0.177748 0.653168 0.736055 -0.241398 0.569806 0.785524 -0.243919 0.571135 0.783778 -0.301483 0.471342 0.828821 -0.303114 0.472072 0.82781 -0.336502 0.395053 0.85481 -0.336802 0.395239 0.854606 -0.366126 0.312397 0.876562 -0.366443 0.312502 0.876391 -0.394472 0.19327 0.898353 -0.393245 0.19296 0.898958 -0.40156 0.130255 0.906523 -0.401632 0.130291 0.906486 -0.403979 0.109333 0.908211 -0.40434 0.109372 0.908046 -0.407613 0.0681501 0.910608 -0.407261 0.0681204 0.910768 -0.408919 0.0294696 0.912095 -0.535828 0.036166 0.843552 0.962313 0.024886 0.270803 0.960943 0.0518048 0.271855 0.96145 0.0518614 0.270045 0.959955 0.0698588 0.271304 0.960099 0.0698384 0.2708 0.959202 0.0788705 0.271498 0.959243 0.0788722 0.271351 0.957105 0.0972755 0.272923 0.95827 0.0973916 0.268762 0.945882 0.166955 0.278267 0.946815 0.167372 0.274825 0.934431 0.213424 0.285112 0.934524 0.213416 0.284813 0.920291 0.256496 0.295423 0.920023 0.256241 0.296477 0.892513 0.31995 0.317888 0.891995 0.319195 0.320094 0.870863 0.357385 0.337453 0.870683 0.35747 0.337825 0.84423 0.399436 0.357389 0.844168 0.399295 0.357692 0.782322 0.472238 0.406158 0.782547 0.473274 0.404514 0.748344 0.503153 0.432224 0.748743 0.50346 0.431175 0.715664 0.528824 0.456257 0.715685 0.532309 0.452152 0.662719 0.563157 0.493618 0.662594 0.56453 0.492214 0.616353 0.583579 0.52872 0.616465 0.582573 0.529698 0.567786 0.596408 0.567377 0.56877 0.592194 0.570795 0.509613 0.599659 0.617012 0.511595 0.5937 0.621121 0.497343 0.593917 0.632386 0.4993 0.589413 0.635052 0.499105 0.589413 0.635206 0.500051 0.587173 0.636535 0.500082 0.587174 0.63651 0.500967 0.58508 0.63774 0.499273 0.585081 0.639067 0.49952 0.584496 0.639409 0.503554 0.584479 0.636253 0.504109 0.583086 0.637091 0.460073 0.58165 0.670832 0.457879 0.587167 0.66752 0.394362 0.574528 0.717214 0.392005 0.579179 0.714761 0.336648 0.558159 0.758371 0.334898 0.561191 0.756907 0.281072 0.532092 0.798672 0.278749 0.535249 0.797376 0.222424 0.492465 0.841431 0.220325 0.494824 0.840599 0.172199 0.445728 0.87845 0.170533 0.44735 0.87795 0.126853 0.390388 0.911869 0.125236 0.391645 0.911554 0.0857866 0.323222 0.942427 0.0847659 0.323862 0.942299 0.0622598 0.270816 0.960616 0.0619878 0.27102 0.960576 0.0414254 0.214383 0.975871 0.0412708 0.21445 0.975863 0.0220595 0.132627 0.990921 0.0229625 0.132353 0.990937 0.0177739 0.0892939 0.995847 0.0177482 0.0893069 0.995846 0.016083 0.0749221 0.99706 0.01568 0.0749783 0.997062 0.0134382 0.0467172 0.998818 0.0136176 0.0466989 0.998816 0.0124682 0.0195483 0.999731 -0.131536 0.0262558 0.990964 0.431971 0.00677265 0.901862 0.432386 0.0165836 0.901536 0.43233 0.0165909 0.901563 0.433125 0.0266246 0.90094 0.433085 0.0266319 0.90096 0.433684 0.031773 0.900505 0.433838 0.0316814 0.900434 0.435643 0.0470297 0.89889 0.435276 0.0471705 0.899061 0.442104 0.0762625 0.893716 0.442089 0.0762712 0.893723 0.449432 0.0963575 0.888102 0.449582 0.0962119 0.888042 0.457571 0.115159 0.881684 0.457806 0.114957 0.881589 0.47183 0.139286 0.870618 0.47231 0.138754 0.870443 0.487831 0.158962 0.858343 0.488233 0.158378 0.858222 0.50534 0.175857 0.844811 0.505905 0.17485 0.844682 0.525894 0.190036 0.829049 0.526409 0.188821 0.829 0.545498 0.199092 0.814122 0.545876 0.19777 0.814191 0.565506 0.205274 0.79879 0.565919 0.203325 0.798997 0.588393 0.207804 0.781416 0.58861 0.205733 0.7818 0.604033 0.206116 0.769844 0.603993 0.206551 0.769759 0.602578 0.206556 0.770866 0.602555 0.206758 0.770829 0.603149 0.206758 0.770365 0.603045 0.207696 0.770194 0.603036 0.207699 0.770201 0.602954 0.208445 0.770063 0.603025 0.208443 0.770008 0.602809 0.21029 0.769675 0.607845 0.210238 0.765718 0.60778 0.21284 0.765051 0.62875 0.210188 0.748662 0.628899 0.211951 0.748039 0.646196 0.206951 0.734576 0.646291 0.207391 0.734368 0.662807 0.200669 0.7214 0.662646 0.20005 0.72172 0.681503 0.189081 0.706967 0.680944 0.187618 0.707894 0.692533 0.178506 0.698951 0.692309 0.178359 0.699212 0.7046 0.167917 0.689451 0.704369 0.167559 0.689774 0.726267 0.141768 0.672635 0.726276 0.141777 0.672623 0.735438 0.126744 0.665633 0.735541 0.126726 0.665522 0.743214 0.113272 0.659395 0.743658 0.113593 0.65884 0.753411 0.0909459 0.65123 0.753639 0.0910614 0.65095 0.758572 0.0757307 0.647173 0.75852 0.0757276 0.647234 0.763068 0.0593759 0.643585 0.762301 0.0591738 0.644512 0.766646 0.0345226 0.641142 0.765689 0.0344396 0.642288 0.76642 0.0279428 0.641732 0.766383 0.0279408 0.641776 0.7667 0.0247348 0.641529 0.766595 0.0247379 0.641654 0.767146 0.0183637 0.641209 0.766752 0.0183359 0.641682 0.767305 0.00722928 0.641242 0.753672 0.0071404 0.657212 -0.876714 -0.0395421 0.479384 0.274966 -0.896722 0.34682 -0.0684524 -0.993274 -0.0933872 0.662984 -0.282268 -0.693381 0.711812 -0.0416846 -0.701132 0.714937 -0.0206875 -0.698882 0.714585 -0.0247559 -0.699111 0.708277 -0.0414838 -0.704715 0.72128 -0.0517115 -0.690711 0.703516 -0.0802267 -0.706137 0.728318 -0.114157 -0.675663 0.69624 -0.0984626 -0.711024 0.704344 -0.137504 -0.696414 0.709435 -0.13345 -0.692021 0.684001 -0.219115 -0.695796 0.684255 -0.220326 -0.695163 0.697475 -0.147044 -0.701361 0.662775 -0.286992 -0.691639 0.649797 -0.330601 -0.684447 0.629824 -0.361041 -0.687729 0.63258 -0.392229 -0.667831 0.60916 -0.446407 -0.655473 0.608915 -0.451288 -0.652351 0.581507 -0.523139 -0.623038 0.583353 -0.533148 -0.612742 0.536447 -0.605468 -0.587906 0.519429 -0.624431 -0.583335 0.493663 -0.707781 -0.505316 0.498005 -0.679544 -0.538712 0.428097 -0.754101 -0.498061 0.426551 -0.756369 -0.495943 0.376426 -0.807692 -0.453803 0.377857 -0.804921 -0.457522 0.332082 -0.838537 -0.431946 0.297588 -0.857765 -0.419142 0.297672 -0.857634 -0.419352 0.258472 -0.886814 -0.383083 0.256829 -0.888256 -0.380841 0.195324 -0.912836 -0.358578 0.18624 -0.928099 -0.322408 0.0907675 -0.954411 -0.28436 0.111734 -0.952409 -0.283607 0.029854 -0.97972 -0.198136 0.0427136 -0.979311 -0.197802 -0.0644017 -0.99053 -0.121252 -0.0402961 -0.992187 -0.118077 -0.0682611 -0.993231 -0.0939815 -0.0700426 -0.993086 -0.0942018 -0.0619265 -0.994677 -0.0823517 -0.0602252 -0.99503 -0.0793012 -0.0645112 -0.994047 -0.0878038 -0.0599939 -0.995042 -0.0793197 -0.0563201 -0.995361 -0.0780026 -0.0567133 -0.99537 -0.0776018 -0.0509133 -0.996491 -0.0664272 -0.0443599 -0.997083 -0.0621079 -0.0466436 -0.996839 -0.0643193 -0.0472289 -0.996842 -0.0638357 -0.130453 -0.991092 -0.026795 -0.0991121 -0.994866 -0.0204493 -0.237899 -0.970498 0.0392147 -0.221733 -0.974231 0.0413399 -0.290734 -0.953068 0.0844688 -0.319908 -0.942597 0.0957571 -0.322706 -0.941204 0.0999748 -0.387892 -0.908302 0.15661 -0.409389 -0.899236 0.154195 -0.493745 -0.840076 0.224694 -0.507392 -0.83256 0.222257 -0.56188 -0.783827 0.264395 -0.590491 -0.759599 0.272636 -0.613734 -0.722631 0.318018 -0.666752 -0.674503 0.316997 -0.693347 -0.616355 0.373332 -0.737347 -0.56698 0.367224 -0.747675 -0.537061 0.390573 -0.783666 -0.45551 0.422349 -0.756172 -0.486538 0.43759 -0.854102 -0.320639 0.409512 -0.779816 -0.397217 0.483844 -0.852034 -0.263393 0.452396 -0.851618 -0.21053 0.480024 -0.861131 -0.174802 0.477385 -0.863086 -0.143688 0.484186 -0.872477 -0.127402 0.471755 -0.870477 -0.0394961 0.490623 -0.87137 -0.0401491 0.488981 -0.870467 -0.0737669 0.486668 -0.877246 -0.0823633 0.472923 -0.866565 -0.100265 0.488889 -0.869693 -0.123925 0.477784 0.711807 0.0418508 -0.701127 -0.870481 0.0393732 0.490625 -0.876822 0.0362815 0.479443 -0.867856 0.0374567 0.495402 -0.874069 0.0760315 0.479815 -0.865921 0.0827773 0.493284 -0.869386 0.111058 0.481491 -0.866972 0.11503 0.484899 -0.865676 0.133956 0.482349 -0.866297 0.133114 0.481467 -0.863525 0.145599 0.482831 -0.858214 0.159318 0.487942 -0.861763 0.268581 0.430383 -0.837179 0.216596 0.502212 -0.822764 0.398232 0.40555 -0.804415 0.350445 0.479692 -0.751979 0.52665 0.396443 -0.751485 0.527162 0.396699 -0.791282 0.441249 0.423286 -0.708731 0.604242 0.364133 -0.673279 0.674038 0.303921 -0.668281 0.641521 0.376633 -0.589036 0.771086 0.241792 -0.585767 0.736668 0.337931 -0.524248 0.827367 0.201562 -0.532574 0.812449 0.237257 -0.0826185 0.992997 -0.0844511 -0.166051 0.985851 0.0229217 -0.168455 0.985341 0.0269338 -0.24831 0.967839 0.0403716 -0.25921 0.964111 0.0574425 -0.33162 0.935171 0.12443 -0.32874 0.937731 0.11221 -0.433917 0.883973 0.174092 -0.43192 0.886588 0.165549 -0.4788 0.852878 0.208206 -0.0466163 0.99681 -0.0647834 -0.0550246 0.996065 -0.0694805 -0.0566505 0.995533 -0.0755292 -0.0433948 0.996693 -0.0687075 -0.0802001 0.99654 0.021816 -0.0585622 0.995347 -0.0765103 -0.0580019 0.995356 -0.0768218 -0.063708 0.994195 -0.0866992 -0.0635021 0.994269 -0.0860065 -0.0665073 0.9939 -0.0879712 -0.064733 0.993685 -0.0916506 -0.0652602 0.993503 -0.0932367 -0.0571958 0.989916 -0.129597 0.0100596 0.987533 -0.157089 0.0293358 0.974717 -0.221508 0.103464 0.962469 -0.250894 0.111984 0.953277 -0.280574 0.152552 0.93766 -0.312286 0.197251 0.908469 -0.368478 0.198263 0.923859 -0.327379 0.263265 0.878059 -0.39963 0.269304 0.870597 -0.411748 0.318715 0.851238 -0.416912 0.339447 0.833453 -0.436042 0.369911 0.810347 -0.454426 0.390969 0.782435 -0.484705 0.45946 0.737186 -0.495432 0.477493 0.699809 -0.531289 0.547402 0.608609 -0.574409 0.561704 0.595415 -0.574429 0.521374 0.635718 -0.569238 0.713259 0.117052 -0.691058 0.700577 0.131872 -0.701286 0.69934 0.157425 -0.697239 0.694814 0.162124 -0.700678 0.676703 0.23973 -0.696134 0.678563 0.236452 -0.695445 0.665097 0.276364 -0.693735 0.655786 0.295898 -0.694543 0.655766 0.346127 -0.670945 0.650522 0.352782 -0.672581 0.615252 0.416128 -0.669554 0.633002 0.392654 -0.667182 0.593759 0.475512 -0.649106 0.629184 0.445604 -0.63684 0.561973 0.535562 -0.630365 0.575606 0.522147 -0.629317 0.556371 0.579365 -0.595641 0.71399 0.116543 -0.690389 0.687624 0.0691671 -0.722765 0.731001 0.0871706 -0.676786 0.699153 0.0325772 -0.71423 0.714459 0.0420005 -0.698415 0.999775 -0.0164978 -0.0133249 0.63346 -0.000571866 0.773776 -0.112367 -0.0280079 0.993272 -0.513831 -0.0360965 0.857132 -0.768344 -0.0419689 0.63866 0.598424 -0.000884408 0.80118 0.916638 0.0231911 0.399044 0.750137 -0.0540239 0.659072 0.824433 -0.0207968 -0.565577 0.845553 -0.059742 -0.530538 0.846765 -0.0247435 -0.531391 0.846607 -0.0248316 -0.531639 0.84578 -0.0516415 -0.531027 0.844136 -0.0517816 -0.533623 0.841328 -0.098771 -0.531425 0.839253 -0.098962 -0.534659 0.835607 -0.137697 -0.53179 0.789707 -0.332584 -0.515509 0.800917 -0.289277 -0.524262 0.879521 -0.235994 -0.413219 0.821685 -0.220817 -0.525427 0.833686 -0.137933 -0.534735 0.563553 -0.759698 -0.324449 0.628321 -0.681311 -0.375537 0.626957 -0.681673 -0.377155 0.67651 -0.607991 -0.415549 0.675274 -0.608776 -0.41641 0.716078 -0.534772 -0.44861 0.7116 -0.535846 -0.454417 0.748643 -0.45396 -0.483171 0.829267 -0.409009 -0.380825 0.769619 -0.394689 -0.501904 0.78869 -0.333049 -0.516766 0.585487 -0.791762 -0.174122 0.522224 -0.797234 -0.302819 0.469818 -0.843114 -0.261589 0.011548 -0.988086 0.153468 0.0802288 -0.991735 0.100122 0.0826258 -0.99139 0.101578 0.0833175 -0.991388 0.101038 0.0784839 -0.992363 0.0951675 0.0766222 -0.992367 0.0966245 0.0731379 -0.993043 0.0922859 0.0738384 -0.993042 0.0917385 0.0689138 -0.993941 0.0856315 0.0688564 -0.993941 0.0856765 0.0677896 -0.994114 0.0845136 0.0683253 -0.994113 0.0840947 0.0671259 -0.994302 0.0828059 0.0679855 -0.9943 0.0821337 0.0665682 -0.994518 0.0806358 0.0677479 -0.994513 0.0797133 0.0660492 -0.994767 0.0779521 0.0825064 -0.994465 0.0650578 0.0738456 -0.995683 0.0562268 0.171357 -0.985004 -0.0200979 0.161263 -0.986439 -0.0305495 0.243414 -0.965294 -0.094638 0.240138 -0.96582 -0.0975959 0.317682 -0.934882 -0.15835 0.317948 -0.93484 -0.158062 0.390431 -0.895269 -0.214609 0.487712 -0.865257 -0.11605 0.440628 -0.86461 -0.241447 0.467626 -0.844045 -0.262514 0.765693 -0.0295853 0.642526 0.766349 -0.00518387 0.642404 0.766399 -0.0052093 0.642344 0.766265 -0.0108209 0.642434 0.766517 -0.010857 0.642132 0.765925 -0.0207209 0.642596 0.766289 -0.0207998 0.642159 0.765503 -0.028933 0.642782 0.765886 -0.0290489 0.64232 0.762812 -0.0508319 0.644619 0.763814 -0.0514115 0.643385 0.758978 -0.0705574 0.647282 0.759103 -0.0706999 0.64712 0.75361 -0.0886652 0.651314 0.753513 -0.0885707 0.651439 0.74271 -0.113779 0.659876 0.742239 -0.113147 0.660514 0.733356 -0.128408 0.667608 0.733322 -0.128192 0.667687 0.723197 -0.144136 0.675434 0.723149 -0.144028 0.675508 0.701512 -0.168462 0.692461 0.701721 -0.169222 0.692063 0.690562 -0.178439 0.700916 0.690481 -0.178912 0.700875 0.679661 -0.187271 0.709218 0.679859 -0.188517 0.708699 0.660333 -0.199602 0.723961 0.660338 -0.199692 0.723932 0.64379 -0.206018 0.736947 0.643858 -0.205287 0.737092 0.626505 -0.210055 0.750578 0.62672 -0.20811 0.750941 0.606141 -0.210212 0.767075 0.606546 -0.20822 0.767298 0.603126 -0.208243 0.769983 0.603201 -0.207888 0.77002 0.602968 -0.207889 0.770203 0.603031 -0.20758 0.770237 0.602859 -0.207581 0.770371 0.60289 -0.207423 0.770389 0.602784 -0.207423 0.770472 0.60285 -0.207082 0.770513 0.602864 -0.207082 0.770501 0.603012 -0.206031 0.770667 0.60287 -0.206032 0.770778 0.60297 -0.205319 0.77089 0.603368 -0.20532 0.770579 0.603523 -0.20426 0.770739 0.603336 -0.204262 0.770885 0.603171 -0.204639 0.770913 0.588841 -0.204315 0.781999 0.588317 -0.206068 0.781933 0.5655 -0.201451 0.799767 0.56486 -0.202943 0.799842 0.550376 -0.197214 0.811291 0.550069 -0.197576 0.811411 0.535747 -0.191036 0.822484 0.535082 -0.192093 0.822671 0.514173 -0.177993 0.839014 0.513526 -0.178785 0.839242 0.500634 -0.166743 0.849448 0.500489 -0.166838 0.849515 0.487998 -0.153989 0.859154 0.487453 -0.154454 0.85938 0.471095 -0.131891 0.872166 0.470641 -0.132182 0.872368 0.46161 -0.115295 0.879559 0.461582 -0.115301 0.879573 0.453169 -0.097989 0.886023 0.452975 -0.0980648 0.886113 0.443361 -0.0697192 0.893628 0.44336 -0.0697193 0.893628 0.438224 -0.0452605 0.897726 0.438331 -0.0452573 0.897674 0.436425 -0.0308343 0.899212 0.43654 -0.030829 0.899156 0.436085 -0.0266396 0.899511 0.436046 -0.0266413 0.89953 0.435582 -0.0215256 0.899892 0.435563 -0.0215261 0.899901 0.435165 -0.0158373 0.900212 0.435242 -0.0158368 0.900174 0.434934 -0.00942559 0.900413 0.444541 -0.00944772 0.895708 0.134171 -0.0192029 0.990772 0.0224994 -0.0262058 0.999403 0.0233828 -0.0446616 0.998729 0.0231492 -0.0446914 0.998733 0.0242711 -0.0606979 0.997861 0.0244347 -0.0606725 0.997859 0.0257439 -0.0751252 0.996842 0.0257315 -0.0751275 0.996842 0.0270161 -0.0869613 0.995845 0.0269792 -0.0869695 0.995846 0.032367 -0.12741 0.991322 0.0317449 -0.127637 0.991313 0.0462733 -0.196449 0.979421 0.0461921 -0.196482 0.979419 0.0733112 -0.276439 0.958231 0.0739221 -0.276106 0.95828 0.0976674 -0.325312 0.940549 0.0979352 -0.325038 0.940616 0.123568 -0.372629 0.919717 0.12476 -0.371742 0.919915 0.17113 -0.435702 0.883673 0.172622 -0.434327 0.88406 0.208221 -0.471254 0.857067 0.208711 -0.470449 0.85739 0.245453 -0.50445 0.827818 0.247324 -0.502195 0.828632 0.306929 -0.542396 0.78205 0.308888 -0.539494 0.783284 0.350151 -0.55867 0.751852 0.350519 -0.557435 0.752598 0.392231 -0.57358 0.719139 0.394236 -0.569623 0.721185 0.45972 -0.582879 0.670007 0.461564 -0.57815 0.672831 0.503115 -0.579483 0.641151 0.503182 -0.578479 0.642005 0.503925 -0.578471 0.641429 0.50281 -0.581178 0.639855 0.501611 -0.581177 0.640796 0.500745 -0.583202 0.639633 0.50108 -0.583201 0.639371 0.499913 -0.585926 0.637791 0.499786 -0.585926 0.637891 0.499602 -0.586425 0.637576 0.499806 -0.586425 0.637417 0.499552 -0.587128 0.636968 0.499919 -0.587127 0.636681 0.499672 -0.587824 0.636231 0.500189 -0.587822 0.635828 0.499897 -0.588669 0.635273 0.508886 -0.588577 0.628182 0.507348 -0.593305 0.62497 0.564196 -0.587354 0.580257 0.563046 -0.592169 0.576467 0.611453 -0.579177 0.539147 0.611346 -0.580477 0.537868 0.657563 -0.562484 0.501222 0.657572 -0.56238 0.501326 0.713048 -0.530884 0.457957 0.713017 -0.528163 0.46114 0.744771 -0.504256 0.437083 0.74438 -0.504001 0.438042 0.776161 -0.477029 0.412333 0.77584 -0.475313 0.41491 0.836752 -0.406332 0.367071 0.836852 -0.40658 0.366568 0.865813 -0.362372 0.345043 0.866068 -0.36237 0.344405 0.890269 -0.319534 0.32453 0.890916 -0.320526 0.321763 0.921284 -0.249769 0.298079 0.921469 -0.249945 0.297359 0.937441 -0.199202 0.285522 0.937247 -0.1992 0.286161 0.950567 -0.14428 0.274964 0.949178 -0.143836 0.279951 0.958392 -0.0819312 0.273445 0.957924 -0.0818331 0.27511 0.960128 -0.0586752 0.273335 0.959681 -0.0586102 0.274914 0.961357 -0.0306224 0.273597 0.960988 -0.0306207 0.274891 0.961435 -0.0146572 0.27464 0.961401 -0.0146916 0.27476 0.95859 -0.0739155 0.275032 0.987859 -0.0141599 0.154708 -0.277385 -0.0323833 0.960213 -0.393958 -0.0374265 0.918366 -0.392636 -0.065446 0.917363 -0.392784 -0.0654627 0.917298 -0.391146 -0.088902 0.916025 -0.391201 -0.0889094 0.916 -0.389289 -0.110083 0.914514 -0.389193 -0.110068 0.914557 -0.387315 -0.127432 0.913098 -0.387198 -0.12741 0.913151 -0.379043 -0.186585 0.906373 -0.380004 -0.186889 0.905908 -0.358298 -0.287455 0.888252 -0.358332 -0.287466 0.888235 -0.318672 -0.404456 0.857242 -0.31795 -0.404167 0.857646 -0.283812 -0.476632 0.832029 -0.283336 -0.47624 0.832416 -0.245138 -0.545525 0.801443 -0.243193 -0.544529 0.802711 -0.175253 -0.638261 0.749606 -0.172629 -0.636679 0.751558 -0.120892 -0.691493 0.712196 -0.120118 -0.69063 0.713164 -0.0657272 -0.739869 0.669532 -0.0623728 -0.737428 0.67254 0.0252065 -0.796525 0.60408 0.0289404 -0.793422 0.607983 0.0894028 -0.822421 0.56181 0.0901878 -0.821123 0.56358 0.151912 -0.84412 0.514183 0.156203 -0.839934 0.519722 0.252841 -0.859515 0.44419 0.257263 -0.854641 0.451005 0.31867 -0.857404 0.404114 0.319118 -0.85639 0.405906 0.320234 -0.856384 0.40504 0.317456 -0.859196 0.401253 0.31568 -0.859199 0.402646 0.313604 -0.861236 0.399906 0.314093 -0.861235 0.399524 0.311145 -0.864107 0.395611 0.310944 -0.864108 0.395767 0.310415 -0.864674 0.394946 0.310712 -0.864673 0.394714 0.310141 -0.865289 0.393811 0.310674 -0.865288 0.393394 0.309998 -0.866025 0.392303 0.310745 -0.866022 0.391719 0.309954 -0.866898 0.390407 0.323198 -0.866699 0.379967 0.31912 -0.871257 0.372926 0.402444 -0.862281 0.307425 0.398356 -0.867079 0.299143 0.469232 -0.848581 0.244402 0.468302 -0.849886 0.241632 0.535863 -0.823072 0.18816 0.535968 -0.822939 0.18844 0.617218 -0.776813 0.124911 0.619158 -0.774251 0.131067 0.666079 -0.739758 0.09538 0.665862 -0.739713 0.097224 0.712285 -0.699338 0.0597981 0.713467 -0.697676 0.0649137 0.802678 -0.596391 -0.00510229 0.802466 -0.596664 -0.00627469 0.845558 -0.532494 -0.0384974 0.845626 -0.532297 -0.0396973 0.88058 -0.468954 -0.0682676 0.879737 -0.469784 -0.0732509 0.924285 -0.366106 -0.107999 0.924086 -0.366233 -0.109261 0.947922 -0.292063 -0.127053 0.948042 -0.292177 -0.125896 0.967074 -0.21133 -0.141798 0.968307 -0.211247 -0.133256 0.982326 -0.120423 -0.143297 0.982712 -0.120387 -0.140656 0.98592 -0.0862938 -0.143233 0.986315 -0.0862701 -0.140501 0.988778 -0.0450652 -0.142435 0.989089 -0.0450983 -0.140248 0.989819 -0.0215742 -0.140687 0.989847 -0.021634 -0.140479 0.987168 -0.0777383 -0.139487 0.965298 0.0106958 -0.260932 -0.739444 -0.0398604 0.672037 -0.737873 -0.0744505 0.67082 -0.738076 -0.0744321 0.6706 -0.736217 -0.101115 0.669148 -0.736231 -0.101114 0.669134 -0.734065 -0.125182 0.667442 -0.733985 -0.12519 0.667528 -0.731858 -0.14493 0.665867 -0.731812 -0.144937 0.665917 -0.722173 -0.212383 0.658301 -0.72302 -0.212189 0.657433 -0.697748 -0.32664 0.637537 -0.697891 -0.326621 0.63739 -0.652891 -0.459427 0.602212 -0.651896 -0.459534 0.603208 -0.614101 -0.541809 0.573866 -0.613466 -0.542018 0.574348 -0.569493 -0.61996 0.539748 -0.566924 -0.620132 0.542249 -0.490121 -0.726125 0.482208 -0.486474 -0.726251 0.485698 -0.428972 -0.788367 0.440978 -0.427155 -0.788683 0.442173 -0.365283 -0.843619 0.393542 -0.360211 -0.843541 0.398356 -0.261292 -0.910312 0.321027 -0.254943 -0.909964 0.327061 -0.187744 -0.942992 0.274807 -0.184879 -0.943075 0.276458 -0.158176 -0.953757 0.255593 -0.0503395 -0.953494 0.297177 -0.0964806 -0.970379 0.221485 0.00222365 -0.989548 0.144187 -0.277386 0.0322859 0.960216 0.751203 0.00919491 0.660008 0.987708 0.0224751 0.154684 0.964963 0.02842 -0.260841 0.824082 0.0358236 -0.565337 0.63346 0.000736669 0.773775 0.134171 0.0191368 0.990773 0.444542 0.0094326 0.895709 -0.768411 0.0398226 0.638716 0.845925 0.0327562 -0.532296 0.844414 0.0696514 -0.531143 0.842504 0.0695311 -0.534185 0.839012 0.116687 -0.531454 0.837204 0.11659 -0.534319 0.832639 0.15819 -0.530743 0.838273 0.240681 -0.489256 0.813593 0.250293 -0.524805 0.828836 0.157647 -0.536822 0.804057 0.278652 -0.52521 0.785903 0.34787 -0.511218 0.784351 0.347632 -0.513757 0.760863 0.41936 -0.495201 0.793516 0.460865 -0.397412 0.739832 0.478622 -0.472832 0.711448 0.539353 -0.45049 0.712061 0.540034 -0.4487 0.672876 0.61013 -0.418306 0.675952 0.610446 -0.41285 0.582325 0.738525 -0.339821 0.581071 0.73845 -0.342123 0.506249 0.814549 -0.283236 0.523043 0.840302 -0.142541 0.442599 0.864232 -0.239184 0.504634 0.814051 -0.287518 0.405423 0.88637 -0.223564 0.349827 0.919308 -0.180261 0.348035 0.919377 -0.183352 0.291766 0.946306 -0.139202 0.291893 0.946353 -0.138616 0.230971 0.968681 -0.0911603 0.23525 0.9683 -0.083979 0.132106 0.99123 -0.0033392 0.141217 0.98991 0.0116202 0.0638386 0.995333 0.0723665 0.0691978 0.994396 0.0799299 0.0665185 0.994408 0.0820254 0.0691857 0.993919 0.0856684 0.0691502 0.993919 0.0856962 0.0739138 0.993014 0.0919786 0.0734911 0.993015 0.0923096 0.0767478 0.99236 0.0966008 0.077545 0.992358 0.0959767 0.0810174 0.991619 0.10064 0.0689073 0.991532 0.110071 0.0650419 0.99245 0.103986 -0.0426678 0.981214 0.188143 -0.0492127 0.98285 0.177718 -0.121738 0.964403 0.234747 -0.122844 0.965082 0.231357 -0.193715 0.938306 0.286455 -0.204659 0.871471 0.445706 -0.302243 0.883075 0.358925 -0.19908 0.939644 0.278273 -0.345619 0.856608 0.383105 -0.372896 0.835102 0.404416 -0.373819 0.835735 0.402252 -0.435456 0.779559 0.450185 -0.438782 0.780383 0.445502 -0.522833 0.682131 0.511217 -0.525439 0.682767 0.507684 -0.574745 0.609131 0.546468 -0.575294 0.609527 0.545448 -0.618569 0.531091 0.579063 -0.619994 0.531429 0.577227 -0.673383 0.404276 0.618963 -0.673789 0.404368 0.618461 -0.711231 0.273012 0.647777 -0.710782 0.27291 0.648312 -0.730468 0.160628 0.663789 -0.729852 0.160509 0.664494 -0.732927 0.134344 0.666911 -0.73314 0.13438 0.666669 -0.734967 0.116065 0.668097 -0.734962 0.116064 0.668102 -0.737557 0.0834399 0.67011 -0.73733 0.0834243 0.670362 -0.739404 0.0413439 0.671992 -0.513833 0.0359711 0.857136 -0.393841 0.0373303 0.91842 -0.392089 0.0733575 0.916998 -0.392379 0.0733575 0.916874 -0.39002 0.102045 0.915135 -0.389944 0.102049 0.915166 -0.388337 0.118135 0.913914 -0.388253 0.118139 0.913949 -0.385587 0.141199 0.911803 -0.386482 0.141163 0.91143 -0.369443 0.240193 0.897674 -0.370137 0.240197 0.897388 -0.337315 0.355865 0.871538 -0.336737 0.355815 0.871782 -0.28985 0.467425 0.835165 -0.288296 0.467169 0.835846 -0.249794 0.535392 0.80682 -0.249052 0.535396 0.807047 -0.20683 0.599837 0.772928 -0.203985 0.599061 0.774285 -0.130787 0.684616 0.717074 -0.127287 0.683368 0.718893 -0.0734554 0.731483 0.677892 -0.0718128 0.731139 0.678439 -0.0160502 0.773377 0.633744 -0.0115511 0.771232 0.63645 0.0779242 0.820347 0.566531 0.0832175 0.817322 0.570141 0.143897 0.839609 0.523784 0.146075 0.838692 0.524651 0.20698 0.854776 0.475938 0.213011 0.850499 0.480914 0.305081 0.859979 0.409098 0.308632 0.857003 0.412664 0.318722 0.857022 0.404881 0.316432 0.859174 0.402107 0.315875 0.859175 0.402544 0.31378 0.86115 0.399953 0.31427 0.861149 0.399571 0.311172 0.864038 0.39574 0.311364 0.864038 0.395589 0.309588 0.865639 0.393478 0.312284 0.865627 0.391368 0.308402 0.869018 0.386905 0.377118 0.864556 0.332154 0.369805 0.870749 0.324098 0.462198 0.850238 0.251929 0.459019 0.853154 0.247849 0.513692 0.832859 0.206071 0.51337 0.833109 0.205866 0.562585 0.809786 0.166567 0.5638 0.808554 0.168432 0.638943 0.761389 0.109719 0.642238 0.757739 0.115599 0.696136 0.714063 0.0742178 0.697747 0.712259 0.076395 0.762086 0.647014 0.0244318 0.762677 0.646266 0.0257798 0.84487 0.533631 -0.0378533 0.843643 0.535303 -0.0414384 0.878723 0.472498 -0.0677589 0.87816 0.473399 -0.0687569 0.907844 0.408857 -0.0930343 0.907011 0.409977 -0.0961729 0.94393 0.305592 -0.124941 0.944395 0.30499 -0.12288 0.965436 0.220659 -0.138719 0.966358 0.219238 -0.134485 0.979642 0.13855 -0.145275 0.980572 0.137617 -0.139787 0.984477 0.101946 -0.142869 0.984837 0.101715 -0.140536 0.987867 0.0607893 -0.142908 0.988248 0.0605949 -0.140339 0.989461 0.032262 -0.141163 0.999569 0.0261645 -0.0133221 -0.112367 0.0279241 0.993274 0.0224911 0.0261484 0.999405 0.0236301 0.0500715 0.998466 0.0234445 0.0500764 0.99847 0.0251039 0.0696569 0.997255 0.0252272 0.0696576 0.997252 0.0263241 0.0806219 0.996397 0.0263513 0.0806218 0.996396 0.0281414 0.0963474 0.99495 0.0272043 0.0963594 0.994975 0.0386583 0.1641 0.985686 0.0384745 0.164117 0.98569 0.0608122 0.243177 0.968074 0.0609117 0.243155 0.968073 0.0929885 0.319448 0.94303 0.0939529 0.319125 0.943044 0.120651 0.365369 0.923011 0.1212 0.365272 0.922977 0.149641 0.409655 0.899884 0.151346 0.408783 0.899995 0.20132 0.467168 0.860944 0.203462 0.465758 0.861204 0.24047 0.498113 0.833102 0.241329 0.497693 0.833104 0.279081 0.526967 0.802757 0.281676 0.52467 0.803356 0.342589 0.558087 0.755759 0.345348 0.555084 0.756714 0.386726 0.569701 0.725179 0.387924 0.568696 0.725328 0.429183 0.580158 0.692257 0.432044 0.576061 0.693896 0.494513 0.582403 0.645185 0.496282 0.579158 0.646746 0.503054 0.57912 0.641527 0.502116 0.581159 0.640417 0.501732 0.581159 0.640718 0.500848 0.583106 0.63964 0.501176 0.583105 0.639384 0.499924 0.585844 0.637858 0.500051 0.585844 0.637759 0.499305 0.587413 0.636899 0.50112 0.587406 0.635479 0.499448 0.590808 0.633638 0.546154 0.588289 0.596349 0.543275 0.594274 0.593035 0.606234 0.580261 0.543855 0.605147 0.583104 0.542021 0.642386 0.568766 0.513659 0.642255 0.568988 0.513577 0.675952 0.553462 0.48659 0.676276 0.552264 0.487499 0.727607 0.520028 0.44739 0.728232 0.516605 0.45033 0.764883 0.486471 0.422257 0.765257 0.484953 0.423323 0.809483 0.441129 0.387482 0.809505 0.440531 0.388117 0.865398 0.363497 0.3449 0.865556 0.364898 0.343019 0.889099 0.321839 0.325457 0.889057 0.322514 0.324904 0.909598 0.27884 0.308025 0.909894 0.279791 0.306284 0.935045 0.208556 0.286696 0.934796 0.208053 0.287874 0.948936 0.150437 0.27729 0.948378 0.149352 0.279775 0.957586 0.0943392 0.272266 0.956669 0.0935453 0.275743 0.959331 0.06932 0.273639 0.958957 0.0691299 0.274994 0.961018 0.0413101 0.273381 0.960597 0.0411591 0.274882 0.961335 0.0232069 0.274404 0.9168 0.0136478 0.399114 0.76645 0.00837092 0.642249 0.766217 0.0145951 0.642416 0.766473 0.0146063 0.64211 0.76574 0.0244866 0.642683 0.766067 0.0245249 0.642292 0.765104 0.0332392 0.643048 0.765975 0.033327 0.642006 0.762576 0.0531703 0.64471 0.763115 0.0532063 0.644068 0.758171 0.073835 0.647862 0.758462 0.073943 0.647509 0.749582 0.0991531 0.654442 0.749182 0.0989135 0.654937 0.74182 0.114115 0.660819 0.741566 0.114084 0.661109 0.733537 0.129181 0.66726 0.733155 0.128839 0.667745 0.713425 0.156222 0.683096 0.713576 0.156422 0.682892 0.697475 0.171957 0.695672 0.697821 0.172358 0.695226 0.684666 0.183351 0.705418 0.685151 0.184472 0.704655 0.666797 0.196007 0.719002 0.666923 0.196425 0.718771 0.654876 0.201823 0.728289 0.654848 0.201778 0.728327 0.641903 0.206934 0.738335 0.641735 0.205847 0.738785 0.619785 0.210743 0.755946 0.619681 0.208323 0.756702 0.603289 0.209065 0.769632 0.603406 0.207755 0.769896 0.602827 0.207758 0.770348 0.602896 0.207095 0.770472 0.60288 0.207095 0.770485 0.603006 0.206019 0.770675 0.60291 0.206021 0.77075 0.602993 0.205315 0.770873 0.603156 0.205317 0.770745 0.603251 0.204449 0.770902 0.600776 0.204478 0.772824 0.600698 0.205778 0.77254 0.578299 0.203523 0.790031 0.578031 0.20531 0.789765 0.563054 0.201023 0.801598 0.563054 0.201538 0.801469 0.548181 0.196409 0.812971 0.54776 0.197806 0.812915 0.525945 0.185845 0.829966 0.525512 0.186851 0.830014 0.511934 0.176208 0.840758 0.511844 0.17652 0.840747 0.498605 0.16506 0.850969 0.498155 0.165777 0.851094 0.480319 0.144942 0.865035 0.479971 0.145367 0.865157 0.469825 0.129415 0.873222 0.469751 0.129537 0.873243 0.460227 0.113156 0.88056 0.459983 0.113367 0.880661 0.448581 0.0862494 0.889571 0.448404 0.086364 0.889649 0.440481 0.0582981 0.895867 0.440644 0.0582215 0.895792 0.436599 0.0342006 0.899006 0.43695 0.0340907 0.89884 0.436324 0.0285726 0.899336 0.436155 0.0286173 0.899416 0.435765 0.0247185 0.899721 0.435798 0.0247107 0.899705 0.435205 0.0177648 0.900156 0.435213 0.0177638 0.900152 0.434817 0.00940623 0.900469 0.598424 0.00087756 0.801179 0.615953 1.76897e-07 0.787783 0.615959 4.19402e-06 0.787778 0.615951 1.08744e-05 0.787784 0.615952 2.56604e-06 0.787783 0.615954 -3.06659e-06 0.787782 0.615955 -4.18105e-06 0.787782 0.615955 -5.13429e-06 0.787781 0.615956 3.68344e-06 0.787781 0.615957 5.60323e-06 0.78778 0.615954 3.51127e-07 0.787782 0.615955 4.79971e-06 0.787782 0.615954 -2.33904e-06 0.787782 0.615953 3.23528e-06 0.787783 0.615954 -3.17134e-06 0.787782 0.615949 1.37922e-05 0.787786 0.615949 -6.61789e-06 0.787786 0.615955 3.3321e-06 0.787782 0.615957 -1.07495e-05 0.787779 0.615954 -1.21519e-06 0.787782 0.615956 -5.10664e-06 0.787781 0.615953 -2.67387e-06 0.787783 0.615961 4.53982e-06 0.787777 0.615951 -4.55948e-06 0.787785 0.615947 -9.57969e-06 0.787788 0.615954 3.58548e-07 0.787782 0.615953 -1.50923e-07 0.787783 0.615949 -2.63442e-06 0.787786 0.615956 5.28969e-07 0.787781 0.615947 -5.29238e-06 0.787788 0.615957 -4.38686e-06 0.78778 0.615958 3.58616e-06 0.787779 0.615956 2.04592e-06 0.787781 0.615958 3.37253e-06 0.787779 0.615956 7.43515e-06 0.78778 0.615955 1.55965e-06 0.787781 0.615955 4.08284e-06 0.787781 0.615955 2.29514e-06 0.787781 0.615954 6.52192e-07 0.787782 0.615952 -6.65768e-06 0.787784 0.615958 4.46938e-06 0.787779 0.615954 -2.32691e-06 0.787782 0.615947 -1.66939e-05 0.787788 0.615948 3.42655e-06 0.787786 0.61595 2.39747e-06 0.787785 0.615959 -2.66283e-06 0.787779 0.615959 -7.71995e-06 0.787778 0.615951 4.03175e-06 0.787785 0.615952 2.57368e-06 0.787784 0.615955 0 0.787781 0.615956 3.81213e-06 0.78778 0.615955 0 0.787781 0.615919 -0.000107369 0.787809 0.615954 -1.61806e-06 0.787782 0.615955 4.14194e-06 0.787782 0.61595 -1.99259e-06 0.787786 0.61596 2.63707e-06 0.787777 0.61594 -9.95949e-06 0.787793 0.615954 -2.84595e-07 0.787782 0.615954 -2.68298e-06 0.787782 0.615953 0 0.787783 0.615953 -1.57605e-06 0.787783 0.615953 6.40538e-06 0.787783 0.615954 -7.4269e-08 0.787782 0.615955 -5.33264e-07 0.787782 0.615954 -6.71661e-07 0.787782 0.615954 -1.58335e-06 0.787782 0.615953 3.74504e-07 0.787783 0.615955 -4.24124e-06 0.787781 0.615953 -8.28738e-07 0.787783 0.615957 -5.84301e-06 0.78778 0.615938 3.55696e-05 0.787795 0.615956 -1.5977e-06 0.787781 0.615952 -1.98583e-06 0.787783 0.615954 1.65342e-06 0.787782 0.615953 -3.14739e-06 0.787783 0.615955 2.48959e-06 0.787781 0.615954 -4.63297e-06 0.787782 0.615955 -4.38214e-07 0.787781 0.615955 -2.19805e-07 0.787781 0.615948 7.39034e-06 0.787787 0.615952 1.90884e-06 0.787784 0.615955 -2.05439e-06 0.787781 0.61595 -3.35829e-06 0.787785 0.61595 -3.27034e-06 0.787785 0.615976 3.04868e-05 0.787765 0.615948 4.75053e-06 0.787787 0.615952 2.23492e-06 0.787784 0.61595 3.23245e-06 0.787786 0.615962 -5.6415e-06 0.787776 0.615954 -1.46743e-08 0.787782 0.615953 1.41616e-06 0.787783 0.615957 6.85625e-07 0.78778 0.615955 5.68614e-07 0.787782 0.61595 -9.19262e-07 0.787786 0.615955 1.90591e-06 0.787781 0.615945 8.19657e-06 0.787789 0.615954 -7.22937e-07 0.787782 0.615958 -3.62763e-06 0.787779 0.615952 3.25087e-06 0.787784 0.615978 -1.87288e-05 0.787763 0.615954 -3.96128e-08 0.787782 0.615954 -7.07239e-08 0.787782 0.615954 2.43763e-07 0.787782 0.615954 9.36066e-08 0.787782 0.61595 1.20185e-06 0.787786 0.00274769 -0.999996 0.000971838 0.00593209 -0.999982 0.000689266 0.997109 -0.0179353 0.0738415 0.933403 0.14058 0.330146 0.880115 0.36674 0.301496 0.934369 0.100743 0.341768 0.900784 0.292531 0.320957 0.785292 0.554466 0.275471 0.741846 0.616662 0.263425 0.523399 0.831661 0.185457 0.472936 0.866019 0.162304 0.599517 0.771909 0.211506 0.183924 0.980785 0.0650542 0.120914 0.992013 0.0359184 0.274072 0.956827 0.0967847 -0.999987 0 0.00510167 -0.999987 -1.61599e-07 0.0051013 -0.999991 -1.36951e-07 0.00432501 -0.999991 0 0.00432532 0.978308 -4.46374e-07 0.207155 0.978159 -0.00275888 0.207838 0.97885 0.00498629 0.20452 0.978701 0 0.205291 0.978562 0 0.205951 0.978323 5.61217e-05 0.207084 0.978308 0.00024875 0.207155 0.978083 0 0.208215 0.978562 0 0.205951 0.978862 0 0.204522 0.978862 0 0.204522 -0.39403 0 0.919098 -0.39403 0 0.919098 -0.715762 0 0.698344 -0.715762 0 0.698344 -0.928522 0 0.371278 -0.928522 0 0.371278 -0.999924 0 -0.0123126 -0.999924 0 -0.0123126 0.977787 -0.0155258 0.209026 0.952167 -0.213702 0.218426 0.945353 -0.258818 0.198296 0.944754 -0.258819 0.201128 0.978163 -0.000875325 0.207837 0.961052 -0.19509 0.195753 0.877771 -0.442288 0.18412 0.692047 -0.707106 0.145163 0.778735 -0.608735 0.151704 0.595797 -0.793352 0.124974 0.253103 -0.965926 0.0540959 0.253307 -0.965926 0.0531333 0.253307 -0.965926 0.0531333 0.958915 -0.195089 0.205966 0.962847 -0.177782 0.20327 0.872159 -0.442192 0.209297 0.941646 -0.269812 0.201259 0.775831 -0.608761 0.165819 0.690282 -0.70709 0.153411 0.595315 -0.793354 0.127237 0.253103 -0.965926 0.0540959 -0.0536153 -0.965926 0.253206 -0.203171 -0.195089 0.959511 -0.193996 -0.258818 0.946245 -0.176313 -0.55557 0.812561 -0.164344 -0.608761 0.776145 -0.120059 -0.814919 0.567003 -0.128989 -0.793346 0.594949 -0.0779535 -0.923297 0.376092 -0.0232891 -0.985737 0.166675 -0.12899 0.793345 0.59495 -0.0497419 0.965918 0.254023 -0.0463208 0.974679 0.218756 -0.120059 0.814919 0.567003 -0.172239 0.555575 0.813431 -0.170432 0.608749 0.77484 -0.195082 0.195082 0.96119 -0.200092 0.258823 0.944973 -0.3685 0.0247241 -0.929299 -0.320798 0.00979505 -0.947097 -0.400071 0.0390555 -0.915651 -0.424887 0.0519255 -0.903756 -0.433514 0.0569355 -0.899347 0.0436546 0.044591 -0.998051 -0.145104 0.00703224 -0.989392 -0.157265 0.00503307 -0.987544 -0.164888 0.00390483 -0.986305 -0.196929 -0.000234561 -0.980418 -0.259092 0.000291487 -0.965853 0.801773 0.0954151 -0.589963 0.780835 0.0442382 -0.623169 0.721549 0.03074 -0.691681 0.709077 0.022478 -0.704773 0.701874 0.0182792 -0.712066 0.697928 0.0161246 -0.715987 0.693357 0.0137905 -0.720462 0.690733 0.0126001 -0.723 -0.000371183 0 -1 0.433549 0 -0.90113 0.433549 0 -0.90113 0.662424 0 -0.749129 0.662424 0 -0.749129 0.94041 0.0168125 -0.339626 0.91829 4.36548e-05 -0.395907 0.885772 -3.49132e-05 -0.46412 0.956122 0.0359416 -0.290757 0.972132 0.0745608 -0.222262 0.985792 0.0260409 -0.16594 0.973883 0.0480758 0.221902 0.99877 4.97187e-06 0.0495835 0.99933 -3.66981e-06 -0.0365983 -0.534613 0 -0.845097 -0.782063 0 -0.6232 -0.782063 0 -0.6232 -0.97501 0 -0.222159 -0.97501 0 -0.222159 -0.974845 0 0.222883 -0.974845 0 0.222883 -0.7816 0 0.62378 -0.7816 0 0.62378 -0.433549 0 0.90113 -0.433549 0 0.90113 0.000371183 0 1 0.000371183 0 1 0.434218 0 0.900808 0.434218 0 0.900808 0.782063 0 0.6232 0.782063 0 0.6232 0.94934 0 0.31425 0.977066 0.0673778 0.201995 0.987903 0.0115788 0.154641 0.993974 0 0.109619 0.935797 0 -0.352539 0.935797 -4.96373e-07 -0.352539 0.935797 1.07928e-06 -0.352538 0.983662 -0.0962594 0.152127 0.921827 -6.80155e-05 -0.387602 0.973236 -0.0574298 -0.222515 0.948833 -0.133193 -0.286313 0.981616 -0.0385496 -0.186935 0.993974 0 0.109619 0.970875 -0.0330024 0.237301 0.974153 -0.223473 0.0329546 0.97501 -2.22765e-05 0.222159 0.99933 3.6698e-06 -0.0365982 0.996314 -0.00977173 -0.0852202 0.433549 0 -0.90113 0.662424 0 -0.749129 0.662424 0 -0.749129 0.705529 -0.0202997 -0.70839 0.690738 -0.0125979 -0.722995 0.694412 -0.014272 -0.719437 0.699252 -0.0168443 -0.714677 0.712999 -0.0250568 -0.700718 0.721549 -0.0307399 -0.69168 0.779333 -0.0761049 -0.621971 0.804948 -0.0352389 -0.592298 0.885792 4.48758e-05 -0.464082 -0.195119 0 -0.98078 -0.158713 -0.00469946 -0.987314 -0.142316 -0.00759681 -0.989792 -0.000370944 -0.0359506 -0.999354 0.0436981 0 -0.999045 0.433549 0 -0.90113 -0.424888 -0.0519256 -0.903756 -0.531045 -0.115325 -0.839459 -0.276802 -0.202454 -0.939358 -0.28906 0 -0.957311 -0.3685 -0.0247241 -0.929299 -0.400071 -0.0390555 -0.915651 0.94934 0 0.31425 0.782063 0 0.6232 0.782063 0 0.6232 0.434218 0 0.900808 0.434218 0 0.900808 0.000371183 0 1 0.000371183 0 1 -0.433549 0 0.90113 -0.433549 0 0.90113 -0.7816 0 0.62378 -0.7816 0 0.62378 -0.974845 0 0.222883 -0.974845 0 0.222883 -0.97501 0 -0.222159 -0.97501 0 -0.222159 -0.782063 0 -0.6232 -0.782063 0 -0.6232 -0.434218 0 -0.900808 0.935797 1.41724e-07 -0.352539 0.935797 2.18638e-06 -0.352539 0.935797 0 -0.352539 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.347229 0 0.93778 -0.347229 0 0.93778 -0.769615 0 0.638509 -0.769615 0 0.638509 -0.98576 0 0.168159 -0.98576 0 0.168159 -0.101957 0.814913 0.570545 -0.111923 0.772804 0.624697 -0.104831 0.814977 0.569932 -0.0902493 0.859782 0.502624 -0.0383147 0.974678 0.220304 -0.0418046 0.971631 0.232779 -0.000325656 0.999998 0.00182056 -0.172698 0.195088 0.965461 -0.189179 0.0528351 0.98052 -0.172903 0.226053 0.958647 -0.144338 0.555574 0.818843 -0.162332 0.474974 0.864898 -0.133381 0.651872 0.746507 -0.175847 -0.0516458 0.983062 -0.176257 -0.195087 0.964818 -0.172903 -0.226053 0.958647 -0.101958 -0.814913 0.570545 -0.154413 -0.468894 0.869652 -0.150517 -0.55557 0.817733 -0.133381 -0.651873 0.746506 -0.102353 -0.814922 0.570461 -0.115609 -0.77661 0.619284 -0.0637144 -0.923292 0.378778 -0.0925921 -0.862065 0.498267 -0.0295615 -0.985807 0.165262 -0.00816866 -0.999878 -0.013289 -0.0386631 -0.969837 0.240667 0.0259531 0.900659 0.433752 0.0248316 0.912313 0.40874 0.0339293 0.816643 0.576145 0.033955 0.814943 0.578546 0.00195315 0.999471 0.032452 0.00982326 0.980782 0.19486 0.00121651 0.99241 0.122966 0.0170699 0.960711 0.277025 0.0478135 0.55554 0.830114 0.0477936 0.598532 0.799672 0.0419988 0.715918 0.696921 0.0599992 0.0509347 0.996898 0.0581357 0.151107 0.986806 0.0565572 0.195122 0.979147 0.0575597 0.319264 0.945916 0.0528396 0.462777 0.884899 0.0170699 -0.960711 0.277025 0.0599992 -0.0509347 0.996898 0.04949 -0.555541 0.830015 0.04539 -0.594874 0.802537 0.0528395 -0.462778 0.884898 0.0603981 -0.195122 0.978918 0.0516541 -0.313666 0.948128 0.0581357 -0.151107 0.986806 0.024539 -0.912313 0.408757 0.0261669 -0.900918 0.433201 0.0340587 -0.814943 0.57854 0.0338105 -0.816467 0.576402 0.0419989 -0.715916 0.696922 0.0117209 -0.980784 0.194746 -0.00657635 -0.998333 0.0573491 0.00121651 -0.99241 0.122966 -0.0385143 -0.768983 -0.638108 -0.0361922 -0.814916 -0.578449 -0.0281406 -0.878493 -0.476925 -0.0147085 -0.974677 -0.223135 -0.0114781 -0.981768 -0.189734 -9.77727e-05 -0.999999 -0.00162454 -0.058924 -0.195049 -0.979022 -0.0653795 -0.0679231 -0.995546 -0.0588429 -0.241504 -0.968614 -0.0490385 -0.555594 -0.830007 -0.057863 -0.456054 -0.888069 -0.0461558 -0.637559 -0.769018 -0.0599425 0.0670954 -0.995944 -0.0608007 0.195048 -0.978907 -0.0281406 0.878493 -0.476925 -0.040719 0.771688 -0.634697 -0.0350235 0.814916 -0.57852 -0.0461559 0.637559 -0.769018 -0.0519609 0.555593 -0.829829 -0.0531931 0.451636 -0.890615 -0.0588429 0.241504 -0.968614 -0.013434 0.974677 -0.223212 -0.00837791 0.999847 0.0153797 -0.012745 0.982399 -0.186359 -0.727871 -3.44018e-06 0.685714 -0.727876 0 0.685708 -0.727933 4.19332e-06 0.685648 -0.72787 3.02618e-07 0.685715 -0.727868 -6.64963e-08 0.685717 -0.727866 1.15734e-06 0.68572 -0.727869 -4.06961e-07 0.685716 -0.727864 5.1261e-06 0.685722 -0.727869 -5.76684e-07 0.685717 -0.727939 -2.51226e-05 0.685641 -0.727867 6.61701e-07 0.685718 -0.72787 -2.89124e-06 0.685715 -0.728247 -0.000681481 0.685314 -0.727868 2.00934e-06 0.685717 -0.727869 0 0.685717 -0.727869 0 0.685717 -0.727863 1.18112e-05 0.685723 -0.727875 -1.16471e-05 0.68571 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.99646 -0.00045798 0.0840732 0.996333 0 0.0855652 0.996353 0.00486916 0.0851877 0.996521 0.00425865 0.0832381 0.995136 0 0.0985078 0.992627 0 0.12121 0.992627 0 0.12121 0.978675 0 0.205414 0.978675 0 0.205414 0.813062 0 0.582177 0.813062 0 0.582177 0.509737 0 0.86033 0.509737 0 0.86033 0.120072 0 0.992765 0.226303 -0.010751 0.973998 0.0210325 0 0.999779 1 0 -0.0003714 1 0 -0.0003714 0.995148 0 -0.098385 0.965801 -0.0077082 -0.25917 0.956394 -0.00502874 -0.292035 0.793112 0.00607655 -0.609045 0.831263 0 -0.555879 0.608468 0 -0.793579 0.557804 0.00368527 -0.829965 0.258456 -0.00538283 -0.966008 0.194726 0 -0.980858 0.25846 0 -0.966022 0.187661 0.0073326 -0.982206 0.608459 -0.00538287 -0.793567 0.555262 0 -0.831676 0.793127 0 -0.609056 0.832489 -0.003997 -0.554027 0.96583 0 -0.259177 0.994749 0.0201999 -0.100335 0.956394 0.00502874 -0.292035 1 0 -0.0003714 1 0 -0.0003714 0.978675 0 0.205414 0.978675 0 0.205414 0.813062 0 0.582177 0.813062 0 0.582177 0.509737 0 0.86033 0.509737 0 0.86033 0.226316 0 0.974054 0.12007 0.00518111 0.992752 0.0210325 0 0.999779 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.998194 2.69449e-06 -0.0600745 0.998194 -3.44504e-07 -0.0600735 0.998194 1.39199e-07 -0.0600736 0.998194 -3.56199e-06 -0.0600744 0.998194 0 -0.0600736 0.998192 -0.001624 -0.0600889 0.998194 -1.13744e-06 -0.0600732 0.998194 1.06104e-06 -0.0600742 0.998194 0 -0.0600735 0.998194 0 -0.0600736 0.998194 3.56199e-06 -0.0600744 0.998194 -1.39199e-07 -0.0600736 0.998194 3.44504e-07 -0.0600735 0.998194 -2.69449e-06 -0.0600746 0.998212 0.00089266 -0.0597613 0.998194 2.32346e-05 -0.0600694 0.998194 0 -0.060078 -0.996836 0 -0.0794893 -0.996823 0.000206526 -0.0796466 -0.99875 -0.0009084 -0.0499768 -0.998737 0.000461128 -0.0502368 -0.999974 -0.000299584 -0.00720875 -0.999973 0 -0.00730776 -0.999755 0 0.0221299 -0.999755 0 0.0221299 -0.998328 0 0.0578009 -0.998328 0 0.0578009 -0.995217 0 0.0976927 -0.995217 0 0.0976927 -0.991034 0 0.133609 -0.991034 0 0.133609 -0.984449 0 0.17567 -0.984442 -8.01501e-05 0.175711 -0.971696 0.000145473 0.236234 -0.971675 -0.000145568 0.236323 -0.951291 0.000108967 0.308295 -0.951275 0 0.308344 -0.9853 0 -0.170835 -0.9853 0 -0.170835 -0.985278 0 -0.170961 -0.985278 0 -0.170961 -0.97917 0 -0.203044 -0.97917 0 -0.203044 -0.980372 0 -0.197158 -0.980372 0 -0.197158 -0.981033 0 -0.193842 -0.981033 0 -0.193842 -0.982496 0 -0.186284 -0.982496 0 -0.186284 -0.993438 0 -0.114371 -0.993438 0 -0.114371 -0.991715 0 -0.128459 -0.991715 0 -0.128459 -0.98868 0 -0.15004 -0.98868 0 -0.15004 -0.983592 0 -0.180407 -0.983592 0 -0.180407 -0.98074 0 -0.195317 -0.98074 0 -0.195317 -0.977977 0 -0.208715 -0.977977 0 -0.208715 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.99545 0 0.0952837 0.979837 0.138352 0.144145 0.997318 -0.0466739 -0.0563837 0.957347 0.138352 -0.253664 0.978368 0 -0.206874 0.993964 -1.48048e-06 0.109711 0.994004 -0.000501504 0.109346 0.99371 0.000260922 0.111981 0.993691 0.000373737 0.112154 0.993626 0.000149778 0.112728 0.993131 0 0.117011 0.993091 0.000675678 0.117344 0.993516 -7.98111e-05 0.113692 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0410121 -0.995559 0.0847333 0.397842 -0.783681 0.477037 0.410808 -0.799548 0.438131 0.323418 -0.857368 0.400402 0.363957 -0.840236 0.40192 0.287453 -0.895289 0.340335 0.279383 -0.899512 0.335893 0.163138 -0.96772 0.192105 0.196891 -0.957518 0.210697 0.128008 -0.978274 0.163078 0.362368 -0.843699 0.396058 0.0145091 -0.999798 0.013887 0.0903843 -0.991611 0.0924074 0.163365 -0.962564 0.216291 0.176919 -0.959483 0.219297 0.290609 -0.914047 0.282956 0.370445 -0.833699 0.409531 0.202133 -0.81494 0.543153 0.378734 -0.825262 0.418932 0.0519819 -0.984037 0.170201 0.0524427 -0.984045 0.170014 0.258064 -0.94728 0.189904 0.104853 -0.938642 0.328568 0.363412 -0.845691 0.390818 0.0054271 -0.992657 0.120844 0.00234437 -0.994846 0.101372 0.00166014 -0.999931 0.0116202 0.000663416 -0.997406 -0.0719765 0.00123446 -0.997408 -0.0719472 0.000371786 -0.997997 -0.0632678 7.91232e-05 -0.997419 -0.071803 -0.000254801 -0.997413 -0.0718799 -0.0015575 -0.997349 -0.0727489 0.00204933 -0.997783 -0.0665167 -0.00178466 -0.997609 -0.0690842 0.00247853 -0.998091 -0.0617097 0.000898016 -0.998027 -0.0627725 -0.000769007 -0.997987 -0.0634115 0.00164891 -0.998055 -0.0623162 -0.000974201 -0.99661 -0.0822637 -0.001009 -0.996606 -0.0823079 -0.000968025 -0.996671 -0.0815259 -0.00102258 -0.996613 -0.0822328 -0.00103584 -0.996616 -0.0821909 -0.00109738 -0.996619 -0.0821493 -0.00099484 -0.996639 -0.0819141 -0.00104049 -0.996641 -0.0818891 -0.000925125 -0.996663 -0.0816239 -0.000921065 -0.996663 -0.0816256 -0.000945429 -0.996667 -0.0815679 -0.00104648 -0.996671 -0.0815219 -0.000856839 -0.996602 -0.0823679 -0.000885789 -0.996599 -0.0823945 -0.000885164 -0.9966 -0.082393 -0.000874906 -0.996603 -0.0823571 -0.000944228 -0.996594 -0.0824627 -0.00098382 -0.996605 -0.0823262 -0.000978892 -0.996608 -0.0822914 -0.00103383 -0.996611 -0.0822585 -0.000152324 -0.997324 -0.0731051 0.000313336 -0.997291 -0.0735532 0.00171053 -0.99728 -0.0736849 0.000327281 -0.99724 -0.0742498 -0.000218283 -0.997199 -0.0747893 -5.99044e-05 -0.997206 -0.0746969 -0.000203017 -0.997172 -0.075147 -3.73958e-05 -0.997178 -0.0750697 -0.00103639 -0.997106 -0.0760115 0.000305106 -0.997009 -0.07728 -0.00105802 -0.99688 -0.0789195 -0.000218985 -0.996818 -0.0797099 -0.000780369 -0.996749 -0.0805718 -0.000685488 -0.996751 -0.0805427 -0.000811323 -0.99673 -0.0807987 -0.000706341 -0.996734 -0.0807456 -0.000945331 -0.99671 -0.0810427 -0.000900791 -0.996713 -0.0810136 -0.000827527 -0.996693 -0.081256 -0.000937892 -0.996671 -0.0815207 -0.000934606 -0.996671 -0.0815224 0.000521458 -0.996964 -0.0778659 0.00143154 -0.997228 -0.0743914 0.00208619 -0.997669 -0.0682034 0.00124343 -0.998201 -0.059939 0.000809177 -0.997456 -0.0712826 0.00112068 -0.997265 -0.0739068 0.000923854 -0.997281 -0.0736826 0.00119896 -0.997205 -0.0746984 0.00208638 -0.997139 -0.0755652 0.000444432 -0.997039 -0.0768917 -0.00671222 -0.997013 -0.0769393 0.000200093 -0.997118 -0.0758664 0.00111961 -0.997113 -0.075928 -0.000570109 -0.997093 -0.0761899 0.00392102 -0.99707 -0.0763993 0.00193499 -0.997026 -0.0770407 0.000236875 -0.996917 -0.0784633 0.000262014 -0.996881 -0.0789158 0.000488483 -0.996725 -0.0808628 -0.000670791 -0.996836 -0.0794842 -0.000253111 -0.996601 -0.0823829 -0.000976161 -0.996671 -0.0815282 -0.000859648 -0.996614 -0.0822175 -0.000845298 -0.996606 -0.0823182 -0.00334198 -0.999361 -0.0355963 -0.014505 -0.999246 -0.0360156 0.00113073 -0.999463 -0.0327539 0.0019448 -0.999506 -0.0313567 -0.000950758 -0.999155 -0.0411014 0.00166044 -0.999199 -0.0399903 0.00258205 -0.998387 -0.0567137 0.00188199 -0.998817 -0.0485943 0.00218103 -0.998797 -0.0489933 0.00144674 -0.998948 -0.0458455 -0.00157449 -0.999092 -0.0425648 0.000685385 -0.998922 -0.046421 -0.00112345 -0.998877 -0.0473719 0.0073384 -0.999214 -0.038947 0.00125447 -0.999372 -0.0354189 -0.00100537 -0.999384 -0.0350897 0.0015133 -0.999571 -0.0292602 0.00110711 -0.999647 -0.0265274 -0.0014203 -0.999895 -0.0144121 0.00138572 -0.999831 -0.0183152 -0.000708268 -0.999995 0.00315828 -0.00167604 -0.999988 0.00456838 -0.000354823 -0.999904 0.0138438 -0.000807458 -0.999913 0.0131661 -0.000687656 -0.999894 0.0145263 -0.000604897 -0.999903 0.0139075 -0.00010885 -0.999926 0.0121539 -0.00425426 -0.996274 0.0861422 -0.012039 -0.996512 0.0825764 -0.219655 -0.975137 0.0293208 -0.163904 -0.985535 0.0430788 -0.0403035 -0.996433 0.0741393 -6.10563e-05 -0.996753 0.0805198 0.000204139 -0.996728 0.0808342 -0.0027451 -0.99846 0.0554008 -0.00433666 -0.998548 0.0537002 0.000443288 -0.998871 0.0475111 0.00475362 -0.998946 0.0456534 0.00432738 -0.998987 0.0447893 0.000539148 -0.999375 0.0353352 -0.00304717 -0.9998 0.019764 0.00148311 -0.999589 0.0286277 -0.0024905 -0.999877 0.0154892 -0.000283013 -0.999747 0.0224933 -0.00080983 -0.999843 0.0177145 0.000692811 -0.995885 0.0906224 0.000640838 -0.995663 0.0930308 0.00126338 -0.995935 0.0900656 8.70307e-05 -0.995325 0.0965823 0.00140104 -0.995619 0.0934955 0.00162887 -0.995686 0.0927769 0.000222029 -0.995916 0.0902802 -0.0011432 -0.99607 0.0885583 0.00300679 -0.994947 0.100359 0.00232761 -0.994777 0.102044 0.00381171 -0.994269 0.10684 0.00318525 -0.994397 0.105661 0.00459998 -0.993727 0.111741 0.00197109 -0.994796 0.101868 -0.000240249 -0.994668 0.103128 -0.000522266 -0.994664 0.103163 0.00631359 -0.993776 0.111222 0.0061941 -0.993531 0.113397 0.00166729 -0.992781 0.119931 -0.0172639 -0.992599 0.120201 0.0138188 -0.991149 0.132032 0.0200617 -0.990321 0.137335 0.00222951 -0.993822 0.110961 0.00444945 -0.993562 0.113199 0.00596795 -0.993023 0.117769 0.00316351 -0.992677 0.12076 0.0051581 -0.992777 0.119868 0.109812 0.98838 0.105104 0.102608 0.971845 0.212107 0.124565 0.976198 0.17754 0.362283 0.872843 0.326949 0.454581 0.817394 0.353868 0.293853 0.829852 0.474337 0.00235392 0.994809 0.101736 -0.000807689 0.999825 0.0187129 -0.000651435 0.999803 0.0198249 0.0177212 0.998858 0.044375 0.00294901 0.99904 0.0437053 -0.000800866 0.999549 0.0300131 -0.00120227 0.99971 0.0240485 0.00204253 0.995227 0.0975617 0.00140221 0.995586 0.0938416 0.000620793 0.995888 0.0905868 0.00354115 0.998939 0.0459074 0.000195368 0.998855 0.0478322 -0.00433666 0.998548 0.0537002 -0.00274457 0.99846 0.0554013 0.000203979 0.996728 0.0808338 -6.10744e-05 0.996753 0.0805195 0.000716355 0.995856 0.0909377 0.00170205 0.995665 0.0929986 0.000441044 0.995884 0.0906342 -0.000696379 0.996027 0.0890478 -0.00318721 0.996217 0.0868419 -0.00921076 0.996449 0.0836879 -0.0277239 0.996597 0.0776218 -0.0895474 0.994055 0.0619298 -0.163904 0.985535 0.0430788 -0.219628 0.975143 0.0293276 0.00179034 0.999929 0.0118052 -0.00323398 0.999362 -0.0355729 -0.00100769 0.999384 -0.0350902 0.0012564 0.999372 -0.0354201 -0.00587395 0.999182 -0.0399999 0.000351898 0.99902 -0.0442518 0.00244296 0.998837 -0.048153 -4.28968e-05 0.999924 0.012325 -0.000598987 0.999901 0.0140705 -0.000722407 0.999889 0.014879 -0.00093464 0.999907 0.0135732 -0.000301475 0.999899 0.0142183 -0.00162198 0.999986 0.00494788 -0.000651972 0.999997 0.00256257 0.00138795 0.999831 -0.0183191 -0.00141923 0.999895 -0.0144146 0.00132078 0.99962 -0.0275488 0.00149632 0.999523 -0.0308607 -0.00112637 0.998877 -0.0473725 0.0109316 0.999098 -0.0410298 -0.00161013 0.999175 -0.0405906 0.00447879 0.999211 -0.0394726 0.00163715 0.999224 -0.0393558 -0.00130118 0.999203 -0.0398925 -0.0531863 0.998373 -0.0205599 0.00189759 0.997213 -0.0745792 0.000697343 0.997227 -0.0744151 0.00259154 0.997115 -0.0758643 0.00391681 0.99707 -0.0763987 0.00133404 0.997006 -0.0773155 0.000456239 0.997039 -0.0768908 0.00143542 0.997228 -0.0743911 -0.00670642 0.997013 -0.0769384 0.00111026 0.997128 -0.0757249 0.000209437 0.997102 -0.0760691 -0.000568098 0.997093 -0.0761896 0.00116962 0.997255 -0.0740342 0.00109348 0.997281 -0.0736874 0.000752912 0.997489 -0.0708182 0.00213431 0.997636 -0.0686839 0.00119054 0.998231 -0.0594429 0.00262627 0.998358 -0.0572266 0.00193339 0.998788 -0.0491904 0.00140751 0.998868 -0.0475554 -0.000199326 0.99657 -0.0827581 -0.0006712 0.996836 -0.0794834 0.000487416 0.996725 -0.0808612 0.000226584 0.996905 -0.0786188 0.000394734 0.996951 -0.0780253 -0.00104318 0.996703 -0.0811316 -0.000844878 0.996607 -0.0823049 -0.000866056 0.996595 -0.082447 -0.000877923 0.996595 -0.0824469 -0.000870531 0.996603 -0.0823551 -0.000873007 0.996602 -0.0823622 -0.000942728 0.996596 -0.0824414 -0.00098206 0.996604 -0.0823331 -0.000977096 0.996609 -0.0822734 -0.00113784 0.996681 -0.0813972 -0.000817384 0.996672 -0.0815107 -0.00085402 0.996705 -0.0811135 -0.000937271 0.996712 -0.081018 -0.000697208 0.996732 -0.0807772 -0.00100899 0.996606 -0.0823079 -0.000985186 0.996608 -0.0822948 -0.00103385 0.996613 -0.0822306 -0.00104742 0.996613 -0.0822238 -0.000982712 0.996672 -0.0815068 -0.000934598 0.99667 -0.0815366 -0.000998956 0.99667 -0.0815324 -0.000910866 0.996665 -0.0815966 -0.000963566 0.996664 -0.0816052 -0.000898357 0.996662 -0.0816331 -0.00106397 0.996642 -0.081874 -0.000972325 0.996638 -0.081924 -0.00111676 0.996621 -0.0821337 -0.00101486 0.996615 -0.0822026 -0.00099452 0.996614 -0.0822122 -0.000208967 0.997191 -0.0748946 -9.44649e-05 0.997196 -0.0748302 -0.000189873 0.997167 -0.0752163 -0.000884797 0.997117 -0.0758714 0.000170085 0.996997 -0.07744 -0.00097387 0.996889 -0.078816 -0.000293397 0.996809 -0.0798242 -0.000722787 0.996756 -0.0804834 -0.000726823 0.996742 -0.0806566 -0.000873096 0.996726 -0.0808473 0.00089866 0.998028 -0.0627712 0.00519269 0.998192 -0.0598833 -0.0044867 0.997474 -0.0708936 0.00433069 0.997877 -0.0649888 -1.99535e-05 0.998044 -0.062518 0.00118615 0.998034 -0.062661 0.00037179 0.997997 -0.0632678 -0.00383034 0.997231 -0.0742644 -0.000349488 0.997409 -0.0719431 0.000805986 0.99744 -0.0715094 0.000123827 0.997229 -0.0743961 0.00129641 0.997272 -0.0738011 0.00155458 0.997278 -0.07372 -0.000219383 0.997312 -0.0732697 0.00108307 0.997405 -0.0719813 0.000968792 0.997405 -0.071993 0.000143652 0.997414 -0.0718686 9.64175e-06 0.997414 -0.0718684 0.0200649 0.990321 0.137338 0.0138176 0.991149 0.132031 -0.0172642 0.992599 0.120201 0.00166734 0.992781 0.119931 0.0114625 0.994323 0.105783 -0.0189231 0.994362 0.104338 -0.0019503 0.99462 0.103569 0.00317083 0.992678 0.120751 0.0051634 0.992776 0.11987 0.00149431 0.994755 0.102281 0.00265265 0.994884 0.100986 0.00235744 0.994819 0.101632 0.00368587 0.994294 0.106607 0.0034156 0.994367 0.10594 0.0037358 0.994139 0.108041 0.00410876 0.993945 0.109802 0.00413558 0.993595 0.112923 0.00448523 0.99355 0.113304 0.00627505 0.992912 0.11869 0.004255 0.992814 0.119595 0.121037 0.962595 0.242408 0.114536 0.96522 0.235014 0.11087 0.960809 0.254073 0.241711 0.907372 0.343878 0.245189 0.903921 0.350441 0.336714 0.841786 0.421925 0.345037 0.861686 0.372085 0.377143 0.818557 0.433276 0.374173 0.82119 0.430862 0.423378 0.820941 0.383154 0.315401 0.867812 0.383959 0.310042 0.887874 0.339933 0.246917 0.940201 0.234637 0.130415 0.979352 0.15447 0.121249 0.98339 0.135067 0.0359185 0.998763 0.0343785 -0.531299 0 0.847185 -0.531299 0 0.847185 -0.531294 -2.73323e-06 0.847187 -0.531299 -6.90159e-09 0.847185 -0.531299 0 0.847185 -0.531295 -3.45889e-06 0.847187 -0.531428 7.17545e-05 0.847104 -0.531304 2.87204e-06 0.847181 -0.531299 5.43381e-08 0.847185 -0.531293 -5.497e-06 0.847188 -0.531322 2.23567e-05 0.84717 -0.531301 2.63184e-06 0.847183 -0.531301 2.73503e-06 0.847183 -0.531123 -0.000211232 0.847295 -0.451912 2.18439e-06 -0.892062 -0.451904 0 -0.892067 -0.451909 -2.30511e-07 -0.892064 -0.451901 2.5459e-07 -0.892068 -0.451914 0 -0.892062 -0.451908 0 -0.892064 -0.451908 0 -0.892064 -0.451889 -7.50273e-05 -0.892074 -0.451912 4.01798e-06 -0.892063 -0.451908 -8.6732e-07 -0.892065 -0.451908 -1.22817e-07 -0.892064 -0.451881 -1.54672e-05 -0.892078 -0.451918 4.71079e-06 -0.892059 -0.697132 0 0.716942 -0.666148 0.00169741 0.745818 -0.875358 -0.00101801 0.483475 -0.92981 0.00203379 0.368035 -0.968721 -1.83848e-07 0.248151 -0.996646 1.78787e-07 0.0818285 -0.998958 0.00201537 -0.0455984 -0.985441 -0.00100044 -0.170015 -0.892415 0.00132655 -0.451214 -0.873052 1.19242e-05 -0.487628 -0.661695 -1.21644e-05 -0.749773 -0.628913 0.00134159 -0.777474 -0.489426 0 -0.872045 0.977913 0 0.20901 0.977905 -0.000242345 0.209048 0.978701 0.000311472 0.205291 0.978691 0 0.205338 0.952212 0 0.305439 0.933784 0.00410533 0.357814 0.330654 -0.00703963 0.943726 0.242945 -0.00114001 0.970039 0.467267 0.000682097 0.884116 0.454943 0.0012227 0.89052 0.57164 -0.000629292 0.820504 0.598513 -0.0012945 0.801112 0.718618 0.00319019 0.695397 0.761899 -2.87987e-06 0.647696 0.860255 1.49898e-06 0.509864 0.28545 -0.0047934 0.958382 0.227719 -0.00218701 0.973724 -0.0907802 0.00467783 0.99586 0.123363 -0.0149279 0.992249 -0.307543 0.0162234 0.951396 0.0494089 -0.0177409 0.998621 -0.0180009 -0.0122044 0.999763 -0.266884 0 0.963729 -0.266884 0 0.963729 -0.174046 -0.00368519 0.984731 -0.117424 -0.00590467 0.993064 0.999569 0 0.0293524 0.992378 0.00426497 -0.123154 0.992694 0.0041553 -0.120591 -0.19013 0 -0.981759 0.962445 -9.04658e-06 -0.271477 0.901214 6.88118e-06 -0.433374 0.852105 0.00219351 -0.523366 0.765454 -0.00209764 -0.643488 0.695054 2.09229e-05 -0.718958 0.502495 -4.93246e-05 -0.86458 0.538499 -0.0021289 -0.842623 0.271897 0.00154862 -0.962325 0.312588 1.16981e-05 -0.949889 0.109799 -8.19551e-06 -0.993954 0.172929 -0.00157172 -0.984933 -0.140074 0.00431053 -0.990132 0.105837 -0.0123325 -0.994307 -0.00668567 -0.00625215 -0.999958 -0.303861 0 -0.952716 -0.303861 0 -0.952716 -0.303983 0.00015916 -0.952677 -0.303862 4.19089e-07 -0.952716 -0.303864 2.75089e-06 -0.952715 -0.304677 0 -0.952456 -0.303861 -7.48634e-07 -0.952716 -0.303859 -2.24066e-06 -0.952717 -0.303861 0 -0.952716 -0.303863 7.77542e-07 -0.952716 -0.303862 7.16193e-07 -0.952716 -0.303861 1.65482e-07 -0.952716 -0.359686 0 0.933073 -0.359686 0 0.933073 -0.359686 0 0.933073 -0.359687 2.74835e-07 0.933073 -0.359686 -1.79962e-07 0.933073 -0.359686 3.26425e-08 0.933073 -0.359687 8.26068e-08 0.933073 -0.995815 0.000433507 0.0913909 -0.894543 -0.00101695 0.446981 -0.938252 0.006459 0.345892 -0.816881 -4.29516e-05 0.576806 -0.576486 0.000107447 0.817107 -0.7124 0.0111711 0.701685 -0.52662 0 0.850101 -0.990188 0.00707631 -0.139564 -0.999562 0 -0.0295897 -0.939473 0 -0.342623 -0.866531 0.00332947 -0.499112 -0.827477 0 -0.561499 -0.692479 0 -0.721438 -0.52714 0.00201591 -0.849776 -0.49551 0 -0.868602 0.983966 0 0.178359 0.983958 -0.000195977 0.178399 0.98478 0.000196798 0.173805 0.984773 0 0.173844 -0.531304 -2.9618e-06 0.847181 -0.531439 -7.72202e-05 0.847097 -0.531299 2.18921e-07 0.847185 -0.531294 -1.9773e-07 0.847188 -0.531299 0 0.847185 -0.531299 0 0.847185 -0.531299 0 0.847185 -0.531123 0.000211232 0.847295 -0.531301 -2.63532e-06 0.847183 -0.531297 1.92901e-06 0.847186 -0.531299 -1.33119e-07 0.847185 -0.531329 -1.47641e-05 0.847166 -0.531293 3.06048e-06 0.847188 -0.451914 0 -0.892062 -0.451908 0 -0.892064 -0.451908 0 -0.892064 -0.451908 -1.0599e-07 -0.892064 -0.451902 4.42358e-06 -0.892068 -0.451904 0 -0.892067 -0.451912 -2.37001e-06 -0.892062 -0.451918 -6.05677e-06 -0.892059 -0.451909 -4.10545e-07 -0.892064 -0.451888 2.70572e-05 -0.892075 -0.451911 -2.82136e-06 -0.892063 -0.451877 3.74081e-05 -0.89208 -0.451912 -4.05601e-06 -0.892062 -0.45189 7.50398e-05 -0.892074 -0.628914 0 -0.777475 -0.595165 -0.00168037 -0.803601 -0.827622 0.0010067 -0.561285 -0.892414 -0.00201974 -0.451214 -0.942027 4.22408e-07 -0.335537 -0.984993 -3.11158e-07 -0.172595 -0.998958 -0.0020108 -0.0455984 -0.996876 0.000996512 0.0789756 -0.929811 -0.00132382 0.368035 -0.914208 -2.67514e-05 0.405244 -0.697132 0 0.716942 -0.567472 -0.00670036 0.823365 -0.72779 2.62773e-05 0.6858 0.977701 0 0.210001 0.977701 0 0.210001 0.977905 0 0.209051 0.977905 0 0.209051 -0.739226 0 0.673458 -0.739226 0 0.673458 -0.739232 -5.12166e-06 0.673451 -0.739217 7.67185e-06 0.673467 -0.739202 1.85053e-05 0.673484 -0.739226 -6.15756e-07 0.673458 -0.739233 8.63711e-07 0.67345 -0.739226 0 0.673457 -0.739188 5.91958e-05 0.673499 -0.739224 2.71137e-06 0.67346 -0.739226 -5.52083e-07 0.673458 -0.739232 -4.72439e-06 0.673451 -0.739217 8.07425e-06 0.673467 -0.602841 0 -0.797862 -0.602822 1.49573e-05 -0.797876 -0.60284 -1.2394e-07 -0.797862 -0.60284 -8.65736e-07 -0.797862 -0.602702 0.0001235 -0.797966 -0.602843 -1.83872e-06 -0.79786 -0.602841 -1.45742e-06 -0.797861 -0.602841 -3.48612e-07 -0.797861 -0.602841 -1.27751e-06 -0.797861 -0.602847 -6.34589e-06 -0.797857 -0.60284 0 -0.797862 -0.60284 0 -0.797862 -0.602689 0.000232829 -0.797976 -0.602845 -7.44884e-06 -0.797858 -0.646815 0 -0.762647 -0.646815 0 -0.762647 -0.646723 0.00017645 -0.762725 -0.646816 0 -0.762647 -0.646814 -1.10412e-07 -0.762648 -0.646815 -8.48951e-07 -0.762647 -0.646812 1.39498e-06 -0.76265 -0.646821 -3.37404e-06 -0.762642 -0.646814 -1.85039e-07 -0.762648 -0.646813 1.38242e-06 -0.762649 -0.646773 3.83614e-05 -0.762682 -0.646818 -5.66978e-06 -0.762645 -0.6468 2.44208e-05 -0.76266 -0.646812 3.96837e-06 -0.762649 -0.646813 7.5012e-07 -0.762648 -0.64682 -1.0737e-05 -0.762642 -0.646813 2.50427e-06 -0.762649 -0.61746 0 0.786603 -0.617441 1.7662e-05 0.786617 -0.617461 -1.27945e-05 0.786601 -0.617453 7.28814e-07 0.786608 -0.617458 -1.85181e-07 0.786604 -0.617454 -1.11745e-06 0.786607 -0.617458 -1.4055e-06 0.786604 -0.617455 -4.41211e-07 0.786606 -0.617455 -5.08988e-07 0.786606 -0.617459 -1.71417e-06 0.786603 -0.617371 2.1117e-05 0.786673 -0.617455 -7.81531e-07 0.786606 -0.616621 0.00108651 0.78726 -0.617455 -2.24968e-06 0.786606 -0.617454 0 0.786607 -0.617454 0 0.786607 -0.617453 3.04702e-06 0.786608 -0.617453 2.05581e-06 0.786608 -0.632419 0 -0.774627 -0.632419 0 -0.774627 -0.632413 0 -0.774631 -0.632418 -5.12283e-07 -0.774627 -0.632419 -5.00058e-07 -0.774627 -0.632412 4.1361e-06 -0.774632 -0.632432 -8.3247e-06 -0.774616 -0.632391 1.59183e-05 -0.774649 -0.632432 -7.77763e-06 -0.774616 -0.632419 -8.44238e-07 -0.774627 -0.632417 1.9702e-06 -0.774628 -0.63241 1.55433e-05 -0.774634 -0.632417 2.52611e-06 -0.774628 -0.632419 -2.30353e-07 -0.774627 -0.632458 -0.000166436 -0.774595 -0.632419 -3.7032e-07 -0.774627 -0.632423 -1.07842e-05 -0.774623 -0.747969 0 -0.663733 -0.74797 -3.19351e-07 -0.663732 -0.747968 -4.41478e-07 -0.663734 -0.747969 -5.4851e-07 -0.663734 -0.747971 -1.16431e-06 -0.663731 -0.747771 0.000269401 -0.663957 -0.747967 5.46713e-06 -0.663736 -0.747983 -1.5893e-05 -0.663718 -0.747904 8.13231e-05 -0.663807 -0.747981 -1.10201e-05 -0.663721 -0.74797 5.59745e-07 -0.663733 -0.747971 0 -0.663732 -0.747971 0 -0.663732 -0.748038 -0.000232926 -0.663656 -0.747971 -2.33876e-06 -0.663731 -0.747967 7.72734e-06 -0.663736 -0.747992 -5.43744e-05 -0.663707 -0.0317373 -1.4375e-06 0.999496 -0.0317379 0 0.999496 -0.0317378 0 0.999496 -0.0318111 -5.71149e-05 0.999494 -0.0317 3.14567e-05 0.999497 -0.0317397 -1.6957e-06 0.999496 -0.0318094 -7.30431e-06 0.999494 -0.0317102 2.6305e-06 0.999497 -0.0317374 -1.37847e-06 0.999496 -0.0317388 -2.54831e-07 0.999496 -0.0317362 0 0.999496 -0.0312678 0.000696023 0.999511 -0.031757 -2.89102e-05 0.999496 -0.0317377 1.59393e-06 0.999496 -0.0316519 6.288e-05 0.999499 -0.0317496 -9.22074e-06 0.999496 0.9799 0 0.199491 0.933783 -0.00432668 0.357814 0.249186 0.00283941 0.968452 0.330737 0.00679564 0.943698 0.191106 -0.00239865 0.981567 0.466819 0.00233768 0.88435 0.404977 -0.00197135 0.914325 0.57164 0.000629709 0.820504 0.551933 0.000150946 0.833888 0.718622 -0.00055474 0.695401 0.721645 -0.000232316 0.692263 0.909543 0.00022448 0.41561 -0.266884 0 0.963729 -0.266884 0 0.963729 -0.174046 0.0036852 0.984731 -0.0951453 0.00676858 0.99544 -0.198806 -0.000958662 0.980038 0.0159213 0.000188179 0.999873 0.0245311 0.000314183 0.999699 0.108915 -0.000435566 0.994051 0.190648 0.00126535 0.981658 -0.204895 0 -0.978784 -0.255731 -0.0146793 -0.966637 0.056365 0.00835219 -0.998375 -0.0907295 0.00341517 -0.99587 -0.0384446 -0.00168905 -0.999259 0.164396 1.37656e-06 -0.986394 0.312549 -5.13101e-06 -0.949902 0.331526 0.000719933 -0.943446 0.538936 -0.000620373 -0.842346 0.55558 -6.15248e-06 -0.831463 0.695243 4.13991e-06 -0.718775 0.687945 -0.000206305 -0.725763 0.852107 0.000532961 -0.523367 0.999569 0 0.0293524 0.992693 -0.00419345 -0.120591 0.970859 0.000837239 -0.239649 0.836239 -0.00104844 -0.548365 -0.359686 0 0.933073 -0.359687 -8.26068e-08 0.933073 -0.359685 5.34371e-07 0.933074 -0.359687 0 0.933073 -0.359686 -8.86972e-08 0.933073 -0.359686 4.2786e-07 0.933074 -0.359687 -3.40031e-07 0.933073 -0.303861 0 -0.952716 -0.303861 0 -0.952716 -0.303863 -2.75089e-06 -0.952716 -0.30386 1.83808e-06 -0.952717 -0.303862 0 -0.952716 -0.303865 -1.48092e-06 -0.952715 -0.303861 0 -0.952716 -0.303862 -1.69564e-07 -0.952716 -0.303861 0 -0.952716 -0.304004 -0.000141584 -0.952671 -0.49551 0 -0.868602 -0.52714 -0.00201591 -0.849776 -0.866531 -0.00332947 -0.499112 -0.827477 0 -0.561499 -0.692479 0 -0.721438 -0.98916 1.41001e-05 0.146844 -0.999342 -0.00203554 0.0362138 -0.999554 -0.00393379 -0.0295895 -0.990213 0 -0.139568 -0.939473 0 -0.342623 -0.950939 -1.95294e-05 0.309378 -0.894537 -0.00376727 0.446978 -0.849174 -0.000151188 0.528112 -0.662012 0.000142944 0.749494 -0.576482 -0.0037176 0.817102 -0.455535 0 0.890218 0.983958 0 0.178399 0.983966 0.000192573 0.178359 0.984773 -0.000193438 0.173844 0.98478 0 0.173805 0.918621 0.0838731 -0.386135 -0.0883141 0.961054 0.261871 0.249155 0.96839 0.0119165 -0.702812 0.0991521 0.704432 -0.694499 0.0696882 0.716111 -0.709705 0.0476032 0.702889 -0.707757 0.032458 0.70571 -0.707942 0.037806 0.705258 -0.706863 0.0265708 0.706851 -0.676067 0.14952 0.721511 -0.69517 0.133714 0.7063 -0.663298 0.25071 0.70511 -0.646473 0.287271 0.706787 -0.641601 0.374089 0.669631 -0.599057 0.435404 0.671978 -0.585445 0.486999 0.648141 -0.538659 0.595691 0.595818 -0.46844 0.661113 0.586083 -0.432288 0.723328 0.538445 -0.265983 0.890867 0.368251 -0.302095 0.829704 0.469393 -0.213986 0.897632 0.385313 -0.0730015 0.955484 0.28587 -0.0887876 0.937722 0.335848 0.0357306 0.973111 0.227548 0.0769705 0.986704 0.143144 0.0797136 0.987717 0.134392 0.0823907 0.989818 0.11607 0.0674669 0.991234 0.113594 0.0853129 0.989669 0.115225 0.0691474 0.992119 0.104496 0.074113 0.991664 0.105401 0.0706626 0.992893 0.0957651 0.0710745 0.993191 0.0923036 0.0602055 0.993777 0.0937212 0.0524027 0.993889 0.0971573 0.0640612 0.994005 0.0885969 0.0452223 0.99481 0.0911435 0.227161 0.973059 0.0394153 0.0619121 0.997294 0.0396409 0.648679 0.732095 -0.207969 0.53392 0.832928 -0.145464 0.880389 0.320156 -0.349879 0.822942 0.46996 -0.319224 0.800379 0.523549 -0.292044 0.747259 0.608296 -0.267543 0.649372 0.731271 -0.208709 0.895567 0.141927 -0.421683 0.908339 0.0843475 -0.409642 0.909122 0.0855276 -0.407654 0.903648 0.0308869 -0.427161 0.99786 0.0602622 -0.025363 0.998457 0.034577 -0.0434432 0.974262 0.223583 -0.0287 0.976614 0.213339 -0.0266664 0.897286 0.441033 -0.019161 0.871371 0.490197 -0.0204704 0.798576 0.601842 0.00793094 0.68889 0.724841 0.00607048 0.639014 0.768908 0.021016 0.462287 0.886261 0.028848 0.487106 0.871808 0.0517663 0.440357 0.896987 0.0387266 0.538726 0.841841 0.0328514 0.563585 0.825493 0.0305635 0.0379401 0.997979 0.0509813 0.150795 0.985409 0.0789247 0.175887 0.982353 0.0636063 0.33742 0.940734 0.034166 0.282204 0.957221 0.0639492 0.315362 0.947357 0.0553289 0.0205082 0.994724 0.100521 0.00703188 0.999225 0.0387386 0.00256103 0.99832 0.0578912 0.00342403 0.998272 0.0586678 -0.0126269 0.999566 0.0266234 0.0162741 0.997793 0.0643834 0.020671 0.996879 0.0761945 0.0181923 0.996653 0.0797027 0.0200496 0.995698 0.0904604 0.0203472 0.995735 0.0899935 0.0232237 0.994794 0.0992246 0.0300637 0.993568 0.109169 0.0339057 0.990487 0.133361 0.0347287 0.990594 0.132357 0.0436765 0.989696 0.136358 0.0407068 0.989458 0.138981 -0.00835923 0.9779 0.208907 0.00165687 0.977562 0.210644 0.0730118 0.981681 0.175989 0.0619593 0.987492 0.144983 0.0378211 0.986818 0.15735 -0.620976 0.532798 0.574904 -0.540648 0.676779 0.49967 -0.550849 0.697058 0.458995 -0.552269 0.695318 0.459927 -0.5412 0.751025 0.378239 -0.468109 0.736966 0.4876 -0.295758 0.869942 0.394623 -0.19981 0.92769 0.315383 -0.205127 0.926119 0.316586 -0.12122 0.951804 0.281734 -0.653031 0.652805 0.383923 -0.582551 0.71987 0.377388 -0.726864 0.548847 0.412839 -0.756419 0.461797 0.463221 -0.81749 0.0832788 0.56989 -0.836538 0.339461 0.430081 -0.837933 0.166593 0.519727 -0.853636 0.201 0.480526 -0.881561 0.060664 0.468157 -0.771429 0.0629064 0.633198 -0.761033 0.0505861 0.646738 -0.728613 0.103592 0.677046 -0.740906 0.0707765 0.667869 -0.720904 0.0720304 0.689282 -0.712398 0.0743044 0.697831 0.0579075 0.975017 0.214449 0.0548138 0.979502 0.193835 0.045254 0.9833 0.176274 0.0458057 0.983491 0.175063 0.0534607 0.986701 0.153501 0.0568238 0.978775 0.196905 0.0674269 0.98128 0.180398 0.0503442 0.984306 0.169139 0.0439055 0.986087 0.160327 0.501411 0.864684 0.0301312 0.483591 0.874201 0.0437352 0.484243 0.873501 0.0500514 0.463389 0.886071 -0.0121712 0.463528 0.88599 -0.0127826 0.340143 0.940019 0.0258276 0.261299 0.964586 0.0360204 0.00456733 0.983545 0.180603 0.191742 0.981053 0.027753 0.148685 0.988295 0.0341291 0.0868459 0.99544 0.039448 -0.724941 0.334608 0.602078 -0.688874 0.38052 0.616974 -0.768042 0.176676 0.615547 -0.738262 0.22647 0.635359 -0.774 0.108291 0.623857 -0.668832 0.584991 0.458749 -0.395029 0.834964 0.383128 -0.688641 0.534379 0.490115 -0.669208 0.552804 0.496557 -0.786721 0.328934 0.522373 -0.770489 0.344869 0.536108 -0.82776 0.165542 0.536105 -0.816171 0.181422 0.54859 -0.79325 0.261449 0.549908 -0.868946 0.022889 0.494377 -0.873898 0.0330525 0.484984 0.991735 0.0438735 -0.120571 0.988519 0.0670573 -0.135401 0.968967 0.21746 -0.117529 0.964132 0.237157 -0.119185 0.865736 0.494786 -0.075424 0.859774 0.504991 -0.0759829 0.685029 0.728173 -0.0223211 0.684109 0.729037 -0.0223539 0.529154 0.848356 0.0169807 0.489882 0.871715 0.0113242 0.934439 0.0801429 -0.346988 0.932378 0.0831555 -0.351791 0.907207 0.272616 -0.3204 0.821959 0.444193 -0.356477 0.905927 0.227951 -0.356838 0.0633219 0.975108 0.212495 0.0592759 0.975452 0.212084 0.0115897 0.96527 0.260998 -0.0777274 0.957714 0.277023 -0.178053 0.911596 0.370525 -0.25163 0.883214 0.395747 -0.492486 0.652546 0.575884 -0.476847 0.664743 0.575095 -0.657047 0.373587 0.654769 -0.604313 0.436466 0.666561 -0.701463 0.223002 0.676919 -0.656578 0.288255 0.697004 -0.722611 0.107137 0.682902 -0.700991 0.133897 0.700488 -0.71644 0.0697008 0.694158 -0.710362 0.07564 0.69976 0.967633 0.0693275 -0.242653 0.96534 0.0782394 -0.248993 0.943962 0.242923 -0.223437 0.937369 0.266357 -0.224484 0.841424 0.513334 -0.168804 0.841891 0.512564 -0.168813 0.667566 0.738324 -0.0960912 0.688408 0.718768 -0.0972947 0.488534 0.872087 -0.028248 0.459934 0.882587 -0.09747 0.402346 0.911975 -0.0801238 0.0620935 -0.975511 0.211004 -0.708271 -0.0223697 0.705586 -0.725467 -0.134551 0.674977 0.0452255 -0.98338 0.175835 0.9073 -0.272569 -0.320177 0.0228289 -0.994952 0.097721 0.0313738 -0.991463 0.126561 0.0306831 -0.993693 0.107859 -0.668787 -0.585056 0.45873 -0.697838 -0.538037 0.472798 -0.710596 -0.075437 0.699544 -0.736192 -0.0499135 0.674929 -0.714503 -0.0735258 0.695759 -0.725673 -0.0715367 0.684311 -0.754599 -0.0707901 0.652357 -0.859541 -0.0327154 0.510019 -0.872957 -0.086579 0.480053 -0.879439 -0.0673077 0.471228 -0.859241 -0.178709 0.479342 -0.865239 -0.169245 0.471929 -0.82023 -0.164738 0.5478 -0.839813 -0.0600454 0.539545 -0.794297 -0.0804964 0.602174 -0.773502 -0.473757 0.42101 -0.582722 -0.719702 0.377444 -0.653127 -0.652682 0.383967 -0.554546 -0.692526 0.461396 -0.539966 -0.741179 0.398862 -0.105009 -0.956363 0.272659 -0.199018 -0.927201 0.317317 -0.172987 -0.942786 0.285009 -0.239999 -0.905115 0.350952 0.0435802 -0.991553 0.122158 0.031428 -0.990817 0.131506 0.0315374 -0.990957 0.13042 0.042378 -0.989669 0.136967 0.0411737 -0.98968 0.13725 0.0425255 -0.987178 0.153857 0.0474822 -0.984773 0.167235 0.0202545 -0.99478 0.100012 0.0198753 -0.997056 0.0740574 0.0179664 -0.995594 0.0920337 -0.00327481 -0.998805 0.0487571 0.00713448 -0.998598 0.0524516 0.0162732 -0.997793 0.0643811 0.287139 -0.955866 0.0622209 0.217517 -0.971274 0.0965043 0.32389 -0.945966 -0.0156145 0.0798497 -0.990691 0.110253 0.138198 -0.989592 0.04011 -0.0119301 -0.998072 0.0609156 0.00904313 -0.998717 0.0498186 -0.00411868 -0.998824 0.0482986 0.563589 -0.82549 0.0305648 0.316267 -0.947064 0.055188 0.428008 -0.903085 0.0353072 0.463327 -0.885397 0.0374233 0.538726 -0.84184 0.0328517 0.693191 -0.71939 0.0443207 0.799469 -0.599886 -0.0314091 0.639014 -0.768908 0.0210211 0.871393 -0.490166 -0.0202591 0.977 -0.212693 -0.0152832 0.966311 -0.256065 -0.0259715 0.997476 -0.0574579 -0.0417265 0.999083 -0.0344859 -0.025394 0.890824 -0.184885 -0.415029 0.895912 -0.1388 -0.42199 0.908667 -0.0899302 -0.407723 0.868837 -0.306345 -0.388941 0.863878 -0.369884 -0.341908 0.833702 -0.449879 -0.320236 0.800553 -0.523524 -0.29161 0.761123 -0.584454 -0.281255 0.650218 -0.731826 -0.204078 0.67605 -0.706016 -0.210946 0.555493 -0.814978 -0.165039 0.460537 -0.882445 -0.095903 0.436773 -0.89531 -0.0874585 0.242359 -0.970186 -0.00121131 0.304031 -0.952594 -0.0113762 0.0486333 -0.99584 0.0770536 0.15842 -0.985644 0.0583851 0.0449572 -0.994723 0.0922266 0.0514478 -0.994497 0.0912676 0.0665007 -0.99354 0.0919556 0.0628827 -0.992985 0.100133 0.0654049 -0.993172 0.096597 0.070369 -0.993421 0.0903468 0.0710073 -0.99304 0.0939614 0.0689094 -0.993041 0.095506 0.0689849 -0.99314 0.0944155 0.0762216 -0.990552 0.114004 0.0844006 -0.989765 0.115077 0.0786979 -0.988501 0.12912 0.0746964 -0.988148 0.134104 0.0736893 -0.987464 0.139589 0.0352499 -0.969156 0.243915 0.0594061 -0.986535 0.152379 0.0488237 -0.982634 0.179015 -0.060532 -0.952673 0.297909 -0.0632265 -0.950652 0.303749 -0.22122 -0.9 0.375581 -0.244505 -0.879275 0.408771 -0.310675 -0.841626 0.441753 -0.429736 -0.745469 0.509512 -0.468486 -0.661114 0.586046 -0.515957 -0.60972 0.601689 -0.647231 -0.28724 0.706105 -0.637012 -0.352369 0.685603 -0.600182 -0.435513 0.670902 -0.598514 -0.476693 0.643852 -0.539388 -0.578269 0.6121 -0.706863 -0.0265708 0.706851 -0.707323 -0.0312455 0.7062 -0.707325 -0.0310055 0.706209 -0.707775 -0.038856 0.705369 -0.695387 -0.0683386 0.715379 -0.711911 -0.0971395 0.695519 -0.626372 -0.20098 0.75317 -0.0559833 -0.968991 0.240672 -0.0111558 -0.979458 0.20134 0.0396612 -0.978562 0.202097 0.0621711 -0.980865 0.184497 0.0693676 -0.980919 0.181623 0.491005 -0.870886 -0.0216992 0.270224 -0.961666 0.0466546 0.263949 -0.963641 0.0415551 0.105542 -0.989428 0.0994699 0.172006 -0.984084 0.0446358 0.123041 -0.990597 0.0598227 0.0705328 -0.994813 0.0733014 0.487081 -0.871821 0.0517678 0.484226 -0.87351 0.0500534 0.48359 -0.874202 0.0437351 0.472334 -0.881411 -0.00399939 0.490865 -0.87116 0.0114804 -0.323699 -0.851708 0.412084 -0.484897 -0.723968 0.490659 -0.540703 -0.676783 0.499606 -0.621027 -0.532792 0.574854 -0.70354 -0.383451 0.598328 -0.71175 -0.331425 0.61933 -0.752043 -0.227582 0.618578 -0.550753 -0.697186 0.458914 -0.395168 -0.834889 0.383149 -0.674913 -0.55497 0.486314 -0.68293 -0.532045 0.500535 -0.779584 -0.346755 0.521546 0.990487 -0.066595 -0.120419 0.989576 -0.0408239 -0.138105 0.964728 -0.236846 -0.11491 0.968388 -0.217608 -0.121949 0.86017 -0.504696 -0.0734126 0.865413 -0.494952 -0.077991 0.684157 -0.729002 -0.0220433 0.685002 -0.728191 -0.0225623 0.529088 -0.848396 0.0170251 0.501435 -0.864671 0.0301272 0.934435 -0.080196 -0.346987 0.932468 -0.0830794 -0.35157 0.918622 -0.0838656 -0.386135 0.912347 -0.084192 -0.400668 0.903415 -0.0383101 -0.427052 0.0549117 -0.979329 0.194677 0.0578302 -0.975207 0.213605 -0.0520654 -0.944533 0.324265 -0.00801702 -0.977753 0.209605 -0.236714 -0.874611 0.423111 -0.188553 -0.919776 0.34418 -0.481771 -0.666808 0.568563 -0.488654 -0.650446 0.581496 -0.625111 -0.440368 0.644448 -0.639706 -0.369518 0.673968 -0.67579 -0.289892 0.677695 -0.684427 -0.221186 0.69472 -0.71456 -0.134263 0.68657 -0.70797 -0.106684 0.698138 -0.677128 -0.21407 0.70404 -0.735757 -0.107455 0.668666 -0.782928 -0.0703117 0.618126 -0.755316 -0.175295 0.631482 -0.823795 -0.182087 0.536849 -0.777727 -0.326849 0.536945 -0.83177 -0.338528 0.439953 -0.850215 -0.312996 0.423281 0.967014 -0.0779666 -0.242498 0.965749 -0.0695318 -0.249989 0.938766 -0.265902 -0.219122 0.942687 -0.243115 -0.228551 0.841869 -0.512581 -0.168872 0.841504 -0.513308 -0.168482 0.686504 -0.719767 -0.103192 0.669066 -0.737729 -0.0900352 0.465428 -0.884843 -0.0207401 0.466276 -0.8843 -0.0245005 -0.987844 0.0175448 -0.154458 -0.98625 0.0176425 -0.164315 -0.986524 0.0183298 -0.162589 -0.986814 0.0175933 -0.160902 -0.987119 0.0175399 -0.159025 -0.98742 0.0175739 -0.157139 -0.987219 0.018137 -0.158333 -0.987995 0.0162787 -0.153629 -0.987451 0.0190609 -0.15677 -0.987814 0.0173867 -0.154664 -0.987838 0.019521 -0.154257 -0.987837 0.0180922 -0.154435 -0.981351 0.0211225 -0.191063 -0.984188 0.0218845 -0.175767 -0.984865 0.0174543 -0.172443 -0.978837 0.0165831 -0.203966 -0.980559 0.0172006 -0.195468 -0.980872 0.0188862 -0.193737 -0.981716 0.0173466 -0.189561 -0.982873 0.0165173 -0.183544 -0.977865 0.0167521 -0.208565 -0.977309 0.0224203 -0.210628 -0.977984 0.019657 -0.207751 -0.991557 0.00393918 -0.129612 -0.985699 0.03296 -0.165263 -0.980026 -0.0137118 -0.198396 -0.989669 0.0319829 -0.139758 -0.99305 0.032837 -0.113018 -0.994303 0.0333754 -0.101233 -0.993659 0.0384855 -0.105641 -0.99707 0.0275332 -0.0713736 -0.917079 0.0339888 0.397253 -0.922182 0.0641118 0.381405 -0.994954 0.056081 -0.0831942 -0.998942 0.0217079 -0.0405301 -0.99836 0.0522634 -0.0233603 -0.999047 -0.0144687 0.0411729 -0.998894 0.00680088 0.046529 -0.990992 0.0260979 0.131356 -0.992895 -0.00652612 0.118812 -0.986242 0.0143535 0.164681 -0.982609 0.0234303 0.184201 -0.98118 0.00747005 0.192948 -0.966918 0.00530767 0.255034 -0.967358 0.00860312 0.253269 -0.952571 0.00674301 0.304242 -0.958177 0.022659 0.285279 -0.946465 -0.00875859 0.322689 0.61751 0 -0.786563 0.617441 -1.85362e-06 -0.786617 0.617456 -3.53664e-08 -0.786605 0.617453 7.47743e-07 -0.786608 0.617457 -1.89193e-06 -0.786604 0.61746 -3.6309e-06 -0.786602 0.617457 -1.00553e-06 -0.786605 0.617453 1.02912e-06 -0.786607 0.61742 5.77976e-05 -0.786634 0.618204 -0.00115388 -0.786017 0.617438 2.45682e-05 -0.786619 0.61747 -2.53237e-05 -0.786595 0.617453 1.05149e-06 -0.786608 0.617453 6.66289e-07 -0.786608 0.617453 4.63298e-06 -0.786608 0.617453 0 -0.786608 0.617453 0 -0.786608 0.617451 8.38589e-06 -0.78661 0.617456 -7.94999e-06 -0.786605 0.747968 0 0.663735 0.747973 5.74284e-07 0.663729 0.74797 -1.07343e-08 0.663732 0.747967 1.30456e-05 0.663736 0.747992 0 0.663708 0.747971 0 0.663732 0.747971 -4.67042e-06 0.663731 0.74797 2.47978e-06 0.663733 0.748935 -0.00243808 0.662639 0.747971 6.00874e-07 0.663732 0.747963 1.14531e-05 0.66374 0.74797 7.04322e-07 0.663733 0.747979 -5.40275e-06 0.663722 0.747977 -3.61739e-06 0.663724 0.747958 8.13907e-06 0.663746 0.747971 -1.40015e-06 0.663732 0.747999 0 0.6637 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.74797 0 -0.663732 -0.747969 3.72661e-07 -0.663733 -0.747969 4.15759e-07 -0.663734 -0.747968 4.7333e-07 -0.663734 -0.747971 0 -0.663732 -0.74797 0 -0.663732 -0.747971 2.55011e-06 -0.663731 -0.748037 0.00024224 -0.663657 -0.74797 -5.84462e-07 -0.663733 -0.747965 -5.59422e-06 -0.663738 -0.747983 1.46446e-05 -0.663717 -0.747904 -8.13231e-05 -0.663807 -0.747983 1.5893e-05 -0.663717 -0.747971 1.60142e-07 -0.663731 -0.747965 -1.12816e-06 -0.663738 -0.747722 -6.06976e-05 -0.664012 -0.0317379 0 0.999496 -0.0317379 0 0.999496 -0.0317378 0 0.999496 -0.0317388 4.117e-07 0.999496 -0.0317371 1.23216e-06 0.999496 -0.0317111 -8.16933e-06 0.999497 -0.031804 2.05413e-05 0.999494 -0.0317408 2.34229e-06 0.999496 -0.0317087 -3.00317e-05 0.999497 -0.0317873 4.62664e-05 0.999495 -0.031749 9.95466e-06 0.999496 -0.0317363 -1.50093e-06 0.999496 -0.0317367 -1.23017e-06 0.999496 -0.0317364 -1.70846e-06 0.999496 -0.0312734 -0.000692276 0.999511 -0.617454 0 0.786607 -0.61746 1.53414e-06 0.786603 -0.617458 1.4055e-06 0.786604 -0.617455 4.41211e-07 0.786606 -0.617455 5.23127e-07 0.786606 -0.617539 2.49416e-05 0.78654 -0.617426 -7.60635e-06 0.786629 -0.617453 -9.54099e-07 0.786608 -0.617449 -8.01772e-06 0.786611 -0.617454 0 0.786607 -0.617454 0 0.786607 -0.616909 -0.00140887 0.787033 -0.617451 -7.05015e-06 0.786609 -0.617485 4.79354e-05 0.786583 -0.617456 2.96771e-06 0.786605 -0.617455 1.76373e-06 0.786606 -0.617501 0.000100937 0.78657 -0.617453 -6.73682e-07 0.786608 -0.617453 -1.89065e-06 0.786608 0.999981 0 0.00623477 0.999574 -0.0290506 -0.00284367 0.997323 0.0667557 -0.0298532 0.999205 0 -0.0398588 0.999205 0 -0.0398588 0.997323 -0.0667557 -0.0298532 0.999574 0.0290506 -0.00284367 0.999981 0 0.00623477 0.617452 -7.28674e-08 -0.786609 0.617456 1.45298e-06 -0.786605 0.61751 0 -0.786563 0.617453 0 -0.786608 0.617453 0 -0.786608 0.617927 0.00144152 -0.786234 0.617452 -3.19627e-06 -0.786608 0.617453 -4.66887e-07 -0.786608 0.617466 3.00297e-05 -0.786597 0.617453 -9.30798e-07 -0.786608 0.617461 1.18486e-05 -0.786602 0.617454 -1.3755e-06 -0.786607 0.617442 -9.92673e-06 -0.786617 0.61746 4.67164e-06 -0.786602 0.617453 2.09873e-07 -0.786608 0.617448 -1.6144e-05 -0.786611 0.617451 -9.39585e-06 -0.786609 0.617456 7.19616e-06 -0.786605 0.747968 0 0.663735 0.747973 -5.7678e-07 0.663729 0.74797 1.07343e-08 0.663732 0.74797 0 0.663732 0.748561 0.000699808 0.663066 0.747963 -1.00583e-05 0.663741 0.74797 -6.38918e-07 0.663732 0.747979 4.81891e-06 0.663723 0.747977 3.83706e-06 0.663724 0.747971 1.85639e-07 0.663732 0.747963 1.80661e-06 0.663741 0.747999 0 0.6637 0.747966 -5.06944e-06 0.663737 0.74797 -6.99653e-07 0.663732 0.747994 5.45598e-05 0.663706 0.747971 -4.30712e-07 0.663732 0.747965 -2.50013e-05 0.663738 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.739226 0 -0.673458 0.739228 0 -0.673455 0.739226 0 -0.673458 0.739226 1.20086e-07 -0.673458 0.739903 0.000662996 -0.672714 0.739226 -6.13546e-07 -0.673458 0.739219 7.867e-07 -0.673466 0.739224 7.88753e-08 -0.67346 0.646815 0 0.762647 0.646814 -2.85191e-07 0.762648 0.646814 3.37405e-07 0.762648 0.646814 0 0.762648 0.646629 3.10672e-05 0.762805 0.646815 1.71846e-07 0.762647 0.646814 -3.79521e-07 0.762648 0.646816 2.81334e-07 0.762646 0.646818 2.29652e-08 0.762644 0.646814 4.27503e-08 0.762648 0.646814 5.88842e-08 0.762648 0.646819 0 0.762644 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.602845 0 0.797858 0.60284 0 0.797862 0.60284 0 0.797862 0.60284 0 0.797862 0.60284 8.90277e-08 0.797862 0.603028 -2.06184e-05 0.79772 0.602831 9.80651e-07 0.797869 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.727869 0 -0.685716 0.727883 0 -0.685701 0.727869 1.98224e-07 -0.685716 0.727869 3.35647e-07 -0.685716 0.727869 1.93089e-07 -0.685716 0.727869 -4.6921e-07 -0.685717 0.727771 -8.38001e-06 -0.68582 0.727856 -1.39537e-06 -0.68573 0.727871 -7.61894e-07 -0.685714 0.72787 -8.41171e-07 -0.685715 0.72787 -8.1622e-07 -0.685716 0.727871 -6.65955e-07 -0.685714 0.727846 0 -0.685741 0.632408 0 0.774635 0.632419 0 0.774627 0.632419 -9.38503e-08 0.774627 0.632419 -4.06065e-07 0.774626 0.63241 0 0.774634 0.632419 -7.70984e-08 0.774626 0.632416 3.19199e-07 0.774629 0.632416 3.19982e-07 0.774629 0.632419 1.88162e-07 0.774626 0.633045 4.97939e-05 0.774115 0.63242 8.96233e-07 0.774626 0.632419 -3.42125e-08 0.774627 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.453062 0 0.891479 -0.453059 0 0.891481 -0.453062 1.2511e-07 0.891479 -0.453052 5.59746e-06 0.891484 -0.453062 0 0.891479 -0.452492 0.000537858 0.891768 -0.453064 -1.85359e-06 0.891478 -0.453051 1.09255e-05 0.891484 -0.453062 0 0.891479 -0.453062 0 0.891479 -0.453067 -2.56055e-06 0.891477 -0.453079 -9.11636e-06 0.891471 0.98831 0 0.152457 0.98644 0 0.16412 0.987049 -0.00199686 0.160405 0.987656 -0.000390452 0.15664 0.988171 -4.74902e-05 0.153358 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.990422 0 0.138076 0.990793 -0.00094024 0.13538 0.991159 0 0.132679 0.977552 0 0.210696 0.977731 -9.99447e-05 0.209864 0.977909 0 0.209032 -0.643236 -6.4976e-05 0.765668 -0.642892 0.000168666 0.765957 -0.643136 -1.3797e-07 0.765752 -0.643135 -2.48572e-07 0.765753 -0.643139 0 0.76575 -0.643136 0 0.765752 -0.643136 0 0.765752 -0.642785 0.000427005 0.766047 -0.643144 -8.47937e-06 0.765746 -0.643135 2.17354e-06 0.765753 -0.643137 -1.67218e-07 0.765751 -0.643152 -8.53285e-06 0.765738 -0.643134 1.0422e-06 0.765753 -0.482958 0 -0.875643 -0.482957 -6.84732e-08 -0.875644 -0.482954 2.0093e-06 -0.875646 -0.48296 -1.68311e-06 -0.875642 -0.482942 8.78654e-06 -0.875652 -0.482959 -7.39411e-07 -0.875643 -0.482957 8.86445e-08 -0.875644 -0.482958 -7.9498e-07 -0.875644 -0.482962 -6.05302e-06 -0.875641 -0.482957 0 -0.875644 -0.482957 0 -0.875644 -0.482659 0.000340756 -0.875809 -0.482958 -9.13733e-07 -0.875644 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.9813 0 0.192487 0.982125 -0.00281911 0.188207 0.983127 0 0.182925 -0.331997 0 0.943281 -0.260529 -0.0109647 0.965404 -0.0943782 -6.02841e-05 0.995536 0.081137 8.25533e-05 0.996703 0.224139 -0.0119781 0.974484 0.34323 0.00277007 0.939247 0.626702 -0.00350175 0.779251 0.656147 -0.00919498 0.754577 0.782653 1.92865e-05 0.622458 0.870319 -2.9861e-05 0.492488 0.933916 -0.0117918 0.357299 0.963641 0 0.267202 0.998895 0 0.0470073 0.99982 -0.00299521 -0.0187202 0.983494 9.39924e-06 -0.180941 0.942525 -1.34271e-05 -0.334137 0.888999 -0.00347144 -0.457897 0.822827 0.00133816 -0.568291 0.578964 -0.00208677 -0.81535 0.595793 -0.000905797 -0.803137 0.409304 1.77818e-05 -0.912398 0.281397 -0.000130792 -0.959591 0.180347 -0.00348396 -0.983597 0.0608147 -1.87046e-08 -0.998149 -0.107192 3.31409e-08 -0.994238 -0.2721 -0.00271238 -0.962265 -0.329577 0 -0.944129 -0.0147053 -2.31477e-08 0.999892 -0.313284 -4.93093e-07 0.94966 -0.150062 -0.010498 0.988621 -0.381966 0 0.924176 0.0600588 -0.00122508 0.998194 0.163573 -0.00325526 0.986526 0.240784 0.000176923 0.970579 0.904515 0 0.426442 0.93689 -0.00531234 0.349585 0.825871 5.90019e-06 0.56386 0.603015 -1.67617e-05 0.79773 0.726112 -0.0104957 0.687496 0.545617 -0.000177952 0.838034 0.999931 0 0.0117424 0.999102 -0.00215237 -0.0423154 0.977995 -2.35449e-07 -0.208627 0.929777 3.77687e-07 -0.368123 0.884116 -0.0028979 -0.467259 0.804487 0.000953846 -0.59397 0.617169 -0.00139622 -0.786829 0.597794 -0.00231005 -0.801646 0.462191 -2.35065e-07 -0.88678 0.306945 1.61334e-07 -0.951727 0.19562 -0.00287502 -0.980676 0.0366134 0.00144019 -0.999328 -0.244473 -0.00210285 -0.969654 -0.295909 0 -0.955216 -0.284794 0 -0.958589 -0.0934229 0.00450791 -0.995616 -0.337802 -0.00723819 -0.941189 0.0211457 0.00628603 -0.999757 -0.13469 -6.88325e-05 -0.990888 0.200289 6.75577e-05 -0.979737 0.244766 -0.00176276 -0.969581 0.620219 0.002674 -0.784424 0.513834 -0.00519413 -0.857874 0.71329 8.6949e-07 -0.70087 0.886984 -1.8553e-06 -0.4618 0.82147 -0.006364 -0.570216 0.937669 0.00126851 -0.347528 0.999865 -0.0020899 -0.0163205 0.998302 0 -0.0582451 0.91968 0 0.392668 0.943744 -0.00358984 0.330656 0.598026 -0.0013058 0.801476 0.64377 -0.00310435 0.765213 0.739732 -5.14277e-08 0.672901 0.841401 3.92965e-08 0.540411 -0.297035 0 0.954867 -0.434387 0.00574768 0.900708 -0.0676187 -0.00722757 0.997685 -0.21359 5.78459e-08 0.976923 0.100799 -2.7299e-08 0.994907 0.229515 -0.00312427 0.9733 0.364284 0.00114988 0.931287 0.519152 -0.000374038 0.854682 0.126364 0 0.991984 0.182395 -0.0027444 0.983221 0.671914 -0.00722357 0.740594 0.476537 -4.20671e-05 0.879154 0.336492 2.34385e-05 0.941686 0.575943 0.00243461 0.817486 0.864479 -0.00182787 0.502665 0.864879 -0.00178088 0.501977 0.944739 0 -0.327824 0.917125 -0.00614506 -0.398552 0.981078 6.90313e-05 -0.193613 0.995363 -0.00018543 0.0961908 0.999017 -0.0108547 -0.0429781 0.982424 0.00146444 0.186657 0.93863 0 -0.344925 0.910149 -0.00481149 -0.414252 0.839654 3.44569e-05 -0.543121 0.754696 -2.91956e-05 -0.656075 0.645528 -0.00441732 -0.763724 0.595197 -0.000148264 -0.80358 0.256898 0.000210811 -0.966438 0.303563 -0.00430031 -0.952802 -0.0443291 0.00257057 -0.999014 -0.181089 -0.00458434 -0.983456 -0.309025 -2.03878e-05 -0.951054 -0.470391 2.29873e-05 -0.882458 -0.584323 -0.00447716 -0.811509 -0.652909 0 -0.757436 0.977048 0.00182799 0.213012 0.849114 -0.00271267 0.528202 0.866868 0 0.498538 0.99971 -0.0109399 -0.0214715 0.993493 -1.45118e-05 0.11389 0.98173 7.29193e-06 -0.190281 0.957191 -0.00414498 -0.289428 0.897454 0.00249715 -0.441101 0.763919 -0.00347773 -0.645303 0.722851 0 -0.691004 0.960706 5.12402e-05 0.277568 -0.479025 0 0.877801 -0.416275 -0.00457401 0.909227 -0.259826 1.42472e-05 0.965656 -0.0984366 -2.4389e-05 0.995143 0.0428659 -0.00533111 0.999067 0.156098 0.00113023 0.987741 0.462127 -0.00144636 0.886813 0.4927 -0.00413325 0.87019 0.642645 1.94154e-06 0.766164 0.834622 -0.000177556 0.550824 0.89017 -0.0118522 0.455474 0.764168 -9.64953e-06 0.645017 0.993837 0 0.110855 0.995149 -0.0226154 -0.0957423 0.997362 -0.00642795 0.0723033 0.992021 0 -0.126075 0.978251 -0.00602506 -0.207339 0.937626 5.23443e-05 -0.347646 0.880449 -3.61394e-05 -0.474141 0.787731 -0.0047181 -0.616001 0.765464 -0.00176049 -0.643476 0.521373 0.00158952 -0.853327 0.437057 -0.00503729 -0.89942 0.295128 -5.19454e-05 -0.955458 0.110483 7.88177e-05 -0.993878 -0.00246205 -0.0055439 -0.999982 -0.116899 -5.23547e-05 -0.993144 -0.290099 2.96672e-05 -0.956997 -0.441501 -0.00444719 -0.89725 -0.499337 0 -0.866408 0.750535 0 -0.660831 0.929131 0.00207326 0.369745 0.753534 0 0.657409 0.634295 0.0118781 0.773 0.705058 0.00517739 0.709131 0.773615 0.00201285 0.633653 0.783398 0.00158421 0.621518 0.84214 -0.000893773 0.539259 0.99048 -0.0116454 0.137163 0.963642 2.23157e-06 0.267197 0.999585 -1.12732e-06 -0.0288092 0.990214 -0.00448699 -0.139488 0.960051 0.00236917 -0.279814 0.790652 0.000892444 -0.612265 0.824707 -0.00435555 -0.565543 0.890037 0.00661204 -0.455841 0.81653 0.00204627 -0.5773 0.896856 7.41926e-05 0.442322 -0.608245 0 0.793749 -0.549975 -0.00475306 0.835168 -0.407893 2.40758e-05 0.91303 -0.257913 -2.94189e-05 0.966168 -0.116377 -0.00533285 0.993191 -0.0191226 0.000589688 0.999817 0.727591 -0.000251593 0.686012 0.793314 -0.0115358 0.608703 0.637811 7.95825e-06 0.770193 0.342048 -1.82017e-05 0.939682 0.485497 -0.0166287 0.87408 0.289511 -0.000682406 0.957174 0.958166 0 0.286213 0.995847 -0.0231737 0.088042 0.967678 -0.00662229 0.252101 0.999715 0 -0.0238595 0.993396 -0.00595035 -0.114579 0.828314 -0.00409339 -0.560249 0.918383 -2.60548e-05 -0.395692 0.965102 4.71942e-05 -0.261874 0.476123 -0.00526493 -0.879363 0.580248 0.00204108 -0.814438 0.817358 -0.00254154 -0.576124 -0.199879 -4.0693e-05 -0.979821 -0.0334376 -0.00104296 -0.99944 0.0163819 -0.00438349 -0.999856 0.19121 3.56513e-05 -0.981549 0.339322 -4.71338e-05 -0.94067 -0.284144 0.000184042 -0.958782 -0.447045 -0.00458899 -0.894499 -0.509667 0 -0.860372 0.715055 0 0.699068 0.669057 0.00228385 0.743208 0.871293 -0.00562646 0.490731 0.803833 0.0053428 0.594831 0.965076 -0.0032542 0.26195 0.984346 0.00147712 0.176239 0.999994 -0.000423438 -0.00338283 0.987859 0.0019208 -0.155341 0.979231 -0.000372022 -0.202748 0.882156 0.000476944 -0.470956 0.941452 0.00932071 -0.337017 0.904067 0.00366526 -0.427374 0.824219 -0.000137756 -0.566271 0.779986 2.37342e-05 -0.625797 0.761768 -9.59105e-05 -0.64785 0.754574 0 -0.656215 -0.615742 0 0.787948 -0.442846 -0.0127926 0.896506 -0.57029 -0.00154496 0.821442 -0.287879 0.000835297 0.957667 -0.156097 -0.00475993 0.98773 -0.0454972 5.41163e-05 0.998964 0.134746 -3.09251e-05 0.99088 0.289174 -0.00401738 0.957268 0.364929 0.000891356 0.931035 0.9297 0 0.368317 0.955915 -0.00738947 0.293551 0.866038 3.32466e-05 0.499979 0.676848 -9.25387e-05 0.736123 0.783461 -0.0144291 0.621273 0.640648 -0.000912236 0.767834 0.999351 0 0.0360346 0.998877 -0.00454844 -0.0471674 0.978862 2.39299e-05 -0.204522 0.936431 -2.00404e-05 -0.350851 0.863025 -0.00402689 -0.505145 0.828468 -0.000255565 -0.560036 0.586886 0.000262605 -0.80967 0.53023 -0.00364392 -0.847846 0.372811 -1.2028e-05 -0.927907 0.222616 1.81162e-05 -0.974906 0.0764223 -0.00442612 -0.997066 -0.0369329 0.000931215 -0.999317 -0.394825 -0.0013935 -0.918755 -0.412849 0 -0.910799 0.621072 0 0.783754 0.695599 0.00073053 0.71843 0.728209 0.00219234 0.685352 0.825205 -0.00123174 0.564832 0.862612 8.7095e-07 0.505867 0.935282 -6.63937e-07 0.353903 0.968841 -0.00396267 0.247651 0.990595 2.4837e-07 0.136825 0.9995 -1.47397e-07 -0.0316262 0.995593 -0.00112148 -0.0937689 0.966913 0.00208128 -0.255096 0.949738 6.78936e-05 -0.313045 0.896516 -2.17641e-05 -0.443012 0.827365 0.00142046 -0.561663 0.817173 0.000667933 -0.576393 0.682937 -0.000341727 -0.730478 0.711781 0.000522134 -0.702401 0.661598 0 -0.749859 -0.426547 -0.00156121 0.904464 -0.289867 -0.012165 0.95699 -0.505711 0 0.862703 0.366505 -4.2638e-06 0.930416 0.214153 1.22531e-05 0.9768 0.0750847 -0.00512506 0.997164 -0.0422463 -8.01914e-06 0.999107 -0.202686 1.25028e-06 0.979244 0.894279 0 0.44751 0.942877 -0.0102735 0.332983 0.826407 2.26103e-05 0.563073 0.557178 -4.48586e-05 0.830393 0.713332 -0.0166204 0.700629 0.54986 -0.0027225 0.835252 0.968601 0 -0.248622 0.960197 -0.0351953 -0.277098 0.945349 -5.2705e-07 -0.326061 0.864648 0 -0.502378 0.885424 -0.0135128 -0.464587 0.89873 -0.0329001 -0.437266 0.914184 -0.00415429 -0.405277 0.932183 -1.52974e-07 -0.361988 0.739226 0 -0.673458 0.739226 0 -0.673458 0.739226 -4.80355e-07 -0.673457 0.739228 0 -0.673455 0.739224 -7.66001e-08 -0.67346 0.739226 -1.59615e-07 -0.673458 0.739904 0.000131571 -0.672713 0.739219 -7.93787e-07 -0.673466 0.646814 0 0.762648 0.646814 0 0.762648 0.646815 4.19522e-07 0.762647 0.646814 -5.05765e-07 0.762648 0.646814 0 0.762648 0.646629 5.22222e-05 0.762805 0.646815 -4.56093e-07 0.762647 0.646816 -2.81334e-07 0.762646 0.646818 -2.47021e-08 0.762644 0.646814 -4.41801e-08 0.762648 0.646814 -5.5726e-08 0.762648 0.646819 0 0.762644 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.993935 0 0.109965 0.994295 0.0053202 0.106532 0.99706 -0.00500785 0.0764657 0.997342 0 0.0728697 -0.727869 0 0.685717 -0.727869 0 0.685717 -0.728222 0.000709454 0.685341 -0.727933 0 0.685648 -0.727876 -6.8622e-07 0.685708 -0.72787 -2.62208e-07 0.685716 -0.72787 -1.42948e-07 0.685715 -0.727868 -2.64976e-07 0.685717 -0.727866 -3.04256e-06 0.685719 -0.727867 -1.7032e-06 0.685718 -0.72789 2.65501e-05 0.685694 -0.72787 1.36057e-06 0.685716 -0.727866 -5.14887e-06 0.685719 -0.727873 6.30621e-06 0.685712 -0.727869 -6.7353e-07 0.685717 -0.727867 -3.27785e-06 0.685718 -0.727875 1.10865e-05 0.68571 -0.727863 -1.25743e-05 0.685723 -0.646821 3.33565e-06 -0.762642 -0.646814 -1.26107e-07 -0.762648 -0.646812 3.34485e-07 -0.76265 -0.646815 0 -0.762647 -0.646812 -3.68782e-06 -0.762649 -0.646809 -8.84868e-06 -0.762652 -0.646815 1.33892e-06 -0.762647 -0.646821 7.82749e-06 -0.762642 -0.646814 -4.26701e-07 -0.762648 -0.646736 -3.13238e-05 -0.762714 -0.64681 -1.827e-06 -0.762651 -0.646815 0 -0.762647 -0.646814 0 -0.762647 -0.646813 -2.64181e-06 -0.762649 -0.646789 -0.000159504 -0.762669 -0.64682 1.07794e-05 -0.762642 -0.646812 -3.74889e-06 -0.762649 0.60284 0 0.797862 0.60284 0 0.797862 0.60284 2.44774e-07 0.797862 0.60303 -0.000170308 0.797719 0.602841 9.27352e-08 0.797862 0.602831 -9.77661e-07 0.797869 0.602845 0 0.797858 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.982893 0 0.18418 0.982969 0.000448606 0.183771 0.986557 -0.00050753 0.163419 0.986629 0 0.162982 -0.739226 0 0.673457 -0.739217 -8.05549e-06 0.673467 -0.739226 -3.26704e-08 0.673457 -0.739233 5.92048e-06 0.67345 -0.739203 -1.8506e-05 0.673482 -0.739226 0 0.673458 -0.739226 0 0.673458 -0.739188 -5.91958e-05 0.673499 -0.739224 -2.88083e-06 0.67346 -0.739232 4.77318e-06 0.673451 -0.739216 -8.07431e-06 0.673468 -0.739225 -8.43931e-07 0.673458 -0.739226 -6.33918e-07 0.673458 -0.739285 9.4724e-05 0.673393 -0.602842 1.73929e-06 -0.79786 -0.60284 1.194e-07 -0.797862 -0.602841 1.49401e-08 -0.797862 -0.602841 0 -0.797861 -0.60284 0 -0.797862 -0.602841 0 -0.797862 -0.602705 -0.00027157 -0.797964 -0.602845 7.43213e-06 -0.797858 -0.602811 -5.03143e-05 -0.797884 -0.602841 3.98529e-07 -0.797862 -0.602856 1.0751e-05 -0.79785 -0.602829 -8.77523e-06 -0.797871 0.727883 0 -0.685701 0.727869 0 -0.685716 0.72787 -1.89734e-07 -0.685715 0.727869 -3.21823e-07 -0.685716 0.727869 9.13833e-08 -0.685716 0.727846 0 -0.685741 0.727871 6.65955e-07 -0.685714 0.72787 8.15382e-07 -0.685716 0.727871 8.64259e-07 -0.685714 0.72787 7.94771e-07 -0.685715 0.727771 4.95824e-06 -0.68582 0.727868 1.01519e-06 -0.685717 0.727869 6.4887e-07 -0.685717 0.632419 0 0.774627 0.632408 0 0.774635 0.63241 0 0.774634 0.632416 5.5195e-08 0.774629 0.632419 -3.25653e-07 0.774626 0.632417 -3.1992e-07 0.774629 0.632419 -1.88162e-07 0.774626 0.633047 -4.97881e-05 0.774113 0.63242 -8.96232e-07 0.774626 0.632419 5.72638e-08 0.774627 0.632419 8.96479e-08 0.774627 0.632419 4.00503e-07 0.774626 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.999933 0 -0.0115502 0.999945 -0.00313748 -0.0100464 0.997535 0.00265927 -0.0701231 0.996463 -0.0152234 -0.0826474 0.993591 0 -0.113036 -0.632438 1.06027e-05 -0.774611 -0.632416 -5.13763e-07 -0.774629 -0.632419 6.95297e-07 -0.774627 -0.632412 -1.19982e-05 -0.774632 -0.632418 0 -0.774627 -0.632419 -8.8501e-08 -0.774627 -0.632412 2.90666e-08 -0.774633 -0.632418 -5.94574e-07 -0.774627 -0.632432 8.32472e-06 -0.774616 -0.632383 -2.06503e-05 -0.774656 -0.632419 3.45341e-07 -0.774627 -0.632512 0.000103716 -0.774551 -0.632417 -3.10912e-06 -0.774628 -0.632419 0 -0.774627 -0.632419 0 -0.774627 -0.632423 1.07843e-05 -0.774623 -0.632419 3.7032e-07 -0.774627 -0.453062 0 0.891479 -0.453059 -1.57455e-06 0.891481 -0.453061 -8.02706e-07 0.89148 -0.453052 -5.5233e-06 0.891484 -0.45309 1.52007e-05 0.891465 -0.453062 1.57446e-07 0.891479 -0.453064 3.33305e-06 0.891478 -0.453062 0 0.891479 -0.453062 0 0.891479 -0.453062 0 0.891479 -0.452529 -0.000517817 0.89175 -0.453062 -1.18085e-08 0.891479 0.98831 0 0.152457 0.988171 4.74902e-05 0.153358 0.987656 0.000390452 0.15664 0.987049 0.00199686 0.160405 0.98644 0 0.16412 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.991159 0 0.132679 0.990793 0.000940254 0.13538 0.990422 0 0.138076 0.977563 0 0.210641 0.977669 0.000306375 0.210152 0.978299 -0.000329765 0.207197 0.978458 0 0.206446 0.977731 0 0.209864 0.977555 0.000197833 0.210679 0.977909 0 0.209032 -0.643139 0 0.76575 -0.643136 1.76482e-07 0.765752 -0.643135 -5.98534e-07 0.765753 -0.643136 2.24442e-07 0.765752 -0.642887 -0.000331254 0.765961 -0.643253 0.000169218 0.765654 -0.643135 -2.07402e-06 0.765753 -0.643148 1.26377e-05 0.765742 -0.643135 -2.17354e-06 0.765753 -0.643136 0 0.765752 -0.643136 0 0.765752 -0.642755 -0.000428453 0.766072 -0.643144 8.47936e-06 0.765746 -0.482955 -1.3476e-06 -0.875645 -0.482983 1.44401e-05 -0.87563 -0.482957 -1.0376e-07 -0.875644 -0.482954 3.22064e-07 -0.875646 -0.482958 0 -0.875643 -0.482957 0 -0.875644 -0.482957 0 -0.875644 -0.482687 -0.00034224 -0.875793 -0.482957 7.22617e-08 -0.875644 -0.48296 2.96991e-06 -0.875643 -0.482957 -5.0654e-08 -0.875644 -0.482931 -1.41153e-05 -0.875658 -0.482965 4.26788e-06 -0.87564 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.983018 0 0.18351 0.982125 0.00286827 0.188207 0.981185 0 0.193071 0.993091 0 0.117344 0.993146 -0.000578593 0.116875 0.993516 7.98119e-05 0.113692 0.994008 0 0.109311 0.993963 0.000395934 0.109711 0.99369 -0.000313564 0.112163 0.99371 -0.00044111 0.111981 0.993626 -0.000149778 0.112728 0.959728 0 0.280931 0.933925 0.0109403 0.357302 0.863218 2.75318e-05 0.504831 0.767153 -2.90548e-05 0.641464 0.656134 0.0111015 0.754562 0.585 -0.00054786 0.811033 0.300965 0.000556347 0.953635 0.224141 0.01116 0.974493 0.0642216 -5.43663e-05 0.997936 -0.090408 4.6197e-05 0.995905 -0.26053 0.010624 0.965407 -0.328391 0 0.944542 -0.329577 0 -0.944129 -0.2721 0.00271238 -0.962265 -0.107192 -3.32061e-08 -0.994238 0.0608147 1.88022e-08 -0.998149 0.180347 0.00348396 -0.983597 0.281355 0.000132221 -0.959604 0.409315 -1.77272e-05 -0.912393 0.595793 0.000905797 -0.803137 0.578964 0.00208677 -0.81535 0.822827 -0.00133816 -0.568291 0.888999 0.00347144 -0.457897 0.942525 1.34268e-05 -0.334137 0.999825 0 -0.0187202 0.998931 0.00416998 0.046041 0.983494 -9.39934e-06 -0.180941 0.936841 0 0.349755 0.904509 0.00349791 0.42644 0.603012 0.00327754 0.797725 0.727254 5.16605e-06 0.686369 0.825871 -5.90019e-06 0.56386 -0.0147053 2.31454e-08 0.999892 0.0600589 0.00122508 0.998194 0.163573 0.00325526 0.986526 0.240784 -0.000176923 0.970579 0.545617 0.000177952 0.838034 -0.149877 2.35899e-07 0.988705 -0.313282 0.00321648 0.949655 -0.381966 0 0.924176 -0.244473 0 -0.969656 -0.295847 0.00275926 -0.955232 0.0366134 -0.00144019 -0.999328 0.19562 0.00287502 -0.980676 0.306945 -1.614e-07 -0.951727 0.462191 2.35133e-07 -0.88678 0.597794 0.00231005 -0.801646 0.617169 0.00139622 -0.786829 0.804487 -0.000953845 -0.59397 0.884116 0.0028979 -0.467259 0.929777 -3.78085e-07 -0.368123 0.999104 0 -0.0423155 0.999932 0.0028299 0.0112825 0.977995 2.35327e-07 -0.208627 0.99416 0 0.107914 0.998301 0.00175471 -0.058245 0.994451 -0.000104288 -0.105197 0.90346 0.000107324 -0.428672 0.886983 0.00162191 -0.4618 0.710971 -0.00122107 -0.703221 0.620219 0.00254142 -0.784425 -0.285464 0 -0.95839 -0.0941134 -0.0044755 -0.995551 0.514591 8.97189e-07 -0.857436 0.364021 -6.79633e-07 -0.931391 0.244765 0.00258112 -0.969579 0.160975 4.0775e-07 -0.986959 0.0211461 5.3563e-08 -0.999776 -0.00639551 -0.000101768 -0.99998 -0.215614 0.00129371 -0.976478 -0.434275 0 0.90078 -0.21359 -0.00113358 0.976923 -0.297068 0.00351953 0.95485 -0.0676144 -1.83118e-08 0.997712 0.229516 6.21589e-08 0.973305 0.10084 0.00702058 0.994878 0.364284 -0.00114988 0.931287 0.519152 0.000374038 0.854682 0.598026 0.0013058 0.801476 0.64377 0.00310435 0.765213 0.943755 0 0.330646 0.919677 0.00258035 0.392666 0.841401 -3.96412e-08 0.540411 0.739732 5.12027e-08 0.672901 0.916438 0 -0.400177 0.944732 0.00395303 -0.327821 0.981297 -8.22221e-05 -0.192498 0.999336 8.37071e-05 -0.036433 0.995356 0.0038147 0.0961901 0.984697 2.80897e-05 0.174278 0.929594 -1.37867e-05 0.368586 0.864476 0.00327836 0.502663 0.814594 -0.00125734 0.58003 0.575944 0.00158047 0.817487 0.553254 -6.08082e-05 0.833013 0.224985 5.41948e-05 0.974362 0.182395 0.00230164 0.983223 0.0128765 0 0.999917 -0.584329 0 -0.811517 -0.626477 0.00442235 -0.779428 -0.333102 -0.0023161 -0.942888 -0.181088 0.00478779 -0.983455 -0.0666961 -2.63294e-05 -0.997773 0.0989883 1.68692e-05 -0.995089 0.256896 0.0038871 -0.966431 0.322427 -0.000570632 -0.946594 0.645534 0.000750665 -0.763731 0.625169 0.00308442 -0.780484 0.91016 0 -0.414257 0.951282 0.0110645 -0.308124 0.843762 -0.00166652 -0.536715 0.763924 0 -0.645307 0.738898 0.00304006 -0.67381 0.918918 -0.00193884 -0.394444 0.957192 0.0038387 -0.289429 0.986604 -6.46478e-06 -0.163136 1 7.69212e-06 -0.000323945 0.993485 0.00405595 0.113889 0.968754 -0.00215128 0.248014 0.866865 0.00291587 0.498535 0.842107 0 0.53931 0.999689 0 0.024933 0.993819 0.00596297 0.110853 0.834613 0.00459686 0.550818 0.918789 2.95251e-05 0.394749 0.965827 -4.36174e-05 0.259186 0.492698 0.00502676 0.870186 0.575207 -0.00144353 0.818007 0.813463 0.00160821 0.581615 0.0428659 0.00554817 0.999065 0.171544 -5.20927e-05 0.985176 0.348702 3.72119e-05 0.937234 -0.599267 0 0.80055 -0.437116 0.00169739 0.899403 -0.416277 0.00342117 0.909231 -0.236171 -8.19634e-06 0.971712 -0.0643007 3.2481e-05 0.997931 -0.498378 0 -0.86696 -0.441501 0.00440237 -0.89725 -0.289214 -2.39411e-05 -0.957264 -0.132757 3.69545e-05 -0.991149 -0.00246205 0.00539397 -0.999982 0.118455 -0.00143147 -0.992958 0.437061 0.0022076 -0.899429 0.420968 0.00379681 -0.907068 0.978268 0 -0.207343 0.989695 0.00754501 -0.142995 0.931888 -5.43318e-05 -0.362747 0.78774 0.000182115 -0.616008 0.860598 0.0145861 -0.509075 0.702975 -0.00260537 -0.71121 0.750535 0 -0.660831 0.790652 -0.000892444 -0.612265 0.81653 -0.00204627 -0.5773 0.832989 -0.00298831 -0.553282 0.890055 0.00142679 -0.455851 0.96937 -0.00207423 -0.245596 0.999907 0.0116489 -0.00702775 0.990224 -2.0413e-06 -0.13949 0.987359 8.34135e-07 0.158499 0.963632 0.00448642 0.267194 0.915563 -0.00236857 0.402169 0.634342 0 0.773053 0.842139 0.000936791 0.539259 0.783399 -0.000963416 0.621519 0.74495 -0.00226244 0.667117 0.77361 -0.00419137 0.633649 0.705067 -9.13136e-05 0.709141 0.979842 0 0.199774 0.958146 0.0063972 0.286207 0.906803 -5.25697e-05 0.421555 0.840251 2.84636e-05 0.542198 0.727584 0.00434919 0.686005 0.718172 0.00313296 0.695859 0.463465 -0.00235737 0.886112 0.342043 0.00580473 0.939667 0.21084 7.04925e-05 0.977521 0.0236511 -7.16886e-05 0.99972 -0.116377 0.00557211 0.99319 -0.245996 -0.00222503 0.969268 -0.555815 0.00321139 0.8313 -0.549979 0.00262866 0.835174 -0.705794 0 0.708418 -0.509667 0 -0.860372 -0.447045 0.00463343 -0.894499 -0.284144 -0.000185823 -0.958782 -0.199879 4.1087e-05 -0.979821 -0.0334388 0.00105305 -0.99944 0.0163819 0.00442624 -0.999856 0.19121 -3.60018e-05 -0.981549 0.339322 4.7597e-05 -0.94067 0.476123 0.00531742 -0.879363 0.580257 -0.00206215 -0.814431 0.993414 0 -0.114581 0.999615 0.00954799 -0.0260406 0.965102 -4.77113e-05 -0.261874 0.828321 0.000123349 -0.560254 0.914219 0.0184511 -0.4048 0.817349 0.00256776 -0.576137 0.754574 0 -0.656215 0.761768 9.59105e-05 -0.64785 0.83527 -0.000416144 -0.54984 0.824219 -0.00116277 -0.566271 0.919277 0.00114094 -0.39361 0.904073 -0.000237203 -0.427377 0.941493 3.01942e-08 -0.337032 0.971803 8.25724e-07 -0.235792 0.97923 0.00128437 -0.202748 0.999616 -0.0017134 0.0276686 0.999989 -0.00328909 -0.00338281 0.965076 0.0033771 0.26195 0.935093 -0.00169212 0.354397 0.870554 0.00020244 0.492072 0.765474 -0.000944817 0.643466 0.773982 -0.00172106 0.633205 0.669058 0 0.74321 0.956067 0 0.293149 0.92969 0.00480594 0.368312 0.866038 -3.32461e-05 0.499979 0.786835 2.57007e-05 0.617163 0.676842 0.00411052 0.736117 0.640648 0.000912236 0.767834 0.364929 -0.000891355 0.931035 0.289174 0.00401738 0.957268 0.134746 3.09252e-05 0.99088 -0.0454972 -5.41162e-05 0.998964 -0.156097 0.00475993 0.98773 -0.287879 -0.000835297 0.957667 -0.442565 0.000427743 0.896737 -0.570287 0.00355516 0.821438 -0.615742 0 0.787948 -0.460616 0 -0.8876 -0.394822 0.00392669 -0.918749 -0.235273 -4.33374e-07 -0.971929 -0.0689982 -9.81802e-07 -0.997617 0.0782781 0.00451374 -0.996921 0.0764223 0.00442612 -0.997066 0.223295 -3.91104e-05 -0.974751 0.417175 4.53946e-05 -0.908826 0.530228 0.00468372 -0.847842 0.622246 -5.59434e-05 -0.782822 0.767406 3.25562e-05 -0.641162 0.863025 0.00409818 -0.505144 0.912172 -0.00189564 -0.409802 0.998884 0.00235814 -0.0471678 0.9999 0 -0.014152 0.796972 0.000124085 0.604017 0.661598 0 -0.749859 0.711781 -0.000522134 -0.702401 0.762801 -0.00214122 -0.64663 0.837242 0.00172686 -0.54683 0.968849 -0.000164599 0.247653 0.952392 0.00407552 0.30485 0.996526 3.65107e-08 0.0832791 0.995594 3.64765e-08 -0.0937689 0.996336 0.000311003 -0.0855258 0.949738 -0.000293956 -0.313045 0.952313 9.60864e-07 -0.305122 0.887541 -1.30986e-07 -0.460728 0.621072 0 0.783754 0.644251 -0.000220899 0.764814 0.695599 0.000436405 0.71843 0.825203 -0.00249883 0.564831 0.936194 0 0.351484 0.894267 0.00517545 0.447504 0.815326 -1.53955e-05 0.579002 0.718784 6.18396e-06 0.695233 0.557175 0.00312833 0.830389 0.562093 0.00352811 0.827067 0.0750847 0.0051345 0.997164 0.212763 -1.59482e-05 0.977104 0.377257 6.74575e-06 0.926108 -0.547427 0 0.836854 -0.336422 0.00863666 0.941672 -0.426547 0.00156121 0.904464 -0.202715 -1.05768e-06 0.979238 -0.0437552 7.97517e-06 0.999042 -0.615954 -3.8337e-06 -0.787782 -0.616041 0.000428274 -0.787714 -0.615956 4.47024e-06 -0.787781 -0.615956 -3.27828e-06 -0.78778 -0.615952 1.74267e-06 -0.787783 -0.615956 -2.05948e-06 -0.787781 -0.615955 4.48624e-06 -0.787781 -0.615961 1.00013e-05 -0.787777 -0.615952 9.01322e-07 -0.787783 -0.615953 1.35233e-06 -0.787783 -0.615953 -7.00732e-07 -0.787783 -0.615952 -1.81127e-06 -0.787784 -0.615958 4.21964e-06 -0.787779 -0.615955 -3.50483e-07 -0.787782 -0.615951 -5.86207e-06 -0.787785 -0.615954 -1.98332e-06 -0.787782 -0.615955 4.49723e-06 -0.787781 -0.615954 1.09882e-06 -0.787782 -0.615954 -4.89135e-06 -0.787782 -0.615955 3.46082e-07 -0.787782 -0.615952 7.18418e-06 -0.787784 -0.615954 1.46762e-06 -0.787782 -0.615954 2.14453e-07 -0.787782 -0.615954 2.26453e-07 -0.787782 -0.615952 -1.25215e-06 -0.787784 -0.615954 1.14407e-07 -0.787782 -0.615948 -1.10227e-05 -0.787787 -0.615955 1.26228e-06 -0.787781 -0.615953 -3.77888e-07 -0.787783 -0.615956 1.71729e-06 -0.787781 -0.615954 -8.78321e-07 -0.787782 -0.615951 -7.89275e-06 -0.787785 -0.615944 -2.2916e-05 -0.78779 -0.615951 -5.82468e-06 -0.787784 -0.615941 9.45835e-06 -0.787792 -0.615955 -4.45657e-07 -0.787781 -0.615956 -8.27345e-07 -0.787781 -0.615954 2.58398e-07 -0.787782 -0.615955 -3.9152e-07 -0.787782 -0.615956 -1.62202e-06 -0.78778 -0.615954 2.51063e-07 -0.787782 -0.615955 -6.66796e-07 -0.787781 -0.615953 7.48872e-08 -0.787783 -0.615953 5.96701e-07 -0.787783 -0.615953 5.86896e-07 -0.787783 -0.615954 2.87714e-07 -0.787782 -0.615956 1.43619e-06 -0.787781 -0.615955 1.08178e-06 -0.787781 -0.615953 -1.18243e-06 -0.787783 -0.615956 -4.25652e-06 -0.787781 -0.61595 6.18531e-06 -0.787785 -0.615957 -2.81251e-06 -0.78778 -0.615954 -3.77041e-06 -0.787782 -0.615954 -1.95499e-06 -0.787782 -0.615954 3.73439e-06 -0.787782 -0.615954 7.31894e-07 -0.787782 -0.615954 -1.15611e-06 -0.787782 -0.615958 5.10074e-06 -0.787779 -0.615953 -1.82753e-06 -0.787783 -0.615955 1.33534e-06 -0.787782 -0.615953 3.4645e-06 -0.787783 -0.615959 -1.32357e-05 -0.787778 -0.615954 -9.11183e-07 -0.787782 -0.615955 1.34552e-06 -0.787781 -0.615948 -1.15256e-05 -0.787787 -0.615955 1.51269e-06 -0.787782 -0.615953 -1.85563e-06 -0.787783 -0.615954 2.16993e-07 -0.787782 -0.615954 -2.42799e-07 -0.787782 -0.615959 3.9774e-06 -0.787779 -0.615954 -1.23451e-06 -0.787782 -0.615952 -1.68436e-06 -0.787783 -0.615955 -6.25553e-07 -0.787782 -0.615956 -8.48793e-07 -0.787781 -0.615956 3.86005e-06 -0.787781 -0.615954 -5.59824e-07 -0.787782 -0.615954 4.55889e-07 -0.787782 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.96583 0 -0.259178 0.96583 0 -0.259178 0.706844 0 -0.707369 0.706844 0 -0.707369 0.258461 0 -0.966022 0.258461 0 -0.966022 -0.259178 0 -0.96583 -0.259178 0 -0.96583 -0.707369 0 -0.706845 -0.707369 0 -0.706845 -0.966022 0 -0.25846 -0.966022 0 -0.25846 -0.96583 0 0.259178 -0.96583 0 0.259178 -0.706844 0 0.707369 -0.706844 0 0.707369 -0.258461 0 0.966022 -0.258461 0 0.966022 0.259178 0 0.96583 0.259178 0 0.96583 0.707369 0 0.706845 0.707369 0 0.706845 0.966022 0 0.25846 0.966022 0 0.25846 0.96583 0 -0.259178 0.96583 0 -0.259178 0.706844 0 -0.707369 0.706844 0 -0.707369 0.258461 0 -0.966022 0.258461 0 -0.966022 -0.259178 0 -0.96583 -0.259178 0 -0.96583 -0.707369 0 -0.706845 -0.707369 0 -0.706845 -0.966022 0 -0.25846 -0.966022 0 -0.25846 -0.96583 0 0.259178 -0.96583 0 0.259178 -0.706844 0 0.707369 -0.706844 0 0.707369 -0.258461 0 0.966022 -0.258461 0 0.966022 0.259178 0 0.96583 0.259178 0 0.96583 0.707369 0 0.706845 0.707369 0 0.706845 0.966022 0 0.25846 0.966022 0 0.25846 0.9998 -0.0174512 0.00977145 0.9998 -0.0174515 0.00977147 0.9998 -0.0174517 0.00977145 0.146595 -0.017265 0.989046 0.157963 -0.0275116 0.987062 0.445104 -0.0077378 0.895445 0.475648 -0.0363267 0.878886 0.700049 0.000279339 0.714095 0.739535 -0.0436142 0.671704 0.886433 0.00678137 0.462808 0.919937 -0.0493738 0.388944 0.986018 0.0117636 0.166226 0.992581 -0.0173244 0.120347 0.100604 -0.0173647 0.994775 0.146457 -0.0465503 0.988121 0.371004 0.0150197 0.92851 0.444734 -0.04152 0.8947 0.657477 0.0092431 0.753418 0.699621 -0.034953 0.713659 0.871006 0.00225529 0.491268 0.886176 -0.0249983 0.462674 0.984481 -0.00901538 0.175261 0.98594 -0.0172088 0.166212 -0.00977144 -0.0174517 0.9998 -0.00977144 -0.0174517 0.9998 -0.00977144 -0.0174517 0.9998 -0.00977144 -0.0174517 0.9998 -0.872486 -0.0172819 0.488334 -0.104042 -0.0173572 0.994421 -0.159246 0.0251124 0.986919 -0.675516 -0.0172768 0.737143 -0.54217 -0.0174456 0.840088 -0.444034 0.0165415 0.895857 -0.410458 -0.0173202 0.911715 -0.251568 -0.0174344 0.967683 -0.460566 -0.0173246 0.887456 -0.443789 -0.0370624 0.895364 -0.177577 0.00530997 0.984093 -0.159273 -0.0172288 0.987084 -0.603019 -0.0174331 0.797537 -0.688267 -0.0512847 0.723643 -0.689172 0.00240207 0.724594 -0.862727 -0.0396913 0.504109 -0.898331 -0.0173908 0.438975 -0.87105 -0.0598951 0.48753 -0.822592 -0.0174146 0.568366 -0.715496 -0.0173606 0.698401 -0.935655 -0.0174515 0.352485 -0.935655 -0.017452 0.352485 -0.935655 -0.0174514 0.352485 -0.935655 -0.0174516 0.352485 -0.935655 -0.0174517 0.352485 -0.935655 -0.0174516 0.352485 -0.935655 -0.0174433 0.352485 -0.935655 -0.017451 0.352485 -0.935654 -0.0174509 0.352486 -0.935655 -0.0174523 0.352484 -0.935655 -0.0174514 0.352485 -0.935655 -0.0174514 0.352485 -0.935655 -0.0174515 0.352485 -0.935655 -0.0174513 0.352485 0.998194 -0.0502344 0.0329336 0.999723 -0.0179136 0.0152471 0.999723 -0.0179111 0.0152465 0.999805 -0.0174515 0.00928246 0.999888 -0.0143616 0.00429899 0.999844 -0.016781 0.00546474 0.999994 -1.92746e-06 -0.00342521 0.999821 -0.0174014 -0.0073803 0.999945 -0.0102181 0.0023924 0.999982 -0.0060165 0.00057564 0.999934 -0.0112044 0.00259802 0.999802 -0.0178551 -0.00874427 0.999808 -0.0177086 -0.00838317 0.999824 -0.0173299 -0.00717975 0.999831 -0.0176495 -0.00524707 0.999838 -0.0171149 0.00555994 0.999851 -0.0151459 0.00823213 0.999772 -0.0213193 -0.00156009 0.999821 -0.0189059 9.59147e-05 0.999806 -0.0197087 -0.000497188 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.239572 -0.966675 0.0902529 -0.0170604 -0.999829 -0.00717601 -0.243864 -0.965431 0.0920484 -0.655968 -0.71325 0.246943 -0.622587 -0.747455 0.231725 -0.779074 -0.553961 0.293548 -0.901598 -0.268162 0.339427 -0.900293 -0.272839 0.339163 0.858173 -0.51326 0.0101204 0.91353 -0.406768 0.00134994 0.931925 -0.362024 0.021306 0.962061 -0.272834 -0.000478433 0.998616 -0.0477628 -0.022042 0.912288 -0.405975 -0.053987 0.93163 -0.363408 0.000269873 0.983908 -0.178312 -0.0113755 0.994888 -0.0994375 -0.0175848 0.983085 -0.180254 0.0324351 0.961001 -0.272788 0.0454368 0.700608 -0.713249 0.0206227 0.588623 -0.806141 0.0604937 0.692944 -0.719924 0.0392213 0.798468 -0.601457 0.0264257 0.901723 -0.431339 0.0290182 0.255893 -0.966674 0.00771771 0.136472 -0.989083 0.0555922 0.248403 -0.968179 0.0304283 0.386048 -0.922385 0.0131309 0.482182 -0.875938 0.0152637 0.105155 -0.994456 -0.000388759 0.255937 -0.966642 -0.0100031 0.346866 -0.937913 -0.00191029 0.533942 -0.845521 -0.000813175 0.700883 -0.71325 -0.00618795 0.738358 -0.674407 -0.00131826 0.86777 -0.496965 0.000251375 0.858225 -0.513256 0.004363 0.256018 -0.966672 0.000670779 0.256079 -0.966656 0.000668183 0.700923 -0.713234 0.00182891 0.701015 -0.713144 0.0018235 0.96206 -0.272827 0.00250253 0.962078 -0.272763 0.00249966 0.9998 0.0174517 0.00977145 0.9998 0.0174515 0.00977147 0.9998 0.0174512 0.00977145 0.146595 0.017265 0.989046 0.112595 0.0477486 0.992493 0.445028 -0.0200369 0.895292 0.414394 0.0168607 0.909941 0.699942 0.017461 0.713986 0.724605 -0.0138638 0.689025 0.885688 0.0415519 0.462418 0.909228 0.00548586 0.416263 0.985617 0.0308201 0.166158 0.988625 0.0172557 0.14941 0.12974 0.0173059 0.991397 0.146615 0.00380866 0.989186 0.397957 0.0290722 0.916943 0.445107 -0.00681258 0.895451 0.673778 0.0480788 0.737368 0.699947 0.0170136 0.713992 0.901519 0.0174065 0.43239 0.885161 0.0539818 0.462143 0.991105 -0.0131537 0.132431 0.98594 0.0172082 0.166212 -0.00977144 0.0174517 0.9998 -0.00977144 0.0174517 0.9998 -0.00977144 0.0174517 0.9998 -0.00977144 0.0174517 0.9998 -0.872486 0.0172821 0.488334 -0.87386 0.020857 0.48573 -0.68911 0.0135742 0.724529 -0.692798 0.0200219 0.720853 -0.444048 0.014488 0.895886 -0.447323 0.0190455 0.89417 -0.159277 0.0154642 0.987113 -0.16069 0.0172247 0.986855 -0.871784 0.0172784 0.489585 -0.872458 0.0190299 0.488318 -0.686409 0.0154615 0.727051 -0.689036 0.0199969 0.724451 -0.43938 0.0144861 0.898184 -0.443998 0.0209017 0.895784 -0.156376 0.0136703 0.987603 -0.159273 0.0172288 0.987084 -0.935655 0.0174516 0.352485 -0.935655 0.0174511 0.352485 -0.935655 0.0174516 0.352485 -0.935655 0.0174514 0.352485 -0.935655 0.0174515 0.352485 -0.935655 0.0174513 0.352485 -0.935655 0.0174519 0.352485 -0.935655 0.0174515 0.352485 -0.935655 0.0174515 0.352485 -0.935655 0.0174521 0.352484 -0.935654 0.017451 0.352486 -0.935642 0.0174154 0.35252 -0.935655 0.0174523 0.352484 -0.935655 0.0174513 0.352485 0.999805 0.0174515 0.00928246 0.999821 0.0174014 -0.0073803 0.999819 0.0190183 -0.000497194 0.999909 0.013261 0.00259796 0.999998 -0.000468356 -0.00186859 0.999993 0.00375617 -0.000340993 0.999967 0.00799436 0.00142098 0.99993 0.0114497 0.00294932 0.999876 0.0150527 0.004632 0.999821 0.0173995 -0.00737987 0.999815 0.0173565 0.00823182 0.999843 0.0168308 0.00555996 0.999772 0.0213193 -0.00156009 0.999805 0.0197228 -0.000464606 0.999832 0.0173849 -0.00585716 0.999816 0.0175032 -0.00787556 0.999723 0.0179111 0.0152465 0.999994 0.00333191 -0.00101535 0.999359 0.0305521 0.0186857 0.999302 0.0175685 0.0329702 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0251449 0.989442 0.14273 0.164561 0.953695 0.251764 0.165018 0.950171 0.264472 0.167923 0.948939 0.267052 0.137369 0.961394 0.238434 0.0643478 0.980581 0.18526 0.0659403 0.971685 0.226893 0.0458479 0.98461 0.168647 0.263185 0.9137 0.309655 0.257598 0.921418 0.290917 0.264245 0.913817 0.308403 0.237773 0.92202 0.305522 0.200732 0.934759 0.293142 0.227063 0.927769 0.296121 0.170486 0.945222 0.278372 0.212739 0.935609 0.281743 0.204025 0.938166 0.279675 0.26163 0.913174 0.312511 0.264678 0.915957 0.30161 0.265461 0.917832 0.295153 0.292286 0.898506 0.327501 0.29851 0.894057 0.333998 0.315696 0.884315 0.343981 0.285405 0.906757 0.310381 0.29874 0.911156 0.28381 0.258056 0.924408 0.280851 0.123654 0.989155 0.0792561 0.0939099 0.991515 0.0898835 0.252294 0.934996 0.249258 0.25179 0.932464 0.259061 0.200565 0.956722 0.21085 0.173762 0.972785 0.153287 0.141588 0.979831 0.141013 0.0553173 0.997105 0.052176 0.054024 0.9972 0.0517077 0.147657 0.97504 0.165813 0.243972 0.936517 0.25182 0.110771 0.97497 0.192777 0.171147 0.956072 0.237982 0.0917455 0.991903 0.0878119 0.102652 0.993978 0.0383417 0.101871 0.991492 0.0810293 0.0410121 0.995559 0.0847333 0.128008 0.978274 0.163078 0.215847 0.950456 0.223702 0.401028 0.782822 0.47578 0.412572 0.799005 0.437465 0.365246 0.829921 0.421695 0.355654 0.848723 0.391381 0.300247 0.884969 0.355925 0.289769 0.894725 0.339854 0.149353 0.969761 0.193021 -0.964926 0.237292 -0.112293 -0.807887 0.568545 -0.15516 -0.619926 0.764858 -0.17517 -0.146555 0.986978 0.0662981 -0.817386 0.480753 0.317423 -0.974351 0.153652 -0.16441 -0.207071 0.978319 0.00372683 -0.28843 0.957438 0.0109913 -0.293426 0.955914 0.0113771 -0.245418 0.969293 0.0155563 -0.182836 0.981225 0.0613852 -0.193581 0.978075 0.0767876 -0.155775 0.983781 0.0889338 -0.493188 0.869923 -0.000232503 -0.981367 0.0602851 -0.182442 -0.95359 0.264447 -0.143991 -0.881531 0.458374 -0.113125 -0.675044 0.662855 0.323942 -0.612793 0.736481 0.286497 -0.707075 0.650783 0.276633 -0.743675 0.631255 0.220148 -0.48865 0.865273 0.111906 -0.389249 0.90745 0.158176 -0.4807 0.865803 0.138974 -0.290745 0.95144 0.101141 -0.295588 0.950555 0.0952561 -0.26641 0.960445 0.0810592 -0.249392 0.965866 0.0700517 -0.180984 0.980513 0.0764069 -0.2076 0.975418 0.0739011 -0.284056 0.952277 0.111717 -0.00504354 0.999063 0.0429811 -0.0208372 0.995109 0.0965607 -0.00477424 0.99432 0.106321 -0.011923 0.999524 0.0284562 -0.0194596 0.999228 0.0341333 -0.293469 0.953182 0.0729439 -0.274295 0.958469 0.0780936 -0.206692 0.976067 0.0676155 -0.194763 0.978398 0.0693122 -0.113253 0.992875 0.0370464 -0.114788 0.993385 0.00323142 -0.0998872 0.994507 0.0312805 -0.08412 0.995007 0.0537208 -0.0188439 0.999581 0.0219892 -0.730543 0.679223 0.0704488 -0.41956 0.904186 0.0801109 -0.39793 0.913963 0.0795158 -0.749935 0.65359 0.102068 -0.553358 0.825921 0.107931 -0.537919 0.836535 0.104173 -0.49191 0.866482 0.0850496 -0.479883 0.872884 0.0882368 -0.36988 0.924025 0.0967823 -0.00464055 0.999975 -0.00534297 -0.335974 0.941253 -0.0341218 -0.211086 0.97734 -0.0158194 -0.158305 0.987242 0.0171221 -0.195489 0.979325 -0.0520231 -0.0602396 0.998138 0.00959964 -0.075067 0.996858 -0.0252706 -0.0177133 0.999816 -0.00735039 -0.298294 0.954436 -0.00853558 -0.321928 0.946592 -0.0180252 -0.454684 0.890161 -0.029614 -0.415433 0.909399 -0.020238 -0.535958 0.843677 -0.0309596 -0.504312 0.863155 -0.0251445 -0.575988 0.816944 -0.0290021 -0.56142 0.827076 -0.0274464 -0.553365 0.832497 -0.0271301 -0.61745 0.786008 -0.0307743 -0.688958 0.721664 -0.0673622 -0.304668 0.952221 -0.0212793 -0.279316 0.959783 -0.0282731 -0.314682 0.949168 -0.00740109 -0.206597 0.978283 -0.0167642 -0.210711 0.977445 -0.0141899 -0.12402 0.992272 -0.00381765 -0.116026 0.9932 -0.00955379 -0.0385865 0.999248 0.0038594 -0.0346225 0.9994 0.000773114 -0.527207 0.840583 -0.12439 -0.47023 0.875307 -0.112789 -0.490488 0.863566 -0.116944 -0.548333 0.827175 -0.122931 -0.525246 0.84219 -0.12179 -0.54444 0.829626 -0.123716 -0.556897 0.821164 -0.124724 -0.0661492 0.996192 -0.0568043 -0.0497322 0.997859 -0.042486 -0.218241 0.97029 -0.104445 -0.162238 0.985753 -0.044375 -0.386324 0.906203 -0.171901 -0.272717 0.959642 -0.0686433 -0.309444 0.946321 -0.0933836 -0.26019 0.95936 -0.109226 -0.0880085 0.994808 -0.0511037 -0.00391408 0.999174 -0.0404473 -0.0446243 0.996589 -0.0694166 -0.100368 0.993192 -0.0591268 -0.241077 0.967812 -0.0722554 -0.423865 0.905357 -0.0258447 -0.483159 0.860279 -0.16272 -0.556344 0.810173 -0.184665 -0.432358 0.887051 -0.161888 -0.39615 0.904918 -0.155529 -0.410914 0.897577 -0.159706 -0.26884 0.954812 -0.126724 -0.33893 0.927861 -0.155566 -0.214896 0.969605 -0.116988 -0.0733894 0.992912 -0.0934815 -0.0887037 0.991638 -0.0937346 -0.094586 0.991184 -0.0927795 -0.566489 0.800951 -0.193826 -0.557555 0.807081 -0.194299 -0.565099 0.801903 -0.193943 -0.569206 0.799119 -0.193424 -0.56629 0.802154 -0.189381 -0.535889 0.823141 -0.187781 -0.375715 0.912195 -0.163517 -0.407065 0.897832 -0.167917 -0.326018 0.932645 -0.154547 -0.092128 0.990412 -0.102941 -0.102324 0.988949 -0.107281 -0.229445 0.96422 -0.132798 -0.24767 0.958856 -0.138763 -0.352855 0.922372 -0.157235 -0.00669458 0.996456 -0.0838529 -0.00748262 0.996436 -0.0840188 -0.0105294 0.996361 -0.084579 -0.230089 0.970216 -0.0757593 -0.160307 0.986964 0.0143027 -0.291408 0.949986 -0.112284 -0.385153 0.910594 -0.149916 -0.413174 0.897248 -0.155674 -0.249293 0.968399 0.00746174 -0.21974 0.974919 -0.035309 -0.39432 0.913791 -0.0974565 -0.271515 0.95775 -0.0948398 -0.168653 0.980874 -0.0971759 -0.0821101 0.990495 -0.110354 -0.199594 0.976709 -0.0787503 -0.1891 0.977951 -0.0886151 -0.612759 0.774976 -0.154719 -0.499567 0.857413 -0.123592 -0.799878 0.579598 -0.155762 -0.806143 0.584378 -0.0929282 -0.973708 0.20671 -0.0957319 -0.964073 0.236955 -0.120069 -0.960769 0.234698 -0.147784 -0.977055 0.144565 -0.156411 -0.936249 0.285164 -0.205229 -0.710214 0.696157 -0.104701 -0.59127 0.80289 -0.0759516 -0.808872 0.580701 -0.0922627 -0.81207 0.582884 -0.0280915 -0.873909 0.484387 -0.0406358 -0.874283 0.484732 0.0257468 -0.563618 0.825704 -0.0233816 -0.589716 0.807181 -0.0263332 -0.757752 0.651636 -0.0343772 -0.757647 0.651999 0.0294828 -0.890993 0.453023 0.0300197 -0.88592 0.451483 0.106342 -0.936489 0.154476 0.314844 -0.947685 0.155848 0.278577 -0.956397 0.156771 0.24643 -0.968598 0.115147 0.220362 -0.884292 0.418405 0.207277 -0.899461 0.42252 0.111567 -0.752485 0.650549 0.102728 -0.757461 0.652216 0.0294518 -0.504339 0.862969 0.0304378 -0.711504 0.702506 0.0157096 -0.967412 0.172022 0.185805 -0.972193 0.172834 0.158016 -0.9782 0.173527 0.114077 -0.983759 0.12624 0.127603 -0.964582 0.262199 0.0288702 -0.968124 0.248468 0.0316217 -0.978251 0.203574 -0.0397735 -0.970763 0.23529 -0.04752 -0.968343 0.233297 -0.0887995 -0.965681 0.172422 -0.194246 -0.956661 0.235782 -0.170903 -0.815393 0.564713 -0.127411 -0.818302 0.567092 -0.0937489 -0.751148 0.657005 -0.0642012 -0.80308 0.551362 -0.225968 -0.802054 0.55283 -0.226029 -0.804275 0.554369 -0.21405 -0.804821 0.553612 -0.213954 -0.81067 0.557726 -0.178202 -0.339178 0.927817 -0.155288 -0.535987 0.823066 -0.187832 -0.537005 0.824631 -0.177789 -0.539134 0.823253 -0.177736 -0.543435 0.829602 -0.128213 -0.54254 0.830191 -0.128194 -0.546646 0.835447 -0.0566323 -0.539187 0.830801 0.13801 -0.532683 0.835071 0.137497 -0.74263 0.651243 0.156153 -0.681235 0.709543 0.180188 -0.892413 0.398267 0.212089 -0.85603 0.389102 0.340311 -0.933481 0.122798 0.336949 -0.88729 0.205566 0.412866 -0.916134 0.0620122 0.396046 -0.543662 0.81997 -0.179112 -0.799465 0.562265 -0.211458 -0.805867 0.553209 -0.211039 -0.958657 0.190952 -0.210985 -0.952432 0.20568 -0.224878 -0.95962 0.174294 -0.220795 -0.9538 0.20821 -0.216598 -0.959062 0.202249 -0.198231 -0.810901 0.557397 -0.178182 -0.817451 0.561694 -0.12757 -0.541837 0.83861 -0.0560944 -0.54206 0.84031 -0.00709782 -0.333678 0.941547 0.046352 0.000598108 0.9983 -0.0582814 -0.000406734 0.998299 -0.0583049 0.00079536 0.998316 -0.0580027 0.00320172 0.998278 -0.0585732 -0.00293569 0.998678 -0.0513128 0.0033988 0.998588 -0.0530226 -0.0032621 0.998977 -0.0450994 -0.000553044 0.998945 -0.0459117 0.000940481 0.998952 -0.0457617 -0.00017418 0.99895 -0.0458043 0.00234437 0.999436 0.0334897 0.00148968 0.999749 0.0223358 0.00220197 0.999453 0.033006 0.00123363 0.999497 0.0316745 0.00460993 0.999641 0.0264011 0.000374935 0.999598 0.0283651 0.00213227 0.999696 0.0245529 6.31414e-05 0.999674 0.0255126 0.00203149 0.999772 0.0212419 0.00112317 0.999862 0.0165792 -0.00213147 0.999992 0.00332976 0.0021416 0.999971 0.00728721 -0.00326007 0.999971 0.00686254 0.00334827 0.999899 0.0138232 -0.000534184 0.999909 0.0135182 0.000609554 0.999825 -0.018721 -0.000491431 0.999988 -0.00494927 8.31136e-05 0.999981 -0.00618748 -0.000164051 0.999964 -0.00849954 0.0035415 0.999907 -0.0131627 -0.00336969 0.999938 -0.0106419 0.00030733 0.999883 -0.0152688 6.26636e-05 0.999846 -0.0175563 0.00875567 0.998823 0.0476999 0.00866574 0.998822 0.0477396 0.00823568 0.998848 0.0472802 0.00771783 0.998837 0.0475945 0.0080062 0.998851 0.047248 0.0079935 0.998856 0.0471529 0.00789153 0.998865 0.0469786 0.0072528 0.998886 0.046629 0.00642487 0.998935 0.0456863 0.00677095 0.998924 0.0458758 0.00509769 0.99902 0.0439702 0.00576675 0.999014 0.0440183 0.00406353 0.999106 0.0420721 0.0002329 0.999658 -0.0261575 0.000120317 0.999631 -0.0271475 0.00039102 0.999583 -0.0288565 -0.000134241 0.999571 -0.0292822 0.000382588 0.99947 -0.0325447 -0.000142285 0.999456 -0.03297 0.000378289 0.999343 -0.0362553 -0.000142706 0.999327 -0.0366774 0.000288382 0.999224 -0.0393975 -0.000838151 0.999196 -0.0400908 -0.000196869 0.999205 -0.0398613 0.800178 0.59819 0.0434063 0.627534 0.776963 0.050294 0.151671 0.964926 -0.214277 0.0929559 0.995597 -0.0120905 0.190154 0.979898 -0.0603367 0.18877 0.980273 -0.0585685 0.55394 0.831738 -0.0369144 0.545483 0.836068 -0.0586394 0.366728 0.929841 -0.0300969 0.320568 0.943816 -0.0802957 0.552578 0.833338 -0.0143663 0.493412 0.869796 0.000524485 0.544822 0.838362 -0.0178565 0.33303 0.941846 -0.0449168 0.229526 0.972294 -0.0442923 0.0401886 0.996241 -0.0767406 0.3019 0.952271 -0.0451239 0.158903 0.985199 -0.0642898 0.156523 0.985589 -0.0641466 0.039023 0.996259 -0.0771073 0.0407134 0.996179 -0.0772634 0.486384 0.873743 -0.00207556 0.440451 0.897748 -0.00716399 0.494624 0.869079 0.00696841 0.554698 0.832049 0.00199039 0.511212 0.859434 0.00605411 0.54628 0.837603 0.000686349 0.393358 0.918796 -0.0329211 0.29854 0.953332 -0.0450772 0.561465 0.827095 0.0258928 0.503049 0.864159 0.0130537 0.458005 0.888939 0.00428064 0.480073 0.877174 0.00974561 0.388693 0.921337 -0.00740655 0.406082 0.913833 -0.00253875 0.289325 0.956965 -0.0225582 0.150808 0.987725 -0.0406888 0.143728 0.988689 -0.0428626 0.278863 0.960062 -0.0227434 0.0397708 0.997784 -0.0533436 0.038261 0.997796 -0.0542228 0.0376724 0.9978 -0.0545593 0.035598 0.997825 -0.0554826 0.0330274 0.997864 -0.0563535 0.0316468 0.997884 -0.0567934 0.0289232 0.99792 -0.057612 0.0247963 0.997967 -0.0587185 0.0223211 0.997988 -0.0593361 0.0187759 0.998009 -0.0602128 0.0110138 0.998017 -0.0619709 0.0358085 0.997749 -0.0567021 0.403134 0.914315 0.0388841 0.392758 0.918954 0.035552 0.481587 0.874879 0.0515843 0.621851 0.780651 0.0623319 0.556502 0.828922 0.0565125 0.571006 0.818712 0.0605242 0.62537 0.776525 0.076954 0.536875 0.84154 0.0597972 0.552997 0.830743 0.0637185 0.495997 0.866709 0.0529363 0.11716 0.98823 0.0983627 0.0511744 0.998671 -0.00604471 0.00790528 0.999813 -0.0176645 0.113714 0.992298 -0.0491279 0.149195 0.988791 -0.00584308 0.278773 0.959716 0.0350884 0.0977424 0.991002 -0.0914429 0.243371 0.969929 -0.0028528 0.275628 0.961135 0.0157475 0.281413 0.959411 0.0183427 0.243645 0.969634 0.0211673 0.203637 0.978589 0.0299286 0.118719 0.98904 0.0877773 0.156605 0.986257 0.0526492 0.0416224 0.998928 -0.0202702 0.143817 0.987659 -0.0620228 0.360564 0.864802 -0.349444 0.594243 0.801259 0.0697064 0.628667 0.77144 0.0982765 0.646634 0.755135 0.107873 0.642081 0.759314 0.105708 0.557314 0.825731 0.0870062 0.651457 0.752773 0.0945331 0.674544 0.728887 0.117108 0.0204575 0.999601 0.019453 0.0725131 0.99733 0.00868224 0.145844 0.980937 -0.128423 0.209719 0.815665 -0.539175 0.290353 0.955269 -0.0561779 0.489707 0.747764 0.448371 0.485863 0.833111 -0.264316 0.549049 0.83549 -0.022385 0.0358128 0.998988 0.0272139 0.0767189 0.994084 0.0768872 0.0678061 0.871369 0.48592 0.087225 0.983033 0.16136 0.285073 0.958448 0.0104893 0.352818 0.903953 0.241636 0.191375 0.981367 -0.0171361 0.178548 0.971293 -0.157197 0.292365 0.953883 0.0680491 0.257795 0.962894 0.0798509 0.171746 0.965054 0.197927 0.198562 0.971048 0.132813 0.229642 0.967974 0.101445 0.774279 0.621085 0.121433 0.68121 0.723114 0.114279 0.63534 0.763879 0.113284 0.315284 0.947753 0.0485753 0.331014 0.941656 0.0609401 0.473364 0.875769 0.0946325 0.539422 0.833053 0.122664 0.560554 0.819687 0.117863 0.60724 0.786359 0.113574 0.643618 0.765044 0.0215118 0.46105 0.88716 0.0194785 0.481645 0.875801 0.0314866 0.538423 0.842135 0.0301518 0.584095 0.811644 -0.00819861 0.642134 0.764308 0.0591349 0.563935 0.825125 0.0338639 0.68408 0.72887 0.0279943 0.728152 0.684782 0.0294731 0.998941 -0.0386976 0.024906 0.575811 0.815749 0.0547307 0.765869 0.637083 0.087006 0.752812 0.652431 0.0872222 0.612769 0.784758 0.0931052 0.0550131 0.997418 0.0461662 0.125081 0.99193 0.0207491 0.138341 0.990363 0.00653996 0.228536 0.972811 0.0375499 0.338434 0.940097 0.0409842 0.300702 0.953609 0.0144155 0.393816 0.918264 0.0412423 0.82193 0.567726 0.0460261 0.848253 0.528685 0.030978 0.682066 0.730943 0.0225203 0.544784 0.838568 0.00374062 0.515494 0.856843 0.00929732 0.500029 0.865966 0.00861139 0.34418 0.938775 0.0155214 0.249481 0.967611 0.0385866 0.16916 0.9754 0.141348 0.217402 0.974563 -0.054429 0.0884881 0.995975 0.0142513 0.0851253 0.996129 0.0219313 0.514832 0.855894 -0.0489288 0.544871 0.838431 -0.0122392 0.325051 0.944686 -0.0437124 0.24284 0.966684 -0.0809341 0.822468 0.568119 0.0280388 0.559724 0.828626 -0.00935579 0.544807 0.838532 -0.00703523 0.264942 0.963549 -0.0371376 0.443168 0.896434 0.00286356 0.973934 0.220035 0.0551106 0.992692 0.115204 0.0359198 0.960209 0.259124 0.104175 0.970982 0.219939 0.0939234 0.968596 0.210317 0.132623 0.955305 0.259885 0.140899 0.965116 0.209338 0.157252 0.960677 0.228266 0.158098 0.964686 0.218674 0.146844 0.966098 0.212513 0.146602 0.965077 0.226627 0.131403 0.970765 0.201161 0.130959 0.968193 0.223549 0.112373 0.974636 0.19346 0.11251 0.970546 0.223409 0.0901598 0.982286 0.181148 0.0479494 0.970105 0.23418 0.0636806 0.822707 0.567776 0.0280086 0.822491 0.567607 0.0364855 0.554464 0.832083 -0.0144307 0.574521 0.81846 -0.00697588 0.96909 0.238306 0.0638282 0.979627 0.179573 0.089911 0.823816 0.565675 0.0365866 0.822944 0.565199 0.0575689 0.878491 0.470268 0.0842741 0.815404 0.573238 0.0807085 0.813583 0.571711 0.105965 0.81156 0.57459 0.105907 0.809313 0.57296 0.129343 0.812815 0.567989 0.129306 0.813172 0.568268 0.125789 0.819513 0.559197 0.125287 0.821867 0.562619 0.0894156 0.823512 0.560306 0.0887981 0.824219 0.563926 0.0514884 0.898801 0.436338 0.0420135 0.856031 -0.512662 0.0662506 0.526569 -0.757014 0.386853 0.499984 -0.728343 0.468543 0.49508 -0.727512 0.474997 0.518679 -0.731274 0.442958 0.686662 -0.634363 0.355076 0.563664 -0.697257 0.442849 0.576891 -0.727985 0.370452 0.561834 -0.723647 0.400847 0.586739 -0.725769 0.359162 0.514118 -0.785543 0.344391 0.387059 -0.904987 0.176592 0.399296 -0.902061 0.163853 0.475139 -0.806216 0.352505 0.475294 -0.829497 0.29331 0.447212 -0.788497 0.422225 0.239153 -0.952935 0.186334 0.23665 -0.953063 0.188858 0.618618 -0.764868 0.179691 0.584084 -0.796343 0.157112 0.655124 -0.696607 0.292494 0.657395 -0.693977 0.293645 0.685214 -0.634795 0.357096 0.660106 -0.69173 0.292866 0.377902 -0.910715 0.166698 0.374189 -0.911988 0.168109 0.512731 -0.842478 0.165342 0.517146 -0.840255 0.162884 0.975753 -0.162222 0.146936 0.968341 -0.235133 0.0838295 0.964348 -0.235056 0.121581 0.964218 -0.236169 0.120449 0.963337 -0.232182 0.134438 0.966868 -0.215874 0.136254 0.97242 -0.202484 0.115757 0.688489 -0.68562 0.236449 0.61809 -0.724059 0.30611 0.447546 -0.817615 0.362226 0.409368 -0.888553 0.207104 0.382876 -0.865912 0.321873 0.236886 -0.955273 0.177026 0.252632 -0.952595 0.169529 0.911537 -0.3983 0.102265 0.804208 -0.584664 0.106855 0.83058 -0.514918 0.212124 0.833037 -0.510401 0.2134 0.839055 -0.480576 0.255015 0.690046 -0.631169 0.354205 0.686481 -0.634797 0.35465 0.537979 -0.72265 0.433999 0.579122 -0.67926 0.450803 0.817974 -0.568949 0.0849434 0.738998 -0.659975 0.135336 0.640988 -0.752897 0.14927 0.643672 -0.750942 0.147557 0.585903 -0.795313 0.155549 0.732177 -0.666653 0.139607 0.816326 -0.554878 0.16038 0.82681 -0.518254 0.218627 0.824761 -0.522361 0.216584 0.830873 -0.490541 0.262717 0.834871 -0.483605 0.262902 0.834748 -0.484434 0.261762 0.972448 -0.202402 0.115666 0.973119 -0.205312 0.104342 0.964785 -0.248727 0.0855855 0.982873 -0.183669 0.0150209 0.160864 -0.952249 0.259507 0.131907 -0.986205 0.100002 0.235406 -0.967807 0.0890685 0.167312 -0.981556 0.0924923 0.054024 -0.9972 0.0517077 0.298018 -0.890991 0.342521 0.300979 -0.890424 0.341404 0.268816 -0.909777 0.316296 0.265601 -0.912493 0.311148 0.259416 -0.919071 0.296667 0.251254 -0.933976 0.254086 0.263918 -0.92953 0.257531 0.209452 -0.95222 0.222275 0.29473 -0.885663 0.358798 0.296592 -0.910486 0.288182 0.178183 -0.95661 0.23054 0.181212 -0.97802 0.103146 0.0584108 -0.996726 0.0559064 0.301323 -0.889743 0.342874 0.284332 -0.897436 0.33729 0.251781 -0.917776 0.307074 0.210287 -0.929727 0.302303 0.238554 -0.922312 0.304028 0.192646 -0.936957 0.291546 0.226784 -0.928943 0.292634 0.213564 -0.933089 0.289371 0.172689 -0.946601 0.272259 0.158683 -0.961642 0.223752 0.164746 -0.953158 0.25367 0.164452 -0.957549 0.236762 0.0374079 -0.987093 0.155719 0.0501677 -0.981956 0.182336 0.0738964 -0.978094 0.194605 0.122098 -0.966355 0.226386 0.0149075 -0.999787 0.0142684 0.101693 -0.99078 0.0895144 0.224865 -0.934001 0.277631 0.184855 -0.95092 0.248153 0.194621 -0.958609 0.207828 0.147657 -0.97504 0.165813 0.101871 -0.991492 0.08103 0.182138 -0.967696 0.174329 0.181586 -0.967834 0.174138 0.336222 -0.880916 0.33308 0.475063 -0.789725 0.388135 0.217122 -0.841234 0.495159 0.00234611 -0.999436 0.0334897 0.00149034 -0.999749 0.022335 0.00220493 -0.999453 0.0330101 0.000866159 -0.999514 0.0311692 0.00581036 -0.999649 0.0258453 -0.00156963 -0.99957 0.0292678 0.0020284 -0.999772 0.0212486 6.37475e-05 -0.999675 0.0255113 0.00407728 -0.999712 0.0236496 0.00174767 -0.99992 -0.0125093 -0.00393944 -0.999986 -0.00344272 -0.00209861 -0.999982 -0.00562847 0.000528599 -0.999988 -0.00485404 -0.0015879 -0.999935 -0.0112927 0.00405933 -0.999786 -0.0202944 0.00216787 -0.999835 -0.0180512 -0.000333971 -0.999822 -0.0188567 0.00112317 -0.999862 0.0165792 -0.000533336 -0.999908 0.0135197 0.00235655 -0.999903 0.0137468 -0.00226709 -0.999973 0.00694062 0.00102577 -0.999974 0.0071995 -0.00101378 -0.999994 0.00341915 0.00796531 -0.998865 0.04695 0.00800509 -0.998851 0.0472477 0.00797307 -0.99885 0.0472862 0.00844772 -0.998835 0.0475081 0.00866604 -0.998822 0.0477413 0.0083037 -0.998818 0.0479013 0.00427374 -0.999106 0.042051 0.00567197 -0.999018 0.0439343 0.0045059 -0.999052 0.0432958 0.00677249 -0.998924 0.0458771 0.00641339 -0.998936 0.0456806 0.00793065 -0.998853 0.0472291 0.00787985 -0.99886 0.0470823 -0.00556846 -0.998703 -0.050601 0.00631396 -0.998531 -0.053809 -0.00029315 -0.998294 -0.0583927 0.00570513 -0.998232 -0.0591663 0.000792272 -0.998316 -0.0580019 0.000506107 -0.998312 -0.0580739 0.000800227 -0.998958 -0.0456403 -0.00631888 -0.999003 -0.0441834 -0.000552097 -0.998945 -0.0459129 -0.000150629 -0.998947 -0.0458726 0.0558231 -0.995984 0.069993 -0.713566 -0.0591778 0.698084 -0.675933 -0.0463856 0.735502 -0.712453 -0.0906348 0.695842 -0.694501 -0.120627 0.709308 -0.707739 -0.129768 0.694453 -0.684825 -0.174834 0.707423 -0.6892 -0.209138 0.693733 -0.675105 -0.243625 0.696333 -0.670136 -0.261638 0.694596 -0.636048 -0.351213 0.68709 -0.654999 -0.376368 0.655228 -0.606737 -0.459737 0.64847 -0.587256 -0.505258 0.632334 -0.53488 -0.565507 0.627778 -0.553345 -0.640128 0.532959 -0.485736 -0.698599 0.525376 -0.348987 -0.815132 0.46235 -0.340865 -0.779725 0.525204 -0.317409 -0.847726 0.424984 -0.265295 -0.881249 0.391176 -0.242826 -0.899213 0.363939 -0.137101 -0.922697 0.360325 -0.137116 -0.919652 0.368022 -0.111142 -0.962995 0.245537 -0.0369309 -0.973336 0.226394 -0.0112557 -0.984748 0.173622 0.0699399 -0.989765 0.124393 0.0645522 -0.992184 0.106788 0.0663802 -0.993867 0.0884397 0.0639273 -0.994181 0.0867061 0.0608502 -0.994899 0.0804557 0.0563827 -0.995366 0.077895 0.0576457 -0.995379 0.0768001 0.0525829 -0.995987 0.0724276 0.055824 -0.995984 0.0699949 0.062111 -0.994926 0.0791432 0.0212612 -0.999505 -0.0232076 0.0471576 -0.996327 0.0714761 0.385106 -0.912306 -0.139253 0.226829 -0.970074 -0.0866379 0.291909 -0.954933 -0.0537704 0.137428 -0.990483 0.00757706 0.483826 -0.837038 -0.255499 0.514209 -0.857589 0.0113837 0.476427 -0.732203 -0.48672 0.552618 -0.809818 -0.196996 0.634017 -0.70492 -0.317978 0.722621 -0.596989 -0.348457 0.713686 -0.573345 -0.402403 0.786782 -0.457513 -0.414313 0.795406 -0.425278 -0.431819 0.852253 -0.286994 -0.437377 0.837784 -0.301906 -0.454941 0.862435 -0.155138 -0.481806 0.863362 -0.162305 -0.477769 0.863879 -0.103848 -0.492877 0.912712 -0.122029 -0.389955 0.845685 -0.0599151 -0.530308 0.871356 -0.0402806 -0.488994 0.870763 0.0545975 -0.488662 0.836722 0.0395165 -0.5462 0.892825 0.10075 -0.43899 0.867124 0.117276 -0.484089 0.863777 0.147231 -0.481884 0.861381 0.154085 -0.484025 0.851114 0.271405 -0.449382 0.856005 0.281919 -0.433333 0.808484 0.391023 -0.439834 0.79297 0.440608 -0.420788 0.688541 0.587872 -0.424638 0.771033 0.533015 -0.34843 0.660644 0.672039 -0.334535 0.63111 0.713173 -0.305097 0.536284 0.790494 -0.295835 0.537693 0.817803 -0.205147 0.441968 0.877756 -0.184958 0.399345 0.904209 -0.151424 0.290659 0.947485 -0.133374 0.286665 0.9572 -0.0399003 0.110818 0.99384 -0.000689254 0.0904389 0.993279 0.0722382 0.0468762 0.99635 0.0713414 0.046806 0.996577 0.0681438 0.0543482 0.996017 0.0706886 0.0460958 0.997284 0.0574516 0.0569205 0.995324 0.0780355 0.0567574 0.995309 0.0783445 0.0606415 0.99493 0.0802286 0.0633173 0.994208 0.0868388 -0.052626 0.972844 0.225401 0.0286541 0.989862 0.139112 0.0262691 0.992583 0.118697 0.0701073 0.993184 0.0931115 -0.0428069 0.974256 0.221346 -0.0938874 0.962502 0.254509 -0.104152 0.952867 0.284951 -0.229459 0.911478 0.341404 -0.221979 0.8974 0.381311 -0.328391 0.842614 0.426803 -0.658538 0.293641 0.692894 -0.661925 0.345004 0.665453 -0.669318 0.37831 0.639449 -0.576014 0.45385 0.679874 -0.583777 0.549721 0.597504 -0.55454 0.582481 0.594307 -0.475764 0.694869 0.539265 -0.478691 0.693335 0.538648 -0.382293 0.801964 0.459027 -0.381871 0.802197 0.458971 -0.336893 0.834542 0.435938 -0.695316 0.182239 0.695215 -0.617286 0.240635 0.749035 -0.732366 0.124446 0.669443 -0.674153 0.146133 0.723991 -0.705176 0.112581 0.700037 -0.706188 0.0669371 0.704853 -0.723288 0.0615734 0.687796 -0.714608 0.0243029 0.699103 -0.615966 2.35591e-06 -0.787773 -0.615961 2.86327e-07 -0.787777 -0.615949 -3.54568e-07 -0.787786 -0.615949 -2.47324e-07 -0.787786 -0.61596 6.45031e-07 -0.787778 -0.615956 1.90944e-06 -0.787781 -0.615954 -1.03391e-06 -0.787782 -0.615955 -2.68876e-07 -0.787782 -0.615955 2.01845e-06 -0.787782 -0.615954 -2.92979e-06 -0.787783 -0.615943 -1.64831e-06 -0.787791 -0.615949 2.16825e-05 -0.787786 -0.615949 -2.72693e-05 -0.787786 -0.615968 2.13653e-06 -0.787771 -0.615969 1.84156e-06 -0.78777 -0.615973 3.1715e-06 -0.787768 -0.615964 6.74327e-06 -0.787775 -0.61595 -2.48761e-06 -0.787786 -0.615949 -2.28065e-06 -0.787786 -0.615949 -2.21341e-06 -0.787786 -0.615955 1.04723e-05 -0.787781 -0.61594 -1.09834e-05 -0.787793 -0.615954 4.1601e-07 -0.787782 -0.615954 2.90686e-07 -0.787782 -0.615953 -9.47267e-06 -0.787783 -0.615954 -1.99852e-05 -0.787782 -0.615947 -5.21581e-06 -0.787788 -0.61594 -2.35923e-05 -0.787793 -0.615941 -1.57328e-05 -0.787793 -0.615945 -4.53683e-06 -0.787789 -0.61595 -4.22323e-06 -0.787786 -0.615951 1.98933e-06 -0.787785 -0.615951 -1.58648e-05 -0.787784 -0.615953 -4.86889e-08 -0.787783 -0.615952 -8.48929e-07 -0.787784 -0.61595 -3.34938e-05 -0.787785 -0.615952 -4.07445e-05 -0.787784 -0.615953 8.66788e-06 -0.787783 -0.615953 8.77576e-06 -0.787783 -0.615955 -8.04803e-06 -0.787781 -0.615955 -6.99954e-06 -0.787781 -0.615955 2.62621e-06 -0.787781 -0.615954 6.27607e-06 -0.787782 -0.615958 -1.77654e-06 -0.787779 -0.615945 5.70102e-07 -0.787789 -0.615946 -9.07973e-06 -0.787789 -0.615953 3.34683e-05 -0.787783 -0.615955 6.17855e-06 -0.787781 -0.615948 1.03078e-05 -0.787787 -0.615944 -4.72039e-05 -0.78779 -0.615954 -1.20992e-05 -0.787782 -0.615955 2.23294e-06 -0.787782 -0.615957 -1.68969e-07 -0.78778 -0.615955 -7.63054e-06 -0.787781 -0.615946 1.17758e-05 -0.787788 -0.615956 7.90908e-06 -0.787781 -0.615956 7.628e-06 -0.787781 -0.615954 5.78143e-06 -0.787782 -0.615955 1.83592e-06 -0.787782 -0.615954 -7.60121e-06 -0.787782 -0.615953 -9.90827e-07 -0.787783 -0.615955 -4.75551e-07 -0.787782 -0.615954 5.14846e-06 -0.787782 -0.615954 2.75507e-06 -0.787782 -0.615954 -3.15004e-06 -0.787782 -0.615955 -2.56495e-06 -0.787782 -0.615953 1.13751e-05 -0.787783 -0.615948 1.96356e-05 -0.787787 -0.615958 -1.60367e-05 -0.787779 -0.615954 -1.43104e-05 -0.787782 -0.615954 1.07605e-05 -0.787782 -0.615959 7.65132e-06 -0.787779 -0.615958 1.24785e-05 -0.787779 -0.615957 1.33329e-05 -0.78778 -0.615951 -9.45516e-06 -0.787785 -0.615952 -1.13329e-05 -0.787784 -0.615952 -1.68279e-05 -0.787784 -0.615947 -1.04825e-05 -0.787787 -0.615964 1.70762e-05 -0.787774 -0.615964 1.77703e-05 -0.787774 -0.615955 -1.38742e-05 -0.787781 -0.61595 -3.7267e-06 -0.787785 -0.61596 4.09683e-06 -0.787778 -0.61596 4.40887e-06 -0.787778 -0.615957 -1.20995e-05 -0.787779 -0.615955 1.98403e-06 -0.787781 -0.615949 9.39775e-06 -0.787786 -0.615952 1.58575e-06 -0.787784 -0.615948 6.05353e-06 -0.787787 -0.615955 -5.20395e-06 -0.787781 -0.615958 0 -0.787779 -0.615963 -4.57389e-06 -0.787775 -0.61597 -9.19421e-06 -0.787769 -0.615949 8.46102e-06 -0.787786 -0.615947 2.44009e-06 -0.787787 -0.615939 6.20406e-06 -0.787794 -0.61597 2.0141e-06 -0.787769 -0.615947 8.78517e-06 -0.787788 -0.615948 -3.02811e-06 -0.787787 -0.61594 -3.1997e-06 -0.787793 -0.61595 -4.9489e-07 -0.787785 -0.615962 1.10338e-06 -0.787776 -0.615962 7.60509e-07 -0.787776 -0.615947 6.82843e-07 -0.787787 -0.615949 -3.61116e-07 -0.787786 -0.615963 4.60199e-06 -0.787775 -0.615963 2.66348e-06 -0.787775 -0.615955 4.1685e-07 -0.787782 -0.615955 8.36233e-08 -0.787782 -0.615951 -8.59377e-07 -0.787785 -0.615959 4.68e-06 -0.787778 -0.997812 0.0174038 -0.063784 -0.997815 0.0173738 -0.0637369 -0.994259 0.0174038 0.105579 -0.994254 0.017374 0.105626 -0.962165 0.017404 0.271911 -0.962153 0.0173739 0.271957 -0.997643 0.0174072 -0.0663793 -0.997838 0.0158087 -0.0637857 -0.994868 0.0189575 0.0993933 -0.994295 0.0151867 0.105583 -0.963113 0.0196934 0.268374 -0.962166 0.0173738 0.271911 -0.960179 0.271984 -0.0638866 -0.960179 0.271983 -0.0638861 -0.700567 0.712063 -0.0466126 -0.700567 0.712062 -0.0466124 -0.256253 0.966459 -0.0170499 -0.256253 0.96646 -0.01705 -0.927021 0.271853 0.258317 -0.927022 0.271851 0.258317 -0.67653 0.711877 0.188517 -0.676529 0.711877 0.188517 -0.247516 0.966426 0.0689711 -0.247517 0.966426 0.068971 -0.957544 0.271953 0.0956644 -0.957543 0.271954 0.0956649 -0.698682 0.712019 0.0698029 -0.698682 0.712019 0.0698027 -0.255577 0.966451 0.0255337 -0.255577 0.966451 0.0255338 -0.901437 0.268489 0.339595 -0.900367 0.272839 0.338967 -0.779072 0.553965 0.293547 -0.656656 0.713249 0.24511 -0.00145209 0.999999 0.000547041 -0.239601 0.966675 0.0901749 -0.243864 0.965431 0.0920483 -0.619795 0.749267 0.233351 0.931926 0.362021 0.0213065 0.913531 0.406767 0.00134986 0.858152 0.513297 0.0101235 -0.988318 0.017469 -0.151402 -0.988588 0.0174512 -0.149629 -0.988577 0.0173931 -0.149712 -0.988565 0.0174512 -0.149785 0.0815551 0.996666 0.0024597 0.255258 0.966443 0.0288485 0.248403 0.968179 0.0304283 0.386046 0.922386 0.0131312 0.798468 0.601457 0.0264257 0.692942 0.719926 0.0392215 0.700024 0.713126 0.0376453 0.558456 0.829357 0.0171638 0.482182 0.875938 0.015264 0.901724 0.431338 0.0290182 0.961001 0.272788 0.0454368 0.983085 0.180254 0.0324351 0.913533 0.406764 0.000264631 0.959412 0.281967 -0.00495843 0.999226 0.0393361 -0.000496899 0.962058 0.272836 -0.00209758 0.994889 0.0994363 -0.0175849 0.983908 0.178313 -0.0113755 0.256008 0.966674 -0.000946459 0.141546 0.989734 -0.0197836 0.857535 0.512603 -0.0432683 0.766488 0.642259 0.000222033 0.603845 0.796919 -0.0170686 0.70091 0.713247 -0.00179126 0.468224 0.883609 -0.00102361 0.327987 0.944675 -0.00360715 0.96206 0.272827 0.00249962 0.962078 0.272763 0.00250258 0.700922 0.713235 0.00182326 0.701015 0.713145 0.00182914 0.256018 0.966672 0.000668024 0.256079 0.966656 0.000670939 -0.253124 0.966675 -0.0383119 -0.253126 0.966675 -0.0383116 -0.693013 0.713253 -0.104892 -0.693017 0.71325 -0.104892 -0.951226 0.272839 -0.143972 -0.951223 0.272849 -0.143975 -0.959855 0.272029 -0.0683954 -0.975895 0.158994 -0.149499 -0.540416 0.837179 -0.0841545 -0.658838 0.747967 -0.0804812 -0.732445 0.679108 -0.0483486 -0.697737 0.712813 -0.0711399 -0.817195 0.562717 -0.124666 -0.901344 0.40987 -0.13995 -0.153468 0.987869 -0.0237182 -0.256524 0.966412 -0.0156227 -0.282481 0.958976 -0.0238729 -0.390735 0.918631 -0.0586684 0.998018 0.0179194 0.0603246 0.998947 0.0173796 0.042465 0.998947 0.0173814 0.0424614 0.997997 0.017923 0.0606735 0.998008 0.0178608 0.0604989 0.998344 0.0177607 0.0547203 0.99851 0.0171536 0.0518111 0.998659 0.0177161 0.0486451 0.998818 0.0175578 0.0453166 0.998979 0.0176065 0.0416002 0.605292 0.780743 0.15512 0.499985 0.728344 0.468539 0.726305 0.485776 0.486315 0.459673 0.76498 0.451116 0.517917 0.747759 0.415475 0.499417 0.767606 0.4017 0.475139 0.806216 0.352505 0.361609 0.874286 0.323824 0.473918 0.788334 0.392341 0.514117 0.785543 0.344392 0.656559 0.695514 0.291875 0.567153 0.692401 0.446002 0.495077 0.727512 0.475 0.537978 0.722651 0.433999 0.689409 0.632651 0.352799 0.686983 0.633591 0.355832 0.382878 0.865911 0.321873 0.409369 0.888552 0.207106 0.458206 0.785075 0.416778 0.911537 0.398299 0.102265 0.982873 0.183669 0.0150209 0.946193 0.293829 0.135583 0.832648 0.511981 0.211124 0.839457 0.478027 0.25846 0.834432 0.486526 0.258875 0.834526 0.485907 0.25973 0.6871 0.63331 0.356107 0.58574 0.727572 0.357138 0.564718 0.72102 0.401526 0.969022 0.230944 0.0875294 0.975753 0.162221 0.146936 0.856031 0.512662 0.066251 0.96458 0.22499 0.137712 0.963969 0.236376 0.122028 0.826397 0.520074 0.215849 0.816326 0.554878 0.16038 0.732179 0.666651 0.139608 0.230872 0.957819 0.171116 0.258854 0.949803 0.175695 0.373275 0.912547 0.167106 0.379171 0.909933 0.16808 0.518853 0.838766 0.165117 0.511258 0.843742 0.163444 0.585902 0.795314 0.155548 0.640273 0.753743 0.148063 0.644435 0.750032 0.148851 0.738996 0.659976 0.135337 0.541013 0.771808 0.334092 0.618091 0.724058 0.306111 0.65068 0.70775 0.275147 0.706919 0.651562 0.275197 0.831042 0.513145 0.214598 0.800988 0.590819 0.096702 0.824171 0.556247 0.106446 0.234716 0.953965 0.186705 0.241164 0.951989 0.188566 0.40757 0.896347 0.174498 0.374992 0.912838 0.161579 0.596426 0.782561 0.178535 0.65589 0.695182 0.29416 0.825228 0.520387 0.219537 0.831153 0.488598 0.265436 0.971103 0.20579 0.12087 0.972494 0.202233 0.115578 0.972466 0.202498 0.115343 0.97414 0.211794 0.0787104 -0.741834 0.669388 -0.0400251 -0.979854 0.142166 -0.140267 -0.393321 0.919113 -0.0230001 -0.342895 0.939356 -0.00573486 -0.248547 0.968557 0.0110822 -0.0902741 0.995204 0.0376797 -0.578153 0.815921 0.0034639 -0.312746 0.947701 0.0636633 -0.297982 0.952771 0.0586074 -0.209347 0.974808 0.0769605 0.0167919 0.997061 0.0747466 -0.460139 0.886666 0.0457755 -0.401284 0.913165 0.0714146 -0.291365 0.95173 0.0965238 -0.986365 0.0627393 -0.152143 -0.97854 0.14268 -0.14867 -0.979333 0.141932 -0.144088 -0.896785 0.43167 -0.0971502 -0.799644 0.596568 -0.0683807 -0.768083 0.637248 -0.0629639 -0.734141 0.677004 -0.0519925 -0.501375 0.865227 0.00254797 -0.6423 0.764663 -0.0523533 -0.493391 0.869518 -0.0224609 -0.979407 0.141243 -0.144262 -0.909352 0.402682 -0.104532 -0.910854 0.394386 -0.121674 -0.100137 0.983738 0.149102 -0.0681826 0.986618 0.148109 -0.0175641 0.979672 0.199836 0.076054 0.977204 0.198212 -0.385071 0.918374 0.0911603 -0.318842 0.943364 0.0916779 -0.756172 0.653256 -0.038211 -0.70502 0.708522 -0.0307007 -0.878861 0.468012 -0.0925597 -0.954525 0.269959 -0.126507 0.146589 0.968899 0.199365 0.0443949 0.984944 0.167074 -0.252315 0.961924 0.105069 -0.33484 0.939353 0.0741513 -0.570134 0.82142 0.0147195 -0.710777 0.702145 -0.0422942 -0.762461 0.645127 -0.0496422 -0.906204 0.410302 -0.102209 -0.906307 0.409858 -0.103075 -0.977432 0.162149 -0.135402 0.996556 0.0175366 0.0810486 0.986695 0.0271078 0.160307 0.986677 0.027089 0.160422 0.98592 0.0346383 0.163592 0.985919 0.0346335 0.163601 0.996415 0.0174947 0.0827753 0.996513 0.0151458 0.0820554 0.993254 0.0192086 0.114357 0.993862 0.0119761 0.109973 0.99215 0.0164142 0.123976 0.997876 0.0339392 0.0556114 0.998217 0.0275069 0.0529777 0.994518 0.0197908 0.102672 0.994302 0.0211885 0.104473 0.990993 0.0220499 0.132086 0.990591 0.0270599 0.134155 0.987663 0.0268636 0.154274 0.98552 0.0402181 0.164719 0.988875 0.0275864 0.14617 0.987848 0.0433351 0.149259 0.990523 0.0164738 0.136356 -0.997812 -0.0174038 -0.063784 -0.99767 -0.015755 -0.0663811 -0.994228 -0.0190678 0.105576 -0.994934 -0.0150089 0.0994 -0.962122 -0.0197872 0.271899 -0.963155 -0.0173676 0.268386 -0.997815 -0.0174038 -0.0637369 -0.997813 -0.0173737 -0.063784 -0.994254 -0.0174038 0.105626 -0.994259 -0.0173739 0.105579 -0.962152 -0.0174039 0.271956 -0.962166 -0.0173738 0.271911 -0.256253 -0.966459 -0.01705 -0.256253 -0.966459 -0.0170498 -0.700567 -0.712062 -0.0466124 -0.700568 -0.712062 -0.0466127 -0.960179 -0.271984 -0.063886 -0.960179 -0.271983 -0.0638866 -0.247516 -0.966426 0.068971 -0.247517 -0.966426 0.0689711 -0.676531 -0.711876 0.188517 -0.67653 -0.711877 0.188517 -0.927021 -0.271853 0.258316 -0.927022 -0.271852 0.258317 -0.255577 -0.966451 0.0255338 -0.255577 -0.966451 0.0255337 -0.698682 -0.712018 0.0698027 -0.698683 -0.712018 0.069803 -0.957544 -0.271953 0.0956649 -0.957543 -0.271955 0.0956644 -0.988318 -0.017469 -0.151402 -0.988589 -0.0173894 -0.149629 -0.988565 -0.0174512 -0.149785 -0.988565 -0.0174512 -0.149785 -0.153468 -0.987869 -0.0237182 -0.658838 -0.747967 -0.0804812 -0.540416 -0.837179 -0.0841545 -0.253553 -0.96667 -0.0354954 -0.345104 -0.938529 -0.00813744 -0.273387 -0.961798 -0.0142594 -0.951223 -0.272849 -0.143972 -0.950963 -0.272849 -0.145679 -0.982324 -0.185581 -0.0244835 -0.901344 -0.409869 -0.13995 -0.693296 -0.713251 -0.103027 -0.779567 -0.626148 -0.0146645 -0.732445 -0.679108 -0.0483486 -0.951226 -0.272839 -0.143975 -0.693013 -0.713253 -0.104891 -0.693017 -0.713249 -0.104893 -0.253124 -0.966675 -0.0383113 -0.253126 -0.966675 -0.0383122 0.998948 -0.01738 0.0424403 0.998181 -0.0177953 0.0575943 0.998341 -0.0178665 0.0547306 0.998537 -0.0172756 0.0512338 0.998658 -0.0177215 0.0486554 0.998816 -0.0175514 0.0453737 0.998962 -0.0175954 0.0420118 0.998985 -0.0173993 0.0415596 0.997998 -0.0179141 0.0606564 0.997998 -0.0179133 0.0606511 0.997997 -0.0179229 0.0606783 -0.358807 -0.933125 -0.0231163 -0.384629 -0.922975 -0.0133568 -0.248759 -0.968502 0.0110457 -0.0902741 -0.995204 0.0376797 -0.97854 -0.14268 -0.14867 -0.986365 -0.0627389 -0.152143 -0.910854 -0.394387 -0.121673 -0.954525 -0.269959 -0.126507 -0.977167 -0.161575 -0.137982 -0.980154 -0.142806 -0.137493 -0.897141 -0.4303 -0.0999037 -0.905973 -0.411286 -0.100284 -0.799644 -0.596568 -0.068381 -0.736796 -0.673643 -0.0577607 -0.767206 -0.638508 -0.0608507 -0.501375 -0.865227 0.00254798 -0.6423 -0.764663 -0.0523533 -0.493391 -0.869518 -0.022461 -0.291374 -0.951727 0.0965215 -0.109354 -0.9842 0.139253 -0.0577198 -0.985607 0.158894 -0.449925 -0.89108 0.0595264 -0.411881 -0.909371 0.0583001 -0.741835 -0.669387 -0.0400253 -0.87886 -0.468015 -0.0925592 -0.736776 -0.674913 -0.0406506 -0.698073 -0.715823 -0.017078 -0.401559 -0.913071 0.0710771 -0.297222 -0.947862 0.114966 -0.0422205 -0.983701 0.174782 0.103751 -0.968762 0.225245 0.0607423 -0.9812 0.183184 0.128327 -0.974898 0.181952 -0.32196 -0.942628 0.088282 -0.268249 -0.959226 0.0890355 -0.702065 -0.711679 -0.0248571 -0.979419 -0.141266 -0.144164 -0.979319 -0.141946 -0.144172 -0.90633 -0.409757 -0.103274 -0.909259 -0.403134 -0.10359 -0.762462 -0.645125 -0.0496426 -0.599529 -0.799882 -0.0274663 -0.578153 -0.815921 0.0034639 -0.288254 -0.955091 0.0686363 -0.322667 -0.94501 0.0533056 0.0728833 -0.988983 0.12884 -0.124499 -0.99101 0.048983 -0.987844 -0.0175448 -0.154458 -0.98784 -0.0178765 -0.154444 -0.987841 -0.0173911 -0.15449 -0.987218 -0.0175583 -0.158403 -0.987619 -0.0183052 -0.155802 -0.987496 -0.0188496 -0.156513 -0.987994 -0.0163795 -0.153619 -0.98742 -0.0176805 -0.157129 -0.98625 -0.0176425 -0.164315 -0.986524 -0.0183298 -0.162589 -0.986814 -0.0175933 -0.160902 -0.987133 -0.0175374 -0.158937 -0.922688 -0.034099 0.384036 -0.915519 -0.0738285 0.395443 -0.946463 0.00886791 0.322691 -0.951954 -0.00675295 0.306167 -0.958282 -0.00742616 0.285727 -0.966797 -0.00852769 0.255403 -0.967357 -0.00472176 0.253373 -0.983355 -0.00873323 0.181487 -0.980704 -0.0364319 0.192074 -0.991204 0.0032488 0.132304 -0.999308 -0.0343339 -0.0143385 -0.999637 -0.0258072 0.00769018 -0.998493 0.0355447 0.0418148 -0.998696 0.0104485 0.0499781 -0.993479 -0.0340533 0.108815 -0.99803 -0.0254854 -0.057326 -0.99806 -0.0225554 -0.0580235 -0.993189 -0.0400979 -0.109395 -0.993266 -0.0467672 -0.106002 -0.992791 -0.0390952 -0.113304 -0.989493 -0.00666731 -0.144425 -0.989975 -0.0234158 -0.139291 -0.985237 -0.0240449 -0.169497 -0.981185 0.00232101 -0.193054 -0.98173 -0.00886565 -0.190074 -0.978143 -0.0171383 -0.207227 -0.977864 -0.0167708 -0.208567 -0.977368 -0.0218263 -0.210419 -0.978837 -0.0165832 -0.203966 -0.980906 -0.017328 -0.193708 -0.980245 -0.021036 -0.196668 -0.982408 -0.0147031 -0.186169 -0.984188 -0.0218845 -0.175767 -0.984865 -0.0174543 -0.172443 -0.183583 -0.980748 0.0665703 -0.326018 -0.932645 -0.154547 -0.289301 -0.951472 0.104913 -0.27457 -0.956334 0.10018 -0.190523 -0.979107 0.0710599 -0.302172 -0.949373 0.0859219 -0.00504354 -0.999063 0.0429811 -0.011923 -0.999524 0.0284562 -0.00429031 -0.993749 0.111557 -0.0137276 -0.99507 0.0982213 -0.138227 -0.988039 0.0683562 -0.193881 -0.978121 0.0754287 -0.540411 -0.829957 0.138298 -0.248933 -0.96581 0.0724071 -0.287955 -0.9529 0.0951999 -0.372563 -0.922442 0.101482 -0.485193 -0.86352 0.137549 -0.472738 -0.869939 0.140444 -0.530541 -0.836399 0.137706 -0.791875 -0.577589 0.198305 -0.681822 -0.665454 0.303792 -0.666393 -0.68412 0.29648 -0.814367 -0.486026 0.317151 -0.95359 -0.264448 -0.143991 -0.981367 -0.0602846 -0.182442 -0.974351 -0.153652 -0.16441 -0.818954 -0.567647 -0.0842077 -0.75565 -0.650495 -0.076484 -0.881529 -0.458377 -0.113125 -0.19547 -0.977482 0.0795021 -0.160657 -0.983466 0.0835715 -0.333686 -0.941544 0.0463501 -0.290183 -0.956906 0.0111498 -0.206635 -0.978411 0.00368874 -0.272148 -0.962209 0.00948107 -0.23025 -0.972763 0.0267746 -0.182836 -0.981225 0.0613852 -0.16865 -0.980874 -0.0971759 -0.271515 -0.95775 -0.0948398 -0.39432 -0.913791 -0.0974565 -0.21974 -0.974919 -0.0353088 -0.249293 -0.968399 0.00746144 -0.380686 -0.912764 -0.148121 -0.439293 -0.883894 -0.16048 -0.322486 -0.934241 -0.152307 -0.291404 -0.949988 -0.112283 -0.23009 -0.970216 -0.0757607 -0.160307 -0.986964 0.0143027 -0.0406426 -0.998209 -0.0439082 -0.182258 -0.978649 -0.0950163 -0.1891 -0.977951 -0.0886151 -0.565806 -0.801427 -0.193854 -0.565099 -0.801903 -0.193943 -0.566489 -0.800951 -0.193826 -0.407064 -0.897832 -0.167918 -0.352854 -0.922372 -0.157236 -0.247669 -0.958856 -0.138763 -0.229446 -0.96422 -0.132798 -0.102324 -0.988949 -0.107281 -0.0921281 -0.990412 -0.102941 -0.0105294 -0.996361 -0.084579 -0.00717012 -0.996443 -0.0839613 -0.00667033 -0.996458 -0.0838257 -0.60771 -0.774427 -0.175928 -0.434246 -0.88628 -0.161051 -0.410991 -0.897722 -0.158687 -0.571148 -0.798151 -0.191689 -0.545033 -0.819014 -0.179319 -0.466393 -0.867153 -0.174711 -0.550933 -0.815168 -0.178813 -0.462303 -0.870851 -0.167017 -0.34881 -0.925588 -0.14703 -0.226521 -0.96755 -0.111958 -0.337853 -0.926967 -0.163057 -0.0731899 -0.993411 -0.088188 -0.211779 -0.970077 -0.118748 -0.0704936 -0.993586 -0.0884213 -0.0743293 -0.993111 -0.0905898 -0.628263 -0.761579 -0.159007 -0.499567 -0.857413 -0.123592 -0.527207 -0.840583 -0.12439 -0.00391408 -0.999174 -0.0404473 -0.0880067 -0.994808 -0.0511035 -0.306828 -0.947186 -0.0932499 -0.243489 -0.968862 -0.0449454 -0.0661492 -0.996192 -0.0568043 -0.0292022 -0.999271 -0.0245811 -0.0675628 -0.996255 -0.0539554 -0.218698 -0.972098 -0.0848321 -0.398345 -0.888714 -0.226957 -0.0446237 -0.996589 -0.0694159 -0.0880706 -0.994219 -0.0614175 -0.244011 -0.967828 -0.0613741 -0.174264 -0.980891 -0.0865147 -0.409894 -0.910667 -0.0517033 -0.306445 -0.947334 -0.0930056 -0.492084 -0.862881 -0.115283 -0.471403 -0.8744 -0.114903 -0.548333 -0.827175 -0.122931 -0.525249 -0.842188 -0.12179 -0.54444 -0.829626 -0.123716 -0.556899 -0.821162 -0.124724 -0.677587 -0.727222 -0.109653 -0.623173 -0.778132 -0.0785188 -0.705009 -0.705112 -0.0760226 -0.658633 -0.750702 -0.0514735 -0.448173 -0.893738 -0.0193137 -0.396838 -0.917426 -0.0291364 -0.49222 -0.870115 -0.0248796 -0.336846 -0.94155 -0.00431714 -0.210669 -0.97738 -0.0186168 -0.160266 -0.985607 -0.0537932 -0.204515 -0.977375 0.0539605 -0.0714815 -0.996613 -0.040649 -0.0885449 -0.995152 0.042815 -0.0346213 -0.9994 0.000774709 -0.0593391 -0.998143 -0.0137369 -0.00466718 -0.999975 -0.00534706 -0.0511458 -0.998691 6.8995e-05 -0.124034 -0.99209 -0.0193328 -0.174955 -0.984529 -0.00961661 -0.20258 -0.979049 -0.0205946 -0.286693 -0.957768 -0.022067 -0.272167 -0.962132 -0.0150726 -0.312752 -0.949502 -0.0251318 -0.328276 -0.944347 -0.0210434 -0.294651 -0.955038 -0.0328939 -0.559826 -0.828048 0.0305066 -0.666597 -0.745418 -0.000547516 -0.585891 -0.809921 -0.0275577 -0.542376 -0.8397 -0.0270743 -0.56233 -0.82645 -0.0276549 -0.566878 -0.823346 -0.0273785 -0.523771 -0.851408 -0.0277116 -0.555928 -0.82411 0.108571 -0.509249 -0.854802 0.0998905 -0.397929 -0.913964 0.0795156 -0.639126 -0.764543 0.0836197 -0.613912 -0.788641 0.0340229 -0.203564 -0.976836 0.0659805 -0.251638 -0.964797 0.0764476 -0.290298 -0.954432 0.069179 -0.334776 -0.938004 0.0898555 -0.490267 -0.865935 0.0989711 -0.456643 -0.887284 0.064845 -0.524126 -0.845708 0.100346 -0.12454 -0.991425 0.0395821 -0.104317 -0.994231 0.0249519 -0.08412 -0.995007 0.0537208 -0.0188451 -0.999581 0.0219897 -0.0194608 -0.999228 0.0341334 -0.94692 -0.314431 -0.0669 -0.973708 -0.20671 -0.0957319 -0.964926 -0.237292 -0.112293 -0.62411 -0.755365 0.199776 -0.742629 -0.651243 0.156153 -0.749881 -0.653578 0.10254 -0.752537 -0.650574 0.102185 -0.75746 -0.652216 0.0294812 -0.757647 -0.651999 0.0294496 -0.883904 -0.319368 0.341641 -0.85593 -0.389073 0.340595 -0.893111 -0.398404 0.208874 -0.883516 -0.41816 0.21105 -0.899899 -0.422603 0.10765 -0.885446 -0.451305 0.110947 -0.891107 -0.45303 0.0263121 -0.874175 -0.484681 0.0300493 -0.874448 -0.48473 -0.0194181 -0.757752 -0.651636 -0.0343772 -0.607654 -0.793736 -0.0271874 -0.571307 -0.820248 -0.0283162 -0.8043 -0.554387 -0.213909 -0.804794 -0.553594 -0.214103 -0.810678 -0.557733 -0.178146 -0.810892 -0.557391 -0.178242 -0.95962 -0.174294 -0.220795 -0.9538 -0.20821 -0.216598 -0.960264 -0.200811 -0.193826 -0.966907 -0.160087 -0.198653 -0.956661 -0.235782 -0.170903 -0.81741 -0.561667 -0.127949 -0.815436 -0.564746 -0.126984 -0.979194 -0.0688159 0.190904 -0.96051 -0.170841 0.219624 -0.976791 -0.173607 0.125456 -0.982798 -0.145053 0.114312 -0.96534 -0.259127 0.0311722 -0.968616 -0.24686 0.029019 -0.978251 -0.203574 -0.0397735 -0.811731 -0.582661 -0.0399843 -0.808812 -0.580659 -0.0930488 -0.806205 -0.584426 -0.0920853 -0.800022 -0.579707 -0.15461 -0.807732 -0.568428 -0.156396 -0.799621 -0.56238 -0.210557 -0.805692 -0.553093 -0.212011 -0.487684 -0.872988 0.00759822 -0.542093 -0.840242 -0.0113384 -0.541849 -0.838647 -0.055409 -0.546623 -0.835421 -0.0572367 -0.542552 -0.830208 -0.128033 -0.543424 -0.829586 -0.128365 -0.539093 -0.823191 -0.178147 -0.537043 -0.824691 -0.177398 -0.535986 -0.823066 -0.187831 -0.956397 -0.156771 0.24643 -0.947685 -0.155848 0.278577 -0.923373 -0.152808 0.352181 -0.945556 -0.0559335 0.320617 -0.891273 -0.182556 0.415097 -0.915792 -0.0688864 0.395702 -0.375724 -0.912191 -0.163518 -0.535888 -0.823142 -0.187781 -0.557555 -0.807081 -0.194299 -0.802082 -0.55285 -0.225879 -0.803054 -0.551346 -0.226101 -0.952432 -0.205679 -0.224878 -0.958657 -0.190952 -0.210985 -0.936249 -0.285164 -0.205229 -0.977055 -0.144564 -0.156411 -0.960769 -0.234698 -0.147784 -0.964072 -0.236955 -0.120069 0.000233046 -0.999658 -0.0261562 -0.00020154 -0.999205 -0.0398621 -0.000392692 -0.999202 -0.0399305 1.487e-06 -0.999252 -0.0386744 0.000606417 -0.999371 -0.0354485 -0.000371408 -0.999317 -0.0369474 0.000603176 -0.999496 -0.0317494 -0.000359685 -0.999448 -0.0332257 0.000542639 -0.999596 -0.0284122 0.000365252 -0.999588 -0.0286938 0.000120317 -0.999631 -0.0271475 0.979627 -0.179573 0.089911 0.966143 -0.211726 0.147445 0.522889 -0.852159 0.0202926 0.29854 -0.953332 -0.0450772 0.291464 -0.956486 -0.0135336 0.291262 -0.953057 0.0827531 0.713533 -0.700007 0.0293416 0.998941 0.0386982 0.024906 0.893484 -0.446787 0.0454686 0.676033 -0.736369 0.0271973 0.632425 -0.77441 0.0181069 0.639141 -0.768764 0.0223765 0.548787 -0.83531 0.03302 0.564578 -0.824407 0.0400503 0.540975 -0.836307 0.0890936 0.40347 -0.900235 0.163675 0.507089 -0.852326 0.128067 0.583318 -0.804117 0.114611 0.626785 -0.770923 0.113222 0.647039 -0.753951 0.113573 0.698737 -0.706147 0.114555 0.759125 -0.639845 0.119698 0.624783 -0.775587 0.0900668 0.768117 -0.634356 0.0871115 0.686677 -0.723058 0.0752506 0.686369 -0.725068 0.0563317 0.198562 -0.971048 0.132811 0.171746 -0.965054 0.197927 0.242578 -0.966115 0.0881933 0.281677 -0.956893 0.0708072 0.306749 -0.949534 0.0655015 0.28822 -0.955865 0.057023 0.261746 -0.964318 0.0397583 0.179223 -0.983221 0.0339793 0.155423 -0.987659 -0.0193015 0.139249 -0.985031 -0.101602 0.0358123 -0.998988 0.0272133 0.0767189 -0.994084 0.0768871 0.0955579 -0.968146 0.231435 0.211648 -0.861768 -0.461044 0.201825 -0.910036 -0.362079 0.100718 -0.994681 -0.0215874 0.0493344 -0.998691 0.0134864 0.0204575 -0.999601 0.019453 0.554934 -0.827374 0.0866099 0.64333 -0.758173 0.106301 0.639135 -0.761988 0.104311 0.616329 -0.782388 0.0894831 0.584488 -0.809648 0.0533386 0.540926 -0.839695 -0.0480852 0.529335 -0.847814 -0.0318652 0.333449 -0.935874 0.113802 0.55036 -0.832596 0.0623573 0.546618 -0.835111 0.0616366 0.631885 -0.77332 0.0519506 0.392157 -0.919174 0.0364995 0.535664 -0.842269 0.0603884 0.482558 -0.874397 0.05068 0.485124 -0.872935 0.0513804 0.389818 -0.920171 0.0364394 0.615623 -0.785615 0.0617792 0.475667 -0.878245 0.0492559 0.612694 -0.787493 0.0667823 0.672933 -0.73063 0.115503 0.65203 -0.752207 0.095083 0.0416202 -0.998928 -0.0202693 0.143817 -0.987659 -0.0620228 0.156607 -0.986257 0.0526478 0.118719 -0.98904 0.0877773 0.360564 -0.864802 -0.349444 0.206717 -0.977988 0.028427 0.249165 -0.968243 0.0205426 0.279714 -0.959902 0.0186576 0.265331 -0.964078 0.0123733 0.234451 -0.972109 -0.00607287 0.077836 -0.996899 -0.0115837 0.0461861 -0.998216 -0.0378469 0.0615373 -0.9981 -0.00325409 0.007897 -0.999813 -0.0176649 0.13215 -0.991226 0.00262332 0.174708 -0.984618 -0.00220949 0.281712 -0.958241 0.0491227 0.546274 -0.83753 -0.0113099 0.444035 -0.895868 0.0159515 0.511215 -0.859431 0.0060538 0.46564 -0.884974 0.000713433 0.406632 -0.913591 -0.00152781 0.478629 -0.877979 0.00826871 0.552713 -0.833369 0.00217909 0.47875 -0.877947 -0.00293186 0.440452 -0.897748 -0.00716391 0.494618 -0.869083 0.00696669 0.561466 -0.827094 0.0258931 0.503042 -0.864163 0.0130522 0.0110171 -0.998017 -0.0619706 0.0187602 -0.998009 -0.0602166 0.0230738 -0.997982 -0.0591506 0.0265306 -0.997948 -0.0582679 0.0306925 -0.997897 -0.057098 0.0335722 -0.997856 -0.0561804 0.0363359 -0.997815 -0.0551897 0.0379234 -0.997798 -0.0544191 0.0397708 -0.997784 -0.0533436 0.402507 -0.915191 -0.0203346 0.278861 -0.960062 -0.0227435 0.150881 -0.987667 -0.0418284 0.143432 -0.98878 -0.0417413 0.035812 -0.997749 -0.0567016 0.0401921 -0.996241 -0.0767395 0.0390229 -0.996259 -0.0771073 0.0407134 -0.996179 -0.0772634 0.164119 -0.985511 -0.0428067 0.31676 -0.945689 -0.0730495 0.156521 -0.985589 -0.0641468 0.493412 -0.869796 0.000524489 0.551344 -0.83416 -0.0140492 0.556902 -0.83046 -0.0140355 0.57505 -0.818095 -0.00619062 0.553939 -0.831738 -0.0369162 0.545483 -0.836068 -0.058638 0.366729 -0.929841 -0.0300954 0.320568 -0.943816 -0.0802957 0.229526 -0.972294 -0.0442923 0.325051 -0.944686 -0.0437124 0.24284 -0.966684 -0.0809341 0.076509 -0.994567 -0.0705935 0.165673 -0.985748 -0.0292116 0.188771 -0.980273 -0.0585684 0.151672 -0.964926 -0.214275 0.33303 -0.941846 -0.0449168 0.544822 -0.838362 -0.0178565 0.544871 -0.838431 -0.0122392 0.514831 -0.855894 -0.0489305 0.0851272 -0.996129 0.0219313 0.0869079 -0.996056 0.0178667 0.088804 -0.99595 0.0140857 0.217402 -0.974564 -0.0544277 0.16916 -0.9754 0.141348 0.249481 -0.967611 0.0385865 0.34418 -0.938775 0.0155214 0.466284 -0.884577 0.0101872 0.42091 -0.907087 -0.00532776 0.561924 -0.827156 -0.00735908 0.55595 -0.831158 -0.00981508 0.592267 -0.80505 -0.0333819 0.625582 -0.779907 0.0197999 0.676043 -0.73679 0.0102898 0.190642 -0.98003 -0.0565426 0.142236 -0.987783 0.0636745 0.340572 -0.939844 0.0265197 0.332017 -0.942604 0.0355463 0.451702 -0.891544 0.0333751 0.461786 -0.886627 0.0254349 0.538738 -0.841829 0.0329558 0.153522 -0.988097 -0.00979945 0.125081 -0.99193 0.0207491 0.0550131 -0.997418 0.0461662 0.966859 -0.253523 0.0301476 0.975397 -0.216922 0.0393274 0.972072 -0.215075 0.093904 0.962586 -0.25787 0.0832559 0.968777 -0.239748 0.0631788 0.969744 -0.235561 0.0640903 0.982286 -0.181148 0.0479494 0.964791 -0.229776 0.12799 0.971183 -0.196626 0.134693 0.967522 -0.228413 0.108302 0.975295 -0.187372 0.117009 0.970546 -0.223409 0.0901598 0.80395 -0.593118 0.0433167 0.824222 -0.564014 0.0504633 0.823488 -0.560233 0.089478 0.821902 -0.562679 0.0887093 0.819417 -0.559071 0.126474 0.813299 -0.568367 0.124514 0.812751 -0.567939 0.129928 0.809383 -0.573011 0.128672 0.811591 -0.574613 0.105548 0.851895 -0.521622 0.0467563 0.822432 -0.568093 0.0296014 0.82247 -0.568121 0.0279649 0.822705 -0.567775 0.0280795 0.822497 -0.567612 0.0362606 0.823809 -0.565672 0.036791 0.822944 -0.565199 0.0575688 0.878491 -0.470268 0.0842741 0.815404 -0.573238 0.0807085 0.813551 -0.571685 0.106354 0.964919 -0.218098 0.146169 0.960677 -0.228266 0.158098 0.965116 -0.209338 0.157252 0.955305 -0.259885 0.140899 0.968596 -0.210317 0.132623 0.970475 -0.217305 0.104676 0.996415 -0.0174947 0.0827753 0.994491 -0.0211317 0.102669 0.990993 -0.0220499 0.132086 0.990591 -0.0270599 0.134155 0.987663 -0.0268636 0.154274 0.985783 -0.038672 0.163511 0.985749 -0.0339716 0.164757 0.986451 -0.0367607 0.159882 0.998742 -0.0340865 0.036771 0.998449 -0.00167707 0.0556434 0.996347 -0.022973 0.0822482 0.994338 -0.0195124 0.104454 0.986164 -0.026565 0.163633 0.986695 -0.0271078 0.160307 0.98822 -0.0274385 0.150559 0.988581 -0.0367932 0.146127 0.990523 -0.0164738 0.136356 0.99215 -0.0164142 0.123976 0.993278 -0.0135549 0.114956 0.993761 -0.0186561 0.109962 0.996513 -0.0151458 0.0820554 0.996556 -0.0175366 0.0810486 -0.989726 0 -0.142979 -0.990711 -0.00958061 -0.135648 -0.99258 -1.52222e-08 -0.121595 -0.994631 -1.39031e-07 -0.103487 -0.997343 -0.0187389 -0.070396 -0.996915 -0.00553868 -0.0782885 -0.999158 0 -0.0410281 -0.848816 0 -0.528688 -0.877904 -0.0040593 -0.478819 -0.945873 3.13748e-07 -0.324537 -0.986929 -3.0481e-07 -0.161154 -0.998912 -0.00532521 -0.0463257 -0.997913 1.06507e-07 0.0645764 -0.972884 -1.94281e-07 0.231295 -0.918454 -0.00381273 0.395509 -0.913311 -0.00289558 0.407253 -0.759702 0.00193747 0.650269 -0.652735 -0.00527187 0.757568 -0.561081 -3.69302e-07 0.827761 -0.4141 -2.72578e-07 0.910232 -0.255366 -0.00399249 0.966836 -0.199139 0 0.979971 0.864648 0 -0.502378 0.885424 0.0135128 -0.464587 0.913968 0.0575006 -0.401691 0.899217 -8.04878e-06 -0.437503 0.942463 1.79934e-06 -0.334311 0.960363 0.0298725 -0.277147 0.96665 0 -0.256099 -0.987601 0 -0.156988 -0.987594 -3.75601e-05 -0.157031 -0.986879 2.94751e-05 -0.161462 -0.986874 0 -0.161494 0.997072 0 0.0764667 0.996766 -0.00644188 0.080101 0.993926 0.00428916 0.109964 0.993553 0 0.113373 0.643136 0 -0.765752 0.643136 0 -0.765752 0.643136 2.0752e-07 -0.765752 0.642887 -0.000187578 -0.765961 0.643136 5.14918e-07 -0.765752 0.643149 -1.5593e-07 -0.765741 0.643136 0 -0.765752 -0.990843 0 -0.135021 -0.990828 -6.66182e-05 -0.135126 -0.989638 5.84312e-05 -0.143585 -0.989625 0 -0.143672 0.986557 0 0.163419 0.986192 -0.0028346 0.165582 0.982891 0.00185275 0.184179 0.982514 0 0.186186 -0.986148 0 -0.16587 -0.986147 -2.15079e-06 -0.165872 -0.98623 -4.64859e-06 -0.165377 -0.986231 0 -0.165374 0.996578 0 -0.082657 0.995541 0.0186333 -0.0924744 0.999469 -0.0101725 -0.030946 0.99982 0.0150669 -0.0115489 0.999969 0 0.00788828 -0.994513 0 -0.104609 -0.99401 0.00243777 -0.109261 -0.993343 0 -0.115192 0.531299 0 -0.847185 0.531299 2.08559e-08 -0.847185 0.531299 0 -0.847185 0.482957 0 0.875644 0.482957 -1.30319e-07 0.875644 0.482957 0 0.875644 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.453062 0 -0.891479 0.453062 0 -0.891479 0.453062 0 -0.891479 -0.997201 0 -0.0747694 -0.99693 0.00153471 -0.0782833 -0.996485 0 -0.0837772 -0.55539 -0.000248458 -0.83159 0.296972 0 -0.954886 0.221872 -0.00411972 -0.975067 0.0550356 4.56743e-09 -0.998484 -0.265936 0.0010613 -0.96399 -0.364591 -0.00735731 -0.931139 -0.113362 -9.52655e-09 -0.993554 -0.671705 -0.00303461 -0.740812 -0.690432 -0.00432768 -0.723385 -0.7975 2.05977e-06 -0.603319 -0.950553 0 -0.310563 -0.972203 -0.00620047 -0.234058 -0.886024 -1.96894e-06 -0.463639 0.451908 0 0.892064 0.451908 -2.49612e-08 0.892064 0.451909 0 0.892064 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.375876 0 0.92667 0.375876 -4.45951e-08 0.92667 0.375876 1.16598e-07 0.92667 0.375875 1.87471e-07 0.92667 0.375879 0 0.926669 -0.998503 0 -0.0546964 -0.99855 3.61985e-05 -0.0538338 -0.998594 0.000107304 -0.05301 -0.99909 0 -0.0426412 -0.998878 0.00163521 -0.0473357 -0.998869 0.00153487 -0.0475266 -0.998707 0.000389786 -0.0508384 0.359686 0 -0.933074 0.359686 0 -0.933073 0.359686 -6.77816e-09 -0.933073 0.359687 4.97393e-07 -0.933073 0.359686 1.2287e-07 -0.933073 0.359686 -1.63677e-07 -0.933074 0.359686 7.56817e-09 -0.933073 0.359687 7.68992e-08 -0.933073 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.375876 0 -0.92667 -0.375876 2.48751e-07 -0.92667 -0.375872 2.0964e-06 -0.926672 -0.375876 -2.06303e-07 -0.92667 -0.375876 9.40047e-07 -0.92667 -0.375882 -3.83158e-06 -0.926668 -0.375876 0 -0.92667 -0.375876 0 -0.92667 -0.375804 7.93719e-05 -0.926699 -0.375879 -3.02821e-06 -0.926669 0.978299 0 0.207197 0.978118 -0.000580013 0.208051 0.977563 0.000177684 0.210641 0.977455 0 0.211146 -0.486793 3.79158e-08 0.873517 -0.486793 -6.46929e-07 0.873517 -0.486792 0 0.873518 -0.486793 0 0.873517 -0.486793 0 0.873517 -0.486793 4.88621e-08 0.873517 -0.486793 0 0.873518 -0.486793 -3.55539e-07 0.873517 -0.486796 3.38806e-06 0.873516 -0.486792 -1.35387e-06 0.873518 -0.486793 -3.6667e-07 0.873517 -0.486793 -1.26548e-07 0.873517 -0.486791 5.60691e-06 0.873519 -0.999818 0 -0.0190775 -0.999818 0 -0.0190775 0.486793 0 -0.873517 0.486793 0 -0.873517 0.486793 -1.18013e-08 -0.873517 0.486793 -3.94824e-08 -0.873518 0.303861 0 0.952716 0.303861 -4.59912e-08 0.952716 0.303861 0 0.952716 0.303861 -8.83332e-08 0.952716 0.303862 2.20136e-07 0.952716 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.381931 0 -0.924191 0.301363 -0.002736 -0.953506 0.137453 -1.09993e-07 -0.990508 -0.0304447 2.43321e-08 -0.999536 -0.141298 -0.00174724 -0.989965 -0.200533 -0.0030132 -0.979682 -0.317412 0.000264707 -0.948288 -0.603387 -0.000337128 -0.797449 -0.651779 -0.00251429 -0.758405 -0.77822 -4.24627e-06 -0.627992 -0.938393 0 -0.345569 -0.965293 -0.00437677 -0.261134 -0.869016 5.19783e-06 -0.494785 -0.997335 0 0.0729524 -0.992158 -0.00158293 0.124981 -0.560214 -0.00171891 0.828346 -0.753113 0.00119338 0.65789 -0.852142 -0.0021283 0.523306 -0.902409 -4.11697e-06 0.430881 -0.9594 2.02078e-06 0.282048 -0.0359763 -0.00423772 0.999344 -0.287848 -1.89093e-05 0.957676 -0.508357 3.28104e-05 0.861146 -0.168416 0.00212244 0.985714 0.2534 -0.00139767 0.967361 0.296116 0 0.955152 -0.999659 0 -0.0261119 -0.980804 -0.00138502 0.194989 -0.972609 0.000443058 0.232449 -0.791731 -0.000397502 0.61087 -0.765437 -0.00201625 0.643508 -0.624332 -1.81509e-05 0.781159 -0.508226 3.11817e-05 0.861224 -0.360588 -0.00272695 0.932721 -0.287023 -0.00034486 0.957924 0.0256223 0.000329069 0.999672 0.133529 -0.00272575 0.991041 0.284692 0 0.958619 -0.99479 0 0.101945 -0.978396 -0.00416785 0.206696 -0.765627 -0.002298 0.643281 -0.776067 -0.00141241 0.630649 -0.931564 0.000741816 0.363576 -0.372257 -0.00383483 0.928122 -0.472883 2.51152e-06 0.881125 -0.6204 -1.12507e-06 0.784286 0.108888 -0.00347544 0.994048 -0.0478168 5.16315e-05 0.998856 -0.246814 -6.51609e-05 0.969063 0.723792 0 0.690018 0.566468 -0.00176972 0.824082 0.564412 -0.00189477 0.825491 0.380918 1.44521e-05 0.924609 0.196986 -5.47722e-05 0.980406 0.480213 0 -0.877152 0.394264 -0.00431071 -0.918987 -0.114981 1.43452e-06 -0.993368 -0.323961 -0.0159248 -0.945937 -0.141119 -0.00396757 -0.989985 0.0797785 -1.98698e-05 -0.996813 0.237187 3.18818e-05 -0.971464 -0.915274 0 -0.402832 -0.978025 -0.0162988 -0.207848 -0.921236 -0.00440563 -0.388979 -0.82161 4.8458e-05 -0.57005 -0.593742 -0.000175148 -0.804656 -0.694028 -0.0103489 -0.719873 -0.492566 -1.18142e-06 -0.870275 -0.752689 0 -0.658376 -0.879529 -0.010189 -0.475736 -0.788641 -7.64159e-06 -0.614854 -0.947158 3.75357e-06 -0.320768 -0.977111 -0.0034624 -0.212701 -0.994764 4.05287e-06 -0.102194 -0.998078 -2.04492e-06 0.0619782 -0.972857 -0.00246951 0.231395 -0.961979 -0.000433585 0.273122 -0.821781 0.000399972 0.569804 -0.776709 -0.00281837 0.629853 -0.667839 0 0.744306 -0.999814 0 -0.0192765 -0.996937 -0.00436357 0.0780879 -0.731356 -4.52822e-06 0.681996 -0.85185 -0.00313464 0.523776 -0.846182 -0.00247918 0.532889 -0.935274 -1.39096e-05 0.353925 -0.975069 3.37059e-05 0.2219 -0.600223 1.05068e-05 0.799833 -0.501167 -0.00418855 0.865341 -0.392438 -5.90634e-05 0.919778 -0.210936 3.58652e-05 0.9775 -0.0410826 -0.00341067 0.99915 0.0404562 0.000438555 0.999181 0.374949 -0.000448216 0.927045 0.428429 -0.00321339 0.90357 0.578455 0 0.815715 0.60899 0 -0.793177 0.559022 -0.00269019 -0.829149 0.418749 1.2785e-05 -0.908102 0.270189 -2.06574e-05 -0.962807 0.148671 -0.00333657 -0.988881 0.0232864 0.00100455 -0.999728 -0.290525 -0.0015512 -0.956866 -0.284591 -0.00188597 -0.958647 -0.925652 0 -0.378376 -0.951771 -0.00513345 -0.306766 -0.860597 3.60482e-05 -0.509287 -0.673368 -0.000101245 -0.739308 -0.767233 -0.00900435 -0.641305 -0.585537 0.00138812 -0.810645 -0.935588 0.00126855 -0.353091 -0.765372 -0.00189937 -0.643585 -0.787206 0 -0.61669 -0.992301 -0.0074639 -0.123621 -0.966704 1.06549e-06 -0.255899 -0.999098 -4.74421e-07 0.0424654 -0.989216 -0.00282091 0.14644 -0.953997 0.00169863 0.299813 -0.8511 -0.00232573 0.524999 -0.818473 0 0.574545 -0.999853 0 -0.0171698 -0.9968 -0.00417617 0.0798209 -0.722634 -4.73869e-06 0.691231 -0.843872 -0.00266661 0.536538 -0.843229 -0.00259807 0.537548 -0.932335 -1.19882e-05 0.361596 -0.974225 2.54202e-05 0.225578 -0.592241 1.04778e-05 0.805761 -0.493105 -0.00410402 0.86996 -0.380996 -3.80095e-05 0.924577 -0.207076 2.11352e-05 0.978325 -0.0280243 -0.00313109 0.999602 0.0287759 -0.000370681 0.999586 0.319129 0.000243128 0.947711 0.443573 -0.00397658 0.896229 0.544969 0 0.838456 0.615778 0 -0.78792 0.570507 -0.00233301 -0.82129 0.447946 -0.000360655 -0.894061 0.330431 0.000457698 -0.94383 0.156898 -0.00270048 -0.987611 0.0652001 0.000784727 -0.997872 -0.287893 -0.00104499 -0.957662 -0.286178 -0.00113561 -0.958176 -0.928811 0 -0.370555 -0.951724 -0.00402049 -0.30693 -0.859345 1.7271e-05 -0.511396 -0.675476 -5.6938e-05 -0.737382 -0.770494 -0.008073 -0.637396 -0.595596 0.000796635 -0.803284 -0.857058 0.00130126 -0.515218 -0.754488 -0.00257348 -0.656309 -0.725775 -0.00137707 -0.687931 -0.641179 0 -0.767391 -0.962707 -0.00246562 -0.270533 -0.955259 -0.00137333 -0.295768 -0.992285 9.37762e-06 -0.12398 -0.999968 -2.36794e-05 -0.00800652 -0.993346 -0.00248574 0.115139 -0.969119 0.00150955 0.246588 -0.86228 0 0.506432 -0.79073 -0.00647293 0.612131 -0.877151 -0.00155649 0.480212 -0.999992 0 0.00388938 -0.996066 -0.00321883 0.0885527 -0.846284 -0.00275893 0.532724 -0.924657 -1.03649e-05 0.380802 -0.971079 1.31656e-05 0.23876 -0.510547 -0.00301461 0.859845 -0.589635 0.000589449 0.80767 -0.818778 -0.000642786 0.57411 0.115226 -1.68045e-07 0.993339 -0.0272003 -0.00200166 0.999628 -0.0626242 -0.00321486 0.998032 -0.204608 1.43235e-05 0.978844 -0.370126 -1.12643e-05 0.928982 0.23969 -3.49561e-07 0.97085 0.399047 -0.00274947 0.916927 0.46057 0 0.887623 0.465953 0 -0.884809 0.0569365 -0.00244132 -0.998375 0.210731 0.00101479 -0.977544 0.505665 -0.00207334 -0.862728 -0.362365 -0.00205389 -0.932034 -0.277218 0.000867625 -0.960807 -0.0202541 -0.000631602 -0.999795 -0.816801 -0.00615967 -0.576887 -0.638918 -1.28365e-05 -0.769275 -0.498597 7.70851e-06 -0.866834 -0.71635 0.00302996 -0.697735 -0.941247 -0.00186187 -0.337713 -0.957478 0 -0.288507 -0.623126 0 -0.782122 -0.679 -0.00260602 -0.734134 -0.792644 4.97267e-07 -0.609684 -0.883671 -9.43624e-07 -0.468108 -0.942867 -0.00294538 -0.333157 -0.975123 0.000662523 -0.221665 -0.808123 0 0.589014 -0.733944 -0.00600255 0.679184 -0.875285 6.04142e-07 0.483608 -0.989492 -1.55639e-06 0.144586 -0.944563 -0.00964488 0.32819 -0.993483 -0.000852775 0.113981 -0.99932 0 0.0368647 -0.995065 -0.00208441 0.0992049 -0.858547 -0.00249165 0.512728 -0.916078 -6.53836e-06 0.401 -0.967233 4.46957e-06 0.253889 -0.559226 -0.000517971 0.829015 -0.538819 -0.00157356 0.84242 -0.785225 0.000960592 0.61921 -0.000597451 -0.00574694 0.999983 -0.198692 -0.00153182 0.980061 -0.298008 1.63828e-07 0.954563 -0.376456 -1.1498e-08 0.926434 -0.153836 0.0028792 0.988092 0.280709 -0.00180206 0.959791 0.329574 0 0.94413 0.623118 0 0.782128 0.6916 -0.00307313 0.722275 0.958886 -0.00281673 0.283777 0.891634 -7.23007e-07 0.452756 0.803081 6.8745e-07 0.59587 0.973289 -0.00320665 -0.22956 0.993481 0.000415792 -0.113999 0.975112 -0.000485601 0.221712 0.552327 0 -0.833628 0.702811 -0.000956056 -0.711376 0.731017 -0.00250571 -0.682355 0.84901 4.77077e-07 -0.528376 0.925914 -7.29403e-07 -0.377735 0.635884 0 0.771784 0.595352 -0.00204981 0.803463 0.827669 0.00109611 0.561215 0.90426 -0.00218827 0.426976 0.947966 -2.74387e-08 0.318373 0.987974 3.12648e-08 0.15462 0.999998 -0.00183447 0.000646888 0.996862 0.000397952 -0.0791594 0.904814 -0.000528579 -0.425806 0.914312 -0.00137617 -0.405008 0.72864 0.000882802 -0.684897 0.636881 -0.00210204 -0.77096 0.530237 0 -0.84785 -0.526126 0 -0.850407 -0.576096 -0.0018244 -0.81738 -0.70515 3.26256e-08 -0.709058 -0.814173 -1.23444e-07 -0.580623 -0.877755 -0.00235209 -0.479104 -0.924567 -1.40542e-07 -0.38102 -0.975426 -2.52488e-08 -0.220326 -0.999099 -0.00158095 -0.0424154 -0.99999 -0.00035289 -0.00444995 -0.94504 0.000310436 0.326955 -0.915201 -0.00200728 0.402993 -0.840487 1.13399e-08 0.541831 -0.737585 1.44119e-07 0.675255 -0.643302 -0.00229955 0.765609 -0.56537 0 0.824837 0.525969 0 0.850504 0.584426 -0.00219741 0.811444 0.712291 8.63581e-07 0.701885 0.819761 -1.17206e-06 0.572705 0.892036 -0.00256848 0.451957 0.94162 0.000726342 0.336677 0.999981 -0.00101002 0.00613871 0.999961 -0.00155667 -0.00870523 0.979007 -1.29491e-07 -0.203828 0.570211 0 -0.821498 0.52169 -0.00261415 -0.853131 0.708589 6.78664e-07 -0.705622 0.884036 -2.88044e-06 -0.46742 0.818002 -0.00567212 -0.575188 0.930585 4.22493e-07 -0.366076 0.130161 0 -0.991493 0.130161 0 -0.991493 -0.337506 0 -0.941323 -0.337506 0 -0.941323 -0.730505 0 -0.682908 -0.730505 0 -0.682908 -0.961897 0 -0.273413 -0.961897 0 -0.273413 -0.978154 0 0.207883 -0.978154 0 0.207883 -0.773412 0 0.633904 -0.773412 0 0.633904 -0.395881 0 0.918302 -0.395881 0 0.918302 0.0700976 0 0.99754 0.0700976 0 0.99754 0.444662 0 0.895699 0.515153 -0.00287447 0.857094 0.639127 2.32301e-06 0.769102 0.749148 -2.32665e-06 0.662403 0.844733 -0.00273989 0.535181 0.876874 -0.00036665 0.48072 0.980468 0.000331249 0.196679 0.995016 -0.00306854 0.0996696 0.999005 1.25202e-05 -0.0445933 0.978483 -1.05105e-05 -0.206326 0.934101 -0.0028915 -0.356996 0.8971 0.000695791 -0.441826 0.674921 0 -0.73789 0.518071 -0.0116092 -0.855259 0.685791 -0.000881635 -0.727798 0.247051 0 -0.969002 0.247051 0 -0.969002 -0.264729 0 -0.964323 -0.264729 0 -0.964323 -0.707165 0 -0.707049 -0.707165 0 -0.707049 -0.964367 0 -0.264569 -0.964367 0 -0.264569 -0.997929 0 -0.0643319 -0.996801 0.0161266 -0.0782796 -0.995594 0.00523773 -0.0936275 -0.992624 -0.00663104 -0.121054 -0.990707 0.00998198 -0.135647 -0.989118 0 -0.147128 -0.199139 0 0.979971 -0.255366 0.00399249 0.966836 -0.4141 2.72416e-07 0.910232 -0.561081 3.69327e-07 0.827761 -0.652735 0.00527187 0.757568 -0.759702 -0.00193747 0.650269 -0.913311 0.00289558 0.407253 -0.918454 0.00381273 0.395509 -0.972884 1.94352e-07 0.231295 -0.877911 0 -0.478823 -0.84893 0.00542162 -0.528478 -0.945873 -3.13683e-07 -0.324537 -0.998926 7.24483e-07 -0.0463264 -0.986969 0.0107698 -0.160552 -0.997913 -1.06565e-07 0.0645764 -0.986879 0 -0.161462 -0.986908 0.000177577 -0.161285 -0.987601 -0.000200719 -0.156988 -0.987639 0 -0.156748 0.643136 0 -0.765752 0.643136 0 -0.765752 0.643135 1.0376e-06 -0.765753 0.643136 0 -0.765752 0.643137 -2.7634e-07 -0.765751 0.642888 -1.31267e-05 -0.76596 0.643149 1.5593e-07 -0.765741 -0.989638 0 -0.143585 -0.989697 0.000294734 -0.143176 -0.990843 -0.000290853 -0.135021 -0.990909 0 -0.134531 -0.98623 0 -0.165377 -0.986222 -6.02677e-05 -0.165426 -0.986148 -2.7791e-05 -0.16587 -0.986152 0 -0.165845 -0.993542 0 -0.113463 -0.99401 -0.00233806 -0.109261 -0.994694 0 -0.102878 0.482957 0 0.875644 0.482957 2.75561e-07 0.875644 0.482957 0 0.875644 0.531299 0 -0.847184 0.531299 -1.25136e-07 -0.847185 0.531298 0 -0.847185 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.453063 0 -0.891479 0.453062 -1.19866e-07 -0.891479 0.453062 0 -0.891479 -0.996672 0 -0.0815161 -0.99693 -0.00147066 -0.0782833 -0.997368 0 -0.0725069 0.451909 0 0.892064 0.451909 1.41447e-07 0.892064 0.451908 0 0.892064 -0.972347 0 -0.233539 -0.950544 0.00421833 -0.31056 -0.55539 0.000248459 -0.83159 -0.671705 0.00303461 -0.740812 -0.690432 0.00432768 -0.723384 -0.7975 -2.05971e-06 -0.603319 -0.886024 1.96894e-06 -0.463639 -0.36456 -0.000640699 -0.93118 -0.265934 0.00444103 -0.963981 -0.113362 9.58666e-09 -0.993554 0.221873 0 -0.975075 0.296988 0.00598764 -0.954862 0.0550356 -4.62499e-09 -0.998484 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.375876 0 0.92667 0.375876 3.61145e-08 0.92667 0.375879 0 0.926669 0.375875 -1.87471e-07 0.92667 0.375876 -1.12711e-07 0.92667 -0.99909 0 -0.0426412 -0.998878 -0.00163521 -0.0473357 -0.998902 -0.0019097 -0.0468136 -0.99884 -0.00135284 -0.0481272 -0.998746 -0.000609057 -0.050061 -0.99862 -0.00015025 -0.0525125 -0.99855 -3.62977e-05 -0.0538326 -0.998503 0 -0.0546976 0.359686 -1.46542e-08 -0.933073 0.359686 2.56961e-07 -0.933073 0.359686 -1.06329e-07 -0.933073 0.359688 2.33227e-07 -0.933073 0.359686 0 -0.933073 0.359686 0 -0.933074 0.359688 -1.2636e-07 -0.933073 0.359685 1.92117e-07 -0.933074 0.359688 -4.71635e-07 -0.933073 0.359686 1.31793e-08 -0.933073 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.375876 0 -0.92667 -0.375876 0 -0.92667 -0.375874 -3.25198e-06 -0.926671 -0.375876 -2.05625e-07 -0.92667 -0.375882 0 -0.926668 -0.375876 5.43632e-08 -0.92667 -0.375876 -2.22818e-07 -0.92667 -0.375874 -1.68855e-06 -0.926671 -0.375804 -7.93719e-05 -0.926699 -0.375877 7.58251e-07 -0.92667 -0.37588 4.39225e-06 -0.926668 -0.486793 0 0.873518 -0.486793 0 0.873517 -0.486793 4.03408e-07 0.873517 -0.486793 6.88451e-07 0.873517 -0.486793 3.0567e-07 0.873517 -0.486792 -1.70796e-06 0.873518 -0.486793 2.54885e-07 0.873517 -0.486792 1.39618e-06 0.873518 -0.486796 -3.38806e-06 0.873516 -0.486788 5.73343e-06 0.87352 -0.486793 -3.97638e-07 0.873517 -0.486793 -1.82404e-07 0.873517 -0.486793 0 0.873518 -0.999818 0 -0.0190775 -0.999818 0 -0.0190775 0.303862 0 0.952716 0.303861 5.74753e-08 0.952716 0.303861 0 0.952716 0.303861 4.76156e-08 0.952716 0.303861 4.45524e-08 0.952716 0.486793 0 -0.873517 0.486793 1.07193e-08 -0.873517 0.486793 3.94824e-08 -0.873518 0.486793 0 -0.873517 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.965543 0 -0.260243 -0.938389 0.00286145 -0.345568 -0.651779 0.00251429 -0.758405 -0.77822 4.24657e-06 -0.627992 -0.869016 -5.19783e-06 -0.494785 -0.0304447 -2.43321e-08 -0.999536 -0.141298 0.00174724 -0.989965 -0.200533 0.0030132 -0.979682 -0.317412 -0.000264707 -0.948288 -0.603387 0.000337128 -0.797449 0.137453 1.09856e-07 -0.990508 0.301363 0.002736 -0.953506 0.381931 0 -0.924191 0.2534 0 0.967362 -0.168416 0.00205925 0.985714 -0.0359646 -0.00103134 0.999353 0.296169 0.00176219 0.955134 -0.560214 0.00171891 0.828346 -0.508357 -3.28104e-05 0.861146 -0.287848 1.89093e-05 0.957676 -0.923515 0.00519539 0.383528 -0.791324 2.7708e-06 0.611397 -0.679647 -1.71408e-06 0.733539 -0.852141 -0.0025956 0.523305 -0.992158 0.00158293 0.124981 -0.997335 0 0.0729524 -0.624206 1.63469e-05 0.78126 0.234579 0 0.972097 0.133529 0.00279277 0.991041 -0.0163762 -3.31156e-05 0.999866 -0.157192 1.22094e-05 0.987568 -0.360589 -7.85192e-05 0.932725 -0.508628 0.00784878 0.860951 -0.320511 0.00121773 0.947244 -0.980805 0 0.194989 -0.988495 0.00240229 0.151232 -0.920642 -3.87383e-06 0.390407 -0.765439 2.06694e-05 0.643509 -0.807734 0.00351324 0.589537 -0.677961 0.000737596 0.735098 0.631118 0 0.775687 0.564411 0.00325755 0.825488 0.422673 -2.73125e-05 0.906282 -0.372259 1.28359e-05 0.928129 -0.496993 0.00893655 0.867709 -0.263188 -0.00061031 0.964744 0.108889 0.000946579 0.994054 0.0539646 0.00409642 0.998534 0.275327 2.34544e-05 0.961351 -0.978405 0 0.206698 -0.997791 0.00985979 0.0656921 -0.954663 0.000294594 0.29769 -0.765629 -0.000514563 0.643282 -0.81822 0.00551812 0.574879 -0.651368 -3.26188e-06 0.758762 -0.95611 0 -0.293007 -0.915262 0.00514968 -0.402827 -0.453032 9.17565e-06 -0.891494 -0.649156 0.00653475 -0.760627 -0.593741 0.00142469 -0.804655 -0.76798 3.63058e-06 -0.640474 -0.848194 -2.27918e-05 -0.529686 -0.291532 -6.5261e-06 -0.956561 -0.11498 0.00410027 -0.993359 -0.025759 -0.000488781 -0.999668 0.338873 0.00051605 -0.940832 0.394265 0.0035988 -0.91899 0.561329 0 -0.827593 -0.998688 -3.73855e-06 -0.0512064 -0.741174 0 0.671313 -0.77671 0.00251728 0.629853 -0.871685 1.44139e-06 0.490067 -0.97286 1.40635e-05 0.231396 -0.992768 0.00696576 0.119845 -0.941717 -3.57441e-06 0.336405 -0.961692 0.00379339 -0.274108 -0.977117 -0.000137173 -0.212703 -0.822327 9.98783e-05 -0.569016 -0.788638 0.00267027 -0.614852 -0.677074 0 -0.735915 0.49876 0 0.86674 0.428429 0.00352101 0.903569 0.275851 -1.73072e-05 0.9612 0.118583 1.69538e-05 0.992944 -0.0410826 0.00359731 0.999149 -0.116489 0.000245103 0.993192 -0.501171 -9.43674e-06 0.865348 -0.621637 0.0102524 0.783238 -0.416983 -0.000232544 0.908914 -0.996946 0 0.0780886 -0.995872 0.0125873 -0.0898883 -0.992631 0.00154628 0.121164 -0.846182 -0.00246894 0.532889 -0.89865 0.00647533 0.438618 -0.750502 3.28112e-06 0.660869 -0.950852 0 -0.309645 -0.925647 0.00329037 -0.378374 -0.858707 -2.7898e-05 -0.512466 -0.777224 2.64498e-05 -0.629224 -0.673364 0.00313444 -0.739304 -0.619147 -8.48954e-05 -0.785275 -0.290525 0.000121053 -0.956867 -0.325189 0.00242821 -0.945646 0.032778 -0.0016207 -0.999461 0.148671 0.00304923 -0.988882 0.290101 1.71141e-05 -0.956996 0.448117 -2.01729e-05 -0.893975 0.559021 0.00327792 -0.829147 0.634571 0 -0.772864 -0.969215 -0.00125859 0.246212 -0.832622 0.00188378 0.553839 -0.851102 0 0.525001 -0.999899 0.00746613 0.012088 -0.98922 -1.56021e-06 0.14644 -0.987911 6.06985e-07 -0.155025 -0.9667 0.00282245 -0.255898 -0.913641 -0.00170376 -0.406518 -0.787204 0.00234612 -0.616688 -0.74859 0 -0.663034 0.544969 0 0.838456 0.443573 0.00397658 0.89623 -0.0280243 0.00313109 0.999602 0.0287759 0.000370681 0.999586 0.319129 -0.000243128 0.947711 -0.722634 4.73863e-06 0.691231 -0.592241 -1.04778e-05 0.805761 -0.493105 0.00410402 0.86996 -0.380996 3.80094e-05 0.924577 -0.207076 -2.11352e-05 0.978325 -0.996809 0 0.0798216 -0.999839 0.00687851 -0.0165734 -0.974225 -2.54202e-05 0.225578 -0.843232 6.33057e-05 0.53755 -0.930283 0.0134795 0.366594 -0.843872 0.00266661 0.536538 -0.952013 0 -0.306058 -0.928807 0.00281795 -0.370553 -0.859345 -1.72713e-05 -0.511396 -0.772887 2.11732e-05 -0.634544 -0.675473 0.00303084 -0.737378 -0.595596 -0.000796635 -0.803284 -0.287893 0.00112581 -0.957662 -0.286218 0.00103617 -0.958164 0.0652001 -0.000784727 -0.997872 0.156898 0.00270048 -0.987611 0.330431 -0.000457698 -0.94383 0.447946 0.000360655 -0.894061 0.570507 0.00233301 -0.82129 0.615778 0 -0.78792 -0.993349 -0.000361504 0.115139 -0.899869 0.000205314 0.43616 -0.862277 0.00257256 0.50643 -0.840568 0.00169583 0.541703 -0.790489 0 0.612477 -0.794567 0.000270721 -0.607177 -0.929245 -0.000274181 -0.369464 -0.955257 0.00229529 -0.295768 -0.992585 -0.000674225 -0.12155 -0.986933 0.00205275 0.161116 -0.6944 0.00521512 -0.719571 -0.754489 0.00187993 -0.65631 -0.641179 0 -0.767391 0.115233 1.68126e-07 0.993339 0.399048 5.81968e-07 0.91693 0.239879 0.00945392 0.970757 0.46057 0 0.887623 -0.0271448 0.00199976 0.99963 -0.0626242 0.00321486 0.998032 -0.204608 -1.43236e-05 0.978844 -0.370126 1.12643e-05 0.928982 -0.510547 0.00301461 0.859845 -0.589635 -0.000589449 0.80767 -0.996071 0 0.0885532 -0.99998 0.00498751 0.00395975 -0.971079 -1.31656e-05 0.23876 -0.846287 3.69755e-05 0.532726 -0.923604 0.00985251 0.383222 -0.818778 0.000642786 0.57411 -0.941249 0 -0.337714 -0.95731 0.00244278 -0.289054 -0.818452 -0.00121561 -0.574574 -0.716351 0.0025041 -0.697736 -0.638918 1.28366e-05 -0.769275 -0.498597 -7.70851e-06 -0.866834 -0.362364 0.00205389 -0.932034 -0.277218 -0.000867626 -0.960807 -0.0202541 0.000631602 -0.999795 0.0569365 0.00244132 -0.998375 0.210731 -0.00101479 -0.977544 0.465953 0.0016374 -0.884808 0.50577 0 -0.862669 -0.762713 0 0.646737 -0.80812 0.00263914 0.589012 -0.895652 -2.49944e-07 0.444756 -0.957626 7.76826e-07 0.288016 -0.989488 0.00297111 0.144586 -0.999609 -0.000682136 0.0279658 -0.95218 0.00088437 -0.305538 -0.942869 0.00205458 -0.333158 -0.862392 4.60596e-07 -0.506242 -0.764768 -8.21145e-07 -0.644306 -0.678999 0.00307766 -0.734133 -0.587741 0 -0.809049 0.329574 0 0.94413 0.116152 0.00764684 0.993202 0.28071 -5.48733e-08 0.959793 -0.0518717 1.01399e-08 0.998654 -0.153836 0.00250655 0.988093 -0.198692 0.00153182 0.980061 -0.309418 -0.000179331 0.950926 -0.559227 0.000517971 0.829015 -0.538819 0.00157356 0.84242 -0.995067 0 0.0992051 -0.999318 0.00290355 0.0368006 -0.967233 -4.46957e-06 0.253889 -0.85855 1.53141e-05 0.51273 -0.915669 0.00578215 0.401892 -0.785225 -0.000960592 0.61921 0.817843 -4.66537e-07 0.575441 0.666066 0 -0.745892 0.731016 0.00302615 -0.682354 0.835273 -6.30065e-07 -0.549836 0.915689 6.48528e-07 -0.401888 0.973291 0.00279727 -0.22956 0.986068 0.000475051 -0.166344 0.95889 2.08827e-06 0.283778 0.903458 0.00798444 0.428602 0.985403 -0.000408063 0.17024 0.691603 0 0.722278 0.504997 0.0120362 0.863037 0.66157 0.00307747 0.749877 0.636882 0 -0.770961 0.596242 0.00203932 -0.802802 0.828359 -0.00109015 -0.560196 0.904812 0.00217962 -0.425805 0.948347 -1.5512e-07 -0.317235 0.988138 1.36977e-07 -0.153569 0.999998 0.00182891 0.00064689 0.996807 -0.000388241 0.0798486 0.904262 0.000515997 0.426977 0.914179 0.00140319 0.405309 0.635884 0 0.771784 0.52957 0.00520861 0.84825 0.728209 -0.00089585 0.685355 -0.596289 0 0.80277 -0.643303 0.00181518 0.76561 -0.762696 -8.23153e-08 0.646757 -0.860436 5.51486e-08 0.509559 -0.9152 0.00234411 0.402992 -0.953528 -2.0536e-07 0.301305 -0.990572 2.39506e-08 0.136993 -0.999099 0.00157605 -0.0424154 -0.996806 0.000363149 -0.0798601 -0.576097 0 -0.817381 -0.493737 0.00401043 -0.869602 -0.677884 -2.01229e-07 -0.735169 -0.877757 2.18741e-07 -0.479106 -0.791909 0.00643612 -0.610605 -0.914171 -0.000318384 -0.405328 0.511174 0 -0.859477 0.57021 0.00224084 -0.821496 0.700038 -8.95947e-07 -0.714106 0.809749 1.29269e-06 -0.586776 0.884033 0.00260423 -0.467418 0.935757 -0.00074254 -0.352644 0.99976 0.00103824 -0.0218905 0.999961 0.00152404 -0.00870523 0.982243 2.8641e-07 0.187615 0.936445 -9.59124e-07 0.350813 0.892036 0.00264066 0.451957 0.826885 1.23093e-06 0.562371 0.720161 -7.36735e-07 0.693806 0.584426 0.0019681 0.811444 0.535525 0 0.84452 -0.961897 0 -0.273413 -0.961897 0 -0.273413 -0.730505 0 -0.682908 -0.730505 0 -0.682908 -0.337506 0 -0.941323 -0.337506 0 -0.941323 0.130161 0 -0.991493 0.130161 0 -0.991493 0.0700976 0 0.99754 0.0700976 0 0.99754 -0.395881 0 0.918302 -0.395881 0 0.918302 -0.773412 0 0.633904 -0.773412 0 0.633904 -0.978154 0 0.207883 -0.978154 0 0.207883 0.632122 0 -0.774869 0.674919 0.00250937 -0.737887 0.793853 -5.54486e-06 -0.608109 0.883673 1.07254e-05 -0.468105 0.9341 0.00332891 -0.356996 0.967516 1.48058e-05 -0.252811 0.99705 -6.83285e-06 -0.0767588 0.995018 0.0023934 0.0996698 0.98682 -0.000273766 0.161824 0.868198 0.000280002 0.496218 0.844734 0.00220832 0.535181 0.735023 -6.54878e-08 0.678042 0.61806 3.99611e-08 0.786131 0.515152 0.00316105 0.857093 0.420347 0 0.907363 -0.964367 0 -0.264569 -0.964367 0 -0.264569 -0.707165 0 -0.707049 -0.707165 0 -0.707049 -0.264729 0 -0.964323 -0.264729 0 -0.964323 0.247051 0 -0.969002 0.247051 0 -0.969002 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.615954 3.66135e-08 0.787782 0.615954 0 0.787782 0.615954 -3.66135e-08 0.787782 0.942765 5.07899e-07 0.333457 0.942765 0 0.333457 0.942765 0 0.333457 0.942765 0 0.333457 0.942765 -5.29622e-07 0.333457 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.632804 -0.000466015 -0.774312 -0.921132 0.00673228 -0.389193 -0.754072 -0.0305155 -0.656082 -0.999606 -0.0180368 0.0215 -0.989077 -0.0155438 -0.14658 -0.818136 -0.0225488 0.574583 0.791717 -0.0416702 -0.609465 0.545561 -0.0358471 -0.837304 0.415252 -0.0375276 -0.908932 0.304212 -0.0324804 -0.95205 0.14 -0.0283173 -0.989747 -0.00837953 -0.0262797 -0.99962 -0.0970775 -0.0204438 -0.995067 -0.428122 -0.00949336 -0.903671 -0.430676 -0.00950924 -0.902457 -0.598107 -0.000883415 -0.801416 -0.776158 -0.355394 0.520839 -0.81063 -0.205588 0.548282 -0.820164 -0.204538 0.534318 -0.833193 -0.0974577 0.544326 -0.836964 -0.097249 0.538548 -0.840151 -0.0390488 0.540945 -0.841253 -0.0389111 0.539239 -0.841019 -0.0457139 0.539071 -0.96245 -0.00333936 0.271438 -0.364249 -0.909502 0.200321 -0.451994 -0.850675 0.268429 -0.454832 -0.849767 0.266503 -0.56018 -0.750869 0.349849 -0.56358 -0.750307 0.345568 -0.664844 -0.615305 0.423535 -0.664026 -0.615687 0.424262 -0.683419 -0.582972 0.439412 -0.82704 -0.47508 0.300505 -0.730005 -0.480041 0.48647 -0.775487 -0.355569 0.521719 -0.766928 -0.0186609 -0.641462 -0.767193 -0.00820036 -0.641363 -0.767344 -0.00822453 -0.641183 -0.766789 -0.0205116 -0.641571 -0.76746 -0.0206357 -0.640765 -0.764939 -0.0433361 -0.642644 -0.766916 -0.0441383 -0.640228 -0.758738 -0.0759552 -0.646953 -0.758825 -0.0760328 -0.646841 -0.748535 -0.105831 -0.654595 -0.748134 -0.105412 -0.655121 -0.733402 -0.130933 -0.667067 -0.733364 -0.130809 -0.667133 -0.712892 -0.161529 -0.682418 -0.713046 -0.161898 -0.682168 -0.689546 -0.181381 -0.701162 -0.689538 -0.181806 -0.701059 -0.671016 -0.195483 -0.715209 -0.671344 -0.19761 -0.714316 -0.636939 -0.212081 -0.741168 -0.636975 -0.209965 -0.74174 -0.605695 -0.213901 -0.766407 -0.606171 -0.210882 -0.766867 -0.602837 -0.210914 -0.769482 -0.603018 -0.209682 -0.769677 -0.602895 -0.209682 -0.769774 -0.603085 -0.20835 -0.769986 -0.603189 -0.20835 -0.769905 -0.603292 -0.207675 -0.770007 -0.602559 -0.207679 -0.770579 -0.602598 -0.207416 -0.770619 -0.603273 -0.207415 -0.770091 -0.603258 -0.207517 -0.770076 -0.587862 -0.206538 -0.782151 -0.587416 -0.207782 -0.782157 -0.560731 -0.203314 -0.802648 -0.559389 -0.206686 -0.802724 -0.533995 -0.193901 -0.822953 -0.53349 -0.194612 -0.823113 -0.508359 -0.178847 -0.842369 -0.507004 -0.180608 -0.842809 -0.485449 -0.156957 -0.86006 -0.484998 -0.1573 -0.860252 -0.464691 -0.131051 -0.875721 -0.463788 -0.131673 -0.876107 -0.450061 -0.101095 -0.887257 -0.449945 -0.101129 -0.887312 -0.437581 -0.0687824 -0.896544 -0.437713 -0.0687455 -0.896483 -0.961319 -0.048679 -0.271101 -0.962337 -0.0231377 -0.270873 -0.962574 -0.0232226 -0.270024 -0.960806 -0.0579066 -0.271105 -0.961554 -0.0581921 -0.26838 -0.954034 -0.122198 -0.273656 -0.956247 -0.124155 -0.26491 -0.934649 -0.214032 -0.283938 -0.934744 -0.214257 -0.283457 -0.904508 -0.29786 -0.305196 -0.904102 -0.296667 -0.30755 -0.864324 -0.369295 -0.341416 -0.864355 -0.368909 -0.341755 -0.804159 -0.453601 -0.384155 -0.804156 -0.454561 -0.383025 -0.740233 -0.510942 -0.437028 -0.739777 -0.512209 -0.436317 -0.686626 -0.549745 -0.475737 -0.685504 -0.555093 -0.471122 -0.588535 -0.59567 -0.54663 -0.590394 -0.590552 -0.550166 -0.502833 -0.602323 -0.619973 -0.506485 -0.594922 -0.624132 -0.4971 -0.59504 -0.631521 -0.498559 -0.591955 -0.633268 -0.498212 -0.591956 -0.63354 -0.499574 -0.589027 -0.635195 -0.499865 -0.589026 -0.634968 -0.500728 -0.587208 -0.63597 -0.498668 -0.587216 -0.63758 -0.498952 -0.586609 -0.637916 -0.500837 -0.58661 -0.636437 -0.500878 -0.58652 -0.636486 -0.457661 -0.58389 -0.670537 -0.455342 -0.587145 -0.669271 -0.379512 -0.573327 -0.726131 -0.373418 -0.581451 -0.722824 -0.302262 -0.546636 -0.780914 -0.300061 -0.548539 -0.780428 -0.229135 -0.503025 -0.833345 -0.224088 -0.507201 -0.832185 -0.163521 -0.441745 -0.882112 -0.161828 -0.442589 -0.882001 -0.104854 -0.367912 -0.92393 -0.101936 -0.369287 -0.923708 -0.0631813 -0.284191 -0.956684 -0.0627434 -0.284268 -0.956689 -0.0283388 -0.192864 -0.980816 -0.0286814 -0.192798 -0.980819 -0.987664 -0.0547051 0.146719 -0.988537 -0.0340114 0.147097 -0.988316 -0.0341343 0.148548 -0.985509 -0.0850668 0.146749 -0.984756 -0.0854044 0.151533 -0.973291 -0.17931 0.14336 -0.970858 -0.18131 0.156724 -0.940704 -0.31315 0.130431 -0.94052 -0.313392 0.131175 -0.895139 -0.434857 0.0981083 -0.896351 -0.433395 0.0933993 -0.83969 -0.541151 0.0455554 -0.840023 -0.540685 0.0449594 -0.749913 -0.661249 -0.0195254 -0.74882 -0.662561 -0.0167765 -0.656949 -0.748087 -0.0937219 -0.655479 -0.749557 -0.0922564 -0.577283 -0.802522 -0.150678 -0.572063 -0.807957 -0.141241 -0.43083 -0.866743 -0.251281 -0.43641 -0.861618 -0.259154 -0.308572 -0.88011 -0.360819 -0.316759 -0.873233 -0.370308 -0.302914 -0.873458 -0.381201 -0.306415 -0.870359 -0.385467 -0.305892 -0.870362 -0.385876 -0.309362 -0.867226 -0.390147 -0.309778 -0.867223 -0.389822 -0.311819 -0.865391 -0.392258 -0.308782 -0.865402 -0.394631 -0.309415 -0.864824 -0.395401 -0.312174 -0.864819 -0.393237 -0.312514 -0.864509 -0.39365 -0.248879 -0.860899 -0.443748 -0.244061 -0.864171 -0.440048 -0.13317 -0.841536 -0.523529 -0.121198 -0.849588 -0.513333 -0.0162952 -0.800952 -0.598507 -0.0123909 -0.802672 -0.596292 0.0900137 -0.734022 -0.673133 0.0988171 -0.73802 -0.667504 0.188551 -0.644645 -0.740865 0.191155 -0.645266 -0.739656 0.272293 -0.534862 -0.799862 0.276978 -0.536091 -0.797427 0.33535 -0.413801 -0.84635 0.336088 -0.413821 -0.846048 0.383803 -0.27992 -0.879966 0.383487 -0.279891 -0.880113 0.722529 -0.31443 -0.6157 0.671674 -0.465522 -0.576319 0.670894 -0.465704 -0.57708 0.602684 -0.602368 -0.523379 0.59743 -0.602546 -0.529165 0.508442 -0.727927 -0.46001 0.5055 -0.728269 -0.462702 0.402056 -0.832412 -0.381368 0.391449 -0.832146 -0.392812 0.277475 -0.91127 -0.304292 0.272344 -0.911323 -0.308739 0.151432 -0.965124 -0.21355 0.134858 -0.963403 -0.231662 0.00961096 -0.990857 -0.134577 0.00236473 -0.990012 -0.140965 -0.070827 -0.993976 -0.0836354 -0.0697862 -0.994156 -0.0823681 -0.0666317 -0.994165 -0.0848363 -0.0655916 -0.994341 -0.0835644 -0.0690951 -0.99433 -0.0808258 -0.0658033 -0.994867 -0.0768775 -0.0653498 -0.994869 -0.077232 -0.0598441 -0.995719 -0.0704445 -0.060468 -0.995716 -0.0699563 -0.0548646 -0.996497 -0.0631139 -0.0707829 -0.996205 -0.0506523 -0.0585429 -0.997614 -0.0365949 -0.139547 -0.98986 0.0265402 -0.396242 -0.897037 -0.19575 -0.216327 -0.97051 0.106364 -0.353297 -0.910806 0.213572 0.726369 -0.141786 -0.672522 0.747796 -0.18963 -0.636272 0.722305 -0.314446 -0.615954 -0.431155 -0.0200862 -0.902054 -0.431157 -0.0200861 -0.902053 -0.00969804 -0.0564792 -0.998357 -0.00977821 -0.0564755 -0.998356 0.413341 -0.0822297 -0.906856 0.413035 -0.0822247 -0.906996 -0.431957 -0.0313947 -0.901348 -0.432298 -0.0313637 -0.901185 -0.0122187 -0.0882734 -0.996021 -0.0128926 -0.088236 -0.996016 0.409424 -0.128522 -0.903246 0.408825 -0.128517 -0.903518 0.753607 -0.144601 -0.641223 0.758522 -0.0925236 -0.645045 0.758355 -0.0925297 -0.645241 0.761119 -0.0392703 -0.647423 -0.598107 0.000717692 -0.801416 -0.428126 0.00838338 -0.90368 0.14002 0.0228318 -0.989885 0.792007 0.0316898 -0.609689 -0.961546 0.0434572 0.271183 -0.817347 0.049344 0.574029 -0.988655 0.0330687 -0.146518 -0.999032 0.0383938 0.0214876 -0.920922 0.0223906 -0.389104 -0.632804 0.00103747 -0.774311 0.758478 0.087998 -0.64573 0.761036 0.0347127 -0.64778 0.545701 0.0277937 -0.837519 -0.430695 0.00850123 -0.902457 -0.431038 0.0191084 -0.902131 -0.430952 0.0191188 -0.902172 -0.433021 0.0387898 -0.900549 -0.431841 0.0390892 -0.901102 -0.439892 0.0721246 -0.89515 -0.439891 0.0721254 -0.89515 -0.450546 0.106259 -0.886407 -0.451078 0.105897 -0.88618 -0.468588 0.135999 -0.872886 -0.468818 0.135731 -0.872804 -0.488258 0.163722 -0.857204 -0.48939 0.162259 -0.856837 -0.513416 0.182765 -0.838451 -0.513765 0.181978 -0.838409 -0.538442 0.19939 -0.818733 -0.539525 0.196684 -0.818675 -0.575812 0.208901 -0.790443 -0.576428 0.205759 -0.790818 -0.603232 0.207753 -0.770033 -0.603308 0.206835 -0.77022 -0.602777 0.206841 -0.770634 -0.602714 0.207408 -0.770531 -0.603107 0.207407 -0.770223 -0.603 0.208352 -0.770053 -0.603062 0.208349 -0.770004 -0.60291 0.209675 -0.769764 -0.603358 0.209671 -0.769413 -0.603033 0.21253 -0.768884 -0.621065 0.211411 -0.754708 -0.621148 0.213663 -0.754005 -0.649589 0.207081 -0.73154 -0.649647 0.2075 -0.73137 -0.671395 0.196188 -0.71466 -0.671118 0.19549 -0.715112 -0.692414 0.182054 -0.698154 -0.691903 0.180822 -0.698981 -0.715659 0.155322 -0.68096 -0.715617 0.155289 -0.681013 -0.736335 0.128482 -0.664307 -0.73644 0.128589 -0.664169 -0.747723 0.104784 -0.655691 -0.747846 0.104808 -0.655547 -0.757894 0.0808076 -0.647354 -0.757759 0.0807363 -0.647521 -0.764037 0.053948 -0.642913 -0.763636 0.0539505 -0.64339 -0.767581 0.0321349 -0.640146 -0.766182 0.0319141 -0.641831 -0.767258 0.0210455 -0.640994 -0.76683 0.0210054 -0.641507 -0.767436 0.0107991 -0.641035 -0.754382 0.0105203 -0.656351 -0.962556 0.03032 -0.269383 -0.960829 0.0593046 -0.270723 -0.961372 0.059391 -0.26877 -0.958316 0.0900956 -0.271133 -0.959843 0.0905257 -0.265531 -0.949444 0.151979 -0.274695 -0.949997 0.151891 -0.272829 -0.930991 0.227177 -0.285738 -0.931108 0.227304 -0.285255 -0.904201 0.295403 -0.308477 -0.903982 0.295367 -0.309152 -0.870806 0.36181 -0.332852 -0.870672 0.361475 -0.333565 -0.814323 0.437945 -0.380897 -0.814402 0.43805 -0.380607 -0.745811 0.50823 -0.430661 -0.745868 0.511488 -0.426685 -0.68674 0.550305 -0.474923 -0.686799 0.551945 -0.472932 -0.624739 0.582882 -0.519567 -0.624887 0.582162 -0.520195 -0.545243 0.601463 -0.583911 -0.546854 0.595786 -0.588209 -0.49635 0.599186 -0.628183 -0.499397 0.592181 -0.632396 -0.498151 0.592186 -0.633372 -0.499545 0.588954 -0.635286 -0.499372 0.588954 -0.635421 -0.500366 0.586631 -0.636787 -0.499258 0.586633 -0.637655 -0.499886 0.58515 -0.638525 -0.501385 0.585137 -0.63736 -0.500647 0.587032 -0.636196 -0.424858 0.580855 -0.694336 -0.420917 0.588703 -0.690114 -0.318481 0.553824 -0.769317 -0.313425 0.560758 -0.766365 -0.244135 0.512867 -0.823022 -0.242724 0.514759 -0.822258 -0.175048 0.455985 -0.872603 -0.171075 0.459383 -0.871608 -0.11638 0.381655 -0.916949 -0.115274 0.382562 -0.916711 -0.0662302 0.297185 -0.95252 -0.0645677 0.298002 -0.952379 -0.0343673 0.202741 -0.978629 -0.0343408 0.202753 -0.978628 -0.0120442 0.109787 -0.993882 -0.0152347 0.109167 -0.993907 -0.00939942 0.0537324 -0.998511 -0.00968186 0.0537067 -0.99851 -0.00863741 0.0231272 -0.999695 -0.0970855 0.0159429 -0.995148 -0.987774 0.0436389 0.149659 -0.985195 0.0871301 0.147643 -0.984683 0.0871676 0.151002 -0.980171 0.13231 0.147509 -0.978811 0.132532 0.15609 -0.964286 0.222682 0.143404 -0.9639 0.222286 0.146578 -0.934828 0.331867 0.126337 -0.934706 0.331954 0.127008 -0.896692 0.43245 0.0945013 -0.89676 0.432558 0.0933578 -0.846952 0.528573 0.0572888 -0.847502 0.527963 0.0547349 -0.766774 0.641795 -0.012573 -0.766738 0.641846 -0.0121256 -0.66514 0.741634 -0.0869932 -0.66206 0.745406 -0.0777584 -0.576101 0.803959 -0.147505 -0.575023 0.805433 -0.143615 -0.484174 0.848828 -0.212289 -0.484932 0.848007 -0.213834 -0.368929 0.87752 -0.30635 -0.374067 0.871944 -0.315891 -0.300224 0.877382 -0.374254 -0.307683 0.870448 -0.384256 -0.305861 0.870459 -0.385682 -0.309232 0.867253 -0.39019 -0.308985 0.867255 -0.390382 -0.311523 0.864806 -0.393781 -0.309898 0.86481 -0.395054 -0.311477 0.863265 -0.397184 -0.313655 0.863254 -0.39549 -0.312037 0.864924 -0.393115 -0.200605 0.854733 -0.478737 -0.191963 0.862767 -0.467743 -0.0420627 0.810812 -0.583793 -0.0326279 0.81778 -0.574605 0.0697285 0.749968 -0.657789 0.072308 0.752051 -0.655127 0.16967 0.664233 -0.728015 0.176331 0.667729 -0.723219 0.257694 0.556305 -0.790012 0.259355 0.557257 -0.788796 0.328805 0.431654 -0.839978 0.33139 0.432514 -0.838518 0.377446 0.295111 -0.877749 0.377505 0.295134 -0.877717 0.408028 0.159531 -0.898923 0.405165 0.159111 -0.900292 0.413721 0.0782254 -0.907037 0.413352 0.0782004 -0.907207 0.415239 0.0324788 -0.909133 0.304268 0.0261867 -0.952226 -0.83885 0.0478208 0.542258 -0.835824 0.099599 0.539887 -0.833274 0.0994617 0.54384 -0.828119 0.151046 0.539818 -0.822249 0.150661 0.548824 -0.805597 0.253395 0.535541 -0.803319 0.252364 0.539436 -0.770553 0.376515 0.514281 -0.770198 0.376498 0.514824 -0.726725 0.491089 0.480315 -0.727321 0.49152 0.47897 -0.671217 0.599735 0.435644 -0.674168 0.599817 0.430948 -0.581719 0.73046 0.357814 -0.581501 0.730359 0.358376 -0.466969 0.842121 0.269764 -0.457882 0.842431 0.283998 -0.359652 0.909883 0.206795 -0.356934 0.909719 0.212153 -0.255122 0.957733 0.132893 -0.256668 0.957635 0.130605 -0.125004 0.991778 0.0273799 -0.134117 0.990882 0.0128881 -0.05007 0.997341 -0.0529437 -0.0618058 0.995735 -0.0684946 -0.0597493 0.995749 -0.0701028 -0.0652223 0.994868 -0.0773568 -0.0649599 0.994869 -0.0775622 -0.0690465 0.994156 -0.0829861 -0.0671918 0.994161 -0.0844373 -0.0697287 0.993692 -0.0878349 -0.0722211 0.993684 -0.0858891 -0.0701515 0.994084 -0.0829164 0.0572858 0.981606 -0.182122 0.0699314 0.984023 -0.163733 0.240442 0.924176 -0.296793 0.252651 0.926127 -0.280101 0.3708 0.850499 -0.373041 0.373823 0.851357 -0.368032 0.481836 0.750711 -0.451959 0.489322 0.751739 -0.442099 0.583417 0.627128 -0.516077 0.585173 0.627644 -0.513454 0.660926 0.485429 -0.572307 0.663495 0.485747 -0.569055 0.717891 0.331899 -0.611944 0.717968 0.331924 -0.61184 0.740189 0.237169 -0.629182 0.434262 0.161857 -0.886126 0.753497 0.145356 -0.641182 0.758835 0.0880117 -0.645309 -0.99962 0.0195547 0.0194504 -0.91992 0.0191465 -0.391638 -0.633191 0.000512099 -0.773995 0.131683 0.0283386 -0.990887 0.535994 0.0386844 -0.843335 0.785029 0.0373498 -0.618332 -0.433029 0.00745925 -0.901349 -0.597824 -0.0084412 -0.801583 -0.963172 -0.00630248 0.268812 0.754727 0.0395932 -0.654843 0.751193 0.102785 -0.652031 0.751112 0.102782 -0.652125 0.746482 0.148767 -0.648562 0.746512 0.148779 -0.648525 0.722487 0.286498 -0.629231 0.723319 0.286604 -0.628225 0.673469 0.445686 -0.589749 0.672976 0.445483 -0.590464 0.604077 0.589648 -0.536102 0.599784 0.589034 -0.54157 0.5091 0.720253 -0.471225 0.507136 0.719548 -0.474408 0.400863 0.828642 -0.390719 0.392061 0.827255 -0.402415 0.275591 0.909206 -0.31208 0.272805 0.908251 -0.317266 0.147898 0.964496 -0.218801 0.134037 0.961972 -0.238001 -0.0442063 0.994097 -0.0990785 -0.0521598 0.992482 -0.110717 -0.0774624 0.992829 -0.0910483 -0.0735731 0.993605 -0.0856545 -0.0687454 0.993618 -0.0894315 -0.0684701 0.99367 -0.0890585 -0.0716692 0.993666 -0.0865572 -0.0679806 0.994343 -0.0816184 -0.0681176 0.994342 -0.0815114 -0.0660548 0.994714 -0.0786169 -0.0659719 0.994714 -0.0786817 -0.0563145 0.996228 -0.0660161 -0.102488 0.994289 -0.0297517 0.0969777 0.958543 0.267936 -0.179302 0.981655 0.0648372 -0.241481 0.963742 0.113531 -0.239379 0.963825 0.117215 -0.360906 0.908051 0.21258 -0.369803 0.90753 0.199086 -0.468037 0.839735 0.275293 -0.469394 0.840328 0.271143 -0.509014 0.805985 0.302147 -0.342025 0.699882 0.627043 -0.609694 0.697087 0.377284 -0.684038 0.585717 0.434773 -0.68311 0.585194 0.436931 -0.743591 0.460412 0.484864 -0.739836 0.460221 0.490755 -0.779782 0.3464 0.521485 -0.780069 0.346637 0.520899 -0.793764 0.295426 0.531659 -0.516912 0.209112 0.830105 -0.825247 0.182234 0.534564 -0.832395 0.124295 0.540064 -0.833406 0.124364 0.538486 -0.837738 0.0670671 0.541938 -0.841218 0.0671856 0.536505 0.296282 0.0326065 -0.954544 0.409192 0.0324826 -0.91187 0.406221 0.0910553 -0.909227 0.406077 0.0910511 -0.909292 0.401672 0.131785 -0.906252 0.401797 0.13176 -0.9062 0.383177 0.254275 -0.887986 0.384242 0.254352 -0.887504 0.337402 0.394824 -0.854561 0.336788 0.394826 -0.854802 0.27841 0.522937 -0.805621 0.274029 0.52185 -0.807825 0.19202 0.636227 -0.747224 0.189656 0.635734 -0.748247 0.098776 0.732373 -0.673701 0.0902917 0.728609 -0.678953 -0.0128139 0.798498 -0.601861 -0.0163512 0.797069 -0.603667 -0.122533 0.847111 -0.517097 -0.134305 0.839294 -0.526829 -0.288643 0.866307 -0.407674 -0.295601 0.860469 -0.414986 -0.317218 0.860594 -0.398436 -0.314538 0.863031 -0.395276 -0.310513 0.863038 -0.39843 -0.31034 0.863196 -0.398223 -0.313209 0.863192 -0.395979 -0.310758 0.865443 -0.392985 -0.311057 0.865442 -0.392752 -0.309629 0.866703 -0.391095 -0.309768 0.866703 -0.390986 -0.303572 0.87234 -0.383233 -0.362854 0.869446 -0.335262 -0.351209 0.879618 -0.320818 -0.471668 0.851428 -0.229347 -0.470022 0.852894 -0.22727 -0.576719 0.804573 -0.141626 -0.58163 0.799421 -0.150441 -0.667494 0.739584 -0.0864101 -0.669225 0.737794 -0.088309 -0.767379 0.641168 -0.0057835 -0.768125 0.640253 -0.00769792 -0.856169 0.513726 0.05532 -0.855551 0.514613 0.0566136 -0.908767 0.404804 0.101373 -0.907717 0.406073 0.105614 -0.943276 0.305197 0.130708 -0.943419 0.304933 0.130295 -0.968861 0.194478 0.153256 -0.97132 0.192214 0.13997 -0.983032 0.108889 0.147617 -0.983235 0.108751 0.146366 -0.986998 0.0588196 0.149582 -0.987696 0.0585494 0.145015 -0.988715 0.0357284 0.145484 -0.842958 0.0146043 0.537781 -0.819679 0.024369 0.572304 -0.988747 0.0167895 -0.148651 -0.962465 -0.000181949 -0.271406 -0.961457 0.0398143 -0.272059 -0.962205 0.0400367 -0.269368 -0.959543 0.074023 -0.271656 -0.959732 0.0741312 -0.270959 -0.952282 0.131104 -0.275627 -0.954409 0.133217 -0.267126 -0.935939 0.20828 -0.283969 -0.935968 0.20846 -0.283741 -0.91254 0.278047 -0.299935 -0.912135 0.276993 -0.302134 -0.874846 0.351093 -0.333733 -0.874856 0.350394 -0.334443 -0.816206 0.438867 -0.37577 -0.81622 0.439711 -0.374751 -0.747851 0.503462 -0.432718 -0.747366 0.50498 -0.431786 -0.689065 0.54737 -0.474949 -0.688012 0.552425 -0.470602 -0.614573 0.584477 -0.529798 -0.615129 0.583033 -0.530744 -0.532677 0.603782 -0.593045 -0.537546 0.59288 -0.599615 -0.49716 0.594027 -0.632427 -0.499696 0.58851 -0.635578 -0.499607 0.588511 -0.635648 -0.500224 0.587244 -0.636334 -0.500028 0.587245 -0.636487 -0.501014 0.58512 -0.637668 -0.499074 0.585123 -0.639185 -0.499171 0.584915 -0.639298 -0.5019 0.584913 -0.63716 -0.503019 0.582557 -0.638436 -0.488306 0.582644 -0.649679 -0.484872 0.589053 -0.646463 -0.379768 0.571434 -0.727488 -0.373815 0.579268 -0.724369 -0.301879 0.543337 -0.78336 -0.299906 0.544936 -0.783008 -0.228512 0.498741 -0.836086 -0.223548 0.502767 -0.835016 -0.162331 0.435045 -0.885655 -0.160864 0.435725 -0.885588 -0.103273 0.35849 -0.927804 -0.100653 0.359673 -0.927634 -0.0620482 0.270671 -0.96067 -0.0616007 0.270736 -0.960681 -0.0277539 0.175002 -0.984177 -0.0286156 0.174861 -0.984177 -0.0175694 0.0903194 -0.995758 -0.0176721 0.0903326 -0.995755 -0.0144563 0.0624226 -0.997945 -0.014429 0.0624243 -0.997945 -0.012521 0.0217025 -0.999686 -0.108255 0.0216778 -0.993887 -0.431861 0.00853794 -0.9019 -0.432487 0.0221955 -0.901367 -0.432535 0.0221889 -0.901344 -0.433693 0.0320971 -0.900489 -0.43367 0.0321075 -0.9005 -0.437459 0.0622762 -0.897079 -0.437202 0.0623801 -0.897198 -0.449369 0.0962555 -0.888146 -0.449396 0.0962318 -0.888134 -0.4631 0.128288 -0.876972 -0.463909 0.127582 -0.876648 -0.484526 0.15484 -0.860964 -0.484765 0.15447 -0.860896 -0.506706 0.179126 -0.843305 -0.507816 0.177307 -0.843021 -0.533347 0.193432 -0.823484 -0.533584 0.192627 -0.823519 -0.559586 0.206018 -0.802758 -0.560582 0.20254 -0.802948 -0.598006 0.208629 -0.773862 -0.598268 0.205957 -0.774375 -0.603563 0.205879 -0.770277 -0.60348 0.206743 -0.77011 -0.602495 0.206743 -0.770881 -0.602489 0.206801 -0.77087 -0.603152 0.2068 -0.770352 -0.603054 0.207684 -0.77019 -0.603089 0.207684 -0.770163 -0.603042 0.208195 -0.770062 -0.603032 0.208195 -0.770069 -0.602767 0.210411 -0.769675 -0.616952 0.21023 -0.758402 -0.616879 0.21478 -0.757186 -0.64565 0.207084 -0.735019 -0.645757 0.207661 -0.734762 -0.672228 0.196535 -0.713781 -0.671712 0.194601 -0.714796 -0.692266 0.178963 -0.6991 -0.691983 0.178632 -0.699464 -0.717244 0.15652 -0.679016 -0.717057 0.156241 -0.679278 -0.736903 0.124364 -0.664461 -0.737129 0.124473 -0.66419 -0.750833 0.0985312 -0.653101 -0.751275 0.098833 -0.652547 -0.759116 0.0739315 -0.646744 -0.759048 0.073936 -0.646822 -0.766232 0.0471841 -0.64083 -0.764241 0.0466781 -0.643239 -0.766631 0.0262508 -0.641551 -0.766403 0.0262243 -0.641824 -0.767399 0.0141496 -0.641014 -0.766819 0.0141124 -0.641709 -0.767216 -0.00464236 -0.641373 -0.753666 -0.000395717 -0.657258 -0.108254 -0.0222114 -0.993875 -0.597845 -0.000926019 -0.801611 -0.988057 -0.0409454 -0.148548 -0.961697 -0.0556763 0.2684 -0.81852 -0.0584584 0.571495 -0.753626 -0.0102558 -0.657224 -0.433028 -0.00780511 -0.901347 0.131703 -0.0225012 -0.991034 0.536103 -0.0330307 -0.843506 -0.740444 -0.462698 0.487498 -0.687678 -0.572264 0.446781 -0.69264 -0.571368 0.440214 -0.607859 -0.70097 0.373025 -0.607889 -0.700956 0.373003 -0.49408 -0.821313 0.285184 -0.484776 -0.82289 0.296387 -0.398389 -0.888342 0.228331 -0.395317 -0.889207 0.230293 -0.302882 -0.939755 0.158502 -0.300282 -0.940066 0.161574 -0.169244 -0.98382 0.0587705 -0.177275 -0.982863 0.0505267 -0.0593324 -0.997376 -0.0414842 -0.0733733 -0.995609 -0.0581265 -0.0583875 -0.995847 -0.06986 -0.0656977 -0.99471 -0.078966 -0.0659817 -0.994709 -0.078744 -0.0682986 -0.994334 -0.0814602 -0.0678919 -0.994336 -0.0817782 -0.071761 -0.993662 -0.0865202 -0.0685225 -0.993667 -0.0890522 -0.0689563 -0.99359 -0.0895781 -0.0748965 -0.993568 -0.0849316 -0.0802774 -0.992579 -0.0913337 -0.0507779 -0.992154 -0.114243 -0.0412089 -0.993674 -0.104466 0.115622 -0.96715 -0.22639 0.132299 -0.968993 -0.208683 0.256018 -0.916899 -0.306187 0.260821 -0.916812 -0.30237 0.377229 -0.838756 -0.392666 0.387752 -0.839045 -0.381644 0.494647 -0.733717 -0.465816 0.497638 -0.733327 -0.463236 0.589819 -0.605109 -0.534749 0.594902 -0.604925 -0.529299 0.66579 -0.462865 -0.585217 0.666497 -0.462687 -0.584553 0.718608 -0.305328 -0.624802 0.71815 -0.305363 -0.625312 0.745832 -0.156674 -0.647447 0.745426 -0.156814 -0.647881 0.750868 -0.104805 -0.652084 0.751099 -0.104799 -0.651819 -0.431867 -0.00780381 -0.901904 -0.432575 -0.0226221 -0.901314 -0.432598 -0.02262 -0.901303 -0.43392 -0.0338393 -0.900316 -0.433813 -0.0338293 -0.900368 -0.438437 -0.0663898 -0.896307 -0.438239 -0.0664424 -0.8964 -0.450888 -0.0999484 -0.886967 -0.450983 -0.0999216 -0.886922 -0.46515 -0.131576 -0.875399 -0.466001 -0.130989 -0.875034 -0.48698 -0.157659 -0.859066 -0.487378 -0.157361 -0.858895 -0.509559 -0.181284 -0.841122 -0.510881 -0.179537 -0.840695 -0.536469 -0.194903 -0.821105 -0.537019 -0.194143 -0.820926 -0.562901 -0.206668 -0.800269 -0.564206 -0.203273 -0.80022 -0.597281 -0.207811 -0.774642 -0.597801 -0.205627 -0.774824 -0.603922 -0.205517 -0.770092 -0.60374 -0.206697 -0.769918 -0.602511 -0.206698 -0.77088 -0.60249 -0.20684 -0.770859 -0.603156 -0.206841 -0.770338 -0.603034 -0.20768 -0.770207 -0.603109 -0.20768 -0.770148 -0.603043 -0.208083 -0.770091 -0.602975 -0.208083 -0.770145 -0.602725 -0.209866 -0.769856 -0.605889 -0.209844 -0.767375 -0.605324 -0.21365 -0.76677 -0.630438 -0.210074 -0.747273 -0.630286 -0.211654 -0.746955 -0.658678 -0.203138 -0.724485 -0.658632 -0.202604 -0.724677 -0.678322 -0.190531 -0.709632 -0.678357 -0.190016 -0.709736 -0.6975 -0.176903 -0.694406 -0.697238 -0.176024 -0.694892 -0.720445 -0.148665 -0.67739 -0.720441 -0.148639 -0.6774 -0.739321 -0.122352 -0.662144 -0.739584 -0.122705 -0.661785 -0.750175 -0.0986284 -0.653843 -0.750254 -0.0987904 -0.653727 -0.760055 -0.0734126 -0.645699 -0.759519 -0.0730479 -0.64637 -0.766391 -0.0374746 -0.641281 -0.765379 -0.0369946 -0.642515 -0.766674 -0.0255971 -0.641526 -0.766452 -0.0255422 -0.641794 -0.767443 -0.0124997 -0.640995 -0.633187 0.00353759 -0.773991 -0.919689 -0.0294818 -0.39154 -0.962406 -0.0339898 -0.26948 -0.959636 -0.072156 -0.27183 -0.959893 -0.0722144 -0.270909 -0.956046 -0.105059 -0.27375 -0.957437 -0.105187 -0.268796 -0.936725 -0.205848 -0.283149 -0.937352 -0.206424 -0.280643 -0.911367 -0.278198 -0.30334 -0.911161 -0.278197 -0.303961 -0.880197 -0.344935 -0.325995 -0.879824 -0.344128 -0.327852 -0.828444 -0.419353 -0.371247 -0.828413 -0.419332 -0.371339 -0.760455 -0.495087 -0.420234 -0.760595 -0.497425 -0.417209 -0.707406 -0.535662 -0.461132 -0.707717 -0.536442 -0.459746 -0.650923 -0.569574 -0.501882 -0.650712 -0.57089 -0.500658 -0.572076 -0.595584 -0.563923 -0.572896 -0.59183 -0.567034 -0.50257 -0.601349 -0.62113 -0.506183 -0.592335 -0.626832 -0.497679 -0.592417 -0.633528 -0.499412 -0.588432 -0.635874 -0.499707 -0.58843 -0.635643 -0.50022 -0.587157 -0.636417 -0.500094 -0.587157 -0.636516 -0.501008 -0.584993 -0.637788 -0.499163 -0.584996 -0.639231 -0.49923 -0.584837 -0.639324 -0.502844 -0.58483 -0.636492 -0.504027 -0.581881 -0.638257 -0.486063 -0.582016 -0.651921 -0.484056 -0.587442 -0.648539 -0.389059 -0.573528 -0.720901 -0.384159 -0.581949 -0.716768 -0.310734 -0.547557 -0.776934 -0.309551 -0.549686 -0.775902 -0.236562 -0.504747 -0.830222 -0.232177 -0.509401 -0.828616 -0.169428 -0.442791 -0.880472 -0.16832 -0.443977 -0.880087 -0.109152 -0.367656 -0.923534 -0.106324 -0.369462 -0.923143 -0.0661703 -0.28105 -0.957409 -0.0658947 -0.281237 -0.957373 -0.0306757 -0.186503 -0.981975 -0.0312697 -0.186311 -0.981993 -0.0179205 -0.0952718 -0.99529 -0.0182091 -0.0951614 -0.995295 -0.014539 -0.0636456 -0.997867 -0.014459 -0.0636541 -0.997867 -0.0125665 -0.0246904 -0.999616 0.296273 -0.0334968 -0.954516 -0.998675 -0.0476509 0.019432 -0.987493 -0.0505819 0.149329 -0.98358 -0.106034 0.146041 -0.983336 -0.106071 0.147646 -0.97757 -0.154292 0.143355 -0.976395 -0.154041 0.151406 -0.94485 -0.300981 0.129106 -0.944093 -0.301458 0.133463 -0.907583 -0.407326 0.101876 -0.907635 -0.407476 0.10081 -0.861206 -0.503784 0.0672796 -0.862114 -0.502811 0.0627839 -0.788485 -0.615053 0.00103469 -0.788486 -0.615053 0.000995327 -0.687002 -0.722996 -0.072835 -0.684694 -0.725896 -0.0653388 -0.607744 -0.783675 -0.128459 -0.607552 -0.784246 -0.12585 -0.524121 -0.830585 -0.188217 -0.523013 -0.831835 -0.185761 -0.408581 -0.869526 -0.277465 -0.411699 -0.865874 -0.284192 -0.308855 -0.878922 -0.363462 -0.317343 -0.870678 -0.375783 -0.304913 -0.870844 -0.385562 -0.309301 -0.866691 -0.391382 -0.309744 -0.866689 -0.391036 -0.311035 -0.865392 -0.392878 -0.31086 -0.865393 -0.393015 -0.313111 -0.863191 -0.396058 -0.310392 -0.863195 -0.398184 -0.310662 -0.862928 -0.398552 -0.316016 -0.862912 -0.394357 -0.31898 -0.859894 -0.39854 -0.292479 -0.859718 -0.418737 -0.287644 -0.865011 -0.411117 -0.148077 -0.842665 -0.517677 -0.13802 -0.851254 -0.506277 -0.0294738 -0.803386 -0.594729 -0.0271734 -0.805696 -0.591705 0.0784795 -0.737501 -0.67077 0.0861902 -0.742313 -0.664487 0.179424 -0.647211 -0.740894 0.181256 -0.648539 -0.739286 0.265689 -0.535341 -0.80176 0.269823 -0.537079 -0.799213 0.330461 -0.40983 -0.850197 0.331154 -0.410202 -0.849748 0.380059 -0.271084 -0.884346 0.3794 -0.270927 -0.884677 0.401296 -0.138972 -0.905344 0.400687 -0.138752 -0.905648 0.405769 -0.0928231 -0.90925 0.406035 -0.0928438 -0.909129 0.40892 -0.0387281 -0.911748 0.75482 -0.0389793 -0.654773 0.784925 -0.0407327 -0.61825 -0.838572 -0.0592169 0.541562 -0.834157 -0.12113 0.538061 -0.832869 -0.121244 0.540028 -0.826477 -0.175013 0.535076 -0.820416 -0.176475 0.543852 -0.808933 -0.244323 0.534727 -0.666598 -0.341184 0.662752 -0.777944 -0.354182 0.518998 -0.739463 -0.463253 0.488458 0.995049 3.93804e-07 0.0993811 0.99505 7.81806e-07 0.0993752 0.99505 1.07405e-06 0.0993735 0.995033 -3.12053e-05 0.0995484 0.99505 -1.64512e-07 0.0993792 0.99505 -3.56752e-08 0.0993794 0.99505 -3.54819e-08 0.0993777 0.99505 2.55589e-07 0.0993778 0.99505 0 0.0993782 0.99505 -1.91095e-07 0.0993783 0.99505 -2.0364e-06 0.0993779 0.99505 -6.48254e-06 0.0993765 0.99505 -1.07695e-06 0.0993735 0.995033 3.12158e-05 0.0995484 0.99505 3.56752e-08 0.0993794 0.99505 3.55024e-08 0.0993779 0.99505 -3.44326e-07 0.0993777 0.99505 0 0.0993782 0.99505 -7.82446e-07 0.0993753 0.995049 -3.93804e-07 0.0993811 0.99505 8.83681e-07 0.0993749 0.99505 5.11978e-07 0.0993783 0.99505 6.49658e-06 0.0993766 0.99505 1.64511e-07 0.0993792 0.978368 0 -0.206874 0.957347 -0.138352 -0.253664 0.997318 0.0466739 -0.0563837 0.979837 -0.138352 0.144145 0.99545 0 0.0952837 0.148989 0.906308 0.395486 0.148989 0.906308 0.395485 0.148989 0.906308 0.395485 0.14899 0.906308 0.395486 0.148989 -0.906308 0.395485 0.148989 -0.906308 0.395485 0.148989 -0.906308 0.395485 0.148989 -0.906308 0.395486 0.0383799 0.994056 0.101878 0.0586868 0.976123 0.209139 0.11332 0.94693 0.300802 0.0763033 0.976296 0.202543 0.112465 0.993231 0.0290338 0.076763 0.976006 0.203764 0.000491425 -0.999999 0.00130446 0.0770899 -0.976296 0.202248 0.0767633 -0.976006 0.203765 0.0763029 -0.976296 0.202543 0.0763032 -0.976296 0.202543 0.00333234 -0.99337 0.114911 0.113319 -0.946931 0.300801 0.678123 0 0.734948 0.720556 -0.0392047 0.692287 0.788495 0.010304 0.614955 0.824107 0 0.566434 0.523515 -0.831602 0.185396 0.181877 -0.981229 0.0641061 0.183924 -0.980785 0.0650542 0.941759 -0.0461905 0.333101 0.931157 -0.15966 0.327803 0.937893 -0.0998355 0.33225 0.901295 -0.293734 0.318415 0.901808 -0.291901 0.318646 0.825923 -0.481905 0.292607 0.785644 -0.554189 0.275024 0.699491 -0.670249 0.247949 0.507798 -0.84285 0.178174 0.0339231 -0.996336 -0.0785158 0.174555 -0.980835 0.0865623 0.338441 -0.932901 0.123103 0.662361 -0.67915 0.316281 0.655163 -0.258015 0.710063 0.655163 -0.258014 0.710064 0.761837 -0.258015 0.594165 0.761837 -0.258016 0.594165 0.970768 -0.228342 0.0739542 0.480304 -0.705927 0.520553 0.480304 -0.705927 0.520552 0.558508 -0.705927 0.435586 0.558508 -0.705927 0.435587 0.597072 -0.707065 0.378898 0.775024 -0.395786 0.492638 0.176058 -0.965709 0.190811 0.176058 -0.965709 0.190811 0.204724 -0.965709 0.159666 0.204724 -0.96571 0.159666 0.22632 -0.965766 0.126786 0.523738 -0.795943 0.3036 0.594966 -0.25882 0.760939 0.596069 -0.248599 0.763479 0.436115 -0.707106 0.556601 0.444664 -0.690888 0.570042 0.159421 -0.965926 0.203893 -0.0154275 -0.999857 0.00699427 0.169209 -0.961812 0.215144 0.00593612 0.999982 0.000677858 0.00272252 0.999996 0.000962937 0.707524 0.193206 0.679766 0.808279 0.195047 0.555555 0.712835 0.554304 0.429666 0.755262 0.384895 0.530505 0.84468 0.154145 0.512596 0.00696805 0.999973 -0.00223995 0.00976557 0.999939 0.00510613 0.208243 0.972215 0.106922 0.170778 0.980563 0.096601 0.452022 0.85119 0.266743 0.484117 0.83007 0.276794 0.575788 0.730478 0.367247 0.672579 0.60044 0.432561 0.707524 0.193206 0.679766 0.601439 0.551697 0.577843 0.601439 0.551697 0.577843 0.403423 0.828866 0.387596 0.403423 0.828866 0.387596 0.142053 0.980405 0.13648 0.142053 0.980405 0.13648 0.120167 0.980785 0.153689 0.168751 0.963034 0.209974 0.340429 0.831467 0.439056 0.378906 0.788367 0.484673 0.512199 0.55557 0.654976 0.488639 0.604015 0.629601 0.604118 0.195091 0.772645 0.608397 0.0024472 0.793629 0.598052 0.253412 0.760339 -0.760937 -0.258826 0.594965 -0.760937 -0.258826 0.594965 -0.557047 -0.707105 0.435547 -0.557047 -0.707105 0.435547 -0.203892 -0.965926 0.15942 -0.203892 -0.965926 0.15942 0.203894 -0.965925 -0.159422 0.203894 -0.965925 -0.159422 0.557047 -0.707105 -0.435546 0.557044 -0.707111 -0.435541 0.760939 -0.258825 -0.594963 0.76094 -0.258815 -0.594967 0.76094 0.258814 -0.594967 0.76094 0.258815 -0.594967 0.557043 0.707111 -0.435543 0.557042 0.707111 -0.435543 0.203894 0.965925 -0.159422 0.203894 0.965925 -0.159422 -0.203892 0.965926 0.15942 -0.203892 0.965926 0.15942 -0.557047 0.707105 0.435546 -0.557047 0.707105 0.435546 -0.760938 0.258825 0.594965 -0.760937 0.258826 0.594965 -0.615954 -9.32356e-06 -0.787782 -0.615957 1.78332e-06 -0.78778 -0.615955 7.09703e-06 -0.787782 -0.615955 2.17565e-06 -0.787781 -0.615958 2.98194e-07 -0.787779 -0.615954 5.80181e-06 -0.787782 -0.615945 5.80188e-06 -0.78779 -0.615959 -8.73825e-07 -0.787778 -0.615964 2.78313e-06 -0.787775 -0.615953 4.45832e-07 -0.787783 -0.615951 -4.96994e-06 -0.787785 -0.615955 -9.27328e-07 -0.787782 -0.615955 -9.12477e-06 -0.787782 -0.615958 1.92598e-06 -0.787779 -0.615955 7.45487e-06 -0.787781 -0.615956 2.85331e-06 -0.787781 -0.615948 8.84651e-06 -0.787787 -0.615957 -5.87827e-06 -0.787779 -0.615959 -5.87826e-06 -0.787778 -0.615954 -3.63798e-06 -0.787782 -0.615953 -4.13497e-06 -0.787783 -0.615956 -3.46855e-06 -0.78778 -0.615961 6.6e-06 -0.787777 -0.615954 -6.77662e-07 -0.787782 0.76094 -0.258818 -0.594965 0.76094 -0.258819 -0.594965 0.557047 -0.707107 -0.435544 0.557047 -0.707107 -0.435544 0.203892 -0.965926 -0.15942 0.203893 -0.965926 -0.159422 -0.203892 -0.965926 0.159422 -0.203892 -0.965926 0.159422 -0.557044 -0.707107 0.435548 -0.557044 -0.707107 0.435548 -0.760936 -0.258819 0.59497 -0.760939 -0.258823 0.594964 -0.76094 0.258819 0.594965 -0.760935 0.258823 0.594969 -0.557044 0.707107 0.435548 -0.557044 0.707107 0.435548 -0.203893 0.965926 0.159422 -0.203893 0.965926 0.159422 0.203891 0.965926 -0.159421 0.203893 0.965926 -0.159421 0.557047 0.707107 -0.435545 0.557047 0.707107 -0.435545 0.76094 0.258819 -0.594965 0.76094 0.258819 -0.594965 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.983029 -0.182337 0.0202009 0.992939 -0.118026 0.011935 0.997605 -0.068553 0.00917149 0.99935 -0.0350863 0.00822802 0.904461 -0.426473 0.00839771 0.824459 -0.565516 -0.0214354 0.828921 -0.55904 -0.0190572 0.983628 -0.17917 0.0193242 0.983774 -0.179181 0.00913362 0.983774 -0.179182 0.0091341 0.823817 -0.565484 0.0394135 0.15237 -0.988321 0.00230977 0.252992 -0.967465 0.0024726 0.983769 -0.179182 0.00961478 0.962009 -0.272842 0.00984212 0.904457 -0.426473 0.00883541 0.859363 -0.511296 0.00839891 0.690656 -0.723152 0.00675007 0.697545 -0.716509 0.00674145 0.411943 -0.911201 0.00404811 0.322118 -0.946693 0.00339731 0.854516 -0.508987 0.103607 0.9555 -0.27129 0.115851 0.694722 -0.714381 0.0837923 0.252617 -0.967081 0.0306304 0.9555 -0.27129 0.115851 0.887047 -0.269246 0.375038 0.887047 -0.269248 0.375038 0.712903 -0.269247 0.647514 0.712902 -0.269251 0.647514 0.458384 -0.269252 0.846987 0.458385 -0.26925 0.846988 0.152187 -0.26925 0.95097 0.152188 -0.269243 0.950972 0.697944 -0.71111 0.0848392 0.650259 -0.708223 0.274926 0.650259 -0.708223 0.274926 0.5226 -0.708223 0.474667 0.5226 -0.708224 0.474667 0.336023 -0.708224 0.620892 0.336023 -0.708225 0.620892 0.111562 -0.708225 0.697116 0.111562 -0.708224 0.697117 0.255511 -0.966296 0.0314212 0.238968 -0.965757 0.101034 0.238967 -0.965757 0.101034 0.192054 -0.965757 0.174438 0.192054 -0.965757 0.174439 0.123488 -0.965757 0.228177 0.123489 -0.965756 0.228178 0.0409992 -0.965756 0.256191 0.0409984 -0.965757 0.256188 -0.00247253 -0.967465 0.252994 -0.00228196 -0.966675 0.255998 -0.00707549 -0.713252 0.700872 -0.00670488 -0.716512 0.697543 -0.00951445 -0.272833 0.962014 -0.00939799 -0.274331 0.96159 -0.831523 -0.269249 0.485875 -0.0999236 -0.273203 0.956752 -0.0723978 -0.714968 0.695398 -0.0264383 -0.967187 0.252687 -0.100143 -0.271714 0.957154 -0.242088 -0.272444 0.931218 -0.268277 -0.664611 0.697366 -0.39513 -0.271234 0.87767 -0.521706 -0.272668 0.808378 -0.517469 -0.601488 0.608636 -0.6504 -0.270655 0.709736 -0.831523 -0.269248 0.485876 -0.0732748 -0.711697 0.698654 -0.253484 -0.708224 0.658912 -0.253485 -0.708219 0.658917 -0.457301 -0.70822 0.537867 -0.457299 -0.708222 0.537865 -0.609557 -0.708222 0.356176 -0.609557 -0.708222 0.356176 -0.0271027 -0.966399 0.255614 -0.0931551 -0.965756 0.24215 -0.093154 -0.965757 0.242147 -0.168055 -0.965757 0.197662 -0.168055 -0.965757 0.197663 -0.224009 -0.965757 0.130893 -0.22401 -0.965757 0.130893 -0.900293 -0.272839 0.339163 -0.900293 -0.272839 0.339163 -0.655909 -0.71325 0.247098 -0.655909 -0.71325 0.247098 -0.239572 -0.966675 0.0902528 -0.239572 -0.966674 0.090253 -0.20102 -0.961448 0.187639 -0.201286 -0.961346 0.187877 -0.626871 -0.711309 0.317918 -0.626988 -0.711156 0.318031 -0.890045 -0.272805 0.365237 -0.890057 -0.272732 0.365261 -0.128714 -0.916396 0.379014 -0.129531 -0.916019 0.379646 -0.57428 -0.678622 0.457903 -0.574664 -0.678137 0.458139 -0.870883 -0.260879 0.416539 -0.870935 -0.260663 0.416566 -0.0963979 -0.876841 0.471017 -0.0963976 -0.876841 0.471017 -0.55191 -0.64809 0.524762 -0.55191 -0.64809 0.524762 -0.862429 -0.249087 0.44065 -0.862429 -0.249087 0.44065 -0.624588 -0.686608 0.372101 -0.374375 -0.757068 0.535436 -0.0152387 -0.903798 0.427688 -0.105402 -0.888702 0.446206 -0.337069 -0.825394 0.452889 -0.578203 -0.684049 0.4447 -0.902267 -0.315584 0.293806 0.036907 -0.92112 0.387525 -0.0161035 -0.92206 0.386713 -0.186037 -0.916454 0.354263 -0.34004 -0.881221 0.328362 -0.399803 -0.863614 0.30713 -0.625159 -0.745772 0.230219 -0.00100154 -0.999999 0.000934642 -0.312751 -0.948303 0.0539366 -0.11504 -0.983221 0.141568 -0.056721 -0.985359 0.16078 0.0937088 -0.973748 0.207443 -0.000379576 0.999999 0.00108871 0.0403327 0.979842 0.195662 -0.0562167 0.985315 0.161226 -0.165405 0.978883 0.12012 -0.312751 0.948303 0.0539366 -0.889922 0.291083 0.351155 -0.624593 0.686606 0.372098 -0.505373 0.730523 0.459276 -0.335607 0.811355 0.478614 -0.583092 0.690848 0.427473 -0.0150315 0.899412 0.436844 -0.10743 0.891279 0.440546 -0.408398 0.848389 0.336818 -0.623905 0.753496 0.207331 -0.245389 0.900821 0.358197 -0.34003 0.882883 0.323878 -0.0192583 0.924262 0.381273 -0.0161915 0.924005 0.382037 -0.862429 0.249087 0.44065 -0.862429 0.249087 0.44065 -0.551909 0.648091 0.524761 -0.55191 0.64809 0.524762 -0.0964021 0.87684 0.471018 -0.096402 0.87684 0.471018 -0.12968 0.916148 0.379282 -0.128594 0.916259 0.379386 -0.574756 0.678203 0.457927 -0.574214 0.678534 0.458116 -0.870963 0.260681 0.416497 -0.870861 0.260847 0.416605 -0.201338 0.96136 0.187748 -0.200977 0.961431 0.187771 -0.627021 0.71116 0.317956 -0.626846 0.711297 0.317994 -0.890067 0.272732 0.365237 -0.890036 0.2728 0.365262 -0.239572 0.966675 0.0902528 -0.239572 0.966674 0.0902531 -0.65591 0.71325 0.247098 -0.65591 0.71325 0.247098 -0.900293 0.272839 0.339163 -0.900293 0.272839 0.339163 -0.11005 0.710519 0.695019 -0.0775788 0.868293 0.489947 -0.150578 0.270095 0.950986 -0.839547 0.26994 0.47148 -0.225634 0.965936 0.126714 -0.839547 0.26994 0.471481 -0.661001 0.269966 0.70014 -0.661001 0.269966 0.70014 -0.42311 0.269968 0.864925 -0.423108 0.269976 0.864923 -0.150579 0.270116 0.95098 -0.134725 0.507836 0.850854 -0.110331 0.70944 0.696076 -0.309783 0.709235 0.633261 -0.309782 0.709236 0.633261 -0.483958 0.709233 0.512613 -0.483955 0.709237 0.512611 -0.614707 0.709199 0.345213 -0.614709 0.709197 0.345214 -0.225635 0.965936 0.126714 -0.177633 0.965943 0.188151 -0.177633 0.965943 0.188151 -0.113703 0.965944 0.232432 -0.113702 0.965944 0.232431 -0.040667 0.965988 0.255368 -0.0399735 0.966784 0.252449 -0.00250187 0.966675 0.255996 -0.00225001 0.967465 0.252996 -0.00480811 0.870601 0.491967 -0.00684981 0.713252 0.700874 -0.00940216 0.272832 0.962016 -0.00940212 0.272833 0.962016 -0.00839517 0.511931 0.858986 -0.00672795 0.714337 0.699769 0.69415 0.713881 0.0923562 0.252556 0.96698 0.0341498 0.954119 0.270931 0.127489 0.124928 0.270355 0.954621 0.124928 0.270359 0.95462 0.383295 0.270392 0.883161 0.383295 0.270396 0.88316 0.649843 0.268207 0.711174 0.649844 0.268204 0.711175 0.868619 0.268211 0.41661 0.868619 0.268212 0.41661 0.954117 0.270937 0.12749 0.853503 0.508456 0.114046 0.697365 0.710607 0.0933777 0.637887 0.706752 0.305945 0.637889 0.706749 0.305946 0.477232 0.70674 0.522272 0.477232 0.70674 0.522272 0.280428 0.709831 0.646143 0.280426 0.709838 0.646136 0.0914047 0.709793 0.698454 0.0914046 0.709792 0.698456 0.255552 0.966192 0.0341488 0.234843 0.965485 0.112636 0.234842 0.965486 0.112636 0.175697 0.965484 0.192279 0.175698 0.965484 0.19228 0.102853 0.966053 0.236987 0.102854 0.966053 0.236988 0.0335268 0.966044 0.256192 0.0335267 0.966045 0.256189 0.697545 0.716509 0.00674145 0.411943 0.911201 0.00404811 0.252988 0.967465 0.00288997 0.327322 0.944904 0.00403189 0.146912 0.989149 0.00143583 0.823817 0.565484 0.0394135 0.690656 0.723152 0.00675007 0.904457 0.426473 0.00883963 0.859367 0.511295 0.00813406 0.983762 0.179182 0.0103101 0.962013 0.272842 0.00940215 0.99935 0.035085 0.00822799 0.997605 0.0685557 0.00917157 0.992939 0.118024 0.0119348 0.983619 0.179169 0.0197935 0.982435 0.185662 0.0187197 0.828921 0.55904 -0.0190572 0.983774 0.179182 0.00913362 0.983774 0.179181 0.00913409 0.904461 0.426473 0.00839769 0.824459 0.565516 -0.0214354 0.987828 0.00935907 0.155266 0.986204 0.0114781 0.165138 0.945998 0.00050274 0.324173 0.999266 0.0153432 0.035096 0.992563 0.00506207 0.121624 0.986385 -0.00309005 0.164424 0.978236 0.000678289 0.207495 0.956386 0.00222518 0.292096 0.999349 0.00950323 0.034814 0.992625 -0.00694606 0.121028 0.978221 -0.0233929 0.206245 0.956257 -0.0397267 0.289816 0.999272 0.00961062 0.0369074 0.999462 -0.0040768 0.0325321 0.999188 -0.00658694 0.0397568 0.999351 -0.0194391 0.0303184 0.998883 -0.0258894 0.0395203 0.998955 -0.0382387 0.02503 0.997347 -0.060401 0.0406361 0.997398 -0.0682089 0.0233536 0.995632 -0.0873281 0.0330296 0.995573 -0.0926813 0.0156452 0.990875 -0.132118 0.026691 0.990808 -0.135208 0.00427133 0.983599 -0.180071 0.0104034 0.991859 -0.00660453 0.127168 0.992329 -0.0480865 0.113891 0.989294 -0.0557969 0.134848 0.989825 -0.0940566 0.106766 0.984555 -0.113619 0.1332 0.984556 -0.14965 0.0908526 0.967257 -0.215321 0.134353 0.9676 -0.237894 0.0845963 0.949599 -0.293111 0.111118 0.949246 -0.308713 0.0602336 0.903764 -0.418699 0.0888932 0.903532 -0.427965 0.0218256 0.836971 -0.546024 0.0365889 0.976064 -0.0227664 0.216289 0.97668 -0.0915031 0.194227 0.968009 -0.104699 0.22803 0.968944 -0.167137 0.182246 0.953867 -0.199871 0.224031 0.953595 -0.257427 0.156168 0.904781 -0.36355 0.221818 0.905526 -0.39915 0.143879 0.855639 -0.484275 0.182649 0.854907 -0.508379 0.103373 0.732427 -0.666058 0.141128 0.732011 -0.68018 0.0389156 0.560297 -0.826407 0.0558507 0.952026 -0.0387416 0.303555 0.95268 -0.133928 0.272881 0.935652 -0.152772 0.318146 0.937006 -0.23776 0.255911 0.907398 -0.283272 0.310461 0.906778 -0.359658 0.219999 0.812278 -0.500199 0.300009 0.813352 -0.546583 0.199263 0.718631 -0.651183 0.243988 0.71763 -0.681591 0.142972 0.493234 -0.851396 0.178452 0.492661 -0.868544 0.0539935 0.197089 -0.97822 0.0651254 0.999266 -0.0153432 0.0350961 0.945998 -0.00050274 0.324173 0.986204 -0.0114781 0.165138 0.987828 -0.00935907 0.155266 0.956386 -0.00222518 0.292096 0.986365 9.75836e-05 0.164574 0.978299 0.0112334 0.206891 0.992563 -0.00506207 0.121624 0.197231 -0.980357 -0.000307827 0.19723 -0.980357 -0.000307773 0.561002 -0.827814 -0.000875433 0.561001 -0.827815 -0.00087533 0.837479 -0.546468 -0.00130672 0.837481 -0.546466 -0.00130689 0.983649 -0.180088 -0.00153502 0.983649 -0.180089 -0.00153493 0.197228 -0.980357 0.00109676 0.197228 -0.980357 0.00109675 0.560995 -0.827813 0.00311958 0.560995 -0.827813 0.00311959 0.837469 -0.546465 0.00465701 0.837468 -0.546467 0.00465715 0.983635 -0.180091 0.00547001 0.983635 -0.180088 0.00546982 0.983649 0.180087 0.00169084 0.83745 0.54641 0.010634 0.560979 0.827672 0.0161941 0.359174 0.931782 0.0526886 0.197275 0.980206 0.0166789 0.987742 0.156023 0.00483008 0.987731 0.155031 0.0187823 0.994344 0.105133 0.0150625 0.9944 0.102698 0.0249204 0.995652 0.0898675 0.0244996 0.995618 0.0863292 0.0359497 0.998347 0.0519647 0.0245479 0.998301 0.042725 0.0396222 0.99924 0.0258511 0.0291893 0.999117 0.0143982 0.0394603 0.999453 0.00762572 0.0321812 0.999251 -0.00613476 0.0382107 0.999368 -0.00766327 0.0347249 0.874843 0.483917 0.0217596 0.874573 0.480733 0.0633943 0.937141 0.344221 0.0572577 0.937493 0.337082 0.0865015 0.949844 0.300463 0.0867048 0.949493 0.290345 0.11901 0.977711 0.190018 0.0893029 0.977604 0.16364 0.132337 0.988203 0.11282 0.103569 0.987859 0.0794207 0.133519 0.991897 0.0585132 0.112768 0.991254 0.0172593 0.130835 0.992605 0.0124847 0.120747 0.656543 0.753323 0.0381533 0.656115 0.748331 0.0975393 0.821836 0.561135 0.0985516 0.822504 0.550784 0.141861 0.856245 0.49565 0.145518 0.855493 0.480228 0.193681 0.934057 0.322277 0.153869 0.933906 0.281478 0.22043 0.96417 0.197097 0.177567 0.963622 0.14406 0.225122 0.975296 0.108139 0.192621 0.974173 0.0407807 0.22209 0.97807 0.032348 0.205749 0.359175 0.927784 0.101044 0.252382 0.96075 0.115162 0.656322 0.737779 0.157871 0.656559 0.730642 0.187327 0.719579 0.66553 0.198182 0.718631 0.646589 0.255915 0.868574 0.445557 0.216931 0.868371 0.393603 0.301676 0.927562 0.277411 0.250345 0.926811 0.207568 0.312948 0.949862 0.155887 0.271038 0.948217 0.0642499 0.311056 0.95591 0.0517309 0.289069 0.19722 -0.980357 0.00192751 0.19722 -0.980357 0.0019275 0.560974 -0.827816 0.00548261 0.560973 -0.827816 0.0054826 0.83744 -0.546468 0.00818461 0.837442 -0.546466 0.00818466 0.983603 -0.180092 0.00961315 0.983603 -0.180093 0.00961315 0.197228 0.980357 0.00109677 0.197228 0.980357 0.00109674 0.560995 0.827813 0.00311958 0.560995 0.827813 0.00311959 0.837468 0.546467 0.00465701 0.837469 0.546465 0.00465715 0.983635 0.180088 0.00547001 0.983635 0.180091 0.00546983 0.19723 0.980357 -0.000307825 0.197231 0.980357 -0.000307775 0.561001 0.827815 -0.000875431 0.561002 0.827814 -0.000875332 0.837481 0.546465 -0.00130672 0.837479 0.546468 -0.00130692 0.983649 0.18009 -0.00153503 0.983649 0.180088 -0.00153493 0.0223936 -0.980067 0.197399 0.0635645 -0.825842 0.560308 0.110908 -0.178776 0.977619 0.972913 -0.178384 0.147036 0.972914 -0.178379 0.147035 0.894655 -0.178401 0.409592 0.894654 -0.178405 0.409592 0.713246 -0.1769 0.678223 0.713246 -0.1769 0.678223 0.407916 -0.176906 0.895717 0.407918 -0.176897 0.895718 0.110907 -0.178772 0.97762 0.0946152 -0.543575 0.834011 0.094615 -0.543574 0.834012 0.348989 -0.539404 0.766322 0.348991 -0.539398 0.766325 0.610217 -0.53939 0.580253 0.610216 -0.539392 0.580253 0.76367 -0.542744 0.349624 0.763668 -0.542747 0.349624 0.830497 -0.542698 0.125513 0.830501 -0.542692 0.125512 0.063564 -0.825837 0.560315 0.235451 -0.822959 0.517011 0.235451 -0.82296 0.51701 0.411694 -0.822953 0.391479 0.411697 -0.822951 0.391481 0.513486 -0.825268 0.235084 0.513484 -0.825269 0.235084 0.558447 -0.825236 0.0843977 0.558446 -0.825236 0.0843977 0.0223936 -0.980067 0.197401 0.0832039 -0.979641 0.182702 0.0832046 -0.979641 0.182703 0.145487 -0.97964 0.138343 0.145486 -0.97964 0.138343 0.181011 -0.979983 0.0828708 0.181012 -0.979983 0.0828711 0.19687 -0.979978 0.0297527 0.196869 -0.979978 0.0297526 0.983603 0.180092 0.00961315 0.983603 0.180089 0.00961313 0.83744 0.546468 0.00818462 0.837439 0.546469 0.00818462 0.560974 0.827816 0.00548261 0.560973 0.827816 0.00548261 0.19722 0.980357 0.00192751 0.19722 0.980357 0.00192751 -0.00192753 -0.980357 0.19722 -0.00192752 -0.980357 0.19722 -0.00548264 -0.827817 0.560971 -0.00548261 -0.827817 0.560971 -0.00818466 -0.546468 0.83744 -0.00818463 -0.546469 0.83744 -0.00961315 -0.180088 0.983604 -0.00961314 -0.180088 0.983604 0.0199615 0.980122 0.197388 0.196787 0.97982 0.0350326 0.557579 0.824168 0.0992613 0.968853 0.177695 0.172479 0.0989941 0.17902 0.978852 0.365146 0.177611 0.91385 0.365146 0.17761 0.913851 0.647051 0.177612 0.74147 0.647051 0.177619 0.741469 0.857169 0.177548 0.483464 0.85717 0.177544 0.483465 0.968855 0.177683 0.172478 0.827909 0.541151 0.147386 0.82791 0.541149 0.147386 0.732628 0.540838 0.41322 0.732629 0.540836 0.413221 0.552981 0.540992 0.633672 0.55298 0.540993 0.633671 0.312059 0.540994 0.78099 0.312059 0.540994 0.780989 0.0844181 0.544118 0.834751 0.0989907 0.17904 0.978849 0.557577 0.82417 0.0992611 0.493561 0.823955 0.27838 0.49356 0.823956 0.27838 0.372475 0.824063 0.426827 0.372475 0.824064 0.426827 0.210196 0.824064 0.526058 0.210196 0.824065 0.526056 0.0566822 0.826214 0.560498 0.0844165 0.544124 0.834747 0.196785 0.979821 0.0350324 0.174231 0.979789 0.0982707 0.174232 0.979789 0.0982708 0.131472 0.979805 0.150657 0.131472 0.979805 0.150657 0.0741928 0.979805 0.185682 0.0741928 0.979805 0.185682 0.0199617 0.980122 0.197389 0.0566827 0.826212 0.5605 -0.174197 -0.979939 0.0968258 -0.174195 -0.979939 0.0968248 -0.493991 -0.824971 0.274581 -0.493991 -0.824972 0.274581 -0.734361 -0.542306 0.408189 -0.734355 -0.542315 0.408187 -0.860059 -0.17821 0.478059 -0.86006 -0.178205 0.478059 -0.0320507 -0.979913 0.196836 -0.0320505 -0.979913 0.196834 -0.0908726 -0.824795 0.558082 -0.0908727 -0.824795 0.558082 -0.135055 -0.542047 0.829425 -0.135055 -0.542052 0.829421 -0.158145 -0.178094 0.971222 -0.158145 -0.178089 0.971223 -0.0892156 -0.979917 0.178336 -0.0892158 -0.979917 0.178337 -0.252959 -0.824823 0.505647 -0.252959 -0.824823 0.505647 -0.375963 -0.54209 0.751525 -0.375964 -0.542088 0.751526 -0.440251 -0.178109 0.880032 -0.440251 -0.178112 0.880032 -0.138175 -0.979917 0.143771 -0.138175 -0.979917 0.143771 -0.391779 -0.824825 0.407644 -0.391779 -0.824825 0.407644 -0.582289 -0.542091 0.605869 -0.582288 -0.542093 0.605868 -0.681857 -0.178115 0.709469 -0.681857 -0.178111 0.70947 -0.00961313 0.180096 0.983602 -0.00961252 0.180088 0.983603 -0.0081841 0.546468 0.83744 -0.00818415 0.546469 0.83744 -0.00548232 0.827814 0.560976 -0.0054827 0.827817 0.560971 -0.00192754 0.980357 0.19722 -0.00192754 0.980357 0.19722 -0.184567 -0.980357 0.069531 -0.184566 -0.980357 0.0695309 -0.524984 -0.827815 0.197775 -0.524982 -0.827816 0.197774 -0.78371 -0.54647 0.295244 -0.783712 -0.546466 0.295244 -0.920498 -0.180087 0.346775 -0.920497 -0.180093 0.346775 -0.453231 0.178583 0.873321 -0.704049 0.178983 0.687227 -0.0355081 0.979805 0.196779 -0.883905 0.179314 0.431925 -0.883904 0.179321 0.431924 -0.753447 0.544762 0.368175 -0.753445 0.544765 0.368174 -0.505579 0.826652 0.247053 -0.505578 0.826654 0.247052 -0.177964 0.980187 0.0869627 -0.177965 0.980187 0.0869631 -0.0355083 0.979804 0.19678 -0.100598 0.824063 0.557494 -0.100598 0.824064 0.557494 -0.149348 0.540995 0.827659 -0.149348 0.540996 0.827658 -0.174755 0.177613 0.96846 -0.174756 0.177622 0.968458 -0.150653 0.979805 0.131477 -0.150653 0.979805 0.131476 -0.426816 0.824064 0.372487 -0.426817 0.824063 0.372488 -0.633656 0.540993 0.552998 -0.633655 0.540994 0.552998 -0.609353 0.588123 0.53179 -0.809306 0.179817 0.559186 -0.0986415 0.979805 0.173933 -0.0986409 0.979805 0.173932 -0.279461 0.824063 0.492769 -0.279461 0.824064 0.492768 -0.414889 0.540995 0.731568 -0.41489 0.540993 0.731569 -0.422123 0.517489 0.744323 -0.593262 0.179973 0.784633 -0.188594 -0.980538 0.054568 -0.178893 -0.980232 0.0845189 -0.527979 -0.828387 0.187117 -0.521179 -0.827769 0.207778 -0.785741 -0.54702 0.288756 -0.781799 -0.546458 0.300289 -0.921613 -0.180323 0.343675 -0.920293 -0.180092 0.347314 0.0304857 -0.966354 0.255404 -0.0829015 -0.945167 0.31589 -0.355832 -0.856708 0.37341 -0.43052 -0.806232 0.405762 -0.687063 -0.588907 0.425597 -0.720135 -0.539904 0.435785 -0.895874 -0.20045 0.396521 -0.900331 -0.179767 0.396343 0.273689 -0.713916 0.644529 0.19812 -0.698644 0.687492 -0.151198 -0.648555 0.746 -0.207679 -0.618235 0.75806 -0.55551 -0.451355 0.698346 -0.584541 -0.422672 0.692575 -0.853251 -0.1524 0.498735 -0.858887 -0.140361 0.492557 0.397756 -0.259658 0.879982 0.375588 -0.252483 0.891732 -0.0414185 -0.23273 0.971659 -0.0592705 -0.225448 0.972451 -0.481153 -0.157107 0.862444 -0.491069 -0.151684 0.857813 -0.827494 -0.0451842 0.559654 -0.829722 -0.0431504 0.556507 -0.184566 0.980357 0.0695308 -0.184567 0.980357 0.0695312 -0.524983 0.827816 0.197774 -0.524982 0.827816 0.197774 -0.783712 0.546467 0.295244 -0.783711 0.546468 0.295244 -0.920497 0.180092 0.346775 -0.920497 0.180089 0.346775 0.416302 0.00424453 0.909217 0.416302 0.00424452 0.909217 -0.0390839 0.011819 0.999166 -0.0390807 0.0118196 0.999166 -0.486041 0.0168464 0.873773 -0.486039 0.0168469 0.873775 -0.828247 0.0182433 0.560066 -0.82825 0.0182422 0.560062 0.416348 -0.00276406 0.909201 0.416246 -0.000539081 0.909252 -0.0390415 -0.0103987 0.999183 -0.0391296 -0.00862774 0.999197 -0.486024 -0.0157294 0.873804 -0.48607 -0.0147829 0.873795 -0.828247 -0.0178502 0.560079 -0.828256 -0.0176278 0.560073 -0.827667 0.0454281 0.559378 -0.830169 0.0453177 0.555667 -0.481729 0.157401 0.862068 -0.492621 0.158123 0.855758 -0.0418697 0.232223 0.971761 -0.0614456 0.235729 0.969874 0.398195 0.257432 0.880437 0.60873 0.708472 0.357093 0.303098 0.627841 0.716901 0.373678 0.265458 0.888762 -0.443509 0.810959 0.381635 -0.353401 0.851201 0.388027 -0.727773 0.541272 0.421154 -0.686145 0.584466 0.433134 -0.902465 0.179884 0.391406 -0.895344 0.198693 0.398597 -0.853207 0.15057 0.499365 -0.860486 0.142792 0.489055 -0.555735 0.445946 0.701634 -0.590113 0.430778 0.682786 -0.1503 0.639797 0.753704 -0.216402 0.63321 0.743112 0.195604 0.702456 0.684321 0.0372496 0.960038 0.27738 -0.0985986 0.954112 0.282751 -0.828247 -0.0182422 0.560066 -0.82825 -0.0182433 0.560062 -0.486041 -0.0168469 0.873773 -0.486039 -0.0168464 0.873775 -0.0390838 -0.0118196 0.999166 -0.0390807 -0.011819 0.999166 0.416302 -0.00424453 0.909217 0.416302 -0.00424453 0.909216 0.508402 0.694745 -0.508779 0.508402 0.694744 -0.50878 0.1859 0.694744 -0.694818 0.1859 0.694748 -0.694814 -0.186415 0.694748 -0.694676 -0.186415 0.694748 -0.694676 -0.508778 0.694747 -0.508401 -0.50878 0.694745 -0.508402 -0.694817 0.694745 -0.185899 -0.694816 0.694746 -0.185899 -0.694678 0.694746 0.186415 -0.694678 0.694746 0.186415 -0.508402 0.694746 0.508779 -0.508401 0.694748 0.508777 -0.185899 0.694748 0.694814 -0.185898 0.694748 0.694815 0.186415 0.694748 0.694676 0.186415 0.694748 0.694676 0.508778 0.694747 0.508401 0.508777 0.694748 0.5084 0.694816 0.694747 0.185899 0.694815 0.694747 0.185899 0.694679 0.694745 -0.186415 0.694678 0.694746 -0.186415 -0.50878 -0.694745 -0.508403 -0.508779 -0.694747 -0.5084 -0.186415 -0.694748 -0.694676 -0.186415 -0.694748 -0.694676 0.185899 -0.694748 -0.694815 0.185901 -0.694744 -0.694818 0.508402 -0.694744 -0.50878 0.508402 -0.694745 -0.50878 0.694678 -0.694746 -0.186415 0.694679 -0.694745 -0.186415 0.694815 -0.694747 0.185899 0.694816 -0.694747 0.185899 0.508777 -0.694748 0.5084 0.508778 -0.694747 0.508401 0.186415 -0.694748 0.694676 0.186415 -0.694748 0.694676 -0.185899 -0.694748 0.694815 -0.185898 -0.694748 0.694814 -0.5084 -0.694748 0.508778 -0.508402 -0.694746 0.508779 -0.694678 -0.694746 0.186415 -0.694678 -0.694746 0.186415 -0.694816 -0.694746 -0.185899 -0.694817 -0.694745 -0.185899 -0.597895 0.00125586 -0.801573 -0.44458 0.0119479 -0.895659 0.112433 0.0387432 -0.992904 0.768029 0.0552253 -0.63803 -0.963804 0.0564475 0.260569 -0.822905 0.0626189 0.564717 -0.987081 0.0423172 -0.154533 -0.998697 0.0492631 0.0133506 -0.91653 0.0288991 -0.39892 -0.633826 0.00142014 -0.773474 0.734953 0.118354 -0.66771 0.739276 0.0560168 -0.671069 0.513829 0.0508864 -0.856382 -0.0701165 0.993797 -0.0863245 -0.0698385 0.993797 -0.086542 -0.0734548 0.993105 -0.0913576 -0.0728028 0.993106 -0.0918672 -0.0773826 0.992189 -0.0978443 -0.0824735 0.992163 -0.0938636 -0.0858736 0.991406 -0.0986886 -0.0107637 0.987589 -0.15669 -0.00104201 0.989877 -0.141928 0.175726 0.943917 -0.279537 0.186752 0.946149 -0.264436 0.307822 0.880675 -0.36008 0.309531 0.881429 -0.356755 0.421745 0.790833 -0.443524 0.428599 0.792049 -0.434696 0.527929 0.67669 -0.513207 0.529071 0.677209 -0.511344 0.612169 0.542274 -0.575489 0.615031 0.542713 -0.572013 0.677036 0.394505 -0.621279 0.677262 0.394613 -0.620964 0.711153 0.274784 -0.647113 0.389397 0.206465 -0.897632 0.730641 0.155458 -0.664828 0.734709 0.118338 -0.667981 -0.462378 0.847288 0.261361 -0.357723 0.91627 0.180232 -0.353497 0.91661 0.186727 -0.227399 0.969856 0.0875767 -0.2305 0.969623 0.081863 -0.18355 0.981978 0.0450473 -0.208834 0.963749 -0.166062 -0.105008 0.993321 -0.047828 -0.0648711 0.994733 -0.0793614 -0.434812 0.0122785 -0.900437 -0.435746 0.0252078 -0.899717 -0.435803 0.0251981 -0.899689 -0.438554 0.0495904 -0.897336 -0.437412 0.04997 -0.897872 -0.4481 0.0840897 -0.89002 -0.448123 0.0840694 -0.89001 -0.460025 0.116556 -0.880222 -0.460527 0.11616 -0.880012 -0.479438 0.143856 -0.865705 -0.479534 0.143709 -0.865676 -0.499622 0.169525 -0.849494 -0.500559 0.168144 -0.849216 -0.525126 0.185862 -0.83048 -0.525309 0.185258 -0.8305 -0.550195 0.200599 -0.810584 -0.551018 0.198147 -0.810627 -0.588153 0.206925 -0.78183 -0.588477 0.204337 -0.782266 -0.604101 0.204256 -0.770287 -0.604032 0.205078 -0.770123 -0.60298 0.205081 -0.770946 -0.602848 0.206168 -0.770759 -0.60299 0.206168 -0.770648 -0.602894 0.207009 -0.770497 -0.602962 0.20701 -0.770444 -0.602828 0.208175 -0.770235 -0.612898 0.208101 -0.762267 -0.612726 0.212765 -0.761116 -0.640888 0.206125 -0.739443 -0.641028 0.20687 -0.739113 -0.668162 0.196693 -0.717546 -0.667927 0.195749 -0.718022 -0.689714 0.179886 -0.701381 -0.689407 0.179452 -0.701794 -0.714195 0.158345 -0.681801 -0.714043 0.158109 -0.682015 -0.74048 0.116593 -0.661888 -0.741086 0.117082 -0.661123 -0.756825 0.0807744 -0.648608 -0.756648 0.0806831 -0.648826 -0.763222 0.0520089 -0.644039 -0.7628 0.0520544 -0.644536 -0.76646 0.0311548 -0.641537 -0.7653 0.0309794 -0.642927 -0.766022 0.023708 -0.642377 -0.765875 0.0237038 -0.642552 -0.766692 0.0134067 -0.641875 -0.751131 0.0124531 -0.660036 -0.961382 0.0377412 -0.272618 -0.959237 0.0669645 -0.274553 -0.959424 0.0669637 -0.2739 -0.957322 0.0875297 -0.275452 -0.958647 0.0878812 -0.270689 -0.948962 0.146752 -0.279167 -0.949526 0.146547 -0.277353 -0.929437 0.227179 -0.290752 -0.929639 0.22739 -0.289939 -0.886097 0.330129 -0.32534 -0.885415 0.328952 -0.328377 -0.809077 0.444447 -0.384527 -0.8092 0.445113 -0.383498 -0.741474 0.506176 -0.440457 -0.741834 0.507325 -0.438524 -0.679106 0.55098 -0.485011 -0.678846 0.55339 -0.482625 -0.603227 0.583223 -0.54403 -0.603512 0.581126 -0.545954 -0.523541 0.598653 -0.606234 -0.527301 0.587991 -0.613368 -0.499018 0.588516 -0.636105 -0.500309 0.585496 -0.637876 -0.500129 0.585496 -0.638017 -0.501052 0.583318 -0.639287 -0.500657 0.583319 -0.639595 -0.50179 0.580687 -0.6411 -0.504753 0.580675 -0.63878 -0.505571 0.578554 -0.640057 -0.461111 0.578013 -0.673259 -0.458428 0.584381 -0.669584 -0.35328 0.55884 -0.750261 -0.349105 0.565257 -0.747403 -0.279241 0.523373 -0.80505 -0.278483 0.52471 -0.804442 -0.20903 0.473437 -0.855666 -0.205638 0.476681 -0.854686 -0.14906 0.405116 -0.902032 -0.148379 0.405833 -0.901822 -0.095201 0.326767 -0.940298 -0.0934336 0.327767 -0.940127 -0.0596417 0.237011 -0.969674 -0.0595181 0.237093 -0.969662 -0.029839 0.140653 -0.989609 -0.0331785 0.139804 -0.989623 -0.0252446 0.071022 -0.997155 -0.0249873 0.0710554 -0.997159 -0.0223489 0.0344032 -0.999158 -0.133794 0.0273734 -0.990631 -0.988053 0.054904 0.144003 -0.985051 0.0985335 0.141299 -0.984889 0.0984912 0.142452 -0.981725 0.128794 0.1401 -0.98064 0.128973 0.147345 -0.967049 0.215516 0.135534 -0.966731 0.214941 0.138676 -0.935759 0.332506 0.117454 -0.935528 0.332676 0.118803 -0.872578 0.483743 0.0678256 -0.873576 0.482695 0.0622161 -0.760121 0.649412 -0.0218973 -0.759449 0.650281 -0.0192819 -0.661705 0.742942 -0.100916 -0.661193 0.743887 -0.097247 -0.568566 0.80564 -0.166366 -0.566647 0.807938 -0.161701 -0.456432 0.85368 -0.250798 -0.457952 0.85171 -0.254697 -0.340982 0.87516 -0.343259 -0.350475 0.865359 -0.35822 -0.308715 0.866752 -0.391709 -0.311974 0.863598 -0.39607 -0.311716 0.863598 -0.396272 -0.313912 0.861443 -0.399219 -0.313334 0.861444 -0.39967 -0.316193 0.858649 -0.403416 -0.320576 0.858628 -0.399986 -0.322601 0.856491 -0.402928 -0.256966 0.854164 -0.452077 -0.250692 0.860705 -0.443102 -0.096202 0.821639 -0.561831 -0.0880476 0.828263 -0.553379 0.0156725 0.769497 -0.638459 0.0170544 0.770946 -0.636672 0.117468 0.693149 -0.711158 0.123426 0.696637 -0.706727 0.208167 0.594094 -0.776994 0.209193 0.594866 -0.776127 0.284855 0.477295 -0.831292 0.287623 0.478355 -0.829728 0.339441 0.347114 -0.874238 0.339559 0.347179 -0.874166 0.380226 0.20535 -0.901809 0.377153 0.204761 -0.903232 0.389935 0.10406 -0.914944 0.390097 0.104076 -0.914873 0.39394 0.0498293 -0.917785 0.277369 0.0447944 -0.959719 -0.842415 0.0616384 0.535292 -0.8389 0.112911 0.532446 -0.838013 0.112774 0.533869 -0.834389 0.147528 0.531066 -0.829601 0.147216 0.5386 -0.813984 0.246235 0.526117 -0.811891 0.245003 0.529912 -0.776819 0.37867 0.503151 -0.775837 0.378617 0.504704 -0.703989 0.550965 0.448149 -0.708306 0.551297 0.440879 -0.614359 0.698158 0.367612 -0.76765 0.639176 -0.0465593 -0.513323 0.806 0.294725 -0.464355 0.847731 0.256374 -0.633826 -0.00107786 -0.773475 -0.916702 -0.0214669 -0.398994 -0.75115 -0.0102156 -0.660053 -0.999209 -0.0374452 0.0133579 -0.987455 -0.0321655 -0.154591 -0.964472 -0.042459 0.26075 0.739079 -0.0600871 -0.670934 0.76776 -0.0612323 -0.637806 0.513699 -0.0556404 -0.856165 0.393817 -0.0540464 -0.917599 0.277317 -0.0488534 -0.959536 0.112417 -0.0422546 -0.992762 -0.0224424 -0.0372371 -0.999054 -0.133784 -0.0299777 -0.990557 -0.444575 -0.0128634 -0.895649 -0.434822 -0.0132784 -0.900418 -0.597895 -0.00137127 -0.801573 -0.823612 -0.0469978 0.565203 -0.844314 -0.0479562 0.533699 -0.841963 -0.0908184 0.531836 -0.977445 -0.101752 0.18506 -0.835123 -0.130082 0.534461 -0.824315 -0.209147 0.526082 -0.820264 -0.373732 0.433003 -0.808515 -0.263775 0.526048 -0.818694 -0.210827 0.534128 -0.77766 -0.372746 0.506266 -0.725005 -0.508645 0.464379 -0.72699 -0.507822 0.462172 -0.652814 -0.640137 0.405041 -0.65697 -0.639338 0.399546 -0.530584 -0.793003 0.299378 -0.311839 -0.937401 0.155037 -0.372334 -0.905744 0.202474 -0.592505 -0.801702 -0.0788197 -0.457544 -0.853414 0.249677 -0.526526 -0.794102 0.303598 -0.766566 -0.0105437 -0.642079 -0.765767 -0.0238575 -0.642676 -0.76636 -0.0239836 -0.641964 -0.763729 -0.044175 -0.644024 -0.764595 -0.0447059 -0.642959 -0.757054 -0.0794168 -0.648508 -0.757297 -0.0795988 -0.648202 -0.745252 -0.107787 -0.658013 -0.745091 -0.107502 -0.658242 -0.730361 -0.136392 -0.669306 -0.730325 -0.136334 -0.669356 -0.702234 -0.167412 -0.691983 -0.702387 -0.168081 -0.691666 -0.679214 -0.187862 -0.70949 -0.679571 -0.189677 -0.708665 -0.65918 -0.199919 -0.724924 -0.659172 -0.199995 -0.72491 -0.635368 -0.210032 -0.743098 -0.635442 -0.207237 -0.743819 -0.604635 -0.210213 -0.768263 -0.605024 -0.208021 -0.768553 -0.60284 -0.208032 -0.770264 -0.602965 -0.207192 -0.770393 -0.602854 -0.207192 -0.770479 -0.603004 -0.206132 -0.770647 -0.603034 -0.206128 -0.770624 -0.603166 -0.205215 -0.770764 -0.602705 -0.205215 -0.771125 -0.602705 -0.205218 -0.771124 -0.602848 -0.205218 -0.771012 -0.602751 -0.205843 -0.770922 -0.585981 -0.204302 -0.784147 -0.585633 -0.205077 -0.784205 -0.558981 -0.200418 -0.804595 -0.557848 -0.20315 -0.804696 -0.532883 -0.189621 -0.82467 -0.532499 -0.190074 -0.824813 -0.507665 -0.174199 -0.84376 -0.506695 -0.175415 -0.844091 -0.485161 -0.150424 -0.861389 -0.484809 -0.15066 -0.861546 -0.464534 -0.123288 -0.876931 -0.463953 -0.123662 -0.877186 -0.450825 -0.0913871 -0.887922 -0.450685 -0.0914163 -0.88799 -0.961401 -0.0295866 -0.273557 -0.95901 -0.0673838 -0.275244 -0.959773 -0.067715 -0.27249 -0.95239 -0.124537 -0.278288 -0.953345 -0.125906 -0.274373 -0.930564 -0.223589 -0.289929 -0.930815 -0.224041 -0.288773 -0.898458 -0.304164 -0.316635 -0.898375 -0.303354 -0.317646 -0.854966 -0.384066 -0.348608 -0.854908 -0.383631 -0.349227 -0.778433 -0.472447 -0.413323 -0.778181 -0.474215 -0.411771 -0.711889 -0.529199 -0.461695 -0.711113 -0.533793 -0.457585 -0.654433 -0.563689 -0.503956 -0.654447 -0.563658 -0.503973 -0.586193 -0.59061 -0.554578 -0.588725 -0.583696 -0.559198 -0.502688 -0.593243 -0.628782 -0.505291 -0.588127 -0.631496 -0.499144 -0.588172 -0.636325 -0.500198 -0.585925 -0.637568 -0.499886 -0.585926 -0.637812 -0.501172 -0.583112 -0.63938 -0.501258 -0.583113 -0.639311 -0.502094 -0.581296 -0.64031 -0.500797 -0.581296 -0.641325 -0.500947 -0.580971 -0.641502 -0.501318 -0.58097 -0.641213 -0.500612 -0.582467 -0.640406 -0.453551 -0.578501 -0.677959 -0.452007 -0.580386 -0.677379 -0.376045 -0.565778 -0.733816 -0.370991 -0.572392 -0.731254 -0.300965 -0.535636 -0.788996 -0.299675 -0.536598 -0.788833 -0.229413 -0.490484 -0.840711 -0.225205 -0.493893 -0.839853 -0.164543 -0.424631 -0.890289 -0.163569 -0.425061 -0.890263 -0.106523 -0.346905 -0.931831 -0.104372 -0.347861 -0.931719 -0.0671374 -0.257693 -0.963892 -0.066897 -0.25772 -0.963901 -0.988877 -0.0426178 0.142503 -0.985195 -0.0991546 0.139854 -0.984494 -0.0995252 0.144454 -0.973679 -0.18293 0.135962 -0.97237 -0.184737 0.142721 -0.937508 -0.327204 0.118394 -0.93709 -0.32769 0.120339 -0.891239 -0.446209 0.0811751 -0.891918 -0.44518 0.0793462 -0.826508 -0.56201 0.0320933 -0.827405 -0.560841 0.029302 -0.717475 -0.693796 -0.0622595 -0.71575 -0.695847 -0.0591447 -0.617997 -0.77483 -0.13311 -0.613632 -0.77968 -0.124719 -0.531204 -0.825251 -0.191792 -0.531208 -0.825247 -0.191796 -0.431007 -0.862065 -0.266601 -0.438462 -0.855018 -0.27694 -0.312284 -0.871279 -0.378619 -0.318135 -0.866329 -0.385051 -0.30902 -0.866418 -0.392208 -0.311601 -0.864072 -0.395328 -0.311133 -0.864073 -0.395694 -0.314193 -0.861221 -0.399477 -0.314312 -0.861221 -0.399383 -0.316404 -0.859266 -0.401933 -0.314485 -0.859267 -0.403433 -0.314798 -0.858976 -0.403811 -0.315299 -0.858975 -0.40342 -0.314189 -0.859998 -0.402106 -0.244727 -0.854894 -0.457455 -0.241517 -0.856859 -0.45548 -0.130226 -0.832506 -0.538494 -0.120426 -0.839127 -0.530437 -0.0166597 -0.787938 -0.615529 -0.0141324 -0.788887 -0.614376 0.0875411 -0.718642 -0.689848 0.0944871 -0.721805 -0.685617 0.184971 -0.622726 -0.760262 0.186889 -0.623116 -0.759473 0.268299 -0.506861 -0.819212 0.271657 -0.507708 -0.817578 0.328404 -0.377401 -0.865863 0.328716 -0.377396 -0.865747 0.707348 -0.291083 -0.64415 0.664914 -0.42894 -0.611474 0.664535 -0.429037 -0.611817 0.597059 -0.576043 -0.558296 0.593263 -0.576103 -0.562267 0.503578 -0.70951 -0.492955 0.501494 -0.709771 -0.494701 0.395836 -0.821086 -0.411255 0.387352 -0.820665 -0.420079 0.273767 -0.902582 -0.33226 0.270506 -0.902685 -0.334644 0.149645 -0.959388 -0.239125 0.136044 -0.957675 -0.253674 0.0100118 -0.987652 -0.156345 0.00525771 -0.987127 -0.159851 -0.0752474 -0.992478 -0.0965711 -0.0762113 -0.992291 -0.0977251 -0.0756651 -0.992291 -0.098152 -0.0751491 -0.992392 -0.0975227 -0.0773734 -0.992391 -0.0957836 -0.0740041 -0.993037 -0.0916563 -0.0738821 -0.993037 -0.0917518 -0.0689454 -0.993939 -0.0856303 -0.0695045 -0.993937 -0.085193 -0.0653798 -0.994634 -0.0801818 -0.0759374 -0.994516 -0.0719183 -0.0671889 -0.995797 -0.0622449 -0.148255 -0.988949 0.00105956 -0.430767 -0.862804 -0.26459 -0.232488 -0.968121 0.0932219 -0.311865 -0.937395 0.155018 0.72937 -0.164011 -0.664168 0.493781 -0.251217 -0.832509 0.372009 -0.235731 -0.897797 0.373841 -0.235859 -0.897002 -0.036099 -0.161301 -0.986245 -0.0342558 -0.16158 -0.986265 -0.439526 -0.0573281 -0.896399 -0.438966 -0.0574524 -0.896665 0.734202 -0.125841 -0.667167 0.733795 -0.125857 -0.667611 0.389433 -0.110664 -0.914383 0.389127 -0.110656 -0.914514 -0.0255048 -0.0755393 -0.996817 -0.0259094 -0.0755131 -0.996808 -0.435911 -0.0268007 -0.899591 -0.436022 -0.0267899 -0.899537 0.96583 0 -0.259178 0.96583 0 -0.259178 0.706844 0 -0.707369 0.706844 0 -0.707369 0.258461 0 -0.966022 0.258461 0 -0.966022 -0.259178 0 -0.96583 -0.259178 0 -0.96583 -0.707369 0 -0.706844 -0.707369 0 -0.706844 -0.966022 0 -0.258461 -0.966022 0 -0.258461 -0.96583 0 0.259178 -0.96583 0 0.259178 -0.706844 0 0.707369 -0.706844 0 0.707369 -0.258461 0 0.966022 -0.258461 0 0.966022 0.259178 0 0.96583 0.259178 0 0.96583 0.707369 0 0.706844 0.707369 0 0.706844 0.966022 0 0.258461 0.966022 0 0.258461 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.96583 0 -0.259178 0.96583 0 -0.259178 0.706844 0 -0.707369 0.706844 0 -0.707369 0.258461 0 -0.966022 0.258461 0 -0.966022 -0.259178 0 -0.96583 -0.259178 0 -0.96583 -0.707369 0 -0.706844 -0.707369 0 -0.706844 -0.966022 0 -0.258461 -0.966022 0 -0.258461 -0.96583 0 0.259178 -0.96583 0 0.259178 -0.706844 0 0.707369 -0.706844 0 0.707369 -0.258461 0 0.966022 -0.258461 0 0.966022 0.259178 0 0.96583 0.259178 0 0.96583 0.707369 0 0.706844 0.707369 0 0.706844 0.966022 0 0.258461 0.966022 0 0.258461 -0.0272827 -0.508584 -0.86058 -0.0272699 -0.508595 -0.860574 -0.281277 -0.69475 -0.661971 -0.281277 -0.694751 -0.66197 -0.574581 -0.69475 -0.432642 -0.574581 -0.694749 -0.432643 -0.82859 -0.508591 -0.234039 -0.82859 -0.508593 -0.234034 -0.975241 -0.186157 -0.119372 -0.97524 -0.186157 -0.11938 -0.975241 0.186155 -0.11938 -0.975241 0.186158 -0.119374 -0.82859 0.508593 -0.234035 -0.82859 0.50859 -0.234039 -0.574581 0.694749 -0.432643 -0.574581 0.694749 -0.432643 -0.281277 0.69475 -0.661971 -0.281277 0.69475 -0.661971 -0.0272675 0.508593 -0.860575 -0.0272841 0.508587 -0.860578 0.119366 0.186154 -0.975243 0.119385 0.186154 -0.97524 0.119385 -0.186158 -0.97524 0.119367 -0.18615 -0.975243 -0.998011 0 0.0630375 -0.997216 -0.00107267 0.074566 -0.992203 -0.00744716 0.124412 -0.99654 0.0138726 0.0819436 -0.995829 -0.00908725 0.0907915 -0.996683 -0.0039324 0.0812911 -0.923413 0.202776 0.32587 -0.923454 0.203044 0.325587 -0.789492 0.406877 0.459514 -0.977818 0.0431748 0.204961 -0.868136 0.125945 0.480081 -0.975293 0.0425789 0.216774 -0.975825 0.0639026 0.209002 -0.970953 0.0674491 0.229565 -0.971708 0.0816964 0.221608 -0.970366 0.0779857 0.228708 -0.970962 0.0893156 0.221934 -0.963659 0.0995568 0.24789 -0.964681 0.109731 0.239478 -0.956083 0.124473 0.265354 -0.959145 0.207947 0.191829 -0.956783 0.16675 0.238247 -0.860039 0.124526 0.494798 -0.861519 0.189717 0.470949 -0.846152 0.193377 0.496621 -0.848753 0.235506 0.47345 -0.844966 0.229567 0.483043 -0.846644 0.268657 0.459366 -0.824052 0.280902 0.491967 -0.829082 0.331118 0.450538 -0.80178 0.350552 0.484006 -0.806809 0.37917 0.453088 -0.798119 0.378165 0.46904 -0.801371 0.395625 0.448648 -0.831571 0.391317 0.394158 -0.998245 0 0.0592189 -0.997763 0.00011337 0.0668578 -0.996737 0.00263909 0.0806696 -0.996759 0.00243428 0.0804115 -0.993608 -0.00167126 0.112875 -0.992221 0.0131029 0.1238 -0.693736 -0.507384 0.511167 -0.737293 -0.3521 0.576563 -0.792996 -0.0221078 0.608826 -0.734482 -0.369056 0.569503 -0.753307 -0.287685 0.591409 -0.775881 -0.19896 0.598685 -0.776121 -0.189239 0.601519 -0.783231 -0.000138917 0.621731 -0.803277 -0.125093 0.582321 -0.800006 -0.0929789 0.592744 -0.661772 -0.560856 0.497492 -0.657565 -0.553258 0.511384 -0.705128 -0.443856 0.552979 -0.70186 -0.456285 0.546989 -0.716728 -0.415053 0.560386 -0.66066 0.560757 0.499079 -0.663727 0.541754 0.515722 -0.68853 0.513551 0.512046 -0.738118 0.35197 0.575586 -0.737461 0.353591 0.575434 -0.705487 0.443733 0.552621 -0.708221 0.438219 0.553523 -0.687831 0.487445 0.537852 -0.784808 0.0747647 0.615213 -0.778459 0.161769 0.606491 -0.776577 0.198686 0.597873 -0.763426 0.247295 0.596679 -0.751108 0.301497 0.587313 -0.998903 0 0.0468256 -0.999364 0 0.0356547 -0.999686 7.79734e-06 0.0250521 -0.999361 -0.00106446 0.0357379 -0.999686 0 0.0250515 -0.998903 0 0.0468256 -0.998747 -0.000871178 0.0500375 -0.998982 0 0.0451135 -0.998886 0.000325919 0.0471813 -0.998707 0.00108647 0.0508312 0.0317372 4.59273e-07 -0.999496 0.0317382 -5.28974e-07 -0.999496 0.0317345 1.11843e-05 -0.999496 0.0317384 2.51678e-06 -0.999496 0.0317379 0 -0.999496 0.0317386 1.06458e-06 -0.999496 0.0317377 5.69652e-07 -0.999496 0.0317371 -2.89124e-05 -0.999496 0.683974 0.455233 -0.570037 0.679051 -0.48329 -0.552558 0.643531 -0.568397 -0.512633 0.71422 -0.455758 -0.531201 0.679135 -0.49374 -0.543136 0.641643 0.568382 -0.515012 0.732426 0.455239 -0.50627 0.685149 0.492921 -0.536283 0.743359 0.331699 -0.580855 0.735244 0.34927 -0.580885 0.775378 0.20147 -0.598497 0.768262 0.220676 -0.600895 0.78606 0.0675694 -0.614447 0.780797 0.0926822 -0.617872 0.790865 -0.0675672 -0.60825 0.787107 -0.0426676 -0.615339 0.771598 -0.201474 -0.603362 0.771652 -0.16899 -0.613185 0.750066 -0.331678 -0.572181 0.751158 -0.302001 -0.58699 0.714414 -0.421291 -0.558683 -0.116982 0 -0.993134 -0.135501 0.000566339 -0.990777 -0.454181 -0.000706401 -0.890909 -0.421582 0.000668023 -0.90679 -0.650443 -0.000310531 -0.759555 -0.637017 -1.85081e-07 -0.77085 -0.764369 4.20108e-07 -0.644779 -0.756112 0.000242865 -0.654442 -0.905155 -0.0004715 -0.425081 -0.89086 0.000739956 -0.454278 -0.989144 -0.00058216 -0.146949 -0.991859 0 -0.127342 0.30297 -0.186764 -0.93452 0.590811 -0.407513 -0.69633 0.447438 -0.396486 -0.801622 0.132894 -0.200855 -0.970565 0.358847 0.187132 -0.914446 0.653166 0.367084 -0.662287 0.502223 0.348098 -0.79158 0.639729 0.419536 -0.644001 0.562636 -0.38051 -0.73393 0.59178 -0.335536 -0.732948 0.68873 -0.30698 -0.656822 0.602932 -0.232507 -0.76316 0.63136 -0.133415 -0.763927 0.745135 -0.0748451 -0.6627 0.637644 -0.0333266 -0.76961 0.632102 0.0723137 -0.771504 0.742092 0.173196 -0.647536 0.634945 0.17619 -0.752198 0.596612 0.272043 -0.755014 0.228965 -0.131314 -0.964537 0.251082 -0.0968924 -0.963104 0.23497 -0.0924231 -0.967599 0.254122 -0.0220819 -0.96692 0.250012 -0.0223185 -0.967985 0.245344 0.0491168 -0.968191 0.254042 0.0527731 -0.965752 0.226674 0.118744 -0.966705 0.178047 0.0793776 -0.980815 -0.832764 -0.357836 0.422442 -0.957087 -0.107099 0.269286 -0.747632 -0.453683 0.484993 -0.804657 -0.402425 0.436556 -0.799656 -0.373185 0.470409 -0.955992 -0.125 0.265433 -0.962493 -0.116007 0.245256 -0.806834 -0.307754 0.504287 -0.820068 -0.318935 0.475152 -0.822087 -0.336629 0.459189 -0.968804 -0.0849526 0.232814 -0.974294 -0.0668681 0.215128 -0.973885 -0.0553564 0.22019 -0.977412 -0.0452906 0.206435 -0.977311 -0.036799 0.208587 -0.977743 -0.0329819 0.207196 -0.962172 -0.11315 0.247836 -0.96902 -0.08815 0.230715 -0.842246 -0.286749 0.456505 -0.838998 -0.234143 0.491183 -0.857144 -0.20955 0.470523 -0.855197 -0.154073 0.494873 -0.86684 -0.14033 0.478431 -0.866721 -0.10476 0.487668 -0.868221 -0.0993118 0.486137 0.615954 -8.79321e-07 0.787782 0.615958 7.62785e-06 0.787779 0.615956 1.65063e-06 0.787781 0.615952 -2.77242e-06 0.787784 0.615955 1.51011e-06 0.787781 0.615964 -8.69367e-06 0.787775 0.6159 4.81961e-05 0.787825 0.615947 7.03307e-06 0.787787 0.615954 -2.03405e-07 0.787782 0.615958 1.0299e-06 0.787779 0.615954 -1.29931e-07 0.787782 0.615946 -6.74991e-06 0.787788 0.615954 -3.57465e-07 0.787782 0.615953 4.63709e-06 0.787783 0.615957 -7.78477e-06 0.78778 0.615953 6.52413e-07 0.787783 0.615964 -8.39831e-06 0.787775 0.615957 -3.15471e-06 0.78778 0.615954 -1.08613e-07 0.787782 0.615946 -3.00176e-06 0.787788 0.615954 -8.98263e-07 0.787782 0.615901 -4.81965e-05 0.787824 0.615964 8.69366e-06 0.787775 0.615956 9.2925e-07 0.78778 0.61596 6.77922e-06 0.787777 0.615954 -1.50453e-07 0.787782 0.615952 -5.25636e-06 0.787784 0.615955 3.89142e-07 0.787781 0.615955 6.53023e-06 0.787781 0.615954 -2.70397e-07 0.787782 0.615958 -9.36705e-06 0.787779 0.615956 -3.3124e-07 0.787781 0.615956 -9.2925e-07 0.78778 -0.977645 -0.026713 0.208558 -0.867787 -0.0767006 0.490982 -0.978399 -0.0241304 0.205314 -0.978211 -0.00615939 0.207521 -0.978533 -0.00563986 0.206014 -0.978586 0.0200656 0.204857 -0.977476 0.0192653 0.210166 -0.870791 -0.0723375 0.486303 -0.869964 -0.0177422 0.492796 -0.871236 -0.0168491 0.490574 -0.87136 0.0583678 0.487161 -0.867024 0.0568478 0.495012 0.802688 0.194597 0.563758 0.890423 0.444125 0.0994997 0.71787 0.564242 -0.407792 0.879162 -0.323717 0.349688 0.73745 -0.112217 0.666014 0.833048 -0.526541 -0.169661 0.873078 -0.486915 -0.0254681 0.680074 0.123215 0.722716 0.838579 0.522282 -0.154939 0.77547 0.566442 -0.278907 0.836457 0.440398 -0.326173 0.836458 0.440398 -0.326172 0.87705 0.320444 -0.35791 0.877049 0.320445 -0.357912 0.904529 0.194638 -0.379398 0.904529 0.194638 -0.3794 0.918395 0.0652772 -0.390242 0.918396 0.0652769 -0.390241 0.918396 -0.0652772 -0.390241 0.918395 -0.0652769 -0.390242 0.904529 -0.194638 -0.3794 0.904529 -0.194638 -0.379398 0.877049 -0.320444 -0.357912 0.87705 -0.320445 -0.35791 0.836458 -0.440398 -0.326172 0.836457 -0.440398 -0.326173 0.77551 -0.566373 -0.278937 0.712119 -0.564946 -0.4168 0.881697 0.32948 0.337717 0.885405 0.41791 0.203493 0.931412 0.322713 0.16831 0.931412 0.322714 0.168308 0.961157 0.234814 0.145051 0.961157 0.234814 0.145052 0.981294 0.142626 0.129307 0.981294 0.142626 0.129306 0.991455 0.0478331 0.121362 0.991455 0.0478329 0.121362 0.991455 -0.0478331 0.121362 0.991455 -0.047833 0.121361 0.981294 -0.142626 0.129306 0.981294 -0.142626 0.129307 0.961157 -0.234814 0.145052 0.961157 -0.234814 0.145051 0.931412 -0.322714 0.168308 0.931412 -0.322713 0.168311 0.88571 -0.41736 0.203292 0.891426 -0.437488 0.11817 0.840833 -0.248806 0.480724 0.758344 -0.156722 0.632735 0.77674 -0.11824 0.618623 0.776734 -0.118238 0.618631 0.787632 -0.0860324 0.61011 0.787634 -0.0860327 0.610107 0.795012 -0.0522559 0.604338 0.795012 -0.0522559 0.604339 0.798735 -0.0175253 0.601428 0.798734 -0.0175255 0.601429 0.798734 0.0175252 0.601429 0.798735 0.0175256 0.601428 0.795012 0.0522557 0.604339 0.795012 0.0522561 0.604338 0.787634 0.0860337 0.610107 0.787632 0.0860314 0.61011 0.776735 0.118235 0.618631 0.776739 0.118242 0.618624 0.765446 0.142279 0.627574 -0.11582 0.42915 0.895777 0.17419 0.290584 0.940861 0.451029 -0.121651 0.88418 -0.363585 -0.514112 0.776849 0.589068 -0.0556696 0.806164 -0.568631 0.556259 0.605999 -0.5171 0.556026 0.650724 -0.572353 0.43522 0.694979 0.476004 0.103871 0.873287 0.474012 0.10467 0.874275 0.461778 0.0763713 0.883702 0.461773 0.0763727 0.883704 0.45265 0.0389502 0.890837 0.452648 0.0389504 0.890838 0.449569 -2.72314e-05 0.893246 0.449563 -2.82413e-05 0.893249 0.45265 -0.0390054 0.890835 0.452657 -0.0390027 0.890831 0.461788 -0.0764237 0.883692 0.461797 -0.0764184 0.883688 0.474028 -0.104692 0.874264 0.174075 -0.290594 0.940879 0.146962 -0.310299 0.939211 0.106901 -0.217342 0.970224 0.106923 -0.217331 0.970224 0.0809564 -0.11092 0.990526 0.0809375 -0.110926 0.990527 0.0721564 -7.74106e-05 0.997393 0.0721678 -7.57949e-05 0.997393 0.0809242 0.11077 0.990546 0.0809157 0.11077 0.990547 0.106861 0.217198 0.970261 0.106861 0.217198 0.970261 0.14697 0.310326 0.939201 0.0136053 0.374108 0.927285 -0.113694 -0.427432 0.89687 -0.19988 -0.471296 0.859028 -0.263103 -0.324642 0.908507 -0.263124 -0.32465 0.908498 -0.301913 -0.165693 0.938826 -0.301878 -0.165683 0.938839 -0.314994 -0.000114117 0.949094 -0.315002 -0.000115379 0.949091 -0.301922 0.16546 0.938864 -0.30193 0.165459 0.938862 -0.263176 0.324433 0.90856 -0.26319 0.324434 0.908556 -0.199867 0.471388 0.85898 -0.351623 0.510855 0.784467 -0.786896 0.350706 0.50774 -0.592142 0.382175 0.709444 -0.637792 0.19491 0.745138 -0.637798 0.19491 0.745134 -0.653206 -0.000136322 0.757181 -0.653204 -0.000136001 0.757182 -0.637753 -0.195178 0.745101 -0.637745 -0.195175 0.74511 -0.603244 -0.345357 0.718906 -0.706834 -0.389673 0.590373 -0.572312 -0.435341 0.694937 -0.51685 -0.556507 0.650513 -0.574465 -0.556961 0.59982 0.0271541 0.991127 -0.130116 0.0374734 0.204029 -0.978247 0.0375168 0.211603 -0.976635 0.0441706 0.57827 -0.814649 0.0439149 0.596914 -0.801102 0.0435112 0.855937 -0.515247 0.0423995 0.875147 -0.481996 0.0292565 0.995581 0.0892349 0.0401655 0.996275 -0.0763056 0.0357545 0.202569 -0.978615 0.0356892 0.204088 -0.978302 0.0393488 0.574333 -0.817675 0.0390618 0.57843 -0.814796 0.0364991 0.851812 -0.522575 0.0358939 0.856157 -0.515468 0.0276953 0.989507 -0.141802 0.0266877 0.991138 -0.13013 -0.607539 0.213191 -0.765145 -0.118362 0.205418 -0.971491 -0.11702 0.200483 -0.972683 -0.105498 0.574342 -0.811789 -0.104259 0.569596 -0.815286 -0.0753963 0.851849 -0.518333 -0.0743484 0.848478 -0.523981 -0.0326719 0.990112 -0.136422 -0.0317898 0.989121 -0.143627 -0.41064 0.197722 -0.890102 -0.410301 0.195061 -0.890845 -0.337682 0.581347 -0.740274 -0.338304 0.567749 -0.750474 -0.203843 0.865912 -0.456777 -0.208856 0.849966 -0.483671 -0.0327524 0.995488 -0.0890606 -0.0427949 0.990096 -0.13371 -0.723008 0.213569 -0.656999 -0.69243 0.0521291 -0.719599 -0.517136 0.605021 -0.60541 -0.521042 0.593894 -0.613029 -0.26233 0.890346 -0.372111 -0.280946 0.870897 -0.403246 0.0472462 0.99704 -0.0606587 0.0120185 0.992701 -0.120003 -0.859064 0.223487 -0.460503 -0.857887 0.233859 -0.457537 -0.663107 0.637506 -0.392269 -0.668482 0.628343 -0.397891 -0.320823 0.916889 -0.237458 -0.344713 0.902279 -0.258968 0.0962325 0.994984 -0.0273228 0.0520607 0.996379 -0.0672173 -0.959355 0.245136 -0.139812 -0.960832 0.237752 -0.142394 -0.743792 0.660415 -0.103078 -0.752696 0.649293 -0.108936 -0.360325 0.931855 -0.042565 -0.379605 0.923696 -0.0518186 0.110147 0.993491 0.0290302 0.0820298 0.996486 0.0169162 0.485085 0.582435 -0.652275 0.342631 0.924161 -0.168911 0.306652 0.94193 -0.136866 0.15251 0.986579 0.0583353 0.137217 0.98802 0.0706263 0.613333 0.560195 -0.55678 0.566804 0.650579 -0.505451 0.500984 0.777378 -0.380393 0.505432 0.772314 -0.384798 0.43235 0.849988 -0.300989 0.373583 0.382572 -0.845029 0.438979 0.183359 -0.879589 0.409307 0.675964 -0.612814 0.350626 0.798983 -0.488556 0.295129 0.893811 -0.33764 0.242627 0.939314 -0.24253 0.138469 0.990272 -0.0136652 0.112264 0.993275 0.0283274 0.194425 0.20173 -0.95995 0.18133 0.396884 -0.899779 0.189891 0.584453 -0.788895 0.166265 0.700272 -0.694244 0.15185 0.866057 -0.476326 0.128856 0.91058 -0.392735 0.0862207 0.993465 -0.0747916 0.0738984 0.996657 -0.0348418 -0.969359 0.239781 0.0533674 -0.969706 0.240665 0.0418386 -0.970748 0.236551 0.0411399 -0.744069 0.664711 0.0672373 -0.750645 0.657413 0.0658788 -0.34625 0.934963 0.0771665 -0.360733 0.929603 0.0755691 0.131709 0.988857 0.0693921 0.110792 0.991518 0.0679509 -0.967743 0.243259 0.065557 -0.969099 0.238054 0.0646384 -0.736551 0.670341 0.0901975 -0.743302 0.663024 0.08889 -0.331161 0.938911 0.0936904 -0.345711 0.933784 0.0923622 0.152592 0.985425 0.075183 0.131882 0.988481 0.0742407 0.160239 0.982541 0.0945336 0.576216 0.71002 -0.404781 0.562472 0.731262 -0.385852 0.409294 0.895008 -0.177309 0.403481 0.898946 -0.170586 0.195757 0.978125 0.0703608 0.204276 0.976964 0.0617459 0.198645 0.97734 0.0731237 0.102081 0.982507 0.155757 0.411025 0.894541 -0.175657 0.34216 0.934271 -0.10032 0.619281 0.640497 -0.454152 0.581349 0.708614 -0.399875 0.543882 0.764464 -0.346103 0.476024 0.841116 -0.256759 -0.963759 0.246743 0.101422 -0.965522 0.240189 0.100384 -0.726267 0.676327 0.122955 -0.73459 0.667493 0.121787 -0.313341 0.942664 0.114897 -0.329939 0.937063 0.114251 0.175379 0.981308 0.0792299 0.152843 0.985048 0.0794903 -0.957336 0.248341 0.147763 -0.959074 0.242145 0.146775 -0.715216 0.679443 0.163782 -0.722128 0.67227 0.163048 -0.297918 0.9443 0.13979 -0.310763 0.940145 0.139833 0.192436 0.977905 0.081673 0.175736 0.980959 0.0826796 0.244113 0.922468 0.2991 0.500192 0.647622 0.574799 0.644214 0.233114 0.728455 0.237339 0.929828 0.281229 0.262244 0.93119 0.253206 0.246305 0.940178 0.235368 0.263662 0.943679 0.199881 0.248563 0.949733 0.190326 0.254945 0.954501 0.154697 0.242991 0.95813 0.151464 0.238111 0.964654 0.112898 0.232442 0.965978 0.113389 0.212605 0.974286 0.0746114 0.216101 0.973637 0.0730105 0.491538 0.692729 0.527748 0.561491 0.696073 0.447449 0.525517 0.75212 0.397678 0.578095 0.762747 0.289867 0.539425 0.800361 0.261616 0.559766 0.815567 0.146672 0.52908 0.837399 0.137249 0.512555 0.858602 0.00950067 0.501552 0.865064 0.0104784 0.436729 0.892075 -0.116062 0.451507 0.883696 -0.123378 0.660055 0.330686 0.674518 0.754904 0.335897 0.563287 0.733228 0.460931 0.499919 0.809835 0.476554 0.342147 0.769989 0.562975 0.300293 0.800586 0.586234 0.124066 0.763059 0.637209 0.108189 0.73597 0.670487 -0.0937834 0.722562 0.685013 -0.0930624 0.618788 0.72804 -0.295059 0.639842 0.705061 -0.305762 -0.949814 0.242677 0.197383 -0.7761 0.486056 0.40177 -0.946214 0.210271 0.245898 -0.28412 0.931723 0.226205 -0.168975 0.961808 0.215343 -0.693307 0.662045 0.284644 -0.52923 0.79586 0.294147 -0.960204 0.121379 0.251545 -0.812823 0.457913 0.360047 0.227144 0.966322 0.12094 0.220906 0.969695 0.104367 0.196453 0.974427 0.109076 -0.566132 0.690695 0.449928 -0.757844 0.475917 0.44629 -0.330292 0.868022 0.370737 -0.489977 0.77464 0.39982 -0.109034 0.954407 0.277883 -0.141533 0.946953 0.288528 0.0281947 0.976585 0.213276 0.213597 0.96868 0.12663 0.597468 0.235105 0.766653 0.597005 0.238353 0.766011 0.462902 0.653297 0.599104 0.45895 0.66081 0.593881 0.226006 0.92706 0.299133 0.216595 0.933199 0.28675 0.597214 0.232751 0.76757 0.596911 0.235099 0.767089 0.464103 0.647769 0.604155 0.461344 0.653278 0.600324 0.230451 0.922424 0.309882 0.223826 0.927037 0.300838 -0.510361 0.725398 0.461876 0.205799 0.972079 0.112732 0.100241 0.980408 0.169561 -0.55394 0.685447 0.472561 -0.321105 0.86414 0.387496 -0.220828 0.915214 0.337073 -0.105464 0.952911 0.284319 0.0277744 0.976761 0.212523 -0.506129 0.741363 0.440697 -0.519579 0.728844 0.445897 -0.279326 0.900646 0.332886 -0.235535 0.920584 0.311527 -0.0276768 0.980222 0.195955 0.0801404 0.987622 0.134832 -0.0273794 0.980135 0.196431 -0.249234 0.891031 0.379401 -0.447492 0.722647 0.526814 -0.040018 0.978306 0.203264 -0.0113475 0.974224 0.225296 -0.0279319 0.969724 0.2426 -0.440127 0.728609 0.524802 -0.264903 0.70321 0.65979 -0.292038 0.671563 0.680968 -0.01595 0.967396 0.252767 0.0156263 0.964633 0.263134 0.0101111 0.960882 0.276773 0.0808769 0.957447 0.277046 0.0800048 0.948503 0.306499 0.160555 0.946586 0.279638 0.173675 0.931478 0.319666 -0.251231 0.890104 0.380259 -0.144523 0.87481 0.462408 -0.16897 0.857197 0.48648 -0.0295038 0.84607 0.532255 -0.0490971 0.815897 0.576109 0.130544 0.806666 0.576409 0.12632 0.748633 0.650839 0.329123 0.743077 0.582678 0.354324 0.654459 0.667935 -0.103518 0.658896 0.745077 -0.0813249 0.564227 0.821605 -5.70613e-05 0.579496 0.814975 0.163957 0.566086 0.807876 0.152951 0.432282 0.888672 0.442166 0.424215 0.790273 0.452749 0.233522 0.860515 0.314089 -0.296575 -0.901882 0.146034 -0.310211 -0.939385 0.102374 -0.208173 -0.97272 0.137732 -0.653108 -0.744634 0.111762 -0.592743 -0.7976 0.110979 -0.894418 -0.433243 0.0983443 -0.871834 -0.479827 0.0692786 -0.996166 -0.0534188 0.0653418 -0.995002 -0.0755039 0.444312 -0.499973 -0.74338 0.321911 -0.212758 -0.922555 0.301489 -0.759119 -0.576925 0.30239 -0.63749 -0.708638 0.212938 -0.928129 -0.305342 0.227066 -0.883466 -0.40979 0.102894 -0.994688 0.00278283 0.113037 -0.992568 -0.0450769 0.543205 -0.653822 -0.52673 0.565623 -0.479923 -0.67063 0.432955 -0.829298 -0.353291 0.477557 -0.735264 -0.480964 0.292347 -0.944276 -0.151246 0.33434 -0.911576 -0.23926 0.13115 -0.989273 0.0643395 0.151412 -0.988041 0.029129 0.158858 -0.982902 0.0930977 0.185271 -0.980566 0.0645301 0.590664 -0.695766 -0.408689 0.618385 -0.640702 -0.455084 0.415184 -0.891554 -0.180981 0.495717 -0.81818 -0.291284 0.342076 -0.934294 -0.100396 0.565191 -0.730534 -0.383248 0.584437 -0.697435 -0.414749 0.405152 -0.898496 -0.168988 0.414659 -0.891694 -0.181492 0.204775 -0.97683 0.0622207 0.194652 -0.978101 0.0736866 0.0359072 -0.206967 -0.977689 0.0357101 -0.202569 -0.978617 0.0395959 -0.585414 -0.809767 0.0392056 -0.574335 -0.817681 0.0365273 -0.863473 -0.503071 0.036223 -0.851819 -0.522582 0.0272478 -0.993548 -0.110091 0.0272266 -0.989518 -0.141819 0.0386019 -0.211553 -0.976604 0.0383224 -0.206915 -0.977608 0.0470039 -0.596785 -0.801023 0.0464127 -0.585251 -0.809523 0.0470119 -0.87498 -0.481871 0.0464879 -0.8632 -0.502718 0.0386542 -0.996331 -0.0763579 0.0385113 -0.993216 -0.109723 0.214156 -0.974204 0.0711555 0.444296 -0.886304 -0.130642 0.628027 -0.709871 -0.31885 0.211809 -0.974476 0.0743882 0.233046 -0.965833 0.113387 0.238142 -0.964955 0.110226 0.243779 -0.956905 0.15781 0.257661 -0.953749 0.154832 0.435736 -0.892642 -0.115436 0.503027 -0.864222 0.00923474 0.512342 -0.858779 0.0021101 0.530998 -0.832529 0.157912 0.566823 -0.81062 0.146996 0.772119 -0.553956 0.311391 0.808598 -0.57554 0.122159 0.76466 -0.628347 0.143091 0.754382 -0.656385 0.00816209 0.750051 -0.65247 -0.108199 0.719526 -0.68642 -0.105404 0.618836 -0.728812 -0.293045 0.78342 -0.436072 0.442825 0.836046 -0.374723 0.400762 0.590393 -0.744876 0.310798 0.531792 -0.789327 0.306855 0.268822 -0.940575 0.207492 0.24685 -0.947246 0.204424 0.727613 -0.231368 0.645793 0.661138 -0.413628 0.625946 0.55904 -0.644157 0.52205 0.485957 -0.727927 0.483703 0.264914 -0.921994 0.282395 0.234824 -0.93536 0.264498 -0.00533179 -0.989726 -0.142878 -0.731326 -0.213303 -0.647815 -0.964143 -0.237044 -0.119328 -0.961973 -0.244629 -0.121511 -0.754316 -0.650961 -0.085184 -0.745271 -0.660916 -0.0880989 -0.378256 -0.925153 -0.0318488 -0.360498 -0.932102 -0.0350272 -0.871366 -0.235018 -0.430683 -0.874745 -0.225987 -0.428661 -0.682518 -0.630758 -0.369206 -0.673736 -0.640065 -0.369319 -0.356032 -0.904756 -0.233789 -0.323609 -0.918221 -0.228357 -0.620068 -0.214093 -0.754772 -0.712258 -0.0678869 -0.698627 -0.538386 -0.597479 -0.594272 -0.529999 -0.607399 -0.59175 -0.294079 -0.874096 -0.386618 -0.262463 -0.891298 -0.369731 -0.440639 -0.196369 -0.875943 -0.440202 -0.19768 -0.875868 -0.362866 -0.568899 -0.738026 -0.354831 -0.582679 -0.73115 -0.223788 -0.850695 -0.475643 -0.204786 -0.867433 -0.453457 -0.0400338 -0.994507 -0.0967115 -0.136985 -0.199858 -0.970202 -0.135766 -0.204729 -0.969357 -0.122575 -0.568133 -0.813757 -0.120697 -0.57344 -0.810308 -0.0880422 -0.84734 -0.523703 -0.0854173 -0.851668 -0.517074 -0.0372024 -0.990279 -0.134029 -0.0462357 -0.990272 -0.131236 -0.0162285 -0.995663 -0.0916073 0.00513174 -0.99419 -0.107517 0.0609114 -0.995632 -0.0707586 0.0459934 -0.997724 -0.0493171 0.103244 -0.994041 -0.034982 0.0853511 -0.995913 0.0295294 0.110091 -0.99358 0.0260496 0.59639 -0.237612 0.76672 0.597217 -0.232748 0.767568 0.457798 -0.65914 0.59662 0.464126 -0.647773 0.604133 0.215792 -0.931824 0.291783 0.230536 -0.922424 0.309817 0.597834 -0.23836 0.765362 0.597966 -0.237628 0.765486 0.461261 -0.66083 0.592066 0.462216 -0.65918 0.593159 0.219843 -0.933218 0.284205 0.222083 -0.931875 0.286858 -0.967743 -0.243259 0.065557 -0.969359 -0.23978 0.0533828 -0.969098 -0.238055 0.0646386 -0.743258 -0.662939 0.0898857 -0.736598 -0.670422 0.0892127 -0.345657 -0.933651 0.0938951 -0.331246 -0.939031 0.092174 0.131959 -0.988313 0.0763109 0.152467 -0.985599 0.0731376 -0.970737 -0.236521 0.0415624 -0.969716 -0.240696 0.0414208 -0.750622 -0.657341 0.0668525 -0.744095 -0.664778 0.0662738 -0.360701 -0.92949 0.0770918 -0.346304 -0.935066 0.0756607 0.110821 -0.991371 0.0700216 0.131639 -0.989007 0.0673462 -0.0296027 -0.980778 0.192869 0.210161 -0.933115 0.29177 0.450349 -0.660696 0.600556 0.590892 -0.238288 0.770756 0.198458 -0.935777 0.291438 0.169142 -0.935068 0.311511 0.146008 -0.947407 0.284784 0.0851575 -0.948522 0.305048 0.0743263 -0.957992 0.276996 0.0117502 -0.960912 0.276605 0.0110423 -0.965093 0.261675 -0.0169697 -0.967564 0.252054 -0.0304066 -0.969332 0.243867 -0.0113665 -0.974574 0.223777 -0.0369382 -0.978425 0.203274 0.419264 -0.676406 0.605552 0.348425 -0.673834 0.651573 0.289145 -0.746732 0.598988 0.143207 -0.749117 0.646773 0.109078 -0.809323 0.577147 -0.0405514 -0.816347 0.576137 -0.0461122 -0.848818 0.52667 -0.16517 -0.858357 0.485738 -0.157596 -0.877679 0.452597 -0.252191 -0.891481 0.37638 -0.251697 -0.891914 0.375684 0.546128 -0.271847 0.792366 0.456907 -0.270066 0.847526 0.380262 -0.428989 0.819371 0.182719 -0.432629 0.882862 0.126558 -0.571057 0.811096 -0.0852 -0.58098 0.809446 -0.101715 -0.660261 0.744116 -0.289513 -0.674519 0.679122 -0.284804 -0.707361 0.646937 -0.445384 -0.730944 0.517063 -0.44981 -0.723505 0.523652 -0.959008 -0.24209 0.147296 -0.957402 -0.248396 0.147245 -0.722035 -0.672175 0.163847 -0.71532 -0.679524 0.162988 -0.310647 -0.940023 0.14091 -0.298073 -0.944409 0.138723 0.175881 -0.980818 0.0840342 0.192232 -0.978056 0.080336 -0.965477 -0.240138 0.100933 -0.963803 -0.246796 0.100879 -0.734515 -0.667396 0.122761 -0.726354 -0.676409 0.121991 -0.329851 -0.936922 0.11565 -0.313478 -0.942786 0.113516 0.152944 -0.984884 0.0813094 0.175197 -0.981483 0.0774371 -0.515238 -0.736691 0.437968 -0.0341662 -0.982042 0.185543 -0.284561 -0.902052 0.324542 0.000509553 -0.986771 0.162121 0.0229155 -0.979699 0.199162 0.15074 -0.981431 0.11862 -0.11348 -0.956197 0.269834 -0.256671 -0.904412 0.34082 -0.271428 -0.908919 0.316532 -0.509703 -0.742282 0.434994 -0.555426 -0.686098 0.469863 -0.507466 -0.734369 0.450755 -0.408282 -0.815063 0.411069 -0.286371 -0.889659 0.355666 -0.0980084 -0.953349 0.285518 -0.103124 -0.951904 0.288521 0.220807 -0.968563 0.114591 0.170275 -0.973383 0.1534 -0.663753 -0.571349 0.482693 -0.566157 -0.6907 0.449889 -0.407465 -0.815424 0.411166 -0.408075 -0.814975 0.411448 -0.284984 -0.889086 0.358204 -0.769194 -0.471441 0.431375 -0.697025 -0.588182 0.41012 -0.501409 -0.774705 0.385255 -0.432973 -0.828352 0.355482 -0.149981 -0.949575 0.27534 -0.112088 -0.960488 0.254752 0.226562 -0.966638 0.119499 0.223878 -0.96704 0.121294 -0.928327 -0.229934 0.292129 -0.816078 -0.497201 0.294632 -0.689751 -0.659102 0.299715 -0.54197 -0.795703 0.270418 -0.282686 -0.93014 0.234368 -0.176682 -0.963259 0.202275 0.196678 -0.974202 0.110673 0.219841 -0.970255 0.101369 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.978196 0 0.207683 0.978203 8.78515e-05 0.207651 0.977487 -4.69754e-05 0.210996 0.977491 0 0.210979 0.979759 0 0.200179 0.979721 -6.96333e-05 0.200369 0.979947 5.24982e-05 0.199257 0.980019 -4.44189e-05 0.198905 0.980121 0 0.198403 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.98643 0 0.164182 0.986423 -0.000340186 0.164225 0.983216 0.000298859 0.182447 0.983209 0 0.182486 0.990091 -0.000222302 0.140428 0.990082 -0.000198821 0.140493 0.989906 0 0.141728 0.99086 0 0.134897 0.99081 -1.30016e-05 0.135258 0.990682 -0.000103508 0.136195 0.990617 -0.000248566 0.136666 0.990475 -1.42026e-05 0.137689 0.990276 1.19323e-05 0.139115 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.999046 0 0.043669 0.999436 0 0.033584 0.999394 -1.64884e-05 0.0348084 0.999347 -0.000316453 0.0361301 0.999311 -6.15036e-05 0.0371108 0.999147 0.000123601 0.0412871 0.999215 -0.000767666 0.0396189 0.999107 -3.88893e-05 0.0422409 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.980893 0 0.194547 0.980881 -0.000150025 0.194607 0.98196 0.000157932 0.189087 0.981948 0 0.189149 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.978203 0 0.207651 0.978196 -8.65448e-05 0.207683 0.977491 4.62866e-05 0.210979 0.977487 0 0.210996 0.980121 0 0.198403 0.97995 7.45727e-05 0.199246 0.980019 -9.11066e-05 0.198905 0.979759 4.87324e-05 0.200179 0.979722 0 0.200361 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.986423 0 0.164225 0.98643 0.000341708 0.164182 0.983208 -0.000300203 0.182486 0.983216 0 0.182447 0.99086 0 0.134897 0.99081 1.30016e-05 0.135258 0.989906 0 0.141728 0.990091 0.00020935 0.140428 0.990081 0.000234305 0.140495 0.990276 -1.19323e-05 0.139115 0.990617 3.2959e-05 0.136666 0.990478 0.000558558 0.137673 0.990682 0.000103508 0.136195 0.999436 0 0.033584 0.999046 0 0.043669 0.999107 3.88893e-05 0.0422409 0.999147 0.000304013 0.0412871 0.999216 -4.88111e-05 0.0395998 0.999347 0.000104965 0.0361301 0.999312 0.000535295 0.0370944 0.999394 1.64884e-05 0.0348085 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.980881 0 0.194608 0.980893 0.000146667 0.194547 0.981948 -0.000154473 0.189149 0.98196 0 0.189087 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.998194 0 -0.0600739 0.998194 0 -0.0600739 0.998194 0 -0.0600735 0.998194 0 -0.0600735 0.998194 0 -0.0600735 0.998194 0 -0.0600739 0.998194 0 -0.0600739 0.998194 0 -0.0600735 0.998194 0 -0.0600735 0.998194 0 -0.0600735 0.000370956 -4.75554e-05 1 0.000371598 -1.39785e-05 1 0.000371598 4.76377e-05 1 0.000370956 1.39543e-05 1 -0.707372 0 -0.706842 -0.707372 0 -0.706842 -0.607832 0 0.794066 -0.607832 0 0.794066 -0.736647 0 0.676277 -0.736647 0 0.676277 -0.854453 0 0.519528 -0.854453 0 0.519528 -0.931775 0 0.363037 -0.931775 0 0.363037 -0.984697 0 0.174273 -0.984697 0 0.174273 -1 0 0.000371072 -1 0 0.000371072 -0.086786 0 0.996227 -0.0867862 -5.11292e-08 0.996227 -0.0867865 -1.15509e-07 0.996227 -0.086786 6.01245e-08 0.996227 -0.0867866 1.72162e-07 0.996227 -0.0867784 -3.15713e-07 0.996228 -0.0867868 0 0.996227 -0.0867808 2.50556e-07 0.996228 -0.086786 -9.38485e-08 0.996227 -0.0867865 1.63858e-07 0.996227 -0.0867855 -2.26225e-07 0.996227 -0.0867869 1.38759e-07 0.996227 -0.0867229 -7.64341e-06 0.996233 -0.0867869 0 0.996227 -0.0867869 0 0.996227 -0.0867237 7.64348e-06 0.996232 -0.252147 0 -0.967689 -0.252147 0 -0.967689 -0.691781 0 -0.722108 -0.691781 0 -0.722108 -0.955987 0 -0.293408 -0.955987 0 -0.293408 -0.977766 0 0.209697 -0.977766 0 0.209697 -0.751595 0 0.659625 -0.751595 0 0.659625 -0.334828 0 0.942279 -0.334828 0 0.942279 -0.000371033 0 -1 -0.000371212 -1.89477e-06 -1 -0.000371033 0 -1 -0.000371033 0 -1 -0.000371033 0 -1 -0.000371154 0 -1 -0.000371212 1.97966e-06 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.980858 0 -0.194725 -0.980858 0 -0.194725 -0.831675 0 -0.555263 -0.831675 0 -0.555263 0.709048 0.435669 -0.554476 -0.557046 -0.707106 0.435545 0.651606 -0.561996 -0.50948 0.558919 -0.707104 -0.433144 0.205962 -0.96592 -0.156772 0.281018 -0.934236 -0.219617 0.513314 -0.7585 -0.401481 -0.364669 -0.886407 0.285129 -0.251071 -0.947512 0.19795 -0.201889 -0.965921 0.161982 -0.0774975 -0.995161 0.0604059 0.08843 -0.993693 -0.068954 -0.760146 -0.258819 0.595979 -0.693442 -0.474518 0.542191 -0.55704 -0.707114 0.435541 -0.364669 0.886407 0.285129 -0.55704 0.707114 0.435541 -0.557046 0.707107 0.435546 -0.693442 0.474518 0.542191 -0.760146 0.258819 0.595979 -0.766542 0.230646 0.599347 -0.766542 -0.230646 0.599347 -0.204123 0.965926 0.159126 -0.0766165 0.994592 0.070118 -0.251071 0.947512 0.19795 0.557182 0.707107 -0.435372 0.652484 0.571972 -0.497104 0.513314 0.7585 -0.401481 0.203978 0.965926 -0.159312 0.279874 0.936345 -0.211962 0.0884305 0.993693 -0.0689543 0.710328 -0.432403 -0.555394 0.75728 -0.283003 -0.588588 0.763206 -0.258818 -0.592056 0.783795 -0.100481 -0.612837 0.760939 0.25882 -0.594966 0.789536 0.101216 -0.6053 0.757317 0.282858 -0.58861 -0.615984 2.15346e-06 -0.787759 -0.615979 0 -0.787762 -0.615984 -2.14467e-06 -0.787759 -0.760939 -0.25882 0.594966 -0.760939 -0.25882 0.594966 -0.557046 -0.707107 0.435545 -0.557046 -0.707107 0.435545 -0.203893 -0.965926 0.159421 -0.203893 -0.965926 0.159421 0.203893 -0.965926 -0.159421 0.203893 -0.965926 -0.159421 0.557046 -0.707107 -0.435545 0.557046 -0.707107 -0.435545 0.760939 -0.25882 -0.594966 0.760939 -0.25882 -0.594966 0.760939 0.258819 -0.594966 0.760939 0.258819 -0.594966 0.557046 0.707107 -0.435545 0.557046 0.707107 -0.435545 0.203893 0.965926 -0.15942 0.203893 0.965926 -0.15942 -0.203893 0.965926 0.15942 -0.203893 0.965926 0.15942 -0.557047 0.707106 0.435545 -0.557046 0.707107 0.435545 -0.760939 0.25882 0.594966 -0.760939 0.258819 0.594966 -0.615973 -5.45687e-06 -0.787767 -0.615954 -8.59472e-06 -0.787782 -0.615954 -9.23705e-07 -0.787782 -0.615969 1.3665e-05 -0.78777 -0.615967 1.75928e-05 -0.787772 -0.61596 -4.13818e-06 -0.787777 -0.615954 1.42109e-07 -0.787782 -0.615954 0 -0.787782 -0.615954 0 -0.787782 -0.615954 2.27374e-07 -0.787782 -0.615954 4.26326e-08 -0.787782 -0.615936 9.20879e-06 -0.787796 -0.615935 6.7858e-06 -0.787797 -0.615955 1.00385e-05 -0.787782 -0.615955 -1.84741e-07 -0.787782 -0.615939 -1.53252e-05 -0.787794 -0.61594 -1.74227e-05 -0.787793 -0.615947 4.7294e-06 -0.787787 -0.615954 -2.84217e-07 -0.787782 -0.615954 0 -0.787782 -0.615954 0 -0.787782 -0.615954 -1.13687e-07 -0.787782 -0.615954 -5.25802e-07 -0.787782 -0.615971 -9.51542e-06 -0.787769 -0.693607 -0.684552 0.224272 -0.693614 -0.684551 0.224253 -0.351723 -0.935113 -0.0430525 -0.351725 -0.935113 -0.0430561 0.0430429 -0.935109 -0.351736 0.0430483 -0.935112 -0.351727 0.384934 -0.684548 -0.619047 0.384923 -0.684543 -0.61906 0.582303 -0.250561 -0.773396 0.582336 -0.250571 -0.773369 0.582337 0.250564 -0.77337 0.582302 0.250568 -0.773396 0.384921 0.684545 -0.619058 0.384936 0.684546 -0.619048 0.0430495 0.935112 -0.351728 0.043042 0.93511 -0.351734 -0.351725 0.935113 -0.0430551 -0.351723 0.935114 -0.0430528 -0.693616 0.684549 0.224254 -0.693605 0.684555 0.224271 -0.890993 0.250564 0.378614 -0.891003 0.250559 0.378594 -0.891003 -0.250563 0.378593 -0.890994 -0.250561 0.378615 -0.828591 -0.508595 -0.234026 -0.828589 -0.50858 -0.234065 -0.574592 -0.694718 -0.43268 -0.574581 -0.694757 -0.432631 -0.281269 -0.694764 -0.66196 -0.281296 -0.694722 -0.661993 -0.0273067 -0.508566 -0.86059 -0.0272702 -0.508596 -0.860573 0.11938 -0.186168 -0.975238 0.119357 -0.186159 -0.975243 0.119357 0.186163 -0.975242 0.119382 0.186164 -0.975239 -0.0272669 0.508589 -0.860577 -0.0273128 0.508571 -0.860587 -0.281303 0.694726 -0.661986 -0.281261 0.694762 -0.661965 -0.574574 0.694758 -0.432639 -0.574601 0.694714 -0.432674 -0.828593 0.508576 -0.234061 -0.828587 0.508601 -0.234028 -0.975241 0.186159 -0.119369 -0.975241 0.186156 -0.119379 -0.975241 -0.186157 -0.119379 -0.975242 -0.186158 -0.119368 -0.742425 -0.189 -0.642717 -0.742469 -0.189051 -0.64265 -0.64805 -0.258257 -0.716474 -0.648043 -0.258222 -0.716492 -0.539021 -0.258225 -0.801733 -0.539011 -0.258268 -0.801726 -0.444584 -0.189073 -0.875555 -0.444631 -0.189008 -0.875545 -0.390135 -0.0691904 -0.918154 -0.390108 -0.0692035 -0.918165 -0.390109 0.0691977 -0.918165 -0.390137 0.0691955 -0.918153 -0.444637 0.189021 -0.875539 -0.444573 0.189065 -0.875562 -0.539006 0.258264 -0.801731 -0.539028 0.258225 -0.801729 -0.648049 0.258222 -0.716487 -0.648045 0.25826 -0.716477 -0.742458 0.18906 -0.642661 -0.742433 0.188984 -0.642712 -0.796927 0.0691725 -0.600102 -0.796956 0.0691957 -0.600061 -0.796957 -0.0691854 -0.600061 -0.796924 -0.0691815 -0.600105 -0.796927 -0.0691728 -0.600102 -0.742431 -0.188988 -0.642713 -0.742422 -0.188967 -0.64273 -0.648039 -0.258131 -0.716529 -0.648039 -0.258141 -0.716526 -0.539062 -0.258135 -0.801735 -0.539055 -0.25815 -0.801734 -0.44468 -0.188978 -0.875527 -0.444585 -0.189056 -0.875558 -0.390066 -0.0691986 -0.918183 -0.390172 -0.0691798 -0.918139 -0.390172 0.0691688 -0.91814 -0.390068 0.0692086 -0.918181 -0.444587 0.189069 -0.875554 -0.444672 0.188972 -0.875532 -0.539056 0.25815 -0.801734 -0.53906 0.258138 -0.801735 -0.64804 0.258145 -0.716523 -0.648038 0.258131 -0.71653 -0.74242 0.188968 -0.642731 -0.742432 0.188986 -0.642712 -0.796925 0.069179 -0.600104 -0.79697 0.0691915 -0.600043 -0.79697 -0.0691986 -0.600043 -0.975241 -0.186158 -0.119376 -0.82859 -0.50859 -0.234042 -0.828592 -0.50858 -0.234056 -0.574597 -0.694723 -0.432664 -0.574572 -0.694769 -0.432623 -0.281248 -0.69478 -0.661952 -0.281269 -0.694759 -0.661965 -0.0272531 -0.508601 -0.860571 -0.027298 -0.508579 -0.860582 0.119348 -0.186147 -0.975246 0.119358 -0.186148 -0.975245 0.119358 0.186149 -0.975245 0.119349 0.186146 -0.975246 -0.0272964 0.508575 -0.860585 -0.0272565 0.508604 -0.860569 -0.281267 0.694758 -0.661967 -0.28125 0.694781 -0.66195 -0.574577 0.694768 -0.432618 -0.574592 0.694726 -0.432666 -0.828591 0.508581 -0.234057 -0.828591 0.508588 -0.234042 -0.975241 0.186157 -0.119376 -0.975241 0.186157 -0.119377 -0.975241 -0.186157 -0.119377 -0.891018 -0.250558 0.378559 -0.693624 -0.684546 0.22424 -0.693625 -0.684545 0.224238 -0.351722 -0.935114 -0.0430508 -0.351724 -0.935113 -0.0430526 0.0430519 -0.935112 -0.351726 0.0430687 -0.935117 -0.351711 0.384969 -0.684557 -0.619016 0.384974 -0.684558 -0.619012 0.582373 -0.250567 -0.773342 0.582408 -0.250566 -0.773316 0.582407 0.25057 -0.773315 0.582375 0.250563 -0.773342 0.384974 0.684558 -0.619012 0.38497 0.684556 -0.619016 0.0430678 0.935119 -0.351708 0.043054 0.935112 -0.351727 -0.351725 0.935113 -0.0430547 -0.351721 0.935115 -0.0430477 -0.693623 0.684546 0.224242 -0.693624 0.684546 0.22424 -0.891018 0.250561 0.378558 -0.891009 0.25056 0.378579 -0.891009 -0.250562 0.378579 0.988925 0 0.148415 0.989108 0.000151401 0.147189 0.843441 -0.000155991 0.537222 0.845452 0.000305083 0.534052 0.55265 -0.000310003 0.833413 0.557808 0.000455993 0.82997 0.171454 -0.00046139 0.985192 0.175198 0 0.984533 0.956603 0 -0.291393 0.956192 0.000193209 -0.292739 0.720116 -0.000194749 -0.693854 0.717169 0.000383707 -0.696899 0.326756 -0.000386283 -0.945109 0.320025 0.000578818 -0.947409 -0.137842 -0.000568033 -0.990454 -0.147634 0.000766295 -0.989042 -0.572424 -0.000754958 -0.819958 -0.577032 0 -0.816721 0.990556 0 0.137111 0.990716 0.00013587 0.135945 0.862552 -0.000136523 0.505969 0.863153 0 0.504943 0.963398 0 -0.268074 0.963398 0 -0.268074 0.768694 0 -0.639617 0.768694 0 -0.639617 0.985431 0 0.170077 0.985665 0.000185868 0.168717 0.806281 -0.000185859 0.591532 0.808728 0.000375972 0.588183 0.458086 -0.000371598 0.888908 0.46414 0.000558164 0.885762 0.0137318 -0.000572392 0.999906 0.0234357 0.000757798 0.999725 -0.427148 -0.000735776 0.904182 -0.422173 0 0.906515 0.977427 0 -0.211274 0.977427 0 -0.211274 0.977427 0 -0.211274 0.785815 0 -0.618462 0.785815 0 -0.618462 0.435059 0 -0.900402 0.435059 0 -0.900402 -0.00380789 0 -0.999993 -0.00380789 0 -0.999993 -0.441911 0 -0.897059 -0.441911 0 -0.897059 0.635254 0 0.772304 0.969731 0 0.244176 0.997786 -0.0216126 0.0629019 0.980613 -0.00681836 0.195837 0.946568 -0.00220969 0.322496 0.94175 -0.00171846 0.33631 0.781963 0.00716447 0.623284 0.849058 -0.00840236 0.528232 0.691669 -4.87827e-05 0.722214 0.999999 0 0.00165636 0.987847 -0.00358347 -0.155386 0.994931 -0.00829838 -0.100214 0.727472 0 -0.686138 0.779809 -5.13376e-05 -0.626018 0.849506 -0.00410988 -0.527563 0.919344 0.00390411 -0.393436 0.982767 -0.00349209 -0.184814 0.858802 -0.0084038 0.512238 0.705039 -4.89816e-05 0.709169 0.649337 0 0.760501 0.774789 0.0111814 0.63212 0.94978 -0.00420949 0.312892 0.972619 0 0.232406 0.998925 0 0.0463614 0.996968 -0.00638646 -0.0775559 0.994403 -0.00452742 -0.105553 0.740033 0 -0.67257 0.79014 -5.02813e-05 -0.612927 0.868572 -0.00479701 -0.49554 0.925337 0.00321305 -0.379132 0.983836 -0.0016837 -0.179064 0.928391 0 0.371604 0.928891 0 0.370353 0.928597 0.000177113 0.371091 0.672601 -0.000179431 0.740005 0.675595 0.000358266 0.737273 0.281556 -0.00035955 0.959545 0.288028 0.000541569 0.957622 -0.16613 -0.000541616 0.986104 -0.156848 0.000720796 0.987622 -0.574923 -0.000710345 0.818207 -0.570483 0 0.82131 -0.40037 0 -0.916354 0.998704 0 -0.0509022 -0.395062 -0.000792767 -0.918654 0.0655624 0.000797032 -0.997848 0.0756592 -0.000598572 -0.997134 0.523007 0.00060107 -0.852328 0.529147 -0.000400347 -0.84853 0.859922 0.000403797 -0.510426 0.86213 -0.000202158 -0.506687 0.998734 0.000203288 -0.05031 0.998776 0 -0.0494591 0.603483 0 0.797376 0.928437 0 0.37149 0.951404 -0.00653817 0.307875 0.90211 -0.00151681 0.431503 0.736633 0.00458956 0.676277 0.804752 -0.00704734 0.593569 0.664014 -5.0524e-05 0.74772 0.983284 0 0.182079 0.999732 -0.00166847 0.0231015 0.999987 -9.20847e-05 0.00511442 0.944403 0.000103918 -0.328792 0.701611 -4.944e-05 -0.71256 0.645078 0 -0.764117 0.765316 -0.00320929 -0.643647 0.79907 -0.00562698 -0.601212 0.76924 -0.00267858 -0.638954 0.858475 0.000380888 -0.512855 0.950199 -0.00156811 -0.311641 0.893433 0 0.449196 0.894125 0.000232767 0.447817 0.553116 -0.000236199 0.833104 0.556974 0.000467862 0.83053 0.0672116 -0.00047457 0.997739 0.0749389 0.000707986 0.997188 -0.43078 -0.000696759 0.902457 -0.426584 0 0.904448 -0.27175 0 -0.962368 -0.27175 0 -0.962368 0.181402 0 -0.983409 0.181402 0 -0.983409 0.597223 0 -0.802075 0.597223 0 -0.802075 0.890143 0 -0.455681 0.890143 0 -0.455681 0.99988 0 -0.015512 0.99988 0 -0.015512 0.899007 0 0.437934 0.899007 0 0.437934 0.899634 0.000201522 0.436645 0.593081 -0.000204946 0.805143 0.596553 0.00040587 0.802573 0.15168 -0.000410731 0.98843 0.158797 0.000613889 0.987311 -0.318916 -0.000603525 0.947783 -0.31482 0 0.949152 -0.24728 0 -0.968944 0.999773 0 -0.0212911 -0.24206 -0.000687997 -0.970261 0.193678 0.000692973 -0.981065 0.202923 -0.000519813 -0.979195 0.602364 0.000522265 -0.798221 0.607714 -0.000346943 -0.794156 0.890284 0.000351266 -0.455405 0.892121 -0.000175712 -0.451796 0.999785 0.000176571 -0.0207391 0.999801 0 -0.0199458 0.909464 0 0.415783 0.909464 0 0.415783 0.629856 0 0.776712 0.629856 0 0.776712 0.218949 0 0.975736 0.218949 0 0.975736 -0.237586 0 0.971367 -0.237586 0 0.971367 -0.175228 0 -0.984528 -0.170157 -0.00062901 -0.985417 0.246162 0.000631842 -0.969228 0.254876 -0.000474408 -0.966974 0.628786 0.00047692 -0.777578 0.633772 -0.000317967 -0.77352 0.896262 0.000319941 -0.443524 0.897966 -0.000159728 -0.440065 0.999601 0.000161076 -0.0282435 0.999637 0 -0.0269567 0.90394 0 0.42766 0.90394 0 0.42766 0.0877587 0 0.996142 0.0877587 0 0.996142 0.571539 0 0.820575 0.571539 0 0.820575 0.90394 0 0.42766 -0.0568388 0 -0.998383 0.996336 0 -0.0855256 -0.0522326 -0.000676267 -0.998635 0.437701 0.000681309 -0.89912 0.444607 -0.000453578 -0.895725 0.824379 0.000456884 -0.566039 0.826983 -0.000228041 -0.562227 0.99639 0.00023031 -0.0848961 0.996467 0 -0.0839915 0.985665 0 0.168717 0.985431 -0.000184781 0.170077 0.808728 0.00018259 0.588183 0.806281 -0.000369441 0.591532 0.46414 0.000360842 0.885762 0.458086 -0.000541992 0.888908 0.0234357 0.000549413 0.999725 0.0137318 -0.000727163 0.999905 -0.422173 0.000718412 0.906515 -0.427148 0 0.904182 0.977138 0 -0.212605 0.785814 -0.000365256 -0.618462 0.428919 0.00036598 -0.903343 0.435058 -0.000550981 -0.900402 -0.0133647 0.000552845 -0.999911 -0.00380789 -0.000741956 -0.999992 -0.446766 0.000717267 -0.894651 -0.441911 0 -0.897059 0.977427 0 -0.211274 0.977257 -0.000180726 -0.212059 0.783282 0.00018179 -0.621667 0.998977 0 0.0452205 0.96973 0.00130684 0.244176 0.980613 0.00681836 0.195837 0.946568 0.00220968 0.322496 0.635254 0 0.772304 0.69167 4.87827e-05 0.722214 0.781974 0.00455357 0.623294 0.859958 -0.00350642 0.510352 0.94175 0.00171846 0.33631 0.727472 0 -0.686138 0.987854 0 -0.155387 0.999778 0.0155447 -0.0142076 0.994931 0.00829838 -0.100214 0.982767 0.0034921 -0.184814 0.849479 -0.00893993 -0.527547 0.910589 0.00840325 -0.413228 0.779809 5.13376e-05 -0.626018 0.949788 0 0.312894 0.649337 0 0.760501 0.705039 4.89816e-05 0.709169 0.774833 0.00354759 0.632156 0.869928 -0.00415545 0.493161 0.970237 0.00730889 0.242047 0.740033 0 -0.67257 0.996988 0 -0.0775574 0.999348 0.0136654 0.0334122 0.994403 0.00452742 -0.105553 0.983836 0.0016837 -0.179064 0.868565 -0.00619521 -0.495537 0.917372 0.00840384 -0.397942 0.79014 5.02813e-05 -0.612927 0.928891 0 0.370353 0.928391 0 0.371604 0.928597 -0.000177113 0.371091 0.675595 0.000176295 0.737273 0.672601 -0.000352002 0.740005 0.288028 0.000349107 0.957622 0.281556 -0.000525907 0.959545 -0.156849 0.000519791 0.987623 -0.16613 -0.000691705 0.986104 -0.570483 0.000693585 0.821309 -0.574923 0 0.818207 0.998704 0 -0.0509022 -0.395063 0 -0.918654 -0.40037 0.000811888 -0.916353 0.0756592 -0.000830463 -0.997133 0.0655624 0.000623646 -0.997848 0.529147 -0.000618956 -0.84853 0.523007 0.000412261 -0.852328 0.86213 -0.000410965 -0.506687 0.859922 0.000205745 -0.510426 0.998776 -0.000203992 -0.0494591 0.998704 0 -0.0509022 0.953811 0 0.300407 0.928429 0.0039968 0.371487 0.603483 0 0.797376 0.664014 5.0524e-05 0.74772 0.736636 0.00347985 0.67628 0.814404 -0.00206254 0.580294 0.90211 0.00151681 0.431503 0.85013 0.0111357 -0.526455 0.79907 0.00562698 -0.601212 0.765316 0.00320929 -0.643647 0.701611 4.94408e-05 -0.71256 0.645078 0 -0.764117 0.769242 -0.00173567 -0.638956 0.944402 0.00141048 -0.328791 0.950751 -9.25738e-05 -0.309957 0.999733 0 0.0231015 0.984807 0.0148121 0.173022 0.999987 9.20847e-05 0.00511442 0.894125 0 0.447817 0.893433 -0.000231407 0.449196 0.556974 0.000232113 0.83053 0.553116 -0.000459691 0.833104 0.0749389 0.000460936 0.997188 0.0672116 -0.000687537 0.997739 -0.426584 0.00068449 0.904448 -0.43078 0 0.902457 -0.27175 0 -0.962368 -0.277023 0.000731528 -0.960863 0.181402 -0.000751126 -0.983409 0.171931 0.000563024 -0.985109 0.597223 -0.000558799 -0.802075 0.5917 0.000373739 -0.806158 0.890143 -0.000370137 -0.455681 0.888259 0.000185871 -0.459344 0.99988 -0.000184241 -0.015512 0.999857 0 -0.0168846 0.899634 0 0.436645 0.899007 0 0.437934 0.899264 -0.000200826 0.437405 0.596553 0.000201389 0.802573 0.593081 -0.000398766 0.805143 0.158797 0.000398882 0.987311 0.15168 -0.000596117 0.988429 -0.31482 0.000592865 0.949151 -0.318916 0 0.947783 0.999773 0 -0.0212911 0.892121 -0.00035751 -0.451796 0.602364 0.000357314 -0.798222 0.607714 -0.000537832 -0.794156 0.193678 0.000541661 -0.981065 0.202923 -0.0007221 -0.979195 -0.247279 0.000704634 -0.968944 -0.24206 0 -0.970261 0.999801 0 -0.0199458 0.999785 -0.000176571 -0.0207391 0.890284 0.000178843 -0.455405 0.909464 0 0.415783 0.908889 -0.000185469 0.417039 0.629856 0.00018461 0.776712 0.626625 -0.000369843 0.779321 0.218949 0.000365582 0.975736 0.212215 -0.000549563 0.977223 -0.237586 0.000547373 0.971366 -0.241614 0 0.970372 0.990716 0 0.135945 0.990716 0 0.135945 0.863153 0 0.504943 0.863153 0 0.504943 0.963056 0 -0.269301 0.963398 -0.000158118 -0.268074 0.767891 0.00015462 -0.64058 0.768694 0 -0.639617 0.989108 0 0.147189 0.989108 0 0.147189 0.845452 0 0.534052 0.845452 0 0.534052 0.557808 0 0.82997 0.557808 0 0.82997 0.175198 0 0.984533 0.175198 0 0.984533 0.956192 0 -0.292739 0.956603 -0.00019435 -0.291393 0.717169 0.000198182 -0.696899 0.720116 -0.00039057 -0.693853 0.320025 0.000397789 -0.947409 0.326756 -0.000596055 -0.945109 -0.147634 0.00059203 -0.989042 -0.137842 -0.000798296 -0.990454 -0.577032 0.000773196 -0.816721 -0.572424 0 -0.819958 -0.170157 0 -0.985417 -0.175228 0.000644243 -0.984528 0.254876 -0.000658454 -0.966974 0.246162 0.000494366 -0.969229 0.633772 -0.000491176 -0.77352 0.628786 0.000327468 -0.777578 0.897966 -0.00032564 -0.440065 0.896263 0.00016258 -0.443524 0.999637 -0.000162027 -0.0269567 0.999601 0 -0.0282435 0.80314 0 0.595791 0.90394 0 0.42766 0.917612 0.00854644 0.397386 0.9294 0 0.369075 0.671446 0 0.741054 0.571511 0.00990029 0.820535 0.458155 0 0.888872 0.275931 0 0.961178 0.0877561 0.00767901 0.996112 0.0192906 0 0.999814 0.996336 0 -0.0855256 -0.0522326 0 -0.998635 -0.0568387 0.000688392 -0.998383 0.444607 -0.000701517 -0.895725 0.437701 0.000467051 -0.89912 0.826983 -0.000464967 -0.562227 0.824379 0.000232088 -0.566039 0.996466 -0.000231105 -0.0839915 0.996336 0 -0.0855256 -0.512838 -0.7452 -0.426231 -0.226244 -0.973175 -0.041769 -0.403121 -0.873945 -0.271502 -0.586824 -0.635587 -0.501664 -0.62849 -0.449828 -0.634551 -0.657258 -0.166461 -0.735053 -0.24514 -0.967954 -0.0545056 -0.244994 -0.967986 -0.0546009 -0.256996 -0.963691 -0.0724816 -0.283848 -0.956577 -0.0662657 -0.283337 -0.956863 -0.0642868 -0.331322 -0.940855 -0.0708359 -0.332303 -0.942522 -0.0350202 -0.369474 -0.927635 -0.0546032 -0.381391 -0.92441 -0.00277175 -0.423138 -0.860164 -0.284731 -0.342346 -0.876921 -0.337355 -0.357964 -0.860491 -0.362516 -0.273665 -0.882637 -0.382178 -0.277125 -0.873003 -0.401332 -0.206991 -0.896434 -0.391869 -0.207083 -0.896718 -0.391169 -0.138532 -0.924534 -0.355029 -0.143934 -0.929598 -0.339309 -0.560422 -0.670244 -0.486519 -0.40557 -0.701347 -0.586195 -0.421707 -0.667992 -0.613148 -0.234548 -0.716635 -0.656827 -0.238147 -0.684745 -0.688774 -0.0584931 -0.74469 -0.664842 -0.0528681 -0.722343 -0.689511 0.11067 -0.789331 -0.603911 0.116113 -0.778523 -0.616782 -0.644274 -0.417657 -0.640683 -0.42909 -0.460495 -0.777063 -0.442355 -0.408579 -0.798364 -0.171157 -0.478436 -0.861281 -0.172136 -0.417428 -0.892257 0.0958731 -0.506489 -0.8569 0.106842 -0.447847 -0.887704 0.34258 -0.544354 -0.765713 0.354185 -0.500409 -0.790028 0.682182 -0.207079 -0.701246 0.532717 -0.143238 -0.834083 0.525823 -0.226119 -0.819988 0.249752 -0.114231 -0.961548 0.237945 -0.212302 -0.947792 -0.087752 -0.104673 -0.990628 -0.0908045 -0.19473 -0.976645 -0.346461 -0.131518 -0.928799 -0.379651 -0.0295218 -0.924659 -0.502497 -0.163209 -0.849034 -0.667735 -0.126985 -0.733488 0.790299 -0.195304 -0.580762 0.77893 -0.152579 -0.608266 0.561714 -0.562171 -0.606993 0.553985 -0.587689 -0.58968 0.270146 -0.841794 -0.467337 0.268052 -0.844586 -0.46349 -0.0748796 -0.968048 -0.239326 -0.0643493 -0.96375 -0.258931 -0.409107 -0.911778 0.0359481 -0.388609 -0.921348 -0.0100262 0.90729 -0.224266 -0.35571 0.90689 -0.237332 -0.348172 0.723353 -0.614794 -0.314306 0.72172 -0.618395 -0.31098 0.403016 -0.889982 -0.213332 0.40542 -0.888102 -0.216585 0.00173138 -0.99755 -0.0699351 0.0112375 -0.996665 -0.0808207 -0.405216 -0.909874 0.0890512 -0.389708 -0.918177 0.0712652 0.920915 -0.226999 -0.31684 0.894234 -0.232623 -0.382402 0.701301 -0.664412 -0.25833 0.725502 -0.633293 -0.269421 0.713757 -0.648475 -0.264634 0.397112 -0.909232 -0.124895 0.365888 -0.923813 -0.112679 -0.0133638 -0.998871 0.0455777 -0.0634381 -0.995911 0.0643238 -0.415464 -0.886303 0.204589 -0.479161 -0.84788 0.226947 0.944695 -0.223282 -0.240202 0.944952 -0.222015 -0.240364 0.75789 -0.62928 -0.172077 0.765824 -0.618765 -0.175052 0.415676 -0.906922 -0.0686031 0.437869 -0.895841 -0.075762 -0.0122003 -0.998718 0.0491261 0.0244612 -0.998969 0.0382439 -0.431618 -0.888567 0.15542 -0.3937 -0.907748 0.144894 -0.634606 -0.559494 -0.533143 -0.360911 -0.88906 -0.28163 -0.128386 -0.98983 -0.0612714 -0.694323 -0.360098 -0.623093 -0.725931 -0.19757 -0.65878 -0.706345 -0.359582 -0.609736 -0.159476 -0.982507 -0.0961632 -0.190751 -0.979752 -0.0608316 -0.201672 -0.977006 -0.0691904 -0.410753 -0.872917 -0.263247 -0.454376 -0.833685 -0.313866 -0.432968 -0.835561 -0.338195 -0.520478 -0.738775 -0.428151 -0.747854 -0.151543 -0.646335 -0.742023 -0.196375 -0.640967 -0.697627 -0.440121 -0.56534 -0.647911 -0.558415 -0.518057 -0.613779 -0.631756 -0.473455 -0.541998 -0.741431 -0.395624 0.866871 -0.235868 -0.439205 0.867042 -0.234588 -0.439553 0.683781 -0.657673 -0.316084 0.688009 -0.651419 -0.319838 0.345832 -0.930427 -0.121267 0.35754 -0.924817 -0.129917 -0.0702261 -0.992394 0.10111 -0.0515107 -0.994767 0.0882295 -0.470097 -0.829787 0.30077 -0.449429 -0.846063 0.28669 0.851963 -0.236363 -0.467218 0.851752 -0.238434 -0.466549 0.681148 -0.659824 -0.317284 0.682389 -0.657906 -0.318599 0.352985 -0.930892 -0.0940305 0.358397 -0.928355 -0.0985346 -0.0566055 -0.986916 0.150974 -0.0467677 -0.988519 0.143675 -0.452943 -0.815099 0.361187 -0.441315 -0.824964 0.353094 -0.631739 -0.565542 -0.530158 -0.709097 -0.359455 -0.606608 -0.736833 -0.199097 -0.646094 -0.357067 -0.889229 -0.285963 -0.518298 -0.738875 -0.430617 -0.703158 -0.359764 -0.613302 -0.419615 -0.842541 -0.33771 -0.14273 -0.985695 -0.0896269 -0.121372 -0.990193 -0.0691882 -0.142504 -0.98595 -0.0871459 -0.143891 -0.985645 -0.0883182 -0.4183 -0.843253 -0.337565 -0.419118 -0.842564 -0.33827 -0.627511 -0.566393 -0.534255 -0.627856 -0.565726 -0.534557 -0.73689 -0.199337 -0.645955 -0.736927 -0.199093 -0.645988 -0.141723 -0.986154 -0.0861092 -0.142695 -0.985942 -0.086931 -0.417869 -0.843741 -0.336878 -0.418459 -0.843245 -0.337386 -0.627395 -0.566817 -0.533942 -0.627617 -0.566388 -0.534136 -0.736896 -0.199553 -0.645882 -0.736929 -0.199334 -0.645912 0.0290519 -0.957066 0.288411 0.0231172 -0.954712 0.296633 0.450861 -0.889124 0.0786365 0.43719 -0.892748 0.108929 0.766539 -0.624385 -0.150206 0.757624 -0.64493 -0.100354 0.910493 -0.218141 -0.351307 0.999012 -0.0106731 -0.0431333 0.983533 -0.164659 -0.0745013 0.920838 -0.261568 -0.289205 0.0807256 -0.810341 0.580371 0.0979517 -0.810013 0.578174 0.480988 -0.677436 0.556535 0.439026 -0.690226 0.575191 0.794057 -0.428714 0.430903 0.7204 -0.47866 0.501905 0.0867923 -0.789762 0.607243 0.0865206 -0.789811 0.607217 0.403917 -0.625984 0.667079 0.359303 -0.644594 0.674833 0.668478 -0.383402 0.637292 0.593604 -0.433616 0.677946 0.0794633 -0.783786 0.615926 0.0615467 -0.790323 0.609591 0.309505 -0.602093 0.735997 0.264916 -0.628205 0.731559 0.50941 -0.362024 0.780667 0.443746 -0.414293 0.794639 0.0764077 -0.870955 0.485385 0.0815772 -0.87207 0.482533 0.510698 -0.777721 0.366521 0.482741 -0.782133 0.393992 0.834709 -0.524515 0.167767 0.797856 -0.553172 0.23964 0.966756 -0.255671 -0.00397947 0.968216 -0.109974 0.224641 0.90698 -0.203068 0.368985 0.847787 -0.0950823 0.521744 0.76588 -0.178331 0.617759 0.659844 -0.0889455 0.74612 0.583518 -0.166512 0.794846 0.434195 -0.099381 0.89532 0.287683 -0.139658 0.947488 0.431526 -0.0411731 0.901161 0.264935 -0.403129 0.875955 0.310769 -0.354114 0.882058 0.1481 -0.6221 0.768803 0.183737 -0.591225 0.785299 0.0183581 -0.79608 0.604913 0.0419023 -0.781353 0.622681 -0.0819635 -0.918389 0.387096 -0.113883 -0.910996 0.396379 -0.102681 -0.907252 0.407861 -0.148214 -0.886486 0.438379 -0.157846 -0.887579 0.432768 -0.196668 -0.854501 0.480779 -0.241388 -0.851227 0.465987 -0.257884 -0.821464 0.508618 -0.336004 -0.799456 0.497967 -0.33587 -0.804922 0.489175 -0.378701 -0.778806 0.500047 -0.399332 -0.811739 0.42616 -0.40726 -0.803499 0.434199 0.0963746 -0.141894 0.985179 0.119456 -0.101048 0.987684 0.0521679 -0.393888 0.917677 0.0729894 -0.359181 0.930409 0.00318594 -0.619821 0.784737 0.0214441 -0.592864 0.805017 -0.026821 -0.747441 0.663787 -0.0438821 -0.781313 0.622595 -0.0479651 -0.828104 0.558519 -0.0942565 -0.927648 0.361364 -0.968715 -0.200052 -0.146868 -0.170741 -0.977138 0.126685 -0.141987 -0.98222 0.122816 -0.766937 -0.506838 0.393602 -0.683955 -0.651631 0.327998 -0.498013 -0.821441 0.277883 -0.501381 -0.818523 0.280424 -0.373698 -0.903296 0.210728 -0.794384 -0.43969 0.419079 -0.754606 -0.544403 0.366327 -0.886057 -0.22481 0.405419 -0.889809 -0.185651 0.416862 -0.912021 -0.0345289 0.408687 -0.187477 -0.979789 0.0697629 -0.189686 -0.979309 0.0705172 -0.548603 -0.829492 0.104774 -0.55364 -0.825894 0.106687 -0.822976 -0.55451 0.123404 -0.828299 -0.545899 0.126154 -0.974862 -0.185886 0.122844 -0.997917 0.00118672 0.0645066 -0.951174 -0.196385 0.238119 -0.930891 -0.195274 -0.308724 -0.974609 -0.0523438 -0.217708 -0.819492 -0.551355 -0.156337 -0.813939 -0.559289 -0.15716 -0.549007 -0.831614 -0.0837263 -0.543976 -0.834898 -0.083878 -0.188463 -0.982075 0.00310447 -0.186256 -0.982496 0.00311622 -0.837503 -0.191719 -0.511696 -0.834525 -0.201992 -0.512608 -0.716103 -0.556643 -0.421124 -0.711592 -0.562998 -0.420322 -0.480191 -0.836857 -0.262843 -0.476259 -0.839481 -0.261627 -0.164413 -0.984541 -0.0603947 -0.162733 -0.984856 -0.059802 0.00980876 -0.952445 0.304552 -0.0551117 -0.930365 0.362469 -0.057836 -0.745874 0.663572 -0.0605639 -0.827412 0.55832 -0.0531235 -0.388074 0.920096 -0.0482131 -0.61741 0.785162 -0.0381311 -0.132636 0.990431 -0.0453298 -0.908165 0.41615 0.0208206 -0.908396 0.417593 0.019161 -0.929109 0.369309 0.0329101 -0.928497 0.369879 0.0328744 -0.930838 0.36395 0.0225169 -0.931271 0.363631 0.021999 -0.950384 0.3103 0.0145384 -0.942538 0.333784 0.00983469 -0.942651 0.333634 -0.0448906 -0.631668 0.773938 -0.000985478 -0.632284 0.774736 -0.00175391 -0.65617 0.754611 0.00754864 -0.655641 0.755035 0.00756563 -0.658446 0.75259 -0.000858252 -0.658785 0.752331 -0.000777252 -0.672939 0.739698 -0.00893643 -0.673149 0.739453 -0.00893319 -0.686632 0.72695 -0.0271011 -0.226238 0.973695 -0.0222674 -0.226347 0.973792 -0.0225522 -0.236335 0.97141 -0.0194755 -0.236128 0.971527 -0.019473 -0.237327 0.971235 -0.0224676 -0.237445 0.971141 -0.0224709 -0.243663 0.9696 -0.0254625 -0.243736 0.969507 -0.0255102 -0.249664 0.967996 -0.39144 -0.253331 0.884645 -0.758814 -0.0232205 0.650893 -0.190427 -0.959714 0.206608 -0.0283993 -0.998297 -0.0509593 -0.140461 -0.982125 0.125302 -0.677224 -0.428385 0.598209 -0.313336 -0.898219 0.308258 -0.426008 -0.811199 0.400592 -0.543167 -0.695255 0.470734 -0.569181 -0.642462 0.513104 -0.648827 -0.495688 0.577336 -0.555998 -0.0870646 0.826611 -0.121362 -0.956355 0.265814 -0.121292 -0.956439 0.265542 -0.350998 -0.690693 0.632253 -0.351438 -0.687512 0.635467 -0.490647 -0.245465 0.83607 -0.740584 -0.256271 0.621176 -0.741682 -0.213591 0.635836 -0.0327423 -0.952466 0.302882 -0.0329913 -0.953364 0.300014 -0.125662 -0.684538 0.718064 -0.12535 -0.68302 0.719564 -0.186427 -0.250222 0.95007 -0.184702 -0.243414 0.952174 0.0186343 0.964017 0.265186 0.0502726 0.696879 0.715425 0.067836 0.251963 0.965356 0.0678352 0.251961 0.965357 -0.383109 0.251961 0.888675 -0.383111 0.251958 0.888675 -0.74846 0.251959 0.613453 -0.748461 0.251957 0.613453 -0.946596 0.251959 0.201176 -0.946596 0.25196 0.201177 0.050272 0.696877 0.715426 -0.283923 0.696877 0.658597 -0.283922 0.696878 0.658596 -0.554684 0.696877 0.454629 -0.554682 0.696879 0.454629 -0.701522 0.696877 0.149092 -0.701523 0.696877 0.149092 0.018634 0.964017 0.265187 -0.105242 0.964017 0.244122 -0.105241 0.964017 0.244121 -0.205603 0.964017 0.168517 -0.205605 0.964017 0.168517 -0.260033 0.964017 0.0552637 -0.260032 0.964017 0.0552638 -0.258786 0.965922 -0.00493791 -0.258785 0.965922 -0.00493787 -0.608671 0.793338 -0.011614 -0.706956 0.707097 -0.0150789 -0.793221 0.608746 -0.0151354 -0.896719 0.442269 -0.0171103 -0.965729 0.25881 -0.0196172 -0.980609 0.195079 -0.0187109 0.293507 0.258823 0.920252 0.293508 0.258815 0.920254 0.214862 0.70711 0.673669 0.214862 0.70711 0.673669 0.0786457 0.965925 0.246583 0.0786457 0.965925 0.246583 -0.947018 0.188827 -0.25981 -0.947018 0.188828 -0.25981 -0.870509 0.430325 -0.23882 -0.814196 0.541056 -0.21058 -0.774536 0.59577 -0.21249 -0.548333 0.822618 -0.150432 -0.601186 0.785187 -0.148518 -0.183077 0.980378 -0.0730826 -0.257591 0.963666 -0.0706688 -0.694443 0.188829 -0.694329 -0.694443 0.188831 -0.694328 -0.594019 0.542586 -0.593921 -0.594019 0.542587 -0.59392 -0.40209 0.822619 -0.402022 -0.40209 0.822618 -0.402023 -0.142521 0.979481 -0.142498 -0.142521 0.979481 -0.142498 -0.259967 0.188832 -0.946974 -0.259966 0.188828 -0.946975 -0.222372 0.542586 -0.810032 -0.222372 0.542584 -0.810033 -0.150523 0.822618 -0.548308 -0.150523 0.822619 -0.548308 -0.053353 0.979481 -0.194349 -0.053353 0.979481 -0.194347 0.242607 0.188828 -0.95157 0.242605 0.188833 -0.95157 0.207522 0.542584 -0.813964 0.207522 0.542584 -0.813964 0.140471 0.822619 -0.550968 0.140471 0.822619 -0.550968 0.0497899 0.979481 -0.195291 0.0497904 0.979481 -0.195292 0.316294 0.206977 0.925807 0.320621 0.25871 0.911193 0.297353 0.585226 0.754382 0.284499 0.705186 0.64944 0.228535 0.86173 0.452983 0.172191 0.96122 0.215423 0.333218 0.188018 0.923913 0.336146 0.203488 0.919564 0.35337 0.53666 0.766242 0.355055 0.575543 0.736673 0.321684 0.80648 0.496094 0.31299 0.848373 0.426967 0.334701 0.186859 0.923612 0.335017 0.18763 0.923341 0.358625 0.533431 0.766054 0.359232 0.535405 0.764391 0.33034 0.802393 0.497033 0.33077 0.80456 0.493228 0.477439 0.195088 -0.856734 0.477439 0.195093 -0.856733 0.404752 0.555575 -0.7263 0.404753 0.555571 -0.726303 0.270451 0.831465 -0.485306 0.270449 0.831468 -0.485303 0.0949674 0.980786 -0.170413 0.0949674 0.980786 -0.170413 0.909627 0.192577 -0.368093 0.508539 0.633986 0.582623 0.442046 0.146493 0.884949 0.449473 0.160438 0.878768 0.371587 0.824891 0.426002 0.616536 0.130207 0.776485 0.657399 0.0286144 0.752999 0.721453 0.135748 0.679027 0.849211 0.150564 0.506134 0.851735 0.105705 0.5132 0.962697 0.180397 0.201673 0.975456 0.094738 0.198771 0.369207 0.828779 0.42049 0.402418 0.832687 0.380384 0.400805 0.834092 0.379006 0.422536 0.84856 0.318448 0.424979 0.847077 0.319145 0.423395 0.873219 0.241298 0.429343 0.87042 0.240903 0.507538 0.637845 0.579275 0.604965 0.649176 0.461072 0.611588 0.638703 0.466925 0.669357 0.677236 0.305471 0.690131 0.653988 0.309869 0.686541 0.71621 0.125319 0.715504 0.688175 0.120292 0.351421 0.797666 0.490135 0.359133 0.826265 0.433947 0.395822 0.52502 0.753445 0.465043 0.639701 0.611979 0.425826 0.411699 0.805715 0.604478 0.394188 0.692259 0.604408 0.397061 0.690676 0.757576 0.414998 0.50384 0.766003 0.387913 0.512605 0.854326 0.44706 0.265074 0.879474 0.393382 0.26791 0.874581 0.48487 -0.00308366 0.907452 0.419916 -0.0141851 0.977902 0.114077 -0.175199 0.973739 0.071134 -0.216268 0.986631 0.162929 0.00357687 0.828959 0.157343 -0.536722 0.85532 0.088797 -0.510433 0.837703 0.462213 -0.290882 0.806439 0.524998 -0.27209 0.672259 0.736138 -0.078546 0.642408 0.76361 -0.0649059 0.404679 0.902336 0.148407 0.394109 0.906394 0.152079 0.672288 0.147836 -0.725378 0.658873 0.23873 -0.713368 0.664677 0.506871 -0.548895 0.635951 0.567196 -0.523312 0.550021 0.786327 -0.281366 0.518912 0.815693 -0.255685 0.343434 0.938439 0.0372202 0.32217 0.945213 0.0527216 0.510563 0.196284 -0.837137 0.509761 0.200327 -0.836668 0.497194 0.557095 -0.665164 0.492333 0.567281 -0.660153 0.404682 0.828508 -0.38705 0.392942 0.839853 -0.374491 0.248149 0.967561 -0.0474169 0.228096 0.973254 -0.0273657 0.489699 0.195069 -0.84979 0.488257 0.199832 -0.849513 0.440755 0.555094 -0.705412 0.433793 0.567028 -0.700216 0.325014 0.82981 -0.453631 0.309779 0.843105 -0.439557 0.160528 0.977997 -0.133242 0.136122 0.984601 -0.109692 0.0966451 0.607869 0.788134 0.0608824 0.917836 0.392264 0.00587099 0.882931 0.469467 -0.304979 0.238436 0.922028 0.291979 0.771265 0.565595 -0.0414673 0.458657 0.887646 -0.271811 0.144575 0.951429 0.260205 0.753263 0.60406 0.265314 0.749869 0.606057 0.264302 0.749765 0.606628 0.201594 0.788424 0.581161 0.134987 0.712399 0.68867 0.144492 0.837409 0.527133 -0.307981 0.218552 0.92595 -0.2573 0.198991 0.945621 -0.261736 0.192579 0.945731 -0.245866 0.182201 0.952026 -0.245654 0.182312 0.952059 -0.249074 0.184616 0.950726 -0.142718 0.329922 0.933158 0.00459757 0.517545 0.855644 0.0108111 0.513387 0.858089 0.0101628 0.513155 0.858236 -0.0342166 0.541503 0.840002 -0.0197623 0.556467 0.830635 -0.167415 0.612646 0.772423 -0.135977 0.65616 0.74227 -0.195115 0.980315 0.0302034 -0.828875 0.553622 0.0804231 -0.977073 0.194281 0.0870867 -0.97293 0.208234 0.100226 -0.917134 0.185945 0.352548 -0.891131 0.23616 0.387447 -0.810537 0.576125 0.105407 -0.754707 0.549898 0.357812 -0.70565 0.59371 0.386738 -0.553914 0.511724 0.656748 -0.488006 0.552755 0.675509 -0.760377 0.163854 0.628473 -0.758994 0.139386 0.636002 -0.624645 0.188087 0.75792 -0.135662 0.988235 0.0706266 -0.110613 0.973581 0.199761 -0.0315091 0.977243 0.20977 0.0610479 0.926011 0.372528 0.0889843 0.926392 0.365896 0.210215 0.853618 0.476599 0.159421 0.843324 0.513214 -0.0324119 0.685742 0.727123 -0.217057 0.798326 0.561749 -0.26886 0.781894 0.562456 -0.403993 0.855272 0.324499 -0.472001 0.82731 0.304587 -0.515973 0.851321 0.094996 -0.554717 0.82982 0.0607243 -0.385656 0.208808 0.898704 -0.497439 0.114732 0.859878 -0.282821 0.406289 0.868874 -0.268118 0.420201 0.866916 -0.194776 0.540283 0.818631 -0.0404897 0.681294 0.73089 -0.338005 0.241443 0.909647 -0.338272 0.240394 0.909826 -0.236842 0.667895 0.705565 -0.238122 0.665467 0.707426 -0.080291 0.938226 0.336579 -0.0828745 0.936358 0.341125 -0.338796 0.242525 0.909065 -0.339055 0.241496 0.909242 -0.238547 0.670387 0.702621 -0.239781 0.668042 0.704432 -0.082029 0.940218 0.330547 -0.0845218 0.938438 0.334948 -0.679191 0.194955 -0.707596 -0.990172 -0.00905337 -0.139562 -0.823936 0.0924101 -0.559097 -0.194754 0.979942 -0.0422533 -0.194754 0.979942 -0.0422532 -0.551261 0.825716 -0.1196 -0.551261 0.825716 -0.1196 -0.818053 0.547073 -0.177483 -0.818052 0.547075 -0.177482 -0.959278 0.190975 -0.208122 -0.921516 0.194584 -0.336074 -0.79141 0.190979 -0.580687 -0.6749 0.547072 -0.495199 -0.674899 0.547075 -0.495197 -0.454794 0.825716 -0.333698 -0.454794 0.825717 -0.333698 -0.160674 0.979942 -0.117892 -0.160673 0.979942 -0.117891 -0.486391 0.190966 -0.852617 -0.486393 0.190976 -0.852614 -0.414786 0.547076 -0.727091 -0.414786 0.547078 -0.727089 -0.279512 0.825717 -0.489964 -0.279512 0.825715 -0.489966 -0.0987476 0.979942 -0.173098 -0.0987477 0.979942 -0.173098 -0.0721099 0.939689 0.334342 -0.206425 0.668492 0.714498 0.429171 0.244509 0.869498 0.230061 0.233412 0.94477 0.231487 0.239434 0.942913 -0.0843309 0.238093 0.967574 -0.0857832 0.234191 0.968399 -0.288449 0.24339 0.926044 -0.292198 0.240102 0.925727 -0.0704906 0.940131 0.333444 -0.0192282 0.93776 0.346751 -0.0184027 0.938528 0.344713 0.0634038 0.938865 0.338398 0.063356 0.938357 0.339812 0.139827 0.941632 0.306231 0.141297 0.939944 0.31071 0.202731 0.945919 0.253254 0.207091 0.943465 0.258819 0.245949 0.951627 0.184162 0.252858 0.948954 0.188546 -0.203611 0.670251 0.713657 -0.0596711 0.661758 0.747339 -0.0584863 0.664109 0.745344 0.167516 0.665013 0.727803 0.167075 0.662127 0.730529 0.377593 0.671075 0.63803 0.379182 0.66321 0.64527 0.549129 0.679646 0.486353 0.555334 0.667755 0.495689 0.663819 0.690439 0.28747 0.675029 0.675998 0.295573 0.592637 0.0713961 0.8023 0.526753 0.230955 0.818041 0.721333 0.251012 0.645502 0.785837 0.131206 0.604355 0.820159 0.242764 0.518078 0.911682 0.260935 0.317409 0.916754 0.231378 0.325617 -0.059279 0.980786 -0.185863 -0.0592791 0.980786 -0.185863 -0.168817 0.831467 -0.529305 -0.168816 0.831467 -0.529305 -0.252648 0.555577 -0.792151 -0.252653 0.555569 -0.792155 -0.298024 0.195092 -0.934409 -0.298024 0.195092 -0.934409 0.953857 0.251925 0.163376 0.953398 0.253653 0.163381 0.699446 0.691391 0.180978 0.69664 0.694311 0.180624 0.264473 0.952357 0.151888 0.258492 0.954173 0.150783 0.954695 0.250453 0.160721 0.954215 0.252257 0.160748 0.701912 0.687969 0.184437 0.699018 0.690994 0.184122 0.269525 0.949442 0.160987 0.263377 0.951347 0.159913 0.149275 0.98725 -0.0552614 -0.252707 0.245553 -0.935865 -0.254671 0.235524 -0.937908 -0.107322 0.675562 -0.729451 -0.11609 0.652436 -0.7489 0.0644226 0.937498 -0.341976 0.0490623 0.919795 -0.38932 0.219807 0.966809 0.130252 0.203313 0.977368 0.0584421 -0.243144 0.242228 -0.939259 -0.243142 0.243353 -0.938968 -0.0805292 0.666963 -0.740726 -0.0802384 0.669571 -0.738401 0.101985 0.927435 -0.35981 0.102445 0.92948 -0.354361 0.259534 0.959486 0.109673 0.259458 0.958545 0.117782 -0.25727 0.218204 -0.941382 -0.252085 0.244309 -0.936358 -0.127339 0.611115 -0.781232 -0.104041 0.672248 -0.732979 0.0272788 0.883278 -0.468056 0.0692918 0.93449 -0.349181 0.262375 0.941364 0.212117 0.252711 0.961056 0.111844 -0.286459 0.195077 -0.938022 -0.28617 0.221729 -0.932171 -0.216982 0.555183 -0.802926 -0.206455 0.620909 -0.756206 -0.114896 0.830147 -0.545577 -0.0865329 0.897694 -0.432039 0.00432845 0.978607 -0.205695 0.0497475 0.998485 -0.0235108 0.982371 0.176051 0.0628806 0.963479 0.267388 0.0145668 0.902941 0.421833 0.0821812 0.802897 0.586129 0.108671 0.712408 0.699136 0.0606913 0.622594 0.772843 0.122846 0.272284 0.952088 0.139245 0.210246 0.973439 0.0906224 0.458882 0.878079 0.135665 0.796042 0.605051 -0.0152093 0.454698 0.88771 0.0722543 0.211887 0.970812 0.112377 0.621809 0.776253 0.10385 0.896569 0.440758 -0.0435594 0.974538 0.199882 -0.101599 0.222337 0.967473 0.120677 0.218499 0.970777 0.0992503 0.247352 0.964095 0.0966366 0.23758 0.968094 0.0796831 0.254365 0.964426 0.0719823 0.243049 0.967999 0.0624898 0.24629 0.967365 0.0595444 0.575648 0.815792 0.0557938 0.554799 0.830344 -0.052228 0.587121 0.807627 -0.0550272 0.509602 0.839191 -0.189907 0.536823 0.818855 -0.203219 0.418703 0.856239 -0.302561 0.435983 0.841302 -0.319576 0.847158 0.530216 0.0345766 0.802551 0.563697 -0.19534 0.829945 0.522572 -0.195218 0.696491 0.576397 -0.427395 0.724041 0.531742 -0.439334 0.519043 0.596513 -0.612182 0.541065 0.554138 -0.632598 0.337056 0.225086 -0.914183 0.544513 0.165825 -0.822197 0.528612 0.238446 -0.814686 0.786881 0.157286 -0.596725 0.77067 0.226186 -0.595741 0.906241 0.178265 -0.383339 0.935051 0.0977288 -0.340777 0.953998 0.203779 -0.219913 0.979463 0.182997 -0.084645 0.170223 0.203071 -0.964254 0.204253 0.148392 -0.967606 0.297468 0.588678 -0.751646 0.282753 0.623012 -0.729319 0.289736 0.873348 -0.391556 0.281375 0.882397 -0.3771 0.221237 0.973565 0.0567903 0.224542 0.973104 0.0514747 -0.0884353 0.2112 -0.973434 -0.101437 0.257143 -0.961035 0.00641084 0.628692 -0.777628 -0.000766677 0.650773 -0.759272 0.101898 0.908872 -0.404435 0.0997211 0.912679 -0.396324 0.176258 0.982045 0.0672294 0.179377 0.982202 0.0557127 0.0996753 0.95398 0.282819 0.318829 0.597032 0.736139 0.327955 0.640792 0.694141 0.371971 0.211852 0.903746 0.377628 0.229996 0.896939 0.364887 0.250867 0.896618 0.359155 0.230571 0.904347 0.283109 0.689061 0.667116 0.274588 0.642327 0.715554 0.164142 0.91739 0.362564 0.210979 0.915236 0.343266 0.205301 0.875148 0.43814 -0.00712524 0.499617 0.866217 0.319099 0.76038 0.565684 0.141002 0.675408 0.723838 -0.271956 0.358129 0.893187 -0.0625373 0.541464 0.838395 -0.144154 0.513487 0.845902 0.0232927 0.610053 0.792018 0.257163 0.752715 0.606042 0.251505 0.756908 0.603188 0.294805 0.766335 0.570807 0.0763874 0.535712 0.840938 -0.269032 0.146427 0.951935 -0.397903 0.244462 0.884258 -0.472635 0.047359 0.879985 -0.481136 0.366628 0.796299 -0.549875 0.0790047 0.831502 0.0139787 0.0653674 0.997763 -0.0539968 0.163742 0.985024 -0.148401 0.20927 0.966532 0.296776 0.598356 0.744241 0.260971 0.546229 0.795945 0.265508 0.87062 0.414157 0.236059 0.832963 0.500449 0.240484 0.792691 0.560186 0.290496 0.818686 0.495343 0.119719 0.514535 0.849071 0.187453 0.565416 0.803222 0.0117963 0.226848 0.973859 0.239391 0.169768 0.955966 0.276416 0.218683 0.935827 0.358821 0.245733 0.900479 0.358985 0.245738 0.900413 0.364207 0.184812 0.912797 0.0915712 0.953821 0.286078 0.358581 0.250728 0.899197 0.256658 0.688689 0.678111 0.26019 0.681254 0.684247 0.0947593 0.950527 0.295836 0.090088 0.95039 0.29773 0.095967 0.944761 0.313395 0.222178 0.761586 0.608789 0.258094 0.681195 0.685099 0.290331 0.57814 0.762536 0.329838 0.417433 0.846733 -0.860195 0.100904 0.499882 -0.170207 0.52867 0.831587 -0.152747 0.523098 0.838473 -0.320438 0.41212 0.852923 -0.374306 0.294918 0.879158 -0.422017 0.300008 0.85551 -0.601579 0.135841 0.787179 0.335779 0.746064 0.575013 0.328968 0.749535 0.574437 0.0872142 0.668614 0.738478 0.180099 0.628964 0.756286 0.00675961 0.62865 0.777659 -0.863914 -0.082134 0.496896 0.355395 0.740437 0.57048 0.339224 0.741934 0.578326 0.012695 0.685911 0.727575 0.0659645 0.693356 0.71757 -0.330529 0.535738 0.777004 -0.210699 0.575897 0.789904 -0.626272 0.314641 0.713291 -0.463704 0.401479 0.789806 -0.694916 0.221203 0.684223 -0.592314 0.0916026 0.800483 0.31258 0.776439 0.547207 0.34558 0.764639 0.543968 -0.110319 0.785141 0.609412 -0.0253058 0.780597 0.624523 -0.508563 0.654916 0.558971 -0.389248 0.682093 0.61906 -0.814473 0.413948 0.406548 -0.695502 0.485287 0.52988 -0.978713 0.1041 0.176873 -0.903154 0.218001 0.36985 0.414663 0.577102 0.703568 0.135046 0.94522 0.297189 0.298268 0.761566 0.575372 0.431661 0.418472 0.799094 0.517626 0.172544 0.838028 0.520553 0.187765 0.832928 0.123585 0.965231 0.230338 0.150402 0.967042 0.205447 0.153614 0.965546 0.210057 0.183141 0.970902 0.154302 0.188004 0.96941 0.157794 0.197286 0.975696 0.0953724 0.202415 0.974494 0.0968985 0.19028 0.981132 0.0342491 0.194324 0.980345 0.0340944 0.289906 0.795612 0.531936 0.429156 0.807826 0.404032 0.434125 0.800982 0.412266 0.520793 0.81665 0.248712 0.529731 0.80864 0.255904 0.557338 0.827267 0.0707345 0.568693 0.819148 0.0747255 0.532667 0.838916 -0.111741 0.543957 0.831656 -0.111622 0.434565 0.518195 0.736632 0.645319 0.536564 0.543749 0.648967 0.522119 0.553384 0.780149 0.54574 0.305835 0.788531 0.528038 0.31527 0.830355 0.556122 0.0352004 0.842462 0.537135 0.0417747 0.78828 0.566864 -0.239334 0.801647 0.548801 -0.23702 0.807318 0.208156 -0.552186 0.929031 0.181086 -0.32266 0.920309 0.210681 -0.329612 0.984452 0.175622 0.00345511 0.978545 0.205952 -0.00579902 0.959752 0.187265 0.209302 0.942935 0.113608 0.312996 0.908957 0.197302 0.367245 0.775117 0.173065 0.607653 0.821269 0.0639467 0.566946 0.694847 0.189348 0.693783 0.702058 0.198242 -0.68397 0.763351 0.116526 -0.635387 0.667468 0.561696 -0.48886 0.655712 0.576747 -0.487242 0.455336 0.84468 -0.281396 0.446465 0.850331 -0.278579 0.163653 0.986245 -0.0232178 0.161335 0.986647 -0.0223394 0.515825 0.196766 -0.833791 0.507831 0.214539 -0.834315 0.451848 0.573941 -0.682953 0.444056 0.584232 -0.679329 0.310076 0.856258 -0.413128 0.30497 0.859842 -0.409469 0.112839 0.991302 -0.0677321 0.112086 0.99143 -0.0671135 0.292524 0.808648 0.510409 0.268199 0.820854 0.50425 -0.981961 0.180258 0.0570933 -0.818093 0.508183 0.269211 0.292631 0.809867 0.508412 0.314744 0.798161 0.513688 -0.123701 0.850177 0.511759 -0.105848 0.847692 0.519821 -0.518354 0.742128 0.424918 -0.982326 0.178854 0.0552055 -0.982324 0.178871 0.0551776 -0.982725 0.177291 0.053105 -0.903847 0.385801 0.184982 -0.821405 0.513012 0.249225 -0.822286 0.504525 0.263251 -0.507472 0.74485 0.433209 -0.796582 0.536057 0.279464 -0.615203 0.688282 0.384437 -0.517113 0.754137 0.40481 -0.439504 0.779698 0.445991 -0.123698 0.850216 0.511695 -0.1933 0.856672 0.478276 0.0118982 0.85594 0.516938 0.361188 0.208048 -0.908988 0.361261 0.208316 -0.908898 0.317198 0.588042 -0.744038 0.317301 0.588727 -0.743452 0.218148 0.865991 -0.449967 0.218155 0.866685 -0.448627 0.0812144 0.993653 -0.0778265 0.0811088 0.993805 -0.0759844 0.360872 0.208064 -0.90911 0.360967 0.207773 -0.909139 0.316311 0.588087 -0.744379 0.316718 0.587372 -0.744771 0.216841 0.866058 -0.450471 0.217685 0.865314 -0.451492 0.0797123 0.99373 -0.0784055 0.0810239 0.993491 -0.0800654 -0.444029 0.894323 0.0550009 0.0134213 0.872666 0.488133 -0.19728 0.979015 0.0510927 -0.793806 0.608045 0.0123696 -0.609823 0.79061 0.055249 -0.897082 0.441852 0.00332104 -0.980238 0.195074 -0.0328694 -0.0177075 0.991851 0.126166 -0.021062 0.980336 0.19621 0.0309422 0.970476 0.239203 0.0251551 0.934856 0.354136 0.187314 0.905074 0.381779 0.182773 0.857279 0.481319 0.268725 0.826879 0.494022 -0.785019 0.619239 0.0169702 -0.790001 0.606746 0.0880802 -0.776422 0.620789 0.108582 -0.778469 0.598024 0.190666 -0.733945 0.642118 0.221378 -0.44255 0.89503 0.055426 -0.449465 0.878957 0.159423 -0.416081 0.888697 0.1926 -0.419456 0.854779 0.305631 -0.31221 0.88565 0.343728 -0.318335 0.836899 0.445266 -0.194148 0.847746 0.493593 -0.438037 0.794345 0.42088 -0.613675 0.703364 0.358724 -0.739374 0.597865 0.309651 -0.7956 0.545703 0.263114 -0.903071 0.393675 0.171704 -0.975093 0.220538 -0.0235916 -0.976256 0.2166 -0.00303558 -0.974846 0.22285 0.00365055 -0.976011 0.21518 0.033174 -0.971164 0.234285 0.0441634 -0.973092 0.216351 0.0792714 -0.98247 0.179973 0.0485961 0.395244 0.44092 -0.805836 0.350339 0.785179 -0.510644 0.49235 0.582141 -0.647072 0.460773 0.840445 -0.285202 0.390051 0.206701 -0.897293 0.338438 0.931488 0.133379 0.324124 0.934394 0.147822 0.445437 0.873937 0.194474 0.433949 0.874496 0.216669 0.489725 0.838683 0.238287 0.503987 0.837639 0.210613 0.404531 0.898164 0.172206 0.443868 0.891547 0.0901398 0.181195 0.983386 -0.0109849 0.237171 0.964729 -0.114231 0.453012 0.847919 -0.275343 0.561843 0.79417 -0.231576 0.558066 0.800946 -0.216906 0.609203 0.767886 -0.198047 0.61369 0.758924 -0.217757 0.524027 0.813939 -0.250797 0.53826 0.785474 -0.30546 0.307958 0.866189 -0.393546 0.289943 0.887781 -0.357461 0.489416 0.589216 -0.642882 0.565156 0.553169 -0.612048 0.565463 0.559746 -0.605752 0.600712 0.536246 -0.592947 0.599711 0.526943 -0.602228 0.537767 0.566134 -0.62474 0.53747 0.538363 -0.649069 0.379873 0.593946 -0.709172 0.376203 0.605778 -0.701074 0.22552 0.974054 -0.0189846 0.174172 0.982222 0.0700293 0.341826 0.852203 -0.396113 0.314263 0.887025 -0.338269 0.401546 0.581752 -0.707337 0.392184 0.616435 -0.682788 0.393285 0.219855 -0.892743 0.42647 0.207747 -0.880321 0.426035 0.210559 -0.879863 0.453152 0.198121 -0.869139 0.453915 0.200651 -0.868159 0.46612 0.192262 -0.863578 0.464716 0.188439 -0.865176 0.442444 0.202962 -0.873527 0.439718 0.191694 -0.87744 0.383239 0.211757 -0.899048 0.384633 0.194967 -0.902245 -0.979894 0.195087 -0.0418219 -0.979894 0.195089 -0.0418218 -0.896058 0.442286 -0.0382437 -0.896059 0.442284 -0.0382438 -0.792629 0.608765 -0.0338294 -0.79263 0.608764 -0.0338294 -0.60821 0.793352 -0.0259584 -0.60821 0.793352 -0.0259584 -0.441903 0.896865 -0.0188604 -0.258738 0.965921 -0.00717706 -0.194911 0.980786 -0.00831881 0.352776 0.195081 -0.915146 0.352775 0.195082 -0.915146 0.322591 0.4423 -0.836843 0.322591 0.4423 -0.836843 0.285359 0.60876 -0.740258 0.285359 0.60876 -0.740258 0.218961 0.793359 -0.568013 0.218961 0.793358 -0.568013 0.159092 0.896864 -0.412704 0.159092 0.896864 -0.412704 0.0701707 0.980786 -0.182032 0.0701697 0.980786 -0.18203 0.0588963 0.891771 -0.448637 0.10434 0.597844 -0.794793 -0.867406 0.432225 -0.246554 -0.944409 0.189817 -0.268442 -0.944409 0.189818 -0.268442 -0.717223 0.189818 -0.670492 -0.717224 0.189822 -0.670491 -0.331369 0.189823 -0.924209 -0.331367 0.189812 -0.924212 0.127795 0.189812 -0.973468 0.127796 0.189809 -0.973468 -0.771064 0.597851 -0.219169 -0.81124 0.543122 -0.216582 -0.612642 0.544663 -0.572723 -0.612643 0.544658 -0.572727 -0.283049 0.544657 -0.78945 -0.283049 0.544659 -0.789449 0.109162 0.544659 -0.831523 0.154911 0.435522 -0.886748 -0.598183 0.786795 -0.152086 -0.544925 0.824055 -0.154891 -0.413839 0.824054 -0.386875 -0.413839 0.824054 -0.386875 -0.191199 0.824054 -0.533271 -0.191199 0.824055 -0.533269 0.0737383 0.824055 -0.56169 0.0974166 0.7868 -0.609472 -0.255643 0.964037 -0.0726643 -0.180878 0.980537 -0.0763521 -0.146461 0.979695 -0.136918 -0.146461 0.979695 -0.136919 -0.0676675 0.979695 -0.18873 -0.0676674 0.979695 -0.188729 0.0260965 0.979695 -0.198788 0.0260972 0.979695 -0.198789 -0.0664351 0.198542 0.977838 0.81967 0.470248 0.327121 -0.137448 0.198053 0.970506 0.0469618 0.9978 0.0467873 0.572526 0.800699 -0.176339 0.145338 0.965265 0.217117 0.258296 0.882997 0.391918 0.758048 0.65078 0.0429985 0.338154 0.772893 0.536926 0.426661 0.598782 0.677805 0.0747292 0.984587 0.158128 0.0747596 0.98441 0.159209 0.208732 0.836836 0.5061 0.208762 0.837064 0.50571 0.308319 0.557842 0.770553 0.308713 0.559339 0.769309 0.100991 0.0569167 0.993258 0.00867031 0.985124 0.171624 0.00860568 0.98509 0.171826 0.0215736 0.838202 0.544934 0.0216072 0.838251 0.544856 0.0309102 0.559625 0.828169 0.0310693 0.559936 0.827953 0.0353206 0.197148 0.979737 0.358962 0.194698 0.912819 0.360162 0.197802 0.911679 0.512606 0.197839 0.835521 -0.0587028 0.984834 0.163268 -0.0582558 0.984959 0.162674 -0.168187 0.837822 0.519391 -0.168318 0.837707 0.519535 -0.250002 0.559789 0.790022 -0.250645 0.558866 0.790472 -0.29225 0.197582 0.935709 -0.293248 0.195597 0.935814 -0.444127 0.196085 0.874244 -0.444427 0.193615 0.874642 -0.37547 0.55808 0.739979 -0.377594 0.551831 0.743576 -0.249054 0.83426 0.491917 -0.25416 0.827292 0.500989 -0.0843094 0.982138 0.168215 -0.0926548 0.978687 0.183265 -0.445436 0.198357 0.873064 -0.445699 0.196079 0.873445 -0.378022 0.563816 0.73431 -0.379964 0.558062 0.737695 -0.251111 0.840553 0.480014 -0.255815 0.834233 0.488481 -0.0846551 0.985027 0.150185 -0.0923595 0.982106 0.164125 0.717074 0.206433 0.665726 0.0245972 0.997873 0.0603657 0.086083 0.963737 0.252587 0.0818945 0.99211 0.0949278 0.268253 0.882735 0.38577 0.294722 0.772539 0.562425 0.311773 0.857474 0.409312 0.476868 0.576818 0.663233 0.451243 0.598066 0.662342 0.61353 0.203439 0.763016 0.578736 0.239338 0.779603 0.816529 0.213574 0.536346 0.770369 0.130288 0.624145 0.6156 0.598407 0.512783 0.61966 0.579111 0.529766 0.355697 0.88117 0.311479 0.374227 0.857993 0.351855 0.0261973 0.998514 0.0477868 0.061844 0.99167 0.112987 0.920307 0.220341 0.323241 0.920401 0.217647 0.324794 0.746248 0.611956 0.261963 0.749646 0.605335 0.267584 0.42865 0.890932 0.149999 0.438293 0.884443 0.160185 0.0243347 0.999677 0.00728577 0.0405972 0.998941 0.0216612 -0.842407 0.190735 0.503956 -0.101147 0.986297 -0.130335 -0.283415 0.841918 -0.459185 -0.418961 0.563023 -0.712374 -0.489284 0.201026 -0.84864 -0.487011 0.196181 -0.851078 -0.670779 0.195479 -0.715432 -0.724738 0.110663 -0.68008 -0.781382 0.199256 -0.591388 -0.899465 0.189421 -0.393805 -0.899716 0.198491 -0.388732 -0.979346 0.187959 -0.0745236 -0.978026 0.196346 -0.0700987 -0.101238 0.986137 -0.131475 -0.147758 0.984327 -0.0962731 -0.148394 0.984108 -0.0975248 -0.183317 0.982027 -0.044921 -0.183645 0.981951 -0.0452347 -0.19859 0.979988 0.0136281 -0.197564 0.980189 0.0140914 -0.192275 0.978582 0.0735408 -0.189705 0.979067 0.0737622 -0.283461 0.842459 -0.458163 -0.416668 0.836333 -0.356279 -0.415996 0.837433 -0.354477 -0.518714 0.831283 -0.19976 -0.516964 0.832875 -0.197655 -0.561908 0.826944 -0.0205677 -0.558989 0.828961 -0.0188283 -0.542895 0.824067 0.161798 -0.539291 0.82629 0.162514 -0.419684 0.565491 -0.709989 -0.616472 0.556378 -0.557141 -0.616015 0.560732 -0.553268 -0.769522 0.551504 -0.321992 -0.767552 0.556576 -0.317943 -0.835138 0.547628 -0.0514613 -0.831961 0.552724 -0.0483369 -0.807605 0.545345 0.22444 -0.804077 0.549866 0.22607 -0.947848 0.194325 0.252631 -0.94966 0.0808565 0.302667 -0.970969 0.193026 0.141279 -0.746002 0.193955 0.637073 -0.823326 0.108929 0.557018 -0.687627 0.548141 0.476142 -0.690601 0.544616 0.475882 -0.460797 0.824854 0.327539 -0.464132 0.822788 0.328027 -0.161647 0.978534 0.12783 -0.164798 0.977902 0.128643 -0.583431 0.191884 0.78917 -0.584783 0.189168 0.788825 -0.494977 0.547251 0.674918 -0.496843 0.544949 0.675409 -0.331734 0.824245 0.458883 -0.333945 0.822697 0.460054 -0.116426 0.978355 0.171072 -0.118766 0.977798 0.172642 0.166336 0.981965 0.0898723 0.965314 0.204408 0.162436 0.707758 0.691483 0.144674 0.936259 0.31656 0.152344 0.800528 0.57878 0.155463 0.933664 0.315522 0.169462 0.933666 0.315517 0.169462 0.557987 0.820378 0.125025 0.502928 0.856532 0.11583 0.41312 0.904406 0.106687 0.119914 0.990672 0.0647318 0.170541 0.982916 0.0692261 0.0251024 0.999681 0.00282142 0.126681 0.991684 0.0226736 0.444039 0.893046 0.0727923 0.507713 0.857255 0.0856789 0.77792 0.615057 0.128632 0.803903 0.579367 0.134443 0.962582 0.218947 0.159684 0.965591 0.204458 0.160719 -0.373768 0.202951 -0.905046 -0.373725 0.205063 -0.904588 -0.323519 0.575351 -0.751204 -0.322441 0.58066 -0.747574 -0.21991 0.85291 -0.473481 -0.216891 0.858496 -0.464696 -0.0800253 0.989819 -0.117707 -0.074856 0.991802 -0.103568 -0.372603 0.200198 -0.906139 -0.37253 0.202988 -0.905548 -0.321438 0.568478 -0.757305 -0.32 0.575454 -0.75263 -0.218707 0.845567 -0.487016 -0.214724 0.853061 -0.475584 -0.0808729 0.987039 -0.138616 -0.0740845 0.989992 -0.120116 0.0176059 0.997571 0.0674025 0.555809 0.819551 0.139328 0.410725 0.903513 0.122348 0.00527817 0.997947 0.0638352 0.0208429 0.997474 0.0678992 0.701665 0.688873 0.181992 0.691534 0.700736 0.175358 0.938378 0.317434 0.136681 0.938376 0.317442 0.136681 0.955471 0.258151 0.142945 0.934295 0.31577 0.165475 0.253128 0.961674 0.105401 0.249337 0.959745 0.12931 0.166376 0.981981 0.089619 0.952394 0.256559 0.164692 0.952354 0.256764 0.164603 0.780321 0.603973 0.162224 0.699076 0.70392 0.125655 0.598086 0.787886 0.146725 0.253816 0.961443 0.105858 0.161771 0.206901 -0.964895 0.255192 0.962032 0.0968028 0.587271 0.781877 0.209241 0.785179 0.606069 0.127179 0.199572 0.979406 -0.0305792 0.195461 0.979292 0.0527475 0.198722 0.978597 0.0534644 0.18155 0.983353 -0.00755819 0.183492 0.98299 -0.00777885 0.14616 0.987378 -0.0610121 0.146815 0.987261 -0.0613206 0.550812 0.825695 0.121798 0.556202 0.831044 0.00233727 0.564409 0.825482 0.00469269 0.513173 0.839706 -0.177614 0.520716 0.83497 -0.177988 0.41039 0.847987 -0.335409 0.415787 0.844516 -0.33751 0.816216 0.541698 0.200886 0.828739 0.557544 -0.0483464 0.837893 0.544074 -0.0438179 0.760808 0.565464 -0.318469 0.770414 0.553037 -0.317194 0.605312 0.572525 -0.553003 0.613191 0.562653 -0.554454 0.514565 0.20658 -0.832194 0.709031 0.191776 -0.6786 0.7019 0.208779 -0.68099 0.895555 0.186025 -0.404199 0.888623 0.206813 -0.409361 0.979722 0.18164 -0.0845686 0.974766 0.203472 -0.0918173 0.973743 0.190337 0.124889 0.964364 0.264298 0.0121928 0.365039 0.202278 -0.908752 0.437676 0.118353 -0.891309 0.382238 0.571287 -0.72631 0.377649 0.577394 -0.723877 0.259904 0.852447 -0.453635 0.257238 0.854419 -0.451439 0.0921479 0.990664 -0.100471 0.0922144 0.990651 -0.100535 -0.00620017 0.205935 -0.978546 0.118198 0.139964 -0.983076 0.103882 0.577256 -0.809928 0.102878 0.578857 -0.808914 0.0709438 0.857134 -0.510184 0.0705381 0.857549 -0.509543 0.0255558 0.992485 -0.119668 0.0257567 0.992432 -0.120061 -0.216122 0.207635 -0.954033 -0.213726 0.202522 -0.955671 -0.187232 0.579301 -0.793319 -0.185957 0.57631 -0.795793 -0.126944 0.857525 -0.498534 -0.126457 0.856461 -0.500483 -0.0445715 0.992275 -0.115771 -0.044509 0.992226 -0.116216 -0.967502 0.240438 -0.078284 -0.968183 0.23763 -0.0784426 -0.742596 0.665436 -0.0758052 -0.748028 0.659234 -0.0765785 -0.346034 0.936564 -0.0557525 -0.358685 0.931687 -0.0574839 0.13051 0.991187 -0.0227182 0.111786 0.993404 -0.0255243 -0.965422 0.243259 -0.0937339 -0.966302 0.239736 -0.0937359 -0.734267 0.671345 -0.100731 -0.740624 0.664254 -0.101203 -0.329315 0.94049 -0.0838486 -0.343763 0.935171 -0.0853348 0.153589 0.987014 -0.0470564 0.132564 0.989921 -0.0498317 -0.762708 0.212959 -0.610676 -0.031779 0.99233 -0.119462 -0.101406 0.981556 -0.162063 -0.248268 0.906642 -0.341122 -0.382716 0.749499 -0.540166 -0.359351 0.866656 -0.346084 -0.511691 0.57727 -0.636343 -0.575162 0.478109 -0.663778 -0.65033 0.198668 -0.733213 -0.628063 0.0904128 -0.772893 -0.63333 0.282522 -0.720468 -0.850421 0.216812 -0.479351 -0.834822 0.0777927 -0.544996 -0.627353 0.613988 -0.479006 -0.638117 0.591715 -0.492626 -0.312172 0.899098 -0.306874 -0.353442 0.866299 -0.352992 0.0712304 0.995268 -0.0660866 -0.00310262 0.988489 -0.151261 -0.941288 0.230517 -0.246657 -0.939338 0.241691 -0.24337 -0.72829 0.647907 -0.223183 -0.732576 0.64198 -0.226259 -0.350307 0.924677 -0.149186 -0.37253 0.913729 -0.162238 0.112714 0.992849 -0.0393292 0.0703117 0.995474 -0.0639313 -0.752509 0.212479 0.623365 -0.490603 0.198336 0.848511 -0.351878 0.64522 0.67814 -0.447499 0.428058 0.785182 -0.490418 0.197756 0.848754 -0.410184 0.589505 0.695868 -0.213778 0.870285 0.443738 -0.210861 0.879029 0.427604 -0.101538 0.968601 0.226939 0.00161121 0.995625 0.0934258 0.0131989 0.998403 0.0549238 0.0911062 0.992903 0.0764372 0.0199075 0.993903 0.108448 -0.25574 0.895768 0.363589 -0.296605 0.878173 0.375283 -0.545954 0.611867 0.572322 -0.55615 0.602635 0.572301 -0.734635 0.146822 0.662385 -0.642835 0.215499 0.735067 0.14197 0.988552 0.0510871 0.0772265 0.995553 0.0539489 -0.304283 0.924895 0.227996 -0.340766 0.91291 0.224663 -0.675326 0.648714 0.350864 -0.684066 0.641266 0.347608 -0.891178 0.228285 0.392031 -0.884702 0.240577 0.399281 0.150486 0.988523 -0.0132943 0.124412 0.991975 -0.0225209 -0.336233 0.941507 0.0226145 -0.354635 0.934895 0.014315 -0.737491 0.673239 0.0534506 -0.746554 0.663681 0.0467449 -0.96517 0.251587 0.0717655 -0.967152 0.244978 0.0678501 0.0539906 0.196277 -0.979061 -0.463391 0.55734 -0.688942 -0.55356 0.0909441 -0.827829 -0.109736 0.981973 -0.153907 -0.109526 0.98165 -0.156102 -0.238334 0.906553 -0.348365 -0.336095 0.832503 -0.44043 -0.319689 0.746763 -0.583218 -0.55506 0.478914 -0.68011 -0.072921 0.982212 -0.17304 -0.073328 0.981707 -0.175713 -0.206154 0.831741 -0.515469 -0.206271 0.830917 -0.51675 -0.306115 0.553436 -0.774598 -0.306103 0.553178 -0.774787 -0.112535 -0.0999391 -0.988609 -0.007829 0.98252 -0.185993 -0.00772169 0.982413 -0.18656 -0.0208182 0.832488 -0.553652 -0.0207554 0.832323 -0.553902 -0.0304504 0.554368 -0.831714 -0.0304376 0.554323 -0.831745 -0.0353374 0.194469 -0.980272 -0.358486 0.193411 -0.91328 -0.35863 0.194194 -0.913057 -0.545512 0.195573 -0.814965 -0.603647 0.28341 -0.745177 0.0590649 0.982126 -0.178716 0.0581731 0.982458 -0.177176 0.167524 0.831758 -0.529259 0.167066 0.832294 -0.528561 0.249001 0.553915 -0.794467 0.248935 0.554049 -0.794393 0.29188 0.194416 -0.936487 0.292051 0.193867 -0.936548 -0.160526 0.965909 0.203105 -0.0320952 0.998803 0.036922 -0.058214 0.990607 0.123729 -0.165922 0.85374 0.493556 -0.194603 0.879576 0.434139 -0.194845 0.577298 0.792946 -0.275235 0.648354 0.709847 -0.287356 0.201858 0.936312 -0.284535 0.204935 0.936505 -0.267718 0.43467 0.859877 -0.035678 0.202937 0.978542 -0.0354703 0.203355 0.978462 -0.0304839 0.573483 0.81865 -0.0303598 0.573698 0.818504 -0.0202101 0.852727 0.521966 -0.0201679 0.852777 0.521886 -0.00643348 0.990923 0.134279 -0.00647837 0.990907 0.134389 0.296037 0.205749 0.932754 0.293247 0.199428 0.935005 0.256177 0.574271 0.777551 0.25483 0.570475 0.780782 0.174181 0.852089 0.493564 0.173756 0.850663 0.496166 0.0624839 0.990277 0.124288 0.0624395 0.990176 0.12511 0.443216 0.194166 -0.875134 0.443477 0.192161 -0.875444 0.373855 0.553225 -0.744429 0.375645 0.548055 -0.747346 0.248103 0.828843 -0.501463 0.252345 0.823044 -0.508842 0.0849108 0.979461 -0.182883 0.0918138 0.976461 -0.195179 0.444346 0.196343 -0.874075 0.444616 0.194172 -0.874422 0.375934 0.558815 -0.739189 0.377852 0.55324 -0.742397 0.249539 0.835052 -0.490324 0.254128 0.828864 -0.4984 0.0846252 0.982515 -0.165837 0.0921171 0.979487 -0.17922 0.448488 0.201962 0.870672 0.448454 0.202915 0.870468 0.387 0.572946 0.72247 0.386402 0.575303 0.720916 0.262298 0.850302 0.456273 0.26065 0.852823 0.452498 0.0947367 0.988775 0.115537 0.0919329 0.989731 0.109461 0.447739 0.200349 0.87143 0.447675 0.20199 0.871084 0.385759 0.56881 0.726392 0.384681 0.573026 0.723645 0.261792 0.845915 0.464642 0.258871 0.85042 0.458008 0.0957568 0.987106 0.128264 0.0907924 0.98891 0.117534 0.525163 0.201509 0.8268 0.522336 0.197528 0.829547 0.450383 0.567692 0.689116 0.449177 0.565483 0.691714 0.303891 0.844362 0.441251 0.303617 0.843702 0.442701 0.108558 0.986582 0.121946 0.108567 0.986606 0.121747 0.720151 0.201531 0.663903 0.718065 0.191854 0.66901 0.617033 0.562435 0.550397 0.617585 0.556959 0.555324 0.416964 0.838904 0.34983 0.418056 0.837115 0.3528 0.14893 0.984599 0.0915642 0.148859 0.984623 0.0914238 0.900235 0.199971 0.386768 0.899884 0.188836 0.393129 0.768341 0.558053 0.313415 0.770856 0.551556 0.318695 0.51774 0.833923 0.191096 0.520301 0.831607 0.19421 0.184163 0.982179 0.0375258 0.18456 0.98209 0.0379074 0.199482 0.979636 -0.0228202 0.197972 0.979926 -0.0235059 0.562937 0.826398 0.0129724 0.559006 0.829096 0.0105957 0.835978 0.546773 0.0466799 0.831772 0.553491 0.0424554 0.979666 0.186755 0.0733282 0.946989 0.040615 -0.318689 0.968345 0.191461 -0.160157 0.977936 0.197745 0.0673634 0.164634 0.976362 -0.140046 0.161538 0.976993 -0.139251 0.463148 0.819774 -0.336845 0.458984 0.822353 -0.336259 0.689469 0.541443 -0.481115 0.685199 0.546468 -0.481534 0.492693 0.544309 -0.678956 0.49546 0.540905 -0.679663 0.33002 0.820539 -0.466693 0.332744 0.818623 -0.468123 0.116286 0.976282 -0.182625 0.118566 0.97572 -0.184155 0.192562 0.977661 -0.0842533 0.189852 0.97817 -0.0844914 0.542839 0.822331 -0.170579 0.538236 0.825155 -0.171525 0.807411 0.543329 -0.22996 0.802549 0.549513 -0.232274 0.947233 0.195344 -0.254145 0.812192 0.185878 -0.552987 0.80897 0.193173 -0.555204 0.584304 0.186663 -0.789776 0.581951 0.191337 -0.790394 -0.0191121 0.992029 0.124554 -0.0149952 0.204973 0.978653 -0.0192753 0.991989 0.124841 -0.0521523 0.856523 0.513467 -0.0525409 0.856973 0.512677 -0.0761095 0.577413 0.812897 -0.0768476 0.578555 0.812015 -0.0874627 0.149401 0.984901 -0.15045 0.205735 0.966974 -0.0799339 0.990785 0.10934 -0.0809507 0.990579 0.110455 -0.223433 0.854196 0.469497 -0.226306 0.851962 0.472171 -0.328162 0.576829 0.748049 -0.332297 0.571183 0.750553 -0.378131 0.207998 0.902083 -0.382665 0.198685 0.90227 -0.527575 0.203336 0.824815 -0.527598 0.203116 0.824854 -0.454954 0.576299 0.678894 -0.455159 0.575754 0.679218 -0.306949 0.853801 0.420484 -0.307468 0.853222 0.421278 -0.108097 0.989835 0.0924252 -0.108952 0.989621 0.0936961 -0.527803 0.203395 0.824654 -0.52781 0.203324 0.824667 -0.455552 0.576463 0.678353 -0.455627 0.576265 0.678472 -0.307765 0.853956 0.419572 -0.30795 0.853749 0.419856 -0.108955 0.989851 0.0912353 -0.109263 0.989775 0.0916936 0.68088 0.238055 0.692627 -0.0018002 0.99264 0.12109 0.0122318 0.992283 0.123389 0.0228052 0.860067 0.509671 0.0341965 0.858932 0.510946 0.0430148 0.582013 0.812041 0.0505866 0.58095 0.812366 0.0556712 0.20553 0.977066 0.0583198 0.205128 0.976996 0.218776 0.195332 0.956024 0.221771 0.204232 0.953471 0.156407 0.591301 0.791139 0.153249 0.579947 0.80011 0.0635401 0.87905 0.472477 0.0579419 0.860022 0.506956 -0.0414877 0.997331 0.0600809 -0.0487669 0.99104 0.124341 0.503202 0.207384 0.838916 0.507674 0.230236 0.830216 0.357857 0.621622 0.696796 0.357882 0.615327 0.702348 0.133304 0.906154 0.401391 0.138844 0.887631 0.439128 -0.122013 0.992429 0.0140248 -0.109534 0.9899 0.090003 0.788581 0.23893 0.566614 0.760263 0.174728 0.625676 0.547842 0.659815 0.514308 0.54949 0.652868 0.521368 0.222249 0.934901 0.276705 0.23519 0.921944 0.307741 -0.160484 0.986539 -0.0314071 -0.134477 0.990591 0.0253951 0.908277 0.257207 0.329965 0.908304 0.247507 0.337231 0.691687 0.682116 0.237248 0.697379 0.671999 0.249158 0.308287 0.947365 0.086367 0.320566 0.941711 0.102073 -0.155035 0.983943 -0.0884355 -0.138222 0.987887 -0.0705213 -0.377699 0.58742 -0.715739 -0.207888 0.875433 -0.436349 -0.0908613 0.967713 -0.235109 -0.2091 0.765512 -0.608497 -0.428395 0.425826 -0.796963 -0.0905041 0.967554 -0.2359 -0.124854 0.968708 -0.214514 -0.125996 0.967969 -0.217167 -0.166698 0.971814 -0.166703 -0.169146 0.970933 -0.16935 -0.191012 0.975674 -0.107589 -0.194372 0.974811 -0.109375 -0.261133 0.807378 -0.529103 -0.358542 0.808809 -0.466128 -0.360486 0.804632 -0.471823 -0.477192 0.81563 -0.327161 -0.482109 0.810247 -0.333272 -0.544937 0.823851 -0.155927 -0.552454 0.817934 -0.160556 -0.335104 0.528499 -0.779996 -0.539581 0.535915 -0.649344 -0.540487 0.526582 -0.65619 -0.716048 0.543073 -0.438574 -0.720329 0.530756 -0.44657 -0.81471 0.551133 -0.180278 -0.822378 0.537276 -0.187159 -0.978072 0.199816 0.0587274 -0.966173 0.178705 -0.185943 -0.963368 0.200896 -0.177661 -0.851195 0.17676 -0.494189 -0.851393 0.196261 -0.486427 -0.641968 0.176629 -0.746109 -0.64427 0.191306 -0.740485 -0.472521 0.185366 -0.861605 -0.476355 0.18829 -0.858855 -0.955765 0.190431 0.224165 -0.98089 0.105346 0.163577 -0.832781 0.545553 0.0940668 -0.823097 0.559358 0.0981348 -0.561503 0.826997 0.0281109 -0.552877 0.832722 0.0300304 -0.198022 0.979231 -0.0435278 -0.194498 0.979961 -0.0429713 -0.868423 0.187352 0.459064 -0.861413 0.207251 0.463697 -0.747651 0.554649 0.365216 -0.738091 0.566835 0.365949 -0.505778 0.836384 0.211305 -0.497925 0.841296 0.210459 -0.178735 0.983679 0.0207175 -0.175778 0.984222 0.0202013 -0.664016 0.193016 0.722376 -0.65742 0.208179 0.724196 -0.574102 0.563378 0.594148 -0.566776 0.57258 0.592382 -0.389372 0.844866 0.366867 -0.383848 0.848482 0.364333 -0.137811 0.987577 0.0754972 -0.135899 0.987922 0.0744463 0.9568 0.239074 0.165463 0.955563 0.24466 0.16444 0.74528 0.661457 0.0838544 0.733043 0.675543 0.0793081 0.362473 0.93184 -0.0169851 0.332836 0.942649 -0.0251594 -0.103656 0.988079 -0.113821 -0.148032 0.981216 -0.123697 0.959985 0.230316 0.159321 0.958241 0.23837 0.157971 0.762388 0.6412 0.08733 0.745739 0.661237 0.0814804 0.402368 0.915472 -0.0032224 0.36187 0.932126 -0.0138588 -0.043369 0.994723 -0.0929778 -0.105115 0.988773 -0.1062 -0.192602 0.874989 -0.444182 -0.431327 0.249435 -0.867029 -0.109003 0.955443 -0.27431 -0.084943 0.967515 -0.238116 -0.111362 0.951922 -0.285382 -0.11364 0.951998 -0.284227 -0.309222 0.691156 -0.653212 -0.265954 0.769167 -0.581078 -0.310635 0.686142 -0.657811 -0.311251 0.686163 -0.657498 -0.431092 0.251651 -0.866505 -0.438421 0.186989 -0.879103 -0.431947 0.249457 -0.866714 -0.396539 0.424874 -0.813781 -0.348576 0.586623 -0.731005 0.9461 0.208664 -0.247698 0.571298 0.673795 -0.468635 0.645003 0.479373 -0.595125 0.623877 0.554374 -0.55086 0.704234 0.422496 -0.570571 0.777584 0.193274 -0.598338 0.370476 0.838394 -0.399805 0.369369 0.839052 -0.399448 0.315379 0.884271 -0.344385 0.156146 0.962934 -0.219945 0.0513761 0.982921 -0.176712 -0.00852644 0.992946 -0.118257 0.919967 0.0826165 -0.38319 -0.0168054 0.985787 -0.167156 0.0556081 0.984089 -0.16875 0.398662 0.87162 -0.285214 0.43241 0.857015 -0.280262 0.73192 0.587277 -0.345541 0.732957 0.586271 -0.345051 0.914186 0.221973 -0.339105 0.776532 0.181255 -0.603444 -0.0378783 0.99169 -0.122952 -0.00806028 0.993724 -0.111569 0.418333 0.90221 -0.104955 0.427374 0.898538 -0.0999047 0.780302 0.622078 -0.0644004 0.774816 0.628322 -0.0697945 0.976631 0.214732 -0.00910373 0.970575 0.239224 -0.0274846 0.270642 0.880821 -0.388468 0.184416 0.955117 -0.231825 0.157251 0.963006 -0.21884 0.0268599 0.996205 -0.0827846 0.642107 0.187411 -0.743355 0.554066 0.414939 -0.72169 0.533051 0.471793 -0.702331 0.428077 0.690708 -0.582815 0.45798 0.669467 -0.584866 0.320279 0.83427 -0.448794 0.301373 0.141135 -0.943003 0.440902 0.249668 -0.862132 0.588747 0.252752 -0.767785 0.0112466 0.953447 -0.301352 0.011219 0.953464 -0.301299 0.0268532 0.68409 -0.728903 0.0268412 0.684106 -0.728889 -0.204055 0.683508 -0.700842 -0.20503 0.686035 -0.698082 -0.07325 0.953574 -0.292116 -0.0735364 0.954181 -0.290053 0.0955869 0.95355 -0.285667 0.0939546 0.954164 -0.284155 0.256619 0.683577 -0.683279 0.254012 0.686067 -0.681755 0.350766 0.249019 -0.902747 0.0355241 0.246468 -0.9685 0.0355524 0.246422 -0.96851 -0.283737 0.249092 -0.925984 -0.281508 0.244369 -0.927921 -0.961704 0.246113 -0.120638 -0.962265 0.243913 -0.120632 -0.723168 0.677736 -0.133046 -0.726791 0.673784 -0.133379 -0.308643 0.944436 -0.113051 -0.316577 0.941679 -0.114108 0.180983 0.981303 -0.0654968 0.169745 0.983176 -0.0674713 -0.959526 0.248916 -0.131722 -0.960507 0.245147 -0.131642 -0.715673 0.683747 -0.142491 -0.722094 0.676862 -0.142962 -0.293851 0.948565 -0.117794 -0.307942 0.943864 -0.119548 0.201047 0.977505 -0.0637459 0.181158 0.981161 -0.0671236 -0.708777 0.221484 -0.669761 -0.198505 0.5943 -0.779361 -0.133654 0.768966 -0.625163 -0.0899301 0.816063 -0.570924 -0.0338929 0.949047 -0.313307 0.031638 0.974064 -0.224051 -0.19921 0.435351 -0.877944 -0.217648 0.534679 -0.816546 -0.292704 0.206699 -0.933595 -0.283824 0.167045 -0.944214 -0.314348 0.0232035 -0.949024 -0.554017 0.166294 -0.815727 -0.555126 0.217726 -0.802765 -0.392903 0.557392 -0.731397 -0.391153 0.566277 -0.725486 -0.15507 0.848001 -0.506802 -0.164273 0.830157 -0.532779 0.114171 0.976695 -0.181744 0.0906824 0.962836 -0.25441 -0.815621 0.20706 -0.540266 -0.806977 0.155291 -0.569801 -0.566207 0.602818 -0.562157 -0.560136 0.617566 -0.552141 -0.225608 0.886787 -0.403373 -0.236414 0.876644 -0.41905 0.169673 0.973763 -0.151644 0.135729 0.96933 -0.204885 -0.92746 0.224363 -0.29913 -0.922478 0.262498 -0.28307 -0.699043 0.649301 -0.299578 -0.689535 0.664075 -0.289044 -0.30273 0.924987 -0.22968 -0.303679 0.924472 -0.230499 0.173215 0.979417 -0.103631 0.154874 0.980707 -0.119276 -0.964958 0.260046 0.0350996 -0.2614 0.499601 0.825875 -0.307058 0.0749142 0.948738 -0.218671 0.279386 0.934947 -0.0511443 0.909622 0.412277 -0.182354 0.78263 0.595179 -0.219715 0.666759 0.71215 0.0074085 0.995626 0.0931392 -0.298961 0.202835 0.932459 -0.50195 0.211585 0.838617 -0.513942 0.19336 0.835749 -0.732473 0.234276 0.639217 -0.75049 0.20862 0.627091 -0.871149 0.243315 0.426495 -0.91817 0.179578 0.353152 -0.931555 0.241931 0.271431 -0.967232 0.252099 0.0301242 -0.20163 0.578534 0.790344 -0.384408 0.587075 0.712443 -0.381326 0.590233 0.711489 -0.550668 0.621833 0.556855 -0.549514 0.622754 0.556967 -0.678161 0.659633 0.324009 -0.673773 0.663136 0.326007 -0.733887 0.679134 0.0136548 -0.724905 0.688527 0.021059 -0.167177 0.863738 0.475404 -0.197773 0.864518 0.462055 -0.174551 0.877368 0.446941 -0.260091 0.892605 0.368252 -0.227204 0.904155 0.361775 -0.309724 0.926931 0.211827 -0.279313 0.935412 0.216768 -0.3228 0.946442 -0.00683509 -0.305952 0.952045 0.00195948 -0.0156296 0.993568 0.112157 0.025343 0.991275 0.129352 0.0679498 0.993394 0.0924674 0.0843386 0.990626 0.107459 0.148858 0.985318 0.0836026 0.131351 0.989968 0.0520552 0.188458 0.980633 0.0533247 0.172673 0.984617 -0.0267009 0.195198 0.980615 -0.0170842 0.129755 0.244259 -0.96099 -0.0347462 0.94724 -0.318636 -0.283533 0.243975 -0.927408 -0.189747 0.20703 -0.959758 -0.140964 0.0210416 -0.989791 -0.0498682 0.949247 -0.310552 -0.0736274 0.768405 -0.635714 -0.278966 0.666596 -0.69125 -0.130053 0.594879 -0.793225 -0.110739 0.434464 -0.893855 0.0141984 0.94586 -0.324263 0.0139989 0.945989 -0.323895 0.0383353 0.673082 -0.738573 0.0379019 0.673659 -0.73807 0.0540922 0.173331 -0.983377 -0.0285935 0.244853 -0.969139 0.0966705 0.94667 -0.307362 0.0950244 0.947312 -0.305893 0.26461 0.673329 -0.690369 0.260619 0.677117 -0.688179 0.366158 0.238207 -0.899547 0.360699 0.246137 -0.899618 -0.0522562 0.205267 0.97731 -0.0416476 0.991862 0.120315 -0.158814 0.668227 0.726808 -0.136959 0.783621 0.605954 -0.222714 0.849486 0.478301 -0.0480433 0.909499 0.412922 -0.111747 0.991613 0.0649333 -0.387725 0.488814 0.781492 -0.172833 0.579686 0.7963 -0.19491 0.279719 0.940089 -0.319714 0.200112 0.926142 -0.199886 0.0772198 0.976772 0.116042 0.20534 0.971787 -0.0006197 0.13185 0.99127 -0.00109938 0.576173 0.817327 -0.00100591 0.57634 0.817209 -0.0011852 0.855461 0.517866 -0.00112277 0.855539 0.517737 -0.00107237 0.991872 0.127232 -0.00104596 0.991882 0.127161 0.32956 0.207358 0.921082 0.326371 0.200043 0.923832 0.284845 0.577019 0.765449 0.283372 0.572589 0.769313 0.192903 0.854723 0.48191 0.192485 0.853002 0.485115 0.067785 0.99113 0.114313 0.0677586 0.990984 0.115583 0.131463 0.948449 -0.288377 0.131104 0.94865 -0.287879 0.311527 0.767343 -0.560478 0.365336 0.681917 -0.633655 0.408794 0.585031 -0.700447 0.465322 0.423654 -0.77717 0.507341 0.247629 -0.8254 0.515001 0.186389 -0.83668 0.505728 0.247848 -0.826324 0.505791 0.247551 -0.826374 0.36329 0.682545 -0.634155 0.363708 0.681835 -0.634679 0.131427 0.949207 -0.28589 0.132312 0.948712 -0.287121 0.479724 0.203793 0.853424 0.479725 0.203766 0.85343 0.413747 0.577472 0.703803 0.413769 0.577394 0.703855 0.27893 0.855077 0.437082 0.278991 0.854992 0.43721 0.0977103 0.990413 0.097648 0.0978078 0.990384 0.0978431 0.479736 0.20383 0.853409 0.479737 0.203791 0.853417 0.413762 0.577547 0.703733 0.413783 0.577471 0.703783 0.278929 0.855151 0.436938 0.278983 0.855075 0.437053 0.097675 0.990438 0.0974243 0.0977703 0.99041 0.0976149 0.50382 0.204397 0.839278 0.499003 0.202918 0.842508 0.434046 0.577543 0.69141 0.430973 0.576666 0.694059 0.292479 0.854849 0.428589 0.290917 0.854537 0.430271 0.102622 0.990234 0.0943726 0.102178 0.990225 0.0949386 0.135886 0.987978 0.0737229 0.13495 0.988285 0.0712853 0.384704 0.846182 0.368753 0.383079 0.849721 0.362251 0.566759 0.564882 0.599744 0.566772 0.573923 0.591086 0.654232 0.193832 0.731034 0.904209 0.0441437 0.424803 0.812389 0.19617 0.549127 0.658539 0.208753 0.723013 0.197441 0.979205 -0.0466332 0.194139 0.979772 -0.0485504 0.560465 0.827638 0.029885 0.552635 0.833084 0.0237994 0.831282 0.546507 0.101493 0.823412 0.560073 0.0911631 0.194248 0.974372 -0.113434 0.190515 0.975027 -0.114138 0.552892 0.817816 -0.159649 0.543599 0.823415 -0.162752 0.823718 0.537511 -0.180471 0.813016 0.551216 -0.187526 0.177523 0.983942 0.0185176 0.175305 0.984386 0.0159122 0.502903 0.837512 0.213687 0.498088 0.842237 0.206267 0.742976 0.55602 0.372596 0.739328 0.567991 0.361636 0.859138 0.208216 0.46747 0.970432 0.182972 0.157423 0.96815 0.205141 0.143536 0.968485 0.178912 -0.173286 0.835391 -0.00224175 -0.549652 0.891936 0.184317 -0.412889 0.961827 0.201175 -0.185519 0.126971 0.966531 -0.222925 0.184981 0.949336 -0.254055 0.352927 0.800151 -0.484975 0.584035 0.425599 -0.691208 0.53187 0.521867 -0.66691 0.515984 0.585808 -0.624972 0.392764 0.767995 -0.505886 0.169521 0.970002 -0.174236 0.166211 0.970667 -0.173721 0.483989 0.809149 -0.333216 0.475387 0.814306 -0.333035 0.724244 0.53003 -0.441066 0.713406 0.542393 -0.443691 0.853161 0.196672 -0.483152 0.650737 0.175641 -0.738709 0.642616 0.191088 -0.741978 -0.335849 0.2057 0.919181 -0.332703 0.200758 0.921415 -0.2899 0.576554 0.7639 -0.288198 0.573504 0.766835 -0.196134 0.853957 0.481963 -0.195452 0.85275 0.484372 -0.0695181 0.990524 0.118448 -0.0693666 0.990412 0.119468 -0.546191 0.197626 0.814015 -0.54077 0.206316 0.815476 -0.471567 0.569395 0.67336 -0.466502 0.574681 0.672397 -0.31918 0.849121 0.420855 -0.315585 0.851252 0.419256 -0.113164 0.988848 0.0968184 -0.111733 0.989091 0.0959984 -0.102252 0.570658 0.814797 -0.0992271 0.577075 0.810641 -0.102119 0.858274 0.502929 -0.103807 0.856003 0.506441 -0.083836 0.991572 0.0987749 -0.09046 0.989294 0.114522 -0.16724 0.980124 0.106717 -0.163112 0.985078 0.0549084 -0.0343624 0.867432 0.496368 -0.0333271 0.876355 0.480512 0.103745 0.598513 0.794367 0.102347 0.58649 0.803464 -0.212287 0.974086 0.078038 -0.222443 0.974819 0.0157162 0.0590423 0.897559 0.436922 0.0548971 0.908049 0.41525 0.315665 0.636461 0.703756 0.316561 0.626337 0.712384 0.653835 0.243379 0.716426 0.501386 0.202776 0.841127 0.506729 0.249903 0.82509 0.31375 0.206453 0.926789 0.247107 0.13245 0.959893 0.155954 0.219724 0.963016 -0.0758538 0.186574 0.979508 -0.0637435 0.166824 0.983924 -0.20565 0.204306 0.957062 0.765821 0.241697 0.595904 0.756047 0.205365 0.621465 0.513342 0.674001 0.531228 0.512468 0.677285 0.527884 0.157056 0.943864 0.290611 0.165409 0.936017 0.310665 -0.244882 0.969107 -0.0294117 -0.224837 0.974231 0.0179682 0.902297 0.266709 0.338715 0.90231 0.263332 0.341312 0.664496 0.704995 0.247846 0.667976 0.698977 0.255421 0.252442 0.96329 0.091352 0.261622 0.959575 0.103776 -0.232215 0.968282 -0.0922276 -0.218416 0.972875 -0.076218 -0.63783 0.202149 0.743175 -0.63781 0.202313 0.743148 -0.549334 0.573267 0.607945 -0.549112 0.573763 0.607678 -0.370811 0.850477 0.373079 -0.370277 0.850979 0.372463 -0.131534 0.98831 0.0770846 -0.130635 0.988507 0.0760831 -0.63756 0.201914 0.74347 -0.637528 0.202169 0.743428 -0.548765 0.572685 0.609007 -0.548478 0.573324 0.608664 -0.370264 0.849877 0.374984 -0.369538 0.850561 0.374148 -0.131245 0.988144 0.0796677 -0.130047 0.988409 0.0783332 0.950556 0.254252 0.178324 0.950102 0.256241 0.177897 0.711735 0.696742 0.089353 0.708013 0.700721 0.0877934 0.28732 0.957561 -0.0228832 0.278828 0.96 -0.0255784 -0.212025 0.968701 -0.129085 -0.224034 0.96556 -0.132295 0.950698 0.251122 0.181962 0.94991 0.25452 0.181358 0.718092 0.689719 0.0929087 0.711493 0.696842 0.0904876 0.302785 0.952854 -0.0197561 0.287565 0.957459 -0.0240348 -0.189554 0.973578 -0.127337 -0.211325 0.96841 -0.132375 -0.454706 0.585297 -0.671319 -0.251989 0.873359 -0.416828 -0.111431 0.966491 -0.231254 -0.321938 0.767499 -0.554348 -0.514951 0.424768 -0.744579 -0.571836 0.189464 -0.79819 -0.111757 0.966075 -0.23283 -0.152719 0.968961 -0.194402 -0.154373 0.968219 -0.196776 -0.184756 0.972992 -0.138387 -0.187594 0.972156 -0.140435 -0.197027 0.977595 -0.0740903 -0.200618 0.976781 -0.0751696 -0.317437 0.803093 -0.504257 -0.433905 0.810404 -0.393666 -0.437607 0.805362 -0.399865 -0.524199 0.818949 -0.233534 -0.53096 0.812969 -0.239089 -0.557813 0.82842 -0.050647 -0.566582 0.822243 -0.0538677 -0.459587 0.524757 -0.716526 -0.65115 0.538322 -0.534989 -0.654108 0.526517 -0.543067 -0.784139 0.54687 -0.293358 -0.790855 0.532726 -0.301251 -0.831096 0.555791 -0.0193741 -0.840656 0.540995 -0.0249385 -0.943917 0.202488 0.260807 -0.983672 0.179836 0.00694815 -0.978913 0.203727 0.014994 -0.931237 0.176518 -0.318811 -0.929563 0.199259 -0.310176 -0.838041 0.185669 -0.513044 -0.791351 0.103816 -0.602483 -0.739635 0.192336 -0.644939 -0.568581 0.179167 -0.802879 -0.887337 0.193494 0.41856 -0.92911 0.10841 0.353557 -0.794991 0.550393 0.255062 -0.784613 0.564123 0.257194 -0.537804 0.832142 0.135306 -0.528894 0.837798 0.135519 -0.19089 0.981578 -0.00815387 -0.187283 0.982271 -0.00829168 -0.75938 0.190347 0.622182 -0.752089 0.208508 0.62521 -0.656154 0.559745 0.50611 -0.647253 0.570907 0.505103 -0.445284 0.841459 0.306054 -0.438149 0.845992 0.303847 -0.158436 0.985966 0.0526161 -0.155584 0.986479 0.0515162 0.950733 0.250798 0.182231 0.950669 0.251134 0.182097 0.719066 0.688711 0.09285 0.718235 0.689659 0.0922432 0.30517 0.952087 -0.0200336 0.303084 0.952729 -0.0211379 -0.186078 0.97419 -0.127787 -0.189145 0.973409 -0.129224 0.95122 0.250228 0.180464 0.951146 0.250623 0.180307 0.720491 0.687418 0.0913781 0.719532 0.688514 0.0906794 0.307975 0.951169 -0.0207339 0.30559 0.951909 -0.0219914 -0.182259 0.974942 -0.127552 -0.185777 0.974062 -0.129189 -0.459576 0.246983 -0.853105 -0.459582 0.246932 -0.853117 -0.330478 0.680598 -0.653889 -0.330522 0.680497 -0.653972 -0.120678 0.947893 -0.294848 -0.120621 0.947891 -0.29488 -0.120721 0.947817 -0.295076 -0.0933539 0.965949 -0.241302 -0.205786 0.872535 -0.443096 -0.33052 0.6806 -0.653865 -0.288393 0.76673 -0.573545 -0.468191 0.186127 -0.863802 -0.461318 0.247059 -0.852143 -0.423185 0.423061 -0.801208 -0.371969 0.584291 -0.721279 0.564117 0.247815 -0.787629 0.307653 0.583474 -0.751604 0.0788155 0.750388 -0.656282 0.0863722 0.946863 -0.309824 0.391738 0.185042 -0.901277 0.535745 0.192327 -0.822185 0.556288 0.160291 -0.815383 0.751891 0.222616 -0.620566 0.930301 0.0719956 -0.359662 0.912992 0.254944 -0.318513 0.790162 0.170736 -0.588637 0.944262 0.214182 -0.249992 0.963746 0.266314 -0.0164689 0.972585 0.231971 0.0163527 0.201577 0.519267 -0.830499 0.418824 0.535695 -0.733224 0.424344 0.52967 -0.734426 0.56624 0.575067 -0.590484 0.584236 0.560809 -0.586653 0.680438 0.626346 -0.380388 0.700047 0.612053 -0.367866 0.731521 0.675954 -0.0892412 0.745189 0.662817 -0.0732644 0.211153 0.805141 -0.554222 0.239645 0.806532 -0.540442 0.223364 0.817261 -0.531218 0.28513 0.836512 -0.467919 0.263249 0.845073 -0.465351 0.321416 0.884202 -0.338939 0.307544 0.887734 -0.342556 0.33029 0.932921 -0.143415 0.331554 0.932602 -0.142567 0.264951 0.952703 -0.148856 0.0242855 0.962579 -0.269909 -0.0149995 0.971056 -0.238381 -0.0462244 0.96167 -0.270285 -0.112353 0.962197 -0.248102 -0.105197 0.96686 -0.232626 -0.160476 0.958575 -0.235333 -0.152435 0.974175 -0.166572 -0.171799 0.96937 -0.17552 0.0569387 0.242893 -0.968381 0.0688509 0.946209 -0.316147 0.0684903 0.945854 -0.317285 0.264713 0.245901 -0.932448 0.26886 0.241456 -0.932423 0.189867 0.676944 -0.711124 0.298839 0.583178 -0.75538 0.164976 0.761381 -0.626962 -0.101279 0.244534 -0.964337 0.000452918 0.17807 -0.984018 -0.000373159 0.671785 -0.740746 -0.000283267 0.671655 -0.740864 -0.000871704 0.944747 -0.327799 -0.00083704 0.944722 -0.327873 -0.311923 0.237386 -0.919974 -0.315022 0.244542 -0.917039 -0.226104 0.671308 -0.705849 -0.227178 0.674663 -0.702296 -0.0831491 0.945286 -0.315469 -0.0833046 0.945812 -0.313846 -0.967338 0.204775 -0.149414 0.294307 0.954696 -0.0440406 0.27195 0.96109 -0.048469 -0.496596 0.855824 -0.144769 -0.418998 0.89769 -0.136357 -0.110588 0.988608 -0.1021 -0.178489 0.977462 -0.11274 0.0225478 0.99612 -0.0850714 -0.968024 0.201568 -0.149333 -0.883178 0.441309 -0.15888 -0.799252 0.579054 -0.160913 -0.773702 0.613178 -0.159368 -0.592376 0.791521 -0.150285 -0.965447 0.208091 -0.156878 -0.966306 0.204138 -0.156783 -0.792625 0.587455 -0.163226 -0.798861 0.578812 -0.163703 -0.482031 0.864705 -0.141182 -0.496833 0.85597 -0.143079 -0.0876491 0.991653 -0.0945617 -0.111105 0.988925 -0.0984021 0.321957 0.946232 -0.0314526 0.29335 0.955281 -0.0372135 -0.175917 0.884797 -0.431494 0.0239765 0.878711 -0.476751 0.0437646 0.965942 -0.255031 0.0382867 0.968853 -0.244658 0.0542541 0.786026 -0.615808 0.0413458 0.802528 -0.595179 -0.00691415 0.608905 -0.793213 0.0377462 0.52506 -0.850228 0.0166568 0.467851 -0.883651 -0.00943083 0.179447 -0.983723 0.0619134 0.0868172 -0.994299 -0.0287716 0.318606 -0.947451 0.106982 0.959311 -0.261298 0.10695 0.970816 -0.214657 -0.0188849 0.807907 -0.589007 -0.0188428 0.817277 -0.575937 -0.141526 0.539698 -0.829877 -0.14086 0.526888 -0.838181 -0.243488 0.198196 -0.949438 -0.597609 0.115856 -0.793373 -0.421532 0.204877 -0.883366 -0.23776 0.153711 -0.959084 0.204865 0.958633 -0.19762 -0.527128 0.609777 -0.591869 0.277076 0.956715 -0.0890247 0.23207 0.960981 -0.150531 0.201411 0.975511 -0.0883829 0.0326947 0.986158 -0.162552 -0.163274 0.961832 -0.219592 -0.270018 0.938902 -0.213432 -0.17005 0.890237 -0.422565 -0.517632 0.632361 -0.576347 -0.396286 0.875896 -0.275252 -0.564356 0.767426 -0.304236 -0.670716 0.684277 -0.28619 -0.737955 0.587346 -0.332335 -0.84695 0.419059 -0.327208 0.1716 0.953796 -0.246632 0.190763 0.96441 -0.183092 -0.0917001 0.836787 -0.539795 -0.0860077 0.847058 -0.524495 -0.337541 0.580315 -0.741148 -0.343022 0.557952 -0.755663 -0.550411 0.17079 -0.817238 -0.753876 0.257372 -0.604508 -0.758245 0.19176 -0.623132 -0.914822 0.276367 -0.294488 -0.928253 0.182191 -0.324273 -0.975944 0.217914 0.00692323 -0.0980303 0.730079 0.676295 -0.1833 0.474018 0.861225 0.00960422 0.990123 0.139874 0.0448103 0.852781 0.520342 -0.215989 -0.0890651 0.972325 -0.260699 0.170794 0.950192 -0.019384 0.156492 0.987489 -0.334467 0.150973 0.930236 -0.530256 0.190261 0.826213 -0.566973 0.13934 0.811866 -0.760227 0.206615 0.615927 -0.792316 0.160434 0.588639 -0.883558 0.202108 0.422466 -0.940586 0.13723 0.310591 -0.943114 0.19475 0.269459 -0.975963 0.217826 0.00687152 -0.197123 0.454322 0.868754 -0.409689 0.497782 0.76444 -0.434454 0.472739 0.76666 -0.605194 0.532786 0.591506 -0.628285 0.51272 0.585129 -0.747988 0.570002 0.340017 -0.759549 0.558874 0.332784 -0.80857 0.58833 0.00908959 -0.805934 0.591891 0.0116427 -0.104505 0.723087 0.682805 -0.239806 0.750427 0.615916 -0.245172 0.746826 0.618176 -0.368442 0.789784 0.490399 -0.369418 0.789308 0.490432 -0.466957 0.835447 0.289791 -0.463466 0.837037 0.290807 -0.506636 0.862107 0.00961461 -0.499121 0.866416 0.014201 -0.0507665 0.202123 0.978043 0.0143269 0.4626 0.886452 -0.0435104 0.573147 0.818296 0.0314348 0.72197 0.691209 -0.0520651 0.910385 0.410474 -0.000843132 0.908874 0.41707 0.000314889 0.909614 0.415455 -0.0395282 0.917517 0.395726 -0.022418 0.922973 0.384211 -0.0798677 0.942517 0.324473 -0.0522587 0.946687 0.317889 -0.111899 0.974302 0.195487 -0.0867535 0.976312 0.198214 -0.116425 0.993165 0.00826356 -0.103288 0.994549 0.0143083 0.0295708 0.994075 0.104598 0.0970872 0.988943 0.112096 0.104959 0.989581 0.0985569 0.166929 0.977478 0.129117 0.203857 0.974224 0.0965905 0.221666 0.968318 0.115003 0.274856 0.956859 0.0942037 0.263388 0.962084 0.0708663 0.308321 0.948647 0.0707619 0.297945 0.954568 0.00526361 0.315195 0.948948 0.0122795 0.207808 0.0866393 -0.974325 0.13768 0.319636 -0.937484 0.195916 0.239646 -0.950888 0.178409 0.465256 -0.86701 0.156176 0.60691 -0.779275 0.112626 0.669576 -0.734155 0.117317 0.783797 -0.609836 0.0855978 0.877427 -0.472012 0.0249327 0.943408 -0.330696 0.0351491 0.968917 -0.244876 0.127187 0.947105 -0.294646 0.125074 0.947822 -0.29324 0.350384 0.673704 -0.650656 0.344611 0.678727 -0.648517 0.485062 0.237311 -0.841664 0.477469 0.24815 -0.842879 0.114999 0.202295 0.972549 0.240572 0.108565 0.964541 0.394766 0.570718 0.720028 0.393712 0.565554 0.724665 0.267239 0.847942 0.457797 0.26729 0.845852 0.461617 0.0948052 0.988517 0.117673 0.0950182 0.988292 0.119373 0.0376928 0.989684 0.138223 0.0378256 0.989745 0.137747 0.105856 0.850328 0.515497 0.106331 0.850964 0.514348 0.156121 0.571478 0.80563 0.157081 0.573041 0.804331 0.180487 0.203345 0.962328 0.455196 0.196458 0.868448 0.458364 0.20485 0.864835 0.159776 0.951278 -0.263709 0.160965 0.950734 -0.264945 0.379037 0.771595 -0.510855 0.444436 0.685057 -0.577211 0.497083 0.588893 -0.637271 0.613388 0.248906 -0.749534 0.62686 0.187977 -0.756116 0.565277 0.426689 -0.705973 0.61306 0.248642 -0.74989 0.613001 0.24888 -0.749859 0.441431 0.684251 -0.580465 0.441022 0.684836 -0.580086 0.160371 0.950221 -0.267136 0.15947 0.950635 -0.266201 0.596925 0.201624 0.776549 0.596954 0.20118 0.776642 0.512695 0.572008 0.640274 0.513086 0.570912 0.640938 0.344971 0.849245 0.399723 0.34602 0.848067 0.401314 0.121055 0.98818 0.0940531 0.122831 0.987714 0.0966066 0.597278 0.201987 0.776183 0.597302 0.201604 0.776264 0.51341 0.572933 0.638872 0.513759 0.571953 0.639469 0.345618 0.8502 0.397126 0.346544 0.849163 0.398534 0.121322 0.988484 0.0904476 0.122873 0.988085 0.0926799 0.130651 0.987915 0.0833883 0.369798 0.848491 0.378567 0.547994 0.570469 0.611775 0.979631 0.190947 0.0621471 0.937993 0.204927 0.279595 0.93837 0.185708 0.291504 0.789804 0.206642 0.577502 0.786924 0.190527 0.586898 0.640922 0.203498 0.74014 0.636294 0.199556 0.745189 0.130836 0.987984 0.0822727 0.163146 0.985237 0.0518741 0.161514 0.985638 0.0493114 0.192485 0.981246 -0.0102883 0.189724 0.981758 -0.0124513 0.198994 0.976906 -0.077825 0.195681 0.977485 -0.0789415 0.182968 0.97272 -0.142612 0.179848 0.973309 -0.142565 0.370702 0.849397 0.375639 0.460119 0.839591 0.288754 0.456964 0.843562 0.282111 0.544001 0.831227 0.114565 0.537924 0.835998 0.10838 0.563951 0.822356 -0.0754351 0.555914 0.82744 -0.0793909 0.520055 0.814015 -0.258694 0.511919 0.818855 -0.259644 0.14721 0.969148 -0.197691 0.209903 0.952471 -0.220771 0.410522 0.80467 -0.428928 0.453466 0.772645 -0.444285 0.59412 0.590169 -0.546555 0.550389 0.572843 0.60739 0.678963 0.558477 0.476564 0.677156 0.568343 0.467383 0.805399 0.550217 0.22044 0.79982 0.562027 0.210743 0.838224 0.541914 -0.0609052 0.829435 0.554383 -0.0685306 0.776177 0.534496 -0.33446 0.7662 0.546302 -0.338366 0.616044 0.5258 -0.586536 0.671965 0.429196 -0.603535 0.994484 0.0525442 -0.0907829 0.978573 0.202277 -0.0384567 0.930497 0.183151 -0.317225 0.927165 0.111615 -0.357642 0.862456 0.192966 -0.467903 0.746119 0.177264 -0.641782 0.738217 0.193147 -0.646321 0.24971 0.407663 -0.878326 0.208113 0.14969 -0.966582 0.250049 0.387053 -0.887505 0.177167 0.675247 -0.715999 0.177017 0.679749 -0.711762 0.0534938 0.866615 -0.496101 -0.0182246 0.981478 -0.190707 -0.0139047 0.947513 -0.319414 0.967035 0.241595 -0.0804678 0.981413 0.187388 -0.0413953 0.798395 0.585181 -0.141877 0.822035 0.556839 -0.119119 0.508147 0.84168 -0.182651 0.523796 0.833827 -0.174273 0.135074 0.971143 -0.196559 0.129477 0.971535 -0.198384 -0.265319 0.947053 -0.18082 -0.296274 0.936639 -0.186893 0.843658 0.216158 -0.491444 0.89089 0.136411 -0.433251 0.678048 0.52151 -0.517955 0.722029 0.481281 -0.497034 0.426886 0.764221 -0.483461 0.44327 0.756123 -0.481446 0.118807 0.912927 -0.390448 0.092465 0.917112 -0.387758 -0.207639 0.945956 -0.249105 -0.276582 0.933096 -0.229858 -0.189388 0.956063 -0.223775 -0.13744 0.954935 -0.263078 0.0652099 0.882572 -0.465633 0.0856854 0.87488 -0.476699 0.311104 0.697057 -0.646007 0.298243 0.706047 -0.6423 0.516991 0.426946 -0.741915 0.477496 0.467807 -0.743743 0.343827 -0.0461128 -0.9379 0.385646 0.128331 -0.913678 0.628008 0.191239 -0.754343 0.654378 -0.125003 -0.745764 0.716863 0.13909 -0.6832 0.966267 0.21292 0.144888 0.965213 0.218109 0.144199 0.794006 0.601266 0.0896325 0.786421 0.61149 0.0873006 0.475995 0.879265 0.0179427 0.458235 0.888724 0.0137749 0.0705969 0.995875 -0.0570043 0.0429945 0.997123 -0.0624293 -0.347744 0.929693 -0.121428 -0.380368 0.916095 -0.126847 0.964132 0.208662 0.164039 0.963036 0.214277 0.163242 0.80025 0.590626 0.103734 0.792015 0.602103 0.100922 0.4952 0.868415 0.0251476 0.475625 0.87942 0.020038 0.102781 0.993021 -0.0578405 0.071935 0.995316 -0.064584 -0.307768 0.94246 -0.13057 -0.344923 0.928517 -0.137423 -0.0651471 0.246167 -0.967036 0.073991 0.247137 -0.966151 0.0195238 0.948773 -0.315356 0.0194021 0.948797 -0.31529 0.0537662 0.680911 -0.73039 0.0532936 0.681108 -0.730241 0.0701881 0.388601 -0.918729 0.25347 0.149381 -0.95574 -0.222409 0.245671 -0.943493 -0.138178 0.175908 -0.974661 -0.0968234 0.675397 -0.73107 -0.0975261 0.67668 -0.72979 -0.0352488 0.947749 -0.317065 -0.0354225 0.947933 -0.316495 -0.437443 0.239132 -0.866868 -0.440725 0.248125 -0.862668 -0.317587 0.676339 -0.664608 -0.318258 0.680476 -0.660048 -0.115946 0.949023 -0.293106 -0.115857 0.949615 -0.29122 0.71997 0.20778 0.662171 -0.109569 0.989052 0.0988489 -0.106165 0.979401 0.171765 -0.208803 0.893975 0.396496 -0.210134 0.716227 0.66548 -0.258713 0.792782 0.551874 -0.267235 0.452077 0.851006 -0.352083 0.306019 0.884528 -0.273948 0.526048 0.805125 -0.298009 0.110047 0.948198 -0.309471 0.139246 0.940658 -0.0918422 0.171493 0.980895 0.0791924 0.143862 0.986424 0.0275502 0.0357109 0.998982 -0.0878815 0.433763 0.896731 -0.0850843 0.475507 0.875588 -0.149758 0.706 0.692197 -0.147469 0.723662 0.674215 -0.194317 0.894835 0.401885 -0.193865 0.89623 0.398983 -0.215322 0.974558 0.0622371 -0.219171 0.972331 0.0808431 0.310092 0.118595 0.94328 0.300984 0.208727 0.930506 0.166037 0.457254 0.8737 0.156533 0.506903 0.847672 -0.00336928 0.734279 0.678839 -0.00744339 0.74833 0.663285 -0.174053 0.907157 0.383109 -0.17158 0.901528 0.397251 -0.319563 0.947099 0.0297223 -0.315617 0.945291 0.0825355 0.580002 0.148173 0.801026 0.574448 0.226434 0.786598 0.399915 0.507986 0.762901 0.388773 0.548871 0.739997 0.15229 0.786369 0.598692 0.147118 0.795825 0.587383 -0.123673 0.935055 0.332231 -0.117369 0.929928 0.34851 -0.380395 0.924795 0.00731508 -0.366374 0.928651 0.0581093 0.82141 0.197501 0.535051 0.812013 0.155841 0.562449 0.600389 0.566876 0.564078 0.592258 0.591894 0.54671 0.305418 0.846264 0.436529 0.301573 0.85095 0.430044 -0.0492317 0.972593 0.227241 -0.0417 0.969945 0.239725 -0.398408 0.916826 -0.0264662 -0.380651 0.924688 0.00760169 0.927633 0.225041 0.298082 0.927212 0.233114 0.293147 0.747003 0.612516 0.25848 0.745865 0.614789 0.256358 0.428199 0.887371 0.170933 0.429728 0.886269 0.172805 0.0255346 0.998414 0.0501716 0.0317063 0.997903 0.0564356 -0.387053 0.918433 -0.0816698 -0.376841 0.923509 -0.0715651 -0.575317 0.250017 -0.778782 -0.575399 0.249488 -0.778891 -0.414543 0.687437 -0.596309 -0.415211 0.68624 -0.597222 -0.149945 0.952664 -0.264477 -0.151469 0.951824 -0.266624 -0.575714 0.250663 -0.778281 -0.575809 0.250042 -0.77841 -0.415138 0.688858 -0.594251 -0.415893 0.687506 -0.595289 -0.150072 0.953702 -0.260636 -0.1518 0.952758 -0.263076 -0.0885534 0.987054 0.133726 -0.442741 0.107843 0.890141 -0.336687 0.201137 0.919884 -0.426638 0.304657 0.851566 -0.375582 0.56857 0.731892 -0.293185 0.526527 0.798005 -0.363388 0.837924 0.407226 -0.197915 0.792027 0.577515 -0.175537 0.974492 0.13983 -0.123971 0.985858 0.11276 -0.125461 0.985561 0.11371 -0.351187 0.841281 0.41099 -0.354456 0.83907 0.412702 -0.520215 0.564268 0.641076 -0.524378 0.559058 0.642247 -0.606337 0.201879 0.769156 -0.610217 0.193529 0.768233 -0.160896 0.954144 -0.252431 -0.199096 0.970898 -0.133111 -0.610218 0.248802 -0.752151 -0.614565 0.252233 -0.747454 -0.497828 0.590966 -0.634765 -0.529652 0.686873 -0.497669 -0.381481 0.774714 -0.504273 -0.276028 0.880274 -0.385908 -0.729896 0.199344 0.653845 -0.729832 0.199775 0.653785 -0.624789 0.566229 0.537609 -0.624182 0.567415 0.537064 -0.420225 0.843004 0.335791 -0.41869 0.844302 0.334443 -0.148757 0.985592 0.0805025 -0.146251 0.986139 0.0783588 -0.729392 0.198857 0.654556 -0.729313 0.199378 0.654485 -0.623774 0.56507 0.540001 -0.62313 0.566325 0.53943 -0.419349 0.841791 0.339904 -0.41775 0.843147 0.338507 -0.148511 0.985167 0.085968 -0.145849 0.98576 0.0836934 -0.336669 0.882316 -0.328897 -0.333661 0.769096 -0.545125 -0.588118 0.594539 -0.548308 -0.835586 0.252624 -0.487829 -0.659742 0.74071 -0.126845 -0.567447 0.774207 -0.28037 -0.31975 0.942454 -0.0976734 -0.126379 0.947672 -0.293166 -0.243161 0.965806 -0.0899467 -0.849157 0.510297 -0.136124 -0.849023 0.510506 -0.136172 -0.830589 0.516612 -0.207927 -0.849141 0.51032 -0.136136 -0.849141 0.510314 -0.136159 -0.584223 0.808523 -0.0705239 -0.600567 0.790241 -0.121811 -0.183588 0.981032 0.0622253 -0.278254 0.95616 -0.0912855 -0.0899555 0.982217 0.164795 -0.368272 0.783557 -0.500413 -0.574305 0.76871 -0.28153 -0.678866 0.60031 -0.42281 -0.809562 0.550259 -0.204509 -0.883714 0.381852 -0.270626 -0.919067 0.370076 -0.1355 -0.920437 0.366354 -0.136306 -0.921208 0.386923 -0.0408312 -0.796764 0.603907 -0.0215299 -0.770928 0.633679 0.0641858 -0.539868 0.823366 0.174963 -0.56355 0.81545 0.132105 -0.425898 0.842739 0.329245 -0.45732 0.509311 -0.729013 -0.742647 0.502922 -0.442205 -0.758286 0.387782 -0.524049 -0.902397 0.329179 -0.278068 -0.917866 0.237973 -0.317633 -0.966395 0.220917 -0.131441 -0.967884 0.213375 -0.132938 -0.966682 0.2516 0.0471538 -0.933457 0.355797 0.0454527 -0.875544 0.419518 0.23964 -0.789989 0.541142 0.288242 -0.763633 0.548872 0.340008 -0.690217 0.566117 0.450678 -0.680922 0.180458 -0.709774 -0.808284 0.174683 -0.562284 -0.802086 0.147823 -0.578624 -0.934288 0.091617 -0.344546 -0.934005 0.0882491 -0.346189 -0.990013 0.0669611 -0.124056 -0.990448 0.0555367 -0.126209 -0.986561 0.108798 0.121904 -0.988415 0.0869012 0.124431 -0.910905 0.1658 0.377838 -0.905544 0.18302 0.382744 -0.85048 0.193441 0.489146 -0.832663 0.198145 0.517119 -0.782948 0.195529 0.59056 -0.778256 0.202166 0.594514 -0.670588 0.562941 0.483125 -0.665906 0.567043 0.4848 -0.451102 0.841255 0.297989 -0.447682 0.842945 0.298368 -0.158999 0.985181 0.0643322 -0.157574 0.985411 0.0643149 -0.975198 0.221264 -0.00565701 0.266164 0.597661 0.756279 0.0593267 0.997419 0.0404527 0.279942 0.240403 0.929429 0.232552 0.772651 0.590703 0.119087 0.96593 0.229777 0.194217 0.883541 0.426186 0.3246 0.144582 0.934736 0.0623829 0.166431 0.984078 0.0373108 0.123343 0.991663 -0.151375 0.164577 0.97468 -0.324582 0.0521482 0.944419 -0.330384 0.123992 0.935667 -0.564438 0.211412 0.797944 -0.592335 -0.000247969 0.805692 -0.657366 0.153577 0.737756 -0.764964 0.214459 0.607319 -0.815179 0.15498 0.558091 -0.881081 0.200941 0.428158 -0.942494 0.16674 0.289659 -0.941651 0.190505 0.27749 -0.972307 0.23368 0.00355419 0.321559 0.439824 0.838543 0.100504 0.458563 0.88296 0.0806683 0.424048 0.90204 -0.143128 0.471516 0.870165 -0.185216 0.426076 0.885525 -0.379196 0.499081 0.779185 -0.433008 0.45613 0.777463 -0.580405 0.538691 0.61069 -0.624264 0.507845 0.593623 -0.725445 0.584232 0.363872 -0.75021 0.56406 0.344994 -0.789149 0.613523 0.0288789 -0.793183 0.608503 0.0241767 0.274018 0.695357 0.664374 0.130058 0.708122 0.694009 0.115379 0.684449 0.719873 -0.0218994 0.713582 0.700229 -0.0473241 0.692244 0.72011 -0.175008 0.740122 0.649301 -0.202185 0.725927 0.657382 -0.312647 0.787743 0.530767 -0.332962 0.780224 0.529515 -0.418225 0.844309 0.335007 -0.429137 0.840493 0.330777 -0.464756 0.884079 0.0490623 -0.465108 0.883907 0.0488049 0.193288 0.884325 0.424981 0.147698 0.888533 0.43439 0.137632 0.876122 0.462026 0.104176 0.883227 0.457228 0.0956943 0.878928 0.467256 0.0532914 0.894633 0.443613 0.0574163 0.895536 0.44127 0.00214246 0.925984 0.377557 0.0141152 0.926685 0.375574 -0.0399739 0.966809 0.252354 -0.0279636 0.96668 0.254456 -0.0531427 0.996746 0.0606028 -0.0468042 0.996851 0.0640165 0.108794 0.984268 0.13921 0.151235 0.97985 0.130465 0.144899 0.977149 0.155515 0.220927 0.960982 0.166446 0.226652 0.961187 0.157317 0.277606 0.942582 0.18567 0.309031 0.93752 0.159862 0.319264 0.932 0.1716 0.360525 0.919421 0.157122 0.347985 0.928615 0.128765 0.381892 0.915023 0.12997 0.372855 0.925855 0.0614186 0.385606 0.920206 0.0672998 -0.962527 0.214131 -0.166401 -0.963211 0.211032 -0.166406 -0.781249 0.602749 -0.162307 -0.786545 0.595643 -0.162961 -0.456299 0.880522 -0.128345 -0.468979 0.873537 -0.130356 -0.0474395 0.996366 -0.0707463 -0.0673842 0.994946 -0.0744465 0.370123 0.928983 -8.91782e-05 0.34628 0.938116 -0.00526641 -0.961518 0.217318 -0.168095 -0.962249 0.21403 -0.16813 -0.776037 0.610688 -0.157564 -0.781882 0.602976 -0.158368 -0.443696 0.888481 -0.117198 -0.457718 0.881028 -0.119512 -0.027416 0.998131 -0.0546243 -0.0493764 0.997052 -0.0587232 0.394047 0.918908 0.0183327 0.368043 0.929721 0.012803 0.0476619 0.9978 0.0460906 0.120057 0.965921 0.229311 0.108856 0.984147 0.140015 0.268577 0.88103 0.389426 0.30691 0.772647 0.555719 0.308568 0.837615 0.450763 0.457796 0.560617 0.690022 0.423004 0.596563 0.682041 0.562426 0.198371 0.802699 0.533451 0.238119 0.811621 -0.696711 0.196911 -0.689797 0.0867462 0.976141 -0.199057 0.0791465 0.955415 -0.284461 0.298796 0.501638 -0.811838 0.229563 0.708634 -0.667187 0.213377 0.682449 -0.699095 0.197355 0.86556 -0.460279 0.333388 0.39218 -0.857349 0.308058 0.429896 -0.848699 0.326972 0.180504 -0.927635 0.344906 0.141902 -0.927849 0.331089 0.0301909 -0.943116 0.0885861 0.11318 -0.989618 0.0822403 0.158397 -0.983945 0.125841 0.409952 -0.903384 0.120504 0.440296 -0.889729 0.151573 0.669445 -0.727234 0.147597 0.68517 -0.713273 0.162653 0.863837 -0.476792 0.1607 0.868266 -0.46935 0.157559 0.971362 -0.177853 0.158527 0.970552 -0.18138 -0.244151 0.102484 -0.964307 -0.236537 0.187897 -0.953281 -0.130103 0.417683 -0.89923 -0.12264 0.466882 -0.875774 0.000739093 0.686955 -0.726699 0.00420721 0.703184 -0.710996 0.132749 0.875666 -0.464313 0.131419 0.871001 -0.473377 0.248684 0.957796 -0.144167 0.245744 0.951037 -0.187454 -0.541091 0.120831 -0.832238 -0.527778 0.21251 -0.822369 -0.376131 0.457501 -0.805741 -0.360009 0.507351 -0.782936 -0.155851 0.731639 -0.663638 -0.148489 0.74491 -0.65043 0.0894215 0.901673 -0.423071 0.082546 0.894915 -0.438535 0.322619 0.93911 -0.118274 0.304893 0.936554 -0.172934 -0.808814 0.175673 -0.561212 -0.79798 0.123587 -0.589877 -0.58427 0.514405 -0.627707 -0.568696 0.554369 -0.607668 -0.306676 0.79223 -0.527563 -0.29803 0.802828 -0.516377 0.0252808 0.940647 -0.338444 0.0179249 0.93698 -0.348922 0.355978 0.930117 -0.090342 0.333442 0.933843 -0.129438 -0.919116 0.195127 -0.342273 -0.914707 0.237072 -0.327274 -0.742904 0.571825 -0.348009 -0.731098 0.595049 -0.333785 -0.436905 0.850307 -0.293414 -0.427886 0.85775 -0.284919 -0.0494429 0.981234 -0.186374 -0.0506665 0.980966 -0.187456 0.352238 0.934841 -0.0447288 0.339129 0.939001 -0.0571702 0.194988 0.961907 0.191609 0.338203 0.867687 0.364332 0.368559 0.84111 0.395852 0.506889 0.639784 0.577703 0.547258 0.564395 0.618035 0.629379 0.24157 0.738598 0.63782 0.198586 0.744144 0.129189 0.985129 0.113272 0.0748472 0.996565 0.0354512 0.129279 0.984754 0.116391 0.127819 0.985174 0.114433 0.365605 0.840288 0.400313 0.364738 0.841241 0.399098 0.544407 0.563604 0.621266 0.544074 0.564502 0.620743 0.637542 0.198291 0.74446 0.637521 0.198596 0.744397 0.129048 0.984377 0.119786 0.127585 0.984804 0.117827 0.365011 0.839375 0.402761 0.364145 0.840331 0.401551 0.543742 0.562774 0.6226 0.543422 0.563633 0.622102 0.63722 0.197922 0.744834 0.637194 0.198302 0.744756 0.128821 0.983991 0.123155 0.127367 0.984421 0.12121 0.364429 0.838456 0.405195 0.363563 0.839414 0.403988 0.543088 0.561935 0.623927 0.542765 0.5628 0.623428 0.636902 0.197573 0.745198 0.636877 0.197931 0.745125 0.403274 0.394361 -0.825742 0.24864 0.23836 -0.938809 0.375148 0.182366 -0.908849 0.446637 0.0333898 -0.894092 0.112661 0.953511 -0.279507 0.0834568 0.955631 -0.282497 0.334308 0.688855 -0.643209 0.230916 0.708727 -0.666622 0.375181 0.504375 -0.777718 0.157877 0.95354 -0.256587 0.156156 0.954048 -0.255749 0.431299 0.683097 -0.589373 0.42625 0.687253 -0.588213 0.592396 0.242502 -0.768283 0.586151 0.251668 -0.770123 0.0824219 0.99122 0.103393 0.0191077 0.996413 0.0824362 0.185657 0.962151 0.199493 0.332707 0.855906 0.395892 0.307632 0.868031 0.389724 0.555702 0.577944 0.597642 0.476388 0.640233 0.602624 0.65847 0.20421 0.724373 0.62928 0.241573 0.738681 0.70907 0.253063 -0.658163 0.708899 0.253743 -0.658085 0.515081 0.694306 -0.502623 0.513918 0.695787 -0.501766 0.188987 0.95744 -0.218159 0.186386 0.958425 -0.216059 0.708462 0.25239 -0.659075 0.708302 0.253021 -0.659005 0.514092 0.692758 -0.505762 0.512968 0.694188 -0.504943 0.188514 0.956333 -0.223359 0.186054 0.957275 -0.221378 0.818721 0.243392 -0.520054 0.511675 0.76439 -0.392297 0.650344 0.588889 -0.479857 0.185002 0.964702 -0.187414 0.347522 0.88757 -0.302404 0.404095 0.840255 -0.361495 0.016792 0.995513 -0.0931238 0.810753 0.189064 -0.554016 0.889149 0.204121 -0.409571 0.943018 0.125226 -0.308279 0.945216 0.201021 -0.25721 0.974728 0.223309 0.00620387 0.977842 0.208769 0.0155328 0.9128 0.220715 0.343629 0.912912 0.21384 0.347656 0.744955 0.208346 0.633746 0.744132 0.202902 0.636474 0.659933 0.554767 -0.506677 0.762673 0.573049 -0.299908 0.758064 0.578039 -0.302011 0.797129 0.603443 -0.0210268 0.800148 0.599529 -0.01813 0.742897 0.610478 0.274629 0.748423 0.599078 0.284548 0.609224 0.59531 0.523882 0.612879 0.574873 0.542125 0.409334 0.834817 -0.36814 0.478028 0.847094 -0.232209 0.448887 0.861674 -0.236684 0.475384 0.878617 -0.0452024 0.470638 0.881026 -0.0478797 0.431585 0.889046 0.152748 0.446054 0.878894 0.169059 0.360775 0.877525 0.315898 0.377854 0.854625 0.356151 0.0937207 0.981882 -0.164695 0.113044 0.98547 -0.126766 0.0545647 0.990375 -0.127204 0.0636803 0.996054 -0.0618205 0.0472959 0.996528 -0.0685149 0.03396 0.999423 -0.000517059 0.0574436 0.998118 0.0214805 0.0431887 0.998016 0.0458142 0.0759168 0.991148 0.108911 0.0330589 0.996745 -0.0735227 0.241692 0.963249 -0.117201 0.301924 0.949724 -0.082856 0.825069 0.54523 -0.148275 0.505443 0.764399 -0.400278 0.390746 0.83951 -0.377546 0.328245 0.886655 -0.325727 0.483653 0.693586 -0.53387 0.759352 0.255579 -0.598384 0.724985 0.24 -0.645598 0.976533 0.209951 -0.0479903 -0.0730351 0.440843 -0.894608 -0.148624 0.838235 -0.524665 0.0320046 0.652083 -0.757471 0.272994 0.88695 -0.372551 -0.00978969 0.996996 -0.0768369 -0.196664 0.152361 -0.968561 -0.0512472 0.150939 -0.987214 -0.0380399 0.124567 -0.991482 0.142379 0.157661 -0.977175 0.276234 0.0617169 -0.959107 0.28821 0.123829 -0.949527 0.476022 0.193371 -0.857911 0.558237 0.106846 -0.822773 0.720099 0.208673 -0.66175 0.788842 0.137867 -0.598934 0.854193 0.193597 -0.482571 0.92705 0.161574 -0.338336 0.926485 0.175228 -0.333048 0.966779 0.243201 -0.0786892 -0.0610786 0.416399 -0.907128 0.120165 0.449055 -0.885387 0.154023 0.412151 -0.898002 0.32342 0.474578 -0.818643 0.385298 0.423976 -0.819628 0.527996 0.51521 -0.675114 0.5872 0.476885 -0.654046 0.68644 0.568239 -0.453767 0.726981 0.540393 -0.423644 0.775363 0.617429 -0.132641 0.792091 0.5999 -0.112745 0.317772 0.204124 -0.925934 -0.385938 0.431795 -0.815233 0.333441 0.613478 -0.715864 -0.0886421 0.691636 -0.716786 -0.0781585 0.671615 -0.736766 0.0145443 0.688272 -0.725307 0.0343589 0.670651 -0.740977 0.132854 0.706725 -0.694902 0.163252 0.689306 -0.705838 0.263774 0.753505 -0.602208 0.29367 0.742864 -0.60159 0.376239 0.818903 -0.433408 0.400061 0.812039 -0.424903 0.444546 0.880771 -0.163162 0.45744 0.875806 -0.153986 -0.258219 0.864665 -0.430903 -0.0963536 0.877613 -0.469587 -0.0874133 0.864273 -0.49537 -0.0943359 0.863043 -0.496243 -0.088163 0.8594 -0.503646 -0.0755573 0.864006 -0.49778 -0.0803604 0.865392 -0.49461 -0.0387425 0.891491 -0.451379 -0.0476477 0.89209 -0.449339 0.00325357 0.938422 -0.345477 -0.00144558 0.938218 -0.346042 0.0300723 0.985839 -0.164976 0.031329 0.985901 -0.16437 -0.156958 0.973839 -0.16432 -0.0952843 0.979505 -0.177454 -0.0877967 0.97445 -0.206734 -0.195268 0.955674 -0.220356 -0.20042 0.956491 -0.212029 -0.277985 0.928033 -0.247952 -0.312717 0.925284 -0.214609 -0.338758 0.909355 -0.241489 -0.382367 0.897002 -0.221774 -0.373213 0.905212 -0.203233 -0.405676 0.891546 -0.201429 -0.394427 0.908556 -0.137672 -0.406552 0.902519 -0.142036 -0.0110912 0.997003 -0.0765594 -0.0470343 0.944927 -0.323884 -0.0717642 0.95713 -0.280628 -0.145971 0.838307 -0.525293 -0.176138 0.664946 -0.725825 -0.2116 0.693069 -0.689116 -0.259444 0.250736 -0.932641 -0.272163 0.240962 -0.931593 -0.488055 0.246604 -0.837251 -0.489971 0.251877 -0.834558 -0.356766 0.688611 -0.631294 -0.357054 0.690964 -0.628555 -0.130749 0.957066 -0.258708 -0.130665 0.957318 -0.257817 0.972713 0.222475 0.0658313 0.972547 0.223215 0.0657777 0.780196 0.624105 0.042289 0.77966 0.624779 0.0422066 0.432442 0.901602 0.0103338 0.431568 0.902022 0.0102293 -0.00134699 0.999719 -0.0236747 -0.00242315 0.999714 -0.0237874 -0.434827 0.898955 -0.0529673 -0.4359 0.898429 -0.0530712 0.970854 0.219946 0.0952179 0.970102 0.223365 0.0949208 0.783433 0.618692 0.0587641 0.778815 0.624579 0.057865 0.442831 0.89654 0.0108282 0.432536 0.901569 0.0092704 0.0156611 0.999108 -0.0392051 0.000193886 0.999151 -0.0411964 -0.414521 0.906379 -0.0815428 -0.432112 0.897947 -0.0834951 -0.419559 0.765823 -0.487325 -0.513498 0.590196 -0.622887 -0.626361 0.241146 -0.741296 -0.160739 0.966094 -0.202054 -0.282381 0.890612 -0.356469 -0.337652 0.842174 -0.420398 -0.0303314 0.997605 -0.0621683 -0.622011 0.255467 -0.740162 -0.621674 0.255459 -0.740447 -0.621731 0.25501 -0.740554 -0.621293 0.254999 -0.740925 -0.621354 0.254524 -0.741037 -0.620916 0.254511 -0.741409 -0.620974 0.254065 -0.741514 -0.456332 0.69976 -0.549634 -0.452021 0.699668 -0.553301 -0.452602 0.698644 -0.554119 -0.451412 0.698613 -0.555128 -0.451984 0.697605 -0.55593 -0.450787 0.697569 -0.556946 -0.451368 0.696547 -0.557755 -0.170224 0.961284 -0.216698 -0.164353 0.961168 -0.221685 -0.165682 0.96052 -0.223499 -0.16407 0.960477 -0.224866 -0.165414 0.959815 -0.226699 -0.163789 0.959768 -0.228077 -0.165131 0.959102 -0.229904 -0.0512792 0.168242 0.984411 -0.342194 0.886111 0.312588 -0.327288 0.890455 0.316186 -0.136517 0.985341 0.102309 -0.11818 0.987429 0.104966 -0.700052 0.154257 0.697232 -0.696902 0.156474 0.699889 -0.638338 0.449474 0.624899 -0.631297 0.453613 0.629046 -0.515018 0.701558 0.492516 -0.621826 0.644805 0.444476 -0.466272 0.759798 0.453097 -0.562256 0.128582 0.816905 -0.553965 0.15721 0.817562 -0.534071 0.418847 0.734394 -0.519354 0.449902 0.726539 -0.456341 0.672564 0.582589 -0.43422 0.701856 0.564669 -0.335301 0.864548 0.374339 -0.305658 0.886888 0.346413 -0.182327 0.974671 0.129513 -0.145994 0.984865 0.0934118 -0.2742 0.103842 0.95605 -0.268577 0.171063 0.947947 -0.311815 0.399469 0.862088 -0.302413 0.45242 0.838965 -0.319626 0.658503 0.681332 -0.307701 0.694549 0.650324 -0.295846 0.85297 0.43002 -0.28304 0.872519 0.398245 -0.242348 0.960874 0.134122 -0.230542 0.967103 0.107524 0.145779 0.120575 0.981942 0.136191 0.0222935 0.990432 -0.0441257 0.398727 0.916008 -0.0553853 0.470842 0.880478 -0.15735 0.665547 0.729581 -0.162608 0.702463 0.692895 -0.253035 0.854649 0.453374 -0.253743 0.864867 0.433151 -0.318327 0.940209 0.121136 -0.318809 0.939067 0.128504 0.403693 0.101664 0.909228 0.375758 0.218636 0.900558 0.225374 0.431946 0.873287 0.198919 0.503519 0.840774 0.0125448 0.703033 0.711047 -0.00288189 0.732079 0.681214 -0.20447 0.873186 0.442423 -0.205846 0.874843 0.438494 -0.39204 0.913783 0.106327 -0.384815 0.911991 0.14209 -0.419573 0.898729 0.127457 -0.43417 0.896304 0.0902027 -0.141034 0.908407 0.393581 -0.142715 0.909452 0.39055 0.15671 0.783948 0.600723 0.171189 0.764543 0.621424 0.429767 0.546646 0.718664 0.452535 0.490592 0.744669 0.639934 0.232872 0.732295 0.86557 0.168097 0.471733 0.766165 0.201736 0.610159 0.6558 0.135861 0.742609 0.754959 0.61631 0.224051 0.748192 0.627773 0.214731 0.415528 0.891608 0.179924 0.411148 0.894491 0.175624 -0.009513 0.994943 0.0999929 -0.00701496 0.994747 0.102125 -0.438625 0.89867 -0.000581612 -0.428809 0.903359 0.00805992 -0.43002 0.898864 0.0844205 -0.446771 0.892794 0.0575794 -0.0691047 0.955296 0.287462 -0.072116 0.956254 0.283508 0.301032 0.846244 0.439603 0.312196 0.834797 0.453484 0.617434 0.594656 0.514937 0.63341 0.557375 0.536773 0.852335 0.185601 0.488956 0.94586 0.244969 0.212928 0.948661 0.222401 0.2249 -0.0680098 0.985341 -0.156455 -0.263461 0.889922 -0.372326 -0.140273 0.965507 -0.219363 0.0177253 0.99455 -0.102748 -0.307921 0.840889 -0.445074 -0.306807 0.84243 -0.442924 -0.393554 0.765269 -0.509391 -0.51132 0.566379 -0.646349 -0.492103 0.589485 -0.640579 -0.641909 0.200695 -0.74005 -0.620161 0.241009 -0.746535 -0.618659 0.205732 -0.758245 -0.618009 0.198673 -0.760654 -0.486744 0.58235 -0.651113 -0.489532 0.564425 -0.664667 -0.27226 0.859514 -0.432562 -0.282307 0.839975 -0.463406 -0.0122639 0.990128 -0.13963 -0.0290328 0.981471 -0.1894 -0.719758 0.156224 0.676418 -0.114004 0.98744 0.109386 -0.0031423 0.943021 0.332718 -0.41307 0.883496 0.220927 -0.359036 0.8019 0.477545 -0.478364 0.75974 0.440413 -0.559938 0.641272 0.524633 -0.54331 0.648877 0.532703 -0.658803 0.478506 0.580526 -0.711006 0.450738 0.539728 -0.662771 0.283887 0.692924 -0.847314 0.08844 0.523676 -0.960826 0.227142 -0.158809 -0.712215 0.196643 -0.673856 -0.71507 0.219218 -0.663791 -0.555018 0.58755 -0.588847 -0.554667 0.589586 -0.58714 -0.292426 0.871762 -0.393088 -0.298683 0.86222 -0.409104 0.0277707 0.992255 -0.121076 0.010842 0.987169 -0.159309 -0.882614 0.2115 -0.419833 -0.882127 0.23022 -0.410914 -0.6996 0.610627 -0.371072 -0.697792 0.614543 -0.367997 -0.376036 0.89267 -0.248468 -0.38203 0.888118 -0.255539 0.0275204 0.996861 -0.074229 0.00955212 0.995584 -0.0933852 -0.974318 0.224569 0.0165466 -0.985023 0.149185 -0.0864531 -0.779649 0.621723 -0.0748819 -0.776996 0.625337 -0.0723277 -0.433856 0.899755 -0.047002 -0.429001 0.902232 -0.0440038 0.00323405 0.999949 -0.00956008 0.00977573 0.999933 -0.00627171 -0.939533 0.224708 0.258428 -0.943449 0.21444 0.252824 -0.758289 0.609042 0.23252 -0.755189 0.612289 0.234076 -0.436074 0.884835 0.164034 -0.416769 0.89331 0.168227 -0.0288318 0.997512 0.0643336 0.00942167 0.997653 0.0678221 -0.800648 0.211687 0.560492 -0.807568 0.198553 0.555348 -0.649776 0.581677 0.489329 -0.644613 0.586854 0.489977 -0.388473 0.857868 0.33638 -0.361766 0.870941 0.332547 -0.058691 0.990376 0.125341 -0.00813309 0.993788 0.11099 -0.725123 0.0910699 0.682571 -0.561105 0.646509 0.516901 -0.434127 0.810004 0.394242 -0.409975 0.835433 0.366021 -0.171823 0.973524 0.150758 -0.143442 0.982669 0.117411 -0.64772 0.483659 0.58867 -0.608479 0.559209 0.563062 -0.700654 0.283055 0.654954 -0.718978 0.196459 0.666689 -0.725793 0.0888806 0.682148 -0.686178 0.284078 0.669671 -0.714384 0.195661 0.671843 -0.640483 0.478792 0.600449 -0.599425 0.557046 0.574795 -0.560445 0.641269 0.524095 -0.405197 0.833066 0.376586 -0.426891 0.805907 0.410218 -0.150074 0.981441 0.119378 -0.175846 0.971351 0.159863 -0.715193 0.196162 0.670835 -0.715127 0.196532 0.670797 -0.608028 0.558326 0.564424 -0.607552 0.559225 0.564046 -0.407234 0.834536 0.371093 -0.406097 0.835511 0.370145 -0.143775 0.982228 0.12065 -0.141888 0.982697 0.11906 -0.714759 0.195659 0.671445 -0.714673 0.19617 0.671386 -0.607234 0.557018 0.566567 -0.606549 0.558347 0.565992 -0.406741 0.833053 0.374945 -0.405016 0.834566 0.373446 -0.143954 0.981544 0.125891 -0.14115 0.982263 0.123436 -0.724651 0.0889038 0.683358 -0.689822 0.199762 0.695874 -0.696008 0.283142 0.659852 -0.636012 0.483902 0.601105 -0.574043 0.568698 0.589116 -0.551069 0.64664 0.527427 -0.38736 0.846867 0.364374 -0.397684 0.809605 0.431726 -0.141044 0.986948 0.0777185 -0.153887 0.973419 0.169632 -0.0566635 0.990219 0.1275 -0.0878266 0.98699 0.134672 -0.343429 0.856007 0.386405 -0.364134 0.846147 0.389156 -0.572001 0.578513 0.581496 -0.582294 0.569099 0.580569 -0.704421 0.20418 0.67978 -0.706836 0.200458 0.67838 -0.970946 0.229462 -0.0678986 -0.971747 0.222494 -0.0787731 -0.778839 0.626698 -0.0256709 -0.781438 0.623088 -0.0334053 -0.433813 0.900739 0.0218092 -0.435922 0.899804 0.0180207 -0.00254605 0.99785 0.0654897 -0.00261237 0.997856 0.0654001 0.430523 0.897362 0.0969116 0.432686 0.896032 0.0995504 -0.951298 0.240871 0.192387 -0.968034 0.201114 0.149875 -0.752456 0.610224 0.247865 -0.775928 0.590129 0.222897 -0.418665 0.870203 0.259742 -0.434495 0.865274 0.250029 -0.00685158 0.974123 0.225916 -0.005535 0.974015 0.226414 0.409906 0.89933 0.152256 0.429175 0.889503 0.15682 0.423187 0.883301 0.201722 0.381916 0.898812 0.21512 0.039156 0.916431 0.398273 0.0374863 0.916415 0.398471 -0.347799 0.781366 0.518173 -0.308483 0.794571 0.522968 -0.669157 0.509477 0.540982 -0.604445 0.554973 0.571534 -0.873263 0.149936 0.463607 -0.664985 -0.0816825 0.742376 -0.68274 0.134503 0.718175 -0.80948 0.233995 0.538505 0.320159 0.922739 0.214594 0.311321 0.923181 0.225425 0.146948 0.847704 0.509711 0.15944 0.85178 0.49905 -0.0451269 0.6698 0.741169 -0.006798 0.692255 0.721621 -0.232736 0.412754 0.880607 -0.169209 0.461974 0.870602 0.255081 0.943901 0.209726 0.260117 0.944985 0.198349 0.187109 0.841541 0.506754 0.202385 0.852082 0.482696 0.0989081 0.653022 0.750852 0.12721 0.680029 0.722065 -0.000444763 0.399353 0.916797 0.0423275 0.445912 0.894076 0.382087 0.898685 0.215348 0.353098 0.905189 0.236546 0.101341 0.868797 0.484687 0.106192 0.869457 0.48246 -0.194493 0.708527 0.678352 -0.150915 0.726533 0.670354 -0.461201 0.445327 0.767448 -0.385898 0.49523 0.778351 -0.602817 0.222071 0.766353 -0.394218 0.109038 0.912526 -0.311106 0.185101 0.932175 -0.101051 0.107527 0.989053 0.249151 -0.133146 0.959268 0.152543 0.127688 0.980014 -0.0439399 0.172302 0.984064 0.159231 0.970721 0.179853 0.148297 0.980462 0.129234 0.257604 0.900365 0.35069 0.309522 0.853861 0.41847 0.32522 0.82332 0.465162 0.399181 0.66494 0.631276 0.480264 0.395157 0.783069 0.481623 0.412831 0.773052 0.447611 0.529747 0.720425 0.399136 0.69089 0.602794 0.198861 0.959248 0.200741 0.203018 0.96546 0.163313 0.234673 0.844514 0.481377 0.243093 0.862389 0.444063 0.247841 0.651708 0.716835 0.261787 0.681178 0.683713 0.237388 0.400299 0.885103 0.257728 0.439678 0.860384 0.213963 0.162564 0.96322 0.496322 0.130847 0.858221 0.503556 0.153086 0.850292 0.279752 0.900479 0.33298 0.134945 0.962163 0.236711 0.119234 0.981016 0.152942 0.625454 0.152298 0.765253 0.570215 0.255978 0.780596 0.580375 0.396422 0.711347 0.537715 0.531554 0.654456 0.427476 0.702251 0.569304 0.426104 0.691878 0.582872 0.35928 0.823819 0.438453 -0.960844 0.221836 -0.166039 -0.961302 0.219775 -0.166128 -0.770198 0.621809 -0.141947 -0.774022 0.61688 -0.142651 -0.427924 0.899333 -0.0898974 -0.43713 0.89472 -0.0916219 -0.00139617 0.999796 -0.0201262 -0.0157388 0.999614 -0.0229144 0.4254 0.903414 0.0536395 0.408701 0.911288 0.0501807 -0.961139 0.223668 -0.161814 -0.961536 0.221884 -0.161916 -0.768641 0.626216 -0.130557 -0.771997 0.621932 -0.13123 -0.42237 0.903465 -0.0731723 -0.430476 0.899504 -0.0747248 0.00839617 0.999964 -0.00113215 -0.00419389 0.999985 -0.00353111 0.437484 0.896406 0.0711599 0.422924 0.903586 0.0683265 0.500701 0.608049 0.616097 0.27856 0.896181 0.345347 0.16329 0.963135 0.213794 0.445052 0.702643 0.555177 0.609406 0.256781 0.750125 0.16223 0.963649 0.212279 0.164214 0.963668 0.210659 0.161707 0.96481 0.207346 0.163966 0.964823 0.205502 0.126167 0.980407 0.151272 0.444607 0.703451 0.55451 0.44607 0.703466 0.553315 0.444976 0.705316 0.551839 0.446644 0.705325 0.550478 0.391368 0.792563 0.467627 0.60936 0.257173 0.750028 0.609897 0.257179 0.74959 0.609781 0.257985 0.749407 0.610393 0.257988 0.748907 0.61034 0.258466 0.748786 0.549245 0.535541 -0.641503 0.289345 0.906594 -0.307193 0.132757 0.984388 -0.115567 0.394666 0.830921 -0.392185 0.469605 0.697454 -0.541322 0.604328 0.399763 -0.689186 0.628449 0.152863 -0.762682 0.164993 0.976613 -0.137853 0.197757 0.973216 -0.117227 0.214587 0.966134 -0.143307 0.283379 0.950443 -0.127887 0.282664 0.951104 -0.124505 0.355287 0.924862 -0.135653 0.358514 0.92836 -0.0980593 0.396625 0.910171 -0.119488 0.409221 0.909236 -0.0763436 0.342061 0.867713 -0.360651 0.293366 0.87228 -0.391235 0.31008 0.854144 -0.417479 0.265595 0.864129 -0.427482 0.26805 0.854092 -0.445731 0.22226 0.870708 -0.438712 0.221913 0.869967 -0.440354 0.158923 0.900479 -0.404822 0.161415 0.902572 -0.399136 0.487328 0.678731 -0.549395 0.360661 0.68963 -0.62796 0.375878 0.659977 -0.650497 0.221696 0.694051 -0.68494 0.223571 0.661399 -0.715938 0.0650025 0.719134 -0.691825 0.0551375 0.691635 -0.72014 -0.0991161 0.767208 -0.633694 -0.111103 0.747848 -0.654508 0.587385 0.428262 -0.68671 0.393502 0.444412 -0.80477 0.405943 0.404397 -0.819557 0.156364 0.459057 -0.874538 0.155163 0.397246 -0.9045 -0.0982902 0.489567 -0.866408 -0.117392 0.421176 -0.89935 -0.342012 0.531394 -0.775015 -0.362784 0.47416 -0.802222 -0.694768 0.202174 -0.690235 -0.554931 0.127152 -0.822121 -0.537979 0.226928 -0.811839 -0.272359 0.097704 -0.957222 -0.249451 0.209631 -0.945425 0.0712797 0.0931396 -0.993098 0.0766016 0.183916 -0.979953 0.319993 0.132779 -0.93807 0.369691 0.0223143 -0.928887 0.464767 0.156322 -0.871524 0.633684 0.140063 -0.760807 -0.804462 0.184143 -0.564741 -0.797679 0.147821 -0.584685 -0.568615 0.538586 -0.621774 -0.55286 0.579594 -0.598679 -0.267867 0.816131 -0.512032 -0.257318 0.828708 -0.497022 0.0852914 0.94752 -0.30811 0.0818973 0.946081 -0.313406 0.426352 0.903412 -0.0454926 0.410126 0.908746 -0.0773147 -0.916045 0.211214 -0.340956 -0.913193 0.244561 -0.325988 -0.727094 0.599896 -0.333855 -0.717989 0.617954 -0.320351 -0.401634 0.876844 -0.264264 -0.394552 0.882351 -0.256485 0.00460727 0.989631 -0.143556 0.00362483 0.989493 -0.144534 0.415794 0.909438 0.00619137 0.405695 0.913997 -0.00448317 0.0920529 0.979548 0.178921 0.0741319 0.988923 0.128594 0.255831 0.895721 0.363641 0.298963 0.849383 0.434936 0.614349 0.20199 0.762742 0.619385 0.25847 0.74132 0.493437 0.572085 0.655163 0.484196 0.607867 0.629327 0.367965 0.792361 0.486586 0.603221 0.208305 0.769892 0.602742 0.201047 0.772193 0.469192 0.588706 0.658243 0.4726 0.57026 0.671902 0.253521 0.865943 0.431127 0.264635 0.846154 0.462593 -0.00554152 0.991744 0.128113 0.0125 0.983791 0.178882 0.171663 0.967185 -0.187312 -0.0187736 0.962456 -0.270789 0.313608 0.906845 -0.281571 0.355037 0.869868 -0.342461 0.399414 0.830989 -0.387201 0.427612 0.722654 -0.543065 0.497726 0.69893 -0.513581 0.621763 0.526331 -0.579988 0.611459 0.537838 -0.580386 0.663401 0.401396 -0.631491 0.606742 0.301835 -0.735364 0.756711 0.154094 -0.635329 0.72669 0.050692 -0.685093 0.958891 0.232381 0.16287 0.706031 0.196734 0.680306 0.708533 0.224183 0.669122 0.542544 0.59291 0.595066 0.541678 0.596951 0.591806 0.271958 0.878088 0.393702 0.278783 0.868696 0.409447 -0.0548462 0.992118 0.112666 -0.0359217 0.987571 0.153014 0.88247 0.21567 0.418011 0.881907 0.235326 0.408486 0.690469 0.621684 0.369813 0.689112 0.624557 0.367495 0.353387 0.902934 0.244599 0.361668 0.8969 0.254492 -0.0624957 0.99585 0.0661597 -0.0403696 0.995093 0.0903382 0.972667 0.231801 -0.0136942 0.983663 0.157646 0.0869232 0.766551 0.638266 0.0708254 0.766964 0.637723 0.0712386 0.403408 0.914136 0.0402256 0.405421 0.913186 0.0415259 -0.0499488 0.998752 0.00067225 -0.0460742 0.998934 0.00272835 0.934294 0.236676 -0.266606 0.941797 0.218437 -0.255547 0.737892 0.627838 -0.247658 0.741475 0.624366 -0.245729 0.396233 0.900127 -0.181027 0.385681 0.904184 -0.183581 -0.0278766 0.996536 -0.0783463 -0.0564093 0.995085 -0.0813834 0.787514 0.224393 -0.573995 0.8036 0.197746 -0.561359 0.617143 0.597185 -0.512352 0.621324 0.59346 -0.511626 0.33706 0.869027 -0.362192 0.317203 0.877384 -0.359973 -0.00576177 0.989038 -0.147546 -0.0528959 0.989479 -0.134658 0.351434 0.869812 -0.346296 0.614331 0.526219 -0.587955 0.726491 0.0506882 -0.685304 0.351728 0.873692 -0.33608 0.176791 0.969734 -0.168404 0.681763 0.34672 -0.644193 0.615077 0.531577 -0.582329 0.56089 0.637454 -0.528256 0.724491 0.0925859 -0.683038 0.487242 0.726852 -0.484027 0.188371 0.964929 -0.182833 0.18681 0.964918 -0.18449 0.188632 0.964281 -0.185955 0.186025 0.96425 -0.188723 0.188661 0.963299 -0.190952 0.186772 0.963267 -0.192958 0.173202 0.967224 -0.185682 0.511521 0.702872 -0.494285 0.512879 0.702896 -0.492842 0.511685 0.704434 -0.491886 0.513575 0.704456 -0.48988 0.512751 0.705486 -0.48926 0.520031 0.705506 -0.481486 0.441934 0.79229 -0.420679 0.708086 0.258111 -0.657261 0.702072 0.258078 -0.663695 0.702186 0.257623 -0.663751 0.701498 0.257615 -0.664481 0.701661 0.256925 -0.664576 0.701167 0.256916 -0.665101 0.681436 0.305193 -0.665208 0.722477 0.0925764 -0.685169 0.694905 0.200564 -0.690566 0.682291 0.346722 -0.643633 0.596312 0.531291 -0.601782 0.569907 0.571415 -0.5905 0.543159 0.6372 -0.546768 0.426718 0.792017 -0.436601 0.350038 0.848882 -0.396072 0.32509 0.872899 -0.363817 0.105663 0.989144 -0.102124 0.144301 0.968587 -0.202524 -0.003244 0.989446 -0.144863 0.0446508 0.984898 -0.167276 0.296575 0.863761 -0.407383 0.328584 0.846599 -0.418692 0.5439 0.587077 -0.599595 0.55941 0.570315 -0.601499 0.695795 0.207703 -0.687552 0.699148 0.200991 -0.686145 -0.148627 0.966216 0.210563 -0.584845 0.302965 0.752442 -0.519678 0.524078 0.674742 -0.473439 0.629551 0.616053 -0.616142 0.0488185 0.786121 -0.44342 0.675585 0.589036 -0.53305 0.480727 0.696247 -0.319207 0.841005 0.436827 -0.0258007 0.99731 0.0686136 -0.157612 0.961707 0.224227 -0.156195 0.961678 0.225339 -0.157308 0.961214 0.226542 -0.154873 0.961158 0.228452 -0.15695 0.960242 0.230873 -0.123966 0.958565 0.256486 -0.182243 0.94657 0.266071 -0.406787 0.697291 0.590178 -0.430988 0.698257 0.571565 -0.430061 0.699661 0.570545 -0.43182 0.699702 0.569165 -0.431317 0.700418 0.568665 -0.436712 0.700514 0.564413 -0.363187 0.796687 0.4831 -0.596533 0.25587 0.760709 -0.593494 0.25581 0.763103 -0.593578 0.255456 0.763156 -0.592936 0.255442 0.76366 -0.593067 0.254813 0.763768 -0.58142 0.254463 0.772787 -0.595041 0.241068 0.766689 -0.0383121 0.997535 0.0587845 -0.19852 0.946825 0.253206 -0.185652 0.952317 0.242128 -0.329851 0.84123 0.428403 -0.448727 0.686359 0.572325 -0.452805 0.675802 0.581601 -0.539142 0.480883 0.691431 -0.598068 0.249476 0.761628 -0.598131 0.241153 0.764254 -0.605491 0.24154 0.758313 -0.603292 0.249396 0.757523 -0.477864 0.668137 0.570297 -0.464779 0.686092 0.559695 -0.238853 0.938587 0.249004 -0.210087 0.951925 0.22294 -0.614647 0.0487923 0.787292 -0.586309 0.197323 0.785688 -0.587953 0.303018 0.749994 -0.495821 0.523413 0.692965 -0.472053 0.562741 0.678593 -0.451188 0.628923 0.633155 -0.300948 0.840822 0.449943 -0.320094 0.794701 0.515743 -0.0863865 0.985296 0.147409 -0.109743 0.964376 0.240697 0.106232 0.165463 0.980478 -0.246786 0.93815 0.24284 -0.391895 0.247748 0.886024 -0.189537 0.966508 0.173025 -0.206216 0.95892 0.1948 -0.298298 0.854987 0.424282 -0.314103 0.839074 0.444178 -0.380345 0.669917 0.637611 -0.39432 0.646365 0.653241 -0.602833 0.143765 0.784808 -0.441001 0.15419 0.884163 -0.449008 0.120385 0.885381 -0.203318 0.959365 0.195654 -0.209646 0.953303 0.217399 -0.212728 0.854372 0.474126 -0.219943 0.836829 0.501341 -0.202953 0.674714 0.709628 -0.210096 0.642492 0.736929 0.0612645 0.939461 0.337136 -0.407856 0.845194 0.345399 -0.362948 0.668219 0.649424 -0.357048 0.669546 0.651325 -0.621942 0.416184 0.66331 -0.42899 0.429093 0.794888 -0.44033 0.399319 0.804148 -0.175222 0.438077 0.881695 -0.181575 0.390399 0.902563 -0.119226 0.109993 0.986756 -0.0749765 0.037879 0.996466 -0.264507 0.149802 0.952678 0.291268 0.125758 0.948339 0.264283 0.0144755 0.964337 0.101224 0.391782 0.914473 0.0910898 0.4561 0.885254 -0.0158629 0.652474 0.757645 -0.0232937 0.687872 0.725458 -0.132799 0.845095 0.51786 -0.136104 0.857446 0.496248 -0.236115 0.946375 0.220508 -0.236229 0.946687 0.219043 0.527924 0.0971932 0.843712 0.504342 0.207175 0.838282 0.370287 0.417085 0.830017 0.343916 0.485098 0.803991 0.162879 0.686255 0.70889 0.145461 0.714752 0.684084 -0.068412 0.867458 0.492785 -0.0702991 0.869296 0.489268 -0.291611 0.933285 0.209625 -0.279415 0.929591 0.240389 -0.320676 0.916505 0.239137 -0.348594 0.916363 0.19688 -0.0161624 0.897989 0.439721 -0.0229474 0.901675 0.431806 0.288891 0.760379 0.581692 0.30438 0.742855 0.596254 0.55386 0.524726 0.646453 0.580544 0.468874 0.665677 0.745872 0.223633 0.627426 0.938652 0.144022 0.313353 0.85796 0.195767 0.474953 0.764822 0.124637 0.63207 0.79439 0.595905 0.117651 0.781508 0.614572 0.107454 0.465086 0.873082 0.146367 0.456796 0.878246 0.141495 0.0434657 0.988058 0.147825 0.0469201 0.987624 0.149656 -0.392516 0.911717 0.121259 -0.376213 0.917281 0.13061 -0.352267 0.913345 0.204226 -0.383623 0.907392 0.171678 0.0260114 0.942439 0.333365 0.0160793 0.945607 0.324914 0.397618 0.821262 0.409181 0.409073 0.811108 0.418047 0.704133 0.572738 0.419725 0.72488 0.533357 0.43598 0.922875 0.172825 0.34414 0.968265 0.24413 0.0535141 0.975688 0.208628 0.0671409 -0.908947 0.20532 0.362848 0.0418555 0.991107 -0.126311 -0.247043 0.874741 -0.41689 -0.490695 0.600017 -0.631821 -0.645801 0.217438 -0.731889 -0.639003 0.207887 -0.740579 -0.790024 0.229476 -0.568509 -0.788898 0.211729 -0.576897 -0.934571 0.231278 -0.270347 -0.934743 0.229025 -0.271669 0.0400448 0.993806 -0.103662 0.0307016 0.995101 -0.0939791 0.0507207 0.996783 -0.0620622 0.0270003 0.999563 -0.0120416 0.0371817 0.999301 -0.00380285 0.0283261 0.996817 0.074518 0.0110169 0.99755 0.0690861 -0.248908 0.87916 -0.406353 -0.324844 0.887956 -0.325592 -0.316778 0.895964 -0.311289 -0.4013 0.906389 -0.131972 -0.396078 0.909392 -0.126997 -0.420593 0.902538 0.0923404 -0.425201 0.900589 0.0902381 -0.490384 0.599437 -0.632612 -0.615605 0.614162 -0.493797 -0.615785 0.613576 -0.4943 -0.743369 0.63029 -0.223913 -0.742306 0.632087 -0.222369 -0.777167 0.622743 0.0905708 -0.772952 0.627469 0.0939557 -0.969142 0.236127 0.0707638 -0.986573 0.0984791 0.130292 -0.973683 0.225085 -0.0357363 -0.830683 0.213919 0.514009 -0.906549 0.147781 0.395385 -0.700356 0.60136 0.384535 -0.706491 0.595648 0.382196 -0.393973 0.872941 0.28768 -0.379318 0.878996 0.288935 -0.0137305 0.990147 0.139358 0.026723 0.990264 0.136614 -0.700285 0.209503 0.682429 -0.715574 0.184561 0.673715 -0.557491 0.569374 0.604167 -0.560964 0.56599 0.604131 -0.324205 0.842308 0.430591 -0.306661 0.851337 0.425658 -0.0363551 0.98165 0.187194 0.00478995 0.985689 0.168508 0.970241 0.219342 -0.102573 0.970439 0.218478 -0.102551 0.785511 0.615165 -0.0674101 0.78613 0.614372 -0.0674237 0.449923 0.892859 -0.0193084 0.450915 0.892357 -0.0193449 0.0279013 0.999082 0.0324949 0.029132 0.999048 0.0324584 -0.39947 0.913418 0.0780466 -0.398232 0.913959 0.0780402 0.973371 0.220611 -0.0622901 0.973981 0.217888 -0.0623318 0.785321 0.617931 -0.0378639 0.788356 0.614042 -0.0380483 0.44491 0.895555 -0.00609697 0.451223 0.892388 -0.00643041 0.0181277 0.999475 0.0268404 0.0272836 0.999278 0.0264518 -0.412122 0.909495 0.0545427 -0.401841 0.9141 0.0542725 0.975009 0.222056 -0.00700592 0.975611 0.219396 -0.00698246 0.782731 0.62236 -0.000150435 0.786874 0.617113 -0.00010234 0.435905 0.899967 0.00672557 0.445444 0.895284 0.00682031 0.00300237 0.99992 0.0122528 0.0175385 0.999769 0.0124487 -0.430399 0.902509 0.0153291 -0.413686 0.910284 0.0156981 -0.0601436 0.991448 -0.115815 -0.10654 0.982936 -0.149956 -0.247531 0.909491 -0.333999 -0.302153 0.857049 -0.417338 -0.361447 0.810103 -0.461616 -0.471021 0.646638 -0.599998 -0.494843 0.579028 -0.647963 -0.547333 0.483936 -0.682812 -0.601323 0.283192 -0.747136 -0.603954 0.203919 -0.770491 -0.62863 0.0888267 -0.772615 -0.605206 0.212029 -0.767313 -0.604784 0.203972 -0.769826 -0.472258 0.59788 -0.647698 -0.476461 0.577755 -0.66271 -0.254454 0.875554 -0.41068 -0.267581 0.854498 -0.445235 0.00834951 0.995063 -0.0988925 -0.0128332 0.987934 -0.154342 0.46486 0.472695 -0.748642 0.18533 0.741041 -0.645377 -0.428664 0.901772 -0.0552571 0.431846 0.885104 -0.173497 0.42269 0.888614 -0.178041 0.770426 0.610266 -0.18444 0.756283 0.62405 -0.196462 0.962765 0.218961 -0.158558 0.855596 0.0323805 -0.51663 0.885806 0.187523 -0.42448 0.952452 0.246332 -0.17932 0.14694 0.755937 -0.63794 0.0214028 0.688932 -0.72451 -0.0149251 0.70857 -0.705483 -0.127149 0.663828 -0.736997 -0.155581 0.688619 -0.708236 0.393399 0.519889 -0.758256 0.222882 0.428157 -0.875788 0.157395 0.476414 -0.865018 -0.0153955 0.407399 -0.913121 -0.0625074 0.454627 -0.888486 0.334349 0.819307 -0.465776 0.309182 0.826753 -0.469985 0.659335 0.546039 -0.516835 0.614155 0.576044 -0.539432 0.836299 0.246516 -0.489729 0.672002 0.131921 -0.728704 0.585165 0.215917 -0.78164 0.397357 0.114472 -0.910497 0.308833 0.192681 -0.931395 0.0995655 0.109308 -0.989009 0.0337965 0.178014 -0.983447 -0.171378 0.12289 -0.977511 -0.321256 0.155732 -0.9341 -0.190552 0.0501175 -0.980397 -0.277403 0.445379 -0.851284 -0.252504 0.402566 -0.879877 -0.289202 0.685413 -0.668259 -0.27359 0.656218 -0.703226 -0.414613 0.908503 -0.052137 -0.436454 0.891495 -0.121426 -0.402719 0.906164 -0.129168 -0.415681 0.897477 -0.14746 -0.379956 0.908533 -0.173786 -0.360239 0.918978 -0.160337 -0.344602 0.921261 -0.180353 -0.294449 0.9411 -0.166225 -0.295175 0.941173 -0.164517 -0.233997 0.957809 -0.166876 -0.237245 0.961774 -0.136771 -0.189163 0.969656 -0.154871 -0.178829 0.978095 -0.106536 -0.320156 0.856179 -0.405534 -0.275546 0.863497 -0.422431 -0.267274 0.848059 -0.45756 -0.236055 0.856605 -0.45881 -0.223698 0.84912 -0.478491 -0.189028 0.862886 -0.468717 -0.181929 0.860995 -0.474962 -0.123056 0.892203 -0.434547 -0.124867 0.892362 -0.433703 -0.0489222 0.944174 -0.325794 -0.0543751 0.943978 -0.325498 0.00760709 0.991888 -0.12689 0.0055678 0.991819 -0.127533 -0.510549 0.157922 -0.845222 -0.498513 0.125869 -0.857696 -0.488478 0.444566 -0.750833 -0.481561 0.412482 -0.773277 -0.439672 0.635398 -0.63479 -0.43663 0.66033 -0.610998 -0.390578 0.745178 -0.540516 -0.315021 0.876529 -0.363948 -0.124616 0.98259 -0.137798 -0.123461 0.982958 -0.136201 -0.269502 0.909576 -0.316291 -0.378723 0.810038 -0.44767 -0.353944 0.835264 -0.420782 -0.487234 0.646568 -0.586987 -0.530622 0.558972 -0.637174 -0.557067 0.483844 -0.67496 -0.621548 0.196428 -0.75835 -0.61244 0.28305 -0.738105 -0.630582 0.0888003 -0.771026 -0.12527 0.981779 -0.142893 -0.122616 0.982611 -0.139431 -0.353758 0.833542 -0.424339 -0.352168 0.835284 -0.42223 -0.527982 0.557428 -0.64071 -0.527359 0.559011 -0.639843 -0.621202 0.195822 -0.758789 -0.621142 0.196433 -0.758681 -0.124415 0.981328 -0.146685 -0.123008 0.981794 -0.14474 -0.352667 0.832585 -0.427116 -0.351823 0.833555 -0.425919 -0.527001 0.556572 -0.64226 -0.526682 0.557437 -0.641771 -0.62077 0.195492 -0.759229 -0.620743 0.195825 -0.759164 -0.624351 0.195477 -0.75629 -0.13829 0.980511 -0.13955 -0.1371 0.981136 -0.136292 -0.326952 0.876057 -0.354439 -0.35524 0.832569 -0.425009 -0.615045 0.152936 -0.773518 -0.583899 0.441573 -0.681231 -0.52279 0.55658 -0.645685 -0.500779 0.634122 -0.58916 -0.439155 0.744151 -0.503371 -0.964582 0.243966 0.100314 -0.970448 0.227707 0.0798749 -0.753319 0.64459 0.130438 -0.763064 0.63589 0.115659 -0.387194 0.912206 0.134019 -0.39553 0.909797 0.125804 0.0608141 0.992022 0.110424 0.0576139 0.992471 0.108087 0.499094 0.864122 0.0647955 0.50171 0.862479 0.066457 -0.887817 0.244163 0.390085 -0.923192 0.195473 0.330919 -0.662149 0.60995 0.435338 -0.704116 0.584997 0.402492 -0.312529 0.861342 0.40052 -0.342956 0.855454 0.388045 0.0983993 0.951367 0.291923 0.0908186 0.952538 0.290558 0.494609 0.859399 0.129598 0.509825 0.850423 0.129841 0.513489 0.841157 0.169657 0.488702 0.853117 0.182654 0.164938 0.885837 0.433692 0.177864 0.884986 0.430308 -0.212569 0.762303 0.611317 -0.157112 0.775505 0.61148 -0.549085 0.49935 0.670191 -0.463551 0.544299 0.699184 -0.786302 0.146441 0.600237 -0.568467 -0.097426 0.816917 -0.567052 0.123366 0.814391 -0.695849 0.227771 0.681113 0.442695 0.876611 0.188611 0.439772 0.876932 0.193883 0.310003 0.803908 0.507572 0.330096 0.810223 0.48433 0.137475 0.63264 0.762147 0.189698 0.661005 0.726007 -0.0536878 0.385981 0.920943 0.0339486 0.444988 0.894893 0.393291 0.899761 0.189084 0.397182 0.901007 0.174447 0.360322 0.795351 0.487427 0.376527 0.808164 0.452877 0.289706 0.61174 0.736101 0.325035 0.645008 0.691605 0.188532 0.368879 0.910156 0.247949 0.426337 0.869918 0.489288 0.852654 0.183246 0.471907 0.858205 0.201959 0.245754 0.830851 0.49929 0.264465 0.83258 0.486692 -0.0370002 0.678816 0.733376 0.0275538 0.702012 0.711632 -0.314549 0.424112 0.849228 -0.208334 0.483881 0.849974 -0.453874 0.231109 0.860574 -0.240737 0.0956322 0.965867 -0.121293 0.184136 0.975388 0.066676 0.0918808 0.993535 0.373467 -0.137661 0.917372 0.32166 0.110593 0.940375 0.152752 0.171701 0.973235 0.318552 0.932968 0.167618 0.302903 0.944694 0.125714 0.421098 0.85259 0.309462 0.473804 0.800043 0.368024 0.489036 0.773391 0.403373 0.564866 0.611431 0.554147 0.634643 0.371208 0.677815 0.634377 0.368127 0.679741 0.605323 0.495059 0.623298 0.562276 0.644983 0.517535 0.350031 0.918418 0.184357 0.349053 0.925015 0.150032 0.409143 0.796071 0.445951 0.414269 0.816121 0.402898 0.431704 0.605419 0.668655 0.447292 0.642062 0.622645 0.415932 0.364175 0.833293 0.44601 0.41768 0.791592 0.386116 0.167056 0.907197 0.632688 0.105043 0.767249 0.649382 0.150989 0.745323 0.726216 0.241157 0.643781 0.555348 0.674277 0.486765 0.55779 0.668642 0.49172 0.407906 0.839111 0.359868 0.058508 0.997058 0.0495238 0.258906 0.939217 0.225476 0.249272 0.945317 0.21033 0.746843 0.138813 0.650351 0.725447 0.241744 0.644427 0.72622 0.241707 0.64357 0.657433 0.478429 0.582141 0.590556 0.64244 0.488379 0.580339 0.667566 0.466437 0.674154 0.488443 0.554022 0.711907 0.36305 0.601152 0.269333 0.949111 0.163244 0.289397 0.937909 0.191251 0.428288 0.851816 0.301627 0.507351 0.771563 0.383779 -0.964168 0.225727 -0.139383 -0.964434 0.224527 -0.139484 -0.769008 0.630872 -0.103091 -0.770922 0.628461 -0.10352 -0.41728 0.907623 -0.0458005 -0.421767 0.905503 -0.0466704 0.0194036 0.999595 0.0208279 0.0125606 0.999729 0.0195842 0.452138 0.888056 0.0832364 0.44436 0.8921 0.0818595 -0.967123 0.228122 -0.1124 -0.967797 0.225139 -0.112607 -0.767676 0.636019 -0.0784435 -0.772282 0.630315 -0.0792722 -0.40898 0.912108 -0.0282013 -0.419518 0.907258 -0.0298122 0.0346108 0.999011 0.027916 0.0187172 0.999495 0.0256974 0.471012 0.878648 0.0782664 0.453158 0.88819 0.0759405 -0.969823 0.228267 -0.0856588 -0.969991 0.22751 -0.0857683 -0.76879 0.636997 -0.0565414 -0.769938 0.635581 -0.0568617 -0.407592 0.913031 -0.0156313 -0.410194 0.911855 -0.0161842 0.0385226 0.99885 0.02856 0.0346209 0.999013 0.027815 0.476606 0.876573 0.0668352 0.472249 0.878991 0.0659994 -0.971142 0.231457 -0.0575355 -0.972057 0.227523 -0.057776 -0.764129 0.644108 -0.0351027 -0.770519 0.636404 -0.0359228 -0.393728 0.919213 -0.00514136 -0.408384 0.912786 -0.00661471 0.0609041 0.997806 0.0259565 0.0389259 0.998953 0.0240254 0.502455 0.863065 0.0515509 0.478092 0.876909 0.0495894 0.312428 0.897322 0.311772 0.0375384 0.996611 0.0732005 0.225272 0.944855 0.237701 0.539135 0.673744 0.505373 0.72113 0.240935 0.649555 0.462801 0.773777 0.432532 0.685987 0.362953 0.630624 0.685996 0.362925 0.630631 0.132675 0.979842 0.149354 0.195014 0.957148 0.214094 0.196348 0.957211 0.212592 0.195343 0.957626 0.211646 0.195559 0.957635 0.211403 0.194574 0.958045 0.210452 0.194989 0.958064 0.209983 0.524202 0.69511 0.49197 0.523893 0.695096 0.492318 0.524334 0.694464 0.492741 0.524173 0.694457 0.492922 0.524614 0.693834 0.493331 0.523644 0.693789 0.494422 0.39034 0.838616 0.379945 0.718697 0.253385 0.647512 0.718574 0.253379 0.64765 0.718622 0.253116 0.6477 0.718561 0.253113 0.647768 0.718607 0.252872 0.647812 0.718144 0.252851 0.648332 0.647392 0.478023 0.593613 -0.686431 0.192745 -0.701186 -0.179446 0.175005 -0.968077 0.397599 0.856218 -0.329857 0.3795 0.867565 -0.321421 0.252162 0.963866 -0.085882 0.233693 0.969331 -0.0760596 0.581093 0.135373 -0.802499 0.56845 0.159209 -0.807166 0.569859 0.421642 -0.705321 0.554779 0.442725 -0.704425 0.506821 0.669622 -0.542899 0.549173 0.624501 -0.555344 0.468807 0.737907 -0.485504 0.368705 0.0953186 -0.924647 0.366151 0.177984 -0.913376 0.410237 0.389729 -0.82451 0.400079 0.453764 -0.796263 0.411947 0.648106 -0.640514 0.396859 0.690806 -0.604392 0.372322 0.842511 -0.389296 0.355616 0.864946 -0.354127 0.294736 0.950643 -0.0969929 0.279869 0.957507 -0.0696754 0.0201109 0.0841944 -0.996246 0.0412904 0.201371 -0.978644 0.140161 0.393814 -0.908441 0.1523 0.473463 -0.867547 0.245193 0.659624 -0.710477 0.248962 0.701334 -0.667943 0.321509 0.847015 -0.423317 0.320538 0.859557 -0.398017 0.358356 0.929932 -0.0825013 0.358935 0.929368 -0.0862659 -0.372685 0.129699 -0.918849 -0.371863 0.0831527 -0.924556 -0.135785 0.430918 -0.892117 -0.109477 0.506394 -0.855324 0.0679792 0.700985 -0.709928 0.0825998 0.732913 -0.67529 0.263914 0.868563 -0.419462 0.266024 0.871876 -0.411172 0.420834 0.904898 -0.0637094 0.417547 0.903627 -0.095462 -0.58249 0.13585 -0.801405 -0.566593 0.235082 -0.789752 -0.374883 0.491595 -0.786001 -0.353409 0.549677 -0.75694 -0.101253 0.76488 -0.636165 -0.0875139 0.785877 -0.612159 0.19324 0.906985 -0.374214 0.193067 0.906858 -0.374612 0.455937 0.888903 -0.044424 0.446105 0.891428 -0.0796653 -0.792305 0.182492 -0.582193 -0.792262 0.210439 -0.572745 -0.574949 0.559534 -0.596955 -0.560519 0.598119 -0.572776 -0.258714 0.836591 -0.48289 -0.248092 0.848906 -0.4667 0.111178 0.955003 -0.274969 0.109553 0.954426 -0.277612 0.463539 0.886 -0.0116156 0.450549 0.891933 -0.0382323 -0.921984 0.223739 -0.316048 -0.920284 0.247061 -0.303379 -0.726304 0.61978 -0.297245 -0.720185 0.63174 -0.286772 -0.388455 0.89476 -0.220243 -0.384091 0.897914 -0.214999 0.0308263 0.99466 -0.0984939 0.0289676 0.994521 -0.10044 0.449851 0.891998 0.0444318 0.44132 0.896661 0.0351605 0.144642 0.975287 0.167012 0.125451 0.97952 0.157489 0.313486 0.897367 0.310579 0.402871 0.82089 0.404766 0.460243 0.773679 0.435428 0.613391 0.546455 0.570209 0.719988 0.364048 0.590835 0.769599 0.193195 0.6086 0.689835 0.363094 0.62633 0.72102 0.204363 0.662092 0.723191 0.19126 0.663637 0.578348 0.578433 0.575265 0.595333 0.545375 0.590038 0.339417 0.854906 0.39234 0.379795 0.81906 0.429995 0.044752 0.98853 0.144242 0.108447 0.972237 0.207353 0.161391 0.974022 -0.158852 0.491526 0.648306 -0.581465 0.551374 0.548034 -0.629004 0.557701 0.485582 -0.673186 0.601396 0.282546 -0.747323 0.629698 0.191071 -0.752975 0.618173 0.0879882 -0.781102 0.158104 0.976932 -0.143555 0.206188 0.972761 -0.105934 0.200139 0.974423 -0.102197 0.378901 0.867656 -0.321882 0.40293 0.822219 -0.401998 0.387073 0.823681 -0.414396 0.391693 0.810984 -0.434605 0.622951 0.150347 -0.767677 0.610431 0.192943 -0.76821 0.599453 0.435842 -0.671341 0.545294 0.548619 -0.633776 0.530263 0.627656 -0.569973 0.477436 0.736636 -0.47898 0.972799 0.230138 0.0264219 0.804143 0.183618 0.565365 0.803781 0.224484 0.550947 0.631637 0.570235 0.52523 0.625512 0.587136 0.513816 0.340968 0.855859 0.388903 0.341558 0.855245 0.389736 -0.0164657 0.983692 0.179104 -0.00253063 0.980161 0.198185 0.938773 0.200799 0.279974 0.934697 0.23485 0.266809 0.748853 0.599359 0.282822 0.740951 0.612845 0.274614 0.408561 0.883201 0.230289 0.409804 0.88237 0.231264 -0.0184268 0.9912 0.131087 -0.0010798 0.989576 0.144007 0.963361 0.224639 -0.146537 0.985862 0.152779 -0.0688014 0.782043 0.623043 -0.0150284 0.775604 0.630929 -0.0191387 0.429127 0.902835 0.0271946 0.426493 0.904113 0.0261302 -0.0173355 0.997751 0.0647536 -0.0126709 0.997718 0.0663188 0.891011 0.230791 -0.39094 0.892748 0.226966 -0.389213 0.709113 0.627523 -0.321519 0.707374 0.629206 -0.322058 0.385298 0.903462 -0.187887 0.376609 0.906989 -0.18851 -0.0200936 0.999689 -0.0147378 -0.0365256 0.999232 -0.0142249 0.699404 0.229292 -0.676948 0.711837 0.209926 -0.670238 0.541609 0.613269 -0.574944 0.546518 0.608947 -0.574893 0.281637 0.886877 -0.366237 0.272217 0.890806 -0.363817 -0.0343776 0.995615 -0.0870003 -0.0599656 0.995259 -0.0765774 0.616074 0.0880276 -0.782754 0.143379 0.976091 -0.16337 0.56221 0.489406 -0.666635 0.479138 0.652948 -0.586588 0.372121 0.814945 -0.444287 0.616688 0.0862273 -0.782471 0.553872 0.283037 -0.783017 0.3487 0.811808 -0.468375 0.149938 0.97434 -0.167872 0.607595 0.197233 -0.769369 0.607774 0.197229 -0.769228 0.607741 0.197437 -0.7692 0.608063 0.19743 -0.768948 0.608022 0.197693 -0.768913 0.608457 0.197683 -0.768571 0.608412 0.198016 -0.768521 0.617481 0.197747 -0.761323 0.597388 0.281852 -0.750791 0.520163 0.563142 -0.642107 0.519255 0.563168 -0.642819 0.519704 0.562139 -0.643356 0.518466 0.562169 -0.644329 0.518749 0.561553 -0.644638 0.517828 0.561573 -0.64536 0.518131 0.560914 -0.64569 0.494547 0.561116 -0.663756 0.545282 0.485875 -0.683076 0.356132 0.839532 -0.410311 0.348605 0.839772 -0.416241 0.349673 0.83869 -0.417525 0.347822 0.838735 -0.418978 0.348516 0.838053 -0.419767 0.347135 0.838082 -0.42085 0.347848 0.837381 -0.421658 0.347128 0.837395 -0.422223 0.477391 0.648676 -0.59272 0.148381 0.98253 -0.112329 0.123451 0.983529 -0.132022 0.122294 0.98385 -0.130703 0.123927 0.983815 -0.129421 0.122789 0.984128 -0.128123 0.124972 0.984075 -0.126409 0.123209 0.984565 -0.124303 0.124759 0.984523 -0.123086 0.615089 0.0862738 -0.783724 0.600064 0.204526 -0.773364 0.591872 0.282005 -0.75509 0.538118 0.490168 -0.685685 0.49845 0.579624 -0.644658 0.466506 0.653228 -0.596377 0.318105 0.857584 -0.404177 0.351323 0.815258 -0.460356 0.0850868 0.991763 -0.0957387 0.130423 0.976168 -0.173455 -0.0257877 0.996442 -0.0802339 0.0298064 0.989824 -0.139138 0.237862 0.883849 -0.402781 0.274709 0.855899 -0.438145 0.457003 0.60636 -0.650751 0.473879 0.57865 -0.663779 0.59071 0.215573 -0.777553 0.593765 0.204293 -0.778272 -0.335548 0.864863 -0.373389 0.922512 0.228596 -0.310991 0.925088 0.223706 -0.306867 0.7396 0.618288 -0.265918 0.74027 0.617714 -0.265386 0.418165 0.892145 -0.170925 0.41424 0.893606 -0.172841 0.0162039 0.998937 -0.0431511 0.0067175 0.998906 -0.0462863 -0.391478 0.915414 0.0936048 -0.405054 0.909864 0.0898869 0.781572 0.23403 -0.578252 0.809949 0.196539 -0.55259 0.593721 0.595845 -0.5408 0.615381 0.580345 -0.533391 0.305503 0.857908 -0.413113 0.308038 0.857065 -0.41298 -0.0372549 0.975846 -0.215262 -0.0592053 0.975418 -0.212262 -0.377145 0.925936 0.0201033 -0.419137 0.907379 0.0314189 0.526149 0.222848 -0.820674 0.592477 0.153011 -0.790923 0.352466 0.546373 -0.759766 0.400172 0.511628 -0.760329 0.126596 0.794372 -0.594093 0.142985 0.787368 -0.599673 -0.121241 0.930958 -0.344409 -0.139514 0.932491 -0.333162 -0.355061 0.93376 -0.0449867 -0.399629 0.91666 -0.00562975 -0.342725 0.938655 -0.038302 -0.324318 0.943426 -0.069028 -0.204305 0.897959 -0.389782 -0.203113 0.897625 -0.39117 -0.0360787 0.729137 -0.683416 -0.0599351 0.743691 -0.665832 0.138015 0.459483 -0.877398 0.0868997 0.501756 -0.860633 0.294873 0.12865 -0.946836 -0.0497552 -0.042221 -0.997869 0.0352049 0.140412 -0.989467 0.219935 0.20155 -0.954466 -0.403221 0.460012 -0.791077 -0.381506 0.41693 -0.824999 -0.388807 0.70137 -0.597419 -0.241994 0.968248 -0.0627191 -0.254738 0.965409 -0.0556227 -0.255628 0.963958 -0.0737479 -0.231416 0.972191 -0.0359454 -0.410996 0.859757 -0.30315 -0.337902 0.876046 -0.344042 -0.378933 0.675279 -0.632778 -0.618663 0.450808 -0.64345 -0.613031 0.413869 -0.672983 -0.558665 0.638465 -0.529391 -0.552602 0.66373 -0.504077 -0.500089 0.746403 -0.439084 -0.402506 0.87402 -0.272173 -0.288567 0.955363 -0.0633231 -0.287302 0.955411 -0.0681798 -0.264576 0.87705 -0.400978 -0.271555 0.882176 -0.384739 -0.207779 0.694044 -0.689297 -0.228817 0.715868 -0.659678 -0.125057 0.430485 -0.893892 -0.164476 0.475383 -0.864268 -0.0550017 0.194253 -0.979408 -0.343751 0.118019 -0.931615 -0.3806 0.176316 -0.907776 -0.628324 0.122374 -0.768266 -0.645366 0.168111 -0.745145 -0.473268 0.847816 0.239219 -0.434406 0.872089 0.225283 -0.0354976 0.99806 0.0511445 -0.0630435 0.995884 0.0651279 0.377154 0.916347 -0.134403 0.359846 0.924575 -0.125186 0.709836 0.641173 -0.2916 0.703358 0.649994 -0.287742 0.892219 0.232812 -0.386968 0.892555 0.230983 -0.387289 0.910486 0.229388 -0.344087 0.90216 0.3124 -0.297511 0.767348 0.618638 -0.168714 0.760407 0.627638 -0.16689 0.438779 0.895737 -0.0716057 0.419507 0.905283 -0.0669108 0.0247284 0.998913 0.0395216 -0.00703383 0.998885 0.0466797 -0.394107 0.907867 0.143028 -0.426166 0.892213 0.149462 -0.446865 0.873394 0.193638 -0.415208 0.890705 0.185057 -0.0340575 0.997916 0.054802 -0.00700636 0.998881 0.0467684 0.391682 0.914909 -0.0976024 0.40842 0.906982 -0.102843 0.734448 0.638709 -0.229426 0.740675 0.630746 -0.231428 0.922327 0.226604 -0.312991 0.94661 0.222862 -0.232941 0.94685 0.221765 -0.233016 -0.694335 0.360054 -0.623106 -0.520483 0.738769 -0.428156 -0.432966 0.835564 -0.338192 -0.360912 0.88906 -0.281629 -0.128382 0.989831 -0.0612663 -0.159476 0.982507 -0.0961632 -0.737972 0.196689 -0.645531 -0.744444 0.196182 -0.638213 -0.744695 0.152144 -0.649832 -0.697627 0.440121 -0.56534 -0.647913 0.558412 -0.518059 -0.62126 0.560332 -0.547781 -0.710195 0.359447 -0.605327 -0.200709 0.977128 -0.0702567 -0.191482 0.979661 -0.0599984 -0.410757 0.872913 -0.263251 -0.454374 0.833688 -0.313863 -0.541999 0.741431 -0.395624 -0.613779 0.631756 -0.473455 0.851623 0.238453 -0.466774 0.852092 0.236332 -0.466997 0.682541 0.657881 -0.318325 0.680989 0.65986 -0.31755 0.358827 0.928272 -0.0977471 0.35252 0.930992 -0.0947853 -0.046046 0.988363 0.144976 -0.057376 0.987063 0.149717 -0.440281 0.824739 0.354905 -0.453993 0.815301 0.359408 0.867114 0.234584 -0.439413 0.866798 0.235881 -0.439342 0.688453 0.65139 -0.318941 0.683306 0.657753 -0.316945 0.358358 0.924734 -0.128241 0.344936 0.93055 -0.122869 -0.0502863 0.994609 0.0906868 -0.0715246 0.99254 0.0987385 -0.447768 0.845857 0.289878 -0.471751 0.829977 0.297639 -0.143377 0.985667 -0.0888983 -0.120599 0.990227 -0.0700485 -0.359468 0.889127 -0.28326 -0.417592 0.84263 -0.339988 -0.518303 0.738869 -0.430621 -0.626868 0.565772 -0.535667 -0.709085 0.3595 -0.606596 -0.741034 0.198906 -0.641331 -0.704831 0.359649 -0.611446 -0.736895 0.199336 -0.645949 -0.736922 0.199094 -0.645993 -0.627528 0.56639 -0.534239 -0.627839 0.565729 -0.534573 -0.418321 0.843254 -0.337535 -0.419094 0.842564 -0.338298 -0.142539 0.985949 -0.0871064 -0.143856 0.985646 -0.0883579 -0.7369 0.199554 -0.645877 -0.736924 0.199336 -0.645916 -0.627407 0.566813 -0.533932 -0.627608 0.566387 -0.534148 -0.417884 0.843742 -0.336856 -0.418439 0.843248 -0.337403 -0.141751 0.986152 -0.0860852 -0.14267 0.985943 -0.0869586 0.973364 0.189711 0.128731 -0.0324408 0.469649 0.882257 -0.0698085 0.826815 0.558125 -0.0812244 0.928716 0.361787 -0.0645067 0.745456 0.663427 -0.0452313 0.617591 0.785198 -0.0619149 0.346104 0.936151 0.00434085 0.135825 0.990723 -0.00423884 0.126554 0.991951 0.202034 0.148556 0.968046 0.20117 0.0878613 0.975608 0.497972 0.175074 0.849337 0.525708 0.0602872 0.848526 0.735594 0.198677 0.647633 0.78287 0.0622681 0.619062 -0.0876487 0.925025 0.369658 -0.0935023 0.924322 0.369981 -0.090919 0.913415 0.396746 -0.130676 0.901217 0.413197 -0.128149 0.899469 0.417771 -0.185966 0.860476 0.474339 -0.21436 0.868807 0.446346 -0.250597 0.81505 0.522393 -0.328499 0.816271 0.475173 -0.0972298 0.792297 0.602339 -0.0156167 0.801608 0.597646 -0.0121357 0.779055 0.626838 0.0458302 0.796506 0.602892 0.0619777 0.777359 0.625996 0.0805966 0.789914 0.607898 0.0860969 0.78637 0.611726 0.0969857 0.802428 0.588815 0.0808369 0.808084 0.583495 -0.0527289 0.610119 0.790553 0.0635057 0.621199 0.781076 0.0669423 0.585287 0.808058 0.218504 0.630175 0.745074 0.245807 0.582464 0.7748 0.339079 0.645062 0.684777 0.375759 0.606864 0.700372 0.43098 0.688518 0.583267 0.47338 0.657525 0.58615 -0.0293729 0.381705 0.923817 0.137814 0.397804 0.907061 0.139863 0.348587 0.926782 0.373097 0.417051 0.828775 0.405105 0.335274 0.850577 0.564225 0.441169 0.697868 0.617538 0.354478 0.702134 0.7087 0.490392 0.507207 0.779181 0.395798 0.486025 0.958868 0.0969371 0.266788 0.962246 0.0899508 0.256888 0.855361 0.156477 0.493835 0.983655 0.164485 -0.0732691 0.987176 0.143891 -0.0691342 0.840069 0.499133 0.212485 0.791324 0.56933 0.222865 0.515634 0.762115 0.391539 0.480992 0.784926 0.390561 0.0777089 0.868082 0.4903 0.0843808 0.866644 0.49174 -0.383302 0.786504 0.484243 -0.330049 0.795418 0.508308 0.926143 0.211416 -0.31235 0.904887 0.276866 -0.323303 0.778318 0.616068 -0.121162 0.745348 0.654318 -0.127767 0.459535 0.883006 0.0955393 0.431012 0.897684 0.0916106 0.0322574 0.955435 0.293435 0.0219963 0.956187 0.291928 -0.410675 0.804544 0.429016 -0.397527 0.809331 0.432383 -0.93089 0.195275 -0.308725 -0.683955 0.651631 0.327998 -0.766937 0.506839 0.393601 -0.749697 0.542916 0.378413 -0.811406 0.439588 0.385204 -0.894295 0.186465 0.406776 -0.88052 0.224649 0.417395 -0.912021 0.0345293 0.408687 -0.502143 0.818512 0.279091 -0.497802 0.821368 0.278475 -0.373688 0.903301 0.210724 -0.16878 0.97661 0.133216 -0.146173 0.982435 0.115995 -0.189663 0.979351 0.0700003 -0.187338 0.979779 0.0702665 -0.553643 0.826084 0.105189 -0.548244 0.82954 0.106258 -0.828471 0.546222 0.123601 -0.822534 0.554587 0.125977 -0.991327 0.0586679 0.1176 -0.951174 0.196384 0.238119 -0.986213 -0.0300138 -0.162735 -0.188279 0.982112 0.00264675 -0.186284 0.982489 0.00361499 -0.548548 0.831782 -0.0850535 -0.544123 0.834944 -0.082454 -0.818852 0.551645 -0.158648 -0.814347 0.559367 -0.15475 -0.957632 0.201233 -0.206025 -0.979053 0.18947 0.0745439 -0.164153 0.984566 -0.0606991 -0.162889 0.984853 -0.0594268 -0.479469 0.836989 -0.26374 -0.47676 0.839525 -0.260572 -0.714988 0.556857 -0.422731 -0.712552 0.563076 -0.418587 -0.836025 0.191894 -0.514041 -0.83599 0.201973 -0.510222 -0.0113559 0.829357 0.558603 -0.00836966 0.686622 0.726967 -0.0253215 0.249659 0.968003 0.0211043 0.935189 0.353519 0.0187561 0.958055 0.285968 0.0120372 0.944015 0.329682 0.00870478 0.944088 0.329579 0.0107761 0.952423 0.304587 -0.00962819 0.675046 0.737713 -0.00302436 0.674901 0.737902 -0.00430204 0.663779 0.747916 0.00818017 0.663297 0.748312 0.00702295 0.653659 0.756757 -0.001436 0.931762 0.363067 -0.00125478 0.928047 0.372462 0.0509176 0.925823 0.374512 0.0376365 0.966533 0.253766 0.0304528 0.941903 0.334502 0.0264021 0.93499 0.35369 -0.0141761 0.747886 0.663676 -0.0153303 0.619137 0.785133 -0.0168083 0.654794 0.755621 -0.0241819 0.470155 0.882253 -0.0263389 0.348736 0.936851 -0.0256965 0.244587 0.969287 -0.0233238 0.244541 0.969359 -0.0237272 0.239604 0.970581 -0.0192509 0.239431 0.970723 -0.0196261 0.235284 0.971729 -0.0248952 0.2356 0.971531 -0.0303124 0.133241 0.99062 -0.426008 0.811199 0.400591 -0.341145 0.901991 0.264637 -0.124833 0.980682 0.150598 0.00581304 0.999191 0.0397839 -0.583388 0.64501 0.49358 -0.751772 0.214698 0.623493 -0.677224 0.428385 0.598209 -0.648827 0.495688 0.577336 -0.190768 0.959709 0.206315 -0.121231 0.956431 0.265597 -0.121436 0.956355 0.265779 -0.0322009 0.9533 0.300303 -0.0335942 0.952447 0.302847 -0.531717 0.69611 0.482398 -0.352558 0.687678 0.634667 -0.349744 0.690764 0.632871 -0.125973 0.683092 0.719386 -0.125007 0.684579 0.71814 -0.758814 0.0232205 0.650893 -0.733873 0.256357 0.629056 -0.534938 0.249049 0.807351 -0.504282 0.143553 0.851524 -0.391442 0.253332 0.884645 -0.186971 0.243582 0.951688 -0.184117 0.25026 0.950511 0.0554186 -0.997877 -0.0342137 0.477397 -0.648652 -0.592742 0.369976 -0.811703 -0.451946 0.616074 -0.0880275 -0.782754 0.595451 -0.241698 -0.766173 0.320062 -0.882858 -0.34369 0.405074 -0.773283 -0.4878 0.504817 -0.59933 -0.62126 0.122533 -0.983546 -0.13275 0.123374 -0.98353 -0.132089 0.122373 -0.983849 -0.13064 0.123848 -0.983817 -0.129482 0.122871 -0.984125 -0.128066 0.124899 -0.984075 -0.126474 0.123285 -0.984563 -0.124243 0.133579 -0.984209 -0.116148 0.176276 -0.965972 -0.189275 0.34993 -0.839738 -0.415197 0.348657 -0.839774 -0.416195 0.349618 -0.838692 -0.417568 0.347878 -0.838734 -0.418935 0.348457 -0.838057 -0.419807 0.34719 -0.838084 -0.420802 0.34779 -0.837382 -0.421703 0.330701 -0.837521 -0.434967 0.171063 -0.973585 -0.151226 0.526339 -0.562946 -0.637228 0.51929 -0.563164 -0.642794 0.51967 -0.56214 -0.643383 0.518499 -0.562168 -0.644303 0.518716 -0.561551 -0.644666 0.517865 -0.56157 -0.645334 0.518096 -0.560915 -0.645718 0.51765 -0.560923 -0.646068 0.503629 -0.485963 -0.714281 0.608739 -0.198008 -0.768264 0.608421 -0.198017 -0.768514 0.608448 -0.197684 -0.768578 0.608033 -0.197694 -0.768903 0.60805 -0.197432 -0.768957 0.607751 -0.197438 -0.769193 0.607764 -0.19723 -0.769235 0.584486 -0.197581 -0.78698 0.595533 -0.282667 -0.751957 0.158118 -0.97693 -0.143552 0.161411 -0.974015 -0.158875 0.399326 -0.810574 -0.428378 0.380886 -0.82416 -0.419149 0.491541 -0.648282 -0.581479 0.551374 -0.548032 -0.629006 0.557702 -0.48557 -0.673194 0.601395 -0.282551 -0.747322 0.621926 -0.191845 -0.759212 0.629699 -0.191071 -0.752975 0.618173 -0.0879883 -0.781102 0.223371 -0.965899 -0.130941 0.216193 -0.971421 -0.0979861 0.423043 -0.808524 -0.409053 0.420611 -0.820172 -0.38782 0.530263 -0.627656 -0.569973 0.545294 -0.548616 -0.633778 0.584186 -0.470662 -0.661214 0.62056 -0.187775 -0.761344 0.0763389 -0.991783 -0.10266 0.0302861 -0.998087 -0.0539035 0.15912 -0.966234 -0.202662 0.287227 -0.883755 -0.36943 0.313098 -0.857522 -0.408198 0.391109 -0.773564 -0.498631 0.501669 -0.57971 -0.642078 0.490753 -0.599639 -0.632135 0.60791 -0.2048 -0.767139 0.598986 -0.241604 -0.763442 0.591652 -0.215705 -0.776801 0.592753 -0.204256 -0.779053 0.459772 -0.606696 -0.648483 0.47086 -0.578493 -0.666061 0.242464 -0.884299 -0.399032 0.269716 -0.855543 -0.441927 -0.0192958 -0.996988 -0.0751154 0.0229206 -0.989241 -0.144487 -0.420791 -0.11921 -0.899291 -0.950562 -0.227564 -0.211297 -0.952144 -0.225102 -0.206763 -0.755737 -0.629127 -0.181828 -0.757227 -0.628059 -0.179301 -0.409747 -0.904783 -0.116079 -0.410167 -0.904659 -0.115563 0.0188761 -0.999454 -0.0271215 0.0199816 -0.999402 -0.0282145 0.444546 -0.89323 0.0672287 0.446908 -0.892212 0.065048 -0.868649 -0.242378 -0.432091 -0.890049 -0.21041 -0.404402 -0.664575 -0.620305 -0.416607 -0.687005 -0.60453 -0.403197 -0.337535 -0.883581 -0.324584 -0.350354 -0.879955 -0.320827 0.0549723 -0.983534 -0.172159 0.0579636 -0.983305 -0.172489 0.441115 -0.89736 0.0127584 0.458915 -0.888389 0.0127384 0.470546 -0.881604 -0.0368836 0.435825 -0.898044 -0.0597802 0.152844 -0.928785 -0.337634 0.150796 -0.92881 -0.338485 -0.190011 -0.799763 -0.569452 -0.153376 -0.811778 -0.563464 -0.495402 -0.52641 -0.690992 -0.4293 -0.569281 -0.701157 -0.664409 -0.256072 -0.70213 -0.704194 0.0146971 -0.709856 -0.758755 -0.181781 -0.625497 -0.228573 -0.163561 -0.959689 -0.416229 -0.148289 -0.897086 -0.149202 -0.50689 -0.849 -0.225906 -0.456819 -0.860397 0.0513056 -0.739945 -0.670708 0.0108042 -0.722329 -0.691465 0.249502 -0.878576 -0.40725 0.245026 -0.878001 -0.41119 0.418804 -0.903459 -0.0914605 0.440214 -0.895671 -0.0631305 0.382592 -0.920441 -0.0800759 0.377627 -0.921344 -0.0923225 0.300826 -0.854492 -0.423494 0.310731 -0.858488 -0.407976 0.179187 -0.679652 -0.711312 0.212506 -0.702454 -0.679264 0.0330763 -0.420499 -0.90669 0.0946837 -0.471037 -0.877017 -0.119605 -0.111421 -0.98655 0.208382 0.0708326 -0.975479 0.141099 -0.126952 -0.981822 -0.0294785 -0.189863 -0.981368 0.522888 -0.479167 -0.704974 0.498054 -0.402922 -0.767852 0.479052 -0.634208 -0.606868 0.478717 -0.65127 -0.588793 0.398403 -0.811578 -0.427337 0.390949 -0.846311 -0.361824 0.262627 -0.959668 -0.100323 0.262447 -0.959815 -0.0993826 0.318916 -0.943178 -0.0933169 0.32054 -0.943932 -0.0790369 0.341137 -0.847123 -0.407442 0.349588 -0.857917 -0.376519 0.325235 -0.660152 -0.677069 0.346218 -0.688843 -0.636889 0.272924 -0.404114 -0.873043 0.311522 -0.454159 -0.834682 0.219061 -0.184703 -0.958069 0.468094 -0.118625 -0.87568 0.518126 -0.203119 -0.830836 0.958436 -0.225073 -0.175335 0.687456 -0.208748 -0.695578 0.690875 -0.228335 -0.68597 0.529369 -0.608014 -0.591682 0.5288 -0.612708 -0.587333 0.265078 -0.890268 -0.370346 0.267603 -0.886215 -0.378168 -0.0548799 -0.995824 -0.0729572 -0.0459972 -0.994304 -0.0961416 0.869404 -0.224356 -0.440227 0.869545 -0.231252 -0.436365 0.687899 -0.627227 -0.365215 0.688209 -0.6265 -0.365877 0.364539 -0.906005 -0.215098 0.369933 -0.902044 -0.222411 -0.03854 -0.999088 -0.0183609 -0.0261936 -0.999118 -0.0328073 0.973501 -0.228668 0.00273836 0.980918 -0.153689 -0.119079 0.772514 -0.632029 -0.0613285 0.77747 -0.625337 -0.0670433 0.42365 -0.90581 -0.00531655 0.426888 -0.904273 -0.00762473 -0.0152943 -0.998481 0.0529399 -0.016738 -0.998415 0.0537412 0.939839 -0.234406 0.24851 0.951775 -0.204659 0.228559 0.747396 -0.614857 0.251695 0.759124 -0.603315 0.244422 0.41555 -0.885056 0.209749 0.414179 -0.885603 0.210148 0.0020955 -0.991617 0.129196 -0.0187805 -0.991071 0.132006 0.799653 -0.223496 0.557319 0.822386 -0.186125 0.537624 0.626355 -0.587264 0.51264 0.643364 -0.57221 0.508585 0.346422 -0.855979 0.383786 0.345155 -0.856522 0.383717 0.00454815 -0.98174 0.190174 -0.0203891 -0.982609 0.184565 -0.968981 -0.228096 -0.0951256 0.474812 -0.877981 0.0608514 -0.972407 -0.23054 -0.0357289 -0.972257 -0.231156 -0.0358239 -0.765861 -0.642706 -0.0196726 -0.764816 -0.643942 -0.0198932 -0.396338 -0.918104 0.000591308 -0.393936 -0.919138 0.000248502 0.0575232 -0.998128 0.0207672 0.0611211 -0.997924 0.0202788 0.499141 -0.865748 0.036581 0.503115 -0.863474 0.0359004 -0.971737 -0.227274 -0.0638331 -0.97086 -0.231007 -0.0637755 -0.770844 -0.635753 -0.0402319 -0.764837 -0.642989 -0.0398579 -0.409684 -0.91219 -0.00824937 -0.395965 -0.918235 -0.00747918 0.0367009 -0.999002 0.0254781 0.0572671 -0.998008 0.0264537 0.372012 -0.927008 0.0475764 0.498618 -0.865504 0.0477843 0.473454 -0.877608 0.0751373 0.457824 -0.885963 0.0739354 0.0364314 -0.998934 0.0283335 0.022497 -0.999381 0.0270552 -0.408158 -0.912585 -0.0243951 -0.417417 -0.908362 -0.0253331 -0.767855 -0.636557 -0.0720741 -0.771929 -0.631559 -0.0725198 -0.993405 -0.0205789 -0.112798 -0.967571 -0.225855 -0.113121 -0.965074 -0.224453 -0.135105 -0.96464 -0.226343 -0.135048 -0.771538 -0.628376 -0.0993622 -0.76848 -0.632177 -0.0989507 -0.422242 -0.905436 -0.0435525 -0.415146 -0.908755 -0.042629 0.0123298 -0.999702 0.0210668 0.0231087 -0.999482 0.0223937 0.444424 -0.892106 0.0814531 0.456667 -0.885775 0.0828141 0.730385 -0.191615 0.655607 0.719997 -0.364023 0.59084 0.633806 -0.547216 0.546667 0.685051 -0.362908 0.631666 0.460242 -0.773679 0.435429 0.40287 -0.82089 0.404767 0.313485 -0.897367 0.310581 0.141431 -0.975131 0.170639 0.129124 -0.979698 0.153357 0.0415268 -0.988122 0.147954 0.111973 -0.972656 0.203475 0.337153 -0.854538 0.395085 0.382383 -0.819311 0.427215 0.576973 -0.578137 0.57694 0.596913 -0.545484 0.588338 0.720546 -0.204248 0.662643 0.723715 -0.191288 0.663058 -0.326397 -0.184654 0.927021 0.0567363 -0.158956 0.985654 0.610154 -0.63337 0.475977 0.291248 -0.946512 0.138891 0.304904 -0.942325 0.138048 0.43777 -0.850643 0.291143 0.499327 -0.814404 0.295667 0.517964 -0.770214 0.372133 0.598695 -0.641493 0.479636 0.731538 -0.13284 0.668735 0.723189 -0.142182 0.675857 0.697583 -0.398496 0.595465 0.738294 -0.358946 0.571035 0.666456 -0.489446 0.562387 0.583805 -0.0933938 0.806505 0.576743 -0.156158 0.801862 0.587628 -0.361061 0.724106 0.572134 -0.415688 0.707012 0.545212 -0.602448 0.582924 0.522938 -0.6454 0.556771 0.458875 -0.796781 0.393158 0.431834 -0.826231 0.361747 0.335051 -0.926711 0.17014 0.305582 -0.942203 0.137384 0.362606 -0.918554 0.157399 0.372675 -0.908776 0.18772 0.389257 -0.817018 0.425395 0.399439 -0.787356 0.469594 0.383297 -0.648694 0.65748 0.388678 -0.592115 0.705925 0.34584 -0.429334 0.834306 0.342324 -0.34359 0.874506 0.240332 -0.0784568 0.967515 0.227045 -0.0614789 0.971942 0.426924 -0.141483 0.893151 -0.176453 -0.094477 0.979764 -0.190613 -0.00938233 0.981621 0.0438786 -0.351206 0.935269 0.0838323 -0.454653 0.886714 0.199518 -0.607196 0.769094 0.2218 -0.664141 0.713948 0.332921 -0.793555 0.509347 0.340137 -0.813089 0.472432 0.426505 -0.884966 0.186894 0.426567 -0.885289 0.185213 -0.52472 -0.134253 0.840622 -0.507352 -0.0698858 0.858901 -0.23652 -0.396047 0.887246 -0.184198 -0.489441 0.85236 0.0139672 -0.655859 0.754754 0.0472112 -0.699683 0.712892 0.264965 -0.819746 0.50775 0.274976 -0.828566 0.487716 0.477017 -0.859816 0.18213 0.470931 -0.858371 0.203527 -0.715469 -0.113539 0.689357 -0.671473 -0.250199 0.697513 -0.486637 -0.46307 0.740778 -0.434144 -0.5473 0.71553 -0.168873 -0.731923 0.660129 -0.131548 -0.766677 0.628412 0.18453 -0.869839 0.457524 0.193771 -0.873715 0.446178 0.507448 -0.845336 0.167044 0.492261 -0.848266 0.195252 -0.881203 -0.17261 0.4401 -0.869283 -0.254896 0.423527 -0.662067 -0.5556 0.502968 -0.636695 -0.604686 0.478513 -0.310125 -0.828443 0.466374 -0.288895 -0.847234 0.445797 0.108841 -0.935675 0.335658 0.114137 -0.937099 0.329876 0.510322 -0.849252 0.135432 0.498909 -0.853291 0.151605 -0.963654 -0.224401 0.144969 -0.957351 -0.258898 0.128264 -0.756952 -0.627508 0.182366 -0.743394 -0.647559 0.167431 -0.394185 -0.900798 0.182159 -0.38173 -0.908148 0.171897 0.0560515 -0.988003 0.143901 0.0607529 -0.988227 0.140419 0.501216 -0.862041 0.0752883 0.49632 -0.864515 0.0792462 0.312521 -0.897326 0.311668 0.1344 -0.979902 0.147406 0.683882 -0.362854 0.632963 0.689975 -0.3631 0.626173 0.539162 -0.673742 0.505347 0.647393 -0.478065 0.59358 0.390378 -0.838618 0.379901 0.0376079 -0.99661 0.073166 0.194694 -0.958223 0.20953 0.194205 -0.958202 0.210081 0.195677 -0.957641 0.21127 0.195308 -0.957624 0.211685 0.196749 -0.957064 0.212879 0.188902 -0.956645 0.221692 0.225307 -0.944858 0.237655 0.51911 -0.693318 0.499836 0.524807 -0.693599 0.493455 0.52415 -0.694458 0.492945 0.524412 -0.69447 0.492649 0.523758 -0.695311 0.492159 0.527486 -0.695464 0.487942 0.458938 -0.773624 0.4369 0.712647 -0.25324 0.65422 0.718555 -0.253506 0.647621 0.718649 -0.253116 0.647669 0.718556 -0.253111 0.647775 0.71864 -0.252749 0.647823 0.715923 -0.252624 0.650873 0.721136 -0.240934 0.649549 0.058529 -0.997056 0.049544 0.245976 -0.94533 0.214121 0.261894 -0.939175 0.222176 0.407907 -0.839111 0.359867 0.657417 -0.478469 0.582126 0.72622 -0.241709 0.64357 0.726216 -0.241156 0.643781 0.269338 -0.949108 0.16325 0.2894 -0.937907 0.191253 0.42828 -0.851822 0.301621 0.507361 -0.77155 0.38379 0.590554 -0.642444 0.488376 0.580338 -0.667566 0.466437 0.557791 -0.668642 0.49172 0.555349 -0.674274 0.486766 0.746843 -0.138813 0.65035 0.725447 -0.241745 0.644427 0.711907 -0.36305 0.601152 0.674158 -0.488432 0.554027 0.0305301 -0.171102 -0.98478 -0.331676 -0.854111 -0.400606 -0.305226 -0.876763 -0.37165 -0.200451 -0.96809 -0.150401 -0.16902 -0.978929 -0.114588 -0.509914 -0.124113 -0.851225 -0.500948 -0.158238 -0.850889 -0.493183 -0.410315 -0.767081 -0.478578 -0.444525 -0.757206 -0.43224 -0.661692 -0.612643 -0.448797 -0.635449 -0.62832 -0.390963 -0.745174 -0.540244 -0.233156 -0.962602 -0.137974 -0.243638 -0.955348 -0.167186 -0.264073 -0.865141 -0.426375 -0.274939 -0.843936 -0.460631 -0.269713 -0.68745 -0.67429 -0.279439 -0.649196 -0.707431 -0.249929 -0.448149 -0.858311 -0.257306 -0.392517 -0.88302 -0.191174 -0.107222 -0.975682 -0.111456 0.0162414 -0.993637 -0.322075 -0.155844 -0.933799 0.226624 -0.125398 -0.965876 0.20357 -0.0166043 -0.97892 0.0180402 -0.392642 -0.919515 0.00372028 -0.4662 -0.884671 -0.106325 -0.657435 -0.745972 -0.114612 -0.696033 -0.708803 -0.219731 -0.847503 -0.483174 -0.222169 -0.859083 -0.461104 -0.307601 -0.937602 -0.162126 -0.307556 -0.936817 -0.16668 0.465032 -0.0990039 -0.87974 0.435521 -0.217042 -0.873621 0.28695 -0.425865 -0.858079 0.257526 -0.49859 -0.827701 0.066449 -0.695747 -0.715206 0.0483381 -0.72585 -0.686153 -0.16604 -0.868083 -0.467828 -0.168125 -0.870216 -0.463096 -0.37547 -0.914491 -0.150759 -0.365758 -0.912186 -0.184764 -0.399475 -0.900476 -0.171939 -0.417407 -0.898578 -0.135388 -0.104635 -0.904463 -0.413519 -0.106571 -0.905554 -0.410626 0.203627 -0.777791 -0.594623 0.220064 -0.757825 -0.614226 0.480839 -0.541659 -0.689492 0.506364 -0.4844 -0.713409 0.689212 -0.231452 -0.686598 0.903805 -0.15582 -0.398568 0.811058 -0.202216 -0.548903 0.706979 -0.132644 -0.694684 0.771659 -0.611362 -0.17544 0.762785 -0.625135 -0.165426 0.432628 -0.887177 -0.16047 0.426382 -0.891101 -0.155366 0.00532591 -0.993443 -0.114203 0.00689418 -0.993304 -0.115326 -0.429047 -0.902151 -0.0451867 -0.418873 -0.906509 -0.0527841 -0.413644 -0.901216 -0.129263 -0.433061 -0.89544 -0.103177 -0.0409753 -0.952014 -0.3033 -0.0443165 -0.953034 -0.299605 0.3359 -0.840666 -0.424796 0.348633 -0.828624 -0.437993 0.65392 -0.590102 -0.473464 0.672369 -0.551286 -0.493967 0.885896 -0.182551 -0.426454 0.958725 -0.24512 -0.144095 0.963025 -0.219023 -0.156882 -0.136355 -0.981153 -0.136918 -0.139259 -0.980485 -0.138768 -0.326949 -0.876057 -0.354441 -0.355237 -0.832571 -0.425009 -0.628274 -0.152082 -0.762983 -0.614089 -0.195483 -0.764644 -0.583901 -0.441572 -0.681229 -0.522788 -0.556588 -0.64568 -0.500775 -0.63413 -0.589155 -0.43916 -0.744144 -0.503378 0.975184 -0.221207 0.00910653 0.974985 -0.222083 0.00916293 0.78413 -0.620515 0.0101147 0.782625 -0.622409 0.0102555 0.439397 -0.898246 0.00913177 0.435864 -0.899964 0.0093426 0.00855649 -0.999943 0.00634084 0.00310709 -0.999973 0.00661314 -0.423946 -0.905685 0.00228105 -0.430249 -0.902706 0.00261441 0.975424 -0.218764 -0.0262664 0.974807 -0.221515 -0.0261244 0.787827 -0.61576 -0.0129584 0.783965 -0.620678 -0.0125893 0.44804 -0.894009 0.00284646 0.439375 -0.898297 0.00343703 0.0216497 -0.999602 0.018085 0.00859452 -0.999786 0.0188166 -0.408852 -0.912114 0.0298003 -0.423791 -0.905245 0.0305377 0.972512 -0.217649 -0.0827555 0.971943 -0.220257 -0.0825423 0.787769 -0.613691 -0.0529424 0.785372 -0.616793 -0.0525086 0.451701 -0.892075 -0.0129609 0.447102 -0.894398 -0.0123136 0.028761 -0.999151 0.0295084 0.0223989 -0.99929 0.0302823 -0.399656 -0.914265 0.0662864 -0.406578 -0.911153 0.0670414 -0.12462 -0.982589 -0.137803 -0.487237 -0.646562 -0.586991 -0.37683 -0.810068 -0.449209 -0.355399 -0.835248 -0.419587 -0.269502 -0.909576 -0.316291 -0.123464 -0.982957 -0.136206 -0.560811 -0.483795 -0.671888 -0.528548 -0.558995 -0.638875 -0.608646 -0.283103 -0.741217 -0.623651 -0.196404 -0.756627 -0.630582 -0.0888019 -0.771026 -0.621216 -0.195822 -0.758778 -0.621128 -0.196433 -0.758692 -0.528025 -0.557425 -0.640677 -0.527318 -0.559008 -0.639879 -0.353827 -0.833541 -0.424282 -0.352097 -0.835287 -0.422284 -0.125364 -0.981779 -0.142809 -0.122522 -0.982611 -0.139515 -0.620788 -0.195467 -0.75922 -0.620728 -0.195826 -0.759176 -0.527043 -0.55658 -0.642219 -0.526638 -0.557434 -0.641809 -0.352742 -0.832586 -0.427051 -0.351747 -0.833555 -0.425981 -0.124529 -0.981325 -0.146606 -0.122898 -0.981796 -0.144823 -0.39637 -0.913387 0.0928142 0.0319372 -0.997985 0.0548214 0.788649 -0.613233 -0.0444739 0.921249 -0.178794 0.345446 0.963044 -0.237192 0.127618 0.974259 -0.204103 0.0957161 0.972427 -0.219948 -0.0775152 0.972118 -0.217826 -0.0868221 0.895224 0.00945911 0.445517 0.862325 -0.244383 0.443478 0.708254 -0.128537 0.694158 0.70968 -0.109428 0.695974 0.557968 -0.168595 0.812556 0.441475 -0.112071 0.890247 0.369555 -0.185789 0.910446 0.140675 -0.109307 0.984003 0.0885462 -0.172697 0.980987 -0.396062 -0.913638 0.0916557 -0.392228 -0.908973 0.141154 -0.371382 -0.918648 0.134762 -0.383839 -0.903183 0.192167 -0.32974 -0.921473 0.205326 -0.333856 -0.918581 0.211542 -0.294473 -0.925928 0.236521 -0.27128 -0.937232 0.219097 -0.258894 -0.937429 0.232808 -0.224553 -0.94895 0.221515 -0.228009 -0.949767 0.214368 -0.201934 -0.955615 0.214531 -0.205166 -0.959975 0.190672 0.788135 -0.614357 -0.037532 0.791209 -0.590691 0.158345 0.774955 -0.60682 0.176676 0.70409 -0.518523 0.485172 0.655924 -0.556122 0.510385 0.516227 -0.454673 0.725798 0.455236 -0.499317 0.737186 0.291479 -0.418649 0.8601 0.235922 -0.465468 0.853042 0.0449262 -0.401302 0.914843 0.00546914 -0.446229 0.894902 -0.214177 -0.397285 0.892352 -0.234186 -0.434814 0.869536 -0.131108 -0.125013 0.983454 -0.159808 -0.0343262 0.986551 -0.286771 -0.152091 0.945849 -0.200265 -0.960669 0.192378 -0.194708 -0.966834 0.165291 -0.293078 -0.879376 0.375238 0.0316959 -0.997937 0.0558397 0.0405212 -0.982272 0.183031 0.0459904 -0.98247 0.180657 0.00653687 -0.931502 0.363678 0.0229128 -0.930864 0.364648 -0.0414283 -0.885464 0.462857 -0.035399 -0.884472 0.465249 -0.086889 -0.859307 0.504026 -0.0955201 -0.862347 0.497226 -0.147299 -0.844931 0.514194 -0.160836 -0.854378 0.494136 -0.227636 -0.83937 0.493598 -0.234821 -0.853345 0.465469 -0.333017 -0.838819 0.430676 -0.349756 -0.800821 0.486164 -0.41085 -0.649268 0.640042 -0.244638 -0.672516 0.698481 -0.231738 -0.646768 0.726629 -0.0802609 -0.680721 0.728133 -0.0542936 -0.655336 0.753384 0.0755818 -0.699057 0.71106 0.108437 -0.678499 0.726553 0.225146 -0.735804 0.638672 0.25645 -0.721619 0.643039 0.368176 -0.801597 0.471051 0.391299 -0.792891 0.467129 0.45145 -0.870633 0.195425 0.46076 -0.867113 0.189248 0.453262 -0.891322 0.00989704 0.453908 -0.891029 0.00597304 -0.490352 -0.152641 0.858054 -0.480059 -0.124028 0.868424 -0.475443 -0.384155 0.791441 -0.477335 -0.400395 0.782199 -0.449972 -0.513774 0.730453 -0.411706 -0.669747 0.61801 -0.62863 -0.0888278 -0.772615 -0.603954 -0.203919 -0.770491 -0.601324 -0.283189 -0.747137 -0.547332 -0.48394 -0.68281 -0.494844 -0.579028 -0.647963 -0.471024 -0.646632 -0.600003 -0.361444 -0.810106 -0.461612 -0.302151 -0.857051 -0.417335 -0.247531 -0.909491 -0.333999 -0.0726073 -0.991758 -0.105569 -0.0934929 -0.982599 -0.160493 0.0211416 -0.993775 -0.109381 -0.0261819 -0.989298 -0.143541 -0.24535 -0.874547 -0.418295 -0.27723 -0.855378 -0.437575 -0.466749 -0.597176 -0.652324 -0.482328 -0.578194 -0.658066 -0.603333 -0.211771 -0.768858 -0.606757 -0.204097 -0.768239 -0.598131 -0.241153 0.764254 -0.452804 -0.675805 0.581599 -0.448727 -0.686359 0.572325 -0.0383283 -0.997534 0.0588043 -0.187914 -0.952321 0.240361 -0.195874 -0.9468 0.255348 -0.329775 -0.841307 0.428312 -0.614671 -0.145872 0.775178 -0.59512 -0.249516 0.76392 -0.598068 -0.249476 0.761628 -0.539142 -0.480883 0.691431 -0.468437 -0.66863 0.577495 -0.461906 -0.686161 0.561984 -0.544154 -0.511315 0.665172 -0.580437 -0.38049 0.719945 -0.177407 -0.967765 0.178769 -0.205092 -0.952082 0.226887 -0.318183 -0.878564 0.356209 -0.390698 -0.79976 0.455784 -0.919624 -0.226176 -0.321148 -0.0239115 -0.980122 0.196951 -0.286101 -0.839481 0.461971 -0.502561 -0.565884 0.653612 -0.6397 -0.203427 0.741216 -0.6335 -0.192793 0.749339 -0.787205 -0.217984 0.576881 -0.786819 -0.187226 0.588101 -0.929129 -0.232149 0.287794 -0.93184 -0.205625 0.298985 -0.0237254 -0.984136 0.175823 -0.016386 -0.982913 0.183341 0.00963685 -0.989297 0.145597 0.00108291 -0.991856 0.127359 0.0273602 -0.99396 0.106282 0.0206789 -0.998629 0.0480801 0.0283074 -0.998573 0.0452912 -0.286987 -0.844151 0.452821 -0.348681 -0.853067 0.3882 -0.339513 -0.862954 0.374222 -0.408111 -0.884157 0.2274 -0.39971 -0.889803 0.220189 -0.422197 -0.906268 0.0206928 -0.421235 -0.906725 0.0202649 -0.502128 -0.564742 0.65493 -0.61993 -0.581615 0.526698 -0.621767 -0.57614 0.530536 -0.737435 -0.612715 0.284202 -0.741035 -0.606379 0.288394 -0.774921 -0.631968 -0.0107072 -0.778212 -0.627945 -0.00839704 -0.97363 -0.224444 -0.0408671 -0.985581 -0.139931 -0.0951266 -0.970151 -0.227552 0.0838237 -0.846833 -0.225872 -0.481515 -0.91372 -0.158256 -0.374261 -0.711617 -0.627035 -0.316906 -0.710709 -0.627905 -0.317219 -0.384823 -0.902129 -0.19513 -0.37392 -0.90648 -0.196158 0.0228424 -0.999195 -0.0329764 0.0452749 -0.998443 -0.0325854 -0.712335 -0.225374 -0.664669 -0.724445 -0.20618 -0.657776 -0.555592 -0.604777 -0.570581 -0.556439 -0.604016 -0.570562 -0.297023 -0.878647 -0.37384 -0.278274 -0.886734 -0.369142 0.0187431 -0.994037 -0.107416 0.0586364 -0.994105 -0.0911985 -0.319149 -0.841083 0.436718 -0.0258127 -0.997308 0.0686366 -0.417281 -0.674492 0.609046 -0.59504 -0.241068 0.76669 -0.490698 -0.590747 0.640495 -0.597395 -0.24117 0.764824 -0.150828 -0.966376 0.208253 -0.269158 -0.891463 0.364482 -0.322429 -0.84268 0.431196 -0.0287145 -0.997738 0.0607895 -0.593891 -0.255818 0.762791 -0.593515 -0.255811 0.763086 -0.593556 -0.255457 0.763173 -0.592954 -0.255443 0.763645 -0.593048 -0.254812 0.763783 -0.58142 -0.254461 0.772787 -0.53305 -0.480727 0.696247 -0.429801 -0.698225 0.572497 -0.430931 -0.698256 0.57161 -0.430117 -0.699663 0.570501 -0.431761 -0.699701 0.569211 -0.431374 -0.700422 0.568617 -0.434307 -0.700478 0.566311 -0.395254 -0.766255 0.506584 -0.160284 -0.961752 0.222132 -0.156296 -0.961679 0.225265 -0.15721 -0.961212 0.226619 -0.154969 -0.96116 0.228377 -0.156851 -0.960241 0.230945 -0.155297 -0.960199 0.232165 -0.144352 -0.94441 0.295385 -0.0576052 -0.983689 0.170404 -0.239802 -0.890303 0.387113 -0.120623 -0.965263 0.231769 0.0318429 -0.993634 0.108062 -0.283612 -0.840954 0.460826 -0.284743 -0.839344 0.463058 -0.365474 -0.765438 0.529654 -0.482618 -0.563922 0.670128 -0.461454 -0.589806 0.662713 -0.610992 -0.200224 0.765897 -0.588984 -0.241009 0.77137 0.176398 -0.9673 -0.182248 0.0673701 -0.995418 -0.0678506 0.351958 -0.869761 -0.345894 0.690568 -0.305363 -0.655644 0.61457 -0.526291 -0.58764 0.726517 -0.0506903 -0.685276 0.575006 -0.757688 -0.30867 0.57669 -0.607782 -0.545921 0.635953 -0.483809 -0.601243 0.321356 -0.895946 -0.306611 0.386957 -0.845381 -0.368233 0.185569 -0.963579 -0.192562 0.188198 -0.963622 -0.189772 0.186641 -0.964259 -0.188069 0.189012 -0.964285 -0.185551 0.186575 -0.965244 -0.183013 0.251415 -0.961317 -0.112514 0.252149 -0.955865 -0.150806 0.548023 -0.705269 -0.449741 0.512816 -0.706008 -0.488439 0.513867 -0.704461 -0.489566 0.512119 -0.704442 -0.491423 0.512787 -0.703422 -0.492186 0.509605 -0.703368 -0.495557 0.493728 -0.726994 -0.477192 0.698632 -0.257089 -0.667697 0.701725 -0.25714 -0.664425 0.701655 -0.257617 -0.664315 0.702296 -0.257624 -0.663634 0.702183 -0.25832 -0.663483 0.719966 -0.258319 -0.644143 0.705828 -0.241278 -0.666027 0.214893 -0.966439 -0.140774 0.187599 -0.960846 -0.203914 0.726689 -0.050692 -0.685093 0.781635 -0.304092 -0.544586 0.501171 -0.147785 -0.852635 0.663436 -0.401396 -0.631454 0.616646 -0.52633 -0.585427 0.573345 -0.697147 -0.430421 0.49114 -0.726942 -0.479935 0.355105 -0.869807 -0.342544 0.0408838 -0.994555 -0.095862 0.0710107 -0.987697 -0.13933 0.188008 -0.957292 -0.219647 0.298906 -0.895372 -0.330098 0.354491 -0.844309 -0.401845 0.350431 -0.848916 -0.395651 0.448139 -0.768333 -0.456986 0.560385 -0.607541 -0.562906 0.572188 -0.571638 -0.588074 0.622112 -0.483652 -0.615676 0.719914 -0.203008 -0.663711 0.700446 -0.241247 -0.671696 0.697583 -0.208043 -0.685635 0.697263 -0.200802 -0.688116 0.549146 -0.588017 -0.593864 0.553789 -0.569678 -0.607276 0.305221 -0.86514 -0.397961 0.319365 -0.845378 -0.428186 0.00891712 -0.991226 -0.131876 0.031961 -0.983036 -0.180604 -0.352209 -0.473544 -0.807283 -0.0983096 -0.742645 -0.66243 0.416554 -0.90911 0.00111534 -0.404059 -0.878649 -0.254385 -0.39366 -0.882309 -0.257997 -0.73248 -0.602381 -0.317192 -0.715935 -0.616282 -0.328076 -0.92366 -0.212725 -0.318749 -0.766749 -0.0104881 -0.641861 -0.806922 -0.183976 -0.561275 -0.909502 -0.239813 -0.339551 -0.0667265 -0.756033 -0.651124 0.0685257 -0.693619 -0.717075 0.0958429 -0.710662 -0.696975 0.210225 -0.67008 -0.711898 0.229356 -0.691181 -0.685321 -0.286486 -0.518022 -0.805965 -0.100841 -0.431633 -0.896395 -0.0452853 -0.476023 -0.878266 0.13351 -0.412408 -0.901163 0.169338 -0.45427 -0.874622 -0.270592 -0.817006 -0.509197 -0.246849 -0.824416 -0.509317 -0.578055 -0.543014 -0.609088 -0.531984 -0.572915 -0.623507 -0.753256 -0.244041 -0.610778 -0.553143 -0.133152 -0.822377 -0.465916 -0.213483 -0.858689 -0.259542 -0.117003 -0.958618 -0.177866 -0.190572 -0.965425 0.0408724 -0.112906 -0.992765 0.0957552 -0.175294 -0.979848 0.300818 -0.127257 -0.945153 0.438465 -0.154903 -0.885299 0.324611 -0.0521933 -0.944407 0.372416 -0.444655 -0.814609 0.357202 -0.409182 -0.839629 0.350825 -0.688265 -0.634991 0.343203 -0.663847 -0.664469 0.40336 -0.915039 0.00220013 0.432474 -0.899842 -0.0570218 0.399074 -0.914215 -0.0703639 0.413838 -0.906326 -0.0855055 0.379783 -0.917383 -0.119056 0.356162 -0.928198 -0.107687 0.340843 -0.930476 -0.134312 0.285591 -0.94989 -0.127066 0.284571 -0.949676 -0.130898 0.217732 -0.965492 -0.142895 0.216811 -0.969097 -0.117663 0.161688 -0.975765 -0.147445 0.183488 -0.960715 -0.208227 0.609742 -0.15232 -0.777826 0.604756 -0.13373 -0.785103 0.575209 -0.398059 -0.714621 0.574979 -0.419724 -0.702304 0.448647 -0.695679 -0.561022 0.449555 -0.677337 -0.582336 0.346742 -0.862716 -0.368091 0.297404 -0.86915 -0.395133 0.295198 -0.856005 -0.424398 0.269323 -0.862184 -0.429074 0.262786 -0.856583 -0.444082 0.229786 -0.868231 -0.439743 0.227761 -0.867547 -0.442139 0.165829 -0.895922 -0.412098 0.171282 -0.89655 -0.408486 0.0807557 -0.945643 -0.315021 0.0874325 -0.945528 -0.313581 0.00290455 -0.990005 -0.141004 0.00421822 -0.989967 -0.141234 0.971802 -0.232819 -0.0373773 0.7878 -0.196092 -0.583882 0.788754 -0.224604 -0.572207 0.613263 -0.59262 -0.522217 0.611956 -0.596703 -0.519091 0.317434 -0.877926 -0.358443 0.32676 -0.867979 -0.373952 -0.0439849 -0.991548 -0.122054 -0.018844 -0.9867 -0.161455 0.929003 -0.215485 -0.300865 0.927062 -0.236402 -0.290982 0.731691 -0.621727 -0.279435 0.729394 -0.625727 -0.276497 0.380438 -0.902934 -0.199942 0.388788 -0.897634 -0.207599 -0.0556987 -0.99546 -0.0771852 -0.0320719 -0.994761 -0.0970657 0.962742 -0.231486 0.139793 0.986633 -0.157416 0.0421282 0.769921 -0.637517 0.0281828 0.769048 -0.63854 0.0288476 0.406627 -0.913532 0.010682 0.406022 -0.913798 0.0109663 -0.0473908 -0.998832 -0.00937138 -0.0473092 -0.998836 -0.00940153 0.892322 -0.235663 0.384999 0.900595 -0.218539 0.375726 0.701389 -0.626606 0.339731 0.703944 -0.624257 0.338771 0.372691 -0.899305 0.228805 0.360003 -0.904125 0.230123 -0.0334723 -0.996847 0.0719464 -0.0644892 -0.995381 0.0711154 0.707415 -0.22403 0.670354 0.724232 -0.198285 0.660433 0.547679 -0.597389 0.585811 0.551824 -0.59372 0.585652 0.290162 -0.869625 0.399448 0.271689 -0.877643 0.394876 -0.0217737 -0.989707 0.141441 -0.0649276 -0.990229 0.123417 -0.961543 -0.222006 -0.161704 -0.961162 -0.223667 -0.161683 -0.771852 -0.622222 -0.130704 -0.768683 -0.626218 -0.130299 -0.430031 -0.899782 -0.073936 -0.422427 -0.903464 -0.0728624 -0.00344736 -0.999991 -0.00257945 0.00835283 -0.999965 -0.000869767 0.423806 -0.903098 0.069306 0.437467 -0.896406 0.0712674 -0.961326 -0.21978 -0.165981 -0.960823 -0.22196 -0.165991 -0.774101 -0.616889 -0.142179 -0.769995 -0.622106 -0.141745 -0.437251 -0.894736 -0.0908863 -0.427395 -0.899616 -0.0895782 -0.0158854 -0.999632 -0.0220074 -0.000545936 -0.999804 -0.0197833 0.408531 -0.91131 0.0511503 0.426406 -0.902926 0.0538715 -0.0182117 -0.990192 0.138521 0.24449 -0.864731 0.438708 0.604687 -0.201207 0.77063 0.601371 -0.208006 0.771418 0.478424 -0.570809 0.667299 0.0256944 -0.985415 0.168217 0.0618619 -0.9884 0.138701 0.104877 -0.980092 0.168584 0.25583 -0.895723 0.363637 0.298964 -0.849383 0.434936 0.274202 -0.847215 0.455018 0.463714 -0.587879 0.662848 0.615447 -0.194818 0.763722 0.612544 -0.201845 0.764231 0.556902 -0.441624 0.70344 0.493437 -0.572085 0.655163 0.484195 -0.60787 0.629324 0.367968 -0.792359 0.486587 -0.875772 -0.196893 0.440745 -0.490425 -0.185814 0.851444 0.153813 -0.976216 0.152787 0.131597 -0.98095 0.1429 0.444251 -0.681674 0.581345 0.430938 -0.69197 0.579198 0.313222 -0.868269 0.38471 0.393536 -0.822725 0.410187 0.27126 -0.900521 0.339824 0.577527 -0.146634 0.803095 0.572728 -0.153068 0.805328 0.53504 -0.433573 0.725083 0.568718 -0.396585 0.720612 0.502409 -0.531638 0.68187 0.3877 -0.120613 0.913861 0.379073 -0.155934 0.912134 0.384187 -0.4045 0.829928 0.37136 -0.439581 0.817839 0.347036 -0.654799 0.67142 0.329736 -0.685914 0.648688 0.278812 -0.847851 0.451014 0.257148 -0.870958 0.418697 0.185411 -0.964405 0.188536 0.159923 -0.975814 0.149036 0.0714109 -0.0962104 0.992796 0.0703023 -0.171286 0.98271 0.133772 -0.386506 0.912534 0.131293 -0.444917 0.885896 0.184676 -0.64258 0.74363 0.180662 -0.681829 0.708852 0.218578 -0.83775 0.500399 0.2134 -0.858752 0.465838 0.231465 -0.950575 0.206957 0.22606 -0.957457 0.179366 0.297905 -0.929805 0.216139 0.298981 -0.930965 0.209559 0.169027 -0.853106 0.4936 0.163011 -0.841421 0.515208 0.0235183 -0.692099 0.72142 0.00814604 -0.651818 0.758332 -0.123368 -0.465098 0.876621 -0.145909 -0.387618 0.910199 -0.308691 -0.0954706 0.946359 -0.393909 0.00279648 0.919145 -0.134428 -0.160792 0.977791 -0.657612 -0.141479 0.739953 -0.640904 -0.0671892 0.764675 -0.404373 -0.422765 0.81102 -0.367462 -0.498848 0.784935 -0.159363 -0.691724 0.704358 -0.134945 -0.72369 0.676804 0.111555 -0.862372 0.493833 0.11536 -0.865232 0.48792 0.367364 -0.906278 0.209055 0.353068 -0.904148 0.240539 -0.800811 -0.131145 0.584382 -0.780329 -0.233256 0.580239 -0.600602 -0.482903 0.637246 -0.569705 -0.542821 0.617076 -0.297835 -0.755339 0.583744 -0.276569 -0.777118 0.565329 0.0592198 -0.900785 0.430208 0.058717 -0.900555 0.430759 0.408677 -0.890239 0.201143 0.387169 -0.892177 0.23264 -0.939002 -0.183045 0.291152 -0.939208 -0.180012 0.292378 -0.733546 -0.551145 0.397681 -0.710692 -0.59246 0.379352 -0.400956 -0.827876 0.392246 -0.384383 -0.841508 0.379624 0.0116972 -0.949772 0.312725 0.010024 -0.949335 0.314105 0.426502 -0.887861 0.172623 0.405559 -0.893282 0.193829 -0.975513 -0.219169 0.0184275 -0.968782 -0.247855 0.00547251 -0.786786 -0.61339 0.0687054 -0.775149 -0.629016 0.0590252 -0.445473 -0.889031 0.105725 -0.436815 -0.893913 0.100559 -0.0120914 -0.992394 0.122507 -0.0121962 -0.992386 0.122562 0.429817 -0.895492 0.115545 0.419852 -0.899484 0.121046 0.609429 -0.256779 0.750107 0.445123 -0.702635 0.55513 0.163407 -0.963133 0.213713 0.444542 -0.70345 0.554563 0.446145 -0.703467 0.553253 0.444901 -0.705315 0.5519 0.609337 -0.257172 0.750047 0.609921 -0.257178 0.74957 0.609757 -0.257985 0.749426 0.610422 -0.257989 0.748884 0.623583 -0.194838 0.757088 0.566372 -0.441681 0.695802 0.500699 -0.608053 0.616094 0.450472 -0.705334 0.547338 0.383793 -0.792574 0.473845 0.278556 -0.896183 0.345343 0.162118 -0.963649 0.212365 0.164335 -0.96367 0.210555 0.161581 -0.96481 0.207443 0.166906 -0.964829 0.203092 0.122267 -0.980405 0.154458 0.279748 -0.900479 0.332983 0.119234 -0.981016 0.152942 0.134948 -0.962159 0.236725 0.359279 -0.823818 0.438454 0.426107 -0.691874 0.582874 0.427479 -0.702243 0.569312 0.625454 -0.152299 0.765253 0.570216 -0.255977 0.780596 0.580375 -0.396418 0.711349 0.537708 -0.531564 0.654453 0.532815 -0.803829 -0.264515 -0.0418503 -0.960533 -0.275001 -0.270376 -0.862674 -0.427424 0.275279 -0.632105 -0.724337 0.0519906 -0.705992 -0.706309 -0.21333 -0.51228 -0.831901 -0.367797 -0.433662 -0.822595 0.253876 -0.257024 -0.932462 -0.382047 -0.149214 -0.912017 -0.1995 -0.0391035 -0.979117 -0.0879937 -0.979914 -0.178955 -0.095015 -0.973561 -0.20773 -0.0884491 -0.877622 -0.471122 -0.095144 -0.8629 -0.496337 -0.0799782 -0.691303 -0.718125 -0.0865446 -0.669803 -0.737478 -0.0635634 -0.440409 -0.895544 -0.0702152 -0.414361 -0.9074 -0.0410337 -0.150718 -0.987725 0.331544 -0.0198793 -0.94323 0.142379 -0.157661 -0.977175 -0.0479417 -0.122622 -0.991295 -0.287797 -0.923825 -0.252427 -0.305913 -0.929147 -0.207614 -0.076892 -0.863531 -0.498399 -0.0794907 -0.865978 -0.493725 0.141745 -0.709552 -0.690249 0.157343 -0.685088 -0.711265 0.343553 -0.481035 -0.806583 0.370888 -0.41431 -0.831137 -0.348658 -0.902804 -0.251757 -0.376391 -0.902431 -0.209639 -0.040759 -0.890317 -0.453514 -0.0464753 -0.893321 -0.447009 0.271051 -0.757563 -0.593826 0.289003 -0.738033 -0.609742 0.54456 -0.525158 -0.65396 0.574663 -0.465561 -0.673064 -0.197728 -0.955101 -0.220647 -0.198329 -0.957144 -0.211048 -0.0915081 -0.863554 -0.495883 -0.0904905 -0.858532 -0.504713 0.0237858 -0.689594 -0.723806 0.0268382 -0.667543 -0.744088 0.136843 -0.451312 -0.881811 0.140223 -0.406469 -0.90284 0.258725 -0.112839 -0.959338 0.507329 -0.204874 -0.837045 0.533546 -0.0924896 -0.840699 0.744943 -0.225959 -0.627696 0.931619 -0.158925 -0.326846 0.854192 -0.193596 -0.482573 0.767239 -0.121487 -0.62975 0.791696 -0.597254 -0.128476 0.77593 -0.61999 -0.11638 0.457831 -0.874157 -0.161991 0.445397 -0.881851 -0.154787 0.0314063 -0.985795 -0.164991 0.0301844 -0.985942 -0.164342 -0.407367 -0.903031 -0.136337 -0.395488 -0.907223 -0.143305 -0.37893 -0.900157 -0.21478 -0.403592 -0.895232 -0.188873 0.00241386 -0.937775 -0.347234 -0.00111938 -0.938874 -0.344259 0.380765 -0.822448 -0.422608 0.397548 -0.80784 -0.435144 0.695323 -0.576655 -0.428945 0.71973 -0.531504 -0.446645 0.923653 -0.172394 -0.342267 0.967046 -0.248363 -0.0560086 0.975572 -0.207947 -0.0708371 -0.273044 -0.251226 -0.928619 -0.21829 -0.290602 -0.931611 -0.283322 -0.0397269 -0.958202 -0.0719738 -0.957137 -0.280549 -0.0556402 -0.960668 -0.272068 -0.210666 -0.693025 -0.689446 -0.155016 -0.721091 -0.675276 -0.2386 -0.511797 -0.825308 -0.13105 -0.957092 -0.258459 -0.130299 -0.957328 -0.257962 -0.35815 -0.688794 -0.63031 -0.355513 -0.691078 -0.629303 -0.490744 -0.246809 -0.835617 -0.487224 -0.251962 -0.836139 0.969651 -0.222784 0.100723 0.970221 -0.220245 0.100813 0.779537 -0.623358 0.0612098 0.783087 -0.618852 0.0616193 0.434929 -0.900414 0.00957969 0.442891 -0.896516 0.0103554 0.00412144 -0.999026 -0.0439238 0.0161345 -0.998946 -0.0429679 -0.427483 -0.899663 -0.0886842 -0.41375 -0.906134 -0.0879375 0.972074 -0.223295 0.0721974 0.972443 -0.221669 0.0722367 0.779435 -0.624813 0.0457191 0.781077 -0.622749 0.0458523 0.431574 -0.902021 0.0101371 0.434849 -0.900444 0.0103673 -0.00221734 -0.999621 -0.0274573 0.00241223 -0.999628 -0.0271826 -0.435474 -0.898228 -0.0595701 -0.430425 -0.900673 -0.0593493 -0.508548 -0.628241 -0.588805 -0.380551 -0.795456 -0.471625 -0.157401 -0.965521 -0.20735 -0.631225 -0.239368 -0.737738 -0.576002 -0.437171 -0.690727 -0.544605 -0.522628 -0.655946 -0.645459 -0.0475742 -0.762312 -0.165503 -0.961196 -0.220704 -0.164219 -0.961166 -0.221793 -0.165816 -0.960522 -0.223391 -0.16394 -0.960472 -0.224981 -0.165546 -0.959819 -0.226587 -0.163657 -0.959764 -0.228189 -0.165263 -0.959106 -0.229792 -0.456383 -0.699761 -0.54959 -0.451941 -0.699666 -0.553369 -0.45268 -0.698649 -0.554049 -0.451332 -0.698613 -0.555193 -0.452062 -0.697609 -0.555862 -0.450706 -0.697569 -0.557011 -0.451447 -0.696549 -0.557687 -0.626694 -0.25557 -0.736165 -0.621648 -0.255458 -0.740469 -0.621757 -0.25501 -0.740532 -0.621266 -0.254997 -0.740949 -0.621382 -0.254525 -0.741014 -0.62089 -0.254511 -0.741431 -0.621 -0.254065 -0.741492 -0.437266 -0.898846 -0.0295507 0.42921 -0.902013 0.046377 0.777241 -0.624819 0.0741439 0.970814 -0.223442 0.0871388 0.97062 -0.223814 0.0883412 0.939474 -0.215453 0.266399 0.926549 -0.241073 0.288776 0.429389 -0.901951 0.0459172 0.402205 -0.885362 0.233165 0.393687 -0.888157 0.237039 0.27704 -0.811236 0.514922 0.245681 -0.821656 0.514317 0.0934836 -0.732643 0.674163 0.0560468 -0.748096 0.661219 -0.0676848 -0.688555 0.722018 -0.10005 -0.708329 0.698756 -0.208408 -0.669102 0.71335 -0.231008 -0.693418 0.6825 0.777129 -0.624912 0.074538 0.742501 -0.609644 0.277539 0.727391 -0.622145 0.289548 0.593639 -0.536838 0.599498 0.536928 -0.576011 0.616376 0.351007 -0.465366 0.812544 0.279285 -0.512484 0.81201 0.104023 -0.42757 0.897977 0.0440661 -0.474603 0.879096 -0.129937 -0.411511 0.902095 -0.168854 -0.456248 0.873685 -0.290624 -0.129524 0.94803 -0.0929925 -0.176337 0.979927 -0.035969 -0.112175 0.993037 0.179758 -0.190158 0.965156 0.264628 -0.114995 0.95747 0.389357 -0.17551 0.904211 0.567581 -0.107091 0.816323 0.566452 -0.134595 0.813029 0.764288 -0.25572 0.592006 0.796835 -0.000674339 0.604197 0.845403 -0.188389 0.499804 -0.429934 -0.157502 0.889016 -0.320165 -0.0469537 0.946198 -0.372585 -0.449278 0.811991 -0.355595 -0.410748 0.839547 -0.351709 -0.693883 0.628353 -0.342624 -0.666178 0.662431 -0.436481 -0.899175 -0.0311158 -0.442192 -0.896698 0.0199594 -0.426894 -0.904136 0.0173087 -0.452231 -0.888394 0.0790196 -0.413263 -0.905484 0.0965033 -0.422573 -0.900101 0.106063 -0.392923 -0.909582 0.135176 -0.360096 -0.925268 0.119207 -0.349333 -0.926855 0.137504 -0.287549 -0.949026 0.129095 -0.289102 -0.949303 0.123466 -0.218048 -0.966421 0.135959 -0.217063 -0.970834 0.101807 -0.159602 -0.97822 0.132716 -0.140996 -0.986719 0.0806623 -0.331106 -0.869735 0.365964 -0.298277 -0.873959 0.383701 -0.295267 -0.858184 0.419926 -0.272707 -0.863666 0.423925 -0.262905 -0.855605 0.445893 -0.236524 -0.865114 0.442305 -0.229338 -0.862751 0.450628 -0.178519 -0.887055 0.425751 -0.178722 -0.887078 0.425619 -0.0884925 -0.939151 0.33191 -0.0940251 -0.939098 0.330537 -0.0160652 -0.989967 0.140383 -0.0196141 -0.989767 0.141341 -0.00379581 -0.999959 0.00820709 -0.00433137 -0.999947 0.00933598 -0.61036 -0.156011 0.776609 -0.604263 -0.134265 0.785391 -0.565922 -0.451526 0.689823 -0.563718 -0.425221 0.708102 -0.493915 -0.647065 0.580823 -0.48564 -0.67574 0.554553 -0.426818 -0.758423 0.492566 -0.319508 -0.890368 0.324282 -0.644596 -0.0475555 -0.763043 -0.617022 -0.198588 -0.761477 -0.618974 -0.239103 -0.748131 -0.568552 -0.436988 -0.696987 -0.527482 -0.522129 -0.670182 -0.500945 -0.565499 -0.655183 -0.481339 -0.627642 -0.611865 -0.324488 -0.843679 -0.427685 -0.345564 -0.793829 -0.50042 -0.100934 -0.9866 -0.128195 -0.127302 -0.964195 -0.23264 0.00112835 -0.988526 -0.151046 -0.0429625 -0.983147 -0.177698 -0.262712 -0.858279 -0.440839 -0.292371 -0.841087 -0.455074 -0.480954 -0.581526 -0.656133 -0.495653 -0.565014 -0.659611 -0.616699 -0.205437 -0.75992 -0.62006 -0.198854 -0.758935 -0.0651532 -0.996184 0.0580748 -0.197401 -0.98013 0.0194549 -0.175409 -0.95907 0.222299 -0.392329 -0.886597 0.244999 -0.372368 -0.879048 0.297686 -0.459566 -0.759724 0.460021 -0.352976 -0.645032 0.677748 -0.362362 -0.629446 0.68738 -0.377341 -0.649769 0.659858 -0.727577 -0.449199 0.51851 -0.505526 -0.234165 0.830428 -0.719758 -0.156224 0.676418 -0.973128 -0.22511 0.0484515 -0.789402 -0.19872 0.580823 -0.790677 -0.211086 0.574693 -0.634424 -0.586591 0.503407 -0.635616 -0.58173 0.507526 -0.362051 -0.87055 0.333258 -0.372778 -0.857653 0.354215 -0.0208191 -0.994783 0.0998681 -0.0447012 -0.989113 0.140204 -0.926179 -0.211258 0.312348 -0.925294 -0.223457 0.306427 -0.742524 -0.608969 0.278954 -0.744393 -0.605496 0.281519 -0.411315 -0.891399 0.190338 -0.426337 -0.88111 0.204649 0.00583319 -0.99804 0.0623053 -0.0260749 -0.995648 0.0894693 -0.966033 -0.22583 -0.125623 -0.988382 -0.150215 -0.0231609 -0.780594 -0.624827 -0.0162393 -0.783391 -0.62137 -0.0140323 -0.430475 -0.902578 -0.00659695 -0.438191 -0.898878 -0.00281143 0.0112104 -0.999928 0.00429918 -0.00167994 -0.999955 0.0092939 -0.901871 -0.230704 -0.365245 -0.90901 -0.215036 -0.357016 -0.717404 -0.617811 -0.321935 -0.721266 -0.614089 -0.320422 -0.396197 -0.891871 -0.218162 -0.389036 -0.894803 -0.219042 0.00470867 -0.997404 -0.071849 0.0259691 -0.997083 -0.0717775 -0.723347 -0.220264 -0.654411 -0.737631 -0.197362 -0.645716 -0.568687 -0.59047 -0.572661 -0.570991 -0.588357 -0.572543 -0.315373 -0.863379 -0.393848 -0.296158 -0.872147 -0.389423 -0.00471207 -0.989263 -0.14607 0.0382757 -0.990891 -0.129116 -0.402613 -0.833587 0.378199 -0.349191 -0.879727 0.322718 -0.141735 -0.9818 0.126415 -0.202935 -0.959884 0.193494 -0.0670361 -0.996173 0.0560767 -0.707213 -0.241345 0.664531 -0.662127 -0.241784 0.709315 -0.6425 -0.558206 0.524975 -0.589586 -0.59702 0.544017 -0.064535 -0.997042 0.0417322 -0.191068 -0.979461 0.0644067 -0.205968 -0.962682 0.175557 -0.407329 -0.835972 0.367742 -0.436145 -0.872559 0.220043 -0.470549 -0.771342 0.428503 -0.143452 -0.981783 0.124592 -0.141756 -0.982256 0.122793 -0.406546 -0.833559 0.374033 -0.40552 -0.834559 0.372913 -0.607275 -0.557442 0.566106 -0.606881 -0.558342 0.565641 -0.144181 -0.982222 0.120218 -0.141603 -0.982916 0.117581 -0.407593 -0.83453 0.370711 -0.406052 -0.835996 0.369097 -0.608273 -0.558323 0.564163 -0.607674 -0.559647 0.563495 -0.715531 -0.196705 0.670316 -0.715218 -0.196712 0.670648 -0.715279 -0.19616 0.670744 -0.714789 -0.196166 0.671264 -0.714823 -0.195835 0.671325 -0.71731 -0.195809 0.668674 -0.604503 -0.557465 0.569043 -0.54887 -0.665779 0.50545 -0.548865 -0.665787 0.505445 -0.103778 -0.987606 0.117746 -0.0132028 -0.995304 0.0958928 -0.195452 -0.962783 0.186673 -0.337147 -0.881534 0.3305 -0.363101 -0.84609 0.390243 -0.46153 -0.771459 0.437996 -0.592802 -0.5695 0.569434 -0.563553 -0.597127 0.570831 -0.733782 -0.20134 0.648865 -0.70541 -0.241447 0.666409 -0.706131 -0.204342 0.677956 -0.705077 -0.20039 0.680228 -0.577051 -0.578956 0.57604 -0.577038 -0.568855 0.58603 -0.351725 -0.856631 0.377456 -0.355524 -0.845636 0.398123 -0.0682642 -0.991003 0.115125 -0.0759329 -0.986186 0.147213 0.708324 -0.253018 -0.658983 0.708441 -0.252389 -0.659098 0.513031 -0.694191 -0.504873 0.514027 -0.692757 -0.50583 0.186165 -0.957279 -0.221269 0.18841 -0.956327 -0.223474 0.708922 -0.253743 -0.658061 0.709048 -0.253059 -0.658188 0.513984 -0.69579 -0.501694 0.515016 -0.694302 -0.502696 0.186494 -0.958432 -0.215934 0.188881 -0.957431 -0.218286 0.112672 -0.95351 -0.279505 0.0834433 -0.955632 -0.282498 0.32089 -0.711426 -0.625222 0.251723 -0.683869 -0.684805 0.375174 -0.504398 -0.777706 0.403274 -0.394361 -0.825742 0.183061 -0.172413 -0.967865 0.341063 -0.245204 -0.907497 0.446637 -0.033391 -0.894092 0.588039 -0.242041 -0.771769 0.590654 -0.251593 -0.7667 0.429049 -0.682718 -0.591451 0.428857 -0.68709 -0.586506 0.157315 -0.953471 -0.257188 0.156885 -0.954036 -0.255348 0.721771 -0.25434 -0.643706 0.390716 -0.839527 -0.37754 0.50545 -0.764393 -0.400279 0.67278 -0.680432 -0.29048 0.578184 -0.585591 -0.568144 0.764196 -0.242049 -0.597844 0.0330386 -0.996747 -0.0735053 0.268663 -0.9554 -0.122601 0.296346 -0.953966 -0.0461219 0.328247 -0.886647 -0.325748 0.31261 -0.391107 -0.865627 0.331089 -0.030192 -0.943116 0.0791441 -0.955416 -0.284458 0.298788 -0.501661 -0.811827 0.212496 -0.707337 -0.674181 -0.498806 -0.201317 -0.843009 -0.267337 -0.111511 -0.957129 -0.208669 -0.182104 -0.960883 0.0746449 -0.116697 -0.990359 0.0974893 -0.157761 -0.982653 0.327852 -0.143349 -0.93379 0.348768 -0.181401 -0.919486 -0.767494 -0.0178884 -0.640806 -0.757385 -0.229039 -0.611481 -0.56608 -0.132587 -0.813618 -0.808814 -0.175672 -0.561213 -0.908282 -0.232559 -0.347765 -0.925926 -0.197348 -0.322049 0.32272 -0.428359 -0.844014 0.130789 -0.440147 -0.88835 0.116454 -0.412636 -0.903421 -0.105809 -0.463951 -0.879519 -0.143453 -0.42362 -0.894409 -0.342406 -0.501499 -0.794517 -0.390017 -0.465205 -0.794652 -0.555795 -0.548687 -0.624527 -0.595093 -0.520982 -0.611917 -0.726373 -0.592923 -0.347598 -0.747094 -0.574318 -0.334678 0.241085 -0.680352 -0.692098 0.153486 -0.685053 -0.712141 0.14612 -0.67099 -0.726926 0.0106325 -0.702056 -0.712043 -0.00424294 -0.689239 -0.724522 -0.142592 -0.743036 -0.653884 -0.160143 -0.734222 -0.659751 -0.293221 -0.800942 -0.522028 -0.310077 -0.794677 -0.521863 -0.425298 -0.856938 -0.291168 -0.438391 -0.851665 -0.287192 0.197355 -0.86556 -0.460279 0.162891 -0.86814 -0.468828 0.160573 -0.864343 -0.476579 0.128813 -0.871557 -0.473071 0.134792 -0.874812 -0.465333 0.0776522 -0.896616 -0.435947 0.0928712 -0.899684 -0.426549 0.014496 -0.938392 -0.345267 0.0274131 -0.939097 -0.342557 -0.0509719 -0.981069 -0.186831 -0.0493338 -0.981114 -0.187036 0.0867439 -0.976143 -0.19905 0.157693 -0.970649 -0.181585 0.158374 -0.971211 -0.177955 0.235765 -0.953758 -0.186442 0.256866 -0.954993 -0.148352 0.291097 -0.942204 -0.165874 0.332734 -0.934196 -0.128706 0.323026 -0.938918 -0.118692 0.362486 -0.926237 -0.10339 0.336018 -0.940467 -0.0511298 0.353195 -0.934135 -0.0514303 0.456779 -0.825214 -0.332228 -0.247185 -0.882307 -0.400543 0.326604 -0.831277 -0.449788 0.334536 -0.887033 -0.318211 0.185159 -0.964709 -0.187225 0.471822 -0.569639 -0.672975 0.748475 -0.241321 -0.617696 0.133113 -0.975845 -0.173225 0.130877 -0.975634 -0.176094 0.082167 -0.989387 -0.119841 0.0843844 -0.989988 -0.113154 0.0475827 -0.99471 -0.0910408 0.0470052 -0.99841 -0.0310994 0.0514514 -0.998164 -0.0319526 0.0258897 -0.998896 0.0392098 0.075638 -0.995945 0.0487175 0.0447107 -0.995208 0.0869603 0.0887694 -0.99122 0.0979969 0.432813 -0.849563 -0.301523 0.478976 -0.862956 -0.160901 0.463122 -0.873457 -0.150307 0.460714 -0.886246 0.0480637 0.467183 -0.882947 0.0463128 0.39587 -0.884972 0.245178 0.427641 -0.869301 0.247868 0.33482 -0.868704 0.365032 0.364524 -0.855333 0.36814 0.259709 -0.715926 -0.648074 0.425524 -0.824083 -0.373921 0.633955 -0.548184 -0.545523 0.710828 -0.55063 -0.437641 0.705962 -0.563858 -0.428581 0.78771 -0.5889 -0.180858 0.787338 -0.589505 -0.180508 0.783801 -0.609758 0.117688 0.790116 -0.602161 0.114538 0.68676 -0.604928 0.403017 0.700782 -0.590071 0.400901 0.564321 -0.589063 0.5784 0.578839 -0.577162 0.576047 0.893868 -0.197704 -0.402384 0.856735 -0.19721 -0.476563 0.856693 -0.186219 -0.48104 0.960971 -0.218541 -0.169633 0.963581 -0.200295 -0.177183 0.960375 -0.224266 0.165483 0.96387 -0.212544 0.160558 0.847871 -0.21551 0.484427 0.849953 -0.210902 0.482804 0.694106 -0.206829 0.689521 0.696327 -0.204028 0.688114 -0.962174 -0.214386 -0.16811 -0.961497 -0.217313 -0.168224 -0.78134 -0.603825 -0.157808 -0.776044 -0.610694 -0.15751 -0.45637 -0.88188 -0.118384 -0.443727 -0.88849 -0.117014 -0.0472451 -0.99725 -0.0571004 -0.0274507 -0.998141 -0.0544153 0.370599 -0.928676 0.0147544 0.394031 -0.918912 0.0184291 -0.963204 -0.21103 -0.166444 -0.962413 -0.214469 -0.166627 -0.786615 -0.59567 -0.162523 -0.780612 -0.603571 -0.16232 -0.469115 -0.873595 -0.129475 -0.454801 -0.881332 -0.128098 -0.0675774 -0.995025 -0.0732051 -0.0451137 -0.996506 -0.07029 0.346045 -0.93821 -0.00378393 0.372914 -0.927866 0.000429134 0.634576 -0.204047 0.745438 0.649726 -0.240792 0.721023 0.514897 -0.577932 0.633148 0.518181 -0.63936 0.568074 0.323497 -0.855792 0.403695 0.320368 -0.868055 0.379269 0.0824219 -0.99122 0.103393 0.0190956 -0.996414 0.0824322 0.185664 -0.962147 0.199503 -0.504188 -0.188915 0.842678 0.0888505 -0.985694 0.143221 0.0856567 -0.97593 0.200558 0.200762 -0.883449 0.423335 0.380652 -0.282219 0.8806 0.298145 -0.488511 0.820041 0.260358 -0.697249 0.667875 0.293796 -0.652398 0.698614 0.206338 -0.813974 0.54302 0.262523 -0.447223 0.855028 0.339313 -0.142972 0.929745 0.323244 -0.0871738 0.942292 0.0530079 -0.11969 0.991395 0.0457195 -0.167407 0.984827 0.0934494 -0.420619 0.902412 0.0867811 -0.458952 0.884213 0.125511 -0.681726 0.720762 0.119219 -0.708453 0.695616 0.145481 -0.874301 0.46307 0.13944 -0.889088 0.435981 0.150842 -0.976107 0.156406 0.145118 -0.980603 0.131752 0.223389 -0.960353 0.166793 0.224635 -0.961842 0.1562 0.100697 -0.883907 0.456692 0.0984387 -0.877833 0.468743 -0.0325285 -0.715239 0.698122 -0.0389773 -0.688559 0.724132 -0.161796 -0.474392 0.865318 -0.170068 -0.419585 0.891642 -0.302633 -0.113625 0.94631 -0.374211 -0.0176831 0.927175 -0.151374 -0.164578 0.974679 -0.657365 -0.153577 0.737757 -0.626225 -0.0741951 0.776104 -0.418837 -0.447616 0.790073 -0.397758 -0.504986 0.766014 -0.196386 -0.722151 0.663273 -0.18334 -0.742679 0.644061 0.0566191 -0.896028 0.440372 0.0544806 -0.894228 0.444284 0.302628 -0.940824 0.152535 0.286729 -0.938831 0.190742 0.328883 -0.926534 0.182675 0.354824 -0.923754 0.144146 0.00496995 -0.924607 0.380889 0.0124724 -0.928177 0.371931 -0.317869 -0.790149 0.524046 -0.329523 -0.777138 0.536164 -0.593569 -0.545391 0.591797 -0.613817 -0.499843 0.611053 -0.785199 -0.226847 0.576197 -0.949102 -0.16177 0.27025 -0.881081 -0.200942 0.428158 -0.796747 -0.143542 0.587017 -0.793265 -0.608215 0.0283723 -0.789114 -0.613754 0.0246065 -0.46513 -0.883883 0.0490418 -0.464774 -0.884082 0.0488223 -0.0462706 -0.997083 0.0607077 -0.0527252 -0.996558 0.0639724 0.386725 -0.920167 0.0611199 0.373745 -0.925063 0.0676177 0.353728 -0.924558 0.141666 0.380198 -0.917599 0.116023 -0.0378832 -0.965604 0.257243 -0.0286456 -0.967966 0.249443 -0.420253 -0.845465 0.329508 -0.428076 -0.838924 0.336093 -0.73077 -0.588156 0.346479 -0.745792 -0.559624 0.361406 -0.937107 -0.187173 0.294614 -0.972062 -0.23468 -0.00455175 -0.975201 -0.221307 0.00243151 0.129284 -0.985073 0.113654 0.0735164 -0.996624 0.0365648 0.194867 -0.961908 0.191727 0.365956 -0.841059 0.398367 0.340953 -0.867588 0.361998 0.541366 -0.564446 0.623156 0.512573 -0.63959 0.572882 0.634805 -0.198647 0.746701 0.632367 -0.241467 0.736074 0.63751 -0.198222 0.744506 0.637457 -0.198563 0.744461 0.544354 -0.56349 0.621416 0.543936 -0.564368 0.620986 0.365603 -0.840146 0.400612 0.364583 -0.841103 0.399531 0.12935 -0.984698 0.116788 0.127677 -0.985124 0.115017 0.637188 -0.197886 0.744871 0.637133 -0.198233 0.744826 0.54369 -0.562656 0.622751 0.543278 -0.563521 0.622329 0.365008 -0.839234 0.403056 0.36399 -0.840192 0.40198 0.129124 -0.984318 0.120187 0.127442 -0.984753 0.118406 0.636893 -0.197573 0.745206 0.636839 -0.197895 0.745167 0.54306 -0.561935 0.623951 0.542697 -0.562682 0.623594 0.364393 -0.83846 0.40522 0.36352 -0.839273 0.40432 0.128799 -0.983991 0.123174 0.127361 -0.984364 0.121682 0.544506 -0.0842034 0.83452 0.108581 -0.984145 0.140246 0.482168 -0.280446 0.829978 0.535918 -0.198242 0.820666 0.483025 -0.485109 0.728942 0.434825 -0.559212 0.70584 0.422822 -0.64825 0.633241 0.308565 -0.837617 0.45076 0.308463 -0.812913 0.493987 0.153224 -0.97386 0.167689 -0.319784 -0.394749 0.861343 -0.200631 -0.871762 0.446967 -0.279713 -0.642535 0.713379 -0.112496 -0.99341 0.0219326 -0.144179 -0.963513 0.225511 -0.292194 -0.161673 0.942595 -0.300178 -0.140818 0.943432 -0.0137242 -0.180855 0.983414 -0.0250431 0.0741087 0.996936 0.079192 -0.143863 0.986424 0.269105 -0.199838 0.94215 0.337135 -0.12959 0.932495 0.546708 -0.215076 0.80923 0.776455 -0.0421126 0.628764 0.785032 -0.237313 0.572195 0.605438 -0.15871 0.779908 0.82141 -0.1975 0.535051 0.925804 -0.232586 0.297979 0.929185 -0.224907 0.293314 -0.295489 -0.4469 0.844373 -0.10005 -0.474211 0.874708 -0.0750348 -0.43839 0.895647 0.137446 -0.502331 0.853682 0.181234 -0.464422 0.866872 0.371906 -0.543029 0.752864 0.41401 -0.515091 0.750518 0.582873 -0.588607 0.56018 0.608784 -0.570615 0.551163 0.745321 -0.614726 0.258086 0.747522 -0.612601 0.25677 -0.215096 -0.715508 0.664667 -0.154722 -0.722955 0.673348 -0.143454 -0.708239 0.691244 -0.0140662 -0.746738 0.66497 0.00172335 -0.736777 0.676134 0.141863 -0.79411 0.590985 0.156284 -0.788594 0.594722 0.29889 -0.850155 0.433476 0.3074 -0.847362 0.432993 0.430233 -0.886276 0.171509 0.427893 -0.88726 0.172269 -0.203421 -0.894813 0.397404 -0.194693 -0.896111 0.398848 -0.193572 -0.895063 0.401736 -0.16728 -0.902731 0.396351 -0.177392 -0.905666 0.385098 -0.111756 -0.931925 0.345003 -0.127747 -0.93289 0.336744 -0.0374291 -0.971318 0.234818 -0.0519296 -0.971127 0.232844 0.0334674 -0.998052 0.052656 0.0248925 -0.998217 0.0542601 -0.109569 -0.989052 0.0988489 -0.214794 -0.973245 0.0815907 -0.21941 -0.973593 0.0630618 -0.30248 -0.949803 0.0798824 -0.330312 -0.943178 0.0361926 -0.351921 -0.934731 0.0492861 -0.391293 -0.920057 0.0195895 -0.370637 -0.928771 -0.00357211 -0.4047 -0.914359 -0.0128819 -0.374056 -0.924185 -0.0772338 -0.387921 -0.918604 -0.0753927 0.96289 -0.213059 0.165675 0.963758 -0.208828 0.166017 0.793754 -0.59941 0.103258 0.800057 -0.590711 0.104741 0.48033 -0.876809 0.0220986 0.49524 -0.868398 0.0249413 0.0795807 -0.994834 -0.0630295 0.103079 -0.992902 -0.0593266 -0.335644 -0.932028 -0.136629 -0.307252 -0.942257 -0.133221 0.96478 -0.21827 0.146824 0.966171 -0.211656 0.147363 0.786121 -0.611604 0.0891913 0.795902 -0.598493 0.0913599 0.458102 -0.888779 0.0146413 0.480949 -0.876549 0.018695 0.0430267 -0.997108 -0.0626396 0.0785641 -0.995253 -0.0574435 -0.380201 -0.916013 -0.127938 -0.338071 -0.933018 -0.123232 -0.0480007 -0.99754 0.0510959 0.0212467 -0.954886 0.296211 -0.0888777 -0.987048 0.133558 -0.251401 -0.845518 0.471059 -0.14208 -0.870278 0.471624 -0.478933 -0.563914 0.672773 -0.248243 -0.641729 0.725644 -0.438697 -0.200698 0.875937 -0.358915 -0.161358 0.919317 -0.430567 -0.392879 0.812563 -0.609443 -0.201874 0.766698 -0.60711 -0.193745 0.770636 -0.522306 -0.564398 0.639259 -0.52214 -0.559344 0.64382 -0.352339 -0.841356 0.40985 -0.353089 -0.839237 0.413534 -0.124388 -0.985856 0.112315 -0.124934 -0.985593 0.114004 0.884649 -0.19051 -0.425561 -0.0341958 -0.975268 -0.218366 0.025576 -0.948884 -0.314588 0.342509 -0.139355 -0.929122 0.0507995 -0.865116 -0.498993 0.16479 -0.678643 -0.715743 0.163158 -0.680416 -0.714433 0.209449 -0.415814 -0.885003 0.223065 -0.38813 -0.894202 0.286019 -0.0402836 -0.957377 0.207519 -0.149696 -0.966709 0.552426 -0.105073 -0.826913 0.545957 -0.17875 -0.818523 0.434991 -0.41791 -0.79758 0.424574 -0.457906 -0.781063 0.266346 -0.686613 -0.676478 0.261579 -0.696598 -0.668078 0.065044 -0.877594 -0.474972 0.072051 -0.869369 -0.488882 -0.144148 -0.965527 -0.216745 -0.124927 -0.957056 -0.261604 0.789282 -0.119224 -0.602345 0.774761 -0.207413 -0.597265 0.63156 -0.453315 -0.628997 0.611042 -0.499429 -0.614165 0.384473 -0.727547 -0.568205 0.376327 -0.737327 -0.561005 0.08033 -0.901222 -0.425849 0.0960677 -0.891705 -0.442304 -0.236752 -0.9461 -0.221007 -0.196776 -0.941971 -0.271975 0.948538 -0.169265 -0.267628 0.949685 -0.124011 -0.287609 0.766315 -0.508254 -0.392988 0.745487 -0.547375 -0.380301 0.476752 -0.786013 -0.393563 0.466562 -0.795217 -0.387235 0.106052 -0.938046 -0.329882 0.119567 -0.933086 -0.339196 -0.285505 -0.934908 -0.210792 -0.246741 -0.93815 -0.242886 0.981512 -0.191104 -0.0106126 0.971826 -0.235692 0.00174031 0.821199 -0.565211 -0.0785446 0.804545 -0.58983 -0.0693459 0.51966 -0.843888 -0.13344 0.508041 -0.85167 -0.128656 0.123506 -0.978359 -0.166012 0.12577 -0.977923 -0.166876 -0.299854 -0.938729 -0.169928 -0.281371 -0.942982 -0.177804 -0.72933 -0.199347 0.654476 -0.729379 -0.198857 0.65457 -0.623169 -0.566323 0.539387 -0.623735 -0.565075 0.540042 -0.4178 -0.843156 0.338423 -0.419285 -0.841794 0.339975 -0.145947 -0.985754 0.0836019 -0.148425 -0.985171 0.0860708 -0.729843 -0.199775 0.653772 -0.729888 -0.199316 0.653863 -0.624219 -0.567412 0.537024 -0.624752 -0.566231 0.53765 -0.418755 -0.844296 0.334379 -0.42015 -0.84302 0.335845 -0.146332 -0.986135 0.0782614 -0.148679 -0.985595 0.080603 -0.0359745 -0.145959 -0.988636 -0.000889996 -0.240105 -0.970746 -0.0331302 -0.383716 -0.922857 -0.0252114 -0.675744 -0.736705 -0.0254602 -0.676117 -0.736354 -0.00912878 -0.947705 -0.319017 -0.00919273 -0.947755 -0.318868 -0.390995 -0.245199 -0.88713 -0.396626 -0.235074 -0.887372 -0.284122 -0.676362 -0.679565 -0.288397 -0.671667 -0.682415 -0.104008 -0.948513 -0.299176 -0.105538 -0.947854 -0.300725 -0.78217 -0.201951 0.589429 -0.779032 -0.195906 0.595592 -0.668542 -0.566992 0.481218 -0.667809 -0.563302 0.486542 -0.449105 -0.842914 0.296312 -0.449482 -0.841456 0.299864 -0.158051 -0.985382 0.06358 -0.15841 -0.985233 0.0649735 -0.575831 -0.250041 -0.778395 -0.575693 -0.250661 -0.778297 -0.415954 -0.687509 -0.595242 -0.415078 -0.688855 -0.594297 -0.151908 -0.95276 -0.263006 -0.149967 -0.953698 -0.26071 -0.575417 -0.249489 -0.778878 -0.5753 -0.250013 -0.778796 -0.415266 -0.686241 -0.597183 -0.414488 -0.687435 -0.596349 -0.151559 -0.951829 -0.266557 -0.149862 -0.952656 -0.264553 -0.568901 -0.816764 0.0961685 -0.789936 -0.547707 0.275713 -0.885903 -0.19134 0.422569 -0.880232 -0.176998 0.440298 -0.973196 -0.114985 0.19917 -0.973368 -0.128308 0.189978 -0.622964 -0.739543 0.254935 -0.746299 -0.665075 -0.0266909 -0.887442 -0.455366 0.0713334 -0.907761 -0.403972 -0.113034 -0.929707 -0.355187 -0.0974 -0.916839 -0.354929 -0.182846 -0.866652 -0.457115 -0.199898 -0.837826 -0.473666 -0.271456 -0.642007 -0.704975 -0.301393 -0.455675 -0.883216 -0.110858 -0.395808 -0.899091 -0.187008 -0.773386 -0.619721 -0.133488 -0.761583 -0.627049 -0.163709 -0.8627 -0.486985 -0.136364 -0.855674 -0.504164 -0.116791 -0.816113 -0.561864 -0.135163 -0.804748 -0.593213 -0.0218774 -0.493735 -0.862237 -0.113015 -0.395727 -0.912819 0.100802 -0.255089 -0.962822 -0.0888999 -0.0764438 -0.966007 -0.246953 -0.360279 -0.881413 -0.305467 -0.539225 -0.724941 -0.428599 -0.428387 -0.777259 -0.460818 -0.6208 -0.593417 -0.512312 -0.791394 -0.486052 0.370742 -0.909654 -0.407484 0.0805401 -0.94337 -0.299143 0.143407 -0.968583 -0.233685 -0.0850751 -0.973242 -0.216098 -0.0781184 -0.950626 -0.215294 -0.223515 -0.934629 -0.270011 -0.231436 -0.869025 -0.305719 -0.389014 -0.802247 -0.441743 -0.401577 -0.621529 -0.474307 -0.623486 -0.65628 -0.432023 -0.618589 -0.99754 -0.0645112 -0.0274244 -0.998938 0.0269619 -0.0373545 -0.988898 -0.0727439 -0.129571 -0.963702 -0.0715474 -0.257216 -0.963436 -0.0739965 -0.257518 -0.870233 -0.123893 -0.476808 -0.867287 -0.139491 -0.477867 -0.743894 -0.164597 -0.647711 -0.719483 -0.192244 -0.667373 -0.121436 -0.97094 -0.206226 -0.222128 -0.953292 -0.204677 -0.276033 -0.880266 -0.385924 -0.609537 -0.252061 -0.751618 -0.715296 -0.192079 -0.671906 -0.566761 -0.427813 -0.704101 -0.440674 -0.689741 -0.574512 -0.648624 -0.59124 -0.479293 -0.381473 -0.774718 -0.504273 0.0515321 -0.945633 -0.321127 0.00611244 -0.878456 -0.477784 0.0351484 -0.968916 -0.244882 0.207808 -0.0866393 -0.974325 0.164081 -0.237398 -0.957455 0.191244 -0.31805 -0.928585 0.178403 -0.465308 -0.866984 0.143032 -0.673077 -0.72561 0.109304 -0.609164 -0.785476 0.117315 -0.783803 -0.609828 0.479492 -0.236713 -0.845017 0.483216 -0.248082 -0.839617 0.347432 -0.673227 -0.65273 0.347932 -0.67855 -0.646927 0.126353 -0.947002 -0.295333 0.126096 -0.947811 -0.292838 -0.564356 -0.767425 -0.304238 0.0366887 -0.786091 -0.617021 -0.0151592 -0.0861587 -0.996166 0.0705832 -0.609997 -0.789254 0.0166733 -0.467902 -0.883623 -0.0287716 -0.318606 -0.947451 0.044632 -0.968693 -0.244218 0.023973 -0.878711 -0.476751 0.0279384 -0.175524 -0.984079 -0.22539 -0.197113 -0.95412 -0.253382 -0.158201 -0.954343 -0.421534 -0.204877 -0.883366 -0.563674 -0.134625 -0.814953 -0.570715 -0.179186 -0.801359 -0.733621 -0.248442 -0.632517 -0.776598 -0.200433 -0.597262 -0.902385 -0.267987 -0.337468 -0.922036 -0.233371 -0.308848 -0.02323 -0.531993 -0.84643 -0.136019 -0.539512 -0.830919 -0.145437 -0.528407 -0.836441 -0.327978 -0.578315 -0.746982 -0.35029 -0.561574 -0.749621 -0.508841 -0.62935 -0.587367 -0.533854 -0.614013 -0.581367 -0.656253 -0.679101 -0.328868 -0.754805 -0.599728 -0.265699 0.0497618 -0.801536 -0.595872 -0.0240405 -0.808226 -0.588381 -0.0146108 -0.815969 -0.57791 -0.097899 -0.838183 -0.53653 -0.0816179 -0.844842 -0.528753 -0.179428 -0.885966 -0.427632 -0.167835 -0.88867 -0.426727 -0.25609 -0.935 -0.245342 -0.258723 -0.934456 -0.244654 0.0381421 -0.966342 -0.254418 0.0933816 -0.961074 -0.26003 0.118387 -0.968204 -0.220378 0.152529 -0.959389 -0.237292 0.204475 -0.958799 -0.197219 0.190582 -0.964481 -0.182906 0.240637 -0.955932 -0.16819 0.209572 -0.972164 -0.10477 0.229359 -0.967476 -0.1067 0.613005 -0.248909 -0.749846 0.441399 -0.684251 -0.580489 0.160898 -0.950729 -0.265001 0.159521 -0.950638 -0.266158 0.160322 -0.950216 -0.267182 0.159846 -0.951281 -0.263655 0.44205 -0.684905 -0.579221 0.441051 -0.684838 -0.58006 0.61305 -0.248641 -0.749898 0.613313 -0.24927 -0.749474 0.613369 -0.248933 -0.74954 0.497085 -0.588889 -0.637273 0.383762 -0.771888 -0.506868 -0.966157 -0.204579 -0.157124 -0.96537 -0.208049 -0.157402 -0.798154 -0.579818 -0.163587 -0.792558 -0.587419 -0.163679 -0.495204 -0.857031 -0.142378 -0.481978 -0.864676 -0.141533 -0.10854 -0.989341 -0.0970706 -0.0876093 -0.991631 -0.0948274 0.296476 -0.954387 -0.0353099 0.321988 -0.946213 -0.0316955 -0.955896 -0.25104 -0.152451 -0.96739 -0.205332 -0.148306 -0.773507 -0.613044 -0.160822 -0.798634 -0.580109 -0.160179 -0.59236 -0.79151 -0.150405 -0.49491 -0.856852 -0.144461 -0.277459 -0.953272 -0.119537 -0.107695 -0.988828 -0.103057 0.222651 -0.97342 -0.0536605 0.297675 -0.953662 -0.0438038 0.922494 -0.203184 0.328209 0.170787 -0.951891 -0.254431 0.349835 -0.769191 -0.534753 0.529469 -0.590442 -0.609131 0.712683 -0.253572 -0.654053 0.661348 -0.185132 -0.726873 0.806428 -0.194828 -0.558315 0.805561 -0.176713 -0.565547 0.944657 -0.199537 -0.260401 0.946593 -0.178477 -0.268529 0.195496 -0.970556 -0.140721 0.158435 -0.970752 -0.180384 0.160051 -0.970096 -0.182474 0.18758 -0.974639 -0.122031 0.190298 -0.97389 -0.123797 0.196312 -0.978913 -0.056494 0.199717 -0.978175 -0.0573388 0.367926 -0.809814 -0.456981 0.451704 -0.813366 -0.366606 0.455521 -0.808616 -0.372344 0.533648 -0.821497 -0.200903 0.540185 -0.815997 -0.205786 0.557242 -0.830206 -0.0155107 0.565391 -0.824624 -0.0180962 0.514542 -0.530405 -0.673734 0.677668 -0.540818 -0.498278 0.680887 -0.529552 -0.505933 0.797973 -0.548809 -0.249092 0.80458 -0.535724 -0.256223 0.830118 -0.556893 0.0278242 0.839069 -0.543535 0.0230746 0.980696 -0.182821 0.0693656 0.988329 -0.0826118 0.127991 0.979011 -0.19722 -0.0514022 0.85454 -0.195663 0.481121 0.908944 -0.115833 0.400505 0.777788 -0.552066 0.300447 0.768447 -0.564171 0.301994 0.525821 -0.833518 0.169589 0.517836 -0.838536 0.169423 0.186187 -0.982469 0.00943147 0.182839 -0.9831 0.00913793 0.724501 -0.191575 0.662116 0.718023 -0.207028 0.664517 0.625227 -0.560295 0.543287 0.617576 -0.569834 0.542115 0.423779 -0.841612 0.334814 0.417669 -0.845529 0.332617 0.150329 -0.986266 0.068416 0.147786 -0.986728 0.0672861 -0.178777 -0.166999 0.969613 0.0295746 -0.994075 0.104591 -0.0136425 -0.983459 0.180618 0.0426116 -0.905687 0.4218 -0.0668827 -0.729261 0.680959 0.0450656 -0.801851 0.595822 -0.0211696 -0.531628 0.846714 0.0143286 -0.462603 0.88645 -0.0244299 -0.311516 0.949927 0.00303422 -0.154693 0.987958 -0.0216919 -0.112948 0.993364 -0.334466 -0.150972 0.930236 -0.284059 -0.0440005 0.957797 -0.189952 -0.45245 0.871325 -0.191379 -0.474088 0.859427 -0.101542 -0.722306 0.684079 -0.101467 -0.730125 0.675738 -0.000179422 -0.909726 0.415209 -0.000265612 -0.90884 0.417144 0.101574 -0.990099 0.0968813 0.10098 -0.988507 0.112506 -0.550346 -0.133743 0.824155 -0.549267 -0.193829 0.812857 -0.426112 -0.469327 0.773408 -0.42004 -0.499246 0.757839 -0.243732 -0.746202 0.619498 -0.241733 -0.750695 0.614836 -0.0264332 -0.924551 0.38014 -0.0339402 -0.916524 0.398538 0.195205 -0.976836 0.0876731 0.178655 -0.974624 0.134873 0.2345 -0.963609 0.128322 0.266967 -0.960535 0.0781141 -0.0729241 -0.940506 0.33186 -0.0564912 -0.949229 0.309471 -0.368714 -0.789858 0.490077 -0.36923 -0.789191 0.490761 -0.613025 -0.534985 0.58137 -0.622006 -0.50934 0.594711 -0.775235 -0.212077 0.595008 -0.960633 -0.106266 0.256696 -0.883558 -0.202108 0.422466 -0.7787 -0.154753 0.608012 -0.805918 -0.591957 0.00910742 -0.808525 -0.588346 0.0116564 -0.498787 -0.866672 0.00955238 -0.506255 -0.862265 0.0143029 -0.102419 -0.994709 0.00802977 -0.115508 -0.9932 0.0145525 0.316391 -0.948617 0.00479773 0.299192 -0.954108 0.0127122 0.271033 -0.958686 0.0863881 0.305758 -0.950589 0.0537844 -0.107409 -0.972852 0.204992 -0.0884147 -0.978133 0.188254 -0.466273 -0.83525 0.291456 -0.463844 -0.837397 0.289162 -0.75072 -0.571048 0.33215 -0.757315 -0.557393 0.340275 -0.929251 -0.188766 0.317583 -0.975964 -0.217822 0.00692329 -0.975944 -0.217912 0.00687265 0.597312 -0.201606 0.776256 0.597267 -0.201986 0.776191 0.513792 -0.571949 0.639447 0.513379 -0.572933 0.638897 0.346585 -0.849172 0.39848 0.345566 -0.850202 0.397165 0.122948 -0.988081 0.0926284 0.12125 -0.988488 0.0905021 0.596966 -0.201179 0.776633 0.596913 -0.201627 0.776557 0.513121 -0.570911 0.640911 0.512661 -0.572008 0.640302 0.346077 -0.848066 0.401266 0.344901 -0.849259 0.399752 0.122917 -0.987709 0.0965489 0.120975 -0.988183 0.0941186 0.125446 -0.112511 0.9857 0.115713 -0.0970098 0.988534 0.238988 -0.203331 0.949495 0.176954 -0.309445 0.934308 0.157074 -0.573044 0.804331 0.131376 -0.530662 0.83734 0.14298 -0.85195 0.503724 0.0932397 -0.800423 0.59214 0.0621238 -0.989564 0.130013 0.0448654 -0.983139 0.17727 0.0943315 -0.988519 0.118034 0.0955815 -0.988259 0.119196 0.265867 -0.847873 0.458723 0.268822 -0.845683 0.461037 0.392271 -0.570594 0.721489 0.396308 -0.565264 0.723476 0.454689 -0.20487 0.866768 0.458859 -0.196238 0.866568 0.951124 -0.250633 0.180407 0.951241 -0.250218 0.180364 0.719452 -0.688548 0.0910529 0.720571 -0.687384 0.0910022 0.305451 -0.951969 -0.0213447 0.308113 -0.951109 -0.0213845 -0.185974 -0.974146 -0.128268 -0.182067 -0.974857 -0.128476 0.950651 -0.251142 0.182183 0.950751 -0.250791 0.182146 0.718163 -0.689691 0.0925681 0.719136 -0.688682 0.0925245 0.302965 -0.95278 -0.0205691 0.305292 -0.952036 -0.0206015 -0.189325 -0.973481 -0.128417 -0.185904 -0.974117 -0.128595 0.950207 -0.252517 0.1826 0.950546 -0.251186 0.182669 0.715377 -0.69259 0.0924923 0.718075 -0.689727 0.0929741 0.296739 -0.95472 -0.0213489 0.302936 -0.952792 -0.0204321 -0.198155 -0.971559 -0.129646 -0.189257 -0.973453 -0.128728 0.949775 -0.256374 0.179443 0.950792 -0.252272 0.179873 0.707791 -0.700812 0.0888481 0.715728 -0.692443 0.0908602 0.278742 -0.960036 -0.0251888 0.296786 -0.9547 -0.0215685 -0.223987 -0.965544 -0.132495 -0.198389 -0.971655 -0.12856 0.883076 -0.230546 -0.408686 0.061447 -0.965631 -0.25255 0.223027 -0.944267 -0.242114 0.111751 -0.79421 -0.597278 0.230907 -0.769458 -0.595497 0.323472 -0.53207 -0.782475 0.064118 -0.569645 -0.819386 0.407899 -0.0228727 -0.91274 0.326126 -0.18034 -0.927965 0.541922 -0.269195 -0.79615 0.255431 -0.487338 -0.835019 0.545494 -0.156888 -0.8233 0.54835 -0.192739 -0.813735 0.422334 -0.528914 -0.736128 0.421401 -0.535705 -0.731739 0.227891 -0.818874 -0.526794 0.233406 -0.806295 -0.543516 -0.00535051 -0.973548 -0.22842 0.010915 -0.961087 -0.27603 0.775692 -0.16251 -0.60983 0.769539 -0.228322 -0.596388 0.580218 -0.5579 -0.593376 0.572127 -0.576548 -0.583321 0.266592 -0.847685 -0.458649 0.279295 -0.834957 -0.474175 -0.103622 -0.967846 -0.229208 -0.0620059 -0.956154 -0.286225 0.944262 -0.214182 -0.24999 0.942403 -0.158578 -0.294498 0.69747 -0.608283 -0.37885 0.684655 -0.628948 -0.368336 0.308412 -0.889619 -0.33684 0.318919 -0.882825 -0.344834 -0.158158 -0.963752 -0.21487 -0.11424 -0.960916 -0.25217 0.973443 -0.228813 -0.0073078 0.96259 -0.270848 0.00783011 0.746159 -0.660304 -0.0851193 0.731514 -0.677513 -0.0765802 0.331673 -0.932454 -0.143254 0.330351 -0.933012 -0.142677 -0.173759 -0.970571 -0.166731 -0.153541 -0.972403 -0.175664 -0.0648417 -0.187889 0.980048 -0.232985 -0.968461 -0.0883251 0.254235 -0.963496 0.0839089 0.669403 -0.705423 0.232977 0.911432 -0.261133 0.317964 0.908945 -0.265908 0.321111 0.778433 -0.243357 0.578635 0.769073 -0.194632 0.608807 0.650999 -0.243599 0.71893 0.509038 -0.205864 0.835763 0.472394 -0.245253 0.846578 -0.216598 -0.971956 -0.0915825 -0.255819 -0.966609 -0.0149308 -0.204873 -0.978788 0.00124612 -0.237568 -0.970858 0.0315532 -0.188619 -0.979454 0.0713619 -0.175034 -0.982391 0.0653497 -0.149502 -0.983187 0.104845 0.267048 -0.960334 0.0802695 0.158177 -0.943429 0.291415 0.182184 -0.937871 0.295308 0.0433013 -0.903881 0.425587 0.0643859 -0.897093 0.437126 -0.041365 -0.873876 0.484386 -0.0308502 -0.8679 0.495779 0.676816 -0.699618 0.229031 0.524799 -0.675904 0.517436 0.521399 -0.678248 0.517806 0.311916 -0.625284 0.715352 0.300428 -0.633467 0.713066 0.100679 -0.588502 0.802203 0.0909353 -0.597648 0.796585 0.214088 -0.226218 0.950259 0.187839 -0.106914 0.976364 0.302905 -0.207801 0.93009 -0.205626 -0.204307 0.957067 -0.0730167 -0.169376 0.982843 -0.101706 -0.577171 0.810265 -0.098113 -0.571186 0.814936 -0.101887 -0.855987 0.506858 -0.103436 -0.858047 0.503047 -0.0852979 -0.989611 0.115733 -0.0897266 -0.991041 0.0989329 -0.101279 -0.244533 -0.964337 0.280761 -0.0182535 -0.959604 0.0688509 -0.946209 -0.316147 0.0707627 -0.948067 -0.310099 0.161554 -0.765132 -0.623276 0.236527 -0.674338 -0.699516 0.218341 -0.590591 -0.776872 0.234593 -0.48568 -0.842069 0.0590566 -0.138555 -0.988592 -0.000837109 -0.944747 -0.3278 -0.000873793 -0.94472 -0.327878 -0.000285026 -0.671777 -0.740754 -0.000372893 -0.671649 -0.740869 0.000361051 -0.24023 -0.970716 0.268455 -0.245853 -0.931391 0.280818 -0.263648 -0.922839 -0.0837671 -0.945343 -0.315134 -0.0826057 -0.945833 -0.31397 -0.228192 -0.671576 -0.704922 -0.224934 -0.674813 -0.702874 -0.315793 -0.237707 -0.91857 -0.311076 -0.24465 -0.918356 -0.0593806 -0.990832 0.121348 -0.0599036 -0.990763 0.12166 -0.167588 -0.855128 0.490582 -0.169055 -0.854472 0.49122 -0.247697 -0.577629 0.777812 -0.250037 -0.576018 0.778257 -0.286488 -0.204959 0.935904 -0.289481 -0.20238 0.935544 -0.504288 -0.207162 0.838319 -0.500343 -0.196444 0.843248 -0.434927 -0.573855 0.693923 -0.433822 -0.567327 0.699956 -0.294632 -0.850677 0.435363 -0.294918 -0.848083 0.440202 -0.104484 -0.989279 0.102027 -0.104843 -0.989029 0.104068 -0.120549 -0.94798 -0.294621 -0.120686 -0.947895 -0.294839 -0.283817 -0.766539 -0.576078 -0.332828 -0.680698 -0.652592 -0.371971 -0.584287 -0.721281 -0.459594 -0.246985 -0.853096 -0.470479 -0.186227 -0.862536 -0.423183 -0.423068 -0.801205 -0.459584 -0.246933 -0.853116 -0.459574 -0.246985 -0.853106 -0.330528 -0.680495 -0.653971 -0.330474 -0.680596 -0.653893 -0.120728 -0.947818 -0.295068 -0.12061 -0.947892 -0.294881 -0.637539 -0.202136 0.743428 -0.637553 -0.201916 0.743476 -0.548494 -0.573343 0.608632 -0.548741 -0.572686 0.609027 -0.369585 -0.850552 0.374123 -0.370227 -0.849877 0.375021 -0.1301 -0.988406 0.0782838 -0.131186 -0.988148 0.0797101 -0.637815 -0.202313 0.743143 -0.637827 -0.202118 0.743186 -0.549131 -0.573758 0.607665 -0.549307 -0.573289 0.607948 -0.370305 -0.85098 0.372435 -0.370788 -0.850472 0.373113 -0.13068 -0.988503 0.0760525 -0.13149 -0.988313 0.0771169 -0.150719 -0.986805 0.0591621 -0.626268 -0.565129 0.537045 -0.729421 -0.206757 0.652071 -0.725032 -0.194557 0.660663 -0.868245 -0.190883 0.457947 -0.893611 -0.126016 0.430789 -0.931979 -0.200462 0.302045 -0.977947 -0.182091 0.102291 -0.974912 -0.204167 0.088674 -0.95731 -0.178385 -0.227458 -0.950226 -0.200041 -0.238859 -0.626584 -0.572492 0.528815 -0.764548 -0.553785 0.32983 -0.760204 -0.566065 0.318843 -0.837006 -0.544452 0.0547101 -0.828633 -0.557987 0.0449262 -0.813592 -0.535835 -0.22572 -0.802884 -0.549176 -0.231914 -0.70004 -0.52887 -0.479834 -0.689763 -0.540568 -0.481678 -0.860109 -0.182448 -0.476367 -0.842151 -0.097101 -0.530427 -0.767335 -0.191592 -0.611955 -0.14991 -0.987055 0.0570056 -0.183962 -0.982888 0.00944644 -0.181501 -0.983367 0.00687016 -0.200005 -0.978154 -0.0566768 -0.196613 -0.978741 -0.0583951 -0.193055 -0.973437 -0.123089 -0.189438 -0.974088 -0.123559 -0.165094 -0.969271 -0.182364 -0.162057 -0.969906 -0.181711 -0.120086 -0.966072 -0.228659 -0.176286 -0.948515 -0.26314 -0.329476 -0.799372 -0.502443 -0.460172 -0.812562 -0.357749 -0.468193 -0.807682 -0.358392 -0.537223 -0.821341 -0.191809 -0.546361 -0.815869 -0.189335 -0.556458 -0.830849 -0.00666587 -0.564568 -0.825386 -0.00107401 -0.512489 -0.84006 0.177918 -0.517844 -0.83518 0.185234 -0.42293 -0.847934 0.319589 -0.424234 -0.845064 0.325411 -0.601279 -0.189908 -0.776143 -0.60868 -0.17591 -0.77367 -0.546698 -0.424176 -0.721939 -0.496175 -0.521471 -0.694174 -0.483249 -0.584326 -0.651946 -0.368322 -0.766637 -0.525934 -0.0347565 -0.947242 -0.31863 -0.0498682 -0.949247 -0.310552 -0.313899 -0.206332 -0.926766 -0.11074 -0.43447 -0.893853 -0.139137 -0.678412 -0.721386 -0.415149 -0.572044 -0.707402 -0.0736274 -0.768405 -0.635714 -0.140964 -0.0210416 -0.989791 -0.199323 -0.246111 -0.948525 -0.0285935 -0.244854 -0.969138 0.135305 -0.100448 -0.985699 0.262209 -0.673002 -0.691603 0.263227 -0.676953 -0.687347 0.0958656 -0.946592 -0.307852 0.0959501 -0.947289 -0.305674 0.0141801 -0.945982 -0.323909 0.0140202 -0.945849 -0.324306 0.0383041 -0.673621 -0.738083 0.0379378 -0.673046 -0.738627 0.0529648 -0.240647 -0.969167 0.365142 -0.246031 -0.897853 0.361811 -0.237825 -0.901406 -0.245424 -0.434402 -0.866638 -0.314348 -0.0232035 -0.949024 -0.198505 -0.594295 -0.779364 -0.103445 -0.76904 -0.630774 -0.536143 -0.214569 -0.816401 -0.298541 -0.170063 -0.939123 -0.274112 -0.206933 -0.939171 -0.772758 -0.024135 -0.634241 -0.776457 -0.246223 -0.580077 -0.570035 -0.171941 -0.803428 -0.815621 -0.207059 -0.540267 -0.916853 -0.258953 -0.303848 -0.933062 -0.227002 -0.279045 -0.199649 -0.53032 -0.823954 -0.38747 -0.565821 -0.727815 -0.395724 -0.558612 -0.728941 -0.554766 -0.616091 -0.559166 -0.570247 -0.605225 -0.555447 -0.686341 -0.662996 -0.298952 -0.701236 -0.651263 -0.290042 -0.108763 -0.820175 -0.561679 -0.174492 -0.831642 -0.527186 -0.147797 -0.844868 -0.514154 -0.242354 -0.878256 -0.412226 -0.221943 -0.884339 -0.410713 -0.30392 -0.924537 -0.22992 -0.302652 -0.924866 -0.230268 -0.0338909 -0.949047 -0.313307 0.0316397 -0.974063 -0.224052 0.0692418 -0.967427 -0.243495 0.129483 -0.971574 -0.198187 0.119996 -0.974811 -0.188002 0.178788 -0.968788 -0.171713 0.150822 -0.982371 -0.110452 0.174093 -0.978211 -0.113117 0.505781 -0.247536 -0.826384 0.50574 -0.247849 -0.826316 0.363666 -0.681841 -0.634697 0.363329 -0.682547 -0.634131 0.131129 -0.948652 -0.287862 0.132249 -0.948709 -0.28716 0.13149 -0.94921 -0.28585 0.505501 -0.247393 -0.826599 0.505484 -0.247522 -0.826571 0.408796 -0.585026 -0.70045 0.365332 -0.681925 -0.633649 0.311524 -0.767347 -0.560473 0.131437 -0.948448 -0.288393 -0.960068 -0.245962 -0.133313 -0.959308 -0.248746 -0.133619 -0.72033 -0.678499 -0.144098 -0.715456 -0.683586 -0.144337 -0.304341 -0.945026 -0.119596 -0.293676 -0.948442 -0.119216 0.186117 -0.980323 -0.0657788 0.201137 -0.977436 -0.0645278 -0.962091 -0.24377 -0.122302 -0.961251 -0.246906 -0.122612 -0.726654 -0.673668 -0.134702 -0.721345 -0.679305 -0.13493 -0.316522 -0.941626 -0.114696 -0.304932 -0.945493 -0.114279 0.16971 -0.983209 -0.0670718 0.186111 -0.980328 -0.0657284 0.532717 -0.185259 -0.825768 0.664978 -0.25129 -0.703319 0.346535 -0.522251 -0.77921 0.425631 -0.585796 -0.689696 0.294031 -0.805744 -0.514123 0.196819 -0.754744 -0.625798 0.264311 -0.957308 -0.117051 0.136366 -0.948689 -0.285296 0.132579 -0.96759 -0.214925 0.133785 -0.966888 -0.217324 0.380188 -0.807544 -0.450921 0.382715 -0.802905 -0.457026 0.572297 -0.535376 -0.621167 0.57386 -0.524639 -0.62884 0.683909 -0.192028 -0.703843 0.922243 -0.0551884 -0.382651 0.822928 -0.192458 -0.534555 0.681751 -0.174859 -0.710381 0.192872 -0.975815 -0.102886 0.196305 -0.974962 -0.104466 0.550056 -0.824922 -0.13016 0.558325 -0.818633 -0.134584 0.822019 -0.55264 -0.13738 0.830743 -0.537646 -0.144233 0.192607 -0.980579 -0.0369822 0.196323 -0.979827 -0.0373579 0.547891 -0.834598 0.0571061 0.557077 -0.828597 0.055615 0.815264 -0.561433 0.141908 0.825702 -0.546902 0.138253 0.171828 -0.971332 -0.164288 0.174288 -0.97049 -0.166655 0.491377 -0.815579 -0.30558 0.497067 -0.809753 -0.311807 0.737247 -0.543644 -0.401146 0.742547 -0.529959 -0.409594 0.881172 -0.176589 -0.438579 0.97143 -0.202382 -0.123954 0.975018 -0.178228 -0.132573 0.956806 -0.206159 0.204989 0.804786 -0.0485196 0.591579 0.882244 -0.20331 0.42463 0.963048 -0.182617 0.197962 0.538213 -0.565509 0.624921 0.531105 -0.574493 0.622805 0.365055 -0.846977 0.386477 0.359658 -0.850568 0.383641 0.128864 -0.988419 0.0801325 0.126794 -0.988791 0.0788429 0.170059 -0.985088 0.0261212 0.173248 -0.984512 0.0268605 0.482762 -0.843513 0.235429 0.490842 -0.838463 0.236757 0.715356 -0.569036 0.405542 0.725183 -0.556603 0.405343 0.836248 -0.189054 0.514732 0.615413 -0.208894 0.76002 0.621957 -0.194207 0.758586 -0.871149 -0.243315 0.426495 -0.219712 -0.66676 0.71215 -0.182351 -0.78263 0.59518 -0.110876 -0.859829 0.498398 -0.129395 -0.909699 0.394594 -0.00335946 -0.993088 0.117325 -0.00881737 -0.995959 0.0893791 -0.357027 -0.2063 0.911028 -0.185031 -0.501739 0.844998 -0.244179 -0.582514 0.775277 -0.292585 -0.277261 0.915161 -0.2464 -0.182081 0.951911 -0.296128 -0.0751947 0.952184 -0.506484 -0.191826 0.84064 -0.51021 -0.211727 0.833581 -0.382685 -0.590591 0.710461 -0.382776 -0.587102 0.713297 -0.18251 -0.879271 0.439968 -0.187535 -0.864361 0.466595 0.0547617 -0.995258 0.0803929 0.0423768 -0.989744 0.136426 -0.741305 -0.205993 0.638775 -0.742707 -0.235941 0.626672 -0.549869 -0.622899 0.556454 -0.550205 -0.621788 0.557363 -0.234303 -0.907066 0.349763 -0.249328 -0.891338 0.378619 0.136717 -0.988687 0.0616985 0.103405 -0.986769 0.12488 -0.931555 -0.241929 0.271432 -0.91817 -0.179578 0.353152 -0.674656 -0.663603 0.323219 -0.676939 -0.659479 0.326864 -0.282614 -0.93763 0.202433 -0.302729 -0.926019 0.225486 0.183871 -0.98251 0.0294377 0.1433 -0.986942 0.0735613 -0.965198 -0.259806 0.0298793 -0.96707 -0.252036 0.0354088 -0.724906 -0.688725 0.0130028 -0.733271 -0.67959 0.0217278 -0.305117 -0.952282 -0.00792507 -0.321249 -0.94699 0.00294292 0.196604 -0.980082 -0.0280303 0.174866 -0.984463 -0.0159352 0.479739 -0.203791 0.853417 0.479735 -0.20383 0.85341 0.413786 -0.577471 0.703782 0.413759 -0.577547 0.703734 0.278988 -0.855075 0.43705 0.278925 -0.855151 0.436941 0.0977767 -0.99041 0.0976113 0.0976712 -0.990438 0.0974329 0.479726 -0.203767 0.85343 0.479724 -0.203791 0.853425 0.413772 -0.577391 0.703855 0.413744 -0.577472 0.703805 0.278996 -0.854992 0.437207 0.278925 -0.855078 0.437085 0.0978145 -0.990384 0.0978394 0.0977036 -0.990413 0.0976517 -0.293433 -0.571343 0.766462 -0.181016 -0.501765 0.845852 -0.196977 -0.204407 0.958863 -0.387806 -0.271947 0.880711 -0.199886 -0.0772187 0.976772 -0.297058 -0.889489 0.347225 -0.136959 -0.783621 0.605954 -0.158814 -0.668227 0.726808 -0.0259177 -0.85702 0.514631 -0.104519 -0.9885 0.109288 -0.0342609 -0.995924 0.0834317 -0.00104599 -0.991873 0.127228 -0.00107235 -0.991882 0.127156 -0.00112275 -0.855463 0.517863 -0.00118739 -0.855544 0.517729 -0.00100723 -0.576182 0.817321 -0.00109954 -0.576346 0.817205 -0.000705141 -0.204215 0.978926 -0.000859172 -0.204526 0.978861 0.067394 -0.991132 0.114526 0.0681944 -0.990963 0.115507 0.191635 -0.854659 0.482528 0.193851 -0.852863 0.484816 0.282503 -0.576903 0.766404 0.285771 -0.572348 0.768604 0.326101 -0.207375 0.922309 0.329816 -0.199871 0.922645 0.958434 -0.237533 0.158055 0.96011 -0.230266 0.158641 0.747302 -0.659255 0.0831972 0.762548 -0.641132 0.0864376 0.365756 -0.930651 -0.010523 0.40257 -0.915379 -0.00435788 -0.0992051 -0.989862 -0.101643 -0.0430886 -0.994593 -0.0944879 0.955619 -0.244632 0.164156 0.95714 -0.23816 0.164811 0.732951 -0.675587 0.0797837 0.747288 -0.659262 0.0832708 0.332573 -0.942776 -0.0238489 0.367074 -0.930029 -0.017402 -0.148471 -0.981419 -0.121543 -0.0967925 -0.988717 -0.114324 0.890293 -0.214519 -0.401698 0.0541484 -0.983693 -0.171511 0.48044 -0.712026 -0.512051 0.421171 -0.854853 -0.303052 0.635636 -0.512894 -0.576981 0.126382 -0.972387 -0.196193 0.306923 -0.889731 -0.3379 0.347078 -0.85884 -0.376736 0.656052 -0.433041 -0.61812 0.634451 -0.558264 -0.534614 0.768833 -0.231079 -0.596236 0.768019 -0.178849 -0.614947 0.800178 -0.0436944 -0.598168 0.9461 -0.208664 -0.247698 0.934435 -0.133986 -0.329968 0.732077 -0.587418 -0.344968 0.732705 -0.586227 -0.345661 0.40126 -0.874671 -0.271921 0.425948 -0.855835 -0.293454 -0.0129904 -0.989648 -0.14293 0.04358 -0.980558 -0.191331 0.976745 -0.213148 -0.0231744 0.970483 -0.240832 -0.0127978 0.780542 -0.621314 -0.0687201 0.775007 -0.628579 -0.0652073 0.417727 -0.902995 -0.100518 0.426839 -0.89826 -0.104584 -0.0400306 -0.99299 -0.111211 -0.00995438 -0.992279 -0.123625 0.0556716 -0.205143 0.977147 0.043031 -0.581001 0.812764 0.0228512 -0.858982 0.511496 -0.00170461 -0.992275 0.124047 0.0583057 -0.205555 0.976907 0.217532 -0.204338 0.954424 0.222692 -0.195916 0.955 0.49725 -0.2293 0.836758 0.714713 -0.0904651 0.693543 0.743758 -0.247012 0.621135 0.512669 -0.209172 0.832717 0.788582 -0.238931 0.566613 0.910536 -0.24751 0.331153 0.90599 -0.257527 0.33595 0.0505537 -0.5821 0.811544 0.159155 -0.579632 0.799185 0.15109 -0.590294 0.792922 0.361256 -0.615479 0.700485 0.35502 -0.62089 0.698896 0.552903 -0.653038 0.517532 0.544988 -0.659108 0.518232 0.700749 -0.671421 0.241134 0.688966 -0.681953 0.245492 0.0341257 -0.860169 0.508866 0.0720813 -0.859703 0.505683 0.0509987 -0.877042 0.477699 0.154456 -0.888656 0.431781 0.121038 -0.903113 0.41199 0.247063 -0.922635 0.296149 0.213923 -0.932713 0.290316 0.325152 -0.941056 0.0932172 0.30594 -0.947188 0.0961009 0.012135 -0.99269 0.12008 -0.0282531 -0.992009 0.12296 -0.0598461 -0.995876 0.0681825 -0.0843731 -0.9933 0.0789721 -0.14173 -0.989387 0.032031 -0.115835 -0.993233 0.00840607 -0.172709 -0.984926 -0.00965336 -0.132923 -0.987914 -0.0797392 -0.157081 -0.984505 -0.0779452 0.615708 -0.0344022 -0.787223 0.150754 -0.973554 -0.171653 0.265417 -0.886578 -0.378859 0.299387 -0.85501 -0.423468 0.612998 -0.223871 -0.757704 0.433434 -0.708228 -0.557268 0.520412 -0.505291 -0.688369 0.548824 -0.425599 -0.719484 0.62133 -0.252341 -0.741804 0.440902 -0.249669 -0.862131 0.357277 -0.184198 -0.915655 0.292716 -0.250552 -0.92279 0.035552 -0.246471 -0.968498 0.0355239 -0.246423 -0.968511 -0.281038 -0.249182 -0.926783 -0.284171 -0.24455 -0.927061 0.430759 -0.690594 -0.58097 0.254989 -0.683383 -0.684082 0.255767 -0.685932 -0.681234 0.02684 -0.684086 -0.728907 0.0268527 -0.684105 -0.728889 -0.203256 -0.686166 -0.698472 -0.205725 -0.683696 -0.70017 0.158462 -0.955729 -0.247937 0.0947547 -0.953488 -0.286149 0.0948976 -0.954133 -0.283946 0.0112211 -0.953446 -0.301356 0.0112448 -0.953463 -0.301302 -0.0726348 -0.95421 -0.290184 -0.0740633 -0.953633 -0.291716 -0.0149937 -0.204974 0.978653 -0.0191145 -0.992029 0.124554 -0.0192781 -0.991989 0.124841 -0.0520963 -0.85695 0.512759 -0.0526082 -0.856493 0.51347 -0.0760537 -0.578513 0.81212 -0.0769088 -0.577361 0.812859 -0.0871617 -0.205601 0.974747 -0.15096 -0.0991962 0.98355 -0.382317 -0.20795 0.900328 -0.378501 -0.198925 0.903972 -0.330984 -0.576952 0.74671 -0.329397 -0.571499 0.751589 -0.224956 -0.854261 0.468651 -0.224648 -0.852142 0.472638 -0.080383 -0.99078 0.109054 -0.080436 -0.990608 0.110574 -0.112695 -0.9499 -0.29153 -0.10966 -0.951861 -0.286244 -0.265953 -0.769167 -0.581078 -0.310636 -0.686139 -0.657813 -0.348574 -0.586627 -0.731003 -0.396538 -0.424874 -0.813781 -0.431949 -0.24944 -0.866718 -0.438421 -0.186988 -0.879103 -0.431012 -0.251649 -0.866546 -0.43141 -0.249421 -0.866991 -0.308982 -0.691146 -0.653335 -0.311495 -0.686168 -0.657376 -0.108602 -0.955431 -0.274514 -0.114045 -0.952011 -0.284021 -0.527808 -0.203325 0.824668 -0.527805 -0.203393 0.824653 -0.455619 -0.576265 0.678477 -0.455559 -0.576465 0.678347 -0.307942 -0.853744 0.419872 -0.30778 -0.853953 0.419567 -0.109244 -0.989776 0.091703 -0.10897 -0.989851 0.0912192 -0.527591 -0.203118 0.824858 -0.527582 -0.203337 0.82481 -0.455138 -0.575755 0.679231 -0.454975 -0.576299 0.67888 -0.307434 -0.853222 0.421304 -0.306989 -0.853794 0.420469 -0.108903 -0.989624 0.093727 -0.108145 -0.989832 0.0923925 -0.456738 -0.809101 -0.369792 -0.565657 -0.204282 0.798937 -0.560745 -0.201297 0.803147 -0.486816 -0.575725 0.656925 -0.484009 -0.573961 0.660533 -0.328162 -0.852643 0.406583 -0.326937 -0.852007 0.408896 -0.115714 -0.989295 0.0889129 -0.115444 -0.989263 0.0896184 -0.723191 -0.207868 0.658624 -0.719414 -0.192135 0.667479 -0.621447 -0.5714 0.536009 -0.622248 -0.561902 0.545045 -0.419895 -0.846873 0.326336 -0.422169 -0.843206 0.332832 -0.148411 -0.987033 0.0611603 -0.149495 -0.986731 0.0633504 -0.902668 -0.206353 0.377635 -0.901745 -0.186837 0.389805 -0.771203 -0.565042 0.293213 -0.775775 -0.553168 0.303611 -0.519194 -0.839165 0.161986 -0.524553 -0.834484 0.168764 -0.183029 -0.983102 0.00335503 -0.185329 -0.982661 0.00559496 -0.198983 -0.978184 -0.0596775 -0.195611 -0.978768 -0.0612351 -0.564638 -0.825149 -0.0177221 -0.55671 -0.830395 -0.0227573 -0.838438 -0.544321 0.0271326 -0.830144 -0.557253 0.018175 -0.980876 -0.182333 0.0680997 -0.942328 0.0104945 -0.334525 -0.964139 -0.18641 -0.188912 -0.977534 -0.203373 0.0553807 -0.67415 -0.54126 -0.502553 -0.113443 -0.967469 -0.226131 -0.156683 -0.970911 -0.18106 -0.160072 -0.970198 -0.181916 -0.168391 -0.950098 -0.262598 -0.313143 -0.801742 -0.509069 -0.449029 -0.813821 -0.368874 -0.683752 -0.530327 -0.501235 -0.522531 -0.425293 -0.738977 -0.472762 -0.523811 -0.708603 -0.461714 -0.586042 -0.665864 -0.351433 -0.768776 -0.534302 -0.189884 -0.973876 -0.12454 -0.18606 -0.974568 -0.124898 -0.540254 -0.816378 -0.204089 -0.531405 -0.821658 -0.206123 -0.805597 -0.536441 -0.251483 -0.795337 -0.549048 -0.256878 -0.944377 -0.199738 -0.261261 -0.810211 -0.177422 -0.558641 -0.802001 -0.194805 -0.564664 -0.581449 -0.177378 -0.794011 -0.574733 -0.190059 -0.795964 -0.965638 -0.241036 -0.0971836 -0.965125 -0.242996 -0.0974023 -0.737313 -0.667152 -0.106198 -0.733803 -0.670965 -0.106489 -0.336629 -0.937292 -0.0903599 -0.328768 -0.940073 -0.0904154 0.14275 -0.98832 -0.0533488 0.154119 -0.986629 -0.0530095 -0.967886 -0.237547 -0.0822723 -0.966787 -0.241884 -0.0825494 -0.747529 -0.659046 -0.0828147 -0.739109 -0.668444 -0.0830714 -0.358146 -0.931429 -0.0645941 -0.338689 -0.938702 -0.0642477 0.112204 -0.99318 -0.0317 0.140897 -0.989554 -0.0305169 -0.862135 -0.236079 0.448318 -0.00435187 -0.996065 0.0885185 -0.0480042 -0.990651 0.127697 -0.161042 -0.927813 0.336494 -0.251662 -0.802985 0.540261 -0.255282 -0.875476 0.410333 -0.377432 -0.583963 0.718702 -0.41801 -0.528343 0.739 -0.490603 -0.198337 0.848511 -0.460475 -0.110629 0.880752 -0.47386 -0.307577 0.825138 -0.716942 -0.204444 0.666481 -0.718567 -0.221745 0.659159 -0.549364 -0.612967 0.567865 -0.551799 -0.602555 0.576581 -0.265281 -0.898783 0.34902 -0.282617 -0.877546 0.387351 0.0768588 -0.995614 0.0533441 0.0415141 -0.991146 0.126122 -0.9258 -0.236285 0.295067 -0.90381 -0.172411 0.391667 -0.677223 -0.649558 0.345606 -0.681474 -0.641103 0.352959 -0.308747 -0.927286 0.211698 -0.332022 -0.912237 0.239969 0.135994 -0.990377 0.0256816 0.0911261 -0.9929 0.0764598 -0.9655 -0.251462 0.0676527 -0.96686 -0.244937 0.072023 -0.737742 -0.673524 0.0458608 -0.745669 -0.664096 0.0543527 -0.335744 -0.941871 0.0124945 -0.352673 -0.935432 0.0242682 0.151592 -0.988124 -0.0251145 0.127203 -0.991816 -0.0110262 -0.85042 -0.216812 -0.479351 -0.6565 -0.239508 -0.715293 -0.517828 -0.578385 -0.630337 -0.514588 -0.594733 -0.617651 -0.40489 -0.769667 -0.493637 -0.29858 -0.859798 -0.414243 -0.282014 -0.880157 -0.381827 -0.157085 -0.960352 -0.230323 -0.028609 -0.991994 -0.122999 -0.0135995 -0.995267 -0.0962185 -0.800579 0.0590502 -0.596311 0.0812207 -0.992664 -0.089561 -0.0211439 -0.991118 -0.131296 -0.305143 -0.896165 -0.322143 -0.365281 -0.866946 -0.339078 -0.623867 -0.612589 -0.485308 -0.642901 -0.591844 -0.486208 -0.809035 -0.217709 -0.545954 -0.650331 -0.198668 -0.733213 0.113538 -0.992179 -0.0518629 0.0652803 -0.996504 -0.0521372 -0.349467 -0.92373 -0.156831 -0.375363 -0.913868 -0.15475 -0.727853 -0.647613 -0.225449 -0.733266 -0.642008 -0.223934 -0.942128 -0.230735 -0.243219 -0.938468 -0.241437 -0.246954 -0.0580581 -0.990613 0.123756 -0.28903 -0.115792 0.950292 -0.330078 -0.200222 0.922475 -0.278725 -0.314682 0.907352 -0.247533 -0.575004 0.779807 -0.058072 -0.990617 0.123715 -0.124789 -0.928149 0.350666 -0.189926 -0.852064 0.487765 -0.154148 -0.802425 0.5765 -0.293476 -0.53436 0.792674 -0.00647284 -0.990921 0.13429 -0.00643971 -0.990907 0.134391 -0.0201724 -0.852732 0.521959 -0.0202051 -0.852777 0.521884 -0.0303632 -0.573489 0.81865 -0.0304788 -0.573706 0.818494 -0.0354725 -0.202943 0.978548 -0.0356758 -0.20336 0.978454 0.0622234 -0.990278 0.124413 0.0627263 -0.990162 0.125076 0.173133 -0.852033 0.49403 0.174874 -0.850558 0.495955 0.254164 -0.574164 0.778291 0.256888 -0.570271 0.780256 0.293037 -0.205749 0.933701 0.296236 -0.199289 0.934092 -0.111671 -0.196141 -0.974196 -0.0519691 -0.99633 -0.0680188 -0.215948 -0.958463 -0.186319 -0.108782 -0.981988 -0.154484 -0.267582 -0.880041 -0.392337 -0.428901 -0.768474 -0.474859 -0.31003 -0.833721 -0.456936 -0.463562 -0.557335 -0.688831 -0.484267 -0.595513 -0.640975 -0.500134 -0.196052 -0.843463 -0.540222 -0.241368 -0.806165 -0.358683 -0.193404 -0.913204 -0.358433 -0.194189 -0.913135 -0.306041 -0.55344 -0.774625 -0.306175 -0.553184 -0.774755 -0.205805 -0.831773 -0.515556 -0.206587 -0.830943 -0.516581 -0.0723318 -0.982232 -0.173172 -0.073848 -0.981723 -0.175404 0.0539906 -0.196279 -0.979061 -0.0358125 -0.0380076 -0.998636 -0.0304365 -0.554369 -0.831714 -0.0304523 -0.554321 -0.831746 -0.0207477 -0.832494 -0.553646 -0.0208265 -0.832332 -0.553887 -0.00770098 -0.982523 -0.185983 -0.00784869 -0.982416 -0.18654 0.292021 -0.194421 -0.936442 0.29191 -0.193874 -0.93659 0.248963 -0.553909 -0.794483 0.248976 -0.554046 -0.794383 0.167312 -0.83174 -0.529353 0.167296 -0.832275 -0.528518 0.0587092 -0.982115 -0.178894 0.0585695 -0.982444 -0.177126 0.447626 -0.202011 0.871104 0.447787 -0.200347 0.871406 0.38454 -0.573018 0.723726 0.385906 -0.568805 0.726318 0.258626 -0.850433 0.458122 0.262035 -0.845908 0.464518 0.0904531 -0.988921 0.117703 0.0960978 -0.987096 0.128091 0.448427 -0.202916 0.870482 0.448514 -0.201982 0.870654 0.38632 -0.575303 0.72096 0.387086 -0.57293 0.722437 0.260512 -0.852829 0.452567 0.262433 -0.850303 0.456196 0.0917377 -0.989738 0.109553 0.094929 -0.988768 0.115436 0.44454 -0.194172 -0.874461 0.44442 -0.196343 -0.874037 0.377624 -0.553237 -0.742516 0.376161 -0.558811 -0.739076 0.253748 -0.828864 -0.498594 0.249915 -0.835052 -0.490134 0.0915847 -0.979487 -0.179491 0.0851516 -0.982515 -0.16557 0.443408 -0.192158 -0.87548 0.443285 -0.194167 -0.875099 0.375436 -0.548053 -0.747453 0.374063 -0.553224 -0.744325 0.251996 -0.823044 -0.509015 0.248446 -0.828845 -0.501289 0.0913309 -0.976455 -0.195432 0.0853914 -0.979465 -0.182639 0.51759 -0.190195 -0.834222 0.51891 -0.192354 -0.832906 0.437504 -0.545758 -0.714659 0.438213 -0.547341 -0.713013 0.292472 -0.821643 -0.489248 0.292747 -0.822556 -0.487545 0.103544 -0.976182 -0.190652 0.103583 -0.976466 -0.189171 0.712276 -0.186016 -0.676802 0.713228 -0.192209 -0.674063 0.604465 -0.540823 -0.584921 0.603838 -0.545211 -0.581485 0.405983 -0.818909 -0.405666 0.404561 -0.821289 -0.402261 0.14423 -0.975925 -0.163609 0.142783 -0.976592 -0.160876 0.895346 -0.185451 -0.404925 0.895289 -0.19425 -0.400905 0.761116 -0.541909 -0.356423 0.758767 -0.547794 -0.352413 0.511615 -0.820707 -0.254344 0.508609 -0.823585 -0.251047 0.1816 -0.976892 -0.112711 0.179369 -0.977539 -0.110654 0.196994 -0.979026 -0.0519724 0.199002 -0.978574 -0.0528401 0.557249 -0.827008 -0.0743758 0.561306 -0.824061 -0.0765409 0.829919 -0.551354 -0.0851122 0.834046 -0.544541 -0.0885521 0.976973 -0.196615 -0.0828604 0.947384 -0.0590218 0.31461 0.970227 -0.197203 0.140605 0.978692 -0.1858 -0.0874105 0.168052 -0.983468 0.0674435 0.168161 -0.983448 0.0674725 0.470751 -0.836547 0.280326 0.474204 -0.834383 0.280953 0.696926 -0.560334 0.447571 0.702027 -0.554025 0.447453 0.508318 -0.559444 0.654703 0.50454 -0.564219 0.653526 0.344204 -0.839671 0.42009 0.341987 -0.841194 0.418854 0.122564 -0.985824 0.114585 0.122817 -0.985772 0.114756 0.193402 -0.981073 0.00954841 0.194435 -0.98087 0.00947272 0.544649 -0.831505 0.109348 0.548833 -0.828834 0.108703 0.808971 -0.555732 0.191648 0.814175 -0.548749 0.18972 0.95098 -0.187718 0.245761 0.814053 -0.200951 0.544918 0.818371 -0.19001 0.542369 0.586696 -0.201938 0.784225 0.590651 -0.193436 0.783399 0.100034 -0.198388 0.975005 0.104383 -0.984419 0.141506 -0.373814 -0.815837 0.441218 0.663374 -0.731196 0.159019 0.312586 -0.813913 0.489729 0.402339 -0.651539 0.643133 0.886187 -0.417743 0.200408 0.459763 -0.488527 0.741593 0.501307 -0.282387 0.817893 0.951548 -0.136259 0.275662 0.518807 -0.086988 0.850454 0.360343 -0.194638 0.912288 0.35878 -0.197777 0.912229 0.309074 -0.557775 0.770299 0.307984 -0.559287 0.769639 0.208896 -0.836821 0.506057 0.208615 -0.837053 0.505789 0.0743712 -0.984602 0.158205 0.0750791 -0.984417 0.159019 -0.0664351 -0.198542 0.977838 0.0355277 -0.113119 0.992946 0.0310761 -0.559612 0.828172 0.0309023 -0.559927 0.827966 0.0216076 -0.838202 0.544932 0.0215712 -0.838248 0.544862 0.00859841 -0.985126 0.171621 0.00867505 -0.985092 0.171812 -0.293149 -0.197602 0.935424 -0.292349 -0.195631 0.936088 -0.250462 -0.559822 0.789853 -0.250172 -0.558906 0.790593 -0.168263 -0.837831 0.519353 -0.168234 -0.837716 0.519547 -0.0584752 -0.984828 0.163382 -0.0585071 -0.984949 0.162645 0.816529 -0.213573 0.536346 0.595181 -0.085174 0.799065 0.0591235 -0.991556 0.11542 0.521905 -0.486114 0.700934 0.45223 -0.574398 0.682316 0.446375 -0.649934 0.61509 0.311595 -0.857464 0.409468 0.303472 -0.814017 0.495259 0.158409 -0.974274 0.160302 0.735018 -0.0772029 0.673638 0.014015 -0.99746 0.0698342 0.0808158 -0.992105 0.0958949 0.346025 -0.879225 0.32746 0.388064 -0.857248 0.338425 0.609471 -0.597207 0.521429 0.627127 -0.578572 0.521504 0.759174 -0.206418 0.61729 0.580041 -0.201739 0.789211 0.508841 -0.282247 0.813276 0.0229934 -0.999621 0.0151099 0.0444319 -0.998904 0.0147007 0.427303 -0.890527 0.15612 0.441083 -0.884063 0.154528 0.745078 -0.611685 0.265897 0.751211 -0.605081 0.26374 0.919837 -0.220326 0.324586 0.920884 -0.217634 0.323432 -0.445628 -0.196079 0.873481 -0.445507 -0.198355 0.873029 -0.37975 -0.558066 0.737803 -0.378233 -0.563813 0.734204 -0.255463 -0.834233 0.488665 -0.25146 -0.840553 0.479833 -0.0918637 -0.982111 0.164377 -0.0851455 -0.985023 0.149936 -0.44435 -0.193615 0.874681 -0.444202 -0.196086 0.874205 -0.377366 -0.551829 0.743693 -0.375694 -0.558081 0.739864 -0.253781 -0.827291 0.501183 -0.24943 -0.834257 0.491731 -0.0921259 -0.978686 0.183541 -0.0848341 -0.982139 0.167949 0.120317 -0.990781 0.0622707 0.166392 -0.98198 0.0896026 0.169939 -0.982806 0.0722074 0.413131 -0.904401 0.106689 0.502928 -0.856532 0.11583 0.936256 -0.31657 0.152345 0.936259 -0.316559 0.152344 0.707753 -0.691488 0.144673 0.557987 -0.820378 0.125025 0.799596 -0.578588 0.160878 0.964261 -0.20422 0.168802 0.934725 -0.315944 0.16269 0.962491 -0.218961 0.160208 0.965682 -0.204472 0.160157 0.777635 -0.615087 0.1302 0.804155 -0.579405 0.132756 0.443561 -0.893067 0.0753993 0.508134 -0.857282 0.0828734 0.02448 -0.999679 0.00647197 0.127299 -0.991687 0.0187573 -0.803105 -0.199502 -0.561446 -0.110824 -0.978496 0.173967 -0.314349 -0.825501 0.468756 -0.469524 -0.549156 0.691358 -0.553328 -0.190755 0.810827 -0.554051 -0.192708 0.809871 -0.721456 -0.193665 0.664827 -0.779339 -0.102514 0.61816 -0.822573 -0.192113 0.535226 -0.926171 -0.193944 0.323409 -0.926435 -0.18755 0.326409 -0.980635 -0.195845 -0.000351957 -0.982251 -0.187547 0.00313331 -0.111207 -0.97807 0.176103 -0.153644 -0.978449 0.137955 -0.155384 -0.977786 0.140679 -0.185525 -0.97889 0.0857607 -0.187738 -0.978315 0.0874921 -0.197751 -0.979876 0.0271467 -0.199151 -0.979579 0.0276211 -0.188665 -0.98151 -0.0323142 -0.188538 -0.981534 -0.0323132 -0.314471 -0.824365 0.47067 -0.43672 -0.82458 0.359645 -0.438183 -0.822553 0.362495 -0.527254 -0.825773 0.200256 -0.529885 -0.823483 0.202726 -0.560101 -0.828164 0.0207458 -0.563248 -0.825992 0.0221241 -0.531377 -0.831857 -0.160164 -0.53422 -0.830076 -0.15995 -0.469251 -0.54748 0.69287 -0.651404 -0.547769 0.524996 -0.652081 -0.544463 0.527589 -0.786177 -0.549245 0.283294 -0.78819 -0.544824 0.286221 -0.833875 -0.551842 0.0110822 -0.837237 -0.546673 0.0134949 -0.789031 -0.555531 -0.262326 -0.793135 -0.55022 -0.261139 -0.926599 -0.188987 -0.325113 -0.922118 -0.0943192 -0.375238 -0.958273 -0.196728 -0.20739 -0.697328 -0.196635 -0.689252 -0.773749 -0.113723 -0.623202 -0.659231 -0.554993 -0.507344 -0.655367 -0.559732 -0.507144 -0.444805 -0.83511 -0.323635 -0.442811 -0.836373 -0.323109 -0.157015 -0.983844 -0.0860046 -0.158213 -0.983615 -0.0864302 -0.521795 -0.194237 -0.830663 -0.518591 -0.200922 -0.83108 -0.448665 -0.559959 -0.696524 -0.446008 -0.563381 -0.69547 -0.303459 -0.839909 -0.449962 -0.302378 -0.840684 -0.449242 -0.107593 -0.985961 -0.127691 -0.10872 -0.98572 -0.128593 0.25387 -0.961467 0.105501 0.883117 -0.438588 0.16657 0.938378 -0.317434 0.136682 0.934295 -0.31577 0.165476 0.163973 -0.98086 0.10501 0.410735 -0.903509 0.122347 0.55581 -0.819551 0.139326 0.96755 -0.193367 0.162652 0.955588 -0.258205 0.14206 0.955471 -0.258151 0.142945 0.938375 -0.317442 0.136682 0.780324 -0.603968 0.162224 0.699078 -0.703918 0.125654 0.691536 -0.700734 0.175359 0.70166 -0.688878 0.18199 0.598086 -0.787886 0.146725 0.253072 -0.96165 0.105758 0.249337 -0.959745 0.12931 0.165594 -0.982148 0.0892445 0.163421 -0.980505 0.1091 -0.00581512 -0.998126 0.0609106 -0.372449 -0.20297 -0.905585 -0.372686 -0.200196 -0.906105 -0.319751 -0.575476 -0.75272 -0.321687 -0.568473 -0.757203 -0.214317 -0.853067 -0.475758 -0.219121 -0.845559 -0.486842 -0.0735093 -0.990007 -0.120346 -0.0814572 -0.987023 -0.138385 -0.373662 -0.205066 -0.904613 -0.373833 -0.20293 -0.905024 -0.322251 -0.580664 -0.747652 -0.323708 -0.575359 -0.751116 -0.216574 -0.858507 -0.464824 -0.220234 -0.852894 -0.47336 -0.0744124 -0.991816 -0.103747 -0.0804725 -0.989804 -0.117523 0.536778 -0.832915 -0.134616 -0.338302 -0.204106 -0.918636 -0.334369 -0.206256 -0.919595 -0.292461 -0.580185 -0.760165 -0.289701 -0.581423 -0.760277 -0.197454 -0.858552 -0.473182 -0.196022 -0.85898 -0.472999 -0.0692508 -0.991957 -0.105947 -0.0690814 -0.991974 -0.105906 -0.135045 -0.20365 -0.969685 -0.133434 -0.206851 -0.969231 -0.117083 -0.577218 -0.808153 -0.115864 -0.579131 -0.806959 -0.0793398 -0.857085 -0.509028 -0.0786097 -0.857814 -0.507914 -0.0276733 -0.992465 -0.11936 -0.0274557 -0.992521 -0.11895 0.20116 -0.207439 -0.957342 0.198814 -0.202463 -0.958896 0.174754 -0.578916 -0.796441 0.173576 -0.576216 -0.798653 0.119087 -0.857158 -0.501098 0.118715 -0.856386 -0.502504 0.0427282 -0.992162 -0.117423 0.0427887 -0.992206 -0.117032 0.107289 -0.989928 -0.0923624 0.107276 -0.989936 -0.0922928 0.301433 -0.850857 -0.430326 0.301149 -0.853074 -0.426115 0.442581 -0.569674 -0.692527 0.443719 -0.576513 -0.68611 0.508891 -0.196808 -0.838031 0.821398 -0.00490071 -0.570334 0.710818 -0.196854 -0.675268 0.513398 -0.208923 -0.832331 0.789401 -0.563434 -0.243696 0.198763 -0.977633 0.0687477 0.187474 -0.982232 0.00862272 0.189261 -0.981901 0.00709353 0.262818 -0.963858 0.0436492 0.567008 -0.820936 0.0675772 0.531243 -0.837425 -0.128454 0.794618 -0.551503 -0.253825 0.895744 -0.444142 0.0194957 0.84079 -0.53939 0.0461583 0.793444 -0.607901 0.0300651 0.609919 -0.790884 0.0500086 0.157928 -0.986239 -0.0488991 0.157419 -0.986364 -0.0480178 0.446297 -0.842474 -0.301755 0.443745 -0.845969 -0.295679 0.657864 -0.560875 -0.502627 0.656461 -0.570889 -0.493097 0.758639 -0.208465 -0.61726 0.924618 -0.185674 -0.332577 0.92481 -0.205653 -0.320052 0.983308 -0.181804 -0.00721351 0.97936 -0.202069 0.00465998 -0.272107 -0.144741 0.951319 -0.0424373 -0.459226 0.887305 -0.0904169 -0.618726 0.780386 -0.324129 -0.239597 0.915169 0.120879 -0.878736 0.461749 0.0942409 -0.84616 0.52453 0.245969 -0.773349 0.584321 0.240266 -0.767738 0.594012 0.26381 -0.752439 0.603522 0.286647 -0.774637 0.563712 -0.106442 -0.58313 0.805376 -0.00208586 -0.532091 0.846684 -0.00618214 -0.526142 0.850374 0.00961352 -0.515547 0.856807 0.084052 -0.615367 0.783746 -0.0363328 -0.932769 0.35864 -0.0394597 -0.914442 0.402789 -0.204943 -0.663275 0.719767 -0.204673 -0.641781 0.739071 -0.329048 -0.231331 0.91554 -0.284255 -0.223024 0.932448 -0.2881 -0.208131 0.934709 -0.250506 -0.189513 0.949385 -0.25177 -0.186989 0.949551 -0.245971 -0.183023 0.951841 -0.157641 -0.338407 0.927701 -0.338932 -0.241491 0.909289 -0.338918 -0.242529 0.909018 -0.239415 -0.668022 0.704576 -0.238912 -0.670404 0.702481 -0.083908 -0.93841 0.335181 -0.0826374 -0.940249 0.330308 -0.338147 -0.240388 0.909874 -0.338129 -0.241451 0.909599 -0.237746 -0.665444 0.707574 -0.237218 -0.667912 0.705423 -0.0822418 -0.936326 0.341365 -0.080918 -0.93826 0.336334 -0.912908 -0.218268 0.344902 0.0269411 -0.67553 0.73684 0.0197965 -0.651252 0.758603 0.213145 -0.856892 0.469366 0.208883 -0.819212 0.534098 -0.379193 -0.111932 0.918523 -0.367429 -0.19851 0.90862 -0.189304 -0.42148 0.886859 -0.201376 -0.362805 0.909846 -0.141587 -0.513716 0.846197 -0.595665 -0.126704 0.793177 -0.576425 -0.229087 0.784381 -0.3977 -0.465491 0.790666 -0.37307 -0.52874 0.762399 -0.137028 -0.733325 0.665926 -0.11962 -0.75994 0.638891 0.147955 -0.887945 0.435504 0.151496 -0.890843 0.428308 -0.800572 -0.163453 0.576513 -0.793012 -0.241235 0.559408 -0.61856 -0.523767 0.585706 -0.595406 -0.579993 0.555967 -0.334386 -0.798908 0.499932 -0.305871 -0.830568 0.465402 0.00890973 -0.943474 0.331326 0.0334969 -0.95338 0.299907 -0.967513 -0.195219 0.160649 -0.964635 -0.120836 0.234261 -0.791978 -0.547212 0.270793 -0.763993 -0.597404 0.243771 -0.517235 -0.822753 0.235681 -0.463931 -0.86333 0.198567 -0.158787 -0.973442 0.164918 -0.0833576 -0.989392 0.118977 -0.98003 -0.194908 0.0394042 -0.979422 -0.199506 0.0304828 -0.830662 -0.554905 0.0456152 -0.825167 -0.564368 0.024261 -0.555127 -0.830533 0.0452699 -0.541452 -0.840619 0.0137705 -0.195097 -0.980029 0.0384819 -0.172566 -0.984998 -6.28707e-05 0.257211 -0.953082 0.159619 0.691022 -0.689705 0.216324 0.521978 -0.240563 0.818333 0.682472 -0.250524 0.686636 0.69221 -0.230643 0.683849 0.865282 -0.257762 0.429937 0.876659 -0.231916 0.421525 0.939471 -0.256761 0.226864 0.944599 -0.247303 0.215811 0.253954 -0.953636 0.161511 0.240118 -0.947183 0.212575 0.232102 -0.949369 0.211723 0.187513 -0.942311 0.277289 0.181697 -0.944267 0.274491 0.117188 -0.939345 0.322333 0.114587 -0.940569 0.319686 0.0367433 -0.938242 0.344023 0.03665 -0.938321 0.343818 -0.0454629 -0.938907 0.341156 -0.0452084 -0.937725 0.344425 0.684846 -0.69401 0.222119 0.642486 -0.673877 0.364831 0.628288 -0.686415 0.366181 0.503229 -0.666678 0.54982 0.492887 -0.676593 0.547069 0.313769 -0.66295 0.67974 0.308759 -0.668957 0.676139 0.0942586 -0.662528 0.743083 0.0936348 -0.66369 0.742124 -0.132679 -0.665252 0.734735 -0.131899 -0.661182 0.73854 0.401085 -0.0684309 0.913481 0.43169 -0.243694 0.86848 0.180898 -0.238029 0.954263 0.133053 -0.127147 0.982919 0.0241226 -0.241029 0.970218 -0.188121 -0.239822 0.952416 -0.186339 -0.232626 0.954549 -0.971526 -0.193356 -0.136934 -0.812034 -0.192296 -0.55102 -0.48639 -0.190977 -0.852615 -0.486394 -0.190967 -0.852615 -0.414786 -0.547075 -0.727091 -0.414787 -0.547073 -0.727092 -0.279511 -0.825718 -0.489962 -0.279509 -0.82572 -0.489961 -0.0987506 -0.979941 -0.173103 -0.0987504 -0.979941 -0.173103 -0.679191 -0.194956 -0.707595 -0.801254 -0.111148 -0.58791 -0.6749 -0.547073 -0.495199 -0.674902 -0.54707 -0.495199 -0.45479 -0.82572 -0.333695 -0.454791 -0.825719 -0.333696 -0.160678 -0.979941 -0.117895 -0.160679 -0.97994 -0.117895 -0.921516 -0.194585 -0.336074 -0.975257 -0.0640691 -0.211588 -0.818055 -0.54707 -0.177482 -0.818054 -0.547072 -0.177483 -0.551257 -0.825719 -0.119599 -0.551257 -0.825719 -0.119599 -0.194759 -0.97994 -0.0422545 -0.194759 -0.979941 -0.0422545 0.954196 -0.252241 0.160889 0.954713 -0.250473 0.16058 0.698976 -0.690953 0.184437 0.701954 -0.688012 0.18412 0.26331 -0.951283 0.160402 0.269585 -0.949508 0.160495 0.953379 -0.253637 0.163516 0.953875 -0.251943 0.16324 0.696596 -0.694275 0.180931 0.699489 -0.691428 0.18067 0.258423 -0.954116 0.151261 0.264538 -0.952416 0.151407 -0.0592808 -0.980785 -0.185868 -0.0592808 -0.980785 -0.185868 -0.168815 -0.83147 -0.529301 -0.168815 -0.83147 -0.529301 -0.252651 -0.555566 -0.792158 -0.252652 -0.555574 -0.792152 -0.298024 -0.195093 -0.934409 -0.298024 -0.195093 -0.934409 0.213803 -0.966849 0.139614 0.276567 -0.955458 0.103009 0.458882 -0.878079 0.135665 0.962215 -0.260685 0.0786508 0.981889 -0.188524 -0.018759 0.902945 -0.421826 0.0821801 0.70828 -0.69463 0.125815 0.796713 -0.604295 -0.00871612 0.622594 -0.772843 0.122846 -0.28916 -0.21193 -0.933527 -0.29441 -0.195091 -0.935554 -0.217748 -0.597336 -0.771865 -0.239987 -0.555517 -0.79612 -0.10587 -0.875223 -0.471992 -0.150834 -0.831322 -0.534932 0.0271386 -0.995746 -0.088053 -0.041198 -0.980608 -0.191599 -0.260989 -0.239035 -0.935279 -0.269497 -0.210388 -0.939739 -0.129718 -0.660566 -0.739477 -0.164707 -0.592859 -0.788283 0.0329077 -0.927645 -0.37201 -0.0319931 -0.868357 -0.494906 0.18974 -0.978467 0.0812459 0.104163 -0.988178 -0.112494 -0.244742 -0.2428 -0.938696 -0.247033 -0.236089 -0.939807 -0.0848112 -0.668404 -0.738947 -0.0935147 -0.653191 -0.751396 0.0961214 -0.929121 -0.357063 0.0815891 -0.918109 -0.38784 0.253553 -0.96073 0.112732 0.237385 -0.96916 0.0661603 -0.259181 -0.2361 -0.936527 -0.256388 -0.245188 -0.934959 -0.128897 -0.654316 -0.745155 -0.117825 -0.675071 -0.728283 0.0306331 -0.92292 -0.383771 0.0499901 -0.938281 -0.342242 0.182892 -0.980976 0.0650895 0.205861 -0.97019 0.127879 0.0272874 -0.92345 -0.382749 -0.113019 -0.651967 -0.749777 0.227193 -0.209658 -0.951014 0.0305991 -0.251841 -0.967285 -0.00983231 -0.206435 -0.978411 -0.207121 -0.239262 -0.948607 -0.229027 -0.232159 -0.94533 0.237912 -0.9663 0.0982985 0.235325 -0.967518 0.092367 0.248711 -0.965753 0.0739156 0.245614 -0.966794 0.0705868 0.24843 -0.966691 0.0615728 0.233216 -0.970946 0.0536094 0.2333 -0.970744 0.0568091 0.191871 -0.980088 0.0511269 0.195954 -0.978693 0.0613399 0.155019 -0.985408 0.0702865 0.160666 -0.984361 0.0722518 0.0297293 -0.923606 -0.382189 0.158684 -0.898987 -0.408218 0.165306 -0.902629 -0.39741 0.338934 -0.863351 -0.373831 0.343707 -0.870616 -0.351984 0.46896 -0.835469 -0.286475 0.465575 -0.846901 -0.256902 0.550968 -0.818069 -0.164914 0.535882 -0.833636 -0.133726 0.21217 -0.970292 0.116265 0.45147 -0.891562 0.0359444 0.593786 -0.804621 0.00176069 0.611988 -0.790763 -0.0128434 0.784753 -0.612286 -0.0962711 -0.100686 -0.654759 -0.749102 0.0848281 -0.619183 -0.780651 0.107464 -0.640769 -0.760175 0.372168 -0.58046 -0.724263 0.392509 -0.609839 -0.6885 0.599536 -0.551475 -0.580028 0.607703 -0.584774 -0.537342 0.757314 -0.53418 -0.375669 0.751009 -0.568752 -0.335421 0.84861 -0.519174 -0.101587 0.88215 -0.450305 -0.137975 0.367211 -0.117046 -0.922744 0.341197 -0.246777 -0.90702 0.596631 -0.177779 -0.782577 0.61263 -0.135132 -0.778732 0.720664 -0.207621 -0.661466 0.835422 -0.164935 -0.524277 0.849052 -0.21746 -0.481479 0.961049 -0.165047 -0.221686 0.959506 -0.210254 -0.187463 0.396975 -0.213737 -0.892596 0.396713 -0.206248 -0.894472 0.400396 -0.221034 -0.889284 0.411149 -0.618283 -0.669837 0.419299 -0.579619 -0.698735 0.339331 -0.885769 -0.316651 0.36744 -0.847104 -0.38393 0.19964 -0.975139 0.0961661 0.254904 -0.966944 -0.00650935 0.261906 -0.959518 -0.103592 0.241351 -0.969402 0.0448228 0.342505 -0.878747 -0.332406 0.346168 -0.867867 -0.356335 0.391623 -0.194912 -0.899245 0.416958 -0.439949 -0.795356 0.408914 -0.599651 -0.687901 0.409186 -0.603139 -0.684683 0.388007 -0.779628 -0.491559 0.458414 -0.197064 -0.866615 0.453427 -0.188167 -0.871205 0.580164 -0.549031 -0.601643 0.572764 -0.527523 -0.627423 0.581302 -0.785799 -0.211205 0.583908 -0.766339 -0.267912 0.461828 -0.858436 0.223164 0.486263 -0.862683 0.139018 0.45489 -0.197194 -0.868441 0.455798 -0.198893 -0.867577 0.569788 -0.550297 -0.610341 0.571194 -0.554983 -0.604757 0.568364 -0.789877 -0.230338 0.567232 -0.794665 -0.21623 0.453058 -0.870124 0.193967 0.445539 -0.868608 0.216832 0.352776 -0.195083 -0.915146 0.354541 -0.258809 -0.898509 0.322591 -0.4423 -0.836843 0.28536 -0.608755 -0.740261 0.26383 -0.707071 -0.656082 0.218961 -0.793358 -0.568013 0.159086 -0.896871 -0.412691 0.100212 -0.965897 -0.238749 0.0701718 -0.980785 -0.182036 0.0817341 -0.993626 -0.0776391 0.218445 -0.865971 -0.449862 0.0802503 -0.993891 -0.0757688 0.36117 -0.208053 -0.908994 0.361231 -0.208275 -0.908919 0.317106 -0.588044 -0.744076 0.317209 -0.588743 -0.743478 0.217589 -0.866723 -0.448828 0.36088 -0.207777 -0.909173 0.360957 -0.208064 -0.909076 0.316464 -0.587385 -0.744869 0.316564 -0.588071 -0.744285 0.217261 -0.865333 -0.45166 0.217264 -0.866032 -0.450318 0.0804295 -0.993521 -0.0802945 0.0803044 -0.993699 -0.0781903 0.0345926 -0.964036 -0.26351 0.0933392 -0.69698 -0.71099 0.12596 -0.252025 -0.959488 0.125962 -0.25203 -0.959487 -0.326611 -0.25203 -0.910937 -0.32661 -0.252032 -0.910937 -0.706923 -0.252032 -0.660863 -0.706923 -0.252032 -0.660863 -0.930847 -0.252028 -0.264587 -0.930847 -0.252026 -0.264586 0.0933369 -0.696974 -0.710996 -0.242023 -0.696974 -0.67502 -0.24202 -0.696978 -0.675017 -0.523839 -0.696978 -0.489708 -0.52384 -0.696977 -0.489708 -0.689769 -0.696979 -0.196061 -0.689767 -0.69698 -0.196062 0.0345933 -0.964037 -0.263507 -0.0896971 -0.964037 -0.250174 -0.0896985 -0.964037 -0.250175 -0.194146 -0.964037 -0.181496 -0.194144 -0.964037 -0.181495 -0.255642 -0.964037 -0.0726644 -0.255643 -0.964037 -0.0726643 0.114833 -0.991126 -0.0669545 0.456086 -0.573288 -0.680681 0.710358 -0.198924 -0.675145 0.525456 -0.214695 -0.823288 0.51875 -0.196488 -0.83204 0.820598 -0.062444 -0.568084 0.773439 -0.213653 -0.596778 0.923652 -0.185678 -0.335248 0.938368 -0.137363 -0.317171 0.964853 -0.199075 -0.171547 0.984033 -0.177093 0.0178172 0.978217 -0.204602 0.035048 0.923643 -0.174092 0.341432 0.913856 -0.199087 0.353882 0.114603 -0.991225 -0.0658771 0.166113 -0.985907 -0.0198582 0.164748 -0.986179 -0.0175894 0.195214 -0.980028 0.0379114 0.191938 -0.980567 0.0406119 0.201755 -0.974283 0.10034 0.196575 -0.975145 0.102233 0.186296 -0.969328 0.160303 0.180243 -0.970461 0.160371 0.151406 -0.965544 0.211662 0.146102 -0.966757 0.209846 0.457668 -0.583776 -0.670631 0.67558 -0.56186 -0.477394 0.673516 -0.57591 -0.463361 0.805317 -0.549299 -0.223013 0.797809 -0.565759 -0.208369 0.841096 -0.537971 0.0560883 0.82908 -0.555037 0.0675307 0.782816 -0.529026 0.327614 0.769252 -0.544934 0.333615 0.64009 -0.522997 0.562814 0.628495 -0.536108 0.563544 0.795266 -0.179415 0.579105 0.773245 -0.0958234 0.626826 0.687065 -0.189667 0.701404 0.101132 -0.963091 0.249457 0.0980114 -0.964056 0.246963 0.22549 -0.86821 0.442002 0.273558 -0.794378 0.542338 0.417917 -0.807368 0.416537 0.427608 -0.801273 0.418465 0.513272 -0.815875 0.26627 0.525169 -0.808865 0.264453 0.55591 -0.826224 0.0912073 0.567223 -0.819154 0.0851188 0.538159 -0.837799 -0.0920688 0.546371 -0.831423 -0.101071 0.457361 -0.849406 -0.263306 0.461348 -0.844309 -0.272581 0.313401 -0.859227 -0.404363 0.31403 -0.855665 -0.411366 0.50601 -0.187732 0.84185 0.513257 -0.174247 0.84036 0.460218 -0.417782 0.783363 0.413853 -0.517303 0.749082 0.406978 -0.577494 0.707721 0.309003 -0.761133 0.570258 -0.194917 -0.980784 -0.00831906 -0.258738 -0.965921 -0.0071774 -0.441889 -0.896872 -0.0188598 -0.60821 -0.793352 -0.0259584 -0.706668 -0.707104 -0.0250006 -0.792633 -0.608761 -0.0338295 -0.896058 -0.442286 -0.0382437 -0.965204 -0.258819 -0.0373312 -0.979894 -0.195088 -0.0418219 0.329838 -0.417435 0.846732 0.364207 -0.184812 0.912797 0.358985 -0.245737 0.900413 0.35918 -0.245742 0.900333 0.358228 -0.25072 0.89934 0.0947606 -0.950526 0.29584 0.0915712 -0.953821 0.286078 0.290331 -0.57814 0.762537 0.258093 -0.681197 0.685097 0.259475 -0.681236 0.684536 0.257373 -0.688706 0.677823 0.0731352 -0.963592 0.257182 0.091222 -0.950424 0.297276 0.161865 -0.86814 0.469184 0.222178 -0.761586 0.608789 -0.896887 -0.441112 0.031843 -0.608799 -0.786281 0.10548 -0.614467 -0.69646 0.370641 0.218271 -0.837525 0.500908 -0.294142 -0.834769 0.465447 -0.797712 -0.514553 0.314468 -0.971928 -0.222483 0.0765303 0.205622 -0.843741 0.495803 0.20932 -0.888915 0.407451 0.0666985 -0.904761 0.420666 0.079133 -0.983856 0.160518 -0.199802 -0.966896 0.158719 -0.303246 -0.830222 0.467733 -0.297453 -0.876917 0.377543 -0.392411 -0.843096 0.3677 -0.379447 -0.916564 0.126214 -0.443808 -0.887537 0.123743 -0.73303 -0.6041 0.312618 -0.728275 -0.638513 0.248833 -0.767759 -0.596368 0.23429 -0.758093 -0.648963 0.0643596 -0.793212 -0.605873 0.0610919 -0.972318 -0.22081 0.0764297 -0.970908 -0.233215 0.0542927 -0.97524 -0.215788 0.0484033 -0.971971 -0.234802 -0.011888 -0.980704 -0.194996 -0.0139919 0.127298 -0.917431 0.376982 0.366715 -0.230346 0.901366 0.357959 -0.250713 0.899449 0.296914 -0.641949 0.706925 0.26275 -0.688824 0.675636 0.133336 -0.953861 0.269018 0.378259 -0.211315 0.901258 0.371853 -0.230185 0.8993 0.337545 -0.59564 0.728887 0.310856 -0.641521 0.701298 0.236184 -0.873293 0.426117 0.182776 -0.916816 0.355024 -0.982367 -0.178403 0.0559307 -0.981921 -0.180701 0.0563748 -0.822414 -0.503006 0.265746 -0.817953 -0.509699 0.266757 -0.518582 -0.739514 0.429176 -0.507241 -0.747434 0.429009 -0.124027 -0.846476 0.517779 -0.105514 -0.851348 0.51388 0.292192 -0.805087 0.516196 0.315159 -0.802892 0.506003 -0.972151 -0.220052 0.0806144 -0.983152 -0.166745 0.074888 -0.795739 -0.544502 0.265173 -0.822082 -0.506651 0.259781 -0.615219 -0.688274 0.384427 -0.517113 -0.754141 0.404804 -0.296284 -0.808495 0.508479 -0.12272 -0.860682 0.494131 0.216453 -0.817924 0.533056 0.29295 -0.813702 0.502065 -0.122539 -0.488965 0.863653 -0.269343 -0.355212 0.895142 -0.481136 -0.150806 0.863577 -0.481562 -0.367115 0.795817 -0.549943 -0.0790834 0.83145 0.0243911 -0.608818 0.792935 0.318393 -0.761138 0.565062 0.228897 -0.873819 0.429007 0.267838 -0.842053 0.468199 0.255062 -0.844584 0.470767 0.265892 -0.788816 0.55414 0.278173 -0.783386 0.555811 0.264454 -0.749317 0.607115 0.259633 -0.752852 0.604818 0.141451 -0.674897 0.724227 -0.0730962 -0.5541 0.829234 0.0317473 -0.476482 0.878611 0.0591823 -0.556524 0.828721 0.187133 -0.50018 0.845459 0.182265 -0.584466 0.790683 0.316126 -0.560206 0.765659 0.286937 -0.59884 0.747702 -0.317912 -0.193753 0.928112 -0.203376 -0.10949 0.972959 -0.170795 -0.236681 0.956458 0.079491 -0.127811 0.988608 0.0760592 -0.226835 0.970959 0.311743 -0.184499 0.932082 0.291653 -0.217754 0.931408 -0.784896 -0.358034 0.505718 -0.0938782 -0.845273 0.526024 -0.983017 -0.148822 0.107371 -0.819416 -0.477605 0.31694 -0.804852 -0.520479 0.285157 -0.509097 -0.719327 0.47264 0.314084 -0.791156 0.524808 -0.976209 -0.204424 0.0723025 -0.954934 -0.0543353 0.291801 -0.872414 -0.258102 0.415064 -0.00957277 -0.770881 0.636908 -0.0926349 -0.748228 0.656942 -0.359368 -0.678317 0.64089 -0.10727 -0.8306 0.546439 -0.492638 -0.747385 0.445784 -0.482807 -0.603007 0.635044 -0.65859 -0.499242 0.563042 -0.557316 -0.291458 0.777464 -0.783734 -0.0626761 0.617926 -0.631287 -0.170581 0.756557 -0.485167 -0.371248 0.7917 -0.365976 -0.462467 0.80758 -0.277111 -0.514173 0.811687 -0.199105 -0.573562 0.794597 0.0410349 -0.672265 0.739172 -0.00821804 -0.645064 0.764084 0.117235 -0.701726 0.702735 0.321632 -0.796461 0.512058 0.321389 -0.762109 0.562048 0.345644 -0.761059 0.548926 0.355001 -0.742974 0.567419 0.338521 -0.738718 0.582837 0.316096 -0.195058 0.928459 0.29431 -0.607797 0.73754 0.211711 -0.893879 0.395168 0.332442 -0.801942 0.496358 0.35995 -0.533151 0.765628 0.335194 -0.186754 0.923454 0.328643 -0.810234 0.485298 0.32369 -0.811286 0.486867 0.305382 -0.849044 0.431122 0.250517 -0.858108 0.44821 0.13148 -0.977951 0.162249 0.358837 -0.540362 0.761082 0.355235 -0.541133 0.762223 0.350167 -0.575592 0.73897 0.31054 -0.582385 0.751261 0.241206 -0.791955 0.560916 0.335214 -0.189565 0.922874 0.334138 -0.189797 0.923217 0.334482 -0.203438 0.920182 0.320606 -0.205897 0.924564 0.298383 -0.442108 0.845877 0.282268 -0.959332 0.00260107 0.534724 -0.555466 -0.636811 0.90109 -0.128331 -0.414208 0.737935 -0.22658 -0.6357 0.697456 -0.151099 -0.700517 0.564478 -0.198479 -0.801231 0.532764 -0.193778 -0.82378 0.993368 0.0799947 -0.0825927 0.981619 -0.132271 -0.137582 0.920246 -0.207397 -0.331864 0.978618 -0.197559 -0.0572457 0.970774 -0.11153 0.212507 0.951131 -0.169597 0.258042 0.865554 -0.114542 0.487541 0.849689 -0.151311 0.505107 0.557098 -0.557559 -0.615442 0.691033 -0.505412 -0.516752 0.699516 -0.552551 -0.453172 0.854517 -0.459333 -0.242516 0.842834 -0.507314 -0.17962 0.904736 -0.42467 0.0332911 0.879598 -0.468941 0.0800162 0.870373 -0.40396 0.281544 0.84413 -0.440008 0.306329 0.774658 -0.394906 0.493917 0.758577 -0.417131 0.500562 0.629938 -0.396325 0.66791 0.629266 -0.397488 0.667853 0.685792 -0.12993 0.716106 0.63489 0.095762 0.766645 0.734751 -0.133072 0.665156 0.289546 -0.957061 0.0140101 0.354928 -0.933177 0.0566357 0.345767 -0.93496 0.0793407 0.412967 -0.894566 0.170909 0.406079 -0.896207 0.178644 0.429407 -0.865191 0.258947 0.424969 -0.866586 0.261592 0.422149 -0.846103 0.325423 0.420141 -0.846916 0.325905 0.40149 -0.834789 0.376741 0.403158 -0.833912 0.376901 0.372933 -0.829092 0.416566 0.377695 -0.825674 0.419058 0.339849 -0.828158 0.445709 0.370869 -0.792901 0.483492 0.464277 -0.156712 0.871716 0.468225 -0.144319 0.871744 0.422999 -0.518237 0.743305 0.487022 -0.408301 0.772075 0.404187 -0.643371 0.650159 0.524498 -0.635985 0.566061 0.52289 -0.637828 0.565475 0.605898 -0.651234 0.456926 0.615678 -0.642626 0.456039 0.662125 -0.67288 0.329884 0.681601 -0.657788 0.320523 0.687931 -0.703483 0.178502 0.711177 -0.685429 0.156249 0.66497 -0.746866 -0.00248673 0.684524 -0.727981 -0.0383612 0.563035 -0.800953 -0.203634 0.571269 -0.781364 -0.251243 0.460131 -0.825009 -0.328086 0.446327 -0.825576 -0.345278 0.298023 -0.195093 0.93441 0.298023 -0.195092 0.93441 0.272523 -0.4423 0.85446 0.272528 -0.442273 0.854473 0.24107 -0.608762 0.75584 0.24107 -0.608762 0.75584 0.184979 -0.793354 0.579976 0.184979 -0.793354 0.579976 0.134395 -0.896872 0.421378 0.134395 -0.896872 0.421377 0.0592812 -0.980785 0.185868 0.0592812 -0.980785 0.185868 0.489537 -0.199633 -0.848823 0.488394 -0.195074 -0.85054 0.437778 -0.566502 -0.698159 0.436782 -0.555192 -0.707801 0.316647 -0.842401 -0.435999 0.318184 -0.830205 -0.457732 0.145845 -0.983783 -0.104409 0.150695 -0.978773 -0.138905 0.510821 -0.200029 -0.836092 0.509473 -0.196462 -0.837759 0.495617 -0.566427 -0.658426 0.493886 -0.557699 -0.66712 0.398564 -0.838523 -0.371518 0.399055 -0.829677 -0.390372 0.236048 -0.971469 -0.0230112 0.240104 -0.969354 -0.0519939 0.0140578 -0.979682 0.200062 -0.260032 -0.964017 0.0552635 0.0434419 -0.784799 0.618227 -0.701525 -0.696875 0.149093 0.0632137 -0.432139 0.899589 -0.946596 -0.251962 0.201176 -0.946596 -0.25196 0.201177 -0.74846 -0.251958 0.613453 -0.74846 -0.25196 0.613452 -0.383109 -0.251959 0.888675 -0.38311 -0.251962 0.888674 0.067836 -0.251962 0.965357 0.0953275 -0.190907 0.976968 -0.701524 -0.696875 0.149092 -0.554684 -0.696877 0.45463 -0.554685 -0.696875 0.454632 -0.283924 -0.696876 0.658598 -0.283924 -0.696875 0.658599 0.0502728 -0.696875 0.715428 0.102891 -0.602553 0.791418 -0.260032 -0.964017 0.0552639 -0.205604 -0.964017 0.168518 -0.205604 -0.964017 0.168516 -0.105241 -0.964017 0.244121 -0.105241 -0.964017 0.244122 0.0186343 -0.964017 0.265187 0.091667 -0.895975 0.434541 0.470205 -0.258822 -0.843752 0.478606 -0.195089 -0.856082 0.38532 -0.608758 -0.6935 0.404753 -0.555572 -0.726302 0.29634 -0.793354 -0.531763 0.26986 -0.831469 -0.485629 0.126872 -0.965925 -0.225595 0.0949702 -0.980785 -0.170418 -0.258785 -0.965922 -0.00493789 -0.258786 -0.965922 -0.00493788 -0.706998 -0.707087 -0.0134902 -0.706997 -0.707088 -0.0134902 -0.965753 -0.258809 -0.0184275 -0.965754 -0.258806 -0.0184275 0.198421 -0.595764 -0.778264 0.239158 -0.250754 -0.938044 0.239157 -0.250751 -0.938045 -0.256272 -0.250752 -0.933514 -0.256271 -0.250752 -0.933514 -0.684572 -0.250753 -0.684459 -0.684572 -0.250753 -0.684459 -0.933556 -0.250753 -0.256117 -0.933557 -0.25075 -0.256116 0.0659894 -0.963666 -0.25883 0.153593 -0.783249 -0.602437 0.200908 -0.691755 -0.693622 -0.190334 -0.695034 -0.693325 -0.190333 -0.695036 -0.693324 -0.508434 -0.695036 -0.50835 -0.508435 -0.695035 -0.50835 -0.693357 -0.695035 -0.190218 -0.693356 -0.695036 -0.190218 0.0659894 -0.963666 -0.258829 -0.070711 -0.963667 -0.257579 -0.0707117 -0.963666 -0.25758 -0.188891 -0.963666 -0.188859 -0.188891 -0.963666 -0.188859 -0.257592 -0.963666 -0.0706688 -0.257591 -0.963666 -0.0706688 0.977905 0 0.209051 0.977905 0 0.209051 0.977701 0 0.210001 0.977701 0 0.210001 0.983209 0 0.182486 0.983209 0 0.182486 0.986423 0 0.164225 0.986423 0 0.164225 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.999996 0 -0.00284487 0.999996 0 -0.00284487 0.999205 0 -0.0398588 0.999205 0 -0.0398588 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.984017 0.00137524 0.178067 0.983957 0.00181378 0.178398 0.983799 0 0.179277 0.9849 0.00383839 0.173084 0.984901 0 0.17312 0.984686 0.00293629 0.174315 0.984772 0.00166033 0.173844 0.984473 0 0.175534 0.984232 0 0.17688 0.978857 0 0.204545 0.978857 0 0.204545 0.978688 -0.00246524 0.205337 0.977989 -0.00268154 0.208638 0.977905 -0.00114259 0.209047 0.978173 0 0.207792 0.9784 0 0.206723 0.977926 -0.0016165 0.208944 0.978281 -0.00763942 0.207144 0.977779 0 0.20964 0.986423 0 0.164225 0.986423 0 0.164225 0.983209 0 0.182486 0.983209 0 0.182486 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.999205 0 -0.0398588 0.999205 0 -0.0398588 0.999996 0 -0.00284487 0.999996 0 -0.00284487 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.983793 -0.00343638 0.179276 0.983805 0 0.179241 0.984005 -0.002417 0.178125 0.983957 -0.00175954 0.178398 0.984773 0 0.173844 0.984903 -0.00265868 0.173085 0.984672 -0.00112838 0.174411 0.984596 -0.000677698 0.174844 0.984473 0 0.175534 0.984232 0 0.17688 0.969569 0 0.244818 0.969569 8.77548e-08 0.244818 0.969569 -5.23577e-07 0.244817 0.969569 0 0.244818 0.969569 -8.86403e-08 0.244818 0.969569 0 0.244818 -0.999987 0 0.0051013 -0.999987 1.6161e-07 0.00510167 -0.999991 1.36961e-07 0.00432532 -0.999991 0 0.00432501 -0.97342 0 -0.229029 -0.97342 0 -0.229029 -0.764146 0 -0.645044 -0.764146 0 -0.645044 -0.389159 0 -0.921171 -0.389159 0 -0.921171 0.0702166 0 -0.997532 0.0702166 0 -0.997532 0.514375 0 -0.857566 0.514375 0 -0.857566 -0.632337 0 0.774694 -0.632337 0 0.774694 -0.860815 0 0.508918 -0.860815 0 0.508918 -0.983552 0 0.180626 -0.983552 0 0.180626 -0.061367 0.707107 0.704439 -0.061367 0.707107 0.704439 0.706779 0.706768 0.0307052 0.688538 0.710655 0.144517 0.688823 0.708959 0.151327 0.591746 0.685791 0.423707 0.0858168 0.699418 0.709542 0.0858175 0.699418 0.709543 0.364315 0.699417 0.61489 0.364315 0.699418 0.61489 0.597214 0.696633 0.39754 -0.0992313 0.706595 0.700626 -0.234258 0.714499 0.659253 -0.519089 0.723189 0.45557 -0.461931 0.704833 0.538358 -0.274993 0.6999 0.65918 -0.0889142 0.704323 -0.70429 -0.172421 0.72966 -0.661716 -0.26345 0.704136 -0.659383 -0.406852 0.705269 -0.580575 -0.478313 0.72245 -0.499282 -0.541672 0.702956 -0.460916 -0.686961 0.695437 -0.210839 -0.686961 0.695436 -0.210839 -0.702611 0.695437 0.150686 -0.702611 0.695437 0.150686 -0.583642 0.703555 0.405429 0.707107 0.707107 -0.000262229 0.707107 0.707107 -0.000262216 0.707107 0.707107 -0.000262309 -0.00026161 0.707107 -0.707107 -0.000262357 0.707107 -0.707107 -0.000262506 0.707107 -0.707107 0.694677 0.694747 -0.186415 0.694678 0.694747 -0.186415 0.508401 0.694746 -0.508779 0.508401 0.694747 -0.508779 0.185899 0.694747 -0.694816 0.185899 0.694747 -0.694816 0.185899 -0.694747 -0.694816 0.185899 -0.694747 -0.694816 0.508401 -0.694747 -0.508779 0.508401 -0.694746 -0.508779 0.694678 -0.694747 -0.186415 0.694677 -0.694747 -0.186415 0.707107 -0.707107 -0.000262212 0.707107 -0.707107 -0.000262227 0.707107 -0.707107 -0.000262252 -0.000262506 -0.707107 -0.707107 -0.000262357 -0.707107 -0.707107 -0.000261633 -0.707107 -0.707107 0.0858175 -0.699418 0.709542 0.0858169 -0.699418 0.709543 0.364315 -0.699418 0.61489 0.364315 -0.699418 0.61489 0.581107 -0.699418 0.416089 0.602379 -0.690186 0.400978 0.688823 -0.708959 0.151327 0.688538 -0.710655 0.144517 0.706779 -0.706768 0.0307067 -0.478313 -0.72245 -0.499282 -0.410972 -0.706452 -0.576219 -0.18215 -0.69148 -0.699054 -0.260811 -0.749127 -0.608922 -0.088517 -0.704348 -0.704315 -0.0992314 -0.706595 0.700626 -0.234257 -0.714499 0.659253 -0.274994 -0.6999 0.65918 -0.461931 -0.704833 0.538359 -0.519089 -0.723189 0.45557 -0.583642 -0.703555 0.405429 -0.702611 -0.695437 0.150686 -0.702611 -0.695437 0.150686 -0.686961 -0.695436 -0.210839 -0.686961 -0.695437 -0.210839 -0.541672 -0.702956 -0.460916 -0.061367 -0.707107 0.704439 -0.061367 -0.707107 0.704439 -7.24714e-05 -0.980785 -0.195091 -0.000449785 -0.982225 -0.187708 0.000191531 -0.83147 -0.555569 -0.000203675 -0.83606 -0.548637 0.194807 -0.979448 -0.052276 0.549458 -0.822408 -0.147446 0.54946 -0.822407 -0.147446 0.402122 -0.822408 -0.402421 0.402122 -0.822408 -0.40242 0.147038 -0.822409 -0.549567 0.147038 -0.822408 -0.549568 0.194806 -0.979448 -0.0522757 0.14257 -0.979448 -0.142676 0.142569 -0.979448 -0.142675 0.052131 -0.979448 -0.194845 0.0521308 -0.979448 -0.194844 0.555569 -0.83147 -0.00020605 0.555569 -0.83147 -0.000206051 0.195092 -0.980785 -7.23558e-05 0.195092 -0.980785 -7.23566e-05 0.195053 -0.980546 0.0219805 0.376077 -0.926578 0.00436829 0.555526 -0.831398 0.0129628 0.606929 -0.794751 0.00287453 0.444252 -0.894458 0.0508375 0.191995 -0.980476 0.0424912 0.618963 -0.776312 0.119264 0.547716 -0.828891 0.113782 0.37759 -0.924982 0.0428381 0.445743 -0.89468 0.0293503 0.608057 -0.792974 0.0382022 0.626253 -0.778945 0.0324267 0.0239172 -0.979961 0.197749 0.0677072 -0.825853 0.559806 0.0677067 -0.825854 0.559804 0.287432 -0.825855 0.485126 0.287433 -0.825853 0.485128 0.47189 -0.823802 0.314118 0.471892 -0.823801 0.314118 0.0239171 -0.979961 0.197749 0.101534 -0.979961 0.171369 0.101534 -0.979961 0.171368 0.167056 -0.979656 0.111202 0.167055 -0.979656 0.111202 -0.14288 -0.927137 0.346413 -0.0217253 -0.96816 0.249388 -0.0144181 -0.980782 0.194574 -0.0541839 -0.798665 0.599331 -0.0482158 -0.831469 0.553475 -0.0401274 -0.933 0.357633 -0.0626815 -0.835211 0.546346 -0.0844663 -0.798248 0.596378 -0.384662 -0.883536 0.267207 -0.0915974 -0.993243 -0.0712609 -0.426546 -0.828447 -0.362953 -0.543155 -0.822917 -0.166703 -0.543155 -0.822917 -0.166703 -0.555528 -0.822918 0.119142 -0.555529 -0.822917 0.119142 -0.469071 -0.830026 0.301711 -0.147433 -0.984678 0.0931302 -0.168388 -0.980701 0.0993582 -0.19685 -0.979524 0.0422175 -0.19685 -0.979524 0.0422176 -0.192465 -0.979524 -0.0590706 -0.192466 -0.979524 -0.0590707 -0.150259 -0.980343 -0.127866 -0.335952 -0.904245 -0.263587 0.519203 0 -0.854651 0.514375 0.000512902 -0.857566 0.0800607 -0.00051611 -0.99679 0.0702166 0.00038708 -0.997532 -0.382656 -0.000389325 -0.923891 -0.389159 0.000259406 -0.921171 -0.761412 -0.000261153 -0.648268 -0.764146 0.000130215 -0.645044 -0.973095 -0.000131632 -0.230404 -0.97342 0 -0.229029 -0.000206249 0.83147 -0.555569 0.000177024 0.836449 -0.548045 -0.000438079 0.980785 -0.19509 -6.9442e-05 0.982372 -0.186936 0.0521308 0.979448 -0.194844 0.147038 0.822408 -0.549569 0.147037 0.822409 -0.549567 0.402122 0.822408 -0.402421 0.402122 0.822408 -0.402421 0.54946 0.822407 -0.147446 0.549458 0.822408 -0.147446 0.0521311 0.979448 -0.194845 0.142569 0.979448 -0.142675 0.14257 0.979448 -0.142676 0.194806 0.979448 -0.0522757 0.194807 0.979448 -0.0522759 0.555569 0.83147 -0.00020605 0.555569 0.83147 -0.000206039 0.195092 0.980785 -7.23558e-05 0.195092 0.980785 -7.23566e-05 0.555565 0.831462 0.00434704 0.607421 0.794227 0.0155652 0.19509 0.980778 -0.00379346 0.37758 0.924999 0.0425494 0.617471 0.775405 0.132199 0.549824 0.828403 0.106974 0.441224 0.893117 0.0875413 0.19895 0.979745 0.0227667 0.607932 0.793313 0.0327462 0.625864 0.778949 0.0391609 0.376979 0.92587 0.0255492 0.444284 0.894467 0.0504047 0.167055 0.979656 0.111202 0.471891 0.823801 0.314118 0.47189 0.823802 0.314118 0.287433 0.825853 0.485128 0.287432 0.825855 0.485126 0.067707 0.825854 0.559804 0.067707 0.825853 0.559806 0.167055 0.979656 0.111202 0.101534 0.979961 0.171368 0.101534 0.979961 0.171369 0.0239172 0.979961 0.197749 0.0239172 0.979961 0.197749 -0.0169312 0.980785 0.194355 -0.14288 0.927137 0.346413 -0.0195774 0.968661 0.247614 -0.0496134 0.831468 0.553353 -0.0522256 0.798667 0.599503 -0.0401274 0.933 0.357633 -0.0688743 0.798555 0.597968 -0.0806823 0.81791 0.56966 -0.133637 0.985057 -0.108643 -0.420314 0.83392 -0.35765 -0.142558 0.986206 0.0841175 -0.459447 0.828883 0.319157 -0.555529 0.822917 0.119142 -0.555528 0.822918 0.119142 -0.543155 0.822917 -0.166703 -0.543155 0.822917 -0.166703 -0.426972 0.8285 -0.362329 -0.309405 0.916962 -0.251891 -0.154862 0.980562 -0.12048 -0.192466 0.979524 -0.0590707 -0.192465 0.979524 -0.0590706 -0.19685 0.979524 0.0422176 -0.19685 0.979524 0.0422175 -0.165585 0.980602 0.104891 -0.372477 0.896733 0.239022 -0.000363903 -0.195091 -0.980785 -0.000363905 -0.195091 -0.980785 -0.000308502 -0.55557 -0.83147 -0.000308504 -0.55557 -0.83147 0.217159 -0.542275 -0.811653 0.217158 -0.542274 -0.811653 0.253817 -0.188684 -0.94867 0.811491 -0.542276 -0.217761 0.811491 -0.542275 -0.217762 0.793084 0.0104396 -0.609023 0.59697 -0.193484 -0.778583 0.253818 -0.188684 -0.94867 0.593891 -0.542275 -0.594333 0.593891 -0.542276 -0.594332 0.694149 -0.188683 -0.694663 0.948481 -0.188683 -0.254523 0.948481 -0.188684 -0.254522 -0.328792 -0.189034 0.92529 -0.281163 -0.543009 0.791257 -0.281164 -0.543012 0.791255 -0.631134 -0.543011 0.553904 -0.631134 -0.54301 0.553904 -0.821056 -0.54301 0.176088 -0.821056 -0.54301 0.176088 -0.802768 -0.54301 -0.246382 -0.802768 -0.54301 -0.246382 -0.580907 -0.54301 -0.606372 -0.580907 -0.543009 -0.606373 -0.211735 -0.543009 -0.812594 -0.211734 -0.54301 -0.812594 -0.328791 -0.189033 0.925291 -0.738044 -0.189032 0.647733 -0.738044 -0.189033 0.647732 -0.960138 -0.189033 0.205916 -0.960138 -0.189033 0.205916 -0.938752 -0.189033 -0.288118 -0.938752 -0.189033 -0.288118 -0.679309 -0.189033 -0.709088 -0.679308 -0.189034 -0.709088 -0.247601 -0.189034 -0.950242 -0.247601 -0.189034 -0.950242 0.980785 -0.195091 -0.000364263 0.980785 -0.19509 -0.000363723 0.83147 -0.55557 -0.000308349 0.83147 -0.55557 -0.000308334 -0.0851184 -0.195092 0.977085 -0.0851185 -0.195092 0.977085 -0.07216 -0.555569 0.828333 -0.07216 -0.555569 0.828333 0.960645 -0.191069 0.20163 0.819109 -0.547269 0.171923 0.819109 -0.547268 0.171923 0.680499 -0.547269 0.487256 0.680499 -0.547268 0.487256 0.426628 -0.547269 0.72006 0.426627 -0.547269 0.72006 0.100495 -0.547269 0.830902 0.100496 -0.547267 0.830903 0.960645 -0.191069 0.20163 0.798083 -0.191069 0.57145 0.798083 -0.191069 0.571451 0.500345 -0.191069 0.84448 0.500346 -0.191069 0.84448 0.117861 -0.191068 0.974475 0.117859 -0.191071 0.974475 0.980785 0.19509 -0.000364263 0.980785 0.195091 -0.000363717 0.83147 0.55557 -0.000308349 0.83147 0.55557 -0.000308356 0.593891 0.542276 -0.594332 0.593892 0.542275 -0.594332 0.217159 0.542274 -0.811653 0.217158 0.542275 -0.811653 0.811491 0.542275 -0.217761 0.811491 0.542276 -0.217762 0.948481 0.188684 -0.254523 0.948482 0.188683 -0.254522 0.77814 0.193483 -0.597547 0.70373 0.0937757 -0.704252 0.59697 0.193484 -0.778583 0.253817 0.188684 -0.94867 0.253818 0.188684 -0.94867 0.117861 0.19107 0.974475 0.100495 0.547267 0.830903 0.100496 0.547269 0.830901 0.426627 0.547269 0.72006 0.426627 0.547269 0.72006 0.680499 0.547268 0.487257 0.680499 0.547269 0.487256 0.819109 0.547268 0.171923 0.819109 0.547269 0.171923 0.117859 0.191068 0.974475 0.500345 0.191069 0.844481 0.500346 0.191069 0.84448 0.798083 0.191069 0.57145 0.798083 0.191069 0.571451 0.960645 0.191069 0.201629 0.960645 0.191069 0.20163 -0.000363903 0.195091 -0.980785 -0.000363903 0.195091 -0.980785 -0.000308502 0.55557 -0.83147 -0.000308504 0.55557 -0.83147 -0.0851184 0.195092 0.977085 -0.0851184 0.195092 0.977085 -0.07216 0.555569 0.828333 -0.07216 0.555569 0.828333 -0.247601 0.189034 -0.950242 -0.211735 0.54301 -0.812594 -0.211735 0.543009 -0.812594 -0.580907 0.543009 -0.606373 -0.580907 0.54301 -0.606372 -0.802768 0.54301 -0.246382 -0.802768 0.54301 -0.246382 -0.821056 0.54301 0.176088 -0.821056 0.54301 0.176088 -0.631134 0.54301 0.553904 -0.631133 0.543011 0.553904 -0.281163 0.543011 0.791256 -0.281165 0.543009 0.791257 -0.247601 0.189034 -0.950242 -0.679309 0.189034 -0.709088 -0.679309 0.189033 -0.709089 -0.938752 0.189033 -0.288118 -0.938752 0.189033 -0.288118 -0.960138 0.189033 0.205916 -0.960138 0.189033 0.205916 -0.738044 0.189033 0.647733 -0.738044 0.189032 0.647732 -0.328792 0.189033 0.92529 -0.328791 0.189034 0.92529 -0.632337 0 0.774694 -0.632337 0 0.774694 -0.860815 0 0.508918 -0.860815 0 0.508918 -0.983552 0 0.180626 -0.983552 0 0.180626 -0.176083 0 0.984375 -0.176083 0 0.984375 -0.176082 0 0.984376 -0.176082 0 0.984376 -0.176083 0 0.984375 -0.176083 0 0.984375 -0.984376 0 -0.176082 -0.984376 0 -0.176082 0.176086 0 -0.984375 0.176082 -1.05101e-06 -0.984376 0.176081 0 -0.984376 0.176081 0 -0.984376 0.176083 6.61471e-06 -0.984375 0.176082 0 -0.984376 -0.0600703 0 -0.998194 -0.0600703 0 -0.998194 -0.0600703 0 -0.998194 -0.0600703 0 -0.998194 -0.0600779 0 -0.998194 -0.0600779 0 -0.998194 0.0600703 0 0.998194 0.0600772 0 0.998194 0.0600772 0 0.998194 0.0600703 0 0.998194 0.0600703 0 0.998194 0.0600518 1.19016e-05 0.998195 0.0600889 -5.95079e-06 0.998193 0.0600703 0 0.998194 -0.998194 0 0.060076 -0.998194 0 0.060076 0.996333 -7.80019e-05 0.0855652 0.995694 2.70095e-07 0.0927013 0.995694 -1.02162e-05 0.0927014 0.995694 0 0.0927013 0.995694 0 0.0927014 0.995694 2.88979e-06 0.0927013 0.994942 -8.42606e-05 0.100451 0.995694 -1.22264e-06 0.0927011 0.995694 -1.27613e-05 0.0927002 0.995694 1.74871e-07 0.0927014 0.995694 1.3895e-06 0.0927012 0.995694 -2.30789e-06 0.0927016 0.995694 -3.0228e-06 0.0927017 0.995694 1.84851e-06 0.0927013 -0.0927022 6.02579e-06 0.995694 -0.0927052 -2.14216e-05 0.995694 -0.0926998 0 0.995694 -0.0926997 0 0.995694 -0.0927023 0 0.995694 -0.0927467 -3.06319e-05 0.99569 -0.0926901 9.83945e-06 0.995695 -0.0927048 -1.61063e-06 0.995694 -0.0926989 3.4371e-06 0.995694 -0.0927038 -1.54072e-06 0.995694 -0.0931789 -0.000117139 0.995649 -0.0926996 1.37234e-07 0.995694 0.0927038 0 -0.995694 0.0927039 0 -0.995694 0.0927007 0 -0.995694 0.092701 2.81061e-07 -0.995694 0.0927019 1.54584e-06 -0.995694 0.0927043 -1.81783e-05 -0.995694 0.0927024 5.66594e-05 -0.995694 0.0931391 0.000137781 -0.995653 0.0926959 -4.84945e-07 -0.995694 0.0927572 1.05112e-05 -0.995689 -0.995694 0 -0.0927012 -0.995694 0 -0.0927012 -0.207151 0 0.978309 -0.207151 0 0.978309 -0.205946 0 0.978563 -0.205946 0 0.978563 -0.205946 0 0.978563 0 0 0 -0.207152 0 0.978309 -0.207151 -1.02504e-06 0.978309 -0.207152 0 0.978309 -0.978309 0 -0.207152 -0.978309 0 -0.207152 0.207152 3.81942e-07 -0.978309 0.207151 0 -0.978309 0.207151 0 -0.978309 0.207153 -7.29329e-06 -0.978309 0.207151 0 -0.978309 0.207151 0 -0.978309 0.207151 0 -0.978309 0.207153 7.3225e-06 -0.978309 0.207152 0 -0.978309 0.207152 -3.81942e-07 -0.978309 -0.2003 0 0.979735 -0.2003 0 0.979735 -0.663357 0 0.748303 -0.663357 0 0.748303 -0.948633 0 0.316379 -0.948633 0 0.316379 -0.31642 0 -0.948619 -0.31642 0 -0.948619 -0.748299 0 -0.663362 -0.748299 0 -0.663362 -0.97973 0 -0.20032 -0.97973 0 -0.20032 -0.958475 0 -0.285176 -0.958475 0 -0.285176 -0.776397 0 -0.630245 -0.776397 0 -0.630245 -0.476086 0 -0.879399 -0.476086 0 -0.879399 -0.103343 0 -0.994646 -0.103343 0 -0.994646 -0.9191 0 -0.394025 -0.9191 0 -0.394025 -0.698349 0 -0.715758 -0.698349 0 -0.715758 -0.37127 0 -0.928525 -0.37127 0 -0.928525 0.0123164 0 -0.999924 0.0123164 0 -0.999924 -0.424858 0 0.90526 -0.424858 0 0.90526 -0.820568 0 0.571549 -0.820568 0 0.571549 -0.996407 0 0.0846928 -0.996407 0 0.0846928 -0.931109 0 -0.364742 -0.931109 0 -0.364742 -0.720653 0 -0.693296 -0.720653 0 -0.693296 -0.400475 0 -0.916308 -0.400475 0 -0.916308 -0.0193435 0 -0.999813 -0.0193435 0 -0.999813 0.85193 -0.156457 0.499737 0.851015 -0.162658 0.499316 0.973176 -0.1865 0.134705 0.97302 -0.186903 0.135272 0.877719 -0.469315 0.0967101 0.895741 -0.432759 0.101819 0.800124 -0.599321 -0.0248159 0.79917 -0.599479 -0.044179 0.615166 -0.787408 -0.0394952 0.582877 -0.811803 -0.0350789 0.258351 -0.965926 -0.0155482 0.258352 -0.965926 -0.0155481 0.979915 -0.190498 -0.0589738 0.975754 -0.211479 -0.0563931 0.897271 -0.438091 -0.0545953 0.88774 -0.457235 -0.0534263 0.772748 -0.633007 -0.0465058 0.768698 -0.63219 -0.0971524 0.866059 -0.451091 -0.215541 0.839081 -0.504653 -0.203147 0.942643 -0.207004 -0.261865 0.942475 -0.207279 -0.262252 0.756479 -0.176895 -0.62964 0.757861 -0.167286 -0.630604 0.877716 0.469321 0.0967086 0.83924 0.536835 0.0865133 0.973346 0.186995 0.132778 0.973141 0.187526 0.133534 0.851459 0.163692 0.498219 0.852397 0.157374 0.498651 0.194737 0.980785 -0.0117197 0.194738 0.980785 -0.0117198 0.528632 0.848255 -0.0318144 0.561172 0.826833 -0.037856 0.802835 0.594556 -0.0442524 0.838783 0.541927 -0.0525244 0.975754 0.211479 -0.0563931 0.979915 0.190498 -0.0589738 0.751287 0.174518 -0.636483 0.756724 0.16968 -0.63133 0.757195 0.166324 -0.631658 0.945028 0.192587 -0.26426 0.937212 0.206085 -0.281358 0.839827 0.503323 -0.203361 0.786869 0.588985 -0.184215 0.166429 0.983548 0.0702506 0.197459 0.958426 0.205983 0.568962 0.689429 0.448296 0.473898 0.841373 0.25983 0.367635 0.908634 0.198064 0.527567 0.535567 0.659425 0.503928 0.601268 0.620108 0.474306 0.248844 0.844459 0.546998 0.195916 0.813886 0.172419 0.173458 0.969631 0.172793 0.165139 0.971016 0.420028 0.615113 0.667243 0.659191 0.626152 0.416415 0.8178 0.253612 0.516609 0.817808 0.253624 0.51659 0.261242 0.96449 0.038874 0.261242 0.96449 0.0388735 0.706972 0.699374 0.105199 0.706972 0.699373 0.105201 0.956771 0.253615 0.142372 0.956771 0.253612 0.142376 0.194738 0.980785 -0.0117198 0.258268 0.965925 -0.0169266 0.441493 0.896871 -0.02657 0.607661 0.793354 -0.0365704 0.705718 0.707106 -0.044319 0.979014 0.19509 -0.0589193 0.964097 0.258819 -0.0594051 0.895251 0.442292 -0.0538783 0.791922 0.60876 -0.0476597 0.766473 0.597878 -0.234654 0.432624 0.891792 -0.132447 -0.209796 0.593044 -0.777358 -0.11901 0.570902 -0.812347 -0.165083 0.173155 -0.970961 -0.566526 0.190705 -0.801673 -0.567263 0.183228 -0.802895 0.126551 0.937216 -0.324978 0.150564 0.909677 -0.387064 0.0746964 0.984403 -0.159286 0.0683236 0.979913 -0.187355 0.143776 0.979699 -0.13971 0.143776 0.979699 -0.13971 0.191694 0.979698 -0.058687 0.191695 0.979698 -0.0586869 0.0170546 0.781603 -0.623543 0.200013 0.780684 -0.592053 0.152832 0.820086 -0.551454 0.406247 0.824089 -0.394767 0.406257 0.824084 -0.394768 0.541653 0.824084 -0.165826 0.598244 0.789144 -0.139125 0.012402 0.554537 -0.832067 0.268393 0.544712 -0.794515 0.268411 0.544698 -0.794519 0.601438 0.544697 -0.584445 0.60144 0.544696 -0.584445 0.801895 0.544696 -0.245503 0.884782 0.440084 -0.153258 -0.14495 0.189829 -0.971058 0.314206 0.18983 -0.930183 0.314222 0.189816 -0.93018 0.70413 0.189822 -0.684229 0.704126 0.189826 -0.684232 0.938806 0.189832 -0.287416 0.938805 0.189834 -0.287418 0.420455 -0.612481 0.669392 0.502934 -0.600193 0.621954 0.583477 -0.256225 0.770651 0.322701 -0.341423 0.882777 0.5423 -0.19263 0.817805 0.168832 -0.170198 0.970839 0.169183 -0.162221 0.972143 0.166419 -0.983532 0.0704908 0.196651 -0.958334 0.207183 0.81588 -0.253548 0.519667 0.815882 -0.253546 0.519665 0.65992 -0.622761 0.420327 0.566864 -0.689113 0.45143 0.475987 -0.83957 0.261839 0.367578 -0.908538 0.198608 0.95661 -0.253548 0.143565 0.956609 -0.25355 0.143568 0.706931 -0.699279 0.106097 0.706932 -0.699279 0.106096 0.261257 -0.964473 0.0392093 0.261257 -0.964473 0.0392093 0.194738 -0.980785 -0.0117198 0.258268 -0.965925 -0.0169266 0.441493 -0.896871 -0.02657 0.607661 -0.793354 -0.0365704 0.705718 -0.707106 -0.044319 0.791922 -0.60876 -0.0476597 0.895251 -0.442292 -0.0538783 0.964097 -0.258819 -0.0594051 0.979014 -0.19509 -0.0589193 0.314206 -0.189816 -0.930185 0.0157029 -0.715097 -0.698849 0.0170546 -0.781603 -0.623543 0.0746964 -0.984403 -0.159286 0.0683236 -0.979913 -0.187355 -0.127399 -0.517647 -0.846056 -0.567263 -0.183228 -0.802895 -0.566526 -0.190705 -0.801673 -0.145446 -0.171522 -0.974385 -0.163887 -0.188932 -0.968218 0.314221 -0.189829 -0.930178 0.268396 -0.544696 -0.794525 0.938805 -0.189835 -0.287416 0.938805 -0.189833 -0.287418 0.862241 -0.432269 -0.263978 0.817027 -0.539293 -0.204031 -0.128615 -0.573499 -0.809047 -0.0520746 -0.551178 -0.832761 0.268409 -0.54471 -0.794511 0.200013 -0.780684 -0.592053 0.152833 -0.820086 -0.551454 0.150564 -0.909677 -0.387064 0.126551 -0.937216 -0.324977 0.555207 -0.820213 -0.137826 0.592453 -0.784922 -0.181378 0.766473 -0.597878 -0.234654 0.191694 -0.979698 -0.0586868 0.191695 -0.979698 -0.0586871 0.432624 -0.891792 -0.132447 0.704129 -0.189827 -0.684228 0.704126 -0.189823 -0.684232 0.601439 -0.544696 -0.584446 0.60144 -0.544697 -0.584444 0.406253 -0.824083 -0.394773 0.406252 -0.824088 -0.394763 0.143776 -0.979699 -0.13971 0.143776 -0.979699 -0.13971 0.577869 -0.252513 -0.776083 0.12209 -0.98424 -0.127929 0.127826 -0.960446 -0.247394 0.201392 -0.56004 -0.803615 0.195141 -0.618594 -0.761092 0.0781662 -0.661054 -0.746256 0.967478 -0.252509 -0.0150093 0.967478 -0.252509 -0.0150091 0.716295 -0.697709 -0.0111124 0.716295 -0.697709 -0.0111124 0.265232 -0.964176 -0.00411472 0.265232 -0.964176 -0.00411471 0.861297 -0.25251 -0.440915 0.861298 -0.252511 -0.440913 0.637682 -0.69771 -0.32644 0.637682 -0.697708 -0.326443 0.236123 -0.964176 -0.120877 0.236123 -0.964176 -0.120876 -0.267239 -0.181463 -0.94639 -0.26684 -0.191863 -0.94445 0.177174 -0.214641 -0.960489 0.126216 -0.249343 -0.960155 0.577865 -0.252509 -0.776088 0.438757 -0.678427 -0.589262 0.409815 -0.694657 -0.591188 0.297052 -0.875739 -0.380581 0.252072 -0.913053 -0.320614 0.94418 -0.258819 0.203807 0.252992 -0.965926 0.0546098 0.691188 -0.707106 0.149197 0.252992 -0.965926 0.0546098 0.253176 -0.965926 0.0537524 0.253177 -0.965925 0.0537526 0.595489 -0.793353 0.126429 0.690495 -0.707099 0.152403 0.691189 -0.707105 0.149197 0.94418 -0.25882 0.203807 0.9594 -0.195091 0.203693 0.943973 -0.258819 0.204762 0.877318 -0.442289 0.186265 0.776057 -0.608759 0.164767 0.105091 -0.984932 0.137353 0.109367 -0.979307 0.170285 0.0660027 -0.188811 0.979793 0.0660229 -0.188793 0.979795 0.543169 -0.188794 0.818123 0.543162 -0.188801 0.818125 0.464636 -0.54252 0.699847 0.464637 -0.542519 0.699847 0.314531 -0.822574 0.473753 0.877366 -0.1888 0.441117 0.877364 -0.188802 0.441119 0.750522 -0.542519 0.377346 0.843766 -0.438545 0.309415 0.188081 -0.940358 0.283464 0.190924 -0.938499 0.287694 0.314456 -0.822135 0.474564 0.12195 -0.829837 0.544518 0.17364 -0.552948 0.814922 -0.0482149 -0.623707 0.780169 0.0546108 -0.583275 0.810437 -0.163378 -0.468061 0.868462 -0.281905 -0.194176 0.939588 -0.421384 -0.208892 0.882496 -0.422123 -0.19948 0.884319 0.717614 -0.595697 0.360798 0.55551 -0.7832 0.279297 0.524969 -0.818748 0.232504 0.229672 -0.960262 0.158582 0.180093 -0.979473 0.0905475 0.742958 -0.0210922 -0.669006 0.631358 -0.190502 -0.751728 0.642886 -0.00148014 -0.76596 0.643149 -0.00174571 -0.76574 0.643093 -0.0406838 -0.764707 0.753455 -0.169795 -0.635197 0.761548 -0.194955 -0.618091 0.646998 -0.208924 -0.733311 0.72373 -0.145172 -0.674641 0.781339 -0.0675617 -0.620439 0.666942 -0.268986 -0.694864 0.68216 -0.285477 -0.673171 0.695738 -0.360005 -0.621567 0.743986 -0.413643 -0.524771 0.718184 -0.542038 -0.436357 0.734555 -0.573302 -0.362979 0.712978 -0.682336 -0.161492 0.683056 -0.694798 -0.225144 0.635531 -0.77195 -0.0139256 0.723984 -0.146207 -0.674145 0.769538 -0.19596 -0.607792 0.769857 -0.198378 -0.606602 0.850747 -0.290941 -0.437701 0.84899 -0.303849 -0.432311 0.898719 -0.404234 -0.169999 0.887231 -0.439126 -0.141384 0.878622 -0.477146 -0.0188575 0.867308 -0.496385 0.0371368 0.7749 -0.0284966 -0.631442 0.832782 -0.0922971 -0.545853 0.828167 -0.0394886 -0.559089 0.920926 -0.149079 -0.360098 0.927388 -0.0595824 -0.369326 0.982822 -0.178752 -0.0459294 0.989961 -0.114345 -0.0830765 0.9755 -0.173614 0.13512 0.984181 -0.156066 0.0838483 0.871944 -0.391308 0.294267 0.645748 -0.761125 -0.0608191 0.859059 -0.506088 0.0767643 0.971043 -0.175699 0.161879 0.542309 -0.838659 0.0505157 0.5481 -0.824595 0.140103 0.528787 -0.835125 0.151496 0.571888 -0.720914 0.391443 0.617053 -0.723845 0.308699 0.817852 -0.563813 0.115033 0.792319 -0.565739 0.228406 0.831209 -0.516418 0.205922 0.798672 -0.474051 0.370673 0.756196 -0.478797 0.446005 0.964787 -0.198317 0.172789 0.954513 -0.199756 0.221365 0.960729 -0.179459 0.211646 0.948965 -0.164461 0.269107 0.956229 -0.15904 0.245626 0.805424 -0.116357 0.581166 0.573603 -0.383428 0.723852 0.651684 -0.453012 0.608348 0.844387 -0.148808 0.514652 0.859061 -0.168986 0.483176 0.969805 -0.199901 0.139705 0.553909 -0.604895 0.57209 0.713371 -0.590311 0.37767 0.75081 -0.470172 0.463921 0.83587 -0.32884 0.43953 0.603426 -3.67104e-05 0.797419 0.628027 -0.0243895 0.777809 0.65166 -0.00895574 0.758459 0.717203 -0.0798915 0.692269 0.761292 -0.0633072 0.645311 0.603029 -0.000935498 0.797718 0.639353 -0.0373238 0.768007 0.59848 -0.119927 0.792111 0.689844 -0.223297 0.688661 0.56751 -0.337328 0.751094 0.513521 -0.18959 -0.83687 0.159402 -0.718354 -0.677169 0.142457 -0.793212 -0.592048 0.106342 -0.984542 -0.139169 0.107201 -0.97979 -0.168876 0.0503911 -0.523799 -0.85035 -0.393349 -0.186452 -0.900285 -0.392802 -0.194823 -0.89875 0.0646557 -0.165743 -0.984047 0.0405116 -0.188442 -0.981248 0.513526 -0.189596 -0.836866 0.438787 -0.544191 -0.715068 0.0395775 -0.579121 -0.81428 0.127651 -0.55097 -0.824705 0.438784 -0.544186 -0.715073 0.320106 -0.79082 -0.521666 0.276001 -0.820345 -0.500857 0.220592 -0.91675 -0.33303 0.191638 -0.937909 -0.289141 0.980589 -0.189597 -0.0499789 0.980589 -0.189596 -0.0499801 0.9008 -0.431801 -0.0459133 0.842426 -0.538812 0.000203282 0.80092 -0.597378 -0.0408224 0.56624 -0.823735 -0.0288609 0.614598 -0.788779 0.00989338 0.182682 -0.980689 -0.0698366 0.265723 -0.963954 -0.0135437 0.844325 -0.189592 -0.501169 0.844326 -0.189592 -0.501168 0.721441 -0.544192 -0.428227 0.721441 -0.544191 -0.428229 0.487552 -0.823736 -0.289399 0.487553 -0.823735 -0.2894 0.172613 -0.979646 -0.102459 0.172612 -0.979647 -0.102457 0.598556 -0.793344 0.111069 0.254482 -0.965924 0.0472223 0.881826 -0.442275 0.163633 0.950354 -0.258818 0.172744 0.964325 -0.195085 0.178942 0.254483 -0.965924 0.0472225 0.255318 -0.965923 0.0424954 0.255319 -0.965922 0.0424955 0.600521 -0.793337 0.0999511 0.696722 -0.707103 0.120762 0.696089 -0.707104 0.124352 0.780047 -0.608748 0.144747 0.967478 -0.19508 0.161027 0.952231 -0.258816 0.162082 0.884709 -0.442275 0.147251 0.782606 -0.608738 0.130257 -0.163094 -0.190303 0.968083 0.0123099 -0.758147 0.651967 0.00288318 -0.554976 0.831861 0.0723513 -0.984094 0.162249 0.0634458 -0.980125 0.18796 -0.224092 -0.57669 0.785628 -0.126493 -0.561065 0.81805 -0.17329 -0.182255 0.967861 -0.565365 -0.18243 0.804414 -0.566065 -0.17487 0.8056 0.27641 -0.190302 0.94201 0.276394 -0.190315 0.942012 0.235929 -0.545678 0.804098 0.235945 -0.545666 0.804101 0.182857 -0.760404 0.623177 0.127137 -0.820492 0.557342 0.153766 -0.894863 0.419018 0.121603 -0.935842 0.330776 0.911425 -0.190304 0.364813 0.911424 -0.190306 0.364815 0.77799 -0.545672 0.311406 0.869966 -0.440709 0.221214 0.660308 -0.190313 0.72648 0.66032 -0.190302 0.726473 0.56365 -0.545666 0.620118 0.563644 -0.545671 0.62012 0.380347 -0.82476 0.418457 0.380346 -0.824761 0.418457 0.134511 -0.979799 0.147989 0.134514 -0.979798 0.14799 0.743508 -0.598857 0.297602 0.57433 -0.785683 0.229885 0.541361 -0.820859 0.181988 0.238253 -0.960642 0.142836 0.185667 -0.979798 0.074316 0.739902 -0.00100048 -0.672713 0.739219 -0.000210494 -0.673466 0.734471 -0.120644 -0.667831 0.733891 -0.119898 -0.668602 0.696703 -0.436883 -0.56898 0.678078 -0.398247 -0.617746 0.713558 -0.571078 -0.405838 0.740371 0.000259591 -0.672198 0.770247 -0.0356667 -0.636747 0.779773 -0.00871154 -0.626002 0.862375 -0.129521 -0.489421 0.874311 -0.061651 -0.481434 0.929877 -0.165944 -0.328316 0.92056 -0.133946 -0.366916 0.676234 -0.46039 -0.575107 0.96733 -0.103373 -0.23149 0.929783 -0.363023 0.0609841 0.813234 -0.320143 -0.485961 0.559309 -0.80866 0.182327 0.986095 -0.140963 -0.0880117 0.979588 -0.19926 -0.0264983 0.842907 -0.511651 -0.166498 0.857122 -0.453028 -0.245168 0.548191 -0.821341 -0.157748 0.625572 -0.651106 -0.429792 0.560816 -0.784348 -0.265111 0.837342 -0.539768 -0.0866484 0.979514 -0.190144 0.0663062 0.422439 -0.906374 -0.00569442 0.441365 -0.883309 -0.157998 0.405384 -0.912453 0.0556257 0.329051 -0.941851 -0.0681293 0.320992 -0.947081 -0.00108591 0.297183 -0.953635 0.0475626 0.307637 -0.947833 0.0835018 0.348199 -0.936789 0.0344125 0.364003 -0.891598 0.26936 0.495328 -0.855539 0.150674 0.444522 -0.747378 0.493788 0.520926 -0.811843 0.263719 0.778682 -0.626732 0.0293687 0.780649 -0.624815 0.013924 0.726482 -0.680449 0.0959825 0.727199 -0.680375 0.090954 0.717892 -0.68851 0.102886 0.709187 -0.687198 0.157521 0.754195 -0.647953 0.106522 0.727383 -0.631881 0.267658 0.795682 -0.578879 0.178294 0.767371 -0.519523 0.375817 0.802127 -0.53622 0.262792 0.970228 -0.222643 0.0953274 0.969808 -0.223027 0.098653 0.961243 -0.246713 0.123061 0.960333 -0.246829 0.129756 0.958832 -0.250455 0.13384 0.954868 -0.25023 0.16004 0.962329 -0.232451 0.141033 0.952946 -0.227674 0.200146 0.965022 -0.202185 0.166895 0.955996 -0.183783 0.228683 0.963184 -0.184502 0.195542 0.963279 -0.171964 0.206207 0.955416 -0.16395 0.245561 0.81149 -0.507215 0.290202 0.776729 -0.469386 0.419963 0.547173 -0.778053 0.308601 0.47381 -0.680742 0.558654 0.67197 -0.0235792 0.740203 0.708088 0.0017432 0.706122 0.780261 -0.0837206 0.619826 0.854322 -0.0346551 0.518588 0.912711 -0.122849 0.3897 0.945425 -0.126174 0.300418 0.646798 -0.00387139 0.762651 0.681618 -0.0403699 0.730594 0.666889 -0.0620638 0.742568 0.77089 -0.189748 0.60805 0.721158 -0.242668 0.648879 0.813868 -0.398904 0.422485 0.76888 -0.39728 0.500991 0.646622 -0.00458073 0.762797 0.674518 -0.0336805 0.737489 0.639837 -0.146501 0.754418 0.720285 -0.245041 0.648956 0.566622 -0.482284 0.668088 0.641583 -0.623087 0.447363 0.5009 -0.632682 0.590603 0.649337 0 0.760501 0.797395 -0.4582 -0.3927 0.727771 -0.000660684 -0.68582 0.727871 -0.000774165 -0.685714 0.723213 -0.120664 -0.680002 0.722617 -0.119914 -0.680768 0.687102 -0.43687 -0.580547 0.66765 -0.398205 -0.629027 0.617356 -0.786452 0.0191132 0.728241 0.000578473 -0.68532 0.759362 -0.0360582 -0.649669 0.769205 -0.00872877 -0.638942 0.854071 -0.129526 -0.503772 0.866141 -0.0616463 -0.495984 0.926427 -0.171428 -0.335181 0.917904 -0.137664 -0.372157 0.967894 -0.110277 -0.225876 0.918247 -0.381858 0.104918 0.801483 -0.326943 -0.500732 0.80221 -0.47742 -0.35851 0.611795 -0.721286 -0.324736 0.616882 -0.569598 -0.543153 0.980981 -0.136662 -0.137841 0.980773 -0.184818 -0.0626594 0.844664 -0.491275 -0.212585 0.84699 -0.447539 -0.28691 0.576318 -0.790142 -0.208645 0.600462 -0.650565 -0.464985 0.578421 -0.705823 -0.408953 0.844427 -0.486294 -0.224637 0.984079 -0.170742 -0.0493482 0.556567 -0.814886 -0.161842 0.56246 -0.77502 -0.288069 0.419798 -0.906787 -0.0388088 0.418271 -0.906409 -0.0589205 0.34707 -0.93766 0.0183238 0.346871 -0.932968 0.0961796 0.44635 -0.894531 0.0241945 0.391636 -0.885285 0.250781 0.531688 -0.84002 0.108044 0.520272 -0.747624 0.412765 0.541694 -0.820049 0.184627 0.835024 -0.538067 -0.114976 0.836314 -0.529741 -0.141255 0.772326 -0.63408 -0.0381534 0.771391 -0.636302 -0.0087131 0.745195 -0.666345 0.0258508 0.742323 -0.665331 0.0793107 0.773334 -0.63294 0.0366348 0.764035 -0.617754 0.186094 0.819402 -0.564497 0.0996131 0.813858 -0.513482 0.271977 0.82363 -0.543337 0.162538 0.982373 -0.185767 -0.0208218 0.982427 -0.185321 -0.0222062 0.974045 -0.226342 0.00239732 0.973474 -0.227731 0.0220675 0.970039 -0.240729 0.0327853 0.968844 -0.240545 0.0589904 0.9731 -0.226143 0.0439976 0.970109 -0.221489 0.0991524 0.97814 -0.196586 0.067792 0.97605 -0.180655 0.121207 0.978033 -0.18781 0.0904398 0.546754 -0.507037 0.666313 0.891558 -0.0917007 0.443527 0.919844 -0.137818 0.367279 0.821446 -0.305233 0.481725 0.0788716 0.306012 0.948755 0.735745 -0.412011 0.537519 0.604677 -0.604314 0.518816 0.518554 -0.677559 0.52155 0.633551 -0.673806 0.380261 0.790892 -0.436072 0.429338 0.816158 -0.43544 0.37984 0.96185 -0.141577 0.234095 0.925196 -0.148823 0.349091 0.527445 -0.731547 0.43202 0.551879 -0.813185 0.184824 0.813552 -0.493146 0.308124 0.824705 -0.525725 0.208507 0.977425 -0.18289 0.105792 0.970767 -0.162132 0.176989 0.634403 -0.000569188 0.773002 0.657335 -0.0240513 0.753215 0.679709 -0.00895872 0.733427 0.754841 -0.0948814 0.649009 0.802601 -0.0713756 0.592231 0.887828 -0.0860407 0.452059 0.863528 -0.472316 -0.176739 0.81554 -0.294772 0.498 0.74378 -0.426622 0.514573 0.633041 -0.00374575 0.774109 0.667092 -0.0388862 0.74396 0.627852 -0.11993 0.769038 0.729614 -0.24239 0.639461 0.580108 -0.398234 0.710552 0.681162 -0.724813 -0.103269 0.546999 -0.501865 0.670018 0.42095 -0.252602 -0.871202 0.0964592 -0.984185 -0.148579 0.0779122 -0.960393 -0.267534 0.0506545 -0.557876 -0.828377 0.052421 -0.617092 -0.785143 -0.0583937 -0.656858 -0.751749 0.945727 -0.25261 -0.204422 0.945727 -0.25261 -0.204423 0.700062 -0.697864 -0.151321 0.700063 -0.697863 -0.151323 0.259172 -0.964205 -0.0560218 0.259172 -0.964205 -0.0560207 0.76033 -0.252608 -0.598405 0.760327 -0.252604 -0.59841 0.562824 -0.697861 -0.442966 0.562824 -0.697863 -0.442963 0.208363 -0.964206 -0.163989 0.208363 -0.964206 -0.16399 -0.43462 -0.18091 -0.882257 -0.433959 -0.190214 -0.880624 -0.00372052 -0.212988 -0.977048 -0.0561273 -0.249303 -0.966798 0.420961 -0.252611 -0.871194 0.321429 -0.673929 -0.665209 0.286051 -0.6941 -0.660605 0.223793 -0.872801 -0.433745 0.188745 -0.912699 -0.362431 0.965909 -0.258813 0.00602234 0.965909 -0.258812 0.00602221 0.707105 -0.707095 0.00440862 0.707105 -0.707095 0.00440865 0.258822 -0.965924 0.0016137 0.258821 -0.965924 0.00161378 0.965523 -0.258708 -0.0289013 0.965519 -0.258725 -0.0289002 0.706951 -0.706946 -0.0211607 0.706931 -0.706966 -0.0211586 0.258813 -0.965896 -0.00774633 0.258799 -0.9659 -0.00774508 0.258351 -0.965926 -0.0155482 0.258352 -0.965926 -0.0155482 0.705829 -0.707107 -0.0424784 0.705829 -0.707107 -0.0424784 0.964181 -0.25882 -0.0580266 0.964181 -0.258818 -0.0580266 -0.420447 -0.176432 0.889998 -0.419697 -0.187743 0.888036 0.013424 -0.210539 0.977493 -0.0404781 -0.248925 0.967677 -0.0435791 -0.658253 0.751535 0.0683713 -0.617601 0.783514 0.0675056 -0.557539 0.827402 0.0999036 -0.984238 0.145931 0.0862274 -0.960441 0.264797 0.443257 -0.252381 0.860132 0.443231 -0.252398 0.86014 0.337884 -0.675196 0.655702 0.305071 -0.694016 0.652131 0.233272 -0.874071 0.426128 0.197163 -0.913034 0.357064 0.780178 -0.252395 0.572381 0.780183 -0.25239 0.572376 0.577753 -0.697524 0.423865 0.577769 -0.697515 0.423858 0.213988 -0.964139 0.156984 0.21398 -0.964141 0.156985 0.953529 -0.252388 0.164571 0.953529 -0.252388 0.16457 0.706125 -0.697521 0.121871 0.706122 -0.697523 0.121874 0.261523 -0.964141 0.0451381 0.261525 -0.964141 0.0451373 -0.0556946 0.199639 -0.978286 0.369984 0.899612 -0.231969 0.248632 0.945874 -0.208577 0.294718 0.936281 -0.1911 0.344113 0.913804 -0.215751 0.244098 0.944376 -0.220387 0.248599 0.968372 -0.0213396 0.263786 0.964545 -0.00831419 -0.0556983 0.203571 -0.977475 0.35873 0.654003 -0.666028 0.379422 0.600925 -0.703511 0.384396 0.586718 -0.712742 0.319517 0.663339 -0.676675 0.616042 0.664508 -0.42299 0.577661 0.690541 -0.435271 0.716273 0.695106 -0.0614842 0.716273 0.695107 -0.0614846 -0.070343 0.210176 -0.97513 0.427574 0.213871 -0.878316 0.385445 0.247848 -0.888821 0.798031 0.250797 -0.547948 0.798031 0.250798 -0.547948 0.964492 0.250798 -0.0827922 0.964493 0.250798 -0.0827911 0.25467 0.965926 0.0461562 0.254615 0.965941 0.0461529 0.224205 0.92922 0.293738 0.25488 0.965926 0.044984 0.25488 0.965926 0.0449841 0.696346 0.707106 0.122899 0.696346 0.707106 0.122899 0.950438 0.258818 0.172281 0.951225 0.258818 0.167883 0.951225 0.258819 0.167883 0.951975 0.252385 0.173334 0.855397 0.494222 0.155054 0.69577 0.707106 0.126119 0.704694 0.697633 0.129284 0.503293 0.859286 0.0912296 0.45606 0.519171 0.722821 0.811735 0.487009 0.322349 0.691502 0.672321 0.264216 0.666946 0.688745 0.284276 0.442406 0.881264 0.166287 0.484256 0.855612 0.182821 0.394747 0.908087 0.139834 0.258693 0.954646 0.147408 0.601311 0.545392 0.583929 0.516701 0.650477 0.556687 0.486258 0.660871 0.571667 0.0189761 0.179844 0.983512 0.0199017 0.129172 0.991423 0.27301 0.145111 0.951004 0.152166 0.177316 0.972319 0.443172 0.253649 0.859803 0.460705 0.251018 0.851317 0.65007 0.250315 0.717462 0.698717 0.22673 0.678519 0.77724 0.251904 0.576578 0.900404 0.247836 0.357561 0.900404 0.247836 0.35756 0.264616 0.595698 -0.758368 -0.172767 0.167021 -0.970698 0.0491703 0.955507 -0.290842 -0.17265 0.174505 -0.969402 0.241486 0.194004 -0.950814 0.00689007 0.35048 -0.936545 0.188785 0.94622 -0.26273 0.291021 0.901615 -0.319996 0.352399 0.850491 -0.390487 0.197449 0.9659 -0.167486 0.237089 0.964377 -0.117325 0.237089 0.964377 -0.117325 0.264425 0.964377 -0.00747114 0.264425 0.964377 -0.00747153 0.18265 0.628113 -0.756381 0.48348 0.639361 -0.597884 0.403122 0.690246 -0.600877 0.641133 0.698776 -0.317271 0.641135 0.698774 -0.31727 0.715057 0.698774 -0.0202039 0.715057 0.698774 -0.0202034 0.298069 0.256072 -0.919556 0.608294 0.253213 -0.752237 0.608296 0.253212 -0.752236 0.867054 0.253212 -0.42907 0.867054 0.253213 -0.429071 0.967024 0.253214 -0.0273231 0.967024 0.253214 -0.0273232 0.25415 0.965926 0.0489395 0.254151 0.965926 0.0489395 0.694354 0.707104 0.133706 0.694352 0.707105 0.133705 0.948501 0.258819 0.182644 0.948501 0.258818 0.182644 0.253875 0.965926 0.0503527 0.253874 0.965926 0.0503526 0.693598 0.707105 0.137566 0.693599 0.707104 0.137566 0.947471 0.258817 0.187919 0.94747 0.258819 0.187918 0.0173666 0.999707 0.0168873 0.165645 0.964065 0.207701 0.118717 0.969003 0.216656 0.432163 0.694471 0.575279 0.310224 0.87637 0.368424 0.27191 0.907077 0.321366 0.228972 0.559375 0.796663 0.221739 0.608875 0.761645 0.151054 0.248771 0.956711 0.207549 0.208551 0.955735 -0.237384 0.189314 0.95279 -0.237709 0.179061 0.954689 0.126681 0.665514 0.735556 0.46033 0.678488 0.572494 0.606351 0.252351 0.754094 0.606345 0.252346 0.7541 0.241246 0.96413 0.110695 0.241246 0.96413 0.110695 0.651325 0.697467 0.298857 0.651325 0.697467 0.298856 0.879475 0.252347 0.403541 0.879474 0.252346 0.403542 0.0686941 0.576041 -0.814529 0.17166 0.560682 -0.810043 0.180892 0.182596 -0.966404 -0.24325 0.182144 -0.952708 -0.243485 0.174518 -0.954075 0.292865 0.894307 -0.338296 0.125151 0.984081 -0.126182 0.199924 0.979802 -0.00425751 0.17803 0.979802 -0.0910659 0.178029 0.979802 -0.0910659 0.125819 0.980132 -0.153333 0.23091 0.935791 -0.266412 0.800642 0.5989 -0.0170502 0.618455 0.78571 -0.0131704 0.242904 0.757272 -0.606248 0.391724 0.759659 -0.519105 0.31585 0.820529 -0.476415 0.503414 0.824781 -0.257507 0.503413 0.824782 -0.257507 0.570746 0.82088 0.0201247 0.273244 0.960645 -0.0499794 0.297321 0.554977 -0.776917 0.50477 0.545701 -0.668893 0.504757 0.54571 -0.668895 0.746038 0.54571 -0.381614 0.746038 0.545709 -0.381614 0.837785 0.545708 -0.0178414 0.892149 0.440723 0.0991587 0.190138 0.190322 -0.963133 0.591354 0.190322 -0.783631 0.591355 0.190321 -0.783631 0.874012 0.190321 -0.447081 0.874015 0.190317 -0.447077 0.981499 0.190321 -0.020902 0.981499 0.190321 -0.0209019 0.959896 0.19509 0.201346 0.776456 0.608762 0.162868 0.877771 0.442288 0.18412 0.253307 0.965926 0.0531333 0.253307 0.965926 0.0531333 0.946228 0.258814 0.194081 0.944592 0.258818 0.201888 0.957914 0.195087 0.210575 0.877063 0.44229 0.187455 0.691489 0.707107 0.147793 0.693221 0.707089 0.139536 0.595797 0.793352 0.124974 0.253103 0.965926 0.0540959 0.253103 0.965926 0.0540959 0.595315 0.793354 0.127237 0.773394 0.608729 0.176949 0.117853 0.984527 0.129678 0.121109 0.979804 0.159113 0.316882 0.820364 0.476013 0.248793 0.916278 0.313905 0.215578 0.937887 0.271836 0.217185 0.718177 0.661099 0.197853 0.550992 0.810717 0.109436 0.578848 0.808059 0.123491 0.523607 0.842962 0.124879 0.188469 0.974107 0.14959 0.165437 0.974809 -0.312891 0.195138 0.929527 -0.313302 0.186796 0.931101 0.193216 0.792472 0.578495 0.36346 0.790214 0.493416 0.497533 0.544296 0.675428 0.497532 0.544294 0.67543 0.582318 0.189641 0.790533 0.582318 0.189641 0.790533 0.882693 0.189641 0.429987 0.882694 0.189642 0.429986 0.810836 0.431897 0.394982 0.775244 0.53891 0.329503 0.7209 0.59748 0.351172 0.509624 0.823805 0.248253 0.569369 0.788853 0.231366 0.140582 0.980682 0.136012 0.239139 0.963972 0.116492 0.0489074 0.582949 -0.811035 0.149606 0.564755 -0.811585 0.15564 0.179 -0.97146 -0.272325 0.185531 -0.944149 -0.272633 0.17731 -0.945639 0.277394 0.900467 -0.334979 0.121841 0.984213 -0.128372 0.200138 0.979762 -0.0033797 0.1778 0.979762 -0.0919453 0.177798 0.979762 -0.0919453 0.123028 0.980052 -0.156085 0.223955 0.936403 -0.270172 0.801004 0.598506 -0.0135264 0.618898 0.785402 -0.0104512 0.222948 0.766881 -0.60182 0.379026 0.767898 -0.516404 0.309755 0.820172 -0.48101 0.502619 0.82451 -0.259918 0.502616 0.824512 -0.259919 0.571047 0.820622 0.0220141 0.273747 0.960606 -0.047944 0.278067 0.554825 -0.784122 0.495984 0.545314 -0.675746 0.495979 0.545317 -0.675747 0.744566 0.545316 -0.385034 0.744564 0.545318 -0.385035 0.838112 0.545315 -0.0141531 0.892088 0.440478 0.10079 0.168795 0.190127 -0.96714 0.580907 0.190129 -0.791453 0.580909 0.190127 -0.791452 0.872056 0.190129 -0.450965 0.872057 0.190128 -0.450963 0.981618 0.190133 -0.0165766 0.981618 0.190133 -0.0165764 0.252992 0.965926 0.0546098 0.958704 0.195092 0.206942 0.775492 0.608762 0.167394 0.692373 0.707097 0.143644 0.595058 0.793352 0.128447 0.252992 0.965926 0.0546097 0.9594 0.195091 0.203693 0.943973 0.258819 0.204762 0.945068 0.258818 0.199648 0.876683 0.442284 0.189237 0.253177 0.965925 0.0537527 0.253176 0.965926 0.0537523 0.595489 0.793353 0.126429 0.690495 0.707099 0.152403 0.776057 0.608759 0.164767 0.877318 0.442289 0.186265 0.314157 0.822511 0.474111 0.105091 0.984932 0.137353 0.109367 0.979307 0.170285 0.188081 0.940358 0.283464 0.190924 0.938499 0.287695 0.146215 0.728118 0.669676 0.127504 0.549768 0.825529 -0.215362 0.357786 0.90863 -0.42289 0.189112 0.886229 -0.422123 0.19948 0.884319 -0.163378 0.468061 0.868462 0.0546108 0.583275 0.810437 0.0660227 0.18881 0.979792 0.0660029 0.188792 0.979797 0.12195 0.829837 0.544518 0.314933 0.822071 0.474359 0.464637 0.54252 0.699846 0.464636 0.542519 0.699848 0.543163 0.188794 0.818127 0.543168 0.188801 0.818121 0.877365 0.188802 0.441117 0.877365 0.1888 0.441119 0.806501 0.430272 0.40549 0.770762 0.53721 0.342536 0.717614 0.595697 0.360798 0.508057 0.822575 0.255438 0.566762 0.787565 0.241913 0.141512 0.980763 0.134458 0.238681 0.963655 0.120004 0.631358 0.190502 -0.751728 0.742958 0.0210921 -0.669006 0.642886 0.00148002 -0.76596 0.665929 0.0252745 -0.745587 0.64263 0.0402019 -0.765122 0.760929 0.179968 -0.623376 0.74439 0.171653 -0.645305 0.66885 0.709956 -0.220461 0.760383 0.0415407 -0.648145 0.793921 0.0481641 -0.606111 0.808004 0.063473 -0.585748 0.848816 0.0596554 -0.525312 0.898352 0.116354 -0.423586 0.942956 0.0779371 -0.323666 0.981163 0.155385 -0.114781 0.991124 0.129917 -0.028206 0.983796 0.159704 0.0814832 0.97609 0.169353 0.136261 0.869613 0.492226 0.0385647 0.887124 0.429074 -0.170019 0.899855 0.415528 -0.132658 0.846902 0.301075 -0.438305 0.853871 0.295312 -0.428596 0.768972 0.197501 -0.608009 0.77063 0.197229 -0.605995 0.723511 0.145719 -0.674757 0.724271 0.145846 -0.673914 0.876381 0.481251 -0.018813 0.766547 0.641973 -0.0166031 0.712979 0.682336 -0.161492 0.72874 0.492338 -0.475964 0.775035 0.452555 -0.441039 0.670836 0.334275 -0.661996 0.714993 0.322768 -0.620166 0.641825 0.242655 -0.727447 0.678048 0.247176 -0.69221 0.530555 0.846176 -0.0499698 0.617222 0.784734 0.0568215 0.824325 0.561265 0.07396 0.847588 0.516274 0.122702 0.524263 0.840946 0.13401 0.548698 0.82109 0.157294 0.826827 0.509378 0.23852 0.799607 0.565975 0.200751 0.953577 0.169901 0.248645 0.958974 0.176951 0.221487 0.956546 0.199532 0.212619 0.967076 0.197861 0.160046 0.967991 0.179111 0.175818 0.5998 0.686797 0.410548 0.557639 0.778977 0.286764 0.776328 0.514835 0.363675 0.786002 0.460403 0.41259 0.871944 0.391308 0.294267 0.951875 0.150354 0.267073 0.580752 0.354433 0.732874 0.812427 0.109433 0.572701 0.838479 0.162384 0.520178 0.637936 0.468523 0.611166 0.622268 0.446912 0.642692 0.625074 0.745764 0.230474 0.910756 0.09198 0.402572 0.913685 0.271936 0.302044 0.83587 0.32884 0.43953 0.75081 0.470173 0.463921 0.603029 0.000935498 0.797718 0.602831 0.000742004 0.797869 0.599194 0.120676 0.791457 0.598493 0.11994 0.792099 0.596492 0.375202 0.709521 0.603427 3.67065e-05 0.797419 0.63978 0.0363653 0.767698 0.65142 0.0087124 0.758668 0.742835 0.110639 0.660268 0.751863 0.0528576 0.657197 0.212993 0.915065 -0.342475 -0.393349 0.186452 -0.900285 0.100554 0.570022 -0.815453 0.37403 0.694953 -0.614119 -0.0203644 0.682225 -0.730859 0.0991228 0.626378 -0.773191 0.106342 0.984542 -0.139169 0.109174 0.960522 -0.255887 0.228796 0.963955 -0.135807 0.228797 0.963955 -0.135807 0.265723 0.963954 -0.0135439 0.265723 0.963954 -0.0135437 0.375257 0.696537 -0.61157 0.61701 0.69654 -0.366239 0.61701 0.69654 -0.366239 0.716586 0.696542 -0.0365241 0.716585 0.696542 -0.0365245 -0.392622 0.197472 -0.89825 0.0639529 0.220218 -0.973352 0.0233734 0.249104 -0.968195 0.506165 0.251729 -0.824882 0.506149 0.25174 -0.824888 0.832228 0.251741 -0.493988 0.832229 0.251739 -0.493986 0.96654 0.25174 -0.0492629 0.96654 0.251741 -0.0492642 0.949715 0.258811 0.176231 0.254483 0.965924 0.0472226 0.254482 0.965924 0.0472222 0.695253 0.707092 0.129013 0.967478 0.19508 0.161027 0.952231 0.258816 0.162082 0.949715 0.258812 0.176231 0.69525 0.707095 0.129012 0.255319 0.965922 0.0424957 0.255318 0.965923 0.0424952 0.600521 0.793337 0.0999511 0.696722 0.707103 0.120762 0.782606 0.608738 0.130257 0.884709 0.442275 0.147251 0.0723513 0.984094 0.162249 0.0634458 0.980125 0.18796 0.127137 0.820492 0.557342 0.153766 0.894863 0.419018 0.121602 0.935842 0.330776 0.00984434 0.708621 0.705521 -0.0777032 0.551093 0.830818 -0.132466 0.562189 0.816331 -0.135695 0.505089 0.852333 -0.172661 0.189877 0.966507 -0.163361 0.181841 0.969663 -0.565365 0.18243 0.804414 -0.566065 0.174871 0.8056 0.0123099 0.758147 0.651967 0.182857 0.760404 0.623177 0.235943 0.545676 0.804095 0.235932 0.545664 0.804106 0.276395 0.190302 0.942014 0.27641 0.190315 0.942007 0.134512 0.979799 0.147988 0.134513 0.979798 0.147991 0.380346 0.824761 0.418457 0.380346 0.824761 0.418456 0.563646 0.545667 0.620122 0.563648 0.545671 0.620116 0.660319 0.190313 0.726471 0.66031 0.190302 0.726482 0.911425 0.190306 0.364813 0.911424 0.190304 0.364815 0.836769 0.433171 0.334933 0.797266 0.540215 0.269324 0.743508 0.598857 0.297602 0.52499 0.82476 0.210136 0.58433 0.789827 0.186364 0.147953 0.980559 0.128898 0.246128 0.964218 0.0985167 0.740371 -0.000259563 -0.672198 0.760814 0.0239824 -0.648527 0.779965 0.00894885 -0.625759 0.8419 0.0948776 -0.531227 0.880811 0.0713727 -0.468058 0.917964 0.137643 -0.372017 0.931685 0.159224 -0.326513 0.739902 0.00100048 -0.672713 0.769751 0.0369796 -0.637273 0.733887 0.119891 -0.668608 0.81555 0.242377 -0.525483 0.678075 0.398242 -0.617752 0.735555 0.544534 -0.403041 0.665316 0.43586 -0.606119 0.935032 0.167929 -0.312273 0.611436 0.596446 -0.519999 0.698963 0.714438 -0.0320869 0.813235 0.320144 -0.48596 0.878337 0.341589 0.334428 0.566294 0.726594 -0.389066 0.629431 0.755732 -0.180793 0.842581 0.481603 -0.241074 0.856872 0.49105 -0.156974 0.986094 0.165757 -0.0119637 0.980774 0.162239 -0.108451 0.718516 0.688524 0.0983377 0.441365 0.883309 -0.157998 0.445493 0.870164 -0.210595 0.522922 0.852064 -0.0232329 0.788248 0.610719 -0.0754161 0.817545 0.574805 0.0349179 0.973603 0.218963 0.064435 0.97457 0.200379 0.100307 0.966098 0.225969 0.124871 0.964135 0.246206 0.0991293 0.767654 0.633367 0.0977389 0.735246 0.677492 0.0204407 0.405384 0.912453 0.0556257 0.282478 0.956205 0.0766728 0.320992 0.947081 -0.00108591 0.329051 0.941851 -0.0681293 0.957822 0.250411 0.140967 0.959449 0.230879 0.161716 0.958068 0.230165 0.170674 0.960606 0.192254 0.200684 0.960975 0.192998 0.19819 0.958649 0.171679 0.226975 0.745913 0.643625 0.171347 0.746106 0.643736 0.170087 0.782835 0.546225 0.298006 0.78783 0.556602 0.263664 0.784905 0.486623 0.383566 0.959735 0.246896 0.133979 0.959399 0.250474 0.129676 0.725334 0.68053 0.103776 0.719588 0.688513 0.0902369 0.334279 0.941067 0.0514752 0.3482 0.936789 0.0344119 0.361664 0.90962 0.204427 0.37804 0.920893 0.0950903 0.468683 0.79581 0.383436 0.487811 0.836865 0.24839 0.480359 0.696082 0.533597 0.500902 0.632686 0.590598 0.518721 0.802653 0.294409 0.789991 0.440862 0.426092 0.799333 0.525404 0.291577 0.957507 0.15405 0.243823 0.96138 0.179036 0.209034 0.646808 0.0047693 0.762638 0.640363 0.147094 0.753856 0.639839 0.146503 0.754416 0.584757 0.512914 0.628473 0.56662 0.48228 0.668092 0.539096 0.742329 0.397898 0.646798 0.00387192 0.762652 0.674709 0.0329401 0.737348 0.667029 0.0622156 0.74243 0.748621 0.159231 0.643593 0.727705 0.251609 0.638074 0.78861 0.346821 0.507749 0.787477 0.435113 0.436528 0.649337 0 0.760501 0.684071 0.0366077 0.728496 0.707842 -0.00200785 0.706368 0.809927 0.124957 0.573066 0.845019 0.0231566 0.534235 0.932685 0.166379 0.320026 0.928916 0.0969382 0.357377 0.646622 0.00457968 0.762797 0.728241 -0.000578411 -0.68532 0.749592 0.0242168 -0.661457 0.769405 0.00896928 -0.638699 0.832896 0.0948774 -0.545236 0.872864 0.0713696 -0.482717 0.914167 0.142936 -0.3793 0.929034 0.161809 -0.332736 0.797395 0.4582 -0.3927 0.727771 0.000660684 -0.68582 0.758863 0.037353 -0.650178 0.722619 0.119915 -0.680766 0.806649 0.24238 -0.539045 0.667664 0.398231 -0.628997 0.739824 0.641685 -0.202239 0.608921 0.547804 -0.573695 0.591244 0.615977 -0.520579 0.645901 0.687359 -0.33219 0.837499 0.409738 -0.361539 0.721879 0.292581 -0.627126 0.84837 0.355965 0.391863 0.935092 0.17717 -0.306944 0.575653 0.685499 -0.445774 0.610581 0.761086 -0.218948 0.840999 0.459698 -0.285304 0.850486 0.482931 -0.208451 0.984145 0.168669 -0.0548594 0.978039 0.146679 -0.148068 0.98313 0.181872 -0.0194509 0.841252 0.528632 -0.11333 0.57244 0.803076 -0.165474 0.983069 0.176184 -0.0503408 0.980778 0.194962 0.00805789 0.974217 0.224359 -0.0237407 0.972983 0.228478 0.03319 0.970331 0.240756 0.0222469 0.969593 0.240668 0.044372 0.972558 0.224897 0.0596091 0.971943 0.223847 0.0722523 0.977316 0.187542 0.098393 0.977606 0.189742 0.0910179 0.976579 0.17801 0.120852 0.836225 0.501002 -0.222993 0.827362 0.560524 -0.0358408 0.771218 0.624486 -0.12345 0.769439 0.638199 0.0257851 0.745897 0.666028 -0.00669187 0.744898 0.666315 0.0339445 0.772231 0.629566 0.0854785 0.771654 0.628466 0.0978799 0.819147 0.535251 0.206166 0.820462 0.547984 0.162958 0.817807 0.506498 0.273225 0.559442 0.728407 -0.395535 0.546078 0.834991 -0.0677393 0.401828 0.89229 -0.2058 0.423003 0.906016 0.0142466 0.345555 0.937135 -0.0486772 0.346928 0.937864 0.00727864 0.426638 0.896653 0.118297 0.435671 0.896752 0.0776279 0.528306 0.778747 0.338298 0.533908 0.8257 0.182104 0.529103 0.737458 0.41977 0.892364 0.0906227 0.442124 0.548038 0.503581 0.667878 0.602768 0.606584 0.518389 0.735745 0.412011 0.537519 0.0788716 -0.306012 0.948755 0.821446 0.305232 0.481726 0.919072 0.139569 0.368546 0.943776 0.11258 0.310827 0.943989 0.198215 0.263809 0.800962 0.455274 0.388826 0.804484 0.406993 0.432621 0.545419 0.762595 0.347802 0.581167 0.566194 0.584525 0.971453 0.159932 0.175215 0.976678 0.186246 0.106829 0.822553 0.528748 0.209362 0.815498 0.489296 0.309115 0.54161 0.821084 0.180221 0.534394 0.72307 0.437712 0.633041 0.00374575 0.774109 0.632413 0.00311764 0.774625 0.628527 0.120664 0.768371 0.627854 0.119932 0.769035 0.605686 0.436872 0.665047 0.546999 0.501865 0.670018 0.681162 0.724813 -0.103269 0.74378 0.426622 0.514573 0.81554 0.294772 0.498 0.634403 0.000569128 0.773002 0.66844 0.0357757 0.742905 0.679482 0.00872052 0.733641 0.781229 0.129525 0.610659 0.794209 0.0616537 0.604509 0.863528 0.472316 -0.176741 0.887829 0.0860412 0.452059 0.0493638 0.61545 -0.786629 -0.439728 0.176801 -0.880557 -0.439127 0.185438 -0.879079 -0.0130718 0.20822 -0.977995 -0.247886 0.369375 -0.895609 0.187947 0.912521 -0.363292 0.224885 0.869873 -0.43903 0.0961374 0.984158 -0.148966 0.0762119 0.96036 -0.268144 0.207755 0.964183 -0.16489 0.207754 0.964183 -0.16489 0.259172 0.964184 -0.0563905 0.259172 0.964184 -0.0563904 -0.0597116 0.652285 -0.755618 0.318908 0.66874 -0.671628 0.277082 0.693244 -0.665311 0.561086 0.697756 -0.445331 0.561096 0.69775 -0.445327 0.699965 0.69775 -0.152296 0.699963 0.697751 -0.152298 0.0350071 0.254967 -0.966316 0.415017 0.252538 -0.874063 0.415029 0.25253 -0.874059 0.757895 0.252531 -0.601518 0.757883 0.25254 -0.601528 0.945466 0.252537 -0.205714 0.945467 0.252536 -0.205712 0.258822 0.965924 0.00161378 0.258821 0.965924 0.00161369 0.707105 0.707095 0.00440865 0.707105 0.707095 0.00440862 0.965519 0.258725 -0.0289012 0.965909 0.258813 0.00602221 0.965909 0.258812 0.00602234 0.258813 0.965896 -0.00774551 0.258799 0.9659 -0.00774589 0.608662 0.79322 -0.0182174 0.706983 0.707012 -0.0175989 0.793132 0.608586 -0.0237403 0.965523 0.258708 -0.0289004 0.979014 0.195091 -0.0589192 0.964387 0.258817 -0.0545055 0.829823 0.555569 -0.0523048 0.791921 0.608761 -0.0476597 0.554567 0.83147 -0.0333751 0.607445 0.793349 -0.040091 0.195017 0.980775 -0.00704876 0.258352 0.965926 -0.0155482 0.0999036 0.984238 0.145931 0.0968708 0.980034 0.173634 0.230743 0.820137 0.523577 0.219654 0.901605 0.37264 0.178184 0.936522 0.301955 0.132762 0.7117 0.689824 0.0786653 0.551204 0.830654 0.0105095 0.567227 0.823494 0.0155997 0.51074 0.859594 -0.000423114 0.189464 0.981888 0.0135139 0.177437 0.984039 -0.419805 0.186159 0.888318 -0.420447 0.176432 0.889998 0.12393 0.768681 0.627512 0.29257 0.769452 0.567756 0.383992 0.545232 0.745166 0.384011 0.545257 0.745138 0.449747 0.190094 0.872693 0.449734 0.190081 0.872702 0.161424 0.979754 0.118428 0.161422 0.979755 0.118422 0.456297 0.824461 0.334749 0.456301 0.824452 0.334766 0.675885 0.54525 0.495865 0.675882 0.545235 0.495885 0.791569 0.190087 0.580763 0.791578 0.190103 0.580745 0.197286 0.979754 0.0340502 0.197287 0.979754 0.0340504 0.557678 0.824458 0.0962517 0.557676 0.82446 0.0962483 0.826068 0.545239 0.14257 0.826069 0.545236 0.142574 0.967461 0.190099 0.166977 0.967461 0.1901 0.166975 0.591354 -0.190321 -0.783632 0.259287 -0.708357 -0.656507 0.242904 -0.757272 -0.606248 0.125151 -0.984081 -0.126182 0.125819 -0.980132 -0.153332 0.175203 -0.504395 -0.845511 -0.243485 -0.174518 -0.954075 -0.24325 -0.182144 -0.952708 0.190436 -0.182213 -0.964641 0.180997 -0.189914 -0.964973 0.591355 -0.190322 -0.783631 0.504766 -0.545711 -0.668888 0.165597 -0.561764 -0.810555 0.220838 -0.55106 -0.804713 0.50476 -0.545702 -0.668899 0.391724 -0.759659 -0.519105 0.31585 -0.820529 -0.476415 0.292865 -0.894307 -0.338296 0.23091 -0.935791 -0.266412 0.981499 -0.190321 -0.020902 0.981499 -0.190321 -0.0209019 0.901097 -0.433193 -0.0191896 0.841026 -0.540249 0.0284188 0.800642 -0.5989 -0.0170502 0.565323 -0.824782 -0.0120389 0.612507 -0.789851 0.0311634 0.183818 -0.980555 -0.0687309 0.26503 -0.964224 -0.00564399 0.874012 -0.190317 -0.447082 0.874014 -0.190321 -0.447076 0.746038 -0.545709 -0.381614 0.746038 -0.54571 -0.381613 0.503413 -0.824782 -0.257506 0.503414 -0.824782 -0.257507 0.17803 -0.979802 -0.0910663 0.17803 -0.979802 -0.0910656 0.193216 -0.792472 0.578495 0.36346 -0.790214 0.493416 0.316882 -0.820364 0.476013 0.248793 -0.916278 0.313905 0.215578 -0.937887 0.271836 0.121109 -0.979804 0.159113 0.117853 -0.984527 0.129678 0.0266694 -0.600216 0.799393 0.121611 -0.575324 0.808834 0.124459 -0.168061 0.977888 -0.312891 -0.195138 0.929527 -0.313302 -0.186796 0.931101 0.148928 -0.18964 0.970493 0.582318 -0.189641 0.790533 0.582318 -0.189641 0.790533 0.882693 -0.189642 0.429987 0.882694 -0.189641 0.429986 0.254432 -0.554253 0.792507 0.497531 -0.544297 0.675429 0.497534 -0.544294 0.675429 0.754173 -0.544293 0.36738 0.849622 -0.439811 0.291047 0.7209 -0.59748 0.351172 0.557388 -0.784599 0.27152 0.527138 -0.819943 0.223199 0.229315 -0.960492 0.157703 0.180413 -0.979657 0.0878847 0.617243 -0.190737 -0.763303 0.213284 -0.552977 -0.805435 0.230754 -0.494448 -0.838018 0.0733233 -0.995367 -0.0621964 0.0917262 -0.976277 -0.196139 -0.172767 -0.167021 -0.970698 -0.172669 -0.173333 -0.969609 0.242791 -0.164931 -0.955955 0.214096 -0.1895 -0.958255 0.617245 -0.19074 -0.7633 0.550295 -0.483823 -0.680508 0.487942 -0.540685 -0.685253 0.378066 -0.7908 -0.481354 0.334453 -0.82196 -0.461002 0.318601 -0.882191 -0.346745 0.209029 -0.956705 -0.202539 0.981249 -0.190738 -0.027725 0.981249 -0.190738 -0.0277254 0.900555 -0.433996 -0.0254454 0.840618 -0.54106 0.0247963 0.799852 -0.599771 -0.0226001 0.564351 -0.825381 -0.015946 0.611841 -0.790449 0.0290042 0.182809 -0.980436 -0.0729773 0.264425 -0.964377 -0.00747152 0.879808 -0.190737 -0.435381 0.879808 -0.190737 -0.435381 0.750537 -0.546579 -0.37141 0.750537 -0.546579 -0.371409 0.506009 -0.825381 -0.250403 0.506009 -0.825381 -0.250402 0.178835 -0.979891 -0.0884976 0.178835 -0.979891 -0.0884978 0.25415 -0.965926 0.0489395 0.254151 -0.965926 0.0489395 0.948501 -0.258819 0.182644 0.964228 -0.195089 0.179455 0.880694 -0.442288 0.169587 0.694354 -0.707104 0.133705 0.781276 -0.60873 0.13804 0.59778 -0.793353 0.115109 0.947471 -0.258817 0.187918 0.94747 -0.258819 0.187918 0.693598 -0.707105 0.137566 0.693599 -0.707104 0.137566 0.253875 -0.965926 0.0503527 0.253874 -0.965926 0.0503526 -0.233609 -0.1822 0.955107 0.119048 -0.969098 0.216048 0.166219 -0.964065 0.207242 0.0173818 -0.999707 0.0168556 -0.233264 -0.19297 0.953074 0.213965 -0.212159 0.953524 0.16093 -0.249099 0.955014 0.127193 -0.668673 0.732597 0.223577 -0.609987 0.760216 0.230801 -0.56173 0.794475 0.609459 -0.252426 0.751559 0.609463 -0.252423 0.751557 0.460756 -0.681819 0.568179 0.437034 -0.695086 0.570839 0.308594 -0.878218 0.365381 0.272219 -0.90717 0.320841 0.880012 -0.252424 0.402319 0.880013 -0.252423 0.402318 0.651633 -0.697585 0.297909 0.651635 -0.697584 0.297908 0.241327 -0.964152 0.110327 0.241326 -0.964152 0.110328 0.69244 -0.542661 -0.475444 -0.0556946 -0.199638 -0.978286 0.196656 -0.965511 -0.170629 0.416988 -0.698871 -0.58112 0.385959 -0.749353 -0.538057 0.363209 -0.772041 -0.521567 -0.0556803 -0.189163 -0.980366 0.42982 -0.188865 -0.882941 0.429824 -0.188869 -0.882938 0.809543 -0.188868 -0.555849 0.809542 -0.188866 -0.555852 0.153617 -0.363881 -0.918691 0.158246 -0.416797 -0.895119 0.37526 -0.514733 -0.770863 0.356245 -0.54103 -0.761824 0.69244 -0.542659 -0.475446 0.464482 -0.826162 -0.318925 0.47035 -0.823162 -0.31808 0.281359 -0.949229 -0.14072 0.207495 -0.968158 -0.140059 0.978405 -0.188866 -0.0839864 0.978405 -0.188866 -0.083986 0.899334 -0.430394 -0.0771985 0.842764 -0.537345 -0.0317796 0.80016 -0.595841 -0.0686848 0.566431 -0.822673 -0.0486218 0.615942 -0.787666 -0.0140658 0.188695 -0.979408 -0.0717946 0.263786 -0.964545 -0.00831419 0.224205 -0.92922 0.293738 0.25467 -0.965926 0.0461562 0.25488 -0.965926 0.044984 0.25488 -0.965926 0.0449841 0.951225 -0.258818 0.167883 0.967131 -0.195088 0.16309 0.883222 -0.442289 0.155881 0.696346 -0.707106 0.122899 0.783775 -0.608709 0.123168 0.599497 -0.793353 0.105806 0.254615 -0.965941 0.0461529 0.503293 -0.859286 0.0912296 0.695513 -0.707103 0.127543 0.704968 -0.697632 0.127786 0.950438 -0.258818 0.172281 0.849872 -0.494048 0.183398 0.952111 -0.252385 0.172585 0.506904 -0.613259 0.605774 0.0851901 -0.240171 0.966985 0.0871291 -0.175833 0.980557 0.559999 -0.199931 0.804008 0.339293 -0.376857 0.861893 0.79225 -0.481508 0.37482 0.483155 -0.614466 0.623692 0.717275 -0.611617 0.333828 0.490616 -0.773282 0.401659 0.674588 -0.691506 0.258362 0.396879 -0.905807 0.148326 0.495407 -0.858589 0.131896 0.258693 -0.954646 0.147408 0.600293 -0.247647 0.760473 0.876527 -0.244402 0.414691 0.876526 -0.244403 0.414692 0.932577 -0.306744 -0.190287 0.553695 -0.832642 -0.0113349 0.564064 -0.825557 -0.0169629 0.316111 -0.93017 0.186699 0.72149 -0.691056 -0.0435039 0.544439 -0.832707 0.100921 0.768507 -0.63516 -0.0772597 0.717319 -0.696592 0.0145984 0.853415 -0.50995 -0.107862 0.885199 -0.358267 -0.296762 0.942472 -0.234568 -0.238168 0.942472 -0.234569 -0.238168 0.864891 -0.495737 -0.0787999 0.766379 -0.641754 0.0285669 0.362105 -0.881562 0.302868 0.38573 -0.875933 0.289746 0.576414 -0.797079 0.180035 0.735222 -0.675211 0.0594808 0.922621 -0.258396 -0.286359 0.922621 -0.258394 -0.286361 0.782901 -0.603289 -0.152017 0.712728 -0.695285 -0.092725 0.310652 -0.944513 0.106729 0.310654 -0.944512 0.106728 0.622129 -0.781363 -0.0492637 0.90391 -0.258823 -0.340526 0.918019 -0.195094 -0.345224 0.742265 -0.60876 -0.280095 0.77809 -0.555565 -0.293126 0.569671 -0.793359 -0.21461 0.519793 -0.831473 -0.196131 0.242359 -0.965925 -0.0908379 0.182571 -0.980784 -0.068779 0.970532 -0.194123 0.142776 0.97053 -0.194129 0.142776 0.823916 -0.553599 0.121207 0.823918 -0.553596 0.121207 0.551602 -0.830151 0.0811466 0.551601 -0.830152 0.0811464 0.193973 -0.980592 0.0285356 0.193975 -0.980591 0.0285358 0.979412 -0.194129 -0.0553714 0.979412 -0.194131 -0.0553713 0.831458 -0.553596 -0.0470067 0.831457 -0.553596 -0.0470066 0.556649 -0.830152 -0.0314703 0.556653 -0.830149 -0.0314708 0.195751 -0.980591 -0.0110669 0.195748 -0.980592 -0.0110666 0.948253 -0.194131 -0.251254 0.948253 -0.194132 -0.251254 0.805006 -0.553596 -0.213299 0.805008 -0.553593 -0.2133 0.538944 -0.830149 -0.142802 0.538941 -0.830151 -0.142801 0.189521 -0.980592 -0.0502164 0.189522 -0.980591 -0.050217 0.95094 -0.195085 0.240114 0.936746 -0.258823 0.235623 0.806022 -0.555571 0.204129 0.769213 -0.608759 0.194228 0.538659 -0.831473 0.136013 0.590017 -0.793356 0.149887 0.189444 -0.980784 0.0466317 0.250947 -0.965925 0.0633646 0.955418 -0.167604 0.243075 0.931291 -0.258768 0.256389 0.882395 -0.411605 0.227949 0.802886 -0.558569 0.208265 0.766416 -0.60872 0.205101 0.645176 -0.746344 0.163459 0.587583 -0.793311 0.159384 0.507445 -0.850642 0.137503 0.287195 -0.954575 0.0794103 0.246504 -0.965769 0.0807891 0.0424225 -0.998861 0.0218257 0.963791 -0.236976 0.122267 0.978819 -0.170601 0.113176 0.901077 -0.414248 0.128291 0.0332911 -0.996814 0.0724778 0.354851 -0.928654 0.108084 0.817933 -0.560856 0.128165 0.654252 -0.747665 0.113803 0.74277 -0.656766 0.1302 0.511647 -0.85145 0.115111 0.284518 -0.954052 0.093992 0.964312 -0.222828 0.143004 0.961215 -0.234388 0.145355 0.761284 -0.622826 0.180372 0.736643 -0.650611 0.184558 0.404252 -0.896533 0.181129 0.346488 -0.920128 0.182511 0.962558 -0.215318 0.164685 0.961694 -0.218549 0.165473 0.763276 -0.60251 0.233218 0.754874 -0.612318 0.235013 0.415764 -0.872575 0.256423 0.395425 -0.881816 0.256983 0.409069 -0.858026 0.31057 0.74785 -0.573085 0.335104 0.939171 -0.179495 0.292812 0.394687 -0.863947 0.312757 0.368443 -0.852325 0.371204 0.363441 -0.854918 0.370171 0.3177 -0.849708 0.420789 0.322504 -0.846302 0.423986 0.263825 -0.849185 0.457472 0.271536 -0.839974 0.4698 0.722842 -0.597806 0.346594 0.649768 -0.565553 0.50789 0.636109 -0.580384 0.508448 0.508495 -0.565722 0.649147 0.509497 -0.564326 0.649576 0.336748 -0.57242 0.74762 0.345265 -0.55172 0.759208 0.136384 -0.215018 0.96704 0.360342 -0.173221 0.916596 0.353385 -0.205334 0.912665 0.61163 -0.193152 0.767204 0.612748 -0.190257 0.767035 0.749854 -0.206822 0.628446 0.831276 -0.0919916 0.548195 0.836445 -0.19016 0.514002 0.919644 -0.22708 0.320451 -0.028489 -0.18503 0.98232 0.00735216 -0.0568463 0.998356 0.145741 -0.549155 0.822914 0.143915 -0.587319 0.796458 0.210819 -0.840139 0.499721 0.208486 -0.851258 0.481554 -0.261186 -0.15796 0.952276 -0.245857 -0.250313 0.936428 -0.0668229 -0.565696 0.821902 -0.053887 -0.611119 0.789702 0.146152 -0.850533 0.505206 0.149924 -0.859044 0.489454 -0.397963 -0.230458 0.887983 -0.401454 -0.221379 0.888722 -0.154831 -0.63568 0.756266 -0.169105 -0.61489 0.770268 0.124925 -0.887671 0.443209 0.10115 -0.871217 0.480364 -0.432426 -0.258578 0.863797 -0.435332 -0.243023 0.866848 -0.241399 -0.70241 0.669587 -0.257678 -0.669059 0.69711 0.0114812 -0.954157 0.299086 -0.0185238 -0.932109 0.361703 -0.470206 -0.258815 0.843754 -0.470206 -0.25882 0.843753 -0.344214 -0.707108 0.617669 -0.344214 -0.707108 0.617669 -0.125993 -0.965925 0.226085 -0.125993 -0.965925 0.226086 -0.470205 -0.258822 0.843752 -0.470206 -0.258821 0.843753 -0.344214 -0.707109 0.617669 -0.344214 -0.707108 0.617669 -0.125993 -0.965925 0.226087 -0.125993 -0.965925 0.226087 -0.951017 -0.255076 0.174651 -0.951017 -0.255074 0.174652 -0.700876 -0.701574 0.128714 -0.700876 -0.701574 0.128714 -0.258293 -0.964901 0.0474348 -0.258293 -0.964901 0.0474349 -0.83234 -0.255074 0.492084 -0.83234 -0.255077 0.492083 -0.613414 -0.701574 0.362653 -0.613415 -0.701573 0.362654 -0.226061 -0.964901 0.133649 -0.226061 -0.964901 0.133648 -0.61142 -0.255076 0.749067 -0.61142 -0.255078 0.749067 -0.450602 -0.701574 0.552044 -0.450602 -0.701573 0.552044 -0.16606 -0.964901 0.203445 -0.16606 -0.964901 0.203444 -0.965914 -0.258818 0.00492784 -0.965913 -0.258819 0.00492761 -0.707097 -0.707107 0.00360726 -0.707096 -0.707108 0.0036068 -0.258818 -0.965925 0.0013202 -0.258819 -0.965925 0.00132042 -0.965917 -0.258817 0.00417764 -0.965917 -0.258818 0.00417744 -0.707099 -0.707108 0.00305809 -0.7071 -0.707107 0.00305828 -0.258819 -0.965925 0.00111942 -0.258819 -0.965925 0.00111944 0.501278 -0.224215 -0.835732 0.499342 -0.241704 -0.832007 -0.0493586 -0.705506 -0.706983 -0.106714 -0.96846 -0.225159 0.0941524 -0.940488 -0.326523 -0.053008 -0.891205 -0.450493 0.0544466 -0.722657 -0.689059 0.0484189 -0.624733 -0.779336 0.101479 -0.250058 -0.962898 0.0685936 -0.213762 -0.974475 -0.739452 -0.252164 -0.624199 -0.739453 -0.252163 -0.624198 -0.547809 -0.697187 -0.462424 -0.54781 -0.697186 -0.462424 -0.941963 -0.252163 -0.221628 -0.941964 -0.252161 -0.221626 -0.697835 -0.697186 -0.164187 -0.697834 -0.697187 -0.164188 -0.376583 -0.252164 -0.891403 -0.376585 -0.252163 -0.891402 -0.278985 -0.697186 -0.660378 -0.278984 -0.697187 -0.660378 -0.103371 -0.964076 -0.244688 -0.202979 -0.964076 -0.171341 -0.202979 -0.964076 -0.171341 -0.258568 -0.964076 -0.0608365 -0.258567 -0.964076 -0.0608368 0.0786044 0.189864 -0.978659 0.339139 0.372922 -0.863663 0.306805 0.438268 -0.844862 0.000501601 0.828265 -0.560337 -0.084506 0.980102 -0.179609 0.506577 0.219188 -0.833868 0.509358 0.190186 -0.839276 0.078606 0.189862 -0.978659 0.0694617 0.49727 -0.864811 0.0851642 0.542678 -0.835612 -0.0109288 0.695791 -0.718161 -0.0346324 0.825047 -0.564002 -0.375696 0.189865 -0.907086 -0.375695 0.189864 -0.907086 -0.320895 0.544747 -0.774776 -0.320896 0.544748 -0.774774 -0.216743 0.824119 -0.523307 -0.216744 0.824119 -0.523307 -0.0702667 0.982996 -0.169652 -0.121389 0.98364 -0.133107 -0.955395 0.189861 -0.226213 -0.955395 0.189864 -0.226211 -0.877464 0.432311 -0.207759 -0.82502 0.541032 -0.163175 -0.779979 0.597936 -0.184676 -0.551179 0.824118 -0.130503 -0.605414 0.788419 -0.108943 -0.172871 0.980783 -0.0904462 -0.258555 0.964055 -0.0612186 -0.747563 0.189864 -0.636476 -0.747563 0.189864 -0.636476 -0.63852 0.544748 -0.543637 -0.63852 0.544748 -0.543637 -0.431278 0.824118 -0.367191 -0.431278 0.824118 -0.367191 -0.152622 0.979705 -0.129943 -0.152622 0.979705 -0.129943 -0.258812 0.965927 0.00132038 -0.965913 0.25882 0.00492783 -0.707099 0.707105 0.00360727 -0.965913 0.258819 0.00492761 -0.965917 0.258819 0.00417764 -0.980726 0.195067 -0.0112034 -0.896865 0.442288 0.0038788 -0.707103 0.707103 0.00305811 -0.707101 0.707104 0.00360682 -0.258813 0.965927 0.00132017 -0.258813 0.965927 0.00111941 -0.258813 0.965927 0.00111939 -0.60876 0.79335 0.00263295 -0.793099 0.608477 -0.0273781 0.953587 0.234014 -0.189498 0.879287 0.456445 -0.136063 0.696664 0.717123 0.0198497 0.743867 0.665737 -0.0587928 0.686814 0.726569 -0.0195949 0.286975 0.950631 0.118089 0.553696 0.832642 -0.0113349 -0.611419 0.25508 0.749067 -0.61142 0.255078 0.749067 -0.450604 0.70157 0.552047 -0.450603 0.70157 0.552047 -0.166056 0.964903 0.203439 -0.166056 0.964903 0.203439 -0.832339 0.255079 0.492083 -0.832341 0.255076 0.492083 -0.613418 0.701569 0.362655 -0.613417 0.701571 0.362655 -0.226055 0.964903 0.133645 -0.226056 0.964903 0.133645 -0.951017 0.255076 0.174651 -0.951016 0.255078 0.174652 -0.700879 0.701571 0.128715 -0.70088 0.70157 0.128715 -0.258286 0.964903 0.0474336 -0.258286 0.964903 0.0474336 0.946882 0.176811 -0.26861 0.907191 0.2907 -0.304135 0.946883 0.17681 -0.268611 0.86086 0.503519 -0.0734047 0.887472 0.446219 -0.115252 0.644998 0.751947 0.136211 0.717844 0.692434 0.0723568 0.329219 0.888195 0.320508 0.362111 0.88156 0.302865 -0.470206 0.258817 0.843753 -0.470206 0.258817 0.843754 -0.344216 0.707103 0.617673 -0.344216 0.707105 0.617672 -0.12599 0.965927 0.226081 -0.125989 0.965927 0.226079 0.253296 0.958393 0.131624 0.253301 0.958391 0.131622 0.575198 0.817692 -0.0229767 0.575197 0.817692 -0.0229764 0.815348 0.551402 -0.176533 0.815346 0.551406 -0.176531 0.932192 0.19491 -0.305005 0.932193 0.194906 -0.305006 -0.454684 0.252441 0.854129 -0.452053 0.258761 0.853634 -0.307081 0.692397 0.652907 -0.295379 0.706023 0.643649 -0.0817712 0.954897 0.285457 -0.0593868 0.963146 0.262342 -0.423529 0.238492 0.873925 -0.419714 0.246751 0.873473 -0.226106 0.65815 0.718133 -0.210577 0.676206 0.705977 0.0247307 0.919932 0.391298 0.0519115 0.931728 0.359427 -0.401315 0.221319 0.888799 -0.397187 0.229225 0.88865 -0.168819 0.61476 0.770435 -0.152992 0.632634 0.759189 0.101229 0.871183 0.480408 0.127545 0.884444 0.448878 0.917815 0.195095 -0.345765 0.917816 0.195093 -0.345765 0.778091 0.555564 -0.293127 0.778088 0.555569 -0.293126 0.519902 0.831469 -0.19586 0.519903 0.831468 -0.195861 0.182562 0.980786 -0.0687758 0.182562 0.980786 -0.0687757 0.143138 0.852007 0.503583 0.155265 0.857657 0.490222 -0.0772448 0.571083 0.81725 -0.035942 0.607147 0.793776 -0.281078 0.167022 0.945039 0.0491347 -0.0546088 0.997298 -0.0245444 0.185987 0.982246 -0.215421 0.243154 0.945764 0.259407 0.84103 0.474739 0.260516 0.849053 0.459609 0.313235 0.554323 0.77111 0.318807 0.574204 0.75409 0.313016 0.845133 0.433327 0.310616 0.849645 0.42617 0.484005 0.561837 0.670879 0.483477 0.566295 0.667503 0.203963 0.842787 0.498105 0.211299 0.850291 0.482035 0.127766 0.55732 0.820409 0.148593 0.586072 0.796517 0.0427533 0.226644 0.973039 0.312359 0.175766 0.933562 0.325416 0.207871 0.922439 0.57417 0.189684 0.796461 0.574498 0.192042 0.795658 0.735736 0.206506 0.645018 0.828895 0.192899 0.525093 0.813536 0.0642349 0.577957 0.632731 0.562709 0.531987 0.626131 0.577742 0.523616 0.362546 0.851287 0.379304 0.360001 0.85361 0.376496 0.931457 0.170886 0.321226 0.920844 0.229978 0.31489 0.744055 0.566921 0.35353 0.72357 0.598342 0.344141 0.408067 0.855856 0.317792 0.395232 0.86413 0.311563 0.948253 0.194134 -0.251254 0.948253 0.194132 -0.251254 0.805008 0.553593 -0.213299 0.805006 0.553597 -0.213299 0.538947 0.830147 -0.142802 0.538951 0.830144 -0.142803 0.189514 0.980593 -0.0502145 0.189512 0.980594 -0.0502141 0.979411 0.194132 -0.0553714 0.979412 0.194131 -0.0553713 0.831457 0.553596 -0.0470067 0.831458 0.553596 -0.0470067 0.55666 0.830144 -0.0314709 0.556655 0.830147 -0.0314709 0.195739 0.980594 -0.0110662 0.195741 0.980593 -0.0110663 0.97053 0.194131 0.142775 0.970531 0.194124 0.142776 0.823918 0.553596 0.121207 0.823916 0.553599 0.121207 0.551607 0.830147 0.0811474 0.551608 0.830147 0.0811476 0.193966 0.980593 0.0285345 0.193964 0.980594 0.0285342 0.450375 0.886057 0.109847 0.818278 0.560346 0.128191 0.901344 0.413675 0.128264 0.964209 0.237443 0.117989 0.978372 0.168988 0.1193 0.7427 0.656694 0.130954 0.516311 0.851822 0.0884461 0.654259 0.747659 0.113804 0.354701 0.928534 0.109596 0.038742 0.998315 0.0431907 0.224164 0.971118 0.0817338 0.403759 0.895752 0.186028 0.347071 0.920817 0.177872 0.761001 0.622321 0.183289 0.737011 0.650975 0.181786 0.964212 0.222651 0.143948 0.961325 0.234494 0.144452 0.415681 0.872394 0.257174 0.395523 0.881985 0.256248 0.76323 0.602401 0.233654 0.754931 0.612413 0.234584 0.962544 0.21529 0.164799 0.961708 0.218571 0.165359 0.950938 0.195094 0.240114 0.95094 0.195086 0.240114 0.806167 0.555571 0.203559 0.806167 0.555571 0.203559 0.538669 0.831466 0.136015 0.538665 0.831468 0.136014 0.189149 0.980786 0.0477606 0.189149 0.980786 0.0477606 0.0425715 0.998854 0.0218689 0.185242 0.980663 0.0631364 0.645181 0.746339 0.163461 0.504498 0.849845 0.152468 0.533825 0.83131 0.154771 0.447774 0.885541 0.123755 0.227206 0.971673 0.0650243 0.801142 0.557556 0.21749 0.802377 0.555508 0.218178 0.883223 0.411148 0.225555 0.949097 0.195089 0.247297 0.955743 0.166087 0.242837 0 -1 0 0.958691 -0.000470954 0.284449 -0.581273 0 0.813709 -0.557532 -0.00385679 0.830147 -0.136463 0.00511712 0.990632 -0.172276 -0.00129884 0.985048 0.318841 0.00119363 0.947807 0.325357 0.00231287 0.945588 0.707447 -0.00210516 0.706763 0.741875 0.00529929 0.670518 0.948109 -0.00477675 0.31791 0.95872 -7.61325e-05 0.284351 0.996365 -8.42991e-05 0.0851887 0.994132 -0.00222833 -0.108151 -0.481352 0 -0.876528 -0.481352 0 -0.876528 -0.0406041 0 -0.999175 -0.0406041 0 -0.999175 0.46187 0 -0.886948 0.46187 0 -0.886948 0.84194 0 -0.539571 0.84194 0 -0.539571 0.992164 0 -0.124939 0.992314 0.00478729 -0.123651 -0.552944 0 0.833218 -0.552944 0 0.833218 -0.126912 0 0.991914 -0.126912 0 0.991914 0.325343 0 0.945596 0.325343 0 0.945596 0.71035 0 0.703848 0.71035 0 0.703848 0.948557 0 0.316606 0.948557 0 0.316606 0.995694 0 0.0926998 0.995694 0 0.0927014 0.995694 0 0.0927013 0.995694 1.05564e-07 0.0927013 0.995694 0 0.0927014 0.995694 1.07792e-06 0.0927011 0.995694 -1.16419e-05 0.0927035 0.995694 1.37499e-05 0.0927009 0.995694 5.68038e-08 0.0927 0.989669 0 -0.143372 0.989669 0 -0.143372 0.815452 0 -0.578825 0.815452 0 -0.578825 0.461901 0 -0.886931 0.461901 0 -0.886931 0.00670397 0 -0.999978 0.00670397 0 -0.999978 -0.44993 0 -0.893064 -0.44993 0 -0.893064 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.446986 -0.252075 -0.85829 0.0979894 -0.985765 -0.136623 0.0737588 -0.958237 -0.276299 0.081601 -0.532601 -0.842423 0.091987 -0.636495 -0.765776 -0.109793 -0.6135 -0.782025 0.957712 -0.252066 -0.138742 0.957712 -0.252067 -0.138742 0.709625 -0.69704 -0.102802 0.709625 -0.697039 -0.102804 0.26298 -0.964049 -0.0380981 0.26298 -0.964049 -0.0380979 0.789121 -0.252064 -0.560135 0.789128 -0.252071 -0.560123 0.584713 -0.697038 -0.415029 0.584713 -0.697039 -0.415026 0.216688 -0.964049 -0.153804 0.216689 -0.964049 -0.153806 -0.44389 -0.163306 -0.881075 -0.443262 -0.17337 -0.879467 0.00654884 -0.21388 -0.976838 -0.0587929 -0.247677 -0.967057 0.44696 -0.252059 -0.858308 0.357719 -0.632579 -0.686936 0.269664 -0.686363 -0.675416 0.267894 -0.84721 -0.458768 0.20536 -0.914599 -0.348333 0.257705 -0.965926 0.0239929 0.257705 -0.965926 0.0239929 0.704062 -0.707107 0.0655497 0.704062 -0.707107 0.0655497 0.961766 -0.258819 0.0895426 0.961767 -0.258819 0.0895426 -0.545825 -0.159946 0.822491 -0.00542216 -0.625395 0.780289 -0.0263526 -0.524533 0.850982 -0.20399 -0.599224 0.774157 0.25113 -0.635774 0.729881 -0.0122271 -0.767151 0.64135 0.270872 -0.701919 0.65874 0.158146 -0.913412 0.375058 0.0221986 -0.957107 0.288882 0.0793064 -0.985602 0.149328 -0.545229 -0.167604 0.821361 -0.124149 -0.20751 0.970323 -0.199383 -0.247315 0.948199 0.314802 -0.252491 0.914958 0.314809 -0.252488 0.914956 0.687335 -0.252487 0.681044 0.687349 -0.252478 0.681033 0.50892 -0.697667 0.504244 0.508915 -0.697669 0.504245 0.188452 -0.964168 0.186723 0.188454 -0.964168 0.186723 0.917826 -0.25248 0.306349 0.917824 -0.252482 0.306352 0.679565 -0.697668 0.226826 0.679567 -0.697667 0.226824 0.251646 -0.964168 0.0839937 0.251646 -0.964168 0.0839937 0.0789558 0.985581 0.149654 0.0193315 0.956912 0.289733 -0.0303648 0.521155 0.852921 -0.00871885 0.621803 0.783125 0.250371 0.619114 0.74432 0.054223 0.739024 0.671494 0.16172 0.687146 0.708291 0.205551 0.842458 0.498009 0.157262 0.913259 0.375802 -0.550686 0.156279 0.819953 -0.550151 0.163312 0.818941 -0.133623 0.203031 0.970012 0.189804 0.979757 0.063643 0.277332 0.959914 0.0406432 0.187738 0.964146 0.187556 0.187738 0.964146 0.187556 0.506912 0.697551 0.506422 0.506914 0.697555 0.506415 0.428447 0.892073 0.143662 0.586916 0.785366 0.196798 0.715216 0.683917 0.143954 0.759589 0.598458 0.254701 0.854722 0.432793 0.286601 -0.213526 0.246797 0.94525 0.308499 0.252396 0.917129 0.308518 0.252406 0.917119 0.684549 0.252405 0.683875 0.684544 0.252401 0.683881 0.94409 0.246046 0.219445 0.930828 0.190111 0.312116 0.19425 0.980785 0.0180851 0.19425 0.980785 0.0180851 0.440385 0.896872 0.0410008 0.440383 0.896873 0.0410007 0.60614 0.793353 0.056433 0.60614 0.793353 0.056433 0.789937 0.608761 0.0735449 0.789937 0.608761 0.0735449 0.89301 0.44229 0.0831412 0.893012 0.442287 0.0831414 0.976562 0.195091 0.0909201 0.976562 0.195091 0.0909201 0.895117 0.435066 -0.0973781 0.612944 0.787308 -0.0666819 0.197782 0.98001 -0.0215166 0.208725 0.915196 -0.344748 0.083762 0.627973 -0.773714 -0.476635 0.139642 -0.867939 -0.476303 0.145919 -0.867089 -0.0398956 0.185986 -0.981742 -0.258767 0.332481 -0.906916 -0.114064 0.602274 -0.790099 0.358013 0.631822 -0.687479 0.0853468 0.779967 -0.619973 0.0993202 0.985845 -0.135074 0.0826139 0.95861 -0.272472 0.224975 0.963638 -0.144182 0.224976 0.963638 -0.144182 0.262233 0.964583 -0.0285282 0.431371 0.893895 0.121944 0.36537 0.69968 -0.613965 0.60546 0.69488 -0.388021 0.605455 0.694883 -0.388023 0.710085 0.699866 -0.0772488 0.788899 0.608726 0.0842108 0.0377141 0.254888 -0.966235 0.447125 0.250661 -0.858632 0.44714 0.250652 -0.858626 0.815063 0.250652 -0.522346 0.815062 0.250653 -0.522348 0.961547 0.253938 -0.104606 0.980479 0.194697 0.0274592 9.60459e-05 0.965926 0.258818 0.00249159 0.21512 0.976585 -3.06915e-05 0.297045 0.954863 0.000608725 0.0739151 0.997264 0.000369552 0.0869234 0.996215 -0.0575983 0.764063 0.642565 -0.0124681 0.787286 0.616462 0.0202716 0.824131 0.566037 -0.00113697 0.971799 0.235808 0.000955952 0.794522 0.607235 0.00113938 0.790988 0.611831 6.58503e-05 0.658397 0.752671 0.00112016 0.546361 0.837549 -0.000100038 0.498833 0.866698 0.000627421 0.331456 0.94347 -0.146338 0.964649 0.219176 -0.683731 0.464183 0.563069 -0.507379 0.406291 0.759931 -0.793072 0.122986 0.596583 -0.0513117 0.964649 0.258495 -0.127567 0.755466 0.642649 -0.159661 0.755497 0.635399 -0.219068 0.964649 0.1465 -0.952109 0.255135 0.168506 -0.94493 0.267658 0.188324 -0.783595 0.601324 0.15617 -0.90004 0.258762 0.350672 -0.825984 0.255985 0.502218 -0.798555 0.277746 0.53401 -0.71159 0.258597 0.653274 -0.587459 0.256729 0.767452 -0.0832211 0.273803 0.958179 -0.263936 0.70709 0.656019 -0.396429 0.700214 0.593755 -0.396432 0.700215 0.593751 -0.593465 0.700214 0.396862 -0.593462 0.700211 0.396872 -0.578856 0.754512 0.309255 -0.700164 0.700213 0.139539 -0.258457 0.964649 0.0515092 -0.965926 0.258819 0.000358428 -0.980644 0.195064 0.0169635 -0.793296 0.608713 -0.0122186 -0.83147 0.55557 0.000308543 -0.608761 0.793353 0.000225896 -0.555554 0.83144 -0.00816617 -0.258794 0.96585 0.0126092 -0.19509 0.980785 7.24118e-05 -0.165306 0.980048 -0.110366 -0.194959 0.980047 -0.0387045 -0.194959 0.980048 -0.0387046 -0.552248 0.826439 -0.109636 -0.55225 0.826438 -0.109636 -0.820387 0.548123 -0.162868 -0.820383 0.548129 -0.162869 -0.962707 0.191484 -0.191125 -0.96271 0.191474 -0.191122 -0.165309 0.980047 -0.110367 -0.468258 0.826438 -0.312627 -0.468253 0.826441 -0.312626 -0.695611 0.548124 -0.46442 -0.695613 0.548121 -0.46442 -0.816287 0.191482 -0.544986 -0.816284 0.191491 -0.544988 -0.205789 0.955022 -0.213502 -0.704722 0.086473 -0.704194 -0.702644 0.195077 -0.684278 -0.676713 0.287175 -0.677931 -0.637399 0.434789 -0.636145 -0.399225 0.831436 -0.386437 -0.378866 0.868408 -0.319887 -0.425412 0.801009 -0.4212 -0.585099 0.555565 -0.590768 -0.561063 0.664381 -0.493767 -0.590835 0.567057 -0.573899 -0.138 0.980785 -0.1379 -0.148478 0.988468 -0.0297546 -0.157784 0.982915 -0.0947732 -0.00250786 -0.626434 0.77947 0.0045505 -0.505547 0.862787 0.000367658 -0.133037 0.991111 0.0020181 -0.0746612 0.997207 -0.00191029 -0.379665 0.925122 0.0048286 -0.213911 0.976841 0.00183001 -0.329719 0.944077 0.0273055 -0.856657 0.515164 -0.0201273 -0.825415 0.564167 0.00022421 -0.831471 0.555568 0.000297788 -0.674762 0.738035 0.000821183 -0.66011 0.751168 -0.000744532 -0.83054 0.556959 0.00148068 -0.869243 0.494384 -0.0011457 -0.980785 0.195088 5.74135e-05 -0.987959 0.154713 -0.144978 -0.667606 0.730262 -0.116607 -0.714359 0.689996 -0.254051 -0.566996 0.783564 -0.127426 -0.319776 0.938885 -0.722518 -0.19492 0.663306 -0.646372 -0.194691 0.737766 -0.603504 -0.119122 0.788412 -0.91388 -0.195044 0.356064 -0.312627 -0.826442 0.468251 -0.446406 -0.594694 0.668626 -0.515053 -0.552851 0.655039 -0.534495 -0.364937 0.762323 -0.551775 -0.334469 0.763986 -0.0387153 -0.980048 0.194955 -0.109668 -0.826437 0.552245 -0.165227 -0.980048 0.110484 -0.46803 -0.826439 0.312964 -0.46803 -0.826439 0.312964 -0.69528 -0.548117 0.464922 -0.695257 -0.548134 0.464937 -0.8102 -0.223666 0.541802 -0.838408 -0.192885 0.509772 -0.194929 -0.980048 0.0388518 -0.552165 -0.826439 0.110054 -0.55217 -0.826437 0.110047 -0.820263 -0.548128 0.163477 -0.820266 -0.548125 0.163473 -0.958867 -0.209897 0.191096 -0.966332 -0.192233 0.171023 -0.109635 -0.826447 0.552237 -0.312608 -0.826447 0.468254 -0.110361 -0.980048 0.165309 -0.19509 -0.980785 7.24129e-05 -0.258804 -0.96585 -0.012417 -0.555548 -0.83144 0.00857851 -0.608761 -0.793353 0.000225893 -0.83147 -0.55557 0.000308537 -0.793287 -0.608713 0.0128075 -0.980656 -0.195063 -0.0162359 -0.965926 -0.258819 0.000358428 -0.816285 -0.191482 -0.544989 -0.814086 -0.255022 -0.521754 -0.948645 -0.254173 -0.18833 -0.948646 -0.254168 -0.188332 -0.783712 -0.601322 -0.155588 -0.692492 -0.702552 -0.163935 -0.604393 -0.787599 -0.119988 -0.512475 -0.787593 -0.34215 -0.605866 -0.702549 -0.373298 -0.664518 -0.601316 -0.44366 -0.748695 -0.435425 -0.49986 -0.219179 -0.964649 -0.146333 -0.21918 -0.964648 -0.146335 -0.258496 -0.964648 -0.0513182 -0.258496 -0.964648 -0.0513182 -0.0301136 -0.999093 -0.0300918 -0.215022 -0.964928 -0.150599 -0.217029 -0.971544 -0.0948711 -0.239293 -0.947155 -0.213626 -0.323173 -0.889747 -0.32235 -0.429769 -0.793344 -0.431166 -0.425412 -0.801009 -0.4212 -0.507011 -0.696765 -0.507404 -0.564529 -0.60875 -0.557432 -0.576472 -0.57601 -0.579563 -0.638126 -0.434349 -0.635717 -0.634872 -0.442302 -0.633488 -0.676713 -0.287175 -0.677931 -0.702644 -0.195077 -0.684278 -0.704722 -0.086473 -0.704194 -3.63771e-05 0.995185 -0.0980168 0.00281263 0.985571 -0.169242 -0.000851375 0.957003 -0.290078 0.00129828 0.871768 -0.489917 -0.00302419 0.832335 -0.554265 0.0020166 0.657093 -0.753807 -0.00360226 0.557843 -0.829938 0.00708507 0.187913 -0.98216 -0.00943947 0.366478 -0.930379 -0.000369236 0.103035 -0.994678 -4.27569e-05 -0.993342 -0.115207 0.000768961 -0.995177 -0.0980962 -0.000799934 -0.951761 -0.306839 -0.00011069 -0.956941 -0.290284 -0.000168896 -0.886784 -0.462183 -0.00388764 -0.832598 -0.553864 0.00214079 -0.741715 -0.670712 -0.00327204 -0.557616 -0.830093 0.00107527 -0.480742 -0.876862 -0.002045 -0.196706 -0.98046 -0.000366028 -0.166534 -0.986036 0.0181917 -0.980556 -0.195395 0.0325332 -0.96589 -0.2569 0.0411015 -0.896335 -0.441468 0.0566058 -0.791917 -0.607999 0.0770843 -0.707062 -0.702937 0.0909832 -0.191617 -0.977244 0.0984886 -0.258804 -0.960896 0.0832854 -0.439115 -0.894562 0.0736769 -0.606898 -0.791358 -0.0925784 -0.0511275 0.994392 -0.0967987 -0.258808 0.961066 -0.101746 -0.22951 0.967974 -0.0614168 -0.608719 0.791005 -0.0914675 -0.477302 0.873966 -0.0491079 -0.861592 0.50522 -0.0606778 -0.713676 0.697843 -0.0583311 -0.793355 0.605958 -0.0389135 -0.896869 0.440582 -0.0180852 -0.980785 0.194249 -0.0161987 -0.999644 -0.0212034 -0.0186093 -0.970213 0.241537 -0.80926 0 -0.587451 -0.80926 0 -0.587451 -0.893072 0 -0.449914 -0.893072 0 -0.449914 -0.0628418 -0.997571 -0.0300412 -0.0624662 -0.997595 -0.030052 -0.10494 -0.989988 -0.094401 -0.134132 -0.988832 -0.064965 -0.228917 -0.949719 -0.213615 -0.31486 -0.937251 -0.149747 -0.411254 -0.854293 -0.317889 -0.369496 -0.914037 -0.16736 -0.764569 -0.583842 -0.273062 -0.772723 -0.583506 -0.24984 -0.709442 -0.681233 -0.180593 -0.868281 -0.418376 -0.26655 -0.832375 -0.538299 -0.131857 -0.915555 -0.292629 -0.27591 -0.916843 -0.139085 -0.374238 -0.908513 -0.213088 -0.35944 -0.894695 -0.164205 -0.415401 -0.890766 -0.071805 -0.448753 -0.92928 -0.0537578 -0.365444 -0.889191 -0.117109 -0.442296 -0.365183 -0.917076 -0.160039 -0.531295 -0.743734 -0.405691 -0.524651 -0.824754 -0.211004 -0.646674 -0.603707 -0.466209 -0.609742 -0.719023 -0.333498 -0.697485 -0.490096 -0.5228 -0.699395 -0.564839 -0.437953 -0.755569 -0.351946 -0.552494 -0.746181 -0.432476 -0.50614 -0.777728 -0.231384 -0.584467 -0.783898 -0.285636 -0.551286 -0.803936 -0.0671947 -0.590907 -0.806206 -0.0867877 -0.585234 -0.430198 -0.229726 0.873015 -0.219745 -0.0415603 0.974672 -0.235136 -0.0197659 0.971761 -0.246979 -0.116942 0.961939 -0.260108 -0.0546688 0.964031 -0.387204 -0.208176 0.898184 -0.282759 -0.254708 0.924755 -0.267627 -0.237502 0.933793 -0.300031 -0.500809 0.811894 -0.257213 -0.363102 0.895544 -0.257718 -0.371633 0.891892 -0.156574 -0.675264 0.720765 -0.00470929 -0.515368 0.856956 -0.0302908 -0.590609 0.806389 -0.101227 -0.826633 0.553562 -0.0811168 -0.802562 0.591029 -0.0900665 -0.809126 0.580692 -0.0954511 -0.816797 0.568975 -0.0255111 -0.91786 0.396085 -0.0436973 -0.936327 0.348401 -0.00670667 -0.856605 0.51593 0.0265779 -0.805535 0.591952 -0.00637295 -0.998368 0.0567556 -0.00635986 -0.99837 0.05672 0.00253508 -0.992881 0.119085 -0.0146471 -0.99118 0.131714 -0.0150426 -0.991314 0.130651 -0.12256 -0.607939 0.784468 -0.0882215 -0.487428 0.868695 -0.0573761 -0.312358 0.94823 -0.0648166 -0.344133 0.936681 -0.0724739 -0.191671 0.97878 -0.069421 -0.162344 0.984289 -0.0705286 -0.0894626 0.99349 -0.0686747 -0.0544447 0.996152 -0.0703229 -0.029926 0.997075 -0.89529 0.383036 -0.227461 -0.926888 0.171761 -0.333732 -0.884658 0.327652 -0.331701 -0.910237 0.201055 -0.362002 -0.897815 0.22134 -0.380705 -0.889191 0.117109 -0.442296 -0.923657 0.0638108 -0.377869 -0.892276 0.042193 -0.449514 -0.768447 0.578914 -0.272667 -0.768604 0.593124 -0.239689 -0.631584 0.764852 -0.1269 -0.526349 0.818382 -0.230669 -0.153367 0.983616 -0.0947523 -0.133034 0.98909 -0.0632713 -0.351813 0.911716 -0.212134 -0.30892 0.940739 -0.139923 -0.451408 0.834945 -0.314796 -0.499271 0.762685 -0.411145 -0.0628418 0.997571 -0.0300412 -0.0624662 0.997595 -0.030052 -0.0626636 0.997573 -0.0303502 -0.524738 0.824455 -0.211953 -0.584444 0.742385 -0.327551 -0.671948 0.583222 -0.45644 -0.672701 0.580984 -0.458181 -0.734027 0.458611 -0.500879 -0.739567 0.436199 -0.512611 -0.764849 0.344282 -0.544497 -0.77244 0.290537 -0.564734 -0.794126 0.220777 -0.566235 -0.803768 0.0871414 -0.588526 -0.807474 0.0664017 -0.586154 -0.219935 0.00207354 0.975512 -0.0703377 -0.0217843 0.997285 -0.0823638 0.0115824 0.996535 -0.0737198 0 0.997279 -0.0737198 0 0.997279 -0.0823638 -0.0115824 0.996535 -0.0703377 0.0217843 0.997285 -0.219935 -0.00207354 0.975512 -0.00637295 0.998368 0.0567556 -0.00635986 0.99837 0.05672 0.00253508 0.992881 0.119085 -0.0146471 0.99118 0.131714 0.0280809 0.969043 0.245291 -0.0409522 0.933708 0.355686 0.0078222 0.877248 0.479973 -0.0510264 0.912075 0.406836 -0.0545816 0.915895 0.397689 -0.010385 0.744756 0.667257 -0.0934421 0.811557 0.576753 -0.0147945 0.619265 0.785043 -0.112372 0.799323 0.590301 -0.430206 0.229648 0.873032 -0.392116 0.210598 0.895485 -0.358344 0.220349 0.907214 -0.252976 0.377353 0.890847 -0.252141 0.367206 0.895313 -0.29493 0.477409 0.827706 -0.256002 0.244168 0.935332 -0.284135 0.269866 0.920022 -0.267619 0.111254 0.95708 -0.235847 0.0249664 0.971469 -0.2378 0.0399239 0.970493 -0.219933 0.00433177 0.975505 -0.122104 0.823282 0.554344 -0.0451752 0.446644 0.89357 -0.123556 0.611373 0.781637 -0.0449037 0.330146 0.942861 -0.0972016 0.481438 0.871074 -0.0374601 0.22692 0.973193 -0.0865602 0.333646 0.938716 -0.0620808 0.0935876 0.993674 -0.0740717 0.161232 0.984133 -0.0673555 0.0304124 0.997265 -0.0702505 0.0543176 0.996049 -0.407158 0.20211 0.890716 -0.589629 0.192938 0.784291 -0.738381 0.324402 0.591233 -0.805061 0.25969 0.533327 -0.903372 0.335222 0.267478 -0.928725 0.29355 0.226492 -0.948303 0.303573 -0.0925462 -0.92089 0.389363 -0.0189302 -0.393696 0.227008 0.89077 -0.932515 0.312661 -0.180718 -0.977146 0.194226 -0.0863867 -0.923598 0.294609 0.2453 -0.930831 0.243541 0.272474 -0.752708 0.195167 0.628761 -0.75095 0.287661 0.594412 -0.529142 0.0884046 0.843915 -0.471358 0.285375 0.834496 -0.95675 0.193235 -0.217463 -0.977059 0.093546 -0.191325 -0.961609 0.154331 0.226914 -0.964898 0.106572 0.240029 -0.772966 0.0896953 0.628075 -0.773209 0.0926552 0.627346 -0.427422 0.0142336 0.90394 -0.437355 0.0578275 0.897428 -0.97033 0.0704958 -0.231277 -0.97471 0.0300702 -0.221443 -0.973859 0.0559782 0.22015 -0.973635 0.03698 0.225093 -0.778035 0.0320904 0.627401 -0.778162 0.0329038 0.627201 -0.422187 0.00519178 0.906494 -0.426901 0.0203069 0.90407 -0.972751 0 -0.231854 -0.972751 0 -0.231854 -0.975388 0 0.220495 -0.975388 0 0.220495 -0.778436 0 0.627724 -0.778436 0 0.627724 -0.422192 0 0.906506 -0.422192 0 0.906506 -0.972635 -0.0716981 -0.220997 -0.972331 -0.0293592 -0.231754 -0.972594 -0.0562429 0.225606 -0.97472 -0.0369928 0.220344 -0.778217 -0.0320958 0.627174 -0.778015 -0.0328909 0.627385 -0.428134 -0.00561295 0.903698 -0.422109 -0.0198451 0.906328 -0.961255 -0.202257 -0.1873 -0.971323 -0.088422 -0.220709 -0.957564 -0.156128 0.242269 -0.968127 -0.106787 0.226554 -0.773663 -0.0897618 0.627207 -0.772643 -0.0925091 0.628065 -0.444034 -0.017657 0.895836 -0.423727 -0.0539624 0.904181 -0.459314 -0.317963 0.829416 -0.934737 -0.342509 -0.0946252 -0.963246 -0.262545 0.0568046 -0.897868 -0.350561 0.266346 -0.888132 -0.269481 0.372293 -0.741006 -0.316938 0.591997 -0.720999 -0.249955 0.646284 -0.487274 -0.238097 0.840163 -0.512707 -0.343976 0.786646 -0.407152 -0.202134 0.890713 -0.480392 -0.0507597 0.875584 -0.732648 -0.268335 0.625479 -0.775564 -0.20122 0.598341 -0.937991 -0.245466 0.244786 -0.914781 -0.300794 0.269627 -0.969225 -0.157446 -0.189245 -0.928549 -0.358741 -0.0953984 -0.999987 0 -0.00518451 -0.999987 0 -0.00518451 -0.979713 0 0.200404 -0.979713 0 0.200404 -0.93293 0 0.360057 -0.93293 0 0.360057 -0.839037 0 0.544074 -0.839037 0 0.544074 -0.737226 0 0.675646 -0.737226 0 0.675646 -0.582661 0 0.812715 -0.582661 0 0.812715 -0.439858 0 0.898067 -0.439858 0 0.898067 -0.245937 0 0.969286 -0.245937 0 0.969286 -0.016451 0 -0.999865 -0.016451 0 -0.999865 -0.211894 0 -0.977293 -0.211894 0 -0.977293 -0.400115 0 -0.916465 -0.400115 0 -0.916465 -0.571748 0 -0.82043 -0.571748 0 -0.82043 -0.722101 0 -0.691788 -0.722101 0 -0.691788 -0.843506 0 -0.53712 -0.843506 0 -0.53712 -0.932771 0 -0.36047 -0.932771 0 -0.36047 -0.614088 0.789231 -0.0031837 -0.790521 0.550222 0.268947 -0.981285 0.192493 -0.00508755 -0.571624 0.193713 0.797321 -0.145108 0.931751 0.332841 -0.200063 0.831742 0.51786 -0.120722 0.930384 0.346138 -0.292775 0.194018 0.93629 -0.213757 0.494436 0.84252 -0.214806 0.486971 0.846592 -0.910127 -0.219746 0.351256 -0.929007 0.192488 0.316062 -0.823018 0.194474 0.533686 -0.960918 0.194937 0.196559 -0.981285 0.192492 -0.00508744 -0.835008 0.550221 -0.00432907 -0.898752 0.438127 -0.0170373 -0.797413 0.60342 -0.00413413 -0.202328 0.831289 0.517708 -0.305819 0.827867 0.470224 -0.126729 0.97261 0.194858 -0.723161 0.1944 0.662757 -0.768005 -0.230979 0.597341 -0.659122 0.550222 0.512654 -0.790521 0.550221 0.268947 -0.531036 0.827865 0.180666 -0.561365 0.827539 -0.00701022 -0.26318 0.964735 0.00472792 -0.156072 0.980258 0.12139 -0.11232 0.980436 0.161644 -0.0482757 0.994904 0.0885209 -0.187186 0.980258 0.0636833 -0.156072 0.980258 0.12139 -0.442766 0.827866 0.344376 -0.30582 0.827866 0.470225 -0.455257 0.550221 0.699998 -0.27655 0.554594 0.784822 -0.228055 0.650041 0.724871 -0.431423 0.194899 0.880845 -0.539356 -0.146094 0.829308 -0.455257 0.550221 0.699999 -0.659123 0.550221 0.512654 -0.442765 0.827868 0.344375 -0.531033 0.827867 0.180665 -0.187185 0.980258 0.063683 -0.197718 0.980258 -0.00102509 -0.966367 0.195092 -0.167553 -0.25501 0.965926 -0.0442385 -0.25501 0.965926 -0.0442432 -0.599803 0.793352 -0.104064 -0.599804 0.793353 -0.104045 -0.78168 0.608761 -0.135594 -0.781682 0.608764 -0.135569 -0.883677 0.442297 -0.153258 -0.883676 0.442285 -0.153301 -0.966352 0.195089 -0.167644 -0.966347 0.195086 -0.167676 -0.014882 0.920177 -0.391219 -0.0141539 0.478668 -0.877882 -0.0275339 0.638239 -0.769346 -0.0210313 0.808805 -0.587701 -0.026785 0.18267 -0.982809 -0.028361 0.192022 -0.980981 -0.0151107 0.395368 -0.918399 -0.83938 0.43529 -0.325521 -0.915105 0.191412 -0.354887 -0.916563 0.185606 -0.354207 -0.827298 0.195089 -0.5268 -0.707141 0.191413 -0.680671 -0.710336 0.179779 -0.680517 -0.560763 0.195083 -0.804666 -0.389527 0.191406 -0.900906 -0.394016 0.173947 -0.902493 -0.207823 0.19509 -0.958514 -0.0346025 0.32506 -0.94506 -0.0305627 0.549775 -0.834754 -0.331974 0.547983 -0.767795 -0.331971 0.547987 -0.767792 -0.602657 0.547987 -0.580099 -0.602658 0.547987 -0.580099 -0.783341 0.547202 -0.294867 -0.745049 0.60118 -0.288938 0.0430329 0.950491 -0.307759 -0.0152692 0.827121 -0.561816 -0.223501 0.826342 -0.51692 -0.223502 0.826341 -0.516921 -0.405742 0.826342 -0.390555 -0.405743 0.826341 -0.390555 -0.525068 0.826341 -0.203627 -0.577407 0.788553 -0.211625 -0.000598446 0.985352 -0.170533 -0.0068731 0.980201 -0.197886 -0.0789096 0.980033 -0.182504 -0.0789098 0.980033 -0.182504 -0.143252 0.980033 -0.137889 -0.143252 0.980033 -0.137889 -0.176896 0.980521 -0.0853636 -0.245794 0.964624 -0.0953215 -0.431423 -0.194899 0.880845 -0.197719 -0.980258 -0.0010251 -0.187185 -0.980258 0.063683 -0.156072 -0.980258 0.12139 -0.192905 -0.831069 0.521644 -0.146733 -0.932143 0.331027 -0.0487356 -0.996346 0.0701371 -0.106257 -0.980189 0.167149 -0.214806 -0.486971 0.846592 -0.213897 -0.493449 0.843064 -0.287763 -0.193908 0.937866 -0.228148 -0.651358 0.723658 -0.455258 -0.55022 0.699999 -0.305819 -0.827867 0.470224 -0.30582 -0.827866 0.470225 -0.194461 -0.934228 0.299002 -0.110106 -0.978861 0.172361 -0.571624 -0.193714 0.797321 -0.539356 0.146094 0.829308 -0.455257 -0.550221 0.699998 -0.280784 -0.554737 0.783216 -0.199284 -0.829438 0.521842 -0.823018 -0.194475 0.533686 -0.156072 -0.980258 0.12139 -0.442765 -0.827868 0.344375 -0.442767 -0.827866 0.344376 -0.659122 -0.550222 0.512654 -0.659123 -0.55022 0.512654 -0.768005 0.230979 0.597341 -0.723161 -0.1944 0.662757 -0.960918 -0.194937 0.196559 -0.187186 -0.980258 0.0636832 -0.531036 -0.827865 0.180666 -0.531033 -0.827867 0.180665 -0.790521 -0.550222 0.268947 -0.790522 -0.550221 0.268947 -0.939682 0.12163 0.319694 -0.915281 -0.193595 0.353245 -0.197718 -0.980258 -0.00102502 -0.560918 -0.827866 -0.00290794 -0.560919 -0.827866 -0.00290805 -0.835008 -0.550221 -0.00432904 -0.835008 -0.550221 -0.00432907 -0.981285 -0.192493 -0.00508744 -0.981285 -0.192492 -0.00508755 -0.966367 -0.195092 -0.167553 -0.966346 -0.195089 -0.167676 -0.966352 -0.195087 -0.167644 -0.819232 -0.555572 -0.142121 -0.819235 -0.555571 -0.142108 -0.547397 -0.831469 -0.0949539 -0.547395 -0.831469 -0.0949617 -0.19222 -0.980785 -0.0333461 -0.19222 -0.980785 -0.0333458 -0.0789097 -0.980033 -0.182504 -0.143252 -0.980033 -0.137889 -0.185381 -0.980033 -0.0718924 -0.0151107 -0.395368 -0.918399 -0.0133637 -0.826955 -0.562109 0.0615532 -0.895782 -0.440211 -0.0149287 -0.91464 -0.403994 -0.0143959 -0.958522 -0.284655 0.000707574 -0.97991 -0.199441 -0.0020109 -0.998321 -0.0578963 -0.0336801 -0.390838 -0.919843 -0.0271402 -0.549495 -0.835056 -0.0277216 -0.552221 -0.833237 -0.023489 -0.796332 -0.604403 -0.827298 -0.195089 -0.5268 -0.185381 -0.980033 -0.0718927 -0.525068 -0.826341 -0.203627 -0.525068 -0.826342 -0.203627 -0.779894 -0.547986 -0.302451 -0.779894 -0.547985 -0.302451 -0.91613 -0.185684 -0.355285 -0.915516 -0.191456 -0.353802 -0.560763 -0.195084 -0.804666 -0.143252 -0.980033 -0.137889 -0.405742 -0.826342 -0.390554 -0.405743 -0.826341 -0.390555 -0.602658 -0.547987 -0.580099 -0.602658 -0.547986 -0.580099 -0.708694 -0.180004 -0.682166 -0.708737 -0.1915 -0.678985 -0.207823 -0.19509 -0.958514 -0.035908 -0.192277 -0.980683 -0.0256989 -0.235239 -0.971598 -0.0789097 -0.980033 -0.182504 -0.223502 -0.826342 -0.51692 -0.223502 -0.826341 -0.516921 -0.331973 -0.547983 -0.767795 -0.331972 -0.547987 -0.767792 -0.390784 -0.174388 -0.903812 -0.392707 -0.191537 -0.899497 -0.00122142 0.999999 0.000411621 -0.98269 0.167868 -0.0783613 -0.823219 0.563916 -0.0656431 -0.905905 0.417275 -0.0722365 -0.362797 0.931419 -0.028927 -0.513523 0.857098 -0.0409449 -0.11011 0.993881 -0.00877845 -0.784904 0.570418 0.241967 -0.653664 0.726195 0.212988 -0.477543 0.864314 0.157839 -0.919562 0.260481 0.294204 -0.963434 0.258817 -0.0693482 -0.964738 0.258747 -0.0482748 -0.96474 0.258738 -0.0482753 -0.96591 0.258786 -0.00696318 -0.900725 0.434374 0.00353917 -0.965694 0.258801 0.0213759 -0.964329 0.258751 0.0558324 -0.964332 0.258742 0.0558321 -0.961313 0.258791 0.0943646 -0.889391 0.444866 0.105248 -0.95728 0.258763 0.129059 -0.950919 0.258767 0.169687 -0.95092 0.258761 0.169687 -0.938637 0.258624 0.228197 -0.938644 0.2586 0.228197 -0.918906 0.258701 0.2978 -0.952975 0.0741632 0.293834 -0.847619 0.453065 0.276178 -0.672567 0.706915 0.218917 -0.687408 0.706782 0.167119 -0.687369 0.706823 0.167106 -0.696193 0.707023 0.124232 -0.696187 0.707029 0.12423 -0.702459 0.706853 0.0831271 -0.70242 0.706892 0.0831202 -0.706036 0.706996 0.0408775 -0.706023 0.707008 0.0408759 -0.707262 0.706946 0.00277901 -0.70724 0.706968 0.00277785 -0.706342 0.706988 -0.0353451 -0.706325 0.707004 -0.035345 -0.705372 0.707104 -0.0495438 -0.662996 0.746863 -0.0513016 -0.258588 0.965905 -0.0126191 -0.258565 0.965907 -0.0129388 -0.258577 0.965904 -0.0129397 -0.258912 0.9659 0.00101694 -0.258928 0.965896 0.00101645 -0.258454 0.965908 0.0149634 -0.258462 0.965906 0.0149635 -0.257171 0.965887 0.0304321 -0.257198 0.965879 0.0304341 -0.254846 0.965912 0.0454756 -0.254851 0.96591 0.0454761 -0.251682 0.965874 0.0611863 -0.251712 0.965866 0.061192 -0.245992 0.965882 0.0809932 -0.222984 0.971928 0.0750562 -0.576906 -0.794655 0.188953 -0.970762 -0.227596 -0.0762953 -0.50288 -0.863465 -0.0392392 -0.00173393 -0.999999 -0.000142322 -0.23229 -0.972462 -0.0189259 -0.682492 -0.729553 -0.0442498 -0.996427 -0.0528592 -0.0658663 -0.834402 -0.479438 0.271867 -0.918914 -0.258572 0.297888 -0.162646 -0.985225 0.0536371 -0.97767 -0.195086 -0.0781162 -0.979558 -0.195035 -0.0492722 -0.979559 -0.195028 -0.0492721 -0.980764 -0.195064 -0.00716739 -0.901327 -0.433126 0.00344982 -0.980548 -0.195076 0.0217047 -0.979156 -0.195037 0.0566907 -0.979157 -0.195031 0.0566909 -0.194177 -0.980773 -0.0194962 -0.194899 -0.980774 -0.00980402 -0.194908 -0.980773 -0.00980425 -0.195163 -0.980771 0.00074622 -0.195176 -0.980768 0.000746586 -0.194817 -0.980775 0.0112788 -0.194823 -0.980774 0.0112794 -0.193852 -0.980763 0.0229384 -0.193872 -0.980759 0.0229415 -0.192095 -0.980777 0.034286 -0.1921 -0.980776 0.0342871 -0.189712 -0.980755 0.0461377 -0.189734 -0.980751 0.046144 -0.18504 -0.98075 0.0623697 0.0136717 -0.999804 -0.0143392 -0.42307 -0.895112 0.140663 -0.528622 -0.831337 0.171577 -0.540179 -0.831233 0.131374 -0.540131 -0.831265 0.131364 -0.547015 -0.83141 0.0976345 -0.547007 -0.831415 0.0976337 -0.551992 -0.831287 0.0653189 -0.551953 -0.831313 0.0653157 -0.554763 -0.831389 0.0321183 -0.554748 -0.831398 0.0321181 -0.555743 -0.831352 0.00212583 -0.555718 -0.831368 0.00212647 -0.554999 -0.831382 -0.0279176 -0.55498 -0.831395 -0.0279161 -0.553024 -0.8314 -0.0542118 -0.708251 -0.666624 0.232363 -0.791422 -0.555389 0.255331 -0.80815 -0.555213 0.196549 -0.808122 -0.555256 0.196544 -0.818597 -0.555474 0.146109 -0.818594 -0.555478 0.146109 -0.825895 -0.555289 0.0977328 -0.825863 -0.555337 0.0977308 -0.83016 -0.555449 0.0480636 -0.830151 -0.555463 0.0480637 -0.831582 -0.555393 0.00318207 -0.831564 -0.55542 0.0031828 -0.830507 -0.55544 -0.0417754 -0.830494 -0.555459 -0.0417742 -0.829126 -0.555571 -0.0623702 -0.878171 -0.472978 -0.0714664 -0.976098 -0.195069 0.0958159 -0.888966 -0.445726 0.105198 -0.972 -0.195048 0.131043 -0.965534 -0.19505 0.172336 -0.965534 -0.19505 0.172336 -0.953032 -0.194946 0.231788 -0.953037 -0.194922 0.23179 -0.933764 -0.195016 0.30009 -0.948803 -0.0720434 0.307543 -0.108135 0.993883 -0.0224233 -0.47472 0.875538 -0.0898636 -0.957989 0.223317 -0.179963 -0.52774 0.84351 -0.0999025 -0.689373 0.71268 -0.129815 -0.694933 0.707093 -0.13072 -0.826115 0.541317 -0.156552 -0.890759 0.42195 -0.168842 -0.00169264 0.999999 -0.000319906 -0.808605 0.563953 -0.167675 -0.691819 0.707098 -0.146287 -0.650932 0.74692 -0.135637 -0.504374 0.857128 -0.104589 -0.945806 0.258818 -0.196125 -0.964292 0.16789 -0.204829 -0.889838 0.417302 -0.18452 -0.253746 0.965926 -0.0509991 -0.253428 0.965926 -0.0525517 -0.355152 0.931428 -0.079426 -0.947605 0.25882 -0.187237 -0.9492 0.258811 -0.178988 -0.981218 0.0509843 -0.186041 -0.23534 0.970896 -0.0444448 -0.254407 0.965923 -0.047645 -0.253746 0.965926 -0.0509991 -0.693245 0.707105 -0.139332 -0.693247 0.707104 -0.139332 -0.947543 0.2567 -0.190442 -0.946967 0.258818 -0.19044 -0.191266 -0.980785 -0.0384416 -0.545889 -0.831461 -0.103329 -0.627331 -0.769911 -0.117013 -0.506837 -0.85673 -0.0955467 -0.191534 -0.980785 -0.0370854 -0.23534 -0.970896 -0.0444448 -0.00169264 -0.999999 -0.000319906 -0.962182 -0.195091 -0.190118 -0.963619 -0.195086 -0.182704 -0.981673 -0.0512081 -0.183563 -0.957854 -0.222812 -0.181303 -0.816854 -0.555561 -0.155248 -0.869627 -0.465947 -0.163222 -0.749209 -0.646944 -0.141949 -0.814397 -0.555569 -0.167632 -0.965054 -0.167889 -0.201209 -0.960355 -0.19509 -0.199142 -0.295919 -0.95324 -0.0613628 -0.448421 -0.888973 -0.0929861 -0.543624 -0.831465 -0.114625 -0.651319 -0.746915 -0.133794 -0.855949 -0.484727 -0.179978 -0.108135 -0.993883 -0.0224233 -0.190652 -0.980782 -0.0414461 -0.191267 -0.980785 -0.0384418 -0.544679 -0.831469 -0.109472 -0.544681 -0.831468 -0.109473 -0.815171 -0.555567 -0.163837 -0.815169 -0.555569 -0.163837 -0.961557 -0.195089 -0.193258 -0.962115 -0.192088 -0.193486 -0.0175566 0.000660409 0.999846 -0.097565 0.00706832 0.995204 -0.211514 -0.0118436 0.977303 -0.634431 0.0238282 0.772612 -0.555912 -0.00251669 0.831237 -0.471239 0.0177965 0.881826 -0.290358 0.0109353 0.956856 -0.0977027 -0.0036752 0.995209 -0.017553 -0.0201606 0.999643 -0.291625 0.0253356 0.956197 -0.211522 -0.0079457 0.977341 -0.471239 -0.0177965 0.881826 -0.555912 0.00251669 0.831237 -0.634431 -0.0238282 0.772612 -0.68766 -0.143249 0.711761 -0.563686 -0.523082 0.639252 -0.349616 -0.815923 0.460477 -0.0816617 -0.975454 0.2045 -0.688861 -0.118116 0.715205 -0.657419 -0.108225 0.745713 -0.664739 -0.0807611 0.742697 -0.639848 -0.0599094 0.766163 -0.647809 -0.0448242 0.760483 -0.633682 -0.022192 0.773276 -0.639449 -0.0157896 0.768672 -0.631249 0.00942102 0.775523 -0.634877 0.0112006 0.772532 -0.585482 -0.451666 0.673208 -0.50011 -0.424302 0.754889 -0.542868 -0.334643 0.770265 -0.469632 -0.2733 0.839496 -0.507414 -0.219428 0.833296 -0.4621 -0.146729 0.874605 -0.486768 -0.123572 0.864747 -0.458712 -0.0376508 0.887787 -0.472629 -0.0314967 0.880699 -0.408295 -0.72814 0.550551 -0.284016 -0.686774 0.669086 -0.376888 -0.55928 0.73835 -0.264173 -0.464985 0.844986 -0.338875 -0.3799 0.860721 -0.266233 -0.263464 0.927204 -0.312837 -0.224957 0.922782 -0.266591 -0.0832041 0.960212 -0.292697 -0.0724172 0.953459 -0.17897 -0.91432 0.363302 -0.0369989 -0.865253 0.499968 -0.180099 -0.737579 0.650801 -0.0401981 -0.620723 0.782999 -0.151398 -0.517657 0.842086 -0.0568098 -0.366508 0.928679 -0.125651 -0.315186 0.940675 -0.0640317 -0.125151 0.990069 -0.101669 -0.110212 0.988694 -0.634728 -0.0157447 0.772575 -0.472307 0.015636 0.881296 -0.292183 0.0463428 0.955239 -0.10059 0.0753265 0.992072 -0.632687 -0.0158821 0.774244 -0.63794 0.0078094 0.770046 -0.631698 0.0103513 0.775145 -0.645189 0.0365642 0.763148 -0.636054 0.0452677 0.770316 -0.659035 0.0694088 0.748903 -0.648002 0.0889247 0.75643 -0.686102 0.107797 0.719474 -0.676069 0.143175 0.722794 -0.464839 0.0151535 0.885265 -0.482801 0.0969792 0.870344 -0.457752 0.10567 0.882778 -0.502656 0.193063 0.842653 -0.461951 0.224233 0.858091 -0.533679 0.299631 0.790828 -0.48082 0.36494 0.797265 -0.58884 0.418242 0.691621 -0.529719 0.521122 0.6692 -0.278386 0.0453616 0.959397 -0.308313 0.1817 0.933771 -0.260896 0.195642 0.945335 -0.334603 0.339026 0.879262 -0.256951 0.387228 0.885455 -0.371201 0.507029 0.777902 -0.264967 0.601527 0.75363 -0.429406 0.681715 0.592348 -0.298852 0.809405 0.505521 -0.080938 0.0736609 0.993994 -0.121906 0.25842 0.95831 -0.0521499 0.275398 0.959915 -0.150587 0.466573 0.871569 -0.0357236 0.523192 0.851466 -0.183591 0.677484 0.712257 -0.0239777 0.774795 0.631758 -0.226117 0.87199 0.434172 -0.0228823 0.965031 0.261134 -0.175725 -0.979597 0.0975225 -0.174357 -0.979927 0.0966615 -0.498668 -0.821391 0.276853 -0.495242 -0.824201 0.274642 -0.740954 -0.53077 0.411425 -0.737353 -0.537685 0.408908 -0.863712 -0.15466 0.479668 -0.862393 -0.166175 0.478189 -0.166907 -0.979085 0.116337 -0.165084 -0.979555 0.114975 -0.472891 -0.817106 0.329715 -0.468337 -0.821104 0.326264 -0.700497 -0.520288 0.488472 -0.695617 -0.530364 0.484593 -0.812362 -0.138165 0.56655 -0.810697 -0.154489 0.564715 -0.157292 -0.979076 0.129108 -0.157075 -0.979138 0.128905 -0.445827 -0.816887 0.365971 -0.445242 -0.817458 0.365408 -0.660439 -0.519511 0.542151 -0.659907 -0.520772 0.54159 -0.765728 -0.136055 0.62861 -0.765578 -0.138343 0.628292 -0.148371 -0.979275 0.137868 -0.149139 -0.979052 0.138617 -0.420744 -0.818624 0.390934 -0.422669 -0.816723 0.392829 -0.624019 -0.523862 0.5798 -0.625983 -0.519285 0.581797 -0.725039 -0.143234 0.673648 -0.725673 -0.13597 0.674471 -0.150132 0.97904 0.137627 -0.149314 0.979266 0.136908 -0.425345 0.816737 0.3899 -0.423385 0.818567 0.388193 -0.62995 0.519338 0.577452 -0.627875 0.52378 0.575697 -0.730277 0.136325 0.669411 -0.729463 0.143204 0.668862 -0.161168 0.979335 0.122176 -0.162267 0.979058 0.122945 -0.457027 0.819174 0.346525 -0.459751 0.816851 0.348401 -0.678033 0.525294 0.514138 -0.681013 0.519502 0.516081 -0.788244 0.146132 0.59776 -0.789571 0.136391 0.59831 -0.17172 0.979862 0.101892 -0.174163 0.97929 0.103239 -0.487512 0.823766 0.289381 -0.493704 0.818874 0.292749 -0.725356 0.537052 0.43062 -0.732139 0.524879 0.434137 -0.847939 0.16591 0.503461 -0.850956 0.145961 0.504548 -0.911239 -0.165876 0.377 -0.966865 -0.180482 -0.180553 -0.82431 -0.54637 -0.148299 -0.552207 -0.827767 -0.0993454 -0.1942 -0.98034 -0.0349379 -0.96574 -0.180484 -0.186474 -0.938626 -0.28978 -0.187108 -0.819368 -0.548557 -0.166495 -0.953935 -0.224713 -0.198779 -0.962121 -0.180422 -0.204382 -0.961513 -0.180421 -0.207223 -0.961461 -0.180709 -0.207213 -0.963982 -0.180698 -0.195158 -0.964491 -0.177871 -0.195241 -0.970501 -0.177872 -0.162753 -0.971518 -0.172129 -0.16286 -0.976761 -0.172129 -0.127711 -0.831213 0.546833 -0.100291 -0.981241 -0.164868 -0.0999286 -0.983801 -0.164847 -0.0704295 -0.983926 -0.164104 -0.070428 -0.986178 -0.164077 -0.0230418 -0.985436 -0.168473 -0.0230778 -0.984646 -0.168412 0.0459228 -0.98279 -0.17898 0.0457261 -0.976857 -0.179085 0.116955 -0.97574 -0.185237 0.116699 -0.965866 -0.185205 0.181112 -0.965093 -0.18941 0.180888 -0.949424 -0.189445 0.250409 -0.883457 0.397921 0.247312 -0.935841 -0.186825 0.298829 -0.907974 -0.186445 0.375262 -0.968883 -0.18024 -0.169643 -0.823046 -0.548335 -0.148069 -0.824114 -0.546677 -0.148261 -0.820574 -0.546678 -0.16674 -0.82059 -0.546652 -0.166744 -0.818556 -0.546667 -0.176413 -0.818437 -0.546853 -0.176389 -0.820597 -0.546829 -0.166129 -0.821715 -0.545083 -0.16634 -0.826837 -0.545082 -0.138657 -0.829089 -0.541566 -0.138989 -0.834641 -0.541486 -0.100834 -0.837478 -0.537031 -0.101134 -0.84135 -0.537124 -0.0602309 -0.841643 -0.536663 -0.0602443 -0.843606 -0.536601 -0.0197137 -0.841907 -0.539263 -0.0197119 -0.841315 -0.539119 0.0392321 -0.837193 -0.545518 0.0389613 -0.832008 -0.545749 0.0996057 -0.829609 -0.549455 0.0992321 -0.821268 -0.549367 0.153994 -0.81962 -0.551926 0.153628 -0.803144 -0.551772 0.224738 -0.804228 -0.550052 0.225079 -0.771998 -0.549729 0.319088 -0.77951 -0.537006 0.322472 -0.552022 -0.827894 -0.0993107 -0.549649 -0.827896 -0.111689 -0.549665 -0.827885 -0.111692 -0.548294 -0.827895 -0.118167 -0.548189 -0.827968 -0.118145 -0.549649 -0.827952 -0.111275 -0.550676 -0.827242 -0.111474 -0.554109 -0.827242 -0.092921 -0.556163 -0.825826 -0.0932386 -0.559933 -0.825772 -0.0676456 -0.562543 -0.823972 -0.0679354 -0.565092 -0.824035 -0.040454 -0.56537 -0.823844 -0.0404692 -0.566723 -0.823802 -0.0132432 -0.565166 -0.824871 -0.0132295 -0.564853 -0.824771 0.0263407 -0.561112 -0.827328 0.0261192 -0.557505 -0.827486 0.0667435 -0.555329 -0.828974 0.0664309 -0.54979 -0.828917 0.10309 -0.548327 -0.829924 0.102783 -0.537392 -0.829817 0.150376 -0.538381 -0.829122 0.150675 -0.516964 -0.828909 0.21368 -0.523932 -0.823726 0.216727 -0.194071 -0.980366 -0.0349138 -0.193236 -0.980366 -0.0392656 -0.193242 -0.980365 -0.0392667 -0.192758 -0.980367 -0.0415426 -0.192716 -0.980375 -0.0415338 -0.193232 -0.980373 -0.0391203 -0.19364 -0.980289 -0.0391999 -0.194847 -0.980289 -0.0326773 -0.195662 -0.980123 -0.032805 -0.196999 -0.980115 -0.0238019 -0.198035 -0.979903 -0.0239185 -0.198919 -0.979913 -0.0142406 -0.199029 -0.97989 -0.0142469 -0.199515 -0.979884 -0.00465985 -0.198902 -0.980008 -0.00465306 -0.198812 -0.979994 0.00927637 -0.197338 -0.980292 0.00919188 -0.196039 -0.980315 0.0234749 -0.195178 -0.98049 0.0233545 -0.193244 -0.980481 0.0362386 -0.192666 -0.980599 0.036119 -0.188844 -0.980584 0.0528416 -0.189255 -0.980498 0.0529647 -0.181775 -0.980467 0.0751205 -0.184545 -0.979856 0.0763208 -0.968883 0.180239 -0.169643 -0.194114 0.980338 -0.0354505 -0.551956 0.827758 -0.100802 -0.966357 0.18061 -0.183125 -0.723016 0.678095 -0.132041 -0.823923 0.54636 -0.150471 -0.910509 0.165898 0.378749 -0.907034 0.186178 0.377661 -0.93529 0.186524 0.300735 -0.858672 -0.451513 0.242527 -0.949323 0.189467 0.250776 -0.965584 0.189402 0.178255 -0.966489 0.184645 0.178339 -0.976948 0.184679 0.107084 -0.978297 0.17738 0.107104 -0.982906 0.177402 0.0492444 -0.984111 0.170605 0.0491857 -0.985304 0.170638 0.00763015 -0.994658 -0.103217 0.00108466 -0.965054 0.180586 -0.189896 -0.822642 -0.546847 -0.15562 -0.970406 0.174441 -0.166979 -0.974351 0.174424 -0.142182 -0.975286 0.168946 -0.142387 -0.979703 0.168943 -0.107888 -0.980391 0.164823 -0.108016 -0.984709 0.164766 -0.0565647 -0.984543 0.165766 -0.0565465 -0.986046 0.165874 -0.0141099 -0.9622 0.180597 -0.203851 -0.976989 0.0353731 -0.210337 -0.728086 0.668077 -0.153504 -0.841101 0.511692 -0.17527 -0.964337 0.180614 -0.193476 -0.823676 0.546744 -0.150428 -0.819287 0.546747 -0.172732 -0.819271 0.546772 -0.172728 -0.822724 0.546704 -0.155694 -0.825147 0.5429 -0.156181 -0.830948 0.542974 -0.121261 -0.83307 0.539632 -0.12162 -0.836846 0.539625 -0.0921604 -0.838437 0.537113 -0.0923726 -0.842211 0.536973 -0.0483779 -0.841851 0.537541 -0.0483515 -0.843128 0.537712 0.000964506 -0.841265 0.540623 0.00102161 -0.840233 0.540596 0.0420047 -0.837561 0.54473 0.0419555 -0.833658 0.544685 0.0912801 -0.830788 0.54909 0.0910556 -0.82194 0.549008 0.151674 -0.820074 0.55187 0.151388 -0.802637 0.551735 0.226634 -0.803869 0.549811 0.226942 -0.771275 0.549566 0.321112 -0.77884 0.53706 0.323998 -0.551721 0.82792 -0.100761 -0.548779 0.827922 -0.1157 -0.548758 0.827936 -0.115696 -0.551108 0.82789 -0.104294 -0.55334 0.826345 -0.104734 -0.557187 0.826396 -0.0813141 -0.559132 0.825051 -0.0816276 -0.56167 0.825045 -0.0618582 -0.563141 0.824029 -0.0620425 -0.565755 0.823933 -0.0324969 -0.56544 0.82415 -0.0324756 -0.5662 0.824268 0.000652066 -0.564495 0.825436 0.000685389 -0.563819 0.825417 0.0281925 -0.561388 0.827075 0.0281211 -0.558798 0.827043 0.0611915 -0.556193 0.828814 0.0609598 -0.550308 0.828763 0.101554 -0.548642 0.8299 0.101282 -0.537041 0.829815 0.151639 -0.538203 0.829006 0.151942 -0.51651 0.828842 0.21503 -0.523445 0.823764 0.217755 -0.193965 0.980369 -0.0354239 -0.192929 0.980369 -0.0406757 -0.192917 0.980372 -0.0406731 -0.193753 0.980365 -0.0366684 -0.19464 0.980183 -0.0368421 -0.195982 0.98019 -0.0286044 -0.196753 0.980032 -0.0287269 -0.197648 0.980031 -0.02177 -0.198232 0.979912 -0.0218418 -0.199173 0.979898 -0.0114398 -0.199053 0.979922 -0.0114319 -0.199296 0.979939 0.000233777 -0.198621 0.980076 0.000244701 -0.198386 0.980074 0.00992595 -0.197427 0.980268 0.00989456 -0.196523 0.980263 0.0215269 -0.195499 0.98047 0.0214325 -0.193442 0.980462 0.0357026 -0.192792 0.980594 0.035594 -0.188736 0.980581 0.0532898 -0.189197 0.980485 0.0534115 -0.181608 0.980462 0.0755885 -0.184366 0.979862 0.076682 -0.970248 -0.180247 -0.161649 -0.194673 -0.980355 -0.0317418 -0.194671 -0.980355 -0.0317416 -0.553729 -0.827788 -0.0902866 -0.55372 -0.827794 -0.0902856 -0.826606 -0.546404 -0.13478 -0.826595 -0.54642 -0.134779 -0.194623 -0.980342 -0.0324253 -0.194561 -0.980355 -0.0324173 -0.553419 -0.827783 -0.092209 -0.553412 -0.827788 -0.092208 -0.82614 -0.546394 -0.137649 -0.826133 -0.546404 -0.137648 -0.970293 -0.179988 -0.161666 -0.970848 -0.179988 -0.158299 -0.970845 -0.180006 -0.158299 -0.970294 0.179988 -0.161657 -0.194562 0.980355 -0.0324151 -0.194624 0.980342 -0.0324278 -0.553412 0.827788 -0.0922078 -0.553419 0.827783 -0.0922093 -0.826133 0.546403 -0.137647 -0.82614 0.546394 -0.137649 -0.970246 0.180247 -0.161659 -0.194671 0.980355 -0.0317416 -0.194673 0.980355 -0.0317419 -0.55372 0.827794 -0.0902852 -0.553729 0.827788 -0.090287 -0.826595 0.54642 -0.134778 -0.826606 0.546404 -0.134781 -0.970845 0.180005 -0.158298 -0.970848 0.179988 -0.1583 -0.840963 -0.053473 -0.538444 -0.553142 -0.115185 -0.825086 -0.17454 -0.973485 -0.14786 -0.535145 -0.823633 -0.187743 -0.814278 -0.545189 -0.1993 -0.967029 -0.179954 -0.180199 -0.207454 -0.967984 -0.141314 -0.176326 -0.925805 -0.334356 -0.021759 -0.923126 -0.383881 -0.195241 -0.852466 -0.484956 -0.158583 -0.714789 -0.681122 -0.196141 -0.712109 -0.674114 -0.159629 -0.458516 -0.874232 -0.186134 -0.459361 -0.868529 -0.163866 -0.155549 -0.974142 -0.176514 -0.157508 -0.971614 -0.555457 -0.811474 -0.181599 -0.51469 -0.753306 -0.40942 -0.542678 -0.738532 -0.400088 -0.503308 -0.592118 -0.629347 -0.527007 -0.583612 -0.617786 -0.496805 -0.374008 -0.783137 -0.513637 -0.371666 -0.773331 -0.495303 -0.121896 -0.860126 -0.399926 -0.110856 -0.909819 -0.822788 -0.533974 -0.194658 -0.795589 -0.4968 -0.346739 -0.807641 -0.482995 -0.338279 -0.781513 -0.385948 -0.490186 -0.791975 -0.377652 -0.479744 -0.77203 -0.239455 -0.588753 -0.779606 -0.236616 -0.579851 -0.767534 -0.0724479 -0.636901 -0.732815 -0.0696635 -0.676852 -0.968217 -0.175389 -0.178309 -0.9591 -0.162796 -0.231571 -0.960936 -0.157066 -0.227888 -0.951808 -0.123235 -0.280848 -0.953584 -0.11969 -0.27632 -0.94663 -0.0715863 -0.314271 -0.947992 -0.0703025 -0.310434 -0.943788 -0.0131879 -0.330288 -0.944458 -0.0132362 -0.328366 -0.400644 0.0804752 -0.912693 -0.176839 0.0940589 -0.979735 -0.733662 0.0446595 -0.678046 -0.554992 0.0672922 -0.829129 -0.841722 0.0271028 -0.539231 -0.944517 0.00133655 -0.32846 -0.170879 0.0967496 -0.98053 -0.182303 0.345447 -0.920561 -0.161137 0.353433 -0.921477 -0.192165 0.623289 -0.758013 -0.159252 0.637142 -0.754115 -0.201742 0.835091 -0.511785 -0.161246 0.850846 -0.500061 -0.210328 0.955467 -0.20699 -0.166859 0.967828 -0.188329 -0.499979 0.0573253 -0.864138 -0.509304 0.278029 -0.814438 -0.495886 0.285411 -0.820145 -0.521705 0.509309 -0.684418 -0.501023 0.524326 -0.688519 -0.536775 0.690234 -0.485232 -0.511591 0.710552 -0.483105 -0.553409 0.799316 -0.234164 -0.52675 0.819947 -0.224102 -0.769387 0.0261431 -0.638248 -0.775877 0.175097 -0.6061 -0.769898 0.180272 -0.612176 -0.786985 0.328289 -0.52238 -0.777947 0.339723 -0.52857 -0.801764 0.450051 -0.393228 -0.791137 0.466551 -0.395517 -0.819214 0.525983 -0.228539 -0.808401 0.544046 -0.224725 -0.944221 0.00174174 -0.329308 -0.946377 0.0488806 -0.319346 -0.945329 0.0508195 -0.322135 -0.951281 0.102398 -0.290824 -0.949839 0.106821 -0.293931 -0.958146 0.145322 -0.246653 -0.956674 0.15185 -0.248427 -0.966502 0.172641 -0.18992 -0.965285 0.179906 -0.189361 -0.94435 0.0167707 -0.328514 -0.923505 -0.00891086 -0.383483 -0.841718 0.0150591 -0.539708 -0.733857 0.0131274 -0.679177 -0.648831 -0.022535 -0.760599 -0.175945 0.00319016 -0.984395 -0.233025 -0.0217558 -0.972227 -0.400625 0.00728065 -0.916213 -0.555273 0.0100931 -0.831607 -0.94435 -0.0167707 -0.328514 -0.923552 0.00885797 -0.383371 -0.84172 -0.014942 -0.539708 -0.733859 -0.0130254 -0.679177 -0.649295 0.0221782 -0.760213 -0.555277 -0.00985914 -0.831607 -0.400628 -0.00711185 -0.916213 -0.233747 0.0211325 -0.972068 -0.175948 -0.0030534 -0.984395 -0.598699 -0.733214 -0.322423 0.0321713 -0.0916443 -0.995272 -0.247414 -0.764659 -0.595048 -0.187346 -0.795038 -0.576902 -0.429478 -0.613632 -0.662574 -0.18283 -0.393768 -0.900844 -0.235584 -0.368664 -0.899215 -0.429597 -0.624141 -0.652606 -0.598783 -0.732991 -0.322775 -0.338097 -0.902137 -0.268028 -0.421575 -0.883302 -0.205066 -0.131292 -0.954519 -0.267686 -0.26111 -0.942509 -0.208562 -0.0793491 -0.985077 -0.15273 -0.0798953 -0.985372 -0.150531 -0.800251 -0.475871 -0.364891 -0.800252 -0.475706 -0.365103 -0.601194 -0.405108 -0.688806 -0.601144 -0.404961 -0.688935 -0.30907 -0.272224 -0.911246 -0.309009 -0.272117 -0.911299 0.0406831 -0.0921645 -0.994912 0.0567171 -0.132053 -0.989619 -0.907048 -0.164832 -0.387421 -0.907025 -0.164761 -0.387503 -0.692115 -0.14031 -0.708018 -0.692085 -0.140269 -0.708056 -0.370153 -0.0942842 -0.924174 -0.37014 -0.0942724 -0.92418 0.0121207 -0.0332497 -0.999374 0.0121297 -0.0332431 -0.999374 0.0121274 0 -0.999926 0.0121274 0 -0.999926 -0.371809 0 -0.928309 -0.371809 0 -0.928309 -0.69903 0 -0.715092 -0.69903 0 -0.715092 -0.919627 0 -0.392793 -0.919627 0 -0.392793 -0.832307 0.409531 -0.373563 -0.453885 0.840888 -0.294782 -0.0740807 0.985748 -0.15104 -0.0793491 0.985077 -0.15273 -0.0798953 0.985372 -0.150531 -0.306109 0.911935 -0.273261 -0.341361 0.905752 -0.251171 -0.247414 0.764659 -0.595048 -0.187347 0.795038 -0.576902 0.0567171 0.132053 -0.989619 -0.187634 0.331766 -0.924513 -0.598587 0.733166 -0.322742 -0.598889 0.733038 -0.322471 -0.423449 0.619374 -0.66111 -0.435267 0.61825 -0.654454 -0.200811 0.411028 -0.88923 -0.752459 0.553396 -0.357154 -0.817935 0.479801 -0.317448 -0.601081 0.405062 -0.688931 -0.601243 0.405002 -0.688825 -0.308967 0.272175 -0.911296 -0.309095 0.272159 -0.911257 0.0406831 0.0921645 -0.994912 0.0321714 0.0916443 -0.995272 0.0121207 0.0332446 -0.999374 0.0121314 0.033248 -0.999374 -0.370153 0.0942744 -0.924175 -0.370137 0.0942818 -0.924181 -0.692119 0.140273 -0.708022 -0.692077 0.140305 -0.708057 -0.907058 0.164764 -0.387425 -0.907013 0.164829 -0.387503 -0.988465 -0.0997659 0.113943 -0.932712 -0.119915 -0.340102 -0.68239 -0.109965 -0.72267 -0.287317 -0.0759111 -0.954823 -0.293153 -0.100968 -0.950719 -0.259578 -0.273749 -0.92611 -0.278421 -0.352661 -0.893371 -0.204443 -0.495542 -0.844181 -0.222497 -0.59909 -0.769147 -0.991525 -0.0774168 0.104333 -0.93201 -0.336206 0.135362 -0.952715 -0.293279 0.0795039 -0.814219 -0.555627 0.168303 -0.83897 -0.539756 0.0692244 -0.679785 -0.712477 0.17398 -0.67926 -0.711686 0.179188 -0.683306 -0.120509 -0.720118 -0.626269 -0.381979 -0.679616 -0.627537 -0.408282 -0.662951 -0.505796 -0.636925 -0.581804 -0.50747 -0.66406 -0.549088 -0.328993 -0.841039 -0.429438 -0.348473 -0.86158 -0.369115 -0.506868 -0.857068 0.0923004 -0.425551 -0.893474 0.143565 -0.516858 -0.742609 0.425899 -0.142505 -0.985615 -0.0908552 -0.0887641 -0.97617 -0.198021 0.169395 -0.749817 -0.639594 -0.0421087 -0.893135 -0.447814 -0.221762 -0.796966 -0.561843 0.0259254 -0.682435 -0.730486 -0.112513 -0.712105 -0.692999 -0.000925518 -1 7.52866e-05 -0.932809 -0.110527 -0.343002 -0.863341 -0.404796 -0.301301 -0.866341 -0.384271 -0.319045 -0.719714 -0.657081 -0.224182 -0.722803 -0.641301 -0.257466 -0.512788 -0.849713 -0.122623 -0.4963 -0.849092 -0.180912 -0.215933 -0.976408 -0.000249796 -0.288149 0 -0.957586 -0.288149 0 -0.957586 -0.686553 0 -0.72708 -0.686553 0 -0.72708 -0.939491 0 -0.342574 -0.939491 0 -0.342574 -0.993422 0 0.114515 -0.993422 0 0.114515 -0.286702 0.100078 -0.952778 -0.681564 0.120337 -0.721796 -0.933742 0.110461 -0.340478 -0.990528 0.0762695 0.114181 -0.989112 0.100624 0.107391 -0.952796 0.275003 0.128656 -0.930824 0.351763 0.0991393 -0.297023 0.0771081 -0.951752 -0.244812 0.336586 -0.909273 -0.305804 0.29273 -0.905976 -0.169117 0.555516 -0.814126 -0.271811 0.539672 -0.796789 -0.112513 0.712105 -0.692999 -0.110507 0.711781 -0.693654 -0.829284 0.535053 0.161265 -0.848653 0.516816 0.112649 -0.747658 0.650371 0.134258 -0.677592 0.714271 0.175172 -0.555748 0.829239 0.0592243 -0.12028 0.857473 -0.500272 -0.0421092 0.893135 -0.447813 0.169395 0.749817 -0.639593 -0.931937 0.120068 -0.342167 -0.871706 0.38307 -0.305591 -0.858075 0.407284 -0.312774 -0.734186 0.637858 -0.232613 -0.706797 0.663162 -0.24628 -0.524303 0.841626 -0.129507 -0.479494 0.861014 -0.169527 -0.215934 0.976408 -0.000248735 -0.43945 0.8449 0.305005 -0.452476 0.882678 0.127067 -0.684527 0.110044 -0.720634 -0.618411 0.405533 -0.673135 -0.637329 0.383353 -0.66847 -0.491388 0.657475 -0.571196 -0.525252 0.640721 -0.559988 -0.317494 0.849573 -0.421217 -0.366611 0.849036 -0.380441 -0.0885926 0.97621 -0.197904 -0.154359 0.983108 -0.09835 -0.000966918 1 0.000160307 -0.000206116 -0.960615 0.277882 -0.158471 -0.896808 0.413064 -0.0966758 -0.897624 0.430029 -0.25311 -0.790626 0.557535 -0.13384 -0.77645 0.615802 -0.320893 -0.543996 0.775304 -0.232571 -0.571668 0.786833 -0.35718 -0.266026 0.895351 -0.316378 -0.303975 0.898613 -0.348882 -0.058889 0.935314 -0.345135 -0.0715735 0.93582 -0.00131496 -0.999999 0.000158814 -0.125701 -0.986561 0.104385 -0.125434 -0.986567 0.104654 -0.289713 -0.926088 0.241719 -0.289613 -0.926113 0.241743 -0.42314 -0.834387 0.3532 -0.422869 -0.834463 0.353347 -0.602016 -0.620102 0.503041 -0.601776 -0.620273 0.503117 -0.72482 -0.327742 0.605988 -0.724684 -0.327944 0.606041 -0.764872 -0.0762699 0.639651 -0.764856 -0.0763557 0.639661 -0.273008 -0.960716 -0.049911 -0.400701 -0.914674 0.0530098 -0.468265 -0.882647 0.0407819 -0.550268 -0.827682 0.110215 -0.662066 -0.748081 0.0452003 -0.785949 -0.600985 0.145264 -0.847812 -0.518748 0.110072 -0.933018 -0.31184 0.179536 -0.952945 -0.258681 0.158051 -0.981605 -0.0718561 0.176885 -0.982939 -0.058742 0.1743 -0.993914 0 0.110159 -0.984624 0.0055266 0.174599 -0.932023 0 0.362398 -0.843903 0 0.536496 -0.767074 0.00737759 0.641516 -0.28423 0 0.958756 -0.346017 0.00552711 0.938212 -0.521581 0 0.853202 -0.677307 0 0.735701 -0.48932 0.36848 0.790435 -0.442336 0.391889 0.806698 -0.521914 0.839543 0.15091 -0.12194 0.985122 0.121104 -0.122079 0.984837 0.123256 -0.373095 0.919753 0.121878 -0.269903 0.919584 0.285514 -0.399942 0.905398 0.142481 -0.414127 0.7628 0.496623 -0.350912 0.793735 0.496836 -0.605481 0.613203 0.507322 -0.603184 0.621798 0.499537 -0.666962 0.732809 0.134728 -0.909675 0.414906 0.0185807 -0.824525 0.552095 0.123896 -0.667901 0.731659 0.136321 -0.26384 0.0911211 0.960253 -0.28409 0.0330241 0.958229 -0.284075 0.0330126 0.958233 -0.520121 0.0747768 0.850813 -0.632246 0.0687662 0.77171 -0.673729 0.102645 0.731815 -0.868552 0.13985 0.475458 -0.840957 0.0834796 0.534623 -0.921402 0.15054 0.358268 -0.239753 0.129691 0.962132 -0.255809 0.0916054 0.962377 -0.563764 0.271106 0.780174 -0.563587 0.270666 0.780455 -0.776639 0.403972 0.483362 -0.77659 0.403251 0.484041 -0.871778 0.475382 0.118387 -0.980388 0.164662 0.108291 -0.980398 0.164356 0.108661 -0.166524 0 -0.986037 -0.166524 0 -0.986037 -0.634641 0 -0.772807 -0.634641 0 -0.772807 -0.934834 0 -0.355084 -0.934834 0 -0.355084 -0.997473 -0.0680786 0.020346 -0.998262 -0.0564478 0.0169524 -0.913821 -0.0763713 0.398871 -0.914603 -0.0719283 0.397905 -0.69318 -0.0719534 0.717164 -0.692 -0.0763367 0.71785 -0.368481 -0.056764 0.927901 -0.364225 -0.0678012 0.92884 -0.954306 -0.296785 0.0349059 -0.969125 -0.246516 0.00521328 -0.864428 -0.326383 0.382411 -0.873895 -0.310381 0.374127 -0.664732 -0.31117 0.679194 -0.652104 -0.324686 0.685084 -0.380125 -0.257065 0.888495 -0.336162 -0.286385 0.897206 -0.255867 -0.543423 0.799514 -0.345977 -0.531734 0.773019 -0.53164 -0.612043 0.585459 -0.559835 -0.5993 0.57221 -0.744424 -0.596467 0.300099 -0.720122 -0.617514 0.316388 -0.867517 -0.496803 -0.0245271 -0.676573 -0.711007 -0.191619 -0.700173 -0.712281 -0.0491163 -0.813684 -0.580603 0.0286177 -0.00123076 -0.999999 7.68477e-05 -0.138361 -0.985763 0.0955415 -0.0913952 -0.98255 0.161993 -0.269869 -0.918976 0.287495 -0.249342 -0.921503 0.297759 -0.183649 -0.982559 0.0291645 -0.35303 -0.924251 0.145361 -0.37451 -0.917243 0.135676 -0.189613 -0.844669 0.500581 -0.117817 -0.885192 0.450061 -0.17534 -0.890966 0.41885 -0.0133478 -0.9528 0.303304 -0.198314 -0.712287 0.67329 -0.165735 -0.713324 0.680956 -0.362223 -0.825088 0.433618 -0.402014 -0.822308 0.402733 -0.542547 -0.817211 0.194446 -0.503629 -0.83377 0.226242 -0.617014 -0.784355 0.0638766 -0.488274 -0.872192 -0.0294886 -0.422736 -0.906246 -0.00363776 -0.288807 -0.95283 -0.0933075 -0.999856 0 0.0169795 -0.999856 0 0.0169795 -0.916978 0 0.398938 -0.916978 0 0.398938 -0.694025 0 0.719951 -0.694025 0 0.719951 -0.365065 0 0.930982 -0.365065 0 0.930982 -0.767917 0.640529 -0.00509387 -0.36737 0.0680585 0.927581 -0.364482 0.0564925 0.929495 -0.692861 0.0763806 0.717015 -0.692227 0.0719347 0.718086 -0.914072 0.0719474 0.399118 -0.914303 0.0763274 0.397774 -0.998163 0.0567212 0.0212804 -0.997554 0.0678198 0.0169404 -0.365905 0.296752 0.882073 -0.343283 0.246552 0.906294 -0.660157 0.326338 0.676533 -0.655722 0.310424 0.688234 -0.868541 0.311134 0.385788 -0.869657 0.32472 0.371824 -0.965303 0.257049 0.0460032 -0.958109 0.286399 0.00170966 -0.862653 0.505068 -0.027128 -0.865573 0.500509 -0.0165613 -0.734218 0.612059 0.293781 -0.731629 0.59927 0.324953 -0.541085 0.596515 0.592788 -0.547842 0.617471 0.564446 -0.279858 0.496885 0.821453 -0.0563993 0.711029 0.700897 -0.198314 0.712286 0.67329 -0.310826 0.58054 0.752569 -0.474311 0.879497 -0.0389095 -0.47799 0.878237 -0.0150082 -0.183648 0.982559 0.029166 -0.363543 0.918973 0.152728 -0.366015 0.921505 0.129852 -0.00123076 0.999999 7.68477e-05 -0.129624 0.98752 0.0894585 -0.0915878 0.98251 0.162129 -0.259328 0.924241 0.280226 -0.257742 0.917252 0.303676 -0.405037 0.914161 -0.0159661 -0.288807 0.95283 -0.0933076 -0.655378 0.75153 -0.0753834 -0.617015 0.784355 0.0638756 -0.532771 0.825085 0.188123 -0.517651 0.822302 0.236341 -0.37153 0.817241 0.440548 -0.387706 0.83374 0.393144 -0.275054 0.784332 0.556029 -0.142603 0.872206 0.467891 -0.143983 0.906237 0.397496 -0.0133478 0.9528 0.303304 -0.999905 0 -0.0137663 -0.999905 0 -0.0137663 -0.928903 0 0.370323 -0.928903 0 0.370323 -0.716195 0 0.6979 -0.716195 0 0.6979 -0.39423 0 0.919012 -0.39423 0 0.919012 0.984375 9.11509e-06 0.176082 0.984375 1.60063e-06 0.176083 0.984376 0 0.176079 0.984379 2.08158e-06 0.176064 0.984375 -1.61792e-06 0.176085 0.984375 -3.48427e-06 0.176082 0.984375 1.72037e-07 0.176085 0.984375 -1.29823e-06 0.176082 0.984371 1.90491e-06 0.176105 0.984377 0 0.176072 0.998188 -0.000140631 -0.0601679 0.998194 1.79389e-06 -0.0600742 0.998193 0 -0.0600864 0.998193 0 -0.0600864 0.998194 -1.79389e-06 -0.0600742 0.998188 0.000140623 -0.0601679 0.998194 9.32927e-06 -0.0600693 0.998194 -2.039e-06 -0.0600768 0.998195 0 -0.0600629 0.998195 0 -0.0600629 0.998194 2.039e-06 -0.0600768 0.998194 -9.32927e-06 -0.0600693 0.984376 2.6936e-06 0.176082 0.984376 1.04826e-06 0.176081 0.984377 0 0.176074 0.984377 0 0.176074 0.984376 -1.04826e-06 0.176081 0.984376 -2.6936e-06 0.176082 -0.981405 -0.191473 -0.0135116 -0.798945 -0.601303 -0.0109997 -0.449191 -0.893415 -0.00618421 -0.198752 -0.980046 -0.00273609 -0.271656 -0.960929 -0.053085 -0.244814 -0.964646 0.0975962 -0.244815 -0.964645 0.0975958 -0.188753 -0.964645 0.183934 -0.188752 -0.964646 0.183934 -0.103897 -0.964646 0.242207 -0.175098 -0.608724 0.773819 -0.242923 -0.787583 0.566304 -0.103898 -0.964645 0.242208 -0.616144 -0.787588 -0.00848272 -0.718387 -0.689055 -0.095519 -0.663191 -0.7002 0.264382 -0.663188 -0.700202 0.264385 -0.511319 -0.700203 0.498267 -0.511324 -0.7002 0.498265 -0.281461 -0.700201 0.656124 -0.900152 -0.4354 -0.0123932 -0.963803 -0.249352 -0.0943785 -0.898404 -0.254157 0.358155 -0.898399 -0.254162 0.358162 -0.692675 -0.254163 0.674984 -0.692677 -0.254161 0.674982 -0.381287 -0.254162 0.888832 -0.381284 -0.254163 0.888833 -0.775882 -0.60876 -0.165585 -0.432545 -0.896874 -0.092312 -0.190794 -0.980785 -0.0407186 -0.959186 -0.195084 -0.204705 -0.959185 -0.195089 -0.204705 -0.961895 -0.195092 -0.191564 -0.920093 -0.35141 -0.173028 -0.964695 -0.195076 -0.176941 -0.822451 -0.55548 -0.122541 -0.822447 -0.555486 -0.122541 -0.817184 -0.555513 -0.153676 -0.817173 -0.555529 -0.153674 -0.813255 -0.55555 -0.173146 -0.877121 -0.442287 -0.187191 -0.969689 -0.19506 -0.147158 -0.939703 -0.312017 -0.140011 -0.97266 -0.195088 -0.125991 -0.190803 -0.980783 -0.0407205 -0.191748 -0.980781 -0.0360597 -0.191757 -0.98078 -0.0360611 -0.193 -0.980777 -0.0287563 -0.193004 -0.980776 -0.0287568 -0.193822 -0.980783 -0.0223142 -0.193824 -0.980783 -0.0223143 -0.439408 -0.896862 -0.0505876 -0.551753 -0.831459 -0.0651486 -0.549597 -0.831407 -0.0818877 -0.549587 -0.831414 -0.081886 -0.546055 -0.831432 -0.102689 -0.546037 -0.831444 -0.102685 -0.543435 -0.831459 -0.115562 -0.595355 -0.793353 -0.127058 -0.974352 -0.195078 -0.112174 -0.974352 -0.195077 -0.112174 -0.891003 -0.442257 -0.102578 -0.825838 -0.555554 -0.0967018 -0.788164 -0.608739 -0.0907388 -0.604795 -0.793332 -0.069628 -0.0444919 -0.963642 -0.263466 -0.169572 -0.963642 -0.206492 -0.249784 -0.963642 -0.0948764 -0.44013 -0.896872 -0.0436485 -0.188474 -0.979466 -0.0715885 -0.904988 -0.250668 -0.343747 -0.942139 -0.192028 -0.274771 -0.843918 -0.430178 -0.320545 -0.672239 -0.694908 -0.255337 -0.775393 -0.605873 -0.177999 -0.581326 -0.783137 -0.220807 -0.169572 -0.963643 -0.206491 -0.456366 -0.69491 -0.555725 -0.456367 -0.69491 -0.555725 -0.614377 -0.250667 -0.748136 -0.614379 -0.25067 -0.748133 -0.0444924 -0.963642 -0.263465 -0.119742 -0.69491 -0.709057 -0.119742 -0.694911 -0.709056 -0.161202 -0.250663 -0.954559 -0.161207 -0.250667 -0.954557 0.12049 -0.597261 0.792945 0.153642 -0.879708 0.450009 0.38763 -0.389895 0.835299 0.329625 -0.394056 0.857943 0.0999708 -0.254711 0.961836 0.162257 -0.250594 0.954398 0.984136 -0.043267 0.172061 0.985358 -0.0654207 0.157445 0.916923 -0.199599 0.345563 0.965111 -0.155923 0.210352 0.762645 -0.427512 0.485392 0.787608 -0.420542 0.450353 0.740186 -0.476376 0.474542 0.080973 -0.975929 0.202501 0.688298 -0.518334 0.507519 0.480272 -0.578845 0.658997 0.424103 -0.618932 0.661105 0.123511 -0.694397 0.708913 -0.049255 -0.793336 0.606788 0.970392 -0.194823 0.142774 0.97039 -0.194827 0.142777 0.805214 -0.549517 0.222849 0.80522 -0.54951 0.222842 0.51978 -0.811573 0.26679 0.519785 -0.811572 0.266787 0.164307 -0.948578 0.270561 0.976562 -0.195092 0.0909199 0.976562 -0.195092 0.0909199 0.827888 -0.555572 0.0770781 0.827891 -0.555568 0.0770788 0.553178 -0.831469 0.0515023 0.553178 -0.831469 0.0515024 0.19425 -0.980785 0.0180852 0.19425 -0.980785 0.0180851 0.234175 -0.879183 -0.414969 0.277227 -0.188175 -0.942197 0.995481 -0.0893784 -0.0320707 0.991549 -0.0934635 -0.0899717 0.88288 -0.366664 -0.293394 0.861344 -0.250602 -0.441911 0.783167 -0.451424 -0.427627 0.610581 -0.545493 -0.574133 0.640577 -0.441501 -0.628282 0.588398 -0.466418 -0.660486 0.28282 -0.187893 -0.94059 0.257697 -0.432224 -0.864162 0.206238 -0.523617 -0.826614 0.180898 -0.785679 -0.591595 0.265014 -0.595419 -0.758448 0.241444 -0.814161 -0.52806 0.588971 -0.69385 -0.414349 0.588984 -0.693836 -0.414354 0.851972 -0.467106 -0.236548 0.851971 -0.467109 -0.236548 0.986112 -0.164909 -0.0197061 0.986112 -0.164911 -0.0197063 0.208466 -0.962421 -0.174036 0.208471 -0.962419 -0.174039 0.560893 -0.82019 -0.112641 0.56089 -0.820192 -0.112639 0.833062 -0.552168 -0.033427 0.833063 -0.552168 -0.0334273 0.979435 -0.194943 0.0520041 0.979435 -0.194943 0.0520043 0.0180857 0.980785 -0.194249 0.0175423 0.965904 -0.258306 0.0410008 0.896871 -0.440387 0.0564323 0.793356 -0.606137 0.0569334 0.707084 -0.704834 0.0909198 0.195077 -0.976565 0.0830887 0.258809 -0.962348 0.08314 0.442306 -0.893002 0.0735442 0.608764 -0.789935 -0.0756866 0.890721 -0.448205 -0.533161 0.542452 -0.64922 -0.843915 0.430177 -0.320556 -0.163531 0.188751 -0.968313 -0.918025 0.188768 -0.348706 -0.918029 0.188762 -0.348701 -0.62324 0.188761 -0.758908 -0.750907 0.595639 -0.285223 -0.623231 0.188771 -0.758913 -0.163509 0.188772 -0.968313 -0.139876 0.542454 -0.828359 -0.0513265 0.4383 -0.897362 -0.133745 0.595632 -0.792045 -0.58847 0.787411 -0.183539 -0.531669 0.822524 -0.201948 -0.360946 0.822522 -0.439518 -0.801237 0.537371 -0.263157 -0.533154 0.542457 -0.64922 -0.360941 0.822525 -0.439517 -0.0946953 0.822524 -0.560791 -0.0655969 0.787417 -0.612921 -0.0335697 0.979466 -0.198795 -0.0335711 0.979466 -0.198797 -0.127953 0.979465 -0.155806 -0.127946 0.979467 -0.155803 -0.1556 0.980775 -0.117771 -0.249784 0.963642 -0.0948761 -0.604795 0.793331 -0.0696282 -0.891003 0.442257 -0.102578 -0.944653 0.258818 -0.201603 -0.691535 0.707106 -0.147584 -0.944655 0.258809 -0.201604 -0.947322 0.25882 -0.188661 -0.911544 0.373768 -0.171421 -0.974352 0.195078 -0.112174 -0.959311 0.258809 -0.112872 -0.957923 0.258817 -0.124082 -0.928514 0.344561 -0.138344 -0.955002 0.25878 -0.14493 -0.950082 0.2588 -0.174261 -0.788164 0.60874 -0.0907388 -0.702099 0.707099 -0.084076 -0.69947 0.707023 -0.104218 -0.699462 0.70703 -0.104217 -0.694977 0.707054 -0.130694 -0.69496 0.707071 -0.130692 -0.691551 0.707089 -0.147588 -0.253118 0.965926 -0.0540194 -0.253131 0.965923 -0.0540223 -0.254385 0.965919 -0.0478386 -0.254395 0.965916 -0.0478408 -0.256045 0.965912 -0.0381496 -0.25605 0.96591 -0.0381505 -0.257136 0.965922 -0.0296033 -0.257137 0.965921 -0.0296034 -0.315 0.601303 0.734309 -0.967071 0.25416 -0.0133142 -0.967071 0.25416 -0.0133145 -0.898401 0.254157 0.358163 -0.898403 0.254162 0.358154 -0.692676 0.254163 0.674982 -0.692675 0.254161 0.674984 -0.381284 0.254162 0.888833 -0.381287 0.254163 0.888832 -0.713879 0.7002 -0.00982858 -0.713879 0.7002 -0.00982831 -0.66319 0.700199 0.264385 -0.66319 0.700201 0.264382 -0.511322 0.700203 0.498263 -0.51132 0.7002 0.498268 -0.205015 0.689057 0.695104 -0.242923 0.787583 0.566305 -0.263525 0.964646 -0.00362807 -0.263526 0.964646 -0.0036278 -0.244814 0.964646 0.0975953 -0.244814 0.964646 0.0975963 -0.188752 0.964645 0.183934 -0.188752 0.964646 0.183933 -0.103897 0.964646 0.242207 -0.103897 0.964645 0.242208 0.978308 0 0.207153 0.978309 7.61103e-08 0.20715 0.978309 1.36171e-07 0.207149 0.978309 0 0.20715 0.978311 0.000106416 0.207142 0.978309 -4.44755e-07 0.207151 0.978309 -1.27333e-06 0.20715 0.978309 -4.90055e-07 0.20715 0.978308 0 0.207153 0.65598 0.704063 -0.272001 0.655981 0.704062 -0.272002 0.56323 0.704062 -0.432515 0.563229 0.704065 -0.432512 0.432095 0.704065 -0.563548 0.432096 0.704061 -0.563552 0.271515 0.704061 -0.656184 0.271515 0.704061 -0.656184 0.0924301 0.704061 -0.704099 0.0924308 0.704064 -0.704095 -0.0929529 0.704064 -0.704027 -0.0929538 0.704062 -0.704028 -0.272001 0.704062 -0.655981 -0.272001 0.704062 -0.655982 -0.432514 0.704062 -0.56323 -0.432515 0.704061 -0.563231 -0.563552 0.704061 -0.432096 -0.56355 0.704063 -0.432095 -0.656182 0.704063 -0.271515 -0.656182 0.704063 -0.271514 -0.704096 0.704063 -0.0924303 -0.704097 0.704063 -0.0924302 -0.704028 0.704063 0.0929528 -0.704028 0.704063 0.0929526 -0.65598 0.704063 0.272001 -0.655981 0.704063 0.272002 -0.56323 0.704062 0.432514 -0.56323 0.704063 0.432513 -0.432095 0.704063 0.563551 -0.432096 0.704061 0.563552 -0.271515 0.704061 0.656184 -0.271515 0.704061 0.656184 -0.0924301 0.704061 0.704099 -0.0924308 0.704064 0.704095 0.0929529 0.704064 0.704027 0.0929523 0.704065 0.704025 0.272 0.704065 0.655979 0.272002 0.704062 0.655981 0.432514 0.704062 0.56323 0.432513 0.704064 0.563229 0.56355 0.704064 0.432095 0.56355 0.704063 0.432095 0.656182 0.704063 0.271514 0.656183 0.704063 0.271514 0.704097 0.704063 0.0924302 0.704096 0.704063 0.0924302 0.704028 0.704063 -0.0929528 0.704028 0.704063 -0.0929527 -0.656182 -0.704063 -0.271514 -0.656182 -0.704063 -0.271515 -0.563551 -0.704063 -0.432095 -0.563552 -0.704061 -0.432096 -0.432515 -0.704061 -0.563231 -0.432514 -0.704062 -0.56323 -0.272001 -0.704062 -0.655982 -0.272001 -0.704062 -0.655981 -0.0929532 -0.704062 -0.704028 -0.0929536 -0.704064 -0.704027 0.0924297 -0.704064 -0.704095 0.0924311 -0.704061 -0.704098 0.271515 -0.704061 -0.656184 0.271515 -0.704061 -0.656184 0.432097 -0.704061 -0.563551 0.432094 -0.704065 -0.563549 0.563228 -0.704065 -0.432513 0.563231 -0.704062 -0.432514 0.655981 -0.704062 -0.272002 0.65598 -0.704063 -0.272001 0.704028 -0.704063 -0.0929528 0.704028 -0.704063 -0.0929527 0.704096 -0.704063 0.0924302 0.704097 -0.704063 0.0924302 0.656182 -0.704063 0.271514 0.656182 -0.704063 0.271514 0.56355 -0.704063 0.432095 0.56355 -0.704063 0.432095 0.432513 -0.704064 0.563229 0.432514 -0.704062 0.563231 0.272001 -0.704062 0.655982 0.272001 -0.704065 0.655978 0.0929527 -0.704065 0.704025 0.0929525 -0.704064 0.704027 -0.0924297 -0.704064 0.704095 -0.0924311 -0.704061 0.704098 -0.271515 -0.704061 0.656184 -0.271515 -0.704061 0.656184 -0.432096 -0.704061 0.563552 -0.432095 -0.704063 0.563551 -0.56323 -0.704063 0.432513 -0.56323 -0.704062 0.432514 -0.655981 -0.704063 0.272001 -0.65598 -0.704063 0.272001 -0.704028 -0.704063 0.0929528 -0.704028 -0.704063 0.0929526 -0.704097 -0.704063 -0.0924304 -0.704096 -0.704063 -0.0924301 0.554063 0.829254 -0.0731529 0.51625 0.829254 -0.214063 0.516251 0.829254 -0.214063 0.443257 0.829254 -0.340384 0.443257 0.829254 -0.340384 0.340056 0.829253 -0.44351 0.340053 0.829256 -0.443507 0.213678 0.829256 -0.516407 0.213679 0.829255 -0.516408 0.0727412 0.829255 -0.554116 0.0727426 0.829252 -0.55412 -0.0731534 0.829252 -0.554066 -0.0731536 0.829255 -0.554063 -0.214062 0.829254 -0.51625 -0.214062 0.829254 -0.516251 -0.340384 0.829254 -0.443257 -0.340383 0.829255 -0.443255 -0.443508 0.829255 -0.340054 -0.443508 0.829255 -0.340054 -0.516409 0.829254 -0.213679 -0.516411 0.829253 -0.21368 -0.554118 0.829254 -0.0727419 -0.554118 0.829254 -0.0727416 -0.554063 0.829255 0.073153 -0.554064 0.829254 0.0731529 -0.516251 0.829254 0.214063 -0.51625 0.829255 0.214062 -0.443255 0.829255 0.340383 -0.443257 0.829253 0.340384 -0.340056 0.829253 0.44351 -0.340053 0.829256 0.443507 -0.213678 0.829256 0.516407 -0.213679 0.829255 0.516408 -0.072742 0.829255 0.554116 -0.0727421 0.829255 0.554116 0.0731529 0.829255 0.554062 0.0731528 0.829255 0.554063 0.214063 0.829255 0.51625 0.214063 0.829254 0.516251 0.340384 0.829254 0.443257 0.340385 0.829253 0.443258 0.44351 0.829253 0.340056 0.44351 0.829253 0.340056 0.51641 0.829254 0.213679 0.51641 0.829254 0.213679 0.554118 0.829254 0.0727419 0.554117 0.829255 0.0727417 0.554063 0.829254 -0.0731529 0.195017 0.980462 -0.0257481 0.181708 0.980462 -0.075345 0.181708 0.980462 -0.0753449 0.156016 0.980462 -0.119807 0.156016 0.980462 -0.119807 0.119691 0.980462 -0.156105 0.119691 0.980462 -0.156105 0.07521 0.980462 -0.181764 0.0752102 0.980462 -0.181764 0.0256035 0.980462 -0.195037 0.0256032 0.980462 -0.195036 -0.025748 0.980462 -0.195017 -0.025748 0.980462 -0.195016 -0.0753447 0.980462 -0.181707 -0.0753449 0.980462 -0.181708 -0.119807 0.980462 -0.156016 -0.119807 0.980462 -0.156016 -0.156105 0.980462 -0.119691 -0.156104 0.980462 -0.119691 -0.181764 0.980462 -0.07521 -0.181763 0.980462 -0.0752098 -0.195036 0.980462 -0.0256033 -0.195036 0.980462 -0.0256034 -0.195017 0.980462 0.0257481 -0.195017 0.980462 0.0257481 -0.181708 0.980462 0.0753448 -0.181708 0.980462 0.0753448 -0.156015 0.980462 0.119807 -0.156016 0.980462 0.119807 -0.119691 0.980462 0.156105 -0.119691 0.980462 0.156105 -0.07521 0.980462 0.181764 -0.0752102 0.980462 0.181764 -0.0256035 0.980462 0.195037 -0.0256037 0.980462 0.195038 0.0257483 0.980462 0.195019 0.0257483 0.980462 0.195018 0.0753454 0.980462 0.181709 0.0753451 0.980462 0.181708 0.119807 0.980462 0.156016 0.119806 0.980462 0.156015 0.156104 0.980462 0.119691 0.156104 0.980462 0.119691 0.181764 0.980462 0.0752099 0.181764 0.980462 0.0752099 0.195036 0.980462 0.0256033 0.195036 0.980462 0.0256035 0.195017 0.980462 -0.0257481 0.554064 0.829254 -0.0731532 0.554063 0.829255 -0.0731529 0.51625 0.829255 -0.214062 0.51625 0.829255 -0.214062 0.443255 0.829256 -0.340383 0.443257 0.829254 -0.340385 0.340056 0.829253 -0.44351 0.340054 0.829256 -0.443507 0.213678 0.829256 -0.516407 0.213679 0.829255 -0.516408 0.0727412 0.829255 -0.554116 0.0727412 0.829255 -0.554116 -0.0731528 0.829255 -0.554062 -0.0731531 0.829255 -0.554063 -0.214063 0.829254 -0.51625 -0.214061 0.829257 -0.516247 -0.340382 0.829256 -0.443254 -0.340383 0.829255 -0.443255 -0.443508 0.829255 -0.340054 -0.44351 0.829254 -0.340055 -0.51641 0.829254 -0.213679 -0.516409 0.829255 -0.213679 -0.554118 0.829254 -0.0727417 -0.554117 0.829255 -0.0727417 -0.554063 0.829254 0.073153 -0.554063 0.829255 0.0731529 -0.51625 0.829255 0.214062 -0.51625 0.829255 0.214062 -0.443255 0.829255 0.340383 -0.443255 0.829255 0.340383 -0.340054 0.829256 0.443507 -0.340054 0.829256 0.443507 -0.213678 0.829256 0.516407 -0.213679 0.829255 0.516408 -0.0727421 0.829255 0.554116 -0.0727418 0.829252 0.55412 0.0731543 0.829252 0.554066 0.0731531 0.829255 0.554063 0.214062 0.829255 0.51625 0.214062 0.829254 0.516251 0.340385 0.829254 0.443256 0.340383 0.829255 0.443256 0.443508 0.829255 0.340054 0.443508 0.829255 0.340054 0.516409 0.829255 0.213679 0.516409 0.829255 0.213679 0.554117 0.829254 0.0727417 0.554117 0.829254 0.0727417 0.195017 0.980462 -0.025748 0.195017 0.980462 -0.0257482 0.181708 0.980462 -0.075345 0.181708 0.980462 -0.0753449 0.156016 0.980462 -0.119807 0.156016 0.980462 -0.119807 0.119691 0.980462 -0.156105 0.119691 0.980462 -0.156105 0.0752102 0.980462 -0.181764 0.0752103 0.980462 -0.181764 0.0256035 0.980462 -0.195037 0.0256034 0.980462 -0.195038 -0.0257484 0.980462 -0.195019 -0.0257483 0.980462 -0.195018 -0.0753455 0.980462 -0.181709 -0.075345 0.980462 -0.181708 -0.119807 0.980462 -0.156016 -0.119807 0.980462 -0.156016 -0.156105 0.980462 -0.119691 -0.156104 0.980462 -0.119691 -0.181764 0.980462 -0.07521 -0.181764 0.980462 -0.0752101 -0.195036 0.980462 -0.0256033 -0.195036 0.980462 -0.0256033 -0.195017 0.980462 0.0257482 -0.195017 0.980462 0.0257481 -0.181708 0.980462 0.0753449 -0.181708 0.980462 0.0753448 -0.156015 0.980462 0.119807 -0.156016 0.980462 0.119807 -0.119691 0.980462 0.156105 -0.119691 0.980462 0.156105 -0.0752102 0.980462 0.181764 -0.0752103 0.980462 0.181764 -0.0256035 0.980462 0.195037 -0.0256035 0.980462 0.195036 0.0257481 0.980462 0.195017 0.0257486 0.980462 0.195018 0.0753452 0.980462 0.181709 0.0753447 0.980462 0.181708 0.119807 0.980462 0.156016 0.119807 0.980462 0.156016 0.156105 0.980462 0.119691 0.156104 0.980462 0.119691 0.181764 0.980462 0.07521 0.181764 0.980462 0.0752101 0.195036 0.980462 0.0256034 0.195036 0.980462 0.0256034 -0.554117 -0.829255 -0.0727416 -0.554118 -0.829254 -0.0727419 -0.516409 -0.829255 -0.213679 -0.51641 -0.829254 -0.21368 -0.443509 -0.829254 -0.340055 -0.443508 -0.829255 -0.340054 -0.340383 -0.829255 -0.443256 -0.340382 -0.829256 -0.443254 -0.214061 -0.829257 -0.516247 -0.214062 -0.829255 -0.51625 -0.0731529 -0.829255 -0.554063 -0.073153 -0.829255 -0.554062 0.0727412 -0.829255 -0.554116 0.0727412 -0.829255 -0.554116 0.213679 -0.829255 -0.516408 0.213678 -0.829256 -0.516407 0.340054 -0.829256 -0.443507 0.340056 -0.829253 -0.443509 0.443257 -0.829254 -0.340384 0.443255 -0.829255 -0.340383 0.516249 -0.829255 -0.214062 0.51625 -0.829255 -0.214062 0.554063 -0.829255 -0.0731531 0.554064 -0.829254 -0.073153 0.554117 -0.829254 0.0727418 0.554117 -0.829254 0.0727417 0.516409 -0.829255 0.213679 0.516409 -0.829255 0.213679 0.443508 -0.829255 0.340054 0.443508 -0.829255 0.340055 0.340384 -0.829255 0.443255 0.340384 -0.829254 0.443257 0.214062 -0.829254 0.516251 0.214062 -0.829255 0.51625 0.0731538 -0.829255 0.554063 0.0731536 -0.829252 0.554066 -0.0727427 -0.829252 0.55412 -0.0727412 -0.829255 0.554116 -0.213679 -0.829255 0.516408 -0.213678 -0.829256 0.516407 -0.340054 -0.829256 0.443507 -0.340054 -0.829256 0.443507 -0.443255 -0.829255 0.340383 -0.443255 -0.829255 0.340383 -0.51625 -0.829255 0.214062 -0.51625 -0.829255 0.214062 -0.554063 -0.829255 0.073153 -0.554063 -0.829254 0.0731529 -0.195036 -0.980462 -0.0256034 -0.195036 -0.980462 -0.0256033 -0.181764 -0.980462 -0.0752102 -0.181764 -0.980462 -0.07521 -0.156104 -0.980462 -0.119691 -0.156105 -0.980462 -0.119691 -0.119807 -0.980462 -0.156016 -0.119807 -0.980462 -0.156016 -0.0753452 -0.980462 -0.181708 -0.0753454 -0.980462 -0.181709 -0.0257483 -0.980462 -0.195018 -0.0257483 -0.980462 -0.195019 0.0256036 -0.980462 -0.195038 0.0256033 -0.980462 -0.195037 0.0752103 -0.980462 -0.181764 0.0752102 -0.980462 -0.181764 0.119691 -0.980462 -0.156105 0.119691 -0.980462 -0.156105 0.156016 -0.980462 -0.119807 0.156016 -0.980462 -0.119807 0.181708 -0.980462 -0.0753449 0.181708 -0.980462 -0.075345 0.195017 -0.980462 -0.0257481 0.195017 -0.980462 -0.0257481 0.195036 -0.980462 0.0256034 0.195036 -0.980462 0.0256034 0.181764 -0.980462 0.0752102 0.181764 -0.980462 0.0752099 0.156104 -0.980462 0.119691 0.156105 -0.980462 0.119691 0.119807 -0.980462 0.156016 0.119807 -0.980462 0.156016 0.0753449 -0.980462 0.181708 0.0753451 -0.980462 0.181709 0.0257483 -0.980462 0.195018 0.0257484 -0.980462 0.195017 -0.0256033 -0.980462 0.195036 -0.0256037 -0.980462 0.195037 -0.0752103 -0.980462 0.181764 -0.0752102 -0.980462 0.181764 -0.119691 -0.980462 0.156105 -0.119691 -0.980462 0.156105 -0.156016 -0.980462 0.119807 -0.156015 -0.980462 0.119807 -0.181708 -0.980462 0.0753448 -0.181708 -0.980462 0.0753449 -0.195017 -0.980462 0.0257482 -0.195017 -0.980462 0.0257481 -0.554118 -0.829254 -0.0727417 -0.516411 -0.829253 -0.21368 -0.516409 -0.829254 -0.213679 -0.443508 -0.829255 -0.340054 -0.443508 -0.829255 -0.340054 -0.340383 -0.829255 -0.443255 -0.340384 -0.829254 -0.443256 -0.214062 -0.829254 -0.516251 -0.214062 -0.829254 -0.51625 -0.073153 -0.829255 -0.554063 -0.0731541 -0.829252 -0.554066 0.0727418 -0.829252 -0.55412 0.072742 -0.829255 -0.554116 0.213679 -0.829255 -0.516408 0.213678 -0.829256 -0.516407 0.340054 -0.829256 -0.443507 0.340055 -0.829253 -0.44351 0.443257 -0.829254 -0.340384 0.443257 -0.829254 -0.340384 0.516251 -0.829254 -0.214063 0.516251 -0.829254 -0.214063 0.554063 -0.829254 -0.073153 0.554063 -0.829254 -0.0731529 0.554117 -0.829255 0.0727418 0.554118 -0.829254 0.0727418 0.51641 -0.829254 0.213679 0.51641 -0.829254 0.213679 0.44351 -0.829253 0.340056 0.44351 -0.829253 0.340056 0.340386 -0.829253 0.443258 0.340384 -0.829254 0.443257 0.214063 -0.829254 0.516251 0.214063 -0.829254 0.51625 0.073153 -0.829255 0.554063 0.0731527 -0.829255 0.554062 -0.072742 -0.829255 0.554116 -0.072742 -0.829255 0.554116 -0.213678 -0.829255 0.516408 -0.213678 -0.829256 0.516407 -0.340054 -0.829256 0.443507 -0.340055 -0.829253 0.44351 -0.443257 -0.829254 0.340385 -0.443255 -0.829255 0.340383 -0.51625 -0.829255 0.214062 -0.516251 -0.829254 0.214063 -0.554064 -0.829254 0.0731531 -0.554063 -0.829255 0.0731527 -0.554118 -0.829254 -0.0727418 -0.195036 -0.980462 -0.0256033 -0.181763 -0.980462 -0.0752098 -0.181764 -0.980462 -0.0752099 -0.156104 -0.980462 -0.119691 -0.156105 -0.980462 -0.119691 -0.119807 -0.980462 -0.156016 -0.119807 -0.980462 -0.156016 -0.075345 -0.980462 -0.181708 -0.0753446 -0.980462 -0.181707 -0.025748 -0.980462 -0.195016 -0.0257481 -0.980462 -0.195017 0.0256034 -0.980462 -0.195036 0.0256033 -0.980462 -0.195037 0.0752102 -0.980462 -0.181764 0.0752101 -0.980462 -0.181764 0.119691 -0.980462 -0.156105 0.119691 -0.980462 -0.156105 0.156016 -0.980462 -0.119807 0.156016 -0.980462 -0.119807 0.181708 -0.980462 -0.0753449 0.181708 -0.980462 -0.0753451 0.195017 -0.980462 -0.0257481 0.195017 -0.980462 -0.0257481 0.195036 -0.980462 0.0256034 0.195036 -0.980462 0.0256034 0.181764 -0.980462 0.0752099 0.181764 -0.980462 0.0752099 0.156104 -0.980462 0.119691 0.156104 -0.980462 0.119691 0.119806 -0.980462 0.156015 0.119807 -0.980462 0.156016 0.075345 -0.980462 0.181708 0.0753455 -0.980462 0.181709 0.0257482 -0.980462 0.195018 0.0257483 -0.980462 0.195019 -0.0256036 -0.980462 0.195038 -0.0256036 -0.980462 0.195037 -0.0752102 -0.980462 0.181764 -0.0752101 -0.980462 0.181764 -0.119691 -0.980462 0.156105 -0.119691 -0.980462 0.156105 -0.156016 -0.980462 0.119807 -0.156015 -0.980462 0.119807 -0.181708 -0.980462 0.0753447 -0.181708 -0.980462 0.0753449 -0.195017 -0.980462 0.0257481 -0.195017 -0.980462 0.0257482 -0.195036 -0.980462 -0.0256033 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.656511 0.00795758 0.754274 0.98678 0 0.162065 0.99794 0 -0.0641497 0.99794 0 -0.0641497 0.952317 -0.0110021 -0.304912 0.941319 0.0543062 -0.33312 0.941238 0.0409811 -0.33525 0.938626 0.0135179 -0.344673 0.93603 0 -0.35192 0.952317 0.0110021 -0.304912 0.986018 -0.0201288 -0.16542 0.984256 0 -0.176748 0.984256 0 -0.176748 0.986018 0.0201288 -0.16542 0.934582 -0.0322533 -0.354282 0.941992 -0.051015 -0.331737 0.938628 -0.0135295 -0.344666 0.93603 0 -0.35192 0.582468 -0.0192825 0.812625 0.410898 -0.00443385 0.911671 0.428339 0 0.903618 0.478961 0.0439731 0.876734 0.421193 0.0108483 0.906906 0.417807 -0.00983668 0.908483 0.415434 -0.00858435 0.909583 0.449466 0.0138495 0.89319 0.463679 0.000610864 0.886003 0.522135 -0.00101307 0.852862 0.501553 0.00194432 0.865125 0.558527 -0.00126481 0.829485 0.663482 0.000348152 0.748192 0.714918 0 0.699208 0.71722 0 0.696847 0.71723 -5.72721e-08 0.696837 0.719245 -5.67492e-08 0.694757 0.719235 0 0.694767 0.843546 0 0.537057 0.843546 0 0.537057 0.98678 0 0.162065 -0.966022 0 -0.258461 -0.966022 0 -0.258461 -0.707369 0 -0.706844 -0.707369 0 -0.706844 -0.259177 0 -0.96583 -0.259177 0 -0.96583 0.258461 0 -0.966022 0.258461 0 -0.966022 0.706844 0 -0.707369 0.706844 0 -0.707369 0.96583 0 -0.259177 0.96583 0 -0.259177 0.966022 0 0.25846 0.966022 0 0.25846 0.707369 0 0.706844 0.707369 0 0.706844 0.259178 0 0.96583 0.259178 0 0.96583 -0.258461 0 0.966022 -0.258461 0 0.966022 -0.706844 0 0.707369 -0.706844 0 0.707369 -0.96583 0 0.259177 -0.96583 0 0.259177 -0.000366087 1.38415e-05 -1 -0.000365349 0 -1 -0.000366087 -1.38416e-05 -1 -0.702369 -0.0313097 0.711124 -0.697026 -0.0253545 0.716598 -0.707205 -0.0311853 0.70632 -0.707976 -0.0267682 0.705729 -0.704954 -0.0326608 0.708501 -0.709711 -0.0382357 0.703454 -0.715946 -0.0493369 0.696411 -0.714517 -0.0524696 0.697648 -0.733036 -0.0317864 0.679447 -0.761732 0.0339934 0.647 -0.863198 -0.0348334 0.503663 -0.734873 -0.116804 0.66807 -0.769937 -0.0621598 0.635086 -0.805975 -0.0278734 0.591293 -0.804612 -0.0323372 0.59292 -0.835623 -0.0534348 0.546698 -0.869877 -0.0064382 0.493227 -0.943046 -0.0286456 0.331427 -0.928062 -0.0167104 0.372052 -0.908751 -0.0287634 0.416346 -0.909618 -0.0360085 0.413882 -0.965254 0.0234539 0.260257 -0.961335 -0.0176688 0.274813 -0.940101 0.00350202 0.340879 -0.998012 -0.0316144 -0.0545162 -0.997195 -0.0609923 -0.043372 -0.999486 -0.0191154 -0.0257314 -0.999219 -0.0355275 -0.0172968 -0.999367 -0.035423 -0.0032651 -0.999067 -0.0430693 0.00317417 -0.999662 -0.0042051 0.0256383 -0.997972 -0.05011 0.0392659 -0.998008 -0.0237913 0.058425 -0.996562 -0.0248898 0.0790177 -0.996356 -0.0100725 0.0846913 -0.992791 -0.0288785 0.116331 -0.991211 0.0134118 0.131608 -0.986116 -0.0309349 0.163151 -0.981237 0.0222469 0.19152 -0.978685 -0.00594129 0.20528 -0.97238 -0.00769428 0.233277 -0.994711 -0.0142518 -0.101724 -0.99459 -0.00353913 -0.103815 -0.995168 -0.0267069 -0.0944879 -0.995388 -0.0603113 -0.0746002 -0.996063 -0.0390346 -0.0795937 -0.997202 -0.0392868 -0.063605 -0.983705 0.02257 -0.178367 -0.987183 -0.0350552 -0.155693 -0.990503 -0.010104 -0.137118 -0.990225 0.00342395 -0.139434 -0.991598 -0.0449833 -0.121283 -0.983842 -0.0557952 -0.170122 -0.980193 0.000201025 -0.198045 -0.979692 -0.0150182 -0.199944 -0.977459 -0.0194757 -0.210223 -0.977489 -0.023086 -0.209719 -0.977391 -0.0252636 -0.209925 -0.978489 -0.0175475 -0.205553 -0.980173 -0.0270073 -0.196297 -0.980691 -0.0122931 -0.195179 -0.984028 -0.0252438 -0.176215 -0.984281 -0.0180199 -0.175685 -0.980736 -0.00763023 -0.195188 -0.980904 0.0444846 -0.189339 -0.984414 -0.00738492 -0.175709 -0.984768 0.0180864 -0.17293 -0.980209 0.0111835 -0.197647 -0.977445 0.0202175 -0.21022 -0.977488 0.0355631 -0.207974 -0.975704 0.0639201 -0.209563 -0.978072 0.0340575 -0.205466 -0.985655 -0.00288084 -0.16875 -0.983066 0.0425204 -0.178252 -0.979733 -0.0119307 -0.199952 -0.99069 0.00367394 -0.136084 -0.990076 0.0176804 -0.139413 -0.98721 0.034284 -0.155697 -0.996445 0.0391161 -0.0746108 -0.995471 0.0520524 -0.0795464 -0.995174 0.0264545 -0.0944886 -0.994806 0.00923172 -0.101368 -0.994412 0.0192538 -0.103797 -0.991609 0.0447392 -0.121285 -0.999588 0.0191171 -0.0214295 -0.999849 0.00170334 -0.0173077 -0.994923 0.0849332 -0.0539804 -0.998808 0.0222706 -0.0434421 -0.997202 0.0392886 -0.063605 -0.996318 0.0827008 0.0226025 -0.998818 -0.0285888 0.0392992 -0.99909 0.0425285 0.00317425 -0.998127 0.0236839 0.056412 -0.996302 0.0250581 0.0821848 -0.996743 0.016027 0.0790321 -0.991416 0.0247646 0.128379 -0.992702 -0.0318295 0.116321 -0.960793 -0.037961 0.274658 -0.972377 0.00811272 0.233276 -0.981502 0.00362215 0.191416 -0.977429 -0.0509971 0.205017 -0.986122 0.0307506 0.163152 -0.96546 0.0296471 0.25886 -0.94338 -0.00697515 0.331642 -0.939901 0.0208996 0.340807 -0.912138 0.0133514 0.409667 -0.908539 0.0359839 0.416248 0.986739 0.00362636 0.162275 0.987217 0.001154 0.159379 0.98723 0.00091886 0.159298 0.986611 0.00967821 0.162801 0.986738 0 0.162323 0.985374 0 0.170404 0.985374 0 0.170404 0.982541 0 0.186048 0.982541 0 0.186048 0.979704 0 0.20045 0.979704 0 0.20045 0.977659 0 0.210196 0.977659 0 0.210196 0.982394 0 0.186822 0.982394 0 0.186822 0.991404 0 0.130835 0.991404 0 0.130835 0.998251 0 0.0591191 0.998251 0 0.0591191 0.999971 0 -0.00761246 0.999971 0 -0.00761246 0.996119 0 -0.0880156 0.996119 0 -0.0880156 0.983239 0 -0.182323 0.983239 0 -0.182323 0.955236 0 -0.295846 0.955236 0 -0.295846 0.982541 0 0.186048 0.982541 0 0.186048 0.979704 0 0.20045 0.979704 0 0.20045 0.977659 0 0.210196 0.977659 0 0.210196 0.982394 0 0.186822 0.982394 0 0.186822 0.991404 0 0.130835 0.991404 0 0.130835 0.998251 0 0.0591191 0.998251 0 0.0591191 0.999971 0 -0.00761246 0.999971 0 -0.00761246 0.996119 0 -0.0880156 0.996119 0 -0.0880156 0.983239 0 -0.182323 0.983239 0 -0.182323 0.955236 0 -0.295846 0.955236 0 -0.295846 0.7224 0.0285778 -0.690884 0.721227 0.0209293 -0.692383 0.747102 0.195167 -0.635412 0.753216 0 -0.657773 0.851604 0 -0.524186 0.851604 0 -0.524186 0.899051 0 -0.437844 0.899051 0 -0.437844 0.00037063 -1.20474e-05 1 0.000371952 0 1 0.00037063 1.20474e-05 1 -0.987244 -0.0174664 -0.158257 -0.986706 -0.017512 -0.161572 -0.986764 -0.0140296 -0.161552 -0.987252 -0.0174989 -0.1582 -0.987245 -0.0174085 -0.158253 -0.986007 -0.01826 -0.165703 -0.986503 -0.0196508 -0.16256 -0.986696 -0.0161426 -0.161772 -0.986742 -0.0164609 -0.161459 -0.987202 -0.0175861 -0.158503 -0.987272 0.0175001 -0.158077 -0.987238 0.0174206 -0.158299 -0.987274 0.0175222 -0.158063 -0.987208 0.0173491 -0.15849 -0.987159 0.017176 -0.158814 -0.986556 0.0140608 -0.162819 -0.986742 0.0152802 -0.161578 -0.986503 0.0196508 -0.16256 -0.986007 0.01826 -0.165703 -0.869362 0.0349975 0.492935 -0.863616 0.0156169 0.503908 -0.835623 0.0534353 0.546698 -0.805845 0.0331435 0.591198 -0.707977 0.0267681 0.705729 -0.707841 0.0275505 0.705834 -0.80469 0.0291589 0.592978 -0.769936 0.0621611 0.635086 -0.759811 0.0786442 0.645369 -0.73983 0.0171329 0.672576 -0.733036 0.0317864 0.679447 -0.714517 0.0524696 0.697648 -0.710759 0.0606115 0.70082 -0.712093 0.0564089 0.699816 -0.71635 0.0361652 0.696804 -0.702444 0.0313727 0.711047 -0.704926 0.0308756 0.708609 0.716691 0.00753145 -0.69735 0.742053 -0.171524 -0.648025 0.715045 -0.00824619 -0.699029 0.714438 -0.00460333 -0.699684 0.72278 -0.0130697 -0.690954 0.748992 -0.182261 -0.637019 0.757366 0 -0.652991 0.851604 0 -0.524186 0.851604 0 -0.524186 0.899051 0 -0.437844 0.899051 0 -0.437844 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.153519 -0.987677 -0.0304305 0.11287 -0.9877 -0.108209 0.120151 -0.986099 -0.114775 0.327111 -0.891067 -0.31464 0.357423 -0.869051 -0.342052 0.508796 -0.70721 -0.490898 0.645407 -0.454257 -0.614085 0.578094 -0.59359 -0.559873 0.71167 -0.156386 -0.684887 0.703278 -0.209917 -0.679216 0.149163 -0.98852 0.0240669 0.154397 -0.987688 0.0251629 0.154354 -0.987688 0.0254299 0.154354 -0.987688 0.02543 0.154177 -0.987688 0.0264934 0.154177 -0.987688 0.0264934 0.153817 -0.987687 0.0285296 0.153815 -0.987688 0.0285292 0.153195 -0.987687 0.0317199 0.153191 -0.987687 0.0317191 0.153034 -0.987688 0.0324441 0.153042 -0.987687 0.0324456 0.153758 -0.987688 0.0288237 0.153771 -0.987686 0.0288263 0.154566 -0.987686 0.0242068 0.154576 -0.987684 0.0242085 0.155365 -0.987684 0.018509 0.155342 -0.987687 0.018506 0.156024 -0.987685 0.0116073 0.155955 -0.987696 0.0116016 0.156394 -0.987691 0.00253837 0.156448 -0.987683 0.0025397 0.156293 -0.987692 -0.00605101 0.156342 -0.987684 -0.00605207 0.155927 -0.987683 -0.0129852 0.155931 -0.987683 -0.0129855 0.155059 -0.987681 -0.0210428 0.150971 -0.987674 -0.0413289 0.150993 -0.98767 -0.0413345 0.146999 -0.987666 -0.0539107 0.146986 -0.987669 -0.0539061 0.140935 -0.987664 -0.0682379 0.140977 -0.987657 -0.0682573 0.132155 -0.987651 -0.0841483 0.132225 -0.987638 -0.0841914 0.120953 -0.987646 -0.0996251 0.42435 -0.902924 0.0682342 0.448058 -0.891006 0.0731579 0.447953 -0.891006 0.0738007 0.447951 -0.891007 0.0738002 0.447434 -0.891006 0.0768862 0.447437 -0.891004 0.0768868 0.446391 -0.890999 0.0827955 0.446392 -0.890999 0.0827957 0.444589 -0.890992 0.0920548 0.444574 -0.891 0.0920516 0.444122 -0.891005 0.0941561 0.444133 -0.890999 0.0941586 0.446217 -0.891007 0.0836488 0.446254 -0.890988 0.0836562 0.448561 -0.890987 0.0702499 0.448578 -0.890978 0.0702529 0.450868 -0.890973 0.0537123 0.450818 -0.890999 0.0537059 0.45279 -0.890981 0.0336833 0.452622 -0.891066 0.0336693 0.453884 -0.89103 0.0073681 0.454013 -0.890965 0.00737139 0.453594 -0.891036 -0.0175589 0.45371 -0.890976 -0.0175612 0.452502 -0.890967 -0.037683 0.38358 -0.890628 -0.24423 0.383409 -0.89073 -0.244127 0.409026 -0.890775 -0.198037 0.408955 -0.890814 -0.198005 0.426522 -0.890848 -0.156424 0.426549 -0.890833 -0.156434 0.438149 -0.890864 -0.119942 0.438081 -0.8909 -0.119925 0.445486 -0.890923 -0.0883032 0.445427 -0.890954 -0.0882926 0.449937 -0.89097 -0.0610619 0.668163 -0.736297 0.106893 0.697956 -0.707108 0.113385 0.697701 -0.707107 0.114947 0.697708 -0.7071 0.114948 0.696902 -0.707097 0.119754 0.696894 -0.707106 0.119753 0.695259 -0.707097 0.128955 0.695258 -0.707098 0.128955 0.692441 -0.707085 0.143374 0.692436 -0.70709 0.143373 0.691738 -0.707101 0.146652 0.691757 -0.707081 0.146656 0.69501 -0.707097 0.130289 0.695033 -0.707073 0.130293 0.698625 -0.707072 0.109413 0.698652 -0.707045 0.109418 0.702211 -0.707038 0.0836543 0.702155 -0.707094 0.083647 0.705206 -0.707059 0.0524583 0.705045 -0.707221 0.0524443 0.706969 -0.707152 0.0114784 0.707093 -0.707027 0.0114819 0.706522 -0.707162 -0.0273465 0.597058 -0.706405 -0.38015 0.596926 -0.70656 -0.38007 0.636848 -0.706648 -0.308339 0.636788 -0.706714 -0.308312 0.664172 -0.706784 -0.243582 0.664211 -0.706742 -0.243596 0.682302 -0.706809 -0.186776 0.682214 -0.706899 -0.186754 0.693771 -0.706945 -0.137516 0.69372 -0.706996 -0.137507 0.700759 -0.70703 -0.0951024 0.700795 -0.706995 -0.0951063 0.704756 -0.707018 -0.0586892 0.876662 -0.460174 0.140368 0.879749 -0.453987 0.141201 0.879157 -0.453986 0.144842 0.879154 -0.453992 0.144841 0.878136 -0.45399 0.150897 0.878139 -0.453985 0.150898 0.876072 -0.453975 0.162492 0.982559 -0.018751 0.185003 0.41033 -0.907971 0.0849613 0.872496 -0.45398 0.180702 0.871633 -0.453991 0.184791 0.871635 -0.453987 0.184791 0.875746 -0.454001 0.16417 0.87577 -0.453952 0.164176 0.880296 -0.453952 0.137866 0.880305 -0.453934 0.137867 0.884784 -0.453925 0.105403 0.884759 -0.453974 0.1054 0.888578 -0.453939 0.0660963 0.888496 -0.454101 0.0660887 0.890867 -0.454034 0.014466 0.751905 -0.453267 -0.478736 0.751829 -0.453438 -0.478693 0.802169 -0.453527 -0.38838 0.802123 -0.453625 -0.38836 0.836667 -0.453689 -0.306845 0.836685 -0.453652 -0.306851 0.859525 -0.453713 -0.235289 0.859503 -0.453757 -0.235284 0.874093 -0.453809 -0.173257 0.87405 -0.453895 -0.17325 0.882946 -0.453925 -0.119829 0.882973 -0.45387 -0.119831 0.887981 -0.453896 -0.0739471 0.887971 -0.453915 -0.0739467 0.89037 -0.453932 -0.034457 0.985225 -0.156502 0.069555 0.97217 0.222837 0.0723126 0.875481 -0.472495 0.101393 0.980757 -0.156413 0.116836 0.977226 -0.156437 0.14338 0.945578 0.289743 0.14809 0.67947 -0.723556 0.121602 0.97078 -0.156421 0.181986 0.967929 -0.156425 0.196581 0.961549 0.184031 0.203854 0.978012 -0.00775443 0.208404 0.77821 -0.606789 0.161853 0.963251 0.194999 0.184722 0.970773 -0.156425 0.182019 0.972802 -0.156433 0.170834 0.961199 -0.220941 0.16517 0.986052 0.0110179 0.166071 0.974552 -0.156429 0.160558 0.975098 -0.15643 0.157206 0.977125 -0.14217 0.15816 0.986931 -0.156531 0.0382885 0.818362 0.574549 0.0132897 0.890931 -0.453908 0.0144682 0.890311 -0.454047 -0.0344569 0.706636 -0.707049 -0.0273483 0.704744 -0.70703 -0.0586885 0.452514 -0.89096 -0.0376838 0.449979 -0.890949 -0.0610668 0.155046 -0.987683 -0.0210413 0.153496 -0.987681 -0.0304264 0.987669 -0.156442 0.0060686 0.987193 -0.156474 -0.0310643 0.990891 0.12909 -0.0383472 0.986342 -0.156439 -0.0515418 0.984286 -0.156402 -0.081967 0.756358 -0.650208 -0.0717846 0.960536 0.245716 -0.130359 0.976905 -0.156449 -0.145536 0.968846 -0.156392 -0.192038 0.926016 -0.328082 -0.1867 0.964087 0.0297642 -0.263912 0.951673 -0.156368 -0.264325 0.933543 -0.156425 -0.322534 0.857486 0.407209 -0.31448 0.91771 -0.156489 -0.365129 0.888991 -0.156327 -0.430415 0.893967 -0.119085 -0.43202 0.827074 -0.196581 -0.526597 0.833631 -0.156073 -0.529811 0.785568 -0.156357 -0.598694 0.120804 -0.987676 -0.0995072 0.350891 -0.890694 -0.289032 0.350578 -0.890897 -0.288786 0.54622 -0.706536 -0.449945 0.545934 -0.706899 -0.449722 0.687947 -0.4534 -0.566708 0.687755 -0.45387 -0.566564 0.704389 0.408812 -0.580267 0.750993 -0.156365 -0.641529 0.987252 -0.00046032 0.159165 0.718253 0.00282952 -0.695776 0.718595 0 -0.695429 0.719016 -0.00436361 -0.69498 0.719255 -0.011756 -0.694647 0.987252 0.000310311 0.159165 0.98726 4.49739e-05 0.159117 0.987261 0 0.159106 0.98727 -0.000183318 0.159055 0.987256 0 0.159143 0.986112 0 0.166081 0.986112 0 0.166081 0.984928 0 0.172964 0.984928 0 0.172964 0.982104 0 0.188338 0.982104 0 0.188338 0.978042 0 0.20841 0.719266 0.0103755 -0.694657 0.718716 0 -0.695304 0.760346 0 -0.649519 0.760346 0 -0.649519 0.795351 0 -0.60615 0.795351 0 -0.60615 0.843974 0 -0.536385 0.843974 0 -0.536385 0.900374 0 -0.435117 0.900374 0 -0.435117 0.929158 0 -0.369684 0.929158 0 -0.369684 0.945179 0 -0.326554 0.945179 0 -0.326554 0.963525 0 -0.267617 0.963525 0 -0.267617 0.980275 0 -0.19764 0.980275 0 -0.19764 0.989084 0 -0.14735 0.989084 0 -0.14735 0.995526 0 -0.0944836 0.995526 0 -0.0944836 0.998637 0 -0.0521843 0.998637 0 -0.0521843 0.999505 0 -0.0314517 0.999505 0 -0.0314517 0.999981 0 0.00614425 0.999981 0 0.00614425 0.999248 0 0.0387664 0.999248 0 0.0387664 0.997517 0 0.0704227 0.997517 0 0.0704227 0.99336 0 0.115046 0.99336 0 0.115046 0.989407 0 0.145167 0.989407 0 0.145167 0.98436 0 0.176167 0.98436 0 0.176167 0.979993 0 0.199032 0.979993 0 0.199032 0.978042 0 0.20841 0.586227 0.575641 -0.570066 0.659735 0.401612 -0.635183 0.712918 0.127475 -0.689564 0.970639 0.182679 0.156487 0.97217 -0.222838 0.0723126 0.875481 0.472495 0.101393 0.980757 0.156412 0.116836 0.977226 0.156437 0.14338 0.945578 -0.289743 0.14809 0.67947 0.723557 0.121602 0.97078 0.156421 0.181986 0.967929 0.156425 0.196581 0.961549 -0.184031 0.203854 0.978012 0.00775621 0.208404 0.77821 0.606789 0.161853 0.963251 -0.194999 0.184722 0.970773 0.156425 0.182019 0.972802 0.156433 0.170834 0.961199 0.220941 0.16517 0.986052 -0.0110173 0.166071 0.974552 0.156429 0.160558 0.818362 -0.574549 0.0132897 0.986931 0.156531 0.0382885 0.985225 0.156502 0.069555 0.964087 -0.0297636 -0.263912 0.926016 0.328082 -0.1867 0.968846 0.156392 -0.192038 0.976905 0.156449 -0.145536 0.960536 -0.245716 -0.130359 0.756358 0.650208 -0.0717846 0.984286 0.156402 -0.081967 0.986342 0.156439 -0.0515418 0.990891 -0.12909 -0.0383472 0.987193 0.156474 -0.0310643 0.987669 0.156442 0.0060686 0.857486 -0.407209 -0.31448 0.933543 0.156425 -0.322534 0.951673 0.156367 -0.264325 0.710455 0.156378 -0.686148 0.750993 0.156365 -0.641529 0.704389 -0.408812 -0.580267 0.785568 0.156357 -0.598694 0.833195 0.156081 -0.530494 0.827595 0.196056 -0.525975 0.893598 0.119584 -0.432646 0.889304 0.156332 -0.429767 0.91771 0.156489 -0.365129 0.879157 0.453986 0.144842 0.879154 0.453992 0.144842 0.878136 0.45399 0.150897 0.878139 0.453985 0.150898 0.876066 0.453975 0.162528 0.940709 -0.290901 0.17448 0.287956 0.955612 0.0623475 0.872505 0.45398 0.180657 0.871633 0.453991 0.184791 0.871635 0.453987 0.184791 0.875746 0.454001 0.164171 0.87577 0.453952 0.164175 0.880296 0.453952 0.137866 0.880305 0.453934 0.137867 0.884784 0.453925 0.105403 0.884759 0.453974 0.1054 0.888578 0.453939 0.0660948 0.888496 0.454101 0.0660902 0.890867 0.454034 0.0144672 0.890931 0.453908 0.014467 0.890311 0.454047 -0.0344547 0.89037 0.453932 -0.0344592 0.887971 0.453915 -0.0739463 0.887981 0.453896 -0.0739475 0.882973 0.45387 -0.119832 0.882946 0.453925 -0.119828 0.87405 0.453895 -0.173249 0.874093 0.453809 -0.173259 0.859503 0.453757 -0.235283 0.859525 0.453713 -0.23529 0.836685 0.453652 -0.306852 0.836667 0.453689 -0.306844 0.802124 0.453625 -0.388358 0.802168 0.453527 -0.388381 0.751831 0.453438 -0.47869 0.751903 0.453267 -0.47874 0.68794 0.4534 -0.566716 0.687762 0.45387 -0.566556 0.64162 0.454203 -0.61808 0.697701 0.707107 0.114947 0.697708 0.7071 0.114948 0.696902 0.707097 0.119754 0.696894 0.707106 0.119753 0.695259 0.707097 0.128955 0.695258 0.707098 0.128955 0.692441 0.707085 0.143374 0.692436 0.70709 0.143373 0.691738 0.707101 0.146652 0.691757 0.707081 0.146656 0.69501 0.707097 0.130289 0.695033 0.707073 0.130293 0.698625 0.707072 0.109414 0.698652 0.707045 0.109418 0.702211 0.707037 0.0836536 0.702155 0.707094 0.0836476 0.705206 0.707059 0.0524563 0.705045 0.707221 0.0524462 0.706969 0.707152 0.0114798 0.707093 0.707027 0.0114804 0.706522 0.707162 -0.0273439 0.706636 0.707049 -0.0273509 0.704744 0.70703 -0.0586882 0.704756 0.707018 -0.0586895 0.700795 0.706995 -0.0951072 0.700759 0.70703 -0.0951015 0.693721 0.706996 -0.137506 0.693771 0.706945 -0.137517 0.682215 0.706899 -0.186752 0.682301 0.706809 -0.186778 0.664211 0.706742 -0.243597 0.664172 0.706784 -0.243581 0.636789 0.706714 -0.308311 0.636847 0.706648 -0.308341 0.596928 0.70656 -0.380066 0.597056 0.706405 -0.380153 0.546214 0.706536 -0.449953 0.545941 0.706899 -0.449715 0.509128 0.707216 -0.490544 0.444399 0.789358 -0.423584 0.975316 0.156429 0.155846 0.844592 0.517386 0.137755 0.880078 0.453984 0.139144 0.596649 0.796298 0.0995966 0.699141 0.707088 0.105963 0.447906 0.891006 0.0740875 0.447953 0.891006 0.0738006 0.447951 0.891007 0.0738003 0.447434 0.891006 0.0768862 0.447437 0.891004 0.0768867 0.446391 0.890999 0.0827955 0.446392 0.890999 0.0827957 0.444589 0.890992 0.0920547 0.444574 0.891 0.0920517 0.444122 0.891005 0.0941562 0.444133 0.890999 0.0941586 0.446217 0.891007 0.0836492 0.446254 0.890988 0.0836558 0.448561 0.890987 0.0702501 0.448578 0.890978 0.0702527 0.450868 0.890973 0.0537118 0.450818 0.890999 0.0537064 0.45279 0.890981 0.0336817 0.452622 0.891066 0.0336708 0.453884 0.89103 0.00736929 0.454013 0.890965 0.0073702 0.453594 0.891036 -0.0175567 0.45371 0.890976 -0.0175634 0.452502 0.890967 -0.0376828 0.452515 0.89096 -0.037684 0.449979 0.890949 -0.0610676 0.449938 0.89097 -0.0610611 0.445428 0.890954 -0.0882915 0.445486 0.890923 -0.0883043 0.438081 0.8909 -0.119923 0.438148 0.890865 -0.119943 0.426549 0.890833 -0.156434 0.426522 0.890848 -0.156424 0.408955 0.890814 -0.198003 0.409025 0.890775 -0.198039 0.383412 0.89073 -0.244123 0.383577 0.890628 -0.244234 0.350885 0.890694 -0.289039 0.350584 0.890897 -0.288779 0.326589 0.891058 -0.315206 0.149703 0.978259 -0.143521 0.114273 0.987706 -0.106672 0.120806 0.987676 -0.0995043 0.120951 0.987646 -0.0996282 0.132224 0.987638 -0.0841927 0.132155 0.987651 -0.0841468 0.140977 0.987657 -0.0682581 0.140935 0.987664 -0.0682371 0.146986 0.987669 -0.0539058 0.146999 0.987666 -0.0539109 0.150993 0.98767 -0.0413349 0.150971 0.987674 -0.0413285 0.153519 0.987677 -0.0304309 0.153496 0.987681 -0.030426 0.155046 0.987683 -0.0210411 0.155059 0.987681 -0.0210431 0.155931 0.987683 -0.0129855 0.155927 0.987683 -0.0129851 0.156342 0.987684 -0.00605288 0.156293 0.987692 -0.0060502 0.156448 0.987683 0.00253925 0.156394 0.987691 0.00253882 0.155955 0.987696 0.0116022 0.156024 0.987685 0.0116067 0.155342 0.987687 0.0185062 0.155365 0.987684 0.0185088 0.154576 0.987684 0.0242084 0.154566 0.987686 0.0242069 0.153771 0.987686 0.0288262 0.153758 0.987688 0.0288239 0.153042 0.987687 0.0324456 0.153034 0.987688 0.0324441 0.153191 0.987687 0.0317191 0.153195 0.987687 0.0317199 0.153815 0.987688 0.0285293 0.153817 0.987687 0.0285296 0.154177 0.987688 0.0264934 0.154177 0.987688 0.0264934 0.154354 0.987688 0.02543 0.154354 0.987688 0.0254299 0.154437 0.987688 0.0249178 0.217901 0.975446 0.0319872 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.987305 0.000192363 0.158839 0.986721 -0.00704805 0.162272 0.987317 -0.000338684 0.158761 0.987329 -0.00015164 0.158689 0.987226 -0.000518211 0.159327 0.986617 -0.00903109 0.162802 0.986707 0 0.16251 0.985374 0 0.170404 0.985374 0 0.170404 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.26344e-05 1 -1.4683e-05 1.56901e-05 1 -7.64117e-06 1.48062e-05 1 -6.27499e-06 -8.2175e-07 1 5.47486e-06 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.000211436 1 3.31239e-07 2.28654e-05 1 3.77303e-06 2.28631e-05 1 3.95378e-06 9.09634e-06 1 -6.09978e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1.00137e-05 -1 1.24797e-06 1.5799e-05 -1 -7.69423e-06 1.27222e-05 -1 -1.4785e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1.40728e-05 -1 1.02114e-06 2.29803e-05 -1 3.97406e-06 2.34306e-05 -1 -3.06275e-05 0.000211445 -1 3.48906e-05 0.000273869 0.674315 0.738444 -0.0109568 0.628039 0.778104 -0.0239611 0.593978 0.804125 -0.00471324 0.651285 0.758819 0.000268149 0.674327 0.738433 0.000243156 0.781084 0.624426 -0.0133002 0.744647 0.667326 0.0287714 0.919074 0.393033 -0.0274179 0.872884 0.487157 0.020774 0.992635 0.119352 0.000247645 0.985436 0.170046 -0.0566002 0.537267 0.841511 0.0621132 0.659451 0.749177 -0.0493582 0.450004 0.891661 -0.02604 0.482562 0.875475 0.026445 0.250837 0.967668 -0.0259822 0.167625 0.985508 0.000370272 0.0439707 0.999033 0.00026136 -0.709491 0.704715 -0.016723 -0.671616 0.74071 -0.0427116 -0.626791 0.778016 -0.014876 -0.658307 0.752603 -0.0103577 -0.675161 0.737598 0.0235236 -0.869811 0.492823 -0.0487818 -0.791583 0.609111 0.0151057 -0.929412 0.368734 -0.0151932 -0.985725 0.167679 0.000234197 -0.994637 0.103426 0.000365484 -0.166076 0.986113 0.051593 -0.101277 0.99352 -0.033 -0.370288 0.928331 -0.0326231 -0.369604 0.928617 -0.00446207 -0.451535 0.892242 0.0020991 -0.524636 0.851324 -0.00103802 0.633847 -0.773458 -0.000285934 0.673924 -0.738801 -0.00294513 0.606719 -0.794911 -0.0117344 0.550503 -0.834751 -0.0109165 0.55285 -0.833209 0.000627636 0.670849 -0.741594 -0.00644905 0.794489 -0.607244 -0.00621951 0.795063 -0.606496 0.00723727 0.949991 -0.312194 -0.0115622 0.974736 -0.22306 -1.67978e-05 0.998979 -0.0451705 0.000168961 0.45184 -0.892099 -0.00141127 0.331999 -0.943279 -0.00872667 0.301554 -0.953409 0.00778237 0.125939 -0.992007 -0.000364376 0.087626 -0.996153 -5.80049e-05 -0.98776 -0.15598 0.00734762 -0.980142 -0.198163 -0.00829518 -0.8714 -0.490502 -0.00725367 -0.868672 -0.495334 -0.0364131 -0.576157 -0.816528 -0.019865 -0.611379 -0.791088 -0.00756358 -0.657992 -0.752987 0.00317703 -0.710358 -0.703833 -0.000270033 -0.716359 -0.697732 -0.000362412 -0.133188 -0.991091 -0.0151998 -0.0885902 -0.995952 0.0178551 -0.373925 -0.927287 -0.0197736 -0.299102 -0.954016 0.0227836 -0.616202 -0.787259 -0.0945577 -0.480911 -0.871655 -0.0542464 -0.540121 -0.839837 0.920725 0 -0.390211 0.920725 0 -0.390211 0.995581 0 0.0939077 0.995581 0 0.0939077 0.978278 0 0.207297 0.978278 0 0.207297 0.984343 0 0.176264 0.984343 0 0.176264 0.920725 0 -0.390211 0.920725 0 -0.390211 0.995581 0 0.0939077 0.995581 0 0.0939077 0.978278 0 0.207297 0.978278 0 0.207297 0.984343 0 0.176264 0.984343 0 0.176264 + + + + + + + + + + + + + + +

18 0 212 0 213 0 29 1 1626 1 16 1 18 2 213 2 1694 2 1679 3 0 3 1 3 1700 4 2 4 204 4 75 5 9 5 3 5 39 6 132 6 24 6 1 7 0 7 103 7 75 8 3 8 98 8 98 9 3 9 1673 9 98 10 1673 10 5 10 5 11 1673 11 4 11 5 12 4 12 6 12 6 13 4 13 7 13 6 14 7 14 8 14 9 15 75 15 1682 15 1682 16 75 16 10 16 1682 17 10 17 11 17 11 18 10 18 12 18 11 19 12 19 14 19 0 20 13 20 103 20 103 21 13 21 14 21 103 22 14 22 15 22 15 23 14 23 12 23 16 24 1626 24 25 24 2 25 1700 25 205 25 205 26 1700 26 1699 26 205 27 1699 27 17 27 17 28 1699 28 1709 28 17 29 1709 29 52 29 18 30 1707 30 212 30 212 31 1707 31 19 31 212 32 19 32 204 32 204 33 19 33 1704 33 204 34 1704 34 1700 34 213 35 77 35 1694 35 1694 36 77 36 88 36 1694 37 88 37 20 37 20 38 88 38 21 38 20 39 21 39 22 39 22 40 21 40 92 40 22 41 92 41 8 41 8 42 92 42 23 42 8 43 23 43 6 43 24 44 132 44 1620 44 1620 45 132 45 27 45 1620 46 27 46 1625 46 1626 47 26 47 25 47 25 48 26 48 1625 48 25 49 1625 49 131 49 131 50 1625 50 27 50 1679 51 1 51 28 51 28 52 1 52 106 52 28 53 106 53 33 53 29 54 16 54 30 54 30 55 16 55 140 55 30 56 140 56 31 56 31 57 140 57 32 57 31 58 32 58 1642 58 1642 59 32 59 150 59 1642 60 150 60 1672 60 1672 61 150 61 44 61 1672 62 44 62 45 62 106 63 105 63 33 63 33 64 105 64 113 64 33 65 113 65 34 65 34 66 113 66 35 66 34 67 35 67 36 67 36 68 35 68 38 68 36 69 38 69 37 69 37 70 38 70 122 70 37 71 122 71 120 71 24 72 1633 72 39 72 39 73 1633 73 1638 73 39 74 1638 74 40 74 40 75 1638 75 41 75 40 76 41 76 42 76 42 77 41 77 43 77 42 78 43 78 120 78 120 79 43 79 1635 79 120 80 1635 80 37 80 44 81 149 81 45 81 45 82 149 82 148 82 45 83 148 83 46 83 46 84 148 84 47 84 46 85 47 85 1650 85 1650 86 47 86 152 86 1650 87 152 87 48 87 48 88 152 88 154 88 48 89 154 89 49 89 49 90 154 90 50 90 49 91 50 91 1651 91 1651 92 50 92 161 92 1651 93 161 93 51 93 1709 94 1698 94 52 94 52 95 1698 95 53 95 52 96 53 96 55 96 55 97 53 97 54 97 55 98 54 98 56 98 56 99 54 99 57 99 56 100 57 100 192 100 192 101 57 101 58 101 192 102 58 102 1718 102 1656 103 66 103 67 103 161 104 160 104 51 104 51 105 160 105 159 105 51 106 159 106 1662 106 1662 107 159 107 59 107 1662 108 59 108 60 108 60 109 59 109 157 109 60 110 157 110 61 110 61 111 157 111 63 111 61 112 63 112 62 112 62 113 63 113 64 113 62 114 64 114 1657 114 1657 115 64 115 65 115 1657 116 65 116 66 116 66 117 65 117 179 117 66 118 179 118 67 118 1656 119 67 119 69 119 69 120 67 120 68 120 69 121 68 121 1690 121 68 122 70 122 1690 122 1690 123 70 123 71 123 1690 124 71 124 1722 124 1722 125 71 125 72 125 1722 126 72 126 1716 126 1716 127 72 127 73 127 1716 128 73 128 1718 128 1718 129 73 129 74 129 1718 130 74 130 192 130 15 131 12 131 84 131 10 132 75 132 97 132 98 133 5 133 76 133 88 134 77 134 91 134 219 135 218 135 78 135 101 136 220 136 102 136 81 137 111 137 82 137 82 138 111 138 79 138 82 139 79 139 80 139 218 140 81 140 78 140 78 141 81 141 82 141 78 142 82 142 83 142 83 143 82 143 80 143 83 144 80 144 84 144 84 145 80 145 104 145 79 146 85 146 80 146 80 147 85 147 86 147 80 148 86 148 104 148 104 149 86 149 87 149 104 150 87 150 107 150 88 151 91 151 21 151 223 152 89 152 216 152 216 153 89 153 93 153 216 154 93 154 90 154 90 155 93 155 94 155 90 156 94 156 91 156 91 157 94 157 95 157 91 158 95 158 21 158 6 159 23 159 95 159 95 160 23 160 92 160 95 161 92 161 21 161 89 162 222 162 93 162 93 163 222 163 100 163 93 164 100 164 94 164 94 165 100 165 96 165 94 166 96 166 95 166 95 167 96 167 76 167 95 168 76 168 6 168 6 169 76 169 5 169 75 170 98 170 97 170 97 171 98 171 76 171 97 172 76 172 99 172 99 173 76 173 96 173 99 174 96 174 102 174 102 175 96 175 100 175 102 176 100 176 101 176 101 177 100 177 222 177 12 178 10 178 84 178 84 179 10 179 97 179 84 180 97 180 83 180 83 181 97 181 99 181 83 182 99 182 78 182 78 183 99 183 102 183 78 184 102 184 219 184 219 185 102 185 220 185 15 186 84 186 103 186 103 187 84 187 104 187 103 188 104 188 1 188 1 189 104 189 107 189 1 190 107 190 106 190 105 191 106 191 119 191 119 192 106 192 107 192 119 193 107 193 118 193 118 194 107 194 87 194 118 195 87 195 108 195 108 196 87 196 86 196 108 197 86 197 109 197 109 198 86 198 85 198 109 199 85 199 116 199 116 200 85 200 79 200 116 201 79 201 110 201 110 202 79 202 111 202 132 203 39 203 112 203 40 204 42 204 127 204 113 205 105 205 119 205 227 206 225 206 128 206 114 207 115 207 126 207 110 208 230 208 116 208 116 209 230 209 117 209 116 210 117 210 109 210 109 211 117 211 124 211 109 212 124 212 108 212 108 213 124 213 118 213 118 214 124 214 121 214 118 215 121 215 119 215 119 216 121 216 35 216 119 217 35 217 113 217 120 218 122 218 121 218 121 219 122 219 38 219 121 220 38 220 35 220 230 221 228 221 117 221 117 222 228 222 123 222 117 223 123 223 124 223 124 224 123 224 125 224 124 225 125 225 121 225 121 226 125 226 127 226 121 227 127 227 120 227 120 228 127 228 42 228 228 229 114 229 123 229 123 230 114 230 126 230 123 231 126 231 125 231 125 232 126 232 129 232 125 233 129 233 127 233 127 234 129 234 112 234 127 235 112 235 40 235 40 236 112 236 39 236 115 237 227 237 126 237 126 238 227 238 128 238 126 239 128 239 129 239 129 240 128 240 135 240 129 241 135 241 112 241 112 242 135 242 130 242 112 243 130 243 132 243 25 244 131 244 130 244 130 245 131 245 27 245 130 246 27 246 132 246 225 247 133 247 128 247 128 248 133 248 134 248 128 249 134 249 135 249 135 250 134 250 136 250 135 251 136 251 130 251 130 252 136 252 138 252 130 253 138 253 25 253 25 254 138 254 16 254 133 255 144 255 134 255 134 256 144 256 137 256 134 257 137 257 136 257 136 258 137 258 143 258 136 259 143 259 138 259 138 260 143 260 139 260 138 261 139 261 16 261 16 262 139 262 140 262 32 263 140 263 139 263 32 264 139 264 141 264 141 265 139 265 143 265 141 266 143 266 142 266 142 267 143 267 137 267 142 268 137 268 162 268 162 269 137 269 144 269 162 270 144 270 146 270 142 271 162 271 145 271 162 272 146 272 147 272 172 273 141 273 142 273 172 274 151 274 148 274 148 275 149 275 172 275 172 276 149 276 44 276 172 277 44 277 141 277 141 278 44 278 150 278 141 279 150 279 32 279 154 280 152 280 151 280 151 281 152 281 47 281 151 282 47 282 148 282 151 283 153 283 154 283 154 284 153 284 155 284 154 285 155 285 50 285 63 286 157 286 156 286 156 287 157 287 59 287 156 288 59 288 158 288 158 289 59 289 159 289 158 290 159 290 176 290 176 291 159 291 160 291 176 292 160 292 155 292 155 293 160 293 161 293 155 294 161 294 50 294 162 295 147 295 145 295 145 296 147 296 163 296 145 297 163 297 173 297 173 298 163 298 164 298 173 299 164 299 165 299 165 300 164 300 166 300 165 301 166 301 174 301 174 302 166 302 167 302 174 303 167 303 175 303 175 304 167 304 168 304 175 305 168 305 169 305 169 306 168 306 170 306 169 307 170 307 171 307 171 308 170 308 232 308 171 309 232 309 177 309 142 310 145 310 172 310 172 311 145 311 173 311 172 312 173 312 151 312 151 313 173 313 165 313 151 314 165 314 153 314 153 315 165 315 174 315 153 316 174 316 155 316 155 317 174 317 175 317 155 318 175 318 176 318 176 319 175 319 169 319 176 320 169 320 158 320 158 321 169 321 171 321 158 322 171 322 156 322 156 323 171 323 177 323 156 324 177 324 178 324 67 325 179 325 178 325 178 326 179 326 65 326 178 327 65 327 156 327 156 328 65 328 64 328 156 329 64 329 63 329 180 330 236 330 181 330 181 331 236 331 186 331 181 332 186 332 182 332 182 333 186 333 184 333 182 334 184 334 183 334 232 335 180 335 177 335 177 336 180 336 181 336 177 337 181 337 178 337 178 338 181 338 182 338 178 339 182 339 67 339 67 340 182 340 183 340 67 341 183 341 68 341 70 342 68 342 183 342 70 343 183 343 189 343 189 344 183 344 184 344 189 345 184 345 185 345 185 346 184 346 186 346 185 347 186 347 187 347 187 348 186 348 236 348 187 349 236 349 190 349 17 350 52 350 203 350 55 351 56 351 197 351 71 352 70 352 189 352 240 353 239 353 201 353 198 354 188 354 199 354 71 355 189 355 72 355 190 356 193 356 187 356 187 357 193 357 194 357 187 358 194 358 185 358 185 359 194 359 191 359 185 360 191 360 189 360 189 361 191 361 196 361 189 362 196 362 72 362 192 363 74 363 196 363 196 364 74 364 73 364 196 365 73 365 72 365 193 366 241 366 194 366 194 367 241 367 200 367 194 368 200 368 191 368 191 369 200 369 195 369 191 370 195 370 196 370 196 371 195 371 197 371 196 372 197 372 192 372 192 373 197 373 56 373 241 374 198 374 200 374 200 375 198 375 199 375 200 376 199 376 195 376 195 377 199 377 202 377 195 378 202 378 197 378 197 379 202 379 203 379 197 380 203 380 55 380 55 381 203 381 52 381 188 382 240 382 199 382 199 383 240 383 201 383 199 384 201 384 202 384 202 385 201 385 207 385 202 386 207 386 203 386 203 387 207 387 208 387 203 388 208 388 17 388 204 389 2 389 208 389 208 390 2 390 205 390 208 391 205 391 17 391 239 392 238 392 201 392 201 393 238 393 210 393 201 394 210 394 207 394 207 395 210 395 206 395 207 396 206 396 208 396 208 397 206 397 209 397 208 398 209 398 204 398 204 399 209 399 212 399 238 400 242 400 210 400 210 401 242 401 211 401 210 402 211 402 206 402 206 403 211 403 215 403 206 404 215 404 209 404 209 405 215 405 214 405 209 406 214 406 212 406 212 407 214 407 213 407 77 408 213 408 214 408 77 409 214 409 91 409 91 410 214 410 215 410 91 411 215 411 90 411 90 412 215 412 211 412 90 413 211 413 216 413 216 414 211 414 242 414 216 415 242 415 223 415 223 416 4431 416 221 416 217 417 111 417 81 417 217 418 81 418 4428 418 4428 419 81 419 218 419 4428 420 218 420 4442 420 218 421 219 421 4442 421 4442 422 219 422 220 422 4442 423 220 423 4413 423 220 424 101 424 4413 424 4413 425 101 425 222 425 4413 426 222 426 221 426 221 427 222 427 89 427 221 428 89 428 223 428 110 429 111 429 4439 429 4439 430 111 430 217 430 110 431 4439 431 229 431 224 432 144 432 133 432 224 433 133 433 4425 433 4425 434 133 434 225 434 4425 435 225 435 226 435 225 436 227 436 226 436 226 437 227 437 115 437 226 438 115 438 4418 438 115 439 114 439 4418 439 4418 440 114 440 228 440 4418 441 228 441 229 441 229 442 228 442 230 442 229 443 230 443 110 443 146 444 144 444 4436 444 4436 445 144 445 224 445 231 446 236 446 180 446 231 447 180 447 4450 447 180 448 232 448 4450 448 4450 449 232 449 170 449 4450 450 170 450 233 450 170 451 168 451 233 451 233 452 168 452 167 452 233 453 167 453 234 453 167 454 166 454 234 454 234 455 166 455 164 455 234 456 164 456 235 456 146 457 4436 457 147 457 147 458 4436 458 235 458 147 459 235 459 163 459 163 460 235 460 164 460 190 461 236 461 4458 461 4458 462 236 462 231 462 190 463 4458 463 4453 463 237 464 242 464 238 464 237 465 238 465 4443 465 4443 466 238 466 239 466 4443 467 239 467 4445 467 239 468 240 468 4445 468 4445 469 240 469 188 469 4445 470 188 470 4434 470 188 471 198 471 4434 471 4434 472 198 472 241 472 4434 473 241 473 4453 473 4453 474 241 474 193 474 4453 475 193 475 190 475 223 476 242 476 4431 476 4431 477 242 477 237 477 1619 478 1644 478 244 478 1619 479 244 479 243 479 243 480 244 480 414 480 243 481 414 481 245 481 245 482 414 482 246 482 245 483 246 483 247 483 247 484 246 484 248 484 247 485 248 485 250 485 250 486 248 486 1506 486 250 487 1506 487 251 487 1619 488 243 488 275 488 243 489 245 489 249 489 245 490 247 490 258 490 247 491 250 491 253 491 250 492 251 492 252 492 250 493 252 493 253 493 253 494 252 494 1541 494 253 495 1541 495 259 495 259 496 1541 496 254 496 259 497 254 497 260 497 260 498 254 498 256 498 260 499 256 499 255 499 255 500 256 500 1551 500 255 501 1551 501 263 501 263 502 1551 502 257 502 263 503 257 503 264 503 264 504 257 504 1540 504 264 505 1540 505 266 505 247 506 253 506 258 506 258 507 253 507 259 507 258 508 259 508 267 508 267 509 259 509 260 509 267 510 260 510 261 510 261 511 260 511 255 511 261 512 255 512 262 512 262 513 255 513 263 513 262 514 263 514 270 514 270 515 263 515 264 515 270 516 264 516 265 516 265 517 264 517 266 517 265 518 266 518 288 518 245 519 258 519 249 519 249 520 258 520 267 520 249 521 267 521 273 521 273 522 267 522 261 522 273 523 261 523 268 523 268 524 261 524 262 524 268 525 262 525 269 525 269 526 262 526 270 526 269 527 270 527 271 527 271 528 270 528 265 528 271 529 265 529 272 529 272 530 265 530 288 530 272 531 288 531 287 531 243 532 249 532 275 532 275 533 249 533 273 533 275 534 273 534 276 534 276 535 273 535 268 535 276 536 268 536 277 536 277 537 268 537 269 537 277 538 269 538 274 538 274 539 269 539 271 539 274 540 271 540 280 540 280 541 271 541 272 541 280 542 272 542 282 542 282 543 272 543 287 543 282 544 287 544 286 544 1619 545 275 545 1630 545 1630 546 275 546 276 546 1630 547 276 547 1631 547 1631 548 276 548 277 548 1631 549 277 549 278 549 278 550 277 550 274 550 278 551 274 551 279 551 279 552 274 552 280 552 279 553 280 553 281 553 281 554 280 554 282 554 281 555 282 555 1622 555 1622 556 282 556 286 556 1622 557 286 557 283 557 284 558 283 558 286 558 284 559 286 559 285 559 285 560 286 560 287 560 285 561 287 561 305 561 305 562 287 562 288 562 305 563 288 563 289 563 289 564 288 564 266 564 289 565 266 565 290 565 290 566 266 566 1540 566 290 567 1540 567 291 567 284 568 285 568 292 568 285 569 305 569 306 569 305 570 289 570 299 570 289 571 290 571 293 571 290 572 291 572 1596 572 290 573 1596 573 293 573 293 574 1596 574 1597 574 293 575 1597 575 300 575 300 576 1597 576 294 576 300 577 294 577 301 577 301 578 294 578 295 578 301 579 295 579 296 579 296 580 295 580 1610 580 296 581 1610 581 297 581 297 582 1610 582 298 582 297 583 298 583 303 583 303 584 298 584 333 584 303 585 333 585 304 585 289 586 293 586 299 586 299 587 293 587 300 587 299 588 300 588 307 588 307 589 300 589 301 589 307 590 301 590 308 590 308 591 301 591 296 591 308 592 296 592 310 592 310 593 296 593 297 593 310 594 297 594 302 594 302 595 297 595 303 595 302 596 303 596 313 596 313 597 303 597 304 597 313 598 304 598 330 598 305 599 299 599 306 599 306 600 299 600 307 600 306 601 307 601 309 601 309 602 307 602 308 602 309 603 308 603 314 603 314 604 308 604 310 604 314 605 310 605 311 605 311 606 310 606 302 606 311 607 302 607 312 607 312 608 302 608 313 608 312 609 313 609 317 609 317 610 313 610 330 610 317 611 330 611 318 611 285 612 306 612 292 612 292 613 306 613 309 613 292 614 309 614 320 614 320 615 309 615 314 615 320 616 314 616 323 616 323 617 314 617 311 617 323 618 311 618 315 618 315 619 311 619 312 619 315 620 312 620 325 620 325 621 312 621 317 621 325 622 317 622 316 622 316 623 317 623 318 623 316 624 318 624 329 624 284 625 292 625 319 625 319 626 292 626 320 626 319 627 320 627 321 627 321 628 320 628 323 628 321 629 323 629 322 629 322 630 323 630 315 630 322 631 315 631 324 631 324 632 315 632 325 632 324 633 325 633 326 633 326 634 325 634 316 634 326 635 316 635 1676 635 1676 636 316 636 329 636 1676 637 329 637 327 637 1697 638 327 638 329 638 1697 639 329 639 328 639 328 640 329 640 318 640 328 641 318 641 335 641 335 642 318 642 330 642 335 643 330 643 331 643 331 644 330 644 304 644 331 645 304 645 332 645 332 646 304 646 333 646 332 647 333 647 334 647 1697 648 328 648 362 648 328 649 335 649 336 649 335 650 331 650 354 650 331 651 332 651 346 651 332 652 334 652 337 652 332 653 337 653 346 653 346 654 337 654 338 654 346 655 338 655 347 655 347 656 338 656 339 656 347 657 339 657 340 657 340 658 339 658 342 658 340 659 342 659 341 659 341 660 342 660 343 660 341 661 343 661 349 661 349 662 343 662 344 662 349 663 344 663 351 663 351 664 344 664 345 664 351 665 345 665 352 665 331 666 346 666 354 666 354 667 346 667 347 667 354 668 347 668 355 668 355 669 347 669 340 669 355 670 340 670 357 670 357 671 340 671 341 671 357 672 341 672 348 672 348 673 341 673 349 673 348 674 349 674 350 674 350 675 349 675 351 675 350 676 351 676 353 676 353 677 351 677 352 677 353 678 352 678 361 678 335 679 354 679 336 679 336 680 354 680 355 680 336 681 355 681 356 681 356 682 355 682 357 682 356 683 357 683 358 683 358 684 357 684 348 684 358 685 348 685 365 685 365 686 348 686 350 686 365 687 350 687 359 687 359 688 350 688 353 688 359 689 353 689 360 689 360 690 353 690 361 690 360 691 361 691 368 691 328 692 336 692 362 692 362 693 336 693 356 693 362 694 356 694 363 694 363 695 356 695 358 695 363 696 358 696 364 696 364 697 358 697 365 697 364 698 365 698 366 698 366 699 365 699 359 699 366 700 359 700 373 700 373 701 359 701 360 701 373 702 360 702 367 702 367 703 360 703 368 703 367 704 368 704 374 704 1697 705 362 705 369 705 369 706 362 706 363 706 369 707 363 707 370 707 370 708 363 708 364 708 370 709 364 709 1712 709 1712 710 364 710 366 710 1712 711 366 711 371 711 371 712 366 712 373 712 371 713 373 713 372 713 372 714 373 714 367 714 372 715 367 715 1701 715 1701 716 367 716 374 716 1701 717 374 717 375 717 376 718 375 718 374 718 376 719 374 719 377 719 377 720 374 720 368 720 377 721 368 721 378 721 378 722 368 722 361 722 378 723 361 723 386 723 386 724 361 724 352 724 386 725 352 725 380 725 380 726 352 726 345 726 380 727 345 727 1510 727 376 728 377 728 406 728 377 729 378 729 379 729 378 730 386 730 394 730 386 731 380 731 387 731 380 732 1510 732 381 732 380 733 381 733 387 733 387 734 381 734 382 734 387 735 382 735 388 735 388 736 382 736 383 736 388 737 383 737 390 737 390 738 383 738 384 738 390 739 384 739 385 739 385 740 384 740 1514 740 385 741 1514 741 392 741 392 742 1514 742 1515 742 392 743 1515 743 393 743 393 744 1515 744 1507 744 393 745 1507 745 416 745 386 746 387 746 394 746 394 747 387 747 388 747 394 748 388 748 389 748 389 749 388 749 390 749 389 750 390 750 391 750 391 751 390 751 385 751 391 752 385 752 397 752 397 753 385 753 392 753 397 754 392 754 398 754 398 755 392 755 393 755 398 756 393 756 400 756 400 757 393 757 416 757 400 758 416 758 415 758 378 759 394 759 379 759 379 760 394 760 389 760 379 761 389 761 395 761 395 762 389 762 391 762 395 763 391 763 402 763 402 764 391 764 397 764 402 765 397 765 396 765 396 766 397 766 398 766 396 767 398 767 399 767 399 768 398 768 400 768 399 769 400 769 401 769 401 770 400 770 415 770 401 771 415 771 405 771 377 772 379 772 406 772 406 773 379 773 395 773 406 774 395 774 407 774 407 775 395 775 402 775 407 776 402 776 408 776 408 777 402 777 396 777 408 778 396 778 403 778 403 779 396 779 399 779 403 780 399 780 404 780 404 781 399 781 401 781 404 782 401 782 412 782 412 783 401 783 405 783 412 784 405 784 413 784 376 785 406 785 1658 785 1658 786 406 786 407 786 1658 787 407 787 409 787 409 788 407 788 408 788 409 789 408 789 410 789 410 790 408 790 403 790 410 791 403 791 411 791 411 792 403 792 404 792 411 793 404 793 1667 793 1667 794 404 794 412 794 1667 795 412 795 1653 795 1653 796 412 796 413 796 1653 797 413 797 1645 797 1644 798 1645 798 413 798 1644 799 413 799 244 799 244 800 413 800 405 800 244 801 405 801 414 801 414 802 405 802 415 802 414 803 415 803 246 803 246 804 415 804 416 804 246 805 416 805 248 805 248 806 416 806 1507 806 248 807 1507 807 1506 807 916 808 417 808 560 808 903 809 559 809 558 809 919 810 918 810 538 810 900 811 511 811 510 811 925 812 512 812 492 812 418 813 898 813 419 813 923 814 465 814 466 814 895 815 896 815 463 815 904 816 444 816 905 816 905 817 444 817 445 817 905 818 445 818 909 818 909 819 445 819 446 819 909 820 446 820 910 820 910 821 446 821 420 821 910 822 420 822 911 822 911 823 420 823 421 823 911 824 421 824 422 824 422 825 421 825 423 825 422 826 423 826 424 826 424 827 423 827 425 827 424 828 425 828 426 828 426 829 425 829 452 829 426 830 452 830 428 830 428 831 452 831 427 831 428 832 427 832 429 832 429 833 427 833 453 833 429 834 453 834 430 834 430 835 453 835 454 835 430 836 454 836 912 836 912 837 454 837 431 837 912 838 431 838 432 838 432 839 431 839 433 839 432 840 433 840 434 840 434 841 433 841 455 841 434 842 455 842 435 842 435 843 455 843 456 843 435 844 456 844 906 844 906 845 456 845 436 845 906 846 436 846 437 846 437 847 436 847 458 847 437 848 458 848 907 848 907 849 458 849 438 849 907 850 438 850 908 850 908 851 438 851 439 851 908 852 439 852 440 852 440 853 439 853 441 853 440 854 441 854 913 854 913 855 441 855 442 855 913 856 442 856 914 856 914 857 442 857 462 857 914 858 462 858 915 858 915 859 462 859 463 859 915 860 463 860 443 860 443 861 463 861 896 861 444 862 923 862 445 862 445 863 923 863 466 863 445 864 466 864 446 864 446 865 466 865 468 865 446 866 468 866 420 866 420 867 468 867 447 867 420 868 447 868 421 868 421 869 447 869 448 869 421 870 448 870 423 870 423 871 448 871 449 871 423 872 449 872 425 872 425 873 449 873 450 873 425 874 450 874 452 874 452 875 450 875 451 875 452 876 451 876 427 876 427 877 451 877 474 877 427 878 474 878 453 878 453 879 474 879 476 879 453 880 476 880 454 880 454 881 476 881 478 881 454 882 478 882 431 882 431 883 478 883 479 883 431 884 479 884 433 884 433 885 479 885 480 885 433 886 480 886 455 886 455 887 480 887 481 887 455 888 481 888 456 888 456 889 481 889 482 889 456 890 482 890 436 890 436 891 482 891 457 891 436 892 457 892 458 892 458 893 457 893 459 893 458 894 459 894 438 894 438 895 459 895 485 895 438 896 485 896 439 896 439 897 485 897 487 897 439 898 487 898 441 898 441 899 487 899 460 899 441 900 460 900 442 900 442 901 460 901 461 901 442 902 461 902 462 902 462 903 461 903 489 903 462 904 489 904 463 904 463 905 489 905 464 905 463 906 464 906 895 906 895 907 464 907 491 907 465 908 924 908 466 908 466 909 924 909 467 909 466 910 467 910 468 910 468 911 467 911 469 911 468 912 469 912 447 912 447 913 469 913 470 913 447 914 470 914 448 914 448 915 470 915 471 915 448 916 471 916 449 916 449 917 471 917 495 917 449 918 495 918 450 918 450 919 495 919 472 919 450 920 472 920 451 920 451 921 472 921 473 921 451 922 473 922 474 922 474 923 473 923 475 923 474 924 475 924 476 924 476 925 475 925 477 925 476 926 477 926 478 926 478 927 477 927 496 927 478 928 496 928 479 928 479 929 496 929 497 929 479 930 497 930 480 930 480 931 497 931 499 931 480 932 499 932 481 932 481 933 499 933 501 933 481 934 501 934 482 934 482 935 501 935 483 935 482 936 483 936 457 936 457 937 483 937 484 937 457 938 484 938 459 938 459 939 484 939 504 939 459 940 504 940 485 940 485 941 504 941 486 941 485 942 486 942 487 942 487 943 486 943 488 943 487 944 488 944 460 944 460 945 488 945 506 945 460 946 506 946 461 946 461 947 506 947 490 947 461 948 490 948 489 948 489 949 490 949 509 949 489 950 509 950 464 950 464 951 509 951 419 951 464 952 419 952 491 952 491 953 419 953 898 953 924 954 925 954 467 954 467 955 925 955 492 955 467 956 492 956 469 956 469 957 492 957 493 957 469 958 493 958 470 958 470 959 493 959 494 959 470 960 494 960 471 960 471 961 494 961 515 961 471 962 515 962 495 962 495 963 515 963 516 963 495 964 516 964 472 964 472 965 516 965 518 965 472 966 518 966 473 966 473 967 518 967 519 967 473 968 519 968 475 968 475 969 519 969 521 969 475 970 521 970 477 970 477 971 521 971 522 971 477 972 522 972 496 972 496 973 522 973 523 973 496 974 523 974 497 974 497 975 523 975 498 975 497 976 498 976 499 976 499 977 498 977 500 977 499 978 500 978 501 978 501 979 500 979 502 979 501 980 502 980 483 980 483 981 502 981 503 981 483 982 503 982 484 982 484 983 503 983 529 983 484 984 529 984 504 984 504 985 529 985 530 985 504 986 530 986 486 986 486 987 530 987 505 987 486 988 505 988 488 988 488 989 505 989 531 989 488 990 531 990 506 990 506 991 531 991 507 991 506 992 507 992 490 992 490 993 507 993 508 993 490 994 508 994 509 994 509 995 508 995 533 995 509 996 533 996 419 996 419 997 533 997 510 997 419 998 510 998 418 998 418 999 510 999 511 999 512 1000 919 1000 492 1000 492 1001 919 1001 538 1001 492 1002 538 1002 493 1002 493 1003 538 1003 513 1003 493 1004 513 1004 494 1004 494 1005 513 1005 514 1005 494 1006 514 1006 515 1006 515 1007 514 1007 539 1007 515 1008 539 1008 516 1008 516 1009 539 1009 517 1009 516 1010 517 1010 518 1010 518 1011 517 1011 541 1011 518 1012 541 1012 519 1012 519 1013 541 1013 520 1013 519 1014 520 1014 521 1014 521 1015 520 1015 542 1015 521 1016 542 1016 522 1016 522 1017 542 1017 524 1017 522 1018 524 1018 523 1018 523 1019 524 1019 525 1019 523 1020 525 1020 498 1020 498 1021 525 1021 544 1021 498 1022 544 1022 500 1022 500 1023 544 1023 526 1023 500 1024 526 1024 502 1024 502 1025 526 1025 546 1025 502 1026 546 1026 503 1026 503 1027 546 1027 527 1027 503 1028 527 1028 529 1028 529 1029 527 1029 528 1029 529 1030 528 1030 530 1030 530 1031 528 1031 549 1031 530 1032 549 1032 505 1032 505 1033 549 1033 551 1033 505 1034 551 1034 531 1034 531 1035 551 1035 552 1035 531 1036 552 1036 507 1036 507 1037 552 1037 554 1037 507 1038 554 1038 508 1038 508 1039 554 1039 532 1039 508 1040 532 1040 533 1040 533 1041 532 1041 557 1041 533 1042 557 1042 510 1042 510 1043 557 1043 534 1043 510 1044 534 1044 900 1044 900 1045 534 1045 535 1045 918 1046 536 1046 538 1046 538 1047 536 1047 537 1047 538 1048 537 1048 513 1048 513 1049 537 1049 561 1049 513 1050 561 1050 514 1050 514 1051 561 1051 562 1051 514 1052 562 1052 539 1052 539 1053 562 1053 540 1053 539 1054 540 1054 517 1054 517 1055 540 1055 563 1055 517 1056 563 1056 541 1056 541 1057 563 1057 565 1057 541 1058 565 1058 520 1058 520 1059 565 1059 566 1059 520 1060 566 1060 542 1060 542 1061 566 1061 543 1061 542 1062 543 1062 524 1062 524 1063 543 1063 567 1063 524 1064 567 1064 525 1064 525 1065 567 1065 545 1065 525 1066 545 1066 544 1066 544 1067 545 1067 568 1067 544 1068 568 1068 526 1068 526 1069 568 1069 569 1069 526 1070 569 1070 546 1070 546 1071 569 1071 547 1071 546 1072 547 1072 527 1072 527 1073 547 1073 548 1073 527 1074 548 1074 528 1074 528 1075 548 1075 550 1075 528 1076 550 1076 549 1076 549 1077 550 1077 573 1077 549 1078 573 1078 551 1078 551 1079 573 1079 553 1079 551 1080 553 1080 552 1080 552 1081 553 1081 575 1081 552 1082 575 1082 554 1082 554 1083 575 1083 555 1083 554 1084 555 1084 532 1084 532 1085 555 1085 577 1085 532 1086 577 1086 557 1086 557 1087 577 1087 556 1087 557 1088 556 1088 534 1088 534 1089 556 1089 558 1089 534 1090 558 1090 535 1090 535 1091 558 1091 559 1091 536 1092 916 1092 537 1092 537 1093 916 1093 560 1093 537 1094 560 1094 561 1094 561 1095 560 1095 581 1095 561 1096 581 1096 562 1096 562 1097 581 1097 582 1097 562 1098 582 1098 540 1098 540 1099 582 1099 564 1099 540 1100 564 1100 563 1100 563 1101 564 1101 584 1101 563 1102 584 1102 565 1102 565 1103 584 1103 586 1103 565 1104 586 1104 566 1104 566 1105 586 1105 588 1105 566 1106 588 1106 543 1106 543 1107 588 1107 590 1107 543 1108 590 1108 567 1108 567 1109 590 1109 591 1109 567 1110 591 1110 545 1110 545 1111 591 1111 593 1111 545 1112 593 1112 568 1112 568 1113 593 1113 570 1113 568 1114 570 1114 569 1114 569 1115 570 1115 571 1115 569 1116 571 1116 547 1116 547 1117 571 1117 572 1117 547 1118 572 1118 548 1118 548 1119 572 1119 594 1119 548 1120 594 1120 550 1120 550 1121 594 1121 596 1121 550 1122 596 1122 573 1122 573 1123 596 1123 574 1123 573 1124 574 1124 553 1124 553 1125 574 1125 597 1125 553 1126 597 1126 575 1126 575 1127 597 1127 598 1127 575 1128 598 1128 555 1128 555 1129 598 1129 600 1129 555 1130 600 1130 577 1130 577 1131 600 1131 576 1131 577 1132 576 1132 556 1132 556 1133 576 1133 578 1133 556 1134 578 1134 558 1134 558 1135 578 1135 579 1135 558 1136 579 1136 903 1136 903 1137 579 1137 603 1137 417 1138 580 1138 560 1138 560 1139 580 1139 604 1139 560 1140 604 1140 581 1140 581 1141 604 1141 606 1141 581 1142 606 1142 582 1142 582 1143 606 1143 583 1143 582 1144 583 1144 564 1144 564 1145 583 1145 585 1145 564 1146 585 1146 584 1146 584 1147 585 1147 587 1147 584 1148 587 1148 586 1148 586 1149 587 1149 589 1149 586 1150 589 1150 588 1150 588 1151 589 1151 611 1151 588 1152 611 1152 590 1152 590 1153 611 1153 612 1153 590 1154 612 1154 591 1154 591 1155 612 1155 592 1155 591 1156 592 1156 593 1156 593 1157 592 1157 613 1157 593 1158 613 1158 570 1158 570 1159 613 1159 614 1159 570 1160 614 1160 571 1160 571 1161 614 1161 615 1161 571 1162 615 1162 572 1162 572 1163 615 1163 616 1163 572 1164 616 1164 594 1164 594 1165 616 1165 595 1165 594 1166 595 1166 596 1166 596 1167 595 1167 618 1167 596 1168 618 1168 574 1168 574 1169 618 1169 620 1169 574 1170 620 1170 597 1170 597 1171 620 1171 599 1171 597 1172 599 1172 598 1172 598 1173 599 1173 622 1173 598 1174 622 1174 600 1174 600 1175 622 1175 601 1175 600 1176 601 1176 576 1176 576 1177 601 1177 624 1177 576 1178 624 1178 578 1178 578 1179 624 1179 625 1179 578 1180 625 1180 579 1180 579 1181 625 1181 602 1181 579 1182 602 1182 603 1182 603 1183 602 1183 893 1183 580 1184 605 1184 604 1184 604 1185 605 1185 607 1185 604 1186 607 1186 606 1186 606 1187 607 1187 608 1187 606 1188 608 1188 583 1188 583 1189 608 1189 609 1189 583 1190 609 1190 585 1190 585 1191 609 1191 628 1191 585 1192 628 1192 587 1192 587 1193 628 1193 629 1193 587 1194 629 1194 589 1194 589 1195 629 1195 610 1195 589 1196 610 1196 611 1196 611 1197 610 1197 630 1197 611 1198 630 1198 612 1198 612 1199 630 1199 631 1199 612 1200 631 1200 592 1200 592 1201 631 1201 634 1201 592 1202 634 1202 613 1202 613 1203 634 1203 635 1203 613 1204 635 1204 614 1204 614 1205 635 1205 636 1205 614 1206 636 1206 615 1206 615 1207 636 1207 637 1207 615 1208 637 1208 616 1208 616 1209 637 1209 638 1209 616 1210 638 1210 595 1210 595 1211 638 1211 617 1211 595 1212 617 1212 618 1212 618 1213 617 1213 619 1213 618 1214 619 1214 620 1214 620 1215 619 1215 621 1215 620 1216 621 1216 599 1216 599 1217 621 1217 641 1217 599 1218 641 1218 622 1218 622 1219 641 1219 642 1219 622 1220 642 1220 601 1220 601 1221 642 1221 644 1221 601 1222 644 1222 624 1222 624 1223 644 1223 623 1223 624 1224 623 1224 625 1224 625 1225 623 1225 647 1225 625 1226 647 1226 602 1226 602 1227 647 1227 626 1227 602 1228 626 1228 893 1228 893 1229 626 1229 892 1229 605 1230 931 1230 607 1230 607 1231 931 1231 650 1231 607 1232 650 1232 608 1232 608 1233 650 1233 627 1233 608 1234 627 1234 609 1234 609 1235 627 1235 652 1235 609 1236 652 1236 628 1236 628 1237 652 1237 656 1237 628 1238 656 1238 629 1238 629 1239 656 1239 657 1239 629 1240 657 1240 610 1240 610 1241 657 1241 659 1241 610 1242 659 1242 630 1242 630 1243 659 1243 632 1243 630 1244 632 1244 631 1244 631 1245 632 1245 662 1245 631 1246 662 1246 634 1246 634 1247 662 1247 633 1247 634 1248 633 1248 635 1248 635 1249 633 1249 664 1249 635 1250 664 1250 636 1250 636 1251 664 1251 665 1251 636 1252 665 1252 637 1252 637 1253 665 1253 667 1253 637 1254 667 1254 638 1254 638 1255 667 1255 639 1255 638 1256 639 1256 617 1256 617 1257 639 1257 640 1257 617 1258 640 1258 619 1258 619 1259 640 1259 671 1259 619 1260 671 1260 621 1260 621 1261 671 1261 672 1261 621 1262 672 1262 641 1262 641 1263 672 1263 673 1263 641 1264 673 1264 642 1264 642 1265 673 1265 643 1265 642 1266 643 1266 644 1266 644 1267 643 1267 645 1267 644 1268 645 1268 623 1268 623 1269 645 1269 646 1269 623 1270 646 1270 647 1270 647 1271 646 1271 648 1271 647 1272 648 1272 626 1272 626 1273 648 1273 676 1273 626 1274 676 1274 892 1274 892 1275 676 1275 649 1275 931 1276 930 1276 650 1276 650 1277 930 1277 651 1277 650 1278 651 1278 627 1278 627 1279 651 1279 653 1279 627 1280 653 1280 652 1280 652 1281 653 1281 654 1281 652 1282 654 1282 656 1282 656 1283 654 1283 655 1283 656 1284 655 1284 657 1284 657 1285 655 1285 658 1285 657 1286 658 1286 659 1286 659 1287 658 1287 681 1287 659 1288 681 1288 632 1288 632 1289 681 1289 660 1289 632 1290 660 1290 662 1290 662 1291 660 1291 661 1291 662 1292 661 1292 633 1292 633 1293 661 1293 684 1293 633 1294 684 1294 664 1294 664 1295 684 1295 663 1295 664 1296 663 1296 665 1296 665 1297 663 1297 666 1297 665 1298 666 1298 667 1298 667 1299 666 1299 668 1299 667 1300 668 1300 639 1300 639 1301 668 1301 669 1301 639 1302 669 1302 640 1302 640 1303 669 1303 670 1303 640 1304 670 1304 671 1304 671 1305 670 1305 688 1305 671 1306 688 1306 672 1306 672 1307 688 1307 690 1307 672 1308 690 1308 673 1308 673 1309 690 1309 674 1309 673 1310 674 1310 643 1310 643 1311 674 1311 692 1311 643 1312 692 1312 645 1312 645 1313 692 1313 693 1313 645 1314 693 1314 646 1314 646 1315 693 1315 694 1315 646 1316 694 1316 648 1316 648 1317 694 1317 675 1317 648 1318 675 1318 676 1318 676 1319 675 1319 696 1319 676 1320 696 1320 649 1320 649 1321 696 1321 677 1321 930 1322 703 1322 651 1322 651 1323 703 1323 678 1323 651 1324 678 1324 653 1324 653 1325 678 1325 679 1325 653 1326 679 1326 654 1326 654 1327 679 1327 704 1327 654 1328 704 1328 655 1328 655 1329 704 1329 680 1329 655 1330 680 1330 658 1330 658 1331 680 1331 706 1331 658 1332 706 1332 681 1332 681 1333 706 1333 682 1333 681 1334 682 1334 660 1334 660 1335 682 1335 707 1335 660 1336 707 1336 661 1336 661 1337 707 1337 683 1337 661 1338 683 1338 684 1338 684 1339 683 1339 710 1339 684 1340 710 1340 663 1340 663 1341 710 1341 711 1341 663 1342 711 1342 666 1342 666 1343 711 1343 685 1343 666 1344 685 1344 668 1344 668 1345 685 1345 714 1345 668 1346 714 1346 669 1346 669 1347 714 1347 686 1347 669 1348 686 1348 670 1348 670 1349 686 1349 687 1349 670 1350 687 1350 688 1350 688 1351 687 1351 689 1351 688 1352 689 1352 690 1352 690 1353 689 1353 717 1353 690 1354 717 1354 674 1354 674 1355 717 1355 691 1355 674 1356 691 1356 692 1356 692 1357 691 1357 719 1357 692 1358 719 1358 693 1358 693 1359 719 1359 720 1359 693 1360 720 1360 694 1360 694 1361 720 1361 721 1361 694 1362 721 1362 675 1362 675 1363 721 1363 695 1363 675 1364 695 1364 696 1364 696 1365 695 1365 697 1365 696 1366 697 1366 677 1366 677 1367 697 1367 889 1367 932 1368 859 1368 836 1368 858 1369 698 1369 699 1369 794 1370 933 1370 795 1370 700 1371 793 1371 814 1371 774 1372 935 1372 775 1372 956 1373 954 1373 773 1373 726 1374 701 1374 745 1374 951 1375 724 1375 702 1375 703 1376 939 1376 678 1376 678 1377 939 1377 725 1377 678 1378 725 1378 679 1378 679 1379 725 1379 727 1379 679 1380 727 1380 704 1380 704 1381 727 1381 728 1381 704 1382 728 1382 680 1382 680 1383 728 1383 705 1383 680 1384 705 1384 706 1384 706 1385 705 1385 730 1385 706 1386 730 1386 682 1386 682 1387 730 1387 708 1387 682 1388 708 1388 707 1388 707 1389 708 1389 709 1389 707 1390 709 1390 683 1390 683 1391 709 1391 731 1391 683 1392 731 1392 710 1392 710 1393 731 1393 732 1393 710 1394 732 1394 711 1394 711 1395 732 1395 712 1395 711 1396 712 1396 685 1396 685 1397 712 1397 713 1397 685 1398 713 1398 714 1398 714 1399 713 1399 734 1399 714 1400 734 1400 686 1400 686 1401 734 1401 736 1401 686 1402 736 1402 687 1402 687 1403 736 1403 715 1403 687 1404 715 1404 689 1404 689 1405 715 1405 716 1405 689 1406 716 1406 717 1406 717 1407 716 1407 739 1407 717 1408 739 1408 691 1408 691 1409 739 1409 718 1409 691 1410 718 1410 719 1410 719 1411 718 1411 740 1411 719 1412 740 1412 720 1412 720 1413 740 1413 722 1413 720 1414 722 1414 721 1414 721 1415 722 1415 742 1415 721 1416 742 1416 695 1416 695 1417 742 1417 723 1417 695 1418 723 1418 697 1418 697 1419 723 1419 702 1419 697 1420 702 1420 889 1420 889 1421 702 1421 724 1421 939 1422 726 1422 725 1422 725 1423 726 1423 745 1423 725 1424 745 1424 727 1424 727 1425 745 1425 747 1425 727 1426 747 1426 728 1426 728 1427 747 1427 748 1427 728 1428 748 1428 705 1428 705 1429 748 1429 750 1429 705 1430 750 1430 730 1430 730 1431 750 1431 729 1431 730 1432 729 1432 708 1432 708 1433 729 1433 752 1433 708 1434 752 1434 709 1434 709 1435 752 1435 754 1435 709 1436 754 1436 731 1436 731 1437 754 1437 756 1437 731 1438 756 1438 732 1438 732 1439 756 1439 733 1439 732 1440 733 1440 712 1440 712 1441 733 1441 759 1441 712 1442 759 1442 713 1442 713 1443 759 1443 760 1443 713 1444 760 1444 734 1444 734 1445 760 1445 735 1445 734 1446 735 1446 736 1446 736 1447 735 1447 737 1447 736 1448 737 1448 715 1448 715 1449 737 1449 763 1449 715 1450 763 1450 716 1450 716 1451 763 1451 738 1451 716 1452 738 1452 739 1452 739 1453 738 1453 765 1453 739 1454 765 1454 718 1454 718 1455 765 1455 766 1455 718 1456 766 1456 740 1456 740 1457 766 1457 741 1457 740 1458 741 1458 722 1458 722 1459 741 1459 743 1459 722 1460 743 1460 742 1460 742 1461 743 1461 770 1461 742 1462 770 1462 723 1462 723 1463 770 1463 744 1463 723 1464 744 1464 702 1464 702 1465 744 1465 772 1465 702 1466 772 1466 951 1466 951 1467 772 1467 952 1467 701 1468 941 1468 745 1468 745 1469 941 1469 746 1469 745 1470 746 1470 747 1470 747 1471 746 1471 776 1471 747 1472 776 1472 748 1472 748 1473 776 1473 749 1473 748 1474 749 1474 750 1474 750 1475 749 1475 751 1475 750 1476 751 1476 729 1476 729 1477 751 1477 779 1477 729 1478 779 1478 752 1478 752 1479 779 1479 753 1479 752 1480 753 1480 754 1480 754 1481 753 1481 755 1481 754 1482 755 1482 756 1482 756 1483 755 1483 780 1483 756 1484 780 1484 733 1484 733 1485 780 1485 757 1485 733 1486 757 1486 759 1486 759 1487 757 1487 758 1487 759 1488 758 1488 760 1488 760 1489 758 1489 782 1489 760 1490 782 1490 735 1490 735 1491 782 1491 783 1491 735 1492 783 1492 737 1492 737 1493 783 1493 761 1493 737 1494 761 1494 763 1494 763 1495 761 1495 762 1495 763 1496 762 1496 738 1496 738 1497 762 1497 764 1497 738 1498 764 1498 765 1498 765 1499 764 1499 788 1499 765 1500 788 1500 766 1500 766 1501 788 1501 767 1501 766 1502 767 1502 741 1502 741 1503 767 1503 768 1503 741 1504 768 1504 743 1504 743 1505 768 1505 769 1505 743 1506 769 1506 770 1506 770 1507 769 1507 771 1507 770 1508 771 1508 744 1508 744 1509 771 1509 792 1509 744 1510 792 1510 772 1510 772 1511 792 1511 773 1511 772 1512 773 1512 952 1512 952 1513 773 1513 954 1513 941 1514 774 1514 746 1514 746 1515 774 1515 775 1515 746 1516 775 1516 776 1516 776 1517 775 1517 777 1517 776 1518 777 1518 749 1518 749 1519 777 1519 797 1519 749 1520 797 1520 751 1520 751 1521 797 1521 798 1521 751 1522 798 1522 779 1522 779 1523 798 1523 778 1523 779 1524 778 1524 753 1524 753 1525 778 1525 799 1525 753 1526 799 1526 755 1526 755 1527 799 1527 800 1527 755 1528 800 1528 780 1528 780 1529 800 1529 801 1529 780 1530 801 1530 757 1530 757 1531 801 1531 803 1531 757 1532 803 1532 758 1532 758 1533 803 1533 804 1533 758 1534 804 1534 782 1534 782 1535 804 1535 781 1535 782 1536 781 1536 783 1536 783 1537 781 1537 784 1537 783 1538 784 1538 761 1538 761 1539 784 1539 806 1539 761 1540 806 1540 762 1540 762 1541 806 1541 785 1541 762 1542 785 1542 764 1542 764 1543 785 1543 786 1543 764 1544 786 1544 788 1544 788 1545 786 1545 787 1545 788 1546 787 1546 767 1546 767 1547 787 1547 809 1547 767 1548 809 1548 768 1548 768 1549 809 1549 812 1549 768 1550 812 1550 769 1550 769 1551 812 1551 789 1551 769 1552 789 1552 771 1552 771 1553 789 1553 790 1553 771 1554 790 1554 792 1554 792 1555 790 1555 791 1555 792 1556 791 1556 773 1556 773 1557 791 1557 814 1557 773 1558 814 1558 956 1558 956 1559 814 1559 793 1559 935 1560 794 1560 775 1560 775 1561 794 1561 795 1561 775 1562 795 1562 777 1562 777 1563 795 1563 817 1563 777 1564 817 1564 797 1564 797 1565 817 1565 796 1565 797 1566 796 1566 798 1566 798 1567 796 1567 819 1567 798 1568 819 1568 778 1568 778 1569 819 1569 821 1569 778 1570 821 1570 799 1570 799 1571 821 1571 822 1571 799 1572 822 1572 800 1572 800 1573 822 1573 824 1573 800 1574 824 1574 801 1574 801 1575 824 1575 825 1575 801 1576 825 1576 803 1576 803 1577 825 1577 802 1577 803 1578 802 1578 804 1578 804 1579 802 1579 805 1579 804 1580 805 1580 781 1580 781 1581 805 1581 826 1581 781 1582 826 1582 784 1582 784 1583 826 1583 827 1583 784 1584 827 1584 806 1584 806 1585 827 1585 829 1585 806 1586 829 1586 785 1586 785 1587 829 1587 807 1587 785 1588 807 1588 786 1588 786 1589 807 1589 808 1589 786 1590 808 1590 787 1590 787 1591 808 1591 832 1591 787 1592 832 1592 809 1592 809 1593 832 1593 810 1593 809 1594 810 1594 812 1594 812 1595 810 1595 811 1595 812 1596 811 1596 789 1596 789 1597 811 1597 813 1597 789 1598 813 1598 790 1598 790 1599 813 1599 833 1599 790 1600 833 1600 791 1600 791 1601 833 1601 834 1601 791 1602 834 1602 814 1602 814 1603 834 1603 835 1603 814 1604 835 1604 700 1604 700 1605 835 1605 958 1605 933 1606 815 1606 795 1606 795 1607 815 1607 816 1607 795 1608 816 1608 817 1608 817 1609 816 1609 818 1609 817 1610 818 1610 796 1610 796 1611 818 1611 837 1611 796 1612 837 1612 819 1612 819 1613 837 1613 838 1613 819 1614 838 1614 821 1614 821 1615 838 1615 820 1615 821 1616 820 1616 822 1616 822 1617 820 1617 823 1617 822 1618 823 1618 824 1618 824 1619 823 1619 840 1619 824 1620 840 1620 825 1620 825 1621 840 1621 841 1621 825 1622 841 1622 802 1622 802 1623 841 1623 842 1623 802 1624 842 1624 805 1624 805 1625 842 1625 843 1625 805 1626 843 1626 826 1626 826 1627 843 1627 844 1627 826 1628 844 1628 827 1628 827 1629 844 1629 828 1629 827 1630 828 1630 829 1630 829 1631 828 1631 845 1631 829 1632 845 1632 807 1632 807 1633 845 1633 830 1633 807 1634 830 1634 808 1634 808 1635 830 1635 831 1635 808 1636 831 1636 832 1636 832 1637 831 1637 849 1637 832 1638 849 1638 810 1638 810 1639 849 1639 850 1639 810 1640 850 1640 811 1640 811 1641 850 1641 852 1641 811 1642 852 1642 813 1642 813 1643 852 1643 853 1643 813 1644 853 1644 833 1644 833 1645 853 1645 854 1645 833 1646 854 1646 834 1646 834 1647 854 1647 855 1647 834 1648 855 1648 835 1648 835 1649 855 1649 699 1649 835 1650 699 1650 958 1650 958 1651 699 1651 698 1651 815 1652 932 1652 816 1652 816 1653 932 1653 836 1653 816 1654 836 1654 818 1654 818 1655 836 1655 860 1655 818 1656 860 1656 837 1656 837 1657 860 1657 862 1657 837 1658 862 1658 838 1658 838 1659 862 1659 863 1659 838 1660 863 1660 820 1660 820 1661 863 1661 839 1661 820 1662 839 1662 823 1662 823 1663 839 1663 865 1663 823 1664 865 1664 840 1664 840 1665 865 1665 867 1665 840 1666 867 1666 841 1666 841 1667 867 1667 869 1667 841 1668 869 1668 842 1668 842 1669 869 1669 870 1669 842 1670 870 1670 843 1670 843 1671 870 1671 872 1671 843 1672 872 1672 844 1672 844 1673 872 1673 873 1673 844 1674 873 1674 828 1674 828 1675 873 1675 875 1675 828 1676 875 1676 845 1676 845 1677 875 1677 846 1677 845 1678 846 1678 830 1678 830 1679 846 1679 847 1679 830 1680 847 1680 831 1680 831 1681 847 1681 848 1681 831 1682 848 1682 849 1682 849 1683 848 1683 851 1683 849 1684 851 1684 850 1684 850 1685 851 1685 880 1685 850 1686 880 1686 852 1686 852 1687 880 1687 881 1687 852 1688 881 1688 853 1688 853 1689 881 1689 883 1689 853 1690 883 1690 854 1690 854 1691 883 1691 885 1691 854 1692 885 1692 855 1692 855 1693 885 1693 856 1693 855 1694 856 1694 699 1694 699 1695 856 1695 857 1695 699 1696 857 1696 858 1696 858 1697 857 1697 959 1697 859 1698 943 1698 836 1698 836 1699 943 1699 945 1699 836 1700 945 1700 860 1700 860 1701 945 1701 950 1701 860 1702 950 1702 862 1702 862 1703 950 1703 861 1703 862 1704 861 1704 863 1704 863 1705 861 1705 949 1705 863 1706 949 1706 839 1706 839 1707 949 1707 864 1707 839 1708 864 1708 865 1708 865 1709 864 1709 948 1709 865 1710 948 1710 867 1710 867 1711 948 1711 866 1711 867 1712 866 1712 869 1712 869 1713 866 1713 868 1713 869 1714 868 1714 870 1714 870 1715 868 1715 947 1715 870 1716 947 1716 872 1716 872 1717 947 1717 871 1717 872 1718 871 1718 873 1718 873 1719 871 1719 874 1719 873 1720 874 1720 875 1720 875 1721 874 1721 946 1721 875 1722 946 1722 846 1722 846 1723 946 1723 876 1723 846 1724 876 1724 847 1724 847 1725 876 1725 877 1725 847 1726 877 1726 848 1726 848 1727 877 1727 878 1727 848 1728 878 1728 851 1728 851 1729 878 1729 944 1729 851 1730 944 1730 880 1730 880 1731 944 1731 879 1731 880 1732 879 1732 881 1732 881 1733 879 1733 882 1733 881 1734 882 1734 883 1734 883 1735 882 1735 884 1735 883 1736 884 1736 885 1736 885 1737 884 1737 886 1737 885 1738 886 1738 856 1738 856 1739 886 1739 887 1739 856 1740 887 1740 857 1740 857 1741 887 1741 888 1741 857 1742 888 1742 959 1742 959 1743 888 1743 942 1743 889 1744 890 1744 677 1744 677 1745 890 1745 891 1745 677 1746 891 1746 649 1746 649 1747 891 1747 961 1747 649 1748 961 1748 892 1748 892 1749 961 1749 974 1749 892 1750 974 1750 893 1750 893 1751 974 1751 894 1751 895 1752 999 1752 896 1752 896 1753 999 1753 897 1753 896 1754 897 1754 443 1754 895 1755 491 1755 999 1755 999 1756 491 1756 898 1756 999 1757 898 1757 984 1757 984 1758 898 1758 418 1758 984 1759 418 1759 985 1759 985 1760 418 1760 511 1760 985 1761 511 1761 899 1761 899 1762 511 1762 900 1762 899 1763 900 1763 901 1763 901 1764 900 1764 535 1764 901 1765 535 1765 902 1765 893 1766 894 1766 603 1766 603 1767 894 1767 981 1767 603 1768 981 1768 903 1768 903 1769 981 1769 902 1769 903 1770 902 1770 559 1770 559 1771 902 1771 535 1771 897 1772 1006 1772 443 1772 443 1773 1006 1773 904 1773 443 1774 904 1774 905 1774 912 1775 432 1775 905 1775 905 1776 432 1776 434 1776 905 1777 434 1777 435 1777 435 1778 906 1778 905 1778 905 1779 906 1779 437 1779 905 1780 437 1780 907 1780 907 1781 908 1781 905 1781 905 1782 908 1782 440 1782 905 1783 440 1783 913 1783 905 1784 909 1784 912 1784 912 1785 909 1785 910 1785 912 1786 910 1786 911 1786 911 1787 422 1787 912 1787 912 1788 422 1788 424 1788 912 1789 424 1789 426 1789 426 1790 428 1790 912 1790 912 1791 428 1791 429 1791 912 1792 429 1792 430 1792 913 1793 914 1793 905 1793 905 1794 914 1794 915 1794 905 1795 915 1795 443 1795 916 1796 917 1796 417 1796 417 1797 917 1797 1020 1797 417 1798 1020 1798 580 1798 916 1799 536 1799 917 1799 917 1800 536 1800 918 1800 917 1801 918 1801 1017 1801 1017 1802 918 1802 919 1802 1017 1803 919 1803 1007 1803 1007 1804 919 1804 512 1804 1007 1805 512 1805 920 1805 920 1806 512 1806 925 1806 920 1807 925 1807 921 1807 904 1808 1006 1808 444 1808 444 1809 1006 1809 922 1809 444 1810 922 1810 923 1810 923 1811 922 1811 1011 1811 923 1812 1011 1812 465 1812 465 1813 1011 1813 921 1813 465 1814 921 1814 924 1814 924 1815 921 1815 925 1815 926 1816 931 1816 927 1816 927 1817 931 1817 605 1817 927 1818 605 1818 1020 1818 1020 1819 605 1819 580 1819 928 1820 703 1820 929 1820 929 1821 703 1821 930 1821 929 1822 930 1822 926 1822 926 1823 930 1823 931 1823 943 1824 859 1824 1054 1824 1054 1825 859 1825 1041 1825 859 1826 932 1826 1041 1826 1041 1827 932 1827 815 1827 1041 1828 815 1828 1039 1828 815 1829 933 1829 1039 1829 1039 1830 933 1830 794 1830 1039 1831 794 1831 934 1831 934 1832 794 1832 935 1832 934 1833 935 1833 936 1833 936 1834 935 1834 774 1834 936 1835 774 1835 937 1835 703 1836 928 1836 939 1836 939 1837 928 1837 938 1837 939 1838 938 1838 726 1838 726 1839 938 1839 940 1839 726 1840 940 1840 701 1840 701 1841 940 1841 937 1841 701 1842 937 1842 941 1842 941 1843 937 1843 774 1843 1054 1844 1058 1844 943 1844 943 1845 1058 1845 942 1845 942 1846 888 1846 943 1846 943 1847 888 1847 887 1847 943 1848 887 1848 886 1848 886 1849 884 1849 943 1849 943 1850 884 1850 882 1850 943 1851 882 1851 945 1851 945 1852 882 1852 879 1852 879 1853 944 1853 945 1853 945 1854 944 1854 878 1854 945 1855 878 1855 877 1855 877 1856 876 1856 945 1856 945 1857 876 1857 946 1857 945 1858 946 1858 874 1858 874 1859 871 1859 945 1859 945 1860 871 1860 947 1860 945 1861 947 1861 868 1861 868 1862 866 1862 945 1862 945 1863 866 1863 948 1863 945 1864 948 1864 864 1864 949 1865 861 1865 864 1865 864 1866 861 1866 950 1866 864 1867 950 1867 945 1867 951 1868 953 1868 724 1868 724 1869 953 1869 890 1869 724 1870 890 1870 889 1870 951 1871 952 1871 953 1871 953 1872 952 1872 954 1872 953 1873 954 1873 1055 1873 1055 1874 954 1874 956 1874 1055 1875 956 1875 955 1875 955 1876 956 1876 793 1876 955 1877 793 1877 1064 1877 1064 1878 793 1878 700 1878 1064 1879 700 1879 957 1879 957 1880 700 1880 958 1880 957 1881 958 1881 1060 1881 942 1882 1058 1882 959 1882 959 1883 1058 1883 960 1883 959 1884 960 1884 858 1884 858 1885 960 1885 1060 1885 858 1886 1060 1886 698 1886 698 1887 1060 1887 958 1887 891 1888 965 1888 961 1888 961 1889 965 1889 973 1889 973 1890 965 1890 962 1890 962 1891 965 1891 967 1891 962 1892 967 1892 972 1892 972 1893 967 1893 963 1893 963 1894 967 1894 968 1894 963 1895 968 1895 971 1895 971 1896 968 1896 964 1896 964 1897 968 1897 1100 1897 964 1898 1100 1898 1101 1898 891 1899 890 1899 965 1899 965 1900 890 1900 966 1900 965 1901 966 1901 967 1901 967 1902 966 1902 1075 1902 967 1903 1075 1903 968 1903 968 1904 1075 1904 969 1904 968 1905 969 1905 1100 1905 1100 1906 969 1906 1097 1906 1101 1907 970 1907 964 1907 964 1908 970 1908 978 1908 964 1909 978 1909 971 1909 971 1910 978 1910 963 1910 963 1911 978 1911 977 1911 963 1912 977 1912 972 1912 972 1913 977 1913 962 1913 962 1914 977 1914 975 1914 962 1915 975 1915 973 1915 973 1916 975 1916 974 1916 973 1917 974 1917 961 1917 894 1918 974 1918 982 1918 982 1919 974 1919 975 1919 982 1920 975 1920 976 1920 976 1921 975 1921 977 1921 976 1922 977 1922 979 1922 979 1923 977 1923 978 1923 979 1924 978 1924 1083 1924 1083 1925 978 1925 970 1925 988 1926 1001 1926 986 1926 979 1927 1083 1927 991 1927 976 1928 979 1928 990 1928 983 1929 902 1929 980 1929 980 1930 902 1930 981 1930 980 1931 981 1931 894 1931 894 1932 982 1932 980 1932 980 1933 982 1933 998 1933 980 1934 998 1934 983 1934 983 1935 998 1935 989 1935 983 1936 989 1936 987 1936 984 1937 985 1937 987 1937 987 1938 985 1938 899 1938 987 1939 899 1939 983 1939 983 1940 899 1940 901 1940 983 1941 901 1941 902 1941 999 1942 984 1942 986 1942 986 1943 984 1943 987 1943 986 1944 987 1944 988 1944 988 1945 987 1945 989 1945 979 1946 991 1946 990 1946 990 1947 991 1947 992 1947 990 1948 992 1948 997 1948 997 1949 992 1949 1103 1949 997 1950 1103 1950 993 1950 993 1951 1103 1951 994 1951 993 1952 994 1952 996 1952 996 1953 994 1953 1105 1953 996 1954 1105 1954 995 1954 995 1955 1002 1955 996 1955 996 1956 1002 1956 1001 1956 996 1957 1001 1957 993 1957 993 1958 1001 1958 988 1958 993 1959 988 1959 997 1959 997 1960 988 1960 989 1960 997 1961 989 1961 990 1961 990 1962 989 1962 998 1962 990 1963 998 1963 976 1963 976 1964 998 1964 982 1964 897 1965 999 1965 1005 1965 1005 1966 999 1966 986 1966 1005 1967 986 1967 1003 1967 1003 1968 986 1968 1001 1968 1003 1969 1001 1969 1000 1969 1000 1970 1001 1970 1002 1970 995 1971 1105 1971 1010 1971 995 1972 1010 1972 1002 1972 1002 1973 1010 1973 1009 1973 1002 1974 1009 1974 1000 1974 1000 1975 1009 1975 1004 1975 1000 1976 1004 1976 1003 1976 1003 1977 1004 1977 1005 1977 1005 1978 1004 1978 1006 1978 1005 1979 1006 1979 897 1979 1017 1980 1007 1980 1014 1980 920 1981 921 1981 1013 1981 1008 1982 1009 1982 1106 1982 1106 1983 1009 1983 1010 1983 1011 1984 922 1984 1012 1984 1012 1985 922 1985 1006 1985 1012 1986 1006 1986 1004 1986 921 1987 1011 1987 1013 1987 1013 1988 1011 1988 1012 1988 1013 1989 1012 1989 1008 1989 1008 1990 1012 1990 1004 1990 1008 1991 1004 1991 1009 1991 1007 1992 920 1992 1014 1992 1014 1993 920 1993 1013 1993 1014 1994 1013 1994 1015 1994 1015 1995 1013 1995 1008 1995 1015 1996 1008 1996 1016 1996 1016 1997 1008 1997 1106 1997 1019 1998 1092 1998 1018 1998 1018 1999 1092 1999 1023 1999 1018 2000 1023 2000 1022 2000 917 2001 1017 2001 1022 2001 1022 2002 1017 2002 1014 2002 1022 2003 1014 2003 1018 2003 1018 2004 1014 2004 1015 2004 1018 2005 1015 2005 1019 2005 1019 2006 1015 2006 1016 2006 1020 2007 917 2007 1021 2007 1021 2008 917 2008 1022 2008 1021 2009 1022 2009 1024 2009 1024 2010 1022 2010 1023 2010 1024 2011 1023 2011 1089 2011 1089 2012 1023 2012 1092 2012 926 2013 927 2013 1032 2013 1032 2014 927 2014 1028 2014 1032 2015 1028 2015 1025 2015 1025 2016 1028 2016 1031 2016 1031 2017 1028 2017 1029 2017 1031 2018 1029 2018 1026 2018 1026 2019 1029 2019 1027 2019 1027 2020 1029 2020 1088 2020 1027 2021 1088 2021 1087 2021 927 2022 1020 2022 1028 2022 1028 2023 1020 2023 1021 2023 1028 2024 1021 2024 1029 2024 1029 2025 1021 2025 1024 2025 1029 2026 1024 2026 1088 2026 1088 2027 1024 2027 1089 2027 1087 2028 1036 2028 1027 2028 1027 2029 1036 2029 1030 2029 1027 2030 1030 2030 1026 2030 1026 2031 1030 2031 1031 2031 1031 2032 1030 2032 1034 2032 1031 2033 1034 2033 1025 2033 1025 2034 1034 2034 1032 2034 1032 2035 1034 2035 929 2035 1032 2036 929 2036 926 2036 928 2037 929 2037 1033 2037 1033 2038 929 2038 1034 2038 1033 2039 1034 2039 1035 2039 1035 2040 1034 2040 1030 2040 1035 2041 1030 2041 1086 2041 1086 2042 1030 2042 1036 2042 1044 2043 1051 2043 1049 2043 1033 2044 1035 2044 1047 2044 1040 2045 940 2045 1037 2045 1037 2046 940 2046 938 2046 1037 2047 938 2047 928 2047 928 2048 1033 2048 1037 2048 1037 2049 1033 2049 1047 2049 1037 2050 1047 2050 1040 2050 1040 2051 1047 2051 1038 2051 1040 2052 1038 2052 1042 2052 1039 2053 934 2053 1042 2053 1042 2054 934 2054 936 2054 1042 2055 936 2055 1040 2055 1040 2056 936 2056 937 2056 1040 2057 937 2057 940 2057 1041 2058 1039 2058 1049 2058 1049 2059 1039 2059 1042 2059 1049 2060 1042 2060 1044 2060 1044 2061 1042 2061 1038 2061 1052 2062 1051 2062 1043 2062 1043 2063 1051 2063 1044 2063 1043 2064 1044 2064 1045 2064 1045 2065 1044 2065 1038 2065 1045 2066 1038 2066 1046 2066 1046 2067 1038 2067 1047 2067 1046 2068 1047 2068 1080 2068 1080 2069 1047 2069 1035 2069 1080 2070 1035 2070 1086 2070 1054 2071 1041 2071 1048 2071 1048 2072 1041 2072 1049 2072 1048 2073 1049 2073 1050 2073 1050 2074 1049 2074 1051 2074 1050 2075 1051 2075 1053 2075 1053 2076 1051 2076 1052 2076 1052 2077 1079 2077 1057 2077 1052 2078 1057 2078 1053 2078 1053 2079 1057 2079 1067 2079 1053 2080 1067 2080 1050 2080 1050 2081 1067 2081 1063 2081 1050 2082 1063 2082 1048 2082 1048 2083 1063 2083 1058 2083 1048 2084 1058 2084 1054 2084 1055 2085 955 2085 1074 2085 1064 2086 957 2086 1059 2086 1066 2087 1057 2087 1056 2087 1056 2088 1057 2088 1079 2088 1060 2089 960 2089 1061 2089 1061 2090 960 2090 1058 2090 1061 2091 1058 2091 1063 2091 957 2092 1060 2092 1059 2092 1059 2093 1060 2093 1061 2093 1059 2094 1061 2094 1062 2094 1062 2095 1061 2095 1063 2095 1062 2096 1063 2096 1067 2096 955 2097 1064 2097 1074 2097 1074 2098 1064 2098 1059 2098 1074 2099 1059 2099 1065 2099 1065 2100 1059 2100 1062 2100 1065 2101 1062 2101 1066 2101 1066 2102 1062 2102 1067 2102 1066 2103 1067 2103 1057 2103 1069 2104 1095 2104 1072 2104 1072 2105 1095 2105 1077 2105 1072 2106 1077 2106 1073 2106 1068 2107 1069 2107 1070 2107 1070 2108 1069 2108 1072 2108 1070 2109 1072 2109 1071 2109 1071 2110 1072 2110 1073 2110 1071 2111 1073 2111 1076 2111 953 2112 1055 2112 1076 2112 1076 2113 1055 2113 1074 2113 1076 2114 1074 2114 1071 2114 1071 2115 1074 2115 1065 2115 1071 2116 1065 2116 1070 2116 1070 2117 1065 2117 1066 2117 1070 2118 1066 2118 1068 2118 1068 2119 1066 2119 1056 2119 890 2120 953 2120 966 2120 966 2121 953 2121 1076 2121 966 2122 1076 2122 1075 2122 1075 2123 1076 2123 1073 2123 1075 2124 1073 2124 969 2124 969 2125 1073 2125 1077 2125 969 2126 1077 2126 1097 2126 1097 2127 1077 2127 1095 2127 1052 2128 1078 2128 1079 2128 1079 2129 1078 2129 1248 2129 1079 2130 1248 2130 1056 2130 1226 2131 1225 2131 1086 2131 1086 2132 1225 2132 1080 2132 1225 2133 1223 2133 1080 2133 1080 2134 1223 2134 1222 2134 1080 2135 1222 2135 1046 2135 1222 2136 1220 2136 1046 2136 1046 2137 1220 2137 1081 2137 1046 2138 1081 2138 1045 2138 1143 2139 1084 2139 1083 2139 1081 2140 1218 2140 1045 2140 1045 2141 1218 2141 1082 2141 1045 2142 1082 2142 1043 2142 1043 2143 1082 2143 1217 2143 1043 2144 1217 2144 1052 2144 1052 2145 1217 2145 1216 2145 1052 2146 1216 2146 1078 2146 1083 2147 1084 2147 991 2147 1084 2148 1085 2148 991 2148 991 2149 1085 2149 1153 2149 991 2150 1153 2150 992 2150 1086 2151 1036 2151 1226 2151 1226 2152 1036 2152 1087 2152 1226 2153 1087 2153 1207 2153 1207 2154 1087 2154 1088 2154 1207 2155 1088 2155 1090 2155 1090 2156 1088 2156 1089 2156 1090 2157 1089 2157 1091 2157 1091 2158 1089 2158 1092 2158 1091 2159 1092 2159 1093 2159 1093 2160 1092 2160 1019 2160 1093 2161 1019 2161 1094 2161 1094 2162 1019 2162 1016 2162 1094 2163 1016 2163 1208 2163 1208 2164 1016 2164 1106 2164 1105 2165 994 2165 1148 2165 1248 2166 1138 2166 1056 2166 1056 2167 1138 2167 1137 2167 1056 2168 1137 2168 1068 2168 1068 2169 1137 2169 1136 2169 1068 2170 1136 2170 1069 2170 1069 2171 1136 2171 1096 2171 1069 2172 1096 2172 1095 2172 1095 2173 1096 2173 1098 2173 1095 2174 1098 2174 1097 2174 1097 2175 1098 2175 1099 2175 1097 2176 1099 2176 1100 2176 1100 2177 1099 2177 1132 2177 1100 2178 1132 2178 1101 2178 1101 2179 1132 2179 1143 2179 1101 2180 1143 2180 970 2180 970 2181 1143 2181 1083 2181 1153 2182 1102 2182 992 2182 992 2183 1102 2183 1152 2183 992 2184 1152 2184 1103 2184 1103 2185 1152 2185 1149 2185 1103 2186 1149 2186 994 2186 994 2187 1149 2187 1104 2187 994 2188 1104 2188 1148 2188 1148 2189 1147 2189 1105 2189 1105 2190 1147 2190 1179 2190 1105 2191 1179 2191 1010 2191 1010 2192 1179 2192 1178 2192 1010 2193 1178 2193 1106 2193 1106 2194 1178 2194 1107 2194 1106 2195 1107 2195 1208 2195 1130 2196 1125 2196 1123 2196 1124 2197 1108 2197 1109 2197 1109 2198 1108 2198 1300 2198 1300 2199 1250 2199 1109 2199 1109 2200 1250 2200 1111 2200 1109 2201 1111 2201 1110 2201 1110 2202 1111 2202 1253 2202 1110 2203 1253 2203 1112 2203 1253 2204 1254 2204 1112 2204 1112 2205 1254 2205 1256 2205 1112 2206 1256 2206 1114 2206 1256 2207 1113 2207 1114 2207 1114 2208 1113 2208 1119 2208 1114 2209 1119 2209 1115 2209 1258 2210 1116 2210 1259 2210 1259 2211 1116 2211 1117 2211 1259 2212 1117 2212 1118 2212 1118 2213 1117 2213 1115 2213 1118 2214 1115 2214 1262 2214 1262 2215 1115 2215 1119 2215 1116 2216 1140 2216 1117 2216 1117 2217 1140 2217 1126 2217 1117 2218 1126 2218 1115 2218 1115 2219 1126 2219 1120 2219 1115 2220 1120 2220 1114 2220 1114 2221 1120 2221 1121 2221 1114 2222 1121 2222 1112 2222 1112 2223 1121 2223 1127 2223 1112 2224 1127 2224 1110 2224 1110 2225 1127 2225 1122 2225 1110 2226 1122 2226 1109 2226 1109 2227 1122 2227 1123 2227 1109 2228 1123 2228 1124 2228 1124 2229 1123 2229 1125 2229 1140 2230 1142 2230 1126 2230 1126 2231 1142 2231 1131 2231 1126 2232 1131 2232 1120 2232 1120 2233 1131 2233 1133 2233 1120 2234 1133 2234 1121 2234 1121 2235 1133 2235 1134 2235 1121 2236 1134 2236 1127 2236 1127 2237 1134 2237 1128 2237 1127 2238 1128 2238 1122 2238 1122 2239 1128 2239 1135 2239 1122 2240 1135 2240 1123 2240 1123 2241 1135 2241 1129 2241 1123 2242 1129 2242 1130 2242 1130 2243 1129 2243 1247 2243 1142 2244 1132 2244 1131 2244 1131 2245 1132 2245 1099 2245 1131 2246 1099 2246 1133 2246 1133 2247 1099 2247 1098 2247 1133 2248 1098 2248 1134 2248 1134 2249 1098 2249 1096 2249 1134 2250 1096 2250 1128 2250 1128 2251 1096 2251 1136 2251 1128 2252 1136 2252 1135 2252 1135 2253 1136 2253 1137 2253 1135 2254 1137 2254 1129 2254 1129 2255 1137 2255 1138 2255 1129 2256 1138 2256 1247 2256 1247 2257 1138 2257 1248 2257 1258 2258 1264 2258 1139 2258 1258 2259 1139 2259 1116 2259 1116 2260 1139 2260 1156 2260 1116 2261 1156 2261 1140 2261 1140 2262 1156 2262 1141 2262 1140 2263 1141 2263 1142 2263 1142 2264 1141 2264 1143 2264 1142 2265 1143 2265 1132 2265 1156 2266 1139 2266 1144 2266 1175 2267 1146 2267 1145 2267 1175 2268 1145 2268 1174 2268 1146 2269 1179 2269 1145 2269 1145 2270 1179 2270 1147 2270 1145 2271 1147 2271 1163 2271 1163 2272 1147 2272 1148 2272 1163 2273 1148 2273 1162 2273 1162 2274 1148 2274 1104 2274 1162 2275 1104 2275 1161 2275 1161 2276 1104 2276 1149 2276 1161 2277 1149 2277 1150 2277 1150 2278 1149 2278 1152 2278 1150 2279 1152 2279 1151 2279 1151 2280 1152 2280 1102 2280 1151 2281 1102 2281 1158 2281 1158 2282 1102 2282 1153 2282 1158 2283 1153 2283 1154 2283 1154 2284 1153 2284 1085 2284 1154 2285 1085 2285 1155 2285 1155 2286 1085 2286 1084 2286 1155 2287 1084 2287 1141 2287 1141 2288 1084 2288 1143 2288 1141 2289 1156 2289 1155 2289 1155 2290 1156 2290 1144 2290 1155 2291 1144 2291 1154 2291 1154 2292 1144 2292 1172 2292 1154 2293 1172 2293 1158 2293 1158 2294 1172 2294 1157 2294 1158 2295 1157 2295 1151 2295 1151 2296 1157 2296 1159 2296 1151 2297 1159 2297 1150 2297 1150 2298 1159 2298 1160 2298 1150 2299 1160 2299 1161 2299 1161 2300 1160 2300 1169 2300 1161 2301 1169 2301 1162 2301 1162 2302 1169 2302 1168 2302 1162 2303 1168 2303 1163 2303 1163 2304 1168 2304 1167 2304 1163 2305 1167 2305 1145 2305 1145 2306 1167 2306 1164 2306 1145 2307 1164 2307 1174 2307 1165 2308 1174 2308 1273 2308 1273 2309 1174 2309 1164 2309 1273 2310 1164 2310 1166 2310 1166 2311 1164 2311 1167 2311 1166 2312 1167 2312 1272 2312 1272 2313 1167 2313 1168 2313 1272 2314 1168 2314 1270 2314 1270 2315 1168 2315 1169 2315 1270 2316 1169 2316 1170 2316 1170 2317 1169 2317 1160 2317 1170 2318 1160 2318 1171 2318 1171 2319 1160 2319 1159 2319 1171 2320 1159 2320 1269 2320 1269 2321 1159 2321 1157 2321 1269 2322 1157 2322 1265 2322 1265 2323 1157 2323 1172 2323 1265 2324 1172 2324 1173 2324 1173 2325 1172 2325 1144 2325 1173 2326 1144 2326 1264 2326 1264 2327 1144 2327 1139 2327 1165 2328 1183 2328 1192 2328 1165 2329 1192 2329 1174 2329 1174 2330 1192 2330 1176 2330 1174 2331 1176 2331 1175 2331 1175 2332 1176 2332 1177 2332 1175 2333 1177 2333 1146 2333 1146 2334 1177 2334 1178 2334 1146 2335 1178 2335 1179 2335 1214 2336 1180 2336 1181 2336 1283 2337 1210 2337 1211 2337 1284 2338 1182 2338 1190 2338 1184 2339 1192 2339 1183 2339 1183 2340 1280 2340 1184 2340 1184 2341 1280 2341 1185 2341 1184 2342 1185 2342 1186 2342 1186 2343 1185 2343 1187 2343 1186 2344 1187 2344 1196 2344 1188 2345 1198 2345 1189 2345 1189 2346 1198 2346 1196 2346 1189 2347 1196 2347 1277 2347 1277 2348 1196 2348 1187 2348 1182 2349 1199 2349 1190 2349 1190 2350 1199 2350 1191 2350 1190 2351 1191 2351 1206 2351 1176 2352 1192 2352 1193 2352 1193 2353 1192 2353 1184 2353 1193 2354 1184 2354 1194 2354 1194 2355 1184 2355 1186 2355 1194 2356 1186 2356 1195 2356 1195 2357 1186 2357 1196 2357 1195 2358 1196 2358 1197 2358 1197 2359 1196 2359 1198 2359 1197 2360 1198 2360 1204 2360 1199 2361 1283 2361 1191 2361 1191 2362 1283 2362 1211 2362 1191 2363 1211 2363 1206 2363 1206 2364 1211 2364 1213 2364 1206 2365 1213 2365 1200 2365 1177 2366 1176 2366 1209 2366 1209 2367 1176 2367 1193 2367 1209 2368 1193 2368 1201 2368 1201 2369 1193 2369 1194 2369 1201 2370 1194 2370 1202 2370 1202 2371 1194 2371 1195 2371 1202 2372 1195 2372 1203 2372 1203 2373 1195 2373 1197 2373 1203 2374 1197 2374 1205 2374 1205 2375 1197 2375 1204 2375 1205 2376 1204 2376 1181 2376 1188 2377 1284 2377 1198 2377 1198 2378 1284 2378 1190 2378 1198 2379 1190 2379 1204 2379 1204 2380 1190 2380 1206 2380 1204 2381 1206 2381 1181 2381 1181 2382 1206 2382 1200 2382 1181 2383 1200 2383 1214 2383 1180 2384 1207 2384 1181 2384 1181 2385 1207 2385 1090 2385 1181 2386 1090 2386 1205 2386 1205 2387 1090 2387 1091 2387 1205 2388 1091 2388 1203 2388 1203 2389 1091 2389 1093 2389 1203 2390 1093 2390 1202 2390 1202 2391 1093 2391 1094 2391 1202 2392 1094 2392 1201 2392 1201 2393 1094 2393 1208 2393 1201 2394 1208 2394 1209 2394 1209 2395 1208 2395 1107 2395 1209 2396 1107 2396 1177 2396 1177 2397 1107 2397 1178 2397 1210 2398 1285 2398 1211 2398 1211 2399 1285 2399 1212 2399 1211 2400 1212 2400 1213 2400 1213 2401 1212 2401 1200 2401 1200 2402 1212 2402 1215 2402 1200 2403 1215 2403 1214 2403 1214 2404 1215 2404 1180 2404 1180 2405 1215 2405 1226 2405 1180 2406 1226 2406 1207 2406 1228 2407 1078 2407 1230 2407 1230 2408 1078 2408 1216 2408 1230 2409 1216 2409 1231 2409 1231 2410 1216 2410 1217 2410 1231 2411 1217 2411 1233 2411 1233 2412 1217 2412 1082 2412 1233 2413 1082 2413 1234 2413 1234 2414 1082 2414 1218 2414 1234 2415 1218 2415 1235 2415 1235 2416 1218 2416 1081 2416 1235 2417 1081 2417 1219 2417 1219 2418 1081 2418 1220 2418 1219 2419 1220 2419 1236 2419 1236 2420 1220 2420 1222 2420 1236 2421 1222 2421 1221 2421 1221 2422 1222 2422 1223 2422 1221 2423 1223 2423 1224 2423 1224 2424 1223 2424 1225 2424 1224 2425 1225 2425 1215 2425 1215 2426 1225 2426 1226 2426 1227 2427 1228 2427 1229 2427 1229 2428 1228 2428 1230 2428 1229 2429 1230 2429 1239 2429 1239 2430 1230 2430 1231 2430 1239 2431 1231 2431 1232 2431 1232 2432 1231 2432 1233 2432 1232 2433 1233 2433 1241 2433 1241 2434 1233 2434 1234 2434 1241 2435 1234 2435 1242 2435 1242 2436 1234 2436 1235 2436 1242 2437 1235 2437 1243 2437 1243 2438 1235 2438 1219 2438 1243 2439 1219 2439 1245 2439 1245 2440 1219 2440 1236 2440 1245 2441 1236 2441 1246 2441 1246 2442 1236 2442 1221 2442 1246 2443 1221 2443 1237 2443 1237 2444 1221 2444 1224 2444 1237 2445 1224 2445 1212 2445 1212 2446 1224 2446 1215 2446 1298 2447 1227 2447 1238 2447 1238 2448 1227 2448 1229 2448 1238 2449 1229 2449 1296 2449 1296 2450 1229 2450 1239 2450 1296 2451 1239 2451 1240 2451 1240 2452 1239 2452 1232 2452 1240 2453 1232 2453 1293 2453 1293 2454 1232 2454 1241 2454 1293 2455 1241 2455 1291 2455 1291 2456 1241 2456 1242 2456 1291 2457 1242 2457 1290 2457 1290 2458 1242 2458 1243 2458 1290 2459 1243 2459 1244 2459 1244 2460 1243 2460 1245 2460 1244 2461 1245 2461 1288 2461 1288 2462 1245 2462 1246 2462 1288 2463 1246 2463 1286 2463 1286 2464 1246 2464 1237 2464 1286 2465 1237 2465 1285 2465 1285 2466 1237 2466 1212 2466 1300 2467 1108 2467 1298 2467 1298 2468 1108 2468 1227 2468 1108 2469 1124 2469 1227 2469 1227 2470 1124 2470 1125 2470 1227 2471 1125 2471 1228 2471 1228 2472 1125 2472 1130 2472 1228 2473 1130 2473 1078 2473 1078 2474 1130 2474 1247 2474 1078 2475 1247 2475 1248 2475 1300 2476 1249 2476 1250 2476 1250 2477 1249 2477 1251 2477 1250 2478 1251 2478 1111 2478 1111 2479 1251 2479 1252 2479 1111 2480 1252 2480 1253 2480 1253 2481 1252 2481 1255 2481 1253 2482 1255 2482 1254 2482 1254 2483 1255 2483 1327 2483 1254 2484 1327 2484 1256 2484 1256 2485 1327 2485 1329 2485 1256 2486 1329 2486 1113 2486 1113 2487 1329 2487 1330 2487 1257 2488 1258 2488 1260 2488 1260 2489 1258 2489 1259 2489 1260 2490 1259 2490 1261 2490 1261 2491 1259 2491 1118 2491 1261 2492 1118 2492 1331 2492 1331 2493 1118 2493 1262 2493 1331 2494 1262 2494 1330 2494 1330 2495 1262 2495 1119 2495 1330 2496 1119 2496 1113 2496 1258 2497 1257 2497 1264 2497 1264 2498 1257 2498 1263 2498 1264 2499 1263 2499 1173 2499 1173 2500 1263 2500 1266 2500 1173 2501 1266 2501 1265 2501 1265 2502 1266 2502 1267 2502 1265 2503 1267 2503 1269 2503 1269 2504 1267 2504 1268 2504 1269 2505 1268 2505 1171 2505 1171 2506 1268 2506 1340 2506 1171 2507 1340 2507 1170 2507 1170 2508 1340 2508 1357 2508 1170 2509 1357 2509 1270 2509 1357 2510 1360 2510 1270 2510 1270 2511 1360 2511 1271 2511 1270 2512 1271 2512 1272 2512 1272 2513 1271 2513 1359 2513 1272 2514 1359 2514 1166 2514 1166 2515 1359 2515 1362 2515 1166 2516 1362 2516 1273 2516 1273 2517 1362 2517 1361 2517 1273 2518 1361 2518 1165 2518 1165 2519 1361 2519 1274 2519 1165 2520 1274 2520 1183 2520 1183 2521 1274 2521 1279 2521 1401 2522 1188 2522 1275 2522 1275 2523 1188 2523 1189 2523 1275 2524 1189 2524 1276 2524 1276 2525 1189 2525 1277 2525 1276 2526 1277 2526 1398 2526 1398 2527 1277 2527 1187 2527 1398 2528 1187 2528 1395 2528 1395 2529 1187 2529 1185 2529 1395 2530 1185 2530 1278 2530 1278 2531 1185 2531 1280 2531 1278 2532 1280 2532 1279 2532 1279 2533 1280 2533 1183 2533 1404 2534 1210 2534 1281 2534 1281 2535 1210 2535 1283 2535 1281 2536 1283 2536 1282 2536 1282 2537 1283 2537 1199 2537 1282 2538 1199 2538 1402 2538 1402 2539 1199 2539 1182 2539 1402 2540 1182 2540 1401 2540 1401 2541 1182 2541 1284 2541 1401 2542 1284 2542 1188 2542 1210 2543 1404 2543 1285 2543 1285 2544 1404 2544 1287 2544 1285 2545 1287 2545 1286 2545 1286 2546 1287 2546 1434 2546 1286 2547 1434 2547 1288 2547 1288 2548 1434 2548 1436 2548 1288 2549 1436 2549 1244 2549 1244 2550 1436 2550 1437 2550 1244 2551 1437 2551 1290 2551 1290 2552 1437 2552 1289 2552 1290 2553 1289 2553 1291 2553 1291 2554 1289 2554 1440 2554 1291 2555 1440 2555 1293 2555 1293 2556 1440 2556 1292 2556 1293 2557 1292 2557 1240 2557 1240 2558 1292 2558 1294 2558 1240 2559 1294 2559 1296 2559 1296 2560 1294 2560 1295 2560 1296 2561 1295 2561 1238 2561 1238 2562 1295 2562 1297 2562 1238 2563 1297 2563 1298 2563 1298 2564 1297 2564 1299 2564 1298 2565 1299 2565 1300 2565 1300 2566 1299 2566 1249 2566 1249 2567 1301 2567 1302 2567 1301 2568 1442 2568 1316 2568 1442 2569 1456 2569 1303 2569 1305 2570 1317 2570 1316 2570 1442 2571 1303 2571 1316 2571 1316 2572 1303 2572 1304 2572 1316 2573 1304 2573 1305 2573 1305 2574 1306 2574 1317 2574 1317 2575 1306 2575 1488 2575 1317 2576 1488 2576 1307 2576 1488 2577 1486 2577 1307 2577 1307 2578 1486 2578 1485 2578 1307 2579 1485 2579 1309 2579 1311 2580 1308 2580 1319 2580 1485 2581 1482 2581 1309 2581 1309 2582 1482 2582 1310 2582 1309 2583 1310 2583 1319 2583 1319 2584 1310 2584 1447 2584 1319 2585 1447 2585 1311 2585 1474 2586 1313 2586 1323 2586 1311 2587 1490 2587 1308 2587 1308 2588 1490 2588 1471 2588 1308 2589 1471 2589 1323 2589 1323 2590 1471 2590 1473 2590 1323 2591 1473 2591 1474 2591 1314 2592 1315 2592 1312 2592 1312 2593 1315 2593 1313 2593 1312 2594 1313 2594 1475 2594 1475 2595 1313 2595 1474 2595 1314 2596 1338 2596 1315 2596 1315 2597 1338 2597 1335 2597 1315 2598 1335 2598 1334 2598 1301 2599 1316 2599 1302 2599 1302 2600 1316 2600 1317 2600 1302 2601 1317 2601 1318 2601 1318 2602 1317 2602 1307 2602 1318 2603 1307 2603 1326 2603 1326 2604 1307 2604 1309 2604 1326 2605 1309 2605 1328 2605 1328 2606 1309 2606 1319 2606 1328 2607 1319 2607 1320 2607 1320 2608 1319 2608 1308 2608 1320 2609 1308 2609 1321 2609 1321 2610 1308 2610 1323 2610 1321 2611 1323 2611 1322 2611 1322 2612 1323 2612 1313 2612 1322 2613 1313 2613 1332 2613 1332 2614 1313 2614 1315 2614 1332 2615 1315 2615 1324 2615 1324 2616 1315 2616 1334 2616 1324 2617 1334 2617 1325 2617 1249 2618 1302 2618 1251 2618 1251 2619 1302 2619 1318 2619 1251 2620 1318 2620 1252 2620 1252 2621 1318 2621 1326 2621 1252 2622 1326 2622 1255 2622 1255 2623 1326 2623 1328 2623 1255 2624 1328 2624 1327 2624 1327 2625 1328 2625 1320 2625 1327 2626 1320 2626 1329 2626 1329 2627 1320 2627 1321 2627 1329 2628 1321 2628 1330 2628 1330 2629 1321 2629 1322 2629 1330 2630 1322 2630 1331 2630 1331 2631 1322 2631 1332 2631 1331 2632 1332 2632 1261 2632 1261 2633 1332 2633 1324 2633 1261 2634 1324 2634 1260 2634 1260 2635 1324 2635 1325 2635 1260 2636 1325 2636 1257 2636 1263 2637 1257 2637 1325 2637 1263 2638 1325 2638 1333 2638 1333 2639 1325 2639 1334 2639 1333 2640 1334 2640 1336 2640 1336 2641 1334 2641 1335 2641 1336 2642 1335 2642 1337 2642 1337 2643 1335 2643 1338 2643 1337 2644 1338 2644 1344 2644 1362 2645 1359 2645 1339 2645 1340 2646 1268 2646 1349 2646 1267 2647 1266 2647 1346 2647 1479 2648 1480 2648 1355 2648 1355 2649 1480 2649 1341 2649 1355 2650 1341 2650 1342 2650 1342 2651 1341 2651 1343 2651 1342 2652 1343 2652 1358 2652 1358 2653 1343 2653 1339 2653 1344 2654 1478 2654 1337 2654 1337 2655 1478 2655 1347 2655 1337 2656 1347 2656 1336 2656 1336 2657 1347 2657 1345 2657 1336 2658 1345 2658 1333 2658 1333 2659 1345 2659 1346 2659 1333 2660 1346 2660 1263 2660 1263 2661 1346 2661 1266 2661 1478 2662 1352 2662 1347 2662 1347 2663 1352 2663 1351 2663 1347 2664 1351 2664 1345 2664 1345 2665 1351 2665 1348 2665 1345 2666 1348 2666 1346 2666 1346 2667 1348 2667 1349 2667 1346 2668 1349 2668 1267 2668 1267 2669 1349 2669 1268 2669 1357 2670 1340 2670 1350 2670 1350 2671 1340 2671 1349 2671 1350 2672 1349 2672 1356 2672 1356 2673 1349 2673 1348 2673 1356 2674 1348 2674 1354 2674 1354 2675 1348 2675 1351 2675 1354 2676 1351 2676 1353 2676 1353 2677 1351 2677 1352 2677 1353 2678 1479 2678 1354 2678 1354 2679 1479 2679 1355 2679 1354 2680 1355 2680 1356 2680 1356 2681 1355 2681 1342 2681 1356 2682 1342 2682 1350 2682 1350 2683 1342 2683 1358 2683 1350 2684 1358 2684 1357 2684 1357 2685 1358 2685 1360 2685 1339 2686 1359 2686 1358 2686 1358 2687 1359 2687 1271 2687 1358 2688 1271 2688 1360 2688 1361 2689 1362 2689 1363 2689 1363 2690 1362 2690 1339 2690 1363 2691 1339 2691 1368 2691 1368 2692 1339 2692 1343 2692 1368 2693 1343 2693 1364 2693 1364 2694 1343 2694 1341 2694 1364 2695 1341 2695 1365 2695 1365 2696 1341 2696 1480 2696 1365 2697 1366 2697 1364 2697 1364 2698 1366 2698 1367 2698 1364 2699 1367 2699 1368 2699 1368 2700 1367 2700 1371 2700 1368 2701 1371 2701 1363 2701 1363 2702 1371 2702 1369 2702 1363 2703 1369 2703 1361 2703 1361 2704 1369 2704 1274 2704 1279 2705 1274 2705 1369 2705 1279 2706 1369 2706 1370 2706 1370 2707 1369 2707 1371 2707 1370 2708 1371 2708 1372 2708 1372 2709 1371 2709 1367 2709 1372 2710 1367 2710 1374 2710 1374 2711 1367 2711 1366 2711 1374 2712 1366 2712 1373 2712 1373 2713 1461 2713 1374 2713 1374 2714 1461 2714 1375 2714 1374 2715 1375 2715 1372 2715 1279 2716 1370 2716 1387 2716 1387 2717 1370 2717 1372 2717 1461 2718 1496 2718 1375 2718 1375 2719 1496 2719 1495 2719 1375 2720 1495 2720 1376 2720 1495 2721 1494 2721 1376 2721 1376 2722 1494 2722 1377 2722 1376 2723 1377 2723 1389 2723 1380 2724 1381 2724 1379 2724 1377 2725 1378 2725 1389 2725 1389 2726 1378 2726 1492 2726 1389 2727 1492 2727 1379 2727 1379 2728 1492 2728 1491 2728 1379 2729 1491 2729 1380 2729 1380 2730 1505 2730 1381 2730 1381 2731 1505 2731 1504 2731 1381 2732 1504 2732 1382 2732 1504 2733 1503 2733 1382 2733 1382 2734 1503 2734 1383 2734 1382 2735 1383 2735 1390 2735 1383 2736 1384 2736 1390 2736 1390 2737 1384 2737 1501 2737 1390 2738 1501 2738 1385 2738 1501 2739 1499 2739 1385 2739 1385 2740 1499 2740 1497 2740 1385 2741 1497 2741 1393 2741 1497 2742 1445 2742 1393 2742 1393 2743 1445 2743 1444 2743 1393 2744 1444 2744 1386 2744 1372 2745 1375 2745 1387 2745 1387 2746 1375 2746 1376 2746 1387 2747 1376 2747 1388 2747 1388 2748 1376 2748 1389 2748 1388 2749 1389 2749 1396 2749 1396 2750 1389 2750 1379 2750 1396 2751 1379 2751 1397 2751 1397 2752 1379 2752 1381 2752 1397 2753 1381 2753 1399 2753 1399 2754 1381 2754 1382 2754 1399 2755 1382 2755 1400 2755 1400 2756 1382 2756 1390 2756 1400 2757 1390 2757 1391 2757 1391 2758 1390 2758 1385 2758 1391 2759 1385 2759 1403 2759 1403 2760 1385 2760 1393 2760 1403 2761 1393 2761 1392 2761 1392 2762 1393 2762 1386 2762 1392 2763 1386 2763 1394 2763 1279 2764 1387 2764 1278 2764 1278 2765 1387 2765 1388 2765 1278 2766 1388 2766 1395 2766 1395 2767 1388 2767 1396 2767 1395 2768 1396 2768 1398 2768 1398 2769 1396 2769 1397 2769 1398 2770 1397 2770 1276 2770 1276 2771 1397 2771 1399 2771 1276 2772 1399 2772 1275 2772 1275 2773 1399 2773 1400 2773 1275 2774 1400 2774 1401 2774 1401 2775 1400 2775 1391 2775 1401 2776 1391 2776 1402 2776 1402 2777 1391 2777 1403 2777 1402 2778 1403 2778 1282 2778 1282 2779 1403 2779 1392 2779 1282 2780 1392 2780 1281 2780 1281 2781 1392 2781 1394 2781 1281 2782 1394 2782 1404 2782 1287 2783 1404 2783 1394 2783 1287 2784 1394 2784 1407 2784 1407 2785 1394 2785 1386 2785 1407 2786 1386 2786 1405 2786 1405 2787 1386 2787 1444 2787 1405 2788 1444 2788 1406 2788 1287 2789 1407 2789 1433 2789 1407 2790 1405 2790 1410 2790 1405 2791 1406 2791 1408 2791 1454 2792 1411 2792 1410 2792 1405 2793 1408 2793 1410 2793 1410 2794 1408 2794 1409 2794 1410 2795 1409 2795 1454 2795 1415 2796 1417 2796 1413 2796 1454 2797 1412 2797 1411 2797 1411 2798 1412 2798 1453 2798 1411 2799 1453 2799 1413 2799 1413 2800 1453 2800 1414 2800 1413 2801 1414 2801 1415 2801 1469 2802 1427 2802 1425 2802 1415 2803 1451 2803 1417 2803 1417 2804 1451 2804 1416 2804 1417 2805 1416 2805 1425 2805 1425 2806 1416 2806 1418 2806 1425 2807 1418 2807 1469 2807 1469 2808 1419 2808 1427 2808 1427 2809 1419 2809 1467 2809 1427 2810 1467 2810 1429 2810 1463 2811 1423 2811 1422 2811 1467 2812 1420 2812 1429 2812 1429 2813 1420 2813 1421 2813 1429 2814 1421 2814 1422 2814 1422 2815 1421 2815 1464 2815 1422 2816 1464 2816 1463 2816 1463 2817 1446 2817 1423 2817 1423 2818 1446 2818 1443 2818 1423 2819 1443 2819 1431 2819 1407 2820 1410 2820 1433 2820 1433 2821 1410 2821 1411 2821 1433 2822 1411 2822 1435 2822 1435 2823 1411 2823 1413 2823 1435 2824 1413 2824 1424 2824 1424 2825 1413 2825 1417 2825 1424 2826 1417 2826 1438 2826 1438 2827 1417 2827 1425 2827 1438 2828 1425 2828 1439 2828 1439 2829 1425 2829 1427 2829 1439 2830 1427 2830 1426 2830 1426 2831 1427 2831 1429 2831 1426 2832 1429 2832 1428 2832 1428 2833 1429 2833 1422 2833 1428 2834 1422 2834 1430 2834 1430 2835 1422 2835 1423 2835 1430 2836 1423 2836 1432 2836 1432 2837 1423 2837 1431 2837 1432 2838 1431 2838 1441 2838 1287 2839 1433 2839 1434 2839 1434 2840 1433 2840 1435 2840 1434 2841 1435 2841 1436 2841 1436 2842 1435 2842 1424 2842 1436 2843 1424 2843 1437 2843 1437 2844 1424 2844 1438 2844 1437 2845 1438 2845 1289 2845 1289 2846 1438 2846 1439 2846 1289 2847 1439 2847 1440 2847 1440 2848 1439 2848 1426 2848 1440 2849 1426 2849 1292 2849 1292 2850 1426 2850 1428 2850 1292 2851 1428 2851 1294 2851 1294 2852 1428 2852 1430 2852 1294 2853 1430 2853 1295 2853 1295 2854 1430 2854 1432 2854 1295 2855 1432 2855 1297 2855 1297 2856 1432 2856 1441 2856 1297 2857 1441 2857 1299 2857 1249 2858 1299 2858 1441 2858 1249 2859 1441 2859 1301 2859 1301 2860 1441 2860 1431 2860 1301 2861 1431 2861 1442 2861 1442 2862 1431 2862 1443 2862 1442 2863 1443 2863 1456 2863 1406 2864 1444 2864 1588 2864 1588 2865 1444 2865 1445 2865 1588 2866 1445 2866 1498 2866 1456 2867 1443 2867 1591 2867 1591 2868 1443 2868 1446 2868 1591 2869 1446 2869 1462 2869 1555 2870 1447 2870 1310 2870 1588 2871 1448 2871 1406 2871 1406 2872 1448 2872 1449 2872 1406 2873 1449 2873 1408 2873 1408 2874 1449 2874 1599 2874 1408 2875 1599 2875 1409 2875 1409 2876 1599 2876 1598 2876 1470 2877 1416 2877 1450 2877 1450 2878 1416 2878 1451 2878 1450 2879 1451 2879 1602 2879 1602 2880 1451 2880 1415 2880 1602 2881 1415 2881 1452 2881 1452 2882 1415 2882 1414 2882 1452 2883 1414 2883 1603 2883 1603 2884 1414 2884 1453 2884 1603 2885 1453 2885 1604 2885 1604 2886 1453 2886 1412 2886 1604 2887 1412 2887 1598 2887 1598 2888 1412 2888 1454 2888 1598 2889 1454 2889 1409 2889 1591 2890 1455 2890 1456 2890 1456 2891 1455 2891 1457 2891 1456 2892 1457 2892 1303 2892 1303 2893 1457 2893 1458 2893 1303 2894 1458 2894 1304 2894 1304 2895 1458 2895 1459 2895 1472 2896 1471 2896 1490 2896 1373 2897 1460 2897 1461 2897 1461 2898 1460 2898 1568 2898 1461 2899 1568 2899 1496 2899 1496 2900 1568 2900 1493 2900 1446 2901 1463 2901 1462 2901 1462 2902 1463 2902 1464 2902 1462 2903 1464 2903 1614 2903 1614 2904 1464 2904 1421 2904 1614 2905 1421 2905 1465 2905 1465 2906 1421 2906 1420 2906 1465 2907 1420 2907 1466 2907 1466 2908 1420 2908 1467 2908 1466 2909 1467 2909 1608 2909 1608 2910 1467 2910 1419 2910 1608 2911 1419 2911 1468 2911 1468 2912 1419 2912 1469 2912 1468 2913 1469 2913 1470 2913 1470 2914 1469 2914 1418 2914 1470 2915 1418 2915 1416 2915 1471 2916 1472 2916 1473 2916 1473 2917 1472 2917 1560 2917 1473 2918 1560 2918 1474 2918 1474 2919 1560 2919 1559 2919 1474 2920 1559 2920 1475 2920 1475 2921 1559 2921 1563 2921 1475 2922 1563 2922 1312 2922 1312 2923 1563 2923 1314 2923 1314 2924 1563 2924 1536 2924 1314 2925 1536 2925 1338 2925 1338 2926 1536 2926 1476 2926 1338 2927 1476 2927 1344 2927 1344 2928 1476 2928 1533 2928 1344 2929 1533 2929 1478 2929 1478 2930 1533 2930 1477 2930 1478 2931 1477 2931 1352 2931 1352 2932 1477 2932 1531 2932 1352 2933 1531 2933 1353 2933 1353 2934 1531 2934 1529 2934 1353 2935 1529 2935 1479 2935 1479 2936 1529 2936 1528 2936 1479 2937 1528 2937 1480 2937 1480 2938 1528 2938 1481 2938 1480 2939 1481 2939 1365 2939 1365 2940 1481 2940 1527 2940 1365 2941 1527 2941 1366 2941 1366 2942 1527 2942 1525 2942 1366 2943 1525 2943 1373 2943 1373 2944 1525 2944 1538 2944 1373 2945 1538 2945 1460 2945 1555 2946 1310 2946 1483 2946 1483 2947 1310 2947 1482 2947 1483 2948 1482 2948 1548 2948 1548 2949 1482 2949 1485 2949 1548 2950 1485 2950 1484 2950 1484 2951 1485 2951 1486 2951 1484 2952 1486 2952 1487 2952 1487 2953 1486 2953 1488 2953 1487 2954 1488 2954 1543 2954 1543 2955 1488 2955 1306 2955 1543 2956 1306 2956 1459 2956 1459 2957 1306 2957 1305 2957 1459 2958 1305 2958 1304 2958 1447 2959 1555 2959 1311 2959 1311 2960 1555 2960 1489 2960 1311 2961 1489 2961 1490 2961 1490 2962 1489 2962 1553 2962 1490 2963 1553 2963 1472 2963 1578 2964 1380 2964 1564 2964 1564 2965 1380 2965 1491 2965 1564 2966 1491 2966 1575 2966 1575 2967 1491 2967 1492 2967 1575 2968 1492 2968 1572 2968 1572 2969 1492 2969 1378 2969 1572 2970 1378 2970 1573 2970 1573 2971 1378 2971 1377 2971 1573 2972 1377 2972 1571 2972 1571 2973 1377 2973 1494 2973 1571 2974 1494 2974 1493 2974 1493 2975 1494 2975 1495 2975 1493 2976 1495 2976 1496 2976 1445 2977 1497 2977 1498 2977 1498 2978 1497 2978 1499 2978 1498 2979 1499 2979 1500 2979 1500 2980 1499 2980 1501 2980 1500 2981 1501 2981 1502 2981 1502 2982 1501 2982 1384 2982 1502 2983 1384 2983 1583 2983 1583 2984 1384 2984 1383 2984 1583 2985 1383 2985 1579 2985 1579 2986 1383 2986 1503 2986 1579 2987 1503 2987 1580 2987 1580 2988 1503 2988 1504 2988 1580 2989 1504 2989 1578 2989 1578 2990 1504 2990 1505 2990 1578 2991 1505 2991 1380 2991 1506 2992 1507 2992 1508 2992 1508 2993 1507 2993 1509 2993 1508 2994 1509 2994 1535 2994 1535 2995 1509 2995 1532 2995 1535 2996 1532 2996 1476 2996 1476 2997 1532 2997 1533 2997 1510 2998 1511 2998 381 2998 381 2999 1511 2999 1512 2999 381 3000 1512 3000 382 3000 382 3001 1512 3001 1513 3001 382 3002 1513 3002 383 3002 383 3003 1513 3003 1519 3003 383 3004 1519 3004 384 3004 384 3005 1519 3005 1521 3005 384 3006 1521 3006 1514 3006 1514 3007 1521 3007 1522 3007 1514 3008 1522 3008 1515 3008 1515 3009 1522 3009 1523 3009 1515 3010 1523 3010 1507 3010 1507 3011 1523 3011 1509 3011 1511 3012 1516 3012 1512 3012 1512 3013 1516 3013 1517 3013 1512 3014 1517 3014 1513 3014 1513 3015 1517 3015 1526 3015 1513 3016 1526 3016 1519 3016 1519 3017 1526 3017 1518 3017 1519 3018 1518 3018 1521 3018 1521 3019 1518 3019 1520 3019 1521 3020 1520 3020 1522 3020 1522 3021 1520 3021 1524 3021 1522 3022 1524 3022 1523 3022 1523 3023 1524 3023 1530 3023 1523 3024 1530 3024 1509 3024 1509 3025 1530 3025 1532 3025 1516 3026 1525 3026 1517 3026 1517 3027 1525 3027 1527 3027 1517 3028 1527 3028 1526 3028 1526 3029 1527 3029 1481 3029 1526 3030 1481 3030 1518 3030 1518 3031 1481 3031 1528 3031 1518 3032 1528 3032 1520 3032 1520 3033 1528 3033 1529 3033 1520 3034 1529 3034 1524 3034 1524 3035 1529 3035 1531 3035 1524 3036 1531 3036 1530 3036 1530 3037 1531 3037 1477 3037 1530 3038 1477 3038 1532 3038 1532 3039 1477 3039 1533 3039 251 3040 1506 3040 1561 3040 1561 3041 1506 3041 1508 3041 1561 3042 1508 3042 1534 3042 1534 3043 1508 3043 1535 3043 1534 3044 1535 3044 1536 3044 1536 3045 1535 3045 1476 3045 1510 3046 345 3046 1511 3046 1511 3047 345 3047 1567 3047 1511 3048 1567 3048 1516 3048 1516 3049 1567 3049 1537 3049 1516 3050 1537 3050 1525 3050 1525 3051 1537 3051 1538 3051 1555 3052 1483 3052 1550 3052 1557 3053 1542 3053 1558 3053 252 3054 251 3054 1561 3054 1541 3055 252 3055 1539 3055 1549 3056 1545 3056 1540 3056 1541 3057 1542 3057 254 3057 254 3058 1542 3058 1557 3058 254 3059 1557 3059 256 3059 1546 3060 1544 3060 1545 3060 1543 3061 1459 3061 1546 3061 1546 3062 1459 3062 1458 3062 1546 3063 1458 3063 1544 3063 1544 3064 1458 3064 1457 3064 1544 3065 1457 3065 1455 3065 1545 3066 1549 3066 1546 3066 1546 3067 1549 3067 1547 3067 1546 3068 1547 3068 1543 3068 1548 3069 1484 3069 1547 3069 1547 3070 1484 3070 1487 3070 1547 3071 1487 3071 1543 3071 1540 3072 257 3072 1549 3072 1549 3073 257 3073 1552 3073 1549 3074 1552 3074 1547 3074 1547 3075 1552 3075 1550 3075 1547 3076 1550 3076 1548 3076 1548 3077 1550 3077 1483 3077 257 3078 1551 3078 1552 3078 1552 3079 1551 3079 1556 3079 1552 3080 1556 3080 1550 3080 1550 3081 1556 3081 1554 3081 1550 3082 1554 3082 1555 3082 1472 3083 1553 3083 1554 3083 1554 3084 1553 3084 1489 3084 1554 3085 1489 3085 1555 3085 1551 3086 256 3086 1556 3086 1556 3087 256 3087 1557 3087 1556 3088 1557 3088 1554 3088 1554 3089 1557 3089 1558 3089 1554 3090 1558 3090 1472 3090 1472 3091 1558 3091 1560 3091 1562 3092 1563 3092 1559 3092 1541 3093 1539 3093 1542 3093 1542 3094 1539 3094 1562 3094 1542 3095 1562 3095 1558 3095 1558 3096 1562 3096 1559 3096 1558 3097 1559 3097 1560 3097 252 3098 1561 3098 1539 3098 1539 3099 1561 3099 1534 3099 1539 3100 1534 3100 1562 3100 1562 3101 1534 3101 1536 3101 1562 3102 1536 3102 1563 3102 1578 3103 1564 3103 1576 3103 1566 3104 1565 3104 1585 3104 337 3105 334 3105 1586 3105 338 3106 337 3106 1587 3106 1574 3107 1567 3107 345 3107 338 3108 1565 3108 339 3108 339 3109 1565 3109 1566 3109 339 3110 1566 3110 342 3110 1570 3111 1537 3111 1567 3111 1571 3112 1493 3112 1570 3112 1570 3113 1493 3113 1568 3113 1570 3114 1568 3114 1537 3114 1537 3115 1568 3115 1460 3115 1537 3116 1460 3116 1538 3116 1567 3117 1574 3117 1570 3117 1570 3118 1574 3118 1569 3118 1570 3119 1569 3119 1571 3119 1575 3120 1572 3120 1569 3120 1569 3121 1572 3121 1573 3121 1569 3122 1573 3122 1571 3122 345 3123 344 3123 1574 3123 1574 3124 344 3124 1577 3124 1574 3125 1577 3125 1569 3125 1569 3126 1577 3126 1576 3126 1569 3127 1576 3127 1575 3127 1575 3128 1576 3128 1564 3128 344 3129 343 3129 1577 3129 1577 3130 343 3130 1581 3130 1577 3131 1581 3131 1576 3131 1576 3132 1581 3132 1582 3132 1576 3133 1582 3133 1578 3133 1583 3134 1579 3134 1582 3134 1582 3135 1579 3135 1580 3135 1582 3136 1580 3136 1578 3136 343 3137 342 3137 1581 3137 1581 3138 342 3138 1566 3138 1581 3139 1566 3139 1582 3139 1582 3140 1566 3140 1585 3140 1582 3141 1585 3141 1583 3141 1583 3142 1585 3142 1502 3142 1584 3143 1498 3143 1500 3143 338 3144 1587 3144 1565 3144 1565 3145 1587 3145 1584 3145 1565 3146 1584 3146 1585 3146 1585 3147 1584 3147 1500 3147 1585 3148 1500 3148 1502 3148 337 3149 1586 3149 1587 3149 1587 3150 1586 3150 1592 3150 1587 3151 1592 3151 1584 3151 1584 3152 1592 3152 1588 3152 1584 3153 1588 3153 1498 3153 291 3154 1540 3154 1589 3154 1589 3155 1540 3155 1545 3155 1589 3156 1545 3156 1590 3156 1590 3157 1545 3157 1544 3157 1590 3158 1544 3158 1591 3158 1591 3159 1544 3159 1455 3159 334 3160 333 3160 1586 3160 1586 3161 333 3161 1595 3161 1586 3162 1595 3162 1592 3162 1592 3163 1595 3163 1593 3163 1592 3164 1593 3164 1588 3164 1588 3165 1593 3165 1448 3165 1614 3166 1465 3166 1613 3166 1470 3167 1450 3167 1594 3167 1612 3168 1615 3168 1616 3168 1596 3169 291 3169 1589 3169 1605 3170 1595 3170 333 3170 1596 3171 1615 3171 1597 3171 1597 3172 1615 3172 1612 3172 1597 3173 1612 3173 294 3173 1600 3174 1593 3174 1595 3174 1604 3175 1598 3175 1600 3175 1600 3176 1598 3176 1599 3176 1600 3177 1599 3177 1593 3177 1593 3178 1599 3178 1449 3178 1593 3179 1449 3179 1448 3179 1595 3180 1605 3180 1600 3180 1600 3181 1605 3181 1601 3181 1600 3182 1601 3182 1604 3182 1602 3183 1452 3183 1601 3183 1601 3184 1452 3184 1603 3184 1601 3185 1603 3185 1604 3185 333 3186 298 3186 1605 3186 1605 3187 298 3187 1606 3187 1605 3188 1606 3188 1601 3188 1601 3189 1606 3189 1594 3189 1601 3190 1594 3190 1602 3190 1602 3191 1594 3191 1450 3191 298 3192 1610 3192 1606 3192 1606 3193 1610 3193 1607 3193 1606 3194 1607 3194 1594 3194 1594 3195 1607 3195 1609 3195 1594 3196 1609 3196 1470 3196 1466 3197 1608 3197 1609 3197 1609 3198 1608 3198 1468 3198 1609 3199 1468 3199 1470 3199 1610 3200 295 3200 1607 3200 1607 3201 295 3201 1611 3201 1607 3202 1611 3202 1609 3202 1609 3203 1611 3203 1613 3203 1609 3204 1613 3204 1466 3204 1466 3205 1613 3205 1465 3205 295 3206 294 3206 1611 3206 1611 3207 294 3207 1612 3207 1611 3208 1612 3208 1613 3208 1613 3209 1612 3209 1616 3209 1613 3210 1616 3210 1614 3210 1614 3211 1616 3211 1462 3211 1596 3212 1589 3212 1615 3212 1615 3213 1589 3213 1590 3213 1615 3214 1590 3214 1616 3214 1616 3215 1590 3215 1591 3215 1616 3216 1591 3216 1462 3216 30 3217 31 3217 1617 3217 1617 3218 31 3218 1643 3218 1617 3219 1643 3219 1624 3219 1624 3220 1643 3220 1618 3220 1624 3221 1618 3221 1619 3221 1619 3222 1618 3222 1644 3222 1633 3223 24 3223 1628 3223 1620 3224 1625 3224 1621 3224 1632 3225 1636 3225 1634 3225 1622 3226 283 3226 1649 3226 281 3227 1622 3227 1639 3227 279 3228 281 3228 1640 3228 1623 3229 1624 3229 1619 3229 279 3230 1636 3230 278 3230 278 3231 1636 3231 1632 3231 278 3232 1632 3232 1631 3232 1617 3233 1624 3233 1627 3233 1627 3234 1624 3234 1623 3234 1627 3235 1623 3235 1621 3235 1625 3236 26 3236 1621 3236 1621 3237 26 3237 1626 3237 1621 3238 1626 3238 1627 3238 1627 3239 1626 3239 29 3239 1627 3240 29 3240 1617 3240 1617 3241 29 3241 30 3241 24 3242 1620 3242 1628 3242 1628 3243 1620 3243 1621 3243 1628 3244 1621 3244 1629 3244 1629 3245 1621 3245 1623 3245 1629 3246 1623 3246 1630 3246 1630 3247 1623 3247 1619 3247 1630 3248 1631 3248 1629 3248 1629 3249 1631 3249 1632 3249 1629 3250 1632 3250 1628 3250 1628 3251 1632 3251 1634 3251 1628 3252 1634 3252 1633 3252 1633 3253 1634 3253 1638 3253 1635 3254 43 3254 1637 3254 1637 3255 43 3255 41 3255 279 3256 1640 3256 1636 3256 1636 3257 1640 3257 1637 3257 1636 3258 1637 3258 1634 3258 1634 3259 1637 3259 41 3259 1634 3260 41 3260 1638 3260 1641 3261 36 3261 37 3261 281 3262 1639 3262 1640 3262 1640 3263 1639 3263 1641 3263 1640 3264 1641 3264 1637 3264 1637 3265 1641 3265 37 3265 1637 3266 37 3266 1635 3266 1648 3267 33 3267 34 3267 1622 3268 1649 3268 1639 3268 1639 3269 1649 3269 1648 3269 1639 3270 1648 3270 1641 3270 1641 3271 1648 3271 34 3271 1641 3272 34 3272 36 3272 31 3273 1642 3273 1643 3273 1643 3274 1642 3274 1670 3274 1643 3275 1670 3275 1618 3275 1618 3276 1670 3276 1654 3276 1618 3277 1654 3277 1644 3277 1644 3278 1654 3278 1645 3278 28 3279 33 3279 1646 3279 1646 3280 33 3280 1648 3280 1646 3281 1648 3281 1647 3281 1647 3282 1648 3282 1649 3282 1647 3283 1649 3283 284 3283 284 3284 1649 3284 283 3284 1650 3285 48 3285 1669 3285 49 3286 1651 3286 1665 3286 51 3287 1662 3287 1661 3287 1666 3288 1652 3288 1669 3288 1653 3289 1645 3289 1654 3289 1667 3290 1653 3290 1668 3290 1667 3291 1652 3291 411 3291 411 3292 1652 3292 1666 3292 411 3293 1666 3293 410 3293 1655 3294 1691 3294 1692 3294 69 3295 1691 3295 1656 3295 1656 3296 1691 3296 1655 3296 1656 3297 1655 3297 66 3297 66 3298 1655 3298 1657 3298 60 3299 61 3299 1660 3299 1660 3300 61 3300 62 3300 62 3301 1657 3301 1660 3301 1660 3302 1657 3302 1655 3302 1660 3303 1655 3303 1659 3303 1659 3304 1655 3304 1692 3304 1659 3305 1692 3305 376 3305 376 3306 1658 3306 1659 3306 1659 3307 1658 3307 1664 3307 1659 3308 1664 3308 1660 3308 1660 3309 1664 3309 1661 3309 1660 3310 1661 3310 60 3310 60 3311 1661 3311 1662 3311 1651 3312 51 3312 1665 3312 1665 3313 51 3313 1661 3313 1665 3314 1661 3314 1663 3314 1663 3315 1661 3315 1664 3315 1663 3316 1664 3316 409 3316 409 3317 1664 3317 1658 3317 409 3318 410 3318 1663 3318 1663 3319 410 3319 1666 3319 1663 3320 1666 3320 1665 3320 1665 3321 1666 3321 1669 3321 1665 3322 1669 3322 49 3322 49 3323 1669 3323 48 3323 1671 3324 45 3324 46 3324 1667 3325 1668 3325 1652 3325 1652 3326 1668 3326 1671 3326 1652 3327 1671 3327 1669 3327 1669 3328 1671 3328 46 3328 1669 3329 46 3329 1650 3329 1670 3330 1642 3330 1672 3330 1653 3331 1654 3331 1668 3331 1668 3332 1654 3332 1670 3332 1668 3333 1670 3333 1671 3333 1671 3334 1670 3334 1672 3334 1671 3335 1672 3335 45 3335 20 3336 22 3336 1686 3336 1673 3337 3 3337 1685 3337 9 3338 1682 3338 1684 3338 11 3339 14 3339 1681 3339 1675 3340 1674 3340 1695 3340 1677 3341 1647 3341 284 3341 327 3342 1674 3342 1676 3342 1676 3343 1674 3343 1675 3343 1676 3344 1675 3344 326 3344 1646 3345 1647 3345 1678 3345 1678 3346 1647 3346 1677 3346 1678 3347 1677 3347 1681 3347 14 3348 13 3348 1681 3348 1681 3349 13 3349 0 3349 1681 3350 0 3350 1678 3350 1678 3351 0 3351 1679 3351 1678 3352 1679 3352 1646 3352 1646 3353 1679 3353 28 3353 284 3354 319 3354 1677 3354 1677 3355 319 3355 1680 3355 1677 3356 1680 3356 1681 3356 1681 3357 1680 3357 1684 3357 1681 3358 1684 3358 11 3358 11 3359 1684 3359 1682 3359 319 3360 321 3360 1680 3360 1680 3361 321 3361 1683 3361 1680 3362 1683 3362 1684 3362 1684 3363 1683 3363 1685 3363 1684 3364 1685 3364 9 3364 9 3365 1685 3365 3 3365 321 3366 322 3366 1683 3366 1683 3367 322 3367 1689 3367 1683 3368 1689 3368 1685 3368 1685 3369 1689 3369 1687 3369 1685 3370 1687 3370 1673 3370 8 3371 7 3371 1687 3371 1687 3372 7 3372 4 3372 1687 3373 4 3373 1673 3373 22 3374 8 3374 1686 3374 1686 3375 8 3375 1687 3375 1686 3376 1687 3376 1688 3376 1688 3377 1687 3377 1689 3377 1688 3378 1689 3378 324 3378 324 3379 1689 3379 322 3379 324 3380 326 3380 1688 3380 1688 3381 326 3381 1675 3381 1688 3382 1675 3382 1686 3382 1686 3383 1675 3383 1695 3383 1686 3384 1695 3384 20 3384 20 3385 1695 3385 1694 3385 69 3386 1690 3386 1691 3386 1691 3387 1690 3387 1719 3387 1691 3388 1719 3388 1692 3388 1692 3389 1719 3389 1720 3389 1692 3390 1720 3390 376 3390 376 3391 1720 3391 375 3391 18 3392 1694 3392 1693 3392 1693 3393 1694 3393 1695 3393 1693 3394 1695 3394 1696 3394 1696 3395 1695 3395 1674 3395 1696 3396 1674 3396 1697 3396 1697 3397 1674 3397 327 3397 58 3398 57 3398 1715 3398 54 3399 53 3399 1714 3399 1698 3400 1709 3400 1710 3400 1699 3401 1700 3401 1705 3401 1713 3402 1702 3402 1715 3402 1701 3403 375 3403 1720 3403 372 3404 1701 3404 1721 3404 1703 3405 1696 3405 1697 3405 372 3406 1702 3406 371 3406 371 3407 1702 3407 1713 3407 371 3408 1713 3408 1712 3408 1693 3409 1696 3409 1706 3409 1706 3410 1696 3410 1703 3410 1706 3411 1703 3411 1705 3411 1700 3412 1704 3412 1705 3412 1705 3413 1704 3413 19 3413 1705 3414 19 3414 1706 3414 1706 3415 19 3415 1707 3415 1706 3416 1707 3416 1693 3416 1693 3417 1707 3417 18 3417 1697 3418 369 3418 1703 3418 1703 3419 369 3419 1708 3419 1703 3420 1708 3420 1705 3420 1705 3421 1708 3421 1710 3421 1705 3422 1710 3422 1699 3422 1699 3423 1710 3423 1709 3423 369 3424 370 3424 1708 3424 1708 3425 370 3425 1711 3425 1708 3426 1711 3426 1710 3426 1710 3427 1711 3427 1714 3427 1710 3428 1714 3428 1698 3428 1698 3429 1714 3429 53 3429 370 3430 1712 3430 1711 3430 1711 3431 1712 3431 1713 3431 1711 3432 1713 3432 1714 3432 1714 3433 1713 3433 1715 3433 1714 3434 1715 3434 54 3434 54 3435 1715 3435 57 3435 1717 3436 1716 3436 1718 3436 372 3437 1721 3437 1702 3437 1702 3438 1721 3438 1717 3438 1702 3439 1717 3439 1715 3439 1715 3440 1717 3440 1718 3440 1715 3441 1718 3441 58 3441 1719 3442 1690 3442 1722 3442 1701 3443 1720 3443 1721 3443 1721 3444 1720 3444 1719 3444 1721 3445 1719 3445 1717 3445 1717 3446 1719 3446 1722 3446 1717 3447 1722 3447 1716 3447 1723 3448 1724 3448 1725 3448 1725 3449 1724 3449 1734 3449 1728 3450 2126 3450 1727 3450 1723 3451 1725 3451 1726 3451 1726 3452 1725 3452 1735 3452 1726 3453 1735 3453 1727 3453 1727 3454 1735 3454 1782 3454 1727 3455 1782 3455 1728 3455 1760 3456 2093 3456 1729 3456 1730 3457 1760 3457 1731 3457 1759 3458 2090 3458 1733 3458 1730 3459 1731 3459 1732 3459 1732 3460 1731 3460 1762 3460 1732 3461 1762 3461 1733 3461 1733 3462 1762 3462 1757 3462 1733 3463 1757 3463 1759 3463 1734 3464 2060 3464 1725 3464 1725 3465 2060 3465 2077 3465 1725 3466 2077 3466 1735 3466 1735 3467 2077 3467 1736 3467 1735 3468 1736 3468 1781 3468 1781 3469 1736 3469 2079 3469 1781 3470 2079 3470 1737 3470 1737 3471 2079 3471 1738 3471 1737 3472 1738 3472 1779 3472 1779 3473 1738 3473 1739 3473 1779 3474 1739 3474 1740 3474 1740 3475 1739 3475 2081 3475 1740 3476 2081 3476 1778 3476 1778 3477 2081 3477 1741 3477 1778 3478 1741 3478 1742 3478 1742 3479 1741 3479 2082 3479 1742 3480 2082 3480 1743 3480 1743 3481 2082 3481 1744 3481 1743 3482 1744 3482 1777 3482 1777 3483 1744 3483 2084 3483 1777 3484 2084 3484 1745 3484 1745 3485 2084 3485 2085 3485 1745 3486 2085 3486 1776 3486 1776 3487 2085 3487 1746 3487 1776 3488 1746 3488 1773 3488 1773 3489 1746 3489 2061 3489 1773 3490 2061 3490 1747 3490 1747 3491 2061 3491 2062 3491 1747 3492 2062 3492 1770 3492 1770 3493 2062 3493 1749 3493 1770 3494 1749 3494 1748 3494 1748 3495 1749 3495 2063 3495 1748 3496 2063 3496 1750 3496 1750 3497 2063 3497 1751 3497 1750 3498 1751 3498 1768 3498 1768 3499 1751 3499 2066 3499 1768 3500 2066 3500 1767 3500 1767 3501 2066 3501 2067 3501 1767 3502 2067 3502 1766 3502 1766 3503 2067 3503 2068 3503 1766 3504 2068 3504 1752 3504 1752 3505 2068 3505 1753 3505 1752 3506 1753 3506 1764 3506 1764 3507 1753 3507 2071 3507 1764 3508 2071 3508 1763 3508 1763 3509 2071 3509 1754 3509 1763 3510 1754 3510 1755 3510 1755 3511 1754 3511 1756 3511 1755 3512 1756 3512 1762 3512 1762 3513 1756 3513 2076 3513 1762 3514 2076 3514 1757 3514 1757 3515 2076 3515 1758 3515 1757 3516 1758 3516 1759 3516 1760 3517 1729 3517 1731 3517 1731 3518 1729 3518 1761 3518 1731 3519 1761 3519 1762 3519 1762 3520 1761 3520 2094 3520 1762 3521 2094 3521 1755 3521 1755 3522 2094 3522 2095 3522 1755 3523 2095 3523 1763 3523 1763 3524 2095 3524 2097 3524 1763 3525 2097 3525 1764 3525 1764 3526 2097 3526 1765 3526 1764 3527 1765 3527 1752 3527 1752 3528 1765 3528 2099 3528 1752 3529 2099 3529 1766 3529 1766 3530 2099 3530 2100 3530 1766 3531 2100 3531 1767 3531 1767 3532 2100 3532 2101 3532 1767 3533 2101 3533 1768 3533 1768 3534 2101 3534 2102 3534 1768 3535 2102 3535 1750 3535 1750 3536 2102 3536 1769 3536 1750 3537 1769 3537 1748 3537 1748 3538 1769 3538 1771 3538 1748 3539 1771 3539 1770 3539 1770 3540 1771 3540 1772 3540 1770 3541 1772 3541 1747 3541 1747 3542 1772 3542 2106 3542 1747 3543 2106 3543 1773 3543 1773 3544 2106 3544 1774 3544 1773 3545 1774 3545 1776 3545 1776 3546 1774 3546 1775 3546 1776 3547 1775 3547 1745 3547 1745 3548 1775 3548 2110 3548 1745 3549 2110 3549 1777 3549 1777 3550 2110 3550 2112 3550 1777 3551 2112 3551 1743 3551 1743 3552 2112 3552 2114 3552 1743 3553 2114 3553 1742 3553 1742 3554 2114 3554 2115 3554 1742 3555 2115 3555 1778 3555 1778 3556 2115 3556 2117 3556 1778 3557 2117 3557 1740 3557 1740 3558 2117 3558 2118 3558 1740 3559 2118 3559 1779 3559 1779 3560 2118 3560 2120 3560 1779 3561 2120 3561 1737 3561 1737 3562 2120 3562 1780 3562 1737 3563 1780 3563 1781 3563 1781 3564 1780 3564 2123 3564 1781 3565 2123 3565 1735 3565 1735 3566 2123 3566 2124 3566 1735 3567 2124 3567 1782 3567 1782 3568 2124 3568 2125 3568 1782 3569 2125 3569 1728 3569 1789 3570 2226 3570 1783 3570 1783 3571 2226 3571 1784 3571 1783 3572 1784 3572 2230 3572 2230 3573 1784 3573 2228 3573 2231 3574 1785 3574 1788 3574 1788 3575 1785 3575 1786 3575 1788 3576 1786 3576 1790 3576 1790 3577 1786 3577 1787 3577 2230 3578 2231 3578 1783 3578 1783 3579 2231 3579 1788 3579 1783 3580 1788 3580 1789 3580 1789 3581 1788 3581 1790 3581 1789 3582 1790 3582 2204 3582 1799 3583 1793 3583 1792 3583 1791 3584 2195 3584 1795 3584 1793 3585 2193 3585 1794 3585 1794 3586 2193 3586 1791 3586 1798 3587 2202 3587 1792 3587 1793 3588 1794 3588 1792 3588 1792 3589 1794 3589 1796 3589 1792 3590 1796 3590 1798 3590 1791 3591 1795 3591 1794 3591 1794 3592 1795 3592 2198 3592 1794 3593 2198 3593 1796 3593 1796 3594 2198 3594 1797 3594 1796 3595 1797 3595 1798 3595 1792 3596 1800 3596 1799 3596 1799 3597 1800 3597 1801 3597 1799 3598 1801 3598 2166 3598 2166 3599 1801 3599 1802 3599 2166 3600 1802 3600 2168 3600 2168 3601 1802 3601 2209 3601 2168 3602 2209 3602 2190 3602 2190 3603 2209 3603 1803 3603 2190 3604 1803 3604 2188 3604 2188 3605 1803 3605 1805 3605 2188 3606 1805 3606 1804 3606 1804 3607 1805 3607 2213 3607 1804 3608 2213 3608 2186 3608 2186 3609 2213 3609 1806 3609 2186 3610 1806 3610 2185 3610 2185 3611 1806 3611 1807 3611 2185 3612 1807 3612 1808 3612 1808 3613 1807 3613 2215 3613 1808 3614 2215 3614 2182 3614 2182 3615 2215 3615 1809 3615 2182 3616 1809 3616 2180 3616 2180 3617 1809 3617 2217 3617 2180 3618 2217 3618 2179 3618 2179 3619 2217 3619 2218 3619 2179 3620 2218 3620 1810 3620 1810 3621 2218 3621 1811 3621 1810 3622 1811 3622 2177 3622 2177 3623 1811 3623 1812 3623 2177 3624 1812 3624 1813 3624 1813 3625 1812 3625 1814 3625 1813 3626 1814 3626 2174 3626 2174 3627 1814 3627 2222 3627 2174 3628 2222 3628 1815 3628 1815 3629 2222 3629 1817 3629 1815 3630 1817 3630 1816 3630 1816 3631 1817 3631 2224 3631 1816 3632 2224 3632 1818 3632 1818 3633 2224 3633 2225 3633 1818 3634 2225 3634 2171 3634 2171 3635 2225 3635 1819 3635 2171 3636 1819 3636 2169 3636 2169 3637 1819 3637 2207 3637 2169 3638 2207 3638 1820 3638 1820 3639 2207 3639 2205 3639 1820 3640 2205 3640 1821 3640 1821 3641 2205 3641 2204 3641 1821 3642 2204 3642 2163 3642 2163 3643 2204 3643 1790 3643 2279 3644 1825 3644 2239 3644 2300 3645 1822 3645 1824 3645 1822 3646 1823 3646 2303 3646 2300 3647 1824 3647 2299 3647 2299 3648 1824 3648 1825 3648 1825 3649 1824 3649 1826 3649 1825 3650 1826 3650 2239 3650 2239 3651 1826 3651 1827 3651 2239 3652 1827 3652 2235 3652 1822 3653 2303 3653 1824 3653 1824 3654 2303 3654 2233 3654 1824 3655 2233 3655 1826 3655 1826 3656 2233 3656 2234 3656 1826 3657 2234 3657 1827 3657 1828 3658 1831 3658 2272 3658 1829 3659 2266 3659 2268 3659 1831 3660 2264 3660 1832 3660 1832 3661 2264 3661 1829 3661 2271 3662 1830 3662 2272 3662 1831 3663 1832 3663 2272 3663 2272 3664 1832 3664 1833 3664 2272 3665 1833 3665 2271 3665 1829 3666 2268 3666 1832 3666 1832 3667 2268 3667 1834 3667 1832 3668 1834 3668 1833 3668 1833 3669 1834 3669 2269 3669 1833 3670 2269 3670 2271 3670 2272 3671 1835 3671 1828 3671 1828 3672 1835 3672 2275 3672 1828 3673 2275 3673 1836 3673 1836 3674 2275 3674 2276 3674 1836 3675 2276 3675 2238 3675 2238 3676 2276 3676 2277 3676 2238 3677 2277 3677 2260 3677 2260 3678 2277 3678 2286 3678 2260 3679 2286 3679 1837 3679 1837 3680 2286 3680 1838 3680 1837 3681 1838 3681 1839 3681 1839 3682 1838 3682 1840 3682 1839 3683 1840 3683 1841 3683 1841 3684 1840 3684 1843 3684 1841 3685 1843 3685 1842 3685 1842 3686 1843 3686 1844 3686 1842 3687 1844 3687 1845 3687 1845 3688 1844 3688 1846 3688 1845 3689 1846 3689 1847 3689 1847 3690 1846 3690 1848 3690 1847 3691 1848 3691 1849 3691 1849 3692 1848 3692 1850 3692 1849 3693 1850 3693 1851 3693 1851 3694 1850 3694 2291 3694 1851 3695 2291 3695 2255 3695 2255 3696 2291 3696 2292 3696 2255 3697 2292 3697 2253 3697 2253 3698 2292 3698 1852 3698 2253 3699 1852 3699 2252 3699 2252 3700 1852 3700 1854 3700 2252 3701 1854 3701 1853 3701 1853 3702 1854 3702 1855 3702 1853 3703 1855 3703 2250 3703 2250 3704 1855 3704 1856 3704 2250 3705 1856 3705 2249 3705 2249 3706 1856 3706 1857 3706 2249 3707 1857 3707 1858 3707 1858 3708 1857 3708 2297 3708 1858 3709 2297 3709 1859 3709 1859 3710 2297 3710 1860 3710 1859 3711 1860 3711 2246 3711 2246 3712 1860 3712 2283 3712 2246 3713 2283 3713 2242 3713 2242 3714 2283 3714 1861 3714 2242 3715 1861 3715 2241 3715 2241 3716 1861 3716 2279 3716 2241 3717 2279 3717 1862 3717 1862 3718 2279 3718 2239 3718 1899 3719 2307 3719 2319 3719 2371 3720 2372 3720 1863 3720 1868 3721 2371 3721 1870 3721 1870 3722 2371 3722 1863 3722 1870 3723 1863 3723 1900 3723 1900 3724 1863 3724 2304 3724 1900 3725 2304 3725 1864 3725 1864 3726 2304 3726 2305 3726 1864 3727 2305 3727 1899 3727 2342 3728 1898 3728 1865 3728 1867 3729 2335 3729 2338 3729 2342 3730 1865 3730 2340 3730 2340 3731 1865 3731 1896 3731 2340 3732 1896 3732 2338 3732 2338 3733 1896 3733 1866 3733 2338 3734 1866 3734 1867 3734 1868 3735 1870 3735 1869 3735 1869 3736 1870 3736 1900 3736 1869 3737 1900 3737 1871 3737 1871 3738 1900 3738 1901 3738 1871 3739 1901 3739 1872 3739 1872 3740 1901 3740 1902 3740 1872 3741 1902 3741 1873 3741 1873 3742 1902 3742 1874 3742 1873 3743 1874 3743 1875 3743 1875 3744 1874 3744 1904 3744 1875 3745 1904 3745 1876 3745 1876 3746 1904 3746 1877 3746 1876 3747 1877 3747 2362 3747 2362 3748 1877 3748 1907 3748 2362 3749 1907 3749 1878 3749 1878 3750 1907 3750 1880 3750 1878 3751 1880 3751 1879 3751 1879 3752 1880 3752 1881 3752 1879 3753 1881 3753 2364 3753 2364 3754 1881 3754 1882 3754 2364 3755 1882 3755 2366 3755 2366 3756 1882 3756 1909 3756 2366 3757 1909 3757 1883 3757 1883 3758 1909 3758 1884 3758 1883 3759 1884 3759 1885 3759 1885 3760 1884 3760 1911 3760 1885 3761 1911 3761 2356 3761 2356 3762 1911 3762 1912 3762 2356 3763 1912 3763 1887 3763 1887 3764 1912 3764 1886 3764 1887 3765 1886 3765 1888 3765 1888 3766 1886 3766 1889 3766 1888 3767 1889 3767 2354 3767 2354 3768 1889 3768 1890 3768 2354 3769 1890 3769 2353 3769 2353 3770 1890 3770 1915 3770 2353 3771 1915 3771 1892 3771 1892 3772 1915 3772 1891 3772 1892 3773 1891 3773 2350 3773 2350 3774 1891 3774 1916 3774 2350 3775 1916 3775 2349 3775 2349 3776 1916 3776 1918 3776 2349 3777 1918 3777 1893 3777 1893 3778 1918 3778 1919 3778 1893 3779 1919 3779 2347 3779 2347 3780 1919 3780 1894 3780 2347 3781 1894 3781 1895 3781 1895 3782 1894 3782 1896 3782 1895 3783 1896 3783 1897 3783 1897 3784 1896 3784 1865 3784 1897 3785 1865 3785 2345 3785 2345 3786 1865 3786 1898 3786 2345 3787 1898 3787 2344 3787 1899 3788 2319 3788 1864 3788 1864 3789 2319 3789 2322 3789 1864 3790 2322 3790 1900 3790 1900 3791 2322 3791 2323 3791 1900 3792 2323 3792 1901 3792 1901 3793 2323 3793 2324 3793 1901 3794 2324 3794 1902 3794 1902 3795 2324 3795 2326 3795 1902 3796 2326 3796 1874 3796 1874 3797 2326 3797 1903 3797 1874 3798 1903 3798 1904 3798 1904 3799 1903 3799 1905 3799 1904 3800 1905 3800 1877 3800 1877 3801 1905 3801 1906 3801 1877 3802 1906 3802 1907 3802 1907 3803 1906 3803 2329 3803 1907 3804 2329 3804 1880 3804 1880 3805 2329 3805 2330 3805 1880 3806 2330 3806 1881 3806 1881 3807 2330 3807 1908 3807 1881 3808 1908 3808 1882 3808 1882 3809 1908 3809 2331 3809 1882 3810 2331 3810 1909 3810 1909 3811 2331 3811 2332 3811 1909 3812 2332 3812 1884 3812 1884 3813 2332 3813 1910 3813 1884 3814 1910 3814 1911 3814 1911 3815 1910 3815 2318 3815 1911 3816 2318 3816 1912 3816 1912 3817 2318 3817 2317 3817 1912 3818 2317 3818 1886 3818 1886 3819 2317 3819 1913 3819 1886 3820 1913 3820 1889 3820 1889 3821 1913 3821 2315 3821 1889 3822 2315 3822 1890 3822 1890 3823 2315 3823 1914 3823 1890 3824 1914 3824 1915 3824 1915 3825 1914 3825 2313 3825 1915 3826 2313 3826 1891 3826 1891 3827 2313 3827 1917 3827 1891 3828 1917 3828 1916 3828 1916 3829 1917 3829 2311 3829 1916 3830 2311 3830 1918 3830 1918 3831 2311 3831 2310 3831 1918 3832 2310 3832 1919 3832 1919 3833 2310 3833 1920 3833 1919 3834 1920 3834 1894 3834 1894 3835 1920 3835 2309 3835 1894 3836 2309 3836 1896 3836 1896 3837 2309 3837 1921 3837 1896 3838 1921 3838 1866 3838 1866 3839 1921 3839 1922 3839 1866 3840 1922 3840 1867 3840 2437 3841 1924 3841 1923 3841 2443 3842 2444 3842 1924 3842 1924 3843 2444 3843 2445 3843 1924 3844 2445 3844 1923 3844 1954 3845 1955 3845 1925 3845 1925 3846 1955 3846 2377 3846 1925 3847 2377 3847 1926 3847 2405 3848 2407 3848 2404 3848 2404 3849 2407 3849 1929 3849 2404 3850 1929 3850 2403 3850 2410 3851 1927 3851 2408 3851 2408 3852 1927 3852 1928 3852 2408 3853 1928 3853 2407 3853 2407 3854 1928 3854 1931 3854 2407 3855 1931 3855 1929 3855 1929 3856 1931 3856 1930 3856 1929 3857 1930 3857 2403 3857 1928 3858 2411 3858 1931 3858 1931 3859 2411 3859 1932 3859 1931 3860 1932 3860 2379 3860 2379 3861 1932 3861 1933 3861 2379 3862 1933 3862 1934 3862 1934 3863 1933 3863 2414 3863 1934 3864 2414 3864 1935 3864 1935 3865 2414 3865 1936 3865 1935 3866 1936 3866 1937 3866 1937 3867 1936 3867 2416 3867 1937 3868 2416 3868 1938 3868 1938 3869 2416 3869 1939 3869 1938 3870 1939 3870 2398 3870 2398 3871 1939 3871 2417 3871 2398 3872 2417 3872 2396 3872 2396 3873 2417 3873 2418 3873 2396 3874 2418 3874 1940 3874 1940 3875 2418 3875 2421 3875 1940 3876 2421 3876 1941 3876 1941 3877 2421 3877 2423 3877 1941 3878 2423 3878 1943 3878 1943 3879 2423 3879 1942 3879 1943 3880 1942 3880 2393 3880 2393 3881 1942 3881 1944 3881 2393 3882 1944 3882 2391 3882 2391 3883 1944 3883 2427 3883 2391 3884 2427 3884 2389 3884 2389 3885 2427 3885 2428 3885 2389 3886 2428 3886 1945 3886 1945 3887 2428 3887 1946 3887 1945 3888 1946 3888 1947 3888 1947 3889 1946 3889 2431 3889 1947 3890 2431 3890 2387 3890 2387 3891 2431 3891 2432 3891 2387 3892 2432 3892 1948 3892 1948 3893 2432 3893 2434 3893 1948 3894 2434 3894 1949 3894 1949 3895 2434 3895 2435 3895 1949 3896 2435 3896 2385 3896 2385 3897 2435 3897 1950 3897 2385 3898 1950 3898 2383 3898 2383 3899 1950 3899 2440 3899 2383 3900 2440 3900 1951 3900 1951 3901 2440 3901 1952 3901 1951 3902 1952 3902 1953 3902 1953 3903 1952 3903 2437 3903 1953 3904 2437 3904 1954 3904 1954 3905 2437 3905 1923 3905 1954 3906 1923 3906 1955 3906 1955 3907 1923 3907 1956 3907 1955 3908 1956 3908 2377 3908 1973 3909 1958 3909 1960 3909 1957 3910 2510 3910 1962 3910 1958 3911 1959 3911 1961 3911 1961 3912 1959 3912 1957 3912 2449 3913 2451 3913 1960 3913 1958 3914 1961 3914 1960 3914 1960 3915 1961 3915 1964 3915 1960 3916 1964 3916 2449 3916 1957 3917 1962 3917 1961 3917 1961 3918 1962 3918 2447 3918 1961 3919 2447 3919 1964 3919 1964 3920 2447 3920 1963 3920 1964 3921 1963 3921 2449 3921 1965 3922 1966 3922 1967 3922 1967 3923 1966 3923 1968 3923 1967 3924 1968 3924 1971 3924 1971 3925 1968 3925 2481 3925 2482 3926 1969 3926 1972 3926 1972 3927 1969 3927 1970 3927 1972 3928 1970 3928 2485 3928 2485 3929 1970 3929 2483 3929 1971 3930 2482 3930 1967 3930 1967 3931 2482 3931 1972 3931 1967 3932 1972 3932 1965 3932 1965 3933 1972 3933 2485 3933 1965 3934 2485 3934 2453 3934 1960 3935 2455 3935 1973 3935 1973 3936 2455 3936 1974 3936 1973 3937 1974 3937 1975 3937 1975 3938 1974 3938 2457 3938 1975 3939 2457 3939 2508 3939 2508 3940 2457 3940 2460 3940 2508 3941 2460 3941 1976 3941 1976 3942 2460 3942 2461 3942 1976 3943 2461 3943 1977 3943 1977 3944 2461 3944 2462 3944 1977 3945 2462 3945 1978 3945 1978 3946 2462 3946 2464 3946 1978 3947 2464 3947 1979 3947 1979 3948 2464 3948 1981 3948 1979 3949 1981 3949 1980 3949 1980 3950 1981 3950 2466 3950 1980 3951 2466 3951 1983 3951 1983 3952 2466 3952 1982 3952 1983 3953 1982 3953 2503 3953 2503 3954 1982 3954 2469 3954 2503 3955 2469 3955 1984 3955 1984 3956 2469 3956 2471 3956 1984 3957 2471 3957 1985 3957 1985 3958 2471 3958 1986 3958 1985 3959 1986 3959 2500 3959 2500 3960 1986 3960 1987 3960 2500 3961 1987 3961 1988 3961 1988 3962 1987 3962 1989 3962 1988 3963 1989 3963 1990 3963 1990 3964 1989 3964 1991 3964 1990 3965 1991 3965 2498 3965 2498 3966 1991 3966 2475 3966 2498 3967 2475 3967 1992 3967 1992 3968 2475 3968 2476 3968 1992 3969 2476 3969 2495 3969 2495 3970 2476 3970 2477 3970 2495 3971 2477 3971 2493 3971 2493 3972 2477 3972 1994 3972 2493 3973 1994 3973 1993 3973 1993 3974 1994 3974 2478 3974 1993 3975 2478 3975 2492 3975 2492 3976 2478 3976 1995 3976 2492 3977 1995 3977 2490 3977 2490 3978 1995 3978 2452 3978 2490 3979 2452 3979 2488 3979 2488 3980 2452 3980 2453 3980 2488 3981 2453 3981 2486 3981 2486 3982 2453 3982 2485 3982 2539 3983 1996 3983 1997 3983 1997 3984 1996 3984 2541 3984 2004 3985 2539 3985 2026 3985 2026 3986 2539 3986 1997 3986 2026 3987 1997 3987 1998 3987 1998 3988 1997 3988 2541 3988 1998 3989 2541 3989 1999 3989 2000 3990 2515 3990 2002 3990 2002 3991 2515 3991 2001 3991 2002 3992 2001 3992 2021 3992 2021 3993 2001 3993 2516 3993 2000 3994 2002 3994 2511 3994 2511 3995 2002 3995 2021 3995 2511 3996 2021 3996 2003 3996 2026 3997 2028 3997 2004 3997 2004 3998 2028 3998 2005 3998 2004 3999 2005 3999 2535 3999 2535 4000 2005 4000 2056 4000 2535 4001 2056 4001 2537 4001 2537 4002 2056 4002 2006 4002 2537 4003 2006 4003 2008 4003 2008 4004 2006 4004 2007 4004 2008 4005 2007 4005 2009 4005 2009 4006 2007 4006 2054 4006 2009 4007 2054 4007 2010 4007 2010 4008 2054 4008 2011 4008 2010 4009 2011 4009 2534 4009 2534 4010 2011 4010 2053 4010 2534 4011 2053 4011 2533 4011 2533 4012 2053 4012 2012 4012 2533 4013 2012 4013 2531 4013 2531 4014 2012 4014 2050 4014 2531 4015 2050 4015 2013 4015 2013 4016 2050 4016 2049 4016 2013 4017 2049 4017 2530 4017 2530 4018 2049 4018 2047 4018 2530 4019 2047 4019 2014 4019 2014 4020 2047 4020 2046 4020 2014 4021 2046 4021 2528 4021 2528 4022 2046 4022 2015 4022 2528 4023 2015 4023 2526 4023 2526 4024 2015 4024 2016 4024 2526 4025 2016 4025 2525 4025 2525 4026 2016 4026 2017 4026 2525 4027 2017 4027 2524 4027 2524 4028 2017 4028 2018 4028 2524 4029 2018 4029 2523 4029 2523 4030 2018 4030 2039 4030 2523 4031 2039 4031 2019 4031 2019 4032 2039 4032 2038 4032 2019 4033 2038 4033 2522 4033 2522 4034 2038 4034 2037 4034 2522 4035 2037 4035 2521 4035 2521 4036 2037 4036 2035 4036 2521 4037 2035 4037 2020 4037 2020 4038 2035 4038 2034 4038 2020 4039 2034 4039 2519 4039 2519 4040 2034 4040 2031 4040 2519 4041 2031 4041 2518 4041 2518 4042 2031 4042 2003 4042 2518 4043 2003 4043 2517 4043 2517 4044 2003 4044 2021 4044 2024 4045 2022 4045 2025 4045 2025 4046 2022 4046 2130 4046 2025 4047 2130 4047 2027 4047 2027 4048 2130 4048 2023 4048 2024 4049 2025 4049 2026 4049 2026 4050 2025 4050 2027 4050 2026 4051 2027 4051 2028 4051 2157 4052 2159 4052 2029 4052 2029 4053 2159 4053 2160 4053 2030 4054 2157 4054 2511 4054 2511 4055 2157 4055 2029 4055 2511 4056 2029 4056 2512 4056 2512 4057 2029 4057 2160 4057 2512 4058 2160 4058 2161 4058 2511 4059 2003 4059 2030 4059 2030 4060 2003 4060 2031 4060 2030 4061 2031 4061 2032 4061 2032 4062 2031 4062 2034 4062 2032 4063 2034 4063 2033 4063 2033 4064 2034 4064 2035 4064 2033 4065 2035 4065 2156 4065 2156 4066 2035 4066 2037 4066 2156 4067 2037 4067 2036 4067 2036 4068 2037 4068 2038 4068 2036 4069 2038 4069 2040 4069 2040 4070 2038 4070 2039 4070 2040 4071 2039 4071 2041 4071 2041 4072 2039 4072 2018 4072 2041 4073 2018 4073 2042 4073 2042 4074 2018 4074 2017 4074 2042 4075 2017 4075 2043 4075 2043 4076 2017 4076 2016 4076 2043 4077 2016 4077 2150 4077 2150 4078 2016 4078 2015 4078 2150 4079 2015 4079 2044 4079 2044 4080 2015 4080 2046 4080 2044 4081 2046 4081 2045 4081 2045 4082 2046 4082 2047 4082 2045 4083 2047 4083 2048 4083 2048 4084 2047 4084 2049 4084 2048 4085 2049 4085 2051 4085 2051 4086 2049 4086 2050 4086 2051 4087 2050 4087 2146 4087 2146 4088 2050 4088 2012 4088 2146 4089 2012 4089 2052 4089 2052 4090 2012 4090 2053 4090 2052 4091 2053 4091 2143 4091 2143 4092 2053 4092 2011 4092 2143 4093 2011 4093 2141 4093 2141 4094 2011 4094 2054 4094 2141 4095 2054 4095 2055 4095 2055 4096 2054 4096 2007 4096 2055 4097 2007 4097 2139 4097 2139 4098 2007 4098 2006 4098 2139 4099 2006 4099 2138 4099 2138 4100 2006 4100 2056 4100 2138 4101 2056 4101 2137 4101 2137 4102 2056 4102 2005 4102 2137 4103 2005 4103 2057 4103 2057 4104 2005 4104 2028 4104 2057 4105 2028 4105 2136 4105 2136 4106 2028 4106 2027 4106 1726 4107 2612 4107 2610 4107 1726 4108 2610 4108 1723 4108 1723 4109 2610 4109 2566 4109 1723 4110 2566 4110 1724 4110 1724 4111 2566 4111 2058 4111 1724 4112 2058 4112 1734 4112 1734 4113 2058 4113 2059 4113 1734 4114 2059 4114 2060 4114 1746 4115 2576 4115 2061 4115 2061 4116 2576 4116 2575 4116 2061 4117 2575 4117 2062 4117 2062 4118 2575 4118 2574 4118 2062 4119 2574 4119 1749 4119 1749 4120 2574 4120 2573 4120 1749 4121 2573 4121 2063 4121 2063 4122 2573 4122 2064 4122 2063 4123 2064 4123 1751 4123 1751 4124 2064 4124 2571 4124 1751 4125 2571 4125 2066 4125 2066 4126 2571 4126 2065 4126 2066 4127 2065 4127 2067 4127 2067 4128 2065 4128 2069 4128 2067 4129 2069 4129 2068 4129 2068 4130 2069 4130 2070 4130 2068 4131 2070 4131 1753 4131 1753 4132 2070 4132 2072 4132 1753 4133 2072 4133 2071 4133 2071 4134 2072 4134 2073 4134 2071 4135 2073 4135 1754 4135 1754 4136 2073 4136 2074 4136 1754 4137 2074 4137 1756 4137 1756 4138 2074 4138 2075 4138 1756 4139 2075 4139 2076 4139 2076 4140 2075 4140 2567 4140 2060 4141 2059 4141 2077 4141 2077 4142 2059 4142 2078 4142 2077 4143 2078 4143 1736 4143 1736 4144 2078 4144 2590 4144 1736 4145 2590 4145 2079 4145 2079 4146 2590 4146 2589 4146 2079 4147 2589 4147 1738 4147 1738 4148 2589 4148 2080 4148 1738 4149 2080 4149 1739 4149 1739 4150 2080 4150 2587 4150 1739 4151 2587 4151 2081 4151 2081 4152 2587 4152 2585 4152 2081 4153 2585 4153 1741 4153 1741 4154 2585 4154 2583 4154 1741 4155 2583 4155 2082 4155 2082 4156 2583 4156 2083 4156 2082 4157 2083 4157 1744 4157 1744 4158 2083 4158 2582 4158 1744 4159 2582 4159 2084 4159 2084 4160 2582 4160 2580 4160 2084 4161 2580 4161 2085 4161 2085 4162 2580 4162 2578 4162 2085 4163 2578 4163 1746 4163 1746 4164 2578 4164 2086 4164 1746 4165 2086 4165 2576 4165 2076 4166 2567 4166 2087 4166 2076 4167 2087 4167 1758 4167 1758 4168 2087 4168 2088 4168 1758 4169 2088 4169 1759 4169 1759 4170 2088 4170 2089 4170 1759 4171 2089 4171 2090 4171 2090 4172 2089 4172 2598 4172 2090 4173 2598 4173 1733 4173 2598 4174 2091 4174 1733 4174 1733 4175 2091 4175 1732 4175 1732 4176 2091 4176 2596 4176 1732 4177 2596 4177 1730 4177 1730 4178 2596 4178 2595 4178 1730 4179 2595 4179 1760 4179 1760 4180 2595 4180 2092 4180 1760 4181 2092 4181 2093 4181 2093 4182 2092 4182 2592 4182 2093 4183 2592 4183 1729 4183 1729 4184 2592 4184 1761 4184 1761 4185 2592 4185 2594 4185 1761 4186 2594 4186 2094 4186 2094 4187 2594 4187 2647 4187 2094 4188 2647 4188 2095 4188 2095 4189 2647 4189 2096 4189 2095 4190 2096 4190 2097 4190 2097 4191 2096 4191 2645 4191 2097 4192 2645 4192 1765 4192 1765 4193 2645 4193 2098 4193 1765 4194 2098 4194 2099 4194 2099 4195 2098 4195 2642 4195 2099 4196 2642 4196 2100 4196 2100 4197 2642 4197 2641 4197 2100 4198 2641 4198 2101 4198 2101 4199 2641 4199 2648 4199 2101 4200 2648 4200 2102 4200 2102 4201 2648 4201 2103 4201 2102 4202 2103 4202 1769 4202 1769 4203 2103 4203 2104 4203 1769 4204 2104 4204 1771 4204 1771 4205 2104 4205 2105 4205 1771 4206 2105 4206 1772 4206 1772 4207 2105 4207 2602 4207 1772 4208 2602 4208 2106 4208 2602 4209 2603 4209 2106 4209 2106 4210 2603 4210 2107 4210 2106 4211 2107 4211 1774 4211 1774 4212 2107 4212 2108 4212 1774 4213 2108 4213 1775 4213 1775 4214 2108 4214 2109 4214 1775 4215 2109 4215 2110 4215 2110 4216 2109 4216 2111 4216 2110 4217 2111 4217 2112 4217 2112 4218 2111 4218 2606 4218 2112 4219 2606 4219 2114 4219 2114 4220 2606 4220 2113 4220 2114 4221 2113 4221 2115 4221 2115 4222 2113 4222 2607 4222 2115 4223 2607 4223 2117 4223 2117 4224 2607 4224 2116 4224 2117 4225 2116 4225 2118 4225 2118 4226 2116 4226 2119 4226 2118 4227 2119 4227 2120 4227 2120 4228 2119 4228 2121 4228 2120 4229 2121 4229 1780 4229 1780 4230 2121 4230 2122 4230 1780 4231 2122 4231 2123 4231 2123 4232 2122 4232 2618 4232 2123 4233 2618 4233 2124 4233 2124 4234 2618 4234 2616 4234 2124 4235 2616 4235 2615 4235 2124 4236 2615 4236 2125 4236 2125 4237 2615 4237 2614 4237 2125 4238 2614 4238 1728 4238 1728 4239 2614 4239 2613 4239 1728 4240 2613 4240 2126 4240 2126 4241 2613 4241 2127 4241 2126 4242 2127 4242 1727 4242 2127 4243 2612 4243 1727 4243 1727 4244 2612 4244 1726 4244 2024 4245 2821 4245 2128 4245 2024 4246 2128 4246 2022 4246 2022 4247 2128 4247 2129 4247 2022 4248 2129 4248 2130 4248 2130 4249 2129 4249 2131 4249 2130 4250 2131 4250 2023 4250 2023 4251 2131 4251 2819 4251 2023 4252 2819 4252 2027 4252 2156 4253 2132 4253 2033 4253 2033 4254 2132 4254 2133 4254 2033 4255 2133 4255 2032 4255 2032 4256 2133 4256 2134 4256 2032 4257 2134 4257 2030 4257 2030 4258 2134 4258 2824 4258 2030 4259 2824 4259 2157 4259 2157 4260 2824 4260 2823 4260 2027 4261 2819 4261 2136 4261 2136 4262 2819 4262 2135 4262 2136 4263 2135 4263 2057 4263 2057 4264 2135 4264 2846 4264 2057 4265 2846 4265 2137 4265 2137 4266 2846 4266 2844 4266 2137 4267 2844 4267 2138 4267 2844 4268 2842 4268 2138 4268 2138 4269 2842 4269 2840 4269 2138 4270 2840 4270 2139 4270 2139 4271 2840 4271 2140 4271 2139 4272 2140 4272 2055 4272 2055 4273 2140 4273 2837 4273 2055 4274 2837 4274 2141 4274 2141 4275 2837 4275 2142 4275 2141 4276 2142 4276 2143 4276 2143 4277 2142 4277 2144 4277 2143 4278 2144 4278 2052 4278 2052 4279 2144 4279 2145 4279 2052 4280 2145 4280 2146 4280 2146 4281 2145 4281 2147 4281 2146 4282 2147 4282 2051 4282 2051 4283 2147 4283 2833 4283 2051 4284 2833 4284 2048 4284 2048 4285 2833 4285 2148 4285 2048 4286 2148 4286 2045 4286 2045 4287 2148 4287 2149 4287 2045 4288 2149 4288 2044 4288 2044 4289 2149 4289 2151 4289 2044 4290 2151 4290 2150 4290 2150 4291 2151 4291 2831 4291 2150 4292 2831 4292 2043 4292 2043 4293 2831 4293 2152 4293 2043 4294 2152 4294 2042 4294 2042 4295 2152 4295 2153 4295 2042 4296 2153 4296 2041 4296 2041 4297 2153 4297 2154 4297 2041 4298 2154 4298 2040 4298 2040 4299 2154 4299 2155 4299 2040 4300 2155 4300 2036 4300 2036 4301 2155 4301 2829 4301 2036 4302 2829 4302 2156 4302 2156 4303 2829 4303 2828 4303 2156 4304 2828 4304 2132 4304 2157 4305 2823 4305 2793 4305 2157 4306 2793 4306 2159 4306 2159 4307 2793 4307 2158 4307 2159 4308 2158 4308 2160 4308 2160 4309 2158 4309 2795 4309 2160 4310 2795 4310 2161 4310 2161 4311 2795 4311 2791 4311 2161 4312 2791 4312 2512 4312 2231 4313 2817 4313 2816 4313 2231 4314 2816 4314 1785 4314 1785 4315 2816 4315 2162 4315 1785 4316 2162 4316 1786 4316 1786 4317 2162 4317 2814 4317 1786 4318 2814 4318 1787 4318 1787 4319 2814 4319 2813 4319 1787 4320 2813 4320 1790 4320 1790 4321 2813 4321 2163 4321 2163 4322 2813 4322 2164 4322 2163 4323 2164 4323 1821 4323 1821 4324 2164 4324 2868 4324 1821 4325 2868 4325 1820 4325 1820 4326 2868 4326 2867 4326 1820 4327 2867 4327 2169 4327 2797 4328 1793 4328 2848 4328 2848 4329 1793 4329 1799 4329 2848 4330 1799 4330 2165 4330 2165 4331 1799 4331 2166 4331 2165 4332 2166 4332 2167 4332 2167 4333 2166 4333 2168 4333 2167 4334 2168 4334 2191 4334 2191 4335 2168 4335 2190 4335 2867 4336 2866 4336 2169 4336 2169 4337 2866 4337 2170 4337 2169 4338 2170 4338 2171 4338 2171 4339 2170 4339 2864 4339 2171 4340 2864 4340 1818 4340 1818 4341 2864 4341 2172 4341 1818 4342 2172 4342 1816 4342 1816 4343 2172 4343 2173 4343 1816 4344 2173 4344 1815 4344 1815 4345 2173 4345 2175 4345 1815 4346 2175 4346 2174 4346 2174 4347 2175 4347 2861 4347 2174 4348 2861 4348 1813 4348 1813 4349 2861 4349 2176 4349 1813 4350 2176 4350 2177 4350 2177 4351 2176 4351 2860 4351 2177 4352 2860 4352 1810 4352 1810 4353 2860 4353 2178 4353 1810 4354 2178 4354 2179 4354 2179 4355 2178 4355 2181 4355 2179 4356 2181 4356 2180 4356 2180 4357 2181 4357 2856 4357 2180 4358 2856 4358 2182 4358 2182 4359 2856 4359 2183 4359 2182 4360 2183 4360 1808 4360 1808 4361 2183 4361 2184 4361 1808 4362 2184 4362 2185 4362 2185 4363 2184 4363 2855 4363 2185 4364 2855 4364 2186 4364 2186 4365 2855 4365 2854 4365 2186 4366 2854 4366 1804 4366 1804 4367 2854 4367 2187 4367 1804 4368 2187 4368 2188 4368 2188 4369 2187 4369 2189 4369 2188 4370 2189 4370 2190 4370 2190 4371 2189 4371 2851 4371 2190 4372 2851 4372 2191 4372 1793 4373 2797 4373 2192 4373 1793 4374 2192 4374 2193 4374 2193 4375 2192 4375 2796 4375 2193 4376 2796 4376 1791 4376 1791 4377 2796 4377 2194 4377 1791 4378 2194 4378 2195 4378 2195 4379 2194 4379 2196 4379 2195 4380 2196 4380 1795 4380 2196 4381 2197 4381 1795 4381 1795 4382 2197 4382 2198 4382 2198 4383 2197 4383 2199 4383 2198 4384 2199 4384 1797 4384 1797 4385 2199 4385 2200 4385 1797 4386 2200 4386 1798 4386 1798 4387 2200 4387 2201 4387 1798 4388 2201 4388 2202 4388 2202 4389 2201 4389 2792 4389 2202 4390 2792 4390 1792 4390 1792 4391 2792 4391 1800 4391 1800 4392 2792 4392 2794 4392 1800 4393 2794 4393 1801 4393 1801 4394 2794 4394 2825 4394 1801 4395 2825 4395 1802 4395 1802 4396 2825 4396 2826 4396 1802 4397 2826 4397 2209 4397 2847 4398 1789 4398 2203 4398 2203 4399 1789 4399 2204 4399 2203 4400 2204 4400 2845 4400 2845 4401 2204 4401 2205 4401 2845 4402 2205 4402 2206 4402 2206 4403 2205 4403 2207 4403 2206 4404 2207 4404 2843 4404 2843 4405 2207 4405 1819 4405 2826 4406 2827 4406 2209 4406 2209 4407 2827 4407 2208 4407 2209 4408 2208 4408 1803 4408 1803 4409 2208 4409 2210 4409 1803 4410 2210 4410 1805 4410 1805 4411 2210 4411 2211 4411 1805 4412 2211 4412 2213 4412 2213 4413 2211 4413 2212 4413 2213 4414 2212 4414 1806 4414 1806 4415 2212 4415 2214 4415 1806 4416 2214 4416 1807 4416 1807 4417 2214 4417 2830 4417 1807 4418 2830 4418 2215 4418 2215 4419 2830 4419 2216 4419 2215 4420 2216 4420 1809 4420 1809 4421 2216 4421 2832 4421 1809 4422 2832 4422 2217 4422 2217 4423 2832 4423 2219 4423 2217 4424 2219 4424 2218 4424 2218 4425 2219 4425 2220 4425 2218 4426 2220 4426 1811 4426 1811 4427 2220 4427 2834 4427 1811 4428 2834 4428 1812 4428 1812 4429 2834 4429 2221 4429 1812 4430 2221 4430 1814 4430 1814 4431 2221 4431 2835 4431 1814 4432 2835 4432 2222 4432 2222 4433 2835 4433 2836 4433 2222 4434 2836 4434 1817 4434 1817 4435 2836 4435 2223 4435 1817 4436 2223 4436 2224 4436 2224 4437 2223 4437 2838 4437 2224 4438 2838 4438 2225 4438 2225 4439 2838 4439 2839 4439 2225 4440 2839 4440 1819 4440 1819 4441 2839 4441 2841 4441 1819 4442 2841 4442 2843 4442 1789 4443 2847 4443 2810 4443 1789 4444 2810 4444 2226 4444 2226 4445 2810 4445 2818 4445 2226 4446 2818 4446 1784 4446 1784 4447 2818 4447 2227 4447 1784 4448 2227 4448 2228 4448 2228 4449 2227 4449 2229 4449 2228 4450 2229 4450 2230 4450 2231 4451 2230 4451 2817 4451 2817 4452 2230 4452 2229 4452 2233 4453 2232 4453 2807 4453 2233 4454 2807 4454 2234 4454 2234 4455 2807 4455 2806 4455 2234 4456 2806 4456 1827 4456 1827 4457 2806 4457 2805 4457 1827 4458 2805 4458 2235 4458 2235 4459 2805 4459 2240 4459 2235 4460 2240 4460 2239 4460 2803 4461 1831 4461 2236 4461 2236 4462 1831 4462 1828 4462 2236 4463 1828 4463 2889 4463 2889 4464 1828 4464 1836 4464 2889 4465 1836 4465 2237 4465 2237 4466 1836 4466 2238 4466 2237 4467 2238 4467 2891 4467 2891 4468 2238 4468 2260 4468 2239 4469 2240 4469 1862 4469 1862 4470 2240 4470 2869 4470 1862 4471 2869 4471 2241 4471 2241 4472 2869 4472 2871 4472 2241 4473 2871 4473 2242 4473 2242 4474 2871 4474 2243 4474 2242 4475 2243 4475 2246 4475 2243 4476 2244 4476 2246 4476 2246 4477 2244 4477 2245 4477 2246 4478 2245 4478 1859 4478 1859 4479 2245 4479 2247 4479 1859 4480 2247 4480 1858 4480 1858 4481 2247 4481 2248 4481 1858 4482 2248 4482 2249 4482 2249 4483 2248 4483 2873 4483 2249 4484 2873 4484 2250 4484 2250 4485 2873 4485 2251 4485 2250 4486 2251 4486 1853 4486 1853 4487 2251 4487 2875 4487 1853 4488 2875 4488 2252 4488 2252 4489 2875 4489 2254 4489 2252 4490 2254 4490 2253 4490 2253 4491 2254 4491 2881 4491 2253 4492 2881 4492 2255 4492 2255 4493 2881 4493 2256 4493 2255 4494 2256 4494 1851 4494 1851 4495 2256 4495 2883 4495 1851 4496 2883 4496 1849 4496 1849 4497 2883 4497 2884 4497 1849 4498 2884 4498 1847 4498 1847 4499 2884 4499 2887 4499 1847 4500 2887 4500 1845 4500 1845 4501 2887 4501 2257 4501 1845 4502 2257 4502 1842 4502 1842 4503 2257 4503 2893 4503 1842 4504 2893 4504 1841 4504 1841 4505 2893 4505 2258 4505 1841 4506 2258 4506 1839 4506 1839 4507 2258 4507 2259 4507 1839 4508 2259 4508 1837 4508 1837 4509 2259 4509 2261 4509 1837 4510 2261 4510 2260 4510 2260 4511 2261 4511 2262 4511 2260 4512 2262 4512 2891 4512 1831 4513 2803 4513 2263 4513 1831 4514 2263 4514 2264 4514 2264 4515 2263 4515 2800 4515 2264 4516 2800 4516 1829 4516 1829 4517 2800 4517 2265 4517 1829 4518 2265 4518 2266 4518 2266 4519 2265 4519 2267 4519 2266 4520 2267 4520 2268 4520 2267 4521 2802 4521 2268 4521 2268 4522 2802 4522 1834 4522 1834 4523 2802 4523 2801 4523 1834 4524 2801 4524 2269 4524 2269 4525 2801 4525 2270 4525 2269 4526 2270 4526 2271 4526 2271 4527 2270 4527 2799 4527 2271 4528 2799 4528 1830 4528 1830 4529 2799 4529 2273 4529 1830 4530 2273 4530 2272 4530 2272 4531 2273 4531 1835 4531 1835 4532 2273 4532 2274 4532 1835 4533 2274 4533 2275 4533 2275 4534 2274 4534 2849 4534 2275 4535 2849 4535 2276 4535 2276 4536 2849 4536 2850 4536 2276 4537 2850 4537 2277 4537 2811 4538 1825 4538 2278 4538 2278 4539 1825 4539 2279 4539 2278 4540 2279 4540 2280 4540 2280 4541 2279 4541 1861 4541 2280 4542 1861 4542 2281 4542 2281 4543 1861 4543 2283 4543 2281 4544 2283 4544 2282 4544 2282 4545 2283 4545 1860 4545 2850 4546 2284 4546 2277 4546 2277 4547 2284 4547 2852 4547 2277 4548 2852 4548 2286 4548 2286 4549 2852 4549 2285 4549 2286 4550 2285 4550 1838 4550 1838 4551 2285 4551 2853 4551 1838 4552 2853 4552 1840 4552 1840 4553 2853 4553 2287 4553 1840 4554 2287 4554 1843 4554 1843 4555 2287 4555 2288 4555 1843 4556 2288 4556 1844 4556 1844 4557 2288 4557 2289 4557 1844 4558 2289 4558 1846 4558 1846 4559 2289 4559 2290 4559 1846 4560 2290 4560 1848 4560 1848 4561 2290 4561 2857 4561 1848 4562 2857 4562 1850 4562 1850 4563 2857 4563 2858 4563 1850 4564 2858 4564 2291 4564 2291 4565 2858 4565 2859 4565 2291 4566 2859 4566 2292 4566 2292 4567 2859 4567 2293 4567 2292 4568 2293 4568 1852 4568 1852 4569 2293 4569 2294 4569 1852 4570 2294 4570 1854 4570 1854 4571 2294 4571 2862 4571 1854 4572 2862 4572 1855 4572 1855 4573 2862 4573 2295 4573 1855 4574 2295 4574 1856 4574 1856 4575 2295 4575 2296 4575 1856 4576 2296 4576 1857 4576 1857 4577 2296 4577 2863 4577 1857 4578 2863 4578 2297 4578 2297 4579 2863 4579 2298 4579 2297 4580 2298 4580 1860 4580 1860 4581 2298 4581 2865 4581 1860 4582 2865 4582 2282 4582 1825 4583 2811 4583 2299 4583 2299 4584 2811 4584 2812 4584 2299 4585 2812 4585 2300 4585 2812 4586 2808 4586 2300 4586 2300 4587 2808 4587 2301 4587 2300 4588 2301 4588 1822 4588 1822 4589 2301 4589 2809 4589 1822 4590 2809 4590 1823 4590 1823 4591 2809 4591 2302 4591 1823 4592 2302 4592 2303 4592 2233 4593 2303 4593 2232 4593 2232 4594 2303 4594 2302 4594 2304 4595 2374 4595 2940 4595 2304 4596 2940 4596 2305 4596 2305 4597 2940 4597 2939 4597 2305 4598 2939 4598 1899 4598 1899 4599 2939 4599 2306 4599 1899 4600 2306 4600 2307 4600 2307 4601 2306 4601 2320 4601 2307 4602 2320 4602 2319 4602 2913 4603 1921 4603 2308 4603 2308 4604 1921 4604 2309 4604 2308 4605 2309 4605 2994 4605 2994 4606 2309 4606 1920 4606 2994 4607 1920 4607 2995 4607 2995 4608 1920 4608 2310 4608 2995 4609 2310 4609 2312 4609 2312 4610 2310 4610 2311 4610 2312 4611 2311 4611 2996 4611 2996 4612 2311 4612 1917 4612 2996 4613 1917 4613 2997 4613 2997 4614 1917 4614 2313 4614 2997 4615 2313 4615 2999 4615 2999 4616 2313 4616 1914 4616 2999 4617 1914 4617 2314 4617 2314 4618 1914 4618 2315 4618 2314 4619 2315 4619 2316 4619 2316 4620 2315 4620 1913 4620 2316 4621 1913 4621 3003 4621 3003 4622 1913 4622 2317 4622 3003 4623 2317 4623 3005 4623 3005 4624 2317 4624 2318 4624 3005 4625 2318 4625 3006 4625 3006 4626 2318 4626 1910 4626 2319 4627 2320 4627 2322 4627 2322 4628 2320 4628 2321 4628 2322 4629 2321 4629 2323 4629 2323 4630 2321 4630 3017 4630 2323 4631 3017 4631 2324 4631 2324 4632 3017 4632 2325 4632 2324 4633 2325 4633 2326 4633 2326 4634 2325 4634 2327 4634 2326 4635 2327 4635 1903 4635 1903 4636 2327 4636 3016 4636 1903 4637 3016 4637 1905 4637 1905 4638 3016 4638 3015 4638 1905 4639 3015 4639 1906 4639 1906 4640 3015 4640 2328 4640 1906 4641 2328 4641 2329 4641 2329 4642 2328 4642 3013 4642 2329 4643 3013 4643 2330 4643 2330 4644 3013 4644 3011 4644 2330 4645 3011 4645 1908 4645 1908 4646 3011 4646 3010 4646 1908 4647 3010 4647 2331 4647 2331 4648 3010 4648 3009 4648 2331 4649 3009 4649 2332 4649 2332 4650 3009 4650 2333 4650 2332 4651 2333 4651 1910 4651 1910 4652 2333 4652 3007 4652 1910 4653 3007 4653 3006 4653 1921 4654 2913 4654 2334 4654 1921 4655 2334 4655 1922 4655 1922 4656 2334 4656 2912 4656 1922 4657 2912 4657 1867 4657 1867 4658 2912 4658 2336 4658 1867 4659 2336 4659 2335 4659 2335 4660 2336 4660 2337 4660 2335 4661 2337 4661 2338 4661 2337 4662 2339 4662 2338 4662 2338 4663 2339 4663 2340 4663 2340 4664 2339 4664 2341 4664 2340 4665 2341 4665 2342 4665 2342 4666 2341 4666 2916 4666 2342 4667 2916 4667 1898 4667 1898 4668 2916 4668 2343 4668 1898 4669 2343 4669 2344 4669 2344 4670 2343 4670 2914 4670 2344 4671 2914 4671 2345 4671 2345 4672 2914 4672 1897 4672 1897 4673 2914 4673 2938 4673 1897 4674 2938 4674 1895 4674 1895 4675 2938 4675 2346 4675 1895 4676 2346 4676 2347 4676 2347 4677 2346 4677 2937 4677 2347 4678 2937 4678 1893 4678 1893 4679 2937 4679 2348 4679 1893 4680 2348 4680 2349 4680 2349 4681 2348 4681 2934 4681 2349 4682 2934 4682 2350 4682 2350 4683 2934 4683 2933 4683 2350 4684 2933 4684 1892 4684 1892 4685 2933 4685 2351 4685 1892 4686 2351 4686 2353 4686 2353 4687 2351 4687 2352 4687 2353 4688 2352 4688 2354 4688 2354 4689 2352 4689 2930 4689 2354 4690 2930 4690 1888 4690 1888 4691 2930 4691 2355 4691 1888 4692 2355 4692 1887 4692 1887 4693 2355 4693 2368 4693 1887 4694 2368 4694 2356 4694 3021 4695 1869 4695 2918 4695 2918 4696 1869 4696 1871 4696 2918 4697 1871 4697 2357 4697 2357 4698 1871 4698 1872 4698 2357 4699 1872 4699 2358 4699 2358 4700 1872 4700 1873 4700 2358 4701 1873 4701 2920 4701 2920 4702 1873 4702 1875 4702 2920 4703 1875 4703 2359 4703 2359 4704 1875 4704 1876 4704 2359 4705 1876 4705 2360 4705 2360 4706 1876 4706 2362 4706 2360 4707 2362 4707 2361 4707 2361 4708 2362 4708 1878 4708 2361 4709 1878 4709 2363 4709 2363 4710 1878 4710 1879 4710 2363 4711 1879 4711 2365 4711 2365 4712 1879 4712 2364 4712 2365 4713 2364 4713 2922 4713 2922 4714 2364 4714 2366 4714 2922 4715 2366 4715 2367 4715 2367 4716 2366 4716 1883 4716 2367 4717 1883 4717 2924 4717 2924 4718 1883 4718 1885 4718 2924 4719 1885 4719 2925 4719 2925 4720 1885 4720 2356 4720 2925 4721 2356 4721 2926 4721 2926 4722 2356 4722 2368 4722 1869 4723 3021 4723 2369 4723 1869 4724 2369 4724 1868 4724 1868 4725 2369 4725 2370 4725 1868 4726 2370 4726 2371 4726 2371 4727 2370 4727 2942 4727 2371 4728 2942 4728 2372 4728 2372 4729 2942 4729 2373 4729 2372 4730 2373 4730 1863 4730 2304 4731 1863 4731 2374 4731 2374 4732 1863 4732 2373 4732 1923 4733 3140 4733 2375 4733 1923 4734 2375 4734 1956 4734 1956 4735 2375 4735 2376 4735 1956 4736 2376 4736 2377 4736 2377 4737 2376 4737 3139 4737 2377 4738 3139 4738 1926 4738 1926 4739 3139 4739 3138 4739 1926 4740 3138 4740 1925 4740 2378 4741 1930 4741 3177 4741 3177 4742 1930 4742 1931 4742 3177 4743 1931 4743 3176 4743 3176 4744 1931 4744 2379 4744 3176 4745 2379 4745 2380 4745 2380 4746 2379 4746 1934 4746 2380 4747 1934 4747 2381 4747 2381 4748 1934 4748 1935 4748 1925 4749 3138 4749 1954 4749 1954 4750 3138 4750 3146 4750 1954 4751 3146 4751 1953 4751 1953 4752 3146 4752 2382 4752 1953 4753 2382 4753 1951 4753 1951 4754 2382 4754 3148 4754 1951 4755 3148 4755 2383 4755 3148 4756 3149 4756 2383 4756 2383 4757 3149 4757 2384 4757 2383 4758 2384 4758 2385 4758 2385 4759 2384 4759 3151 4759 2385 4760 3151 4760 1949 4760 1949 4761 3151 4761 2386 4761 1949 4762 2386 4762 1948 4762 1948 4763 2386 4763 3155 4763 1948 4764 3155 4764 2387 4764 2387 4765 3155 4765 3156 4765 2387 4766 3156 4766 1947 4766 1947 4767 3156 4767 2388 4767 1947 4768 2388 4768 1945 4768 1945 4769 2388 4769 2390 4769 1945 4770 2390 4770 2389 4770 2389 4771 2390 4771 2392 4771 2389 4772 2392 4772 2391 4772 2391 4773 2392 4773 2394 4773 2391 4774 2394 4774 2393 4774 2393 4775 2394 4775 3161 4775 2393 4776 3161 4776 1943 4776 1943 4777 3161 4777 3162 4777 1943 4778 3162 4778 1941 4778 1941 4779 3162 4779 2395 4779 1941 4780 2395 4780 1940 4780 1940 4781 2395 4781 2397 4781 1940 4782 2397 4782 2396 4782 2396 4783 2397 4783 3167 4783 2396 4784 3167 4784 2398 4784 2398 4785 3167 4785 3168 4785 2398 4786 3168 4786 1938 4786 1938 4787 3168 4787 2399 4787 1938 4788 2399 4788 1937 4788 1937 4789 2399 4789 2400 4789 1937 4790 2400 4790 1935 4790 1935 4791 2400 4791 3172 4791 1935 4792 3172 4792 2381 4792 1930 4793 2378 4793 2401 4793 1930 4794 2401 4794 2403 4794 2403 4795 2401 4795 2402 4795 2403 4796 2402 4796 2404 4796 2404 4797 2402 4797 3182 4797 2404 4798 3182 4798 2405 4798 2405 4799 3182 4799 2406 4799 2405 4800 2406 4800 2407 4800 2406 4801 3180 4801 2407 4801 2407 4802 3180 4802 2408 4802 2412 4803 1928 4803 2409 4803 2409 4804 1928 4804 1927 4804 2409 4805 1927 4805 3178 4805 3178 4806 1927 4806 2410 4806 3178 4807 2410 4807 3179 4807 3179 4808 2410 4808 2408 4808 3179 4809 2408 4809 3180 4809 1928 4810 2412 4810 2411 4810 2411 4811 2412 4811 2413 4811 2411 4812 2413 4812 1932 4812 1932 4813 2413 4813 3218 4813 1932 4814 3218 4814 1933 4814 1933 4815 3218 4815 3215 4815 1933 4816 3215 4816 2414 4816 3215 4817 3214 4817 2414 4817 2414 4818 3214 4818 3213 4818 2414 4819 3213 4819 1936 4819 1936 4820 3213 4820 3211 4820 1936 4821 3211 4821 2416 4821 2416 4822 3211 4822 2415 4822 2416 4823 2415 4823 1939 4823 1939 4824 2415 4824 3208 4824 1939 4825 3208 4825 2417 4825 2417 4826 3208 4826 2419 4826 2417 4827 2419 4827 2418 4827 2418 4828 2419 4828 2420 4828 2418 4829 2420 4829 2421 4829 2421 4830 2420 4830 2422 4830 2421 4831 2422 4831 2423 4831 2423 4832 2422 4832 2424 4832 2423 4833 2424 4833 1942 4833 1942 4834 2424 4834 2425 4834 1942 4835 2425 4835 1944 4835 1944 4836 2425 4836 2426 4836 1944 4837 2426 4837 2427 4837 2427 4838 2426 4838 3204 4838 2427 4839 3204 4839 2428 4839 2428 4840 3204 4840 2429 4840 2428 4841 2429 4841 1946 4841 1946 4842 2429 4842 2430 4842 1946 4843 2430 4843 2431 4843 2431 4844 2430 4844 3203 4844 2431 4845 3203 4845 2432 4845 2432 4846 3203 4846 2433 4846 2432 4847 2433 4847 2434 4847 2434 4848 2433 4848 3201 4848 2434 4849 3201 4849 2435 4849 2435 4850 3201 4850 3199 4850 2435 4851 3199 4851 1950 4851 3221 4852 1924 4852 2436 4852 2436 4853 1924 4853 2437 4853 2436 4854 2437 4854 2438 4854 2438 4855 2437 4855 1952 4855 2438 4856 1952 4856 3197 4856 3197 4857 1952 4857 2440 4857 3197 4858 2440 4858 2439 4858 2439 4859 2440 4859 1950 4859 2439 4860 1950 4860 2441 4860 2441 4861 1950 4861 3199 4861 1924 4862 3221 4862 2443 4862 2443 4863 3221 4863 2442 4863 2442 4864 3133 4864 2443 4864 2443 4865 3133 4865 3143 4865 2443 4866 3143 4866 2444 4866 2444 4867 3143 4867 3142 4867 2444 4868 3142 4868 2445 4868 1923 4869 2445 4869 3140 4869 3140 4870 2445 4870 3142 4870 2447 4871 2446 4871 2448 4871 2447 4872 2448 4872 1963 4872 1963 4873 2448 4873 3224 4873 1963 4874 3224 4874 2449 4874 2449 4875 3224 4875 2450 4875 2449 4876 2450 4876 2451 4876 2451 4877 2450 4877 3220 4877 2451 4878 3220 4878 1960 4878 2478 4879 3216 4879 1995 4879 1995 4880 3216 4880 3217 4880 1995 4881 3217 4881 2452 4881 2452 4882 3217 4882 3219 4882 2452 4883 3219 4883 2453 4883 2453 4884 3219 4884 2454 4884 2453 4885 2454 4885 1965 4885 1965 4886 2454 4886 3194 4886 1960 4887 3220 4887 2455 4887 2455 4888 3220 4888 3222 4888 2455 4889 3222 4889 1974 4889 1974 4890 3222 4890 2456 4890 1974 4891 2456 4891 2457 4891 2457 4892 2456 4892 3198 4892 2457 4893 3198 4893 2460 4893 3198 4894 2458 4894 2460 4894 2460 4895 2458 4895 2459 4895 2460 4896 2459 4896 2461 4896 2461 4897 2459 4897 3200 4897 2461 4898 3200 4898 2462 4898 2462 4899 3200 4899 3202 4899 2462 4900 3202 4900 2464 4900 2464 4901 3202 4901 2463 4901 2464 4902 2463 4902 1981 4902 1981 4903 2463 4903 2465 4903 1981 4904 2465 4904 2466 4904 2466 4905 2465 4905 2467 4905 2466 4906 2467 4906 1982 4906 1982 4907 2467 4907 2468 4907 1982 4908 2468 4908 2469 4908 2469 4909 2468 4909 2470 4909 2469 4910 2470 4910 2471 4910 2471 4911 2470 4911 3205 4911 2471 4912 3205 4912 1986 4912 1986 4913 3205 4913 2472 4913 1986 4914 2472 4914 1987 4914 1987 4915 2472 4915 2473 4915 1987 4916 2473 4916 1989 4916 1989 4917 2473 4917 2474 4917 1989 4918 2474 4918 1991 4918 1991 4919 2474 4919 3206 4919 1991 4920 3206 4920 2475 4920 2475 4921 3206 4921 3207 4921 2475 4922 3207 4922 2476 4922 2476 4923 3207 4923 3209 4923 2476 4924 3209 4924 2477 4924 2477 4925 3209 4925 3210 4925 2477 4926 3210 4926 1994 4926 1994 4927 3210 4927 3212 4927 1994 4928 3212 4928 2478 4928 2478 4929 3212 4929 2479 4929 2478 4930 2479 4930 3216 4930 1965 4931 3194 4931 3195 4931 1965 4932 3195 4932 1966 4932 1966 4933 3195 4933 3196 4933 1966 4934 3196 4934 1968 4934 1968 4935 3196 4935 2480 4935 1968 4936 2480 4936 2481 4936 2481 4937 2480 4937 3193 4937 2481 4938 3193 4938 1971 4938 3193 4939 3192 4939 1971 4939 1971 4940 3192 4940 2482 4940 2482 4941 3192 4941 3191 4941 2482 4942 3191 4942 1969 4942 1969 4943 3191 4943 3190 4943 1969 4944 3190 4944 1970 4944 1970 4945 3190 4945 3188 4945 1970 4946 3188 4946 2483 4946 2483 4947 3188 4947 2484 4947 2483 4948 2484 4948 2485 4948 2485 4949 2484 4949 2486 4949 2486 4950 2484 4950 2487 4950 2486 4951 2487 4951 2488 4951 2488 4952 2487 4952 2489 4952 2488 4953 2489 4953 2490 4953 2490 4954 2489 4954 2491 4954 2490 4955 2491 4955 2492 4955 2491 4956 3236 4956 2492 4956 2492 4957 3236 4957 3235 4957 2492 4958 3235 4958 1993 4958 1993 4959 3235 4959 3233 4959 1993 4960 3233 4960 2493 4960 2493 4961 3233 4961 2494 4961 2493 4962 2494 4962 2495 4962 2495 4963 2494 4963 3231 4963 2495 4964 3231 4964 1992 4964 1992 4965 3231 4965 2496 4965 1992 4966 2496 4966 2498 4966 2498 4967 2496 4967 2497 4967 2498 4968 2497 4968 1990 4968 1990 4969 2497 4969 2499 4969 1990 4970 2499 4970 1988 4970 1988 4971 2499 4971 3240 4971 1988 4972 3240 4972 2500 4972 2500 4973 3240 4973 2501 4973 2500 4974 2501 4974 1985 4974 1985 4975 2501 4975 2502 4975 1985 4976 2502 4976 1984 4976 1984 4977 2502 4977 3252 4977 1984 4978 3252 4978 2503 4978 2503 4979 3252 4979 3251 4979 2503 4980 3251 4980 1983 4980 1983 4981 3251 4981 2504 4981 1983 4982 2504 4982 1980 4982 1980 4983 2504 4983 3249 4983 1980 4984 3249 4984 1979 4984 1979 4985 3249 4985 3248 4985 1979 4986 3248 4986 1978 4986 1978 4987 3248 4987 2505 4987 1978 4988 2505 4988 1977 4988 1977 4989 2505 4989 3246 4989 1977 4990 3246 4990 1976 4990 3227 4991 1958 4991 2506 4991 2506 4992 1958 4992 1973 4992 2506 4993 1973 4993 3241 4993 3241 4994 1973 4994 1975 4994 3241 4995 1975 4995 2507 4995 2507 4996 1975 4996 2508 4996 2507 4997 2508 4997 3243 4997 3243 4998 2508 4998 1976 4998 3243 4999 1976 4999 3244 4999 3244 5000 1976 5000 3246 5000 1958 5001 3227 5001 2509 5001 1958 5002 2509 5002 1959 5002 1959 5003 2509 5003 3226 5003 1959 5004 3226 5004 1957 5004 1957 5005 3226 5005 3223 5005 1957 5006 3223 5006 2510 5006 2510 5007 3223 5007 3225 5007 2510 5008 3225 5008 1962 5008 2447 5009 1962 5009 2446 5009 2446 5010 1962 5010 3225 5010 2511 5011 2512 5011 2791 5011 3187 5012 2000 5012 2513 5012 2513 5013 2000 5013 2511 5013 2513 5014 2511 5014 2514 5014 2514 5015 2511 5015 2791 5015 2000 5016 3187 5016 3186 5016 2000 5017 3186 5017 2515 5017 2515 5018 3186 5018 3185 5018 2515 5019 3185 5019 2001 5019 2001 5020 3185 5020 3184 5020 2001 5021 3184 5021 2516 5021 2516 5022 3184 5022 3183 5022 2516 5023 3183 5023 2021 5023 2021 5024 3183 5024 2517 5024 2517 5025 3183 5025 3175 5025 2517 5026 3175 5026 2518 5026 2518 5027 3175 5027 3174 5027 2518 5028 3174 5028 2519 5028 2519 5029 3174 5029 3173 5029 2519 5030 3173 5030 2020 5030 3173 5031 2520 5031 2020 5031 2020 5032 2520 5032 3171 5032 2020 5033 3171 5033 2521 5033 2521 5034 3171 5034 3170 5034 2521 5035 3170 5035 2522 5035 2522 5036 3170 5036 3169 5036 2522 5037 3169 5037 2019 5037 2019 5038 3169 5038 3166 5038 2019 5039 3166 5039 2523 5039 2523 5040 3166 5040 3165 5040 2523 5041 3165 5041 2524 5041 2524 5042 3165 5042 3164 5042 2524 5043 3164 5043 2525 5043 2525 5044 3164 5044 3163 5044 2525 5045 3163 5045 2526 5045 2526 5046 3163 5046 2527 5046 2526 5047 2527 5047 2528 5047 2528 5048 2527 5048 2529 5048 2528 5049 2529 5049 2014 5049 2014 5050 2529 5050 3160 5050 2014 5051 3160 5051 2530 5051 2530 5052 3160 5052 3159 5052 2530 5053 3159 5053 2013 5053 2013 5054 3159 5054 3158 5054 2013 5055 3158 5055 2531 5055 2531 5056 3158 5056 2532 5056 2531 5057 2532 5057 2533 5057 2533 5058 2532 5058 3157 5058 2533 5059 3157 5059 2534 5059 2534 5060 3157 5060 3154 5060 2534 5061 3154 5061 2010 5061 2010 5062 3154 5062 3153 5062 2010 5063 3153 5063 2009 5063 2009 5064 3153 5064 3152 5064 2009 5065 3152 5065 2008 5065 3144 5066 2539 5066 3145 5066 3145 5067 2539 5067 2004 5067 3145 5068 2004 5068 3147 5068 3147 5069 2004 5069 2535 5069 3147 5070 2535 5070 2536 5070 2536 5071 2535 5071 2537 5071 2536 5072 2537 5072 2538 5072 2538 5073 2537 5073 2008 5073 2538 5074 2008 5074 3150 5074 3150 5075 2008 5075 3152 5075 2539 5076 3144 5076 3137 5076 2539 5077 3137 5077 1996 5077 1996 5078 3137 5078 2540 5078 1996 5079 2540 5079 2541 5079 2541 5080 2540 5080 3136 5080 2541 5081 3136 5081 1999 5081 1999 5082 3136 5082 3135 5082 1999 5083 3135 5083 1998 5083 2821 5084 2024 5084 2822 5084 2822 5085 2024 5085 2026 5085 2822 5086 2026 5086 3134 5086 3134 5087 2026 5087 1998 5087 3134 5088 1998 5088 3135 5088 2542 5089 2677 5089 2561 5089 2686 5090 2543 5090 3325 5090 2686 5091 3325 5091 2544 5091 2561 5092 3293 5092 2545 5092 2555 5093 2557 5093 3325 5093 3325 5094 2557 5094 2546 5094 3325 5095 2546 5095 2544 5095 2561 5096 2677 5096 2553 5096 2553 5097 2677 5097 2547 5097 2553 5098 2547 5098 2548 5098 2548 5099 2549 5099 2553 5099 2553 5100 2549 5100 2550 5100 2553 5101 2550 5101 2552 5101 2670 5102 2672 5102 2561 5102 2561 5103 2672 5103 2551 5103 2552 5104 2683 5104 2553 5104 2553 5105 2683 5105 2554 5105 2553 5106 2554 5106 2555 5106 2555 5107 2554 5107 2556 5107 2555 5108 2556 5108 2557 5108 2558 5109 2669 5109 2561 5109 2561 5110 2669 5110 2559 5110 2561 5111 2559 5111 2670 5111 2551 5112 2560 5112 2561 5112 2561 5113 2560 5113 2675 5113 2561 5114 2675 5114 2542 5114 2545 5115 2665 5115 2561 5115 2561 5116 2665 5116 2666 5116 2561 5117 2666 5117 2558 5117 2562 5118 2563 5118 2564 5118 2804 5119 2565 5119 2617 5119 2650 5120 2648 5120 2641 5120 2059 5121 2058 5121 3305 5121 2059 5122 3305 5122 2078 5122 2058 5123 2566 5123 3305 5123 3305 5124 2566 5124 2610 5124 3305 5125 2610 5125 2611 5125 2567 5126 2075 5126 2568 5126 2568 5127 2075 5127 2074 5127 2568 5128 2074 5128 2764 5128 2764 5129 2074 5129 2073 5129 2764 5130 2073 5130 2765 5130 2765 5131 2073 5131 2072 5131 2765 5132 2072 5132 2767 5132 2767 5133 2072 5133 2070 5133 2767 5134 2070 5134 2569 5134 2569 5135 2070 5135 2069 5135 2569 5136 2069 5136 2768 5136 2768 5137 2069 5137 2065 5137 2768 5138 2065 5138 2570 5138 2570 5139 2065 5139 2571 5139 2570 5140 2571 5140 2572 5140 2572 5141 2571 5141 2064 5141 2572 5142 2064 5142 2771 5142 2771 5143 2064 5143 2573 5143 2771 5144 2573 5144 2773 5144 2773 5145 2573 5145 2574 5145 2773 5146 2574 5146 2774 5146 2774 5147 2574 5147 2575 5147 2774 5148 2575 5148 2775 5148 2775 5149 2575 5149 2576 5149 2775 5150 2576 5150 2577 5150 2577 5151 2576 5151 2086 5151 2577 5152 2086 5152 2776 5152 2776 5153 2086 5153 2578 5153 2776 5154 2578 5154 2579 5154 2579 5155 2578 5155 2580 5155 2579 5156 2580 5156 2581 5156 2581 5157 2580 5157 2582 5157 2581 5158 2582 5158 2780 5158 2780 5159 2582 5159 2083 5159 2780 5160 2083 5160 2782 5160 2782 5161 2083 5161 2583 5161 2782 5162 2583 5162 2584 5162 2584 5163 2583 5163 2585 5163 2584 5164 2585 5164 2586 5164 2586 5165 2585 5165 2587 5165 2586 5166 2587 5166 2588 5166 2588 5167 2587 5167 2080 5167 2588 5168 2080 5168 2786 5168 2786 5169 2080 5169 2589 5169 2786 5170 2589 5170 2788 5170 2788 5171 2589 5171 2590 5171 2788 5172 2590 5172 2790 5172 2790 5173 2590 5173 2078 5173 2790 5174 2078 5174 2591 5174 2591 5175 2078 5175 3305 5175 2088 5176 2087 5176 2662 5176 2592 5177 2092 5177 2593 5177 2592 5178 2593 5178 2594 5178 2092 5179 2595 5179 2593 5179 2593 5180 2595 5180 2596 5180 2593 5181 2596 5181 2597 5181 2597 5182 2596 5182 2091 5182 2597 5183 2091 5183 3289 5183 3289 5184 2091 5184 2598 5184 3289 5185 2598 5185 2662 5185 2662 5186 2598 5186 2089 5186 2662 5187 2089 5187 2088 5187 2103 5188 2649 5188 2599 5188 2104 5189 2600 5189 2105 5189 2105 5190 2600 5190 2601 5190 2105 5191 2601 5191 2602 5191 2602 5192 2635 5192 2603 5192 2603 5193 2635 5193 2604 5193 2603 5194 2604 5194 2107 5194 2107 5195 2631 5195 2108 5195 2108 5196 2631 5196 2605 5196 2108 5197 2605 5197 2109 5197 2109 5198 2605 5198 2630 5198 2109 5199 2630 5199 2111 5199 2111 5200 2630 5200 2629 5200 2111 5201 2629 5201 2606 5201 2606 5202 2629 5202 2626 5202 2606 5203 2626 5203 2113 5203 2113 5204 2626 5204 2625 5204 2113 5205 2625 5205 2607 5205 2607 5206 2625 5206 2608 5206 2607 5207 2608 5207 2116 5207 2116 5208 2608 5208 2622 5208 2116 5209 2622 5209 2119 5209 2119 5210 2622 5210 2609 5210 2119 5211 2609 5211 2121 5211 2121 5212 2609 5212 2620 5212 2121 5213 2620 5213 2122 5213 2122 5214 2620 5214 2617 5214 2610 5215 2612 5215 2611 5215 2611 5216 2612 5216 2127 5216 2611 5217 2127 5217 2565 5217 2565 5218 2127 5218 2613 5218 2565 5219 2613 5219 2614 5219 2614 5220 2615 5220 2565 5220 2565 5221 2615 5221 2616 5221 2565 5222 2616 5222 2617 5222 2617 5223 2616 5223 2618 5223 2617 5224 2618 5224 2122 5224 2804 5225 2617 5225 2619 5225 2619 5226 2617 5226 2620 5226 2619 5227 2620 5227 2870 5227 2870 5228 2620 5228 2609 5228 2870 5229 2609 5229 2621 5229 2621 5230 2609 5230 2622 5230 2621 5231 2622 5231 2623 5231 2623 5232 2622 5232 2608 5232 2623 5233 2608 5233 2624 5233 2624 5234 2608 5234 2625 5234 2624 5235 2625 5235 2627 5235 2627 5236 2625 5236 2626 5236 2627 5237 2626 5237 2628 5237 2628 5238 2626 5238 2629 5238 2628 5239 2629 5239 2872 5239 2872 5240 2629 5240 2874 5240 2874 5241 2629 5241 2630 5241 2874 5242 2630 5242 2876 5242 2876 5243 2630 5243 2877 5243 2877 5244 2630 5244 2605 5244 2877 5245 2605 5245 2878 5245 2878 5246 2605 5246 2879 5246 2879 5247 2605 5247 2631 5247 2879 5248 2631 5248 2632 5248 2107 5249 2604 5249 2631 5249 2631 5250 2604 5250 2880 5250 2631 5251 2880 5251 2632 5251 2636 5252 2882 5252 2635 5252 2635 5253 2882 5253 2633 5253 2635 5254 2633 5254 2604 5254 2604 5255 2633 5255 2634 5255 2604 5256 2634 5256 2880 5256 2602 5257 2601 5257 2635 5257 2635 5258 2601 5258 2885 5258 2635 5259 2885 5259 2636 5259 2637 5260 2600 5260 2599 5260 2599 5261 2600 5261 2104 5261 2599 5262 2104 5262 2103 5262 2637 5263 2888 5263 2600 5263 2600 5264 2888 5264 2638 5264 2600 5265 2638 5265 2601 5265 2601 5266 2638 5266 2886 5266 2601 5267 2886 5267 2885 5267 2651 5268 2894 5268 2649 5268 2649 5269 2894 5269 2639 5269 2649 5270 2639 5270 2599 5270 2599 5271 2639 5271 2640 5271 2599 5272 2640 5272 2637 5272 2650 5273 2641 5273 2643 5273 2643 5274 2641 5274 2642 5274 2643 5275 2642 5275 2644 5275 2644 5276 2642 5276 2098 5276 2644 5277 2098 5277 2654 5277 2654 5278 2098 5278 2645 5278 2654 5279 2645 5279 2655 5279 2655 5280 2645 5280 2096 5280 2655 5281 2096 5281 2646 5281 2646 5282 2096 5282 2647 5282 2646 5283 2647 5283 2657 5283 2657 5284 2647 5284 2594 5284 2657 5285 2594 5285 2659 5285 2659 5286 2594 5286 2593 5286 2659 5287 2593 5287 2660 5287 2103 5288 2648 5288 2649 5288 2649 5289 2648 5289 2650 5289 2649 5290 2650 5290 2651 5290 2651 5291 2650 5291 2643 5291 2651 5292 2643 5292 2652 5292 2652 5293 2643 5293 2644 5293 2652 5294 2644 5294 2892 5294 2892 5295 2644 5295 2654 5295 2892 5296 2654 5296 2653 5296 2653 5297 2654 5297 2655 5297 2653 5298 2655 5298 2656 5298 2656 5299 2655 5299 2646 5299 2656 5300 2646 5300 2890 5300 2890 5301 2646 5301 2657 5301 2890 5302 2657 5302 2658 5302 2658 5303 2657 5303 2659 5303 2658 5304 2659 5304 2661 5304 2661 5305 2659 5305 2660 5305 2661 5306 2660 5306 3300 5306 2087 5307 2567 5307 2662 5307 2662 5308 2567 5308 2568 5308 2662 5309 2568 5309 2563 5309 2738 5310 3291 5310 2562 5310 3291 5311 2738 5311 2713 5311 2663 5312 2713 5312 2714 5312 3293 5313 2663 5313 2664 5313 3293 5314 2664 5314 2545 5314 2545 5315 2664 5315 2691 5315 2545 5316 2691 5316 2665 5316 2665 5317 2691 5317 2692 5317 2665 5318 2692 5318 2666 5318 2666 5319 2692 5319 2667 5319 2666 5320 2667 5320 2558 5320 2558 5321 2667 5321 2668 5321 2558 5322 2668 5322 2669 5322 2669 5323 2668 5323 2694 5323 2669 5324 2694 5324 2559 5324 2559 5325 2694 5325 2695 5325 2559 5326 2695 5326 2670 5326 2670 5327 2695 5327 2671 5327 2670 5328 2671 5328 2672 5328 2672 5329 2671 5329 2697 5329 2672 5330 2697 5330 2551 5330 2551 5331 2697 5331 2673 5331 2551 5332 2673 5332 2560 5332 2560 5333 2673 5333 2674 5333 2560 5334 2674 5334 2675 5334 2675 5335 2674 5335 2699 5335 2675 5336 2699 5336 2542 5336 2542 5337 2699 5337 2676 5337 2542 5338 2676 5338 2677 5338 2677 5339 2676 5339 2678 5339 2677 5340 2678 5340 2547 5340 2547 5341 2678 5341 2679 5341 2547 5342 2679 5342 2548 5342 2548 5343 2679 5343 2680 5343 2548 5344 2680 5344 2549 5344 2549 5345 2680 5345 2704 5345 2549 5346 2704 5346 2550 5346 2550 5347 2704 5347 2681 5347 2550 5348 2681 5348 2552 5348 2552 5349 2681 5349 2682 5349 2552 5350 2682 5350 2683 5350 2683 5351 2682 5351 2684 5351 2683 5352 2684 5352 2554 5352 2554 5353 2684 5353 2685 5353 2554 5354 2685 5354 2556 5354 2556 5355 2685 5355 2708 5355 2556 5356 2708 5356 2557 5356 2557 5357 2708 5357 2710 5357 2557 5358 2710 5358 2546 5358 2546 5359 2710 5359 2711 5359 2546 5360 2711 5360 2544 5360 2544 5361 2711 5361 2687 5361 2544 5362 2687 5362 2686 5362 2686 5363 2687 5363 2712 5363 2686 5364 2712 5364 2543 5364 2688 5365 3306 5365 3254 5365 2762 5366 3312 5366 2737 5366 2761 5367 2689 5367 2763 5367 2663 5368 2714 5368 2664 5368 2664 5369 2714 5369 2690 5369 2664 5370 2690 5370 2691 5370 2691 5371 2690 5371 2716 5371 2691 5372 2716 5372 2692 5372 2692 5373 2716 5373 2717 5373 2692 5374 2717 5374 2667 5374 2667 5375 2717 5375 2693 5375 2667 5376 2693 5376 2668 5376 2668 5377 2693 5377 2720 5377 2668 5378 2720 5378 2694 5378 2694 5379 2720 5379 2723 5379 2694 5380 2723 5380 2695 5380 2695 5381 2723 5381 2696 5381 2695 5382 2696 5382 2671 5382 2671 5383 2696 5383 2724 5383 2671 5384 2724 5384 2697 5384 2697 5385 2724 5385 2698 5385 2697 5386 2698 5386 2673 5386 2673 5387 2698 5387 2726 5387 2673 5388 2726 5388 2674 5388 2674 5389 2726 5389 2727 5389 2674 5390 2727 5390 2699 5390 2699 5391 2727 5391 2700 5391 2699 5392 2700 5392 2676 5392 2676 5393 2700 5393 2729 5393 2676 5394 2729 5394 2678 5394 2678 5395 2729 5395 2701 5395 2678 5396 2701 5396 2679 5396 2679 5397 2701 5397 2702 5397 2679 5398 2702 5398 2680 5398 2680 5399 2702 5399 2703 5399 2680 5400 2703 5400 2704 5400 2704 5401 2703 5401 2705 5401 2704 5402 2705 5402 2681 5402 2681 5403 2705 5403 2706 5403 2681 5404 2706 5404 2682 5404 2682 5405 2706 5405 2733 5405 2682 5406 2733 5406 2684 5406 2684 5407 2733 5407 2734 5407 2684 5408 2734 5408 2685 5408 2685 5409 2734 5409 2707 5409 2685 5410 2707 5410 2708 5410 2708 5411 2707 5411 2709 5411 2708 5412 2709 5412 2710 5412 2710 5413 2709 5413 2736 5413 2710 5414 2736 5414 2711 5414 2711 5415 2736 5415 2688 5415 2711 5416 2688 5416 2687 5416 2687 5417 2688 5417 3254 5417 2687 5418 3254 5418 2712 5418 2713 5419 2738 5419 2714 5419 2714 5420 2738 5420 2715 5420 2714 5421 2715 5421 2690 5421 2690 5422 2715 5422 2740 5422 2690 5423 2740 5423 2716 5423 2716 5424 2740 5424 2718 5424 2716 5425 2718 5425 2717 5425 2717 5426 2718 5426 2742 5426 2717 5427 2742 5427 2693 5427 2693 5428 2742 5428 2719 5428 2693 5429 2719 5429 2720 5429 2720 5430 2719 5430 2721 5430 2720 5431 2721 5431 2723 5431 2723 5432 2721 5432 2722 5432 2723 5433 2722 5433 2696 5433 2696 5434 2722 5434 2745 5434 2696 5435 2745 5435 2724 5435 2724 5436 2745 5436 2747 5436 2724 5437 2747 5437 2698 5437 2698 5438 2747 5438 2749 5438 2698 5439 2749 5439 2726 5439 2726 5440 2749 5440 2725 5440 2726 5441 2725 5441 2727 5441 2727 5442 2725 5442 2752 5442 2727 5443 2752 5443 2700 5443 2700 5444 2752 5444 2728 5444 2700 5445 2728 5445 2729 5445 2729 5446 2728 5446 2753 5446 2729 5447 2753 5447 2701 5447 2701 5448 2753 5448 2754 5448 2701 5449 2754 5449 2702 5449 2702 5450 2754 5450 2730 5450 2702 5451 2730 5451 2703 5451 2703 5452 2730 5452 2756 5452 2703 5453 2756 5453 2705 5453 2705 5454 2756 5454 2731 5454 2705 5455 2731 5455 2706 5455 2706 5456 2731 5456 2732 5456 2706 5457 2732 5457 2733 5457 2733 5458 2732 5458 2757 5458 2733 5459 2757 5459 2734 5459 2734 5460 2757 5460 2758 5460 2734 5461 2758 5461 2707 5461 2707 5462 2758 5462 2760 5462 2707 5463 2760 5463 2709 5463 2709 5464 2760 5464 2735 5464 2709 5465 2735 5465 2736 5465 2736 5466 2735 5466 2762 5466 2736 5467 2762 5467 2688 5467 2688 5468 2762 5468 2737 5468 2688 5469 2737 5469 3306 5469 2562 5470 2564 5470 2738 5470 2738 5471 2564 5471 2739 5471 2738 5472 2739 5472 2715 5472 2715 5473 2739 5473 2766 5473 2715 5474 2766 5474 2740 5474 2740 5475 2766 5475 2741 5475 2740 5476 2741 5476 2718 5476 2718 5477 2741 5477 2743 5477 2718 5478 2743 5478 2742 5478 2742 5479 2743 5479 2744 5479 2742 5480 2744 5480 2719 5480 2719 5481 2744 5481 2769 5481 2719 5482 2769 5482 2721 5482 2721 5483 2769 5483 2770 5483 2721 5484 2770 5484 2722 5484 2722 5485 2770 5485 2772 5485 2722 5486 2772 5486 2745 5486 2745 5487 2772 5487 2746 5487 2745 5488 2746 5488 2747 5488 2747 5489 2746 5489 2748 5489 2747 5490 2748 5490 2749 5490 2749 5491 2748 5491 2750 5491 2749 5492 2750 5492 2725 5492 2725 5493 2750 5493 2751 5493 2725 5494 2751 5494 2752 5494 2752 5495 2751 5495 2777 5495 2752 5496 2777 5496 2728 5496 2728 5497 2777 5497 2778 5497 2728 5498 2778 5498 2753 5498 2753 5499 2778 5499 2779 5499 2753 5500 2779 5500 2754 5500 2754 5501 2779 5501 2755 5501 2754 5502 2755 5502 2730 5502 2730 5503 2755 5503 2781 5503 2730 5504 2781 5504 2756 5504 2756 5505 2781 5505 2783 5505 2756 5506 2783 5506 2731 5506 2731 5507 2783 5507 2784 5507 2731 5508 2784 5508 2732 5508 2732 5509 2784 5509 2785 5509 2732 5510 2785 5510 2757 5510 2757 5511 2785 5511 2787 5511 2757 5512 2787 5512 2758 5512 2758 5513 2787 5513 2759 5513 2758 5514 2759 5514 2760 5514 2760 5515 2759 5515 2789 5515 2760 5516 2789 5516 2735 5516 2735 5517 2789 5517 2761 5517 2735 5518 2761 5518 2762 5518 2762 5519 2761 5519 2763 5519 2762 5520 2763 5520 3312 5520 2563 5521 2568 5521 2564 5521 2564 5522 2568 5522 2764 5522 2564 5523 2764 5523 2739 5523 2739 5524 2764 5524 2765 5524 2739 5525 2765 5525 2766 5525 2766 5526 2765 5526 2767 5526 2766 5527 2767 5527 2741 5527 2741 5528 2767 5528 2569 5528 2741 5529 2569 5529 2743 5529 2743 5530 2569 5530 2768 5530 2743 5531 2768 5531 2744 5531 2744 5532 2768 5532 2570 5532 2744 5533 2570 5533 2769 5533 2769 5534 2570 5534 2572 5534 2769 5535 2572 5535 2770 5535 2770 5536 2572 5536 2771 5536 2770 5537 2771 5537 2772 5537 2772 5538 2771 5538 2773 5538 2772 5539 2773 5539 2746 5539 2746 5540 2773 5540 2774 5540 2746 5541 2774 5541 2748 5541 2748 5542 2774 5542 2775 5542 2748 5543 2775 5543 2750 5543 2750 5544 2775 5544 2577 5544 2750 5545 2577 5545 2751 5545 2751 5546 2577 5546 2776 5546 2751 5547 2776 5547 2777 5547 2777 5548 2776 5548 2579 5548 2777 5549 2579 5549 2778 5549 2778 5550 2579 5550 2581 5550 2778 5551 2581 5551 2779 5551 2779 5552 2581 5552 2780 5552 2779 5553 2780 5553 2755 5553 2755 5554 2780 5554 2782 5554 2755 5555 2782 5555 2781 5555 2781 5556 2782 5556 2584 5556 2781 5557 2584 5557 2783 5557 2783 5558 2584 5558 2586 5558 2783 5559 2586 5559 2784 5559 2784 5560 2586 5560 2588 5560 2784 5561 2588 5561 2785 5561 2785 5562 2588 5562 2786 5562 2785 5563 2786 5563 2787 5563 2787 5564 2786 5564 2788 5564 2787 5565 2788 5565 2759 5565 2759 5566 2788 5566 2790 5566 2759 5567 2790 5567 2789 5567 2789 5568 2790 5568 2591 5568 2789 5569 2591 5569 2761 5569 2761 5570 2591 5570 3305 5570 2761 5571 3305 5571 2689 5571 2796 5572 2192 5572 2798 5572 2514 5573 2791 5573 3297 5573 3297 5574 2791 5574 2795 5574 2201 5575 2158 5575 2793 5575 2201 5576 2793 5576 2792 5576 2792 5577 2793 5577 2823 5577 2792 5578 2823 5578 2794 5578 2200 5579 3297 5579 2201 5579 2201 5580 3297 5580 2795 5580 2201 5581 2795 5581 2158 5581 2796 5582 2798 5582 2194 5582 2200 5583 2199 5583 3297 5583 3297 5584 2199 5584 2197 5584 3297 5585 2197 5585 2798 5585 2798 5586 2197 5586 2196 5586 2798 5587 2196 5587 2194 5587 2273 5588 2192 5588 2797 5588 2273 5589 2797 5589 2274 5589 2192 5590 2273 5590 2798 5590 2798 5591 2273 5591 2799 5591 2798 5592 2799 5592 2270 5592 2265 5593 2800 5593 3300 5593 2270 5594 2801 5594 2798 5594 2798 5595 2801 5595 2802 5595 2798 5596 2802 5596 3300 5596 3300 5597 2802 5597 2267 5597 3300 5598 2267 5598 2265 5598 2800 5599 2263 5599 3300 5599 3300 5600 2263 5600 2803 5600 3300 5601 2803 5601 2661 5601 2869 5602 2240 5602 2804 5602 2240 5603 2805 5603 2804 5603 2804 5604 2805 5604 2806 5604 2804 5605 2806 5605 2807 5605 2808 5606 2812 5606 2815 5606 2808 5607 2815 5607 2301 5607 2807 5608 2232 5608 2804 5608 2804 5609 2232 5609 2302 5609 2804 5610 2302 5610 2815 5610 2815 5611 2302 5611 2809 5611 2815 5612 2809 5612 2301 5612 2164 5613 2813 5613 2811 5613 2818 5614 2810 5614 2820 5614 2811 5615 2813 5615 2812 5615 2812 5616 2813 5616 2814 5616 2812 5617 2814 5617 2815 5617 2815 5618 2814 5618 2162 5618 2815 5619 2162 5619 2816 5619 2816 5620 2817 5620 2815 5620 2815 5621 2817 5621 2229 5621 2815 5622 2229 5622 2820 5622 2820 5623 2229 5623 2227 5623 2820 5624 2227 5624 2818 5624 2135 5625 2819 5625 2847 5625 2847 5626 2819 5626 2131 5626 2847 5627 2131 5627 2810 5627 2131 5628 2129 5628 2810 5628 2810 5629 2129 5629 2128 5629 2810 5630 2128 5630 2820 5630 2820 5631 2128 5631 2821 5631 2820 5632 2821 5632 2822 5632 2823 5633 2824 5633 2794 5633 2794 5634 2824 5634 2134 5634 2794 5635 2134 5635 2825 5635 2825 5636 2134 5636 2133 5636 2825 5637 2133 5637 2826 5637 2826 5638 2133 5638 2132 5638 2826 5639 2132 5639 2827 5639 2827 5640 2132 5640 2828 5640 2827 5641 2828 5641 2208 5641 2208 5642 2828 5642 2829 5642 2208 5643 2829 5643 2210 5643 2210 5644 2829 5644 2155 5644 2210 5645 2155 5645 2211 5645 2211 5646 2155 5646 2154 5646 2211 5647 2154 5647 2212 5647 2212 5648 2154 5648 2153 5648 2212 5649 2153 5649 2214 5649 2214 5650 2153 5650 2152 5650 2214 5651 2152 5651 2830 5651 2830 5652 2152 5652 2831 5652 2830 5653 2831 5653 2216 5653 2216 5654 2831 5654 2151 5654 2216 5655 2151 5655 2832 5655 2832 5656 2151 5656 2149 5656 2832 5657 2149 5657 2219 5657 2219 5658 2149 5658 2148 5658 2219 5659 2148 5659 2220 5659 2220 5660 2148 5660 2833 5660 2220 5661 2833 5661 2834 5661 2834 5662 2833 5662 2147 5662 2834 5663 2147 5663 2221 5663 2221 5664 2147 5664 2145 5664 2221 5665 2145 5665 2835 5665 2835 5666 2145 5666 2144 5666 2835 5667 2144 5667 2836 5667 2836 5668 2144 5668 2142 5668 2836 5669 2142 5669 2223 5669 2223 5670 2142 5670 2837 5670 2223 5671 2837 5671 2838 5671 2838 5672 2837 5672 2140 5672 2838 5673 2140 5673 2839 5673 2839 5674 2140 5674 2840 5674 2839 5675 2840 5675 2841 5675 2841 5676 2840 5676 2842 5676 2841 5677 2842 5677 2843 5677 2843 5678 2842 5678 2844 5678 2843 5679 2844 5679 2206 5679 2206 5680 2844 5680 2846 5680 2206 5681 2846 5681 2845 5681 2845 5682 2846 5682 2135 5682 2845 5683 2135 5683 2203 5683 2203 5684 2135 5684 2847 5684 2797 5685 2848 5685 2274 5685 2274 5686 2848 5686 2165 5686 2274 5687 2165 5687 2849 5687 2849 5688 2165 5688 2167 5688 2849 5689 2167 5689 2850 5689 2850 5690 2167 5690 2191 5690 2850 5691 2191 5691 2284 5691 2284 5692 2191 5692 2851 5692 2284 5693 2851 5693 2852 5693 2852 5694 2851 5694 2189 5694 2852 5695 2189 5695 2285 5695 2285 5696 2189 5696 2187 5696 2285 5697 2187 5697 2853 5697 2853 5698 2187 5698 2854 5698 2853 5699 2854 5699 2287 5699 2287 5700 2854 5700 2855 5700 2287 5701 2855 5701 2288 5701 2288 5702 2855 5702 2184 5702 2288 5703 2184 5703 2289 5703 2289 5704 2184 5704 2183 5704 2289 5705 2183 5705 2290 5705 2290 5706 2183 5706 2856 5706 2290 5707 2856 5707 2857 5707 2857 5708 2856 5708 2181 5708 2857 5709 2181 5709 2858 5709 2858 5710 2181 5710 2178 5710 2858 5711 2178 5711 2859 5711 2859 5712 2178 5712 2860 5712 2859 5713 2860 5713 2293 5713 2293 5714 2860 5714 2176 5714 2293 5715 2176 5715 2294 5715 2294 5716 2176 5716 2861 5716 2294 5717 2861 5717 2862 5717 2862 5718 2861 5718 2175 5718 2862 5719 2175 5719 2295 5719 2295 5720 2175 5720 2173 5720 2295 5721 2173 5721 2296 5721 2296 5722 2173 5722 2172 5722 2296 5723 2172 5723 2863 5723 2863 5724 2172 5724 2864 5724 2863 5725 2864 5725 2298 5725 2298 5726 2864 5726 2170 5726 2298 5727 2170 5727 2865 5727 2865 5728 2170 5728 2866 5728 2865 5729 2866 5729 2282 5729 2282 5730 2866 5730 2867 5730 2282 5731 2867 5731 2281 5731 2281 5732 2867 5732 2868 5732 2281 5733 2868 5733 2280 5733 2280 5734 2868 5734 2164 5734 2280 5735 2164 5735 2278 5735 2278 5736 2164 5736 2811 5736 2804 5737 2619 5737 2869 5737 2869 5738 2619 5738 2870 5738 2869 5739 2870 5739 2871 5739 2871 5740 2870 5740 2621 5740 2871 5741 2621 5741 2243 5741 2243 5742 2621 5742 2623 5742 2243 5743 2623 5743 2244 5743 2244 5744 2623 5744 2624 5744 2244 5745 2624 5745 2245 5745 2245 5746 2624 5746 2627 5746 2245 5747 2627 5747 2247 5747 2247 5748 2627 5748 2628 5748 2247 5749 2628 5749 2248 5749 2248 5750 2628 5750 2872 5750 2248 5751 2872 5751 2873 5751 2873 5752 2872 5752 2874 5752 2873 5753 2874 5753 2251 5753 2251 5754 2874 5754 2876 5754 2251 5755 2876 5755 2875 5755 2876 5756 2877 5756 2875 5756 2875 5757 2877 5757 2878 5757 2875 5758 2878 5758 2254 5758 2878 5759 2879 5759 2254 5759 2254 5760 2879 5760 2632 5760 2254 5761 2632 5761 2881 5761 2632 5762 2880 5762 2881 5762 2881 5763 2880 5763 2634 5763 2881 5764 2634 5764 2256 5764 2634 5765 2633 5765 2256 5765 2256 5766 2633 5766 2882 5766 2256 5767 2882 5767 2883 5767 2883 5768 2882 5768 2636 5768 2883 5769 2636 5769 2884 5769 2636 5770 2885 5770 2884 5770 2884 5771 2885 5771 2886 5771 2884 5772 2886 5772 2887 5772 2886 5773 2638 5773 2887 5773 2887 5774 2638 5774 2888 5774 2887 5775 2888 5775 2257 5775 2888 5776 2637 5776 2257 5776 2257 5777 2637 5777 2640 5777 2257 5778 2640 5778 2893 5778 2893 5779 2640 5779 2639 5779 2803 5780 2236 5780 2661 5780 2661 5781 2236 5781 2889 5781 2661 5782 2889 5782 2658 5782 2658 5783 2889 5783 2237 5783 2658 5784 2237 5784 2890 5784 2890 5785 2237 5785 2891 5785 2890 5786 2891 5786 2656 5786 2656 5787 2891 5787 2262 5787 2656 5788 2262 5788 2653 5788 2653 5789 2262 5789 2261 5789 2653 5790 2261 5790 2892 5790 2892 5791 2261 5791 2259 5791 2892 5792 2259 5792 2652 5792 2652 5793 2259 5793 2258 5793 2652 5794 2258 5794 2651 5794 2651 5795 2258 5795 2893 5795 2651 5796 2893 5796 2894 5796 2894 5797 2893 5797 2639 5797 2896 5798 2895 5798 2902 5798 2896 5799 2902 5799 2911 5799 2951 5800 2953 5800 2897 5800 2897 5801 2953 5801 2902 5801 3374 5802 2898 5802 2943 5802 2953 5803 2954 5803 2902 5803 2902 5804 2954 5804 2899 5804 2902 5805 2899 5805 2956 5805 2943 5806 2946 5806 3374 5806 3374 5807 2946 5807 2900 5807 3374 5808 2900 5808 2901 5808 2956 5809 2958 5809 2902 5809 2902 5810 2958 5810 2959 5810 2902 5811 2959 5811 2960 5811 2903 5812 2907 5812 2897 5812 2960 5813 2961 5813 2902 5813 2902 5814 2961 5814 2904 5814 2902 5815 2904 5815 2905 5815 2900 5816 2906 5816 2901 5816 2901 5817 2906 5817 2947 5817 2901 5818 2947 5818 2897 5818 2897 5819 2947 5819 2948 5819 2897 5820 2948 5820 2903 5820 2907 5821 2908 5821 2897 5821 2897 5822 2908 5822 2950 5822 2897 5823 2950 5823 2951 5823 2905 5824 2909 5824 2902 5824 2902 5825 2909 5825 2910 5825 2902 5826 2910 5826 2911 5826 3082 5827 3375 5827 3084 5827 2321 5828 2320 5828 3020 5828 3020 5829 2320 5829 2306 5829 3020 5830 2306 5830 2939 5830 2912 5831 2334 5831 3362 5831 3362 5832 2334 5832 2913 5832 3362 5833 2913 5833 2975 5833 2914 5834 2343 5834 2915 5834 2914 5835 2915 5835 2938 5835 2343 5836 2916 5836 2915 5836 2915 5837 2916 5837 2341 5837 2915 5838 2341 5838 3360 5838 3360 5839 2341 5839 2339 5839 3360 5840 2339 5840 2917 5840 2917 5841 2339 5841 2337 5841 2917 5842 2337 5842 3362 5842 3362 5843 2337 5843 2336 5843 3362 5844 2336 5844 2912 5844 3021 5845 2918 5845 2919 5845 2919 5846 2918 5846 2357 5846 2919 5847 2357 5847 3108 5847 3108 5848 2357 5848 2358 5848 3108 5849 2358 5849 3109 5849 3109 5850 2358 5850 2920 5850 3109 5851 2920 5851 3110 5851 3110 5852 2920 5852 2359 5852 3110 5853 2359 5853 3111 5853 3111 5854 2359 5854 2360 5854 3111 5855 2360 5855 2921 5855 2921 5856 2360 5856 2361 5856 2921 5857 2361 5857 3113 5857 3113 5858 2361 5858 2363 5858 3113 5859 2363 5859 3115 5859 3115 5860 2363 5860 2365 5860 3115 5861 2365 5861 3116 5861 3116 5862 2365 5862 2922 5862 3116 5863 2922 5863 2923 5863 2923 5864 2922 5864 2367 5864 2923 5865 2367 5865 3117 5865 3117 5866 2367 5866 2924 5866 3117 5867 2924 5867 3118 5867 3118 5868 2924 5868 2925 5868 3118 5869 2925 5869 2927 5869 2927 5870 2925 5870 2926 5870 2927 5871 2926 5871 3121 5871 3121 5872 2926 5872 2368 5872 3121 5873 2368 5873 2928 5873 2928 5874 2368 5874 2355 5874 2928 5875 2355 5875 2929 5875 2929 5876 2355 5876 2930 5876 2929 5877 2930 5877 2931 5877 2931 5878 2930 5878 2352 5878 2931 5879 2352 5879 3122 5879 3122 5880 2352 5880 2351 5880 3122 5881 2351 5881 3124 5881 3124 5882 2351 5882 2933 5882 3124 5883 2933 5883 2932 5883 2932 5884 2933 5884 2934 5884 2932 5885 2934 5885 3125 5885 3125 5886 2934 5886 2348 5886 3125 5887 2348 5887 2935 5887 2935 5888 2348 5888 2937 5888 2935 5889 2937 5889 2936 5889 2936 5890 2937 5890 2346 5890 2936 5891 2346 5891 3128 5891 3128 5892 2346 5892 2938 5892 3128 5893 2938 5893 3131 5893 3131 5894 2938 5894 2915 5894 2370 5895 2369 5895 3376 5895 2939 5896 2940 5896 3020 5896 3020 5897 2940 5897 2374 5897 3020 5898 2374 5898 2941 5898 2941 5899 2374 5899 2373 5899 2941 5900 2373 5900 3376 5900 3376 5901 2373 5901 2942 5901 3376 5902 2942 5902 2370 5902 2943 5903 3024 5903 2944 5903 2943 5904 2944 5904 2946 5904 2946 5905 2944 5905 2945 5905 2946 5906 2945 5906 2900 5906 2900 5907 2945 5907 3027 5907 2900 5908 3027 5908 2906 5908 2906 5909 3027 5909 3028 5909 2906 5910 3028 5910 2947 5910 2947 5911 3028 5911 3030 5911 2947 5912 3030 5912 2948 5912 2948 5913 3030 5913 3031 5913 2948 5914 3031 5914 2903 5914 2903 5915 3031 5915 3034 5915 2903 5916 3034 5916 2907 5916 2907 5917 3034 5917 2949 5917 2907 5918 2949 5918 2908 5918 2908 5919 2949 5919 3037 5919 2908 5920 3037 5920 2950 5920 2950 5921 3037 5921 2952 5921 2950 5922 2952 5922 2951 5922 2951 5923 2952 5923 3040 5923 2951 5924 3040 5924 2953 5924 2953 5925 3040 5925 3042 5925 2953 5926 3042 5926 2954 5926 2954 5927 3042 5927 2955 5927 2954 5928 2955 5928 2899 5928 2899 5929 2955 5929 3045 5929 2899 5930 3045 5930 2956 5930 2956 5931 3045 5931 2957 5931 2956 5932 2957 5932 2958 5932 2958 5933 2957 5933 3046 5933 2958 5934 3046 5934 2959 5934 2959 5935 3046 5935 3048 5935 2959 5936 3048 5936 2960 5936 2960 5937 3048 5937 3049 5937 2960 5938 3049 5938 2961 5938 2961 5939 3049 5939 2962 5939 2961 5940 2962 5940 2904 5940 2904 5941 2962 5941 3051 5941 2904 5942 3051 5942 2905 5942 2905 5943 3051 5943 3054 5943 2905 5944 3054 5944 2909 5944 2909 5945 3054 5945 3055 5945 2909 5946 3055 5946 2910 5946 2910 5947 3055 5947 2963 5947 2910 5948 2963 5948 2911 5948 2911 5949 2963 5949 3057 5949 2911 5950 3057 5950 2896 5950 2896 5951 3057 5951 3355 5951 2896 5952 3355 5952 2895 5952 3106 5953 3132 5953 3359 5953 2974 5954 3189 5954 2964 5954 2976 5955 2965 5955 3004 5955 3004 5956 2965 5956 2966 5956 3004 5957 2966 5957 2967 5957 2967 5958 2966 5958 3229 5958 2967 5959 3229 5959 3002 5959 3002 5960 3229 5960 3230 5960 3002 5961 3230 5961 3001 5961 3001 5962 3230 5962 3232 5962 3001 5963 3232 5963 3000 5963 3000 5964 3232 5964 3234 5964 3000 5965 3234 5965 2998 5965 2998 5966 3234 5966 3237 5966 2998 5967 3237 5967 2968 5967 2968 5968 3237 5968 3238 5968 2968 5969 3238 5969 2969 5969 2969 5970 3238 5970 2970 5970 2969 5971 2970 5971 2971 5971 2971 5972 2970 5972 2973 5972 2971 5973 2973 5973 2972 5973 2972 5974 2973 5974 2974 5974 2972 5975 2974 5975 2975 5975 2975 5976 2974 5976 2964 5976 2975 5977 2964 5977 3362 5977 3008 5978 3239 5978 2976 5978 2976 5979 3239 5979 3228 5979 2976 5980 3228 5980 2965 5980 2978 5981 2977 5981 3008 5981 3008 5982 2977 5982 3253 5982 3008 5983 3253 5983 3239 5983 3008 5984 2979 5984 2978 5984 2978 5985 2979 5985 2980 5985 2978 5986 2980 5986 2981 5986 2981 5987 2980 5987 2982 5987 2981 5988 2982 5988 2983 5988 2983 5989 2982 5989 3012 5989 2983 5990 3012 5990 3250 5990 3250 5991 3012 5991 3014 5991 3250 5992 3014 5992 3247 5992 3247 5993 3014 5993 2984 5993 3247 5994 2984 5994 2985 5994 2985 5995 2984 5995 2987 5995 2985 5996 2987 5996 2986 5996 2986 5997 2987 5997 2988 5997 2986 5998 2988 5998 3245 5998 3245 5999 2988 5999 2990 5999 3245 6000 2990 6000 2989 6000 2989 6001 2990 6001 3018 6001 2989 6002 3018 6002 2991 6002 2991 6003 3018 6003 3019 6003 2991 6004 3019 6004 3242 6004 3242 6005 3019 6005 2992 6005 3242 6006 2992 6006 2993 6006 2913 6007 2308 6007 2975 6007 2975 6008 2308 6008 2994 6008 2975 6009 2994 6009 2972 6009 2972 6010 2994 6010 2995 6010 2972 6011 2995 6011 2971 6011 2971 6012 2995 6012 2312 6012 2971 6013 2312 6013 2969 6013 2969 6014 2312 6014 2996 6014 2969 6015 2996 6015 2968 6015 2968 6016 2996 6016 2997 6016 2968 6017 2997 6017 2998 6017 2998 6018 2997 6018 2999 6018 2998 6019 2999 6019 3000 6019 3000 6020 2999 6020 2314 6020 3000 6021 2314 6021 3001 6021 3001 6022 2314 6022 2316 6022 3001 6023 2316 6023 3002 6023 3002 6024 2316 6024 3003 6024 3002 6025 3003 6025 2967 6025 2967 6026 3003 6026 3005 6026 2967 6027 3005 6027 3004 6027 3004 6028 3005 6028 3006 6028 3004 6029 3006 6029 2976 6029 2976 6030 3006 6030 3007 6030 2976 6031 3007 6031 3008 6031 3008 6032 3007 6032 2333 6032 3008 6033 2333 6033 2979 6033 2979 6034 2333 6034 3009 6034 2979 6035 3009 6035 2980 6035 2980 6036 3009 6036 3010 6036 2980 6037 3010 6037 2982 6037 2982 6038 3010 6038 3011 6038 2982 6039 3011 6039 3012 6039 3012 6040 3011 6040 3013 6040 3012 6041 3013 6041 3014 6041 3014 6042 3013 6042 2328 6042 3014 6043 2328 6043 2984 6043 2984 6044 2328 6044 3015 6044 2984 6045 3015 6045 2987 6045 2987 6046 3015 6046 3016 6046 2987 6047 3016 6047 2988 6047 2988 6048 3016 6048 2327 6048 2988 6049 2327 6049 2990 6049 2990 6050 2327 6050 2325 6050 2990 6051 2325 6051 3018 6051 3018 6052 2325 6052 3017 6052 3018 6053 3017 6053 3019 6053 3019 6054 3017 6054 2321 6054 3019 6055 2321 6055 2992 6055 2992 6056 2321 6056 3020 6056 2992 6057 3020 6057 2993 6057 2993 6058 3020 6058 3378 6058 2369 6059 3021 6059 3376 6059 3376 6060 3021 6060 2919 6060 3376 6061 2919 6061 3375 6061 3022 6062 3371 6062 3083 6062 3083 6063 3371 6063 3082 6063 3023 6064 3372 6064 3058 6064 3058 6065 3372 6065 3022 6065 2943 6066 2898 6066 3024 6066 3024 6067 2898 6067 3368 6067 3024 6068 3368 6068 3023 6068 3023 6069 3058 6069 3024 6069 3024 6070 3058 6070 3059 6070 3024 6071 3059 6071 2944 6071 2944 6072 3059 6072 3025 6072 2944 6073 3025 6073 2945 6073 2945 6074 3025 6074 3026 6074 2945 6075 3026 6075 3027 6075 3027 6076 3026 6076 3029 6076 3027 6077 3029 6077 3028 6077 3028 6078 3029 6078 3064 6078 3028 6079 3064 6079 3030 6079 3030 6080 3064 6080 3032 6080 3030 6081 3032 6081 3031 6081 3031 6082 3032 6082 3033 6082 3031 6083 3033 6083 3034 6083 3034 6084 3033 6084 3035 6084 3034 6085 3035 6085 2949 6085 2949 6086 3035 6086 3036 6086 2949 6087 3036 6087 3037 6087 3037 6088 3036 6088 3038 6088 3037 6089 3038 6089 2952 6089 2952 6090 3038 6090 3039 6090 2952 6091 3039 6091 3040 6091 3040 6092 3039 6092 3041 6092 3040 6093 3041 6093 3042 6093 3042 6094 3041 6094 3043 6094 3042 6095 3043 6095 2955 6095 2955 6096 3043 6096 3044 6096 2955 6097 3044 6097 3045 6097 3045 6098 3044 6098 3072 6098 3045 6099 3072 6099 2957 6099 2957 6100 3072 6100 3074 6100 2957 6101 3074 6101 3046 6101 3046 6102 3074 6102 3047 6102 3046 6103 3047 6103 3048 6103 3048 6104 3047 6104 3075 6104 3048 6105 3075 6105 3049 6105 3049 6106 3075 6106 3078 6106 3049 6107 3078 6107 2962 6107 2962 6108 3078 6108 3050 6108 2962 6109 3050 6109 3051 6109 3051 6110 3050 6110 3052 6110 3051 6111 3052 6111 3054 6111 3054 6112 3052 6112 3053 6112 3054 6113 3053 6113 3055 6113 3055 6114 3053 6114 3080 6114 3055 6115 3080 6115 2963 6115 2963 6116 3080 6116 3056 6116 2963 6117 3056 6117 3057 6117 3057 6118 3056 6118 3353 6118 3057 6119 3353 6119 3355 6119 3022 6120 3083 6120 3058 6120 3058 6121 3083 6121 3086 6121 3058 6122 3086 6122 3059 6122 3059 6123 3086 6123 3060 6123 3059 6124 3060 6124 3025 6124 3025 6125 3060 6125 3061 6125 3025 6126 3061 6126 3026 6126 3026 6127 3061 6127 3062 6127 3026 6128 3062 6128 3029 6128 3029 6129 3062 6129 3063 6129 3029 6130 3063 6130 3064 6130 3064 6131 3063 6131 3065 6131 3064 6132 3065 6132 3032 6132 3032 6133 3065 6133 3066 6133 3032 6134 3066 6134 3033 6134 3033 6135 3066 6135 3067 6135 3033 6136 3067 6136 3035 6136 3035 6137 3067 6137 3068 6137 3035 6138 3068 6138 3036 6138 3036 6139 3068 6139 3069 6139 3036 6140 3069 6140 3038 6140 3038 6141 3069 6141 3095 6141 3038 6142 3095 6142 3039 6142 3039 6143 3095 6143 3070 6143 3039 6144 3070 6144 3041 6144 3041 6145 3070 6145 3096 6145 3041 6146 3096 6146 3043 6146 3043 6147 3096 6147 3098 6147 3043 6148 3098 6148 3044 6148 3044 6149 3098 6149 3100 6149 3044 6150 3100 6150 3072 6150 3072 6151 3100 6151 3071 6151 3072 6152 3071 6152 3074 6152 3074 6153 3071 6153 3073 6153 3074 6154 3073 6154 3047 6154 3047 6155 3073 6155 3103 6155 3047 6156 3103 6156 3075 6156 3075 6157 3103 6157 3076 6157 3075 6158 3076 6158 3078 6158 3078 6159 3076 6159 3077 6159 3078 6160 3077 6160 3050 6160 3050 6161 3077 6161 3105 6161 3050 6162 3105 6162 3052 6162 3052 6163 3105 6163 3079 6163 3052 6164 3079 6164 3053 6164 3053 6165 3079 6165 3107 6165 3053 6166 3107 6166 3080 6166 3080 6167 3107 6167 3081 6167 3080 6168 3081 6168 3056 6168 3056 6169 3081 6169 3352 6169 3056 6170 3352 6170 3353 6170 3082 6171 3084 6171 3083 6171 3083 6172 3084 6172 3085 6172 3083 6173 3085 6173 3086 6173 3086 6174 3085 6174 3087 6174 3086 6175 3087 6175 3060 6175 3060 6176 3087 6176 3088 6176 3060 6177 3088 6177 3061 6177 3061 6178 3088 6178 3089 6178 3061 6179 3089 6179 3062 6179 3062 6180 3089 6180 3090 6180 3062 6181 3090 6181 3063 6181 3063 6182 3090 6182 3112 6182 3063 6183 3112 6183 3065 6183 3065 6184 3112 6184 3114 6184 3065 6185 3114 6185 3066 6185 3066 6186 3114 6186 3091 6186 3066 6187 3091 6187 3067 6187 3067 6188 3091 6188 3092 6188 3067 6189 3092 6189 3068 6189 3068 6190 3092 6190 3093 6190 3068 6191 3093 6191 3069 6191 3069 6192 3093 6192 3094 6192 3069 6193 3094 6193 3095 6193 3095 6194 3094 6194 3119 6194 3095 6195 3119 6195 3070 6195 3070 6196 3119 6196 3120 6196 3070 6197 3120 6197 3096 6197 3096 6198 3120 6198 3097 6198 3096 6199 3097 6199 3098 6199 3098 6200 3097 6200 3099 6200 3098 6201 3099 6201 3100 6201 3100 6202 3099 6202 3101 6202 3100 6203 3101 6203 3071 6203 3071 6204 3101 6204 3123 6204 3071 6205 3123 6205 3073 6205 3073 6206 3123 6206 3102 6206 3073 6207 3102 6207 3103 6207 3103 6208 3102 6208 3126 6208 3103 6209 3126 6209 3076 6209 3076 6210 3126 6210 3127 6210 3076 6211 3127 6211 3077 6211 3077 6212 3127 6212 3104 6212 3077 6213 3104 6213 3105 6213 3105 6214 3104 6214 3129 6214 3105 6215 3129 6215 3079 6215 3079 6216 3129 6216 3130 6216 3079 6217 3130 6217 3107 6217 3107 6218 3130 6218 3106 6218 3107 6219 3106 6219 3081 6219 3081 6220 3106 6220 3359 6220 3081 6221 3359 6221 3352 6221 3375 6222 2919 6222 3084 6222 3084 6223 2919 6223 3108 6223 3084 6224 3108 6224 3085 6224 3085 6225 3108 6225 3109 6225 3085 6226 3109 6226 3087 6226 3087 6227 3109 6227 3110 6227 3087 6228 3110 6228 3088 6228 3088 6229 3110 6229 3111 6229 3088 6230 3111 6230 3089 6230 3089 6231 3111 6231 2921 6231 3089 6232 2921 6232 3090 6232 3090 6233 2921 6233 3113 6233 3090 6234 3113 6234 3112 6234 3112 6235 3113 6235 3115 6235 3112 6236 3115 6236 3114 6236 3114 6237 3115 6237 3116 6237 3114 6238 3116 6238 3091 6238 3091 6239 3116 6239 2923 6239 3091 6240 2923 6240 3092 6240 3092 6241 2923 6241 3117 6241 3092 6242 3117 6242 3093 6242 3093 6243 3117 6243 3118 6243 3093 6244 3118 6244 3094 6244 3094 6245 3118 6245 2927 6245 3094 6246 2927 6246 3119 6246 3119 6247 2927 6247 3121 6247 3119 6248 3121 6248 3120 6248 3120 6249 3121 6249 2928 6249 3120 6250 2928 6250 3097 6250 3097 6251 2928 6251 2929 6251 3097 6252 2929 6252 3099 6252 3099 6253 2929 6253 2931 6253 3099 6254 2931 6254 3101 6254 3101 6255 2931 6255 3122 6255 3101 6256 3122 6256 3123 6256 3123 6257 3122 6257 3124 6257 3123 6258 3124 6258 3102 6258 3102 6259 3124 6259 2932 6259 3102 6260 2932 6260 3126 6260 3126 6261 2932 6261 3125 6261 3126 6262 3125 6262 3127 6262 3127 6263 3125 6263 2935 6263 3127 6264 2935 6264 3104 6264 3104 6265 2935 6265 2936 6265 3104 6266 2936 6266 3129 6266 3129 6267 2936 6267 3128 6267 3129 6268 3128 6268 3130 6268 3130 6269 3128 6269 3131 6269 3130 6270 3131 6270 3106 6270 3106 6271 3131 6271 2915 6271 3106 6272 2915 6272 3132 6272 2513 6273 2514 6273 3297 6273 3143 6274 3133 6274 3141 6274 2822 6275 3134 6275 2820 6275 2820 6276 3134 6276 3135 6276 2820 6277 3135 6277 3136 6277 3139 6278 2540 6278 3137 6278 3139 6279 3137 6279 3138 6279 3138 6280 3137 6280 3144 6280 3138 6281 3144 6281 3146 6281 2376 6282 2820 6282 3139 6282 3139 6283 2820 6283 3136 6283 3139 6284 3136 6284 2540 6284 2376 6285 2375 6285 2820 6285 2820 6286 2375 6286 3140 6286 2820 6287 3140 6287 3141 6287 3141 6288 3140 6288 3142 6288 3141 6289 3142 6289 3143 6289 3144 6290 3145 6290 3146 6290 3146 6291 3145 6291 3147 6291 3146 6292 3147 6292 2382 6292 2382 6293 3147 6293 2536 6293 2382 6294 2536 6294 3148 6294 3148 6295 2536 6295 2538 6295 3148 6296 2538 6296 3149 6296 3149 6297 2538 6297 3150 6297 3149 6298 3150 6298 2384 6298 2384 6299 3150 6299 3152 6299 2384 6300 3152 6300 3151 6300 3151 6301 3152 6301 3153 6301 3151 6302 3153 6302 2386 6302 2386 6303 3153 6303 3154 6303 2386 6304 3154 6304 3155 6304 3155 6305 3154 6305 3157 6305 3155 6306 3157 6306 3156 6306 3156 6307 3157 6307 2532 6307 3156 6308 2532 6308 2388 6308 2388 6309 2532 6309 3158 6309 2388 6310 3158 6310 2390 6310 2390 6311 3158 6311 3159 6311 2390 6312 3159 6312 2392 6312 2392 6313 3159 6313 3160 6313 2392 6314 3160 6314 2394 6314 2394 6315 3160 6315 2529 6315 2394 6316 2529 6316 3161 6316 3161 6317 2529 6317 2527 6317 3161 6318 2527 6318 3162 6318 3162 6319 2527 6319 3163 6319 3162 6320 3163 6320 2395 6320 2395 6321 3163 6321 3164 6321 2395 6322 3164 6322 2397 6322 2397 6323 3164 6323 3165 6323 2397 6324 3165 6324 3167 6324 3167 6325 3165 6325 3166 6325 3167 6326 3166 6326 3168 6326 3168 6327 3166 6327 3169 6327 3168 6328 3169 6328 2399 6328 2399 6329 3169 6329 3170 6329 2399 6330 3170 6330 2400 6330 2400 6331 3170 6331 3171 6331 2400 6332 3171 6332 3172 6332 3172 6333 3171 6333 2520 6333 3172 6334 2520 6334 2381 6334 2381 6335 2520 6335 3173 6335 2381 6336 3173 6336 2380 6336 2380 6337 3173 6337 3174 6337 2380 6338 3174 6338 3176 6338 3176 6339 3174 6339 3175 6339 3176 6340 3175 6340 3177 6340 2409 6341 3178 6341 3181 6341 3181 6342 3178 6342 3179 6342 2402 6343 2401 6343 3297 6343 3179 6344 3180 6344 3181 6344 3181 6345 3180 6345 2406 6345 3181 6346 2406 6346 3297 6346 3297 6347 2406 6347 3182 6347 3297 6348 3182 6348 2402 6348 3184 6349 2401 6349 2378 6349 3177 6350 3175 6350 2378 6350 2378 6351 3175 6351 3183 6351 2378 6352 3183 6352 3184 6352 3184 6353 3185 6353 2401 6353 2401 6354 3185 6354 3186 6354 2401 6355 3186 6355 3297 6355 3297 6356 3186 6356 3187 6356 3297 6357 3187 6357 2513 6357 2487 6358 2484 6358 3189 6358 2484 6359 3188 6359 3189 6359 3189 6360 3188 6360 3190 6360 3189 6361 3190 6361 3191 6361 3191 6362 3192 6362 3189 6362 3189 6363 3192 6363 3193 6363 3189 6364 3193 6364 3181 6364 3181 6365 3193 6365 2480 6365 2413 6366 2412 6366 3194 6366 3194 6367 2412 6367 2409 6367 3194 6368 2409 6368 3195 6368 3195 6369 2409 6369 3181 6369 3195 6370 3181 6370 3196 6370 3196 6371 3181 6371 2480 6371 3222 6372 2438 6372 2456 6372 2456 6373 2438 6373 3197 6373 2456 6374 3197 6374 3198 6374 3198 6375 3197 6375 2439 6375 3198 6376 2439 6376 2458 6376 2458 6377 2439 6377 2441 6377 2458 6378 2441 6378 2459 6378 2459 6379 2441 6379 3199 6379 2459 6380 3199 6380 3200 6380 3200 6381 3199 6381 3201 6381 3200 6382 3201 6382 3202 6382 3202 6383 3201 6383 2433 6383 3202 6384 2433 6384 2463 6384 2463 6385 2433 6385 3203 6385 2463 6386 3203 6386 2465 6386 2465 6387 3203 6387 2430 6387 2465 6388 2430 6388 2467 6388 2467 6389 2430 6389 2429 6389 2467 6390 2429 6390 2468 6390 2468 6391 2429 6391 3204 6391 2468 6392 3204 6392 2470 6392 2470 6393 3204 6393 2426 6393 2470 6394 2426 6394 3205 6394 3205 6395 2426 6395 2425 6395 3205 6396 2425 6396 2472 6396 2472 6397 2425 6397 2424 6397 2472 6398 2424 6398 2473 6398 2473 6399 2424 6399 2422 6399 2473 6400 2422 6400 2474 6400 2474 6401 2422 6401 2420 6401 2474 6402 2420 6402 3206 6402 3206 6403 2420 6403 2419 6403 3206 6404 2419 6404 3207 6404 3207 6405 2419 6405 3208 6405 3207 6406 3208 6406 3209 6406 3209 6407 3208 6407 2415 6407 3209 6408 2415 6408 3210 6408 3210 6409 2415 6409 3211 6409 3210 6410 3211 6410 3212 6410 3212 6411 3211 6411 3213 6411 3212 6412 3213 6412 2479 6412 2479 6413 3213 6413 3214 6413 2479 6414 3214 6414 3216 6414 3216 6415 3214 6415 3215 6415 3216 6416 3215 6416 3217 6416 3217 6417 3215 6417 3218 6417 3217 6418 3218 6418 3219 6418 3219 6419 3218 6419 2413 6419 3219 6420 2413 6420 2454 6420 2454 6421 2413 6421 3194 6421 2450 6422 2442 6422 3220 6422 3220 6423 2442 6423 3221 6423 3220 6424 3221 6424 3222 6424 3222 6425 3221 6425 2436 6425 3222 6426 2436 6426 2438 6426 3224 6427 3141 6427 2450 6427 2450 6428 3141 6428 3133 6428 2450 6429 3133 6429 2442 6429 3223 6430 3226 6430 3378 6430 3224 6431 2448 6431 3141 6431 3141 6432 2448 6432 2446 6432 3141 6433 2446 6433 3378 6433 3378 6434 2446 6434 3225 6434 3378 6435 3225 6435 3223 6435 3226 6436 2509 6436 3378 6436 3378 6437 2509 6437 3227 6437 3378 6438 3227 6438 2993 6438 3239 6439 3240 6439 3228 6439 3228 6440 3240 6440 2499 6440 3228 6441 2499 6441 2965 6441 2965 6442 2499 6442 2497 6442 2965 6443 2497 6443 2966 6443 2966 6444 2497 6444 2496 6444 2966 6445 2496 6445 3229 6445 3229 6446 2496 6446 3231 6446 3229 6447 3231 6447 3230 6447 3230 6448 3231 6448 2494 6448 3230 6449 2494 6449 3232 6449 3232 6450 2494 6450 3233 6450 3232 6451 3233 6451 3234 6451 3234 6452 3233 6452 3235 6452 3234 6453 3235 6453 3237 6453 3237 6454 3235 6454 3236 6454 3237 6455 3236 6455 3238 6455 3238 6456 3236 6456 2491 6456 3238 6457 2491 6457 2970 6457 2970 6458 2491 6458 2489 6458 2970 6459 2489 6459 2973 6459 2973 6460 2489 6460 2487 6460 2973 6461 2487 6461 2974 6461 2974 6462 2487 6462 3189 6462 3253 6463 2502 6463 3239 6463 3239 6464 2502 6464 2501 6464 3239 6465 2501 6465 3240 6465 3227 6466 2506 6466 2993 6466 2993 6467 2506 6467 3241 6467 2993 6468 3241 6468 3242 6468 3242 6469 3241 6469 2507 6469 3242 6470 2507 6470 2991 6470 2991 6471 2507 6471 3243 6471 2991 6472 3243 6472 2989 6472 2989 6473 3243 6473 3244 6473 2989 6474 3244 6474 3245 6474 3245 6475 3244 6475 3246 6475 3245 6476 3246 6476 2986 6476 2986 6477 3246 6477 2505 6477 2986 6478 2505 6478 2985 6478 2985 6479 2505 6479 3248 6479 2985 6480 3248 6480 3247 6480 3247 6481 3248 6481 3249 6481 3247 6482 3249 6482 3250 6482 3250 6483 3249 6483 2504 6483 3250 6484 2504 6484 2983 6484 2983 6485 2504 6485 3251 6485 2983 6486 3251 6486 2981 6486 2981 6487 3251 6487 3252 6487 2981 6488 3252 6488 2978 6488 2978 6489 3252 6489 2502 6489 2978 6490 2502 6490 2977 6490 2977 6491 2502 6491 3253 6491 2712 6492 3254 6492 3307 6492 2815 6493 2820 6493 3364 6493 3418 6494 3417 6494 3255 6494 3256 6495 3257 6495 3307 6495 3258 6496 3283 6496 3271 6496 3513 6497 3313 6497 3314 6497 3508 6498 3510 6498 3259 6498 3259 6499 3510 6499 3260 6499 3259 6500 3260 6500 3314 6500 3314 6501 3260 6501 3512 6501 3314 6502 3512 6502 3513 6502 3508 6503 3259 6503 3261 6503 3261 6504 3259 6504 3315 6504 3261 6505 3315 6505 3262 6505 3262 6506 3315 6506 3263 6506 3262 6507 3263 6507 3267 6507 3264 6508 3489 6508 3265 6508 3265 6509 3489 6509 3487 6509 3265 6510 3487 6510 3263 6510 3263 6511 3487 6511 3266 6511 3263 6512 3266 6512 3267 6512 3264 6513 3265 6513 3268 6513 3268 6514 3265 6514 3317 6514 3268 6515 3317 6515 3269 6515 3319 6516 3401 6516 3270 6516 3270 6517 3401 6517 3400 6517 3270 6518 3400 6518 3317 6518 3317 6519 3400 6519 3399 6519 3317 6520 3399 6520 3269 6520 3258 6521 3271 6521 3405 6521 3405 6522 3271 6522 3272 6522 3405 6523 3272 6523 3273 6523 3273 6524 3272 6524 3406 6524 3406 6525 3272 6525 3274 6525 3406 6526 3274 6526 3407 6526 3407 6527 3274 6527 3287 6527 3407 6528 3287 6528 3275 6528 3324 6529 3410 6529 3275 6529 3256 6530 3307 6530 3309 6530 3414 6531 3413 6531 3310 6531 3310 6532 3276 6532 3414 6532 3414 6533 3276 6533 3277 6533 3414 6534 3277 6534 3416 6534 3418 6535 3255 6535 3278 6535 3278 6536 3255 6536 3304 6536 3278 6537 3304 6537 3421 6537 3421 6538 3304 6538 3279 6538 3421 6539 3279 6539 3422 6539 3422 6540 3279 6540 3303 6540 3422 6541 3303 6541 3423 6541 3423 6542 3303 6542 3280 6542 3423 6543 3280 6543 3281 6543 3281 6544 3280 6544 3282 6544 3281 6545 3282 6545 3424 6545 3258 6546 3401 6546 3283 6546 3283 6547 3401 6547 3319 6547 3283 6548 3319 6548 3271 6548 3271 6549 3319 6549 3284 6549 3271 6550 3284 6550 3272 6550 3272 6551 3284 6551 3285 6551 3272 6552 3285 6552 3274 6552 3274 6553 3285 6553 3286 6553 3274 6554 3286 6554 3287 6554 3287 6555 3286 6555 3288 6555 3287 6556 3288 6556 3275 6556 3275 6557 3288 6557 3323 6557 3275 6558 3323 6558 3324 6558 3316 6559 3295 6559 3289 6559 3289 6560 2662 6560 3316 6560 3316 6561 2662 6561 2563 6561 3316 6562 2563 6562 3318 6562 3318 6563 2563 6563 2562 6563 3318 6564 2562 6564 3290 6564 3290 6565 2562 6565 3291 6565 3290 6566 3291 6566 3320 6566 3320 6567 3291 6567 2713 6567 3320 6568 2713 6568 3292 6568 3292 6569 2713 6569 2663 6569 3292 6570 2663 6570 3321 6570 3321 6571 2663 6571 3293 6571 3321 6572 3293 6572 3294 6572 3294 6573 3293 6573 2561 6573 3294 6574 2561 6574 3322 6574 3322 6575 2561 6575 2553 6575 3322 6576 2553 6576 2555 6576 3301 6577 2593 6577 3295 6577 3295 6578 2593 6578 2597 6578 3295 6579 2597 6579 3289 6579 3296 6580 3297 6580 3298 6580 3298 6581 3297 6581 2798 6581 3298 6582 2798 6582 3299 6582 3299 6583 2798 6583 3300 6583 3299 6584 3300 6584 3301 6584 3301 6585 3300 6585 2660 6585 3301 6586 2660 6586 2593 6586 3302 6587 3424 6587 3364 6587 3364 6588 3424 6588 3282 6588 3364 6589 3282 6589 2815 6589 2815 6590 3282 6590 3280 6590 2815 6591 3280 6591 2804 6591 2804 6592 3280 6592 3303 6592 2804 6593 3303 6593 2565 6593 2565 6594 3303 6594 3279 6594 2565 6595 3279 6595 2611 6595 2611 6596 3279 6596 3304 6596 2611 6597 3304 6597 3305 6597 3305 6598 3304 6598 3255 6598 3305 6599 3255 6599 2689 6599 2543 6600 2712 6600 3324 6600 3324 6601 2712 6601 3307 6601 3324 6602 3307 6602 3410 6602 3410 6603 3307 6603 3257 6603 3254 6604 3306 6604 3307 6604 3307 6605 3306 6605 3308 6605 3307 6606 3308 6606 3309 6606 3309 6607 3308 6607 3310 6607 3309 6608 3310 6608 3311 6608 3311 6609 3310 6609 3413 6609 3306 6610 2737 6610 3308 6610 3308 6611 2737 6611 3312 6611 3308 6612 3312 6612 3310 6612 3310 6613 3312 6613 2763 6613 3310 6614 2763 6614 3276 6614 3276 6615 2763 6615 2689 6615 3276 6616 2689 6616 3277 6616 3277 6617 2689 6617 3255 6617 3277 6618 3255 6618 3416 6618 3416 6619 3255 6619 3417 6619 3313 6620 3296 6620 3314 6620 3314 6621 3296 6621 3298 6621 3314 6622 3298 6622 3259 6622 3259 6623 3298 6623 3299 6623 3259 6624 3299 6624 3315 6624 3315 6625 3299 6625 3301 6625 3315 6626 3301 6626 3263 6626 3263 6627 3301 6627 3295 6627 3263 6628 3295 6628 3265 6628 3265 6629 3295 6629 3316 6629 3265 6630 3316 6630 3317 6630 3317 6631 3316 6631 3318 6631 3317 6632 3318 6632 3270 6632 3270 6633 3318 6633 3290 6633 3270 6634 3290 6634 3319 6634 3319 6635 3290 6635 3320 6635 3319 6636 3320 6636 3284 6636 3284 6637 3320 6637 3292 6637 3284 6638 3292 6638 3285 6638 3285 6639 3292 6639 3321 6639 3285 6640 3321 6640 3286 6640 3286 6641 3321 6641 3294 6641 3286 6642 3294 6642 3288 6642 3288 6643 3294 6643 3322 6643 3288 6644 3322 6644 3323 6644 3323 6645 3322 6645 2555 6645 3323 6646 2555 6646 3324 6646 3324 6647 2555 6647 3325 6647 3324 6648 3325 6648 2543 6648 3375 6649 3082 6649 3365 6649 3388 6650 3326 6650 3352 6650 3370 6651 3367 6651 3373 6651 3380 6652 3587 6652 3381 6652 3381 6653 3587 6653 3383 6653 3590 6654 3327 6654 3380 6654 3380 6655 3327 6655 3328 6655 3380 6656 3328 6656 3587 6656 3380 6657 3379 6657 3590 6657 3590 6658 3379 6658 3329 6658 3590 6659 3329 6659 3592 6659 3592 6660 3329 6660 3330 6660 3592 6661 3330 6661 3593 6661 3593 6662 3330 6662 3377 6662 3593 6663 3377 6663 3594 6663 3594 6664 3377 6664 3331 6664 3594 6665 3331 6665 3332 6665 3597 6666 3369 6666 3334 6666 3334 6667 3369 6667 3333 6667 3334 6668 3333 6668 3599 6668 3350 6669 3606 6669 3349 6669 3349 6670 3606 6670 3604 6670 3349 6671 3604 6671 3392 6671 3335 6672 3339 6672 3527 6672 3524 6673 3336 6673 3525 6673 3525 6674 3336 6674 3335 6674 3525 6675 3335 6675 3526 6675 3526 6676 3335 6676 3527 6676 3523 6677 3338 6677 3337 6677 3337 6678 3338 6678 3521 6678 3337 6679 3521 6679 3339 6679 3339 6680 3521 6680 3340 6680 3339 6681 3340 6681 3527 6681 3523 6682 3337 6682 3341 6682 3341 6683 3337 6683 3342 6683 3341 6684 3342 6684 3519 6684 3519 6685 3342 6685 3343 6685 3519 6686 3343 6686 3344 6686 3344 6687 3343 6687 3387 6687 3344 6688 3387 6688 3520 6688 3520 6689 3387 6689 3386 6689 3520 6690 3386 6690 3345 6690 3345 6691 3386 6691 3516 6691 3516 6692 3386 6692 3313 6692 3516 6693 3313 6693 3513 6693 3346 6694 3391 6694 3395 6694 3395 6695 3391 6695 3347 6695 3395 6696 3347 6696 3394 6696 3394 6697 3347 6697 3348 6697 3394 6698 3348 6698 3392 6698 3392 6699 3348 6699 3389 6699 3392 6700 3389 6700 3349 6700 3349 6701 3389 6701 3336 6701 3349 6702 3336 6702 3350 6702 3350 6703 3336 6703 3524 6703 2895 6704 3351 6704 2902 6704 2902 6705 3351 6705 3390 6705 2902 6706 3390 6706 2897 6706 3352 6707 3326 6707 3353 6707 3353 6708 3326 6708 3354 6708 3353 6709 3354 6709 3355 6709 3355 6710 3354 6710 3356 6710 3355 6711 3356 6711 2895 6711 2895 6712 3356 6712 3357 6712 2895 6713 3357 6713 3351 6713 3360 6714 3363 6714 3358 6714 3352 6715 3359 6715 3388 6715 3388 6716 3359 6716 3132 6716 3388 6717 3132 6717 3358 6717 3358 6718 3132 6718 2915 6718 3358 6719 2915 6719 3360 6719 3297 6720 3296 6720 3181 6720 3181 6721 3296 6721 3384 6721 3181 6722 3384 6722 3189 6722 3189 6723 3384 6723 3385 6723 3189 6724 3385 6724 2964 6724 2964 6725 3385 6725 3361 6725 2964 6726 3361 6726 3362 6726 3362 6727 3361 6727 3363 6727 3362 6728 3363 6728 2917 6728 2917 6729 3363 6729 3360 6729 3302 6730 3364 6730 3382 6730 3382 6731 3364 6731 2820 6731 3382 6732 2820 6732 3141 6732 3082 6733 3371 6733 3365 6733 3365 6734 3371 6734 3367 6734 3365 6735 3367 6735 3366 6735 3366 6736 3367 6736 3370 6736 3368 6737 3369 6737 3373 6737 3373 6738 3369 6738 3597 6738 3373 6739 3597 6739 3370 6739 3371 6740 3022 6740 3367 6740 3367 6741 3022 6741 3372 6741 3367 6742 3372 6742 3373 6742 3373 6743 3372 6743 3023 6743 3373 6744 3023 6744 3368 6744 2901 6745 3333 6745 3374 6745 3374 6746 3333 6746 3369 6746 3374 6747 3369 6747 2898 6747 2898 6748 3369 6748 3368 6748 3366 6749 3332 6749 3365 6749 3365 6750 3332 6750 3331 6750 3365 6751 3331 6751 3375 6751 3375 6752 3331 6752 3377 6752 3375 6753 3377 6753 3376 6753 3376 6754 3377 6754 3330 6754 3376 6755 3330 6755 2941 6755 2941 6756 3330 6756 3329 6756 2941 6757 3329 6757 3020 6757 3020 6758 3329 6758 3379 6758 3020 6759 3379 6759 3378 6759 3378 6760 3379 6760 3380 6760 3378 6761 3380 6761 3141 6761 3141 6762 3380 6762 3381 6762 3141 6763 3381 6763 3382 6763 3382 6764 3381 6764 3383 6764 3382 6765 3383 6765 3302 6765 3296 6766 3313 6766 3384 6766 3384 6767 3313 6767 3386 6767 3384 6768 3386 6768 3385 6768 3385 6769 3386 6769 3387 6769 3385 6770 3387 6770 3361 6770 3361 6771 3387 6771 3343 6771 3361 6772 3343 6772 3363 6772 3363 6773 3343 6773 3342 6773 3363 6774 3342 6774 3358 6774 3358 6775 3342 6775 3337 6775 3358 6776 3337 6776 3388 6776 3388 6777 3337 6777 3339 6777 3388 6778 3339 6778 3326 6778 3326 6779 3339 6779 3335 6779 3326 6780 3335 6780 3354 6780 3354 6781 3335 6781 3336 6781 3354 6782 3336 6782 3356 6782 3356 6783 3336 6783 3389 6783 3356 6784 3389 6784 3357 6784 3357 6785 3389 6785 3348 6785 3357 6786 3348 6786 3351 6786 3351 6787 3348 6787 3347 6787 3351 6788 3347 6788 3390 6788 3390 6789 3347 6789 3391 6789 3604 6790 3603 6790 3392 6790 3392 6791 3603 6791 3393 6791 3392 6792 3393 6792 3394 6792 3394 6793 3393 6793 3600 6793 3394 6794 3600 6794 3395 6794 3395 6795 3600 6795 3396 6795 3395 6796 3396 6796 3346 6796 3346 6797 3396 6797 3599 6797 3346 6798 3599 6798 3391 6798 3391 6799 3599 6799 3333 6799 3391 6800 3333 6800 3390 6800 3390 6801 3333 6801 2901 6801 3390 6802 2901 6802 2897 6802 3507 6803 3397 6803 3493 6803 3426 6804 3514 6804 3427 6804 3555 6805 3426 6805 3398 6805 3485 6806 3269 6806 3484 6806 3484 6807 3269 6807 3399 6807 3484 6808 3399 6808 3483 6808 3483 6809 3399 6809 3400 6809 3483 6810 3400 6810 3482 6810 3482 6811 3400 6811 3401 6811 3482 6812 3401 6812 3402 6812 3402 6813 3401 6813 3258 6813 3402 6814 3258 6814 3403 6814 3403 6815 3258 6815 3405 6815 3403 6816 3405 6816 3404 6816 3404 6817 3405 6817 3273 6817 3404 6818 3273 6818 3477 6818 3477 6819 3273 6819 3406 6819 3477 6820 3406 6820 3475 6820 3475 6821 3406 6821 3407 6821 3475 6822 3407 6822 3408 6822 3408 6823 3407 6823 3275 6823 3408 6824 3275 6824 3473 6824 3473 6825 3275 6825 3410 6825 3473 6826 3410 6826 3409 6826 3409 6827 3410 6827 3257 6827 3409 6828 3257 6828 3411 6828 3411 6829 3257 6829 3256 6829 3411 6830 3256 6830 3471 6830 3471 6831 3256 6831 3309 6831 3471 6832 3309 6832 3412 6832 3412 6833 3309 6833 3311 6833 3412 6834 3311 6834 3470 6834 3470 6835 3311 6835 3413 6835 3470 6836 3413 6836 3469 6836 3469 6837 3413 6837 3414 6837 3469 6838 3414 6838 3467 6838 3467 6839 3414 6839 3416 6839 3467 6840 3416 6840 3415 6840 3415 6841 3416 6841 3417 6841 3415 6842 3417 6842 3466 6842 3466 6843 3417 6843 3418 6843 3466 6844 3418 6844 3419 6844 3419 6845 3418 6845 3278 6845 3419 6846 3278 6846 3420 6846 3420 6847 3278 6847 3421 6847 3420 6848 3421 6848 3463 6848 3463 6849 3421 6849 3422 6849 3463 6850 3422 6850 3462 6850 3462 6851 3422 6851 3423 6851 3462 6852 3423 6852 3461 6852 3461 6853 3423 6853 3281 6853 3461 6854 3281 6854 3459 6854 3459 6855 3281 6855 3424 6855 3459 6856 3424 6856 3425 6856 3425 6857 3424 6857 3302 6857 3425 6858 3302 6858 3555 6858 3426 6859 3427 6859 3398 6859 3398 6860 3427 6860 3428 6860 3398 6861 3428 6861 3429 6861 3429 6862 3428 6862 3662 6862 3429 6863 3662 6863 3430 6863 3430 6864 3662 6864 3431 6864 3430 6865 3431 6865 3460 6865 3460 6866 3431 6866 3663 6866 3460 6867 3663 6867 3464 6867 3464 6868 3663 6868 3665 6868 3464 6869 3665 6869 3432 6869 3432 6870 3665 6870 3433 6870 3432 6871 3433 6871 3465 6871 3465 6872 3433 6872 3434 6872 3465 6873 3434 6873 3435 6873 3435 6874 3434 6874 3436 6874 3435 6875 3436 6875 3437 6875 3437 6876 3436 6876 3438 6876 3437 6877 3438 6877 3439 6877 3439 6878 3438 6878 3609 6878 3439 6879 3609 6879 3468 6879 3468 6880 3609 6880 3441 6880 3468 6881 3441 6881 3440 6881 3440 6882 3441 6882 3442 6882 3440 6883 3442 6883 3443 6883 3443 6884 3442 6884 3672 6884 3443 6885 3672 6885 3444 6885 3444 6886 3672 6886 3673 6886 3444 6887 3673 6887 3472 6887 3472 6888 3673 6888 3676 6888 3472 6889 3676 6889 3445 6889 3445 6890 3676 6890 3677 6890 3445 6891 3677 6891 3446 6891 3446 6892 3677 6892 3447 6892 3446 6893 3447 6893 3474 6893 3474 6894 3447 6894 3448 6894 3474 6895 3448 6895 3449 6895 3449 6896 3448 6896 3651 6896 3449 6897 3651 6897 3476 6897 3476 6898 3651 6898 3650 6898 3476 6899 3650 6899 3450 6899 3450 6900 3650 6900 3451 6900 3450 6901 3451 6901 3478 6901 3478 6902 3451 6902 3648 6902 3478 6903 3648 6903 3479 6903 3479 6904 3648 6904 3622 6904 3479 6905 3622 6905 3480 6905 3480 6906 3622 6906 3621 6906 3480 6907 3621 6907 3481 6907 3481 6908 3621 6908 3452 6908 3481 6909 3452 6909 3454 6909 3454 6910 3452 6910 3453 6910 3454 6911 3453 6911 3455 6911 3455 6912 3453 6912 3618 6912 3455 6913 3618 6913 3456 6913 3456 6914 3618 6914 3457 6914 3456 6915 3457 6915 3486 6915 3486 6916 3457 6916 3458 6916 3486 6917 3458 6917 3506 6917 3555 6918 3398 6918 3425 6918 3425 6919 3398 6919 3429 6919 3425 6920 3429 6920 3459 6920 3459 6921 3429 6921 3430 6921 3459 6922 3430 6922 3461 6922 3461 6923 3430 6923 3460 6923 3461 6924 3460 6924 3462 6924 3462 6925 3460 6925 3464 6925 3462 6926 3464 6926 3463 6926 3463 6927 3464 6927 3432 6927 3463 6928 3432 6928 3420 6928 3420 6929 3432 6929 3465 6929 3420 6930 3465 6930 3419 6930 3419 6931 3465 6931 3435 6931 3419 6932 3435 6932 3466 6932 3466 6933 3435 6933 3437 6933 3466 6934 3437 6934 3415 6934 3415 6935 3437 6935 3439 6935 3415 6936 3439 6936 3467 6936 3467 6937 3439 6937 3468 6937 3467 6938 3468 6938 3469 6938 3469 6939 3468 6939 3440 6939 3469 6940 3440 6940 3470 6940 3470 6941 3440 6941 3443 6941 3470 6942 3443 6942 3412 6942 3412 6943 3443 6943 3444 6943 3412 6944 3444 6944 3471 6944 3471 6945 3444 6945 3472 6945 3471 6946 3472 6946 3411 6946 3411 6947 3472 6947 3445 6947 3411 6948 3445 6948 3409 6948 3409 6949 3445 6949 3446 6949 3409 6950 3446 6950 3473 6950 3473 6951 3446 6951 3474 6951 3473 6952 3474 6952 3408 6952 3408 6953 3474 6953 3449 6953 3408 6954 3449 6954 3475 6954 3475 6955 3449 6955 3476 6955 3475 6956 3476 6956 3477 6956 3477 6957 3476 6957 3450 6957 3477 6958 3450 6958 3404 6958 3404 6959 3450 6959 3478 6959 3404 6960 3478 6960 3403 6960 3403 6961 3478 6961 3479 6961 3403 6962 3479 6962 3402 6962 3402 6963 3479 6963 3480 6963 3402 6964 3480 6964 3482 6964 3482 6965 3480 6965 3481 6965 3482 6966 3481 6966 3483 6966 3483 6967 3481 6967 3454 6967 3483 6968 3454 6968 3484 6968 3484 6969 3454 6969 3455 6969 3484 6970 3455 6970 3485 6970 3485 6971 3455 6971 3456 6971 3485 6972 3456 6972 3490 6972 3490 6973 3456 6973 3486 6973 3490 6974 3486 6974 3488 6974 3488 6975 3486 6975 3506 6975 3488 6976 3506 6976 3491 6976 3491 6977 3487 6977 3488 6977 3488 6978 3487 6978 3489 6978 3488 6979 3489 6979 3490 6979 3490 6980 3489 6980 3264 6980 3490 6981 3264 6981 3485 6981 3485 6982 3264 6982 3268 6982 3485 6983 3268 6983 3269 6983 3262 6984 3267 6984 3491 6984 3491 6985 3267 6985 3266 6985 3491 6986 3266 6986 3487 6986 3397 6987 3505 6987 3492 6987 3397 6988 3492 6988 3493 6988 3493 6989 3492 6989 3494 6989 3493 6990 3494 6990 3500 6990 3500 6991 3494 6991 3624 6991 3500 6992 3624 6992 3502 6992 3502 6993 3624 6993 3495 6993 3502 6994 3495 6994 3503 6994 3503 6995 3495 6995 3496 6995 3503 6996 3496 6996 3497 6996 3497 6997 3496 6997 3498 6997 3497 6998 3498 6998 3556 6998 3507 6999 3493 6999 3499 6999 3499 7000 3493 7000 3500 7000 3499 7001 3500 7001 3509 7001 3509 7002 3500 7002 3502 7002 3509 7003 3502 7003 3501 7003 3501 7004 3502 7004 3503 7004 3501 7005 3503 7005 3504 7005 3504 7006 3503 7006 3497 7006 3504 7007 3497 7007 3511 7007 3511 7008 3497 7008 3556 7008 3511 7009 3556 7009 3517 7009 3458 7010 3505 7010 3506 7010 3506 7011 3505 7011 3397 7011 3506 7012 3397 7012 3491 7012 3491 7013 3397 7013 3507 7013 3491 7014 3507 7014 3262 7014 3262 7015 3507 7015 3499 7015 3262 7016 3499 7016 3261 7016 3261 7017 3499 7017 3509 7017 3261 7018 3509 7018 3508 7018 3508 7019 3509 7019 3501 7019 3508 7020 3501 7020 3510 7020 3510 7021 3501 7021 3504 7021 3510 7022 3504 7022 3260 7022 3260 7023 3504 7023 3511 7023 3260 7024 3511 7024 3512 7024 3512 7025 3511 7025 3517 7025 3512 7026 3517 7026 3513 7026 3658 7027 3514 7027 3426 7027 3516 7028 3513 7028 3517 7028 3529 7029 3557 7029 3612 7029 3515 7030 3345 7030 3559 7030 3559 7031 3345 7031 3516 7031 3559 7032 3516 7032 3558 7032 3558 7033 3516 7033 3517 7033 3558 7034 3517 7034 3556 7034 3522 7035 3341 7035 3518 7035 3518 7036 3341 7036 3519 7036 3518 7037 3519 7037 3560 7037 3560 7038 3519 7038 3344 7038 3560 7039 3344 7039 3515 7039 3515 7040 3344 7040 3520 7040 3515 7041 3520 7041 3345 7041 3528 7042 3521 7042 3562 7042 3562 7043 3521 7043 3338 7043 3562 7044 3338 7044 3522 7044 3522 7045 3338 7045 3523 7045 3522 7046 3523 7046 3341 7046 3350 7047 3524 7047 3605 7047 3605 7048 3524 7048 3525 7048 3605 7049 3525 7049 3564 7049 3564 7050 3525 7050 3526 7050 3564 7051 3526 7051 3563 7051 3563 7052 3526 7052 3527 7052 3563 7053 3527 7053 3528 7053 3528 7054 3527 7054 3340 7054 3528 7055 3340 7055 3521 7055 3529 7056 3612 7056 3530 7056 3530 7057 3612 7057 3611 7057 3530 7058 3611 7058 3531 7058 3531 7059 3611 7059 3607 7059 3531 7060 3607 7060 3532 7060 3532 7061 3607 7061 3608 7061 3532 7062 3608 7062 3534 7062 3534 7063 3608 7063 3533 7063 3534 7064 3533 7064 3535 7064 3535 7065 3533 7065 3626 7065 3535 7066 3626 7066 3536 7066 3536 7067 3626 7067 3628 7067 3536 7068 3628 7068 3561 7068 3561 7069 3628 7069 3537 7069 3561 7070 3537 7070 3538 7070 3538 7071 3537 7071 3631 7071 3538 7072 3631 7072 3539 7072 3539 7073 3631 7073 3632 7073 3539 7074 3632 7074 3565 7074 3565 7075 3632 7075 3540 7075 3565 7076 3540 7076 3566 7076 3566 7077 3540 7077 3541 7077 3566 7078 3541 7078 3567 7078 3567 7079 3541 7079 3636 7079 3567 7080 3636 7080 3542 7080 3542 7081 3636 7081 3652 7081 3542 7082 3652 7082 3543 7082 3543 7083 3652 7083 3544 7083 3543 7084 3544 7084 3570 7084 3570 7085 3544 7085 3545 7085 3570 7086 3545 7086 3572 7086 3572 7087 3545 7087 3637 7087 3572 7088 3637 7088 3546 7088 3546 7089 3637 7089 3638 7089 3546 7090 3638 7090 3547 7090 3547 7091 3638 7091 3640 7091 3547 7092 3640 7092 3574 7092 3574 7093 3640 7093 3548 7093 3574 7094 3548 7094 3576 7094 3576 7095 3548 7095 3550 7095 3576 7096 3550 7096 3549 7096 3549 7097 3550 7097 3615 7097 3549 7098 3615 7098 3551 7098 3551 7099 3615 7099 3643 7099 3551 7100 3643 7100 3579 7100 3579 7101 3643 7101 3644 7101 3579 7102 3644 7102 3580 7102 3580 7103 3644 7103 3552 7103 3580 7104 3552 7104 3582 7104 3582 7105 3552 7105 3647 7105 3582 7106 3647 7106 3553 7106 3553 7107 3647 7107 3554 7107 3553 7108 3554 7108 3584 7108 3584 7109 3554 7109 3658 7109 3584 7110 3658 7110 3585 7110 3585 7111 3658 7111 3426 7111 3585 7112 3426 7112 3555 7112 3498 7113 3557 7113 3556 7113 3556 7114 3557 7114 3529 7114 3556 7115 3529 7115 3558 7115 3558 7116 3529 7116 3530 7116 3558 7117 3530 7117 3559 7117 3559 7118 3530 7118 3531 7118 3559 7119 3531 7119 3515 7119 3515 7120 3531 7120 3532 7120 3515 7121 3532 7121 3560 7121 3560 7122 3532 7122 3534 7122 3560 7123 3534 7123 3518 7123 3518 7124 3534 7124 3535 7124 3518 7125 3535 7125 3522 7125 3522 7126 3535 7126 3536 7126 3522 7127 3536 7127 3562 7127 3562 7128 3536 7128 3561 7128 3562 7129 3561 7129 3528 7129 3528 7130 3561 7130 3538 7130 3528 7131 3538 7131 3563 7131 3563 7132 3538 7132 3539 7132 3563 7133 3539 7133 3564 7133 3564 7134 3539 7134 3565 7134 3564 7135 3565 7135 3605 7135 3605 7136 3565 7136 3566 7136 3605 7137 3566 7137 3568 7137 3568 7138 3566 7138 3567 7138 3568 7139 3567 7139 3602 7139 3602 7140 3567 7140 3542 7140 3602 7141 3542 7141 3601 7141 3601 7142 3542 7142 3543 7142 3601 7143 3543 7143 3569 7143 3569 7144 3543 7144 3570 7144 3569 7145 3570 7145 3571 7145 3571 7146 3570 7146 3572 7146 3571 7147 3572 7147 3598 7147 3598 7148 3572 7148 3546 7148 3598 7149 3546 7149 3573 7149 3573 7150 3546 7150 3547 7150 3573 7151 3547 7151 3596 7151 3596 7152 3547 7152 3574 7152 3596 7153 3574 7153 3575 7153 3575 7154 3574 7154 3576 7154 3575 7155 3576 7155 3595 7155 3595 7156 3576 7156 3549 7156 3595 7157 3549 7157 3577 7157 3577 7158 3549 7158 3551 7158 3577 7159 3551 7159 3578 7159 3578 7160 3551 7160 3579 7160 3578 7161 3579 7161 3591 7161 3591 7162 3579 7162 3580 7162 3591 7163 3580 7163 3581 7163 3581 7164 3580 7164 3582 7164 3581 7165 3582 7165 3589 7165 3589 7166 3582 7166 3553 7166 3589 7167 3553 7167 3588 7167 3588 7168 3553 7168 3584 7168 3588 7169 3584 7169 3583 7169 3583 7170 3584 7170 3585 7170 3583 7171 3585 7171 3586 7171 3586 7172 3585 7172 3555 7172 3586 7173 3555 7173 3302 7173 3302 7174 3383 7174 3586 7174 3586 7175 3383 7175 3587 7175 3586 7176 3587 7176 3583 7176 3583 7177 3587 7177 3328 7177 3583 7178 3328 7178 3588 7178 3588 7179 3328 7179 3327 7179 3588 7180 3327 7180 3589 7180 3589 7181 3327 7181 3590 7181 3589 7182 3590 7182 3581 7182 3581 7183 3590 7183 3592 7183 3581 7184 3592 7184 3591 7184 3591 7185 3592 7185 3593 7185 3591 7186 3593 7186 3578 7186 3578 7187 3593 7187 3594 7187 3578 7188 3594 7188 3577 7188 3577 7189 3594 7189 3332 7189 3577 7190 3332 7190 3595 7190 3595 7191 3332 7191 3366 7191 3595 7192 3366 7192 3575 7192 3575 7193 3366 7193 3370 7193 3575 7194 3370 7194 3596 7194 3596 7195 3370 7195 3597 7195 3596 7196 3597 7196 3573 7196 3573 7197 3597 7197 3334 7197 3573 7198 3334 7198 3598 7198 3598 7199 3334 7199 3599 7199 3598 7200 3599 7200 3571 7200 3571 7201 3599 7201 3396 7201 3571 7202 3396 7202 3569 7202 3569 7203 3396 7203 3600 7203 3569 7204 3600 7204 3601 7204 3601 7205 3600 7205 3393 7205 3601 7206 3393 7206 3602 7206 3602 7207 3393 7207 3603 7207 3602 7208 3603 7208 3568 7208 3568 7209 3603 7209 3604 7209 3568 7210 3604 7210 3605 7210 3605 7211 3604 7211 3606 7211 3605 7212 3606 7212 3350 7212 3610 7213 3954 7213 3611 7213 3611 7214 3954 7214 3607 7214 3607 7215 3954 7215 3956 7215 3607 7216 3956 7216 3608 7216 3492 7217 3720 7217 3719 7217 3436 7218 3669 7218 3438 7218 3438 7219 3669 7219 3735 7219 3438 7220 3735 7220 3609 7220 3643 7221 3615 7221 3979 7221 3610 7222 3611 7222 3952 7222 3952 7223 3611 7223 3612 7223 3952 7224 3612 7224 3613 7224 3613 7225 3612 7225 3557 7225 3613 7226 3557 7226 3614 7226 3614 7227 3557 7227 3498 7227 3614 7228 3498 7228 3717 7228 3717 7229 3498 7229 3496 7229 3717 7230 3496 7230 3623 7230 3548 7231 3641 7231 3550 7231 3550 7232 3641 7232 3977 7232 3550 7233 3977 7233 3615 7233 3615 7234 3977 7234 3616 7234 3615 7235 3616 7235 3979 7235 3720 7236 3492 7236 3617 7236 3617 7237 3492 7237 3505 7237 3617 7238 3505 7238 3722 7238 3722 7239 3505 7239 3458 7239 3722 7240 3458 7240 3723 7240 3723 7241 3458 7241 3457 7241 3723 7242 3457 7242 3619 7242 3619 7243 3457 7243 3618 7243 3619 7244 3618 7244 3620 7244 3620 7245 3618 7245 3453 7245 3620 7246 3453 7246 3724 7246 3724 7247 3453 7247 3452 7247 3724 7248 3452 7248 3725 7248 3725 7249 3452 7249 3621 7249 3725 7250 3621 7250 3726 7250 3726 7251 3621 7251 3622 7251 3726 7252 3622 7252 3729 7252 3496 7253 3495 7253 3623 7253 3623 7254 3495 7254 3624 7254 3623 7255 3624 7255 3719 7255 3719 7256 3624 7256 3494 7256 3719 7257 3494 7257 3492 7257 3956 7258 3957 7258 3608 7258 3608 7259 3957 7259 3959 7259 3608 7260 3959 7260 3533 7260 3533 7261 3959 7261 3625 7261 3533 7262 3625 7262 3626 7262 3626 7263 3625 7263 3627 7263 3626 7264 3627 7264 3628 7264 3628 7265 3627 7265 3629 7265 3628 7266 3629 7266 3537 7266 3537 7267 3629 7267 3630 7267 3537 7268 3630 7268 3631 7268 3631 7269 3630 7269 3963 7269 3631 7270 3963 7270 3632 7270 3632 7271 3963 7271 3633 7271 3632 7272 3633 7272 3540 7272 3540 7273 3633 7273 3634 7273 3540 7274 3634 7274 3541 7274 3541 7275 3634 7275 3635 7275 3541 7276 3635 7276 3636 7276 3636 7277 3635 7277 3967 7277 3636 7278 3967 7278 3652 7278 3637 7279 3655 7279 3638 7279 3638 7280 3655 7280 3639 7280 3638 7281 3639 7281 3640 7281 3640 7282 3639 7282 3974 7282 3640 7283 3974 7283 3548 7283 3548 7284 3974 7284 3976 7284 3548 7285 3976 7285 3641 7285 3979 7286 3642 7286 3643 7286 3643 7287 3642 7287 3981 7287 3643 7288 3981 7288 3644 7288 3644 7289 3981 7289 3645 7289 3644 7290 3645 7290 3552 7290 3552 7291 3645 7291 3646 7291 3552 7292 3646 7292 3647 7292 3622 7293 3648 7293 3729 7293 3729 7294 3648 7294 3451 7294 3729 7295 3451 7295 3649 7295 3649 7296 3451 7296 3650 7296 3649 7297 3650 7297 3730 7297 3730 7298 3650 7298 3651 7298 3730 7299 3651 7299 3678 7299 3967 7300 3968 7300 3652 7300 3652 7301 3968 7301 3653 7301 3652 7302 3653 7302 3544 7302 3544 7303 3653 7303 3971 7303 3544 7304 3971 7304 3545 7304 3545 7305 3971 7305 3972 7305 3545 7306 3972 7306 3637 7306 3637 7307 3972 7307 3654 7307 3637 7308 3654 7308 3655 7308 3646 7309 3656 7309 3647 7309 3647 7310 3656 7310 3657 7310 3647 7311 3657 7311 3554 7311 3554 7312 3657 7312 3659 7312 3554 7313 3659 7313 3658 7313 3658 7314 3659 7314 3660 7314 3658 7315 3660 7315 3514 7315 3514 7316 3660 7316 3661 7316 3514 7317 3661 7317 3427 7317 3427 7318 3661 7318 3744 7318 3427 7319 3744 7319 3428 7319 3428 7320 3744 7320 3743 7320 3428 7321 3743 7321 3662 7321 3662 7322 3743 7322 3741 7322 3662 7323 3741 7323 3431 7323 3431 7324 3741 7324 3740 7324 3431 7325 3740 7325 3663 7325 3663 7326 3740 7326 3664 7326 3663 7327 3664 7327 3665 7327 3665 7328 3664 7328 3666 7328 3665 7329 3666 7329 3433 7329 3433 7330 3666 7330 3667 7330 3433 7331 3667 7331 3434 7331 3434 7332 3667 7332 3668 7332 3434 7333 3668 7333 3436 7333 3436 7334 3668 7334 3738 7334 3436 7335 3738 7335 3669 7335 3609 7336 3735 7336 3441 7336 3441 7337 3735 7337 3670 7337 3441 7338 3670 7338 3442 7338 3442 7339 3670 7339 3671 7339 3442 7340 3671 7340 3672 7340 3672 7341 3671 7341 3732 7341 3672 7342 3732 7342 3673 7342 3673 7343 3732 7343 3674 7343 3673 7344 3674 7344 3676 7344 3676 7345 3674 7345 3675 7345 3676 7346 3675 7346 3677 7346 3651 7347 3448 7347 3678 7347 3678 7348 3448 7348 3447 7348 3678 7349 3447 7349 3679 7349 3679 7350 3447 7350 3677 7350 3679 7351 3677 7351 3680 7351 3680 7352 3677 7352 3675 7352 3917 7353 3828 7353 3782 7353 3830 7354 3829 7354 3781 7354 3950 7355 3614 7355 3717 7355 3950 7356 3717 7356 3829 7356 4027 7357 4030 7357 3827 7357 3783 7358 3681 7358 3784 7358 3784 7359 3681 7359 3988 7359 3826 7360 3825 7360 3682 7360 3682 7361 3825 7361 3783 7361 3684 7362 3683 7362 3826 7362 3683 7363 3684 7363 3685 7363 3827 7364 3686 7364 4027 7364 4027 7365 3686 7365 3818 7365 4027 7366 3818 7366 3687 7366 3687 7367 3818 7367 3816 7367 3687 7368 3816 7368 4025 7368 4025 7369 3816 7369 3815 7369 4025 7370 3815 7370 4024 7370 4024 7371 3815 7371 3814 7371 4024 7372 3814 7372 3688 7372 3688 7373 3814 7373 3689 7373 3688 7374 3689 7374 3690 7374 3690 7375 3689 7375 3691 7375 3690 7376 3691 7376 3692 7376 3692 7377 3691 7377 3693 7377 3692 7378 3693 7378 4021 7378 4021 7379 3693 7379 3811 7379 4021 7380 3811 7380 4019 7380 4019 7381 3811 7381 3809 7381 4019 7382 3809 7382 3694 7382 3694 7383 3809 7383 3808 7383 3694 7384 3808 7384 3695 7384 3695 7385 3808 7385 3806 7385 3695 7386 3806 7386 4015 7386 4015 7387 3806 7387 3696 7387 4015 7388 3696 7388 4014 7388 4014 7389 3696 7389 3803 7389 4014 7390 3803 7390 4013 7390 4013 7391 3803 7391 3802 7391 4013 7392 3802 7392 3697 7392 3697 7393 3802 7393 3698 7393 3697 7394 3698 7394 3699 7394 3699 7395 3698 7395 3801 7395 3699 7396 3801 7396 3700 7396 3700 7397 3801 7397 3701 7397 3700 7398 3701 7398 3702 7398 3702 7399 3701 7399 3800 7399 3702 7400 3800 7400 4009 7400 4009 7401 3800 7401 3798 7401 4009 7402 3798 7402 3703 7402 3703 7403 3798 7403 3704 7403 3703 7404 3704 7404 4007 7404 4007 7405 3704 7405 3795 7405 4007 7406 3795 7406 4004 7406 4004 7407 3795 7407 3705 7407 4004 7408 3705 7408 3716 7408 3787 7409 3706 7409 3789 7409 3789 7410 3706 7410 3997 7410 3789 7411 3997 7411 3707 7411 3707 7412 3997 7412 3708 7412 3707 7413 3708 7413 3710 7413 3710 7414 3708 7414 3709 7414 3710 7415 3709 7415 3711 7415 3711 7416 3709 7416 3712 7416 3711 7417 3712 7417 3793 7417 3793 7418 3712 7418 3713 7418 3793 7419 3713 7419 3714 7419 3714 7420 3713 7420 3715 7420 3714 7421 3715 7421 3705 7421 3705 7422 3715 7422 4003 7422 3705 7423 4003 7423 3716 7423 3822 7424 3824 7424 3787 7424 3787 7425 3824 7425 3995 7425 3787 7426 3995 7426 3706 7426 3829 7427 3717 7427 3781 7427 3781 7428 3717 7428 3623 7428 3781 7429 3623 7429 3780 7429 3780 7430 3623 7430 3719 7430 3780 7431 3719 7431 3718 7431 3718 7432 3719 7432 3720 7432 3718 7433 3720 7433 3778 7433 3778 7434 3720 7434 3617 7434 3778 7435 3617 7435 3721 7435 3721 7436 3617 7436 3722 7436 3721 7437 3722 7437 3776 7437 3776 7438 3722 7438 3723 7438 3776 7439 3723 7439 3774 7439 3774 7440 3723 7440 3619 7440 3774 7441 3619 7441 3773 7441 3773 7442 3619 7442 3620 7442 3773 7443 3620 7443 3771 7443 3771 7444 3620 7444 3724 7444 3771 7445 3724 7445 3770 7445 3770 7446 3724 7446 3725 7446 3770 7447 3725 7447 3727 7447 3727 7448 3725 7448 3726 7448 3727 7449 3726 7449 3728 7449 3728 7450 3726 7450 3729 7450 3728 7451 3729 7451 3769 7451 3769 7452 3729 7452 3649 7452 3769 7453 3649 7453 3767 7453 3767 7454 3649 7454 3730 7454 3767 7455 3730 7455 3731 7455 3731 7456 3730 7456 3678 7456 3731 7457 3678 7457 3765 7457 3765 7458 3678 7458 3679 7458 3765 7459 3679 7459 3764 7459 3764 7460 3679 7460 3680 7460 3764 7461 3680 7461 3761 7461 3761 7462 3680 7462 3675 7462 3761 7463 3675 7463 3759 7463 3759 7464 3675 7464 3674 7464 3759 7465 3674 7465 3758 7465 3758 7466 3674 7466 3732 7466 3758 7467 3732 7467 3756 7467 3756 7468 3732 7468 3671 7468 3756 7469 3671 7469 3733 7469 3733 7470 3671 7470 3670 7470 3733 7471 3670 7471 3734 7471 3734 7472 3670 7472 3735 7472 3734 7473 3735 7473 3736 7473 3736 7474 3735 7474 3669 7474 3736 7475 3669 7475 3754 7475 3754 7476 3669 7476 3738 7476 3754 7477 3738 7477 3737 7477 3737 7478 3738 7478 3668 7478 3737 7479 3668 7479 3752 7479 3752 7480 3668 7480 3667 7480 3752 7481 3667 7481 3739 7481 3739 7482 3667 7482 3666 7482 3739 7483 3666 7483 3750 7483 3750 7484 3666 7484 3664 7484 3750 7485 3664 7485 3749 7485 3749 7486 3664 7486 3740 7486 3749 7487 3740 7487 3748 7487 3748 7488 3740 7488 3741 7488 3748 7489 3741 7489 3746 7489 3746 7490 3741 7490 3743 7490 3746 7491 3743 7491 3742 7491 3742 7492 3743 7492 3744 7492 3742 7493 3744 7493 3684 7493 3684 7494 3744 7494 3661 7494 3684 7495 3661 7495 3685 7495 3826 7496 3682 7496 3684 7496 3684 7497 3682 7497 3785 7497 3684 7498 3785 7498 3742 7498 3742 7499 3785 7499 3745 7499 3742 7500 3745 7500 3746 7500 3746 7501 3745 7501 3747 7501 3746 7502 3747 7502 3748 7502 3748 7503 3747 7503 3788 7503 3748 7504 3788 7504 3749 7504 3749 7505 3788 7505 3790 7505 3749 7506 3790 7506 3750 7506 3750 7507 3790 7507 3751 7507 3750 7508 3751 7508 3739 7508 3739 7509 3751 7509 3791 7509 3739 7510 3791 7510 3752 7510 3752 7511 3791 7511 3792 7511 3752 7512 3792 7512 3737 7512 3737 7513 3792 7513 3753 7513 3737 7514 3753 7514 3754 7514 3754 7515 3753 7515 3794 7515 3754 7516 3794 7516 3736 7516 3736 7517 3794 7517 3755 7517 3736 7518 3755 7518 3734 7518 3734 7519 3755 7519 3796 7519 3734 7520 3796 7520 3733 7520 3733 7521 3796 7521 3797 7521 3733 7522 3797 7522 3756 7522 3756 7523 3797 7523 3757 7523 3756 7524 3757 7524 3758 7524 3758 7525 3757 7525 3799 7525 3758 7526 3799 7526 3759 7526 3759 7527 3799 7527 3760 7527 3759 7528 3760 7528 3761 7528 3761 7529 3760 7529 3762 7529 3761 7530 3762 7530 3764 7530 3764 7531 3762 7531 3763 7531 3764 7532 3763 7532 3765 7532 3765 7533 3763 7533 3766 7533 3765 7534 3766 7534 3731 7534 3731 7535 3766 7535 3804 7535 3731 7536 3804 7536 3767 7536 3767 7537 3804 7537 3768 7537 3767 7538 3768 7538 3769 7538 3769 7539 3768 7539 3805 7539 3769 7540 3805 7540 3728 7540 3728 7541 3805 7541 3807 7541 3728 7542 3807 7542 3727 7542 3727 7543 3807 7543 3810 7543 3727 7544 3810 7544 3770 7544 3770 7545 3810 7545 3812 7545 3770 7546 3812 7546 3771 7546 3771 7547 3812 7547 3772 7547 3771 7548 3772 7548 3773 7548 3773 7549 3772 7549 3813 7549 3773 7550 3813 7550 3774 7550 3774 7551 3813 7551 3775 7551 3774 7552 3775 7552 3776 7552 3776 7553 3775 7553 3777 7553 3776 7554 3777 7554 3721 7554 3721 7555 3777 7555 3779 7555 3721 7556 3779 7556 3778 7556 3778 7557 3779 7557 3817 7557 3778 7558 3817 7558 3718 7558 3718 7559 3817 7559 3819 7559 3718 7560 3819 7560 3780 7560 3780 7561 3819 7561 3782 7561 3780 7562 3782 7562 3781 7562 3781 7563 3782 7563 3828 7563 3781 7564 3828 7564 3830 7564 3783 7565 3784 7565 3682 7565 3682 7566 3784 7566 3820 7566 3682 7567 3820 7567 3785 7567 3785 7568 3820 7568 3786 7568 3785 7569 3786 7569 3745 7569 3745 7570 3786 7570 3822 7570 3745 7571 3822 7571 3747 7571 3747 7572 3822 7572 3787 7572 3747 7573 3787 7573 3788 7573 3788 7574 3787 7574 3789 7574 3788 7575 3789 7575 3790 7575 3790 7576 3789 7576 3707 7576 3790 7577 3707 7577 3751 7577 3751 7578 3707 7578 3710 7578 3751 7579 3710 7579 3791 7579 3791 7580 3710 7580 3711 7580 3791 7581 3711 7581 3792 7581 3792 7582 3711 7582 3793 7582 3792 7583 3793 7583 3753 7583 3753 7584 3793 7584 3714 7584 3753 7585 3714 7585 3794 7585 3794 7586 3714 7586 3705 7586 3794 7587 3705 7587 3755 7587 3755 7588 3705 7588 3795 7588 3755 7589 3795 7589 3796 7589 3796 7590 3795 7590 3704 7590 3796 7591 3704 7591 3797 7591 3797 7592 3704 7592 3798 7592 3797 7593 3798 7593 3757 7593 3757 7594 3798 7594 3800 7594 3757 7595 3800 7595 3799 7595 3799 7596 3800 7596 3701 7596 3799 7597 3701 7597 3760 7597 3760 7598 3701 7598 3801 7598 3760 7599 3801 7599 3762 7599 3762 7600 3801 7600 3698 7600 3762 7601 3698 7601 3763 7601 3763 7602 3698 7602 3802 7602 3763 7603 3802 7603 3766 7603 3766 7604 3802 7604 3803 7604 3766 7605 3803 7605 3804 7605 3804 7606 3803 7606 3696 7606 3804 7607 3696 7607 3768 7607 3768 7608 3696 7608 3806 7608 3768 7609 3806 7609 3805 7609 3805 7610 3806 7610 3808 7610 3805 7611 3808 7611 3807 7611 3807 7612 3808 7612 3809 7612 3807 7613 3809 7613 3810 7613 3810 7614 3809 7614 3811 7614 3810 7615 3811 7615 3812 7615 3812 7616 3811 7616 3693 7616 3812 7617 3693 7617 3772 7617 3772 7618 3693 7618 3691 7618 3772 7619 3691 7619 3813 7619 3813 7620 3691 7620 3689 7620 3813 7621 3689 7621 3775 7621 3775 7622 3689 7622 3814 7622 3775 7623 3814 7623 3777 7623 3777 7624 3814 7624 3815 7624 3777 7625 3815 7625 3779 7625 3779 7626 3815 7626 3816 7626 3779 7627 3816 7627 3817 7627 3817 7628 3816 7628 3818 7628 3817 7629 3818 7629 3819 7629 3819 7630 3818 7630 3686 7630 3819 7631 3686 7631 3782 7631 3782 7632 3686 7632 3827 7632 3782 7633 3827 7633 3917 7633 3988 7634 3987 7634 3784 7634 3784 7635 3987 7635 3992 7635 3784 7636 3992 7636 3820 7636 3820 7637 3992 7637 3993 7637 3820 7638 3993 7638 3786 7638 3786 7639 3993 7639 3821 7639 3786 7640 3821 7640 3822 7640 3822 7641 3821 7641 3823 7641 3822 7642 3823 7642 3824 7642 3783 7643 3825 7643 3919 7643 3826 7644 3683 7644 3918 7644 3685 7645 3661 7645 3660 7645 3826 7646 3918 7646 3825 7646 3783 7647 3919 7647 3681 7647 3876 7648 3988 7648 3681 7648 3916 7649 3827 7649 4030 7649 3915 7650 3828 7650 3917 7650 3950 7651 3829 7651 3949 7651 3949 7652 3829 7652 3830 7652 3613 7653 3614 7653 3950 7653 4030 7654 4031 7654 3916 7654 3916 7655 4031 7655 4033 7655 3916 7656 4033 7656 3831 7656 3831 7657 4033 7657 4034 7657 3831 7658 4034 7658 3833 7658 4034 7659 3832 7659 3833 7659 3833 7660 3832 7660 4037 7660 3833 7661 4037 7661 3913 7661 3913 7662 4037 7662 3834 7662 3913 7663 3834 7663 3912 7663 3912 7664 3834 7664 4041 7664 3912 7665 4041 7665 3835 7665 3835 7666 4041 7666 4040 7666 3835 7667 4040 7667 3836 7667 3836 7668 4040 7668 4038 7668 3836 7669 4038 7669 3837 7669 3837 7670 4038 7670 4043 7670 3837 7671 4043 7671 3838 7671 3838 7672 4043 7672 3839 7672 3838 7673 3839 7673 3911 7673 3911 7674 3839 7674 3840 7674 3911 7675 3840 7675 3909 7675 3909 7676 3840 7676 3841 7676 3909 7677 3841 7677 3842 7677 3842 7678 3841 7678 4045 7678 3842 7679 4045 7679 3843 7679 3843 7680 4045 7680 3844 7680 3843 7681 3844 7681 3845 7681 3845 7682 3844 7682 3846 7682 3845 7683 3846 7683 3905 7683 3846 7684 3847 7684 3905 7684 3905 7685 3847 7685 3848 7685 3905 7686 3848 7686 3903 7686 3903 7687 3848 7687 3849 7687 3903 7688 3849 7688 3900 7688 3900 7689 3849 7689 3851 7689 3900 7690 3851 7690 3850 7690 3850 7691 3851 7691 3852 7691 3850 7692 3852 7692 3898 7692 3898 7693 3852 7693 3853 7693 3898 7694 3853 7694 3855 7694 3853 7695 3854 7695 3855 7695 3855 7696 3854 7696 4050 7696 3855 7697 4050 7697 3895 7697 3895 7698 4050 7698 3856 7698 3895 7699 3856 7699 3858 7699 3858 7700 3856 7700 3857 7700 3858 7701 3857 7701 3859 7701 3859 7702 3857 7702 4053 7702 3859 7703 4053 7703 3892 7703 3892 7704 4053 7704 3860 7704 3892 7705 3860 7705 3861 7705 3861 7706 3860 7706 4054 7706 3861 7707 4054 7707 3862 7707 3862 7708 4054 7708 4055 7708 3862 7709 4055 7709 3889 7709 3889 7710 4055 7710 4056 7710 3889 7711 4056 7711 3863 7711 4056 7712 3864 7712 3863 7712 3863 7713 3864 7713 3865 7713 3863 7714 3865 7714 3866 7714 3866 7715 3865 7715 3867 7715 3866 7716 3867 7716 3887 7716 3867 7717 4065 7717 3887 7717 3887 7718 4065 7718 3869 7718 3887 7719 3869 7719 3868 7719 3868 7720 3869 7720 3870 7720 3868 7721 3870 7721 3871 7721 4062 7722 3881 7722 3871 7722 3871 7723 3881 7723 3872 7723 3871 7724 3872 7724 3868 7724 4062 7725 3873 7725 3881 7725 3881 7726 3873 7726 4060 7726 3881 7727 4060 7727 3874 7727 3874 7728 4060 7728 4059 7728 3874 7729 4059 7729 3880 7729 3880 7730 4059 7730 3875 7730 3880 7731 3875 7731 3877 7731 3877 7732 3875 7732 3876 7732 3877 7733 3876 7733 3878 7733 3878 7734 3876 7734 3681 7734 3681 7735 3919 7735 3878 7735 3878 7736 3919 7736 3879 7736 3878 7737 3879 7737 3877 7737 3877 7738 3879 7738 3920 7738 3877 7739 3920 7739 3880 7739 3880 7740 3920 7740 3921 7740 3880 7741 3921 7741 3874 7741 3874 7742 3921 7742 3882 7742 3874 7743 3882 7743 3881 7743 3881 7744 3882 7744 3883 7744 3881 7745 3883 7745 3872 7745 3872 7746 3883 7746 3884 7746 3872 7747 3884 7747 3868 7747 3868 7748 3884 7748 3885 7748 3868 7749 3885 7749 3887 7749 3887 7750 3885 7750 3886 7750 3887 7751 3886 7751 3866 7751 3866 7752 3886 7752 3888 7752 3866 7753 3888 7753 3863 7753 3863 7754 3888 7754 3927 7754 3863 7755 3927 7755 3889 7755 3889 7756 3927 7756 3890 7756 3889 7757 3890 7757 3862 7757 3862 7758 3890 7758 3891 7758 3862 7759 3891 7759 3861 7759 3861 7760 3891 7760 3930 7760 3861 7761 3930 7761 3892 7761 3892 7762 3930 7762 3931 7762 3892 7763 3931 7763 3859 7763 3859 7764 3931 7764 3893 7764 3859 7765 3893 7765 3858 7765 3858 7766 3893 7766 3894 7766 3858 7767 3894 7767 3895 7767 3895 7768 3894 7768 3896 7768 3895 7769 3896 7769 3855 7769 3855 7770 3896 7770 3897 7770 3855 7771 3897 7771 3898 7771 3898 7772 3897 7772 3899 7772 3898 7773 3899 7773 3850 7773 3850 7774 3899 7774 3901 7774 3850 7775 3901 7775 3900 7775 3900 7776 3901 7776 3902 7776 3900 7777 3902 7777 3903 7777 3903 7778 3902 7778 3904 7778 3903 7779 3904 7779 3905 7779 3905 7780 3904 7780 3937 7780 3905 7781 3937 7781 3845 7781 3845 7782 3937 7782 3906 7782 3845 7783 3906 7783 3843 7783 3843 7784 3906 7784 3907 7784 3843 7785 3907 7785 3842 7785 3842 7786 3907 7786 3908 7786 3842 7787 3908 7787 3909 7787 3909 7788 3908 7788 3910 7788 3909 7789 3910 7789 3911 7789 3911 7790 3910 7790 3940 7790 3911 7791 3940 7791 3838 7791 3838 7792 3940 7792 3941 7792 3838 7793 3941 7793 3837 7793 3837 7794 3941 7794 3942 7794 3837 7795 3942 7795 3836 7795 3836 7796 3942 7796 3943 7796 3836 7797 3943 7797 3835 7797 3835 7798 3943 7798 3946 7798 3835 7799 3946 7799 3912 7799 3912 7800 3946 7800 3947 7800 3912 7801 3947 7801 3913 7801 3913 7802 3947 7802 3914 7802 3913 7803 3914 7803 3833 7803 3833 7804 3914 7804 3948 7804 3833 7805 3948 7805 3831 7805 3831 7806 3948 7806 3915 7806 3831 7807 3915 7807 3916 7807 3916 7808 3915 7808 3917 7808 3916 7809 3917 7809 3827 7809 3825 7810 3918 7810 3919 7810 3919 7811 3918 7811 3984 7811 3919 7812 3984 7812 3879 7812 3879 7813 3984 7813 3983 7813 3879 7814 3983 7814 3920 7814 3920 7815 3983 7815 3982 7815 3920 7816 3982 7816 3921 7816 3921 7817 3982 7817 3922 7817 3921 7818 3922 7818 3882 7818 3882 7819 3922 7819 3923 7819 3882 7820 3923 7820 3883 7820 3883 7821 3923 7821 3980 7821 3883 7822 3980 7822 3884 7822 3884 7823 3980 7823 3924 7823 3884 7824 3924 7824 3885 7824 3885 7825 3924 7825 3925 7825 3885 7826 3925 7826 3886 7826 3886 7827 3925 7827 3978 7827 3886 7828 3978 7828 3888 7828 3888 7829 3978 7829 3926 7829 3888 7830 3926 7830 3927 7830 3927 7831 3926 7831 3975 7831 3927 7832 3975 7832 3890 7832 3890 7833 3975 7833 3928 7833 3890 7834 3928 7834 3891 7834 3891 7835 3928 7835 3929 7835 3891 7836 3929 7836 3930 7836 3930 7837 3929 7837 3973 7837 3930 7838 3973 7838 3931 7838 3931 7839 3973 7839 3932 7839 3931 7840 3932 7840 3893 7840 3893 7841 3932 7841 3933 7841 3893 7842 3933 7842 3894 7842 3894 7843 3933 7843 3934 7843 3894 7844 3934 7844 3896 7844 3896 7845 3934 7845 3970 7845 3896 7846 3970 7846 3897 7846 3897 7847 3970 7847 3935 7847 3897 7848 3935 7848 3899 7848 3899 7849 3935 7849 3969 7849 3899 7850 3969 7850 3901 7850 3901 7851 3969 7851 3966 7851 3901 7852 3966 7852 3902 7852 3902 7853 3966 7853 3965 7853 3902 7854 3965 7854 3904 7854 3904 7855 3965 7855 3936 7855 3904 7856 3936 7856 3937 7856 3937 7857 3936 7857 3964 7857 3937 7858 3964 7858 3906 7858 3906 7859 3964 7859 3938 7859 3906 7860 3938 7860 3907 7860 3907 7861 3938 7861 3939 7861 3907 7862 3939 7862 3908 7862 3908 7863 3939 7863 3962 7863 3908 7864 3962 7864 3910 7864 3910 7865 3962 7865 3961 7865 3910 7866 3961 7866 3940 7866 3940 7867 3961 7867 3960 7867 3940 7868 3960 7868 3941 7868 3941 7869 3960 7869 3958 7869 3941 7870 3958 7870 3942 7870 3942 7871 3958 7871 3955 7871 3942 7872 3955 7872 3943 7872 3943 7873 3955 7873 3944 7873 3943 7874 3944 7874 3946 7874 3946 7875 3944 7875 3945 7875 3946 7876 3945 7876 3947 7876 3947 7877 3945 7877 3953 7877 3947 7878 3953 7878 3914 7878 3914 7879 3953 7879 3951 7879 3914 7880 3951 7880 3948 7880 3948 7881 3951 7881 3949 7881 3948 7882 3949 7882 3915 7882 3915 7883 3949 7883 3830 7883 3915 7884 3830 7884 3828 7884 3950 7885 3949 7885 3613 7885 3613 7886 3949 7886 3951 7886 3613 7887 3951 7887 3952 7887 3952 7888 3951 7888 3953 7888 3952 7889 3953 7889 3610 7889 3610 7890 3953 7890 3945 7890 3610 7891 3945 7891 3954 7891 3954 7892 3945 7892 3944 7892 3954 7893 3944 7893 3956 7893 3956 7894 3944 7894 3955 7894 3956 7895 3955 7895 3957 7895 3957 7896 3955 7896 3958 7896 3957 7897 3958 7897 3959 7897 3959 7898 3958 7898 3960 7898 3959 7899 3960 7899 3625 7899 3625 7900 3960 7900 3961 7900 3625 7901 3961 7901 3627 7901 3627 7902 3961 7902 3962 7902 3627 7903 3962 7903 3629 7903 3629 7904 3962 7904 3939 7904 3629 7905 3939 7905 3630 7905 3630 7906 3939 7906 3938 7906 3630 7907 3938 7907 3963 7907 3963 7908 3938 7908 3964 7908 3963 7909 3964 7909 3633 7909 3633 7910 3964 7910 3936 7910 3633 7911 3936 7911 3634 7911 3634 7912 3936 7912 3965 7912 3634 7913 3965 7913 3635 7913 3635 7914 3965 7914 3966 7914 3635 7915 3966 7915 3967 7915 3967 7916 3966 7916 3969 7916 3967 7917 3969 7917 3968 7917 3968 7918 3969 7918 3935 7918 3968 7919 3935 7919 3653 7919 3653 7920 3935 7920 3970 7920 3653 7921 3970 7921 3971 7921 3971 7922 3970 7922 3934 7922 3971 7923 3934 7923 3972 7923 3972 7924 3934 7924 3933 7924 3972 7925 3933 7925 3654 7925 3654 7926 3933 7926 3932 7926 3654 7927 3932 7927 3655 7927 3655 7928 3932 7928 3973 7928 3655 7929 3973 7929 3639 7929 3639 7930 3973 7930 3929 7930 3639 7931 3929 7931 3974 7931 3974 7932 3929 7932 3928 7932 3974 7933 3928 7933 3976 7933 3976 7934 3928 7934 3975 7934 3976 7935 3975 7935 3641 7935 3641 7936 3975 7936 3926 7936 3641 7937 3926 7937 3977 7937 3977 7938 3926 7938 3978 7938 3977 7939 3978 7939 3616 7939 3616 7940 3978 7940 3925 7940 3616 7941 3925 7941 3979 7941 3979 7942 3925 7942 3924 7942 3979 7943 3924 7943 3642 7943 3642 7944 3924 7944 3980 7944 3642 7945 3980 7945 3981 7945 3981 7946 3980 7946 3923 7946 3981 7947 3923 7947 3645 7947 3645 7948 3923 7948 3922 7948 3645 7949 3922 7949 3646 7949 3646 7950 3922 7950 3982 7950 3646 7951 3982 7951 3656 7951 3656 7952 3982 7952 3983 7952 3656 7953 3983 7953 3657 7953 3657 7954 3983 7954 3984 7954 3657 7955 3984 7955 3659 7955 3659 7956 3984 7956 3918 7956 3659 7957 3918 7957 3660 7957 3660 7958 3918 7958 3683 7958 3660 7959 3683 7959 3685 7959 4026 7960 4030 7960 4027 7960 3702 7961 3985 7961 3700 7961 3986 7962 3702 7962 4009 7962 3995 7963 3824 7963 4079 7963 3987 7964 3988 7964 3990 7964 3989 7965 4075 7965 3990 7965 3990 7966 4075 7966 3991 7966 3990 7967 3991 7967 3987 7967 3987 7968 3991 7968 4076 7968 3987 7969 4076 7969 3992 7969 3992 7970 4076 7970 3993 7970 4076 7971 4080 7971 3993 7971 3993 7972 4080 7972 3994 7972 3993 7973 3994 7973 3821 7973 4079 7974 3824 7974 3994 7974 3994 7975 3824 7975 3823 7975 3994 7976 3823 7976 3821 7976 4079 7977 3996 7977 3995 7977 3995 7978 3996 7978 4088 7978 3995 7979 4088 7979 3706 7979 3706 7980 4088 7980 4087 7980 3706 7981 4087 7981 3997 7981 3997 7982 4087 7982 4085 7982 3997 7983 4085 7983 3708 7983 4085 7984 3998 7984 3708 7984 3708 7985 3998 7985 3999 7985 3708 7986 3999 7986 3709 7986 3709 7987 3999 7987 3712 7987 3712 7988 3999 7988 4000 7988 3712 7989 4000 7989 3713 7989 3713 7990 4000 7990 4081 7990 3713 7991 4081 7991 3715 7991 4081 7992 4001 7992 3715 7992 3715 7993 4001 7993 4103 7993 3715 7994 4103 7994 4003 7994 4003 7995 4103 7995 4002 7995 4003 7996 4002 7996 3716 7996 3716 7997 4002 7997 4101 7997 3716 7998 4101 7998 4004 7998 4101 7999 4005 7999 4004 7999 4004 8000 4005 8000 4006 8000 4004 8001 4006 8001 4007 8001 4007 8002 4006 8002 4008 8002 4007 8003 4008 8003 3703 8003 3703 8004 4008 8004 4099 8004 3703 8005 4099 8005 4009 8005 4009 8006 4099 8006 4010 8006 4009 8007 4010 8007 3986 8007 3986 8008 4095 8008 3702 8008 3702 8009 4095 8009 4093 8009 3702 8010 4093 8010 3985 8010 3985 8011 4093 8011 4092 8011 3985 8012 4092 8012 3700 8012 3700 8013 4092 8013 3699 8013 4092 8014 4011 8014 3699 8014 3699 8015 4011 8015 4012 8015 3699 8016 4012 8016 3697 8016 4012 8017 4090 8017 3697 8017 3697 8018 4090 8018 4251 8018 3697 8019 4251 8019 4013 8019 4013 8020 4251 8020 4250 8020 4013 8021 4250 8021 4014 8021 4014 8022 4250 8022 4246 8022 4014 8023 4246 8023 4015 8023 4246 8024 4016 8024 4015 8024 4015 8025 4016 8025 4017 8025 4015 8026 4017 8026 3695 8026 3695 8027 4017 8027 4018 8027 3695 8028 4018 8028 3694 8028 3694 8029 4018 8029 4020 8029 3694 8030 4020 8030 4019 8030 4019 8031 4020 8031 4243 8031 4019 8032 4243 8032 4021 8032 4021 8033 4243 8033 4022 8033 4021 8034 4022 8034 3692 8034 4022 8035 4023 8035 3692 8035 3692 8036 4023 8036 4240 8036 3692 8037 4240 8037 3690 8037 3690 8038 4240 8038 4239 8038 3690 8039 4239 8039 3688 8039 3688 8040 4239 8040 4024 8040 4024 8041 4239 8041 4238 8041 4024 8042 4238 8042 4025 8042 4025 8043 4238 8043 4029 8043 4025 8044 4029 8044 3687 8044 4074 8045 4026 8045 4235 8045 4235 8046 4026 8046 4027 8046 4235 8047 4027 8047 4236 8047 4236 8048 4027 8048 3687 8048 4236 8049 3687 8049 4028 8049 4028 8050 3687 8050 4029 8050 3990 8051 3988 8051 3876 8051 4026 8052 4074 8052 4032 8052 4030 8053 4026 8053 4031 8053 4031 8054 4026 8054 4032 8054 4031 8055 4032 8055 4033 8055 4033 8056 4032 8056 4035 8056 4033 8057 4035 8057 4034 8057 4034 8058 4035 8058 4294 8058 4034 8059 4294 8059 3832 8059 3832 8060 4294 8060 4036 8060 3832 8061 4036 8061 4037 8061 4036 8062 4291 8062 4037 8062 4037 8063 4291 8063 4290 8063 4037 8064 4290 8064 3834 8064 3834 8065 4290 8065 4039 8065 3834 8066 4039 8066 4041 8066 4288 8067 4038 8067 4039 8067 4039 8068 4038 8068 4040 8068 4039 8069 4040 8069 4041 8069 4288 8070 4286 8070 4038 8070 4038 8071 4286 8071 4042 8071 4038 8072 4042 8072 4043 8072 4043 8073 4042 8073 4284 8073 4043 8074 4284 8074 3839 8074 3839 8075 4284 8075 4283 8075 3839 8076 4283 8076 3840 8076 4276 8077 3846 8077 4044 8077 4044 8078 3846 8078 3844 8078 4044 8079 3844 8079 4279 8079 4279 8080 3844 8080 4045 8080 4279 8081 4045 8081 4281 8081 4281 8082 4045 8082 3841 8082 4281 8083 3841 8083 4046 8083 4046 8084 3841 8084 3840 8084 4046 8085 3840 8085 4047 8085 4047 8086 3840 8086 4283 8086 3851 8087 3849 8087 4275 8087 4275 8088 3849 8088 3848 8088 4275 8089 3848 8089 4276 8089 4276 8090 3848 8090 3847 8090 4276 8091 3847 8091 3846 8091 4275 8092 4048 8092 3851 8092 3851 8093 4048 8093 4274 8093 3851 8094 4274 8094 3852 8094 3852 8095 4274 8095 3853 8095 4274 8096 4273 8096 3853 8096 3853 8097 4273 8097 4049 8097 3853 8098 4049 8098 3854 8098 3854 8099 4049 8099 4050 8099 4050 8100 4049 8100 4051 8100 4050 8101 4051 8101 3856 8101 3856 8102 4051 8102 4052 8102 3856 8103 4052 8103 3857 8103 4052 8104 4269 8104 3857 8104 3857 8105 4269 8105 4267 8105 3857 8106 4267 8106 4053 8106 4053 8107 4267 8107 4266 8107 4053 8108 4266 8108 3860 8108 3860 8109 4266 8109 4263 8109 3860 8110 4263 8110 4054 8110 4054 8111 4263 8111 4262 8111 4054 8112 4262 8112 4055 8112 4055 8113 4262 8113 4058 8113 4055 8114 4058 8114 4056 8114 4057 8115 3865 8115 4058 8115 4058 8116 3865 8116 3864 8116 4058 8117 3864 8117 4056 8117 3875 8118 4059 8118 4256 8118 4256 8119 4059 8119 4060 8119 4256 8120 4060 8120 4257 8120 4257 8121 4060 8121 3873 8121 4257 8122 3873 8122 4061 8122 4061 8123 3873 8123 4062 8123 4061 8124 4062 8124 4258 8124 4258 8125 4062 8125 3871 8125 4258 8126 3871 8126 4063 8126 4063 8127 3871 8127 3870 8127 4063 8128 3870 8128 4064 8128 4064 8129 3870 8129 3869 8129 4064 8130 3869 8130 4260 8130 4260 8131 3869 8131 4065 8131 4260 8132 4065 8132 4057 8132 4057 8133 4065 8133 3867 8133 4057 8134 3867 8134 3865 8134 4256 8135 4066 8135 3875 8135 3875 8136 4066 8136 4067 8136 3875 8137 4067 8137 3876 8137 3876 8138 4067 8138 3989 8138 3876 8139 3989 8139 3990 8139 4326 8140 4068 8140 4233 8140 4252 8141 4069 8141 4432 8141 4253 8142 4070 8142 4196 8142 4071 8143 4073 8143 4072 8143 4072 8144 4073 8144 4074 8144 4143 8145 4437 8145 4254 8145 4195 8146 4373 8146 4194 8146 4194 8147 4373 8147 4252 8147 4075 8148 3989 8148 4234 8148 4234 8149 4232 8149 4075 8149 4075 8150 4232 8150 4231 8150 4075 8151 4231 8151 3991 8151 3991 8152 4231 8152 4229 8152 3991 8153 4229 8153 4076 8153 4076 8154 4229 8154 4227 8154 4076 8155 4227 8155 4080 8155 4080 8156 4227 8156 4077 8156 4078 8157 3996 8157 4225 8157 4225 8158 3996 8158 4079 8158 4225 8159 4079 8159 4077 8159 4077 8160 4079 8160 3994 8160 4077 8161 3994 8161 4080 8161 4081 8162 4000 8162 4082 8162 4082 8163 4000 8163 3999 8163 4082 8164 3999 8164 4083 8164 4083 8165 3999 8165 3998 8165 4083 8166 3998 8166 4084 8166 4084 8167 3998 8167 4085 8167 4084 8168 4085 8168 4086 8168 4086 8169 4085 8169 4087 8169 4086 8170 4087 8170 4078 8170 4078 8171 4087 8171 4088 8171 4078 8172 4088 8172 3996 8172 4081 8173 4082 8173 4001 8173 4001 8174 4082 8174 4089 8174 4001 8175 4089 8175 4102 8175 4249 8176 4090 8176 4209 8176 4209 8177 4090 8177 4012 8177 4209 8178 4012 8178 4091 8178 4091 8179 4012 8179 4011 8179 4091 8180 4011 8180 4210 8180 4210 8181 4011 8181 4092 8181 4210 8182 4092 8182 4094 8182 4094 8183 4092 8183 4093 8183 4094 8184 4093 8184 4211 8184 4211 8185 4093 8185 4095 8185 4211 8186 4095 8186 4096 8186 4096 8187 4095 8187 3986 8187 4096 8188 3986 8188 4097 8188 4097 8189 3986 8189 4010 8189 4097 8190 4010 8190 4098 8190 4098 8191 4010 8191 4099 8191 4098 8192 4099 8192 4214 8192 4214 8193 4099 8193 4008 8193 4214 8194 4008 8194 4216 8194 4216 8195 4008 8195 4006 8195 4216 8196 4006 8196 4217 8196 4217 8197 4006 8197 4005 8197 4217 8198 4005 8198 4100 8198 4100 8199 4005 8199 4101 8199 4100 8200 4101 8200 4219 8200 4219 8201 4101 8201 4002 8201 4219 8202 4002 8202 4102 8202 4102 8203 4002 8203 4103 8203 4102 8204 4103 8204 4001 8204 4252 8205 4432 8205 4194 8205 4194 8206 4432 8206 4104 8206 4194 8207 4104 8207 4105 8207 4105 8208 4104 8208 4106 8208 4105 8209 4106 8209 4193 8209 4193 8210 4106 8210 4107 8210 4193 8211 4107 8211 4192 8211 4192 8212 4107 8212 4108 8212 4192 8213 4108 8213 4109 8213 4109 8214 4108 8214 4110 8214 4109 8215 4110 8215 4111 8215 4111 8216 4110 8216 4112 8216 4111 8217 4112 8217 4113 8217 4113 8218 4112 8218 4114 8218 4113 8219 4114 8219 4190 8219 4190 8220 4114 8220 4115 8220 4190 8221 4115 8221 4189 8221 4189 8222 4115 8222 4447 8222 4189 8223 4447 8223 4188 8223 4188 8224 4447 8224 4446 8224 4188 8225 4446 8225 4186 8225 4186 8226 4446 8226 4116 8226 4186 8227 4116 8227 4185 8227 4185 8228 4116 8228 4117 8228 4185 8229 4117 8229 4182 8229 4182 8230 4117 8230 4423 8230 4182 8231 4423 8231 4118 8231 4118 8232 4423 8232 4408 8232 4118 8233 4408 8233 4180 8233 4180 8234 4408 8234 4119 8234 4180 8235 4119 8235 4179 8235 4179 8236 4119 8236 4433 8236 4179 8237 4433 8237 4177 8237 4177 8238 4433 8238 4120 8238 4177 8239 4120 8239 4176 8239 4176 8240 4120 8240 4454 8240 4176 8241 4454 8241 4174 8241 4174 8242 4454 8242 4452 8242 4174 8243 4452 8243 4121 8243 4121 8244 4452 8244 4451 8244 4121 8245 4451 8245 4122 8245 4122 8246 4451 8246 4123 8246 4122 8247 4123 8247 4171 8247 4171 8248 4123 8248 4457 8248 4171 8249 4457 8249 4124 8249 4124 8250 4457 8250 4125 8250 4124 8251 4125 8251 4168 8251 4168 8252 4125 8252 4126 8252 4168 8253 4126 8253 4167 8253 4167 8254 4126 8254 4449 8254 4167 8255 4449 8255 4164 8255 4164 8256 4449 8256 4127 8256 4164 8257 4127 8257 4163 8257 4163 8258 4127 8258 4448 8258 4163 8259 4448 8259 4128 8259 4128 8260 4448 8260 4456 8260 4128 8261 4456 8261 4129 8261 4129 8262 4456 8262 4130 8262 4129 8263 4130 8263 4161 8263 4161 8264 4130 8264 4131 8264 4161 8265 4131 8265 4159 8265 4159 8266 4131 8266 4455 8266 4159 8267 4455 8267 4132 8267 4132 8268 4455 8268 4444 8268 4132 8269 4444 8269 4156 8269 4156 8270 4444 8270 4133 8270 4156 8271 4133 8271 4135 8271 4135 8272 4133 8272 4134 8272 4135 8273 4134 8273 4154 8273 4154 8274 4134 8274 4137 8274 4154 8275 4137 8275 4136 8275 4136 8276 4137 8276 4138 8276 4136 8277 4138 8277 4151 8277 4151 8278 4138 8278 4415 8278 4151 8279 4415 8279 4149 8279 4149 8280 4415 8280 4409 8280 4149 8281 4409 8281 4147 8281 4147 8282 4409 8282 4139 8282 4147 8283 4139 8283 4146 8283 4146 8284 4139 8284 4140 8284 4146 8285 4140 8285 4141 8285 4141 8286 4140 8286 4143 8286 4141 8287 4143 8287 4142 8287 4142 8288 4143 8288 4254 8288 4142 8289 4254 8289 4144 8289 4144 8290 4253 8290 4142 8290 4142 8291 4253 8291 4196 8291 4142 8292 4196 8292 4141 8292 4141 8293 4196 8293 4145 8293 4141 8294 4145 8294 4146 8294 4146 8295 4145 8295 4148 8295 4146 8296 4148 8296 4147 8296 4147 8297 4148 8297 4198 8297 4147 8298 4198 8298 4149 8298 4149 8299 4198 8299 4150 8299 4149 8300 4150 8300 4151 8300 4151 8301 4150 8301 4152 8301 4151 8302 4152 8302 4136 8302 4136 8303 4152 8303 4153 8303 4136 8304 4153 8304 4154 8304 4154 8305 4153 8305 4155 8305 4154 8306 4155 8306 4135 8306 4135 8307 4155 8307 4202 8307 4135 8308 4202 8308 4156 8308 4156 8309 4202 8309 4157 8309 4156 8310 4157 8310 4132 8310 4132 8311 4157 8311 4158 8311 4132 8312 4158 8312 4159 8312 4159 8313 4158 8313 4160 8313 4159 8314 4160 8314 4161 8314 4161 8315 4160 8315 4205 8315 4161 8316 4205 8316 4129 8316 4129 8317 4205 8317 4206 8317 4129 8318 4206 8318 4128 8318 4128 8319 4206 8319 4162 8319 4128 8320 4162 8320 4163 8320 4163 8321 4162 8321 4208 8321 4163 8322 4208 8322 4164 8322 4164 8323 4208 8323 4165 8323 4164 8324 4165 8324 4167 8324 4167 8325 4165 8325 4166 8325 4167 8326 4166 8326 4168 8326 4168 8327 4166 8327 4169 8327 4168 8328 4169 8328 4124 8328 4124 8329 4169 8329 4170 8329 4124 8330 4170 8330 4171 8330 4171 8331 4170 8331 4172 8331 4171 8332 4172 8332 4122 8332 4122 8333 4172 8333 4212 8333 4122 8334 4212 8334 4121 8334 4121 8335 4212 8335 4173 8335 4121 8336 4173 8336 4174 8336 4174 8337 4173 8337 4175 8337 4174 8338 4175 8338 4176 8338 4176 8339 4175 8339 4213 8339 4176 8340 4213 8340 4177 8340 4177 8341 4213 8341 4178 8341 4177 8342 4178 8342 4179 8342 4179 8343 4178 8343 4215 8343 4179 8344 4215 8344 4180 8344 4180 8345 4215 8345 4218 8345 4180 8346 4218 8346 4118 8346 4118 8347 4218 8347 4181 8347 4118 8348 4181 8348 4182 8348 4182 8349 4181 8349 4183 8349 4182 8350 4183 8350 4185 8350 4185 8351 4183 8351 4184 8351 4185 8352 4184 8352 4186 8352 4186 8353 4184 8353 4187 8353 4186 8354 4187 8354 4188 8354 4188 8355 4187 8355 4220 8355 4188 8356 4220 8356 4189 8356 4189 8357 4220 8357 4221 8357 4189 8358 4221 8358 4190 8358 4190 8359 4221 8359 4191 8359 4190 8360 4191 8360 4113 8360 4113 8361 4191 8361 4222 8361 4113 8362 4222 8362 4111 8362 4111 8363 4222 8363 4223 8363 4111 8364 4223 8364 4109 8364 4109 8365 4223 8365 4224 8365 4109 8366 4224 8366 4192 8366 4192 8367 4224 8367 4226 8367 4192 8368 4226 8368 4193 8368 4193 8369 4226 8369 4228 8369 4193 8370 4228 8370 4105 8370 4105 8371 4228 8371 4230 8371 4105 8372 4230 8372 4194 8372 4194 8373 4230 8373 4233 8373 4194 8374 4233 8374 4195 8374 4195 8375 4233 8375 4068 8375 4070 8376 4071 8376 4196 8376 4196 8377 4071 8377 4072 8377 4196 8378 4072 8378 4145 8378 4145 8379 4072 8379 4197 8379 4145 8380 4197 8380 4148 8380 4148 8381 4197 8381 4237 8381 4148 8382 4237 8382 4198 8382 4198 8383 4237 8383 4199 8383 4198 8384 4199 8384 4150 8384 4150 8385 4199 8385 4200 8385 4150 8386 4200 8386 4152 8386 4152 8387 4200 8387 4201 8387 4152 8388 4201 8388 4153 8388 4153 8389 4201 8389 4241 8389 4153 8390 4241 8390 4155 8390 4155 8391 4241 8391 4242 8391 4155 8392 4242 8392 4202 8392 4202 8393 4242 8393 4203 8393 4202 8394 4203 8394 4157 8394 4157 8395 4203 8395 4204 8395 4157 8396 4204 8396 4158 8396 4158 8397 4204 8397 4244 8397 4158 8398 4244 8398 4160 8398 4160 8399 4244 8399 4245 8399 4160 8400 4245 8400 4205 8400 4205 8401 4245 8401 4207 8401 4205 8402 4207 8402 4206 8402 4206 8403 4207 8403 4247 8403 4206 8404 4247 8404 4162 8404 4162 8405 4247 8405 4248 8405 4162 8406 4248 8406 4208 8406 4208 8407 4248 8407 4249 8407 4208 8408 4249 8408 4165 8408 4165 8409 4249 8409 4209 8409 4165 8410 4209 8410 4166 8410 4166 8411 4209 8411 4091 8411 4166 8412 4091 8412 4169 8412 4169 8413 4091 8413 4210 8413 4169 8414 4210 8414 4170 8414 4170 8415 4210 8415 4094 8415 4170 8416 4094 8416 4172 8416 4172 8417 4094 8417 4211 8417 4172 8418 4211 8418 4212 8418 4212 8419 4211 8419 4096 8419 4212 8420 4096 8420 4173 8420 4173 8421 4096 8421 4097 8421 4173 8422 4097 8422 4175 8422 4175 8423 4097 8423 4098 8423 4175 8424 4098 8424 4213 8424 4213 8425 4098 8425 4214 8425 4213 8426 4214 8426 4178 8426 4178 8427 4214 8427 4216 8427 4178 8428 4216 8428 4215 8428 4215 8429 4216 8429 4217 8429 4215 8430 4217 8430 4218 8430 4218 8431 4217 8431 4100 8431 4218 8432 4100 8432 4181 8432 4181 8433 4100 8433 4219 8433 4181 8434 4219 8434 4183 8434 4183 8435 4219 8435 4102 8435 4183 8436 4102 8436 4184 8436 4184 8437 4102 8437 4089 8437 4184 8438 4089 8438 4187 8438 4187 8439 4089 8439 4082 8439 4187 8440 4082 8440 4220 8440 4220 8441 4082 8441 4083 8441 4220 8442 4083 8442 4221 8442 4221 8443 4083 8443 4084 8443 4221 8444 4084 8444 4191 8444 4191 8445 4084 8445 4086 8445 4191 8446 4086 8446 4222 8446 4222 8447 4086 8447 4078 8447 4222 8448 4078 8448 4223 8448 4223 8449 4078 8449 4225 8449 4223 8450 4225 8450 4224 8450 4224 8451 4225 8451 4077 8451 4224 8452 4077 8452 4226 8452 4226 8453 4077 8453 4227 8453 4226 8454 4227 8454 4228 8454 4228 8455 4227 8455 4229 8455 4228 8456 4229 8456 4230 8456 4230 8457 4229 8457 4231 8457 4230 8458 4231 8458 4233 8458 4233 8459 4231 8459 4232 8459 4233 8460 4232 8460 4326 8460 4326 8461 4232 8461 4234 8461 4074 8462 4235 8462 4072 8462 4072 8463 4235 8463 4236 8463 4072 8464 4236 8464 4197 8464 4197 8465 4236 8465 4028 8465 4197 8466 4028 8466 4237 8466 4237 8467 4028 8467 4029 8467 4237 8468 4029 8468 4199 8468 4199 8469 4029 8469 4238 8469 4199 8470 4238 8470 4200 8470 4200 8471 4238 8471 4239 8471 4200 8472 4239 8472 4201 8472 4201 8473 4239 8473 4240 8473 4201 8474 4240 8474 4241 8474 4241 8475 4240 8475 4023 8475 4241 8476 4023 8476 4242 8476 4242 8477 4023 8477 4022 8477 4242 8478 4022 8478 4203 8478 4203 8479 4022 8479 4243 8479 4203 8480 4243 8480 4204 8480 4204 8481 4243 8481 4020 8481 4204 8482 4020 8482 4244 8482 4244 8483 4020 8483 4018 8483 4244 8484 4018 8484 4245 8484 4245 8485 4018 8485 4017 8485 4245 8486 4017 8486 4207 8486 4207 8487 4017 8487 4016 8487 4207 8488 4016 8488 4247 8488 4247 8489 4016 8489 4246 8489 4247 8490 4246 8490 4248 8490 4248 8491 4246 8491 4250 8491 4248 8492 4250 8492 4249 8492 4249 8493 4250 8493 4251 8493 4249 8494 4251 8494 4090 8494 4071 8495 4070 8495 4327 8495 4252 8496 4373 8496 4374 8496 4195 8497 4068 8497 4372 8497 4326 8498 4234 8498 4325 8498 4325 8499 4234 8499 3989 8499 4375 8500 4069 8500 4252 8500 4253 8501 4144 8501 4328 8501 4328 8502 4144 8502 4254 8502 4032 8503 4074 8503 4073 8503 3989 8504 4067 8504 4325 8504 4325 8505 4067 8505 4066 8505 4325 8506 4066 8506 4324 8506 4324 8507 4066 8507 4256 8507 4324 8508 4256 8508 4255 8508 4255 8509 4256 8509 4257 8509 4061 8510 4259 8510 4257 8510 4257 8511 4259 8511 4321 8511 4257 8512 4321 8512 4255 8512 4061 8513 4258 8513 4259 8513 4259 8514 4258 8514 4063 8514 4259 8515 4063 8515 4320 8515 4320 8516 4063 8516 4064 8516 4320 8517 4064 8517 4261 8517 4064 8518 4260 8518 4261 8518 4261 8519 4260 8519 4057 8519 4261 8520 4057 8520 4318 8520 4318 8521 4057 8521 4058 8521 4318 8522 4058 8522 4317 8522 4317 8523 4058 8523 4262 8523 4317 8524 4262 8524 4265 8524 4265 8525 4262 8525 4263 8525 4266 8526 4268 8526 4263 8526 4263 8527 4268 8527 4264 8527 4263 8528 4264 8528 4265 8528 4266 8529 4267 8529 4268 8529 4268 8530 4267 8530 4269 8530 4268 8531 4269 8531 4314 8531 4314 8532 4269 8532 4052 8532 4314 8533 4052 8533 4270 8533 4270 8534 4052 8534 4051 8534 4270 8535 4051 8535 4312 8535 4312 8536 4051 8536 4049 8536 4312 8537 4049 8537 4271 8537 4271 8538 4049 8538 4273 8538 4271 8539 4273 8539 4272 8539 4272 8540 4273 8540 4274 8540 4272 8541 4274 8541 4309 8541 4309 8542 4274 8542 4048 8542 4309 8543 4048 8543 4308 8543 4308 8544 4048 8544 4275 8544 4308 8545 4275 8545 4306 8545 4306 8546 4275 8546 4276 8546 4306 8547 4276 8547 4277 8547 4277 8548 4276 8548 4044 8548 4277 8549 4044 8549 4278 8549 4278 8550 4044 8550 4279 8550 4278 8551 4279 8551 4305 8551 4305 8552 4279 8552 4281 8552 4305 8553 4281 8553 4280 8553 4280 8554 4281 8554 4046 8554 4047 8555 4282 8555 4046 8555 4046 8556 4282 8556 4303 8556 4046 8557 4303 8557 4280 8557 4047 8558 4283 8558 4282 8558 4282 8559 4283 8559 4284 8559 4282 8560 4284 8560 4302 8560 4302 8561 4284 8561 4042 8561 4302 8562 4042 8562 4285 8562 4285 8563 4042 8563 4286 8563 4285 8564 4286 8564 4287 8564 4287 8565 4286 8565 4288 8565 4287 8566 4288 8566 4301 8566 4301 8567 4288 8567 4039 8567 4301 8568 4039 8568 4289 8568 4289 8569 4039 8569 4290 8569 4289 8570 4290 8570 4292 8570 4292 8571 4290 8571 4291 8571 4292 8572 4291 8572 4300 8572 4300 8573 4291 8573 4036 8573 4300 8574 4036 8574 4293 8574 4293 8575 4036 8575 4294 8575 4293 8576 4294 8576 4298 8576 4298 8577 4294 8577 4035 8577 4298 8578 4035 8578 4296 8578 4296 8579 4035 8579 4032 8579 4296 8580 4032 8580 4295 8580 4295 8581 4032 8581 4073 8581 4073 8582 4071 8582 4295 8582 4295 8583 4071 8583 4327 8583 4295 8584 4327 8584 4296 8584 4296 8585 4327 8585 4297 8585 4296 8586 4297 8586 4298 8586 4298 8587 4297 8587 4299 8587 4298 8588 4299 8588 4293 8588 4293 8589 4299 8589 4330 8589 4293 8590 4330 8590 4300 8590 4300 8591 4330 8591 4332 8591 4300 8592 4332 8592 4292 8592 4292 8593 4332 8593 4333 8593 4292 8594 4333 8594 4289 8594 4289 8595 4333 8595 4334 8595 4289 8596 4334 8596 4301 8596 4301 8597 4334 8597 4335 8597 4301 8598 4335 8598 4287 8598 4287 8599 4335 8599 4337 8599 4287 8600 4337 8600 4285 8600 4285 8601 4337 8601 4339 8601 4285 8602 4339 8602 4302 8602 4302 8603 4339 8603 4340 8603 4302 8604 4340 8604 4282 8604 4282 8605 4340 8605 4304 8605 4282 8606 4304 8606 4303 8606 4303 8607 4304 8607 4341 8607 4303 8608 4341 8608 4280 8608 4280 8609 4341 8609 4342 8609 4280 8610 4342 8610 4305 8610 4305 8611 4342 8611 4344 8611 4305 8612 4344 8612 4278 8612 4278 8613 4344 8613 4346 8613 4278 8614 4346 8614 4277 8614 4277 8615 4346 8615 4349 8615 4277 8616 4349 8616 4306 8616 4306 8617 4349 8617 4307 8617 4306 8618 4307 8618 4308 8618 4308 8619 4307 8619 4350 8619 4308 8620 4350 8620 4309 8620 4309 8621 4350 8621 4310 8621 4309 8622 4310 8622 4272 8622 4272 8623 4310 8623 4354 8623 4272 8624 4354 8624 4271 8624 4271 8625 4354 8625 4356 8625 4271 8626 4356 8626 4312 8626 4312 8627 4356 8627 4311 8627 4312 8628 4311 8628 4270 8628 4270 8629 4311 8629 4313 8629 4270 8630 4313 8630 4314 8630 4314 8631 4313 8631 4358 8631 4314 8632 4358 8632 4268 8632 4268 8633 4358 8633 4315 8633 4268 8634 4315 8634 4264 8634 4264 8635 4315 8635 4316 8635 4264 8636 4316 8636 4265 8636 4265 8637 4316 8637 4361 8637 4265 8638 4361 8638 4317 8638 4317 8639 4361 8639 4362 8639 4317 8640 4362 8640 4318 8640 4318 8641 4362 8641 4319 8641 4318 8642 4319 8642 4261 8642 4261 8643 4319 8643 4364 8643 4261 8644 4364 8644 4320 8644 4320 8645 4364 8645 4366 8645 4320 8646 4366 8646 4259 8646 4259 8647 4366 8647 4368 8647 4259 8648 4368 8648 4321 8648 4321 8649 4368 8649 4322 8649 4321 8650 4322 8650 4255 8650 4255 8651 4322 8651 4323 8651 4255 8652 4323 8652 4324 8652 4324 8653 4323 8653 4370 8653 4324 8654 4370 8654 4325 8654 4325 8655 4370 8655 4372 8655 4325 8656 4372 8656 4326 8656 4326 8657 4372 8657 4068 8657 4070 8658 4253 8658 4327 8658 4327 8659 4253 8659 4328 8659 4327 8660 4328 8660 4297 8660 4297 8661 4328 8661 4329 8661 4297 8662 4329 8662 4299 8662 4299 8663 4329 8663 4331 8663 4299 8664 4331 8664 4330 8664 4330 8665 4331 8665 4405 8665 4330 8666 4405 8666 4332 8666 4332 8667 4405 8667 4404 8667 4332 8668 4404 8668 4333 8668 4333 8669 4404 8669 4403 8669 4333 8670 4403 8670 4334 8670 4334 8671 4403 8671 4402 8671 4334 8672 4402 8672 4335 8672 4335 8673 4402 8673 4336 8673 4335 8674 4336 8674 4337 8674 4337 8675 4336 8675 4338 8675 4337 8676 4338 8676 4339 8676 4339 8677 4338 8677 4399 8677 4339 8678 4399 8678 4340 8678 4340 8679 4399 8679 4396 8679 4340 8680 4396 8680 4304 8680 4304 8681 4396 8681 4394 8681 4304 8682 4394 8682 4341 8682 4341 8683 4394 8683 4393 8683 4341 8684 4393 8684 4342 8684 4342 8685 4393 8685 4343 8685 4342 8686 4343 8686 4344 8686 4344 8687 4343 8687 4345 8687 4344 8688 4345 8688 4346 8688 4346 8689 4345 8689 4347 8689 4346 8690 4347 8690 4349 8690 4349 8691 4347 8691 4348 8691 4349 8692 4348 8692 4307 8692 4307 8693 4348 8693 4351 8693 4307 8694 4351 8694 4350 8694 4350 8695 4351 8695 4352 8695 4350 8696 4352 8696 4310 8696 4310 8697 4352 8697 4353 8697 4310 8698 4353 8698 4354 8698 4354 8699 4353 8699 4355 8699 4354 8700 4355 8700 4356 8700 4356 8701 4355 8701 4388 8701 4356 8702 4388 8702 4311 8702 4311 8703 4388 8703 4357 8703 4311 8704 4357 8704 4313 8704 4313 8705 4357 8705 4359 8705 4313 8706 4359 8706 4358 8706 4358 8707 4359 8707 4360 8707 4358 8708 4360 8708 4315 8708 4315 8709 4360 8709 4385 8709 4315 8710 4385 8710 4316 8710 4316 8711 4385 8711 4383 8711 4316 8712 4383 8712 4361 8712 4361 8713 4383 8713 4381 8713 4361 8714 4381 8714 4362 8714 4362 8715 4381 8715 4380 8715 4362 8716 4380 8716 4319 8716 4319 8717 4380 8717 4363 8717 4319 8718 4363 8718 4364 8718 4364 8719 4363 8719 4365 8719 4364 8720 4365 8720 4366 8720 4366 8721 4365 8721 4367 8721 4366 8722 4367 8722 4368 8722 4368 8723 4367 8723 4369 8723 4368 8724 4369 8724 4322 8724 4322 8725 4369 8725 4378 8725 4322 8726 4378 8726 4323 8726 4323 8727 4378 8727 4376 8727 4323 8728 4376 8728 4370 8728 4370 8729 4376 8729 4371 8729 4370 8730 4371 8730 4372 8730 4372 8731 4371 8731 4374 8731 4372 8732 4374 8732 4195 8732 4195 8733 4374 8733 4373 8733 4252 8734 4374 8734 4375 8734 4375 8735 4374 8735 4371 8735 4375 8736 4371 8736 4411 8736 4411 8737 4371 8737 4376 8737 4411 8738 4376 8738 4377 8738 4377 8739 4376 8739 4378 8739 4377 8740 4378 8740 4412 8740 4412 8741 4378 8741 4369 8741 4412 8742 4369 8742 4414 8742 4414 8743 4369 8743 4367 8743 4414 8744 4367 8744 4440 8744 4440 8745 4367 8745 4365 8745 4440 8746 4365 8746 4441 8746 4441 8747 4365 8747 4363 8747 4441 8748 4363 8748 4379 8748 4379 8749 4363 8749 4380 8749 4379 8750 4380 8750 4382 8750 4382 8751 4380 8751 4381 8751 4382 8752 4381 8752 4422 8752 4422 8753 4381 8753 4383 8753 4422 8754 4383 8754 4384 8754 4384 8755 4383 8755 4385 8755 4384 8756 4385 8756 4430 8756 4430 8757 4385 8757 4360 8757 4430 8758 4360 8758 4386 8758 4386 8759 4360 8759 4359 8759 4386 8760 4359 8760 4387 8760 4387 8761 4359 8761 4357 8761 4387 8762 4357 8762 4429 8762 4429 8763 4357 8763 4388 8763 4429 8764 4388 8764 4389 8764 4389 8765 4388 8765 4355 8765 4389 8766 4355 8766 4438 8766 4438 8767 4355 8767 4353 8767 4438 8768 4353 8768 4390 8768 4390 8769 4353 8769 4352 8769 4390 8770 4352 8770 4391 8770 4391 8771 4352 8771 4351 8771 4391 8772 4351 8772 4392 8772 4392 8773 4351 8773 4348 8773 4392 8774 4348 8774 4417 8774 4417 8775 4348 8775 4347 8775 4417 8776 4347 8776 4419 8776 4419 8777 4347 8777 4345 8777 4419 8778 4345 8778 4420 8778 4420 8779 4345 8779 4343 8779 4420 8780 4343 8780 4421 8780 4421 8781 4343 8781 4393 8781 4421 8782 4393 8782 4416 8782 4416 8783 4393 8783 4394 8783 4416 8784 4394 8784 4395 8784 4395 8785 4394 8785 4396 8785 4395 8786 4396 8786 4397 8786 4397 8787 4396 8787 4399 8787 4397 8788 4399 8788 4398 8788 4398 8789 4399 8789 4338 8789 4398 8790 4338 8790 4400 8790 4400 8791 4338 8791 4336 8791 4400 8792 4336 8792 4410 8792 4410 8793 4336 8793 4402 8793 4410 8794 4402 8794 4401 8794 4401 8795 4402 8795 4403 8795 4401 8796 4403 8796 4426 8796 4426 8797 4403 8797 4404 8797 4426 8798 4404 8798 4427 8798 4427 8799 4404 8799 4405 8799 4427 8800 4405 8800 4406 8800 4406 8801 4405 8801 4331 8801 4406 8802 4331 8802 4424 8802 4424 8803 4331 8803 4329 8803 4424 8804 4329 8804 4407 8804 4407 8805 4329 8805 4328 8805 4407 8806 4328 8806 4435 8806 4435 8807 4328 8807 4254 8807 4435 8808 4254 8808 4437 8808 217 8809 4428 8809 4389 8809 4408 8810 4423 8810 4434 8810 4415 8811 234 8811 4409 8811 4409 8812 234 8812 235 8812 4409 8813 235 8813 4139 8813 4139 8814 235 8814 4436 8814 4139 8815 4436 8815 4140 8815 4401 8816 226 8816 4410 8816 4410 8817 226 8817 4418 8817 229 8818 4439 8818 4392 8818 4431 8819 4411 8819 221 8819 221 8820 4411 8820 4377 8820 221 8821 4377 8821 4413 8821 4413 8822 4377 8822 4412 8822 4413 8823 4412 8823 4414 8823 4115 8824 4114 8824 4445 8824 4445 8825 4114 8825 4112 8825 4415 8826 4138 8826 234 8826 234 8827 4138 8827 4137 8827 234 8828 4137 8828 4134 8828 4425 8829 226 8829 4406 8829 4421 8830 4416 8830 4418 8830 4418 8831 4416 8831 4395 8831 4418 8832 4395 8832 4397 8832 4392 8833 4417 8833 229 8833 229 8834 4417 8834 4419 8834 229 8835 4419 8835 4418 8835 4418 8836 4419 8836 4420 8836 4418 8837 4420 8837 4421 8837 4422 8838 4384 8838 4442 8838 4434 8839 4423 8839 4445 8839 4445 8840 4423 8840 4117 8840 4445 8841 4117 8841 4116 8841 4406 8842 4424 8842 4425 8842 4425 8843 4424 8843 4407 8843 4425 8844 4407 8844 224 8844 4401 8845 4426 8845 226 8845 226 8846 4426 8846 4427 8846 226 8847 4427 8847 4406 8847 4397 8848 4398 8848 4418 8848 4418 8849 4398 8849 4400 8849 4418 8850 4400 8850 4410 8850 4389 8851 4428 8851 4429 8851 4429 8852 4428 8852 4442 8852 4429 8853 4442 8853 4387 8853 4422 8854 4442 8854 4382 8854 4384 8855 4430 8855 4442 8855 4442 8856 4430 8856 4386 8856 4442 8857 4386 8857 4387 8857 4432 8858 4431 8858 4104 8858 4104 8859 4431 8859 237 8859 4432 8860 4069 8860 4431 8860 4431 8861 4069 8861 4375 8861 4431 8862 4375 8862 4411 8862 4453 8863 4433 8863 4434 8863 4434 8864 4433 8864 4119 8864 4434 8865 4119 8865 4408 8865 4407 8866 4435 8866 224 8866 224 8867 4435 8867 4437 8867 224 8868 4437 8868 4436 8868 4436 8869 4437 8869 4143 8869 4436 8870 4143 8870 4140 8870 4389 8871 4438 8871 217 8871 217 8872 4438 8872 4390 8872 217 8873 4390 8873 4439 8873 4439 8874 4390 8874 4391 8874 4439 8875 4391 8875 4392 8875 4414 8876 4440 8876 4413 8876 4413 8877 4440 8877 4441 8877 4413 8878 4441 8878 4442 8878 4442 8879 4441 8879 4379 8879 4442 8880 4379 8880 4382 8880 4112 8881 4110 8881 4445 8881 4445 8882 4110 8882 4108 8882 4445 8883 4108 8883 4443 8883 4443 8884 4108 8884 4107 8884 4443 8885 4107 8885 237 8885 237 8886 4107 8886 4106 8886 237 8887 4106 8887 4104 8887 4134 8888 4133 8888 234 8888 234 8889 4133 8889 4444 8889 234 8890 4444 8890 4455 8890 4116 8891 4446 8891 4445 8891 4445 8892 4446 8892 4447 8892 4445 8893 4447 8893 4115 8893 4448 8894 4127 8894 233 8894 233 8895 4127 8895 4449 8895 233 8896 4449 8896 4450 8896 4450 8897 4449 8897 4126 8897 4450 8898 4126 8898 231 8898 4458 8899 4451 8899 4453 8899 4453 8900 4451 8900 4452 8900 4452 8901 4454 8901 4453 8901 4453 8902 4454 8902 4120 8902 4453 8903 4120 8903 4433 8903 4455 8904 4131 8904 234 8904 234 8905 4131 8905 4130 8905 234 8906 4130 8906 233 8906 233 8907 4130 8907 4456 8907 233 8908 4456 8908 4448 8908 4126 8909 4125 8909 231 8909 231 8910 4125 8910 4457 8910 231 8911 4457 8911 4458 8911 4458 8912 4457 8912 4123 8912 4458 8913 4123 8913 4451 8913 17075 8914 7647 8914 4459 8914 4459 8915 7647 8915 17074 8915 8473 8916 7648 8916 4460 8916 4460 8917 7648 8917 17063 8917 4460 8918 17063 8918 4461 8918 4461 8919 17063 8919 17059 8919 17059 8920 4462 8920 4461 8920 4461 8921 4462 8921 4465 8921 4461 8922 4465 8922 8471 8922 4463 8923 4464 8923 4465 8923 4465 8924 4464 8924 8468 8924 4465 8925 8468 8925 8471 8925 4466 8926 4467 8926 4463 8926 4463 8927 4467 8927 4468 8927 4463 8928 4468 8928 4464 8928 4469 8929 15571 8929 4470 8929 4469 8930 4470 8930 4839 8930 4839 8931 4470 8931 14419 8931 4839 8932 14419 8932 4840 8932 4471 8933 4474 8933 4476 8933 4471 8934 4476 8934 4472 8934 4472 8935 4476 8935 9749 8935 4472 8936 9749 8936 15386 8936 4475 8937 4473 8937 4804 8937 4475 8938 4476 8938 4500 8938 4500 8939 4476 8939 4474 8939 4500 8940 4474 8940 4499 8940 4475 8941 4804 8941 4476 8941 4476 8942 4804 8942 9754 8942 4476 8943 9754 8943 9749 8943 4477 8944 4796 8944 4478 8944 4478 8945 4796 8945 4795 8945 4478 8946 4795 8946 4817 8946 4817 8947 4795 8947 4793 8947 4817 8948 4793 8948 4479 8948 4479 8949 4793 8949 4799 8949 4479 8950 4799 8950 4480 8950 4480 8951 4799 8951 4806 8951 4485 8952 14644 8952 16805 8952 16805 8953 4481 8953 4487 8953 15386 8954 4487 8954 4472 8954 4472 8955 4487 8955 4481 8955 4472 8956 4481 8956 4471 8956 15386 8957 15387 8957 4487 8957 4487 8958 15387 8958 15389 8958 4487 8959 15389 8959 4489 8959 4489 8960 15389 8960 4482 8960 4489 8961 4482 8961 15390 8961 4483 8962 4489 8962 4484 8962 4484 8963 4489 8963 15390 8963 4484 8964 15390 8964 15391 8964 5172 8965 4485 8965 4486 8965 4486 8966 4485 8966 16805 8966 4486 8967 16805 8967 4488 8967 4488 8968 16805 8968 4487 8968 4488 8969 4487 8969 4490 8969 4490 8970 4487 8970 4489 8970 4490 8971 4489 8971 15410 8971 15410 8972 4489 8972 4483 8972 4497 8973 16683 8973 4495 8973 16692 8974 4491 8974 4493 8974 16692 8975 4493 8975 4492 8975 4492 8976 4493 8976 4494 8976 4492 8977 4494 8977 16681 8977 16681 8978 4494 8978 4496 8978 16681 8979 4496 8979 4495 8979 4495 8980 4496 8980 14369 8980 4495 8981 14369 8981 4497 8981 16787 8982 4498 8982 4499 8982 4499 8983 4498 8983 4738 8983 4499 8984 4738 8984 4500 8984 4499 8985 16804 8985 16787 8985 16787 8986 16804 8986 16803 8986 16787 8987 16803 8987 4501 8987 4501 8988 16803 8988 14646 8988 4501 8989 14646 8989 16794 8989 14440 8990 14441 8990 4503 8990 14440 8991 4503 8991 14435 8991 14441 8992 14504 8992 4503 8992 4503 8993 14504 8993 4502 8993 4503 8994 4502 8994 4516 8994 4827 8995 14532 8995 4503 8995 4503 8996 14532 8996 4504 8996 4503 8997 4504 8997 4505 8997 4505 8998 14533 8998 4503 8998 4503 8999 14533 8999 14436 8999 4503 9000 14436 9000 14435 9000 4506 9001 4507 9001 6742 9001 6742 9002 4507 9002 17051 9002 4506 9003 15603 9003 4507 9003 4507 9004 15603 9004 15599 9004 4507 9005 15599 9005 15595 9005 15595 9006 4508 9006 4507 9006 4507 9007 4508 9007 15596 9007 4507 9008 15596 9008 4510 9008 4503 9009 4509 9009 4827 9009 4827 9010 4509 9010 4507 9010 4827 9011 4507 9011 4829 9011 4829 9012 4507 9012 4510 9012 4829 9013 4510 9013 4830 9013 4511 9014 4512 9014 17051 9014 17051 9015 4512 9015 6744 9015 17051 9016 6744 9016 6742 9016 4511 9017 17051 9017 6743 9017 6743 9018 17051 9018 4513 9018 6743 9019 4513 9019 4515 9019 4526 9020 4528 9020 4513 9020 4513 9021 4528 9021 4514 9021 4513 9022 4514 9022 4515 9022 4502 9023 6125 9023 4516 9023 4516 9024 6125 9024 4518 9024 4516 9025 4518 9025 4517 9025 4517 9026 4518 9026 4519 9026 4517 9027 4519 9027 4520 9027 4520 9028 4519 9028 4521 9028 4520 9029 4521 9029 17055 9029 17055 9030 4521 9030 6129 9030 17055 9031 6129 9031 4522 9031 4522 9032 6129 9032 6132 9032 4522 9033 6132 9033 4523 9033 4523 9034 6132 9034 4524 9034 4523 9035 4524 9035 17048 9035 17048 9036 4524 9036 6121 9036 17048 9037 6121 9037 17049 9037 17049 9038 6121 9038 4525 9038 17049 9039 4525 9039 4526 9039 4526 9040 4525 9040 4527 9040 4526 9041 4527 9041 4528 9041 4528 9042 4527 9042 8393 9042 4528 9043 8393 9043 8129 9043 6128 9044 4530 9044 4529 9044 4529 9045 4530 9045 15651 9045 4529 9046 15651 9046 4531 9046 4532 9047 8278 9047 4535 9047 4533 9048 4543 9048 6226 9048 4533 9049 6226 9049 4536 9049 4536 9050 6226 9050 4534 9050 4536 9051 4534 9051 6227 9051 8135 9052 4532 9052 6214 9052 6214 9053 4532 9053 4535 9053 6214 9054 4535 9054 6213 9054 6213 9055 4535 9055 4536 9055 6213 9056 4536 9056 6228 9056 6228 9057 4536 9057 6227 9057 17042 9058 4837 9058 4540 9058 4540 9059 4837 9059 4842 9059 4540 9060 4842 9060 4538 9060 4541 9061 4537 9061 4540 9061 4538 9062 4539 9062 4540 9062 4540 9063 4539 9063 15583 9063 4540 9064 15583 9064 4541 9064 4537 9065 15581 9065 4540 9065 4540 9066 15581 9066 4542 9066 4540 9067 4542 9067 4533 9067 4533 9068 4542 9068 4888 9068 4533 9069 4888 9069 4543 9069 4547 9070 4545 9070 4544 9070 4544 9071 14498 9071 4547 9071 4547 9072 14498 9072 4835 9072 4547 9073 4835 9073 17042 9073 17042 9074 4835 9074 4834 9074 17042 9075 4834 9075 4837 9075 4845 9076 4548 9076 4547 9076 4845 9077 4547 9077 4556 9077 14453 9078 4545 9078 4546 9078 4546 9079 4545 9079 4547 9079 4546 9080 4547 9080 14464 9080 14464 9081 4547 9081 4548 9081 8278 9082 4862 9082 4535 9082 4535 9083 4862 9083 4863 9083 4535 9084 4863 9084 17045 9084 17045 9085 4863 9085 4550 9085 17045 9086 4550 9086 4549 9086 4549 9087 4550 9087 4865 9087 4549 9088 4865 9088 17039 9088 17039 9089 4865 9089 4857 9089 17039 9090 4857 9090 4551 9090 4551 9091 4857 9091 4552 9091 4551 9092 4552 9092 4553 9092 4553 9093 4552 9093 4554 9093 4553 9094 4554 9094 4555 9094 4555 9095 4554 9095 4843 9095 4555 9096 4843 9096 17040 9096 17040 9097 4843 9097 4556 9097 17040 9098 4556 9098 17041 9098 17041 9099 4556 9099 4547 9099 4861 9100 15488 9100 4557 9100 4557 9101 15488 9101 4558 9101 4557 9102 4558 9102 15506 9102 14622 9103 5217 9103 4559 9103 14622 9104 14620 9104 5217 9104 5217 9105 14620 9105 14655 9105 5217 9106 14655 9106 4568 9106 4568 9107 14655 9107 4569 9107 4559 9108 9688 9108 14622 9108 14622 9109 9688 9109 4560 9109 14622 9110 4560 9110 4561 9110 4561 9111 9686 9111 14622 9111 14622 9112 9686 9112 4657 9112 4564 9113 7134 9113 7132 9113 7138 9114 4565 9114 4562 9114 4562 9115 4565 9115 4563 9115 4562 9116 4563 9116 4574 9116 7138 9117 4564 9117 4565 9117 4565 9118 4564 9118 7132 9118 4565 9119 7132 9119 4566 9119 4566 9120 7132 9120 4568 9120 4566 9121 4568 9121 4567 9121 4567 9122 4568 9122 4569 9122 4563 9123 4570 9123 4574 9123 4574 9124 4570 9124 14626 9124 4574 9125 14626 9125 4576 9125 4576 9126 14626 9126 4571 9126 4576 9127 4571 9127 4572 9127 4572 9128 4571 9128 4573 9128 4572 9129 4573 9129 4629 9129 9683 9130 9685 9130 4575 9130 4575 9131 9685 9131 4574 9131 4575 9132 4574 9132 4763 9132 4763 9133 4574 9133 4576 9133 16678 9134 4616 9134 16676 9134 16676 9135 4616 9135 4577 9135 4582 9136 4578 9136 16665 9136 16665 9137 4578 9137 9770 9137 16665 9138 9770 9138 4579 9138 4579 9139 4580 9139 16665 9139 16665 9140 4580 9140 14366 9140 16665 9141 14366 9141 16664 9141 4588 9142 14672 9142 14613 9142 14668 9143 4587 9143 14669 9143 14669 9144 4587 9144 4581 9144 14669 9145 4581 9145 14670 9145 16665 9146 4583 9146 4582 9146 4582 9147 4583 9147 4584 9147 4582 9148 4584 9148 4588 9148 4588 9149 4584 9149 4585 9149 4588 9150 4585 9150 14672 9150 14670 9151 4581 9151 4586 9151 4586 9152 4581 9152 5260 9152 4586 9153 5260 9153 14613 9153 4577 9154 9767 9154 9765 9154 14668 9155 16676 9155 4587 9155 4587 9156 16676 9156 4577 9156 4587 9157 4577 9157 9764 9157 9764 9158 4577 9158 9765 9158 5257 9159 4588 9159 5258 9159 5258 9160 4588 9160 14613 9160 5258 9161 14613 9161 5259 9161 5259 9162 14613 9162 5260 9162 9855 9163 16672 9163 14625 9163 4598 9164 14621 9164 4592 9164 7378 9165 4589 9165 14625 9165 4589 9166 9857 9166 4594 9166 4590 9167 4591 9167 4764 9167 4764 9168 4591 9168 9862 9168 4592 9169 16671 9169 4764 9169 4592 9170 4764 9170 4598 9170 4598 9171 4764 9171 9862 9171 4598 9172 9862 9172 4593 9172 14625 9173 4589 9173 9855 9173 9855 9174 4589 9174 4594 9174 9855 9175 4594 9175 4595 9175 14653 9176 14654 9176 4596 9176 14654 9177 4597 9177 4596 9177 4596 9178 4597 9178 14657 9178 4596 9179 14657 9179 4598 9179 4598 9180 14657 9180 14656 9180 4598 9181 14656 9181 14621 9181 4596 9182 7383 9182 14653 9182 14653 9183 7383 9183 7385 9183 14653 9184 7385 9184 7382 9184 14625 9185 14652 9185 7378 9185 7378 9186 14652 9186 14653 9186 7378 9187 14653 9187 7379 9187 7379 9188 14653 9188 7382 9188 4599 9189 16127 9189 16663 9189 16663 9190 16127 9190 4600 9190 4601 9191 4602 9191 4604 9191 4601 9192 5139 9192 4602 9192 4602 9193 5139 9193 4603 9193 4602 9194 4603 9194 5136 9194 4609 9195 14673 9195 5145 9195 4604 9196 4605 9196 4601 9196 4601 9197 4605 9197 4606 9197 4601 9198 4606 9198 14671 9198 5145 9199 14673 9199 9870 9199 9870 9200 14673 9200 14674 9200 9870 9201 14674 9201 14617 9201 5136 9202 5124 9202 4602 9202 4602 9203 5124 9203 4607 9203 4602 9204 4607 9204 9867 9204 9867 9205 14410 9205 4602 9205 4602 9206 14410 9206 4625 9206 4602 9207 4625 9207 4608 9207 4600 9208 9872 9208 9871 9208 5143 9209 4601 9209 5144 9209 5144 9210 4601 9210 14671 9210 5144 9211 14671 9211 5145 9211 5145 9212 14671 9212 14614 9212 5145 9213 14614 9213 4609 9213 14617 9214 16663 9214 9870 9214 9870 9215 16663 9215 4600 9215 9870 9216 4600 9216 4610 9216 4610 9217 4600 9217 9871 9217 14388 9218 14637 9218 4611 9218 4611 9219 14637 9219 4612 9219 4611 9220 4612 9220 4613 9220 4613 9221 4612 9221 4614 9221 4613 9222 4614 9222 14391 9222 14391 9223 4614 9223 4671 9223 4616 9224 16678 9224 16677 9224 16677 9225 16645 9225 4615 9225 16677 9226 4615 9226 4616 9226 4616 9227 4615 9227 16657 9227 4616 9228 16657 9228 14364 9228 14364 9229 16657 9229 16658 9229 14364 9230 16658 9230 4709 9230 4617 9231 14612 9231 4618 9231 4618 9232 16636 9232 4617 9232 4617 9233 16636 9233 4619 9233 4617 9234 4619 9234 16677 9234 16677 9235 4619 9235 4620 9235 16677 9236 4620 9236 16645 9236 14611 9237 14610 9237 4621 9237 4621 9238 14610 9238 16675 9238 4621 9239 16675 9239 4622 9239 16674 9240 4608 9240 4625 9240 4622 9241 16675 9241 4623 9241 4623 9242 16675 9242 16674 9242 4623 9243 16674 9243 16623 9243 16623 9244 16674 9244 4625 9244 16623 9245 4625 9245 4624 9245 4624 9246 4625 9246 14411 9246 4624 9247 14411 9247 16626 9247 4626 9248 9536 9248 14411 9248 14411 9249 9536 9249 4627 9249 14411 9250 4627 9250 16626 9250 15977 9251 4628 9251 15979 9251 15979 9252 4628 9252 4629 9252 15979 9253 4629 9253 4634 9253 4634 9254 4629 9254 4632 9254 4759 9255 4712 9255 15975 9255 15975 9256 4712 9256 4628 9256 15975 9257 4628 9257 4630 9257 4630 9258 4628 9258 15977 9258 4637 9259 4631 9259 4632 9259 4632 9260 4631 9260 4633 9260 4632 9261 4633 9261 4634 9261 15989 9262 15988 9262 4635 9262 4635 9263 15988 9263 4636 9263 4635 9264 4636 9264 4637 9264 4637 9265 4636 9265 15986 9265 4637 9266 15986 9266 4631 9266 15950 9267 15945 9267 4765 9267 15952 9268 15954 9268 4638 9268 4640 9269 16673 9269 4639 9269 4639 9270 15951 9270 4640 9270 4640 9271 15951 9271 4641 9271 4640 9272 4641 9272 4638 9272 4638 9273 4641 9273 4642 9273 4638 9274 4642 9274 15952 9274 4765 9275 15945 9275 4643 9275 4643 9276 15945 9276 4644 9276 4643 9277 4644 9277 16673 9277 16673 9278 4644 9278 15942 9278 16673 9279 15942 9279 4639 9279 9570 9280 4645 9280 4765 9280 4765 9281 4645 9281 15948 9281 4765 9282 15948 9282 15950 9282 4647 9283 4646 9283 16535 9283 4647 9284 16535 9284 16671 9284 16671 9285 16535 9285 16534 9285 16671 9286 16534 9286 4648 9286 4648 9287 16534 9287 16533 9287 4648 9288 16533 9288 9568 9288 4649 9289 16670 9289 14624 9289 14624 9290 4650 9290 4649 9290 4649 9291 4650 9291 16518 9291 4649 9292 16518 9292 4647 9292 4647 9293 16518 9293 16520 9293 4647 9294 16520 9294 4646 9294 16543 9295 14623 9295 16548 9295 16548 9296 14623 9296 4655 9296 4651 9297 16555 9297 4657 9297 4657 9298 16555 9298 4652 9298 4657 9299 4652 9299 4653 9299 4653 9300 4652 9300 4654 9300 4653 9301 4654 9301 4655 9301 4655 9302 4654 9302 4656 9302 4655 9303 4656 9303 16548 9303 4761 9304 4711 9304 4657 9304 4657 9305 4711 9305 16556 9305 4657 9306 16556 9306 4651 9306 4658 9307 4660 9307 12969 9307 5725 9308 12931 9308 15771 9308 15771 9309 12931 9309 12956 9309 15771 9310 12956 9310 15769 9310 15769 9311 12956 9311 4659 9311 15769 9312 4659 9312 15768 9312 12969 9313 4660 9313 4661 9313 4661 9314 4660 9314 15765 9314 4661 9315 15765 9315 4659 9315 4659 9316 15765 9316 4662 9316 4659 9317 4662 9317 15768 9317 12981 9318 4664 9318 12969 9318 12969 9319 4664 9319 15764 9319 12969 9320 15764 9320 4658 9320 4674 9321 4672 9321 4663 9321 4663 9322 4672 9322 4664 9322 4663 9323 4664 9323 12980 9323 12980 9324 4664 9324 12981 9324 15730 9325 15731 9325 4665 9325 4672 9326 4612 9326 14637 9326 5183 9327 14663 9327 4666 9327 5183 9328 4666 9328 4670 9328 4667 9329 15726 9329 4668 9329 15739 9330 15737 9330 4669 9330 4669 9331 15735 9331 15739 9331 15739 9332 15735 9332 15730 9332 15739 9333 15730 9333 5183 9333 5183 9334 15730 9334 4665 9334 5183 9335 4665 9335 14663 9335 4666 9336 14659 9336 4670 9336 4670 9337 14659 9337 14658 9337 4670 9338 14658 9338 7267 9338 7267 9339 14658 9339 4671 9339 7267 9340 4671 9340 4676 9340 14637 9341 15733 9341 4672 9341 4672 9342 15733 9342 4673 9342 4672 9343 4673 9343 4668 9343 4668 9344 4673 9344 15728 9344 4668 9345 15728 9345 4667 9345 4612 9346 4672 9346 4614 9346 4614 9347 4672 9347 4674 9347 4614 9348 4674 9348 4671 9348 4671 9349 4674 9349 4675 9349 4671 9350 4675 9350 4676 9350 14395 9351 15714 9351 4677 9351 4677 9352 15714 9352 14629 9352 15723 9353 15724 9353 14631 9353 14631 9354 15724 9354 4678 9354 14631 9355 4678 9355 4679 9355 14387 9356 14630 9356 4679 9356 14387 9357 4679 9357 4678 9357 4686 9358 9548 9358 4680 9358 4680 9359 9548 9359 4681 9359 4680 9360 4681 9360 4682 9360 4682 9361 4681 9361 9549 9361 4682 9362 9549 9362 4683 9362 4683 9363 9549 9363 9550 9363 4683 9364 9550 9364 4684 9364 4684 9365 9550 9365 4685 9365 4684 9366 4685 9366 16098 9366 4686 9367 14579 9367 9548 9367 9548 9368 14579 9368 15897 9368 15897 9369 14579 9369 4687 9369 4687 9370 14579 9370 4688 9370 4687 9371 4688 9371 4689 9371 4689 9372 4688 9372 14580 9372 4689 9373 14580 9373 4690 9373 4690 9374 14580 9374 4691 9374 4690 9375 4691 9375 15900 9375 15900 9376 4691 9376 4692 9376 15900 9377 4692 9377 15901 9377 4695 9378 4693 9378 4694 9378 4695 9379 4694 9379 4696 9379 4696 9380 4694 9380 4697 9380 4696 9381 4697 9381 4698 9381 4698 9382 4697 9382 14547 9382 4698 9383 14547 9383 15895 9383 4699 9384 4700 9384 14547 9384 14547 9385 4700 9385 15894 9385 14547 9386 15894 9386 15895 9386 4699 9387 4701 9387 4700 9387 4700 9388 4701 9388 4720 9388 4720 9389 4701 9389 4721 9389 4721 9390 4701 9390 14571 9390 4721 9391 14571 9391 4703 9391 4703 9392 14571 9392 4702 9392 4703 9393 4702 9393 4704 9393 4704 9394 4702 9394 4705 9394 4704 9395 4705 9395 4725 9395 4725 9396 4705 9396 14573 9396 4725 9397 14573 9397 16045 9397 15838 9398 15836 9398 4718 9398 4723 9399 16460 9399 4700 9399 4758 9400 4731 9400 4742 9400 4711 9401 4707 9401 4749 9401 15994 9402 4707 9402 15981 9402 15981 9403 4707 9403 4711 9403 15981 9404 4711 9404 4736 9404 15994 9405 4706 9405 4707 9405 4707 9406 4706 9406 4739 9406 4707 9407 4739 9407 4708 9407 4709 9408 16089 9408 16088 9408 4710 9409 16404 9409 4709 9409 4709 9410 16404 9410 4726 9410 4761 9411 4712 9411 4711 9411 4711 9412 4712 9412 4759 9412 4713 9413 15982 9413 4711 9413 15838 9414 4718 9414 4719 9414 16059 9415 16066 9415 4726 9415 4710 9416 16212 9416 16404 9416 16404 9417 16212 9417 4727 9417 16404 9418 4727 9418 4714 9418 4714 9419 4727 9419 4715 9419 4730 9420 4716 9420 14635 9420 4741 9421 4717 9421 4718 9421 4718 9422 4717 9422 15837 9422 4718 9423 15837 9423 4719 9423 4700 9424 4720 9424 4723 9424 4723 9425 4720 9425 4721 9425 4723 9426 4721 9426 4703 9426 16088 9427 16087 9427 4709 9427 4709 9428 16087 9428 4722 9428 4709 9429 4722 9429 14364 9429 4726 9430 4723 9430 16059 9430 16059 9431 4723 9431 4703 9431 16059 9432 4703 9432 4724 9432 4724 9433 4703 9433 4704 9433 4724 9434 4704 9434 4725 9434 16066 9435 16057 9435 4726 9435 4726 9436 16057 9436 16091 9436 4726 9437 16091 9437 4709 9437 4709 9438 16091 9438 16090 9438 4709 9439 16090 9439 16089 9439 4727 9440 16802 9440 16801 9440 14635 9441 4728 9441 4730 9441 4730 9442 4728 9442 4729 9442 4730 9443 4729 9443 4731 9443 4731 9444 4729 9444 16591 9444 4731 9445 16591 9445 4742 9445 4742 9446 16591 9446 4732 9446 4752 9447 4733 9447 4711 9447 4711 9448 4733 9448 15980 9448 4711 9449 15980 9449 4713 9449 15982 9450 4734 9450 4711 9450 4711 9451 4734 9451 4735 9451 4711 9452 4735 9452 4736 9452 4741 9453 15966 9453 15965 9453 16504 9454 16505 9454 16802 9454 16505 9455 4737 9455 16802 9455 16802 9456 4737 9456 16506 9456 16802 9457 16506 9457 4738 9457 4738 9458 16506 9458 16513 9458 4738 9459 16513 9459 4500 9459 4500 9460 16513 9460 4475 9460 4739 9461 15996 9461 4708 9461 4708 9462 15996 9462 4740 9462 4708 9463 4740 9463 4741 9463 4741 9464 4740 9464 15958 9464 4741 9465 15958 9465 15966 9465 4732 9466 16590 9466 4742 9466 4742 9467 16590 9467 16589 9467 4742 9468 16589 9468 16588 9468 16588 9469 16587 9469 4742 9469 4742 9470 16587 9470 4744 9470 4742 9471 4744 9471 4743 9471 4743 9472 4744 9472 4745 9472 4743 9473 4745 9473 16408 9473 16408 9474 4745 9474 4746 9474 16408 9475 4746 9475 4747 9475 4747 9476 4746 9476 16162 9476 4747 9477 16162 9477 16409 9477 16409 9478 16162 9478 16163 9478 16409 9479 16163 9479 16411 9479 16411 9480 16163 9480 4748 9480 16411 9481 4748 9481 4749 9481 4749 9482 4748 9482 16167 9482 4749 9483 16167 9483 4711 9483 15965 9484 15964 9484 4741 9484 4741 9485 15964 9485 15961 9485 4741 9486 15961 9486 15959 9486 15978 9487 4750 9487 4711 9487 4711 9488 4750 9488 4751 9488 4711 9489 4751 9489 4752 9489 4727 9490 16502 9490 16802 9490 16802 9491 16502 9491 4753 9491 16802 9492 4753 9492 16504 9492 16783 9493 4754 9493 4755 9493 15959 9494 4756 9494 4741 9494 4741 9495 4756 9495 4757 9495 4741 9496 4757 9496 4717 9496 16801 9497 16800 9497 4727 9497 4727 9498 16800 9498 16783 9498 4727 9499 16783 9499 4715 9499 4715 9500 16783 9500 4755 9500 4715 9501 4755 9501 16407 9501 16407 9502 4755 9502 16785 9502 16407 9503 16785 9503 4742 9503 4742 9504 16785 9504 16786 9504 4742 9505 16786 9505 4758 9505 4759 9506 15974 9506 4711 9506 4711 9507 15974 9507 15976 9507 4711 9508 15976 9508 15978 9508 4628 9509 4712 9509 4760 9509 4760 9510 4712 9510 4761 9510 4760 9511 4761 9511 4762 9511 4762 9512 4761 9512 4657 9512 4762 9513 4657 9513 9686 9513 4629 9514 4628 9514 4572 9514 4572 9515 4628 9515 4760 9515 4572 9516 4760 9516 4576 9516 4576 9517 4760 9517 4763 9517 4764 9518 16671 9518 9858 9518 9858 9519 16671 9519 4648 9519 9858 9520 4648 9520 4766 9520 4766 9521 4648 9521 9570 9521 4766 9522 9570 9522 4765 9522 4765 9523 4643 9523 4766 9523 4766 9524 4643 9524 16672 9524 4766 9525 16672 9525 9855 9525 16604 9526 16581 9526 16148 9526 16148 9527 16581 9527 16176 9527 16148 9528 16176 9528 4767 9528 4767 9529 16176 9529 16177 9529 4767 9530 16177 9530 4768 9530 4768 9531 16177 9531 4769 9531 4768 9532 4769 9532 4770 9532 4770 9533 4769 9533 16179 9533 4770 9534 16179 9534 4771 9534 4771 9535 16179 9535 4772 9535 4771 9536 4772 9536 16150 9536 16150 9537 4772 9537 16200 9537 16150 9538 16200 9538 4773 9538 4773 9539 16200 9539 4774 9539 4773 9540 4774 9540 16152 9540 16152 9541 4774 9541 4775 9541 16152 9542 4775 9542 4776 9542 4776 9543 4775 9543 4777 9543 4776 9544 4777 9544 4778 9544 4778 9545 4777 9545 4779 9545 16042 9546 16115 9546 16116 9546 16042 9547 16116 9547 4780 9547 4780 9548 16116 9548 4781 9548 4780 9549 4781 9549 16072 9549 16225 9550 16209 9550 16226 9550 16226 9551 16209 9551 4782 9551 16226 9552 4782 9552 16220 9552 16220 9553 4782 9553 4783 9553 16220 9554 4783 9554 16221 9554 16221 9555 4783 9555 16213 9555 16221 9556 16213 9556 16608 9556 16608 9557 16213 9557 16214 9557 16709 9558 16775 9558 4784 9558 4784 9559 16775 9559 16776 9559 4784 9560 16776 9560 4785 9560 4785 9561 16776 9561 4786 9561 4785 9562 4786 9562 16700 9562 16700 9563 4786 9563 16778 9563 16700 9564 16778 9564 4787 9564 4787 9565 16778 9565 16774 9565 4787 9566 16774 9566 4789 9566 4789 9567 16774 9567 4788 9567 4789 9568 4788 9568 16659 9568 16659 9569 4788 9569 16788 9569 4790 9570 14667 9570 4803 9570 4803 9571 14667 9571 4791 9571 4803 9572 4791 9572 4792 9572 4798 9573 4793 9573 4794 9573 4794 9574 4793 9574 4795 9574 4794 9575 4795 9575 4796 9575 4800 9576 4797 9576 9746 9576 5170 9577 4806 9577 4798 9577 4798 9578 4806 9578 4799 9578 4798 9579 4799 9579 4793 9579 9746 9580 9748 9580 4800 9580 4800 9581 9748 9581 4794 9581 4800 9582 4794 9582 14340 9582 14340 9583 4794 9583 4796 9583 14340 9584 4796 9584 14645 9584 9752 9585 4801 9585 9750 9585 9750 9586 4801 9586 4802 9586 9750 9587 4802 9587 4803 9587 4803 9588 4802 9588 9754 9588 4803 9589 9754 9589 4790 9589 4790 9590 9754 9590 4804 9590 4790 9591 4804 9591 4473 9591 4791 9592 14665 9592 4792 9592 4792 9593 14665 9593 4805 9593 4792 9594 4805 9594 4807 9594 4807 9595 4805 9595 4806 9595 4807 9596 4806 9596 4808 9596 4808 9597 4806 9597 5170 9597 4808 9598 5170 9598 5168 9598 9832 9599 16806 9599 4477 9599 4818 9600 9839 9600 4478 9600 14647 9601 14664 9601 5110 9601 5110 9602 14664 9602 4809 9602 5110 9603 4809 9603 4815 9603 4815 9604 4809 9604 4810 9604 4815 9605 4810 9605 14666 9605 9835 9606 9833 9606 9837 9606 9837 9607 9833 9607 9832 9607 9837 9608 9832 9608 9839 9608 9839 9609 9832 9609 4477 9609 9839 9610 4477 9610 4478 9610 4811 9611 4812 9611 9844 9611 9844 9612 4812 9612 4813 9612 9844 9613 4813 9613 4814 9613 4814 9614 4813 9614 4815 9614 4814 9615 4815 9615 4816 9615 4816 9616 4815 9616 14666 9616 4478 9617 4817 9617 4818 9617 4818 9618 4817 9618 4479 9618 4818 9619 4479 9619 5103 9619 5103 9620 4479 9620 4480 9620 5103 9621 4480 9621 5105 9621 5105 9622 4480 9622 5107 9622 14647 9623 5110 9623 4480 9623 4480 9624 5110 9624 5108 9624 4480 9625 5108 9625 5107 9625 4819 9626 14529 9626 7445 9626 5929 9627 5930 9627 14526 9627 5929 9628 14526 9628 4820 9628 4820 9629 14526 9629 4821 9629 4820 9630 4821 9630 5938 9630 4819 9631 7445 9631 4821 9631 4821 9632 7445 9632 5939 9632 4821 9633 5939 9633 5938 9633 5650 9634 4823 9634 4822 9634 4822 9635 4823 9635 14488 9635 4822 9636 14488 9636 14476 9636 5650 9637 5648 9637 4823 9637 4823 9638 5648 9638 5647 9638 4823 9639 5647 9639 14482 9639 14482 9640 5647 9640 4824 9640 14482 9641 4824 9641 7205 9641 14605 9642 14534 9642 14542 9642 14532 9643 4827 9643 14539 9643 14539 9644 4827 9644 4825 9644 4829 9645 4826 9645 4827 9645 4827 9646 4826 9646 14605 9646 4827 9647 14605 9647 4825 9647 4825 9648 14605 9648 14542 9648 14608 9649 4826 9649 4828 9649 4828 9650 4826 9650 4829 9650 4828 9651 4829 9651 14417 9651 14417 9652 4829 9652 4830 9652 14417 9653 4830 9653 14418 9653 14418 9654 4830 9654 14502 9654 4831 9655 14499 9655 4830 9655 4830 9656 14499 9656 14500 9656 4830 9657 14500 9657 14502 9657 4832 9658 4836 9658 4833 9658 4833 9659 4836 9659 14495 9659 4834 9660 4835 9660 14493 9660 14493 9661 14495 9661 4834 9661 4834 9662 14495 9662 4836 9662 4834 9663 4836 9663 4837 9663 4837 9664 4836 9664 14425 9664 4837 9665 14425 9665 4838 9665 4838 9666 4469 9666 4837 9666 4837 9667 4469 9667 4839 9667 4837 9668 4839 9668 4842 9668 4842 9669 4839 9669 4840 9669 14423 9670 4841 9670 14422 9670 14422 9671 4841 9671 4842 9671 14422 9672 4842 9672 14420 9672 14420 9673 4842 9673 4840 9673 4855 9674 17038 9674 4856 9674 14472 9675 14465 9675 14416 9675 14416 9676 14465 9676 14469 9676 14416 9677 14469 9677 4860 9677 4843 9678 4859 9678 4556 9678 4556 9679 4859 9679 4844 9679 4556 9680 4844 9680 4845 9680 4846 9681 4847 9681 4848 9681 4848 9682 4847 9682 17021 9682 4848 9683 17021 9683 8313 9683 8313 9684 17021 9684 4849 9684 8313 9685 4849 9685 4850 9685 4850 9686 4849 9686 17020 9686 4850 9687 17020 9687 8303 9687 8303 9688 17020 9688 4851 9688 8303 9689 4851 9689 4852 9689 4852 9690 4851 9690 17017 9690 4852 9691 17017 9691 4854 9691 4854 9692 17017 9692 4853 9692 4854 9693 4853 9693 8296 9693 8296 9694 4853 9694 17016 9694 8296 9695 17016 9695 8294 9695 8294 9696 17016 9696 4855 9696 8294 9697 4855 9697 8284 9697 8284 9698 4855 9698 4856 9698 4865 9699 4867 9699 4857 9699 4857 9700 4867 9700 4858 9700 4857 9701 4858 9701 4552 9701 14469 9702 4859 9702 4860 9702 4860 9703 4859 9703 4843 9703 4860 9704 4843 9704 8137 9704 8137 9705 4843 9705 4554 9705 8137 9706 4554 9706 4557 9706 4557 9707 4554 9707 4552 9707 4557 9708 4552 9708 4861 9708 4861 9709 4552 9709 4858 9709 8278 9710 4856 9710 4862 9710 4862 9711 4856 9711 4863 9711 17038 9712 17037 9712 4856 9712 4856 9713 17037 9713 17036 9713 4856 9714 17036 9714 4863 9714 17031 9715 4550 9715 17032 9715 17032 9716 4550 9716 4863 9716 17032 9717 4863 9717 17034 9717 17034 9718 4863 9718 17036 9718 17031 9719 17030 9719 4550 9719 4550 9720 17030 9720 4864 9720 4550 9721 4864 9721 4865 9721 4865 9722 4864 9722 17028 9722 4865 9723 17028 9723 17027 9723 4846 9724 8149 9724 4847 9724 4847 9725 8149 9725 8147 9725 4847 9726 8147 9726 17022 9726 17022 9727 8147 9727 8146 9727 17022 9728 8146 9728 4871 9728 4871 9729 8146 9729 15481 9729 17027 9730 4866 9730 4865 9730 4865 9731 4866 9731 17025 9731 4865 9732 17025 9732 4867 9732 4867 9733 17025 9733 4869 9733 4867 9734 4869 9734 4868 9734 4868 9735 4869 9735 4871 9735 4868 9736 4871 9736 4870 9736 4870 9737 4871 9737 15481 9737 14035 9738 14040 9738 14292 9738 4888 9739 4542 9739 15589 9739 15574 9740 4877 9740 4882 9740 4885 9741 4928 9741 4872 9741 14334 9742 4879 9742 4873 9742 4873 9743 4879 9743 4874 9743 4873 9744 4874 9744 4875 9744 4875 9745 4874 9745 15559 9745 4876 9746 4882 9746 14336 9746 14336 9747 4882 9747 4877 9747 14336 9748 4877 9748 14334 9748 14334 9749 4877 9749 4878 9749 14334 9750 4878 9750 4879 9750 14185 9751 6533 9751 14167 9751 14167 9752 6533 9752 4880 9752 14167 9753 4880 9753 4881 9753 4881 9754 4880 9754 4883 9754 4881 9755 4883 9755 4887 9755 4887 9756 4883 9756 14318 9756 4876 9757 14323 9757 4882 9757 4882 9758 14323 9758 14316 9758 4882 9759 14316 9759 4880 9759 4880 9760 14316 9760 14317 9760 4880 9761 14317 9761 4883 9761 14035 9762 14292 9762 14030 9762 14030 9763 14292 9763 6553 9763 14030 9764 6553 9764 4884 9764 14040 9765 4885 9765 14292 9765 14292 9766 4885 9766 4872 9766 14292 9767 4872 9767 14318 9767 14318 9768 4872 9768 4886 9768 14318 9769 4886 9769 4887 9769 15589 9770 15590 9770 4888 9770 4888 9771 15590 9771 15577 9771 4888 9772 15577 9772 4882 9772 4882 9773 15577 9773 15578 9773 4882 9774 15578 9774 15574 9774 4506 9775 6742 9775 15613 9775 15613 9776 6742 9776 4889 9776 6748 9777 4997 9777 4890 9777 4900 9778 10068 9778 4895 9778 4895 9779 10068 9779 4891 9779 4895 9780 4891 9780 4893 9780 4892 9781 15637 9781 4893 9781 4893 9782 15637 9782 4894 9782 4893 9783 4894 9783 4895 9783 4895 9784 4894 9784 15627 9784 4895 9785 15627 9785 15630 9785 10162 9786 10168 9786 10054 9786 4890 9787 10393 9787 6748 9787 6748 9788 10393 9788 10417 9788 6748 9789 10417 9789 4896 9789 4896 9790 10417 9790 4897 9790 4896 9791 4898 9791 6748 9791 6748 9792 4898 9792 10049 9792 6748 9793 10049 9793 4895 9793 4895 9794 10049 9794 4899 9794 4895 9795 4899 9795 4900 9795 15630 9796 15614 9796 4895 9796 4895 9797 15614 9797 4901 9797 4895 9798 4901 9798 6742 9798 6742 9799 4901 9799 4902 9799 6742 9800 4902 9800 4889 9800 5087 9801 10162 9801 10399 9801 10399 9802 10162 9802 10054 9802 10399 9803 10054 9803 10418 9803 10418 9804 10054 9804 4897 9804 10418 9805 4897 9805 4903 9805 4903 9806 4897 9806 10417 9806 10194 9807 6275 9807 10173 9807 10173 9808 6275 9808 10054 9808 10173 9809 10054 9809 10172 9809 10172 9810 10054 9810 10168 9810 4904 9811 15683 9811 4906 9811 4906 9812 15683 9812 4905 9812 4905 9813 15677 9813 4906 9813 4906 9814 15677 9814 4530 9814 4906 9815 4530 9815 6128 9815 14416 9816 15519 9816 14472 9816 14472 9817 15519 9817 4907 9817 14472 9818 4907 9818 14478 9818 14478 9819 4907 9819 4908 9819 14478 9820 4908 9820 14475 9820 15526 9821 4822 9821 4908 9821 4908 9822 4822 9822 14476 9822 4908 9823 14476 9823 14475 9823 4921 9824 8887 9824 17079 9824 17079 9825 8887 9825 8886 9825 17079 9826 8886 9826 17080 9826 17080 9827 8886 9827 8885 9827 17080 9828 8885 9828 17081 9828 17081 9829 8885 9829 4910 9829 17081 9830 4910 9830 4909 9830 4909 9831 4910 9831 4912 9831 4909 9832 4912 9832 4911 9832 4911 9833 4912 9833 8896 9833 4911 9834 8896 9834 4913 9834 4913 9835 8896 9835 8894 9835 4913 9836 8894 9836 4915 9836 4915 9837 8894 9837 4914 9837 4915 9838 4914 9838 17085 9838 17085 9839 4914 9839 8890 9839 17085 9840 8890 9840 17086 9840 17086 9841 8890 9841 4916 9841 17086 9842 4916 9842 4917 9842 4917 9843 4916 9843 4918 9843 4917 9844 4918 9844 4919 9844 4919 9845 4918 9845 4920 9845 4919 9846 4920 9846 4921 9846 4921 9847 4920 9847 8887 9847 4927 9848 14174 9848 4975 9848 14211 9849 4922 9849 6518 9849 6518 9850 4922 9850 6520 9850 6520 9851 4922 9851 4923 9851 4923 9852 4922 9852 4924 9852 4923 9853 4924 9853 4925 9853 4925 9854 4924 9854 14212 9854 4925 9855 14212 9855 4975 9855 4975 9856 14212 9856 4926 9856 4975 9857 4926 9857 4927 9857 4930 9858 4931 9858 13967 9858 4885 9859 14000 9859 4928 9859 4928 9860 14000 9860 13997 9860 4928 9861 13997 9861 4929 9861 13997 9862 13998 9862 4929 9862 4929 9863 13998 9863 13992 9863 4929 9864 13992 9864 4930 9864 4930 9865 13992 9865 13969 9865 4930 9866 13969 9866 4931 9866 13980 9867 4996 9867 13972 9867 13972 9868 4996 9868 4932 9868 13972 9869 4932 9869 13967 9869 13967 9870 4932 9870 14113 9870 13967 9871 14113 9871 4930 9871 4996 9872 13980 9872 13982 9872 14148 9873 4985 9873 4982 9873 13785 9874 13758 9874 7095 9874 13366 9875 13331 9875 13179 9875 13179 9876 13331 9876 4941 9876 7075 9877 13378 9877 7077 9877 13179 9878 4933 9878 13366 9878 13366 9879 4933 9879 13218 9879 13366 9880 13218 9880 13365 9880 13365 9881 13218 9881 13225 9881 13365 9882 13225 9882 13370 9882 13370 9883 13225 9883 13255 9883 13370 9884 13255 9884 13378 9884 13378 9885 13255 9885 7078 9885 13378 9886 7078 9886 7077 9886 13564 9887 13555 9887 4940 9887 4934 9888 13395 9888 4935 9888 13572 9889 4951 9889 4950 9889 13564 9890 4940 9890 4936 9890 4936 9891 4940 9891 13464 9891 4936 9892 13464 9892 13594 9892 13594 9893 13464 9893 13459 9893 13594 9894 13459 9894 13599 9894 13599 9895 13459 9895 13458 9895 13599 9896 13458 9896 4938 9896 4938 9897 13458 9897 4937 9897 4938 9898 4937 9898 13484 9898 4939 9899 13546 9899 4960 9899 4960 9900 13680 9900 4939 9900 4939 9901 13680 9901 13674 9901 4939 9902 13674 9902 13554 9902 13554 9903 13674 9903 4934 9903 13554 9904 4934 9904 13555 9904 13555 9905 4934 9905 4935 9905 13555 9906 4935 9906 4940 9906 13331 9907 13313 9907 4941 9907 4941 9908 13313 9908 13312 9908 4941 9909 13312 9909 4942 9909 4942 9910 13312 9910 13311 9910 4942 9911 13311 9911 13451 9911 13451 9912 13311 9912 4943 9912 13451 9913 4943 9913 4944 9913 4944 9914 4943 9914 4946 9914 4944 9915 4946 9915 4945 9915 4945 9916 4946 9916 13293 9916 4945 9917 13293 9917 4947 9917 4947 9918 13293 9918 13269 9918 4947 9919 13269 9919 4948 9919 4948 9920 13269 9920 13270 9920 4948 9921 13270 9921 4949 9921 4949 9922 13270 9922 13262 9922 4949 9923 13262 9923 13483 9923 13483 9924 13262 9924 4950 9924 13483 9925 4950 9925 13484 9925 13484 9926 4950 9926 4951 9926 13484 9927 4951 9927 4938 9927 4952 9928 4959 9928 4958 9928 4955 9929 7089 9929 4956 9929 13803 9930 4963 9930 13681 9930 13681 9931 4963 9931 13688 9931 13681 9932 13717 9932 13803 9932 13803 9933 13717 9933 13716 9933 13803 9934 13716 9934 4953 9934 4953 9935 13716 9935 13723 9935 4953 9936 13723 9936 13722 9936 4954 9937 4955 9937 13502 9937 13502 9938 4955 9938 4956 9938 13502 9939 4956 9939 4957 9939 4957 9940 4956 9940 4953 9940 4957 9941 4953 9941 4958 9941 4958 9942 4953 9942 13722 9942 4958 9943 13722 9943 4952 9943 4959 9944 13707 9944 4958 9944 4958 9945 13707 9945 13702 9945 4958 9946 13702 9946 13527 9946 13527 9947 13702 9947 13691 9947 13527 9948 13691 9948 13526 9948 13526 9949 13691 9949 4960 9949 13526 9950 4960 9950 13545 9950 13545 9951 4960 9951 13546 9951 13850 9952 13839 9952 6930 9952 4961 9953 13824 9953 13672 9953 13819 9954 4962 9954 13824 9954 13824 9955 4962 9955 13858 9955 13824 9956 13858 9956 13672 9956 13672 9957 13858 9957 13669 9957 4963 9958 13800 9958 13688 9958 13688 9959 13800 9959 13831 9959 13688 9960 13831 9960 13672 9960 13672 9961 13831 9961 13827 9961 13672 9962 13827 9962 4961 9962 13669 9963 6930 9963 13668 9963 13668 9964 6930 9964 13621 9964 13669 9965 13858 9965 6930 9965 6930 9966 13858 9966 13849 9966 6930 9967 13849 9967 13850 9967 13819 9968 4964 9968 4962 9968 4962 9969 4964 9969 4965 9969 4962 9970 4965 9970 13881 9970 13881 9971 4965 9971 4966 9971 13881 9972 4966 9972 4967 9972 4967 9973 4966 9973 13793 9973 4967 9974 13793 9974 4978 9974 4978 9975 13793 9975 13794 9975 4978 9976 13794 9976 7095 9976 7095 9977 13794 9977 4968 9977 7095 9978 4968 9978 13785 9978 13959 9979 13958 9979 4982 9979 13959 9980 4982 9980 4969 9980 6925 9981 13925 9981 4982 9981 4982 9982 13925 9982 13953 9982 4982 9983 13953 9983 4969 9983 14156 9984 4970 9984 4972 9984 14156 9985 4972 9985 4971 9985 4971 9986 4972 9986 4973 9986 4971 9987 4973 9987 14174 9987 14174 9988 4973 9988 4974 9988 14174 9989 4974 9989 4975 9989 4974 9990 13916 9990 4975 9990 4975 9991 13916 9991 13898 9991 4975 9992 13898 9992 7094 9992 7094 9993 13898 9993 4976 9993 7094 9994 4976 9994 7095 9994 7095 9995 4976 9995 4977 9995 7095 9996 4977 9996 4978 9996 14156 9997 14155 9997 4970 9997 4970 9998 14155 9998 4979 9998 4970 9999 4979 9999 4980 9999 4980 10000 4979 10000 14148 10000 4980 10001 14148 10001 4981 10001 4981 10002 14148 10002 4982 10002 4981 10003 4982 10003 13945 10003 13945 10004 4982 10004 13958 10004 14014 10005 4982 10005 4983 10005 4983 10006 4982 10006 4985 10006 4983 10007 4985 10007 4984 10007 4984 10008 4985 10008 4993 10008 4984 10009 4993 10009 13982 10009 14014 10010 14011 10010 4982 10010 4982 10011 14011 10011 4986 10011 4982 10012 4986 10012 4987 10012 4987 10013 4986 10013 4988 10013 4988 10014 4989 10014 4987 10014 4987 10015 4989 10015 4991 10015 4987 10016 4991 10016 4990 10016 4990 10017 4991 10017 14043 10017 4990 10018 14043 10018 4992 10018 4993 10019 4994 10019 13982 10019 13982 10020 4994 10020 4995 10020 13982 10021 4995 10021 4996 10021 4996 10022 4995 10022 14118 10022 4996 10023 14118 10023 4932 10023 4998 10024 4890 10024 4997 10024 4998 10025 4997 10025 10352 10025 4997 10026 4999 10026 10352 10026 10352 10027 4999 10027 6770 10027 10352 10028 6770 10028 5000 10028 5000 10029 6770 10029 10354 10029 10304 10030 10303 10030 5004 10030 5018 10031 5019 10031 10470 10031 5018 10032 10470 10032 5001 10032 10465 10033 10255 10033 10467 10033 10467 10034 10255 10034 5001 10034 10467 10035 5001 10035 10468 10035 10468 10036 5001 10036 10470 10036 10303 10037 5002 10037 5004 10037 5004 10038 5002 10038 5003 10038 5004 10039 5003 10039 5005 10039 10465 10040 10459 10040 10255 10040 10255 10041 10459 10041 10458 10041 10255 10042 10458 10042 10279 10042 10279 10043 10458 10043 5006 10043 10279 10044 5006 10044 5005 10044 5005 10045 5006 10045 5007 10045 5005 10046 5007 10046 5004 10046 5007 10047 5008 10047 5004 10047 5004 10048 5008 10048 5009 10048 5004 10049 5009 10049 10536 10049 10536 10050 10519 10050 5004 10050 5004 10051 10519 10051 5010 10051 5004 10052 5010 10052 5011 10052 5011 10053 5012 10053 5004 10053 5004 10054 5012 10054 5013 10054 5004 10055 5013 10055 10510 10055 5018 10056 6488 10056 10580 10056 6359 10057 10424 10057 5014 10057 5014 10058 10424 10058 10428 10058 5014 10059 10428 10059 5015 10059 10635 10060 10634 10060 5016 10060 5016 10061 10634 10061 5037 10061 5016 10062 5037 10062 10759 10062 10580 10063 10582 10063 5018 10063 5018 10064 10582 10064 5017 10064 5018 10065 5017 10065 5019 10065 5019 10066 5017 10066 5021 10066 5019 10067 5021 10067 5020 10067 5020 10068 5021 10068 5022 10068 5021 10069 5023 10069 5022 10069 5022 10070 5023 10070 10648 10070 5022 10071 10648 10071 10435 10071 10435 10072 10648 10072 10643 10072 10435 10073 10643 10073 10649 10073 10737 10074 5014 10074 10751 10074 10751 10075 5014 10075 5015 10075 10751 10076 5015 10076 10760 10076 10760 10077 5015 10077 10435 10077 10760 10078 10435 10078 5016 10078 5016 10079 10435 10079 10649 10079 5016 10080 10649 10080 10635 10080 10696 10081 10619 10081 5024 10081 5024 10082 10619 10082 5029 10082 5024 10083 5029 10083 5025 10083 5025 10084 5029 10084 5026 10084 5025 10085 5026 10085 10710 10085 6421 10086 10812 10086 5028 10086 5027 10087 6421 10087 10596 10087 10596 10088 6421 10088 5028 10088 10596 10089 5028 10089 5029 10089 5029 10090 5028 10090 5030 10090 5029 10091 5030 10091 5026 10091 10696 10092 5031 10092 10619 10092 10619 10093 5031 10093 5032 10093 10619 10094 5032 10094 5033 10094 5033 10095 5032 10095 5034 10095 5033 10096 5034 10096 5035 10096 5035 10097 5034 10097 10759 10097 5035 10098 10759 10098 5036 10098 5036 10099 10759 10099 5037 10099 5041 10100 5039 10100 5038 10100 5038 10101 5039 10101 5040 10101 5038 10102 5040 10102 5026 10102 5026 10103 5040 10103 10715 10103 5026 10104 10715 10104 10710 10104 5038 10105 5042 10105 5041 10105 5041 10106 5042 10106 5043 10106 5041 10107 5043 10107 5044 10107 5045 10108 10655 10108 5044 10108 5043 10109 10861 10109 5044 10109 5044 10110 10861 10110 10856 10110 5044 10111 10856 10111 5045 10111 5045 10112 10856 10112 5046 10112 5045 10113 5046 10113 5055 10113 5050 10114 5047 10114 10931 10114 10931 10115 5047 10115 6427 10115 10931 10116 6427 10116 5062 10116 5062 10117 6427 10117 11070 10117 5062 10118 11070 10118 5061 10118 10989 10119 5045 10119 5048 10119 5048 10120 5045 10120 5055 10120 5048 10121 5055 10121 10998 10121 10998 10122 5055 10122 5054 10122 10829 10123 5047 10123 5050 10123 10829 10124 5050 10124 5049 10124 5049 10125 5050 10125 5051 10125 5049 10126 5051 10126 5052 10126 5052 10127 5051 10127 5053 10127 5052 10128 5053 10128 10839 10128 10839 10129 5053 10129 10960 10129 10839 10130 10960 10130 10845 10130 10845 10131 10960 10131 5054 10131 10845 10132 5054 10132 10848 10132 10848 10133 5054 10133 5055 10133 11112 10134 5056 10134 5058 10134 11112 10135 5058 10135 5057 10135 5057 10136 5058 10136 5059 10136 5057 10137 5059 10137 11082 10137 11082 10138 5059 10138 5060 10138 11082 10139 5060 10139 11089 10139 11089 10140 5060 10140 10912 10140 11089 10141 10912 10141 5061 10141 5061 10142 10912 10142 10949 10142 5061 10143 10949 10143 5062 10143 11078 10144 5065 10144 5063 10144 11078 10145 5063 10145 5064 10145 5064 10146 5063 10146 11200 10146 5064 10147 11200 10147 11097 10147 11212 10148 5063 10148 6441 10148 6441 10149 5063 10149 5065 10149 6441 10150 5065 10150 11061 10150 11200 10151 11165 10151 11097 10151 11097 10152 11165 10152 5066 10152 11097 10153 5066 10153 5068 10153 11112 10154 11106 10154 5056 10154 5056 10155 11106 10155 11103 10155 5056 10156 11103 10156 6349 10156 6349 10157 11103 10157 11102 10157 6349 10158 11102 10158 5067 10158 5067 10159 11102 10159 5068 10159 5067 10160 5068 10160 11162 10160 11162 10161 5068 10161 5066 10161 6265 10162 10205 10162 6291 10162 6291 10163 10205 10163 5069 10163 6291 10164 5069 10164 6290 10164 6290 10165 5069 10165 10182 10165 6290 10166 10182 10166 5004 10166 5004 10167 10182 10167 5070 10167 5004 10168 5070 10168 5071 10168 5072 10169 5080 10169 5073 10169 5073 10170 5080 10170 10345 10170 5071 10171 10181 10171 5004 10171 5004 10172 10181 10172 10178 10172 5004 10173 10178 10173 10304 10173 10304 10174 10178 10174 10177 10174 10304 10175 10177 10175 5074 10175 5074 10176 10177 10176 5075 10176 5074 10177 5075 10177 10322 10177 10322 10178 5075 10178 5076 10178 10322 10179 5076 10179 5072 10179 5072 10180 5076 10180 5077 10180 5072 10181 5077 10181 5080 10181 5080 10182 5077 10182 5078 10182 10345 10183 5080 10183 5079 10183 5079 10184 5080 10184 5078 10184 5079 10185 5078 10185 5081 10185 5081 10186 5078 10186 10126 10186 5081 10187 10126 10187 10371 10187 10371 10188 10126 10188 5082 10188 5082 10189 5083 10189 10371 10189 10371 10190 5083 10190 5085 10190 10371 10191 5085 10191 5084 10191 5084 10192 5085 10192 5086 10192 5085 10193 10146 10193 5086 10193 5086 10194 10146 10194 5088 10194 5086 10195 5088 10195 5087 10195 5087 10196 5088 10196 10144 10196 5087 10197 10144 10197 10162 10197 9839 10198 4818 10198 5089 10198 5089 10199 4818 10199 5090 10199 15114 10200 10665 10200 5091 10200 5091 10201 10665 10201 5955 10201 5091 10202 5955 10202 5954 10202 15118 10203 5093 10203 5090 10203 15114 10204 15116 10204 10665 10204 10665 10205 15116 10205 15115 10205 10665 10206 15115 10206 5090 10206 5090 10207 15115 10207 5092 10207 5090 10208 5092 10208 15118 10208 5093 10209 5094 10209 5090 10209 5090 10210 5094 10210 5095 10210 5090 10211 5095 10211 5089 10211 15096 10212 5096 10212 5097 10212 5097 10213 5096 10213 15095 10213 5097 10214 15095 10214 5099 10214 5099 10215 15095 10215 5098 10215 5099 10216 5098 10216 9411 10216 5110 10217 4815 10217 5111 10217 5111 10218 4815 10218 9842 10218 5111 10219 9842 10219 15090 10219 15090 10220 5100 10220 5111 10220 5111 10221 5100 10221 5101 10221 5111 10222 5101 10222 5097 10222 5097 10223 5101 10223 5102 10223 5097 10224 5102 10224 15096 10224 4818 10225 5103 10225 5090 10225 5090 10226 5103 10226 10717 10226 10717 10227 5103 10227 5104 10227 5104 10228 5103 10228 5105 10228 5104 10229 5105 10229 10707 10229 10707 10230 5105 10230 5106 10230 5106 10231 5105 10231 5107 10231 5106 10232 5107 10232 10702 10232 10702 10233 5107 10233 5108 10233 10702 10234 5108 10234 10704 10234 10704 10235 5108 10235 5109 10235 5109 10236 5108 10236 5110 10236 5109 10237 5110 10237 5111 10237 14371 10238 5112 10238 15109 10238 14371 10239 15109 10239 14370 10239 14370 10240 15109 10240 9840 10240 14370 10241 9840 10241 9843 10241 10199 10242 5113 10242 10193 10242 10193 10243 5113 10243 5119 10243 15043 10244 10176 10244 5114 10244 5114 10245 10176 10245 5115 10245 5114 10246 5115 10246 5116 10246 5116 10247 5115 10247 10175 10247 5116 10248 10175 10248 5117 10248 5117 10249 10175 10249 10191 10249 5117 10250 10191 10250 5119 10250 5119 10251 10191 10251 5118 10251 5119 10252 5118 10252 10193 10252 15043 10253 15048 10253 10176 10253 10176 10254 15048 10254 15047 10254 10176 10255 15047 10255 5120 10255 5120 10256 15047 10256 5121 10256 5120 10257 5121 10257 5123 10257 5123 10258 5121 10258 5122 10258 5123 10259 5122 10259 5125 10259 5124 10260 5136 10260 15049 10260 15049 10261 5136 10261 5123 10261 15049 10262 5123 10262 15050 10262 15050 10263 5123 10263 5125 10263 5902 10264 10246 10264 5903 10264 5903 10265 10246 10265 5126 10265 5903 10266 5126 10266 9333 10266 10250 10267 5134 10267 15028 10267 5126 10268 10244 10268 9333 10268 9333 10269 10244 10269 5127 10269 9333 10270 5127 10270 15025 10270 15025 10271 5127 10271 5128 10271 15025 10272 5128 10272 5129 10272 5129 10273 5128 10273 10243 10273 5129 10274 10243 10274 15023 10274 15023 10275 10243 10275 10242 10275 15023 10276 10242 10276 5130 10276 5130 10277 10242 10277 5131 10277 5130 10278 5131 10278 15024 10278 15024 10279 5131 10279 10250 10279 15024 10280 10250 10280 15029 10280 15029 10281 10250 10281 15028 10281 5145 10282 9870 10282 10169 10282 10169 10283 9870 10283 5133 10283 5132 10284 10220 10284 5133 10284 5133 10285 10220 10285 10219 10285 5133 10286 10219 10286 10169 10286 15027 10287 5134 10287 10250 10287 5132 10288 15031 10288 10220 10288 10220 10289 15031 10289 15032 10289 10220 10290 15032 10290 5135 10290 5135 10291 15032 10291 15027 10291 5135 10292 15027 10292 10208 10292 10208 10293 15027 10293 10250 10293 5137 10294 5123 10294 5136 10294 4603 10295 10150 10295 5136 10295 5136 10296 10150 10296 10124 10296 5136 10297 10124 10297 10130 10297 10130 10298 10128 10298 5136 10298 5136 10299 10128 10299 10155 10299 5136 10300 10155 10300 5137 10300 5138 10301 10135 10301 4601 10301 4601 10302 10135 10302 5139 10302 10135 10303 10143 10303 5139 10303 5139 10304 10143 10304 5140 10304 5139 10305 5140 10305 4603 10305 4603 10306 5140 10306 5141 10306 4603 10307 5141 10307 10150 10307 5138 10308 4601 10308 5142 10308 5142 10309 4601 10309 5143 10309 5142 10310 5143 10310 10161 10310 10161 10311 5143 10311 5144 10311 10161 10312 5144 10312 10160 10312 10160 10313 5144 10313 10158 10313 10158 10314 5144 10314 5145 10314 10158 10315 5145 10315 10169 10315 14412 10316 5146 10316 5147 10316 14412 10317 5147 10317 14413 10317 14413 10318 5147 10318 5148 10318 14413 10319 5148 10319 5149 10319 5156 10320 15399 10320 5155 10320 5155 10321 15399 10321 5150 10321 5155 10322 5150 10322 5656 10322 5656 10323 5150 10323 15400 10323 5656 10324 15400 10324 5151 10324 4798 10325 4794 10325 13692 10325 13692 10326 4794 10326 5152 10326 13692 10327 5152 10327 5153 10327 5153 10328 5154 10328 13692 10328 13692 10329 5154 10329 15402 10329 13692 10330 15402 10330 5155 10330 5155 10331 15402 10331 15401 10331 5155 10332 15401 10332 5156 10332 5157 10333 9489 10333 5159 10333 4803 10334 4792 10334 5158 10334 5158 10335 4792 10335 5163 10335 5157 10336 5159 10336 13685 10336 13685 10337 5159 10337 5160 10337 13685 10338 5160 10338 15385 10338 15385 10339 5161 10339 13685 10339 13685 10340 5161 10340 15378 10340 13685 10341 15378 10341 5163 10341 5163 10342 15378 10342 15382 10342 5163 10343 15382 10343 5162 10343 5162 10344 15380 10344 5163 10344 5163 10345 15380 10345 5164 10345 5163 10346 5164 10346 5158 10346 4792 10347 4807 10347 5163 10347 5163 10348 4807 10348 5165 10348 5165 10349 4807 10349 5166 10349 5166 10350 4807 10350 4808 10350 5166 10351 4808 10351 5167 10351 5167 10352 4808 10352 13712 10352 13712 10353 4808 10353 5168 10353 13712 10354 5168 10354 13713 10354 13713 10355 5168 10355 5170 10355 13713 10356 5170 10356 5171 10356 4798 10357 13692 10357 5170 10357 5170 10358 13692 10358 5169 10358 5170 10359 5169 10359 5171 10359 5172 10360 5173 10360 14339 10360 5172 10361 14339 10361 4485 10361 4485 10362 14339 10362 14338 10362 4485 10363 14338 10363 14644 10363 14344 10364 5174 10364 5175 10364 5175 10365 5174 10365 5176 10365 14862 10366 5177 10366 13207 10366 5177 10367 14870 10367 13207 10367 13207 10368 14870 10368 14863 10368 13207 10369 14863 10369 5748 10369 5748 10370 14863 10370 9431 10370 5748 10371 9431 10371 5749 10371 5176 10372 5178 10372 5175 10372 5175 10373 5178 10373 14866 10373 5175 10374 14866 10374 13207 10374 13207 10375 14866 10375 5179 10375 13207 10376 5179 10376 14862 10376 13215 10377 5767 10377 14835 10377 14843 10378 14842 10378 5180 10378 13215 10379 14835 10379 5180 10379 5180 10380 14835 10380 14844 10380 5180 10381 14844 10381 14843 10381 14842 10382 14834 10382 5180 10382 5180 10383 14834 10383 14833 10383 5180 10384 14833 10384 5181 10384 5181 10385 14833 10385 5182 10385 5181 10386 5182 10386 14838 10386 14346 10387 14348 10387 9724 10387 9724 10388 14348 10388 5181 10388 9724 10389 5181 10389 14837 10389 14837 10390 5181 10390 14838 10390 5183 10391 4670 10391 5185 10391 5185 10392 4670 10392 5184 10392 5185 10393 5184 10393 5186 10393 12852 10394 5187 10394 5188 10394 12852 10395 5188 10395 5189 10395 12872 10396 12874 10396 5192 10396 5188 10397 5190 10397 5189 10397 5189 10398 5190 10398 5191 10398 5189 10399 5191 10399 12874 10399 12874 10400 5191 10400 15758 10400 12874 10401 15758 10401 5192 10401 5192 10402 15750 10402 12872 10402 12872 10403 15750 10403 5193 10403 12872 10404 5193 10404 5194 10404 5194 10405 5193 10405 5186 10405 5194 10406 5186 10406 5195 10406 5195 10407 5186 10407 5184 10407 9449 10408 9452 10408 5199 10408 15010 10409 15009 10409 5196 10409 5196 10410 15009 10410 15008 10410 5196 10411 15008 10411 5197 10411 5197 10412 15008 10412 5198 10412 5199 10413 12586 10413 9449 10413 9449 10414 12586 10414 5200 10414 9449 10415 5200 10415 15016 10415 15016 10416 5200 10416 5197 10416 15016 10417 5197 10417 15015 10417 15015 10418 5197 10418 5198 10418 12632 10419 5201 10419 5196 10419 5196 10420 5201 10420 5202 10420 5196 10421 5202 10421 15010 10421 14363 10422 14361 10422 12644 10422 12644 10423 14361 10423 5201 10423 12644 10424 5201 10424 12646 10424 12646 10425 5201 10425 12632 10425 5203 10426 14357 10426 9700 10426 9700 10427 14357 10427 7249 10427 5715 10428 5204 10428 5206 10428 5206 10429 5204 10429 5205 10429 5206 10430 5205 10430 12528 10430 12528 10431 5205 10431 14985 10431 12528 10432 14985 10432 5207 10432 5207 10433 14998 10433 12528 10433 12528 10434 14998 10434 5209 10434 12528 10435 5209 10435 5208 10435 5208 10436 5209 10436 14987 10436 14987 10437 5210 10437 5208 10437 5208 10438 5210 10438 14996 10438 5208 10439 14996 10439 12524 10439 12524 10440 14996 10440 9700 10440 12524 10441 9700 10441 12575 10441 12575 10442 9700 10442 7249 10442 9877 10443 5211 10443 5212 10443 5212 10444 5211 10444 5213 10444 5212 10445 5213 10445 9941 10445 9941 10446 5213 10446 5214 10446 9941 10447 5214 10447 9942 10447 5214 10448 14752 10448 9942 10448 9942 10449 14752 10449 5215 10449 9942 10450 5215 10450 5216 10450 5216 10451 14740 10451 9942 10451 9942 10452 14740 10452 14748 10452 9942 10453 14748 10453 5218 10453 5217 10454 4568 10454 9690 10454 9690 10455 4568 10455 10009 10455 9690 10456 10009 10456 14742 10456 14742 10457 10009 10457 5218 10457 14742 10458 5218 10458 14741 10458 14741 10459 5218 10459 14748 10459 10028 10460 5219 10460 5223 10460 4562 10461 4574 10461 5220 10461 5220 10462 4574 10462 5225 10462 5221 10463 14731 10463 5227 10463 5227 10464 14731 10464 5222 10464 5227 10465 5222 10465 5219 10465 5219 10466 5222 10466 14732 10466 5219 10467 14732 10467 5223 10467 10028 10468 5223 10468 10026 10468 10026 10469 5223 10469 9473 10469 10026 10470 9473 10470 5224 10470 5225 10471 14727 10471 5220 10471 5220 10472 14727 10472 5226 10472 5220 10473 5226 10473 5227 10473 5227 10474 5226 10474 14725 10474 5227 10475 14725 10475 5221 10475 14044 10476 5228 10476 5617 10476 5617 10477 5228 10477 5229 10477 15478 10478 5230 10478 5236 10478 5236 10479 5230 10479 5231 10479 5236 10480 5231 10480 14021 10480 14021 10481 5231 10481 5232 10481 14021 10482 5232 10482 5233 10482 5233 10483 5232 10483 9419 10483 5233 10484 9419 10484 5234 10484 5234 10485 9419 10485 5229 10485 5234 10486 5229 10486 14009 10486 14009 10487 5229 10487 5228 10487 14025 10488 4587 10488 15474 10488 15474 10489 4587 10489 9764 10489 15474 10490 15475 10490 14025 10490 14025 10491 15475 10491 5235 10491 14025 10492 5235 10492 14022 10492 14022 10493 5235 10493 5237 10493 14022 10494 5237 10494 5236 10494 5236 10495 5237 10495 15473 10495 5236 10496 15473 10496 15478 10496 15453 10497 5252 10497 5238 10497 14074 10498 5240 10498 5238 10498 5238 10499 5240 10499 5239 10499 5238 10500 5239 10500 15453 10500 14074 10501 5241 10501 5240 10501 5240 10502 5241 10502 5242 10502 5240 10503 5242 10503 5243 10503 5243 10504 5242 10504 14091 10504 5243 10505 14091 10505 15460 10505 15460 10506 14091 10506 5244 10506 15460 10507 5244 10507 5245 10507 5245 10508 5244 10508 5247 10508 5245 10509 5247 10509 9415 10509 14053 10510 9418 10510 5246 10510 5246 10511 9418 10511 9415 10511 5246 10512 9415 10512 14093 10512 14093 10513 9415 10513 5247 10513 14025 10514 13976 10514 4587 10514 4587 10515 13976 10515 13966 10515 4587 10516 13966 10516 13965 10516 13961 10517 4581 10517 5248 10517 5248 10518 4581 10518 4587 10518 5248 10519 4587 10519 5249 10519 5249 10520 4587 10520 13965 10520 9768 10521 4582 10521 4588 10521 4588 10522 5256 10522 9768 10522 9768 10523 5256 10523 5250 10523 9768 10524 5250 10524 5254 10524 5238 10525 5252 10525 5251 10525 5251 10526 5252 10526 15458 10526 5251 10527 15458 10527 5253 10527 5253 10528 15458 10528 5254 10528 5254 10529 15458 10529 5255 10529 5254 10530 5255 10530 9768 10530 5256 10531 4588 10531 14027 10531 14027 10532 4588 10532 5257 10532 5258 10533 14026 10533 5257 10533 5257 10534 14026 10534 14031 10534 5257 10535 14031 10535 14027 10535 13983 10536 14003 10536 5259 10536 5259 10537 14003 10537 14002 10537 5259 10538 14002 10538 5258 10538 5258 10539 14002 10539 14036 10539 5258 10540 14036 10540 14026 10540 13983 10541 5259 10541 5261 10541 5261 10542 5259 10542 5260 10542 5261 10543 5260 10543 13993 10543 13993 10544 5260 10544 13985 10544 13985 10545 5260 10545 4581 10545 13985 10546 4581 10546 13961 10546 15472 10547 5262 10547 14365 10547 15472 10548 14365 10548 15471 10548 15471 10549 14365 10549 14368 10549 15471 10550 14368 10550 15461 10550 5425 10551 5263 10551 5288 10551 12191 10552 5305 10552 5312 10552 5285 10553 5329 10553 5357 10553 5319 10554 7868 10554 7867 10554 5319 10555 7867 10555 5264 10555 5264 10556 7867 10556 5265 10556 5264 10557 5265 10557 16245 10557 16245 10558 5265 10558 5403 10558 16245 10559 5403 10559 16239 10559 7868 10560 5319 10560 5266 10560 5266 10561 5319 10561 5353 10561 5266 10562 5353 10562 7871 10562 7871 10563 5353 10563 5267 10563 7871 10564 5267 10564 7872 10564 7872 10565 5267 10565 5268 10565 7872 10566 5268 10566 7874 10566 7874 10567 5268 10567 5269 10567 5269 10568 5268 10568 5270 10568 5269 10569 5270 10569 7877 10569 7877 10570 5270 10570 5272 10570 7877 10571 5272 10571 7878 10571 7878 10572 5272 10572 5271 10572 5271 10573 5272 10573 5273 10573 5271 10574 5273 10574 5323 10574 5275 10575 5323 10575 5274 10575 5274 10576 5276 10576 5275 10576 5275 10577 5276 10577 9148 10577 5275 10578 9148 10578 5278 10578 5278 10579 9148 10579 5277 10579 5278 10580 5277 10580 5279 10580 5277 10581 5280 10581 5279 10581 5279 10582 5280 10582 5281 10582 5279 10583 5281 10583 5282 10583 5282 10584 5281 10584 5283 10584 5281 10585 5284 10585 5283 10585 5283 10586 5284 10586 9191 10586 5283 10587 9191 10587 7883 10587 7883 10588 9191 10588 9189 10588 7883 10589 9189 10589 5285 10589 5285 10590 9189 10590 5332 10590 5356 10591 7884 10591 5286 10591 5286 10592 7884 10592 5287 10592 7889 10593 7888 10593 5347 10593 5347 10594 7888 10594 7887 10594 5347 10595 7887 10595 5356 10595 5356 10596 7887 10596 7886 10596 5356 10597 7886 10597 7884 10597 7890 10598 5288 10598 5289 10598 5289 10599 5288 10599 5263 10599 5289 10600 5263 10600 7792 10600 7792 10601 5263 10601 5290 10601 5382 10602 5341 10602 5291 10602 5291 10603 5341 10603 6495 10603 6495 10604 5341 10604 5292 10604 5292 10605 5341 10605 5342 10605 5292 10606 5342 10606 5293 10606 5293 10607 5342 10607 5343 10607 5293 10608 5343 10608 5294 10608 5294 10609 5343 10609 5325 10609 5294 10610 5325 10610 5297 10610 9128 10611 5300 10611 5296 10611 5325 10612 5295 10612 9128 10612 9128 10613 5296 10613 5325 10613 5325 10614 5296 10614 6469 10614 5325 10615 6469 10615 5297 10615 9098 10616 6479 10616 5298 10616 5298 10617 6479 10617 6481 10617 5298 10618 6481 10618 5299 10618 5299 10619 6481 10619 5300 10619 5299 10620 5300 10620 9111 10620 9111 10621 5300 10621 9128 10621 5302 10622 9087 10622 5301 10622 12256 10623 6479 10623 12261 10623 12261 10624 6479 10624 9098 10624 12261 10625 9098 10625 12262 10625 12262 10626 9098 10626 9092 10626 12262 10627 9092 10627 12244 10627 12244 10628 9092 10628 5302 10628 12244 10629 5302 10629 12242 10629 12242 10630 5302 10630 5301 10630 12242 10631 5301 10631 5303 10631 5303 10632 5301 10632 9087 10632 5303 10633 9087 10633 5304 10633 5304 10634 9087 10634 9122 10634 5304 10635 9122 10635 5309 10635 5309 10636 9122 10636 5324 10636 5309 10637 5324 10637 5306 10637 5312 10638 5305 10638 5349 10638 5349 10639 5305 10639 5307 10639 5349 10640 5307 10640 5306 10640 5306 10641 5307 10641 5308 10641 5306 10642 5308 10642 5309 10642 5337 10643 5336 10643 5351 10643 5351 10644 5336 10644 5350 10644 5310 10645 12214 10645 5336 10645 12214 10646 12215 10646 5336 10646 5336 10647 12215 10647 12193 10647 5336 10648 12193 10648 5350 10648 5350 10649 12193 10649 5311 10649 5350 10650 5311 10650 5312 10650 5312 10651 5311 10651 12192 10651 5312 10652 12192 10652 12191 10652 6295 10653 5313 10653 5314 10653 5314 10654 5335 10654 6295 10654 6295 10655 5335 10655 5315 10655 6295 10656 5315 10656 6391 10656 5318 10657 16292 10657 16288 10657 5315 10658 5316 10658 6391 10658 6391 10659 5316 10659 5338 10659 6391 10660 5338 10660 5317 10660 5317 10661 5338 10661 5340 10661 16292 10662 5318 10662 16295 10662 16295 10663 5318 10663 5334 10663 16295 10664 5334 10664 16294 10664 5264 10665 5320 10665 5319 10665 5319 10666 5320 10666 5321 10666 5319 10667 5321 10667 16243 10667 5348 10668 9151 10668 5273 10668 5273 10669 9151 10669 5322 10669 5273 10670 5322 10670 5323 10670 5323 10671 5322 10671 9149 10671 5323 10672 9149 10672 5274 10672 9134 10673 5349 10673 9115 10673 9115 10674 5349 10674 5306 10674 9115 10675 5306 10675 9114 10675 9114 10676 5306 10676 5324 10676 5345 10677 9142 10677 5325 10677 5325 10678 9142 10678 9132 10678 5325 10679 9132 10679 5295 10679 5326 10680 5328 10680 5327 10680 5327 10681 5328 10681 5357 10681 5327 10682 5357 10682 9183 10682 9183 10683 5357 10683 5329 10683 9183 10684 5329 10684 5330 10684 5330 10685 5329 10685 5285 10685 5330 10686 5285 10686 5331 10686 5331 10687 5285 10687 5332 10687 5337 10688 5351 10688 5339 10688 5339 10689 5351 10689 5333 10689 5339 10690 5333 10690 5318 10690 5318 10691 5333 10691 5352 10691 5318 10692 5352 10692 5334 10692 5314 10693 5310 10693 5335 10693 5335 10694 5310 10694 5336 10694 5335 10695 5336 10695 5315 10695 5315 10696 5336 10696 5337 10696 5315 10697 5337 10697 5316 10697 5316 10698 5337 10698 5339 10698 5316 10699 5339 10699 5338 10699 5338 10700 5339 10700 5318 10700 5338 10701 5318 10701 5340 10701 5340 10702 5318 10702 16288 10702 5340 10703 16288 10703 5461 10703 5382 10704 5439 10704 5341 10704 5341 10705 5439 10705 5354 10705 5341 10706 5354 10706 5342 10706 5342 10707 5354 10707 5355 10707 5342 10708 5355 10708 5343 10708 5343 10709 5355 10709 5344 10709 5343 10710 5344 10710 5325 10710 5325 10711 5344 10711 5328 10711 5325 10712 5328 10712 5345 10712 5345 10713 5328 10713 5326 10713 5424 10714 5425 10714 5346 10714 5346 10715 5425 10715 5288 10715 5346 10716 5288 10716 5347 10716 5347 10717 5288 10717 7890 10717 5347 10718 7890 10718 7889 10718 9134 10719 5348 10719 5349 10719 5349 10720 5348 10720 5273 10720 5349 10721 5273 10721 5312 10721 5312 10722 5273 10722 5272 10722 5312 10723 5272 10723 5350 10723 5350 10724 5272 10724 5270 10724 5350 10725 5270 10725 5351 10725 5351 10726 5270 10726 5268 10726 5351 10727 5268 10727 5333 10727 5333 10728 5268 10728 5267 10728 5333 10729 5267 10729 5352 10729 5352 10730 5267 10730 5353 10730 5352 10731 5353 10731 5334 10731 5334 10732 5353 10732 5319 10732 5334 10733 5319 10733 16294 10733 16294 10734 5319 10734 16243 10734 5439 10735 5424 10735 5354 10735 5354 10736 5424 10736 5346 10736 5354 10737 5346 10737 5355 10737 5355 10738 5346 10738 5347 10738 5355 10739 5347 10739 5344 10739 5344 10740 5347 10740 5356 10740 5344 10741 5356 10741 5328 10741 5328 10742 5356 10742 5286 10742 5328 10743 5286 10743 5357 10743 5357 10744 5286 10744 5287 10744 5357 10745 5287 10745 5285 10745 9221 10746 9214 10746 5430 10746 5403 10747 5265 10747 5405 10747 7692 10748 5400 10748 5358 10748 5398 10749 5428 10749 5429 10749 5384 10750 5426 10750 5440 10750 10019 10751 10016 10751 5374 10751 5374 10752 10016 10752 5359 10752 5360 10753 5408 10753 10015 10753 9938 10754 5368 10754 5419 10754 6918 10755 5361 10755 5419 10755 5362 10756 5363 10756 5358 10756 5362 10757 5358 10757 16302 10757 5363 10758 16265 10758 5358 10758 5358 10759 16265 10759 16263 10759 5358 10760 16263 10760 16262 10760 5364 10761 16308 10761 7010 10761 7010 10762 16308 10762 5367 10762 7010 10763 5367 10763 5365 10763 6985 10764 5365 10764 5366 10764 5366 10765 5365 10765 5367 10765 5366 10766 5367 10766 5437 10766 5437 10767 5367 10767 16308 10767 5437 10768 16308 10768 16302 10768 6918 10769 5419 10769 6916 10769 6916 10770 5419 10770 5368 10770 6916 10771 5368 10771 6915 10771 9985 10772 5418 10772 5369 10772 5369 10773 5418 10773 5414 10773 5432 10774 9993 10774 5370 10774 5432 10775 5370 10775 5371 10775 5371 10776 5370 10776 9981 10776 5371 10777 9981 10777 9982 10777 10015 10778 5408 10778 5359 10778 5372 10779 5374 10779 5373 10779 5373 10780 5374 10780 5359 10780 5373 10781 5359 10781 9210 10781 9210 10782 5359 10782 5408 10782 9210 10783 5408 10783 9209 10783 9209 10784 5408 10784 9213 10784 5372 10785 9247 10785 5374 10785 5374 10786 9247 10786 5375 10786 5374 10787 5375 10787 10019 10787 9246 10788 10030 10788 9247 10788 9247 10789 10030 10789 10035 10789 9247 10790 10035 10790 5375 10790 9265 10791 9266 10791 5378 10791 9265 10792 5378 10792 5376 10792 5376 10793 5378 10793 5377 10793 5376 10794 5377 10794 9262 10794 9262 10795 5377 10795 7100 10795 9262 10796 7100 10796 9246 10796 9246 10797 7100 10797 6579 10797 9246 10798 6579 10798 10030 10798 5412 10799 7030 10799 5379 10799 9266 10800 9281 10800 5378 10800 5378 10801 9281 10801 5412 10801 5378 10802 5412 10802 7102 10802 7102 10803 5412 10803 5379 10803 5380 10804 5381 10804 5412 10804 5412 10805 5381 10805 7029 10805 5412 10806 7029 10806 7030 10806 5380 10807 5422 10807 5381 10807 5381 10808 5422 10808 5421 10808 5381 10809 5421 10809 7104 10809 7104 10810 5421 10810 5382 10810 7104 10811 5382 10811 5291 10811 7782 10812 5383 10812 5384 10812 5384 10813 5383 10813 7780 10813 5384 10814 7780 10814 5427 10814 7782 10815 5384 10815 5385 10815 5385 10816 5384 10816 5440 10816 5385 10817 5440 10817 7765 10817 7765 10818 5440 10818 5386 10818 7765 10819 5386 10819 5387 10819 5387 10820 5386 10820 5443 10820 5387 10821 5443 10821 5388 10821 5388 10822 5443 10822 5389 10822 5389 10823 5443 10823 5410 10823 5389 10824 5410 10824 7768 10824 7768 10825 5410 10825 5411 10825 7768 10826 5411 10826 5390 10826 9291 10827 9290 10827 5390 10827 5390 10828 9290 10828 7769 10828 9290 10829 9288 10829 7769 10829 7769 10830 9288 10830 9287 10830 7769 10831 9287 10831 5391 10831 9287 10832 5392 10832 5391 10832 5391 10833 5392 10833 5393 10833 5391 10834 5393 10834 7772 10834 7772 10835 5393 10835 5394 10835 7772 10836 5394 10836 7773 10836 7773 10837 5394 10837 5395 10837 5395 10838 5394 10838 9244 10838 5395 10839 9244 10839 7774 10839 7774 10840 9244 10840 9241 10840 7774 10841 9241 10841 5396 10841 5396 10842 9241 10842 5397 10842 5396 10843 5397 10843 7777 10843 5397 10844 5398 10844 7777 10844 7777 10845 5398 10845 5429 10845 7777 10846 5429 10846 7778 10846 7778 10847 5429 10847 5431 10847 7778 10848 5431 10848 7684 10848 7684 10849 5431 10849 5433 10849 7684 10850 5433 10850 7685 10850 7685 10851 5433 10851 7687 10851 7687 10852 5433 10852 5401 10852 7687 10853 5401 10853 5399 10853 5400 10854 7692 10854 5434 10854 5434 10855 7692 10855 5402 10855 5434 10856 5402 10856 5401 10856 5401 10857 5402 10857 7691 10857 5401 10858 7691 10858 5399 10858 16239 10859 5403 10859 5404 10859 5404 10860 5403 10860 5405 10860 5404 10861 5405 10861 16262 10861 16262 10862 5405 10862 5406 10862 16262 10863 5406 10863 5358 10863 5358 10864 5406 10864 5407 10864 5358 10865 5407 10865 7692 10865 9993 10866 5432 10866 5360 10866 5360 10867 5432 10867 5430 10867 5360 10868 5430 10868 5408 10868 5408 10869 5430 10869 9214 10869 5408 10870 9214 10870 9213 10870 5443 10871 5409 10871 5410 10871 5410 10872 5409 10872 9316 10872 5410 10873 9316 10873 5411 10873 5411 10874 9316 10874 9283 10874 5411 10875 9283 10875 5390 10875 5390 10876 9283 10876 9293 10876 5390 10877 9293 10877 9291 10877 9281 10878 9277 10878 5412 10878 5412 10879 9277 10879 9314 10879 5412 10880 9314 10880 9315 10880 5444 10881 5413 10881 9330 10881 9330 10882 5413 10882 5423 10882 9982 10883 5414 10883 5371 10883 5371 10884 5414 10884 5418 10884 5371 10885 5418 10885 5415 10885 5415 10886 5418 10886 5416 10886 5415 10887 5416 10887 5435 10887 5435 10888 5416 10888 5417 10888 5435 10889 5417 10889 5438 10889 9985 10890 9938 10890 5418 10890 5418 10891 9938 10891 5419 10891 5418 10892 5419 10892 5416 10892 5416 10893 5419 10893 5361 10893 5416 10894 5361 10894 5417 10894 5439 10895 5382 10895 5420 10895 5420 10896 5382 10896 5421 10896 5420 10897 5421 10897 5441 10897 5441 10898 5421 10898 5422 10898 5441 10899 5422 10899 5442 10899 5442 10900 5422 10900 5380 10900 5442 10901 5380 10901 5413 10901 5413 10902 5380 10902 5412 10902 5413 10903 5412 10903 5423 10903 5423 10904 5412 10904 9315 10904 5424 10905 5426 10905 5425 10905 5425 10906 5426 10906 5384 10906 5425 10907 5384 10907 5263 10907 5263 10908 5384 10908 5427 10908 5263 10909 5427 10909 5290 10909 5428 10910 9221 10910 5429 10910 5429 10911 9221 10911 5430 10911 5429 10912 5430 10912 5431 10912 5431 10913 5430 10913 5432 10913 5431 10914 5432 10914 5433 10914 5433 10915 5432 10915 5371 10915 5433 10916 5371 10916 5401 10916 5401 10917 5371 10917 5415 10917 5401 10918 5415 10918 5434 10918 5434 10919 5415 10919 5435 10919 5434 10920 5435 10920 5400 10920 5400 10921 5435 10921 5438 10921 5400 10922 5438 10922 5358 10922 5358 10923 5438 10923 5436 10923 5358 10924 5436 10924 16302 10924 16302 10925 5436 10925 5438 10925 16302 10926 5438 10926 5437 10926 5437 10927 5438 10927 5417 10927 5437 10928 5417 10928 5366 10928 5366 10929 5417 10929 5361 10929 5366 10930 5361 10930 6985 10930 6985 10931 5361 10931 6918 10931 5424 10932 5439 10932 5426 10932 5426 10933 5439 10933 5420 10933 5426 10934 5420 10934 5440 10934 5440 10935 5420 10935 5441 10935 5440 10936 5441 10936 5386 10936 5386 10937 5441 10937 5442 10937 5386 10938 5442 10938 5443 10938 5443 10939 5442 10939 5413 10939 5443 10940 5413 10940 5409 10940 5409 10941 5413 10941 5444 10941 16449 10942 16475 10942 6846 10942 5452 10943 5445 10943 5446 10943 5452 10944 5446 10944 5447 10944 5446 10945 5448 10945 5447 10945 5447 10946 5448 10946 16445 10946 5447 10947 16445 10947 6810 10947 6810 10948 16445 10948 16447 10948 6810 10949 16447 10949 5449 10949 5449 10950 16447 10950 16448 10950 5449 10951 16448 10951 6846 10951 6846 10952 16448 10952 5450 10952 6846 10953 5450 10953 16449 10953 16317 10954 5451 10954 6363 10954 6384 10955 5453 10955 5452 10955 5452 10956 5453 10956 5445 10956 16315 10957 16313 10957 5455 10957 5455 10958 16313 10958 5454 10958 5455 10959 5454 10959 6384 10959 6384 10960 5454 10960 16311 10960 6384 10961 16311 10961 5453 10961 5451 10962 16317 10962 5455 10962 5455 10963 16317 10963 16316 10963 5455 10964 16316 10964 16315 10964 5458 10965 5456 10965 6363 10965 6363 10966 5456 10966 5457 10966 6363 10967 5457 10967 16317 10967 6363 10968 6362 10968 5458 10968 5458 10969 6362 10969 5460 10969 5458 10970 5460 10970 5459 10970 5459 10971 5460 10971 5462 10971 5459 10972 5462 10972 5463 10972 5340 10973 5461 10973 6390 10973 6390 10974 5461 10974 16323 10974 5462 10975 6383 10975 5463 10975 5463 10976 6383 10976 6382 10976 5463 10977 6382 10977 16319 10977 16319 10978 6382 10978 5464 10978 16319 10979 5464 10979 16320 10979 16320 10980 5464 10980 6380 10980 16320 10981 6380 10981 16321 10981 16321 10982 6380 10982 6379 10982 16321 10983 6379 10983 16322 10983 16322 10984 6379 10984 6378 10984 16322 10985 6378 10985 5465 10985 5465 10986 6378 10986 5466 10986 5465 10987 5466 10987 16323 10987 16323 10988 5466 10988 6371 10988 16323 10989 6371 10989 6390 10989 5467 10990 9388 10990 5996 10990 5467 10991 5996 10991 5468 10991 5996 10992 12097 10992 5468 10992 5468 10993 12097 10993 12096 10993 5468 10994 12096 10994 14696 10994 14696 10995 12096 10995 12082 10995 14696 10996 12082 10996 5469 10996 5469 10997 12082 10997 5470 10997 5469 10998 5470 10998 5471 10998 14694 10999 5472 10999 5470 10999 5470 11000 5472 11000 14693 11000 5470 11001 14693 11001 5471 11001 5470 11002 5473 11002 14694 11002 14694 11003 5473 11003 5474 11003 14694 11004 5474 11004 12072 11004 5494 11005 5475 11005 5476 11005 5476 11006 5475 11006 14694 11006 5476 11007 14694 11007 12052 11007 12052 11008 14694 11008 12072 11008 11956 11009 11961 11009 7491 11009 7491 11010 11961 11010 5477 11010 7491 11011 5477 11011 5484 11011 14690 11012 5478 11012 5477 11012 5477 11013 5478 11013 9850 11013 5477 11014 9850 11014 5484 11014 5477 11015 5479 11015 14690 11015 14690 11016 5479 11016 11999 11016 14690 11017 11999 11017 5480 11017 5480 11018 11999 11018 11998 11018 5480 11019 11998 11019 5481 11019 5481 11020 11998 11020 11989 11020 5481 11021 11989 11021 5482 11021 5482 11022 11989 11022 12041 11022 5482 11023 12041 11023 9389 11023 9389 11024 12041 11024 5483 11024 9389 11025 5483 11025 6002 11025 5490 11026 7491 11026 5495 11026 5495 11027 7491 11027 5484 11027 5495 11028 5484 11028 5485 11028 5485 11029 9496 11029 5495 11029 5495 11030 9496 11030 9851 11030 5495 11031 9851 11031 9853 11031 5486 11032 5487 11032 5488 11032 5488 11033 5487 11033 7491 11033 5488 11034 7491 11034 5489 11034 5489 11035 7491 11035 5490 11035 7500 11036 5491 11036 5492 11036 5492 11037 5491 11037 5493 11037 5492 11038 5493 11038 5494 11038 5494 11039 5493 11039 5495 11039 5494 11040 5495 11040 5475 11040 5475 11041 5495 11041 9853 11041 9391 11042 5989 11042 5496 11042 5496 11043 5989 11043 12155 11043 5496 11044 12155 11044 14713 11044 14713 11045 12155 11045 5504 11045 4596 11046 4598 11046 5498 11046 5498 11047 4598 11047 5497 11047 5498 11048 5497 11048 5499 11048 5499 11049 5497 11049 5501 11049 5499 11050 5501 11050 5500 11050 5500 11051 5501 11051 5502 11051 5500 11052 5502 11052 14712 11052 14712 11053 5503 11053 5500 11053 5500 11054 5503 11054 14717 11054 5500 11055 14717 11055 5504 11055 5504 11056 14717 11056 5505 11056 5504 11057 5505 11057 14713 11057 4589 11058 7378 11058 5506 11058 5506 11059 7378 11059 12268 11059 12187 11060 5507 11060 5508 11060 5508 11061 5507 11061 5509 11061 5508 11062 5509 11062 5510 11062 5509 11063 5511 11063 5510 11063 5510 11064 5511 11064 5512 11064 5510 11065 5512 11065 12253 11065 12253 11066 5512 11066 14702 11066 12253 11067 14702 11067 14701 11067 14701 11068 14699 11068 12253 11068 12253 11069 14699 11069 14698 11069 12253 11070 14698 11070 12268 11070 12268 11071 14698 11071 5513 11071 12268 11072 5513 11072 5506 11072 11771 11073 5514 11073 5515 11073 5515 11074 5514 11074 5516 11074 5515 11075 5516 11075 5517 11075 5517 11076 5516 11076 5518 11076 5517 11077 5518 11077 11754 11077 5518 11078 5519 11078 11754 11078 11754 11079 5519 11079 5520 11079 11754 11080 5520 11080 5525 11080 5525 11081 5520 11081 15366 11081 5521 11082 14403 11082 5522 11082 5522 11083 14403 11083 5528 11083 5522 11084 5528 11084 5523 11084 5523 11085 5528 11085 5527 11085 15366 11086 5524 11086 5525 11086 5525 11087 5524 11087 5526 11087 5525 11088 5526 11088 11752 11088 11752 11089 5526 11089 5527 11089 11752 11090 5527 11090 11738 11090 11738 11091 5527 11091 5528 11091 15359 11092 9781 11092 5529 11092 5529 11093 9781 11093 14399 11093 5529 11094 14399 11094 5530 11094 5530 11095 14399 11095 14398 11095 9494 11096 9495 11096 14352 11096 9494 11097 14352 11097 15000 11097 15000 11098 14352 11098 5531 11098 15000 11099 5531 11099 5532 11099 14681 11100 12299 11100 5533 11100 5533 11101 12299 11101 12302 11101 5533 11102 12302 11102 9460 11102 9693 11103 5560 11103 5534 11103 5534 11104 5560 11104 5541 11104 5534 11105 5541 11105 5540 11105 5535 11106 5536 11106 5542 11106 5542 11107 5536 11107 5537 11107 5542 11108 5537 11108 14686 11108 14686 11109 5537 11109 5538 11109 14686 11110 5538 11110 14680 11110 14680 11111 5538 11111 5539 11111 14680 11112 5539 11112 14681 11112 14681 11113 5539 11113 12301 11113 14681 11114 12301 11114 12299 11114 5540 11115 5541 11115 5542 11115 5542 11116 5541 11116 12292 11116 5542 11117 12292 11117 5535 11117 12456 11118 5543 11118 5544 11118 12456 11119 5544 11119 12452 11119 12452 11120 5544 11120 5554 11120 12452 11121 5554 11121 5545 11121 14678 11122 14679 11122 5546 11122 5546 11123 14679 11123 5547 11123 5546 11124 5547 11124 12390 11124 12390 11125 5547 11125 5548 11125 12390 11126 5548 11126 12398 11126 12398 11127 5548 11127 12362 11127 12362 11128 5548 11128 5549 11128 12362 11129 5549 11129 9462 11129 14678 11130 5546 11130 14675 11130 14675 11131 5546 11131 5550 11131 14675 11132 5550 11132 5545 11132 5545 11133 5550 11133 5551 11133 5545 11134 5551 11134 12452 11134 7128 11135 5553 11135 5554 11135 5555 11136 7241 11136 5552 11136 5560 11137 9693 11137 5553 11137 5553 11138 9693 11138 5558 11138 5554 11139 5544 11139 7128 11139 7128 11140 5544 11140 5555 11140 7128 11141 5555 11141 5556 11141 5556 11142 5555 11142 5552 11142 9691 11143 5554 11143 5557 11143 5557 11144 5554 11144 5553 11144 5557 11145 5553 11145 9692 11145 9692 11146 5553 11146 5558 11146 7248 11147 7244 11147 5559 11147 5559 11148 7244 11148 5560 11148 5559 11149 5560 11149 7126 11149 7126 11150 5560 11150 5553 11150 14880 11151 5571 11151 5562 11151 5561 11152 14889 11152 14884 11152 5562 11153 12992 11153 14880 11153 14880 11154 12992 11154 12984 11154 14880 11155 12984 11155 14881 11155 14881 11156 12984 11156 5561 11156 14881 11157 5561 11157 14882 11157 14882 11158 5561 11158 14884 11158 13121 11159 5563 11159 7280 11159 13112 11160 13121 11160 5564 11160 5564 11161 13121 11161 7280 11161 5564 11162 7280 11162 9713 11162 14927 11163 5565 11163 5564 11163 5564 11164 5565 11164 13111 11164 5564 11165 13111 11165 13112 11165 14927 11166 14928 11166 5565 11166 5565 11167 14928 11167 5566 11167 5565 11168 5566 11168 5567 11168 5567 11169 5566 11169 14916 11169 5567 11170 14916 11170 14902 11170 7146 11171 5570 11171 9445 11171 9445 11172 5568 11172 7146 11172 7146 11173 5568 11173 9713 11173 7146 11174 9713 11174 5573 11174 5573 11175 9713 11175 7280 11175 5573 11176 7280 11176 5572 11176 5562 11177 5571 11177 5569 11177 5569 11178 5571 11178 7146 11178 5570 11179 7146 11179 9442 11179 9442 11180 7146 11180 5571 11180 9442 11181 5571 11181 9714 11181 5572 11182 7277 11182 5573 11182 5573 11183 7277 11183 5574 11183 5573 11184 5574 11184 7274 11184 7283 11185 7282 11185 7287 11185 7287 11186 7282 11186 5562 11186 7287 11187 5562 11187 5575 11187 5575 11188 5562 11188 5569 11188 5576 11189 14820 11189 5769 11189 5577 11190 13381 11190 5579 11190 5579 11191 13381 11191 5578 11191 5579 11192 5578 11192 9729 11192 5577 11193 5579 11193 5769 11193 5769 11194 5579 11194 14829 11194 5769 11195 14829 11195 5576 11195 7154 11196 9729 11196 7294 11196 7294 11197 9729 11197 5578 11197 9728 11198 9729 11198 5580 11198 5580 11199 9729 11199 7154 11199 5580 11200 7154 11200 5581 11200 5581 11201 7154 11201 9731 11201 7297 11202 7295 11202 5582 11202 5582 11203 7295 11203 7294 11203 5582 11204 7294 11204 7300 11204 7300 11205 7294 11205 5578 11205 9732 11206 9731 11206 9733 11206 9733 11207 9731 11207 7154 11207 9733 11208 7154 11208 9735 11208 9735 11209 7154 11209 5585 11209 9735 11210 5585 11210 7148 11210 7148 11211 5585 11211 7303 11211 5583 11212 5584 11212 5585 11212 5585 11213 5584 11213 5586 11213 5585 11214 5586 11214 7303 11214 14936 11215 5598 11215 5587 11215 5587 11216 12659 11216 12649 11216 12649 11217 5588 11217 5587 11217 5587 11218 5588 11218 5589 11218 5587 11219 5589 11219 14936 11219 14936 11220 5589 11220 5590 11220 14936 11221 5590 11221 14931 11221 14931 11222 5590 11222 5591 11222 14931 11223 5591 11223 14933 11223 14933 11224 5591 11224 12672 11224 14933 11225 12672 11225 14934 11225 14934 11226 12672 11226 12714 11226 14934 11227 12714 11227 5716 11227 5595 11228 14983 11228 5596 11228 5600 11229 9708 11229 9701 11229 9701 11230 5592 11230 5600 11230 5600 11231 5592 11231 5593 11231 5600 11232 5593 11232 5594 11232 5595 11233 5596 11233 14982 11233 14982 11234 5596 11234 5597 11234 14982 11235 5597 11235 14979 11235 14979 11236 5597 11236 12800 11236 14979 11237 12800 11237 9701 11237 9701 11238 12800 11238 12798 11238 9701 11239 12798 11239 5592 11239 5598 11240 9711 11240 9709 11240 5604 11241 9447 11241 9702 11241 9702 11242 9704 11242 5604 11242 5604 11243 9704 11243 9708 11243 5604 11244 9708 11244 5599 11244 5599 11245 9708 11245 5600 11245 5601 11246 7264 11246 7263 11246 7255 11247 7253 11247 5602 11247 5602 11248 7253 11248 5599 11248 5602 11249 5599 11249 7257 11249 7257 11250 5599 11250 5600 11250 7263 11251 7261 11251 5601 11251 5601 11252 7261 11252 5587 11252 5601 11253 5587 11253 5603 11253 5603 11254 5587 11254 5598 11254 5603 11255 5598 11255 5604 11255 5604 11256 5598 11256 9709 11256 5604 11257 9709 11257 9447 11257 5606 11258 5613 11258 5616 11258 5684 11259 13873 11259 15440 11259 15440 11260 13873 11260 13876 11260 15440 11261 13876 11261 5607 11261 5616 11262 9759 11262 5606 11262 5606 11263 9759 11263 15439 11263 5606 11264 15439 11264 15444 11264 15444 11265 5605 11265 5606 11265 5606 11266 5605 11266 15443 11266 5606 11267 15443 11267 13876 11267 13876 11268 15443 11268 15446 11268 13876 11269 15446 11269 5607 11269 5608 11270 13921 11270 5609 11270 5681 11271 5680 11271 13888 11271 13888 11272 5680 11272 5608 11272 13888 11273 5608 11273 13887 11273 13887 11274 5608 11274 5609 11274 9487 11275 9486 11275 7199 11275 7199 11276 9486 11276 5612 11276 5615 11277 9762 11277 5614 11277 5613 11278 5610 11278 5611 11278 9486 11279 5616 11279 5612 11279 5612 11280 5616 11280 5613 11280 5612 11281 5613 11281 7342 11281 7342 11282 5613 11282 5611 11282 7342 11283 5611 11283 7345 11283 9487 11284 7199 11284 5614 11284 5614 11285 7199 11285 9761 11285 5614 11286 9761 11286 5615 11286 9756 11287 9757 11287 9755 11287 9755 11288 9757 11288 5616 11288 9755 11289 5616 11289 9483 11289 9483 11290 5616 11290 9486 11290 14044 11291 5617 11291 14045 11291 14045 11292 5617 11292 9418 11292 14045 11293 9418 11293 14053 11293 7203 11294 9427 11294 5618 11294 5618 11295 9427 11295 5619 11295 5618 11296 5619 11296 5620 11296 5629 11297 5621 11297 5628 11297 5628 11298 5621 11298 5623 11298 5628 11299 5623 11299 5622 11299 5622 11300 5623 11300 9420 11300 5622 11301 9420 11301 5624 11301 7310 11302 5645 11302 5626 11302 5626 11303 5645 11303 5625 11303 5626 11304 5625 11304 14788 11304 14788 11305 5627 11305 5626 11305 5626 11306 5627 11306 14787 11306 5626 11307 14787 11307 5628 11307 5628 11308 14787 11308 14785 11308 5628 11309 14785 11309 5629 11309 13450 11310 5630 11310 14757 11310 13450 11311 14757 11311 13462 11311 13462 11312 14757 11312 14769 11312 13462 11313 14769 11313 14768 11313 14768 11314 14758 11314 13462 11314 13462 11315 14758 11315 5631 11315 13462 11316 5631 11316 5632 11316 5632 11317 5631 11317 5633 11317 5632 11318 5633 11318 5634 11318 5635 11319 7307 11319 9741 11319 9741 11320 7307 11320 5632 11320 9741 11321 5632 11321 5636 11321 5636 11322 5632 11322 5634 11322 5640 11323 5637 11323 7307 11323 7311 11324 5641 11324 7310 11324 7310 11325 5641 11325 5644 11325 7310 11326 5644 11326 5645 11326 5638 11327 5639 11327 9742 11327 9742 11328 5639 11328 9745 11328 9742 11329 9745 11329 5642 11329 7311 11330 5640 11330 5641 11330 5641 11331 5640 11331 7307 11331 5641 11332 7307 11332 9745 11332 9745 11333 7307 11333 5635 11333 9745 11334 5635 11334 5642 11334 9737 11335 5643 11335 5644 11335 5644 11336 5643 11336 9740 11336 5644 11337 9740 11337 5645 11337 13643 11338 9492 11338 13616 11338 13616 11339 9492 11339 9491 11339 13616 11340 9491 11340 5646 11340 15547 11341 4824 11341 15549 11341 15549 11342 4824 11342 5647 11342 15549 11343 5647 11343 15544 11343 15544 11344 5647 11344 15538 11344 15538 11345 5647 11345 5648 11345 15538 11346 5648 11346 15540 11346 15540 11347 5648 11347 15541 11347 15541 11348 5648 11348 5650 11348 15541 11349 5650 11349 5649 11349 5649 11350 5650 11350 5651 11350 5651 11351 5650 11351 4822 11351 5651 11352 4822 11352 15526 11352 5620 11353 5619 11353 13409 11353 13409 11354 5619 11354 9426 11354 13409 11355 9426 11355 13410 11355 13410 11356 9426 11356 5652 11356 5652 11357 9426 11357 9421 11357 5652 11358 9421 11358 13405 11358 13405 11359 9421 11359 13400 11359 13400 11360 9421 11360 9422 11360 13400 11361 9422 11361 13399 11361 13399 11362 9422 11362 13446 11362 13446 11363 9422 11363 5653 11363 13446 11364 5653 11364 5654 11364 5654 11365 5653 11365 5655 11365 5655 11366 5653 11366 5630 11366 5655 11367 5630 11367 13450 11367 5657 11368 13677 11368 5658 11368 5658 11369 13677 11369 5151 11369 5151 11370 13677 11370 13678 11370 5151 11371 13678 11371 5656 11371 5657 11372 5658 11372 13640 11372 13640 11373 5658 11373 9493 11373 13640 11374 9493 11374 13641 11374 5659 11375 9492 11375 13643 11375 13643 11376 5660 11376 5659 11376 5659 11377 5660 11377 5661 11377 5659 11378 5661 11378 9493 11378 9493 11379 5661 11379 5662 11379 9493 11380 5662 11380 13641 11380 5646 11381 9491 11381 5664 11381 5664 11382 9491 11382 5663 11382 5664 11383 5663 11383 5665 11383 5665 11384 5663 11384 5667 11384 5667 11385 5663 11385 5666 11385 5667 11386 5666 11386 5668 11386 5668 11387 5666 11387 5669 11387 5669 11388 5666 11388 9490 11388 5669 11389 9490 11389 13661 11389 13661 11390 9490 11390 13663 11390 13663 11391 9490 11391 5670 11391 13663 11392 5670 11392 13665 11392 13665 11393 5670 11393 9489 11393 13665 11394 9489 11394 5157 11394 15426 11395 15425 11395 7197 11395 15426 11396 7197 11396 15414 11396 15414 11397 7197 11397 5671 11397 15414 11398 5671 11398 5674 11398 5671 11399 5672 11399 5674 11399 5674 11400 5672 11400 5673 11400 5674 11401 5673 11401 5675 11401 5675 11402 5673 11402 9480 11402 5673 11403 5676 11403 9480 11403 9480 11404 5676 11404 5678 11404 9480 11405 5678 11405 5677 11405 5677 11406 5678 11406 13949 11406 13949 11407 5679 11407 5677 11407 5677 11408 5679 11408 13921 11408 5677 11409 13921 11409 5608 11409 5680 11410 5681 11410 5682 11410 5682 11411 5681 11411 5683 11411 13859 11412 9476 11412 13869 11412 13869 11413 9476 11413 5682 11413 13869 11414 5682 11414 13862 11414 13862 11415 5682 11415 5683 11415 13873 11416 5684 11416 5685 11416 5685 11417 5684 11417 9478 11417 5685 11418 9478 11418 5686 11418 5686 11419 9478 11419 9477 11419 5686 11420 9477 11420 13845 11420 13845 11421 9477 11421 9476 11421 13845 11422 9476 11422 13844 11422 13844 11423 9476 11423 13859 11423 5224 11424 9473 11424 9976 11424 9976 11425 9473 11425 9471 11425 9975 11426 5687 11426 9471 11426 9471 11427 5687 11427 5688 11427 9471 11428 5688 11428 9976 11428 9471 11429 9472 11429 9975 11429 9975 11430 9472 11430 9475 11430 9975 11431 9475 11431 9973 11431 5689 11432 9470 11432 9959 11432 9959 11433 9958 11433 5689 11433 5689 11434 9958 11434 5690 11434 5689 11435 5690 11435 9475 11435 9475 11436 5690 11436 9972 11436 9475 11437 9972 11437 9973 11437 7145 11438 9467 11438 9904 11438 9904 11439 9467 11439 5691 11439 9904 11440 5691 11440 9897 11440 9897 11441 5691 11441 9898 11441 9898 11442 5691 11442 9468 11442 9898 11443 9468 11443 5692 11443 5692 11444 9468 11444 9469 11444 5692 11445 9469 11445 9901 11445 9901 11446 9469 11446 5693 11446 5693 11447 9469 11447 9465 11447 5693 11448 9465 11448 9902 11448 9902 11449 9465 11449 5694 11449 5694 11450 9465 11450 5211 11450 5694 11451 5211 11451 9877 11451 5695 11452 12364 11452 5696 11452 5696 11453 12364 11453 12362 11453 5696 11454 12362 11454 9462 11454 5695 11455 5696 11455 5697 11455 5697 11456 5696 11456 9461 11456 5697 11457 9461 11457 5698 11457 5698 11458 9461 11458 5699 11458 5698 11459 5699 11459 12346 11459 12346 11460 5699 11460 9460 11460 12346 11461 9460 11461 12302 11461 12533 11462 12537 11462 9455 11462 5199 11463 9452 11463 12573 11463 12573 11464 9452 11464 9451 11464 12573 11465 9451 11465 12551 11465 12551 11466 9451 11466 12540 11466 12540 11467 9451 11467 9450 11467 12540 11468 9450 11468 5700 11468 5700 11469 9450 11469 5701 11469 5701 11470 9450 11470 5703 11470 5701 11471 5703 11471 5702 11471 9455 11472 12537 11472 5703 11472 5703 11473 12537 11473 5704 11473 5703 11474 5704 11474 5702 11474 9457 11475 5705 11475 9455 11475 9455 11476 5705 11476 12535 11476 9455 11477 12535 11477 12533 11477 7159 11478 5706 11478 12498 11478 12498 11479 5706 11479 5707 11479 12498 11480 5707 11480 12488 11480 12488 11481 5707 11481 12490 11481 12490 11482 5707 11482 5709 11482 12490 11483 5709 11483 5708 11483 5708 11484 5709 11484 5710 11484 5710 11485 5709 11485 9454 11485 5710 11486 9454 11486 12476 11486 12476 11487 9454 11487 5711 11487 5711 11488 9454 11488 5713 11488 5711 11489 5713 11489 5712 11489 5712 11490 5713 11490 5714 11490 5714 11491 5713 11491 5204 11491 5714 11492 5204 11492 5715 11492 14947 11493 5716 11493 12714 11493 12726 11494 5718 11494 5717 11494 5596 11495 14983 11495 5718 11495 5718 11496 14983 11496 5719 11496 5718 11497 5719 11497 5720 11497 5720 11498 14956 11498 5718 11498 5718 11499 14956 11499 14954 11499 5718 11500 14954 11500 5717 11500 12726 11501 5717 11501 12721 11501 12721 11502 5717 11502 5721 11502 12721 11503 5721 11503 5722 11503 5722 11504 5721 11504 5723 11504 5722 11505 5723 11505 12713 11505 14947 11506 12714 11506 14946 11506 12713 11507 5723 11507 12714 11507 12714 11508 5723 11508 14950 11508 12714 11509 14950 11509 14946 11509 12878 11510 12895 11510 5724 11510 12931 11511 5725 11511 5727 11511 5727 11512 5725 11512 5726 11512 5727 11513 5726 11513 12888 11513 12888 11514 5726 11514 12889 11514 12889 11515 5726 11515 5728 11515 12889 11516 5728 11516 12890 11516 5724 11517 12895 11517 15748 11517 12895 11518 12894 11518 15748 11518 15748 11519 12894 11519 5729 11519 15748 11520 5729 11520 5728 11520 5728 11521 5729 11521 5730 11521 5728 11522 5730 11522 12890 11522 15746 11523 12857 11523 5724 11523 5724 11524 12857 11524 5731 11524 5724 11525 5731 11525 12878 11525 5732 11526 5734 11526 5733 11526 5733 11527 5734 11527 5736 11527 5737 11528 5735 11528 5736 11528 5736 11529 5735 11529 12834 11529 5736 11530 12834 11530 5733 11530 15740 11531 12830 11531 5737 11531 5737 11532 12830 11532 12832 11532 5737 11533 12832 11533 5735 11533 5738 11534 12817 11534 15742 11534 15742 11535 12817 11535 5739 11535 15742 11536 5739 11536 15740 11536 15740 11537 5739 11537 5740 11537 15740 11538 5740 11538 12830 11538 5738 11539 15742 11539 12844 11539 12844 11540 15742 11540 5187 11540 12844 11541 5187 11541 12852 11541 5567 11542 14902 11542 13059 11542 13059 11543 14902 11543 5741 11543 13059 11544 5741 11544 13057 11544 5741 11545 14900 11545 13057 11545 13057 11546 14900 11546 14899 11546 13057 11547 14899 11547 13055 11547 13055 11548 14899 11548 5743 11548 13055 11549 5743 11549 5742 11549 5742 11550 5743 11550 5744 11550 5742 11551 5744 11551 5745 11551 5745 11552 5744 11552 14896 11552 14896 11553 14895 11553 5745 11553 5745 11554 14895 11554 5746 11554 5745 11555 5746 11555 5747 11555 5747 11556 5746 11556 14889 11556 5747 11557 14889 11557 5561 11557 13172 11558 5748 11558 5749 11558 13172 11559 5749 11559 13133 11559 13133 11560 5749 11560 5750 11560 13133 11561 5750 11561 13134 11561 13134 11562 5750 11562 5751 11562 13134 11563 5751 11563 13136 11563 13136 11564 5751 11564 5752 11564 5752 11565 5751 11565 5757 11565 5752 11566 5757 11566 5753 11566 5755 11567 9437 11567 13139 11567 13139 11568 5754 11568 5755 11568 5755 11569 5754 11569 5756 11569 5755 11570 5756 11570 5757 11570 5757 11571 5756 11571 13137 11571 5757 11572 13137 11572 5753 11572 13199 11573 5758 11573 5759 11573 5759 11574 5758 11574 9435 11574 5759 11575 9435 11575 5760 11575 5760 11576 9435 11576 5761 11576 5761 11577 9435 11577 5762 11577 5761 11578 5762 11578 13189 11578 13189 11579 5762 11579 13183 11579 13183 11580 5762 11580 9433 11580 13183 11581 9433 11581 5763 11581 5763 11582 9433 11582 5764 11582 5764 11583 9433 11583 5765 11583 5764 11584 5765 11584 5766 11584 5766 11585 5765 11585 5767 11585 5766 11586 5767 11586 13215 11586 14820 11587 5768 11587 5769 11587 5769 11588 5768 11588 5770 11588 5769 11589 5770 11589 13328 11589 13328 11590 5770 11590 5771 11590 13328 11591 5771 11591 5772 11591 5772 11592 5771 11592 5773 11592 5773 11593 5771 11593 14814 11593 5773 11594 14814 11594 5774 11594 5774 11595 14814 11595 5775 11595 5775 11596 14814 11596 14798 11596 5775 11597 14798 11597 5776 11597 14798 11598 5777 11598 5776 11598 5776 11599 5777 11599 5778 11599 5776 11600 5778 11600 5779 11600 5779 11601 5778 11601 5780 11601 5779 11602 5780 11602 13297 11602 13297 11603 5780 11603 14795 11603 13297 11604 14795 11604 5781 11604 9425 11605 5782 11605 5624 11605 5624 11606 5782 11606 13454 11606 5624 11607 13454 11607 5622 11607 13435 11608 13434 11608 5785 11608 5785 11609 13434 11609 13433 11609 5785 11610 13433 11610 9425 11610 9425 11611 13433 11611 13436 11611 9425 11612 13436 11612 5782 11612 5783 11613 7200 11613 7201 11613 7201 11614 5784 11614 5783 11614 5783 11615 5784 11615 13419 11615 5783 11616 13419 11616 5785 11616 5785 11617 13419 11617 13421 11617 5785 11618 13421 11618 13435 11618 5995 11619 9399 11619 12152 11619 12152 11620 9399 11620 9397 11620 12152 11621 9397 11621 12143 11621 5979 11622 5786 11622 5980 11622 5980 11623 5786 11623 5787 11623 5980 11624 5787 11624 9397 11624 9397 11625 5787 11625 5788 11625 9397 11626 5788 11626 12143 11626 5803 11627 5789 11627 11366 11627 11366 11628 5789 11628 5791 11628 11366 11629 5791 11629 11367 11629 15251 11630 5790 11630 6039 11630 15251 11631 6039 11631 15250 11631 11367 11632 5791 11632 6039 11632 6039 11633 5791 11633 15248 11633 6039 11634 15248 11634 15250 11634 15284 11635 5799 11635 7529 11635 7528 11636 11348 11636 7529 11636 7529 11637 11348 11637 11349 11637 7529 11638 11349 11638 15284 11638 15284 11639 11349 11639 5792 11639 15284 11640 5792 11640 15280 11640 15280 11641 5792 11641 5794 11641 15280 11642 5794 11642 5793 11642 5793 11643 5794 11643 5795 11643 5795 11644 5794 11644 15283 11644 15283 11645 5794 11645 6047 11645 15283 11646 6047 11646 15277 11646 5799 11647 9794 11647 5800 11647 9794 11648 5796 11648 5800 11648 5800 11649 5796 11649 5797 11649 5800 11650 5797 11650 9361 11650 9361 11651 9798 11651 5800 11651 5800 11652 9798 11652 5789 11652 5800 11653 5789 11653 5802 11653 7543 11654 7542 11654 5802 11654 7386 11655 7540 11655 5798 11655 5799 11656 5800 11656 7529 11656 7529 11657 5800 11657 7386 11657 7529 11658 7386 11658 7531 11658 7531 11659 7386 11659 5798 11659 7531 11660 5798 11660 7537 11660 5801 11661 7543 11661 7546 11661 7546 11662 7543 11662 5802 11662 7546 11663 5802 11663 5803 11663 5803 11664 5802 11664 5789 11664 11398 11665 5804 11665 5805 11665 11398 11666 5805 11666 5806 11666 5806 11667 5805 11667 6025 11667 5806 11668 6025 11668 11504 11668 14396 11669 14390 11669 15780 11669 15780 11670 14390 11670 11571 11670 15780 11671 11571 11671 5807 11671 6032 11672 9370 11672 11524 11672 11524 11673 9370 11673 5808 11673 11524 11674 5808 11674 5809 11674 5809 11675 5808 11675 5811 11675 5809 11676 5811 11676 5810 11676 5810 11677 5811 11677 5812 11677 5812 11678 15778 11678 5810 11678 5810 11679 15778 11679 15777 11679 5810 11680 15777 11680 5813 11680 15777 11681 5814 11681 5813 11681 5813 11682 5814 11682 5815 11682 5813 11683 5815 11683 11547 11683 11547 11684 5815 11684 5807 11684 11547 11685 5807 11685 11563 11685 11563 11686 5807 11686 11571 11686 15803 11687 15798 11687 5820 11687 5820 11688 15798 11688 11438 11688 11438 11689 15798 11689 5816 11689 11438 11690 5816 11690 9364 11690 15795 11691 5817 11691 5821 11691 5821 11692 5817 11692 15806 11692 5821 11693 15806 11693 11454 11693 11454 11694 15806 11694 5818 11694 11454 11695 5818 11695 5820 11695 5820 11696 5818 11696 5819 11696 5820 11697 5819 11697 15803 11697 14384 11698 14386 11698 11514 11698 11514 11699 14386 11699 15715 11699 11514 11700 15715 11700 11515 11700 11515 11701 15715 11701 15795 11701 11515 11702 15795 11702 11513 11702 11513 11703 15795 11703 5821 11703 7553 11704 5822 11704 5823 11704 5831 11705 7553 11705 15200 11705 15200 11706 7553 11706 5823 11706 15200 11707 5823 11707 15201 11707 15201 11708 5823 11708 11100 11708 15201 11709 11100 11709 5824 11709 5824 11710 11100 11710 15202 11710 7390 11711 5831 11711 5825 11711 5825 11712 5831 11712 9812 11712 5825 11713 9812 11713 9811 11713 9811 11714 5826 11714 5825 11714 5825 11715 5826 11715 5827 11715 5825 11716 5827 11716 5828 11716 5828 11717 5829 11717 5825 11717 5825 11718 5829 11718 9815 11718 5825 11719 9815 11719 7560 11719 7560 11720 9815 11720 5832 11720 7560 11721 5832 11721 7562 11721 7558 11722 7556 11722 7559 11722 7559 11723 7556 11723 5830 11723 7559 11724 5830 11724 7390 11724 7390 11725 5830 11725 7553 11725 7390 11726 7553 11726 5831 11726 7570 11727 7569 11727 5832 11727 5832 11728 7569 11728 7565 11728 5832 11729 7565 11729 7562 11729 11130 11730 6060 11730 5833 11730 11130 11731 5833 11731 5834 11731 5834 11732 5833 11732 9353 11732 5834 11733 9353 11733 11148 11733 11211 11734 5835 11734 5836 11734 5838 11735 5839 11735 5837 11735 11211 11736 5836 11736 5837 11736 5837 11737 5836 11737 15229 11737 5837 11738 15229 11738 5838 11738 9803 11739 14378 11739 9804 11739 9804 11740 14378 11740 5842 11740 9804 11741 5842 11741 15234 11741 15234 11742 5842 11742 15231 11742 5839 11743 5840 11743 5837 11743 5837 11744 5840 11744 5841 11744 5837 11745 5841 11745 5842 11745 5842 11746 5841 11746 15230 11746 5842 11747 15230 11747 15231 11747 15210 11748 5843 11748 5845 11748 5845 11749 5843 11749 11197 11749 11197 11750 5843 11750 5844 11750 11197 11751 5844 11751 6053 11751 7552 11752 14375 11752 11213 11752 11213 11753 14375 11753 9805 11753 11213 11754 9805 11754 15207 11754 15207 11755 15218 11755 11213 11755 11213 11756 15218 11756 15208 11756 11213 11757 15208 11757 5845 11757 5845 11758 15208 11758 15212 11758 5845 11759 15212 11759 15210 11759 11716 11760 5846 11760 5848 11760 5848 11761 5847 11761 5851 11761 11716 11762 5848 11762 5849 11762 5849 11763 5848 11763 5851 11763 5849 11764 5851 11764 5852 11764 15300 11765 11735 11765 15299 11765 15299 11766 11735 11766 11726 11766 15299 11767 11726 11767 15297 11767 15297 11768 11726 11768 15296 11768 15296 11769 11726 11769 5850 11769 15296 11770 5850 11770 5851 11770 5851 11771 5850 11771 11725 11771 5851 11772 11725 11772 5852 11772 5860 11773 5853 11773 5854 11773 11695 11774 5855 11774 5856 11774 5854 11775 7508 11775 5862 11775 11695 11776 5856 11776 5857 11776 5856 11777 5858 11777 5857 11777 5857 11778 5858 11778 15338 11778 5857 11779 15338 11779 11680 11779 11680 11780 15338 11780 5860 11780 11680 11781 5860 11781 5859 11781 5859 11782 5860 11782 5854 11782 5859 11783 5854 11783 5861 11783 5861 11784 5854 11784 5862 11784 9374 11785 5863 11785 7392 11785 7392 11786 5863 11786 5865 11786 7514 11787 7510 11787 5854 11787 5866 11788 7515 11788 5864 11788 5865 11789 9789 11789 7392 11789 7392 11790 9789 11790 5847 11790 7392 11791 5847 11791 5868 11791 5868 11792 5847 11792 5848 11792 5864 11793 7514 11793 5866 11793 5866 11794 7514 11794 5854 11794 5866 11795 5854 11795 7392 11795 7392 11796 5854 11796 5853 11796 7392 11797 5853 11797 9374 11797 9374 11798 5853 11798 9784 11798 7519 11799 5867 11799 7520 11799 7520 11800 5867 11800 5868 11800 7520 11801 5868 11801 7522 11801 7522 11802 5868 11802 5848 11802 9386 11803 5871 11803 6015 11803 6015 11804 5871 11804 5869 11804 5869 11805 5871 11805 5870 11805 5870 11806 5871 11806 5872 11806 5870 11807 5872 11807 6003 11807 5873 11808 15346 11808 15347 11808 15346 11809 5873 11809 15345 11809 15345 11810 5873 11810 11897 11810 15345 11811 11897 11811 15344 11811 5874 11812 11909 11812 5875 11812 5875 11813 11909 11813 5876 11813 5875 11814 5876 11814 5877 11814 5877 11815 5876 11815 5873 11815 5877 11816 5873 11816 5878 11816 5878 11817 5873 11817 15347 11817 11898 11818 5879 11818 11897 11818 11897 11819 5879 11819 15343 11819 11897 11820 15343 11820 15344 11820 5880 11821 9780 11821 11811 11821 11811 11822 9780 11822 5879 11822 11811 11823 5879 11823 11857 11823 11857 11824 5879 11824 11898 11824 10436 11825 5881 11825 10442 11825 10442 11826 5881 11826 5882 11826 15082 11827 15085 11827 10438 11827 5882 11828 15080 11828 10442 11828 10442 11829 15080 11829 5883 11829 10442 11830 5883 11830 10438 11830 10438 11831 5883 11831 15083 11831 10438 11832 15083 11832 15082 11832 5899 11833 5897 11833 5884 11833 5884 11834 5897 11834 10438 11834 5884 11835 10438 11835 5885 11835 5885 11836 10438 11836 15085 11836 10514 11837 5886 11837 5887 11837 10514 11838 5887 11838 5888 11838 5888 11839 5887 11839 5889 11839 5889 11840 5887 11840 5890 11840 5889 11841 5890 11841 5891 11841 5896 11842 5898 11842 5892 11842 5892 11843 5898 11843 5900 11843 5892 11844 5900 11844 5893 11844 7595 11845 7593 11845 7597 11845 7597 11846 7593 11846 5897 11846 7597 11847 5897 11847 5894 11847 5894 11848 5897 11848 5896 11848 9846 11849 5895 11849 9845 11849 5896 11850 5897 11850 5898 11850 5898 11851 5897 11851 5899 11851 5898 11852 5899 11852 9845 11852 9845 11853 5899 11853 9847 11853 9845 11854 9847 11854 9846 11854 9865 11855 5901 11855 5900 11855 5900 11856 5901 11856 9864 11856 5900 11857 9864 11857 5893 11857 5902 11858 5903 11858 10198 11858 10198 11859 5903 11859 5113 11859 10198 11860 5113 11860 10199 11860 10919 11861 9345 11861 5904 11861 10919 11862 5904 11862 10920 11862 10920 11863 5904 11863 9344 11863 10920 11864 9344 11864 10905 11864 9345 11865 10919 11865 9339 11865 9339 11866 10919 11866 10952 11866 9339 11867 10952 11867 10970 11867 10883 11868 6073 11868 5905 11868 10883 11869 5905 11869 5906 11869 5906 11870 5905 11870 5907 11870 5906 11871 5907 11871 5908 11871 5908 11872 5907 11872 5909 11872 5908 11873 5909 11873 5910 11873 5910 11874 15155 11874 5908 11874 5908 11875 15155 11875 5911 11875 5908 11876 5911 11876 5912 11876 9825 11877 5913 11877 5914 11877 5914 11878 5913 11878 5908 11878 5914 11879 5908 11879 5915 11879 5915 11880 5908 11880 5912 11880 15134 11881 15132 11881 10965 11881 10965 11882 15132 11882 5916 11882 10965 11883 5916 11883 5917 11883 5917 11884 5916 11884 15130 11884 5917 11885 15130 11885 5918 11885 5924 11886 5919 11886 10929 11886 10929 11887 5919 11887 9826 11887 10929 11888 9826 11888 5920 11888 5920 11889 15128 11889 10929 11889 10929 11890 15128 11890 15127 11890 10929 11891 15127 11891 10965 11891 10965 11892 15127 11892 15126 11892 10965 11893 15126 11893 15134 11893 9346 11894 5923 11894 5913 11894 9827 11895 5919 11895 5921 11895 5921 11896 5919 11896 5924 11896 5921 11897 5924 11897 5923 11897 7571 11898 5913 11898 5922 11898 5922 11899 5913 11899 5923 11899 5922 11900 5923 11900 7573 11900 7573 11901 5923 11901 5924 11901 9822 11902 5925 11902 9824 11902 9824 11903 5925 11903 9346 11903 9824 11904 9346 11904 9825 11904 9825 11905 9346 11905 5913 11905 9829 11906 5926 11906 5921 11906 5921 11907 5926 11907 9828 11907 5921 11908 9828 11908 9827 11908 5961 11909 5927 11909 10719 11909 10719 11910 5927 11910 9412 11910 10719 11911 9412 11911 5928 11911 5929 11912 15699 11912 5930 11912 5930 11913 15699 11913 5931 11913 5930 11914 5931 11914 14520 11914 15710 11915 5932 11915 5933 11915 5933 11916 5932 11916 14513 11916 5933 11917 14513 11917 5931 11917 5931 11918 14513 11918 5934 11918 5931 11919 5934 11919 14520 11919 15699 11920 5929 11920 5935 11920 5935 11921 5929 11921 4820 11921 5935 11922 4820 11922 5936 11922 5936 11923 4820 11923 15671 11923 15671 11924 4820 11924 5938 11924 15671 11925 5938 11925 5937 11925 5937 11926 5938 11926 15670 11926 15670 11927 5938 11927 5939 11927 15670 11928 5939 11928 15661 11928 15661 11929 5939 11929 5940 11929 5940 11930 5939 11930 7445 11930 5940 11931 7445 11931 15662 11931 5917 11932 5918 11932 10997 11932 10997 11933 5918 11933 9337 11933 10997 11934 9337 11934 5941 11934 5941 11935 9337 11935 5942 11935 5942 11936 9337 11936 9338 11936 5942 11937 9338 11937 10990 11937 10990 11938 9338 11938 5943 11938 5943 11939 9338 11939 9342 11939 5943 11940 9342 11940 10968 11940 10968 11941 9342 11941 10969 11941 10969 11942 9342 11942 9341 11942 10969 11943 9341 11943 5944 11943 9339 11944 10970 11944 9341 11944 9341 11945 10970 11945 5945 11945 9341 11946 5945 11946 5944 11946 5928 11947 9412 11947 5946 11947 5946 11948 9412 11948 9413 11948 5949 11949 5947 11949 9413 11949 9413 11950 5947 11950 10681 11950 9413 11951 10681 11951 5946 11951 10656 11952 5948 11952 5953 11952 5953 11953 5948 11953 5950 11953 5953 11954 5950 11954 5949 11954 5949 11955 5950 11955 5951 11955 5949 11956 5951 11956 5947 11956 10656 11957 5953 11957 5952 11957 5952 11958 5953 11958 5954 11958 5952 11959 5954 11959 5955 11959 9411 11960 5956 11960 5099 11960 5099 11961 5956 11961 10761 11961 10761 11962 5956 11962 5957 11962 5957 11963 5956 11963 9409 11963 5957 11964 9409 11964 10753 11964 10753 11965 9409 11965 5958 11965 5958 11966 9409 11966 9407 11966 5958 11967 9407 11967 5959 11967 5959 11968 9407 11968 5960 11968 5960 11969 9407 11969 5962 11969 5960 11970 5962 11970 10738 11970 5927 11971 5961 11971 5962 11971 5962 11972 5961 11972 10747 11972 5962 11973 10747 11973 10738 11973 5887 11974 5886 11974 10530 11974 5887 11975 10530 11975 5964 11975 10530 11976 5963 11976 5964 11976 5964 11977 5963 11977 10526 11977 5964 11978 10526 11978 9404 11978 9404 11979 10526 11979 5967 11979 9404 11980 5967 11980 9405 11980 15057 11981 5965 11981 10502 11981 10502 11982 5965 11982 5966 11982 5967 11983 5968 11983 9405 11983 9405 11984 5968 11984 10532 11984 9405 11985 10532 11985 5969 11985 5969 11986 10532 11986 5970 11986 5969 11987 5970 11987 5966 11987 5966 11988 5970 11988 5971 11988 5966 11989 5971 11989 10502 11989 5972 11990 5881 11990 10436 11990 5972 11991 10436 11991 9402 11991 10436 11992 10437 11992 9402 11992 9402 11993 10437 11993 5973 11993 9402 11994 5973 11994 5974 11994 5974 11995 5973 11995 10434 11995 5974 11996 10434 11996 5975 11996 5975 11997 5976 11997 5974 11997 5974 11998 5976 11998 10451 11998 5974 11999 10451 11999 5977 11999 5891 12000 5890 12000 10455 12000 10455 12001 5890 12001 5977 12001 10455 12002 5977 12002 5978 12002 5978 12003 5977 12003 10451 12003 5979 12004 5980 12004 12209 12004 12209 12005 5980 12005 5981 12005 12209 12006 5981 12006 5982 12006 5982 12007 5981 12007 5983 12007 5983 12008 5981 12008 9400 12008 5983 12009 9400 12009 5984 12009 5984 12010 9400 12010 5985 12010 5985 12011 9400 12011 5987 12011 5985 12012 5987 12012 5986 12012 5986 12013 5987 12013 9390 12013 5986 12014 9390 12014 5988 12014 5988 12015 9390 12015 12188 12015 12188 12016 9390 12016 5507 12016 12188 12017 5507 12017 12187 12017 9391 12018 9392 12018 5989 12018 5989 12019 9392 12019 12137 12019 12137 12020 9392 12020 5990 12020 5990 12021 9392 12021 9394 12021 5990 12022 9394 12022 12124 12022 12124 12023 9394 12023 5991 12023 5991 12024 9394 12024 9396 12024 5991 12025 9396 12025 5992 12025 5992 12026 9396 12026 5994 12026 5992 12027 5994 12027 5993 12027 9399 12028 5995 12028 5994 12028 5994 12029 5995 12029 12111 12029 5994 12030 12111 12030 5993 12030 9388 12031 5997 12031 5996 12031 5996 12032 5997 12032 12068 12032 12068 12033 5997 12033 5998 12033 5998 12034 5997 12034 5999 12034 5998 12035 5999 12035 12055 12035 12055 12036 5999 12036 12056 12036 12056 12037 5999 12037 6001 12037 12056 12038 6001 12038 6000 12038 6000 12039 6001 12039 6002 12039 6000 12040 6002 12040 5483 12040 6003 12041 5872 12041 6004 12041 6004 12042 5872 12042 6006 12042 9377 12043 6005 12043 6006 12043 6006 12044 6005 12044 11795 12044 6006 12045 11795 12045 6004 12045 6008 12046 6007 12046 9377 12046 9377 12047 6007 12047 11796 12047 9377 12048 11796 12048 6005 12048 9382 12049 11764 12049 6008 12049 6008 12050 11764 12050 6009 12050 6008 12051 6009 12051 6007 12051 11771 12052 11773 12052 5514 12052 5514 12053 11773 12053 11774 12053 5514 12054 11774 12054 9382 12054 9382 12055 11774 12055 11784 12055 9382 12056 11784 12056 11764 12056 11909 12057 5874 12057 11874 12057 11874 12058 5874 12058 9381 12058 11874 12059 9381 12059 6010 12059 6010 12060 9381 12060 11873 12060 11873 12061 9381 12061 6011 12061 11873 12062 6011 12062 6012 12062 6012 12063 6011 12063 6013 12063 6012 12064 6013 12064 6014 12064 9379 12065 9386 12065 6015 12065 6015 12066 6016 12066 9379 12066 9379 12067 6016 12067 6017 12067 9379 12068 6017 12068 6013 12068 6013 12069 6017 12069 11870 12069 6013 12070 11870 12070 6014 12070 11735 12071 15300 12071 6018 12071 6018 12072 6019 12072 11735 12072 11735 12073 6019 12073 15320 12073 11735 12074 15320 12074 11712 12074 11712 12075 15320 12075 15321 12075 11712 12076 15321 12076 11703 12076 11703 12077 15321 12077 6020 12077 6020 12078 15321 12078 15322 12078 6020 12079 15322 12079 6021 12079 6021 12080 15322 12080 6022 12080 6021 12081 6022 12081 6023 12081 15327 12082 5855 12082 11695 12082 6022 12083 15324 12083 6023 12083 6023 12084 15324 12084 6024 12084 6023 12085 6024 12085 11695 12085 11695 12086 6024 12086 15332 12086 11695 12087 15332 12087 15327 12087 11504 12088 6025 12088 11503 12088 11503 12089 6025 12089 9371 12089 11503 12090 9371 12090 6026 12090 6026 12091 9371 12091 6027 12091 6027 12092 9371 12092 6028 12092 6027 12093 6028 12093 11493 12093 11493 12094 6028 12094 11484 12094 11484 12095 6028 12095 9367 12095 11484 12096 9367 12096 11479 12096 11479 12097 9367 12097 6029 12097 6029 12098 9367 12098 6031 12098 6029 12099 6031 12099 11469 12099 11469 12100 6031 12100 6030 12100 6030 12101 6031 12101 9370 12101 6030 12102 9370 12102 6032 12102 11438 12103 9364 12103 11437 12103 11437 12104 9364 12104 6033 12104 11437 12105 6033 12105 11401 12105 11401 12106 6033 12106 6034 12106 6034 12107 6033 12107 11403 12107 11403 12108 6033 12108 9366 12108 11403 12109 9366 12109 11405 12109 11405 12110 9366 12110 6035 12110 6035 12111 9366 12111 6037 12111 6035 12112 6037 12112 11406 12112 9373 12113 5804 12113 11398 12113 11398 12114 6036 12114 9373 12114 9373 12115 6036 12115 11408 12115 9373 12116 11408 12116 6037 12116 6037 12117 11408 12117 6038 12117 6037 12118 6038 12118 11406 12118 6039 12119 5790 12119 6040 12119 6040 12120 5790 12120 6041 12120 6040 12121 6041 12121 11372 12121 11372 12122 6041 12122 15257 12122 11372 12123 15257 12123 11373 12123 15257 12124 6042 12124 11373 12124 11373 12125 6042 12125 6044 12125 11373 12126 6044 12126 6043 12126 6043 12127 6044 12127 15262 12127 6043 12128 15262 12128 11375 12128 15262 12129 6045 12129 11375 12129 11375 12130 6045 12130 15273 12130 11375 12131 15273 12131 6046 12131 6046 12132 15273 12132 15274 12132 6046 12133 15274 12133 6047 12133 6047 12134 15274 12134 6048 12134 6047 12135 6048 12135 15277 12135 11148 12136 9353 12136 11188 12136 11188 12137 9353 12137 9351 12137 11188 12138 9351 12138 11167 12138 11167 12139 9351 12139 11182 12139 11182 12140 9351 12140 6049 12140 11182 12141 6049 12141 11177 12141 11177 12142 6049 12142 11178 12142 11178 12143 6049 12143 6050 12143 11178 12144 6050 12144 6051 12144 6051 12145 6050 12145 11171 12145 11171 12146 6050 12146 6052 12146 11171 12147 6052 12147 11170 12147 11170 12148 6052 12148 11204 12148 11204 12149 6052 12149 5835 12149 11204 12150 5835 12150 11211 12150 11197 12151 6053 12151 11163 12151 11163 12152 6053 12152 6054 12152 11163 12153 6054 12153 11158 12153 11158 12154 6054 12154 6055 12154 6055 12155 6054 12155 6056 12155 6056 12156 6054 12156 6057 12156 6056 12157 6057 12157 11144 12157 11144 12158 6057 12158 11146 12158 11146 12159 6057 12159 9355 12159 11146 12160 9355 12160 11147 12160 11147 12161 9355 12161 11136 12161 11136 12162 9355 12162 6058 12162 11136 12163 6058 12163 6059 12163 6059 12164 6058 12164 6060 12164 6059 12165 6060 12165 11130 12165 6067 12166 6062 12166 15191 12166 7387 12167 6061 12167 7388 12167 7388 12168 6061 12168 15182 12168 7388 12169 15182 12169 11122 12169 11122 12170 15182 12170 15181 12170 15191 12171 6062 12171 6063 12171 6062 12172 11099 12172 6063 12172 6063 12173 11099 12173 6064 12173 6063 12174 6064 12174 15183 12174 15183 12175 6064 12175 6065 12175 15183 12176 6065 12176 15181 12176 15181 12177 6065 12177 6066 12177 15181 12178 6066 12178 11122 12178 15202 12179 11100 12179 15196 12179 15196 12180 11100 12180 6067 12180 15196 12181 6067 12181 15190 12181 15190 12182 6067 12182 15191 12182 10905 12183 9344 12183 6068 12183 6068 12184 9344 12184 6069 12184 6068 12185 6069 12185 10901 12185 10901 12186 6069 12186 6070 12186 6070 12187 6069 12187 6071 12187 6070 12188 6071 12188 10895 12188 6074 12189 10898 12189 6071 12189 6071 12190 10898 12190 6072 12190 6071 12191 6072 12191 10895 12191 10883 12192 10878 12192 6073 12192 6073 12193 10878 12193 10877 12193 6073 12194 10877 12194 6074 12194 6074 12195 10877 12195 10900 12195 6074 12196 10900 12196 10898 12196 6103 12197 6075 12197 8907 12197 8907 12198 6075 12198 6076 12198 8907 12199 6076 12199 8908 12199 8780 12200 6077 12200 6106 12200 6106 12201 6077 12201 8777 12201 6106 12202 8777 12202 6098 12202 6111 12203 9658 12203 6078 12203 6088 12204 6090 12204 6103 12204 6096 12205 6114 12205 6087 12205 6087 12206 8686 12206 8684 12206 8767 12207 6080 12207 8768 12207 8768 12208 6080 12208 6089 12208 8767 12209 6079 12209 6080 12209 6080 12210 6079 12210 6081 12210 6080 12211 6081 12211 6082 12211 6082 12212 6081 12212 6083 12212 6082 12213 6083 12213 6084 12213 6084 12214 6083 12214 6085 12214 6084 12215 6085 12215 6086 12215 6086 12216 6085 12216 8689 12216 6086 12217 8689 12217 6087 12217 6087 12218 8689 12218 8688 12218 6087 12219 8688 12219 8686 12219 6088 12220 6103 12220 8773 12220 6080 12221 6075 12221 6089 12221 6089 12222 6075 12222 6103 12222 6089 12223 6103 12223 8770 12223 8770 12224 6103 12224 6090 12224 8674 12225 8901 12225 6091 12225 6091 12226 8901 12226 6092 12226 6091 12227 6092 12227 6110 12227 8908 12228 6076 12228 6111 12228 6111 12229 6076 12229 6093 12229 6111 12230 6093 12230 9658 12230 6096 12231 6094 12231 6114 12231 6114 12232 6094 12232 8681 12232 6114 12233 8681 12233 8680 12233 8684 12234 6095 12234 6087 12234 6087 12235 6095 12235 8682 12235 6087 12236 8682 12236 6096 12236 8777 12237 6097 12237 6098 12237 6098 12238 6097 12238 6099 12238 6098 12239 6099 12239 6100 12239 6100 12240 6099 12240 6101 12240 6100 12241 6101 12241 6102 12241 6102 12242 6101 12242 8776 12242 6102 12243 8776 12243 6103 12243 6103 12244 8776 12244 8775 12244 6103 12245 8775 12245 8773 12245 8784 12246 6104 12246 6106 12246 6106 12247 6104 12247 6105 12247 6106 12248 6105 12248 8780 12248 8901 12249 8665 12249 8902 12249 8902 12250 8665 12250 8647 12250 8902 12251 8647 12251 6106 12251 6106 12252 8647 12252 8755 12252 6106 12253 8755 12253 8852 12253 8674 12254 8671 12254 8901 12254 8901 12255 8671 12255 6107 12255 8901 12256 6107 12256 8668 12256 8852 12257 6108 12257 6106 12257 6106 12258 6108 12258 8785 12258 6106 12259 8785 12259 8784 12259 8668 12260 6109 12260 8901 12260 8901 12261 6109 12261 8667 12261 8901 12262 8667 12262 6115 12262 6110 12263 6111 12263 6091 12263 6091 12264 6111 12264 6078 12264 6091 12265 6078 12265 6112 12265 6112 12266 6078 12266 9654 12266 6112 12267 9654 12267 6113 12267 6113 12268 9654 12268 6114 12268 6113 12269 6114 12269 8679 12269 8679 12270 6114 12270 8680 12270 6115 12271 8666 12271 8901 12271 8901 12272 8666 12272 6116 12272 8901 12273 6116 12273 8665 12273 5932 12274 4904 12274 6127 12274 6127 12275 6117 12275 5932 12275 5932 12276 6117 12276 14511 12276 5932 12277 14511 12277 14513 12277 6135 12278 6118 12278 4524 12278 4524 12279 6118 12279 6121 12279 6121 12280 6118 12280 6119 12280 6121 12281 6119 12281 6120 12281 4527 12282 4525 12282 8394 12282 8394 12283 4525 12283 6121 12283 8394 12284 6121 12284 16899 12284 16899 12285 6121 12285 6120 12285 8369 12286 16887 12286 16883 12286 6132 12287 16902 12287 6131 12287 8142 12288 6122 12288 8356 12288 16905 12289 6124 12289 6123 12289 6123 12290 6124 12290 8142 12290 6123 12291 8142 12291 16883 12291 16883 12292 8142 12292 8356 12292 16883 12293 8356 12293 8369 12293 4502 12294 6126 12294 6125 12294 6125 12295 6126 12295 6127 12295 6125 12296 6127 12296 4518 12296 4518 12297 6127 12297 4904 12297 4518 12298 4904 12298 4519 12298 4519 12299 4904 12299 4906 12299 4519 12300 4906 12300 4521 12300 4521 12301 4906 12301 6128 12301 4521 12302 6128 12302 6129 12302 6129 12303 6128 12303 4529 12303 6129 12304 4529 12304 6132 12304 6132 12305 4529 12305 6130 12305 6132 12306 6130 12306 16902 12306 6131 12307 16900 12307 6132 12307 6132 12308 16900 12308 6133 12308 6132 12309 6133 12309 4524 12309 4524 12310 6133 12310 6134 12310 4524 12311 6134 12311 6135 12311 16899 12312 6136 12312 8394 12312 8394 12313 6136 12313 16895 12313 8394 12314 16895 12314 6137 12314 6137 12315 16895 12315 6139 12315 6137 12316 6139 12316 6138 12316 6138 12317 6139 12317 16894 12317 6138 12318 16894 12318 6140 12318 6140 12319 16894 12319 16893 12319 16887 12320 8369 12320 6141 12320 6141 12321 8369 12321 6142 12321 6141 12322 6142 12322 16889 12322 16889 12323 6142 12323 6143 12323 16889 12324 6143 12324 6144 12324 6144 12325 6143 12325 8371 12325 6144 12326 8371 12326 16892 12326 16892 12327 8371 12327 8389 12327 16892 12328 8389 12328 16893 12328 16893 12329 8389 12329 8388 12329 16893 12330 8388 12330 6140 12330 4529 12331 15620 12331 6130 12331 6130 12332 15620 12332 15622 12332 6130 12333 15622 12333 16905 12333 16905 12334 15622 12334 6145 12334 16905 12335 6145 12335 6124 12335 6146 12336 7654 12336 8636 12336 8636 12337 7654 12337 7649 12337 8636 12338 7649 12338 6147 12338 6147 12339 7649 12339 7659 12339 6147 12340 7659 12340 6148 12340 6148 12341 7659 12341 7656 12341 6148 12342 7656 12342 6149 12342 6149 12343 7656 12343 7657 12343 6149 12344 7657 12344 8646 12344 8646 12345 7657 12345 7665 12345 8646 12346 7665 12346 8645 12346 8645 12347 7665 12347 6150 12347 8645 12348 6150 12348 8644 12348 8644 12349 6150 12349 6151 12349 8644 12350 6151 12350 8642 12350 8642 12351 6151 12351 6152 12351 8642 12352 6152 12352 8640 12352 8640 12353 6152 12353 6153 12353 8640 12354 6153 12354 8639 12354 8639 12355 6153 12355 7661 12355 8639 12356 7661 12356 6154 12356 6154 12357 7661 12357 7655 12357 6154 12358 7655 12358 6146 12358 6146 12359 7655 12359 7654 12359 7637 12360 6163 12360 6155 12360 6155 12361 6163 12361 8632 12361 6155 12362 8632 12362 7641 12362 7641 12363 8632 12363 6156 12363 7641 12364 6156 12364 7639 12364 7639 12365 6156 12365 8621 12365 7639 12366 8621 12366 7633 12366 7633 12367 8621 12367 8622 12367 7633 12368 8622 12368 7635 12368 7635 12369 8622 12369 8624 12369 7635 12370 8624 12370 7645 12370 7645 12371 8624 12371 8626 12371 7645 12372 8626 12372 7646 12372 7646 12373 8626 12373 6157 12373 7646 12374 6157 12374 6159 12374 6159 12375 6157 12375 6158 12375 6159 12376 6158 12376 7643 12376 7643 12377 6158 12377 6161 12377 7643 12378 6161 12378 6160 12378 6160 12379 6161 12379 6162 12379 6160 12380 6162 12380 7636 12380 7636 12381 6162 12381 8630 12381 7636 12382 8630 12382 7637 12382 7637 12383 8630 12383 6163 12383 6171 12384 8279 12384 6170 12384 6170 12385 8279 12385 8482 12385 6170 12386 8482 12386 6175 12386 6176 12387 8299 12387 6172 12387 6172 12388 8299 12388 6164 12388 6172 12389 6164 12389 6165 12389 6165 12390 6164 12390 6166 12390 6165 12391 6166 12391 6167 12391 6167 12392 6166 12392 8285 12392 6167 12393 8285 12393 6168 12393 6168 12394 8285 12394 6169 12394 6168 12395 6169 12395 6170 12395 6170 12396 6169 12396 6171 12396 8519 12397 6176 12397 8520 12397 8520 12398 6176 12398 6172 12398 8520 12399 6172 12399 6173 12399 6173 12400 6172 12400 6165 12400 6173 12401 6165 12401 8521 12401 8521 12402 6165 12402 6167 12402 8521 12403 6167 12403 6174 12403 6174 12404 6167 12404 6168 12404 6174 12405 6168 12405 6175 12405 6175 12406 6168 12406 6170 12406 8519 12407 8565 12407 6176 12407 6176 12408 8565 12408 6177 12408 6176 12409 6177 12409 8299 12409 8299 12410 6177 12410 8300 12410 6185 12411 6192 12411 8301 12411 8300 12412 6177 12412 6179 12412 6179 12413 6177 12413 6183 12413 8309 12414 8308 12414 6182 12414 6182 12415 8308 12415 6178 12415 6182 12416 6178 12416 6183 12416 6183 12417 6178 12417 8305 12417 6183 12418 8305 12418 6179 12418 6180 12419 6182 12419 6181 12419 6181 12420 6182 12420 6183 12420 6181 12421 6183 12421 8565 12421 8565 12422 6183 12422 6177 12422 6180 12423 6184 12423 6182 12423 6182 12424 6184 12424 6185 12424 6182 12425 6185 12425 8309 12425 8309 12426 6185 12426 8301 12426 6191 12427 6192 12427 8570 12427 8570 12428 6192 12428 6185 12428 8570 12429 6185 12429 8569 12429 8569 12430 6185 12430 6184 12430 6843 12431 8330 12431 8612 12431 8612 12432 6186 12432 6843 12432 6843 12433 6186 12433 8601 12433 6843 12434 8601 12434 6835 12434 6835 12435 8601 12435 6187 12435 6835 12436 6187 12436 6188 12436 6188 12437 6187 12437 8615 12437 6188 12438 8615 12438 6189 12438 8330 12439 6190 12439 8612 12439 8612 12440 6190 12440 8319 12440 8612 12441 8319 12441 6191 12441 6191 12442 8319 12442 6193 12442 6191 12443 6193 12443 6192 12443 6192 12444 6193 12444 8301 12444 6220 12445 6219 12445 6194 12445 6194 12446 6219 12446 6857 12446 6194 12447 6857 12447 6760 12447 8482 12448 8279 12448 8275 12448 6195 12449 6196 12449 6220 12449 6195 12450 6220 12450 8436 12450 8436 12451 6220 12451 6194 12451 8436 12452 6194 12452 6253 12452 6196 12453 8452 12453 6220 12453 6220 12454 8452 12454 8451 12454 6220 12455 8451 12455 6230 12455 6230 12456 8451 12456 6197 12456 6197 12457 6198 12457 6230 12457 6230 12458 6198 12458 8449 12458 6230 12459 8449 12459 6200 12459 8482 12460 8275 12460 6199 12460 6199 12461 8275 12461 6201 12461 6199 12462 6201 12462 6200 12462 6200 12463 6201 12463 8133 12463 6200 12464 8133 12464 6230 12464 15489 12465 6202 12465 15494 12465 15494 12466 6202 12466 6203 12466 15494 12467 6203 12467 15508 12467 15508 12468 6203 12468 6204 12468 15508 12469 6204 12469 15501 12469 15501 12470 6204 12470 6208 12470 15501 12471 6208 12471 6206 12471 6864 12472 6205 12472 6847 12472 6847 12473 6205 12473 6206 12473 6847 12474 6206 12474 6207 12474 6207 12475 6206 12475 6208 12475 6209 12476 6203 12476 6202 12476 6202 12477 6210 12477 6209 12477 6209 12478 6210 12478 6211 12478 6209 12479 6211 12479 6842 12479 6842 12480 6211 12480 6212 12480 6212 12481 8325 12481 6842 12481 6842 12482 8325 12482 8330 12482 6842 12483 8330 12483 6843 12483 6228 12484 6216 12484 6213 12484 6213 12485 6216 12485 8134 12485 6213 12486 8134 12486 6214 12486 6230 12487 8133 12487 6217 12487 6217 12488 8133 12488 6215 12488 8134 12489 6216 12489 6218 12489 6218 12490 6216 12490 6217 12490 6218 12491 6217 12491 8136 12491 8136 12492 6217 12492 6215 12492 6219 12493 6220 12493 6547 12493 6547 12494 6220 12494 6229 12494 6222 12495 6540 12495 6229 12495 6229 12496 6540 12496 6539 12496 6539 12497 6221 12497 6229 12497 6229 12498 6221 12498 6534 12498 6229 12499 6534 12499 6547 12499 4880 12500 6533 12500 6222 12500 6222 12501 6533 12501 6223 12501 6223 12502 6524 12502 6222 12502 6222 12503 6524 12503 6224 12503 6222 12504 6224 12504 6540 12504 4888 12505 4882 12505 4543 12505 4543 12506 4882 12506 6225 12506 4543 12507 6225 12507 6226 12507 6226 12508 6225 12508 4534 12508 4534 12509 6225 12509 6217 12509 4534 12510 6217 12510 6227 12510 6227 12511 6217 12511 6216 12511 6227 12512 6216 12512 6228 12512 4882 12513 4880 12513 6225 12513 6225 12514 4880 12514 6222 12514 6225 12515 6222 12515 6217 12515 6217 12516 6222 12516 6229 12516 6217 12517 6229 12517 6230 12517 6230 12518 6229 12518 6220 12518 6231 12519 8478 12519 6235 12519 6235 12520 8478 12520 6232 12520 6235 12521 6232 12521 8377 12521 6242 12522 8489 12522 6236 12522 6236 12523 8489 12523 8494 12523 6236 12524 8494 12524 6233 12524 6233 12525 8494 12525 8492 12525 6233 12526 8492 12526 6239 12526 6239 12527 8492 12527 6234 12527 6239 12528 6234 12528 6240 12528 6240 12529 6234 12529 8490 12529 6240 12530 8490 12530 6235 12530 6235 12531 8490 12531 6231 12531 8374 12532 6242 12532 8379 12532 8379 12533 6242 12533 6236 12533 8379 12534 6236 12534 6237 12534 6237 12535 6236 12535 6233 12535 6237 12536 6233 12536 6238 12536 6238 12537 6233 12537 6239 12537 6238 12538 6239 12538 8376 12538 8376 12539 6239 12539 6240 12539 8376 12540 6240 12540 8377 12540 8377 12541 6240 12541 6235 12541 8515 12542 8489 12542 6241 12542 6241 12543 8489 12543 6242 12543 6241 12544 6242 12544 6249 12544 6249 12545 6242 12545 8374 12545 6243 12546 6250 12546 6244 12546 6244 12547 6250 12547 6245 12547 6244 12548 6245 12548 6246 12548 6246 12549 6245 12549 8547 12549 6246 12550 8547 12550 6247 12550 6247 12551 8547 12551 8544 12551 6247 12552 8544 12552 6241 12552 6241 12553 8544 12553 8515 12553 8358 12554 6243 12554 8361 12554 8361 12555 6243 12555 6244 12555 8361 12556 6244 12556 8366 12556 8366 12557 6244 12557 6246 12557 8366 12558 6246 12558 6248 12558 6248 12559 6246 12559 6247 12559 6248 12560 6247 12560 6249 12560 6249 12561 6247 12561 6241 12561 6188 12562 6189 12562 6722 12562 6722 12563 6189 12563 8596 12563 6722 12564 8596 12564 6734 12564 8556 12565 6250 12565 6251 12565 6251 12566 6250 12566 6243 12566 6251 12567 6243 12567 8358 12567 8596 12568 8590 12568 6734 12568 6734 12569 8590 12569 6252 12569 6734 12570 6252 12570 8343 12570 8343 12571 6252 12571 8579 12571 8343 12572 8579 12572 8351 12572 8351 12573 8579 12573 8556 12573 8351 12574 8556 12574 8355 12574 8355 12575 8556 12575 6251 12575 8397 12576 6232 12576 8478 12576 6257 12577 6253 12577 6194 12577 6254 12578 8125 12578 8396 12578 6254 12579 8411 12579 6255 12579 6255 12580 8411 12580 8408 12580 6255 12581 8408 12581 8407 12581 8407 12582 8406 12582 6255 12582 6255 12583 8406 12583 6256 12583 6255 12584 6256 12584 8402 12584 6257 12585 6194 12585 8402 12585 8397 12586 8478 12586 8396 12586 8478 12587 6258 12587 8396 12587 8396 12588 6258 12588 8442 12588 8396 12589 8442 12589 6254 12589 6254 12590 8442 12590 8413 12590 6254 12591 8413 12591 8411 12591 6194 12592 6760 12592 6259 12592 8402 12593 6194 12593 6255 12593 6255 12594 6194 12594 6259 12594 6255 12595 6259 12595 6799 12595 15702 12596 15704 12596 6264 12596 6736 12597 6260 12597 6730 12597 6730 12598 6260 12598 6261 12598 6730 12599 6261 12599 6729 12599 6729 12600 6261 12600 15682 12600 6729 12601 15682 12601 6733 12601 6733 12602 15682 12602 6262 12602 6733 12603 6262 12603 6749 12603 6749 12604 6262 12604 15702 12604 6749 12605 15702 12605 6263 12605 6263 12606 15702 12606 6264 12606 6267 12607 6265 12607 6291 12607 6266 12608 15664 12608 6814 12608 6266 12609 6814 12609 6278 12609 15664 12610 10233 12610 6814 12610 6814 12611 10233 12611 10231 12611 6814 12612 10231 12612 6291 12612 6291 12613 10231 12613 10230 12613 6291 12614 10230 12614 6267 12614 10092 12615 10090 12615 6268 12615 10110 12616 10092 12616 15658 12616 15658 12617 10092 12617 6268 12617 15658 12618 6268 12618 6269 12618 6269 12619 6268 12619 10249 12619 6269 12620 10249 12620 15667 12620 15667 12621 10249 12621 10233 12621 15667 12622 10233 12622 6270 12622 6270 12623 10233 12623 15664 12623 10090 12624 6271 12624 6268 12624 6268 12625 6271 12625 10098 12625 6268 12626 10098 12626 10214 12626 10098 12627 6272 12627 10214 12627 10214 12628 6272 12628 10075 12628 10214 12629 10075 12629 6273 12629 6273 12630 10075 12630 6274 12630 6273 12631 6274 12631 10207 12631 10207 12632 6274 12632 6276 12632 6276 12633 6274 12633 6275 12633 6276 12634 6275 12634 10194 12634 10110 12635 15658 12635 10109 12635 10109 12636 15658 12636 15645 12636 10109 12637 15645 12637 10118 12637 10118 12638 15645 12638 15647 12638 10118 12639 15647 12639 10117 12639 10117 12640 15647 12640 15637 12640 10117 12641 15637 12641 4892 12641 15696 12642 6277 12642 6280 12642 6280 12643 6277 12643 6278 12643 6280 12644 6278 12644 6279 12644 6279 12645 6278 12645 6814 12645 6264 12646 15704 12646 6280 12646 6280 12647 15704 12647 15695 12647 6280 12648 15695 12648 15696 12648 10255 12649 10262 12649 5001 12649 5001 12650 10262 12650 6281 12650 5001 12651 6281 12651 6284 12651 10287 12652 6764 12652 6283 12652 6283 12653 6764 12653 6282 12653 6283 12654 6282 12654 10271 12654 10271 12655 6282 12655 6766 12655 10271 12656 6766 12656 6284 12656 6284 12657 6766 12657 6285 12657 6284 12658 6285 12658 5001 12658 5462 12659 5460 12659 6286 12659 6286 12660 6392 12660 6361 12660 11135 12661 6360 12661 6361 12661 6304 12662 6301 12662 12045 12662 6295 12663 6391 12663 6287 12663 6294 12664 6384 12664 5452 12664 10510 12665 10489 12665 6288 12665 6288 12666 10489 12666 6357 12666 10510 12667 6288 12667 5004 12667 5004 12668 6288 12668 6289 12668 5004 12669 6289 12669 6290 12669 6290 12670 6289 12670 6815 12670 6290 12671 6815 12671 6291 12671 6396 12672 6292 12672 6804 12672 5452 12673 6813 12673 6294 12673 6294 12674 6813 12674 6293 12674 6294 12675 6293 12675 6819 12675 5313 12676 6295 12676 6296 12676 6296 12677 6295 12677 6287 12677 6296 12678 6287 12678 12147 12678 12147 12679 6287 12679 12146 12679 6313 12680 6299 12680 6311 12680 6311 12681 6299 12681 12120 12681 6311 12682 12120 12682 6297 12682 6313 12683 6305 12683 6298 12683 6313 12684 6298 12684 6299 12684 6299 12685 6298 12685 6300 12685 6299 12686 6300 12686 6303 12686 12045 12687 6301 12687 6303 12687 6303 12688 6301 12688 6302 12688 6303 12689 6302 12689 6299 12689 12037 12690 6413 12690 12157 12690 6304 12691 12045 12691 12157 12691 12157 12692 12045 12692 12046 12692 12157 12693 12046 12693 12037 12693 6309 12694 11755 12694 12074 12694 6313 12695 11788 12695 6305 12695 6305 12696 11788 12696 11789 12696 6305 12697 11789 12697 6306 12697 6306 12698 11789 12698 11775 12698 6306 12699 11775 12699 6307 12699 6307 12700 11775 12700 11779 12700 11779 12701 6308 12701 6307 12701 6307 12702 6308 12702 6309 12702 6307 12703 6309 12703 12074 12703 6375 12704 11847 12704 11841 12704 11841 12705 6310 12705 6375 12705 6375 12706 6310 12706 6311 12706 6375 12707 6311 12707 6373 12707 6310 12708 11799 12708 6311 12708 6311 12709 11799 12709 6312 12709 6311 12710 6312 12710 6313 12710 6313 12711 6312 12711 6314 12711 6313 12712 6314 12712 11788 12712 6315 12713 11520 12713 6319 12713 11710 12714 11482 12714 11483 12714 11710 12715 11483 12715 6316 12715 6316 12716 11483 12716 6317 12716 6317 12717 11483 12717 6318 12717 6317 12718 6318 12718 6319 12718 6319 12719 6318 12719 6320 12719 6319 12720 6320 12720 6315 12720 11710 12721 11705 12721 11482 12721 11482 12722 11705 12722 6324 12722 11482 12723 6324 12723 11489 12723 11489 12724 6324 12724 6321 12724 11489 12725 6321 12725 11497 12725 11497 12726 6321 12726 11880 12726 11497 12727 11880 12727 11499 12727 11499 12728 11880 12728 11861 12728 11499 12729 11861 12729 6322 12729 6322 12730 11861 12730 6367 12730 6322 12731 6367 12731 6364 12731 11705 12732 6323 12732 6324 12732 6324 12733 6323 12733 6325 12733 6324 12734 6325 12734 11882 12734 11882 12735 6325 12735 6326 12735 11882 12736 6326 12736 11883 12736 11883 12737 6326 12737 6327 12737 11883 12738 6327 12738 6328 12738 6328 12739 6327 12739 11676 12739 6328 12740 11676 12740 6329 12740 6330 12741 6334 12741 6365 12741 6331 12742 6332 12742 6345 12742 6345 12743 6333 12743 6331 12743 6331 12744 6333 12744 6335 12744 6331 12745 6335 12745 6334 12745 6334 12746 6335 12746 6336 12746 6334 12747 6336 12747 6365 12747 6337 12748 6338 12748 6339 12748 6339 12749 6338 12749 6340 12749 6339 12750 6340 12750 6341 12750 6341 12751 6340 12751 11386 12751 6341 12752 11386 12752 6332 12752 6332 12753 11386 12753 11388 12753 6332 12754 11388 12754 6345 12754 6345 12755 11388 12755 11389 12755 6342 12756 6343 12756 11430 12756 11430 12757 6343 12757 6344 12757 11391 12758 6343 12758 6342 12758 11391 12759 6342 12759 11389 12759 11389 12760 6342 12760 11432 12760 11389 12761 11432 12761 6345 12761 6393 12762 11134 12762 11135 12762 6393 12763 6346 12763 11134 12763 11134 12764 6346 12764 6347 12764 11134 12765 6347 12765 11140 12765 11140 12766 6347 12766 10893 12766 11140 12767 10893 12767 6348 12767 6348 12768 10893 12768 10892 12768 6348 12769 10892 12769 10888 12769 10888 12770 5056 12770 6348 12770 6348 12771 5056 12771 6349 12771 6348 12772 6349 12772 5067 12772 6350 12773 6393 12773 10959 12773 10959 12774 6393 12774 6352 12774 6350 12775 10956 12775 6393 12775 6393 12776 10956 12776 6351 12776 6393 12777 6351 12777 6346 12777 6352 12778 10689 12778 10959 12778 10959 12779 10689 12779 10685 12779 10959 12780 10685 12780 10987 12780 10987 12781 10685 12781 6354 12781 10670 12782 10983 12782 6353 12782 6353 12783 10983 12783 10985 12783 6353 12784 10985 12784 6354 12784 6354 12785 10985 12785 10986 12785 6354 12786 10986 12786 10987 12786 10670 12787 10655 12787 10983 12787 10983 12788 10655 12788 5045 12788 10983 12789 5045 12789 10989 12789 10741 12790 10739 12790 6356 12790 10741 12791 6356 12791 10737 12791 10739 12792 10744 12792 6356 12792 6356 12793 10744 12793 6355 12793 6356 12794 6355 12794 6389 12794 6357 12795 10497 12795 6288 12795 6288 12796 10497 12796 10496 12796 6288 12797 10496 12797 6356 12797 6356 12798 10496 12798 10457 12798 6356 12799 10457 12799 6358 12799 6358 12800 6359 12800 6356 12800 6356 12801 6359 12801 5014 12801 6356 12802 5014 12802 10737 12802 6360 12803 6330 12803 6361 12803 6361 12804 6330 12804 6365 12804 6361 12805 6365 12805 6286 12805 6286 12806 6365 12806 6366 12806 6286 12807 6366 12807 5462 12807 5460 12808 6362 12808 6286 12808 6286 12809 6362 12809 6363 12809 6286 12810 6363 12810 6392 12810 6392 12811 6363 12811 5451 12811 6336 12812 6364 12812 6365 12812 6365 12813 6364 12813 6367 12813 6365 12814 6367 12814 6366 12814 6366 12815 6367 12815 6368 12815 6366 12816 6368 12816 6381 12816 6381 12817 6368 12817 6369 12817 11861 12818 6377 12818 6367 12818 6367 12819 6377 12819 6376 12819 6367 12820 6376 12820 6368 12820 6368 12821 6376 12821 6374 12821 6368 12822 6374 12822 6369 12822 6369 12823 6374 12823 6372 12823 6390 12824 6371 12824 6370 12824 6370 12825 6371 12825 5466 12825 5466 12826 6378 12826 6370 12826 6370 12827 6378 12827 6372 12827 6370 12828 6372 12828 6373 12828 6373 12829 6372 12829 6374 12829 6373 12830 6374 12830 6375 12830 6375 12831 6374 12831 6376 12831 6375 12832 6376 12832 11847 12832 11847 12833 6376 12833 6377 12833 6378 12834 6379 12834 6372 12834 6372 12835 6379 12835 6380 12835 6372 12836 6380 12836 6369 12836 6369 12837 6380 12837 5464 12837 6369 12838 5464 12838 6381 12838 6381 12839 5464 12839 6382 12839 6381 12840 6382 12840 6366 12840 6366 12841 6382 12841 6383 12841 6366 12842 6383 12842 5462 12842 5455 12843 6384 12843 6395 12843 6395 12844 6384 12844 6294 12844 6395 12845 6294 12845 6396 12845 6396 12846 6294 12846 6819 12846 6396 12847 6819 12847 6292 12847 6393 12848 6385 12848 6352 12848 6352 12849 6385 12849 6394 12849 6352 12850 6394 12850 6386 12850 6386 12851 6394 12851 6387 12851 6386 12852 6387 12852 6388 12852 6355 12853 10689 12853 6389 12853 6389 12854 10689 12854 6352 12854 6389 12855 6352 12855 6356 12855 6356 12856 6352 12856 6386 12856 6356 12857 6386 12857 6288 12857 6288 12858 6386 12858 6388 12858 6288 12859 6388 12859 6289 12859 6297 12860 12109 12860 6311 12860 6311 12861 12109 12861 12146 12861 6311 12862 12146 12862 6373 12862 6373 12863 12146 12863 6287 12863 6373 12864 6287 12864 6370 12864 6370 12865 6287 12865 6391 12865 6370 12866 6391 12866 6390 12866 6390 12867 6391 12867 5317 12867 6390 12868 5317 12868 5340 12868 11135 12869 6361 12869 6393 12869 6393 12870 6361 12870 6392 12870 6393 12871 6392 12871 6385 12871 6385 12872 6392 12872 5451 12872 6385 12873 5451 12873 6394 12873 6394 12874 5451 12874 5455 12874 6394 12875 5455 12875 6387 12875 6387 12876 5455 12876 6395 12876 6387 12877 6395 12877 6388 12877 6388 12878 6395 12878 6396 12878 6388 12879 6396 12879 6289 12879 6289 12880 6396 12880 6804 12880 6289 12881 6804 12881 6815 12881 11353 12882 11355 12882 11230 12882 11230 12883 11355 12883 6397 12883 6397 12884 11355 12884 6398 12884 6397 12885 6398 12885 6400 12885 6400 12886 6398 12886 6399 12886 6400 12887 6399 12887 11222 12887 11222 12888 6399 12888 11392 12888 11222 12889 11392 12889 6401 12889 6401 12890 11392 12890 6338 12890 6401 12891 6338 12891 6337 12891 6402 12892 12074 12892 11755 12892 6404 12893 11763 12893 12048 12893 6402 12894 11755 12894 11743 12894 6402 12895 11743 12895 6403 12895 6403 12896 11743 12896 11742 12896 6403 12897 11742 12897 12095 12897 12095 12898 11742 12898 6404 12898 12095 12899 6404 12899 12079 12899 12079 12900 6404 12900 12048 12900 6405 12901 11852 12901 11899 12901 6329 12902 11676 12902 11905 12902 11905 12903 11676 12903 11634 12903 11905 12904 11634 12904 11899 12904 11899 12905 11634 12905 11632 12905 11899 12906 11632 12906 6405 12906 11558 12907 6447 12907 6406 12907 6407 12908 6319 12908 11520 12908 6407 12909 11520 12909 11562 12909 6407 12910 11562 12910 6408 12910 6408 12911 11562 12911 11557 12911 6408 12912 11557 12912 11718 12912 11718 12913 11557 12913 11558 12913 11718 12914 11558 12914 6406 12914 12255 12915 6409 12915 12256 12915 12256 12916 6409 12916 6479 12916 6479 12917 6409 12917 6478 12917 6478 12918 6409 12918 6410 12918 6410 12919 12238 12919 6478 12919 6478 12920 12238 12920 12237 12920 6478 12921 12237 12921 6411 12921 6411 12922 12237 12922 12179 12922 6411 12923 12179 12923 11992 12923 11992 12924 12179 12924 12180 12924 11992 12925 12180 12925 6412 12925 6412 12926 12180 12926 6413 12926 6412 12927 6413 12927 12037 12927 6453 12928 11505 12928 11453 12928 6414 12929 6453 12929 11453 12929 6414 12930 11453 12930 6415 12930 6415 12931 11453 12931 11460 12931 6415 12932 11460 12932 6416 12932 6416 12933 11460 12933 6417 12933 6416 12934 6417 12934 11340 12934 11340 12935 6417 12935 11441 12935 11340 12936 11441 12936 6343 12936 6343 12937 11441 12937 6418 12937 6343 12938 6418 12938 6344 12938 5293 12939 5294 12939 6512 12939 6445 12940 6431 12940 6511 12940 6419 12941 6492 12941 5027 12941 6420 12942 10812 12942 6492 12942 6492 12943 10812 12943 6421 12943 6492 12944 6421 12944 5027 12944 10808 12945 6422 12945 6423 12945 6423 12946 6422 12946 6424 12946 6423 12947 6424 12947 10806 12947 10806 12948 6424 12948 10804 12948 6510 12949 10768 12949 6489 12949 6489 12950 10768 12950 6425 12950 6489 12951 6425 12951 6492 12951 6492 12952 6425 12952 6426 12952 6492 12953 6426 12953 6420 12953 11014 12954 11070 12954 6427 12954 6424 12955 11015 12955 10804 12955 10804 12956 11015 12956 11014 12956 10804 12957 11014 12957 10803 12957 10803 12958 11014 12958 6427 12958 10803 12959 6427 12959 5047 12959 11000 12960 6422 12960 11066 12960 11066 12961 6422 12961 6511 12961 11066 12962 6511 12962 6430 12962 11000 12963 11022 12963 6422 12963 6422 12964 11022 12964 6428 12964 6422 12965 6428 12965 6424 12965 6424 12966 6428 12966 6429 12966 6424 12967 6429 12967 11015 12967 6511 12968 6431 12968 6430 12968 6430 12969 6431 12969 11332 12969 6430 12970 11332 12970 11064 12970 11064 12971 11332 12971 6432 12971 11064 12972 6432 12972 6433 12972 6433 12973 6432 12973 11322 12973 6433 12974 11322 12974 11315 12974 6437 12975 6442 12975 11315 12975 11315 12976 6442 12976 11063 12976 11315 12977 11063 12977 6433 12977 11353 12978 11230 12978 6437 12978 6437 12979 11230 12979 6434 12979 6437 12980 6434 12980 6435 12980 6435 12981 6436 12981 6437 12981 6437 12982 6436 12982 6438 12982 6437 12983 6438 12983 11229 12983 11229 12984 6439 12984 6437 12984 6437 12985 6439 12985 6440 12985 6437 12986 6440 12986 11212 12986 11212 12987 6441 12987 6437 12987 6437 12988 6441 12988 11061 12988 6437 12989 11061 12989 6442 12989 11646 12990 6443 12990 6444 12990 6444 12991 6443 12991 11283 12991 6444 12992 11283 12992 11286 12992 6445 12993 6511 12993 6446 12993 6446 12994 6511 12994 6455 12994 6446 12995 6455 12995 11287 12995 11287 12996 6455 12996 6457 12996 11287 12997 6457 12997 11286 12997 11286 12998 6457 12998 11648 12998 11286 12999 11648 12999 6444 12999 11644 13000 11643 13000 6447 13000 6447 13001 11643 13001 11686 13001 6447 13002 11686 13002 6406 13002 6449 13003 6448 13003 11644 13003 11644 13004 6448 13004 11537 13004 11644 13005 11537 13005 11646 13005 6449 13006 11644 13006 6447 13006 11537 13007 11539 13007 11646 13007 11646 13008 11539 13008 6450 13008 11646 13009 6450 13009 6443 13009 6443 13010 6450 13010 6451 13010 6443 13011 6451 13011 11528 13011 11505 13012 6443 13012 6452 13012 6452 13013 6443 13013 11528 13013 6453 13014 6454 13014 11505 13014 11505 13015 6454 13015 11281 13015 11505 13016 11281 13016 6443 13016 11585 13017 11584 13017 6464 13017 6464 13018 11584 13018 11577 13018 11577 13019 11578 13019 6464 13019 6464 13020 11578 13020 11629 13020 6464 13021 11629 13021 6455 13021 6455 13022 11629 13022 6456 13022 6455 13023 6456 13023 6457 13023 11852 13024 6405 13024 11615 13024 11615 13025 11608 13025 11852 13025 11852 13026 11608 13026 11596 13026 11852 13027 11596 13027 6462 13027 6462 13028 11596 13028 6458 13028 6462 13029 6458 13029 6464 13029 6464 13030 6458 13030 6459 13030 6464 13031 6459 13031 11585 13031 12048 13032 11763 13032 6460 13032 6460 13033 11763 13033 12004 13033 11763 13034 12019 13034 12003 13034 11763 13035 12003 13035 12004 13035 11831 13036 6461 13036 11830 13036 11830 13037 6461 13037 12019 13037 11830 13038 12019 13038 11762 13038 11762 13039 12019 13039 11763 13039 6465 13040 11816 13040 6462 13040 6462 13041 11816 13041 6463 13041 11850 13042 11852 13042 6462 13042 11850 13043 6462 13043 11859 13043 11859 13044 6462 13044 6463 13044 6475 13045 6477 13045 6464 13045 6464 13046 6477 13046 12035 13046 6464 13047 12035 13047 12036 13047 11831 13048 6465 13048 6461 13048 6461 13049 6465 13049 6462 13049 6461 13050 6462 13050 6466 13050 6466 13051 6462 13051 6464 13051 6466 13052 6464 13052 6467 13052 6467 13053 6464 13053 12036 13053 6470 13054 6472 13054 5294 13054 5300 13055 6468 13055 5296 13055 5296 13056 6468 13056 6471 13056 5296 13057 6471 13057 6469 13057 6470 13058 5294 13058 6471 13058 6471 13059 5294 13059 5297 13059 6471 13060 5297 13060 6469 13060 6472 13061 6473 13061 5294 13061 5294 13062 6473 13062 11983 13062 5294 13063 11983 13063 6512 13063 6512 13064 11983 13064 6474 13064 6512 13065 6474 13065 6475 13065 6475 13066 6474 13066 6476 13066 6475 13067 6476 13067 6477 13067 6478 13068 6480 13068 6479 13068 6479 13069 6480 13069 11948 13069 6479 13070 11948 13070 6481 13070 6481 13071 11948 13071 11947 13071 6481 13072 11947 13072 5300 13072 5300 13073 11947 13073 11933 13073 5300 13074 11933 13074 6468 13074 6509 13075 6483 13075 6778 13075 6778 13076 6483 13076 6783 13076 6783 13077 6483 13077 6482 13077 6482 13078 6483 13078 6484 13078 6482 13079 6484 13079 6487 13079 6487 13080 6484 13080 10545 13080 6487 13081 10545 13081 6485 13081 6485 13082 6486 13082 6487 13082 6487 13083 6486 13083 6488 13083 6487 13084 6488 13084 6796 13084 6796 13085 6488 13085 5018 13085 6796 13086 5018 13086 5001 13086 6493 13087 6489 13087 6490 13087 6490 13088 6489 13088 6492 13088 6490 13089 6492 13089 6491 13089 6491 13090 6492 13090 6419 13090 6509 13091 6489 13091 6483 13091 6483 13092 6489 13092 6493 13092 6483 13093 6493 13093 6484 13093 6484 13094 6493 13094 6494 13094 6484 13095 6494 13095 10545 13095 6495 13096 5292 13096 6496 13096 6496 13097 5292 13097 6513 13097 6496 13098 6513 13098 6497 13098 6497 13099 6513 13099 6498 13099 6497 13100 6498 13100 6500 13100 6500 13101 6498 13101 6499 13101 6500 13102 6499 13102 6824 13102 6824 13103 6499 13103 6501 13103 6824 13104 6501 13104 6502 13104 6502 13105 6501 13105 6503 13105 6502 13106 6503 13106 6504 13106 6504 13107 6503 13107 6505 13107 6504 13108 6505 13108 6827 13108 6827 13109 6505 13109 6506 13109 6827 13110 6506 13110 6507 13110 6778 13111 6759 13111 6509 13111 6509 13112 6759 13112 6508 13112 6509 13113 6508 13113 6489 13113 6489 13114 6508 13114 6422 13114 6489 13115 6422 13115 6510 13115 6510 13116 6422 13116 10808 13116 6759 13117 6507 13117 6508 13117 6508 13118 6507 13118 6506 13118 6508 13119 6506 13119 6422 13119 6422 13120 6506 13120 6505 13120 6422 13121 6505 13121 6511 13121 6511 13122 6505 13122 6503 13122 6511 13123 6503 13123 6455 13123 6455 13124 6503 13124 6501 13124 6455 13125 6501 13125 6464 13125 6464 13126 6501 13126 6499 13126 6464 13127 6499 13127 6475 13127 6475 13128 6499 13128 6498 13128 6475 13129 6498 13129 6512 13129 6512 13130 6498 13130 6513 13130 6512 13131 6513 13131 5293 13131 5293 13132 6513 13132 5292 13132 6514 13133 6527 13133 6543 13133 6515 13134 6566 13134 6537 13134 6537 13135 6566 13135 6516 13135 6537 13136 6516 13136 14230 13136 6536 13137 6520 13137 6517 13137 6536 13138 6517 13138 6535 13138 6536 13139 14242 13139 14244 13139 14244 13140 14211 13140 6536 13140 6536 13141 14211 13141 6518 13141 6536 13142 6518 13142 6520 13142 6517 13143 6521 13143 6519 13143 6519 13144 6521 13144 7093 13144 6519 13145 7093 13145 7025 13145 6520 13146 4923 13146 6517 13146 6517 13147 4923 13147 4925 13147 6517 13148 4925 13148 6521 13148 6521 13149 4925 13149 4975 13149 6521 13150 4975 13150 7093 13150 7025 13151 6541 13151 6519 13151 6519 13152 6541 13152 6542 13152 6519 13153 6542 13153 6517 13153 6517 13154 6542 13154 6544 13154 6517 13155 6544 13155 6535 13155 6537 13156 6522 13156 6538 13156 6223 13157 6523 13157 6524 13157 6524 13158 6523 13158 6525 13158 6524 13159 6525 13159 6224 13159 6224 13160 6525 13160 6526 13160 6527 13161 6858 13161 6543 13161 6543 13162 6858 13162 6528 13162 6543 13163 6528 13163 6529 13163 6529 13164 6528 13164 6855 13164 6529 13165 6855 13165 6530 13165 6530 13166 6855 13166 6531 13166 6530 13167 6531 13167 6856 13167 6538 13168 6526 13168 6537 13168 6537 13169 6526 13169 6525 13169 6537 13170 6525 13170 6515 13170 6515 13171 6525 13171 6523 13171 6515 13172 6523 13172 6532 13172 6532 13173 6523 13173 6223 13173 6532 13174 6223 13174 6533 13174 6547 13175 6534 13175 6546 13175 6546 13176 6534 13176 6538 13176 6546 13177 6538 13177 6545 13177 6545 13178 6538 13178 6522 13178 6545 13179 6522 13179 6535 13179 6535 13180 6522 13180 6537 13180 6535 13181 6537 13181 6536 13181 6536 13182 6537 13182 14230 13182 6536 13183 14230 13183 14242 13183 6534 13184 6221 13184 6538 13184 6538 13185 6221 13185 6539 13185 6538 13186 6539 13186 6526 13186 6526 13187 6539 13187 6540 13187 6526 13188 6540 13188 6224 13188 6541 13189 6514 13189 6542 13189 6542 13190 6514 13190 6543 13190 6542 13191 6543 13191 6544 13191 6544 13192 6543 13192 6529 13192 6544 13193 6529 13193 6535 13193 6535 13194 6529 13194 6530 13194 6535 13195 6530 13195 6545 13195 6545 13196 6530 13196 6856 13196 6545 13197 6856 13197 6546 13197 6546 13198 6856 13198 6219 13198 6546 13199 6219 13199 6547 13199 6560 13200 14078 13200 6876 13200 15559 13201 15553 13201 6548 13201 6548 13202 14301 13202 15559 13202 15559 13203 14301 13203 14298 13203 15559 13204 14298 13204 4875 13204 6549 13205 14274 13205 14069 13205 6549 13206 14069 13206 6550 13206 6552 13207 6555 13207 14273 13207 14273 13208 6551 13208 6552 13208 6552 13209 6551 13209 14272 13209 6552 13210 14272 13210 15553 13210 15553 13211 14272 13211 14271 13211 15553 13212 14271 13212 6548 13212 6550 13213 14069 13213 14249 13213 14249 13214 14069 13214 14063 13214 14249 13215 14063 13215 6553 13215 6553 13216 14063 13216 6554 13216 6553 13217 6554 13217 4884 13217 14274 13218 6555 13218 14069 13218 14069 13219 6555 13219 6552 13219 14069 13220 6552 13220 14073 13220 14073 13221 6552 13221 6556 13221 6556 13222 6552 13222 15550 13222 6556 13223 15550 13223 14078 13223 15550 13224 6557 13224 14078 13224 14078 13225 6557 13225 15533 13225 14078 13226 15533 13226 6876 13226 15533 13227 15532 13227 6876 13227 6876 13228 15532 13228 6563 13228 6876 13229 6563 13229 6558 13229 4990 13230 4992 13230 6559 13230 4990 13231 6559 13231 6876 13231 6876 13232 6559 13232 14076 13232 6876 13233 14076 13233 6560 13233 6205 13234 6864 13234 6561 13234 6561 13235 6864 13235 6562 13235 6563 13236 15530 13236 6558 13236 6558 13237 15530 13237 15525 13237 6558 13238 15525 13238 6562 13238 6562 13239 15525 13239 6564 13239 6562 13240 6564 13240 6561 13240 6533 13241 14185 13241 6532 13241 6532 13242 14185 13242 6565 13242 6532 13243 6565 13243 6515 13243 6515 13244 6565 13244 14183 13244 6515 13245 14183 13245 6566 13245 12587 13246 6567 13246 6568 13246 12278 13247 7041 13247 12640 13247 12629 13248 12587 13248 6568 13248 12629 13249 6568 13249 12641 13249 12641 13250 6568 13250 12274 13250 12641 13251 12274 13251 12640 13251 6569 13252 12278 13252 12640 13252 6569 13253 12640 13253 12271 13253 12271 13254 12640 13254 12274 13254 12963 13255 12954 13255 12653 13255 12653 13256 12954 13256 12955 13256 12653 13257 12955 13257 6570 13257 6570 13258 12955 13258 6966 13258 12653 13259 6571 13259 12963 13259 12963 13260 6571 13260 6572 13260 12963 13261 6572 13261 12960 13261 12960 13262 6572 13262 12976 13262 7048 13263 7049 13263 12518 13263 12518 13264 7049 13264 6573 13264 12518 13265 6573 13265 6574 13265 6574 13266 6573 13266 6575 13266 6574 13267 6575 13267 6576 13267 6576 13268 6575 13268 6577 13268 6582 13269 6578 13269 12442 13269 12442 13270 6578 13270 10008 13270 12442 13271 10008 13271 7100 13271 7100 13272 10008 13272 9994 13272 7100 13273 9994 13273 6579 13273 6579 13274 9994 13274 6580 13274 6581 13275 6910 13275 9947 13275 6581 13276 9947 13276 9949 13276 6581 13277 9949 13277 12444 13277 12444 13278 9949 13278 9952 13278 12444 13279 9952 13279 6582 13279 6582 13280 9952 13280 10011 13280 6582 13281 10011 13281 6578 13281 13211 13282 6583 13282 12986 13282 12986 13283 6583 13283 6584 13283 13030 13284 13224 13284 13211 13284 12986 13285 6585 13285 13211 13285 13211 13286 6585 13286 6586 13286 13211 13287 6586 13287 13030 13287 6587 13288 13002 13288 6584 13288 6583 13289 13206 13289 6584 13289 6584 13290 13206 13290 13170 13290 6584 13291 13170 13291 6587 13291 6607 13292 6588 13292 8842 13292 8119 13293 6655 13293 8756 13293 8756 13294 8759 13294 8119 13294 8119 13295 8759 13295 6589 13295 8119 13296 6589 13296 6590 13296 6590 13297 6589 13297 8760 13297 6590 13298 8760 13298 6591 13298 6591 13299 8760 13299 6592 13299 6591 13300 6592 13300 6593 13300 6593 13301 6592 13301 6594 13301 6593 13302 6594 13302 8121 13302 8121 13303 6594 13303 6596 13303 8121 13304 6596 13304 6595 13304 6595 13305 6596 13305 8763 13305 6595 13306 8763 13306 6597 13306 6597 13307 8763 13307 8764 13307 6597 13308 8764 13308 8014 13308 8014 13309 8764 13309 8017 13309 8764 13310 6598 13310 8017 13310 8017 13311 6598 13311 8766 13311 8017 13312 8766 13312 8018 13312 8018 13313 8766 13313 6599 13313 8018 13314 6599 13314 6601 13314 6599 13315 6600 13315 6601 13315 6601 13316 6600 13316 8849 13316 6601 13317 8849 13317 6602 13317 6602 13318 8849 13318 8846 13318 6602 13319 8846 13319 6603 13319 8846 13320 6604 13320 6603 13320 6603 13321 6604 13321 8845 13321 6603 13322 8845 13322 6605 13322 6605 13323 8845 13323 8844 13323 6605 13324 8844 13324 8022 13324 8022 13325 8844 13325 6588 13325 8022 13326 6588 13326 6606 13326 6606 13327 6588 13327 6607 13327 8840 13328 8027 13328 8842 13328 8842 13329 8027 13329 8025 13329 8842 13330 8025 13330 6607 13330 6609 13331 6608 13331 8836 13331 8836 13332 6608 13332 8027 13332 8836 13333 8027 13333 8837 13333 8837 13334 8027 13334 8840 13334 6609 13335 8836 13335 6610 13335 6610 13336 8836 13336 6611 13336 6610 13337 6611 13337 8031 13337 6611 13338 6612 13338 8031 13338 8031 13339 6612 13339 6613 13339 8031 13340 6613 13340 6614 13340 6614 13341 6613 13341 8835 13341 6614 13342 8835 13342 6615 13342 8835 13343 6616 13343 6615 13343 6615 13344 6616 13344 8834 13344 6615 13345 8834 13345 6617 13345 6617 13346 8834 13346 6618 13346 6618 13347 8834 13347 6620 13347 6618 13348 6620 13348 6619 13348 6620 13349 8853 13349 6619 13349 6619 13350 8853 13350 6621 13350 6619 13351 6621 13351 6623 13351 6621 13352 6622 13352 6623 13352 6623 13353 6622 13353 6624 13353 6624 13354 6622 13354 7897 13354 7897 13355 6622 13355 8659 13355 7897 13356 8659 13356 6626 13356 8659 13357 6625 13357 6626 13357 6626 13358 6625 13358 6627 13358 6626 13359 6627 13359 7900 13359 7900 13360 6627 13360 6628 13360 7900 13361 6628 13361 7902 13361 7902 13362 6628 13362 7904 13362 6628 13363 6629 13363 7904 13363 7904 13364 6629 13364 6630 13364 7904 13365 6630 13365 7905 13365 7905 13366 6630 13366 6631 13366 7905 13367 6631 13367 7906 13367 7906 13368 6631 13368 6632 13368 7906 13369 6632 13369 7908 13369 7908 13370 6632 13370 6633 13370 7908 13371 6633 13371 6634 13371 6634 13372 6633 13372 6635 13372 6634 13373 6635 13373 7912 13373 7912 13374 6635 13374 8654 13374 7912 13375 8654 13375 6636 13375 6636 13376 8654 13376 8652 13376 6636 13377 8652 13377 7914 13377 7914 13378 8652 13378 6637 13378 6637 13379 8652 13379 6639 13379 6639 13380 8652 13380 6638 13380 6639 13381 6638 13381 6641 13381 7918 13382 7917 13382 6640 13382 6640 13383 7917 13383 6641 13383 6640 13384 6641 13384 8664 13384 8664 13385 6641 13385 6638 13385 6640 13386 8661 13386 7918 13386 7918 13387 8661 13387 6642 13387 7918 13388 6642 13388 6643 13388 6643 13389 6642 13389 6644 13389 6643 13390 6644 13390 6645 13390 6645 13391 6644 13391 6650 13391 7930 13392 7928 13392 6646 13392 6646 13393 7928 13393 7927 13393 6646 13394 7927 13394 8741 13394 8741 13395 7927 13395 6647 13395 8741 13396 6647 13396 8743 13396 8743 13397 6647 13397 6648 13397 8743 13398 6648 13398 6649 13398 6649 13399 6648 13399 7923 13399 6649 13400 7923 13400 6650 13400 6650 13401 7923 13401 7921 13401 6650 13402 7921 13402 6645 13402 7930 13403 6646 13403 7931 13403 7931 13404 6646 13404 6652 13404 7931 13405 6652 13405 6651 13405 6652 13406 6653 13406 6651 13406 6651 13407 6653 13407 6654 13407 6651 13408 6654 13408 7933 13408 7933 13409 6654 13409 8756 13409 7933 13410 8756 13410 6655 13410 7693 13411 6656 13411 8060 13411 8060 13412 6656 13412 8061 13412 8061 13413 6656 13413 6657 13413 8061 13414 6657 13414 8063 13414 8063 13415 6657 13415 6658 13415 8063 13416 6658 13416 8064 13416 6659 13417 6661 13417 6660 13417 6660 13418 6661 13418 7990 13418 7990 13419 6661 13419 6662 13419 7990 13420 6662 13420 7989 13420 6658 13421 7669 13421 8064 13421 8064 13422 7669 13422 6663 13422 8064 13423 6663 13423 6664 13423 6664 13424 6663 13424 7791 13424 6664 13425 7791 13425 6665 13425 6665 13426 7791 13426 6666 13426 6665 13427 6666 13427 8006 13427 8006 13428 6666 13428 7811 13428 8006 13429 7811 13429 6667 13429 6667 13430 7811 13430 6669 13430 6667 13431 6669 13431 8004 13431 8004 13432 6669 13432 8001 13432 6660 13433 7992 13433 6659 13433 6659 13434 7992 13434 6668 13434 6659 13435 6668 13435 6677 13435 6677 13436 6668 13436 7993 13436 6669 13437 6670 13437 8001 13437 8001 13438 6670 13438 6671 13438 8001 13439 6671 13439 6672 13439 6672 13440 6671 13440 7808 13440 6672 13441 7808 13441 6673 13441 6673 13442 7808 13442 7805 13442 6673 13443 7805 13443 6674 13443 6674 13444 7805 13444 6675 13444 6674 13445 6675 13445 7997 13445 7997 13446 6675 13446 7803 13446 7997 13447 7803 13447 7996 13447 7996 13448 7803 13448 7802 13448 7996 13449 7802 13449 7993 13449 7993 13450 7802 13450 6676 13450 7993 13451 6676 13451 6677 13451 8060 13452 8058 13452 7693 13452 7693 13453 8058 13453 8057 13453 7693 13454 8057 13454 6678 13454 6678 13455 8057 13455 8055 13455 6678 13456 8055 13456 7695 13456 7695 13457 8055 13457 6679 13457 7695 13458 6679 13458 6680 13458 6680 13459 6679 13459 8053 13459 6680 13460 8053 13460 7697 13460 7697 13461 8053 13461 6681 13461 7697 13462 6681 13462 7698 13462 7698 13463 6681 13463 8051 13463 7698 13464 8051 13464 7699 13464 7699 13465 8051 13465 6682 13465 7699 13466 6682 13466 6683 13466 6683 13467 6682 13467 8048 13467 6683 13468 8048 13468 7701 13468 7701 13469 8048 13469 6684 13469 7701 13470 6684 13470 7702 13470 7702 13471 6684 13471 8047 13471 7702 13472 8047 13472 6685 13472 6685 13473 8047 13473 8046 13473 6685 13474 8046 13474 6686 13474 6686 13475 8046 13475 6687 13475 6686 13476 6687 13476 6688 13476 6688 13477 6687 13477 8043 13477 6688 13478 8043 13478 7704 13478 7704 13479 8043 13479 8042 13479 7704 13480 8042 13480 7706 13480 7706 13481 8042 13481 8041 13481 7706 13482 8041 13482 6689 13482 6689 13483 8041 13483 6691 13483 6689 13484 6691 13484 6690 13484 6690 13485 6691 13485 6692 13485 6690 13486 6692 13486 6693 13486 6693 13487 6692 13487 6694 13487 6693 13488 6694 13488 7709 13488 7709 13489 6694 13489 6695 13489 7709 13490 6695 13490 7711 13490 7711 13491 6695 13491 8039 13491 7711 13492 8039 13492 7712 13492 7712 13493 8039 13493 6696 13493 7712 13494 6696 13494 6714 13494 7989 13495 6662 13495 6697 13495 6697 13496 6662 13496 7799 13496 6697 13497 7799 13497 7987 13497 7987 13498 7799 13498 6698 13498 7987 13499 6698 13499 6699 13499 6699 13500 6698 13500 7797 13500 6699 13501 7797 13501 6700 13501 6700 13502 7797 13502 6701 13502 6700 13503 6701 13503 7984 13503 7984 13504 6701 13504 7795 13504 7984 13505 7795 13505 6702 13505 6702 13506 7795 13506 6704 13506 6702 13507 6704 13507 6703 13507 6703 13508 6704 13508 6705 13508 6703 13509 6705 13509 6707 13509 6707 13510 6705 13510 6706 13510 6707 13511 6706 13511 7981 13511 7981 13512 6706 13512 6708 13512 7981 13513 6708 13513 7979 13513 7979 13514 6708 13514 6709 13514 7979 13515 6709 13515 6710 13515 6710 13516 6709 13516 6712 13516 6710 13517 6712 13517 6711 13517 6711 13518 6712 13518 7783 13518 6711 13519 7783 13519 6714 13519 6714 13520 7783 13520 6713 13520 6714 13521 6713 13521 7712 13521 6720 13522 6715 13522 6716 13522 6716 13523 6715 13523 6717 13523 6716 13524 6717 13524 6718 13524 6718 13525 6717 13525 6719 13525 6718 13526 6719 13526 6722 13526 6722 13527 6719 13527 6188 13527 6738 13528 6720 13528 6731 13528 6731 13529 6720 13529 6716 13529 6731 13530 6716 13530 6721 13530 6721 13531 6716 13531 6718 13531 6721 13532 6718 13532 6734 13532 6734 13533 6718 13533 6722 13533 6738 13534 6731 13534 6732 13534 6738 13535 6732 13535 6723 13535 6723 13536 6732 13536 6724 13536 6723 13537 6724 13537 6725 13537 6725 13538 6724 13538 6733 13538 6725 13539 6733 13539 6749 13539 6721 13540 6734 13540 6726 13540 6726 13541 6734 13541 6735 13541 6726 13542 6735 13542 6727 13542 6727 13543 6735 13543 6728 13543 6727 13544 6728 13544 6729 13544 6729 13545 6728 13545 6730 13545 6731 13546 6721 13546 6732 13546 6732 13547 6721 13547 6726 13547 6732 13548 6726 13548 6724 13548 6724 13549 6726 13549 6727 13549 6724 13550 6727 13550 6733 13550 6733 13551 6727 13551 6729 13551 6734 13552 8343 13552 8337 13552 6734 13553 8337 13553 6735 13553 6735 13554 8337 13554 8339 13554 6735 13555 8339 13555 6728 13555 6736 13556 6730 13556 8334 13556 8334 13557 6730 13557 6728 13557 8334 13558 6728 13558 8336 13558 8336 13559 6728 13559 8339 13559 4528 13560 8128 13560 4514 13560 4514 13561 8128 13561 6737 13561 4514 13562 6737 13562 4515 13562 6751 13563 5449 13563 6846 13563 6738 13564 6751 13564 6720 13564 6720 13565 6751 13565 6846 13565 6720 13566 6846 13566 6715 13566 4997 13567 6748 13567 6785 13567 6785 13568 6748 13568 6739 13568 6785 13569 6739 13569 6786 13569 6786 13570 6739 13570 6740 13570 6794 13571 6793 13571 6746 13571 6746 13572 6793 13572 6788 13572 6746 13573 6788 13573 6739 13573 6739 13574 6788 13574 6787 13574 6739 13575 6787 13575 6740 13575 6794 13576 6746 13576 6771 13576 6771 13577 6746 13577 6255 13577 6771 13578 6255 13578 6799 13578 6737 13579 8128 13579 6745 13579 6745 13580 8128 13580 6741 13580 8125 13581 6254 13581 8130 13581 8130 13582 6254 13582 6745 13582 8130 13583 6745 13583 8126 13583 8126 13584 6745 13584 6741 13584 4895 13585 6742 13585 6747 13585 6747 13586 6742 13586 6744 13586 4515 13587 6737 13587 6743 13587 6743 13588 6737 13588 6745 13588 6743 13589 6745 13589 4511 13589 4511 13590 6745 13590 6747 13590 4511 13591 6747 13591 4512 13591 4512 13592 6747 13592 6744 13592 6254 13593 6255 13593 6745 13593 6745 13594 6255 13594 6746 13594 6745 13595 6746 13595 6747 13595 6747 13596 6746 13596 6739 13596 6747 13597 6739 13597 4895 13597 4895 13598 6739 13598 6748 13598 6749 13599 6263 13599 6752 13599 6749 13600 6752 13600 6725 13600 6725 13601 6752 13601 6750 13601 6725 13602 6750 13602 6723 13602 6751 13603 6738 13603 6723 13603 6723 13604 6750 13604 6751 13604 6751 13605 6750 13605 6805 13605 6751 13606 6805 13606 5449 13606 6752 13607 6753 13607 6754 13607 6754 13608 6808 13608 6752 13608 6752 13609 6808 13609 6755 13609 6752 13610 6755 13610 6750 13610 6750 13611 6755 13611 6756 13611 6750 13612 6756 13612 6805 13612 6263 13613 6264 13613 6802 13613 6263 13614 6802 13614 6752 13614 6752 13615 6802 13615 6757 13615 6752 13616 6757 13616 6753 13616 6758 13617 6759 13617 6780 13617 6259 13618 6760 13618 6761 13618 6259 13619 6761 13619 6799 13619 6860 13620 6758 13620 6859 13620 6859 13621 6758 13621 6780 13621 6859 13622 6780 13622 6762 13622 6762 13623 6780 13623 6779 13623 6762 13624 6779 13624 6761 13624 6761 13625 6779 13625 6763 13625 6761 13626 6763 13626 6799 13626 6782 13627 6482 13627 6487 13627 10330 13628 10354 13628 6769 13628 6776 13629 6775 13629 6765 13629 10287 13630 6776 13630 6764 13630 6764 13631 6776 13631 6765 13631 6764 13632 6765 13632 6282 13632 6282 13633 6765 13633 6766 13633 6285 13634 6766 13634 6795 13634 6795 13635 6766 13635 6765 13635 6795 13636 6765 13636 6797 13636 6797 13637 6765 13637 6775 13637 6767 13638 6768 13638 10331 13638 10330 13639 6769 13639 10331 13639 10331 13640 6769 13640 6767 13640 6767 13641 6769 13641 6791 13641 6767 13642 6791 13642 6774 13642 4999 13643 6784 13643 6770 13643 6770 13644 6784 13644 6789 13644 6770 13645 6789 13645 10354 13645 6772 13646 6794 13646 6771 13646 6771 13647 6799 13647 6772 13647 6772 13648 6799 13648 6798 13648 6772 13649 6798 13649 6791 13649 6791 13650 6798 13650 6773 13650 6791 13651 6773 13651 6774 13651 6774 13652 6773 13652 6775 13652 6774 13653 6775 13653 6767 13653 6767 13654 6775 13654 6776 13654 6767 13655 6776 13655 6768 13655 6780 13656 6759 13656 6777 13656 6777 13657 6759 13657 6778 13657 6777 13658 6778 13658 6783 13658 6779 13659 6780 13659 6781 13659 6781 13660 6780 13660 6777 13660 6781 13661 6777 13661 6782 13661 6782 13662 6777 13662 6783 13662 6782 13663 6783 13663 6482 13663 4999 13664 4997 13664 6784 13664 6784 13665 4997 13665 6785 13665 6784 13666 6785 13666 6789 13666 6789 13667 6785 13667 6786 13667 6789 13668 6786 13668 6790 13668 6786 13669 6740 13669 6790 13669 6790 13670 6740 13670 6787 13670 6790 13671 6787 13671 6792 13671 6792 13672 6787 13672 6788 13672 6792 13673 6788 13673 6793 13673 10354 13674 6789 13674 6769 13674 6769 13675 6789 13675 6790 13675 6769 13676 6790 13676 6791 13676 6791 13677 6790 13677 6792 13677 6791 13678 6792 13678 6772 13678 6772 13679 6792 13679 6793 13679 6772 13680 6793 13680 6794 13680 5001 13681 6285 13681 6796 13681 6796 13682 6285 13682 6795 13682 6796 13683 6795 13683 6487 13683 6487 13684 6795 13684 6797 13684 6487 13685 6797 13685 6782 13685 6782 13686 6797 13686 6775 13686 6782 13687 6775 13687 6781 13687 6781 13688 6775 13688 6773 13688 6781 13689 6773 13689 6779 13689 6779 13690 6773 13690 6798 13690 6779 13691 6798 13691 6763 13691 6763 13692 6798 13692 6799 13692 6800 13693 6292 13693 6819 13693 6821 13694 6810 13694 5449 13694 6801 13695 6809 13695 6753 13695 6753 13696 6757 13696 6801 13696 6801 13697 6757 13697 6802 13697 6801 13698 6802 13698 6264 13698 6807 13699 6809 13699 6820 13699 6820 13700 6809 13700 6801 13700 6820 13701 6801 13701 6803 13701 6803 13702 6801 13702 6264 13702 6803 13703 6264 13703 6280 13703 6292 13704 6800 13704 6804 13704 6804 13705 6800 13705 6816 13705 6804 13706 6816 13706 6815 13706 6813 13707 5452 13707 6811 13707 6811 13708 5452 13708 5447 13708 6811 13709 5447 13709 6810 13709 6805 13710 6756 13710 6806 13710 6806 13711 6756 13711 6755 13711 6806 13712 6755 13712 6807 13712 6807 13713 6755 13713 6808 13713 6807 13714 6808 13714 6809 13714 6809 13715 6808 13715 6754 13715 6809 13716 6754 13716 6753 13716 6810 13717 6821 13717 6811 13717 6811 13718 6821 13718 6812 13718 6811 13719 6812 13719 6813 13719 6291 13720 6815 13720 6814 13720 6814 13721 6815 13721 6816 13721 6814 13722 6816 13722 6279 13722 6279 13723 6816 13723 6817 13723 6817 13724 6816 13724 6800 13724 6817 13725 6800 13725 6818 13725 6818 13726 6800 13726 6819 13726 6818 13727 6819 13727 6812 13727 6812 13728 6819 13728 6293 13728 6812 13729 6293 13729 6813 13729 6280 13730 6279 13730 6803 13730 6803 13731 6279 13731 6817 13731 6803 13732 6817 13732 6820 13732 6820 13733 6817 13733 6818 13733 6820 13734 6818 13734 6807 13734 6807 13735 6818 13735 6812 13735 6807 13736 6812 13736 6806 13736 6806 13737 6812 13737 6821 13737 6806 13738 6821 13738 6805 13738 6805 13739 6821 13739 5449 13739 6758 13740 6860 13740 6826 13740 6502 13741 6822 13741 6823 13741 6502 13742 6823 13742 6824 13742 6824 13743 6823 13743 6825 13743 6824 13744 6825 13744 6500 13744 6759 13745 6758 13745 6507 13745 6507 13746 6758 13746 6826 13746 6507 13747 6826 13747 6827 13747 6827 13748 6826 13748 6828 13748 6827 13749 6828 13749 7124 13749 5291 13750 6495 13750 6829 13750 6829 13751 6495 13751 6496 13751 6829 13752 6496 13752 7119 13752 7119 13753 6496 13753 6497 13753 7119 13754 6497 13754 7120 13754 7120 13755 6497 13755 6500 13755 7120 13756 6500 13756 6830 13756 6830 13757 6500 13757 6825 13757 6822 13758 6502 13758 7124 13758 7124 13759 6502 13759 6504 13759 7124 13760 6504 13760 6827 13760 6834 13761 6840 13761 6831 13761 6831 13762 6840 13762 6845 13762 6831 13763 6845 13763 6832 13763 6832 13764 6845 13764 6833 13764 6832 13765 6833 13765 6835 13765 6835 13766 6833 13766 6843 13766 6715 13767 6834 13767 6717 13767 6717 13768 6834 13768 6831 13768 6717 13769 6831 13769 6719 13769 6719 13770 6831 13770 6832 13770 6719 13771 6832 13771 6188 13771 6188 13772 6832 13772 6835 13772 6207 13773 6208 13773 6836 13773 6207 13774 6836 13774 6837 13774 6837 13775 6836 13775 6838 13775 6837 13776 6838 13776 6839 13776 6839 13777 6838 13777 6845 13777 6839 13778 6845 13778 6840 13778 6204 13779 6203 13779 6844 13779 6844 13780 6203 13780 6209 13780 6844 13781 6209 13781 6841 13781 6841 13782 6209 13782 6842 13782 6841 13783 6842 13783 6833 13783 6833 13784 6842 13784 6843 13784 6208 13785 6204 13785 6836 13785 6836 13786 6204 13786 6844 13786 6836 13787 6844 13787 6838 13787 6838 13788 6844 13788 6841 13788 6838 13789 6841 13789 6845 13789 6845 13790 6841 13790 6833 13790 6846 13791 6886 13791 6852 13791 6852 13792 6840 13792 6846 13792 6846 13793 6840 13793 6834 13793 6846 13794 6834 13794 6715 13794 6863 13795 6864 13795 6847 13795 6848 13796 6849 13796 6854 13796 6854 13797 6849 13797 6850 13797 6854 13798 6850 13798 6847 13798 6847 13799 6850 13799 6851 13799 6847 13800 6851 13800 6863 13800 6840 13801 6852 13801 6853 13801 6853 13802 6852 13802 6886 13802 6886 13803 6867 13803 6853 13803 6853 13804 6867 13804 6869 13804 6853 13805 6869 13805 6854 13805 6854 13806 6869 13806 6870 13806 6854 13807 6870 13807 6848 13807 6840 13808 6853 13808 6839 13808 6839 13809 6853 13809 6854 13809 6839 13810 6854 13810 6837 13810 6837 13811 6854 13811 6847 13811 6837 13812 6847 13812 6207 13812 6761 13813 6760 13813 6857 13813 6528 13814 6859 13814 6855 13814 6855 13815 6859 13815 6762 13815 6855 13816 6762 13816 6531 13816 6531 13817 6762 13817 6761 13817 6531 13818 6761 13818 6856 13818 6856 13819 6761 13819 6857 13819 6856 13820 6857 13820 6219 13820 6528 13821 6858 13821 6859 13821 6859 13822 6858 13822 7125 13822 6859 13823 7125 13823 6860 13823 6850 13824 6861 13824 6851 13824 6851 13825 6861 13825 6862 13825 6851 13826 6862 13826 6863 13826 6863 13827 6862 13827 6864 13827 6887 13828 6920 13828 6880 13828 6880 13829 6920 13829 6865 13829 6880 13830 6865 13830 6882 13830 6882 13831 6865 13831 6919 13831 6886 13832 6866 13832 6867 13832 6867 13833 6866 13833 6868 13833 6867 13834 6868 13834 6869 13834 6869 13835 6868 13835 6881 13835 6869 13836 6881 13836 6870 13836 6870 13837 6881 13837 6848 13837 6881 13838 6871 13838 6848 13838 6848 13839 6871 13839 6861 13839 6848 13840 6861 13840 6849 13840 6849 13841 6861 13841 6850 13841 6873 13842 6922 13842 6872 13842 6872 13843 6922 13843 4990 13843 6872 13844 4990 13844 6876 13844 6873 13845 6872 13845 7001 13845 7001 13846 6872 13846 6875 13846 7001 13847 6875 13847 6874 13847 6919 13848 6874 13848 6882 13848 6882 13849 6874 13849 6875 13849 6882 13850 6875 13850 6879 13850 6879 13851 6875 13851 6872 13851 6879 13852 6872 13852 6877 13852 6877 13853 6872 13853 6876 13853 6877 13854 6876 13854 6558 13854 6558 13855 6562 13855 6877 13855 6877 13856 6562 13856 6878 13856 6877 13857 6878 13857 6879 13857 6879 13858 6878 13858 6883 13858 6879 13859 6883 13859 6882 13859 6866 13860 6887 13860 6868 13860 6868 13861 6887 13861 6880 13861 6868 13862 6880 13862 6881 13862 6881 13863 6880 13863 6882 13863 6881 13864 6882 13864 6871 13864 6871 13865 6882 13865 6883 13865 6871 13866 6883 13866 6861 13866 6861 13867 6883 13867 6878 13867 6861 13868 6878 13868 6862 13868 6862 13869 6878 13869 6562 13869 6862 13870 6562 13870 6864 13870 16475 13871 6884 13871 6846 13871 6846 13872 6884 13872 16468 13872 6846 13873 16468 13873 6886 13873 6885 13874 16472 13874 6887 13874 16468 13875 16470 13875 6886 13875 6886 13876 16470 13876 6885 13876 6886 13877 6885 13877 6866 13877 6866 13878 6885 13878 6887 13878 16419 13879 6920 13879 16420 13879 16420 13880 6920 13880 6887 13880 16420 13881 6887 13881 16474 13881 16474 13882 6887 13882 16472 13882 6888 13883 5364 13883 7010 13883 7010 13884 7009 13884 6888 13884 6888 13885 7009 13885 6889 13885 6888 13886 6889 13886 16368 13886 16368 13887 6889 13887 7008 13887 16368 13888 7008 13888 6890 13888 6890 13889 7008 13889 6994 13889 6890 13890 6994 13890 6891 13890 6891 13891 6994 13891 6995 13891 6891 13892 6995 13892 6894 13892 6896 13893 6892 13893 6893 13893 6893 13894 6892 13894 6895 13894 6893 13895 6895 13895 6894 13895 6894 13896 6895 13896 16370 13896 6894 13897 16370 13897 6891 13897 6896 13898 6893 13898 16377 13898 16377 13899 6893 13899 6897 13899 16377 13900 6897 13900 6898 13900 6897 13901 6980 13901 6898 13901 6898 13902 6980 13902 6899 13902 6898 13903 6899 13903 6900 13903 6900 13904 6899 13904 6901 13904 6900 13905 6901 13905 16374 13905 16374 13906 6901 13906 16373 13906 16373 13907 6901 13907 7017 13907 16373 13908 7017 13908 16378 13908 16378 13909 7017 13909 6992 13909 16378 13910 6992 13910 6902 13910 6902 13911 6992 13911 6903 13911 6903 13912 6992 13912 6904 13912 6903 13913 6904 13913 16379 13913 16379 13914 6904 13914 6905 13914 6905 13915 6904 13915 6920 13915 6905 13916 6920 13916 16419 13916 6906 13917 12546 13917 6976 13917 6907 13918 7011 13918 6933 13918 6908 13919 12354 13919 6913 13919 12368 13920 6912 13920 9880 13920 12368 13921 9880 13921 12367 13921 6908 13922 6913 13922 6909 13922 9947 13923 6910 13923 9926 13923 9926 13924 6910 13924 12396 13924 9926 13925 12396 13925 6911 13925 6911 13926 12396 13926 12367 13926 6911 13927 12367 13927 9873 13927 9873 13928 12367 13928 9880 13928 6982 13929 9914 13929 9910 13929 12368 13930 6909 13930 6912 13930 6912 13931 6909 13931 6913 13931 6912 13932 6913 13932 6914 13932 6914 13933 6913 13933 6982 13933 6914 13934 6982 13934 9882 13934 9882 13935 6982 13935 9910 13935 6987 13936 6917 13936 9920 13936 6915 13937 9920 13937 6916 13937 6916 13938 9920 13938 6917 13938 6916 13939 6917 13939 6918 13939 6919 13940 6865 13940 6921 13940 6921 13941 6865 13941 6920 13941 6921 13942 6920 13942 6904 13942 7003 13943 7001 13943 6921 13943 6921 13944 7001 13944 6874 13944 6921 13945 6874 13945 6919 13945 4987 13946 4990 13946 7002 13946 7002 13947 4990 13947 6922 13947 7002 13948 6922 13948 6873 13948 6923 13949 6924 13949 13882 13949 6924 13950 6923 13950 6925 13950 6924 13951 6925 13951 7002 13951 7002 13952 6925 13952 4982 13952 7002 13953 4982 13953 4987 13953 6926 13954 13864 13954 7004 13954 7004 13955 13864 13955 13870 13955 7004 13956 13870 13956 6924 13956 6924 13957 13870 13957 6927 13957 6924 13958 6927 13958 13882 13958 6928 13959 7004 13959 13620 13959 13620 13960 7004 13960 7006 13960 13620 13961 7006 13961 6929 13961 6928 13962 13636 13962 7004 13962 7004 13963 13636 13963 13630 13963 7004 13964 13630 13964 13621 13964 13839 13965 6926 13965 6930 13965 6930 13966 6926 13966 7004 13966 6930 13967 7004 13967 13621 13967 6941 13968 6931 13968 7015 13968 7015 13969 6931 13969 6932 13969 7015 13970 6932 13970 7012 13970 6933 13971 7011 13971 7012 13971 6933 13972 6934 13972 6907 13972 6907 13973 6934 13973 6936 13973 6907 13974 6936 13974 6935 13974 6935 13975 6936 13975 6937 13975 6935 13976 6937 13976 6938 13976 6937 13977 13395 13977 4934 13977 6937 13978 4934 13978 6938 13978 6938 13979 4934 13979 13674 13979 6943 13980 13163 13980 6944 13980 13198 13981 6939 13981 6940 13981 6940 13982 6939 13982 13423 13982 6941 13983 7015 13983 6942 13983 6942 13984 7015 13984 6943 13984 6942 13985 6943 13985 13423 13985 13423 13986 6943 13986 6944 13986 13423 13987 6944 13987 6940 13987 13198 13988 13187 13988 6939 13988 6939 13989 13187 13989 6945 13989 6939 13990 6945 13990 13424 13990 6945 13991 13179 13991 4941 13991 13424 13992 6945 13992 6946 13992 6946 13993 6945 13993 4941 13993 6946 13994 4941 13994 4942 13994 13163 13995 6943 13995 6947 13995 6947 13996 6943 13996 6999 13996 6947 13997 6999 13997 6960 13997 12811 13998 12846 13998 6948 13998 12811 13999 6948 13999 6954 13999 6949 14000 13041 14000 6950 14000 6950 14001 13041 14001 6951 14001 13002 14002 6587 14002 6952 14002 13039 14003 13002 14003 6952 14003 13039 14004 6952 14004 6951 14004 6951 14005 6952 14005 6953 14005 6951 14006 6953 14006 6950 14006 6948 14007 6955 14007 6954 14007 6954 14008 6955 14008 6956 14008 6954 14009 6956 14009 12824 14009 12824 14010 6956 14010 6949 14010 12824 14011 6949 14011 12819 14011 12819 14012 6949 14012 6950 14012 12819 14013 6950 14013 6957 14013 6957 14014 6950 14014 6958 14014 6957 14015 6958 14015 6959 14015 6959 14016 6958 14016 6960 14016 6959 14017 6960 14017 12838 14017 12838 14018 6960 14018 6999 14018 12838 14019 6999 14019 6961 14019 6961 14020 6999 14020 6998 14020 6961 14021 6998 14021 12862 14021 12862 14022 6998 14022 12898 14022 6969 14023 6962 14023 12484 14023 12484 14024 6962 14024 12899 14024 12484 14025 12899 14025 6974 14025 6963 14026 6969 14026 6965 14026 6963 14027 6965 14027 12735 14027 12735 14028 6965 14028 6964 14028 6964 14029 6965 14029 12464 14029 6964 14030 12464 14030 6577 14030 6577 14031 12464 14031 12465 14031 6577 14032 12465 14032 6576 14032 12901 14033 6966 14033 12903 14033 12903 14034 6966 14034 12955 14034 6967 14035 6966 14035 12901 14035 6967 14036 12901 14036 12677 14036 12677 14037 12901 14037 6968 14037 12677 14038 6968 14038 12718 14038 12718 14039 6968 14039 6962 14039 12718 14040 6962 14040 12725 14040 12725 14041 6962 14041 6969 14041 12725 14042 6969 14042 12724 14042 12724 14043 6969 14043 6963 14043 6970 14044 6971 14044 6984 14044 6984 14045 6971 14045 6972 14045 6984 14046 6972 14046 6989 14046 6989 14047 6972 14047 6973 14047 6989 14048 6973 14048 6974 14048 6974 14049 6973 14049 12493 14049 6974 14050 12493 14050 12484 14050 12542 14051 12541 14051 6982 14051 6982 14052 12541 14052 6975 14052 6982 14053 6975 14053 6970 14053 6970 14054 6975 14054 12517 14054 6970 14055 12517 14055 6971 14055 6976 14056 12546 14056 12354 14056 12354 14057 12546 14057 6977 14057 12354 14058 6977 14058 6913 14058 6913 14059 6977 14059 12544 14059 6913 14060 12544 14060 6982 14060 6982 14061 12544 14061 6978 14061 6982 14062 6978 14062 12542 14062 6906 14063 6976 14063 12597 14063 12597 14064 6976 14064 6979 14064 12597 14065 6979 14065 12589 14065 12589 14066 6979 14066 6567 14066 12589 14067 6567 14067 12587 14067 6893 14068 6997 14068 6897 14068 6897 14069 6997 14069 7018 14069 6897 14070 7018 14070 6980 14070 9920 14071 9914 14071 6987 14071 6987 14072 9914 14072 6982 14072 6987 14073 6982 14073 6981 14073 6981 14074 6982 14074 6970 14074 6981 14075 6970 14075 6983 14075 6983 14076 6970 14076 6984 14076 6985 14077 6918 14077 7007 14077 7007 14078 6918 14078 6917 14078 7007 14079 6917 14079 6986 14079 6986 14080 6917 14080 6987 14080 6986 14081 6987 14081 6988 14081 6988 14082 6987 14082 6981 14082 6988 14083 6981 14083 6996 14083 6996 14084 6981 14084 6983 14084 6996 14085 6983 14085 6998 14085 6998 14086 6983 14086 6984 14086 6998 14087 6984 14087 12898 14087 12898 14088 6984 14088 6989 14088 7014 14089 7013 14089 6990 14089 6990 14090 7013 14090 7005 14090 6990 14091 7005 14091 6991 14091 6991 14092 7005 14092 6993 14092 7017 14093 7014 14093 6992 14093 6992 14094 7014 14094 6990 14094 6992 14095 6990 14095 6904 14095 6904 14096 6990 14096 6991 14096 6904 14097 6991 14097 6921 14097 6921 14098 6991 14098 6993 14098 6921 14099 6993 14099 7003 14099 6994 14100 7007 14100 6995 14100 6995 14101 7007 14101 6986 14101 6995 14102 6986 14102 6894 14102 6894 14103 6986 14103 6988 14103 6894 14104 6988 14104 6893 14104 6893 14105 6988 14105 6996 14105 6893 14106 6996 14106 6997 14106 6997 14107 6996 14107 6998 14107 6997 14108 6998 14108 7018 14108 7018 14109 6998 14109 6999 14109 7018 14110 6999 14110 7016 14110 7016 14111 6999 14111 6943 14111 7016 14112 6943 14112 7000 14112 7000 14113 6943 14113 7015 14113 6873 14114 7001 14114 7002 14114 7002 14115 7001 14115 7003 14115 7002 14116 7003 14116 6924 14116 6924 14117 7003 14117 6993 14117 6924 14118 6993 14118 7004 14118 7004 14119 6993 14119 7005 14119 7004 14120 7005 14120 7006 14120 7006 14121 7005 14121 7013 14121 7006 14122 7013 14122 6929 14122 6994 14123 7008 14123 7007 14123 7007 14124 7008 14124 6889 14124 7007 14125 6889 14125 6985 14125 6985 14126 6889 14126 7009 14126 6985 14127 7009 14127 5365 14127 5365 14128 7009 14128 7010 14128 7011 14129 6929 14129 7012 14129 7012 14130 6929 14130 7013 14130 7012 14131 7013 14131 7015 14131 7015 14132 7013 14132 7014 14132 7015 14133 7014 14133 7000 14133 7000 14134 7014 14134 7017 14134 7000 14135 7017 14135 7016 14135 7016 14136 7017 14136 6901 14136 7016 14137 6901 14137 7018 14137 7018 14138 6901 14138 6899 14138 7018 14139 6899 14139 6980 14139 7019 14140 7067 14140 13126 14140 12846 14141 12849 14141 6948 14141 6948 14142 12849 14142 13107 14142 13107 14143 12849 14143 12848 14143 13107 14144 12848 14144 13116 14144 13116 14145 12848 14145 7020 14145 13116 14146 7020 14146 13125 14146 13125 14147 7020 14147 12867 14147 13125 14148 12867 14148 7021 14148 7021 14149 12867 14149 7019 14149 7021 14150 7019 14150 13126 14150 7022 14151 7023 14151 7109 14151 7121 14152 7107 14152 7024 14152 6541 14153 7025 14153 7098 14153 13290 14154 13291 14154 7083 14154 13031 14155 13032 14155 13356 14155 7038 14156 12328 14156 12605 14156 7026 14157 7029 14157 7027 14157 7027 14158 7029 14158 7028 14158 7027 14159 7028 14159 12376 14159 7026 14160 12431 14160 7029 14160 7029 14161 12431 14161 7031 14161 7029 14162 7031 14162 7030 14162 7030 14163 7031 14163 7101 14163 7030 14164 7101 14164 5379 14164 7054 14165 12328 14165 7051 14165 7051 14166 12328 14166 12326 14166 12326 14167 12327 14167 7051 14167 7051 14168 12327 14168 12316 14168 7051 14169 12316 14169 7032 14169 7032 14170 7033 14170 7051 14170 7051 14171 7033 14171 7034 14171 7051 14172 7034 14172 7036 14172 7036 14173 7034 14173 7035 14173 7036 14174 7035 14174 7028 14174 7028 14175 7035 14175 12369 14175 7028 14176 12369 14176 12376 14176 12582 14177 12625 14177 7054 14177 12582 14178 7054 14178 7048 14178 12625 14179 12626 14179 7054 14179 7054 14180 12626 14180 7037 14180 7054 14181 7037 14181 12328 14181 12328 14182 7037 14182 12606 14182 12328 14183 12606 14183 12605 14183 12605 14184 7039 14184 7038 14184 7038 14185 7039 14185 7040 14185 7038 14186 7040 14186 7041 14186 12278 14187 7042 14187 7041 14187 7041 14188 7042 14188 7043 14188 7041 14189 7043 14189 7038 14189 7048 14190 7054 14190 7044 14190 7048 14191 7044 14191 7045 14191 7045 14192 7046 14192 7048 14192 7048 14193 7046 14193 7047 14193 7048 14194 7047 14194 7049 14194 7061 14195 7050 14195 7051 14195 7051 14196 7050 14196 7052 14196 7051 14197 7052 14197 12789 14197 12789 14198 7053 14198 7051 14198 7051 14199 7053 14199 12786 14199 7051 14200 12786 14200 7054 14200 7054 14201 12786 14201 12773 14201 7054 14202 12773 14202 7044 14202 7058 14203 12699 14203 7057 14203 7057 14204 12699 14204 7060 14204 7055 14205 13070 14205 13071 14205 7056 14206 7065 14206 12702 14206 7057 14207 13094 14207 7058 14207 7058 14208 13094 14208 7056 14208 7058 14209 7056 14209 7059 14209 7059 14210 7056 14210 12702 14210 13071 14211 7060 14211 7055 14211 7055 14212 7060 14212 12699 14212 7055 14213 12699 14213 7061 14213 7061 14214 12699 14214 7062 14214 7061 14215 7062 14215 7050 14215 13126 14216 7067 14216 7063 14216 7063 14217 7067 14217 7066 14217 7064 14218 7068 14218 7065 14218 7064 14219 7065 14219 7067 14219 7066 14220 7067 14220 7065 14220 7068 14221 12948 14221 7065 14221 7065 14222 12948 14222 7069 14222 7065 14223 7069 14223 12702 14223 12702 14224 7069 14224 12943 14224 12702 14225 12943 14225 7071 14225 12983 14226 12974 14226 7070 14226 7070 14227 12974 14227 12976 14227 7070 14228 12976 14228 12705 14228 12705 14229 12976 14229 6572 14229 12983 14230 7070 14230 7071 14230 7071 14231 7070 14231 12703 14231 7071 14232 12703 14232 12702 14232 7083 14233 13291 14233 7114 14233 7114 14234 13291 14234 7072 14234 7114 14235 7072 14235 7074 14235 13356 14236 13032 14236 7073 14236 7073 14237 13032 14237 13034 14237 7073 14238 13034 14238 13035 14238 7074 14239 13303 14239 7114 14239 7114 14240 13303 14240 13304 14240 7114 14241 13304 14241 7055 14241 7055 14242 13304 14242 7073 14242 7055 14243 7073 14243 13070 14243 13070 14244 7073 14244 13035 14244 7075 14245 7077 14245 7076 14245 7076 14246 7077 14246 7078 14246 7076 14247 7078 14247 13238 14247 13238 14248 7079 14248 7076 14248 7076 14249 7079 14249 13239 14249 7076 14250 13239 14250 13240 14250 13240 14251 13242 14251 7076 14251 7076 14252 13242 14252 13224 14252 7076 14253 13224 14253 13030 14253 13356 14254 13346 14254 13031 14254 13031 14255 13346 14255 7080 14255 13031 14256 7080 14256 7076 14256 7076 14257 7080 14257 7081 14257 7076 14258 7081 14258 7075 14258 13262 14259 7082 14259 4950 14259 4950 14260 7082 14260 7084 14260 4950 14261 7084 14261 13572 14261 13290 14262 7083 14262 7082 14262 7082 14263 7083 14263 13578 14263 7082 14264 13578 14264 7084 14264 13524 14265 7085 14265 7099 14265 7099 14266 7085 14266 7086 14266 7099 14267 7086 14267 7114 14267 7086 14268 7087 14268 7114 14268 7114 14269 7087 14269 13587 14269 7114 14270 13587 14270 7083 14270 7083 14271 13587 14271 7088 14271 7083 14272 7088 14272 13578 14272 13521 14273 13523 14273 7090 14273 7091 14274 13747 14274 7090 14274 7090 14275 13747 14275 13743 14275 4954 14276 13521 14276 4955 14276 4955 14277 13521 14277 7090 14277 4955 14278 7090 14278 7089 14278 7089 14279 7090 14279 13743 14279 13523 14280 13524 14280 7090 14280 7090 14281 13524 14281 7099 14281 7090 14282 7099 14282 7091 14282 7091 14283 7099 14283 7092 14283 7093 14284 4975 14284 7094 14284 7094 14285 7095 14285 7093 14285 7093 14286 7095 14286 13758 14286 7093 14287 13758 14287 7025 14287 7025 14288 13758 14288 7096 14288 7096 14289 13763 14289 7025 14289 7025 14290 13763 14290 7097 14290 7025 14291 7097 14291 7098 14291 7098 14292 7097 14292 13730 14292 7092 14293 7099 14293 13730 14293 13730 14294 7099 14294 7113 14294 13730 14295 7113 14295 7098 14295 7098 14296 7113 14296 6514 14296 7098 14297 6514 14297 6541 14297 12407 14298 7100 14298 12408 14298 12408 14299 7100 14299 5377 14299 12408 14300 5377 14300 12409 14300 12409 14301 5377 14301 5378 14301 12409 14302 5378 14302 7101 14302 7101 14303 5378 14303 7102 14303 7101 14304 7102 14304 5379 14304 12407 14305 7103 14305 7100 14305 7100 14306 7103 14306 12453 14306 7100 14307 12453 14307 12442 14307 5381 14308 7104 14308 7110 14308 7110 14309 7104 14309 7105 14309 7110 14310 7105 14310 7117 14310 7117 14311 7105 14311 7118 14311 7022 14312 7109 14312 7106 14312 7106 14313 7109 14313 6858 14313 7106 14314 6858 14314 6527 14314 7024 14315 7107 14315 7115 14315 7115 14316 7107 14316 7123 14316 7115 14317 7123 14317 7023 14317 7023 14318 7123 14318 7108 14318 7023 14319 7108 14319 7109 14319 7029 14320 5381 14320 7028 14320 7028 14321 5381 14321 7110 14321 7028 14322 7110 14322 7036 14322 7036 14323 7110 14323 7117 14323 7036 14324 7117 14324 7051 14324 7051 14325 7117 14325 7111 14325 7051 14326 7111 14326 7061 14326 7061 14327 7111 14327 7112 14327 7061 14328 7112 14328 7055 14328 6527 14329 6514 14329 7106 14329 7106 14330 6514 14330 7113 14330 7106 14331 7113 14331 7022 14331 7022 14332 7113 14332 7099 14332 7022 14333 7099 14333 7023 14333 7023 14334 7099 14334 7114 14334 7023 14335 7114 14335 7115 14335 7115 14336 7114 14336 7055 14336 7115 14337 7055 14337 7024 14337 7024 14338 7055 14338 7112 14338 7024 14339 7112 14339 7121 14339 7121 14340 7112 14340 7111 14340 7121 14341 7111 14341 7116 14341 7116 14342 7111 14342 7117 14342 7116 14343 7117 14343 7122 14343 7122 14344 7117 14344 7118 14344 7125 14345 6858 14345 7109 14345 6829 14346 7119 14346 7122 14346 7122 14347 7119 14347 7120 14347 7122 14348 7120 14348 7116 14348 7116 14349 7120 14349 6830 14349 7116 14350 6830 14350 7121 14350 7121 14351 6830 14351 6825 14351 7121 14352 6825 14352 7107 14352 7104 14353 5291 14353 7105 14353 7105 14354 5291 14354 6829 14354 7105 14355 6829 14355 7118 14355 7118 14356 6829 14356 7122 14356 6825 14357 6823 14357 7107 14357 7107 14358 6823 14358 6822 14358 7107 14359 6822 14359 7123 14359 7123 14360 6822 14360 7124 14360 7123 14361 7124 14361 7108 14361 7108 14362 7124 14362 6828 14362 7108 14363 6828 14363 7109 14363 7109 14364 6828 14364 6826 14364 7109 14365 6826 14365 7125 14365 7125 14366 6826 14366 6860 14366 7246 14367 7126 14367 12386 14367 12386 14368 7126 14368 5553 14368 12386 14369 5553 14369 7127 14369 7127 14370 5553 14370 12377 14370 12377 14371 5553 14371 12378 14371 12378 14372 5553 14372 7128 14372 12378 14373 7128 14373 12435 14373 10009 14374 4568 14374 7129 14374 7129 14375 4568 14375 7132 14375 7129 14376 7132 14376 7130 14376 7130 14377 7132 14377 7131 14377 7131 14378 7132 14378 7134 14378 7131 14379 7134 14379 7133 14379 7133 14380 7134 14380 7135 14380 7135 14381 7134 14381 4564 14381 7135 14382 4564 14382 7136 14382 7136 14383 4564 14383 7137 14383 7137 14384 4564 14384 7138 14384 7137 14385 7138 14385 7139 14385 7139 14386 7138 14386 7140 14386 7140 14387 7138 14387 4562 14387 7140 14388 4562 14388 5220 14388 7141 14389 9959 14389 9470 14389 7141 14390 9470 14390 9915 14390 9915 14391 9470 14391 7142 14391 7142 14392 9470 14392 7143 14392 7142 14393 7143 14393 7144 14393 7144 14394 7143 14394 9467 14394 7144 14395 9467 14395 7145 14395 13011 14396 5569 14396 7146 14396 13011 14397 7146 14397 7147 14397 7147 14398 7146 14398 5573 14398 7147 14399 5573 14399 13106 14399 12857 14400 15746 14400 15744 14400 12857 14401 15744 14401 12859 14401 12859 14402 15744 14402 5734 14402 12859 14403 5734 14403 5732 14403 14792 14404 9735 14404 7148 14404 7148 14405 7149 14405 14792 14405 14792 14406 7149 14406 7150 14406 14792 14407 7150 14407 7151 14407 7151 14408 7150 14408 13297 14408 7151 14409 13297 14409 7152 14409 7152 14410 13297 14410 5781 14410 13275 14411 5585 14411 7154 14411 13275 14412 7154 14412 7153 14412 7153 14413 7154 14413 7294 14413 7153 14414 7294 14414 7155 14414 13139 14415 9437 14415 9436 14415 13139 14416 9436 14416 7156 14416 7156 14417 9436 14417 5758 14417 7156 14418 5758 14418 13199 14418 12679 14419 5603 14419 5604 14419 12679 14420 5604 14420 7157 14420 7157 14421 5604 14421 5599 14421 7157 14422 5599 14422 12736 14422 9457 14423 7158 14423 5705 14423 5705 14424 7158 14424 12509 14424 12509 14425 7158 14425 12504 14425 12504 14426 7158 14426 5706 14426 12504 14427 5706 14427 7159 14427 13536 14428 7164 14428 13530 14428 13530 14429 7164 14429 7167 14429 13530 14430 7167 14430 13588 14430 7327 14431 7166 14431 13528 14431 13528 14432 7166 14432 7220 14432 13528 14433 7220 14433 13504 14433 13613 14434 7160 14434 13591 14434 13591 14435 7160 14435 7168 14435 13591 14436 7168 14436 13592 14436 7220 14437 7166 14437 7164 14437 7164 14438 7166 14438 7167 14438 7316 14439 7315 14439 7321 14439 7321 14440 7315 14440 7167 14440 7321 14441 7167 14441 7322 14441 7166 14442 7161 14442 7162 14442 7163 14443 7225 14443 7164 14443 7164 14444 7225 14444 7222 14444 7164 14445 7222 14445 7220 14445 7162 14446 7165 14446 7166 14446 7166 14447 7165 14447 7168 14447 7166 14448 7168 14448 7167 14448 7167 14449 7168 14449 7160 14449 7167 14450 7160 14450 7322 14450 13811 14451 7184 14451 13809 14451 13809 14452 7184 14452 7169 14452 13809 14453 7169 14453 13804 14453 7178 14454 7186 14454 7170 14454 7170 14455 7186 14455 7185 14455 7170 14456 7185 14456 13728 14456 13761 14457 7174 14457 7171 14457 13804 14458 7169 14458 7172 14458 7172 14459 7169 14459 7173 14459 7172 14460 7173 14460 13787 14460 7171 14461 7174 14461 7173 14461 7173 14462 7174 14462 7175 14462 7173 14463 7175 14463 13787 14463 13761 14464 7171 14464 7176 14464 7176 14465 7171 14465 7183 14465 7176 14466 7183 14466 7177 14466 7186 14467 7178 14467 7183 14467 7183 14468 7178 14468 7179 14468 7183 14469 7179 14469 7177 14469 7180 14470 7232 14470 7181 14470 7181 14471 7232 14471 7331 14471 7181 14472 7331 14472 7333 14472 7334 14473 7332 14473 7331 14473 7230 14474 7226 14474 7231 14474 7231 14475 7226 14475 7182 14475 7231 14476 7182 14476 7232 14476 7232 14477 7182 14477 7185 14477 7232 14478 7185 14478 7331 14478 7171 14479 7173 14479 7183 14479 7183 14480 7173 14480 7169 14480 7183 14481 7169 14481 7186 14481 7186 14482 7169 14482 7184 14482 7336 14483 7334 14483 7339 14483 7339 14484 7334 14484 7331 14484 7339 14485 7331 14485 7184 14485 7184 14486 7331 14486 7185 14486 7184 14487 7185 14487 7186 14487 7350 14488 14171 14488 7236 14488 7236 14489 14171 14489 14173 14489 14173 14490 14196 14490 7236 14490 7236 14491 14196 14491 14195 14491 7236 14492 14195 14492 7237 14492 14227 14493 7187 14493 7188 14493 7188 14494 7187 14494 14189 14494 7188 14495 14189 14495 7189 14495 14131 14496 7195 14496 14194 14496 14194 14497 7195 14497 7188 14497 14194 14498 7188 14498 14192 14498 14192 14499 7188 14499 7189 14499 7190 14500 14123 14500 7191 14500 7194 14501 14128 14501 14114 14501 7194 14502 14114 14502 7191 14502 7191 14503 14114 14503 14095 14503 7191 14504 14095 14504 14108 14504 14108 14505 14097 14505 7191 14505 7191 14506 14097 14506 14096 14506 7191 14507 14096 14507 7190 14507 7350 14508 7191 14508 7357 14508 7359 14509 7192 14509 7193 14509 7193 14510 7192 14510 7194 14510 7193 14511 7194 14511 7195 14511 7195 14512 7194 14512 7191 14512 7195 14513 7191 14513 7188 14513 7188 14514 7191 14514 7350 14514 7188 14515 7350 14515 7236 14515 7357 14516 7355 14516 7350 14516 7350 14517 7355 14517 7353 14517 7350 14518 7353 14518 7351 14518 7236 14519 7235 14519 7188 14519 7188 14520 7235 14520 7234 14520 7188 14521 7234 14521 7233 14521 7196 14522 7197 14522 15425 14522 15425 14523 15424 14523 7196 14523 7196 14524 15424 14524 15421 14524 7196 14525 15421 14525 7198 14525 7198 14526 15421 14526 15412 14526 7198 14527 15412 14527 15419 14527 7199 14528 5612 14528 15417 14528 15417 14529 5612 14529 7198 14529 15417 14530 7198 14530 15418 14530 15418 14531 7198 14531 15419 14531 7201 14532 7200 14532 7202 14532 7201 14533 7202 14533 13386 14533 13386 14534 7202 14534 9427 14534 13386 14535 9427 14535 7203 14535 7204 14536 7205 14536 15554 14536 15554 14537 7205 14537 4824 14537 15554 14538 4824 14538 15547 14538 7207 14539 15570 14539 4836 14539 4836 14540 4832 14540 7207 14540 7207 14541 4832 14541 14492 14541 7207 14542 14492 14542 14456 14542 7207 14543 14491 14543 7204 14543 7204 14544 14491 14544 14490 14544 7204 14545 14490 14545 7205 14545 14456 14546 7206 14546 7207 14546 7207 14547 7206 14547 14454 14547 7207 14548 14454 14548 14491 14548 7214 14549 7212 14549 14329 14549 14329 14550 7212 14550 14326 14550 14299 14551 7208 14551 7213 14551 7219 14552 7372 14552 7213 14552 7213 14553 7372 14553 14293 14553 7213 14554 14293 14554 14299 14554 14288 14555 7210 14555 7209 14555 7209 14556 7210 14556 7215 14556 7365 14557 14251 14557 7215 14557 7215 14558 14251 14558 7211 14558 7215 14559 7211 14559 7209 14559 7212 14560 7215 14560 7210 14560 7215 14561 7213 14561 7370 14561 7363 14562 7362 14562 7210 14562 7210 14563 7362 14563 7361 14563 7210 14564 7361 14564 7212 14564 7215 14565 7212 14565 7213 14565 7213 14566 7212 14566 7214 14566 7213 14567 7214 14567 7219 14567 7370 14568 7216 14568 7215 14568 7215 14569 7216 14569 7217 14569 7215 14570 7217 14570 7366 14570 7218 14571 7376 14571 7214 14571 7214 14572 7376 14572 7374 14572 7214 14573 7374 14573 7219 14573 13504 14574 7220 14574 13498 14574 13498 14575 7220 14575 7222 14575 13498 14576 7222 14576 7221 14576 7221 14577 7222 14577 13497 14577 13497 14578 7222 14578 7223 14578 7223 14579 7222 14579 7225 14579 7223 14580 7225 14580 13507 14580 13507 14581 7225 14581 7224 14581 7224 14582 7225 14582 7163 14582 7224 14583 7163 14583 13512 14583 7164 14584 13536 14584 7163 14584 7163 14585 13536 14585 13513 14585 7163 14586 13513 14586 13512 14586 13728 14587 7185 14587 13749 14587 13749 14588 7185 14588 7182 14588 7230 14589 13738 14589 7226 14589 7226 14590 13738 14590 13733 14590 7226 14591 13733 14591 7182 14591 7182 14592 13733 14592 7227 14592 7182 14593 7227 14593 13749 14593 7228 14594 7229 14594 7230 14594 7230 14595 7229 14595 13766 14595 7230 14596 13766 14596 13738 14596 7230 14597 7231 14597 7228 14597 7228 14598 7231 14598 7232 14598 7228 14599 7232 14599 7180 14599 14227 14600 7188 14600 14231 14600 14231 14601 7188 14601 7233 14601 14231 14602 7233 14602 14236 14602 14236 14603 7233 14603 14237 14603 14237 14604 7233 14604 7234 14604 14237 14605 7234 14605 14220 14605 14220 14606 7234 14606 14221 14606 14221 14607 7234 14607 7235 14607 14221 14608 7235 14608 14222 14608 14222 14609 7235 14609 14224 14609 14224 14610 7235 14610 7236 14610 14224 14611 7236 14611 7237 14611 12435 14612 7128 14612 7238 14612 7238 14613 7128 14613 5556 14613 5552 14614 7239 14614 5556 14614 5556 14615 7239 14615 12433 14615 5556 14616 12433 14616 7238 14616 7241 14617 12399 14617 5552 14617 5552 14618 12399 14618 7240 14618 5552 14619 7240 14619 7239 14619 5555 14620 12400 14620 7241 14620 7241 14621 12400 14621 7242 14621 7241 14622 7242 14622 12399 14622 5543 14623 7243 14623 5544 14623 5544 14624 7243 14624 12417 14624 5544 14625 12417 14625 5555 14625 5555 14626 12417 14626 12415 14626 5555 14627 12415 14627 12400 14627 5541 14628 5560 14628 12344 14628 12344 14629 5560 14629 7244 14629 7248 14630 12321 14630 7244 14630 7244 14631 12321 14631 12334 14631 12334 14632 7245 14632 7244 14632 7244 14633 7245 14633 12335 14633 7244 14634 12335 14634 12344 14634 7126 14635 7246 14635 5559 14635 5559 14636 7246 14636 12312 14636 12312 14637 12311 14637 5559 14637 5559 14638 12311 14638 7247 14638 5559 14639 7247 14639 7248 14639 7248 14640 7247 14640 12304 14640 7248 14641 12304 14641 12321 14641 12622 14642 7249 14642 14357 14642 12622 14643 14357 14643 12619 14643 12619 14644 14357 14644 7250 14644 12619 14645 7250 14645 12616 14645 12616 14646 7250 14646 7251 14646 12616 14647 7251 14647 12617 14647 12617 14648 7251 14648 7252 14648 7252 14649 7251 14649 14353 14649 7252 14650 14353 14650 12601 14650 12601 14651 14353 14651 12600 14651 12600 14652 14353 14652 14363 14652 12600 14653 14363 14653 12644 14653 12736 14654 5599 14654 12791 14654 12791 14655 5599 14655 7253 14655 12755 14656 12783 14656 7255 14656 7255 14657 12783 14657 7254 14657 7255 14658 7254 14658 7253 14658 7253 14659 7254 14659 12753 14659 7253 14660 12753 14660 12791 14660 12755 14661 7255 14661 12779 14661 12779 14662 7255 14662 5602 14662 12779 14663 5602 14663 7256 14663 7256 14664 5602 14664 12765 14664 12765 14665 5602 14665 7257 14665 12765 14666 7257 14666 12766 14666 12766 14667 7257 14667 7258 14667 7258 14668 7257 14668 5600 14668 7258 14669 5600 14669 5594 14669 12659 14670 5587 14670 7259 14670 7259 14671 5587 14671 7261 14671 7259 14672 7261 14672 7260 14672 7260 14673 7261 14673 7262 14673 7262 14674 7261 14674 7263 14674 7262 14675 7263 14675 7265 14675 7265 14676 7263 14676 7264 14676 7265 14677 7264 14677 12693 14677 5601 14678 5603 14678 12679 14678 12679 14679 12681 14679 5601 14679 5601 14680 12681 14680 12680 14680 5601 14681 12680 14681 7264 14681 7264 14682 12680 14682 7266 14682 7264 14683 7266 14683 12693 14683 12944 14684 12949 14684 7267 14684 7267 14685 12949 14685 5184 14685 7267 14686 5184 14686 4670 14686 12944 14687 7267 14687 7268 14687 7268 14688 7267 14688 4676 14688 7268 14689 4676 14689 7269 14689 7269 14690 4676 14690 4675 14690 7269 14691 4675 14691 7270 14691 7270 14692 4675 14692 4674 14692 7270 14693 4674 14693 4663 14693 13106 14694 5573 14694 7271 14694 7271 14695 5573 14695 7274 14695 7272 14696 13091 14696 5574 14696 5574 14697 13091 14697 7273 14697 5574 14698 7273 14698 7274 14698 7274 14699 7273 14699 7275 14699 7274 14700 7275 14700 7271 14700 7272 14701 5574 14701 7276 14701 7276 14702 5574 14702 7277 14702 7276 14703 7277 14703 13090 14703 13090 14704 7277 14704 7278 14704 7278 14705 7277 14705 5572 14705 7278 14706 5572 14706 13079 14706 13079 14707 5572 14707 7279 14707 7279 14708 5572 14708 7280 14708 7279 14709 7280 14709 5563 14709 12992 14710 5562 14710 12993 14710 12993 14711 5562 14711 7282 14711 12993 14712 7282 14712 7281 14712 7281 14713 7282 14713 13008 14713 13008 14714 7282 14714 7283 14714 13008 14715 7283 14715 7284 14715 7284 14716 7283 14716 7287 14716 7284 14717 7287 14717 7288 14717 5575 14718 5569 14718 13011 14718 13011 14719 7285 14719 5575 14719 5575 14720 7285 14720 7286 14720 5575 14721 7286 14721 7287 14721 7287 14722 7286 14722 13009 14722 7287 14723 13009 14723 7288 14723 7289 14724 13252 14724 7290 14724 7289 14725 7290 14725 14348 14725 14348 14726 7290 14726 13257 14726 14348 14727 13257 14727 5181 14727 13252 14728 7289 14728 7292 14728 7292 14729 7289 14729 7291 14729 7292 14730 7291 14730 13248 14730 13248 14731 7291 14731 13247 14731 13247 14732 7291 14732 7293 14732 13247 14733 7293 14733 13230 14733 14344 14734 5175 14734 7293 14734 7293 14735 5175 14735 13219 14735 7293 14736 13219 14736 13230 14736 7155 14737 7294 14737 13360 14737 13360 14738 7294 14738 7295 14738 7297 14739 7296 14739 7295 14739 7295 14740 7296 14740 13350 14740 7295 14741 13350 14741 13360 14741 5582 14742 7298 14742 7297 14742 7297 14743 7298 14743 7299 14743 7297 14744 7299 14744 7296 14744 13373 14745 13372 14745 7300 14745 7300 14746 13372 14746 13338 14746 7300 14747 13338 14747 5582 14747 5582 14748 13338 14748 13332 14748 5582 14749 13332 14749 7298 14749 13373 14750 7300 14750 7301 14750 7301 14751 7300 14751 5578 14751 7301 14752 5578 14752 13381 14752 7149 14753 7148 14753 7303 14753 5586 14754 13263 14754 7303 14754 7303 14755 13263 14755 7302 14755 7303 14756 7302 14756 7149 14756 5584 14757 7304 14757 5586 14757 5586 14758 7304 14758 13272 14758 5586 14759 13272 14759 13263 14759 13274 14760 7305 14760 5584 14760 5584 14761 7305 14761 7306 14761 5584 14762 7306 14762 7304 14762 5584 14763 5583 14763 13274 14763 13274 14764 5583 14764 5585 14764 13274 14765 5585 14765 13275 14765 5632 14766 7307 14766 7308 14766 7308 14767 7307 14767 5637 14767 7308 14768 5637 14768 13481 14768 13481 14769 5637 14769 7309 14769 7309 14770 5637 14770 5640 14770 7309 14771 5640 14771 13475 14771 7311 14772 7310 14772 5626 14772 5626 14773 7312 14773 7311 14773 7311 14774 7312 14774 7313 14774 7311 14775 7313 14775 5640 14775 5640 14776 7313 14776 7314 14776 5640 14777 7314 14777 13475 14777 13588 14778 7167 14778 13582 14778 13582 14779 7167 14779 7315 14779 7316 14780 7318 14780 7315 14780 7315 14781 7318 14781 13569 14781 7315 14782 13569 14782 13582 14782 7321 14783 13573 14783 7316 14783 7316 14784 13573 14784 7317 14784 7316 14785 7317 14785 7318 14785 7319 14786 13602 14786 7321 14786 13602 14787 7320 14787 7321 14787 7321 14788 7320 14788 13575 14788 7321 14789 13575 14789 13573 14789 7321 14790 7322 14790 7319 14790 7319 14791 7322 14791 7160 14791 7319 14792 7160 14792 13613 14792 13592 14793 7168 14793 13568 14793 13568 14794 7168 14794 7165 14794 7162 14795 7323 14795 7165 14795 7165 14796 7323 14796 7324 14796 7165 14797 7324 14797 13568 14797 7161 14798 7325 14798 7162 14798 7162 14799 7325 14799 7326 14799 7162 14800 7326 14800 7323 14800 7327 14801 7328 14801 7166 14801 7166 14802 7328 14802 7329 14802 7166 14803 7329 14803 7161 14803 7161 14804 7329 14804 7330 14804 7161 14805 7330 14805 7325 14805 7331 14806 7332 14806 7333 14806 7333 14807 7332 14807 13837 14807 13837 14808 7332 14808 13836 14808 13836 14809 7332 14809 7334 14809 13836 14810 7334 14810 7335 14810 7335 14811 7334 14811 7337 14811 7337 14812 7334 14812 7336 14812 7337 14813 7336 14813 7338 14813 7338 14814 7336 14814 7339 14814 7338 14815 7339 14815 13820 14815 13820 14816 7339 14816 7340 14816 7340 14817 7339 14817 7184 14817 7340 14818 7184 14818 13811 14818 7198 14819 5612 14819 7341 14819 7341 14820 5612 14820 7342 14820 7341 14821 7342 14821 13894 14821 13894 14822 7342 14822 7343 14822 7343 14823 7342 14823 7345 14823 7343 14824 7345 14824 7344 14824 7344 14825 7345 14825 13911 14825 13911 14826 7345 14826 5611 14826 13911 14827 5611 14827 13895 14827 13895 14828 5611 14828 7346 14828 7346 14829 5611 14829 5610 14829 7346 14830 5610 14830 7347 14830 7347 14831 5610 14831 7348 14831 7348 14832 5610 14832 5613 14832 7348 14833 5613 14833 5606 14833 14171 14834 7350 14834 7349 14834 7349 14835 7350 14835 7351 14835 7349 14836 7351 14836 14154 14836 14154 14837 7351 14837 7352 14837 7352 14838 7351 14838 7353 14838 7352 14839 7353 14839 7354 14839 7354 14840 7353 14840 14145 14840 14145 14841 7353 14841 7355 14841 14145 14842 7355 14842 7356 14842 7357 14843 7191 14843 14123 14843 14123 14844 14139 14844 7357 14844 7357 14845 14139 14845 14140 14845 7357 14846 14140 14846 7355 14846 7355 14847 14140 14847 14142 14847 7355 14848 14142 14848 7356 14848 14128 14849 7194 14849 14129 14849 14129 14850 7194 14850 7192 14850 14129 14851 7192 14851 7358 14851 7358 14852 7192 14852 7359 14852 7358 14853 7359 14853 7360 14853 7360 14854 7359 14854 7193 14854 7360 14855 7193 14855 14131 14855 14131 14856 7193 14856 7195 14856 14326 14857 7212 14857 14307 14857 14307 14858 7212 14858 7361 14858 14307 14859 7361 14859 14309 14859 14309 14860 7361 14860 7362 14860 14309 14861 7362 14861 7364 14861 7364 14862 7362 14862 7363 14862 7364 14863 7363 14863 14288 14863 14288 14864 7363 14864 7210 14864 7365 14865 7215 14865 14267 14865 14267 14866 7215 14866 7366 14866 14267 14867 7366 14867 14268 14867 14268 14868 7366 14868 14261 14868 14261 14869 7366 14869 7217 14869 14261 14870 7217 14870 7367 14870 7367 14871 7217 14871 7368 14871 7368 14872 7217 14872 7216 14872 7368 14873 7216 14873 14259 14873 14259 14874 7216 14874 7369 14874 7369 14875 7216 14875 7370 14875 7369 14876 7370 14876 7371 14876 7213 14877 7208 14877 7370 14877 7370 14878 7208 14878 14256 14878 7370 14879 14256 14879 7371 14879 7372 14880 7219 14880 7373 14880 7373 14881 7219 14881 7374 14881 7373 14882 7374 14882 7375 14882 7375 14883 7374 14883 7376 14883 7375 14884 7376 14884 14328 14884 14328 14885 7376 14885 7218 14885 14328 14886 7218 14886 14329 14886 14329 14887 7218 14887 7214 14887 7495 14888 5490 14888 7377 14888 7377 14889 5490 14889 5495 14889 7377 14890 5495 14890 11971 14890 11971 14891 5495 14891 11972 14891 11972 14892 5495 14892 5493 14892 11972 14893 5493 14893 7497 14893 12268 14894 7378 14894 12267 14894 12267 14895 7378 14895 7379 14895 12267 14896 7379 14896 7380 14896 7380 14897 7379 14897 7381 14897 7381 14898 7379 14898 7382 14898 7381 14899 7382 14899 12264 14899 12264 14900 7382 14900 12230 14900 12230 14901 7382 14901 7385 14901 12230 14902 7385 14902 12236 14902 7383 14903 4596 14903 5498 14903 5498 14904 12221 14904 7383 14904 7383 14905 12221 14905 7384 14905 7383 14906 7384 14906 7385 14906 7385 14907 7384 14907 12231 14907 7385 14908 12231 14908 12236 14908 7538 14909 7386 14909 5800 14909 7538 14910 5800 14910 11288 14910 11288 14911 5800 14911 5802 14911 11288 14912 5802 14912 11334 14912 5832 14913 9815 14913 11085 14913 11085 14914 9815 14914 9818 14914 11085 14915 9818 14915 11086 14915 15167 14916 7387 14916 7388 14916 11086 14917 9818 14917 7388 14917 7388 14918 9818 14918 15166 14918 7388 14919 15166 14919 15167 14919 7389 14920 7390 14920 5825 14920 7389 14921 5825 14921 10999 14921 10999 14922 5825 14922 7560 14922 10999 14923 7560 14923 7561 14923 7391 14924 5866 14924 7392 14924 7391 14925 7392 14925 7393 14925 7393 14926 7392 14926 5868 14926 7393 14927 5868 14927 11621 14927 10769 14928 7399 14928 10763 14928 10763 14929 7399 14929 7402 14929 10763 14930 7402 14930 7459 14930 7397 14931 7394 14931 7404 14931 7404 14932 7394 14932 10841 14932 7404 14933 10841 14933 10846 14933 10833 14934 7396 14934 7395 14934 7395 14935 7396 14935 7403 14935 7395 14936 7403 14936 10876 14936 7397 14937 7404 14937 7399 14937 7577 14938 7397 14938 7398 14938 7398 14939 7397 14939 7399 14939 7398 14940 7399 14940 7400 14940 7400 14941 7399 14941 7581 14941 7401 14942 7461 14942 7465 14942 7465 14943 7461 14943 7402 14943 7465 14944 7402 14944 7396 14944 7396 14945 7402 14945 7403 14945 7404 14946 7583 14946 7587 14946 7402 14947 7399 14947 7403 14947 7403 14948 7399 14948 7404 14948 7403 14949 7404 14949 7585 14949 7585 14950 7404 14950 7587 14950 7413 14951 7420 14951 10608 14951 10608 14952 7420 14952 7418 14952 10608 14953 7418 14953 7405 14953 10546 14954 7479 14954 7406 14954 7406 14955 7479 14955 7407 14955 7406 14956 7407 14956 7409 14956 7408 14957 7415 14957 10615 14957 10615 14958 7415 14958 7469 14958 10615 14959 7469 14959 10616 14959 7409 14960 7407 14960 10554 14960 10554 14961 7407 14961 7411 14961 10591 14962 10579 14962 7419 14962 7419 14963 10579 14963 7410 14963 7419 14964 7410 14964 7411 14964 7411 14965 7410 14965 10555 14965 7411 14966 10555 14966 10554 14966 10591 14967 7419 14967 10587 14967 10587 14968 7419 14968 7412 14968 10587 14969 7412 14969 10577 14969 7420 14970 7413 14970 7412 14970 7412 14971 7413 14971 7414 14971 7412 14972 7414 14972 10577 14972 7469 14973 7415 14973 7479 14973 7479 14974 7415 14974 7418 14974 7479 14975 7418 14975 7407 14975 7479 14976 7478 14976 7477 14976 7469 14977 7479 14977 7470 14977 7470 14978 7479 14978 7477 14978 7470 14979 7477 14979 7475 14979 7589 14980 7416 14980 7417 14980 7417 14981 7416 14981 7418 14981 7417 14982 7418 14982 7592 14982 7592 14983 7418 14983 7415 14983 7419 14984 7411 14984 7412 14984 7412 14985 7411 14985 7407 14985 7412 14986 7407 14986 7420 14986 7420 14987 7407 14987 7418 14987 7606 14988 7605 14988 10275 14988 10275 14989 7605 14989 7421 14989 10259 14990 10261 14990 7421 14990 7421 14991 10261 14991 10274 14991 7421 14992 10274 14992 10275 14992 7434 14993 7607 14993 7422 14993 7434 14994 7422 14994 7424 14994 7422 14995 7423 14995 7424 14995 7424 14996 7423 14996 7425 14996 7424 14997 7425 14997 7426 14997 7426 14998 10366 14998 7424 14998 7424 14999 10366 14999 10328 14999 7424 15000 10328 15000 10297 15000 7432 15001 10384 15001 7429 15001 7429 15002 10384 15002 10388 15002 7429 15003 10388 15003 7435 15003 7435 15004 10388 15004 7427 15004 7435 15005 7427 15005 7611 15005 7428 15006 10346 15006 7429 15006 7429 15007 10346 15007 10340 15007 10340 15008 7430 15008 7429 15008 7429 15009 7430 15009 7431 15009 7429 15010 7431 15010 7432 15010 7429 15011 7605 15011 7437 15011 7609 15012 7608 15012 7433 15012 7433 15013 7608 15013 7434 15013 7433 15014 7434 15014 7435 15014 7435 15015 7434 15015 7429 15015 7424 15016 7487 15016 7488 15016 7436 15017 7438 15017 7437 15017 7437 15018 7438 15018 7601 15018 7437 15019 7601 15019 7429 15019 7429 15020 7434 15020 7605 15020 7605 15021 7434 15021 7424 15021 7605 15022 7424 15022 7421 15022 7421 15023 7424 15023 7488 15023 7421 15024 7488 15024 7484 15024 5896 15025 5892 15025 7441 15025 7441 15026 5892 15026 15055 15026 15066 15027 15061 15027 7441 15027 7441 15028 15061 15028 7440 15028 15057 15029 10502 15029 15058 15029 15058 15030 10502 15030 7440 15030 15058 15031 7440 15031 7439 15031 7439 15032 7440 15032 15061 15032 15055 15033 7442 15033 7441 15033 7441 15034 7442 15034 7443 15034 7441 15035 7443 15035 15066 15035 15649 15036 15662 15036 7445 15036 14605 15037 7444 15037 14534 15037 14534 15038 7444 15038 7446 15038 14534 15039 7446 15039 14543 15039 14529 15040 7446 15040 7445 15040 7445 15041 7446 15041 15642 15041 7445 15042 15642 15042 15649 15042 14529 15043 14528 15043 7446 15043 7446 15044 14528 15044 14530 15044 7446 15045 14530 15045 14432 15045 14432 15046 14434 15046 7446 15046 7446 15047 14434 15047 14437 15047 7446 15048 14437 15048 14543 15048 7616 15049 7627 15049 7615 15049 7615 15050 7627 15050 7625 15050 10083 15051 7624 15051 7447 15051 7447 15052 7624 15052 7450 15052 7448 15053 7449 15053 7624 15053 7624 15054 7449 15054 10070 15054 7624 15055 10070 15055 7450 15055 10076 15056 7451 15056 10119 15056 10119 15057 7451 15057 7454 15057 10119 15058 7454 15058 7452 15058 7452 15059 7454 15059 10115 15059 7448 15060 7624 15060 7616 15060 7616 15061 7624 15061 7627 15061 7622 15062 7620 15062 7456 15062 7614 15063 7453 15063 7616 15063 7616 15064 7453 15064 7613 15064 7616 15065 7613 15065 7448 15065 7451 15066 7627 15066 7454 15066 7454 15067 7627 15067 7624 15067 7454 15068 7624 15068 7456 15068 7456 15069 7624 15069 7455 15069 7456 15070 7455 15070 7622 15070 7451 15071 7457 15071 7627 15071 7627 15072 7457 15072 7458 15072 7627 15073 7458 15073 7628 15073 7459 15074 7402 15074 7463 15074 7463 15075 7402 15075 7461 15075 7401 15076 7460 15076 7461 15076 7461 15077 7460 15077 7462 15077 7461 15078 7462 15078 7463 15078 7467 15079 7464 15079 7465 15079 7465 15080 7464 15080 10811 15080 7465 15081 10811 15081 7401 15081 7401 15082 10811 15082 7466 15082 7401 15083 7466 15083 7460 15083 7467 15084 7465 15084 7468 15084 7468 15085 7465 15085 7396 15085 7468 15086 7396 15086 10833 15086 10616 15087 7469 15087 7470 15087 7475 15088 7471 15088 7470 15088 7470 15089 7471 15089 7472 15089 7470 15090 7472 15090 10616 15090 7477 15091 7473 15091 7475 15091 7475 15092 7473 15092 7474 15092 7475 15093 7474 15093 7471 15093 10574 15094 7476 15094 7477 15094 7477 15095 7476 15095 10568 15095 7477 15096 10568 15096 7473 15096 7477 15097 7478 15097 10574 15097 10574 15098 7478 15098 7479 15098 10574 15099 7479 15099 10546 15099 7490 15100 7483 15100 7488 15100 10259 15101 7421 15101 7480 15101 7480 15102 7421 15102 7484 15102 7480 15103 7484 15103 7481 15103 7481 15104 7484 15104 7482 15104 7488 15105 7483 15105 7484 15105 7484 15106 7483 15106 10269 15106 7484 15107 10269 15107 7482 15107 7487 15108 7424 15108 10297 15108 10297 15109 7485 15109 7487 15109 7487 15110 7485 15110 7486 15110 7487 15111 7486 15111 7488 15111 7488 15112 7486 15112 7489 15112 7488 15113 7489 15113 7490 15113 11956 15114 7491 15114 7492 15114 7492 15115 7491 15115 5487 15115 7492 15116 5487 15116 11945 15116 5486 15117 5488 15117 7496 15117 7496 15118 7493 15118 5486 15118 5486 15119 7493 15119 7494 15119 5486 15120 7494 15120 5487 15120 5487 15121 7494 15121 11946 15121 5487 15122 11946 15122 11945 15122 5489 15123 5490 15123 7495 15123 7495 15124 11919 15124 5489 15124 5489 15125 11919 15125 11918 15125 5489 15126 11918 15126 5488 15126 5488 15127 11918 15127 11930 15127 5488 15128 11930 15128 7496 15128 7497 15129 5493 15129 12029 15129 12029 15130 5493 15130 5491 15130 7498 15131 7499 15131 7500 15131 7500 15132 7499 15132 12025 15132 7500 15133 12025 15133 5491 15133 5491 15134 12025 15134 7501 15134 5491 15135 7501 15135 12029 15135 7498 15136 7500 15136 7502 15136 7502 15137 7500 15137 5492 15137 7502 15138 5492 15138 12015 15138 12015 15139 5492 15139 7503 15139 7503 15140 5492 15140 5494 15140 7503 15141 5494 15141 5476 15141 7506 15142 7504 15142 7507 15142 5528 15143 14403 15143 11827 15143 11827 15144 14403 15144 7505 15144 11827 15145 7505 15145 11807 15145 7507 15146 7504 15146 7505 15146 7505 15147 7504 15147 11825 15147 7505 15148 11825 15148 11807 15148 7506 15149 7507 15149 11814 15149 11814 15150 7507 15150 14402 15150 11814 15151 14402 15151 11812 15151 11812 15152 14402 15152 5880 15152 11812 15153 5880 15153 11811 15153 7508 15154 5854 15154 7509 15154 7509 15155 5854 15155 7510 15155 7509 15156 7510 15156 7511 15156 7511 15157 7510 15157 11604 15157 11604 15158 7510 15158 7514 15158 11604 15159 7514 15159 7512 15159 5864 15160 7516 15160 7514 15160 7514 15161 7516 15161 7513 15161 7514 15162 7513 15162 7512 15162 7515 15163 5866 15163 7391 15163 7391 15164 11580 15164 7515 15164 7515 15165 11580 15165 11591 15165 7515 15166 11591 15166 5864 15166 5864 15167 11591 15167 11590 15167 5864 15168 11590 15168 7516 15168 11621 15169 5868 15169 7517 15169 7517 15170 5868 15170 5867 15170 7517 15171 5867 15171 7518 15171 7518 15172 5867 15172 11658 15172 11658 15173 5867 15173 7519 15173 11658 15174 7519 15174 11660 15174 11660 15175 7519 15175 7520 15175 11660 15176 7520 15176 11661 15176 11661 15177 7520 15177 11663 15177 11663 15178 7520 15178 7522 15178 11663 15179 7522 15179 7521 15179 7521 15180 7522 15180 11665 15180 11665 15181 7522 15181 5848 15181 11665 15182 5848 15182 5846 15182 7523 15183 7524 15183 14389 15183 14389 15184 7524 15184 11571 15184 14389 15185 11571 15185 14390 15185 7523 15186 14389 15186 11525 15186 11525 15187 14389 15187 7525 15187 11525 15188 7525 15188 7527 15188 7527 15189 7525 15189 7526 15189 7527 15190 7526 15190 11529 15190 11529 15191 7526 15191 14384 15191 11529 15192 14384 15192 11514 15192 7528 15193 7529 15193 7533 15193 7533 15194 7529 15194 7531 15194 7537 15195 7530 15195 7531 15195 7531 15196 7530 15196 7532 15196 7531 15197 7532 15197 7533 15197 7534 15198 7535 15198 5798 15198 5798 15199 7535 15199 7536 15199 5798 15200 7536 15200 7537 15200 7537 15201 7536 15201 11260 15201 7537 15202 11260 15202 7530 15202 7540 15203 7386 15203 7538 15203 7538 15204 7539 15204 7540 15204 7540 15205 7539 15205 11264 15205 7540 15206 11264 15206 5798 15206 5798 15207 11264 15207 7541 15207 5798 15208 7541 15208 7534 15208 11334 15209 5802 15209 11335 15209 11335 15210 5802 15210 7542 15210 11335 15211 7542 15211 11305 15211 11305 15212 7542 15212 11324 15212 11324 15213 7542 15213 7543 15213 11324 15214 7543 15214 7544 15214 7544 15215 7543 15215 5801 15215 7544 15216 5801 15216 11316 15216 11316 15217 5801 15217 7545 15217 7545 15218 5801 15218 7546 15218 7545 15219 7546 15219 11312 15219 11312 15220 7546 15220 7547 15220 7547 15221 7546 15221 5803 15221 7547 15222 5803 15222 11366 15222 14377 15223 7548 15223 7550 15223 7550 15224 7548 15224 7549 15224 7550 15225 7549 15225 14378 15225 14378 15226 7549 15226 11253 15226 14378 15227 11253 15227 5842 15227 11248 15228 7551 15228 14379 15228 14379 15229 7551 15229 11249 15229 14379 15230 11249 15230 14377 15230 14377 15231 11249 15231 11250 15231 14377 15232 11250 15232 7548 15232 11248 15233 14379 15233 11225 15233 11225 15234 14379 15234 7552 15234 11225 15235 7552 15235 11213 15235 11054 15236 11074 15236 5830 15236 5830 15237 11074 15237 7553 15237 7553 15238 11074 15238 7554 15238 7553 15239 7554 15239 5822 15239 11054 15240 5830 15240 7555 15240 7555 15241 5830 15241 7556 15241 7555 15242 7556 15242 7557 15242 7557 15243 7556 15243 11035 15243 11035 15244 7556 15244 7558 15244 11035 15245 7558 15245 11038 15245 7559 15246 7390 15246 7389 15246 7389 15247 11042 15247 7559 15247 7559 15248 11042 15248 11041 15248 7559 15249 11041 15249 7558 15249 7558 15250 11041 15250 11039 15250 7558 15251 11039 15251 11038 15251 7560 15252 7562 15252 7561 15252 7561 15253 7562 15253 7563 15253 7563 15254 7562 15254 7564 15254 7564 15255 7562 15255 7565 15255 7564 15256 7565 15256 11020 15256 11020 15257 7565 15257 7566 15257 7566 15258 7565 15258 7569 15258 7566 15259 7569 15259 7567 15259 7567 15260 7569 15260 7568 15260 7568 15261 7569 15261 7570 15261 7568 15262 7570 15262 11067 15262 11067 15263 7570 15263 5832 15263 11067 15264 5832 15264 11085 15264 5908 15265 5913 15265 10946 15265 10946 15266 5913 15266 7571 15266 10946 15267 7571 15267 10940 15267 10940 15268 7571 15268 10941 15268 10941 15269 7571 15269 5922 15269 10941 15270 5922 15270 7572 15270 7572 15271 5922 15271 10944 15271 10944 15272 5922 15272 7573 15272 10944 15273 7573 15273 7574 15273 7574 15274 7573 15274 7575 15274 7575 15275 7573 15275 5924 15275 7575 15276 5924 15276 10929 15276 7576 15277 7394 15277 7397 15277 7576 15278 7397 15278 10824 15278 10824 15279 7397 15279 7577 15279 10824 15280 7577 15280 7578 15280 7578 15281 7577 15281 7398 15281 7578 15282 7398 15282 7579 15282 7579 15283 7398 15283 7580 15283 7580 15284 7398 15284 7400 15284 7580 15285 7400 15285 10789 15285 7581 15286 7399 15286 10769 15286 10769 15287 10793 15287 7581 15287 7581 15288 10793 15288 10792 15288 7581 15289 10792 15289 7400 15289 7400 15290 10792 15290 7582 15290 7400 15291 7582 15291 10789 15291 10855 15292 10854 15292 7583 15292 10876 15293 7403 15293 7584 15293 7584 15294 7403 15294 7585 15294 7584 15295 7585 15295 10867 15295 10867 15296 7585 15296 7586 15296 7586 15297 7585 15297 7587 15297 7586 15298 7587 15298 10868 15298 7583 15299 10854 15299 7587 15299 7587 15300 10854 15300 10865 15300 7587 15301 10865 15301 10868 15301 7404 15302 10846 15302 7583 15302 7583 15303 10846 15303 7588 15303 7583 15304 7588 15304 10855 15304 7418 15305 7416 15305 7405 15305 7405 15306 7416 15306 10654 15306 10654 15307 7416 15307 10640 15307 10640 15308 7416 15308 7589 15308 10640 15309 7589 15309 7590 15309 7590 15310 7589 15310 7591 15310 7591 15311 7589 15311 7417 15311 7591 15312 7417 15312 10639 15312 10639 15313 7417 15313 7592 15313 10639 15314 7592 15314 10628 15314 7415 15315 7408 15315 7592 15315 7592 15316 7408 15316 10629 15316 7592 15317 10629 15317 10628 15317 10438 15318 5897 15318 10487 15318 10487 15319 5897 15319 7593 15319 10487 15320 7593 15320 10483 15320 10483 15321 7593 15321 7594 15321 7594 15322 7593 15322 7595 15322 7594 15323 7595 15323 7596 15323 7596 15324 7595 15324 10463 15324 10463 15325 7595 15325 7597 15325 10463 15326 7597 15326 7598 15326 5894 15327 5896 15327 7441 15327 7441 15328 7599 15328 5894 15328 5894 15329 7599 15329 10461 15329 5894 15330 10461 15330 7597 15330 7597 15331 10461 15331 7600 15331 7597 15332 7600 15332 7598 15332 7428 15333 7429 15333 10324 15333 10324 15334 7429 15334 7601 15334 10324 15335 7601 15335 10319 15335 10319 15336 7601 15336 10315 15336 10315 15337 7601 15337 7438 15337 10315 15338 7438 15338 7602 15338 7602 15339 7438 15339 10316 15339 10316 15340 7438 15340 7436 15340 10316 15341 7436 15341 10317 15341 10317 15342 7436 15342 7603 15342 7603 15343 7436 15343 7437 15343 7603 15344 7437 15344 7604 15344 7604 15345 7437 15345 10301 15345 10301 15346 7437 15346 7605 15346 10301 15347 7605 15347 7606 15347 7607 15348 7434 15348 10404 15348 10404 15349 7434 15349 7608 15349 10404 15350 7608 15350 7610 15350 7610 15351 7608 15351 7609 15351 7610 15352 7609 15352 10405 15352 10405 15353 7609 15353 7433 15353 10405 15354 7433 15354 7611 15354 7611 15355 7433 15355 7435 15355 7449 15356 7448 15356 7612 15356 7612 15357 7448 15357 7613 15357 7612 15358 7613 15358 10039 15358 10039 15359 7613 15359 7453 15359 10039 15360 7453 15360 10041 15360 10041 15361 7453 15361 7614 15361 10041 15362 7614 15362 7615 15362 7615 15363 7614 15363 7616 15363 10115 15364 7454 15364 7617 15364 7617 15365 7454 15365 7456 15365 7617 15366 7456 15366 10082 15366 10082 15367 7456 15367 7618 15367 7618 15368 7456 15368 7620 15368 7618 15369 7620 15369 7619 15369 7619 15370 7620 15370 7621 15370 7621 15371 7620 15371 7622 15371 7621 15372 7622 15372 10087 15372 10087 15373 7622 15373 10086 15373 10086 15374 7622 15374 7455 15374 10086 15375 7455 15375 10085 15375 10085 15376 7455 15376 7623 15376 7623 15377 7455 15377 7624 15377 7623 15378 7624 15378 10083 15378 7625 15379 7627 15379 7626 15379 7626 15380 7627 15380 7628 15380 7626 15381 7628 15381 10060 15381 10060 15382 7628 15382 7458 15382 10060 15383 7458 15383 10064 15383 10064 15384 7458 15384 7457 15384 10064 15385 7457 15385 10076 15385 10076 15386 7457 15386 7451 15386 7643 15387 6160 15387 7629 15387 7629 15388 6160 15388 7630 15388 7633 15389 7631 15389 8510 15389 7633 15390 8510 15390 7639 15390 8504 15391 7631 15391 7632 15391 7632 15392 7631 15392 7633 15392 7632 15393 7633 15393 8506 15393 8506 15394 7633 15394 7635 15394 8506 15395 7635 15395 7634 15395 7634 15396 7635 15396 7645 15396 7634 15397 7645 15397 8474 15397 6160 15398 7636 15398 7630 15398 7630 15399 7636 15399 7637 15399 7630 15400 7637 15400 8552 15400 8552 15401 7637 15401 6155 15401 8510 15402 7638 15402 7639 15402 7639 15403 7638 15403 7640 15403 7639 15404 7640 15404 7641 15404 7641 15405 7640 15405 7642 15405 7641 15406 7642 15406 6155 15406 6155 15407 7642 15407 8537 15407 6155 15408 8537 15408 8552 15408 7643 15409 7629 15409 6159 15409 6159 15410 7629 15410 8171 15410 6159 15411 8171 15411 7644 15411 7645 15412 7646 15412 8474 15412 8474 15413 7646 15413 6159 15413 8474 15414 6159 15414 7647 15414 7647 15415 6159 15415 7644 15415 7647 15416 17075 15416 17057 15416 7647 15417 17057 15417 8474 15417 8474 15418 17057 15418 17058 15418 8474 15419 17058 15419 8443 15419 8443 15420 17058 15420 8156 15420 8443 15421 8156 15421 8437 15421 8190 15422 8178 15422 8619 15422 8619 15423 8178 15423 8151 15423 8619 15424 8151 15424 8172 15424 7648 15425 8434 15425 17063 15425 17063 15426 8434 15426 8432 15426 17063 15427 8432 15427 8158 15427 8158 15428 8432 15428 8401 15428 8158 15429 8401 15429 8157 15429 7659 15430 7649 15430 7658 15430 7650 15431 7651 15431 7666 15431 7658 15432 7649 15432 7652 15432 7652 15433 7649 15433 7654 15433 7652 15434 7654 15434 7653 15434 7653 15435 7654 15435 7655 15435 7653 15436 7655 15436 8187 15436 7656 15437 7660 15437 7657 15437 7657 15438 7660 15438 8535 15438 7657 15439 8535 15439 7665 15439 7658 15440 8572 15440 7659 15440 7659 15441 8572 15441 8571 15441 7659 15442 8571 15442 7656 15442 7656 15443 8571 15443 8557 15443 7656 15444 8557 15444 7660 15444 8479 15445 4467 15445 4466 15445 7655 15446 7661 15446 8187 15446 8187 15447 7661 15447 6153 15447 8187 15448 6153 15448 8181 15448 8181 15449 6153 15449 6152 15449 8479 15450 4466 15450 7663 15450 17077 15451 8177 15451 7662 15451 7662 15452 8177 15452 7663 15452 7662 15453 7663 15453 7664 15453 7664 15454 7663 15454 4466 15454 8535 15455 7650 15455 7665 15455 7665 15456 7650 15456 7666 15456 7665 15457 7666 15457 6150 15457 6150 15458 7666 15458 7667 15458 6150 15459 7667 15459 6151 15459 6151 15460 7667 15460 7663 15460 6151 15461 7663 15461 6152 15461 6152 15462 7663 15462 8177 15462 6152 15463 8177 15463 8181 15463 7668 15464 6663 15464 7669 15464 7672 15465 7670 15465 7713 15465 7713 15466 7670 15466 7668 15466 7790 15467 7671 15467 7740 15467 7740 15468 7671 15468 7672 15468 5405 15469 5265 15469 7789 15469 7675 15470 7673 15470 5290 15470 7673 15471 7675 15471 7674 15471 7674 15472 7675 15472 7676 15472 7674 15473 7676 15473 7677 15473 7677 15474 7676 15474 7678 15474 7678 15475 7676 15475 7784 15475 7678 15476 7784 15476 7679 15476 7679 15477 7784 15477 7680 15477 7680 15478 7784 15478 7783 15478 7680 15479 7783 15479 6712 15479 7690 15480 7692 15480 7681 15480 7681 15481 7692 15481 5407 15481 7681 15482 5407 15482 7682 15482 7682 15483 5407 15483 5406 15483 7682 15484 5406 15484 7683 15484 7683 15485 5406 15485 5405 15485 7683 15486 5405 15486 7741 15486 7741 15487 5405 15487 7789 15487 7741 15488 7789 15488 7790 15488 7779 15489 7684 15489 7744 15489 7744 15490 7684 15490 7685 15490 7744 15491 7685 15491 7686 15491 7686 15492 7685 15492 7687 15492 7686 15493 7687 15493 7688 15493 7688 15494 7687 15494 5399 15494 7688 15495 5399 15495 7689 15495 7689 15496 5399 15496 7691 15496 7689 15497 7691 15497 7690 15497 7690 15498 7691 15498 5402 15498 7690 15499 5402 15499 7692 15499 7668 15500 7669 15500 7713 15500 7713 15501 7669 15501 6658 15501 7713 15502 6658 15502 7714 15502 7714 15503 6658 15503 6657 15503 7714 15504 6657 15504 7715 15504 7715 15505 6657 15505 6656 15505 7715 15506 6656 15506 7719 15506 7719 15507 6656 15507 7693 15507 7719 15508 7693 15508 7694 15508 7694 15509 7693 15509 6678 15509 7694 15510 6678 15510 7720 15510 7720 15511 6678 15511 7695 15511 7720 15512 7695 15512 7721 15512 7721 15513 7695 15513 6680 15513 7721 15514 6680 15514 7696 15514 7696 15515 6680 15515 7697 15515 7696 15516 7697 15516 7723 15516 7723 15517 7697 15517 7698 15517 7723 15518 7698 15518 7725 15518 7725 15519 7698 15519 7699 15519 7725 15520 7699 15520 7726 15520 7726 15521 7699 15521 6683 15521 7726 15522 6683 15522 7700 15522 7700 15523 6683 15523 7701 15523 7700 15524 7701 15524 7728 15524 7728 15525 7701 15525 7702 15525 7728 15526 7702 15526 7729 15526 7729 15527 7702 15527 6685 15527 7729 15528 6685 15528 7730 15528 7730 15529 6685 15529 6686 15529 7730 15530 6686 15530 7703 15530 7703 15531 6686 15531 6688 15531 7703 15532 6688 15532 7731 15532 7731 15533 6688 15533 7704 15533 7731 15534 7704 15534 7705 15534 7705 15535 7704 15535 7706 15535 7705 15536 7706 15536 7707 15536 7707 15537 7706 15537 6689 15537 7707 15538 6689 15538 7708 15538 7708 15539 6689 15539 6690 15539 7708 15540 6690 15540 7734 15540 7734 15541 6690 15541 6693 15541 7734 15542 6693 15542 7710 15542 7710 15543 6693 15543 7709 15543 7710 15544 7709 15544 7736 15544 7736 15545 7709 15545 7711 15545 7736 15546 7711 15546 7737 15546 7737 15547 7711 15547 7712 15547 7737 15548 7712 15548 7738 15548 7672 15549 7713 15549 7740 15549 7740 15550 7713 15550 7714 15550 7740 15551 7714 15551 7716 15551 7716 15552 7714 15552 7715 15552 7716 15553 7715 15553 7717 15553 7717 15554 7715 15554 7719 15554 7717 15555 7719 15555 7718 15555 7718 15556 7719 15556 7694 15556 7718 15557 7694 15557 7742 15557 7742 15558 7694 15558 7720 15558 7742 15559 7720 15559 7743 15559 7743 15560 7720 15560 7721 15560 7743 15561 7721 15561 7722 15561 7722 15562 7721 15562 7696 15562 7722 15563 7696 15563 7724 15563 7724 15564 7696 15564 7723 15564 7724 15565 7723 15565 7745 15565 7745 15566 7723 15566 7725 15566 7745 15567 7725 15567 7746 15567 7746 15568 7725 15568 7726 15568 7746 15569 7726 15569 7747 15569 7747 15570 7726 15570 7700 15570 7747 15571 7700 15571 7727 15571 7727 15572 7700 15572 7728 15572 7727 15573 7728 15573 7748 15573 7748 15574 7728 15574 7729 15574 7748 15575 7729 15575 7749 15575 7749 15576 7729 15576 7730 15576 7749 15577 7730 15577 7751 15577 7751 15578 7730 15578 7703 15578 7751 15579 7703 15579 7732 15579 7732 15580 7703 15580 7731 15580 7732 15581 7731 15581 7754 15581 7754 15582 7731 15582 7705 15582 7754 15583 7705 15583 7756 15583 7756 15584 7705 15584 7707 15584 7756 15585 7707 15585 7758 15585 7758 15586 7707 15586 7708 15586 7758 15587 7708 15587 7733 15587 7733 15588 7708 15588 7734 15588 7733 15589 7734 15589 7735 15589 7735 15590 7734 15590 7710 15590 7735 15591 7710 15591 7760 15591 7760 15592 7710 15592 7736 15592 7760 15593 7736 15593 7761 15593 7761 15594 7736 15594 7737 15594 7761 15595 7737 15595 7763 15595 7763 15596 7737 15596 7738 15596 7763 15597 7738 15597 7739 15597 7790 15598 7740 15598 7741 15598 7741 15599 7740 15599 7716 15599 7741 15600 7716 15600 7683 15600 7683 15601 7716 15601 7717 15601 7683 15602 7717 15602 7682 15602 7682 15603 7717 15603 7718 15603 7682 15604 7718 15604 7681 15604 7681 15605 7718 15605 7742 15605 7681 15606 7742 15606 7690 15606 7690 15607 7742 15607 7743 15607 7690 15608 7743 15608 7689 15608 7689 15609 7743 15609 7722 15609 7689 15610 7722 15610 7688 15610 7688 15611 7722 15611 7724 15611 7688 15612 7724 15612 7686 15612 7686 15613 7724 15613 7745 15613 7686 15614 7745 15614 7744 15614 7744 15615 7745 15615 7746 15615 7744 15616 7746 15616 7779 15616 7779 15617 7746 15617 7747 15617 7779 15618 7747 15618 7776 15618 7776 15619 7747 15619 7727 15619 7776 15620 7727 15620 7775 15620 7775 15621 7727 15621 7748 15621 7775 15622 7748 15622 7750 15622 7750 15623 7748 15623 7749 15623 7750 15624 7749 15624 7752 15624 7752 15625 7749 15625 7751 15625 7752 15626 7751 15626 7753 15626 7753 15627 7751 15627 7732 15627 7753 15628 7732 15628 7771 15628 7771 15629 7732 15629 7754 15629 7771 15630 7754 15630 7755 15630 7755 15631 7754 15631 7756 15631 7755 15632 7756 15632 7770 15632 7770 15633 7756 15633 7758 15633 7770 15634 7758 15634 7757 15634 7757 15635 7758 15635 7733 15635 7757 15636 7733 15636 7767 15636 7767 15637 7733 15637 7735 15637 7767 15638 7735 15638 7759 15638 7759 15639 7735 15639 7760 15639 7759 15640 7760 15640 7766 15640 7766 15641 7760 15641 7761 15641 7766 15642 7761 15642 7762 15642 7762 15643 7761 15643 7763 15643 7762 15644 7763 15644 7764 15644 7764 15645 7763 15645 7739 15645 7764 15646 7739 15646 7781 15646 7781 15647 5385 15647 7764 15647 7764 15648 5385 15648 7765 15648 7764 15649 7765 15649 7762 15649 7762 15650 7765 15650 5387 15650 7762 15651 5387 15651 7766 15651 7766 15652 5387 15652 5388 15652 7766 15653 5388 15653 7759 15653 7759 15654 5388 15654 5389 15654 7759 15655 5389 15655 7767 15655 7767 15656 5389 15656 7768 15656 7767 15657 7768 15657 7757 15657 7757 15658 7768 15658 5390 15658 7757 15659 5390 15659 7770 15659 7770 15660 5390 15660 7769 15660 7770 15661 7769 15661 7755 15661 7755 15662 7769 15662 5391 15662 7755 15663 5391 15663 7771 15663 7771 15664 5391 15664 7772 15664 7771 15665 7772 15665 7753 15665 7753 15666 7772 15666 7773 15666 7753 15667 7773 15667 7752 15667 7752 15668 7773 15668 5395 15668 7752 15669 5395 15669 7750 15669 7750 15670 5395 15670 7774 15670 7750 15671 7774 15671 7775 15671 7775 15672 7774 15672 5396 15672 7775 15673 5396 15673 7776 15673 7776 15674 5396 15674 7777 15674 7776 15675 7777 15675 7779 15675 7779 15676 7777 15676 7778 15676 7779 15677 7778 15677 7684 15677 7780 15678 5383 15678 7781 15678 7781 15679 5383 15679 7782 15679 7781 15680 7782 15680 5385 15680 6713 15681 7783 15681 7785 15681 7785 15682 7783 15682 7784 15682 7785 15683 7784 15683 7786 15683 7786 15684 7784 15684 7676 15684 7786 15685 7676 15685 7787 15685 7787 15686 7676 15686 7675 15686 7712 15687 6713 15687 7738 15687 7738 15688 6713 15688 7785 15688 7738 15689 7785 15689 7739 15689 7739 15690 7785 15690 7786 15690 7739 15691 7786 15691 7781 15691 7781 15692 7786 15692 7787 15692 7781 15693 7787 15693 7780 15693 7780 15694 7787 15694 7675 15694 7780 15695 7675 15695 5427 15695 5427 15696 7675 15696 5290 15696 7680 15697 6712 15697 6709 15697 7845 15698 7679 15698 7680 15698 7788 15699 7677 15699 7678 15699 7792 15700 5290 15700 7673 15700 7790 15701 7789 15701 7869 15701 7869 15702 7789 15702 5265 15702 7672 15703 7671 15703 7815 15703 7815 15704 7671 15704 7790 15704 7814 15705 7670 15705 7672 15705 7791 15706 6663 15706 7668 15706 7891 15707 7792 15707 7866 15707 7866 15708 7792 15708 7673 15708 7866 15709 7673 15709 7674 15709 7680 15710 6709 15710 7845 15710 7845 15711 6709 15711 6708 15711 7845 15712 6708 15712 7844 15712 7844 15713 6708 15713 6706 15713 7844 15714 6706 15714 7842 15714 7842 15715 6706 15715 6705 15715 7842 15716 6705 15716 7793 15716 7793 15717 6705 15717 6704 15717 7793 15718 6704 15718 7794 15718 7794 15719 6704 15719 7795 15719 7794 15720 7795 15720 7839 15720 7839 15721 7795 15721 6701 15721 7839 15722 6701 15722 7796 15722 7796 15723 6701 15723 7797 15723 7796 15724 7797 15724 7835 15724 7835 15725 7797 15725 6698 15725 7835 15726 6698 15726 7798 15726 7798 15727 6698 15727 7799 15727 7798 15728 7799 15728 7832 15728 7832 15729 7799 15729 6662 15729 7832 15730 6662 15730 7800 15730 7800 15731 6662 15731 6661 15731 7800 15732 6661 15732 7829 15732 7829 15733 6661 15733 6659 15733 7829 15734 6659 15734 7827 15734 7827 15735 6659 15735 6677 15735 7827 15736 6677 15736 7801 15736 7801 15737 6677 15737 6676 15737 7801 15738 6676 15738 7825 15738 7825 15739 6676 15739 7802 15739 7825 15740 7802 15740 7823 15740 7823 15741 7802 15741 7803 15741 7823 15742 7803 15742 7822 15742 7822 15743 7803 15743 6675 15743 7822 15744 6675 15744 7804 15744 7804 15745 6675 15745 7805 15745 7804 15746 7805 15746 7806 15746 7806 15747 7805 15747 7808 15747 7806 15748 7808 15748 7807 15748 7807 15749 7808 15749 6671 15749 7807 15750 6671 15750 7809 15750 7809 15751 6671 15751 6670 15751 7809 15752 6670 15752 7818 15752 7818 15753 6670 15753 6669 15753 7818 15754 6669 15754 7810 15754 7810 15755 6669 15755 7811 15755 7810 15756 7811 15756 7812 15756 7812 15757 7811 15757 6666 15757 7812 15758 6666 15758 7813 15758 7813 15759 6666 15759 7791 15759 7813 15760 7791 15760 7814 15760 7814 15761 7791 15761 7668 15761 7814 15762 7668 15762 7670 15762 7672 15763 7815 15763 7814 15763 7814 15764 7815 15764 7816 15764 7814 15765 7816 15765 7813 15765 7813 15766 7816 15766 7847 15766 7813 15767 7847 15767 7812 15767 7812 15768 7847 15768 7817 15768 7812 15769 7817 15769 7810 15769 7810 15770 7817 15770 7848 15770 7810 15771 7848 15771 7818 15771 7818 15772 7848 15772 7819 15772 7818 15773 7819 15773 7809 15773 7809 15774 7819 15774 7820 15774 7809 15775 7820 15775 7807 15775 7807 15776 7820 15776 7850 15776 7807 15777 7850 15777 7806 15777 7806 15778 7850 15778 7853 15778 7806 15779 7853 15779 7804 15779 7804 15780 7853 15780 7821 15780 7804 15781 7821 15781 7822 15781 7822 15782 7821 15782 7856 15782 7822 15783 7856 15783 7823 15783 7823 15784 7856 15784 7857 15784 7823 15785 7857 15785 7825 15785 7825 15786 7857 15786 7824 15786 7825 15787 7824 15787 7801 15787 7801 15788 7824 15788 7826 15788 7801 15789 7826 15789 7827 15789 7827 15790 7826 15790 7828 15790 7827 15791 7828 15791 7829 15791 7829 15792 7828 15792 7830 15792 7829 15793 7830 15793 7800 15793 7800 15794 7830 15794 7831 15794 7800 15795 7831 15795 7832 15795 7832 15796 7831 15796 7833 15796 7832 15797 7833 15797 7798 15797 7798 15798 7833 15798 7834 15798 7798 15799 7834 15799 7835 15799 7835 15800 7834 15800 7836 15800 7835 15801 7836 15801 7796 15801 7796 15802 7836 15802 7837 15802 7796 15803 7837 15803 7839 15803 7839 15804 7837 15804 7838 15804 7839 15805 7838 15805 7794 15805 7794 15806 7838 15806 7840 15806 7794 15807 7840 15807 7793 15807 7793 15808 7840 15808 7841 15808 7793 15809 7841 15809 7842 15809 7842 15810 7841 15810 7843 15810 7842 15811 7843 15811 7844 15811 7844 15812 7843 15812 7788 15812 7844 15813 7788 15813 7845 15813 7845 15814 7788 15814 7678 15814 7845 15815 7678 15815 7679 15815 7790 15816 7869 15816 7815 15816 7815 15817 7869 15817 7846 15817 7815 15818 7846 15818 7816 15818 7816 15819 7846 15819 7870 15819 7816 15820 7870 15820 7847 15820 7847 15821 7870 15821 7873 15821 7847 15822 7873 15822 7817 15822 7817 15823 7873 15823 7849 15823 7817 15824 7849 15824 7848 15824 7848 15825 7849 15825 7875 15825 7848 15826 7875 15826 7819 15826 7819 15827 7875 15827 7876 15827 7819 15828 7876 15828 7820 15828 7820 15829 7876 15829 7851 15829 7820 15830 7851 15830 7850 15830 7850 15831 7851 15831 7852 15831 7850 15832 7852 15832 7853 15832 7853 15833 7852 15833 7854 15833 7853 15834 7854 15834 7821 15834 7821 15835 7854 15835 7879 15835 7821 15836 7879 15836 7856 15836 7856 15837 7879 15837 7855 15837 7856 15838 7855 15838 7857 15838 7857 15839 7855 15839 7880 15839 7857 15840 7880 15840 7824 15840 7824 15841 7880 15841 7881 15841 7824 15842 7881 15842 7826 15842 7826 15843 7881 15843 7858 15843 7826 15844 7858 15844 7828 15844 7828 15845 7858 15845 7882 15845 7828 15846 7882 15846 7830 15846 7830 15847 7882 15847 7859 15847 7830 15848 7859 15848 7831 15848 7831 15849 7859 15849 7860 15849 7831 15850 7860 15850 7833 15850 7833 15851 7860 15851 7861 15851 7833 15852 7861 15852 7834 15852 7834 15853 7861 15853 7862 15853 7834 15854 7862 15854 7836 15854 7836 15855 7862 15855 7885 15855 7836 15856 7885 15856 7837 15856 7837 15857 7885 15857 7863 15857 7837 15858 7863 15858 7838 15858 7838 15859 7863 15859 7864 15859 7838 15860 7864 15860 7840 15860 7840 15861 7864 15861 7865 15861 7840 15862 7865 15862 7841 15862 7841 15863 7865 15863 7891 15863 7841 15864 7891 15864 7843 15864 7843 15865 7891 15865 7866 15865 7843 15866 7866 15866 7788 15866 7788 15867 7866 15867 7674 15867 7788 15868 7674 15868 7677 15868 5265 15869 7867 15869 7869 15869 7869 15870 7867 15870 7868 15870 7869 15871 7868 15871 7846 15871 7846 15872 7868 15872 5266 15872 7846 15873 5266 15873 7870 15873 7870 15874 5266 15874 7871 15874 7870 15875 7871 15875 7873 15875 7873 15876 7871 15876 7872 15876 7873 15877 7872 15877 7849 15877 7849 15878 7872 15878 7874 15878 7849 15879 7874 15879 7875 15879 7875 15880 7874 15880 5269 15880 7875 15881 5269 15881 7876 15881 7876 15882 5269 15882 7877 15882 7876 15883 7877 15883 7851 15883 7851 15884 7877 15884 7878 15884 7851 15885 7878 15885 7852 15885 7852 15886 7878 15886 5271 15886 7852 15887 5271 15887 7854 15887 7854 15888 5271 15888 5323 15888 7854 15889 5323 15889 7879 15889 7879 15890 5323 15890 5275 15890 7879 15891 5275 15891 7855 15891 7855 15892 5275 15892 5278 15892 7855 15893 5278 15893 7880 15893 7880 15894 5278 15894 5279 15894 7880 15895 5279 15895 7881 15895 7881 15896 5279 15896 5282 15896 7881 15897 5282 15897 7858 15897 7858 15898 5282 15898 5283 15898 7858 15899 5283 15899 7882 15899 7882 15900 5283 15900 7883 15900 7882 15901 7883 15901 7859 15901 7859 15902 7883 15902 5285 15902 7859 15903 5285 15903 7860 15903 7860 15904 5285 15904 5287 15904 7860 15905 5287 15905 7861 15905 7861 15906 5287 15906 7884 15906 7861 15907 7884 15907 7862 15907 7862 15908 7884 15908 7886 15908 7862 15909 7886 15909 7885 15909 7885 15910 7886 15910 7887 15910 7885 15911 7887 15911 7863 15911 7863 15912 7887 15912 7888 15912 7863 15913 7888 15913 7864 15913 7864 15914 7888 15914 7889 15914 7864 15915 7889 15915 7865 15915 7865 15916 7889 15916 7890 15916 7865 15917 7890 15917 7891 15917 7891 15918 7890 15918 5289 15918 7891 15919 5289 15919 7792 15919 8010 15920 8095 15920 7892 15920 8065 15921 8009 15921 8008 15921 7893 15922 8064 15922 6664 15922 7977 15923 8094 15923 7976 15923 8012 15924 7894 15924 7896 15924 7896 15925 7894 15925 6623 15925 7895 15926 8011 15926 7978 15926 7895 15927 7978 15927 6710 15927 8010 15928 7892 15928 7952 15928 6623 15929 6624 15929 7896 15929 7896 15930 6624 15930 7897 15930 7896 15931 7897 15931 7898 15931 7898 15932 7897 15932 6626 15932 7898 15933 6626 15933 7899 15933 7899 15934 6626 15934 7900 15934 7899 15935 7900 15935 7901 15935 7901 15936 7900 15936 7902 15936 7901 15937 7902 15937 7903 15937 7903 15938 7902 15938 7904 15938 7903 15939 7904 15939 7937 15939 7937 15940 7904 15940 7905 15940 7937 15941 7905 15941 7938 15941 7938 15942 7905 15942 7906 15942 7938 15943 7906 15943 7907 15943 7907 15944 7906 15944 7908 15944 7907 15945 7908 15945 7909 15945 7909 15946 7908 15946 6634 15946 7909 15947 6634 15947 7910 15947 7910 15948 6634 15948 7912 15948 7910 15949 7912 15949 7911 15949 7911 15950 7912 15950 6636 15950 7911 15951 6636 15951 7913 15951 7913 15952 6636 15952 7914 15952 7913 15953 7914 15953 7915 15953 7915 15954 7914 15954 6637 15954 7915 15955 6637 15955 7916 15955 7916 15956 6637 15956 6639 15956 7916 15957 6639 15957 7944 15957 7944 15958 6639 15958 6641 15958 7944 15959 6641 15959 7945 15959 7945 15960 6641 15960 7917 15960 7945 15961 7917 15961 7946 15961 7917 15962 7918 15962 7946 15962 7946 15963 7918 15963 6643 15963 7946 15964 6643 15964 7919 15964 7919 15965 6643 15965 6645 15965 7919 15966 6645 15966 7920 15966 7920 15967 6645 15967 7921 15967 7920 15968 7921 15968 7922 15968 7922 15969 7921 15969 7923 15969 7922 15970 7923 15970 7924 15970 7923 15971 6648 15971 7924 15971 7924 15972 6648 15972 6647 15972 7924 15973 6647 15973 7925 15973 7925 15974 6647 15974 7927 15974 7925 15975 7927 15975 7926 15975 7926 15976 7927 15976 7928 15976 7926 15977 7928 15977 7929 15977 7929 15978 7928 15978 7930 15978 7929 15979 7930 15979 7932 15979 7930 15980 7931 15980 7932 15980 7932 15981 7931 15981 6651 15981 7932 15982 6651 15982 7950 15982 7950 15983 6651 15983 7933 15983 7950 15984 7933 15984 7951 15984 8094 15985 8012 15985 7976 15985 7976 15986 8012 15986 7896 15986 7976 15987 7896 15987 7975 15987 7975 15988 7896 15988 7898 15988 7975 15989 7898 15989 7973 15989 7973 15990 7898 15990 7899 15990 7973 15991 7899 15991 7934 15991 7934 15992 7899 15992 7901 15992 7934 15993 7901 15993 7935 15993 7935 15994 7901 15994 7903 15994 7935 15995 7903 15995 7936 15995 7936 15996 7903 15996 7937 15996 7936 15997 7937 15997 7939 15997 7939 15998 7937 15998 7938 15998 7939 15999 7938 15999 7940 15999 7940 16000 7938 16000 7907 16000 7940 16001 7907 16001 7969 16001 7969 16002 7907 16002 7909 16002 7969 16003 7909 16003 7968 16003 7968 16004 7909 16004 7910 16004 7968 16005 7910 16005 7967 16005 7967 16006 7910 16006 7911 16006 7967 16007 7911 16007 7941 16007 7941 16008 7911 16008 7913 16008 7941 16009 7913 16009 7942 16009 7942 16010 7913 16010 7915 16010 7942 16011 7915 16011 7964 16011 7964 16012 7915 16012 7916 16012 7964 16013 7916 16013 7943 16013 7943 16014 7916 16014 7944 16014 7943 16015 7944 16015 7962 16015 7962 16016 7944 16016 7945 16016 7962 16017 7945 16017 7961 16017 7961 16018 7945 16018 7946 16018 7961 16019 7946 16019 7959 16019 7959 16020 7946 16020 7919 16020 7959 16021 7919 16021 7958 16021 7958 16022 7919 16022 7920 16022 7958 16023 7920 16023 7947 16023 7947 16024 7920 16024 7922 16024 7947 16025 7922 16025 7957 16025 7957 16026 7922 16026 7924 16026 7957 16027 7924 16027 7948 16027 7948 16028 7924 16028 7925 16028 7948 16029 7925 16029 7956 16029 7956 16030 7925 16030 7926 16030 7956 16031 7926 16031 7949 16031 7949 16032 7926 16032 7929 16032 7949 16033 7929 16033 7954 16033 7954 16034 7929 16034 7932 16034 7954 16035 7932 16035 7953 16035 7953 16036 7932 16036 7950 16036 7953 16037 7950 16037 7892 16037 7892 16038 7950 16038 7951 16038 7892 16039 7951 16039 7952 16039 7952 16040 7951 16040 7933 16040 7952 16041 7933 16041 6655 16041 8095 16042 8065 16042 7892 16042 7892 16043 8065 16043 8008 16043 7892 16044 8008 16044 7953 16044 7953 16045 8008 16045 8007 16045 7953 16046 8007 16046 7954 16046 7954 16047 8007 16047 7955 16047 7954 16048 7955 16048 7949 16048 7949 16049 7955 16049 8005 16049 7949 16050 8005 16050 7956 16050 7956 16051 8005 16051 8003 16051 7956 16052 8003 16052 7948 16052 7948 16053 8003 16053 8002 16053 7948 16054 8002 16054 7957 16054 7957 16055 8002 16055 8000 16055 7957 16056 8000 16056 7947 16056 7947 16057 8000 16057 7999 16057 7947 16058 7999 16058 7958 16058 7958 16059 7999 16059 7998 16059 7958 16060 7998 16060 7959 16060 7959 16061 7998 16061 7960 16061 7959 16062 7960 16062 7961 16062 7961 16063 7960 16063 7995 16063 7961 16064 7995 16064 7962 16064 7962 16065 7995 16065 7994 16065 7962 16066 7994 16066 7943 16066 7943 16067 7994 16067 7963 16067 7943 16068 7963 16068 7964 16068 7964 16069 7963 16069 7965 16069 7964 16070 7965 16070 7942 16070 7942 16071 7965 16071 7991 16071 7942 16072 7991 16072 7941 16072 7941 16073 7991 16073 7966 16073 7941 16074 7966 16074 7967 16074 7967 16075 7966 16075 7988 16075 7967 16076 7988 16076 7968 16076 7968 16077 7988 16077 7970 16077 7968 16078 7970 16078 7969 16078 7969 16079 7970 16079 7971 16079 7969 16080 7971 16080 7940 16080 7940 16081 7971 16081 7986 16081 7940 16082 7986 16082 7939 16082 7939 16083 7986 16083 7985 16083 7939 16084 7985 16084 7936 16084 7936 16085 7985 16085 7983 16085 7936 16086 7983 16086 7935 16086 7935 16087 7983 16087 7982 16087 7935 16088 7982 16088 7934 16088 7934 16089 7982 16089 7972 16089 7934 16090 7972 16090 7973 16090 7973 16091 7972 16091 7974 16091 7973 16092 7974 16092 7975 16092 7975 16093 7974 16093 7980 16093 7975 16094 7980 16094 7976 16094 7976 16095 7980 16095 7978 16095 7976 16096 7978 16096 7977 16096 7977 16097 7978 16097 8011 16097 6710 16098 7978 16098 7979 16098 7979 16099 7978 16099 7980 16099 7979 16100 7980 16100 7981 16100 7981 16101 7980 16101 7974 16101 7981 16102 7974 16102 6707 16102 6707 16103 7974 16103 7972 16103 6707 16104 7972 16104 6703 16104 6703 16105 7972 16105 7982 16105 6703 16106 7982 16106 6702 16106 6702 16107 7982 16107 7983 16107 6702 16108 7983 16108 7984 16108 7984 16109 7983 16109 7985 16109 7984 16110 7985 16110 6700 16110 6700 16111 7985 16111 7986 16111 6700 16112 7986 16112 6699 16112 6699 16113 7986 16113 7971 16113 6699 16114 7971 16114 7987 16114 7987 16115 7971 16115 7970 16115 7987 16116 7970 16116 6697 16116 6697 16117 7970 16117 7988 16117 6697 16118 7988 16118 7989 16118 7989 16119 7988 16119 7966 16119 7989 16120 7966 16120 7990 16120 7990 16121 7966 16121 7991 16121 7990 16122 7991 16122 6660 16122 6660 16123 7991 16123 7965 16123 6660 16124 7965 16124 7992 16124 7992 16125 7965 16125 7963 16125 7992 16126 7963 16126 6668 16126 6668 16127 7963 16127 7994 16127 6668 16128 7994 16128 7993 16128 7993 16129 7994 16129 7995 16129 7993 16130 7995 16130 7996 16130 7996 16131 7995 16131 7960 16131 7996 16132 7960 16132 7997 16132 7997 16133 7960 16133 7998 16133 7997 16134 7998 16134 6674 16134 6674 16135 7998 16135 7999 16135 6674 16136 7999 16136 6673 16136 6673 16137 7999 16137 8000 16137 6673 16138 8000 16138 6672 16138 6672 16139 8000 16139 8002 16139 6672 16140 8002 16140 8001 16140 8001 16141 8002 16141 8003 16141 8001 16142 8003 16142 8004 16142 8004 16143 8003 16143 8005 16143 8004 16144 8005 16144 6667 16144 6667 16145 8005 16145 7955 16145 6667 16146 7955 16146 8006 16146 8006 16147 7955 16147 8007 16147 8006 16148 8007 16148 6665 16148 6665 16149 8007 16149 8008 16149 6665 16150 8008 16150 6664 16150 6664 16151 8008 16151 8009 16151 6664 16152 8009 16152 7893 16152 7977 16153 8011 16153 8093 16153 7895 16154 6710 16154 6711 16154 8065 16155 8095 16155 8067 16155 8010 16156 7952 16156 8120 16156 8120 16157 7952 16157 6655 16157 7893 16158 8009 16158 8066 16158 7895 16159 6711 16159 8011 16159 7977 16160 8093 16160 8094 16160 7894 16161 8012 16161 8092 16161 8100 16162 6595 16162 8013 16162 8013 16163 6595 16163 6597 16163 8013 16164 6597 16164 8102 16164 8102 16165 6597 16165 8014 16165 8102 16166 8014 16166 8015 16166 8015 16167 8014 16167 8017 16167 8015 16168 8017 16168 8016 16168 8016 16169 8017 16169 8018 16169 8016 16170 8018 16170 8019 16170 8019 16171 8018 16171 6601 16171 8019 16172 6601 16172 8106 16172 8106 16173 6601 16173 6602 16173 8106 16174 6602 16174 8020 16174 8020 16175 6602 16175 6603 16175 8020 16176 6603 16176 8021 16176 8021 16177 6603 16177 6605 16177 8021 16178 6605 16178 8023 16178 8023 16179 6605 16179 8022 16179 8023 16180 8022 16180 8108 16180 8108 16181 8022 16181 6606 16181 8108 16182 6606 16182 8024 16182 8024 16183 6606 16183 6607 16183 8024 16184 6607 16184 8111 16184 8111 16185 6607 16185 8025 16185 8111 16186 8025 16186 8026 16186 8026 16187 8025 16187 8027 16187 8026 16188 8027 16188 8028 16188 8028 16189 8027 16189 6608 16189 8028 16190 6608 16190 8029 16190 8029 16191 6608 16191 6609 16191 8029 16192 6609 16192 8114 16192 8114 16193 6609 16193 6610 16193 8114 16194 6610 16194 8030 16194 8030 16195 6610 16195 8031 16195 8030 16196 8031 16196 8032 16196 8032 16197 8031 16197 6614 16197 8032 16198 6614 16198 8033 16198 8033 16199 6614 16199 6615 16199 8033 16200 6615 16200 8034 16200 8034 16201 6615 16201 6617 16201 8034 16202 6617 16202 8035 16202 8035 16203 6617 16203 6618 16203 8035 16204 6618 16204 8036 16204 8036 16205 6618 16205 6619 16205 8036 16206 6619 16206 8118 16206 8011 16207 6711 16207 8093 16207 8093 16208 6711 16208 6714 16208 8093 16209 6714 16209 8037 16209 8037 16210 6714 16210 6696 16210 8037 16211 6696 16211 8038 16211 8038 16212 6696 16212 8039 16212 8038 16213 8039 16213 8090 16213 8090 16214 8039 16214 6695 16214 8090 16215 6695 16215 8088 16215 8088 16216 6695 16216 6694 16216 8088 16217 6694 16217 8086 16217 8086 16218 6694 16218 6692 16218 8086 16219 6692 16219 8085 16219 8085 16220 6692 16220 6691 16220 8085 16221 6691 16221 8040 16221 8040 16222 6691 16222 8041 16222 8040 16223 8041 16223 8082 16223 8082 16224 8041 16224 8042 16224 8082 16225 8042 16225 8081 16225 8081 16226 8042 16226 8043 16226 8081 16227 8043 16227 8044 16227 8044 16228 8043 16228 6687 16228 8044 16229 6687 16229 8045 16229 8045 16230 6687 16230 8046 16230 8045 16231 8046 16231 8079 16231 8079 16232 8046 16232 8047 16232 8079 16233 8047 16233 8078 16233 8078 16234 8047 16234 6684 16234 8078 16235 6684 16235 8076 16235 8076 16236 6684 16236 8048 16236 8076 16237 8048 16237 8074 16237 8074 16238 8048 16238 6682 16238 8074 16239 6682 16239 8049 16239 8049 16240 6682 16240 8051 16240 8049 16241 8051 16241 8050 16241 8050 16242 8051 16242 6681 16242 8050 16243 6681 16243 8052 16243 8052 16244 6681 16244 8053 16244 8052 16245 8053 16245 8073 16245 8073 16246 8053 16246 6679 16246 8073 16247 6679 16247 8054 16247 8054 16248 6679 16248 8055 16248 8054 16249 8055 16249 8056 16249 8056 16250 8055 16250 8057 16250 8056 16251 8057 16251 8070 16251 8070 16252 8057 16252 8058 16252 8070 16253 8058 16253 8059 16253 8059 16254 8058 16254 8060 16254 8059 16255 8060 16255 8069 16255 8069 16256 8060 16256 8061 16256 8069 16257 8061 16257 8062 16257 8062 16258 8061 16258 8063 16258 8062 16259 8063 16259 8066 16259 8066 16260 8063 16260 8064 16260 8066 16261 8064 16261 7893 16261 8009 16262 8065 16262 8066 16262 8066 16263 8065 16263 8067 16263 8066 16264 8067 16264 8062 16264 8062 16265 8067 16265 8068 16265 8062 16266 8068 16266 8069 16266 8069 16267 8068 16267 8096 16267 8069 16268 8096 16268 8059 16268 8059 16269 8096 16269 8098 16269 8059 16270 8098 16270 8070 16270 8070 16271 8098 16271 8071 16271 8070 16272 8071 16272 8056 16272 8056 16273 8071 16273 8101 16273 8056 16274 8101 16274 8054 16274 8054 16275 8101 16275 8072 16275 8054 16276 8072 16276 8073 16276 8073 16277 8072 16277 8103 16277 8073 16278 8103 16278 8052 16278 8052 16279 8103 16279 8104 16279 8052 16280 8104 16280 8050 16280 8050 16281 8104 16281 8105 16281 8050 16282 8105 16282 8049 16282 8049 16283 8105 16283 8075 16283 8049 16284 8075 16284 8074 16284 8074 16285 8075 16285 8077 16285 8074 16286 8077 16286 8076 16286 8076 16287 8077 16287 8107 16287 8076 16288 8107 16288 8078 16288 8078 16289 8107 16289 8109 16289 8078 16290 8109 16290 8079 16290 8079 16291 8109 16291 8080 16291 8079 16292 8080 16292 8045 16292 8045 16293 8080 16293 8110 16293 8045 16294 8110 16294 8044 16294 8044 16295 8110 16295 8112 16295 8044 16296 8112 16296 8081 16296 8081 16297 8112 16297 8113 16297 8081 16298 8113 16298 8082 16298 8082 16299 8113 16299 8083 16299 8082 16300 8083 16300 8040 16300 8040 16301 8083 16301 8084 16301 8040 16302 8084 16302 8085 16302 8085 16303 8084 16303 8115 16303 8085 16304 8115 16304 8086 16304 8086 16305 8115 16305 8087 16305 8086 16306 8087 16306 8088 16306 8088 16307 8087 16307 8089 16307 8088 16308 8089 16308 8090 16308 8090 16309 8089 16309 8116 16309 8090 16310 8116 16310 8038 16310 8038 16311 8116 16311 8117 16311 8038 16312 8117 16312 8037 16312 8037 16313 8117 16313 8091 16313 8037 16314 8091 16314 8093 16314 8093 16315 8091 16315 8092 16315 8093 16316 8092 16316 8094 16316 8094 16317 8092 16317 8012 16317 8095 16318 8010 16318 8067 16318 8067 16319 8010 16319 8120 16319 8067 16320 8120 16320 8068 16320 8068 16321 8120 16321 8097 16321 8068 16322 8097 16322 8096 16322 8096 16323 8097 16323 8099 16323 8096 16324 8099 16324 8098 16324 8098 16325 8099 16325 8100 16325 8098 16326 8100 16326 8071 16326 8071 16327 8100 16327 8013 16327 8071 16328 8013 16328 8101 16328 8101 16329 8013 16329 8102 16329 8101 16330 8102 16330 8072 16330 8072 16331 8102 16331 8015 16331 8072 16332 8015 16332 8103 16332 8103 16333 8015 16333 8016 16333 8103 16334 8016 16334 8104 16334 8104 16335 8016 16335 8019 16335 8104 16336 8019 16336 8105 16336 8105 16337 8019 16337 8106 16337 8105 16338 8106 16338 8075 16338 8075 16339 8106 16339 8020 16339 8075 16340 8020 16340 8077 16340 8077 16341 8020 16341 8021 16341 8077 16342 8021 16342 8107 16342 8107 16343 8021 16343 8023 16343 8107 16344 8023 16344 8109 16344 8109 16345 8023 16345 8108 16345 8109 16346 8108 16346 8080 16346 8080 16347 8108 16347 8024 16347 8080 16348 8024 16348 8110 16348 8110 16349 8024 16349 8111 16349 8110 16350 8111 16350 8112 16350 8112 16351 8111 16351 8026 16351 8112 16352 8026 16352 8113 16352 8113 16353 8026 16353 8028 16353 8113 16354 8028 16354 8083 16354 8083 16355 8028 16355 8029 16355 8083 16356 8029 16356 8084 16356 8084 16357 8029 16357 8114 16357 8084 16358 8114 16358 8115 16358 8115 16359 8114 16359 8030 16359 8115 16360 8030 16360 8087 16360 8087 16361 8030 16361 8032 16361 8087 16362 8032 16362 8089 16362 8089 16363 8032 16363 8033 16363 8089 16364 8033 16364 8116 16364 8116 16365 8033 16365 8034 16365 8116 16366 8034 16366 8117 16366 8117 16367 8034 16367 8035 16367 8117 16368 8035 16368 8091 16368 8091 16369 8035 16369 8036 16369 8091 16370 8036 16370 8092 16370 8092 16371 8036 16371 8118 16371 8092 16372 8118 16372 7894 16372 7894 16373 8118 16373 6619 16373 7894 16374 6619 16374 6623 16374 6655 16375 8119 16375 8120 16375 8120 16376 8119 16376 6590 16376 8120 16377 6590 16377 8097 16377 8097 16378 6590 16378 6591 16378 8097 16379 6591 16379 8099 16379 8099 16380 6591 16380 6593 16380 8099 16381 6593 16381 8100 16381 8100 16382 6593 16382 8121 16382 8100 16383 8121 16383 6595 16383 8398 16384 8122 16384 8125 16384 8122 16385 8123 16385 8125 16385 8125 16386 8123 16386 8124 16386 8125 16387 8124 16387 8396 16387 8126 16388 6741 16388 8131 16388 8131 16389 6741 16389 8128 16389 8131 16390 8128 16390 8127 16390 8127 16391 8128 16391 4528 16391 8127 16392 4528 16392 8129 16392 8398 16393 8125 16393 8131 16393 8131 16394 8125 16394 8130 16394 8131 16395 8130 16395 8126 16395 8271 16396 8133 16396 8132 16396 8132 16397 8133 16397 6201 16397 8273 16398 8134 16398 6218 16398 8134 16399 8273 16399 6214 16399 6214 16400 8273 16400 8277 16400 6214 16401 8277 16401 8135 16401 8271 16402 8270 16402 8133 16402 8133 16403 8270 16403 8274 16403 8133 16404 8274 16404 6215 16404 6215 16405 8274 16405 8273 16405 6215 16406 8273 16406 8136 16406 8136 16407 8273 16407 6218 16407 4557 16408 15506 16408 8137 16408 8137 16409 15506 16409 8138 16409 8138 16410 15496 16410 8137 16410 8137 16411 15496 16411 15495 16411 8137 16412 15495 16412 4860 16412 8347 16413 8346 16413 15623 16413 8347 16414 15623 16414 8139 16414 8139 16415 15623 16415 15638 16415 8139 16416 15638 16416 8144 16416 8145 16417 8140 16417 8141 16417 8141 16418 8140 16418 8148 16418 8141 16419 8148 16419 8324 16419 8324 16420 8148 16420 8320 16420 6122 16421 8142 16421 8348 16421 8348 16422 8142 16422 15623 16422 8348 16423 15623 16423 8346 16423 6260 16424 6736 16424 15638 16424 15638 16425 6736 16425 8143 16425 15638 16426 8143 16426 8144 16426 6202 16427 15489 16427 8331 16427 8331 16428 15489 16428 8140 16428 8331 16429 8140 16429 8145 16429 8148 16430 8146 16430 8147 16430 8147 16431 8149 16431 8148 16431 8148 16432 8149 16432 8150 16432 8148 16433 8150 16433 8320 16433 8151 16434 8178 16434 8166 16434 8166 16435 8178 16435 8153 16435 8166 16436 8153 16436 8152 16436 8152 16437 8153 16437 17065 16437 17062 16438 8155 16438 8154 16438 8154 16439 8155 16439 8437 16439 8154 16440 8437 16440 8156 16440 8157 16441 8429 16441 8158 16441 8158 16442 8429 16442 8160 16442 8158 16443 8160 16443 8159 16443 8159 16444 8160 16444 8161 16444 8159 16445 8161 16445 8162 16445 8162 16446 8161 16446 8430 16446 8162 16447 8430 16447 17062 16447 17062 16448 8430 16448 8163 16448 17062 16449 8163 16449 8155 16449 17074 16450 7647 16450 17064 16450 17064 16451 7647 16451 7644 16451 17064 16452 7644 16452 17070 16452 17066 16453 17068 16453 8169 16453 8164 16454 8151 16454 8165 16454 8165 16455 8151 16455 8166 16455 8165 16456 8166 16456 8167 16456 8167 16457 8166 16457 8152 16457 8167 16458 8152 16458 8170 16458 8174 16459 8164 16459 8168 16459 8168 16460 8164 16460 8165 16460 8168 16461 8165 16461 8169 16461 8169 16462 8165 16462 8167 16462 8169 16463 8167 16463 17066 16463 17066 16464 8167 16464 8170 16464 7629 16465 8174 16465 8171 16465 8171 16466 8174 16466 8168 16466 8171 16467 8168 16467 7644 16467 7644 16468 8168 16468 8169 16468 7644 16469 8169 16469 17070 16469 17070 16470 8169 16470 17068 16470 8172 16471 8151 16471 8164 16471 8172 16472 8164 16472 8173 16472 8173 16473 8164 16473 8174 16473 8173 16474 8174 16474 8580 16474 7629 16475 7630 16475 8174 16475 8174 16476 7630 16476 8175 16476 8174 16477 8175 16477 8580 16477 8176 16478 8177 16478 17076 16478 17076 16479 8177 16479 17077 16479 8153 16480 8178 16480 8179 16480 17065 16481 8153 16481 8183 16481 8184 16482 8182 16482 8183 16482 8183 16483 8182 16483 8180 16483 8183 16484 8180 16484 17065 16484 8177 16485 8176 16485 17073 16485 8177 16486 17073 16486 8181 16486 8181 16487 17073 16487 17072 16487 8181 16488 17072 16488 8186 16488 8186 16489 17072 16489 17071 16489 8186 16490 17071 16490 8184 16490 8184 16491 17071 16491 17069 16491 8184 16492 17069 16492 8182 16492 8153 16493 8179 16493 8183 16493 8183 16494 8179 16494 8185 16494 8183 16495 8185 16495 8184 16495 8184 16496 8185 16496 8189 16496 8184 16497 8189 16497 8186 16497 8186 16498 8189 16498 8187 16498 8186 16499 8187 16499 8181 16499 7653 16500 8187 16500 8189 16500 7653 16501 8189 16501 8188 16501 8188 16502 8189 16502 8185 16502 8188 16503 8185 16503 8605 16503 8605 16504 8185 16504 8179 16504 8605 16505 8179 16505 8606 16505 8178 16506 8190 16506 8179 16506 8179 16507 8190 16507 8607 16507 8179 16508 8607 16508 8606 16508 8191 16509 8193 16509 8192 16509 8192 16510 8193 16510 8194 16510 8192 16511 8194 16511 8212 16511 8212 16512 8194 16512 8195 16512 8212 16513 8195 16513 8210 16513 8210 16514 8195 16514 8196 16514 8210 16515 8196 16515 8209 16515 8209 16516 8196 16516 9003 16516 8209 16517 9003 16517 8197 16517 8197 16518 9003 16518 8199 16518 8197 16519 8199 16519 8198 16519 8198 16520 8199 16520 9007 16520 8198 16521 9007 16521 8207 16521 8207 16522 9007 16522 9008 16522 8207 16523 9008 16523 8200 16523 8200 16524 9008 16524 8999 16524 8200 16525 8999 16525 8206 16525 8206 16526 8999 16526 8201 16526 8206 16527 8201 16527 8205 16527 8205 16528 8201 16528 8998 16528 8205 16529 8998 16529 8203 16529 8203 16530 8998 16530 8202 16530 8203 16531 8202 16531 8191 16531 8191 16532 8202 16532 8193 16532 8191 16533 8220 16533 8203 16533 8203 16534 8220 16534 8204 16534 8203 16535 8204 16535 8205 16535 8205 16536 8204 16536 8221 16536 8205 16537 8221 16537 8206 16537 8206 16538 8221 16538 8222 16538 8206 16539 8222 16539 8200 16539 8200 16540 8222 16540 8223 16540 8200 16541 8223 16541 8207 16541 8207 16542 8223 16542 8225 16542 8207 16543 8225 16543 8198 16543 8198 16544 8225 16544 8214 16544 8198 16545 8214 16545 8197 16545 8197 16546 8214 16546 8208 16546 8197 16547 8208 16547 8209 16547 8209 16548 8208 16548 8217 16548 8209 16549 8217 16549 8210 16549 8210 16550 8217 16550 8211 16550 8210 16551 8211 16551 8212 16551 8212 16552 8211 16552 8218 16552 8212 16553 8218 16553 8192 16553 8192 16554 8218 16554 8213 16554 8192 16555 8213 16555 8191 16555 8191 16556 8213 16556 8220 16556 8214 16557 8215 16557 8208 16557 8208 16558 8215 16558 8216 16558 8208 16559 8216 16559 8217 16559 8217 16560 8216 16560 8897 16560 8217 16561 8897 16561 8211 16561 8211 16562 8897 16562 8898 16562 8211 16563 8898 16563 8218 16563 8218 16564 8898 16564 8899 16564 8218 16565 8899 16565 8213 16565 8213 16566 8899 16566 8900 16566 8213 16567 8900 16567 8220 16567 8220 16568 8900 16568 8219 16568 8220 16569 8219 16569 8204 16569 8204 16570 8219 16570 8903 16570 8204 16571 8903 16571 8221 16571 8221 16572 8903 16572 8904 16572 8221 16573 8904 16573 8222 16573 8222 16574 8904 16574 8905 16574 8222 16575 8905 16575 8223 16575 8223 16576 8905 16576 8224 16576 8223 16577 8224 16577 8225 16577 8225 16578 8224 16578 8906 16578 8225 16579 8906 16579 8214 16579 8214 16580 8906 16580 8215 16580 8631 16581 8229 16581 8226 16581 8227 16582 8231 16582 8244 16582 8629 16583 8236 16583 8229 16583 8229 16584 8236 16584 8228 16584 8229 16585 8228 16585 8226 16585 8628 16586 8627 16586 16940 16586 8227 16587 8230 16587 8231 16587 8231 16588 8230 16588 8232 16588 8231 16589 8232 16589 8627 16589 8627 16590 8232 16590 16938 16590 8627 16591 16938 16591 16940 16591 8233 16592 8238 16592 8620 16592 8226 16593 16947 16593 8631 16593 8631 16594 16947 16594 8234 16594 8631 16595 8234 16595 8620 16595 8620 16596 8234 16596 16927 16596 8620 16597 16927 16597 8233 16597 16940 16598 16941 16598 8628 16598 8628 16599 16941 16599 8235 16599 8628 16600 8235 16600 8629 16600 8629 16601 8235 16601 16943 16601 8629 16602 16943 16602 8236 16602 8233 16603 8237 16603 8238 16603 8238 16604 8237 16604 16930 16604 8238 16605 16930 16605 8239 16605 16934 16606 8625 16606 8623 16606 16930 16607 8240 16607 8239 16607 8239 16608 8240 16608 8241 16608 8239 16609 8241 16609 8623 16609 8623 16610 8241 16610 16933 16610 8623 16611 16933 16611 16934 16611 16934 16612 8242 16612 8625 16612 8625 16613 8242 16613 8243 16613 8625 16614 8243 16614 8244 16614 8244 16615 8243 16615 16936 16615 8244 16616 16936 16616 8227 16616 8246 16617 8263 16617 8245 16617 8643 16618 16986 16618 8245 16618 8245 16619 16986 16619 16987 16619 8245 16620 16987 16620 8246 16620 8641 16621 8250 16621 8643 16621 8643 16622 8250 16622 8247 16622 8643 16623 8247 16623 16986 16623 8251 16624 8637 16624 8255 16624 8638 16625 8248 16625 8641 16625 8641 16626 8248 16626 8249 16626 8641 16627 8249 16627 8250 16627 8251 16628 8252 16628 8637 16628 8637 16629 8252 16629 8253 16629 8637 16630 8253 16630 8638 16630 8638 16631 8253 16631 8254 16631 8638 16632 8254 16632 8248 16632 8259 16633 16977 16633 8255 16633 8255 16634 16977 16634 8256 16634 8255 16635 8256 16635 8251 16635 8257 16636 8258 16636 8259 16636 8259 16637 8258 16637 16975 16637 8259 16638 16975 16638 16977 16638 8635 16639 8260 16639 8257 16639 8257 16640 8260 16640 8261 16640 8257 16641 8261 16641 8258 16641 8246 16642 8262 16642 8263 16642 8263 16643 8262 16643 8266 16643 8263 16644 8266 16644 8633 16644 8634 16645 8264 16645 8635 16645 8635 16646 8264 16646 8265 16646 8635 16647 8265 16647 8260 16647 8266 16648 8267 16648 8633 16648 8633 16649 8267 16649 8268 16649 8633 16650 8268 16650 8634 16650 8634 16651 8268 16651 8269 16651 8634 16652 8269 16652 8264 16652 8274 16653 8270 16653 8275 16653 8270 16654 8271 16654 8275 16654 8275 16655 8271 16655 8132 16655 8275 16656 8132 16656 6201 16656 8272 16657 8280 16657 8276 16657 8276 16658 8280 16658 8273 16658 8276 16659 8273 16659 8274 16659 8274 16660 8275 16660 8276 16660 8276 16661 8275 16661 8279 16661 8276 16662 8279 16662 8272 16662 8277 16663 8273 16663 8280 16663 4532 16664 8282 16664 8278 16664 8278 16665 8282 16665 4856 16665 8279 16666 6171 16666 8272 16666 8272 16667 6171 16667 8281 16667 8272 16668 8281 16668 8280 16668 8280 16669 8281 16669 8283 16669 8280 16670 8283 16670 8277 16670 8277 16671 8283 16671 8282 16671 8277 16672 8282 16672 8135 16672 8135 16673 8282 16673 4532 16673 8283 16674 8281 16674 8287 16674 8287 16675 8281 16675 6171 16675 8293 16676 8282 16676 8283 16676 8284 16677 4856 16677 8282 16677 6171 16678 6169 16678 8287 16678 8287 16679 6169 16679 8285 16679 8287 16680 8285 16680 8286 16680 8286 16681 8285 16681 6166 16681 8286 16682 6166 16682 8289 16682 8289 16683 6166 16683 6164 16683 8289 16684 6164 16684 8291 16684 8291 16685 6164 16685 8299 16685 8291 16686 8299 16686 8292 16686 8283 16687 8287 16687 8293 16687 8293 16688 8287 16688 8286 16688 8293 16689 8286 16689 8288 16689 8288 16690 8286 16690 8289 16690 8288 16691 8289 16691 8290 16691 8290 16692 8289 16692 8291 16692 8290 16693 8291 16693 8295 16693 8295 16694 8291 16694 8292 16694 8295 16695 8292 16695 8297 16695 8282 16696 8293 16696 8284 16696 8284 16697 8293 16697 8288 16697 8284 16698 8288 16698 8294 16698 8294 16699 8288 16699 8290 16699 8294 16700 8290 16700 8296 16700 8296 16701 8290 16701 8295 16701 8296 16702 8295 16702 4854 16702 4854 16703 8295 16703 8297 16703 4854 16704 8297 16704 4852 16704 8302 16705 8303 16705 4852 16705 4852 16706 8297 16706 8302 16706 8302 16707 8297 16707 8292 16707 8302 16708 8292 16708 8298 16708 8298 16709 8292 16709 8299 16709 8298 16710 8299 16710 8300 16710 8301 16711 8311 16711 8307 16711 8304 16712 8298 16712 8300 16712 8312 16713 8302 16713 8298 16713 4850 16714 8303 16714 8302 16714 8300 16715 6179 16715 8304 16715 8304 16716 6179 16716 8305 16716 8304 16717 8305 16717 8306 16717 8305 16718 6178 16718 8306 16718 8306 16719 6178 16719 8308 16719 8306 16720 8308 16720 8307 16720 8307 16721 8308 16721 8309 16721 8307 16722 8309 16722 8301 16722 8298 16723 8304 16723 8312 16723 8312 16724 8304 16724 8306 16724 8312 16725 8306 16725 8310 16725 8310 16726 8306 16726 8307 16726 8310 16727 8307 16727 8314 16727 8314 16728 8307 16728 8311 16728 8314 16729 8311 16729 8316 16729 8302 16730 8312 16730 4850 16730 4850 16731 8312 16731 8310 16731 4850 16732 8310 16732 8313 16732 8313 16733 8310 16733 8314 16733 8313 16734 8314 16734 4848 16734 4848 16735 8314 16735 8316 16735 4848 16736 8316 16736 4846 16736 8301 16737 6193 16737 8315 16737 8301 16738 8315 16738 8311 16738 8311 16739 8315 16739 8317 16739 8311 16740 8317 16740 8316 16740 8316 16741 8317 16741 8149 16741 8316 16742 8149 16742 4846 16742 8150 16743 8149 16743 8318 16743 8318 16744 8149 16744 8317 16744 8318 16745 8317 16745 8323 16745 8323 16746 8317 16746 8315 16746 8323 16747 8315 16747 8319 16747 8319 16748 8315 16748 6193 16748 8320 16749 8150 16749 8321 16749 8321 16750 8150 16750 8318 16750 8321 16751 8318 16751 8322 16751 8322 16752 8318 16752 8323 16752 8322 16753 8323 16753 6190 16753 6190 16754 8323 16754 8319 16754 8324 16755 8320 16755 8321 16755 8324 16756 8321 16756 8326 16756 8326 16757 8321 16757 8322 16757 8326 16758 8322 16758 8329 16758 8329 16759 8322 16759 6190 16759 8329 16760 6190 16760 8330 16760 8325 16761 6212 16761 8328 16761 8325 16762 8328 16762 8330 16762 8141 16763 8324 16763 8327 16763 8327 16764 8324 16764 8326 16764 8327 16765 8326 16765 8328 16765 8328 16766 8326 16766 8329 16766 8328 16767 8329 16767 8330 16767 8145 16768 8141 16768 8333 16768 8333 16769 8141 16769 8327 16769 8333 16770 8327 16770 8332 16770 8332 16771 8327 16771 8328 16771 8332 16772 8328 16772 6211 16772 6211 16773 8328 16773 6212 16773 6210 16774 6202 16774 8331 16774 6211 16775 6210 16775 8332 16775 8332 16776 6210 16776 8333 16776 8333 16777 6210 16777 8331 16777 8333 16778 8331 16778 8145 16778 8334 16779 8143 16779 6736 16779 8144 16780 8143 16780 8341 16780 8341 16781 8143 16781 8334 16781 8341 16782 8334 16782 8335 16782 8335 16783 8334 16783 8336 16783 8337 16784 8343 16784 8344 16784 8339 16785 8337 16785 8340 16785 8340 16786 8337 16786 8344 16786 8340 16787 8344 16787 8342 16787 8342 16788 8344 16788 8338 16788 8342 16789 8338 16789 8139 16789 8139 16790 8338 16790 8347 16790 8336 16791 8339 16791 8335 16791 8335 16792 8339 16792 8340 16792 8335 16793 8340 16793 8341 16793 8341 16794 8340 16794 8342 16794 8341 16795 8342 16795 8144 16795 8144 16796 8342 16796 8139 16796 8343 16797 8351 16797 8345 16797 8343 16798 8345 16798 8344 16798 8344 16799 8345 16799 8349 16799 8344 16800 8349 16800 8338 16800 8338 16801 8349 16801 8346 16801 8338 16802 8346 16802 8347 16802 8348 16803 8346 16803 8350 16803 8350 16804 8346 16804 8349 16804 8350 16805 8349 16805 8354 16805 8354 16806 8349 16806 8345 16806 8354 16807 8345 16807 8355 16807 8355 16808 8345 16808 8351 16808 6122 16809 8348 16809 8352 16809 8352 16810 8348 16810 8350 16810 8352 16811 8350 16811 8353 16811 8353 16812 8350 16812 8354 16812 8353 16813 8354 16813 6251 16813 6251 16814 8354 16814 8355 16814 8356 16815 6122 16815 8352 16815 8356 16816 8352 16816 8362 16816 8362 16817 8352 16817 8353 16817 8362 16818 8353 16818 8357 16818 8357 16819 8353 16819 6251 16819 8357 16820 6251 16820 8358 16820 8368 16821 8372 16821 8359 16821 8359 16822 8372 16822 8360 16822 6248 16823 6249 16823 8373 16823 8357 16824 8358 16824 8361 16824 8356 16825 8362 16825 8363 16825 8357 16826 8361 16826 8364 16826 8364 16827 8361 16827 8366 16827 8364 16828 8366 16828 8365 16828 8365 16829 8366 16829 6248 16829 8365 16830 6248 16830 8367 16830 8367 16831 6248 16831 8373 16831 8367 16832 8373 16832 8368 16832 8368 16833 8359 16833 8367 16833 8367 16834 8359 16834 8370 16834 8367 16835 8370 16835 8365 16835 8365 16836 8370 16836 8363 16836 8365 16837 8363 16837 8364 16837 8364 16838 8363 16838 8362 16838 8364 16839 8362 16839 8357 16839 8356 16840 8363 16840 8369 16840 8369 16841 8363 16841 8370 16841 8369 16842 8370 16842 6142 16842 6142 16843 8370 16843 8359 16843 6142 16844 8359 16844 6143 16844 6143 16845 8359 16845 8360 16845 6143 16846 8360 16846 8371 16846 8391 16847 8389 16847 8371 16847 8371 16848 8360 16848 8391 16848 8391 16849 8360 16849 8372 16849 8391 16850 8372 16850 8375 16850 6249 16851 8374 16851 8373 16851 8373 16852 8374 16852 8375 16852 8373 16853 8375 16853 8368 16853 8368 16854 8375 16854 8372 16854 8383 16855 8392 16855 8386 16855 8386 16856 8392 16856 8394 16856 8376 16857 8377 16857 8378 16857 8375 16858 8374 16858 8379 16858 8375 16859 8379 16859 8380 16859 8380 16860 8379 16860 6237 16860 8380 16861 6237 16861 8381 16861 8381 16862 6237 16862 6238 16862 8381 16863 6238 16863 8382 16863 8382 16864 6238 16864 8376 16864 8382 16865 8376 16865 8384 16865 8384 16866 8376 16866 8378 16866 8384 16867 8378 16867 8383 16867 8383 16868 8386 16868 8384 16868 8384 16869 8386 16869 8387 16869 8384 16870 8387 16870 8382 16870 8382 16871 8387 16871 8385 16871 8382 16872 8385 16872 8381 16872 8381 16873 8385 16873 8390 16873 8381 16874 8390 16874 8380 16874 8380 16875 8390 16875 8391 16875 8380 16876 8391 16876 8375 16876 8394 16877 6137 16877 8386 16877 8386 16878 6137 16878 6138 16878 8386 16879 6138 16879 8387 16879 8387 16880 6138 16880 6140 16880 8387 16881 6140 16881 8385 16881 8385 16882 6140 16882 8388 16882 8385 16883 8388 16883 8390 16883 8390 16884 8388 16884 8389 16884 8390 16885 8389 16885 8391 16885 8383 16886 8127 16886 8392 16886 8392 16887 8127 16887 8129 16887 8392 16888 8129 16888 8394 16888 8394 16889 8129 16889 8393 16889 8394 16890 8393 16890 4527 16890 8131 16891 8127 16891 8395 16891 8395 16892 8127 16892 8383 16892 8395 16893 8383 16893 8399 16893 8399 16894 8383 16894 8378 16894 8399 16895 8378 16895 6232 16895 6232 16896 8378 16896 8377 16896 8397 16897 8396 16897 8124 16897 8124 16898 8123 16898 8397 16898 8397 16899 8123 16899 8122 16899 8397 16900 8122 16900 8400 16900 8400 16901 8122 16901 8398 16901 8400 16902 8398 16902 8131 16902 6232 16903 8397 16903 8399 16903 8399 16904 8397 16904 8400 16904 8399 16905 8400 16905 8395 16905 8395 16906 8400 16906 8131 16906 6253 16907 6257 16907 8433 16907 8433 16908 6257 16908 8401 16908 8433 16909 8401 16909 8432 16909 8402 16910 8405 16910 6257 16910 6257 16911 8405 16911 8403 16911 6257 16912 8403 16912 8401 16912 8401 16913 8403 16913 8404 16913 8401 16914 8404 16914 8157 16914 8405 16915 8402 16915 6256 16915 8403 16916 8405 16916 8415 16916 8404 16917 8403 16917 8421 16917 8157 16918 8404 16918 8428 16918 8405 16919 6256 16919 8415 16919 8415 16920 6256 16920 8406 16920 8415 16921 8406 16921 8416 16921 8416 16922 8406 16922 8407 16922 8416 16923 8407 16923 8417 16923 8417 16924 8407 16924 8408 16924 8417 16925 8408 16925 8409 16925 8409 16926 8408 16926 8411 16926 8409 16927 8411 16927 8410 16927 8410 16928 8411 16928 8413 16928 8410 16929 8413 16929 8412 16929 8412 16930 8413 16930 8442 16930 8412 16931 8442 16931 8414 16931 8403 16932 8415 16932 8421 16932 8421 16933 8415 16933 8416 16933 8421 16934 8416 16934 8422 16934 8422 16935 8416 16935 8417 16935 8422 16936 8417 16936 8418 16936 8418 16937 8417 16937 8409 16937 8418 16938 8409 16938 8426 16938 8426 16939 8409 16939 8410 16939 8426 16940 8410 16940 8419 16940 8419 16941 8410 16941 8412 16941 8419 16942 8412 16942 8420 16942 8420 16943 8412 16943 8414 16943 8420 16944 8414 16944 8440 16944 8404 16945 8421 16945 8428 16945 8428 16946 8421 16946 8422 16946 8428 16947 8422 16947 8423 16947 8423 16948 8422 16948 8418 16948 8423 16949 8418 16949 8424 16949 8424 16950 8418 16950 8426 16950 8424 16951 8426 16951 8425 16951 8425 16952 8426 16952 8419 16952 8425 16953 8419 16953 8431 16953 8431 16954 8419 16954 8420 16954 8431 16955 8420 16955 8427 16955 8427 16956 8420 16956 8440 16956 8427 16957 8440 16957 8438 16957 8157 16958 8428 16958 8429 16958 8429 16959 8428 16959 8423 16959 8429 16960 8423 16960 8160 16960 8160 16961 8423 16961 8424 16961 8160 16962 8424 16962 8161 16962 8161 16963 8424 16963 8425 16963 8161 16964 8425 16964 8430 16964 8430 16965 8425 16965 8431 16965 8430 16966 8431 16966 8163 16966 8163 16967 8431 16967 8427 16967 8163 16968 8427 16968 8155 16968 8155 16969 8427 16969 8438 16969 8155 16970 8438 16970 8437 16970 8460 16971 6195 16971 8436 16971 8432 16972 8434 16972 8433 16972 8433 16973 8434 16973 8436 16973 8433 16974 8436 16974 6253 16974 8434 16975 7648 16975 8435 16975 8434 16976 8435 16976 8436 16976 8436 16977 8435 16977 8466 16977 8436 16978 8466 16978 8460 16978 8443 16979 8437 16979 8445 16979 8445 16980 8437 16980 8438 16980 8445 16981 8438 16981 8439 16981 8439 16982 8438 16982 8440 16982 8439 16983 8440 16983 8441 16983 8441 16984 8440 16984 8414 16984 8441 16985 8414 16985 6258 16985 6258 16986 8414 16986 8442 16986 8474 16987 8443 16987 8444 16987 8444 16988 8443 16988 8445 16988 8444 16989 8445 16989 8476 16989 8476 16990 8445 16990 8439 16990 8476 16991 8439 16991 8446 16991 8446 16992 8439 16992 8441 16992 8446 16993 8441 16993 8478 16993 8478 16994 8441 16994 6258 16994 8447 16995 6200 16995 8449 16995 8485 16996 8447 16996 8454 16996 8483 16997 8485 16997 8448 16997 4468 16998 4467 16998 8467 16998 8467 16999 4467 16999 8483 16999 8447 17000 8449 17000 8454 17000 8454 17001 8449 17001 6198 17001 8454 17002 6198 17002 8455 17002 8455 17003 6198 17003 6197 17003 8455 17004 6197 17004 8456 17004 8456 17005 6197 17005 8451 17005 8456 17006 8451 17006 8450 17006 8450 17007 8451 17007 8452 17007 8450 17008 8452 17008 8453 17008 8453 17009 8452 17009 6196 17009 8453 17010 6196 17010 8458 17010 8458 17011 6196 17011 6195 17011 8458 17012 6195 17012 8460 17012 8485 17013 8454 17013 8448 17013 8448 17014 8454 17014 8455 17014 8448 17015 8455 17015 8461 17015 8461 17016 8455 17016 8456 17016 8461 17017 8456 17017 8457 17017 8457 17018 8456 17018 8450 17018 8457 17019 8450 17019 8462 17019 8462 17020 8450 17020 8453 17020 8462 17021 8453 17021 8464 17021 8464 17022 8453 17022 8458 17022 8464 17023 8458 17023 8459 17023 8459 17024 8458 17024 8460 17024 8459 17025 8460 17025 8466 17025 8483 17026 8448 17026 8467 17026 8467 17027 8448 17027 8461 17027 8467 17028 8461 17028 8469 17028 8469 17029 8461 17029 8457 17029 8469 17030 8457 17030 8470 17030 8470 17031 8457 17031 8462 17031 8470 17032 8462 17032 8463 17032 8463 17033 8462 17033 8464 17033 8463 17034 8464 17034 8472 17034 8472 17035 8464 17035 8459 17035 8472 17036 8459 17036 8465 17036 8465 17037 8459 17037 8466 17037 8465 17038 8466 17038 8435 17038 4468 17039 8467 17039 4464 17039 4464 17040 8467 17040 8469 17040 4464 17041 8469 17041 8468 17041 8468 17042 8469 17042 8470 17042 8468 17043 8470 17043 8471 17043 8471 17044 8470 17044 8463 17044 8471 17045 8463 17045 4461 17045 4461 17046 8463 17046 8472 17046 4461 17047 8472 17047 4460 17047 4460 17048 8472 17048 8465 17048 4460 17049 8465 17049 8473 17049 8473 17050 8465 17050 8435 17050 8473 17051 8435 17051 7648 17051 7634 17052 8474 17052 8444 17052 7634 17053 8444 17053 8502 17053 8502 17054 8444 17054 8476 17054 8502 17055 8476 17055 8475 17055 8475 17056 8476 17056 8446 17056 8475 17057 8446 17057 8477 17057 8477 17058 8446 17058 8478 17058 8477 17059 8478 17059 6231 17059 8479 17060 7663 17060 8484 17060 8484 17061 7663 17061 8480 17061 8484 17062 8480 17062 8486 17062 8486 17063 8480 17063 8481 17063 8486 17064 8481 17064 8487 17064 8487 17065 8481 17065 8508 17065 8487 17066 8508 17066 6199 17066 6199 17067 8508 17067 8482 17067 4467 17068 8479 17068 8483 17068 8483 17069 8479 17069 8484 17069 8483 17070 8484 17070 8485 17070 8485 17071 8484 17071 8486 17071 8485 17072 8486 17072 8447 17072 8447 17073 8486 17073 8487 17073 8447 17074 8487 17074 6200 17074 6200 17075 8487 17075 6199 17075 8499 17076 8511 17076 8510 17076 8488 17077 8513 17077 8511 17077 8494 17078 8489 17078 8495 17078 8477 17079 6231 17079 8490 17079 8477 17080 8490 17080 8491 17080 8491 17081 8490 17081 6234 17081 8491 17082 6234 17082 8497 17082 8497 17083 6234 17083 8492 17083 8497 17084 8492 17084 8496 17084 8496 17085 8492 17085 8494 17085 8496 17086 8494 17086 8493 17086 8493 17087 8494 17087 8495 17087 8493 17088 8495 17088 8513 17088 8513 17089 8488 17089 8493 17089 8493 17090 8488 17090 8500 17090 8493 17091 8500 17091 8496 17091 8496 17092 8500 17092 8501 17092 8496 17093 8501 17093 8497 17093 8497 17094 8501 17094 8498 17094 8497 17095 8498 17095 8491 17095 8491 17096 8498 17096 8475 17096 8491 17097 8475 17097 8477 17097 8511 17098 8499 17098 8488 17098 8488 17099 8499 17099 8503 17099 8488 17100 8503 17100 8500 17100 8500 17101 8503 17101 8505 17101 8500 17102 8505 17102 8501 17102 8501 17103 8505 17103 8507 17103 8501 17104 8507 17104 8498 17104 8498 17105 8507 17105 8502 17105 8498 17106 8502 17106 8475 17106 8510 17107 7631 17107 8499 17107 8499 17108 7631 17108 8504 17108 8499 17109 8504 17109 8503 17109 8503 17110 8504 17110 7632 17110 8503 17111 7632 17111 8505 17111 8505 17112 7632 17112 8506 17112 8505 17113 8506 17113 8507 17113 8507 17114 8506 17114 7634 17114 8507 17115 7634 17115 8502 17115 6175 17116 8482 17116 8508 17116 6175 17117 8508 17117 8509 17117 8509 17118 8508 17118 8481 17118 8509 17119 8481 17119 8522 17119 8522 17120 8481 17120 8480 17120 8522 17121 8480 17121 8517 17121 8517 17122 8480 17122 7663 17122 8517 17123 7663 17123 7667 17123 7638 17124 8510 17124 8511 17124 7638 17125 8511 17125 8512 17125 8512 17126 8511 17126 8513 17126 8512 17127 8513 17127 8542 17127 8542 17128 8513 17128 8495 17128 8542 17129 8495 17129 8514 17129 8514 17130 8495 17130 8489 17130 8514 17131 8489 17131 8515 17131 8535 17132 7660 17132 8516 17132 8527 17133 8517 17133 7667 17133 8518 17134 8522 17134 8517 17134 6174 17135 6175 17135 8509 17135 8519 17136 8520 17136 8526 17136 8526 17137 8520 17137 6173 17137 8526 17138 6173 17138 8525 17138 8525 17139 6173 17139 8521 17139 8525 17140 8521 17140 8524 17140 8524 17141 8521 17141 6174 17141 8524 17142 6174 17142 8523 17142 8523 17143 6174 17143 8509 17143 8523 17144 8509 17144 8522 17144 8522 17145 8518 17145 8523 17145 8523 17146 8518 17146 8529 17146 8523 17147 8529 17147 8524 17147 8524 17148 8529 17148 8531 17148 8524 17149 8531 17149 8525 17149 8525 17150 8531 17150 8533 17150 8525 17151 8533 17151 8526 17151 8526 17152 8533 17152 8534 17152 8526 17153 8534 17153 8519 17153 8517 17154 8527 17154 8518 17154 8518 17155 8527 17155 8528 17155 8518 17156 8528 17156 8529 17156 8529 17157 8528 17157 8530 17157 8529 17158 8530 17158 8531 17158 8531 17159 8530 17159 8532 17159 8531 17160 8532 17160 8533 17160 8533 17161 8532 17161 8536 17161 8533 17162 8536 17162 8534 17162 7667 17163 7666 17163 8527 17163 8527 17164 7666 17164 7651 17164 8527 17165 7651 17165 8528 17165 8528 17166 7651 17166 7650 17166 8528 17167 7650 17167 8530 17167 8530 17168 7650 17168 8535 17168 8530 17169 8535 17169 8532 17169 8532 17170 8535 17170 8516 17170 8532 17171 8516 17171 8536 17171 8552 17172 8537 17172 8538 17172 8552 17173 8538 17173 8553 17173 8553 17174 8538 17174 8548 17174 8553 17175 8548 17175 8554 17175 8554 17176 8548 17176 8540 17176 8554 17177 8540 17177 8539 17177 8539 17178 8540 17178 6245 17178 8539 17179 6245 17179 6250 17179 7640 17180 7638 17180 8541 17180 8541 17181 7638 17181 8512 17181 8541 17182 8512 17182 8546 17182 8546 17183 8512 17183 8542 17183 8546 17184 8542 17184 8543 17184 8543 17185 8542 17185 8514 17185 8543 17186 8514 17186 8544 17186 8544 17187 8514 17187 8515 17187 7642 17188 7640 17188 8545 17188 8545 17189 7640 17189 8541 17189 8545 17190 8541 17190 8549 17190 8549 17191 8541 17191 8546 17191 8549 17192 8546 17192 8550 17192 8550 17193 8546 17193 8543 17193 8550 17194 8543 17194 8547 17194 8547 17195 8543 17195 8544 17195 8537 17196 7642 17196 8538 17196 8538 17197 7642 17197 8545 17197 8538 17198 8545 17198 8548 17198 8548 17199 8545 17199 8549 17199 8548 17200 8549 17200 8540 17200 8540 17201 8549 17201 8550 17201 8540 17202 8550 17202 6245 17202 6245 17203 8550 17203 8547 17203 8565 17204 8519 17204 8534 17204 8565 17205 8534 17205 8564 17205 8564 17206 8534 17206 8536 17206 8564 17207 8536 17207 8551 17207 8551 17208 8536 17208 8516 17208 8551 17209 8516 17209 8561 17209 8561 17210 8516 17210 7660 17210 8561 17211 7660 17211 8557 17211 7630 17212 8552 17212 8553 17212 7630 17213 8553 17213 8576 17213 8576 17214 8553 17214 8554 17214 8576 17215 8554 17215 8577 17215 8577 17216 8554 17216 8539 17216 8577 17217 8539 17217 8555 17217 8555 17218 8539 17218 6250 17218 8555 17219 6250 17219 8556 17219 6180 17220 6181 17220 8563 17220 8569 17221 6184 17221 8567 17221 8557 17222 8571 17222 8562 17222 6191 17223 8570 17223 8568 17223 6191 17224 8568 17224 8593 17224 8593 17225 8568 17225 8558 17225 8593 17226 8558 17226 8559 17226 8559 17227 8558 17227 8560 17227 8559 17228 8560 17228 8592 17228 8592 17229 8560 17229 7658 17229 8592 17230 7658 17230 7652 17230 8557 17231 8562 17231 8561 17231 8561 17232 8562 17232 8574 17232 8561 17233 8574 17233 8551 17233 8551 17234 8574 17234 8563 17234 8551 17235 8563 17235 8564 17235 8564 17236 8563 17236 6181 17236 8564 17237 6181 17237 8565 17237 8572 17238 7658 17238 8573 17238 8573 17239 7658 17239 8560 17239 8573 17240 8560 17240 8566 17240 8566 17241 8560 17241 8558 17241 8566 17242 8558 17242 8567 17242 8567 17243 8558 17243 8568 17243 8567 17244 8568 17244 8569 17244 8569 17245 8568 17245 8570 17245 8571 17246 8572 17246 8562 17246 8562 17247 8572 17247 8573 17247 8562 17248 8573 17248 8574 17248 8574 17249 8573 17249 8566 17249 8574 17250 8566 17250 8563 17250 8563 17251 8566 17251 8567 17251 8563 17252 8567 17252 6180 17252 6180 17253 8567 17253 6184 17253 8175 17254 7630 17254 8581 17254 8581 17255 7630 17255 8576 17255 8581 17256 8576 17256 8575 17256 8575 17257 8576 17257 8577 17257 8575 17258 8577 17258 8578 17258 8578 17259 8577 17259 8555 17259 8578 17260 8555 17260 8579 17260 8579 17261 8555 17261 8556 17261 8580 17262 8175 17262 8584 17262 8584 17263 8175 17263 8581 17263 8584 17264 8581 17264 8585 17264 8585 17265 8581 17265 8575 17265 8585 17266 8575 17266 8582 17266 8582 17267 8575 17267 8578 17267 8582 17268 8578 17268 6252 17268 6252 17269 8578 17269 8579 17269 8173 17270 8580 17270 8583 17270 8583 17271 8580 17271 8584 17271 8583 17272 8584 17272 8588 17272 8588 17273 8584 17273 8585 17273 8588 17274 8585 17274 8589 17274 8589 17275 8585 17275 8582 17275 8589 17276 8582 17276 8590 17276 8590 17277 8582 17277 6252 17277 8172 17278 8173 17278 8586 17278 8586 17279 8173 17279 8583 17279 8586 17280 8583 17280 8587 17280 8587 17281 8583 17281 8588 17281 8587 17282 8588 17282 8595 17282 8595 17283 8588 17283 8589 17283 8595 17284 8589 17284 8596 17284 8596 17285 8589 17285 8590 17285 7652 17286 7653 17286 8591 17286 7652 17287 8591 17287 8592 17287 8592 17288 8591 17288 8609 17288 8592 17289 8609 17289 8559 17289 8559 17290 8609 17290 8611 17290 8559 17291 8611 17291 8593 17291 8593 17292 8611 17292 8612 17292 8593 17293 8612 17293 6191 17293 8619 17294 8172 17294 8586 17294 8619 17295 8586 17295 8594 17295 8594 17296 8586 17296 8587 17296 8594 17297 8587 17297 8617 17297 8617 17298 8587 17298 8595 17298 8617 17299 8595 17299 8616 17299 8616 17300 8595 17300 8596 17300 8616 17301 8596 17301 6189 17301 8607 17302 8190 17302 8604 17302 8604 17303 8190 17303 8618 17303 8604 17304 8618 17304 8597 17304 8597 17305 8618 17305 8599 17305 8597 17306 8599 17306 8598 17306 8598 17307 8599 17307 8600 17307 8598 17308 8600 17308 6187 17308 6187 17309 8600 17309 8615 17309 6187 17310 8601 17310 8598 17310 8598 17311 8601 17311 8602 17311 8598 17312 8602 17312 8597 17312 8597 17313 8602 17313 8603 17313 8597 17314 8603 17314 8604 17314 8604 17315 8603 17315 8614 17315 8604 17316 8614 17316 8607 17316 8188 17317 8605 17317 8614 17317 8614 17318 8605 17318 8606 17318 8614 17319 8606 17319 8607 17319 8591 17320 8608 17320 8609 17320 8609 17321 8608 17321 8610 17321 8609 17322 8610 17322 8611 17322 8611 17323 8610 17323 8613 17323 8611 17324 8613 17324 8612 17324 8612 17325 8613 17325 6186 17325 8601 17326 6186 17326 8602 17326 8602 17327 6186 17327 8613 17327 8602 17328 8613 17328 8603 17328 8603 17329 8613 17329 8610 17329 8603 17330 8610 17330 8614 17330 8614 17331 8610 17331 8608 17331 8614 17332 8608 17332 8188 17332 8188 17333 8608 17333 8591 17333 8188 17334 8591 17334 7653 17334 6189 17335 8615 17335 8600 17335 6189 17336 8600 17336 8616 17336 8616 17337 8600 17337 8599 17337 8616 17338 8599 17338 8617 17338 8617 17339 8599 17339 8618 17339 8617 17340 8618 17340 8594 17340 8594 17341 8618 17341 8190 17341 8594 17342 8190 17342 8619 17342 8632 17343 8620 17343 6156 17343 6156 17344 8620 17344 8238 17344 6156 17345 8238 17345 8621 17345 8621 17346 8238 17346 8239 17346 8621 17347 8239 17347 8622 17347 8622 17348 8239 17348 8623 17348 8622 17349 8623 17349 8624 17349 8624 17350 8623 17350 8625 17350 8624 17351 8625 17351 8626 17351 8626 17352 8625 17352 8244 17352 8626 17353 8244 17353 6157 17353 6157 17354 8244 17354 8231 17354 6157 17355 8231 17355 6158 17355 6158 17356 8231 17356 8627 17356 6158 17357 8627 17357 6161 17357 6161 17358 8627 17358 8628 17358 6161 17359 8628 17359 6162 17359 6162 17360 8628 17360 8629 17360 6162 17361 8629 17361 8630 17361 8630 17362 8629 17362 8229 17362 8630 17363 8229 17363 6163 17363 6163 17364 8229 17364 8631 17364 6163 17365 8631 17365 8632 17365 8632 17366 8631 17366 8620 17366 8646 17367 8633 17367 6149 17367 6149 17368 8633 17368 8634 17368 6149 17369 8634 17369 6148 17369 6148 17370 8634 17370 8635 17370 6148 17371 8635 17371 6147 17371 6147 17372 8635 17372 8257 17372 6147 17373 8257 17373 8636 17373 8636 17374 8257 17374 8259 17374 8636 17375 8259 17375 6146 17375 6146 17376 8259 17376 8255 17376 6146 17377 8255 17377 6154 17377 6154 17378 8255 17378 8637 17378 6154 17379 8637 17379 8639 17379 8639 17380 8637 17380 8638 17380 8639 17381 8638 17381 8640 17381 8640 17382 8638 17382 8641 17382 8640 17383 8641 17383 8642 17383 8642 17384 8641 17384 8643 17384 8642 17385 8643 17385 8644 17385 8644 17386 8643 17386 8245 17386 8644 17387 8245 17387 8645 17387 8645 17388 8245 17388 8263 17388 8645 17389 8263 17389 8646 17389 8646 17390 8263 17390 8633 17390 8754 17391 8647 17391 8665 17391 8648 17392 8753 17392 8754 17392 8718 17393 8738 17393 8751 17393 6622 17394 6621 17394 8749 17394 8649 17395 8757 17395 8739 17395 8739 17396 8757 17396 8756 17396 8748 17397 8747 17397 8692 17397 8692 17398 8747 17398 8649 17398 8690 17399 8746 17399 8748 17399 8689 17400 6085 17400 8691 17400 8658 17401 6622 17401 8650 17401 8650 17402 6622 17402 8749 17402 8650 17403 8749 17403 8737 17403 8663 17404 6638 17404 8651 17404 8651 17405 6638 17405 8652 17405 8651 17406 8652 17406 8653 17406 8653 17407 8652 17407 8654 17407 8653 17408 8654 17408 8728 17408 8728 17409 8654 17409 6635 17409 8728 17410 6635 17410 8655 17410 8655 17411 6635 17411 6633 17411 8655 17412 6633 17412 8656 17412 8656 17413 6633 17413 6632 17413 8656 17414 6632 17414 8731 17414 8731 17415 6632 17415 6631 17415 8731 17416 6631 17416 8732 17416 8732 17417 6631 17417 6630 17417 8732 17418 6630 17418 8733 17418 8733 17419 6630 17419 6629 17419 8733 17420 6629 17420 8657 17420 8657 17421 6629 17421 6628 17421 8657 17422 6628 17422 8734 17422 8734 17423 6628 17423 6627 17423 8734 17424 6627 17424 8735 17424 8735 17425 6627 17425 6625 17425 8735 17426 6625 17426 8658 17426 8658 17427 6625 17427 8659 17427 8658 17428 8659 17428 6622 17428 8744 17429 6644 17429 8660 17429 8660 17430 6644 17430 6642 17430 8660 17431 6642 17431 8727 17431 8727 17432 6642 17432 8661 17432 8727 17433 8661 17433 8662 17433 8662 17434 8661 17434 6640 17434 8662 17435 6640 17435 8663 17435 8663 17436 6640 17436 8664 17436 8663 17437 8664 17437 6638 17437 8754 17438 8665 17438 8648 17438 8648 17439 8665 17439 6116 17439 8648 17440 6116 17440 8717 17440 8717 17441 6116 17441 8666 17441 8717 17442 8666 17442 8715 17442 8715 17443 8666 17443 6115 17443 8715 17444 6115 17444 8714 17444 8714 17445 6115 17445 8667 17445 8714 17446 8667 17446 8712 17446 8712 17447 8667 17447 6109 17447 8712 17448 6109 17448 8709 17448 8709 17449 6109 17449 8668 17449 8709 17450 8668 17450 8669 17450 8669 17451 8668 17451 6107 17451 8669 17452 6107 17452 8670 17452 8670 17453 6107 17453 8671 17453 8670 17454 8671 17454 8672 17454 8672 17455 8671 17455 8674 17455 8672 17456 8674 17456 8673 17456 8673 17457 8674 17457 6091 17457 8673 17458 6091 17458 8675 17458 8675 17459 6091 17459 6112 17459 8675 17460 6112 17460 8676 17460 8676 17461 6112 17461 6113 17461 8676 17462 6113 17462 8677 17462 8677 17463 6113 17463 8679 17463 8677 17464 8679 17464 8678 17464 8678 17465 8679 17465 8680 17465 8678 17466 8680 17466 8702 17466 8702 17467 8680 17467 8681 17467 8702 17468 8681 17468 8700 17468 8700 17469 8681 17469 6094 17469 8700 17470 6094 17470 8698 17470 8698 17471 6094 17471 6096 17471 8698 17472 6096 17472 8697 17472 8697 17473 6096 17473 8682 17473 8697 17474 8682 17474 8683 17474 8683 17475 8682 17475 6095 17475 8683 17476 6095 17476 8685 17476 8685 17477 6095 17477 8684 17477 8685 17478 8684 17478 8694 17478 8694 17479 8684 17479 8686 17479 8694 17480 8686 17480 8687 17480 8687 17481 8686 17481 8688 17481 8687 17482 8688 17482 8693 17482 8693 17483 8688 17483 8689 17483 8693 17484 8689 17484 8690 17484 8690 17485 8689 17485 8691 17485 8690 17486 8691 17486 8746 17486 8748 17487 8692 17487 8690 17487 8690 17488 8692 17488 8720 17488 8690 17489 8720 17489 8693 17489 8693 17490 8720 17490 8721 17490 8693 17491 8721 17491 8687 17491 8687 17492 8721 17492 8695 17492 8687 17493 8695 17493 8694 17493 8694 17494 8695 17494 8696 17494 8694 17495 8696 17495 8685 17495 8685 17496 8696 17496 8723 17496 8685 17497 8723 17497 8683 17497 8683 17498 8723 17498 8725 17498 8683 17499 8725 17499 8697 17499 8697 17500 8725 17500 8726 17500 8697 17501 8726 17501 8698 17501 8698 17502 8726 17502 8699 17502 8698 17503 8699 17503 8700 17503 8700 17504 8699 17504 8701 17504 8700 17505 8701 17505 8702 17505 8702 17506 8701 17506 8703 17506 8702 17507 8703 17507 8678 17507 8678 17508 8703 17508 8704 17508 8678 17509 8704 17509 8677 17509 8677 17510 8704 17510 8705 17510 8677 17511 8705 17511 8676 17511 8676 17512 8705 17512 8729 17512 8676 17513 8729 17513 8675 17513 8675 17514 8729 17514 8706 17514 8675 17515 8706 17515 8673 17515 8673 17516 8706 17516 8730 17516 8673 17517 8730 17517 8672 17517 8672 17518 8730 17518 8707 17518 8672 17519 8707 17519 8670 17519 8670 17520 8707 17520 8708 17520 8670 17521 8708 17521 8669 17521 8669 17522 8708 17522 8710 17522 8669 17523 8710 17523 8709 17523 8709 17524 8710 17524 8711 17524 8709 17525 8711 17525 8712 17525 8712 17526 8711 17526 8713 17526 8712 17527 8713 17527 8714 17527 8714 17528 8713 17528 8736 17528 8714 17529 8736 17529 8715 17529 8715 17530 8736 17530 8716 17530 8715 17531 8716 17531 8717 17531 8717 17532 8716 17532 8718 17532 8717 17533 8718 17533 8648 17533 8648 17534 8718 17534 8751 17534 8648 17535 8751 17535 8753 17535 8649 17536 8739 17536 8692 17536 8692 17537 8739 17537 8719 17537 8692 17538 8719 17538 8720 17538 8720 17539 8719 17539 8740 17539 8720 17540 8740 17540 8721 17540 8721 17541 8740 17541 8742 17541 8721 17542 8742 17542 8695 17542 8695 17543 8742 17543 8722 17543 8695 17544 8722 17544 8696 17544 8696 17545 8722 17545 8724 17545 8696 17546 8724 17546 8723 17546 8723 17547 8724 17547 8744 17547 8723 17548 8744 17548 8725 17548 8725 17549 8744 17549 8660 17549 8725 17550 8660 17550 8726 17550 8726 17551 8660 17551 8727 17551 8726 17552 8727 17552 8699 17552 8699 17553 8727 17553 8662 17553 8699 17554 8662 17554 8701 17554 8701 17555 8662 17555 8663 17555 8701 17556 8663 17556 8703 17556 8703 17557 8663 17557 8651 17557 8703 17558 8651 17558 8704 17558 8704 17559 8651 17559 8653 17559 8704 17560 8653 17560 8705 17560 8705 17561 8653 17561 8728 17561 8705 17562 8728 17562 8729 17562 8729 17563 8728 17563 8655 17563 8729 17564 8655 17564 8706 17564 8706 17565 8655 17565 8656 17565 8706 17566 8656 17566 8730 17566 8730 17567 8656 17567 8731 17567 8730 17568 8731 17568 8707 17568 8707 17569 8731 17569 8732 17569 8707 17570 8732 17570 8708 17570 8708 17571 8732 17571 8733 17571 8708 17572 8733 17572 8710 17572 8710 17573 8733 17573 8657 17573 8710 17574 8657 17574 8711 17574 8711 17575 8657 17575 8734 17575 8711 17576 8734 17576 8713 17576 8713 17577 8734 17577 8735 17577 8713 17578 8735 17578 8736 17578 8736 17579 8735 17579 8658 17579 8736 17580 8658 17580 8716 17580 8716 17581 8658 17581 8650 17581 8716 17582 8650 17582 8718 17582 8718 17583 8650 17583 8737 17583 8718 17584 8737 17584 8738 17584 8756 17585 6654 17585 8739 17585 8739 17586 6654 17586 6653 17586 8739 17587 6653 17587 8719 17587 8719 17588 6653 17588 6652 17588 8719 17589 6652 17589 8740 17589 8740 17590 6652 17590 6646 17590 8740 17591 6646 17591 8742 17591 8742 17592 6646 17592 8741 17592 8742 17593 8741 17593 8722 17593 8722 17594 8741 17594 8743 17594 8722 17595 8743 17595 8724 17595 8724 17596 8743 17596 6649 17596 8724 17597 6649 17597 8744 17597 8744 17598 6649 17598 6650 17598 8744 17599 6650 17599 6644 17599 8691 17600 6085 17600 6083 17600 8748 17601 8746 17601 8745 17601 8745 17602 8746 17602 8691 17602 8649 17603 8747 17603 8810 17603 8810 17604 8747 17604 8748 17604 8758 17605 8757 17605 8649 17605 8853 17606 8750 17606 6621 17606 6621 17607 8750 17607 8749 17607 8749 17608 8750 17608 8737 17608 8737 17609 8750 17609 8856 17609 8737 17610 8856 17610 8738 17610 8738 17611 8856 17611 8751 17611 8751 17612 8856 17612 8752 17612 8751 17613 8752 17613 8753 17613 8753 17614 8752 17614 8754 17614 8754 17615 8752 17615 8755 17615 8754 17616 8755 17616 8647 17616 8756 17617 8757 17617 8759 17617 8759 17618 8757 17618 8758 17618 8759 17619 8758 17619 6589 17619 6589 17620 8758 17620 8811 17620 6589 17621 8811 17621 8760 17621 8760 17622 8811 17622 8813 17622 6596 17623 6594 17623 8813 17623 8813 17624 6594 17624 6592 17624 8813 17625 6592 17625 8760 17625 8813 17626 8761 17626 6596 17626 6596 17627 8761 17627 8762 17627 6596 17628 8762 17628 8763 17628 8763 17629 8762 17629 8816 17629 8763 17630 8816 17630 8764 17630 8764 17631 8816 17631 8817 17631 8765 17632 6599 17632 8819 17632 8819 17633 6599 17633 8766 17633 8819 17634 8766 17634 8817 17634 8817 17635 8766 17635 6598 17635 8817 17636 6598 17636 8764 17636 8691 17637 6083 17637 8745 17637 8745 17638 6083 17638 6081 17638 8745 17639 6081 17639 8788 17639 8788 17640 6081 17640 6079 17640 8788 17641 6079 17641 8790 17641 8790 17642 6079 17642 8767 17642 8790 17643 8767 17643 8792 17643 8792 17644 8767 17644 8768 17644 8792 17645 8768 17645 8769 17645 8769 17646 8768 17646 6089 17646 8769 17647 6089 17647 8793 17647 8793 17648 6089 17648 8770 17648 8793 17649 8770 17649 8771 17649 8771 17650 8770 17650 6090 17650 8771 17651 6090 17651 8772 17651 8772 17652 6090 17652 6088 17652 8772 17653 6088 17653 8795 17653 8795 17654 6088 17654 8773 17654 8795 17655 8773 17655 8774 17655 8774 17656 8773 17656 8775 17656 8774 17657 8775 17657 8796 17657 8796 17658 8775 17658 8776 17658 8796 17659 8776 17659 8797 17659 8797 17660 8776 17660 6101 17660 8797 17661 6101 17661 8798 17661 8798 17662 6101 17662 6099 17662 8798 17663 6099 17663 8799 17663 8799 17664 6099 17664 6097 17664 8799 17665 6097 17665 8801 17665 8801 17666 6097 17666 8777 17666 8801 17667 8777 17667 8778 17667 8778 17668 8777 17668 6077 17668 8778 17669 6077 17669 8779 17669 8779 17670 6077 17670 8780 17670 8779 17671 8780 17671 8781 17671 8781 17672 8780 17672 6105 17672 8781 17673 6105 17673 8782 17673 8782 17674 6105 17674 6104 17674 8782 17675 6104 17675 8783 17675 8783 17676 6104 17676 8784 17676 8783 17677 8784 17677 8807 17677 8807 17678 8784 17678 8785 17678 8807 17679 8785 17679 8786 17679 8786 17680 8785 17680 6108 17680 8786 17681 6108 17681 8787 17681 8748 17682 8745 17682 8810 17682 8810 17683 8745 17683 8788 17683 8810 17684 8788 17684 8789 17684 8789 17685 8788 17685 8790 17685 8789 17686 8790 17686 8812 17686 8812 17687 8790 17687 8792 17687 8812 17688 8792 17688 8791 17688 8791 17689 8792 17689 8769 17689 8791 17690 8769 17690 8814 17690 8814 17691 8769 17691 8793 17691 8814 17692 8793 17692 8815 17692 8815 17693 8793 17693 8771 17693 8815 17694 8771 17694 8794 17694 8794 17695 8771 17695 8772 17695 8794 17696 8772 17696 8818 17696 8818 17697 8772 17697 8795 17697 8818 17698 8795 17698 8820 17698 8820 17699 8795 17699 8774 17699 8820 17700 8774 17700 8821 17700 8821 17701 8774 17701 8796 17701 8821 17702 8796 17702 8822 17702 8822 17703 8796 17703 8797 17703 8822 17704 8797 17704 8823 17704 8823 17705 8797 17705 8798 17705 8823 17706 8798 17706 8824 17706 8824 17707 8798 17707 8799 17707 8824 17708 8799 17708 8800 17708 8800 17709 8799 17709 8801 17709 8800 17710 8801 17710 8802 17710 8802 17711 8801 17711 8778 17711 8802 17712 8778 17712 8827 17712 8827 17713 8778 17713 8779 17713 8827 17714 8779 17714 8828 17714 8828 17715 8779 17715 8781 17715 8828 17716 8781 17716 8803 17716 8803 17717 8781 17717 8782 17717 8803 17718 8782 17718 8804 17718 8804 17719 8782 17719 8783 17719 8804 17720 8783 17720 8805 17720 8805 17721 8783 17721 8807 17721 8805 17722 8807 17722 8806 17722 8806 17723 8807 17723 8786 17723 8806 17724 8786 17724 8808 17724 8808 17725 8786 17725 8787 17725 8808 17726 8787 17726 8809 17726 8649 17727 8810 17727 8758 17727 8758 17728 8810 17728 8789 17728 8758 17729 8789 17729 8811 17729 8811 17730 8789 17730 8812 17730 8811 17731 8812 17731 8813 17731 8813 17732 8812 17732 8791 17732 8813 17733 8791 17733 8761 17733 8761 17734 8791 17734 8814 17734 8761 17735 8814 17735 8762 17735 8762 17736 8814 17736 8815 17736 8762 17737 8815 17737 8816 17737 8816 17738 8815 17738 8794 17738 8816 17739 8794 17739 8817 17739 8817 17740 8794 17740 8818 17740 8817 17741 8818 17741 8819 17741 8819 17742 8818 17742 8820 17742 8819 17743 8820 17743 8765 17743 8765 17744 8820 17744 8821 17744 8765 17745 8821 17745 8848 17745 8848 17746 8821 17746 8822 17746 8848 17747 8822 17747 8847 17747 8847 17748 8822 17748 8823 17748 8847 17749 8823 17749 8825 17749 8825 17750 8823 17750 8824 17750 8825 17751 8824 17751 8826 17751 8826 17752 8824 17752 8800 17752 8826 17753 8800 17753 8843 17753 8843 17754 8800 17754 8802 17754 8843 17755 8802 17755 8841 17755 8841 17756 8802 17756 8827 17756 8841 17757 8827 17757 8839 17757 8839 17758 8827 17758 8828 17758 8839 17759 8828 17759 8838 17759 8838 17760 8828 17760 8803 17760 8838 17761 8803 17761 8829 17761 8829 17762 8803 17762 8804 17762 8829 17763 8804 17763 8830 17763 8830 17764 8804 17764 8805 17764 8830 17765 8805 17765 8831 17765 8831 17766 8805 17766 8806 17766 8831 17767 8806 17767 8832 17767 8832 17768 8806 17768 8808 17768 8832 17769 8808 17769 8833 17769 8833 17770 8808 17770 8809 17770 8833 17771 8809 17771 8850 17771 8834 17772 6616 17772 8850 17772 8850 17773 6616 17773 8835 17773 8850 17774 8835 17774 8833 17774 8833 17775 8835 17775 6613 17775 8833 17776 6613 17776 8832 17776 8832 17777 6613 17777 6612 17777 8832 17778 6612 17778 8831 17778 8831 17779 6612 17779 6611 17779 8831 17780 6611 17780 8830 17780 8830 17781 6611 17781 8836 17781 8830 17782 8836 17782 8829 17782 8829 17783 8836 17783 8837 17783 8829 17784 8837 17784 8838 17784 8838 17785 8837 17785 8840 17785 8838 17786 8840 17786 8839 17786 8839 17787 8840 17787 8842 17787 8839 17788 8842 17788 8841 17788 8841 17789 8842 17789 6588 17789 8841 17790 6588 17790 8843 17790 8843 17791 6588 17791 8844 17791 8843 17792 8844 17792 8826 17792 8826 17793 8844 17793 8845 17793 8826 17794 8845 17794 8825 17794 8825 17795 8845 17795 6604 17795 8825 17796 6604 17796 8847 17796 8847 17797 6604 17797 8846 17797 8847 17798 8846 17798 8848 17798 8848 17799 8846 17799 8849 17799 8848 17800 8849 17800 8765 17800 8765 17801 8849 17801 6600 17801 8765 17802 6600 17802 6599 17802 6620 17803 8834 17803 8854 17803 8854 17804 8834 17804 8850 17804 8854 17805 8850 17805 8855 17805 8855 17806 8850 17806 8809 17806 8855 17807 8809 17807 8851 17807 8851 17808 8809 17808 8787 17808 8851 17809 8787 17809 8852 17809 8852 17810 8787 17810 6108 17810 8853 17811 6620 17811 8750 17811 8750 17812 6620 17812 8854 17812 8750 17813 8854 17813 8856 17813 8856 17814 8854 17814 8855 17814 8856 17815 8855 17815 8752 17815 8752 17816 8855 17816 8851 17816 8752 17817 8851 17817 8755 17817 8755 17818 8851 17818 8852 17818 8876 17819 17054 17819 8857 17819 8857 17820 17054 17820 8858 17820 8857 17821 8858 17821 8880 17821 8880 17822 8858 17822 8859 17822 8880 17823 8859 17823 8882 17823 8882 17824 8859 17824 17056 17824 8882 17825 17056 17825 8860 17825 8860 17826 17056 17826 8861 17826 8860 17827 8861 17827 8869 17827 8869 17828 8861 17828 17050 17828 8869 17829 17050 17829 8862 17829 8862 17830 17050 17830 8863 17830 8862 17831 8863 17831 8864 17831 8864 17832 8863 17832 8865 17832 8864 17833 8865 17833 8870 17833 8870 17834 8865 17834 8866 17834 8870 17835 8866 17835 8872 17835 8872 17836 8866 17836 17052 17836 8872 17837 17052 17837 8873 17837 8873 17838 17052 17838 8867 17838 8873 17839 8867 17839 8874 17839 8874 17840 8867 17840 17053 17840 8874 17841 17053 17841 8876 17841 8876 17842 17053 17842 17054 17842 17078 17843 8860 17843 8868 17843 8868 17844 8860 17844 8869 17844 8868 17845 8869 17845 17087 17845 17087 17846 8869 17846 8862 17846 17087 17847 8862 17847 17084 17847 17084 17848 8862 17848 8864 17848 17084 17849 8864 17849 17083 17849 17083 17850 8864 17850 8870 17850 17083 17851 8870 17851 8871 17851 8871 17852 8870 17852 8872 17852 8871 17853 8872 17853 17082 17853 17082 17854 8872 17854 8873 17854 17082 17855 8873 17855 8875 17855 8875 17856 8873 17856 8874 17856 8875 17857 8874 17857 8877 17857 8877 17858 8874 17858 8876 17858 8877 17859 8876 17859 8878 17859 8878 17860 8876 17860 8857 17860 8878 17861 8857 17861 8879 17861 8879 17862 8857 17862 8880 17862 8879 17863 8880 17863 8881 17863 8881 17864 8880 17864 8882 17864 8881 17865 8882 17865 17078 17865 17078 17866 8882 17866 8860 17866 8895 17867 4912 17867 8883 17867 8883 17868 4912 17868 4910 17868 8883 17869 4910 17869 8884 17869 8884 17870 4910 17870 8885 17870 8884 17871 8885 17871 17047 17871 17047 17872 8885 17872 8886 17872 17047 17873 8886 17873 17046 17873 17046 17874 8886 17874 8887 17874 17046 17875 8887 17875 8888 17875 8888 17876 8887 17876 4920 17876 8888 17877 4920 17877 8889 17877 8889 17878 4920 17878 4918 17878 8889 17879 4918 17879 17044 17879 17044 17880 4918 17880 4916 17880 17044 17881 4916 17881 17043 17881 17043 17882 4916 17882 8890 17882 17043 17883 8890 17883 8891 17883 8891 17884 8890 17884 4914 17884 8891 17885 4914 17885 8892 17885 8892 17886 4914 17886 8894 17886 8892 17887 8894 17887 8893 17887 8893 17888 8894 17888 8896 17888 8893 17889 8896 17889 8895 17889 8895 17890 8896 17890 4912 17890 8216 17891 8908 17891 8897 17891 8897 17892 8908 17892 6111 17892 8897 17893 6111 17893 8898 17893 8898 17894 6111 17894 6110 17894 8898 17895 6110 17895 8899 17895 8899 17896 6110 17896 6092 17896 8899 17897 6092 17897 8900 17897 8900 17898 6092 17898 8901 17898 8900 17899 8901 17899 8219 17899 8219 17900 8901 17900 8902 17900 8219 17901 8902 17901 8903 17901 8903 17902 8902 17902 6106 17902 8903 17903 6106 17903 8904 17903 8904 17904 6106 17904 6098 17904 8904 17905 6098 17905 8905 17905 8905 17906 6098 17906 6100 17906 8905 17907 6100 17907 8224 17907 8224 17908 6100 17908 6102 17908 8224 17909 6102 17909 8906 17909 8906 17910 6102 17910 6103 17910 8906 17911 6103 17911 8215 17911 8215 17912 6103 17912 8907 17912 8215 17913 8907 17913 8216 17913 8216 17914 8907 17914 8908 17914 8918 17915 8909 17915 9140 17915 8918 17916 9140 17916 8919 17916 8911 17917 8920 17917 8910 17917 8911 17918 8910 17918 9140 17918 9140 17919 8910 17919 8912 17919 9140 17920 8912 17920 8919 17920 8913 17921 8928 17921 8927 17921 8928 17922 8913 17922 8914 17922 9172 17923 9182 17923 8915 17923 9015 17924 8909 17924 8918 17924 8916 17925 9015 17925 8917 17925 9015 17926 8918 17926 8917 17926 8917 17927 8918 17927 8919 17927 8917 17928 8919 17928 8922 17928 8922 17929 8919 17929 8912 17929 8922 17930 8912 17930 8923 17930 8923 17931 8912 17931 8910 17931 8923 17932 8910 17932 8926 17932 8926 17933 8910 17933 8920 17933 8926 17934 8920 17934 8927 17934 8927 17935 8920 17935 9166 17935 8927 17936 9166 17936 8913 17936 8916 17937 8917 17937 8942 17937 8942 17938 8917 17938 8922 17938 8942 17939 8922 17939 8921 17939 8921 17940 8922 17940 8923 17940 8921 17941 8923 17941 8924 17941 8924 17942 8923 17942 8926 17942 8924 17943 8926 17943 8925 17943 8925 17944 8926 17944 8927 17944 8925 17945 8927 17945 8940 17945 8940 17946 8927 17946 8928 17946 8940 17947 8928 17947 8915 17947 8915 17948 8928 17948 8914 17948 8915 17949 8914 17949 9172 17949 9273 17950 8943 17950 8989 17950 8989 17951 8988 17951 9273 17951 9273 17952 8988 17952 8990 17952 9273 17953 8990 17953 8929 17953 8929 17954 8990 17954 8930 17954 8929 17955 8930 17955 9331 17955 9320 17956 8931 17956 8984 17956 8934 17957 8938 17957 8932 17957 8933 17958 9016 17958 8941 17958 8932 17959 8986 17959 8934 17959 8934 17960 8986 17960 8935 17960 8934 17961 8935 17961 8936 17961 8936 17962 8935 17962 8995 17962 8936 17963 8995 17963 8933 17963 8933 17964 8995 17964 9011 17964 8933 17965 9011 17965 9016 17965 9083 17966 9320 17966 8937 17966 8937 17967 9320 17967 8984 17967 8937 17968 8984 17968 8938 17968 8938 17969 8984 17969 8987 17969 8938 17970 8987 17970 8932 17970 9054 17971 8939 17971 9184 17971 9184 17972 8939 17972 8915 17972 9184 17973 8915 17973 9182 17973 9080 17974 8924 17974 9078 17974 9078 17975 8924 17975 8925 17975 9078 17976 8925 17976 8939 17976 8939 17977 8925 17977 8940 17977 8939 17978 8940 17978 8915 17978 8941 17979 8916 17979 8933 17979 8933 17980 8916 17980 8942 17980 8933 17981 8942 17981 9080 17981 9080 17982 8942 17982 8921 17982 9080 17983 8921 17983 8924 17983 8943 17984 9273 17984 9272 17984 9123 17985 8944 17985 9272 17985 9123 17986 9272 17986 8965 17986 8965 17987 9272 17987 9274 17987 8965 17988 9274 17988 8966 17988 9140 17989 8909 17989 8944 17989 8944 17990 8909 17990 9013 17990 8944 17991 9013 17991 9272 17991 9272 17992 9013 17992 9012 17992 9272 17993 9012 17993 8943 17993 8947 17994 8981 17994 8957 17994 8957 17995 8981 17995 8945 17995 8957 17996 8945 17996 8946 17996 8946 17997 8945 17997 9084 17997 8957 17998 9223 17998 8947 17998 8947 17999 9223 17999 9222 17999 8947 18000 9222 18000 8978 18000 8978 18001 9222 18001 8969 18001 8948 18002 9116 18002 8977 18002 8956 18003 9216 18003 9220 18003 9233 18004 8949 18004 9220 18004 9220 18005 8949 18005 9031 18005 9220 18006 9031 18006 8956 18006 9020 18007 9019 18007 8948 18007 9020 18008 8948 18008 9027 18008 9027 18009 8948 18009 8977 18009 9027 18010 8977 18010 9028 18010 9028 18011 8977 18011 8950 18011 9028 18012 8950 18012 8951 18012 8951 18013 8950 18013 8975 18013 8951 18014 8975 18014 8952 18014 8952 18015 8975 18015 8954 18015 8952 18016 8954 18016 8953 18016 8953 18017 8954 18017 8974 18017 8953 18018 8974 18018 8955 18018 8955 18019 8974 18019 8973 18019 8955 18020 8973 18020 9031 18020 9031 18021 8973 18021 8971 18021 9031 18022 8971 18022 8956 18022 8957 18023 8958 18023 9223 18023 9223 18024 8958 18024 8959 18024 8959 18025 8958 18025 9253 18025 9253 18026 8958 18026 8960 18026 9253 18027 8960 18027 8961 18027 8961 18028 8960 18028 8962 18028 8961 18029 8962 18029 9249 18029 9249 18030 8962 18030 8963 18030 9249 18031 8963 18031 8964 18031 8963 18032 9105 18032 8964 18032 8964 18033 9105 18033 8965 18033 8964 18034 8965 18034 8966 18034 9201 18035 8967 18035 8972 18035 8968 18036 9216 18036 8956 18036 8968 18037 8956 18037 8967 18037 9201 18038 8972 18038 8969 18038 8982 18039 8976 18039 9118 18039 9118 18040 8976 18040 8977 18040 9118 18041 8977 18041 8970 18041 8970 18042 8977 18042 9116 18042 8967 18043 8956 18043 8972 18043 8972 18044 8956 18044 8971 18044 8972 18045 8971 18045 8979 18045 8971 18046 8973 18046 8979 18046 8979 18047 8973 18047 8974 18047 8979 18048 8974 18048 8980 18048 8974 18049 8954 18049 8980 18049 8980 18050 8954 18050 8975 18050 8980 18051 8975 18051 8976 18051 8976 18052 8975 18052 8950 18052 8976 18053 8950 18053 8977 18053 8969 18054 8972 18054 8978 18054 8978 18055 8972 18055 8979 18055 8978 18056 8979 18056 8947 18056 8947 18057 8979 18057 8980 18057 8947 18058 8980 18058 8981 18058 8981 18059 8980 18059 8976 18059 8981 18060 8976 18060 8945 18060 8945 18061 8976 18061 8982 18061 8945 18062 8982 18062 9084 18062 8983 18063 9332 18063 8985 18063 8985 18064 9332 18064 9331 18064 8931 18065 8983 18065 8984 18065 8984 18066 8983 18066 8985 18066 8984 18067 8985 18067 8991 18067 8991 18068 8985 18068 9331 18068 8991 18069 9331 18069 8930 18069 8986 18070 8932 18070 8991 18070 8991 18071 8932 18071 8987 18071 8991 18072 8987 18072 8984 18072 8992 18073 8990 18073 8988 18073 8992 18074 8988 18074 8993 18074 8993 18075 8988 18075 8989 18075 8993 18076 8989 18076 8994 18076 8994 18077 8989 18077 8943 18077 8994 18078 8943 18078 9010 18078 8930 18079 8990 18079 8991 18079 8991 18080 8990 18080 8992 18080 8991 18081 8992 18081 8986 18081 8986 18082 8992 18082 8993 18082 8986 18083 8993 18083 8935 18083 8935 18084 8993 18084 8994 18084 8935 18085 8994 18085 8995 18085 8995 18086 8994 18086 9010 18086 8995 18087 9010 18087 9011 18087 8996 18088 8193 18088 9062 18088 9062 18089 8193 18089 8202 18089 9062 18090 8202 18090 8997 18090 8997 18091 8202 18091 8998 18091 8997 18092 8998 18092 9065 18092 9046 18093 9045 18093 8999 18093 8999 18094 9045 18094 9000 18094 8999 18095 9000 18095 8201 18095 8201 18096 9000 18096 9267 18096 8201 18097 9267 18097 8998 18097 8998 18098 9267 18098 9001 18098 8998 18099 9001 18099 9065 18099 9002 18100 8195 18100 8996 18100 8996 18101 8195 18101 8194 18101 8996 18102 8194 18102 8193 18102 9002 18103 9058 18103 8195 18103 8195 18104 9058 18104 9057 18104 8195 18105 9057 18105 8196 18105 8196 18106 9057 18106 9180 18106 8196 18107 9180 18107 9003 18107 9003 18108 9180 18108 9004 18108 9003 18109 9004 18109 9052 18109 9052 18110 9051 18110 9003 18110 9003 18111 9051 18111 9005 18111 9003 18112 9005 18112 8199 18112 8199 18113 9005 18113 9006 18113 8199 18114 9006 18114 9007 18114 9007 18115 9006 18115 9049 18115 9007 18116 9049 18116 9008 18116 9008 18117 9049 18117 9009 18117 9008 18118 9009 18118 8999 18118 8999 18119 9009 18119 9048 18119 8999 18120 9048 18120 9046 18120 9010 18121 8943 18121 9012 18121 9011 18122 9010 18122 9014 18122 9010 18123 9012 18123 9014 18123 9014 18124 9012 18124 9013 18124 9014 18125 9013 18125 9017 18125 9017 18126 9013 18126 8909 18126 9017 18127 8909 18127 9015 18127 9011 18128 9014 18128 9016 18128 9016 18129 9014 18129 9017 18129 9016 18130 9017 18130 8941 18130 8941 18131 9017 18131 9015 18131 8941 18132 9015 18132 8916 18132 9025 18133 9163 18133 9033 18133 9034 18134 9164 18134 9018 18134 9165 18135 9019 18135 9020 18135 9021 18136 9022 18136 9043 18136 9242 18137 9000 18137 9045 18137 9032 18138 9023 18138 9024 18138 9024 18139 9023 18139 9237 18139 9025 18140 9033 18140 9004 18140 9164 18141 9165 18141 9018 18141 9018 18142 9165 18142 9020 18142 9018 18143 9020 18143 9026 18143 9026 18144 9020 18144 9027 18144 9026 18145 9027 18145 9037 18145 9037 18146 9027 18146 9028 18146 9037 18147 9028 18147 9038 18147 9038 18148 9028 18148 8951 18148 9038 18149 8951 18149 9029 18149 9029 18150 8951 18150 8952 18150 9029 18151 8952 18151 9040 18151 9040 18152 8952 18152 8953 18152 9040 18153 8953 18153 9042 18153 9042 18154 8953 18154 8955 18154 9042 18155 8955 18155 9030 18155 9030 18156 8955 18156 9031 18156 9030 18157 9031 18157 9024 18157 9024 18158 9031 18158 8949 18158 9024 18159 8949 18159 9032 18159 9032 18160 8949 18160 9233 18160 9163 18161 9034 18161 9033 18161 9033 18162 9034 18162 9018 18162 9033 18163 9018 18163 9035 18163 9035 18164 9018 18164 9026 18164 9035 18165 9026 18165 9036 18165 9036 18166 9026 18166 9037 18166 9036 18167 9037 18167 9050 18167 9050 18168 9037 18168 9038 18168 9050 18169 9038 18169 9039 18169 9039 18170 9038 18170 9029 18170 9039 18171 9029 18171 9047 18171 9047 18172 9029 18172 9040 18172 9047 18173 9040 18173 9041 18173 9041 18174 9040 18174 9042 18174 9041 18175 9042 18175 9044 18175 9044 18176 9042 18176 9030 18176 9044 18177 9030 18177 9043 18177 9043 18178 9030 18178 9024 18178 9043 18179 9024 18179 9021 18179 9021 18180 9024 18180 9237 18180 9022 18181 9242 18181 9043 18181 9043 18182 9242 18182 9045 18182 9043 18183 9045 18183 9044 18183 9044 18184 9045 18184 9046 18184 9044 18185 9046 18185 9041 18185 9041 18186 9046 18186 9048 18186 9041 18187 9048 18187 9047 18187 9047 18188 9048 18188 9009 18188 9047 18189 9009 18189 9039 18189 9039 18190 9009 18190 9049 18190 9039 18191 9049 18191 9050 18191 9050 18192 9049 18192 9006 18192 9050 18193 9006 18193 9036 18193 9036 18194 9006 18194 9005 18194 9036 18195 9005 18195 9035 18195 9035 18196 9005 18196 9051 18196 9035 18197 9051 18197 9033 18197 9033 18198 9051 18198 9052 18198 9033 18199 9052 18199 9004 18199 9077 18200 9197 18200 9076 18200 9071 18201 9053 18201 9059 18201 9300 18202 9301 18202 9064 18202 9073 18203 9304 18203 9305 18203 9300 18204 9064 18204 9001 18204 9054 18205 9055 18205 8939 18205 8939 18206 9055 18206 9056 18206 8939 18207 9056 18207 9078 18207 9053 18208 9057 18208 9059 18208 9059 18209 9057 18209 9058 18209 9059 18210 9058 18210 9060 18210 9060 18211 9058 18211 9002 18211 9060 18212 9002 18212 9061 18212 9061 18213 9002 18213 8996 18213 9061 18214 8996 18214 9067 18214 9067 18215 8996 18215 9062 18215 9067 18216 9062 18216 9063 18216 9063 18217 9062 18217 8997 18217 9063 18218 8997 18218 9064 18218 9064 18219 8997 18219 9065 18219 9064 18220 9065 18220 9001 18220 9301 18221 9066 18221 9064 18221 9064 18222 9066 18222 9072 18222 9064 18223 9072 18223 9063 18223 9063 18224 9072 18224 9068 18224 9063 18225 9068 18225 9067 18225 9067 18226 9068 18226 9074 18226 9067 18227 9074 18227 9061 18227 9061 18228 9074 18228 9069 18228 9061 18229 9069 18229 9060 18229 9060 18230 9069 18230 9070 18230 9060 18231 9070 18231 9059 18231 9059 18232 9070 18232 9076 18232 9059 18233 9076 18233 9071 18233 9071 18234 9076 18234 9197 18234 9066 18235 9304 18235 9072 18235 9072 18236 9304 18236 9073 18236 9072 18237 9073 18237 9068 18237 9068 18238 9073 18238 9082 18238 9068 18239 9082 18239 9074 18239 9074 18240 9082 18240 9081 18240 9074 18241 9081 18241 9069 18241 9069 18242 9081 18242 9075 18242 9069 18243 9075 18243 9070 18243 9070 18244 9075 18244 9079 18244 9070 18245 9079 18245 9076 18245 9076 18246 9079 18246 9056 18246 9076 18247 9056 18247 9077 18247 9077 18248 9056 18248 9055 18248 9078 18249 9056 18249 9080 18249 9080 18250 9056 18250 9079 18250 9080 18251 9079 18251 8933 18251 8933 18252 9079 18252 9075 18252 8933 18253 9075 18253 8936 18253 8936 18254 9075 18254 9081 18254 8936 18255 9081 18255 8934 18255 8934 18256 9081 18256 9082 18256 8934 18257 9082 18257 8938 18257 8938 18258 9082 18258 9073 18258 8938 18259 9073 18259 8937 18259 8937 18260 9073 18260 9305 18260 8937 18261 9305 18261 9083 18261 9087 18262 5302 18262 9093 18262 8946 18263 9084 18263 9089 18263 9089 18264 9084 18264 9085 18264 9089 18265 9085 18265 9091 18265 9091 18266 9085 18266 9086 18266 9091 18267 9086 18267 9093 18267 9093 18268 9086 18268 9088 18268 9093 18269 9088 18269 9087 18269 9087 18270 9088 18270 9122 18270 8957 18271 8946 18271 9096 18271 9096 18272 8946 18272 9089 18272 9096 18273 9089 18273 9090 18273 9090 18274 9089 18274 9091 18274 9090 18275 9091 18275 9099 18275 9099 18276 9091 18276 9093 18276 9099 18277 9093 18277 9092 18277 9092 18278 9093 18278 5302 18278 8962 18279 8960 18279 9102 18279 8958 18280 8957 18280 9094 18280 9094 18281 8957 18281 9096 18281 9094 18282 9096 18282 9095 18282 9095 18283 9096 18283 9090 18283 9095 18284 9090 18284 9097 18284 9097 18285 9090 18285 9099 18285 9097 18286 9099 18286 9098 18286 9098 18287 9099 18287 9092 18287 8960 18288 8958 18288 9102 18288 9102 18289 8958 18289 9094 18289 9102 18290 9094 18290 9103 18290 9103 18291 9094 18291 9095 18291 9103 18292 9095 18292 9100 18292 9100 18293 9095 18293 9097 18293 9100 18294 9097 18294 5298 18294 5298 18295 9097 18295 9098 18295 8963 18296 8962 18296 9101 18296 9101 18297 8962 18297 9102 18297 9101 18298 9102 18298 9107 18298 9107 18299 9102 18299 9103 18299 9107 18300 9103 18300 9104 18300 9104 18301 9103 18301 9100 18301 9104 18302 9100 18302 5299 18302 5299 18303 9100 18303 5298 18303 9105 18304 8963 18304 9106 18304 9106 18305 8963 18305 9101 18305 9106 18306 9101 18306 9109 18306 9109 18307 9101 18307 9107 18307 9109 18308 9107 18308 9110 18308 9110 18309 9107 18309 9104 18309 9110 18310 9104 18310 9111 18310 9111 18311 9104 18311 5299 18311 8965 18312 9105 18312 9125 18312 9125 18313 9105 18313 9106 18313 9125 18314 9106 18314 9108 18314 9108 18315 9106 18315 9109 18315 9108 18316 9109 18316 9127 18316 9127 18317 9109 18317 9110 18317 9127 18318 9110 18318 9128 18318 9128 18319 9110 18319 9111 18319 9118 18320 8970 18320 9117 18320 9112 18321 9136 18321 9113 18321 9113 18322 9136 18322 9135 18322 9113 18323 9135 18323 9114 18323 9114 18324 9135 18324 9115 18324 8970 18325 9116 18325 9117 18325 9117 18326 9116 18326 9138 18326 9117 18327 9138 18327 9112 18327 9112 18328 9138 18328 9139 18328 9112 18329 9139 18329 9136 18329 8982 18330 9118 18330 9121 18330 9121 18331 9118 18331 9117 18331 9121 18332 9117 18332 9119 18332 9119 18333 9117 18333 9112 18333 9119 18334 9112 18334 9120 18334 9120 18335 9112 18335 9113 18335 9120 18336 9113 18336 5324 18336 5324 18337 9113 18337 9114 18337 9084 18338 8982 18338 9085 18338 9085 18339 8982 18339 9121 18339 9085 18340 9121 18340 9086 18340 9086 18341 9121 18341 9119 18341 9086 18342 9119 18342 9088 18342 9088 18343 9119 18343 9120 18343 9088 18344 9120 18344 9122 18344 9122 18345 9120 18345 5324 18345 8944 18346 9123 18346 9124 18346 9123 18347 8965 18347 9124 18347 9124 18348 8965 18348 9125 18348 9124 18349 9125 18349 9130 18349 9130 18350 9125 18350 9108 18350 9130 18351 9108 18351 9126 18351 9126 18352 9108 18352 9127 18352 9126 18353 9127 18353 5295 18353 5295 18354 9127 18354 9128 18354 9140 18355 8944 18355 9129 18355 9129 18356 8944 18356 9124 18356 9129 18357 9124 18357 9141 18357 9141 18358 9124 18358 9130 18358 9141 18359 9130 18359 9131 18359 9131 18360 9130 18360 9126 18360 9131 18361 9126 18361 9132 18361 9132 18362 9126 18362 5295 18362 9134 18363 9115 18363 9135 18363 8948 18364 9019 18364 9137 18364 9137 18365 9019 18365 9162 18365 9137 18366 9162 18366 9133 18366 9133 18367 9162 18367 9161 18367 9133 18368 9161 18368 5348 18368 5348 18369 9161 18369 9151 18369 5348 18370 9134 18370 9133 18370 9133 18371 9134 18371 9135 18371 9133 18372 9135 18372 9137 18372 9137 18373 9135 18373 9136 18373 9116 18374 8948 18374 9138 18374 9138 18375 8948 18375 9137 18375 9138 18376 9137 18376 9139 18376 9139 18377 9137 18377 9136 18377 8911 18378 9140 18378 9143 18378 9143 18379 9140 18379 9129 18379 9143 18380 9129 18380 9145 18380 9145 18381 9129 18381 9141 18381 9145 18382 9141 18382 9146 18382 9146 18383 9141 18383 9131 18383 9146 18384 9131 18384 9142 18384 9142 18385 9131 18385 9132 18385 8920 18386 8911 18386 9144 18386 9144 18387 8911 18387 9143 18387 9144 18388 9143 18388 9167 18388 9167 18389 9143 18389 9145 18389 9167 18390 9145 18390 9170 18390 9170 18391 9145 18391 9146 18391 9170 18392 9146 18392 5345 18392 5345 18393 9146 18393 9142 18393 9181 18394 5277 18394 9148 18394 9147 18395 9181 18395 9153 18395 9004 18396 9147 18396 9152 18396 9181 18397 9148 18397 9153 18397 9153 18398 9148 18398 5276 18398 9153 18399 5276 18399 9154 18399 9154 18400 5276 18400 5274 18400 9154 18401 5274 18401 9156 18401 9156 18402 5274 18402 9149 18402 9156 18403 9149 18403 9158 18403 9158 18404 9149 18404 5322 18404 9158 18405 5322 18405 9150 18405 9150 18406 5322 18406 9151 18406 9150 18407 9151 18407 9161 18407 9147 18408 9153 18408 9152 18408 9152 18409 9153 18409 9154 18409 9152 18410 9154 18410 9155 18410 9155 18411 9154 18411 9156 18411 9155 18412 9156 18412 9157 18412 9157 18413 9156 18413 9158 18413 9157 18414 9158 18414 9159 18414 9159 18415 9158 18415 9150 18415 9159 18416 9150 18416 9160 18416 9160 18417 9150 18417 9161 18417 9160 18418 9161 18418 9162 18418 9004 18419 9152 18419 9025 18419 9025 18420 9152 18420 9155 18420 9025 18421 9155 18421 9163 18421 9163 18422 9155 18422 9157 18422 9163 18423 9157 18423 9034 18423 9034 18424 9157 18424 9159 18424 9034 18425 9159 18425 9164 18425 9164 18426 9159 18426 9160 18426 9164 18427 9160 18427 9165 18427 9165 18428 9160 18428 9162 18428 9165 18429 9162 18429 9019 18429 9166 18430 8920 18430 9144 18430 9169 18431 9172 18431 8914 18431 9166 18432 9144 18432 8913 18432 9170 18433 9175 18433 9167 18433 9167 18434 9175 18434 9168 18434 9167 18435 9168 18435 9144 18435 9144 18436 9168 18436 9169 18436 9144 18437 9169 18437 8913 18437 8913 18438 9169 18438 8914 18438 5327 18439 9175 18439 5326 18439 5326 18440 9175 18440 9170 18440 5326 18441 9170 18441 5345 18441 9182 18442 9172 18442 9171 18442 9171 18443 9172 18443 9169 18443 9171 18444 9169 18444 9173 18444 9173 18445 9169 18445 9168 18445 9173 18446 9168 18446 9174 18446 9174 18447 9168 18447 9175 18447 9174 18448 9175 18448 9176 18448 9176 18449 9175 18449 5327 18449 9180 18450 9057 18450 9177 18450 9177 18451 9057 18451 9200 18451 9177 18452 9200 18452 9178 18452 9178 18453 9200 18453 9179 18453 9178 18454 9179 18454 5280 18454 5280 18455 9179 18455 5281 18455 9004 18456 9180 18456 9147 18456 9147 18457 9180 18457 9177 18457 9147 18458 9177 18458 9181 18458 9181 18459 9177 18459 9178 18459 9181 18460 9178 18460 5277 18460 5277 18461 9178 18461 5280 18461 9186 18462 9184 18462 9182 18462 5327 18463 9183 18463 9176 18463 9176 18464 9183 18464 9187 18464 9182 18465 9171 18465 9186 18465 9186 18466 9171 18466 9173 18466 9186 18467 9173 18467 9187 18467 9187 18468 9173 18468 9174 18468 9187 18469 9174 18469 9176 18469 9054 18470 9184 18470 9193 18470 9193 18471 9184 18471 9186 18471 9193 18472 9186 18472 9185 18472 9185 18473 9186 18473 9187 18473 9185 18474 9187 18474 5330 18474 5330 18475 9187 18475 9183 18475 9185 18476 5330 18476 5331 18476 9193 18477 9185 18477 9194 18477 9054 18478 9193 18478 9188 18478 9185 18479 5331 18479 9194 18479 9194 18480 5331 18480 5332 18480 9194 18481 5332 18481 9190 18481 9054 18482 9188 18482 9055 18482 9055 18483 9188 18483 9195 18483 9055 18484 9195 18484 9077 18484 5332 18485 9189 18485 9190 18485 9190 18486 9189 18486 9191 18486 9190 18487 9191 18487 9192 18487 9192 18488 9191 18488 5284 18488 9192 18489 5284 18489 9196 18489 9196 18490 5284 18490 5281 18490 9196 18491 5281 18491 9179 18491 9193 18492 9194 18492 9188 18492 9188 18493 9194 18493 9190 18493 9188 18494 9190 18494 9195 18494 9195 18495 9190 18495 9192 18495 9195 18496 9192 18496 9198 18496 9198 18497 9192 18497 9196 18497 9198 18498 9196 18498 9199 18498 9199 18499 9196 18499 9179 18499 9199 18500 9179 18500 9200 18500 9077 18501 9195 18501 9197 18501 9197 18502 9195 18502 9198 18502 9197 18503 9198 18503 9071 18503 9071 18504 9198 18504 9199 18504 9071 18505 9199 18505 9053 18505 9053 18506 9199 18506 9200 18506 9053 18507 9200 18507 9057 18507 8967 18508 9201 18508 9202 18508 9201 18509 8969 18509 9202 18509 9202 18510 8969 18510 9228 18510 9202 18511 9228 18511 9208 18511 9208 18512 9228 18512 9203 18512 9208 18513 9203 18513 9204 18513 9204 18514 9203 18514 9205 18514 9204 18515 9205 18515 9210 18515 9210 18516 9205 18516 5373 18516 8968 18517 8967 18517 9206 18517 9206 18518 8967 18518 9202 18518 9206 18519 9202 18519 9211 18519 9211 18520 9202 18520 9208 18520 9211 18521 9208 18521 9207 18521 9207 18522 9208 18522 9204 18522 9207 18523 9204 18523 9209 18523 9209 18524 9204 18524 9210 18524 9216 18525 8968 18525 9217 18525 9217 18526 8968 18526 9206 18526 9217 18527 9206 18527 9219 18527 9219 18528 9206 18528 9211 18528 9219 18529 9211 18529 9212 18529 9212 18530 9211 18530 9207 18530 9212 18531 9207 18531 9213 18531 9213 18532 9207 18532 9209 18532 9213 18533 9214 18533 9212 18533 9212 18534 9214 18534 9215 18534 9220 18535 9216 18535 9218 18535 9218 18536 9216 18536 9217 18536 9218 18537 9217 18537 9215 18537 9215 18538 9217 18538 9219 18538 9215 18539 9219 18539 9212 18539 9233 18540 9220 18540 9231 18540 9231 18541 9220 18541 9218 18541 9231 18542 9218 18542 9230 18542 9230 18543 9218 18543 9215 18543 9230 18544 9215 18544 9221 18544 9221 18545 9215 18545 9214 18545 9222 18546 9223 18546 9229 18546 9229 18547 9223 18547 9224 18547 9229 18548 9224 18548 9225 18548 9225 18549 9224 18549 9227 18549 9225 18550 9227 18550 9226 18550 9226 18551 9227 18551 9260 18551 9226 18552 9260 18552 5372 18552 5372 18553 9260 18553 9247 18553 8969 18554 9222 18554 9228 18554 9228 18555 9222 18555 9229 18555 9228 18556 9229 18556 9203 18556 9203 18557 9229 18557 9225 18557 9203 18558 9225 18558 9205 18558 9205 18559 9225 18559 9226 18559 9205 18560 9226 18560 5373 18560 5373 18561 9226 18561 5372 18561 9230 18562 9221 18562 5428 18562 9231 18563 9230 18563 9232 18563 9233 18564 9231 18564 9234 18564 9230 18565 5428 18565 9232 18565 9232 18566 5428 18566 5398 18566 9232 18567 5398 18567 9235 18567 9235 18568 5398 18568 5397 18568 9235 18569 5397 18569 9236 18569 9231 18570 9232 18570 9234 18570 9234 18571 9232 18571 9235 18571 9234 18572 9235 18572 9238 18572 9238 18573 9235 18573 9236 18573 9238 18574 9236 18574 9240 18574 9022 18575 9021 18575 9240 18575 9240 18576 9021 18576 9237 18576 9240 18577 9237 18577 9238 18577 9238 18578 9237 18578 9023 18578 9238 18579 9023 18579 9234 18579 9234 18580 9023 18580 9032 18580 9234 18581 9032 18581 9233 18581 9242 18582 9022 18582 9239 18582 9239 18583 9022 18583 9240 18583 9239 18584 9240 18584 9245 18584 9245 18585 9240 18585 9236 18585 9245 18586 9236 18586 9241 18586 9241 18587 9236 18587 5397 18587 9000 18588 9242 18588 9243 18588 9243 18589 9242 18589 9239 18589 9243 18590 9239 18590 9268 18590 9268 18591 9239 18591 9245 18591 9268 18592 9245 18592 9244 18592 9244 18593 9245 18593 9241 18593 9246 18594 9247 18594 9260 18594 8961 18595 9249 18595 9255 18595 8964 18596 8966 18596 9250 18596 9250 18597 8966 18597 9248 18597 9250 18598 9248 18598 9252 18598 9252 18599 9248 18599 9279 18599 9252 18600 9279 18600 9264 18600 9264 18601 9279 18601 9280 18601 9249 18602 8964 18602 9255 18602 9255 18603 8964 18603 9250 18603 9255 18604 9250 18604 9251 18604 9251 18605 9250 18605 9252 18605 9251 18606 9252 18606 9263 18606 9263 18607 9252 18607 9264 18607 9253 18608 8961 18608 9254 18608 9254 18609 8961 18609 9255 18609 9254 18610 9255 18610 9258 18610 9258 18611 9255 18611 9251 18611 9258 18612 9251 18612 9256 18612 9256 18613 9251 18613 9263 18613 8959 18614 9253 18614 9257 18614 9257 18615 9253 18615 9254 18615 9257 18616 9254 18616 9259 18616 9259 18617 9254 18617 9258 18617 9259 18618 9258 18618 9261 18618 9261 18619 9258 18619 9256 18619 9246 18620 9260 18620 9262 18620 9223 18621 8959 18621 9224 18621 9224 18622 8959 18622 9257 18622 9224 18623 9257 18623 9227 18623 9227 18624 9257 18624 9259 18624 9227 18625 9259 18625 9260 18625 9260 18626 9259 18626 9261 18626 9260 18627 9261 18627 9262 18627 9262 18628 9261 18628 9256 18628 9262 18629 9256 18629 5376 18629 5376 18630 9256 18630 9263 18630 5376 18631 9263 18631 9265 18631 9265 18632 9263 18632 9264 18632 9265 18633 9264 18633 9266 18633 9266 18634 9264 18634 9280 18634 9266 18635 9280 18635 9281 18635 9267 18636 9000 18636 9270 18636 9270 18637 9000 18637 9243 18637 9270 18638 9243 18638 9271 18638 9271 18639 9243 18639 9268 18639 9271 18640 9268 18640 5394 18640 5394 18641 9268 18641 9244 18641 9001 18642 9267 18642 9285 18642 9285 18643 9267 18643 9270 18643 9285 18644 9270 18644 9269 18644 9269 18645 9270 18645 9271 18645 9269 18646 9271 18646 5393 18646 5393 18647 9271 18647 5394 18647 9272 18648 9273 18648 9310 18648 9274 18649 9272 18649 9275 18649 9275 18650 9272 18650 9310 18650 9275 18651 9310 18651 9276 18651 9276 18652 9310 18652 9312 18652 9276 18653 9312 18653 9282 18653 9282 18654 9312 18654 9278 18654 9282 18655 9278 18655 9277 18655 9277 18656 9278 18656 9314 18656 8966 18657 9274 18657 9248 18657 9248 18658 9274 18658 9275 18658 9248 18659 9275 18659 9279 18659 9279 18660 9275 18660 9276 18660 9279 18661 9276 18661 9280 18661 9280 18662 9276 18662 9282 18662 9280 18663 9282 18663 9281 18663 9281 18664 9282 18664 9277 18664 9283 18665 9284 18665 9292 18665 9269 18666 5393 18666 5392 18666 9285 18667 9269 18667 9286 18667 9001 18668 9285 18668 9299 18668 9269 18669 5392 18669 9286 18669 9286 18670 5392 18670 9287 18670 9286 18671 9287 18671 9289 18671 9289 18672 9287 18672 9288 18672 9289 18673 9288 18673 9295 18673 9295 18674 9288 18674 9290 18674 9295 18675 9290 18675 9296 18675 9296 18676 9290 18676 9291 18676 9296 18677 9291 18677 9292 18677 9292 18678 9291 18678 9293 18678 9292 18679 9293 18679 9283 18679 9285 18680 9286 18680 9299 18680 9299 18681 9286 18681 9289 18681 9299 18682 9289 18682 9294 18682 9294 18683 9289 18683 9295 18683 9294 18684 9295 18684 9302 18684 9302 18685 9295 18685 9296 18685 9302 18686 9296 18686 9303 18686 9303 18687 9296 18687 9292 18687 9303 18688 9292 18688 9297 18688 9297 18689 9292 18689 9284 18689 9297 18690 9284 18690 9298 18690 9001 18691 9299 18691 9300 18691 9300 18692 9299 18692 9294 18692 9300 18693 9294 18693 9301 18693 9301 18694 9294 18694 9302 18694 9301 18695 9302 18695 9066 18695 9066 18696 9302 18696 9303 18696 9066 18697 9303 18697 9304 18697 9304 18698 9303 18698 9297 18698 9304 18699 9297 18699 9305 18699 9305 18700 9297 18700 9298 18700 9305 18701 9298 18701 9083 18701 8929 18702 9331 18702 9311 18702 9311 18703 9331 18703 9307 18703 9311 18704 9307 18704 9306 18704 9306 18705 9307 18705 9308 18705 9306 18706 9308 18706 9313 18706 9313 18707 9308 18707 9309 18707 9313 18708 9309 18708 9315 18708 9315 18709 9309 18709 5423 18709 9273 18710 8929 18710 9310 18710 9310 18711 8929 18711 9311 18711 9310 18712 9311 18712 9312 18712 9312 18713 9311 18713 9306 18713 9312 18714 9306 18714 9278 18714 9278 18715 9306 18715 9313 18715 9278 18716 9313 18716 9314 18716 9314 18717 9313 18717 9315 18717 9319 18718 9320 18718 9083 18718 9284 18719 9283 18719 9316 18719 9298 18720 9284 18720 9318 18720 9284 18721 9316 18721 9318 18721 9318 18722 9316 18722 5409 18722 9318 18723 5409 18723 9322 18723 9322 18724 9317 18724 9318 18724 9318 18725 9317 18725 9319 18725 9318 18726 9319 18726 9298 18726 9298 18727 9319 18727 9083 18727 8931 18728 9320 18728 9324 18728 9324 18729 9320 18729 9319 18729 9324 18730 9319 18730 9321 18730 9321 18731 9319 18731 9317 18731 9323 18732 9317 18732 9328 18732 9328 18733 9317 18733 9322 18733 9328 18734 9322 18734 5444 18734 5444 18735 9322 18735 5409 18735 8983 18736 8931 18736 9326 18736 9326 18737 8931 18737 9324 18737 9326 18738 9324 18738 9323 18738 9323 18739 9324 18739 9321 18739 9323 18740 9321 18740 9317 18740 9332 18741 8983 18741 9325 18741 9325 18742 8983 18742 9326 18742 9325 18743 9326 18743 9327 18743 9327 18744 9326 18744 9323 18744 9327 18745 9323 18745 9329 18745 9329 18746 9323 18746 9328 18746 9329 18747 9328 18747 9330 18747 9330 18748 9328 18748 5444 18748 9331 18749 9332 18749 9307 18749 9307 18750 9332 18750 9325 18750 9307 18751 9325 18751 9308 18751 9308 18752 9325 18752 9327 18752 9308 18753 9327 18753 9309 18753 9309 18754 9327 18754 9329 18754 9309 18755 9329 18755 5423 18755 5423 18756 9329 18756 9330 18756 9335 18757 5117 18757 5119 18757 5903 18758 9333 18758 15025 18758 15025 18759 9334 18759 5903 18759 5903 18760 9334 18760 9335 18760 5903 18761 9335 18761 5113 18761 5113 18762 9335 18762 5119 18762 6073 18763 6074 18763 6071 18763 15130 18764 9336 18764 5918 18764 5918 18765 9336 18765 9337 18765 15154 18766 5905 18766 6073 18766 9337 18767 9336 18767 9338 18767 9338 18768 9336 18768 9340 18768 9338 18769 9340 18769 9342 18769 15144 18770 9339 18770 9340 18770 9340 18771 9339 18771 9341 18771 9340 18772 9341 18772 9342 18772 6073 18773 6071 18773 15154 18773 15154 18774 6071 18774 6069 18774 15154 18775 6069 18775 15151 18775 15151 18776 6069 18776 9344 18776 15151 18777 9344 18777 9343 18777 9343 18778 9344 18778 5904 18778 9343 18779 5904 18779 15144 18779 15144 18780 5904 18780 9345 18780 15144 18781 9345 18781 9339 18781 9346 18782 9820 18782 15145 18782 9346 18783 15145 18783 5923 18783 5923 18784 15145 18784 9831 18784 5923 18785 9831 18785 5921 18785 5827 18786 5826 18786 9347 18786 9347 18787 5826 18787 9348 18787 9348 18788 5826 18788 15189 18788 15189 18789 5826 18789 9811 18789 15189 18790 9811 18790 15194 18790 5844 18791 15213 18791 6053 18791 6053 18792 15213 18792 6054 18792 6050 18793 6049 18793 9351 18793 6054 18794 15213 18794 6057 18794 6057 18795 15213 18795 9349 18795 6057 18796 9349 18796 9355 18796 5836 18797 5835 18797 9350 18797 9350 18798 5835 18798 6052 18798 9350 18799 6052 18799 9352 18799 6052 18800 6050 18800 9352 18800 9352 18801 6050 18801 9351 18801 9352 18802 9351 18802 15225 18802 15225 18803 9351 18803 9353 18803 15225 18804 9353 18804 9354 18804 9354 18805 9353 18805 5833 18805 9354 18806 5833 18806 15223 18806 15223 18807 5833 18807 6060 18807 15223 18808 6060 18808 9349 18808 9349 18809 6060 18809 6058 18809 9349 18810 6058 18810 9355 18810 14372 18811 9356 18811 9357 18811 14372 18812 9357 18812 9358 18812 9358 18813 9357 18813 9359 18813 9358 18814 9359 18814 14374 18814 5797 18815 15268 18815 9361 18815 9361 18816 15268 18816 9360 18816 9361 18817 9360 18817 9362 18817 5796 18818 9792 18818 15279 18818 15279 18819 9363 18819 5796 18819 5796 18820 9363 18820 15263 18820 5796 18821 15263 18821 5797 18821 5797 18822 15263 18822 15269 18822 5797 18823 15269 18823 15268 18823 9364 18824 5816 18824 15799 18824 9365 18825 9368 18825 9371 18825 9364 18826 15799 18826 6033 18826 15800 18827 6037 18827 15799 18827 15799 18828 6037 18828 9366 18828 15799 18829 9366 18829 6033 18829 6028 18830 9371 18830 9367 18830 9367 18831 9371 18831 9368 18831 9367 18832 9368 18832 6031 18832 6031 18833 9368 18833 9369 18833 6031 18834 9369 18834 9370 18834 9370 18835 9369 18835 5808 18835 9371 18836 6025 18836 9365 18836 9365 18837 6025 18837 5805 18837 9365 18838 5805 18838 9372 18838 9372 18839 5805 18839 5804 18839 9372 18840 5804 18840 15800 18840 15800 18841 5804 18841 9373 18841 15800 18842 9373 18842 6037 18842 9376 18843 15306 18843 5865 18843 15333 18844 15314 18844 9374 18844 9374 18845 15314 18845 15313 18845 9374 18846 15313 18846 5863 18846 5863 18847 15313 18847 9375 18847 5863 18848 9375 18848 5865 18848 5865 18849 9375 18849 15310 18849 5865 18850 15310 18850 9376 18850 6008 18851 9377 18851 6006 18851 5874 18852 5875 18852 9380 18852 5516 18853 5514 18853 9378 18853 9378 18854 5514 18854 9382 18854 9378 18855 9382 18855 15373 18855 9386 18856 9379 18856 9387 18856 9379 18857 6013 18857 9387 18857 9387 18858 6013 18858 6011 18858 9387 18859 6011 18859 9380 18859 9380 18860 6011 18860 9381 18860 9380 18861 9381 18861 5874 18861 9382 18862 6008 18862 15373 18862 15373 18863 6008 18863 6006 18863 15373 18864 6006 18864 9383 18864 9383 18865 6006 18865 5872 18865 9383 18866 5872 18866 9384 18866 9384 18867 5872 18867 5871 18867 9384 18868 5871 18868 9385 18868 9385 18869 5871 18869 9386 18869 9385 18870 9386 18870 15357 18870 15357 18871 9386 18871 9387 18871 6002 18872 6001 18872 5999 18872 5467 18873 9389 18873 9388 18873 9388 18874 9389 18874 6002 18874 9388 18875 6002 18875 5997 18875 5997 18876 6002 18876 5999 18876 5507 18877 9390 18877 5987 18877 5496 18878 9393 18878 9391 18878 9391 18879 9393 18879 9392 18879 9392 18880 9393 18880 9394 18880 9394 18881 9393 18881 9395 18881 9394 18882 9395 18882 9396 18882 5981 18883 5980 18883 14707 18883 14707 18884 5980 18884 9397 18884 14707 18885 9397 18885 9398 18885 9398 18886 9397 18886 9399 18886 9398 18887 9399 18887 9395 18887 9395 18888 9399 18888 5994 18888 9395 18889 5994 18889 9396 18889 5509 18890 5507 18890 14697 18890 14697 18891 5507 18891 5987 18891 14697 18892 5987 18892 14707 18892 14707 18893 5987 18893 9400 18893 14707 18894 9400 18894 5981 18894 5969 18895 5966 18895 15059 18895 5972 18896 9402 18896 9401 18896 9401 18897 9402 18897 5974 18897 9401 18898 5974 18898 15087 18898 15087 18899 5974 18899 5977 18899 15087 18900 5977 18900 15074 18900 5977 18901 5890 18901 15074 18901 15074 18902 5890 18902 5887 18902 15074 18903 5887 18903 9403 18903 9403 18904 5887 18904 5964 18904 9403 18905 5964 18905 15060 18905 15060 18906 5964 18906 9404 18906 15060 18907 9404 18907 15059 18907 15059 18908 9404 18908 9405 18908 15059 18909 9405 18909 5969 18909 9845 18910 15077 18910 15072 18910 9845 18911 15072 18911 5898 18911 5898 18912 15072 18912 9406 18912 5898 18913 9406 18913 5900 18913 9411 18914 5098 18914 9410 18914 15125 18915 5091 18915 5954 18915 5927 18916 5962 18916 9408 18916 5962 18917 9407 18917 9408 18917 9408 18918 9407 18918 9409 18918 9408 18919 9409 18919 9410 18919 9410 18920 9409 18920 5956 18920 9410 18921 5956 18921 9411 18921 9408 18922 15092 18922 5927 18922 5927 18923 15092 18923 15107 18923 5927 18924 15107 18924 9412 18924 9412 18925 15107 18925 9414 18925 9412 18926 9414 18926 9413 18926 9413 18927 9414 18927 15125 18927 9413 18928 15125 18928 5949 18928 5949 18929 15125 18929 5954 18929 5949 18930 5954 18930 5953 18930 5245 18931 9415 18931 9416 18931 9416 18932 9415 18932 9418 18932 9416 18933 9418 18933 9417 18933 9417 18934 9418 18934 5617 18934 9417 18935 5617 18935 9419 18935 9419 18936 5617 18936 5229 18936 14770 18937 14764 18937 9426 18937 5624 18938 9420 18938 9424 18938 5624 18939 9424 18939 9425 18939 9421 18940 9426 18940 9422 18940 9422 18941 9426 18941 14764 18941 9422 18942 14764 18942 5653 18942 5653 18943 14764 18943 9423 18943 5653 18944 9423 18944 5630 18944 5630 18945 9423 18945 14757 18945 9428 18946 5783 18946 9424 18946 9424 18947 5783 18947 5785 18947 9424 18948 5785 18948 9425 18948 9426 18949 5619 18949 14770 18949 14770 18950 5619 18950 9427 18950 14770 18951 9427 18951 14772 18951 14772 18952 9427 18952 7202 18952 14772 18953 7202 18953 9428 18953 9428 18954 7202 18954 7200 18954 9428 18955 7200 18955 5783 18955 14781 18956 5644 18956 5641 18956 14781 18957 5641 18957 14778 18957 14778 18958 5641 18958 9745 18958 14778 18959 9745 18959 9429 18959 14818 18960 14823 18960 5580 18960 14818 18961 5580 18961 9430 18961 5580 18962 5581 18962 9430 18962 9430 18963 5581 18963 9731 18963 9430 18964 9731 18964 14812 18964 9431 18965 14864 18965 5749 18965 5749 18966 14864 18966 5750 18966 5750 18967 14864 18967 5751 18967 5751 18968 14864 18968 9432 18968 5751 18969 9432 18969 5757 18969 14835 18970 5767 18970 14854 18970 14854 18971 5767 18971 5765 18971 14854 18972 5765 18972 14853 18972 14853 18973 5765 18973 9433 18973 9433 18974 5762 18974 14853 18974 14853 18975 5762 18975 9435 18975 14853 18976 9435 18976 9434 18976 9434 18977 9435 18977 5758 18977 9434 18978 5758 18978 14856 18978 14856 18979 5758 18979 9436 18979 14856 18980 9436 18980 14859 18980 14859 18981 9436 18981 9437 18981 14859 18982 9437 18982 9432 18982 9432 18983 9437 18983 5755 18983 9432 18984 5755 18984 5757 18984 14872 18985 9438 18985 14341 18985 14872 18986 14341 18986 14857 18986 14857 18987 14341 18987 9439 18987 14857 18988 9439 18988 9440 18988 14920 18989 9445 18989 9441 18989 9441 18990 9445 18990 14912 18990 9442 18991 14892 18991 9443 18991 9442 18992 9443 18992 5570 18992 9443 18993 9444 18993 5570 18993 5570 18994 9444 18994 14909 18994 5570 18995 14909 18995 9445 18995 9445 18996 14909 18996 14911 18996 9445 18997 14911 18997 14912 18997 9446 18998 9703 18998 9702 18998 14944 18999 14960 18999 9709 18999 9709 19000 14960 19000 14962 19000 9709 19001 14962 19001 9447 19001 9447 19002 14962 19002 9448 19002 9447 19003 9448 19003 9702 19003 9702 19004 9448 19004 14964 19004 9702 19005 14964 19005 9446 19005 9452 19006 9449 19006 15011 19006 9455 19007 5703 19007 9456 19007 9456 19008 5703 19008 9450 19008 9456 19009 9450 19009 15011 19009 15011 19010 9450 19010 9451 19010 15011 19011 9451 19011 9452 19011 5706 19012 9453 19012 5707 19012 5707 19013 9453 19013 14991 19013 5707 19014 14991 19014 5709 19014 5205 19015 5204 19015 14994 19015 14994 19016 5204 19016 5713 19016 14994 19017 5713 19017 14991 19017 14991 19018 5713 19018 9454 19018 14991 19019 9454 19019 5709 19019 9455 19020 9456 19020 9457 19020 9457 19021 9456 19021 9458 19021 9457 19022 9458 19022 7158 19022 7158 19023 9458 19023 15003 19023 7158 19024 15003 19024 5706 19024 5706 19025 15003 19025 9459 19025 5706 19026 9459 19026 9453 19026 9462 19027 5549 19027 9460 19027 9460 19028 5549 19028 5533 19028 5699 19029 9461 19029 9460 19029 9460 19030 9461 19030 5696 19030 9460 19031 5696 19031 9462 19031 14735 19032 9463 19032 9467 19032 5213 19033 5211 19033 9464 19033 9464 19034 5211 19034 9465 19034 9464 19035 9465 19035 9463 19035 5223 19036 9466 19036 9473 19036 9473 19037 9466 19037 9474 19037 14735 19038 9467 19038 9474 19038 5691 19039 9467 19039 9468 19039 9468 19040 9467 19040 9463 19040 9468 19041 9463 19041 9469 19041 9469 19042 9463 19042 9465 19042 9467 19043 7143 19043 9474 19043 9474 19044 7143 19044 9470 19044 9474 19045 9470 19045 5689 19045 9471 19046 9473 19046 9472 19046 9472 19047 9473 19047 9474 19047 9472 19048 9474 19048 9475 19048 9475 19049 9474 19049 5689 19049 15414 19050 5674 19050 15415 19050 15415 19051 5674 19051 5675 19051 15415 19052 5675 19052 9479 19052 9482 19053 9476 19053 15450 19053 15450 19054 9476 19054 9477 19054 15450 19055 9477 19055 9478 19055 5675 19056 9480 19056 9479 19056 9479 19057 9480 19057 5677 19057 9479 19058 5677 19058 9481 19058 9481 19059 5677 19059 5608 19059 9481 19060 5608 19060 15435 19060 15435 19061 5608 19061 5680 19061 15435 19062 5680 19062 9482 19062 9482 19063 5680 19063 5682 19063 9482 19064 5682 19064 9476 19064 9484 19065 9483 19065 9486 19065 9484 19066 9486 19066 9485 19066 9485 19067 9486 19067 9487 19067 9485 19068 9487 19068 9763 19068 5151 19069 15400 19069 9488 19069 5151 19070 9488 19070 5658 19070 5159 19071 9489 19071 15398 19071 15398 19072 9489 19072 5670 19072 15398 19073 5670 19073 15397 19073 15397 19074 5670 19074 9490 19074 9490 19075 5666 19075 15397 19075 15397 19076 5666 19076 5663 19076 15397 19077 5663 19077 15391 19077 15391 19078 5663 19078 9491 19078 15391 19079 9491 19079 4484 19079 4484 19080 9491 19080 9492 19080 4484 19081 9492 19081 4483 19081 4483 19082 9492 19082 5659 19082 4483 19083 5659 19083 9488 19083 9488 19084 5659 19084 9493 19084 9488 19085 9493 19085 5658 19085 14677 19086 5557 19086 14687 19086 14687 19087 5557 19087 9692 19087 9494 19088 15006 19088 9495 19088 9495 19089 15006 19089 14360 19089 9495 19090 14360 19090 14362 19090 14692 19091 9851 19091 14691 19091 14691 19092 9851 19092 9496 19092 14401 19093 14400 19093 14398 19093 14398 19094 14400 19094 9771 19094 14398 19095 9771 19095 5530 19095 9589 19096 9497 19096 9498 19096 9498 19097 9497 19097 9499 19097 9498 19098 9499 19098 15810 19098 15810 19099 9499 19099 15811 19099 9500 19100 9502 19100 9501 19100 9501 19101 9502 19101 15843 19101 9591 19102 15827 19102 9503 19102 9503 19103 15827 19103 15826 19103 9503 19104 15826 19104 15868 19104 15868 19105 15826 19105 9505 19105 15868 19106 9505 19106 9504 19106 9504 19107 9505 19107 15823 19107 9504 19108 15823 19108 15861 19108 15861 19109 15823 19109 9506 19109 15861 19110 9506 19110 9507 19110 9507 19111 9506 19111 9508 19111 9509 19112 9510 19112 9508 19112 9508 19113 9510 19113 9507 19113 16044 19114 16045 19114 14573 19114 9517 19115 9512 19115 9511 19115 9511 19116 9512 19116 16063 19116 9511 19117 16063 19117 14573 19117 14573 19118 16063 19118 9513 19118 14573 19119 9513 19119 16044 19119 16098 19120 9514 19120 4684 19120 4684 19121 9514 19121 16096 19121 4684 19122 16096 19122 14604 19122 14604 19123 16096 19123 16102 19123 14604 19124 16102 19124 16100 19124 16100 19125 9515 19125 14604 19125 14604 19126 9515 19126 16099 19126 14604 19127 16099 19127 9511 19127 9511 19128 16099 19128 9516 19128 9511 19129 9516 19129 9517 19129 14544 19130 14591 19130 14561 19130 14561 19131 14591 19131 9518 19131 14561 19132 9518 19132 9519 19132 9519 19133 9518 19133 9520 19133 9519 19134 9520 19134 14560 19134 14560 19135 9520 19135 14600 19135 14560 19136 14600 19136 9521 19136 9521 19137 14600 19137 9523 19137 9521 19138 9523 19138 9522 19138 9522 19139 9523 19139 14602 19139 9522 19140 14602 19140 9511 19140 9511 19141 14602 19141 14604 19141 15901 19142 4692 19142 14591 19142 4695 19143 16450 19143 9524 19143 14544 19144 4693 19144 14591 19144 14591 19145 4693 19145 4695 19145 14591 19146 4695 19146 15901 19146 15901 19147 4695 19147 9524 19147 15901 19148 9524 19148 15902 19148 15870 19149 15874 19149 9525 19149 9525 19150 15874 19150 15885 19150 15885 19151 15884 19151 9525 19151 9525 19152 15884 19152 15886 19152 9525 19153 15886 19153 9526 19153 16024 19154 9537 19154 16022 19154 16022 19155 9537 19155 16284 19155 9528 19156 9527 19156 9562 19156 9528 19157 9562 19157 9529 19157 9530 19158 9531 19158 9536 19158 9536 19159 16139 19159 16125 19159 9532 19160 9533 19160 9568 19160 9568 19161 9533 19161 16025 19161 9534 19162 9535 19162 16740 19162 9555 19163 14649 19163 14648 19163 9531 19164 9530 19164 16230 19164 16230 19165 9530 19165 9565 19165 16230 19166 9565 19166 16228 19166 9536 19167 4626 19167 14415 19167 16024 19168 9532 19168 9537 19168 9537 19169 9532 19169 9568 19169 9537 19170 9568 19170 9538 19170 9538 19171 9568 19171 9539 19171 9538 19172 9539 19172 9540 19172 9540 19173 9539 19173 16182 19173 9540 19174 16182 19174 9541 19174 9541 19175 16182 19175 9542 19175 9541 19176 9542 19176 9544 19176 9544 19177 9542 19177 9543 19177 9544 19178 9543 19178 9551 19178 16139 19179 9536 19179 16129 19179 16129 19180 9536 19180 14415 19180 16129 19181 14415 19181 14414 19181 15921 19182 9545 19182 16289 19182 16289 19183 9545 19183 9546 19183 16289 19184 9546 19184 16284 19184 16284 19185 9546 19185 15922 19185 16284 19186 15922 19186 16022 19186 16125 19187 16122 19187 9536 19187 9536 19188 16122 19188 9547 19188 9536 19189 9547 19189 9530 19189 16122 19190 16123 19190 9547 19190 9547 19191 16123 19191 16093 19191 9547 19192 16093 19192 16412 19192 16412 19193 16093 19193 16094 19193 15897 19194 16413 19194 9548 19194 9548 19195 16413 19195 16412 19195 9548 19196 16412 19196 4681 19196 4681 19197 16412 19197 16094 19197 4681 19198 16094 19198 9549 19198 9549 19199 16094 19199 16095 19199 9549 19200 16095 19200 9550 19200 9550 19201 16095 19201 4685 19201 15918 19202 15919 19202 16289 19202 16025 19203 15932 19203 9568 19203 9568 19204 15932 19204 15936 19204 9568 19205 15936 19205 15939 19205 9543 19206 9552 19206 9551 19206 9551 19207 9552 19207 9553 19207 9551 19208 9553 19208 9554 19208 9554 19209 9553 19209 16171 19209 9554 19210 16171 19210 9562 19210 9562 19211 16171 19211 9534 19211 9562 19212 9534 19212 9529 19212 9529 19213 9534 19213 16740 19213 4497 19214 9555 19214 16683 19214 16683 19215 9555 19215 14648 19215 16683 19216 14648 19216 9558 19216 9558 19217 14648 19217 16487 19217 16487 19218 16486 19218 9558 19218 9558 19219 16486 19219 9556 19219 9558 19220 9556 19220 16484 19220 15918 19221 16289 19221 9560 19221 15919 19222 15920 19222 16289 19222 16289 19223 15920 19223 15926 19223 16289 19224 15926 19224 15921 19224 15939 19225 9557 19225 9568 19225 9568 19226 9557 19226 15941 19226 9568 19227 15941 19227 15943 19227 16484 19228 16489 19228 9558 19228 9558 19229 16489 19229 16491 19229 9558 19230 16491 19230 16228 19230 9526 19231 15886 19231 16289 19231 16289 19232 15886 19232 9559 19232 16289 19233 9559 19233 9560 19233 15943 19234 15944 19234 9568 19234 9568 19235 15944 19235 9561 19235 9568 19236 9561 19236 15947 19236 9527 19237 16704 19237 9562 19237 9562 19238 16704 19238 16703 19238 9562 19239 16703 19239 16359 19239 16359 19240 16703 19240 9563 19240 16359 19241 9563 19241 9564 19241 9564 19242 9563 19242 16701 19242 9564 19243 16701 19243 16357 19243 16357 19244 16701 19244 16680 19244 16357 19245 16680 19245 9565 19245 9565 19246 16680 19246 9566 19246 9565 19247 9566 19247 16228 19247 16228 19248 9566 19248 9567 19248 16228 19249 9567 19249 9558 19249 15947 19250 15946 19250 9568 19250 9568 19251 15946 19251 9569 19251 9568 19252 9569 19252 15949 19252 9570 19253 4648 19253 4645 19253 4645 19254 4648 19254 9568 19254 4645 19255 9568 19255 9571 19255 9571 19256 9568 19256 15949 19256 9510 19257 9509 19257 9572 19257 9572 19258 9509 19258 15844 19258 9572 19259 15844 19259 9502 19259 9502 19260 15844 19260 15843 19260 15809 19261 15808 19261 9573 19261 9581 19262 9617 19262 9608 19262 9574 19263 9575 19263 9576 19263 9576 19264 9575 19264 9577 19264 9615 19265 9578 19265 9577 19265 9577 19266 9578 19266 15855 19266 9577 19267 15855 19267 9576 19267 9581 19268 9579 19268 9617 19268 9617 19269 9579 19269 15854 19269 9617 19270 15854 19270 9615 19270 9615 19271 15854 19271 15853 19271 9615 19272 15853 19272 9578 19272 9584 19273 15860 19273 9608 19273 9608 19274 15860 19274 9580 19274 9608 19275 9580 19275 9581 19275 15812 19276 15830 19276 9609 19276 9609 19277 15830 19277 15828 19277 9609 19278 15828 19278 9582 19278 9582 19279 15828 19279 9583 19279 9582 19280 9583 19280 9584 19280 9584 19281 9583 19281 9585 19281 9584 19282 9585 19282 15860 19282 9611 19283 15815 19283 9609 19283 9609 19284 15815 19284 15813 19284 9609 19285 15813 19285 15812 19285 9573 19286 15808 19286 9586 19286 15808 19287 9587 19287 9586 19287 9586 19288 9587 19288 15817 19288 9586 19289 15817 19289 9611 19289 9611 19290 15817 19290 15816 19290 9611 19291 15816 19291 15815 19291 9574 19292 9588 19292 9575 19292 9575 19293 9588 19293 9589 19293 9575 19294 9589 19294 9590 19294 9590 19295 9589 19295 9498 19295 9590 19296 9498 19296 9573 19296 9573 19297 9498 19297 15810 19297 9573 19298 15810 19298 15809 19298 9583 19299 15827 19299 9585 19299 9585 19300 15827 19300 9591 19300 9585 19301 9591 19301 15860 19301 9607 19302 9592 19302 9593 19302 9593 19303 9592 19303 9594 19303 9593 19304 9594 19304 9595 19304 9595 19305 9594 19305 9618 19305 9595 19306 9618 19306 9596 19306 9596 19307 9618 19307 9620 19307 9596 19308 9620 19308 9597 19308 9597 19309 9620 19309 9621 19309 9597 19310 9621 19310 9677 19310 9677 19311 9621 19311 9623 19311 9677 19312 9623 19312 9598 19312 9598 19313 9623 19313 9600 19313 9598 19314 9600 19314 9599 19314 9599 19315 9600 19315 9601 19315 9599 19316 9601 19316 9679 19316 9679 19317 9601 19317 9626 19317 9679 19318 9626 19318 9602 19318 9602 19319 9626 19319 9603 19319 9602 19320 9603 19320 9680 19320 9680 19321 9603 19321 9605 19321 9680 19322 9605 19322 9604 19322 9604 19323 9605 19323 9606 19323 9604 19324 9606 19324 9607 19324 9607 19325 9606 19325 9592 19325 9608 19326 9653 19326 9584 19326 9584 19327 9653 19327 9652 19327 9584 19328 9652 19328 9582 19328 9582 19329 9652 19329 9610 19329 9582 19330 9610 19330 9609 19330 9609 19331 9610 19331 9650 19331 9609 19332 9650 19332 9611 19332 9611 19333 9650 19333 9612 19333 9611 19334 9612 19334 9586 19334 9586 19335 9612 19335 9648 19335 9586 19336 9648 19336 9573 19336 9573 19337 9648 19337 9646 19337 9573 19338 9646 19338 9590 19338 9590 19339 9646 19339 9644 19339 9590 19340 9644 19340 9575 19340 9575 19341 9644 19341 9613 19341 9575 19342 9613 19342 9577 19342 9577 19343 9613 19343 9614 19343 9577 19344 9614 19344 9615 19344 9615 19345 9614 19345 9616 19345 9615 19346 9616 19346 9617 19346 9617 19347 9616 19347 9640 19347 9617 19348 9640 19348 9608 19348 9608 19349 9640 19349 9653 19349 9594 19350 9639 19350 9618 19350 9618 19351 9639 19351 9619 19351 9618 19352 9619 19352 9620 19352 9620 19353 9619 19353 9632 19353 9620 19354 9632 19354 9621 19354 9621 19355 9632 19355 9622 19355 9621 19356 9622 19356 9623 19356 9623 19357 9622 19357 9624 19357 9623 19358 9624 19358 9600 19358 9600 19359 9624 19359 9625 19359 9600 19360 9625 19360 9601 19360 9601 19361 9625 19361 9634 19361 9601 19362 9634 19362 9626 19362 9626 19363 9634 19363 9627 19363 9626 19364 9627 19364 9603 19364 9603 19365 9627 19365 9635 19365 9603 19366 9635 19366 9605 19366 9605 19367 9635 19367 9637 19367 9605 19368 9637 19368 9606 19368 9606 19369 9637 19369 9628 19369 9606 19370 9628 19370 9592 19370 9592 19371 9628 19371 9629 19371 9592 19372 9629 19372 9594 19372 9594 19373 9629 19373 9639 19373 9639 19374 9630 19374 9619 19374 9619 19375 9630 19375 9631 19375 9619 19376 9631 19376 9632 19376 9632 19377 9631 19377 9641 19377 9632 19378 9641 19378 9622 19378 9622 19379 9641 19379 9633 19379 9622 19380 9633 19380 9624 19380 9624 19381 9633 19381 9642 19381 9624 19382 9642 19382 9625 19382 9625 19383 9642 19383 9643 19383 9625 19384 9643 19384 9634 19384 9634 19385 9643 19385 9645 19385 9634 19386 9645 19386 9627 19386 9627 19387 9645 19387 9647 19387 9627 19388 9647 19388 9635 19388 9635 19389 9647 19389 9636 19389 9635 19390 9636 19390 9637 19390 9637 19391 9636 19391 9649 19391 9637 19392 9649 19392 9628 19392 9628 19393 9649 19393 9651 19393 9628 19394 9651 19394 9629 19394 9629 19395 9651 19395 9638 19395 9629 19396 9638 19396 9639 19396 9639 19397 9638 19397 9630 19397 9630 19398 9653 19398 9631 19398 9631 19399 9653 19399 9640 19399 9631 19400 9640 19400 9641 19400 9641 19401 9640 19401 9616 19401 9641 19402 9616 19402 9633 19402 9633 19403 9616 19403 9614 19403 9633 19404 9614 19404 9642 19404 9642 19405 9614 19405 9613 19405 9642 19406 9613 19406 9643 19406 9643 19407 9613 19407 9644 19407 9643 19408 9644 19408 9645 19408 9645 19409 9644 19409 9646 19409 9645 19410 9646 19410 9647 19410 9647 19411 9646 19411 9648 19411 9647 19412 9648 19412 9636 19412 9636 19413 9648 19413 9612 19413 9636 19414 9612 19414 9649 19414 9649 19415 9612 19415 9650 19415 9649 19416 9650 19416 9651 19416 9651 19417 9650 19417 9610 19417 9651 19418 9610 19418 9638 19418 9638 19419 9610 19419 9652 19419 9638 19420 9652 19420 9630 19420 9630 19421 9652 19421 9653 19421 9658 19422 9659 19422 6078 19422 6078 19423 9659 19423 9660 19423 6078 19424 9660 19424 9654 19424 9654 19425 9660 19425 9662 19425 9654 19426 9662 19426 6114 19426 6114 19427 9662 19427 9663 19427 6114 19428 9663 19428 6087 19428 6087 19429 9663 19429 9655 19429 6087 19430 9655 19430 6086 19430 6086 19431 9655 19431 9666 19431 6086 19432 9666 19432 6084 19432 6084 19433 9666 19433 9667 19433 6084 19434 9667 19434 6082 19434 6082 19435 9667 19435 9669 19435 6082 19436 9669 19436 6080 19436 6080 19437 9669 19437 9672 19437 6080 19438 9672 19438 6075 19438 6075 19439 9672 19439 9656 19439 6075 19440 9656 19440 6076 19440 6076 19441 9656 19441 9674 19441 6076 19442 9674 19442 6093 19442 6093 19443 9674 19443 9657 19443 6093 19444 9657 19444 9658 19444 9658 19445 9657 19445 9659 19445 9657 19446 9675 19446 9659 19446 9659 19447 9675 19447 9661 19447 9659 19448 9661 19448 9660 19448 9660 19449 9661 19449 9676 19449 9660 19450 9676 19450 9662 19450 9662 19451 9676 19451 9664 19451 9662 19452 9664 19452 9663 19452 9663 19453 9664 19453 9665 19453 9663 19454 9665 19454 9655 19454 9655 19455 9665 19455 9678 19455 9655 19456 9678 19456 9666 19456 9666 19457 9678 19457 9668 19457 9666 19458 9668 19458 9667 19458 9667 19459 9668 19459 9670 19459 9667 19460 9670 19460 9669 19460 9669 19461 9670 19461 9671 19461 9669 19462 9671 19462 9672 19462 9672 19463 9671 19463 9681 19463 9672 19464 9681 19464 9656 19464 9656 19465 9681 19465 9673 19465 9656 19466 9673 19466 9674 19466 9674 19467 9673 19467 9682 19467 9674 19468 9682 19468 9657 19468 9657 19469 9682 19469 9675 19469 9682 19470 9593 19470 9675 19470 9675 19471 9593 19471 9595 19471 9675 19472 9595 19472 9661 19472 9661 19473 9595 19473 9596 19473 9661 19474 9596 19474 9676 19474 9676 19475 9596 19475 9597 19475 9676 19476 9597 19476 9664 19476 9664 19477 9597 19477 9677 19477 9664 19478 9677 19478 9665 19478 9665 19479 9677 19479 9598 19479 9665 19480 9598 19480 9678 19480 9678 19481 9598 19481 9599 19481 9678 19482 9599 19482 9668 19482 9668 19483 9599 19483 9679 19483 9668 19484 9679 19484 9670 19484 9670 19485 9679 19485 9602 19485 9670 19486 9602 19486 9671 19486 9671 19487 9602 19487 9680 19487 9671 19488 9680 19488 9681 19488 9681 19489 9680 19489 9604 19489 9681 19490 9604 19490 9673 19490 9673 19491 9604 19491 9607 19491 9673 19492 9607 19492 9682 19492 9682 19493 9607 19493 9593 19493 4763 19494 4760 19494 14730 19494 4763 19495 14730 19495 4575 19495 4575 19496 14730 19496 14726 19496 4575 19497 14726 19497 9683 19497 9683 19498 14726 19498 9684 19498 9683 19499 9684 19499 9685 19499 9685 19500 9684 19500 5225 19500 9685 19501 5225 19501 4574 19501 4762 19502 9686 19502 4561 19502 4762 19503 4561 19503 9687 19503 9687 19504 4561 19504 4560 19504 9687 19505 4560 19505 14739 19505 14739 19506 4560 19506 9688 19506 14739 19507 9688 19507 9689 19507 9689 19508 9688 19508 4559 19508 9689 19509 4559 19509 14743 19509 14743 19510 4559 19510 5217 19510 14743 19511 5217 19511 9690 19511 5557 19512 14677 19512 14676 19512 5557 19513 14676 19513 9691 19513 9691 19514 14676 19514 5545 19514 9691 19515 5545 19515 5554 19515 14687 19516 9692 19516 14688 19516 14688 19517 9692 19517 5558 19517 14688 19518 5558 19518 5534 19518 5534 19519 5558 19519 9693 19519 14360 19520 15006 19520 9694 19520 14360 19521 9694 19521 14359 19521 14359 19522 9694 19522 15017 19522 14359 19523 15017 19523 9695 19523 9695 19524 15017 19524 15012 19524 9695 19525 15012 19525 14354 19525 14354 19526 15012 19526 15007 19526 14354 19527 15007 19527 14355 19527 14355 19528 15007 19528 5201 19528 14355 19529 5201 19529 14361 19529 5531 19530 14351 19530 9696 19530 5532 19531 5531 19531 14988 19531 14988 19532 5531 19532 9696 19532 14988 19533 9696 19533 9697 19533 9697 19534 9696 19534 14356 19534 9697 19535 14356 19535 14984 19535 14984 19536 14356 19536 9698 19536 14984 19537 9698 19537 14995 19537 14995 19538 9698 19538 9699 19538 14995 19539 9699 19539 9700 19539 9700 19540 9699 19540 5203 19540 14974 19541 9701 19541 9708 19541 9702 19542 9703 19542 9704 19542 9704 19543 9703 19543 9705 19543 9704 19544 9705 19544 14967 19544 14967 19545 9706 19545 9704 19545 9704 19546 9706 19546 9707 19546 9704 19547 9707 19547 9708 19547 9708 19548 9707 19548 14976 19548 9708 19549 14976 19549 14974 19549 14944 19550 9709 19550 14945 19550 14945 19551 9709 19551 9711 19551 14945 19552 9711 19552 14942 19552 14936 19553 14937 19553 5598 19553 5598 19554 14937 19554 9710 19554 5598 19555 9710 19555 9711 19555 9711 19556 9710 19556 14939 19556 9711 19557 14939 19557 14942 19557 14919 19558 9712 19558 9713 19558 9713 19559 9712 19559 14918 19559 9713 19560 14918 19560 5564 19560 9713 19561 5568 19561 14919 19561 14919 19562 5568 19562 9445 19562 14919 19563 9445 19563 14920 19563 14892 19564 9442 19564 9715 19564 9715 19565 9442 19565 9714 19565 9715 19566 9714 19566 14888 19566 14880 19567 9716 19567 5571 19567 5571 19568 9716 19568 9717 19568 5571 19569 9717 19569 9714 19569 9714 19570 9717 19570 14886 19570 9714 19571 14886 19571 14888 19571 9438 19572 14872 19572 14871 19572 9718 19573 9719 19573 9438 19573 9438 19574 14871 19574 9718 19574 9718 19575 14871 19575 9720 19575 9718 19576 9720 19576 14349 19576 14349 19577 9720 19577 9721 19577 14349 19578 9721 19578 9722 19578 9722 19579 9721 19579 9723 19579 9722 19580 9723 19580 14350 19580 14350 19581 9723 19581 5176 19581 14350 19582 5176 19582 5174 19582 14346 19583 9724 19583 14836 19583 9725 19584 9440 19584 9439 19584 14346 19585 14836 19585 9726 19585 9726 19586 14836 19586 14832 19586 9726 19587 14832 19587 14345 19587 14345 19588 14832 19588 14850 19588 14345 19589 14850 19589 9727 19589 9727 19590 14850 19590 9725 19590 9727 19591 9725 19591 14343 19591 14343 19592 9725 19592 9439 19592 14343 19593 9439 19593 14347 19593 9730 19594 5579 19594 9729 19594 9728 19595 5580 19595 14823 19595 14823 19596 14822 19596 9728 19596 9728 19597 14822 19597 14828 19597 9728 19598 14828 19598 9729 19598 9729 19599 14828 19599 14827 19599 9729 19600 14827 19600 9730 19600 14812 19601 9731 19601 14809 19601 14809 19602 9731 19602 9732 19602 14809 19603 9732 19603 14808 19603 14808 19604 9732 19604 9733 19604 9734 19605 9735 19605 14793 19605 14793 19606 9735 19606 14792 19606 9734 19607 14791 19607 9735 19607 9735 19608 14791 19608 9736 19608 9735 19609 9736 19609 9733 19609 9733 19610 9736 19610 14807 19610 9733 19611 14807 19611 14808 19611 5644 19612 14781 19612 14780 19612 5644 19613 14780 19613 9737 19613 9737 19614 14780 19614 9738 19614 9737 19615 9738 19615 5643 19615 5643 19616 9738 19616 9739 19616 5643 19617 9739 19617 9740 19617 9740 19618 9739 19618 5625 19618 9740 19619 5625 19619 5645 19619 5635 19620 9741 19620 5642 19620 5642 19621 9741 19621 14766 19621 5642 19622 14766 19622 9742 19622 9742 19623 14766 19623 9743 19623 9742 19624 9743 19624 5638 19624 5638 19625 9743 19625 9744 19625 5638 19626 9744 19626 5639 19626 5639 19627 9744 19627 14761 19627 5639 19628 14761 19628 9745 19628 9745 19629 14761 19629 9429 19629 5173 19630 5172 19630 15405 19630 5173 19631 15405 19631 4800 19631 4800 19632 15405 19632 4797 19632 4797 19633 15405 19633 15403 19633 4797 19634 15403 19634 9746 19634 9746 19635 15403 19635 9747 19635 9746 19636 9747 19636 9748 19636 9748 19637 9747 19637 5152 19637 9748 19638 5152 19638 4794 19638 4803 19639 5158 19639 9751 19639 15388 19640 15386 19640 9749 19640 4803 19641 9751 19641 9750 19641 9750 19642 9751 19642 15381 19642 9750 19643 15381 19643 9752 19643 9752 19644 15381 19644 9753 19644 9752 19645 9753 19645 4801 19645 4801 19646 9753 19646 15388 19646 4801 19647 15388 19647 4802 19647 4802 19648 15388 19648 9749 19648 4802 19649 9749 19649 9754 19649 9483 19650 9484 19650 9755 19650 9755 19651 9484 19651 15447 19651 9755 19652 15447 19652 9756 19652 9756 19653 15447 19653 15442 19653 9756 19654 15442 19654 9757 19654 9757 19655 15442 19655 9758 19655 9757 19656 9758 19656 5616 19656 5616 19657 9758 19657 9759 19657 7199 19658 15417 19658 9760 19658 7199 19659 9760 19659 9761 19659 9761 19660 9760 19660 15420 19660 9761 19661 15420 19661 5615 19661 5615 19662 15420 19662 15411 19662 5615 19663 15411 19663 9762 19663 9762 19664 15411 19664 15432 19664 9762 19665 15432 19665 5614 19665 5614 19666 15432 19666 9763 19666 5614 19667 9763 19667 9487 19667 5262 19668 15472 19668 9766 19668 5262 19669 9766 19669 4577 19669 15474 19670 9764 19670 15476 19670 15476 19671 9764 19671 9765 19671 15476 19672 9765 19672 9766 19672 9766 19673 9765 19673 9767 19673 9766 19674 9767 19674 4577 19674 4582 19675 9768 19675 15452 19675 9769 19676 15461 19676 14368 19676 4582 19677 15452 19677 4578 19677 4578 19678 15452 19678 15456 19678 4578 19679 15456 19679 9770 19679 9770 19680 15456 19680 9769 19680 9770 19681 9769 19681 4579 19681 4579 19682 9769 19682 14368 19682 4579 19683 14368 19683 4580 19683 9771 19684 14400 19684 14409 19684 9771 19685 14409 19685 9772 19685 9772 19686 14409 19686 14408 19686 9772 19687 14408 19687 15372 19687 15372 19688 14408 19688 9774 19688 15372 19689 9774 19689 9773 19689 9773 19690 9774 19690 9775 19690 9773 19691 9775 19691 9776 19691 9776 19692 9775 19692 5521 19692 9776 19693 5521 19693 5522 19693 9781 19694 15359 19694 9782 19694 14404 19695 15356 19695 14405 19695 14405 19696 15356 19696 15355 19696 14405 19697 15355 19697 9777 19697 9777 19698 15355 19698 9778 19698 9777 19699 9778 19699 9779 19699 9779 19700 9778 19700 5879 19700 9779 19701 5879 19701 9780 19701 14406 19702 9781 19702 14404 19702 14404 19703 9781 19703 9782 19703 14404 19704 9782 19704 15356 19704 15333 19705 9374 19705 9783 19705 9783 19706 9374 19706 9784 19706 9783 19707 9784 19707 15330 19707 15330 19708 9784 19708 15342 19708 5860 19709 9785 19709 5853 19709 5853 19710 9785 19710 9786 19710 5853 19711 9786 19711 9784 19711 9784 19712 9786 19712 9787 19712 9784 19713 9787 19713 15342 19713 9791 19714 5851 19714 5847 19714 5865 19715 15306 19715 9789 19715 9789 19716 15306 19716 15304 19716 15304 19717 9788 19717 9789 19717 9789 19718 9788 19718 15292 19718 9789 19719 15292 19719 5847 19719 5847 19720 15292 19720 9790 19720 5847 19721 9790 19721 9791 19721 9792 19722 5796 19722 9794 19722 15284 19723 15288 19723 5799 19723 5799 19724 15288 19724 9793 19724 5799 19725 9793 19725 9794 19725 9794 19726 9793 19726 15290 19726 9794 19727 15290 19727 9792 19727 9795 19728 5791 19728 5789 19728 9361 19729 9362 19729 9798 19729 9798 19730 9362 19730 9796 19730 9796 19731 15253 19731 9798 19731 9798 19732 15253 19732 9797 19732 9798 19733 9797 19733 5789 19733 5789 19734 9797 19734 9799 19734 5789 19735 9799 19735 9795 19735 14372 19736 14381 19736 9800 19736 15241 19737 9356 19737 14372 19737 14372 19738 9800 19738 15241 19738 15241 19739 9800 19739 9801 19739 15241 19740 9801 19740 15239 19740 15239 19741 9801 19741 14380 19741 15239 19742 14380 19742 15233 19742 15233 19743 14380 19743 14382 19743 15233 19744 14382 19744 9802 19744 9802 19745 14382 19745 9803 19745 9802 19746 9803 19746 9804 19746 14374 19747 9359 19747 9809 19747 9805 19748 14375 19748 14376 19748 9805 19749 14376 19749 15217 19749 15217 19750 14376 19750 9806 19750 15217 19751 9806 19751 15219 19751 15219 19752 9806 19752 9807 19752 15219 19753 9807 19753 15220 19753 15220 19754 9807 19754 9808 19754 15220 19755 9808 19755 9809 19755 9809 19756 9808 19756 9810 19756 9809 19757 9810 19757 14374 19757 15194 19758 9811 19758 15197 19758 15197 19759 9811 19759 9812 19759 15200 19760 15203 19760 5831 19760 5831 19761 15203 19761 9813 19761 5831 19762 9813 19762 9812 19762 9812 19763 9813 19763 9814 19763 9812 19764 9814 19764 15197 19764 9819 19765 9816 19765 9815 19765 9815 19766 9816 19766 15168 19766 15168 19767 15165 19767 9815 19767 9815 19768 15165 19768 9817 19768 9815 19769 9817 19769 9818 19769 9815 19770 5829 19770 9819 19770 9819 19771 5829 19771 5828 19771 9819 19772 5828 19772 15171 19772 5827 19773 9347 19773 5828 19773 5828 19774 9347 19774 15172 19774 5828 19775 15172 19775 15171 19775 9820 19776 9346 19776 5925 19776 9820 19777 5925 19777 9821 19777 9821 19778 5925 19778 9822 19778 9821 19779 9822 19779 15160 19779 15160 19780 9822 19780 9824 19780 15160 19781 9824 19781 9823 19781 9823 19782 9824 19782 9825 19782 9823 19783 9825 19783 5914 19783 9826 19784 5919 19784 9827 19784 9826 19785 9827 19785 15129 19785 15129 19786 9827 19786 9828 19786 15129 19787 9828 19787 15140 19787 15140 19788 9828 19788 5926 19788 15140 19789 5926 19789 15141 19789 15141 19790 5926 19790 9829 19790 15141 19791 9829 19791 9830 19791 9830 19792 9829 19792 5921 19792 9830 19793 5921 19793 9831 19793 14371 19794 9832 19794 9833 19794 9834 19795 5112 19795 14371 19795 14371 19796 9833 19796 9834 19796 9834 19797 9833 19797 9835 19797 9834 19798 9835 19798 9836 19798 9836 19799 9835 19799 9837 19799 9836 19800 9837 19800 9838 19800 9838 19801 9837 19801 9839 19801 9838 19802 9839 19802 5089 19802 9843 19803 9840 19803 15105 19803 9844 19804 15104 19804 4811 19804 4811 19805 15104 19805 9841 19805 4811 19806 9841 19806 4812 19806 4812 19807 9841 19807 15091 19807 4812 19808 15091 19808 4813 19808 4813 19809 15091 19809 9842 19809 4813 19810 9842 19810 4815 19810 4814 19811 9843 19811 9844 19811 9844 19812 9843 19812 15105 19812 9844 19813 15105 19813 15104 19813 15077 19814 9845 19814 5895 19814 15077 19815 5895 19815 15088 19815 15088 19816 5895 19816 9846 19816 15088 19817 9846 19817 15084 19817 15084 19818 9846 19818 9847 19818 15084 19819 9847 19819 9848 19819 9848 19820 9847 19820 5899 19820 9848 19821 5899 19821 5884 19821 14691 19822 9496 19822 9849 19822 9849 19823 9496 19823 5485 19823 9849 19824 5485 19824 9850 19824 9850 19825 5485 19825 5484 19825 9851 19826 14692 19826 9852 19826 9851 19827 9852 19827 9853 19827 9853 19828 9852 19828 14694 19828 9853 19829 14694 19829 5475 19829 4766 19830 9855 19830 9854 19830 9854 19831 9855 19831 4595 19831 9854 19832 4595 19832 9856 19832 9856 19833 4595 19833 4594 19833 9856 19834 4594 19834 14700 19834 14700 19835 4594 19835 9857 19835 14700 19836 9857 19836 5506 19836 5506 19837 9857 19837 4589 19837 4764 19838 9858 19838 9859 19838 4764 19839 9859 19839 4590 19839 4590 19840 9859 19840 9860 19840 4590 19841 9860 19841 4591 19841 4591 19842 9860 19842 9861 19842 4591 19843 9861 19843 9862 19843 9862 19844 9861 19844 9863 19844 9862 19845 9863 19845 4593 19845 4593 19846 9863 19846 5497 19846 4593 19847 5497 19847 4598 19847 15055 19848 5892 19848 5893 19848 15055 19849 5893 19849 15056 19849 15056 19850 5893 19850 9864 19850 15056 19851 9864 19851 15067 19851 15067 19852 9864 19852 5901 19852 15067 19853 5901 19853 15068 19853 15068 19854 5901 19854 9865 19854 15068 19855 9865 19855 9866 19855 9866 19856 9865 19856 5900 19856 9866 19857 5900 19857 9406 19857 9867 19858 15052 19858 15053 19858 14410 19859 9867 19859 14412 19859 14412 19860 9867 19860 15053 19860 14412 19861 15053 19861 5146 19861 15052 19862 9867 19862 9868 19862 9868 19863 9867 19863 4607 19863 9868 19864 4607 19864 15051 19864 15051 19865 4607 19865 9869 19865 9869 19866 4607 19866 5124 19866 9869 19867 5124 19867 15049 19867 5149 19868 5148 19868 15035 19868 5133 19869 9870 19869 4610 19869 5133 19870 4610 19870 15026 19870 15026 19871 4610 19871 9871 19871 15026 19872 9871 19872 15034 19872 15034 19873 9871 19873 9872 19873 15034 19874 9872 19874 15035 19874 15035 19875 9872 19875 4600 19875 15035 19876 4600 19876 5149 19876 9875 19877 9874 19877 9884 19877 9878 19878 6911 19878 9873 19878 9874 19879 9878 19879 9879 19879 9875 19880 9884 19880 9876 19880 9930 19881 9876 19881 9889 19881 9877 19882 9930 19882 9903 19882 9878 19883 9873 19883 9879 19883 9879 19884 9873 19884 9880 19884 9879 19885 9880 19885 9881 19885 9881 19886 9880 19886 6912 19886 9881 19887 6912 19887 9886 19887 9886 19888 6912 19888 6914 19888 9886 19889 6914 19889 9887 19889 9887 19890 6914 19890 9882 19890 9887 19891 9882 19891 9883 19891 9874 19892 9879 19892 9884 19892 9884 19893 9879 19893 9881 19893 9884 19894 9881 19894 9885 19894 9885 19895 9881 19895 9886 19895 9885 19896 9886 19896 9890 19896 9890 19897 9886 19897 9887 19897 9890 19898 9887 19898 9888 19898 9888 19899 9887 19899 9883 19899 9888 19900 9883 19900 9893 19900 9876 19901 9884 19901 9889 19901 9889 19902 9884 19902 9885 19902 9889 19903 9885 19903 9891 19903 9891 19904 9885 19904 9890 19904 9891 19905 9890 19905 9895 19905 9895 19906 9890 19906 9888 19906 9895 19907 9888 19907 9892 19907 9892 19908 9888 19908 9893 19908 9892 19909 9893 19909 9907 19909 9930 19910 9889 19910 9903 19910 9903 19911 9889 19911 9891 19911 9903 19912 9891 19912 9894 19912 9894 19913 9891 19913 9895 19913 9894 19914 9895 19914 9900 19914 9900 19915 9895 19915 9892 19915 9900 19916 9892 19916 9896 19916 9896 19917 9892 19917 9907 19917 9896 19918 9907 19918 9899 19918 9897 19919 9898 19919 9899 19919 9899 19920 9898 19920 5692 19920 9899 19921 5692 19921 9896 19921 9896 19922 5692 19922 9901 19922 9896 19923 9901 19923 9900 19923 9900 19924 9901 19924 5693 19924 9900 19925 5693 19925 9894 19925 9894 19926 5693 19926 9902 19926 9894 19927 9902 19927 9903 19927 9903 19928 9902 19928 5694 19928 9903 19929 5694 19929 9877 19929 9904 19930 9897 19930 9905 19930 9905 19931 9897 19931 9899 19931 9905 19932 9899 19932 9906 19932 9906 19933 9899 19933 9907 19933 9906 19934 9907 19934 9908 19934 9908 19935 9907 19935 9893 19935 9908 19936 9893 19936 9909 19936 9909 19937 9893 19937 9883 19937 9909 19938 9883 19938 9910 19938 9910 19939 9883 19939 9882 19939 7145 19940 9904 19940 9911 19940 9911 19941 9904 19941 9905 19941 9911 19942 9905 19942 9912 19942 9912 19943 9905 19943 9906 19943 9912 19944 9906 19944 9923 19944 9923 19945 9906 19945 9908 19945 9923 19946 9908 19946 9913 19946 9913 19947 9908 19947 9909 19947 9913 19948 9909 19948 9914 19948 9914 19949 9909 19949 9910 19949 7142 19950 7144 19950 9917 19950 9916 19951 9915 19951 7142 19951 7142 19952 9917 19952 9916 19952 9916 19953 9917 19953 9921 19953 9916 19954 9921 19954 9918 19954 9918 19955 9921 19955 9922 19955 9918 19956 9922 19956 9919 19956 9919 19957 9922 19957 9924 19957 9919 19958 9924 19958 9932 19958 9932 19959 9924 19959 9920 19959 9932 19960 9920 19960 6915 19960 7144 19961 7145 19961 9917 19961 9917 19962 7145 19962 9911 19962 9917 19963 9911 19963 9921 19963 9921 19964 9911 19964 9912 19964 9921 19965 9912 19965 9922 19965 9922 19966 9912 19966 9923 19966 9922 19967 9923 19967 9924 19967 9924 19968 9923 19968 9913 19968 9924 19969 9913 19969 9920 19969 9920 19970 9913 19970 9914 19970 9929 19971 9928 19971 9931 19971 9944 19972 9946 19972 9927 19972 9927 19973 9946 19973 9947 19973 9929 19974 9931 19974 9925 19974 9925 19975 9931 19975 5212 19975 9925 19976 5212 19976 9941 19976 9947 19977 9926 19977 9927 19977 9927 19978 9926 19978 6911 19978 9927 19979 6911 19979 9878 19979 9878 19980 9874 19980 9927 19980 9927 19981 9874 19981 9928 19981 9927 19982 9928 19982 9944 19982 9944 19983 9928 19983 9929 19983 9877 19984 5212 19984 9930 19984 9930 19985 5212 19985 9931 19985 9930 19986 9931 19986 9876 19986 9876 19987 9931 19987 9928 19987 9876 19988 9928 19988 9875 19988 9875 19989 9928 19989 9874 19989 7141 19990 9915 19990 9933 19990 9933 19991 9915 19991 9916 19991 9933 19992 9916 19992 9935 19992 9935 19993 9916 19993 9918 19993 9935 19994 9918 19994 9936 19994 9936 19995 9918 19995 9919 19995 9936 19996 9919 19996 9939 19996 9939 19997 9919 19997 9932 19997 9939 19998 9932 19998 5368 19998 5368 19999 9932 19999 6915 19999 9959 20000 7141 20000 9956 20000 9956 20001 7141 20001 9933 20001 9956 20002 9933 20002 9934 20002 9934 20003 9933 20003 9935 20003 9934 20004 9935 20004 9955 20004 9955 20005 9935 20005 9936 20005 9955 20006 9936 20006 9937 20006 9937 20007 9936 20007 9939 20007 9937 20008 9939 20008 9938 20008 9938 20009 9939 20009 5368 20009 9943 20010 9925 20010 9940 20010 9940 20011 9925 20011 9941 20011 9940 20012 9941 20012 9942 20012 9946 20013 9944 20013 9943 20013 9943 20014 9944 20014 9929 20014 9943 20015 9929 20015 9925 20015 9943 20016 9945 20016 9946 20016 9946 20017 9945 20017 9949 20017 9946 20018 9949 20018 9947 20018 9952 20019 9949 20019 9948 20019 9948 20020 9949 20020 9945 20020 9948 20021 9945 20021 9950 20021 9950 20022 9945 20022 9943 20022 9950 20023 9943 20023 9951 20023 9951 20024 9943 20024 9940 20024 9951 20025 9940 20025 5218 20025 5218 20026 9940 20026 9942 20026 10011 20027 9952 20027 10010 20027 10010 20028 9952 20028 9948 20028 10010 20029 9948 20029 9953 20029 9953 20030 9948 20030 9950 20030 9953 20031 9950 20031 9954 20031 9954 20032 9950 20032 9951 20032 9954 20033 9951 20033 10009 20033 10009 20034 9951 20034 5218 20034 9937 20035 9984 20035 9955 20035 9955 20036 9984 20036 9966 20036 9955 20037 9966 20037 9934 20037 9934 20038 9966 20038 9970 20038 9934 20039 9970 20039 9956 20039 9956 20040 9970 20040 9957 20040 9956 20041 9957 20041 9959 20041 9972 20042 5690 20042 9957 20042 9957 20043 5690 20043 9958 20043 9957 20044 9958 20044 9959 20044 9967 20045 9983 20045 9968 20045 9968 20046 9983 20046 9961 20046 9968 20047 9961 20047 9969 20047 9969 20048 9961 20048 9962 20048 9969 20049 9962 20049 9960 20049 9960 20050 9962 20050 9971 20050 9983 20051 9980 20051 9961 20051 9961 20052 9980 20052 9963 20052 9961 20053 9963 20053 9962 20053 9962 20054 9963 20054 9964 20054 9962 20055 9964 20055 9971 20055 9971 20056 9964 20056 9974 20056 9980 20057 9979 20057 9963 20057 9963 20058 9979 20058 9978 20058 9963 20059 9978 20059 9964 20059 9964 20060 9978 20060 9965 20060 9964 20061 9965 20061 9974 20061 9974 20062 9965 20062 9977 20062 9984 20063 9967 20063 9966 20063 9966 20064 9967 20064 9968 20064 9966 20065 9968 20065 9970 20065 9970 20066 9968 20066 9969 20066 9970 20067 9969 20067 9957 20067 9957 20068 9969 20068 9960 20068 9957 20069 9960 20069 9972 20069 9972 20070 9960 20070 9971 20070 9972 20071 9971 20071 9973 20071 9973 20072 9971 20072 9974 20072 9973 20073 9974 20073 9975 20073 9975 20074 9974 20074 9977 20074 9975 20075 9977 20075 5687 20075 5687 20076 9977 20076 5688 20076 9976 20077 5688 20077 9986 20077 9986 20078 5688 20078 9977 20078 9986 20079 9977 20079 9988 20079 9988 20080 9977 20080 9965 20080 9988 20081 9965 20081 9989 20081 9989 20082 9965 20082 9978 20082 9989 20083 9978 20083 9992 20083 9992 20084 9978 20084 9979 20084 9993 20085 9992 20085 5370 20085 5370 20086 9992 20086 9979 20086 5370 20087 9979 20087 9981 20087 9981 20088 9979 20088 9980 20088 9981 20089 9980 20089 9982 20089 9982 20090 9980 20090 9983 20090 9982 20091 9983 20091 5414 20091 5414 20092 9983 20092 9967 20092 5414 20093 9967 20093 5369 20093 5369 20094 9967 20094 9984 20094 5369 20095 9984 20095 9985 20095 9985 20096 9984 20096 9937 20096 9985 20097 9937 20097 9938 20097 5224 20098 9976 20098 10014 20098 10014 20099 9976 20099 9986 20099 10014 20100 9986 20100 9987 20100 9987 20101 9986 20101 9988 20101 9987 20102 9988 20102 10012 20102 10012 20103 9988 20103 9989 20103 10012 20104 9989 20104 9990 20104 9990 20105 9989 20105 9992 20105 9990 20106 9992 20106 9991 20106 9991 20107 9992 20107 9993 20107 7130 20108 7131 20108 10002 20108 9994 20109 9995 20109 6580 20109 6580 20110 9995 20110 9999 20110 10034 20111 10033 20111 9996 20111 9996 20112 10033 20112 9997 20112 9996 20113 9997 20113 9995 20113 9995 20114 9997 20114 9998 20114 9995 20115 9998 20115 9999 20115 10034 20116 9996 20116 10031 20116 10031 20117 9996 20117 10000 20117 10031 20118 10000 20118 10001 20118 10001 20119 10000 20119 7135 20119 10001 20120 7135 20120 7136 20120 9994 20121 10008 20121 9995 20121 9995 20122 10008 20122 10007 20122 9995 20123 10007 20123 9996 20123 9996 20124 10007 20124 10005 20124 9996 20125 10005 20125 10000 20125 10000 20126 10005 20126 10002 20126 10002 20127 7131 20127 10000 20127 10000 20128 7131 20128 7133 20128 10000 20129 7133 20129 7135 20129 7129 20130 7130 20130 10003 20130 10003 20131 7130 20131 10002 20131 10003 20132 10002 20132 10004 20132 10004 20133 10002 20133 10005 20133 10004 20134 10005 20134 10006 20134 10006 20135 10005 20135 10007 20135 10006 20136 10007 20136 6578 20136 6578 20137 10007 20137 10008 20137 10009 20138 7129 20138 9954 20138 9954 20139 7129 20139 10003 20139 9954 20140 10003 20140 9953 20140 9953 20141 10003 20141 10004 20141 9953 20142 10004 20142 10010 20142 10010 20143 10004 20143 10006 20143 10010 20144 10006 20144 10011 20144 10011 20145 10006 20145 6578 20145 5375 20146 10024 20146 10018 20146 9991 20147 9993 20147 5360 20147 10012 20148 9990 20148 10013 20148 10013 20149 9990 20149 9991 20149 10014 20150 9987 20150 10020 20150 10020 20151 9987 20151 10012 20151 10026 20152 5224 20152 10014 20152 9991 20153 5360 20153 10013 20153 10013 20154 5360 20154 10015 20154 10013 20155 10015 20155 10021 20155 10021 20156 10015 20156 5359 20156 10021 20157 5359 20157 10017 20157 10017 20158 5359 20158 10016 20158 10017 20159 10016 20159 10018 20159 10018 20160 10016 20160 10019 20160 10018 20161 10019 20161 5375 20161 10012 20162 10013 20162 10020 20162 10020 20163 10013 20163 10021 20163 10020 20164 10021 20164 10027 20164 10027 20165 10021 20165 10017 20165 10027 20166 10017 20166 10022 20166 10022 20167 10017 20167 10018 20167 10022 20168 10018 20168 10023 20168 10023 20169 10018 20169 10024 20169 10023 20170 10024 20170 10025 20170 10014 20171 10020 20171 10026 20171 10026 20172 10020 20172 10027 20172 10026 20173 10027 20173 10028 20173 10028 20174 10027 20174 10022 20174 10028 20175 10022 20175 5219 20175 5219 20176 10022 20176 10023 20176 5219 20177 10023 20177 5227 20177 5227 20178 10023 20178 10025 20178 5227 20179 10025 20179 5220 20179 7139 20180 7140 20180 10029 20180 10001 20181 7136 20181 7137 20181 10030 20182 6579 20182 10036 20182 10036 20183 6579 20183 6580 20183 10036 20184 6580 20184 9999 20184 10032 20185 10034 20185 10031 20185 9999 20186 9998 20186 10036 20186 10036 20187 9998 20187 9997 20187 10036 20188 9997 20188 10032 20188 10032 20189 9997 20189 10033 20189 10032 20190 10033 20190 10034 20190 7139 20191 10029 20191 7137 20191 10035 20192 10030 20192 10037 20192 10037 20193 10030 20193 10036 20193 10037 20194 10036 20194 10029 20194 10029 20195 10036 20195 10032 20195 10029 20196 10032 20196 7137 20196 7137 20197 10032 20197 10031 20197 7137 20198 10031 20198 10001 20198 5375 20199 10035 20199 10024 20199 10024 20200 10035 20200 10037 20200 10024 20201 10037 20201 10025 20201 10025 20202 10037 20202 10029 20202 10025 20203 10029 20203 5220 20203 5220 20204 10029 20204 7140 20204 10054 20205 10051 20205 10046 20205 10051 20206 10038 20206 10042 20206 10038 20207 7449 20207 7612 20207 10038 20208 7612 20208 10042 20208 10042 20209 7612 20209 10039 20209 10042 20210 10039 20210 10040 20210 10040 20211 10039 20211 10041 20211 10040 20212 10041 20212 10044 20212 10044 20213 10041 20213 7615 20213 10044 20214 7615 20214 10045 20214 10051 20215 10042 20215 10046 20215 10046 20216 10042 20216 10040 20216 10046 20217 10040 20217 10043 20217 10043 20218 10040 20218 10044 20218 10043 20219 10044 20219 10047 20219 10047 20220 10044 20220 10045 20220 10047 20221 10045 20221 10048 20221 10054 20222 10046 20222 4897 20222 4897 20223 10046 20223 10043 20223 4897 20224 10043 20224 4896 20224 4896 20225 10043 20225 10047 20225 4896 20226 10047 20226 4898 20226 4898 20227 10047 20227 10048 20227 4898 20228 10048 20228 10049 20228 4899 20229 10049 20229 10050 20229 10050 20230 10049 20230 10048 20230 10050 20231 10048 20231 10058 20231 10058 20232 10048 20232 10045 20232 10058 20233 10045 20233 10057 20233 10057 20234 10045 20234 10055 20234 10055 20235 10045 20235 7615 20235 10055 20236 7615 20236 7625 20236 10070 20237 7449 20237 10038 20237 10070 20238 10038 20238 10052 20238 10052 20239 10038 20239 10051 20239 10052 20240 10051 20240 10053 20240 10053 20241 10051 20241 10054 20241 10053 20242 10054 20242 6275 20242 7625 20243 7626 20243 10055 20243 10055 20244 7626 20244 10061 20244 10055 20245 10061 20245 10057 20245 10057 20246 10061 20246 10056 20246 10057 20247 10056 20247 10058 20247 10058 20248 10056 20248 10059 20248 10058 20249 10059 20249 10050 20249 10050 20250 10059 20250 4900 20250 10050 20251 4900 20251 4899 20251 7626 20252 10060 20252 10061 20252 10061 20253 10060 20253 10065 20253 10061 20254 10065 20254 10056 20254 10056 20255 10065 20255 10062 20255 10056 20256 10062 20256 10059 20256 10059 20257 10062 20257 10063 20257 10059 20258 10063 20258 4900 20258 4900 20259 10063 20259 10068 20259 10060 20260 10064 20260 10065 20260 10065 20261 10064 20261 10066 20261 10065 20262 10066 20262 10062 20262 10062 20263 10066 20263 10069 20263 10062 20264 10069 20264 10063 20264 10063 20265 10069 20265 10067 20265 10063 20266 10067 20266 10068 20266 10068 20267 10067 20267 4891 20267 10064 20268 10076 20268 10066 20268 10066 20269 10076 20269 10077 20269 10066 20270 10077 20270 10069 20270 10069 20271 10077 20271 10078 20271 10069 20272 10078 20272 10067 20272 10067 20273 10078 20273 10081 20273 10067 20274 10081 20274 4891 20274 4891 20275 10081 20275 4893 20275 7450 20276 10070 20276 10073 20276 10073 20277 10070 20277 10052 20277 10073 20278 10052 20278 10071 20278 10071 20279 10052 20279 10053 20279 10071 20280 10053 20280 6274 20280 6274 20281 10053 20281 6275 20281 7447 20282 7450 20282 10072 20282 10072 20283 7450 20283 10073 20283 10072 20284 10073 20284 10074 20284 10074 20285 10073 20285 10071 20285 10074 20286 10071 20286 10075 20286 10075 20287 10071 20287 6274 20287 10083 20288 7447 20288 10100 20288 10100 20289 7447 20289 10072 20289 10100 20290 10072 20290 10099 20290 10099 20291 10072 20291 10074 20291 10099 20292 10074 20292 6272 20292 6272 20293 10074 20293 10075 20293 10076 20294 10119 20294 10120 20294 10076 20295 10120 20295 10077 20295 10077 20296 10120 20296 10079 20296 10077 20297 10079 20297 10078 20297 10078 20298 10079 20298 10080 20298 10078 20299 10080 20299 10081 20299 10081 20300 10080 20300 4892 20300 10081 20301 4892 20301 4893 20301 10082 20302 7618 20302 10104 20302 10094 20303 10088 20303 10089 20303 7623 20304 10083 20304 10101 20304 10101 20305 10083 20305 10100 20305 10088 20306 10098 20306 6271 20306 7623 20307 10101 20307 10085 20307 10085 20308 10101 20308 10084 20308 10085 20309 10084 20309 10086 20309 10086 20310 10084 20310 10103 20310 10086 20311 10103 20311 10087 20311 10087 20312 10103 20312 10105 20312 10087 20313 10105 20313 7621 20313 10088 20314 6271 20314 10089 20314 10089 20315 6271 20315 10090 20315 10089 20316 10090 20316 10091 20316 10091 20317 10090 20317 10092 20317 10091 20318 10092 20318 10093 20318 10093 20319 10092 20319 10110 20319 10093 20320 10110 20320 10096 20320 10094 20321 10089 20321 10102 20321 10102 20322 10089 20322 10091 20322 10102 20323 10091 20323 10095 20323 10095 20324 10091 20324 10093 20324 10095 20325 10093 20325 10097 20325 10097 20326 10093 20326 10096 20326 10097 20327 10096 20327 10108 20327 6272 20328 10098 20328 10099 20328 10099 20329 10098 20329 10088 20329 10099 20330 10088 20330 10100 20330 10100 20331 10088 20331 10094 20331 10100 20332 10094 20332 10101 20332 10101 20333 10094 20333 10102 20333 10101 20334 10102 20334 10084 20334 10084 20335 10102 20335 10095 20335 10084 20336 10095 20336 10103 20336 10103 20337 10095 20337 10097 20337 10103 20338 10097 20338 10105 20338 10105 20339 10097 20339 10108 20339 10105 20340 10108 20340 10104 20340 10104 20341 7618 20341 10105 20341 10105 20342 7618 20342 7619 20342 10105 20343 7619 20343 7621 20343 7617 20344 10082 20344 10106 20344 10106 20345 10082 20345 10104 20345 10106 20346 10104 20346 10107 20346 10107 20347 10104 20347 10108 20347 10107 20348 10108 20348 10114 20348 10114 20349 10108 20349 10096 20349 10114 20350 10096 20350 10109 20350 10109 20351 10096 20351 10110 20351 10115 20352 7617 20352 10111 20352 10111 20353 7617 20353 10106 20353 10111 20354 10106 20354 10112 20354 10112 20355 10106 20355 10107 20355 10112 20356 10107 20356 10113 20356 10113 20357 10107 20357 10114 20357 10113 20358 10114 20358 10118 20358 10118 20359 10114 20359 10109 20359 7452 20360 10115 20360 10116 20360 10116 20361 10115 20361 10111 20361 10116 20362 10111 20362 10121 20362 10121 20363 10111 20363 10112 20363 10121 20364 10112 20364 10122 20364 10122 20365 10112 20365 10113 20365 10122 20366 10113 20366 10117 20366 10117 20367 10113 20367 10118 20367 10119 20368 7452 20368 10120 20368 10120 20369 7452 20369 10116 20369 10120 20370 10116 20370 10079 20370 10079 20371 10116 20371 10121 20371 10079 20372 10121 20372 10080 20372 10080 20373 10121 20373 10122 20373 10080 20374 10122 20374 4892 20374 4892 20375 10122 20375 10117 20375 10152 20376 10153 20376 10125 20376 10156 20377 10127 20377 5077 20377 5077 20378 10127 20378 5078 20378 10129 20379 10123 20379 10155 20379 10153 20380 5085 20380 5083 20380 10131 20381 10132 20381 10152 20381 10124 20382 10150 20382 10151 20382 10153 20383 5083 20383 10125 20383 10125 20384 5083 20384 5082 20384 10125 20385 5082 20385 10133 20385 10133 20386 5082 20386 10127 20386 10127 20387 5082 20387 10126 20387 10127 20388 10126 20388 5078 20388 10155 20389 10128 20389 10129 20389 10129 20390 10128 20390 10130 20390 10129 20391 10130 20391 10134 20391 10134 20392 10130 20392 10124 20392 10134 20393 10124 20393 10131 20393 10131 20394 10124 20394 10151 20394 10131 20395 10151 20395 10132 20395 10152 20396 10125 20396 10131 20396 10131 20397 10125 20397 10133 20397 10131 20398 10133 20398 10134 20398 10134 20399 10133 20399 10127 20399 10134 20400 10127 20400 10129 20400 10129 20401 10127 20401 10156 20401 10129 20402 10156 20402 10123 20402 10149 20403 10162 20403 10144 20403 10136 20404 10164 20404 10137 20404 5138 20405 10136 20405 10138 20405 5138 20406 10138 20406 10135 20406 10135 20407 10138 20407 10140 20407 10135 20408 10140 20408 10143 20408 10136 20409 10137 20409 10138 20409 10138 20410 10137 20410 10139 20410 10138 20411 10139 20411 10140 20411 10140 20412 10139 20412 10141 20412 10140 20413 10141 20413 10142 20413 10143 20414 10140 20414 5140 20414 5140 20415 10140 20415 10142 20415 5140 20416 10142 20416 5141 20416 10149 20417 10144 20417 10145 20417 10145 20418 10144 20418 5088 20418 10145 20419 5088 20419 10148 20419 10148 20420 5088 20420 10146 20420 10148 20421 10146 20421 10147 20421 10147 20422 10146 20422 5085 20422 10147 20423 5085 20423 10153 20423 10153 20424 10141 20424 10147 20424 10147 20425 10141 20425 10139 20425 10147 20426 10139 20426 10148 20426 10148 20427 10139 20427 10137 20427 10148 20428 10137 20428 10145 20428 10145 20429 10137 20429 10164 20429 10145 20430 10164 20430 10149 20430 10150 20431 5141 20431 10151 20431 10151 20432 5141 20432 10142 20432 10151 20433 10142 20433 10132 20433 10132 20434 10142 20434 10141 20434 10132 20435 10141 20435 10152 20435 10152 20436 10141 20436 10153 20436 5137 20437 10155 20437 10154 20437 10154 20438 10155 20438 10123 20438 10154 20439 10123 20439 10157 20439 10157 20440 10123 20440 10156 20440 10157 20441 10156 20441 5076 20441 5076 20442 10156 20442 5077 20442 5123 20443 5137 20443 10183 20443 10183 20444 5137 20444 10154 20444 10183 20445 10154 20445 10174 20445 10174 20446 10154 20446 10157 20446 10174 20447 10157 20447 5075 20447 5075 20448 10157 20448 5076 20448 10160 20449 10158 20449 10170 20449 5138 20450 5142 20450 10159 20450 10160 20451 10170 20451 10161 20451 10168 20452 10162 20452 10167 20452 10167 20453 10162 20453 10149 20453 10167 20454 10149 20454 10163 20454 10163 20455 10149 20455 10164 20455 10163 20456 10164 20456 10159 20456 10159 20457 10164 20457 10136 20457 10159 20458 10136 20458 5138 20458 5142 20459 10161 20459 10159 20459 10159 20460 10161 20460 10170 20460 10159 20461 10170 20461 10163 20461 10163 20462 10170 20462 10165 20462 10163 20463 10165 20463 10167 20463 10167 20464 10165 20464 10166 20464 10167 20465 10166 20465 10168 20465 10168 20466 10166 20466 10172 20466 10158 20467 10169 20467 10170 20467 10170 20468 10169 20468 10197 20468 10170 20469 10197 20469 10165 20469 10165 20470 10197 20470 10196 20470 10165 20471 10196 20471 10166 20471 10166 20472 10196 20472 10171 20472 10166 20473 10171 20473 10172 20473 10172 20474 10171 20474 10173 20474 10174 20475 5075 20475 10177 20475 10183 20476 10174 20476 10185 20476 10175 20477 5115 20477 10192 20477 10192 20478 5115 20478 10176 20478 10192 20479 10176 20479 10186 20479 10186 20480 10176 20480 5120 20480 10186 20481 5120 20481 10184 20481 10184 20482 5120 20482 5123 20482 10184 20483 5123 20483 10183 20483 10174 20484 10177 20484 10185 20484 10185 20485 10177 20485 10178 20485 10185 20486 10178 20486 10179 20486 10179 20487 10178 20487 10181 20487 10179 20488 10181 20488 10180 20488 10180 20489 10181 20489 5071 20489 10180 20490 5071 20490 10187 20490 10187 20491 5071 20491 5070 20491 10187 20492 5070 20492 10190 20492 10190 20493 5070 20493 10182 20493 10190 20494 10182 20494 10202 20494 10183 20495 10185 20495 10184 20495 10184 20496 10185 20496 10179 20496 10184 20497 10179 20497 10186 20497 10186 20498 10179 20498 10180 20498 10186 20499 10180 20499 10192 20499 10192 20500 10180 20500 10187 20500 10192 20501 10187 20501 10188 20501 10188 20502 10187 20502 10190 20502 10188 20503 10190 20503 10189 20503 10189 20504 10190 20504 10202 20504 10189 20505 10202 20505 10201 20505 10175 20506 10192 20506 10191 20506 10191 20507 10192 20507 10188 20507 10191 20508 10188 20508 5118 20508 5118 20509 10188 20509 10189 20509 5118 20510 10189 20510 10193 20510 10193 20511 10189 20511 10201 20511 10193 20512 10201 20512 10199 20512 10194 20513 10173 20513 10171 20513 10194 20514 10171 20514 10195 20514 10195 20515 10171 20515 10196 20515 10195 20516 10196 20516 10222 20516 10222 20517 10196 20517 10197 20517 10222 20518 10197 20518 10221 20518 10221 20519 10197 20519 10169 20519 10221 20520 10169 20520 10219 20520 10198 20521 10199 20521 10200 20521 10200 20522 10199 20522 10201 20522 10200 20523 10201 20523 10206 20523 10206 20524 10201 20524 10202 20524 10206 20525 10202 20525 5069 20525 5069 20526 10202 20526 10182 20526 5902 20527 10198 20527 10203 20527 10203 20528 10198 20528 10200 20528 10203 20529 10200 20529 10204 20529 10204 20530 10200 20530 10206 20530 10204 20531 10206 20531 10205 20531 10205 20532 10206 20532 5069 20532 10207 20533 6276 20533 10217 20533 10208 20534 10250 20534 10209 20534 10209 20535 10250 20535 10251 20535 10209 20536 10251 20536 10210 20536 10210 20537 10251 20537 10253 20537 10210 20538 10253 20538 10213 20538 10213 20539 10253 20539 10254 20539 10213 20540 10254 20540 10214 20540 10214 20541 10254 20541 6268 20541 5135 20542 10208 20542 10211 20542 10211 20543 10208 20543 10209 20543 10211 20544 10209 20544 10212 20544 10212 20545 10209 20545 10210 20545 10212 20546 10210 20546 10218 20546 10218 20547 10210 20547 10213 20547 10218 20548 10213 20548 6273 20548 6273 20549 10213 20549 10214 20549 10220 20550 5135 20550 10215 20550 10215 20551 5135 20551 10211 20551 10215 20552 10211 20552 10216 20552 10216 20553 10211 20553 10212 20553 10216 20554 10212 20554 10217 20554 10217 20555 10212 20555 10218 20555 10217 20556 10218 20556 10207 20556 10207 20557 10218 20557 6273 20557 10219 20558 10220 20558 10221 20558 10221 20559 10220 20559 10215 20559 10221 20560 10215 20560 10222 20560 10222 20561 10215 20561 10216 20561 10222 20562 10216 20562 10195 20562 10195 20563 10216 20563 10217 20563 10195 20564 10217 20564 10194 20564 10194 20565 10217 20565 6276 20565 10246 20566 5902 20566 10223 20566 10223 20567 5902 20567 10203 20567 10223 20568 10203 20568 10237 20568 10237 20569 10203 20569 10225 20569 10225 20570 10203 20570 10204 20570 10225 20571 10204 20571 10224 20571 10205 20572 6265 20572 10204 20572 10204 20573 6265 20573 10228 20573 10204 20574 10228 20574 10224 20574 10237 20575 10225 20575 10226 20575 10224 20576 10228 20576 10227 20576 10228 20577 6265 20577 6267 20577 10224 20578 10227 20578 10225 20578 10229 20579 10223 20579 10237 20579 10223 20580 10229 20580 10246 20580 10228 20581 6267 20581 10227 20581 10227 20582 6267 20582 10230 20582 10227 20583 10230 20583 10235 20583 10235 20584 10230 20584 10231 20584 10235 20585 10231 20585 10232 20585 10232 20586 10231 20586 10233 20586 10232 20587 10233 20587 10234 20587 10225 20588 10227 20588 10226 20588 10226 20589 10227 20589 10235 20589 10226 20590 10235 20590 10238 20590 10238 20591 10235 20591 10232 20591 10238 20592 10232 20592 10236 20592 10236 20593 10232 20593 10234 20593 10236 20594 10234 20594 10240 20594 10237 20595 10226 20595 10229 20595 10229 20596 10226 20596 10238 20596 10229 20597 10238 20597 10245 20597 10245 20598 10238 20598 10236 20598 10245 20599 10236 20599 10239 20599 10239 20600 10236 20600 10240 20600 10239 20601 10240 20601 10241 20601 10242 20602 10243 20602 10241 20602 10241 20603 10243 20603 5128 20603 10241 20604 5128 20604 10239 20604 10239 20605 5128 20605 5127 20605 10239 20606 5127 20606 10245 20606 10245 20607 5127 20607 10244 20607 10245 20608 10244 20608 10229 20608 10229 20609 10244 20609 5126 20609 10229 20610 5126 20610 10246 20610 5131 20611 10242 20611 10252 20611 10252 20612 10242 20612 10241 20612 10252 20613 10241 20613 10247 20613 10247 20614 10241 20614 10240 20614 10247 20615 10240 20615 10248 20615 10248 20616 10240 20616 10234 20616 10248 20617 10234 20617 10249 20617 10249 20618 10234 20618 10233 20618 10250 20619 5131 20619 10251 20619 10251 20620 5131 20620 10252 20620 10251 20621 10252 20621 10253 20621 10253 20622 10252 20622 10247 20622 10253 20623 10247 20623 10254 20623 10254 20624 10247 20624 10248 20624 10254 20625 10248 20625 6268 20625 6268 20626 10248 20626 10249 20626 10262 20627 10255 20627 10278 20627 10256 20628 10258 20628 10257 20628 10257 20629 10258 20629 10260 20629 10257 20630 10260 20630 10259 20630 10259 20631 10260 20631 10261 20631 10274 20632 10261 20632 10277 20632 10277 20633 10261 20633 10260 20633 10277 20634 10260 20634 10278 20634 10278 20635 10260 20635 10258 20635 10278 20636 10258 20636 10262 20636 10262 20637 10258 20637 10256 20637 10262 20638 10256 20638 6281 20638 10263 20639 10265 20639 10272 20639 10290 20640 10287 20640 6283 20640 10265 20641 10264 20641 10290 20641 10263 20642 10266 20642 10284 20642 10263 20643 10284 20643 10265 20643 10265 20644 10284 20644 10291 20644 10265 20645 10291 20645 10264 20645 10290 20646 6283 20646 10265 20646 10265 20647 6283 20647 10271 20647 10265 20648 10271 20648 10272 20648 10272 20649 10268 20649 10263 20649 10263 20650 10268 20650 10269 20650 10263 20651 10269 20651 10266 20651 10266 20652 10269 20652 7483 20652 10266 20653 7483 20653 10267 20653 10267 20654 7483 20654 7490 20654 7480 20655 7481 20655 10268 20655 10268 20656 7481 20656 7482 20656 10268 20657 7482 20657 10269 20657 10257 20658 10270 20658 10256 20658 10256 20659 10270 20659 10273 20659 10256 20660 10273 20660 6281 20660 6281 20661 10273 20661 6284 20661 10271 20662 6284 20662 10272 20662 10272 20663 6284 20663 10273 20663 10272 20664 10273 20664 10268 20664 10268 20665 10273 20665 10270 20665 10268 20666 10270 20666 7480 20666 7480 20667 10270 20667 10257 20667 7480 20668 10257 20668 10259 20668 10274 20669 10281 20669 10275 20669 10275 20670 10281 20670 10276 20670 10275 20671 10276 20671 7606 20671 10278 20672 10255 20672 10279 20672 10274 20673 10277 20673 10281 20673 10281 20674 10277 20674 10278 20674 10281 20675 10278 20675 10280 20675 10280 20676 10278 20676 10279 20676 10280 20677 10279 20677 5005 20677 5005 20678 10299 20678 10280 20678 10280 20679 10299 20679 10298 20679 10280 20680 10298 20680 10281 20680 10281 20681 10298 20681 10282 20681 10281 20682 10282 20682 10276 20682 7486 20683 7485 20683 10283 20683 10285 20684 10289 20684 10291 20684 10291 20685 10284 20685 10285 20685 10285 20686 10284 20686 10266 20686 10285 20687 10266 20687 10286 20687 10286 20688 10266 20688 10267 20688 10286 20689 10267 20689 7490 20689 6776 20690 10287 20690 10288 20690 10288 20691 10287 20691 10290 20691 10288 20692 10290 20692 10289 20692 10289 20693 10290 20693 10264 20693 10289 20694 10264 20694 10291 20694 7486 20695 10283 20695 7489 20695 6768 20696 6776 20696 10292 20696 10292 20697 6776 20697 10288 20697 10292 20698 10288 20698 10293 20698 10293 20699 10288 20699 10289 20699 10293 20700 10289 20700 10294 20700 10294 20701 10289 20701 10285 20701 10294 20702 10285 20702 10283 20702 10283 20703 10285 20703 10286 20703 10283 20704 10286 20704 7489 20704 7489 20705 10286 20705 7490 20705 10331 20706 6768 20706 10332 20706 10332 20707 6768 20707 10292 20707 10332 20708 10292 20708 10295 20708 10295 20709 10292 20709 10293 20709 10295 20710 10293 20710 10329 20710 10329 20711 10293 20711 10294 20711 10329 20712 10294 20712 10296 20712 10296 20713 10294 20713 10283 20713 10296 20714 10283 20714 10297 20714 10297 20715 10283 20715 7485 20715 10282 20716 10298 20716 10300 20716 10299 20717 5005 20717 5003 20717 10298 20718 10299 20718 10305 20718 10282 20719 10300 20719 10276 20719 10301 20720 7606 20720 10318 20720 10318 20721 7606 20721 10276 20721 10299 20722 5003 20722 10305 20722 10305 20723 5003 20723 5002 20723 10305 20724 5002 20724 10302 20724 10302 20725 5002 20725 10303 20725 10302 20726 10303 20726 10306 20726 10306 20727 10303 20727 10304 20727 10306 20728 10304 20728 10308 20728 10308 20729 10304 20729 5074 20729 10308 20730 5074 20730 10323 20730 10298 20731 10305 20731 10300 20731 10300 20732 10305 20732 10302 20732 10300 20733 10302 20733 10311 20733 10311 20734 10302 20734 10306 20734 10311 20735 10306 20735 10307 20735 10307 20736 10306 20736 10308 20736 10307 20737 10308 20737 10309 20737 10309 20738 10308 20738 10323 20738 10309 20739 10323 20739 10321 20739 10276 20740 10300 20740 10318 20740 10318 20741 10300 20741 10311 20741 10318 20742 10311 20742 10310 20742 10310 20743 10311 20743 10307 20743 10310 20744 10307 20744 10312 20744 10312 20745 10307 20745 10309 20745 10312 20746 10309 20746 10313 20746 10313 20747 10309 20747 10321 20747 10313 20748 10321 20748 10314 20748 10319 20749 10315 20749 10314 20749 10314 20750 10315 20750 7602 20750 10314 20751 7602 20751 10313 20751 10313 20752 7602 20752 10316 20752 10313 20753 10316 20753 10312 20753 10312 20754 10316 20754 10317 20754 10312 20755 10317 20755 10310 20755 10310 20756 10317 20756 7603 20756 10310 20757 7603 20757 10318 20757 10318 20758 7603 20758 7604 20758 10318 20759 7604 20759 10301 20759 10324 20760 10319 20760 10326 20760 10326 20761 10319 20761 10314 20761 10326 20762 10314 20762 10320 20762 10320 20763 10314 20763 10321 20763 10320 20764 10321 20764 10327 20764 10327 20765 10321 20765 10323 20765 10327 20766 10323 20766 10322 20766 10322 20767 10323 20767 5074 20767 7428 20768 10324 20768 10325 20768 10325 20769 10324 20769 10326 20769 10325 20770 10326 20770 10348 20770 10348 20771 10326 20771 10320 20771 10348 20772 10320 20772 10349 20772 10349 20773 10320 20773 10327 20773 10349 20774 10327 20774 5072 20774 5072 20775 10327 20775 10322 20775 10339 20776 10350 20776 10330 20776 10330 20777 10350 20777 10354 20777 10296 20778 10297 20778 10328 20778 10329 20779 10296 20779 10334 20779 10330 20780 10331 20780 10339 20780 10339 20781 10331 20781 10332 20781 10339 20782 10332 20782 10333 20782 10333 20783 10332 20783 10295 20783 10333 20784 10295 20784 10335 20784 10296 20785 10328 20785 10334 20785 10334 20786 10328 20786 10366 20786 10334 20787 10366 20787 10364 20787 10364 20788 10363 20788 10334 20788 10334 20789 10363 20789 10335 20789 10334 20790 10335 20790 10329 20790 10329 20791 10335 20791 10295 20791 10363 20792 10336 20792 10335 20792 10335 20793 10336 20793 10337 20793 10335 20794 10337 20794 10333 20794 10333 20795 10337 20795 10338 20795 10333 20796 10338 20796 10339 20796 10339 20797 10338 20797 10360 20797 10339 20798 10360 20798 10350 20798 10340 20799 10346 20799 10341 20799 10340 20800 10341 20800 10368 20800 10368 20801 10341 20801 10342 20801 10368 20802 10342 20802 10343 20802 10343 20803 10342 20803 10347 20803 10343 20804 10347 20804 10344 20804 10344 20805 10347 20805 5073 20805 10344 20806 5073 20806 10345 20806 10346 20807 7428 20807 10341 20807 10341 20808 7428 20808 10325 20808 10341 20809 10325 20809 10342 20809 10342 20810 10325 20810 10348 20810 10342 20811 10348 20811 10347 20811 10347 20812 10348 20812 10349 20812 10347 20813 10349 20813 5073 20813 5073 20814 10349 20814 5072 20814 10351 20815 10394 20815 10357 20815 10350 20816 10360 20816 10359 20816 10394 20817 4890 20817 4998 20817 10390 20818 10392 20818 10355 20818 10355 20819 10392 20819 10351 20819 10356 20820 10389 20820 10390 20820 10389 20821 10356 20821 7422 20821 10394 20822 4998 20822 10357 20822 10357 20823 4998 20823 10352 20823 10357 20824 10352 20824 10353 20824 10353 20825 10352 20825 5000 20825 10353 20826 5000 20826 10359 20826 10359 20827 5000 20827 10354 20827 10359 20828 10354 20828 10350 20828 10390 20829 10355 20829 10356 20829 10356 20830 10355 20830 10358 20830 10356 20831 10358 20831 10365 20831 10365 20832 10358 20832 10361 20832 10365 20833 10361 20833 10362 20833 10351 20834 10357 20834 10355 20834 10355 20835 10357 20835 10353 20835 10355 20836 10353 20836 10358 20836 10358 20837 10353 20837 10359 20837 10358 20838 10359 20838 10361 20838 10361 20839 10359 20839 10360 20839 10361 20840 10360 20840 10338 20840 10338 20841 10337 20841 10361 20841 10361 20842 10337 20842 10336 20842 10361 20843 10336 20843 10362 20843 10362 20844 10336 20844 10363 20844 10362 20845 10363 20845 10364 20845 7422 20846 10356 20846 7423 20846 7423 20847 10356 20847 10365 20847 7423 20848 10365 20848 7425 20848 7425 20849 10365 20849 10362 20849 7425 20850 10362 20850 7426 20850 7426 20851 10362 20851 10364 20851 7426 20852 10364 20852 10366 20852 10380 20853 10387 20853 10386 20853 10376 20854 10397 20854 10375 20854 10367 20855 10382 20855 10373 20855 10382 20856 10381 20856 10369 20856 7430 20857 10340 20857 10368 20857 10381 20858 5079 20858 5081 20858 10381 20859 5081 20859 10369 20859 10369 20860 5081 20860 10371 20860 10369 20861 10371 20861 10370 20861 10370 20862 10371 20862 5084 20862 10370 20863 5084 20863 10374 20863 10374 20864 5084 20864 5086 20864 10374 20865 5086 20865 10372 20865 10372 20866 5086 20866 5087 20866 10372 20867 5087 20867 10398 20867 10382 20868 10369 20868 10373 20868 10373 20869 10369 20869 10370 20869 10373 20870 10370 20870 10377 20870 10377 20871 10370 20871 10374 20871 10377 20872 10374 20872 10379 20872 10379 20873 10374 20873 10372 20873 10379 20874 10372 20874 10375 20874 10375 20875 10372 20875 10398 20875 10375 20876 10398 20876 10376 20876 10367 20877 10373 20877 10383 20877 10383 20878 10373 20878 10377 20878 10383 20879 10377 20879 10378 20879 10378 20880 10377 20880 10379 20880 10378 20881 10379 20881 10385 20881 10385 20882 10379 20882 10375 20882 10385 20883 10375 20883 10386 20883 10386 20884 10375 20884 10397 20884 10386 20885 10397 20885 10380 20885 10345 20886 5079 20886 10344 20886 10344 20887 5079 20887 10381 20887 10344 20888 10381 20888 10343 20888 10343 20889 10381 20889 10382 20889 10343 20890 10382 20890 10368 20890 10368 20891 10382 20891 10367 20891 10368 20892 10367 20892 7430 20892 7430 20893 10367 20893 10383 20893 7430 20894 10383 20894 7431 20894 7431 20895 10383 20895 10378 20895 7431 20896 10378 20896 7432 20896 7432 20897 10378 20897 10385 20897 7432 20898 10385 20898 10384 20898 10384 20899 10385 20899 10386 20899 10384 20900 10386 20900 10388 20900 10388 20901 10386 20901 10387 20901 10388 20902 10387 20902 7427 20902 7422 20903 7607 20903 10389 20903 10389 20904 7607 20904 10391 20904 10389 20905 10391 20905 10390 20905 10390 20906 10391 20906 10402 20906 10390 20907 10402 20907 10392 20907 10392 20908 10402 20908 10411 20908 10392 20909 10411 20909 10351 20909 10351 20910 10411 20910 10410 20910 10351 20911 10410 20911 10394 20911 10394 20912 10410 20912 10393 20912 10394 20913 10393 20913 4890 20913 7611 20914 7427 20914 10395 20914 10395 20915 7427 20915 10387 20915 10395 20916 10387 20916 10396 20916 10396 20917 10387 20917 10380 20917 10396 20918 10380 20918 10414 20918 10414 20919 10380 20919 10397 20919 10414 20920 10397 20920 10415 20920 10415 20921 10397 20921 10376 20921 10415 20922 10376 20922 10400 20922 10400 20923 10376 20923 10398 20923 10400 20924 10398 20924 10399 20924 10399 20925 10398 20925 5087 20925 10415 20926 10400 20926 10401 20926 10396 20927 10414 20927 10413 20927 10402 20928 10391 20928 10403 20928 10391 20929 7607 20929 10404 20929 10391 20930 10404 20930 10403 20930 10403 20931 10404 20931 7610 20931 10403 20932 7610 20932 10406 20932 10406 20933 7610 20933 10405 20933 10406 20934 10405 20934 10408 20934 10408 20935 10405 20935 7611 20935 10408 20936 7611 20936 10395 20936 10407 20937 10411 20937 10402 20937 10402 20938 10403 20938 10407 20938 10407 20939 10403 20939 10406 20939 10407 20940 10406 20940 10412 20940 10412 20941 10406 20941 10408 20941 10412 20942 10408 20942 10413 20942 10413 20943 10408 20943 10395 20943 10413 20944 10395 20944 10396 20944 10409 20945 10410 20945 10411 20945 10411 20946 10407 20946 10409 20946 10409 20947 10407 20947 10412 20947 10409 20948 10412 20948 10416 20948 10416 20949 10412 20949 10413 20949 10416 20950 10413 20950 10401 20950 10401 20951 10413 20951 10414 20951 10401 20952 10414 20952 10415 20952 10417 20953 10393 20953 10410 20953 10410 20954 10409 20954 10417 20954 10417 20955 10409 20955 10416 20955 10417 20956 10416 20956 4903 20956 4903 20957 10416 20957 10401 20957 4903 20958 10401 20958 10418 20958 10418 20959 10401 20959 10400 20959 10418 20960 10400 20960 10399 20960 5973 20961 10437 20961 10433 20961 10425 20962 10423 20962 10427 20962 10427 20963 10423 20963 5976 20963 10424 20964 6359 20964 10419 20964 10424 20965 10419 20965 10420 20965 10419 20966 10449 20966 10420 20966 10420 20967 10449 20967 10421 20967 10420 20968 10421 20968 10425 20968 10425 20969 10421 20969 10422 20969 10425 20970 10422 20970 10423 20970 10428 20971 10424 20971 10430 20971 10430 20972 10424 20972 10420 20972 10430 20973 10420 20973 10432 20973 10432 20974 10420 20974 10425 20974 10432 20975 10425 20975 10426 20975 10426 20976 10425 20976 10427 20976 5973 20977 10433 20977 10434 20977 5015 20978 10428 20978 10429 20978 10429 20979 10428 20979 10430 20979 10429 20980 10430 20980 10431 20980 10431 20981 10430 20981 10432 20981 10431 20982 10432 20982 10433 20982 10433 20983 10432 20983 10426 20983 10433 20984 10426 20984 10434 20984 10434 20985 10426 20985 10427 20985 10434 20986 10427 20986 5975 20986 5975 20987 10427 20987 5976 20987 10435 20988 5015 20988 10447 20988 10447 20989 5015 20989 10429 20989 10447 20990 10429 20990 10444 20990 10444 20991 10429 20991 10431 20991 10444 20992 10431 20992 10443 20992 10443 20993 10431 20993 10433 20993 10443 20994 10433 20994 10436 20994 10436 20995 10433 20995 10437 20995 10442 20996 10438 20996 10445 20996 10445 20997 10438 20997 10439 20997 10445 20998 10439 20998 10440 20998 10440 20999 10439 20999 10441 20999 10440 21000 10441 21000 10446 21000 10446 21001 10441 21001 10488 21001 10446 21002 10488 21002 5022 21002 5022 21003 10488 21003 5020 21003 10436 21004 10442 21004 10443 21004 10443 21005 10442 21005 10445 21005 10443 21006 10445 21006 10444 21006 10444 21007 10445 21007 10440 21007 10444 21008 10440 21008 10447 21008 10447 21009 10440 21009 10446 21009 10447 21010 10446 21010 10435 21010 10435 21011 10446 21011 5022 21011 5978 21012 10451 21012 10448 21012 10419 21013 6359 21013 6358 21013 10419 21014 6358 21014 10449 21014 10449 21015 6358 21015 10454 21015 10449 21016 10454 21016 10421 21016 10421 21017 10454 21017 10422 21017 10454 21018 10450 21018 10422 21018 10422 21019 10450 21019 10448 21019 10422 21020 10448 21020 10423 21020 10423 21021 10448 21021 10451 21021 10423 21022 10451 21022 5976 21022 10455 21023 5978 21023 10456 21023 10456 21024 5978 21024 10448 21024 10456 21025 10448 21025 10452 21025 10452 21026 10448 21026 10450 21026 10452 21027 10450 21027 10453 21027 10453 21028 10450 21028 10454 21028 10453 21029 10454 21029 10457 21029 10457 21030 10454 21030 6358 21030 5891 21031 10455 21031 10500 21031 10500 21032 10455 21032 10456 21032 10500 21033 10456 21033 10499 21033 10499 21034 10456 21034 10452 21034 10499 21035 10452 21035 10498 21035 10498 21036 10452 21036 10453 21036 10498 21037 10453 21037 10496 21037 10496 21038 10453 21038 10457 21038 10483 21039 7594 21039 10482 21039 10460 21040 10458 21040 10459 21040 10472 21041 10460 21041 10464 21041 10507 21042 10472 21042 10473 21042 7599 21043 7441 21043 10476 21043 10476 21044 7441 21044 10507 21044 7599 21045 10476 21045 10461 21045 10461 21046 10476 21046 10477 21046 10461 21047 10477 21047 7600 21047 7600 21048 10477 21048 10462 21048 7600 21049 10462 21049 7598 21049 7598 21050 10462 21050 10480 21050 7598 21051 10480 21051 10463 21051 10460 21052 10459 21052 10464 21052 10464 21053 10459 21053 10465 21053 10464 21054 10465 21054 10466 21054 10466 21055 10465 21055 10467 21055 10466 21056 10467 21056 10474 21056 10474 21057 10467 21057 10468 21057 10474 21058 10468 21058 10469 21058 10469 21059 10468 21059 10470 21059 10469 21060 10470 21060 10471 21060 10472 21061 10464 21061 10473 21061 10473 21062 10464 21062 10466 21062 10473 21063 10466 21063 10478 21063 10478 21064 10466 21064 10474 21064 10478 21065 10474 21065 10475 21065 10475 21066 10474 21066 10469 21066 10475 21067 10469 21067 10479 21067 10479 21068 10469 21068 10471 21068 10479 21069 10471 21069 10481 21069 10507 21070 10473 21070 10476 21070 10476 21071 10473 21071 10478 21071 10476 21072 10478 21072 10477 21072 10477 21073 10478 21073 10475 21073 10477 21074 10475 21074 10462 21074 10462 21075 10475 21075 10479 21075 10462 21076 10479 21076 10480 21076 10480 21077 10479 21077 10481 21077 10480 21078 10481 21078 10482 21078 10482 21079 7594 21079 10480 21079 10480 21080 7594 21080 7596 21080 10480 21081 7596 21081 10463 21081 10487 21082 10483 21082 10484 21082 10484 21083 10483 21083 10482 21083 10484 21084 10482 21084 10485 21084 10485 21085 10482 21085 10481 21085 10485 21086 10481 21086 10486 21086 10486 21087 10481 21087 10471 21087 10486 21088 10471 21088 5019 21088 5019 21089 10471 21089 10470 21089 10438 21090 10487 21090 10439 21090 10439 21091 10487 21091 10484 21091 10439 21092 10484 21092 10441 21092 10441 21093 10484 21093 10485 21093 10441 21094 10485 21094 10488 21094 10488 21095 10485 21095 10486 21095 10488 21096 10486 21096 5020 21096 5020 21097 10486 21097 5019 21097 6357 21098 10489 21098 10511 21098 5888 21099 5889 21099 10501 21099 10490 21100 10491 21100 10493 21100 10493 21101 10491 21101 10513 21101 10493 21102 10513 21102 10501 21102 10501 21103 10513 21103 10492 21103 10501 21104 10492 21104 5888 21104 10490 21105 10493 21105 10494 21105 10494 21106 10493 21106 10495 21106 10494 21107 10495 21107 10511 21107 10511 21108 10495 21108 10497 21108 10511 21109 10497 21109 6357 21109 10496 21110 10497 21110 10498 21110 10498 21111 10497 21111 10495 21111 10498 21112 10495 21112 10499 21112 10499 21113 10495 21113 10493 21113 10499 21114 10493 21114 10500 21114 10500 21115 10493 21115 10501 21115 10500 21116 10501 21116 5891 21116 5891 21117 10501 21117 5889 21117 7440 21118 10502 21118 10503 21118 10503 21119 10502 21119 10504 21119 10503 21120 10504 21120 10508 21120 10508 21121 10504 21121 10542 21121 10508 21122 10542 21122 10505 21122 10505 21123 10542 21123 10506 21123 10505 21124 10506 21124 5006 21124 5006 21125 10506 21125 5007 21125 7441 21126 7440 21126 10507 21126 10507 21127 7440 21127 10503 21127 10507 21128 10503 21128 10472 21128 10472 21129 10503 21129 10508 21129 10472 21130 10508 21130 10460 21130 10460 21131 10508 21131 10505 21131 10460 21132 10505 21132 10458 21132 10458 21133 10505 21133 5006 21133 10509 21134 10510 21134 5013 21134 10490 21135 10494 21135 10515 21135 10515 21136 10494 21136 10511 21136 10510 21137 10509 21137 10489 21137 10489 21138 10509 21138 5013 21138 10490 21139 10515 21139 10491 21139 10491 21140 10515 21140 10512 21140 10491 21141 10512 21141 10513 21141 10513 21142 10512 21142 10492 21142 10492 21143 10512 21143 10514 21143 10492 21144 10514 21144 5888 21144 5012 21145 10515 21145 5013 21145 5013 21146 10515 21146 10511 21146 5013 21147 10511 21147 10489 21147 5886 21148 10514 21148 10531 21148 10531 21149 10514 21149 10512 21149 10531 21150 10512 21150 10516 21150 10516 21151 10512 21151 10515 21151 10516 21152 10515 21152 10517 21152 10517 21153 10515 21153 5012 21153 5970 21154 10532 21154 10538 21154 10517 21155 5012 21155 5011 21155 10516 21156 10517 21156 10518 21156 10531 21157 10516 21157 10520 21157 10517 21158 5011 21158 10518 21158 10518 21159 5011 21159 5010 21159 10518 21160 5010 21160 10521 21160 10521 21161 5010 21161 10519 21161 10521 21162 10519 21162 10523 21162 10523 21163 10519 21163 10536 21163 10523 21164 10536 21164 10524 21164 10516 21165 10518 21165 10520 21165 10520 21166 10518 21166 10521 21166 10520 21167 10521 21167 10522 21167 10522 21168 10521 21168 10523 21168 10522 21169 10523 21169 10525 21169 10525 21170 10523 21170 10524 21170 10525 21171 10524 21171 10534 21171 10531 21172 10520 21172 10529 21172 10529 21173 10520 21173 10522 21173 10529 21174 10522 21174 10528 21174 10528 21175 10522 21175 10525 21175 10528 21176 10525 21176 10527 21176 10527 21177 10525 21177 10534 21177 10527 21178 10534 21178 10533 21178 5968 21179 5967 21179 10533 21179 10533 21180 5967 21180 10526 21180 10533 21181 10526 21181 10527 21181 10527 21182 10526 21182 5963 21182 10527 21183 5963 21183 10528 21183 10528 21184 5963 21184 10530 21184 10528 21185 10530 21185 10529 21185 10529 21186 10530 21186 5886 21186 10529 21187 5886 21187 10531 21187 10532 21188 5968 21188 10538 21188 10538 21189 5968 21189 10533 21189 10538 21190 10533 21190 10541 21190 10541 21191 10533 21191 10534 21191 10541 21192 10534 21192 10535 21192 10535 21193 10534 21193 10524 21193 10535 21194 10524 21194 5009 21194 5009 21195 10524 21195 10536 21195 5971 21196 5970 21196 10537 21196 10537 21197 5970 21197 10538 21197 10537 21198 10538 21198 10539 21198 10539 21199 10538 21199 10541 21199 10539 21200 10541 21200 10540 21200 10540 21201 10541 21201 10535 21201 10540 21202 10535 21202 5008 21202 5008 21203 10535 21203 5009 21203 10502 21204 5971 21204 10504 21204 10504 21205 5971 21205 10537 21205 10504 21206 10537 21206 10542 21206 10542 21207 10537 21207 10539 21207 10542 21208 10539 21208 10506 21208 10506 21209 10539 21209 10540 21209 10506 21210 10540 21210 5007 21210 5007 21211 10540 21211 5008 21211 7406 21212 7409 21212 10543 21212 10543 21213 7409 21213 10558 21213 10543 21214 10558 21214 10547 21214 10547 21215 10558 21215 10561 21215 10547 21216 10561 21216 10544 21216 10544 21217 10561 21217 10562 21217 10544 21218 10562 21218 6494 21218 6494 21219 10562 21219 10545 21219 10546 21220 7406 21220 10576 21220 10576 21221 7406 21221 10543 21221 10576 21222 10543 21222 10548 21222 10548 21223 10543 21223 10547 21223 10548 21224 10547 21224 10549 21224 10549 21225 10547 21225 10544 21225 10549 21226 10544 21226 6493 21226 6493 21227 10544 21227 6494 21227 10555 21228 7410 21228 10556 21228 6488 21229 6486 21229 10552 21229 10550 21230 6488 21230 10552 21230 10550 21231 10552 21231 10581 21231 10581 21232 10552 21232 10551 21232 10552 21233 10553 21233 10551 21233 10551 21234 10553 21234 10556 21234 10551 21235 10556 21235 10592 21235 7410 21236 10579 21236 10556 21236 10556 21237 10579 21237 10578 21237 10556 21238 10578 21238 10592 21238 10554 21239 10555 21239 10559 21239 10559 21240 10555 21240 10556 21240 10559 21241 10556 21241 10560 21241 10560 21242 10556 21242 10553 21242 10560 21243 10553 21243 10557 21243 10557 21244 10553 21244 10552 21244 10557 21245 10552 21245 6485 21245 6485 21246 10552 21246 6486 21246 7409 21247 10554 21247 10558 21247 10558 21248 10554 21248 10559 21248 10558 21249 10559 21249 10561 21249 10561 21250 10559 21250 10560 21250 10561 21251 10560 21251 10562 21251 10562 21252 10560 21252 10557 21252 10562 21253 10557 21253 10545 21253 10545 21254 10557 21254 6485 21254 10568 21255 7476 21255 10563 21255 7474 21256 7473 21256 10569 21256 10598 21257 10564 21257 10569 21257 10569 21258 10564 21258 10599 21258 10569 21259 10599 21259 7474 21259 10569 21260 10567 21260 10598 21260 10598 21261 10567 21261 10566 21261 10598 21262 10566 21262 10565 21262 10565 21263 10566 21263 10595 21263 10595 21264 10566 21264 6419 21264 10595 21265 6419 21265 5027 21265 6491 21266 6419 21266 10570 21266 10570 21267 6419 21267 10566 21267 10570 21268 10566 21268 10572 21268 10572 21269 10566 21269 10567 21269 10572 21270 10567 21270 10563 21270 10563 21271 10567 21271 10569 21271 10563 21272 10569 21272 10568 21272 10568 21273 10569 21273 7473 21273 6490 21274 6491 21274 10575 21274 10575 21275 6491 21275 10570 21275 10575 21276 10570 21276 10571 21276 10571 21277 10570 21277 10572 21277 10571 21278 10572 21278 10573 21278 10573 21279 10572 21279 10563 21279 10573 21280 10563 21280 10574 21280 10574 21281 10563 21281 7476 21281 6493 21282 6490 21282 10549 21282 10549 21283 6490 21283 10575 21283 10549 21284 10575 21284 10548 21284 10548 21285 10575 21285 10571 21285 10548 21286 10571 21286 10576 21286 10576 21287 10571 21287 10573 21287 10576 21288 10573 21288 10546 21288 10546 21289 10573 21289 10574 21289 10577 21290 7414 21290 10588 21290 10592 21291 10590 21291 10585 21291 10578 21292 10579 21292 10591 21292 10580 21293 6488 21293 10583 21293 6488 21294 10550 21294 10583 21294 10583 21295 10550 21295 10581 21295 10583 21296 10581 21296 10585 21296 10585 21297 10581 21297 10551 21297 10585 21298 10551 21298 10592 21298 10582 21299 10580 21299 10584 21299 10584 21300 10580 21300 10583 21300 10584 21301 10583 21301 10589 21301 10589 21302 10583 21302 10585 21302 10589 21303 10585 21303 10586 21303 10586 21304 10585 21304 10590 21304 10577 21305 10588 21305 10587 21305 5017 21306 10582 21306 10593 21306 10593 21307 10582 21307 10584 21307 10593 21308 10584 21308 10594 21308 10594 21309 10584 21309 10589 21309 10594 21310 10589 21310 10588 21310 10588 21311 10589 21311 10586 21311 10588 21312 10586 21312 10587 21312 10587 21313 10586 21313 10590 21313 10587 21314 10590 21314 10591 21314 10591 21315 10590 21315 10592 21315 10591 21316 10592 21316 10578 21316 5021 21317 5017 21317 10612 21317 10612 21318 5017 21318 10593 21318 10612 21319 10593 21319 10611 21319 10611 21320 10593 21320 10594 21320 10611 21321 10594 21321 10609 21321 10609 21322 10594 21322 10588 21322 10609 21323 10588 21323 7413 21323 7413 21324 10588 21324 7414 21324 10565 21325 10595 21325 10596 21325 10596 21326 10595 21326 5027 21326 10596 21327 10597 21327 10565 21327 10565 21328 10597 21328 10601 21328 10565 21329 10601 21329 10598 21329 10598 21330 10601 21330 10600 21330 10598 21331 10600 21331 10564 21331 7471 21332 7474 21332 10600 21332 10600 21333 7474 21333 10599 21333 10600 21334 10599 21334 10564 21334 7472 21335 7471 21335 10604 21335 10604 21336 7471 21336 10600 21336 10604 21337 10600 21337 10605 21337 10605 21338 10600 21338 10601 21338 10605 21339 10601 21339 10602 21339 10602 21340 10601 21340 10597 21340 10602 21341 10597 21341 5029 21341 5029 21342 10597 21342 10596 21342 10616 21343 7472 21343 10603 21343 10603 21344 7472 21344 10604 21344 10603 21345 10604 21345 10618 21345 10618 21346 10604 21346 10605 21346 10618 21347 10605 21347 10606 21347 10606 21348 10605 21348 10602 21348 10606 21349 10602 21349 10619 21349 10619 21350 10602 21350 5029 21350 10608 21351 7405 21351 10610 21351 10610 21352 7405 21352 10653 21352 10610 21353 10653 21353 10613 21353 10613 21354 10653 21354 10647 21354 10613 21355 10647 21355 10614 21355 10614 21356 10647 21356 10607 21356 10614 21357 10607 21357 5023 21357 5023 21358 10607 21358 10648 21358 7413 21359 10608 21359 10609 21359 10609 21360 10608 21360 10610 21360 10609 21361 10610 21361 10611 21361 10611 21362 10610 21362 10613 21362 10611 21363 10613 21363 10612 21363 10612 21364 10613 21364 10614 21364 10612 21365 10614 21365 5021 21365 5021 21366 10614 21366 5023 21366 10615 21367 10616 21367 10617 21367 10617 21368 10616 21368 10603 21368 10617 21369 10603 21369 10621 21369 10621 21370 10603 21370 10618 21370 10621 21371 10618 21371 10622 21371 10622 21372 10618 21372 10606 21372 10622 21373 10606 21373 5033 21373 5033 21374 10606 21374 10619 21374 7408 21375 10615 21375 10625 21375 10625 21376 10615 21376 10617 21376 10625 21377 10617 21377 10620 21377 10620 21378 10617 21378 10621 21378 10620 21379 10621 21379 10626 21379 10626 21380 10621 21380 10622 21380 10626 21381 10622 21381 5035 21381 5035 21382 10622 21382 5033 21382 10629 21383 7408 21383 10623 21383 10623 21384 7408 21384 10625 21384 10623 21385 10625 21385 10624 21385 10624 21386 10625 21386 10620 21386 10624 21387 10620 21387 10627 21387 10627 21388 10620 21388 10626 21388 10627 21389 10626 21389 5036 21389 5036 21390 10626 21390 5035 21390 10628 21391 10629 21391 10630 21391 10630 21392 10629 21392 10623 21392 10630 21393 10623 21393 10632 21393 10632 21394 10623 21394 10624 21394 10632 21395 10624 21395 10633 21395 10633 21396 10624 21396 10627 21396 10633 21397 10627 21397 5037 21397 5037 21398 10627 21398 5036 21398 10639 21399 10628 21399 10631 21399 10631 21400 10628 21400 10630 21400 10631 21401 10630 21401 10637 21401 10637 21402 10630 21402 10632 21402 10637 21403 10632 21403 10636 21403 10636 21404 10632 21404 10633 21404 10636 21405 10633 21405 10634 21405 10634 21406 10633 21406 5037 21406 10634 21407 10635 21407 10636 21407 10636 21408 10635 21408 10638 21408 10636 21409 10638 21409 10637 21409 10637 21410 10638 21410 10650 21410 10637 21411 10650 21411 10631 21411 10631 21412 10650 21412 10641 21412 10631 21413 10641 21413 10639 21413 10640 21414 7590 21414 10641 21414 10641 21415 7590 21415 7591 21415 10641 21416 7591 21416 10639 21416 10649 21417 10643 21417 10642 21417 10642 21418 10643 21418 10644 21418 10642 21419 10644 21419 10651 21419 10651 21420 10644 21420 10645 21420 10651 21421 10645 21421 10652 21421 10652 21422 10645 21422 10646 21422 10653 21423 10646 21423 10647 21423 10647 21424 10646 21424 10645 21424 10647 21425 10645 21425 10607 21425 10607 21426 10645 21426 10644 21426 10607 21427 10644 21427 10648 21427 10648 21428 10644 21428 10643 21428 10635 21429 10649 21429 10638 21429 10638 21430 10649 21430 10642 21430 10638 21431 10642 21431 10650 21431 10650 21432 10642 21432 10651 21432 10650 21433 10651 21433 10641 21433 10641 21434 10651 21434 10652 21434 10641 21435 10652 21435 10640 21435 10640 21436 10652 21436 10646 21436 10640 21437 10646 21437 10654 21437 10654 21438 10646 21438 10653 21438 10654 21439 10653 21439 7405 21439 5044 21440 10655 21440 10659 21440 10674 21441 5948 21441 10656 21441 10655 21442 10671 21442 10659 21442 10659 21443 10671 21443 10672 21443 10659 21444 10672 21444 10661 21444 10661 21445 10672 21445 10674 21445 10661 21446 10674 21446 10657 21446 10657 21447 10674 21447 10656 21447 10657 21448 10656 21448 5952 21448 5041 21449 5044 21449 10658 21449 10658 21450 5044 21450 10659 21450 10658 21451 10659 21451 10666 21451 10666 21452 10659 21452 10661 21452 10666 21453 10661 21453 10660 21453 10660 21454 10661 21454 10657 21454 10660 21455 10657 21455 5955 21455 5955 21456 10657 21456 5952 21456 10665 21457 5090 21457 10662 21457 10662 21458 5090 21458 10663 21458 10662 21459 10663 21459 10667 21459 10667 21460 10663 21460 10718 21460 10667 21461 10718 21461 10668 21461 10668 21462 10718 21462 10664 21462 10668 21463 10664 21463 5039 21463 5039 21464 10664 21464 5040 21464 5955 21465 10665 21465 10660 21465 10660 21466 10665 21466 10662 21466 10660 21467 10662 21467 10666 21467 10666 21468 10662 21468 10667 21468 10666 21469 10667 21469 10658 21469 10658 21470 10667 21470 10668 21470 10658 21471 10668 21471 5041 21471 5041 21472 10668 21472 5039 21472 10681 21473 5947 21473 10669 21473 10655 21474 10670 21474 10677 21474 10655 21475 10677 21475 10671 21475 10671 21476 10677 21476 10673 21476 10671 21477 10673 21477 10672 21477 10672 21478 10673 21478 10676 21478 10672 21479 10676 21479 10674 21479 10674 21480 10676 21480 5950 21480 10674 21481 5950 21481 5948 21481 5951 21482 5950 21482 10675 21482 10675 21483 5950 21483 10676 21483 10675 21484 10676 21484 10678 21484 10678 21485 10676 21485 10673 21485 10678 21486 10673 21486 10679 21486 10679 21487 10673 21487 10677 21487 10679 21488 10677 21488 6353 21488 6353 21489 10677 21489 10670 21489 5947 21490 5951 21490 10669 21490 10669 21491 5951 21491 10675 21491 10669 21492 10675 21492 10683 21492 10683 21493 10675 21493 10678 21493 10683 21494 10678 21494 10680 21494 10680 21495 10678 21495 10679 21495 10680 21496 10679 21496 6354 21496 6354 21497 10679 21497 6353 21497 5946 21498 10681 21498 10682 21498 10682 21499 10681 21499 10669 21499 10682 21500 10669 21500 10688 21500 10688 21501 10669 21501 10683 21501 10688 21502 10683 21502 10684 21502 10684 21503 10683 21503 10680 21503 10684 21504 10680 21504 10685 21504 10685 21505 10680 21505 6354 21505 5928 21506 5946 21506 10720 21506 10720 21507 5946 21507 10682 21507 10720 21508 10682 21508 10686 21508 10686 21509 10682 21509 10688 21509 10686 21510 10688 21510 10687 21510 10687 21511 10688 21511 10684 21511 10687 21512 10684 21512 10689 21512 10689 21513 10684 21513 10685 21513 10730 21514 10729 21514 10690 21514 10692 21515 10691 21515 10693 21515 10691 21516 5032 21516 5031 21516 10692 21517 10693 21517 10729 21517 10705 21518 10694 21518 10730 21518 10691 21519 5031 21519 10693 21519 10693 21520 5031 21520 10696 21520 10693 21521 10696 21521 10695 21521 10695 21522 10696 21522 5024 21522 10695 21523 5024 21523 10697 21523 10697 21524 5024 21524 5025 21524 10697 21525 5025 21525 10709 21525 10729 21526 10693 21526 10690 21526 10690 21527 10693 21527 10695 21527 10690 21528 10695 21528 10700 21528 10700 21529 10695 21529 10697 21529 10700 21530 10697 21530 10701 21530 10701 21531 10697 21531 10709 21531 10701 21532 10709 21532 10698 21532 10730 21533 10690 21533 10705 21533 10705 21534 10690 21534 10700 21534 10705 21535 10700 21535 10699 21535 10699 21536 10700 21536 10701 21536 10699 21537 10701 21537 10703 21537 10703 21538 10701 21538 10698 21538 10703 21539 10698 21539 10708 21539 10707 21540 5106 21540 10708 21540 10708 21541 5106 21541 10702 21541 10708 21542 10702 21542 10703 21542 10703 21543 10702 21543 10704 21543 10703 21544 10704 21544 10699 21544 10699 21545 10704 21545 5109 21545 10699 21546 5109 21546 10705 21546 10705 21547 5109 21547 5111 21547 10705 21548 5111 21548 10694 21548 5104 21549 10707 21549 10706 21549 10706 21550 10707 21550 10708 21550 10706 21551 10708 21551 10714 21551 10714 21552 10708 21552 10698 21552 10714 21553 10698 21553 10716 21553 10716 21554 10698 21554 10709 21554 10716 21555 10709 21555 10710 21555 10710 21556 10709 21556 5025 21556 10717 21557 5104 21557 10711 21557 10711 21558 5104 21558 10706 21558 10711 21559 10706 21559 10712 21559 10712 21560 10706 21560 10714 21560 10712 21561 10714 21561 10713 21561 10713 21562 10714 21562 10716 21562 10713 21563 10716 21563 10715 21563 10715 21564 10716 21564 10710 21564 5090 21565 10717 21565 10663 21565 10663 21566 10717 21566 10711 21566 10663 21567 10711 21567 10718 21567 10718 21568 10711 21568 10712 21568 10718 21569 10712 21569 10664 21569 10664 21570 10712 21570 10713 21570 10664 21571 10713 21571 5040 21571 5040 21572 10713 21572 10715 21572 10719 21573 5928 21573 10723 21573 10723 21574 5928 21574 10720 21574 10723 21575 10720 21575 10721 21575 10721 21576 10720 21576 10686 21576 10721 21577 10686 21577 10725 21577 10725 21578 10686 21578 10687 21578 10725 21579 10687 21579 6355 21579 6355 21580 10687 21580 10689 21580 5961 21581 10719 21581 10722 21581 10722 21582 10719 21582 10723 21582 10722 21583 10723 21583 10745 21583 10745 21584 10723 21584 10721 21584 10745 21585 10721 21585 10724 21585 10724 21586 10721 21586 10725 21586 10724 21587 10725 21587 10744 21587 10744 21588 10725 21588 6355 21588 10691 21589 10692 21589 10727 21589 10726 21590 5097 21590 5099 21590 10728 21591 10759 21591 5034 21591 5032 21592 10691 21592 5034 21592 5034 21593 10691 21593 10727 21593 5034 21594 10727 21594 10728 21594 10728 21595 10727 21595 10762 21595 10692 21596 10729 21596 10727 21596 10727 21597 10729 21597 10726 21597 10727 21598 10726 21598 10762 21598 10762 21599 10726 21599 5099 21599 5111 21600 5097 21600 10694 21600 10694 21601 5097 21601 10726 21601 10694 21602 10726 21602 10730 21602 10730 21603 10726 21603 10729 21603 10738 21604 10747 21604 10742 21604 10731 21605 10732 21605 10735 21605 10735 21606 10732 21606 10733 21606 10735 21607 10733 21607 10743 21607 10743 21608 10733 21608 10734 21608 10743 21609 10734 21609 5959 21609 10731 21610 10735 21610 10748 21610 10748 21611 10735 21611 10736 21611 10748 21612 10736 21612 10749 21612 10749 21613 10736 21613 10750 21613 10750 21614 10736 21614 10741 21614 10750 21615 10741 21615 10737 21615 10738 21616 10742 21616 5960 21616 10739 21617 10741 21617 10740 21617 10740 21618 10741 21618 10736 21618 10740 21619 10736 21619 10746 21619 10746 21620 10736 21620 10735 21620 10746 21621 10735 21621 10742 21621 10742 21622 10735 21622 10743 21622 10742 21623 10743 21623 5960 21623 5960 21624 10743 21624 5959 21624 10744 21625 10739 21625 10724 21625 10724 21626 10739 21626 10740 21626 10724 21627 10740 21627 10745 21627 10745 21628 10740 21628 10746 21628 10745 21629 10746 21629 10722 21629 10722 21630 10746 21630 10742 21630 10722 21631 10742 21631 5961 21631 5961 21632 10742 21632 10747 21632 10752 21633 10748 21633 10749 21633 10752 21634 10749 21634 10751 21634 10751 21635 10749 21635 10750 21635 10751 21636 10750 21636 10737 21636 5959 21637 10734 21637 10754 21637 10734 21638 10733 21638 10754 21638 10754 21639 10733 21639 10732 21639 10754 21640 10732 21640 10752 21640 10752 21641 10732 21641 10731 21641 10752 21642 10731 21642 10748 21642 5957 21643 10753 21643 10754 21643 10754 21644 10753 21644 5958 21644 10754 21645 5958 21645 5959 21645 10760 21646 5016 21646 10755 21646 10755 21647 5016 21647 10756 21647 10755 21648 10756 21648 10757 21648 10757 21649 10756 21649 10758 21649 10762 21650 10758 21650 10728 21650 10728 21651 10758 21651 10756 21651 10728 21652 10756 21652 10759 21652 10759 21653 10756 21653 5016 21653 10751 21654 10760 21654 10752 21654 10752 21655 10760 21655 10755 21655 10752 21656 10755 21656 10754 21656 10754 21657 10755 21657 10757 21657 10754 21658 10757 21658 5957 21658 5957 21659 10757 21659 10758 21659 5957 21660 10758 21660 10761 21660 10761 21661 10758 21661 10762 21661 10761 21662 10762 21662 5099 21662 10763 21663 7459 21663 10764 21663 10764 21664 7459 21664 10765 21664 10764 21665 10765 21665 10771 21665 10771 21666 10765 21666 10766 21666 10771 21667 10766 21667 10773 21667 10773 21668 10766 21668 10767 21668 10773 21669 10767 21669 6510 21669 6510 21670 10767 21670 10768 21670 10769 21671 10763 21671 10770 21671 10770 21672 10763 21672 10764 21672 10770 21673 10764 21673 10799 21673 10799 21674 10764 21674 10771 21674 10799 21675 10771 21675 10772 21675 10772 21676 10771 21676 10773 21676 10772 21677 10773 21677 10808 21677 10808 21678 10773 21678 6510 21678 7462 21679 7460 21679 10776 21679 10775 21680 10814 21680 10779 21680 10779 21681 10814 21681 10774 21681 10779 21682 10774 21682 10780 21682 10780 21683 10774 21683 10812 21683 10780 21684 10812 21684 6420 21684 10775 21685 10779 21685 10809 21685 10809 21686 10779 21686 10777 21686 10809 21687 10777 21687 10810 21687 10810 21688 10777 21688 7466 21688 10810 21689 7466 21689 10811 21689 7460 21690 7466 21690 10776 21690 10776 21691 7466 21691 10777 21691 10776 21692 10777 21692 10781 21692 10781 21693 10777 21693 10779 21693 10781 21694 10779 21694 10778 21694 10778 21695 10779 21695 10780 21695 10778 21696 10780 21696 6426 21696 6426 21697 10780 21697 6420 21697 7463 21698 7462 21698 10782 21698 10782 21699 7462 21699 10776 21699 10782 21700 10776 21700 10783 21700 10783 21701 10776 21701 10781 21701 10783 21702 10781 21702 10784 21702 10784 21703 10781 21703 10778 21703 10784 21704 10778 21704 6425 21704 6425 21705 10778 21705 6426 21705 7459 21706 7463 21706 10765 21706 10765 21707 7463 21707 10782 21707 10765 21708 10782 21708 10766 21708 10766 21709 10782 21709 10783 21709 10766 21710 10783 21710 10767 21710 10767 21711 10783 21711 10784 21711 10767 21712 10784 21712 10768 21712 10768 21713 10784 21713 6425 21713 10769 21714 10770 21714 10797 21714 10794 21715 10785 21715 10795 21715 10786 21716 7579 21716 7580 21716 10786 21717 7580 21717 10785 21717 10800 21718 10821 21718 10787 21718 10787 21719 10821 21719 10820 21719 10787 21720 10820 21720 10794 21720 5047 21721 10800 21721 10788 21721 10785 21722 7580 21722 10795 21722 10795 21723 7580 21723 10789 21723 10795 21724 10789 21724 10790 21724 10790 21725 10789 21725 7582 21725 10790 21726 7582 21726 10791 21726 10791 21727 7582 21727 10792 21727 10791 21728 10792 21728 10797 21728 10797 21729 10792 21729 10793 21729 10797 21730 10793 21730 10769 21730 10794 21731 10795 21731 10787 21731 10787 21732 10795 21732 10790 21732 10787 21733 10790 21733 10796 21733 10796 21734 10790 21734 10791 21734 10796 21735 10791 21735 10801 21735 10801 21736 10791 21736 10797 21736 10801 21737 10797 21737 10798 21737 10798 21738 10797 21738 10770 21738 10798 21739 10770 21739 10799 21739 10800 21740 10787 21740 10788 21740 10788 21741 10787 21741 10796 21741 10788 21742 10796 21742 10802 21742 10802 21743 10796 21743 10801 21743 10802 21744 10801 21744 10805 21744 10805 21745 10801 21745 10798 21745 10805 21746 10798 21746 10807 21746 10807 21747 10798 21747 10799 21747 10807 21748 10799 21748 10772 21748 5047 21749 10788 21749 10803 21749 10803 21750 10788 21750 10802 21750 10803 21751 10802 21751 10804 21751 10804 21752 10802 21752 10805 21752 10804 21753 10805 21753 10806 21753 10806 21754 10805 21754 10807 21754 10806 21755 10807 21755 6423 21755 6423 21756 10807 21756 10772 21756 6423 21757 10772 21757 10808 21757 7467 21758 7468 21758 10819 21758 5028 21759 10812 21759 10813 21759 10816 21760 10809 21760 7464 21760 7464 21761 10809 21761 10810 21761 7464 21762 10810 21762 10811 21762 10812 21763 10774 21763 10813 21763 10813 21764 10774 21764 10814 21764 10813 21765 10814 21765 10816 21765 10816 21766 10814 21766 10775 21766 10816 21767 10775 21767 10809 21767 5030 21768 5028 21768 10815 21768 10815 21769 5028 21769 10813 21769 10815 21770 10813 21770 10819 21770 10819 21771 10813 21771 10816 21771 10819 21772 10816 21772 7467 21772 7467 21773 10816 21773 7464 21773 5026 21774 5030 21774 10817 21774 10817 21775 5030 21775 10815 21775 10817 21776 10815 21776 10818 21776 10818 21777 10815 21777 10819 21777 10818 21778 10819 21778 10833 21778 10833 21779 10819 21779 7468 21779 10824 21780 7578 21780 10826 21780 5047 21781 10829 21781 10822 21781 10794 21782 10820 21782 10823 21782 10823 21783 10820 21783 10821 21783 10823 21784 10821 21784 10822 21784 10822 21785 10821 21785 10800 21785 10822 21786 10800 21786 5047 21786 10794 21787 10823 21787 10785 21787 10785 21788 10823 21788 10826 21788 10785 21789 10826 21789 10786 21789 10786 21790 10826 21790 7578 21790 10786 21791 7578 21791 7579 21791 7576 21792 10824 21792 10825 21792 10825 21793 10824 21793 10826 21793 10825 21794 10826 21794 10827 21794 10827 21795 10826 21795 10823 21795 10827 21796 10823 21796 10828 21796 10828 21797 10823 21797 10822 21797 10828 21798 10822 21798 5049 21798 5049 21799 10822 21799 10829 21799 7394 21800 7576 21800 10836 21800 10836 21801 7576 21801 10825 21801 10836 21802 10825 21802 10837 21802 10837 21803 10825 21803 10827 21803 10837 21804 10827 21804 10838 21804 10838 21805 10827 21805 10828 21805 10838 21806 10828 21806 5052 21806 5052 21807 10828 21807 5049 21807 5042 21808 5038 21808 10869 21808 10869 21809 5038 21809 10834 21809 10869 21810 10834 21810 10831 21810 10831 21811 10834 21811 10830 21811 10831 21812 10830 21812 10871 21812 10871 21813 10830 21813 10832 21813 10832 21814 10830 21814 7395 21814 10832 21815 7395 21815 10876 21815 10833 21816 7395 21816 10818 21816 10818 21817 7395 21817 10830 21817 10818 21818 10830 21818 10817 21818 10817 21819 10830 21819 10834 21819 10817 21820 10834 21820 5026 21820 5026 21821 10834 21821 5038 21821 10841 21822 7394 21822 10835 21822 10835 21823 7394 21823 10836 21823 10835 21824 10836 21824 10843 21824 10843 21825 10836 21825 10837 21825 10843 21826 10837 21826 10844 21826 10844 21827 10837 21827 10838 21827 10844 21828 10838 21828 10839 21828 10839 21829 10838 21829 5052 21829 10846 21830 10841 21830 10840 21830 10840 21831 10841 21831 10835 21831 10840 21832 10835 21832 10842 21832 10842 21833 10835 21833 10843 21833 10842 21834 10843 21834 10849 21834 10849 21835 10843 21835 10844 21835 10849 21836 10844 21836 10845 21836 10845 21837 10844 21837 10839 21837 7588 21838 10846 21838 10847 21838 10847 21839 10846 21839 10840 21839 10847 21840 10840 21840 10851 21840 10851 21841 10840 21841 10842 21841 10851 21842 10842 21842 10850 21842 10850 21843 10842 21843 10849 21843 10850 21844 10849 21844 10848 21844 10848 21845 10849 21845 10845 21845 10848 21846 5055 21846 10850 21846 10850 21847 5055 21847 10864 21847 10850 21848 10864 21848 10851 21848 10851 21849 10864 21849 10852 21849 10851 21850 10852 21850 10847 21850 10847 21851 10852 21851 10853 21851 10847 21852 10853 21852 7588 21852 10865 21853 10854 21853 10853 21853 10853 21854 10854 21854 10855 21854 10853 21855 10855 21855 7588 21855 5046 21856 10856 21856 10857 21856 10857 21857 10856 21857 10858 21857 10857 21858 10858 21858 10859 21858 10859 21859 10858 21859 10860 21859 10859 21860 10860 21860 10866 21860 10866 21861 10860 21861 10862 21861 10856 21862 10861 21862 10858 21862 10858 21863 10861 21863 10872 21863 10858 21864 10872 21864 10860 21864 10860 21865 10872 21865 10863 21865 10860 21866 10863 21866 10862 21866 10862 21867 10863 21867 10875 21867 5055 21868 5046 21868 10864 21868 10864 21869 5046 21869 10857 21869 10864 21870 10857 21870 10852 21870 10852 21871 10857 21871 10859 21871 10852 21872 10859 21872 10853 21872 10853 21873 10859 21873 10866 21873 10853 21874 10866 21874 10865 21874 10865 21875 10866 21875 10862 21875 10865 21876 10862 21876 10868 21876 10868 21877 10862 21877 10875 21877 7584 21878 10867 21878 10875 21878 10875 21879 10867 21879 7586 21879 10875 21880 7586 21880 10868 21880 5043 21881 5042 21881 10873 21881 10873 21882 5042 21882 10869 21882 10873 21883 10869 21883 10870 21883 10832 21884 10874 21884 10871 21884 10871 21885 10874 21885 10870 21885 10871 21886 10870 21886 10831 21886 10831 21887 10870 21887 10869 21887 10861 21888 5043 21888 10872 21888 10872 21889 5043 21889 10873 21889 10872 21890 10873 21890 10863 21890 10863 21891 10873 21891 10870 21891 10863 21892 10870 21892 10875 21892 10875 21893 10870 21893 10874 21893 10875 21894 10874 21894 7584 21894 7584 21895 10874 21895 10832 21895 7584 21896 10832 21896 10876 21896 10877 21897 10878 21897 10882 21897 10877 21898 10882 21898 10899 21898 10899 21899 10882 21899 10880 21899 10899 21900 10880 21900 10879 21900 10879 21901 10880 21901 10886 21901 10879 21902 10886 21902 10881 21902 10881 21903 10886 21903 5058 21903 10881 21904 5058 21904 5056 21904 10878 21905 10883 21905 10882 21905 10882 21906 10883 21906 10884 21906 10882 21907 10884 21907 10880 21907 10880 21908 10884 21908 10885 21908 10880 21909 10885 21909 10886 21909 10886 21910 10885 21910 10915 21910 10886 21911 10915 21911 5058 21911 5058 21912 10915 21912 5059 21912 10897 21913 10899 21913 10889 21913 10889 21914 10899 21914 10879 21914 10889 21915 10879 21915 10887 21915 10887 21916 10879 21916 10881 21916 10887 21917 10881 21917 10888 21917 10888 21918 10881 21918 5056 21918 10888 21919 10892 21919 10887 21919 10887 21920 10892 21920 10890 21920 10887 21921 10890 21921 10889 21921 10889 21922 10890 21922 10891 21922 10889 21923 10891 21923 10897 21923 10897 21924 10891 21924 10896 21924 10892 21925 10893 21925 10890 21925 10890 21926 10893 21926 10904 21926 10890 21927 10904 21927 10891 21927 10891 21928 10904 21928 10894 21928 10891 21929 10894 21929 10896 21929 10896 21930 10894 21930 10902 21930 10901 21931 6070 21931 10902 21931 10902 21932 6070 21932 10895 21932 10902 21933 10895 21933 10896 21933 10896 21934 10895 21934 6072 21934 10896 21935 6072 21935 10897 21935 10897 21936 6072 21936 10898 21936 10897 21937 10898 21937 10899 21937 10899 21938 10898 21938 10900 21938 10899 21939 10900 21939 10877 21939 6068 21940 10901 21940 10907 21940 10907 21941 10901 21941 10902 21941 10907 21942 10902 21942 10908 21942 10908 21943 10902 21943 10894 21943 10908 21944 10894 21944 10903 21944 10903 21945 10894 21945 10904 21945 10903 21946 10904 21946 6347 21946 6347 21947 10904 21947 10893 21947 10905 21948 6068 21948 10916 21948 10916 21949 6068 21949 10907 21949 10916 21950 10907 21950 10906 21950 10906 21951 10907 21951 10908 21951 10906 21952 10908 21952 10918 21952 10918 21953 10908 21953 10903 21953 10918 21954 10903 21954 6346 21954 6346 21955 10903 21955 6347 21955 5906 21956 5908 21956 10913 21956 10913 21957 5908 21957 10950 21957 10913 21958 10950 21958 10909 21958 10909 21959 10950 21959 10910 21959 10909 21960 10910 21960 10914 21960 10914 21961 10910 21961 10911 21961 10914 21962 10911 21962 5060 21962 5060 21963 10911 21963 10912 21963 10883 21964 5906 21964 10884 21964 10884 21965 5906 21965 10913 21965 10884 21966 10913 21966 10885 21966 10885 21967 10913 21967 10909 21967 10885 21968 10909 21968 10915 21968 10915 21969 10909 21969 10914 21969 10915 21970 10914 21970 5059 21970 5059 21971 10914 21971 5060 21971 10920 21972 10905 21972 10921 21972 10921 21973 10905 21973 10916 21973 10921 21974 10916 21974 10917 21974 10917 21975 10916 21975 10906 21975 10917 21976 10906 21976 10924 21976 10924 21977 10906 21977 10918 21977 10924 21978 10918 21978 6351 21978 6351 21979 10918 21979 6346 21979 10919 21980 10920 21980 10954 21980 10954 21981 10920 21981 10921 21981 10954 21982 10921 21982 10922 21982 10922 21983 10921 21983 10917 21983 10922 21984 10917 21984 10923 21984 10923 21985 10917 21985 10924 21985 10923 21986 10924 21986 10956 21986 10956 21987 10924 21987 6351 21987 10925 21988 10928 21988 10932 21988 10927 21989 10926 21989 10933 21989 10926 21990 5053 21990 5051 21990 10927 21991 10933 21991 10928 21991 10945 21992 10964 21992 10925 21992 10964 21993 10945 21993 10929 21993 10926 21994 5051 21994 10933 21994 10933 21995 5051 21995 5050 21995 10933 21996 5050 21996 10930 21996 10930 21997 5050 21997 10931 21997 10930 21998 10931 21998 10934 21998 10934 21999 10931 21999 5062 21999 10934 22000 5062 22000 10935 22000 10928 22001 10933 22001 10932 22001 10932 22002 10933 22002 10930 22002 10932 22003 10930 22003 10937 22003 10937 22004 10930 22004 10934 22004 10937 22005 10934 22005 10936 22005 10936 22006 10934 22006 10935 22006 10936 22007 10935 22007 10939 22007 10925 22008 10932 22008 10945 22008 10945 22009 10932 22009 10937 22009 10945 22010 10937 22010 10938 22010 10938 22011 10937 22011 10936 22011 10938 22012 10936 22012 10943 22012 10943 22013 10936 22013 10939 22013 10943 22014 10939 22014 10942 22014 10940 22015 10941 22015 10942 22015 10942 22016 10941 22016 7572 22016 10942 22017 7572 22017 10943 22017 10943 22018 7572 22018 10944 22018 10943 22019 10944 22019 10938 22019 10938 22020 10944 22020 7574 22020 10938 22021 7574 22021 10945 22021 10945 22022 7574 22022 7575 22022 10945 22023 7575 22023 10929 22023 10946 22024 10940 22024 10951 22024 10951 22025 10940 22025 10942 22025 10951 22026 10942 22026 10947 22026 10947 22027 10942 22027 10939 22027 10947 22028 10939 22028 10948 22028 10948 22029 10939 22029 10935 22029 10948 22030 10935 22030 10949 22030 10949 22031 10935 22031 5062 22031 5908 22032 10946 22032 10950 22032 10950 22033 10946 22033 10951 22033 10950 22034 10951 22034 10910 22034 10910 22035 10951 22035 10947 22035 10910 22036 10947 22036 10911 22036 10911 22037 10947 22037 10948 22037 10911 22038 10948 22038 10912 22038 10912 22039 10948 22039 10949 22039 10952 22040 10919 22040 10953 22040 10953 22041 10919 22041 10954 22041 10953 22042 10954 22042 10955 22042 10955 22043 10954 22043 10922 22043 10955 22044 10922 22044 10958 22044 10958 22045 10922 22045 10923 22045 10958 22046 10923 22046 6350 22046 6350 22047 10923 22047 10956 22047 10970 22048 10952 22048 10957 22048 10957 22049 10952 22049 10953 22049 10957 22050 10953 22050 10981 22050 10981 22051 10953 22051 10955 22051 10981 22052 10955 22052 10982 22052 10982 22053 10955 22053 10958 22053 10982 22054 10958 22054 10959 22054 10959 22055 10958 22055 6350 22055 10965 22056 5917 22056 10963 22056 10963 22057 5917 22057 10996 22057 10963 22058 10996 22058 10961 22058 10961 22059 10996 22059 10962 22059 5053 22060 10961 22060 10960 22060 10960 22061 10961 22061 10962 22061 10960 22062 10962 22062 5054 22062 5053 22063 10926 22063 10961 22063 10961 22064 10926 22064 10927 22064 10961 22065 10927 22065 10963 22065 10963 22066 10927 22066 10928 22066 10929 22067 10965 22067 10964 22067 10964 22068 10965 22068 10963 22068 10964 22069 10963 22069 10925 22069 10925 22070 10963 22070 10928 22070 10967 22071 10971 22071 10990 22071 10966 22072 10977 22072 10971 22072 10978 22073 10991 22073 10977 22073 10983 22074 10989 22074 10991 22074 10990 22075 5943 22075 10967 22075 10967 22076 5943 22076 10968 22076 10967 22077 10968 22077 10972 22077 10972 22078 10968 22078 10969 22078 5944 22079 10976 22079 10969 22079 10969 22080 10976 22080 10974 22080 10969 22081 10974 22081 10972 22081 5944 22082 5945 22082 10976 22082 10976 22083 5945 22083 10970 22083 10976 22084 10970 22084 10957 22084 10971 22085 10967 22085 10966 22085 10966 22086 10967 22086 10972 22086 10966 22087 10972 22087 10973 22087 10973 22088 10972 22088 10974 22088 10973 22089 10974 22089 10975 22089 10975 22090 10974 22090 10976 22090 10975 22091 10976 22091 10980 22091 10980 22092 10976 22092 10957 22092 10980 22093 10957 22093 10981 22093 10977 22094 10966 22094 10978 22094 10978 22095 10966 22095 10973 22095 10978 22096 10973 22096 10984 22096 10984 22097 10973 22097 10975 22097 10984 22098 10975 22098 10979 22098 10979 22099 10975 22099 10980 22099 10979 22100 10980 22100 10988 22100 10988 22101 10980 22101 10981 22101 10988 22102 10981 22102 10982 22102 10991 22103 10978 22103 10983 22103 10983 22104 10978 22104 10984 22104 10983 22105 10984 22105 10985 22105 10985 22106 10984 22106 10979 22106 10985 22107 10979 22107 10986 22107 10986 22108 10979 22108 10988 22108 10986 22109 10988 22109 10987 22109 10987 22110 10988 22110 10982 22110 10987 22111 10982 22111 10959 22111 5941 22112 5942 22112 10993 22112 10989 22113 5048 22113 10995 22113 10989 22114 10995 22114 10991 22114 5942 22115 10990 22115 10993 22115 10993 22116 10990 22116 10971 22116 10993 22117 10971 22117 10995 22117 10995 22118 10971 22118 10977 22118 10995 22119 10977 22119 10991 22119 10997 22120 5941 22120 10992 22120 10992 22121 5941 22121 10993 22121 10992 22122 10993 22122 10994 22122 10994 22123 10993 22123 10995 22123 10994 22124 10995 22124 10998 22124 10998 22125 10995 22125 5048 22125 5917 22126 10997 22126 10996 22126 10996 22127 10997 22127 10992 22127 10996 22128 10992 22128 10962 22128 10962 22129 10992 22129 10994 22129 10962 22130 10994 22130 5054 22130 5054 22131 10994 22131 10998 22131 11005 22132 10999 22132 7561 22132 11003 22133 11023 22133 11000 22133 11000 22134 11023 22134 11022 22134 11006 22135 11002 22135 11001 22135 11001 22136 11002 22136 11024 22136 11001 22137 11024 22137 11003 22137 11003 22138 11024 22138 11004 22138 11003 22139 11004 22139 11023 22139 7561 22140 11032 22140 11005 22140 11005 22141 11032 22141 11027 22141 11005 22142 11027 22142 11006 22142 11006 22143 11027 22143 11026 22143 11006 22144 11026 22144 11002 22144 7389 22145 10999 22145 11046 22145 11046 22146 10999 22146 11005 22146 11046 22147 11005 22147 11007 22147 11007 22148 11005 22148 11006 22148 11007 22149 11006 22149 11059 22149 11059 22150 11006 22150 11001 22150 11059 22151 11001 22151 11060 22151 11060 22152 11001 22152 11003 22152 11060 22153 11003 22153 11066 22153 11066 22154 11003 22154 11000 22154 11030 22155 11008 22155 11025 22155 11069 22156 11009 22156 11010 22156 11010 22157 11009 22157 11014 22157 11014 22158 11009 22158 11070 22158 11069 22159 11010 22159 11011 22159 11011 22160 11010 22160 11016 22160 11011 22161 11016 22161 11012 22161 11012 22162 11016 22162 11018 22162 11012 22163 11018 22163 11068 22163 7567 22164 7568 22164 11018 22164 11018 22165 7568 22165 11013 22165 11018 22166 11013 22166 11068 22166 11014 22167 11015 22167 11010 22167 11010 22168 11015 22168 11029 22168 11010 22169 11029 22169 11016 22169 11016 22170 11029 22170 11017 22170 11016 22171 11017 22171 11018 22171 11018 22172 11017 22172 11019 22172 11018 22173 11019 22173 7567 22173 7564 22174 11020 22174 11019 22174 11019 22175 11020 22175 7566 22175 11019 22176 7566 22176 7567 22176 11008 22177 6429 22177 6428 22177 11021 22178 11028 22178 11031 22178 6428 22179 11022 22179 11023 22179 11008 22180 6428 22180 11025 22180 11025 22181 6428 22181 11023 22181 11025 22182 11023 22182 11004 22182 11004 22183 11024 22183 11025 22183 11025 22184 11024 22184 11021 22184 11025 22185 11021 22185 11030 22185 11030 22186 11021 22186 11031 22186 11024 22187 11002 22187 11021 22187 11021 22188 11002 22188 11026 22188 11021 22189 11026 22189 11028 22189 11028 22190 11026 22190 11027 22190 11028 22191 11027 22191 11032 22191 11015 22192 6429 22192 11029 22192 11029 22193 6429 22193 11008 22193 11029 22194 11008 22194 11017 22194 11017 22195 11008 22195 11030 22195 11017 22196 11030 22196 11019 22196 11019 22197 11030 22197 11031 22197 11019 22198 11031 22198 7564 22198 7564 22199 11031 22199 11028 22199 7564 22200 11028 22200 7563 22200 7563 22201 11028 22201 11032 22201 7563 22202 11032 22202 7561 22202 7389 22203 11046 22203 11045 22203 11047 22204 11055 22204 11049 22204 11055 22205 11034 22205 11036 22205 11061 22206 11033 22206 11062 22206 11062 22207 11033 22207 11080 22207 7557 22208 11036 22208 7555 22208 7555 22209 11036 22209 11034 22209 7555 22210 11034 22210 11054 22210 7557 22211 11035 22211 11036 22211 11036 22212 11035 22212 11038 22212 11036 22213 11038 22213 11037 22213 11037 22214 11038 22214 11039 22214 11037 22215 11039 22215 11040 22215 11040 22216 11039 22216 11041 22216 11040 22217 11041 22217 11045 22217 11045 22218 11041 22218 11042 22218 11045 22219 11042 22219 7389 22219 11055 22220 11036 22220 11049 22220 11049 22221 11036 22221 11037 22221 11049 22222 11037 22222 11050 22222 11050 22223 11037 22223 11040 22223 11050 22224 11040 22224 11043 22224 11043 22225 11040 22225 11045 22225 11043 22226 11045 22226 11044 22226 11044 22227 11045 22227 11046 22227 11044 22228 11046 22228 11007 22228 11047 22229 11049 22229 11048 22229 11048 22230 11049 22230 11050 22230 11048 22231 11050 22231 11051 22231 11051 22232 11050 22232 11043 22232 11051 22233 11043 22233 11052 22233 11052 22234 11043 22234 11044 22234 11052 22235 11044 22235 11053 22235 11053 22236 11044 22236 11007 22236 11053 22237 11007 22237 11059 22237 11054 22238 11034 22238 11075 22238 11075 22239 11034 22239 11055 22239 11075 22240 11055 22240 11080 22240 11080 22241 11055 22241 11047 22241 11080 22242 11047 22242 11062 22242 11062 22243 11047 22243 11048 22243 11062 22244 11048 22244 11056 22244 11056 22245 11048 22245 11051 22245 11056 22246 11051 22246 11057 22246 11057 22247 11051 22247 11052 22247 11057 22248 11052 22248 11058 22248 11058 22249 11052 22249 11053 22249 11058 22250 11053 22250 11065 22250 11065 22251 11053 22251 11059 22251 11065 22252 11059 22252 11060 22252 11061 22253 11062 22253 6442 22253 6442 22254 11062 22254 11056 22254 6442 22255 11056 22255 11063 22255 11063 22256 11056 22256 11057 22256 11063 22257 11057 22257 6433 22257 6433 22258 11057 22258 11058 22258 6433 22259 11058 22259 11064 22259 11064 22260 11058 22260 11065 22260 11064 22261 11065 22261 6430 22261 6430 22262 11065 22262 11060 22262 6430 22263 11060 22263 11066 22263 11013 22264 7568 22264 11067 22264 11013 22265 11067 22265 11068 22265 11068 22266 11067 22266 11073 22266 11068 22267 11073 22267 11012 22267 11012 22268 11073 22268 11011 22268 11011 22269 11073 22269 11071 22269 11011 22270 11071 22270 11069 22270 11069 22271 11071 22271 11009 22271 11009 22272 11071 22272 5061 22272 11009 22273 5061 22273 11070 22273 11089 22274 5061 22274 11088 22274 11088 22275 5061 22275 11071 22275 11088 22276 11071 22276 11072 22276 11072 22277 11071 22277 11073 22277 11072 22278 11073 22278 11085 22278 11085 22279 11073 22279 11067 22279 11074 22280 11054 22280 11075 22280 11074 22281 11075 22281 7554 22281 11091 22282 11076 22282 11077 22282 11077 22283 11076 22283 11081 22283 11077 22284 11081 22284 11093 22284 11093 22285 11081 22285 11079 22285 11093 22286 11079 22286 11078 22286 11078 22287 11079 22287 5065 22287 11061 22288 5065 22288 11033 22288 11033 22289 5065 22289 11079 22289 11033 22290 11079 22290 11080 22290 11080 22291 11079 22291 11081 22291 11080 22292 11081 22292 11075 22292 11075 22293 11081 22293 11076 22293 11075 22294 11076 22294 7554 22294 7554 22295 11076 22295 11091 22295 7554 22296 11091 22296 5822 22296 5057 22297 11082 22297 11113 22297 11113 22298 11082 22298 11087 22298 11113 22299 11087 22299 11114 22299 11114 22300 11087 22300 11083 22300 11114 22301 11083 22301 11084 22301 11086 22302 7388 22302 11083 22302 11083 22303 7388 22303 11123 22303 11083 22304 11123 22304 11084 22304 11085 22305 11086 22305 11072 22305 11072 22306 11086 22306 11083 22306 11072 22307 11083 22307 11088 22307 11088 22308 11083 22308 11087 22308 11088 22309 11087 22309 11089 22309 11089 22310 11087 22310 11082 22310 5823 22311 5822 22311 11090 22311 11090 22312 5822 22312 11091 22312 11090 22313 11091 22313 11092 22313 11092 22314 11091 22314 11077 22314 11092 22315 11077 22315 11096 22315 11096 22316 11077 22316 11093 22316 11096 22317 11093 22317 5064 22317 5064 22318 11093 22318 11078 22318 11100 22319 5823 22319 11101 22319 11101 22320 5823 22320 11090 22320 11101 22321 11090 22321 11094 22321 11094 22322 11090 22322 11092 22322 11094 22323 11092 22323 11095 22323 11095 22324 11092 22324 11096 22324 11095 22325 11096 22325 11097 22325 11097 22326 11096 22326 5064 22326 11095 22327 11097 22327 5068 22327 11094 22328 11095 22328 11098 22328 11101 22329 11094 22329 11115 22329 6064 22330 11099 22330 11118 22330 11118 22331 11099 22331 6062 22331 11118 22332 6062 22332 11117 22332 11117 22333 6062 22333 6067 22333 11117 22334 6067 22334 11116 22334 11116 22335 6067 22335 11100 22335 11116 22336 11100 22336 11101 22336 11095 22337 5068 22337 11098 22337 11098 22338 5068 22338 11102 22338 11098 22339 11102 22339 11104 22339 11104 22340 11102 22340 11103 22340 11104 22341 11103 22341 11105 22341 11105 22342 11103 22342 11106 22342 11105 22343 11106 22343 11109 22343 11109 22344 11106 22344 11112 22344 11109 22345 11112 22345 11110 22345 11094 22346 11098 22346 11115 22346 11115 22347 11098 22347 11104 22347 11115 22348 11104 22348 11107 22348 11107 22349 11104 22349 11105 22349 11107 22350 11105 22350 11108 22350 11108 22351 11105 22351 11109 22351 11108 22352 11109 22352 11111 22352 11111 22353 11109 22353 11110 22353 11111 22354 11110 22354 11120 22354 11112 22355 5057 22355 11110 22355 11110 22356 5057 22356 11113 22356 11110 22357 11113 22357 11120 22357 11120 22358 11113 22358 11114 22358 11120 22359 11114 22359 11084 22359 11101 22360 11115 22360 11116 22360 11116 22361 11115 22361 11107 22361 11116 22362 11107 22362 11117 22362 11117 22363 11107 22363 11108 22363 11117 22364 11108 22364 11118 22364 11118 22365 11108 22365 11111 22365 11118 22366 11111 22366 11119 22366 11119 22367 11111 22367 11120 22367 11119 22368 11120 22368 11121 22368 11121 22369 11120 22369 11084 22369 11121 22370 11084 22370 11123 22370 6064 22371 11118 22371 6065 22371 6065 22372 11118 22372 11119 22372 6065 22373 11119 22373 6066 22373 6066 22374 11119 22374 11121 22374 6066 22375 11121 22375 11122 22375 11122 22376 11121 22376 11123 22376 11122 22377 11123 22377 7388 22377 11124 22378 11145 22378 11125 22378 11124 22379 6056 22379 11144 22379 11124 22380 11125 22380 11126 22380 11126 22381 11125 22381 11127 22381 11126 22382 11127 22382 11129 22382 11127 22383 11128 22383 11129 22383 11129 22384 11128 22384 6348 22384 11129 22385 6348 22385 5067 22385 6059 22386 11130 22386 11138 22386 11138 22387 11130 22387 11154 22387 11138 22388 11154 22388 11131 22388 11131 22389 11154 22389 11155 22389 11131 22390 11155 22390 11132 22390 11132 22391 11155 22391 11133 22391 11132 22392 11133 22392 11141 22392 11141 22393 11133 22393 11157 22393 11141 22394 11157 22394 11134 22394 11134 22395 11157 22395 11135 22395 11136 22396 6059 22396 11137 22396 11137 22397 6059 22397 11138 22397 11137 22398 11138 22398 11143 22398 11143 22399 11138 22399 11131 22399 11143 22400 11131 22400 11142 22400 11142 22401 11131 22401 11132 22401 11142 22402 11132 22402 11139 22402 11139 22403 11132 22403 11141 22403 11139 22404 11141 22404 11140 22404 11140 22405 11141 22405 11134 22405 11140 22406 6348 22406 11139 22406 11139 22407 6348 22407 11128 22407 11139 22408 11128 22408 11142 22408 11142 22409 11128 22409 11127 22409 11142 22410 11127 22410 11143 22410 11143 22411 11127 22411 11125 22411 11143 22412 11125 22412 11137 22412 11137 22413 11125 22413 11145 22413 11124 22414 11144 22414 11145 22414 11145 22415 11144 22415 11146 22415 11145 22416 11146 22416 11137 22416 11137 22417 11146 22417 11147 22417 11137 22418 11147 22418 11136 22418 5834 22419 11148 22419 11149 22419 11149 22420 11148 22420 11150 22420 11149 22421 11150 22421 11156 22421 11156 22422 11150 22422 11151 22422 11156 22423 11151 22423 11152 22423 11152 22424 11151 22424 11195 22424 11152 22425 11195 22425 11153 22425 11153 22426 11195 22426 11196 22426 11153 22427 11196 22427 6360 22427 6360 22428 11196 22428 6330 22428 11130 22429 5834 22429 11154 22429 11154 22430 5834 22430 11149 22430 11154 22431 11149 22431 11155 22431 11155 22432 11149 22432 11156 22432 11155 22433 11156 22433 11133 22433 11133 22434 11156 22434 11152 22434 11133 22435 11152 22435 11157 22435 11157 22436 11152 22436 11153 22436 11157 22437 11153 22437 11135 22437 11135 22438 11153 22438 6360 22438 11158 22439 6055 22439 11160 22439 11160 22440 6055 22440 6056 22440 5067 22441 11162 22441 11129 22441 11129 22442 11162 22442 11161 22442 11129 22443 11161 22443 11126 22443 11126 22444 11161 22444 11160 22444 11126 22445 11160 22445 11124 22445 11124 22446 11160 22446 6056 22446 11163 22447 11158 22447 11159 22447 11159 22448 11158 22448 11160 22448 11159 22449 11160 22449 11166 22449 11166 22450 11160 22450 11161 22450 11166 22451 11161 22451 5066 22451 5066 22452 11161 22452 11162 22452 11197 22453 11163 22453 11198 22453 11198 22454 11163 22454 11159 22454 11198 22455 11159 22455 11164 22455 11164 22456 11159 22456 11166 22456 11164 22457 11166 22457 11165 22457 11165 22458 11166 22458 5066 22458 11167 22459 11182 22459 11189 22459 6337 22460 6339 22460 11168 22460 6337 22461 11168 22461 11169 22461 11168 22462 11176 22462 11169 22462 11169 22463 11176 22463 11174 22463 11169 22464 11174 22464 11208 22464 11173 22465 11205 22465 11174 22465 11174 22466 11205 22466 11207 22466 11174 22467 11207 22467 11208 22467 11170 22468 11205 22468 11171 22468 11171 22469 11205 22469 11173 22469 11171 22470 11173 22470 6051 22470 11178 22471 6051 22471 11172 22471 11172 22472 6051 22472 11173 22472 11172 22473 11173 22473 11180 22473 11180 22474 11173 22474 11174 22474 11180 22475 11174 22475 11175 22475 11175 22476 11174 22476 11176 22476 11175 22477 11176 22477 11181 22477 11181 22478 11176 22478 11168 22478 11181 22479 11168 22479 6341 22479 6341 22480 11168 22480 6339 22480 11177 22481 11178 22481 11183 22481 11183 22482 11178 22482 11172 22482 11183 22483 11172 22483 11179 22483 11179 22484 11172 22484 11180 22484 11179 22485 11180 22485 11186 22485 11186 22486 11180 22486 11175 22486 11186 22487 11175 22487 11187 22487 11187 22488 11175 22488 11181 22488 11187 22489 11181 22489 6332 22489 6332 22490 11181 22490 6341 22490 11182 22491 11177 22491 11189 22491 11189 22492 11177 22492 11183 22492 11189 22493 11183 22493 11184 22493 11184 22494 11183 22494 11179 22494 11184 22495 11179 22495 11185 22495 11185 22496 11179 22496 11186 22496 11185 22497 11186 22497 11191 22497 11191 22498 11186 22498 11187 22498 11191 22499 11187 22499 6331 22499 6331 22500 11187 22500 6332 22500 11188 22501 11167 22501 11192 22501 11192 22502 11167 22502 11189 22502 11192 22503 11189 22503 11193 22503 11193 22504 11189 22504 11184 22504 11193 22505 11184 22505 11194 22505 11194 22506 11184 22506 11185 22506 11194 22507 11185 22507 11190 22507 11190 22508 11185 22508 11191 22508 11190 22509 11191 22509 6334 22509 6334 22510 11191 22510 6331 22510 11148 22511 11188 22511 11150 22511 11150 22512 11188 22512 11192 22512 11150 22513 11192 22513 11151 22513 11151 22514 11192 22514 11193 22514 11151 22515 11193 22515 11195 22515 11195 22516 11193 22516 11194 22516 11195 22517 11194 22517 11196 22517 11196 22518 11194 22518 11190 22518 11196 22519 11190 22519 6330 22519 6330 22520 11190 22520 6334 22520 5845 22521 11197 22521 11199 22521 11199 22522 11197 22522 11198 22522 11199 22523 11198 22523 11202 22523 11202 22524 11198 22524 11164 22524 11202 22525 11164 22525 11200 22525 11200 22526 11164 22526 11165 22526 11213 22527 5845 22527 11201 22527 11201 22528 5845 22528 11199 22528 11201 22529 11199 22529 11215 22529 11215 22530 11199 22530 11202 22530 11215 22531 11202 22531 5063 22531 5063 22532 11202 22532 11200 22532 11203 22533 6401 22533 6337 22533 11170 22534 11204 22534 11205 22534 11205 22535 11204 22535 11206 22535 11205 22536 11206 22536 11207 22536 11207 22537 11206 22537 11210 22537 11207 22538 11210 22538 11208 22538 11208 22539 11210 22539 11203 22539 11208 22540 11203 22540 11169 22540 11169 22541 11203 22541 6337 22541 11222 22542 6401 22542 11221 22542 11221 22543 6401 22543 11203 22543 11221 22544 11203 22544 11219 22544 11219 22545 11203 22545 11210 22545 11219 22546 11210 22546 11209 22546 11209 22547 11210 22547 11206 22547 11209 22548 11206 22548 11211 22548 11211 22549 11206 22549 11204 22549 5063 22550 11212 22550 11215 22550 11215 22551 11212 22551 11226 22551 11225 22552 11213 22552 11237 22552 11237 22553 11213 22553 11201 22553 11237 22554 11201 22554 11214 22554 11214 22555 11201 22555 11215 22555 11214 22556 11215 22556 11223 22556 11223 22557 11215 22557 11226 22557 5837 22558 5842 22558 11216 22558 11216 22559 5842 22559 11252 22559 11216 22560 11252 22560 11217 22560 11217 22561 11252 22561 11218 22561 11217 22562 11218 22562 11220 22562 11220 22563 11218 22563 11255 22563 11220 22564 11255 22564 6400 22564 6400 22565 11255 22565 6397 22565 11211 22566 5837 22566 11209 22566 11209 22567 5837 22567 11216 22567 11209 22568 11216 22568 11219 22568 11219 22569 11216 22569 11217 22569 11219 22570 11217 22570 11221 22570 11221 22571 11217 22571 11220 22571 11221 22572 11220 22572 11222 22572 11222 22573 11220 22573 6400 22573 11223 22574 11226 22574 11224 22574 11223 22575 11224 22575 11214 22575 11237 22576 11214 22576 11238 22576 11225 22577 11237 22577 11247 22577 11229 22578 11231 22578 6439 22578 6439 22579 11231 22579 11224 22579 6439 22580 11224 22580 6440 22580 6440 22581 11224 22581 11226 22581 6440 22582 11226 22582 11212 22582 6438 22583 11227 22583 11229 22583 11229 22584 11227 22584 11228 22584 11229 22585 11228 22585 11231 22585 6438 22586 6436 22586 11227 22586 11227 22587 6436 22587 6435 22587 11227 22588 6435 22588 11234 22588 11234 22589 6435 22589 6434 22589 11234 22590 6434 22590 11235 22590 11235 22591 6434 22591 11230 22591 11235 22592 11230 22592 11236 22592 11214 22593 11224 22593 11238 22593 11238 22594 11224 22594 11231 22594 11238 22595 11231 22595 11232 22595 11232 22596 11231 22596 11228 22596 11232 22597 11228 22597 11240 22597 11240 22598 11228 22598 11227 22598 11240 22599 11227 22599 11233 22599 11233 22600 11227 22600 11234 22600 11233 22601 11234 22601 11243 22601 11243 22602 11234 22602 11235 22602 11243 22603 11235 22603 11244 22603 11244 22604 11235 22604 11236 22604 11244 22605 11236 22605 11246 22605 11237 22606 11238 22606 11247 22606 11247 22607 11238 22607 11232 22607 11247 22608 11232 22608 11239 22608 11239 22609 11232 22609 11240 22609 11239 22610 11240 22610 11241 22610 11241 22611 11240 22611 11233 22611 11241 22612 11233 22612 11242 22612 11242 22613 11233 22613 11243 22613 11242 22614 11243 22614 11251 22614 11251 22615 11243 22615 11244 22615 11251 22616 11244 22616 11245 22616 11245 22617 11244 22617 11246 22617 11245 22618 11246 22618 11254 22618 11225 22619 11247 22619 11248 22619 11248 22620 11247 22620 11239 22620 11248 22621 11239 22621 7551 22621 7551 22622 11239 22622 11241 22622 7551 22623 11241 22623 11249 22623 11249 22624 11241 22624 11242 22624 11249 22625 11242 22625 11250 22625 11250 22626 11242 22626 11251 22626 11250 22627 11251 22627 7548 22627 7548 22628 11251 22628 11245 22628 7548 22629 11245 22629 7549 22629 7549 22630 11245 22630 11254 22630 7549 22631 11254 22631 11253 22631 5842 22632 11253 22632 11252 22632 11252 22633 11253 22633 11254 22633 11252 22634 11254 22634 11218 22634 11218 22635 11254 22635 11246 22635 11218 22636 11246 22636 11255 22636 11255 22637 11246 22637 11236 22637 11255 22638 11236 22638 6397 22638 6397 22639 11236 22639 11230 22639 7538 22640 11256 22640 11268 22640 11303 22641 11265 22641 11257 22641 6454 22642 6453 22642 11299 22642 11259 22643 11265 22643 7533 22643 11258 22644 11301 22644 11303 22644 11299 22645 11300 22645 11276 22645 11276 22646 11300 22646 11301 22646 7533 22647 7532 22647 11259 22647 11259 22648 7532 22648 7530 22648 11259 22649 7530 22649 11266 22649 11266 22650 7530 22650 11260 22650 11266 22651 11260 22651 11261 22651 11261 22652 11260 22652 7536 22652 11261 22653 7536 22653 11262 22653 11262 22654 7536 22654 7535 22654 7535 22655 7534 22655 11262 22655 11262 22656 7534 22656 7541 22656 11262 22657 7541 22657 11263 22657 11263 22658 7541 22658 11264 22658 11263 22659 11264 22659 11268 22659 11268 22660 11264 22660 7539 22660 11268 22661 7539 22661 7538 22661 11265 22662 11259 22662 11257 22662 11257 22663 11259 22663 11266 22663 11257 22664 11266 22664 11269 22664 11269 22665 11266 22665 11261 22665 11269 22666 11261 22666 11271 22666 11271 22667 11261 22667 11262 22667 11271 22668 11262 22668 11267 22668 11267 22669 11262 22669 11263 22669 11267 22670 11263 22670 11273 22670 11273 22671 11263 22671 11268 22671 11273 22672 11268 22672 11275 22672 11275 22673 11268 22673 11256 22673 11275 22674 11256 22674 11296 22674 11303 22675 11257 22675 11258 22675 11258 22676 11257 22676 11269 22676 11258 22677 11269 22677 11270 22677 11270 22678 11269 22678 11271 22678 11270 22679 11271 22679 11272 22679 11272 22680 11271 22680 11267 22680 11272 22681 11267 22681 11277 22681 11277 22682 11267 22682 11273 22682 11277 22683 11273 22683 11274 22683 11274 22684 11273 22684 11275 22684 11274 22685 11275 22685 11278 22685 11278 22686 11275 22686 11296 22686 11278 22687 11296 22687 11297 22687 11301 22688 11258 22688 11276 22688 11276 22689 11258 22689 11270 22689 11276 22690 11270 22690 11280 22690 11280 22691 11270 22691 11272 22691 11280 22692 11272 22692 11282 22692 11282 22693 11272 22693 11277 22693 11282 22694 11277 22694 11284 22694 11284 22695 11277 22695 11274 22695 11284 22696 11274 22696 11285 22696 11285 22697 11274 22697 11278 22697 11285 22698 11278 22698 11279 22698 11279 22699 11278 22699 11297 22699 11279 22700 11297 22700 11298 22700 11299 22701 11276 22701 6454 22701 6454 22702 11276 22702 11280 22702 6454 22703 11280 22703 11281 22703 11281 22704 11280 22704 11282 22704 11281 22705 11282 22705 6443 22705 6443 22706 11282 22706 11284 22706 6443 22707 11284 22707 11283 22707 11283 22708 11284 22708 11285 22708 11283 22709 11285 22709 11286 22709 11286 22710 11285 22710 11279 22710 11286 22711 11279 22711 11287 22711 11287 22712 11279 22712 11298 22712 11287 22713 11298 22713 6446 22713 11288 22714 11334 22714 11289 22714 11289 22715 11334 22715 11290 22715 11289 22716 11290 22716 11291 22716 11291 22717 11290 22717 11336 22717 11291 22718 11336 22718 11292 22718 11292 22719 11336 22719 11294 22719 11292 22720 11294 22720 11293 22720 11293 22721 11294 22721 11295 22721 11293 22722 11295 22722 6445 22722 6445 22723 11295 22723 6431 22723 7538 22724 11288 22724 11256 22724 11256 22725 11288 22725 11289 22725 11256 22726 11289 22726 11296 22726 11296 22727 11289 22727 11291 22727 11296 22728 11291 22728 11297 22728 11297 22729 11291 22729 11292 22729 11297 22730 11292 22730 11298 22730 11298 22731 11292 22731 11293 22731 11298 22732 11293 22732 6446 22732 6446 22733 11293 22733 6445 22733 11299 22734 6453 22734 6414 22734 11299 22735 6414 22735 11300 22735 11300 22736 6414 22736 11302 22736 11300 22737 11302 22737 11301 22737 11301 22738 11302 22738 11303 22738 11302 22739 11304 22739 11303 22739 11303 22740 11304 22740 11351 22740 11303 22741 11351 22741 11265 22741 11265 22742 11351 22742 7528 22742 11265 22743 7528 22743 7533 22743 11305 22744 11324 22744 11326 22744 11353 22745 6437 22745 11314 22745 11353 22746 11314 22746 11307 22746 11354 22747 11306 22747 11310 22747 11310 22748 11306 22748 11307 22748 11310 22749 11307 22749 11308 22749 11308 22750 11307 22750 11314 22750 11354 22751 11310 22751 11309 22751 11309 22752 11310 22752 11311 22752 11309 22753 11311 22753 11352 22753 11352 22754 11311 22754 7545 22754 11352 22755 7545 22755 11312 22755 11316 22756 7545 22756 11313 22756 11313 22757 7545 22757 11311 22757 11313 22758 11311 22758 11318 22758 11318 22759 11311 22759 11310 22759 11318 22760 11310 22760 11320 22760 11320 22761 11310 22761 11308 22761 11320 22762 11308 22762 11323 22762 11323 22763 11308 22763 11314 22763 11323 22764 11314 22764 11315 22764 11315 22765 11314 22765 6437 22765 7544 22766 11316 22766 11325 22766 11325 22767 11316 22767 11313 22767 11325 22768 11313 22768 11317 22768 11317 22769 11313 22769 11318 22769 11317 22770 11318 22770 11319 22770 11319 22771 11318 22771 11320 22771 11319 22772 11320 22772 11321 22772 11321 22773 11320 22773 11323 22773 11321 22774 11323 22774 11322 22774 11322 22775 11323 22775 11315 22775 11324 22776 7544 22776 11326 22776 11326 22777 7544 22777 11325 22777 11326 22778 11325 22778 11327 22778 11327 22779 11325 22779 11317 22779 11327 22780 11317 22780 11328 22780 11328 22781 11317 22781 11319 22781 11328 22782 11319 22782 11333 22782 11333 22783 11319 22783 11321 22783 11333 22784 11321 22784 6432 22784 6432 22785 11321 22785 11322 22785 11335 22786 11305 22786 11329 22786 11329 22787 11305 22787 11326 22787 11329 22788 11326 22788 11330 22788 11330 22789 11326 22789 11327 22789 11330 22790 11327 22790 11337 22790 11337 22791 11327 22791 11328 22791 11337 22792 11328 22792 11331 22792 11331 22793 11328 22793 11333 22793 11331 22794 11333 22794 11332 22794 11332 22795 11333 22795 6432 22795 11334 22796 11335 22796 11290 22796 11290 22797 11335 22797 11329 22797 11290 22798 11329 22798 11336 22798 11336 22799 11329 22799 11330 22799 11336 22800 11330 22800 11294 22800 11294 22801 11330 22801 11337 22801 11294 22802 11337 22802 11295 22802 11295 22803 11337 22803 11331 22803 11295 22804 11331 22804 6431 22804 6431 22805 11331 22805 11332 22805 11339 22806 11359 22806 11342 22806 11342 22807 11359 22807 11361 22807 11342 22808 11361 22808 11338 22808 11338 22809 11361 22809 11362 22809 11338 22810 11362 22810 11344 22810 11344 22811 11362 22811 5794 22811 11344 22812 5794 22812 5792 22812 11340 22813 6343 22813 11342 22813 11342 22814 6343 22814 11339 22814 6416 22815 11340 22815 11346 22815 11346 22816 11340 22816 11342 22816 11346 22817 11342 22817 11341 22817 11341 22818 11342 22818 11338 22818 11341 22819 11338 22819 11343 22819 11343 22820 11338 22820 11344 22820 11343 22821 11344 22821 11349 22821 11349 22822 11344 22822 5792 22822 6415 22823 6416 22823 11345 22823 11345 22824 6416 22824 11346 22824 11345 22825 11346 22825 11350 22825 11350 22826 11346 22826 11341 22826 11350 22827 11341 22827 11347 22827 11347 22828 11341 22828 11343 22828 11347 22829 11343 22829 11348 22829 11348 22830 11343 22830 11349 22830 6414 22831 6415 22831 11302 22831 11302 22832 6415 22832 11345 22832 11302 22833 11345 22833 11304 22833 11304 22834 11345 22834 11350 22834 11304 22835 11350 22835 11351 22835 11351 22836 11350 22836 11347 22836 11351 22837 11347 22837 7528 22837 7528 22838 11347 22838 11348 22838 11358 22839 11354 22839 11309 22839 11358 22840 11309 22840 7547 22840 7547 22841 11309 22841 11352 22841 7547 22842 11352 22842 11312 22842 11355 22843 11353 22843 11357 22843 11357 22844 11353 22844 11307 22844 11357 22845 11307 22845 11358 22845 11358 22846 11307 22846 11306 22846 11358 22847 11306 22847 11354 22847 6398 22848 11355 22848 11356 22848 11356 22849 11355 22849 11357 22849 11356 22850 11357 22850 11368 22850 11368 22851 11357 22851 11358 22851 11368 22852 11358 22852 11366 22852 11366 22853 11358 22853 7547 22853 6343 22854 11391 22854 11390 22854 11339 22855 6343 22855 11390 22855 11339 22856 11390 22856 11359 22856 11359 22857 11390 22857 11360 22857 11359 22858 11360 22858 11361 22858 11361 22859 11360 22859 11363 22859 11361 22860 11363 22860 11362 22860 11362 22861 11363 22861 6047 22861 11362 22862 6047 22862 5794 22862 11367 22863 6039 22863 11364 22863 11364 22864 6039 22864 11397 22864 11364 22865 11397 22865 11365 22865 11365 22866 11397 22866 11393 22866 11365 22867 11393 22867 6399 22867 6399 22868 11393 22868 11392 22868 11366 22869 11367 22869 11368 22869 11368 22870 11367 22870 11364 22870 11368 22871 11364 22871 11356 22871 11356 22872 11364 22872 11365 22872 11356 22873 11365 22873 6398 22873 6398 22874 11365 22874 6399 22874 11379 22875 11378 22875 6040 22875 11395 22876 11394 22876 11380 22876 11380 22877 11394 22877 11378 22877 11371 22878 11396 22878 11369 22878 11369 22879 11396 22879 11370 22879 11369 22880 11370 22880 11395 22880 6338 22881 11371 22881 6340 22881 6040 22882 11372 22882 11379 22882 11379 22883 11372 22883 11373 22883 11379 22884 11373 22884 11374 22884 11373 22885 6043 22885 11374 22885 11374 22886 6043 22886 11375 22886 11374 22887 11375 22887 11376 22887 11376 22888 11375 22888 6046 22888 11376 22889 6046 22889 11377 22889 11377 22890 6046 22890 6047 22890 11377 22891 6047 22891 11363 22891 11378 22892 11379 22892 11380 22892 11380 22893 11379 22893 11374 22893 11380 22894 11374 22894 11383 22894 11383 22895 11374 22895 11376 22895 11383 22896 11376 22896 11381 22896 11381 22897 11376 22897 11377 22897 11381 22898 11377 22898 11382 22898 11382 22899 11377 22899 11363 22899 11382 22900 11363 22900 11360 22900 11395 22901 11380 22901 11369 22901 11369 22902 11380 22902 11383 22902 11369 22903 11383 22903 11384 22903 11384 22904 11383 22904 11381 22904 11384 22905 11381 22905 11387 22905 11387 22906 11381 22906 11382 22906 11387 22907 11382 22907 11385 22907 11385 22908 11382 22908 11360 22908 11385 22909 11360 22909 11390 22909 11371 22910 11369 22910 6340 22910 6340 22911 11369 22911 11384 22911 6340 22912 11384 22912 11386 22912 11386 22913 11384 22913 11387 22913 11386 22914 11387 22914 11388 22914 11388 22915 11387 22915 11385 22915 11388 22916 11385 22916 11389 22916 11389 22917 11385 22917 11390 22917 11389 22918 11390 22918 11391 22918 11371 22919 6338 22919 11392 22919 11371 22920 11392 22920 11396 22920 11396 22921 11392 22921 11393 22921 11378 22922 11394 22922 11393 22922 11394 22923 11395 22923 11393 22923 11393 22924 11395 22924 11370 22924 11393 22925 11370 22925 11396 22925 11393 22926 11397 22926 11378 22926 11378 22927 11397 22927 6039 22927 11378 22928 6039 22928 6040 22928 11398 22929 11414 22929 11399 22929 11418 22930 11402 22930 11404 22930 11426 22931 11436 22931 11417 22931 11417 22932 11436 22932 11416 22932 11429 22933 11400 22933 11426 22933 11430 22934 6344 22934 11400 22934 11401 22935 6034 22935 11402 22935 11402 22936 6034 22936 11403 22936 11402 22937 11403 22937 11404 22937 11404 22938 11403 22938 11405 22938 11404 22939 11405 22939 11409 22939 11405 22940 6035 22940 11409 22940 11409 22941 6035 22941 11406 22941 11409 22942 11406 22942 11407 22942 11407 22943 11406 22943 6038 22943 11407 22944 6038 22944 11412 22944 11412 22945 6038 22945 11408 22945 11412 22946 11408 22946 11399 22946 11399 22947 11408 22947 6036 22947 11399 22948 6036 22948 11398 22948 11418 22949 11404 22949 11410 22949 11410 22950 11404 22950 11409 22950 11410 22951 11409 22951 11420 22951 11420 22952 11409 22952 11407 22952 11420 22953 11407 22953 11411 22953 11411 22954 11407 22954 11412 22954 11411 22955 11412 22955 11422 22955 11422 22956 11412 22956 11399 22956 11422 22957 11399 22957 11413 22957 11413 22958 11399 22958 11414 22958 11413 22959 11414 22959 11415 22959 11401 22960 11402 22960 11416 22960 11416 22961 11402 22961 11418 22961 11416 22962 11418 22962 11417 22962 11417 22963 11418 22963 11410 22963 11417 22964 11410 22964 11419 22964 11419 22965 11410 22965 11420 22965 11419 22966 11420 22966 11421 22966 11421 22967 11420 22967 11411 22967 11421 22968 11411 22968 11423 22968 11423 22969 11411 22969 11422 22969 11423 22970 11422 22970 11424 22970 11424 22971 11422 22971 11413 22971 11424 22972 11413 22972 11425 22972 11425 22973 11413 22973 11415 22973 11425 22974 11415 22974 11449 22974 11426 22975 11417 22975 11429 22975 11429 22976 11417 22976 11419 22976 11429 22977 11419 22977 11427 22977 11427 22978 11419 22978 11421 22978 11427 22979 11421 22979 11431 22979 11431 22980 11421 22980 11423 22980 11431 22981 11423 22981 11428 22981 11428 22982 11423 22982 11424 22982 11428 22983 11424 22983 11433 22983 11433 22984 11424 22984 11425 22984 11433 22985 11425 22985 11434 22985 11434 22986 11425 22986 11449 22986 11434 22987 11449 22987 11435 22987 11400 22988 11429 22988 11430 22988 11430 22989 11429 22989 11427 22989 11430 22990 11427 22990 6342 22990 6342 22991 11427 22991 11431 22991 6342 22992 11431 22992 11432 22992 11432 22993 11431 22993 11428 22993 11432 22994 11428 22994 6345 22994 6345 22995 11428 22995 11433 22995 6345 22996 11433 22996 6333 22996 6333 22997 11433 22997 11434 22997 6333 22998 11434 22998 6335 22998 6335 22999 11434 22999 11435 22999 6335 23000 11435 23000 6336 23000 11400 23001 6344 23001 6418 23001 11400 23002 6418 23002 11426 23002 11426 23003 6418 23003 11440 23003 11426 23004 11440 23004 11436 23004 11436 23005 11440 23005 11416 23005 11440 23006 11439 23006 11416 23006 11416 23007 11439 23007 11437 23007 11416 23008 11437 23008 11401 23008 11438 23009 11437 23009 11457 23009 11457 23010 11437 23010 11439 23010 11457 23011 11439 23011 11458 23011 11458 23012 11439 23012 11440 23012 11458 23013 11440 23013 11441 23013 11441 23014 11440 23014 6418 23014 5806 23015 11504 23015 11448 23015 11448 23016 11504 23016 11442 23016 11448 23017 11442 23017 11443 23017 11443 23018 11442 23018 11444 23018 11443 23019 11444 23019 11450 23019 11450 23020 11444 23020 11445 23020 11450 23021 11445 23021 11446 23021 11446 23022 11445 23022 11447 23022 11446 23023 11447 23023 6364 23023 6364 23024 11447 23024 6322 23024 11398 23025 5806 23025 11414 23025 11414 23026 5806 23026 11448 23026 11414 23027 11448 23027 11415 23027 11415 23028 11448 23028 11443 23028 11415 23029 11443 23029 11449 23029 11449 23030 11443 23030 11450 23030 11449 23031 11450 23031 11435 23031 11435 23032 11450 23032 11446 23032 11435 23033 11446 23033 6336 23033 6336 23034 11446 23034 6364 23034 11508 23035 11510 23035 11451 23035 11451 23036 11510 23036 11511 23036 11451 23037 11511 23037 11513 23037 11459 23038 11506 23038 11452 23038 11452 23039 11506 23039 11507 23039 11452 23040 11507 23040 11508 23040 11453 23041 11505 23041 11459 23041 11513 23042 5821 23042 11451 23042 11451 23043 5821 23043 11454 23043 11451 23044 11454 23044 11456 23044 11456 23045 11454 23045 5820 23045 11456 23046 5820 23046 11455 23046 11455 23047 5820 23047 11438 23047 11455 23048 11438 23048 11457 23048 11508 23049 11451 23049 11452 23049 11452 23050 11451 23050 11456 23050 11452 23051 11456 23051 11461 23051 11461 23052 11456 23052 11455 23052 11461 23053 11455 23053 11462 23053 11462 23054 11455 23054 11457 23054 11462 23055 11457 23055 11458 23055 11459 23056 11452 23056 11453 23056 11453 23057 11452 23057 11461 23057 11453 23058 11461 23058 11460 23058 11460 23059 11461 23059 11462 23059 11460 23060 11462 23060 6417 23060 6417 23061 11462 23061 11458 23061 6417 23062 11458 23062 11441 23062 11479 23063 6029 23063 11471 23063 11463 23064 11521 23064 11464 23064 11464 23065 11521 23065 11465 23065 11464 23066 11465 23066 6320 23066 6320 23067 11465 23067 6315 23067 6030 23068 6032 23068 11467 23068 11467 23069 6032 23069 11466 23069 11467 23070 11466 23070 11470 23070 11470 23071 11466 23071 11522 23071 11470 23072 11522 23072 11463 23072 11463 23073 11522 23073 11468 23073 11463 23074 11468 23074 11521 23074 11469 23075 6030 23075 11473 23075 11473 23076 6030 23076 11467 23076 11473 23077 11467 23077 11474 23077 11474 23078 11467 23078 11470 23078 11474 23079 11470 23079 11475 23079 11475 23080 11470 23080 11463 23080 11475 23081 11463 23081 11477 23081 11477 23082 11463 23082 11464 23082 11477 23083 11464 23083 6318 23083 6318 23084 11464 23084 6320 23084 6029 23085 11469 23085 11471 23085 11471 23086 11469 23086 11473 23086 11471 23087 11473 23087 11472 23087 11472 23088 11473 23088 11474 23088 11472 23089 11474 23089 11481 23089 11481 23090 11474 23090 11475 23090 11481 23091 11475 23091 11476 23091 11476 23092 11475 23092 11477 23092 11476 23093 11477 23093 11483 23093 11483 23094 11477 23094 6318 23094 11484 23095 11479 23095 11478 23095 11478 23096 11479 23096 11471 23096 11478 23097 11471 23097 11487 23097 11487 23098 11471 23098 11472 23098 11487 23099 11472 23099 11480 23099 11480 23100 11472 23100 11481 23100 11480 23101 11481 23101 11488 23101 11488 23102 11481 23102 11476 23102 11488 23103 11476 23103 11482 23103 11482 23104 11476 23104 11483 23104 11493 23105 11484 23105 11485 23105 11485 23106 11484 23106 11478 23106 11485 23107 11478 23107 11486 23107 11486 23108 11478 23108 11487 23108 11486 23109 11487 23109 11491 23109 11491 23110 11487 23110 11480 23110 11491 23111 11480 23111 11490 23111 11490 23112 11480 23112 11488 23112 11490 23113 11488 23113 11489 23113 11489 23114 11488 23114 11482 23114 11489 23115 11497 23115 11490 23115 11490 23116 11497 23116 11498 23116 11490 23117 11498 23117 11491 23117 11491 23118 11498 23118 11492 23118 11491 23119 11492 23119 11486 23119 11486 23120 11492 23120 11501 23120 11486 23121 11501 23121 11485 23121 11485 23122 11501 23122 11494 23122 11485 23123 11494 23123 11493 23123 11503 23124 6026 23124 11494 23124 11494 23125 6026 23125 6027 23125 11494 23126 6027 23126 11493 23126 11442 23127 11495 23127 11444 23127 11444 23128 11495 23128 11496 23128 11444 23129 11496 23129 11445 23129 11445 23130 11496 23130 11502 23130 11445 23131 11502 23131 11447 23131 11447 23132 11502 23132 11500 23132 11447 23133 11500 23133 6322 23133 6322 23134 11500 23134 11499 23134 11497 23135 11499 23135 11498 23135 11498 23136 11499 23136 11500 23136 11498 23137 11500 23137 11492 23137 11492 23138 11500 23138 11502 23138 11492 23139 11502 23139 11501 23139 11501 23140 11502 23140 11496 23140 11501 23141 11496 23141 11494 23141 11494 23142 11496 23142 11495 23142 11494 23143 11495 23143 11503 23143 11503 23144 11495 23144 11442 23144 11503 23145 11442 23145 11504 23145 11505 23146 6452 23146 11519 23146 11507 23147 11506 23147 11519 23147 11519 23148 11506 23148 11459 23148 11519 23149 11459 23149 11505 23149 11507 23150 11519 23150 11508 23150 11508 23151 11519 23151 11509 23151 11508 23152 11509 23152 11510 23152 11510 23153 11509 23153 11512 23153 11510 23154 11512 23154 11511 23154 11511 23155 11512 23155 11515 23155 11511 23156 11515 23156 11513 23156 11514 23157 11515 23157 11516 23157 11516 23158 11515 23158 11512 23158 11516 23159 11512 23159 11517 23159 11517 23160 11512 23160 11509 23160 11517 23161 11509 23161 11518 23161 11518 23162 11509 23162 11519 23162 11518 23163 11519 23163 11528 23163 11528 23164 11519 23164 6452 23164 11466 23165 6032 23165 11524 23165 11520 23166 6315 23166 11465 23166 11520 23167 11465 23167 11553 23167 11553 23168 11465 23168 11521 23168 11553 23169 11521 23169 11551 23169 11551 23170 11521 23170 11468 23170 11551 23171 11468 23171 11549 23171 11549 23172 11468 23172 11522 23172 11549 23173 11522 23173 11523 23173 11523 23174 11522 23174 11466 23174 11523 23175 11466 23175 11548 23175 11548 23176 11466 23176 11524 23176 11525 23177 7527 23177 11526 23177 11529 23178 11514 23178 11530 23178 11530 23179 11514 23179 11516 23179 11530 23180 11516 23180 11527 23180 11527 23181 11516 23181 11517 23181 11527 23182 11517 23182 11532 23182 11532 23183 11517 23183 11518 23183 11532 23184 11518 23184 6451 23184 6451 23185 11518 23185 11528 23185 7527 23186 11529 23186 11526 23186 11526 23187 11529 23187 11530 23187 11526 23188 11530 23188 11534 23188 11534 23189 11530 23189 11527 23189 11534 23190 11527 23190 11531 23190 11531 23191 11527 23191 11532 23191 11531 23192 11532 23192 6450 23192 6450 23193 11532 23193 6451 23193 7523 23194 11525 23194 11533 23194 11533 23195 11525 23195 11526 23195 11533 23196 11526 23196 11536 23196 11536 23197 11526 23197 11534 23197 11536 23198 11534 23198 11538 23198 11538 23199 11534 23199 11531 23199 11538 23200 11531 23200 11539 23200 11539 23201 11531 23201 6450 23201 7524 23202 7523 23202 11535 23202 11535 23203 7523 23203 11533 23203 11535 23204 11533 23204 11542 23204 11542 23205 11533 23205 11536 23205 11542 23206 11536 23206 11543 23206 11543 23207 11536 23207 11538 23207 11543 23208 11538 23208 11537 23208 11537 23209 11538 23209 11539 23209 11571 23210 7524 23210 11540 23210 11540 23211 7524 23211 11535 23211 11540 23212 11535 23212 11541 23212 11541 23213 11535 23213 11542 23213 11541 23214 11542 23214 11569 23214 11569 23215 11542 23215 11543 23215 11569 23216 11543 23216 6448 23216 6448 23217 11543 23217 11537 23217 11548 23218 11524 23218 5809 23218 11566 23219 11544 23219 11545 23219 11545 23220 11544 23220 11568 23220 11545 23221 11568 23221 11556 23221 11556 23222 11568 23222 6447 23222 11556 23223 6447 23223 11558 23223 11566 23224 11545 23224 11565 23224 11565 23225 11545 23225 11554 23225 11565 23226 11554 23226 11546 23226 11546 23227 11554 23227 5813 23227 11546 23228 5813 23228 11547 23228 11548 23229 5809 23229 11523 23229 11523 23230 5809 23230 11559 23230 11523 23231 11559 23231 11549 23231 11549 23232 11559 23232 11550 23232 11549 23233 11550 23233 11551 23233 11551 23234 11550 23234 11552 23234 11551 23235 11552 23235 11553 23235 11553 23236 11552 23236 11562 23236 11553 23237 11562 23237 11520 23237 5810 23238 5813 23238 11560 23238 11560 23239 5813 23239 11554 23239 11560 23240 11554 23240 11561 23240 11561 23241 11554 23241 11545 23241 11561 23242 11545 23242 11555 23242 11555 23243 11545 23243 11556 23243 11555 23244 11556 23244 11557 23244 11557 23245 11556 23245 11558 23245 5809 23246 5810 23246 11559 23246 11559 23247 5810 23247 11560 23247 11559 23248 11560 23248 11550 23248 11550 23249 11560 23249 11561 23249 11550 23250 11561 23250 11552 23250 11552 23251 11561 23251 11555 23251 11552 23252 11555 23252 11562 23252 11562 23253 11555 23253 11557 23253 11547 23254 11563 23254 11546 23254 11546 23255 11563 23255 11564 23255 11546 23256 11564 23256 11565 23256 11565 23257 11564 23257 11566 23257 11566 23258 11564 23258 11570 23258 11566 23259 11570 23259 11544 23259 11544 23260 11570 23260 11567 23260 11544 23261 11567 23261 11568 23261 11568 23262 11567 23262 6449 23262 11568 23263 6449 23263 6447 23263 6448 23264 6449 23264 11569 23264 11569 23265 6449 23265 11567 23265 11569 23266 11567 23266 11541 23266 11541 23267 11567 23267 11570 23267 11541 23268 11570 23268 11540 23268 11540 23269 11570 23269 11564 23269 11540 23270 11564 23270 11571 23270 11571 23271 11564 23271 11563 23271 11580 23272 7391 23272 11572 23272 11572 23273 7391 23273 11624 23273 11572 23274 11624 23274 11582 23274 11582 23275 11624 23275 11573 23275 11582 23276 11573 23276 11574 23276 11574 23277 11573 23277 11626 23277 11574 23278 11626 23278 11575 23278 11575 23279 11626 23279 11576 23279 11575 23280 11576 23280 11577 23280 11577 23281 11576 23281 11578 23281 11591 23282 11580 23282 11579 23282 11579 23283 11580 23283 11572 23283 11579 23284 11572 23284 11581 23284 11581 23285 11572 23285 11582 23285 11581 23286 11582 23286 11586 23286 11586 23287 11582 23287 11574 23287 11586 23288 11574 23288 11583 23288 11583 23289 11574 23289 11575 23289 11583 23290 11575 23290 11584 23290 11584 23291 11575 23291 11577 23291 11584 23292 11585 23292 11583 23292 11583 23293 11585 23293 11600 23293 11583 23294 11600 23294 11586 23294 11586 23295 11600 23295 11587 23295 11586 23296 11587 23296 11581 23296 11581 23297 11587 23297 11588 23297 11581 23298 11588 23298 11579 23298 11579 23299 11588 23299 11589 23299 11579 23300 11589 23300 11591 23300 7513 23301 7516 23301 11589 23301 11589 23302 7516 23302 11590 23302 11589 23303 11590 23303 11591 23303 6459 23304 6458 23304 11592 23304 11592 23305 6458 23305 11595 23305 11592 23306 11595 23306 11601 23306 11601 23307 11595 23307 11597 23307 11601 23308 11597 23308 11602 23308 11602 23309 11597 23309 11593 23309 11602 23310 11593 23310 11594 23310 11594 23311 11593 23311 11598 23311 6458 23312 11596 23312 11595 23312 11595 23313 11596 23313 11607 23313 11595 23314 11607 23314 11597 23314 11597 23315 11607 23315 11610 23315 11597 23316 11610 23316 11593 23316 11593 23317 11610 23317 11599 23317 11593 23318 11599 23318 11598 23318 11598 23319 11599 23319 11603 23319 11585 23320 6459 23320 11600 23320 11600 23321 6459 23321 11592 23321 11600 23322 11592 23322 11587 23322 11587 23323 11592 23323 11601 23323 11587 23324 11601 23324 11588 23324 11588 23325 11601 23325 11602 23325 11588 23326 11602 23326 11589 23326 11589 23327 11602 23327 11594 23327 11589 23328 11594 23328 7513 23328 7513 23329 11594 23329 11598 23329 7513 23330 11598 23330 7512 23330 7512 23331 11598 23331 11603 23331 7509 23332 7511 23332 11603 23332 11603 23333 7511 23333 11604 23333 11603 23334 11604 23334 7512 23334 11609 23335 11608 23335 11615 23335 11615 23336 11614 23336 11609 23336 11609 23337 11614 23337 11605 23337 11609 23338 11605 23338 11611 23338 11611 23339 11605 23339 11620 23339 11611 23340 11620 23340 11606 23340 11616 23341 11612 23341 11617 23341 11617 23342 11612 23342 11606 23342 11617 23343 11606 23343 11619 23343 11619 23344 11606 23344 11620 23344 11596 23345 11608 23345 11607 23345 11607 23346 11608 23346 11609 23346 11607 23347 11609 23347 11610 23347 11610 23348 11609 23348 11611 23348 11610 23349 11611 23349 11599 23349 11599 23350 11611 23350 11606 23350 11599 23351 11606 23351 11603 23351 11603 23352 11606 23352 11612 23352 11603 23353 11612 23353 7509 23353 7509 23354 11612 23354 11616 23354 7509 23355 11616 23355 7508 23355 11613 23356 11605 23356 11614 23356 11613 23357 11614 23357 6405 23357 6405 23358 11614 23358 11615 23358 7508 23359 11616 23359 5862 23359 5862 23360 11616 23360 11618 23360 11616 23361 11617 23361 11618 23361 11618 23362 11617 23362 11619 23362 11618 23363 11619 23363 11613 23363 11613 23364 11619 23364 11620 23364 11613 23365 11620 23365 11605 23365 7393 23366 11621 23366 11622 23366 11622 23367 11621 23367 11623 23367 11622 23368 11623 23368 11625 23368 11625 23369 11623 23369 11671 23369 11625 23370 11671 23370 11627 23370 11627 23371 11671 23371 11673 23371 11627 23372 11673 23372 11628 23372 11628 23373 11673 23373 11674 23373 11628 23374 11674 23374 11629 23374 11629 23375 11674 23375 6456 23375 7391 23376 7393 23376 11624 23376 11624 23377 7393 23377 11622 23377 11624 23378 11622 23378 11573 23378 11573 23379 11622 23379 11625 23379 11573 23380 11625 23380 11626 23380 11626 23381 11625 23381 11627 23381 11626 23382 11627 23382 11576 23382 11576 23383 11627 23383 11628 23383 11576 23384 11628 23384 11578 23384 11578 23385 11628 23385 11629 23385 11682 23386 11681 23386 11636 23386 11630 23387 11677 23387 11631 23387 11613 23388 6405 23388 11632 23388 11618 23389 11613 23389 11633 23389 5862 23390 11618 23390 11635 23390 11613 23391 11632 23391 11633 23391 11633 23392 11632 23392 11634 23392 11633 23393 11634 23393 11631 23393 11631 23394 11634 23394 11676 23394 11631 23395 11676 23395 11630 23395 11618 23396 11633 23396 11635 23396 11635 23397 11633 23397 11631 23397 11635 23398 11631 23398 11636 23398 11636 23399 11631 23399 11677 23399 11636 23400 11677 23400 11682 23400 5862 23401 11635 23401 5861 23401 5861 23402 11635 23402 11636 23402 5861 23403 11636 23403 5859 23403 5859 23404 11636 23404 11681 23404 5859 23405 11681 23405 11680 23405 11641 23406 11639 23406 11637 23406 11689 23407 11687 23407 11638 23407 11687 23408 11686 23408 11643 23408 11689 23409 11638 23409 11691 23409 11639 23410 11691 23410 11640 23410 11641 23411 11637 23411 11642 23411 5846 23412 11642 23412 11666 23412 11687 23413 11643 23413 11638 23413 11638 23414 11643 23414 11644 23414 11638 23415 11644 23415 11645 23415 11645 23416 11644 23416 11646 23416 11645 23417 11646 23417 11650 23417 11650 23418 11646 23418 6444 23418 11650 23419 6444 23419 11647 23419 11647 23420 6444 23420 11648 23420 11647 23421 11648 23421 11652 23421 11691 23422 11638 23422 11640 23422 11640 23423 11638 23423 11645 23423 11640 23424 11645 23424 11649 23424 11649 23425 11645 23425 11650 23425 11649 23426 11650 23426 11653 23426 11653 23427 11650 23427 11647 23427 11653 23428 11647 23428 11651 23428 11651 23429 11647 23429 11652 23429 11651 23430 11652 23430 11670 23430 11639 23431 11640 23431 11637 23431 11637 23432 11640 23432 11649 23432 11637 23433 11649 23433 11655 23433 11655 23434 11649 23434 11653 23434 11655 23435 11653 23435 11654 23435 11654 23436 11653 23436 11651 23436 11654 23437 11651 23437 11656 23437 11656 23438 11651 23438 11670 23438 11656 23439 11670 23439 11668 23439 11642 23440 11637 23440 11666 23440 11666 23441 11637 23441 11655 23441 11666 23442 11655 23442 11664 23442 11664 23443 11655 23443 11654 23443 11664 23444 11654 23444 11662 23444 11662 23445 11654 23445 11656 23445 11662 23446 11656 23446 11657 23446 11657 23447 11656 23447 11668 23447 11657 23448 11668 23448 11659 23448 7518 23449 11658 23449 11659 23449 11659 23450 11658 23450 11660 23450 11659 23451 11660 23451 11657 23451 11657 23452 11660 23452 11661 23452 11657 23453 11661 23453 11662 23453 11662 23454 11661 23454 11663 23454 11662 23455 11663 23455 11664 23455 11664 23456 11663 23456 7521 23456 11664 23457 7521 23457 11666 23457 11666 23458 7521 23458 11665 23458 11666 23459 11665 23459 5846 23459 7517 23460 7518 23460 11667 23460 11667 23461 7518 23461 11659 23461 11667 23462 11659 23462 11672 23462 11672 23463 11659 23463 11668 23463 11672 23464 11668 23464 11669 23464 11669 23465 11668 23465 11670 23465 11669 23466 11670 23466 11675 23466 11675 23467 11670 23467 11652 23467 11675 23468 11652 23468 6457 23468 6457 23469 11652 23469 11648 23469 11621 23470 7517 23470 11623 23470 11623 23471 7517 23471 11667 23471 11623 23472 11667 23472 11671 23472 11671 23473 11667 23473 11672 23473 11671 23474 11672 23474 11673 23474 11673 23475 11672 23475 11669 23475 11673 23476 11669 23476 11674 23476 11674 23477 11669 23477 11675 23477 11674 23478 11675 23478 6456 23478 6456 23479 11675 23479 6457 23479 11676 23480 6327 23480 11630 23480 11630 23481 6327 23481 11685 23481 11630 23482 11685 23482 11677 23482 11677 23483 11685 23483 11678 23483 5857 23484 11680 23484 11679 23484 11679 23485 11680 23485 11681 23485 11679 23486 11681 23486 11678 23486 11678 23487 11681 23487 11682 23487 11678 23488 11682 23488 11677 23488 11695 23489 5857 23489 11683 23489 11683 23490 5857 23490 11679 23490 11683 23491 11679 23491 11696 23491 11696 23492 11679 23492 11678 23492 11696 23493 11678 23493 11684 23493 11684 23494 11678 23494 11685 23494 11684 23495 11685 23495 6326 23495 6326 23496 11685 23496 6327 23496 6406 23497 11686 23497 11688 23497 11686 23498 11687 23498 11688 23498 11688 23499 11687 23499 11689 23499 11688 23500 11689 23500 11690 23500 11690 23501 11689 23501 11691 23501 11690 23502 11691 23502 11692 23502 11692 23503 11691 23503 11639 23503 11692 23504 11639 23504 11693 23504 11639 23505 11641 23505 11693 23505 11693 23506 11641 23506 11642 23506 11693 23507 11642 23507 11694 23507 11694 23508 11642 23508 5846 23508 11694 23509 5846 23509 11716 23509 6020 23510 6021 23510 11698 23510 6023 23511 11695 23511 11699 23511 11699 23512 11695 23512 11683 23512 11699 23513 11683 23513 11697 23513 11697 23514 11683 23514 11696 23514 11697 23515 11696 23515 11702 23515 11702 23516 11696 23516 11684 23516 11702 23517 11684 23517 6325 23517 6325 23518 11684 23518 6326 23518 6021 23519 6023 23519 11698 23519 11698 23520 6023 23520 11699 23520 11698 23521 11699 23521 11700 23521 11700 23522 11699 23522 11697 23522 11700 23523 11697 23523 11701 23523 11701 23524 11697 23524 11702 23524 11701 23525 11702 23525 6323 23525 6323 23526 11702 23526 6325 23526 11703 23527 6020 23527 11707 23527 11707 23528 6020 23528 11698 23528 11707 23529 11698 23529 11704 23529 11704 23530 11698 23530 11700 23530 11704 23531 11700 23531 11709 23531 11709 23532 11700 23532 11701 23532 11709 23533 11701 23533 11705 23533 11705 23534 11701 23534 6323 23534 11712 23535 11703 23535 11706 23535 11706 23536 11703 23536 11707 23536 11706 23537 11707 23537 11714 23537 11714 23538 11707 23538 11704 23538 11714 23539 11704 23539 11708 23539 11708 23540 11704 23540 11709 23540 11708 23541 11709 23541 11710 23541 11710 23542 11709 23542 11705 23542 11735 23543 11712 23543 11711 23543 11711 23544 11712 23544 11706 23544 11711 23545 11706 23545 11713 23545 11713 23546 11706 23546 11714 23546 11713 23547 11714 23547 11734 23547 11734 23548 11714 23548 11708 23548 11734 23549 11708 23549 6316 23549 6316 23550 11708 23550 11710 23550 11688 23551 11690 23551 11721 23551 11692 23552 11693 23552 11715 23552 11694 23553 11716 23553 5849 23553 11731 23554 11732 23554 11722 23554 11722 23555 11732 23555 6319 23555 11727 23556 11717 23556 11724 23556 11724 23557 11717 23557 11730 23557 11724 23558 11730 23558 11723 23558 11725 23559 5850 23559 11727 23559 11692 23560 11715 23560 11690 23560 6319 23561 6407 23561 11722 23561 11722 23562 6407 23562 6408 23562 11722 23563 6408 23563 11719 23563 11719 23564 6408 23564 11718 23564 11719 23565 11718 23565 11721 23565 11721 23566 11718 23566 6406 23566 11721 23567 6406 23567 11688 23567 11690 23568 11715 23568 11721 23568 11721 23569 11715 23569 11720 23569 11721 23570 11720 23570 11719 23570 11719 23571 11720 23571 11724 23571 11719 23572 11724 23572 11722 23572 11722 23573 11724 23573 11723 23573 11722 23574 11723 23574 11731 23574 11727 23575 11724 23575 11725 23575 11725 23576 11724 23576 11720 23576 11725 23577 11720 23577 5852 23577 5852 23578 11720 23578 11715 23578 5852 23579 11715 23579 5849 23579 5849 23580 11715 23580 11693 23580 5849 23581 11693 23581 11694 23581 5850 23582 11726 23582 11727 23582 11727 23583 11726 23583 11728 23583 11727 23584 11728 23584 11717 23584 11717 23585 11728 23585 11730 23585 11730 23586 11728 23586 11729 23586 11730 23587 11729 23587 11723 23587 11723 23588 11729 23588 11731 23588 11731 23589 11729 23589 11733 23589 11731 23590 11733 23590 11732 23590 11732 23591 11733 23591 6317 23591 11732 23592 6317 23592 6319 23592 6316 23593 6317 23593 11734 23593 11734 23594 6317 23594 11733 23594 11734 23595 11733 23595 11713 23595 11713 23596 11733 23596 11729 23596 11713 23597 11729 23597 11711 23597 11711 23598 11729 23598 11728 23598 11711 23599 11728 23599 11735 23599 11735 23600 11728 23600 11726 23600 11741 23601 11760 23601 11763 23601 11751 23602 11736 23602 11753 23602 11753 23603 11736 23603 11737 23603 11753 23604 11737 23604 11750 23604 11752 23605 11738 23605 11751 23605 11740 23606 11739 23606 11747 23606 11747 23607 11739 23607 11757 23607 11744 23608 11746 23608 11740 23608 11743 23609 11755 23609 11745 23609 11763 23610 6404 23610 11741 23610 11741 23611 6404 23611 11742 23611 11741 23612 11742 23612 11749 23612 11749 23613 11742 23613 11743 23613 11749 23614 11743 23614 11744 23614 11744 23615 11743 23615 11745 23615 11744 23616 11745 23616 11746 23616 11740 23617 11747 23617 11744 23617 11744 23618 11747 23618 11748 23618 11744 23619 11748 23619 11749 23619 11749 23620 11748 23620 11753 23620 11749 23621 11753 23621 11741 23621 11741 23622 11753 23622 11750 23622 11741 23623 11750 23623 11760 23623 11751 23624 11753 23624 11752 23624 11752 23625 11753 23625 11748 23625 11752 23626 11748 23626 5525 23626 5525 23627 11748 23627 11747 23627 5525 23628 11747 23628 11754 23628 11754 23629 11747 23629 11757 23629 11754 23630 11757 23630 5517 23630 11745 23631 11755 23631 6309 23631 11745 23632 6309 23632 11746 23632 11746 23633 6309 23633 11758 23633 11746 23634 11758 23634 11740 23634 11740 23635 11758 23635 11756 23635 11740 23636 11756 23636 11739 23636 11739 23637 11756 23637 11757 23637 11757 23638 11756 23638 5515 23638 11757 23639 5515 23639 5517 23639 11771 23640 5515 23640 11765 23640 11765 23641 5515 23641 11756 23641 11765 23642 11756 23642 11780 23642 11780 23643 11756 23643 11758 23643 11780 23644 11758 23644 6308 23644 6308 23645 11758 23645 6309 23645 11738 23646 5528 23646 11751 23646 11751 23647 5528 23647 11759 23647 11751 23648 11759 23648 11736 23648 11736 23649 11759 23649 11737 23649 11737 23650 11759 23650 11832 23650 11737 23651 11832 23651 11750 23651 11750 23652 11832 23652 11761 23652 11750 23653 11761 23653 11760 23653 11760 23654 11761 23654 11762 23654 11760 23655 11762 23655 11763 23655 6009 23656 11764 23656 11783 23656 11780 23657 6308 23657 11779 23657 11771 23658 11765 23658 11772 23658 11779 23659 11775 23659 11766 23659 11766 23660 11775 23660 11767 23660 11766 23661 11767 23661 11768 23661 11768 23662 11767 23662 11770 23662 11768 23663 11770 23663 11769 23663 11769 23664 11770 23664 11778 23664 11771 23665 11772 23665 11773 23665 11773 23666 11772 23666 11782 23666 11773 23667 11782 23667 11774 23667 11775 23668 11789 23668 11767 23668 11767 23669 11789 23669 11776 23669 11767 23670 11776 23670 11770 23670 11770 23671 11776 23671 11777 23671 11770 23672 11777 23672 11778 23672 11778 23673 11777 23673 11781 23673 11779 23674 11766 23674 11780 23674 11780 23675 11766 23675 11768 23675 11780 23676 11768 23676 11765 23676 11765 23677 11768 23677 11769 23677 11765 23678 11769 23678 11772 23678 11772 23679 11769 23679 11778 23679 11772 23680 11778 23680 11782 23680 11782 23681 11778 23681 11781 23681 11782 23682 11781 23682 11783 23682 11783 23683 11764 23683 11782 23683 11782 23684 11764 23684 11784 23684 11782 23685 11784 23685 11774 23685 6007 23686 6009 23686 11785 23686 11785 23687 6009 23687 11783 23687 11785 23688 11783 23688 11791 23688 11791 23689 11783 23689 11781 23689 11791 23690 11781 23690 11786 23690 11786 23691 11781 23691 11777 23691 11786 23692 11777 23692 11787 23692 11787 23693 11777 23693 11776 23693 11787 23694 11776 23694 11788 23694 11788 23695 11776 23695 11789 23695 11796 23696 6007 23696 11790 23696 11790 23697 6007 23697 11785 23697 11790 23698 11785 23698 11794 23698 11794 23699 11785 23699 11791 23699 11794 23700 11791 23700 11793 23700 11793 23701 11791 23701 11786 23701 11793 23702 11786 23702 11792 23702 11792 23703 11786 23703 11787 23703 11792 23704 11787 23704 6314 23704 6314 23705 11787 23705 11788 23705 6314 23706 6312 23706 11792 23706 11792 23707 6312 23707 11800 23707 11792 23708 11800 23708 11793 23708 11793 23709 11800 23709 11802 23709 11793 23710 11802 23710 11794 23710 11794 23711 11802 23711 11803 23711 11794 23712 11803 23712 11790 23712 11790 23713 11803 23713 11805 23713 11790 23714 11805 23714 11796 23714 6004 23715 11795 23715 11805 23715 11805 23716 11795 23716 6005 23716 11805 23717 6005 23717 11796 23717 11836 23718 11806 23718 11797 23718 11797 23719 11806 23719 11798 23719 11797 23720 11798 23720 11837 23720 11837 23721 11798 23721 11804 23721 11837 23722 11804 23722 11840 23722 11840 23723 11804 23723 11801 23723 11840 23724 11801 23724 6310 23724 6310 23725 11801 23725 11799 23725 6312 23726 11799 23726 11800 23726 11800 23727 11799 23727 11801 23727 11800 23728 11801 23728 11802 23728 11802 23729 11801 23729 11804 23729 11802 23730 11804 23730 11803 23730 11803 23731 11804 23731 11798 23731 11803 23732 11798 23732 11805 23732 11805 23733 11798 23733 11806 23733 11805 23734 11806 23734 6004 23734 6004 23735 11806 23735 11836 23735 6004 23736 11836 23736 6003 23736 11807 23737 11825 23737 11824 23737 11808 23738 11859 23738 6463 23738 11810 23739 11808 23739 11815 23739 11809 23740 11810 23740 11818 23740 11811 23741 11809 23741 11822 23741 11811 23742 11822 23742 11812 23742 11812 23743 11822 23743 11813 23743 11812 23744 11813 23744 11814 23744 11814 23745 11813 23745 11826 23745 11814 23746 11826 23746 7506 23746 11808 23747 6463 23747 11815 23747 11815 23748 6463 23748 11816 23748 11815 23749 11816 23749 11819 23749 11819 23750 11816 23750 6465 23750 11819 23751 6465 23751 11817 23751 11817 23752 6465 23752 11831 23752 11817 23753 11831 23753 11821 23753 11810 23754 11815 23754 11818 23754 11818 23755 11815 23755 11819 23755 11818 23756 11819 23756 11823 23756 11823 23757 11819 23757 11817 23757 11823 23758 11817 23758 11820 23758 11820 23759 11817 23759 11821 23759 11820 23760 11821 23760 11829 23760 11809 23761 11818 23761 11822 23761 11822 23762 11818 23762 11823 23762 11822 23763 11823 23763 11813 23763 11813 23764 11823 23764 11820 23764 11813 23765 11820 23765 11826 23765 11826 23766 11820 23766 11829 23766 11826 23767 11829 23767 11824 23767 11824 23768 11825 23768 11826 23768 11826 23769 11825 23769 7504 23769 11826 23770 7504 23770 7506 23770 11827 23771 11807 23771 11828 23771 11828 23772 11807 23772 11824 23772 11828 23773 11824 23773 11833 23773 11833 23774 11824 23774 11829 23774 11833 23775 11829 23775 11834 23775 11834 23776 11829 23776 11821 23776 11834 23777 11821 23777 11830 23777 11830 23778 11821 23778 11831 23778 5528 23779 11827 23779 11759 23779 11759 23780 11827 23780 11828 23780 11759 23781 11828 23781 11832 23781 11832 23782 11828 23782 11833 23782 11832 23783 11833 23783 11761 23783 11761 23784 11833 23784 11834 23784 11761 23785 11834 23785 11762 23785 11762 23786 11834 23786 11830 23786 5870 23787 6003 23787 11835 23787 11835 23788 6003 23788 11836 23788 11835 23789 11836 23789 11844 23789 11844 23790 11836 23790 11797 23790 11844 23791 11797 23791 11838 23791 11838 23792 11797 23792 11837 23792 11838 23793 11837 23793 11839 23793 11839 23794 11837 23794 11840 23794 11839 23795 11840 23795 11841 23795 11841 23796 11840 23796 6310 23796 5869 23797 5870 23797 11842 23797 11842 23798 5870 23798 11835 23798 11842 23799 11835 23799 11843 23799 11843 23800 11835 23800 11844 23800 11843 23801 11844 23801 11845 23801 11845 23802 11844 23802 11838 23802 11845 23803 11838 23803 11846 23803 11846 23804 11838 23804 11839 23804 11846 23805 11839 23805 11847 23805 11847 23806 11839 23806 11841 23806 6015 23807 5869 23807 11848 23807 11848 23808 5869 23808 11842 23808 11848 23809 11842 23809 11849 23809 11849 23810 11842 23810 11843 23810 11849 23811 11843 23811 11862 23811 11862 23812 11843 23812 11845 23812 11862 23813 11845 23813 11892 23813 11892 23814 11845 23814 11846 23814 11892 23815 11846 23815 6377 23815 6377 23816 11846 23816 11847 23816 11850 23817 11851 23817 11852 23817 11852 23818 11851 23818 11894 23818 11894 23819 11851 23819 11895 23819 11895 23820 11851 23820 11858 23820 11895 23821 11858 23821 11853 23821 11853 23822 11858 23822 11854 23822 11854 23823 11858 23823 11856 23823 11854 23824 11856 23824 11896 23824 11896 23825 11856 23825 11855 23825 11855 23826 11856 23826 11857 23826 11855 23827 11857 23827 11898 23827 11811 23828 11857 23828 11809 23828 11809 23829 11857 23829 11856 23829 11809 23830 11856 23830 11810 23830 11810 23831 11856 23831 11858 23831 11810 23832 11858 23832 11808 23832 11808 23833 11858 23833 11851 23833 11808 23834 11851 23834 11859 23834 11859 23835 11851 23835 11850 23835 11869 23836 11867 23836 11864 23836 11867 23837 11860 23837 11888 23837 11892 23838 6377 23838 11861 23838 11862 23839 11863 23839 11849 23839 11849 23840 11863 23840 11866 23840 11849 23841 11866 23841 11848 23841 11848 23842 11866 23842 11868 23842 11848 23843 11868 23843 6015 23843 11870 23844 6017 23844 11868 23844 11868 23845 6017 23845 6016 23845 11868 23846 6016 23846 6015 23846 11867 23847 11888 23847 11864 23847 11864 23848 11888 23848 11887 23848 11864 23849 11887 23849 11865 23849 11865 23850 11887 23850 11879 23850 11865 23851 11879 23851 11878 23851 11869 23852 11864 23852 11871 23852 11871 23853 11864 23853 11865 23853 11871 23854 11865 23854 11872 23854 11872 23855 11865 23855 11878 23855 11872 23856 11878 23856 11875 23856 11863 23857 11860 23857 11866 23857 11866 23858 11860 23858 11867 23858 11866 23859 11867 23859 11868 23859 11868 23860 11867 23860 11869 23860 11868 23861 11869 23861 11870 23861 11870 23862 11869 23862 11871 23862 11870 23863 11871 23863 6014 23863 6014 23864 11871 23864 11872 23864 6014 23865 11872 23865 6012 23865 6012 23866 11872 23866 11875 23866 6012 23867 11875 23867 11873 23867 11873 23868 11875 23868 6010 23868 11874 23869 6010 23869 11876 23869 11876 23870 6010 23870 11875 23870 11876 23871 11875 23871 11877 23871 11877 23872 11875 23872 11878 23872 11877 23873 11878 23873 11893 23873 11893 23874 11878 23874 11879 23874 11892 23875 11861 23875 11891 23875 11891 23876 11861 23876 11880 23876 11891 23877 11880 23877 11890 23877 11890 23878 11880 23878 6321 23878 11890 23879 6321 23879 11889 23879 11889 23880 6321 23880 6324 23880 11889 23881 6324 23881 11881 23881 11881 23882 6324 23882 11882 23882 11881 23883 11882 23883 11886 23883 11886 23884 11882 23884 11883 23884 11886 23885 11883 23885 11885 23885 11885 23886 11883 23886 6328 23886 11885 23887 6328 23887 11884 23887 11884 23888 11893 23888 11885 23888 11885 23889 11893 23889 11879 23889 11885 23890 11879 23890 11886 23890 11886 23891 11879 23891 11887 23891 11886 23892 11887 23892 11881 23892 11881 23893 11887 23893 11888 23893 11881 23894 11888 23894 11889 23894 11889 23895 11888 23895 11860 23895 11889 23896 11860 23896 11890 23896 11890 23897 11860 23897 11863 23897 11890 23898 11863 23898 11891 23898 11891 23899 11863 23899 11862 23899 11891 23900 11862 23900 11892 23900 11909 23901 11874 23901 11910 23901 11910 23902 11874 23902 11876 23902 11910 23903 11876 23903 11911 23903 11911 23904 11876 23904 11877 23904 11911 23905 11877 23905 11914 23905 11914 23906 11877 23906 11893 23906 11914 23907 11893 23907 11908 23907 11908 23908 11893 23908 11884 23908 11899 23909 11852 23909 11901 23909 11901 23910 11852 23910 11894 23910 11894 23911 11895 23911 11901 23911 11901 23912 11895 23912 11853 23912 11901 23913 11853 23913 11902 23913 11902 23914 11853 23914 11854 23914 11902 23915 11854 23915 11904 23915 11904 23916 11854 23916 11896 23916 11904 23917 11896 23917 11897 23917 11897 23918 11896 23918 11855 23918 11897 23919 11855 23919 11898 23919 11905 23920 11899 23920 11900 23920 11900 23921 11899 23921 11901 23921 11900 23922 11901 23922 11907 23922 11907 23923 11901 23923 11902 23923 11907 23924 11902 23924 11903 23924 11903 23925 11902 23925 11904 23925 11903 23926 11904 23926 5873 23926 5873 23927 11904 23927 11897 23927 6329 23928 11905 23928 11906 23928 11906 23929 11905 23929 11900 23929 11906 23930 11900 23930 11913 23930 11913 23931 11900 23931 11907 23931 11913 23932 11907 23932 11912 23932 11912 23933 11907 23933 11903 23933 11912 23934 11903 23934 5876 23934 5876 23935 11903 23935 5873 23935 11912 23936 5876 23936 11909 23936 6328 23937 6329 23937 11884 23937 11884 23938 6329 23938 11906 23938 11884 23939 11906 23939 11908 23939 11908 23940 11906 23940 11913 23940 11909 23941 11910 23941 11912 23941 11912 23942 11910 23942 11911 23942 11912 23943 11911 23943 11913 23943 11913 23944 11911 23944 11914 23944 11913 23945 11914 23945 11908 23945 11919 23946 7495 23946 11920 23946 11920 23947 7495 23947 11981 23947 11920 23948 11981 23948 11921 23948 11921 23949 11981 23949 11982 23949 11921 23950 11982 23950 11915 23950 11915 23951 11982 23951 11916 23951 11915 23952 11916 23952 11923 23952 11923 23953 11916 23953 11917 23953 11923 23954 11917 23954 6473 23954 6473 23955 11917 23955 11983 23955 11918 23956 11919 23956 11928 23956 11928 23957 11919 23957 11920 23957 11928 23958 11920 23958 11927 23958 11927 23959 11920 23959 11921 23959 11927 23960 11921 23960 11924 23960 11924 23961 11921 23961 11915 23961 11924 23962 11915 23962 11922 23962 11922 23963 11915 23963 11923 23963 11922 23964 11923 23964 6472 23964 6472 23965 11923 23965 6473 23965 6472 23966 6470 23966 11922 23966 11922 23967 6470 23967 11940 23967 11922 23968 11940 23968 11924 23968 11924 23969 11940 23969 11925 23969 11924 23970 11925 23970 11927 23970 11927 23971 11925 23971 11926 23971 11927 23972 11926 23972 11928 23972 11928 23973 11926 23973 11929 23973 11928 23974 11929 23974 11918 23974 7493 23975 7496 23975 11929 23975 11929 23976 7496 23976 11930 23976 11929 23977 11930 23977 11918 23977 6471 23978 6468 23978 11931 23978 11931 23979 6468 23979 11934 23979 11931 23980 11934 23980 11941 23980 11941 23981 11934 23981 11936 23981 11941 23982 11936 23982 11942 23982 11942 23983 11936 23983 11938 23983 11942 23984 11938 23984 11943 23984 11943 23985 11938 23985 11932 23985 6468 23986 11933 23986 11934 23986 11934 23987 11933 23987 11935 23987 11934 23988 11935 23988 11936 23988 11936 23989 11935 23989 11937 23989 11936 23990 11937 23990 11938 23990 11938 23991 11937 23991 11939 23991 11938 23992 11939 23992 11932 23992 11932 23993 11939 23993 11944 23993 6470 23994 6471 23994 11940 23994 11940 23995 6471 23995 11931 23995 11940 23996 11931 23996 11925 23996 11925 23997 11931 23997 11941 23997 11925 23998 11941 23998 11926 23998 11926 23999 11941 23999 11942 23999 11926 24000 11942 24000 11929 24000 11929 24001 11942 24001 11943 24001 11929 24002 11943 24002 7493 24002 7493 24003 11943 24003 11932 24003 7493 24004 11932 24004 7494 24004 7494 24005 11932 24005 11944 24005 7492 24006 11945 24006 11944 24006 11944 24007 11945 24007 11946 24007 11944 24008 11946 24008 7494 24008 11955 24009 11947 24009 11948 24009 11948 24010 11964 24010 11955 24010 11955 24011 11964 24011 11949 24011 11955 24012 11949 24012 11950 24012 11950 24013 11949 24013 11962 24013 11950 24014 11962 24014 11954 24014 11951 24015 11952 24015 11953 24015 11953 24016 11952 24016 11954 24016 11953 24017 11954 24017 11963 24017 11963 24018 11954 24018 11962 24018 11933 24019 11947 24019 11935 24019 11935 24020 11947 24020 11955 24020 11935 24021 11955 24021 11937 24021 11937 24022 11955 24022 11950 24022 11937 24023 11950 24023 11939 24023 11939 24024 11950 24024 11954 24024 11939 24025 11954 24025 11944 24025 11944 24026 11954 24026 11952 24026 11944 24027 11952 24027 7492 24027 7492 24028 11952 24028 11951 24028 7492 24029 11951 24029 11956 24029 11987 24030 5477 24030 11961 24030 12000 24031 11958 24031 11957 24031 11957 24032 11958 24032 11959 24032 11957 24033 11959 24033 11985 24033 6480 24034 6478 24034 11960 24034 6480 24035 11960 24035 11959 24035 11959 24036 11960 24036 11985 24036 11956 24037 11951 24037 11961 24037 11961 24038 11951 24038 11958 24038 11961 24039 11958 24039 11987 24039 11987 24040 11958 24040 12000 24040 11962 24041 11959 24041 11963 24041 11963 24042 11959 24042 11958 24042 11963 24043 11958 24043 11953 24043 11953 24044 11958 24044 11951 24044 11948 24045 6480 24045 11964 24045 11964 24046 6480 24046 11959 24046 11964 24047 11959 24047 11949 24047 11949 24048 11959 24048 11962 24048 11972 24049 7497 24049 11965 24049 11965 24050 7497 24050 11966 24050 11965 24051 11966 24051 11967 24051 11967 24052 11966 24052 11968 24052 11967 24053 11968 24053 11969 24053 11969 24054 11968 24054 12033 24054 11969 24055 12033 24055 11974 24055 11974 24056 12033 24056 11970 24056 11974 24057 11970 24057 6477 24057 6477 24058 11970 24058 12035 24058 11971 24059 11972 24059 11973 24059 11973 24060 11972 24060 11965 24060 11973 24061 11965 24061 11975 24061 11975 24062 11965 24062 11967 24062 11975 24063 11967 24063 11978 24063 11978 24064 11967 24064 11969 24064 11978 24065 11969 24065 11979 24065 11979 24066 11969 24066 11974 24066 11979 24067 11974 24067 6476 24067 6476 24068 11974 24068 6477 24068 7377 24069 11971 24069 11980 24069 11980 24070 11971 24070 11973 24070 11980 24071 11973 24071 11976 24071 11976 24072 11973 24072 11975 24072 11976 24073 11975 24073 11977 24073 11977 24074 11975 24074 11978 24074 11977 24075 11978 24075 11984 24075 11984 24076 11978 24076 11979 24076 11984 24077 11979 24077 6474 24077 6474 24078 11979 24078 6476 24078 7495 24079 7377 24079 11981 24079 11981 24080 7377 24080 11980 24080 11981 24081 11980 24081 11982 24081 11982 24082 11980 24082 11976 24082 11982 24083 11976 24083 11916 24083 11916 24084 11976 24084 11977 24084 11916 24085 11977 24085 11917 24085 11917 24086 11977 24086 11984 24086 11917 24087 11984 24087 11983 24087 11983 24088 11984 24088 6474 24088 11990 24089 11994 24089 11996 24089 11960 24090 6478 24090 6411 24090 11991 24091 11985 24091 11960 24091 11986 24092 12000 24092 11957 24092 5479 24093 5477 24093 11987 24093 11994 24094 12039 24094 11995 24094 11995 24095 12039 24095 11988 24095 11995 24096 11988 24096 11989 24096 11990 24097 11996 24097 12037 24097 11960 24098 6411 24098 11991 24098 11991 24099 6411 24099 11992 24099 11991 24100 11992 24100 11993 24100 11993 24101 11992 24101 6412 24101 11993 24102 6412 24102 11996 24102 11996 24103 6412 24103 12037 24103 11994 24104 11995 24104 11996 24104 11996 24105 11995 24105 11997 24105 11996 24106 11997 24106 11993 24106 11993 24107 11997 24107 11986 24107 11993 24108 11986 24108 11991 24108 11991 24109 11986 24109 11957 24109 11991 24110 11957 24110 11985 24110 11989 24111 11998 24111 11995 24111 11995 24112 11998 24112 11999 24112 11995 24113 11999 24113 11997 24113 11997 24114 11999 24114 5479 24114 11997 24115 5479 24115 11986 24115 11986 24116 5479 24116 11987 24116 11986 24117 11987 24117 12000 24117 7501 24118 12025 24118 12001 24118 7498 24119 7502 24119 12014 24119 12011 24120 12050 24120 12013 24120 12013 24121 12050 24121 12002 24121 12013 24122 12002 24122 12003 24122 12003 24123 12002 24123 12004 24123 7503 24124 5476 24124 12008 24124 12008 24125 5476 24125 12005 24125 12008 24126 12005 24126 12006 24126 12006 24127 12005 24127 12053 24127 12006 24128 12053 24128 12011 24128 12011 24129 12053 24129 12007 24129 12011 24130 12007 24130 12050 24130 12015 24131 7503 24131 12016 24131 12016 24132 7503 24132 12008 24132 12016 24133 12008 24133 12009 24133 12009 24134 12008 24134 12006 24134 12009 24135 12006 24135 12010 24135 12010 24136 12006 24136 12011 24136 12010 24137 12011 24137 12012 24137 12012 24138 12011 24138 12013 24138 12012 24139 12013 24139 12019 24139 12019 24140 12013 24140 12003 24140 7502 24141 12015 24141 12014 24141 12014 24142 12015 24142 12016 24142 12014 24143 12016 24143 12022 24143 12022 24144 12016 24144 12009 24144 12022 24145 12009 24145 12017 24145 12017 24146 12009 24146 12010 24146 12017 24147 12010 24147 12018 24147 12018 24148 12010 24148 12012 24148 12018 24149 12012 24149 6461 24149 6461 24150 12012 24150 12019 24150 7499 24151 7498 24151 12020 24151 12020 24152 7498 24152 12014 24152 12020 24153 12014 24153 12021 24153 12021 24154 12014 24154 12022 24154 12021 24155 12022 24155 12023 24155 12023 24156 12022 24156 12017 24156 12023 24157 12017 24157 12024 24157 12024 24158 12017 24158 12018 24158 12024 24159 12018 24159 6466 24159 6466 24160 12018 24160 6461 24160 12025 24161 7499 24161 12001 24161 12001 24162 7499 24162 12020 24162 12001 24163 12020 24163 12026 24163 12026 24164 12020 24164 12021 24164 12026 24165 12021 24165 12027 24165 12027 24166 12021 24166 12023 24166 12027 24167 12023 24167 12028 24167 12028 24168 12023 24168 12024 24168 12028 24169 12024 24169 6467 24169 6467 24170 12024 24170 6466 24170 12029 24171 7501 24171 12030 24171 12030 24172 7501 24172 12001 24172 12030 24173 12001 24173 12031 24173 12031 24174 12001 24174 12026 24174 12031 24175 12026 24175 12034 24175 12034 24176 12026 24176 12027 24176 12034 24177 12027 24177 12032 24177 12032 24178 12027 24178 12028 24178 12032 24179 12028 24179 12036 24179 12036 24180 12028 24180 6467 24180 7497 24181 12029 24181 11966 24181 11966 24182 12029 24182 12030 24182 11966 24183 12030 24183 11968 24183 11968 24184 12030 24184 12031 24184 11968 24185 12031 24185 12033 24185 12033 24186 12031 24186 12034 24186 12033 24187 12034 24187 11970 24187 11970 24188 12034 24188 12032 24188 11970 24189 12032 24189 12035 24189 12035 24190 12032 24190 12036 24190 12046 24191 12044 24191 12037 24191 12037 24192 12044 24192 11990 24192 11990 24193 12044 24193 11994 24193 11994 24194 12044 24194 12038 24194 11994 24195 12038 24195 12039 24195 12039 24196 12038 24196 12040 24196 12039 24197 12040 24197 11988 24197 11988 24198 12040 24198 12041 24198 11988 24199 12041 24199 11989 24199 5483 24200 12041 24200 12058 24200 12058 24201 12041 24201 12040 24201 12058 24202 12040 24202 12042 24202 12042 24203 12040 24203 12038 24203 12042 24204 12038 24204 12043 24204 12043 24205 12038 24205 12044 24205 12043 24206 12044 24206 12045 24206 12045 24207 12044 24207 12046 24207 12049 24208 12094 24208 12048 24208 12078 24209 12051 24209 12088 24209 12088 24210 12051 24210 12054 24210 12088 24211 12054 24211 12077 24211 12077 24212 12054 24212 12047 24212 12047 24213 12054 24213 12052 24213 12047 24214 12052 24214 12072 24214 12048 24215 6460 24215 12049 24215 12049 24216 6460 24216 12004 24216 12049 24217 12004 24217 12002 24217 12002 24218 12050 24218 12049 24218 12049 24219 12050 24219 12051 24219 12049 24220 12051 24220 12094 24220 12094 24221 12051 24221 12078 24221 5476 24222 12052 24222 12005 24222 12005 24223 12052 24223 12054 24223 12005 24224 12054 24224 12053 24224 12053 24225 12054 24225 12051 24225 12053 24226 12051 24226 12007 24226 12007 24227 12051 24227 12050 24227 12055 24228 12056 24228 12057 24228 6000 24229 5483 24229 12060 24229 12060 24230 5483 24230 12058 24230 12060 24231 12058 24231 12061 24231 12061 24232 12058 24232 12042 24232 12061 24233 12042 24233 12059 24233 12059 24234 12042 24234 12043 24234 12059 24235 12043 24235 6303 24235 6303 24236 12043 24236 12045 24236 12056 24237 6000 24237 12057 24237 12057 24238 6000 24238 12060 24238 12057 24239 12060 24239 12064 24239 12064 24240 12060 24240 12061 24240 12064 24241 12061 24241 12065 24241 12065 24242 12061 24242 12059 24242 12065 24243 12059 24243 6300 24243 6300 24244 12059 24244 6303 24244 5998 24245 12055 24245 12062 24245 12062 24246 12055 24246 12057 24246 12062 24247 12057 24247 12063 24247 12063 24248 12057 24248 12064 24248 12063 24249 12064 24249 12067 24249 12067 24250 12064 24250 12065 24250 12067 24251 12065 24251 6298 24251 6298 24252 12065 24252 6300 24252 12068 24253 5998 24253 12069 24253 12069 24254 5998 24254 12062 24254 12069 24255 12062 24255 12070 24255 12070 24256 12062 24256 12063 24256 12070 24257 12063 24257 12066 24257 12066 24258 12063 24258 12067 24258 12066 24259 12067 24259 6305 24259 6305 24260 12067 24260 6298 24260 5996 24261 12068 24261 12104 24261 12104 24262 12068 24262 12069 24262 12104 24263 12069 24263 12071 24263 12071 24264 12069 24264 12070 24264 12071 24265 12070 24265 12103 24265 12103 24266 12070 24266 12066 24266 12103 24267 12066 24267 6306 24267 6306 24268 12066 24268 6305 24268 12047 24269 12072 24269 5474 24269 12073 24270 12102 24270 12074 24270 12075 24271 12100 24271 12089 24271 12089 24272 12100 24272 12076 24272 12089 24273 12076 24273 12102 24273 12082 24274 12096 24274 12083 24274 12047 24275 5474 24275 12077 24275 12093 24276 12094 24276 12078 24276 12079 24277 12048 24277 12094 24277 12077 24278 5474 24278 12080 24278 12080 24279 5474 24279 5473 24279 12080 24280 5473 24280 12087 24280 12087 24281 5473 24281 5470 24281 12087 24282 5470 24282 12081 24282 12081 24283 5470 24283 12082 24283 12081 24284 12082 24284 12084 24284 12084 24285 12082 24285 12083 24285 12084 24286 12083 24286 12075 24286 12075 24287 12089 24287 12084 24287 12084 24288 12089 24288 12085 24288 12084 24289 12085 24289 12081 24289 12081 24290 12085 24290 12092 24290 12081 24291 12092 24291 12087 24291 12087 24292 12092 24292 12086 24292 12087 24293 12086 24293 12080 24293 12080 24294 12086 24294 12088 24294 12080 24295 12088 24295 12077 24295 12102 24296 12073 24296 12089 24296 12089 24297 12073 24297 12090 24297 12089 24298 12090 24298 12085 24298 12085 24299 12090 24299 12091 24299 12085 24300 12091 24300 12092 24300 12092 24301 12091 24301 12093 24301 12092 24302 12093 24302 12086 24302 12086 24303 12093 24303 12078 24303 12086 24304 12078 24304 12088 24304 12094 24305 12093 24305 12079 24305 12079 24306 12093 24306 12091 24306 12079 24307 12091 24307 12095 24307 12095 24308 12091 24308 12090 24308 12095 24309 12090 24309 6403 24309 6403 24310 12090 24310 12073 24310 6403 24311 12073 24311 6402 24311 6402 24312 12073 24312 12074 24312 12096 24313 12097 24313 12083 24313 12083 24314 12097 24314 12098 24314 12083 24315 12098 24315 12075 24315 12075 24316 12098 24316 12100 24316 12100 24317 12098 24317 12099 24317 12100 24318 12099 24318 12076 24318 12076 24319 12099 24319 12101 24319 12076 24320 12101 24320 12102 24320 12102 24321 12101 24321 6307 24321 12102 24322 6307 24322 12074 24322 6306 24323 6307 24323 12103 24323 12103 24324 6307 24324 12101 24324 12103 24325 12101 24325 12071 24325 12071 24326 12101 24326 12099 24326 12071 24327 12099 24327 12104 24327 12104 24328 12099 24328 12098 24328 12104 24329 12098 24329 5996 24329 5996 24330 12098 24330 12097 24330 12136 24331 12130 24331 12131 24331 12111 24332 5995 24332 12112 24332 12112 24333 5995 24333 12106 24333 12112 24334 12106 24334 12105 24334 12105 24335 12106 24335 12107 24335 12105 24336 12107 24336 12114 24336 12114 24337 12107 24337 12144 24337 12114 24338 12144 24338 12108 24338 12108 24339 12144 24339 12110 24339 12108 24340 12110 24340 12109 24340 12109 24341 12110 24341 12146 24341 5993 24342 12111 24342 12116 24342 12116 24343 12111 24343 12112 24343 12116 24344 12112 24344 12118 24344 12118 24345 12112 24345 12105 24345 12118 24346 12105 24346 12113 24346 12113 24347 12105 24347 12114 24347 12113 24348 12114 24348 12119 24348 12119 24349 12114 24349 12108 24349 12119 24350 12108 24350 6297 24350 6297 24351 12108 24351 12109 24351 5992 24352 5993 24352 12115 24352 12115 24353 5993 24353 12116 24353 12115 24354 12116 24354 12117 24354 12117 24355 12116 24355 12118 24355 12117 24356 12118 24356 12123 24356 12123 24357 12118 24357 12113 24357 12123 24358 12113 24358 12121 24358 12121 24359 12113 24359 12119 24359 12121 24360 12119 24360 12120 24360 12120 24361 12119 24361 6297 24361 12120 24362 6299 24362 12121 24362 12121 24363 6299 24363 12122 24363 12121 24364 12122 24364 12123 24364 12123 24365 12122 24365 12134 24365 12123 24366 12134 24366 12117 24366 12117 24367 12134 24367 12135 24367 12117 24368 12135 24368 12115 24368 12115 24369 12135 24369 12125 24369 12115 24370 12125 24370 5992 24370 5990 24371 12124 24371 12125 24371 12125 24372 12124 24372 5991 24372 12125 24373 5991 24373 5992 24373 12126 24374 12127 24374 12129 24374 12129 24375 12127 24375 12128 24375 12129 24376 12128 24376 12133 24376 6304 24377 12131 24377 6301 24377 6301 24378 12131 24378 12130 24378 6301 24379 12130 24379 6302 24379 6304 24380 12158 24380 12131 24380 12131 24381 12158 24381 12133 24381 12131 24382 12133 24382 12136 24382 12136 24383 12133 24383 12128 24383 12138 24384 12126 24384 12132 24384 12132 24385 12126 24385 12129 24385 12132 24386 12129 24386 12161 24386 12161 24387 12129 24387 12133 24387 12161 24388 12133 24388 12160 24388 12160 24389 12133 24389 12158 24389 6299 24390 6302 24390 12122 24390 12122 24391 6302 24391 12130 24391 12122 24392 12130 24392 12134 24392 12134 24393 12130 24393 12136 24393 12134 24394 12136 24394 12135 24394 12135 24395 12136 24395 12128 24395 12135 24396 12128 24396 12125 24396 12125 24397 12128 24397 12127 24397 12125 24398 12127 24398 5990 24398 5990 24399 12127 24399 12126 24399 5990 24400 12126 24400 12137 24400 12137 24401 12126 24401 12138 24401 12137 24402 12138 24402 5989 24402 12169 24403 5313 24403 6296 24403 6296 24404 12139 24404 12169 24404 12169 24405 12139 24405 12141 24405 12169 24406 12141 24406 12140 24406 12140 24407 12141 24407 12148 24407 12140 24408 12148 24408 12168 24408 12168 24409 12148 24409 12142 24409 12168 24410 12142 24410 12166 24410 5787 24411 12166 24411 5788 24411 5788 24412 12166 24412 12142 24412 5788 24413 12142 24413 12143 24413 12143 24414 12142 24414 12152 24414 12106 24415 12151 24415 12107 24415 12107 24416 12151 24416 12150 24416 12107 24417 12150 24417 12144 24417 12144 24418 12150 24418 12149 24418 12144 24419 12149 24419 12110 24419 12110 24420 12149 24420 12145 24420 12110 24421 12145 24421 12146 24421 12146 24422 12145 24422 12147 24422 6296 24423 12147 24423 12139 24423 12139 24424 12147 24424 12145 24424 12139 24425 12145 24425 12141 24425 12141 24426 12145 24426 12149 24426 12141 24427 12149 24427 12148 24427 12148 24428 12149 24428 12150 24428 12148 24429 12150 24429 12142 24429 12142 24430 12150 24430 12151 24430 12142 24431 12151 24431 12152 24431 12152 24432 12151 24432 12106 24432 12152 24433 12106 24433 5995 24433 12156 24434 12176 24434 5504 24434 12173 24435 12159 24435 12153 24435 12153 24436 12159 24436 12154 24436 12153 24437 12154 24437 12172 24437 12172 24438 12154 24438 6413 24438 6413 24439 12154 24439 12157 24439 5504 24440 12155 24440 12156 24440 12156 24441 12155 24441 5989 24441 12156 24442 5989 24442 12138 24442 12138 24443 12132 24443 12156 24443 12156 24444 12132 24444 12159 24444 12156 24445 12159 24445 12176 24445 12176 24446 12159 24446 12173 24446 6304 24447 12157 24447 12158 24447 12158 24448 12157 24448 12154 24448 12158 24449 12154 24449 12160 24449 12160 24450 12154 24450 12159 24450 12160 24451 12159 24451 12161 24451 12161 24452 12159 24452 12132 24452 5786 24453 5979 24453 12167 24453 12167 24454 5979 24454 12162 24454 12167 24455 12162 24455 12163 24455 12163 24456 12162 24456 12165 24456 12163 24457 12165 24457 12164 24457 12164 24458 12165 24458 12218 24458 12164 24459 12218 24459 12170 24459 12170 24460 12218 24460 12219 24460 12170 24461 12219 24461 5314 24461 5314 24462 12219 24462 5310 24462 5787 24463 5786 24463 12166 24463 12166 24464 5786 24464 12167 24464 12166 24465 12167 24465 12168 24465 12168 24466 12167 24466 12163 24466 12168 24467 12163 24467 12140 24467 12140 24468 12163 24468 12164 24468 12140 24469 12164 24469 12169 24469 12169 24470 12164 24470 12170 24470 12169 24471 12170 24471 5313 24471 5313 24472 12170 24472 5314 24472 12180 24473 12171 24473 6413 24473 6413 24474 12171 24474 12172 24474 12172 24475 12171 24475 12153 24475 12153 24476 12171 24476 12174 24476 12153 24477 12174 24477 12173 24477 12173 24478 12174 24478 12175 24478 12173 24479 12175 24479 12176 24479 12176 24480 12175 24480 5500 24480 12176 24481 5500 24481 5504 24481 5499 24482 5500 24482 12177 24482 12177 24483 5500 24483 12175 24483 12177 24484 12175 24484 12178 24484 12178 24485 12175 24485 12174 24485 12178 24486 12174 24486 12184 24486 12184 24487 12174 24487 12171 24487 12184 24488 12171 24488 12179 24488 12179 24489 12171 24489 12180 24489 5498 24490 5499 24490 12181 24490 12181 24491 5499 24491 12177 24491 12181 24492 12177 24492 12182 24492 12182 24493 12177 24493 12178 24493 12182 24494 12178 24494 12183 24494 12183 24495 12178 24495 12184 24495 12183 24496 12184 24496 12237 24496 12237 24497 12184 24497 12179 24497 5982 24498 5983 24498 12210 24498 12186 24499 12251 24499 12200 24499 12249 24500 12185 24500 12196 24500 12185 24501 5305 24501 12191 24501 12201 24502 12250 24502 12249 24502 12250 24503 12201 24503 12251 24503 12186 24504 12200 24504 12252 24504 12187 24505 12252 24505 12189 24505 12187 24506 12189 24506 12188 24506 12188 24507 12189 24507 12190 24507 12188 24508 12190 24508 5988 24508 5988 24509 12190 24509 12207 24509 5988 24510 12207 24510 5986 24510 5986 24511 12207 24511 12208 24511 5986 24512 12208 24512 5985 24512 12185 24513 12191 24513 12196 24513 12196 24514 12191 24514 12192 24514 12196 24515 12192 24515 12197 24515 12197 24516 12192 24516 5311 24516 12197 24517 5311 24517 12198 24517 12198 24518 5311 24518 12193 24518 12198 24519 12193 24519 12194 24519 12194 24520 12193 24520 12215 24520 12194 24521 12215 24521 12195 24521 12249 24522 12196 24522 12201 24522 12201 24523 12196 24523 12197 24523 12201 24524 12197 24524 12203 24524 12203 24525 12197 24525 12198 24525 12203 24526 12198 24526 12204 24526 12204 24527 12198 24527 12194 24527 12204 24528 12194 24528 12199 24528 12199 24529 12194 24529 12195 24529 12199 24530 12195 24530 12213 24530 12251 24531 12201 24531 12200 24531 12200 24532 12201 24532 12203 24532 12200 24533 12203 24533 12202 24533 12202 24534 12203 24534 12204 24534 12202 24535 12204 24535 12206 24535 12206 24536 12204 24536 12199 24536 12206 24537 12199 24537 12205 24537 12205 24538 12199 24538 12213 24538 12205 24539 12213 24539 12211 24539 12252 24540 12200 24540 12189 24540 12189 24541 12200 24541 12202 24541 12189 24542 12202 24542 12190 24542 12190 24543 12202 24543 12206 24543 12190 24544 12206 24544 12207 24544 12207 24545 12206 24545 12205 24545 12207 24546 12205 24546 12208 24546 12208 24547 12205 24547 12211 24547 12208 24548 12211 24548 12210 24548 12210 24549 5983 24549 12208 24549 12208 24550 5983 24550 5984 24550 12208 24551 5984 24551 5985 24551 12209 24552 5982 24552 12216 24552 12216 24553 5982 24553 12210 24553 12216 24554 12210 24554 12217 24554 12217 24555 12210 24555 12211 24555 12217 24556 12211 24556 12212 24556 12212 24557 12211 24557 12213 24557 12212 24558 12213 24558 12220 24558 12220 24559 12213 24559 12195 24559 12220 24560 12195 24560 12214 24560 12214 24561 12195 24561 12215 24561 5979 24562 12209 24562 12162 24562 12162 24563 12209 24563 12216 24563 12162 24564 12216 24564 12165 24564 12165 24565 12216 24565 12217 24565 12165 24566 12217 24566 12218 24566 12218 24567 12217 24567 12212 24567 12218 24568 12212 24568 12219 24568 12219 24569 12212 24569 12220 24569 12219 24570 12220 24570 5310 24570 5310 24571 12220 24571 12214 24571 7384 24572 12221 24572 12234 24572 12257 24573 12222 24573 12223 24573 12223 24574 12222 24574 12260 24574 12223 24575 12260 24575 12224 24575 12224 24576 12260 24576 12225 24576 12224 24577 12225 24577 12230 24577 12230 24578 12225 24578 12259 24578 12230 24579 12259 24579 12264 24579 12257 24580 12223 24580 12226 24580 12226 24581 12223 24581 12227 24581 12226 24582 12227 24582 12228 24582 12228 24583 12227 24583 6409 24583 12228 24584 6409 24584 12255 24584 6410 24585 6409 24585 12229 24585 12229 24586 6409 24586 12227 24586 12229 24587 12227 24587 12232 24587 12232 24588 12227 24588 12223 24588 12232 24589 12223 24589 12235 24589 12235 24590 12223 24590 12224 24590 12235 24591 12224 24591 12236 24591 12236 24592 12224 24592 12230 24592 7384 24593 12234 24593 12231 24593 12238 24594 6410 24594 12239 24594 12239 24595 6410 24595 12229 24595 12239 24596 12229 24596 12233 24596 12233 24597 12229 24597 12232 24597 12233 24598 12232 24598 12234 24598 12234 24599 12232 24599 12235 24599 12234 24600 12235 24600 12231 24600 12231 24601 12235 24601 12236 24601 12237 24602 12238 24602 12183 24602 12183 24603 12238 24603 12239 24603 12183 24604 12239 24604 12182 24604 12182 24605 12239 24605 12233 24605 12182 24606 12233 24606 12181 24606 12181 24607 12233 24607 12234 24607 12181 24608 12234 24608 5498 24608 5498 24609 12234 24609 12221 24609 12185 24610 12249 24610 12240 24610 12241 24611 12243 24611 12245 24611 12268 24612 12241 24612 12246 24612 5304 24613 12248 24613 5303 24613 5303 24614 12248 24614 12245 24614 5303 24615 12245 24615 12242 24615 12242 24616 12245 24616 12243 24616 12242 24617 12243 24617 12244 24617 12241 24618 12245 24618 12246 24618 12246 24619 12245 24619 12248 24619 12246 24620 12248 24620 12247 24620 12247 24621 12248 24621 12240 24621 12247 24622 12240 24622 12254 24622 5305 24623 12185 24623 5307 24623 5307 24624 12185 24624 12240 24624 5307 24625 12240 24625 5308 24625 5308 24626 12240 24626 12248 24626 5308 24627 12248 24627 5309 24627 5309 24628 12248 24628 5304 24628 12249 24629 12250 24629 12240 24629 12240 24630 12250 24630 12251 24630 12240 24631 12251 24631 12254 24631 12254 24632 12251 24632 12186 24632 12254 24633 12186 24633 12252 24633 12268 24634 12246 24634 12253 24634 12253 24635 12246 24635 12247 24635 12253 24636 12247 24636 5510 24636 5510 24637 12247 24637 12254 24637 5510 24638 12254 24638 5508 24638 5508 24639 12254 24639 12252 24639 5508 24640 12252 24640 12187 24640 12257 24641 12226 24641 12258 24641 12226 24642 12228 24642 12261 24642 12261 24643 12228 24643 12255 24643 12261 24644 12255 24644 12256 24644 12257 24645 12258 24645 12222 24645 12259 24646 12225 24646 12265 24646 12265 24647 12225 24647 12260 24647 12265 24648 12260 24648 12222 24648 12226 24649 12261 24649 12258 24649 12258 24650 12261 24650 12262 24650 12258 24651 12262 24651 12263 24651 12263 24652 12262 24652 12244 24652 12263 24653 12244 24653 12243 24653 12222 24654 12258 24654 12265 24654 12265 24655 12258 24655 12263 24655 12265 24656 12263 24656 12266 24656 12266 24657 12263 24657 12243 24657 12266 24658 12243 24658 12241 24658 12264 24659 12259 24659 7381 24659 7381 24660 12259 24660 12265 24660 7381 24661 12265 24661 7380 24661 7380 24662 12265 24662 12266 24662 7380 24663 12266 24663 12267 24663 12267 24664 12266 24664 12241 24664 12267 24665 12241 24665 12268 24665 6568 24666 6567 24666 12294 24666 12290 24667 12269 24667 12283 24667 12283 24668 12269 24668 12288 24668 5536 24669 5535 24669 12286 24669 12284 24670 12300 24670 12301 24670 12275 24671 12296 24671 12270 24671 12270 24672 12296 24672 12298 24672 12270 24673 12298 24673 12300 24673 12278 24674 6569 24674 12277 24674 12277 24675 6569 24675 12271 24675 12277 24676 12271 24676 12272 24676 12272 24677 12271 24677 12274 24677 12272 24678 12274 24678 12273 24678 12273 24679 12274 24679 6568 24679 12273 24680 6568 24680 12276 24680 12276 24681 6568 24681 12294 24681 12276 24682 12294 24682 12275 24682 12275 24683 12270 24683 12276 24683 12276 24684 12270 24684 12280 24684 12276 24685 12280 24685 12273 24685 12273 24686 12280 24686 12281 24686 12273 24687 12281 24687 12272 24687 12272 24688 12281 24688 12283 24688 12272 24689 12283 24689 12277 24689 12277 24690 12283 24690 12288 24690 12277 24691 12288 24691 12278 24691 12300 24692 12284 24692 12270 24692 12270 24693 12284 24693 12279 24693 12270 24694 12279 24694 12280 24694 12280 24695 12279 24695 12285 24695 12280 24696 12285 24696 12281 24696 12281 24697 12285 24697 12282 24697 12281 24698 12282 24698 12283 24698 12283 24699 12282 24699 12291 24699 12283 24700 12291 24700 12290 24700 12301 24701 5539 24701 12284 24701 12284 24702 5539 24702 5538 24702 12284 24703 5538 24703 12279 24703 12279 24704 5538 24704 5537 24704 12279 24705 5537 24705 12285 24705 12285 24706 5537 24706 5536 24706 12285 24707 5536 24707 12282 24707 12282 24708 5536 24708 12286 24708 12282 24709 12286 24709 12291 24709 7042 24710 12278 24710 12287 24710 12278 24711 12288 24711 12287 24711 12287 24712 12288 24712 12269 24712 12287 24713 12269 24713 12289 24713 12289 24714 12269 24714 12290 24714 12289 24715 12290 24715 12293 24715 12293 24716 12290 24716 12291 24716 12293 24717 12291 24717 12286 24717 5541 24718 12293 24718 12292 24718 12292 24719 12293 24719 12286 24719 12292 24720 12286 24720 5535 24720 7043 24721 7042 24721 12340 24721 12340 24722 7042 24722 12287 24722 12340 24723 12287 24723 12339 24723 12339 24724 12287 24724 12289 24724 12339 24725 12289 24725 12338 24725 12338 24726 12289 24726 12293 24726 12338 24727 12293 24727 12337 24727 12337 24728 12293 24728 5541 24728 6567 24729 6979 24729 12295 24729 12294 24730 6567 24730 12295 24730 12294 24731 12295 24731 12275 24731 12275 24732 12295 24732 12296 24732 12296 24733 12295 24733 12303 24733 12296 24734 12303 24734 12298 24734 12298 24735 12303 24735 12297 24735 12298 24736 12297 24736 12300 24736 12300 24737 12297 24737 12299 24737 12300 24738 12299 24738 12301 24738 12302 24739 12299 24739 12348 24739 12348 24740 12299 24740 12297 24740 12348 24741 12297 24741 12349 24741 12349 24742 12297 24742 12303 24742 12349 24743 12303 24743 12351 24743 12351 24744 12303 24744 12295 24744 12351 24745 12295 24745 6976 24745 6976 24746 12295 24746 6979 24746 12321 24747 12304 24747 12323 24747 12312 24748 7246 24748 12305 24748 12305 24749 7246 24749 12306 24749 12305 24750 12306 24750 12307 24750 12307 24751 12306 24751 12308 24751 12307 24752 12308 24752 12309 24752 12309 24753 12308 24753 12310 24753 12309 24754 12310 24754 12315 24754 12315 24755 12310 24755 12388 24755 12315 24756 12388 24756 7032 24756 7032 24757 12388 24757 7033 24757 12311 24758 12312 24758 12313 24758 12313 24759 12312 24759 12305 24759 12313 24760 12305 24760 12314 24760 12314 24761 12305 24761 12307 24761 12314 24762 12307 24762 12319 24762 12319 24763 12307 24763 12309 24763 12319 24764 12309 24764 12317 24764 12317 24765 12309 24765 12315 24765 12317 24766 12315 24766 12316 24766 12316 24767 12315 24767 7032 24767 12316 24768 12327 24768 12317 24768 12317 24769 12327 24769 12318 24769 12317 24770 12318 24770 12319 24770 12319 24771 12318 24771 12325 24771 12319 24772 12325 24772 12314 24772 12314 24773 12325 24773 12320 24773 12314 24774 12320 24774 12313 24774 12313 24775 12320 24775 12323 24775 12323 24776 12304 24776 12313 24776 12313 24777 12304 24777 7247 24777 12313 24778 7247 24778 12311 24778 12334 24779 12321 24779 12322 24779 12322 24780 12321 24780 12323 24780 12322 24781 12323 24781 12324 24781 12324 24782 12323 24782 12320 24782 12324 24783 12320 24783 12331 24783 12331 24784 12320 24784 12325 24784 12331 24785 12325 24785 12330 24785 12330 24786 12325 24786 12318 24786 12330 24787 12318 24787 12326 24787 12326 24788 12318 24788 12327 24788 12326 24789 12328 24789 12330 24789 12330 24790 12328 24790 12329 24790 12330 24791 12329 24791 12331 24791 12331 24792 12329 24792 12332 24792 12331 24793 12332 24793 12324 24793 12324 24794 12332 24794 12333 24794 12324 24795 12333 24795 12322 24795 12322 24796 12333 24796 12336 24796 12322 24797 12336 24797 12334 24797 12344 24798 12335 24798 12336 24798 12336 24799 12335 24799 7245 24799 12336 24800 7245 24800 12334 24800 12337 24801 12345 24801 12338 24801 12338 24802 12345 24802 12343 24802 12338 24803 12343 24803 12339 24803 12339 24804 12343 24804 12342 24804 12339 24805 12342 24805 12340 24805 12340 24806 12342 24806 12341 24806 12340 24807 12341 24807 7043 24807 7043 24808 12341 24808 7038 24808 12328 24809 7038 24809 12329 24809 12329 24810 7038 24810 12341 24810 12329 24811 12341 24811 12332 24811 12332 24812 12341 24812 12342 24812 12332 24813 12342 24813 12333 24813 12333 24814 12342 24814 12343 24814 12333 24815 12343 24815 12336 24815 12336 24816 12343 24816 12345 24816 12336 24817 12345 24817 12344 24817 12344 24818 12345 24818 12337 24818 12344 24819 12337 24819 5541 24819 5697 24820 5698 24820 12352 24820 12346 24821 12302 24821 12353 24821 12353 24822 12302 24822 12348 24822 12353 24823 12348 24823 12347 24823 12347 24824 12348 24824 12349 24824 12347 24825 12349 24825 12350 24825 12350 24826 12349 24826 12351 24826 12350 24827 12351 24827 12354 24827 12354 24828 12351 24828 6976 24828 5698 24829 12346 24829 12352 24829 12352 24830 12346 24830 12353 24830 12352 24831 12353 24831 12357 24831 12357 24832 12353 24832 12347 24832 12357 24833 12347 24833 12358 24833 12358 24834 12347 24834 12350 24834 12358 24835 12350 24835 6908 24835 6908 24836 12350 24836 12354 24836 5695 24837 5697 24837 12355 24837 12355 24838 5697 24838 12352 24838 12355 24839 12352 24839 12356 24839 12356 24840 12352 24840 12357 24840 12356 24841 12357 24841 12361 24841 12361 24842 12357 24842 12358 24842 12361 24843 12358 24843 6909 24843 6909 24844 12358 24844 6908 24844 12364 24845 5695 24845 12365 24845 12365 24846 5695 24846 12355 24846 12365 24847 12355 24847 12359 24847 12359 24848 12355 24848 12356 24848 12359 24849 12356 24849 12360 24849 12360 24850 12356 24850 12361 24850 12360 24851 12361 24851 12368 24851 12368 24852 12361 24852 6909 24852 12362 24853 12364 24853 12363 24853 12363 24854 12364 24854 12365 24854 12363 24855 12365 24855 12366 24855 12366 24856 12365 24856 12359 24856 12366 24857 12359 24857 12395 24857 12395 24858 12359 24858 12360 24858 12395 24859 12360 24859 12367 24859 12367 24860 12360 24860 12368 24860 7127 24861 12377 24861 12384 24861 12369 24862 7035 24862 12381 24862 12378 24863 12435 24863 12379 24863 12379 24864 12435 24864 12370 24864 12379 24865 12370 24865 12371 24865 12371 24866 12370 24866 12373 24866 12371 24867 12373 24867 12372 24867 12372 24868 12373 24868 12437 24868 12372 24869 12437 24869 12374 24869 12374 24870 12437 24870 12375 24870 12374 24871 12375 24871 12376 24871 12376 24872 12375 24872 7027 24872 12377 24873 12378 24873 12384 24873 12384 24874 12378 24874 12379 24874 12384 24875 12379 24875 12383 24875 12383 24876 12379 24876 12371 24876 12383 24877 12371 24877 12380 24877 12380 24878 12371 24878 12372 24878 12380 24879 12372 24879 12381 24879 12381 24880 12372 24880 12374 24880 12381 24881 12374 24881 12369 24881 12369 24882 12374 24882 12376 24882 7035 24883 7034 24883 12381 24883 12381 24884 7034 24884 12389 24884 12381 24885 12389 24885 12380 24885 12380 24886 12389 24886 12382 24886 12380 24887 12382 24887 12383 24887 12383 24888 12382 24888 12385 24888 12383 24889 12385 24889 12384 24889 12384 24890 12385 24890 12387 24890 12384 24891 12387 24891 7127 24891 7127 24892 12387 24892 12386 24892 7246 24893 12386 24893 12306 24893 12306 24894 12386 24894 12387 24894 12306 24895 12387 24895 12308 24895 12308 24896 12387 24896 12385 24896 12308 24897 12385 24897 12310 24897 12310 24898 12385 24898 12382 24898 12310 24899 12382 24899 12388 24899 12388 24900 12382 24900 12389 24900 12388 24901 12389 24901 7033 24901 7033 24902 12389 24902 7034 24902 12390 24903 12398 24903 12391 24903 12390 24904 12391 24904 12441 24904 12441 24905 12391 24905 12394 24905 12441 24906 12394 24906 12392 24906 12392 24907 12394 24907 12393 24907 12393 24908 12394 24908 12397 24908 12393 24909 12397 24909 12440 24909 12440 24910 12397 24910 12396 24910 12440 24911 12396 24911 6910 24911 12367 24912 12396 24912 12395 24912 12395 24913 12396 24913 12397 24913 12395 24914 12397 24914 12366 24914 12366 24915 12397 24915 12394 24915 12366 24916 12394 24916 12363 24916 12363 24917 12394 24917 12391 24917 12363 24918 12391 24918 12362 24918 12362 24919 12391 24919 12398 24919 7240 24920 12399 24920 12423 24920 7242 24921 12400 24921 12418 24921 12403 24922 12406 24922 12401 24922 7103 24923 12407 24923 12457 24923 12457 24924 12407 24924 12402 24924 12457 24925 12402 24925 12404 24925 12404 24926 12402 24926 12403 24926 12404 24927 12403 24927 12458 24927 12458 24928 12403 24928 12401 24928 7243 24929 5543 24929 12405 24929 12405 24930 5543 24930 12462 24930 12405 24931 12462 24931 12406 24931 12406 24932 12462 24932 12463 24932 12406 24933 12463 24933 12401 24933 12417 24934 7243 24934 12416 24934 12416 24935 7243 24935 12405 24935 12416 24936 12405 24936 12413 24936 12413 24937 12405 24937 12406 24937 12413 24938 12406 24938 12411 24938 12411 24939 12406 24939 12403 24939 12411 24940 12403 24940 12410 24940 12410 24941 12403 24941 12402 24941 12410 24942 12402 24942 12408 24942 12408 24943 12402 24943 12407 24943 12408 24944 12409 24944 12410 24944 12410 24945 12409 24945 12412 24945 12410 24946 12412 24946 12411 24946 12411 24947 12412 24947 12420 24947 12411 24948 12420 24948 12413 24948 12413 24949 12420 24949 12414 24949 12413 24950 12414 24950 12416 24950 12416 24951 12414 24951 12418 24951 12418 24952 12400 24952 12416 24952 12416 24953 12400 24953 12415 24953 12416 24954 12415 24954 12417 24954 12399 24955 7242 24955 12423 24955 12423 24956 7242 24956 12418 24956 12423 24957 12418 24957 12419 24957 12419 24958 12418 24958 12414 24958 12419 24959 12414 24959 12427 24959 12427 24960 12414 24960 12420 24960 12427 24961 12420 24961 12421 24961 12421 24962 12420 24962 12412 24962 12421 24963 12412 24963 7101 24963 7101 24964 12412 24964 12409 24964 7239 24965 7240 24965 12422 24965 12422 24966 7240 24966 12423 24966 12422 24967 12423 24967 12424 24967 12424 24968 12423 24968 12419 24968 12424 24969 12419 24969 12425 24969 12425 24970 12419 24970 12427 24970 12425 24971 12427 24971 12426 24971 12426 24972 12427 24972 12421 24972 12426 24973 12421 24973 7031 24973 7031 24974 12421 24974 7101 24974 12433 24975 7239 24975 12428 24975 12428 24976 7239 24976 12422 24976 12428 24977 12422 24977 12429 24977 12429 24978 12422 24978 12424 24978 12429 24979 12424 24979 12430 24979 12430 24980 12424 24980 12425 24980 12430 24981 12425 24981 12434 24981 12434 24982 12425 24982 12426 24982 12434 24983 12426 24983 12431 24983 12431 24984 12426 24984 7031 24984 7238 24985 12433 24985 12432 24985 12432 24986 12433 24986 12428 24986 12432 24987 12428 24987 12436 24987 12436 24988 12428 24988 12429 24988 12436 24989 12429 24989 12438 24989 12438 24990 12429 24990 12430 24990 12438 24991 12430 24991 12439 24991 12439 24992 12430 24992 12434 24992 12439 24993 12434 24993 7026 24993 7026 24994 12434 24994 12431 24994 12435 24995 7238 24995 12370 24995 12370 24996 7238 24996 12432 24996 12370 24997 12432 24997 12373 24997 12373 24998 12432 24998 12436 24998 12373 24999 12436 24999 12437 24999 12437 25000 12436 25000 12438 25000 12437 25001 12438 25001 12375 25001 12375 25002 12438 25002 12439 25002 12375 25003 12439 25003 7027 25003 7027 25004 12439 25004 7026 25004 12393 25005 12440 25005 12443 25005 12443 25006 12440 25006 6910 25006 12450 25007 12441 25007 12392 25007 5546 25008 12390 25008 12441 25008 12460 25009 12461 25009 12448 25009 12448 25010 12461 25010 12454 25010 12445 25011 12447 25011 12460 25011 6582 25012 12442 25012 12446 25012 6910 25013 6581 25013 12443 25013 12443 25014 6581 25014 12444 25014 12443 25015 12444 25015 12449 25015 12449 25016 12444 25016 6582 25016 12449 25017 6582 25017 12445 25017 12445 25018 6582 25018 12446 25018 12445 25019 12446 25019 12447 25019 12460 25020 12448 25020 12445 25020 12445 25021 12448 25021 12451 25021 12445 25022 12451 25022 12449 25022 12449 25023 12451 25023 12450 25023 12449 25024 12450 25024 12443 25024 12443 25025 12450 25025 12392 25025 12443 25026 12392 25026 12393 25026 12441 25027 12450 25027 5546 25027 5546 25028 12450 25028 12451 25028 5546 25029 12451 25029 5550 25029 5550 25030 12451 25030 12448 25030 5550 25031 12448 25031 5551 25031 5551 25032 12448 25032 12454 25032 5551 25033 12454 25033 12452 25033 12446 25034 12442 25034 12453 25034 12446 25035 12453 25035 12447 25035 12447 25036 12453 25036 12459 25036 12447 25037 12459 25037 12460 25037 12461 25038 12455 25038 12454 25038 12454 25039 12455 25039 12456 25039 12454 25040 12456 25040 12452 25040 12453 25041 7103 25041 12457 25041 12453 25042 12457 25042 12459 25042 12459 25043 12457 25043 12404 25043 12459 25044 12404 25044 12458 25044 12458 25045 12401 25045 12459 25045 12459 25046 12401 25046 12455 25046 12459 25047 12455 25047 12460 25047 12460 25048 12455 25048 12461 25048 5543 25049 12456 25049 12462 25049 12462 25050 12456 25050 12455 25050 12462 25051 12455 25051 12463 25051 12463 25052 12455 25052 12401 25052 12476 25053 5711 25053 12478 25053 12472 25054 12501 25054 12470 25054 12470 25055 12501 25055 12500 25055 12470 25056 12500 25056 12464 25056 12464 25057 12500 25057 12465 25057 5714 25058 5715 25058 12466 25058 12466 25059 5715 25059 12467 25059 12466 25060 12467 25060 12474 25060 12474 25061 12467 25061 12468 25061 12474 25062 12468 25062 12472 25062 12472 25063 12468 25063 12469 25063 12472 25064 12469 25064 12501 25064 12464 25065 6965 25065 12470 25065 12470 25066 6965 25066 12471 25066 12470 25067 12471 25067 12472 25067 12472 25068 12471 25068 12473 25068 12472 25069 12473 25069 12474 25069 12474 25070 12473 25070 12475 25070 12474 25071 12475 25071 12466 25071 12466 25072 12475 25072 12478 25072 12478 25073 5711 25073 12466 25073 12466 25074 5711 25074 5712 25074 12466 25075 5712 25075 5714 25075 5710 25076 12476 25076 12480 25076 12480 25077 12476 25077 12478 25077 12480 25078 12478 25078 12477 25078 12477 25079 12478 25079 12475 25079 12477 25080 12475 25080 12479 25080 12479 25081 12475 25081 12473 25081 12479 25082 12473 25082 12483 25082 12483 25083 12473 25083 12471 25083 12483 25084 12471 25084 6969 25084 6969 25085 12471 25085 6965 25085 5708 25086 5710 25086 12487 25086 12487 25087 5710 25087 12480 25087 12487 25088 12480 25088 12481 25088 12481 25089 12480 25089 12477 25089 12481 25090 12477 25090 12482 25090 12482 25091 12477 25091 12479 25091 12482 25092 12479 25092 12485 25092 12485 25093 12479 25093 12483 25093 12485 25094 12483 25094 12484 25094 12484 25095 12483 25095 6969 25095 12484 25096 12493 25096 12485 25096 12485 25097 12493 25097 12486 25097 12485 25098 12486 25098 12482 25098 12482 25099 12486 25099 12495 25099 12482 25100 12495 25100 12481 25100 12481 25101 12495 25101 12497 25101 12481 25102 12497 25102 12487 25102 12487 25103 12497 25103 12489 25103 12487 25104 12489 25104 5708 25104 12498 25105 12488 25105 12489 25105 12489 25106 12488 25106 12490 25106 12489 25107 12490 25107 5708 25107 12505 25108 12499 25108 12507 25108 12507 25109 12499 25109 12492 25109 12507 25110 12492 25110 12491 25110 12491 25111 12492 25111 12496 25111 12491 25112 12496 25112 12508 25112 12508 25113 12496 25113 12494 25113 12508 25114 12494 25114 6972 25114 6972 25115 12494 25115 6973 25115 12493 25116 6973 25116 12486 25116 12486 25117 6973 25117 12494 25117 12486 25118 12494 25118 12495 25118 12495 25119 12494 25119 12496 25119 12495 25120 12496 25120 12497 25120 12497 25121 12496 25121 12492 25121 12497 25122 12492 25122 12489 25122 12489 25123 12492 25123 12499 25123 12489 25124 12499 25124 12498 25124 12498 25125 12499 25125 12505 25125 12498 25126 12505 25126 7159 25126 12502 25127 6576 25127 12465 25127 12465 25128 12500 25128 12502 25128 12502 25129 12500 25129 12501 25129 12502 25130 12501 25130 12530 25130 5715 25131 5206 25131 12467 25131 12467 25132 5206 25132 12503 25132 12467 25133 12503 25133 12468 25133 12468 25134 12503 25134 12530 25134 12468 25135 12530 25135 12469 25135 12469 25136 12530 25136 12501 25136 12504 25137 7159 25137 12510 25137 12510 25138 7159 25138 12505 25138 12510 25139 12505 25139 12506 25139 12506 25140 12505 25140 12507 25140 12506 25141 12507 25141 12513 25141 12513 25142 12507 25142 12491 25142 12513 25143 12491 25143 12514 25143 12514 25144 12491 25144 12508 25144 12514 25145 12508 25145 6971 25145 6971 25146 12508 25146 6972 25146 12509 25147 12504 25147 12511 25147 12511 25148 12504 25148 12510 25148 12511 25149 12510 25149 12512 25149 12512 25150 12510 25150 12506 25150 12512 25151 12506 25151 12515 25151 12515 25152 12506 25152 12513 25152 12515 25153 12513 25153 12516 25153 12516 25154 12513 25154 12514 25154 12516 25155 12514 25155 12517 25155 12517 25156 12514 25156 6971 25156 5705 25157 12509 25157 12536 25157 12536 25158 12509 25158 12511 25158 12536 25159 12511 25159 12571 25159 12571 25160 12511 25160 12512 25160 12571 25161 12512 25161 12555 25161 12555 25162 12512 25162 12515 25162 12555 25163 12515 25163 12531 25163 12531 25164 12515 25164 12516 25164 12531 25165 12516 25165 6975 25165 6975 25166 12516 25166 12517 25166 7048 25167 12518 25167 12521 25167 12519 25168 12577 25168 12520 25168 12520 25169 12577 25169 12580 25169 12520 25170 12580 25170 12521 25170 12521 25171 12580 25171 12581 25171 12521 25172 12581 25172 7048 25172 12519 25173 12520 25173 12522 25173 12522 25174 12520 25174 12525 25174 12522 25175 12525 25175 12523 25175 12523 25176 12525 25176 5208 25176 12523 25177 5208 25177 12524 25177 12528 25178 5208 25178 12529 25178 12529 25179 5208 25179 12525 25179 12529 25180 12525 25180 12526 25180 12526 25181 12525 25181 12520 25181 12526 25182 12520 25182 12527 25182 12527 25183 12520 25183 12521 25183 12527 25184 12521 25184 6574 25184 6574 25185 12521 25185 12518 25185 5206 25186 12528 25186 12503 25186 12503 25187 12528 25187 12529 25187 12503 25188 12529 25188 12530 25188 12530 25189 12529 25189 12526 25189 12530 25190 12526 25190 12502 25190 12502 25191 12526 25191 12527 25191 12502 25192 12527 25192 6576 25192 6576 25193 12527 25193 6574 25193 12531 25194 6975 25194 12541 25194 12555 25195 12531 25195 12532 25195 12536 25196 12571 25196 12569 25196 12537 25197 12533 25197 12534 25197 12534 25198 12533 25198 12535 25198 12534 25199 12535 25199 12547 25199 12547 25200 12535 25200 5705 25200 12547 25201 5705 25201 12536 25201 12537 25202 12534 25202 5704 25202 5704 25203 12534 25203 12548 25203 5704 25204 12548 25204 5702 25204 5702 25205 12548 25205 12538 25205 5702 25206 12538 25206 5701 25206 5701 25207 12538 25207 12539 25207 5701 25208 12539 25208 5700 25208 5700 25209 12539 25209 12549 25209 5700 25210 12549 25210 12540 25210 12531 25211 12541 25211 12532 25211 12532 25212 12541 25212 12542 25212 12532 25213 12542 25213 12543 25213 12543 25214 12542 25214 6978 25214 12543 25215 6978 25215 12557 25215 12557 25216 6978 25216 12544 25216 12557 25217 12544 25217 12558 25217 12558 25218 12544 25218 6977 25218 12558 25219 6977 25219 12545 25219 12545 25220 6977 25220 12546 25220 12545 25221 12546 25221 12559 25221 12559 25222 12546 25222 6906 25222 12559 25223 6906 25223 12553 25223 12536 25224 12569 25224 12547 25224 12547 25225 12569 25225 12568 25225 12547 25226 12568 25226 12534 25226 12534 25227 12568 25227 12567 25227 12534 25228 12567 25228 12548 25228 12548 25229 12567 25229 12564 25229 12548 25230 12564 25230 12538 25230 12538 25231 12564 25231 12563 25231 12538 25232 12563 25232 12539 25232 12539 25233 12563 25233 12562 25233 12539 25234 12562 25234 12549 25234 12549 25235 12562 25235 12550 25235 12549 25236 12550 25236 12552 25236 12540 25237 12549 25237 12551 25237 12551 25238 12549 25238 12552 25238 12551 25239 12552 25239 12573 25239 6906 25240 12597 25240 12553 25240 12553 25241 12597 25241 12554 25241 12553 25242 12554 25242 12598 25242 12555 25243 12532 25243 12572 25243 12572 25244 12532 25244 12543 25244 12572 25245 12543 25245 12570 25245 12570 25246 12543 25246 12557 25246 12570 25247 12557 25247 12556 25247 12556 25248 12557 25248 12558 25248 12556 25249 12558 25249 12566 25249 12566 25250 12558 25250 12545 25250 12566 25251 12545 25251 12565 25251 12565 25252 12545 25252 12559 25252 12565 25253 12559 25253 12561 25253 12561 25254 12559 25254 12553 25254 12561 25255 12553 25255 12560 25255 12560 25256 12553 25256 12598 25256 12560 25257 12598 25257 12593 25257 12593 25258 12550 25258 12560 25258 12560 25259 12550 25259 12562 25259 12560 25260 12562 25260 12561 25260 12561 25261 12562 25261 12563 25261 12561 25262 12563 25262 12565 25262 12565 25263 12563 25263 12564 25263 12565 25264 12564 25264 12566 25264 12566 25265 12564 25265 12567 25265 12566 25266 12567 25266 12556 25266 12556 25267 12567 25267 12568 25267 12556 25268 12568 25268 12570 25268 12570 25269 12568 25269 12569 25269 12570 25270 12569 25270 12572 25270 12572 25271 12569 25271 12571 25271 12572 25272 12571 25272 12555 25272 5199 25273 12573 25273 12596 25273 12596 25274 12573 25274 12552 25274 12596 25275 12552 25275 12595 25275 12595 25276 12552 25276 12550 25276 12595 25277 12550 25277 12574 25277 12574 25278 12550 25278 12593 25278 12524 25279 12575 25279 12523 25279 12523 25280 12575 25280 12576 25280 12523 25281 12576 25281 12522 25281 12522 25282 12576 25282 12519 25282 12519 25283 12576 25283 12578 25283 12519 25284 12578 25284 12577 25284 12577 25285 12578 25285 12580 25285 12580 25286 12578 25286 12579 25286 12580 25287 12579 25287 12581 25287 12581 25288 12579 25288 12582 25288 12581 25289 12582 25289 7048 25289 12625 25290 12582 25290 12583 25290 12583 25291 12582 25291 12579 25291 12583 25292 12579 25292 12584 25292 12584 25293 12579 25293 12578 25293 12584 25294 12578 25294 12585 25294 12585 25295 12578 25295 12576 25295 12585 25296 12576 25296 7249 25296 7249 25297 12576 25297 12575 25297 12635 25298 5200 25298 12586 25298 12592 25299 12591 25299 12590 25299 12590 25300 12591 25300 12594 25300 12589 25301 12587 25301 12588 25301 12589 25302 12588 25302 12594 25302 12594 25303 12588 25303 12627 25303 12594 25304 12627 25304 12590 25304 5199 25305 12596 25305 12586 25305 12586 25306 12596 25306 12591 25306 12586 25307 12591 25307 12635 25307 12635 25308 12591 25308 12592 25308 12593 25309 12594 25309 12574 25309 12574 25310 12594 25310 12591 25310 12574 25311 12591 25311 12595 25311 12595 25312 12591 25312 12596 25312 12597 25313 12589 25313 12554 25313 12554 25314 12589 25314 12594 25314 12554 25315 12594 25315 12598 25315 12598 25316 12594 25316 12593 25316 12619 25317 12616 25317 12620 25317 12604 25318 7040 25318 7039 25318 12608 25319 12604 25319 12609 25319 12599 25320 12608 25320 12610 25320 12644 25321 12599 25321 12613 25321 12644 25322 12613 25322 12600 25322 12600 25323 12613 25323 12602 25323 12600 25324 12602 25324 12601 25324 12601 25325 12602 25325 12603 25325 12601 25326 12603 25326 7252 25326 12604 25327 7039 25327 12609 25327 12609 25328 7039 25328 12605 25328 12609 25329 12605 25329 12611 25329 12611 25330 12605 25330 12606 25330 12611 25331 12606 25331 12607 25331 12607 25332 12606 25332 7037 25332 12607 25333 7037 25333 12612 25333 12608 25334 12609 25334 12610 25334 12610 25335 12609 25335 12611 25335 12610 25336 12611 25336 12614 25336 12614 25337 12611 25337 12607 25337 12614 25338 12607 25338 12615 25338 12615 25339 12607 25339 12612 25339 12615 25340 12612 25340 12621 25340 12599 25341 12610 25341 12613 25341 12613 25342 12610 25342 12614 25342 12613 25343 12614 25343 12602 25343 12602 25344 12614 25344 12615 25344 12602 25345 12615 25345 12603 25345 12603 25346 12615 25346 12621 25346 12603 25347 12621 25347 12620 25347 12620 25348 12616 25348 12603 25348 12603 25349 12616 25349 12617 25349 12603 25350 12617 25350 7252 25350 12622 25351 12619 25351 12618 25351 12618 25352 12619 25352 12620 25352 12618 25353 12620 25353 12623 25353 12623 25354 12620 25354 12621 25354 12623 25355 12621 25355 12624 25355 12624 25356 12621 25356 12612 25356 12624 25357 12612 25357 12626 25357 12626 25358 12612 25358 7037 25358 7249 25359 12622 25359 12585 25359 12585 25360 12622 25360 12618 25360 12585 25361 12618 25361 12584 25361 12584 25362 12618 25362 12623 25362 12584 25363 12623 25363 12583 25363 12583 25364 12623 25364 12624 25364 12583 25365 12624 25365 12625 25365 12625 25366 12624 25366 12626 25366 12590 25367 12627 25367 12628 25367 12588 25368 12587 25368 12629 25368 12590 25369 12628 25369 12592 25369 5197 25370 5200 25370 12635 25370 12643 25371 12645 25371 12638 25371 12638 25372 12645 25372 12646 25372 12631 25373 12630 25373 12637 25373 12637 25374 12630 25374 12642 25374 12637 25375 12642 25375 12639 25375 12631 25376 12640 25376 7041 25376 12646 25377 12632 25377 12638 25377 12638 25378 12632 25378 5196 25378 12638 25379 5196 25379 12633 25379 12633 25380 5196 25380 5197 25380 12633 25381 5197 25381 12634 25381 12634 25382 5197 25382 12635 25382 12634 25383 12635 25383 12592 25383 12592 25384 12628 25384 12634 25384 12634 25385 12628 25385 12636 25385 12634 25386 12636 25386 12633 25386 12633 25387 12636 25387 12637 25387 12633 25388 12637 25388 12638 25388 12638 25389 12637 25389 12639 25389 12638 25390 12639 25390 12643 25390 12631 25391 12637 25391 12640 25391 12640 25392 12637 25392 12636 25392 12640 25393 12636 25393 12641 25393 12641 25394 12636 25394 12628 25394 12641 25395 12628 25395 12629 25395 12629 25396 12628 25396 12627 25396 12629 25397 12627 25397 12588 25397 7041 25398 7040 25398 12604 25398 12642 25399 12630 25399 12604 25399 12604 25400 12630 25400 12631 25400 12604 25401 12631 25401 7041 25401 12642 25402 12604 25402 12639 25402 12639 25403 12604 25403 12608 25403 12639 25404 12608 25404 12643 25404 12643 25405 12608 25405 12599 25405 12643 25406 12599 25406 12645 25406 12645 25407 12599 25407 12644 25407 12645 25408 12644 25408 12646 25408 12665 25409 6572 25409 6571 25409 6570 25410 6966 25410 12666 25410 12657 25411 12647 25411 12665 25411 12648 25412 12662 25412 12656 25412 12656 25413 12662 25413 12663 25413 5588 25414 12649 25414 12648 25414 12670 25415 12671 25415 12650 25415 12650 25416 12671 25416 12651 25416 12650 25417 12651 25417 12658 25417 12667 25418 12668 25418 12654 25418 12654 25419 12668 25419 12670 25419 12665 25420 6571 25420 12657 25420 12657 25421 6571 25421 12653 25421 12657 25422 12653 25422 12652 25422 12652 25423 12653 25423 6570 25423 12652 25424 6570 25424 12654 25424 12654 25425 6570 25425 12666 25425 12654 25426 12666 25426 12667 25426 12670 25427 12650 25427 12654 25427 12654 25428 12650 25428 12655 25428 12654 25429 12655 25429 12652 25429 12652 25430 12655 25430 12656 25430 12652 25431 12656 25431 12657 25431 12657 25432 12656 25432 12663 25432 12657 25433 12663 25433 12647 25433 12648 25434 12656 25434 5588 25434 5588 25435 12656 25435 12655 25435 5588 25436 12655 25436 5589 25436 5589 25437 12655 25437 12650 25437 5589 25438 12650 25438 5590 25438 5590 25439 12650 25439 12658 25439 5590 25440 12658 25440 5591 25440 12665 25441 12664 25441 6572 25441 6572 25442 12664 25442 12705 25442 12648 25443 12649 25443 12659 25443 12648 25444 12659 25444 12662 25444 12659 25445 12660 25445 12662 25445 12662 25446 12660 25446 12661 25446 12662 25447 12661 25447 12663 25447 12663 25448 12661 25448 12664 25448 12663 25449 12664 25449 12647 25449 12647 25450 12664 25450 12665 25450 6966 25451 6967 25451 12666 25451 12666 25452 6967 25452 12676 25452 12666 25453 12676 25453 12667 25453 12667 25454 12676 25454 12668 25454 12668 25455 12676 25455 12670 25455 12670 25456 12676 25456 12669 25456 12670 25457 12669 25457 12671 25457 12671 25458 12669 25458 12651 25458 12651 25459 12669 25459 12673 25459 12651 25460 12673 25460 12658 25460 12658 25461 12673 25461 12672 25461 12658 25462 12672 25462 5591 25462 12714 25463 12672 25463 12716 25463 12716 25464 12672 25464 12673 25464 12716 25465 12673 25465 12674 25465 12674 25466 12673 25466 12669 25466 12674 25467 12669 25467 12675 25467 12675 25468 12669 25468 12676 25468 12675 25469 12676 25469 12677 25469 12677 25470 12676 25470 6967 25470 12691 25471 12689 25471 12682 25471 12689 25472 12710 25472 12683 25472 12744 25473 7062 25473 12699 25473 12711 25474 12687 25474 12678 25474 12678 25475 12687 25475 12688 25475 12678 25476 12688 25476 12742 25476 12742 25477 12688 25477 12690 25477 12742 25478 12690 25478 12679 25478 7266 25479 12680 25479 12690 25479 12690 25480 12680 25480 12681 25480 12690 25481 12681 25481 12679 25481 12689 25482 12683 25482 12682 25482 12682 25483 12683 25483 12685 25483 12682 25484 12685 25484 12684 25484 12684 25485 12685 25485 12707 25485 12684 25486 12707 25486 12686 25486 12691 25487 12682 25487 12692 25487 12692 25488 12682 25488 12684 25488 12692 25489 12684 25489 12694 25489 12694 25490 12684 25490 12686 25490 12694 25491 12686 25491 12697 25491 12687 25492 12710 25492 12688 25492 12688 25493 12710 25493 12689 25493 12688 25494 12689 25494 12690 25494 12690 25495 12689 25495 12691 25495 12690 25496 12691 25496 7266 25496 7266 25497 12691 25497 12692 25497 7266 25498 12692 25498 12693 25498 12693 25499 12692 25499 12694 25499 12693 25500 12694 25500 7265 25500 7265 25501 12694 25501 12697 25501 7265 25502 12697 25502 7262 25502 7262 25503 12697 25503 7260 25503 7259 25504 7260 25504 12695 25504 12695 25505 7260 25505 12697 25505 12695 25506 12697 25506 12696 25506 12696 25507 12697 25507 12686 25507 12696 25508 12686 25508 12706 25508 12706 25509 12686 25509 12707 25509 12744 25510 12699 25510 12698 25510 12698 25511 12699 25511 7058 25511 12698 25512 7058 25512 12700 25512 12700 25513 7058 25513 7059 25513 12700 25514 7059 25514 12709 25514 12709 25515 7059 25515 12702 25515 12709 25516 12702 25516 12701 25516 12701 25517 12702 25517 12703 25517 12701 25518 12703 25518 12708 25518 12708 25519 12703 25519 7070 25519 12708 25520 7070 25520 12704 25520 12704 25521 7070 25521 12705 25521 12704 25522 12705 25522 12664 25522 12659 25523 7259 25523 12660 25523 12660 25524 7259 25524 12695 25524 12660 25525 12695 25525 12661 25525 12661 25526 12695 25526 12696 25526 12661 25527 12696 25527 12664 25527 12664 25528 12696 25528 12706 25528 12664 25529 12706 25529 12704 25529 12704 25530 12706 25530 12707 25530 12704 25531 12707 25531 12708 25531 12708 25532 12707 25532 12685 25532 12708 25533 12685 25533 12701 25533 12701 25534 12685 25534 12683 25534 12701 25535 12683 25535 12709 25535 12709 25536 12683 25536 12710 25536 12709 25537 12710 25537 12700 25537 12700 25538 12710 25538 12687 25538 12700 25539 12687 25539 12698 25539 12698 25540 12687 25540 12711 25540 12698 25541 12711 25541 12744 25541 12721 25542 5722 25542 12712 25542 12713 25543 12714 25543 12715 25543 12715 25544 12714 25544 12716 25544 12715 25545 12716 25545 12719 25545 12719 25546 12716 25546 12674 25546 12719 25547 12674 25547 12717 25547 12717 25548 12674 25548 12675 25548 12717 25549 12675 25549 12718 25549 12718 25550 12675 25550 12677 25550 5722 25551 12713 25551 12712 25551 12712 25552 12713 25552 12715 25552 12712 25553 12715 25553 12723 25553 12723 25554 12715 25554 12719 25554 12723 25555 12719 25555 12720 25555 12720 25556 12719 25556 12717 25556 12720 25557 12717 25557 12725 25557 12725 25558 12717 25558 12718 25558 12726 25559 12721 25559 12722 25559 12722 25560 12721 25560 12712 25560 12722 25561 12712 25561 12729 25561 12729 25562 12712 25562 12723 25562 12729 25563 12723 25563 12730 25563 12730 25564 12723 25564 12720 25564 12730 25565 12720 25565 12724 25565 12724 25566 12720 25566 12725 25566 5718 25567 12726 25567 12733 25567 12733 25568 12726 25568 12722 25568 12733 25569 12722 25569 12727 25569 12727 25570 12722 25570 12729 25570 12727 25571 12729 25571 12728 25571 12728 25572 12729 25572 12730 25572 12728 25573 12730 25573 6963 25573 6963 25574 12730 25574 12724 25574 5596 25575 5718 25575 12731 25575 12731 25576 5718 25576 12733 25576 12731 25577 12733 25577 12732 25577 12732 25578 12733 25578 12727 25578 12732 25579 12727 25579 12734 25579 12734 25580 12727 25580 12728 25580 12734 25581 12728 25581 12735 25581 12735 25582 12728 25582 6963 25582 7157 25583 12736 25583 12743 25583 12743 25584 12736 25584 12737 25584 12743 25585 12737 25585 12738 25585 12738 25586 12737 25586 12792 25586 12738 25587 12792 25587 12745 25587 12745 25588 12792 25588 12739 25588 12745 25589 12739 25589 12740 25589 12740 25590 12739 25590 12741 25590 12740 25591 12741 25591 7050 25591 7050 25592 12741 25592 7052 25592 12679 25593 7157 25593 12742 25593 12742 25594 7157 25594 12743 25594 12742 25595 12743 25595 12678 25595 12678 25596 12743 25596 12738 25596 12678 25597 12738 25597 12711 25597 12711 25598 12738 25598 12745 25598 12711 25599 12745 25599 12744 25599 12744 25600 12745 25600 12740 25600 12744 25601 12740 25601 7062 25601 7062 25602 12740 25602 7050 25602 12734 25603 12735 25603 6964 25603 12732 25604 12734 25604 12747 25604 5597 25605 5596 25605 12749 25605 12749 25606 5596 25606 12731 25606 12749 25607 12731 25607 12750 25607 12734 25608 6964 25608 12747 25608 12747 25609 6964 25609 6577 25609 12747 25610 6577 25610 12746 25610 12746 25611 12752 25611 12747 25611 12747 25612 12752 25612 12750 25612 12747 25613 12750 25613 12732 25613 12732 25614 12750 25614 12731 25614 12800 25615 5597 25615 12748 25615 12748 25616 5597 25616 12749 25616 12748 25617 12749 25617 12751 25617 12751 25618 12749 25618 12750 25618 12751 25619 12750 25619 12801 25619 12801 25620 12750 25620 12752 25620 12753 25621 7254 25621 12754 25621 12755 25622 12779 25622 12778 25622 12764 25623 12757 25623 7046 25623 7046 25624 12757 25624 7047 25624 12759 25625 12760 25625 12763 25625 12763 25626 12760 25626 12756 25626 12763 25627 12756 25627 12764 25627 12764 25628 12756 25628 12803 25628 12764 25629 12803 25629 12757 25629 7258 25630 5594 25630 12762 25630 12762 25631 5594 25631 12758 25631 12762 25632 12758 25632 12759 25632 12759 25633 12758 25633 12805 25633 12759 25634 12805 25634 12760 25634 12766 25635 7258 25635 12761 25635 12761 25636 7258 25636 12762 25636 12761 25637 12762 25637 12769 25637 12769 25638 12762 25638 12759 25638 12769 25639 12759 25639 12770 25639 12770 25640 12759 25640 12763 25640 12770 25641 12763 25641 12771 25641 12771 25642 12763 25642 12764 25642 12771 25643 12764 25643 7045 25643 7045 25644 12764 25644 7046 25644 12765 25645 12766 25645 12777 25645 12777 25646 12766 25646 12761 25646 12777 25647 12761 25647 12767 25647 12767 25648 12761 25648 12769 25648 12767 25649 12769 25649 12768 25649 12768 25650 12769 25650 12770 25650 12768 25651 12770 25651 12772 25651 12772 25652 12770 25652 12771 25652 12772 25653 12771 25653 7044 25653 7044 25654 12771 25654 7045 25654 7044 25655 12773 25655 12772 25655 12772 25656 12773 25656 12774 25656 12772 25657 12774 25657 12768 25657 12768 25658 12774 25658 12775 25658 12768 25659 12775 25659 12767 25659 12767 25660 12775 25660 12776 25660 12767 25661 12776 25661 12777 25661 12777 25662 12776 25662 12778 25662 12778 25663 12779 25663 12777 25663 12777 25664 12779 25664 7256 25664 12777 25665 7256 25665 12765 25665 12783 25666 12755 25666 12780 25666 12780 25667 12755 25667 12778 25667 12780 25668 12778 25668 12781 25668 12781 25669 12778 25669 12776 25669 12781 25670 12776 25670 12785 25670 12785 25671 12776 25671 12775 25671 12785 25672 12775 25672 12782 25672 12782 25673 12775 25673 12774 25673 12782 25674 12774 25674 12786 25674 12786 25675 12774 25675 12773 25675 7254 25676 12783 25676 12754 25676 12754 25677 12783 25677 12780 25677 12754 25678 12780 25678 12788 25678 12788 25679 12780 25679 12781 25679 12788 25680 12781 25680 12784 25680 12784 25681 12781 25681 12785 25681 12784 25682 12785 25682 12790 25682 12790 25683 12785 25683 12782 25683 12790 25684 12782 25684 7053 25684 7053 25685 12782 25685 12786 25685 12791 25686 12753 25686 12787 25686 12787 25687 12753 25687 12754 25687 12787 25688 12754 25688 12793 25688 12793 25689 12754 25689 12788 25689 12793 25690 12788 25690 12794 25690 12794 25691 12788 25691 12784 25691 12794 25692 12784 25692 12795 25692 12795 25693 12784 25693 12790 25693 12795 25694 12790 25694 12789 25694 12789 25695 12790 25695 7053 25695 12736 25696 12791 25696 12737 25696 12737 25697 12791 25697 12787 25697 12737 25698 12787 25698 12792 25698 12792 25699 12787 25699 12793 25699 12792 25700 12793 25700 12739 25700 12739 25701 12793 25701 12794 25701 12739 25702 12794 25702 12741 25702 12741 25703 12794 25703 12795 25703 12741 25704 12795 25704 7052 25704 7052 25705 12795 25705 12789 25705 12806 25706 5593 25706 5592 25706 12804 25707 12806 25707 12796 25707 7049 25708 12804 25708 12797 25708 12804 25709 12796 25709 12797 25709 12797 25710 12796 25710 12799 25710 12797 25711 12799 25711 12802 25711 12806 25712 5592 25712 12796 25712 12796 25713 5592 25713 12798 25713 12796 25714 12798 25714 12799 25714 12799 25715 12798 25715 12800 25715 12799 25716 12800 25716 12748 25716 12748 25717 12751 25717 12799 25717 12799 25718 12751 25718 12801 25718 12799 25719 12801 25719 12802 25719 12802 25720 12801 25720 12752 25720 12802 25721 12752 25721 12746 25721 7049 25722 12797 25722 6573 25722 6573 25723 12797 25723 12802 25723 6573 25724 12802 25724 6575 25724 6575 25725 12802 25725 12746 25725 6575 25726 12746 25726 6577 25726 12757 25727 12803 25727 12804 25727 7047 25728 12757 25728 7049 25728 7049 25729 12757 25729 12804 25729 12803 25730 12756 25730 12804 25730 12804 25731 12756 25731 12760 25731 12804 25732 12760 25732 12806 25732 5594 25733 5593 25733 12758 25733 12758 25734 5593 25734 12806 25734 12758 25735 12806 25735 12805 25735 12805 25736 12806 25736 12760 25736 12812 25737 12807 25737 12811 25737 12811 25738 12807 25738 12846 25738 12812 25739 12808 25739 12807 25739 12807 25740 12808 25740 12814 25740 12807 25741 12814 25741 12809 25741 12809 25742 12814 25742 12810 25742 12810 25743 12814 25743 12815 25743 12810 25744 12815 25744 12845 25744 12845 25745 12815 25745 12817 25745 12845 25746 12817 25746 5738 25746 12811 25747 6954 25747 12812 25747 12812 25748 6954 25748 12813 25748 12812 25749 12813 25749 12808 25749 12808 25750 12813 25750 12825 25750 12808 25751 12825 25751 12814 25751 12814 25752 12825 25752 12827 25752 12814 25753 12827 25753 12815 25753 12815 25754 12827 25754 12816 25754 12815 25755 12816 25755 12817 25755 12830 25756 5740 25756 12816 25756 12816 25757 5740 25757 5739 25757 12816 25758 5739 25758 12817 25758 12824 25759 12819 25759 12818 25759 12818 25760 12819 25760 12821 25760 12818 25761 12821 25761 12826 25761 12826 25762 12821 25762 12820 25762 12826 25763 12820 25763 12828 25763 12828 25764 12820 25764 12823 25764 12828 25765 12823 25765 12829 25765 12829 25766 12823 25766 12831 25766 12819 25767 6957 25767 12821 25767 12821 25768 6957 25768 12822 25768 12821 25769 12822 25769 12820 25769 12820 25770 12822 25770 12840 25770 12820 25771 12840 25771 12823 25771 12823 25772 12840 25772 12841 25772 12823 25773 12841 25773 12831 25773 12831 25774 12841 25774 12833 25774 6954 25775 12824 25775 12813 25775 12813 25776 12824 25776 12818 25776 12813 25777 12818 25777 12825 25777 12825 25778 12818 25778 12826 25778 12825 25779 12826 25779 12827 25779 12827 25780 12826 25780 12828 25780 12827 25781 12828 25781 12816 25781 12816 25782 12828 25782 12829 25782 12816 25783 12829 25783 12830 25783 12830 25784 12829 25784 12831 25784 12830 25785 12831 25785 12832 25785 12832 25786 12831 25786 12833 25786 5733 25787 12834 25787 12833 25787 12833 25788 12834 25788 5735 25788 12833 25789 5735 25789 12832 25789 12843 25790 12842 25790 12854 25790 12854 25791 12842 25791 12835 25791 12854 25792 12835 25792 12855 25792 12855 25793 12835 25793 12836 25793 12855 25794 12836 25794 12837 25794 12837 25795 12836 25795 12839 25795 12837 25796 12839 25796 12838 25796 12838 25797 12839 25797 6959 25797 6957 25798 6959 25798 12822 25798 12822 25799 6959 25799 12839 25799 12822 25800 12839 25800 12840 25800 12840 25801 12839 25801 12836 25801 12840 25802 12836 25802 12841 25802 12841 25803 12836 25803 12835 25803 12841 25804 12835 25804 12833 25804 12833 25805 12835 25805 12842 25805 12833 25806 12842 25806 5733 25806 5733 25807 12842 25807 12843 25807 5733 25808 12843 25808 5732 25808 12847 25809 12810 25809 12844 25809 12844 25810 12810 25810 12845 25810 12844 25811 12845 25811 5738 25811 12849 25812 12846 25812 12850 25812 12850 25813 12846 25813 12807 25813 12850 25814 12807 25814 12847 25814 12847 25815 12807 25815 12809 25815 12847 25816 12809 25816 12810 25816 12848 25817 12849 25817 12870 25817 12870 25818 12849 25818 12850 25818 12870 25819 12850 25819 12851 25819 12851 25820 12850 25820 12847 25820 12851 25821 12847 25821 12852 25821 12852 25822 12847 25822 12844 25822 12859 25823 5732 25823 12853 25823 12853 25824 5732 25824 12843 25824 12853 25825 12843 25825 12860 25825 12860 25826 12843 25826 12854 25826 12860 25827 12854 25827 12861 25827 12861 25828 12854 25828 12855 25828 12861 25829 12855 25829 12856 25829 12856 25830 12855 25830 12837 25830 12856 25831 12837 25831 6961 25831 6961 25832 12837 25832 12838 25832 12857 25833 12859 25833 12858 25833 12858 25834 12859 25834 12853 25834 12858 25835 12853 25835 12876 25835 12876 25836 12853 25836 12860 25836 12876 25837 12860 25837 12913 25837 12913 25838 12860 25838 12861 25838 12913 25839 12861 25839 12914 25839 12914 25840 12861 25840 12856 25840 12914 25841 12856 25841 12862 25841 12862 25842 12856 25842 6961 25842 12863 25843 12921 25843 12864 25843 12864 25844 12921 25844 12922 25844 12864 25845 12922 25845 7067 25845 12919 25846 12865 25846 12871 25846 12871 25847 12865 25847 12866 25847 12871 25848 12866 25848 12863 25848 12872 25849 5194 25849 12919 25849 7067 25850 7019 25850 12864 25850 12864 25851 7019 25851 12867 25851 12864 25852 12867 25852 12869 25852 12869 25853 12867 25853 7020 25853 12869 25854 7020 25854 12868 25854 12868 25855 7020 25855 12848 25855 12868 25856 12848 25856 12870 25856 12863 25857 12864 25857 12871 25857 12871 25858 12864 25858 12869 25858 12871 25859 12869 25859 12873 25859 12873 25860 12869 25860 12868 25860 12873 25861 12868 25861 12875 25861 12875 25862 12868 25862 12870 25862 12875 25863 12870 25863 12851 25863 12919 25864 12871 25864 12872 25864 12872 25865 12871 25865 12873 25865 12872 25866 12873 25866 12874 25866 12874 25867 12873 25867 12875 25867 12874 25868 12875 25868 5189 25868 5189 25869 12875 25869 12851 25869 5189 25870 12851 25870 12852 25870 12914 25871 12862 25871 12898 25871 12876 25872 12913 25872 12910 25872 12858 25873 12876 25873 12879 25873 12857 25874 12858 25874 12885 25874 12857 25875 12885 25875 5731 25875 5731 25876 12885 25876 12877 25876 5731 25877 12877 25877 12878 25877 12876 25878 12910 25878 12879 25878 12879 25879 12910 25879 12909 25879 12879 25880 12909 25880 12880 25880 12880 25881 12909 25881 12907 25881 12880 25882 12907 25882 12881 25882 12881 25883 12907 25883 12906 25883 12881 25884 12906 25884 12882 25884 12882 25885 12906 25885 12883 25885 12882 25886 12883 25886 12886 25886 12886 25887 12883 25887 12884 25887 12886 25888 12884 25888 12887 25888 12858 25889 12879 25889 12885 25889 12885 25890 12879 25890 12880 25890 12885 25891 12880 25891 12877 25891 12877 25892 12880 25892 12881 25892 12877 25893 12881 25893 12893 25893 12893 25894 12881 25894 12882 25894 12893 25895 12882 25895 12892 25895 12892 25896 12882 25896 12886 25896 12892 25897 12886 25897 12891 25897 12891 25898 12886 25898 12887 25898 12891 25899 12887 25899 12897 25899 12888 25900 12889 25900 12897 25900 12897 25901 12889 25901 12890 25901 12897 25902 12890 25902 12891 25902 12891 25903 12890 25903 5730 25903 12891 25904 5730 25904 12892 25904 12892 25905 5730 25905 5729 25905 12892 25906 5729 25906 12893 25906 12893 25907 5729 25907 12894 25907 12893 25908 12894 25908 12877 25908 12877 25909 12894 25909 12895 25909 12877 25910 12895 25910 12878 25910 5727 25911 12888 25911 12896 25911 12896 25912 12888 25912 12897 25912 12896 25913 12897 25913 12917 25913 12917 25914 12897 25914 12887 25914 12917 25915 12887 25915 12918 25915 12918 25916 12887 25916 12884 25916 12914 25917 12898 25917 12912 25917 12912 25918 12898 25918 6989 25918 12912 25919 6989 25919 12911 25919 12911 25920 6989 25920 6974 25920 12911 25921 6974 25921 12908 25921 12908 25922 6974 25922 12899 25922 12908 25923 12899 25923 12900 25923 12900 25924 12899 25924 6962 25924 12900 25925 6962 25925 12905 25925 12905 25926 6962 25926 6968 25926 12905 25927 6968 25927 12904 25927 12904 25928 6968 25928 12901 25928 12904 25929 12901 25929 12902 25929 12902 25930 12901 25930 12903 25930 12902 25931 12903 25931 12927 25931 12927 25932 12918 25932 12902 25932 12902 25933 12918 25933 12884 25933 12902 25934 12884 25934 12904 25934 12904 25935 12884 25935 12883 25935 12904 25936 12883 25936 12905 25936 12905 25937 12883 25937 12906 25937 12905 25938 12906 25938 12900 25938 12900 25939 12906 25939 12907 25939 12900 25940 12907 25940 12908 25940 12908 25941 12907 25941 12909 25941 12908 25942 12909 25942 12911 25942 12911 25943 12909 25943 12910 25943 12911 25944 12910 25944 12912 25944 12912 25945 12910 25945 12913 25945 12912 25946 12913 25946 12914 25946 12931 25947 5727 25947 12930 25947 12930 25948 5727 25948 12896 25948 12930 25949 12896 25949 12915 25949 12915 25950 12896 25950 12917 25950 12915 25951 12917 25951 12916 25951 12916 25952 12917 25952 12918 25952 12916 25953 12918 25953 12928 25953 12928 25954 12918 25954 12927 25954 5194 25955 5195 25955 12919 25955 12919 25956 5195 25956 12925 25956 12919 25957 12925 25957 12865 25957 12865 25958 12925 25958 12866 25958 12866 25959 12925 25959 12863 25959 12863 25960 12925 25960 12923 25960 12863 25961 12923 25961 12921 25961 12921 25962 12923 25962 12920 25962 12921 25963 12920 25963 12922 25963 12922 25964 12920 25964 7064 25964 12922 25965 7064 25965 7067 25965 7068 25966 7064 25966 12952 25966 12952 25967 7064 25967 12920 25967 12952 25968 12920 25968 12924 25968 12924 25969 12920 25969 12923 25969 12924 25970 12923 25970 12950 25970 12950 25971 12923 25971 12925 25971 12950 25972 12925 25972 5184 25972 5184 25973 12925 25973 5195 25973 12903 25974 12955 25974 12926 25974 12903 25975 12926 25975 12927 25975 12927 25976 12926 25976 12953 25976 12927 25977 12953 25977 12928 25977 12928 25978 12953 25978 12973 25978 12928 25979 12973 25979 12916 25979 12916 25980 12973 25980 12929 25980 12916 25981 12929 25981 12915 25981 12915 25982 12929 25982 12957 25982 12915 25983 12957 25983 12930 25983 12930 25984 12957 25984 12956 25984 12930 25985 12956 25985 12931 25985 7268 25986 7269 25986 12939 25986 7270 25987 4663 25987 12935 25987 12935 25988 4663 25988 12932 25988 12935 25989 12932 25989 12936 25989 12936 25990 12932 25990 12933 25990 12936 25991 12933 25991 12938 25991 12938 25992 12933 25992 12934 25992 12938 25993 12934 25993 7071 25993 7071 25994 12934 25994 12983 25994 7269 25995 7270 25995 12939 25995 12939 25996 7270 25996 12935 25996 12939 25997 12935 25997 12940 25997 12940 25998 12935 25998 12936 25998 12940 25999 12936 25999 12937 25999 12937 26000 12936 26000 12938 26000 12937 26001 12938 26001 12943 26001 12943 26002 12938 26002 7071 26002 12944 26003 7268 26003 12946 26003 12946 26004 7268 26004 12939 26004 12946 26005 12939 26005 12941 26005 12941 26006 12939 26006 12940 26006 12941 26007 12940 26007 12942 26007 12942 26008 12940 26008 12937 26008 12942 26009 12937 26009 7069 26009 7069 26010 12937 26010 12943 26010 12949 26011 12944 26011 12945 26011 12945 26012 12944 26012 12946 26012 12945 26013 12946 26013 12951 26013 12951 26014 12946 26014 12941 26014 12951 26015 12941 26015 12947 26015 12947 26016 12941 26016 12942 26016 12947 26017 12942 26017 12948 26017 12948 26018 12942 26018 7069 26018 5184 26019 12949 26019 12950 26019 12950 26020 12949 26020 12945 26020 12950 26021 12945 26021 12924 26021 12924 26022 12945 26022 12951 26022 12924 26023 12951 26023 12952 26023 12952 26024 12951 26024 12947 26024 12952 26025 12947 26025 7068 26025 7068 26026 12947 26026 12948 26026 12972 26027 12973 26027 12962 26027 12962 26028 12973 26028 12953 26028 12962 26029 12953 26029 12954 26029 12954 26030 12953 26030 12926 26030 12954 26031 12926 26031 12955 26031 4659 26032 12956 26032 12957 26032 12981 26033 12970 26033 12958 26033 12958 26034 12970 26034 12968 26034 12958 26035 12968 26035 12979 26035 12960 26036 12976 26036 12959 26036 12960 26037 12959 26037 12966 26037 12966 26038 12959 26038 12961 26038 12966 26039 12961 26039 12968 26039 12968 26040 12961 26040 12977 26040 12968 26041 12977 26041 12979 26041 12954 26042 12963 26042 12962 26042 12962 26043 12963 26043 12964 26043 12962 26044 12964 26044 12972 26044 12972 26045 12964 26045 12967 26045 12972 26046 12967 26046 12971 26046 12971 26047 12967 26047 12965 26047 12963 26048 12960 26048 12964 26048 12964 26049 12960 26049 12966 26049 12964 26050 12966 26050 12967 26050 12967 26051 12966 26051 12968 26051 12967 26052 12968 26052 12965 26052 12965 26053 12968 26053 12970 26053 12981 26054 12969 26054 12970 26054 12970 26055 12969 26055 4661 26055 12970 26056 4661 26056 12965 26056 12965 26057 4661 26057 4659 26057 12965 26058 4659 26058 12971 26058 12971 26059 4659 26059 12957 26059 12971 26060 12957 26060 12972 26060 12972 26061 12957 26061 12929 26061 12972 26062 12929 26062 12973 26062 12976 26063 12974 26063 12975 26063 12959 26064 12976 26064 12975 26064 12959 26065 12975 26065 12961 26065 12961 26066 12975 26066 12977 26066 12977 26067 12975 26067 12978 26067 12977 26068 12978 26068 12979 26068 12979 26069 12978 26069 12982 26069 12979 26070 12982 26070 12958 26070 12958 26071 12982 26071 12980 26071 12958 26072 12980 26072 12981 26072 4663 26073 12980 26073 12932 26073 12932 26074 12980 26074 12982 26074 12932 26075 12982 26075 12933 26075 12933 26076 12982 26076 12978 26076 12933 26077 12978 26077 12934 26077 12934 26078 12978 26078 12975 26078 12934 26079 12975 26079 12983 26079 12983 26080 12975 26080 12974 26080 12984 26081 12992 26081 12985 26081 12985 26082 12992 26082 12994 26082 12985 26083 12994 26083 12988 26083 12988 26084 12994 26084 12997 26084 12988 26085 12997 26085 12986 26085 12986 26086 12997 26086 6585 26086 5561 26087 12984 26087 13000 26087 13000 26088 12984 26088 12985 26088 13000 26089 12985 26089 12987 26089 12987 26090 12985 26090 12988 26090 12987 26091 12988 26091 6584 26091 6584 26092 12988 26092 12986 26092 13030 26093 6586 26093 12996 26093 13023 26094 13030 26094 12996 26094 13023 26095 12996 26095 12989 26095 12989 26096 12996 26096 12995 26096 12989 26097 12995 26097 12990 26097 12990 26098 12995 26098 13004 26098 13004 26099 12995 26099 12991 26099 12991 26100 12995 26100 12993 26100 12991 26101 12993 26101 7281 26101 12992 26102 12993 26102 12994 26102 12994 26103 12993 26103 12995 26103 12994 26104 12995 26104 12997 26104 12997 26105 12995 26105 12996 26105 12997 26106 12996 26106 6585 26106 6585 26107 12996 26107 6586 26107 5747 26108 5561 26108 13000 26108 12998 26109 12999 26109 12987 26109 12987 26110 12999 26110 13047 26110 12987 26111 13047 26111 13000 26111 13000 26112 13047 26112 13001 26112 13000 26113 13001 26113 5747 26113 6584 26114 13002 26114 13003 26114 6584 26115 13003 26115 12987 26115 12987 26116 13003 26116 13038 26116 12987 26117 13038 26117 12998 26117 12990 26118 13004 26118 13007 26118 12991 26119 7281 26119 13008 26119 13030 26120 13023 26120 13024 26120 13005 26121 12989 26121 12990 26121 13016 26122 13023 26122 12989 26122 13009 26123 13013 26123 7288 26123 7288 26124 13013 26124 13006 26124 7288 26125 13006 26125 7284 26125 7284 26126 13006 26126 13007 26126 7284 26127 13007 26127 13008 26127 13008 26128 13007 26128 13004 26128 13008 26129 13004 26129 12991 26129 7286 26130 13010 26130 13009 26130 13009 26131 13010 26131 13014 26131 13009 26132 13014 26132 13013 26132 7286 26133 7285 26133 13010 26133 13010 26134 7285 26134 13011 26134 13010 26135 13011 26135 13015 26135 12990 26136 13007 26136 13005 26136 13005 26137 13007 26137 13006 26137 13005 26138 13006 26138 13012 26138 13012 26139 13006 26139 13013 26139 13012 26140 13013 26140 13018 26140 13018 26141 13013 26141 13014 26141 13018 26142 13014 26142 13020 26142 13020 26143 13014 26143 13010 26143 13020 26144 13010 26144 13022 26144 13022 26145 13010 26145 13015 26145 13022 26146 13015 26146 13068 26146 12989 26147 13005 26147 13016 26147 13016 26148 13005 26148 13012 26148 13016 26149 13012 26149 13017 26149 13017 26150 13012 26150 13018 26150 13017 26151 13018 26151 13019 26151 13019 26152 13018 26152 13020 26152 13019 26153 13020 26153 13027 26153 13027 26154 13020 26154 13022 26154 13027 26155 13022 26155 13021 26155 13021 26156 13022 26156 13068 26156 13021 26157 13068 26157 13029 26157 13023 26158 13016 26158 13024 26158 13024 26159 13016 26159 13017 26159 13024 26160 13017 26160 13025 26160 13025 26161 13017 26161 13019 26161 13025 26162 13019 26162 13026 26162 13026 26163 13019 26163 13027 26163 13026 26164 13027 26164 13028 26164 13028 26165 13027 26165 13021 26165 13028 26166 13021 26166 13033 26166 13033 26167 13021 26167 13029 26167 13033 26168 13029 26168 13036 26168 13030 26169 13024 26169 7076 26169 7076 26170 13024 26170 13025 26170 7076 26171 13025 26171 13031 26171 13031 26172 13025 26172 13026 26172 13031 26173 13026 26173 13032 26173 13032 26174 13026 26174 13028 26174 13032 26175 13028 26175 13034 26175 13034 26176 13028 26176 13033 26176 13034 26177 13033 26177 13035 26177 13035 26178 13033 26178 13036 26178 13035 26179 13036 26179 13070 26179 13037 26180 13048 26180 13040 26180 13003 26181 13002 26181 13048 26181 12999 26182 12998 26182 13048 26182 13048 26183 12998 26183 13038 26183 13048 26184 13038 26184 13003 26184 13054 26185 13001 26185 13047 26185 5745 26186 5747 26186 13001 26186 13002 26187 13039 26187 13048 26187 13048 26188 13039 26188 6951 26188 13048 26189 6951 26189 13040 26189 13040 26190 6951 26190 13041 26190 13040 26191 13041 26191 13043 26191 13043 26192 13041 26192 6949 26192 13043 26193 6949 26193 13044 26193 13044 26194 6949 26194 6956 26194 13044 26195 6956 26195 13045 26195 13045 26196 6956 26196 6955 26196 13045 26197 6955 26197 13073 26197 13037 26198 13040 26198 13042 26198 13042 26199 13040 26199 13043 26199 13042 26200 13043 26200 13050 26200 13050 26201 13043 26201 13044 26201 13050 26202 13044 26202 13052 26202 13052 26203 13044 26203 13045 26203 13052 26204 13045 26204 13046 26204 13046 26205 13045 26205 13073 26205 13046 26206 13073 26206 13053 26206 12999 26207 13048 26207 13047 26207 13047 26208 13048 26208 13037 26208 13047 26209 13037 26209 13054 26209 13054 26210 13037 26210 13042 26210 13054 26211 13042 26211 13049 26211 13049 26212 13042 26212 13050 26212 13049 26213 13050 26213 13051 26213 13051 26214 13050 26214 13052 26214 13051 26215 13052 26215 13056 26215 13056 26216 13052 26216 13046 26216 13056 26217 13046 26217 13058 26217 13058 26218 13046 26218 13053 26218 13058 26219 13053 26219 13060 26219 13001 26220 13054 26220 5745 26220 5745 26221 13054 26221 13049 26221 5745 26222 13049 26222 5742 26222 5742 26223 13049 26223 13051 26223 5742 26224 13051 26224 13055 26224 13055 26225 13051 26225 13056 26225 13055 26226 13056 26226 13057 26226 13057 26227 13056 26227 13058 26227 13057 26228 13058 26228 13059 26228 13059 26229 13058 26229 13060 26229 13059 26230 13060 26230 5567 26230 7147 26231 13106 26231 13061 26231 13061 26232 13106 26232 13062 26232 13061 26233 13062 26233 13063 26233 13063 26234 13062 26234 13064 26234 13063 26235 13064 26235 13069 26235 13069 26236 13064 26236 13065 26236 13069 26237 13065 26237 13066 26237 13066 26238 13065 26238 13067 26238 13066 26239 13067 26239 13071 26239 13071 26240 13067 26240 7060 26240 13011 26241 7147 26241 13015 26241 13015 26242 7147 26242 13061 26242 13015 26243 13061 26243 13068 26243 13068 26244 13061 26244 13063 26244 13068 26245 13063 26245 13029 26245 13029 26246 13063 26246 13069 26246 13029 26247 13069 26247 13036 26247 13036 26248 13069 26248 13066 26248 13036 26249 13066 26249 13070 26249 13070 26250 13066 26250 13071 26250 5565 26251 5567 26251 13060 26251 5565 26252 13060 26252 13072 26252 13072 26253 13060 26253 13053 26253 13072 26254 13053 26254 13110 26254 13110 26255 13053 26255 13073 26255 13110 26256 13073 26256 13109 26256 13073 26257 6955 26257 6948 26257 13073 26258 6948 26258 13108 26258 13073 26259 13108 26259 13109 26259 7272 26260 7276 26260 13089 26260 13126 26261 7063 26261 13084 26261 13126 26262 13084 26262 13074 26262 13074 26263 13084 26263 13083 26263 13078 26264 13076 26264 13075 26264 13075 26265 13076 26265 13077 26265 13075 26266 13077 26266 13083 26266 13083 26267 13077 26267 13129 26267 13083 26268 13129 26268 13074 26268 13075 26269 13080 26269 13078 26269 13078 26270 13080 26270 13079 26270 13078 26271 13079 26271 7279 26271 7278 26272 13079 26272 13087 26272 13087 26273 13079 26273 13080 26273 13087 26274 13080 26274 13081 26274 13081 26275 13080 26275 13075 26275 13081 26276 13075 26276 13082 26276 13082 26277 13075 26277 13083 26277 13082 26278 13083 26278 13085 26278 13085 26279 13083 26279 13084 26279 13085 26280 13084 26280 7066 26280 7066 26281 13084 26281 7063 26281 7066 26282 7065 26282 13085 26282 13085 26283 7065 26283 13092 26283 13085 26284 13092 26284 13082 26284 13082 26285 13092 26285 13086 26285 13082 26286 13086 26286 13081 26286 13081 26287 13086 26287 13088 26287 13081 26288 13088 26288 13087 26288 13087 26289 13088 26289 13089 26289 13089 26290 7276 26290 13087 26290 13087 26291 7276 26291 13090 26291 13087 26292 13090 26292 7278 26292 13091 26293 7272 26293 13098 26293 13098 26294 7272 26294 13089 26294 13098 26295 13089 26295 13097 26295 13097 26296 13089 26296 13088 26296 13097 26297 13088 26297 13095 26297 13095 26298 13088 26298 13086 26298 13095 26299 13086 26299 13093 26299 13093 26300 13086 26300 13092 26300 13093 26301 13092 26301 7056 26301 7056 26302 13092 26302 7065 26302 7056 26303 13094 26303 13093 26303 13093 26304 13094 26304 13096 26304 13093 26305 13096 26305 13095 26305 13095 26306 13096 26306 13103 26306 13095 26307 13103 26307 13097 26307 13097 26308 13103 26308 13104 26308 13097 26309 13104 26309 13098 26309 13098 26310 13104 26310 13099 26310 13098 26311 13099 26311 13091 26311 7271 26312 7275 26312 13099 26312 13099 26313 7275 26313 7273 26313 13099 26314 7273 26314 13091 26314 13062 26315 13100 26315 13064 26315 13064 26316 13100 26316 13105 26316 13064 26317 13105 26317 13065 26317 13065 26318 13105 26318 13101 26318 13065 26319 13101 26319 13067 26319 13067 26320 13101 26320 13102 26320 13067 26321 13102 26321 7060 26321 7060 26322 13102 26322 7057 26322 13094 26323 7057 26323 13096 26323 13096 26324 7057 26324 13102 26324 13096 26325 13102 26325 13103 26325 13103 26326 13102 26326 13101 26326 13103 26327 13101 26327 13104 26327 13104 26328 13101 26328 13105 26328 13104 26329 13105 26329 13099 26329 13099 26330 13105 26330 13100 26330 13099 26331 13100 26331 7271 26331 7271 26332 13100 26332 13062 26332 7271 26333 13062 26333 13106 26333 6948 26334 13107 26334 13115 26334 6948 26335 13115 26335 13108 26335 13108 26336 13115 26336 13109 26336 13109 26337 13115 26337 13114 26337 13109 26338 13114 26338 13110 26338 13110 26339 13114 26339 13113 26339 13110 26340 13113 26340 13072 26340 13072 26341 13113 26341 13111 26341 13072 26342 13111 26342 5565 26342 13112 26343 13111 26343 13117 26343 13117 26344 13111 26344 13113 26344 13117 26345 13113 26345 13118 26345 13118 26346 13113 26346 13114 26346 13118 26347 13114 26347 13120 26347 13120 26348 13114 26348 13115 26348 13120 26349 13115 26349 13116 26349 13116 26350 13115 26350 13107 26350 13121 26351 13112 26351 13122 26351 13122 26352 13112 26352 13117 26352 13122 26353 13117 26353 13119 26353 13119 26354 13117 26354 13118 26354 13119 26355 13118 26355 13123 26355 13123 26356 13118 26356 13120 26356 13123 26357 13120 26357 13125 26357 13125 26358 13120 26358 13116 26358 5563 26359 13121 26359 13127 26359 13127 26360 13121 26360 13122 26360 13127 26361 13122 26361 13128 26361 13128 26362 13122 26362 13119 26362 13128 26363 13119 26363 13124 26363 13124 26364 13119 26364 13123 26364 13124 26365 13123 26365 7021 26365 7021 26366 13123 26366 13125 26366 13078 26367 7279 26367 5563 26367 13124 26368 7021 26368 13126 26368 13078 26369 5563 26369 13076 26369 13076 26370 5563 26370 13127 26370 13076 26371 13127 26371 13077 26371 13077 26372 13127 26372 13128 26372 13077 26373 13128 26373 13129 26373 13129 26374 13128 26374 13124 26374 13129 26375 13124 26375 13074 26375 13074 26376 13124 26376 13126 26376 13130 26377 13145 26377 13132 26377 13171 26378 13131 26378 13152 26378 13152 26379 13131 26379 13145 26379 6587 26380 13169 26380 13156 26380 13156 26381 13169 26381 13171 26381 13132 26382 13133 26382 13140 26382 13140 26383 13133 26383 13134 26383 13140 26384 13134 26384 13135 26384 13135 26385 13134 26385 13136 26385 13136 26386 5752 26386 13135 26386 13135 26387 5752 26387 5753 26387 13135 26388 5753 26388 13138 26388 13138 26389 5753 26389 13137 26389 5756 26390 13143 26390 13137 26390 13137 26391 13143 26391 13142 26391 13137 26392 13142 26392 13138 26392 5756 26393 5754 26393 13143 26393 13143 26394 5754 26394 13139 26394 13143 26395 13139 26395 13164 26395 13132 26396 13140 26396 13130 26396 13130 26397 13140 26397 13135 26397 13130 26398 13135 26398 13141 26398 13141 26399 13135 26399 13138 26399 13141 26400 13138 26400 13146 26400 13146 26401 13138 26401 13142 26401 13146 26402 13142 26402 13148 26402 13148 26403 13142 26403 13143 26403 13148 26404 13143 26404 13144 26404 13144 26405 13143 26405 13164 26405 13144 26406 13164 26406 13150 26406 13145 26407 13130 26407 13152 26407 13152 26408 13130 26408 13141 26408 13152 26409 13141 26409 13153 26409 13153 26410 13141 26410 13146 26410 13153 26411 13146 26411 13147 26411 13147 26412 13146 26412 13148 26412 13147 26413 13148 26413 13149 26413 13149 26414 13148 26414 13144 26414 13149 26415 13144 26415 13155 26415 13155 26416 13144 26416 13150 26416 13155 26417 13150 26417 13151 26417 13171 26418 13152 26418 13156 26418 13156 26419 13152 26419 13153 26419 13156 26420 13153 26420 13157 26420 13157 26421 13153 26421 13147 26421 13157 26422 13147 26422 13154 26422 13154 26423 13147 26423 13149 26423 13154 26424 13149 26424 13158 26424 13158 26425 13149 26425 13155 26425 13158 26426 13155 26426 13159 26426 13159 26427 13155 26427 13151 26427 13159 26428 13151 26428 13167 26428 6587 26429 13156 26429 6952 26429 6952 26430 13156 26430 13157 26430 6952 26431 13157 26431 6953 26431 6953 26432 13157 26432 13154 26432 6953 26433 13154 26433 6950 26433 6950 26434 13154 26434 13158 26434 6950 26435 13158 26435 6958 26435 6958 26436 13158 26436 13159 26436 6958 26437 13159 26437 6960 26437 6960 26438 13159 26438 13167 26438 6960 26439 13167 26439 6947 26439 7156 26440 13199 26440 13160 26440 13160 26441 13199 26441 13161 26441 13160 26442 13161 26442 13165 26442 13165 26443 13161 26443 13162 26443 13165 26444 13162 26444 13166 26444 13166 26445 13162 26445 13200 26445 13166 26446 13200 26446 13168 26446 13168 26447 13200 26447 13202 26447 13168 26448 13202 26448 13163 26448 13163 26449 13202 26449 6944 26449 13139 26450 7156 26450 13164 26450 13164 26451 7156 26451 13160 26451 13164 26452 13160 26452 13150 26452 13150 26453 13160 26453 13165 26453 13150 26454 13165 26454 13151 26454 13151 26455 13165 26455 13166 26455 13151 26456 13166 26456 13167 26456 13167 26457 13166 26457 13168 26457 13167 26458 13168 26458 6947 26458 6947 26459 13168 26459 13163 26459 13169 26460 6587 26460 13170 26460 13169 26461 13170 26461 13171 26461 13170 26462 13176 26462 13171 26462 13171 26463 13176 26463 13175 26463 13171 26464 13175 26464 13131 26464 13131 26465 13175 26465 13173 26465 13131 26466 13173 26466 13145 26466 13172 26467 13133 26467 13173 26467 13173 26468 13133 26468 13132 26468 13173 26469 13132 26469 13145 26469 5748 26470 13172 26470 13204 26470 13204 26471 13172 26471 13173 26471 13204 26472 13173 26472 13174 26472 13174 26473 13173 26473 13175 26473 13174 26474 13175 26474 13177 26474 13177 26475 13175 26475 13176 26475 13177 26476 13176 26476 13206 26476 13206 26477 13176 26477 13170 26477 5760 26478 5761 26478 13178 26478 6945 26479 13188 26479 13179 26479 13179 26480 13188 26480 13180 26480 13181 26481 13183 26481 5763 26481 13188 26482 13186 26482 13180 26482 13180 26483 13186 26483 13185 26483 13180 26484 13185 26484 13213 26484 13213 26485 13185 26485 13181 26485 13213 26486 13181 26486 13182 26486 13182 26487 13181 26487 5763 26487 13182 26488 5763 26488 5764 26488 13189 26489 13183 26489 13190 26489 13190 26490 13183 26490 13181 26490 13190 26491 13181 26491 13184 26491 13184 26492 13181 26492 13185 26492 13184 26493 13185 26493 13192 26493 13192 26494 13185 26494 13186 26494 13192 26495 13186 26495 13193 26495 13193 26496 13186 26496 13188 26496 13193 26497 13188 26497 13187 26497 13187 26498 13188 26498 6945 26498 5761 26499 13189 26499 13178 26499 13178 26500 13189 26500 13190 26500 13178 26501 13190 26501 13191 26501 13191 26502 13190 26502 13184 26502 13191 26503 13184 26503 13196 26503 13196 26504 13184 26504 13192 26504 13196 26505 13192 26505 13197 26505 13197 26506 13192 26506 13193 26506 13197 26507 13193 26507 13198 26507 13198 26508 13193 26508 13187 26508 5759 26509 5760 26509 13194 26509 13194 26510 5760 26510 13178 26510 13194 26511 13178 26511 13195 26511 13195 26512 13178 26512 13191 26512 13195 26513 13191 26513 13201 26513 13201 26514 13191 26514 13196 26514 13201 26515 13196 26515 13203 26515 13203 26516 13196 26516 13197 26516 13203 26517 13197 26517 6940 26517 6940 26518 13197 26518 13198 26518 13199 26519 5759 26519 13161 26519 13161 26520 5759 26520 13194 26520 13161 26521 13194 26521 13162 26521 13162 26522 13194 26522 13195 26522 13162 26523 13195 26523 13200 26523 13200 26524 13195 26524 13201 26524 13200 26525 13201 26525 13202 26525 13202 26526 13201 26526 13203 26526 13202 26527 13203 26527 6944 26527 6944 26528 13203 26528 6940 26528 13207 26529 5748 26529 13209 26529 13209 26530 5748 26530 13204 26530 13209 26531 13204 26531 13205 26531 13205 26532 13204 26532 13174 26532 13205 26533 13174 26533 13212 26533 13212 26534 13174 26534 13177 26534 13212 26535 13177 26535 6583 26535 6583 26536 13177 26536 13206 26536 5175 26537 13207 26537 13208 26537 13208 26538 13207 26538 13209 26538 13208 26539 13209 26539 13222 26539 13222 26540 13209 26540 13205 26540 13222 26541 13205 26541 13210 26541 13210 26542 13205 26542 13212 26542 13210 26543 13212 26543 13211 26543 13211 26544 13212 26544 6583 26544 5764 26545 5766 26545 13182 26545 13182 26546 5766 26546 13216 26546 13182 26547 13216 26547 13213 26547 13213 26548 13216 26548 13214 26548 13213 26549 13214 26549 13180 26549 13180 26550 13214 26550 4933 26550 13180 26551 4933 26551 13179 26551 5766 26552 13215 26552 13216 26552 13216 26553 13215 26553 13217 26553 13216 26554 13217 26554 13214 26554 13214 26555 13217 26555 13226 26555 13214 26556 13226 26556 4933 26556 4933 26557 13226 26557 13218 26557 13219 26558 5175 26558 13220 26558 13220 26559 5175 26559 13208 26559 13220 26560 13208 26560 13221 26560 13221 26561 13208 26561 13222 26561 13221 26562 13222 26562 13223 26562 13223 26563 13222 26563 13210 26563 13223 26564 13210 26564 13224 26564 13224 26565 13210 26565 13211 26565 5180 26566 5181 26566 13227 26566 13227 26567 5181 26567 13259 26567 13227 26568 13259 26568 13228 26568 13228 26569 13259 26569 13256 26569 13228 26570 13256 26570 13225 26570 13225 26571 13256 26571 13255 26571 13215 26572 5180 26572 13217 26572 13217 26573 5180 26573 13227 26573 13217 26574 13227 26574 13226 26574 13226 26575 13227 26575 13228 26575 13226 26576 13228 26576 13218 26576 13218 26577 13228 26577 13225 26577 13221 26578 13223 26578 13229 26578 13220 26579 13221 26579 13231 26579 13219 26580 13220 26580 13245 26580 13219 26581 13245 26581 13230 26581 13230 26582 13245 26582 13249 26582 13230 26583 13249 26583 13247 26583 13221 26584 13229 26584 13231 26584 13231 26585 13229 26585 13241 26585 13231 26586 13241 26586 13232 26586 13232 26587 13241 26587 13233 26587 13232 26588 13233 26588 13246 26588 13246 26589 13233 26589 13234 26589 13246 26590 13234 26590 13235 26590 13235 26591 13234 26591 13236 26591 13235 26592 13236 26592 13237 26592 7078 26593 13236 26593 13238 26593 13238 26594 13236 26594 13234 26594 13238 26595 13234 26595 7079 26595 7079 26596 13234 26596 13233 26596 7079 26597 13233 26597 13239 26597 13239 26598 13233 26598 13241 26598 13239 26599 13241 26599 13240 26599 13240 26600 13241 26600 13229 26600 13240 26601 13229 26601 13242 26601 13242 26602 13229 26602 13223 26602 13242 26603 13223 26603 13224 26603 7078 26604 13254 26604 13236 26604 13236 26605 13254 26605 13243 26605 13236 26606 13243 26606 13237 26606 13237 26607 13243 26607 13244 26607 13237 26608 13244 26608 13260 26608 13220 26609 13231 26609 13245 26609 13245 26610 13231 26610 13232 26610 13245 26611 13232 26611 13249 26611 13249 26612 13232 26612 13246 26612 13249 26613 13246 26613 13250 26613 13250 26614 13246 26614 13235 26614 13250 26615 13235 26615 13251 26615 13251 26616 13235 26616 13237 26616 13251 26617 13237 26617 13253 26617 13253 26618 13237 26618 13260 26618 13253 26619 13260 26619 13258 26619 13247 26620 13249 26620 13248 26620 13248 26621 13249 26621 13250 26621 13248 26622 13250 26622 7292 26622 7292 26623 13250 26623 13251 26623 7292 26624 13251 26624 13252 26624 13252 26625 13251 26625 13253 26625 13252 26626 13253 26626 7290 26626 7290 26627 13253 26627 13258 26627 7290 26628 13258 26628 13257 26628 7078 26629 13255 26629 13254 26629 13254 26630 13255 26630 13256 26630 13254 26631 13256 26631 13243 26631 13259 26632 5181 26632 13257 26632 13257 26633 13258 26633 13259 26633 13259 26634 13258 26634 13260 26634 13259 26635 13260 26635 13256 26635 13256 26636 13260 26636 13244 26636 13256 26637 13244 26637 13243 26637 13268 26638 13267 26638 13270 26638 13270 26639 13267 26639 13261 26639 13270 26640 13261 26640 13262 26640 7302 26641 13263 26641 13264 26641 7302 26642 13264 26642 13265 26642 13264 26643 13266 26643 13265 26643 13265 26644 13266 26644 13271 26644 13265 26645 13271 26645 13268 26645 13268 26646 13271 26646 13276 26646 13268 26647 13276 26647 13267 26647 7149 26648 7302 26648 13295 26648 13295 26649 7302 26649 13265 26649 13295 26650 13265 26650 13292 26650 13292 26651 13265 26651 13268 26651 13292 26652 13268 26652 13269 26652 13269 26653 13268 26653 13270 26653 13306 26654 13287 26654 13282 26654 13267 26655 13276 26655 13277 26655 13264 26656 13263 26656 13272 26656 13276 26657 13271 26657 13278 26657 13278 26658 13271 26658 13266 26658 13278 26659 13266 26659 13264 26659 13288 26660 13262 26660 13261 26660 13288 26661 13261 26661 13267 26661 13264 26662 13272 26662 13278 26662 13278 26663 13272 26663 7304 26663 13278 26664 7304 26664 13279 26664 13279 26665 7304 26665 7306 26665 13279 26666 7306 26666 13273 26666 7306 26667 7305 26667 13273 26667 13273 26668 7305 26668 13274 26668 13273 26669 13274 26669 13280 26669 13280 26670 13274 26670 13275 26670 13280 26671 13275 26671 13283 26671 13276 26672 13278 26672 13277 26672 13277 26673 13278 26673 13279 26673 13277 26674 13279 26674 13284 26674 13284 26675 13279 26675 13273 26675 13284 26676 13273 26676 13281 26676 13281 26677 13273 26677 13280 26677 13281 26678 13280 26678 13282 26678 13282 26679 13280 26679 13283 26679 13282 26680 13283 26680 13306 26680 13267 26681 13277 26681 13288 26681 13288 26682 13277 26682 13284 26682 13288 26683 13284 26683 13289 26683 13289 26684 13284 26684 13281 26684 13289 26685 13281 26685 13285 26685 13285 26686 13281 26686 13282 26686 13285 26687 13282 26687 13286 26687 13286 26688 13282 26688 13287 26688 13286 26689 13287 26689 13308 26689 13262 26690 13288 26690 7082 26690 7082 26691 13288 26691 13289 26691 7082 26692 13289 26692 13290 26692 13290 26693 13289 26693 13285 26693 13290 26694 13285 26694 13291 26694 13291 26695 13285 26695 13286 26695 13291 26696 13286 26696 7072 26696 7072 26697 13286 26697 13308 26697 7072 26698 13308 26698 7074 26698 13296 26699 7150 26699 7149 26699 13295 26700 13292 26700 13294 26700 4946 26701 13294 26701 13293 26701 13293 26702 13294 26702 13292 26702 13293 26703 13292 26703 13269 26703 4946 26704 13299 26704 13294 26704 13294 26705 13299 26705 13296 26705 13294 26706 13296 26706 13295 26706 13295 26707 13296 26707 7149 26707 13297 26708 7150 26708 13298 26708 13298 26709 7150 26709 13296 26709 13298 26710 13296 26710 13316 26710 13316 26711 13296 26711 13299 26711 7153 26712 7155 26712 13305 26712 13305 26713 7155 26713 13361 26713 13305 26714 13361 26714 13300 26714 13300 26715 13361 26715 13353 26715 13300 26716 13353 26716 13307 26716 13307 26717 13353 26717 13301 26717 13307 26718 13301 26718 13309 26718 13309 26719 13301 26719 13302 26719 13309 26720 13302 26720 13303 26720 13303 26721 13302 26721 13304 26721 13275 26722 7153 26722 13283 26722 13283 26723 7153 26723 13305 26723 13283 26724 13305 26724 13306 26724 13306 26725 13305 26725 13300 26725 13306 26726 13300 26726 13287 26726 13287 26727 13300 26727 13307 26727 13287 26728 13307 26728 13308 26728 13308 26729 13307 26729 13309 26729 13308 26730 13309 26730 7074 26730 7074 26731 13309 26731 13303 26731 5772 26732 5773 26732 13310 26732 13299 26733 4946 26733 4943 26733 13316 26734 13299 26734 13317 26734 13298 26735 13316 26735 13321 26735 13297 26736 13298 26736 13322 26736 13297 26737 13322 26737 5779 26737 5779 26738 13322 26738 13323 26738 5779 26739 13323 26739 5776 26739 5776 26740 13323 26740 13324 26740 5776 26741 13324 26741 5775 26741 13299 26742 4943 26742 13317 26742 13317 26743 4943 26743 13311 26743 13317 26744 13311 26744 13318 26744 13318 26745 13311 26745 13312 26745 13318 26746 13312 26746 13314 26746 13314 26747 13312 26747 13313 26747 13314 26748 13313 26748 13315 26748 13316 26749 13317 26749 13321 26749 13321 26750 13317 26750 13318 26750 13321 26751 13318 26751 13319 26751 13319 26752 13318 26752 13314 26752 13319 26753 13314 26753 13320 26753 13320 26754 13314 26754 13315 26754 13320 26755 13315 26755 13327 26755 13298 26756 13321 26756 13322 26756 13322 26757 13321 26757 13319 26757 13322 26758 13319 26758 13323 26758 13323 26759 13319 26759 13320 26759 13323 26760 13320 26760 13324 26760 13324 26761 13320 26761 13327 26761 13324 26762 13327 26762 13310 26762 13310 26763 5773 26763 13324 26763 13324 26764 5773 26764 5774 26764 13324 26765 5774 26765 5775 26765 13328 26766 5772 26766 13325 26766 13325 26767 5772 26767 13310 26767 13325 26768 13310 26768 13326 26768 13326 26769 13310 26769 13327 26769 13326 26770 13327 26770 13330 26770 13330 26771 13327 26771 13315 26771 13330 26772 13315 26772 13331 26772 13331 26773 13315 26773 13313 26773 5769 26774 13328 26774 13329 26774 13329 26775 13328 26775 13325 26775 13329 26776 13325 26776 13363 26776 13363 26777 13325 26777 13326 26777 13363 26778 13326 26778 13364 26778 13364 26779 13326 26779 13330 26779 13364 26780 13330 26780 13366 26780 13366 26781 13330 26781 13331 26781 13332 26782 13338 26782 13336 26782 7075 26783 7081 26783 13333 26783 7075 26784 13333 26784 13335 26784 13333 26785 13341 26785 13335 26785 13335 26786 13341 26786 13334 26786 13335 26787 13334 26787 13375 26787 13375 26788 13334 26788 13374 26788 13374 26789 13334 26789 13336 26789 13374 26790 13336 26790 13337 26790 13337 26791 13336 26791 13338 26791 13337 26792 13338 26792 13372 26792 7298 26793 13332 26793 13344 26793 13344 26794 13332 26794 13336 26794 13344 26795 13336 26795 13339 26795 13339 26796 13336 26796 13334 26796 13339 26797 13334 26797 13340 26797 13340 26798 13334 26798 13341 26798 13340 26799 13341 26799 13342 26799 13342 26800 13341 26800 13333 26800 13342 26801 13333 26801 7080 26801 7080 26802 13333 26802 7081 26802 7299 26803 7298 26803 13343 26803 13343 26804 7298 26804 13344 26804 13343 26805 13344 26805 13348 26805 13348 26806 13344 26806 13339 26806 13348 26807 13339 26807 13345 26807 13345 26808 13339 26808 13340 26808 13345 26809 13340 26809 13347 26809 13347 26810 13340 26810 13342 26810 13347 26811 13342 26811 13346 26811 13346 26812 13342 26812 7080 26812 13346 26813 13356 26813 13347 26813 13347 26814 13356 26814 13357 26814 13347 26815 13357 26815 13345 26815 13345 26816 13357 26816 13358 26816 13345 26817 13358 26817 13348 26817 13348 26818 13358 26818 13349 26818 13348 26819 13349 26819 13343 26819 13343 26820 13349 26820 13351 26820 13343 26821 13351 26821 7299 26821 13360 26822 13350 26822 13351 26822 13351 26823 13350 26823 7296 26823 13351 26824 7296 26824 7299 26824 13361 26825 13352 26825 13353 26825 13353 26826 13352 26826 13354 26826 13353 26827 13354 26827 13301 26827 13301 26828 13354 26828 13359 26828 13301 26829 13359 26829 13302 26829 13302 26830 13359 26830 13355 26830 13302 26831 13355 26831 13304 26831 13304 26832 13355 26832 7073 26832 13356 26833 7073 26833 13357 26833 13357 26834 7073 26834 13355 26834 13357 26835 13355 26835 13358 26835 13358 26836 13355 26836 13359 26836 13358 26837 13359 26837 13349 26837 13349 26838 13359 26838 13354 26838 13349 26839 13354 26839 13351 26839 13351 26840 13354 26840 13352 26840 13351 26841 13352 26841 13360 26841 13360 26842 13352 26842 13361 26842 13360 26843 13361 26843 7155 26843 5577 26844 5769 26844 13367 26844 13367 26845 5769 26845 13329 26845 13367 26846 13329 26846 13362 26846 13362 26847 13329 26847 13363 26847 13362 26848 13363 26848 13369 26848 13369 26849 13363 26849 13364 26849 13369 26850 13364 26850 13365 26850 13365 26851 13364 26851 13366 26851 13381 26852 5577 26852 13380 26852 13380 26853 5577 26853 13367 26853 13380 26854 13367 26854 13379 26854 13379 26855 13367 26855 13362 26855 13379 26856 13362 26856 13368 26856 13368 26857 13362 26857 13369 26857 13368 26858 13369 26858 13370 26858 13370 26859 13369 26859 13365 26859 13337 26860 13372 26860 13371 26860 13371 26861 13372 26861 13373 26861 13371 26862 13373 26862 7301 26862 13337 26863 13371 26863 13374 26863 13374 26864 13371 26864 13376 26864 13374 26865 13376 26865 13375 26865 13375 26866 13376 26866 13377 26866 13375 26867 13377 26867 13335 26867 13335 26868 13377 26868 13378 26868 13335 26869 13378 26869 7075 26869 13370 26870 13378 26870 13368 26870 13368 26871 13378 26871 13377 26871 13368 26872 13377 26872 13379 26872 13379 26873 13377 26873 13376 26873 13379 26874 13376 26874 13380 26874 13380 26875 13376 26875 13371 26875 13380 26876 13371 26876 13381 26876 13381 26877 13371 26877 7301 26877 5618 26878 5620 26878 13382 26878 13382 26879 5620 26879 13413 26879 13382 26880 13413 26880 13383 26880 13383 26881 13413 26881 13414 26881 13383 26882 13414 26882 13385 26882 13385 26883 13414 26883 13384 26883 13385 26884 13384 26884 6932 26884 6932 26885 13384 26885 7012 26885 7203 26886 5618 26886 13387 26886 13387 26887 5618 26887 13382 26887 13387 26888 13382 26888 13389 26888 13389 26889 13382 26889 13383 26889 13389 26890 13383 26890 13391 26890 13391 26891 13383 26891 13385 26891 13391 26892 13385 26892 6931 26892 6931 26893 13385 26893 6932 26893 13386 26894 7203 26894 13392 26894 13392 26895 7203 26895 13387 26895 13392 26896 13387 26896 13388 26896 13388 26897 13387 26897 13389 26897 13388 26898 13389 26898 13390 26898 13390 26899 13389 26899 13391 26899 13390 26900 13391 26900 6941 26900 6941 26901 13391 26901 6931 26901 7201 26902 13386 26902 13417 26902 13417 26903 13386 26903 13392 26903 13417 26904 13392 26904 13393 26904 13393 26905 13392 26905 13388 26905 13393 26906 13388 26906 13394 26906 13394 26907 13388 26907 13390 26907 13394 26908 13390 26908 6942 26908 6942 26909 13390 26909 6941 26909 13410 26910 5652 26910 13406 26910 13395 26911 6937 26911 13397 26911 13395 26912 13397 26912 13396 26912 13396 26913 13397 26913 13403 26913 13396 26914 13403 26914 13441 26914 13441 26915 13403 26915 13398 26915 13441 26916 13398 26916 13443 26916 13400 26917 13399 26917 13439 26917 13400 26918 13439 26918 13398 26918 13398 26919 13439 26919 13447 26919 13398 26920 13447 26920 13443 26920 13405 26921 13400 26921 13401 26921 13401 26922 13400 26922 13398 26922 13401 26923 13398 26923 13402 26923 13402 26924 13398 26924 13403 26924 13402 26925 13403 26925 13404 26925 13404 26926 13403 26926 13397 26926 13404 26927 13397 26927 6936 26927 6936 26928 13397 26928 6937 26928 5652 26929 13405 26929 13406 26929 13406 26930 13405 26930 13401 26930 13406 26931 13401 26931 13407 26931 13407 26932 13401 26932 13402 26932 13407 26933 13402 26933 13408 26933 13408 26934 13402 26934 13404 26934 13408 26935 13404 26935 6934 26935 6934 26936 13404 26936 6936 26936 13409 26937 13410 26937 13415 26937 13415 26938 13410 26938 13406 26938 13415 26939 13406 26939 13411 26939 13411 26940 13406 26940 13407 26940 13411 26941 13407 26941 13412 26941 13412 26942 13407 26942 13408 26942 13412 26943 13408 26943 6933 26943 6933 26944 13408 26944 6934 26944 5620 26945 13409 26945 13413 26945 13413 26946 13409 26946 13415 26946 13413 26947 13415 26947 13414 26947 13414 26948 13415 26948 13411 26948 13414 26949 13411 26949 13384 26949 13384 26950 13411 26950 13412 26950 13384 26951 13412 26951 7012 26951 7012 26952 13412 26952 6933 26952 13436 26953 13433 26953 13432 26953 13394 26954 6942 26954 13423 26954 13393 26955 13394 26955 13416 26955 13417 26956 13393 26956 13425 26956 5784 26957 7201 26957 13418 26957 13418 26958 7201 26958 13417 26958 5784 26959 13418 26959 13419 26959 13419 26960 13418 26960 13420 26960 13419 26961 13420 26961 13421 26961 13421 26962 13420 26962 13422 26962 13421 26963 13422 26963 13435 26963 13394 26964 13423 26964 13416 26964 13416 26965 13423 26965 6939 26965 13416 26966 6939 26966 13426 26966 13426 26967 6939 26967 13424 26967 13426 26968 13424 26968 13427 26968 13427 26969 13424 26969 6946 26969 13427 26970 6946 26970 13429 26970 13393 26971 13416 26971 13425 26971 13425 26972 13416 26972 13426 26972 13425 26973 13426 26973 13431 26973 13431 26974 13426 26974 13427 26974 13431 26975 13427 26975 13428 26975 13428 26976 13427 26976 13429 26976 13428 26977 13429 26977 13430 26977 13417 26978 13425 26978 13418 26978 13418 26979 13425 26979 13431 26979 13418 26980 13431 26980 13420 26980 13420 26981 13431 26981 13428 26981 13420 26982 13428 26982 13422 26982 13422 26983 13428 26983 13430 26983 13422 26984 13430 26984 13432 26984 13432 26985 13433 26985 13422 26985 13422 26986 13433 26986 13434 26986 13422 26987 13434 26987 13435 26987 5782 26988 13436 26988 13437 26988 13437 26989 13436 26989 13432 26989 13437 26990 13432 26990 13438 26990 13438 26991 13432 26991 13430 26991 13438 26992 13430 26992 13452 26992 13452 26993 13430 26993 13429 26993 13452 26994 13429 26994 4942 26994 4942 26995 13429 26995 6946 26995 5654 26996 5655 26996 13445 26996 13439 26997 13399 26997 13446 26997 4935 26998 13395 26998 13440 26998 13395 26999 13396 26999 13440 26999 13440 27000 13396 27000 13441 27000 13440 27001 13441 27001 13442 27001 13442 27002 13441 27002 13443 27002 13442 27003 13443 27003 13447 27003 5654 27004 13445 27004 13446 27004 4940 27005 4935 27005 13444 27005 13444 27006 4935 27006 13440 27006 13444 27007 13440 27007 13445 27007 13445 27008 13440 27008 13442 27008 13445 27009 13442 27009 13446 27009 13446 27010 13442 27010 13447 27010 13446 27011 13447 27011 13439 27011 13464 27012 4940 27012 13448 27012 13448 27013 4940 27013 13444 27013 13448 27014 13444 27014 13449 27014 13449 27015 13444 27015 13445 27015 13449 27016 13445 27016 13450 27016 13450 27017 13445 27017 5655 27017 4942 27018 13451 27018 13456 27018 4942 27019 13456 27019 13452 27019 13452 27020 13456 27020 13455 27020 13452 27021 13455 27021 13438 27021 13438 27022 13455 27022 13453 27022 13438 27023 13453 27023 13437 27023 13437 27024 13453 27024 13454 27024 13437 27025 13454 27025 5782 27025 5622 27026 13454 27026 13465 27026 13465 27027 13454 27027 13453 27027 13465 27028 13453 27028 13466 27028 13466 27029 13453 27029 13455 27029 13466 27030 13455 27030 13457 27030 13457 27031 13455 27031 13456 27031 13457 27032 13456 27032 4944 27032 4944 27033 13456 27033 13451 27033 13458 27034 13459 27034 13460 27034 13460 27035 13459 27035 13463 27035 13460 27036 13463 27036 13493 27036 13493 27037 13463 27037 13461 27037 13493 27038 13461 27038 13492 27038 13462 27039 5632 27039 13461 27039 13461 27040 5632 27040 13491 27040 13461 27041 13491 27041 13492 27041 13450 27042 13462 27042 13449 27042 13449 27043 13462 27043 13461 27043 13449 27044 13461 27044 13448 27044 13448 27045 13461 27045 13463 27045 13448 27046 13463 27046 13464 27046 13464 27047 13463 27047 13459 27047 5628 27048 5622 27048 13468 27048 13468 27049 5622 27049 13465 27049 13468 27050 13465 27050 13469 27050 13469 27051 13465 27051 13466 27051 13469 27052 13466 27052 13467 27052 13467 27053 13466 27053 13457 27053 13467 27054 13457 27054 4945 27054 4945 27055 13457 27055 4944 27055 5626 27056 5628 27056 13472 27056 13472 27057 5628 27057 13468 27057 13472 27058 13468 27058 13470 27058 13470 27059 13468 27059 13469 27059 13470 27060 13469 27060 13490 27060 13490 27061 13469 27061 13467 27061 13490 27062 13467 27062 4947 27062 4947 27063 13467 27063 4945 27063 13490 27064 4947 27064 4948 27064 13472 27065 13470 27065 13471 27065 7312 27066 5626 27066 13476 27066 13476 27067 5626 27067 13472 27067 7312 27068 13476 27068 7313 27068 7313 27069 13476 27069 13473 27069 7313 27070 13473 27070 7314 27070 7314 27071 13473 27071 13474 27071 7314 27072 13474 27072 13475 27072 13475 27073 13474 27073 13479 27073 13475 27074 13479 27074 7309 27074 13472 27075 13471 27075 13476 27075 13476 27076 13471 27076 13477 27076 13476 27077 13477 27077 13473 27077 13473 27078 13477 27078 13486 27078 13473 27079 13486 27079 13474 27079 13474 27080 13486 27080 13478 27080 13474 27081 13478 27081 13479 27081 13479 27082 13478 27082 13494 27082 13479 27083 13494 27083 13480 27083 7309 27084 13479 27084 13481 27084 13481 27085 13479 27085 13480 27085 13481 27086 13480 27086 7308 27086 13490 27087 4948 27087 13482 27087 13482 27088 4948 27088 4949 27088 13482 27089 4949 27089 13489 27089 13489 27090 4949 27090 13483 27090 13489 27091 13483 27091 13488 27091 13488 27092 13483 27092 13484 27092 13488 27093 13484 27093 13487 27093 13487 27094 13484 27094 4937 27094 13487 27095 4937 27095 13485 27095 13485 27096 4937 27096 13458 27096 13485 27097 13458 27097 13460 27097 13460 27098 13494 27098 13485 27098 13485 27099 13494 27099 13478 27099 13485 27100 13478 27100 13487 27100 13487 27101 13478 27101 13486 27101 13487 27102 13486 27102 13488 27102 13488 27103 13486 27103 13477 27103 13488 27104 13477 27104 13489 27104 13489 27105 13477 27105 13471 27105 13489 27106 13471 27106 13482 27106 13482 27107 13471 27107 13470 27107 13482 27108 13470 27108 13490 27108 5632 27109 7308 27109 13491 27109 13491 27110 7308 27110 13480 27110 13491 27111 13480 27111 13492 27111 13492 27112 13480 27112 13494 27112 13492 27113 13494 27113 13493 27113 13493 27114 13494 27114 13460 27114 4954 27115 13502 27115 13496 27115 4954 27116 13496 27116 13520 27116 13510 27117 13506 27117 13495 27117 13495 27118 13506 27118 13505 27118 13495 27119 13505 27119 13496 27119 13496 27120 13505 27120 13508 27120 13496 27121 13508 27121 13520 27121 7223 27122 13510 27122 13497 27122 13497 27123 13510 27123 13495 27123 13497 27124 13495 27124 7221 27124 7221 27125 13495 27125 13498 27125 13499 27126 13500 27126 13501 27126 13501 27127 13500 27127 13503 27127 13501 27128 13503 27128 4958 27128 4958 27129 13503 27129 4957 27129 13502 27130 4957 27130 13496 27130 13496 27131 4957 27131 13503 27131 13496 27132 13503 27132 13495 27132 13495 27133 13503 27133 13500 27133 13495 27134 13500 27134 13498 27134 13498 27135 13500 27135 13499 27135 13498 27136 13499 27136 13504 27136 13505 27137 13506 27137 13509 27137 13510 27138 7223 27138 13507 27138 13514 27139 13508 27139 13505 27139 13517 27140 13520 27140 13508 27140 7224 27141 13509 27141 13507 27141 13507 27142 13509 27142 13506 27142 13507 27143 13506 27143 13510 27143 13512 27144 13511 27144 7224 27144 7224 27145 13511 27145 13515 27145 7224 27146 13515 27146 13509 27146 13512 27147 13513 27147 13511 27147 13511 27148 13513 27148 13536 27148 13511 27149 13536 27149 13537 27149 13505 27150 13509 27150 13514 27150 13514 27151 13509 27151 13515 27151 13514 27152 13515 27152 13516 27152 13516 27153 13515 27153 13511 27153 13516 27154 13511 27154 13518 27154 13518 27155 13511 27155 13537 27155 13518 27156 13537 27156 13538 27156 13508 27157 13514 27157 13517 27157 13517 27158 13514 27158 13516 27158 13517 27159 13516 27159 13522 27159 13522 27160 13516 27160 13518 27160 13522 27161 13518 27161 13519 27161 13519 27162 13518 27162 13538 27162 13519 27163 13538 27163 13539 27163 4954 27164 13520 27164 13517 27164 4954 27165 13517 27165 13521 27165 13521 27166 13517 27166 13522 27166 13521 27167 13522 27167 13523 27167 13523 27168 13522 27168 13519 27168 13523 27169 13519 27169 13524 27169 13524 27170 13519 27170 13539 27170 13524 27171 13539 27171 7085 27171 13528 27172 13504 27172 13529 27172 13529 27173 13504 27173 13499 27173 13529 27174 13499 27174 13525 27174 13525 27175 13499 27175 13501 27175 13526 27176 13525 27176 13527 27176 13527 27177 13525 27177 13501 27177 13527 27178 13501 27178 4958 27178 7327 27179 13528 27179 13541 27179 13541 27180 13528 27180 13529 27180 13541 27181 13529 27181 13542 27181 13542 27182 13529 27182 13525 27182 13542 27183 13525 27183 13543 27183 13543 27184 13525 27184 13526 27184 13530 27185 13588 27185 13531 27185 13531 27186 13588 27186 13532 27186 13531 27187 13532 27187 13533 27187 13533 27188 13532 27188 13589 27188 13533 27189 13589 27189 13534 27189 13534 27190 13589 27190 13535 27190 13534 27191 13535 27191 7086 27191 7086 27192 13535 27192 7087 27192 13536 27193 13530 27193 13537 27193 13537 27194 13530 27194 13531 27194 13537 27195 13531 27195 13538 27195 13538 27196 13531 27196 13533 27196 13538 27197 13533 27197 13539 27197 13539 27198 13533 27198 13534 27198 13539 27199 13534 27199 7085 27199 7085 27200 13534 27200 7086 27200 7328 27201 7327 27201 13540 27201 13540 27202 7327 27202 13541 27202 13540 27203 13541 27203 13549 27203 13549 27204 13541 27204 13542 27204 13549 27205 13542 27205 13544 27205 13544 27206 13542 27206 13543 27206 13544 27207 13543 27207 13545 27207 13545 27208 13543 27208 13526 27208 13545 27209 13546 27209 13544 27209 13544 27210 13546 27210 13547 27210 13544 27211 13547 27211 13549 27211 13549 27212 13547 27212 13548 27212 13549 27213 13548 27213 13540 27213 13540 27214 13548 27214 13550 27214 13540 27215 13550 27215 7328 27215 7325 27216 7330 27216 13550 27216 13550 27217 7330 27217 7329 27217 13550 27218 7329 27218 7328 27218 4939 27219 13554 27219 13556 27219 13556 27220 13554 27220 13551 27220 13556 27221 13551 27221 13552 27221 13552 27222 13551 27222 13553 27222 13552 27223 13553 27223 13557 27223 13557 27224 13553 27224 13558 27224 13554 27225 13555 27225 13551 27225 13551 27226 13555 27226 13563 27226 13551 27227 13563 27227 13553 27227 13553 27228 13563 27228 13566 27228 13553 27229 13566 27229 13558 27229 13558 27230 13566 27230 13559 27230 13546 27231 4939 27231 13547 27231 13547 27232 4939 27232 13556 27232 13547 27233 13556 27233 13548 27233 13548 27234 13556 27234 13552 27234 13548 27235 13552 27235 13550 27235 13550 27236 13552 27236 13557 27236 13550 27237 13557 27237 7325 27237 7325 27238 13557 27238 13558 27238 7325 27239 13558 27239 7326 27239 7326 27240 13558 27240 13559 27240 13568 27241 7324 27241 13559 27241 13559 27242 7324 27242 7323 27242 13559 27243 7323 27243 7326 27243 13593 27244 13560 27244 13561 27244 13561 27245 13560 27245 13567 27245 13561 27246 13567 27246 13562 27246 13562 27247 13567 27247 13565 27247 13562 27248 13565 27248 4936 27248 4936 27249 13565 27249 13564 27249 13555 27250 13564 27250 13563 27250 13563 27251 13564 27251 13565 27251 13563 27252 13565 27252 13566 27252 13566 27253 13565 27253 13567 27253 13566 27254 13567 27254 13559 27254 13559 27255 13567 27255 13560 27255 13559 27256 13560 27256 13568 27256 13568 27257 13560 27257 13593 27257 13568 27258 13593 27258 13592 27258 13569 27259 7318 27259 13580 27259 13604 27260 13570 27260 13571 27260 13571 27261 13570 27261 13603 27261 13571 27262 13603 27262 13579 27262 13579 27263 13603 27263 13606 27263 13579 27264 13606 27264 7084 27264 7084 27265 13606 27265 13572 27265 13574 27266 13573 27266 13575 27266 13604 27267 13571 27267 13600 27267 13600 27268 13571 27268 13574 27268 13600 27269 13574 27269 13601 27269 13601 27270 13574 27270 13575 27270 13601 27271 13575 27271 7320 27271 7317 27272 13573 27272 13576 27272 13576 27273 13573 27273 13574 27273 13576 27274 13574 27274 13577 27274 13577 27275 13574 27275 13571 27275 13577 27276 13571 27276 13581 27276 13581 27277 13571 27277 13579 27277 13581 27278 13579 27278 13578 27278 13578 27279 13579 27279 7084 27279 7318 27280 7317 27280 13580 27280 13580 27281 7317 27281 13576 27281 13580 27282 13576 27282 13584 27282 13584 27283 13576 27283 13577 27283 13584 27284 13577 27284 13586 27284 13586 27285 13577 27285 13581 27285 13586 27286 13581 27286 7088 27286 7088 27287 13581 27287 13578 27287 13582 27288 13569 27288 13583 27288 13583 27289 13569 27289 13580 27289 13583 27290 13580 27290 13590 27290 13590 27291 13580 27291 13584 27291 13590 27292 13584 27292 13585 27292 13585 27293 13584 27293 13586 27293 13585 27294 13586 27294 13587 27294 13587 27295 13586 27295 7088 27295 13588 27296 13582 27296 13532 27296 13532 27297 13582 27297 13583 27297 13532 27298 13583 27298 13589 27298 13589 27299 13583 27299 13590 27299 13589 27300 13590 27300 13535 27300 13535 27301 13590 27301 13585 27301 13535 27302 13585 27302 7087 27302 7087 27303 13585 27303 13587 27303 13591 27304 13592 27304 13596 27304 13596 27305 13592 27305 13593 27305 13596 27306 13593 27306 13597 27306 13597 27307 13593 27307 13561 27307 13597 27308 13561 27308 13598 27308 13598 27309 13561 27309 13562 27309 13598 27310 13562 27310 13594 27310 13594 27311 13562 27311 4936 27311 13613 27312 13591 27312 13595 27312 13595 27313 13591 27313 13596 27313 13595 27314 13596 27314 13611 27314 13611 27315 13596 27315 13597 27315 13611 27316 13597 27316 13609 27316 13609 27317 13597 27317 13598 27317 13609 27318 13598 27318 13599 27318 13599 27319 13598 27319 13594 27319 13607 27320 13604 27320 13608 27320 13608 27321 13604 27321 13600 27321 13608 27322 13600 27322 13602 27322 13602 27323 13600 27323 13601 27323 13602 27324 13601 27324 7320 27324 13606 27325 13603 27325 13607 27325 13607 27326 13603 27326 13570 27326 13607 27327 13570 27327 13604 27327 13607 27328 13605 27328 13606 27328 13606 27329 13605 27329 4951 27329 13606 27330 4951 27330 13572 27330 4938 27331 4951 27331 13610 27331 13610 27332 4951 27332 13605 27332 13610 27333 13605 27333 13612 27333 13612 27334 13605 27334 13607 27334 13612 27335 13607 27335 13614 27335 13614 27336 13607 27336 13608 27336 13614 27337 13608 27337 7319 27337 7319 27338 13608 27338 13602 27338 13599 27339 4938 27339 13609 27339 13609 27340 4938 27340 13610 27340 13609 27341 13610 27341 13611 27341 13611 27342 13610 27342 13612 27342 13611 27343 13612 27343 13595 27343 13595 27344 13612 27344 13614 27344 13595 27345 13614 27345 13613 27345 13613 27346 13614 27346 7319 27346 13616 27347 5646 27347 13618 27347 13618 27348 5646 27348 13631 27348 13618 27349 13631 27349 13619 27349 13619 27350 13631 27350 13632 27350 13619 27351 13632 27351 13615 27351 13615 27352 13632 27352 13633 27352 13615 27353 13633 27353 13620 27353 13620 27354 13633 27354 6928 27354 13643 27355 13616 27355 13617 27355 13617 27356 13616 27356 13618 27356 13617 27357 13618 27357 13652 27357 13652 27358 13618 27358 13619 27358 13652 27359 13619 27359 13656 27359 13656 27360 13619 27360 13615 27360 13656 27361 13615 27361 6929 27361 6929 27362 13615 27362 13620 27362 5665 27363 5667 27363 13626 27363 13621 27364 13630 27364 13629 27364 13624 27365 13629 27365 13622 27365 13622 27366 13629 27366 13628 27366 13622 27367 13628 27367 13625 27367 13659 27368 13621 27368 13629 27368 13659 27369 13629 27369 13623 27369 13623 27370 13629 27370 13624 27370 13625 27371 13628 27371 13660 27371 13660 27372 13628 27372 13626 27372 13660 27373 13626 27373 13657 27373 13657 27374 13626 27374 5667 27374 13657 27375 5667 27375 5668 27375 5664 27376 5665 27376 13627 27376 13627 27377 5665 27377 13626 27377 13627 27378 13626 27378 13634 27378 13634 27379 13626 27379 13628 27379 13634 27380 13628 27380 13635 27380 13635 27381 13628 27381 13629 27381 13635 27382 13629 27382 13636 27382 13636 27383 13629 27383 13630 27383 5646 27384 5664 27384 13631 27384 13631 27385 5664 27385 13627 27385 13631 27386 13627 27386 13632 27386 13632 27387 13627 27387 13634 27387 13632 27388 13634 27388 13633 27388 13633 27389 13634 27389 13635 27389 13633 27390 13635 27390 6928 27390 6928 27391 13635 27391 13636 27391 13639 27392 13637 27392 5657 27392 13644 27393 13650 27393 13637 27393 13653 27394 13638 27394 13650 27394 13674 27395 13638 27395 6938 27395 5657 27396 13640 27396 13639 27396 13639 27397 13640 27397 13641 27397 13639 27398 13641 27398 13642 27398 13642 27399 13641 27399 5662 27399 5661 27400 13648 27400 5662 27400 5662 27401 13648 27401 13646 27401 5662 27402 13646 27402 13642 27402 5661 27403 5660 27403 13648 27403 13648 27404 5660 27404 13643 27404 13648 27405 13643 27405 13617 27405 13637 27406 13639 27406 13644 27406 13644 27407 13639 27407 13642 27407 13644 27408 13642 27408 13645 27408 13645 27409 13642 27409 13646 27409 13645 27410 13646 27410 13647 27410 13647 27411 13646 27411 13648 27411 13647 27412 13648 27412 13649 27412 13649 27413 13648 27413 13617 27413 13649 27414 13617 27414 13652 27414 13650 27415 13644 27415 13653 27415 13653 27416 13644 27416 13645 27416 13653 27417 13645 27417 13651 27417 13651 27418 13645 27418 13647 27418 13651 27419 13647 27419 13654 27419 13654 27420 13647 27420 13649 27420 13654 27421 13649 27421 13655 27421 13655 27422 13649 27422 13652 27422 13655 27423 13652 27423 13656 27423 13638 27424 13653 27424 6938 27424 6938 27425 13653 27425 13651 27425 6938 27426 13651 27426 6935 27426 6935 27427 13651 27427 13654 27427 6935 27428 13654 27428 6907 27428 6907 27429 13654 27429 13655 27429 6907 27430 13655 27430 7011 27430 7011 27431 13655 27431 13656 27431 7011 27432 13656 27432 6929 27432 13657 27433 5668 27433 5669 27433 13621 27434 13659 27434 13658 27434 13658 27435 13659 27435 13623 27435 13658 27436 13623 27436 13624 27436 13657 27437 5669 27437 13660 27437 13624 27438 13622 27438 13662 27438 13662 27439 13622 27439 13625 27439 13662 27440 13625 27440 13660 27440 13660 27441 5669 27441 13662 27441 13662 27442 5669 27442 13661 27442 13662 27443 13661 27443 13664 27443 13661 27444 13663 27444 13664 27444 13664 27445 13663 27445 13665 27445 13664 27446 13665 27446 13667 27446 13667 27447 13665 27447 5157 27447 13667 27448 5157 27448 13686 27448 13624 27449 13662 27449 13658 27449 13658 27450 13662 27450 13664 27450 13658 27451 13664 27451 13666 27451 13666 27452 13664 27452 13667 27452 13666 27453 13667 27453 13670 27453 13670 27454 13667 27454 13686 27454 13670 27455 13686 27455 13671 27455 13621 27456 13658 27456 13668 27456 13668 27457 13658 27457 13666 27457 13668 27458 13666 27458 13669 27458 13669 27459 13666 27459 13670 27459 13669 27460 13670 27460 13672 27460 13672 27461 13670 27461 13671 27461 13672 27462 13671 27462 13688 27462 13677 27463 5657 27463 13637 27463 13674 27464 13680 27464 13673 27464 13674 27465 13673 27465 13638 27465 13638 27466 13673 27466 13675 27466 13638 27467 13675 27467 13650 27467 13650 27468 13675 27468 13676 27468 13650 27469 13676 27469 13637 27469 13637 27470 13676 27470 13678 27470 13637 27471 13678 27471 13677 27471 5656 27472 13678 27472 13689 27472 13689 27473 13678 27473 13676 27473 13689 27474 13676 27474 13690 27474 13690 27475 13676 27475 13675 27475 13690 27476 13675 27476 13679 27476 13679 27477 13675 27477 13673 27477 13679 27478 13673 27478 4960 27478 4960 27479 13673 27479 13680 27479 13717 27480 13681 27480 13721 27480 13721 27481 13681 27481 13687 27481 13721 27482 13687 27482 13682 27482 13682 27483 13687 27483 13683 27483 13682 27484 13683 27484 13720 27484 13720 27485 13683 27485 13684 27485 13684 27486 13683 27486 13685 27486 13684 27487 13685 27487 5163 27487 5157 27488 13685 27488 13686 27488 13686 27489 13685 27489 13683 27489 13686 27490 13683 27490 13671 27490 13671 27491 13683 27491 13687 27491 13671 27492 13687 27492 13688 27492 13688 27493 13687 27493 13681 27493 5155 27494 5656 27494 13693 27494 13693 27495 5656 27495 13689 27495 13693 27496 13689 27496 13694 27496 13694 27497 13689 27497 13690 27497 13694 27498 13690 27498 13695 27498 13695 27499 13690 27499 13679 27499 13695 27500 13679 27500 13691 27500 13691 27501 13679 27501 4960 27501 13692 27502 5155 27502 13698 27502 13698 27503 5155 27503 13693 27503 13698 27504 13693 27504 13700 27504 13700 27505 13693 27505 13694 27505 13700 27506 13694 27506 13701 27506 13701 27507 13694 27507 13695 27507 13701 27508 13695 27508 13702 27508 13702 27509 13695 27509 13691 27509 13726 27510 13696 27510 13715 27510 5169 27511 13692 27511 13697 27511 13697 27512 13692 27512 13698 27512 13697 27513 13698 27513 13699 27513 13699 27514 13698 27514 13700 27514 13699 27515 13700 27515 13706 27515 13706 27516 13700 27516 13701 27516 13706 27517 13701 27517 13707 27517 13707 27518 13701 27518 13702 27518 5171 27519 5169 27519 13703 27519 13703 27520 5169 27520 13697 27520 13703 27521 13697 27521 13704 27521 13704 27522 13697 27522 13699 27522 13704 27523 13699 27523 13705 27523 13705 27524 13699 27524 13706 27524 13705 27525 13706 27525 4959 27525 4959 27526 13706 27526 13707 27526 13713 27527 5171 27527 13710 27527 13710 27528 5171 27528 13703 27528 13710 27529 13703 27529 13709 27529 13709 27530 13703 27530 13704 27530 13709 27531 13704 27531 13708 27531 13708 27532 13704 27532 13705 27532 13708 27533 13705 27533 4952 27533 4952 27534 13705 27534 4959 27534 4952 27535 13722 27535 13708 27535 13708 27536 13722 27536 13724 27536 13708 27537 13724 27537 13709 27537 13709 27538 13724 27538 13725 27538 13709 27539 13725 27539 13710 27539 13710 27540 13725 27540 13711 27540 13710 27541 13711 27541 13713 27541 5166 27542 5167 27542 13711 27542 13711 27543 5167 27543 13712 27543 13711 27544 13712 27544 13713 27544 13718 27545 13719 27545 13714 27545 13717 27546 13715 27546 13716 27546 13716 27547 13715 27547 13696 27547 13716 27548 13696 27548 13723 27548 13717 27549 13721 27549 13715 27549 13715 27550 13721 27550 13718 27550 13715 27551 13718 27551 13726 27551 13726 27552 13718 27552 13714 27552 13684 27553 13719 27553 13720 27553 13720 27554 13719 27554 13718 27554 13720 27555 13718 27555 13682 27555 13682 27556 13718 27556 13721 27556 13722 27557 13723 27557 13724 27557 13724 27558 13723 27558 13696 27558 13724 27559 13696 27559 13725 27559 13725 27560 13696 27560 13726 27560 13725 27561 13726 27561 13711 27561 13711 27562 13726 27562 13714 27562 13711 27563 13714 27563 5166 27563 5166 27564 13714 27564 13719 27564 5166 27565 13719 27565 5165 27565 5165 27566 13719 27566 13684 27566 5165 27567 13684 27567 5163 27567 7170 27568 13728 27568 13727 27568 13727 27569 13728 27569 13748 27569 13727 27570 13748 27570 13732 27570 13732 27571 13748 27571 13750 27571 13732 27572 13750 27572 13729 27572 13729 27573 13750 27573 13752 27573 13729 27574 13752 27574 13730 27574 13730 27575 13752 27575 7092 27575 7178 27576 7170 27576 13731 27576 13731 27577 7170 27577 13727 27577 13731 27578 13727 27578 13765 27578 13765 27579 13727 27579 13732 27579 13765 27580 13732 27580 13762 27580 13762 27581 13732 27581 13729 27581 13762 27582 13729 27582 7097 27582 7097 27583 13729 27583 13730 27583 7227 27584 13733 27584 13740 27584 7089 27585 13743 27585 13742 27585 13734 27586 7089 27586 13742 27586 13734 27587 13742 27587 13735 27587 13735 27588 13742 27588 13737 27588 13742 27589 13736 27589 13737 27589 13737 27590 13736 27590 13739 27590 13737 27591 13739 27591 13768 27591 13738 27592 13766 27592 13739 27592 13739 27593 13766 27593 13767 27593 13739 27594 13767 27594 13768 27594 13733 27595 13738 27595 13740 27595 13740 27596 13738 27596 13739 27596 13740 27597 13739 27597 13746 27597 13746 27598 13739 27598 13736 27598 13746 27599 13736 27599 13741 27599 13741 27600 13736 27600 13742 27600 13741 27601 13742 27601 13747 27601 13747 27602 13742 27602 13743 27602 13749 27603 7227 27603 13744 27603 13744 27604 7227 27604 13740 27604 13744 27605 13740 27605 13751 27605 13751 27606 13740 27606 13746 27606 13751 27607 13746 27607 13745 27607 13745 27608 13746 27608 13741 27608 13745 27609 13741 27609 7091 27609 7091 27610 13741 27610 13747 27610 13728 27611 13749 27611 13748 27611 13748 27612 13749 27612 13744 27612 13748 27613 13744 27613 13750 27613 13750 27614 13744 27614 13751 27614 13750 27615 13751 27615 13752 27615 13752 27616 13751 27616 13745 27616 13752 27617 13745 27617 7092 27617 7092 27618 13745 27618 7091 27618 7177 27619 7179 27619 13753 27619 13761 27620 13754 27620 13755 27620 13755 27621 13754 27621 13756 27621 13755 27622 13756 27622 13779 27622 13779 27623 13756 27623 13757 27623 13757 27624 13756 27624 13759 27624 13757 27625 13759 27625 13778 27625 13778 27626 13759 27626 13777 27626 13777 27627 13759 27627 7096 27627 13777 27628 7096 27628 13758 27628 7177 27629 13753 27629 7176 27629 13763 27630 7096 27630 13764 27630 13764 27631 7096 27631 13759 27631 13764 27632 13759 27632 13760 27632 13760 27633 13759 27633 13756 27633 13760 27634 13756 27634 13753 27634 13753 27635 13756 27635 13754 27635 13753 27636 13754 27636 7176 27636 7176 27637 13754 27637 13761 27637 7097 27638 13763 27638 13762 27638 13762 27639 13763 27639 13764 27639 13762 27640 13764 27640 13765 27640 13765 27641 13764 27641 13760 27641 13765 27642 13760 27642 13731 27642 13731 27643 13760 27643 13753 27643 13731 27644 13753 27644 7178 27644 7178 27645 13753 27645 7179 27645 4956 27646 7089 27646 13771 27646 13766 27647 7229 27647 13767 27647 13767 27648 7229 27648 13769 27648 13767 27649 13769 27649 13768 27649 13768 27650 13769 27650 13770 27650 7089 27651 13734 27651 13771 27651 13771 27652 13734 27652 13735 27652 13771 27653 13735 27653 13770 27653 13770 27654 13735 27654 13737 27654 13770 27655 13737 27655 13768 27655 4953 27656 4956 27656 13772 27656 13772 27657 4956 27657 13771 27657 13772 27658 13771 27658 13773 27658 13773 27659 13771 27659 13770 27659 13773 27660 13770 27660 13774 27660 13774 27661 13770 27661 13769 27661 13774 27662 13769 27662 7228 27662 7228 27663 13769 27663 7229 27663 13803 27664 4953 27664 13802 27664 13802 27665 4953 27665 13772 27665 13802 27666 13772 27666 13775 27666 13775 27667 13772 27667 13773 27667 13775 27668 13773 27668 13776 27668 13776 27669 13773 27669 13774 27669 13776 27670 13774 27670 7180 27670 7180 27671 13774 27671 7228 27671 13787 27672 7175 27672 13781 27672 13777 27673 13758 27673 13785 27673 13777 27674 13785 27674 13778 27674 13778 27675 13785 27675 13784 27675 13778 27676 13784 27676 13757 27676 13757 27677 13784 27677 13779 27677 13784 27678 13783 27678 13779 27678 13779 27679 13783 27679 13780 27679 13779 27680 13780 27680 13755 27680 13755 27681 13780 27681 7174 27681 13755 27682 7174 27682 13761 27682 7175 27683 7174 27683 13781 27683 13781 27684 7174 27684 13780 27684 13781 27685 13780 27685 13782 27685 13782 27686 13780 27686 13783 27686 13782 27687 13783 27687 13788 27687 13788 27688 13783 27688 13784 27688 13788 27689 13784 27689 4968 27689 4968 27690 13784 27690 13785 27690 7172 27691 13787 27691 13786 27691 13786 27692 13787 27692 13781 27692 13786 27693 13781 27693 13790 27693 13790 27694 13781 27694 13782 27694 13790 27695 13782 27695 13792 27695 13792 27696 13782 27696 13788 27696 13792 27697 13788 27697 13794 27697 13794 27698 13788 27698 4968 27698 13804 27699 7172 27699 13805 27699 13805 27700 7172 27700 13786 27700 13805 27701 13786 27701 13789 27701 13789 27702 13786 27702 13790 27702 13789 27703 13790 27703 13791 27703 13791 27704 13790 27704 13792 27704 13791 27705 13792 27705 13793 27705 13793 27706 13792 27706 13794 27706 7181 27707 7333 27707 13801 27707 13801 27708 7333 27708 13795 27708 13801 27709 13795 27709 13796 27709 13796 27710 13795 27710 13797 27710 13796 27711 13797 27711 13798 27711 13798 27712 13797 27712 13799 27712 13798 27713 13799 27713 4963 27713 4963 27714 13799 27714 13800 27714 7180 27715 7181 27715 13776 27715 13776 27716 7181 27716 13801 27716 13776 27717 13801 27717 13775 27717 13775 27718 13801 27718 13796 27718 13775 27719 13796 27719 13802 27719 13802 27720 13796 27720 13798 27720 13802 27721 13798 27721 13803 27721 13803 27722 13798 27722 4963 27722 13809 27723 13804 27723 13810 27723 13810 27724 13804 27724 13805 27724 13810 27725 13805 27725 13806 27725 13806 27726 13805 27726 13789 27726 13806 27727 13789 27727 13807 27727 13807 27728 13789 27728 13791 27728 13807 27729 13791 27729 4966 27729 4966 27730 13791 27730 13793 27730 13811 27731 13809 27731 13808 27731 13808 27732 13809 27732 13810 27732 13808 27733 13810 27733 13812 27733 13812 27734 13810 27734 13806 27734 13812 27735 13806 27735 13813 27735 13813 27736 13806 27736 13807 27736 13813 27737 13807 27737 4965 27737 4965 27738 13807 27738 4966 27738 7340 27739 13811 27739 13814 27739 13814 27740 13811 27740 13808 27740 13814 27741 13808 27741 13816 27741 13816 27742 13808 27742 13812 27742 13816 27743 13812 27743 13817 27743 13817 27744 13812 27744 13813 27744 13817 27745 13813 27745 4964 27745 4964 27746 13813 27746 4965 27746 13820 27747 7340 27747 13821 27747 13821 27748 7340 27748 13814 27748 13821 27749 13814 27749 13815 27749 13815 27750 13814 27750 13816 27750 13815 27751 13816 27751 13818 27751 13818 27752 13816 27752 13817 27752 13818 27753 13817 27753 13819 27753 13819 27754 13817 27754 4964 27754 7338 27755 13820 27755 13822 27755 13822 27756 13820 27756 13821 27756 13822 27757 13821 27757 13823 27757 13823 27758 13821 27758 13815 27758 13823 27759 13815 27759 13825 27759 13825 27760 13815 27760 13818 27760 13825 27761 13818 27761 13824 27761 13824 27762 13818 27762 13819 27762 13824 27763 4961 27763 13825 27763 13825 27764 4961 27764 13832 27764 13825 27765 13832 27765 13823 27765 13823 27766 13832 27766 13826 27766 13823 27767 13826 27767 13822 27767 13822 27768 13826 27768 13834 27768 13822 27769 13834 27769 7338 27769 13836 27770 7335 27770 13834 27770 13834 27771 7335 27771 7337 27771 13834 27772 7337 27772 7338 27772 13827 27773 13831 27773 13828 27773 13828 27774 13831 27774 13829 27774 13828 27775 13829 27775 13833 27775 13833 27776 13829 27776 13830 27776 13833 27777 13830 27777 13835 27777 13835 27778 13830 27778 13838 27778 13795 27779 13838 27779 13797 27779 13797 27780 13838 27780 13830 27780 13797 27781 13830 27781 13799 27781 13799 27782 13830 27782 13829 27782 13799 27783 13829 27783 13800 27783 13800 27784 13829 27784 13831 27784 4961 27785 13827 27785 13832 27785 13832 27786 13827 27786 13828 27786 13832 27787 13828 27787 13826 27787 13826 27788 13828 27788 13833 27788 13826 27789 13833 27789 13834 27789 13834 27790 13833 27790 13835 27790 13834 27791 13835 27791 13836 27791 13836 27792 13835 27792 13838 27792 13836 27793 13838 27793 13837 27793 13837 27794 13838 27794 13795 27794 13837 27795 13795 27795 7333 27795 5686 27796 13845 27796 13851 27796 13839 27797 13850 27797 13848 27797 13839 27798 13848 27798 13840 27798 13840 27799 13848 27799 13847 27799 13840 27800 13847 27800 13861 27800 13861 27801 13847 27801 13841 27801 13841 27802 13847 27802 13846 27802 13841 27803 13846 27803 13842 27803 13842 27804 13846 27804 13843 27804 13843 27805 13846 27805 13844 27805 13843 27806 13844 27806 13859 27806 13845 27807 13844 27807 13851 27807 13851 27808 13844 27808 13846 27808 13851 27809 13846 27809 13853 27809 13853 27810 13846 27810 13847 27810 13853 27811 13847 27811 13854 27811 13854 27812 13847 27812 13848 27812 13854 27813 13848 27813 13849 27813 13849 27814 13848 27814 13850 27814 5685 27815 5686 27815 13856 27815 13856 27816 5686 27816 13851 27816 13856 27817 13851 27817 13852 27817 13852 27818 13851 27818 13853 27818 13852 27819 13853 27819 13857 27819 13857 27820 13853 27820 13854 27820 13857 27821 13854 27821 13858 27821 13858 27822 13854 27822 13849 27822 13873 27823 5685 27823 13855 27823 13855 27824 5685 27824 13856 27824 13855 27825 13856 27825 13874 27825 13874 27826 13856 27826 13852 27826 13874 27827 13852 27827 13875 27827 13875 27828 13852 27828 13857 27828 13875 27829 13857 27829 4962 27829 4962 27830 13857 27830 13858 27830 13862 27831 5683 27831 13863 27831 13843 27832 13859 27832 13869 27832 13866 27833 6926 27833 13839 27833 13842 27834 13868 27834 13841 27834 13841 27835 13868 27835 13860 27835 13841 27836 13860 27836 13861 27836 13861 27837 13860 27837 13866 27837 13861 27838 13866 27838 13840 27838 13840 27839 13866 27839 13839 27839 13862 27840 13863 27840 13869 27840 13864 27841 6926 27841 13865 27841 13865 27842 6926 27842 13866 27842 13865 27843 13866 27843 13867 27843 13867 27844 13866 27844 13860 27844 13867 27845 13860 27845 13863 27845 13863 27846 13860 27846 13868 27846 13863 27847 13868 27847 13869 27847 13869 27848 13868 27848 13842 27848 13869 27849 13842 27849 13843 27849 13870 27850 13864 27850 13892 27850 13892 27851 13864 27851 13865 27851 13892 27852 13865 27852 13890 27852 13890 27853 13865 27853 13867 27853 13890 27854 13867 27854 13871 27854 13871 27855 13867 27855 13863 27855 13871 27856 13863 27856 5681 27856 5681 27857 13863 27857 5683 27857 13876 27858 13873 27858 13872 27858 13872 27859 13873 27859 13855 27859 13872 27860 13855 27860 13877 27860 13877 27861 13855 27861 13874 27861 13877 27862 13874 27862 13880 27862 13880 27863 13874 27863 13875 27863 13880 27864 13875 27864 13881 27864 13881 27865 13875 27865 4962 27865 5606 27866 13876 27866 13905 27866 13905 27867 13876 27867 13872 27867 13905 27868 13872 27868 13878 27868 13878 27869 13872 27869 13877 27869 13878 27870 13877 27870 13879 27870 13879 27871 13877 27871 13880 27871 13879 27872 13880 27872 4967 27872 4967 27873 13880 27873 13881 27873 13882 27874 6927 27874 13893 27874 6923 27875 13882 27875 13926 27875 13926 27876 13882 27876 13893 27876 13926 27877 13893 27877 13886 27877 13886 27878 13893 27878 13891 27878 13923 27879 13883 27879 13891 27879 13883 27880 13884 27880 13891 27880 13891 27881 13884 27881 13885 27881 13891 27882 13885 27882 13886 27882 13891 27883 13889 27883 13923 27883 13923 27884 13889 27884 13888 27884 13923 27885 13888 27885 13887 27885 5681 27886 13888 27886 13871 27886 13871 27887 13888 27887 13889 27887 13871 27888 13889 27888 13890 27888 13890 27889 13889 27889 13891 27889 13890 27890 13891 27890 13892 27890 13892 27891 13891 27891 13893 27891 13892 27892 13893 27892 13870 27892 13870 27893 13893 27893 6927 27893 13894 27894 7343 27894 13910 27894 13879 27895 4967 27895 4978 27895 13878 27896 13879 27896 13899 27896 13905 27897 13878 27897 13901 27897 7348 27898 5606 27898 13906 27898 13906 27899 5606 27899 13905 27899 7348 27900 13906 27900 7347 27900 7347 27901 13906 27901 13907 27901 7347 27902 13907 27902 7346 27902 7346 27903 13907 27903 13896 27903 7346 27904 13896 27904 13895 27904 13895 27905 13896 27905 13909 27905 13895 27906 13909 27906 13911 27906 13879 27907 4978 27907 13899 27907 13899 27908 4978 27908 4977 27908 13899 27909 4977 27909 13900 27909 13900 27910 4977 27910 4976 27910 13900 27911 4976 27911 13897 27911 13897 27912 4976 27912 13898 27912 13897 27913 13898 27913 13904 27913 13904 27914 13898 27914 13916 27914 13904 27915 13916 27915 13915 27915 13878 27916 13899 27916 13901 27916 13901 27917 13899 27917 13900 27917 13901 27918 13900 27918 13902 27918 13902 27919 13900 27919 13897 27919 13902 27920 13897 27920 13903 27920 13903 27921 13897 27921 13904 27921 13903 27922 13904 27922 13908 27922 13908 27923 13904 27923 13915 27923 13908 27924 13915 27924 13913 27924 13905 27925 13901 27925 13906 27925 13906 27926 13901 27926 13902 27926 13906 27927 13902 27927 13907 27927 13907 27928 13902 27928 13903 27928 13907 27929 13903 27929 13896 27929 13896 27930 13903 27930 13908 27930 13896 27931 13908 27931 13909 27931 13909 27932 13908 27932 13913 27932 13909 27933 13913 27933 13910 27933 13910 27934 7343 27934 13909 27934 13909 27935 7343 27935 7344 27935 13909 27936 7344 27936 13911 27936 7341 27937 13894 27937 13912 27937 13912 27938 13894 27938 13910 27938 13912 27939 13910 27939 13918 27939 13918 27940 13910 27940 13913 27940 13918 27941 13913 27941 13914 27941 13914 27942 13913 27942 13915 27942 13914 27943 13915 27943 4974 27943 4974 27944 13915 27944 13916 27944 7198 27945 7341 27945 13917 27945 13917 27946 7341 27946 13912 27946 13917 27947 13912 27947 13929 27947 13929 27948 13912 27948 13918 27948 13929 27949 13918 27949 13930 27949 13930 27950 13918 27950 13914 27950 13930 27951 13914 27951 4973 27951 4973 27952 13914 27952 4974 27952 13954 27953 13953 27953 13925 27953 13922 27954 13955 27954 13919 27954 13884 27955 13883 27955 13919 27955 13923 27956 13887 27956 5609 27956 13920 27957 6923 27957 13926 27957 13926 27958 13886 27958 13924 27958 13924 27959 13886 27959 13885 27959 13921 27960 13922 27960 5609 27960 5609 27961 13922 27961 13919 27961 5609 27962 13919 27962 13923 27962 13923 27963 13919 27963 13883 27963 13955 27964 13956 27964 13919 27964 13919 27965 13956 27965 13924 27965 13919 27966 13924 27966 13884 27966 13884 27967 13924 27967 13885 27967 13956 27968 13954 27968 13924 27968 13924 27969 13954 27969 13925 27969 13924 27970 13925 27970 13926 27970 13926 27971 13925 27971 6925 27971 13926 27972 6925 27972 13920 27972 13920 27973 6925 27973 6923 27973 7196 27974 7198 27974 13927 27974 13927 27975 7198 27975 13917 27975 13927 27976 13917 27976 13932 27976 13932 27977 13917 27977 13929 27977 13932 27978 13929 27978 13928 27978 13928 27979 13929 27979 13930 27979 13928 27980 13930 27980 4972 27980 4972 27981 13930 27981 4973 27981 7197 27982 7196 27982 13931 27982 13931 27983 7196 27983 13927 27983 13931 27984 13927 27984 13936 27984 13936 27985 13927 27985 13932 27985 13936 27986 13932 27986 13937 27986 13937 27987 13932 27987 13928 27987 13937 27988 13928 27988 4970 27988 4970 27989 13928 27989 4972 27989 13933 27990 13934 27990 13935 27990 5671 27991 7197 27991 13938 27991 13938 27992 7197 27992 13931 27992 13938 27993 13931 27993 13940 27993 13940 27994 13931 27994 13936 27994 13940 27995 13936 27995 13941 27995 13941 27996 13936 27996 13937 27996 13941 27997 13937 27997 4980 27997 4980 27998 13937 27998 4970 27998 5672 27999 5671 27999 13943 27999 13943 28000 5671 28000 13938 28000 13943 28001 13938 28001 13939 28001 13939 28002 13938 28002 13940 28002 13939 28003 13940 28003 13944 28003 13944 28004 13940 28004 13941 28004 13944 28005 13941 28005 4981 28005 4981 28006 13941 28006 4980 28006 5673 28007 5672 28007 13942 28007 13942 28008 5672 28008 13943 28008 13942 28009 13943 28009 13947 28009 13947 28010 13943 28010 13939 28010 13947 28011 13939 28011 13946 28011 13946 28012 13939 28012 13944 28012 13946 28013 13944 28013 13945 28013 13945 28014 13944 28014 4981 28014 13945 28015 13958 28015 13946 28015 13946 28016 13958 28016 13960 28016 13946 28017 13960 28017 13947 28017 13947 28018 13960 28018 13948 28018 13947 28019 13948 28019 13942 28019 13942 28020 13948 28020 13950 28020 13942 28021 13950 28021 5673 28021 13949 28022 5678 28022 13950 28022 13950 28023 5678 28023 5676 28023 13950 28024 5676 28024 5673 28024 13957 28025 13951 28025 13952 28025 13953 28026 13935 28026 4969 28026 4969 28027 13935 28027 13934 28027 4969 28028 13934 28028 13959 28028 13953 28029 13954 28029 13935 28029 13935 28030 13954 28030 13957 28030 13935 28031 13957 28031 13933 28031 13933 28032 13957 28032 13952 28032 13922 28033 13951 28033 13955 28033 13955 28034 13951 28034 13957 28034 13955 28035 13957 28035 13956 28035 13956 28036 13957 28036 13954 28036 13958 28037 13959 28037 13960 28037 13960 28038 13959 28038 13934 28038 13960 28039 13934 28039 13948 28039 13948 28040 13934 28040 13933 28040 13948 28041 13933 28041 13950 28041 13950 28042 13933 28042 13952 28042 13950 28043 13952 28043 13949 28043 13949 28044 13952 28044 13951 28044 13949 28045 13951 28045 5679 28045 5679 28046 13951 28046 13922 28046 5679 28047 13922 28047 13921 28047 13986 28048 13961 28048 5248 28048 13988 28049 13962 28049 13963 28049 13964 28050 13974 28050 13970 28050 13965 28051 13966 28051 13973 28051 13974 28052 13972 28052 13967 28052 13974 28053 13967 28053 13970 28053 13970 28054 13967 28054 4931 28054 13970 28055 4931 28055 13968 28055 13968 28056 4931 28056 13969 28056 13968 28057 13969 28057 13971 28057 13964 28058 13970 28058 13975 28058 13975 28059 13970 28059 13968 28059 13975 28060 13968 28060 13963 28060 13963 28061 13968 28061 13971 28061 13963 28062 13971 28062 13988 28062 13980 28063 13972 28063 13979 28063 13979 28064 13972 28064 13974 28064 13979 28065 13974 28065 13973 28065 13973 28066 13974 28066 13964 28066 13973 28067 13964 28067 13965 28067 13965 28068 13964 28068 13975 28068 13965 28069 13975 28069 5249 28069 5249 28070 13975 28070 13963 28070 5249 28071 13963 28071 5248 28071 5248 28072 13963 28072 13962 28072 5248 28073 13962 28073 13986 28073 13976 28074 14025 28074 13978 28074 13978 28075 14025 28075 14024 28075 13978 28076 14024 28076 13981 28076 13981 28077 14024 28077 13977 28077 13981 28078 13977 28078 13982 28078 13982 28079 13977 28079 4984 28079 13966 28080 13976 28080 13973 28080 13973 28081 13976 28081 13978 28081 13973 28082 13978 28082 13979 28082 13979 28083 13978 28083 13981 28083 13979 28084 13981 28084 13980 28084 13980 28085 13981 28085 13982 28085 13983 28086 5261 28086 13994 28086 13984 28087 13988 28087 13991 28087 13991 28088 13988 28088 13971 28088 13991 28089 13971 28089 13992 28089 13992 28090 13971 28090 13969 28090 13985 28091 13961 28091 13987 28091 13987 28092 13961 28092 13986 28092 13987 28093 13986 28093 13984 28093 13984 28094 13986 28094 13962 28094 13984 28095 13962 28095 13988 28095 13993 28096 13985 28096 13995 28096 13995 28097 13985 28097 13987 28097 13995 28098 13987 28098 13989 28098 13989 28099 13987 28099 13984 28099 13989 28100 13984 28100 13990 28100 13990 28101 13984 28101 13991 28101 13990 28102 13991 28102 13998 28102 13998 28103 13991 28103 13992 28103 5261 28104 13993 28104 13994 28104 13994 28105 13993 28105 13995 28105 13994 28106 13995 28106 13996 28106 13996 28107 13995 28107 13989 28107 13996 28108 13989 28108 14001 28108 14001 28109 13989 28109 13990 28109 14001 28110 13990 28110 13997 28110 13997 28111 13990 28111 13998 28111 14003 28112 13983 28112 13999 28112 13999 28113 13983 28113 13994 28113 13999 28114 13994 28114 14005 28114 14005 28115 13994 28115 13996 28115 14005 28116 13996 28116 14006 28116 14006 28117 13996 28117 14001 28117 14006 28118 14001 28118 14000 28118 14000 28119 14001 28119 13997 28119 14002 28120 14003 28120 14038 28120 14038 28121 14003 28121 13999 28121 14038 28122 13999 28122 14004 28122 14004 28123 13999 28123 14005 28123 14004 28124 14005 28124 14039 28124 14039 28125 14005 28125 14006 28125 14039 28126 14006 28126 4885 28126 4885 28127 14006 28127 14000 28127 14007 28128 4989 28128 4988 28128 14010 28129 14007 28129 14017 28129 5233 28130 5234 28130 14019 28130 14019 28131 5234 28131 14009 28131 14019 28132 14009 28132 14008 28132 14008 28133 14009 28133 5228 28133 14008 28134 5228 28134 14016 28134 14016 28135 5228 28135 14044 28135 14016 28136 14044 28136 14010 28136 14007 28137 4988 28137 14017 28137 14017 28138 4988 28138 4986 28138 14017 28139 4986 28139 14018 28139 14018 28140 4986 28140 14011 28140 14018 28141 14011 28141 14012 28141 14012 28142 14011 28142 14014 28142 14012 28143 14014 28143 14013 28143 14013 28144 14014 28144 4983 28144 14013 28145 4983 28145 14015 28145 14015 28146 4983 28146 4984 28146 14015 28147 4984 28147 13977 28147 14010 28148 14017 28148 14016 28148 14016 28149 14017 28149 14018 28149 14016 28150 14018 28150 14008 28150 14008 28151 14018 28151 14012 28151 14008 28152 14012 28152 14019 28152 14019 28153 14012 28153 14013 28153 14019 28154 14013 28154 14020 28154 14020 28155 14013 28155 14015 28155 14020 28156 14015 28156 14023 28156 14023 28157 14015 28157 13977 28157 14023 28158 13977 28158 14024 28158 5233 28159 14019 28159 14021 28159 14021 28160 14019 28160 14020 28160 14021 28161 14020 28161 5236 28161 5236 28162 14020 28162 14023 28162 5236 28163 14023 28163 14022 28163 14022 28164 14023 28164 14024 28164 14022 28165 14024 28165 14025 28165 14036 28166 14002 28166 14038 28166 14031 28167 14026 28167 14037 28167 5256 28168 14027 28168 14049 28168 14049 28169 14027 28169 14028 28169 14049 28170 14028 28170 14048 28170 14048 28171 14028 28171 14032 28171 14048 28172 14032 28172 14047 28172 14047 28173 14032 28173 14029 28173 14047 28174 14029 28174 14030 28174 14030 28175 14029 28175 14035 28175 14027 28176 14031 28176 14028 28176 14028 28177 14031 28177 14037 28177 14028 28178 14037 28178 14032 28178 14032 28179 14037 28179 14033 28179 14032 28180 14033 28180 14029 28180 14029 28181 14033 28181 14034 28181 14029 28182 14034 28182 14035 28182 14035 28183 14034 28183 14040 28183 14026 28184 14036 28184 14037 28184 14037 28185 14036 28185 14038 28185 14037 28186 14038 28186 14033 28186 14033 28187 14038 28187 14004 28187 14033 28188 14004 28188 14034 28188 14034 28189 14004 28189 14039 28189 14034 28190 14039 28190 14040 28190 14040 28191 14039 28191 4885 28191 14045 28192 14053 28192 14046 28192 14046 28193 14053 28193 14052 28193 14046 28194 14052 28194 14041 28194 14041 28195 14052 28195 14042 28195 14041 28196 14042 28196 4991 28196 4991 28197 14042 28197 14043 28197 14044 28198 14045 28198 14010 28198 14010 28199 14045 28199 14046 28199 14010 28200 14046 28200 14007 28200 14007 28201 14046 28201 14041 28201 14007 28202 14041 28202 4989 28202 4989 28203 14041 28203 4991 28203 14030 28204 4884 28204 14059 28204 14030 28205 14059 28205 14047 28205 14047 28206 14059 28206 14058 28206 14047 28207 14058 28207 14048 28207 14048 28208 14058 28208 14057 28208 14048 28209 14057 28209 14049 28209 14049 28210 14057 28210 5250 28210 14049 28211 5250 28211 5256 28211 4992 28212 14043 28212 14050 28212 14050 28213 14043 28213 14042 28213 14050 28214 14042 28214 14051 28214 14052 28215 14053 28215 5246 28215 5246 28216 14090 28216 14052 28216 14052 28217 14090 28217 14054 28217 14052 28218 14054 28218 14042 28218 14042 28219 14054 28219 14055 28219 14042 28220 14055 28220 14051 28220 5254 28221 5250 28221 14061 28221 14061 28222 5250 28222 14057 28222 14061 28223 14057 28223 14056 28223 14056 28224 14057 28224 14058 28224 14056 28225 14058 28225 14062 28225 14062 28226 14058 28226 14059 28226 14062 28227 14059 28227 6554 28227 6554 28228 14059 28228 4884 28228 5253 28229 5254 28229 14064 28229 14064 28230 5254 28230 14061 28230 14064 28231 14061 28231 14060 28231 14060 28232 14061 28232 14056 28232 14060 28233 14056 28233 14068 28233 14068 28234 14056 28234 14062 28234 14068 28235 14062 28235 14063 28235 14063 28236 14062 28236 6554 28236 5251 28237 5253 28237 14065 28237 14065 28238 5253 28238 14064 28238 14065 28239 14064 28239 14066 28239 14066 28240 14064 28240 14060 28240 14066 28241 14060 28241 14067 28241 14067 28242 14060 28242 14068 28242 14067 28243 14068 28243 14069 28243 14069 28244 14068 28244 14063 28244 5238 28245 5251 28245 14070 28245 14070 28246 5251 28246 14065 28246 14070 28247 14065 28247 14071 28247 14071 28248 14065 28248 14066 28248 14071 28249 14066 28249 14072 28249 14072 28250 14066 28250 14067 28250 14072 28251 14067 28251 14073 28251 14073 28252 14067 28252 14069 28252 14071 28253 14072 28253 14079 28253 14070 28254 14071 28254 14080 28254 5242 28255 5241 28255 14087 28255 14087 28256 5241 28256 14074 28256 14087 28257 14074 28257 14075 28257 14075 28258 14074 28258 5238 28258 14075 28259 5238 28259 14070 28259 4992 28260 14086 28260 6559 28260 6559 28261 14086 28261 14084 28261 6559 28262 14084 28262 14076 28262 14076 28263 14084 28263 14083 28263 14076 28264 14083 28264 6560 28264 6560 28265 14083 28265 14077 28265 6560 28266 14077 28266 14078 28266 14078 28267 14077 28267 14079 28267 14078 28268 14079 28268 6556 28268 6556 28269 14079 28269 14072 28269 6556 28270 14072 28270 14073 28270 14071 28271 14079 28271 14080 28271 14080 28272 14079 28272 14077 28272 14080 28273 14077 28273 14081 28273 14081 28274 14077 28274 14083 28274 14081 28275 14083 28275 14082 28275 14082 28276 14083 28276 14084 28276 14082 28277 14084 28277 14088 28277 14088 28278 14084 28278 14086 28278 14088 28279 14086 28279 14085 28279 4992 28280 14050 28280 14086 28280 14086 28281 14050 28281 14051 28281 14086 28282 14051 28282 14085 28282 14085 28283 14051 28283 14055 28283 14085 28284 14055 28284 14054 28284 14070 28285 14080 28285 14075 28285 14075 28286 14080 28286 14081 28286 14075 28287 14081 28287 14087 28287 14087 28288 14081 28288 14082 28288 14087 28289 14082 28289 14089 28289 14089 28290 14082 28290 14088 28290 14089 28291 14088 28291 14092 28291 14092 28292 14088 28292 14085 28292 14092 28293 14085 28293 14094 28293 14094 28294 14085 28294 14054 28294 14094 28295 14054 28295 14090 28295 5242 28296 14087 28296 14091 28296 14091 28297 14087 28297 14089 28297 14091 28298 14089 28298 5244 28298 5244 28299 14089 28299 14092 28299 5244 28300 14092 28300 5247 28300 5247 28301 14092 28301 14094 28301 5247 28302 14094 28302 14093 28302 14093 28303 14094 28303 14090 28303 14093 28304 14090 28304 5246 28304 14104 28305 14095 28305 14114 28305 14098 28306 14096 28306 14097 28306 14097 28307 14109 28307 14098 28307 14098 28308 14109 28308 14110 28308 14098 28309 14110 28309 14121 28309 14121 28310 14110 28310 14099 28310 14121 28311 14099 28311 14119 28311 14119 28312 14099 28312 14113 28312 14119 28313 14113 28313 4932 28313 4928 28314 4929 28314 14100 28314 14100 28315 4929 28315 14107 28315 14100 28316 14107 28316 14117 28316 14117 28317 14107 28317 14106 28317 14114 28318 14101 28318 14104 28318 14104 28319 14101 28319 14102 28319 14104 28320 14102 28320 14106 28320 14106 28321 14102 28321 14103 28321 14106 28322 14103 28322 14117 28322 14108 28323 14095 28323 14111 28323 14111 28324 14095 28324 14104 28324 14111 28325 14104 28325 14105 28325 14105 28326 14104 28326 14106 28326 14105 28327 14106 28327 14112 28327 14112 28328 14106 28328 14107 28328 14112 28329 14107 28329 4930 28329 4930 28330 14107 28330 4929 28330 14097 28331 14108 28331 14109 28331 14109 28332 14108 28332 14111 28332 14109 28333 14111 28333 14110 28333 14110 28334 14111 28334 14105 28334 14110 28335 14105 28335 14099 28335 14099 28336 14105 28336 14112 28336 14099 28337 14112 28337 14113 28337 14113 28338 14112 28338 4930 28338 14114 28339 14128 28339 14101 28339 14101 28340 14128 28340 14115 28340 14101 28341 14115 28341 14102 28341 14102 28342 14115 28342 14103 28342 14103 28343 14115 28343 14116 28343 14103 28344 14116 28344 14117 28344 14117 28345 14116 28345 14100 28345 14100 28346 14116 28346 4872 28346 14100 28347 4872 28347 4928 28347 4932 28348 14118 28348 14127 28348 14122 28349 14119 28349 14127 28349 14127 28350 14119 28350 4932 28350 7190 28351 14096 28351 14120 28351 14120 28352 14096 28352 14098 28352 14120 28353 14098 28353 14122 28353 14122 28354 14098 28354 14121 28354 14122 28355 14121 28355 14119 28355 14123 28356 7190 28356 14124 28356 14124 28357 7190 28357 14120 28357 14124 28358 14120 28358 14125 28358 14125 28359 14120 28359 14122 28359 14125 28360 14122 28360 14126 28360 14126 28361 14122 28361 14127 28361 14126 28362 14127 28362 4995 28362 4995 28363 14127 28363 14118 28363 4872 28364 14116 28364 14138 28364 14116 28365 14115 28365 14130 28365 14115 28366 14128 28366 14129 28366 14115 28367 14129 28367 14130 28367 14130 28368 14129 28368 7358 28368 14130 28369 7358 28369 14133 28369 14133 28370 7358 28370 7360 28370 14133 28371 7360 28371 14134 28371 14134 28372 7360 28372 14131 28372 14134 28373 14131 28373 14136 28373 14116 28374 14130 28374 14138 28374 14138 28375 14130 28375 14133 28375 14138 28376 14133 28376 14132 28376 14132 28377 14133 28377 14134 28377 14132 28378 14134 28378 14135 28378 14135 28379 14134 28379 14136 28379 14135 28380 14136 28380 14137 28380 4872 28381 14138 28381 4886 28381 4886 28382 14138 28382 14132 28382 4886 28383 14132 28383 4887 28383 4887 28384 14132 28384 14135 28384 4887 28385 14135 28385 4881 28385 4881 28386 14135 28386 14137 28386 4881 28387 14137 28387 14167 28387 14126 28388 4995 28388 4994 28388 14124 28389 14125 28389 14150 28389 14140 28390 14139 28390 14141 28390 14141 28391 14139 28391 14123 28391 14141 28392 14123 28392 14124 28392 14140 28393 14141 28393 14142 28393 14142 28394 14141 28394 14143 28394 14142 28395 14143 28395 7356 28395 7356 28396 14143 28396 14144 28396 7356 28397 14144 28397 14145 28397 14145 28398 14144 28398 14152 28398 14145 28399 14152 28399 7354 28399 7354 28400 14152 28400 14146 28400 7354 28401 14146 28401 7352 28401 14126 28402 4994 28402 14163 28402 14163 28403 4994 28403 4993 28403 14163 28404 4993 28404 14147 28404 14147 28405 4993 28405 4985 28405 14147 28406 4985 28406 14161 28406 14161 28407 4985 28407 14148 28407 14161 28408 14148 28408 14149 28408 14149 28409 14148 28409 4979 28409 14149 28410 4979 28410 14159 28410 14159 28411 4979 28411 14155 28411 14159 28412 14155 28412 14157 28412 14124 28413 14150 28413 14141 28413 14141 28414 14150 28414 14151 28414 14141 28415 14151 28415 14143 28415 14143 28416 14151 28416 14162 28416 14143 28417 14162 28417 14144 28417 14144 28418 14162 28418 14160 28418 14144 28419 14160 28419 14152 28419 14152 28420 14160 28420 14158 28420 14152 28421 14158 28421 14146 28421 14146 28422 14158 28422 14165 28422 14146 28423 14165 28423 14153 28423 7352 28424 14146 28424 14154 28424 14154 28425 14146 28425 14153 28425 14154 28426 14153 28426 7349 28426 14155 28427 14156 28427 14157 28427 14157 28428 14156 28428 14178 28428 14157 28429 14178 28429 14166 28429 14166 28430 14165 28430 14157 28430 14157 28431 14165 28431 14158 28431 14157 28432 14158 28432 14159 28432 14159 28433 14158 28433 14160 28433 14159 28434 14160 28434 14149 28434 14149 28435 14160 28435 14162 28435 14149 28436 14162 28436 14161 28436 14161 28437 14162 28437 14151 28437 14161 28438 14151 28438 14147 28438 14147 28439 14151 28439 14150 28439 14147 28440 14150 28440 14163 28440 14163 28441 14150 28441 14125 28441 14163 28442 14125 28442 14126 28442 14171 28443 7349 28443 14172 28443 14172 28444 7349 28444 14153 28444 14172 28445 14153 28445 14164 28445 14164 28446 14153 28446 14165 28446 14164 28447 14165 28447 14175 28447 14175 28448 14165 28448 14166 28448 14185 28449 14167 28449 14187 28449 14187 28450 14167 28450 14137 28450 14187 28451 14137 28451 14168 28451 14168 28452 14137 28452 14169 28452 14169 28453 14137 28453 14136 28453 14169 28454 14136 28454 14170 28454 14170 28455 14136 28455 14193 28455 14193 28456 14136 28456 14131 28456 14193 28457 14131 28457 14194 28457 14172 28458 14164 28458 14176 28458 14173 28459 14171 28459 14172 28459 14172 28460 14176 28460 14173 28460 14173 28461 14176 28461 14197 28461 14173 28462 14197 28462 14196 28462 14179 28463 4971 28463 14177 28463 14177 28464 4971 28464 14174 28464 14164 28465 14175 28465 14176 28465 14176 28466 14175 28466 14179 28466 14176 28467 14179 28467 14197 28467 14197 28468 14179 28468 14177 28468 14156 28469 4971 28469 14178 28469 14178 28470 4971 28470 14179 28470 14178 28471 14179 28471 14166 28471 14166 28472 14179 28472 14175 28472 14170 28473 14193 28473 14191 28473 14168 28474 14169 28474 14188 28474 14180 28475 14181 28475 14182 28475 14184 28476 14207 28476 6566 28476 14207 28477 14184 28477 14181 28477 14180 28478 14182 28478 14203 28478 14189 28479 14203 28479 14190 28479 6566 28480 14183 28480 14184 28480 14184 28481 14183 28481 6565 28481 14184 28482 6565 28482 14186 28482 14186 28483 6565 28483 14185 28483 14186 28484 14185 28484 14187 28484 14181 28485 14184 28485 14182 28485 14182 28486 14184 28486 14186 28486 14182 28487 14186 28487 14188 28487 14188 28488 14186 28488 14187 28488 14188 28489 14187 28489 14168 28489 14203 28490 14182 28490 14190 28490 14190 28491 14182 28491 14188 28491 14190 28492 14188 28492 14191 28492 14191 28493 14188 28493 14169 28493 14191 28494 14169 28494 14170 28494 14189 28495 14190 28495 7189 28495 7189 28496 14190 28496 14191 28496 7189 28497 14191 28497 14192 28497 14192 28498 14191 28498 14193 28498 14192 28499 14193 28499 14194 28499 14174 28500 4927 28500 14199 28500 14195 28501 14196 28501 14198 28501 14198 28502 14196 28502 14197 28502 14198 28503 14197 28503 14199 28503 14199 28504 14197 28504 14177 28504 14199 28505 14177 28505 14174 28505 7237 28506 14195 28506 14200 28506 14200 28507 14195 28507 14198 28507 14200 28508 14198 28508 14219 28508 14219 28509 14198 28509 14199 28509 14219 28510 14199 28510 4926 28510 4926 28511 14199 28511 4927 28511 7187 28512 14227 28512 14204 28512 14204 28513 14227 28513 14201 28513 14204 28514 14201 28514 14205 28514 14205 28515 14201 28515 14228 28515 14205 28516 14228 28516 14206 28516 14206 28517 14228 28517 14235 28517 14206 28518 14235 28518 14208 28518 14208 28519 14235 28519 14202 28519 14208 28520 14202 28520 6516 28520 6516 28521 14202 28521 14230 28521 14189 28522 7187 28522 14203 28522 14203 28523 7187 28523 14204 28523 14203 28524 14204 28524 14180 28524 14180 28525 14204 28525 14205 28525 14180 28526 14205 28526 14181 28526 14181 28527 14205 28527 14206 28527 14181 28528 14206 28528 14207 28528 14207 28529 14206 28529 14208 28529 14207 28530 14208 28530 6566 28530 6566 28531 14208 28531 6516 28531 14241 28532 14239 28532 14215 28532 14215 28533 14239 28533 14209 28533 14215 28534 14209 28534 14220 28534 14220 28535 14209 28535 14238 28535 14220 28536 14238 28536 14237 28536 14216 28537 14210 28537 14241 28537 4922 28538 14211 28538 14214 28538 14219 28539 4926 28539 14212 28539 14219 28540 14212 28540 14218 28540 14218 28541 14212 28541 4924 28541 14218 28542 4924 28542 14213 28542 14213 28543 4924 28543 4922 28543 14213 28544 4922 28544 14216 28544 14216 28545 4922 28545 14214 28545 14216 28546 14214 28546 14210 28546 14241 28547 14215 28547 14216 28547 14216 28548 14215 28548 14223 28548 14216 28549 14223 28549 14213 28549 14213 28550 14223 28550 14217 28550 14213 28551 14217 28551 14218 28551 14218 28552 14217 28552 14200 28552 14218 28553 14200 28553 14219 28553 14220 28554 14221 28554 14215 28554 14215 28555 14221 28555 14222 28555 14215 28556 14222 28556 14223 28556 14223 28557 14222 28557 14224 28557 14223 28558 14224 28558 14217 28558 14217 28559 14224 28559 7237 28559 14217 28560 7237 28560 14200 28560 14229 28561 14232 28561 14233 28561 14225 28562 14226 28562 14202 28562 14201 28563 14227 28563 14231 28563 14201 28564 14232 28564 14228 28564 14228 28565 14232 28565 14229 28565 14228 28566 14229 28566 14235 28566 14202 28567 14226 28567 14230 28567 14201 28568 14231 28568 14232 28568 14232 28569 14231 28569 14236 28569 14232 28570 14236 28570 14233 28570 14243 28571 14226 28571 14240 28571 14240 28572 14226 28572 14225 28572 14240 28573 14225 28573 14234 28573 14202 28574 14235 28574 14225 28574 14225 28575 14235 28575 14229 28575 14225 28576 14229 28576 14234 28576 14234 28577 14229 28577 14233 28577 14234 28578 14233 28578 14238 28578 14238 28579 14233 28579 14236 28579 14238 28580 14236 28580 14237 28580 14238 28581 14209 28581 14234 28581 14234 28582 14209 28582 14239 28582 14234 28583 14239 28583 14240 28583 14240 28584 14239 28584 14241 28584 14240 28585 14241 28585 14243 28585 14243 28586 14241 28586 14210 28586 14243 28587 14210 28587 14214 28587 14230 28588 14226 28588 14242 28588 14242 28589 14226 28589 14243 28589 14242 28590 14243 28590 14244 28590 14244 28591 14243 28591 14214 28591 14244 28592 14214 28592 14211 28592 14289 28593 7209 28593 7211 28593 14291 28594 14253 28594 14250 28594 14245 28595 14246 28595 14248 28595 14277 28596 6549 28596 6550 28596 14276 28597 14277 28597 14247 28597 7365 28598 14276 28598 14252 28598 14277 28599 6550 28599 14247 28599 14247 28600 6550 28600 14249 28600 14247 28601 14249 28601 14248 28601 14248 28602 14249 28602 6553 28602 14248 28603 6553 28603 14245 28603 14276 28604 14247 28604 14252 28604 14252 28605 14247 28605 14248 28605 14252 28606 14248 28606 14250 28606 14250 28607 14248 28607 14246 28607 14250 28608 14246 28608 14291 28608 7365 28609 14252 28609 14251 28609 14251 28610 14252 28610 14250 28610 14251 28611 14250 28611 7211 28611 7211 28612 14250 28612 14253 28612 7211 28613 14253 28613 14289 28613 14269 28614 14301 28614 6548 28614 14257 28615 14300 28615 14262 28615 14258 28616 7371 28616 14254 28616 14254 28617 7371 28617 14256 28617 14254 28618 14256 28618 14255 28618 14255 28619 14256 28619 7208 28619 14255 28620 7208 28620 14257 28620 7368 28621 14259 28621 14258 28621 14258 28622 14259 28622 7369 28622 14258 28623 7369 28623 7371 28623 14258 28624 14264 28624 7368 28624 7368 28625 14264 28625 14265 28625 7368 28626 14265 28626 7367 28626 7367 28627 14265 28627 14260 28627 7367 28628 14260 28628 14261 28628 14257 28629 14262 28629 14255 28629 14255 28630 14262 28630 14287 28630 14255 28631 14287 28631 14254 28631 14254 28632 14287 28632 14263 28632 14254 28633 14263 28633 14258 28633 14258 28634 14263 28634 14283 28634 14258 28635 14283 28635 14264 28635 14264 28636 14283 28636 14280 28636 14264 28637 14280 28637 14265 28637 14265 28638 14280 28638 14279 28638 14265 28639 14279 28639 14260 28639 14260 28640 14279 28640 14278 28640 14260 28641 14278 28641 14266 28641 14266 28642 14267 28642 14260 28642 14260 28643 14267 28643 14268 28643 14260 28644 14268 28644 14261 28644 14269 28645 6548 28645 14270 28645 14270 28646 6548 28646 14271 28646 14270 28647 14271 28647 14286 28647 14286 28648 14271 28648 14272 28648 14286 28649 14272 28649 14285 28649 14285 28650 14272 28650 6551 28650 14285 28651 6551 28651 14284 28651 14284 28652 6551 28652 14273 28652 14284 28653 14273 28653 14282 28653 14282 28654 14273 28654 6555 28654 14282 28655 6555 28655 14281 28655 14281 28656 6555 28656 14274 28656 14281 28657 14274 28657 14275 28657 14275 28658 14274 28658 6549 28658 14275 28659 6549 28659 14277 28659 7365 28660 14267 28660 14276 28660 14276 28661 14267 28661 14266 28661 14276 28662 14266 28662 14277 28662 14277 28663 14266 28663 14278 28663 14277 28664 14278 28664 14275 28664 14275 28665 14278 28665 14279 28665 14275 28666 14279 28666 14281 28666 14281 28667 14279 28667 14280 28667 14281 28668 14280 28668 14282 28668 14282 28669 14280 28669 14283 28669 14282 28670 14283 28670 14284 28670 14284 28671 14283 28671 14263 28671 14284 28672 14263 28672 14285 28672 14285 28673 14263 28673 14287 28673 14285 28674 14287 28674 14286 28674 14286 28675 14287 28675 14262 28675 14286 28676 14262 28676 14270 28676 14270 28677 14262 28677 14300 28677 14270 28678 14300 28678 14269 28678 7209 28679 14289 28679 14288 28679 14288 28680 14289 28680 14311 28680 14311 28681 14289 28681 14315 28681 14315 28682 14289 28682 14253 28682 14315 28683 14253 28683 14290 28683 14290 28684 14253 28684 14291 28684 14290 28685 14291 28685 14304 28685 14304 28686 14291 28686 14246 28686 14304 28687 14246 28687 14319 28687 14246 28688 14245 28688 14319 28688 14319 28689 14245 28689 6553 28689 14319 28690 6553 28690 14292 28690 14299 28691 14293 28691 14294 28691 14294 28692 14293 28692 14296 28692 14294 28693 14296 28693 14295 28693 14295 28694 14296 28694 14321 28694 14295 28695 14321 28695 14302 28695 14302 28696 14321 28696 14297 28696 14302 28697 14297 28697 14298 28697 14298 28698 14297 28698 4875 28698 7208 28699 14299 28699 14257 28699 14257 28700 14299 28700 14294 28700 14257 28701 14294 28701 14300 28701 14300 28702 14294 28702 14295 28702 14300 28703 14295 28703 14269 28703 14269 28704 14295 28704 14302 28704 14269 28705 14302 28705 14301 28705 14301 28706 14302 28706 14298 28706 14319 28707 14292 28707 14318 28707 14316 28708 14312 28708 14303 28708 14290 28709 14304 28709 14305 28709 14312 28710 14306 28710 14308 28710 14311 28711 14315 28711 14310 28711 14306 28712 14326 28712 14307 28712 14306 28713 14307 28713 14308 28713 14308 28714 14307 28714 14309 28714 14308 28715 14309 28715 14313 28715 14313 28716 14309 28716 7364 28716 14313 28717 7364 28717 14310 28717 14310 28718 7364 28718 14288 28718 14310 28719 14288 28719 14311 28719 14312 28720 14308 28720 14303 28720 14303 28721 14308 28721 14313 28721 14303 28722 14313 28722 14314 28722 14314 28723 14313 28723 14310 28723 14314 28724 14310 28724 14305 28724 14305 28725 14310 28725 14315 28725 14305 28726 14315 28726 14290 28726 14316 28727 14303 28727 14317 28727 14317 28728 14303 28728 14314 28728 14317 28729 14314 28729 4883 28729 4883 28730 14314 28730 14305 28730 4883 28731 14305 28731 14318 28731 14318 28732 14305 28732 14304 28732 14318 28733 14304 28733 14319 28733 14293 28734 7372 28734 14320 28734 14293 28735 14320 28735 14296 28735 14296 28736 14320 28736 14330 28736 14296 28737 14330 28737 14321 28737 14321 28738 14330 28738 14322 28738 14321 28739 14322 28739 14297 28739 14297 28740 14322 28740 4873 28740 14297 28741 4873 28741 4875 28741 14316 28742 14323 28742 14312 28742 14312 28743 14323 28743 14324 28743 14312 28744 14324 28744 14306 28744 14306 28745 14324 28745 14325 28745 14306 28746 14325 28746 14326 28746 14326 28747 14325 28747 14329 28747 14330 28748 14320 28748 14327 28748 14320 28749 7372 28749 7373 28749 14320 28750 7373 28750 14327 28750 14327 28751 7373 28751 7375 28751 14327 28752 7375 28752 14331 28752 14331 28753 7375 28753 14328 28753 14331 28754 14328 28754 14332 28754 14332 28755 14328 28755 14329 28755 14332 28756 14329 28756 14325 28756 4873 28757 14322 28757 14333 28757 14333 28758 14322 28758 14330 28758 14330 28759 14327 28759 14333 28759 14333 28760 14327 28760 14331 28760 14333 28761 14331 28761 14335 28761 14335 28762 14331 28762 14332 28762 14335 28763 14332 28763 14337 28763 14337 28764 14332 28764 14325 28764 14337 28765 14325 28765 14324 28765 4873 28766 14333 28766 14334 28766 14334 28767 14333 28767 14335 28767 14334 28768 14335 28768 14336 28768 14336 28769 14335 28769 14337 28769 14336 28770 14337 28770 4876 28770 4876 28771 14337 28771 14324 28771 4876 28772 14324 28772 14323 28772 14645 28773 14338 28773 14339 28773 14645 28774 14339 28774 14340 28774 14340 28775 14339 28775 5173 28775 14340 28776 5173 28776 4800 28776 14347 28777 9439 28777 14341 28777 14347 28778 14341 28778 14342 28778 14342 28779 14341 28779 9438 28779 14342 28780 9438 28780 9719 28780 9727 28781 14343 28781 14347 28781 5174 28782 14344 28782 9719 28782 14346 28783 9726 28783 14345 28783 9719 28784 14344 28784 14342 28784 14342 28785 14344 28785 7293 28785 14342 28786 7293 28786 7291 28786 14345 28787 9727 28787 14346 28787 14346 28788 9727 28788 14347 28788 14346 28789 14347 28789 14348 28789 14348 28790 14347 28790 14342 28790 14348 28791 14342 28791 7289 28791 7289 28792 14342 28792 7291 28792 9722 28793 14350 28793 14349 28793 14349 28794 14350 28794 5174 28794 14349 28795 5174 28795 9718 28795 9718 28796 5174 28796 9719 28796 14351 28797 5531 28797 14352 28797 14351 28798 14352 28798 14358 28798 14358 28799 14352 28799 9495 28799 14358 28800 9495 28800 14362 28800 14353 28801 7251 28801 7250 28801 14354 28802 14355 28802 14361 28802 14356 28803 9696 28803 9698 28803 9698 28804 9696 28804 14351 28804 9698 28805 14351 28805 9699 28805 9699 28806 14351 28806 5203 28806 5203 28807 14351 28807 14357 28807 14357 28808 14351 28808 14358 28808 14357 28809 14358 28809 7250 28809 7250 28810 14358 28810 14362 28810 7250 28811 14362 28811 14353 28811 14360 28812 14359 28812 9695 28812 9695 28813 14354 28813 14360 28813 14360 28814 14354 28814 14361 28814 14360 28815 14361 28815 14362 28815 14362 28816 14361 28816 14363 28816 14362 28817 14363 28817 14353 28817 14364 28818 14365 28818 4616 28818 4616 28819 14365 28819 5262 28819 4616 28820 5262 28820 4577 28820 14366 28821 4580 28821 14367 28821 14367 28822 4580 28822 14368 28822 14367 28823 14368 28823 16087 28823 16087 28824 14368 28824 14365 28824 16087 28825 14365 28825 4722 28825 4722 28826 14365 28826 14364 28826 4814 28827 4816 28827 9843 28827 9843 28828 4816 28828 14649 28828 9843 28829 14649 28829 14370 28829 14369 28830 14371 28830 4497 28830 4497 28831 14371 28831 14370 28831 4497 28832 14370 28832 9555 28832 9555 28833 14370 28833 14649 28833 14369 28834 4496 28834 14371 28834 14371 28835 4496 28835 16806 28835 14371 28836 16806 28836 9832 28836 14381 28837 14372 28837 9358 28837 14381 28838 9358 28838 14373 28838 14373 28839 9358 28839 14374 28839 14373 28840 14374 28840 9810 28840 7552 28841 14373 28841 14375 28841 14375 28842 14373 28842 9810 28842 14373 28843 14378 28843 14381 28843 14381 28844 14378 28844 9803 28844 9806 28845 14376 28845 9807 28845 9807 28846 14376 28846 14375 28846 9807 28847 14375 28847 9808 28847 9808 28848 14375 28848 9810 28848 7550 28849 14378 28849 14377 28849 14377 28850 14378 28850 14373 28850 14377 28851 14373 28851 14379 28851 14379 28852 14373 28852 7552 28852 9801 28853 9800 28853 14380 28853 14380 28854 9800 28854 14381 28854 14380 28855 14381 28855 14382 28855 14382 28856 14381 28856 9803 28856 14390 28857 4613 28857 14391 28857 16729 28858 14383 28858 14388 28858 14388 28859 14383 28859 16730 28859 14388 28860 16730 28860 16731 28860 16745 28861 16743 28861 14640 28861 14640 28862 16743 28862 16742 28862 14640 28863 16742 28863 14662 28863 14391 28864 14385 28864 14384 28864 14384 28865 14385 28865 14660 28865 14384 28866 14660 28866 14386 28866 14386 28867 14660 28867 14661 28867 14386 28868 14661 28868 14662 28868 14662 28869 16742 28869 14386 28869 14386 28870 16742 28870 14387 28870 4613 28871 14390 28871 4611 28871 4611 28872 14390 28872 14396 28872 4611 28873 14396 28873 14388 28873 14388 28874 14396 28874 4677 28874 14388 28875 4677 28875 16729 28875 14389 28876 14390 28876 7525 28876 7525 28877 14390 28877 14391 28877 7525 28878 14391 28878 7526 28878 7526 28879 14391 28879 14384 28879 14397 28880 15722 28880 15719 28880 15712 28881 14392 28881 14393 28881 14393 28882 14392 28882 14394 28882 14393 28883 14394 28883 14396 28883 14396 28884 14394 28884 14395 28884 14396 28885 14395 28885 4677 28885 15719 28886 15717 28886 14397 28886 14397 28887 15717 28887 14386 28887 14397 28888 14386 28888 15724 28888 15724 28889 14386 28889 14387 28889 15724 28890 14387 28890 4678 28890 14401 28891 14398 28891 14399 28891 14401 28892 14399 28892 14407 28892 14407 28893 14399 28893 9781 28893 14407 28894 9781 28894 14406 28894 14409 28895 14400 28895 5521 28895 5521 28896 14400 28896 14401 28896 5521 28897 14401 28897 14403 28897 5880 28898 14402 28898 14401 28898 14402 28899 7507 28899 14401 28899 14401 28900 7507 28900 7505 28900 14401 28901 7505 28901 14403 28901 14404 28902 14405 28902 14406 28902 14406 28903 14405 28903 9777 28903 14401 28904 14407 28904 5880 28904 5880 28905 14407 28905 14406 28905 5880 28906 14406 28906 9780 28906 9780 28907 14406 28907 9777 28907 9780 28908 9777 28908 9779 28908 9775 28909 9774 28909 5521 28909 5521 28910 9774 28910 14408 28910 5521 28911 14408 28911 14409 28911 4625 28912 14410 28912 14411 28912 14411 28913 14410 28913 14412 28913 14411 28914 14412 28914 4626 28914 4626 28915 14412 28915 14413 28915 5149 28916 4600 28916 14413 28916 14413 28917 4600 28917 16127 28917 14413 28918 16127 28918 16128 28918 16128 28919 14414 28919 14413 28919 14413 28920 14414 28920 14415 28920 14413 28921 14415 28921 4626 28921 4860 28922 15495 28922 14416 28922 14416 28923 15495 28923 15510 28923 14416 28924 15510 28924 15519 28924 15683 28925 4904 28925 15709 28925 15709 28926 4904 28926 5932 28926 15709 28927 5932 28927 15710 28927 14609 28928 4828 28928 14417 28928 14609 28929 14417 28929 15617 28929 15617 28930 14417 28930 14418 28930 15617 28931 14418 28931 15604 28931 4840 28932 14419 28932 14420 28932 14420 28933 14419 28933 14421 28933 14420 28934 14421 28934 14422 28934 14422 28935 14421 28935 15587 28935 14422 28936 15587 28936 14423 28936 14423 28937 15587 28937 14424 28937 14423 28938 14424 28938 4841 28938 4841 28939 14424 28939 15579 28939 4841 28940 15579 28940 4842 28940 4842 28941 15579 28941 4538 28941 4836 28942 15570 28942 14425 28942 14425 28943 15570 28943 15565 28943 14425 28944 15565 28944 4838 28944 4838 28945 15565 28945 15563 28945 4838 28946 15563 28946 4469 28946 4469 28947 15563 28947 15571 28947 14590 28948 14426 28948 14430 28948 14430 28949 14426 28949 14427 28949 14514 28950 14428 28950 14517 28950 14517 28951 14428 28951 14429 28951 14517 28952 14429 28952 14518 28952 14518 28953 14429 28953 14431 28953 14430 28954 14427 28954 14582 28954 14582 28955 14427 28955 14524 28955 14582 28956 14524 28956 14431 28956 14431 28957 14524 28957 14523 28957 14431 28958 14523 28958 14518 28958 14426 28959 14590 28959 14432 28959 14432 28960 14590 28960 14597 28960 14433 28961 14437 28961 14597 28961 14597 28962 14437 28962 14434 28962 14597 28963 14434 28963 14432 28963 14592 28964 14440 28964 14435 28964 14592 28965 14435 28965 14593 28965 14435 28966 14436 28966 14593 28966 14593 28967 14436 28967 14533 28967 14593 28968 14533 28968 14594 28968 14594 28969 14533 28969 14538 28969 14594 28970 14538 28970 14595 28970 14595 28971 14538 28971 14536 28971 14595 28972 14536 28972 14433 28972 14433 28973 14536 28973 14535 28973 14433 28974 14535 28974 14437 28974 14428 28975 14514 28975 14438 28975 14438 28976 14514 28976 14439 28976 14438 28977 14439 28977 14510 28977 14440 28978 14592 28978 14441 28978 14441 28979 14592 28979 14588 28979 14441 28980 14588 28980 14505 28980 14438 28981 14510 28981 14578 28981 14578 28982 14510 28982 14509 28982 14578 28983 14509 28983 14442 28983 14442 28984 14509 28984 14507 28984 14442 28985 14507 28985 14588 28985 14588 28986 14507 28986 14505 28986 14546 28987 14443 28987 14444 28987 14444 28988 14443 28988 14445 28988 14444 28989 14445 28989 14549 28989 14549 28990 14445 28990 14446 28990 14549 28991 14446 28991 14447 28991 14447 28992 14446 28992 14467 28992 14480 28993 14567 28993 14470 28993 14470 28994 14567 28994 14447 28994 14470 28995 14447 28995 14467 28995 14443 28996 14546 28996 14464 28996 14464 28997 14546 28997 14557 28997 14464 28998 14557 28998 4546 28998 14483 28999 14448 28999 14486 28999 14486 29000 14448 29000 14569 29000 14486 29001 14569 29001 14449 29001 14569 29002 14568 29002 14449 29002 14449 29003 14568 29003 14450 29003 14449 29004 14450 29004 14451 29004 14451 29005 14450 29005 14481 29005 14481 29006 14450 29006 14567 29006 14481 29007 14567 29007 14480 29007 14553 29008 4544 29008 14452 29008 14452 29009 4544 29009 4545 29009 14452 29010 4545 29010 14557 29010 14557 29011 4545 29011 14453 29011 14557 29012 14453 29012 4546 29012 14461 29013 14462 29013 14454 29013 14461 29014 14454 29014 14455 29014 14454 29015 7206 29015 14455 29015 14455 29016 7206 29016 14456 29016 14455 29017 14456 29017 14552 29017 14552 29018 14456 29018 14457 29018 14552 29019 14457 29019 14459 29019 14459 29020 14457 29020 14458 29020 14459 29021 14458 29021 14553 29021 14553 29022 14458 29022 14460 29022 14553 29023 14460 29023 4544 29023 14448 29024 14483 29024 14461 29024 14461 29025 14483 29025 14462 29025 4845 29026 4844 29026 14463 29026 4845 29027 14463 29027 4548 29027 4548 29028 14463 29028 14443 29028 4548 29029 14443 29029 14464 29029 14465 29030 14471 29030 14466 29030 14471 29031 14467 29031 14446 29031 14471 29032 14446 29032 14466 29032 14466 29033 14446 29033 14445 29033 14466 29034 14445 29034 14468 29034 14468 29035 14445 29035 14443 29035 14468 29036 14443 29036 14463 29036 14465 29037 14466 29037 14469 29037 14469 29038 14466 29038 14468 29038 14469 29039 14468 29039 4859 29039 4859 29040 14468 29040 14463 29040 4859 29041 14463 29041 4844 29041 14470 29042 14467 29042 14471 29042 14470 29043 14471 29043 14473 29043 14473 29044 14471 29044 14465 29044 14473 29045 14465 29045 14472 29045 14472 29046 14478 29046 14473 29046 14473 29047 14478 29047 14474 29047 14473 29048 14474 29048 14470 29048 14470 29049 14474 29049 14480 29049 14475 29050 14476 29050 14479 29050 14479 29051 14476 29051 14477 29051 14479 29052 14477 29052 14481 29052 14481 29053 14477 29053 14451 29053 14478 29054 14475 29054 14474 29054 14474 29055 14475 29055 14479 29055 14474 29056 14479 29056 14480 29056 14480 29057 14479 29057 14481 29057 14482 29058 14484 29058 14485 29058 14484 29059 14483 29059 14486 29059 14484 29060 14486 29060 14485 29060 14485 29061 14486 29061 14449 29061 14485 29062 14449 29062 14487 29062 14487 29063 14449 29063 14451 29063 14487 29064 14451 29064 14477 29064 14482 29065 14485 29065 4823 29065 4823 29066 14485 29066 14487 29066 4823 29067 14487 29067 14488 29067 14488 29068 14487 29068 14477 29068 14488 29069 14477 29069 14476 29069 7205 29070 14490 29070 14489 29070 7205 29071 14489 29071 14482 29071 14482 29072 14489 29072 14484 29072 14484 29073 14489 29073 14462 29073 14484 29074 14462 29074 14483 29074 14490 29075 14491 29075 14489 29075 14489 29076 14491 29076 14454 29076 14489 29077 14454 29077 14462 29077 14457 29078 14456 29078 14492 29078 14493 29079 4835 29079 14498 29079 4544 29080 14460 29080 14497 29080 14497 29081 14460 29081 14458 29081 14497 29082 14458 29082 14496 29082 14496 29083 14458 29083 14457 29083 14496 29084 14457 29084 14494 29084 14494 29085 14457 29085 14492 29085 14494 29086 14492 29086 4832 29086 4832 29087 4833 29087 14494 29087 14494 29088 4833 29088 14495 29088 14494 29089 14495 29089 14496 29089 14496 29090 14495 29090 14493 29090 14496 29091 14493 29091 14497 29091 14497 29092 14493 29092 14498 29092 14497 29093 14498 29093 4544 29093 4830 29094 4510 29094 15593 29094 4830 29095 15593 29095 4831 29095 4831 29096 15593 29096 15592 29096 4831 29097 15592 29097 14499 29097 14499 29098 15592 29098 15600 29098 14499 29099 15600 29099 14500 29099 14500 29100 15600 29100 14501 29100 14500 29101 14501 29101 14502 29101 14502 29102 14501 29102 15604 29102 14502 29103 15604 29103 14418 29103 14441 29104 14505 29104 14503 29104 14441 29105 14503 29105 14504 29105 14504 29106 14503 29106 6126 29106 14504 29107 6126 29107 4502 29107 6126 29108 14503 29108 14506 29108 14503 29109 14505 29109 14507 29109 14503 29110 14507 29110 14506 29110 14506 29111 14507 29111 14509 29111 14506 29112 14509 29112 14508 29112 14508 29113 14509 29113 14510 29113 14508 29114 14510 29114 14512 29114 6126 29115 14506 29115 6127 29115 6127 29116 14506 29116 14508 29116 6127 29117 14508 29117 6117 29117 6117 29118 14508 29118 14512 29118 6117 29119 14512 29119 14511 29119 14510 29120 14439 29120 14516 29120 14510 29121 14516 29121 14512 29121 14512 29122 14516 29122 14513 29122 14512 29123 14513 29123 14511 29123 14439 29124 14514 29124 14516 29124 14516 29125 14514 29125 14515 29125 14516 29126 14515 29126 14513 29126 14513 29127 14515 29127 5934 29127 14517 29128 14518 29128 14521 29128 14521 29129 14518 29129 14519 29129 14521 29130 14519 29130 14520 29130 14520 29131 14519 29131 5930 29131 14514 29132 14517 29132 14515 29132 14515 29133 14517 29133 14521 29133 14515 29134 14521 29134 5934 29134 5934 29135 14521 29135 14520 29135 5930 29136 14519 29136 14522 29136 14519 29137 14518 29137 14523 29137 14519 29138 14523 29138 14522 29138 14522 29139 14523 29139 14524 29139 14522 29140 14524 29140 14527 29140 14527 29141 14524 29141 14427 29141 14527 29142 14427 29142 14525 29142 5930 29143 14522 29143 14526 29143 14526 29144 14522 29144 14527 29144 14526 29145 14527 29145 4821 29145 4821 29146 14527 29146 14525 29146 4821 29147 14525 29147 4819 29147 14529 29148 4819 29148 14525 29148 14531 29149 14528 29149 14529 29149 14529 29150 14525 29150 14531 29150 14531 29151 14525 29151 14427 29151 14531 29152 14427 29152 14426 29152 14528 29153 14531 29153 14530 29153 14530 29154 14531 29154 14426 29154 14530 29155 14426 29155 14432 29155 14540 29156 4504 29156 14532 29156 14538 29157 14533 29157 4505 29157 14542 29158 14534 29158 14543 29158 14437 29159 14535 29159 14537 29159 14537 29160 14535 29160 14536 29160 14537 29161 14536 29161 14541 29161 14541 29162 14536 29162 14538 29162 14541 29163 14538 29163 14540 29163 14540 29164 14538 29164 4505 29164 14540 29165 4505 29165 4504 29165 14532 29166 14539 29166 14540 29166 14540 29167 14539 29167 4825 29167 14540 29168 4825 29168 14541 29168 14541 29169 4825 29169 14542 29169 14541 29170 14542 29170 14537 29170 14537 29171 14542 29171 14543 29171 14537 29172 14543 29172 14437 29172 4693 29173 14544 29173 14558 29173 4693 29174 14558 29174 14545 29174 14545 29175 14558 29175 14557 29175 14545 29176 14557 29176 14546 29176 14546 29177 14444 29177 14545 29177 14545 29178 14444 29178 14548 29178 14545 29179 14548 29179 4693 29179 14549 29180 14447 29180 14550 29180 14550 29181 14447 29181 14562 29181 14547 29182 4697 29182 14548 29182 14548 29183 4697 29183 4694 29183 14548 29184 4694 29184 4693 29184 14444 29185 14549 29185 14548 29185 14548 29186 14549 29186 14550 29186 14548 29187 14550 29187 14547 29187 14547 29188 14550 29188 14562 29188 14547 29189 14562 29189 4699 29189 9511 29190 14563 29190 14551 29190 14563 29191 14461 29191 14455 29191 14563 29192 14455 29192 14551 29192 14551 29193 14455 29193 14552 29193 14551 29194 14552 29194 14559 29194 14559 29195 14552 29195 14459 29195 14559 29196 14459 29196 14554 29196 14554 29197 14459 29197 14553 29197 14554 29198 14553 29198 14555 29198 14555 29199 14553 29199 14452 29199 14555 29200 14452 29200 14556 29200 14556 29201 14452 29201 14557 29201 14556 29202 14557 29202 14558 29202 9511 29203 14551 29203 9522 29203 9522 29204 14551 29204 14559 29204 9522 29205 14559 29205 9521 29205 9521 29206 14559 29206 14554 29206 9521 29207 14554 29207 14560 29207 14560 29208 14554 29208 14555 29208 14560 29209 14555 29209 9519 29209 9519 29210 14555 29210 14556 29210 9519 29211 14556 29211 14561 29211 14561 29212 14556 29212 14558 29212 14561 29213 14558 29213 14544 29213 4701 29214 4699 29214 14562 29214 4701 29215 14562 29215 14566 29215 14566 29216 14562 29216 14447 29216 14566 29217 14447 29217 14567 29217 9511 29218 14573 29218 14564 29218 9511 29219 14564 29219 14563 29219 14563 29220 14564 29220 14448 29220 14563 29221 14448 29221 14461 29221 4701 29222 14566 29222 14565 29222 14566 29223 14567 29223 14450 29223 14566 29224 14450 29224 14565 29224 14565 29225 14450 29225 14568 29225 14565 29226 14568 29226 14570 29226 14570 29227 14568 29227 14569 29227 14570 29228 14569 29228 14572 29228 14572 29229 14569 29229 14448 29229 14572 29230 14448 29230 14564 29230 4701 29231 14565 29231 14571 29231 14571 29232 14565 29232 14570 29232 14571 29233 14570 29233 4702 29233 4702 29234 14570 29234 14572 29234 4702 29235 14572 29235 4705 29235 4705 29236 14572 29236 14564 29236 4705 29237 14564 29237 14573 29237 14579 29238 4686 29238 14586 29238 14579 29239 14586 29239 14577 29239 14577 29240 14586 29240 14428 29240 14577 29241 14428 29241 14438 29241 14574 29242 14578 29242 14442 29242 14574 29243 14442 29243 14575 29243 14575 29244 14442 29244 14588 29244 14575 29245 14588 29245 14576 29245 14438 29246 14578 29246 14577 29246 14577 29247 14578 29247 14574 29247 14577 29248 14574 29248 14579 29248 14579 29249 14574 29249 4688 29249 4688 29250 14574 29250 14580 29250 14580 29251 14574 29251 14575 29251 14580 29252 14575 29252 4691 29252 4691 29253 14575 29253 14576 29253 4691 29254 14576 29254 4692 29254 4684 29255 14581 29255 14584 29255 14581 29256 14430 29256 14582 29256 14581 29257 14582 29257 14584 29257 14584 29258 14582 29258 14431 29258 14584 29259 14431 29259 14583 29259 14583 29260 14431 29260 14429 29260 14583 29261 14429 29261 14585 29261 14585 29262 14429 29262 14428 29262 14585 29263 14428 29263 14586 29263 4684 29264 14584 29264 4683 29264 4683 29265 14584 29265 14583 29265 4683 29266 14583 29266 4682 29266 4682 29267 14583 29267 14585 29267 4682 29268 14585 29268 4680 29268 4680 29269 14585 29269 14586 29269 4680 29270 14586 29270 4686 29270 14591 29271 4692 29271 14576 29271 14591 29272 14576 29272 14587 29272 14587 29273 14576 29273 14588 29273 14587 29274 14588 29274 14592 29274 4684 29275 14604 29275 14589 29275 4684 29276 14589 29276 14581 29276 14581 29277 14589 29277 14590 29277 14581 29278 14590 29278 14430 29278 14591 29279 14587 29279 14598 29279 14587 29280 14592 29280 14593 29280 14587 29281 14593 29281 14598 29281 14598 29282 14593 29282 14594 29282 14598 29283 14594 29283 14599 29283 14599 29284 14594 29284 14595 29284 14599 29285 14595 29285 14596 29285 14596 29286 14595 29286 14433 29286 14596 29287 14433 29287 14601 29287 14601 29288 14433 29288 14597 29288 14601 29289 14597 29289 14603 29289 14603 29290 14597 29290 14590 29290 14603 29291 14590 29291 14589 29291 14591 29292 14598 29292 9518 29292 9518 29293 14598 29293 14599 29293 9518 29294 14599 29294 9520 29294 9520 29295 14599 29295 14596 29295 9520 29296 14596 29296 14600 29296 14600 29297 14596 29297 14601 29297 14600 29298 14601 29298 9523 29298 9523 29299 14601 29299 14603 29299 9523 29300 14603 29300 14602 29300 14602 29301 14603 29301 14589 29301 14602 29302 14589 29302 14604 29302 7444 29303 14605 29303 14606 29303 14606 29304 14605 29304 4826 29304 14606 29305 4826 29305 14607 29305 14607 29306 4826 29306 14608 29306 14607 29307 14608 29307 14609 29307 14609 29308 14608 29308 4828 29308 14612 29309 16676 29309 14668 29309 4604 29310 4602 29310 14610 29310 14611 29311 4618 29311 14610 29311 14610 29312 4618 29312 14612 29312 14610 29313 14612 29313 4604 29313 4604 29314 14612 29314 14668 29314 4586 29315 14613 29315 14671 29315 14671 29316 14613 29316 14614 29316 14615 29317 16663 29317 14616 29317 14616 29318 16663 29318 14617 29318 14616 29319 14617 29319 14618 29319 14618 29320 14617 29320 4583 29320 14618 29321 4583 29321 14619 29321 14619 29322 4583 29322 16665 29322 14620 29323 14622 29323 14621 29323 14621 29324 14622 29324 14623 29324 4592 29325 14621 29325 16670 29325 16670 29326 14621 29326 14623 29326 16670 29327 14623 29327 14624 29327 14624 29328 14623 29328 16543 29328 14625 29329 16672 29329 4638 29329 15954 29330 15989 29330 4638 29330 4638 29331 15989 29331 4635 29331 4638 29332 4635 29332 14625 29332 14625 29333 4635 29333 4573 29333 4573 29334 4571 29334 14625 29334 14625 29335 4571 29335 14626 29335 14625 29336 14626 29336 4570 29336 4566 29337 4567 29337 14654 29337 14654 29338 4567 29338 4597 29338 15714 29339 15792 29339 14629 29339 14629 29340 15792 29340 14627 29340 16729 29341 4677 29341 14628 29341 14628 29342 4677 29342 14629 29342 14387 29343 16742 29343 14630 29343 14630 29344 16742 29344 14632 29344 14627 29345 14631 29345 14630 29345 14632 29346 16749 29346 14630 29346 14630 29347 16749 29347 16756 29347 14630 29348 16756 29348 14627 29348 14627 29349 16756 29349 16738 29349 14627 29350 16738 29350 14629 29350 14629 29351 16738 29351 14633 29351 14629 29352 14633 29352 14628 29352 14634 29353 4728 29353 14635 29353 14634 29354 14635 29354 14636 29354 14636 29355 14635 29355 15733 29355 14636 29356 15733 29356 14638 29356 14388 29357 16731 29357 14637 29357 14637 29358 16731 29358 16732 29358 14637 29359 16732 29359 16726 29359 16726 29360 16727 29360 14637 29360 14637 29361 16727 29361 16728 29361 14637 29362 16728 29362 15733 29362 15733 29363 16728 29363 15909 29363 15733 29364 15909 29364 14638 29364 4665 29365 15731 29365 14640 29365 14640 29366 15731 29366 15729 29366 16605 29367 16721 29367 15729 29367 15729 29368 16721 29368 14639 29368 15729 29369 14643 29369 14640 29369 14640 29370 14643 29370 14641 29370 14640 29371 14641 29371 16745 29371 14639 29372 16741 29372 15729 29372 15729 29373 16741 29373 14642 29373 15729 29374 14642 29374 14643 29374 14385 29375 14391 29375 14658 29375 14658 29376 14391 29376 4671 29376 16692 29377 16794 29377 4491 29377 4491 29378 16794 29378 14646 29378 14644 29379 14338 29379 16805 29379 16805 29380 14338 29380 14645 29380 16805 29381 14645 29381 14646 29381 16806 29382 4491 29382 14646 29382 16806 29383 14646 29383 4477 29383 4477 29384 14646 29384 14645 29384 4477 29385 14645 29385 4796 29385 4806 29386 4805 29386 4480 29386 4480 29387 4805 29387 14647 29387 16483 29388 14648 29388 14649 29388 4790 29389 4473 29389 14666 29389 14666 29390 4473 29390 4816 29390 16483 29391 14649 29391 16498 29391 16498 29392 14649 29392 4816 29392 16498 29393 4816 29393 14650 29393 14650 29394 4816 29394 4473 29394 14650 29395 4473 29395 14651 29395 14651 29396 4473 29396 4475 29396 14651 29397 4475 29397 16513 29397 14625 29398 4570 29398 14652 29398 14652 29399 4570 29399 4563 29399 14652 29400 4563 29400 14653 29400 14653 29401 4563 29401 4565 29401 14653 29402 4565 29402 14654 29402 14654 29403 4565 29403 4566 29403 14620 29404 14621 29404 14655 29404 14655 29405 14621 29405 14656 29405 14655 29406 14656 29406 4569 29406 4569 29407 14656 29407 14657 29407 4569 29408 14657 29408 4567 29408 4567 29409 14657 29409 4597 29409 14385 29410 14658 29410 14660 29410 14660 29411 14658 29411 14659 29411 14660 29412 14659 29412 14661 29412 14661 29413 14659 29413 4666 29413 14661 29414 4666 29414 14662 29414 14662 29415 4666 29415 14663 29415 14662 29416 14663 29416 14640 29416 14640 29417 14663 29417 4665 29417 14647 29418 4805 29418 14664 29418 14664 29419 4805 29419 14665 29419 14664 29420 14665 29420 4809 29420 4809 29421 14665 29421 4791 29421 4809 29422 4791 29422 4810 29422 4810 29423 4791 29423 14667 29423 4810 29424 14667 29424 14666 29424 14666 29425 14667 29425 4790 29425 4604 29426 14668 29426 4605 29426 4605 29427 14668 29427 14669 29427 4605 29428 14669 29428 4606 29428 4606 29429 14669 29429 14670 29429 4606 29430 14670 29430 14671 29430 14671 29431 14670 29431 4586 29431 14614 29432 14613 29432 4609 29432 4609 29433 14613 29433 14672 29433 4609 29434 14672 29434 14673 29434 14673 29435 14672 29435 4585 29435 14673 29436 4585 29436 14674 29436 14674 29437 4585 29437 4584 29437 14674 29438 4584 29438 14617 29438 14617 29439 4584 29439 4583 29439 5545 29440 14676 29440 14675 29440 14675 29441 14676 29441 14678 29441 14676 29442 14677 29442 14678 29442 14678 29443 14677 29443 14682 29443 14678 29444 14682 29444 14679 29444 14679 29445 14682 29445 14684 29445 14679 29446 14684 29446 5547 29446 5547 29447 14684 29447 14680 29447 5547 29448 14680 29448 5548 29448 14680 29449 14681 29449 5548 29449 5548 29450 14681 29450 5533 29450 5548 29451 5533 29451 5549 29451 14677 29452 14687 29452 14682 29452 14682 29453 14687 29453 14683 29453 14682 29454 14683 29454 14684 29454 14684 29455 14683 29455 14685 29455 14684 29456 14685 29456 14680 29456 14680 29457 14685 29457 14686 29457 14686 29458 14685 29458 14683 29458 14686 29459 14683 29459 5542 29459 14683 29460 14687 29460 5542 29460 5542 29461 14687 29461 14688 29461 5542 29462 14688 29462 5540 29462 5540 29463 14688 29463 5534 29463 14690 29464 5480 29464 14689 29464 14689 29465 5480 29465 5481 29465 14689 29466 14691 29466 14690 29466 14690 29467 14691 29467 9849 29467 14690 29468 9849 29468 5478 29468 5478 29469 9849 29469 9850 29469 9389 29470 5467 29470 5468 29470 9389 29471 5468 29471 5482 29471 5482 29472 5468 29472 14696 29472 5482 29473 14696 29473 5481 29473 5481 29474 14696 29474 14695 29474 5481 29475 14695 29475 14689 29475 14689 29476 14695 29476 14692 29476 14689 29477 14692 29477 14691 29477 5471 29478 14693 29478 9852 29478 9852 29479 14693 29479 5472 29479 9852 29480 5472 29480 14694 29480 9852 29481 14692 29481 5471 29481 5471 29482 14692 29482 14695 29482 5471 29483 14695 29483 5469 29483 5469 29484 14695 29484 14696 29484 5509 29485 14697 29485 5511 29485 5511 29486 14697 29486 14704 29486 14706 29487 14702 29487 14704 29487 14704 29488 14702 29488 5512 29488 14704 29489 5512 29489 5511 29489 14698 29490 14699 29490 14703 29490 14703 29491 14699 29491 14701 29491 14703 29492 9856 29492 14698 29492 14698 29493 9856 29493 14700 29493 14698 29494 14700 29494 5513 29494 5513 29495 14700 29495 5506 29495 14701 29496 14702 29496 14703 29496 14703 29497 14702 29497 14706 29497 14703 29498 14706 29498 9856 29498 9856 29499 14706 29499 9854 29499 14697 29500 14707 29500 14704 29500 14704 29501 14707 29501 14705 29501 14704 29502 14705 29502 14706 29502 14706 29503 14705 29503 14708 29503 14706 29504 14708 29504 9854 29504 9854 29505 14708 29505 4766 29505 9398 29506 14711 29506 14707 29506 14707 29507 14711 29507 14705 29507 14711 29508 14719 29508 14705 29508 14705 29509 14719 29509 14710 29509 14705 29510 14710 29510 14708 29510 9858 29511 4766 29511 14724 29511 14724 29512 4766 29512 14708 29512 14724 29513 14708 29513 14709 29513 14709 29514 14708 29514 14710 29514 14709 29515 14710 29515 14718 29515 14719 29516 14711 29516 14715 29516 5503 29517 14712 29517 14722 29517 14722 29518 14712 29518 5502 29518 14722 29519 5502 29519 9863 29519 9863 29520 5502 29520 5501 29520 9863 29521 5501 29521 5497 29521 14713 29522 5505 29522 14714 29522 14714 29523 5505 29523 14717 29523 9393 29524 5496 29524 14713 29524 14713 29525 14714 29525 9393 29525 9393 29526 14714 29526 14715 29526 9393 29527 14715 29527 9395 29527 9395 29528 14715 29528 14711 29528 9395 29529 14711 29529 9398 29529 5503 29530 14716 29530 14717 29530 14717 29531 14716 29531 14721 29531 14717 29532 14721 29532 14714 29532 14714 29533 14721 29533 14718 29533 14714 29534 14718 29534 14715 29534 14715 29535 14718 29535 14710 29535 14715 29536 14710 29536 14719 29536 5503 29537 14722 29537 14716 29537 14716 29538 14722 29538 14720 29538 14716 29539 14720 29539 14721 29539 14721 29540 14720 29540 14723 29540 14721 29541 14723 29541 14718 29541 14718 29542 14723 29542 14724 29542 14718 29543 14724 29543 14709 29543 9863 29544 9861 29544 14722 29544 14722 29545 9861 29545 9860 29545 14722 29546 9860 29546 14720 29546 14720 29547 9860 29547 9859 29547 14720 29548 9859 29548 14723 29548 14723 29549 9859 29549 9858 29549 14723 29550 9858 29550 14724 29550 14731 29551 5221 29551 14729 29551 14729 29552 5221 29552 14725 29552 14729 29553 14725 29553 14726 29553 14726 29554 14725 29554 5226 29554 14726 29555 5226 29555 9684 29555 9684 29556 5226 29556 14727 29556 9684 29557 14727 29557 5225 29557 5223 29558 14732 29558 9466 29558 9466 29559 14732 29559 14728 29559 14726 29560 14730 29560 14729 29560 14729 29561 14730 29561 14733 29561 14729 29562 14733 29562 14731 29562 14731 29563 14733 29563 14728 29563 14731 29564 14728 29564 5222 29564 5222 29565 14728 29565 14732 29565 14730 29566 4760 29566 14733 29566 14733 29567 4760 29567 14734 29567 14733 29568 14734 29568 14728 29568 14728 29569 14734 29569 14738 29569 14728 29570 14738 29570 9466 29570 9466 29571 14738 29571 9474 29571 14735 29572 9474 29572 14736 29572 14736 29573 9474 29573 14738 29573 14736 29574 14738 29574 14753 29574 14753 29575 14738 29575 14737 29575 14737 29576 14738 29576 14734 29576 14737 29577 14734 29577 14746 29577 14746 29578 14734 29578 14745 29578 14745 29579 14734 29579 4760 29579 14745 29580 4760 29580 4762 29580 14754 29581 14739 29581 9689 29581 14740 29582 5216 29582 14749 29582 14749 29583 5216 29583 5215 29583 5213 29584 9464 29584 5214 29584 5214 29585 9464 29585 14751 29585 14744 29586 14741 29586 14748 29586 9690 29587 14742 29587 14743 29587 14743 29588 14742 29588 14741 29588 14743 29589 14741 29589 9689 29589 9689 29590 14741 29590 14744 29590 9689 29591 14744 29591 14754 29591 14754 29592 14744 29592 14750 29592 4762 29593 9687 29593 14745 29593 14745 29594 9687 29594 14747 29594 14745 29595 14747 29595 14746 29595 14746 29596 14747 29596 14755 29596 14748 29597 14740 29597 14744 29597 14744 29598 14740 29598 14749 29598 14744 29599 14749 29599 14750 29599 14750 29600 14749 29600 5215 29600 14750 29601 5215 29601 14751 29601 14751 29602 5215 29602 14752 29602 14751 29603 14752 29603 5214 29603 14756 29604 14753 29604 14755 29604 14755 29605 14753 29605 14737 29605 14755 29606 14737 29606 14746 29606 9463 29607 14735 29607 14756 29607 14756 29608 14735 29608 14736 29608 14756 29609 14736 29609 14753 29609 9687 29610 14739 29610 14747 29610 14747 29611 14739 29611 14754 29611 14747 29612 14754 29612 14755 29612 14755 29613 14754 29613 14750 29613 14755 29614 14750 29614 14756 29614 14756 29615 14750 29615 14751 29615 14756 29616 14751 29616 9463 29616 9463 29617 14751 29617 9464 29617 14763 29618 9744 29618 9743 29618 14757 29619 9423 29619 14769 29619 14769 29620 9423 29620 14765 29620 5634 29621 5633 29621 14767 29621 14767 29622 5633 29622 5631 29622 14767 29623 5631 29623 14758 29623 9429 29624 14761 29624 14759 29624 14759 29625 14761 29625 14762 29625 14759 29626 14762 29626 14771 29626 14771 29627 14762 29627 14760 29627 14771 29628 14760 29628 14770 29628 14770 29629 14760 29629 14764 29629 14761 29630 9744 29630 14762 29630 14762 29631 9744 29631 14763 29631 14762 29632 14763 29632 14760 29632 14760 29633 14763 29633 14765 29633 14760 29634 14765 29634 14764 29634 14764 29635 14765 29635 9423 29635 9741 29636 5636 29636 14766 29636 14766 29637 5636 29637 5634 29637 14766 29638 5634 29638 9743 29638 9743 29639 5634 29639 14767 29639 9743 29640 14767 29640 14763 29640 14763 29641 14767 29641 14758 29641 14763 29642 14758 29642 14765 29642 14765 29643 14758 29643 14768 29643 14765 29644 14768 29644 14769 29644 14776 29645 14778 29645 9429 29645 14771 29646 14770 29646 14772 29646 14759 29647 14771 29647 14774 29647 14771 29648 14772 29648 14774 29648 14774 29649 14772 29649 9428 29649 14774 29650 9428 29650 14773 29650 14773 29651 14775 29651 14774 29651 14774 29652 14775 29652 14776 29652 14774 29653 14776 29653 14759 29653 14759 29654 14776 29654 9429 29654 14781 29655 14778 29655 14777 29655 14777 29656 14778 29656 14776 29656 14777 29657 14776 29657 14783 29657 14783 29658 14776 29658 14775 29658 9420 29659 5623 29659 9424 29659 9424 29660 5623 29660 14790 29660 9739 29661 9738 29661 14779 29661 14779 29662 9738 29662 14786 29662 9738 29663 14780 29663 14786 29663 14786 29664 14780 29664 14782 29664 14786 29665 14782 29665 14784 29665 14784 29666 14782 29666 14789 29666 14784 29667 14789 29667 14790 29667 14780 29668 14781 29668 14782 29668 14782 29669 14781 29669 14777 29669 14782 29670 14777 29670 14789 29670 14789 29671 14777 29671 14783 29671 5623 29672 5621 29672 14790 29672 14790 29673 5621 29673 5629 29673 14790 29674 5629 29674 14784 29674 14784 29675 5629 29675 14785 29675 14784 29676 14785 29676 14786 29676 14786 29677 14785 29677 14787 29677 14786 29678 14787 29678 14779 29678 14779 29679 14787 29679 5627 29679 14779 29680 5627 29680 9739 29680 9739 29681 5627 29681 14788 29681 9739 29682 14788 29682 5625 29682 14783 29683 14775 29683 14789 29683 14789 29684 14775 29684 14773 29684 14789 29685 14773 29685 14790 29685 14790 29686 14773 29686 9428 29686 14790 29687 9428 29687 9424 29687 14794 29688 14791 29688 9734 29688 7152 29689 5781 29689 14796 29689 14792 29690 7151 29690 14793 29690 14793 29691 7151 29691 7152 29691 14793 29692 7152 29692 9734 29692 9734 29693 7152 29693 14796 29693 9734 29694 14796 29694 14794 29694 14796 29695 5781 29695 14795 29695 14794 29696 14796 29696 14799 29696 14791 29697 14794 29697 14805 29697 14796 29698 14795 29698 14799 29698 14799 29699 14795 29699 5780 29699 14799 29700 5780 29700 14800 29700 14800 29701 5780 29701 5778 29701 14800 29702 5778 29702 14797 29702 14797 29703 5778 29703 5777 29703 14797 29704 5777 29704 14801 29704 14801 29705 5777 29705 14798 29705 14801 29706 14798 29706 14804 29706 14794 29707 14799 29707 14805 29707 14805 29708 14799 29708 14800 29708 14805 29709 14800 29709 14806 29709 14806 29710 14800 29710 14797 29710 14806 29711 14797 29711 14802 29711 14802 29712 14797 29712 14801 29712 14802 29713 14801 29713 14803 29713 14803 29714 14801 29714 14804 29714 14803 29715 14804 29715 14810 29715 14791 29716 14805 29716 9736 29716 9736 29717 14805 29717 14806 29717 9736 29718 14806 29718 14807 29718 14807 29719 14806 29719 14802 29719 14807 29720 14802 29720 14808 29720 14808 29721 14802 29721 14803 29721 14808 29722 14803 29722 14809 29722 14809 29723 14803 29723 14810 29723 14809 29724 14810 29724 14812 29724 14825 29725 14811 29725 14817 29725 14804 29726 14798 29726 14814 29726 14810 29727 14804 29727 14813 29727 14812 29728 14810 29728 14816 29728 14804 29729 14814 29729 14813 29729 14813 29730 14814 29730 5771 29730 14813 29731 5771 29731 14815 29731 14815 29732 5771 29732 5770 29732 14815 29733 5770 29733 14824 29733 14810 29734 14813 29734 14816 29734 14816 29735 14813 29735 14815 29735 14816 29736 14815 29736 14817 29736 14817 29737 14815 29737 14824 29737 14817 29738 14824 29738 14825 29738 14812 29739 14816 29739 9430 29739 9430 29740 14816 29740 14817 29740 9430 29741 14817 29741 14818 29741 14818 29742 14817 29742 14811 29742 14818 29743 14811 29743 14823 29743 14821 29744 14828 29744 14822 29744 5768 29745 14820 29745 14819 29745 14819 29746 14820 29746 14821 29746 14821 29747 14822 29747 14819 29747 14819 29748 14822 29748 14823 29748 14819 29749 14823 29749 14811 29749 5770 29750 5768 29750 14824 29750 14824 29751 5768 29751 14819 29751 14824 29752 14819 29752 14825 29752 14825 29753 14819 29753 14811 29753 5579 29754 9730 29754 14826 29754 14826 29755 9730 29755 14827 29755 14826 29756 14827 29756 14830 29756 14830 29757 14827 29757 14828 29757 14830 29758 14828 29758 14821 29758 5579 29759 14826 29759 14829 29759 14829 29760 14826 29760 14830 29760 14829 29761 14830 29761 5576 29761 5576 29762 14830 29762 14821 29762 5576 29763 14821 29763 14820 29763 14831 29764 14850 29764 14832 29764 14833 29765 14834 29765 14841 29765 14841 29766 14834 29766 14842 29766 14835 29767 14854 29767 14844 29767 14844 29768 14854 29768 14852 29768 14840 29769 14838 29769 5182 29769 9724 29770 14837 29770 14836 29770 14836 29771 14837 29771 14838 29771 14836 29772 14838 29772 14832 29772 14832 29773 14838 29773 14840 29773 14832 29774 14840 29774 14831 29774 14831 29775 14840 29775 14839 29775 5182 29776 14833 29776 14840 29776 14840 29777 14833 29777 14841 29777 14840 29778 14841 29778 14839 29778 14839 29779 14841 29779 14842 29779 14839 29780 14842 29780 14852 29780 14852 29781 14842 29781 14843 29781 14852 29782 14843 29782 14844 29782 9440 29783 9725 29783 14845 29783 14845 29784 9725 29784 14847 29784 14845 29785 14847 29785 14846 29785 14846 29786 14847 29786 14851 29786 14846 29787 14851 29787 14849 29787 14849 29788 14851 29788 14848 29788 14849 29789 14848 29789 14855 29789 14855 29790 14848 29790 14853 29790 14855 29791 14853 29791 9434 29791 9725 29792 14850 29792 14847 29792 14847 29793 14850 29793 14831 29793 14847 29794 14831 29794 14851 29794 14851 29795 14831 29795 14839 29795 14851 29796 14839 29796 14848 29796 14848 29797 14839 29797 14852 29797 14848 29798 14852 29798 14853 29798 14853 29799 14852 29799 14854 29799 14849 29800 14855 29800 14858 29800 14855 29801 9434 29801 14856 29801 14846 29802 14861 29802 14845 29802 14845 29803 14861 29803 14857 29803 14845 29804 14857 29804 9440 29804 14855 29805 14856 29805 14858 29805 14858 29806 14856 29806 14859 29806 14858 29807 14859 29807 14879 29807 14879 29808 14878 29808 14858 29808 14858 29809 14878 29809 14861 29809 14858 29810 14861 29810 14849 29810 14849 29811 14861 29811 14846 29811 14872 29812 14857 29812 14860 29812 14860 29813 14857 29813 14861 29813 14860 29814 14861 29814 14877 29814 14877 29815 14861 29815 14878 29815 9723 29816 9721 29816 14865 29816 14862 29817 14868 29817 5177 29817 14868 29818 14862 29818 14865 29818 9431 29819 14863 29819 14864 29819 14864 29820 14863 29820 14869 29820 14862 29821 5179 29821 14865 29821 14865 29822 5179 29822 14866 29822 14865 29823 14866 29823 9723 29823 9723 29824 14866 29824 5178 29824 9723 29825 5178 29825 5176 29825 9721 29826 9720 29826 14865 29826 14865 29827 9720 29827 14874 29827 14865 29828 14874 29828 14868 29828 14868 29829 14874 29829 14867 29829 14868 29830 14867 29830 5177 29830 5177 29831 14867 29831 14869 29831 5177 29832 14869 29832 14870 29832 14870 29833 14869 29833 14863 29833 14871 29834 14872 29834 14873 29834 14873 29835 14872 29835 14860 29835 14873 29836 14860 29836 14875 29836 14875 29837 14860 29837 14877 29837 9720 29838 14871 29838 14874 29838 14874 29839 14871 29839 14873 29839 14874 29840 14873 29840 14867 29840 14867 29841 14873 29841 14875 29841 14867 29842 14875 29842 14869 29842 14869 29843 14875 29843 14876 29843 14869 29844 14876 29844 14864 29844 14864 29845 14876 29845 9432 29845 14877 29846 14878 29846 14875 29846 14875 29847 14878 29847 14879 29847 14875 29848 14879 29848 14876 29848 14876 29849 14879 29849 14859 29849 14876 29850 14859 29850 9432 29850 14880 29851 14881 29851 14885 29851 14885 29852 14881 29852 14882 29852 14885 29853 14882 29853 14883 29853 14883 29854 14882 29854 14884 29854 14883 29855 14884 29855 14887 29855 14887 29856 14884 29856 14889 29856 14887 29857 14889 29857 14891 29857 14880 29858 14885 29858 9716 29858 9716 29859 14885 29859 14883 29859 9716 29860 14883 29860 9717 29860 9717 29861 14883 29861 14887 29861 9717 29862 14887 29862 14886 29862 14886 29863 14887 29863 14891 29863 14886 29864 14891 29864 14888 29864 14891 29865 14889 29865 5746 29865 9715 29866 14888 29866 14894 29866 14894 29867 14888 29867 14891 29867 14894 29868 14891 29868 14890 29868 14890 29869 14891 29869 5746 29869 14892 29870 9715 29870 14893 29870 14893 29871 9715 29871 14894 29871 14893 29872 14894 29872 14897 29872 14897 29873 14894 29873 14890 29873 14897 29874 14890 29874 14895 29874 14895 29875 14890 29875 5746 29875 14897 29876 14895 29876 14896 29876 14893 29877 14897 29877 14903 29877 14892 29878 14893 29878 14907 29878 14897 29879 14896 29879 14903 29879 14903 29880 14896 29880 5744 29880 14903 29881 5744 29881 14904 29881 5744 29882 5743 29882 14904 29882 14904 29883 5743 29883 14899 29883 14904 29884 14899 29884 14898 29884 14898 29885 14899 29885 14900 29885 14898 29886 14900 29886 14901 29886 14901 29887 14900 29887 5741 29887 14901 29888 5741 29888 14906 29888 14906 29889 5741 29889 14902 29889 14906 29890 14902 29890 14917 29890 14893 29891 14903 29891 14907 29891 14907 29892 14903 29892 14904 29892 14907 29893 14904 29893 14908 29893 14908 29894 14904 29894 14898 29894 14908 29895 14898 29895 14905 29895 14905 29896 14898 29896 14901 29896 14905 29897 14901 29897 14910 29897 14910 29898 14901 29898 14906 29898 14910 29899 14906 29899 14913 29899 14913 29900 14906 29900 14917 29900 14913 29901 14917 29901 14914 29901 14892 29902 14907 29902 9443 29902 9443 29903 14907 29903 14908 29903 9443 29904 14908 29904 9444 29904 9444 29905 14908 29905 14905 29905 9444 29906 14905 29906 14909 29906 14909 29907 14905 29907 14910 29907 14909 29908 14910 29908 14911 29908 14911 29909 14910 29909 14913 29909 14911 29910 14913 29910 14912 29910 14912 29911 14913 29911 14914 29911 14912 29912 14914 29912 9441 29912 14920 29913 9441 29913 14926 29913 14926 29914 9441 29914 14914 29914 14926 29915 14914 29915 14915 29915 14915 29916 14914 29916 14917 29916 14915 29917 14917 29917 14916 29917 14916 29918 14917 29918 14902 29918 14929 29919 14918 29919 9712 29919 14929 29920 9712 29920 14921 29920 14921 29921 9712 29921 14919 29921 14921 29922 14919 29922 14924 29922 14924 29923 14919 29923 14920 29923 14924 29924 14920 29924 14926 29924 5564 29925 14929 29925 14922 29925 14922 29926 14929 29926 14921 29926 14922 29927 14921 29927 14923 29927 14923 29928 14921 29928 14924 29928 14923 29929 14924 29929 14925 29929 14925 29930 14924 29930 14926 29930 14925 29931 14926 29931 14915 29931 5564 29932 14922 29932 14927 29932 14927 29933 14922 29933 14923 29933 14927 29934 14923 29934 14928 29934 14928 29935 14923 29935 14925 29935 14928 29936 14925 29936 5566 29936 5566 29937 14925 29937 14915 29937 5566 29938 14915 29938 14916 29938 14918 29939 14929 29939 5564 29939 14935 29940 14940 29940 14930 29940 14936 29941 14931 29941 14932 29941 14932 29942 14931 29942 14933 29942 14932 29943 14933 29943 14938 29943 14938 29944 14933 29944 14934 29944 14938 29945 14934 29945 14930 29945 14930 29946 14934 29946 5716 29946 14930 29947 5716 29947 14935 29947 14936 29948 14932 29948 14937 29948 14937 29949 14932 29949 14938 29949 14937 29950 14938 29950 9710 29950 9710 29951 14938 29951 14930 29951 9710 29952 14930 29952 14939 29952 14939 29953 14930 29953 14940 29953 14939 29954 14940 29954 14942 29954 14945 29955 14942 29955 14941 29955 14941 29956 14942 29956 14940 29956 14941 29957 14940 29957 14943 29957 14943 29958 14940 29958 14935 29958 14943 29959 14935 29959 14947 29959 14947 29960 14935 29960 5716 29960 14944 29961 14945 29961 14948 29961 14948 29962 14945 29962 14941 29962 14948 29963 14941 29963 14949 29963 14949 29964 14941 29964 14943 29964 14949 29965 14943 29965 14946 29965 14946 29966 14943 29966 14947 29966 14949 29967 14946 29967 14950 29967 14948 29968 14949 29968 14951 29968 14944 29969 14948 29969 14959 29969 14949 29970 14950 29970 14951 29970 14951 29971 14950 29971 5723 29971 14951 29972 5723 29972 14957 29972 14957 29973 5723 29973 5721 29973 14957 29974 5721 29974 14952 29974 14952 29975 5721 29975 5717 29975 14952 29976 5717 29976 14953 29976 14953 29977 5717 29977 14954 29977 14953 29978 14954 29978 14955 29978 14955 29979 14954 29979 14956 29979 14955 29980 14956 29980 14973 29980 14948 29981 14951 29981 14959 29981 14959 29982 14951 29982 14957 29982 14959 29983 14957 29983 14958 29983 14958 29984 14957 29984 14952 29984 14958 29985 14952 29985 14961 29985 14961 29986 14952 29986 14953 29986 14961 29987 14953 29987 14963 29987 14963 29988 14953 29988 14955 29988 14963 29989 14955 29989 14965 29989 14965 29990 14955 29990 14973 29990 14965 29991 14973 29991 14966 29991 14944 29992 14959 29992 14960 29992 14960 29993 14959 29993 14958 29993 14960 29994 14958 29994 14962 29994 14962 29995 14958 29995 14961 29995 14962 29996 14961 29996 9448 29996 9448 29997 14961 29997 14963 29997 9448 29998 14963 29998 14964 29998 14964 29999 14963 29999 14965 29999 14964 30000 14965 30000 9446 30000 9446 30001 14965 30001 14966 30001 9446 30002 14966 30002 9703 30002 14971 30003 5719 30003 14983 30003 9706 30004 14967 30004 14969 30004 14969 30005 14967 30005 14968 30005 14969 30006 14968 30006 14977 30006 14977 30007 14968 30007 14971 30007 14977 30008 14971 30008 14978 30008 14978 30009 14971 30009 14983 30009 5720 30010 5719 30010 14970 30010 14970 30011 5719 30011 14971 30011 14970 30012 14971 30012 14972 30012 14972 30013 14971 30013 14968 30013 14972 30014 14968 30014 9705 30014 9705 30015 14968 30015 14967 30015 14956 30016 5720 30016 14973 30016 14973 30017 5720 30017 14970 30017 14973 30018 14970 30018 14966 30018 14966 30019 14970 30019 14972 30019 14966 30020 14972 30020 9703 30020 9703 30021 14972 30021 9705 30021 9701 30022 14974 30022 14975 30022 14975 30023 14974 30023 14976 30023 14975 30024 14976 30024 14980 30024 14980 30025 14976 30025 9707 30025 14980 30026 9707 30026 14981 30026 9707 30027 9706 30027 14969 30027 9707 30028 14969 30028 14981 30028 14981 30029 14969 30029 14977 30029 14981 30030 14977 30030 14978 30030 9701 30031 14975 30031 14979 30031 14979 30032 14975 30032 14980 30032 14979 30033 14980 30033 14982 30033 14982 30034 14980 30034 14981 30034 14982 30035 14981 30035 5595 30035 5595 30036 14981 30036 14978 30036 5595 30037 14978 30037 14983 30037 14997 30038 9697 30038 14984 30038 5205 30039 14994 30039 14985 30039 14985 30040 14994 30040 14993 30040 5210 30041 14987 30041 14986 30041 14986 30042 14987 30042 5209 30042 14986 30043 5209 30043 14998 30043 5532 30044 14988 30044 14999 30044 14999 30045 14988 30045 14992 30045 14999 30046 14992 30046 14989 30046 14989 30047 14992 30047 14990 30047 14989 30048 14990 30048 9453 30048 9453 30049 14990 30049 14991 30049 14988 30050 9697 30050 14992 30050 14992 30051 9697 30051 14997 30051 14992 30052 14997 30052 14990 30052 14990 30053 14997 30053 14993 30053 14990 30054 14993 30054 14991 30054 14991 30055 14993 30055 14994 30055 9700 30056 14996 30056 14995 30056 14995 30057 14996 30057 5210 30057 14995 30058 5210 30058 14984 30058 14984 30059 5210 30059 14986 30059 14984 30060 14986 30060 14997 30060 14997 30061 14986 30061 14998 30061 14997 30062 14998 30062 14993 30062 14993 30063 14998 30063 5207 30063 14993 30064 5207 30064 14985 30064 15000 30065 5532 30065 15001 30065 15001 30066 5532 30066 14999 30066 15001 30067 14999 30067 15004 30067 15004 30068 14999 30068 14989 30068 15004 30069 14989 30069 9459 30069 9459 30070 14989 30070 9453 30070 9494 30071 15000 30071 15005 30071 15005 30072 15000 30072 15001 30072 15005 30073 15001 30073 15002 30073 15002 30074 15001 30074 15004 30074 15002 30075 15004 30075 15003 30075 15003 30076 15004 30076 9459 30076 15003 30077 9458 30077 15022 30077 15003 30078 15022 30078 15002 30078 15002 30079 15022 30079 15021 30079 15002 30080 15021 30080 15005 30080 15005 30081 15021 30081 15006 30081 15005 30082 15006 30082 9494 30082 5202 30083 5201 30083 15007 30083 5202 30084 15007 30084 15010 30084 15010 30085 15007 30085 15012 30085 15010 30086 15012 30086 15013 30086 5198 30087 15008 30087 15013 30087 15013 30088 15008 30088 15009 30088 15013 30089 15009 30089 15010 30089 9449 30090 15016 30090 15011 30090 15011 30091 15016 30091 15014 30091 15012 30092 15017 30092 15013 30092 15013 30093 15017 30093 15019 30093 15013 30094 15019 30094 5198 30094 5198 30095 15019 30095 15014 30095 5198 30096 15014 30096 15015 30096 15015 30097 15014 30097 15016 30097 15017 30098 9694 30098 15019 30098 15019 30099 9694 30099 15018 30099 15019 30100 15018 30100 15014 30100 15014 30101 15018 30101 15020 30101 15014 30102 15020 30102 15011 30102 15011 30103 15020 30103 9456 30103 9694 30104 15006 30104 15018 30104 15018 30105 15006 30105 15021 30105 15018 30106 15021 30106 15020 30106 15020 30107 15021 30107 15022 30107 15020 30108 15022 30108 9456 30108 9456 30109 15022 30109 9458 30109 5132 30110 5133 30110 15026 30110 15030 30111 15024 30111 15029 30111 5129 30112 15023 30112 15030 30112 15030 30113 15023 30113 5130 30113 15030 30114 5130 30114 15024 30114 5129 30115 15030 30115 15025 30115 15025 30116 15030 30116 15038 30116 15025 30117 15038 30117 9334 30117 5132 30118 15026 30118 15031 30118 15028 30119 5134 30119 15033 30119 15033 30120 5134 30120 15027 30120 15033 30121 15027 30121 15032 30121 15028 30122 15033 30122 15029 30122 15029 30123 15033 30123 15036 30123 15029 30124 15036 30124 15030 30124 15030 30125 15036 30125 15040 30125 15030 30126 15040 30126 15038 30126 15031 30127 15026 30127 15032 30127 15032 30128 15026 30128 15034 30128 15032 30129 15034 30129 15033 30129 15033 30130 15034 30130 15035 30130 15033 30131 15035 30131 15036 30131 15036 30132 15035 30132 5148 30132 15036 30133 5148 30133 15040 30133 9335 30134 15037 30134 5117 30134 5117 30135 15037 30135 15044 30135 5117 30136 15044 30136 5116 30136 9335 30137 9334 30137 15037 30137 15037 30138 9334 30138 15038 30138 15037 30139 15038 30139 15039 30139 15039 30140 15038 30140 15040 30140 5146 30141 15039 30141 5147 30141 5147 30142 15039 30142 15040 30142 5147 30143 15040 30143 5148 30143 5146 30144 15054 30144 15039 30144 15039 30145 15054 30145 15042 30145 15039 30146 15042 30146 15037 30146 15037 30147 15042 30147 15041 30147 15037 30148 15041 30148 15044 30148 5121 30149 15045 30149 5122 30149 15054 30150 15046 30150 15042 30150 15042 30151 15046 30151 15048 30151 15042 30152 15048 30152 15041 30152 15041 30153 15048 30153 15043 30153 15041 30154 15043 30154 15044 30154 15044 30155 15043 30155 5114 30155 15044 30156 5114 30156 5116 30156 15045 30157 5121 30157 15046 30157 15046 30158 5121 30158 15047 30158 15046 30159 15047 30159 15048 30159 15049 30160 15050 30160 9869 30160 9869 30161 15050 30161 5125 30161 9869 30162 5125 30162 15051 30162 15051 30163 5125 30163 5122 30163 15051 30164 5122 30164 9868 30164 9868 30165 5122 30165 15045 30165 9868 30166 15045 30166 15052 30166 15052 30167 15045 30167 15046 30167 15052 30168 15046 30168 15053 30168 15053 30169 15046 30169 15054 30169 15053 30170 15054 30170 5146 30170 15061 30171 15066 30171 15069 30171 7442 30172 15055 30172 15056 30172 5966 30173 5965 30173 15063 30173 7442 30174 15056 30174 7443 30174 7443 30175 15056 30175 15067 30175 7443 30176 15067 30176 15066 30176 5965 30177 15057 30177 15063 30177 15063 30178 15057 30178 15058 30178 15063 30179 15058 30179 7439 30179 5966 30180 15063 30180 15059 30180 15059 30181 15063 30181 15065 30181 15059 30182 15065 30182 15060 30182 15060 30183 15065 30183 15070 30183 15060 30184 15070 30184 9403 30184 15061 30185 15069 30185 7439 30185 7439 30186 15069 30186 15062 30186 7439 30187 15062 30187 15063 30187 15063 30188 15062 30188 15064 30188 15063 30189 15064 30189 15065 30189 15065 30190 15064 30190 15071 30190 15065 30191 15071 30191 15070 30191 15066 30192 15067 30192 15069 30192 15069 30193 15067 30193 15068 30193 15069 30194 15068 30194 15062 30194 15062 30195 15068 30195 9866 30195 15062 30196 9866 30196 15064 30196 15064 30197 9866 30197 9406 30197 15064 30198 9406 30198 15071 30198 15074 30199 9403 30199 15075 30199 15075 30200 9403 30200 15070 30200 15075 30201 15070 30201 15078 30201 15078 30202 15070 30202 15071 30202 15078 30203 15071 30203 15072 30203 15072 30204 15071 30204 9406 30204 15087 30205 15074 30205 15073 30205 15073 30206 15074 30206 15075 30206 15073 30207 15075 30207 15076 30207 15076 30208 15075 30208 15078 30208 15076 30209 15078 30209 15077 30209 15077 30210 15078 30210 15072 30210 5972 30211 9401 30211 5881 30211 5881 30212 9401 30212 15079 30212 5881 30213 15079 30213 5882 30213 15086 30214 5883 30214 15079 30214 15079 30215 5883 30215 15080 30215 15079 30216 15080 30216 5882 30216 15085 30217 15082 30217 15081 30217 15081 30218 15082 30218 15083 30218 15081 30219 15084 30219 15085 30219 15085 30220 15084 30220 9848 30220 15085 30221 9848 30221 5885 30221 5885 30222 9848 30222 5884 30222 15083 30223 5883 30223 15081 30223 15081 30224 5883 30224 15086 30224 15081 30225 15086 30225 15084 30225 15084 30226 15086 30226 15088 30226 9401 30227 15087 30227 15079 30227 15079 30228 15087 30228 15073 30228 15079 30229 15073 30229 15086 30229 15086 30230 15073 30230 15076 30230 15086 30231 15076 30231 15088 30231 15088 30232 15076 30232 15077 30232 5102 30233 5101 30233 15089 30233 15089 30234 5101 30234 5100 30234 15089 30235 5100 30235 15091 30235 15091 30236 5100 30236 15090 30236 15091 30237 15090 30237 9842 30237 15094 30238 5096 30238 15096 30238 9410 30239 5098 30239 15095 30239 15092 30240 9408 30240 15093 30240 15093 30241 9408 30241 9410 30241 15093 30242 9410 30242 15094 30242 15094 30243 9410 30243 15095 30243 15094 30244 15095 30244 5096 30244 15103 30245 15111 30245 15097 30245 15097 30246 15111 30246 15108 30246 5102 30247 15098 30247 15096 30247 15096 30248 15098 30248 15099 30248 15096 30249 15099 30249 15094 30249 15094 30250 15099 30250 15097 30250 15094 30251 15097 30251 15093 30251 15093 30252 15097 30252 15108 30252 15093 30253 15108 30253 15092 30253 5102 30254 15089 30254 15098 30254 15098 30255 15089 30255 15100 30255 15098 30256 15100 30256 15099 30256 15099 30257 15100 30257 15101 30257 15099 30258 15101 30258 15097 30258 15097 30259 15101 30259 15102 30259 15097 30260 15102 30260 15103 30260 15091 30261 9841 30261 15089 30261 15089 30262 9841 30262 15104 30262 15089 30263 15104 30263 15100 30263 15100 30264 15104 30264 15105 30264 15100 30265 15105 30265 15101 30265 15101 30266 15105 30266 9840 30266 15101 30267 9840 30267 15102 30267 15102 30268 9840 30268 15109 30268 15111 30269 15103 30269 15106 30269 15106 30270 15103 30270 15102 30270 15107 30271 15092 30271 15112 30271 15112 30272 15092 30272 15108 30272 15102 30273 15109 30273 15106 30273 15106 30274 15109 30274 5112 30274 15106 30275 5112 30275 15122 30275 15122 30276 15110 30276 15106 30276 15106 30277 15110 30277 15112 30277 15106 30278 15112 30278 15111 30278 15111 30279 15112 30279 15108 30279 9414 30280 15107 30280 15113 30280 15113 30281 15107 30281 15112 30281 15113 30282 15112 30282 15124 30282 15124 30283 15112 30283 15110 30283 5091 30284 15125 30284 15114 30284 15114 30285 15125 30285 15117 30285 15121 30286 15115 30286 15117 30286 15117 30287 15115 30287 15116 30287 15117 30288 15116 30288 15114 30288 5092 30289 15120 30289 15118 30289 15118 30290 15120 30290 15119 30290 15118 30291 15119 30291 5093 30291 5093 30292 15119 30292 5094 30292 15119 30293 9836 30293 5094 30293 5094 30294 9836 30294 9838 30294 5094 30295 9838 30295 5095 30295 5095 30296 9838 30296 5089 30296 5092 30297 15115 30297 15120 30297 15120 30298 15115 30298 15121 30298 15120 30299 15121 30299 15119 30299 15119 30300 15121 30300 15123 30300 15119 30301 15123 30301 9836 30301 9836 30302 15123 30302 9834 30302 5112 30303 9834 30303 15122 30303 15122 30304 9834 30304 15123 30304 15122 30305 15123 30305 15110 30305 15110 30306 15123 30306 15121 30306 15110 30307 15121 30307 15124 30307 15124 30308 15121 30308 15117 30308 15124 30309 15117 30309 15113 30309 15113 30310 15117 30310 15125 30310 15113 30311 15125 30311 9414 30311 15126 30312 15127 30312 15142 30312 15142 30313 15127 30313 15128 30313 15142 30314 15128 30314 15129 30314 15129 30315 15128 30315 5920 30315 15129 30316 5920 30316 9826 30316 15131 30317 15132 30317 15134 30317 9336 30318 15130 30318 5916 30318 15144 30319 9340 30319 15137 30319 15137 30320 9340 30320 9336 30320 15137 30321 9336 30321 15131 30321 15131 30322 9336 30322 5916 30322 15131 30323 5916 30323 15132 30323 15150 30324 15147 30324 15136 30324 15136 30325 15147 30325 15148 30325 15126 30326 15133 30326 15134 30326 15134 30327 15133 30327 15135 30327 15134 30328 15135 30328 15131 30328 15131 30329 15135 30329 15136 30329 15131 30330 15136 30330 15137 30330 15137 30331 15136 30331 15148 30331 15137 30332 15148 30332 15144 30332 15126 30333 15142 30333 15133 30333 15133 30334 15142 30334 15138 30334 15133 30335 15138 30335 15135 30335 15135 30336 15138 30336 15143 30336 15135 30337 15143 30337 15136 30337 15136 30338 15143 30338 15139 30338 15136 30339 15139 30339 15150 30339 15129 30340 15140 30340 15142 30340 15142 30341 15140 30341 15141 30341 15142 30342 15141 30342 15138 30342 15138 30343 15141 30343 9830 30343 15138 30344 9830 30344 15143 30344 15143 30345 9830 30345 9831 30345 15143 30346 9831 30346 15139 30346 15149 30347 9343 30347 15144 30347 15139 30348 9831 30348 15145 30348 15150 30349 15146 30349 15147 30349 15147 30350 15146 30350 15149 30350 15147 30351 15149 30351 15148 30351 15148 30352 15149 30352 15144 30352 9820 30353 15161 30353 15145 30353 15145 30354 15161 30354 15146 30354 15145 30355 15146 30355 15139 30355 15139 30356 15146 30356 15150 30356 15151 30357 9343 30357 15152 30357 15152 30358 9343 30358 15149 30358 15152 30359 15149 30359 15163 30359 15163 30360 15149 30360 15146 30360 15163 30361 15146 30361 15153 30361 15153 30362 15146 30362 15161 30362 5910 30363 15164 30363 15158 30363 5905 30364 15154 30364 5907 30364 5907 30365 15154 30365 15164 30365 5907 30366 15164 30366 5909 30366 5909 30367 15164 30367 5910 30367 15155 30368 15156 30368 5911 30368 5911 30369 15156 30369 15159 30369 5912 30370 15157 30370 5915 30370 5915 30371 15157 30371 9823 30371 5915 30372 9823 30372 5914 30372 5912 30373 5911 30373 15157 30373 15157 30374 5911 30374 15159 30374 15157 30375 15159 30375 9823 30375 9823 30376 15159 30376 15160 30376 15155 30377 5910 30377 15156 30377 15156 30378 5910 30378 15158 30378 15156 30379 15158 30379 15159 30379 15159 30380 15158 30380 15162 30380 15159 30381 15162 30381 15160 30381 15160 30382 15162 30382 9821 30382 9820 30383 9821 30383 15161 30383 15161 30384 9821 30384 15162 30384 15161 30385 15162 30385 15153 30385 15153 30386 15162 30386 15158 30386 15153 30387 15158 30387 15163 30387 15163 30388 15158 30388 15164 30388 15163 30389 15164 30389 15152 30389 15152 30390 15164 30390 15154 30390 15152 30391 15154 30391 15151 30391 15178 30392 7387 30392 15167 30392 15165 30393 15168 30393 15169 30393 9818 30394 9817 30394 15166 30394 15166 30395 9817 30395 15165 30395 15166 30396 15165 30396 15167 30396 15167 30397 15165 30397 15169 30397 15167 30398 15169 30398 15178 30398 15184 30399 15183 30399 15181 30399 15169 30400 15168 30400 9816 30400 15169 30401 9816 30401 15170 30401 15170 30402 9816 30402 9819 30402 15170 30403 9819 30403 15176 30403 15176 30404 9819 30404 15171 30404 15176 30405 15171 30405 15174 30405 15174 30406 15171 30406 15172 30406 15174 30407 15172 30407 15173 30407 15173 30408 15172 30408 9347 30408 15173 30409 9347 30409 15187 30409 15187 30410 15179 30410 15173 30410 15173 30411 15179 30411 15180 30411 15173 30412 15180 30412 15174 30412 15174 30413 15180 30413 15175 30413 15174 30414 15175 30414 15176 30414 15176 30415 15175 30415 15177 30415 15176 30416 15177 30416 15170 30416 15170 30417 15177 30417 15178 30417 15170 30418 15178 30418 15169 30418 15187 30419 15184 30419 15179 30419 15179 30420 15184 30420 15181 30420 15179 30421 15181 30421 15180 30421 15180 30422 15181 30422 15182 30422 15180 30423 15182 30423 15175 30423 15175 30424 15182 30424 6061 30424 15175 30425 6061 30425 15177 30425 15177 30426 6061 30426 7387 30426 15177 30427 7387 30427 15178 30427 6063 30428 15183 30428 15185 30428 15185 30429 15183 30429 15184 30429 15185 30430 15184 30430 15186 30430 15186 30431 15184 30431 15187 30431 15191 30432 6063 30432 15188 30432 15188 30433 6063 30433 15185 30433 15188 30434 15185 30434 15192 30434 15192 30435 15185 30435 15186 30435 15194 30436 15192 30436 15189 30436 15189 30437 15192 30437 15186 30437 15189 30438 15186 30438 9348 30438 9348 30439 15186 30439 15187 30439 9348 30440 15187 30440 9347 30440 15190 30441 15191 30441 15199 30441 15199 30442 15191 30442 15188 30442 15199 30443 15188 30443 15198 30443 15198 30444 15188 30444 15192 30444 15198 30445 15192 30445 15193 30445 15193 30446 15192 30446 15194 30446 15206 30447 15202 30447 15196 30447 15197 30448 9814 30448 15195 30448 15195 30449 9814 30449 15206 30449 15206 30450 15196 30450 15195 30450 15195 30451 15196 30451 15190 30451 15195 30452 15190 30452 15199 30452 15194 30453 15197 30453 15193 30453 15193 30454 15197 30454 15195 30454 15193 30455 15195 30455 15198 30455 15198 30456 15195 30456 15199 30456 15200 30457 15201 30457 15204 30457 15204 30458 15201 30458 5824 30458 15204 30459 5824 30459 15205 30459 15205 30460 5824 30460 15202 30460 15205 30461 15202 30461 15206 30461 15200 30462 15204 30462 15203 30462 15203 30463 15204 30463 15205 30463 15203 30464 15205 30464 9813 30464 9813 30465 15205 30465 15206 30465 9813 30466 15206 30466 9814 30466 5843 30467 15210 30467 15209 30467 15207 30468 9805 30468 15217 30468 15211 30469 15208 30469 15218 30469 15209 30470 15210 30470 15211 30470 15211 30471 15210 30471 15212 30471 15211 30472 15212 30472 15208 30472 15213 30473 5844 30473 5843 30473 5843 30474 15209 30474 15213 30474 15213 30475 15209 30475 15215 30475 15213 30476 15215 30476 9349 30476 9349 30477 15215 30477 15214 30477 9349 30478 15214 30478 15223 30478 15211 30479 15221 30479 15209 30479 15209 30480 15221 30480 15216 30480 15209 30481 15216 30481 15215 30481 15215 30482 15216 30482 15224 30482 15215 30483 15224 30483 15214 30483 15207 30484 15217 30484 15218 30484 15218 30485 15217 30485 15219 30485 15218 30486 15219 30486 15211 30486 15211 30487 15219 30487 15220 30487 15211 30488 15220 30488 15221 30488 15221 30489 15220 30489 9809 30489 15221 30490 9809 30490 15216 30490 15216 30491 9809 30491 9359 30491 15216 30492 9359 30492 15224 30492 15224 30493 9359 30493 9357 30493 9354 30494 15223 30494 15222 30494 15222 30495 15223 30495 15214 30495 15222 30496 15214 30496 15228 30496 9356 30497 15240 30497 9357 30497 9357 30498 15240 30498 15228 30498 9357 30499 15228 30499 15224 30499 15224 30500 15228 30500 15214 30500 15225 30501 9354 30501 15245 30501 15245 30502 9354 30502 15222 30502 15245 30503 15222 30503 15226 30503 15226 30504 15222 30504 15228 30504 15226 30505 15228 30505 15227 30505 15227 30506 15228 30506 15240 30506 5836 30507 9350 30507 15229 30507 15229 30508 9350 30508 15238 30508 15235 30509 5839 30509 15238 30509 15238 30510 5839 30510 5838 30510 15238 30511 5838 30511 15229 30511 5840 30512 15236 30512 5841 30512 5841 30513 15236 30513 15232 30513 5841 30514 15232 30514 15230 30514 15230 30515 15232 30515 15231 30515 15232 30516 15233 30516 15231 30516 15231 30517 15233 30517 9802 30517 15231 30518 9802 30518 15234 30518 15234 30519 9802 30519 9804 30519 5840 30520 5839 30520 15236 30520 15236 30521 5839 30521 15235 30521 15236 30522 15235 30522 15232 30522 15232 30523 15235 30523 15237 30523 15232 30524 15237 30524 15233 30524 15233 30525 15237 30525 15239 30525 9350 30526 9352 30526 15238 30526 15238 30527 9352 30527 15244 30527 15238 30528 15244 30528 15235 30528 15235 30529 15244 30529 15243 30529 15235 30530 15243 30530 15237 30530 15237 30531 15243 30531 15242 30531 15237 30532 15242 30532 15239 30532 15239 30533 15242 30533 15241 30533 9356 30534 15241 30534 15240 30534 15240 30535 15241 30535 15242 30535 15240 30536 15242 30536 15227 30536 15227 30537 15242 30537 15243 30537 15227 30538 15243 30538 15226 30538 15226 30539 15243 30539 15244 30539 15226 30540 15244 30540 15245 30540 15245 30541 15244 30541 9352 30541 15245 30542 9352 30542 15225 30542 5791 30543 9795 30543 15246 30543 15246 30544 9795 30544 9799 30544 15246 30545 9799 30545 15249 30545 15249 30546 9799 30546 9797 30546 15249 30547 9797 30547 15247 30547 15247 30548 9797 30548 15253 30548 15247 30549 15253 30549 15252 30549 5791 30550 15246 30550 15248 30550 15248 30551 15246 30551 15249 30551 15248 30552 15249 30552 15250 30552 15250 30553 15249 30553 15247 30553 15250 30554 15247 30554 15251 30554 15251 30555 15247 30555 15252 30555 15251 30556 15252 30556 5790 30556 15252 30557 15253 30557 9796 30557 6041 30558 5790 30558 15256 30558 15256 30559 5790 30559 15252 30559 15256 30560 15252 30560 15254 30560 15254 30561 15252 30561 9796 30561 15257 30562 6041 30562 15255 30562 15255 30563 6041 30563 15256 30563 15255 30564 15256 30564 15259 30564 15259 30565 15256 30565 15254 30565 15259 30566 15254 30566 9362 30566 9362 30567 15254 30567 9796 30567 15272 30568 15271 30568 15264 30568 6044 30569 6042 30569 15260 30569 6042 30570 15257 30570 15260 30570 15260 30571 15257 30571 15255 30571 15260 30572 15255 30572 15258 30572 15258 30573 15255 30573 15259 30573 15258 30574 15259 30574 9360 30574 9360 30575 15259 30575 9362 30575 9360 30576 15268 30576 15258 30576 15258 30577 15268 30577 15270 30577 15258 30578 15270 30578 15260 30578 15260 30579 15270 30579 15261 30579 15260 30580 15261 30580 6044 30580 15273 30581 6045 30581 15261 30581 15261 30582 6045 30582 15262 30582 15261 30583 15262 30583 6044 30583 15271 30584 15269 30584 15263 30584 15271 30585 15263 30585 15264 30585 15264 30586 15263 30586 9363 30586 15264 30587 9363 30587 15266 30587 15266 30588 9363 30588 15279 30588 15266 30589 15279 30589 15267 30589 15272 30590 15264 30590 15265 30590 15265 30591 15264 30591 15266 30591 15265 30592 15266 30592 15275 30592 15275 30593 15266 30593 15267 30593 15275 30594 15267 30594 15276 30594 15268 30595 15269 30595 15270 30595 15270 30596 15269 30596 15271 30596 15270 30597 15271 30597 15261 30597 15261 30598 15271 30598 15272 30598 15261 30599 15272 30599 15273 30599 15273 30600 15272 30600 15265 30600 15273 30601 15265 30601 15274 30601 15274 30602 15265 30602 15275 30602 15274 30603 15275 30603 6048 30603 6048 30604 15275 30604 15276 30604 6048 30605 15276 30605 15277 30605 15283 30606 15277 30606 15286 30606 15286 30607 15277 30607 15276 30607 15286 30608 15276 30608 15278 30608 15278 30609 15276 30609 15267 30609 15278 30610 15267 30610 9792 30610 9792 30611 15267 30611 15279 30611 15291 30612 15280 30612 5793 30612 15291 30613 5793 30613 15281 30613 15281 30614 5793 30614 5795 30614 15281 30615 5795 30615 15282 30615 15282 30616 5795 30616 15283 30616 15282 30617 15283 30617 15286 30617 15284 30618 15291 30618 15287 30618 15287 30619 15291 30619 15281 30619 15287 30620 15281 30620 15285 30620 15285 30621 15281 30621 15282 30621 15285 30622 15282 30622 15289 30622 15289 30623 15282 30623 15286 30623 15289 30624 15286 30624 15278 30624 15284 30625 15287 30625 15288 30625 15288 30626 15287 30626 15285 30626 15288 30627 15285 30627 9793 30627 9793 30628 15285 30628 15289 30628 9793 30629 15289 30629 15290 30629 15290 30630 15289 30630 15278 30630 15290 30631 15278 30631 9792 30631 15280 30632 15291 30632 15284 30632 5851 30633 9791 30633 15294 30633 15294 30634 9791 30634 9790 30634 15294 30635 9790 30635 15295 30635 15295 30636 9790 30636 15292 30636 15295 30637 15292 30637 15298 30637 15292 30638 9788 30638 15298 30638 15298 30639 9788 30639 15293 30639 15298 30640 15293 30640 15302 30640 5851 30641 15294 30641 15296 30641 15296 30642 15294 30642 15295 30642 15296 30643 15295 30643 15297 30643 15297 30644 15295 30644 15298 30644 15297 30645 15298 30645 15299 30645 15299 30646 15298 30646 15302 30646 15299 30647 15302 30647 15300 30647 6018 30648 15300 30648 15301 30648 15301 30649 15300 30649 15302 30649 15301 30650 15302 30650 15303 30650 15303 30651 15302 30651 15293 30651 15303 30652 15293 30652 15304 30652 15304 30653 15293 30653 9788 30653 6019 30654 6018 30654 15305 30654 15305 30655 6018 30655 15301 30655 15305 30656 15301 30656 15307 30656 15307 30657 15301 30657 15303 30657 15307 30658 15303 30658 15306 30658 15306 30659 15303 30659 15304 30659 15307 30660 15306 30660 9376 30660 15305 30661 15307 30661 15309 30661 6019 30662 15305 30662 15308 30662 15307 30663 9376 30663 15309 30663 15309 30664 9376 30664 15310 30664 15309 30665 15310 30665 15311 30665 15311 30666 15310 30666 9375 30666 15311 30667 9375 30667 15312 30667 15312 30668 9375 30668 15313 30668 15312 30669 15313 30669 15317 30669 15317 30670 15313 30670 15314 30670 15317 30671 15314 30671 15319 30671 15319 30672 15314 30672 15333 30672 15319 30673 15333 30673 15334 30673 15305 30674 15309 30674 15308 30674 15308 30675 15309 30675 15311 30675 15308 30676 15311 30676 15315 30676 15315 30677 15311 30677 15312 30677 15315 30678 15312 30678 15323 30678 15323 30679 15312 30679 15317 30679 15323 30680 15317 30680 15316 30680 15316 30681 15317 30681 15319 30681 15316 30682 15319 30682 15318 30682 15318 30683 15319 30683 15334 30683 15318 30684 15334 30684 15325 30684 6019 30685 15308 30685 15320 30685 15320 30686 15308 30686 15315 30686 15320 30687 15315 30687 15321 30687 15321 30688 15315 30688 15323 30688 15321 30689 15323 30689 15322 30689 15322 30690 15323 30690 15316 30690 15322 30691 15316 30691 6022 30691 6022 30692 15316 30692 15318 30692 6022 30693 15318 30693 15324 30693 15324 30694 15318 30694 15325 30694 15324 30695 15325 30695 6024 30695 15331 30696 15330 30696 15342 30696 5855 30697 15327 30697 15326 30697 15326 30698 15327 30698 15328 30698 15326 30699 15328 30699 15329 30699 15329 30700 15328 30700 15331 30700 15329 30701 15331 30701 15339 30701 15339 30702 15331 30702 15342 30702 9783 30703 15330 30703 15335 30703 15335 30704 15330 30704 15331 30704 15335 30705 15331 30705 15336 30705 15336 30706 15331 30706 15328 30706 15336 30707 15328 30707 15332 30707 15332 30708 15328 30708 15327 30708 15333 30709 9783 30709 15334 30709 15334 30710 9783 30710 15335 30710 15334 30711 15335 30711 15325 30711 15325 30712 15335 30712 15336 30712 15325 30713 15336 30713 6024 30713 6024 30714 15336 30714 15332 30714 5860 30715 15338 30715 15337 30715 15337 30716 15338 30716 5858 30716 15337 30717 5858 30717 15340 30717 15340 30718 5858 30718 5856 30718 15340 30719 5856 30719 15341 30719 5856 30720 5855 30720 15326 30720 5856 30721 15326 30721 15341 30721 15341 30722 15326 30722 15329 30722 15341 30723 15329 30723 15339 30723 5860 30724 15337 30724 9785 30724 9785 30725 15337 30725 15340 30725 9785 30726 15340 30726 9786 30726 9786 30727 15340 30727 15341 30727 9786 30728 15341 30728 9787 30728 9787 30729 15341 30729 15339 30729 9787 30730 15339 30730 15342 30730 15346 30731 15345 30731 15354 30731 15343 30732 5879 30732 9778 30732 15343 30733 9778 30733 15344 30733 15344 30734 9778 30734 15355 30734 15344 30735 15355 30735 15345 30735 5877 30736 5878 30736 15349 30736 15349 30737 5878 30737 15347 30737 9380 30738 5875 30738 5877 30738 5877 30739 15349 30739 9380 30739 9380 30740 15349 30740 15352 30740 9380 30741 15352 30741 9387 30741 9387 30742 15352 30742 15353 30742 9387 30743 15353 30743 15357 30743 15346 30744 15354 30744 15347 30744 15347 30745 15354 30745 15348 30745 15347 30746 15348 30746 15349 30746 15349 30747 15348 30747 15350 30747 15349 30748 15350 30748 15352 30748 15352 30749 15350 30749 15351 30749 15352 30750 15351 30750 15353 30750 15345 30751 15355 30751 15354 30751 15354 30752 15355 30752 15356 30752 15354 30753 15356 30753 15348 30753 15348 30754 15356 30754 9782 30754 15348 30755 9782 30755 15350 30755 15350 30756 9782 30756 15359 30756 15350 30757 15359 30757 15351 30757 9385 30758 15357 30758 15360 30758 15360 30759 15357 30759 15353 30759 15360 30760 15353 30760 15358 30760 15358 30761 15353 30761 15351 30761 5530 30762 15358 30762 5529 30762 5529 30763 15358 30763 15351 30763 5529 30764 15351 30764 15359 30764 9384 30765 9385 30765 15364 30765 15364 30766 9385 30766 15360 30766 15364 30767 15360 30767 15361 30767 15361 30768 15360 30768 15358 30768 15361 30769 15358 30769 15362 30769 15362 30770 15358 30770 5530 30770 5530 30771 9771 30771 15377 30771 5530 30772 15377 30772 15362 30772 15362 30773 15377 30773 15375 30773 15362 30774 15375 30774 15361 30774 15361 30775 15375 30775 15363 30775 15361 30776 15363 30776 15364 30776 15364 30777 15363 30777 9383 30777 15364 30778 9383 30778 9384 30778 5516 30779 9378 30779 5518 30779 5518 30780 9378 30780 15371 30780 15365 30781 5520 30781 15371 30781 15371 30782 5520 30782 5519 30782 15371 30783 5519 30783 5518 30783 15366 30784 15367 30784 5524 30784 5524 30785 15367 30785 15369 30785 5524 30786 15369 30786 5526 30786 5526 30787 15369 30787 5527 30787 15369 30788 9773 30788 5527 30788 5527 30789 9773 30789 9776 30789 5527 30790 9776 30790 5523 30790 5523 30791 9776 30791 5522 30791 15366 30792 5520 30792 15367 30792 15367 30793 5520 30793 15365 30793 15367 30794 15365 30794 15369 30794 15369 30795 15365 30795 15368 30795 15369 30796 15368 30796 9773 30796 9773 30797 15368 30797 15372 30797 9378 30798 15373 30798 15371 30798 15371 30799 15373 30799 15370 30799 15371 30800 15370 30800 15365 30800 15365 30801 15370 30801 15374 30801 15365 30802 15374 30802 15368 30802 15368 30803 15374 30803 15376 30803 15368 30804 15376 30804 15372 30804 15372 30805 15376 30805 9772 30805 15373 30806 9383 30806 15370 30806 15370 30807 9383 30807 15363 30807 15370 30808 15363 30808 15374 30808 15374 30809 15363 30809 15375 30809 15374 30810 15375 30810 15376 30810 15376 30811 15375 30811 15377 30811 15376 30812 15377 30812 9772 30812 9772 30813 15377 30813 9771 30813 15392 30814 9753 30814 15381 30814 15382 30815 15378 30815 15383 30815 15383 30816 15378 30816 5161 30816 5159 30817 15398 30817 5160 30817 5160 30818 15398 30818 15396 30818 15379 30819 15380 30819 5162 30819 5158 30820 5164 30820 9751 30820 9751 30821 5164 30821 15380 30821 9751 30822 15380 30822 15381 30822 15381 30823 15380 30823 15379 30823 15381 30824 15379 30824 15392 30824 15392 30825 15379 30825 15384 30825 5162 30826 15382 30826 15379 30826 15379 30827 15382 30827 15383 30827 15379 30828 15383 30828 15384 30828 15384 30829 15383 30829 5161 30829 15384 30830 5161 30830 15396 30830 15396 30831 5161 30831 15385 30831 15396 30832 15385 30832 5160 30832 15386 30833 15388 30833 15387 30833 15387 30834 15388 30834 15393 30834 15387 30835 15393 30835 15389 30835 15389 30836 15393 30836 15394 30836 15389 30837 15394 30837 4482 30837 4482 30838 15394 30838 15395 30838 4482 30839 15395 30839 15390 30839 15390 30840 15395 30840 15397 30840 15390 30841 15397 30841 15391 30841 15388 30842 9753 30842 15393 30842 15393 30843 9753 30843 15392 30843 15393 30844 15392 30844 15394 30844 15394 30845 15392 30845 15384 30845 15394 30846 15384 30846 15395 30846 15395 30847 15384 30847 15396 30847 15395 30848 15396 30848 15397 30848 15397 30849 15396 30849 15398 30849 15401 30850 15406 30850 5156 30850 15406 30851 15408 30851 5156 30851 5156 30852 15408 30852 15409 30852 5156 30853 15409 30853 15399 30853 15399 30854 15409 30854 5150 30854 5150 30855 15409 30855 9488 30855 5150 30856 9488 30856 15400 30856 15401 30857 15402 30857 15404 30857 15404 30858 15402 30858 5154 30858 15404 30859 5154 30859 9747 30859 9747 30860 5154 30860 5153 30860 9747 30861 5153 30861 5152 30861 9747 30862 15403 30862 15404 30862 15404 30863 15403 30863 15405 30863 15404 30864 15405 30864 15407 30864 15407 30865 15405 30865 5172 30865 15407 30866 5172 30866 4486 30866 15401 30867 15404 30867 15406 30867 15406 30868 15404 30868 15407 30868 15406 30869 15407 30869 15408 30869 15408 30870 15407 30870 4486 30870 15408 30871 4486 30871 4488 30871 4488 30872 4490 30872 15408 30872 15408 30873 4490 30873 15410 30873 15408 30874 15410 30874 15409 30874 15409 30875 15410 30875 4483 30875 15409 30876 4483 30876 9488 30876 15422 30877 15411 30877 15420 30877 15421 30878 15413 30878 15412 30878 15412 30879 15413 30879 15419 30879 15414 30880 15415 30880 15426 30880 15426 30881 15415 30881 15416 30881 15417 30882 15418 30882 9760 30882 9760 30883 15418 30883 15419 30883 9760 30884 15419 30884 15420 30884 15420 30885 15419 30885 15413 30885 15420 30886 15413 30886 15422 30886 15422 30887 15413 30887 15421 30887 15422 30888 15421 30888 15423 30888 15423 30889 15421 30889 15424 30889 15423 30890 15424 30890 15416 30890 15416 30891 15424 30891 15425 30891 15416 30892 15425 30892 15426 30892 9763 30893 15432 30893 15437 30893 15437 30894 15432 30894 15427 30894 15437 30895 15427 30895 15428 30895 15428 30896 15427 30896 15429 30896 15428 30897 15429 30897 15430 30897 15430 30898 15429 30898 15433 30898 15430 30899 15433 30899 15431 30899 15431 30900 15433 30900 9479 30900 15431 30901 9479 30901 9481 30901 15432 30902 15411 30902 15427 30902 15427 30903 15411 30903 15422 30903 15427 30904 15422 30904 15429 30904 15429 30905 15422 30905 15423 30905 15429 30906 15423 30906 15433 30906 15433 30907 15423 30907 15416 30907 15433 30908 15416 30908 9479 30908 9479 30909 15416 30909 15415 30909 15434 30910 15431 30910 15435 30910 15435 30911 15431 30911 9481 30911 15436 30912 9485 30912 9763 30912 9763 30913 15437 30913 15436 30913 15436 30914 15437 30914 15428 30914 15436 30915 15428 30915 15434 30915 15434 30916 15428 30916 15430 30916 15434 30917 15430 30917 15431 30917 9484 30918 9485 30918 15438 30918 15438 30919 9485 30919 15436 30919 15438 30920 15436 30920 15449 30920 15449 30921 15436 30921 15434 30921 15449 30922 15434 30922 9482 30922 9482 30923 15434 30923 15435 30923 15439 30924 9759 30924 9758 30924 15440 30925 15441 30925 5684 30925 5684 30926 15441 30926 15450 30926 5684 30927 15450 30927 9478 30927 15439 30928 9758 30928 15444 30928 15444 30929 9758 30929 15442 30929 15444 30930 15442 30930 15445 30930 15446 30931 15443 30931 15445 30931 15445 30932 15443 30932 5605 30932 15445 30933 5605 30933 15444 30933 15442 30934 15447 30934 15445 30934 15445 30935 15447 30935 15448 30935 15445 30936 15448 30936 15446 30936 15446 30937 15448 30937 15441 30937 15446 30938 15441 30938 5607 30938 5607 30939 15441 30939 15440 30939 15447 30940 9484 30940 15448 30940 15448 30941 9484 30941 15438 30941 15448 30942 15438 30942 15441 30942 15441 30943 15438 30943 15449 30943 15441 30944 15449 30944 15450 30944 15450 30945 15449 30945 9482 30945 15459 30946 15451 30946 15457 30946 15452 30947 9768 30947 5255 30947 15464 30948 15460 30948 5245 30948 5252 30949 15453 30949 15454 30949 15454 30950 15453 30950 5239 30950 15454 30951 5239 30951 5240 30951 5255 30952 15455 30952 15452 30952 15452 30953 15455 30953 15457 30953 15452 30954 15457 30954 15456 30954 15456 30955 15457 30955 15451 30955 15456 30956 15451 30956 9769 30956 5255 30957 15458 30957 15455 30957 15455 30958 15458 30958 5252 30958 15455 30959 5252 30959 15457 30959 15457 30960 5252 30960 15454 30960 15457 30961 15454 30961 15459 30961 15459 30962 15454 30962 5240 30962 15459 30963 5240 30963 15464 30963 15464 30964 5240 30964 5243 30964 15464 30965 5243 30965 15460 30965 15461 30966 9769 30966 15462 30966 15462 30967 9769 30967 15451 30967 15462 30968 15451 30968 15463 30968 15463 30969 15451 30969 15459 30969 15463 30970 15459 30970 15467 30970 15467 30971 15459 30971 15464 30971 15467 30972 15464 30972 15465 30972 15465 30973 15464 30973 5245 30973 15465 30974 5245 30974 9416 30974 9419 30975 5232 30975 15469 30975 9419 30976 15468 30976 9417 30976 9417 30977 15468 30977 15465 30977 9417 30978 15465 30978 9416 30978 15466 30979 15471 30979 15461 30979 15461 30980 15462 30980 15466 30980 15466 30981 15462 30981 15463 30981 15466 30982 15463 30982 15468 30982 15468 30983 15463 30983 15467 30983 15468 30984 15467 30984 15465 30984 9419 30985 15469 30985 15468 30985 15468 30986 15469 30986 15479 30986 15468 30987 15479 30987 15466 30987 15466 30988 15479 30988 15477 30988 15466 30989 15477 30989 15471 30989 15471 30990 15477 30990 15470 30990 15471 30991 15470 30991 15472 30991 15473 30992 5237 30992 15480 30992 15475 30993 15474 30993 15476 30993 15475 30994 15476 30994 5235 30994 5235 30995 15476 30995 9766 30995 5235 30996 9766 30996 5237 30996 15480 30997 15470 30997 15477 30997 15473 30998 15480 30998 15478 30998 15478 30999 15480 30999 15477 30999 15478 31000 15477 31000 5230 31000 5230 31001 15477 31001 15479 31001 5230 31002 15479 31002 5231 31002 5231 31003 15479 31003 15469 31003 5231 31004 15469 31004 5232 31004 5237 31005 9766 31005 15480 31005 15480 31006 9766 31006 15472 31006 15480 31007 15472 31007 15470 31007 15483 31008 4858 31008 4867 31008 15481 31009 8146 31009 8148 31009 15481 31010 8148 31010 4870 31010 4870 31011 8148 31011 15482 31011 4870 31012 15482 31012 4868 31012 4868 31013 15482 31013 15486 31013 4868 31014 15486 31014 4867 31014 4867 31015 15486 31015 15485 31015 4867 31016 15485 31016 15483 31016 4861 31017 4858 31017 15483 31017 4861 31018 15483 31018 15488 31018 15488 31019 15483 31019 15484 31019 15484 31020 15483 31020 15485 31020 15484 31021 15485 31021 15487 31021 8148 31022 8140 31022 15482 31022 15482 31023 8140 31023 15487 31023 15482 31024 15487 31024 15486 31024 15486 31025 15487 31025 15485 31025 4558 31026 15488 31026 15490 31026 15490 31027 15488 31027 15484 31027 15490 31028 15484 31028 15491 31028 15491 31029 15484 31029 15487 31029 8140 31030 15489 31030 15487 31030 15487 31031 15489 31031 15493 31031 15487 31032 15493 31032 15491 31032 15506 31033 4558 31033 15490 31033 15506 31034 15490 31034 15492 31034 15492 31035 15490 31035 15491 31035 15492 31036 15491 31036 15507 31036 15507 31037 15491 31037 15493 31037 15507 31038 15493 31038 15509 31038 15509 31039 15493 31039 15489 31039 15509 31040 15489 31040 15494 31040 15495 31041 15496 31041 15511 31041 15511 31042 15496 31042 15498 31042 15511 31043 15498 31043 15497 31043 15497 31044 15498 31044 15499 31044 15497 31045 15499 31045 15500 31045 15500 31046 15499 31046 15504 31046 15500 31047 15504 31047 6206 31047 6206 31048 15504 31048 15501 31048 15496 31049 8138 31049 15498 31049 15498 31050 8138 31050 15502 31050 15498 31051 15502 31051 15499 31051 15499 31052 15502 31052 15503 31052 15499 31053 15503 31053 15504 31053 15504 31054 15503 31054 15505 31054 15504 31055 15505 31055 15501 31055 15501 31056 15505 31056 15508 31056 8138 31057 15506 31057 15502 31057 15502 31058 15506 31058 15492 31058 15502 31059 15492 31059 15503 31059 15503 31060 15492 31060 15507 31060 15503 31061 15507 31061 15505 31061 15505 31062 15507 31062 15509 31062 15505 31063 15509 31063 15508 31063 15508 31064 15509 31064 15494 31064 15510 31065 15495 31065 15511 31065 15510 31066 15511 31066 15512 31066 15512 31067 15511 31067 15497 31067 15512 31068 15497 31068 15513 31068 15513 31069 15497 31069 15500 31069 15513 31070 15500 31070 15516 31070 15516 31071 15500 31071 6206 31071 15516 31072 6206 31072 6205 31072 15519 31073 15510 31073 15514 31073 15514 31074 15510 31074 15512 31074 15514 31075 15512 31075 15520 31075 15520 31076 15512 31076 15521 31076 15521 31077 15512 31077 15513 31077 15521 31078 15513 31078 15515 31078 15515 31079 15513 31079 15516 31079 15515 31080 15516 31080 15517 31080 15517 31081 15516 31081 15523 31081 15523 31082 15516 31082 6205 31082 15523 31083 6205 31083 6561 31083 15518 31084 4907 31084 15519 31084 15518 31085 15519 31085 15514 31085 15518 31086 15514 31086 15520 31086 6561 31087 6564 31087 15523 31087 15523 31088 6564 31088 15522 31088 15520 31089 15521 31089 15518 31089 15518 31090 15521 31090 15515 31090 15518 31091 15515 31091 15522 31091 15522 31092 15515 31092 15517 31092 15522 31093 15517 31093 15523 31093 4908 31094 4907 31094 15529 31094 15529 31095 4907 31095 15518 31095 15529 31096 15518 31096 15524 31096 15524 31097 15518 31097 15522 31097 15524 31098 15522 31098 15525 31098 15525 31099 15522 31099 6564 31099 15526 31100 4908 31100 15527 31100 15527 31101 4908 31101 15529 31101 15527 31102 15529 31102 15528 31102 15528 31103 15529 31103 15524 31103 15528 31104 15524 31104 15530 31104 15530 31105 15524 31105 15525 31105 15528 31106 15530 31106 6563 31106 15527 31107 15528 31107 15531 31107 15526 31108 15527 31108 15543 31108 15528 31109 6563 31109 15531 31109 15531 31110 6563 31110 15532 31110 15531 31111 15532 31111 15535 31111 15535 31112 15532 31112 15533 31112 15535 31113 15533 31113 15537 31113 15537 31114 15533 31114 6557 31114 15537 31115 6557 31115 15534 31115 15527 31116 15531 31116 15543 31116 15543 31117 15531 31117 15535 31117 15543 31118 15535 31118 15536 31118 15536 31119 15535 31119 15537 31119 15536 31120 15537 31120 15542 31120 15542 31121 15537 31121 15534 31121 15542 31122 15534 31122 15539 31122 15544 31123 15538 31123 15539 31123 15539 31124 15538 31124 15540 31124 15539 31125 15540 31125 15542 31125 15542 31126 15540 31126 15541 31126 15542 31127 15541 31127 15536 31127 15536 31128 15541 31128 5649 31128 15536 31129 5649 31129 15543 31129 15543 31130 5649 31130 5651 31130 15543 31131 5651 31131 15526 31131 15549 31132 15544 31132 15545 31132 15545 31133 15544 31133 15539 31133 15545 31134 15539 31134 15546 31134 15546 31135 15539 31135 15534 31135 15546 31136 15534 31136 15550 31136 15550 31137 15534 31137 6557 31137 15547 31138 15549 31138 15548 31138 15548 31139 15549 31139 15545 31139 15548 31140 15545 31140 15552 31140 15552 31141 15545 31141 15546 31141 15552 31142 15546 31142 6552 31142 6552 31143 15546 31143 15550 31143 15554 31144 15547 31144 15551 31144 15551 31145 15547 31145 15548 31145 15551 31146 15548 31146 15557 31146 15557 31147 15548 31147 15552 31147 15557 31148 15552 31148 15553 31148 15553 31149 15552 31149 6552 31149 7204 31150 15554 31150 15555 31150 15555 31151 15554 31151 15551 31151 15555 31152 15551 31152 15556 31152 15556 31153 15551 31153 15557 31153 15556 31154 15557 31154 15559 31154 15559 31155 15557 31155 15553 31155 7207 31156 7204 31156 15555 31156 7207 31157 15555 31157 15558 31157 15558 31158 15555 31158 15556 31158 15558 31159 15556 31159 15561 31159 15561 31160 15556 31160 15559 31160 15561 31161 15559 31161 4874 31161 15570 31162 7207 31162 15558 31162 15570 31163 15558 31163 15560 31163 15560 31164 15558 31164 15561 31164 15560 31165 15561 31165 15562 31165 15562 31166 15561 31166 4874 31166 15562 31167 4874 31167 4879 31167 15571 31168 15563 31168 15572 31168 15572 31169 15563 31169 15566 31169 15572 31170 15566 31170 15564 31170 15564 31171 15566 31171 15567 31171 15564 31172 15567 31172 15574 31172 15574 31173 15567 31173 4877 31173 15563 31174 15565 31174 15566 31174 15566 31175 15565 31175 15568 31175 15566 31176 15568 31176 15567 31176 15567 31177 15568 31177 15569 31177 15567 31178 15569 31178 4877 31178 4877 31179 15569 31179 4878 31179 15565 31180 15570 31180 15568 31180 15568 31181 15570 31181 15560 31181 15568 31182 15560 31182 15569 31182 15569 31183 15560 31183 15562 31183 15569 31184 15562 31184 4878 31184 4878 31185 15562 31185 4879 31185 4470 31186 15571 31186 15573 31186 15573 31187 15571 31187 15572 31187 15573 31188 15572 31188 15576 31188 15576 31189 15572 31189 15564 31189 15576 31190 15564 31190 15578 31190 15578 31191 15564 31191 15574 31191 14419 31192 4470 31192 15575 31192 15575 31193 4470 31193 15573 31193 15575 31194 15573 31194 15586 31194 15586 31195 15573 31195 15576 31195 15586 31196 15576 31196 15577 31196 15577 31197 15576 31197 15578 31197 4538 31198 15579 31198 4539 31198 4539 31199 15579 31199 15583 31199 15582 31200 15580 31200 4537 31200 15589 31201 4542 31201 15580 31201 15580 31202 4542 31202 15581 31202 15580 31203 15581 31203 4537 31203 4537 31204 4541 31204 15582 31204 15582 31205 4541 31205 15583 31205 15582 31206 15583 31206 14424 31206 14424 31207 15583 31207 15579 31207 15587 31208 14421 31208 15588 31208 15588 31209 14421 31209 15585 31209 15588 31210 15585 31210 15584 31210 15584 31211 15585 31211 15591 31211 14421 31212 14419 31212 15585 31212 15585 31213 14419 31213 15575 31213 15585 31214 15575 31214 15591 31214 15591 31215 15575 31215 15586 31215 14424 31216 15587 31216 15582 31216 15582 31217 15587 31217 15588 31217 15582 31218 15588 31218 15580 31218 15580 31219 15588 31219 15584 31219 15580 31220 15584 31220 15589 31220 15589 31221 15584 31221 15591 31221 15589 31222 15591 31222 15590 31222 15590 31223 15591 31223 15586 31223 15590 31224 15586 31224 15577 31224 15597 31225 15592 31225 15593 31225 15596 31226 4508 31226 15594 31226 15594 31227 4508 31227 15595 31227 15603 31228 15602 31228 15598 31228 4506 31229 15613 31229 15612 31229 4510 31230 15596 31230 15593 31230 15593 31231 15596 31231 15594 31231 15593 31232 15594 31232 15597 31232 15597 31233 15594 31233 15595 31233 15597 31234 15595 31234 15598 31234 15598 31235 15595 31235 15599 31235 15598 31236 15599 31236 15603 31236 15600 31237 15592 31237 15601 31237 15601 31238 15592 31238 15597 31238 15601 31239 15597 31239 15611 31239 15611 31240 15597 31240 15598 31240 15611 31241 15598 31241 15612 31241 15612 31242 15598 31242 15602 31242 15612 31243 15602 31243 4506 31243 4506 31244 15602 31244 15603 31244 15604 31245 14501 31245 15605 31245 15605 31246 14501 31246 15606 31246 15605 31247 15606 31247 15618 31247 15618 31248 15606 31248 15610 31248 15618 31249 15610 31249 15607 31249 15607 31250 15610 31250 15609 31250 15607 31251 15609 31251 15608 31251 15608 31252 15609 31252 4889 31252 15608 31253 4889 31253 4902 31253 14501 31254 15600 31254 15606 31254 15606 31255 15600 31255 15601 31255 15606 31256 15601 31256 15610 31256 15610 31257 15601 31257 15611 31257 15610 31258 15611 31258 15609 31258 15609 31259 15611 31259 15612 31259 15609 31260 15612 31260 4889 31260 4889 31261 15612 31261 15613 31261 15619 31262 4901 31262 15614 31262 15628 31263 14609 31263 15617 31263 15615 31264 15628 31264 15616 31264 15628 31265 15617 31265 15616 31265 15616 31266 15617 31266 15604 31266 15616 31267 15604 31267 15605 31267 15605 31268 15618 31268 15616 31268 15616 31269 15618 31269 15619 31269 15616 31270 15619 31270 15615 31270 15615 31271 15619 31271 15614 31271 4902 31272 4901 31272 15608 31272 15608 31273 4901 31273 15619 31273 15608 31274 15619 31274 15607 31274 15607 31275 15619 31275 15618 31275 15622 31276 15620 31276 15631 31276 15631 31277 15621 31277 15622 31277 15622 31278 15621 31278 15632 31278 15622 31279 15632 31279 6145 31279 6145 31280 15632 31280 6124 31280 6124 31281 15632 31281 15623 31281 6124 31282 15623 31282 8142 31282 7444 31283 14606 31283 15633 31283 15633 31284 14606 31284 15624 31284 15633 31285 15624 31285 15635 31285 15635 31286 15624 31286 15626 31286 15635 31287 15626 31287 4894 31287 4894 31288 15626 31288 15627 31288 14606 31289 14607 31289 15624 31289 15624 31290 14607 31290 15625 31290 15624 31291 15625 31291 15626 31291 15626 31292 15625 31292 15629 31292 15626 31293 15629 31293 15627 31293 15627 31294 15629 31294 15630 31294 14607 31295 14609 31295 15625 31295 15625 31296 14609 31296 15628 31296 15625 31297 15628 31297 15629 31297 15629 31298 15628 31298 15615 31298 15629 31299 15615 31299 15630 31299 15630 31300 15615 31300 15614 31300 4529 31301 4531 31301 15641 31301 15631 31302 15620 31302 4529 31302 4529 31303 15641 31303 15631 31303 15631 31304 15641 31304 15640 31304 15631 31305 15640 31305 15621 31305 15621 31306 15640 31306 15639 31306 15621 31307 15639 31307 15632 31307 15632 31308 15639 31308 15638 31308 15632 31309 15638 31309 15623 31309 7446 31310 7444 31310 15633 31310 7446 31311 15633 31311 15634 31311 15634 31312 15633 31312 15635 31312 15634 31313 15635 31313 15636 31313 15636 31314 15635 31314 4894 31314 15636 31315 4894 31315 15637 31315 6260 31316 15638 31316 15657 31316 15657 31317 15638 31317 15639 31317 15657 31318 15639 31318 15655 31318 15655 31319 15639 31319 15640 31319 15655 31320 15640 31320 15653 31320 15653 31321 15640 31321 15641 31321 15653 31322 15641 31322 15651 31322 15651 31323 15641 31323 4531 31323 15642 31324 7446 31324 15643 31324 15643 31325 7446 31325 15634 31325 15643 31326 15634 31326 15646 31326 15646 31327 15634 31327 15636 31327 15646 31328 15636 31328 15647 31328 15647 31329 15636 31329 15637 31329 15649 31330 15642 31330 15650 31330 15650 31331 15642 31331 15643 31331 15650 31332 15643 31332 15644 31332 15644 31333 15643 31333 15646 31333 15644 31334 15646 31334 15645 31334 15645 31335 15646 31335 15647 31335 15662 31336 15649 31336 15648 31336 15648 31337 15649 31337 15650 31337 15648 31338 15650 31338 15659 31338 15659 31339 15650 31339 15644 31339 15659 31340 15644 31340 15658 31340 15658 31341 15644 31341 15645 31341 15651 31342 4530 31342 15652 31342 15651 31343 15652 31343 15653 31343 15653 31344 15652 31344 15654 31344 15653 31345 15654 31345 15655 31345 15655 31346 15654 31346 15656 31346 15655 31347 15656 31347 15657 31347 15657 31348 15656 31348 6261 31348 15657 31349 6261 31349 6260 31349 15658 31350 6269 31350 15659 31350 15659 31351 6269 31351 15666 31351 15659 31352 15666 31352 15648 31352 15648 31353 15666 31353 15660 31353 15648 31354 15660 31354 15662 31354 15670 31355 15661 31355 15660 31355 15660 31356 15661 31356 5940 31356 15660 31357 5940 31357 15662 31357 15667 31358 6270 31358 15668 31358 15668 31359 6270 31359 15663 31359 15668 31360 15663 31360 15669 31360 15669 31361 15663 31361 15665 31361 6270 31362 15664 31362 15663 31362 15663 31363 15664 31363 15674 31363 15663 31364 15674 31364 15665 31364 15665 31365 15674 31365 15672 31365 6269 31366 15667 31366 15666 31366 15666 31367 15667 31367 15668 31367 15666 31368 15668 31368 15660 31368 15660 31369 15668 31369 15669 31369 15660 31370 15669 31370 15670 31370 15670 31371 15669 31371 15665 31371 15670 31372 15665 31372 5937 31372 5937 31373 15665 31373 15672 31373 5937 31374 15672 31374 15671 31374 15671 31375 15672 31375 5936 31375 5935 31376 5936 31376 15675 31376 15675 31377 5936 31377 15672 31377 15675 31378 15672 31378 15673 31378 15673 31379 15672 31379 15674 31379 15673 31380 15674 31380 6266 31380 6266 31381 15674 31381 15664 31381 15699 31382 5935 31382 15698 31382 15698 31383 5935 31383 15675 31383 15698 31384 15675 31384 15676 31384 15676 31385 15675 31385 15673 31385 15676 31386 15673 31386 6278 31386 6278 31387 15673 31387 6266 31387 4530 31388 15677 31388 15652 31388 15652 31389 15677 31389 15678 31389 15652 31390 15678 31390 15654 31390 15654 31391 15678 31391 15679 31391 15654 31392 15679 31392 15656 31392 15656 31393 15679 31393 15681 31393 15656 31394 15681 31394 6261 31394 6261 31395 15681 31395 15682 31395 15677 31396 4905 31396 15678 31396 15678 31397 4905 31397 15684 31397 15678 31398 15684 31398 15679 31398 15679 31399 15684 31399 15685 31399 15679 31400 15685 31400 15681 31400 15681 31401 15685 31401 15680 31401 15681 31402 15680 31402 15682 31402 15682 31403 15680 31403 6262 31403 4905 31404 15683 31404 15684 31404 15684 31405 15683 31405 15686 31405 15684 31406 15686 31406 15685 31406 15685 31407 15686 31407 15687 31407 15685 31408 15687 31408 15680 31408 15680 31409 15687 31409 15688 31409 15680 31410 15688 31410 6262 31410 6262 31411 15688 31411 15702 31411 15707 31412 15689 31412 15690 31412 15691 31413 15708 31413 15692 31413 15692 31414 15708 31414 15693 31414 15692 31415 15693 31415 5933 31415 5933 31416 15693 31416 15710 31416 15690 31417 15689 31417 15692 31417 15692 31418 15689 31418 15694 31418 15692 31419 15694 31419 15691 31419 15696 31420 15695 31420 15690 31420 15690 31421 15695 31421 15703 31421 15690 31422 15703 31422 15707 31422 6277 31423 15696 31423 15697 31423 15697 31424 15696 31424 15690 31424 15697 31425 15690 31425 15700 31425 15700 31426 15690 31426 15692 31426 15700 31427 15692 31427 5931 31427 5931 31428 15692 31428 5933 31428 6278 31429 6277 31429 15676 31429 15676 31430 6277 31430 15697 31430 15676 31431 15697 31431 15698 31431 15698 31432 15697 31432 15700 31432 15698 31433 15700 31433 15699 31433 15699 31434 15700 31434 5931 31434 15683 31435 15709 31435 15701 31435 15683 31436 15701 31436 15686 31436 15686 31437 15701 31437 15705 31437 15686 31438 15705 31438 15687 31438 15687 31439 15705 31439 15706 31439 15687 31440 15706 31440 15688 31440 15688 31441 15706 31441 15704 31441 15688 31442 15704 31442 15702 31442 15695 31443 15704 31443 15703 31443 15703 31444 15704 31444 15706 31444 15691 31445 15694 31445 15705 31445 15705 31446 15694 31446 15689 31446 15705 31447 15689 31447 15706 31447 15706 31448 15689 31448 15707 31448 15706 31449 15707 31449 15703 31449 15691 31450 15705 31450 15708 31450 15708 31451 15705 31451 15701 31451 15708 31452 15701 31452 15693 31452 15693 31453 15701 31453 15709 31453 15693 31454 15709 31454 15710 31454 14630 31455 14631 31455 4679 31455 15714 31456 14395 31456 14394 31456 14393 31457 14396 31457 15780 31457 15780 31458 15711 31458 14393 31458 14393 31459 15711 31459 15781 31459 14393 31460 15781 31460 15712 31460 15712 31461 15781 31461 15786 31461 15712 31462 15786 31462 14392 31462 14392 31463 15786 31463 15713 31463 14392 31464 15713 31464 14394 31464 14394 31465 15713 31465 15792 31465 14394 31466 15792 31466 15714 31466 14631 31467 14627 31467 15723 31467 15723 31468 14627 31468 15721 31468 15715 31469 14386 31469 15716 31469 15716 31470 14386 31470 15717 31470 15716 31471 15717 31471 15718 31471 15718 31472 15717 31472 15719 31472 15718 31473 15719 31473 15720 31473 15720 31474 15719 31474 15722 31474 15720 31475 15722 31475 15721 31475 15721 31476 15722 31476 14397 31476 15721 31477 14397 31477 15723 31477 15723 31478 14397 31478 15724 31478 4664 31479 4672 31479 15772 31479 15772 31480 4672 31480 4668 31480 15772 31481 4668 31481 15725 31481 15725 31482 4668 31482 15726 31482 15725 31483 15726 31483 15773 31483 15773 31484 15726 31484 4667 31484 15773 31485 4667 31485 15727 31485 15727 31486 4667 31486 15728 31486 15727 31487 15728 31487 15732 31487 15732 31488 15728 31488 4673 31488 16759 31489 15729 31489 15731 31489 15732 31490 4673 31490 15733 31490 15730 31491 15763 31491 15731 31491 15731 31492 15763 31492 15732 31492 15733 31493 14635 31493 15732 31493 15732 31494 14635 31494 4716 31494 15732 31495 4716 31495 15731 31495 15731 31496 4716 31496 16758 31496 15731 31497 16758 31497 16759 31497 15763 31498 15730 31498 15734 31498 15734 31499 15730 31499 15735 31499 15734 31500 15735 31500 15736 31500 15736 31501 15735 31501 4669 31501 15736 31502 4669 31502 15756 31502 15756 31503 4669 31503 15737 31503 15756 31504 15737 31504 15738 31504 15738 31505 15737 31505 15739 31505 15738 31506 15739 31506 5185 31506 5185 31507 15739 31507 5183 31507 15759 31508 15741 31508 5736 31508 15771 31509 15743 31509 5725 31509 5725 31510 15743 31510 5726 31510 5737 31511 5736 31511 15740 31511 15740 31512 5736 31512 15741 31512 15740 31513 15741 31513 15742 31513 15742 31514 15741 31514 15755 31514 15742 31515 15755 31515 5187 31515 5187 31516 15755 31516 5188 31516 5726 31517 15743 31517 5728 31517 5728 31518 15743 31518 15747 31518 5728 31519 15747 31519 15748 31519 5736 31520 5734 31520 15759 31520 15759 31521 5734 31521 15744 31521 15759 31522 15744 31522 15745 31522 15745 31523 15744 31523 15746 31523 15745 31524 15746 31524 15747 31524 15747 31525 15746 31525 5724 31525 15747 31526 5724 31526 15748 31526 15749 31527 15736 31527 15756 31527 5188 31528 15755 31528 5190 31528 5190 31529 15755 31529 15754 31529 5193 31530 15750 31530 15757 31530 15757 31531 15750 31531 5192 31531 15757 31532 5192 31532 15758 31532 15763 31533 15734 31533 15751 31533 15751 31534 15734 31534 15753 31534 15751 31535 15753 31535 15761 31535 15761 31536 15753 31536 15752 31536 15761 31537 15752 31537 15759 31537 15759 31538 15752 31538 15741 31538 15734 31539 15736 31539 15753 31539 15753 31540 15736 31540 15749 31540 15753 31541 15749 31541 15752 31541 15752 31542 15749 31542 15754 31542 15752 31543 15754 31543 15741 31543 15741 31544 15754 31544 15755 31544 5185 31545 5186 31545 15738 31545 15738 31546 5186 31546 5193 31546 15738 31547 5193 31547 15756 31547 15756 31548 5193 31548 15757 31548 15756 31549 15757 31549 15749 31549 15749 31550 15757 31550 15758 31550 15749 31551 15758 31551 15754 31551 15754 31552 15758 31552 5191 31552 15754 31553 5191 31553 5190 31553 15759 31554 15745 31554 15760 31554 15759 31555 15760 31555 15761 31555 15761 31556 15760 31556 15762 31556 15761 31557 15762 31557 15751 31557 15751 31558 15762 31558 15732 31558 15751 31559 15732 31559 15763 31559 15764 31560 4664 31560 15772 31560 15765 31561 4660 31561 15766 31561 15766 31562 4660 31562 4658 31562 15765 31563 15766 31563 4662 31563 4662 31564 15766 31564 15767 31564 4662 31565 15767 31565 15768 31565 15768 31566 15767 31566 15770 31566 15768 31567 15770 31567 15769 31567 15769 31568 15770 31568 15743 31568 15769 31569 15743 31569 15771 31569 15764 31570 15772 31570 4658 31570 4658 31571 15772 31571 15725 31571 4658 31572 15725 31572 15766 31572 15766 31573 15725 31573 15773 31573 15766 31574 15773 31574 15767 31574 15773 31575 15727 31575 15767 31575 15767 31576 15727 31576 15774 31576 15767 31577 15774 31577 15770 31577 15770 31578 15774 31578 15775 31578 15770 31579 15775 31579 15743 31579 15743 31580 15775 31580 15747 31580 15727 31581 15732 31581 15774 31581 15774 31582 15732 31582 15762 31582 15774 31583 15762 31583 15775 31583 15775 31584 15762 31584 15760 31584 15775 31585 15760 31585 15747 31585 15747 31586 15760 31586 15745 31586 5808 31587 9369 31587 5811 31587 5811 31588 9369 31588 15779 31588 5815 31589 5814 31589 15776 31589 15776 31590 5814 31590 15777 31590 15776 31591 15777 31591 15787 31591 15787 31592 15777 31592 15778 31592 15787 31593 15778 31593 15779 31593 15779 31594 15778 31594 5812 31594 15779 31595 5812 31595 5811 31595 15780 31596 5807 31596 15711 31596 15711 31597 5807 31597 5815 31597 15711 31598 5815 31598 15781 31598 9368 31599 9365 31599 15782 31599 9368 31600 15782 31600 15784 31600 9369 31601 9368 31601 15779 31601 15779 31602 9368 31602 15784 31602 15779 31603 15784 31603 15787 31603 15787 31604 15784 31604 15785 31604 15782 31605 15783 31605 15784 31605 15784 31606 15783 31606 15789 31606 15784 31607 15789 31607 15785 31607 15785 31608 15789 31608 15790 31608 15785 31609 15790 31609 15791 31609 5815 31610 15776 31610 15781 31610 15781 31611 15776 31611 15787 31611 15781 31612 15787 31612 15786 31612 15786 31613 15787 31613 15785 31613 15786 31614 15785 31614 15713 31614 15713 31615 15785 31615 15791 31615 15713 31616 15791 31616 15792 31616 9372 31617 15788 31617 9365 31617 9365 31618 15788 31618 15782 31618 15782 31619 15788 31619 15783 31619 15783 31620 15788 31620 15802 31620 15783 31621 15802 31621 15789 31621 15789 31622 15802 31622 15794 31622 15789 31623 15794 31623 15790 31623 15790 31624 15794 31624 15805 31624 15790 31625 15805 31625 15791 31625 15805 31626 15793 31626 15791 31626 15791 31627 15793 31627 14627 31627 15791 31628 14627 31628 15792 31628 15793 31629 15805 31629 15807 31629 15794 31630 15802 31630 15801 31630 15788 31631 9372 31631 15800 31631 15798 31632 15803 31632 15804 31632 15806 31633 15796 31633 5818 31633 15795 31634 15715 31634 15716 31634 15795 31635 15716 31635 5817 31635 5817 31636 15716 31636 15718 31636 5817 31637 15718 31637 15806 31637 5818 31638 15796 31638 5819 31638 5819 31639 15796 31639 15797 31639 5819 31640 15797 31640 15803 31640 15799 31641 5816 31641 15798 31641 15798 31642 15804 31642 15799 31642 15799 31643 15804 31643 15801 31643 15799 31644 15801 31644 15800 31644 15800 31645 15801 31645 15802 31645 15800 31646 15802 31646 15788 31646 15803 31647 15797 31647 15804 31647 15804 31648 15797 31648 15807 31648 15804 31649 15807 31649 15801 31649 15801 31650 15807 31650 15805 31650 15801 31651 15805 31651 15794 31651 15806 31652 15718 31652 15796 31652 15796 31653 15718 31653 15720 31653 15796 31654 15720 31654 15797 31654 15797 31655 15720 31655 15721 31655 15797 31656 15721 31656 15807 31656 15807 31657 15721 31657 14627 31657 15807 31658 14627 31658 15793 31658 4718 31659 15836 31659 15814 31659 15808 31660 15809 31660 16279 31660 16279 31661 15809 31661 16276 31661 16276 31662 15809 31662 15810 31662 16276 31663 15810 31663 15811 31663 15812 31664 15813 31664 15814 31664 15814 31665 15813 31665 15815 31665 15814 31666 15815 31666 15816 31666 4718 31667 15814 31667 16280 31667 16280 31668 15814 31668 15816 31668 16280 31669 15816 31669 15818 31669 15818 31670 15816 31670 15817 31670 15818 31671 15817 31671 16279 31671 16279 31672 15817 31672 9587 31672 16279 31673 9587 31673 15808 31673 15820 31674 15831 31674 15836 31674 15828 31675 15829 31675 9583 31675 9583 31676 15829 31676 15825 31676 9583 31677 15825 31677 15827 31677 15836 31678 15831 31678 15814 31678 15814 31679 15831 31679 15830 31679 15814 31680 15830 31680 15812 31680 15819 31681 15820 31681 15836 31681 9508 31682 9506 31682 15821 31682 15821 31683 9506 31683 15824 31683 15821 31684 15824 31684 15822 31684 9506 31685 15823 31685 15824 31685 15824 31686 15823 31686 9505 31686 15824 31687 9505 31687 15825 31687 15825 31688 9505 31688 15826 31688 15825 31689 15826 31689 15827 31689 15828 31690 15830 31690 15829 31690 15829 31691 15830 31691 15831 31691 15829 31692 15831 31692 15825 31692 15825 31693 15831 31693 15820 31693 15825 31694 15820 31694 15824 31694 15824 31695 15820 31695 15819 31695 15822 31696 15824 31696 15832 31696 15832 31697 15824 31697 15819 31697 15832 31698 15819 31698 15836 31698 9509 31699 9508 31699 15821 31699 9509 31700 15821 31700 15833 31700 15833 31701 15821 31701 15822 31701 15833 31702 15822 31702 15834 31702 15834 31703 15822 31703 15832 31703 15834 31704 15832 31704 15835 31704 15835 31705 15832 31705 15836 31705 15835 31706 15836 31706 15838 31706 4719 31707 15837 31707 15845 31707 15838 31708 4719 31708 15839 31708 15838 31709 15839 31709 15835 31709 15835 31710 15839 31710 15840 31710 15835 31711 15840 31711 15834 31711 15834 31712 15840 31712 15841 31712 15834 31713 15841 31713 15833 31713 15833 31714 15841 31714 15844 31714 15833 31715 15844 31715 9509 31715 4719 31716 15845 31716 15839 31716 15839 31717 15845 31717 15842 31717 15839 31718 15842 31718 15840 31718 15840 31719 15842 31719 15848 31719 15840 31720 15848 31720 15841 31720 15841 31721 15848 31721 15843 31721 15841 31722 15843 31722 15844 31722 15960 31723 15962 31723 15845 31723 9501 31724 15843 31724 15846 31724 15846 31725 15843 31725 15848 31725 15846 31726 15848 31726 15968 31726 15968 31727 15848 31727 15850 31727 15845 31728 15962 31728 15842 31728 15962 31729 15963 31729 15842 31729 15842 31730 15963 31730 15847 31730 15842 31731 15847 31731 15848 31731 15848 31732 15847 31732 15849 31732 15848 31733 15849 31733 15850 31733 15837 31734 4717 31734 15845 31734 15845 31735 4717 31735 15851 31735 15845 31736 15851 31736 15960 31736 16257 31737 9576 31737 15852 31737 15852 31738 9576 31738 15855 31738 9497 31739 9589 31739 16260 31739 16260 31740 9589 31740 9588 31740 16260 31741 9588 31741 16257 31741 16257 31742 9588 31742 9574 31742 16257 31743 9574 31743 9576 31743 9578 31744 15853 31744 15856 31744 15856 31745 15853 31745 15854 31745 15856 31746 15854 31746 15858 31746 15858 31747 15854 31747 9579 31747 15855 31748 9578 31748 15852 31748 15852 31749 9578 31749 15856 31749 15852 31750 15856 31750 15857 31750 15857 31751 15856 31751 15870 31751 15857 31752 15870 31752 9525 31752 15858 31753 9579 31753 15862 31753 15862 31754 9579 31754 9581 31754 15862 31755 9581 31755 15859 31755 15859 31756 9581 31756 9580 31756 15868 31757 15867 31757 9503 31757 9503 31758 15867 31758 15860 31758 9503 31759 15860 31759 9591 31759 15869 31760 9504 31760 15861 31760 15873 31761 15862 31761 15865 31761 15865 31762 15862 31762 15859 31762 15865 31763 15859 31763 15867 31763 15867 31764 15859 31764 9580 31764 15867 31765 9580 31765 15860 31765 15870 31766 15856 31766 15863 31766 15863 31767 15856 31767 15858 31767 15870 31768 15873 31768 15864 31768 15864 31769 15873 31769 15865 31769 15864 31770 15865 31770 15866 31770 15866 31771 15865 31771 15867 31771 15866 31772 15867 31772 15869 31772 15869 31773 15867 31773 15868 31773 15869 31774 15868 31774 9504 31774 15870 31775 15864 31775 15871 31775 15871 31776 15864 31776 15866 31776 15871 31777 15866 31777 15877 31777 15877 31778 15866 31778 15869 31778 15877 31779 15869 31779 15872 31779 15872 31780 15869 31780 15861 31780 15872 31781 15861 31781 9507 31781 15858 31782 15862 31782 15863 31782 15863 31783 15862 31783 15873 31783 15863 31784 15873 31784 15870 31784 15874 31785 15870 31785 15871 31785 15874 31786 15871 31786 15875 31786 15875 31787 15871 31787 15877 31787 15875 31788 15877 31788 15876 31788 15876 31789 15877 31789 15872 31789 15876 31790 15872 31790 15880 31790 15880 31791 15872 31791 9507 31791 15880 31792 9507 31792 9510 31792 9502 31793 15878 31793 9572 31793 9572 31794 15878 31794 15879 31794 9572 31795 15879 31795 9510 31795 9510 31796 15879 31796 15880 31796 15880 31797 15879 31797 15876 31797 15876 31798 15879 31798 15882 31798 15876 31799 15882 31799 15875 31799 15881 31800 15882 31800 15889 31800 15889 31801 15882 31801 15879 31801 15889 31802 15879 31802 15883 31802 15883 31803 15879 31803 15878 31803 15881 31804 15884 31804 15882 31804 15882 31805 15884 31805 15885 31805 15882 31806 15885 31806 15875 31806 15875 31807 15885 31807 15874 31807 15886 31808 15884 31808 15917 31808 15917 31809 15884 31809 15881 31809 15917 31810 15881 31810 15887 31810 15887 31811 15881 31811 15888 31811 15888 31812 15881 31812 15927 31812 15927 31813 15881 31813 15889 31813 15927 31814 15889 31814 15890 31814 15890 31815 15889 31815 15891 31815 15891 31816 15889 31816 15883 31816 15891 31817 15883 31817 15928 31817 15928 31818 15883 31818 15892 31818 15892 31819 15883 31819 15878 31819 15892 31820 15878 31820 15893 31820 15893 31821 15878 31821 9502 31821 15893 31822 9502 31822 9500 31822 4700 31823 16460 31823 15894 31823 15894 31824 16460 31824 16458 31824 15894 31825 16458 31825 15895 31825 15895 31826 16458 31826 15896 31826 15895 31827 15896 31827 4698 31827 4698 31828 15896 31828 16456 31828 4698 31829 16456 31829 4696 31829 4696 31830 16456 31830 4695 31830 4695 31831 16456 31831 16454 31831 4695 31832 16454 31832 16450 31832 16413 31833 15897 31833 16428 31833 16428 31834 15897 31834 4687 31834 16428 31835 4687 31835 15898 31835 15898 31836 4687 31836 4689 31836 15898 31837 4689 31837 16432 31837 16432 31838 4689 31838 4690 31838 16432 31839 4690 31839 15899 31839 15899 31840 4690 31840 15900 31840 15899 31841 15900 31841 16433 31841 16433 31842 15900 31842 15901 31842 16433 31843 15901 31843 15902 31843 16740 31844 15903 31844 9529 31844 9529 31845 15903 31845 15904 31845 15903 31846 15905 31846 15904 31846 15904 31847 15905 31847 15906 31847 15904 31848 15906 31848 15908 31848 14639 31849 16721 31849 15907 31849 15907 31850 16721 31850 15908 31850 15907 31851 15908 31851 16747 31851 16747 31852 15908 31852 15906 31852 14638 31853 15909 31853 15910 31853 15910 31854 15909 31854 16723 31854 15910 31855 16723 31855 16570 31855 16570 31856 16723 31856 15911 31856 16570 31857 15911 31857 15912 31857 15914 31858 15915 31858 15913 31858 15912 31859 15911 31859 15913 31859 15913 31860 15911 31860 16724 31860 15913 31861 16724 31861 15914 31861 9535 31862 9534 31862 15914 31862 15914 31863 9534 31863 16565 31863 15914 31864 16565 31864 15915 31864 9500 31865 9501 31865 15931 31865 15931 31866 9501 31866 15970 31866 15931 31867 15970 31867 15916 31867 15916 31868 15970 31868 15957 31868 9559 31869 15886 31869 15917 31869 9559 31870 15917 31870 9560 31870 9560 31871 15917 31871 15887 31871 9560 31872 15887 31872 15918 31872 15918 31873 15887 31873 15888 31873 15918 31874 15888 31874 15919 31874 15919 31875 15888 31875 15927 31875 15919 31876 15927 31876 15920 31876 15921 31877 15929 31877 9545 31877 9545 31878 15929 31878 9546 31878 9546 31879 15929 31879 15922 31879 15922 31880 15929 31880 15923 31880 15922 31881 15923 31881 16022 31881 16022 31882 15923 31882 15925 31882 16022 31883 15925 31883 15924 31883 15924 31884 15925 31884 15930 31884 15924 31885 15930 31885 16018 31885 15931 31886 15916 31886 15930 31886 15930 31887 15916 31887 16013 31887 15930 31888 16013 31888 16018 31888 15920 31889 15927 31889 15926 31889 15926 31890 15927 31890 15890 31890 15926 31891 15890 31891 15921 31891 15921 31892 15890 31892 15891 31892 15921 31893 15891 31893 15929 31893 15929 31894 15891 31894 15928 31894 15929 31895 15928 31895 15923 31895 15923 31896 15928 31896 15892 31896 15923 31897 15892 31897 15925 31897 15925 31898 15892 31898 15893 31898 15925 31899 15893 31899 15930 31899 15930 31900 15893 31900 9500 31900 15930 31901 9500 31901 15931 31901 15932 31902 16025 31902 15935 31902 16026 31903 15953 31903 15934 31903 16026 31904 15934 31904 15933 31904 15933 31905 15934 31905 15937 31905 15933 31906 15937 31906 15935 31906 15932 31907 15935 31907 15936 31907 15935 31908 15937 31908 15936 31908 15936 31909 15937 31909 15938 31909 15936 31910 15938 31910 15939 31910 15939 31911 15938 31911 15940 31911 15939 31912 15940 31912 9557 31912 15941 31913 9557 31913 15951 31913 15951 31914 4639 31914 15941 31914 15941 31915 4639 31915 15942 31915 15941 31916 15942 31916 15943 31916 15947 31917 9561 31917 15942 31917 15942 31918 9561 31918 15944 31918 15942 31919 15944 31919 15943 31919 15950 31920 15946 31920 15945 31920 15945 31921 15946 31921 15947 31921 15945 31922 15947 31922 4644 31922 4644 31923 15947 31923 15942 31923 4645 31924 9571 31924 15948 31924 15948 31925 9571 31925 15949 31925 15948 31926 15949 31926 15950 31926 15950 31927 15949 31927 9569 31927 15950 31928 9569 31928 15946 31928 9557 31929 15940 31929 15951 31929 15951 31930 15940 31930 15938 31930 15951 31931 15938 31931 4641 31931 4641 31932 15938 31932 15937 31932 4641 31933 15937 31933 4642 31933 4642 31934 15937 31934 15934 31934 4642 31935 15934 31935 15952 31935 15952 31936 15934 31936 15953 31936 15952 31937 15953 31937 15954 31937 15955 31938 15996 31938 15967 31938 15967 31939 15996 31939 15998 31939 15967 31940 15998 31940 15956 31940 15956 31941 15998 31941 15997 31941 15956 31942 15997 31942 15969 31942 15969 31943 15997 31943 16001 31943 15969 31944 16001 31944 15970 31944 15970 31945 16001 31945 15957 31945 15966 31946 15958 31946 15955 31946 15955 31947 15958 31947 4740 31947 15955 31948 4740 31948 15996 31948 15964 31949 15965 31949 15847 31949 15851 31950 15959 31950 15960 31950 15960 31951 15959 31951 15961 31951 15960 31952 15961 31952 15962 31952 15962 31953 15961 31953 15964 31953 15962 31954 15964 31954 15963 31954 15963 31955 15964 31955 15847 31955 4717 31956 4757 31956 15851 31956 15851 31957 4757 31957 4756 31957 15851 31958 4756 31958 15959 31958 15965 31959 15966 31959 15847 31959 15847 31960 15966 31960 15955 31960 15847 31961 15955 31961 15849 31961 15849 31962 15955 31962 15967 31962 15849 31963 15967 31963 15850 31963 15850 31964 15967 31964 15956 31964 15850 31965 15956 31965 15968 31965 15968 31966 15956 31966 15969 31966 15968 31967 15969 31967 15846 31967 15846 31968 15969 31968 15970 31968 15846 31969 15970 31969 9501 31969 15953 31970 16026 31970 15971 31970 15953 31971 15971 31971 15954 31971 15954 31972 15971 31972 16012 31972 15954 31973 16012 31973 15989 31973 16012 31974 15972 31974 15989 31974 15989 31975 15972 31975 16008 31975 15989 31976 16008 31976 15973 31976 15973 31977 16008 31977 15991 31977 15974 31978 4759 31978 15975 31978 15974 31979 15975 31979 15976 31979 15976 31980 15975 31980 4630 31980 15976 31981 4630 31981 15978 31981 15978 31982 4630 31982 15977 31982 15978 31983 15977 31983 4750 31983 4750 31984 15977 31984 15979 31984 4750 31985 15979 31985 4751 31985 4751 31986 15979 31986 4752 31986 4752 31987 15979 31987 4634 31987 4752 31988 4634 31988 4733 31988 4733 31989 4634 31989 4633 31989 4733 31990 4633 31990 15980 31990 15981 31991 4736 31991 16000 31991 16000 31992 4736 31992 4735 31992 16000 31993 4735 31993 4734 31993 4713 31994 15985 31994 15982 31994 15982 31995 15985 31995 15983 31995 15982 31996 15983 31996 4734 31996 4734 31997 15983 31997 15984 31997 4734 31998 15984 31998 16000 31998 16000 31999 15984 31999 15987 31999 16000 32000 15987 32000 15990 32000 15990 32001 15987 32001 15973 32001 15990 32002 15973 32002 15991 32002 15980 32003 4633 32003 4713 32003 4713 32004 4633 32004 4631 32004 4713 32005 4631 32005 15985 32005 15985 32006 4631 32006 15986 32006 15985 32007 15986 32007 15983 32007 15983 32008 15986 32008 4636 32008 15983 32009 4636 32009 15984 32009 15984 32010 4636 32010 15988 32010 15984 32011 15988 32011 15987 32011 15987 32012 15988 32012 15989 32012 15987 32013 15989 32013 15973 32013 15990 32014 15991 32014 16003 32014 15981 32015 15992 32015 15994 32015 15994 32016 15992 32016 15993 32016 15994 32017 15993 32017 4706 32017 4706 32018 15993 32018 15995 32018 4706 32019 15995 32019 4739 32019 4739 32020 15995 32020 15998 32020 4739 32021 15998 32021 15996 32021 15990 32022 16003 32022 16000 32022 15997 32023 15998 32023 15999 32023 15999 32024 15998 32024 15995 32024 15999 32025 15995 32025 16002 32025 16002 32026 15995 32026 15993 32026 16002 32027 15993 32027 16003 32027 16003 32028 15993 32028 15992 32028 16003 32029 15992 32029 16000 32029 16000 32030 15992 32030 15981 32030 16001 32031 15997 32031 16005 32031 16005 32032 15997 32032 15999 32032 16005 32033 15999 32033 16007 32033 16007 32034 15999 32034 16002 32034 16007 32035 16002 32035 16004 32035 16004 32036 16002 32036 16003 32036 16004 32037 16003 32037 16008 32037 16008 32038 16003 32038 15991 32038 15957 32039 16001 32039 16006 32039 16006 32040 16001 32040 16005 32040 16006 32041 16005 32041 16009 32041 16009 32042 16005 32042 16007 32042 16009 32043 16007 32043 16011 32043 16011 32044 16007 32044 16004 32044 16011 32045 16004 32045 15972 32045 15972 32046 16004 32046 16008 32046 15916 32047 15957 32047 16006 32047 15916 32048 16006 32048 16015 32048 16015 32049 16006 32049 16009 32049 16015 32050 16009 32050 16010 32050 16010 32051 16009 32051 16011 32051 16010 32052 16011 32052 16017 32052 16017 32053 16011 32053 15972 32053 16017 32054 15972 32054 16012 32054 16013 32055 15916 32055 16014 32055 16014 32056 15916 32056 16015 32056 16014 32057 16015 32057 16016 32057 16016 32058 16015 32058 16010 32058 16016 32059 16010 32059 16020 32059 16020 32060 16010 32060 16017 32060 16020 32061 16017 32061 15971 32061 15971 32062 16017 32062 16012 32062 16018 32063 16013 32063 16019 32063 16019 32064 16013 32064 16014 32064 16019 32065 16014 32065 16028 32065 16028 32066 16014 32066 16016 32066 16028 32067 16016 32067 16027 32067 16027 32068 16016 32068 16020 32068 16027 32069 16020 32069 16026 32069 16026 32070 16020 32070 15971 32070 15933 32071 15935 32071 16021 32071 16022 32072 15924 32072 16023 32072 16022 32073 16023 32073 16024 32073 16024 32074 16023 32074 16029 32074 16024 32075 16029 32075 9532 32075 9532 32076 16029 32076 16021 32076 9532 32077 16021 32077 9533 32077 9533 32078 16021 32078 15935 32078 9533 32079 15935 32079 16025 32079 16026 32080 15933 32080 16027 32080 16027 32081 15933 32081 16021 32081 16027 32082 16021 32082 16028 32082 16028 32083 16021 32083 16029 32083 16028 32084 16029 32084 16019 32084 16019 32085 16029 32085 16023 32085 16019 32086 16023 32086 16018 32086 16018 32087 16023 32087 15924 32087 16115 32088 16042 32088 16030 32088 16030 32089 16042 32089 16049 32089 16030 32090 16049 32090 16031 32090 16031 32091 16049 32091 16032 32091 16031 32092 16032 32092 16113 32092 16113 32093 16032 32093 16033 32093 16113 32094 16033 32094 16105 32094 16105 32095 16033 32095 16048 32095 16105 32096 16048 32096 16034 32096 16034 32097 16048 32097 16043 32097 16034 32098 16043 32098 16092 32098 16092 32099 16043 32099 16064 32099 16092 32100 16064 32100 16035 32100 16035 32101 16064 32101 16036 32101 16035 32102 16036 32102 16099 32102 16099 32103 16036 32103 9516 32103 14616 32104 14618 32104 16037 32104 16037 32105 14618 32105 16071 32105 16037 32106 16071 32106 16143 32106 16143 32107 16071 32107 16075 32107 16143 32108 16075 32108 16038 32108 16038 32109 16075 32109 16074 32109 16038 32110 16074 32110 16137 32110 16137 32111 16074 32111 16039 32111 16137 32112 16039 32112 16138 32112 16138 32113 16039 32113 16073 32113 16138 32114 16073 32114 16040 32114 16073 32115 16041 32115 16040 32115 16040 32116 16041 32116 16072 32116 16040 32117 16072 32117 4781 32117 16055 32118 16052 32118 16067 32118 16047 32119 16050 32119 16055 32119 16049 32120 16042 32120 16051 32120 16064 32121 16043 32121 16065 32121 9513 32122 16053 32122 16044 32122 9513 32123 16063 32123 16062 32123 16044 32124 16053 32124 16045 32124 16046 32125 9512 32125 16036 32125 16036 32126 9512 32126 9517 32126 16036 32127 9517 32127 9516 32127 16032 32128 16050 32128 16033 32128 16033 32129 16050 32129 16047 32129 16033 32130 16047 32130 16048 32130 16032 32131 16049 32131 16050 32131 16050 32132 16049 32132 16051 32132 16050 32133 16051 32133 16055 32133 16055 32134 16051 32134 16069 32134 16055 32135 16069 32135 16052 32135 9513 32136 16062 32136 16053 32136 16053 32137 16062 32137 16058 32137 16053 32138 16058 32138 16045 32138 16043 32139 16048 32139 16065 32139 16065 32140 16048 32140 16047 32140 16065 32141 16047 32141 16054 32141 16054 32142 16047 32142 16055 32142 16054 32143 16055 32143 16056 32143 16056 32144 16055 32144 16067 32144 16056 32145 16067 32145 16057 32145 16059 32146 4724 32146 16058 32146 16058 32147 4724 32147 4725 32147 16058 32148 4725 32148 16045 32148 16066 32149 16059 32149 16060 32149 16060 32150 16059 32150 16058 32150 16060 32151 16058 32151 16061 32151 16061 32152 16058 32152 16062 32152 16061 32153 16062 32153 16046 32153 16046 32154 16062 32154 16063 32154 16046 32155 16063 32155 9512 32155 16036 32156 16064 32156 16046 32156 16046 32157 16064 32157 16065 32157 16046 32158 16065 32158 16061 32158 16061 32159 16065 32159 16054 32159 16061 32160 16054 32160 16060 32160 16060 32161 16054 32161 16056 32161 16060 32162 16056 32162 16066 32162 16066 32163 16056 32163 16057 32163 16051 32164 16042 32164 4780 32164 16091 32165 16057 32165 16086 32165 16086 32166 16057 32166 16067 32166 16086 32167 16067 32167 16068 32167 16068 32168 16067 32168 16052 32168 16068 32169 16052 32169 16081 32169 16081 32170 16052 32170 16069 32170 16081 32171 16069 32171 16070 32171 16070 32172 16069 32172 16051 32172 16070 32173 16051 32173 16072 32173 16072 32174 16051 32174 4780 32174 14366 32175 14367 32175 16083 32175 16668 32176 16667 32176 16082 32176 16082 32177 16667 32177 16666 32177 16082 32178 16666 32178 16664 32178 16669 32179 16076 32179 14619 32179 14619 32180 16076 32180 16071 32180 14619 32181 16071 32181 14618 32181 16081 32182 16070 32182 16079 32182 16079 32183 16070 32183 16072 32183 16072 32184 16041 32184 16079 32184 16079 32185 16041 32185 16073 32185 16079 32186 16073 32186 16077 32186 16073 32187 16039 32187 16077 32187 16077 32188 16039 32188 16074 32188 16077 32189 16074 32189 16076 32189 16076 32190 16074 32190 16075 32190 16076 32191 16075 32191 16071 32191 16669 32192 16668 32192 16076 32192 16076 32193 16668 32193 16082 32193 16076 32194 16082 32194 16077 32194 16077 32195 16082 32195 16078 32195 16077 32196 16078 32196 16079 32196 16079 32197 16078 32197 16080 32197 16079 32198 16080 32198 16081 32198 16081 32199 16080 32199 16068 32199 16664 32200 14366 32200 16082 32200 16082 32201 14366 32201 16083 32201 16082 32202 16083 32202 16078 32202 16078 32203 16083 32203 16084 32203 16078 32204 16084 32204 16080 32204 16080 32205 16084 32205 16085 32205 16080 32206 16085 32206 16068 32206 16068 32207 16085 32207 16086 32207 14367 32208 16087 32208 16083 32208 16083 32209 16087 32209 16088 32209 16083 32210 16088 32210 16084 32210 16084 32211 16088 32211 16089 32211 16084 32212 16089 32212 16085 32212 16085 32213 16089 32213 16090 32213 16085 32214 16090 32214 16086 32214 16086 32215 16090 32215 16091 32215 16092 32216 16035 32216 16101 32216 16093 32217 16123 32217 16121 32217 16094 32218 16093 32218 16114 32218 16095 32219 16094 32219 16108 32219 16096 32220 16104 32220 16097 32220 16104 32221 16096 32221 9514 32221 4685 32222 16095 32222 16098 32222 16098 32223 16095 32223 16103 32223 16099 32224 9515 32224 16035 32224 16035 32225 9515 32225 16100 32225 16035 32226 16100 32226 16101 32226 16101 32227 16100 32227 16102 32227 16107 32228 16097 32228 16106 32228 16106 32229 16097 32229 16104 32229 16106 32230 16104 32230 16103 32230 16103 32231 16104 32231 9514 32231 16103 32232 9514 32232 16098 32232 16034 32233 16092 32233 16107 32233 16107 32234 16092 32234 16101 32234 16107 32235 16101 32235 16097 32235 16097 32236 16101 32236 16102 32236 16097 32237 16102 32237 16096 32237 16112 32238 16113 32238 16105 32238 16095 32239 16108 32239 16103 32239 16103 32240 16108 32240 16109 32240 16103 32241 16109 32241 16106 32241 16106 32242 16109 32242 16112 32242 16106 32243 16112 32243 16107 32243 16107 32244 16112 32244 16105 32244 16107 32245 16105 32245 16034 32245 16111 32246 16030 32246 16031 32246 16094 32247 16114 32247 16108 32247 16108 32248 16114 32248 16110 32248 16108 32249 16110 32249 16109 32249 16109 32250 16110 32250 16111 32250 16109 32251 16111 32251 16112 32251 16112 32252 16111 32252 16031 32252 16112 32253 16031 32253 16113 32253 16093 32254 16121 32254 16114 32254 16114 32255 16121 32255 16119 32255 16114 32256 16119 32256 16110 32256 16110 32257 16119 32257 16118 32257 16110 32258 16118 32258 16111 32258 16111 32259 16118 32259 16115 32259 16111 32260 16115 32260 16030 32260 16116 32261 16115 32261 16118 32261 4781 32262 16116 32262 16117 32262 16117 32263 16116 32263 16118 32263 16117 32264 16118 32264 16133 32264 16133 32265 16118 32265 16119 32265 16133 32266 16119 32266 16120 32266 16120 32267 16119 32267 16121 32267 16120 32268 16121 32268 16122 32268 16122 32269 16121 32269 16123 32269 16139 32270 16129 32270 16140 32270 16125 32271 16139 32271 16124 32271 16122 32272 16125 32272 16135 32272 14615 32273 14616 32273 16037 32273 16141 32274 16140 32274 16126 32274 4599 32275 16126 32275 16127 32275 16127 32276 16126 32276 16140 32276 16127 32277 16140 32277 16128 32277 16128 32278 16140 32278 16129 32278 16128 32279 16129 32279 14414 32279 16662 32280 16130 32280 16131 32280 16131 32281 16130 32281 16141 32281 16131 32282 16141 32282 16661 32282 16661 32283 16141 32283 16126 32283 16134 32284 16138 32284 16040 32284 16122 32285 16135 32285 16120 32285 16120 32286 16135 32286 16132 32286 16120 32287 16132 32287 16133 32287 16133 32288 16132 32288 16134 32288 16133 32289 16134 32289 16117 32289 16117 32290 16134 32290 16040 32290 16117 32291 16040 32291 4781 32291 16142 32292 16038 32292 16137 32292 16125 32293 16124 32293 16135 32293 16135 32294 16124 32294 16136 32294 16135 32295 16136 32295 16132 32295 16132 32296 16136 32296 16142 32296 16132 32297 16142 32297 16134 32297 16134 32298 16142 32298 16137 32298 16134 32299 16137 32299 16138 32299 16143 32300 16130 32300 16037 32300 16037 32301 16130 32301 16662 32301 16037 32302 16662 32302 14615 32302 16139 32303 16140 32303 16124 32303 16124 32304 16140 32304 16141 32304 16124 32305 16141 32305 16136 32305 16136 32306 16141 32306 16130 32306 16136 32307 16130 32307 16142 32307 16142 32308 16130 32308 16143 32308 16142 32309 16143 32309 16038 32309 16564 32310 4711 32310 16167 32310 16603 32311 16604 32311 16148 32311 16159 32312 16593 32312 16144 32312 16144 32313 16593 32313 16603 32313 16145 32314 16586 32314 16160 32314 16160 32315 16586 32315 16585 32315 4744 32316 16587 32316 16145 32316 16551 32317 16553 32317 16166 32317 16166 32318 16553 32318 16146 32318 16166 32319 16146 32319 16147 32319 16154 32320 16546 32320 16547 32320 16603 32321 16148 32321 16144 32321 16144 32322 16148 32322 4767 32322 16144 32323 4767 32323 16158 32323 16158 32324 4767 32324 4768 32324 16158 32325 4768 32325 16156 32325 4768 32326 4770 32326 16156 32326 16156 32327 4770 32327 4771 32327 16156 32328 4771 32328 16149 32328 16149 32329 4771 32329 16150 32329 16149 32330 16150 32330 16151 32330 16150 32331 4773 32331 16151 32331 16151 32332 4773 32332 16152 32332 16151 32333 16152 32333 16153 32333 16153 32334 16152 32334 4776 32334 16153 32335 4776 32335 16154 32335 16154 32336 4776 32336 4778 32336 16154 32337 4778 32337 16546 32337 16547 32338 16551 32338 16154 32338 16154 32339 16551 32339 16166 32339 16154 32340 16166 32340 16153 32340 16153 32341 16166 32341 16165 32341 16153 32342 16165 32342 16151 32342 16151 32343 16165 32343 16164 32343 16151 32344 16164 32344 16149 32344 16149 32345 16164 32345 16155 32345 16149 32346 16155 32346 16156 32346 16156 32347 16155 32347 16157 32347 16156 32348 16157 32348 16158 32348 16158 32349 16157 32349 16161 32349 16158 32350 16161 32350 16144 32350 16144 32351 16161 32351 16160 32351 16144 32352 16160 32352 16159 32352 16159 32353 16160 32353 16585 32353 16145 32354 16160 32354 4744 32354 4744 32355 16160 32355 16161 32355 4744 32356 16161 32356 4745 32356 4745 32357 16161 32357 16157 32357 4745 32358 16157 32358 4746 32358 4746 32359 16157 32359 16155 32359 4746 32360 16155 32360 16162 32360 16162 32361 16155 32361 16164 32361 16162 32362 16164 32362 16163 32362 16163 32363 16164 32363 16165 32363 16163 32364 16165 32364 4748 32364 4748 32365 16165 32365 16166 32365 4748 32366 16166 32366 16167 32366 16167 32367 16166 32367 16147 32367 16167 32368 16147 32368 16564 32368 16532 32369 16168 32369 16185 32369 16173 32370 16579 32370 16199 32370 16575 32371 16172 32371 16169 32371 16170 32372 9534 32372 16171 32372 16170 32373 16171 32373 16172 32373 16575 32374 16169 32374 16578 32374 16173 32375 16199 32375 16581 32375 16174 32376 16521 32376 16175 32376 16175 32377 16521 32377 16201 32377 16537 32378 16184 32378 16183 32378 16581 32379 16199 32379 16176 32379 16176 32380 16199 32380 16178 32380 16176 32381 16178 32381 16177 32381 16177 32382 16178 32382 4769 32382 4769 32383 16178 32383 16180 32383 4769 32384 16180 32384 16179 32384 16179 32385 16180 32385 16181 32385 16179 32386 16181 32386 4772 32386 16172 32387 16171 32387 16169 32387 16169 32388 16171 32388 9553 32388 16169 32389 9553 32389 16192 32389 16192 32390 9553 32390 9552 32390 16192 32391 9552 32391 16191 32391 16191 32392 9552 32392 9543 32392 16191 32393 9543 32393 16189 32393 16189 32394 9543 32394 9542 32394 16189 32395 9542 32395 16188 32395 16188 32396 9542 32396 16182 32396 16188 32397 16182 32397 16186 32397 16186 32398 16182 32398 9539 32398 16186 32399 9539 32399 16183 32399 16183 32400 9539 32400 9568 32400 16183 32401 9568 32401 16537 32401 16184 32402 16532 32402 16183 32402 16183 32403 16532 32403 16185 32403 16183 32404 16185 32404 16186 32404 16186 32405 16185 32405 16187 32405 16186 32406 16187 32406 16188 32406 16188 32407 16187 32407 16196 32407 16188 32408 16196 32408 16189 32408 16189 32409 16196 32409 16190 32409 16189 32410 16190 32410 16191 32410 16191 32411 16190 32411 16198 32411 16191 32412 16198 32412 16192 32412 16192 32413 16198 32413 16193 32413 16192 32414 16193 32414 16169 32414 16169 32415 16193 32415 16194 32415 16169 32416 16194 32416 16578 32416 16168 32417 16174 32417 16185 32417 16185 32418 16174 32418 16175 32418 16185 32419 16175 32419 16187 32419 16187 32420 16175 32420 16195 32420 16187 32421 16195 32421 16196 32421 16196 32422 16195 32422 16197 32422 16196 32423 16197 32423 16190 32423 16190 32424 16197 32424 16181 32424 16190 32425 16181 32425 16198 32425 16198 32426 16181 32426 16180 32426 16198 32427 16180 32427 16193 32427 16193 32428 16180 32428 16178 32428 16193 32429 16178 32429 16194 32429 16194 32430 16178 32430 16199 32430 16194 32431 16199 32431 16578 32431 16578 32432 16199 32432 16579 32432 4772 32433 16181 32433 16200 32433 16200 32434 16181 32434 16197 32434 16200 32435 16197 32435 4774 32435 4774 32436 16197 32436 16195 32436 4774 32437 16195 32437 4775 32437 4775 32438 16195 32438 16175 32438 4775 32439 16175 32439 4777 32439 4777 32440 16175 32440 16201 32440 4777 32441 16201 32441 4779 32441 16503 32442 4727 32442 16212 32442 16653 32443 16647 32443 16215 32443 16202 32444 16203 32444 16206 32444 16647 32445 16646 32445 16215 32445 16215 32446 16646 32446 16204 32446 16215 32447 16204 32447 16206 32447 16206 32448 16204 32448 16205 32448 16206 32449 16205 32449 16202 32449 4710 32450 4709 32450 16650 32450 16217 32451 16511 32451 16207 32451 16217 32452 16207 32452 16216 32452 16216 32453 16207 32453 16208 32453 16216 32454 16208 32454 16211 32454 4782 32455 16209 32455 16217 32455 16217 32456 16209 32456 16210 32456 16217 32457 16210 32457 16511 32457 4710 32458 16216 32458 16212 32458 16212 32459 16216 32459 16211 32459 16212 32460 16211 32460 16503 32460 4783 32461 16206 32461 16213 32461 16213 32462 16206 32462 16203 32462 16213 32463 16203 32463 16214 32463 16650 32464 16653 32464 4710 32464 4710 32465 16653 32465 16215 32465 4710 32466 16215 32466 16216 32466 16216 32467 16215 32467 16206 32467 16216 32468 16206 32468 16217 32468 16217 32469 16206 32469 4783 32469 16217 32470 4783 32470 4782 32470 16232 32471 9531 32471 16230 32471 16232 32472 16233 32472 16618 32472 16618 32473 16218 32473 16232 32473 16232 32474 16218 32474 16219 32474 16232 32475 16219 32475 9531 32475 9531 32476 16219 32476 16620 32476 9531 32477 16620 32477 9536 32477 16220 32478 16221 32478 16223 32478 16223 32479 16221 32479 16608 32479 16608 32480 16610 32480 16223 32480 16223 32481 16610 32481 16222 32481 16223 32482 16222 32482 16233 32482 16233 32483 16222 32483 16619 32483 16233 32484 16619 32484 16618 32484 16231 32485 16224 32485 16234 32485 16234 32486 16224 32486 16225 32486 16234 32487 16225 32487 16226 32487 16490 32488 16227 32488 16229 32488 16229 32489 16227 32489 16482 32489 16229 32490 16482 32490 16231 32490 16231 32491 16482 32491 16481 32491 16231 32492 16481 32492 16224 32492 16228 32493 16490 32493 16230 32493 16230 32494 16490 32494 16229 32494 16230 32495 16229 32495 16232 32495 16232 32496 16229 32496 16231 32496 16232 32497 16231 32497 16233 32497 16233 32498 16231 32498 16234 32498 16233 32499 16234 32499 16223 32499 16223 32500 16234 32500 16226 32500 16223 32501 16226 32501 16220 32501 9499 32502 9497 32502 16235 32502 16235 32503 9497 32503 16259 32503 16235 32504 16259 32504 16236 32504 16245 32505 16239 32505 16246 32505 16246 32506 16239 32506 16236 32506 16246 32507 16236 32507 16237 32507 16237 32508 16236 32508 16259 32508 15811 32509 9499 32509 16238 32509 16238 32510 9499 32510 16235 32510 16238 32511 16235 32511 16266 32511 16266 32512 16235 32512 16236 32512 16266 32513 16236 32513 16261 32513 16261 32514 16236 32514 16239 32514 16261 32515 16239 32515 5404 32515 16240 32516 16294 32516 16243 32516 16242 32517 16240 32517 16247 32517 16241 32518 16242 32518 16248 32518 9525 32519 16241 32519 16256 32519 16240 32520 16243 32520 16247 32520 16247 32521 16243 32521 5321 32521 16247 32522 5321 32522 16250 32522 16250 32523 5321 32523 5320 32523 16250 32524 5320 32524 16251 32524 16251 32525 5320 32525 5264 32525 16251 32526 5264 32526 16244 32526 16244 32527 5264 32527 16245 32527 16244 32528 16245 32528 16246 32528 16242 32529 16247 32529 16248 32529 16248 32530 16247 32530 16250 32530 16248 32531 16250 32531 16249 32531 16249 32532 16250 32532 16251 32532 16249 32533 16251 32533 16255 32533 16255 32534 16251 32534 16244 32534 16255 32535 16244 32535 16252 32535 16252 32536 16244 32536 16246 32536 16252 32537 16246 32537 16237 32537 16241 32538 16248 32538 16256 32538 16256 32539 16248 32539 16249 32539 16256 32540 16249 32540 16253 32540 16253 32541 16249 32541 16255 32541 16253 32542 16255 32542 16254 32542 16254 32543 16255 32543 16252 32543 16254 32544 16252 32544 16258 32544 16258 32545 16252 32545 16237 32545 16258 32546 16237 32546 16259 32546 9525 32547 16256 32547 15857 32547 15857 32548 16256 32548 16253 32548 15857 32549 16253 32549 15852 32549 15852 32550 16253 32550 16254 32550 15852 32551 16254 32551 16257 32551 16257 32552 16254 32552 16258 32552 16257 32553 16258 32553 16260 32553 16260 32554 16258 32554 16259 32554 16260 32555 16259 32555 9497 32555 16261 32556 5404 32556 16262 32556 16266 32557 16261 32557 16267 32557 16238 32558 16266 32558 16271 32558 15811 32559 16238 32559 16277 32559 16261 32560 16262 32560 16267 32560 16267 32561 16262 32561 16263 32561 16267 32562 16263 32562 16268 32562 16268 32563 16263 32563 16265 32563 16268 32564 16265 32564 16264 32564 16264 32565 16265 32565 5363 32565 16264 32566 5363 32566 16269 32566 16269 32567 5363 32567 5362 32567 16269 32568 5362 32568 16301 32568 16266 32569 16267 32569 16271 32569 16271 32570 16267 32570 16268 32570 16271 32571 16268 32571 16272 32571 16272 32572 16268 32572 16264 32572 16272 32573 16264 32573 16274 32573 16274 32574 16264 32574 16269 32574 16274 32575 16269 32575 16270 32575 16270 32576 16269 32576 16301 32576 16270 32577 16301 32577 16299 32577 16238 32578 16271 32578 16277 32578 16277 32579 16271 32579 16272 32579 16277 32580 16272 32580 16273 32580 16273 32581 16272 32581 16274 32581 16273 32582 16274 32582 16278 32582 16278 32583 16274 32583 16270 32583 16278 32584 16270 32584 16275 32584 16275 32585 16270 32585 16299 32585 16275 32586 16299 32586 16297 32586 15811 32587 16277 32587 16276 32587 16276 32588 16277 32588 16273 32588 16276 32589 16273 32589 16279 32589 16279 32590 16273 32590 16278 32590 16279 32591 16278 32591 15818 32591 15818 32592 16278 32592 16275 32592 15818 32593 16275 32593 16280 32593 16280 32594 16275 32594 16297 32594 16280 32595 16297 32595 4718 32595 16284 32596 9537 32596 16281 32596 16281 32597 9537 32597 16354 32597 16281 32598 16354 32598 16286 32598 16286 32599 16354 32599 16353 32599 16286 32600 16353 32600 16282 32600 16282 32601 16353 32601 16339 32601 16282 32602 16339 32602 16288 32602 16288 32603 16339 32603 5461 32603 16289 32604 16284 32604 16283 32604 16283 32605 16284 32605 16281 32605 16283 32606 16281 32606 16285 32606 16285 32607 16281 32607 16286 32607 16285 32608 16286 32608 16287 32608 16287 32609 16286 32609 16282 32609 16287 32610 16282 32610 16292 32610 16292 32611 16282 32611 16288 32611 9526 32612 16289 32612 16290 32612 16290 32613 16289 32613 16283 32613 16290 32614 16283 32614 16291 32614 16291 32615 16283 32615 16285 32615 16291 32616 16285 32616 16293 32616 16293 32617 16285 32617 16287 32617 16293 32618 16287 32618 16295 32618 16295 32619 16287 32619 16292 32619 9525 32620 9526 32620 16241 32620 16241 32621 9526 32621 16290 32621 16241 32622 16290 32622 16242 32622 16242 32623 16290 32623 16291 32623 16242 32624 16291 32624 16240 32624 16240 32625 16291 32625 16293 32625 16240 32626 16293 32626 16294 32626 16294 32627 16293 32627 16295 32627 4741 32628 4718 32628 16296 32628 16296 32629 4718 32629 16297 32629 16296 32630 16297 32630 16298 32630 16298 32631 16297 32631 16299 32631 16298 32632 16299 32632 16300 32632 16300 32633 16299 32633 16301 32633 16300 32634 16301 32634 16302 32634 16302 32635 16301 32635 5362 32635 4708 32636 4741 32636 16303 32636 16303 32637 4741 32637 16296 32637 16303 32638 16296 32638 16304 32638 16304 32639 16296 32639 16298 32639 16304 32640 16298 32640 16307 32640 16307 32641 16298 32641 16300 32641 16307 32642 16300 32642 16308 32642 16308 32643 16300 32643 16302 32643 4707 32644 4708 32644 16305 32644 16305 32645 4708 32645 16303 32645 16305 32646 16303 32646 16306 32646 16306 32647 16303 32647 16304 32647 16306 32648 16304 32648 16366 32648 16366 32649 16304 32649 16307 32649 16366 32650 16307 32650 5364 32650 5364 32651 16307 32651 16308 32651 5461 32652 16339 32652 16309 32652 5453 32653 16311 32653 16312 32653 16325 32654 16340 32654 16324 32654 16310 32655 16355 32655 16340 32655 9530 32656 9547 32656 16355 32656 16311 32657 5454 32657 16312 32657 16312 32658 5454 32658 16313 32658 16312 32659 16313 32659 16314 32659 16314 32660 16313 32660 16315 32660 16315 32661 16316 32661 16314 32661 16314 32662 16316 32662 16317 32662 16314 32663 16317 32663 16318 32663 16318 32664 16317 32664 5457 32664 16318 32665 5457 32665 16328 32665 16328 32666 5457 32666 5456 32666 16328 32667 5456 32667 16329 32667 16329 32668 5456 32668 5458 32668 16329 32669 5458 32669 16330 32669 5458 32670 5459 32670 16330 32670 16330 32671 5459 32671 5463 32671 16330 32672 5463 32672 16331 32672 16331 32673 5463 32673 16319 32673 16331 32674 16319 32674 16333 32674 16333 32675 16319 32675 16320 32675 16333 32676 16320 32676 16334 32676 16334 32677 16320 32677 16321 32677 16334 32678 16321 32678 16336 32678 16336 32679 16321 32679 16322 32679 16336 32680 16322 32680 16337 32680 16337 32681 16322 32681 5465 32681 16337 32682 5465 32682 16309 32682 16309 32683 5465 32683 16323 32683 16309 32684 16323 32684 5461 32684 5445 32685 5453 32685 16324 32685 16324 32686 5453 32686 16312 32686 16324 32687 16312 32687 16325 32687 16325 32688 16312 32688 16314 32688 16325 32689 16314 32689 16341 32689 16341 32690 16314 32690 16318 32690 16341 32691 16318 32691 16326 32691 16326 32692 16318 32692 16328 32692 16326 32693 16328 32693 16327 32693 16327 32694 16328 32694 16329 32694 16327 32695 16329 32695 16344 32695 16344 32696 16329 32696 16330 32696 16344 32697 16330 32697 16345 32697 16345 32698 16330 32698 16331 32698 16345 32699 16331 32699 16332 32699 16332 32700 16331 32700 16333 32700 16332 32701 16333 32701 16348 32701 16348 32702 16333 32702 16334 32702 16348 32703 16334 32703 16335 32703 16335 32704 16334 32704 16336 32704 16335 32705 16336 32705 16338 32705 16338 32706 16336 32706 16337 32706 16338 32707 16337 32707 16349 32707 16349 32708 16337 32708 16309 32708 16349 32709 16309 32709 16351 32709 16351 32710 16309 32710 16339 32710 16351 32711 16339 32711 16353 32711 16340 32712 16325 32712 16310 32712 16310 32713 16325 32713 16341 32713 16310 32714 16341 32714 16342 32714 16342 32715 16341 32715 16326 32715 16342 32716 16326 32716 16356 32716 16356 32717 16326 32717 16327 32717 16356 32718 16327 32718 16343 32718 16343 32719 16327 32719 16344 32719 16343 32720 16344 32720 16358 32720 16358 32721 16344 32721 16345 32721 16358 32722 16345 32722 16346 32722 16346 32723 16345 32723 16332 32723 16346 32724 16332 32724 16347 32724 16347 32725 16332 32725 16348 32725 16347 32726 16348 32726 16360 32726 16360 32727 16348 32727 16335 32727 16360 32728 16335 32728 16361 32728 16361 32729 16335 32729 16338 32729 16361 32730 16338 32730 16362 32730 16362 32731 16338 32731 16349 32731 16362 32732 16349 32732 16350 32732 16350 32733 16349 32733 16351 32733 16350 32734 16351 32734 16352 32734 16352 32735 16351 32735 16353 32735 16352 32736 16353 32736 16354 32736 16355 32737 16310 32737 9530 32737 9530 32738 16310 32738 16342 32738 9530 32739 16342 32739 9565 32739 9565 32740 16342 32740 16356 32740 9565 32741 16356 32741 16357 32741 16357 32742 16356 32742 16343 32742 16357 32743 16343 32743 9564 32743 9564 32744 16343 32744 16358 32744 9564 32745 16358 32745 16359 32745 16359 32746 16358 32746 16346 32746 16359 32747 16346 32747 9562 32747 9562 32748 16346 32748 16347 32748 9562 32749 16347 32749 9554 32749 9554 32750 16347 32750 16360 32750 9554 32751 16360 32751 9551 32751 9551 32752 16360 32752 16361 32752 9551 32753 16361 32753 9544 32753 9544 32754 16361 32754 16362 32754 9544 32755 16362 32755 9541 32755 9541 32756 16362 32756 16350 32756 9541 32757 16350 32757 9540 32757 9540 32758 16350 32758 16352 32758 9540 32759 16352 32759 9538 32759 9538 32760 16352 32760 16354 32760 9538 32761 16354 32761 9537 32761 6905 32762 16419 32762 16365 32762 16363 32763 16390 32763 4726 32763 16381 32764 16364 32764 16390 32764 16379 32765 6905 32765 16380 32765 16380 32766 6905 32766 16365 32766 16380 32767 16365 32767 16364 32767 16366 32768 5364 32768 6888 32768 16366 32769 6888 32769 16367 32769 16367 32770 6888 32770 16368 32770 16367 32771 16368 32771 16369 32771 16368 32772 6890 32772 16369 32772 16369 32773 6890 32773 6891 32773 16369 32774 6891 32774 16389 32774 16389 32775 6891 32775 16370 32775 16389 32776 16370 32776 16388 32776 16388 32777 16370 32777 6895 32777 16388 32778 6895 32778 16371 32778 16371 32779 6895 32779 6892 32779 16371 32780 6892 32780 16372 32780 16373 32781 16384 32781 16374 32781 16374 32782 16384 32782 16385 32782 16374 32783 16385 32783 6900 32783 6900 32784 16385 32784 16375 32784 6900 32785 16375 32785 6898 32785 6898 32786 16375 32786 16376 32786 6898 32787 16376 32787 16377 32787 16377 32788 16376 32788 16372 32788 16377 32789 16372 32789 6896 32789 6896 32790 16372 32790 6892 32790 16373 32791 16378 32791 16384 32791 16384 32792 16378 32792 6902 32792 16384 32793 6902 32793 16380 32793 16380 32794 6902 32794 6903 32794 16380 32795 6903 32795 16379 32795 16364 32796 16381 32796 16380 32796 16380 32797 16381 32797 16382 32797 16380 32798 16382 32798 16384 32798 16384 32799 16382 32799 16383 32799 16384 32800 16383 32800 16385 32800 16385 32801 16383 32801 16386 32801 16385 32802 16386 32802 16375 32802 16375 32803 16386 32803 16392 32803 16375 32804 16392 32804 16376 32804 16376 32805 16392 32805 16394 32805 16376 32806 16394 32806 16372 32806 16372 32807 16394 32807 16397 32807 16372 32808 16397 32808 16371 32808 16371 32809 16397 32809 16387 32809 16371 32810 16387 32810 16388 32810 16388 32811 16387 32811 16400 32811 16388 32812 16400 32812 16389 32812 16389 32813 16400 32813 16402 32813 16389 32814 16402 32814 16369 32814 16369 32815 16402 32815 16403 32815 16369 32816 16403 32816 16367 32816 16367 32817 16403 32817 16306 32817 16367 32818 16306 32818 16366 32818 16390 32819 16363 32819 16381 32819 16381 32820 16363 32820 16405 32820 16381 32821 16405 32821 16382 32821 16382 32822 16405 32822 16406 32822 16382 32823 16406 32823 16383 32823 16383 32824 16406 32824 16391 32824 16383 32825 16391 32825 16386 32825 16386 32826 16391 32826 16393 32826 16386 32827 16393 32827 16392 32827 16392 32828 16393 32828 16395 32828 16392 32829 16395 32829 16394 32829 16394 32830 16395 32830 16396 32830 16394 32831 16396 32831 16397 32831 16397 32832 16396 32832 16398 32832 16397 32833 16398 32833 16387 32833 16387 32834 16398 32834 16399 32834 16387 32835 16399 32835 16400 32835 16400 32836 16399 32836 16410 32836 16400 32837 16410 32837 16402 32837 16402 32838 16410 32838 16401 32838 16402 32839 16401 32839 16403 32839 16403 32840 16401 32840 16305 32840 16403 32841 16305 32841 16306 32841 4726 32842 16404 32842 16363 32842 16363 32843 16404 32843 4714 32843 16363 32844 4714 32844 16405 32844 16405 32845 4714 32845 4715 32845 16405 32846 4715 32846 16406 32846 16406 32847 4715 32847 16407 32847 16406 32848 16407 32848 16391 32848 16391 32849 16407 32849 4742 32849 16391 32850 4742 32850 16393 32850 16393 32851 4742 32851 4743 32851 16393 32852 4743 32852 16395 32852 16395 32853 4743 32853 16408 32853 16395 32854 16408 32854 16396 32854 16396 32855 16408 32855 4747 32855 16396 32856 4747 32856 16398 32856 16398 32857 4747 32857 16409 32857 16398 32858 16409 32858 16399 32858 16399 32859 16409 32859 16411 32859 16399 32860 16411 32860 16410 32860 16410 32861 16411 32861 4749 32861 16410 32862 4749 32862 16401 32862 16401 32863 4749 32863 4707 32863 16401 32864 4707 32864 16305 32864 5446 32865 5445 32865 16324 32865 16412 32866 16413 32866 16417 32866 16417 32867 16413 32867 16429 32867 16417 32868 16429 32868 16418 32868 16418 32869 16429 32869 16414 32869 16418 32870 16414 32870 16415 32870 16415 32871 16414 32871 16416 32871 9547 32872 16412 32872 16355 32872 16355 32873 16412 32873 16417 32873 16355 32874 16417 32874 16340 32874 16340 32875 16417 32875 16418 32875 16340 32876 16418 32876 16324 32876 16324 32877 16418 32877 16415 32877 16324 32878 16415 32878 5446 32878 5446 32879 16415 32879 16416 32879 5446 32880 16416 32880 5448 32880 16419 32881 16420 32881 16421 32881 4723 32882 4726 32882 16423 32882 16423 32883 4726 32883 16390 32883 16423 32884 16390 32884 16424 32884 16424 32885 16390 32885 16364 32885 16424 32886 16364 32886 16421 32886 16421 32887 16364 32887 16365 32887 16421 32888 16365 32888 16419 32888 16460 32889 4723 32889 16422 32889 16422 32890 4723 32890 16423 32890 16422 32891 16423 32891 16463 32891 16463 32892 16423 32892 16424 32892 16463 32893 16424 32893 16473 32893 16473 32894 16424 32894 16421 32894 16473 32895 16421 32895 16474 32895 16474 32896 16421 32896 16420 32896 16443 32897 16425 32897 16426 32897 16427 32898 16442 32898 16438 32898 16429 32899 16413 32899 16428 32899 16414 32900 16429 32900 16430 32900 16416 32901 16414 32901 16435 32901 5448 32902 16416 32902 16444 32902 16429 32903 16428 32903 16430 32903 16430 32904 16428 32904 15898 32904 16430 32905 15898 32905 16431 32905 15898 32906 16432 32906 16431 32906 16431 32907 16432 32907 15899 32907 16431 32908 15899 32908 16436 32908 16436 32909 15899 32909 16433 32909 16436 32910 16433 32910 16437 32910 16437 32911 16433 32911 15902 32911 16437 32912 15902 32912 16434 32912 16414 32913 16430 32913 16435 32913 16435 32914 16430 32914 16431 32914 16435 32915 16431 32915 16439 32915 16439 32916 16431 32916 16436 32916 16439 32917 16436 32917 16440 32917 16440 32918 16436 32918 16437 32918 16440 32919 16437 32919 16438 32919 16438 32920 16437 32920 16434 32920 16438 32921 16434 32921 16427 32921 16416 32922 16435 32922 16444 32922 16444 32923 16435 32923 16439 32923 16444 32924 16439 32924 16446 32924 16446 32925 16439 32925 16440 32925 16446 32926 16440 32926 16441 32926 16441 32927 16440 32927 16438 32927 16441 32928 16438 32928 16426 32928 16426 32929 16438 32929 16442 32929 16426 32930 16442 32930 16443 32930 5448 32931 16444 32931 16445 32931 16445 32932 16444 32932 16446 32932 16445 32933 16446 32933 16447 32933 16447 32934 16446 32934 16441 32934 16447 32935 16441 32935 16448 32935 16448 32936 16441 32936 16426 32936 16448 32937 16426 32937 5450 32937 5450 32938 16426 32938 16425 32938 5450 32939 16425 32939 16449 32939 16479 32940 16480 32940 16455 32940 16480 32941 16450 32941 16454 32941 16451 32942 16453 32942 16452 32942 16452 32943 16453 32943 16479 32943 16464 32944 16476 32944 16451 32944 16476 32945 16464 32945 6884 32945 16480 32946 16454 32946 16455 32946 16455 32947 16454 32947 16456 32947 16455 32948 16456 32948 16457 32948 16457 32949 16456 32949 15896 32949 16457 32950 15896 32950 16461 32950 16461 32951 15896 32951 16458 32951 16461 32952 16458 32952 16459 32952 16459 32953 16458 32953 16460 32953 16459 32954 16460 32954 16422 32954 16479 32955 16455 32955 16452 32955 16452 32956 16455 32956 16457 32956 16452 32957 16457 32957 16465 32957 16465 32958 16457 32958 16461 32958 16465 32959 16461 32959 16466 32959 16466 32960 16461 32960 16459 32960 16466 32961 16459 32961 16462 32961 16462 32962 16459 32962 16422 32962 16462 32963 16422 32963 16463 32963 16451 32964 16452 32964 16464 32964 16464 32965 16452 32965 16465 32965 16464 32966 16465 32966 16469 32966 16469 32967 16465 32967 16466 32967 16469 32968 16466 32968 16467 32968 16467 32969 16466 32969 16462 32969 16467 32970 16462 32970 16471 32970 16471 32971 16462 32971 16463 32971 16471 32972 16463 32972 16473 32972 6884 32973 16464 32973 16468 32973 16468 32974 16464 32974 16469 32974 16468 32975 16469 32975 16470 32975 16470 32976 16469 32976 16467 32976 16470 32977 16467 32977 6885 32977 6885 32978 16467 32978 16471 32978 6885 32979 16471 32979 16472 32979 16472 32980 16471 32980 16473 32980 16472 32981 16473 32981 16474 32981 16449 32982 16425 32982 16475 32982 16475 32983 16425 32983 16477 32983 16425 32984 16443 32984 16477 32984 16477 32985 16443 32985 16442 32985 16477 32986 16442 32986 16478 32986 15902 32987 9524 32987 16434 32987 16434 32988 9524 32988 16478 32988 16434 32989 16478 32989 16427 32989 16427 32990 16478 32990 16442 32990 6884 32991 16475 32991 16476 32991 16476 32992 16475 32992 16477 32992 16476 32993 16477 32993 16451 32993 16451 32994 16477 32994 16453 32994 16453 32995 16477 32995 16478 32995 16453 32996 16478 32996 16479 32996 16479 32997 16478 32997 16480 32997 16480 32998 16478 32998 9524 32998 16480 32999 9524 32999 16450 32999 16493 33000 16481 33000 16482 33000 14648 33001 16483 33001 16495 33001 16484 33002 9556 33002 16485 33002 16485 33003 9556 33003 16486 33003 16485 33004 16486 33004 16494 33004 16494 33005 16486 33005 16487 33005 16494 33006 16487 33006 16488 33006 16494 33007 16493 33007 16485 33007 16485 33008 16493 33008 16482 33008 16485 33009 16482 33009 16484 33009 16484 33010 16482 33010 16227 33010 16484 33011 16227 33011 16489 33011 16489 33012 16227 33012 16490 33012 16489 33013 16490 33013 16491 33013 16491 33014 16490 33014 16228 33014 16224 33015 16481 33015 16492 33015 16492 33016 16481 33016 16493 33016 16492 33017 16493 33017 16496 33017 16496 33018 16493 33018 16494 33018 16496 33019 16494 33019 16495 33019 16495 33020 16494 33020 16488 33020 16495 33021 16488 33021 14648 33021 14648 33022 16488 33022 16487 33022 16225 33023 16224 33023 16500 33023 16500 33024 16224 33024 16492 33024 16500 33025 16492 33025 16499 33025 16499 33026 16492 33026 16496 33026 16499 33027 16496 33027 16497 33027 16497 33028 16496 33028 16495 33028 16497 33029 16495 33029 16498 33029 16498 33030 16495 33030 16483 33030 16498 33031 14650 33031 16514 33031 16498 33032 16514 33032 16497 33032 16497 33033 16514 33033 16516 33033 16497 33034 16516 33034 16499 33034 16499 33035 16516 33035 16517 33035 16499 33036 16517 33036 16500 33036 16500 33037 16517 33037 16209 33037 16500 33038 16209 33038 16225 33038 16511 33039 16210 33039 16501 33039 16211 33040 16208 33040 16508 33040 16504 33041 4753 33041 16503 33041 16503 33042 4753 33042 16502 33042 16503 33043 16502 33043 4727 33043 16503 33044 16211 33044 16504 33044 16504 33045 16211 33045 16508 33045 16504 33046 16508 33046 16505 33046 16505 33047 16508 33047 4737 33047 16513 33048 16506 33048 16507 33048 16507 33049 16506 33049 4737 33049 16208 33050 16207 33050 16508 33050 16508 33051 16207 33051 16510 33051 16508 33052 16510 33052 4737 33052 4737 33053 16510 33053 16509 33053 4737 33054 16509 33054 16507 33054 16207 33055 16511 33055 16510 33055 16510 33056 16511 33056 16501 33056 16510 33057 16501 33057 16509 33057 16509 33058 16501 33058 16512 33058 16509 33059 16512 33059 16507 33059 16507 33060 16512 33060 16515 33060 16507 33061 16515 33061 16513 33061 16513 33062 16515 33062 14651 33062 14650 33063 14651 33063 16514 33063 16514 33064 14651 33064 16515 33064 16514 33065 16515 33065 16516 33065 16516 33066 16515 33066 16512 33066 16516 33067 16512 33067 16517 33067 16517 33068 16512 33068 16501 33068 16517 33069 16501 33069 16209 33069 16209 33070 16501 33070 16210 33070 16540 33071 4779 33071 16201 33071 16538 33072 16540 33072 16522 33072 16539 33073 16538 33073 16526 33073 14624 33074 16539 33074 16528 33074 14624 33075 16528 33075 4650 33075 4650 33076 16528 33076 16529 33076 4650 33077 16529 33077 16518 33077 16518 33078 16529 33078 16519 33078 16518 33079 16519 33079 16520 33079 16540 33080 16201 33080 16522 33080 16522 33081 16201 33081 16521 33081 16522 33082 16521 33082 16523 33082 16523 33083 16521 33083 16174 33083 16523 33084 16174 33084 16524 33084 16524 33085 16174 33085 16168 33085 16524 33086 16168 33086 16525 33086 16539 33087 16526 33087 16528 33087 16528 33088 16526 33088 16527 33088 16528 33089 16527 33089 16529 33089 16529 33090 16527 33090 16530 33090 16529 33091 16530 33091 16519 33091 16519 33092 16530 33092 16531 33092 16519 33093 16531 33093 16536 33093 16168 33094 16532 33094 16525 33094 16525 33095 16532 33095 16184 33095 16525 33096 16184 33096 16537 33096 16533 33097 16536 33097 16537 33097 16537 33098 16536 33098 16531 33098 16533 33099 16534 33099 16536 33099 16536 33100 16534 33100 16535 33100 16536 33101 16535 33101 16519 33101 16519 33102 16535 33102 4646 33102 16519 33103 4646 33103 16520 33103 16537 33104 9568 33104 16533 33104 16538 33105 16522 33105 16526 33105 16526 33106 16522 33106 16523 33106 16526 33107 16523 33107 16527 33107 16527 33108 16523 33108 16524 33108 16527 33109 16524 33109 16530 33109 16530 33110 16524 33110 16525 33110 16530 33111 16525 33111 16531 33111 16531 33112 16525 33112 16537 33112 14624 33113 16543 33113 16542 33113 14624 33114 16542 33114 16539 33114 16539 33115 16542 33115 16544 33115 16539 33116 16544 33116 16538 33116 16538 33117 16544 33117 16541 33117 16538 33118 16541 33118 16540 33118 16540 33119 16541 33119 4778 33119 16540 33120 4778 33120 4779 33120 16542 33121 16543 33121 16548 33121 16544 33122 16542 33122 16545 33122 16541 33123 16544 33123 16557 33123 4778 33124 16541 33124 16558 33124 4778 33125 16558 33125 16546 33125 16546 33126 16558 33126 16552 33126 16546 33127 16552 33127 16547 33127 16542 33128 16548 33128 16545 33128 16545 33129 16548 33129 4656 33129 16545 33130 4656 33130 16549 33130 16549 33131 4656 33131 4654 33131 16549 33132 4654 33132 16550 33132 16550 33133 4654 33133 4652 33133 16550 33134 4652 33134 16562 33134 16547 33135 16552 33135 16551 33135 16551 33136 16552 33136 16554 33136 16551 33137 16554 33137 16553 33137 16553 33138 16554 33138 16560 33138 16553 33139 16560 33139 16146 33139 4652 33140 16555 33140 16562 33140 16562 33141 16555 33141 4651 33141 16562 33142 4651 33142 16556 33142 16541 33143 16557 33143 16558 33143 16558 33144 16557 33144 16561 33144 16558 33145 16561 33145 16552 33145 16552 33146 16561 33146 16559 33146 16552 33147 16559 33147 16554 33147 16554 33148 16559 33148 16563 33148 16554 33149 16563 33149 16560 33149 16560 33150 16563 33150 16564 33150 16560 33151 16564 33151 16147 33151 16560 33152 16147 33152 16146 33152 16544 33153 16545 33153 16557 33153 16557 33154 16545 33154 16549 33154 16557 33155 16549 33155 16561 33155 16561 33156 16549 33156 16550 33156 16561 33157 16550 33157 16559 33157 16559 33158 16550 33158 16562 33158 16559 33159 16562 33159 16563 33159 16563 33160 16562 33160 16556 33160 16563 33161 16556 33161 16564 33161 16564 33162 16556 33162 4711 33162 16565 33163 16566 33163 15915 33163 15915 33164 16566 33164 16567 33164 15915 33165 16567 33165 15913 33165 15913 33166 16567 33166 16568 33166 15913 33167 16568 33167 15912 33167 15912 33168 16568 33168 16569 33168 15912 33169 16569 33169 16570 33169 16570 33170 16569 33170 16571 33170 16570 33171 16571 33171 15910 33171 15910 33172 16571 33172 16572 33172 15910 33173 16572 33173 14638 33173 9534 33174 16170 33174 16565 33174 16565 33175 16170 33175 16574 33175 16565 33176 16574 33176 16566 33176 16566 33177 16574 33177 16576 33177 16566 33178 16576 33178 16567 33178 16567 33179 16576 33179 16577 33179 16567 33180 16577 33180 16568 33180 16568 33181 16577 33181 16573 33181 16568 33182 16573 33182 16569 33182 16569 33183 16573 33183 16580 33183 16569 33184 16580 33184 16571 33184 16571 33185 16580 33185 16582 33185 16571 33186 16582 33186 16572 33186 16170 33187 16172 33187 16574 33187 16574 33188 16172 33188 16575 33188 16574 33189 16575 33189 16576 33189 16576 33190 16575 33190 16578 33190 16576 33191 16578 33191 16577 33191 16577 33192 16578 33192 16579 33192 16577 33193 16579 33193 16573 33193 16573 33194 16579 33194 16173 33194 16573 33195 16173 33195 16580 33195 16580 33196 16173 33196 16581 33196 16580 33197 16581 33197 16582 33197 16604 33198 16599 33198 16581 33198 16581 33199 16599 33199 16582 33199 16599 33200 16598 33200 16582 33200 16582 33201 16598 33201 16583 33201 16582 33202 16583 33202 16572 33202 14636 33203 14638 33203 16584 33203 16584 33204 14638 33204 16572 33204 16584 33205 16572 33205 16596 33205 16596 33206 16572 33206 16583 33206 16600 33207 16601 33207 4729 33207 4729 33208 16601 33208 16591 33208 16592 33209 16585 33209 16586 33209 16587 33210 16588 33210 16145 33210 16145 33211 16588 33211 16589 33211 16145 33212 16589 33212 16586 33212 16586 33213 16589 33213 16590 33213 16586 33214 16590 33214 16592 33214 16592 33215 16590 33215 4732 33215 16592 33216 4732 33216 16591 33216 16591 33217 16601 33217 16592 33217 16592 33218 16601 33218 16594 33218 16592 33219 16594 33219 16585 33219 16603 33220 16593 33220 16594 33220 16594 33221 16593 33221 16159 33221 16594 33222 16159 33222 16585 33222 4728 33223 14634 33223 16595 33223 16595 33224 14634 33224 14636 33224 14636 33225 16584 33225 16595 33225 16595 33226 16584 33226 16596 33226 16595 33227 16596 33227 16597 33227 16597 33228 16596 33228 16583 33228 16597 33229 16583 33229 16602 33229 16602 33230 16583 33230 16598 33230 16602 33231 16598 33231 16599 33231 4729 33232 4728 33232 16600 33232 16600 33233 4728 33233 16595 33233 16600 33234 16595 33234 16601 33234 16601 33235 16595 33235 16597 33235 16601 33236 16597 33236 16594 33236 16594 33237 16597 33237 16602 33237 16594 33238 16602 33238 16603 33238 16603 33239 16602 33239 16599 33239 16603 33240 16599 33240 16604 33240 16721 33241 16605 33241 16606 33241 16721 33242 16606 33242 16722 33242 16722 33243 16606 33243 16607 33243 16722 33244 16607 33244 16714 33244 16714 33245 16607 33245 16775 33245 16714 33246 16775 33246 16709 33246 16610 33247 16608 33247 16612 33247 16612 33248 16608 33248 16609 33248 16612 33249 16609 33249 16613 33249 16613 33250 16609 33250 16631 33250 16613 33251 16631 33251 16614 33251 16614 33252 16631 33252 16632 33252 16614 33253 16632 33253 4621 33253 4621 33254 16632 33254 14611 33254 16222 33255 16610 33255 16611 33255 16611 33256 16610 33256 16612 33256 16611 33257 16612 33257 16616 33257 16616 33258 16612 33258 16613 33258 16616 33259 16613 33259 16615 33259 16615 33260 16613 33260 16614 33260 16615 33261 16614 33261 4622 33261 4622 33262 16614 33262 4621 33262 4622 33263 4623 33263 16615 33263 16615 33264 4623 33264 16627 33264 16615 33265 16627 33265 16616 33265 16616 33266 16627 33266 16617 33266 16616 33267 16617 33267 16611 33267 16611 33268 16617 33268 16629 33268 16611 33269 16629 33269 16222 33269 16218 33270 16618 33270 16629 33270 16629 33271 16618 33271 16619 33271 16629 33272 16619 33272 16222 33272 9536 33273 16620 33273 4627 33273 4627 33274 16620 33274 16622 33274 4627 33275 16622 33275 16625 33275 16625 33276 16622 33276 16628 33276 16625 33277 16628 33277 16624 33277 16620 33278 16621 33278 16622 33278 16622 33279 16621 33279 16630 33279 16622 33280 16630 33280 16628 33280 16623 33281 4624 33281 16624 33281 16624 33282 4624 33282 16626 33282 16624 33283 16626 33283 16625 33283 16625 33284 16626 33284 4627 33284 4623 33285 16623 33285 16627 33285 16627 33286 16623 33286 16624 33286 16627 33287 16624 33287 16617 33287 16617 33288 16624 33288 16628 33288 16617 33289 16628 33289 16629 33289 16629 33290 16628 33290 16630 33290 16629 33291 16630 33291 16218 33291 16218 33292 16630 33292 16621 33292 16218 33293 16621 33293 16219 33293 16219 33294 16621 33294 16620 33294 16608 33295 16214 33295 16635 33295 16608 33296 16635 33296 16609 33296 16609 33297 16635 33297 16634 33297 16609 33298 16634 33298 16631 33298 16631 33299 16634 33299 16633 33299 16631 33300 16633 33300 16632 33300 16632 33301 16633 33301 4618 33301 16632 33302 4618 33302 14611 33302 16205 33303 16204 33303 16654 33303 16636 33304 4618 33304 16637 33304 16637 33305 4618 33305 16633 33305 16637 33306 16633 33306 16640 33306 16640 33307 16633 33307 16634 33307 16640 33308 16634 33308 16641 33308 16641 33309 16634 33309 16635 33309 16641 33310 16635 33310 16203 33310 16203 33311 16635 33311 16214 33311 4619 33312 16636 33312 16638 33312 16638 33313 16636 33313 16637 33313 16638 33314 16637 33314 16642 33314 16642 33315 16637 33315 16640 33315 16642 33316 16640 33316 16639 33316 16639 33317 16640 33317 16641 33317 16639 33318 16641 33318 16202 33318 16202 33319 16641 33319 16203 33319 16202 33320 16205 33320 16639 33320 16639 33321 16205 33321 16654 33321 16639 33322 16654 33322 16642 33322 16642 33323 16654 33323 16643 33323 16642 33324 16643 33324 16638 33324 16638 33325 16643 33325 16644 33325 16638 33326 16644 33326 4619 33326 4615 33327 16645 33327 16644 33327 16644 33328 16645 33328 4620 33328 16644 33329 4620 33329 4619 33329 16648 33330 16646 33330 16647 33330 16648 33331 16647 33331 16649 33331 16650 33332 16652 33332 16649 33332 16649 33333 16652 33333 16655 33333 16649 33334 16655 33334 16648 33334 4709 33335 16658 33335 16650 33335 16650 33336 16658 33336 16651 33336 16650 33337 16651 33337 16652 33337 16652 33338 16651 33338 16656 33338 16652 33339 16656 33339 16655 33339 16647 33340 16653 33340 16649 33340 16649 33341 16653 33341 16650 33341 16204 33342 16646 33342 16654 33342 16654 33343 16646 33343 16648 33343 16654 33344 16648 33344 16643 33344 16643 33345 16648 33345 16655 33345 16643 33346 16655 33346 16644 33346 16644 33347 16655 33347 16656 33347 16644 33348 16656 33348 4615 33348 4615 33349 16656 33349 16651 33349 4615 33350 16651 33350 16657 33350 16657 33351 16651 33351 16658 33351 16659 33352 16788 33352 16791 33352 16659 33353 16791 33353 16687 33353 16687 33354 16791 33354 16792 33354 16687 33355 16792 33355 16689 33355 16689 33356 16792 33356 16660 33356 16689 33357 16660 33357 16691 33357 16691 33358 16660 33358 16794 33358 16691 33359 16794 33359 16692 33359 4599 33360 16663 33360 16126 33360 16126 33361 16663 33361 16661 33361 14615 33362 16662 33362 16663 33362 16663 33363 16662 33363 16131 33363 16663 33364 16131 33364 16661 33364 16664 33365 16666 33365 16665 33365 16665 33366 16666 33366 16667 33366 16667 33367 16668 33367 16665 33367 16665 33368 16668 33368 16669 33368 16665 33369 16669 33369 14619 33369 4657 33370 4653 33370 14622 33370 14622 33371 4653 33371 4655 33371 14622 33372 4655 33372 14623 33372 16670 33373 4649 33373 4592 33373 4592 33374 4649 33374 4647 33374 4592 33375 4647 33375 16671 33375 4643 33376 16673 33376 16672 33376 16672 33377 16673 33377 4640 33377 16672 33378 4640 33378 4638 33378 4635 33379 4637 33379 4573 33379 4573 33380 4637 33380 4632 33380 4573 33381 4632 33381 4629 33381 4608 33382 16674 33382 4602 33382 4602 33383 16674 33383 16675 33383 4602 33384 16675 33384 14610 33384 14612 33385 4617 33385 16676 33385 16676 33386 4617 33386 16677 33386 16676 33387 16677 33387 16678 33387 16697 33388 16659 33388 16687 33388 16679 33389 16693 33389 16685 33389 16695 33390 16694 33390 16684 33390 16680 33391 16695 33391 9566 33391 9566 33392 16695 33392 16684 33392 9566 33393 16684 33393 9567 33393 9567 33394 16684 33394 16686 33394 9567 33395 16686 33395 9558 33395 9558 33396 16686 33396 16682 33396 9558 33397 16682 33397 16683 33397 4492 33398 16681 33398 16682 33398 16682 33399 16681 33399 4495 33399 16682 33400 4495 33400 16683 33400 16694 33401 16679 33401 16684 33401 16684 33402 16679 33402 16685 33402 16684 33403 16685 33403 16686 33403 16686 33404 16685 33404 16688 33404 16686 33405 16688 33405 16682 33405 16682 33406 16688 33406 16690 33406 16682 33407 16690 33407 4492 33407 16693 33408 16697 33408 16685 33408 16685 33409 16697 33409 16687 33409 16685 33410 16687 33410 16688 33410 16688 33411 16687 33411 16689 33411 16688 33412 16689 33412 16690 33412 16690 33413 16689 33413 16691 33413 16690 33414 16691 33414 4492 33414 4492 33415 16691 33415 16692 33415 16693 33416 16679 33416 16699 33416 16694 33417 16695 33417 16708 33417 16695 33418 16680 33418 16701 33418 4789 33419 16659 33419 16696 33419 16696 33420 16659 33420 16697 33420 4789 33421 16696 33421 4787 33421 4787 33422 16696 33422 16698 33422 4787 33423 16698 33423 16700 33423 16713 33424 16711 33424 16707 33424 16707 33425 16711 33425 16698 33425 16707 33426 16698 33426 16699 33426 16699 33427 16698 33427 16696 33427 16699 33428 16696 33428 16693 33428 16693 33429 16696 33429 16697 33429 16700 33430 16698 33430 4785 33430 4785 33431 16698 33431 16711 33431 4785 33432 16711 33432 4784 33432 16695 33433 16701 33433 16708 33433 16708 33434 16701 33434 9563 33434 16708 33435 9563 33435 16706 33435 16706 33436 9563 33436 16703 33436 16706 33437 16703 33437 16702 33437 16702 33438 16703 33438 16704 33438 16702 33439 16704 33439 16705 33439 16705 33440 16716 33440 16702 33440 16702 33441 16716 33441 16713 33441 16702 33442 16713 33442 16706 33442 16706 33443 16713 33443 16707 33443 16706 33444 16707 33444 16708 33444 16708 33445 16707 33445 16699 33445 16708 33446 16699 33446 16694 33446 16694 33447 16699 33447 16679 33447 16709 33448 4784 33448 16710 33448 16710 33449 4784 33449 16711 33449 16710 33450 16711 33450 16715 33450 16715 33451 16711 33451 16713 33451 16715 33452 16713 33452 16712 33452 16712 33453 16713 33453 16716 33453 9528 33454 9529 33454 15904 33454 9527 33455 9528 33455 16719 33455 16717 33456 16716 33456 9527 33456 9527 33457 16716 33457 16705 33457 9527 33458 16705 33458 16704 33458 16718 33459 16714 33459 16709 33459 16709 33460 16710 33460 16718 33460 16718 33461 16710 33461 16715 33461 16718 33462 16715 33462 16717 33462 16717 33463 16715 33463 16712 33463 16717 33464 16712 33464 16716 33464 9527 33465 16719 33465 16717 33465 16717 33466 16719 33466 16720 33466 16717 33467 16720 33467 16718 33467 16718 33468 16720 33468 16722 33468 16718 33469 16722 33469 16714 33469 9528 33470 15904 33470 16719 33470 16719 33471 15904 33471 15908 33471 16719 33472 15908 33472 16720 33472 16720 33473 15908 33473 16721 33473 16720 33474 16721 33474 16722 33474 15911 33475 16723 33475 16734 33475 15914 33476 16724 33476 16725 33476 16726 33477 16734 33477 16727 33477 16727 33478 16734 33478 16728 33478 16728 33479 16734 33479 16723 33479 16728 33480 16723 33480 15909 33480 16729 33481 14628 33481 14383 33481 14383 33482 14628 33482 14633 33482 14383 33483 14633 33483 16730 33483 16730 33484 14633 33484 16735 33484 16730 33485 16735 33485 16731 33485 16731 33486 16735 33486 16733 33486 16731 33487 16733 33487 16732 33487 15914 33488 16725 33488 9535 33488 16732 33489 16733 33489 16726 33489 16726 33490 16733 33490 16725 33490 16726 33491 16725 33491 16734 33491 16734 33492 16725 33492 16724 33492 16734 33493 16724 33493 15911 33493 14633 33494 16738 33494 16735 33494 16735 33495 16738 33495 16739 33495 16735 33496 16739 33496 16733 33496 16733 33497 16739 33497 16736 33497 16733 33498 16736 33498 16725 33498 16725 33499 16736 33499 16737 33499 16725 33500 16737 33500 9535 33500 16738 33501 16756 33501 16755 33501 16738 33502 16755 33502 16739 33502 16739 33503 16755 33503 16754 33503 16739 33504 16754 33504 16736 33504 16736 33505 16754 33505 16752 33505 16736 33506 16752 33506 16737 33506 16737 33507 16752 33507 16740 33507 16737 33508 16740 33508 9535 33508 15905 33509 15903 33509 16750 33509 16741 33510 14639 33510 15907 33510 14632 33511 16742 33511 16743 33511 14632 33512 16743 33512 16744 33512 16744 33513 16743 33513 16745 33513 16744 33514 16745 33514 16746 33514 16746 33515 16745 33515 14641 33515 16746 33516 14641 33516 16748 33516 16748 33517 14641 33517 14643 33517 16748 33518 14643 33518 14642 33518 16741 33519 15907 33519 14642 33519 14642 33520 15907 33520 16747 33520 14642 33521 16747 33521 16748 33521 15905 33522 16750 33522 15906 33522 16747 33523 15906 33523 16748 33523 16748 33524 15906 33524 16750 33524 16748 33525 16750 33525 16746 33525 16746 33526 16750 33526 16751 33526 16746 33527 16751 33527 16744 33527 16744 33528 16751 33528 16753 33528 16744 33529 16753 33529 14632 33529 14632 33530 16753 33530 16749 33530 15903 33531 16740 33531 16750 33531 16750 33532 16740 33532 16752 33532 16750 33533 16752 33533 16751 33533 16751 33534 16752 33534 16754 33534 16751 33535 16754 33535 16753 33535 16753 33536 16754 33536 16755 33536 16753 33537 16755 33537 16749 33537 16749 33538 16755 33538 16756 33538 4730 33539 16771 33539 4716 33539 4716 33540 16771 33540 16758 33540 16771 33541 16757 33541 16758 33541 16758 33542 16757 33542 16770 33542 16758 33543 16770 33543 16759 33543 16605 33544 15729 33544 16766 33544 16766 33545 15729 33545 16759 33545 16766 33546 16759 33546 16760 33546 16760 33547 16759 33547 16770 33547 16757 33548 16771 33548 16768 33548 16764 33549 16765 33549 16761 33549 16762 33550 16763 33550 16764 33550 16606 33551 16605 33551 16766 33551 16763 33552 16775 33552 16764 33552 16764 33553 16775 33553 16607 33553 16764 33554 16607 33554 16765 33554 16769 33555 16779 33555 16762 33555 16607 33556 16606 33556 16765 33556 16765 33557 16606 33557 16766 33557 16765 33558 16766 33558 16761 33558 16761 33559 16766 33559 16760 33559 16761 33560 16760 33560 16770 33560 16772 33561 16779 33561 16767 33561 16767 33562 16779 33562 16769 33562 16767 33563 16769 33563 16768 33563 16762 33564 16764 33564 16769 33564 16769 33565 16764 33565 16761 33565 16769 33566 16761 33566 16768 33566 16768 33567 16761 33567 16770 33567 16768 33568 16770 33568 16757 33568 16771 33569 4730 33569 16768 33569 16768 33570 4730 33570 4731 33570 16768 33571 4731 33571 16767 33571 16767 33572 4731 33572 4758 33572 16767 33573 4758 33573 16772 33573 16772 33574 4758 33574 16786 33574 16779 33575 16772 33575 16784 33575 16763 33576 16762 33576 16777 33576 16789 33577 16788 33577 4788 33577 16796 33578 16789 33578 16773 33578 16789 33579 4788 33579 16773 33579 16773 33580 4788 33580 16774 33580 16773 33581 16774 33581 16780 33581 16775 33582 16763 33582 16776 33582 16776 33583 16763 33583 16777 33583 16776 33584 16777 33584 4786 33584 4786 33585 16777 33585 16780 33585 4786 33586 16780 33586 16778 33586 16778 33587 16780 33587 16774 33587 16762 33588 16779 33588 16777 33588 16777 33589 16779 33589 16784 33589 16777 33590 16784 33590 16780 33590 16780 33591 16784 33591 16781 33591 16780 33592 16781 33592 16773 33592 16773 33593 16781 33593 16782 33593 16773 33594 16782 33594 16796 33594 16796 33595 16782 33595 16783 33595 16783 33596 16782 33596 4754 33596 4754 33597 16782 33597 16781 33597 4754 33598 16781 33598 4755 33598 4755 33599 16781 33599 16784 33599 4755 33600 16784 33600 16785 33600 16785 33601 16784 33601 16772 33601 16785 33602 16772 33602 16786 33602 16787 33603 4501 33603 16795 33603 16788 33604 16789 33604 16791 33604 16791 33605 16789 33605 16790 33605 16791 33606 16790 33606 16792 33606 16792 33607 16790 33607 16793 33607 16792 33608 16793 33608 16660 33608 16660 33609 16793 33609 16795 33609 16660 33610 16795 33610 16794 33610 16794 33611 16795 33611 4501 33611 16789 33612 16796 33612 16790 33612 16790 33613 16796 33613 16797 33613 16790 33614 16797 33614 16793 33614 16793 33615 16797 33615 16799 33615 16793 33616 16799 33616 16795 33616 16795 33617 16799 33617 16798 33617 16795 33618 16798 33618 16787 33618 16787 33619 16798 33619 4498 33619 16796 33620 16783 33620 16797 33620 16797 33621 16783 33621 16800 33621 16797 33622 16800 33622 16799 33622 16799 33623 16800 33623 16801 33623 16799 33624 16801 33624 16798 33624 16798 33625 16801 33625 16802 33625 16798 33626 16802 33626 4498 33626 4498 33627 16802 33627 4738 33627 16805 33628 14646 33628 16803 33628 16803 33629 16804 33629 16805 33629 16805 33630 16804 33630 4499 33630 16805 33631 4499 33631 4474 33631 4471 33632 4481 33632 16805 33632 4471 33633 16805 33633 4474 33633 4496 33634 4494 33634 16806 33634 16806 33635 4494 33635 4493 33635 16806 33636 4493 33636 4491 33636 16837 33637 16862 33637 16807 33637 16807 33638 16862 33638 16863 33638 16807 33639 16863 33639 16808 33639 16808 33640 16863 33640 16809 33640 16808 33641 16809 33641 16810 33641 16810 33642 16809 33642 16864 33642 16810 33643 16864 33643 16908 33643 16908 33644 16864 33644 16812 33644 16908 33645 16812 33645 16811 33645 16811 33646 16812 33646 16813 33646 16811 33647 16813 33647 16911 33647 16911 33648 16813 33648 16866 33648 16911 33649 16866 33649 16912 33649 16912 33650 16866 33650 16814 33650 16912 33651 16814 33651 16815 33651 16815 33652 16814 33652 16816 33652 16815 33653 16816 33653 16914 33653 16914 33654 16816 33654 16817 33654 16914 33655 16817 33655 16916 33655 16916 33656 16817 33656 16818 33656 16916 33657 16818 33657 16819 33657 16819 33658 16818 33658 16820 33658 16819 33659 16820 33659 16821 33659 16821 33660 16820 33660 16822 33660 16821 33661 16822 33661 16823 33661 16823 33662 16822 33662 16870 33662 16823 33663 16870 33663 16824 33663 16824 33664 16870 33664 16873 33664 16824 33665 16873 33665 16825 33665 16825 33666 16873 33666 16827 33666 16825 33667 16827 33667 16826 33667 16826 33668 16827 33668 16829 33668 16826 33669 16829 33669 16828 33669 16828 33670 16829 33670 16830 33670 16828 33671 16830 33671 16921 33671 16921 33672 16830 33672 16878 33672 16921 33673 16878 33673 16831 33673 16831 33674 16878 33674 16879 33674 16831 33675 16879 33675 16832 33675 16832 33676 16879 33676 16833 33676 16832 33677 16833 33677 16834 33677 16834 33678 16833 33678 16835 33678 16834 33679 16835 33679 16924 33679 16924 33680 16835 33680 16881 33680 16924 33681 16881 33681 16925 33681 16925 33682 16881 33682 16836 33682 16925 33683 16836 33683 16837 33683 16837 33684 16836 33684 16862 33684 16949 33685 16838 33685 16950 33685 16950 33686 16838 33686 16839 33686 16950 33687 16839 33687 16840 33687 16840 33688 16839 33688 16991 33688 16840 33689 16991 33689 16952 33689 16952 33690 16991 33690 16841 33690 16952 33691 16841 33691 16953 33691 16953 33692 16841 33692 16842 33692 16953 33693 16842 33693 16954 33693 16954 33694 16842 33694 16843 33694 16954 33695 16843 33695 16844 33695 16844 33696 16843 33696 16994 33696 16844 33697 16994 33697 16845 33697 16845 33698 16994 33698 16996 33698 16845 33699 16996 33699 16846 33699 16846 33700 16996 33700 16998 33700 16846 33701 16998 33701 16847 33701 16847 33702 16998 33702 16999 33702 16847 33703 16999 33703 16848 33703 16848 33704 16999 33704 16849 33704 16848 33705 16849 33705 16955 33705 16955 33706 16849 33706 17002 33706 16955 33707 17002 33707 16956 33707 16956 33708 17002 33708 16850 33708 16956 33709 16850 33709 16957 33709 16957 33710 16850 33710 16851 33710 16957 33711 16851 33711 16958 33711 16958 33712 16851 33712 17004 33712 16958 33713 17004 33713 16852 33713 16852 33714 17004 33714 17005 33714 16852 33715 17005 33715 16960 33715 16960 33716 17005 33716 17007 33716 16960 33717 17007 33717 16961 33717 16961 33718 17007 33718 16854 33718 16961 33719 16854 33719 16853 33719 16853 33720 16854 33720 16855 33720 16853 33721 16855 33721 16963 33721 16963 33722 16855 33722 17010 33722 16963 33723 17010 33723 16965 33723 16965 33724 17010 33724 16856 33724 16965 33725 16856 33725 16858 33725 16858 33726 16856 33726 16857 33726 16858 33727 16857 33727 16859 33727 16859 33728 16857 33728 16861 33728 16859 33729 16861 33729 16860 33729 16860 33730 16861 33730 17013 33730 16860 33731 17013 33731 16949 33731 16949 33732 17013 33732 16838 33732 16836 33733 16884 33733 16862 33733 16862 33734 16884 33734 16885 33734 16862 33735 16885 33735 16863 33735 16863 33736 16885 33736 16886 33736 16863 33737 16886 33737 16809 33737 16809 33738 16886 33738 16888 33738 16809 33739 16888 33739 16864 33739 16864 33740 16888 33740 16890 33740 16864 33741 16890 33741 16812 33741 16812 33742 16890 33742 16865 33742 16812 33743 16865 33743 16813 33743 16813 33744 16865 33744 16891 33744 16813 33745 16891 33745 16866 33745 16866 33746 16891 33746 16867 33746 16866 33747 16867 33747 16814 33747 16814 33748 16867 33748 16868 33748 16814 33749 16868 33749 16816 33749 16816 33750 16868 33750 16896 33750 16816 33751 16896 33751 16817 33751 16817 33752 16896 33752 16897 33752 16817 33753 16897 33753 16818 33753 16818 33754 16897 33754 16898 33754 16818 33755 16898 33755 16820 33755 16820 33756 16898 33756 16869 33756 16820 33757 16869 33757 16822 33757 16822 33758 16869 33758 16871 33758 16822 33759 16871 33759 16870 33759 16870 33760 16871 33760 16872 33760 16870 33761 16872 33761 16873 33761 16873 33762 16872 33762 16874 33762 16873 33763 16874 33763 16827 33763 16827 33764 16874 33764 16875 33764 16827 33765 16875 33765 16829 33765 16829 33766 16875 33766 16876 33766 16829 33767 16876 33767 16830 33767 16830 33768 16876 33768 16877 33768 16830 33769 16877 33769 16878 33769 16878 33770 16877 33770 16901 33770 16878 33771 16901 33771 16879 33771 16879 33772 16901 33772 16903 33772 16879 33773 16903 33773 16833 33773 16833 33774 16903 33774 16904 33774 16833 33775 16904 33775 16835 33775 16835 33776 16904 33776 16880 33776 16835 33777 16880 33777 16881 33777 16881 33778 16880 33778 16882 33778 16881 33779 16882 33779 16836 33779 16836 33780 16882 33780 16884 33780 16882 33781 6123 33781 16884 33781 16884 33782 6123 33782 16883 33782 16884 33783 16883 33783 16885 33783 16885 33784 16883 33784 16887 33784 16885 33785 16887 33785 16886 33785 16886 33786 16887 33786 6141 33786 16886 33787 6141 33787 16888 33787 16888 33788 6141 33788 16889 33788 16888 33789 16889 33789 16890 33789 16890 33790 16889 33790 6144 33790 16890 33791 6144 33791 16865 33791 16865 33792 6144 33792 16892 33792 16865 33793 16892 33793 16891 33793 16891 33794 16892 33794 16893 33794 16891 33795 16893 33795 16867 33795 16867 33796 16893 33796 16894 33796 16867 33797 16894 33797 16868 33797 16868 33798 16894 33798 6139 33798 16868 33799 6139 33799 16896 33799 16896 33800 6139 33800 16895 33800 16896 33801 16895 33801 16897 33801 16897 33802 16895 33802 6136 33802 16897 33803 6136 33803 16898 33803 16898 33804 6136 33804 16899 33804 16898 33805 16899 33805 16869 33805 16869 33806 16899 33806 6120 33806 16869 33807 6120 33807 16871 33807 16871 33808 6120 33808 6119 33808 16871 33809 6119 33809 16872 33809 16872 33810 6119 33810 6118 33810 16872 33811 6118 33811 16874 33811 16874 33812 6118 33812 6135 33812 16874 33813 6135 33813 16875 33813 16875 33814 6135 33814 6134 33814 16875 33815 6134 33815 16876 33815 16876 33816 6134 33816 6133 33816 16876 33817 6133 33817 16877 33817 16877 33818 6133 33818 16900 33818 16877 33819 16900 33819 16901 33819 16901 33820 16900 33820 6131 33820 16901 33821 6131 33821 16903 33821 16903 33822 6131 33822 16902 33822 16903 33823 16902 33823 16904 33823 16904 33824 16902 33824 6130 33824 16904 33825 6130 33825 16880 33825 16880 33826 6130 33826 16905 33826 16880 33827 16905 33827 16882 33827 16882 33828 16905 33828 6123 33828 16926 33829 16925 33829 16928 33829 16928 33830 16925 33830 16837 33830 16928 33831 16837 33831 16906 33831 16906 33832 16837 33832 16807 33832 16906 33833 16807 33833 16907 33833 16907 33834 16807 33834 16808 33834 16907 33835 16808 33835 16929 33835 16929 33836 16808 33836 16810 33836 16929 33837 16810 33837 16931 33837 16931 33838 16810 33838 16908 33838 16931 33839 16908 33839 16932 33839 16932 33840 16908 33840 16811 33840 16932 33841 16811 33841 16909 33841 16909 33842 16811 33842 16911 33842 16909 33843 16911 33843 16910 33843 16910 33844 16911 33844 16912 33844 16910 33845 16912 33845 16913 33845 16913 33846 16912 33846 16815 33846 16913 33847 16815 33847 16935 33847 16935 33848 16815 33848 16914 33848 16935 33849 16914 33849 16915 33849 16915 33850 16914 33850 16916 33850 16915 33851 16916 33851 16917 33851 16917 33852 16916 33852 16819 33852 16917 33853 16819 33853 16918 33853 16918 33854 16819 33854 16821 33854 16918 33855 16821 33855 16937 33855 16937 33856 16821 33856 16823 33856 16937 33857 16823 33857 16919 33857 16919 33858 16823 33858 16824 33858 16919 33859 16824 33859 16939 33859 16939 33860 16824 33860 16825 33860 16939 33861 16825 33861 16920 33861 16920 33862 16825 33862 16826 33862 16920 33863 16826 33863 16942 33863 16942 33864 16826 33864 16828 33864 16942 33865 16828 33865 16944 33865 16944 33866 16828 33866 16921 33866 16944 33867 16921 33867 16945 33867 16945 33868 16921 33868 16831 33868 16945 33869 16831 33869 16922 33869 16922 33870 16831 33870 16832 33870 16922 33871 16832 33871 16946 33871 16946 33872 16832 33872 16834 33872 16946 33873 16834 33873 16923 33873 16923 33874 16834 33874 16924 33874 16923 33875 16924 33875 16926 33875 16926 33876 16924 33876 16925 33876 16947 33877 16926 33877 8234 33877 8234 33878 16926 33878 16928 33878 8234 33879 16928 33879 16927 33879 16927 33880 16928 33880 16906 33880 16927 33881 16906 33881 8233 33881 8233 33882 16906 33882 16907 33882 8233 33883 16907 33883 8237 33883 8237 33884 16907 33884 16929 33884 8237 33885 16929 33885 16930 33885 16930 33886 16929 33886 16931 33886 16930 33887 16931 33887 8240 33887 8240 33888 16931 33888 16932 33888 8240 33889 16932 33889 8241 33889 8241 33890 16932 33890 16909 33890 8241 33891 16909 33891 16933 33891 16933 33892 16909 33892 16910 33892 16933 33893 16910 33893 16934 33893 16934 33894 16910 33894 16913 33894 16934 33895 16913 33895 8242 33895 8242 33896 16913 33896 16935 33896 8242 33897 16935 33897 8243 33897 8243 33898 16935 33898 16915 33898 8243 33899 16915 33899 16936 33899 16936 33900 16915 33900 16917 33900 16936 33901 16917 33901 8227 33901 8227 33902 16917 33902 16918 33902 8227 33903 16918 33903 8230 33903 8230 33904 16918 33904 16937 33904 8230 33905 16937 33905 8232 33905 8232 33906 16937 33906 16919 33906 8232 33907 16919 33907 16938 33907 16938 33908 16919 33908 16939 33908 16938 33909 16939 33909 16940 33909 16940 33910 16939 33910 16920 33910 16940 33911 16920 33911 16941 33911 16941 33912 16920 33912 16942 33912 16941 33913 16942 33913 8235 33913 8235 33914 16942 33914 16944 33914 8235 33915 16944 33915 16943 33915 16943 33916 16944 33916 16945 33916 16943 33917 16945 33917 8236 33917 8236 33918 16945 33918 16922 33918 8236 33919 16922 33919 8228 33919 8228 33920 16922 33920 16946 33920 8228 33921 16946 33921 8226 33921 8226 33922 16946 33922 16923 33922 8226 33923 16923 33923 16947 33923 16947 33924 16923 33924 16926 33924 16967 33925 16860 33925 16968 33925 16968 33926 16860 33926 16949 33926 16968 33927 16949 33927 16948 33927 16948 33928 16949 33928 16950 33928 16948 33929 16950 33929 16951 33929 16951 33930 16950 33930 16840 33930 16951 33931 16840 33931 16969 33931 16969 33932 16840 33932 16952 33932 16969 33933 16952 33933 16970 33933 16970 33934 16952 33934 16953 33934 16970 33935 16953 33935 16971 33935 16971 33936 16953 33936 16954 33936 16971 33937 16954 33937 16972 33937 16972 33938 16954 33938 16844 33938 16972 33939 16844 33939 16973 33939 16973 33940 16844 33940 16845 33940 16973 33941 16845 33941 16974 33941 16974 33942 16845 33942 16846 33942 16974 33943 16846 33943 16976 33943 16976 33944 16846 33944 16847 33944 16976 33945 16847 33945 16978 33945 16978 33946 16847 33946 16848 33946 16978 33947 16848 33947 16979 33947 16979 33948 16848 33948 16955 33948 16979 33949 16955 33949 16980 33949 16980 33950 16955 33950 16956 33950 16980 33951 16956 33951 16981 33951 16981 33952 16956 33952 16957 33952 16981 33953 16957 33953 16959 33953 16959 33954 16957 33954 16958 33954 16959 33955 16958 33955 16982 33955 16982 33956 16958 33956 16852 33956 16982 33957 16852 33957 16983 33957 16983 33958 16852 33958 16960 33958 16983 33959 16960 33959 16984 33959 16984 33960 16960 33960 16961 33960 16984 33961 16961 33961 16962 33961 16962 33962 16961 33962 16853 33962 16962 33963 16853 33963 16985 33963 16985 33964 16853 33964 16963 33964 16985 33965 16963 33965 16964 33965 16964 33966 16963 33966 16965 33966 16964 33967 16965 33967 16966 33967 16966 33968 16965 33968 16858 33968 16966 33969 16858 33969 16988 33969 16988 33970 16858 33970 16859 33970 16988 33971 16859 33971 16967 33971 16967 33972 16859 33972 16860 33972 8262 33973 16967 33973 8266 33973 8266 33974 16967 33974 16968 33974 8266 33975 16968 33975 8267 33975 8267 33976 16968 33976 16948 33976 8267 33977 16948 33977 8268 33977 8268 33978 16948 33978 16951 33978 8268 33979 16951 33979 8269 33979 8269 33980 16951 33980 16969 33980 8269 33981 16969 33981 8264 33981 8264 33982 16969 33982 16970 33982 8264 33983 16970 33983 8265 33983 8265 33984 16970 33984 16971 33984 8265 33985 16971 33985 8260 33985 8260 33986 16971 33986 16972 33986 8260 33987 16972 33987 8261 33987 8261 33988 16972 33988 16973 33988 8261 33989 16973 33989 8258 33989 8258 33990 16973 33990 16974 33990 8258 33991 16974 33991 16975 33991 16975 33992 16974 33992 16976 33992 16975 33993 16976 33993 16977 33993 16977 33994 16976 33994 16978 33994 16977 33995 16978 33995 8256 33995 8256 33996 16978 33996 16979 33996 8256 33997 16979 33997 8251 33997 8251 33998 16979 33998 16980 33998 8251 33999 16980 33999 8252 33999 8252 34000 16980 34000 16981 34000 8252 34001 16981 34001 8253 34001 8253 34002 16981 34002 16959 34002 8253 34003 16959 34003 8254 34003 8254 34004 16959 34004 16982 34004 8254 34005 16982 34005 8248 34005 8248 34006 16982 34006 16983 34006 8248 34007 16983 34007 8249 34007 8249 34008 16983 34008 16984 34008 8249 34009 16984 34009 8250 34009 8250 34010 16984 34010 16962 34010 8250 34011 16962 34011 8247 34011 8247 34012 16962 34012 16985 34012 8247 34013 16985 34013 16986 34013 16986 34014 16985 34014 16964 34014 16986 34015 16964 34015 16987 34015 16987 34016 16964 34016 16966 34016 16987 34017 16966 34017 8246 34017 8246 34018 16966 34018 16988 34018 8246 34019 16988 34019 8262 34019 8262 34020 16988 34020 16967 34020 17013 34021 17015 34021 16838 34021 16838 34022 17015 34022 16989 34022 16838 34023 16989 34023 16839 34023 16839 34024 16989 34024 16990 34024 16839 34025 16990 34025 16991 34025 16991 34026 16990 34026 17018 34026 16991 34027 17018 34027 16841 34027 16841 34028 17018 34028 17019 34028 16841 34029 17019 34029 16842 34029 16842 34030 17019 34030 16992 34030 16842 34031 16992 34031 16843 34031 16843 34032 16992 34032 16993 34032 16843 34033 16993 34033 16994 34033 16994 34034 16993 34034 16995 34034 16994 34035 16995 34035 16996 34035 16996 34036 16995 34036 16997 34036 16996 34037 16997 34037 16998 34037 16998 34038 16997 34038 17023 34038 16998 34039 17023 34039 16999 34039 16999 34040 17023 34040 17000 34040 16999 34041 17000 34041 16849 34041 16849 34042 17000 34042 17001 34042 16849 34043 17001 34043 17002 34043 17002 34044 17001 34044 17024 34044 17002 34045 17024 34045 16850 34045 16850 34046 17024 34046 17003 34046 16850 34047 17003 34047 16851 34047 16851 34048 17003 34048 17026 34048 16851 34049 17026 34049 17004 34049 17004 34050 17026 34050 17006 34050 17004 34051 17006 34051 17005 34051 17005 34052 17006 34052 17029 34052 17005 34053 17029 34053 17007 34053 17007 34054 17029 34054 17008 34054 17007 34055 17008 34055 16854 34055 16854 34056 17008 34056 17009 34056 16854 34057 17009 34057 16855 34057 16855 34058 17009 34058 17011 34058 16855 34059 17011 34059 17010 34059 17010 34060 17011 34060 17033 34060 17010 34061 17033 34061 16856 34061 16856 34062 17033 34062 17035 34062 16856 34063 17035 34063 16857 34063 16857 34064 17035 34064 17012 34064 16857 34065 17012 34065 16861 34065 16861 34066 17012 34066 17014 34066 16861 34067 17014 34067 17013 34067 17013 34068 17014 34068 17015 34068 17014 34069 17038 34069 17015 34069 17015 34070 17038 34070 4855 34070 17015 34071 4855 34071 16989 34071 16989 34072 4855 34072 17016 34072 16989 34073 17016 34073 16990 34073 16990 34074 17016 34074 4853 34074 16990 34075 4853 34075 17018 34075 17018 34076 4853 34076 17017 34076 17018 34077 17017 34077 17019 34077 17019 34078 17017 34078 4851 34078 17019 34079 4851 34079 16992 34079 16992 34080 4851 34080 17020 34080 16992 34081 17020 34081 16993 34081 16993 34082 17020 34082 4849 34082 16993 34083 4849 34083 16995 34083 16995 34084 4849 34084 17021 34084 16995 34085 17021 34085 16997 34085 16997 34086 17021 34086 4847 34086 16997 34087 4847 34087 17023 34087 17023 34088 4847 34088 17022 34088 17023 34089 17022 34089 17000 34089 17000 34090 17022 34090 4871 34090 17000 34091 4871 34091 17001 34091 17001 34092 4871 34092 4869 34092 17001 34093 4869 34093 17024 34093 17024 34094 4869 34094 17025 34094 17024 34095 17025 34095 17003 34095 17003 34096 17025 34096 4866 34096 17003 34097 4866 34097 17026 34097 17026 34098 4866 34098 17027 34098 17026 34099 17027 34099 17006 34099 17006 34100 17027 34100 17028 34100 17006 34101 17028 34101 17029 34101 17029 34102 17028 34102 4864 34102 17029 34103 4864 34103 17008 34103 17008 34104 4864 34104 17030 34104 17008 34105 17030 34105 17009 34105 17009 34106 17030 34106 17031 34106 17009 34107 17031 34107 17011 34107 17011 34108 17031 34108 17032 34108 17011 34109 17032 34109 17033 34109 17033 34110 17032 34110 17034 34110 17033 34111 17034 34111 17035 34111 17035 34112 17034 34112 17036 34112 17035 34113 17036 34113 17012 34113 17012 34114 17036 34114 17037 34114 17012 34115 17037 34115 17014 34115 17014 34116 17037 34116 17038 34116 17047 34117 17039 34117 8884 34117 8884 34118 17039 34118 4551 34118 8884 34119 4551 34119 8883 34119 8883 34120 4551 34120 4553 34120 8883 34121 4553 34121 8895 34121 8895 34122 4553 34122 4555 34122 8895 34123 4555 34123 8893 34123 8893 34124 4555 34124 17040 34124 8893 34125 17040 34125 8892 34125 8892 34126 17040 34126 17041 34126 8892 34127 17041 34127 8891 34127 17041 34128 4547 34128 8891 34128 8891 34129 4547 34129 17042 34129 8891 34130 17042 34130 17043 34130 17043 34131 17042 34131 4540 34131 17043 34132 4540 34132 17044 34132 17044 34133 4540 34133 4533 34133 17044 34134 4533 34134 8889 34134 8889 34135 4533 34135 4536 34135 8889 34136 4536 34136 8888 34136 8888 34137 4536 34137 4535 34137 8888 34138 4535 34138 17046 34138 17046 34139 4535 34139 17045 34139 17046 34140 17045 34140 17047 34140 17047 34141 17045 34141 4549 34141 17047 34142 4549 34142 17039 34142 17056 34143 17048 34143 8861 34143 8861 34144 17048 34144 17049 34144 8861 34145 17049 34145 17050 34145 17050 34146 17049 34146 4526 34146 17050 34147 4526 34147 8863 34147 8863 34148 4526 34148 4513 34148 8863 34149 4513 34149 8865 34149 8865 34150 4513 34150 17051 34150 8865 34151 17051 34151 8866 34151 8866 34152 17051 34152 4507 34152 8866 34153 4507 34153 17052 34153 4507 34154 4509 34154 17052 34154 17052 34155 4509 34155 4503 34155 17052 34156 4503 34156 8867 34156 8867 34157 4503 34157 4516 34157 8867 34158 4516 34158 17053 34158 17053 34159 4516 34159 4517 34159 17053 34160 4517 34160 17054 34160 17054 34161 4517 34161 4520 34161 17054 34162 4520 34162 8858 34162 8858 34163 4520 34163 17055 34163 8858 34164 17055 34164 8859 34164 8859 34165 17055 34165 4522 34165 8859 34166 4522 34166 17056 34166 17056 34167 4522 34167 4523 34167 17056 34168 4523 34168 17048 34168 17072 34169 17073 34169 17070 34169 17057 34170 7664 34170 17058 34170 17058 34171 7664 34171 4466 34171 17058 34172 4466 34172 8156 34172 4463 34173 4465 34173 17060 34173 17060 34174 4465 34174 4462 34174 4462 34175 17059 34175 17060 34175 17060 34176 17059 34176 17063 34176 17060 34177 17063 34177 17061 34177 17062 34178 8154 34178 17061 34178 17061 34179 8154 34179 8156 34179 17061 34180 8156 34180 17060 34180 17060 34181 8156 34181 4466 34181 17060 34182 4466 34182 4463 34182 8162 34183 17062 34183 8159 34183 8159 34184 17062 34184 17061 34184 8159 34185 17061 34185 8158 34185 8158 34186 17061 34186 17063 34186 17070 34187 17073 34187 17064 34187 17067 34188 8152 34188 17069 34188 17069 34189 8152 34189 17065 34189 17069 34190 17065 34190 8182 34190 8182 34191 17065 34191 8180 34191 8170 34192 8152 34192 17066 34192 17066 34193 8152 34193 17067 34193 17066 34194 17067 34194 17068 34194 17068 34195 17067 34195 17069 34195 17068 34196 17069 34196 17070 34196 17070 34197 17069 34197 17071 34197 17070 34198 17071 34198 17072 34198 17064 34199 17073 34199 17074 34199 17074 34200 17073 34200 8176 34200 17074 34201 8176 34201 4459 34201 4459 34202 8176 34202 17076 34202 4459 34203 17076 34203 17075 34203 17075 34204 17076 34204 17077 34204 17075 34205 17077 34205 17057 34205 17057 34206 17077 34206 7662 34206 17057 34207 7662 34207 7664 34207 17087 34208 4917 34208 8868 34208 8868 34209 4917 34209 4919 34209 8868 34210 4919 34210 17078 34210 17078 34211 4919 34211 4921 34211 17078 34212 4921 34212 8881 34212 8881 34213 4921 34213 17079 34213 8881 34214 17079 34214 8879 34214 8879 34215 17079 34215 17080 34215 8879 34216 17080 34216 8878 34216 8878 34217 17080 34217 17081 34217 8878 34218 17081 34218 8877 34218 8877 34219 17081 34219 4909 34219 8877 34220 4909 34220 8875 34220 8875 34221 4909 34221 4911 34221 8875 34222 4911 34222 17082 34222 17082 34223 4911 34223 4913 34223 17082 34224 4913 34224 8871 34224 8871 34225 4913 34225 4915 34225 8871 34226 4915 34226 17083 34226 17083 34227 4915 34227 17085 34227 17083 34228 17085 34228 17084 34228 17084 34229 17085 34229 17086 34229 17084 34230 17086 34230 17087 34230 17087 34231 17086 34231 4917 34231 17186 34232 17329 34232 17088 34232 17088 34233 17329 34233 17089 34233 17088 34234 17089 34234 17091 34234 17090 34235 17092 34235 17555 34235 17558 34236 17092 34236 17091 34236 17091 34237 17092 34237 17090 34237 17091 34238 17090 34238 17088 34238 17555 34239 17093 34239 17090 34239 17090 34240 17093 34240 17094 34240 17090 34241 17094 34241 17190 34241 17190 34242 17094 34242 17515 34242 17190 34243 17515 34243 17187 34243 17187 34244 17515 34244 17096 34244 17097 34245 17518 34245 17184 34245 17515 34246 17095 34246 17096 34246 17096 34247 17095 34247 17520 34247 17096 34248 17520 34248 17185 34248 17185 34249 17520 34249 17097 34249 17185 34250 17097 34250 17098 34250 17098 34251 17097 34251 17184 34251 17103 34252 17516 34252 17101 34252 17516 34253 17103 34253 17099 34253 17099 34254 17103 34254 17184 34254 17099 34255 17184 34255 17518 34255 17513 34256 17100 34256 17101 34256 17101 34257 17100 34257 17102 34257 17101 34258 17102 34258 17103 34258 17121 34259 17104 34259 17106 34259 17106 34260 17104 34260 17105 34260 17106 34261 17105 34261 17108 34261 17108 34262 17105 34262 17107 34262 17108 34263 17107 34263 17109 34263 17109 34264 17107 34264 17111 34264 17109 34265 17111 34265 17110 34265 17110 34266 17111 34266 17112 34266 17110 34267 17112 34267 17113 34267 17113 34268 17112 34268 17147 34268 17113 34269 17147 34269 17114 34269 17114 34270 17147 34270 17115 34270 17114 34271 17115 34271 17116 34271 17116 34272 17115 34272 17117 34272 17116 34273 17117 34273 17513 34273 17513 34274 17117 34274 17148 34274 17513 34275 17148 34275 17100 34275 17120 34276 17123 34276 17118 34276 17118 34277 17119 34277 17120 34277 17120 34278 17119 34278 17142 34278 17120 34279 17142 34279 17121 34279 17121 34280 17142 34280 17140 34280 17121 34281 17140 34281 17104 34281 17127 34282 17138 34282 17122 34282 17122 34283 17138 34283 17124 34283 17122 34284 17124 34284 17123 34284 17123 34285 17124 34285 17125 34285 17123 34286 17125 34286 17118 34286 17122 34287 17126 34287 17127 34287 17127 34288 17126 34288 17129 34288 17127 34289 17129 34289 17128 34289 17128 34290 17129 34290 17137 34290 17137 34291 17129 34291 17131 34291 17137 34292 17131 34292 17130 34292 17130 34293 17131 34293 17133 34293 17133 34294 17131 34294 17526 34294 17133 34295 17526 34295 17132 34295 17132 34296 17526 34296 17528 34296 17132 34297 17528 34297 17183 34297 17133 34298 17132 34298 17134 34298 17134 34299 17132 34299 17506 34299 17506 34300 17132 34300 17183 34300 17506 34301 17183 34301 17504 34301 17135 34302 17128 34302 17136 34302 17136 34303 17128 34303 17137 34303 17136 34304 17137 34304 17134 34304 17134 34305 17137 34305 17130 34305 17134 34306 17130 34306 17133 34306 17507 34307 17138 34307 17135 34307 17135 34308 17138 34308 17127 34308 17135 34309 17127 34309 17128 34309 17143 34310 17125 34310 17507 34310 17507 34311 17125 34311 17124 34311 17507 34312 17124 34312 17138 34312 17141 34313 17139 34313 17140 34313 17140 34314 17142 34314 17141 34314 17141 34315 17142 34315 17119 34315 17141 34316 17119 34316 17143 34316 17143 34317 17119 34317 17118 34317 17143 34318 17118 34318 17125 34318 17144 34319 17107 34319 17145 34319 17145 34320 17107 34320 17105 34320 17145 34321 17105 34321 17139 34321 17139 34322 17105 34322 17104 34322 17139 34323 17104 34323 17140 34323 17146 34324 17112 34324 17144 34324 17144 34325 17112 34325 17111 34325 17144 34326 17111 34326 17107 34326 17146 34327 17500 34327 17112 34327 17112 34328 17500 34328 17498 34328 17112 34329 17498 34329 17147 34329 17147 34330 17498 34330 17497 34330 17147 34331 17497 34331 17115 34331 17102 34332 17100 34332 17496 34332 17496 34333 17100 34333 17148 34333 17496 34334 17148 34334 17497 34334 17497 34335 17148 34335 17117 34335 17497 34336 17117 34336 17115 34336 17496 34337 17495 34337 17102 34337 17102 34338 17495 34338 17149 34338 17102 34339 17149 34339 17103 34339 17103 34340 17149 34340 17494 34340 17103 34341 17494 34341 17184 34341 17152 34342 17530 34342 17215 34342 17150 34343 17534 34343 17151 34343 17151 34344 17534 34344 17152 34344 17151 34345 17152 34345 17153 34345 17152 34346 17215 34346 17153 34346 17153 34347 17215 34347 17154 34347 17153 34348 17154 34348 17155 34348 17505 34349 17568 34349 17218 34349 17505 34350 17218 34350 17501 34350 17501 34351 17218 34351 17214 34351 17501 34352 17214 34352 17510 34352 17509 34353 17217 34353 17156 34353 17509 34354 17156 34354 17508 34354 17508 34355 17156 34355 17216 34355 17508 34356 17216 34356 17157 34356 17157 34357 17216 34357 17207 34357 17157 34358 17207 34358 17566 34358 17503 34359 17567 34359 17211 34359 17503 34360 17211 34360 17502 34360 17502 34361 17211 34361 17158 34361 17502 34362 17158 34362 17499 34362 17499 34363 17158 34363 17203 34363 17499 34364 17203 34364 17159 34364 17159 34365 17203 34365 17161 34365 17159 34366 17161 34366 17160 34366 17160 34367 17161 34367 17565 34367 17160 34368 17565 34368 17162 34368 17473 34369 17525 34369 17524 34369 17473 34370 17524 34370 17475 34370 17475 34371 17524 34371 17563 34371 17475 34372 17563 34372 17483 34372 17482 34373 17523 34373 17163 34373 17482 34374 17163 34374 17164 34374 17164 34375 17163 34375 17165 34375 17164 34376 17165 34376 17479 34376 17479 34377 17165 34377 17522 34377 17479 34378 17522 34378 17561 34378 17562 34379 17521 34379 17166 34379 17562 34380 17166 34380 17167 34380 17167 34381 17166 34381 17168 34381 17167 34382 17168 34382 17472 34382 17472 34383 17168 34383 17169 34383 17472 34384 17169 34384 17170 34384 17170 34385 17169 34385 17512 34385 17170 34386 17512 34386 17470 34386 17470 34387 17512 34387 17511 34387 17470 34388 17511 34388 17467 34388 17171 34389 17172 34389 17514 34389 17514 34390 17172 34390 17462 34390 17514 34391 17462 34391 17519 34391 17462 34392 17464 34392 17519 34392 17519 34393 17464 34393 17465 34393 17519 34394 17465 34394 17173 34394 17173 34395 17465 34395 17174 34395 17173 34396 17174 34396 17517 34396 17176 34397 17543 34397 17182 34397 17182 34398 17543 34398 17331 34398 17182 34399 17331 34399 17181 34399 17178 34400 17538 34400 17175 34400 17182 34401 17177 34401 17176 34401 17176 34402 17177 34402 17178 34402 17176 34403 17178 34403 17545 34403 17545 34404 17178 34404 17175 34404 17183 34405 17528 34405 17177 34405 17177 34406 17528 34406 17179 34406 17177 34407 17179 34407 17178 34407 17178 34408 17179 34408 17542 34408 17178 34409 17542 34409 17538 34409 17180 34410 17537 34410 17181 34410 17181 34411 17537 34411 17536 34411 17181 34412 17536 34412 17182 34412 17182 34413 17536 34413 17532 34413 17532 34414 17533 34414 17182 34414 17182 34415 17533 34415 17535 34415 17182 34416 17535 34416 17177 34416 17177 34417 17535 34417 17504 34417 17177 34418 17504 34418 17183 34418 17184 34419 17494 34419 17098 34419 17098 34420 17494 34420 17493 34420 17098 34421 17493 34421 17185 34421 17185 34422 17493 34422 17096 34422 17186 34423 17088 34423 17090 34423 17186 34424 17090 34424 17553 34424 17493 34425 17492 34425 17096 34425 17096 34426 17492 34426 17489 34426 17096 34427 17489 34427 17187 34427 17187 34428 17489 34428 17491 34428 17187 34429 17491 34429 17190 34429 17190 34430 17491 34430 17188 34430 17188 34431 17189 34431 17190 34431 17190 34432 17189 34432 17547 34432 17190 34433 17547 34433 17090 34433 17090 34434 17547 34434 17552 34434 17090 34435 17552 34435 17553 34435 17191 34436 17550 34436 17551 34436 17198 34437 17199 34437 17191 34437 17191 34438 17199 34438 17549 34438 17191 34439 17549 34439 17550 34439 17551 34440 17192 34440 17191 34440 17191 34441 17192 34441 17490 34441 17191 34442 17490 34442 17198 34442 17198 34443 17490 34443 17193 34443 17198 34444 17193 34444 17200 34444 17200 34445 17193 34445 17194 34445 17200 34446 17194 34446 17195 34446 17201 34447 17196 34447 17198 34447 17198 34448 17196 34448 17197 34448 17198 34449 17197 34449 17199 34449 17199 34450 17197 34450 17548 34450 17198 34451 17200 34451 17201 34451 17201 34452 17200 34452 17195 34452 17201 34453 17195 34453 17202 34453 17202 34454 17195 34454 17565 34454 17202 34455 17565 34455 17206 34455 17206 34456 17565 34456 17161 34456 17237 34457 17208 34457 17216 34457 17158 34458 17213 34458 17203 34458 17203 34459 17213 34459 17204 34459 17203 34460 17204 34460 17161 34460 17161 34461 17204 34461 17205 34461 17161 34462 17205 34462 17206 34462 17216 34463 17208 34463 17207 34463 17207 34464 17208 34464 17209 34464 17207 34465 17209 34465 17567 34465 17567 34466 17209 34466 17210 34466 17567 34467 17210 34467 17211 34467 17211 34468 17210 34468 17240 34468 17211 34469 17240 34469 17158 34469 17158 34470 17240 34470 17212 34470 17158 34471 17212 34471 17213 34471 17233 34472 17235 34472 17214 34472 17215 34473 17219 34473 17231 34473 17237 34474 17216 34474 17236 34474 17236 34475 17216 34475 17156 34475 17236 34476 17156 34476 17235 34476 17235 34477 17156 34477 17217 34477 17235 34478 17217 34478 17214 34478 17214 34479 17218 34479 17233 34479 17233 34480 17218 34480 17568 34480 17233 34481 17568 34481 17231 34481 17231 34482 17568 34482 17154 34482 17231 34483 17154 34483 17215 34483 17219 34484 17215 34484 17220 34484 17220 34485 17215 34485 17530 34485 17220 34486 17530 34486 17221 34486 17311 34487 17262 34487 17205 34487 17548 34488 17197 34488 17325 34488 17548 34489 17325 34489 17222 34489 17222 34490 17325 34490 17326 34490 17222 34491 17326 34491 17224 34491 17326 34492 17223 34492 17224 34492 17224 34493 17223 34493 17226 34493 17224 34494 17226 34494 17225 34494 17225 34495 17226 34495 17227 34495 17225 34496 17227 34496 17228 34496 17221 34497 17531 34497 17220 34497 17220 34498 17531 34498 17229 34498 17220 34499 17229 34499 17219 34499 17219 34500 17229 34500 17230 34500 17219 34501 17230 34501 17231 34501 17231 34502 17230 34502 17232 34502 17231 34503 17232 34503 17233 34503 17233 34504 17232 34504 17234 34504 17233 34505 17234 34505 17235 34505 17235 34506 17234 34506 17251 34506 17235 34507 17251 34507 17236 34507 17236 34508 17251 34508 17253 34508 17236 34509 17253 34509 17237 34509 17237 34510 17253 34510 17238 34510 17237 34511 17238 34511 17208 34511 17208 34512 17238 34512 17254 34512 17208 34513 17254 34513 17209 34513 17209 34514 17254 34514 17239 34514 17209 34515 17239 34515 17210 34515 17210 34516 17239 34516 17257 34516 17210 34517 17257 34517 17240 34517 17240 34518 17257 34518 17258 34518 17240 34519 17258 34519 17212 34519 17212 34520 17258 34520 17241 34520 17212 34521 17241 34521 17213 34521 17213 34522 17241 34522 17242 34522 17213 34523 17242 34523 17204 34523 17205 34524 17262 34524 17206 34524 17206 34525 17262 34525 17243 34525 17206 34526 17243 34526 17202 34526 17202 34527 17243 34527 17244 34527 17202 34528 17244 34528 17201 34528 17201 34529 17244 34529 17260 34529 17201 34530 17260 34530 17196 34530 17196 34531 17260 34531 17245 34531 17196 34532 17245 34532 17197 34532 17531 34533 17246 34533 17229 34533 17229 34534 17246 34534 17247 34534 17229 34535 17247 34535 17230 34535 17230 34536 17247 34536 17248 34536 17230 34537 17248 34537 17232 34537 17232 34538 17248 34538 17249 34538 17232 34539 17249 34539 17234 34539 17234 34540 17249 34540 17250 34540 17234 34541 17250 34541 17251 34541 17251 34542 17250 34542 17252 34542 17251 34543 17252 34543 17253 34543 17253 34544 17252 34544 17267 34544 17253 34545 17267 34545 17238 34545 17238 34546 17267 34546 17269 34546 17238 34547 17269 34547 17254 34547 17254 34548 17269 34548 17255 34548 17254 34549 17255 34549 17239 34549 17239 34550 17255 34550 17256 34550 17239 34551 17256 34551 17257 34551 17257 34552 17256 34552 17271 34552 17257 34553 17271 34553 17258 34553 17258 34554 17271 34554 17272 34554 17258 34555 17272 34555 17241 34555 17241 34556 17272 34556 17310 34556 17241 34557 17310 34557 17242 34557 17259 34558 17245 34558 17274 34558 17274 34559 17245 34559 17260 34559 17274 34560 17260 34560 17275 34560 17275 34561 17260 34561 17244 34561 17275 34562 17244 34562 17276 34562 17276 34563 17244 34563 17243 34563 17276 34564 17243 34564 17261 34564 17261 34565 17243 34565 17262 34565 17261 34566 17262 34566 17263 34566 17263 34567 17262 34567 17311 34567 17263 34568 17311 34568 17309 34568 17246 34569 17264 34569 17247 34569 17247 34570 17264 34570 17265 34570 17247 34571 17265 34571 17248 34571 17248 34572 17265 34572 17281 34572 17248 34573 17281 34573 17249 34573 17249 34574 17281 34574 17266 34574 17249 34575 17266 34575 17250 34575 17250 34576 17266 34576 17283 34576 17250 34577 17283 34577 17252 34577 17252 34578 17283 34578 17285 34578 17252 34579 17285 34579 17267 34579 17267 34580 17285 34580 17268 34580 17267 34581 17268 34581 17269 34581 17269 34582 17268 34582 17287 34582 17269 34583 17287 34583 17255 34583 17255 34584 17287 34584 17288 34584 17255 34585 17288 34585 17256 34585 17256 34586 17288 34586 17270 34586 17256 34587 17270 34587 17271 34587 17271 34588 17270 34588 17290 34588 17271 34589 17290 34589 17272 34589 17272 34590 17290 34590 17291 34590 17272 34591 17291 34591 17310 34591 17273 34592 17259 34592 17293 34592 17293 34593 17259 34593 17274 34593 17293 34594 17274 34594 17294 34594 17294 34595 17274 34595 17275 34595 17294 34596 17275 34596 17277 34596 17277 34597 17275 34597 17276 34597 17277 34598 17276 34598 17295 34598 17295 34599 17276 34599 17261 34599 17295 34600 17261 34600 17278 34600 17278 34601 17261 34601 17263 34601 17278 34602 17263 34602 17296 34602 17296 34603 17263 34603 17309 34603 17296 34604 17309 34604 17308 34604 17264 34605 17279 34605 17265 34605 17265 34606 17279 34606 17280 34606 17265 34607 17280 34607 17281 34607 17281 34608 17280 34608 17304 34608 17281 34609 17304 34609 17266 34609 17266 34610 17304 34610 17282 34610 17266 34611 17282 34611 17283 34611 17283 34612 17282 34612 17284 34612 17283 34613 17284 34613 17285 34613 17285 34614 17284 34614 17286 34614 17285 34615 17286 34615 17268 34615 17268 34616 17286 34616 17301 34616 17268 34617 17301 34617 17287 34617 17287 34618 17301 34618 17300 34618 17287 34619 17300 34619 17288 34619 17288 34620 17300 34620 17298 34620 17288 34621 17298 34621 17270 34621 17270 34622 17298 34622 17289 34622 17270 34623 17289 34623 17290 34623 17290 34624 17289 34624 17307 34624 17290 34625 17307 34625 17291 34625 17324 34626 17273 34626 17292 34626 17292 34627 17273 34627 17293 34627 17292 34628 17293 34628 17320 34628 17320 34629 17293 34629 17294 34629 17320 34630 17294 34630 17319 34630 17319 34631 17294 34631 17277 34631 17319 34632 17277 34632 17318 34632 17318 34633 17277 34633 17295 34633 17318 34634 17295 34634 17317 34634 17317 34635 17295 34635 17278 34635 17317 34636 17278 34636 17316 34636 17316 34637 17278 34637 17296 34637 17316 34638 17296 34638 17314 34638 17314 34639 17296 34639 17308 34639 17314 34640 17308 34640 17312 34640 17351 34641 17307 34641 17297 34641 17297 34642 17307 34642 17289 34642 17297 34643 17289 34643 17353 34643 17353 34644 17289 34644 17298 34644 17353 34645 17298 34645 17355 34645 17355 34646 17298 34646 17300 34646 17355 34647 17300 34647 17299 34647 17299 34648 17300 34648 17301 34648 17299 34649 17301 34649 17356 34649 17356 34650 17301 34650 17286 34650 17356 34651 17286 34651 17302 34651 17302 34652 17286 34652 17284 34652 17302 34653 17284 34653 17332 34653 17332 34654 17284 34654 17282 34654 17332 34655 17282 34655 17303 34655 17303 34656 17282 34656 17304 34656 17303 34657 17304 34657 17305 34657 17305 34658 17304 34658 17280 34658 17305 34659 17280 34659 17306 34659 17306 34660 17280 34660 17279 34660 17351 34661 17348 34661 17307 34661 17307 34662 17348 34662 17312 34662 17307 34663 17312 34663 17291 34663 17291 34664 17312 34664 17308 34664 17291 34665 17308 34665 17310 34665 17310 34666 17308 34666 17309 34666 17310 34667 17309 34667 17242 34667 17242 34668 17309 34668 17311 34668 17242 34669 17311 34669 17204 34669 17204 34670 17311 34670 17205 34670 17348 34671 17347 34671 17312 34671 17312 34672 17347 34672 17313 34672 17312 34673 17313 34673 17314 34673 17314 34674 17313 34674 17346 34674 17314 34675 17346 34675 17316 34675 17316 34676 17346 34676 17315 34676 17316 34677 17315 34677 17317 34677 17317 34678 17315 34678 17343 34678 17317 34679 17343 34679 17318 34679 17318 34680 17343 34680 17341 34680 17318 34681 17341 34681 17319 34681 17341 34682 17340 34682 17319 34682 17319 34683 17340 34683 17321 34683 17319 34684 17321 34684 17320 34684 17320 34685 17321 34685 17338 34685 17320 34686 17338 34686 17292 34686 17292 34687 17338 34687 17322 34687 17292 34688 17322 34688 17324 34688 17324 34689 17322 34689 17323 34689 17324 34690 17323 34690 17336 34690 17197 34691 17245 34691 17325 34691 17325 34692 17245 34692 17259 34692 17325 34693 17259 34693 17326 34693 17326 34694 17259 34694 17273 34694 17326 34695 17273 34695 17223 34695 17223 34696 17273 34696 17324 34696 17223 34697 17324 34697 17226 34697 17226 34698 17324 34698 17336 34698 17226 34699 17336 34699 17227 34699 17544 34700 17327 34700 17358 34700 17328 34701 17089 34701 17227 34701 17089 34702 17329 34702 17227 34702 17227 34703 17329 34703 17554 34703 17227 34704 17554 34704 17228 34704 17306 34705 17330 34705 17305 34705 17305 34706 17330 34706 17331 34706 17305 34707 17331 34707 17543 34707 17543 34708 17544 34708 17305 34708 17305 34709 17544 34709 17358 34709 17305 34710 17358 34710 17303 34710 17303 34711 17358 34711 17333 34711 17303 34712 17333 34712 17332 34712 17332 34713 17333 34713 17334 34713 17332 34714 17334 34714 17302 34714 17302 34715 17334 34715 17365 34715 17302 34716 17365 34716 17364 34716 17559 34717 17328 34717 17335 34717 17335 34718 17328 34718 17227 34718 17335 34719 17227 34719 17378 34719 17378 34720 17227 34720 17336 34720 17378 34721 17336 34721 17380 34721 17380 34722 17336 34722 17323 34722 17380 34723 17323 34723 17382 34723 17382 34724 17323 34724 17322 34724 17382 34725 17322 34725 17337 34725 17337 34726 17322 34726 17338 34726 17337 34727 17338 34727 17339 34727 17339 34728 17338 34728 17321 34728 17339 34729 17321 34729 17377 34729 17377 34730 17321 34730 17340 34730 17377 34731 17340 34731 17369 34731 17369 34732 17340 34732 17341 34732 17369 34733 17341 34733 17342 34733 17342 34734 17341 34734 17343 34734 17342 34735 17343 34735 17344 34735 17344 34736 17343 34736 17315 34736 17344 34737 17315 34737 17345 34737 17345 34738 17315 34738 17346 34738 17345 34739 17346 34739 17373 34739 17373 34740 17346 34740 17313 34740 17373 34741 17313 34741 17374 34741 17374 34742 17313 34742 17347 34742 17374 34743 17347 34743 17375 34743 17375 34744 17347 34744 17348 34744 17375 34745 17348 34745 17349 34745 17349 34746 17348 34746 17351 34746 17349 34747 17351 34747 17350 34747 17350 34748 17351 34748 17297 34748 17350 34749 17297 34749 17352 34749 17352 34750 17297 34750 17353 34750 17352 34751 17353 34751 17354 34751 17354 34752 17353 34752 17355 34752 17354 34753 17355 34753 17363 34753 17363 34754 17355 34754 17299 34754 17363 34755 17299 34755 17364 34755 17364 34756 17299 34756 17356 34756 17364 34757 17356 34757 17302 34757 17556 34758 17357 34758 17402 34758 17402 34759 17357 34759 17560 34759 17402 34760 17560 34760 17559 34760 17358 34761 17327 34761 17359 34761 17360 34762 17350 34762 17392 34762 17392 34763 17350 34763 17352 34763 17392 34764 17352 34764 17361 34764 17361 34765 17352 34765 17354 34765 17361 34766 17354 34766 17390 34766 17390 34767 17354 34767 17363 34767 17390 34768 17363 34768 17362 34768 17362 34769 17363 34769 17364 34769 17362 34770 17364 34770 17387 34770 17387 34771 17364 34771 17365 34771 17387 34772 17365 34772 17366 34772 17366 34773 17365 34773 17334 34773 17366 34774 17334 34774 17367 34774 17367 34775 17334 34775 17333 34775 17367 34776 17333 34776 17368 34776 17368 34777 17333 34777 17358 34777 17368 34778 17358 34778 17421 34778 17394 34779 17375 34779 17360 34779 17360 34780 17375 34780 17349 34780 17360 34781 17349 34781 17350 34781 17376 34782 17369 34782 17397 34782 17397 34783 17369 34783 17342 34783 17397 34784 17342 34784 17370 34784 17370 34785 17342 34785 17344 34785 17370 34786 17344 34786 17371 34786 17371 34787 17344 34787 17345 34787 17371 34788 17345 34788 17372 34788 17372 34789 17345 34789 17373 34789 17372 34790 17373 34790 17394 34790 17394 34791 17373 34791 17374 34791 17394 34792 17374 34792 17375 34792 17381 34793 17339 34793 17376 34793 17376 34794 17339 34794 17377 34794 17376 34795 17377 34795 17369 34795 17559 34796 17335 34796 17402 34796 17402 34797 17335 34797 17378 34797 17402 34798 17378 34798 17401 34798 17401 34799 17378 34799 17380 34799 17401 34800 17380 34800 17379 34800 17379 34801 17380 34801 17382 34801 17379 34802 17382 34802 17381 34802 17381 34803 17382 34803 17337 34803 17381 34804 17337 34804 17339 34804 17421 34805 17383 34805 17368 34805 17368 34806 17383 34806 17384 34806 17368 34807 17384 34807 17367 34807 17367 34808 17384 34808 17385 34808 17367 34809 17385 34809 17366 34809 17366 34810 17385 34810 17386 34810 17366 34811 17386 34811 17387 34811 17387 34812 17386 34812 17388 34812 17387 34813 17388 34813 17362 34813 17362 34814 17388 34814 17389 34814 17362 34815 17389 34815 17390 34815 17390 34816 17389 34816 17407 34816 17390 34817 17407 34817 17361 34817 17361 34818 17407 34818 17391 34818 17361 34819 17391 34819 17392 34819 17392 34820 17391 34820 17409 34820 17392 34821 17409 34821 17360 34821 17360 34822 17409 34822 17393 34822 17360 34823 17393 34823 17394 34823 17394 34824 17393 34824 17411 34824 17394 34825 17411 34825 17372 34825 17372 34826 17411 34826 17395 34826 17372 34827 17395 34827 17371 34827 17371 34828 17395 34828 17396 34828 17371 34829 17396 34829 17370 34829 17370 34830 17396 34830 17414 34830 17370 34831 17414 34831 17397 34831 17397 34832 17414 34832 17398 34832 17397 34833 17398 34833 17376 34833 17376 34834 17398 34834 17399 34834 17376 34835 17399 34835 17381 34835 17381 34836 17399 34836 17400 34836 17381 34837 17400 34837 17379 34837 17379 34838 17400 34838 17416 34838 17379 34839 17416 34839 17401 34839 17401 34840 17416 34840 17419 34840 17401 34841 17419 34841 17402 34841 17402 34842 17419 34842 17403 34842 17402 34843 17403 34843 17556 34843 17383 34844 17404 34844 17384 34844 17384 34845 17404 34845 17422 34845 17384 34846 17422 34846 17385 34846 17385 34847 17422 34847 17405 34847 17385 34848 17405 34848 17386 34848 17386 34849 17405 34849 17425 34849 17386 34850 17425 34850 17388 34850 17388 34851 17425 34851 17406 34851 17388 34852 17406 34852 17389 34852 17389 34853 17406 34853 17427 34853 17389 34854 17427 34854 17407 34854 17407 34855 17427 34855 17408 34855 17407 34856 17408 34856 17391 34856 17391 34857 17408 34857 17429 34857 17391 34858 17429 34858 17409 34858 17409 34859 17429 34859 17410 34859 17409 34860 17410 34860 17393 34860 17393 34861 17410 34861 17430 34861 17393 34862 17430 34862 17411 34862 17411 34863 17430 34863 17412 34863 17411 34864 17412 34864 17395 34864 17395 34865 17412 34865 17434 34865 17395 34866 17434 34866 17396 34866 17396 34867 17434 34867 17413 34867 17396 34868 17413 34868 17414 34868 17414 34869 17413 34869 17435 34869 17414 34870 17435 34870 17398 34870 17398 34871 17435 34871 17436 34871 17398 34872 17436 34872 17399 34872 17399 34873 17436 34873 17415 34873 17399 34874 17415 34874 17400 34874 17400 34875 17415 34875 17417 34875 17400 34876 17417 34876 17416 34876 17416 34877 17417 34877 17418 34877 17416 34878 17418 34878 17419 34878 17419 34879 17418 34879 17438 34879 17419 34880 17438 34880 17403 34880 17403 34881 17438 34881 17439 34881 17403 34882 17439 34882 17556 34882 17556 34883 17439 34883 17420 34883 17358 34884 17359 34884 17421 34884 17421 34885 17359 34885 17546 34885 17421 34886 17546 34886 17383 34886 17383 34887 17546 34887 17539 34887 17383 34888 17539 34888 17404 34888 17404 34889 17539 34889 17460 34889 17404 34890 17460 34890 17422 34890 17422 34891 17460 34891 17423 34891 17422 34892 17423 34892 17405 34892 17405 34893 17423 34893 17424 34893 17405 34894 17424 34894 17425 34894 17425 34895 17424 34895 17426 34895 17425 34896 17426 34896 17406 34896 17406 34897 17426 34897 17458 34897 17406 34898 17458 34898 17427 34898 17427 34899 17458 34899 17428 34899 17427 34900 17428 34900 17408 34900 17408 34901 17428 34901 17457 34901 17408 34902 17457 34902 17429 34902 17429 34903 17457 34903 17456 34903 17429 34904 17456 34904 17410 34904 17410 34905 17456 34905 17453 34905 17410 34906 17453 34906 17430 34906 17430 34907 17453 34907 17431 34907 17430 34908 17431 34908 17412 34908 17412 34909 17431 34909 17432 34909 17412 34910 17432 34910 17434 34910 17434 34911 17432 34911 17433 34911 17434 34912 17433 34912 17413 34912 17413 34913 17433 34913 17449 34913 17413 34914 17449 34914 17435 34914 17435 34915 17449 34915 17448 34915 17435 34916 17448 34916 17436 34916 17436 34917 17448 34917 17447 34917 17436 34918 17447 34918 17415 34918 17415 34919 17447 34919 17445 34919 17415 34920 17445 34920 17417 34920 17417 34921 17445 34921 17443 34921 17417 34922 17443 34922 17418 34922 17418 34923 17443 34923 17437 34923 17418 34924 17437 34924 17438 34924 17438 34925 17437 34925 17442 34925 17438 34926 17442 34926 17439 34926 17439 34927 17442 34927 17440 34927 17439 34928 17440 34928 17420 34928 17557 34929 17420 34929 17463 34929 17463 34930 17420 34930 17440 34930 17463 34931 17440 34931 17441 34931 17441 34932 17440 34932 17442 34932 17441 34933 17442 34933 17466 34933 17466 34934 17442 34934 17437 34934 17466 34935 17437 34935 17444 34935 17444 34936 17437 34936 17443 34936 17444 34937 17443 34937 17469 34937 17469 34938 17443 34938 17445 34938 17469 34939 17445 34939 17446 34939 17446 34940 17445 34940 17447 34940 17446 34941 17447 34941 17471 34941 17471 34942 17447 34942 17448 34942 17471 34943 17448 34943 17450 34943 17450 34944 17448 34944 17449 34944 17450 34945 17449 34945 17451 34945 17451 34946 17449 34946 17433 34946 17451 34947 17433 34947 17468 34947 17468 34948 17433 34948 17432 34948 17468 34949 17432 34949 17452 34949 17452 34950 17432 34950 17431 34950 17452 34951 17431 34951 17454 34951 17454 34952 17431 34952 17453 34952 17454 34953 17453 34953 17455 34953 17455 34954 17453 34954 17456 34954 17455 34955 17456 34955 17478 34955 17478 34956 17456 34956 17457 34956 17478 34957 17457 34957 17480 34957 17480 34958 17457 34958 17428 34958 17480 34959 17428 34959 17481 34959 17481 34960 17428 34960 17458 34960 17481 34961 17458 34961 17476 34961 17476 34962 17458 34962 17426 34962 17476 34963 17426 34963 17474 34963 17474 34964 17426 34964 17424 34964 17474 34965 17424 34965 17459 34965 17459 34966 17424 34966 17423 34966 17459 34967 17423 34967 17477 34967 17477 34968 17423 34968 17460 34968 17477 34969 17460 34969 17461 34969 17461 34970 17460 34970 17539 34970 17462 34971 17557 34971 17463 34971 17466 34972 17465 34972 17464 34972 17462 34973 17463 34973 17464 34973 17464 34974 17463 34974 17441 34974 17464 34975 17441 34975 17466 34975 17465 34976 17466 34976 17174 34976 17174 34977 17466 34977 17444 34977 17174 34978 17444 34978 17467 34978 17467 34979 17444 34979 17469 34979 17467 34980 17469 34980 17470 34980 17472 34981 17468 34981 17167 34981 17167 34982 17468 34982 17452 34982 17167 34983 17452 34983 17562 34983 17562 34984 17452 34984 17454 34984 17562 34985 17454 34985 17561 34985 17561 34986 17454 34986 17455 34986 17561 34987 17455 34987 17479 34987 17469 34988 17446 34988 17470 34988 17470 34989 17446 34989 17471 34989 17470 34990 17471 34990 17170 34990 17170 34991 17471 34991 17450 34991 17170 34992 17450 34992 17472 34992 17472 34993 17450 34993 17451 34993 17472 34994 17451 34994 17468 34994 17564 34995 17473 34995 17474 34995 17483 34996 17481 34996 17476 34996 17474 34997 17473 34997 17476 34997 17476 34998 17473 34998 17475 34998 17476 34999 17475 34999 17483 34999 17461 35000 17540 35000 17477 35000 17477 35001 17540 35001 17485 35001 17455 35002 17478 35002 17479 35002 17479 35003 17478 35003 17480 35003 17479 35004 17480 35004 17164 35004 17164 35005 17480 35005 17481 35005 17164 35006 17481 35006 17482 35006 17482 35007 17481 35007 17483 35007 17564 35008 17474 35008 17485 35008 17485 35009 17474 35009 17459 35009 17485 35010 17459 35010 17477 35010 17486 35011 17487 35011 17484 35011 17485 35012 17540 35012 17486 35012 17486 35013 17540 35013 17541 35013 17486 35014 17541 35014 17487 35014 17484 35015 17488 35015 17486 35015 17486 35016 17488 35016 17529 35016 17486 35017 17529 35017 17485 35017 17485 35018 17529 35018 17527 35018 17485 35019 17527 35019 17564 35019 17489 35020 17490 35020 17491 35020 17491 35021 17490 35021 17192 35021 17491 35022 17192 35022 17188 35022 17489 35023 17492 35023 17490 35023 17490 35024 17492 35024 17493 35024 17490 35025 17493 35025 17193 35025 17193 35026 17493 35026 17494 35026 17193 35027 17494 35027 17194 35027 17194 35028 17494 35028 17162 35028 17494 35029 17149 35029 17162 35029 17162 35030 17149 35030 17495 35030 17162 35031 17495 35031 17160 35031 17160 35032 17495 35032 17496 35032 17160 35033 17496 35033 17159 35033 17502 35034 17499 35034 17144 35034 17144 35035 17499 35035 17146 35035 17496 35036 17497 35036 17159 35036 17159 35037 17497 35037 17498 35037 17159 35038 17498 35038 17499 35038 17499 35039 17498 35039 17500 35039 17499 35040 17500 35040 17146 35040 17501 35041 17134 35041 17506 35041 17144 35042 17145 35042 17502 35042 17502 35043 17145 35043 17139 35043 17502 35044 17139 35044 17503 35044 17503 35045 17139 35045 17141 35045 17503 35046 17141 35046 17566 35046 17566 35047 17141 35047 17143 35047 17566 35048 17143 35048 17157 35048 17504 35049 17535 35049 17151 35049 17151 35050 17153 35050 17504 35050 17504 35051 17153 35051 17155 35051 17504 35052 17155 35052 17506 35052 17506 35053 17155 35053 17505 35053 17506 35054 17505 35054 17501 35054 17143 35055 17507 35055 17157 35055 17157 35056 17507 35056 17135 35056 17157 35057 17135 35057 17508 35057 17508 35058 17135 35058 17136 35058 17508 35059 17136 35059 17509 35059 17509 35060 17136 35060 17134 35060 17509 35061 17134 35061 17510 35061 17510 35062 17134 35062 17501 35062 17511 35063 17512 35063 17101 35063 17101 35064 17512 35064 17513 35064 17519 35065 17095 35065 17514 35065 17514 35066 17095 35066 17515 35066 17514 35067 17515 35067 17094 35067 17101 35068 17516 35068 17511 35068 17511 35069 17516 35069 17099 35069 17511 35070 17099 35070 17517 35070 17517 35071 17099 35071 17518 35071 17517 35072 17518 35072 17173 35072 17173 35073 17518 35073 17097 35073 17173 35074 17097 35074 17519 35074 17519 35075 17097 35075 17520 35075 17519 35076 17520 35076 17095 35076 17513 35077 17512 35077 17116 35077 17116 35078 17512 35078 17169 35078 17116 35079 17169 35079 17114 35079 17114 35080 17169 35080 17168 35080 17114 35081 17168 35081 17113 35081 17524 35082 17526 35082 17131 35082 17106 35083 17108 35083 17166 35083 17166 35084 17108 35084 17109 35084 17166 35085 17109 35085 17168 35085 17168 35086 17109 35086 17110 35086 17168 35087 17110 35087 17113 35087 17106 35088 17166 35088 17121 35088 17121 35089 17166 35089 17521 35089 17121 35090 17521 35090 17120 35090 17120 35091 17521 35091 17522 35091 17120 35092 17522 35092 17123 35092 17123 35093 17522 35093 17165 35093 17123 35094 17165 35094 17122 35094 17122 35095 17165 35095 17126 35095 17126 35096 17165 35096 17163 35096 17126 35097 17163 35097 17129 35097 17129 35098 17163 35098 17523 35098 17129 35099 17523 35099 17131 35099 17131 35100 17523 35100 17563 35100 17131 35101 17563 35101 17524 35101 17524 35102 17525 35102 17526 35102 17526 35103 17525 35103 17527 35103 17526 35104 17527 35104 17528 35104 17528 35105 17527 35105 17529 35105 17528 35106 17529 35106 17179 35106 17179 35107 17529 35107 17488 35107 17221 35108 17530 35108 17152 35108 17531 35109 17536 35109 17246 35109 17246 35110 17536 35110 17264 35110 17531 35111 17221 35111 17536 35111 17536 35112 17221 35112 17152 35112 17536 35113 17152 35113 17532 35113 17532 35114 17152 35114 17534 35114 17532 35115 17534 35115 17533 35115 17533 35116 17534 35116 17150 35116 17533 35117 17150 35117 17535 35117 17535 35118 17150 35118 17151 35118 17264 35119 17536 35119 17279 35119 17279 35120 17536 35120 17537 35120 17279 35121 17537 35121 17306 35121 17306 35122 17537 35122 17180 35122 17306 35123 17180 35123 17330 35123 17330 35124 17180 35124 17181 35124 17330 35125 17181 35125 17331 35125 17540 35126 17461 35126 17538 35126 17461 35127 17539 35127 17538 35127 17538 35128 17539 35128 17546 35128 17538 35129 17546 35129 17175 35129 17540 35130 17538 35130 17541 35130 17541 35131 17538 35131 17542 35131 17541 35132 17542 35132 17487 35132 17487 35133 17542 35133 17484 35133 17484 35134 17542 35134 17179 35134 17484 35135 17179 35135 17488 35135 17543 35136 17176 35136 17544 35136 17544 35137 17176 35137 17545 35137 17544 35138 17545 35138 17327 35138 17327 35139 17545 35139 17175 35139 17327 35140 17175 35140 17359 35140 17359 35141 17175 35141 17546 35141 17548 35142 17222 35142 17547 35142 17549 35143 17199 35143 17548 35143 17222 35144 17224 35144 17547 35144 17547 35145 17224 35145 17225 35145 17547 35146 17225 35146 17552 35146 17548 35147 17547 35147 17549 35147 17549 35148 17547 35148 17189 35148 17549 35149 17189 35149 17550 35149 17550 35150 17189 35150 17551 35150 17551 35151 17189 35151 17188 35151 17551 35152 17188 35152 17192 35152 17225 35153 17228 35153 17552 35153 17552 35154 17228 35154 17554 35154 17552 35155 17554 35155 17553 35155 17553 35156 17554 35156 17329 35156 17553 35157 17329 35157 17186 35157 17514 35158 17094 35158 17093 35158 17514 35159 17093 35159 17171 35159 17171 35160 17093 35160 17555 35160 17171 35161 17555 35161 17172 35161 17357 35162 17556 35162 17555 35162 17556 35163 17420 35163 17555 35163 17555 35164 17420 35164 17557 35164 17555 35165 17557 35165 17172 35165 17172 35166 17557 35166 17462 35166 17091 35167 17089 35167 17558 35167 17558 35168 17089 35168 17328 35168 17558 35169 17328 35169 17092 35169 17092 35170 17328 35170 17559 35170 17092 35171 17559 35171 17555 35171 17555 35172 17559 35172 17560 35172 17555 35173 17560 35173 17357 35173 17511 35174 17517 35174 17467 35174 17467 35175 17517 35175 17174 35175 17522 35176 17521 35176 17561 35176 17561 35177 17521 35177 17562 35177 17563 35178 17523 35178 17483 35178 17483 35179 17523 35179 17482 35179 17527 35180 17525 35180 17564 35180 17564 35181 17525 35181 17473 35181 17194 35182 17162 35182 17195 35182 17195 35183 17162 35183 17565 35183 17503 35184 17566 35184 17567 35184 17567 35185 17566 35185 17207 35185 17509 35186 17510 35186 17217 35186 17217 35187 17510 35187 17214 35187 17505 35188 17155 35188 17568 35188 17568 35189 17155 35189 17154 35189

+
+
+
+
+ + + + + + + + + + + + + + +
diff --git a/robots/b1_description/meshes/hip.dae b/robots/b1_description/meshes/hip.dae new file mode 100644 index 0000000..2ce73c1 --- /dev/null +++ b/robots/b1_description/meshes/hip.dae @@ -0,0 +1,63 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + 周四 2月 24 03:21:28 2022 + 周四 2月 24 03:21:28 2022 + + + + + + + + + -0.089947 0.0516717 0.00680662 -0.0886496 0.0540627 0.00226319 -0.0886008 0.0540621 -0.00368173 -0.0888917 0.0534115 0.00563829 -0.0972547 0.0444055 0.00615382 -0.0958382 0.0453563 0.00672059 -0.0993463 0.043398 0.00444869 -0.0976717 0.0442498 0.0050823 -0.0965068 0.0452544 1.80458e-06 -0.0990364 0.043513 -0.00483684 -0.0952385 0.0458242 -0.00684846 -0.0936189 0.0477347 2.94676e-06 -0.094531 0.0464296 -0.006907 -0.0901274 0.0518836 4.55453e-06 -0.0904923 0.0509014 -0.0068995 -0.0921662 0.048827 -0.00690206 -0.0730344 0.0286459 0.0433452 -0.0707255 0.0289214 0.04156 -0.0704241 0.0289142 0.0416848 -0.0709259 0.0288071 0.0446464 -0.0694755 0.0289086 0.04156 -0.0670753 0.028873 0.043619 -0.0692167 0.0289125 0.0413613 -0.0662224 0.0288263 0.0381046 -0.0669774 0.0289324 0.037154 -0.0701005 0.0289922 0.0392274 -0.0707255 0.0289931 0.0393949 -0.0732449 0.029106 0.0376724 -0.0711831 0.0289826 0.0398524 -0.104996 0.0324547 2.44063e-06 -0.104996 0.037213 -0.00127256 -0.104996 0.0362797 -0.00220592 -0.104996 0.0337297 -0.00220592 -0.104996 0.0350047 2.44063e-06 -0.104996 0.037213 0.00127744 -0.104996 0.0337297 0.00221081 -0.104996 0.0362797 0.00221081 -0.104996 0.0290405 -0.0197059 -0.104996 0.0281072 -0.0187726 -0.104996 0.0277655 -0.0174976 -0.104996 0.0325239 -0.0187726 -0.104996 0.0315905 -0.0197059 -0.104996 0.0303155 -0.0174976 -0.104996 0.0303155 -0.0200476 -0.104996 0.0325239 -0.0162226 -0.104996 0.0290405 -0.0152892 -0.104996 0.0315905 -0.0152892 -0.104996 0.0149547 -0.0303084 -0.104996 0.019713 -0.0315834 -0.104996 0.0175047 -0.0303084 -0.104996 0.019713 -0.0290334 -0.104996 4.65996e-06 -0.0349976 -0.104996 0.00127966 -0.0372059 -0.104996 -0.00127034 -0.0372059 -0.104996 0.00127966 -0.0327892 -0.104996 0.00221302 -0.0337226 -0.104996 0.00221302 -0.0362726 -0.104996 -0.00127034 -0.0327892 -0.104996 4.65996e-06 -0.0324476 -0.104996 -0.0187703 -0.0325168 -0.104996 -0.0162203 -0.0281001 -0.104996 -0.0174953 -0.0303084 -0.104996 -0.0149453 -0.0303084 -0.104996 -0.015287 -0.0315834 -0.104996 -0.0174953 -0.0277584 -0.104996 -0.0315812 -0.0197059 -0.104996 -0.0325146 -0.0187726 -0.104996 -0.0325146 -0.0162226 -0.104996 -0.0303062 -0.0174976 -0.104996 -0.0280979 -0.0162226 -0.104996 -0.0277562 -0.0174976 -0.104996 -0.0280979 -0.0187726 -0.104996 -0.0303062 -0.0149476 -0.104996 -0.0372037 -0.00127256 -0.104996 -0.0349953 2.44063e-06 -0.104996 -0.0362703 -0.00220592 -0.104996 -0.0324453 2.44063e-06 -0.104996 -0.0372037 0.00127744 -0.104996 -0.0325146 0.0162274 -0.104996 -0.0328562 0.0175024 -0.104996 -0.0290312 0.0152941 -0.104996 -0.0303062 0.0175024 -0.104996 -0.0280979 0.0187774 -0.104996 -0.0277562 0.0175024 -0.104996 -0.0303062 0.0200524 -0.104996 -0.0290312 0.0197108 -0.104996 -0.0197037 0.0290383 -0.104996 -0.0200453 0.0303133 -0.104996 -0.015287 0.0290383 -0.104996 -0.0174953 0.0277633 -0.104996 -0.0187703 0.028105 -0.104996 -0.0162203 0.0325217 -0.104996 -0.015287 0.0315883 -0.104996 -0.0174953 0.0303133 -0.104996 -0.0174953 0.0328633 -0.104996 -0.00254534 0.0350024 -0.104996 0.00127966 0.0327941 -0.104996 4.65996e-06 0.0350024 -0.104996 4.65996e-06 0.0324524 -0.104996 0.00255466 0.0350024 -0.104996 0.00127966 0.0372108 -0.104996 0.0149547 0.0303133 -0.104996 0.0175047 0.0303133 -0.104996 0.0175047 0.0277633 -0.104996 0.0162297 0.0325217 -0.104996 0.0175047 0.0328633 -0.104996 0.0303155 0.0175024 -0.104996 0.0277655 0.0175024 -0.104996 0.0315905 0.0152941 -0.104996 0.0303155 0.0149524 -0.104996 0.0290405 0.0152941 -0.104996 0.0303155 0.0200524 -0.0967958 -0.0211125 0.0229359 -0.0967958 -0.0194995 0.0228303 -0.0967958 -0.01802 0.0234816 -0.0967958 -0.0129876 0.02734 -0.0967958 -0.0263347 0.0292266 -0.0967958 -0.013157 0.0270537 -0.0967958 -0.0146112 0.0368794 -0.0967958 -0.0128453 0.0343461 -0.0967958 -0.0128453 0.0338683 -0.0967958 -0.0259561 0.0305989 -0.0967958 -0.0125556 0.0324948 -0.0967958 -0.013157 -0.0270488 -0.0967958 -0.0129876 -0.0273351 -0.0967958 -0.0263347 -0.0292217 -0.0967958 -0.0136199 -0.0264153 -0.0967958 -0.0194995 -0.0228254 -0.0967958 -0.0136229 -0.0362371 -0.0967958 -0.0157768 -0.0370313 -0.0967958 -0.0129993 -0.0352399 -0.0967958 -0.0250489 -0.0316911 -0.0967958 -0.0125556 -0.0324899 -0.0967958 -0.0121221 -0.0308449 -0.0967958 -0.01802 -0.0234768 -0.0495892 0.0284676 -0.0614091 -0.0499147 0.0284668 -0.0606172 -0.0493742 0.0287586 -0.0610751 -0.0504023 0.028467 -0.0600459 -0.0497273 0.0287618 -0.0635754 -0.0498725 0.0284703 -0.0632507 -0.052077 0.0284684 -0.064519 -0.0520759 0.0287597 -0.0648159 -0.0507413 0.0287626 -0.0644826 -0.0518089 0.0284691 -0.0645048 -0.0509847 0.0284712 -0.0642732 -0.0522432 0.028468 -0.0645135 -0.0532736 0.0284626 -0.0642208 -0.05388 0.0284612 -0.0637722 -0.0540942 0.0287524 -0.0639873 -0.0541809 0.0284635 -0.0634098 -0.050484 0.0284671 -0.0599777 -0.0512329 0.0284691 -0.0595627 -0.0512592 0.0287608 -0.0592418 -0.0528122 0.0284792 -0.0595272 -0.0539018 0.0287784 -0.0597866 -0.0543086 0.0284893 -0.0607352 -0.0544992 0.0284871 -0.0611719 -0.054908 0.0287731 -0.0616693 -0.0546126 0.0284753 -0.0622392 -0.0544089 0.0284675 -0.0630008 -0.0606922 0.0285179 -0.0498704 -0.0616258 0.0285452 -0.0546058 -0.0619673 0.0288066 -0.0549199 -0.0628059 0.028788 -0.054798 -0.0627849 0.0285181 -0.0544941 -0.0632422 0.0285074 -0.0542871 -0.0635162 0.0285022 -0.0541043 -0.0631757 0.0287799 -0.0546578 -0.0639826 0.0287672 -0.0540984 -0.064285 0.0285783 -0.0510155 -0.0646751 0.0287836 -0.0529676 -0.0644415 0.0285212 -0.0526953 -0.0641756 0.0285036 -0.0533537 -0.0628569 0.0288328 -0.0493865 -0.0632929 0.0288427 -0.0495738 -0.0632422 0.0285761 -0.0498704 -0.0638026 0.028585 -0.0503084 -0.0610048 0.0287928 -0.0494068 -0.0611544 0.0287954 -0.0493578 -0.0611576 0.0285254 -0.0496607 -0.0619672 0.0285433 -0.0495287 -0.0619671 0.0288117 -0.0492406 -0.0619725 0.0285434 -0.0495287 -0.0604316 0.0285147 -0.0500429 -0.0599618 0.0287807 -0.050067 -0.0592636 0.0287821 -0.0512088 -0.0594172 0.0285215 -0.0520787 -0.0596436 0.0285374 -0.0531291 -0.0594269 0.0285244 -0.0523009 -0.0608091 0.0285535 -0.0543506 -0.0601223 0.0285491 -0.0538391 -0.0596176 0.0288123 -0.0536684 -0.0597608 0.0285413 -0.0533571 -0.0647925 0.0288002 0.0524297 -0.0611486 0.0288193 0.0548003 -0.0619681 0.0288066 0.0549247 -0.0619632 0.0285383 0.0546336 -0.0598426 0.0285435 0.0534938 -0.0599565 0.0288181 0.0540839 -0.0604284 0.0285524 0.054117 -0.061002 0.0288205 0.0547513 -0.0606922 0.0285535 0.054292 -0.0611537 0.0285516 0.0545004 -0.0597588 0.0285412 0.0533586 -0.0592748 0.0288017 0.0529811 -0.0594957 0.0285304 0.0527113 -0.0591448 0.0287866 0.051771 -0.0596452 0.0285122 0.0510296 -0.059629 0.0287796 0.0504708 -0.0608121 0.0285196 0.0498102 -0.0606922 0.0285179 0.0498752 -0.062145 0.0288158 0.0492515 -0.0621326 0.0285475 0.049539 -0.0627891 0.0285649 0.0496697 -0.0635197 0.0285816 0.0500607 -0.063974 0.0288532 0.0500841 -0.0643043 0.0285773 0.0510636 -0.0642832 0.0285081 0.0531506 -0.0645059 0.0285344 0.0523233 -0.064635 0.0288419 0.0511193 -0.0631111 0.0285103 0.0543626 -0.0632422 0.0285074 0.054292 -0.0638369 0.0287684 0.054238 -0.0643089 0.0287686 0.053714 -0.050802 0.0284713 0.0641822 -0.0500634 0.0287624 0.0639857 -0.0498686 0.0284703 0.0632488 -0.0492467 0.0287592 0.0616696 -0.0495436 0.0284679 0.0616833 -0.0497825 0.028467 0.0608611 -0.0498619 0.0284669 0.0607105 -0.0502802 0.0284669 0.0601644 -0.0507437 0.0287592 0.0594582 -0.0518042 0.0284718 0.0594385 -0.050802 0.0284677 0.0597655 -0.0531025 0.0287722 0.0593192 -0.0529216 0.0284802 0.0595678 -0.0529001 0.0287706 0.0592494 -0.0520776 0.0284735 0.0594238 -0.0542853 0.0284894 0.0606988 -0.0546098 0.0284751 0.0622693 -0.054627 0.0284785 0.0619738 -0.0549057 0.0287664 0.0623044 -0.0547557 0.0287789 0.061015 -0.0545649 0.028485 0.0614146 -0.0512576 0.0287617 0.0647002 -0.0534231 0.0287538 0.0644882 -0.0544243 0.0287546 0.0635949 -0.0538702 0.0284611 0.0637868 -0.0542853 0.028465 0.0632488 -0.0707255 0.0263547 -0.03939 -0.0707256 0.028988 -0.03939 -0.0713505 0.0263547 -0.0404726 -0.0713505 0.0289596 -0.0404726 -0.0701005 0.0289049 -0.0417226 -0.0704241 0.0289099 -0.04168 -0.0707255 0.0289173 -0.0415551 -0.0688505 0.0263547 -0.0404726 -0.069018 0.0263547 -0.0410976 -0.0694755 0.0289034 -0.0415551 -0.0701005 0.0263547 -0.0417226 -0.0701005 0.0289866 -0.0392226 -0.0701005 0.0263547 -0.0392226 -0.069777 0.0289816 -0.0392652 -0.0704694 0.0289941 0.0392831 -0.0701005 0.0263547 0.0392274 -0.069777 0.0289875 0.03927 -0.0694755 0.0263547 0.0393949 -0.0694755 0.0289803 0.0393949 -0.069018 0.0263547 0.0398524 -0.0688505 0.0263547 0.0404774 -0.069018 0.0289605 0.0398524 -0.0688505 0.028938 0.0404774 -0.069018 0.0289191 0.0411024 -0.0701005 0.0263547 0.0417274 -0.069777 0.0289075 0.0416848 -0.0711831 0.0289412 0.0411024 -0.0711831 0.0263547 0.0411024 -0.0701005 0.0289094 0.0417274 -0.0707255 0.0263547 0.0393949 -0.0711831 0.0263547 0.0398524 -0.0709844 0.0289891 0.0395936 -0.0713505 0.0289636 0.0404774 -0.0866285 -0.0125556 -0.028127 -0.0868822 -0.0128653 -0.0275294 -0.0967958 -0.0122863 -0.0288849 -0.0867419 -0.0127521 -0.0277275 -0.0755423 -0.0121351 -0.0296544 -0.0771351 -0.0121649 -0.0294444 -0.0779065 -0.0123496 -0.0286711 -0.0680253 -0.0120953 -0.0303084 -0.0742638 -0.0123496 -0.0286711 -0.0675035 -0.0122126 -0.0314258 -0.0766279 -0.0121351 0.0296593 -0.0760851 -0.0121269 0.0297307 -0.0967958 -0.0121221 0.0308498 -0.0674993 -0.0122142 0.03144 -0.0755417 -0.0121351 0.0296591 -0.0750351 -0.0121649 0.0294493 -0.0689764 -0.0125556 0.0281319 -0.0742638 -0.0123496 0.028676 -0.0685133 -0.0122073 0.0292193 -0.0866828 -0.0126497 0.0279301 -0.0967958 -0.0122863 0.0288898 -0.0746601 0.0289547 -0.0251576 -0.0736169 0.0289547 -0.0262008 -0.0738767 0.0286547 -0.0289008 -0.0736169 0.0289547 -0.0290508 -0.0748101 0.0286547 -0.0298342 -0.0760851 0.0286547 -0.0301758 -0.0775101 0.0289547 -0.030094 -0.0785533 0.0289547 -0.0290508 -0.0789351 0.0289547 -0.0276258 -0.0736169 0.0289547 0.0290557 -0.0736169 0.0289547 0.0262057 -0.0746601 0.0289547 0.0251625 -0.0760851 0.0286547 0.0250807 -0.0786351 0.0286547 0.0276307 -0.0789351 0.0289547 0.0276307 -0.0785533 0.0289547 0.0290557 -0.0760851 0.0289547 0.0304807 -0.0748101 0.0286547 0.029839 -0.0606922 0.0263547 -0.0542871 -0.0606922 0.0285535 -0.0542871 -0.0594172 0.0263547 -0.0520787 -0.0597588 0.0263547 -0.0533537 -0.0594965 0.0285149 -0.0514478 -0.0606922 0.0263547 -0.0498704 -0.0602955 0.0285133 -0.0501531 -0.0598444 0.0285113 -0.0506658 -0.0597588 0.0285114 -0.0508037 -0.0619672 0.0263547 -0.0495287 -0.0631152 0.0285732 -0.0498018 -0.062136 0.0285476 -0.0495343 -0.0632422 0.0263547 -0.0498704 -0.0645172 0.0285434 -0.0520787 -0.0645063 0.0285523 -0.0518432 -0.0641756 0.0263547 -0.0508037 -0.0641756 0.0285823 -0.0508037 -0.0641756 0.0263547 -0.0533537 -0.0637678 0.0284995 -0.0538843 -0.0640993 0.0285016 -0.0534775 -0.0619624 0.0285383 -0.0546287 -0.0619672 0.0285382 -0.0546287 -0.0619672 0.0263547 -0.0546287 -0.0632422 0.0263547 -0.0542871 -0.052077 0.0284684 0.0645238 -0.0512348 0.0284707 0.0643808 -0.0531691 0.0284633 0.0642781 -0.053352 0.0284622 0.0641822 -0.0543692 0.0284666 0.063091 -0.054627 0.0263547 0.0619738 -0.0542853 0.0263547 0.0606988 -0.053352 0.0263547 0.0597655 -0.053352 0.0284841 0.0597655 -0.0536704 0.0284868 0.059983 -0.0542396 0.0284895 0.0606227 -0.0509804 0.0284682 0.0596717 -0.0498686 0.0263547 0.0606988 -0.049527 0.0263547 0.0619738 -0.049527 0.0284683 0.0619738 -0.0495902 0.0284692 0.0625383 -0.0498686 0.0263547 0.0632488 -0.0504877 0.0284713 0.063968 -0.0499172 0.0284704 0.0633296 -0.0619672 0.0285382 0.0546336 -0.0637994 0.0284993 0.0538571 -0.0632422 0.0263547 0.054292 -0.0641756 0.0263547 0.0533586 -0.0641756 0.0285036 0.0533586 -0.0644427 0.0285657 0.0514716 -0.0645172 0.0285434 0.0520836 -0.0641756 0.0285823 0.0508086 -0.0641017 0.0285839 0.0506885 -0.0632422 0.0263547 0.0498752 -0.0619672 0.0285433 0.0495336 -0.0619718 0.0285434 0.0495336 -0.0632422 0.0285761 0.0498752 -0.0616293 0.0285352 0.0495561 -0.0606922 0.0263547 0.0498752 -0.0601249 0.0285121 0.0503205 -0.0597629 0.0285114 0.0508016 -0.0594272 0.0285188 0.0518577 -0.0597588 0.0263547 0.0508086 -0.0594172 0.0285215 0.0520836 -0.0597588 0.0263547 0.0533586 -0.0598353 0.0285433 0.0534828 -0.0760851 0.0286547 0.0301807 -0.0738767 0.0286547 0.0289057 -0.0735351 0.0286547 0.0276307 -0.0738767 0.0286547 0.0263557 -0.0748101 0.0263547 0.0254223 -0.0748101 0.0286547 0.0254223 -0.0773601 0.0263547 0.0254223 -0.0773601 0.0286547 0.0254223 -0.0782935 0.0263547 0.0263557 -0.0782935 0.0286547 0.0263557 -0.0786351 0.0263547 0.0276307 -0.0782935 0.0263547 0.0289057 -0.0782935 0.0286547 0.0289057 -0.0773601 0.0263547 0.029839 -0.0773601 0.0286547 0.029839 -0.0760851 0.0263547 0.0301807 -0.0748101 0.0286547 -0.0254174 -0.0748101 0.0263547 -0.0254174 -0.0738767 0.0286547 -0.0263508 -0.0735351 0.0263547 -0.0276258 -0.0735351 0.0286547 -0.0276258 -0.0738767 0.0263547 -0.0289008 -0.0748101 0.0263547 -0.0298342 -0.0773601 0.0263547 -0.0298342 -0.0782935 0.0263547 -0.0289008 -0.0773601 0.0286547 -0.0298342 -0.0782935 0.0286547 -0.0289008 -0.0786351 0.0263547 -0.0276258 -0.0786351 0.0286547 -0.0276258 -0.0782935 0.0263547 -0.0263508 -0.0782935 0.0286547 -0.0263508 -0.0773601 0.0286547 -0.0254174 -0.0760851 0.0263547 -0.0250758 -0.0760851 0.0286547 -0.0250758 -0.081027 0.0340516 -0.0254491 -0.0807616 0.0289547 -0.0249258 -0.0797522 0.0289547 -0.0236619 -0.0807616 0.0289547 -0.0303258 -0.0814851 0.0289547 -0.0276258 -0.0787851 0.0289547 -0.0323023 -0.0792908 0.0296685 -0.0319713 -0.0804942 0.0301627 -0.0307435 -0.0785733 0.0296068 -0.0324184 -0.0774791 0.0296163 -0.0328428 -0.0773972 0.0296192 -0.0328639 -0.0736088 0.0298964 -0.0324245 -0.0760851 0.0289547 -0.0330258 -0.0720241 0.0303469 -0.031185 -0.0733851 0.0289547 -0.0323023 -0.0709699 0.0313285 -0.0293562 -0.0706851 0.0289547 -0.0276258 -0.0714086 0.0289547 -0.0303258 -0.0715786 0.0306204 -0.0306009 -0.0714011 0.0343851 -0.0249388 -0.0714086 0.0289547 -0.0249258 -0.0707694 0.0332202 -0.0266718 -0.072418 0.0289547 -0.0236619 -0.0721284 0.0304897 -0.023951 -0.0725332 0.032177 -0.0235583 -0.0730661 0.0328518 -0.0231486 -0.0720877 0.0349812 -0.0239953 -0.0727681 0.0353651 -0.0233646 -0.0733851 0.0330962 -0.0229492 -0.0733721 0.0356072 -0.0229568 -0.073887 0.035761 -0.0226934 -0.074646 0.0335946 -0.0224211 -0.0748639 0.0359496 -0.0223657 -0.0760851 0.0337386 -0.0222258 -0.0783852 0.0357338 -0.0227402 -0.0787989 0.0356069 -0.0229572 -0.0795363 0.0353001 -0.0234727 -0.0801896 0.0349059 -0.0241168 -0.0807712 0.0343827 -0.0249425 -0.0812661 0.0314175 -0.0291481 -0.0812218 0.0337096 -0.0259602 -0.0714086 0.0289547 0.0303307 -0.071399 0.0343827 0.0249474 -0.0807726 0.0304461 0.0303115 -0.0810763 0.0309362 0.0296917 -0.0814851 0.0289547 0.0276307 -0.0812661 0.0314177 0.0291528 -0.0814008 0.0332202 0.0266767 -0.0814853 0.0325374 0.0276334 -0.0807616 0.0289547 0.0249307 -0.0799488 0.0313277 0.0238582 -0.0805179 0.0346391 0.0245466 -0.0791041 0.0328518 0.0231534 -0.0800825 0.0349812 0.0240002 -0.0794021 0.0353651 0.0233695 -0.0782832 0.035761 0.0226983 -0.0787851 0.0330962 0.0229541 -0.0773063 0.0359496 0.0223706 -0.0760851 0.0360292 0.0222307 -0.0725333 0.0321771 0.0235632 -0.0714086 0.0289547 0.0249307 -0.0710561 0.0311817 0.0295978 -0.0708964 0.0314792 0.0291264 -0.0706946 0.0323047 0.0279504 -0.0706851 0.0325338 0.0276383 -0.0706851 0.0289547 0.0276307 -0.0735322 0.0299086 0.0323891 -0.0733324 0.0299432 0.0322764 -0.0720067 0.0303556 0.0311699 -0.0754331 0.0297188 0.0329912 -0.0787851 0.0289547 0.0323072 -0.0807616 0.0289547 0.0303307 -0.0792379 0.0296606 0.0320147 -0.051027 -0.00634534 -0.0601503 -0.0502583 -0.00634534 -0.060919 -0.049977 -0.0128453 -0.061969 -0.0502583 -0.0128453 -0.063019 -0.0502583 -0.00634534 -0.063019 -0.051027 -0.0128453 -0.0637876 -0.052077 -0.0128453 -0.064069 -0.051027 -0.00634534 -0.0637876 -0.0538956 -0.0128453 -0.063019 -0.0538956 -0.00634534 -0.063019 -0.054177 -0.0128453 -0.061969 -0.054177 -0.00634534 -0.061969 -0.0538956 -0.0128453 -0.060919 -0.0609172 -0.0128453 -0.0502601 -0.0609172 -0.00634534 -0.0502601 -0.0601485 -0.0128453 -0.0510287 -0.0601485 -0.00634534 -0.0510287 -0.0598672 -0.00634534 -0.0520787 -0.0601485 -0.0128453 -0.0531287 -0.0609172 -0.00634534 -0.0538974 -0.0619672 -0.0128453 -0.0541787 -0.0619672 -0.00634534 -0.0541787 -0.0630172 -0.0128453 -0.0538974 -0.0630172 -0.00634534 -0.0538974 -0.0637858 -0.00634534 -0.0531287 -0.0640672 -0.00634534 -0.0520787 -0.0637858 -0.0128453 -0.0510287 -0.0630172 -0.0128453 -0.0502601 -0.0619672 -0.00634534 -0.0499787 -0.0609172 -0.0128453 0.0539023 -0.0601485 -0.0128453 0.0510336 -0.0609172 -0.0128453 0.050265 -0.0601485 -0.00634534 0.0510336 -0.0609172 -0.00634534 0.050265 -0.0619672 -0.00634534 0.0499836 -0.0630172 -0.00634534 0.050265 -0.0630172 -0.0128453 0.050265 -0.0637858 -0.0128453 0.0510336 -0.0640672 -0.00634534 0.0520836 -0.0637858 -0.00634534 0.0531336 -0.0630172 -0.0128453 0.0539023 -0.0630172 -0.00634534 0.0539023 -0.0502583 -0.00634534 0.0630238 -0.049977 -0.0128453 0.0619738 -0.052077 -0.0128453 0.0598738 -0.052077 -0.00634534 0.0598738 -0.053127 -0.00634534 0.0601552 -0.0538956 -0.0128453 0.0609238 -0.0538956 -0.0128453 0.0630238 -0.053127 -0.00634534 0.0637925 -0.053127 -0.0128453 0.0637925 -0.052077 -0.00634534 0.0640738 -0.106496 0.0325239 -0.0187726 -0.106696 0.0316905 -0.0198791 -0.106496 0.0303155 -0.0200476 -0.106496 0.0290405 -0.0197059 -0.106696 0.0289405 -0.0198791 -0.106496 0.0281072 -0.0187726 -0.106496 0.0277655 -0.0174976 -0.106496 0.0281072 -0.0162226 -0.106496 0.0290405 -0.0152892 -0.106496 0.0303155 -0.0149476 -0.106696 0.0289405 -0.015116 -0.106496 0.0315905 -0.0152892 -0.106696 0.0326971 -0.0161226 -0.106496 0.0325239 -0.0162226 -0.106696 0.0330656 -0.0174976 -0.106696 0.0272412 -0.0192726 -0.106696 0.0285405 -0.0205719 -0.106496 0.0321906 -0.0207452 -0.106496 0.0340655 -0.0174976 -0.106696 0.0333899 -0.0157226 -0.106696 0.0303155 -0.0139476 -0.106496 0.0321906 -0.01425 -0.106496 0.0303155 -0.0137476 -0.106496 0.0284405 -0.01425 -0.106696 0.0272412 -0.0157226 -0.106696 0.0198862 -0.0316834 -0.106696 0.0175047 -0.0330584 -0.106696 0.0161297 -0.03269 -0.106496 0.0149547 -0.0303084 -0.106696 0.0147547 -0.0303084 -0.106496 0.0162297 -0.0281001 -0.106696 0.0151231 -0.0289334 -0.106496 0.0175047 -0.0277584 -0.106696 0.0161297 -0.0279269 -0.106696 0.0175047 -0.0275584 -0.106496 0.0187797 -0.0281001 -0.106696 0.0188797 -0.0279269 -0.106696 0.0202547 -0.0303084 -0.106696 0.0144303 -0.0320834 -0.106696 0.0157297 -0.0333828 -0.106496 0.0156297 -0.033556 -0.106696 0.0192797 -0.0333828 -0.106696 0.020579 -0.0320834 -0.106496 0.0207523 -0.0321834 -0.106496 0.0212547 -0.0303084 -0.106696 0.0210547 -0.0303084 -0.106496 0.0207523 -0.0284334 -0.106696 0.0192797 -0.0272341 -0.106496 0.0193797 -0.0270609 -0.106696 0.0157297 -0.0272341 -0.106696 0.0144303 -0.0285334 -0.106496 0.0142571 -0.0284334 -0.106496 0.0137547 -0.0303084 -0.106696 0.00238623 -0.0363726 -0.106696 0.00137966 -0.0373791 -0.106696 4.65996e-06 -0.0377476 -0.106696 -0.00137034 -0.0373791 -0.106496 -0.00127034 -0.0372059 -0.106696 -0.00237691 -0.0363726 -0.106496 -0.0022037 -0.0337226 -0.106496 -0.00127034 -0.0327892 -0.106496 4.65996e-06 -0.0324476 -0.106696 0.00137966 -0.032616 -0.106496 0.00221302 -0.0337226 -0.106696 0.00238623 -0.0336226 -0.106496 0.00255466 -0.0349976 -0.106696 -0.00306973 -0.0367726 -0.106496 -0.00324294 -0.0368726 -0.106496 4.65996e-06 -0.0387476 -0.106696 0.00177966 -0.0380719 -0.106496 0.00187966 -0.0382452 -0.106496 0.00375466 -0.0349976 -0.106496 0.00187966 -0.03175 -0.106496 4.65996e-06 -0.0312476 -0.106496 -0.00187034 -0.03175 -0.106496 -0.00324294 -0.0331226 -0.106696 -0.00306973 -0.0332226 -0.106696 -0.0151138 -0.0316834 -0.106696 -0.0161203 -0.03269 -0.106496 -0.0187703 -0.0325168 -0.106696 -0.0174953 -0.0330584 -0.106696 -0.0188703 -0.03269 -0.106696 -0.0198769 -0.0316834 -0.106696 -0.0202453 -0.0303084 -0.106696 -0.0198769 -0.0289334 -0.106696 -0.0174953 -0.0275584 -0.106496 -0.0162203 -0.0281001 -0.106696 -0.0161203 -0.0279269 -0.106496 -0.015287 -0.0290334 -0.106696 -0.0151138 -0.0289334 -0.106496 -0.0149453 -0.0303084 -0.106496 -0.0212453 -0.0303084 -0.106696 -0.0205697 -0.0320834 -0.106696 -0.0192703 -0.0333828 -0.106496 -0.0174953 -0.0340584 -0.106696 -0.0174953 -0.0338584 -0.106496 -0.0156203 -0.033556 -0.106696 -0.0157203 -0.0333828 -0.106696 -0.0144209 -0.0320834 -0.106496 -0.0142477 -0.0284334 -0.106496 -0.0174953 -0.0265584 -0.106696 -0.0192703 -0.0272341 -0.106696 -0.0210453 -0.0303084 -0.106696 -0.0279247 -0.0188726 -0.106496 -0.0290312 -0.0197059 -0.106696 -0.0289312 -0.0198791 -0.106496 -0.0303062 -0.0200476 -0.106696 -0.0303062 -0.0202476 -0.106496 -0.0315812 -0.0197059 -0.106696 -0.0316812 -0.0198791 -0.106696 -0.0326878 -0.0188726 -0.106496 -0.0315812 -0.0152892 -0.106496 -0.0303062 -0.0149476 -0.106696 -0.0303062 -0.0147476 -0.106496 -0.0290312 -0.0152892 -0.106496 -0.0280979 -0.0162226 -0.106696 -0.0275562 -0.0174976 -0.106696 -0.0333806 -0.0192726 -0.106696 -0.0320812 -0.0205719 -0.106496 -0.0321812 -0.0207452 -0.106696 -0.0303062 -0.0210476 -0.106496 -0.0284312 -0.0207452 -0.106696 -0.0272318 -0.0192726 -0.106696 -0.0267562 -0.0174976 -0.106496 -0.0265562 -0.0174976 -0.106696 -0.0272318 -0.0157226 -0.106696 -0.0285312 -0.0144232 -0.106696 -0.0303062 -0.0139476 -0.106496 -0.0284312 -0.01425 -0.106496 -0.0303062 -0.0137476 -0.106696 -0.0320812 -0.0144232 -0.106496 -0.0321812 -0.01425 -0.106496 -0.0335538 -0.0156226 -0.106496 -0.0340562 -0.0174976 -0.106496 -0.0337203 -0.00220592 -0.106696 -0.0336203 -0.00237913 -0.106496 -0.0362703 -0.00220592 -0.106496 -0.0375453 2.44063e-06 -0.106696 -0.0377453 2.44063e-06 -0.106496 -0.0372037 0.00127744 -0.106696 -0.0363703 0.00238401 -0.106496 -0.0349953 0.00255244 -0.106496 -0.0337203 0.00221081 -0.106696 -0.0349953 0.00275244 -0.106696 -0.0326138 0.00137744 -0.106496 -0.032787 -0.00127256 -0.106696 -0.0380697 -0.00177256 -0.106696 -0.0367703 -0.00307195 -0.106696 -0.0349953 -0.00354756 -0.106496 -0.0312453 2.44063e-06 -0.106496 -0.0317477 0.00187744 -0.106696 -0.0332203 0.00307683 -0.106696 -0.0367703 0.00307683 -0.106696 -0.0380697 0.00177744 -0.106496 -0.0368703 0.00325004 -0.106696 -0.0385453 2.44063e-06 -0.106696 -0.0289312 0.0151209 -0.106496 -0.0315812 0.0152941 -0.106496 -0.0328562 0.0175024 -0.106496 -0.0325146 0.0187774 -0.106496 -0.0303062 0.0200524 -0.106496 -0.0290312 0.0197108 -0.106696 -0.0289312 0.019884 -0.106696 -0.0279247 0.0188774 -0.106696 -0.0275562 0.0175024 -0.106696 -0.0279247 0.0161274 -0.106696 -0.0333806 0.0157274 -0.106696 -0.0320812 0.0144281 -0.106496 -0.0335538 0.0156274 -0.106696 -0.0303062 0.0139524 -0.106496 -0.0303062 0.0137524 -0.106696 -0.0285312 0.0144281 -0.106496 -0.0284312 0.0142548 -0.106696 -0.0267562 0.0175024 -0.106496 -0.0270586 0.0156274 -0.106696 -0.0285312 0.0205768 -0.106696 -0.0333806 0.0192774 -0.106496 -0.0335538 0.0193774 -0.106496 -0.0174953 0.0277633 -0.106696 -0.0174953 0.0275633 -0.106696 -0.0188703 0.0279318 -0.106496 -0.0197037 0.0290383 -0.106496 -0.0197037 0.0315883 -0.106696 -0.0198769 0.0316883 -0.106696 -0.0188703 0.0326949 -0.106496 -0.0174953 0.0328633 -0.106496 -0.0162203 0.0325217 -0.106496 -0.015287 0.0315883 -0.106696 -0.0151138 0.0316883 -0.106696 -0.0205697 0.0285383 -0.106496 -0.0193703 0.0270657 -0.106496 -0.0174953 0.0265633 -0.106696 -0.0144209 0.0285383 -0.106496 -0.0142477 0.0284383 -0.106496 -0.0137453 0.0303133 -0.106496 -0.0156203 0.0335609 -0.106696 -0.0174953 0.0338633 -0.106496 -0.0193703 0.0335609 -0.106696 -0.0192703 0.0333877 -0.106696 -0.0210453 0.0303133 -0.106496 0.00221302 0.0337274 -0.106496 0.00127966 0.0327941 -0.106696 0.00238623 0.0336274 -0.106696 4.65996e-06 0.0322524 -0.106496 -0.00127034 0.0327941 -0.106696 -0.00137034 0.0326209 -0.106696 -0.00274534 0.0350024 -0.106496 -0.0022037 0.0362774 -0.106496 4.65996e-06 0.0375524 -0.106696 -0.00137034 0.037384 -0.106696 4.65996e-06 0.0377524 -0.106496 0.00127966 0.0372108 -0.106696 0.00137966 0.037384 -0.106696 0.00238623 0.0363774 -0.106496 4.65996e-06 0.0312524 -0.106696 4.65996e-06 0.0314524 -0.106696 0.00177966 0.0319281 -0.106696 0.00355466 0.0350024 -0.106696 0.00307905 0.0367774 -0.106496 4.65996e-06 0.0387524 -0.106696 -0.00177034 0.0380768 -0.106496 -0.00187034 0.03825 -0.106696 -0.00306973 0.0367774 -0.106696 0.0198862 0.0289383 -0.106496 0.0175047 0.0277633 -0.106496 0.0162297 0.028105 -0.106496 0.0152963 0.0290383 -0.106696 0.0151231 0.0289383 -0.106696 0.0147547 0.0303133 -0.106496 0.0152963 0.0315883 -0.106496 0.0162297 0.0325217 -0.106696 0.0151231 0.0316883 -0.106496 0.0175047 0.0328633 -0.106696 0.0188797 0.0326949 -0.106496 0.019713 0.0315883 -0.106496 0.0200547 0.0303133 -0.106496 0.019713 0.0290383 -0.106496 0.0137547 0.0303133 -0.106696 0.0144303 0.0285383 -0.106496 0.0142571 0.0284383 -0.106696 0.0175047 0.0267633 -0.106496 0.0156297 0.0270657 -0.106496 0.0193797 0.0270657 -0.106496 0.0207523 0.0284383 -0.106696 0.020579 0.0320883 -0.106496 0.0207523 0.0321883 -0.106696 0.0192797 0.0333877 -0.106496 0.0193797 0.0335609 -0.106696 0.0175047 0.0338633 -0.106696 0.0144303 0.0320883 -0.106696 0.0139547 0.0303133 -0.106696 0.0316905 0.0151209 -0.106496 0.0290405 0.0152941 -0.106696 0.0275655 0.0175024 -0.106496 0.0281072 0.0187774 -0.106696 0.0289405 0.019884 -0.106496 0.0303155 0.0200524 -0.106496 0.0315905 0.0197108 -0.106496 0.0325239 0.0187774 -0.106496 0.0325239 0.0162274 -0.106696 0.0326971 0.0161274 -0.106496 0.0284405 0.0142548 -0.106496 0.0303155 0.0137524 -0.106496 0.0335631 0.0156274 -0.106496 0.0340655 0.0175024 -0.106696 0.0338655 0.0175024 -0.106696 0.0303155 0.0210524 -0.106496 0.0321906 0.02075 -0.106496 0.0303155 0.0212524 -0.106696 0.0272412 0.0192774 -0.106696 0.0267655 0.0175024 -0.106496 0.027068 0.0193774 -0.106496 0.0265655 0.0175024 -0.106496 0.0284405 -0.0207452 -0.104996 0.0284405 -0.0207452 -0.106496 0.0303155 -0.0212476 -0.104996 0.0321906 -0.0207452 -0.106496 0.0335631 -0.0193726 -0.104996 0.0335631 -0.0193726 -0.104996 0.0340655 -0.0174976 -0.104996 0.0335631 -0.0156226 -0.106496 0.0335631 -0.0156226 -0.104996 0.0321906 -0.01425 -0.104996 0.0284405 -0.01425 -0.106496 0.027068 -0.0156226 -0.104996 0.027068 -0.0156226 -0.106496 0.0265655 -0.0174976 -0.104996 0.0265655 -0.0174976 -0.106496 0.027068 -0.0193726 -0.106496 0.0142571 -0.0321834 -0.104996 0.0142571 -0.0321834 -0.106496 0.0175047 -0.0340584 -0.104996 0.0193797 -0.033556 -0.106496 0.0193797 -0.033556 -0.104996 0.0212547 -0.0303084 -0.104996 0.0207523 -0.0284334 -0.106496 0.0175047 -0.0265584 -0.106496 0.0156297 -0.0270609 -0.104996 0.0156297 -0.0270609 -0.104996 0.0142571 -0.0284334 -0.104996 0.0137547 -0.0303084 -0.104996 -0.00324294 -0.0368726 -0.106496 -0.00187034 -0.0382452 -0.106496 0.00325226 -0.0368726 -0.104996 0.00325226 -0.0368726 -0.106496 0.00325226 -0.0331226 -0.104996 4.65996e-06 -0.0312476 -0.104996 -0.00187034 -0.03175 -0.106496 -0.00374534 -0.0349976 -0.104996 -0.0207429 -0.0321834 -0.106496 -0.0193703 -0.033556 -0.104996 -0.0174953 -0.0340584 -0.104996 -0.0156203 -0.033556 -0.106496 -0.0142477 -0.0321834 -0.106496 -0.0137453 -0.0303084 -0.104996 -0.0142477 -0.0321834 -0.104996 -0.0137453 -0.0303084 -0.104996 -0.0142477 -0.0284334 -0.106496 -0.0156203 -0.0270609 -0.104996 -0.0156203 -0.0270609 -0.106496 -0.0193703 -0.0270609 -0.104996 -0.0207429 -0.0284334 -0.106496 -0.0207429 -0.0284334 -0.106496 -0.0207429 -0.0321834 -0.106496 -0.0335538 -0.0193726 -0.106496 -0.0303062 -0.0212476 -0.104996 -0.0303062 -0.0212476 -0.104996 -0.0284312 -0.0207452 -0.106496 -0.0270586 -0.0193726 -0.104996 -0.0265562 -0.0174976 -0.106496 -0.0270586 -0.0156226 -0.104996 -0.0270586 -0.0156226 -0.104996 -0.0321812 -0.01425 -0.104996 -0.0340562 -0.0174976 -0.106496 -0.0382429 -0.00187256 -0.104996 -0.0382429 -0.00187256 -0.106496 -0.0368703 -0.00324515 -0.104996 -0.0368703 -0.00324515 -0.106496 -0.0349953 -0.00374756 -0.104996 -0.0349953 -0.00374756 -0.106496 -0.0331203 -0.00324515 -0.106496 -0.0317477 -0.00187256 -0.104996 -0.0312453 2.44063e-06 -0.104996 -0.0317477 0.00187744 -0.106496 -0.0331203 0.00325004 -0.106496 -0.0349953 0.00375244 -0.104996 -0.0349953 0.00375244 -0.106496 -0.0382429 0.00187744 -0.104996 -0.0382429 0.00187744 -0.106496 -0.0387453 2.44063e-06 -0.106496 -0.0321812 0.0142548 -0.104996 -0.0303062 0.0137524 -0.104996 -0.0270586 0.0156274 -0.106496 -0.0265562 0.0175024 -0.106496 -0.0270586 0.0193774 -0.104996 -0.0284312 0.02075 -0.106496 -0.0284312 0.02075 -0.106496 -0.0303062 0.0212524 -0.104996 -0.0303062 0.0212524 -0.106496 -0.0321812 0.02075 -0.106496 -0.0340562 0.0175024 -0.104996 -0.0207429 0.0284383 -0.106496 -0.0207429 0.0284383 -0.106496 -0.0156203 0.0270657 -0.104996 -0.0142477 0.0284383 -0.106496 -0.0142477 0.0321883 -0.104996 -0.0142477 0.0321883 -0.104996 -0.0156203 0.0335609 -0.106496 -0.0174953 0.0340633 -0.104996 -0.0174953 0.0340633 -0.106496 -0.0207429 0.0321883 -0.106496 -0.0212453 0.0303133 -0.104996 -0.0212453 0.0303133 -0.104996 -0.00187034 0.0317548 -0.106496 -0.00187034 0.0317548 -0.104996 4.65996e-06 0.0312524 -0.106496 0.00187966 0.0317548 -0.104996 0.00325226 0.0331274 -0.106496 0.00325226 0.0331274 -0.106496 0.00375466 0.0350024 -0.106496 0.00325226 0.0368774 -0.106496 0.00187966 0.03825 -0.104996 0.00325226 0.0368774 -0.106496 -0.00324294 0.0368774 -0.104996 -0.00187034 0.03825 -0.104996 -0.00324294 0.0368774 -0.106496 -0.00374534 0.0350024 -0.106496 -0.00324294 0.0331274 -0.104996 0.0142571 0.0284383 -0.104996 0.0156297 0.0270657 -0.104996 0.0175047 0.0265633 -0.106496 0.0175047 0.0265633 -0.104996 0.0193797 0.0270657 -0.104996 0.0212547 0.0303133 -0.106496 0.0212547 0.0303133 -0.104996 0.0207523 0.0321883 -0.104996 0.0193797 0.0335609 -0.106496 0.0175047 0.0340633 -0.104996 0.0175047 0.0340633 -0.106496 0.0156297 0.0335609 -0.106496 0.0142571 0.0321883 -0.104996 0.0142571 0.0321883 -0.104996 0.0265655 0.0175024 -0.106496 0.027068 0.0156274 -0.104996 0.027068 0.0156274 -0.106496 0.0321906 0.0142548 -0.104996 0.0303155 0.0137524 -0.104996 0.0321906 0.0142548 -0.106496 0.0335631 0.0193774 -0.104996 0.0321906 0.02075 -0.106496 0.0284405 0.02075 -0.104996 0.027068 0.0193774 -0.0866194 -0.0358826 0.0106176 -0.0967958 -0.036527 0.0110313 -0.0828283 -0.0372235 0.0118041 -0.0967958 -0.0374179 0.0121416 -0.0808302 -0.0377211 0.0130399 -0.0967958 -0.0377763 0.0135193 -0.0967958 -0.0261182 0.0278196 -0.0881087 -0.0262767 0.0283735 -0.0886953 -0.0259708 0.0274869 -0.0967958 -0.0250489 0.0316959 -0.0967958 -0.0259561 -0.030594 -0.0881274 -0.026245 -0.028224 -0.0967958 -0.0261182 -0.0278147 -0.0797974 -0.0376982 -0.0144017 -0.0967958 -0.0377763 -0.0135145 -0.0821159 -0.0374298 -0.0121605 -0.0802177 -0.0377795 -0.0136625 -0.0967958 -0.036527 -0.0110265 -0.0841707 -0.0367861 -0.0112608 -0.106496 0.0362797 -0.00220592 -0.106696 0.0350047 -0.00274756 -0.106696 0.0326231 -0.00137256 -0.106496 0.0327963 0.00127744 -0.106696 0.0326231 0.00137744 -0.106496 0.0350047 0.00255244 -0.106496 0.0362797 0.00221081 -0.106696 0.0363797 0.00238401 -0.106496 0.037213 0.00127744 -0.106696 0.0373862 0.00137744 -0.106496 0.037213 -0.00127256 -0.106496 0.0317571 -0.00187256 -0.106496 0.0350047 -0.00374756 -0.106696 0.0367797 -0.00307195 -0.106496 0.0382523 -0.00187256 -0.106696 0.038079 -0.00177256 -0.106696 0.0385547 2.44063e-06 -0.106496 0.0387547 2.44063e-06 -0.106696 0.038079 0.00177744 -0.106696 0.0350047 0.00355244 -0.106496 0.0331297 0.00325004 -0.106696 0.0319303 0.00177744 -0.106696 0.0319303 -0.00177256 -0.104996 0.0312547 2.44063e-06 -0.106496 0.0331297 -0.00324515 -0.106496 0.0368797 -0.00324515 -0.104996 0.0387547 2.44063e-06 -0.106496 0.0382523 0.00187744 -0.104996 0.0382523 0.00187744 -0.104996 0.0368797 0.00325004 -0.106496 0.0368797 0.00325004 -0.106496 0.0350047 0.00375244 -0.106496 0.0317571 0.00187744 -0.106496 0.0312547 2.44063e-06 -0.0967958 0.0318414 0.00760132 -0.0967958 0.0318414 -0.00759644 -0.0963805 0.0314201 -0.00745341 -0.0796687 0.0376785 0.0145915 -0.0728981 0.0377363 0.0144419 -0.0737785 0.0394323 0.00881267 -0.0967958 0.0399788 0.00585273 -0.0967958 0.0402369 0.00368067 -0.0797062 0.0399788 0.00585273 -0.0796854 0.0399395 0.00611511 -0.0740629 0.0399691 0.00591895 -0.0796397 0.0390281 0.0104587 -0.0967958 0.0402369 -0.00367579 -0.0797062 0.0399788 -0.00584784 -0.0742058 0.0402368 -0.00367642 -0.0796397 0.0399074 -0.0063165 -0.0737826 0.0394403 -0.00877244 -0.0797062 0.0375484 -0.0149181 -0.072331 0.0366131 -0.0170851 -0.0796854 0.0376456 -0.0146713 -0.0796397 0.0377209 -0.0144766 -0.0967958 0.0362792 -0.017783 -0.104996 -0.0355288 0.0572927 -0.104996 -0.0358436 0.0567286 -0.104696 -0.036189 0.0560421 -0.104696 -0.0359167 0.0553164 -0.104996 -0.0355288 -0.0572878 -0.104696 -0.0351429 -0.0579346 -0.104696 -0.036189 -0.0560372 -0.104996 -0.0358436 -0.0567238 -0.104996 -0.035892 -0.0560797 -0.104996 -0.0356651 -0.0554749 -0.0874957 -0.0362064 -0.05634 -0.0875024 -0.0362071 -0.0562919 -0.104696 -0.0361308 -0.0568101 -0.087438 -0.0361337 -0.0568005 -0.0873716 -0.0356631 -0.0575813 -0.104696 -0.0357531 -0.0574869 -0.104696 -0.0351429 0.0579395 -0.0873662 -0.0354625 0.0577549 -0.104696 -0.0357531 0.0574918 -0.0874537 -0.0361677 0.056671 -0.087438 -0.0361337 0.0568055 -0.104696 -0.0361308 0.056815 -0.087374 -0.0357103 0.0575384 -0.104996 -0.0262603 0.0398865 -0.104696 -0.0273143 0.0331062 -0.104996 -0.0262603 -0.0398817 -0.104696 -0.0263552 -0.0363413 -0.104996 -0.0260514 -0.0363569 -0.104696 -0.0265523 -0.0398128 -0.0858658 -0.0293335 0.0303358 -0.104696 -0.0326432 -0.0267362 -0.0858658 -0.0345694 -0.0241943 -0.104696 -0.0347874 -0.0238797 -0.0858658 -0.0372268 -0.0198639 -0.104696 -0.0372267 -0.0198638 -0.104696 -0.038847 -0.0164713 -0.0858658 -0.0381854 -0.017952 -0.104696 -0.0403835 -0.0122302 -0.0858658 -0.0419927 -0.00412786 -0.104696 -0.0419927 -0.00412786 -0.0858658 -0.042002 -0.00403245 -0.104696 -0.0413498 0.00840774 -0.0858658 -0.0419927 0.00413274 -0.104696 -0.0347874 0.0238845 -0.104696 -0.0372267 0.0198687 -0.0858658 -0.0398367 0.0139132 -0.104696 -0.038847 0.0164762 -0.104696 -0.0403835 0.0122351 -0.0858658 -0.0403835 0.0122351 -0.0680002 -0.00718196 0.0558088 -0.048769 -0.00747313 0.0570023 -0.0481192 -0.00742899 0.0575183 -0.0680002 -0.00747205 0.0571095 -0.0680002 -0.00746927 0.0571753 -0.0680002 -0.00746862 0.0571869 -0.0680002 -0.00745673 0.057327 -0.0680002 -0.00739942 0.0576558 -0.0474566 -0.00727972 0.0580325 -0.0680002 -0.00718196 0.0582486 -0.0468388 -0.00703626 0.0585014 -0.0462412 -0.00667485 0.0589455 -0.0680002 -0.00655042 0.0590614 -0.0680002 -0.00718196 -0.0582437 -0.0487361 -0.00747325 -0.0570238 -0.0680002 -0.00745473 -0.0573396 -0.0680002 -0.00745673 -0.0573221 -0.0680002 -0.00746532 -0.0572307 -0.0680002 -0.00655042 -0.0549912 -0.0500227 -0.00725811 -0.0559677 -0.0680002 -0.00747325 -0.0570238 -0.0781851 -0.00634534 -0.0276258 -0.0781851 -0.0127315 -0.0276258 -0.0740458 -0.0125556 -0.028127 -0.0739851 -0.00634534 -0.0276258 -0.0742664 -0.00634534 -0.0286758 -0.0744045 -0.0122863 -0.0288849 -0.0766285 -0.0121351 -0.0296543 -0.0760851 -0.0121269 -0.0297258 -0.0760851 -0.00634534 -0.0297258 -0.0750351 -0.0121649 -0.0294444 -0.0781244 -0.0125556 -0.028127 -0.0779038 -0.00634534 -0.0286758 -0.0777657 -0.0122863 -0.0288849 -0.0741748 -0.0128453 -0.0267535 -0.0742664 -0.0128453 -0.0265758 -0.0750351 -0.00634534 -0.0258071 -0.0750351 -0.0128453 -0.0258071 -0.0760851 -0.00634534 -0.0255258 -0.0771351 -0.00634534 -0.0258071 -0.0771351 -0.0128453 -0.0258071 -0.0779038 -0.00634534 -0.0265758 -0.0779065 -0.0123496 0.028676 -0.0781244 -0.0125556 0.0281319 -0.0771351 -0.0121649 0.0294493 -0.0777657 -0.0122863 0.0288898 -0.0779038 -0.00634534 0.0286807 -0.0750351 -0.00634534 0.0294493 -0.0760851 -0.00634534 0.0297307 -0.0771351 -0.00634534 0.0294493 -0.0744045 -0.0122863 0.0288898 -0.0740458 -0.0125556 0.0281319 -0.0742664 -0.00634534 0.0286807 -0.0739851 -0.00634534 0.0276307 -0.0739851 -0.0127315 0.0276307 -0.0781851 -0.0127315 0.0276307 -0.0781851 -0.00634534 0.0276307 -0.0779038 -0.00634534 0.0265807 -0.0779954 -0.0128453 0.0267584 -0.0771351 -0.00634534 0.025812 -0.0760851 -0.00634534 0.0255307 -0.0750351 -0.0128453 0.025812 -0.0779954 -0.0128453 -0.0267535 -0.0779038 -0.0128453 -0.0265758 -0.0760851 -0.0128453 -0.0255258 -0.0867958 -0.0128453 -0.0244258 -0.0702849 -0.0128453 -0.0244258 -0.0661409 -0.0128453 0.0343461 -0.0702849 -0.0128453 0.0244307 -0.0760851 -0.0128453 0.0255307 -0.0741748 -0.0128453 0.0267584 -0.0742664 -0.0128453 0.0265807 -0.0867958 -0.0128453 0.0267584 -0.0779038 -0.0128453 0.0265807 -0.0771351 -0.0128453 0.025812 -0.0700875 -0.00817476 -0.0240711 -0.0700007 -0.0125453 -0.0243299 -0.0700942 -0.00824976 -0.0240511 -0.070018 -0.0125408 -0.0242786 -0.0700509 -0.0123953 -0.0241805 -0.070091 -0.0123746 -0.0240605 -0.0698181 -0.00679534 -0.0248644 -0.0697766 -0.0066802 -0.0249841 -0.0697886 -0.00670168 -0.0249493 -0.0667132 -0.0122811 -0.032483 -0.0672302 -0.0119191 -0.0313642 -0.0669689 -0.0105225 -0.0319359 -0.0682408 -0.011916 -0.0290275 -0.0672803 -0.00954658 -0.0312536 -0.0686973 -0.0122811 -0.0278958 -0.0673807 -0.00874314 -0.0310299 -0.0677583 -0.00679534 -0.0301702 -0.0673924 -0.00834534 -0.0310035 -0.0674103 -0.00817476 -0.0309635 -0.0637632 -0.0113453 -0.0381105 -0.0637766 -0.0173193 -0.0380875 -0.0641003 -0.0183366 -0.037522 -0.0674869 -0.0264673 -0.030791 -0.0664751 -0.0256664 -0.0329828 -0.0674169 -0.0281043 -0.0309489 -0.0629994 -0.0156545 -0.039401 -0.0617187 -0.0140279 -0.0414431 -0.0627253 -0.0113453 -0.0398503 -0.0606563 -0.0132429 -0.0430349 -0.0593435 -0.0127153 -0.0448892 -0.058488 -0.0112766 -0.0460373 -0.0499004 -0.00750007 -0.055554 -0.0509524 -0.00674788 -0.0545503 -0.0510618 -0.00666989 -0.0544437 -0.0557104 -0.00664534 -0.0494801 -0.0565946 -0.00817476 -0.048428 -0.0566188 -0.00824569 -0.0483986 -0.0566276 -0.00832476 -0.0483879 -0.0566276 -0.00834534 -0.0483879 -0.053609 -0.0125453 -0.0518345 -0.0460514 -0.00688613 -0.0589213 -0.0472782 -0.00756372 -0.0578971 -0.0485717 -0.00777309 -0.0567685 -0.0685857 -0.0309022 -0.0281774 -0.0691328 -0.0305628 -0.0267643 -0.0706782 -0.0340347 -0.0222216 -0.0706999 -0.0355057 -0.0221503 -0.0720351 -0.0368681 -0.0171603 -0.0724433 -0.0389812 -0.0152901 -0.0735892 -0.0411465 -0.00785357 -0.0730885 -0.0389588 -0.0117131 -0.0734751 -0.0397056 -0.00888448 -0.0737817 -0.0415023 -0.00570134 -0.073936 -0.0405825 -0.00301367 -0.0739958 -0.0418953 2.44063e-06 -0.0738922 -0.0417054 0.00397195 -0.0739958 -0.0406953 -4.12508e-05 -0.0724433 -0.0389812 0.0152949 -0.0737817 -0.0415023 0.00570622 -0.0678695 -0.00664534 0.0299163 -0.0677992 -0.00669471 0.0300802 -0.0674103 -0.00817476 0.0309684 -0.067397 -0.00824669 0.0309981 -0.0673924 -0.00832476 0.0310084 -0.0685857 -0.0309022 0.0281823 -0.0686967 -0.0295241 0.0279022 -0.0687122 -0.0311928 0.0278627 -0.0720483 -0.0368949 0.017108 -0.0674169 -0.0281043 0.0309538 -0.0674923 -0.0264816 0.0307836 -0.0658861 -0.0218769 0.0341851 -0.0651436 -0.0218304 0.0356236 -0.0641003 -0.0183366 0.0375269 -0.0686973 -0.0122811 0.0279007 -0.0643874 -0.01451 0.0370159 -0.065873 -0.0125453 0.0342112 -0.0659805 -0.0113453 0.0339966 -0.0661104 -0.0125453 0.0337353 -0.0667132 -0.0122811 0.0324879 -0.0672601 -0.0096449 0.0313034 -0.0677434 -0.0117954 0.0302095 -0.0629972 -0.0156507 0.0394095 -0.0626586 -0.0151219 0.0399635 -0.0610924 -0.0135191 0.0423968 -0.0627253 -0.0113453 0.0398552 -0.0589672 -0.0113453 0.0454046 -0.0581717 -0.0111537 0.0464555 -0.0576758 -0.0108213 0.0470919 -0.054286 -0.0125453 0.0511022 -0.0559309 -0.00679534 0.0492261 -0.0557104 -0.00664534 0.0494849 -0.0566435 -0.00868604 0.0483736 -0.0700509 -0.0123953 0.0241854 -0.0700007 -0.0125453 0.0243347 -0.0701008 -0.0122453 0.0240359 -0.0701008 -0.00832476 0.0240359 -0.069759 -0.00665909 0.0250394 -0.0878672 -0.0142455 -0.0259416 -0.0873005 -0.0133621 -0.0267196 -0.0967958 -0.0136166 0.0264235 -0.0878672 -0.0142455 0.0259465 -0.0871689 -0.013157 0.0270537 -0.0867958 -0.0128453 0.0273762 -0.0868822 -0.0128653 0.0275343 -0.0867419 -0.0127521 0.0277324 -0.0875205 -0.0137051 0.0263373 -0.0873005 -0.0133621 0.0267244 -0.0876074 -0.0142511 -0.0256787 -0.0870407 -0.0132695 -0.0265431 -0.0874312 -0.0135659 -0.0264719 -0.0867958 -0.0128453 -0.0273714 -0.0871689 -0.013157 -0.0270488 -0.0870201 -0.0129876 -0.0273351 -0.0867657 -0.0127932 -0.027548 -0.0661409 -0.0128453 -0.0343412 -0.0662764 -0.0128225 -0.0338125 -0.0660384 -0.0128225 -0.0342896 -0.0659935 -0.0127958 -0.034267 -0.0661892 -0.0127575 -0.0337693 -0.0661309 -0.0126601 -0.0337405 -0.0694572 -0.0128453 -0.0267535 -0.0693538 -0.0128243 -0.0267148 -0.0701428 -0.0128051 -0.0243778 -0.0693167 -0.0128051 -0.026701 -0.0700829 -0.0127564 -0.0243576 -0.0691959 -0.0126558 -0.0266558 -0.0700388 -0.0126953 -0.0243427 -0.0692585 -0.0127575 -0.0266792 -0.0700223 -0.0126601 0.024342 -0.0691976 -0.0126601 0.0266613 -0.0701761 -0.0128225 0.024394 -0.0702329 -0.0128403 0.0244131 -0.0661309 -0.0126601 0.0337454 -0.0658934 -0.0126601 0.0342215 -0.0659515 -0.0127575 0.0342507 -0.0663793 -0.0128453 0.0338683 -0.0910547 0.0501642 -0.00690026 -0.104638 0.0408223 0.0109395 -0.103834 0.0409276 -0.0112093 -0.104696 0.0412338 -0.00899756 -0.102285 0.0414357 -0.0105353 -0.0897383 0.0519861 -0.00670251 -0.0891559 0.0529353 -0.00614147 -0.0886475 0.0539037 0.00468959 -0.0886008 0.0540621 0.0036866 -0.088779 0.0536284 -0.0053049 -0.0886073 0.0540043 -0.0042924 -0.0893274 0.0526435 0.00636869 -0.0904923 0.0509014 0.00690438 -0.0910547 0.0501642 0.00690515 -0.0913228 0.049595 0.00863996 -0.0928312 0.0480952 0.00690818 -0.094531 0.0464296 0.00691188 -0.0962157 0.0448013 0.00870103 -0.100182 0.0423144 0.00972647 -0.10004 0.0432836 2.44063e-06 -0.099669 0.0433264 -0.00343915 -0.099565 0.0433313 -0.00402602 -0.0999905 0.0429682 -0.00592213 -0.0999905 0.0429682 0.00592701 -0.098598 0.0436996 0.0052619 -0.0996592 0.0433164 0.00366076 -0.099669 0.0433264 0.00344403 -0.0996143 0.0434584 -0.000600082 -0.104696 0.0420706 0.0033638 -0.104696 0.0412338 0.00900244 -0.102376 0.0422004 0.00592943 -0.102402 0.0425661 2.44063e-06 -0.0934061 0.0475 -0.00690447 -0.0950932 0.0457071 -0.0086428 -0.0952988 0.0455343 -0.00864333 -0.0966417 0.0447909 -0.00643619 -0.0971443 0.0441192 -0.0088378 -0.0980233 0.043978 -0.00569141 -0.102376 0.0422004 -0.00592455 -0.104696 0.041786 -0.00592709 -0.104696 0.0421082 -0.00284848 -0.104696 0.0422047 2.44063e-06 -0.104996 -0.0207429 0.0321883 -0.104996 -0.0385708 -0.0163542 -0.104996 0.0380079 -0.0177858 -0.104996 0.0317571 0.00187744 -0.104996 0.0331297 0.00325004 -0.104996 0.0317571 -0.00187256 -0.104996 0.0331297 -0.00324515 -0.104996 0.0350047 -0.00374756 -0.104996 0.0417956 -0.0030185 -0.104996 -0.00374534 0.0350024 -0.104996 -0.00324294 0.0331274 -0.104996 0.00187966 0.0317548 -0.104996 0.00875466 0.0239079 -0.104996 -0.0331203 -0.00324515 -0.104996 -0.0317477 -0.00187256 -0.104996 -0.0331203 0.00325004 -0.104996 -0.0364008 0.00875244 -0.104996 -0.0368703 0.00325004 -0.104996 -0.0418953 2.44063e-06 -0.104996 -0.0387453 2.44063e-06 -0.104996 -0.00324294 -0.0331226 -0.104996 -0.00374534 -0.0349976 -0.104996 0.00187966 -0.0382452 -0.104996 0.00375466 -0.0349976 -0.104996 0.00325226 -0.0331226 -0.104996 0.00187966 -0.03175 -0.104996 -0.0202558 -0.0591094 -0.104996 0.00857444 -0.0489345 -0.104996 4.65996e-06 -0.0387476 -0.104996 0.0263383 -0.0350184 -0.104996 0.0239101 -0.023903 -0.104996 0.027068 -0.0193726 -0.104996 0.0303155 -0.0137476 -0.104996 0.0239101 -0.00874756 -0.104996 0.0303155 -0.0212476 -0.104996 0.0341548 -0.0250186 -0.104996 0.0364101 -0.00874756 -0.104996 0.0382523 -0.00187256 -0.104996 0.0368797 -0.00324515 -0.104996 0.0409267 -0.00899756 -0.104996 0.0322233 0.0279042 -0.104996 0.0350047 0.00375244 -0.104996 0.0364101 0.00875244 -0.104996 0.0335631 0.0156274 -0.104996 0.0340655 0.0175024 -0.104996 0.0335631 0.0193774 -0.104996 0.0303155 0.0212524 -0.104996 0.0284405 0.02075 -0.104996 0.0239101 0.00875244 -0.104996 0.0284405 0.0142548 -0.104996 0.0128853 0.0462536 -0.104996 0.010649 0.0476909 -0.104996 0.0142841 0.0453032 -0.104996 0.00375466 0.0350024 -0.104996 0.00187966 0.03825 -0.104996 0.00522327 0.0507954 -0.104996 -0.00399382 0.0549676 -0.104996 4.65996e-06 0.0387524 -0.104996 -0.0129168 0.0577749 -0.104996 -0.0202558 0.0591143 -0.104996 -0.0254441 0.0594147 -0.104996 -0.0276473 0.0431336 -0.104996 -0.035892 0.0560846 -0.104996 -0.0356651 0.0554798 -0.104996 -0.0260514 0.0363618 -0.104996 -0.0270452 0.0329736 -0.104996 -0.0340562 0.0175024 -0.104996 -0.0284312 0.0142548 -0.104996 -0.0321812 0.0142548 -0.104996 -0.0335538 0.0156274 -0.104996 -0.0265562 0.0175024 -0.104996 -0.0270586 0.0193774 -0.104996 -0.0321812 0.02075 -0.104996 -0.03454 0.0237148 -0.104996 -0.0335538 0.0193774 -0.104996 -0.0284312 -0.01425 -0.104996 -0.0303062 -0.0137476 -0.104996 -0.0364008 -0.00874756 -0.104996 -0.0335538 -0.0156226 -0.104996 -0.0335538 -0.0193726 -0.104996 -0.0321812 -0.0207452 -0.104996 -0.0291249 -0.0301153 -0.104996 -0.0270586 -0.0193726 -0.104996 -0.0239008 -0.00874756 -0.104996 -0.0276473 -0.0431287 -0.104996 -0.0270452 -0.0329687 -0.104996 -0.034004 -0.0580733 -0.104996 -0.00858492 -0.0565591 -0.104996 -0.00187034 -0.0382452 -0.104996 -0.00874534 -0.036403 -0.104996 -0.0193703 -0.0270609 -0.104996 -0.0239008 -0.023903 -0.104996 -0.0239008 -0.036403 -0.104996 -0.0212453 -0.0303084 -0.104996 -0.0193703 -0.033556 -0.104996 -0.0239008 0.0239079 -0.104996 -0.0193703 0.0270657 -0.104996 -0.0239008 0.00875244 -0.104996 -0.00874534 0.00875244 -0.104996 -0.0174953 -0.0265584 -0.104996 -0.0193703 0.0335609 -0.104996 -0.0239008 0.0364079 -0.104996 -0.0174953 0.0265633 -0.104996 -0.0156203 0.0270657 -0.104996 -0.00874534 0.0364079 -0.104996 -0.0137453 0.0303133 -0.104996 -0.00874534 0.0239079 -0.104996 -0.00874534 -0.00874756 -0.104996 0.00875466 -0.00874756 -0.104996 -0.00874534 -0.023903 -0.104996 0.00875466 -0.023903 -0.104996 0.0156297 -0.033556 -0.104996 0.0175047 -0.0340584 -0.104996 0.00875466 -0.036403 -0.104996 0.0207523 -0.0321834 -0.104996 0.0239101 -0.036403 -0.104996 0.0156297 0.0335609 -0.104996 0.00875466 0.0364079 -0.104996 0.0137547 0.0303133 -0.104996 0.0193797 -0.0270609 -0.104996 0.0175047 -0.0265584 -0.104996 0.00875466 0.00875244 -0.104996 0.0207523 0.0284383 -0.104996 0.0239101 0.0239079 -0.104996 0.0239101 0.0364079 -0.0967958 -0.0293124 0.00577735 -0.0967958 -0.0292195 0.0263418 -0.0967958 -0.0301759 0.00923832 -0.0967958 -0.0326373 0.0238071 -0.0967958 -0.0278125 0.0261253 -0.0967958 0.0263547 -0.0312794 -0.0967958 -0.0282721 0.00965973 -0.0967958 -0.0293124 -0.00577247 -0.0967958 -0.0318321 -0.00759644 -0.0967958 -0.0318321 0.00760132 -0.0967958 -0.0266174 -0.0253468 -0.0967958 -0.0403953 2.44063e-06 -0.0967958 0.00459606 -0.0401623 -0.0967958 -0.0294727 -0.0061136 -0.0967958 -0.0300577 -0.00678421 -0.0967958 0.00314083 -0.0403122 -0.0967958 0.0263604 -0.0313621 -0.0967958 0.0152928 -0.0374181 -0.0967958 0.0153904 -0.0373531 -0.0967958 0.0171165 -0.0369221 -0.0967958 0.0261929 -0.0327375 -0.0967958 0.0394824 0.00718693 -0.0967958 0.0371564 0.00871694 -0.0967958 0.0307598 -0.00708935 -0.0967958 -0.0301759 -0.00923344 -0.0967958 -0.0375391 0.014923 -0.0967958 0.0213707 -0.0377718 -0.0967958 0.0293217 0.00577735 -0.0967958 0.0305959 -0.00704682 -0.0967958 0.030067 0.00678909 -0.0967958 0.0263598 0.0313628 -0.0967958 0.0262546 0.0325391 -0.0967958 0.00477854 0.0403305 -0.0967958 -0.0374179 -0.0121367 -0.0967958 0.0282168 -0.0233017 -0.0967958 0.0263873 0.0237817 -0.0967958 0.0263547 0.0239771 -0.0967958 0.0190148 0.0384199 -0.0967958 0.0352688 0.0103832 -0.0967958 0.00480466 0.0404529 -0.0967958 0.0152047 0.0376354 -0.0967958 -0.0300128 -0.00918835 -0.0967958 0.0282814 -0.00965485 -0.0967958 0.0271154 -0.0232794 -0.0967958 0.0280547 -0.0232794 -0.0967958 0.0301853 -0.00923344 -0.0967958 0.0328518 -0.0231486 -0.0967958 0.0352688 -0.0103783 -0.0967958 0.0337937 -0.0221439 -0.0967958 0.00480466 -0.0446862 -0.0967958 0.0115048 -0.0453622 -0.0967958 0.0140652 -0.0436198 -0.0967958 0.00480466 -0.040448 -0.0967958 0.0371564 -0.00871206 -0.0967958 0.0357347 -0.00863964 -0.0967958 -0.00834534 -0.0482787 -0.0967958 -0.0110453 -0.0341258 -0.0967958 0.0282814 0.00965973 -0.0967958 -0.00664534 -0.030549 -0.0967958 -0.00832476 -0.0314258 -0.0967958 0.00304089 0.0404255 -0.0967958 -0.00832476 0.0314307 -0.0967958 -0.00664534 0.0305539 -0.0967958 -0.00637803 0.0494847 -0.0967958 -0.00649251 0.0492864 -0.0967958 -0.00802476 0.048364 -0.0967958 0.0282168 0.0233066 -0.0967958 0.0313755 0.00933998 -0.0967958 0.0265018 0.0235834 -0.0967958 -0.036883 -0.0164735 -0.0967958 -0.0352595 -0.0103783 -0.0967958 -0.0292195 -0.0263369 -0.0967958 -0.0305918 -0.0259584 -0.0967958 -0.00649251 -0.0492815 -0.0967958 0.00146376 -0.0509941 -0.0967958 0.00224672 -0.0504313 -0.0967958 -0.0237673 0.0225016 -0.0967958 -0.0282721 -0.00965485 -0.0967958 -0.0191866 -0.0210528 -0.0967958 0.00300466 0.0485604 -0.0967958 -0.00634534 0.0503111 -0.0967958 0.00283884 0.0494921 -0.0967958 0.0362792 0.0177878 -0.0967958 0.00496918 -0.0456143 -0.0967958 0.00801887 -0.0473368 -0.0967958 -0.00816947 -0.0482992 -0.0967958 -0.00664534 -0.0491555 -0.0967958 0.00283884 -0.0494872 -0.0967958 -0.0191866 0.0210577 -0.0967958 -0.0108785 -0.0331913 -0.0967958 0.00304089 -0.0404206 -0.0967958 -0.00927986 -0.0315927 -0.0967958 -0.00927986 0.0315976 -0.0967958 -0.00634534 -0.0300294 -0.0967958 0.0280547 0.0232843 -0.0967958 0.0291616 0.00920471 -0.0967958 0.0150839 0.0422197 -0.0967958 -0.00346528 -0.0530002 -0.0967958 -0.00261791 -0.0528031 -0.0967958 -0.00649251 -0.0248286 -0.0967958 -0.0108785 0.0465181 -0.0967958 0.0140652 0.0436247 -0.0967958 -0.0102545 -0.0474879 -0.0967958 -0.00927986 -0.0481118 -0.0967958 -0.0110453 -0.0455787 -0.0967958 -0.0123842 0.023847 -0.0967958 -0.015007 0.0234009 -0.0967958 -0.00637803 0.0302296 -0.0967958 -0.00802476 -0.0239062 -0.0967958 -0.00816947 -0.0238462 -0.0967958 -0.0169239 0.0220539 -0.0735007 0.0452287 -0.0086634 -0.0480926 0.0272547 0.0571974 -0.0508092 0.0267092 0.0546941 -0.0508401 0.0284541 0.0546649 -0.055252 0.0284536 0.0500155 -0.0574747 0.0272547 0.047346 -0.0592586 0.0284534 0.0450101 -0.0613206 0.0266681 0.0420546 -0.0634384 0.0266547 0.0386714 -0.0628292 0.0284537 0.0396857 -0.0635394 0.0267092 0.0384996 -0.0637561 0.0269328 0.0381278 -0.0645769 0.0286571 0.0366734 -0.0675597 0.0305248 0.0306307 -0.066868 0.0271172 0.0321576 -0.0672466 0.0267092 0.0313332 -0.0701972 0.0266892 0.0237445 -0.0702095 0.0267126 0.023707 -0.0702366 0.0268047 0.0236241 -0.0687159 0.0266547 0.0278533 -0.0702797 0.0280547 0.0234917 -0.0700959 0.0314169 0.0240507 -0.0703145 0.0329175 0.0233843 -0.0734304 0.0427401 0.00926115 -0.0732078 0.0407802 0.0109249 -0.0726036 0.0380165 0.014492 -0.0720795 0.0383321 0.016972 -0.0706784 0.0340446 0.0222256 -0.0737822 0.0453047 -0.00569492 -0.0737664 0.0402707 -0.00590191 -0.0732016 0.0407493 -0.0109628 -0.0729604 0.039979 -0.0125079 -0.0734846 0.0397332 -0.00880289 -0.072612 0.0380329 -0.0144437 -0.0720795 0.0383321 -0.0169671 -0.0720388 0.0368849 -0.0171444 -0.0706784 0.0340446 -0.0222207 -0.0700301 0.0345765 -0.024243 -0.0703138 0.0329143 -0.0233816 -0.0702336 0.0325155 -0.0236286 -0.0687389 0.0322231 -0.0277899 -0.0702655 0.0282108 -0.0235304 -0.0702761 0.028136 -0.023498 -0.0702797 0.0280547 -0.0234868 -0.0702764 0.0270376 -0.023497 -0.0702366 0.0268047 -0.0236193 -0.0673239 0.0266547 -0.0311565 -0.0687159 0.0266547 -0.0278485 -0.0672837 0.0266684 -0.0312461 -0.0672466 0.0267092 -0.0313283 -0.0661684 0.0293404 -0.0336128 -0.0668661 0.0271188 -0.0321572 -0.0664444 0.0272547 -0.0330465 -0.0645768 0.0286571 -0.0366687 -0.0645173 0.0272547 -0.0367766 -0.0634599 0.0266569 -0.03863 -0.0637649 0.0285035 -0.0381077 -0.0613796 0.0266547 -0.0419607 -0.0508955 0.0266678 -0.0546056 -0.0607013 0.0271212 -0.0429692 -0.0628291 0.0284537 -0.0396809 -0.060089 0.0272547 -0.0438506 -0.0573337 0.0284535 -0.047518 -0.0567541 0.0271176 -0.0482341 -0.0559976 0.026668 -0.0491425 -0.0559226 0.0266547 -0.049231 -0.0508092 0.0267092 -0.0546892 -0.0480926 0.0272547 -0.0571925 -0.0460579 0.0267055 -0.0589159 -0.0739958 0.0453047 2.44063e-06 -0.0739958 0.0407046 4.33666e-05 -0.0739386 0.0405969 -0.00294632 -0.0851489 0.029465 -0.0319631 -0.0858658 0.0324676 -0.0280734 -0.0858658 0.0286575 -0.0329088 -0.0853807 0.0292063 -0.0322692 -0.0858658 0.0297354 -0.0316336 -0.0855128 0.0281996 -0.0334325 -0.084039 0.0303715 -0.0308705 -0.0849119 0.0294544 -0.0319787 -0.0697567 0.0324671 0.0280789 -0.0729011 -0.0377329 -0.0144214 -0.0967958 -0.0399695 -0.00584784 -0.079696 -0.0376075 0.0147498 -0.0796397 -0.0377116 0.0144815 -0.0729115 -0.0377533 0.0143729 -0.0796397 -0.0390187 0.0104587 -0.0737853 -0.039436 0.00875405 -0.0796397 -0.0395075 0.00842553 -0.0740693 -0.0399717 0.00583768 -0.0742398 -0.040291 0.00290584 -0.0797062 -0.0399695 0.00585273 -0.0742958 -0.0403953 -4.10997e-05 -0.0796854 -0.0399302 -0.00611023 -0.0737731 -0.0394129 -0.00885375 -0.073823 -0.0395075 -0.00842134 -0.0796397 -0.0398981 -0.0063165 -0.0967958 -0.0316888 -0.0250511 -0.0867958 -0.0311991 -0.0256585 -0.0867958 -0.025893 -0.0310051 -0.086969 -0.0250489 -0.0316911 -0.0967958 -0.0200914 -0.0350448 -0.0967958 -0.0375391 -0.0149181 -0.0967958 -0.0326373 -0.0238023 -0.0797062 -0.0375391 0.014923 -0.0967958 -0.036883 0.0164784 -0.0854121 -0.0316888 0.025056 -0.0694203 -0.0303531 0.0266589 -0.0677666 -0.0262864 0.0306772 -0.0853317 -0.0254909 0.0313415 -0.0854121 -0.0250489 0.0316959 -0.0967958 -0.0200914 0.0350497 -0.0967958 -0.016659 0.0368057 -0.0661541 -0.0217156 0.0340669 -0.0804735 0.0165816 -0.03684 -0.0858657 0.016721 -0.036777 -0.083674 0.0167082 -0.0367828 -0.0967958 0.00447149 -0.0401499 -0.0967958 0.00328034 -0.0402645 -0.0772137 0.00328034 0.0402694 -0.0967958 0.00447149 0.0401547 -0.0967958 0.0153904 0.037358 -0.0858657 0.016721 0.0367818 -0.0448647 -0.0125453 -0.066909 -0.0484371 0.0149187 -0.0722363 -0.0474426 0.0284546 -0.0707533 -0.0448647 0.0272547 -0.066909 -0.0448647 0.0284547 -0.066909 -0.0482239 0.0269065 -0.0719185 -0.0489095 0.0275261 -0.0729408 -0.0474426 0.0272547 -0.0707534 -0.0481082 0.028281 -0.0717459 -0.0489215 -0.00975036 -0.0729588 -0.0496695 0.0255401 -0.0740742 -0.0495882 0.0259278 -0.073953 -0.048819 0.0259554 -0.0728059 -0.0494859 0.0262991 -0.0738004 -0.0486236 0.0263768 -0.0725145 -0.049369 -0.0107353 -0.0736261 -0.0491161 -0.00834803 -0.0732489 -0.0489366 0.00615155 -0.0729812 -0.0484371 0.00271875 -0.0722363 -0.0491004 0.0246283 -0.0732255 -0.0497818 0.0242547 -0.0742417 -0.0491162 0.0197075 -0.0732491 -0.0497846 0.00795221 -0.0742458 -0.0489369 0.0183527 -0.0729817 -0.049116 0.0125045 -0.0732488 -0.0489369 0.0138559 -0.0729817 -0.0485308 -0.0120659 -0.0723761 -0.0474453 -0.0125453 -0.0707574 -0.0480855 -0.0111162 -0.0717121 -0.0476519 -0.0113221 -0.0710654 -0.0474451 -0.0113453 -0.070757 -0.0458217 -0.0113453 -0.068336 -0.0453281 -0.0112536 -0.0676 -0.0491162 0.0197075 0.073254 -0.0497818 0.0242547 0.0742465 -0.0489374 0.0183544 0.0729873 -0.0487754 -0.0118006 0.0727458 -0.0489364 0.0138577 0.0729859 -0.0497846 0.00795208 0.0742507 -0.0489195 0.0256576 0.0729607 -0.0491135 0.0242548 0.0732499 -0.0476506 0.0272312 0.0710684 -0.0477788 0.0284109 0.0712595 -0.0485141 0.027988 0.0723561 -0.0486245 0.0263753 0.0725207 -0.0492268 0.0269707 0.0734188 -0.0474456 -0.0125453 0.0707626 -0.0458217 -0.0113453 0.0683409 -0.0448647 -0.0125453 0.0669138 -0.0453281 -0.0112536 0.0676049 -0.0461535 0.0284556 0.0688358 -0.0448647 0.0272547 0.0669138 -0.049103 -0.00871921 0.0732343 -0.0488217 -0.0100459 0.0728148 -0.049516 -0.0103001 0.0738501 -0.0490909 -0.0113308 0.0732162 -0.049116 0.000304482 0.0732538 -0.0484371 0.0050904 0.0722412 -0.0484371 0.00271875 0.0722412 -0.0967958 0.00480466 0.0446911 -0.0858658 0.00480466 0.0446911 -0.0758118 0.00480466 0.0407587 -0.0804748 0.00480466 0.0460093 -0.0789043 0.00480466 0.0469476 -0.059915 0.00480466 0.060713 -0.0662229 0.00480466 0.0537618 -0.0742122 0.00480466 0.0507066 -0.0690804 0.00480466 0.0500365 -0.0752883 0.00480466 0.0410366 -0.0558542 0.00300466 0.064469 -0.0831029 0.00300466 0.0489194 -0.0967958 0.00300466 0.0405684 -0.0858658 0.00300466 0.0485604 -0.0567252 0.00300466 0.0644268 -0.0621757 0.00300466 0.0604935 -0.0749631 0.00300466 0.0413301 -0.0697603 0.00300466 0.0555387 -0.070168 0.00300466 0.0484994 -0.0658501 0.00300466 0.0542177 -0.0658459 0.00300466 0.0579735 -0.0804735 0.0170047 0.0371185 -0.0701903 0.0170047 0.0508367 -0.0636794 0.0170047 0.0582232 -0.0574212 0.0170047 0.0637571 -0.0563206 0.0170047 0.0640618 -0.0788498 0.0170047 0.0384718 -0.0778589 0.0170047 0.0395632 -0.0773749 0.0170047 0.0376241 -0.0671176 0.0170047 0.0526403 -0.0716816 0.0170047 0.0462327 -0.0746514 0.0170047 0.0442349 -0.0769245 0.0170047 0.0407778 -0.0770508 0.0170047 0.0378262 -0.0562378 0.0152047 0.0641345 -0.0575954 0.0152047 0.0637281 -0.0789613 0.0152047 0.0376354 -0.077223 0.0152047 0.0380655 -0.075972 0.0152047 0.0390483 -0.0669272 0.0152047 0.0528822 -0.061839 0.0152047 0.058752 -0.060033 0.0152047 0.0618139 -0.0670366 0.0152047 0.0558139 -0.0858658 0.0152047 0.0414213 -0.0830994 0.0152047 0.0417279 -0.082698 0.0152047 0.0418356 -0.0714604 0.0152047 0.0465739 -0.0754009 0.0152047 0.0398793 -0.0770375 0.0152047 0.0456197 -0.0967958 0.00300466 -0.0405636 -0.0831029 0.00300466 -0.0489145 -0.0772137 0.00300466 -0.0405636 -0.0757511 0.00300466 -0.0408646 -0.0782839 0.00300466 -0.0506803 -0.0502465 0.00300466 -0.0689247 -0.0631646 0.00300466 -0.0573193 -0.0658458 0.00300466 -0.0579686 -0.0662229 0.00300466 -0.0537569 -0.0690804 0.00300466 -0.0500316 -0.0739906 0.00300466 -0.042434 -0.0792908 0.00480466 -0.0466894 -0.0858658 0.00480466 -0.0446862 -0.0772858 0.00480466 -0.040448 -0.0656764 0.00480466 -0.057534 -0.0662229 0.00480466 -0.0537569 -0.0609901 0.00480466 -0.0611934 -0.0740487 0.00480466 -0.0423326 -0.0754993 0.00480466 -0.0495989 -0.0967958 0.0152047 -0.0376305 -0.0967958 0.0152047 -0.0414165 -0.0858658 0.0152047 -0.0414165 -0.0778755 0.0152047 -0.0377952 -0.0802677 0.0152047 -0.0429256 -0.0771529 0.0152047 -0.0380975 -0.0760364 0.0152047 -0.0389713 -0.0791869 0.0152047 -0.043676 -0.0754009 0.0152047 -0.0398745 -0.0756647 0.0152047 -0.0470646 -0.0675151 0.0152047 -0.0521247 -0.0607976 0.0152047 -0.0598242 -0.0569757 0.0152047 -0.0641949 -0.0716816 0.0170047 -0.0462278 -0.079252 0.0170047 -0.0371136 -0.0787145 0.0170047 -0.0386037 -0.0761357 0.0170047 -0.0386673 -0.0756358 0.0170047 -0.0394269 -0.0701904 0.0170047 -0.0508317 -0.0574214 0.0170047 -0.0637521 -0.0619827 0.0170047 -0.0585954 -0.0671176 0.0170047 -0.0526355 -0.0653153 0.0170047 -0.0565558 -0.0858658 0.0115048 -0.0453622 -0.0967958 0.00889863 -0.0469986 -0.0757998 0.0110395 -0.0516915 -0.0836266 0.0140441 -0.0438777 -0.0858658 0.0140652 -0.0436198 -0.0718957 0.0111416 -0.0553485 -0.0733636 0.0130889 -0.0534539 -0.0676072 0.0112069 -0.0590793 -0.0492022 0.0100047 -0.0728299 -0.0537885 0.010969 -0.0698112 -0.0584954 0.0110871 -0.0664427 -0.063335 0.0075798 -0.0627906 -0.0774033 0.00835734 -0.051344 -0.0716147 0.00793392 -0.0562881 -0.0674831 0.0093793 -0.0593741 -0.0824923 0.00882451 -0.0476728 -0.0808401 0.00868842 -0.0485825 -0.0804652 0.00865172 -0.0488401 -0.0794824 0.00855501 -0.0495824 -0.0839863 0.00889033 -0.047205 -0.0811148 0.0107422 -0.0471913 -0.0673851 0.00770334 -0.0596161 -0.0758201 0.00920826 -0.0523861 -0.0777295 0.0109548 -0.0498445 -0.0795191 0.0136312 -0.0466199 -0.0798386 0.0108298 -0.0480448 -0.0825216 0.0139763 -0.0442948 -0.0826723 0.0106476 -0.0464733 -0.0844245 0.010581 -0.0460704 -0.0967958 -0.000577827 -0.0519315 -0.0858659 -0.000577827 -0.0519315 -0.0805692 -0.0028091 -0.0539494 -0.0535593 -0.00615815 -0.0699563 -0.0528761 -0.008382 -0.0704032 -0.0673089 -0.00380125 -0.0604824 -0.0759676 -0.000713553 -0.0553557 -0.0778654 -0.00300655 -0.0550241 -0.0740893 -0.00327566 -0.056887 -0.071503 -0.00361211 -0.0581496 -0.0838958 -0.00264396 -0.0530522 -0.0829684 -0.00267332 -0.053237 -0.0803427 0.00125553 -0.0525016 -0.0667216 -0.00317487 -0.0608131 -0.0715781 -0.000595101 -0.057746 -0.0759536 0.000902634 -0.054955 -0.0703935 0.000575064 -0.0582806 -0.0714914 -0.00325091 -0.0581157 -0.057595 -0.00319792 -0.0671203 -0.058306 0.000299403 -0.0666111 -0.0858658 0.0230063 0.0362499 -0.0858658 0.0235588 0.0357122 -0.0967958 0.0256574 0.033558 -0.0858658 0.0256574 0.033558 -0.0858658 0.0222264 0.0369895 -0.0967958 0.0213707 0.0377767 -0.0858658 0.0218172 0.0373691 -0.0672505 0.0240915 0.0577185 -0.067036 0.0241962 0.0579491 -0.0665678 0.0244983 0.0584344 -0.0658156 0.0244759 0.0592579 -0.0655854 0.0242842 0.0595246 -0.0683067 0.020066 0.0572759 -0.0651095 0.0199496 0.0605847 -0.0653408 0.0241226 0.0597973 -0.0641748 0.0238253 0.0610105 -0.0698673 0.0239541 0.0545594 -0.0685478 0.0233176 0.0563198 -0.0774043 0.0229783 0.0429548 -0.0757715 0.0230913 0.0457915 -0.0759407 0.0245838 0.0447171 -0.0755695 0.0248873 0.0452612 -0.0735572 0.0248019 0.0488882 -0.079599 0.0251364 0.0378905 -0.0795809 0.0251337 0.0379184 -0.0793267 0.0250976 0.038316 -0.0794392 0.0241468 0.0387699 -0.0805433 0.025325 0.0365352 -0.0818793 0.025655 0.0349568 -0.0824039 0.0238426 0.0361589 -0.0836879 0.0255788 0.0339638 -0.0844035 0.0238178 0.0355257 -0.0838969 0.0213974 0.0378957 -0.0792969 0.0227724 0.040075 -0.0806518 0.0211505 0.0398996 -0.0757957 0.0205186 0.0472428 -0.0789029 0.020861 0.0422058 -0.0722746 0.0202785 0.0524547 -0.069857 0.0201396 0.0555023 -0.0723953 0.0232267 0.0512337 -0.0551496 0.0242824 0.0686935 -0.0541795 0.0197622 0.0695343 -0.0777713 0.0239519 0.0416388 -0.0807115 0.0239851 0.0373417 -0.080577 0.0226059 0.0386844 -0.0822963 0.0224289 0.0375316 -0.0843586 0.02234 0.03695 -0.0967958 0.00889863 0.0470034 -0.0967958 0.0115048 0.0453671 -0.0853221 0.0088984 0.0470225 -0.0798386 0.0108298 0.0480497 -0.0818023 0.00877385 0.0480095 -0.0826723 0.0106476 0.0464782 -0.0858658 0.0115048 0.0453671 -0.0844245 0.010581 0.0460753 -0.0758201 0.00920826 0.052391 -0.0697996 0.00782185 0.0577212 -0.062559 0.00756481 0.0633972 -0.0674831 0.0093793 0.059379 -0.0641348 0.0126051 0.0619338 -0.0592375 0.0125267 0.0658715 -0.0541427 0.0125045 0.0695729 -0.0537885 0.010969 0.0698161 -0.05626 0.00751024 0.0680996 -0.0492026 0.00750491 0.0728349 -0.0688427 0.0127816 0.0578015 -0.0718957 0.0111416 0.0553534 -0.0775605 0.0134127 0.0487647 -0.0811148 0.0107422 0.0471961 -0.0777295 0.0109548 0.0498494 -0.0584954 0.0110871 0.0664475 -0.0676072 0.0112069 0.0590842 -0.0757998 0.0110395 0.0516964 -0.0773497 0.00835248 0.051396 -0.0794824 0.00855501 0.0495872 -0.0720278 0.0268131 -0.0479701 -0.0727431 0.0263557 -0.0483972 -0.0747193 0.0263827 -0.044804 -0.0733478 0.0254914 -0.0487583 -0.0645409 0.0267827 -0.0580646 -0.0645699 0.0269547 -0.0566297 -0.0651854 0.0262405 -0.0586655 -0.0665678 0.0244983 -0.0584295 -0.0656334 0.0254068 -0.0590832 -0.0663637 0.0254633 -0.0582457 -0.065271 0.0267844 -0.0572612 -0.0506415 0.0269547 -0.0685885 -0.054033 0.0268255 -0.0671827 -0.0541195 0.0267743 -0.0672994 -0.0482672 0.0267492 -0.0714444 -0.0487547 0.0261646 -0.0721713 -0.0490806 0.0252902 -0.0726573 -0.0794545 0.0251154 0.0381143 -0.0816094 0.0261866 0.034632 -0.0802384 0.0259777 0.0362762 -0.0797846 0.0265108 0.0358907 -0.0811808 0.0266654 0.0341165 -0.0808341 0.0268693 0.0336995 -0.0792318 0.0268461 0.035421 -0.0778485 0.0268295 0.0373739 -0.0739974 0.0268193 0.0444249 -0.0712872 0.0269547 0.0475326 -0.0733478 0.0254914 0.0487632 -0.0752685 0.0256947 0.045101 -0.0727431 0.0263557 0.0484021 -0.065271 0.0267844 0.0572661 -0.0638474 0.0269547 0.0574229 -0.0645409 0.0267827 0.0580695 -0.0482905 0.0269547 0.0574229 -0.0732522 0.0269547 0.0440284 -0.072291 0.0269547 0.0457933 -0.0577096 0.0269547 0.0475326 -0.0667146 0.0269547 -0.0331767 -0.0722911 0.0269547 -0.0457883 -0.0638474 0.0269547 -0.057418 -0.0967958 -0.0110453 0.0455836 -0.059208 -0.0110453 0.0455836 -0.0538286 -0.0128453 -0.0520389 -0.0577604 -0.0128453 -0.0650203 -0.0533228 -0.0128453 -0.0673809 -0.0619672 -0.0128453 -0.0499787 -0.0609172 -0.0128453 -0.0538974 -0.053127 -0.0128453 -0.0637876 -0.0642481 -0.0128453 -0.0618672 -0.0818658 -0.0128453 -0.0563396 -0.0640672 -0.0128453 -0.0520787 -0.0759196 -0.0128453 -0.0574009 -0.0637858 -0.0128453 -0.0531287 -0.0703748 -0.0128453 -0.0592911 -0.0442874 -0.0128453 -0.0648202 -0.0442099 -0.0128453 -0.0627297 -0.0502583 -0.0128453 -0.060919 -0.0462412 -0.0128453 -0.0591536 -0.051027 -0.0128453 -0.0601503 -0.052077 -0.0128453 -0.059869 -0.0598672 -0.0128453 -0.0520787 -0.053127 -0.0128453 -0.0601503 -0.0608347 -0.0128453 -0.0635055 -0.0545083 -0.0128453 0.0513036 -0.0619672 -0.0128453 0.0499836 -0.0818658 -0.0128453 0.0469356 -0.0637858 -0.0128453 0.0531336 -0.0640672 -0.0128453 0.0520836 -0.0778032 -0.0128453 0.0569448 -0.0502583 -0.0128453 0.0630238 -0.0442099 -0.0128453 0.0627346 -0.0441568 -0.0128453 0.0638885 -0.054177 -0.0128453 0.0619738 -0.0619672 -0.0128453 0.0541836 -0.0601485 -0.0128453 0.0531336 -0.053127 -0.0128453 0.0601552 -0.0598672 -0.0128453 0.0520836 -0.051027 -0.0128453 0.0601552 -0.0505215 -0.0128453 0.0553855 -0.0502583 -0.0128453 0.0609238 -0.044999 -0.0128453 0.0605759 -0.0443374 -0.0128453 0.0650294 -0.0451139 -0.0128453 0.0667468 -0.051027 -0.0128453 0.0637925 -0.0476946 -0.0128453 0.0705954 -0.052077 -0.0128453 0.0640738 -0.0533848 -0.0128453 0.0673459 -0.0554403 -0.0128453 0.0662605 -0.0786542 0.0269547 0.0349303 -0.0637232 0.0263613 -0.038729 -0.0637492 0.0263816 -0.0386407 -0.0767511 0.0263811 -0.0386429 -0.0694755 0.0263547 -0.0415551 -0.0711831 0.0263547 -0.0398476 -0.0753016 0.0263547 -0.0404625 -0.0711831 0.0263547 -0.0410976 -0.0744193 0.0263547 -0.0421261 -0.0707255 0.0263547 -0.0415551 -0.0762209 0.0263547 -0.038819 -0.0694755 0.0263547 -0.03939 -0.0636967 0.0263547 -0.038819 -0.069018 0.0263547 -0.0398476 -0.0735512 0.0264171 -0.0423926 -0.0561891 0.0263612 -0.049336 -0.0708176 0.0263808 -0.0492501 -0.0597588 0.0263547 -0.0508037 -0.066286 0.0263547 -0.0547323 -0.0683326 0.0263547 -0.0521351 -0.0645172 0.0263547 -0.0520787 -0.0702273 0.0263547 -0.0494251 -0.0654227 0.0263824 -0.0549126 -0.0650074 0.026415 -0.0549946 -0.0658557 0.0263617 -0.054824 -0.0511497 0.0263613 -0.0548215 -0.062993 0.0263805 -0.0591413 -0.0625298 0.0263609 -0.0592285 -0.0460997 0.0263604 -0.0592309 -0.0638474 0.0264638 -0.0589704 -0.0462478 0.0264565 -0.058981 -0.0462412 0.0264494 -0.0589918 -0.0498686 0.0263547 -0.063244 -0.054627 0.0263547 -0.061969 -0.0542853 0.0263547 -0.063244 -0.0542853 0.0263547 -0.060694 -0.053352 0.0263547 -0.0597606 -0.052077 0.0263547 -0.059419 -0.050802 0.0263547 -0.0641773 -0.052077 0.0263547 -0.064519 -0.053352 0.0263547 -0.0641773 -0.050802 0.0263547 -0.0597606 -0.0460518 0.0263547 -0.0593154 -0.0498686 0.0263547 -0.060694 -0.049527 0.0263547 -0.061969 -0.0560292 0.0263547 -0.0646226 -0.0554012 0.0263614 -0.0647123 -0.0547747 0.0263815 -0.0647999 -0.0442465 0.0263547 -0.0646226 -0.0541759 0.0264136 -0.064882 -0.0442644 0.0263827 -0.0648036 -0.0705651 0.0271154 -0.0232794 -0.0967958 0.0269601 -0.0232998 -0.0705617 0.0269593 -0.0233001 -0.0967958 0.0268154 -0.0233598 -0.0967958 0.0266547 -0.0234526 -0.0704922 0.0264601 -0.0236334 -0.0967958 0.0265018 -0.0235786 -0.0967958 0.0263873 -0.0237769 -0.0704617 0.026375 -0.0238187 -0.0967958 0.0263547 -0.0239722 -0.0822695 0.0264396 -0.0315625 -0.0884303 0.0263599 -0.0313585 -0.0738767 0.0263547 -0.0263508 -0.0675976 0.0263547 -0.0312794 -0.0760851 0.0263547 -0.0301758 -0.0773601 0.0263547 -0.0254174 -0.0704364 0.0263547 -0.0239722 -0.0443776 -0.00780515 -0.065469 -0.0513716 -0.00780515 -0.065469 -0.044366 -0.00750515 -0.0653886 -0.0443017 -0.00707752 -0.0651417 -0.0442484 -0.00664534 -0.0648922 -0.04422 -0.0063785 -0.0645677 -0.0538664 -0.00648014 -0.0647515 -0.0442269 -0.00641495 -0.0646516 -0.0442337 -0.00646441 -0.0647303 -0.0527583 -0.00664534 -0.0648922 -0.053645 -0.00650467 -0.0647797 -0.0567977 -0.00634534 -0.0643726 -0.053127 -0.00634534 -0.0637876 -0.052077 -0.00634534 -0.064069 -0.0442052 -0.00634534 -0.0643726 -0.049977 -0.00634534 -0.061969 -0.052077 -0.00634534 -0.059869 -0.053127 -0.00634534 -0.0601503 -0.0538956 -0.00634534 -0.060919 -0.0459093 -0.00635782 -0.0593858 -0.0680002 -0.00655042 -0.0590565 -0.0460891 -0.00655042 -0.0590565 -0.0460327 -0.00645889 -0.0591568 -0.0459761 -0.00639898 -0.0592602 -0.0512714 -0.0063944 -0.0547771 -0.0513314 -0.0063574 -0.0546598 -0.0511616 -0.00655042 -0.0549912 -0.0844818 -0.00634534 -0.0504186 -0.0967958 -0.00634534 -0.0496751 -0.0630172 -0.00634534 -0.0502601 -0.0637858 -0.00634534 -0.0510287 -0.0513928 -0.00634534 -0.0545395 -0.0601485 -0.00634534 -0.0531287 -0.0559383 -0.00634534 -0.0496751 -0.0560215 -0.00637778 -0.0494805 -0.0967958 -0.00637803 -0.0494798 -0.0560774 -0.00644149 -0.0493494 -0.056826 -0.00802476 -0.0483591 -0.0967958 -0.00802476 -0.0483591 -0.0568503 -0.00816662 -0.0483002 -0.0568591 -0.00832476 -0.0482787 -0.0967958 -0.00832476 -0.0482787 -0.0568591 -0.00834534 -0.0482787 -0.0676664 -0.00832476 -0.0314258 -0.0967958 -0.00834534 -0.0314258 -0.0676676 -0.00824546 -0.0314205 -0.0967958 -0.00816947 -0.0314053 -0.0967958 -0.00802476 -0.0313454 -0.0676843 -0.00802476 -0.0313454 -0.0967958 -0.00649251 -0.030423 -0.0680768 -0.00643747 -0.0303488 -0.0680837 -0.00641857 -0.0303166 -0.0681128 -0.00636508 -0.0301814 -0.0967958 -0.00637803 -0.0302247 -0.0771351 -0.00634534 -0.0294444 -0.0750351 -0.00634534 -0.0294444 -0.0681453 -0.00634534 -0.0300294 -0.0742664 -0.00634534 -0.0265758 -0.0967958 -0.00634534 -0.0252222 -0.0967958 -0.00637803 -0.0250269 -0.0967958 -0.00664534 -0.0247026 -0.0701016 -0.00664534 -0.0247026 -0.0967958 -0.00832476 -0.0238258 -0.0703041 -0.0128342 -0.0243118 -0.0867891 -0.0128337 -0.0243083 -0.0867705 -0.0127253 -0.0240658 -0.08674 -0.0127487 -0.0240993 -0.0703327 -0.0127734 -0.0241416 -0.0868336 -0.0126442 -0.0239776 -0.0703774 -0.0124809 -0.0238744 -0.0703792 -0.012453 -0.0238633 -0.0967958 -0.0122453 -0.0238258 -0.0443776 -0.00834534 0.0654738 -0.0513605 -0.00834534 0.0654738 -0.0868359 -0.0123842 0.023847 -0.0703855 -0.0122453 0.0238307 -0.0703774 -0.0124801 0.0238794 -0.0868868 -0.0124865 0.0238813 -0.0703561 -0.0126698 0.0240066 -0.0703432 -0.0127346 0.0240837 -0.0867697 -0.0128002 0.0242024 -0.0867892 -0.012834 0.0243143 -0.0703198 -0.0128079 0.0242233 -0.0702989 -0.0128394 0.0243479 -0.0867958 -0.0128453 0.0244307 -0.0967958 -0.0122453 0.0238307 -0.070382 -0.00816861 0.0238514 -0.0967958 -0.00832476 0.0238307 -0.0967958 -0.00816947 0.0238511 -0.0967958 -0.00802476 0.0239111 -0.0967958 -0.00664534 0.0247075 -0.0967958 -0.00649251 0.0248334 -0.0967958 -0.00637803 0.0250317 -0.0967958 -0.00634534 0.0252271 -0.0700113 -0.00634534 0.0252271 -0.0750351 -0.00634534 0.025812 -0.0742664 -0.00634534 0.0265807 -0.0967958 -0.00634534 0.0300343 -0.0681453 -0.00634534 0.0300343 -0.0681128 -0.00636502 0.0301862 -0.0680987 -0.00638621 0.0302517 -0.0967958 -0.00649251 0.0304279 -0.0680549 -0.00651804 0.0304553 -0.0676843 -0.00802476 0.0313503 -0.0967958 -0.00802476 0.0313503 -0.067671 -0.00816889 0.03141 -0.0967958 -0.00816947 0.0314102 -0.0676664 -0.00832476 0.0314307 -0.0967958 -0.00834534 0.0482836 -0.0967958 -0.00816947 0.0483041 -0.0967958 -0.00832476 0.0482836 -0.0568503 -0.00816639 0.0483051 -0.056826 -0.00802476 0.048364 -0.0967958 -0.00664534 0.0491604 -0.0559383 -0.00634534 0.04968 -0.0598672 -0.00634534 0.0520836 -0.0601485 -0.00634534 0.0531336 -0.0967958 -0.00634534 0.04968 -0.0774041 -0.00634534 0.0523823 -0.0791362 -0.00634534 0.0517303 -0.0637858 -0.00634534 0.0510336 -0.0609172 -0.00634534 0.0539023 -0.0619672 -0.00634534 0.0541836 -0.0513928 -0.00634534 0.0545444 -0.0728078 -0.00634534 0.0545444 -0.0511616 -0.00655042 0.0549961 -0.0691701 -0.00644419 0.0548743 -0.0512138 -0.00645807 0.0548945 -0.0715467 -0.00635518 0.0546526 -0.0513314 -0.00635741 0.0546648 -0.0703121 -0.00638648 0.0547627 -0.0512713 -0.0063945 0.0547822 -0.045976 -0.00639894 0.0592652 -0.0460327 -0.00645885 0.0591617 -0.0538956 -0.00634534 0.0630238 -0.0602646 -0.00634534 0.0619084 -0.054177 -0.00634534 0.0619738 -0.0538956 -0.00634534 0.0609238 -0.051027 -0.00634534 0.0601552 -0.0458463 -0.00634534 0.0595131 -0.0502583 -0.00634534 0.0609238 -0.049977 -0.00634534 0.0619738 -0.0444945 -0.00634534 0.0616151 -0.0442052 -0.00634534 0.0643774 -0.051027 -0.00634534 0.0637925 -0.0514033 -0.00774261 0.0654706 -0.0443746 -0.00764984 0.0654533 -0.0515576 -0.00764545 0.0654522 -0.0442305 -0.00643906 0.0646981 -0.0442395 -0.00652046 0.0648006 -0.0442168 -0.00636621 0.0645328 -0.044223 -0.00639236 0.0646086 -0.0546644 -0.00641288 0.064654 -0.0527583 -0.00664534 0.064897 -0.044366 -0.00750515 0.0653935 -0.0967958 0.0268154 0.0233646 -0.0705617 0.02696 0.0233048 -0.0967958 0.0269601 0.0233047 -0.0967958 0.0271154 0.0232843 -0.0705651 0.0271154 0.0232843 -0.0705651 0.0280547 0.0232843 -0.0553986 0.0263614 0.0647175 -0.0442818 0.0264638 0.0649724 -0.050802 0.0263547 0.0597655 -0.052077 0.0263547 0.0594238 -0.052077 0.0263547 0.0645238 -0.050802 0.0263547 0.0641822 -0.0442465 0.0263547 0.0646274 -0.0442099 0.0263547 0.0627346 -0.0444945 0.0263547 0.0616151 -0.0542853 0.0263547 0.0632488 -0.053352 0.0263547 0.0641822 -0.0625308 0.026361 0.0592331 -0.0511498 0.0263613 0.0548262 -0.0645699 0.0264638 0.0550822 -0.0594172 0.0263547 0.0520836 -0.066286 0.0263547 0.0547372 -0.0645172 0.0263547 0.0520836 -0.0641756 0.0263547 0.0508086 -0.0619672 0.0263547 0.0495336 -0.0619672 0.0263547 0.0546336 -0.0606922 0.0263547 0.054292 -0.0708176 0.0263808 0.0492549 -0.0738493 0.0263828 0.0423127 -0.0615709 0.0263815 0.0423091 -0.0616001 0.0263613 0.0422208 -0.0735512 0.0264171 0.0423975 -0.0615425 0.0264156 0.0423947 -0.0615155 0.0264638 0.042476 -0.069018 0.0263547 0.0411024 -0.0744193 0.0263547 0.042131 -0.0713505 0.0263547 0.0404774 -0.0762209 0.0263547 0.0388239 -0.0707255 0.0263547 0.04156 -0.0616298 0.0263547 0.042131 -0.0694755 0.0263547 0.04156 -0.0637982 0.0264638 0.0384789 -0.0771704 0.0264638 0.0384789 -0.0637234 0.0263615 0.0387333 -0.0636967 0.0263547 0.0388239 -0.0858659 0.0263598 0.0313628 -0.0840998 0.0263635 0.0313867 -0.06752 0.0264638 0.0316292 -0.0967958 0.0266547 0.0234575 -0.0738767 0.0263547 0.0263557 -0.0735351 0.0263547 0.0276307 -0.0738767 0.0263547 0.0289057 -0.0760851 0.0263547 0.0250807 -0.0704364 0.0263547 0.0239771 -0.0967958 0.0263547 0.0312843 -0.0748101 0.0263547 0.029839 -0.0451139 0.0269547 0.0667468 -0.0460708 -0.0110453 0.0681738 -0.0858658 0.0256574 -0.0335531 -0.0967958 0.0258625 -0.0333322 -0.0858658 0.0213707 -0.0377718 -0.0967958 0.0236797 -0.0355882 -0.0440775 -0.00765515 -0.065211 -0.0439947 -0.0125453 -0.0648861 -0.0440897 -0.00780515 -0.0652533 -0.0456357 -0.00664534 -0.0592946 -0.0459697 -0.00681903 -0.0589892 -0.0460514 -0.0125453 -0.0589213 -0.0458913 -0.00674788 -0.0590568 -0.0442128 -0.00664534 -0.0615072 -0.0460514 0.026702 -0.0589213 -0.0460514 0.0284545 -0.0589213 -0.0459524 0.0266662 -0.0590039 -0.0445803 0.0266547 -0.0606947 -0.0439131 0.0266547 -0.0626856 -0.0439941 0.0284546 -0.0648832 -0.0439888 0.0267092 -0.0648597 -0.0442613 0.0271246 -0.0657557 -0.0440775 -0.00765515 0.0652158 -0.0448647 -0.0109842 0.0669138 -0.0440474 -0.0125453 0.0651061 -0.0442507 -0.00992804 0.0657334 -0.0439537 -0.00679534 0.0646933 -0.0439131 -0.0125453 0.0626905 -0.0440897 -0.00780515 0.0652581 -0.0440897 -0.00834534 0.0652581 -0.0438572 -0.0125453 0.0639051 -0.0440097 -0.00722753 0.0649559 -0.0447438 -0.00664534 0.0604182 -0.0442128 -0.00664534 0.0615121 -0.0439131 -0.00664534 0.0626905 -0.0447157 0.0272547 0.0666802 -0.0439888 0.0267092 0.0648645 -0.0439941 0.0284546 0.0648881 -0.0439704 0.0266686 0.064778 -0.0439133 0.0284545 0.0626892 -0.0442128 0.0266547 0.0615121 -0.044631 0.0284544 0.0606085 -0.0447438 0.0266547 0.0604182 -0.045852 0.0266547 0.0590965 -0.0929224 0.0471952 0.00900244 -0.0892966 0.0516569 0.00900244 -0.0736515 0.046112 0.00900244 -0.0737988 0.0453047 0.00900244 -0.0729168 0.0473359 0.00900244 -0.0863651 0.0549047 0.00900244 -0.0728079 0.0538047 0.00900244 -0.073229 0.0468158 0.00900244 -0.0873103 0.054599 0.00900244 -0.0729431 0.0543561 0.00900244 -0.0732588 0.0547399 0.00900244 -0.0737988 0.0453047 -0.00899756 -0.0737988 0.0452287 -0.00899756 -0.0729167 0.0473359 -0.00899756 -0.0736514 0.0461122 -0.00899756 -0.0728079 0.0538047 -0.00899756 -0.0863651 0.0549047 -0.00899756 -0.086988 0.0547797 -0.00899756 -0.0863651 0.0553047 0.00860244 -0.0744275 0.0553047 -0.00328155 -0.0700352 0.0242547 0.0572071 -0.0656848 0.0252344 0.0617007 -0.0662391 0.0288314 0.0425736 -0.0661368 0.0288405 0.0433482 -0.0851306 0.0291046 0.0323963 -0.0854628 0.0283534 0.0332632 -0.0857672 0.0269418 0.03482 -0.077499 0.0298077 0.0331148 -0.0774442 0.0297629 0.0332787 -0.0712011 0.0309734 0.0304587 -0.0722988 0.0301617 0.0323871 -0.0708691 0.0294019 0.0351107 -0.069267 0.0291559 0.0361261 -0.0680343 0.0290574 0.0364528 -0.0648413 0.028954 0.0368612 -0.0657928 0.0287731 0.0392109 -0.0630868 0.0287537 0.0398429 -0.0656544 0.028846 0.0401091 -0.0538927 0.0287716 0.0577814 -0.0554796 0.0287536 0.0502139 -0.044892 0.0287544 0.0607568 -0.0457749 0.0287545 0.059585 -0.0467663 0.0287547 0.0692111 -0.0484049 0.0285687 0.0716545 -0.0490762 0.0280059 0.0726552 -0.0498811 0.0264452 0.0738557 -0.0715643 0.0306991 0.0310178 -0.0734072 0.0294208 0.0354722 -0.0705983 0.0291523 0.0361964 -0.0722808 0.0291868 0.0368706 -0.0736975 0.0286271 0.042392 -0.072589 0.0283448 0.0465231 -0.070737 0.0287963 0.045099 -0.0741469 0.028684 0.0411219 -0.0657915 0.0288 0.0414663 -0.0615371 0.0287541 0.0422742 -0.062449 0.0288125 0.0484719 -0.064629 0.0288591 0.0494522 -0.0462414 0.0287545 0.0591587 -0.0493459 0.0287605 0.0625911 -0.0540891 0.0287796 0.0599631 -0.052076 0.0287648 0.059127 -0.0497298 0.0287581 0.0603628 -0.0491317 0.0287593 0.0619549 -0.0493763 0.0287608 0.0628731 -0.0451138 0.0287547 0.0667468 -0.0519786 0.0287585 0.0651468 -0.0520769 0.0287597 0.0648208 -0.0533228 0.0287315 0.0668897 -0.0522521 0.0287594 0.0648156 -0.0591913 0.0287974 0.0526764 -0.0583501 0.0287899 0.0532878 -0.0621881 0.0287736 0.055838 -0.0631591 0.0288398 0.0495119 -0.0627852 0.0288311 0.0493685 -0.0606404 0.0287874 0.0495722 -0.0619663 0.0288117 0.0492455 -0.0633036 0.0287772 0.0545998 -0.0654576 0.0242547 0.0622436 -0.0606759 0.0242547 0.0666201 -0.0656382 0.026174 0.0610619 -0.0701672 0.0260224 0.0558641 -0.0638303 0.0285813 0.0574564 -0.0500779 0.0256318 0.0741492 -0.0552743 0.026378 0.0701201 -0.0554335 0.0253358 0.0705326 -0.0545069 0.0280436 0.0687092 -0.059947 0.0279629 0.0642464 -0.0587391 0.0286765 0.0623558 -0.0572424 0.0287652 0.0606647 -0.0650372 0.027795 0.0593681 -0.0606375 0.0262995 0.0658121 -0.0607361 0.0252932 0.0663299 -0.0835766 0.0242547 0.0378344 -0.0807033 0.0258795 0.0384371 -0.0806363 0.0242547 0.0404053 -0.0796104 0.0242547 0.0420379 -0.0830598 0.0299046 0.0313511 -0.0837981 0.0290796 0.0323264 -0.0816914 0.0294822 0.0320896 -0.082376 0.0287109 0.033009 -0.0820102 0.0305798 0.0305322 -0.0807102 0.0301085 0.0313262 -0.0795327 0.0297194 0.0324746 -0.0758923 0.029884 0.0332805 -0.0771681 0.0271939 0.0424036 -0.0787526 0.0272711 0.0393723 -0.0777428 0.0285047 0.0375259 -0.0804519 0.0274774 0.0364323 -0.0774795 0.0257673 0.0443419 -0.0790265 0.0257924 0.0413448 -0.0817441 0.0259515 0.0371197 -0.0814957 0.0276343 0.0350934 -0.0830445 0.0260653 0.0360752 -0.0741183 0.0258706 0.0502558 -0.0737112 0.0273473 0.0483822 -0.0761262 0.0283071 0.0405641 -0.0720446 0.028719 0.0441642 -0.0742151 0.0288256 0.0397755 -0.0742251 0.0288885 0.0392218 -0.0739264 0.0289691 0.0387158 -0.0758122 0.029208 0.0362094 -0.0785453 0.0294037 0.0338362 -0.0794436 0.0288862 0.0345731 -0.0804623 0.0291474 0.0332162 -0.0827819 0.0278577 0.0340129 -0.0842442 0.0281675 0.0333805 -0.084562 0.0262376 0.0355201 -0.0680763 0.0288979 0.04431 -0.0697116 0.0288403 0.0447529 -0.066718 0.0287822 0.0506448 -0.0684836 0.0284627 0.0521714 -0.0696626 0.0275755 0.0540674 -0.0701746 0.0251655 0.0566272 -0.0741038 0.0250956 0.05113 -0.0749681 0.0242547 0.0502916 -0.0853807 0.0292063 0.0322741 -0.0858658 0.0293916 0.0320522 -0.0858658 0.0297354 0.0316385 -0.0851489 0.029465 0.031968 -0.0858658 0.0324676 0.0280783 -0.0858658 0.0242547 0.0375466 -0.0858658 0.0285802 0.0330027 -0.0858658 0.0286575 0.0329137 -0.0848377 0.0295575 0.0318609 -0.0840334 0.030376 0.0308697 -0.0829041 0.0310588 0.0300152 -0.0640098 0.0242547 0.0636475 -0.0743538 -0.0113129 0.0594797 -0.0858658 -0.01271 0.0580329 -0.0834239 -0.0112159 0.0577423 -0.0833721 -0.00819401 0.0569737 -0.0810099 -0.00818943 0.0573217 -0.0543091 -0.00870477 0.0716042 -0.0501965 0.0149626 0.0743359 -0.05496 0.0150586 0.0712003 -0.0554366 0.0242547 0.0707157 -0.0602411 0.0197538 0.0672665 -0.0570647 0.0242547 0.0695079 -0.0605873 0.0242547 0.0666948 -0.0650342 0.0198364 0.0631535 -0.0806947 0.0110211 0.0497814 -0.0816723 0.01563 0.0460897 -0.0827018 0.0242547 0.0382706 -0.0806221 0.0156282 0.0470344 -0.0690446 0.0154161 0.0597548 -0.0751555 0.0155527 0.0534393 -0.0733773 0.017772 0.054789 -0.0694915 0.0199142 0.0586985 -0.0686221 0.0107925 0.0606353 -0.0645605 0.0153018 0.0638219 -0.0770508 0.017836 0.0501486 -0.0805451 0.0200558 0.0439898 -0.0772199 0.0242547 0.0464078 -0.073214 0.015512 0.0555529 -0.0769824 0.0155871 0.0512566 -0.0815709 0.0200571 0.0428648 -0.0815386 0.0242547 0.0392675 -0.0764562 -0.00820655 0.058518 -0.0765821 -0.00340053 0.0576927 -0.0831796 0.00146365 0.0534391 -0.0832741 -0.00337772 0.0554108 -0.0809349 -0.00336982 0.0560042 -0.072135 -0.00343406 0.0598413 -0.0726574 0.00616756 0.0581341 -0.0746047 0.00140383 0.0578625 -0.076688 0.00143133 0.0565309 -0.080858 0.00147237 0.0542911 -0.0830857 0.00627908 0.0510827 -0.0843891 0.0109933 0.0479739 -0.0843374 0.0156112 0.0448528 -0.0845308 0.0242547 0.0376036 -0.0591366 0.00586724 0.0682466 -0.0585551 -0.00354766 0.0686526 -0.0637012 0.00598459 0.0648315 -0.0598462 0.0151779 0.0676547 -0.0735274 0.0199803 0.0539469 -0.0738302 0.0242547 0.0520683 -0.0771015 0.0200302 0.0489671 -0.0716152 -0.0112464 0.0605272 -0.0718617 -0.0082201 0.0603494 -0.0686769 -0.0109972 0.0619549 -0.0675331 -0.00345909 0.0624493 -0.0682345 0.00608658 0.0613858 -0.0723952 0.00137668 0.059098 -0.0729209 0.0108909 0.0569425 -0.0749579 0.0109343 0.0551611 -0.0747854 0.00620502 0.0566483 -0.0767839 0.00623984 0.0550585 -0.0768723 0.0109725 0.0532899 -0.0807785 0.00628688 0.052209 -0.0829902 0.0110162 0.048365 -0.0829 0.0156256 0.0453089 -0.084282 0.0200493 0.0414071 -0.0828041 0.0200553 0.0419373 -0.0704403 0.0350626 0.0241192 -0.0777382 0.036067 0.022377 -0.0858658 0.0368994 0.0208152 -0.0713987 0.0347281 0.0246698 -0.0816753 0.0324676 0.0280783 -0.08226 0.0324676 0.0280783 -0.0809909 0.034501 0.025036 -0.0803587 0.0350654 0.0241146 -0.0858658 0.0348481 0.0244739 -0.0797485 0.0354313 0.0234959 -0.0814182 0.0338646 0.0260319 -0.0812293 0.0341918 0.0255253 -0.0732563 0.0402653 0.0126516 -0.0858658 0.0402653 0.0126516 -0.0858658 0.0387763 0.0167534 -0.0725692 0.038975 0.0162647 -0.104696 0.0324676 0.0280783 -0.104696 0.0402653 0.0126516 -0.104696 0.0368994 0.0208152 -0.104696 0.0384217 0.0175925 -0.0858658 0.0398189 0.0140068 -0.104696 -0.0112082 0.0576432 -0.0858658 -0.00824735 0.0567722 -0.0858658 -0.00370554 0.0551784 -0.104696 0.00296908 0.0522723 -0.0858658 0.00562915 0.0509204 -0.0858658 0.0109527 0.0478552 -0.104696 0.0108072 0.0479458 -0.104696 0.0144551 0.0455496 -0.0858658 0.0146635 0.0454046 -0.0858658 0.0219016 0.0397169 -0.104696 0.0219016 0.0397169 -0.104696 -0.0341073 0.0583599 -0.104696 -0.0305994 0.0592831 -0.0873658 -0.0270037 0.0596738 -0.104696 -0.0202215 0.0594123 -0.0873658 -0.0250501 0.0597145 -0.0873658 -0.022009 0.0595847 -0.104696 -0.0128453 0.0580663 -0.0870094 -0.0145795 0.0584674 -0.104696 -0.0278989 0.0429702 -0.083077 -0.0284621 0.0312954 -0.0838658 -0.0293244 0.0303447 -0.081885 -0.0293053 0.0303631 -0.0846345 -0.0274895 0.0327669 -0.104696 -0.0293335 0.0303358 -0.0876658 -0.0278989 0.0429702 -0.0876658 -0.0271585 0.0416099 -0.104696 -0.0265523 0.0398177 -0.0876658 -0.0266371 0.0401516 -0.104696 -0.0263495 0.0363956 -0.0856467 -0.0269483 0.0339442 -0.0858658 0.0335694 -0.0264747 -0.0726453 0.0355382 -0.0233069 -0.0711793 0.034501 -0.0250312 -0.071464 0.0369347 -0.0207414 -0.0767933 0.03618 -0.0221669 -0.0790392 0.035733 -0.0229673 -0.0858658 0.0368994 -0.0208103 -0.0816051 0.0333548 -0.0267947 -0.08226 0.0324676 -0.0280734 -0.104696 0.0285802 -0.0329979 -0.104696 0.0324676 -0.0280734 -0.0858658 0.0293916 -0.0320474 -0.0858658 0.0285802 -0.0329979 -0.0858658 0.0242547 -0.0375418 -0.104696 0.0384217 -0.0175876 -0.0858658 0.0374218 -0.0197645 -0.0858658 -0.0127099 -0.058028 -0.104696 0.0169314 -0.0437579 -0.0858658 0.0200389 -0.0413071 -0.0858658 0.0169314 -0.0437579 -0.104696 0.0144551 -0.0455448 -0.0858658 0.00896966 -0.0490508 -0.104696 0.00896966 -0.0490508 -0.0858658 -0.00346084 -0.0550789 -0.104696 -0.00886252 -0.0569593 -0.104696 -0.0128453 -0.0580614 -0.0868089 -0.0141046 -0.0583575 -0.104696 -0.0202215 -0.0594074 -0.0873658 -0.0212427 -0.0595141 -0.104696 -0.0277806 -0.0596218 -0.104696 -0.0302503 -0.0593371 -0.0873658 -0.0314465 -0.0591134 -0.104696 -0.0328757 -0.0587565 -0.0873658 -0.0328757 -0.0587565 -0.0873658 -0.0351429 -0.0579346 -0.0876658 -0.0359167 -0.0553116 -0.104696 -0.0293335 -0.0303309 -0.0828983 -0.0285841 -0.0311404 -0.104696 -0.0273143 -0.0331013 -0.0870912 -0.0263569 -0.0363273 -0.0858658 -0.0293335 -0.0303309 -0.104696 -0.0263495 -0.0363908 -0.0876658 -0.0263764 -0.0388633 -0.0858658 -0.017008 0.0455479 -0.0858658 -0.0249003 0.0406246 -0.0858658 -0.0168453 0.0469356 -0.0858658 -0.0306931 0.057741 -0.0858658 -0.0311328 0.0576516 -0.0858658 -0.0202189 0.0415409 -0.0858658 -0.0255157 0.0423454 -0.0858658 -0.0188288 0.0424782 -0.0858658 -0.0177571 0.043756 -0.0858658 -0.0269308 0.0581754 -0.0818658 -0.01291 0.0457973 -0.0818658 -0.0157084 0.0399311 -0.0632538 -0.0158603 0.0397795 -0.063158 -0.0157067 0.0399328 -0.0818658 -0.0137722 0.042731 -0.0625492 -0.0148816 0.0408875 -0.0611231 -0.0136499 0.0430056 -0.0609007 -0.013521 0.0433222 -0.0818658 -0.0280195 0.0315538 -0.0688643 -0.0311235 0.0284959 -0.0818658 -0.0268852 0.032526 -0.0675776 -0.0280208 0.0315535 -0.0818658 -0.0222859 0.0358351 -0.064899 -0.0203438 0.0369729 -0.0818658 -0.0293244 0.0303447 -0.0696706 -0.0329455 0.0263682 -0.069961 -0.0335825 0.0255519 -0.0858658 -0.0329463 0.0263668 -0.0858658 -0.0415912 0.007118 -0.0738876 -0.0414411 0.00794587 -0.0733985 -0.0405246 0.0117612 -0.0858658 -0.0372268 0.0198688 -0.0727372 -0.0392604 0.0154652 -0.0858658 -0.0369239 0.0204264 -0.0858658 -0.0421953 2.44063e-06 -0.0741918 -0.042004 0.00401613 -0.0767839 0.00623985 -0.0550536 -0.0844975 0.00143081 -0.0531662 -0.0858658 0.00137254 -0.0530246 -0.0844437 0.00624905 -0.0507475 -0.0858658 0.0109527 -0.0478503 -0.0686221 0.0107925 -0.0606304 -0.0763462 -0.0112425 -0.0588356 -0.0781192 -0.0111816 -0.0583971 -0.0819975 -0.0110515 -0.0578047 -0.064637 -0.0104473 -0.0643649 -0.0709241 -0.0112014 -0.0608306 -0.0640929 -0.0103558 -0.0647224 -0.0501965 -0.00363302 -0.0743314 -0.0535247 -0.00860361 -0.0721342 -0.05496 0.0150586 -0.0711954 -0.0585551 -0.00354766 -0.0686477 -0.0682345 0.00608659 -0.0613809 -0.0694915 0.0199142 -0.0586936 -0.0645605 0.0153018 -0.063817 -0.0605874 0.0242547 -0.06669 -0.0602411 0.0197538 -0.0672616 -0.0650342 0.0198364 -0.0631486 -0.0639674 0.0242547 -0.0636827 -0.0606761 0.0242547 -0.0666153 -0.0830857 0.00627909 -0.0510779 -0.080858 0.00147237 -0.0542862 -0.0769824 0.0155871 -0.0512517 -0.0726574 0.00616756 -0.0581292 -0.0747854 0.00620502 -0.0566434 -0.0749579 0.0109343 -0.0551562 -0.0729209 0.0108909 -0.0569376 -0.0843374 0.0156112 -0.0448479 -0.0829902 0.0110162 -0.0483601 -0.0805451 0.0200558 -0.043985 -0.0768723 0.0109725 -0.053285 -0.0806221 0.0156282 -0.0470295 -0.0751555 0.0155527 -0.0534345 -0.0770508 0.017836 -0.0501437 -0.0733773 0.017772 -0.0547841 -0.073214 0.015512 -0.055548 -0.0832741 -0.00337771 -0.0554059 -0.0833721 -0.008194 -0.0569688 -0.0858658 -0.00886252 -0.0569593 -0.0858658 0.000233132 -0.0535409 -0.072135 -0.00343405 -0.0598364 -0.0765821 -0.00340052 -0.0576878 -0.0810099 -0.00818942 -0.0573168 -0.0809349 -0.00336981 -0.0559993 -0.0835608 0.0242547 -0.0378359 -0.0828041 0.0200553 -0.0419325 -0.0815709 0.0200571 -0.0428599 -0.0746047 0.00140384 -0.0578576 -0.0723952 0.00137668 -0.0590931 -0.0842229 0.0242547 -0.0376483 -0.084282 0.0200493 -0.0414022 -0.0829 0.0156256 -0.045304 -0.0816723 0.01563 -0.0460848 -0.0806947 0.0110211 -0.0497765 -0.0807785 0.00628689 -0.0522041 -0.076688 0.00143133 -0.056526 -0.0771015 0.0200302 -0.0489623 -0.0772199 0.0242547 -0.046403 -0.0738302 0.0242547 -0.0520635 -0.0699979 0.0242547 -0.0572479 -0.0554366 0.0242547 -0.0707109 -0.0501965 0.0149626 -0.074331 -0.0598462 0.015178 -0.0676498 -0.0591366 0.00586725 -0.0682417 -0.0637012 0.0059846 -0.0648266 -0.0675331 -0.00345908 -0.0624444 -0.0718617 -0.00822009 -0.0603445 -0.0764562 -0.00820654 -0.0585131 -0.0743538 -0.0113129 -0.0594748 -0.0806365 0.0242547 -0.0404006 -0.0795816 0.0242547 -0.0420827 -0.0735274 0.0199803 -0.0539421 -0.0690446 0.0154161 -0.0597499 -0.0831796 0.00146365 -0.0534343 -0.0843891 0.0109933 -0.047969 -0.0858658 -0.0170791 -0.0452722 -0.0858658 -0.0214136 -0.0580229 -0.0858658 -0.0177571 -0.0437511 -0.0858658 -0.0248934 -0.0405942 -0.0858658 -0.0281864 -0.0580838 -0.0858658 -0.0263893 -0.0439457 -0.0858658 -0.0311328 -0.0576468 -0.0858658 -0.0301022 -0.0578417 -0.0613444 -0.0137927 -0.0426822 -0.0818658 -0.0143646 -0.0416318 -0.0818658 -0.0152289 -0.0404508 -0.0628252 -0.0152262 -0.0404539 -0.0818658 -0.0176738 -0.0383712 -0.0643613 -0.0184679 -0.0379397 -0.0818658 -0.0128453 -0.0469307 -0.0581793 -0.0128453 -0.0469307 -0.0595856 -0.0130103 -0.0451208 -0.0818658 -0.013456 -0.0434896 -0.0838658 -0.0293426 -0.0303222 -0.0829058 -0.0293382 -0.0303264 -0.0858658 -0.029963 -0.0297092 -0.0818658 -0.0214314 -0.036348 -0.0654087 -0.0219868 -0.0360152 -0.0818658 -0.0245768 -0.0342991 -0.067691 -0.0283055 -0.0312934 -0.0818658 -0.0293335 -0.030331 -0.0858658 -0.040693 -0.0111573 -0.0742958 -0.0421953 2.44063e-06 -0.0858658 -0.0403835 -0.0122302 -0.0734878 -0.0406932 -0.0111588 -0.0721862 -0.0381842 -0.0179545 -0.070737 0.0287963 -0.0450941 -0.0547797 0.0287611 -0.0628712 -0.052077 0.0287648 -0.0591221 -0.0734072 0.0294208 -0.0354673 -0.0722989 0.0301617 -0.0323823 -0.0697568 0.0324671 -0.028074 -0.0678363 0.0307939 -0.0308793 -0.0670968 0.0300924 -0.032485 -0.0722233 0.0303877 -0.0317542 -0.0744582 0.0299807 -0.0330383 -0.0785453 0.0294037 -0.0338313 -0.0792557 0.0298262 -0.0323403 -0.0777239 0.0297998 -0.0330493 -0.0774442 0.0297629 -0.0332738 -0.0775532 0.0298057 -0.0330962 -0.0795327 0.0297194 -0.0324698 -0.0807102 0.0301085 -0.0313214 -0.0807895 0.0304328 -0.0307929 -0.0814143 0.0314672 -0.0294507 -0.0828916 0.031064 -0.0300031 -0.0845308 0.0242547 -0.0375984 -0.0467663 0.0287547 -0.0692062 -0.0519786 0.0287585 -0.0651419 -0.044892 0.0287544 -0.060752 -0.0491317 0.0287593 -0.06195 -0.0441526 0.0287546 -0.0637963 -0.0442868 0.0287546 -0.0648174 -0.0492461 0.02876 -0.062267 -0.0447918 0.0287547 -0.0661988 -0.0451138 0.0287547 -0.0667419 -0.0554795 0.0287536 -0.050209 -0.0591422 0.0287932 -0.0523597 -0.0665493 0.0288734 -0.0376121 -0.0664394 0.0296271 -0.0338339 -0.0685522 0.0291052 -0.0362579 -0.0741306 0.0286782 -0.0411939 -0.0693025 0.0288888 -0.0447036 -0.0718775 0.0287329 -0.0442576 -0.0729587 0.0286503 -0.0434214 -0.0722778 0.0291869 -0.0368639 -0.0732721 0.0291024 -0.0376974 -0.0708691 0.0294019 -0.0351058 -0.0709686 0.0292112 -0.036283 -0.0770825 0.0298249 -0.0331968 -0.062449 0.0288125 -0.048467 -0.064629 0.0288591 -0.0494473 -0.0661368 0.0288405 -0.0433433 -0.0661779 0.0288276 -0.0424592 -0.0630867 0.0287537 -0.0398382 -0.0656544 0.0288414 -0.040104 -0.0637771 0.0288513 -0.0498992 -0.0643082 0.0288528 -0.0504823 -0.064795 0.0288214 -0.0517968 -0.0621563 0.0288027 -0.0549146 -0.0583501 0.0287899 -0.0532829 -0.060629 0.028822 -0.0545794 -0.049342 0.0287589 -0.0613748 -0.0462414 0.0287545 -0.0591538 -0.0500648 0.0287582 -0.0599549 -0.0510495 0.0287541 -0.0548763 -0.0587391 0.0286765 -0.0623509 -0.0533228 0.0287315 -0.0668848 -0.0529088 0.0287568 -0.0646943 -0.0522633 0.0287593 -0.0648101 -0.0538927 0.0287716 -0.0577765 -0.0534065 0.0287746 -0.0594532 -0.0544214 0.0287808 -0.0603582 -0.0570239 0.0242547 -0.0695333 -0.0554335 0.0253358 -0.0705277 -0.0621881 0.0287736 -0.0558331 -0.0572424 0.0287652 -0.0606598 -0.0638303 0.0285813 -0.0574515 -0.0827015 0.0242547 -0.0382654 -0.0790265 0.0257924 -0.0413399 -0.0817441 0.0259514 -0.0371148 -0.08153 0.0242547 -0.0392719 -0.0830598 0.0299046 -0.0313462 -0.0607361 0.0252932 -0.0663251 -0.0654575 0.0242547 -0.0622387 -0.0741038 0.0250956 -0.0511251 -0.0701672 0.0260224 -0.0558592 -0.0656382 0.026174 -0.061057 -0.0701746 0.0251655 -0.0566223 -0.0656848 0.0252344 -0.0616959 -0.0552743 0.026378 -0.0701152 -0.0498811 0.0264453 -0.0738508 -0.0545069 0.0280436 -0.0687043 -0.0696626 0.0275755 -0.0540625 -0.0774795 0.0257673 -0.044337 -0.0851306 0.0291047 -0.0323913 -0.0837981 0.0290796 -0.0323215 -0.082376 0.0287109 -0.0330041 -0.0814957 0.0276343 -0.0350885 -0.0804519 0.0274774 -0.0364275 -0.0794436 0.0288862 -0.0345682 -0.0771681 0.0271939 -0.0423987 -0.0761262 0.0283071 -0.0405592 -0.0737428 0.028628 -0.042299 -0.0749274 0.0242547 -0.0503526 -0.0741183 0.0258706 -0.0502509 -0.0650372 0.027795 -0.0593633 -0.0606375 0.0262995 -0.0658072 -0.059947 0.0279629 -0.0642415 -0.0496036 0.0271646 -0.0734369 -0.0739263 0.0289692 -0.0387105 -0.0742251 0.0288885 -0.039217 -0.0758122 0.029208 -0.0362045 -0.0777428 0.0285047 -0.037521 -0.0804624 0.0291474 -0.0332114 -0.0816914 0.0294822 -0.0320847 -0.0820102 0.0305798 -0.0305274 -0.0857887 0.026744 -0.035026 -0.0842442 0.0281675 -0.0333757 -0.084562 0.0262376 -0.0355152 -0.0830445 0.0260653 -0.0360703 -0.0827819 0.0278577 -0.034008 -0.0807033 0.0258795 -0.0384322 -0.0787526 0.0272711 -0.0393674 -0.0737112 0.0273473 -0.0483773 -0.072589 0.0283448 -0.0465182 -0.0684836 0.0284627 -0.0521666 -0.066718 0.0287822 -0.0506399 -0.104846 0.0410802 -0.00899756 -0.104682 0.041025 -0.00996606 -0.104638 0.0408223 -0.0109346 -0.104996 0.0322233 -0.0278993 -0.104696 0.0407667 -0.0109197 -0.104996 0.040477 -0.0108421 -0.104616 0.0407519 -0.0112791 -0.10459 0.0406584 -0.0117051 -0.104996 0.0384267 -0.0168084 -0.104696 0.0374218 -0.0197645 -0.104996 0.0349516 -0.0237149 -0.104696 0.0335694 -0.0264747 -0.104996 0.0283532 -0.0328017 -0.104996 0.0240466 -0.0373256 -0.104696 0.0242547 -0.0375418 -0.104996 0.0167237 -0.0435387 -0.104996 0.0142841 -0.0452983 -0.104696 0.00695248 -0.0501997 -0.104996 0.00680748 -0.0499371 -0.104696 0.000233132 -0.0535409 -0.104996 0.000576048 -0.0530586 -0.104996 -0.0039491 -0.0549456 -0.104696 -0.00384183 -0.0552258 -0.104996 -0.0112868 -0.0573488 -0.104996 -0.0129168 -0.05777 -0.104996 -0.0350202 -0.0576609 -0.104996 -0.0302024 -0.059041 -0.104696 -0.0254455 -0.0597098 -0.104996 -0.0254441 -0.0594098 -0.104696 -0.0212427 -0.0595141 -0.104696 -0.0359167 -0.0553116 -0.104696 -0.0278989 -0.0429653 -0.104996 -0.03454 -0.0237099 -0.104996 -0.0410558 -0.00834311 -0.104696 -0.0413498 -0.00840286 -0.104696 -0.0421953 2.44063e-06 -0.104696 -0.0419927 0.00413274 -0.104996 -0.0410558 0.00834799 -0.104996 -0.0385708 0.0163591 -0.104996 -0.0291249 0.0301202 -0.104696 -0.0326432 0.0267411 -0.104696 -0.0250501 0.0597145 -0.104696 -0.0180747 0.059121 -0.104996 -0.0302024 0.0590459 -0.104696 -0.0302503 0.059342 -0.104996 -0.034004 0.0580782 -0.104996 -0.0350203 0.0576657 -0.104696 -0.00370554 0.0551784 -0.104996 0.00283776 0.0520025 -0.104696 0.00562915 0.0509204 -0.104696 0.00695248 0.0502046 -0.104696 0.0146635 0.0454046 -0.104996 0.0207385 0.0403306 -0.104696 0.0242547 0.0375466 -0.104996 0.0240466 0.0373305 -0.104996 0.0283532 0.0328066 -0.104696 0.0285802 0.0330027 -0.104996 0.0302678 0.0305029 -0.104588 0.0406774 0.0116505 -0.104616 0.0407519 0.011284 -0.104996 0.036632 0.020679 -0.104996 0.0381464 0.0174734 -0.104696 0.0398189 0.0140068 -0.104996 0.0397726 0.0132058 -0.104603 0.0406213 0.0117915 -0.104996 0.040477 0.010847 -0.104696 0.0407667 0.0109246 -0.104682 0.041025 0.00997095 -0.104846 0.0419201 0.00336396 -0.104696 0.041786 0.00593197 -0.104996 0.0409267 0.00900244 -0.104996 0.0417956 0.00302338 -0.104846 0.0419579 -0.00284862 -0.0740376 -0.00327842 0.0569205 -0.0714672 -0.00362152 0.0581734 -0.0858659 -0.000565576 0.0519309 -0.0805693 -0.00280934 0.0539543 -0.0703687 -0.00399292 0.058771 -0.0652602 -0.00356508 0.0617716 -0.0667216 -0.00317487 0.0608179 -0.0692883 -0.0046037 0.0593956 -0.0528858 -0.00783067 0.0704092 -0.0492022 -0.00834776 0.0728349 -0.0530466 -0.00700217 0.0703072 -0.0535017 -0.00622678 0.0700004 -0.0535593 -0.00615815 0.0699612 -0.0542926 -0.00529075 0.0694571 -0.0551981 -0.00450998 0.0688256 -0.0515068 0.000301291 0.0713328 -0.0492032 -0.00328505 0.072835 -0.0593085 0.000304041 0.0658903 -0.057595 -0.00319792 0.0671252 -0.0688479 0.000505626 0.0592408 -0.0714914 -0.00325091 0.0581206 -0.0740893 -0.00327566 0.0568919 -0.0813485 0.00132869 0.0520507 -0.0809616 -0.00278343 0.053819 -0.0803423 0.0012555 0.0525067 -0.0759676 -0.000713553 0.0553606 -0.0715781 -0.000595101 0.0577509 -0.0476918 0.0269547 -0.0705863 -0.0838969 0.0213974 -0.0378909 -0.0804732 0.0211207 -0.0400947 -0.0858658 0.0230063 -0.036245 -0.0858658 0.0222264 -0.0369847 -0.0858658 0.0218172 -0.0373642 -0.0805388 0.025324 -0.0365363 -0.0767318 0.0243339 -0.0433431 -0.0789246 0.0246466 -0.0392106 -0.0794542 0.0251153 -0.0381099 -0.0698673 0.0239541 -0.0545546 -0.0718899 0.0240311 -0.0517476 -0.0724577 0.0240637 -0.0508908 -0.0759407 0.0245838 -0.0447122 -0.0755695 0.0248873 -0.0452563 -0.0646571 0.0238957 -0.0605159 -0.0577091 0.0237261 -0.0667351 -0.0609015 0.0237658 -0.0640654 -0.0597004 0.0198326 -0.0653799 -0.0639414 0.023814 -0.0612372 -0.0639114 0.0199165 -0.0617198 -0.066345 0.0199894 -0.0593507 -0.0552127 0.0242485 -0.0686423 -0.055276 0.0242156 -0.0685956 -0.056275 0.0238846 -0.0678482 -0.0674657 0.0240249 -0.0574757 -0.0683078 0.020066 -0.0572698 -0.0680155 0.0239216 -0.0568498 -0.0685478 0.0233176 -0.0563149 -0.0723953 0.0232267 -0.0512288 -0.0757715 0.0230913 -0.0457866 -0.0769254 0.0206182 -0.045387 -0.071519 0.0202321 -0.0534436 -0.0800501 0.0210485 -0.0406029 -0.080577 0.0226059 -0.0386795 -0.0774043 0.0229783 -0.0429499 -0.0777713 0.0239519 -0.0416339 -0.0792969 0.0227724 -0.0400701 -0.0794392 0.0241468 -0.038765 -0.0822963 0.0224289 -0.0375267 -0.0807115 0.0239851 -0.0373368 -0.0824039 0.0238426 -0.036154 -0.0843586 0.02234 -0.0369451 -0.0844035 0.0238178 -0.0355208 -0.0858658 0.0236797 -0.0355882 -0.0482722 -0.0108392 -0.0714485 -0.0492022 -0.00834776 -0.07283 -0.0517893 -0.0109351 -0.068801 -0.0495341 -0.0110453 -0.0693892 -0.0490871 -0.00938031 -0.0726589 -0.052425 -0.0102674 -0.0697382 -0.0476942 -0.0110453 0.0705948 -0.0495341 -0.0110453 0.0693941 -0.0528761 -0.008382 0.0704081 -0.0528157 -0.00910065 0.0703191 -0.0490865 -0.00938253 0.072663 -0.0527638 -0.00936575 0.0702426 -0.048271 -0.0108401 0.0714515 -0.0519143 -0.0108587 0.0689901 -0.0517893 -0.0109351 0.0688059 -0.0535416 0.0269547 0.0665248 -0.0506414 0.0269547 0.0685935 -0.0482685 0.0267482 0.0714511 -0.0487555 0.0261632 0.0721774 -0.0795899 0.0251351 -0.0378995 -0.079599 0.0251364 -0.0378856 -0.0794472 0.0251143 -0.0381208 -0.079383 0.0251053 -0.0382218 -0.0783761 0.0265358 -0.037717 -0.0797798 0.0265105 -0.0358921 -0.0784928 0.026441 -0.037794 -0.0786486 0.0269547 -0.034932 -0.0816094 0.0261866 -0.0346272 -0.0802339 0.0259771 -0.0362774 -0.0792266 0.026846 -0.0354226 -0.0804036 0.0269547 -0.0331767 -0.0856066 -0.0154288 -0.0569966 -0.0858658 -0.0168453 -0.0469307 -0.084164 -0.0135715 -0.0564011 -0.0832503 -0.0130926 -0.0469307 -0.0826759 -0.0129282 -0.0562787 -0.0856186 -0.0154609 -0.0469307 -0.0846942 -0.0140169 -0.0469307 -0.0818658 -0.0132348 -0.0441671 -0.083347 -0.0135081 -0.0442456 -0.0847083 -0.0143743 -0.0444947 -0.0855954 -0.0165309 -0.0429851 -0.0855954 -0.0156896 -0.0448728 -0.0847083 -0.0169433 -0.040384 -0.083347 -0.0146058 -0.0417825 -0.0847083 -0.0153702 -0.04226 -0.0858658 -0.0174435 -0.0443186 -0.0858658 -0.0190376 -0.0422933 -0.0847083 -0.018987 -0.0390057 -0.0855954 -0.0178602 -0.0414 -0.083347 -0.0185924 -0.0381953 -0.083347 -0.0163394 -0.0397149 -0.0818658 -0.0161489 -0.0395038 -0.0858658 -0.0224401 -0.0403793 -0.0857502 -0.0247204 -0.0378899 -0.0855849 -0.0227153 -0.0385252 -0.0846942 -0.0220265 -0.0373571 -0.0846568 -0.0258865 -0.0347475 -0.0846942 -0.024912 -0.0354976 -0.0858658 -0.0202189 -0.0415361 -0.0855954 -0.019586 -0.0402362 -0.0833382 -0.021574 -0.0365899 -0.0820064 -0.0291423 -0.0305181 -0.0833382 -0.0270717 -0.0327317 -0.0818658 -0.0268925 -0.0325151 -0.0833382 -0.0244004 -0.0347685 -0.0818658 -0.0184679 -0.0379397 -0.0852337 -0.0252573 0.0360791 -0.0846942 -0.0249067 0.0355062 -0.0858658 -0.0224401 0.0403842 -0.0855849 -0.0195744 0.0402171 -0.0818658 -0.0184679 0.0379445 -0.0855849 -0.0227124 0.0385318 -0.0857088 -0.0247628 0.0376814 -0.0846942 -0.0220237 0.0373637 -0.0843694 -0.0262109 0.0341886 -0.0833382 -0.0270643 0.0327426 -0.0831637 -0.0276463 0.0321677 -0.0820429 -0.0290958 0.0305694 -0.0833382 -0.0243952 0.0347771 -0.0833382 -0.0215713 0.0365964 -0.0855954 -0.0178602 0.0414049 -0.0846942 -0.0189808 0.0389979 -0.0833471 -0.0163394 0.0397198 -0.0833382 -0.0185909 0.038197 -0.0858658 -0.0181329 0.0432217 -0.0847083 -0.0153703 0.0422649 -0.0847083 -0.0169433 0.0403889 -0.0818658 -0.0161489 0.0395086 -0.0855954 -0.016531 0.04299 -0.0833471 -0.0135081 0.0442505 -0.0833471 -0.0146058 0.0417873 -0.0818658 -0.0143646 0.0416367 -0.0856186 -0.0154609 0.0469356 -0.0855954 -0.0156897 0.0448777 -0.0847083 -0.0143743 0.0444995 -0.0818658 -0.0132348 0.0441719 -0.0858658 -0.0168453 0.0573913 -0.0832503 -0.0130926 0.0469356 -0.0826759 -0.0129282 0.0562836 -0.0846942 -0.0140169 0.0469356 -0.0847749 -0.0140999 0.0565769 -0.0873658 -0.0277806 -0.0596218 -0.0873658 -0.0270037 -0.0596689 -0.0868174 -0.0269986 -0.0595651 -0.0868174 -0.0333938 -0.0584902 -0.0863683 -0.0333095 -0.0582276 -0.0860668 -0.0348363 -0.0572502 -0.0858658 -0.0269308 -0.0581705 -0.0858658 -0.0168453 -0.0573864 -0.0858658 -0.0215062 -0.0580314 -0.0859035 -0.0312026 -0.0579734 -0.0861105 -0.0313045 -0.0584494 -0.0868174 -0.0314247 -0.0590118 -0.08598 -0.0167421 -0.0579511 -0.0861105 -0.0220616 -0.0589026 -0.0863683 -0.0220384 -0.059201 -0.0863051 -0.0166545 -0.0584298 -0.0859035 -0.0269471 -0.0585044 -0.0863683 -0.031367 -0.058742 -0.0863683 -0.0269852 -0.0592895 -0.0859035 -0.0220993 -0.058417 -0.0861105 -0.0269707 -0.0589906 -0.0868174 -0.0220171 -0.0594762 -0.060828 -0.0123823 -0.0652653 -0.0605233 -0.012649 -0.0648274 -0.0708497 -0.012372 -0.0603362 -0.0738527 -0.0128453 -0.0580614 -0.0706188 -0.0127348 -0.0598281 -0.067219 -0.0127137 -0.0613147 -0.0633073 -0.0128453 -0.0623104 -0.0554494 -0.0103703 -0.0704289 -0.049463 -0.0115282 -0.0732349 -0.0526586 -0.0101295 -0.0723259 -0.0500051 -0.0100711 -0.074045 -0.0501967 -0.00835061 -0.0743305 -0.0616252 -0.00992996 -0.0664108 -0.0588064 -0.00940965 -0.0684201 -0.0614903 -0.011017 -0.066217 -0.0492844 -0.0128453 -0.069615 -0.0537196 -0.0127852 -0.0679497 -0.0570088 -0.0127927 -0.0660947 -0.0607668 -0.0128453 -0.0635382 -0.0602077 -0.0128009 -0.0643739 -0.0585502 -0.0106821 -0.0682595 -0.0580833 -0.0118527 -0.0676037 -0.0549272 -0.0117092 -0.0696804 -0.0545577 -0.0122183 -0.0691509 -0.0739864 -0.0113186 -0.0596056 -0.0710014 -0.0118156 -0.06067 -0.0676747 -0.0119701 -0.0621242 -0.0644079 -0.0117717 -0.0640113 -0.0642333 -0.0121547 -0.0637414 -0.0676046 -0.010868 -0.0625446 -0.0677659 -0.0116193 -0.0622863 -0.0670296 -0.0107966 -0.0628782 -0.0645345 -0.0113407 -0.0642069 -0.0613266 -0.0115411 -0.0659817 -0.0486531 -0.0125018 -0.072024 -0.074036 -0.0127414 -0.0585784 -0.0742092 -0.0123999 -0.0590668 -0.0541461 -0.0125796 -0.0685609 -0.0577543 -0.0122975 -0.0671417 -0.0573881 -0.0126131 -0.0666273 -0.0611018 -0.0120064 -0.0656587 -0.0637826 -0.0126838 -0.063045 -0.0675479 -0.0122822 -0.061899 -0.0872728 -0.0155432 -0.0586638 -0.0870094 -0.0145795 -0.0584625 -0.0858004 -0.0161251 -0.0571965 -0.0858886 -0.0159982 -0.0577488 -0.0853354 -0.0146202 -0.0573723 -0.0848628 -0.0141962 -0.0566046 -0.0852919 -0.01478 -0.0567963 -0.0856732 -0.0152813 -0.05756 -0.0856101 -0.0143332 -0.0578957 -0.0859779 -0.0150543 -0.0580744 -0.0859867 -0.0128453 -0.0580614 -0.0864702 -0.0147987 -0.0583929 -0.0867918 -0.016596 -0.0587496 -0.0873658 -0.0165754 -0.0588619 -0.0743214 -0.0118772 -0.0593833 -0.0778111 -0.0128453 -0.0569382 -0.0781078 -0.0117798 -0.0583429 -0.0779298 -0.012731 -0.0575003 -0.0819692 -0.0123031 -0.0574894 -0.0780408 -0.0123524 -0.0580259 -0.0819968 -0.0116798 -0.057796 -0.0859268 -0.0127772 -0.0580446 -0.0847749 -0.0140999 -0.056572 -0.0847933 -0.013936 -0.057164 -0.0848854 -0.0140307 -0.0571978 -0.0851248 -0.0136879 -0.0577324 -0.0855401 -0.0132464 -0.0580359 -0.0841797 -0.0134214 -0.0570115 -0.0850216 -0.0135881 -0.0576987 -0.0854222 -0.0131347 -0.0580035 -0.0850636 -0.0119852 -0.0578571 -0.0834759 -0.0130378 -0.0569195 -0.0843702 -0.0130353 -0.0575595 -0.0838557 -0.012036 -0.0577694 -0.0847023 -0.0124999 -0.0578574 -0.084108 -0.011455 -0.0577604 -0.0834559 -0.013175 -0.0563014 -0.0827137 -0.0127996 -0.0568975 -0.0828108 -0.0123786 -0.0574519 -0.0836181 -0.0126281 -0.0574733 -0.082945 -0.0117557 -0.0577487 -0.083073 -0.0111357 -0.0577404 -0.0819195 -0.0127203 -0.0569368 -0.0671976 -0.0127138 0.0613321 -0.0506029 -0.00836482 0.0740721 -0.0500022 -0.0100834 0.0740458 -0.049454 -0.0115441 0.0732267 -0.0526482 -0.0101308 0.0723378 -0.0549886 -0.0117104 0.0696429 -0.0486364 -0.0125142 0.0720041 -0.0542077 -0.01258 0.0685244 -0.0740394 -0.0127374 0.0585929 -0.0706128 -0.0127349 0.0598357 -0.0701703 -0.0128453 0.0593743 -0.0669173 -0.0128453 0.0606876 -0.0604905 -0.0126493 0.0648567 -0.0598816 -0.0128453 0.0639821 -0.0564956 -0.0128453 0.065711 -0.0709955 -0.0118158 0.0606775 -0.0645607 -0.011342 0.0641952 -0.0614571 -0.0110187 0.066245 -0.0652916 -0.010548 0.0639485 -0.0601627 -0.00967766 0.0674519 -0.0708438 -0.0123722 0.0603438 -0.0677448 -0.0116201 0.062303 -0.0675267 -0.0122826 0.0619159 -0.0610688 -0.0120073 0.0656872 -0.0555108 -0.0103726 0.0703908 -0.0781118 -0.0111819 0.0584036 -0.0819975 -0.0110515 0.0578095 -0.0819697 -0.0122965 0.0574997 -0.0818658 -0.0128453 0.0563445 -0.0779243 -0.0127266 0.0575171 -0.0738527 -0.0128453 0.0580663 -0.0780343 -0.0123465 0.0580376 -0.0781005 -0.0117763 0.0583504 -0.0742109 -0.0123945 0.0590767 -0.0743218 -0.0118738 0.0593894 -0.0763461 -0.0112425 0.0588404 -0.0854222 -0.0131347 0.0580083 -0.0847933 -0.013936 0.0571689 -0.0847023 -0.0124999 0.0578623 -0.084164 -0.0135715 0.0564059 -0.0841797 -0.0134214 0.0570164 -0.0834759 -0.0130378 0.0569244 -0.0836181 -0.0126281 0.0574782 -0.0843702 -0.0130353 0.0575644 -0.0847711 -0.0117938 0.0578238 -0.0834559 -0.013175 0.0563062 -0.0827137 -0.0127996 0.0569024 -0.0838557 -0.012036 0.0577742 -0.0820635 -0.0110499 0.0578033 -0.0819968 -0.0116758 0.0578018 -0.082945 -0.0117557 0.0577536 -0.0819205 -0.0127154 0.0569527 -0.0828108 -0.0123786 0.0574568 -0.0869925 -0.0270014 0.0596266 -0.0873658 -0.0305994 0.0592831 -0.0866158 -0.0350607 0.0577561 -0.0869925 -0.0334112 0.0585491 -0.0858658 -0.0221252 0.0580884 -0.0858658 -0.0245674 0.0582079 -0.0859626 -0.0269566 0.0587048 -0.0858658 -0.0337973 0.0568744 -0.0858658 -0.0345297 0.0565707 -0.0867918 -0.016596 0.0587545 -0.0873658 -0.0165754 0.0588668 -0.0873658 -0.0180747 0.059121 -0.0863051 -0.0166545 0.0584346 -0.0865101 -0.0313904 0.0588562 -0.0862329 -0.0313384 0.0586128 -0.0869925 -0.0220127 0.0595376 -0.0865101 -0.0269907 0.059406 -0.0865101 -0.0220298 0.0593174 -0.0862329 -0.0220491 0.0590691 -0.08598 -0.0167421 0.0579559 -0.0859626 -0.0220842 0.0586172 -0.0862329 -0.0269786 0.0591574 -0.0859626 -0.0312436 0.0581697 -0.0860668 -0.0348363 0.0572551 -0.0869925 -0.0314366 0.0590721 -0.0865101 -0.0333437 0.0583388 -0.0873658 -0.0314465 0.0591183 -0.0859268 -0.0127772 0.0580495 -0.0850217 -0.0135881 0.0577036 -0.0851248 -0.0136879 0.0577373 -0.0859779 -0.0150543 0.0580793 -0.0848628 -0.0141962 0.0566095 -0.0852919 -0.01478 0.0568012 -0.0853354 -0.0146202 0.0573772 -0.0856066 -0.0154288 0.0570015 -0.0858886 -0.0159982 0.0577537 -0.0858004 -0.0161251 0.0572014 -0.0859867 -0.0128453 0.0580663 -0.0864702 -0.0147987 0.0583978 -0.0855401 -0.0132464 0.0580408 -0.0848854 -0.0140307 0.0572027 -0.0856101 -0.0143332 0.0579005 -0.0856732 -0.0152813 0.0575649 -0.0818937 -0.0293106 0.030358 -0.0847113 -0.0263944 0.0343464 -0.0833794 -0.027684 0.0322224 -0.0835326 -0.027793 0.0321566 -0.0818894 -0.029308 0.0303606 -0.0860545 -0.0259722 0.0365732 -0.0863358 -0.0258389 0.0377744 -0.0853193 -0.0268377 0.0341169 -0.0870542 -0.0263674 0.0362477 -0.0865412 -0.0262583 0.0364268 -0.0856727 -0.02554 0.0366613 -0.085444 -0.0250357 0.0366825 -0.086393 -0.025854 0.0389391 -0.0867658 -0.0261375 0.0389006 -0.0874986 -0.0262856 0.0375347 -0.0849997 -0.0266494 0.0342547 -0.0838478 -0.0279605 0.0319838 -0.0861069 -0.0254846 0.0389892 -0.0859335 -0.0253148 0.0378577 -0.0852517 -0.0259071 0.0354817 -0.0870983 -0.0263549 0.0363487 -0.0868973 -0.0261779 0.0376585 -0.0861069 -0.0263371 0.0419777 -0.086393 -0.0274568 0.0432573 -0.0867658 -0.0276967 0.0431016 -0.0867658 -0.0269384 0.0417085 -0.0867658 -0.0264044 0.040215 -0.0876658 -0.0263764 0.0388682 -0.0861069 -0.0257687 0.0403881 -0.0859922 -0.0252493 0.0390211 -0.0858658 -0.0245928 0.0391102 -0.0876658 -0.0359167 0.0553164 -0.0868305 -0.0358201 0.0555452 -0.0861069 -0.0271441 0.0434604 -0.0858808 -0.0347635 0.05642 -0.0858658 -0.0263893 0.0439506 -0.0859004 -0.0348618 0.0563523 -0.0859772 -0.0350832 0.0561933 -0.0873658 -0.0351429 0.0579395 -0.0870928 -0.0353738 0.0577854 -0.0868137 -0.0353301 0.0577181 -0.0859711 -0.0348712 0.0570115 -0.0875278 -0.0361985 0.0561211 -0.0875024 -0.0362071 0.0562968 -0.0871421 -0.0361653 0.0564453 -0.0858658 -0.0345705 0.0565484 -0.0860668 -0.0349789 0.0571774 -0.0863505 -0.0355132 0.0571468 -0.0861534 -0.0355052 0.056478 -0.0863492 -0.0357176 0.0562146 -0.0873658 -0.0353874 0.0578064 -0.0871543 -0.0359239 0.0572305 -0.0869157 -0.0359204 0.0571173 -0.0868411 -0.0356669 0.0574418 -0.0866158 -0.035278 0.0576379 -0.086393 -0.0355901 0.0557815 -0.0861835 -0.035398 0.0559478 -0.0860028 -0.0351357 0.0561541 -0.0860194 -0.0352194 0.0567526 -0.0874012 -0.036138 0.0558352 -0.0869882 -0.0361261 0.0563257 -0.0872986 -0.0361787 0.0565613 -0.0874061 -0.0360113 0.0571131 -0.0873886 -0.0358905 0.0573163 -0.0865827 -0.0356104 0.0573115 -0.0864734 -0.0357886 0.0568213 -0.0866846 -0.0358756 0.0569792 -0.0866454 -0.0359666 0.0565007 -0.0868413 -0.0360612 0.0562057 -0.0865837 -0.0358611 0.055977 -0.0871101 -0.0359795 0.0555911 -0.0872528 -0.0360717 0.0557081 -0.0856249 -0.0269591 -0.0339112 -0.0870507 -0.0263684 -0.0362349 -0.0858171 -0.0246512 -0.0383302 -0.083578 -0.0271395 -0.0328101 -0.0863356 -0.025839 -0.0377683 -0.0865383 -0.0262593 -0.0364142 -0.0871732 -0.0263353 -0.0365242 -0.0874982 -0.0262856 -0.0375284 -0.0827012 -0.0285273 -0.0311914 -0.0835157 -0.0278073 -0.032131 -0.0845694 -0.0275268 -0.032693 -0.0852998 -0.0268487 -0.0340831 -0.0855913 -0.0269759 -0.0338682 -0.0854416 -0.0250382 -0.03667 -0.0851494 -0.0253472 -0.0358567 -0.0855359 -0.0252938 -0.0366675 -0.086393 -0.025854 -0.0389342 -0.0858658 -0.0245928 -0.0391053 -0.0855574 -0.0249181 -0.0370568 -0.0859333 -0.0253149 -0.0378516 -0.0845699 -0.0262636 -0.0343389 -0.0846957 -0.0264088 -0.034312 -0.083364 -0.0276996 -0.0321963 -0.0849824 -0.0266617 -0.0342204 -0.0856705 -0.025542 -0.0366488 -0.0860521 -0.0259735 -0.0365607 -0.086897 -0.0261779 -0.0376523 -0.0867658 -0.0261375 -0.0388957 -0.0876658 -0.0266312 -0.0401251 -0.0859922 -0.0252493 -0.0390162 -0.0861069 -0.0254846 -0.0389843 -0.0876658 -0.027154 -0.0415948 -0.0867658 -0.0269338 -0.0416931 -0.0876658 -0.0278989 -0.0429653 -0.0867658 -0.0276967 -0.0430967 -0.0861069 -0.0257623 -0.0403596 -0.0867658 -0.0263984 -0.0401879 -0.086393 -0.0274568 -0.0432525 -0.0861069 -0.0271441 -0.0434555 -0.0858658 -0.0255103 -0.0423285 -0.0861069 -0.0263321 -0.0419616 -0.085977 -0.0269118 -0.0436064 -0.0860028 -0.0351357 -0.0561492 -0.0863935 -0.0355904 -0.0557763 -0.0866251 -0.0357331 -0.0556375 -0.086977 -0.0358643 -0.0554825 -0.0874438 -0.0359252 -0.0553501 -0.0865837 -0.0358611 -0.0559721 -0.0862936 -0.0356627 -0.0566464 -0.0874537 -0.0361677 -0.0566662 -0.087021 -0.0360835 -0.0567731 -0.0868411 -0.0356669 -0.0574369 -0.0866454 -0.0359666 -0.0564958 -0.0871421 -0.0361653 -0.0564404 -0.0864791 -0.0357324 -0.0558691 -0.0866158 -0.035278 -0.057633 -0.0863505 -0.0355132 -0.0571419 -0.0860668 -0.0349789 -0.0571725 -0.0858908 -0.0347191 -0.0567724 -0.0860637 -0.0352407 -0.0560689 -0.0867053 -0.035972 -0.0560835 -0.0861534 -0.0355052 -0.0564731 -0.0860566 -0.035326 -0.056305 -0.0860194 -0.0352194 -0.0567477 -0.0861594 -0.0353799 -0.0569516 -0.0869157 -0.0359204 -0.0571124 -0.0876308 -0.0360208 -0.0554945 -0.0874012 -0.036138 -0.0558304 -0.0875523 -0.0361754 -0.0559556 -0.0872528 -0.0360717 -0.0557033 -0.0871101 -0.0359795 -0.0555862 -0.0868413 -0.0360612 -0.0562008 -0.0864734 -0.0357886 -0.0568164 -0.0873994 -0.0359721 -0.0571811 -0.087374 -0.0357102 -0.0575336 -0.0858658 -0.0345297 -0.0565658 -0.0858658 -0.0345705 -0.0565435 -0.0859711 -0.0348712 -0.0570066 -0.0863051 -0.0351481 -0.0574331 -0.0873658 -0.0353874 -0.0578015 -0.0868137 -0.0353301 -0.0577132 -0.0866158 -0.0350607 -0.0577512 -0.0885196 0.0543285 2.44233e-06 -0.0863651 0.0553047 -0.00859756 -0.0868803 0.0552376 -0.00860791 -0.087789 0.0550436 2.44232e-06 -0.0872595 0.0550949 -0.00861547 -0.0876497 0.0548408 -0.00862319 -0.0877766 0.0547259 0.00863057 -0.0868014 0.0553047 2.44031e-06 -0.0870295 0.0551917 0.00861577 -0.0950449 0.0452287 -0.00899756 -0.0737667 0.0436036 -0.00925799 -0.0734985 0.0409937 -0.0111801 -0.0858658 0.0402653 -0.0126467 -0.104696 0.0402653 -0.0126467 -0.104603 0.0406213 -0.0117866 -0.0735513 0.0412656 -0.0108309 -0.0736681 0.0421431 -0.010012 -0.0734975 0.0409894 0.011191 -0.0735513 0.0412656 0.0108358 -0.102146 0.0413662 0.0107208 -0.0996972 0.0423372 0.00988045 -0.0738679 0.0552657 0.00877498 -0.0863651 0.0552799 0.00874089 -0.0863651 0.0551875 0.00888528 -0.0863651 0.0550431 0.00897772 -0.0735931 0.055001 0.00899082 -0.0736539 0.0550831 0.00896044 -0.0868486 0.0551211 0.00888891 -0.0871128 0.0547212 0.00900244 -0.0868715 0.0552079 0.00875715 -0.0873448 0.0550114 0.00876402 -0.0873628 0.0550398 0.0086224 -0.0874649 0.0549773 0.00862442 -0.087688 0.0546359 0.00889506 -0.0873001 0.054933 0.00889224 -0.0872346 0.0548178 0.00897595 -0.0877527 0.0541133 0.00900244 -0.0877515 0.0547004 0.00876985 -0.0952988 0.0455343 0.00864821 -0.0894124 0.0517356 0.00897717 -0.08952 0.0518087 0.00889753 -0.0878735 0.0541844 0.00897709 -0.0879858 0.0542505 0.00889719 -0.088064 0.0542965 0.00877427 -0.0910135 0.0493441 0.00900244 -0.0912226 0.0495137 0.00889825 -0.0912932 0.049571 0.00877648 -0.0911218 0.049432 0.00897733 -0.0931143 0.0473823 0.0088994 -0.0931794 0.0474458 0.00877886 -0.0950932 0.0457071 0.00864768 -0.0951329 0.0453346 0.00897797 -0.0930217 0.0472921 0.0089776 -0.095215 0.0454334 0.00890103 -0.0932073 0.047473 0.00864336 -0.0895951 0.0518598 0.00877497 -0.0896262 0.0518809 0.00863782 -0.0880962 0.0543155 0.00863683 -0.0984084 0.0429976 0.00950538 -0.096164 0.0444053 0.00906775 -0.104589 0.0406824 0.0116285 -0.102737 0.0412797 0.0107264 -0.102235 0.0414105 0.0106453 -0.0952732 0.0455035 0.00878225 -0.0997416 0.0423926 0.00983233 -0.103312 0.0410068 0.0111666 -0.099786 0.042437 0.00976776 -0.0950449 0.0452287 0.00900244 -0.0962391 0.0444994 0.00903286 -0.0974887 0.0438427 0.00903117 -0.0974371 0.0437979 0.00913067 -0.0973738 0.0437282 0.00920621 -0.0998259 0.0424651 0.00969203 -0.098072 0.0434982 0.00905612 -0.0735931 0.055001 -0.00898594 -0.0863651 0.0551875 -0.0088804 -0.0863651 0.0552799 -0.00873601 -0.0740264 0.0553047 -0.00859756 -0.0873455 0.055011 -0.00875915 -0.0863651 0.0550431 -0.00897284 -0.0872352 0.0548174 -0.00897107 -0.0872205 0.0546595 -0.00899756 -0.0877521 0.0546998 -0.00876497 -0.0880962 0.0543155 -0.00863195 -0.0873628 0.0550398 -0.00861752 -0.0879858 0.0542505 -0.00889231 -0.0876886 0.0546353 -0.00889018 -0.0873009 0.0549326 -0.00888737 -0.0868494 0.0551209 -0.00888404 -0.0868724 0.0552076 -0.00875228 -0.0931794 0.0474458 -0.00877398 -0.0896262 0.0518809 -0.00863294 -0.088064 0.0542965 -0.00876939 -0.08952 0.0518087 -0.00889265 -0.0878735 0.0541844 -0.00897221 -0.0877527 0.0541133 -0.00899756 -0.0913228 0.049595 -0.00863508 -0.0895951 0.0518598 -0.00877009 -0.0912932 0.049571 -0.0087716 -0.0910435 0.0493072 -0.00899756 -0.0894124 0.0517356 -0.00897228 -0.0892966 0.0516569 -0.00899756 -0.0932073 0.047473 -0.00863848 -0.0912226 0.0495137 -0.00889337 -0.0930217 0.0472921 -0.00897272 -0.0911218 0.049432 -0.00897245 -0.0929224 0.0471952 -0.00899756 -0.0931143 0.0473823 -0.00889452 -0.0951329 0.0453346 -0.00897309 -0.102121 0.0413742 -0.0107071 -0.099786 0.042437 -0.00976288 -0.101231 0.0418417 -0.0101157 -0.102235 0.0414105 -0.0106404 -0.0996972 0.0423372 -0.00987556 -0.0984312 0.042985 -0.0095065 -0.104589 0.0406824 -0.0116236 -0.0997416 0.0423926 -0.00982745 -0.0973738 0.0437282 -0.00920133 -0.0972573 0.0436789 -0.00923385 -0.0974887 0.0438427 -0.00902629 -0.0952732 0.0455035 -0.00877737 -0.095215 0.0454334 -0.00889615 -0.0950866 0.0452789 -0.0089922 -0.0973406 0.0436872 -0.00922724 -0.0974371 0.0437979 -0.00912579 -0.0990582 0.0429053 -0.00933838 -0.0998259 0.0424651 -0.00968715 -0.0967958 0.0399788 -0.00584784 -0.0967958 0.0394824 -0.00718204 -0.0798057 0.039851 -0.00639774 -0.0841235 0.0375203 -0.00863267 -0.0967958 0.0384832 -0.00819604 -0.0815245 0.0388143 -0.00794808 -0.0960059 0.0318414 -0.00759644 -0.094639 0.0328196 -0.00785855 -0.0953721 0.0323982 0.00775053 -0.0960059 0.0318414 0.00760132 -0.0956894 0.0321477 0.00768339 -0.0967958 0.0357347 0.00864452 -0.0881681 0.0357347 0.00864452 -0.0821159 0.0385053 0.00818625 -0.0967958 0.0384832 0.00820092 -0.0825438 0.038288 0.0083201 -0.0832821 0.0379231 0.00849854 -0.0798579 0.0398078 0.00652822 -0.0801076 0.0396303 0.00693064 -0.106696 0.0336297 0.00238401 -0.106696 0.0350047 0.00275244 -0.106696 0.0332297 0.00307683 -0.106696 0.0367797 0.00307683 -0.106696 0.0377547 2.44063e-06 -0.106696 0.0373862 -0.00137256 -0.106696 0.0363797 -0.00237913 -0.106696 0.0350047 -0.00354756 -0.106696 0.0336297 -0.00237913 -0.106696 0.0332297 -0.00307195 -0.106696 0.0322547 2.44063e-06 -0.106696 0.0314547 2.44063e-06 -0.0967958 0.0375484 0.014923 -0.0797348 0.0376476 0.014637 -0.0798057 0.0377127 0.0143829 -0.0967958 0.0374273 0.0121416 -0.0967958 0.0377856 0.0135193 -0.0801616 0.037788 0.0137405 -0.0967958 0.0365363 0.0110313 -0.0841235 0.0368117 0.011282 -0.0950346 0.0321504 0.00954762 -0.0947939 0.0322802 0.0095824 -0.094639 0.0323537 0.0096021 -0.0960059 0.0313755 0.00933998 -0.0967958 0.0313755 -0.0093351 -0.0960059 0.0313755 -0.0093351 -0.0881681 0.0352688 -0.0103783 -0.0967958 0.0374273 -0.0121367 -0.0967958 0.0365363 -0.0110265 -0.0856522 0.036262 -0.010825 -0.0967958 0.0375484 -0.0149181 -0.0967958 0.0377856 -0.0135145 -0.0967958 -0.039473 0.00718693 -0.0815245 -0.038805 0.00795296 -0.0967958 -0.0399695 0.00585273 -0.0967958 -0.0371471 0.00871694 -0.0857013 -0.0367869 0.00875552 -0.0967958 -0.0384739 0.00820092 -0.0960059 -0.0318321 0.00760132 -0.0950346 -0.032607 0.00780895 -0.0967958 -0.0357254 0.00864452 -0.0967958 -0.0307504 0.00709423 -0.0967958 -0.0307504 -0.00708935 -0.0965681 -0.0311484 -0.00733141 -0.0953721 -0.0323889 -0.00774565 -0.0960059 -0.0318321 -0.00759644 -0.095888 -0.0319538 -0.00762905 -0.0967958 -0.0357254 -0.00863964 -0.0967958 -0.0384739 -0.00819604 -0.0967958 -0.039473 -0.00718204 -0.0821159 -0.038496 -0.00818137 -0.0825438 -0.0382787 -0.00831522 -0.0832821 -0.0379137 -0.00849366 -0.0967958 -0.0371471 -0.00871206 -0.0856522 -0.0368088 -0.0087494 -0.0797062 -0.0399695 -0.00584784 -0.0801076 -0.039621 -0.00692576 -0.0806113 -0.0393114 -0.00741395 -0.0960059 -0.0313662 -0.0093351 -0.0953751 -0.0319209 -0.00948373 -0.0881681 -0.0352595 -0.0103783 -0.0967958 -0.0313662 -0.0093351 -0.0963805 -0.0309298 -0.00924831 -0.08903 -0.0263038 -0.0250333 -0.0967958 -0.0237673 -0.0224967 -0.0890536 -0.0259868 -0.0247162 -0.0890527 -0.0260513 -0.0247807 -0.0890472 -0.0261519 -0.0248814 -0.0889592 -0.0266174 -0.0253468 -0.0875165 -0.0294658 -0.0263135 -0.0879989 -0.0284203 -0.0262891 -0.0967958 -0.0278125 -0.0261204 -0.0870044 -0.0312688 -0.0254941 -0.0870872 -0.0308131 -0.0258324 -0.0890958 -0.0224945 -0.0237695 -0.0967958 -0.0253446 -0.0266196 -0.0890958 -0.0194995 -0.0228254 -0.0967958 -0.0211125 -0.022931 -0.0967958 -0.0224945 -0.0237695 -0.0890958 -0.0211125 -0.022931 -0.0885197 -0.0153872 -0.0252809 -0.0967958 -0.0142455 -0.0259416 -0.0890296 -0.0167998 -0.024365 -0.0890958 -0.01802 -0.0234768 -0.0890958 -0.01802 0.0234816 -0.0890958 -0.0175593 0.0238282 -0.0967958 -0.0142455 0.0259465 -0.0886321 -0.0155969 0.025157 -0.0881976 -0.0148237 0.0256204 -0.0967958 -0.0224945 0.0237744 -0.0890958 -0.0224945 0.0237744 -0.0890958 -0.0194995 0.0228303 -0.0967958 -0.0253446 0.0266245 -0.0890443 -0.0253446 0.0266245 -0.0967958 -0.0305918 0.0259632 -0.086986 -0.0295413 0.0263076 -0.086586 -0.0298913 0.0262344 -0.0858741 -0.0306565 0.0259287 -0.0967958 -0.0316888 0.025056 -0.0967958 -0.0266174 0.0253517 -0.0890443 -0.0266174 0.0253517 -0.0965681 -0.0306416 0.00922769 -0.0953721 -0.0319231 0.00948919 -0.094639 -0.0323444 0.0096021 -0.0967958 -0.0352595 0.0103832 -0.095888 -0.0314879 0.0093726 -0.0967958 -0.0313662 0.00933998 -0.106696 0.027934 0.0188774 -0.106696 0.0285405 0.0205768 -0.106696 0.0303155 0.0202524 -0.106696 0.0316905 0.019884 -0.106696 0.0326971 0.0188774 -0.106696 0.0320905 0.0205768 -0.106696 0.0333899 0.0192774 -0.106696 0.0330656 0.0175024 -0.106696 0.0333899 0.0157274 -0.106696 0.0303155 0.0147524 -0.106696 0.0320905 0.0144281 -0.106696 0.0289405 0.0151209 -0.106696 0.0303155 0.0139524 -0.106696 0.027934 0.0161274 -0.106696 0.0285405 0.0144281 -0.106696 0.0272412 0.0157274 -0.106696 0.0161297 0.0279318 -0.106696 0.0157297 0.0272389 -0.106696 0.0161297 0.0326949 -0.106696 0.0175047 0.0330633 -0.106696 0.0157297 0.0333877 -0.106696 0.0198862 0.0316883 -0.106696 0.0202547 0.0303133 -0.106696 0.0210547 0.0303133 -0.106696 0.020579 0.0285383 -0.106696 0.0188797 0.0279318 -0.106696 0.0192797 0.0272389 -0.106696 0.0175047 0.0275633 -0.106696 0.00177966 0.0380768 -0.106696 0.00275466 0.0350024 -0.106696 0.00307905 0.0332274 -0.106696 0.00137966 0.0326209 -0.106696 -0.00177034 0.0319281 -0.106696 -0.00237691 0.0336274 -0.106696 -0.00306973 0.0332274 -0.106696 -0.00237691 0.0363774 -0.106696 -0.00354534 0.0350024 -0.106696 4.65996e-06 0.0385524 -0.106696 -0.0147453 0.0303133 -0.106696 -0.0151138 0.0289383 -0.106696 -0.0139453 0.0303133 -0.106696 -0.0161203 0.0279318 -0.106696 -0.0157203 0.0272389 -0.106696 -0.0174953 0.0267633 -0.106696 -0.0198769 0.0289383 -0.106696 -0.0192703 0.0272389 -0.106696 -0.0202453 0.0303133 -0.106696 -0.0205697 0.0320883 -0.106696 -0.0174953 0.0330633 -0.106696 -0.0161203 0.0326949 -0.106696 -0.0157203 0.0333877 -0.106696 -0.0144209 0.0320883 -0.106696 -0.0326878 0.0161274 -0.106696 -0.0330562 0.0175024 -0.106696 -0.0338562 0.0175024 -0.106696 -0.0326878 0.0188774 -0.106696 -0.0316812 0.019884 -0.106696 -0.0320812 0.0205768 -0.106696 -0.0303062 0.0202524 -0.106696 -0.0303062 0.0210524 -0.106696 -0.0272318 0.0192774 -0.106696 -0.0272318 0.0157274 -0.106696 -0.0303062 0.0147524 -0.106696 -0.0316812 0.0151209 -0.106696 -0.0373769 0.00137744 -0.106696 -0.0349953 0.00355244 -0.106696 -0.0336203 0.00238401 -0.106696 -0.031921 0.00177744 -0.106696 -0.0322453 2.44063e-06 -0.106696 -0.0314453 2.44063e-06 -0.106696 -0.0326138 -0.00137256 -0.106696 -0.031921 -0.00177256 -0.106696 -0.0332203 -0.00307195 -0.106696 -0.0349953 -0.00274756 -0.106696 -0.0363703 -0.00237913 -0.106696 -0.0373769 -0.00137256 -0.106696 -0.0316812 -0.015116 -0.106696 -0.0289312 -0.015116 -0.106696 -0.0279247 -0.0161226 -0.106696 -0.0285312 -0.0205719 -0.106696 -0.0330562 -0.0174976 -0.106696 -0.0338562 -0.0174976 -0.106696 -0.0326878 -0.0161226 -0.106696 -0.0333806 -0.0157226 -0.106696 -0.0157203 -0.0272341 -0.106696 -0.0147453 -0.0303084 -0.106696 -0.0144209 -0.0285334 -0.106696 -0.0139453 -0.0303084 -0.106696 -0.0205697 -0.0285334 -0.106696 -0.0188703 -0.0279269 -0.106696 -0.0174953 -0.0267584 -0.106696 0.00307905 -0.0332226 -0.106696 0.00355466 -0.0349976 -0.106696 0.00275466 -0.0349976 -0.106696 0.00307905 -0.0367726 -0.106696 4.65996e-06 -0.0385476 -0.106696 -0.00177034 -0.0380719 -0.106696 -0.00274534 -0.0349976 -0.106696 -0.00237691 -0.0336226 -0.106696 -0.00354534 -0.0349976 -0.106696 -0.00137034 -0.032616 -0.106696 -0.00177034 -0.0319232 -0.106696 4.65996e-06 -0.0322476 -0.106696 4.65996e-06 -0.0314476 -0.106696 0.00177966 -0.0319232 -0.106696 0.0188797 -0.03269 -0.106696 0.0175047 -0.0338584 -0.106696 0.0151231 -0.0316834 -0.106696 0.0139547 -0.0303084 -0.106696 0.0175047 -0.0267584 -0.106696 0.0198862 -0.0289334 -0.106696 0.020579 -0.0285334 -0.106696 0.0320905 -0.0205719 -0.106696 0.0303155 -0.0210476 -0.106696 0.0303155 -0.0202476 -0.106696 0.027934 -0.0188726 -0.106696 0.0275655 -0.0174976 -0.106696 0.027934 -0.0161226 -0.106696 0.0267655 -0.0174976 -0.106696 0.0285405 -0.0144232 -0.106696 0.0303155 -0.0147476 -0.106696 0.0316905 -0.015116 -0.106696 0.0320905 -0.0144232 -0.106696 0.0338655 -0.0174976 -0.106696 0.0326971 -0.0188726 -0.106696 0.0333899 -0.0192726 -0.06478 0.0269547 0.0369265 -0.0789073 0.0255725 0.0385192 -0.0777869 0.0262883 0.0385922 -0.0783709 0.026357 0.0381218 -0.0771704 0.0269547 0.0369265 -0.0771704 0.0266018 0.038261 -0.0790016 0.0258286 0.0381346 -0.0787726 0.0261535 0.0379835 -0.0784928 0.026441 0.0377989 -0.0767511 0.0263811 0.0386478 -0.0774024 0.0261942 0.0389201 -0.0780285 0.0258145 0.0391204 -0.0769283 0.0262273 0.0392375 -0.0785536 0.0252756 0.0392207 -0.0781272 0.0252084 0.0399383 -0.0784443 0.0244649 0.0401238 -0.0783846 0.0259837 0.0386076 -0.0793128 0.0250956 0.0383381 -0.0789246 0.0246466 0.0392155 -0.0753016 0.0263547 0.0404674 -0.0751572 0.0262227 0.0425194 -0.0764227 0.0251259 0.0431854 -0.0775998 0.0258315 0.03963 -0.0732522 0.0264638 0.042476 -0.0612429 0.0266805 0.0428423 -0.0754427 0.0257363 0.0445728 -0.0746632 0.0263651 0.0428193 -0.0741791 0.0265959 0.0430541 -0.0744014 0.0264736 0.0429343 -0.0759491 0.0252954 0.0439507 -0.0758731 0.0257973 0.0428961 -0.0754201 0.0259883 0.043405 -0.0767318 0.0243339 0.043348 -0.0761686 0.0244533 0.0443534 -0.0745965 0.0265539 0.0435853 -0.0745965 0.0265279 0.0445896 -0.0749521 0.0263392 0.0437939 -0.0753641 0.0258941 0.0444049 -0.0747193 0.0263827 0.0448089 -0.0732522 0.0269059 0.0435175 -0.0612409 0.0266814 -0.0428402 -0.0609488 0.0268345 -0.0432271 -0.0606464 0.0269248 -0.0436219 -0.0603342 0.0269547 -0.0440235 -0.0739974 0.0268193 -0.04442 -0.0732522 0.0269547 -0.0440235 -0.0741791 0.0265959 -0.0430492 -0.0745965 0.0265539 -0.0435804 -0.0753641 0.0258941 -0.0444001 -0.0745965 0.0265279 -0.0445848 -0.0732522 0.0269059 -0.0435126 -0.0752685 0.0256947 -0.0450962 -0.0732522 0.0264638 -0.0424711 -0.0754427 0.0257363 -0.0445679 -0.0754201 0.0259883 -0.0434001 -0.0749521 0.0263392 -0.0437891 -0.0744014 0.0264736 -0.0429294 -0.0761686 0.0244533 -0.0443485 -0.0764227 0.0251259 -0.0431805 -0.0759491 0.0252954 -0.0439458 -0.0751572 0.0262227 -0.0425145 -0.0746632 0.0263651 -0.0428144 -0.0738493 0.0263828 -0.0423078 -0.0758731 0.0257973 -0.0428913 -0.0784443 0.0244649 -0.0401189 -0.0785536 0.0252756 -0.0392159 -0.0781246 0.0252126 -0.0399319 -0.0780285 0.0258145 -0.0391155 -0.0775924 0.0258378 -0.0396208 -0.0769156 0.026232 -0.0392251 -0.0774024 0.0261942 -0.0389152 -0.079312 0.0250955 -0.0383345 -0.0783846 0.0259837 -0.0386027 -0.0777869 0.0262883 -0.0385873 -0.0783709 0.026357 -0.0381169 -0.0789073 0.0255725 -0.0385143 -0.0790016 0.0258286 -0.0381297 -0.0778485 0.0268295 -0.037369 -0.0771704 0.0269547 -0.0369216 -0.0771704 0.0266018 -0.0382561 -0.0771704 0.0264638 -0.038474 -0.0645699 0.0264638 -0.0550773 -0.049655 0.0269258 -0.0562351 -0.0662699 0.0263417 -0.0568402 -0.0663786 0.0254226 -0.058259 -0.0659229 0.0262481 -0.0578485 -0.0657407 0.0264842 -0.0576036 -0.0657407 0.0266738 -0.0563711 -0.0645699 0.0269394 -0.0563427 -0.0658404 0.026519 -0.0557469 -0.0662235 0.0263842 -0.055637 -0.0669996 0.0261896 -0.0553281 -0.0669046 0.0242705 -0.058083 -0.0666451 0.0255626 -0.0577579 -0.0672505 0.0240915 -0.0577136 -0.0673098 0.0257615 -0.0561842 -0.0665224 0.0259767 -0.0573458 -0.0666024 0.0261091 -0.0566659 -0.066251 0.026383 -0.0562002 -0.065524 0.0266656 -0.0558766 -0.0654718 0.0266684 -0.0558232 -0.0673843 0.0250377 -0.0571121 -0.0672138 0.0255117 -0.0568084 -0.0669508 0.0259134 -0.0564437 -0.0666131 0.0262717 -0.055498 -0.0683493 0.0239108 -0.0564549 -0.0713071 0.0239997 -0.0525943 -0.0709774 0.0262011 -0.0499181 -0.0676805 0.0256521 -0.0558966 -0.0681557 0.0248199 -0.0562933 -0.0722174 0.0249271 -0.0507329 -0.072213 0.0256685 -0.0498206 -0.0716972 0.0257032 -0.0503911 -0.0735572 0.0248019 -0.0488834 -0.0730774 0.0242677 -0.0498634 -0.0727491 0.0249977 -0.0499186 -0.0731755 0.0253582 -0.049111 -0.0712872 0.0264638 -0.0490802 -0.0715334 0.026148 -0.0495832 -0.0719697 0.0262457 -0.0492189 -0.0725871 0.0259139 -0.0492151 -0.0732783 0.0256372 -0.0487168 -0.0726255 0.0258653 -0.0492321 -0.0725871 0.0264404 -0.0484347 -0.0712872 0.0269547 -0.0475278 -0.0712872 0.0267485 -0.0485626 -0.0804036 0.0269382 0.032884 -0.0804036 0.0264638 0.0316292 -0.0671399 0.026831 0.0323741 -0.0814237 0.0267498 0.0333356 -0.0816596 0.0265225 0.0339363 -0.0817566 0.0263316 0.0342519 -0.0812504 0.0266074 0.0342002 -0.0811779 0.0268255 0.0328965 -0.0804036 0.0269547 0.0331816 -0.0816691 0.0264017 0.0315172 -0.0858659 0.0262762 0.0324683 -0.0858658 0.0262546 0.0325391 -0.0842878 0.0256114 0.0337565 -0.0834055 0.0263318 0.0327946 -0.0823409 0.0264845 0.0330668 -0.0832139 0.0264473 0.0321011 -0.0828658 0.0255588 0.0343573 -0.0809333 0.0267828 0.0323955 -0.0811224 0.0268169 0.0327251 -0.0820138 0.0265758 0.0322574 -0.0835686 0.0260285 0.0334368 -0.0817114 0.0264324 0.0340964 -0.0569906 0.0268329 0.0483345 -0.0712872 0.0267485 0.0485675 -0.0720278 0.0268131 0.0479749 -0.0712872 0.0264638 0.049085 -0.0726255 0.0258653 0.049237 -0.0725871 0.0259139 0.0492199 -0.0725871 0.0264404 0.0484396 -0.0732783 0.0256372 0.0487217 -0.0702273 0.0263547 0.04943 -0.0715334 0.026148 0.0495881 -0.072213 0.0256685 0.0498254 -0.0717046 0.0256955 0.0504008 -0.0730774 0.0242677 0.0498682 -0.0722195 0.0249224 0.0507392 -0.0724577 0.0240637 0.0508957 -0.0719697 0.0262457 0.0492238 -0.0727491 0.0249976 0.0499234 -0.0731755 0.0253581 0.0491158 -0.0713071 0.0239997 0.0525992 -0.0718899 0.0240311 0.0517525 -0.0683493 0.0239108 0.0564598 -0.0676805 0.0256521 0.0559015 -0.0709911 0.0261953 0.0499319 -0.0669996 0.0261896 0.055333 -0.0683326 0.0263547 0.05214 -0.0496559 0.0269256 0.0562392 -0.0501281 0.0268365 0.0558444 -0.0649903 0.0264166 0.0550028 -0.0654718 0.0266684 0.055828 -0.0666131 0.0262717 0.0555029 -0.0666957 0.0244053 0.0583045 -0.0672138 0.0255117 0.0568132 -0.0665224 0.0259767 0.0573507 -0.0666451 0.0255626 0.0577627 -0.0666024 0.0261091 0.0566708 -0.0662235 0.0263842 0.0556419 -0.0658404 0.026519 0.0557518 -0.066251 0.026383 0.0562051 -0.0673098 0.0257615 0.0561891 -0.0681557 0.0248199 0.0562982 -0.0673843 0.0250377 0.057117 -0.0678006 0.0239494 0.0571027 -0.0669508 0.0259134 0.0564486 -0.0658557 0.0263617 0.0548289 -0.0654227 0.0263824 0.0549174 -0.0645699 0.0269394 0.0563475 -0.065524 0.0266656 0.0558815 -0.0657407 0.0266738 0.0563759 -0.0662699 0.0263417 0.0568451 -0.0659229 0.0262481 0.0578534 -0.0663637 0.0254633 0.0582505 -0.0663786 0.0254226 0.0582639 -0.0645699 0.0269547 0.0566346 -0.0657407 0.0264842 0.0576085 -0.0638474 0.0266487 0.0586714 -0.0462543 0.0264638 0.0589753 -0.0477732 0.0269243 0.0578277 -0.0646378 0.0260009 0.0593245 -0.065324 0.0253078 0.059423 -0.0644385 0.0261462 0.0592566 -0.0649257 0.0264495 0.0585675 -0.0651854 0.0262405 0.0586704 -0.0649375 0.0257397 0.0593968 -0.0656334 0.0254068 0.0590881 -0.0650394 0.0256377 0.059412 -0.0648852 0.0239536 0.0602834 -0.0633569 0.0256101 0.0606477 -0.0638474 0.0264638 0.0589753 -0.0634189 0.0264125 0.0590632 -0.0629956 0.0263806 0.0591457 -0.0627297 0.0261755 0.0600098 -0.0646713 0.0247631 0.0602443 -0.0642163 0.0255205 0.0600428 -0.0636234 0.026084 0.0596514 -0.0629657 0.026019 0.0602498 -0.0631811 0.0261139 0.0598364 -0.0597371 0.0261807 0.0627717 -0.0620516 0.0263547 0.0593203 -0.0591103 0.0263547 0.0620531 -0.0566424 0.0261685 0.0653986 -0.0636525 0.0250956 0.0609483 -0.0639414 0.023814 0.0612421 -0.0577091 0.0237261 0.06674 -0.0608889 0.0237656 0.0640815 -0.0607417 0.0247342 0.0639141 -0.0603358 0.0256117 0.0634526 -0.0563017 0.0254462 0.0671043 -0.0564842 0.0238396 0.0676939 -0.0544767 0.0267425 0.066049 -0.0552696 0.0264262 0.0663794 -0.05557 0.0261189 0.0669309 -0.0544229 0.0267464 0.065973 -0.0549072 0.0265682 0.0658254 -0.0539478 0.0266671 0.0653824 -0.0560292 0.0263547 0.0646274 -0.0547727 0.0263815 0.064805 -0.0552834 0.0259454 0.0677069 -0.056091 0.0258945 0.0666885 -0.0575832 0.0246824 0.0665816 -0.0564224 0.0249203 0.0674259 -0.0574695 0.0250457 0.0664387 -0.0571958 0.0255981 0.0660945 -0.0568566 0.0260047 0.0656679 -0.0552127 0.0242485 0.0686472 -0.055276 0.0242156 0.0686005 -0.0566392 0.0257136 0.0664128 -0.0560486 0.0262746 0.0655674 -0.0558044 0.0262229 0.0662101 -0.0554687 0.0264091 0.0657112 -0.0551154 0.0264548 0.0652327 -0.0545231 0.0265537 0.0653185 -0.0541525 0.0264152 0.06489 -0.0535416 0.0264638 0.0649724 -0.0546672 0.026183 0.0680429 -0.0545292 0.0267356 0.0661252 -0.0535416 0.026908 0.0660248 -0.0553443 0.0254964 0.0681053 -0.0550306 0.0252745 0.068533 -0.0550796 0.026394 0.0671143 -0.0545132 0.0266936 0.0671555 -0.0550647 0.0264137 0.0670802 -0.0547682 0.0266598 0.0665038 -0.054033 0.0268255 0.0671876 -0.0541195 0.0267743 0.0673042 -0.0513605 -0.0103141 0.0663261 -0.0513605 -0.0110453 0.0681738 -0.0447568 -0.0103262 0.0663392 -0.0447169 -0.0102562 0.0662664 -0.0526989 -0.0100813 0.0697503 -0.0529429 -0.00838362 0.0659865 -0.0536467 -0.00840095 0.0667384 -0.0536853 -0.00879876 0.06947 -0.0540594 -0.00841097 0.068219 -0.0540597 -0.00841098 0.0681942 -0.0536853 -0.00967905 0.0685006 -0.0536853 -0.00967351 0.0678252 -0.0536853 -0.00877743 0.0668704 -0.0536853 -0.00934661 0.0672341 -0.0540585 -0.00841092 0.0680918 -0.052425 -0.0102674 0.0697431 -0.0536853 -0.00936189 0.069097 -0.0526989 -0.0106229 0.0687319 -0.0526989 -0.0106134 0.0675785 -0.0526989 -0.00908322 0.065948 -0.0513605 -0.0109569 0.0674883 -0.0526989 -0.0100552 0.0665691 -0.0513605 -0.00919495 0.065611 -0.052049 -0.00836218 0.0655631 -0.0583697 -0.00363423 0.0665725 -0.0558206 -0.00417302 0.0683877 -0.0562227 -0.00400871 0.0681034 -0.0563453 -0.00513363 0.0676923 -0.0555042 -0.00563013 0.0682308 -0.0554829 -0.00618118 0.0676931 -0.0553013 -0.00661208 0.0670374 -0.0545895 -0.00569921 0.069178 -0.05369 -0.00649943 0.0647789 -0.0545467 -0.00666062 0.0651414 -0.0549724 -0.00685677 0.0663431 -0.0545464 -0.00689568 0.0656997 -0.054088 -0.00675891 0.0651719 -0.0572789 -0.00479652 0.0670811 -0.0576647 -0.00589756 0.0655881 -0.0567977 -0.00634534 0.0643774 -0.0560406 -0.00641069 0.0649573 -0.0557187 -0.00636197 0.0645177 -0.0547945 -0.00706405 0.0671099 -0.0547917 -0.00706666 0.0671013 -0.0549629 -0.00674317 0.0656745 -0.0550324 -0.00656754 0.0650933 -0.0541801 -0.00704061 0.065688 -0.0536686 -0.00685644 0.0651814 -0.0579526 -0.0036488 0.0668712 -0.0571598 -0.00532808 0.0667864 -0.0562639 -0.00569014 0.0672883 -0.0569583 -0.00578727 0.0663936 -0.0560688 -0.00615036 0.0667736 -0.0566877 -0.00613251 0.0659312 -0.0563722 -0.00634045 0.0654389 -0.0557741 -0.0064601 0.0661967 -0.0554145 -0.00659537 0.0656185 -0.0637828 -0.00634534 0.0595131 -0.0570861 -0.0062995 0.0647802 -0.0651681 -0.00458676 0.0616308 -0.0582599 -0.00463713 0.0664191 -0.0579061 -0.00556011 0.0659251 -0.0643258 -0.00615655 0.0603431 -0.0573672 -0.00616194 0.0651726 -0.0648381 -0.00553575 0.0611264 -0.0648503 -0.00635838 0.0593887 -0.066364 -0.00600328 0.0598453 -0.0659192 -0.00639681 0.05927 -0.0673195 -0.00380392 0.060481 -0.069032 -0.00513773 0.059497 -0.0658066 -0.00540046 0.0607107 -0.0653446 -0.0060418 0.0601099 -0.0667864 -0.00537992 0.0602809 -0.0673726 -0.00603681 0.0595798 -0.0669709 -0.00646003 0.0591603 -0.0671187 -0.00460591 0.060498 -0.0687161 -0.00566675 0.059474 -0.0683628 -0.00614917 0.0593234 -0.0680002 -0.00746532 0.0572356 -0.0696921 -0.00656536 0.0581313 -0.0697222 -0.0056747 0.0589027 -0.0686176 -0.007293 0.0562806 -0.0680002 -0.00747325 0.0570287 -0.068102 -0.00731688 0.056129 -0.0681071 -0.00677399 0.0552189 -0.0680002 -0.00655042 0.0549961 -0.0680812 -0.00746793 0.0571777 -0.0680002 -0.00745473 0.0573444 -0.0685707 -0.00719511 0.0580771 -0.0692241 -0.00562974 0.0592778 -0.0680073 -0.00656536 0.0590482 -0.0689723 -0.00654922 0.058815 -0.0680479 -0.00720386 0.0582034 -0.0689607 -0.00720386 0.0577067 -0.0691133 -0.00722774 0.0571915 -0.0689877 -0.00726037 0.0566695 -0.0685473 -0.00649259 0.0549381 -0.0693518 -0.00692314 0.0559667 -0.069351 -0.00708275 0.0566659 -0.0689164 -0.00707089 0.0559464 -0.0689386 -0.00677121 0.0553783 -0.0688178 -0.00704154 0.0558137 -0.0684445 -0.00686725 0.0553832 -0.0714203 -0.00595358 0.0570594 -0.0709046 -0.00650351 0.0558545 -0.0698408 -0.00677298 0.0559522 -0.0694733 -0.00667733 0.0553547 -0.0730601 -0.00629348 0.0550066 -0.0720262 -0.00629249 0.0557193 -0.0733436 -0.00610287 0.0555259 -0.0735674 -0.00583094 0.0559358 -0.0737832 -0.00541902 0.0563311 -0.0705299 -0.00459505 0.0586565 -0.0716289 -0.00482667 0.0579002 -0.070618 -0.00524127 0.058381 -0.0697834 -0.00655053 0.0580041 -0.0705973 -0.00586068 0.0579277 -0.0704486 -0.00636407 0.0573216 -0.0696667 -0.00685313 0.0574611 -0.0701831 -0.00667719 0.0566329 -0.0694585 -0.00704159 0.0568944 -0.0715708 -0.00543532 0.0575508 -0.0739492 -0.00491645 0.0566352 -0.0724523 -0.00564686 0.0567757 -0.0722573 -0.00604446 0.0562735 -0.0711888 -0.00631969 0.0564719 -0.0717824 -0.00638901 0.0551652 -0.0706024 -0.0065136 0.0552704 -0.0830104 -0.00388604 0.053407 -0.0836241 -0.00265137 0.0531049 -0.0825896 -0.00634534 0.0507472 -0.0800205 -0.00403343 0.0542517 -0.0829793 -0.0045563 0.0532628 -0.0776335 -0.0030239 0.0551309 -0.0769889 -0.00421233 0.0554239 -0.0799629 -0.00467005 0.0540875 -0.0763587 -0.00611656 0.0540056 -0.0795102 -0.00609745 0.0527967 -0.0858659 -0.00461492 0.052831 -0.0858659 -0.00607664 0.0514853 -0.0843296 -0.00607813 0.0516332 -0.0826881 -0.00608171 0.0519159 -0.0829106 -0.0051869 0.0529451 -0.0798519 -0.005262 0.0537709 -0.0767666 -0.00535186 0.0549236 -0.0740476 -0.0044166 0.0568155 -0.0967958 -0.00261791 0.052808 -0.0967958 -0.00619489 0.0511998 -0.0858659 -0.00620935 0.0511572 -0.0858658 -0.00634534 0.0503111 -0.0858659 -0.00261791 0.052808 -0.0858659 -0.00378302 0.0530076 -0.0967958 -0.00346528 0.0530051 -0.0967958 -0.00461492 0.052831 -0.0858659 -0.00499147 0.0526516 -0.0967958 -0.00558474 0.0521896 -0.0858659 -0.00557162 0.052203 -0.0513605 -0.0110453 -0.068169 -0.0513605 -0.0109569 -0.0674835 -0.0445295 -0.0097657 -0.0658728 -0.0513605 -0.00919495 -0.0656061 -0.0513605 -0.00834534 -0.065469 -0.0537212 -0.00840247 -0.0694782 -0.0536853 -0.00879874 -0.069465 -0.0536855 -0.00840159 -0.0667972 -0.0529732 -0.00838435 -0.0660038 -0.052699 -0.00837788 -0.0658243 -0.0536853 -0.00967344 -0.0678203 -0.0540571 -0.00841076 -0.0680501 -0.0540596 -0.00841085 -0.0681462 -0.0540597 -0.00841085 -0.0681794 -0.0536853 -0.00936184 -0.0690921 -0.054056 -0.00841077 -0.0683099 -0.0540293 -0.00841006 -0.0685736 -0.0530195 -0.00838548 -0.0702988 -0.0528157 -0.00910065 -0.0703142 -0.0526989 -0.0100813 -0.0697454 -0.0519143 -0.0108587 -0.0689853 -0.0526989 -0.0106229 -0.068727 -0.0536853 -0.00877741 -0.0668656 -0.0536853 -0.00934655 -0.0672293 -0.0526989 -0.00908322 -0.0659432 -0.0526989 -0.0106134 -0.0675736 -0.0536853 -0.00967898 -0.0684957 -0.0527638 -0.00936575 -0.0702377 -0.0526989 -0.0100552 -0.0665642 -0.0513605 -0.0103141 -0.0663213 -0.0582599 -0.00463713 -0.0664142 -0.0554786 -0.00618391 -0.0676913 -0.0542926 -0.00529075 -0.0694522 -0.0545219 -0.00504292 -0.069293 -0.0551917 -0.00451406 -0.0688251 -0.0547167 -0.005915 -0.0689829 -0.0563369 -0.00513647 -0.0676935 -0.0572729 -0.00479714 -0.0670807 -0.0562561 -0.00569338 -0.0672885 -0.0571542 -0.00532917 -0.0667855 -0.0569528 -0.00578871 -0.0663919 -0.0557663 -0.00646337 -0.0661943 -0.0566819 -0.00613405 -0.0659287 -0.0546547 -0.00641354 -0.0646504 -0.0540824 -0.00676027 -0.0651674 -0.0537206 -0.0071092 -0.0654771 -0.0545416 -0.00689768 -0.0656953 -0.0544123 -0.00721341 -0.0662948 -0.0548532 -0.00699712 -0.0673056 -0.0560342 -0.00641154 -0.0649535 -0.0573672 -0.00616194 -0.0651678 -0.0563661 -0.00634179 -0.0654357 -0.057665 -0.00589728 -0.0655836 -0.0560611 -0.00615381 -0.0667726 -0.0562088 -0.00401381 -0.0681084 -0.0554992 -0.00563276 -0.0682299 -0.0552973 -0.00661483 -0.0670345 -0.0549682 -0.00685929 -0.0663393 -0.0554061 -0.00659801 -0.0656153 -0.0550232 -0.00656923 -0.0650896 -0.0556689 -0.00636356 -0.0645193 -0.0637828 -0.00634534 -0.0595082 -0.0570862 -0.00629947 -0.0647754 -0.0602646 -0.00634534 -0.0619035 -0.0583697 -0.00363423 -0.0665677 -0.0652602 -0.00356508 -0.0617667 -0.0579061 -0.00556011 -0.0659202 -0.0648381 -0.00553575 -0.0611215 -0.0643258 -0.00615655 -0.0603383 -0.0651681 -0.00458676 -0.0616259 -0.0648469 -0.0063583 -0.0593842 -0.0653414 -0.00604203 -0.0601058 -0.069032 -0.00513773 -0.0594921 -0.0687161 -0.00566675 -0.0594691 -0.0667761 -0.00537959 -0.0602805 -0.0673687 -0.00603654 -0.0595759 -0.066967 -0.00645973 -0.0591558 -0.065908 -0.00639628 -0.0592663 -0.0658035 -0.00540069 -0.0607071 -0.0663534 -0.00600331 -0.0598432 -0.0671085 -0.00460449 -0.0604988 -0.0689723 -0.00654922 -0.0588102 -0.0680002 -0.00718196 -0.0558039 -0.0680002 -0.00747205 -0.0571046 -0.0694585 -0.00704159 -0.0568895 -0.0686176 -0.007293 -0.0562757 -0.069351 -0.00708275 -0.056661 -0.0689164 -0.00707089 -0.0559415 -0.0684445 -0.00686725 -0.0553783 -0.068102 -0.00731688 -0.0561241 -0.0681071 -0.00677399 -0.055214 -0.0691133 -0.00722774 -0.0571866 -0.0689877 -0.00726037 -0.0566646 -0.0696921 -0.00656536 -0.0581264 -0.0689607 -0.00720386 -0.0577018 -0.0692241 -0.00562974 -0.0592729 -0.0692883 -0.0046037 -0.0593907 -0.0680002 -0.00746927 -0.0571705 -0.0680002 -0.00746862 -0.057182 -0.0680812 -0.00746793 -0.0571728 -0.0680479 -0.00720386 -0.0581985 -0.0680002 -0.00739942 -0.0576509 -0.0683628 -0.00614917 -0.0593185 -0.0680073 -0.00656536 -0.0590433 -0.0685707 -0.00719511 -0.0580722 -0.0723097 -0.00634713 -0.0545858 -0.0724512 -0.00564713 -0.0567712 -0.0708965 -0.00650529 -0.0558505 -0.0705939 -0.00651467 -0.0552662 -0.0703032 -0.00638681 -0.0547587 -0.0714948 -0.00635598 -0.054652 -0.0688178 -0.00704154 -0.0558088 -0.069459 -0.0066797 -0.0553506 -0.0701708 -0.00668233 -0.0566295 -0.0696667 -0.00685313 -0.0574562 -0.0705855 -0.00586706 -0.0579273 -0.0697834 -0.00655053 -0.0579993 -0.0697222 -0.0056747 -0.0588979 -0.0737832 -0.00541902 -0.0563263 -0.0735674 -0.00583094 -0.0559309 -0.0722561 -0.00604471 -0.0562688 -0.0720249 -0.00629268 -0.0557146 -0.0717812 -0.00638912 -0.0551604 -0.0730601 -0.00629348 -0.0550017 -0.0728078 -0.00634534 -0.0545395 -0.0691081 -0.00644836 -0.0548757 -0.0698276 -0.00677681 -0.0559481 -0.0711811 -0.00632203 -0.0564685 -0.0704369 -0.00637009 -0.0573195 -0.0714128 -0.00595623 -0.0570567 -0.0715634 -0.005438 -0.0575488 -0.0716213 -0.00482922 -0.0578988 -0.0706055 -0.00524767 -0.0583822 -0.0705163 -0.00460137 -0.058659 -0.0703541 -0.00399923 -0.0587743 -0.0830045 -0.00388617 -0.0534034 -0.0740476 -0.0044166 -0.0568106 -0.0826818 -0.00608163 -0.0519126 -0.0843316 -0.00607803 -0.0516282 -0.0858658 -0.00634534 -0.0503062 -0.0769797 -0.00421279 -0.0554231 -0.0813389 -0.00275885 -0.0536899 -0.0799954 -0.00403482 -0.0542554 -0.0823001 -0.00634534 -0.0508048 -0.0791093 -0.00634534 -0.0517349 -0.079484 -0.00609751 -0.0528009 -0.0733436 -0.00610287 -0.055521 -0.0767572 -0.00535201 -0.0549228 -0.0739492 -0.00491645 -0.0566303 -0.0858658 -0.00466193 -0.0528075 -0.0829045 -0.00518686 -0.0529416 -0.0759071 -0.00634534 -0.0530111 -0.0763491 -0.00611653 -0.054005 -0.0798263 -0.00526261 -0.0537745 -0.0829733 -0.00455634 -0.0532592 -0.0799376 -0.00467107 -0.0540911 -0.0858658 -0.00345206 -0.0529993 -0.0858659 -0.0026179 -0.0528031 -0.0967958 -0.00461492 -0.0528261 -0.0858658 -0.00529751 -0.0524417 -0.0858658 -0.00558474 -0.0521847 -0.0967958 -0.00558474 -0.0521847 -0.0967958 -0.00619489 -0.0511949 -0.0858658 -0.00607653 -0.0514806 -0.0858658 -0.00608658 -0.0514596 -0.0967958 -0.00634534 -0.0503062 -0.0445406 0.0268376 -0.0657336 -0.0550306 0.0252745 -0.0685281 -0.0546672 0.026183 -0.068038 -0.0552834 0.0259454 -0.0677021 -0.0545132 0.0266936 -0.0671507 -0.0535416 0.026908 -0.0660199 -0.0535416 0.0269547 -0.0665199 -0.0544229 0.0267464 -0.0659682 -0.0551496 0.0242824 -0.0686886 -0.0553443 0.0254964 -0.0681004 -0.0574972 0.0237276 -0.066903 -0.0575832 0.0246824 -0.0665768 -0.0545218 0.0265539 -0.0653138 -0.054906 0.0265685 -0.0658207 -0.0539478 0.0266671 -0.0653775 -0.0560511 0.0262741 -0.0655619 -0.0572017 0.0255889 -0.066097 -0.0550796 0.026394 -0.0671094 -0.0550647 0.0264137 -0.0670753 -0.0547682 0.0266598 -0.0664989 -0.0552685 0.0264267 -0.0663748 -0.0545292 0.0267356 -0.0661203 -0.0544767 0.0267425 -0.0660441 -0.0564243 0.0249197 -0.0674197 -0.0566415 0.025713 -0.0664067 -0.0563034 0.0254456 -0.0670983 -0.0555689 0.0261194 -0.0669265 -0.0560927 0.0258938 -0.0666827 -0.0558062 0.0262223 -0.0662046 -0.0554706 0.0264086 -0.0657059 -0.0551173 0.0264545 -0.0652275 -0.0535416 0.0264638 -0.0649675 -0.0627297 0.0261755 -0.0600049 -0.0629657 0.026019 -0.060245 -0.0591103 0.0263547 -0.0620482 -0.059761 0.026174 -0.062769 -0.0566424 0.0261685 -0.0653937 -0.0568566 0.0260047 -0.065663 -0.0607559 0.0247286 -0.0638999 -0.0574695 0.0250457 -0.0664338 -0.0636525 0.0250956 -0.0609434 -0.0603544 0.0256028 -0.0634436 -0.0482905 0.0269547 -0.057418 -0.0472556 0.0268326 -0.0582207 -0.06318 0.0261138 -0.059832 -0.0658156 0.0244759 -0.0592531 -0.0644385 0.0261462 -0.0592517 -0.0620516 0.0263547 -0.0593154 -0.0636209 0.0260841 -0.0596476 -0.0646378 0.0260009 -0.0593196 -0.0642138 0.0255205 -0.0600397 -0.0646687 0.0247628 -0.0602419 -0.065324 0.0253078 -0.0594182 -0.0653408 0.0241226 -0.0597924 -0.0655854 0.0242842 -0.0595197 -0.0633569 0.0256102 -0.0606428 -0.0649257 0.0264495 -0.0585626 -0.0650394 0.0256377 -0.0594071 -0.0649375 0.0257397 -0.0593919 -0.0638474 0.0266487 -0.0586665 -0.0804036 0.0264638 -0.0316244 -0.0673364 0.0266783 -0.0319871 -0.0669302 0.0269242 -0.032771 -0.0818793 0.025655 -0.0349519 -0.0812504 0.0266074 -0.0341953 -0.0806657 0.0266592 -0.031977 -0.0811224 0.0268169 -0.0327202 -0.0808341 0.0268693 -0.0336946 -0.0804036 0.0269382 -0.0328792 -0.0811808 0.0266654 -0.0341117 -0.0811779 0.0268255 -0.0328916 -0.0814237 0.0267498 -0.0333307 -0.0967958 0.0263836 -0.0318512 -0.0884795 0.026008 -0.0330879 -0.0825413 0.0265085 -0.0321804 -0.0853749 0.0256525 -0.0335689 -0.084536 0.0260072 -0.0331885 -0.0846573 0.0256295 -0.0336631 -0.0836901 0.0255788 -0.0339581 -0.0828291 0.0255593 -0.0343724 -0.0817114 0.0264324 -0.0340916 -0.0817566 0.0263316 -0.034247 -0.0843752 0.0263905 -0.0319905 -0.0842922 0.0264134 -0.0314955 -0.0824027 0.0264734 -0.0318145 -0.0830204 0.026068 -0.0336344 -0.0816596 0.0265225 -0.0339314 -0.0828049 0.0264029 -0.0329343 -0.0844605 0.0262708 -0.0326119 -0.0863772 0.0260086 -0.0330833 -0.0863775 0.0262546 -0.0325344 -0.0941079 0.0258323 -0.0333649 -0.0884805 0.0262549 -0.0325378 -0.0584093 -0.0108729 0.0465331 -0.0967958 -0.0102545 0.0474928 -0.0570918 -0.00949152 0.0480282 -0.0967958 -0.00927986 0.0481167 -0.0569969 -0.00923513 0.0481327 -0.0967958 -0.00834534 0.0314307 -0.0676502 -0.008765 0.0314633 -0.0675533 -0.00942872 0.0316576 -0.0967958 -0.0102545 0.0322215 -0.0674326 -0.00986287 0.0318975 -0.0967958 -0.0110453 0.0341307 -0.0665227 -0.0109992 0.0336321 -0.0967958 -0.0108785 0.0331962 -0.0670051 -0.0106529 0.0327281 -0.0967958 -0.0157768 0.0370362 -0.0646512 -0.014606 0.0368774 -0.0967958 -0.0136229 0.0362419 -0.0656318 -0.0129978 0.0352403 -0.0967958 -0.0129993 0.0352448 -0.0967958 -0.0128453 -0.0343412 -0.0654385 -0.0131395 -0.0355667 -0.0650595 -0.0135906 -0.0362037 -0.0648489 -0.0139939 -0.036551 -0.0967958 -0.0146112 -0.0368745 -0.0967958 -0.016659 -0.0368009 -0.0646955 -0.016659 -0.0368009 -0.0672474 -0.0102932 -0.0322561 -0.0672223 -0.010339 -0.032305 -0.0967958 -0.0102545 -0.0322166 -0.057187 -0.00969344 -0.0479181 -0.0568847 -0.00873127 -0.0482508 -0.0967958 -0.0108785 -0.0465132 -0.059208 -0.0110453 -0.0455787 -0.0588079 -0.0110027 -0.0460586 -0.054823 -0.00613583 0.0687587 -0.0542324 -0.00766518 0.0673104 -0.0549479 -0.00665292 0.0680433 -0.0540061 -0.00718432 0.065764 -0.0544118 -0.00721345 0.0662989 -0.0546995 -0.00713282 0.0668536 -0.0526517 -0.00760413 0.0655333 -0.0513746 -0.00778967 0.0654736 -0.0513716 -0.00780515 0.0654738 -0.0539973 -0.00808945 0.0674041 -0.0536574 -0.00811064 0.0666706 -0.0540596 -0.00841097 0.06815 -0.0540588 -0.00841094 0.0681038 -0.0540518 -0.00841071 0.0679663 -0.0540215 -0.00840983 0.0677212 -0.054115 -0.00803213 0.0682092 -0.0539994 -0.00840933 0.0687415 -0.0538661 -0.00840594 0.0691781 -0.0535518 -0.00839826 0.0697504 -0.0523384 -0.00799156 0.0656178 -0.053906 -0.00773491 0.0666004 -0.0532323 -0.00789572 0.066032 -0.0533818 -0.00772478 0.0659841 -0.0524885 -0.00778854 0.0655961 -0.0520363 -0.00750515 0.0653935 -0.0534692 -0.00701638 0.0652802 -0.0526989 -0.00837777 0.0658291 -0.0531052 -0.00808643 0.0660493 -0.0537632 -0.00790978 0.0666479 -0.0543562 -0.00752923 0.0680796 -0.053976 -0.00792524 0.0690288 -0.0538616 -0.00702335 0.0695862 -0.0542429 -0.00732042 0.0688529 -0.0532334 -0.00790253 -0.066033 -0.0543086 -0.00721734 -0.0661384 -0.0523042 -0.00836842 -0.0656393 -0.0520363 -0.00750515 -0.0653886 -0.0533028 -0.00694311 -0.065162 -0.0526546 -0.00760976 -0.0655263 -0.0538815 -0.00715597 -0.0656284 -0.0538999 -0.00774163 -0.0665894 -0.054792 -0.00706635 -0.0670974 -0.0542311 -0.00767013 -0.0672919 -0.0542363 -0.00731702 -0.0688451 -0.0549418 -0.00676095 -0.0678425 -0.0549093 -0.00638688 -0.0684436 -0.0545943 -0.00570683 -0.0691669 -0.053871 -0.00702782 -0.069574 -0.0533466 -0.00839341 -0.0699974 -0.0538122 -0.00840467 -0.0670395 -0.053106 -0.00809246 -0.0660482 -0.0532234 -0.00839045 -0.0662151 -0.0536528 -0.00811733 -0.0666605 -0.0513858 -0.00776542 -0.0654676 -0.0514533 -0.00770113 -0.0654599 -0.0518307 -0.00755414 -0.0654139 -0.0523407 -0.00799381 -0.0656073 -0.0524917 -0.00779342 -0.065586 -0.0533821 -0.00773114 -0.0659852 -0.0528858 -0.00783067 -0.0704043 -0.0535608 -0.00775615 -0.0697879 -0.0530825 -0.00691358 -0.0702784 -0.0539731 -0.00792475 -0.0690194 -0.0541084 -0.00803114 -0.0682047 -0.0543462 -0.00752419 -0.0680786 -0.0539965 -0.00809284 -0.0673883 -0.0855745 -0.0361369 0.0104906 -0.0945122 -0.0323199 0.00866378 -0.0813173 -0.0376253 0.0123941 -0.0799131 -0.0378143 0.0138446 -0.0798988 -0.0378124 -0.0138641 -0.0796397 -0.0390187 -0.0104538 -0.0805351 -0.0377859 -0.0130542 -0.085626 -0.0361158 -0.0104722 -0.091346 -0.033587 -0.00961479 -0.0855745 -0.0365389 -0.00898528 -0.084114 -0.0372663 -0.00887489 -0.0880413 -0.0350757 -0.0100139 -0.0819891 -0.0383971 -0.00837278 -0.0813173 -0.0387797 -0.00808103 -0.0808901 -0.0390327 -0.00783829 -0.0796397 -0.0395075 -0.00842065 -0.084114 0.0367209 -0.0109451 -0.0880413 0.035085 -0.0100139 -0.0945122 0.0321701 -0.00923242 -0.0813173 0.0376346 -0.0123892 -0.0796397 0.0390281 -0.0104538 -0.0798988 0.0396885 -0.00689729 -0.0820448 0.0383754 -0.00839318 -0.085626 0.0365232 -0.00898648 -0.0880413 0.0353933 -0.00886334 -0.0799131 0.0396779 0.00692424 -0.0805351 0.0377952 0.0130591 -0.0820448 0.0374325 0.011917 -0.0839018 0.0368003 0.0110299 -0.091346 0.0335963 0.00961967 -0.085626 0.0361251 0.0104771 -0.0880413 0.035085 0.0100188 -0.0945122 0.0323292 0.00866378 -0.0808901 0.039042 0.00784317 -0.0967748 -0.0296063 0.00636762 -0.0948799 -0.0322799 0.00803665 -0.0946562 -0.0324005 0.00806913 -0.0945122 -0.0321607 0.0092373 -0.0957828 -0.0315598 0.00784276 -0.0956732 -0.0313643 0.00902494 -0.0951936 -0.0317689 0.00913282 -0.0963602 -0.0307765 -0.00751102 -0.096475 -0.0301515 -0.00889239 -0.0967515 -0.0297478 -0.00657423 -0.0967748 -0.0288218 -0.00929064 -0.0948799 -0.0319717 -0.009182 -0.0951936 -0.0320773 -0.00797722 -0.0945122 -0.0323199 -0.0086589 -0.0946562 -0.0320924 -0.00921418 -0.09616 -0.0310932 -0.00767276 -0.0956732 -0.0316729 -0.00786834 -0.0954885 -0.0318444 -0.00791452 -0.096563 0.0303734 0.00723144 -0.0963602 0.0307858 0.0075159 -0.0957828 0.0312605 0.00899477 -0.0963088 0.030519 0.00888736 -0.0951964 0.0317762 0.00913228 -0.0957828 0.0315692 0.00784276 -0.0952438 0.0317418 0.00912309 -0.0956732 0.0316823 0.00787322 -0.0951936 0.0320866 0.0079821 -0.0945122 0.0323292 -0.0086589 -0.0946562 0.0324098 -0.00806425 -0.0948799 0.0322892 -0.00803177 -0.0951964 0.0320846 -0.00797667 -0.0957828 0.0315692 -0.00783788 -0.0954885 0.0315453 -0.00906582 -0.0963602 0.0304186 -0.00888127 -0.09616 0.0307738 -0.00889957 -0.0966372 0.030179 -0.0070565 -0.0967515 0.0290593 -0.0091782 -0.0967748 0.0296156 -0.00636274 -0.0489464 0.0155041 0.0694923 -0.0751356 0.0155047 0.0397391 -0.0714295 0.0167047 0.0460701 -0.0668816 0.0167047 0.0524552 -0.0616215 0.0155047 0.0585454 -0.0640457 0.0167047 0.0558828 -0.0499938 0.0155047 0.0687425 -0.0656185 0.00330466 0.054027 -0.0629425 0.00450466 0.0571226 -0.0608528 0.00330466 0.059344 -0.0597043 0.00450466 0.0604995 -0.0562852 0.00450466 0.0636931 -0.0737571 0.00390509 0.042243 -0.0714159 0.00450466 -0.0460862 -0.0500698 0.00330466 -0.0686823 -0.0499515 0.00450466 -0.0687684 -0.0597043 0.00330466 -0.0604946 -0.0629425 0.00450466 -0.0571177 -0.0659899 0.00330466 -0.0535678 -0.0737571 0.00390509 -0.0422381 -0.0737304 0.00330466 -0.0422848 -0.0753698 0.0167047 -0.0392882 -0.0728141 0.0155047 -0.0438439 -0.0702679 0.0155047 -0.0478183 -0.0640457 0.0167047 -0.0558779 -0.0617647 0.0167047 -0.0583893 -0.0500029 0.0167047 -0.068731 -0.0569043 0.0155047 -0.0631356 -0.0605838 0.0155047 -0.0596138 -0.0744279 0.00449532 0.0413476 -0.0752642 0.00448618 0.0407006 -0.0761727 0.0032851 0.0404069 -0.0772858 0.00447149 0.0401547 -0.0786478 0.016592 0.0368876 -0.077792 0.0154119 0.0375272 -0.075251 0.0161065 0.0395202 -0.0758162 0.015472 0.0387751 -0.0743682 0.00329782 -0.0414488 -0.0752642 0.00448618 -0.0406957 -0.0772137 0.00328034 -0.0402645 -0.077792 0.0154119 -0.0375223 -0.079252 0.0165816 -0.03684 -0.0780603 0.0166046 -0.0370158 -0.0760567 0.0166694 -0.0383014 -0.0758162 0.015472 -0.0387702 -0.0751356 0.0155047 -0.0397342 -0.0760361 0.0166703 -0.0383244 -0.075251 0.0161065 -0.0395153 -0.0483952 0.00329664 -0.0700738 -0.0481588 0.00305134 -0.0716113 -0.0482729 0.00490288 -0.0719392 -0.0481207 0.00457071 -0.0708234 -0.0481204 0.00323822 -0.0708251 -0.0489464 0.00450514 -0.0694874 -0.0489464 0.0155041 -0.0694874 -0.0483952 0.0154967 -0.0700738 -0.0483957 0.0167126 -0.0700729 -0.0481866 0.0167387 -0.0705345 -0.0481314 0.0154468 -0.0707598 -0.0480993 0.0154002 -0.0710585 -0.0482729 0.0171029 -0.0719392 -0.048266 0.00489467 0.0719292 -0.0481866 0.00327052 0.0705394 -0.0483433 0.00451572 0.070168 -0.0483952 0.00451256 0.0700787 -0.0483957 0.00329667 0.0700778 -0.0489464 0.0167052 0.0694923 -0.0483952 0.0167126 0.0700787 -0.0481204 0.0167709 0.07083 -0.0481208 0.0153136 0.0714257 -0.0484371 0.0172904 0.0722412 -0.0482729 0.0151063 0.0719441 -0.0481552 0.0169525 0.0716014 -0.0481588 0.0169578 0.0716162 -0.048266 0.0170947 0.0719293 -0.0754521 0.0180952 0.0470256 -0.0825024 0.0202163 0.0389843 -0.049162 0.0190823 0.0727746 -0.0814601 0.0170437 0.0370542 -0.0797311 0.0173104 0.0393555 -0.0696801 0.0170047 0.0515012 -0.0663211 0.0170047 0.0554822 -0.0491162 0.0170051 0.069733 -0.0531125 0.0171913 0.0681899 -0.0563299 0.0170047 0.0646133 -0.0825108 0.020114 0.0389999 -0.0790189 0.0189183 0.0422896 -0.0824103 0.0208233 0.0388139 -0.081734 0.0213167 0.0388811 -0.0790621 0.020288 0.0423208 -0.0795548 0.0209637 0.0412628 -0.0757342 0.0186912 0.0472057 -0.0758787 0.0193313 0.047298 -0.0791128 0.0196238 0.0423574 -0.0793916 0.0209367 0.0414912 -0.07751 0.0206786 0.0444259 -0.0758907 0.0199556 0.0473057 -0.0637734 0.0188592 0.0616788 -0.0638601 0.0199152 0.0617724 -0.0581211 0.0198096 0.0666386 -0.0820572 0.0176186 0.0381599 -0.0805075 0.0183709 0.040134 -0.0824409 0.0187399 0.0388705 -0.080709 0.0191066 0.0403361 -0.0783758 0.0176831 0.0418254 -0.0536441 0.0178055 0.0689562 -0.0539889 0.0187457 0.0694531 -0.0590052 0.0187913 0.0657436 -0.0682404 0.0189726 0.0572345 -0.0633709 0.0178606 0.0612446 -0.0678149 0.0179162 0.056846 -0.0787666 0.0182455 0.0421074 -0.0806606 0.0205498 0.0402875 -0.0807532 0.0198615 0.0403803 -0.0751046 0.0204659 0.0483422 -0.0722953 0.0191387 0.0524302 -0.0485896 0.0175318 0.0719246 -0.0580439 0.0171962 0.064538 -0.0586312 0.0178276 0.0652745 -0.0627215 0.0172035 0.060544 -0.0670937 0.0172156 0.0561876 -0.0718588 0.0179984 0.0520997 -0.0710574 0.0172333 0.0514931 -0.0750533 0.0176028 0.0467709 -0.0745799 0.0172539 0.0464686 -0.0801649 0.0177497 0.0397904 -0.0778961 0.0172851 0.0414791 -0.0807604 0.0173246 0.0384831 -0.0839432 0.0203638 0.0384701 -0.083931 0.0197053 0.0385811 -0.0858658 0.0190667 0.0384301 -0.0858658 0.0213707 0.0377767 -0.083635 0.0173699 0.0374293 -0.0838897 0.0190131 0.0385235 -0.0826131 0.0172962 0.0374576 -0.0824584 0.0170875 0.0369863 -0.081682 0.0171679 0.0374651 -0.0837329 0.0177938 0.0379084 -0.0830504 0.0214139 0.0381221 -0.0822485 0.0213808 0.0385141 -0.0831663 0.0203283 0.0386749 -0.0825121 0.019314 0.0390023 -0.0838212 0.0183549 0.0382902 -0.0822476 0.0180263 0.0385126 -0.0821627 0.017823 0.0383554 -0.0827985 0.0176893 0.0379734 -0.0818599 0.0173377 0.0377945 -0.0858657 0.0178518 0.0378674 -0.0858657 0.0184046 0.0382162 -0.0967958 0.0177803 0.037807 -0.0967958 0.020391 0.0383437 -0.0858658 0.0203408 0.0383594 -0.0783326 0.00844397 0.0505407 -0.0795839 0.00798327 0.0497236 -0.083815 0.00762736 0.0476336 -0.0681271 0.00667673 0.0588841 -0.0739561 0.00808525 0.0544393 -0.0727865 0.00689619 0.0553454 -0.0858659 0.00676138 0.0472868 -0.0858659 0.00617683 0.047042 -0.0858659 0.00566543 0.0466678 -0.0858658 0.00522885 0.0461439 -0.0836322 0.00553937 0.0468078 -0.0858657 0.00496919 0.0456192 -0.083232 0.00480466 0.0450001 -0.0858657 0.00489677 0.0453903 -0.0756992 0.00480466 0.0494349 -0.0496232 0.00480478 0.0693762 -0.0501278 0.00480466 0.069016 -0.0577911 0.00498782 0.0648551 -0.0485896 0.00533182 0.0719246 -0.0583436 0.00559081 0.0655995 -0.0487549 0.00558543 0.07217 -0.0835276 0.00887821 0.0473179 -0.081674 0.00818103 0.0483319 -0.0806067 0.0086655 0.0487459 -0.0538214 0.00650571 0.0695668 -0.058706 0.00651601 0.0660876 -0.0727978 0.00802586 0.0553603 -0.067381 0.00770317 0.0596242 -0.057456 0.00480466 0.0638859 -0.0677635 0.00566881 0.0584193 -0.0817135 0.00750724 0.0484084 -0.0795255 0.00664492 0.0496451 -0.0793345 0.0059965 0.0493884 -0.0816685 0.00678361 0.0483213 -0.0815294 0.00608854 0.0480519 -0.079048 0.00545669 0.0490033 -0.0813075 0.0055057 0.047622 -0.0822666 0.00480466 0.0452601 -0.0810321 0.00509342 0.0470888 -0.0835 0.00510618 0.0462107 -0.0837371 0.00615205 0.0472817 -0.0837997 0.00687894 0.0475646 -0.0787003 0.00507462 0.0485358 -0.0764322 0.00505647 0.0503059 -0.0767961 0.00541001 0.0507382 -0.0771016 0.00590926 0.0511013 -0.0773161 0.00651289 0.0513561 -0.0774234 0.00715997 0.0514836 -0.0698897 0.00480466 0.0542576 -0.0671725 0.00500497 0.0576637 -0.0674867 0.00528035 0.0580654 -0.0679814 0.00614643 0.0586978 -0.079606 0.00733043 0.0497534 -0.0837889 0.008313 0.0475154 -0.085866 0.00776424 0.0473786 -0.0967958 0.00496918 0.0456192 -0.085866 0.00729714 0.0473831 -0.0967958 0.00676138 0.0472868 -0.0967958 0.00566542 0.0466678 -0.0967958 0.00801886 0.0473417 -0.0858658 0.00889863 0.0470034 -0.0491161 0.00300417 0.0697328 -0.0485391 0.00298975 0.0703849 -0.0858659 0.00277095 0.0496592 -0.0835957 0.00144077 0.0513184 -0.085866 0.00198674 0.0506724 -0.0858659 0.00146375 0.050999 -0.0492022 0.0003045 0.0728348 -0.0484892 0.0026126 0.0717486 -0.0572971 0.00282185 0.0652188 -0.0483519 0.00288826 0.0711022 -0.0764036 0.00300466 0.0516683 -0.0809842 0.00255244 0.0511168 -0.0832494 0.00290465 0.0496324 -0.0807149 0.00289696 0.0504266 -0.0834709 0.00300466 0.0488476 -0.0798094 0.00300466 0.0499809 -0.0782484 0.00288469 0.0515928 -0.0758488 0.00287128 0.0529418 -0.0710536 0.00284886 0.0558351 -0.0663676 0.00283331 0.0587638 -0.0787506 0.00112815 0.0533301 -0.0835133 0.00207345 0.0509174 -0.0828866 0.00141466 0.0514999 -0.0673314 0.000448641 0.060224 -0.0672037 0.00140784 0.0600305 -0.0719294 0.000655751 0.0573769 -0.0765645 0.0017623 0.0541852 -0.0759559 0.000902807 0.0549584 -0.0833936 0.00258552 0.0503345 -0.0812038 0.00200174 0.0516796 -0.0788775 0.00188731 0.0528341 -0.0785996 0.00249938 0.0522856 -0.0762544 0.00244103 0.0536464 -0.0717896 0.00155305 0.0571308 -0.0668642 0.00227313 0.0595161 -0.0581946 0.0013008 0.0664615 -0.0578385 0.00222166 0.0659685 -0.0490401 0.00152238 0.0725941 -0.0967958 0.00146376 0.050999 -0.0967958 0.00224672 0.0504362 -0.0858658 0.0140652 0.0436247 -0.0540339 0.0135048 0.0694146 -0.0485894 0.0146773 0.0719246 -0.0501703 0.0152047 0.0689851 -0.0581855 0.0150244 0.0644984 -0.0630131 0.0150304 0.0605987 -0.0676541 0.0150437 0.0564934 -0.0762645 0.0150892 0.0475717 -0.0702412 0.0152047 0.0528162 -0.0700725 0.0152047 0.0529791 -0.080619 0.0151206 0.043499 -0.0797429 0.0152047 0.0432744 -0.0778397 0.0152047 0.0448357 -0.0783391 0.0151042 0.0453677 -0.0756896 0.0152047 0.0470425 -0.0816299 0.0152047 0.042219 -0.0832475 0.0151318 0.0423329 -0.0818826 0.0151274 0.0428085 -0.0768274 0.014718 0.0480899 -0.0721136 0.0150662 0.052188 -0.0682461 0.0145183 0.057145 -0.0635977 0.0144588 0.0612945 -0.0587456 0.0144317 0.0652295 -0.0536889 0.014424 0.0689127 -0.0531653 0.0150227 0.0681509 -0.0858658 0.0149068 0.0426541 -0.083525 0.0145255 0.0434672 -0.0833951 0.0149009 0.0429364 -0.0821341 0.014882 0.0433955 -0.0812675 0.0144208 0.0445487 -0.0809678 0.0148533 0.0440635 -0.0788314 0.014783 0.0458921 -0.0772777 0.0141269 0.0485044 -0.0726936 0.014618 0.0527775 -0.068664 0.0137018 0.0576049 -0.0488457 0.0142479 0.0723053 -0.0487548 0.014424 0.0721702 -0.0823533 0.0144838 0.0439071 -0.0836266 0.0140441 0.0438825 -0.0825216 0.0139763 0.0442997 -0.0814906 0.0138747 0.0449098 -0.0792394 0.0142675 0.0463268 -0.0795191 0.0136312 0.0466248 -0.0731308 0.0139125 0.0532219 -0.0733637 0.0130889 0.0534587 -0.0639931 0.0135771 0.0617651 -0.0591168 0.0135209 0.065714 -0.0858658 0.0145384 0.0431972 -0.0967958 0.0146469 0.0430647 -0.0858658 0.0151332 0.0420383 -0.0967958 0.0152047 0.0414213 -0.0618131 0.000326197 -0.0640697 -0.0578382 0.00222207 -0.0659633 -0.0858659 0.00146375 -0.0509941 -0.0851574 0.00145903 -0.0510391 -0.0835133 0.0020736 -0.0509124 -0.0833935 0.00258574 -0.0503293 -0.0858658 0.00300466 -0.0485556 -0.0832492 0.00290481 -0.0496269 -0.0826024 0.00300466 -0.0490272 -0.0807147 0.00289713 -0.0504212 -0.0804405 0.00300466 -0.0497184 -0.0758484 0.0028715 -0.0529364 -0.0754306 0.00300466 -0.0522107 -0.0710532 0.00284912 -0.0558297 -0.0714608 0.00300466 -0.0545764 -0.0503428 0.00300466 -0.0688611 -0.0567251 0.00300466 -0.064422 -0.0663671 0.00283359 -0.0587583 -0.0651455 0.00300466 -0.0584346 -0.0835957 0.00144077 -0.0513136 -0.0829775 0.00141849 -0.0514689 -0.0717895 0.00155328 -0.0571259 -0.0672035 0.00140809 -0.0600256 -0.0812037 0.0020019 -0.0516746 -0.080984 0.00255268 -0.0511116 -0.0785994 0.00249965 -0.0522804 -0.0765644 0.0017625 -0.0541802 -0.0487547 0.00222366 -0.0721653 -0.0581944 0.00130106 -0.0664566 -0.0819654 0.0013678 -0.0518012 -0.0788774 0.00188749 -0.0528291 -0.0785161 0.00110893 -0.053454 -0.0673313 0.000448638 -0.0602192 -0.085866 0.00235583 -0.0503113 -0.0782481 0.00288488 -0.0515873 -0.0762541 0.00244132 -0.0536412 -0.0668638 0.00227351 -0.059511 -0.0572965 0.00282215 -0.0652133 -0.0485894 0.00247734 -0.0719198 -0.0967958 0.00300466 -0.0485556 -0.0858659 0.00293426 -0.0491681 -0.0485393 0.00481944 -0.0703801 -0.085866 0.00743541 -0.0473853 -0.0858659 0.00676138 -0.0472819 -0.0858658 0.00530632 -0.0462538 -0.0836324 0.00554038 -0.046804 -0.0858658 0.00506903 -0.0458514 -0.081674 0.00818128 -0.048327 -0.0815727 0.0087548 -0.0481309 -0.0795839 0.00798351 -0.0497186 -0.077428 0.0077891 -0.0514841 -0.068201 0.00773918 -0.0589735 -0.068198 0.00721959 -0.0589697 -0.0538216 0.00650609 -0.0695619 -0.0491611 0.00687757 -0.0727684 -0.0568838 0.00751202 -0.0676478 -0.0587063 0.0065164 -0.0660828 -0.0498969 0.00750534 -0.0723814 -0.0583441 0.00559142 -0.065595 -0.048846 0.00576126 -0.0723004 -0.0485896 0.00533182 -0.0719197 -0.0577919 0.00498827 -0.0648511 -0.0572084 0.00480466 -0.0640651 -0.0501278 0.00480466 -0.0690111 -0.0496232 0.00480478 -0.0693713 -0.048352 0.00492085 -0.071097 -0.0491162 0.00480509 -0.0697281 -0.0787011 0.00507529 -0.048532 -0.0835003 0.00510694 -0.0462073 -0.0832321 0.00480466 -0.0449953 -0.0810328 0.00509415 -0.0470852 -0.0825536 0.00480466 -0.0451679 -0.0804748 0.00480466 -0.0460044 -0.0764331 0.0050571 -0.050302 -0.0790487 0.00545758 -0.0489992 -0.081308 0.00550666 -0.0476181 -0.0674873 0.00528099 -0.0580612 -0.0771021 0.00591011 -0.0510969 -0.0767968 0.00541083 -0.0507341 -0.0793349 0.00599743 -0.049384 -0.0815297 0.00608954 -0.0480476 -0.0837372 0.0061531 -0.0472774 -0.0679817 0.00614701 -0.0586932 -0.0858659 0.00617683 -0.0470371 -0.0681273 0.00667715 -0.0588792 -0.0837888 0.00831324 -0.0475105 -0.0858659 0.00825227 -0.0472806 -0.085866 0.00801886 -0.0473368 -0.083815 0.00762791 -0.0476287 -0.0837998 0.0068798 -0.0475599 -0.0816686 0.00678444 -0.0483166 -0.0817135 0.00750778 -0.0484035 -0.0796061 0.00733095 -0.0497485 -0.0774235 0.00716046 -0.0514788 -0.0795257 0.0066457 -0.0496404 -0.0773163 0.00651362 -0.0513514 -0.067764 0.00566948 -0.0584148 -0.0671733 0.00500546 -0.0576597 -0.0858658 0.00889863 -0.0469985 -0.0967958 0.00566542 -0.0466629 -0.0967958 0.00676138 -0.0472819 -0.0858659 0.00566543 -0.0466629 -0.0822497 0.0152047 -0.0419741 -0.0830994 0.0152047 -0.041723 -0.0806184 0.0151209 -0.0434933 -0.0778397 0.0152047 -0.0448308 -0.071515 0.0152047 -0.0515748 -0.0531643 0.0150233 -0.0681448 -0.058822 0.0152047 -0.0627717 -0.0623996 0.0152047 -0.0598638 -0.0692482 0.0152047 -0.053761 -0.0483636 0.0150223 -0.0713183 -0.0491161 0.0152042 -0.069728 -0.0835249 0.0145257 -0.0434621 -0.0823532 0.0144841 -0.043902 -0.0814906 0.0138747 -0.0449049 -0.0775605 0.0134127 -0.0487599 -0.0731305 0.0139129 -0.0532169 -0.0688426 0.0127816 -0.0577967 -0.0686638 0.0137023 -0.0575999 -0.0641347 0.0126051 -0.061929 -0.0592374 0.0125267 -0.0658667 -0.0541425 0.0125045 -0.0695681 -0.0540336 0.0135054 -0.0694096 -0.0809674 0.0148536 -0.0440581 -0.0812673 0.0144211 -0.0445436 -0.0792392 0.0142678 -0.0463217 -0.0768268 0.0147185 -0.0480845 -0.0772775 0.0141272 -0.0484993 -0.0635971 0.0144596 -0.0612891 -0.0639928 0.0135776 -0.0617602 -0.058745 0.0144325 -0.065224 -0.0591165 0.0135214 -0.065709 -0.0487542 0.0144246 -0.0721644 -0.0490405 0.0137208 -0.0725898 -0.0858658 0.0151335 -0.0420324 -0.0832472 0.0151321 -0.0423271 -0.0858658 0.0149071 -0.0426486 -0.083395 0.0149013 -0.0429309 -0.0818821 0.0151276 -0.0428027 -0.0821338 0.0148823 -0.04339 -0.0783383 0.0151045 -0.045362 -0.0788309 0.0147834 -0.0458867 -0.0762636 0.0150895 -0.047566 -0.0721126 0.0150667 -0.0521822 -0.072693 0.0146186 -0.0527721 -0.067653 0.0150442 -0.0564875 -0.0682455 0.0145191 -0.0571395 -0.063012 0.015031 -0.0605927 -0.0581844 0.015025 -0.0644923 -0.0536883 0.0144248 -0.0689073 -0.0967958 0.0150839 -0.0422148 -0.0967958 0.0146469 -0.0430598 -0.0858658 0.0145387 -0.0431921 -0.048352 0.0171209 -0.0710972 -0.0485896 0.0175318 -0.0719197 -0.0490407 0.0184879 -0.0725896 -0.0539891 0.0187458 -0.0694481 -0.0491613 0.0190792 -0.0727687 -0.0492026 0.0197072 -0.07283 -0.0536444 0.0178057 -0.0689513 -0.0587413 0.0170047 -0.0626778 -0.0670941 0.0172157 -0.0561829 -0.0620304 0.0170047 -0.0597932 -0.0580443 0.0171963 -0.0645332 -0.0710827 0.0170047 -0.0496258 -0.0787667 0.0182457 -0.0421026 -0.0778964 0.0172853 -0.0414744 -0.0807606 0.0173248 -0.0384785 -0.0783761 0.0176834 -0.0418206 -0.0754523 0.0180955 -0.0470207 -0.0484892 0.0173964 -0.0717434 -0.0531129 0.0171915 -0.0681851 -0.0586314 0.0178278 -0.0652696 -0.0627219 0.0172036 -0.0605392 -0.0678151 0.0179164 -0.0568412 -0.0710578 0.0172335 -0.0514883 -0.0532298 0.0197519 -0.0701819 -0.0590054 0.0187914 -0.0657386 -0.0822485 0.0213808 -0.0385093 -0.0824103 0.0208233 -0.0388089 -0.0789029 0.020861 -0.0422009 -0.0790621 0.020288 -0.0423158 -0.0794082 0.0209394 -0.0414629 -0.0758908 0.0199557 -0.0473007 -0.072274 0.0202784 -0.0524506 -0.0757948 0.0205185 -0.0472394 -0.0722954 0.0191388 -0.0524252 -0.0758788 0.0193315 -0.0472931 -0.0791129 0.019624 -0.0423525 -0.0806606 0.0205499 -0.0402826 -0.0807532 0.0198617 -0.0403754 -0.0825024 0.0202163 -0.0389794 -0.0823933 0.0185103 -0.0387774 -0.0805077 0.0183712 -0.0401292 -0.0801651 0.01775 -0.0397857 -0.0809654 0.0170155 -0.0370852 -0.0797314 0.0173106 -0.0393509 -0.0763477 0.0170047 -0.0415989 -0.073625 0.0170047 -0.0458539 -0.0745803 0.0172541 -0.0464639 -0.0750536 0.017603 -0.0467661 -0.0633712 0.0178608 -0.0612398 -0.0637735 0.0188593 -0.0616738 -0.0682406 0.0189727 -0.0572295 -0.071859 0.0179986 -0.0520949 -0.0757343 0.0186914 -0.0472008 -0.079019 0.0189185 -0.0422847 -0.0807091 0.0191068 -0.0403312 -0.0822476 0.0180263 -0.0385077 -0.0820572 0.0176186 -0.038155 -0.0818601 0.0173379 -0.03779 -0.0858657 0.0171165 -0.0369221 -0.0858657 0.017843 -0.0378553 -0.0858657 0.0203705 -0.0383453 -0.0839408 0.0197057 -0.0385746 -0.0858657 0.0190667 -0.0384252 -0.0838999 0.0190138 -0.0385172 -0.0858657 0.0178299 -0.0378445 -0.0837446 0.0177947 -0.0379028 -0.0836476 0.0173705 -0.0374241 -0.082619 0.0172968 -0.0374526 -0.0831707 0.0203287 -0.0386684 -0.081682 0.0171679 -0.0374602 -0.0828038 0.0176901 -0.0379681 -0.083832 0.0183558 -0.0382843 -0.0824409 0.0187399 -0.0388656 -0.0825121 0.0193142 -0.0389975 -0.083953 0.020364 -0.0384634 -0.0825108 0.020114 -0.038995 -0.0830836 0.0214137 -0.0381053 -0.0825609 0.0214048 -0.0383299 -0.0967958 0.020391 -0.0383388 -0.0858657 0.0190518 -0.0384224 -0.0967958 0.0190148 -0.038415 -0.0858657 0.0184046 -0.0382114 -0.0967958 0.0177803 -0.0378021 -0.0705993 0.0327422 -0.023228 -0.0967958 0.0283669 -0.023367 -0.0722214 0.0313277 -0.0238533 -0.0722047 0.0296487 -0.0238705 -0.0703623 0.0298053 -0.0238992 -0.0705508 0.0283669 -0.023367 -0.0796369 0.0321771 -0.0235583 -0.0787851 0.0330962 -0.0229492 -0.0775228 0.0335949 -0.0224207 -0.0967958 0.0296487 -0.0238705 -0.0799655 0.0296487 -0.0238705 -0.0800418 0.0304899 -0.023951 -0.0967958 0.0313277 -0.0238533 -0.0799488 0.0313277 -0.0238533 -0.0721284 0.0304899 0.0239558 -0.0722214 0.0313277 0.0238582 -0.0733851 0.0330962 0.0229541 -0.0746474 0.0335949 0.0224256 -0.0760851 0.0337386 0.0222307 -0.0709653 0.0337937 0.0221488 -0.0967958 0.0337937 0.0221488 -0.0775243 0.0335946 0.022426 -0.0967958 0.0313277 0.0238582 -0.0967958 0.0296487 0.0238753 -0.0800418 0.0304897 0.0239559 -0.0799655 0.0296487 0.0238753 -0.0967958 0.0283669 0.0233719 -0.0705508 0.0283669 0.0233719 -0.0722047 0.0296487 0.0238753 -0.0967958 0.0328518 0.0231534 -0.079637 0.032177 0.0235632 -0.0887958 -0.0258402 -0.0248628 -0.0887958 -0.0212027 -0.0226449 -0.0887958 -0.0217196 -0.0214543 -0.0887688 -0.0157327 -0.0229142 -0.0884832 -0.0151394 -0.0233106 -0.0967958 -0.015007 -0.0233961 -0.0890536 -0.0172688 -0.0218058 -0.0967958 -0.0169239 -0.022049 -0.0967958 -0.0216537 -0.0212143 -0.0890536 -0.0217873 -0.0212584 -0.0887958 -0.025936 0.0250946 -0.0887958 -0.0212027 0.0226497 -0.0887958 -0.0194473 0.0225349 -0.0887958 -0.0216704 0.0215403 -0.0887958 -0.0194612 0.0213191 -0.0887958 -0.0178373 0.0232437 -0.0887958 -0.0173812 0.0220956 -0.0967958 -0.0216537 0.0212191 -0.0890958 -0.0237673 0.0225016 -0.089087 -0.0169239 0.0220539 -0.0890958 -0.0172154 0.0218456 -0.0885017 -0.0150378 0.0233812 -0.0874235 -0.0139325 0.0241884 -0.0866285 -0.0125556 0.0281319 -0.0867535 -0.0127721 0.0274603 -0.0867657 -0.0127932 0.0275529 -0.0870407 -0.0132695 0.0265479 -0.0876074 -0.0142511 0.0256835 -0.0879357 -0.0148198 0.0253628 -0.088224 -0.015319 0.0236534 -0.0853317 -0.0313344 0.025498 -0.0867958 -0.0294307 0.0264246 -0.0853317 -0.0269568 0.0300896 -0.0867958 -0.0269568 -0.0300847 -0.0874418 -0.0290238 -0.0264618 -0.0878717 -0.0264318 -0.0280363 -0.0882599 -0.0274028 -0.0261226 -0.0868639 -0.0308237 -0.0259256 -0.0871612 -0.02646 -0.02968 -0.0871905 -0.0296786 -0.0263848 -0.0867741 -0.0128079 -0.024217 -0.0879357 -0.0148198 -0.025358 -0.0867535 -0.0127721 -0.0274554 -0.0866828 -0.0126497 -0.0279252 -0.0874025 -0.0138961 -0.0240921 -0.0867958 -0.0128453 -0.0267535 -0.0881718 -0.0145105 0.0236643 -0.0880275 -0.0142808 0.023753 -0.0967958 -0.013741 0.0238911 -0.0876307 -0.013741 -0.0238863 -0.0872305 -0.0130877 -0.0239334 -0.0967958 -0.0123842 -0.0238421 -0.0869609 -0.0126475 -0.0238938 -0.0967958 -0.013741 -0.0238863 -0.0887236 -0.0166246 -0.0225696 -0.0887958 -0.0173812 -0.0235819 -0.0887837 -0.0170702 -0.0222134 -0.0886652 -0.0163674 -0.0243477 -0.0886225 -0.0162166 -0.0228823 -0.0885072 -0.0158894 -0.0246839 -0.088363 -0.0155715 -0.0248991 -0.0887937 -0.0172522 0.0221911 -0.0887958 -0.0173812 0.0235868 -0.0887876 -0.0171257 0.0222918 -0.0887612 -0.0168564 0.0239924 -0.0883515 -0.015549 0.023496 -0.0882599 -0.0153812 0.0250296 -0.0869721 -0.0292587 0.0264544 -0.0880404 -0.0263911 0.0279332 -0.0879373 -0.0280823 0.0264319 -0.0885341 -0.0270121 0.0260287 -0.0885259 -0.0260327 0.0270382 -0.0887479 -0.026372 0.0255316 -0.0887829 -0.0261624 0.0253215 -0.0887829 -0.0253144 0.0261695 -0.0884104 -0.0260514 -0.0270739 -0.0885971 -0.0257892 -0.0266762 -0.0883202 -0.0261375 -0.0272388 -0.0887958 -0.0249273 -0.025778 -0.0887071 -0.0264319 -0.025456 -0.0886784 -0.0265215 -0.0255423 -0.0785533 0.0289547 0.0262057 -0.0797522 0.0289547 0.0236667 -0.0775101 0.0289547 0.0251625 -0.0760851 0.0289547 0.0247807 -0.072418 0.0289547 0.0236667 -0.0732351 0.0289547 0.0276307 -0.0733851 0.0289547 0.0323072 -0.0760851 0.0289547 0.0330307 -0.0746601 0.0289547 0.0300988 -0.0775101 0.0289547 0.0300988 -0.0760851 0.0289547 -0.0247758 -0.0775101 0.0289547 -0.0251576 -0.0785533 0.0289547 -0.0262008 -0.0760851 0.0289547 -0.0304758 -0.0746601 0.0289547 -0.030094 -0.0732351 0.0289547 -0.0276258 -0.0512108 0.028469 -0.0595706 -0.0510025 0.0284712 -0.0642815 -0.0509905 0.0284712 -0.0642759 -0.0509815 0.0284712 -0.0642717 -0.0511042 0.0284709 -0.0643061 -0.0509796 0.0284712 -0.0642708 -0.0509546 0.0284712 -0.0642587 -0.0509074 0.0284713 -0.0642349 -0.0503894 0.0284712 -0.0638807 -0.0507249 0.0284714 -0.064131 -0.0527424 0.0284786 -0.0595073 -0.0525274 0.0284768 -0.0594591 -0.0524187 0.028476 -0.059442 -0.0531751 0.0284825 -0.0596675 -0.0523641 0.0284756 -0.0594352 -0.0523514 0.0284755 -0.0594338 -0.0523572 0.0284755 -0.0594344 -0.0523538 0.0284755 -0.059434 -0.0531585 0.0284823 -0.0596597 -0.0538813 0.0284883 -0.0601671 -0.0538748 0.0284882 -0.0601605 -0.0543699 0.028489 -0.0608532 -0.0545657 0.0284724 -0.0625247 -0.0545771 0.0284729 -0.0624708 -0.0545965 0.028474 -0.0623618 -0.0545642 0.0284723 -0.0625314 -0.0546212 0.0284765 -0.0621408 -0.0543719 0.0284889 -0.0608574 -0.0546128 0.0284818 -0.0617006 -0.0546105 0.028482 -0.0616798 -0.0545626 0.0284722 -0.0625382 -0.0545531 0.0284718 -0.0625784 -0.0545595 0.0284721 -0.0625516 -0.0542417 0.0284643 -0.0633166 -0.0542562 0.0284646 -0.0632931 -0.0543118 0.0284655 -0.063197 -0.0544106 0.0284676 -0.0629969 -0.0542381 0.0284643 -0.0633225 -0.0545634 0.0284723 -0.0625348 -0.0542344 0.0284642 -0.0633284 -0.054227 0.0284641 -0.06334 -0.05368 0.028461 -0.0639521 -0.0537004 0.028461 -0.0639354 -0.0542362 0.0284642 -0.0633254 -0.0541968 0.0284637 -0.0633863 -0.0537808 0.028461 -0.0638662 -0.0539335 0.0284614 -0.0637171 -0.0536696 0.028461 -0.0639604 -0.0536175 0.0284611 -0.064001 -0.0536593 0.0284611 -0.0639686 -0.0536645 0.028461 -0.0639645 -0.0536671 0.028461 -0.0639625 -0.0530416 0.0284641 -0.0643295 -0.053244 0.0284628 -0.0642363 -0.0528861 0.0284651 -0.0643872 -0.0529122 0.0284649 -0.0643783 -0.0528336 0.0284654 -0.0644041 -0.0529155 0.0284649 -0.0643772 -0.0529187 0.0284649 -0.064376 -0.0529252 0.0284649 -0.0643737 -0.0529383 0.0284648 -0.0643691 -0.0502875 0.0284711 -0.0637856 -0.0503075 0.0284711 -0.0638051 -0.050083 0.0284708 -0.0635585 -0.0502287 0.028471 -0.0637258 -0.05028 0.0284711 -0.0637782 -0.0502676 0.0284711 -0.0637659 -0.0502775 0.0284711 -0.0637758 -0.0502835 0.0284711 -0.0637817 -0.0495436 0.0284688 -0.0622596 -0.0496603 0.0284696 -0.0627829 -0.0497402 0.0284699 -0.0629897 -0.049763 0.02847 -0.0630406 -0.0497749 0.02847 -0.0630659 -0.049781 0.02847 -0.0630785 -0.0498384 0.0284702 -0.0631902 -0.0497825 0.02847 -0.0630816 -0.0497846 0.02847 -0.0630859 -0.0497871 0.02847 -0.0630911 -0.0495482 0.0284688 -0.0622978 -0.0495763 0.0284676 -0.0614698 -0.0495276 0.0284682 -0.0619096 -0.0495321 0.0284686 -0.0621311 -0.0495416 0.0284687 -0.0622422 -0.0495432 0.0284687 -0.0622561 -0.049556 0.0284689 -0.062353 -0.0495441 0.0284688 -0.0622642 -0.0495448 0.0284688 -0.06227 -0.0496929 0.0284672 -0.061064 -0.0496264 0.0284674 -0.0612636 -0.0495901 0.0284676 -0.0614048 -0.0495872 0.0284676 -0.0614178 -0.0495993 0.0284675 -0.061366 -0.0495931 0.0284675 -0.0613918 -0.0499177 0.0284668 -0.0606125 -0.0495916 0.0284675 -0.0613983 -0.0495909 0.0284675 -0.0614016 -0.0501305 0.0284668 -0.0603216 -0.0499949 0.0284668 -0.0604967 -0.0499326 0.0284668 -0.0605891 -0.0499028 0.0284669 -0.0606365 -0.0498741 0.0284669 -0.0606844 -0.0499194 0.0284668 -0.0606097 -0.0499213 0.0284668 -0.0606068 -0.049925 0.0284668 -0.0606008 -0.0512356 0.0284691 -0.0595618 -0.0508091 0.0284678 -0.0597565 -0.0506222 0.0284674 -0.0598747 -0.0504448 0.0284671 -0.0600097 -0.0505322 0.0284672 -0.0599401 -0.0505101 0.0284672 -0.0599571 -0.0504884 0.0284671 -0.0599742 -0.0504991 0.0284671 -0.0599657 -0.0504936 0.0284671 -0.0599701 -0.0504909 0.0284671 -0.0599723 -0.0520785 0.0284735 -0.059419 -0.0523092 0.0284751 -0.0594296 -0.0523367 0.0284753 -0.0594322 -0.0708826 0.0338192 0.0260153 -0.0711893 0.0345123 0.025018 -0.073131 0.035733 0.0229721 -0.0753769 0.03618 0.0221717 -0.0785074 0.0358984 0.0226796 -0.0794514 0.0354687 0.0233661 -0.0795249 0.0355382 0.0233118 -0.0712996 0.0344497 0.0250401 -0.0718286 0.0350774 0.0240945 -0.0726731 0.0355507 0.0232901 -0.0736998 0.0359083 0.0226619 -0.0737499 0.0358365 0.0227282 -0.0748904 0.0360576 0.0223352 -0.074865 0.0361307 0.0222616 -0.0726339 0.0353001 0.0234775 -0.0719806 0.0349059 0.0241217 -0.0719579 0.0349597 0.0241345 -0.0709404 0.0337377 0.0259808 -0.0711432 0.0340516 0.025454 -0.0709484 0.0337096 0.0259651 -0.0814778 0.0323349 0.027972 -0.0812278 0.0336972 0.0259835 -0.0812395 0.0337152 0.0260121 -0.0807691 0.0343851 0.0249436 -0.0802288 0.0349477 0.024154 -0.0814876 0.0323658 0.0279946 -0.0812494 0.0337537 0.0260136 -0.0812688 0.0337814 0.0260254 -0.0794219 0.035418 0.0233747 -0.0787981 0.0356072 0.0229617 -0.0784356 0.0357764 0.0227608 -0.074901 0.0360075 0.0223549 -0.0746217 0.0359141 0.0224327 -0.0737705 0.0357862 0.0227437 -0.073785 0.0357338 0.022745 -0.0733713 0.0356069 0.0229621 -0.0707581 0.0338771 0.0260127 -0.0705651 0.0333548 0.0267996 -0.0705689 0.0324581 0.0280671 -0.0706645 0.0323956 0.0280169 -0.0709073 0.0337938 0.0260067 -0.0706829 0.0323651 0.0279941 -0.0812935 0.0338068 0.026034 -0.0808803 0.0344385 0.0250578 -0.080839 0.0343865 0.025048 -0.0773252 0.0360518 0.0223456 -0.0773142 0.0360017 0.0223652 -0.0761088 0.0362047 0.0221267 -0.0761081 0.0360811 0.0222239 -0.0727461 0.0354812 0.0233449 -0.0727753 0.0354305 0.0233537 -0.0719216 0.0350109 0.0241342 -0.0713408 0.0343977 0.0250305 -0.0709267 0.0337662 0.025995 -0.0815316 0.0324219 0.0280372 -0.0814756 0.0323047 0.0279504 -0.0812695 0.0314838 0.0292011 -0.081285 0.031516 0.0292287 -0.0815057 0.0323956 0.0280169 -0.0816004 0.0324578 0.0280669 -0.0813808 0.0315776 0.0293009 -0.0704949 0.0324676 0.0280783 -0.07057 0.0324557 0.0280698 -0.0706386 0.0324219 0.0280372 -0.0706948 0.0323026 0.0279533 -0.0706924 0.0323349 0.027972 -0.0706647 0.0323934 0.0280198 -0.0754143 0.0299116 0.0332427 -0.080564 0.030268 0.0306557 -0.0797621 0.0297753 0.0315854 -0.0799836 0.0299429 0.031398 -0.0787488 0.0296143 0.032328 -0.0760851 0.0296807 0.0330307 -0.0774297 0.0296603 0.0328652 -0.0776039 0.0296122 0.0328127 -0.0747167 0.0297707 0.0328544 -0.0722308 0.0302529 0.0314128 -0.0720116 0.0303947 0.0311821 -0.0714117 0.0307598 0.0303362 -0.0710594 0.0312164 0.0296169 -0.0706926 0.0323327 0.0279749 -0.0713203 0.030905 0.030582 -0.071756 0.0306259 0.0311452 -0.0718892 0.0305584 0.0312904 -0.0718997 0.0305533 0.0313014 -0.0719361 0.030536 0.0313406 -0.0807504 0.0303968 0.0308573 -0.0804006 0.0302063 0.0311824 -0.08012 0.0300178 0.0316332 -0.0809039 0.0306521 0.0304355 -0.0806348 0.0303985 0.0307808 -0.0808504 0.0305876 0.0305293 -0.08131 0.0315436 0.0292558 -0.0805784 0.0303459 0.0307118 -0.0812636 0.0314503 0.0291754 -0.0704951 0.0324655 0.0280813 -0.0719412 0.0305336 0.0313463 -0.0793027 0.0298503 0.0321411 -0.0754332 0.0298772 0.03307 -0.073497 0.0300906 0.0325078 -0.0719793 0.0305065 0.0312573 -0.0710164 0.031316 0.0296922 -0.0709848 0.0313384 0.0297177 -0.0706065 0.032441 0.0280571 -0.070872 0.0313545 0.0297713 -0.071601 0.0307136 0.030962 -0.0718372 0.030584 0.0312349 -0.0718787 0.0305635 0.0312793 -0.0719103 0.0305483 0.0313124 -0.0719209 0.0305433 0.0313234 -0.0719311 0.0305384 0.0313349 -0.0719616 0.030524 0.0313691 -0.0720028 0.030505 0.0314144 -0.0719525 0.0305302 0.0312905 -0.0720868 0.0304684 0.0315035 -0.0718555 0.0305399 0.0313787 -0.0722608 0.0304001 0.0316763 -0.0726334 0.0302812 0.0319991 -0.0734357 0.0300995 0.0326246 -0.0734769 0.0301039 0.0325491 -0.0774651 0.0298046 0.0329834 -0.0754296 0.029902 0.0331121 -0.0774532 0.0297803 0.0329403 -0.0813429 0.0315647 0.0292805 -0.0800198 0.0300183 0.0314621 -0.0793864 0.0298416 0.0322558 -0.0781204 0.0297899 0.0329227 -0.0805419 0.0303016 0.030999 -0.0805075 0.0302767 0.0310452 -0.0800864 0.0300488 0.0315377 -0.0800509 0.0300403 0.0315004 -0.0804725 0.0302525 0.0310911 -0.0805162 0.0302829 0.0310337 -0.0805248 0.0302891 0.0310221 -0.0805334 0.0302953 0.0310106 -0.0805376 0.0302984 0.0310048 -0.0806732 0.0304081 0.0308123 -0.0807941 0.0305254 0.0306236 -0.0808539 0.0305916 0.0305234 -0.0808573 0.0305956 0.0305176 -0.0808775 0.0306196 0.0304823 -0.0808641 0.0306035 0.0305058 -0.0812334 0.0310416 0.029955 -0.0810929 0.030931 0.0300625 -0.0814589 0.0315802 0.0293258 -0.0799803 0.0298987 0.0313777 -0.0804916 0.0301605 0.0307521 -0.0805659 0.0303081 0.0306808 -0.0706388 0.0324198 0.0280401 -0.0774429 0.0297457 0.0329047 -0.0735266 0.030032 0.0324356 -0.0754359 0.0298025 0.0330101 -0.0719988 0.0304738 0.0312266 -0.0720095 0.0304353 0.0312011 -0.0710401 0.0312865 0.0296656 -0.0710545 0.0312523 0.0296399 -0.0792422 0.0297497 0.0320378 -0.0792368 0.0297041 0.0320215 -0.0774349 0.0297042 0.0328793 -0.0754351 0.0297599 0.0329957 -0.0735335 0.0299918 0.0324108 -0.0735351 0.0299494 0.0323955 -0.0706831 0.032363 0.027997 -0.0735141 0.0300661 0.0324688 -0.0754354 0.029843 0.0330351 -0.0792554 0.0297926 0.0320643 -0.0792762 0.0298275 0.0320999 -0.0799967 0.0299844 0.0314267 -0.0806021 0.0303772 0.0307462 -0.0704951 0.0324655 -0.0280764 -0.0706065 0.032441 -0.0280523 -0.0706388 0.0324198 -0.0280352 -0.0706829 0.0323651 -0.0279892 -0.0706831 0.032363 -0.0279921 -0.0706926 0.0323327 -0.02797 -0.0816004 0.0324578 -0.028062 -0.0807715 0.0347281 -0.024665 -0.0772798 0.0360576 -0.0223304 -0.074432 0.036067 -0.0223721 -0.0748451 0.0360518 -0.0223408 -0.0709409 0.0341918 -0.0255204 -0.0708767 0.0338068 -0.0260292 -0.0724218 0.0354313 -0.023491 -0.0808707 0.0344497 -0.0250352 -0.0809809 0.0345123 -0.0250131 -0.0803416 0.0350774 -0.0240896 -0.0794971 0.0355507 -0.0232853 -0.0784203 0.0358365 -0.0227233 -0.0784704 0.0359083 -0.022657 -0.0773052 0.0361307 -0.0222567 -0.0793949 0.0354305 -0.0233488 -0.0802123 0.0349597 -0.0241296 -0.0808295 0.0343977 -0.0250256 -0.0706924 0.0323349 -0.0279671 -0.0706946 0.0323047 -0.0279455 -0.0709307 0.0337152 -0.0260072 -0.0713312 0.0343865 -0.0250431 -0.0709424 0.0336972 -0.0259786 -0.0716523 0.0346391 -0.0245417 -0.0719414 0.0349477 -0.0241491 -0.0727483 0.035418 -0.0233698 -0.0706849 0.0325374 -0.0276285 -0.0706645 0.0323956 -0.028012 -0.0709208 0.0337537 -0.0260087 -0.0709014 0.0337814 -0.0260205 -0.0706386 0.0324219 -0.0280323 -0.074856 0.0360017 -0.0223603 -0.0760621 0.0360811 -0.022219 -0.0760851 0.0360292 -0.0222258 -0.0775485 0.0359141 -0.0224278 -0.0812876 0.0338192 -0.0260104 -0.0814121 0.0338771 -0.0260078 -0.0815057 0.0323956 -0.028012 -0.081263 0.0337938 -0.0260018 -0.0814876 0.0323658 -0.0279898 -0.0814778 0.0323349 -0.0279671 -0.0704949 0.0324676 -0.0280734 -0.070752 0.0338646 -0.026027 -0.0705689 0.0324581 -0.0280622 -0.0712899 0.0344385 -0.0250529 -0.0718115 0.0350654 -0.0241097 -0.0727188 0.0354687 -0.0233612 -0.0736628 0.0358984 -0.0226747 -0.0737346 0.0357764 -0.0227559 -0.0760614 0.0362047 -0.0221218 -0.0772692 0.0360075 -0.02235 -0.0794242 0.0354812 -0.02334 -0.0783997 0.0357862 -0.0227388 -0.0802486 0.0350109 -0.0241293 -0.0812435 0.0337662 -0.0259901 -0.0812298 0.0337377 -0.0259759 -0.0814851 0.0325338 -0.0276334 -0.0710623 0.0311721 -0.0296086 -0.0706948 0.0323026 -0.0279484 -0.0733832 0.029934 -0.0323012 -0.0724692 0.0301628 -0.0316364 -0.0754783 0.0297572 -0.0329959 -0.0774816 0.0296585 -0.0328468 -0.0807702 0.0304431 -0.0303108 -0.0806027 0.0303043 -0.0305926 -0.0800264 0.0299187 -0.0313243 -0.0812695 0.0314837 -0.0291964 -0.0806171 0.0303815 -0.0306492 -0.0802932 0.030145 -0.0313064 -0.080443 0.0302331 -0.0311241 -0.0807084 0.0303604 -0.0309145 -0.080712 0.0304434 -0.0307488 -0.0814589 0.0315802 -0.0293209 -0.0742121 0.0300112 -0.0328735 -0.080174 0.0300864 -0.0314402 -0.0771599 0.0298215 -0.0331831 -0.0794148 0.0298628 -0.0321789 -0.0775308 0.0298148 -0.0330111 -0.0793855 0.0298668 -0.0321401 -0.0754595 0.0299089 -0.0332431 -0.0775181 0.0298029 -0.032965 -0.0740077 0.0300312 -0.03278 -0.0740367 0.0300283 -0.0327939 -0.0718735 0.0305313 -0.0313942 -0.0719386 0.0305348 -0.0313386 -0.0734685 0.0300945 -0.0326369 -0.0719968 0.030498 -0.0312722 -0.073529 0.0300856 -0.0325198 -0.0735459 0.0300611 -0.0324806 -0.0793809 0.0298409 -0.0322547 -0.0793559 0.029858 -0.0320981 -0.0775058 0.0297787 -0.0329219 -0.075477 0.0298745 -0.0330703 -0.0754789 0.0298403 -0.0330353 -0.0720268 0.0304267 -0.031216 -0.072029 0.0303861 -0.0311971 -0.0710656 0.0312069 -0.0296276 -0.0714039 0.0307671 -0.0303177 -0.0708784 0.0313451 -0.0297824 -0.0710283 0.0311509 -0.0301234 -0.0719701 0.0305218 -0.0313055 -0.0720162 0.0304653 -0.0312415 -0.0735582 0.030027 -0.0324474 -0.0739789 0.0300342 -0.032766 -0.0740948 0.0300225 -0.0328211 -0.0744507 0.0299895 -0.0329702 -0.0812636 0.0314502 -0.0291707 -0.0810187 0.0308228 -0.0298212 -0.0806046 0.030344 -0.0306181 -0.0792894 0.029712 -0.0319784 -0.0800295 0.0299626 -0.031345 -0.0796927 0.0297546 -0.0316439 -0.0787867 0.0296165 -0.0323014 -0.0750167 0.0297472 -0.032919 -0.0800658 0.0300377 -0.0314092 -0.0813428 0.0315646 -0.0292757 -0.0813099 0.0315435 -0.029251 -0.0806407 0.0304125 -0.0306836 -0.0800426 0.030004 -0.0313739 -0.079308 0.0298004 -0.0320215 -0.0792948 0.0297576 -0.0319948 -0.0774869 0.0297024 -0.0328609 -0.0760851 0.0296807 -0.0330258 -0.0754764 0.0297161 -0.0329914 -0.0705691 0.032456 -0.0280652 -0.0709545 0.0313427 -0.0297511 -0.0709912 0.0313291 -0.0297286 -0.0706647 0.0323934 -0.0280149 -0.0710227 0.0313067 -0.029703 -0.0710464 0.0312771 -0.0296763 -0.0710607 0.0312428 -0.0296506 -0.0806735 0.0304337 -0.0307179 -0.0802144 0.0301052 -0.0313959 -0.0801535 0.0300772 -0.0314622 -0.0799614 0.0300024 -0.0316577 -0.0801329 0.0300682 -0.0314842 -0.0802026 0.0300513 -0.0315424 -0.0798715 0.0299734 -0.0317425 -0.0797789 0.0299471 -0.0318258 -0.0800971 0.0300597 -0.0314473 -0.079329 0.0298353 -0.0320571 -0.077495 0.029744 -0.0328862 -0.0754793 0.0297998 -0.0330102 -0.0735651 0.0299867 -0.0324227 -0.0735666 0.0299443 -0.0324074 -0.0813807 0.0315775 -0.0292961 -0.0816753 0.0324676 -0.0280734 -0.0814756 0.0323047 -0.0279455 -0.081285 0.0315159 -0.0292239 -0.0815316 0.0324219 -0.0280323 -0.0728698 0.0479458 -0.00441727 -0.0729288 0.0538047 -0.0032192 -0.0729958 0.0538047 2.44063e-06 -0.0729288 0.0538047 0.00322408 -0.0725098 0.0479326 0.0086689 -0.0736519 0.0460158 -0.00568513 -0.0737822 0.0453047 0.0056998 -0.0736519 0.0460158 0.00569001 -0.0730043 0.0466187 -0.00867161 -0.0734958 0.0466275 -2.5996e-05 -0.0733694 0.0466253 0.00440652 -0.0738651 0.0460158 2.44063e-06 -0.0733671 0.0466252 -0.00444298 -0.0728721 0.0479459 0.00438105 -0.0730006 0.0472402 0.0043869 -0.0729983 0.0472401 -0.00442318 -0.0726376 0.0472306 -0.00866577 -0.0725098 0.0479326 -0.00866402 -0.0729958 0.0479504 -2.58308e-05 -0.073125 0.0472433 -2.58687e-05 -0.0864767 -0.0297329 0.0263626 -0.0858602 -0.0304197 0.0261168 -0.0857418 -0.0308398 0.0258205 -0.0854834 -0.0313273 0.0254463 -0.0853572 -0.0313966 0.0254213 -0.0869458 -0.0295752 0.0263022 -0.0872896 -0.0292687 0.0263386 -0.0874542 -0.0291083 0.0263464 -0.0876193 -0.0285199 0.0264868 -0.0882743 -0.0281452 0.0262327 -0.0888034 -0.0272689 0.025861 -0.0890958 -0.0261481 0.0248824 -0.0887958 -0.0235552 0.0227138 -0.0890958 -0.0217671 0.0212563 -0.0890958 -0.0194227 0.0210216 -0.0890936 -0.0170696 0.021946 -0.0885197 -0.0150686 0.0233613 -0.0884818 -0.0158278 0.0232966 -0.0890131 -0.0163653 0.0224717 -0.0886314 -0.0162464 0.0229866 -0.0882599 -0.0153812 0.0236134 -0.0868377 -0.0127544 0.0241131 -0.0869069 -0.0125824 0.0239343 -0.0873449 -0.0131944 0.0239392 -0.0884838 -0.015007 0.0234009 -0.0868952 -0.0126678 0.0240046 -0.0876833 -0.0137329 0.0238925 -0.0853992 -0.025226 0.0315551 -0.0854712 -0.0254066 0.0313692 -0.0854066 -0.0256551 0.0311512 -0.0857287 -0.025801 0.0308664 -0.0855748 -0.0258822 0.030836 -0.0863486 -0.0261581 0.0301271 -0.0859093 -0.0261385 0.0303646 -0.0869458 -0.0262951 0.0295823 -0.0867958 -0.0264175 0.0294378 -0.0871405 -0.026469 0.0290903 -0.0872834 -0.026481 0.0289325 -0.0875394 -0.0263404 0.0290287 -0.088491 -0.0261232 0.0278328 -0.088756 -0.0259093 0.0273716 -0.0887479 -0.0255245 0.0263791 -0.0887958 -0.0227067 0.0235623 -0.0887958 -0.0250875 0.0259431 -0.0890958 -0.0248753 0.0261552 -0.0890958 -0.0211125 0.0229359 -0.0889571 -0.0164649 0.0245974 -0.0887904 -0.0171744 0.0237491 -0.0885197 -0.0153872 0.0252858 -0.0887873 -0.0159435 0.0249387 -0.0886668 -0.0163736 0.0243481 -0.0869555 -0.0262586 -0.0303313 -0.0868452 -0.0257616 -0.0311144 -0.0869734 -0.0252239 -0.0315429 -0.0870963 -0.0258597 -0.0307667 -0.0874111 -0.0262607 -0.0297558 -0.0873471 -0.0265296 -0.0291841 -0.0877186 -0.0263404 -0.0290238 -0.0885197 -0.026018 -0.0275785 -0.088529 -0.0259027 -0.0268329 -0.0887214 -0.0258391 -0.0272468 -0.0882599 -0.0261858 -0.0273426 -0.0890027 -0.0253446 -0.0266196 -0.0890958 -0.0247151 -0.0259902 -0.0887092 -0.0255136 -0.0263629 -0.0887958 -0.0194473 -0.02253 -0.0887958 -0.0227067 -0.0235574 -0.0887958 -0.0178373 -0.0232388 -0.0890958 -0.0175593 -0.0238234 -0.0882599 -0.0153812 -0.0250247 -0.0881976 -0.0148237 -0.0256155 -0.0867996 -0.0123842 -0.0238421 -0.0884062 -0.015007 -0.0233961 -0.0868532 -0.0125704 -0.0239214 -0.086842 -0.0124765 -0.0238721 -0.0881829 -0.0152479 -0.0235705 -0.0882599 -0.0153812 -0.0234844 -0.0890407 -0.0169239 -0.022049 -0.0887662 -0.0168956 -0.0223548 -0.0887927 -0.0172239 -0.022093 -0.0890504 -0.0170963 -0.0219222 -0.0887958 -0.0173812 -0.0219799 -0.0890536 -0.0194649 -0.0210114 -0.0887958 -0.0194899 -0.0212172 -0.0890536 -0.0237673 -0.0224967 -0.0887958 -0.0236207 -0.0226433 -0.0886242 -0.02667 -0.0256717 -0.0885259 -0.0269007 -0.0258438 -0.0887774 -0.0270634 -0.0257221 -0.0885157 -0.0269227 -0.0258586 -0.0883422 -0.0278102 -0.0261196 -0.0879706 -0.0279107 -0.0263152 -0.0884832 -0.0275838 -0.0260237 -0.0869818 -0.0303429 -0.0261749 -0.0870542 -0.0300943 -0.0262702 -0.0869738 -0.0316888 -0.0250511 -0.0869415 -0.0314841 -0.0253079 -0.0871881 -0.0304181 -0.0260426 -0.0796687 0.0399257 -0.00619997 -0.0797348 0.0399217 -0.0061451 -0.080069 0.039656 -0.0068755 -0.0801616 0.0395951 -0.00699173 -0.0810239 0.0390862 -0.0076903 -0.0805351 0.0392605 -0.00758543 -0.0816649 0.0385891 -0.00824336 -0.0832821 0.0379231 -0.00849366 -0.0839018 0.0373844 -0.00884537 -0.0857013 0.0367962 -0.00875064 -0.0881681 0.0357347 -0.00863964 -0.091346 0.0339045 -0.00846463 -0.0945122 0.0324781 -0.00808264 -0.0947939 0.0327461 -0.00783886 -0.0950346 0.0326163 -0.00780407 -0.0953751 0.0323961 -0.00774506 -0.0952438 0.0320501 -0.0079674 -0.0967958 0.0293217 -0.00577247 -0.0967958 0.0298565 -0.00660664 -0.096475 0.0305681 -0.00737249 -0.0963088 0.0308734 -0.00756019 -0.0965681 0.0311577 0.00733629 -0.0967958 0.029482 0.00611848 -0.0967515 0.0297571 0.00657912 -0.0967958 0.0307598 0.00709423 -0.09616 0.0311025 0.00767764 -0.095888 0.0319631 0.00763393 -0.0954885 0.0318538 0.00791941 -0.094639 0.0328196 0.00786343 -0.0945122 0.0324781 0.00808751 -0.0796397 0.0399074 0.00632138 -0.0806113 0.0393207 0.00741883 -0.0813173 0.038789 0.00808591 -0.0819891 0.0384065 0.00837766 -0.084114 0.0372756 0.00887977 -0.0855745 0.0365482 0.00899016 -0.0856522 0.0368182 0.00875428 -0.0880413 0.0353933 0.00886823 -0.0967748 0.0288311 0.00929553 -0.0966372 0.0296659 0.00897641 -0.0967958 0.0300221 0.00919323 -0.0967958 0.0301853 0.00923832 -0.096475 0.0301608 0.00889727 -0.0963805 0.0309391 0.00925319 -0.0945122 0.0321701 0.00923729 -0.0946562 0.0321017 0.00921907 -0.0953751 0.0319302 0.00948861 -0.0948799 0.031981 0.00918688 -0.0881681 0.0352688 0.0103832 -0.0857013 0.0362436 0.0108178 -0.0821159 0.0374391 0.0121654 -0.0815245 0.0375901 0.0125219 -0.0816649 0.0375426 0.0121536 -0.0810239 0.0376967 0.0128811 -0.0798988 0.0378217 0.013869 -0.080069 0.0377827 0.0138716 -0.0796397 0.0377209 0.0144815 -0.0797062 0.0375484 0.014923 -0.0963602 -0.0304093 0.00888616 -0.0967515 -0.02905 0.00918308 -0.0967958 -0.0285815 0.00944445 -0.0967958 -0.0294235 0.00915622 -0.096563 -0.0299099 0.0089263 -0.0960059 -0.0313662 0.00933998 -0.09616 -0.0307645 0.00890445 -0.0957828 -0.0312512 0.00899477 -0.0956894 -0.0316725 0.00942205 -0.0954885 -0.031536 0.0090707 -0.0881681 -0.0352595 0.0103832 -0.0797635 -0.0376719 0.0145159 -0.0802177 -0.0377795 0.0136673 -0.0808901 -0.037723 0.0127308 -0.0819891 -0.0374399 0.0119502 -0.0821243 -0.0374275 0.0121607 -0.084114 -0.0367116 0.0109499 -0.0850899 -0.0364604 0.0109785 -0.0880413 -0.0350757 0.0100188 -0.0796687 -0.0399164 0.00620485 -0.0796397 -0.0398981 0.00632138 -0.0797348 -0.0399124 0.00614998 -0.0798057 -0.0398417 0.00640262 -0.0798988 -0.0396792 0.00690217 -0.080069 -0.0396467 0.00688038 -0.0801616 -0.0395857 0.00699661 -0.0805351 -0.0392512 0.00759032 -0.0810239 -0.0390769 0.00769518 -0.0816649 -0.0385797 0.00824824 -0.0820448 -0.0383661 0.00839806 -0.0839018 -0.037375 0.00885025 -0.0832821 -0.0379137 0.00849854 -0.0841235 -0.0375109 0.00863755 -0.085626 -0.0365139 0.00899136 -0.0880413 -0.035384 0.00886823 -0.0881681 -0.0357254 0.00864452 -0.091346 -0.0338952 0.00846951 -0.0945122 -0.0324688 0.00808752 -0.094639 -0.0328103 0.00786343 -0.0947939 -0.0327368 0.00784374 -0.0953751 -0.0323867 0.00774994 -0.0951964 -0.0320752 0.00798156 -0.0967958 -0.0298471 0.00661152 -0.0966372 -0.0301697 0.00706138 -0.0967958 -0.0305866 0.0070517 -0.096475 -0.0305587 0.00737737 -0.0963088 -0.030864 0.00756507 -0.0963805 -0.0314108 0.00745829 -0.096563 -0.030364 -0.00722656 -0.0957828 -0.0315598 -0.00783788 -0.0956894 -0.0321384 -0.00767851 -0.0945122 -0.0324688 -0.00808263 -0.094639 -0.0328103 -0.00785855 -0.0881681 -0.0357254 -0.00863964 -0.0798579 -0.0397985 -0.00652334 -0.0799131 -0.0396686 -0.00691936 -0.0880413 -0.035384 -0.00886334 -0.0967958 -0.0291523 -0.00919982 -0.0966372 -0.0296566 -0.00897153 -0.0963088 -0.0305097 -0.00888248 -0.0957828 -0.0312512 -0.00898989 -0.094639 -0.0323444 -0.00959722 -0.0947939 -0.0322709 -0.00957752 -0.0950346 -0.0321411 -0.00954274 -0.0951964 -0.0317669 -0.0091274 -0.0945122 -0.0321607 -0.00923241 -0.0873665 -0.0355865 -0.0104839 -0.0849894 -0.0364968 -0.0110022 -0.0839018 -0.036791 -0.011025 -0.0825694 -0.037301 -0.0119232 -0.0820448 -0.0374232 -0.0119121 -0.0816649 -0.0375333 -0.0121487 -0.0811247 -0.0376679 -0.0127985 -0.0796397 -0.0377116 -0.0144766 -0.0796687 -0.0376692 -0.0145866 -0.0797062 -0.0375391 -0.0149181 -0.0967958 0.0285908 -0.00943957 -0.0967958 0.0294328 -0.00915134 -0.096563 0.0299192 -0.00892141 -0.0957828 0.0312605 -0.00898989 -0.0965681 0.0306509 -0.0092228 -0.095888 0.0314972 -0.00936772 -0.0956732 0.0313737 -0.00902006 -0.0956894 0.0316818 -0.00941717 -0.0953721 0.0319324 -0.00948431 -0.0951936 0.0317783 -0.00912794 -0.094639 0.0323537 -0.00959722 -0.0799131 0.0378236 -0.0138397 -0.0798579 0.0377381 -0.0142476 -0.0801076 0.0377856 -0.0138104 -0.0806113 0.0377616 -0.0132328 -0.0808901 0.0377323 -0.012726 -0.0821159 0.0374391 -0.0121605 -0.0819891 0.0374492 -0.0119453 -0.0825438 0.0373178 -0.0119359 -0.0832821 0.037091 -0.0115989 -0.0855745 0.0361462 -0.0104857 -0.0967958 0.0170561 -0.0368368 -0.0967958 0.0169485 -0.0367684 -0.0858657 0.0170295 -0.0368134 -0.0858657 0.0168983 -0.0367548 -0.0967958 0.0168222 -0.0367509 -0.0967958 0.016721 -0.036777 -0.0836834 0.0169404 -0.0367759 -0.0836827 0.0169968 -0.0368048 -0.0825743 0.0170313 -0.0368712 -0.0814596 0.0169927 -0.0369221 -0.0825739 0.0170673 -0.0369223 -0.0814601 0.0170437 -0.0370493 -0.0824647 0.0170877 -0.0369811 -0.0836687 0.0171088 -0.0369397 -0.0836822 0.0170449 -0.036844 -0.0858657 0.0169471 -0.0367679 -0.0858657 0.0168272 -0.0367506 -0.0836852 0.0168173 -0.0367562 -0.0858657 0.0167577 -0.0367631 -0.0814687 0.0168198 -0.0368032 -0.0814843 0.0166246 -0.0368206 -0.0809794 0.0165935 -0.0368346 -0.0804735 0.0167273 -0.0368145 -0.0804735 0.0170047 -0.0371136 -0.0814592 0.0170277 -0.0369885 -0.0804735 0.016928 -0.0369133 -0.0814612 0.0169496 -0.036873 -0.0804735 0.0168659 -0.0368606 -0.0814644 0.016889 -0.03683 -0.0814731 0.0167587 -0.0367944 -0.079252 0.0167943 -0.0368273 -0.079252 0.0169289 -0.0369144 -0.0804735 0.0169682 -0.0369702 -0.0804735 0.0169972 -0.0370472 -0.079252 0.0169682 -0.0369702 -0.0780931 0.0166038 -0.0370059 -0.0764889 0.0167755 -0.0378871 -0.0761909 0.0169807 -0.0384221 -0.0770293 0.0169414 -0.0376138 -0.0768591 0.0166387 -0.0375981 -0.0760642 0.0167889 -0.0383081 -0.0764864 0.016652 -0.0378842 -0.0780559 0.0166672 -0.0370016 -0.0775169 0.0170047 -0.037543 -0.0781059 0.0169749 -0.0371614 -0.0780872 0.0169345 -0.0371017 -0.0780716 0.0168778 -0.0370519 -0.0780609 0.0168098 -0.0370175 -0.079252 0.0168676 -0.0368617 -0.079252 0.0167273 -0.0368145 -0.079252 0.0166447 -0.0368196 -0.0770622 0.0169777 -0.037664 -0.0765291 0.0168973 -0.0379337 -0.0756958 0.0168021 -0.0387804 -0.0756829 0.016687 -0.0387714 -0.0761115 0.0169039 -0.0383507 -0.0770013 0.0168906 -0.037571 -0.0769807 0.016829 -0.0375395 -0.0769689 0.0167622 -0.0375216 -0.0780557 0.0167373 -0.0370011 -0.0769659 0.016696 -0.0375171 -0.0773154 0.0166244 -0.0373222 -0.0715851 0.0169818 -0.0461656 -0.0754477 0.0169168 -0.0393288 -0.0753901 0.0168195 -0.0392988 -0.0714295 0.0167047 -0.0460652 -0.0714487 0.0168195 -0.0460776 -0.0668995 0.0168195 -0.0524644 -0.0668816 0.0167047 -0.0524503 -0.0561225 0.0167047 -0.0638316 -0.0561376 0.0168195 -0.0638488 -0.0715033 0.0169168 -0.0461128 -0.0617813 0.0168195 -0.058405 -0.0618286 0.0169168 -0.0584497 -0.075534 0.0169818 -0.0393738 -0.0669507 0.0169168 -0.0525046 -0.0618993 0.0169818 -0.0585165 -0.0561805 0.0169168 -0.0638976 -0.0562448 0.0169818 -0.0639707 -0.0500546 0.0169168 -0.0688021 -0.0670273 0.0169818 -0.0525646 -0.0563206 0.0170047 -0.0640569 -0.0501794 0.0170047 -0.0689736 -0.0496491 0.0170048 -0.0693528 -0.0489464 0.0167052 -0.0694874 -0.0500163 0.0168195 -0.0687495 -0.0501118 0.0169818 -0.0688808 -0.048996 0.0169153 -0.0695576 -0.0490534 0.0169825 -0.069639 -0.0491162 0.0170051 -0.0697281 -0.0482691 0.0171949 -0.0718836 -0.0482882 0.0171985 -0.0714592 -0.0485495 0.0169854 -0.0701577 -0.0481982 0.0169652 -0.0708037 -0.0481207 0.0167707 -0.0708234 -0.048414 0.0168189 -0.0700803 -0.0486599 0.0167061 -0.069733 -0.0481407 0.0168712 -0.0708102 -0.0482853 0.0170328 -0.0708059 -0.0485392 0.0170195 -0.0703802 -0.0482095 0.0171351 -0.071505 -0.0484371 0.0172904 -0.0722363 -0.0481208 0.0168955 -0.0714207 -0.0481632 0.0170467 -0.0715535 -0.0481171 0.01694 -0.0711897 -0.048468 0.0169175 -0.07011 -0.0489583 0.0168145 -0.0695042 -0.0488997 0.0184018 -0.0728895 -0.0488462 0.0179617 -0.0723007 -0.0487559 0.0177866 -0.0721666 -0.0490287 0.019059 -0.07296 -0.0490786 0.0190746 -0.0728475 -0.0489573 0.0184788 -0.0726672 -0.0489045 0.0184484 -0.072775 -0.0484181 0.0173834 -0.0721665 -0.0487042 0.017905 -0.0724767 -0.0484405 0.017462 -0.0720817 -0.0487615 0.0179486 -0.0723761 -0.0485007 0.0175141 -0.071995 -0.0490683 0.0242548 -0.0730199 -0.0491206 0.0197072 -0.0729085 -0.0490695 0.0242548 -0.0731416 -0.0490715 0.0197073 -0.0730214 -0.049072 0.0197074 -0.0731445 -0.0489992 0.0252984 -0.0727355 -0.0491956 0.0242548 -0.0728288 -0.0491156 0.0242548 -0.0729078 -0.0489492 0.0253243 -0.0728442 -0.0489468 0.0253637 -0.07296 -0.0491135 0.0242548 -0.073245 -0.0486708 0.0261797 -0.0722457 -0.0489857 0.0254053 -0.0730545 -0.0481091 0.0268313 -0.0715914 -0.0486126 0.0262275 -0.0723423 -0.0480757 0.0269262 -0.0716611 -0.0485978 0.0263001 -0.0724396 -0.0481795 0.0267689 -0.0715131 -0.0475995 0.026976 -0.0706482 -0.0475672 0.0269949 -0.0706698 -0.047476 0.0271047 -0.070731 -0.0449893 0.0269949 -0.0668254 -0.0449377 0.0270425 -0.06686 -0.0449723 0.0269547 -0.0665199 -0.0451139 0.0269547 -0.0667419 -0.0450185 0.0269775 -0.0668058 -0.0447909 0.0270425 -0.0666298 -0.0447353 0.0271399 -0.0666635 -0.0448981 0.0271047 -0.0668866 -0.0448837 0.0271399 -0.0668962 -0.044019 0.0266245 -0.0649125 -0.0443529 0.0269317 -0.0657786 -0.0441807 0.0264891 -0.064972 -0.0442818 0.0264638 -0.0649675 -0.0447157 0.0272547 -0.0666753 -0.0442889 0.0270247 -0.0657753 -0.0448741 0.0269775 -0.0665794 -0.0444434 0.026866 -0.0657631 -0.0439705 0.0266687 -0.0647734 -0.0439961 0.0265668 -0.0648004 -0.0441337 0.0263775 -0.0646438 -0.0440864 0.0265455 -0.0649532 -0.0440626 0.0264724 -0.0648167 -0.0441597 0.0264076 -0.0648173 -0.0446575 0.0264425 -0.0607368 -0.0458672 0.0265399 -0.0591086 -0.045852 0.0266547 -0.0590916 -0.0448437 0.0263547 -0.0608384 -0.0447429 0.0263775 -0.0607834 -0.0441043 0.0263775 -0.0626609 -0.0446004 0.0265399 -0.0607057 -0.0439439 0.0265399 -0.0626356 -0.0439213 0.0266547 -0.062632 -0.0439517 0.0266547 -0.0646781 -0.0439741 0.0265399 -0.0646739 -0.0440381 0.0264425 -0.0646618 -0.0440081 0.0264425 -0.0626457 -0.0442177 0.0263547 -0.0626788 -0.0459753 0.0263775 -0.0592297 -0.0461474 0.0263779 -0.0591485 -0.0461556 0.0263822 -0.0591344 -0.0461833 0.0264915 -0.0589479 -0.0460829 0.0264136 -0.0590833 -0.0461278 0.0265528 -0.0589193 -0.046082 0.0266268 -0.0589106 -0.046031 0.0263897 -0.0591564 -0.0460222 0.026481 -0.0590318 -0.0459105 0.0264425 -0.0591571 -0.0459767 0.0265708 -0.0590044 -0.0460644 0.0267092 -0.0589106 -0.046142 0.0265656 -0.0589046 -0.046096 0.0266369 -0.0588985 -0.047771 0.0269239 -0.0578246 -0.047703 0.0269538 -0.0577504 -0.0481076 0.0271399 -0.0572097 -0.0470864 0.0270249 -0.0580807 -0.0471319 0.0269362 -0.0581068 -0.0482147 0.0269775 -0.0573317 -0.0462543 0.0264638 -0.0589704 -0.0471919 0.026869 -0.0581568 -0.046197 0.0265059 -0.0589299 -0.0470618 0.027119 -0.0580809 -0.0489735 0.0272547 -0.0564073 -0.0481505 0.0270425 -0.0572586 -0.0490978 0.0269775 -0.0565446 -0.0495029 0.0270004 -0.0560589 -0.0490325 0.0270425 -0.0564724 -0.0499599 0.026896 -0.0556514 -0.0499955 0.026859 -0.0557008 -0.0501233 0.0268377 -0.0558436 -0.0491748 0.0269547 -0.0566297 -0.0495753 0.0269368 -0.0561469 -0.0509081 0.0264404 -0.0549804 -0.0508655 0.0264518 -0.0549282 -0.0507991 0.02653 -0.0548047 -0.0499182 0.0271247 -0.0555373 -0.0489888 0.0271399 -0.0564242 -0.049918 0.0270042 -0.0555738 -0.0499334 0.0269459 -0.055608 -0.0504028 0.0267256 -0.0552513 -0.0504406 0.0266911 -0.0553076 -0.0500371 0.0268374 -0.0557518 -0.0504857 0.0266739 -0.0553633 -0.0505335 0.0266734 -0.0554136 -0.0510137 0.0264024 -0.0549534 -0.0509674 0.0264452 -0.0550382 -0.0510178 0.0264638 -0.0550773 -0.0507894 0.0265802 -0.0547593 -0.0510678 0.0263724 -0.0547356 -0.0509201 0.0264201 -0.0548481 -0.0509742 0.0264028 -0.054769 -0.0509656 0.026403 -0.0549034 -0.0510166 0.0263812 -0.0548193 -0.0511043 0.0263815 -0.0549096 -0.0509862 0.0266547 -0.0545174 -0.0508952 0.0265477 -0.0546427 -0.0510143 0.0265047 -0.0545462 -0.0508253 0.0264826 -0.054865 -0.0508819 0.0264546 -0.0547919 -0.0509379 0.0264398 -0.0547201 -0.0509109 0.0264896 -0.0546769 -0.0509932 0.026436 -0.0546494 -0.0511185 0.0263757 -0.0546532 -0.0510009 0.0265442 -0.0545325 -0.0511955 0.0263547 -0.0547323 -0.0560672 0.0263757 -0.0493537 -0.0510909 0.0263949 -0.0546248 -0.0510475 0.0264425 -0.0545803 -0.056037 0.0263949 -0.0493281 -0.0561514 0.0263547 -0.0494251 -0.0562265 0.0265022 -0.0490474 -0.0562018 0.0265207 -0.0490397 -0.056068 0.0267092 -0.0490592 -0.0560247 0.0265721 -0.0491362 -0.0561212 0.026607 -0.0490323 -0.0559533 0.0265047 -0.049257 -0.0560781 0.0264822 -0.0491535 -0.0559896 0.0264425 -0.0492879 -0.05615 0.0264154 -0.0491937 -0.0561091 0.0263897 -0.0492725 -0.0562265 0.0263812 -0.0492479 -0.0577096 0.0269547 -0.0475278 -0.0572648 0.026952 -0.0478742 -0.0573465 0.0269236 -0.0479357 -0.0569085 0.0268653 -0.0482816 -0.0569861 0.0268313 -0.0483346 -0.0562973 0.0264638 -0.0490802 -0.0568357 0.026932 -0.0482428 -0.0567816 0.0270219 -0.0482267 -0.0561588 0.026561 -0.0490316 -0.0575062 0.0271047 -0.0473661 -0.0574747 0.0272547 -0.0473411 -0.0602116 0.0269949 -0.0439371 -0.0575922 0.0269949 -0.0474344 -0.0575435 0.0270425 -0.0473958 -0.0601608 0.0270425 -0.0439013 -0.0576232 0.0269757 -0.0474591 -0.0607571 0.0268992 -0.043076 -0.0607053 0.0270045 -0.043008 -0.0601062 0.0271442 -0.0438628 -0.0608481 0.0268392 -0.0431567 -0.0605512 0.026938 -0.0435538 -0.0602439 0.0269757 -0.0439599 -0.0604643 0.0270022 -0.0434838 -0.0610384 0.0267316 -0.0426793 -0.0601218 0.0271047 -0.0438738 -0.0607251 0.026948 -0.043039 -0.0610823 0.0266969 -0.0427258 -0.0613953 0.0264532 -0.0423986 -0.0611339 0.0266775 -0.04277 -0.0614019 0.0264522 -0.0424037 -0.0615155 0.0264638 -0.0424711 -0.0612657 0.0267092 -0.0421325 -0.0613206 0.0266681 -0.0420497 -0.0614152 0.026439 -0.0420825 -0.0615033 0.0263747 -0.0421508 -0.0615377 0.0263757 -0.0420653 -0.0615423 0.0264159 -0.0423906 -0.0613831 0.0264316 -0.0422772 -0.061339 0.0264662 -0.0422309 -0.0613015 0.026499 -0.0423041 -0.0612549 0.0265911 -0.0422084 -0.0613972 0.0265442 -0.0419723 -0.0614529 0.0264425 -0.0420092 -0.0614689 0.0263866 -0.0422364 -0.0615998 0.0263614 -0.0422168 -0.0615705 0.0263819 -0.0423054 -0.0614349 0.0264122 -0.0423211 -0.0613771 0.0264466 -0.0421568 -0.0613447 0.0264954 -0.0421201 -0.0613247 0.0265518 -0.0420892 -0.0634384 0.0266547 -0.0386665 -0.0616298 0.0263547 -0.0421261 -0.0615047 0.0263949 -0.0420434 -0.063514 0.0264425 -0.0387112 -0.063473 0.0265047 -0.0386869 -0.0614131 0.0265047 -0.0419829 -0.0636016 0.0263757 -0.0387629 -0.0637155 0.0264983 -0.0384498 -0.0635394 0.0267092 -0.0384947 -0.0635949 0.0266034 -0.0384529 -0.063519 0.0265705 -0.038564 -0.0635788 0.0264792 -0.0385708 -0.0635675 0.0263949 -0.0387427 -0.0636319 0.0263883 -0.0386793 -0.0636612 0.026413 -0.0385986 -0.0637561 0.0269332 -0.0381229 -0.0641857 0.0268613 -0.0376916 -0.0642746 0.02683 -0.0377324 -0.0645264 0.0269232 -0.0373316 -0.0644338 0.0269501 -0.0372839 -0.06478 0.0269547 -0.0369216 -0.0637982 0.0264638 -0.038474 -0.0640139 0.0271162 -0.037674 -0.0645373 0.0271399 -0.0367876 -0.0636866 0.0265164 -0.0384455 -0.0636371 0.0265564 -0.0384447 -0.0641026 0.0269274 -0.0376651 -0.0640424 0.0270187 -0.0376595 -0.0645942 0.0270425 -0.0368191 -0.0646794 0.0269775 -0.0368661 -0.0666112 0.0269775 -0.0331269 -0.067123 0.0267369 -0.0318606 -0.0668744 0.0270052 -0.0321965 -0.067397 0.0264623 -0.0315698 -0.0672241 0.026681 -0.0319344 -0.067138 0.0268323 -0.0323733 -0.0670302 0.0268412 -0.0323203 -0.066732 0.027004 -0.032665 -0.0669324 0.0269022 -0.0322557 -0.0672987 0.0265105 -0.0314915 -0.066465 0.0271399 -0.0330564 -0.0665236 0.0270425 -0.0330846 -0.0668267 0.0269393 -0.0327197 -0.0673242 0.0264752 -0.0314192 -0.0673507 0.0264524 -0.0313442 -0.0673774 0.0264416 -0.0312682 -0.06752 0.0264638 -0.0316244 -0.067538 0.0264165 -0.0315446 -0.0675572 0.0263823 -0.0314594 -0.0674255 0.0264193 -0.0314924 -0.0673448 0.0265399 -0.0311659 -0.0674929 0.0263775 -0.0312324 -0.0675772 0.0263616 -0.0313704 -0.0674729 0.0263769 -0.0313211 -0.0674489 0.0263913 -0.0314077 -0.0672923 0.0265552 -0.0312856 -0.067245 0.0265988 -0.0314052 -0.0701516 0.0266547 -0.023878 -0.070235 0.0264425 -0.0239056 -0.0674041 0.0264425 -0.0311925 -0.0704298 0.0266751 -0.0234579 -0.0701812 0.0266688 -0.0237882 -0.0702063 0.0267058 -0.0237118 -0.0703428 0.0267105 -0.0234908 -0.0705218 0.0266547 -0.0234526 -0.0705058 0.0265282 -0.0235505 -0.0704112 0.0265555 -0.023546 -0.0703878 0.0264633 -0.0236597 -0.0704829 0.026426 -0.0236897 -0.0703606 0.0264021 -0.0237925 -0.0702309 0.0266077 -0.0236906 -0.0703222 0.026606 -0.0235667 -0.0701733 0.0265399 -0.0238852 -0.0702968 0.0265242 -0.0236645 -0.0702668 0.0264688 -0.0237793 -0.0703274 0.0263775 -0.0239362 -0.070552 0.0268154 -0.0233598 -0.0702754 0.0267563 -0.0235482 -0.0702667 0.0269654 -0.0235268 -0.0703728 0.0268712 -0.0233982 -0.0704708 0.0269704 -0.0233118 -0.070443 0.0271154 -0.0233053 -0.07046 0.0268358 -0.0233652 -0.0703887 0.0271154 -0.0233367 -0.0703055 0.026917 -0.0234556 -0.0703421 0.0271154 -0.0233787 -0.0703887 0.0280547 -0.0233367 -0.0702797 0.0271154 -0.0234868 -0.0703421 0.0280547 -0.0233787 -0.0703166 0.0281617 -0.0234192 -0.0703041 0.0282612 -0.0234602 -0.0703843 0.0281862 -0.0233538 -0.0703714 0.0283089 -0.0234037 -0.0704586 0.0283458 -0.0233716 -0.0705614 0.028217 -0.0233019 -0.070443 0.0280547 -0.0233053 -0.0705651 0.0280547 -0.0232794 -0.0704705 0.0282055 -0.0233134 -0.0707096 0.0339611 -0.0221755 -0.070776 0.0338808 -0.0221431 -0.0704179 0.0328061 -0.0232607 -0.0708675 0.0338221 -0.0221326 -0.0705059 0.0327652 -0.0232308 -0.0702033 0.0313716 -0.0239029 -0.0703507 0.0328594 -0.0233151 -0.0703802 0.0313457 -0.0238492 -0.0702894 0.0313554 -0.0238615 -0.0700956 0.031413 -0.0240468 -0.0700778 0.029757 -0.0241002 -0.07006 0.0305941 -0.0241535 -0.0701869 0.0286665 -0.023771 -0.0701857 0.0297866 -0.0239545 -0.0702717 0.0297982 -0.0239122 -0.0709653 0.0337937 -0.0221439 -0.0729065 0.0377526 -0.0143938 -0.0732882 0.0387235 -0.0116006 -0.0733947 0.0386998 -0.01161 -0.0720668 0.0367898 -0.0171065 -0.0730983 0.0389871 -0.0116503 -0.0726381 0.0379334 -0.0144108 -0.0735077 0.0396269 -0.00878195 -0.0737883 0.0401621 -0.00588763 -0.0740655 0.0399739 -0.00588149 -0.0739561 0.0399957 -0.00587619 -0.0742384 0.0402976 -0.00293612 -0.0742958 0.0404047 2.44063e-06 -0.0741282 0.0403189 -0.0029334 -0.0741853 0.0404257 4.3187e-05 -0.0741261 0.0403151 0.00299316 -0.0742958 0.0404046 4.32251e-05 -0.0742363 0.0402938 0.00299591 -0.0739535 0.0399909 0.00591361 -0.0736703 0.039455 0.00880508 -0.0737821 0.0403006 -0.00569569 -0.0739599 0.0404869 -0.00293912 -0.0740168 0.0405942 4.32665e-05 -0.0739365 0.0405929 0.0030063 -0.0737638 0.0402658 0.00593947 -0.0734805 0.0397251 0.00884324 -0.0730893 0.0389697 0.0117127 -0.0731138 0.0388665 0.0116854 -0.0720343 0.0368759 0.0171684 -0.0726298 0.037917 0.014459 -0.0720624 0.0367808 0.0171305 -0.0707105 0.0339596 0.0221797 -0.0721336 0.0367013 -0.0170806 -0.0727049 0.0378411 -0.0143886 -0.0731227 0.0388838 -0.0116231 -0.0735745 0.0395287 -0.0087679 -0.0740267 0.0403856 -0.00293432 -0.0740836 0.0404925 4.31997e-05 -0.0739578 0.040483 0.00299899 -0.0738526 0.0400572 0.00591553 -0.0737858 0.0401573 0.00592512 -0.0735035 0.0396188 0.00882219 -0.0731807 0.038771 0.011667 -0.0726966 0.0378248 0.0144367 -0.0721291 0.0366923 0.0171046 -0.0722287 0.0366392 -0.0170736 -0.0728019 0.0377775 -0.0143831 -0.0731896 0.0387882 -0.0116048 -0.0736745 0.039463 -0.00876491 -0.0738552 0.040062 -0.0058781 -0.0740246 0.0403817 0.00299411 -0.0735704 0.0395206 0.00880807 -0.0732793 0.0387062 0.0116628 -0.0727936 0.0377612 0.0144312 -0.0722243 0.0366303 0.0170976 -0.0735004 0.0389025 0.0109164 -0.0733858 0.0386825 0.0116722 -0.0723266 0.0366042 0.0171091 -0.0702655 0.0282108 0.0235353 -0.0703041 0.0282612 0.023465 -0.0703714 0.0283089 0.0234086 -0.0704586 0.0283458 0.0233765 -0.0703621 0.029809 0.0239047 -0.0700775 0.0297611 0.0241058 -0.0701189 0.0297763 0.0240259 -0.0701865 0.0297907 0.0239594 -0.0703805 0.0313493 0.0238533 -0.070272 0.0298021 0.0239176 -0.0704195 0.0328086 0.0232629 -0.0701369 0.0313955 0.0239717 -0.0702045 0.0313751 0.0239062 -0.0705072 0.032768 0.0232334 -0.0706 0.0327452 0.0232308 -0.0702903 0.0313591 0.0238654 -0.0703523 0.0328615 0.0233167 -0.070777 0.0338799 0.0221477 -0.0708681 0.0338218 0.0221375 -0.0703842 0.0281867 0.0233589 -0.0703887 0.0280547 0.0233416 -0.0704705 0.0282061 0.0233184 -0.0705614 0.0282177 0.0233069 -0.0702761 0.028136 0.0235029 -0.0703166 0.0281621 0.0234241 -0.0703421 0.0280547 0.0233836 -0.070443 0.0280547 0.0233102 -0.070443 0.0271154 0.0233102 -0.0704709 0.0269711 0.0233165 -0.0702797 0.0271154 0.0234917 -0.0702764 0.0270376 0.0235019 -0.0703421 0.0271154 0.0233836 -0.0703055 0.026917 0.0234605 -0.0703887 0.0271154 0.0233416 -0.0703728 0.0268712 0.023403 -0.070552 0.0268154 0.0233646 -0.0704298 0.0266751 0.0234628 -0.07046 0.0268358 0.02337 -0.0702667 0.0269654 0.0235317 -0.0703606 0.0264021 0.0237975 -0.0704723 0.0263962 0.0237593 -0.0703878 0.0264632 0.0236648 -0.0704617 0.026375 0.0238237 -0.0704894 0.026449 0.0236552 -0.0705058 0.0265282 0.0235554 -0.0703222 0.026606 0.0235716 -0.0702309 0.0266077 0.0236955 -0.0702967 0.0265242 0.0236695 -0.0702668 0.0264688 0.0237843 -0.070294 0.0263949 0.02393 -0.0702754 0.0267563 0.023553 -0.0703428 0.0267105 0.0234957 -0.0704112 0.0265555 0.023551 -0.0705218 0.0266547 0.0234575 -0.0673239 0.0266547 0.0311614 -0.0701516 0.0266547 0.0238829 -0.0701897 0.0265047 0.0238955 -0.070234 0.0264436 0.0239102 -0.0674041 0.0264425 0.0311974 -0.0703309 0.026376 0.0239422 -0.0674969 0.0263757 0.031239 -0.0673432 0.0265442 0.03117 -0.067307 0.026657 0.0311991 -0.0674608 0.0263949 0.0312228 -0.067473 0.0263769 0.0313254 -0.0674491 0.0263912 0.0314119 -0.0673776 0.0264416 0.0312726 -0.0675976 0.0263547 0.0312843 -0.0675773 0.0263615 0.0313748 -0.0675573 0.0263821 0.0314636 -0.0675381 0.0264162 0.031549 -0.0674257 0.0264191 0.0314968 -0.0673606 0.0265047 0.0311779 -0.0672925 0.0265551 0.03129 -0.0673509 0.0264522 0.0313485 -0.0673244 0.026475 0.0314236 -0.0671238 0.0267361 0.0318637 -0.0668762 0.0270039 0.0321975 -0.0672987 0.0265105 0.0314964 -0.067225 0.0266802 0.0319374 -0.0670319 0.0268399 0.0323215 -0.0668276 0.0269388 0.0327226 -0.0667329 0.0270035 0.032668 -0.0666112 0.0269775 0.0331318 -0.067397 0.0264623 0.0315747 -0.0673374 0.0266774 0.03199 -0.0669312 0.0269236 0.0327738 -0.0664444 0.0272547 0.0330513 -0.066465 0.0271399 0.0330612 -0.0665236 0.0270425 0.0330895 -0.067245 0.0265988 0.0314101 -0.066934 0.0269009 0.0322569 -0.0645173 0.0272547 0.0367815 -0.0645373 0.0271399 0.0367925 -0.0667146 0.0269547 0.0331816 -0.0635949 0.0266034 0.0384578 -0.0646794 0.0269775 0.036871 -0.0636866 0.0265164 0.0384504 -0.0645274 0.0269238 0.0373348 -0.0644349 0.0269506 0.037287 -0.0636371 0.0265564 0.0384496 -0.0641064 0.0269293 0.0376635 -0.0640178 0.0271183 0.037672 -0.0640462 0.0270207 0.0376577 -0.0645942 0.0270425 0.036824 -0.0641896 0.0268632 0.0376902 -0.0642785 0.026832 0.0377311 -0.0637495 0.026382 0.0386446 -0.0636615 0.0264135 0.0386026 -0.0636321 0.0263886 0.0386836 -0.0634909 0.0266682 0.0385822 -0.063458 0.0265399 0.038683 -0.0635792 0.0264797 0.0385749 -0.0637155 0.0264983 0.0384547 -0.0635194 0.0265709 0.0385683 -0.063514 0.0264425 0.0387161 -0.0635979 0.0263775 0.0387655 -0.0615036 0.0263747 0.0421548 -0.0614529 0.0264425 0.0420141 -0.0614156 0.026439 0.0420867 -0.0614352 0.0264119 0.0423252 -0.0614693 0.0263864 0.0422402 -0.0615341 0.0263775 0.0420677 -0.0613015 0.026499 0.042309 -0.0613252 0.0265516 0.0420933 -0.0612657 0.0267092 0.0421374 -0.0612549 0.0265911 0.0422133 -0.0613394 0.026466 0.0422351 -0.0613796 0.0266547 0.0419656 -0.0613986 0.0265399 0.0419782 -0.0613452 0.0264952 0.0421241 -0.0613776 0.0264464 0.0421607 -0.0613834 0.0264313 0.0422814 -0.0610404 0.0267305 0.0426813 -0.0607062 0.027119 0.0429669 -0.0606488 0.026924 0.0436237 -0.0609538 0.0268325 0.0432255 -0.0608529 0.0268371 0.0431551 -0.0613953 0.0264532 0.0424035 -0.0614019 0.0264522 0.0424086 -0.0610843 0.0266959 0.0427279 -0.061136 0.0266765 0.0427722 -0.0604666 0.0270013 0.0434855 -0.0602403 0.0269775 0.0439622 -0.0605535 0.0269371 0.0435556 -0.0603342 0.0269547 0.0440284 -0.060089 0.0272547 0.0438555 -0.0601077 0.0271399 0.0438687 -0.0607618 0.0268969 0.0430742 -0.0607101 0.0270023 0.043006 -0.0607298 0.0269458 0.0430371 -0.0574926 0.0271399 0.0473602 -0.0601608 0.0270425 0.0439061 -0.0575435 0.0270425 0.0474007 -0.0562265 0.0265022 0.0490523 -0.0576197 0.0269775 0.0474612 -0.0573485 0.0269242 0.0479385 -0.0572667 0.0269526 0.0478768 -0.0567586 0.0271193 0.0482334 -0.0567861 0.0270235 0.0482262 -0.0561212 0.026607 0.0490372 -0.0561588 0.026561 0.0490365 -0.0568401 0.0269335 0.0482424 -0.056913 0.0268668 0.0482814 -0.0562973 0.0264638 0.049085 -0.0562268 0.0263815 0.049252 -0.0561894 0.0263613 0.0493403 -0.0561094 0.0263899 0.0492768 -0.0559226 0.0266547 0.0492359 -0.0560251 0.0265723 0.0491406 -0.0561503 0.0264156 0.0491979 -0.056037 0.0263949 0.049333 -0.0562018 0.0265207 0.0490445 -0.0560784 0.0264824 0.0491578 -0.0559976 0.0266679 0.0491474 -0.056068 0.0267092 0.0490641 -0.0509862 0.0266547 0.0545223 -0.0559533 0.0265047 0.0492619 -0.0559896 0.0264425 0.0492928 -0.0510909 0.0263949 0.0546297 -0.0560672 0.0263757 0.0493586 -0.0511185 0.0263757 0.0546581 -0.0561514 0.0263547 0.04943 -0.0511955 0.0263547 0.0547372 -0.0509385 0.0264397 0.0547242 -0.0508955 0.0266678 0.0546105 -0.050966 0.0264028 0.0549076 -0.0509081 0.0264404 0.0549852 -0.0509674 0.0264452 0.055043 -0.0510141 0.0264022 0.0549576 -0.0510171 0.026381 0.0548233 -0.0511048 0.0263812 0.0549136 -0.0508253 0.0264826 0.0548699 -0.0508957 0.0265476 0.054647 -0.0510679 0.0263723 0.0547403 -0.0509934 0.026436 0.0546541 -0.0510475 0.0264425 0.0545852 -0.0510009 0.0265442 0.0545373 -0.0509115 0.0264895 0.0546811 -0.0510143 0.0265047 0.0545511 -0.0509748 0.0264027 0.054773 -0.0508824 0.0264544 0.0547962 -0.0509205 0.02642 0.0548523 -0.0507985 0.0265316 0.0548078 -0.0504058 0.026725 0.0552513 -0.0499375 0.0269462 0.0556073 -0.0491003 0.026976 0.0565522 -0.0491748 0.0269547 0.0566346 -0.0490005 0.0271047 0.056442 -0.0495757 0.0269367 0.0561505 -0.0500414 0.0268362 0.0557519 -0.0495029 0.0270012 0.056062 -0.0499638 0.0268957 0.0556509 -0.0499232 0.0271233 0.0555375 -0.0507894 0.0265802 0.0547642 -0.0499223 0.027005 0.0555732 -0.0499995 0.0268581 0.0557005 -0.050489 0.0266725 0.0553641 -0.0505371 0.0266719 0.0554149 -0.0510178 0.0264638 0.0550822 -0.0504436 0.02669 0.055308 -0.0508655 0.0264518 0.0549331 -0.0507991 0.02653 0.0548095 -0.0489735 0.0272547 0.0564122 -0.0489871 0.0271463 0.0564272 -0.0481191 0.0271047 0.0572276 -0.0481915 0.0269949 0.0573101 -0.0490742 0.0269949 0.0565234 -0.0490317 0.0270436 0.0564765 -0.0477053 0.0269541 0.0577534 -0.0482176 0.0269757 0.0573399 -0.046197 0.0265059 0.0589348 -0.046142 0.0265656 0.0589095 -0.0471969 0.0268701 0.0581577 -0.046096 0.0266369 0.0589034 -0.0460644 0.0267092 0.0589155 -0.0470668 0.0271203 0.0580815 -0.0470914 0.0270261 0.0580814 -0.0481505 0.0270425 0.0572634 -0.0471368 0.0269373 0.0581076 -0.0472606 0.0268338 0.0582218 -0.0460514 0.026702 0.0589262 -0.046082 0.0266268 0.0589155 -0.0460579 0.0267055 0.0589208 -0.0462412 0.0264494 0.0589967 -0.0462478 0.0264565 0.0589859 -0.0461833 0.0264915 0.0589527 -0.0460998 0.0263605 0.0592355 -0.0460312 0.0263899 0.059161 -0.0460518 0.0263547 0.0593203 -0.0460226 0.0264813 0.0590363 -0.0459519 0.0263949 0.0592084 -0.0460832 0.0264139 0.0590878 -0.0461477 0.0263782 0.0591529 -0.0461556 0.0263823 0.0591393 -0.0461278 0.0265528 0.0589242 -0.045977 0.026571 0.059009 -0.0459524 0.0266662 0.0590088 -0.044138 0.0263757 0.0646479 -0.0439517 0.0266547 0.064683 -0.0439529 0.0265047 0.0626964 -0.0439912 0.0265047 0.0646755 -0.0440615 0.0263949 0.0627125 -0.0443536 0.0263949 0.0615636 -0.044999 0.0263547 0.0605759 -0.0459782 0.0263757 0.0592379 -0.0442505 0.0265047 0.0615259 -0.0448714 0.0263949 0.0604971 -0.0459105 0.0264425 0.059162 -0.0439131 0.0266547 0.0626905 -0.044778 0.0265047 0.0604394 -0.0458788 0.0265047 0.0591264 -0.043996 0.0265667 0.064805 -0.0440864 0.0265455 0.0649581 -0.0442643 0.0263826 0.064808 -0.0440381 0.0264425 0.0646667 -0.0440625 0.0264722 0.0648212 -0.0440991 0.0263949 0.0646552 -0.0441596 0.0264075 0.0648217 -0.0449723 0.0269547 0.0665248 -0.044844 0.0269949 0.0666025 -0.044353 0.0269318 0.0657839 -0.044019 0.0266245 0.0649174 -0.0442615 0.0271248 0.065761 -0.0442891 0.0270249 0.0657806 -0.0441807 0.0264891 0.0649769 -0.0444436 0.0268661 0.0657684 -0.0445408 0.0268378 0.0657389 -0.0448779 0.0269757 0.066582 -0.0449893 0.0269949 0.0668303 -0.0447909 0.0270425 0.0666347 -0.0448981 0.0271047 0.0668915 -0.0447501 0.0271047 0.0666594 -0.0476918 0.0269547 0.0705912 -0.0475995 0.026976 0.070653 -0.0475672 0.0269949 0.0706747 -0.0474426 0.0272547 0.0707582 -0.0483898 0.0267261 0.0721707 -0.0480834 0.0270253 0.0717138 -0.0475147 0.0270436 0.0707099 -0.0480771 0.0269252 0.071668 -0.047476 0.0271047 0.0707359 -0.0481104 0.0268304 0.0715982 -0.0481807 0.0267679 0.0715198 -0.0485986 0.0262987 0.0724457 -0.0490811 0.025288 0.0726629 -0.0486716 0.0261783 0.0722518 -0.0486134 0.0262261 0.0723484 -0.0489473 0.0253613 0.0729657 -0.0489998 0.0252961 0.0727412 -0.0489497 0.025322 0.0728499 -0.049068 0.0242548 0.0730263 -0.0491956 0.0242548 0.0728336 -0.0491206 0.0197072 0.0729134 -0.0491151 0.0242548 0.0729132 -0.049072 0.0197074 0.0731494 -0.0490699 0.0242548 0.0731486 -0.0484181 0.0173834 0.0721714 -0.0484405 0.017462 0.0720866 -0.0485007 0.0175141 0.0719998 -0.0487052 0.0179078 0.072483 -0.048905 0.0184501 0.0727806 -0.0487625 0.0179514 0.0723825 -0.0489577 0.0184804 0.0726727 -0.0488472 0.0179644 0.0723071 -0.0490412 0.0184895 0.0725952 -0.0490792 0.0190777 0.0728534 -0.0489002 0.0184035 0.0728951 -0.0484231 0.0173346 0.0722113 -0.0490715 0.0197073 0.0730263 -0.0490293 0.0190621 0.0729658 -0.0492026 0.0197072 0.0728349 -0.048996 0.0169153 0.0695625 -0.0482884 0.0171989 0.071465 -0.0484239 0.0170431 0.0706641 -0.048549 0.0169854 0.0701634 -0.0481258 0.0168207 0.0708227 -0.0483433 0.0167157 0.070168 -0.0480993 0.0168089 0.0710633 -0.0481979 0.0169654 0.0708101 -0.0490534 0.0169825 0.0696439 -0.0487839 0.0170071 0.0700298 -0.0481404 0.0168715 0.0708167 -0.0481635 0.0170472 0.0715595 -0.0484675 0.0169175 0.0701157 -0.0484135 0.0168189 0.070086 -0.0481548 0.0169994 0.0715818 -0.0482097 0.0171355 0.0715109 -0.048285 0.017033 0.0708122 -0.0483637 0.0171868 0.071323 -0.0496491 0.0170048 0.0693576 -0.0501794 0.0170047 0.0689785 -0.0489583 0.0168145 0.0695091 -0.0702679 0.0167047 0.0478232 -0.075534 0.0169818 0.0393787 -0.0754477 0.0169168 0.0393337 -0.0715851 0.0169818 0.0461705 -0.0715033 0.0169168 0.0461177 -0.0670273 0.0169818 0.0525695 -0.0669507 0.0169168 0.0525094 -0.0714487 0.0168195 0.0460825 -0.0668995 0.0168195 0.0524693 -0.0617647 0.0167047 0.0583942 -0.0617813 0.0168195 0.0584099 -0.0618993 0.0169818 0.0585214 -0.0619827 0.0170047 0.0586003 -0.0562448 0.0169818 0.0639756 -0.0618286 0.0169168 0.0584546 -0.0561805 0.0169168 0.0639025 -0.0561376 0.0168195 0.0638537 -0.0501118 0.0169818 0.0688857 -0.0500546 0.0169168 0.068807 -0.0500163 0.0168195 0.0687544 -0.0561225 0.0167047 0.0638365 -0.0500029 0.0167047 0.0687359 -0.0786468 0.0168014 0.0368817 -0.0780609 0.0168098 0.0370224 -0.0786445 0.0167265 0.0368667 -0.0780557 0.0167373 0.0370059 -0.0770013 0.0168906 0.0375759 -0.0770293 0.0169414 0.0376187 -0.0781448 0.0170047 0.0372905 -0.0781059 0.0169749 0.0371663 -0.0770622 0.0169777 0.0376689 -0.0753698 0.0167047 0.0392931 -0.0759079 0.016676 0.038479 -0.0753743 0.0167592 0.0392954 -0.0775157 0.0168841 0.0372803 -0.0774915 0.0167494 0.0372296 -0.0774954 0.0166192 0.0372378 -0.0773837 0.0166224 0.037292 -0.0760567 0.0166694 0.0383063 -0.0753901 0.0168195 0.0393037 -0.0760642 0.0167889 0.038313 -0.0761115 0.0169039 0.0383556 -0.0756358 0.0170047 0.0394318 -0.0761909 0.0169807 0.0384269 -0.0762783 0.0170047 0.0385055 -0.0760559 0.0167276 0.0383055 -0.0769659 0.016696 0.037522 -0.0769689 0.0167622 0.0375265 -0.0760828 0.0168492 0.0383297 -0.0769807 0.016829 0.0375444 -0.0780872 0.0169345 0.0371065 -0.0780716 0.0168778 0.0370568 -0.0786523 0.0168723 0.0369165 -0.0780603 0.0166046 0.0370206 -0.079252 0.0170047 0.0371185 -0.079252 0.0169682 0.0369751 -0.079252 0.0169289 0.0369192 -0.0804735 0.0168676 0.0368666 -0.079252 0.0168676 0.0368666 -0.0804735 0.0167273 0.0368193 -0.079252 0.0167273 0.0368193 -0.079252 0.0165816 0.0368449 -0.0809655 0.0170155 0.0370901 -0.0814843 0.0166246 0.0368255 -0.0804735 0.0167174 0.0368187 -0.0809794 0.0165935 0.0368395 -0.0804735 0.0165816 0.0368449 -0.0804735 0.0169973 0.0370525 -0.0814596 0.0169927 0.036927 -0.0804735 0.0169727 0.0369838 -0.0804735 0.0169682 0.0369751 -0.0804735 0.0169289 0.0369192 -0.0814612 0.0169496 0.0368779 -0.0814731 0.0167587 0.0367993 -0.083674 0.0167082 0.0367876 -0.0836721 0.0168172 0.0367612 -0.0814643 0.0168906 0.0368357 -0.0825677 0.0170312 0.0368763 -0.0836702 0.0169403 0.0367809 -0.0858657 0.0169485 0.0367733 -0.0836695 0.0169967 0.0368099 -0.083669 0.0170448 0.0368491 -0.0858657 0.0170561 0.0368416 -0.0825672 0.0170671 0.0369275 -0.0836687 0.0171088 0.0369446 -0.0814592 0.0170277 0.0369933 -0.0967958 0.016721 0.0367818 -0.0967958 0.0170561 0.0368416 -0.0967958 0.0171165 0.036927 -0.0858657 0.0171165 0.036927 -0.0967958 0.0168222 0.0367558 -0.0858657 0.0168222 0.0367558 -0.0967958 0.0169485 0.0367733 -0.0772137 0.0030841 -0.0403602 -0.0737653 0.00315466 -0.0423048 -0.0743845 0.00318928 -0.041465 -0.0752015 0.00329111 -0.0408061 -0.0744321 0.00309012 -0.0415124 -0.0752478 0.00308779 -0.0408861 -0.0745035 0.00302517 -0.0415834 -0.0752245 0.00300466 -0.0411428 -0.0762229 0.00302416 -0.0405883 -0.0772137 0.00314083 -0.0403122 -0.0772137 0.00317682 -0.0402922 -0.0752139 0.00318448 -0.0408276 -0.0761727 0.0032851 -0.040402 -0.0761796 0.0031802 -0.0404275 -0.0761972 0.00308572 -0.040493 -0.0752979 0.00302464 -0.0409722 -0.0772137 0.00304089 -0.0404206 -0.0738066 0.00309253 -0.0423285 -0.0738605 0.00304485 -0.0423594 -0.0737487 0.00319423 -0.0422952 -0.0716363 0.00300466 -0.0462979 -0.0661064 0.00304485 -0.0536624 -0.059915 0.00300466 -0.0607081 -0.0564839 0.00300466 -0.063913 -0.0501582 0.00304485 -0.0688035 -0.0715103 0.00304485 -0.0462165 -0.0689589 0.00304485 -0.0499436 -0.0714181 0.00315466 -0.0461569 -0.0630535 0.00304485 -0.0572185 -0.0598097 0.00304485 -0.0606014 -0.0563846 0.00304485 -0.0638006 -0.0501216 0.00309253 -0.0687533 -0.0713844 0.00330466 -0.0461351 -0.06887 0.00315466 -0.0498792 -0.0688375 0.00330466 -0.0498556 -0.0660211 0.00315466 -0.0535932 -0.0629722 0.00315466 -0.0571448 -0.0629425 0.00330466 -0.0571177 -0.0597325 0.00315466 -0.0605232 -0.0563119 0.00315466 -0.0637183 -0.0562852 0.00330466 -0.0636882 -0.0491161 0.00300417 -0.0697279 -0.0490534 0.00302685 -0.0696389 -0.0496828 0.00300452 -0.0693284 -0.048996 0.00309401 -0.0695575 -0.0500935 0.00315466 -0.0687148 -0.0489583 0.00319485 -0.0695042 -0.0489464 0.00330412 -0.0694874 -0.0482883 0.00281033 -0.0714602 -0.0487839 0.00300217 -0.0700247 -0.048285 0.00297619 -0.0708073 -0.0481404 0.00313774 -0.0708118 -0.0480993 0.00320021 -0.0710585 -0.0483433 0.00329347 -0.0701632 -0.0484675 0.00309173 -0.0701108 -0.048549 0.00302389 -0.0701584 -0.048266 0.00291445 -0.0719245 -0.0481548 0.00300979 -0.0715769 -0.0481258 0.00318844 -0.0708178 -0.0481635 0.00296204 -0.0715546 -0.0484135 0.00319034 -0.0700812 -0.0481979 0.00304382 -0.0708052 -0.0482097 0.00287368 -0.0715061 -0.0483636 0.00282237 -0.0713182 -0.0484238 0.00296607 -0.0706591 -0.049116 0.000304482 -0.0732489 -0.0489369 0.00165592 -0.0729818 -0.0484404 0.00254723 -0.0720817 -0.0487048 0.00210182 -0.0724778 -0.0487621 0.00205829 -0.0723773 -0.0489045 0.00156025 -0.0727752 -0.0485006 0.00249505 -0.071995 -0.0490405 0.00152079 -0.0725899 -0.0491613 0.000928714 -0.0727693 -0.0490787 0.000933338 -0.0728481 -0.0489572 0.00152986 -0.0726674 -0.0490289 0.00094893 -0.0729605 -0.0484181 0.00262583 -0.0721665 -0.0484231 0.0026746 -0.0722065 -0.0488998 0.00160687 -0.0728896 -0.0490718 0.000304489 -0.0731444 -0.0490714 0.000304495 -0.0730214 -0.0491203 0.000304499 -0.0729085 -0.0492022 0.0003045 -0.07283 -0.0491204 -0.00834778 -0.0729086 -0.0492032 -0.00328505 -0.0728301 -0.0483913 -0.0108181 -0.072168 -0.0480793 -0.0110158 -0.0716661 -0.0476942 -0.0110453 -0.0705899 -0.0476019 -0.0110667 -0.0706518 -0.0475696 -0.0110855 -0.0706734 -0.0475171 -0.0111343 -0.0707086 -0.0486754 -0.0102691 -0.072248 -0.0481839 -0.0108584 -0.0715172 -0.048113 -0.0109207 -0.071596 -0.0486006 -0.0103898 -0.0724434 -0.0487604 -0.0102548 -0.0721737 -0.0489525 -0.00941379 -0.0728463 -0.048616 -0.0103168 -0.0723452 -0.0486265 -0.0104669 -0.0725188 -0.0490714 -0.00834784 -0.0730214 -0.0490041 -0.00938798 -0.0727368 -0.0490719 -0.00834793 -0.0731445 -0.0489494 -0.00945341 -0.0729633 -0.0458936 -0.0111344 -0.0682878 -0.045855 -0.0111953 -0.0683137 -0.0474784 -0.0111953 -0.0707346 -0.0458384 -0.0112372 -0.0683248 -0.0459462 -0.0110855 -0.0682525 -0.0459785 -0.0110667 -0.0682309 -0.0460708 -0.0110453 -0.068169 -0.0448647 -0.0109842 -0.066909 -0.0454109 -0.0110613 -0.0675927 -0.0454911 -0.0109936 -0.0675562 -0.0455773 -0.0109625 -0.0675066 -0.0451139 -0.0107203 -0.0668846 -0.0444356 -0.00928118 -0.0656364 -0.0445256 -0.0104735 -0.0663073 -0.0448984 -0.0108989 -0.0669324 -0.0449572 -0.0108183 -0.0669366 -0.0450334 -0.010756 -0.0669193 -0.0442899 -0.00987343 -0.065791 -0.0444871 -0.0105433 -0.0662619 -0.0443563 -0.00982587 -0.0658423 -0.0445893 -0.0104073 -0.0663369 -0.0446701 -0.0103551 -0.0663448 -0.0444407 -0.0097884 -0.0658703 -0.0447168 -0.0102562 -0.0662614 -0.0447551 -0.0103235 -0.0663313 -0.0442496 -0.00992352 -0.0657255 -0.0440897 -0.00834534 -0.0652533 -0.0441267 -0.00916912 -0.0653747 -0.0441508 -0.00834534 -0.0653653 -0.0441669 -0.00914279 -0.0654541 -0.044253 -0.00834534 -0.0654418 -0.0442346 -0.00911783 -0.0655202 -0.0443213 -0.00909832 -0.0655611 -0.0444127 -0.00908674 -0.0655727 -0.0441978 -0.00834534 -0.0654091 -0.0443776 -0.00834534 -0.065469 -0.0441258 -0.00770199 -0.0653243 -0.0441508 -0.00780515 -0.0653653 -0.0441978 -0.00780515 -0.0654091 -0.0441938 -0.00767819 -0.0653929 -0.0442817 -0.00765976 -0.0654358 -0.044253 -0.00780515 -0.0654418 -0.0440865 -0.00772705 -0.0652424 -0.0441149 -0.00760609 -0.0652853 -0.0441826 -0.00755979 -0.0653462 -0.0442717 -0.00752456 -0.0653818 -0.0443746 -0.00764912 -0.0654483 -0.0439537 -0.00679534 -0.0646884 -0.0439868 -0.00674453 -0.0647701 -0.0439361 -0.00669678 -0.0645911 -0.0439952 -0.00643321 -0.0644025 -0.0440958 -0.0063664 -0.0643882 -0.0440567 -0.00638553 -0.0643937 -0.0440115 -0.00645521 -0.0645368 -0.0439082 -0.00664534 -0.0644149 -0.043923 -0.00666029 -0.0645125 -0.0441102 -0.00638996 -0.0645388 -0.0441246 -0.00645055 -0.0646759 -0.044055 -0.00669694 -0.0648396 -0.0439605 -0.0065946 -0.0646208 -0.043948 -0.00649534 -0.0644093 -0.0440279 -0.00650975 -0.0646584 -0.0440428 -0.00659182 -0.0647612 -0.0441378 -0.00654291 -0.0647926 -0.0441486 -0.00666219 -0.064882 -0.0442099 -0.00634534 -0.0627297 -0.0444945 -0.00634534 -0.0616102 -0.0440615 -0.00638553 -0.0627076 -0.0443536 -0.00638553 -0.0615587 -0.044999 -0.00634534 -0.0605711 -0.045741 -0.00638553 -0.0594014 -0.0448714 -0.00638553 -0.0604922 -0.0456966 -0.00643428 -0.0593564 -0.044778 -0.00649534 -0.0604345 -0.0439131 -0.00664534 -0.0626856 -0.0439529 -0.00649534 -0.0626915 -0.0442505 -0.00649534 -0.061521 -0.0447438 -0.00664534 -0.0604134 -0.0456639 -0.00649534 -0.0593232 -0.0459719 -0.00650017 -0.0591191 -0.0457959 -0.0065843 -0.0591609 -0.0457673 -0.00667021 -0.0591687 -0.046032 -0.00658833 -0.0590348 -0.0458382 -0.00639013 -0.0593181 -0.0457683 -0.00636667 -0.0594291 -0.0458463 -0.00634534 -0.0595082 -0.0457718 -0.00645869 -0.0592629 -0.0459718 -0.00639549 -0.0592681 -0.0459063 -0.00643465 -0.0592146 -0.0458443 -0.00650041 -0.0591764 -0.0459773 -0.0066363 -0.0590273 -0.0459282 -0.00669229 -0.0590353 -0.0462412 -0.00667485 -0.0589406 -0.0462138 -0.00669318 -0.0589255 -0.0461637 -0.0066145 -0.0589986 -0.0461334 -0.00676612 -0.0589006 -0.050631 -0.0069679 -0.0554511 -0.0478243 -0.00770696 -0.0574268 -0.0505803 -0.0069488 -0.0554116 -0.0510584 -0.00651568 -0.0549248 -0.0509739 -0.00652287 -0.0548297 -0.0505274 -0.00694302 -0.0553603 -0.0504778 -0.00695488 -0.0552998 -0.0473791 -0.00735379 -0.0579326 -0.0487348 -0.00747778 -0.0569542 -0.04741 -0.00732361 -0.0579568 -0.0486611 -0.00752177 -0.0568712 -0.0486031 -0.00760978 -0.0568053 -0.0498274 -0.00740737 -0.0556598 -0.0504377 -0.00698601 -0.0552355 -0.0509233 -0.00657068 -0.0547229 -0.0498667 -0.00729752 -0.0557494 -0.0492597 -0.00748611 -0.0562867 -0.0499037 -0.0072617 -0.0558044 -0.0499477 -0.00724296 -0.0558596 -0.049294 -0.00744759 -0.0563324 -0.0499943 -0.00724076 -0.0559104 -0.0493336 -0.00742339 -0.0563808 -0.0493752 -0.00741372 -0.0564284 -0.0494156 -0.00741685 -0.056472 -0.0474554 -0.00727936 -0.0580285 -0.0474416 -0.0073005 -0.0579848 -0.0461861 -0.00671485 -0.0589135 -0.0460863 -0.00682628 -0.0589037 -0.0473505 -0.0073902 -0.0579134 -0.0486972 -0.00749375 -0.056912 -0.048629 -0.00756119 -0.0568348 -0.0498407 -0.00734782 -0.0556997 -0.0509156 -0.00665049 -0.0546238 -0.0510689 -0.00649097 -0.054528 -0.0510551 -0.00655026 -0.0544883 -0.0510956 -0.00644082 -0.054577 -0.0511627 -0.00643903 -0.0548505 -0.0512256 -0.00638345 -0.0547349 -0.0511333 -0.00640496 -0.0546311 -0.0513125 -0.00636818 -0.0544575 -0.0512058 -0.00638927 -0.054525 -0.0511703 -0.00642784 -0.0544808 -0.0511263 -0.00653564 -0.0544138 -0.0512138 -0.00645787 -0.0548894 -0.0511037 -0.00652636 -0.0549592 -0.0511094 -0.00643347 -0.0547998 -0.0510431 -0.00651394 -0.054911 -0.0510595 -0.00644546 -0.0547399 -0.0509427 -0.0065429 -0.0547747 -0.051019 -0.00647659 -0.054676 -0.0512897 -0.00635476 -0.0546177 -0.0512468 -0.00636483 -0.0545718 -0.0511782 -0.00638601 -0.0546852 -0.0511828 -0.00664534 -0.0543253 -0.0557278 -0.00653053 -0.0494949 -0.0557772 -0.00643321 -0.0495372 -0.0511988 -0.00653053 -0.0543416 -0.0512443 -0.00643321 -0.054388 -0.0558511 -0.00636818 -0.0496005 -0.0513151 -0.00636667 -0.0544602 -0.056094 -0.0066738 -0.049149 -0.0559807 -0.00660094 -0.0492319 -0.0559882 -0.00645624 -0.0493478 -0.0559195 -0.00651885 -0.0493232 -0.0559234 -0.00639583 -0.0494711 -0.0559743 -0.00675223 -0.0491834 -0.0558652 -0.0065982 -0.0493201 -0.055971 -0.00635022 -0.0495988 -0.0560008 -0.00636341 -0.0495291 -0.0561151 -0.00651147 -0.0492607 -0.0560466 -0.00654852 -0.0492378 -0.0561597 -0.00664534 -0.0491555 -0.0558447 -0.0066903 -0.0493227 -0.0558509 -0.00646318 -0.0494261 -0.0560302 -0.00671043 -0.0491584 -0.0567589 -0.0080532 -0.048353 -0.0559309 -0.00679534 -0.0492213 -0.0566946 -0.0080896 -0.048363 -0.0567846 -0.00818242 -0.0483037 -0.0567311 -0.00834534 -0.0483074 -0.0567311 -0.00832476 -0.0483074 -0.0576019 -0.0103988 -0.0473503 -0.0584128 -0.0108744 -0.0465242 -0.0589855 -0.0112305 -0.0454134 -0.0590377 -0.0111332 -0.0454522 -0.0587247 -0.0110319 -0.0460009 -0.0574746 -0.0106258 -0.0473413 -0.0582047 -0.0110625 -0.0464341 -0.0589672 -0.0113453 -0.0453997 -0.0567943 -0.00834534 -0.0482858 -0.057094 -0.00949676 -0.0480209 -0.0580289 -0.01066 -0.0469687 -0.0579543 -0.0106976 -0.0469329 -0.05786 -0.0105324 -0.047162 -0.0575817 -0.010265 -0.0474773 -0.0569061 -0.00958808 -0.0480613 -0.0568085 -0.00947578 -0.0481676 -0.0570275 -0.00952127 -0.0480186 -0.0569629 -0.00955254 -0.0480322 -0.0574264 -0.0105724 -0.0474019 -0.057477 -0.0105179 -0.047357 -0.0575335 -0.0104527 -0.0473439 -0.0586472 -0.0110995 -0.0459544 -0.0582603 -0.0109751 -0.0464442 -0.0583343 -0.0109093 -0.0464767 -0.0584323 -0.0108828 -0.0465014 -0.0659805 -0.0113453 -0.0339918 -0.0627448 -0.0112305 -0.0398623 -0.066001 -0.0112305 -0.034002 -0.0628002 -0.0111332 -0.0398963 -0.0662489 -0.0110453 -0.0341258 -0.0591158 -0.0110682 -0.0455102 -0.0628831 -0.0110682 -0.0399473 -0.0629809 -0.0110453 -0.0400074 -0.0667527 -0.010775 -0.03246 -0.0673079 -0.00943948 -0.0315111 -0.0674393 -0.00889658 -0.0314051 -0.0673869 -0.00890447 -0.0313441 -0.0673595 -0.00942402 -0.0315697 -0.0675036 -0.00889336 -0.0314493 -0.0674225 -0.00941729 -0.0316135 -0.0676664 -0.00834534 -0.0314258 -0.0676379 -0.00889885 -0.0314831 -0.0675728 -0.00933515 -0.0316138 -0.0674193 -0.00990046 -0.031919 -0.0670118 -0.0103408 -0.032128 -0.0669772 -0.0103805 -0.0320743 -0.0668071 -0.0106776 -0.0325472 -0.0665757 -0.0109239 -0.0330137 -0.0672592 -0.00949028 -0.0313729 -0.0667309 -0.0108555 -0.0331149 -0.0667852 -0.0108588 -0.0331396 -0.0666568 -0.0109401 -0.0333795 -0.0672736 -0.00946247 -0.031443 -0.0672313 -0.00990147 -0.0318322 -0.0661462 -0.0110682 -0.0340745 -0.0661012 -0.0110949 -0.034052 -0.0666218 -0.0108873 -0.0330501 -0.0660591 -0.0111332 -0.034031 -0.0665194 -0.0110271 -0.0329462 -0.0667173 -0.0109298 -0.0324743 -0.0671727 -0.00998736 -0.0314913 -0.0669595 -0.0104275 -0.0320215 -0.0671808 -0.00992384 -0.0317775 -0.067061 -0.0103124 -0.0321776 -0.0672923 -0.00989078 -0.0318751 -0.0671195 -0.0102976 -0.0322187 -0.066675 -0.0108644 -0.0330846 -0.0671814 -0.0102958 -0.032249 -0.0661998 -0.0110504 -0.0341012 -0.0673924 -0.00832476 -0.0310035 -0.0673673 -0.00834534 -0.0311491 -0.0673673 -0.00832476 -0.0311491 -0.0673796 -0.00834534 -0.0312137 -0.0674147 -0.00834534 -0.0312891 -0.0674147 -0.00832476 -0.0312891 -0.0675232 -0.00834534 -0.0313894 -0.0675232 -0.00832476 -0.0313894 -0.0674435 -0.00804296 -0.0312066 -0.0674692 -0.00824368 -0.0313443 -0.0674746 -0.00816553 -0.0313271 -0.0676767 -0.00809429 -0.0313797 -0.0675459 -0.0080855 -0.0313426 -0.0675383 -0.00816148 -0.0313705 -0.067671 -0.00816825 -0.0314049 -0.0675335 -0.00824172 -0.031388 -0.0673736 -0.00820853 -0.031123 -0.0674167 -0.00824865 -0.0312835 -0.0673927 -0.00810463 -0.0310772 -0.067397 -0.00824669 -0.0309932 -0.0674087 -0.0080709 -0.0311427 -0.0673878 -0.00819031 -0.0311967 -0.0674314 -0.00810639 -0.0312413 -0.0674223 -0.00817539 -0.0312673 -0.0677419 -0.00672573 -0.0302837 -0.0675562 -0.00801517 -0.0313049 -0.0678433 -0.00664565 -0.0304662 -0.0679059 -0.00663643 -0.0305092 -0.0679705 -0.00663705 -0.0305361 -0.0680337 -0.00664534 -0.030549 -0.0677977 -0.00669696 -0.0300787 -0.0680593 -0.0063649 -0.0301586 -0.0680431 -0.00636669 -0.0299857 -0.0678695 -0.00664534 -0.0299114 -0.0678075 -0.00657806 -0.0301191 -0.0678637 -0.00647954 -0.030199 -0.0678246 -0.00655459 -0.0303147 -0.0679669 -0.00642479 -0.0302743 -0.068055 -0.00651789 -0.0304502 -0.0680045 -0.00637675 -0.0301319 -0.0679521 -0.00640196 -0.0301028 -0.0678336 -0.00665757 -0.0299953 -0.0677713 -0.00663931 -0.0302083 -0.0678741 -0.00652673 -0.0303634 -0.0677933 -0.00666445 -0.0304121 -0.0679329 -0.00651187 -0.0304034 -0.0679949 -0.00650966 -0.0304324 -0.0680253 -0.00641802 -0.0303033 -0.0679114 -0.00644531 -0.0302388 -0.0679062 -0.0064401 -0.0300731 -0.0678473 -0.00654425 -0.0300206 -0.0679064 -0.00649534 -0.0299272 -0.0687159 -0.00664534 -0.0278485 -0.067888 -0.00653711 -0.0299194 -0.06981 -0.00643428 -0.0251518 -0.0679492 -0.00643437 -0.0299455 -0.0699064 -0.00636667 -0.0251855 -0.0698697 -0.00638553 -0.0251727 -0.0680074 -0.00638553 -0.0299704 -0.0699664 -0.00645423 -0.0249089 -0.0698446 -0.00645976 -0.0250265 -0.0699377 -0.00639297 -0.0250413 -0.070049 -0.00638623 -0.0250061 -0.070038 -0.00636561 -0.0250691 -0.0700113 -0.00634534 -0.0252222 -0.0697281 -0.00664534 -0.0251231 -0.069766 -0.00649534 -0.0251364 -0.0700674 -0.00643973 -0.0249002 -0.0698761 -0.0065153 -0.0249121 -0.0698105 -0.00659855 -0.0249368 -0.069903 -0.00659713 -0.0248146 -0.0700107 -0.00666621 -0.0247073 -0.0699911 -0.00654648 -0.0247953 -0.0700846 -0.00651865 -0.0248008 -0.0702805 -0.00804535 -0.0239113 -0.0699246 -0.0067017 -0.024739 -0.0698575 -0.00674726 -0.0247947 -0.0701265 -0.00812649 -0.0240005 -0.0703821 -0.00816932 -0.0238463 -0.0701008 -0.00832476 -0.024031 -0.0700974 -0.00824688 -0.0240413 -0.07021 -0.00832476 -0.0238825 -0.0701938 -0.00808079 -0.0239438 -0.0702917 -0.00818049 -0.0238579 -0.0703721 -0.00802476 -0.0239062 -0.0703855 -0.0122453 -0.0238258 -0.0703855 -0.00832476 -0.0238258 -0.0702641 -0.0122453 -0.0238514 -0.0702641 -0.00832476 -0.0238514 -0.070209 -0.0122453 -0.0238832 -0.0701635 -0.0122453 -0.023924 -0.0701008 -0.0122453 -0.024031 -0.0701635 -0.00832476 -0.023924 -0.0702022 -0.0128083 -0.0242825 -0.0701796 -0.012824 -0.0243903 -0.0702859 -0.0124641 -0.023883 -0.0702608 -0.0126481 -0.0240025 -0.0701316 -0.0127083 -0.0241749 -0.0702435 -0.012719 -0.0240854 -0.0700614 -0.0124842 -0.0241492 -0.0702949 -0.0122453 -0.0238398 -0.0703847 -0.012318 -0.0238303 -0.0701992 -0.0124359 -0.0239201 -0.0703683 -0.0125813 -0.023929 -0.0703561 -0.0126698 -0.0240017 -0.0702237 -0.0127728 -0.0241798 -0.0701721 -0.0125972 -0.0240223 -0.0701055 -0.0125299 -0.0240655 -0.0700664 -0.0126178 -0.0241895 -0.0701079 -0.0127409 -0.0242638 -0.0645116 -0.0140329 -0.0367869 -0.0645481 -0.0156619 -0.0370387 -0.0644917 -0.0160004 -0.0370131 -0.0644766 -0.0152801 -0.0370385 -0.0656692 -0.0129759 -0.0351708 -0.0647281 -0.0139466 -0.036552 -0.0652672 -0.0130429 -0.0355253 -0.0646273 -0.0138733 -0.036601 -0.0650776 -0.0129723 -0.0357429 -0.064586 -0.0138215 -0.036652 -0.0644777 -0.0167456 -0.0368712 -0.0657377 -0.0129102 -0.0349501 -0.0657839 -0.01292 -0.0349716 -0.0653947 -0.0131266 -0.0355501 -0.0653547 -0.0131085 -0.0355382 -0.0647679 -0.0139659 -0.0365463 -0.0645736 -0.0145828 -0.0368756 -0.0645411 -0.0167099 -0.0368275 -0.0644189 -0.0152748 -0.0370602 -0.0646588 -0.0145736 -0.0368603 -0.0648178 -0.0139669 -0.036535 -0.0659515 -0.0127575 -0.0342459 -0.0658934 -0.0126601 -0.0342166 -0.065873 -0.0125453 -0.0342064 -0.0652052 -0.012959 -0.0355353 -0.0643746 -0.0165161 -0.0370339 -0.0643531 -0.0160268 -0.0370929 -0.0642925 -0.0152588 -0.0371809 -0.0643381 -0.0152648 -0.0371196 -0.0646906 -0.0139242 -0.0365633 -0.065307 -0.0130779 -0.0355286 -0.0693215 -0.0303664 -0.0266626 -0.0675264 -0.0264054 -0.0307362 -0.0704329 -0.0326346 -0.0238061 -0.0646561 -0.0166684 0.0368045 -0.0644777 -0.0167456 0.0368761 -0.0646955 -0.016659 0.0368057 -0.0722383 -0.036649 0.0170374 -0.0709762 -0.0338075 0.0221135 -0.0704329 -0.0326346 0.023811 -0.0680254 -0.0269566 0.0300898 -0.0732891 -0.0387159 0.0115996 -0.0733957 -0.0386922 0.011609 -0.0724706 -0.0368825 0.0164796 -0.0723406 -0.0366229 0.0170488 -0.073823 -0.0395074 0.00842606 -0.0736771 -0.0394587 0.0087465 -0.0691395 -0.0305785 0.0267514 -0.0706892 -0.0340586 0.0221902 -0.072617 -0.0380336 0.0144228 -0.0730992 -0.0389796 0.0116492 -0.0734873 -0.0397289 0.00878441 -0.0737702 -0.0402686 0.00585792 -0.0737921 -0.04016 0.00584376 -0.0739598 -0.0399935 0.00583241 -0.0741853 -0.0404164 -4.1059e-05 -0.0742358 -0.0402834 -0.00300324 -0.0741256 -0.0403046 -0.00300045 -0.0739497 -0.0399743 -0.00595738 -0.0737822 -0.0402913 0.00570039 -0.07394 -0.0405902 0.00291591 -0.0740168 -0.0405849 -4.11439e-05 -0.0739573 -0.0404726 -0.00300631 -0.07376 -0.0402492 -0.00598345 -0.073113 -0.0388556 -0.0116858 -0.0726066 -0.0380131 -0.0144715 -0.0659285 -0.0218272 0.0341286 -0.0675318 -0.0264197 0.0307289 -0.0691755 -0.0305046 0.0267 -0.0707213 -0.0339734 0.0221443 -0.0707878 -0.0338937 0.0221124 -0.0720763 -0.0367997 0.0170701 -0.0721431 -0.0367111 0.0170443 -0.0727099 -0.0378418 0.0143678 -0.0726431 -0.0379341 0.01439 -0.0731237 -0.0388763 0.011622 -0.0735772 -0.0395244 0.00874947 -0.0735104 -0.0396226 0.00876349 -0.0739613 -0.0404803 0.00290881 -0.0740281 -0.040379 0.00290408 -0.0740241 -0.0403713 -0.0030014 -0.073782 -0.0401407 -0.00596899 -0.0738488 -0.0400406 -0.00595932 -0.0734982 -0.0395993 -0.00886337 -0.0659927 -0.0217798 0.0340864 -0.0675969 -0.0263609 0.0306891 -0.0660716 -0.0217411 0.0340654 -0.0676796 -0.0263145 0.0306715 -0.0692414 -0.0304349 0.0266635 -0.0693282 -0.030382 0.0266497 -0.0708789 -0.0338356 0.0221022 -0.072807 -0.0377782 0.0143623 -0.0731905 -0.0387807 0.0116037 -0.0738589 -0.0400598 0.0058343 -0.0741296 -0.0403123 0.00290316 -0.0740836 -0.0404832 -4.10726e-05 -0.073565 -0.0395012 -0.0088492 -0.0731799 -0.0387601 -0.0116674 -0.0726996 -0.0378214 -0.0144163 -0.0724706 -0.0368825 -0.0164749 -0.0727966 -0.0377578 -0.0144108 -0.0732784 -0.0386953 -0.0116632 -0.0733849 -0.0386716 -0.0116726 -0.0736649 -0.0394356 -0.00884617 -0.0740591 -0.0399525 -0.00596275 -0.0723273 -0.0365963 -0.017101 -0.0720631 -0.036773 -0.0171224 -0.0726328 -0.0379137 -0.0144386 -0.0709651 -0.0337838 -0.0221447 -0.0708678 -0.0338119 -0.0221334 -0.0722251 -0.0366224 -0.0170895 -0.0721299 -0.0366845 -0.0170965 -0.0707103 -0.0339497 -0.0221756 -0.0691688 -0.0304889 -0.0267129 -0.0707767 -0.03387 -0.0221437 -0.0692347 -0.0304193 -0.0266765 -0.0694136 -0.0303375 -0.0266718 -0.0680254 -0.0269566 -0.0300849 -0.0676742 -0.0263003 -0.0306788 -0.0675916 -0.0263466 -0.0306964 -0.0686969 -0.0295246 -0.0278968 -0.0677612 -0.0262722 -0.0306845 -0.0660699 -0.0217359 -0.0340639 -0.065991 -0.0217745 -0.0340849 -0.0659268 -0.021822 -0.034127 -0.0658844 -0.0218716 -0.0341836 -0.0661524 -0.0217104 -0.0340654 -0.0646167 -0.01668 -0.0368035 -0.0644332 -0.0167827 -0.0369285 -0.0643766 -0.0162281 0.037056 -0.0645878 -0.0138167 0.0366535 -0.0652057 -0.0129584 0.0355393 -0.0653915 -0.0126979 0.0351517 -0.0646291 -0.0138686 0.0366026 -0.0651738 -0.0128716 0.0355665 -0.0647833 -0.0133956 0.0362955 -0.065037 -0.0134646 0.0360891 -0.0645302 -0.0159893 0.0370119 -0.0646167 -0.01668 0.0368084 -0.0656058 -0.0128224 0.0349029 -0.0660384 -0.0128225 0.0342945 -0.0656926 -0.0128899 0.0349316 -0.065786 -0.0129191 0.0349729 -0.0647604 -0.0142232 0.0367002 -0.0645204 -0.0152759 0.0370346 -0.0645548 -0.0152775 0.0370328 -0.0646298 -0.0163849 0.0369121 -0.0646923 -0.0139196 0.036565 -0.0653217 -0.013251 0.0357696 -0.064377 -0.016231 0.0370553 -0.0644022 -0.0163921 0.0370107 -0.0645411 -0.0167099 0.0368324 -0.0643872 -0.0163004 0.0370373 -0.0643803 -0.0162542 0.0370495 -0.0643762 -0.0162252 0.0370567 -0.0644021 -0.0152649 0.0370737 -0.0643755 -0.0162194 0.0370581 -0.0644332 -0.0167827 0.0369334 -0.0642849 -0.0155073 0.0371993 -0.0643739 -0.0162078 0.0370609 -0.0643524 -0.0160201 0.0370989 -0.0644877 -0.015273 0.03704 -0.0647697 -0.0139615 0.0365481 -0.0651211 -0.0134978 0.0361061 -0.0648105 -0.0139774 0.0365479 -0.0643385 -0.0152564 0.0371237 -0.0652677 -0.0130424 0.0355293 -0.0653507 -0.0131056 0.035541 -0.0700999 -0.0122848 0.0240386 -0.0700836 -0.0124135 0.0240875 -0.0701993 -0.0124353 0.023925 -0.0702641 -0.0122453 0.0238563 -0.0702091 -0.0122453 0.023888 -0.0701756 -0.0127445 0.0241793 -0.0700665 -0.0126176 0.024194 -0.0701317 -0.012708 0.0241793 -0.0703085 -0.0126645 0.0240067 -0.0703742 -0.0125211 0.0238987 -0.0700839 -0.0127575 0.0243628 -0.0700476 -0.0125104 0.0241951 -0.0701056 -0.0125298 0.0240702 -0.0701722 -0.012597 0.0240269 -0.0702859 -0.0124633 0.023888 -0.0702609 -0.0126478 0.0240071 -0.0702737 -0.0127913 0.0241934 -0.0702238 -0.0127725 0.0241842 -0.0701635 -0.0122453 0.0239289 -0.070295 -0.0122453 0.0238446 -0.0702641 -0.00832476 0.0238563 -0.0700974 -0.00824688 0.0240462 -0.07021 -0.00832476 0.0238873 -0.0703855 -0.00832476 0.0238307 -0.0702916 -0.00817983 0.0238629 -0.0702805 -0.00804535 0.0239162 -0.0701635 -0.00832476 0.0239289 -0.0701265 -0.00812649 0.0240054 -0.0700875 -0.00817476 0.024076 -0.0703721 -0.00802476 0.0239111 -0.0701016 -0.00664534 0.0247075 -0.0700107 -0.00666621 0.0247122 -0.0701938 -0.00808079 0.0239486 -0.0699246 -0.0067017 0.0247439 -0.0698181 -0.00679534 0.0248692 -0.06981 -0.00643431 0.0251567 -0.0697861 -0.0066966 0.0249615 -0.0697281 -0.00664534 0.025128 -0.0698106 -0.00659858 0.0249416 -0.0699064 -0.00636668 0.0251904 -0.0699377 -0.00639298 0.025046 -0.0698446 -0.00645978 0.0250312 -0.0698761 -0.00651532 0.0249169 -0.0700846 -0.00651865 0.0248056 -0.0700698 -0.00644887 0.024891 -0.0699664 -0.00645424 0.0249136 -0.0700606 -0.00641693 0.024944 -0.070038 -0.00636561 0.0250738 -0.0698575 -0.00674726 0.0247996 -0.069766 -0.00649534 0.0251413 -0.069903 -0.00659715 0.0248195 -0.0699911 -0.00654648 0.0248002 -0.0679064 -0.00649534 0.0299321 -0.0679492 -0.00643438 0.0299504 -0.0698697 -0.00638553 0.0251775 -0.0680431 -0.0063667 0.0299906 -0.0678086 -0.00668159 0.0300583 -0.0677933 -0.00666445 0.030417 -0.0678246 -0.00655473 0.0303197 -0.0677922 -0.00666508 0.0304154 -0.0680337 -0.00664534 0.0305539 -0.0679705 -0.00663705 0.030541 -0.0679949 -0.00650981 0.0304375 -0.0679328 -0.00651202 0.0304085 -0.067874 -0.00652687 0.0303685 -0.0678433 -0.00664565 0.0304711 -0.0677583 -0.00679534 0.0301751 -0.0679062 -0.00644007 0.0300779 -0.0679521 -0.00640192 0.0301076 -0.0680045 -0.0063767 0.0301367 -0.0680253 -0.00641801 0.0303081 -0.0680767 -0.00643793 0.0303544 -0.0678473 -0.00654424 0.0300254 -0.0678075 -0.00657808 0.0301239 -0.0680074 -0.00638553 0.0299753 -0.0680593 -0.00636484 0.0301633 -0.0679669 -0.00642478 0.0302792 -0.0679114 -0.00644531 0.0302437 -0.0678637 -0.00647955 0.0302038 -0.0677712 -0.00663943 0.0302133 -0.0674087 -0.0080709 0.0311476 -0.0677419 -0.00672573 0.0302886 -0.0674435 -0.00804296 0.0312115 -0.0675562 -0.00801517 0.0313098 -0.0679059 -0.00663643 0.0305141 -0.0673673 -0.00832476 0.031154 -0.0674223 -0.008176 0.0312723 -0.0675382 -0.00816215 0.0313756 -0.0675459 -0.00808599 0.0313477 -0.0676766 -0.00809476 0.0313848 -0.0675335 -0.00824224 0.0313929 -0.0676676 -0.00824596 0.0314254 -0.0673735 -0.00820901 0.031128 -0.0673927 -0.00810463 0.0310821 -0.0674313 -0.00810683 0.0312464 -0.0673877 -0.00819086 0.0312017 -0.0674166 -0.00824913 0.0312884 -0.0674147 -0.00832476 0.031294 -0.0676664 -0.00834534 0.0314307 -0.0675232 -0.00832476 0.0313943 -0.0673924 -0.00834534 0.0310084 -0.0669111 -0.010626 0.0326346 -0.0668555 -0.0106447 0.0325966 -0.0673878 -0.00890885 0.0313511 -0.0674674 -0.00834534 0.0313552 -0.067012 -0.0103418 0.032136 -0.067061 -0.0103139 0.0321851 -0.0671809 -0.00992632 0.0317857 -0.0675232 -0.00834534 0.0313943 -0.0674893 -0.00942098 0.0316464 -0.0672648 -0.01026 0.032227 -0.0672402 -0.0103065 0.0322749 -0.0671193 -0.0102993 0.0322259 -0.0673601 -0.0094261 0.0315765 -0.0674228 -0.00941951 0.0316198 -0.0673673 -0.00834534 0.031154 -0.0672739 -0.00946405 0.031451 -0.0669771 -0.010381 0.0320827 -0.0665411 -0.0109709 0.0329854 -0.066001 -0.0112305 0.0340068 -0.0663239 -0.0110766 0.0335204 -0.0661462 -0.0110682 0.0340794 -0.0672589 -0.00949164 0.0313813 -0.0673393 -0.00893519 0.0312047 -0.0668563 -0.01073 0.0321831 -0.0671298 -0.00999684 0.0316626 -0.066514 -0.0111386 0.0329067 -0.0669589 -0.0104277 0.0320302 -0.0665193 -0.0110256 0.0329535 -0.0662579 -0.0112923 0.0334354 -0.0675824 -0.00928502 0.0315994 -0.0676005 -0.00834534 0.0314233 -0.0671808 -0.0102976 0.0322559 -0.0665761 -0.0109234 0.0330208 -0.0668079 -0.0106774 0.0325535 -0.0667845 -0.0108593 0.0331458 -0.0664188 -0.0110127 0.0335788 -0.066675 -0.0108648 0.0330912 -0.0673085 -0.00944132 0.0315185 -0.0673533 -0.0089207 0.0312795 -0.0674147 -0.00834534 0.031294 -0.0628831 -0.0110682 0.0399522 -0.0629809 -0.0110453 0.0400123 -0.0627448 -0.0112305 0.0398672 -0.0637632 -0.0113453 0.0381154 -0.0628002 -0.0111332 0.0399012 -0.0660591 -0.0111332 0.0340359 -0.0662489 -0.0110453 0.0341307 -0.0575425 -0.0102205 0.0475263 -0.0568591 -0.00834534 0.0482836 -0.0570253 -0.00951593 0.0480261 -0.0569607 -0.00954706 0.0480398 -0.0583704 -0.0108864 0.0465082 -0.0575973 -0.0103941 0.0473605 -0.0574725 -0.0105129 0.0473676 -0.0568593 -0.00961887 0.0481102 -0.0569039 -0.00958243 0.0480689 -0.0569307 -0.00979157 0.0480226 -0.057297 -0.0104141 0.0475687 -0.0591158 -0.0110682 0.0455151 -0.0583308 -0.0109078 0.0464858 -0.0590762 -0.0110942 0.0454857 -0.0582923 -0.0109371 0.0464671 -0.0582568 -0.0109735 0.0464535 -0.0590377 -0.0111332 0.045457 -0.0589855 -0.0112305 0.0454182 -0.0566276 -0.00834534 0.0483928 -0.0566743 -0.00834534 0.0483473 -0.057529 -0.0104479 0.0473543 -0.0580771 -0.0106924 0.0469182 -0.0576331 -0.0103734 0.0473705 -0.0591642 -0.0110503 0.045551 -0.0567311 -0.00834534 0.0483123 -0.0567943 -0.00834534 0.0482907 -0.0567311 -0.00832476 0.0483123 -0.0568591 -0.00832476 0.0482836 -0.0567092 -0.00814404 0.0483449 -0.0566109 -0.0082164 0.0484131 -0.0566276 -0.00832476 0.0483928 -0.0567207 -0.00820178 0.0483274 -0.0568398 -0.00809278 0.0483304 -0.0565946 -0.00817476 0.0484329 -0.0559734 -0.00675301 0.0491889 -0.0566946 -0.0080896 0.0483679 -0.0560936 -0.006674 0.0491539 -0.0558603 -0.00670258 0.0493093 -0.0557418 -0.00664759 0.0494482 -0.0558643 -0.00659959 0.0493253 -0.0560302 -0.00671043 0.0491633 -0.0559186 -0.00651957 0.0493282 -0.0558499 -0.00646404 0.0494308 -0.0560006 -0.00636329 0.0495343 -0.0560605 -0.00641797 0.0493939 -0.056115 -0.00651116 0.0492657 -0.0559877 -0.00645638 0.0493527 -0.0560461 -0.00654849 0.0492427 -0.0561488 -0.00660473 0.049186 -0.0561597 -0.00664534 0.0491604 -0.0559799 -0.00660138 0.0492369 -0.0557278 -0.00653053 0.0494998 -0.0559227 -0.00639599 0.049476 -0.0511988 -0.00653053 0.0543465 -0.0557772 -0.00643321 0.0495421 -0.0558511 -0.00636818 0.0496054 -0.0513151 -0.00636667 0.054465 -0.0510431 -0.00651394 0.0549159 -0.051055 -0.00655034 0.0544933 -0.0511828 -0.00664534 0.0543302 -0.0510156 -0.00669412 0.0544937 -0.0509156 -0.00665049 0.0546287 -0.0510954 -0.00644089 0.054582 -0.0511331 -0.00640503 0.0546361 -0.0510189 -0.00647688 0.054681 -0.0511626 -0.00643927 0.0548555 -0.0511094 -0.00643374 0.0548048 -0.0510594 -0.00644575 0.0547449 -0.0509428 -0.00654288 0.0547797 -0.0510687 -0.00649104 0.054533 -0.0511263 -0.00653568 0.0544187 -0.0512443 -0.00643321 0.0543929 -0.0512058 -0.00638928 0.0545299 -0.0512467 -0.00636483 0.0545767 -0.0513125 -0.00636818 0.0544624 -0.0512897 -0.00635477 0.0546227 -0.0511703 -0.00642786 0.0544857 -0.051178 -0.00638608 0.0546903 -0.0512255 -0.00638353 0.05474 -0.0460863 -0.00682628 0.0589086 -0.0460514 -0.00688613 0.0589262 -0.0475869 -0.0076548 0.0576372 -0.0473505 -0.00739022 0.0579182 -0.0480512 -0.00746064 0.0574461 -0.0479878 -0.00752934 0.0573861 -0.04741 -0.00732362 0.0579617 -0.0467802 -0.00707819 0.0584585 -0.0504734 -0.00695788 0.0553086 -0.0499441 -0.0072444 0.0558676 -0.0509739 -0.00652287 0.0548346 -0.0505757 -0.00695168 0.0554204 -0.0510584 -0.00651568 0.0549297 -0.0511037 -0.00652636 0.0549641 -0.0505229 -0.00694596 0.0553691 -0.0492592 -0.00748574 0.056292 -0.0498632 -0.00729902 0.0557574 -0.0498371 -0.00734932 0.0557079 -0.0492169 -0.00759384 0.0562231 -0.049622 -0.00760504 0.0558181 -0.0498309 -0.00752906 0.0556239 -0.0506264 -0.00697072 0.0554599 -0.0500203 -0.00725898 0.0559746 -0.0487361 -0.00747325 0.0570287 -0.0498238 -0.00740887 0.055668 -0.0509524 -0.00674788 0.0545551 -0.0509233 -0.00657068 0.0547278 -0.0504333 -0.00698905 0.0552443 -0.0473045 -0.00747577 0.057898 -0.0486265 -0.00756127 0.0568418 -0.0485693 -0.00777311 0.0567755 -0.0486587 -0.00752185 0.0568782 -0.0486947 -0.00749382 0.0569189 -0.0499001 -0.00726317 0.0558124 -0.0487323 -0.00747783 0.0569611 -0.0499906 -0.00724215 0.0559184 -0.0459697 -0.00681903 0.0589941 -0.0461334 -0.00676612 0.0589055 -0.0461861 -0.00671485 0.0589184 -0.0461637 -0.0066145 0.0590035 -0.0459773 -0.0066363 0.0590322 -0.046032 -0.00658833 0.0590397 -0.045741 -0.00638553 0.0594063 -0.0460891 -0.00655042 0.0590614 -0.0459093 -0.00635782 0.0593907 -0.0458382 -0.00639012 0.059323 -0.0459718 -0.00639543 0.0592731 -0.0459063 -0.00643459 0.0592196 -0.0457672 -0.00667018 0.0591736 -0.0458913 -0.00674788 0.0590617 -0.0459282 -0.00669228 0.0590402 -0.0458442 -0.00650035 0.0591814 -0.0459719 -0.00650014 0.059124 -0.0457718 -0.00645868 0.0592678 -0.0457959 -0.00658425 0.0591658 -0.0456357 -0.00664534 0.0592994 -0.044999 -0.00634534 0.0605759 -0.0456966 -0.00643428 0.0593613 -0.0456639 -0.00649534 0.0593281 -0.0457683 -0.00636667 0.059434 -0.0442099 -0.00634534 0.0627346 -0.0440958 -0.0063664 0.064393 -0.0440615 -0.00638553 0.0627125 -0.0448714 -0.00638553 0.0604971 -0.0443536 -0.00638553 0.0615636 -0.0442505 -0.00649534 0.0615259 -0.044778 -0.00649534 0.0604394 -0.0439529 -0.00649534 0.0626964 -0.043948 -0.00649534 0.0644141 -0.0439381 -0.00670478 0.0646079 -0.0439604 -0.00659448 0.0646254 -0.0441102 -0.00638989 0.0645434 -0.0440567 -0.00638553 0.0643986 -0.0440278 -0.00650959 0.064663 -0.0441246 -0.00645037 0.0646805 -0.043931 -0.00668008 0.0645665 -0.0439082 -0.00664534 0.0644198 -0.0441378 -0.00654272 0.0647972 -0.0439952 -0.00643321 0.0644074 -0.0440114 -0.00645515 0.0645414 -0.0439859 -0.00674545 0.0647736 -0.0440428 -0.00659165 0.0647659 -0.0442484 -0.00664534 0.064897 -0.0441139 -0.00760697 0.0652889 -0.044054 -0.00669745 0.0648438 -0.044148 -0.00666235 0.0648867 -0.0443017 -0.00707752 0.0651466 -0.0441258 -0.00770247 0.0653293 -0.0441817 -0.0075603 0.0653505 -0.0442818 -0.00766044 0.0654408 -0.0442711 -0.00752473 0.0653866 -0.0440865 -0.00772705 0.0652472 -0.0441508 -0.00780515 0.0653702 -0.0441939 -0.00767878 0.065398 -0.044253 -0.00780515 0.0654467 -0.0443776 -0.00780515 0.0654738 -0.0441978 -0.00780515 0.0654139 -0.0441673 -0.00914716 0.0654603 -0.044235 -0.00912206 0.0655263 -0.0441508 -0.00834534 0.0653702 -0.0441978 -0.00834534 0.0654139 -0.044253 -0.00834534 0.0654467 -0.0441271 -0.00917364 0.0653809 -0.044291 -0.00987781 0.0657987 -0.0443574 -0.00983012 0.0658499 -0.0443217 -0.00910245 0.0655672 -0.0444131 -0.00909081 0.0655788 -0.0445273 -0.0104765 0.0663155 -0.0446717 -0.0103579 0.0663527 -0.0445306 -0.00976977 0.0658802 -0.0444418 -0.00979254 0.0658778 -0.0444356 -0.00928119 0.0656412 -0.0448984 -0.0108989 0.0669373 -0.0444888 -0.0105463 0.0662702 -0.0450334 -0.010756 0.0669241 -0.044591 -0.0104101 0.0663449 -0.0451139 -0.0107203 0.0668895 -0.0459785 -0.0110667 0.0682358 -0.0454109 -0.0110613 0.0675976 -0.0449572 -0.0108183 0.0669415 -0.0454911 -0.0109936 0.0675611 -0.0455773 -0.0109625 0.0675115 -0.0459462 -0.0110855 0.0682574 -0.0458936 -0.0111344 0.0682927 -0.045855 -0.0111953 0.0683185 -0.0474784 -0.0111953 0.0707395 -0.0485998 -0.0103912 0.072447 -0.0491199 -0.00834778 0.0729141 -0.0490035 -0.00939022 0.0727409 -0.0489519 -0.00941608 0.0728504 -0.0490711 -0.00834784 0.0730278 -0.0490723 -0.00834794 0.0731515 -0.0489488 -0.00945579 0.0729673 -0.0491161 -0.00834803 0.0732538 -0.0486746 -0.0102705 0.0722518 -0.0489879 -0.00949777 0.0730626 -0.0481827 -0.0108593 0.0715203 -0.0487597 -0.0102561 0.0721774 -0.0480779 -0.0110168 0.071669 -0.0486152 -0.0103182 0.0723489 -0.0482265 -0.0109971 0.0719272 -0.0486257 -0.0104684 0.0725225 -0.0476019 -0.0110667 0.0706566 -0.0481117 -0.0109217 0.071599 -0.0475696 -0.0110855 0.0706783 -0.0474451 -0.0113453 0.0707618 -0.0490718 0.000304489 0.0731493 -0.0490714 0.000304495 0.0730263 -0.0491203 0.000304499 0.0729134 -0.0489364 0.00165768 0.0729859 -0.0487551 0.00222349 0.0721707 -0.0490283 0.000952068 0.0729644 -0.0489041 0.00156189 0.0727794 -0.0490781 0.0009364 0.0728521 -0.0491607 0.000931749 0.0727732 -0.0488457 0.00204793 0.0723053 -0.0489567 0.00153145 0.0726716 -0.0488993 0.00160857 0.0728938 -0.0487038 0.00210464 0.0724812 -0.0487611 0.00206104 0.0723807 -0.0485006 0.00249505 0.0719999 -0.0485894 0.00247734 0.0719246 -0.0481981 0.00304403 0.0708086 -0.048996 0.00309401 0.0695624 -0.0485495 0.00302391 0.0701625 -0.0481208 0.00311363 0.0714257 -0.0486599 0.0033032 0.0697379 -0.0484575 0.00329927 0.0699837 -0.0481207 0.00323844 0.0708283 -0.0482881 0.00281072 0.0714641 -0.0482852 0.00297639 0.0708108 -0.0482095 0.00287408 0.0715099 -0.0484404 0.00254723 0.0720866 -0.0482691 0.00281432 0.0718886 -0.0484181 0.00262583 0.0721714 -0.0482729 0.00290629 0.0719441 -0.0481632 0.00296245 0.0715584 -0.0481171 0.00306921 0.0711946 -0.0481407 0.00313795 0.0708151 -0.048468 0.00309175 0.0701148 -0.048414 0.00319036 0.0700852 -0.0489583 0.00319485 0.0695091 -0.0496828 0.00300452 0.0693333 -0.0489464 0.00330412 0.0694923 -0.0501216 0.00309253 0.0687582 -0.0490534 0.00302685 0.0696438 -0.0501789 0.0030275 0.0688368 -0.073891 0.0030275 0.0423818 -0.0699212 0.00330466 0.0483288 -0.06994 0.00318986 0.0483418 -0.0629425 0.00330466 0.0571226 -0.0556577 0.00330466 0.0642422 -0.0556727 0.00318986 0.0642595 -0.0500698 0.00330466 0.0686872 -0.0656864 0.00309253 0.0540829 -0.0656362 0.00318986 0.0540415 -0.0608692 0.00318986 0.0593599 -0.0557152 0.00309253 0.0643086 -0.0500833 0.00318986 0.0687056 -0.0700735 0.0030275 0.0484341 -0.0699935 0.00309253 0.0483788 -0.0609157 0.00309253 0.0594053 -0.0739906 0.00300466 0.0424389 -0.0657615 0.0030275 0.0541447 -0.0609854 0.0030275 0.0594733 -0.0610676 0.00300466 0.0595534 -0.055779 0.0030275 0.0643822 -0.0502465 0.00300466 0.0689296 -0.0737502 0.00318986 0.042301 -0.0738066 0.00309253 0.0423334 -0.0754877 0.00300466 0.0409951 -0.0745035 0.00302517 0.0415882 -0.0752478 0.00308779 0.0408909 -0.0752979 0.00302464 0.0409771 -0.0762229 0.00302416 0.0405932 -0.0772137 0.00304089 0.0404255 -0.0772137 0.0030841 0.0403651 -0.0744321 0.00309012 0.0415173 -0.0761972 0.00308572 0.0404979 -0.0761796 0.0031802 0.0404324 -0.0737304 0.00330466 0.0422896 -0.0743682 0.00329782 0.0414536 -0.0743845 0.00318928 0.0414699 -0.0752139 0.00318448 0.0408325 -0.0752015 0.00329111 0.040811 -0.0772137 0.00317682 0.040297 -0.0772137 0.00314083 0.0403171 -0.0967958 0.00314083 0.0403171 -0.0967958 0.00328034 0.0402694 -0.0772137 0.00300466 0.0405684 -0.0772858 0.00470472 0.0402294 -0.0772858 0.00459606 0.0401672 -0.0967958 0.00470472 0.0402294 -0.0967958 0.00459606 0.0401672 -0.0744409 0.00460827 0.0413605 -0.0738066 0.00461509 0.042199 -0.0738232 0.00465466 0.0422085 -0.0744879 0.00471346 0.041407 -0.0739185 0.00476447 0.042263 -0.075272 0.00460152 0.040714 -0.0745611 0.00478284 0.0414796 -0.0762875 0.00478141 0.04047 -0.0762599 0.00470714 0.0403681 -0.0762397 0.00447798 0.0402933 -0.076243 0.00459539 0.0403057 -0.0753049 0.00471015 0.0407705 -0.0753575 0.00478209 0.0408607 -0.0772858 0.00477854 0.0403305 -0.0772858 0.00480466 0.0404529 -0.0738645 0.00471679 0.0422322 -0.0740487 0.00480466 0.0423375 -0.071542 0.00476447 0.0461724 -0.0737883 0.00450466 0.0421886 -0.071668 0.00480466 0.0462537 -0.0631646 0.00480466 0.0573242 -0.0564839 0.00480466 0.0639179 -0.0563846 0.00476447 0.0638055 -0.0500031 0.00471679 0.0688444 -0.0714497 0.00465466 0.0461129 -0.0689589 0.00476447 0.0499485 -0.0660211 0.00465466 0.053598 -0.0661064 0.00476447 0.0536672 -0.0630535 0.00476447 0.0572234 -0.0598097 0.00476447 0.0606063 -0.0563119 0.00465466 0.0637232 -0.0714159 0.00450466 0.0460911 -0.0688375 0.00450466 0.0498605 -0.06887 0.00465466 0.0498841 -0.0659899 0.00450466 0.0535727 -0.0629722 0.00465466 0.0571496 -0.0597325 0.00465466 0.0605281 -0.0499751 0.00465466 0.0688058 -0.0499515 0.00450466 0.0687733 -0.0491162 0.00480509 0.069733 -0.0500397 0.00476447 0.0688946 -0.0489583 0.00461447 0.0695091 -0.0489464 0.00450514 0.0694923 -0.0484675 0.00471753 0.0701157 -0.0490535 0.00478251 0.069644 -0.0482884 0.00499888 0.071465 -0.0485007 0.00531416 0.0719998 -0.0484405 0.00526199 0.0720866 -0.0481404 0.00467145 0.0708167 -0.0484135 0.00461889 0.070086 -0.0481258 0.00462073 0.0708227 -0.0480993 0.00460894 0.0710633 -0.0481204 0.00457094 0.07083 -0.0485491 0.00478536 0.0701634 -0.048784 0.00480707 0.0700298 -0.0481552 0.00475251 0.0716015 -0.048996 0.00471536 0.0695625 -0.0481548 0.00479939 0.0715818 -0.0481635 0.00484715 0.0715595 -0.0482097 0.00493554 0.0715109 -0.0481979 0.00476538 0.0708101 -0.0483637 0.00498679 0.071323 -0.048285 0.00483301 0.0708122 -0.0484239 0.00484311 0.0706641 -0.0487623 0.00575094 0.0723822 -0.0489574 0.00627942 0.0726723 -0.049079 0.006876 0.072853 -0.0490409 0.00628845 0.0725948 -0.0489047 0.00624903 0.0727801 -0.0484181 0.00518336 0.0721714 -0.0487049 0.00570741 0.0724827 -0.0484231 0.00513457 0.0722113 -0.0489371 0.00615331 0.0729868 -0.0488999 0.00620239 0.0728946 -0.0490291 0.00686041 0.0729655 -0.0491617 0.00688061 0.0727742 -0.0492022 0.0100047 0.0728348 -0.0491206 0.00750491 0.0729134 -0.0490715 0.00750492 0.0730263 -0.0490719 0.00750493 0.0731494 -0.0491162 0.00750494 0.073254 -0.049116 0.0125045 0.0732537 -0.0488993 0.0138085 0.0728938 -0.0484371 0.0149187 0.0722412 -0.0490713 0.0125045 0.0730262 -0.0491203 0.0125045 0.0729134 -0.0490283 0.0131521 0.0729644 -0.049078 0.0131364 0.072852 -0.0492021 0.0125045 0.0728348 -0.0491607 0.0131317 0.0727732 -0.0490401 0.0137224 0.072594 -0.0489567 0.0137314 0.0726716 -0.048904 0.0137619 0.0727794 -0.0490718 0.0125045 0.0731492 -0.0484181 0.0148258 0.0721714 -0.0487038 0.0143046 0.0724812 -0.0487611 0.014261 0.0723807 -0.0484891 0.0148127 0.0717485 -0.0482881 0.0150107 0.0714641 -0.048468 0.0152918 0.0701148 -0.0482853 0.0151764 0.0708108 -0.0481407 0.015338 0.0708151 -0.0481207 0.0154385 0.0708283 -0.0486599 0.0155032 0.0697379 -0.0484575 0.0154993 0.0699837 -0.0483957 0.0154967 0.0700778 -0.0481866 0.0154705 0.0705394 -0.0485006 0.014695 0.0719999 -0.0483519 0.0150883 0.0711021 -0.0485495 0.0152239 0.0701626 -0.0485392 0.0151898 0.0703849 -0.0491161 0.0152042 0.0697329 -0.0482095 0.0150741 0.0715099 -0.0484404 0.0147472 0.0720866 -0.0481632 0.0151624 0.0715584 -0.0482691 0.0150143 0.0718886 -0.0481171 0.0152692 0.0711946 -0.0481981 0.015244 0.0708086 -0.048414 0.0153904 0.0700852 -0.0496445 0.0152045 0.0693609 -0.0500072 0.0153899 0.068761 -0.0489583 0.0153949 0.0695091 -0.0500455 0.0152925 0.0688136 -0.048996 0.015294 0.0695624 -0.0501027 0.0152275 0.0688923 -0.0490534 0.0152268 0.0696439 -0.0752994 0.0152275 0.0398257 -0.0712091 0.0155047 0.0464101 -0.0712282 0.0153899 0.0464226 -0.0702679 0.0155047 0.0478232 -0.0569043 0.0155047 0.0631405 -0.0666918 0.0155047 0.0526962 -0.0667098 0.0153899 0.0527104 -0.0640457 0.0155047 0.0558828 -0.061638 0.0153899 0.0585611 -0.0560551 0.0153899 0.0639261 -0.05604 0.0155047 0.0639089 -0.0712827 0.0152925 0.0464581 -0.0713642 0.0152275 0.0465112 -0.0667608 0.0152925 0.0527507 -0.0616852 0.0152925 0.0586059 -0.0617558 0.0152275 0.0586729 -0.056098 0.0152925 0.063975 -0.0668372 0.0152275 0.052811 -0.0561621 0.0152275 0.0640482 -0.0758381 0.0153709 0.0387951 -0.0751558 0.0153899 0.0397498 -0.0758885 0.0152813 0.0388412 -0.0752133 0.0152925 0.0397802 -0.076719 0.0154402 0.0380185 -0.0767387 0.0153491 0.0380491 -0.0767758 0.0152708 0.0381068 -0.0778239 0.015262 0.0376314 -0.077849 0.0152186 0.0377136 -0.0768251 0.0152207 0.0381835 -0.0759598 0.0152231 0.0389063 -0.0789613 0.0152554 0.0374685 -0.0778041 0.0153303 0.0375666 -0.0789613 0.0152276 0.0375204 -0.0789613 0.0153904 0.037358 -0.0789613 0.0152928 0.037423 -0.0967958 0.0152928 0.037423 -0.0967958 0.0152276 0.0375204 -0.0789613 0.0152047 -0.0376305 -0.0789613 0.0152276 -0.0375155 -0.0967958 0.0152276 -0.0375155 -0.0789613 0.0153904 -0.0373531 -0.0759598 0.0152231 -0.0389014 -0.0758885 0.0152813 -0.0388363 -0.0751712 0.0153547 -0.039753 -0.0767882 0.0152047 -0.0383191 -0.0767758 0.0152708 -0.0381019 -0.076719 0.0154402 -0.0380136 -0.0758381 0.0153709 -0.0387902 -0.0767387 0.0153491 -0.0380443 -0.0778041 0.0153303 -0.0375617 -0.0768251 0.0152207 -0.0381786 -0.077849 0.0152186 -0.0377087 -0.0789613 0.0152554 -0.0374636 -0.0778239 0.015262 -0.0376265 -0.0789613 0.0152928 -0.0374181 -0.0751543 0.0153942 -0.0397441 -0.0752133 0.0152925 -0.0397753 -0.0752683 0.0152449 -0.0398043 -0.0730711 0.0152047 -0.0439986 -0.0729426 0.0152449 -0.0439212 -0.070516 0.0152047 -0.0479871 -0.0642717 0.0152047 -0.0560751 -0.0570048 0.0152449 -0.0632471 -0.0571052 0.0152047 -0.0633585 -0.0537113 0.0152047 -0.0662602 -0.0536169 0.0152449 -0.0661436 -0.0501703 0.0152047 -0.0689803 -0.0500455 0.0152925 -0.0688087 -0.070392 0.0152449 -0.0479027 -0.0673963 0.0152449 -0.052033 -0.0641587 0.0152449 -0.0559765 -0.0606907 0.0152449 -0.059719 -0.0728485 0.0153547 -0.0438646 -0.0703012 0.0153547 -0.0478409 -0.0672776 0.0155047 -0.0519414 -0.0673094 0.0153547 -0.0519659 -0.064076 0.0153547 -0.0559043 -0.0640457 0.0155047 -0.0558779 -0.0606124 0.0153547 -0.059642 -0.0569312 0.0153547 -0.0631655 -0.0535477 0.0153547 -0.0660583 -0.0535224 0.0155047 -0.0660271 -0.0490534 0.0152268 -0.069639 -0.0496445 0.0152045 -0.069356 -0.050082 0.0152449 -0.068859 -0.0500174 0.0153547 -0.0687702 -0.0499938 0.0155047 -0.0687376 -0.0484675 0.0152917 -0.0701108 -0.048996 0.015294 -0.0695576 -0.0482883 0.0150103 -0.0714602 -0.0485894 0.0146773 -0.0719197 -0.0485006 0.014695 -0.071995 -0.0482097 0.0150737 -0.0715061 -0.048784 0.0152022 -0.0700247 -0.0484238 0.0151661 -0.0706592 -0.048549 0.0152239 -0.0701585 -0.0483433 0.0154935 -0.0701631 -0.0481404 0.0153377 -0.0708118 -0.0481258 0.0153884 -0.0708178 -0.0481588 0.0152513 -0.0716113 -0.0481979 0.0152438 -0.0708052 -0.0481548 0.0152098 -0.0715769 -0.0481635 0.015162 -0.0715546 -0.0484135 0.0153904 -0.0700812 -0.0489583 0.0153949 -0.0695042 -0.048266 0.0151144 -0.0719244 -0.0484181 0.0148258 -0.0721665 -0.048285 0.0151762 -0.0708073 -0.0484231 0.0148746 -0.0722065 -0.0484404 0.0147472 -0.0720817 -0.0487621 0.0142583 -0.0723773 -0.0491613 0.0131287 -0.0727693 -0.0489572 0.0137298 -0.0726674 -0.0490289 0.0131489 -0.0729605 -0.0489045 0.0137602 -0.0727752 -0.0487048 0.0143018 -0.0724778 -0.0488998 0.0138069 -0.0728896 -0.0490787 0.0131333 -0.0728481 -0.0490718 0.0125045 -0.0731443 -0.0490713 0.0125045 -0.0730213 -0.0490715 0.00750492 -0.0730214 -0.0491206 0.00750491 -0.0729085 -0.0491203 0.0125045 -0.0729085 -0.0492021 0.0125045 -0.0728299 -0.0491162 0.00750494 -0.0732491 -0.0484371 0.0050904 -0.0722363 -0.0487554 0.00558579 -0.0721659 -0.0492026 0.00750491 -0.07283 -0.0490783 0.00687294 -0.0728472 -0.048957 0.00627783 -0.0726667 -0.0487613 0.00574819 -0.0723758 -0.0490404 0.00628687 -0.0725892 -0.0489042 0.0062474 -0.0727746 -0.0490285 0.00685728 -0.0729596 -0.0488994 0.00620069 -0.0728891 -0.0490719 0.00750493 -0.0731445 -0.0487039 0.0057046 -0.0724763 -0.0482691 0.00499488 -0.0718836 -0.0484181 0.00518336 -0.0721665 -0.0484405 0.00526199 -0.0720817 -0.0485496 0.00478534 -0.0701578 -0.0490535 0.00478251 -0.0696391 -0.0482882 0.0049985 -0.0714592 -0.0481982 0.00476518 -0.0708037 -0.0482853 0.00483281 -0.0708059 -0.0486599 0.00450604 -0.069733 -0.048414 0.00461887 -0.0700803 -0.0483957 0.00451253 -0.0700729 -0.0481866 0.00453864 -0.0705344 -0.0484892 0.00519632 -0.0717433 -0.0485007 0.00531416 -0.071995 -0.0482095 0.00493514 -0.071505 -0.0481632 0.00484675 -0.0715535 -0.0481208 0.0046955 -0.0714207 -0.0481171 0.00473998 -0.0711897 -0.0481407 0.00467123 -0.0708102 -0.048468 0.00471751 -0.07011 -0.0499751 0.00465466 -0.0688009 -0.0489583 0.00461447 -0.0695042 -0.0500031 0.00471679 -0.0688395 -0.048996 0.00471536 -0.0695576 -0.0500397 0.00476447 -0.0688897 -0.0738066 0.00461509 -0.0421942 -0.0738645 0.00471679 -0.0422273 -0.0739185 0.00476447 -0.0422581 -0.071542 0.00476447 -0.0461675 -0.0714497 0.00465466 -0.046108 -0.0688375 0.00450466 -0.0498556 -0.06887 0.00465466 -0.0498792 -0.0659899 0.00450466 -0.0535678 -0.0597043 0.00450466 -0.0604946 -0.0562852 0.00450466 -0.0636882 -0.0563119 0.00465466 -0.0637183 -0.0660211 0.00465466 -0.0535932 -0.0661064 0.00476447 -0.0536624 -0.0629722 0.00465466 -0.0571448 -0.0597325 0.00465466 -0.0605232 -0.071668 0.00480466 -0.0462488 -0.0690804 0.00480466 -0.0500316 -0.0689589 0.00476447 -0.0499436 -0.0630535 0.00476447 -0.0572185 -0.0631646 0.00480466 -0.0573193 -0.0598097 0.00476447 -0.0606014 -0.059915 0.00480466 -0.0607081 -0.0563846 0.00476447 -0.0638006 -0.0564839 0.00480466 -0.063913 -0.0744279 0.00449532 -0.0413427 -0.0744879 0.00471346 -0.0414021 -0.0738232 0.00465466 -0.0422036 -0.0744409 0.00460827 -0.0413556 -0.0737883 0.00450466 -0.0421837 -0.0753049 0.00471015 -0.0407656 -0.0753575 0.00478209 -0.0408558 -0.0745611 0.00478284 -0.0414747 -0.0750061 0.00480466 -0.0412306 -0.076243 0.00459539 -0.0403008 -0.0762599 0.00470714 -0.0403632 -0.075272 0.00460152 -0.0407091 -0.0772858 0.00447149 -0.0401499 -0.0762397 0.00447798 -0.0402884 -0.0772858 0.00470472 -0.0402245 -0.0772858 0.00477854 -0.0403256 -0.0762875 0.00478141 -0.0404651 -0.0755581 0.00480466 -0.0408751 -0.0772858 0.00459606 -0.0401623 -0.0967958 0.00470472 -0.0402245 -0.0967958 0.00477854 -0.0403256 -0.0442868 0.0287546 0.0648223 -0.0450238 0.0287344 0.0668072 -0.0440808 0.0286678 0.0648686 -0.0449385 0.0286678 0.0668643 -0.0440149 0.0285657 0.0648834 -0.0448647 0.0284547 0.0669138 -0.044181 0.0287344 0.0648461 -0.0441951 0.0287546 0.0643022 -0.0442101 0.0287545 0.0627333 -0.0439344 0.0285656 0.0626923 -0.0446496 0.0285655 0.0606191 -0.0440013 0.0286676 0.0627023 -0.0441028 0.0287342 0.0627174 -0.0444653 0.0287543 0.061697 -0.0447977 0.0287341 0.0607033 -0.0461727 0.0287343 0.0590746 -0.0461077 0.0286678 0.0589951 -0.0447084 0.0286676 0.0606525 -0.0460649 0.0285656 0.0589427 -0.0460514 0.0284545 0.0589262 -0.0448824 0.0285658 0.066902 -0.0595023 0.0287534 0.0451889 -0.0592757 0.0285643 0.0450226 -0.0509012 0.0286666 0.0547285 -0.0508546 0.0285647 0.0546802 -0.0510495 0.0287541 0.0548811 -0.055396 0.0287331 0.0501409 -0.0509723 0.0287333 0.0548018 -0.0553188 0.0286664 0.0500737 -0.0593301 0.0286663 0.0450625 -0.0573337 0.0284535 0.0475229 -0.055268 0.0285644 0.0500294 -0.0629048 0.0286664 0.0397317 -0.0594128 0.028733 0.0451232 -0.0628474 0.0285645 0.0396967 -0.0474424 0.0284546 0.0707578 -0.0481082 0.028281 0.0717508 -0.0481432 0.0283869 0.0717652 -0.04746 0.0285651 0.0707462 -0.0475155 0.0286668 0.0707092 -0.0482148 0.0284844 0.0717519 -0.0483099 0.0285485 0.071711 -0.0476001 0.0287336 0.0706526 -0.0476918 0.0287546 0.0705911 -0.068901 0.0324681 0.0280322 -0.0637649 0.0285035 0.0381125 -0.06459 0.0287711 0.036697 -0.0629922 0.0287331 0.0397851 -0.0690183 0.0324676 0.0280783 -0.0678363 0.0307939 0.0308842 -0.066332 0.0296193 0.0337834 -0.0670968 0.0300924 0.0324899 -0.0664394 0.0296271 0.0338387 -0.0661685 0.0293404 0.0336177 -0.0675632 0.0306356 0.0306865 -0.0646477 0.0288752 0.0367435 -0.0661765 0.0294548 0.0336566 -0.0662343 0.0295585 0.0337167 -0.0687387 0.0323259 0.0278677 -0.0647403 0.0289398 0.0368036 -0.0676209 0.0307354 0.0307608 -0.0677231 0.0307912 0.0308331 -0.0487429 0.0282359 0.0723566 -0.0488401 0.0282546 0.0723031 -0.0487183 0.0277749 0.0726606 -0.0485598 0.0280862 0.0723864 -0.0492636 0.0277599 0.0729347 -0.0486413 0.0281766 0.0723879 -0.0489656 0.0276122 0.0729915 -0.0721583 0.0384782 0.0166238 -0.0701987 0.0348284 0.0244582 -0.0687958 0.032418 0.0279555 -0.0700301 0.0345765 0.0242479 -0.068739 0.0322233 0.0277946 -0.0711751 0.0366675 0.0205288 -0.0700348 0.0346807 0.024313 -0.0700943 0.0347748 0.0243904 -0.0713496 0.0369262 0.0207099 -0.0716461 0.037269 0.020081 -0.0711843 0.0367732 0.0205854 -0.0712459 0.0368692 0.0206517 -0.0722348 0.0386829 0.0167257 -0.0721714 0.0385852 0.0166711 -0.0729604 0.039979 0.0125128 -0.0729768 0.0400873 0.0125494 -0.0730417 0.0401866 0.0125912 -0.072338 0.0387429 0.0167736 -0.0731443 0.0402494 0.012628 -0.0489095 0.0275261 0.0729457 -0.04939 0.0271079 0.0735044 -0.0490566 0.0276914 0.0730072 -0.0491645 0.0277435 0.0729853 -0.0496036 0.0271646 0.0734418 -0.0736761 0.0452287 0.00897622 -0.0737988 0.0452287 0.00900244 -0.0737664 0.0435963 0.00926531 -0.0736486 0.0435928 0.00924103 -0.0736675 0.0421367 0.0100216 -0.0735418 0.0435724 0.00916655 -0.0734443 0.0420908 0.00993078 -0.0734685 0.0435021 0.00894522 -0.0735505 0.0421297 0.00999703 -0.0733822 0.0409782 0.0111663 -0.0733699 0.0419583 0.00974198 -0.0732133 0.0408376 0.0110418 -0.0732772 0.0409246 0.0111129 -0.0495029 0.027151 0.07349 -0.0497792 0.026435 0.073902 -0.0492912 0.0270421 0.0734771 -0.0493654 0.0266462 0.0736256 -0.0735749 0.0452287 0.00890213 -0.0735128 0.0453047 0.00879313 -0.0735128 0.0452287 0.00879313 -0.0735007 0.0452287 0.00866828 -0.0735007 0.0453047 0.00866828 -0.0496695 0.0255402 0.0740791 -0.0494859 0.026299 0.0738053 -0.0497456 0.0255739 0.0741547 -0.0495571 0.0263529 0.0738737 -0.049855 0.025605 0.0741979 -0.0496621 0.0264025 0.0739102 -0.0733724 0.0460067 0.00867039 -0.0730043 0.0466187 0.00867649 -0.0735442 0.0460715 0.00897965 -0.0736761 0.0453047 0.00897622 -0.0735749 0.0453047 0.00890213 -0.0734437 0.0460336 0.00890414 -0.0735113 0.0453047 0.00878828 -0.073383 0.0460107 0.00878988 -0.049859 0.0242547 0.0743253 -0.0497536 0.0249053 0.0742046 -0.0499715 0.0242547 0.0743735 -0.0500939 0.0242547 0.0743728 -0.049975 0.0256254 0.0741941 -0.0731436 0.046741 0.00898014 -0.0730636 0.0466707 0.00890638 -0.0726377 0.0472306 0.00867065 -0.0730143 0.0466275 0.00879446 -0.0728094 0.0472954 0.00897965 -0.072709 0.0472575 0.00890421 -0.0726483 0.0472346 0.00879005 -0.0497845 -0.0083505 0.0742506 -0.0498609 -0.00835068 0.0743288 -0.0500929 -0.00835084 0.0743776 -0.050198 0.0242547 0.0743286 -0.0501966 0.00566592 0.0743357 -0.0501965 -0.00363303 0.0743363 -0.0501967 -0.00835092 0.0743354 -0.0725206 0.0479326 0.00878873 -0.0725221 0.0538047 0.00879358 -0.0725221 0.0479326 0.00879358 -0.0725842 0.0538047 0.00890236 -0.0726854 0.0538047 0.00897628 -0.0725842 0.0479326 0.00890236 -0.0726854 0.0479326 0.00897628 -0.0728079 0.0479326 0.00900244 -0.0491496 -0.0114073 0.0732679 -0.0496032 -0.00996759 0.0739802 -0.0477402 -0.0125119 0.071202 -0.0483656 -0.0123362 0.0720986 -0.0474746 -0.0126858 0.0707431 -0.0475185 -0.0127575 0.0707136 -0.0475537 -0.0127927 0.07069 -0.0476084 -0.0128268 0.0706533 -0.04854 -0.0124938 0.0720587 -0.0496749 -0.0100091 0.0740514 -0.0499718 -0.00835078 0.0743771 -0.0497813 -0.0100484 0.0740931 -0.0498994 -0.0100746 0.0740894 -0.0493539 -0.011528 0.0732748 -0.0484418 -0.012431 0.0720939 -0.0483263 -0.0122362 0.072076 -0.0492438 -0.0114798 0.0732911 -0.047649 -0.0128403 0.070626 -0.0476024 -0.012824 0.0706573 -0.0448981 -0.0126953 0.0668915 -0.0449377 -0.0127575 0.0668649 -0.0449893 -0.0128051 0.0668303 -0.0441924 -0.0128051 0.0650677 -0.044007 -0.0128051 0.0638968 -0.0444945 -0.0128453 0.0616151 -0.0448714 -0.0128051 0.0604971 -0.0462412 -0.0128453 0.0591585 -0.0461463 -0.0128051 0.0590423 -0.0440862 -0.0126953 0.0650958 -0.0440615 -0.0128051 0.0627125 -0.0443536 -0.0128051 0.0615636 -0.0438974 -0.0126953 0.0639029 -0.0439529 -0.0126953 0.0626964 -0.0442505 -0.0126953 0.0615259 -0.044778 -0.0126953 0.0604394 -0.0442128 -0.0125453 0.0615121 -0.0447438 -0.0125453 0.0604182 -0.0460514 -0.0125453 0.0589262 -0.0543029 -0.0126601 0.0511175 -0.0573337 -0.0125453 0.0475229 -0.0580119 -0.0127575 0.0468052 -0.0580887 -0.0128225 0.046865 -0.0581793 -0.0128453 0.0469356 -0.0503149 -0.0125453 0.055168 -0.0503306 -0.0126601 0.0551846 -0.0543511 -0.0127575 0.0511612 -0.0503754 -0.0127575 0.0552317 -0.0544232 -0.0128225 0.0512265 -0.0504424 -0.0128225 0.0553023 -0.0460768 -0.0126953 0.0589573 -0.046107 -0.0127575 0.0589942 -0.0728079 0.0479326 -0.00899756 -0.0726854 0.0479326 -0.0089714 -0.0726854 0.0538047 -0.0089714 -0.0725221 0.0479326 -0.0087887 -0.0725221 0.0538047 -0.0087887 -0.0728094 0.0472954 -0.00897476 -0.0725206 0.0479326 -0.00878385 -0.072709 0.0472575 -0.00889933 -0.0725842 0.0479326 -0.00889748 -0.0731436 0.0467409 -0.00897523 -0.0730143 0.0466275 -0.00878956 -0.0726483 0.0472346 -0.00878517 -0.0606534 -0.013356 0.0430886 -0.059584 -0.0130099 0.0451278 -0.0594885 -0.0129987 0.045056 -0.0594019 -0.0129345 0.0449808 -0.0579606 -0.0126601 0.0467653 -0.0579426 -0.0125453 0.0467513 -0.0593502 -0.0128284 0.0449235 -0.0593419 -0.0127149 0.0448963 -0.0733829 0.0460108 -0.008785 -0.0733723 0.0460068 -0.00866551 -0.0736761 0.0453047 -0.00897134 -0.0735128 0.0453047 -0.00878825 -0.0730635 0.0466707 -0.00890148 -0.0734437 0.0460337 -0.00889926 -0.073229 0.0468158 -0.00899756 -0.0735441 0.0460717 -0.00897477 -0.0606533 -0.0132413 0.0430441 -0.0608749 -0.0133741 0.0427192 -0.0607037 -0.013462 0.0431642 -0.0607968 -0.0135203 0.0432506 -0.0613415 -0.0137907 0.0426913 -0.0612888 -0.0137985 0.0426596 -0.0735007 0.0453047 -0.0086634 -0.0735113 0.0453047 -0.0087834 -0.0735749 0.0452287 -0.00889725 -0.0735749 0.0453047 -0.00889725 -0.0622827 -0.0147496 0.0406195 -0.061716 -0.0140254 0.0414522 -0.0622954 -0.0146427 0.0405463 -0.0610897 -0.0136351 0.0424494 -0.0611399 -0.0137389 0.0425317 -0.0612351 -0.0137937 0.0426213 -0.0611829 -0.0137734 0.0425767 -0.0624328 -0.0148932 0.040823 -0.0729768 0.0400873 -0.0125445 -0.0730417 0.0401866 -0.0125864 -0.0733706 0.0419651 -0.00973211 -0.0732149 0.0408437 -0.011032 -0.0732792 0.0409298 -0.0111027 -0.073446 0.042098 -0.00992212 -0.0735518 0.0421362 -0.00998769 -0.0733838 0.0409827 -0.0111557 -0.0734688 0.0435099 -0.00893777 -0.0734794 0.0435467 -0.00905101 -0.073382 0.0420346 -0.00982798 -0.0735128 0.0452287 -0.00878825 -0.0736761 0.0452287 -0.00897134 -0.0735432 0.0435802 -0.00916036 -0.0736496 0.0436003 -0.00923401 -0.0622981 -0.0148026 0.0406694 -0.0623302 -0.014847 0.0407234 -0.0623768 -0.0148779 0.0407762 -0.062492 -0.0148934 0.0408605 -0.0687387 0.0323258 -0.0278627 -0.0700943 0.0347748 -0.0243855 -0.0687958 0.0324179 -0.0279507 -0.0701987 0.0348284 -0.0244533 -0.0703144 0.0348326 -0.0244949 -0.0711751 0.0366675 -0.0205239 -0.0700348 0.0346807 -0.0243081 -0.0713496 0.0369262 -0.020705 -0.0711843 0.0367732 -0.0205805 -0.0721714 0.0385852 -0.0166662 -0.0712459 0.0368692 -0.0206468 -0.0724511 0.0387554 -0.0167992 -0.0721583 0.0384782 -0.016619 -0.0722348 0.0386829 -0.0167208 -0.0731443 0.0402494 -0.0126231 -0.0732563 0.0402653 -0.0126467 -0.072338 0.0387429 -0.0167687 -0.0643613 -0.0184679 0.0379445 -0.0637452 -0.017089 0.0387181 -0.0636839 -0.0170805 0.0386704 -0.0636014 -0.0170254 0.0385442 -0.064114 -0.0184611 0.0377902 -0.0640814 -0.0184353 0.0377188 -0.0635888 -0.0169845 0.0384789 -0.0636137 -0.0168994 0.0383728 -0.0638729 -0.0170725 0.038769 -0.0631312 -0.0158756 0.039721 -0.0630724 -0.0158637 0.0396732 -0.063634 -0.0170587 0.0386105 -0.0630241 -0.0158367 0.0396163 -0.0629926 -0.0157981 0.0395577 -0.0629782 -0.0157484 0.0394981 -0.0662928 -0.0252392 0.0336583 -0.0651669 -0.0219733 0.0358694 -0.0640702 -0.0184033 0.0376468 -0.0642288 -0.0184831 0.0379006 -0.0654087 -0.0219868 0.0360201 -0.065507 -0.0222908 0.0358327 -0.066755 -0.0258761 0.0333348 -0.0680301 -0.0295993 0.029538 -0.0685811 -0.0309976 0.0282678 -0.0674063 -0.0281947 0.0310487 -0.0659843 -0.0243142 0.0339891 -0.06512 -0.0219068 0.0357357 -0.0687441 -0.0311271 0.0284513 -0.0674592 -0.0282747 0.0311607 -0.0662428 -0.0251654 0.0335351 -0.0641652 -0.0184774 0.0378529 -0.0652796 -0.0220009 0.0359745 -0.0664035 -0.0252725 0.033757 -0.0675681 -0.0283135 0.0312522 -0.0690183 0.0324676 -0.0280734 -0.068901 0.0324678 -0.0280276 -0.0646477 0.0288752 -0.0367388 -0.0648412 0.0289539 -0.0368564 -0.0647402 0.0289397 -0.0367989 -0.0677231 0.0307912 -0.0308282 -0.0663319 0.0296192 -0.0337786 -0.0662342 0.0295584 -0.0337119 -0.0628473 0.0285645 -0.0396919 -0.0676209 0.0307354 -0.0307559 -0.0675632 0.0306356 -0.0306816 -0.06459 0.0287711 -0.0366922 -0.0661765 0.0294548 -0.0336518 -0.0675597 0.0305248 -0.0306258 -0.0715546 -0.0369226 0.0204287 -0.0720769 -0.0382703 0.0169836 -0.0716298 -0.0373896 0.0188304 -0.0739683 -0.041591 0.00711921 -0.0740812 -0.0419835 0.00400839 -0.0739794 -0.0419171 0.00399673 -0.0740837 -0.0421075 2.44063e-06 -0.0737765 -0.0414221 0.0079307 -0.0736084 -0.0412561 0.00788145 -0.0739128 -0.0418156 0.00398356 -0.0731842 -0.0404445 0.0117047 -0.0736745 -0.0413569 0.00790761 -0.073119 -0.040345 0.0116658 -0.0735892 -0.0411465 0.00785845 -0.0730363 -0.0398358 0.0139164 -0.0732866 -0.0405079 0.011739 -0.0725213 -0.0391863 0.0153917 -0.0724574 -0.0390884 0.0153401 -0.073102 -0.0402365 0.0116317 -0.0719204 -0.0376573 0.0190399 -0.0718062 -0.0376478 0.0190059 -0.0726244 -0.039247 0.0154367 -0.0716401 -0.0374948 0.0188862 -0.0706999 -0.0355057 0.0221552 -0.0717024 -0.0375904 0.0189504 -0.0709869 -0.03576 0.0224018 -0.070871 -0.0357547 0.0223632 -0.0707662 -0.0357013 0.0222978 -0.0696791 -0.0334433 0.0253465 -0.0696781 -0.0333438 0.0252707 -0.0707058 -0.0356084 0.0222213 -0.0697373 -0.0335327 0.025435 -0.0698432 -0.0335817 0.0255097 -0.0686368 -0.0310829 0.0283681 -0.055252 0.0284536 -0.0500107 -0.0545826 0.0287537 -0.0512193 -0.0508546 0.0285647 -0.0546754 -0.0509012 0.0286666 -0.0547236 -0.046107 0.0286667 -0.0589894 -0.0461715 0.0287335 -0.0590682 -0.05084 0.0284541 -0.05466 -0.055268 0.0285644 -0.0500246 -0.0553187 0.0286664 -0.0500688 -0.0553959 0.0287331 -0.0501361 -0.0509723 0.0287333 -0.0547969 -0.0592585 0.0284534 -0.0450053 -0.0592756 0.0285643 -0.0450179 -0.05933 0.0286663 -0.0450577 -0.0594127 0.028733 -0.0451184 -0.0629047 0.0286664 -0.039727 -0.0629921 0.0287331 -0.0397803 -0.0615371 0.0287541 -0.0422694 -0.0595023 0.0287534 -0.0451841 -0.0740169 -0.0420058 2.44063e-06 -0.0741854 -0.0421743 2.44063e-06 -0.0741918 -0.042004 -0.00401125 -0.0740812 -0.0419835 -0.00400351 -0.0738876 -0.0414411 -0.00794099 -0.0737765 -0.0414221 -0.00792582 -0.0738922 -0.0417054 -0.00396707 -0.0733985 -0.0405246 -0.0117563 -0.0732866 -0.0405079 -0.0117341 -0.0727372 -0.0392604 -0.0154603 -0.0718062 -0.0376478 -0.019001 -0.0719204 -0.0376573 -0.019035 -0.070871 -0.0357547 -0.0223583 -0.0709869 -0.03576 -0.0223969 -0.0704192 -0.0345681 -0.0241964 -0.0698432 -0.0335817 -0.0255048 -0.0731842 -0.0404445 -0.0116999 -0.0726244 -0.039247 -0.0154319 -0.0725213 -0.0391863 -0.0153868 -0.0717024 -0.0375904 -0.0189455 -0.0707662 -0.0357013 -0.022293 -0.0739128 -0.0418156 -0.00397868 -0.0739794 -0.0419171 -0.00399185 -0.0736745 -0.0413569 -0.00790273 -0.0736084 -0.0412561 -0.00787657 -0.073119 -0.040345 -0.0116609 -0.0724574 -0.0390884 -0.0153352 -0.0707058 -0.0356084 -0.0222164 -0.0696781 -0.0333438 -0.0252658 -0.0716298 -0.0373896 -0.0188255 -0.0720769 -0.0382703 -0.0169787 -0.0716401 -0.0374948 -0.0188813 -0.073102 -0.0402365 -0.0116268 -0.0685811 -0.0309976 -0.028263 -0.0687122 -0.0311928 -0.0278579 -0.0696791 -0.0334432 -0.0253417 -0.0697373 -0.0335327 -0.0254301 -0.0688643 -0.0311235 -0.0284911 -0.069961 -0.0335825 -0.025547 -0.0440149 0.0285657 -0.0648785 -0.0440808 0.0286678 -0.0648637 -0.0448824 0.0285658 -0.0668971 -0.0441028 0.0287342 -0.0627125 -0.044181 0.0287344 -0.0648412 -0.0439133 0.0284545 -0.0626843 -0.0439344 0.0285656 -0.0626875 -0.0447084 0.0286676 -0.0606476 -0.0440013 0.0286676 -0.0626974 -0.0446513 0.0287543 -0.0612257 -0.0442101 0.0287545 -0.0627284 -0.044631 0.0284544 -0.0606037 -0.0446496 0.0285655 -0.0606142 -0.0460647 0.028565 -0.0589376 -0.0447977 0.0287341 -0.0606984 -0.0686368 -0.0310829 -0.0283632 -0.064114 -0.0184611 -0.0377854 -0.0641652 -0.0184774 -0.037848 -0.0651436 -0.0218304 -0.0356187 -0.0640702 -0.0184033 -0.0376419 -0.0646191 -0.020143 -0.0365917 -0.0682869 -0.0297642 -0.0299088 -0.0687441 -0.0311271 -0.0284465 -0.0664035 -0.0252725 -0.0337521 -0.0652796 -0.0220009 -0.0359696 -0.0674592 -0.0282747 -0.0311558 -0.0662928 -0.0252392 -0.0336534 -0.0675681 -0.0283135 -0.0312473 -0.0662433 -0.0244616 -0.0343815 -0.06512 -0.0219068 -0.0357309 -0.0651669 -0.0219733 -0.0358645 -0.0662428 -0.0251654 -0.0335302 -0.0674063 -0.0281946 -0.0310438 -0.0476004 0.0287336 -0.0706481 -0.0475158 0.0286668 -0.0707047 -0.0450238 0.0287344 -0.0668023 -0.0449385 0.0286678 -0.0668594 -0.0474602 0.0285651 -0.0707418 -0.0461537 0.0284557 -0.0688312 -0.0636146 -0.0169016 -0.0383663 -0.0640814 -0.0184353 -0.0377139 -0.0636349 -0.0170609 -0.0386041 -0.0636848 -0.0170826 -0.038664 -0.0637461 -0.0170912 -0.0387117 -0.0642288 -0.0184831 -0.0378957 -0.0638738 -0.0170746 -0.0387626 -0.0635896 -0.0169867 -0.0384725 -0.0629948 -0.0158018 -0.0395492 -0.0636023 -0.0170276 -0.0385379 -0.0630273 -0.0158412 -0.0396093 -0.0630756 -0.0158677 -0.0396657 -0.0631342 -0.0158793 -0.0397131 -0.0632561 -0.0158639 -0.0397711 -0.0477789 0.0284109 -0.0712548 -0.0476921 0.0287546 -0.0705867 -0.0481432 0.0283869 -0.0717602 -0.0625518 -0.0148846 -0.0408787 -0.0622852 -0.0147527 -0.0406106 -0.062661 -0.0151253 -0.0399547 -0.0629805 -0.015754 -0.0394916 -0.0623793 -0.014881 -0.0407673 -0.0624353 -0.0148962 -0.0408142 -0.0484049 0.0285687 -0.0716495 -0.0483099 0.0285485 -0.0717061 -0.0486414 0.0281765 -0.0723831 -0.0485599 0.0280861 -0.0723816 -0.0482148 0.0284845 -0.071747 -0.0622979 -0.0146458 -0.0405373 -0.0610953 -0.0135211 -0.0423876 -0.06111 -0.0136916 -0.0424775 -0.0623006 -0.0148057 -0.0406605 -0.0611419 -0.0137399 -0.0425215 -0.0611858 -0.0137754 -0.0425676 -0.0623328 -0.01485 -0.0407145 -0.0612374 -0.0137955 -0.0426117 -0.0612917 -0.0138005 -0.0426505 -0.0624946 -0.0148965 -0.0408517 -0.0488401 0.0282546 -0.0722983 -0.0490762 0.0280059 -0.0726503 -0.048743 0.0282359 -0.0723518 -0.0490566 0.0276915 -0.0730023 -0.0485141 0.027988 -0.0723512 -0.0611261 -0.0136517 -0.0429965 -0.0609037 -0.0135226 -0.0433131 -0.0608003 -0.0135221 -0.043242 -0.0610922 -0.0136351 -0.042439 -0.0608778 -0.013376 -0.04271 -0.0492635 0.0277599 -0.0729297 -0.0491644 0.0277435 -0.0729803 -0.04939 0.0271078 -0.0734995 -0.0492912 0.0270421 -0.0734723 -0.0489655 0.0276122 -0.0729866 -0.0492268 0.0269707 -0.073414 -0.0593518 -0.0128288 -0.0449165 -0.0606568 -0.0133597 -0.0430806 -0.0607774 -0.0134553 -0.0434914 -0.0594901 -0.0129991 -0.045049 -0.0607075 -0.0134647 -0.0431561 -0.0594035 -0.0129349 -0.0449738 -0.0497791 0.0264351 -0.0738971 -0.049503 0.027151 -0.0734852 -0.0497753 -0.0128453 -0.0560802 -0.0579743 -0.0126953 -0.0467711 -0.0537188 -0.0128051 -0.0519367 -0.0580609 -0.0128051 -0.0468385 -0.0580916 -0.012824 -0.0468624 -0.0573337 -0.0125453 -0.047518 -0.0579426 -0.0125453 -0.0467464 -0.0579586 -0.0126538 -0.0467588 -0.0536384 -0.0126953 -0.0518619 -0.0496734 -0.0128051 -0.0559701 -0.0495988 -0.0126953 -0.0558895 -0.0461463 -0.0128051 -0.0590374 -0.0495715 -0.0125453 -0.05586 -0.0460658 -0.0126601 -0.058939 -0.0497439 0.0255732 -0.0741487 -0.0496621 0.0264025 -0.0739053 -0.0495571 0.026353 -0.0738688 -0.0497536 0.0249053 -0.0741997 -0.050198 0.0242547 -0.0743238 -0.0500779 0.0256317 -0.0741443 -0.0499715 0.0242547 -0.0743686 -0.0499743 0.0256252 -0.0741894 -0.0498536 0.0256045 -0.0741928 -0.0448837 -0.0126601 -0.0668962 -0.0439131 -0.0125453 -0.0626856 -0.0446309 -0.0125453 -0.0606039 -0.0446508 -0.0126601 -0.0606151 -0.044017 -0.0126601 -0.0648811 -0.0439357 -0.0126601 -0.062689 -0.0440804 -0.0127575 -0.0648668 -0.0447073 -0.0127575 -0.0606473 -0.0460768 -0.0126953 -0.0589524 -0.046107 -0.0127575 -0.0589893 -0.0450185 -0.0128225 -0.0668058 -0.044 -0.0127575 -0.0626985 -0.0451139 -0.0128453 -0.0667419 -0.0450293 -0.0128275 -0.0667986 -0.0447919 -0.0128225 -0.0606953 -0.0448918 -0.0128453 -0.060752 -0.0440963 -0.0128225 -0.0627128 -0.0441754 -0.0128225 -0.0648454 -0.0501966 0.00566593 -0.0743309 -0.049859 0.0242547 -0.0743204 -0.0500939 0.0242547 -0.0743679 -0.0499718 -0.0083505 -0.0743722 -0.0497845 -0.00835024 -0.0742458 -0.0449377 -0.0127575 -0.06686 -0.0474622 -0.0126538 -0.0707461 -0.0476023 -0.012824 -0.0706522 -0.0483418 -0.0122247 -0.0720943 -0.0496776 -0.00999726 -0.0740505 -0.0496058 -0.00995608 -0.0739792 -0.049158 -0.0113921 -0.0732757 -0.0490991 -0.011316 -0.0732236 -0.0500929 -0.00835056 -0.0743728 -0.0499023 -0.0100624 -0.0740886 -0.0497841 -0.0100363 -0.0740924 -0.0492526 -0.0114643 -0.0732991 -0.0493628 -0.0115122 -0.0732829 -0.0484581 -0.0124189 -0.0721133 -0.0485566 -0.0124815 -0.0720785 -0.0476946 -0.0128453 -0.0705904 -0.0497657 -0.00887871 -0.0742176 -0.0498609 -0.0083504 -0.0743239 -0.0483815 -0.0123244 -0.0721174 -0.0475175 -0.0127564 -0.0707091 -0.0694572 -0.0128453 0.0267584 -0.0692149 -0.0127729 0.0274596 -0.0870201 -0.0129876 0.02734 -0.0967958 -0.0128453 -0.0338634 -0.0663793 -0.0128453 -0.0338634 -0.0739851 -0.0127315 -0.0276258 -0.0692149 -0.0127729 -0.0274548 -0.0664202 -0.0124801 -0.0330966 -0.0661104 -0.0125453 -0.0337304 -0.0666903 -0.0127736 -0.0331656 -0.0665955 -0.0127459 -0.0331256 -0.0665073 -0.0126789 -0.0330971 -0.0669845 -0.0125556 -0.0324899 -0.0668931 -0.0125241 -0.0324606 -0.0673179 -0.0121183 -0.0313621 -0.0668074 -0.0124603 -0.0324483 -0.0667444 -0.0123736 -0.0324569 -0.0672557 -0.0120223 -0.0313541 -0.0674073 -0.0121852 -0.0313883 -0.0680203 -0.0120954 -0.0303194 -0.067919 -0.0120742 -0.0302757 -0.0687625 -0.0124914 -0.0280144 -0.0687037 -0.0123915 -0.0279471 -0.067745 -0.0117954 -0.030201 -0.0677644 -0.0119057 -0.0302091 -0.0682537 -0.012029 -0.0290565 -0.0678257 -0.0120074 -0.0302354 -0.0683139 -0.0121322 -0.0291029 -0.0684114 -0.012196 -0.0291564 -0.0685181 -0.0122096 -0.0292033 -0.0691762 -0.0125453 -0.0266485 -0.0689348 -0.0124794 -0.0272854 -0.0692139 -0.0126953 -0.0266625 -0.0691073 -0.0127589 -0.0274105 -0.0690091 -0.012695 -0.0273593 -0.0688641 -0.0125493 -0.02808 -0.0689764 -0.0125556 -0.028127 -0.0691762 -0.0125453 0.0266533 -0.0689348 -0.0124794 0.0272903 -0.0688634 -0.0125491 0.0280845 -0.0690091 -0.012695 0.0273642 -0.0692585 -0.0127575 0.0266841 -0.0691073 -0.0127589 0.0274153 -0.0693497 -0.0128225 0.0267182 -0.068236 -0.0119135 0.029044 -0.0681736 -0.0119896 0.0292516 -0.068278 -0.0120402 0.0290004 -0.068315 -0.0120612 0.028911 -0.068337 -0.0120745 0.0288575 -0.0687031 -0.0123895 0.0279509 -0.0681848 -0.0119944 0.0292247 -0.068166 -0.0119864 0.0292696 -0.0681585 -0.0119833 0.0292876 -0.0687615 -0.0124904 0.0280185 -0.0683662 -0.012093 0.0287863 -0.0684815 -0.0121766 0.0285037 -0.0683223 -0.0120655 0.0288931 -0.0683076 -0.0120569 0.0289288 -0.0682928 -0.0120484 0.0289646 -0.0682483 -0.0120246 0.0290721 -0.0681885 -0.0119961 0.0292157 -0.0681811 -0.0119928 0.0292337 -0.0681284 -0.0119715 0.0293594 -0.0680071 -0.0119338 0.0296467 -0.0678213 -0.0120063 0.0302476 -0.0677603 -0.0119037 0.0302215 -0.0672259 -0.0119208 0.0313789 -0.0673129 -0.0121188 0.0313759 -0.0667435 -0.0123719 0.0324621 -0.0668065 -0.0124594 0.0324532 -0.0683082 -0.0121287 0.0291184 -0.0684059 -0.0121933 0.0291721 -0.0680253 -0.0120953 0.0303133 -0.067915 -0.0120739 0.0302879 -0.0680169 -0.0120954 0.0303319 -0.0674026 -0.0121864 0.0314021 -0.0669845 -0.0125556 0.0324948 -0.0664202 -0.0124801 0.0331015 -0.0661892 -0.0127575 0.0337742 -0.0662764 -0.0128225 0.0338174 -0.0665073 -0.0126789 0.033102 -0.0665955 -0.0127459 0.0331305 -0.0668926 -0.0125238 0.0324654 -0.0666903 -0.0127736 0.0331705 -0.0739088 0.0552119 -0.00325997 -0.0734137 0.0551797 -0.00868428 -0.0733678 0.0548653 -0.00323746 -0.0729509 0.0548653 -0.00867395 -0.0727559 0.0546265 -0.00866957 -0.0725732 0.0542338 -0.00866545 -0.0725733 0.0542357 0.00867033 -0.0727573 0.0546286 0.00867448 -0.0733678 0.0548653 0.00324234 -0.0734341 0.0551884 0.00868936 -0.0744275 0.0553047 0.00328643 -0.0740264 0.0553047 0.00860244 -0.0739088 0.0552119 0.00326485 -0.0730214 0.0543238 -0.00322306 -0.0730214 0.0543238 0.00322794 -0.0735328 0.0549047 0.00900244 -0.0725098 0.0538047 0.0086689 -0.0725841 0.0542324 0.00878987 -0.0726029 0.0543239 0.008671 -0.0730455 0.0549514 0.00868095 -0.073055 0.0549401 0.00879782 -0.0734137 0.0551797 0.00868916 -0.0726463 0.0542136 0.00890419 -0.0727679 0.0546216 0.00879299 -0.0727491 0.0541826 0.00897969 -0.0729115 0.0545266 0.00898002 -0.0728224 0.0545856 0.00890571 -0.0730974 0.0548895 0.00890807 -0.0731654 0.0548083 0.00898054 -0.0734471 0.0551025 0.00891102 -0.0734887 0.0550064 0.00898119 -0.0738864 0.055294 0.00868731 -0.0737613 0.0552385 0.00881981 -0.0737307 0.0552728 0.00871577 -0.0734206 0.0551637 0.00880389 -0.0735581 0.0550865 0.00895246 -0.0735106 0.0549559 0.00899719 -0.0737775 0.0552075 0.00886373 -0.073755 0.0551888 0.00888399 -0.0736942 0.0551992 0.00886917 -0.0736779 0.0551115 0.00894481 -0.0735757 0.0550444 0.00897593 -0.0736265 0.055149 0.00891409 -0.0736003 0.0552006 0.00884668 -0.0735253 0.0551579 0.008881 -0.0735788 0.0552302 0.0087657 -0.0737454 0.0552607 0.00876964 -0.0737179 0.0552743 0.00866116 -0.0734206 0.0551637 -0.00879901 -0.0730439 0.0549506 -0.00867603 -0.0734471 0.0551025 -0.00890613 -0.0730534 0.0549393 -0.00879291 -0.0730958 0.0548887 -0.00890316 -0.073466 0.0550589 -0.00894605 -0.0731639 0.0548076 -0.00897564 -0.0727664 0.0546195 -0.00878808 -0.072584 0.0542306 -0.00878498 -0.072821 0.0545835 -0.00890081 -0.0729102 0.0545247 -0.00897513 -0.0730746 0.0545568 -0.00899756 -0.072857 0.0541434 -0.00899756 -0.072749 0.054181 -0.0089748 -0.0726461 0.054212 -0.00889929 -0.0725842 0.0538047 -0.00889748 -0.0725098 0.0538047 -0.00866402 -0.0737179 0.0552743 -0.00865628 -0.0739012 0.0552804 -0.00873508 -0.0735328 0.0549047 -0.00899756 -0.0736244 0.0550451 -0.00897218 -0.0734887 0.0550064 -0.00897629 -0.0735106 0.0549559 -0.00899231 -0.0735581 0.0550865 -0.00894758 -0.0735757 0.0550444 -0.00897105 -0.0735646 0.0549575 -0.00899415 -0.0736131 0.0551772 -0.00887779 -0.0737613 0.0552385 -0.00881493 -0.073797 0.0552223 -0.00884069 -0.0738864 0.055294 -0.00868243 -0.0737192 0.0551555 -0.00890917 -0.0737695 0.055224 -0.0088378 -0.0736403 0.0551172 -0.00893526 -0.0736265 0.055149 -0.0089092 -0.0737454 0.0552607 -0.00876476 -0.0737307 0.0552728 -0.00871089 -0.0736003 0.0552006 -0.0088418 -0.0735788 0.0552302 -0.00876082 -0.104996 0.0328656 0.0175024 -0.104996 0.0325239 0.0162274 -0.106496 0.0328656 0.0175024 -0.106496 0.0315905 0.0152941 -0.106496 0.0303155 0.0149524 -0.104996 0.0281072 0.0162274 -0.106496 0.0281072 0.0162274 -0.106496 0.0277655 0.0175024 -0.104996 0.0281072 0.0187774 -0.104996 0.0290405 0.0197108 -0.106496 0.0290405 0.0197108 -0.104996 0.0315905 0.0197108 -0.104996 0.0325239 0.0187774 -0.104996 0.019713 0.0290383 -0.104996 0.0187797 0.028105 -0.106496 0.0187797 0.028105 -0.104996 0.0162297 0.028105 -0.104996 0.0152963 0.0290383 -0.104996 0.0152963 0.0315883 -0.106496 0.0149547 0.0303133 -0.104996 0.0187797 0.0325217 -0.106496 0.0187797 0.0325217 -0.104996 0.019713 0.0315883 -0.104996 0.0200547 0.0303133 -0.104996 0.00221302 0.0337274 -0.106496 0.00255466 0.0350024 -0.104996 -0.00127034 0.0327941 -0.106496 4.65996e-06 0.0324524 -0.104996 -0.0022037 0.0337274 -0.106496 -0.0022037 0.0337274 -0.106496 -0.00254534 0.0350024 -0.104996 -0.0022037 0.0362774 -0.104996 -0.00127034 0.0372108 -0.106496 -0.00127034 0.0372108 -0.104996 4.65996e-06 0.0375524 -0.104996 0.00221302 0.0362774 -0.106496 0.00221302 0.0362774 -0.106496 -0.0149453 0.0303133 -0.106496 -0.015287 0.0290383 -0.104996 -0.0162203 0.028105 -0.106496 -0.0162203 0.028105 -0.106496 -0.0187703 0.028105 -0.106496 -0.0200453 0.0303133 -0.104996 -0.0197037 0.0315883 -0.106496 -0.0187703 0.0325217 -0.104996 -0.0187703 0.0325217 -0.104996 -0.0149453 0.0303133 -0.104996 -0.0280979 0.0162274 -0.106496 -0.0280979 0.0162274 -0.104996 -0.0303062 0.0149524 -0.106496 -0.0290312 0.0152941 -0.106496 -0.0303062 0.0149524 -0.104996 -0.0315812 0.0152941 -0.106496 -0.0325146 0.0162274 -0.104996 -0.0325146 0.0187774 -0.104996 -0.0315812 0.0197108 -0.106496 -0.0315812 0.0197108 -0.106496 -0.0280979 0.0187774 -0.106496 -0.0277562 0.0175024 -0.106496 -0.0324453 2.44063e-06 -0.104996 -0.032787 -0.00127256 -0.104996 -0.0337203 -0.00220592 -0.104996 -0.0349953 -0.00254756 -0.106496 -0.0349953 -0.00254756 -0.106496 -0.0372037 -0.00127256 -0.104996 -0.0375453 2.44063e-06 -0.104996 -0.0362703 0.00221081 -0.106496 -0.0362703 0.00221081 -0.104996 -0.0349953 0.00255244 -0.104996 -0.0337203 0.00221081 -0.104996 -0.032787 0.00127744 -0.106496 -0.032787 0.00127744 -0.106496 -0.0280979 -0.0187726 -0.104996 -0.0290312 -0.0197059 -0.104996 -0.0303062 -0.0200476 -0.104996 -0.0328562 -0.0174976 -0.106496 -0.0325146 -0.0187726 -0.106496 -0.0328562 -0.0174976 -0.106496 -0.0325146 -0.0162226 -0.104996 -0.0315812 -0.0152892 -0.104996 -0.0290312 -0.0152892 -0.106496 -0.0277562 -0.0174976 -0.104996 -0.0162203 -0.0325168 -0.106496 -0.015287 -0.0315834 -0.104996 -0.0174953 -0.0328584 -0.106496 -0.0162203 -0.0325168 -0.106496 -0.0174953 -0.0328584 -0.106496 -0.0197037 -0.0315834 -0.104996 -0.0197037 -0.0315834 -0.104996 -0.0200453 -0.0303084 -0.106496 -0.0200453 -0.0303084 -0.104996 -0.0197037 -0.0290334 -0.104996 -0.0187703 -0.0281001 -0.106496 -0.0197037 -0.0290334 -0.106496 -0.0187703 -0.0281001 -0.106496 -0.0174953 -0.0277584 -0.104996 -0.015287 -0.0290334 -0.106496 0.00221302 -0.0362726 -0.106496 0.00127966 -0.0372059 -0.104996 4.65996e-06 -0.0375476 -0.106496 4.65996e-06 -0.0375476 -0.104996 -0.0022037 -0.0362726 -0.106496 -0.0022037 -0.0362726 -0.104996 -0.00254534 -0.0349976 -0.104996 -0.0022037 -0.0337226 -0.106496 -0.00254534 -0.0349976 -0.106496 0.00127966 -0.0327892 -0.104996 0.00255466 -0.0349976 -0.104996 0.0200547 -0.0303084 -0.106496 0.0200547 -0.0303084 -0.106496 0.019713 -0.0315834 -0.104996 0.0187797 -0.0325168 -0.106496 0.0187797 -0.0325168 -0.104996 0.0175047 -0.0328584 -0.106496 0.0175047 -0.0328584 -0.104996 0.0162297 -0.0325168 -0.106496 0.0162297 -0.0325168 -0.104996 0.0152963 -0.0315834 -0.106496 0.0152963 -0.0315834 -0.104996 0.0152963 -0.0290334 -0.106496 0.0152963 -0.0290334 -0.104996 0.0162297 -0.0281001 -0.104996 0.0175047 -0.0277584 -0.104996 0.0187797 -0.0281001 -0.106496 0.019713 -0.0290334 -0.106496 0.0328656 -0.0174976 -0.106496 0.0315905 -0.0197059 -0.104996 0.0281072 -0.0162226 -0.104996 0.0303155 -0.0149476 -0.104996 0.0328656 -0.0174976 -0.104996 0.0375547 2.44063e-06 -0.106496 0.0375547 2.44063e-06 -0.104996 0.0350047 -0.00254756 -0.106496 0.0350047 -0.00254756 -0.106496 0.0337297 -0.00220592 -0.104996 0.0327963 -0.00127256 -0.106496 0.0327963 -0.00127256 -0.104996 0.0327963 0.00127744 -0.106496 0.0324547 2.44063e-06 -0.104996 0.0350047 0.00255244 -0.106496 0.0337297 0.00221081 -0.0694755 0.0289741 -0.03939 -0.069018 0.0289541 -0.0398476 -0.0659356 0.0287872 -0.0387335 -0.0742273 0.02881 -0.0398941 -0.0711831 0.0289782 -0.0398476 -0.0709844 0.0289844 -0.0395887 -0.0705034 0.0289889 -0.0392893 -0.069593 0.0291282 -0.0361002 -0.0674144 0.0289882 -0.036798 -0.0705832 0.0288214 -0.0447106 -0.0711831 0.0289374 -0.0410976 -0.0688505 0.0289318 -0.0404726 -0.0657324 0.0287945 -0.0411973 -0.069018 0.0289133 -0.0410976 -0.0692167 0.028907 -0.0413564 -0.0669839 0.0288693 -0.0435277 -0.0680708 0.0288978 -0.0443025 -0.069777 0.0289027 -0.04168 -0.0985958 -0.0248606 -0.056391 -0.0985958 -0.0267038 -0.0486019 -0.0985958 -0.0278351 -0.0488985 -0.0985958 -0.0286919 -0.0496946 -0.0985958 -0.0255666 -0.0488752 -0.0985958 -0.0195452 -0.0556787 -0.0985958 -0.0299212 -0.0558999 -0.0985958 -0.0287653 -0.0563077 -0.0985958 -0.0190955 -0.0520023 -0.0985958 -0.0199667 -0.0514179 -0.0985958 -0.0185567 -0.0529025 -0.0985958 -0.0184534 -0.0539466 -0.0878658 -0.0299212 -0.0558999 -0.0878658 -0.030725 -0.0549745 -0.0985958 -0.030725 -0.0549745 -0.0878658 -0.0309671 -0.0537728 -0.0985958 -0.0309671 -0.0537728 -0.0878658 -0.0305841 -0.0526084 -0.0985958 -0.0305841 -0.0526084 -0.0878658 -0.0267038 -0.0486019 -0.0878658 -0.0255666 -0.0488752 -0.0878658 -0.0286919 -0.0496946 -0.0878658 -0.0199667 -0.0514179 -0.0985958 -0.0205317 -0.0560358 -0.0878658 -0.0287653 -0.0563077 -0.0878658 -0.0190955 -0.0520023 -0.0878658 -0.0185567 -0.0529025 -0.0878658 -0.0184534 -0.0539466 -0.0878658 -0.0188053 -0.0549349 -0.0985958 -0.0188053 -0.0549349 -0.0878658 -0.0195452 -0.0556787 -0.0878658 -0.0205317 -0.0560358 -0.0878658 -0.0248606 -0.056391 -0.0878658 -0.0278351 -0.0488985 -0.0985958 -0.0252754 0.0459462 -0.0985958 -0.0248184 0.0468018 -0.0985958 -0.0253564 0.0449796 -0.0985958 -0.022154 0.0378338 -0.0985958 -0.0234523 0.0395986 -0.0985958 -0.0187306 0.038484 -0.0985958 -0.016043 0.0404489 -0.0985958 -0.0142113 0.0432197 -0.0985958 -0.0144379 0.0501711 -0.0985958 -0.0137078 0.0493185 -0.0985958 -0.0154759 0.0505985 -0.0985958 -0.0165947 0.0505071 -0.0985958 -0.02406 0.0474066 -0.0985958 -0.0134453 0.0482271 -0.0878658 -0.0234523 0.0395986 -0.0878658 -0.0250482 0.0440599 -0.0878658 -0.0252754 0.0459462 -0.0878658 -0.0248184 0.0468018 -0.0878658 -0.02406 0.0474066 -0.0878658 -0.0142113 0.0432197 -0.0878658 -0.0134453 0.0482271 -0.0878658 -0.0134453 0.0469356 -0.0878658 -0.0210555 0.0375818 -0.0878658 -0.022154 0.0378338 -0.0878658 -0.0187306 0.038484 -0.0985958 -0.0193491 0.0381766 -0.0878658 -0.0193491 0.0381766 -0.0985958 -0.0199632 0.0378589 -0.0985958 -0.0134453 0.0469356 -0.0878658 -0.0134671 0.0462887 -0.0985958 -0.0134671 0.0462887 -0.0878658 -0.016043 0.0404489 -0.0878658 -0.0165947 0.0505071 -0.0878658 -0.0154759 0.0505985 -0.0878658 -0.0144379 0.0501711 -0.0878658 -0.0137078 0.0493185 -0.0878658 -0.0199632 0.0378589 -0.0985958 -0.0210555 0.0375818 -0.0878658 -0.0230162 0.0385594 -0.0985958 -0.0230162 0.0385594 -0.0985958 -0.0250482 0.0440599 -0.0878658 -0.0253564 0.0449796 -0.0878658 -0.0230162 -0.0385545 -0.0878658 -0.0199632 -0.037854 -0.0878658 -0.0234523 -0.0395937 -0.0878658 -0.02406 -0.0474017 -0.0878658 -0.016043 -0.040444 -0.0878658 -0.0142113 -0.0432148 -0.0878658 -0.0134671 -0.0462838 -0.0878658 -0.0154759 -0.0505936 -0.0878658 -0.0134453 -0.0482222 -0.0878658 -0.0165947 -0.0505022 -0.0878658 -0.0193491 -0.0381717 -0.0878658 -0.0187306 -0.0384791 -0.0985958 -0.0187306 -0.0384791 -0.0985958 -0.0134671 -0.0462838 -0.0878658 -0.0134453 -0.0469307 -0.0878658 -0.0137078 -0.0493136 -0.0985958 -0.0137078 -0.0493136 -0.0878658 -0.0144379 -0.0501663 -0.0985958 -0.0144379 -0.0501663 -0.0985958 -0.0154759 -0.0505936 -0.0985958 -0.0230162 -0.0385545 -0.0878658 -0.022154 -0.0378289 -0.0985958 -0.022154 -0.0378289 -0.0878658 -0.0210555 -0.0375769 -0.0985958 -0.0210555 -0.0375769 -0.0878658 -0.0248184 -0.0467969 -0.0878658 -0.0252754 -0.0459413 -0.0985958 -0.0252754 -0.0459413 -0.0878658 -0.0253564 -0.0449747 -0.0985958 -0.0253564 -0.0449747 -0.0878658 -0.0250482 -0.044055 -0.0985958 -0.02406 -0.0474017 -0.0985958 -0.0248184 -0.0467969 -0.0985958 -0.0250482 -0.044055 -0.0985958 -0.0234523 -0.0395937 -0.0985958 -0.0134453 -0.0482222 -0.0985958 -0.0165947 -0.0505022 -0.0985958 -0.016043 -0.040444 -0.0985958 -0.0142113 -0.0432148 -0.0985958 -0.0134453 -0.0469307 -0.0985958 -0.0199632 -0.037854 -0.0985958 -0.0193491 -0.0381717 -0.0878658 -0.0255666 0.0488801 -0.0878658 -0.0248606 0.0563959 -0.0878658 -0.0205317 0.0560407 -0.0878658 -0.030725 0.0549793 -0.0878658 -0.0299212 0.0559048 -0.0878658 -0.0309671 0.0537777 -0.0878658 -0.0287653 0.0563125 -0.0878658 -0.0305841 0.0526133 -0.0878658 -0.0286919 0.0496995 -0.0878658 -0.0190955 0.0520072 -0.0878658 -0.0199667 0.0514228 -0.0985958 -0.0205317 0.0560407 -0.0985958 -0.0195452 0.0556836 -0.0878658 -0.0195452 0.0556836 -0.0878658 -0.0188053 0.0549398 -0.0878658 -0.0184534 0.0539514 -0.0985958 -0.0188053 0.0549398 -0.0985958 -0.0184534 0.0539514 -0.0985958 -0.0185567 0.0529074 -0.0878658 -0.0185567 0.0529074 -0.0985958 -0.0190955 0.0520072 -0.0985958 -0.0248606 0.0563959 -0.0878658 -0.0267038 0.0486068 -0.0985958 -0.0255666 0.0488801 -0.0985958 -0.0267038 0.0486068 -0.0878658 -0.0278351 0.0489034 -0.0985958 -0.0278351 0.0489034 -0.0985958 -0.0286919 0.0496995 -0.0985958 -0.0299212 0.0559048 -0.0985958 -0.0287653 0.0563125 -0.0985958 -0.0199667 0.0514228 -0.0985958 -0.030725 0.0549793 -0.0985958 -0.0309671 0.0537777 -0.0985958 -0.0305841 0.0526133 0.0256671 0.0307587 -0.0289649 0.0361893 0.0307587 -0.0137208 0.0363763 0.0305587 -0.0137917 0.0180819 0.0305587 0.0344467 0.0105377 0.0307587 0.0372414 0.00950143 0.0307587 0.037519 0.017989 0.0307587 0.0342696 0.0257997 0.0305587 0.0291195 0.0256671 0.0307587 0.0289698 0.0386206 0.0305587 0.00469132 0.0318537 0.0307587 0.0219865 0.0320183 0.0305587 0.0221002 0.0363763 0.0305587 0.0137966 0.038422 0.0307587 0.00466721 0.0375208 0.0307587 -0.00949478 0.0386206 0.0305587 -0.00468644 0.038422 0.0307587 -0.00466233 0.0204597 0.0307587 -0.0328497 0.0209767 0.0307587 -0.0325221 0.0257997 0.0305587 -0.0291146 0.0235819 0.0307587 -0.0306861 0.00926573 0.0307587 -0.037573 0.00950143 0.0307587 -0.0375141 0.0105377 0.0307587 -0.0372365 0.00621125 0.0307587 -0.0381965 0.0076966 0.0307587 -0.0379253 0.0269873 0.0307587 -0.0277393 0.0247529 0.0307587 -0.0284813 0.0277459 0.0307587 -0.0269807 0.0279876 0.0307587 -0.0266138 0.0284879 0.0307587 -0.0247463 0.0284879 0.0318087 -0.0247463 0.0279876 0.0318087 -0.0228788 0.0266204 0.0318087 -0.0215117 0.0279876 0.0307587 -0.0228788 0.0247529 0.0318087 -0.0210113 0.0370462 0.0318087 -0.0109237 0.0375466 0.0318087 -0.00905623 0.0375466 0.0307587 -0.00905623 0.0356791 0.0318087 -0.00582162 0.0338116 0.0307587 -0.00532123 0.0375466 0.0307587 0.00906111 0.0370462 0.0318087 0.00719361 0.0372431 0.0307587 0.0105359 0.0356791 0.0318087 0.0122957 0.0283943 0.0318087 0.0239201 0.0283943 0.0307587 0.0255823 0.0276731 0.0307587 0.0224224 0.0276731 0.0318087 0.0224224 0.0247529 0.0307587 0.0210162 0.0266204 0.0318087 0.0215166 0.0247529 0.0318087 0.0210162 0.0283943 0.0318087 0.0255823 0.0277459 0.0307587 0.0269856 0.0269873 0.0307587 0.0277441 0.0266204 0.0318087 0.0279858 0.00906288 0.0307587 0.0300748 0.0106834 0.0318087 0.0304447 0.011983 0.0318087 0.0314811 0.0122975 0.0307587 0.0319423 0.0127979 0.0307587 0.0338098 0.0127979 0.0318087 0.0338098 0.0122975 0.0307587 0.0356773 0.011983 0.0318087 0.0361386 0.0109304 0.0307587 0.0370445 0.0109304 0.0318087 0.0370445 0.0106834 0.0318087 0.037175 -0.00718696 0.0307587 0.0370445 -0.00581985 0.0307587 0.0356773 -0.00581985 0.0318087 0.0356773 -0.00531946 0.0318087 0.0338098 -0.00581985 0.0318087 0.0319423 -0.00905446 0.0307587 0.0300748 -0.0247445 0.0318087 0.0284862 -0.0218244 0.0307587 0.0270799 -0.0211032 0.0318087 0.0255823 -0.023124 0.0318087 0.0213861 -0.0321826 0.0318087 0.0124262 -0.0308831 0.0307587 0.0113898 -0.0308831 0.0318087 0.0113898 -0.0301618 0.0307587 0.00989222 -0.0301618 0.0318087 0.00822999 -0.0301618 0.0307587 0.00822999 -0.0308831 0.0307587 0.00673237 -0.0321826 0.0307587 0.00569599 -0.0321826 0.0318087 0.00569599 -0.0305686 0.0307587 -0.00718873 -0.0300682 0.0307587 -0.00905623 -0.0300682 0.0318087 -0.00905623 -0.0305686 0.0318087 -0.0109237 -0.0319357 0.0318087 -0.0122908 -0.0319357 0.0307587 -0.0122908 -0.022877 0.0318087 -0.0215117 -0.0247445 0.0318087 -0.0210113 -0.0210095 0.0318087 -0.0247463 -0.0211032 0.0307587 -0.0239152 -0.0218244 0.0307587 -0.0224176 -0.0211032 0.0318087 -0.0255774 -0.0218244 0.0318087 -0.027075 -0.0218244 0.0307587 -0.027075 -0.023124 0.0307587 -0.0281114 -0.00613432 0.0307587 -0.0314762 -0.00613432 0.0318087 -0.0314762 -0.0054131 0.0307587 -0.0346361 -0.0054131 0.0318087 -0.0346361 -0.00613432 0.0318087 -0.0361337 -0.0074339 0.0307587 -0.0371701 0.0122975 0.0318087 -0.0356725 0.0122975 0.0307587 -0.0319375 0.0247529 0.0320087 -0.0212113 0.0279876 0.0318087 -0.0266138 0.0278143 0.0320087 -0.0265138 0.0266204 0.0318087 -0.0279809 -0.00459672 0.0307587 0.0279918 -0.00296768 0.0307587 0.0266134 -0.00213594 0.0307587 0.0246482 0.00668091 0.0307587 0.0284868 0.024027 0.0307587 0.0107624 0.0259009 0.0305587 0.0101435 -0.0112485 0.0305587 -0.00940652 -0.0100371 0.0307587 -0.00942967 -0.0314067 0.0307587 0.0155972 -0.0322119 0.0307587 0.0164024 -0.0319567 0.0302087 0.0175024 -0.0317356 0.0302087 0.0183274 -0.0322119 0.0307587 0.0186024 -0.0311317 0.0302087 0.0189314 -0.0314067 0.0307587 0.0194077 -0.0303067 0.0307587 0.0197024 -0.0349958 0.0307587 -0.00219756 -0.0367158 0.0307587 -0.00136924 -0.0366044 0.0302087 0.0003696 -0.0371406 0.0307587 0.000491987 -0.0367158 0.0307587 0.00137412 -0.0357117 0.0302087 0.00148904 -0.0183208 0.0302087 -0.0317374 -0.019401 0.0307587 -0.0314084 -0.0196958 0.0307587 -0.0303084 -0.0191458 0.0302087 -0.0303084 -0.0185958 0.0307587 -0.0284032 -0.00171582 0.0307587 -0.0363692 -0.00160442 0.0302087 -0.0353647 -0.00214063 0.0307587 -0.0354871 -0.00128581 0.0302087 -0.0339688 -0.00171582 0.0307587 -0.0336259 -0.000711698 0.0302087 -0.033511 -0.000950335 0.0307587 -0.0330154 0.0175042 0.0307587 -0.0325084 0.0166792 0.0302087 -0.0317374 0.0158542 0.0302087 -0.0303084 0.015599 0.0307587 -0.0314084 0.0160753 0.0302087 -0.0294834 0.0166792 0.0302087 -0.0288795 0.0175042 0.0307587 -0.0281084 0.0341792 0.0302087 -0.0014265 0.0335753 0.0302087 -0.000822559 0.0333542 0.0302087 2.44063e-06 0.033099 0.0307587 0.00110244 0.0350042 0.0302087 0.00165244 0.0339042 0.0307587 0.0019077 0.0303151 0.0307587 0.0153024 0.0293606 0.0307587 0.0155203 0.0285951 0.0307587 0.0161308 0.0287065 0.0302087 0.0171353 0.0281703 0.0307587 0.0170129 0.0285951 0.0307587 0.0188741 0.0295992 0.0302087 0.018989 0.0293606 0.0307587 0.0194846 0.0303151 0.0302087 0.0191524 0.0303151 0.0307587 0.0197024 0.0175042 0.0307587 0.0281133 0.0167883 0.0302087 0.0288267 0.0162142 0.0302087 0.0292846 0.0157842 0.0307587 0.0289417 0.0162142 0.0302087 0.0313421 -0.0187858 0.0302087 0.0292846 -0.0192158 0.0307587 0.0289417 -0.0191044 0.0302087 0.0299462 -0.0196406 0.0307587 0.0308029 -0.0187858 0.0302087 0.0313421 -0.0184503 0.0307587 0.0322955 0.0338116 0.0320087 -0.00552123 0.0355791 0.0320087 -0.00599483 0.0370462 0.0318087 -0.00718873 0.0356791 0.0318087 -0.0122908 0.0355791 0.0320087 -0.0121176 0.0338116 0.0318087 -0.0127912 0.0338116 0.0320087 0.0125961 0.0355791 0.0320087 0.0121225 0.036873 0.0320087 0.0108286 0.0370462 0.0318087 0.0109286 0.0375466 0.0318087 0.00906111 0.036873 0.0320087 0.00729361 0.0356791 0.0318087 0.0058265 0.0355791 0.0320087 0.00599971 0.0247529 0.0320087 0.0282862 0.0247529 0.0318087 0.0284862 0.0276731 0.0318087 0.0270799 0.0279876 0.0318087 0.0266187 0.0282879 0.0320087 0.0247512 0.0284879 0.0318087 0.0247512 0.0279876 0.0318087 0.0228837 0.0278143 0.0320087 0.0229837 0.0105967 0.0320087 0.0369948 0.0122975 0.0318087 0.0356773 0.0127042 0.0318087 0.034641 0.0127042 0.0318087 0.0329787 0.0118267 0.0320087 0.0316058 0.0122975 0.0318087 0.0319423 0.0109304 0.0318087 0.0305752 0.0105967 0.0320087 0.0306249 0.00906288 0.0318087 0.0300748 0.00906288 0.0320087 0.0302748 -0.00718696 0.0318087 0.0370445 -0.00728696 0.0320087 0.0368712 -0.00599306 0.0320087 0.0355773 -0.00551946 0.0320087 0.0338098 -0.00718696 0.0318087 0.0305752 -0.00728696 0.0320087 0.0307484 -0.00905446 0.0318087 0.0300748 -0.023124 0.0318087 0.0281163 -0.0218244 0.0318087 0.0270799 -0.0211032 0.0318087 0.0239201 -0.0218244 0.0318087 0.0224224 -0.0232107 0.0320087 0.0215663 -0.0338032 0.0320087 0.0125961 -0.0310394 0.0320087 0.0112651 -0.0301618 0.0318087 0.00989222 -0.0303568 0.0320087 0.0082745 -0.0308831 0.0318087 0.00673237 -0.0319357 0.0318087 -0.00582162 -0.0320357 0.0320087 -0.00599483 -0.0305686 0.0318087 -0.00718873 -0.0307418 0.0320087 -0.0108237 -0.022977 0.0320087 -0.0216849 -0.0247445 0.0320087 -0.0212113 -0.0218244 0.0318087 -0.0224176 -0.0212095 0.0320087 -0.0247463 -0.0215099 0.0318087 -0.0228788 -0.0211032 0.0318087 -0.0239152 -0.0215099 0.0318087 -0.0266138 -0.022877 0.0318087 -0.0279809 -0.022977 0.0320087 -0.0278077 -0.0247445 0.0318087 -0.0284813 -0.0247445 0.0320087 -0.0282813 -0.00905446 0.0320087 -0.03027 -0.0074339 0.0318087 -0.0304398 -0.00629068 0.0320087 -0.0316009 -0.0054131 0.0318087 -0.0329738 -0.00560809 0.0320087 -0.0345916 -0.00629068 0.0320087 -0.036009 -0.0074339 0.0318087 -0.0371701 -0.00752068 0.0320087 -0.0369899 0.00906288 0.0318087 -0.03007 0.0109304 0.0318087 -0.0305704 0.00906288 0.0320087 -0.03027 0.0122975 0.0318087 -0.0319375 0.0121243 0.0320087 -0.0320375 0.0127979 0.0318087 -0.033805 0.0121243 0.0320087 -0.0355725 0.0108304 0.0320087 -0.0368664 0.0109304 0.0318087 -0.0370396 -0.0224797 0.0305587 0.0102845 -0.0101083 0.0223087 0.00962142 -0.00911783 0.0223087 0.0102239 -0.00468697 0.0305587 0.0278133 -0.00312876 0.0223087 0.0264948 -0.00312876 0.0305587 0.0264948 -0.00233318 0.0223087 0.0246151 0.0112569 0.0305587 0.00941141 0.0112569 0.0223087 0.00941141 0.0113482 0.0305587 0.00941271 0.00668091 0.0223087 0.0282868 0.00668091 0.0305587 0.0282868 0.00786549 0.0223087 0.0281243 0.00786549 0.0305587 0.0281243 0.0274178 0.0305587 0.00896638 -0.0303067 0.0226587 0.0158524 -0.0311317 0.0226587 0.0160735 -0.0311317 0.0302087 0.0160735 -0.0317356 0.0226587 0.0166774 -0.0319567 0.0226587 0.0175024 -0.0317356 0.0302087 0.0166774 -0.0317356 0.0226587 0.0183274 -0.0311317 0.0226587 0.0189314 -0.0303067 0.0226587 0.0191524 -0.0357117 0.0302087 -0.00148416 -0.0358208 0.0226587 -0.0014265 -0.0362858 0.0302087 -0.00102632 -0.0364247 0.0226587 -0.000822559 -0.0366044 0.0226587 -0.000364719 -0.0366044 0.0302087 -0.000364719 -0.0366044 0.0226587 0.0003696 -0.0362858 0.0302087 0.0010312 -0.0174958 0.0302087 -0.0319584 -0.0189247 0.0226587 -0.0311334 -0.0189247 0.0302087 -0.0311334 -0.0191458 0.0226587 -0.0303084 -0.0183208 0.0226587 -0.0288795 -0.0189247 0.0302087 -0.0294834 -0.0183208 0.0302087 -0.0288795 4.20971e-06 0.0302087 -0.0366476 4.20971e-06 0.0226587 -0.0366476 -0.000711698 0.0302087 -0.0364842 -0.00128581 0.0302087 -0.0360263 -0.00142473 0.0226587 -0.0358226 -0.00164579 0.0226587 -0.0349976 -0.00160442 0.0226587 -0.0346304 -0.00160442 0.0302087 -0.0346304 -0.00128581 0.0226587 -0.0339688 -0.00082079 0.0226587 -0.0335686 0.0175042 0.0226587 -0.0319584 0.0160753 0.0302087 -0.0311334 0.0158542 0.0226587 -0.0303084 0.0160753 0.0226587 -0.0294834 0.0166792 0.0226587 -0.0288795 0.0175042 0.0226587 -0.0286584 0.0175042 0.0302087 -0.0286584 0.0335753 0.0226587 -0.000822559 0.0333542 0.0226587 2.44063e-06 0.0335753 0.0226587 0.000827441 0.0335753 0.0302087 0.000827441 0.0341792 0.0226587 0.00143138 0.0341792 0.0302087 0.00143138 0.0303151 0.0302087 0.0158524 0.0295992 0.0302087 0.0160158 0.0290251 0.0226587 0.0164737 0.0290251 0.0302087 0.0164737 0.0288862 0.0226587 0.0166774 0.0286651 0.0226587 0.0175024 0.0287065 0.0302087 0.0178696 0.0290251 0.0302087 0.0185312 0.0294901 0.0226587 0.0189314 0.0303151 0.0226587 0.0191524 0.0175042 0.0226587 0.0286633 0.0166792 0.0226587 0.0288844 0.0162142 0.0226587 0.0292846 0.0158956 0.0302087 0.0299462 0.0158956 0.0226587 0.0299462 0.0158956 0.0302087 0.0306805 0.0158542 0.0226587 0.0303133 0.0158956 0.0226587 0.0306805 0.0167883 0.0302087 0.0317999 0.0166792 0.0226587 0.0317423 -0.0182117 0.0302087 0.0288267 -0.0183208 0.0226587 0.0288844 -0.0187858 0.0226587 0.0292846 -0.0189247 0.0226587 0.0294883 -0.0191458 0.0226587 0.0303133 -0.0191044 0.0226587 0.0306805 -0.0191044 0.0302087 0.0306805 -0.0189247 0.0226587 0.0311383 -0.0187858 0.0226587 0.0313421 -0.0182117 0.0302087 0.0317999 -0.0174958 0.0302087 0.0319633 -0.0174958 0.0226587 0.0319633 0.0247529 0.0320087 -0.0274463 0.0231111 0.0314087 -0.0260556 0.0227056 0.0314087 -0.0252136 0.0227056 0.0314087 -0.024279 0.0231111 0.0314087 -0.023437 0.0221206 0.0320087 -0.0241455 0.022642 0.0320087 -0.0230629 0.0238418 0.0314087 -0.0228543 -0.0303067 0.0216673 0.0175024 -0.0362858 0.0226587 -0.00102632 -0.0366458 0.0226587 2.44063e-06 -0.0362858 0.0226587 0.0010312 -0.0358208 0.0226587 0.00143138 -0.0364247 0.0226587 0.000827441 -0.0174958 0.0216673 -0.0303084 -0.0183208 0.0226587 -0.0317374 -0.0189247 0.0226587 -0.0294834 -0.00082079 0.0226587 -0.0364265 -0.00142473 0.0226587 -0.0341726 -0.00160442 0.0226587 -0.0353647 -0.00128581 0.0226587 -0.0360263 0.0166792 0.0226587 -0.0317374 0.0160753 0.0226587 -0.0311334 0.0341792 0.0226587 -0.0014265 0.0303151 0.0226587 0.0158524 0.0288862 0.0226587 0.0183274 0.0290251 0.0226587 0.0185312 0.0287065 0.0226587 0.0178696 0.0287065 0.0226587 0.0171353 0.0294901 0.0226587 0.0160735 0.0160753 0.0226587 0.0294883 0.0160753 0.0226587 0.0311383 0.0162142 0.0226587 0.0313421 0.0175042 0.0216673 0.0303133 -0.0174958 0.0226587 0.0286633 -0.0183208 0.0226587 0.0317423 -0.0191044 0.0226587 0.0299462 0.0338116 0.0314087 -0.0111562 0.0317007 0.0320087 -0.0107396 0.0311793 0.0320087 -0.00965703 0.0317007 0.0320087 -0.0073728 0.0321698 0.0314087 -0.0077469 0.0338116 0.0314087 -0.00695623 0.0338116 0.0314087 0.00696111 0.0338116 0.0320087 0.00636111 0.0327616 0.0314087 0.00724245 0.0324616 0.0320087 0.00672284 0.031993 0.0314087 0.00801111 0.031993 0.0314087 0.0101111 0.0314733 0.0320087 0.0104111 0.0324616 0.0320087 0.0113994 0.0338116 0.0314087 0.0111611 0.0234029 0.0320087 0.0224129 0.0220529 0.0320087 0.0247512 0.0224147 0.0320087 0.0261012 0.0229343 0.0314087 0.0258012 0.0247529 0.0314087 0.0268512 0.0234029 0.0320087 0.0270894 0.00906288 0.0320087 0.0311098 0.00771288 0.0320087 0.0314716 0.00672461 0.0320087 0.0324598 0.00724422 0.0314087 0.0327598 0.00696288 0.0314087 0.0338098 0.00672461 0.0320087 0.0351598 0.00801288 0.0314087 0.0356285 0.00906288 0.0314087 0.0359098 -0.00905446 0.0320087 0.0311098 -0.00996561 0.0314087 0.0319178 -0.0111018 0.0314087 0.0333426 -0.0106963 0.0314087 0.0351192 -0.0111654 0.0320087 0.0354933 -0.00905446 0.0314087 0.0359098 -0.00905446 0.0320087 0.0365098 -0.0247445 0.0320087 0.0220512 -0.0257945 0.0314087 0.0229325 -0.0260945 0.0320087 0.0224129 -0.0274445 0.0320087 0.0247512 -0.0268445 0.0314087 0.0247512 -0.0257945 0.0314087 0.0265698 -0.0348532 0.0314087 0.00724245 -0.0351532 0.0320087 0.00672284 -0.0348532 0.0314087 0.0108798 -0.0361415 0.0320087 0.0104111 -0.0359141 0.0320087 -0.0107396 -0.035445 0.0314087 -0.0103656 -0.0364355 0.0320087 -0.00965703 -0.0364355 0.0320087 -0.00845542 -0.0359141 0.0320087 -0.0073728 -0.0268445 0.0314087 -0.0247463 -0.0270828 0.0320087 -0.0260963 -0.0274445 0.0320087 -0.0247463 -0.0265632 0.0314087 -0.0236963 -0.0270828 0.0320087 -0.0233963 -0.0260945 0.0320087 -0.022408 -0.0101045 0.0314087 -0.0356236 -0.0108731 0.0314087 -0.034855 -0.0113927 0.0320087 -0.035155 -0.0108731 0.0314087 -0.032755 -0.0113927 0.0320087 -0.032455 -0.0104045 0.0320087 -0.0314667 -0.00905446 0.0314087 -0.031705 0.00906288 0.0314087 -0.035905 0.00815172 0.0314087 -0.035697 0.00643057 0.0320087 -0.0344058 0.00643057 0.0320087 -0.0332042 0.00701553 0.0314087 -0.0333377 0.00742103 0.0314087 -0.0324956 0.00815172 0.0314087 -0.0319129 0.0231111 0.0220087 -0.0260556 0.0238418 0.0314087 -0.0266383 0.0227056 0.0220087 -0.0252136 0.0227056 0.0220087 -0.024279 0.0231111 0.0220087 -0.023437 0.0247529 0.0314087 -0.0226463 0.0338116 0.0220087 -0.0111562 0.0329005 0.0314087 -0.0109483 0.0321698 0.0314087 -0.0103656 0.0317643 0.0314087 -0.00952352 0.031993 0.0220087 -0.0101062 0.0317643 0.0220087 -0.00952352 0.0317643 0.0314087 -0.00858893 0.0317116 0.0220087 -0.00905623 0.0321698 0.0220087 -0.0077469 0.0329005 0.0314087 -0.00716419 0.0338116 0.0220087 -0.00695623 0.0329005 0.0220087 0.00716907 0.0327616 0.0220087 0.00724245 0.0317643 0.0220087 0.0095284 0.0317116 0.0314087 0.00906111 0.0321698 0.0220087 0.0103704 0.0327616 0.0220087 0.0108798 0.0329005 0.0220087 0.0109531 0.0327616 0.0314087 0.0108798 0.0238418 0.0220087 0.0228591 0.0237029 0.0314087 0.0229325 0.0231111 0.0220087 0.0234418 0.0229343 0.0220087 0.0237012 0.0227056 0.0220087 0.0242839 0.0229343 0.0314087 0.0237012 0.0226529 0.0314087 0.0247512 0.0226529 0.0220087 0.0247512 0.0229343 0.0220087 0.0258012 0.0231111 0.0220087 0.0260605 0.0237029 0.0314087 0.0265698 0.0237029 0.0220087 0.0265698 0.0247529 0.0220087 0.0268512 0.00801288 0.0314087 0.0319912 0.00724422 0.0314087 0.0348598 0.00801288 0.0220087 0.0356285 -0.00905446 0.0314087 0.0317098 -0.0101045 0.0220087 0.0319912 -0.0108731 0.0220087 0.0327598 -0.0106963 0.0314087 0.0325005 -0.0111545 0.0220087 0.0338098 -0.0111018 0.0314087 0.0342771 -0.0106963 0.0220087 0.0351192 -0.00996561 0.0314087 0.0357019 -0.0247445 0.0314087 0.0226512 -0.0257945 0.0220087 0.0229325 -0.0265632 0.0314087 0.0237012 -0.0265632 0.0314087 0.0258012 -0.0257945 0.0220087 0.0265698 -0.0338032 0.0314087 0.00696111 -0.0356218 0.0314087 0.00801111 -0.0359032 0.0220087 0.00906111 -0.0359032 0.0314087 0.00906111 -0.0356218 0.0314087 0.0101111 -0.0338032 0.0314087 -0.0111562 -0.0347143 0.0314087 -0.0109483 -0.0358505 0.0314087 -0.00952352 -0.0358505 0.0314087 -0.00858893 -0.035445 0.0220087 -0.0077469 -0.0347143 0.0220087 -0.00716419 -0.035445 0.0314087 -0.0077469 -0.0347143 0.0314087 -0.00716419 -0.0338032 0.0314087 -0.00695623 -0.0265632 0.0220087 -0.0257963 -0.0257945 0.0314087 -0.026565 -0.0265632 0.0314087 -0.0257963 -0.0257945 0.0220087 -0.0229276 -0.0257945 0.0314087 -0.0229276 -0.0108731 0.0220087 -0.034855 -0.0111545 0.0220087 -0.033805 -0.0111545 0.0314087 -0.033805 -0.0108731 0.0220087 -0.032755 -0.0101045 0.0220087 -0.0319863 -0.0101045 0.0314087 -0.0319863 0.00742103 0.0314087 -0.0351143 0.00701553 0.0314087 -0.0342723 0.00701553 0.0220087 -0.0333377 0.00742103 0.0220087 -0.0324956 0.00815172 0.0220087 -0.0319129 -0.0122171 0.0308087 0.0369328 4.20971e-06 0.0308087 0.0389024 -0.00930517 0.0308087 0.0377721 -0.0257913 0.0308087 0.0291195 -0.0279653 0.0308087 0.0270379 -0.0270313 0.0308087 0.0279719 -0.0377358 0.0308087 0.0094311 -0.0363679 0.0305587 0.0137966 -0.0386122 0.0305587 -0.00468644 -0.0384776 0.0308087 -0.00568603 -0.0320099 0.0305587 -0.0220953 -0.0257913 0.0305587 -0.0291146 -0.0279653 0.0308087 -0.027033 -0.0122171 0.0308087 -0.0369279 -0.0180735 0.0305587 -0.0344418 -0.00930517 0.0308087 -0.0377672 -0.0338032 0.0308087 -0.0130062 -0.0354303 0.0310087 -0.0124349 -0.0367351 0.0310087 -0.0113943 -0.0368914 0.0308087 -0.011519 -0.0373939 0.0308087 -0.0107021 -0.0338032 0.0308087 -0.00510623 -0.0374592 0.0310087 -0.00989068 -0.0377358 0.0308087 -0.00942622 -0.0247445 0.0308087 -0.0286963 -0.0267195 0.0308087 -0.0281671 -0.0266195 0.0310087 -0.0279939 -0.0266195 0.0310087 -0.0214987 -0.0267195 0.0308087 -0.0213255 -0.0279921 0.0310087 -0.0228713 -0.0286945 0.0308087 -0.0247463 -0.0281653 0.0308087 -0.0267213 -0.0107004 0.0308087 -0.0373957 -0.0110295 0.0308087 -0.0303842 -0.0109295 0.0310087 -0.0305574 -0.0124753 0.0308087 -0.03183 -0.0128045 0.0310087 -0.033805 -0.0123021 0.0310087 -0.03568 -0.0124753 0.0308087 -0.03578 -0.0109295 0.0310087 -0.0370526 -0.0110295 0.0308087 -0.0372258 0.0054069 0.0310087 -0.0329705 0.00734904 0.0308087 -0.0373638 0.00906288 0.0308087 -0.037755 0.0247529 0.0310087 -0.0209963 0.0227779 0.0308087 -0.0213255 0.0213321 0.0308087 -0.0227713 0.0215054 0.0310087 -0.0266213 0.0338116 0.0310087 -0.00530623 0.0321845 0.0310087 -0.00567759 0.0338116 0.0308087 -0.00510623 0.0299606 0.0308087 -0.00817727 0.0301556 0.0310087 -0.00989068 0.0308797 0.0310087 -0.0113943 0.0338116 0.0310087 -0.0128062 0.0320978 0.0308087 -0.0126151 0.0318366 0.0308087 0.00564031 0.0298616 0.0308087 0.00906111 0.0319366 0.0310087 0.00581351 0.0308797 0.0310087 0.00672302 0.030564 0.0310087 0.00718611 0.0301556 0.0310087 0.00822665 0.0303908 0.0308087 0.0110361 0.0301556 0.0310087 0.00989556 0.030564 0.0310087 0.0109361 0.0318366 0.0308087 0.0124819 0.0321845 0.0310087 0.0124397 0.0319366 0.0310087 0.0123087 0.0215054 0.0310087 0.0266262 0.0210029 0.0310087 0.0247512 0.0208029 0.0308087 0.0247512 0.0228779 0.0310087 0.0215036 0.00718788 0.0310087 0.0370574 0.00564208 0.0308087 0.0357848 0.00531288 0.0310087 0.0338098 0.00511288 0.0308087 0.0338098 0.00581528 0.0310087 0.0319348 0.00718788 0.0310087 0.0305622 0.00708788 0.0308087 0.030389 0.00906288 0.0310087 0.0300598 -0.0106815 0.0310087 0.0304312 -0.0107683 0.0308087 0.030251 -0.0109295 0.0310087 0.0305622 -0.0129054 0.0308087 0.0329309 -0.0128045 0.0310087 0.0338098 -0.0129054 0.0308087 0.0346888 -0.0121427 0.0308087 0.0362726 -0.0119863 0.0310087 0.0361479 -0.0107683 0.0308087 0.0373687 -0.0106815 0.0310087 0.0371885 -0.00942445 0.0308087 0.0377425 -0.0281653 0.0308087 0.0267262 -0.0286945 0.0308087 0.0247512 -0.0281653 0.0308087 0.0227762 -0.0267195 0.0308087 0.0213304 -0.0247445 0.0310087 0.0210012 -0.0279921 0.0310087 0.0266262 -0.0370508 0.0310087 0.00718611 -0.037224 0.0308087 0.00708611 -0.0357782 0.0308087 0.00564031 -0.0338032 0.0308087 0.00511111 -0.0375532 0.0310087 0.00906111 -0.0377532 0.0308087 0.00906111 -0.0338032 0.0308087 0.0130111 -0.0370508 0.0310087 0.0109361 -0.0357782 0.0308087 0.0124819 -0.037224 0.0308087 0.0110361 -0.00476851 0.0310087 0.0099131 -0.010915 0.0308087 0.00249468 -0.00476851 0.0310087 -0.00990822 0.00786549 0.0310087 -0.0281194 0.00668091 0.0308087 -0.0284819 0.0126031 0.0308087 0.00948925 -0.0101083 0.0310087 0.00962142 -0.0100371 0.0308087 0.00943455 -0.0240186 0.0310087 -0.0105575 -0.00312876 0.0310087 -0.02649 -0.00233318 0.0310087 -0.0246102 -0.0184286 0.0308087 0.0283762 -0.0191767 0.0308087 0.0289728 -0.0195919 0.0308087 0.0298349 -0.0193577 0.0311587 0.0292383 -0.0195919 0.0308087 0.0307918 -0.0191767 0.0308087 0.0316538 -0.0195919 0.0311587 0.0307918 -0.0193577 0.0311587 0.0313883 -0.0191767 0.0311587 0.0316538 -0.0184286 0.0308087 0.0322504 -0.0174958 0.0308087 0.0324633 -0.0303067 0.0308087 0.0153524 -0.0313817 0.0308087 0.0156405 -0.0321686 0.0311587 0.0164274 -0.0324567 0.0308087 0.0175024 -0.0321686 0.0308087 0.0185774 -0.0313817 0.0311587 0.0193644 -0.0303067 0.0308087 0.0196524 -0.0303067 0.0311587 0.0196524 -0.0349958 0.0311587 -0.00214756 -0.0360708 0.0311587 -0.00185951 -0.0366767 0.0308087 -0.00133806 -0.0366767 0.0311587 -0.00133806 -0.0370919 0.0308087 -0.000475979 -0.0370919 0.0308087 0.000480861 -0.0370919 0.0311587 0.000480861 -0.0368577 0.0311587 0.00107744 -0.0366767 0.0311587 0.00134294 -0.0366767 0.0308087 0.00134294 -0.0359286 0.0308087 0.00193952 -0.0360708 0.0311587 0.0018644 -0.0174958 0.0308087 -0.0324584 -0.0193577 0.0311587 -0.0313834 -0.0196458 0.0308087 -0.0303084 -0.0193577 0.0308087 -0.0292334 -0.0174958 0.0308087 -0.0281584 -0.0185708 0.0311587 -0.0284465 -0.00167673 0.0308087 -0.0363381 -0.00209189 0.0308087 -0.035476 -0.00167673 0.0311587 -0.0363381 -0.00167673 0.0308087 -0.0336571 -0.00167673 0.0311587 -0.0336571 -0.00092864 0.0311587 -0.0330605 0.0164292 0.0308087 -0.0321704 0.0164292 0.0311587 -0.0321704 0.0156423 0.0308087 -0.0313834 0.0156423 0.0311587 -0.0313834 0.0156423 0.0308087 -0.0292334 0.0153542 0.0311587 -0.0303084 0.0175042 0.0308087 -0.0281584 0.0339292 0.0311587 -0.00185951 0.0331423 0.0308087 -0.00107256 0.0331423 0.0311587 -0.00107256 0.0331423 0.0311587 0.00107744 0.0339292 0.0308087 0.0018644 0.0350042 0.0308087 0.00215244 0.0303151 0.0311587 0.0153524 0.0293822 0.0308087 0.0155654 0.0286342 0.0308087 0.0161619 0.028219 0.0308087 0.017024 0.028219 0.0311587 0.017024 0.028219 0.0308087 0.0179809 0.028219 0.0311587 0.0179809 0.0293822 0.0311587 0.0194395 0.0175042 0.0311587 0.0281633 0.0165714 0.0311587 0.0283762 0.0154081 0.0308087 0.0298349 0.0158233 0.0311587 0.0289728 0.0154081 0.0308087 0.0307918 0.0154081 0.0311587 0.0307918 0.0158233 0.0308087 0.0316538 0.0158233 0.0311587 0.0316538 0.0175042 0.0308087 0.0324633 0.0165714 0.0311587 0.0322504 -0.0354303 0.0336087 -0.0124349 -0.0367351 0.0336087 -0.0113943 -0.0374592 0.0336087 -0.00989068 -0.0374592 0.0310087 -0.00822177 -0.0367351 0.0310087 -0.00671814 -0.0367351 0.0336087 -0.00671814 -0.0354303 0.0310087 -0.00567759 -0.0279921 0.0310087 -0.0266213 -0.0284945 0.0310087 -0.0247463 -0.0279921 0.0336087 -0.0266213 -0.0284945 0.0336087 -0.0247463 -0.0247445 0.0336087 -0.0209963 -0.0109295 0.0336087 -0.0370526 -0.0128045 0.0336087 -0.033805 -0.0123021 0.0310087 -0.03193 -0.0123021 0.0336087 -0.03193 -0.0109295 0.0336087 -0.0305574 -0.00905446 0.0310087 -0.030055 0.00743581 0.0310087 -0.0371836 0.00906288 0.0336087 -0.037555 0.00743581 0.0336087 -0.0371836 0.00613101 0.0310087 -0.036143 0.0054069 0.0310087 -0.0346394 0.0054069 0.0336087 -0.0346394 0.0054069 0.0336087 -0.0329705 0.00613101 0.0310087 -0.0314669 0.00613101 0.0336087 -0.0314669 0.00743581 0.0310087 -0.0304263 0.00906288 0.0310087 -0.030055 0.0247529 0.0336087 -0.0284963 0.0228779 0.0310087 -0.0279939 0.0228779 0.0336087 -0.0279939 0.0210029 0.0310087 -0.0247463 0.0215054 0.0310087 -0.0228713 0.0228779 0.0336087 -0.0214987 0.0228779 0.0310087 -0.0214987 0.0321845 0.0310087 -0.0124349 0.0321845 0.0336087 -0.0124349 0.0301556 0.0310087 -0.00822177 0.0301556 0.0336087 -0.00989068 0.0308797 0.0310087 -0.00671814 0.0301556 0.0336087 -0.00822177 0.0321845 0.0310087 0.00568247 0.0319366 0.0336087 0.00581351 0.0308797 0.0336087 0.00672302 0.0300616 0.0310087 0.00906111 0.0300616 0.0336087 0.00906111 0.0301556 0.0336087 0.00989556 0.0308797 0.0310087 0.0113992 0.0319366 0.0336087 0.0123087 0.0321845 0.0336087 0.0124397 0.0338116 0.0336087 0.0128111 0.0247529 0.0310087 0.0210012 0.0215054 0.0310087 0.0228762 0.0215054 0.0336087 0.0228762 0.0210029 0.0336087 0.0247512 0.0228779 0.0310087 0.0279988 0.0228779 0.0336087 0.0279988 0.0247529 0.0310087 0.0285012 0.00906288 0.0336087 0.0300598 0.00718788 0.0336087 0.0305622 0.00581528 0.0336087 0.0319348 0.00581528 0.0310087 0.0356848 0.00906288 0.0336087 0.0375598 -0.00905446 0.0336087 0.0375598 -0.0109295 0.0310087 0.0370574 -0.0119863 0.0336087 0.0361479 -0.0123021 0.0336087 0.0356848 -0.0123021 0.0310087 0.0356848 -0.0127104 0.0310087 0.0346443 -0.0128045 0.0336087 0.0338098 -0.0123021 0.0336087 0.0319348 -0.0127104 0.0310087 0.0329754 -0.0123021 0.0310087 0.0319348 -0.0119863 0.0310087 0.0314718 -0.0109295 0.0336087 0.0305622 -0.0106815 0.0336087 0.0304312 -0.00905446 0.0336087 0.0300598 -0.0266195 0.0310087 0.0215036 -0.0247445 0.0336087 0.0210012 -0.0266195 0.0336087 0.0215036 -0.0279921 0.0310087 0.0228762 -0.0279921 0.0336087 0.0228762 -0.0284945 0.0336087 0.0247512 -0.0284945 0.0310087 0.0247512 -0.0266195 0.0336087 0.0279988 -0.0266195 0.0310087 0.0279988 -0.0247445 0.0310087 0.0285012 -0.0247445 0.0336087 0.0285012 -0.0338032 0.0336087 0.00531111 -0.0356782 0.0310087 0.00581351 -0.0356782 0.0336087 0.00581351 -0.0375532 0.0336087 0.00906111 -0.0370508 0.0336087 0.0109361 -0.0356782 0.0310087 0.0123087 4.20971e-06 0.0328087 -0.0109976 -0.00859594 0.0310087 -0.00685595 -0.01072 0.0310087 -0.00244529 -0.01072 0.0310087 0.00245017 -0.01072 0.0328087 -0.00244529 -0.01072 0.0328087 0.00245017 -0.00859594 0.0310087 0.00686083 -0.00859594 0.0328087 0.00686083 -0.00476851 0.0328087 0.0099131 0.0112569 0.0335087 -0.00940652 0.0125239 0.0335087 -0.00966802 0.024027 0.0335087 -0.0105575 0.024027 0.0310087 -0.0105575 0.0260637 0.0335087 -0.0100578 0.0259009 0.0310087 -0.0101386 0.027475 0.0335087 -0.00889087 0.0274178 0.0310087 -0.00896149 0.0282891 0.0310087 -0.00725044 -0.0240186 0.0335087 -0.0105575 -0.00667249 0.0310087 -0.0282819 -0.00602937 0.0335087 -0.0282346 -0.00468697 0.0310087 -0.0278084 -0.00468697 0.0335087 -0.0278084 -0.00431309 0.0335087 -0.0275958 -0.00300552 0.0335087 -0.0263136 -0.0112485 0.0310087 -0.00940652 -0.0198958 0.0338087 0.0344703 -0.0185708 0.0311587 0.0321753 -0.0216527 0.0338087 0.0327133 -0.0196458 0.0311587 0.0303133 -0.0195919 0.0311587 0.0298349 -0.0174958 0.0311587 0.0281633 -0.0185708 0.0311587 0.0284514 -0.0191767 0.0311587 0.0289728 -0.0198958 0.0338087 0.0261564 -0.0216527 0.0338087 0.0279133 4.20971e-06 0.0335087 -0.0419976 0.00935009 0.0333087 -0.0409445 0.0182273 0.0335087 -0.0378383 0.0182273 0.0333087 -0.0378383 0.0261908 0.0335087 -0.0328345 0.0378449 0.0333087 -0.0182207 0.0409512 0.0333087 -0.00934344 0.0420042 0.0335087 2.44063e-06 0.0409512 0.0335087 0.00934832 0.0378449 0.0333087 0.0182256 0.0261908 0.0333087 0.0328394 0.00935009 0.0335087 0.0409494 4.20971e-06 0.0333087 0.0420024 4.20971e-06 0.0338087 0.0417024 0.00928333 0.0338087 0.0406569 0.0182273 0.0335087 0.0378431 0.0261908 0.0335087 0.0328394 0.0328411 0.0335087 0.026189 0.0298659 0.0338087 0.0291086 0.0378449 0.0335087 0.0182256 0.0375746 0.0338087 0.0180954 0.0378449 0.0335087 -0.0182207 0.0409512 0.0335087 -0.00934344 0.0414053 0.0338087 0.004986 0.0302093 0.0338087 -0.0287472 0.0326066 0.0338087 -0.0259971 0.0328411 0.0335087 -0.0261841 0.0260037 0.0338087 -0.0325999 0.00935009 0.0335087 -0.0409445 0.00498777 0.0338087 -0.0413987 0.00891311 0.0338087 -0.0407348 0.00928333 0.0338087 -0.0406521 -0.0313817 0.0311587 0.0156405 -0.0327067 0.0338087 0.0133455 -0.0324567 0.0311587 0.0175024 -0.0321686 0.0311587 0.0185774 -0.0327067 0.0338087 0.0216594 -0.0303067 0.0338087 0.0223024 -0.0349958 0.0311587 0.00215244 -0.0373958 0.0338087 0.00415936 -0.0391527 0.0338087 0.00240244 -0.0371458 0.0311587 2.44063e-06 -0.0370919 0.0311587 -0.000475979 -0.0373958 0.0338087 -0.00415448 -0.0368577 0.0311587 -0.00107256 -0.0185708 0.0311587 -0.0321704 -0.0196458 0.0311587 -0.0303084 -0.0193577 0.0311587 -0.0292334 -0.0216527 0.0338087 -0.0279084 -0.00092864 0.0311587 -0.0369346 -0.00209189 0.0311587 -0.035476 -0.00209189 0.0311587 -0.0345191 -0.00207843 0.0338087 -0.0306729 0.0175042 0.0338087 -0.0351084 0.0156423 0.0311587 -0.0292334 0.0164292 0.0311587 -0.0284465 0.0133473 0.0338087 -0.0279084 0.0350042 0.0311587 -0.00214756 0.0326042 0.0338087 -0.00415448 0.0328542 0.0311587 2.44063e-06 0.0308473 0.0338087 0.00240244 0.0339292 0.0311587 0.0018644 0.0326042 0.0338087 0.00415936 0.0350042 0.0311587 0.00215244 0.0350042 0.0338087 0.00480244 0.0303151 0.0311587 0.0196524 0.0300203 0.0338087 0.0127115 0.0296602 0.0338087 0.0127473 0.0293822 0.0311587 0.0155654 0.0286342 0.0311587 0.0161619 0.0282325 0.0338087 0.0131778 0.0256354 0.0338087 0.0185705 0.0286342 0.0311587 0.0188429 0.0282325 0.0338087 0.0218271 0.0175042 0.0338087 0.0255133 0.0154216 0.0338087 0.0259887 0.0154081 0.0311587 0.0298349 0.024027 0.0338087 0.0108624 0.0259009 0.0335087 0.0101435 -0.0101083 0.0335087 -0.00961654 -0.0112485 0.0338087 -0.00910652 -0.00911783 0.0335087 -0.010219 -0.0100015 0.0338087 -0.00933623 -0.0240186 0.0335087 0.0105624 -0.00233318 0.0335087 0.0246151 -0.00312876 0.0335087 0.0264948 -0.0045516 0.0338087 0.028081 -0.00667249 0.0335087 0.0282868 0.0307234 0.0338087 -0.011519 0.0308797 0.0336087 -0.0113943 0.0299606 0.0338087 -0.00993518 0.0308797 0.0336087 -0.00671814 0.0321845 0.0336087 -0.00567759 0.0307234 0.0338087 -0.00659344 0.0320978 0.0338087 -0.0054974 0.0338116 0.0336087 -0.00530623 0.0247529 0.0338087 -0.0286963 0.0215054 0.0336087 -0.0266213 0.0210029 0.0336087 -0.0247463 0.0208029 0.0338087 -0.0247463 0.0215054 0.0336087 -0.0228713 0.0227779 0.0338087 -0.0213255 0.0247529 0.0336087 -0.0209963 0.00734904 0.0338087 -0.0373638 0.00613101 0.0336087 -0.036143 0.00597464 0.0338087 -0.0362677 0.00521191 0.0338087 -0.032926 0.00597464 0.0338087 -0.0313422 0.00743581 0.0336087 -0.0304263 0.00734904 0.0338087 -0.0302461 0.00906288 0.0338087 -0.029855 -0.00905446 0.0336087 -0.037555 -0.0123021 0.0336087 -0.03568 -0.0124753 0.0338087 -0.03578 -0.0130045 0.0338087 -0.033805 -0.00905446 0.0336087 -0.030055 -0.00905446 0.0338087 -0.029855 -0.0266195 0.0336087 -0.0279939 -0.0286945 0.0338087 -0.0247463 -0.0279921 0.0336087 -0.0228713 -0.0266195 0.0336087 -0.0214987 -0.0267195 0.0338087 -0.0213255 -0.0247445 0.0338087 -0.0207963 -0.035517 0.0338087 -0.0126151 -0.0376542 0.0338087 -0.00993518 -0.0374592 0.0336087 -0.00822177 -0.0376542 0.0338087 -0.00817727 -0.0354303 0.0336087 -0.00567759 -0.0368914 0.0338087 -0.00659344 -0.0338032 0.0336087 -0.00530623 -0.035517 0.0338087 -0.0054974 -0.0338032 0.0338087 -0.00510623 -0.0338032 0.0338087 0.00511111 -0.0357782 0.0338087 0.00564031 -0.0370508 0.0336087 0.00718611 -0.037224 0.0338087 0.00708611 -0.0356782 0.0336087 0.0123087 -0.0338032 0.0336087 0.0128111 -0.0357782 0.0338087 0.0124819 -0.0247445 0.0338087 0.0208012 -0.0279921 0.0336087 0.0266262 -0.0281653 0.0338087 0.0267262 -0.0267195 0.0338087 0.028172 -0.0247445 0.0338087 0.0287012 -0.0106815 0.0336087 0.0371885 -0.0109295 0.0336087 0.0370574 -0.0129054 0.0338087 0.0346888 -0.0121427 0.0338087 0.0362726 -0.0127104 0.0336087 0.0346443 -0.0127104 0.0336087 0.0329754 -0.0119863 0.0336087 0.0314718 -0.00905446 0.0338087 0.0298598 -0.0107683 0.0338087 0.030251 0.00708788 0.0338087 0.030389 0.00531288 0.0336087 0.0338098 0.00581528 0.0336087 0.0356848 0.00718788 0.0336087 0.0370574 0.0228779 0.0336087 0.0215036 0.0247529 0.0338087 0.0208012 0.0227779 0.0338087 0.0213304 0.0213321 0.0338087 0.0227762 0.0215054 0.0336087 0.0266262 0.0208029 0.0338087 0.0247512 0.0318366 0.0338087 0.0124819 0.0308797 0.0336087 0.0113992 0.030564 0.0336087 0.0109361 0.0301556 0.0336087 0.00822665 0.030564 0.0336087 0.00718611 0.0303908 0.0338087 0.00708611 0.0321845 0.0336087 0.00568247 0.0114463 0.0304087 -0.0575206 0.0326995 0.0306087 -0.0489295 0.0416174 0.0306087 -0.0416108 0.0487699 0.0304087 -0.0325818 0.0489362 0.0306087 -0.0326929 0.0543745 0.0306087 -0.0225185 0.0541897 0.0304087 -0.0224419 0.0586542 0.0304087 2.44063e-06 0.0575273 0.0304087 0.0114445 0.0541897 0.0304087 0.0224468 0.0543745 0.0306087 0.0225234 0.041476 0.0304087 0.0414743 0.0416174 0.0306087 0.0416157 0.0326995 0.0306087 0.0489344 0.0225251 0.0306087 0.0543728 0.0224486 0.0304087 0.054188 0.0114463 0.0304087 0.0575255 0.0114853 0.0311087 -0.0577168 4.20971e-06 0.0306087 -0.0588476 0.0114853 0.0306087 -0.0577168 0.0225251 0.0311087 -0.0543679 0.0225251 0.0306087 -0.0543679 0.0326995 0.0311087 -0.0489295 0.0416174 0.0311087 -0.0416108 0.0489362 0.0311087 -0.0326929 0.0577234 0.0306087 -0.0114786 0.0588542 0.0306087 2.44063e-06 0.0588542 0.0311087 2.44063e-06 0.0577234 0.0306087 0.0114835 0.0543745 0.0311087 0.0225234 0.0416174 0.0311087 0.0416157 0.0489362 0.0306087 0.0326977 0.0225251 0.0311087 0.0543728 0.0114853 0.0306087 0.0577217 0.0114853 0.0311087 0.0577217 0.0108903 0.0333087 0.0547303 0.0326995 0.0311087 0.0489344 0.0489362 0.0311087 0.0326977 0.0515567 0.0333087 0.0213562 0.0577234 0.0311087 0.0114835 0.054732 0.0333087 0.0108885 0.0577234 0.0311087 -0.0114786 0.054732 0.0333087 -0.0108836 0.0543745 0.0311087 -0.0225185 0.031005 0.0333087 -0.0463936 0.0213579 0.0333087 -0.05155 4.20971e-06 0.0300087 -0.0574476 0.0219894 0.0304087 -0.0530744 0.0319217 0.0304087 -0.0477655 0.0406275 0.0300087 -0.0406208 0.0530811 0.0304087 -0.0219827 0.0530811 0.0300087 -0.0219827 0.0574542 0.0304087 2.44063e-06 0.0530811 0.0300087 0.0219876 0.0530811 0.0304087 0.0219876 0.0406275 0.0304087 0.0406257 0.0406275 0.0300087 0.0406257 0.0319217 0.0304087 0.0477704 0.0112121 0.0304087 0.0563486 4.20971e-06 0.0300087 0.0574524 4.20971e-06 -0.0212913 0.0525024 -0.0192326 -0.0197913 0.0504598 -0.00950427 -0.0212913 0.0516342 -0.028053 -0.0197913 0.0461413 -0.0272736 -0.0212913 0.0448596 -0.0349468 -0.0212913 0.0391774 -0.0426487 -0.0197913 0.0331193 -0.0414639 -0.0212913 0.0321994 -0.0479413 -0.0197913 0.0248466 -0.0466094 -0.0212913 0.0241565 4.20971e-06 0.0180087 0.0847524 4.20971e-06 0.0178087 0.0849524 0.0139865 0.0178087 0.0837938 0.0139536 0.0180087 0.0835966 0.0404359 0.0178087 0.0747137 0.0275225 0.0180087 0.0801605 0.0403408 0.0180087 0.0745378 0.0521816 0.0178087 0.0670399 0.0623568 0.0180087 0.0574021 0.077616 0.0180087 0.0340461 0.0777992 0.0178087 0.0341265 0.0823548 0.0178087 0.0208564 0.0846641 0.0178087 0.00701756 0.0846641 0.0178087 -0.00701267 0.0823548 0.0178087 -0.0208516 0.077616 0.0180087 -0.0340412 0.0777992 0.0178087 -0.0341216 0.0709541 0.0180087 -0.0463514 0.0711215 0.0178087 -0.0464608 0.062504 0.0178087 -0.0575326 0.0521816 0.0178087 -0.067035 0.0520587 0.0180087 -0.0668772 0.0404359 0.0178087 -0.0747089 0.0275225 0.0180087 -0.0801556 0.0139536 0.0180087 -0.0835917 0.0139865 0.0178087 -0.083789 0.0139042 -0.00829131 -0.0832958 0.0243444 -0.00829131 -0.0808638 0.0275874 -0.00779131 -0.0803447 0.0404359 -0.00779131 -0.0747089 0.0521816 -0.00779131 -0.067035 0.0707029 -0.00829131 -0.0461873 0.0711215 -0.00779131 -0.0464608 0.0646323 -0.00829131 -0.0543576 0.062504 -0.00779131 -0.0575326 0.0770155 -0.00829131 -0.0346539 0.0777992 -0.00779131 -0.0341216 0.0727285 -0.00829131 -0.0429276 0.0823548 -0.00779131 -0.0208516 0.0818701 -0.00829131 -0.0207288 0.0823548 -0.00779131 0.0208564 0.079358 -0.00829131 0.0288949 0.074596 -0.00829131 0.0395988 0.0777992 -0.00779131 0.0341265 0.0773413 -0.00829131 0.0339256 0.0622824 -0.00829131 0.0570395 0.0646323 -0.00829131 0.0543624 0.0727285 -0.00829131 0.0429324 0.0521816 -0.00779131 0.0670399 0.0458646 -0.00829131 0.0709153 0.0404359 -0.00779131 0.0747137 0.0347448 -0.00829131 0.0769758 0.0275874 -0.00779131 0.0803496 0.0139042 -0.00829131 0.0833007 4.20971e-06 -0.00519131 0.0849524 0.0275874 -0.00519131 0.0803496 0.0275225 -0.00499131 0.0801605 0.0403408 -0.00499131 0.0745378 0.0521816 -0.00519131 0.0670399 0.0520587 -0.00499131 0.0668821 0.0623568 -0.00499131 0.0574021 0.0711215 -0.00519131 0.0464657 0.0777992 -0.00519131 0.0341265 0.077616 -0.00499131 0.0340461 0.0844647 -0.00499131 0.00700104 0.0844647 -0.00499131 -0.00699616 0.0846641 -0.00519131 -0.00701267 0.0823548 -0.00519131 -0.0208516 0.0777992 -0.00519131 -0.0341216 0.0711215 -0.00519131 -0.0464608 0.0403408 -0.00499131 -0.074533 0.0275874 -0.00519131 -0.0803447 0.0139865 -0.00519131 -0.083789 4.20971e-06 -0.00499131 -0.0847476 0.0139536 -0.00399131 -0.0835917 0.0275874 -0.00379131 -0.0803447 0.0777992 -0.00379131 -0.0341216 0.077616 -0.00399131 -0.0340412 0.0823548 -0.00379131 -0.0208516 0.0821609 -0.00399131 -0.0208025 0.0846641 -0.00379131 0.00701756 0.0821609 -0.00399131 0.0208073 0.0777992 -0.00379131 0.0341265 0.0711215 -0.00379131 0.0464657 0.062504 -0.00379131 0.0575375 0.0520587 -0.00399131 0.0668821 0.0403408 -0.00399131 0.0745378 0.0275225 -0.00399131 0.0801605 0.0139865 -0.00379131 0.0837938 4.20971e-06 -0.00379131 0.0849524 4.20971e-06 -0.00269131 0.0849524 0.0403408 -0.00249131 0.0745378 0.0520587 -0.00249131 0.0668821 0.062504 -0.00269131 0.0575375 0.0623568 -0.00249131 0.0574021 0.0777992 -0.00269131 0.0341265 0.077616 -0.00249131 0.0340461 0.0823548 -0.00269131 0.0208564 0.0846641 -0.00269131 0.00701756 0.0844647 -0.00249131 -0.00699616 0.0823548 -0.00269131 -0.0208516 0.0777992 -0.00269131 -0.0341216 0.0821609 -0.00249131 -0.0208025 0.077616 -0.00249131 -0.0340412 0.0709541 -0.00249131 -0.0463514 0.062504 -0.00269131 -0.0575326 0.0521816 -0.00269131 -0.067035 0.0404359 -0.00269131 -0.0747089 0.0403408 -0.00249131 -0.074533 0.0275874 -0.00269131 -0.0803447 0.0275225 -0.00249131 -0.0801556 0.0139536 -0.00249131 -0.0835917 4.20971e-06 -0.00269131 -0.0849476 0.0139865 -0.00129131 -0.083789 0.0139536 -0.00149131 -0.0835917 0.0275874 -0.00129131 -0.0803447 0.0275225 -0.00149131 -0.0801556 0.0623568 -0.00149131 -0.0573972 0.0709541 -0.00149131 -0.0463514 0.0777992 -0.00129131 -0.0341216 0.0821609 -0.00149131 -0.0208025 0.0823548 -0.00129131 -0.0208516 0.0844647 -0.00149131 -0.00699616 0.0821609 -0.00149131 0.0208073 0.0823548 -0.00129131 0.0208564 0.077616 -0.00149131 0.0340461 0.062504 -0.00129131 0.0575375 0.0521816 -0.00129131 0.0670399 0.0404359 -0.00129131 0.0747137 0.0403408 -0.00149131 0.0745378 0.0275874 -0.00129131 0.0803496 0.0139865 -0.00129131 0.0837938 0.0139536 -0.00149131 0.0835966 4.20971e-06 -0.00149131 0.0847524 4.20971e-06 8.6865e-06 0.0847524 0.0139865 -0.000191313 0.0837938 0.0403408 8.6865e-06 0.0745378 0.0404359 -0.000191313 0.0747137 0.0521816 -0.000191313 0.0670399 0.0709541 8.6865e-06 0.0463563 0.077616 8.6865e-06 0.0340461 0.0777992 -0.000191313 0.0341265 0.0846641 -0.000191313 0.00701756 0.0844647 8.6865e-06 -0.00699616 0.0823548 -0.000191313 -0.0208516 0.0821609 8.6865e-06 -0.0208025 0.0709541 8.6865e-06 -0.0463514 0.0623568 8.6865e-06 -0.0573972 0.0520587 8.6865e-06 -0.0668772 0.0404359 -0.000191313 -0.0747089 0.0275225 8.6865e-06 -0.0801556 0.0139865 -0.000191313 -0.083789 4.20971e-06 -0.000191313 -0.0849476 0.0139536 0.00100869 -0.0835917 0.0275225 0.00100869 -0.0801556 0.0403408 0.00100869 -0.074533 0.0520587 0.00100869 -0.0668772 0.0777992 0.00120869 -0.0341216 0.077616 0.00100869 -0.0340412 0.0846641 0.00120869 -0.00701267 0.0844647 0.00100869 -0.00699616 0.0844647 0.00100869 0.00700104 0.077616 0.00100869 0.0340461 0.0520587 0.00100869 0.0668821 0.0275225 0.00100869 0.0801605 0.0139536 0.00100869 0.0835966 4.20971e-06 0.00230869 0.0849524 0.0139865 0.00230869 0.0837938 0.0275874 0.00230869 0.0803496 0.0521816 0.00230869 0.0670399 0.0709541 0.00250869 0.0463563 0.077616 0.00250869 0.0340461 0.0823548 0.00230869 0.0208564 0.0844647 0.00250869 0.00700104 0.0777992 0.00230869 -0.0341216 0.077616 0.00250869 -0.0340412 0.0709541 0.00250869 -0.0463514 0.062504 0.00230869 -0.0575326 0.0520587 0.00250869 -0.0668772 0.0404359 0.00230869 -0.0747089 0.0139865 0.00230869 -0.083789 0.0139536 0.00250869 -0.0835917 0.0139536 0.00350869 -0.0835917 0.0139865 0.00370869 -0.083789 0.0275874 0.00370869 -0.0803447 0.062504 0.00370869 -0.0575326 0.0623568 0.00350869 -0.0573972 0.0709541 0.00350869 -0.0463514 0.0823548 0.00370869 -0.0208516 0.077616 0.00350869 -0.0340412 0.0846641 0.00370869 -0.00701267 0.0844647 0.00350869 -0.00699616 0.0844647 0.00350869 0.00700104 0.0821609 0.00350869 0.0208073 0.0520587 0.00350869 0.0668821 0.0521816 0.00370869 0.0670399 0.0404359 0.00370869 0.0747137 0.0139536 0.00350869 0.0835966 0.0139865 0.00370869 0.0837938 4.20971e-06 0.00480869 0.0849524 0.0139865 0.00480869 0.0837938 0.0139536 0.00500869 0.0835966 0.0275874 0.00480869 0.0803496 0.0275225 0.00500869 0.0801605 0.0404359 0.00480869 0.0747137 0.0403408 0.00500869 0.0745378 0.0520587 0.00500869 0.0668821 0.0623568 0.00500869 0.0574021 0.077616 0.00500869 0.0340461 0.0821609 0.00500869 0.0208073 0.0844647 0.00500869 0.00700104 0.0846641 0.00480869 -0.00701267 0.0844647 0.00500869 -0.00699616 0.0821609 0.00500869 -0.0208025 0.0711215 0.00480869 -0.0464608 0.0709541 0.00500869 -0.0463514 0.062504 0.00480869 -0.0575326 0.0521816 0.00480869 -0.067035 0.0520587 0.00500869 -0.0668772 0.0275225 0.00500869 -0.0801556 0.0139536 0.00500869 -0.0835917 0.0139536 0.00600869 -0.0835917 0.062504 0.00620869 -0.0575326 0.0844647 0.00600869 -0.00699616 0.0844647 0.00600869 0.00700104 0.0711215 0.00620869 0.0464657 0.0709541 0.00600869 0.0463563 0.062504 0.00620869 0.0575375 0.0623568 0.00600869 0.0574021 0.0404359 0.00620869 0.0747137 0.0403408 0.00600869 0.0745378 0.0139865 0.00620869 0.0837938 4.20971e-06 0.00600869 0.0847524 0.0275874 0.00730869 0.0803496 0.0404359 0.00730869 0.0747137 0.0520587 0.00750869 0.0668821 0.0623568 0.00750869 0.0574021 0.0711215 0.00730869 0.0464657 0.0777992 0.00730869 0.0341265 0.0709541 0.00750869 0.0463563 0.077616 0.00750869 0.0340461 0.0821609 0.00750869 0.0208073 0.0844647 0.00750869 0.00700104 0.0823548 0.00730869 -0.0208516 0.0821609 0.00750869 -0.0208025 0.077616 0.00750869 -0.0340412 0.0709541 0.00750869 -0.0463514 0.0623568 0.00750869 -0.0573972 0.0520587 0.00750869 -0.0668772 0.0521816 0.00730869 -0.067035 0.0404359 0.00730869 -0.0747089 0.0139865 0.00730869 -0.083789 4.20971e-06 0.00730869 -0.0849476 0.0139865 0.00870869 -0.083789 0.0139536 0.00850869 -0.0835917 0.0623568 0.00850869 -0.0573972 0.0709541 0.00850869 -0.0463514 0.0821609 0.00850869 -0.0208025 0.0846641 0.00870869 0.00701756 0.0821609 0.00850869 0.0208073 0.0777992 0.00870869 0.0341265 0.062504 0.00870869 0.0575375 0.0521816 0.00870869 0.0670399 0.0404359 0.00870869 0.0747137 0.0275225 0.00850869 0.0801605 4.20971e-06 0.00870869 0.0849524 4.20971e-06 0.0100087 0.0847524 4.20971e-06 0.00980869 0.0849524 0.0139536 0.0100087 0.0835966 0.0275225 0.0100087 0.0801605 0.0275874 0.00980869 0.0803496 0.0403408 0.0100087 0.0745378 0.0520587 0.0100087 0.0668821 0.062504 0.00980869 0.0575375 0.0711215 0.00980869 0.0464657 0.0709541 0.0100087 0.0463563 0.0821609 0.0100087 0.0208073 0.0821609 0.0100087 -0.0208025 0.077616 0.0100087 -0.0340412 0.0777992 0.00980869 -0.0341216 0.0520587 0.0100087 -0.0668772 0.0275225 0.0100087 -0.0801556 0.0275874 0.00980869 -0.0803447 0.0139865 0.00980869 -0.083789 4.20971e-06 0.00980869 -0.0849476 0.0139536 0.0100087 -0.0835917 0.0139865 0.0112087 -0.083789 0.0139536 0.0110087 -0.0835917 0.0275225 0.0110087 -0.0801556 0.0404359 0.0112087 -0.0747089 0.0623568 0.0110087 -0.0573972 0.0709541 0.0110087 -0.0463514 0.0777992 0.0112087 -0.0341216 0.0823548 0.0112087 -0.0208516 0.077616 0.0110087 -0.0340412 0.0821609 0.0110087 -0.0208025 0.0844647 0.0110087 0.00700104 0.0846641 0.0112087 0.00701756 0.0777992 0.0112087 0.0341265 0.0711215 0.0112087 0.0464657 0.0709541 0.0110087 0.0463563 0.0623568 0.0110087 0.0574021 0.0521816 0.0112087 0.0670399 0.0404359 0.0112087 0.0747137 0.0275874 0.0123087 0.0803496 0.0275225 0.0125087 0.0801605 0.0404359 0.0123087 0.0747137 0.0520587 0.0125087 0.0668821 0.062504 0.0123087 0.0575375 0.0711215 0.0123087 0.0464657 0.0709541 0.0125087 0.0463563 0.077616 0.0125087 0.0340461 0.0844647 0.0125087 -0.00699616 0.0823548 0.0123087 -0.0208516 0.077616 0.0125087 -0.0340412 0.0777992 0.0123087 -0.0341216 0.0711215 0.0123087 -0.0464608 0.0709541 0.0125087 -0.0463514 0.062504 0.0123087 -0.0575326 0.0520587 0.0125087 -0.0668772 0.0403408 0.0125087 -0.074533 0.0275874 0.0123087 -0.0803447 0.0275225 0.0125087 -0.0801556 4.20971e-06 0.0123087 -0.0849476 4.20971e-06 0.0125087 -0.0847476 0.0139865 0.0137087 -0.083789 0.0139536 0.0135087 -0.0835917 0.0275874 0.0137087 -0.0803447 0.0275225 0.0135087 -0.0801556 0.0403408 0.0135087 -0.074533 0.0521816 0.0137087 -0.067035 0.0623568 0.0135087 -0.0573972 0.062504 0.0137087 -0.0575326 0.0709541 0.0135087 -0.0463514 0.0711215 0.0137087 -0.0464608 0.0777992 0.0137087 -0.0341216 0.0823548 0.0137087 0.0208564 0.077616 0.0135087 0.0340461 0.0711215 0.0137087 0.0464657 0.0623568 0.0135087 0.0574021 0.0520587 0.0135087 0.0668821 0.0139865 0.0137087 0.0837938 4.20971e-06 0.0137087 0.0849524 4.20971e-06 -0.00499131 -0.0844476 0.0139042 -0.00499131 -0.0832958 0.0274251 -0.00399131 -0.0798718 0.040198 -0.00399131 -0.0742691 0.0518745 -0.00399131 -0.0666405 0.0621361 -0.00399131 -0.057194 0.0841658 -0.00499131 -0.00697138 0.0818701 -0.00399131 0.0207337 0.0818701 -0.00499131 0.0207337 0.0773413 -0.00399131 0.0339256 0.0518745 -0.00399131 0.0666454 0.040198 -0.00499131 0.074274 0.0274251 -0.00399131 0.0798767 0.0274251 -0.00499131 0.0798767 0.0139042 -0.00399131 0.0833007 0.0139042 -0.00499131 0.0833007 4.20971e-06 -0.00399131 0.0844524 4.20971e-06 -0.00249131 -0.0844476 0.0139042 -0.00149131 -0.0832958 0.0274251 -0.00149131 -0.0798718 0.0139042 -0.00249131 -0.0832958 0.040198 -0.00149131 -0.0742691 0.0274251 -0.00249131 -0.0798718 0.0518745 -0.00149131 -0.0666405 0.0518745 -0.00249131 -0.0666405 0.0707029 -0.00249131 -0.0461873 0.0773413 -0.00149131 -0.0339207 0.0841658 -0.00149131 -0.00697138 0.0841658 -0.00249131 -0.00697138 0.0818701 -0.00149131 0.0207337 0.0773413 -0.00149131 0.0339256 0.0707029 -0.00249131 0.0461922 0.0707029 -0.00149131 0.0461922 0.0621361 -0.00149131 0.0571989 0.0518745 -0.00149131 0.0666454 0.040198 -0.00149131 0.074274 0.0518745 -0.00249131 0.0666454 0.040198 -0.00249131 0.074274 0.0274251 -0.00149131 0.0798767 4.20971e-06 -0.00149131 0.0844524 4.20971e-06 8.6865e-06 -0.0844476 0.0139042 0.00100869 -0.0832958 0.0274251 0.00100869 -0.0798718 0.0274251 8.6865e-06 -0.0798718 0.040198 0.00100869 -0.0742691 0.040198 8.6865e-06 -0.0742691 0.0518745 0.00100869 -0.0666405 0.0621361 0.00100869 -0.057194 0.0707029 0.00100869 -0.0461873 0.0773413 0.00100869 -0.0339207 0.0818701 0.00100869 -0.0207288 0.0818701 8.6865e-06 -0.0207288 0.0841658 0.00100869 -0.00697138 0.0841658 8.6865e-06 -0.00697138 0.0818701 0.00100869 0.0207337 0.0818701 8.6865e-06 0.0207337 0.0773413 8.6865e-06 0.0339256 0.0707029 0.00100869 0.0461922 0.0707029 8.6865e-06 0.0461922 0.0621361 0.00100869 0.0571989 0.0518745 8.6865e-06 0.0666454 0.0274251 8.6865e-06 0.0798767 0.0139042 0.00350869 -0.0832958 0.040198 0.00350869 -0.0742691 0.0274251 0.00250869 -0.0798718 0.0518745 0.00350869 -0.0666405 0.040198 0.00250869 -0.0742691 0.0518745 0.00250869 -0.0666405 0.0621361 0.00350869 -0.057194 0.0621361 0.00250869 -0.057194 0.0707029 0.00350869 -0.0461873 0.0773413 0.00250869 -0.0339207 0.0818701 0.00350869 -0.0207288 0.0818701 0.00250869 -0.0207288 0.0841658 0.00250869 -0.00697138 0.0841658 0.00350869 0.00697627 0.0841658 0.00250869 0.00697627 0.0818701 0.00250869 0.0207337 0.0773413 0.00250869 0.0339256 0.0707029 0.00350869 0.0461922 0.0621361 0.00350869 0.0571989 0.0707029 0.00250869 0.0461922 0.0518745 0.00350869 0.0666454 0.040198 0.00250869 0.074274 0.0274251 0.00250869 0.0798767 0.0139042 0.00600869 -0.0832958 0.040198 0.00500869 -0.0742691 0.0518745 0.00600869 -0.0666405 0.0621361 0.00500869 -0.057194 0.0621361 0.00600869 -0.057194 0.0818701 0.00500869 -0.0207288 0.0818701 0.00600869 -0.0207288 0.0841658 0.00600869 0.00697627 0.0841658 0.00500869 0.00697627 0.0818701 0.00600869 0.0207337 0.0818701 0.00500869 0.0207337 0.0621361 0.00600869 0.0571989 0.0518745 0.00600869 0.0666454 0.040198 0.00600869 0.074274 0.040198 0.00500869 0.074274 0.0274251 0.00600869 0.0798767 0.0139042 0.00600869 0.0833007 0.0274251 0.00500869 0.0798767 4.20971e-06 0.00500869 0.0844524 4.20971e-06 0.00850869 -0.0844476 0.0139042 0.00750869 -0.0832958 0.0139042 0.00850869 -0.0832958 0.0274251 0.00850869 -0.0798718 0.0274251 0.00750869 -0.0798718 0.040198 0.00850869 -0.0742691 0.040198 0.00750869 -0.0742691 0.0621361 0.00850869 -0.057194 0.0518745 0.00750869 -0.0666405 0.0621361 0.00750869 -0.057194 0.0707029 0.00750869 -0.0461873 0.0773413 0.00850869 -0.0339207 0.0773413 0.00750869 -0.0339207 0.0818701 0.00750869 -0.0207288 0.0818701 0.00850869 -0.0207288 0.0841658 0.00750869 -0.00697138 0.0841658 0.00850869 0.00697627 0.0818701 0.00750869 0.0207337 0.0707029 0.00850869 0.0461922 0.0773413 0.00750869 0.0339256 0.0621361 0.00850869 0.0571989 0.0621361 0.00750869 0.0571989 0.0518745 0.00750869 0.0666454 0.040198 0.00850869 0.074274 0.040198 0.00750869 0.074274 0.0274251 0.00850869 0.0798767 0.0139042 0.00750869 0.0833007 0.0139042 0.00850869 0.0833007 4.20971e-06 0.0100087 -0.0844476 0.0139042 0.0110087 -0.0832958 0.0274251 0.0110087 -0.0798718 0.0518745 0.0100087 -0.0666405 0.0707029 0.0110087 -0.0461873 0.0773413 0.0100087 -0.0339207 0.0818701 0.0110087 -0.0207288 0.0841658 0.0100087 -0.00697138 0.0841658 0.0100087 0.00697627 0.0818701 0.0110087 0.0207337 0.0818701 0.0100087 0.0207337 0.0707029 0.0100087 0.0461922 0.040198 0.0100087 0.074274 0.040198 0.0125087 -0.0742691 0.0518745 0.0135087 -0.0666405 0.0621361 0.0125087 -0.057194 0.0773413 0.0135087 -0.0339207 0.0818701 0.0135087 -0.0207288 0.0841658 0.0135087 -0.00697138 0.0841658 0.0125087 -0.00697138 0.0818701 0.0135087 0.0207337 0.0818701 0.0125087 0.0207337 0.0707029 0.0125087 0.0461922 0.0518745 0.0135087 0.0666454 0.0139042 0.0135087 0.0833007 0.0139042 0.0125087 0.0833007 0.0139865 0.0148087 0.0837938 0.0139536 0.0150087 0.0835966 0.0403408 0.0150087 0.0745378 0.0520587 0.0150087 0.0668821 0.062504 0.0148087 0.0575375 0.0709541 0.0150087 0.0463563 0.077616 0.0150087 0.0340461 0.0821609 0.0150087 0.0208073 0.0846641 0.0148087 0.00701756 0.0844647 0.0150087 -0.00699616 0.0846641 0.0148087 -0.00701267 0.0777992 0.0148087 -0.0341216 0.0821609 0.0150087 -0.0208025 0.077616 0.0150087 -0.0340412 0.0711215 0.0148087 -0.0464608 0.0520587 0.0150087 -0.0668772 0.0404359 0.0148087 -0.0747089 0.0275225 0.0150087 -0.0801556 0.0139865 0.0162087 -0.083789 0.0139536 0.0160087 -0.0835917 0.0404359 0.0162087 -0.0747089 0.0403408 0.0160087 -0.074533 0.0521816 0.0162087 -0.067035 0.0520587 0.0160087 -0.0668772 0.062504 0.0162087 -0.0575326 0.0711215 0.0162087 -0.0464608 0.0709541 0.0160087 -0.0463514 0.0821609 0.0160087 -0.0208025 0.0844647 0.0160087 -0.00699616 0.0844647 0.0160087 0.00700104 0.0777992 0.0162087 0.0341265 0.0821609 0.0160087 0.0208073 0.077616 0.0160087 0.0340461 0.062504 0.0162087 0.0575375 0.0520587 0.0160087 0.0668821 0.0403408 0.0160087 0.0745378 0.0275874 0.0162087 0.0803496 0.0139865 0.0162087 0.0837938 4.20971e-06 0.0162087 0.0849524 0.0139042 0.0160087 -0.0832958 0.0139042 0.0150087 -0.0832958 0.040198 0.0160087 -0.0742691 0.0518745 0.0150087 -0.0666405 0.0621361 0.0150087 -0.057194 0.0707029 0.0150087 -0.0461873 0.0707029 0.0160087 -0.0461873 0.0773413 0.0150087 -0.0339207 0.0841658 0.0160087 -0.00697138 0.0818701 0.0160087 0.0207337 0.0841658 0.0150087 0.00697627 0.0818701 0.0150087 0.0207337 0.0707029 0.0160087 0.0461922 0.0621361 0.0150087 0.0571989 0.0518745 0.0150087 0.0666454 0.040198 0.0150087 0.074274 0.040198 0.0160087 0.074274 0.0274251 0.0150087 0.0798767 4.20971e-06 0.0160087 0.0844524 -0.0419958 -0.0129163 -0.010665 -0.0519958 -0.0129163 -0.010665 -0.0519958 -0.0124588 -0.0111226 -0.0419958 -0.0124588 -0.0111226 -0.0419958 -0.0122913 -0.0117476 -0.0519958 -0.0122913 -0.0117476 -0.0419958 -0.0129163 -0.0128301 -0.0519958 -0.0129163 -0.0128301 -0.0419958 -0.0135413 -0.0104976 -0.0419958 -0.0135413 -0.0129976 -0.0419958 -0.0124588 -0.0123726 -0.0419958 -0.0135413 0.0130024 -0.0419958 -0.0129163 0.012835 -0.0519958 -0.0129163 0.012835 -0.0419958 -0.0124588 0.0111274 -0.0519958 -0.0124588 0.0111274 -0.0419958 -0.0129163 0.0106699 -0.0419958 -0.0135413 0.0105024 -0.0519958 -0.0135413 0.0105024 -0.0419958 -0.0124588 0.0123774 -0.0419958 -0.0122913 0.0117524 0.0520042 -0.0129163 -0.0128301 0.0420042 -0.0122913 -0.0117476 0.0520042 -0.0122913 -0.0117476 0.0420042 -0.0129163 -0.010665 0.0520042 -0.0129163 -0.010665 0.0420042 -0.0124588 -0.0123726 0.0420042 -0.0129163 -0.0128301 0.0420042 -0.0124588 -0.0111226 0.0412531 -0.0135413 -0.0117476 0.0420042 -0.0135413 0.0105024 0.0420042 -0.0129163 0.0106699 0.0520042 -0.0129163 0.0106699 0.0420042 -0.0122913 0.0117524 0.0520042 -0.0124588 0.0123774 0.0420042 -0.0124588 0.0111274 0.0420042 -0.0129163 0.012835 0.0420042 -0.0124588 0.0123774 0.0412531 -0.0135413 0.0117524 -0.0791648 0.0172587 -0.0217283 -0.0801373 0.0180087 -0.021394 -0.0791648 0.0172587 -0.0201696 -0.0797511 0.0180087 -0.019702 -0.0781875 0.0172587 -0.022199 -0.0787298 0.0172587 -0.0220752 -0.0791648 0.00645869 -0.0217283 -0.0794061 0.00645869 -0.0212271 -0.0794061 0.0172587 -0.0212271 -0.0794061 0.0172587 -0.0206708 -0.0794061 0.00645869 -0.0206708 -0.0787298 0.0172587 -0.0198228 -0.0788125 0.00645869 -0.0198664 -0.0799195 0.00570869 -0.021949 -0.0788125 0.00645869 -0.0220315 -0.07927 0.00645869 -0.021574 -0.0794375 0.00645869 -0.020949 -0.0781875 0.00645869 -0.019699 -0.0791875 0.00570869 -0.0192169 -0.0791648 0.00645869 -0.0201696 -0.0799195 0.00570869 -0.019949 -0.07927 0.00645869 -0.020324 -0.0572361 0.0172587 -0.0584879 -0.0572361 0.0180087 -0.0592379 -0.0577784 0.0172587 -0.0583641 -0.0581039 0.0180087 -0.0590398 -0.0582134 0.0172587 -0.0580172 -0.0584547 0.0172587 -0.057516 -0.0584547 0.0172587 -0.0569597 -0.0591859 0.0180087 -0.0576829 -0.0591859 0.0180087 -0.0567928 -0.0582134 0.0172587 -0.0564585 -0.0581039 0.0180087 -0.0554359 -0.0582134 0.00645869 -0.0580172 -0.0583186 0.00645869 -0.0578629 -0.0584547 0.00645869 -0.057516 -0.0584861 0.00645869 -0.0572379 -0.0584547 0.00645869 -0.0569597 -0.0583186 0.00645869 -0.0566129 -0.0577784 0.0172587 -0.0561116 -0.0572361 0.00570869 -0.0592379 -0.0572361 0.00645869 -0.0584879 -0.0578611 0.00645869 -0.0583204 -0.0592361 0.00570869 -0.0572379 -0.0589681 0.00570869 -0.0562379 -0.0578611 0.00645869 -0.0561553 -0.0572361 0.00570869 -0.0552379 -0.0582134 0.00645869 -0.0564585 -0.0582361 0.00570869 -0.0555058 -0.0209472 0.0172587 -0.0794393 -0.0215722 0.0172587 -0.0792718 -0.0219472 0.0180087 -0.0799213 -0.0220297 0.0172587 -0.0788143 -0.0221972 0.0172587 -0.0781893 -0.0220297 0.0172587 -0.0775643 -0.0226792 0.0180087 -0.0771893 -0.0215722 0.0172587 -0.0771067 -0.0219472 0.0180087 -0.0764572 -0.0221972 0.00645869 -0.0781893 -0.0220297 0.00645869 -0.0775643 -0.0215722 0.00645869 -0.0771067 -0.0226792 0.00570869 -0.0771893 -0.0220297 0.00645869 -0.0788143 -0.0215722 0.00645869 -0.0792718 -0.0209472 0.00645869 -0.0794393 -0.0794375 -0.00799131 -0.0187839 -0.0781875 -0.00829131 -0.018149 -0.0806124 -0.00829131 -0.019549 -0.0806124 -0.00829131 -0.022349 -0.0795875 -0.00829131 -0.0233738 -0.0781875 -0.00799131 -0.023449 -0.0781875 -0.00829131 -0.023749 -0.0803526 0.00570869 -0.019699 -0.0803526 -0.00799131 -0.019699 -0.0803526 0.00570869 -0.022199 -0.0806875 -0.00799131 -0.020949 -0.0803526 -0.00799131 -0.022199 -0.0794375 0.00570869 -0.023114 -0.0794375 -0.00799131 -0.023114 -0.0781875 0.00570869 -0.023449 -0.0594011 -0.00799131 -0.0584879 -0.0600361 -0.00829131 -0.0572379 -0.059661 -0.00829131 -0.0586379 -0.0586361 -0.00829131 -0.0596627 -0.0572361 -0.00799131 -0.0597379 -0.0584861 0.00570869 -0.0550728 -0.0584861 -0.00799131 -0.0550728 -0.0594011 -0.00799131 -0.0559879 -0.0597361 -0.00799131 -0.0572379 -0.0584861 -0.00799131 -0.0594029 -0.0231123 -0.00799131 -0.0769393 -0.0233721 -0.00829131 -0.0767893 -0.0234472 -0.00799131 -0.0781893 -0.0231123 -0.00799131 -0.0794393 -0.0233721 -0.00829131 -0.0795893 -0.0221972 0.00570869 -0.0760242 -0.0221972 -0.00799131 -0.0760242 -0.0234472 0.00570869 -0.0781893 -0.0221972 -0.00799131 -0.0803543 -0.0209472 0.00570869 -0.0806893 -0.0771698 -0.00799131 -0.0298782 -0.0773351 -0.00799131 -0.0297908 -0.0788149 -0.00829131 -0.0282488 -0.0785224 -0.00799131 -0.0281821 -0.0780397 -0.00799131 -0.0260671 -0.0760851 -0.00799131 -0.0251258 -0.0760851 -0.00829131 -0.0248258 -0.0771698 -0.00799131 -0.0253734 -0.0643921 -0.00829131 -0.0534787 -0.0644045 -0.00799131 -0.052635 -0.0647672 -0.00829131 -0.0520787 -0.0633672 -0.00829131 -0.0496539 -0.0531617 -0.00799131 -0.0642214 -0.053327 -0.00799131 -0.064134 -0.0540315 -0.00799131 -0.0635277 -0.0542661 -0.00829131 -0.0637147 -0.054242 -0.00799131 -0.063219 -0.0548068 -0.00829131 -0.062592 -0.054577 -0.00799131 -0.061969 -0.0545143 -0.00799131 -0.0614127 -0.0542661 -0.00829131 -0.0602232 -0.054242 -0.00799131 -0.060719 -0.0531617 -0.00799131 -0.0597165 -0.0532918 -0.00829131 -0.0594462 -0.053327 -0.00799131 -0.0598039 -0.0540315 -0.00799131 -0.0604102 -0.029024 -0.00829131 -0.073662 -0.0297891 -0.00799131 -0.0748369 -0.028874 -0.00799131 -0.0782519 -0.029024 -0.00829131 -0.0785117 -0.027624 -0.00829131 -0.0788869 -0.0760851 0.0177087 -0.0301258 -0.0782502 0.0177087 -0.0288758 -0.0774851 0.0180087 -0.0300507 -0.07851 0.0180087 -0.0290258 -0.0785851 0.0177087 -0.0276258 -0.0788851 0.0180087 -0.0276258 -0.07851 0.0180087 -0.0262258 -0.0782502 0.0177087 -0.0263758 -0.0760851 0.0177087 -0.0251258 -0.0774851 0.0180087 -0.0252009 -0.0780397 -0.00799131 -0.0291845 -0.0773351 0.0177087 -0.0297908 -0.0782502 -0.00799131 -0.0288758 -0.0785851 -0.00799131 -0.0276258 -0.0785224 -0.00799131 -0.0270695 -0.0782502 -0.00799131 -0.0263758 -0.0773351 0.0177087 -0.0254607 -0.0773351 -0.00799131 -0.0254607 -0.0619672 0.0177087 -0.0545787 -0.0639218 0.0177087 -0.0536374 -0.0631821 0.0180087 -0.0546014 -0.064697 0.0180087 -0.0514557 -0.0639218 0.0177087 -0.05052 -0.0641563 0.0180087 -0.050333 -0.0630519 0.0177087 -0.0498263 -0.0619672 -0.00799131 -0.0545787 -0.0630519 0.0177087 -0.0543311 -0.0632172 -0.00799131 -0.0542438 -0.0639218 -0.00799131 -0.0536374 -0.0641323 -0.00799131 -0.0533287 -0.0644045 0.0177087 -0.052635 -0.0644045 0.0177087 -0.0515224 -0.0644672 -0.00799131 -0.0520787 -0.0644045 -0.00799131 -0.0515224 -0.0641323 -0.00799131 -0.0508287 -0.0639218 -0.00799131 -0.05052 -0.0632172 -0.00799131 -0.0499137 -0.0619672 0.0177087 -0.0495787 -0.054242 0.0177087 -0.063219 -0.054877 0.0180087 -0.061969 -0.0545018 0.0180087 -0.060569 -0.053477 0.0180087 -0.0595441 -0.052077 0.0180087 -0.059169 -0.052077 -0.00799131 -0.064469 -0.052077 0.0177087 -0.064469 -0.053327 0.0177087 -0.064134 -0.0545143 -0.00799131 -0.0625253 -0.054577 0.0177087 -0.061969 -0.054242 0.0177087 -0.060719 -0.053327 0.0177087 -0.0598039 -0.052077 0.0177087 -0.059469 -0.052077 -0.00799131 -0.059469 -0.0287087 0.0177087 -0.0738344 -0.0295786 0.0177087 -0.0745282 -0.0303538 0.0180087 -0.0754638 -0.0297891 0.0177087 -0.0748369 -0.030124 0.0177087 -0.0760869 -0.0297891 0.0177087 -0.0773369 -0.0295786 0.0177087 -0.0776456 -0.027624 0.0180087 -0.0788869 -0.0288389 0.0180087 -0.0786096 -0.027624 -0.00799131 -0.0785869 -0.0287087 0.0177087 -0.0783393 -0.028874 0.0177087 -0.0782519 -0.0297891 -0.00799131 -0.0773369 -0.0300613 0.0177087 -0.0766432 -0.030124 -0.00799131 -0.0760869 -0.0300613 0.0177087 -0.0755306 -0.028874 -0.00799131 -0.0739218 -0.028874 0.0177087 -0.0739218 0.0781959 0.0172587 -0.022199 0.0761959 0.0180087 -0.020949 0.0775709 0.0172587 -0.0220315 0.0771134 0.0172587 -0.021574 0.0769459 0.0172587 -0.020949 0.0771134 0.0172587 -0.020324 0.0771134 0.00645869 -0.020324 0.0775709 0.0172587 -0.0198664 0.0781959 0.00645869 -0.019699 0.0775709 0.00645869 -0.0198664 0.0761959 0.00570869 -0.020949 0.0769459 0.00645869 -0.020949 0.0771134 0.00645869 -0.021574 0.0775709 0.00645869 -0.0220315 0.0764639 0.00570869 -0.021949 0.0781959 0.00645869 -0.022199 0.0572445 0.0180087 -0.0592379 0.056162 0.0172587 -0.0578629 0.0555125 0.0180087 -0.0582379 0.0559945 0.0172587 -0.0572379 0.0552445 0.0180087 -0.0572379 0.0572445 0.0180087 -0.0552379 0.0566195 0.0172587 -0.0583204 0.0566195 0.00645869 -0.0583204 0.056162 0.00645869 -0.0578629 0.0559945 0.00645869 -0.0572379 0.056162 0.0172587 -0.0566129 0.0566195 0.0172587 -0.0561553 0.0572445 0.00645869 -0.0559879 0.0572445 0.00645869 -0.0584879 0.0567021 0.00645869 -0.0583641 0.0562672 0.00645869 -0.0580172 0.0560258 0.00645869 -0.057516 0.0552946 0.00570869 -0.0567928 0.0560258 0.00645869 -0.0569597 0.056162 0.00645869 -0.0566129 0.0562672 0.00645869 -0.0564585 0.0556808 0.00570869 -0.0559909 0.0567021 0.00645869 -0.0561116 0.0563767 0.00570869 -0.0554359 0.0566195 0.00645869 -0.0561553 0.0199783 0.0172587 -0.0789686 0.019737 0.0172587 -0.0784674 0.019737 0.0172587 -0.0779111 0.0190058 0.0180087 -0.0786343 0.0193919 0.0180087 -0.0769423 0.0204133 0.0172587 -0.077063 0.0209556 0.0180087 -0.0761893 0.0204133 0.0172587 -0.0793155 0.019737 0.00645869 -0.0784674 0.019737 0.00645869 -0.0779111 0.0199783 0.0172587 -0.0774099 0.0204133 0.00645869 -0.077063 0.0209556 0.00645869 -0.0769393 0.0200878 0.00570869 -0.0763873 0.0199783 0.00645869 -0.0774099 0.0190058 0.00570869 -0.0777442 0.0193919 0.00570869 -0.0794362 0.0199783 0.00645869 -0.0789686 0.0204133 0.00645869 -0.0793155 0.0209556 0.00645869 -0.0794393 0.0209556 0.00570869 -0.0801893 0.0781959 -0.00829131 -0.018149 0.076981 -0.00829131 -0.0184262 0.0771112 -0.00799131 -0.0186965 0.0757586 -0.00799131 -0.0215053 0.0754661 -0.00829131 -0.021572 0.0771112 -0.00799131 -0.0232014 0.0760068 -0.00829131 -0.0226947 0.0781959 -0.00799131 -0.023449 0.0781959 -0.00799131 -0.018449 0.0771112 0.00570869 -0.0186965 0.0762413 0.00570869 -0.0193902 0.0762413 -0.00799131 -0.0193902 0.0757586 -0.00799131 -0.0203927 0.0762413 0.00570869 -0.0225077 0.0762413 -0.00799131 -0.0225077 0.0572445 -0.00829131 -0.0544379 0.0558445 -0.00829131 -0.054813 0.0547445 -0.00799131 -0.0572379 0.0544445 -0.00829131 -0.0572379 0.0548196 -0.00829131 -0.0586379 0.0559945 -0.00799131 -0.0594029 0.0558445 -0.00829131 -0.0596627 0.0572445 -0.00799131 -0.0547379 0.0559945 -0.00799131 -0.0550728 0.0550794 -0.00799131 -0.0559879 0.0550794 -0.00799131 -0.0584879 0.0559945 0.00570869 -0.0594029 0.0195556 -0.00829131 -0.0757644 0.0184556 -0.00799131 -0.0781893 0.0181556 -0.00829131 -0.0781893 0.0187905 -0.00799131 -0.0794393 0.0195556 -0.00829131 -0.0806141 0.0209556 -0.00799131 -0.0806893 0.0209556 0.00570869 -0.0756893 0.0209556 -0.00799131 -0.0756893 0.0197056 -0.00799131 -0.0760242 0.0187905 0.00570869 -0.0769393 0.0187905 -0.00799131 -0.0769393 0.0187905 0.00570869 -0.0794393 0.0197056 0.00570869 -0.0803543 0.0197056 -0.00799131 -0.0803543 0.0209556 0.00570869 -0.0806893 0.0746935 -0.00829131 -0.0252009 0.0739285 -0.00799131 -0.0263758 0.0736687 -0.00829131 -0.0262258 0.0732935 -0.00829131 -0.0276258 0.0736687 -0.00829131 -0.0290258 0.0760935 -0.00799131 -0.0301258 0.0605756 -0.00829131 -0.0545036 0.0595507 -0.00829131 -0.0534787 0.0607256 -0.00799131 -0.0542438 0.060021 -0.00799131 -0.0536374 0.0591756 -0.00829131 -0.0520787 0.0595383 -0.00799131 -0.052635 0.0595383 -0.00799131 -0.0515224 0.0595507 -0.00829131 -0.0506787 0.0607256 -0.00799131 -0.0499137 0.0520854 -0.00829131 -0.064769 0.0506854 -0.00829131 -0.0643938 0.0501308 -0.00799131 -0.0635277 0.0496481 -0.00799131 -0.0625253 0.0492854 -0.00829131 -0.061969 0.0496481 -0.00799131 -0.0614127 0.0508354 -0.00799131 -0.0598039 0.0506854 -0.00829131 -0.0595441 0.0496605 -0.00829131 -0.060569 0.0262324 -0.00829131 -0.073662 0.0252076 -0.00829131 -0.0774869 0.0748435 0.0177087 -0.0297908 0.0736687 0.0180087 -0.0290258 0.0736687 0.0180087 -0.0262258 0.0739285 0.0177087 -0.0263758 0.0748435 0.0177087 -0.0254607 0.0746935 0.0180087 -0.0252009 0.0748435 -0.00799131 -0.0297908 0.0739285 -0.00799131 -0.0288758 0.0735935 -0.00799131 -0.0276258 0.0739285 0.0177087 -0.0288758 0.0735935 0.0177087 -0.0276258 0.0748435 -0.00799131 -0.0254607 0.0760935 -0.00799131 -0.0251258 0.0592458 0.0180087 -0.0527018 0.0595383 0.0177087 -0.0515224 0.0592458 0.0180087 -0.0514557 0.060021 0.0177087 -0.05052 0.0597865 0.0180087 -0.050333 0.0619756 0.0180087 -0.0492787 0.0619756 -0.00799131 -0.0545787 0.0608909 0.0177087 -0.0543311 0.0598105 -0.00799131 -0.0533287 0.060021 0.0177087 -0.0536374 0.0594756 -0.00799131 -0.0520787 0.0595383 0.0177087 -0.052635 0.0598105 -0.00799131 -0.0508287 0.060021 -0.00799131 -0.05052 0.0608909 0.0177087 -0.0498263 0.0510007 0.0177087 -0.0642214 0.0520854 0.0180087 -0.064769 0.0498962 0.0180087 -0.0637147 0.0493556 0.0180087 -0.062592 0.0496481 0.0177087 -0.0614127 0.0520854 0.0177087 -0.059469 0.0508705 0.0180087 -0.0594462 0.0520854 0.0177087 -0.064469 0.0508354 -0.00799131 -0.064134 0.0501308 0.0177087 -0.0635277 0.0499203 -0.00799131 -0.063219 0.0496481 0.0177087 -0.0625253 0.0495854 -0.00799131 -0.061969 0.0501308 0.0177087 -0.0604102 0.0499203 -0.00799131 -0.060719 0.0501308 -0.00799131 -0.0604102 0.0510007 0.0177087 -0.0597165 0.0264176 0.0180087 -0.0735642 0.0265477 0.0177087 -0.0738344 0.0254433 0.0180087 -0.0743411 0.0254674 0.0177087 -0.0748369 0.0251324 0.0177087 -0.0760869 0.0251951 0.0177087 -0.0766432 0.0254433 0.0180087 -0.0778326 0.0256779 0.0177087 -0.0776456 0.0263824 0.0177087 -0.0782519 0.0276324 0.0177087 -0.0785869 0.0265477 0.0177087 -0.0783393 0.0263824 -0.00799131 -0.0782519 0.0254674 0.0177087 -0.0773369 0.0254674 -0.00799131 -0.0773369 0.0251324 -0.00799131 -0.0760869 0.0251951 0.0177087 -0.0755306 0.0254674 -0.00799131 -0.0748369 0.0276324 0.0177087 -0.0735869 0.0276324 -0.00799131 -0.0735869 0.0263824 -0.00799131 -0.0739218 0.0263824 0.0177087 -0.0739218 0.0256779 0.0177087 -0.0745282 -0.0781875 0.0180087 0.0189538 -0.0791875 0.0180087 0.0192218 -0.07927 0.0172587 0.0203288 -0.0794375 0.0172587 0.0209538 -0.0801875 0.0180087 0.0209538 -0.07927 0.0172587 0.0215788 -0.0799195 0.0180087 0.0219538 -0.0781875 0.0172587 0.0222038 -0.0791875 0.0180087 0.0226859 -0.0788125 0.0172587 0.0198713 -0.0794375 0.00645869 0.0209538 -0.07927 0.00645869 0.0215788 -0.0788125 0.00645869 0.0220364 -0.0788125 0.0172587 0.0220364 -0.0781875 0.00645869 0.0222038 -0.07927 0.00645869 0.0203288 -0.0799195 0.00570869 0.0199538 -0.0788125 0.00645869 0.0198713 -0.0781875 0.00645869 0.0197038 -0.0578611 0.0172587 0.0561602 -0.0582361 0.0180087 0.0555107 -0.0589681 0.0180087 0.0562427 -0.0584861 0.0172587 0.0572427 -0.0592361 0.0180087 0.0572427 -0.0589681 0.0180087 0.0582427 -0.0578611 0.0172587 0.0583253 -0.0578611 0.00645869 0.0561602 -0.0583186 0.00645869 0.0566177 -0.0583186 0.0172587 0.0566177 -0.0584861 0.00645869 0.0572427 -0.0583186 0.00645869 0.0578677 -0.0578611 0.00645869 0.0583253 -0.0583186 0.0172587 0.0578677 -0.0572361 0.00645869 0.0584927 -0.0572361 0.00570869 0.0592427 -0.0582361 0.00570869 0.0589748 -0.0589681 0.00570869 0.0582427 -0.0592361 0.00570869 0.0572427 -0.0589681 0.00570869 0.0562427 -0.0582361 0.00570869 0.0555107 -0.0220297 0.0172587 0.0775691 -0.0221972 0.0172587 0.0781941 -0.0229472 0.0180087 0.0781941 -0.0220297 0.0172587 0.0788191 -0.0209472 0.0172587 0.0794441 -0.0209472 0.00645869 0.0769441 -0.0215722 0.00645869 0.0771116 -0.0215722 0.0172587 0.0771116 -0.0221972 0.00645869 0.0781941 -0.0209472 0.00645869 0.0794441 -0.0215722 0.0172587 0.0792767 -0.0215722 0.00645869 0.0792767 -0.0219472 0.00570869 0.0799262 -0.0220297 0.00645869 0.0788191 -0.0220297 0.00645869 0.0775691 -0.0226792 0.00570869 0.0771941 -0.0209472 0.00570869 0.0761941 -0.0781875 -0.00829131 0.0237538 -0.0806875 -0.00799131 0.0209538 -0.0809875 -0.00829131 0.0209538 -0.0806124 -0.00829131 0.0195538 -0.0795875 -0.00829131 0.018529 -0.0794375 -0.00799131 0.0231189 -0.0803526 -0.00799131 0.0222038 -0.0803526 -0.00799131 0.0197038 -0.0803526 0.00570869 0.0197038 -0.0794375 0.00570869 0.0187888 -0.0794375 -0.00799131 0.0187888 -0.0781875 0.00570869 0.0184538 -0.058451 -0.00829131 0.0597654 -0.0599659 -0.00829131 0.0566197 -0.0572361 -0.00799131 0.0547427 -0.058451 -0.00829131 0.05472 -0.0583208 -0.00799131 0.0594952 -0.0591907 -0.00799131 0.0588015 -0.0596734 0.00570869 0.057799 -0.0596734 -0.00799131 0.057799 -0.0596734 0.00570869 0.0566864 -0.0596734 -0.00799131 0.0566864 -0.0591907 -0.00799131 0.055684 -0.0583208 -0.00799131 0.0549903 -0.0583208 0.00570869 0.0549903 -0.0209472 -0.00829131 0.0809941 -0.0221621 -0.00829131 0.0807168 -0.0231363 -0.00829131 0.0799399 -0.0229018 -0.00799131 0.0797529 -0.0233845 -0.00799131 0.0776378 -0.023677 -0.00829131 0.0775711 -0.0229018 -0.00799131 0.0766354 -0.0231363 -0.00829131 0.0764484 -0.0221621 -0.00829131 0.0756714 -0.0209472 -0.00829131 0.0753941 -0.0209472 -0.00799131 0.0806941 -0.0220319 0.00570869 0.0804466 -0.0220319 -0.00799131 0.0804466 -0.0233845 -0.00799131 0.0787504 -0.0220319 0.00570869 0.0759417 -0.0220319 -0.00799131 0.0759417 -0.0774851 -0.00829131 0.0252058 -0.0773351 -0.00799131 0.0254656 -0.0780397 -0.00799131 0.0260719 -0.0785851 -0.00799131 0.0276307 -0.0760851 -0.00799131 0.0301307 -0.07851 -0.00829131 0.0290307 -0.0785224 -0.00799131 0.028187 -0.0633672 -0.00829131 0.0496587 -0.0639218 -0.00799131 0.0505249 -0.0641323 -0.00799131 0.0508336 -0.0644045 -0.00799131 0.0515273 -0.0639218 -0.00799131 0.0536423 -0.053327 -0.00799131 0.0598088 -0.0545018 -0.00829131 0.0605738 -0.054242 -0.00799131 0.0607238 -0.0545143 -0.00799131 0.0614175 -0.054577 -0.00799131 0.0619738 -0.0545143 -0.00799131 0.0625301 -0.053327 -0.00799131 0.0641389 -0.0540315 -0.00799131 0.0635326 -0.0545018 -0.00829131 0.0633738 -0.054242 -0.00799131 0.0632238 -0.028874 -0.00799131 0.0739267 -0.0298131 -0.00829131 0.074346 -0.0295786 -0.00799131 0.074533 -0.0303538 -0.00829131 0.0767148 -0.0297891 -0.00799131 0.0773418 -0.0295786 -0.00799131 0.0776505 -0.0298131 -0.00829131 0.0778375 -0.027624 -0.00829131 0.0788918 -0.0287087 -0.00799131 0.0783442 -0.0760851 0.0180087 0.0248307 -0.0773 0.0180087 0.025108 -0.0771698 0.0177087 0.0253782 -0.0785224 0.0177087 0.0270744 -0.0785224 0.0177087 0.028187 -0.0780397 0.0177087 0.0291894 -0.0760851 0.0177087 0.0301307 -0.0760851 -0.00799131 0.0251307 -0.0760851 0.0177087 0.0251307 -0.0782502 -0.00799131 0.0263807 -0.0780397 0.0177087 0.0260719 -0.0785224 -0.00799131 0.0270744 -0.0782502 -0.00799131 0.0288807 -0.0780397 -0.00799131 0.0291894 -0.0773351 -0.00799131 0.0297957 -0.0771698 0.0177087 0.0298831 -0.0641563 0.0180087 0.0503378 -0.0644045 0.0177087 0.0526399 -0.0630519 0.0177087 0.054336 -0.0619672 0.0177087 0.0545836 -0.0632172 -0.00799131 0.0499185 -0.0630519 0.0177087 0.0498312 -0.0639218 0.0177087 0.0505249 -0.0644045 0.0177087 0.0515273 -0.0644672 -0.00799131 0.0520836 -0.0644045 -0.00799131 0.0526399 -0.0641323 -0.00799131 0.0533336 -0.0639218 0.0177087 0.0536423 -0.0632172 -0.00799131 0.0542487 -0.052077 0.0177087 0.0594738 -0.0542661 0.0180087 0.0602281 -0.0548068 0.0180087 0.0613508 -0.0545143 0.0177087 0.0625301 -0.0540315 0.0177087 0.0635326 -0.0531617 0.0177087 0.0642263 -0.0532918 0.0180087 0.0644966 -0.052077 0.0177087 0.0644738 -0.0531617 0.0177087 0.0597214 -0.0540315 -0.00799131 0.0604151 -0.0540315 0.0177087 0.0604151 -0.0545143 0.0177087 0.0614175 -0.028874 0.0177087 0.0739267 -0.027624 0.0180087 0.0732918 -0.0300489 0.0180087 0.0746918 -0.030124 0.0177087 0.0760918 -0.030424 0.0180087 0.0760918 -0.0297891 0.0177087 0.0773418 -0.027624 0.0177087 0.0785918 -0.027624 0.0177087 0.0735918 -0.0287087 -0.00799131 0.0738393 -0.0297891 0.0177087 0.0748418 -0.0297891 -0.00799131 0.0748418 -0.0300613 -0.00799131 0.0755355 -0.030124 -0.00799131 0.0760918 -0.0300613 -0.00799131 0.0766481 -0.028874 -0.00799131 0.0782568 -0.028874 0.0177087 0.0782568 0.0781959 0.0180087 0.0189538 0.0764639 0.0180087 0.0199538 0.0761959 0.0180087 0.0209538 0.0764639 0.0180087 0.0219538 0.0781959 0.0180087 0.0229538 0.0775709 0.00645869 0.0198713 0.0775709 0.0172587 0.0198713 0.0771134 0.00645869 0.0203288 0.0771134 0.0172587 0.0203288 0.0771134 0.00645869 0.0215788 0.0769459 0.0172587 0.0209538 0.0771134 0.0172587 0.0215788 0.0775709 0.0172587 0.0220364 0.0775709 0.00645869 0.0220364 0.0769459 0.00645869 0.0209538 0.0761959 0.00570869 0.0209538 0.0764639 0.00570869 0.0199538 0.0771959 0.00570869 0.0192218 0.0572445 0.0180087 0.0552427 0.0563767 0.0180087 0.0554408 0.0556808 0.0180087 0.0559958 0.0560258 0.0172587 0.0569646 0.0560258 0.0172587 0.0575209 0.0562672 0.0172587 0.0580221 0.0556808 0.0180087 0.0584897 0.0572445 0.0172587 0.0584927 0.0572445 0.00645869 0.0559927 0.0572445 0.0172587 0.0559927 0.0567021 0.0172587 0.0561165 0.0566195 0.00645869 0.0561602 0.0562672 0.00645869 0.0564634 0.056162 0.00645869 0.0566177 0.0562672 0.0172587 0.0564634 0.0559945 0.00645869 0.0572427 0.056162 0.00645869 0.0578677 0.0567021 0.0172587 0.0583689 0.0560258 0.00645869 0.0569646 0.0552445 0.00570869 0.0572427 0.0560258 0.00645869 0.0575209 0.0555125 0.00570869 0.0582427 0.0566195 0.00645869 0.0583253 0.0562445 0.00570869 0.0589748 0.0562672 0.00645869 0.0580221 0.0199783 0.0172587 0.0774148 0.0193919 0.0180087 0.0769472 0.019737 0.0172587 0.0784723 0.0193919 0.0180087 0.0794411 0.0209556 0.0172587 0.0794441 0.0209556 0.0172587 0.0769441 0.0204133 0.0172587 0.0770679 0.0199783 0.00645869 0.0774148 0.0198731 0.00645869 0.0775691 0.019737 0.0172587 0.077916 0.0197056 0.00645869 0.0781941 0.019737 0.00645869 0.0784723 0.0199783 0.0172587 0.0789735 0.0204133 0.0172587 0.0793203 0.0199556 0.00570869 0.0764621 0.0203306 0.00645869 0.0771116 0.019737 0.00645869 0.077916 0.0203306 0.00645869 0.0792767 0.0199556 0.00570869 0.0799262 0.0199783 0.00645869 0.0789735 0.0192236 0.00570869 0.0791941 0.0198731 0.00645869 0.0788191 0.0781959 -0.00829131 0.0237538 0.0771112 -0.00799131 0.0232063 0.0760068 -0.00829131 0.0226996 0.0757586 -0.00799131 0.0215101 0.0757586 -0.00799131 0.0203975 0.0762413 -0.00799131 0.0193951 0.0760068 -0.00829131 0.0192081 0.0771112 -0.00799131 0.0187014 0.0781959 -0.00799131 0.0184538 0.076981 -0.00829131 0.0184311 0.0771112 0.00570869 0.0232063 0.0762413 0.00570869 0.0225126 0.0757586 0.00570869 0.0215101 0.0762413 -0.00799131 0.0225126 0.0757586 0.00570869 0.0203975 0.0762413 0.00570869 0.0193951 0.0771112 0.00570869 0.0187014 0.0559945 -0.00799131 0.0594078 0.0547445 -0.00799131 0.0572427 0.0548196 -0.00829131 0.0586427 0.0548196 -0.00829131 0.0558427 0.0558445 -0.00829131 0.0548179 0.0559945 0.00570869 0.0594078 0.0550794 -0.00799131 0.0584927 0.0547445 0.00570869 0.0572427 0.0550794 0.00570869 0.0559927 0.0550794 -0.00799131 0.0559927 0.0559945 -0.00799131 0.0550777 0.0187905 -0.00799131 0.0794441 0.0195556 -0.00829131 0.080619 0.0184556 -0.00799131 0.0781941 0.0185307 -0.00829131 0.0795941 0.0185307 -0.00829131 0.0767941 0.0195556 -0.00829131 0.0757693 0.0209556 0.00570869 0.0806941 0.0209556 -0.00799131 0.0806941 0.0197056 -0.00799131 0.0803592 0.0184556 0.00570869 0.0781941 0.0187905 0.00570869 0.0769441 0.0197056 0.00570869 0.0760291 0.0187905 -0.00799131 0.0769441 0.0197056 -0.00799131 0.0760291 0.0809542 -0.00829131 0.00165244 0.0801292 -0.00829131 0.00143138 0.0795253 -0.00729131 0.000827441 0.0795253 -0.00829131 0.000827441 0.0793042 -0.00729131 2.44063e-06 0.0795253 -0.00829131 -0.000822559 0.0801292 -0.00729131 -0.0014265 0.0809542 -0.00729131 -0.00164756 0.0809542 -0.00829131 -0.00164756 0.069284 -0.00829131 0.0419064 0.06868 -0.00829131 0.0413024 0.06868 -0.00729131 0.0413024 0.06868 -0.00729131 0.0396524 0.06868 -0.00829131 0.0396524 0.070109 -0.00729131 0.0388274 0.0397633 -0.00729131 0.0715938 0.0397633 -0.00829131 0.0715938 0.0388706 -0.00829131 0.0704744 0.0388706 -0.00729131 0.06974 0.0388706 -0.00829131 0.06974 0.0391892 -0.00729131 0.0690784 0.0397633 -0.00829131 0.0686206 0.0404792 -0.00729131 0.0684572 0.0404792 -0.00729131 -0.0684523 0.0404792 -0.00829131 -0.0684523 0.0396542 -0.00829131 -0.0686734 0.0388292 -0.00829131 -0.0701023 0.0390503 -0.00729131 -0.0709273 0.0396542 -0.00729131 -0.0715313 0.0396542 -0.00829131 -0.0715313 0.070109 -0.00829131 -0.0388226 0.069284 -0.00729131 -0.0390436 0.06868 -0.00729131 -0.0396476 0.06868 -0.00829131 -0.0396476 0.06868 -0.00729131 -0.0412976 0.069284 -0.00729131 -0.0419015 0.06868 -0.00829131 -0.0412976 -0.0420794 -0.00729131 -0.0697352 -0.0420794 -0.00829131 -0.0697352 -0.0420794 -0.00729131 -0.0704695 -0.0420794 -0.00829131 -0.0704695 -0.0417608 -0.00829131 -0.0711311 -0.0411867 -0.00829131 -0.0715889 -0.0411867 -0.00729131 -0.0715889 -0.0404708 -0.00729131 -0.0717523 -0.0709255 -0.00729131 -0.0390436 -0.0709255 -0.00829131 -0.0390436 -0.0715295 -0.00829131 -0.0412976 -0.0701005 -0.00829131 -0.0421226 -0.0817708 -0.00829131 0.00143138 -0.0817708 -0.00729131 0.00143138 -0.0823747 -0.00729131 0.000827441 -0.0825958 -0.00729131 2.44063e-06 -0.0825958 -0.00829131 2.44063e-06 -0.0809458 -0.00729131 -0.00164756 -0.0809458 -0.00829131 -0.00164756 -0.0701005 -0.00729131 0.0421274 -0.0701005 -0.00829131 0.0421274 -0.0709255 -0.00829131 0.0419064 -0.0715295 -0.00829131 0.0413024 -0.0717505 -0.00729131 0.0404774 -0.0715295 -0.00829131 0.0396524 -0.0701005 -0.00729131 0.0388274 -0.0404708 -0.00829131 0.0717572 -0.0412958 -0.00729131 0.0715361 -0.0412958 -0.00829131 0.0715361 -0.0418997 -0.00829131 0.0709322 -0.0421208 -0.00729131 0.0701072 -0.0421208 -0.00829131 0.0701072 -0.0412958 -0.00729131 0.0686783 -0.0404708 -0.00729131 0.0684572 0.0760935 -0.00829131 0.0248307 0.0760935 -0.00799131 0.0251307 0.0748435 -0.00799131 0.0254656 0.0741389 -0.00799131 0.0260719 0.0733637 -0.00829131 0.0270076 0.0736562 -0.00799131 0.0270744 0.0739044 -0.00829131 0.0293764 0.0739285 -0.00799131 0.0288807 0.0750088 -0.00799131 0.0298831 0.0748786 -0.00829131 0.0301534 0.0605756 -0.00829131 0.0496587 0.0607256 -0.00799131 0.0499185 0.0595507 -0.00829131 0.0506836 0.060021 -0.00799131 0.0505249 0.0598105 -0.00799131 0.0508336 0.0595383 -0.00799131 0.0515273 0.0591756 -0.00829131 0.0520836 0.0595383 -0.00799131 0.0526399 0.0607256 -0.00799131 0.0542487 0.060021 -0.00799131 0.0536423 0.0520854 -0.00829131 0.0591738 0.0520854 -0.00799131 0.0594738 0.0498962 -0.00829131 0.0602281 0.0499203 -0.00799131 0.0607238 0.0496481 -0.00799131 0.0614175 0.0498962 -0.00829131 0.0637196 0.0520854 -0.00829131 0.0647738 0.0508354 -0.00799131 0.0641389 0.0508705 -0.00829131 0.0644966 0.0263824 -0.00799131 0.0739267 0.0254433 -0.00829131 0.074346 0.0254674 -0.00799131 0.0748418 0.0249026 -0.00829131 0.0754687 0.0249026 -0.00829131 0.0767148 0.0251324 -0.00799131 0.0760918 0.0254674 -0.00799131 0.0773418 0.0256779 -0.00799131 0.0776505 0.0264176 -0.00829131 0.0786145 0.0748435 0.0177087 0.0254656 0.0746935 0.0180087 0.0252058 0.0732935 0.0180087 0.0276307 0.0736687 0.0180087 0.0290307 0.0748435 0.0177087 0.0297957 0.0746935 0.0180087 0.0300555 0.0760935 0.0177087 0.0251307 0.0750088 -0.00799131 0.0253782 0.0739285 -0.00799131 0.0263807 0.0739285 0.0177087 0.0263807 0.0735935 -0.00799131 0.0276307 0.0735935 0.0177087 0.0276307 0.0739285 0.0177087 0.0288807 0.0736562 -0.00799131 0.028187 0.0741389 -0.00799131 0.0291894 0.0748435 -0.00799131 0.0297957 0.0760935 0.0177087 0.0301307 0.0760935 -0.00799131 0.0301307 0.0608909 0.0177087 0.0498312 0.060021 0.0177087 0.0505249 0.0597865 0.0180087 0.0503378 0.0595383 0.0177087 0.0526399 0.0607607 0.0180087 0.0546063 0.0619756 -0.00799131 0.0495836 0.0594756 -0.00799131 0.0520836 0.0595383 0.0177087 0.0515273 0.0598105 -0.00799131 0.0533336 0.060021 0.0177087 0.0536423 0.0608909 0.0177087 0.054336 0.0619756 0.0177087 0.0545836 0.0508354 0.0177087 0.0598088 0.0499203 0.0177087 0.0607238 0.0492854 0.0180087 0.0619738 0.0506854 0.0180087 0.0643987 0.0520854 0.0177087 0.0594738 0.0510007 -0.00799131 0.0597214 0.0508354 -0.00799131 0.0598088 0.0501308 -0.00799131 0.0604151 0.0495854 0.0177087 0.0619738 0.0495854 -0.00799131 0.0619738 0.0496481 -0.00799131 0.0625301 0.0499203 0.0177087 0.0632238 0.0499203 -0.00799131 0.0632238 0.0508354 0.0177087 0.0641389 0.0501308 -0.00799131 0.0635326 0.0510007 -0.00799131 0.0642263 0.0520854 0.0177087 0.0644738 0.0276324 0.0180087 0.0732918 0.0262324 0.0180087 0.0736669 0.0252076 0.0180087 0.0746918 0.0254674 0.0177087 0.0773418 0.0263824 0.0177087 0.0782568 0.0252076 0.0180087 0.0774918 0.0262324 0.0180087 0.0785166 0.0276324 0.0177087 0.0735918 0.0265477 -0.00799131 0.0738393 0.0263824 0.0177087 0.0739267 0.0256779 -0.00799131 0.074533 0.0251951 -0.00799131 0.0755355 0.0254674 0.0177087 0.0748418 0.0251324 0.0177087 0.0760918 0.0251951 -0.00799131 0.0766481 0.0263824 -0.00799131 0.0782568 0.0265477 -0.00799131 0.0783442 4.20971e-06 -0.0197913 0.0540024 -0.00977595 -0.00829131 0.0531094 -0.00977595 -0.0197913 0.0531094 -0.028053 -0.00829131 0.0461413 -0.0359454 -0.0197913 0.0402967 -0.0359454 -0.00829131 0.0402967 -0.0426487 -0.00829131 0.0331193 -0.0479413 -0.00829131 0.0248466 0.0275874 0.0162087 -0.0803447 0.0275874 0.0178087 -0.0803447 0.0777992 0.0162087 -0.0341216 0.0823548 0.0162087 -0.0208516 0.0846641 0.0162087 -0.00701267 0.0846641 0.0162087 0.00701756 0.0823548 0.0162087 0.0208564 0.0711215 0.0178087 0.0464657 0.0711215 0.0162087 0.0464657 0.062504 0.0178087 0.0575375 0.0521816 0.0162087 0.0670399 0.0404359 0.0162087 0.0747137 0.0275874 0.0178087 0.0803496 0.0139865 0.0148087 -0.083789 0.0275874 0.0148087 -0.0803447 0.0404359 0.0137087 -0.0747089 0.0521816 0.0148087 -0.067035 0.062504 0.0148087 -0.0575326 0.0823548 0.0137087 -0.0208516 0.0823548 0.0148087 -0.0208516 0.0846641 0.0137087 -0.00701267 0.0846641 0.0137087 0.00701756 0.0823548 0.0148087 0.0208564 0.0777992 0.0148087 0.0341265 0.0777992 0.0137087 0.0341265 0.0711215 0.0148087 0.0464657 0.062504 0.0137087 0.0575375 0.0521816 0.0148087 0.0670399 0.0521816 0.0137087 0.0670399 0.0404359 0.0148087 0.0747137 0.0404359 0.0137087 0.0747137 0.0275874 0.0137087 0.0803496 0.0275874 0.0148087 0.0803496 4.20971e-06 0.0148087 0.0849524 0.0139865 0.0123087 -0.083789 0.0275874 0.0112087 -0.0803447 0.0404359 0.0123087 -0.0747089 0.0521816 0.0123087 -0.067035 0.0521816 0.0112087 -0.067035 0.062504 0.0112087 -0.0575326 0.0711215 0.0112087 -0.0464608 0.0846641 0.0123087 -0.00701267 0.0846641 0.0112087 -0.00701267 0.0846641 0.0123087 0.00701756 0.0823548 0.0123087 0.0208564 0.0823548 0.0112087 0.0208564 0.0777992 0.0123087 0.0341265 0.0521816 0.0123087 0.0670399 0.062504 0.0112087 0.0575375 0.0275874 0.0112087 0.0803496 0.0139865 0.0123087 0.0837938 0.0139865 0.0112087 0.0837938 4.20971e-06 0.00870869 -0.0849476 0.0275874 0.00870869 -0.0803447 0.0404359 0.00870869 -0.0747089 0.0404359 0.00980869 -0.0747089 0.0521816 0.00980869 -0.067035 0.062504 0.00980869 -0.0575326 0.0521816 0.00870869 -0.067035 0.062504 0.00870869 -0.0575326 0.0711215 0.00980869 -0.0464608 0.0711215 0.00870869 -0.0464608 0.0777992 0.00870869 -0.0341216 0.0823548 0.00870869 -0.0208516 0.0823548 0.00980869 -0.0208516 0.0846641 0.00980869 -0.00701267 0.0846641 0.00870869 -0.00701267 0.0846641 0.00980869 0.00701756 0.0823548 0.00870869 0.0208564 0.0823548 0.00980869 0.0208564 0.0777992 0.00980869 0.0341265 0.0711215 0.00870869 0.0464657 0.0521816 0.00980869 0.0670399 0.0404359 0.00980869 0.0747137 0.0275874 0.00870869 0.0803496 0.0139865 0.00980869 0.0837938 0.0139865 0.00870869 0.0837938 4.20971e-06 0.00620869 -0.0849476 0.0139865 0.00620869 -0.083789 0.0275874 0.00730869 -0.0803447 0.0275874 0.00620869 -0.0803447 0.0404359 0.00620869 -0.0747089 0.062504 0.00730869 -0.0575326 0.0521816 0.00620869 -0.067035 0.0711215 0.00730869 -0.0464608 0.0711215 0.00620869 -0.0464608 0.0777992 0.00730869 -0.0341216 0.0777992 0.00620869 -0.0341216 0.0823548 0.00620869 -0.0208516 0.0846641 0.00730869 -0.00701267 0.0846641 0.00620869 -0.00701267 0.0846641 0.00620869 0.00701756 0.0846641 0.00730869 0.00701756 0.0823548 0.00730869 0.0208564 0.0823548 0.00620869 0.0208564 0.0777992 0.00620869 0.0341265 0.062504 0.00730869 0.0575375 0.0521816 0.00730869 0.0670399 0.0521816 0.00620869 0.0670399 0.0275874 0.00620869 0.0803496 0.0139865 0.00730869 0.0837938 4.20971e-06 0.00730869 0.0849524 4.20971e-06 0.00480869 -0.0849476 0.0139865 0.00480869 -0.083789 0.0275874 0.00480869 -0.0803447 0.0404359 0.00480869 -0.0747089 0.0404359 0.00370869 -0.0747089 0.0521816 0.00370869 -0.067035 0.0777992 0.00480869 -0.0341216 0.0711215 0.00370869 -0.0464608 0.0777992 0.00370869 -0.0341216 0.0823548 0.00480869 -0.0208516 0.0846641 0.00370869 0.00701756 0.0846641 0.00480869 0.00701756 0.0823548 0.00480869 0.0208564 0.0823548 0.00370869 0.0208564 0.0777992 0.00370869 0.0341265 0.0777992 0.00480869 0.0341265 0.0711215 0.00480869 0.0464657 0.0711215 0.00370869 0.0464657 0.062504 0.00370869 0.0575375 0.062504 0.00480869 0.0575375 0.0521816 0.00480869 0.0670399 0.0275874 0.00370869 0.0803496 0.0139865 0.00120869 -0.083789 0.0275874 0.00120869 -0.0803447 0.0275874 0.00230869 -0.0803447 0.0404359 0.00120869 -0.0747089 0.0521816 0.00230869 -0.067035 0.0521816 0.00120869 -0.067035 0.062504 0.00120869 -0.0575326 0.0711215 0.00230869 -0.0464608 0.0711215 0.00120869 -0.0464608 0.0823548 0.00230869 -0.0208516 0.0823548 0.00120869 -0.0208516 0.0846641 0.00230869 -0.00701267 0.0846641 0.00120869 0.00701756 0.0846641 0.00230869 0.00701756 0.0823548 0.00120869 0.0208564 0.0777992 0.00230869 0.0341265 0.0777992 0.00120869 0.0341265 0.0711215 0.00230869 0.0464657 0.0711215 0.00120869 0.0464657 0.062504 0.00120869 0.0575375 0.062504 0.00230869 0.0575375 0.0521816 0.00120869 0.0670399 0.0404359 0.00230869 0.0747137 0.0404359 0.00120869 0.0747137 0.0275874 0.00120869 0.0803496 0.0139865 0.00120869 0.0837938 0.0275874 -0.000191313 -0.0803447 0.0404359 -0.00129131 -0.0747089 0.0521816 -0.000191313 -0.067035 0.0521816 -0.00129131 -0.067035 0.062504 -0.00129131 -0.0575326 0.062504 -0.000191313 -0.0575326 0.0711215 -0.000191313 -0.0464608 0.0711215 -0.00129131 -0.0464608 0.0777992 -0.000191313 -0.0341216 0.0846641 -0.000191313 -0.00701267 0.0846641 -0.00129131 -0.00701267 0.0846641 -0.00129131 0.00701756 0.0823548 -0.000191313 0.0208564 0.0777992 -0.00129131 0.0341265 0.0711215 -0.000191313 0.0464657 0.0711215 -0.00129131 0.0464657 0.062504 -0.000191313 0.0575375 0.0275874 -0.000191313 0.0803496 4.20971e-06 -0.00519131 -0.0849476 4.20971e-06 -0.00779131 -0.0849476 0.0139865 -0.00779131 -0.083789 0.0404359 -0.00519131 -0.0747089 0.0521816 -0.00519131 -0.067035 0.062504 -0.00519131 -0.0575326 0.0846641 -0.00779131 -0.00701267 0.0846641 -0.00519131 0.00701756 0.0846641 -0.00779131 0.00701756 0.0823548 -0.00519131 0.0208564 0.0711215 -0.00779131 0.0464657 0.062504 -0.00779131 0.0575375 0.062504 -0.00519131 0.0575375 0.0404359 -0.00519131 0.0747137 0.0139865 -0.00779131 0.0837938 0.0139865 -0.00519131 0.0837938 4.20971e-06 -0.00779131 0.0849524 4.20971e-06 -0.00379131 -0.0849476 0.0139865 -0.00269131 -0.083789 0.0139865 -0.00379131 -0.083789 0.0404359 -0.00379131 -0.0747089 0.0521816 -0.00379131 -0.067035 0.062504 -0.00379131 -0.0575326 0.0711215 -0.00379131 -0.0464608 0.0711215 -0.00269131 -0.0464608 0.0846641 -0.00379131 -0.00701267 0.0846641 -0.00269131 -0.00701267 0.0823548 -0.00379131 0.0208564 0.0711215 -0.00269131 0.0464657 0.0521816 -0.00379131 0.0670399 0.0521816 -0.00269131 0.0670399 0.0404359 -0.00269131 0.0747137 0.0275874 -0.00269131 0.0803496 0.0404359 -0.00379131 0.0747137 0.0275874 -0.00379131 0.0803496 0.0139865 -0.00269131 0.0837938 0.0275874 0.0182087 -0.0803447 0.0403408 0.0180087 -0.074533 0.062504 0.0182087 -0.0575326 0.0711215 0.0182087 -0.0464608 0.0623568 0.0180087 -0.0573972 0.0821609 0.0180087 -0.0208025 0.0846641 0.0182087 -0.00701267 0.0844647 0.0180087 -0.00699616 0.0844647 0.0180087 0.00700104 0.0846641 0.0182087 0.00701756 0.0823548 0.0182087 0.0208564 0.0821609 0.0180087 0.0208073 0.0711215 0.0182087 0.0464657 0.062504 0.0182087 0.0575375 0.0709541 0.0180087 0.0463563 0.0520587 0.0180087 0.0668821 0.0275874 0.0182087 0.0803496 0.0139865 0.0182087 0.0837938 0.0809542 0.0243087 -0.00164756 0.0801292 0.0243087 -0.0014265 0.0795253 0.0243087 -0.000822559 0.0793042 0.0243087 2.44063e-06 0.0793042 0.0195087 2.44063e-06 0.0793456 0.0195087 0.0003696 0.0795253 0.0243087 0.000827441 0.0795253 0.0195087 0.000827441 0.0801292 0.0243087 0.00143138 0.0809542 0.0195087 0.00165244 0.06868 0.0243087 0.0396524 0.068459 0.0195087 0.0404774 0.068459 0.0243087 0.0404774 0.069284 0.0195087 0.0419064 0.069284 0.0243087 0.0419064 0.0396542 0.0195087 0.0686783 0.0390503 0.0243087 0.0692822 0.0390503 0.0195087 0.0692822 0.0390503 0.0243087 0.0709322 0.0396542 0.0195087 0.0715361 0.0404792 0.0243087 0.0717572 0.0390503 0.0195087 -0.0709273 0.0388292 0.0195087 -0.0701023 0.0390503 0.0243087 -0.0709273 0.0388292 0.0243087 -0.0701023 0.0390503 0.0243087 -0.0692773 0.0396542 0.0195087 -0.0686734 0.0404792 0.0195087 -0.0684523 0.0396542 0.0243087 -0.0686734 0.069284 0.0243087 -0.0419015 0.068459 0.0195087 -0.0404726 0.068459 0.0243087 -0.0404726 0.06868 0.0195087 -0.0396476 0.069284 0.0195087 -0.0390436 0.069284 0.0243087 -0.0390436 -0.0823747 0.0243087 -0.000822559 -0.0823747 0.0195087 0.000827441 -0.0823747 0.0243087 0.000827441 -0.0817708 0.0195087 0.00143138 -0.0709255 0.0195087 -0.0419015 -0.0709255 0.0243087 -0.0419015 -0.0715295 0.0195087 -0.0412976 -0.0717505 0.0195087 -0.0404726 -0.0715295 0.0195087 -0.0396476 -0.0715295 0.0243087 -0.0396476 -0.0412958 0.0243087 -0.0715313 -0.0421208 0.0195087 -0.0701023 -0.0418997 0.0195087 -0.0692773 -0.0412958 0.0195087 -0.0686734 -0.0418997 0.0243087 -0.0692773 -0.0404708 0.0195087 0.0684572 -0.0412958 0.0195087 0.0686783 -0.0418997 0.0195087 0.0692822 -0.0421208 0.0195087 0.0701072 -0.0418997 0.0195087 0.0709322 -0.0412958 0.0243087 0.0715361 -0.0404708 0.0195087 0.0717572 -0.0404708 0.0243087 0.0717572 -0.0701005 0.0195087 0.0388274 -0.0715295 0.0195087 0.0396524 -0.0715295 0.0243087 0.0396524 -0.0717505 0.0195087 0.0404774 -0.0717505 0.0243087 0.0404774 -0.0715295 0.0243087 0.0413024 -0.0709255 0.0243087 0.0419064 -0.0709255 0.0195087 0.0419064 -0.0701005 0.0243087 0.0421274 0.0114853 0.0298087 0.0577217 0.0225251 0.0298087 0.0543728 0.0114463 0.0300087 0.0575255 0.0326995 0.0298087 0.0489344 0.0325884 0.0300087 0.0487681 0.0489362 0.0298087 0.0326977 0.0543745 0.0298087 0.0225234 0.0575273 0.0300087 0.0114445 0.0577234 0.0298087 -0.0114786 0.0543745 0.0298087 -0.0225185 0.0489362 0.0298087 -0.0326929 0.0541897 0.0300087 -0.0224419 0.0416174 0.0298087 -0.0416108 0.0325884 0.0300087 -0.0487633 0.0224486 0.0300087 -0.0541831 0.0114853 0.0298087 -0.0577168 4.20971e-06 0.0298087 -0.0588476 4.20971e-06 0.0243087 0.0843524 0.0273926 0.0243087 0.0797821 0.0245417 0.0243087 0.0807046 0.0139865 0.0237087 0.0837938 0.051742 0.0243087 0.0666217 0.0458645 0.0243087 0.0707962 0.0428011 0.0243087 0.0726891 0.0402199 0.0243087 0.0741484 0.0708875 0.0243087 0.0457242 0.0711215 0.0237087 0.0464657 0.062504 0.0237087 0.0575375 0.0601428 0.0243087 0.0591486 0.0777992 0.0237087 0.0341265 0.0743971 0.0243087 0.0397595 0.072734 0.0243087 0.042726 0.0772497 0.0243087 0.0338854 0.0769051 0.0243087 0.0346604 0.0817731 0.0243087 0.0207091 0.0823548 0.0237087 0.0208564 0.0817731 0.0243087 -0.0207043 0.0777992 0.0237087 -0.0341216 0.0772497 0.0243087 -0.0338806 0.0743971 0.0243087 -0.0397546 0.0601428 0.0243087 -0.0591437 0.051742 0.0243087 -0.0666168 0.0518131 0.0243087 -0.0665616 0.0273926 0.0243087 -0.0797772 0.0401504 0.0243087 -0.0741812 0.0428011 0.0243087 -0.0726842 0.0404359 0.0237087 -0.0747089 0.0458645 0.0243087 -0.0707913 4.20971e-06 0.0237087 -0.0849476 4.20971e-06 0.0243087 -0.0843476 -0.0774851 0.0243087 -0.0300507 -0.0782502 0.0240087 -0.0288758 -0.07851 0.0243087 -0.0262258 -0.0774851 0.0243087 -0.0252009 -0.0760851 0.0243087 -0.0248258 -0.0773351 0.0182087 -0.0297908 -0.0782502 0.0182087 -0.0288758 -0.0773351 0.0240087 -0.0297908 -0.0785851 0.0182087 -0.0276258 -0.0785851 0.0240087 -0.0276258 -0.0782502 0.0240087 -0.0263758 -0.0773351 0.0240087 -0.0254607 -0.0760851 0.0182087 -0.0251258 -0.0773351 0.0182087 -0.0254607 -0.0782502 0.0182087 -0.0263758 -0.0784234 0.0180087 -0.0289758 -0.0774351 0.0180087 -0.0299641 -0.0630519 0.0240087 -0.0543311 -0.0631821 0.0243087 -0.0546014 -0.0639218 0.0240087 -0.0536374 -0.064697 0.0243087 -0.0527018 -0.0644045 0.0240087 -0.052635 -0.064697 0.0243087 -0.0514557 -0.0641563 0.0243087 -0.050333 -0.0639218 0.0240087 -0.05052 -0.0631821 0.0243087 -0.049556 -0.0630519 0.0182087 -0.0543311 -0.0644045 0.0182087 -0.052635 -0.0644045 0.0182087 -0.0515224 -0.0644045 0.0240087 -0.0515224 -0.0639218 0.0182087 -0.05052 -0.0630519 0.0182087 -0.0498263 -0.0630519 0.0240087 -0.0498263 -0.0640781 0.0180087 -0.0503953 -0.0639218 0.0182087 -0.0536374 -0.0640781 0.0180087 -0.0537621 -0.0631387 0.0180087 -0.0545113 -0.054242 0.0240087 -0.063219 -0.054877 0.0243087 -0.061969 -0.0545018 0.0243087 -0.060569 -0.052077 0.0240087 -0.059469 -0.052077 0.0240087 -0.064469 -0.053327 0.0182087 -0.064134 -0.053327 0.0240087 -0.064134 -0.054242 0.0182087 -0.063219 -0.054577 0.0240087 -0.061969 -0.054242 0.0240087 -0.060719 -0.053327 0.0182087 -0.0598039 -0.052077 0.0182087 -0.059469 -0.053327 0.0240087 -0.0598039 -0.054242 0.0182087 -0.060719 -0.054577 0.0182087 -0.061969 -0.054777 0.0180087 -0.061969 -0.053427 0.0180087 -0.0643072 -0.052077 0.0180087 -0.064669 -0.027624 0.0240087 -0.0785869 -0.028874 0.0240087 -0.0782519 -0.0297891 0.0240087 -0.0773369 -0.0300489 0.0243087 -0.0774869 -0.030424 0.0243087 -0.0760869 -0.0300489 0.0243087 -0.0746869 -0.028874 0.0240087 -0.0739218 -0.029024 0.0243087 -0.073662 -0.028874 0.0182087 -0.0782519 -0.030124 0.0240087 -0.0760869 -0.0297891 0.0240087 -0.0748369 -0.028874 0.0182087 -0.0739218 -0.027624 0.0240087 -0.0735869 -0.027624 0.0180087 -0.0733869 -0.0297891 0.0182087 -0.0748369 -0.030124 0.0182087 -0.0760869 -0.0297891 0.0182087 -0.0773369 -0.028974 0.0180087 -0.0784251 -0.0796875 0.0241087 -0.023547 -0.0811875 0.0241087 -0.020949 -0.0809588 0.0243087 -0.022549 -0.0813875 0.0243087 -0.020949 -0.0809588 0.0243087 -0.019349 -0.0796875 0.0241087 -0.0183509 -0.0781875 0.0241087 -0.017949 -0.0572361 0.0243087 -0.0604379 -0.0586245 0.0243087 -0.060121 -0.0585377 0.0241087 -0.0599408 -0.0595816 0.0241087 -0.0591083 -0.0597379 0.0243087 -0.059233 -0.0603559 0.0243087 -0.0579499 -0.0603559 0.0243087 -0.0565258 -0.0572361 0.0241087 -0.0542379 -0.0223356 0.0243087 -0.0753062 -0.0209472 0.0241087 -0.0751893 -0.0222488 0.0241087 -0.0754863 -0.0232927 0.0241087 -0.0763188 -0.024067 0.0243087 -0.0774772 -0.0234491 0.0243087 -0.0801844 -0.0229424 0.0243087 -0.0806911 -0.0789625 0.0210587 -0.0222913 -0.0790875 0.0213087 -0.0225078 -0.0795298 0.0210587 -0.021724 -0.0797463 0.0213087 -0.021849 -0.0797375 0.0210587 -0.020949 -0.0799875 0.0213087 -0.020949 -0.0789625 0.0210587 -0.0196066 -0.0781875 0.0210587 -0.022499 -0.0795298 0.0181587 -0.021724 -0.0797375 0.0181587 -0.020949 -0.0795298 0.0210587 -0.020174 -0.0789625 0.0181587 -0.0196066 -0.0795298 0.0181587 -0.020174 -0.0796597 0.0180087 -0.020099 -0.0798875 0.0180087 -0.020949 -0.0789625 0.0181587 -0.0222913 -0.0781875 0.0181587 -0.022499 -0.0572361 0.0210587 -0.0587879 -0.0579086 0.0210587 -0.0586344 -0.0580171 0.0213087 -0.0588596 -0.0586434 0.0213087 -0.0583601 -0.0587472 0.0210587 -0.0568929 -0.0584479 0.0210587 -0.0562714 -0.058991 0.0213087 -0.0568373 -0.0586434 0.0213087 -0.0561156 -0.0572361 0.0210587 -0.0556879 -0.0584479 0.0181587 -0.0582043 -0.0584479 0.0210587 -0.0582043 -0.0587472 0.0181587 -0.0568929 -0.0587472 0.0210587 -0.0575828 -0.0579086 0.0210587 -0.0558414 -0.0579086 0.0181587 -0.0558414 -0.0579737 0.0180087 -0.0557062 -0.0584479 0.0181587 -0.0562714 -0.0588935 0.0180087 -0.0568596 -0.0587472 0.0181587 -0.0575828 -0.0585652 0.0180087 -0.0582978 -0.0579086 0.0181587 -0.0586344 -0.0209472 0.0213087 -0.0799893 -0.0216197 0.0210587 -0.0795858 -0.022159 0.0210587 -0.0791557 -0.0223545 0.0213087 -0.0793115 -0.0224583 0.0210587 -0.0785342 -0.0227021 0.0213087 -0.0785898 -0.0227021 0.0213087 -0.0777887 -0.0223545 0.0213087 -0.077067 -0.0217282 0.0213087 -0.0765675 -0.0209472 0.0181587 -0.0797393 -0.022159 0.0181587 -0.0791557 -0.0224583 0.0181587 -0.0778443 -0.0224583 0.0210587 -0.0778443 -0.022159 0.0210587 -0.0772228 -0.0216197 0.0210587 -0.0767928 -0.022159 0.0181587 -0.0772228 -0.0209472 0.0210587 -0.0766393 -0.0209472 0.0181587 -0.0766393 -0.0217972 0.0180087 -0.0796615 -0.0217222 0.0181587 -0.0795316 -0.0224194 0.0180087 -0.0790393 -0.0222895 0.0181587 -0.0789643 -0.0224583 0.0181587 -0.0785342 -0.0226472 0.0180087 -0.0781893 -0.0224972 0.0181587 -0.0781893 -0.0209472 0.0180087 -0.0764893 -0.0217222 0.0181587 -0.0768469 -0.0217972 0.0180087 -0.076717 -0.0222895 0.0181587 -0.0774143 -0.0796875 0.0213087 -0.023547 -0.0781875 0.0241087 -0.023949 -0.0811875 0.0213087 -0.020949 -0.0807856 0.0241087 -0.022449 -0.0807856 0.0213087 -0.019449 -0.0807856 0.0241087 -0.019449 -0.0572361 0.0241087 -0.0602379 -0.0601609 0.0213087 -0.0565703 -0.0601609 0.0241087 -0.0579054 -0.0601609 0.0241087 -0.0565703 -0.0595816 0.0213087 -0.0553674 -0.0595816 0.0241087 -0.0553674 -0.0585377 0.0213087 -0.0545349 -0.0585377 0.0241087 -0.0545349 -0.0572361 0.0213087 -0.0542379 -0.0209472 0.0241087 -0.0811893 -0.0222488 0.0241087 -0.0808922 -0.0232927 0.0213087 -0.0800597 -0.0232927 0.0241087 -0.0800597 -0.023872 0.0213087 -0.0788568 -0.023872 0.0241087 -0.0788568 -0.023872 0.0241087 -0.0775217 -0.0771698 0.0240087 0.0253782 -0.0760851 0.0240087 0.0301307 -0.0760851 0.0182087 0.0251307 -0.0780397 0.0240087 0.0260719 -0.0785224 0.0182087 0.0270744 -0.0785224 0.0240087 0.0270744 -0.0785224 0.0240087 0.028187 -0.0780397 0.0240087 0.0291894 -0.0771698 0.0240087 0.0298831 -0.0760851 0.0182087 0.0301307 -0.0760851 0.0180087 0.0303307 -0.0771698 0.0182087 0.0298831 -0.0780397 0.0182087 0.0291894 -0.078196 0.0180087 0.0293141 -0.0785224 0.0182087 0.028187 -0.0787174 0.0180087 0.0282315 -0.0787174 0.0180087 0.0270299 -0.0780397 0.0182087 0.0260719 -0.078196 0.0180087 0.0259472 -0.0771698 0.0182087 0.0253782 -0.0631821 0.0243087 0.0495609 -0.0639218 0.0240087 0.0505249 -0.0644045 0.0240087 0.0515273 -0.064697 0.0243087 0.0514605 -0.0644045 0.0240087 0.0526399 -0.0631821 0.0243087 0.0546063 -0.0619672 0.0240087 0.0495836 -0.0630519 0.0182087 0.0498312 -0.0630519 0.0240087 0.0498312 -0.0644045 0.0182087 0.0515273 -0.0644045 0.0182087 0.0526399 -0.0639218 0.0182087 0.0536423 -0.0639218 0.0240087 0.0536423 -0.0630519 0.0240087 0.054336 -0.0630519 0.0182087 0.054336 -0.0631387 0.0180087 0.0545162 -0.0645995 0.0180087 0.0526844 -0.0639218 0.0182087 0.0505249 -0.0640781 0.0180087 0.0504002 -0.0532918 0.0243087 0.0594511 -0.0540315 0.0240087 0.0604151 -0.0542661 0.0243087 0.0602281 -0.0540315 0.0240087 0.0635326 -0.0531617 0.0240087 0.0642263 -0.0542661 0.0243087 0.0637196 -0.0532918 0.0243087 0.0644966 -0.052077 0.0240087 0.0644738 -0.052077 0.0240087 0.0594738 -0.0531617 0.0240087 0.0597214 -0.0545143 0.0182087 0.0625301 -0.0545143 0.0240087 0.0614175 -0.0545143 0.0240087 0.0625301 -0.052077 0.0182087 0.0644738 -0.0531617 0.0182087 0.0642263 -0.0532484 0.0180087 0.0644065 -0.0540315 0.0182087 0.0635326 -0.0541879 0.0180087 0.0636573 -0.0547093 0.0180087 0.061373 -0.0545143 0.0182087 0.0614175 -0.0540315 0.0182087 0.0604151 -0.0541879 0.0180087 0.0602904 -0.0531617 0.0182087 0.0597214 -0.0532484 0.0180087 0.0595412 -0.027624 0.0243087 0.0732918 -0.0300489 0.0243087 0.0746918 -0.030424 0.0243087 0.0760918 -0.027624 0.0240087 0.0785918 -0.029024 0.0243087 0.0785166 -0.028874 0.0240087 0.0739267 -0.0297891 0.0240087 0.0748418 -0.030124 0.0240087 0.0760918 -0.0297891 0.0240087 0.0773418 -0.028874 0.0182087 0.0782568 -0.027624 0.0182087 0.0785918 -0.028874 0.0240087 0.0782568 -0.0297891 0.0182087 0.0773418 -0.0299623 0.0180087 0.0774418 -0.030324 0.0180087 0.0760918 -0.030124 0.0182087 0.0760918 -0.0297891 0.0182087 0.0748418 -0.028874 0.0182087 0.0739267 -0.028974 0.0180087 0.0737535 -0.0781875 0.0241087 0.0239538 -0.0795759 0.0243087 0.0238369 -0.0796875 0.0241087 0.0235519 -0.0806893 0.0243087 0.022949 -0.0807856 0.0241087 0.0224538 -0.0813073 0.0243087 0.0216659 -0.0813073 0.0243087 0.0202418 -0.0811123 0.0241087 0.0202863 -0.0796875 0.0241087 0.0183558 -0.0587361 0.0241087 0.0598408 -0.0598756 0.0243087 0.0590518 -0.0587361 0.0241087 0.0546447 -0.0598342 0.0241087 0.0557427 -0.0600074 0.0243087 0.0556427 -0.0604361 0.0243087 0.0572427 -0.0598342 0.0241087 0.0587427 -0.0209472 0.0241087 0.0811941 -0.0222488 0.0241087 0.080897 -0.0223356 0.0243087 0.0810772 -0.0234491 0.0243087 0.0801893 -0.0224472 0.0241087 0.0807922 -0.0232927 0.0241087 0.0800646 -0.024067 0.0243087 0.0774821 -0.0234491 0.0243087 0.076199 -0.0209472 0.0243087 0.0749941 -0.0222488 0.0241087 0.0754912 -0.0223356 0.0243087 0.075311 -0.0224472 0.0241087 0.0755961 -0.0232927 0.0241087 0.0763237 -0.0781875 0.0213087 0.0191538 -0.0789625 0.0210587 0.0196115 -0.0795298 0.0210587 0.0201788 -0.0797375 0.0210587 0.0209538 -0.0797463 0.0213087 0.0218538 -0.0789625 0.0210587 0.0222962 -0.07886 0.0181587 0.0195573 -0.0795298 0.0181587 0.0201788 -0.0796986 0.0181587 0.0206089 -0.0796986 0.0181587 0.0212987 -0.0795298 0.0210587 0.0217288 -0.0795298 0.0181587 0.0217288 -0.0793993 0.0181587 0.0219203 -0.0781875 0.0210587 0.0225038 -0.07886 0.0181587 0.0223503 -0.0789251 0.0180087 0.0194222 -0.0789625 0.0181587 0.0196115 -0.0793993 0.0181587 0.0199874 -0.0795166 0.0180087 0.0198939 -0.0798449 0.0180087 0.0205756 -0.0797375 0.0181587 0.0209538 -0.0795166 0.0180087 0.0220138 -0.0781875 0.0180087 0.0226538 -0.0789625 0.0181587 0.0222962 -0.0572361 0.0213087 0.0554427 -0.0580111 0.0210587 0.0559004 -0.0585784 0.0210587 0.0564677 -0.0587861 0.0210587 0.0572427 -0.0590361 0.0213087 0.0572427 -0.0585784 0.0210587 0.0580177 -0.0587949 0.0213087 0.0581427 -0.0572361 0.0213087 0.0590427 -0.0585784 0.0181587 0.0564677 -0.0585784 0.0181587 0.0580177 -0.0580111 0.0181587 0.0585851 -0.0580111 0.0210587 0.0585851 -0.0572361 0.0181587 0.0587927 -0.0580861 0.0180087 0.058715 -0.0587861 0.0181587 0.0572427 -0.0580861 0.0180087 0.0557705 -0.0580111 0.0181587 0.0559004 -0.0209472 0.0210587 0.0766441 -0.0217222 0.0210587 0.0768518 -0.0222895 0.0210587 0.0774191 -0.0222895 0.0210587 0.0789691 -0.022506 0.0213087 0.0790941 -0.0218472 0.0213087 0.079753 -0.0209472 0.0213087 0.0799941 -0.0224972 0.0210587 0.0781941 -0.0224972 0.0181587 0.0781941 -0.0222895 0.0181587 0.0789691 -0.0217222 0.0210587 0.0795365 -0.0217222 0.0181587 0.0795365 -0.0209472 0.0210587 0.0797441 -0.0224194 0.0180087 0.0790441 -0.0222895 0.0181587 0.0774191 -0.0224194 0.0180087 0.0773441 -0.0217222 0.0181587 0.0768518 -0.0781875 0.0241087 0.0179538 -0.0794891 0.0241087 0.0182509 -0.0781875 0.0213087 0.0179538 -0.0796875 0.0213087 0.0183558 -0.080533 0.0241087 0.0190834 -0.0807856 0.0213087 0.0194538 -0.0807856 0.0241087 0.0194538 -0.0811875 0.0241087 0.0209538 -0.0807856 0.0213087 0.0224538 -0.0811123 0.0241087 0.0216214 -0.080533 0.0241087 0.0228243 -0.0794891 0.0241087 0.0236567 -0.0796875 0.0213087 0.0235519 -0.0572361 0.0213087 0.0542427 -0.0587361 0.0213087 0.0546447 -0.0598342 0.0213087 0.0557427 -0.0602361 0.0241087 0.0572427 -0.0598342 0.0213087 0.0587427 -0.0587361 0.0213087 0.0598408 -0.0209472 0.0241087 0.0751941 -0.0209472 0.0213087 0.0751941 -0.0235453 0.0213087 0.0766941 -0.0235453 0.0241087 0.0766941 -0.023872 0.0241087 0.0775266 -0.0239472 0.0241087 0.0781941 -0.023872 0.0241087 0.0788617 -0.0235453 0.0241087 0.0796941 -0.0235453 0.0213087 0.0796941 -0.0224472 0.0213087 0.0807922 0.0741389 0.0240087 -0.0291845 0.0739044 0.0243087 -0.0293716 0.0736562 0.0240087 -0.0281821 0.0733637 0.0243087 -0.0282488 0.0739044 0.0243087 -0.02588 0.0750088 0.0240087 -0.0253734 0.0750088 0.0240087 -0.0298782 0.0748435 0.0182087 -0.0297908 0.0741389 0.0182087 -0.0291845 0.0736562 0.0240087 -0.0270695 0.0739285 0.0182087 -0.0263758 0.0741389 0.0240087 -0.0260671 0.0741389 0.0182087 -0.0260671 0.0747435 0.0180087 -0.0299641 0.0739285 0.0182087 -0.0288758 0.0736562 0.0182087 -0.0281821 0.0737553 0.0180087 -0.0289758 0.0735935 0.0182087 -0.0276258 0.0733935 0.0180087 -0.0276258 0.0736562 0.0182087 -0.0270695 0.0760935 0.0180087 -0.0249258 0.0748435 0.0182087 -0.0254607 0.0607607 0.0243087 -0.0546014 0.0592458 0.0243087 -0.0527018 0.060021 0.0240087 -0.05052 0.0597865 0.0243087 -0.050333 0.0607607 0.0243087 -0.049556 0.0608909 0.0240087 -0.0543311 0.060021 0.0240087 -0.0536374 0.0595383 0.0182087 -0.052635 0.0595383 0.0240087 -0.052635 0.0595383 0.0240087 -0.0515224 0.060021 0.0182087 -0.05052 0.0608909 0.0182087 -0.0498263 0.0608909 0.0240087 -0.0498263 0.0619756 0.0182087 -0.0495787 0.0619756 0.0180087 -0.0493787 0.0598647 0.0180087 -0.0503953 0.0595383 0.0182087 -0.0515224 0.060021 0.0182087 -0.0536374 0.0608909 0.0182087 -0.0543311 0.0608041 0.0180087 -0.0545113 0.0619756 0.0182087 -0.0545787 0.0520854 0.0240087 -0.064469 0.0510007 0.0240087 -0.0642214 0.0501308 0.0240087 -0.0635277 0.0498962 0.0243087 -0.0637147 0.0496481 0.0240087 -0.0625253 0.0508705 0.0243087 -0.0594462 0.0510007 0.0182087 -0.0642214 0.0496481 0.0182087 -0.0625253 0.0496481 0.0182087 -0.0614127 0.0501308 0.0182087 -0.0604102 0.0496481 0.0240087 -0.0614127 0.0501308 0.0240087 -0.0604102 0.0520854 0.0182087 -0.059469 0.0510007 0.0240087 -0.0597165 0.0510007 0.0182087 -0.0597165 0.0509139 0.0180087 -0.0595363 0.0499744 0.0180087 -0.0602855 0.0501308 0.0182087 -0.0635277 0.0499744 0.0180087 -0.0636524 0.0520854 0.0182087 -0.064469 0.0276324 0.0240087 -0.0785869 0.0254674 0.0240087 -0.0773369 0.0251324 0.0240087 -0.0760869 0.0248324 0.0243087 -0.0760869 0.0254674 0.0240087 -0.0748369 0.0254674 0.0182087 -0.0773369 0.0263824 0.0240087 -0.0782519 0.0263824 0.0240087 -0.0739218 0.0276324 0.0180087 -0.0733869 0.0263824 0.0182087 -0.0739218 0.0254674 0.0182087 -0.0748369 0.0251324 0.0182087 -0.0760869 0.0249324 0.0180087 -0.0760869 0.0252942 0.0180087 -0.0774369 0.0263824 0.0182087 -0.0782519 0.0781959 0.0243087 -0.024149 0.0766959 0.0241087 -0.023547 0.0765959 0.0243087 -0.0181777 0.0781959 0.0243087 -0.017749 0.0556445 0.0243087 -0.0600091 0.0542445 0.0241087 -0.0572379 0.0540445 0.0243087 -0.0572379 0.0546464 0.0241087 -0.0557379 0.0557445 0.0241087 -0.0546398 0.0572445 0.0241087 -0.0542379 0.0556445 0.0243087 -0.0544666 0.0209556 0.0243087 -0.0813893 0.0195672 0.0243087 -0.0810724 0.0178358 0.0243087 -0.0774772 0.0209556 0.0241087 -0.0751893 0.0772959 0.0213087 -0.0225078 0.0768536 0.0210587 -0.021724 0.0766459 0.0210587 -0.020949 0.0763959 0.0213087 -0.020949 0.0772959 0.0213087 -0.0193901 0.0781959 0.0210587 -0.019399 0.0774209 0.0181587 -0.0222913 0.0774209 0.0210587 -0.0222913 0.0768536 0.0210587 -0.020174 0.0774209 0.0210587 -0.0196066 0.0774209 0.0181587 -0.0196066 0.0781959 0.0180087 -0.019249 0.0773459 0.0180087 -0.0194767 0.0768536 0.0181587 -0.020174 0.0767237 0.0180087 -0.020099 0.0766459 0.0181587 -0.020949 0.0764959 0.0180087 -0.020949 0.0768536 0.0181587 -0.021724 0.0773459 0.0180087 -0.0224212 0.0563445 0.0213087 -0.0587967 0.0564695 0.0210587 -0.0585802 0.0556945 0.0210587 -0.0572379 0.0554445 0.0213087 -0.0572379 0.0564695 0.0210587 -0.0558955 0.0563445 0.0213087 -0.055679 0.0572445 0.0210587 -0.0556879 0.0572445 0.0213087 -0.0554379 0.0572445 0.0181587 -0.0587879 0.0559022 0.0210587 -0.0580129 0.0559022 0.0210587 -0.0564629 0.0564695 0.0181587 -0.0558955 0.0563945 0.0180087 -0.0557656 0.0559022 0.0181587 -0.0564629 0.0556945 0.0181587 -0.0572379 0.0555445 0.0180087 -0.0572379 0.0559022 0.0181587 -0.0580129 0.0564695 0.0181587 -0.0585802 0.0563945 0.0180087 -0.0587101 0.0209556 0.0213087 -0.0799893 0.0197438 0.0210587 -0.0791557 0.0192007 0.0213087 -0.0785898 0.0192007 0.0213087 -0.0777887 0.0194445 0.0210587 -0.0778443 0.0197438 0.0210587 -0.0772228 0.0195483 0.0213087 -0.077067 0.0209556 0.0210587 -0.0797393 0.0202831 0.0210587 -0.0795858 0.0194445 0.0210587 -0.0785342 0.0202831 0.0210587 -0.0767928 0.0209556 0.0181587 -0.0766393 0.0202831 0.0181587 -0.0767928 0.0197438 0.0181587 -0.0772228 0.0196265 0.0180087 -0.0771293 0.0194445 0.0181587 -0.0778443 0.0194445 0.0181587 -0.0785342 0.0197438 0.0181587 -0.0791557 0.0192982 0.0180087 -0.0785675 0.0202831 0.0181587 -0.0795858 0.0196265 0.0180087 -0.0792492 0.020218 0.0180087 -0.0797209 0.0209556 0.0181587 -0.0797393 0.0209556 0.0180087 -0.0798893 0.0766959 0.0213087 -0.023547 0.0755978 0.0213087 -0.022449 0.0755978 0.0241087 -0.022449 0.0751959 0.0241087 -0.020949 0.0755978 0.0213087 -0.019449 0.0766959 0.0213087 -0.0183509 0.0755978 0.0241087 -0.019449 0.0766959 0.0241087 -0.0183509 0.0557445 0.0241087 -0.0598359 0.0546464 0.0213087 -0.0587379 0.0546464 0.0241087 -0.0587379 0.0542445 0.0213087 -0.0572379 0.0557445 0.0213087 -0.0546398 0.0209556 0.0241087 -0.0811893 0.019654 0.0241087 -0.0808922 0.0186101 0.0213087 -0.0800597 0.0186101 0.0241087 -0.0800597 0.0180308 0.0241087 -0.0788568 0.0180308 0.0241087 -0.0775217 0.0186101 0.0213087 -0.0763188 0.0186101 0.0241087 -0.0763188 0.019654 0.0241087 -0.0754863 0.0746935 0.0243087 0.0252058 0.0732935 0.0243087 0.0276307 0.0736687 0.0243087 0.0290307 0.0760935 0.0240087 0.0301307 0.0760935 0.0182087 0.0251307 0.0760935 0.0240087 0.0251307 0.0748435 0.0240087 0.0254656 0.0739285 0.0240087 0.0263807 0.0735935 0.0182087 0.0276307 0.0735935 0.0240087 0.0276307 0.0739285 0.0182087 0.0288807 0.0739285 0.0240087 0.0288807 0.0748435 0.0240087 0.0297957 0.0747435 0.0180087 0.0299689 0.0748435 0.0182087 0.0297957 0.0733935 0.0180087 0.0276307 0.0737553 0.0180087 0.0262807 0.0739285 0.0182087 0.0263807 0.0748435 0.0182087 0.0254656 0.0619756 0.0243087 0.0492836 0.0607607 0.0243087 0.0495609 0.0595383 0.0240087 0.0526399 0.0608909 0.0240087 0.054336 0.0607607 0.0243087 0.0546063 0.0619756 0.0240087 0.0495836 0.0608909 0.0240087 0.0498312 0.060021 0.0240087 0.0505249 0.0595383 0.0182087 0.0515273 0.0595383 0.0240087 0.0515273 0.060021 0.0240087 0.0536423 0.0608909 0.0182087 0.054336 0.060021 0.0182087 0.0536423 0.0595383 0.0182087 0.0526399 0.060021 0.0182087 0.0505249 0.0598647 0.0180087 0.0504002 0.0608041 0.0180087 0.049651 0.0608909 0.0182087 0.0498312 0.0508354 0.0240087 0.0598088 0.0506854 0.0243087 0.059549 0.0499203 0.0240087 0.0607238 0.0496605 0.0243087 0.0605738 0.0495854 0.0240087 0.0619738 0.0508354 0.0240087 0.0641389 0.0496605 0.0243087 0.0633738 0.0520854 0.0240087 0.0644738 0.0520854 0.0240087 0.0594738 0.0508354 0.0182087 0.0598088 0.0495854 0.0182087 0.0619738 0.0499203 0.0240087 0.0632238 0.0508354 0.0182087 0.0641389 0.0520854 0.0182087 0.0644738 0.0499203 0.0182087 0.0632238 0.0507354 0.0180087 0.0643121 0.0497471 0.0180087 0.0633238 0.0499203 0.0182087 0.0607238 0.0493854 0.0180087 0.0619738 0.0497471 0.0180087 0.0606238 0.0507354 0.0180087 0.0596356 0.0520854 0.0182087 0.0594738 0.0276324 0.0243087 0.0732918 0.0254674 0.0240087 0.0748418 0.0251324 0.0240087 0.0760918 0.0254674 0.0240087 0.0773418 0.0248324 0.0243087 0.0760918 0.0252076 0.0243087 0.0774918 0.0263824 0.0240087 0.0782568 0.0262324 0.0243087 0.0785166 0.0276324 0.0243087 0.0788918 0.0263824 0.0182087 0.0739267 0.0254674 0.0182087 0.0748418 0.0263824 0.0240087 0.0739267 0.0254674 0.0182087 0.0773418 0.0276324 0.0240087 0.0785918 0.0276324 0.0180087 0.0787918 0.0263824 0.0182087 0.0782568 0.0262824 0.0180087 0.07843 0.0251324 0.0182087 0.0760918 0.0262824 0.0180087 0.0737535 0.0768943 0.0241087 0.0182509 0.0768075 0.0243087 0.0180707 0.0750761 0.0243087 0.0202418 0.0752711 0.0241087 0.0202863 0.0750761 0.0243087 0.0216659 0.0758504 0.0241087 0.0228243 0.0768943 0.0241087 0.0236567 0.075694 0.0243087 0.022949 0.0768075 0.0243087 0.0238369 0.0558561 0.0243087 0.0543596 0.0559429 0.0241087 0.0545398 0.054899 0.0241087 0.0553723 0.0547426 0.0243087 0.0552476 0.0543197 0.0241087 0.0565752 0.0541247 0.0243087 0.0579548 0.054899 0.0241087 0.0591132 0.0559429 0.0241087 0.0599456 0.0572445 0.0241087 0.0602427 0.0209556 0.0241087 0.0751941 0.0209556 0.0243087 0.0749941 0.0186101 0.0241087 0.0763237 0.0180308 0.0241087 0.0775266 0.0184538 0.0243087 0.076199 0.0180308 0.0241087 0.0788617 0.0184538 0.0243087 0.0801893 0.019654 0.0241087 0.080897 0.0195672 0.0243087 0.0810772 0.0781959 0.0213087 0.0191538 0.0774149 0.0213087 0.0193321 0.0766848 0.0210587 0.0206089 0.0767886 0.0213087 0.0198316 0.076441 0.0213087 0.0213544 0.0767886 0.0213087 0.0220761 0.0775234 0.0210587 0.0223503 0.0774149 0.0213087 0.0225756 0.0781959 0.0210587 0.0225038 0.0775234 0.0210587 0.0195573 0.0774209 0.0181587 0.0196115 0.0769841 0.0181587 0.0199874 0.0769841 0.0210587 0.0199874 0.0766848 0.0181587 0.0206089 0.0766459 0.0181587 0.0209538 0.0766848 0.0210587 0.0212987 0.0768536 0.0181587 0.0217288 0.0769841 0.0181587 0.0219203 0.0769841 0.0210587 0.0219203 0.0774209 0.0181587 0.0222962 0.0781959 0.0181587 0.0194038 0.0773459 0.0180087 0.0194816 0.0768536 0.0181587 0.0201788 0.0766848 0.0181587 0.0212987 0.0764959 0.0180087 0.0209538 0.0767237 0.0180087 0.0218038 0.0572445 0.0213087 0.0554427 0.0564635 0.0213087 0.055621 0.0560327 0.0210587 0.0562763 0.0554896 0.0213087 0.0576433 0.0560327 0.0210587 0.0582091 0.0564635 0.0213087 0.0588645 0.056572 0.0210587 0.0558462 0.0560327 0.0181587 0.0562763 0.0557334 0.0210587 0.0568978 0.0557334 0.0210587 0.0575876 0.056572 0.0210587 0.0586392 0.0572445 0.0181587 0.0587927 0.056572 0.0181587 0.0586392 0.0560327 0.0181587 0.0582091 0.0557334 0.0181587 0.0575876 0.0557334 0.0181587 0.0568978 0.056572 0.0181587 0.0558462 0.0572445 0.0181587 0.0556927 0.0565069 0.0180087 0.0557111 0.0209556 0.0210587 0.0766441 0.0202831 0.0210587 0.0767976 0.0201746 0.0213087 0.0765724 0.0197438 0.0210587 0.0772277 0.0192007 0.0213087 0.0785947 0.0197438 0.0210587 0.0791605 0.0202831 0.0210587 0.0795906 0.0195483 0.0213087 0.0793164 0.0201746 0.0213087 0.0798159 0.0209556 0.0210587 0.0797441 0.0197438 0.0181587 0.0772277 0.0194445 0.0210587 0.0778492 0.0194445 0.0181587 0.0778492 0.0194445 0.0210587 0.078539 0.0197438 0.0181587 0.0791605 0.0209556 0.0181587 0.0797441 0.0202831 0.0181587 0.0795906 0.0209556 0.0180087 0.0798941 0.020218 0.0180087 0.0797258 0.0194445 0.0181587 0.078539 0.0192982 0.0180087 0.0778159 0.0202831 0.0181587 0.0767976 0.0209556 0.0181587 0.0766441 0.0209556 0.0180087 0.0764941 0.0758504 0.0213087 0.0190834 0.0758504 0.0241087 0.0190834 0.0752711 0.0241087 0.0216214 0.0781959 0.0213087 0.0239538 0.054899 0.0213087 0.0553723 0.0543197 0.0213087 0.0579103 0.0543197 0.0241087 0.0579103 0.019654 0.0241087 0.0754912 0.0186101 0.0213087 0.0763237 0.0180308 0.0213087 0.0775266 0.0186101 0.0213087 0.0800646 0.0186101 0.0241087 0.0800646 0.0209556 0.0213087 0.0811941 4.20971e-06 0.0243087 -0.0588476 0.0225251 0.0243087 -0.0543679 0.0225251 0.0298087 -0.0543679 0.0326995 0.0298087 -0.0489295 0.0416174 0.0243087 -0.0416108 0.0543745 0.0243087 -0.0225185 0.0588542 0.0243087 2.44063e-06 0.0588542 0.0298087 2.44063e-06 0.0577234 0.0298087 0.0114835 0.0577234 0.0243087 0.0114835 0.0543745 0.0243087 0.0225234 0.0416174 0.0298087 0.0416157 0.0139865 0.0237087 -0.083789 0.0139865 0.0182087 -0.083789 0.0275874 0.0237087 -0.0803447 0.0404359 0.0182087 -0.0747089 0.0521816 0.0237087 -0.067035 0.0521816 0.0182087 -0.067035 0.062504 0.0237087 -0.0575326 0.0711215 0.0237087 -0.0464608 0.0777992 0.0182087 -0.0341216 0.0823548 0.0237087 -0.0208516 0.0823548 0.0182087 -0.0208516 0.0846641 0.0237087 -0.00701267 0.0846641 0.0237087 0.00701756 0.0777992 0.0182087 0.0341265 0.0521816 0.0237087 0.0670399 0.0521816 0.0182087 0.0670399 0.0404359 0.0182087 0.0747137 0.0404359 0.0237087 0.0747137 0.0275874 0.0237087 0.0803496 4.20971e-06 0.0237087 0.0849524 4.20971e-06 0.0182087 0.0849524 0.0802383 0.0195087 0.00148904 0.0804549 0.0192087 0.0010392 0.0800545 0.0192087 0.0007199 0.0796642 0.0195087 0.0010312 0.0801292 0.0195087 0.00143138 0.0800545 0.0192087 -0.000715019 0.0795253 0.0195087 -0.000822559 0.0798323 0.0192087 -0.000253618 0.0793456 0.0195087 -0.000364719 0.0802383 0.0195087 -0.00148416 0.0801292 0.0195087 -0.0014265 0.0796642 0.0195087 -0.00102632 0.069284 0.0195087 0.0390485 0.0691124 0.0192087 0.0399021 0.06868 0.0195087 0.0396524 0.06868 0.0195087 0.0413024 0.0404792 0.0195087 0.0684572 0.0394827 0.0192087 0.0695318 0.0388292 0.0195087 0.0701072 0.0394827 0.0192087 0.0706826 0.0399039 0.0192087 0.0711037 0.0390503 0.0195087 0.0709322 0.0404792 0.0192087 0.0712579 0.0404792 0.0192087 -0.071253 0.0399039 0.0192087 -0.0710989 0.0396542 0.0195087 -0.0715313 0.0390503 0.0195087 -0.0692773 0.0695336 0.0192087 -0.0414691 0.069284 0.0195087 -0.0419015 0.0691124 0.0192087 -0.0410479 0.06868 0.0195087 -0.0412976 0.0689583 0.0192087 -0.0404726 0.0691124 0.0192087 -0.0398972 -0.0809458 0.0192087 -0.00114828 -0.0809458 0.0195087 -0.00164756 -0.0817708 0.0195087 -0.0014265 -0.0819423 0.0192087 -0.000572917 -0.0823747 0.0195087 -0.000822559 -0.0825958 0.0195087 2.44063e-06 -0.0819423 0.0192087 0.000577799 -0.0815211 0.0192087 0.00099899 -0.0809458 0.0192087 0.00115316 -0.0706759 0.0192087 -0.0414691 -0.0701005 0.0195087 -0.0421226 -0.0710971 0.0192087 -0.0410479 -0.0709255 0.0195087 -0.0390436 -0.0701005 0.0192087 -0.0393218 -0.0412958 0.0195087 -0.0715313 -0.0410462 0.0192087 -0.0710989 -0.0414673 0.0192087 -0.0706777 -0.0416215 0.0192087 -0.0701023 -0.0418997 0.0195087 -0.0709273 -0.0414673 0.0192087 -0.069527 -0.0410462 0.0192087 -0.0691058 -0.0414673 0.0192087 0.0695318 -0.0414673 0.0192087 0.0706826 -0.0404708 0.0192087 0.0712579 -0.0412958 0.0195087 0.0715361 -0.0709255 0.0195087 0.0390485 -0.0715295 0.0195087 0.0413024 -0.0706759 0.0192087 0.041474 0.0247529 0.0220087 -0.0268463 0.0247083 0.0208087 -0.024839 0.0238418 0.0220087 -0.0266383 0.0246725 0.0208087 -0.0248104 0.0246527 0.0208087 -0.0247692 0.0246725 0.0208087 -0.0246822 0.0238418 0.0220087 -0.0228543 0.0247529 0.0208087 -0.0246434 0.0338116 0.0208087 -0.00915909 0.0338116 0.0208087 -0.00895336 0.0327616 0.0220087 -0.00723757 0.0337225 0.0208087 -0.00900479 0.0317643 0.0220087 -0.00858893 0.031993 0.0220087 -0.00800623 0.0337225 0.0208087 -0.00910766 0.0327616 0.0220087 -0.0108749 0.0337602 0.0208087 -0.00914531 0.0321698 0.0220087 -0.0103656 0.033767 0.0208087 0.00896843 0.0338116 0.0208087 0.00895824 0.0337312 0.0208087 0.00912524 0.031993 0.0220087 0.0101111 0.0317116 0.0220087 0.00906111 0.0337113 0.0208087 0.00903822 0.0317643 0.0220087 0.00859381 0.0321698 0.0220087 0.00775178 0.031993 0.0220087 0.00801111 0.0238418 0.0220087 0.0266432 0.0227056 0.0220087 0.0252185 0.0246527 0.0208087 0.0247741 0.0246527 0.0208087 0.0247283 0.0247083 0.0208087 0.0246585 0.0237029 0.0220087 0.0229325 0.00901144 0.0208087 0.0337208 0.00801288 0.0220087 0.0319912 0.00897379 0.0208087 0.0337584 0.00724422 0.0220087 0.0327598 0.00696288 0.0220087 0.0338098 0.00897379 0.0208087 0.0338613 0.00724422 0.0220087 0.0348598 0.00901144 0.0208087 0.0338989 0.00906288 0.0208087 0.0339127 -0.0101045 0.0220087 0.0356285 -0.00910589 0.0208087 0.0338989 -0.00914354 0.0208087 0.0338613 -0.0108731 0.0220087 0.0348598 -0.00915732 0.0208087 0.0338098 -0.0111018 0.0220087 0.0342771 -0.00910589 0.0208087 0.0337208 -0.0106963 0.0220087 0.0325005 -0.0111018 0.0220087 0.0333426 -0.0248336 0.0208087 0.0246997 -0.0265632 0.0220087 0.0237012 -0.0268445 0.0220087 0.0247512 -0.0248336 0.0208087 0.0248026 -0.0265632 0.0220087 0.0258012 -0.0338032 0.0220087 0.00696111 -0.0338546 0.0208087 0.00897202 -0.0348532 0.0220087 0.00724245 -0.0338923 0.0208087 0.00900968 -0.0356218 0.0220087 0.00801111 -0.0356218 0.0220087 0.0101111 -0.0338546 0.0208087 0.00915019 -0.0348532 0.0220087 0.0108798 -0.0338032 0.0208087 -0.00915909 -0.0347143 0.0220087 -0.0109483 -0.0338836 0.0208087 -0.00912036 -0.035445 0.0220087 -0.0103656 -0.0339035 0.0208087 -0.00903334 -0.0358505 0.0220087 -0.00952352 -0.0358505 0.0220087 -0.00858893 -0.0338836 0.0208087 -0.00899209 -0.0338478 0.0208087 -0.00896355 -0.0338032 0.0208087 -0.00895336 -0.0338032 0.0220087 -0.00695623 -0.0247445 0.0208087 -0.0248492 -0.0257945 0.0220087 -0.026565 -0.024796 0.0208087 -0.0248354 -0.0248336 0.0208087 -0.0247977 -0.0248474 0.0208087 -0.0247463 -0.0248336 0.0208087 -0.0246949 -0.0268445 0.0220087 -0.0247463 -0.024796 0.0208087 -0.0246572 -0.0265632 0.0220087 -0.0236963 -0.0247445 0.0208087 -0.0246434 -0.00905446 0.0220087 -0.035905 -0.0101045 0.0220087 -0.0356236 -0.00914354 0.0208087 -0.0338564 -0.00905446 0.0208087 -0.0337021 -0.00905446 0.0220087 -0.031705 0.00815172 0.0220087 -0.035697 0.00898245 0.0208087 -0.0338691 0.00742103 0.0220087 -0.0351143 0.00896259 0.0208087 -0.0338279 0.00896259 0.0208087 -0.0337821 0.00701553 0.0220087 -0.0342723 0.00898245 0.0208087 -0.0337408 0.00901825 0.0208087 -0.0337123 0.00906288 0.0208087 -0.0337021 0.00915196 0.0208087 -0.0337535 0.0108815 0.0220087 -0.032755 0.0111629 0.0220087 -0.033805 0.00916574 0.0208087 -0.033805 0.00915196 0.0208087 -0.0338564 0.0108815 0.0220087 -0.034855 0.00911431 0.0208087 -0.033894 0.0101129 0.0220087 -0.0356236 0.00906288 0.0208087 -0.0339078 -0.00896537 0.0208087 -0.0338564 -0.00895159 0.0208087 -0.033805 -0.0072358 0.0220087 -0.034855 -0.00741261 0.0220087 -0.0351143 -0.00896537 0.0208087 -0.0337535 -0.0246931 0.0208087 -0.0246572 -0.0247445 0.0220087 -0.0268463 -0.0226972 0.0220087 -0.0252136 -0.0246554 0.0208087 -0.0247977 -0.0229259 0.0220087 -0.0257963 -0.0246417 0.0208087 -0.0247463 -0.0226445 0.0220087 -0.0247463 -0.0231027 0.0220087 -0.023437 -0.0226972 0.0220087 -0.024279 -0.0337518 0.0208087 -0.00896714 -0.0327532 0.0220087 -0.00723757 -0.0337003 0.0208087 -0.00905623 -0.0319845 0.0220087 -0.00800623 -0.0317032 0.0220087 -0.00905623 -0.0337141 0.0208087 -0.00910766 -0.0319845 0.0220087 -0.0101062 -0.0327532 0.0220087 -0.0108749 -0.0338032 0.0208087 0.00916397 -0.0338032 0.0220087 0.0111611 -0.0338032 0.0208087 0.00895824 -0.0337518 0.0208087 0.00897202 -0.0317558 0.0220087 0.00859381 -0.0337141 0.0208087 0.00900968 -0.0319845 0.0220087 0.00801111 -0.0317558 0.0220087 0.0095284 -0.0337003 0.0208087 0.00906111 -0.0317032 0.0220087 0.00906111 -0.0337518 0.0208087 0.00915019 -0.0327532 0.0220087 0.0108798 -0.0321613 0.0220087 0.0103704 -0.0337141 0.0208087 0.00911254 -0.0247445 0.0208087 0.024854 -0.0246931 0.0208087 0.0248403 -0.0246417 0.0208087 0.0247512 -0.0246554 0.0208087 0.0246997 -0.0247445 0.0208087 0.0246483 -0.0236945 0.0220087 0.0229325 -0.00905446 0.0220087 0.0359098 -0.00905446 0.0220087 0.0317098 -0.00905446 0.0208087 0.033707 -0.0081433 0.0220087 0.0319178 -0.00900983 0.0208087 0.0337172 -0.00800446 0.0220087 0.0319912 -0.00895417 0.0208087 0.0338327 -0.00895417 0.0208087 0.033787 -0.00897403 0.0208087 0.033874 -0.00741261 0.0220087 0.0351192 0.00906288 0.0220087 0.0359098 0.00910751 0.0208087 0.0339025 0.0091433 0.0208087 0.033874 0.00916316 0.0208087 0.033787 0.0111102 0.0220087 0.0333426 0.0091433 0.0208087 0.0337457 0.00906288 0.0208087 0.033707 0.00906288 0.0220087 0.0317098 0.0248044 0.0208087 0.0248403 0.0248558 0.0208087 0.0247512 0.0248044 0.0208087 0.0246621 0.0265716 0.0220087 0.0237012 0.0247529 0.0208087 0.0246483 0.0338116 0.0220087 0.0111611 0.033863 0.0208087 0.00915019 0.0348616 0.0220087 0.0108798 0.0356303 0.0220087 0.0101111 0.0339145 0.0208087 0.00906111 0.0338116 0.0220087 0.00696111 0.0338562 0.0208087 -0.00896355 0.0347228 0.0220087 -0.0109483 0.0348616 0.0220087 -0.0108749 0.0338562 0.0208087 -0.0091489 0.0356303 0.0220087 -0.0101062 0.033892 0.0208087 -0.00912036 0.0339119 0.0208087 -0.00903334 0.0339119 0.0208087 -0.00907912 0.0359116 0.0220087 -0.00905623 0.035859 0.0220087 -0.00858893 0.0347228 0.0220087 -0.00716419 0.0348616 0.0220087 -0.00723757 0.0247529 0.0220087 -0.0226463 0.0258029 0.0220087 -0.0229276 0.0265716 0.0220087 -0.0236963 0.0248558 0.0208087 -0.0247463 0.0248044 0.0208087 -0.0248354 0.0247529 0.0208087 -0.0248492 0.0258029 0.0220087 -0.026565 -0.0414676 0.0300087 0.0414743 -0.0114378 0.0300087 0.0575255 4.20971e-06 0.0300087 0.0586524 0.0112121 0.0300087 0.0563486 0.0219894 0.0300087 0.0530793 0.0224486 0.0300087 0.054188 0.0319217 0.0300087 0.0477704 0.041476 0.0300087 0.0414743 0.0487699 0.0300087 0.0325866 0.0477721 0.0300087 0.0319199 0.0541897 0.0300087 0.0224468 0.0563503 0.0300087 0.0112104 0.0574542 0.0300087 2.44063e-06 0.0586542 0.0300087 2.44063e-06 0.0575273 0.0300087 -0.0114396 0.0563503 0.0300087 -0.0112055 0.0477721 0.0300087 -0.0319151 0.0487699 0.0300087 -0.0325818 0.041476 0.0300087 -0.0414694 0.0319217 0.0300087 -0.0477655 0.0219894 0.0300087 -0.0530744 0.0112121 0.0300087 -0.0563437 0.0114463 0.0300087 -0.0575206 4.20971e-06 0.0300087 -0.0586476 -0.0224402 0.0300087 -0.0541831 -0.0477637 0.0300087 -0.0319151 -0.0530727 0.0300087 -0.0219827 -0.0575188 0.0300087 -0.0114396 -0.0586458 0.0300087 2.44063e-06 -0.0575188 0.0300087 0.0114445 -0.0477637 0.0300087 0.0319199 -0.0541813 0.0300087 0.0224468 -0.0487615 0.0300087 0.0325866 0.0773459 0.0180087 0.0224261 0.0771959 0.0180087 0.0226859 0.0767237 0.0180087 0.0201038 0.0771959 0.0180087 0.0192218 0.0789335 0.0180087 0.0194222 0.0790637 0.0180087 0.0191519 0.0797596 0.0180087 0.0197069 0.0801458 0.0180087 0.0205088 0.0801458 0.0180087 0.0213989 0.079525 0.0180087 0.0220138 0.0797596 0.0180087 0.0222008 0.0559154 0.0180087 0.0561828 0.0572445 0.0180087 0.0555427 0.0589766 0.0180087 0.0562427 0.0589445 0.0180087 0.0572427 0.0592445 0.0180087 0.0572427 0.0587167 0.0180087 0.0580927 0.0580945 0.0180087 0.058715 0.0589766 0.0180087 0.0582427 0.0582445 0.0180087 0.0589748 0.0565069 0.0180087 0.0587744 0.0559154 0.0180087 0.0583027 0.0563767 0.0180087 0.0590447 0.0555871 0.0180087 0.057621 0.0552946 0.0180087 0.0576878 0.0555871 0.0180087 0.0568644 0.0552946 0.0180087 0.0567977 0.0760935 0.0180087 0.0303307 0.0760935 0.0180087 0.0304307 0.0737553 0.0180087 0.0289807 0.0736687 0.0180087 0.0262307 0.0747435 0.0180087 0.0252924 0.0774435 0.0180087 0.0252924 0.0784318 0.0180087 0.0262807 0.0788935 0.0180087 0.0276307 0.0774935 0.0180087 0.0300555 0.0593433 0.0180087 0.0526844 0.0592458 0.0180087 0.0527067 0.0593433 0.0180087 0.0514828 0.0592458 0.0180087 0.0514605 0.0619756 0.0180087 0.0493836 0.0607607 0.0180087 0.0495609 0.0619756 0.0180087 0.0492836 0.0633256 0.0180087 0.0497453 0.0633756 0.0180087 0.0496587 0.0643139 0.0180087 0.0534336 0.0644005 0.0180087 0.0534836 0.0633256 0.0180087 0.0544219 0.0633756 0.0180087 0.0545085 0.0619756 0.0180087 0.0547836 0.0608041 0.0180087 0.0545162 0.0598647 0.0180087 0.053767 0.0597865 0.0180087 0.0538294 0.0496605 0.0180087 0.0605738 0.0520854 0.0180087 0.0592738 0.0506854 0.0180087 0.059549 0.0534354 0.0180087 0.0596356 0.0534854 0.0180087 0.059549 0.0544236 0.0180087 0.0606238 0.0547854 0.0180087 0.0619738 0.0544236 0.0180087 0.0633238 0.0534854 0.0180087 0.0643987 0.0520854 0.0180087 0.0646738 0.0520854 0.0180087 0.0647738 0.0496605 0.0180087 0.0633738 0.0302647 0.0180087 0.0754909 0.0302647 0.0180087 0.0766926 0.0303622 0.0180087 0.0767148 0.0298216 0.0180087 0.0778375 0.0288473 0.0180087 0.0786145 0.0276324 0.0180087 0.0788918 0.0252942 0.0180087 0.0774418 0.0249324 0.0180087 0.0760918 0.0252942 0.0180087 0.0747418 0.0248324 0.0180087 0.0760918 0.0276324 0.0180087 0.0733918 0.0288039 0.0180087 0.0736591 0.0196265 0.0180087 0.0792541 0.0192982 0.0180087 0.0785724 0.0190058 0.0180087 0.0786392 0.0190058 0.0180087 0.0777491 0.0196265 0.0180087 0.0771342 0.0200878 0.0180087 0.0763922 0.020218 0.0180087 0.0766625 0.0209556 0.0180087 0.0761941 0.0218056 0.0180087 0.0767219 0.0219556 0.0180087 0.0764621 0.0224279 0.0180087 0.0773441 0.0229556 0.0180087 0.0781941 0.0226877 0.0180087 0.0791941 0.0224279 0.0180087 0.0790441 0.0218056 0.0180087 0.0796664 0.0209556 0.0180087 0.0801941 0.0200878 0.0180087 0.0799961 -0.0249917 0.0180087 0.0766926 -0.0255131 0.0180087 0.0777752 -0.0254349 0.0180087 0.0778375 -0.0264525 0.0180087 0.0785244 -0.027624 0.0180087 0.0787918 -0.027624 0.0180087 0.0788918 -0.028974 0.0180087 0.07843 -0.029024 0.0180087 0.0785166 -0.0300489 0.0180087 0.0774918 -0.0299623 0.0180087 0.0747418 -0.029024 0.0180087 0.0736669 -0.027624 0.0180087 0.0733918 -0.0264525 0.0180087 0.0736591 -0.0255131 0.0180087 0.0744083 -0.0254349 0.0180087 0.074346 -0.0547093 0.0180087 0.0625746 -0.0548068 0.0180087 0.0625969 -0.0532918 0.0180087 0.0594511 -0.052077 0.0180087 0.0591738 -0.052077 0.0180087 0.0592738 -0.050727 0.0180087 0.0596356 -0.0497387 0.0180087 0.0606238 -0.0496521 0.0180087 0.0605738 -0.049377 0.0180087 0.0619738 -0.0497387 0.0180087 0.0633238 -0.050677 0.0180087 0.0643987 -0.052077 0.0180087 0.0646738 -0.0542661 0.0180087 0.0637196 -0.0631821 0.0180087 0.0546063 -0.0640781 0.0180087 0.053767 -0.0641563 0.0180087 0.0538294 -0.0645995 0.0180087 0.0514828 -0.064697 0.0180087 0.0527067 -0.064697 0.0180087 0.0514605 -0.0631387 0.0180087 0.049651 -0.0631821 0.0180087 0.0495609 -0.0619672 0.0180087 0.0492836 -0.0605672 0.0180087 0.0496587 -0.0596289 0.0180087 0.0507336 -0.0595423 0.0180087 0.0506836 -0.0592672 0.0180087 0.0520836 -0.0591672 0.0180087 0.0520836 -0.0595423 0.0180087 0.0534836 -0.0606172 0.0180087 0.0544219 -0.0619672 0.0180087 0.0548836 -0.0788149 0.0180087 0.0270076 -0.0772566 0.0180087 0.0251981 -0.0782742 0.0180087 0.0258849 -0.0760851 0.0180087 0.0249307 -0.0747351 0.0180087 0.0252924 -0.0736602 0.0180087 0.0262307 -0.0733851 0.0180087 0.0276307 -0.0732851 0.0180087 0.0276307 -0.0747351 0.0180087 0.0299689 -0.0772566 0.0180087 0.0300633 -0.0773 0.0180087 0.0301534 -0.0782742 0.0180087 0.0293764 -0.0788149 0.0180087 0.0282537 -0.0209472 0.0180087 0.0798941 -0.0217972 0.0180087 0.0796664 -0.0219472 0.0180087 0.0799262 -0.0226792 0.0180087 0.0791941 -0.0226472 0.0180087 0.0781941 -0.0226792 0.0180087 0.0771941 -0.0217972 0.0180087 0.0767219 -0.0219472 0.0180087 0.0764621 -0.0209472 0.0180087 0.0761941 -0.0202096 0.0180087 0.0766625 -0.0192898 0.0180087 0.0778159 -0.0202096 0.0180087 0.0797258 -0.0564985 0.0180087 0.0587744 -0.0563683 0.0180087 0.0590447 -0.0572361 0.0180087 0.0589427 -0.0572361 0.0180087 0.0592427 -0.0582361 0.0180087 0.0589748 -0.0587083 0.0180087 0.0580927 -0.0589361 0.0180087 0.0572427 -0.0587083 0.0180087 0.0563927 -0.0564985 0.0180087 0.0557111 -0.0563683 0.0180087 0.0554408 -0.055907 0.0180087 0.0561828 -0.0555787 0.0180087 0.057621 -0.0552862 0.0180087 0.0567977 -0.0552862 0.0180087 0.0576878 -0.0556724 0.0180087 0.0584897 -0.0799195 0.0180087 0.0199538 -0.0798449 0.0180087 0.0213321 -0.0789251 0.0180087 0.0224855 -0.0771875 0.0180087 0.0226859 -0.0764875 0.0180087 0.0209538 -0.0764554 0.0180087 0.0199538 -0.0767152 0.0180087 0.0201038 -0.0773375 0.0180087 0.0194816 -0.0781875 0.0180087 0.0192538 0.0252942 0.0180087 -0.0747369 0.0249026 0.0180087 -0.0754638 0.0249026 0.0180087 -0.0767099 0.0262824 0.0180087 -0.0784251 0.0276324 0.0180087 -0.0787869 0.0264176 0.0180087 -0.0786096 0.0276324 0.0180087 -0.0788869 0.0299707 0.0180087 -0.0774369 0.0303324 0.0180087 -0.0760869 0.0300573 0.0180087 -0.0746869 0.0276324 0.0180087 -0.0732869 0.0262824 0.0180087 -0.0737486 0.0494531 0.0180087 -0.0613682 0.0498962 0.0180087 -0.0602232 0.0493556 0.0180087 -0.0613459 0.0494531 0.0180087 -0.0625698 0.0509139 0.0180087 -0.0644016 0.0508705 0.0180087 -0.0644917 0.0520854 0.0180087 -0.064669 0.0534854 0.0180087 -0.0643938 0.0544236 0.0180087 -0.063319 0.0545102 0.0180087 -0.063369 0.0547854 0.0180087 -0.061969 0.0548854 0.0180087 -0.061969 0.0520854 0.0180087 -0.059169 0.0607607 0.0180087 -0.0546014 0.0619756 0.0180087 -0.0548787 0.0633756 0.0180087 -0.0545036 0.0644005 0.0180087 -0.0534787 0.0646756 0.0180087 -0.0520787 0.0644005 0.0180087 -0.0506787 0.0607607 0.0180087 -0.049556 0.0608041 0.0180087 -0.0496461 0.0593433 0.0180087 -0.0514779 0.0593433 0.0180087 -0.0526795 0.0598647 0.0180087 -0.0537621 0.0597865 0.0180087 -0.0538245 0.0747435 0.0180087 -0.0252875 0.0760935 0.0180087 -0.0248258 0.0737553 0.0180087 -0.0262758 0.0732935 0.0180087 -0.0276258 0.0746935 0.0180087 -0.0300507 0.0760935 0.0180087 -0.0304258 0.0760935 0.0180087 -0.0303258 0.0782045 0.0180087 -0.0293092 0.0782827 0.0180087 -0.0293716 0.0788233 0.0180087 -0.0282488 0.077265 0.0180087 -0.0251932 0.0200878 0.0180087 -0.0763873 0.0192982 0.0180087 -0.077811 0.0190058 0.0180087 -0.0777442 0.0193919 0.0180087 -0.0794362 0.0200878 0.0180087 -0.0799912 0.0209556 0.0180087 -0.0801893 0.0219556 0.0180087 -0.0799213 0.0224279 0.0180087 -0.0790393 0.0226877 0.0180087 -0.0791893 0.0226556 0.0180087 -0.0781893 0.0224279 0.0180087 -0.0773393 0.0218056 0.0180087 -0.076717 0.0219556 0.0180087 -0.0764572 0.0209556 0.0180087 -0.0764893 0.020218 0.0180087 -0.0766576 0.0555125 0.0180087 -0.0562379 0.0557723 0.0180087 -0.0580879 0.0562445 0.0180087 -0.0589699 0.0587167 0.0180087 -0.0580879 0.0589445 0.0180087 -0.0572379 0.0589766 0.0180087 -0.0562379 0.0580945 0.0180087 -0.0557656 0.0582445 0.0180087 -0.0555058 0.0557723 0.0180087 -0.0563879 0.0562445 0.0180087 -0.0555058 0.0771959 0.0180087 -0.0192169 0.0764639 0.0180087 -0.019949 0.0767237 0.0180087 -0.021799 0.0764639 0.0180087 -0.021949 0.0771959 0.0180087 -0.022681 0.0796681 0.0180087 -0.020099 0.079928 0.0180087 -0.019949 0.0790459 0.0180087 -0.0194767 -0.0298131 0.0180087 -0.0743411 -0.0299623 0.0180087 -0.0747369 -0.0303538 0.0180087 -0.0767099 -0.030324 0.0180087 -0.0760869 -0.0299623 0.0180087 -0.0774369 -0.0298131 0.0180087 -0.0778326 -0.026274 0.0180087 -0.0784251 -0.0252857 0.0180087 -0.0774369 -0.026224 0.0180087 -0.0785117 -0.024924 0.0180087 -0.0760869 -0.024824 0.0180087 -0.0760869 -0.026224 0.0180087 -0.073662 -0.0288389 0.0180087 -0.0735642 -0.028974 0.0180087 -0.0737486 -0.0498878 0.0180087 -0.0602232 -0.052077 0.0180087 -0.059269 -0.053427 0.0180087 -0.0596307 -0.0544152 0.0180087 -0.060619 -0.0545018 0.0180087 -0.063369 -0.0544152 0.0180087 -0.063319 -0.053477 0.0180087 -0.0643938 -0.052077 0.0180087 -0.064769 -0.0494446 0.0180087 -0.0625698 -0.0494446 0.0180087 -0.0613682 -0.0493472 0.0180087 -0.062592 -0.049966 0.0180087 -0.0602855 -0.0641563 0.0180087 -0.0538245 -0.0619672 0.0180087 -0.0548787 -0.0619672 0.0180087 -0.0547787 -0.0606172 0.0180087 -0.054417 -0.0605672 0.0180087 -0.0545036 -0.0596289 0.0180087 -0.0534287 -0.0595423 0.0180087 -0.0506787 -0.0606172 0.0180087 -0.0497405 -0.0619672 0.0180087 -0.0493787 -0.0631387 0.0180087 -0.0496461 -0.0631821 0.0180087 -0.049556 -0.0645995 0.0180087 -0.0514779 -0.0645995 0.0180087 -0.0526795 -0.064697 0.0180087 -0.0527018 -0.0784234 0.0180087 -0.0262758 -0.0787851 0.0180087 -0.0276258 -0.0760851 0.0180087 -0.0303258 -0.0747351 0.0180087 -0.0299641 -0.0746851 0.0180087 -0.0300507 -0.0733851 0.0180087 -0.0276258 -0.0760851 0.0180087 -0.0249258 -0.0746851 0.0180087 -0.0252009 -0.0774351 0.0180087 -0.0252875 -0.0760851 0.0180087 -0.0248258 -0.0202096 0.0180087 -0.0766576 -0.0209472 0.0180087 -0.0761893 -0.0224194 0.0180087 -0.0773393 -0.0229472 0.0180087 -0.0781893 -0.0226792 0.0180087 -0.0791893 -0.0209472 0.0180087 -0.0801893 -0.0200794 0.0180087 -0.0799912 -0.0189973 0.0180087 -0.0777442 -0.0196181 0.0180087 -0.0771293 -0.0588935 0.0180087 -0.0576161 -0.0587997 0.0180087 -0.0584848 -0.0579737 0.0180087 -0.0587695 -0.0572361 0.0180087 -0.0589379 -0.0562361 0.0180087 -0.0589699 -0.0557638 0.0180087 -0.0580879 -0.0552361 0.0180087 -0.0572379 -0.0562361 0.0180087 -0.0555058 -0.0572361 0.0180087 -0.0555379 -0.0572361 0.0180087 -0.0552379 -0.0587997 0.0180087 -0.0559909 -0.0585652 0.0180087 -0.0561779 -0.0801373 0.0180087 -0.0205039 -0.0796597 0.0180087 -0.021799 -0.0790375 0.0180087 -0.0224212 -0.0797511 0.0180087 -0.0221959 -0.0790552 0.0180087 -0.0227509 -0.0764875 0.0180087 -0.020949 -0.0761875 0.0180087 -0.020949 -0.0767152 0.0180087 -0.020099 -0.0773375 0.0180087 -0.0194767 -0.0771875 0.0180087 -0.0192169 -0.0781875 0.0180087 -0.019249 -0.0790375 0.0180087 -0.0194767 -0.0790552 0.0180087 -0.019147 -0.0695252 0.0192087 0.0394809 -0.0689498 0.0192087 0.0404774 -0.0686716 0.0195087 0.0396524 -0.069104 0.0192087 0.0399021 -0.0684505 0.0195087 0.0404774 -0.0701005 0.0195087 0.0421274 -0.0692755 0.0195087 0.0419064 -0.0688105 0.0195087 0.0415062 -0.0684919 0.0195087 0.0408446 -0.0391808 0.0195087 0.071136 -0.0393489 0.0192087 0.0703633 -0.0395711 0.0192087 0.0693897 -0.0399715 0.0192087 0.0690704 -0.0391808 0.0195087 0.0690784 -0.0404708 0.0192087 -0.0689516 -0.0404708 0.0195087 -0.0717523 -0.0398954 0.0192087 -0.0710989 -0.0388622 0.0195087 -0.0697352 -0.0388208 0.0195087 -0.0701023 -0.0396458 0.0195087 -0.0686734 -0.0391808 0.0195087 -0.0690736 -0.0390418 0.0195087 -0.0692773 -0.0394742 0.0192087 -0.069527 -0.0701005 0.0192087 -0.0416233 -0.0692755 0.0195087 -0.0419015 -0.0688105 0.0195087 -0.0415013 -0.0684919 0.0195087 -0.0408397 -0.0689498 0.0192087 -0.0404726 -0.0695252 0.0192087 -0.039476 -0.0692755 0.0195087 -0.0390436 -0.0688105 0.0195087 -0.0394438 -0.069104 0.0192087 -0.0398972 -0.0686716 0.0195087 -0.0396476 -0.0803704 0.0192087 0.00099899 -0.0797951 0.0192087 2.44063e-06 -0.0799492 0.0192087 -0.000572917 -0.0795169 0.0195087 -0.000822559 -0.0803704 0.0192087 -0.000994109 0.070109 0.0192087 -0.0393218 0.0711055 0.0192087 -0.0398972 0.0712597 0.0192087 -0.0404726 0.0715379 0.0195087 -0.0396476 0.0711055 0.0192087 -0.0410479 0.0715379 0.0195087 -0.0412976 0.0706843 0.0192087 -0.0414691 0.070934 0.0195087 -0.0419015 0.070109 0.0195087 -0.0421226 0.0404792 0.0192087 -0.0689516 0.0410546 0.0192087 -0.0691058 0.0416299 0.0192087 -0.0701023 0.0414758 0.0192087 -0.0706777 0.0419082 0.0195087 -0.0709273 0.0413042 0.0195087 -0.0715313 0.0413042 0.0195087 0.0715361 0.0410546 0.0192087 0.0711037 0.0414758 0.0192087 0.0706826 0.0419082 0.0195087 0.0709322 0.0404792 0.0192087 0.0689565 0.070109 0.0192087 0.0416282 0.0715379 0.0195087 0.0413024 0.071759 0.0195087 0.0404774 0.0706843 0.0192087 0.0394809 0.070934 0.0195087 0.0390485 0.070109 0.0195087 0.0388274 0.0809542 0.0192087 0.00115316 0.0817792 0.0195087 0.00143138 0.0819508 0.0192087 0.000577799 0.0821049 0.0192087 2.44063e-06 0.0815296 0.0192087 -0.000994109 0.0809542 0.0192087 -0.00114828 -0.0346224 0.0243087 -0.0725196 -0.0706108 0.0243087 -0.0461326 -0.0768967 0.0243087 -0.0346555 0.06868 0.0243087 0.0413024 0.0793623 0.0243087 0.0285894 -0.0817708 0.0243087 0.00143138 -0.0489278 0.0243087 0.0326977 0.0572445 0.0243087 0.0540427 -0.0572361 0.0243087 0.0604427 -0.0547342 0.0243087 0.0552476 -0.0588361 0.0243087 0.0544715 -0.0620541 0.0243087 0.0571311 -0.0641563 0.0243087 0.0538294 -0.0706108 0.0243087 0.0461375 -0.064697 0.0243087 0.0527067 -0.0590065 0.0243087 0.0457055 -0.0595423 0.0243087 0.0506836 -0.0588361 0.0243087 0.060014 -0.0600074 0.0243087 0.0588427 -0.0795759 0.0243087 0.0180707 -0.0781875 0.0243087 0.0177538 -0.0725178 0.0243087 0.00970314 -0.0754162 0.0243087 0.0193538 -0.0765875 0.0243087 0.0237251 -0.0781875 0.0243087 0.0241538 -0.0806891 0.0243087 0.0245689 -0.0806893 0.0243087 0.0189587 0.0806978 0.0243087 -0.0189538 0.0795843 0.0243087 -0.0180659 0.0754246 0.0243087 -0.019349 0.0749959 0.0243087 -0.020949 0.0748786 0.0243087 -0.0301485 0.0760935 0.0243087 -0.0304258 0.0774935 0.0243087 -0.0300507 0.0785184 0.0243087 -0.0290258 0.0785184 0.0243087 -0.0262258 0.0795843 0.0243087 -0.0238321 0.0765959 0.0243087 -0.0237202 0.0774935 0.0243087 -0.0252009 0.0754246 0.0243087 -0.022549 0.0760935 0.0243087 -0.0248258 0.0748786 0.0243087 -0.0251031 0.0741447 0.0243087 -0.0346242 0.0586329 0.0243087 -0.0543548 0.0592458 0.0243087 -0.0514557 0.0597464 0.0243087 -0.0552427 0.0597865 0.0243087 -0.0538245 0.0633756 0.0243087 -0.0496539 0.0619756 0.0243087 -0.0548787 0.0626646 0.0243087 -0.0564652 0.0706192 0.0243087 -0.0461326 0.0225556 0.0243087 -0.0809605 0.0241556 0.0243087 -0.0781893 0.0225556 0.0243087 -0.075418 0.0209556 0.0243087 -0.0749893 0.0195672 0.0243087 -0.0753062 0.0184538 0.0243087 -0.0761941 0.0138878 0.0243087 -0.0831971 0.0178358 0.0243087 -0.0789013 0.0184538 0.0243087 -0.0801844 0.0572445 0.0243087 -0.0540379 0.0603643 0.0243087 -0.0565258 0.0620625 0.0243087 -0.0571263 0.0603643 0.0243087 -0.0579499 0.0508705 0.0243087 -0.0644917 0.0534854 0.0243087 -0.0643938 0.0545102 0.0243087 -0.063369 0.0498962 0.0243087 -0.0602232 0.0493556 0.0243087 -0.0613459 0.0493556 0.0243087 -0.062592 0.0544732 0.0243087 -0.0588379 0.059178 0.0243087 -0.060109 0.0544732 0.0243087 -0.0556379 0.0457073 0.0243087 -0.0568631 0.0806978 0.0243087 -0.0229441 0.0813157 0.0243087 -0.021661 0.0793623 0.0243087 -0.0285845 0.0813157 0.0243087 -0.0202369 0.0790989 0.0243087 0.0244923 0.0760935 0.0243087 0.0248307 0.0741447 0.0243087 0.0244923 0.0773084 0.0243087 0.0301534 0.0782827 0.0243087 0.0293764 0.0736687 0.0243087 0.0262307 0.0725262 0.0243087 0.0244923 0.0746935 0.0243087 0.0300555 0.0597865 0.0243087 0.0538294 0.0592458 0.0243087 0.0527067 0.0592458 0.0243087 0.0514605 0.0597865 0.0243087 0.0503378 0.0647756 0.0243087 0.0520836 0.0706192 0.0243087 0.0461375 0.0620625 0.0243087 0.0571311 0.0619756 0.0243087 0.0548836 0.0633756 0.0243087 0.0496587 0.0457073 0.0243087 0.0590131 0.0520854 0.0243087 0.0591738 0.0563028 0.0243087 0.0628148 0.059178 0.0243087 0.0601139 0.0558561 0.0243087 0.0601258 0.0542745 0.0243087 0.0602281 0.0547426 0.0243087 0.0592379 0.0518131 0.0243087 0.0665664 0.0533003 0.0243087 0.0644966 0.0492854 0.0243087 0.0619738 0.0506854 0.0243087 0.0643987 0.0572445 0.0243087 0.0604427 0.0298216 0.0243087 0.074346 0.0346308 0.0243087 0.0725245 0.0262324 0.0243087 0.0736669 0.0252076 0.0243087 0.0746918 0.0303622 0.0243087 0.0767148 0.0401504 0.0243087 0.074186 0.0600158 0.0243087 0.0556427 0.0604445 0.0243087 0.0572427 0.0600158 0.0243087 0.0588427 0.0541247 0.0243087 0.0565307 0.075694 0.0243087 0.0189587 0.0809672 0.0243087 0.0193538 0.0813959 0.0243087 0.0209538 0.0806975 0.0243087 0.0245689 0.0797959 0.0243087 0.0237251 0.0781959 0.0243087 0.0241538 -0.0568614 0.0243087 -0.0346242 -0.0489278 0.0243087 -0.0326929 -0.0326911 0.0243087 0.0489344 -0.0456989 0.0243087 0.0457055 0.0416174 0.0243087 0.0416157 0.0326995 0.0243087 0.0489344 0.0590149 0.0243087 0.0244923 0.0489362 0.0243087 0.0326977 0.0457073 0.0243087 0.0457055 0.0590149 0.0243087 0.0346291 0.0590149 0.0243087 0.0457055 0.0590149 0.0243087 0.00970314 0.0457073 0.0243087 -0.0457006 0.0489362 0.0243087 -0.0326929 0.0590149 0.0243087 -0.0346242 0.0577234 0.0243087 -0.0114786 0.024494 0.0243087 -0.0568631 0.0114853 0.0243087 -0.0577168 -0.0346224 0.0243087 0.0725245 -0.029024 0.0243087 0.0736669 -0.0346224 0.0243087 0.0741429 -0.0300489 0.0243087 0.0774918 -0.040142 0.0243087 0.074186 -0.0273842 0.0243087 0.0797821 -0.027624 0.0243087 0.0788918 -0.0138793 0.0243087 0.083202 -0.0177472 0.0243087 0.0781941 -0.0181759 0.0243087 0.0797941 -0.0216593 0.0243087 0.0813139 -0.0207025 0.0243087 0.0817714 -0.024067 0.0243087 0.0789062 -0.0248942 0.0243087 0.0767148 -0.0248942 0.0243087 0.0754687 -0.0254349 0.0243087 0.074346 -0.0193472 0.0243087 0.0754229 -0.050677 0.0243087 0.059549 -0.0496521 0.0243087 0.0605738 -0.0456989 0.0243087 0.0626083 -0.049277 0.0243087 0.0619738 -0.0496521 0.0243087 0.0633738 -0.052077 0.0243087 0.0647738 -0.0518046 0.0243087 0.0665664 -0.0562944 0.0243087 0.0628148 -0.0548068 0.0243087 0.0625969 -0.0548068 0.0243087 0.0613508 -0.0781875 0.0243087 -0.024149 -0.07851 0.0243087 -0.0290258 -0.0772413 0.0243087 -0.0338806 -0.0760851 0.0243087 -0.0304258 -0.0748702 0.0243087 -0.0301485 -0.0756856 0.0243087 -0.0189538 -0.0733553 0.0243087 -0.0270027 -0.0756856 0.0243087 -0.0229441 -0.0767991 0.0243087 -0.0238321 -0.0797875 0.0243087 -0.0181777 -0.0817647 0.0243087 -0.0207043 -0.0793539 0.0243087 -0.0285845 -0.0788851 0.0243087 -0.0276258 -0.0797875 0.0243087 -0.0237202 -0.0508621 0.0243087 -0.0594462 -0.053477 0.0243087 -0.0595441 -0.0545018 0.0243087 -0.063369 -0.0518046 0.0243087 -0.0665616 -0.053477 0.0243087 -0.0643938 -0.0508621 0.0243087 -0.0644917 -0.0498878 0.0243087 -0.0637147 -0.0493472 0.0243087 -0.062592 -0.0620541 0.0243087 -0.0571263 -0.0601344 0.0243087 -0.0591437 -0.0570565 0.0243087 -0.0621184 -0.0590065 0.0243087 -0.0457006 -0.0619672 0.0243087 -0.0492787 -0.0586245 0.0243087 -0.0543548 -0.0568614 0.0243087 -0.0457006 -0.0556361 0.0243087 -0.0544666 -0.0641563 0.0243087 -0.0538245 -0.0597379 0.0243087 -0.0552427 -0.0177472 0.0243087 -0.0781893 4.20971e-06 0.0243087 -0.0801381 -0.0193472 0.0243087 -0.075418 -0.0248942 0.0243087 -0.0754638 -0.0254349 0.0243087 -0.0743411 -0.027624 0.0243087 -0.0732869 -0.0261844 0.0243087 -0.0801791 -0.029024 0.0243087 -0.0785117 -0.027624 0.0243087 -0.0788869 -0.024067 0.0243087 -0.0789013 -0.0234491 0.0243087 -0.0761941 -0.0248942 0.0243087 -0.0767099 -0.0254349 0.0243087 -0.0778326 -0.0223356 0.0243087 -0.0810724 -0.0209472 0.0243087 -0.0813893 -0.0207025 0.0243087 -0.0817665 -0.0181759 0.0243087 -0.0797893 -0.0809458 0.0243087 -0.00164756 -0.0790904 0.0243087 -0.00969826 -0.0790904 0.0243087 0.00970314 -0.0819916 0.0243087 0.00970314 -0.0801208 0.0243087 -0.0014265 -0.0795169 0.0243087 0.000827441 -0.0825958 0.0243087 2.44063e-06 -0.0840577 0.0243087 0.00696801 -0.0840577 0.0243087 -0.00696313 -0.0819916 0.0243087 -0.00969826 -0.0817708 0.0243087 -0.0014265 0.0262324 0.0243087 -0.073662 0.0252076 0.0243087 -0.0746869 0.024494 0.0243087 -0.0801381 0.0252076 0.0243087 -0.0774869 0.0262324 0.0243087 -0.0785117 0.0245417 0.0243087 -0.0806997 0.0259945 0.0243087 -0.0802436 0.0288473 0.0243087 -0.0735642 0.0303622 0.0243087 -0.0754638 0.0346308 0.0243087 -0.0725196 0.0276324 0.0243087 -0.0788869 0.0298216 0.0243087 -0.0778326 0.0396542 0.0243087 -0.0715313 0.0404792 0.0243087 -0.0717523 0.0419082 0.0243087 -0.0692773 0.0457073 0.0243087 -0.0666106 0.0404792 0.0243087 -0.0684523 0.0419082 0.0243087 -0.0709273 0.0421292 0.0243087 -0.0701023 0.06868 0.0243087 -0.0396476 0.070934 0.0243087 -0.0419015 0.0715379 0.0243087 -0.0396476 0.06868 0.0243087 -0.0412976 0.0708875 0.0243087 -0.0457193 0.070109 0.0243087 -0.0421226 0.0769051 0.0243087 -0.0346555 0.072734 0.0243087 -0.0427211 0.0817792 0.0243087 0.00143138 0.083791 0.0243087 -0.00972852 0.0790989 0.0243087 0.00970314 0.0809542 0.0243087 0.00165244 0.0826042 0.0243087 2.44063e-06 0.0840661 0.0243087 -0.00696313 0.0840661 0.0243087 0.00696801 0.083791 0.0243087 0.0097334 0.0797959 0.0243087 0.0181826 0.0790989 0.0243087 -0.00969826 0.0741447 0.0243087 0.0346291 0.070109 0.0243087 0.0388274 0.0725262 0.0243087 0.0346291 0.0715379 0.0243087 0.0396524 0.0715379 0.0243087 0.0413024 0.0413042 0.0243087 0.0686783 0.0457073 0.0243087 0.0666155 0.0396542 0.0243087 0.0686783 0.0520854 0.0243087 0.0647738 0.0419082 0.0243087 0.0692822 0.0388292 0.0243087 0.0701072 0.0421292 0.0243087 0.0701072 0.0419082 0.0243087 0.0709322 0.0413042 0.0243087 0.0715361 0.0346308 0.0243087 0.0741429 0.0396542 0.0243087 0.0715361 0.0225556 0.0243087 0.0754229 0.024494 0.0243087 0.0741429 0.0237269 0.0243087 0.0765941 0.0237269 0.0243087 0.0797941 0.0225556 0.0243087 0.0809654 0.0195672 0.0243087 0.075311 0.0138878 0.0243087 0.083202 0.0178358 0.0243087 0.0789062 4.20971e-06 0.0243087 0.0741429 0.0178358 0.0243087 0.0774821 -0.0402115 0.0243087 0.0741484 -0.050677 0.0243087 0.0643987 -0.0517336 0.0243087 0.0666217 -0.0456989 0.0243087 0.0666155 -0.0418997 0.0243087 0.0692822 -0.0412958 0.0243087 0.0686783 -0.0391808 0.0243087 0.0690784 -0.0427927 0.0243087 0.0726891 -0.0418997 0.0243087 0.0709322 -0.0421208 0.0243087 0.0701072 -0.0708791 0.0243087 0.0457242 -0.0709255 0.0243087 0.0390485 -0.0688105 0.0243087 0.0415062 -0.0641563 0.0243087 0.0503378 -0.0688105 0.0243087 0.0394487 -0.0666089 0.0243087 0.0346291 -0.0684919 0.0243087 0.0401103 -0.0684919 0.0243087 0.0408446 -0.0666089 0.0243087 0.0457055 -0.0736602 0.0243087 0.0262307 -0.0790904 0.0243087 0.0244923 -0.0782742 0.0243087 0.0258849 -0.0725178 0.0243087 0.0244923 -0.0782742 0.0243087 0.0293764 -0.0788149 0.0243087 0.0282537 -0.0788149 0.0243087 0.0270076 -0.0773 0.0243087 0.025108 -0.0760851 0.0243087 0.0248307 -0.0760851 0.0243087 0.0304307 -0.0768967 0.0243087 0.0346604 -0.0772413 0.0243087 0.0338854 -0.0773 0.0243087 0.0301534 -0.0717505 0.0243087 -0.0404726 -0.0715295 0.0243087 -0.0412976 -0.0725178 0.0243087 -0.0346242 -0.0709255 0.0243087 -0.0390436 -0.0693846 0.0243087 -0.038986 -0.0701005 0.0243087 -0.0421226 -0.0684919 0.0243087 -0.0408397 -0.0666089 0.0243087 -0.0346242 -0.0684919 0.0243087 -0.0401054 -0.0688105 0.0243087 -0.0394438 -0.0458561 0.0243087 -0.0707913 -0.0404708 0.0243087 -0.0684523 -0.0412958 0.0243087 -0.0686734 -0.0456989 0.0243087 -0.0666106 -0.0421208 0.0243087 -0.0701023 -0.0418997 0.0243087 -0.0709273 -0.0404708 0.0243087 -0.0717523 -0.0456989 0.0243087 -0.0590083 -0.0427927 0.0243087 -0.0726842 -0.0388622 0.0243087 -0.0704695 -0.0388622 0.0243087 -0.0697352 -0.0391808 0.0243087 -0.0690736 4.20971e-06 0.0243087 -0.0666106 4.20971e-06 0.0243087 -0.0590083 0.024494 0.0243087 -0.0666106 0.024494 0.0243087 -0.0725196 4.20971e-06 0.0243087 -0.0725196 -0.0346224 0.0243087 -0.0666106 -0.0346224 0.0243087 -0.0590083 -0.0456989 0.0243087 -0.0568631 -0.0456989 0.0243087 -0.0457006 -0.0540361 0.0243087 -0.0572379 0.0346308 0.0243087 -0.0590083 0.0457073 0.0243087 -0.0590083 0.0346308 0.0243087 -0.0568631 0.0326995 0.0243087 -0.0489295 0.024494 0.0243087 -0.0590083 0.0346308 0.0243087 -0.0666106 0.0276324 0.0243087 -0.0732869 -0.041609 0.0243087 -0.0416108 -0.0326911 0.0243087 -0.0489295 -0.0346224 0.0243087 -0.0568631 -0.0725178 0.0243087 -0.00969826 -0.0767991 0.0243087 -0.0180659 0.0725262 0.0243087 0.00970314 0.0741447 0.0243087 0.00970314 0.0741447 0.0243087 -0.00969826 0.0725262 0.0243087 -0.00969826 0.0733637 0.0243087 -0.0270027 0.069284 0.0243087 0.0390485 0.0725262 0.0243087 -0.0346242 0.070109 0.0243087 -0.0388226 -0.0725178 0.0243087 0.0346291 -0.0666089 0.0243087 0.0244923 0.0626101 0.0243087 0.0457055 0.0626101 0.0243087 0.0346291 0.0626101 0.0243087 0.0244923 0.0626101 0.0243087 0.00970314 0.0626101 0.0243087 -0.00969826 0.0590149 0.0243087 -0.00969826 0.0626101 0.0243087 -0.0346242 0.0590149 0.0243087 -0.0457006 0.0626101 0.0243087 -0.0457006 -0.0558477 0.0243087 0.0543596 -0.0572361 0.0243087 0.0540427 -0.0568614 0.0243087 0.0457055 -0.0568614 0.0243087 0.0346291 -0.0590065 0.0243087 0.0244923 -0.0568614 0.0243087 0.0244923 -0.0590065 0.0243087 0.00970314 -0.0588458 0.0243087 2.44063e-06 -0.057715 0.0243087 -0.0114786 -0.0590065 0.0243087 -0.0346242 -0.0590065 0.0243087 0.0346291 -0.0666089 0.0243087 0.00970314 -0.0590065 0.0243087 -0.00969826 -0.0666089 0.0243087 -0.00969826 -0.0666089 0.0243087 -0.0457006 0.0457073 0.0243087 0.0626083 0.0346308 0.0243087 0.0626083 -0.0456989 0.0243087 0.0590131 -0.0346224 0.0243087 0.0666155 -0.0404708 0.0243087 0.0684572 0.024494 0.0243087 0.0725245 0.0346308 0.0243087 0.0666155 0.0346308 0.0243087 0.0590131 0.0225251 0.0243087 0.0543728 0.024494 0.0243087 0.0590131 0.0114853 0.0243087 0.0577217 4.20971e-06 0.0243087 0.0626083 -0.0346224 0.0243087 0.0626083 -0.0346224 0.0243087 0.0590131 -0.0114769 0.0243087 0.0577217 4.20971e-06 0.0243087 0.0725245 0.024494 0.0243087 0.0666155 4.20971e-06 0.0243087 0.0666155 0.024494 0.0243087 0.0626083 4.20971e-06 0.0243087 0.0590131 -0.0543113 0.0213087 0.0565752 -0.0558288 0.0213087 0.0561205 -0.0548906 0.0213087 0.0553723 -0.0564551 0.0213087 0.055621 -0.0581361 0.0213087 0.0556839 -0.0587949 0.0213087 0.0563427 -0.0602361 0.0213087 0.0572427 -0.0581361 0.0213087 0.0588016 -0.0572361 0.0213087 0.0602427 -0.0139781 0.0237087 0.0837938 -0.027579 0.0182087 0.0803496 -0.0404275 0.0182087 0.0747137 -0.0521732 0.0182087 0.0670399 -0.0624955 0.0237087 0.0575375 -0.0624955 0.0182087 0.0575375 -0.0777907 0.0237087 0.0341265 -0.0777907 0.0182087 0.0341265 -0.0823463 0.0237087 0.0208564 -0.0846556 0.0237087 0.00701756 -0.0846556 0.0182087 0.00701756 -0.0846556 0.0182087 -0.00701267 -0.0823463 0.0182087 -0.0208516 -0.0777907 0.0237087 -0.0341216 -0.0777907 0.0182087 -0.0341216 -0.0624955 0.0237087 -0.0575326 -0.0404275 0.0182087 -0.0747089 -0.027579 0.0237087 -0.0803447 -0.027579 0.0182087 -0.0803447 4.20971e-06 0.0182087 -0.0849476 4.20971e-06 0.0243087 0.0588524 4.20971e-06 0.0298087 0.0588524 -0.0114769 0.0298087 0.0577217 -0.0225167 0.0298087 0.0543728 -0.0225167 0.0243087 0.0543728 -0.0326911 0.0298087 0.0489344 -0.041609 0.0243087 0.0416157 -0.0543661 0.0243087 0.0225234 -0.057715 0.0298087 0.0114835 -0.057715 0.0243087 0.0114835 -0.0543661 0.0298087 -0.0225185 -0.0543661 0.0243087 -0.0225185 -0.0489278 0.0298087 -0.0326929 -0.0326911 0.0298087 -0.0489295 -0.0225167 0.0243087 -0.0543679 -0.0114769 0.0243087 -0.0577168 0.0209556 0.0241087 0.0811941 0.0224556 0.0213087 0.0807922 0.0235537 0.0213087 0.0796941 0.0239556 0.0241087 0.0781941 0.0224556 0.0241087 0.0755961 0.0209556 0.0213087 0.0799941 0.0218556 0.0213087 0.079753 0.0225145 0.0213087 0.0790941 0.0239556 0.0213087 0.0781941 0.0225145 0.0213087 0.0772941 0.0235537 0.0213087 0.0766941 0.0224556 0.0213087 0.0755961 0.0209556 0.0213087 0.0763941 0.0209556 0.0213087 0.0751941 0.0195483 0.0213087 0.0770719 0.019654 0.0213087 0.0754912 0.0192007 0.0213087 0.0777936 0.0180308 0.0213087 0.0788617 0.019654 0.0213087 0.080897 0.0587445 0.0241087 0.0598408 0.0602445 0.0213087 0.0572427 0.0598426 0.0213087 0.0557427 0.0602445 0.0241087 0.0572427 0.0587445 0.0241087 0.0546447 0.0558372 0.0213087 0.0561205 0.0554896 0.0213087 0.0568422 0.0543197 0.0213087 0.0565752 0.0558372 0.0213087 0.058365 0.054899 0.0213087 0.0591132 0.0559429 0.0213087 0.0599456 0.0572445 0.0213087 0.0602427 0.0587445 0.0213087 0.0598408 0.0588033 0.0213087 0.0581427 0.0598426 0.0213087 0.0587427 0.0590445 0.0213087 0.0572427 0.0588033 0.0213087 0.0563427 0.0581445 0.0213087 0.0556839 0.0587445 0.0213087 0.0546447 0.0572445 0.0213087 0.0542427 0.0559429 0.0213087 0.0545398 0.0796959 0.0213087 0.0235519 0.0796959 0.0241087 0.0235519 0.080794 0.0213087 0.0224538 0.080794 0.0241087 0.0224538 0.0811959 0.0213087 0.0209538 0.0811959 0.0241087 0.0209538 0.0796959 0.0213087 0.0183558 0.080794 0.0241087 0.0194538 0.0796959 0.0241087 0.0183558 0.0781959 0.0213087 0.0179538 0.0752711 0.0213087 0.0202863 0.0752711 0.0213087 0.0216214 0.0758504 0.0213087 0.0228243 0.0781959 0.0213087 0.0227538 0.0768943 0.0213087 0.0236567 0.0790959 0.0213087 0.0225127 0.0799959 0.0213087 0.0209538 0.0790959 0.0213087 0.019395 0.080794 0.0213087 0.0194538 0.0768943 0.0213087 0.0182509 0.076441 0.0213087 0.0205533 0.0217306 0.0181587 0.0768518 0.0225056 0.0181587 0.0781941 0.0226556 0.0180087 0.0781941 0.0217306 0.0181587 0.0795365 0.0217306 0.0210587 0.0795365 0.022298 0.0181587 0.0789691 0.022298 0.0210587 0.0789691 0.0225056 0.0210587 0.0781941 0.022298 0.0181587 0.0774191 0.022298 0.0210587 0.0774191 0.0227556 0.0213087 0.0781941 0.0217306 0.0210587 0.0768518 0.0218556 0.0213087 0.0766353 0.0580945 0.0180087 0.0557705 0.0587167 0.0180087 0.0563927 0.0587945 0.0181587 0.0572427 0.0585868 0.0181587 0.0580177 0.0572445 0.0180087 0.0589427 0.0580195 0.0181587 0.0585851 0.0572445 0.0210587 0.0587927 0.0585868 0.0210587 0.0580177 0.0585868 0.0181587 0.0564677 0.0580195 0.0181587 0.0559004 0.0580195 0.0210587 0.0559004 0.0580195 0.0210587 0.0585851 0.0572445 0.0213087 0.0590427 0.0581445 0.0213087 0.0588016 0.0587945 0.0210587 0.0572427 0.0585868 0.0210587 0.0564677 0.0572445 0.0210587 0.0556927 0.0781959 0.0180087 0.0226538 0.0781959 0.0181587 0.0225038 0.0789335 0.0180087 0.0224855 0.0789709 0.0181587 0.0222962 0.0795382 0.0181587 0.0217288 0.079707 0.0181587 0.0212987 0.0798533 0.0180087 0.0213321 0.0797459 0.0181587 0.0209538 0.0798533 0.0180087 0.0205756 0.079525 0.0180087 0.0198939 0.0794077 0.0181587 0.0199874 0.0788684 0.0181587 0.0195573 0.0781959 0.0180087 0.0192538 0.0788684 0.0181587 0.0223503 0.0789709 0.0210587 0.0222962 0.0794077 0.0181587 0.0219203 0.0795382 0.0210587 0.0217288 0.079707 0.0181587 0.0206089 0.0795382 0.0181587 0.0201788 0.0789709 0.0181587 0.0196115 0.0789709 0.0210587 0.0196115 0.0797459 0.0210587 0.0209538 0.0797547 0.0213087 0.0218538 0.0795382 0.0210587 0.0201788 0.0797547 0.0213087 0.0200538 0.0781959 0.0210587 0.0194038 0.0209556 0.0243087 0.0813941 0.0224556 0.0241087 0.0807922 0.0235537 0.0241087 0.0796941 0.0235537 0.0241087 0.0766941 0.0241556 0.0243087 0.0781941 0.0598426 0.0241087 0.0587427 0.0588445 0.0243087 0.060014 0.0598426 0.0241087 0.0557427 0.0588445 0.0243087 0.0544715 0.0572445 0.0241087 0.0542427 0.0781959 0.0241087 0.0239538 0.0809672 0.0243087 0.0225538 0.0781959 0.0241087 0.0179538 0.0781959 0.0243087 0.0177538 0.0297434 0.0180087 0.0744083 0.0300698 0.0182087 0.0755355 0.0300698 0.0182087 0.0766481 0.0297434 0.0180087 0.0777752 0.0288039 0.0180087 0.0785244 0.0276324 0.0182087 0.0785918 0.0287171 0.0182087 0.0783442 0.0287171 0.0240087 0.0783442 0.029587 0.0240087 0.0776505 0.029587 0.0182087 0.0776505 0.029587 0.0182087 0.074533 0.0287171 0.0182087 0.0738393 0.0276324 0.0182087 0.0735918 0.0276324 0.0240087 0.0735918 0.0288473 0.0243087 0.0786145 0.0300698 0.0240087 0.0766481 0.0298216 0.0243087 0.0778375 0.0300698 0.0240087 0.0755355 0.0303622 0.0243087 0.0754687 0.029587 0.0240087 0.074533 0.0287171 0.0240087 0.0738393 0.0288473 0.0243087 0.073569 0.0534354 0.0180087 0.0643121 0.0533354 0.0182087 0.0641389 0.0542504 0.0182087 0.0632238 0.05404 0.0182087 0.0604151 0.05404 0.0182087 0.0635326 0.05404 0.0240087 0.0635326 0.0545227 0.0182087 0.0625301 0.0545854 0.0182087 0.0619738 0.0545227 0.0240087 0.0625301 0.0545227 0.0182087 0.0614175 0.0545227 0.0240087 0.0614175 0.0542504 0.0182087 0.0607238 0.0531701 0.0240087 0.0597214 0.0533354 0.0182087 0.0598088 0.0531701 0.0240087 0.0642263 0.0542745 0.0243087 0.0637196 0.0548152 0.0243087 0.0625969 0.0548152 0.0243087 0.0613508 0.05404 0.0240087 0.0604151 0.0533003 0.0243087 0.0594511 0.0632256 0.0182087 0.0499185 0.0641407 0.0182087 0.0508336 0.0643139 0.0180087 0.0507336 0.0644756 0.0182087 0.0520836 0.0646756 0.0180087 0.0520836 0.0632256 0.0182087 0.0542487 0.0619756 0.0182087 0.0545836 0.0641407 0.0182087 0.0533336 0.0619756 0.0182087 0.0495836 0.0619756 0.0240087 0.0545836 0.0632256 0.0240087 0.0542487 0.0633756 0.0243087 0.0545085 0.0644005 0.0243087 0.0534836 0.0641407 0.0240087 0.0533336 0.0644756 0.0240087 0.0520836 0.0644005 0.0243087 0.0506836 0.0641407 0.0240087 0.0508336 0.0632256 0.0240087 0.0499185 0.0774435 0.0180087 0.0299689 0.0782586 0.0182087 0.0288807 0.0784318 0.0180087 0.0289807 0.0787935 0.0180087 0.0276307 0.0785935 0.0182087 0.0276307 0.0785308 0.0182087 0.0270744 0.0773435 0.0182087 0.0254656 0.0760935 0.0180087 0.0249307 0.0780481 0.0182087 0.0260719 0.0760935 0.0182087 0.0301307 0.0771782 0.0240087 0.0298831 0.0773435 0.0182087 0.0297957 0.0780481 0.0240087 0.0291894 0.0780481 0.0182087 0.0291894 0.0785308 0.0240087 0.028187 0.0785308 0.0182087 0.028187 0.0785308 0.0240087 0.0270744 0.0782586 0.0182087 0.0263807 0.0771782 0.0240087 0.0253782 0.0760935 0.0243087 0.0304307 0.0788233 0.0243087 0.0282537 0.0788233 0.0243087 0.0270076 0.0780481 0.0240087 0.0260719 0.0782827 0.0243087 0.0258849 0.0773084 0.0243087 0.025108 0.0224556 0.0241087 -0.0755912 0.0224556 0.0213087 -0.0755912 0.0235537 0.0213087 -0.0766893 0.0235537 0.0241087 -0.0796893 0.0224556 0.0213087 -0.0807873 0.019654 0.0213087 -0.0754863 0.0218556 0.0213087 -0.0766304 0.0209556 0.0213087 -0.0751893 0.0227556 0.0213087 -0.0781893 0.0239556 0.0213087 -0.0781893 0.0235537 0.0213087 -0.0796893 0.0225145 0.0213087 -0.0790893 0.0201746 0.0213087 -0.079811 0.0209556 0.0213087 -0.0811893 0.0195483 0.0213087 -0.0793115 0.019654 0.0213087 -0.0808922 0.0180308 0.0213087 -0.0788568 0.0180308 0.0213087 -0.0775217 0.0201746 0.0213087 -0.0765675 0.0587445 0.0241087 -0.0546398 0.0598426 0.0213087 -0.0557379 0.0602445 0.0241087 -0.0572379 0.0602445 0.0213087 -0.0572379 0.0598426 0.0213087 -0.0587379 0.0585462 0.0241087 -0.0599408 0.0587445 0.0213087 -0.0598359 0.0572445 0.0213087 -0.0542379 0.0587445 0.0213087 -0.0546398 0.0588033 0.0213087 -0.0563379 0.0588033 0.0213087 -0.0581379 0.0572445 0.0213087 -0.0602379 0.0556857 0.0213087 -0.0581379 0.0557445 0.0213087 -0.0598359 0.0556857 0.0213087 -0.0563379 0.0546464 0.0213087 -0.0557379 0.0794976 0.0241087 -0.0182461 0.0805414 0.0213087 -0.0190785 0.0805414 0.0241087 -0.0190785 0.0811207 0.0241087 -0.0216165 0.0811207 0.0213087 -0.0216165 0.0794976 0.0241087 -0.0236519 0.0781959 0.0213087 -0.023949 0.0781959 0.0241087 -0.023949 0.0789769 0.0213087 -0.0193272 0.0799508 0.0213087 -0.0205484 0.0811207 0.0213087 -0.0202814 0.0796032 0.0213087 -0.0220712 0.0805414 0.0213087 -0.0228194 0.0789769 0.0213087 -0.0225707 0.0794976 0.0213087 -0.0236519 0.0781959 0.0213087 -0.022749 0.0766371 0.0213087 -0.021849 0.0766371 0.0213087 -0.020049 0.0751959 0.0213087 -0.020949 0.0781959 0.0213087 -0.017949 0.0794976 0.0213087 -0.0182461 0.0218056 0.0180087 -0.0796615 0.0217306 0.0181587 -0.0795316 0.022298 0.0181587 -0.0789643 0.022298 0.0181587 -0.0774143 0.0209556 0.0210587 -0.0766393 0.0217306 0.0181587 -0.0768469 0.0225056 0.0181587 -0.0781893 0.0217306 0.0210587 -0.0795316 0.0209556 0.0213087 -0.0763893 0.0217306 0.0210587 -0.0768469 0.022298 0.0210587 -0.0774143 0.0225145 0.0213087 -0.0772893 0.0225056 0.0210587 -0.0781893 0.022298 0.0210587 -0.0789643 0.0218556 0.0213087 -0.0797481 0.0572445 0.0180087 -0.0589379 0.0580945 0.0180087 -0.0587101 0.0587945 0.0181587 -0.0572379 0.0587167 0.0180087 -0.0563879 0.0580195 0.0181587 -0.0558955 0.0572445 0.0181587 -0.0556879 0.0572445 0.0180087 -0.0555379 0.0580195 0.0210587 -0.0558955 0.0585868 0.0181587 -0.0564629 0.0585868 0.0210587 -0.0564629 0.0587945 0.0210587 -0.0572379 0.0585868 0.0181587 -0.0580129 0.0580195 0.0181587 -0.0585802 0.0580195 0.0210587 -0.0585802 0.0572445 0.0210587 -0.0587879 0.0581445 0.0213087 -0.055679 0.0585868 0.0210587 -0.0580129 0.0590445 0.0213087 -0.0572379 0.0581445 0.0213087 -0.0587967 0.0572445 0.0213087 -0.0590379 0.0781959 0.0181587 -0.019399 0.0789709 0.0181587 -0.0196066 0.0795382 0.0181587 -0.020174 0.079707 0.0181587 -0.0206041 0.0798959 0.0180087 -0.020949 0.0781959 0.0181587 -0.022499 0.0789709 0.0181587 -0.0222913 0.0781959 0.0180087 -0.022649 0.0790459 0.0180087 -0.0224212 0.0794077 0.0181587 -0.0219154 0.0796681 0.0180087 -0.021799 0.0795382 0.0181587 -0.021724 0.0794077 0.0210587 -0.0199826 0.0794077 0.0181587 -0.0199826 0.0797459 0.0181587 -0.020949 0.079707 0.0210587 -0.0212939 0.079707 0.0181587 -0.0212939 0.0788684 0.0210587 -0.0223455 0.0781959 0.0210587 -0.022499 0.0788684 0.0210587 -0.0195525 0.0781959 0.0213087 -0.019149 0.0796032 0.0213087 -0.0198267 0.079707 0.0210587 -0.0206041 0.0799508 0.0213087 -0.0213495 0.0794077 0.0210587 -0.0219154 0.0235537 0.0241087 -0.0766893 0.0239556 0.0241087 -0.0781893 0.0237269 0.0243087 -0.0765893 0.0224556 0.0241087 -0.0807873 0.0237269 0.0243087 -0.0797893 0.0572445 0.0243087 -0.0604379 0.0572445 0.0241087 -0.0602379 0.0586329 0.0243087 -0.060121 0.0587445 0.0241087 -0.0598359 0.05959 0.0241087 -0.0591083 0.0597464 0.0243087 -0.059233 0.0598426 0.0241087 -0.0587379 0.0601693 0.0241087 -0.0579054 0.0601693 0.0241087 -0.0565703 0.0598426 0.0241087 -0.0557379 0.05959 0.0241087 -0.0553674 0.0585462 0.0241087 -0.0545349 0.0781959 0.0241087 -0.017949 0.0811207 0.0241087 -0.0202814 0.0805414 0.0241087 -0.0228194 0.0276324 0.0182087 -0.0735869 0.0289824 0.0180087 -0.0737486 0.0299707 0.0180087 -0.0747369 0.0297975 0.0182087 -0.0748369 0.0300698 0.0182087 -0.0755306 0.0300698 0.0182087 -0.0766432 0.0288824 0.0182087 -0.0782519 0.0289824 0.0180087 -0.0784251 0.029587 0.0182087 -0.0776456 0.0276324 0.0240087 -0.0735869 0.0288824 0.0182087 -0.0739218 0.029587 0.0240087 -0.0745282 0.029587 0.0182087 -0.0745282 0.0300698 0.0240087 -0.0766432 0.0301324 0.0182087 -0.0760869 0.0297975 0.0182087 -0.0773369 0.0276324 0.0182087 -0.0785869 0.0287171 0.0240087 -0.0738344 0.0298216 0.0243087 -0.0743411 0.0300698 0.0240087 -0.0755306 0.029587 0.0240087 -0.0776456 0.0303622 0.0243087 -0.0767099 0.0287171 0.0240087 -0.0783393 0.0288473 0.0243087 -0.0786096 0.0534354 0.0180087 -0.0643072 0.0545854 0.0182087 -0.061969 0.0542504 0.0182087 -0.060719 0.0544236 0.0180087 -0.060619 0.0533354 0.0182087 -0.0598039 0.0534354 0.0180087 -0.0596307 0.0520854 0.0180087 -0.059269 0.0520854 0.0240087 -0.059469 0.0533354 0.0240087 -0.0598039 0.0542504 0.0240087 -0.060719 0.0545854 0.0240087 -0.061969 0.0542504 0.0240087 -0.063219 0.0542504 0.0182087 -0.063219 0.0533354 0.0182087 -0.064134 0.0520854 0.0243087 -0.059169 0.0534854 0.0243087 -0.0595441 0.0545102 0.0243087 -0.060569 0.0548854 0.0243087 -0.061969 0.0533354 0.0240087 -0.064134 0.0520854 0.0243087 -0.064769 0.0619756 0.0180087 -0.0547787 0.0633256 0.0180087 -0.054417 0.0643139 0.0180087 -0.0534287 0.0641407 0.0182087 -0.0533287 0.0641407 0.0182087 -0.0508287 0.0643139 0.0180087 -0.0507287 0.0632256 0.0182087 -0.0499137 0.0633256 0.0180087 -0.0497405 0.0632256 0.0240087 -0.0499137 0.0644756 0.0182087 -0.0520787 0.0644756 0.0240087 -0.0520787 0.0641407 0.0240087 -0.0533287 0.0632256 0.0182087 -0.0542438 0.0619756 0.0240087 -0.0495787 0.0619756 0.0243087 -0.0492787 0.0641407 0.0240087 -0.0508287 0.0644005 0.0243087 -0.0506787 0.0647756 0.0243087 -0.0520787 0.0644005 0.0243087 -0.0534787 0.0632256 0.0240087 -0.0542438 0.0633756 0.0243087 -0.0545036 0.0619756 0.0240087 -0.0545787 0.0760935 0.0182087 -0.0251258 0.0771782 0.0182087 -0.0253734 0.0773435 0.0182087 -0.0254607 0.0782045 0.0180087 -0.0259424 0.0787258 0.0180087 -0.027025 0.0787258 0.0180087 -0.0282266 0.0782586 0.0182087 -0.0288758 0.0780481 0.0182087 -0.0291845 0.0760935 0.0182087 -0.0301258 0.077265 0.0180087 -0.0300584 0.0760935 0.0240087 -0.0251258 0.0773435 0.0240087 -0.0254607 0.0780481 0.0182087 -0.0260671 0.0782586 0.0182087 -0.0263758 0.0782586 0.0240087 -0.0263758 0.0785308 0.0182087 -0.0270695 0.0785935 0.0182087 -0.0276258 0.0785308 0.0182087 -0.0281821 0.0782586 0.0240087 -0.0288758 0.0773435 0.0182087 -0.0297908 0.0771782 0.0182087 -0.0298782 0.0773435 0.0240087 -0.0297908 0.0785935 0.0240087 -0.0276258 0.0788935 0.0243087 -0.0276258 0.0760935 0.0240087 -0.0301258 -0.0209472 0.0213087 0.0811941 -0.0194472 0.0241087 0.0807922 -0.0179472 0.0241087 0.0781941 -0.0183491 0.0241087 0.0766941 -0.0186017 0.0213087 0.0763237 -0.0186017 0.0241087 0.0763237 -0.0196455 0.0213087 0.0754912 -0.0218472 0.0213087 0.0766353 -0.0224472 0.0213087 0.0755961 -0.022506 0.0213087 0.0772941 -0.0227472 0.0213087 0.0781941 -0.0239472 0.0213087 0.0781941 -0.0201662 0.0213087 0.0798159 -0.0196455 0.0213087 0.080897 -0.0186017 0.0213087 0.0800646 -0.0180224 0.0213087 0.0788617 -0.0195399 0.0213087 0.0770719 -0.0180224 0.0213087 0.0775266 -0.0559344 0.0213087 0.0599456 -0.0572361 0.0241087 0.0602427 -0.0559344 0.0241087 0.0599456 -0.0548906 0.0213087 0.0591132 -0.0543113 0.0213087 0.0579103 -0.0543113 0.0241087 0.0565752 -0.0559344 0.0213087 0.0545398 -0.0766875 0.0213087 0.0235519 -0.0755894 0.0213087 0.0224538 -0.0755894 0.0241087 0.0224538 -0.0755894 0.0213087 0.0194538 -0.0766875 0.0213087 0.0183558 -0.0766875 0.0241087 0.0183558 -0.0751875 0.0213087 0.0209538 -0.0764326 0.0213087 0.0213544 -0.0781875 0.0213087 0.0239538 -0.0790875 0.0213087 0.0225127 -0.0811875 0.0213087 0.0209538 -0.0799875 0.0213087 0.0209538 -0.0797463 0.0213087 0.0200538 -0.0790875 0.0213087 0.019395 -0.0774065 0.0213087 0.0193321 -0.0209472 0.0180087 0.0764941 -0.0202747 0.0181587 0.0767976 -0.0197354 0.0181587 0.0772277 -0.0196181 0.0180087 0.0771342 -0.0194361 0.0181587 0.0778492 -0.0194361 0.0181587 0.078539 -0.0192898 0.0180087 0.0785724 -0.0202747 0.0181587 0.0795906 -0.0196181 0.0180087 0.0792541 -0.0209472 0.0181587 0.0797441 -0.0197354 0.0181587 0.0791605 -0.0194361 0.0210587 0.078539 -0.0194361 0.0210587 0.0778492 -0.0197354 0.0210587 0.0772277 -0.0209472 0.0181587 0.0766441 -0.0202747 0.0210587 0.0767976 -0.0202747 0.0210587 0.0795906 -0.0195399 0.0213087 0.0793164 -0.0197354 0.0210587 0.0791605 -0.0191923 0.0213087 0.0785947 -0.0191923 0.0213087 0.0777936 -0.0201662 0.0213087 0.0765724 -0.0209472 0.0213087 0.0763941 -0.0572361 0.0180087 0.0555427 -0.0565636 0.0181587 0.0558462 -0.0555787 0.0180087 0.0568644 -0.0557249 0.0181587 0.0575876 -0.0560242 0.0181587 0.0582091 -0.055907 0.0180087 0.0583027 -0.0565636 0.0181587 0.0586392 -0.0572361 0.0210587 0.0587927 -0.0565636 0.0210587 0.0586392 -0.0557249 0.0210587 0.0575876 -0.0557249 0.0181587 0.0568978 -0.0557249 0.0210587 0.0568978 -0.0560242 0.0181587 0.0562763 -0.0560242 0.0210587 0.0562763 -0.0572361 0.0181587 0.0556927 -0.0565636 0.0210587 0.0558462 -0.0572361 0.0210587 0.0556927 -0.0564551 0.0213087 0.0588645 -0.0560242 0.0210587 0.0582091 -0.0558288 0.0213087 0.058365 -0.0554812 0.0213087 0.0576433 -0.0554812 0.0213087 0.0568422 -0.0768451 0.0181587 0.0201788 -0.0767152 0.0180087 0.0218038 -0.0773375 0.0180087 0.0224261 -0.0781875 0.0181587 0.0225038 -0.077515 0.0210587 0.0223503 -0.0769756 0.0210587 0.0219203 -0.0774125 0.0181587 0.0222962 -0.0768451 0.0181587 0.0217288 -0.0766763 0.0210587 0.0212987 -0.0766375 0.0181587 0.0209538 -0.0766375 0.0210587 0.0209538 -0.0766763 0.0210587 0.0206089 -0.0774125 0.0181587 0.0196115 -0.0781875 0.0181587 0.0194038 -0.077515 0.0210587 0.0195573 -0.0781875 0.0210587 0.0194038 -0.0774125 0.0210587 0.0196115 -0.0769756 0.0210587 0.0199874 -0.0767802 0.0213087 0.0198316 -0.0768451 0.0210587 0.0201788 -0.0764326 0.0213087 0.0205533 -0.0767802 0.0213087 0.0220761 -0.0768451 0.0210587 0.0217288 -0.0774065 0.0213087 0.0225756 -0.0781875 0.0213087 0.0227538 -0.0774125 0.0210587 0.0222962 -0.0194472 0.0241087 0.0755961 -0.0181759 0.0243087 0.0765941 -0.0180224 0.0241087 0.0775266 -0.0180224 0.0241087 0.0788617 -0.0209472 0.0243087 0.0813941 -0.0193472 0.0243087 0.0809654 -0.0186017 0.0241087 0.0800646 -0.0183491 0.0241087 0.0796941 -0.0548906 0.0241087 0.0591132 -0.0558477 0.0243087 0.0601258 -0.0547342 0.0243087 0.0592379 -0.0541163 0.0243087 0.0579548 -0.0543113 0.0241087 0.0579103 -0.0541163 0.0243087 0.0565307 -0.0548906 0.0241087 0.0553723 -0.0559344 0.0241087 0.0545398 -0.0572361 0.0241087 0.0542427 -0.0766875 0.0241087 0.0235519 -0.0754162 0.0243087 0.0225538 -0.0751875 0.0241087 0.0209538 -0.0749875 0.0243087 0.0209538 -0.0755894 0.0241087 0.0194538 -0.0765875 0.0243087 0.0181826 -0.027624 0.0182087 0.0735918 -0.0265393 0.0182087 0.0738393 -0.0256694 0.0182087 0.074533 -0.0249917 0.0180087 0.0754909 -0.0265393 0.0182087 0.0783442 -0.0256694 0.0182087 0.0776505 -0.0251867 0.0182087 0.0766481 -0.0251867 0.0240087 0.0766481 -0.0251867 0.0182087 0.0755355 -0.0265393 0.0240087 0.0783442 -0.0256694 0.0240087 0.0776505 -0.0264091 0.0243087 0.0786145 -0.0254349 0.0243087 0.0778375 -0.0251867 0.0240087 0.0755355 -0.0256694 0.0240087 0.074533 -0.0265393 0.0240087 0.0738393 -0.0264091 0.0243087 0.073569 -0.027624 0.0240087 0.0735918 -0.0499119 0.0182087 0.0607238 -0.0499119 0.0182087 0.0632238 -0.050727 0.0180087 0.0643121 -0.050827 0.0182087 0.0641389 -0.050827 0.0240087 0.0641389 -0.0499119 0.0240087 0.0632238 -0.049577 0.0240087 0.0619738 -0.049577 0.0182087 0.0619738 -0.050827 0.0182087 0.0598088 -0.052077 0.0182087 0.0594738 -0.0499119 0.0240087 0.0607238 -0.050827 0.0240087 0.0598088 -0.052077 0.0243087 0.0591738 -0.0607172 0.0182087 0.0499185 -0.0619672 0.0180087 0.0493836 -0.0606172 0.0180087 0.0497453 -0.0598021 0.0182087 0.0508336 -0.0594672 0.0182087 0.0520836 -0.0598021 0.0182087 0.0533336 -0.0596289 0.0180087 0.0534336 -0.0619672 0.0180087 0.0547836 -0.0619672 0.0182087 0.0545836 -0.0619672 0.0240087 0.0545836 -0.0607172 0.0182087 0.0542487 -0.0598021 0.0240087 0.0533336 -0.0594672 0.0240087 0.0520836 -0.0598021 0.0240087 0.0508336 -0.0619672 0.0182087 0.0495836 -0.0607172 0.0240087 0.0499185 -0.0619672 0.0243087 0.0548836 -0.0605672 0.0243087 0.0545085 -0.0607172 0.0240087 0.0542487 -0.0595423 0.0243087 0.0534836 -0.0591672 0.0243087 0.0520836 -0.0605672 0.0243087 0.0496587 -0.0619672 0.0243087 0.0492836 -0.0748351 0.0182087 0.0254656 -0.0737468 0.0180087 0.0262807 -0.07392 0.0182087 0.0288807 -0.0748351 0.0182087 0.0297957 -0.0737468 0.0180087 0.0289807 -0.0748351 0.0240087 0.0297957 -0.07392 0.0240087 0.0288807 -0.0735851 0.0182087 0.0276307 -0.0735851 0.0240087 0.0276307 -0.07392 0.0182087 0.0263807 -0.0760851 0.0240087 0.0251307 -0.0746851 0.0243087 0.0300555 -0.0736602 0.0243087 0.0290307 -0.07392 0.0240087 0.0263807 -0.0732851 0.0243087 0.0276307 -0.0748351 0.0240087 0.0254656 -0.0746851 0.0243087 0.0252058 -0.0194472 0.0213087 -0.0755912 -0.0194472 0.0241087 -0.0755912 -0.0183491 0.0241087 -0.0766893 -0.0179472 0.0241087 -0.0781893 -0.0194472 0.0213087 -0.0807873 -0.0222488 0.0213087 -0.0754863 -0.0209472 0.0213087 -0.0763893 -0.0209472 0.0213087 -0.0751893 -0.0200472 0.0213087 -0.0766304 -0.0183491 0.0213087 -0.0766893 -0.0191472 0.0213087 -0.0781893 -0.0193883 0.0213087 -0.0790893 -0.0179472 0.0213087 -0.0781893 -0.0183491 0.0213087 -0.0796893 -0.0209472 0.0213087 -0.0811893 -0.0217282 0.0213087 -0.079811 -0.0222488 0.0213087 -0.0808922 -0.023872 0.0213087 -0.0775217 -0.0232927 0.0213087 -0.0763188 -0.0557361 0.0241087 -0.0546398 -0.054638 0.0241087 -0.0557379 -0.0542361 0.0213087 -0.0572379 -0.0542361 0.0241087 -0.0572379 -0.054638 0.0241087 -0.0587379 -0.0557361 0.0241087 -0.0598359 -0.0572361 0.0213087 -0.0602379 -0.0595816 0.0213087 -0.0591083 -0.058991 0.0213087 -0.0576384 -0.0601609 0.0213087 -0.0579054 -0.0580171 0.0213087 -0.0556161 -0.0572361 0.0213087 -0.0554379 -0.0556772 0.0213087 -0.0563379 -0.0557361 0.0213087 -0.0546398 -0.054638 0.0213087 -0.0557379 -0.0556772 0.0213087 -0.0581379 -0.054638 0.0213087 -0.0587379 -0.0557361 0.0213087 -0.0598359 -0.0563361 0.0213087 -0.0587967 -0.0572361 0.0213087 -0.0590379 -0.0585377 0.0213087 -0.0599408 -0.0781875 0.0213087 -0.017949 -0.0766875 0.0213087 -0.0183509 -0.0766875 0.0241087 -0.0183509 -0.0752627 0.0241087 -0.0202814 -0.0751875 0.0213087 -0.020949 -0.0752627 0.0241087 -0.0216165 -0.075842 0.0241087 -0.0228194 -0.0766875 0.0213087 -0.023547 -0.0781875 0.0213087 -0.023949 -0.0766875 0.0241087 -0.023547 -0.0755894 0.0213087 -0.019449 -0.0763875 0.0213087 -0.020949 -0.0766286 0.0213087 -0.021849 -0.0755894 0.0213087 -0.022449 -0.0807856 0.0213087 -0.022449 -0.0797463 0.0213087 -0.020049 -0.0790875 0.0213087 -0.0193901 -0.0796875 0.0213087 -0.0183509 -0.0781875 0.0213087 -0.019149 -0.0201722 0.0181587 -0.0768469 -0.0197354 0.0181587 -0.0772228 -0.0196049 0.0181587 -0.0774143 -0.0192898 0.0180087 -0.077811 -0.0192898 0.0180087 -0.0785675 -0.0194361 0.0181587 -0.0785342 -0.0196181 0.0180087 -0.0792492 -0.0196049 0.0181587 -0.0789643 -0.0209472 0.0180087 -0.0798893 -0.0202747 0.0181587 -0.0795858 -0.0202096 0.0180087 -0.0797209 -0.0201722 0.0181587 -0.0795316 -0.0197354 0.0181587 -0.0791557 -0.0202747 0.0181587 -0.0767928 -0.0194361 0.0181587 -0.0778443 -0.0193972 0.0181587 -0.0781893 -0.0196049 0.0210587 -0.0789643 -0.0201722 0.0210587 -0.0795316 -0.0201722 0.0210587 -0.0768469 -0.0196049 0.0210587 -0.0774143 -0.0193883 0.0213087 -0.0772893 -0.0193972 0.0210587 -0.0781893 -0.0209472 0.0210587 -0.0797393 -0.0200472 0.0213087 -0.0797481 -0.0563861 0.0180087 -0.0587101 -0.0558937 0.0181587 -0.0580129 -0.0555361 0.0180087 -0.0572379 -0.0557638 0.0180087 -0.0563879 -0.0564611 0.0181587 -0.0558955 -0.0572361 0.0181587 -0.0556879 -0.0563861 0.0180087 -0.0557656 -0.0558937 0.0181587 -0.0564629 -0.0556861 0.0181587 -0.0572379 -0.0556861 0.0210587 -0.0572379 -0.0558937 0.0210587 -0.0580129 -0.0564611 0.0181587 -0.0585802 -0.0572361 0.0181587 -0.0587879 -0.0564611 0.0210587 -0.0558955 -0.0563361 0.0213087 -0.055679 -0.0558937 0.0210587 -0.0564629 -0.0554361 0.0213087 -0.0572379 -0.0564611 0.0210587 -0.0585802 -0.0774125 0.0181587 -0.0222913 -0.0781875 0.0180087 -0.022649 -0.0773375 0.0180087 -0.0224212 -0.0768451 0.0181587 -0.021724 -0.0767152 0.0180087 -0.021799 -0.0766375 0.0181587 -0.020949 -0.0768451 0.0181587 -0.020174 -0.0774125 0.0181587 -0.0196066 -0.0781875 0.0181587 -0.019399 -0.0768451 0.0210587 -0.021724 -0.0781875 0.0210587 -0.019399 -0.0774125 0.0210587 -0.0196066 -0.0772875 0.0213087 -0.0193901 -0.0768451 0.0210587 -0.020174 -0.0766286 0.0213087 -0.020049 -0.0766375 0.0210587 -0.020949 -0.0774125 0.0210587 -0.0222913 -0.0772875 0.0213087 -0.0225078 -0.0781875 0.0213087 -0.022749 -0.0209472 0.0243087 -0.0749893 -0.0181759 0.0243087 -0.0765893 -0.0183491 0.0241087 -0.0796893 -0.0194472 0.0241087 -0.0807873 -0.0193472 0.0243087 -0.0809605 -0.0572361 0.0243087 -0.0540379 -0.0544648 0.0243087 -0.0556379 -0.0544648 0.0243087 -0.0588379 -0.0556361 0.0243087 -0.0600091 -0.0768858 0.0241087 -0.0236519 -0.0755894 0.0241087 -0.022449 -0.0750677 0.0243087 -0.021661 -0.0751875 0.0241087 -0.020949 -0.0750677 0.0243087 -0.0202369 -0.0755894 0.0241087 -0.019449 -0.0781875 0.0243087 -0.017749 -0.0768858 0.0241087 -0.0182461 -0.075842 0.0241087 -0.0190785 -0.026374 0.0182087 -0.0739218 -0.026274 0.0180087 -0.0737486 -0.025459 0.0182087 -0.0748369 -0.0252857 0.0180087 -0.0747369 -0.0251867 0.0182087 -0.0755306 -0.027624 0.0182087 -0.0785869 -0.027624 0.0180087 -0.0787869 -0.0256694 0.0182087 -0.0776456 -0.027624 0.0182087 -0.0735869 -0.0256694 0.0240087 -0.0745282 -0.0256694 0.0182087 -0.0745282 -0.025124 0.0182087 -0.0760869 -0.0251867 0.0182087 -0.0766432 -0.0251867 0.0240087 -0.0766432 -0.025459 0.0182087 -0.0773369 -0.0256694 0.0240087 -0.0776456 -0.0265393 0.0240087 -0.0783393 -0.026374 0.0182087 -0.0782519 -0.0265393 0.0240087 -0.0738344 -0.0264091 0.0243087 -0.0735642 -0.0251867 0.0240087 -0.0755306 -0.0264091 0.0243087 -0.0786096 -0.052077 0.0182087 -0.064469 -0.0509055 0.0180087 -0.0644016 -0.0501224 0.0182087 -0.0635277 -0.049966 0.0180087 -0.0636524 -0.0501224 0.0182087 -0.0604102 -0.0509922 0.0182087 -0.0597165 -0.0509055 0.0180087 -0.0595363 -0.0501224 0.0240087 -0.0604102 -0.0496396 0.0182087 -0.0614127 -0.0496396 0.0182087 -0.0625253 -0.0496396 0.0240087 -0.0625253 -0.0501224 0.0240087 -0.0635277 -0.0509922 0.0182087 -0.0642214 -0.0509922 0.0240087 -0.0642214 -0.0509922 0.0240087 -0.0597165 -0.052077 0.0243087 -0.059169 -0.0498878 0.0243087 -0.0602232 -0.0493472 0.0243087 -0.0613459 -0.0496396 0.0240087 -0.0614127 -0.052077 0.0243087 -0.064769 -0.0607172 0.0182087 -0.0542438 -0.0598021 0.0182087 -0.0533287 -0.0592672 0.0180087 -0.0520787 -0.0596289 0.0180087 -0.0507287 -0.0607172 0.0182087 -0.0499137 -0.0619672 0.0182087 -0.0495787 -0.0607172 0.0240087 -0.0499137 -0.0598021 0.0182087 -0.0508287 -0.0594672 0.0240087 -0.0520787 -0.0594672 0.0182087 -0.0520787 -0.0607172 0.0240087 -0.0542438 -0.0619672 0.0182087 -0.0545787 -0.0619672 0.0240087 -0.0495787 -0.0605672 0.0243087 -0.0496539 -0.0598021 0.0240087 -0.0508287 -0.0595423 0.0243087 -0.0506787 -0.0598021 0.0240087 -0.0533287 -0.0591672 0.0243087 -0.0520787 -0.0595423 0.0243087 -0.0534787 -0.0619672 0.0240087 -0.0545787 -0.0605672 0.0243087 -0.0545036 -0.0619672 0.0243087 -0.0548787 -0.0747351 0.0180087 -0.0252875 -0.0748351 0.0182087 -0.0254607 -0.0737468 0.0180087 -0.0262758 -0.0736478 0.0182087 -0.0270695 -0.0735851 0.0182087 -0.0276258 -0.0736478 0.0182087 -0.0281821 -0.0760851 0.0182087 -0.0301258 -0.0748351 0.0182087 -0.0297908 -0.0741305 0.0182087 -0.0291845 -0.0737468 0.0180087 -0.0289758 -0.07392 0.0182087 -0.0288758 -0.0750004 0.0240087 -0.0253734 -0.0741305 0.0182087 -0.0260671 -0.07392 0.0182087 -0.0263758 -0.0741305 0.0240087 -0.0260671 -0.0736478 0.0240087 -0.0270695 -0.0736478 0.0240087 -0.0281821 -0.0750004 0.0240087 -0.0298782 -0.0760851 0.0240087 -0.0251258 -0.0748702 0.0243087 -0.0251031 -0.073896 0.0243087 -0.02588 -0.0733553 0.0243087 -0.0282488 -0.0741305 0.0240087 -0.0291845 -0.073896 0.0243087 -0.0293716 -0.0760851 0.0240087 -0.0301258 -0.0139781 0.0237087 -0.083789 -0.0138793 0.0243087 -0.0831971 -0.040142 0.0243087 -0.0741812 -0.0404275 0.0237087 -0.0747089 -0.0273842 0.0243087 -0.0797772 -0.0517336 0.0243087 -0.0666168 -0.0591696 0.0243087 -0.060109 -0.0521732 0.0237087 -0.067035 -0.0727255 0.0243087 -0.0427211 -0.0711131 0.0237087 -0.0464608 -0.0708791 0.0243087 -0.0457193 -0.0817647 0.0243087 0.0207091 -0.0846556 0.0237087 -0.00701267 -0.0823463 0.0237087 -0.0208516 -0.0793539 0.0243087 0.0285894 -0.0727255 0.0243087 0.042726 -0.0601344 0.0243087 0.0591486 -0.0711131 0.0237087 0.0464657 -0.0521732 0.0237087 0.0670399 -0.0570565 0.0243087 0.0621233 -0.0591696 0.0243087 0.0601139 -0.0458561 0.0243087 0.0707962 -0.0404275 0.0237087 0.0747137 -0.027579 0.0237087 0.0803496 -0.0114769 0.0298087 -0.0577168 -0.0114378 0.0300087 -0.0575206 -0.0225167 0.0298087 -0.0543679 -0.03258 0.0300087 -0.0487633 -0.041609 0.0298087 -0.0416108 -0.0414676 0.0300087 -0.0414694 -0.0487615 0.0300087 -0.0325818 -0.0541813 0.0300087 -0.0224419 -0.057715 0.0298087 -0.0114786 -0.0588458 0.0298087 2.44063e-06 -0.0543661 0.0298087 0.0225234 -0.0489278 0.0298087 0.0326977 -0.041609 0.0298087 0.0416157 -0.03258 0.0300087 0.0487681 -0.0224402 0.0300087 0.054188 -0.0693846 0.0243087 0.041964 -0.0686716 0.0195087 0.0413024 -0.0684919 0.0195087 0.0401103 -0.0688105 0.0195087 0.0394487 -0.0693846 0.0243087 0.0389908 -0.0692755 0.0195087 0.0390485 -0.0701005 0.0243087 0.0388274 -0.0397549 0.0195087 0.0715938 -0.0397549 0.0243087 0.0715938 -0.0388622 0.0195087 0.0704744 -0.0391808 0.0243087 0.071136 -0.0388622 0.0243087 0.0704744 -0.0388622 0.0195087 0.06974 -0.0388622 0.0243087 0.06974 -0.0397549 0.0195087 0.0686206 -0.0397549 0.0243087 0.0686206 -0.0404708 0.0195087 -0.0684523 -0.0397549 0.0243087 -0.0686157 -0.0388622 0.0195087 -0.0704695 -0.0390418 0.0195087 -0.0709273 -0.0391808 0.0195087 -0.0711311 -0.0391808 0.0243087 -0.0711311 -0.0397549 0.0243087 -0.0715889 -0.0396458 0.0195087 -0.0715313 -0.0701005 0.0195087 -0.0388226 -0.0701005 0.0243087 -0.0388226 -0.0684919 0.0195087 -0.0401054 -0.0684505 0.0195087 -0.0404726 -0.0688105 0.0243087 -0.0415013 -0.0686716 0.0195087 -0.0412976 -0.0693846 0.0243087 -0.0419592 -0.0809458 0.0195087 0.00165244 -0.0809458 0.0243087 0.00165244 -0.0801208 0.0243087 0.00143138 -0.0801208 0.0195087 0.00143138 -0.0795169 0.0195087 0.000827441 -0.0792958 0.0195087 2.44063e-06 -0.0792958 0.0243087 2.44063e-06 -0.0801208 0.0195087 -0.0014265 -0.0795169 0.0243087 -0.000822559 0.070109 0.0195087 -0.0388226 0.070934 0.0195087 -0.0390436 0.070934 0.0243087 -0.0390436 0.071759 0.0195087 -0.0404726 0.071759 0.0243087 -0.0404726 0.0715379 0.0243087 -0.0412976 0.0413042 0.0195087 -0.0686734 0.0413042 0.0243087 -0.0686734 0.0419082 0.0195087 -0.0692773 0.0421292 0.0195087 -0.0701023 0.0404792 0.0195087 -0.0717523 0.0413042 0.0243087 -0.0715313 0.0404792 0.0195087 0.0717572 0.0421292 0.0195087 0.0701072 0.0419082 0.0195087 0.0692822 0.0413042 0.0195087 0.0686783 0.0404792 0.0243087 0.0684572 0.070109 0.0195087 0.0421274 0.070934 0.0195087 0.0419064 0.070109 0.0243087 0.0421274 0.070934 0.0243087 0.0419064 0.0715379 0.0195087 0.0396524 0.071759 0.0243087 0.0404774 0.070934 0.0243087 0.0390485 0.0823831 0.0195087 0.000827441 0.0823831 0.0243087 0.000827441 0.0826042 0.0195087 2.44063e-06 0.0823831 0.0243087 -0.000822559 0.0823831 0.0195087 -0.000822559 0.0817792 0.0243087 -0.0014265 0.0817792 0.0195087 -0.0014265 0.0809542 0.0195087 -0.00164756 -0.0139781 0.0182087 0.0837938 -0.0139452 0.0180087 0.0835966 -0.0275141 0.0180087 0.0801605 -0.0711131 0.0182087 0.0464657 -0.0776076 0.0180087 0.0340461 -0.0823463 0.0182087 0.0208564 -0.0844563 0.0180087 0.00700104 -0.0711131 0.0182087 -0.0464608 -0.0776076 0.0180087 -0.0340412 -0.0624955 0.0182087 -0.0575326 -0.0521732 0.0182087 -0.067035 -0.0275141 0.0180087 -0.0801556 -0.0139781 0.0182087 -0.083789 4.20971e-06 0.0180087 -0.0847476 0.0819508 0.0192087 -0.000572917 0.0798323 0.0192087 0.000258499 0.0804549 0.0192087 -0.00103432 0.0815296 0.0192087 0.00099899 0.0706843 0.0192087 0.041474 0.0695336 0.0192087 0.0394809 0.0711055 0.0192087 0.0410528 0.0712597 0.0192087 0.0404774 0.0711055 0.0192087 0.0399021 0.0689583 0.0192087 0.0404774 0.0691124 0.0192087 0.0410528 0.070109 0.0192087 0.0393267 0.0695336 0.0192087 0.041474 0.0399039 0.0192087 0.0691106 0.0416299 0.0192087 0.0701072 0.0414758 0.0192087 0.0695318 0.0410546 0.0192087 0.0691106 0.0393285 0.0192087 0.0701072 0.0394827 0.0192087 -0.069527 0.0414758 0.0192087 -0.069527 0.0410546 0.0192087 -0.0710989 0.0394827 0.0192087 -0.0706777 0.0393285 0.0192087 -0.0701023 0.0399039 0.0192087 -0.0691058 0.070109 0.0192087 -0.0416233 0.0695336 0.0192087 -0.039476 0.0706843 0.0192087 -0.039476 -0.0799492 0.0192087 0.000577799 -0.0820965 0.0192087 2.44063e-06 -0.0815211 0.0192087 -0.000994109 -0.0710971 0.0192087 -0.0398972 -0.0706759 0.0192087 -0.039476 -0.0712513 0.0192087 -0.0404726 -0.0695252 0.0192087 -0.0414691 -0.069104 0.0192087 -0.0410479 -0.0398954 0.0192087 -0.0691058 -0.0404708 0.0192087 -0.071253 -0.0394742 0.0192087 -0.0706777 -0.0393201 0.0192087 -0.0701023 -0.0410462 0.0192087 0.0711037 -0.0404708 0.0192087 0.0689565 -0.0410462 0.0192087 0.0691106 -0.0395711 0.0192087 0.0708247 -0.0399715 0.0192087 0.071144 -0.0416215 0.0192087 0.0701072 -0.0393489 0.0192087 0.0698511 -0.0695252 0.0192087 0.041474 -0.069104 0.0192087 0.0410528 -0.0701005 0.0192087 0.0393267 -0.0701005 0.0192087 0.0416282 -0.0710971 0.0192087 0.0410528 -0.0712513 0.0192087 0.0404774 -0.0710971 0.0192087 0.0399021 -0.0706759 0.0192087 0.0394809 -0.0404275 -0.00269131 0.0747137 -0.0521732 -0.00379131 0.0670399 -0.0624955 -0.00379131 0.0575375 -0.0777907 -0.00269131 0.0341265 -0.0823463 -0.00269131 0.0208564 -0.0846556 -0.00379131 0.00701756 -0.0846556 -0.00269131 -0.00701267 -0.0846556 -0.00379131 -0.00701267 -0.0823463 -0.00269131 -0.0208516 -0.0624955 -0.00269131 -0.0575326 -0.0521732 -0.00269131 -0.067035 -0.0404275 -0.00269131 -0.0747089 -0.027579 -0.00269131 -0.0803447 -0.027579 -0.00379131 -0.0803447 -0.0139781 -0.00269131 -0.083789 -0.0139781 -0.00379131 -0.083789 -0.027579 -0.00779131 0.0803496 -0.0404275 -0.00519131 0.0747137 -0.0521732 -0.00779131 0.0670399 -0.0624955 -0.00519131 0.0575375 -0.0624955 -0.00779131 0.0575375 -0.0711131 -0.00519131 0.0464657 -0.0711131 -0.00779131 0.0464657 -0.0777907 -0.00779131 0.0341265 -0.0823463 -0.00519131 0.0208564 -0.0823463 -0.00779131 0.0208564 -0.0846556 -0.00519131 0.00701756 -0.0846556 -0.00779131 0.00701756 -0.0846556 -0.00519131 -0.00701267 -0.0823463 -0.00519131 -0.0208516 -0.0777907 -0.00519131 -0.0341216 -0.0777907 -0.00779131 -0.0341216 -0.0711131 -0.00519131 -0.0464608 -0.0624955 -0.00779131 -0.0575326 -0.0521732 -0.00519131 -0.067035 -0.0404275 -0.00519131 -0.0747089 -0.0404275 -0.00779131 -0.0747089 -0.027579 -0.00519131 -0.0803447 -0.027579 -0.00779131 -0.0803447 -0.0139781 -0.00519131 -0.083789 4.20971e-06 -0.00129131 0.0849524 -0.0139781 -0.000191313 0.0837938 -0.0139781 -0.00129131 0.0837938 -0.027579 -0.000191313 0.0803496 -0.0404275 -0.000191313 0.0747137 -0.0404275 -0.00129131 0.0747137 -0.0521732 -0.00129131 0.0670399 -0.0711131 -0.00129131 0.0464657 -0.0777907 -0.000191313 0.0341265 -0.0823463 -0.00129131 0.0208564 -0.0823463 -0.000191313 -0.0208516 -0.0711131 -0.000191313 -0.0464608 -0.0711131 -0.00129131 -0.0464608 -0.0624955 -0.000191313 -0.0575326 -0.0404275 -0.000191313 -0.0747089 -0.0404275 -0.00129131 -0.0747089 -0.027579 -0.00129131 -0.0803447 -0.027579 -0.000191313 -0.0803447 4.20971e-06 0.00120869 0.0849524 -0.0139781 0.00120869 0.0837938 -0.027579 0.00120869 0.0803496 -0.0404275 0.00120869 0.0747137 -0.0404275 0.00230869 0.0747137 -0.0521732 0.00230869 0.0670399 -0.0624955 0.00230869 0.0575375 -0.0823463 0.00120869 0.0208564 -0.0846556 0.00230869 0.00701756 -0.0846556 0.00230869 -0.00701267 -0.0846556 0.00120869 -0.00701267 -0.0823463 0.00230869 -0.0208516 -0.0823463 0.00120869 -0.0208516 -0.0777907 0.00230869 -0.0341216 -0.0777907 0.00120869 -0.0341216 -0.0624955 0.00230869 -0.0575326 -0.0521732 0.00230869 -0.067035 -0.0404275 0.00230869 -0.0747089 -0.0404275 0.00120869 -0.0747089 -0.0139781 0.00230869 -0.083789 4.20971e-06 0.00230869 -0.0849476 -0.0139781 0.00480869 0.0837938 -0.027579 0.00370869 0.0803496 -0.0521732 0.00480869 0.0670399 -0.0521732 0.00370869 0.0670399 -0.0846556 0.00370869 0.00701756 -0.0846556 0.00480869 0.00701756 -0.0846556 0.00370869 -0.00701267 -0.0777907 0.00480869 -0.0341216 -0.0777907 0.00370869 -0.0341216 -0.0624955 0.00480869 -0.0575326 -0.0624955 0.00370869 -0.0575326 -0.0521732 0.00480869 -0.067035 -0.0404275 0.00480869 -0.0747089 -0.0404275 0.00370869 -0.0747089 -0.027579 0.00370869 -0.0803447 -0.027579 0.00480869 -0.0803447 -0.0139781 0.00370869 -0.083789 4.20971e-06 0.00620869 0.0849524 -0.0139781 0.00730869 0.0837938 -0.0624955 0.00620869 0.0575375 -0.0777907 0.00620869 0.0341265 -0.0846556 0.00730869 0.00701756 -0.0846556 0.00730869 -0.00701267 -0.0846556 0.00620869 0.00701756 -0.0846556 0.00620869 -0.00701267 -0.0823463 0.00620869 -0.0208516 -0.0777907 0.00730869 -0.0341216 -0.0711131 0.00620869 -0.0464608 -0.0521732 0.00620869 -0.067035 -0.0404275 0.00620869 -0.0747089 -0.0404275 0.00730869 -0.0747089 -0.027579 0.00620869 -0.0803447 -0.0139781 0.00980869 0.0837938 -0.0404275 0.00870869 0.0747137 -0.0404275 0.00980869 0.0747137 -0.0624955 0.00980869 0.0575375 -0.0777907 0.00980869 0.0341265 -0.0846556 0.00980869 -0.00701267 -0.0846556 0.00870869 -0.00701267 -0.0711131 0.00870869 -0.0464608 -0.0624955 0.00980869 -0.0575326 -0.0521732 0.00870869 -0.067035 -0.0404275 0.00870869 -0.0747089 -0.0139781 0.00870869 -0.083789 4.20971e-06 0.0123087 0.0849524 -0.0139781 0.0123087 0.0837938 4.20971e-06 0.0112087 0.0849524 -0.0521732 0.0112087 0.0670399 -0.0521732 0.0123087 0.0670399 -0.0624955 0.0112087 0.0575375 -0.0711131 0.0112087 0.0464657 -0.0823463 0.0123087 0.0208564 -0.0846556 0.0123087 0.00701756 -0.0823463 0.0112087 0.0208564 -0.0846556 0.0112087 0.00701756 -0.0846556 0.0112087 -0.00701267 -0.0846556 0.0123087 -0.00701267 -0.0777907 0.0123087 -0.0341216 -0.0711131 0.0123087 -0.0464608 -0.0624955 0.0123087 -0.0575326 -0.0404275 0.0123087 -0.0747089 -0.0404275 0.0112087 -0.0747089 -0.0139781 0.0148087 0.0837938 -0.027579 0.0148087 0.0803496 -0.0404275 0.0137087 0.0747137 -0.0521732 0.0137087 0.0670399 -0.0624955 0.0148087 0.0575375 -0.0624955 0.0137087 0.0575375 -0.0777907 0.0148087 0.0341265 -0.0823463 0.0137087 0.0208564 -0.0846556 0.0148087 0.00701756 -0.0823463 0.0137087 -0.0208516 -0.0711131 0.0148087 -0.0464608 -0.0624955 0.0148087 -0.0575326 -0.0521732 0.0148087 -0.067035 -0.0404275 0.0148087 -0.0747089 -0.027579 0.0148087 -0.0803447 -0.0139781 0.0137087 -0.083789 -0.0404275 0.0162087 0.0747137 -0.0624955 0.0178087 0.0575375 -0.0711131 0.0178087 0.0464657 -0.0624955 0.0162087 0.0575375 -0.0711131 0.0162087 0.0464657 -0.0823463 0.0178087 0.0208564 -0.0846556 0.0162087 -0.00701267 -0.0823463 0.0178087 -0.0208516 -0.0777907 0.0162087 -0.0341216 -0.0711131 0.0162087 -0.0464608 -0.0711131 0.0178087 -0.0464608 -0.0139781 0.0178087 -0.083789 4.20971e-06 0.0178087 -0.0849476 4.20971e-06 0.0162087 -0.0849476 0.0516564 -0.0197913 0.0157521 0.0479497 -0.0197913 0.0248466 0.0426571 -0.00829131 0.0331193 0.0426571 -0.0197913 0.0331193 0.0359538 -0.0197913 0.0402967 0.0280614 -0.00829131 0.0461413 0.019241 -0.00829131 0.0504598 0.019241 -0.0197913 0.0504598 0.00978437 -0.00829131 0.0531094 0.00978437 -0.0197913 0.0531094 4.20971e-06 -0.00829131 0.0540024 -0.051648 -0.00829131 -0.0157473 -0.0475885 -0.00829131 -0.0255109 -0.0475885 -0.0197913 -0.0255109 -0.0342207 -0.00829131 -0.0417666 -0.015654 -0.00829131 -0.0516775 0.00529119 -0.00829131 -0.0537381 -0.00528277 -0.0197913 -0.0537381 0.0156624 -0.0197913 -0.0516775 0.0254333 -0.0197913 -0.0476354 0.0254333 -0.00829131 -0.0476354 0.0342291 -0.0197913 -0.0417666 0.0516564 -0.00829131 -0.0157473 -0.0504958 -0.0212913 -0.013414 0.0505042 -0.0212913 -0.013414 0.0502216 -0.0212913 -0.0153098 -0.0502132 -0.0212913 -0.0153098 0.0332784 -0.0212913 -0.0406064 0.0502216 -0.0212913 0.0153146 -0.0186983 -0.0212913 0.0490582 -0.0152191 -0.0212913 -0.050242 0.0349552 -0.0212913 0.0391774 -0.0409958 -0.0176913 -0.00469756 -0.0409958 -0.0176913 0.00470244 -0.0409958 -0.00939131 -0.00469756 0.0420042 -0.0136413 0.00875244 0.0503557 -0.00939131 -0.00469756 0.0420042 -0.0136413 -0.00874756 0.0420042 -0.0134413 -0.00874756 -0.0390418 -0.00829131 0.0709322 -0.0346224 -0.00829131 0.0725245 -0.0519009 -0.00829131 -0.0666133 0.024294 -0.00829131 -0.0799381 0.040198 -0.00829131 0.074274 -0.0456989 -0.00829131 -0.0346242 0.0346308 -0.00829131 0.0542226 -0.053477 -0.00829131 0.059549 -0.0597781 -0.00829131 -0.0538245 0.0773413 -0.00829131 -0.0339207 0.0760935 -0.00829131 -0.0248258 0.0754661 -0.00829131 -0.0203259 0.0760068 -0.00829131 -0.0192032 0.0795959 -0.00829131 -0.0233738 0.076981 -0.00829131 -0.0234717 0.0806208 -0.00829131 -0.019549 0.079358 -0.00829131 -0.02889 0.0788935 -0.00829131 -0.0276258 0.0785184 -0.00829131 -0.0262258 0.0599743 -0.00829131 -0.0566148 0.0548196 -0.00829131 -0.0558379 0.0496605 -0.00829131 -0.063369 0.0572258 -0.00829131 -0.0621062 0.0548152 -0.00829131 -0.062592 0.0457073 -0.00829131 -0.0570238 0.0520854 -0.00829131 -0.059169 0.0548152 -0.00829131 -0.0613459 0.0622824 -0.00829131 -0.0570346 0.0621361 -0.00829131 -0.057194 0.0594336 -0.00829131 -0.0589836 0.0746935 -0.00829131 -0.0300507 0.0743447 -0.00829131 -0.00989826 0.0584594 -0.00829131 -0.0547151 0.0624383 -0.00829131 -0.056864 0.0619756 -0.00829131 -0.0548787 0.0605756 -0.00829131 -0.0496539 0.0631905 -0.00829131 -0.049556 0.071005 -0.00829131 -0.0457216 0.0647054 -0.00829131 -0.0527018 0.0754661 -0.00829131 0.0215769 0.076981 -0.00829131 0.0234766 0.0808634 -0.00829131 0.0243661 0.0818701 -0.00829131 0.0207337 0.0838681 -0.00829131 0.00993497 0.0599743 -0.00829131 0.0578658 0.0594336 -0.00829131 0.0589885 0.0621361 -0.00829131 0.0571989 0.0572258 -0.00829131 0.0621111 0.0518745 -0.00829131 0.0666454 0.0548854 -0.00829131 0.0619738 0.0558445 -0.00829131 0.0596676 0.0544445 -0.00829131 0.0572427 0.0508705 -0.00829131 0.0594511 0.0493556 -0.00829131 0.0613508 0.0493556 -0.00829131 0.0625969 0.0457073 -0.00829131 0.0666155 0.0572445 -0.00829131 0.0544427 0.0594336 -0.00829131 0.055497 0.0605756 -0.00829131 0.0545085 0.0760935 -0.00829131 0.0304307 0.0743447 -0.00829131 0.0346291 0.0785184 -0.00829131 0.0290307 0.0790989 -0.00829131 0.0242923 0.0748786 -0.00829131 0.025108 0.0743447 -0.00829131 0.0242923 0.0739044 -0.00829131 0.0258849 0.0733637 -0.00829131 0.0282537 0.0624101 -0.00829131 0.0346291 0.0595507 -0.00829131 0.0534836 0.069284 -0.00829131 0.0390485 0.070109 -0.00829131 0.0388274 0.0708249 -0.00829131 0.0389908 0.068459 -0.00829131 0.0404774 0.0717176 -0.00829131 0.0408446 0.0647054 -0.00829131 0.0527067 0.0641647 -0.00829131 0.0503378 0.0707029 -0.00829131 0.0461922 0.0708249 -0.00829131 0.041964 0.0619756 -0.00829131 0.0548836 0.0624383 -0.00829131 0.0568689 0.0641647 -0.00829131 0.0538294 -0.0271605 -0.00829131 -0.0799593 -0.0223472 -0.00829131 -0.0806141 -0.0347364 -0.00829131 -0.0769709 -0.0346224 -0.00829131 -0.0725196 -0.0300489 -0.00829131 -0.0774869 -0.030424 -0.00829131 -0.0760869 -0.0248942 -0.00829131 -0.0754638 -0.0264091 -0.00829131 -0.0786096 -0.0209472 -0.00829131 -0.0753893 -0.0195472 -0.00829131 -0.0757644 -0.0181472 -0.00829131 -0.0781893 -0.0185223 -0.00829131 -0.0795893 -0.0300489 -0.00829131 -0.0746869 -0.027624 -0.00829131 -0.0732869 -0.0264091 -0.00829131 -0.0735642 -0.0223472 -0.00829131 -0.0757644 -0.0248942 -0.00829131 -0.0767099 -0.0237472 -0.00829131 -0.0781893 0.0274251 -0.00829131 0.0798767 0.0254433 -0.00829131 0.0778375 0.0346308 -0.00829131 0.0743429 4.20971e-06 -0.00829131 0.0743429 -0.0347364 -0.00829131 0.0769758 -0.0288389 -0.00829131 0.0786145 -0.0138958 -0.00829131 0.0833007 -0.0274167 -0.00829131 0.0798767 -0.026224 -0.00829131 0.0785166 -0.0251991 -0.00829131 0.0746918 -0.023677 -0.00829131 0.0788172 -0.0288389 -0.00829131 0.073569 -0.0346224 -0.00829131 0.0743429 0.0209556 -0.00829131 -0.0753893 0.024294 -0.00829131 -0.0725196 0.0236854 -0.00829131 -0.0775662 -0.0138958 -0.00829131 -0.0832958 4.20971e-06 -0.00829131 -0.0844476 0.0236854 -0.00829131 -0.0788123 4.20971e-06 -0.00829131 -0.0799381 0.0185307 -0.00829131 -0.0767893 0.0221705 -0.00829131 -0.080712 0.0209556 -0.00829131 -0.0809893 0.0185307 -0.00829131 -0.0795893 -0.0767875 -0.00829131 -0.0185241 -0.0795875 -0.00829131 -0.0185241 -0.0790904 -0.00829131 -0.00989826 -0.0746851 -0.00829131 -0.0252009 -0.0736602 -0.00829131 -0.0262258 -0.0760851 -0.00829131 -0.0304258 -0.0773 -0.00829131 -0.0301485 -0.0782742 -0.00829131 -0.0293716 -0.0809875 -0.00829131 -0.020949 -0.0818616 -0.00829131 -0.0207288 -0.0788149 -0.00829131 -0.0270027 -0.0782742 -0.00829131 -0.02588 -0.0767875 -0.00829131 -0.0233738 -0.0773 -0.00829131 -0.0251031 -0.0757626 -0.00829131 -0.022349 -0.0759984 -0.00829131 0.0226996 -0.0754577 -0.00829131 0.0215769 -0.080855 -0.00829131 0.0243661 -0.0806124 -0.00829131 0.0223538 -0.0795875 -0.00829131 0.0233787 -0.0621277 -0.00829131 0.0571989 -0.0599659 -0.00829131 0.0578658 -0.0594252 -0.00829131 0.0589885 -0.062274 -0.00829131 0.0570395 -0.0619672 -0.00829131 0.0548836 -0.0594252 -0.00829131 0.055497 -0.0572361 -0.00829131 0.0544427 -0.0558361 -0.00829131 0.0548179 -0.0532159 -0.00829131 0.0570287 -0.0548112 -0.00829131 0.0586427 -0.054877 -0.00829131 0.0619738 -0.0817916 -0.00829131 -0.00989826 -0.0817916 -0.00829131 0.00990314 -0.0801208 -0.00829131 0.00143138 -0.0795169 -0.00829131 0.000827441 -0.0801208 -0.00829131 -0.0014265 -0.0817708 -0.00829131 -0.0014265 -0.0841573 -0.00829131 -0.00697138 -0.0823747 -0.00829131 -0.000822559 -0.0643921 -0.00829131 0.0506836 -0.0647672 -0.00829131 0.0520836 -0.0643921 -0.00829131 0.0534836 -0.0633672 -0.00829131 0.0545085 -0.0592374 -0.00829131 0.0527067 -0.0607523 -0.00829131 0.0495609 -0.0619672 -0.00829131 -0.0492787 -0.0570221 -0.00829131 -0.0457006 -0.0643921 -0.00829131 -0.0506787 -0.066836 -0.00829131 -0.0516133 -0.0646239 -0.00829131 -0.0543576 -0.0633672 -0.00829131 -0.0545036 -0.062274 -0.00829131 -0.0570346 -0.0548068 -0.00829131 -0.0613459 -0.0572361 -0.00829131 -0.0600379 -0.0572174 -0.00829131 -0.0621062 -0.0619672 -0.00829131 -0.0548787 -0.059661 -0.00829131 -0.0558379 -0.0570221 -0.00829131 -0.0542177 -0.0586361 -0.00829131 -0.054813 -0.0572361 -0.00829131 -0.0544379 -0.0532159 -0.00829131 -0.0542177 -0.0558361 -0.00829131 -0.054813 -0.0548112 -0.00829131 -0.0558379 -0.0572361 -0.00829131 0.0600427 -0.0533053 -0.00829131 0.0654998 -0.052077 -0.00829131 0.0647738 -0.050677 -0.00829131 0.0643987 -0.0496521 -0.00829131 0.0633738 -0.052077 -0.00829131 0.0591738 -0.050677 -0.00829131 0.059549 0.0359538 -0.00829131 0.0402967 0.0457073 -0.00829131 0.0542226 0.024294 -0.00829131 0.0542226 -0.0192326 -0.00829131 0.0504598 -0.0346224 -0.00829131 0.0542226 4.20971e-06 -0.00829131 0.0542226 -0.0456989 -0.00829131 0.0346291 -0.051648 -0.00829131 0.0157521 -0.0532159 -0.00829131 0.00990314 -0.0346224 -0.00829131 -0.0457006 -0.00528277 -0.00829131 -0.0537381 0.0520042 -0.00829131 -0.013414 0.0457073 -0.00829131 -0.0346242 0.0475969 -0.00829131 -0.0255109 -0.0456989 -0.00829131 -0.0570238 -0.050677 -0.00829131 -0.0595441 -0.0496521 -0.00829131 -0.060569 -0.052077 -0.00829131 -0.059169 -0.050677 -0.00829131 -0.0643938 -0.052077 -0.00829131 -0.064769 -0.0532918 -0.00829131 -0.0644917 -0.0181472 -0.00829131 0.0781941 0.0209556 -0.00829131 0.0753941 0.0231447 -0.00829131 0.0764484 0.0181556 -0.00829131 0.0781941 0.0209556 -0.00829131 0.0809941 0.0243444 -0.00829131 0.0808687 0.0221705 -0.00829131 0.0807168 0.0421292 -0.00829131 0.0701072 0.0419082 -0.00829131 0.0692822 0.0419082 -0.00829131 0.0709322 0.0391892 -0.00829131 0.0690784 0.0391892 -0.00829131 0.071136 0.0770155 -0.00829131 0.0346588 0.0725262 -0.00829131 0.0346291 0.071399 -0.00829131 0.0394487 0.0841658 -0.00829131 0.00697627 0.0841658 -0.00829131 -0.00697138 0.0826042 -0.00829131 2.44063e-06 0.0817792 -0.00829131 -0.0014265 0.0790989 -0.00829131 -0.00989826 0.0838681 -0.00829131 -0.00993008 0.0795959 -0.00829131 -0.0185241 0.0801292 -0.00829131 -0.0014265 0.0743447 -0.00829131 -0.0346242 0.074596 -0.00829131 -0.0395939 0.068459 -0.00829131 -0.0404726 0.0624101 -0.00829131 -0.0346242 0.0725262 -0.00829131 -0.0346242 0.069284 -0.00829131 -0.0390436 0.0708249 -0.00829131 -0.038986 0.070109 -0.00829131 -0.0421226 0.0624101 -0.00829131 -0.0457006 0.069284 -0.00829131 -0.0419015 0.0717176 -0.00829131 -0.0401054 0.0717176 -0.00829131 -0.0408397 0.071399 -0.00829131 -0.0415013 0.0390503 -0.00829131 -0.0709273 0.0390503 -0.00829131 -0.0692773 0.0346308 -0.00829131 -0.0666106 0.0533003 -0.00829131 -0.0644917 0.0519093 -0.00829131 -0.0666133 0.0457073 -0.00829131 -0.0666106 0.0417692 -0.00829131 -0.0690736 0.0518745 -0.00829131 -0.0666405 0.0417692 -0.00829131 -0.0711311 0.0411951 -0.00829131 -0.0715889 0.0248324 -0.00829131 -0.0760869 0.040198 -0.00829131 -0.0742691 0.0288473 -0.00829131 -0.0786096 0.0274251 -0.00829131 -0.0798718 0.0262324 -0.00829131 -0.0785117 0.0271689 -0.00829131 -0.0799593 0.0429874 -0.00829131 -0.0726904 0.0346308 -0.00829131 -0.0725196 0.0252076 -0.00829131 -0.0746869 0.0276324 -0.00829131 -0.0732869 -0.0390418 -0.00829131 -0.0709273 -0.0401895 -0.00829131 -0.0742691 -0.0346224 -0.00829131 -0.0666106 -0.0404708 -0.00829131 -0.0684523 -0.0411867 -0.00829131 -0.0686157 -0.0417608 -0.00829131 -0.0690736 -0.0666089 -0.00829131 -0.0457006 -0.0717505 -0.00829131 -0.0404726 -0.0692755 -0.00829131 -0.0419015 -0.0709966 -0.00829131 -0.0457216 -0.0770071 -0.00829131 -0.0346539 -0.0709255 -0.00829131 -0.0419015 -0.0727201 -0.00829131 -0.0429276 -0.0715295 -0.00829131 -0.0396476 -0.0725178 -0.00829131 -0.0346242 -0.0701005 -0.00829131 -0.0388226 -0.0692755 -0.00829131 -0.0390436 -0.0666089 -0.00829131 -0.0346242 -0.0823747 -0.00829131 0.000827441 -0.0841573 -0.00829131 0.00697627 -0.0818616 -0.00829131 0.0207337 -0.0736602 -0.00829131 0.0262307 -0.0760851 -0.00829131 0.0248307 -0.0736602 -0.00829131 0.0290307 -0.0732851 -0.00829131 0.0276307 -0.0790904 -0.00829131 0.0242923 -0.0746851 -0.00829131 0.0252058 -0.07851 -0.00829131 0.0262307 -0.0788851 -0.00829131 0.0276307 -0.0793496 -0.00829131 0.0288949 -0.0774851 -0.00829131 0.0300555 -0.0760851 -0.00829131 0.0304307 -0.0666089 -0.00829131 0.0346291 -0.066836 -0.00829131 0.0516182 -0.0684505 -0.00829131 0.0404774 -0.0701005 -0.00829131 0.0388274 -0.0709255 -0.00829131 0.0390485 -0.0725178 -0.00829131 0.0346291 -0.0717505 -0.00829131 0.0404774 -0.0770071 -0.00829131 0.0346588 -0.0727201 -0.00829131 0.0429324 -0.0401895 -0.00829131 0.074274 -0.053477 -0.00829131 0.0643987 -0.0518661 -0.00829131 0.0666454 -0.0418997 -0.00829131 0.0692822 -0.0303538 -0.00829131 0.0754687 -0.0396458 -0.00829131 0.0715361 -0.0404708 -0.00829131 0.0684572 -0.0456989 -0.00829131 0.0666155 -0.0412958 -0.00829131 0.0686783 -0.0532159 -0.00829131 0.0346291 -0.0570221 -0.00829131 0.0242923 -0.0532159 -0.00829131 0.0242923 -0.0666089 -0.00829131 0.0242923 -0.0725178 -0.00829131 0.0242923 -0.0725178 -0.00829131 0.00990314 -0.0519958 -0.00829131 -0.00989826 -0.0570221 -0.00829131 0.00990314 -0.0666089 -0.00829131 0.00990314 -0.0666089 -0.00829131 -0.00989826 -0.0790904 -0.00829131 0.00990314 -0.0532159 -0.00829131 -0.00989826 -0.0570221 -0.00829131 -0.00989826 -0.0570221 -0.00829131 -0.0346242 -0.0725178 -0.00829131 -0.00989826 -0.0456989 -0.00829131 0.0542226 -0.0570221 -0.00829131 0.0346291 -0.0570221 -0.00829131 0.0542226 -0.0417042 -0.00829131 -0.0342964 -0.0532159 -0.00829131 -0.0346242 -0.0686716 -0.00829131 -0.0412976 -0.0254249 -0.00829131 -0.0476354 -0.0346224 -0.00829131 -0.0542177 -0.0456989 -0.00829131 -0.0457006 -0.0532159 -0.00829131 -0.0457006 0.0264176 -0.00829131 0.073569 0.024294 -0.00829131 0.0743429 0.024294 -0.00829131 0.0725245 4.20971e-06 -0.00829131 0.0725245 -0.026224 -0.00829131 0.0736669 -0.027624 -0.00829131 0.0732918 0.0346308 -0.00829131 0.0725245 0.0346308 -0.00829131 0.0666155 -0.0346224 -0.00829131 0.0666155 -0.0388208 -0.00829131 0.0701072 -0.0390418 -0.00829131 0.0692822 4.20971e-06 -0.00829131 -0.0666106 4.20971e-06 -0.00829131 -0.0725196 -0.0390418 -0.00829131 -0.0692773 0.0346308 -0.00829131 0.0570287 0.024294 -0.00829131 0.0666155 4.20971e-06 -0.00829131 0.0666155 0.0457073 -0.00829131 0.0570287 0.024294 -0.00829131 0.0570287 4.20971e-06 -0.00829131 0.0570287 -0.0346224 -0.00829131 0.0570287 -0.0456989 -0.00829131 0.0570287 -0.0532159 -0.00829131 0.0542226 -0.0544361 -0.00829131 0.0572427 -0.0548112 -0.00829131 0.0558427 0.0346308 -0.00829131 -0.0542177 0.024294 -0.00829131 -0.0570238 4.20971e-06 -0.00829131 -0.0542177 4.20971e-06 -0.00829131 -0.0570238 -0.0456989 -0.00829131 -0.0542177 -0.0532159 -0.00829131 -0.0570238 0.0346308 -0.00829131 -0.0570238 0.024294 -0.00829131 -0.0666106 -0.0346224 -0.00829131 -0.0570238 -0.0456989 -0.00829131 -0.0666106 0.0479497 -0.00829131 0.0248466 0.0457073 -0.00829131 0.0346291 0.0570305 -0.00829131 0.0542226 0.0570305 -0.00829131 -0.0457006 0.0570305 -0.00829131 -0.0542177 0.0457073 -0.00829131 -0.0457006 0.0457073 -0.00829131 -0.0542177 0.0346308 -0.00829131 -0.0457006 0.024294 -0.00829131 -0.0542177 0.0156624 -0.00829131 -0.0516775 0.0570305 -0.00829131 -0.0346242 0.0417126 -0.00829131 -0.0342964 0.0342291 -0.00829131 -0.0417666 0.0570305 -0.00829131 0.0346291 0.0624101 -0.00829131 -0.00989826 0.0570305 -0.00829131 -0.00989826 0.0754661 -0.00829131 0.0203308 0.0725262 -0.00829131 0.0242923 0.0725262 -0.00829131 0.00990314 0.0624101 -0.00829131 0.00990314 0.0624101 -0.00829131 0.0242923 0.0570305 -0.00829131 0.0242923 0.0570305 -0.00829131 0.00990314 0.0793042 -0.00829131 2.44063e-06 0.0790989 -0.00829131 0.00990314 0.0743447 -0.00829131 0.00990314 0.0725262 -0.00829131 -0.00989826 0.0276324 0.0177087 0.0785918 0.0287171 0.0177087 0.0783442 0.0288824 -0.00799131 0.0782568 0.029587 -0.00799131 0.0776505 0.0300698 0.0177087 0.0766481 0.0300698 0.0177087 0.0755355 0.0297975 -0.00799131 0.0748418 0.029587 0.0177087 0.0776505 0.0303622 0.0180087 0.0754687 0.029587 0.0177087 0.074533 0.0298216 0.0180087 0.074346 0.0287171 0.0177087 0.0738393 0.0288473 0.0180087 0.073569 0.0520854 -0.00799131 0.0644738 0.0533354 -0.00799131 0.0641389 0.0542504 -0.00799131 0.0632238 0.0542504 0.0177087 0.0607238 0.0533354 0.0177087 0.0641389 0.0542504 0.0177087 0.0632238 0.0545102 0.0180087 0.0633738 0.0545854 0.0177087 0.0619738 0.0548854 0.0180087 0.0619738 0.0545102 0.0180087 0.0605738 0.0533354 0.0177087 0.0598088 0.0520854 0.0180087 0.0591738 0.0630603 -0.00799131 0.054336 0.0632256 0.0177087 0.0542487 0.0632256 -0.00799131 0.0542487 0.0641407 -0.00799131 0.0533336 0.0644756 0.0177087 0.0520836 0.0644756 -0.00799131 0.0520836 0.0644129 -0.00799131 0.0515273 0.0641407 -0.00799131 0.0508336 0.0641407 0.0177087 0.0508336 0.0632256 -0.00799131 0.0499185 0.0632256 0.0177087 0.0499185 0.0619756 0.0177087 0.0495836 0.0619756 0.0180087 0.0548836 0.0641407 0.0177087 0.0533336 0.0647756 0.0180087 0.0520836 0.0644005 0.0180087 0.0506836 0.0773435 -0.00799131 0.0297957 0.0782586 -0.00799131 0.0288807 0.0773435 0.0177087 0.0254656 0.0773435 0.0177087 0.0297957 0.0782586 0.0177087 0.0288807 0.0785184 0.0180087 0.0290307 0.0785935 0.0177087 0.0276307 0.0782586 0.0177087 0.0263807 0.0785184 0.0180087 0.0262307 0.0774935 0.0180087 0.0252058 0.0760935 0.0180087 0.0248307 0.0276324 -0.00829131 0.0788918 0.0290324 -0.00829131 0.0785166 0.0276324 -0.00799131 0.0785918 0.0300573 -0.00829131 0.0774918 0.0297975 -0.00799131 0.0773418 0.0304324 -0.00829131 0.0760918 0.0300698 -0.00799131 0.0766481 0.0301324 -0.00799131 0.0760918 0.0300698 -0.00799131 0.0755355 0.0276324 -0.00799131 0.0735918 0.0276324 -0.00829131 0.0732918 0.0288824 -0.00799131 0.0739267 0.029587 -0.00799131 0.074533 0.0290324 -0.00829131 0.0736669 0.0300573 -0.00829131 0.0746918 0.0533354 -0.00799131 0.0598088 0.0534854 -0.00829131 0.059549 0.0542504 -0.00799131 0.0607238 0.0545102 -0.00829131 0.0605738 0.0545854 -0.00799131 0.0619738 0.0545102 -0.00829131 0.0633738 0.0534854 -0.00829131 0.0643987 0.0619756 -0.00799131 0.0545836 0.0631905 -0.00829131 0.0546063 0.0639302 -0.00799131 0.0536423 0.0644129 -0.00799131 0.0526399 0.0647054 -0.00829131 0.0514605 0.0639302 -0.00799131 0.0505249 0.0619756 -0.00829131 0.0492836 0.0630603 -0.00799131 0.0498312 0.0631905 -0.00829131 0.0495609 0.0774935 -0.00829131 0.0252058 0.0773435 -0.00799131 0.0254656 0.0782586 -0.00799131 0.0263807 0.0785184 -0.00829131 0.0262307 0.0788935 -0.00829131 0.0276307 0.0785935 -0.00799131 0.0276307 0.0774935 -0.00829131 0.0300555 -0.0396458 -0.00829131 0.0686783 -0.0390418 -0.00729131 0.0692822 -0.0692755 -0.00829131 0.0390485 -0.0692755 -0.00729131 0.0390485 -0.0686716 -0.00829131 0.0396524 -0.0686716 -0.00729131 0.0413024 -0.0686716 -0.00829131 0.0413024 -0.0692755 -0.00729131 0.0419064 -0.0692755 -0.00829131 0.0419064 -0.0801208 -0.00729131 -0.0014265 -0.0792958 -0.00729131 2.44063e-06 -0.0795169 -0.00829131 -0.000822559 -0.0792958 -0.00829131 2.44063e-06 -0.0809458 -0.00729131 0.00165244 -0.0809458 -0.00829131 0.00165244 -0.0692755 -0.00729131 -0.0419015 -0.0684505 -0.00829131 -0.0404726 -0.0686716 -0.00729131 -0.0396476 -0.0686716 -0.00829131 -0.0396476 -0.0701005 -0.00729131 -0.0388226 -0.0404708 -0.00829131 -0.0717523 -0.0396458 -0.00829131 -0.0715313 -0.0388208 -0.00829131 -0.0701023 -0.0390418 -0.00729131 -0.0692773 -0.0396458 -0.00829131 -0.0686734 -0.0404708 -0.00729131 -0.0684523 0.0708249 -0.00829131 -0.0419592 0.071399 -0.00829131 -0.0394438 0.0404792 -0.00829131 -0.0717523 0.0420878 -0.00829131 -0.0704695 0.0420878 -0.00729131 -0.0697352 0.0420878 -0.00829131 -0.0697352 0.0417692 -0.00729131 -0.0690736 0.0411951 -0.00729131 -0.0686157 0.0411951 -0.00829131 -0.0686157 0.0404792 -0.00829131 0.0684572 0.0413042 -0.00829131 0.0686783 0.0421292 -0.00729131 0.0701072 0.0419082 -0.00729131 0.0709322 0.0413042 -0.00829131 0.0715361 0.0404792 -0.00729131 0.0717572 0.0404792 -0.00829131 0.0717572 0.0717176 -0.00729131 0.0401103 0.0717176 -0.00829131 0.0401103 0.071399 -0.00729131 0.0415062 0.071399 -0.00829131 0.0415062 0.070109 -0.00729131 0.0421274 0.070109 -0.00829131 0.0421274 0.0823831 -0.00729131 -0.000822559 0.0826042 -0.00729131 2.44063e-06 0.0823831 -0.00829131 -0.000822559 0.0823831 -0.00829131 0.000827441 0.0817792 -0.00729131 0.00143138 0.0809542 -0.00729131 0.00165244 0.0817792 -0.00829131 0.00143138 0.0229055 0.00570869 0.0777491 0.0233929 0.00570869 0.0776378 0.0233929 0.00570869 0.0787504 0.0218234 0.00570869 0.0799961 0.0197056 0.00570869 0.0803592 0.0187905 0.00570869 0.0794441 0.0189556 0.00570869 0.0781941 0.0192236 0.00570869 0.0771941 0.0209556 0.00570869 0.0761941 0.0225193 0.00570869 0.0769472 0.0209556 0.00570869 0.0756941 0.0220403 0.00570869 0.0759417 0.0220403 -0.00799131 0.0759417 0.0229102 0.00570869 0.0766354 0.0233929 -0.00799131 0.0776378 0.0233929 -0.00799131 0.0787504 0.0229102 0.00570869 0.0797529 0.0229102 -0.00799131 0.0797529 0.0220403 0.00570869 0.0804466 0.0209556 -0.00799131 0.0756941 0.0221705 -0.00829131 0.0756714 0.0229102 -0.00799131 0.0766354 0.0236854 -0.00829131 0.0775711 0.0236854 -0.00829131 0.0788172 0.0231447 -0.00829131 0.0799399 0.0220403 -0.00799131 0.0804466 0.0550794 0.00570869 0.0584927 0.0555125 0.00570869 0.0562427 0.0562445 0.00570869 0.0555107 0.0572445 0.00570869 0.0552427 0.0559945 0.00570869 0.0550777 0.0572445 0.00570869 0.0547427 0.0588082 0.00570869 0.0559958 0.0591991 0.00570869 0.055684 0.0596818 0.00570869 0.0566864 0.0596818 0.00570869 0.057799 0.0588082 0.00570869 0.0584897 0.0572445 -0.00799131 0.0547427 0.0583292 0.00570869 0.0549903 0.0591991 0.00570869 0.0588015 0.0583292 0.00570869 0.0594952 0.0583292 -0.00799131 0.0594952 0.0572445 0.00570869 0.0597427 0.0584594 -0.00829131 0.05472 0.0583292 -0.00799131 0.0549903 0.0591991 -0.00799131 0.055684 0.0596818 -0.00799131 0.0566864 0.0599743 -0.00829131 0.0566197 0.0596818 -0.00799131 0.057799 0.0591991 -0.00799131 0.0588015 0.0572445 -0.00799131 0.0597427 0.0584594 -0.00829131 0.0597654 0.0572445 -0.00829131 0.0600427 0.0791959 0.00570869 0.0192218 0.079928 0.00570869 0.0199538 0.080361 0.00570869 0.0197038 0.079928 0.00570869 0.0219538 0.0806959 0.00570869 0.0209538 0.080361 0.00570869 0.0222038 0.0794459 0.00570869 0.0231189 0.0781959 0.00570869 0.0229538 0.0771959 0.00570869 0.0226859 0.0764639 0.00570869 0.0219538 0.0781959 0.00570869 0.0184538 0.0794459 0.00570869 0.0187888 0.080361 -0.00799131 0.0197038 0.0781959 0.00570869 0.0234538 0.0781959 -0.00829131 0.0181538 0.0794459 -0.00799131 0.0187888 0.0795959 -0.00829131 0.018529 0.0806208 -0.00829131 0.0195538 0.0806959 -0.00799131 0.0209538 0.080361 -0.00799131 0.0222038 0.0809959 -0.00829131 0.0209538 0.0806208 -0.00829131 0.0223538 0.0795959 -0.00829131 0.0233787 0.0794459 -0.00799131 0.0231189 0.0781959 -0.00799131 0.0234538 0.0209556 0.00570869 0.0801941 0.0215806 0.00645869 0.0792767 0.0225193 0.00570869 0.0794411 0.0220381 0.00645869 0.0788191 0.0221743 0.00645869 0.0784723 0.0229055 0.00570869 0.0786392 0.0222056 0.00645869 0.0781941 0.0221743 0.00645869 0.077916 0.0220381 0.00645869 0.0775691 0.0218234 0.00570869 0.0763922 0.021498 0.00645869 0.0770679 0.0215806 0.00645869 0.0771116 0.0209556 0.00645869 0.0794441 0.021498 0.00645869 0.0793203 0.0215806 0.0172587 0.0792767 0.0219329 0.00645869 0.0789735 0.0222056 0.0172587 0.0781941 0.0220381 0.0172587 0.0775691 0.0219329 0.00645869 0.0774148 0.0215806 0.0172587 0.0771116 0.0209556 0.00645869 0.0769441 0.0219556 0.0180087 0.0799262 0.0220381 0.0172587 0.0788191 0.0226877 0.0180087 0.0771941 0.0572445 0.00570869 0.0592427 0.0572445 0.00645869 0.0584927 0.0577869 0.00645869 0.0583689 0.0581123 0.00570869 0.0590447 0.058327 0.00645869 0.0578677 0.0591944 0.00570869 0.0576878 0.0591944 0.00570869 0.0567977 0.0584945 0.00645869 0.0572427 0.0584632 0.00645869 0.0569646 0.0577869 0.00645869 0.0561165 0.0581123 0.00570869 0.0554408 0.0578695 0.00645869 0.0583253 0.0582218 0.00645869 0.0580221 0.058327 0.0172587 0.0578677 0.0584632 0.00645869 0.0575209 0.058327 0.00645869 0.0566177 0.0582218 0.00645869 0.0564634 0.0578695 0.00645869 0.0561602 0.0572445 0.0180087 0.0592427 0.0578695 0.0172587 0.0583253 0.0584945 0.0172587 0.0572427 0.058327 0.0172587 0.0566177 0.0578695 0.0172587 0.0561602 0.0582445 0.0180087 0.0555107 0.0781959 0.00645869 0.0222038 0.0791959 0.00570869 0.0226859 0.0788209 0.00645869 0.0220364 0.0801959 0.00570869 0.0209538 0.0781959 0.00645869 0.0197038 0.0781959 0.00570869 0.0189538 0.0791732 0.00645869 0.0201745 0.0794146 0.00645869 0.0206757 0.0787383 0.0172587 0.0220801 0.0791732 0.0172587 0.0217332 0.0791732 0.00645869 0.0217332 0.0792784 0.00645869 0.0215788 0.0794146 0.00645869 0.021232 0.0794146 0.0172587 0.021232 0.0794459 0.00645869 0.0209538 0.0792784 0.00645869 0.0203288 0.0791732 0.0172587 0.0201745 0.0788209 0.00645869 0.0198713 0.0781959 0.0172587 0.0197038 0.0781959 0.0172587 0.0222038 0.0790637 0.0180087 0.0227558 0.0794146 0.0172587 0.0206757 0.0787383 0.0172587 0.0198276 -0.027624 -0.00799131 0.0785918 -0.025459 -0.00799131 0.0773418 -0.0251867 -0.00799131 0.0766481 -0.0251867 0.0177087 0.0766481 -0.0251867 -0.00799131 0.0755355 -0.0256694 0.0177087 0.074533 -0.026374 -0.00799131 0.0739267 -0.0265393 0.0177087 0.0783442 -0.0256694 0.0177087 0.0776505 -0.0264091 0.0180087 0.0786145 -0.0248942 0.0180087 0.0767148 -0.0251867 0.0177087 0.0755355 -0.0248942 0.0180087 0.0754687 -0.0265393 0.0177087 0.0738393 -0.0264091 0.0180087 0.073569 -0.050827 0.0177087 0.0641389 -0.050827 -0.00799131 0.0641389 -0.0499119 -0.00799131 0.0632238 -0.0499119 0.0177087 0.0607238 -0.050827 -0.00799131 0.0598088 -0.052077 -0.00799131 0.0594738 -0.050827 0.0177087 0.0598088 -0.052077 0.0180087 0.0647738 -0.0499119 0.0177087 0.0632238 -0.0496521 0.0180087 0.0633738 -0.049577 0.0177087 0.0619738 -0.049277 0.0180087 0.0619738 -0.050677 0.0180087 0.059549 -0.0619672 -0.00799131 0.0545836 -0.0608825 -0.00799131 0.054336 -0.0607172 0.0177087 0.0542487 -0.0600126 -0.00799131 0.0536423 -0.0594672 0.0177087 0.0520836 -0.0594672 -0.00799131 0.0520836 -0.0598021 -0.00799131 0.0508336 -0.0608825 -0.00799131 0.0498312 -0.0619672 0.0177087 0.0495836 -0.0605672 0.0180087 0.0545085 -0.0598021 0.0177087 0.0533336 -0.0598021 0.0177087 0.0508336 -0.0607172 0.0177087 0.0499185 -0.0748351 0.0177087 0.0297957 -0.0735851 -0.00799131 0.0276307 -0.07392 0.0177087 0.0263807 -0.0748351 -0.00799131 0.0254656 -0.0760851 0.0180087 0.0304307 -0.07392 0.0177087 0.0288807 -0.0746851 0.0180087 0.0300555 -0.0736602 0.0180087 0.0290307 -0.0735851 0.0177087 0.0276307 -0.0748351 0.0177087 0.0254656 -0.0746851 0.0180087 0.0252058 -0.026374 -0.00799131 0.0782568 -0.0251991 -0.00829131 0.0774918 -0.0256694 -0.00799131 0.0776505 -0.024824 -0.00829131 0.0760918 -0.025124 -0.00799131 0.0760918 -0.027624 -0.00799131 0.0735918 -0.0256694 -0.00799131 0.074533 -0.025459 -0.00799131 0.0748418 -0.0499119 -0.00799131 0.0607238 -0.049577 -0.00799131 0.0619738 -0.0496521 -0.00829131 0.0605738 -0.049277 -0.00829131 0.0619738 -0.052077 -0.00799131 0.0644738 -0.0607523 -0.00829131 0.0546063 -0.0597781 -0.00829131 0.0538294 -0.0607172 -0.00799131 0.0542487 -0.0598021 -0.00799131 0.0533336 -0.0595299 -0.00799131 0.0526399 -0.0592374 -0.00829131 0.0514605 -0.0595299 -0.00799131 0.0515273 -0.0597781 -0.00829131 0.0503378 -0.0600126 -0.00799131 0.0505249 -0.0619672 -0.00799131 0.0495836 -0.0619672 -0.00829131 0.0492836 -0.0607172 -0.00799131 0.0499185 -0.07392 -0.00799131 0.0263807 -0.07392 -0.00799131 0.0288807 -0.0748351 -0.00799131 0.0297957 -0.0746851 -0.00829131 0.0300555 -0.0229018 0.00570869 0.0797529 -0.0229472 0.00570869 0.0781941 -0.0233845 0.00570869 0.0787504 -0.0233845 0.00570869 0.0776378 -0.0229018 0.00570869 0.0766354 -0.0219472 0.00570869 0.0764621 -0.0209472 0.00570869 0.0756941 -0.0199472 0.00570869 0.0764621 -0.0192151 0.00570869 0.0771941 -0.0189472 0.00570869 0.0781941 -0.0199472 0.00570869 0.0799262 -0.0196972 0.00570869 0.0803592 -0.0209472 0.00570869 0.0801941 -0.0226792 0.00570869 0.0791941 -0.0209472 -0.00799131 0.0756941 -0.0196972 -0.00799131 0.0760291 -0.0196972 0.00570869 0.0760291 -0.0187821 0.00570869 0.0769441 -0.0187821 -0.00799131 0.0769441 -0.0184472 0.00570869 0.0781941 -0.0187821 0.00570869 0.0794441 -0.0196972 -0.00799131 0.0803592 -0.0209472 0.00570869 0.0806941 -0.0195472 -0.00829131 0.0757693 -0.0185223 -0.00829131 0.0767941 -0.0184472 -0.00799131 0.0781941 -0.0187821 -0.00799131 0.0794441 -0.0185223 -0.00829131 0.0795941 -0.0195472 -0.00829131 0.080619 -0.0591907 0.00570869 0.055684 -0.0572361 0.00570869 0.0552427 -0.0572361 0.00570869 0.0547427 -0.055071 0.00570869 0.0559927 -0.055504 0.00570869 0.0582427 -0.0562361 0.00570869 0.0589748 -0.0559861 0.00570869 0.0594078 -0.0572361 0.00570869 0.0597427 -0.0583208 0.00570869 0.0594952 -0.0591907 0.00570869 0.0588015 -0.0559861 0.00570869 0.0550777 -0.0559861 -0.00799131 0.0550777 -0.0547361 0.00570869 0.0572427 -0.055071 0.00570869 0.0584927 -0.0559861 -0.00799131 0.0594078 -0.055071 -0.00799131 0.0559927 -0.0547361 -0.00799131 0.0572427 -0.055071 -0.00799131 0.0584927 -0.0558361 -0.00829131 0.0596676 -0.0572361 -0.00799131 0.0597427 -0.0773197 0.00570869 0.0227558 -0.0791875 0.00570869 0.0226859 -0.0794375 0.00570869 0.0231189 -0.0799195 0.00570869 0.0219538 -0.0801875 0.00570869 0.0209538 -0.0803526 0.00570869 0.0222038 -0.0806875 0.00570869 0.0209538 -0.0791875 0.00570869 0.0192218 -0.0781875 0.00570869 0.0189538 -0.0771028 0.00570869 0.0187014 -0.0757502 0.00570869 0.0203975 -0.0762329 0.00570869 0.0225126 -0.0762329 0.00570869 0.0193951 -0.0757502 0.00570869 0.0215101 -0.0757502 -0.00799131 0.0203975 -0.0762329 -0.00799131 0.0225126 -0.0771028 0.00570869 0.0232063 -0.0781875 0.00570869 0.0234538 -0.0781875 -0.00799131 0.0184538 -0.0781875 -0.00829131 0.0181538 -0.0769726 -0.00829131 0.0184311 -0.0771028 -0.00799131 0.0187014 -0.0762329 -0.00799131 0.0193951 -0.0759984 -0.00829131 0.0192081 -0.0754577 -0.00829131 0.0203308 -0.0757502 -0.00799131 0.0215101 -0.0771028 -0.00799131 0.0232063 -0.0781875 -0.00799131 0.0234538 -0.0769726 -0.00829131 0.0234766 -0.0192151 0.00570869 0.0791941 -0.0199699 0.00645869 0.0789735 -0.0198647 0.00645869 0.0788191 -0.0197285 0.00645869 0.0784723 -0.0197285 0.00645869 0.077916 -0.0203222 0.00645869 0.0771116 -0.0199699 0.00645869 0.0774148 -0.0203222 0.00645869 0.0792767 -0.0204048 0.0172587 0.0793203 -0.0199699 0.0172587 0.0789735 -0.0196972 0.00645869 0.0781941 -0.0197285 0.0172587 0.0784723 -0.0197285 0.0172587 0.077916 -0.0198647 0.00645869 0.0775691 -0.0209472 0.0172587 0.0769441 -0.0209472 0.0180087 0.0801941 -0.0200794 0.0180087 0.0799961 -0.0193835 0.0180087 0.0794411 -0.0189973 0.0180087 0.0786392 -0.0189973 0.0180087 0.0777491 -0.0199699 0.0172587 0.0774148 -0.0193835 0.0180087 0.0769472 -0.0200794 0.0180087 0.0763922 -0.0204048 0.0172587 0.0770679 -0.0552361 0.00570869 0.0572427 -0.0561536 0.00645869 0.0578677 -0.0560174 0.00645869 0.0575209 -0.0572361 0.00645869 0.0559927 -0.0562361 0.00570869 0.0555107 -0.055504 0.00570869 0.0562427 -0.0561536 0.00645869 0.0566177 -0.0566111 0.00645869 0.0583253 -0.0562588 0.00645869 0.0580221 -0.0562588 0.0172587 0.0580221 -0.0560174 0.0172587 0.0575209 -0.0559861 0.00645869 0.0572427 -0.0560174 0.00645869 0.0569646 -0.0560174 0.0172587 0.0569646 -0.0562588 0.0172587 0.0564634 -0.0562588 0.00645869 0.0564634 -0.0566937 0.0172587 0.0561165 -0.0566111 0.00645869 0.0561602 -0.0572361 0.0172587 0.0559927 -0.0572361 0.0172587 0.0584927 -0.0566937 0.0172587 0.0583689 -0.0556724 0.0180087 0.0559958 -0.0572361 0.0180087 0.0552427 -0.0781875 0.00570869 0.0229538 -0.0766238 0.00570869 0.0222008 -0.077105 0.00645869 0.0215788 -0.0769688 0.00645869 0.021232 -0.0762376 0.00570869 0.0213989 -0.0769375 0.00645869 0.0209538 -0.0762376 0.00570869 0.0205088 -0.0766238 0.00570869 0.0197069 -0.0773197 0.00570869 0.0191519 -0.0776451 0.00645869 0.0220801 -0.0775625 0.00645869 0.0220364 -0.0775625 0.0172587 0.0220364 -0.0772102 0.00645869 0.0217332 -0.077105 0.0172587 0.0215788 -0.0769375 0.0172587 0.0209538 -0.0769688 0.00645869 0.0206757 -0.077105 0.00645869 0.0203288 -0.0775625 0.0172587 0.0198713 -0.0772102 0.00645869 0.0201745 -0.0775625 0.00645869 0.0198713 -0.0776451 0.00645869 0.0198276 -0.0781875 0.0172587 0.0197038 -0.0781875 0.0180087 0.0229538 -0.0764554 0.0180087 0.0219538 -0.0761875 0.0180087 0.0209538 -0.077105 0.0172587 0.0203288 -0.0771875 0.0180087 0.0192218 0.0287171 -0.00799131 -0.0738344 0.0288824 0.0177087 -0.0739218 0.0288824 -0.00799131 -0.0739218 0.029587 -0.00799131 -0.0745282 0.0297975 -0.00799131 -0.0748369 0.0297975 0.0177087 -0.0748369 0.0300698 -0.00799131 -0.0755306 0.0301324 -0.00799131 -0.0760869 0.0301324 0.0177087 -0.0760869 0.0288824 -0.00799131 -0.0782519 0.0288824 0.0177087 -0.0782519 0.0290324 0.0180087 -0.073662 0.0304324 0.0180087 -0.0760869 0.0297975 0.0177087 -0.0773369 0.0300573 0.0180087 -0.0774869 0.0290324 0.0180087 -0.0785117 0.05404 -0.00799131 -0.0604102 0.0542504 0.0177087 -0.060719 0.0545227 -0.00799131 -0.0614127 0.0545227 -0.00799131 -0.0625253 0.0545854 0.0177087 -0.061969 0.0542504 -0.00799131 -0.063219 0.05404 -0.00799131 -0.0635277 0.0542504 0.0177087 -0.063219 0.0533354 -0.00799131 -0.064134 0.0531701 -0.00799131 -0.0642214 0.0533354 0.0177087 -0.0598039 0.0534854 0.0180087 -0.0595441 0.0545102 0.0180087 -0.060569 0.0533354 0.0177087 -0.064134 0.0619756 0.0177087 -0.0495787 0.0630603 -0.00799131 -0.0498263 0.0632256 0.0177087 -0.0499137 0.0641407 -0.00799131 -0.0508287 0.0644129 -0.00799131 -0.0515224 0.0644756 -0.00799131 -0.0520787 0.0644756 0.0177087 -0.0520787 0.0644129 -0.00799131 -0.052635 0.0641407 -0.00799131 -0.0533287 0.0641407 0.0177087 -0.0533287 0.0639302 -0.00799131 -0.0536374 0.0630603 -0.00799131 -0.0543311 0.0641407 0.0177087 -0.0508287 0.0633756 0.0180087 -0.0496539 0.0647756 0.0180087 -0.0520787 0.0632256 0.0177087 -0.0542438 0.0619756 0.0177087 -0.0545787 0.0773435 -0.00799131 -0.0254607 0.0780481 0.0177087 -0.0260671 0.0782586 -0.00799131 -0.0263758 0.0785935 -0.00799131 -0.0276258 0.0785308 0.0177087 -0.0281821 0.0782586 -0.00799131 -0.0288758 0.0780481 0.0177087 -0.0291845 0.0773435 -0.00799131 -0.0297908 0.0760935 0.0177087 -0.0251258 0.0773084 0.0180087 -0.0251031 0.0771782 0.0177087 -0.0253734 0.0782827 0.0180087 -0.02588 0.0785308 0.0177087 -0.0270695 0.0788233 0.0180087 -0.0270027 0.0773084 0.0180087 -0.0301485 0.0771782 0.0177087 -0.0298782 0.0760935 0.0177087 -0.0301258 0.0288473 -0.00829131 -0.0735642 0.0298216 -0.00829131 -0.0743411 0.0303622 -0.00829131 -0.0754638 0.0303622 -0.00829131 -0.0767099 0.0300698 -0.00799131 -0.0766432 0.0298216 -0.00829131 -0.0778326 0.0297975 -0.00799131 -0.0773369 0.0276324 -0.00799131 -0.0785869 0.0287171 -0.00799131 -0.0783393 0.0276324 -0.00829131 -0.0788869 0.029587 -0.00799131 -0.0776456 0.0520854 -0.00799131 -0.059469 0.0533003 -0.00829131 -0.0594462 0.0531701 -0.00799131 -0.0597165 0.0542745 -0.00829131 -0.0602232 0.0533354 -0.00799131 -0.0598039 0.0542504 -0.00799131 -0.060719 0.0545854 -0.00799131 -0.061969 0.0542745 -0.00829131 -0.0637147 0.0520854 -0.00799131 -0.064469 0.0619756 -0.00829131 -0.0492787 0.0619756 -0.00799131 -0.0495787 0.0632256 -0.00799131 -0.0499137 0.0641647 -0.00829131 -0.050333 0.0639302 -0.00799131 -0.05052 0.0647054 -0.00829131 -0.0514557 0.0641647 -0.00829131 -0.0538245 0.0631905 -0.00829131 -0.0546014 0.0632256 -0.00799131 -0.0542438 0.0774935 -0.00829131 -0.0252009 0.0780481 -0.00799131 -0.0260671 0.0785308 -0.00799131 -0.0270695 0.0785308 -0.00799131 -0.0281821 0.0760935 -0.00829131 -0.0304258 0.0774935 -0.00829131 -0.0300507 0.0780481 -0.00799131 -0.0291845 0.0785184 -0.00829131 -0.0290258 0.0226877 0.00570869 -0.0791893 0.0219556 0.00570869 -0.0799213 0.0200878 0.00570869 -0.0799912 0.0229556 0.00570869 -0.0781893 0.0226877 0.00570869 -0.0771893 0.0233929 0.00570869 -0.077633 0.0219556 0.00570869 -0.0764572 0.0220403 0.00570869 -0.0759368 0.0197056 0.00570869 -0.0760242 0.0193919 0.00570869 -0.0769423 0.0184556 0.00570869 -0.0781893 0.0190058 0.00570869 -0.0786343 0.0220403 0.00570869 -0.0804417 0.0220403 -0.00799131 -0.0804417 0.0229102 0.00570869 -0.079748 0.0229102 -0.00799131 -0.079748 0.0233929 0.00570869 -0.0787456 0.0233929 -0.00799131 -0.0787456 0.0229102 -0.00799131 -0.0766305 0.0229102 0.00570869 -0.0766305 0.0220403 -0.00799131 -0.0759368 0.0231447 -0.00829131 -0.079935 0.0233929 -0.00799131 -0.077633 0.0231447 -0.00829131 -0.0764435 0.0221705 -0.00829131 -0.0756665 0.0589766 0.00570869 -0.0582379 0.0582445 0.00570869 -0.0589699 0.0583292 0.00570869 -0.0594903 0.0572445 0.00570869 -0.0592379 0.0563767 0.00570869 -0.0590398 0.0550794 0.00570869 -0.0584879 0.0556808 0.00570869 -0.0584848 0.0592445 0.00570869 -0.0572379 0.0596818 0.00570869 -0.0566816 0.0591991 0.00570869 -0.0556791 0.0582445 0.00570869 -0.0555058 0.0572445 0.00570869 -0.0552379 0.0559945 0.00570869 -0.0550728 0.0550794 0.00570869 -0.0559879 0.0552946 0.00570869 -0.0576829 0.0547445 0.00570869 -0.0572379 0.0572445 0.00570869 -0.0597379 0.0572445 -0.00799131 -0.0597379 0.0591991 0.00570869 -0.0587966 0.0596818 0.00570869 -0.0577942 0.0596818 -0.00799131 -0.0577942 0.0596818 -0.00799131 -0.0566816 0.0583292 0.00570869 -0.0549854 0.0572445 0.00570869 -0.0547379 0.0583292 -0.00799131 -0.0594903 0.0572445 -0.00829131 -0.0600379 0.0584594 -0.00829131 -0.0597606 0.0591991 -0.00799131 -0.0587966 0.0599743 -0.00829131 -0.0578609 0.0591991 -0.00799131 -0.0556791 0.0583292 -0.00799131 -0.0549854 0.0594336 -0.00829131 -0.0554921 0.0757586 0.00570869 -0.0203927 0.0757586 0.00570869 -0.0215053 0.0771959 0.00570869 -0.022681 0.0771112 0.00570869 -0.0232014 0.0781959 0.00570869 -0.023449 0.0791959 0.00570869 -0.022681 0.0794459 0.00570869 -0.023114 0.080361 0.00570869 -0.022199 0.0791959 0.00570869 -0.0192169 0.0781959 0.00570869 -0.018949 0.0771959 0.00570869 -0.0192169 0.0764639 0.00570869 -0.019949 0.0794459 -0.00799131 -0.023114 0.080361 -0.00799131 -0.022199 0.0806959 0.00570869 -0.020949 0.080361 0.00570869 -0.019699 0.0794459 -0.00799131 -0.0187839 0.0794459 0.00570869 -0.0187839 0.0781959 0.00570869 -0.018449 0.0781959 -0.00829131 -0.023749 0.0806208 -0.00829131 -0.022349 0.0806959 -0.00799131 -0.020949 0.0809959 -0.00829131 -0.020949 0.080361 -0.00799131 -0.019699 0.0220381 0.00645869 -0.0775643 0.0209556 0.00570869 -0.0761893 0.0209556 0.0172587 -0.0769393 0.0215806 0.00645869 -0.0771067 0.0220381 0.0172587 -0.0775643 0.0222056 0.00645869 -0.0781893 0.0222056 0.0172587 -0.0781893 0.0220381 0.00645869 -0.0788143 0.0215806 0.00645869 -0.0792718 0.0209556 0.0172587 -0.0794393 0.0215806 0.0172587 -0.0771067 0.0226877 0.0180087 -0.0771893 0.0229556 0.0180087 -0.0781893 0.0220381 0.0172587 -0.0788143 0.0215806 0.0172587 -0.0792718 0.058327 0.00645869 -0.0566129 0.0589766 0.00570869 -0.0562379 0.0572445 0.0172587 -0.0559879 0.0578695 0.00645869 -0.0561553 0.058327 0.0172587 -0.0566129 0.0584945 0.00645869 -0.0572379 0.058327 0.00645869 -0.0578629 0.0578695 0.00645869 -0.0583204 0.058327 0.0172587 -0.0578629 0.0578695 0.0172587 -0.0583204 0.0572445 0.0172587 -0.0584879 0.0578695 0.0172587 -0.0561553 0.0584945 0.0172587 -0.0572379 0.0592445 0.0180087 -0.0572379 0.0589766 0.0180087 -0.0582379 0.0582445 0.0180087 -0.0589699 0.0781959 0.00570869 -0.022949 0.0788209 0.00645869 -0.0220315 0.0792784 0.00645869 -0.021574 0.079928 0.00570869 -0.021949 0.0801959 0.00570869 -0.020949 0.0792784 0.00645869 -0.020324 0.0788209 0.00645869 -0.0198664 0.079928 0.00570869 -0.019949 0.0781959 0.0172587 -0.019699 0.0792784 0.0172587 -0.020324 0.0794459 0.00645869 -0.020949 0.0788209 0.0172587 -0.0220315 0.0781959 0.0180087 -0.018949 0.0788209 0.0172587 -0.0198664 0.0791959 0.0180087 -0.0192169 0.0794459 0.0172587 -0.020949 0.0792784 0.0172587 -0.021574 0.0801959 0.0180087 -0.020949 0.079928 0.0180087 -0.021949 0.0791959 0.0180087 -0.022681 0.0781959 0.0180087 -0.022949 -0.0265393 -0.00799131 -0.0738344 -0.027624 0.0177087 -0.0735869 -0.026374 0.0177087 -0.0739218 -0.026374 -0.00799131 -0.0739218 -0.025124 -0.00799131 -0.0760869 -0.025459 -0.00799131 -0.0773369 -0.025459 0.0177087 -0.0773369 -0.026374 0.0177087 -0.0782519 -0.027624 0.0180087 -0.0732869 -0.025459 0.0177087 -0.0748369 -0.0251991 0.0180087 -0.0746869 -0.025124 0.0177087 -0.0760869 -0.0251991 0.0180087 -0.0774869 -0.027624 0.0177087 -0.0785869 -0.0499119 -0.00799131 -0.060719 -0.0496396 -0.00799131 -0.0614127 -0.049577 -0.00799131 -0.061969 -0.0501224 -0.00799131 -0.0635277 -0.0501224 0.0177087 -0.0635277 -0.0509922 0.0177087 -0.0642214 -0.0509922 0.0177087 -0.0597165 -0.0508621 0.0180087 -0.0594462 -0.0501224 0.0177087 -0.0604102 -0.0496396 0.0177087 -0.0614127 -0.0493472 0.0180087 -0.0613459 -0.0496396 0.0177087 -0.0625253 -0.0498878 0.0180087 -0.0637147 -0.0508621 0.0180087 -0.0644917 -0.0619672 -0.00799131 -0.0495787 -0.0607172 0.0177087 -0.0499137 -0.0600126 -0.00799131 -0.05052 -0.0598021 0.0177087 -0.0508287 -0.0598021 -0.00799131 -0.0508287 -0.0594672 -0.00799131 -0.0520787 -0.0594672 0.0177087 -0.0520787 -0.0600126 -0.00799131 -0.0536374 -0.0607172 -0.00799131 -0.0542438 -0.0619672 0.0180087 -0.0492787 -0.0605672 0.0180087 -0.0496539 -0.0591672 0.0180087 -0.0520787 -0.0598021 0.0177087 -0.0533287 -0.0595423 0.0180087 -0.0534787 -0.0607172 0.0177087 -0.0542438 -0.07392 -0.00799131 -0.0263758 -0.07392 0.0177087 -0.0263758 -0.07392 0.0177087 -0.0288758 -0.0748351 0.0177087 -0.0254607 -0.0735851 0.0177087 -0.0276258 -0.0736602 0.0180087 -0.0262258 -0.0732851 0.0180087 -0.0276258 -0.0748351 0.0177087 -0.0297908 -0.0736602 0.0180087 -0.0290258 -0.0760851 0.0180087 -0.0304258 -0.027624 -0.00799131 -0.0735869 -0.0254349 -0.00829131 -0.0743411 -0.0256694 -0.00799131 -0.0745282 -0.025459 -0.00799131 -0.0748369 -0.0251867 -0.00799131 -0.0755306 -0.0251867 -0.00799131 -0.0766432 -0.0254349 -0.00829131 -0.0778326 -0.0256694 -0.00799131 -0.0776456 -0.0265393 -0.00799131 -0.0783393 -0.026374 -0.00799131 -0.0782519 -0.050827 -0.00799131 -0.0598039 -0.0501224 -0.00799131 -0.0604102 -0.049277 -0.00829131 -0.061969 -0.0496396 -0.00799131 -0.0625253 -0.050827 -0.00799131 -0.064134 -0.0496521 -0.00829131 -0.063369 -0.0499119 -0.00799131 -0.063219 -0.0608825 -0.00799131 -0.0498263 -0.0607523 -0.00829131 -0.049556 -0.0607172 -0.00799131 -0.0499137 -0.0597781 -0.00829131 -0.050333 -0.0592374 -0.00829131 -0.0514557 -0.0595299 -0.00799131 -0.0515224 -0.0592374 -0.00829131 -0.0527018 -0.0595299 -0.00799131 -0.052635 -0.0598021 -0.00799131 -0.0533287 -0.0607523 -0.00829131 -0.0546014 -0.0608825 -0.00799131 -0.0543311 -0.0760851 -0.00799131 -0.0301258 -0.0746851 -0.00829131 -0.0300507 -0.0748351 -0.00799131 -0.0297908 -0.0736602 -0.00829131 -0.0290258 -0.07392 -0.00799131 -0.0288758 -0.0732851 -0.00829131 -0.0276258 -0.0735851 -0.00799131 -0.0276258 -0.0748351 -0.00799131 -0.0254607 -0.0231123 0.00570869 -0.0769393 -0.0229472 0.00570869 -0.0781893 -0.0226792 0.00570869 -0.0791893 -0.0219472 0.00570869 -0.0799213 -0.0231123 0.00570869 -0.0794393 -0.0221972 0.00570869 -0.0803543 -0.0209472 0.00570869 -0.0761893 -0.0196972 0.00570869 -0.0760242 -0.0219472 0.00570869 -0.0764572 -0.0209472 0.00570869 -0.0756893 -0.0196972 0.00570869 -0.0803543 -0.0209472 -0.00799131 -0.0806893 -0.0187821 0.00570869 -0.0794393 -0.0184472 0.00570869 -0.0781893 -0.0187821 0.00570869 -0.0769393 -0.0209472 -0.00799131 -0.0756893 -0.0209472 -0.00829131 -0.0809893 -0.0196972 -0.00799131 -0.0803543 -0.0195472 -0.00829131 -0.0806141 -0.0187821 -0.00799131 -0.0794393 -0.0184472 -0.00799131 -0.0781893 -0.0187821 -0.00799131 -0.0769393 -0.0185223 -0.00829131 -0.0767893 -0.0196972 -0.00799131 -0.0760242 -0.0572361 0.00570869 -0.0547379 -0.0594011 0.00570869 -0.0559879 -0.0597361 0.00570869 -0.0572379 -0.0594011 0.00570869 -0.0584879 -0.0589681 0.00570869 -0.0582379 -0.0582361 0.00570869 -0.0589699 -0.0584861 0.00570869 -0.0594029 -0.0552862 0.00570869 -0.0576829 -0.0547988 0.00570869 -0.0577942 -0.0552815 0.00570869 -0.0556791 -0.0556724 0.00570869 -0.0559909 -0.0572361 0.00570869 -0.0597379 -0.0561514 0.00570869 -0.0594903 -0.0552815 0.00570869 -0.0587966 -0.0547988 -0.00799131 -0.0577942 -0.0547361 -0.00799131 -0.0572379 -0.0547988 -0.00799131 -0.0566816 -0.0547988 0.00570869 -0.0566816 -0.0552815 -0.00799131 -0.0556791 -0.0559861 -0.00799131 -0.0550728 -0.0561514 0.00570869 -0.0549854 -0.0572361 -0.00799131 -0.0547379 -0.055071 -0.00799131 -0.0559879 -0.0544361 -0.00829131 -0.0572379 -0.0559861 -0.00799131 -0.0594029 -0.0558361 -0.00829131 -0.0596627 -0.0548112 -0.00829131 -0.0586379 -0.0552815 -0.00799131 -0.0587966 -0.055071 -0.00799131 -0.0584879 -0.0801875 0.00570869 -0.020949 -0.0806875 0.00570869 -0.020949 -0.0791875 0.00570869 -0.022681 -0.0771875 0.00570869 -0.022681 -0.0764554 0.00570869 -0.021949 -0.0760224 0.00570869 -0.022199 -0.0764554 0.00570869 -0.019949 -0.0760224 0.00570869 -0.019699 -0.0769375 0.00570869 -0.0187839 -0.0781875 0.00570869 -0.018949 -0.0794375 0.00570869 -0.0187839 -0.0769375 0.00570869 -0.023114 -0.0769375 -0.00799131 -0.023114 -0.0760224 -0.00799131 -0.022199 -0.0756875 0.00570869 -0.020949 -0.0756875 -0.00799131 -0.020949 -0.0781875 0.00570869 -0.018449 -0.0769375 -0.00799131 -0.0187839 -0.0753875 -0.00829131 -0.020949 -0.0760224 -0.00799131 -0.019699 -0.0757626 -0.00829131 -0.019549 -0.0781875 -0.00799131 -0.018449 -0.0199472 0.00570869 -0.0764572 -0.0192151 0.00570869 -0.0771893 -0.0199699 0.00645869 -0.0774099 -0.0198647 0.00645869 -0.0775643 -0.0197285 0.00645869 -0.0784674 -0.0189472 0.00570869 -0.0781893 -0.0203222 0.00645869 -0.0792718 -0.0209472 0.00570869 -0.0801893 -0.0199472 0.00570869 -0.0799213 -0.0199699 0.00645869 -0.0789686 -0.0192151 0.00570869 -0.0791893 -0.0209472 0.00645869 -0.0769393 -0.0209472 0.0172587 -0.0769393 -0.0204048 0.0172587 -0.077063 -0.0203222 0.00645869 -0.0771067 -0.0197285 0.00645869 -0.0779111 -0.0197285 0.0172587 -0.0779111 -0.0196972 0.00645869 -0.0781893 -0.0198647 0.00645869 -0.0788143 -0.0199699 0.0172587 -0.0774099 -0.0200794 0.0180087 -0.0763873 -0.0193835 0.0180087 -0.0769423 -0.0189973 0.0180087 -0.0786343 -0.0197285 0.0172587 -0.0784674 -0.0193835 0.0180087 -0.0794362 -0.0199699 0.0172587 -0.0789686 -0.0204048 0.0172587 -0.0793155 -0.0572361 0.00645869 -0.0559879 -0.0563683 0.00570869 -0.0554359 -0.0566111 0.00645869 -0.0561553 -0.0562588 0.00645869 -0.0564585 -0.0552862 0.00570869 -0.0567928 -0.0559861 0.00645869 -0.0572379 -0.0560174 0.00645869 -0.057516 -0.0556724 0.00570869 -0.0584848 -0.0563683 0.00570869 -0.0590398 -0.0566937 0.00645869 -0.0583641 -0.0572361 0.0172587 -0.0559879 -0.0566937 0.00645869 -0.0561116 -0.0566111 0.0172587 -0.0561553 -0.0561536 0.00645869 -0.0566129 -0.0561536 0.0172587 -0.0566129 -0.0560174 0.00645869 -0.0569597 -0.0561536 0.00645869 -0.0578629 -0.0562588 0.00645869 -0.0580172 -0.0561536 0.0172587 -0.0578629 -0.0566111 0.00645869 -0.0583204 -0.0566111 0.0172587 -0.0583204 -0.055504 0.0180087 -0.0562379 -0.0559861 0.0172587 -0.0572379 -0.055504 0.0180087 -0.0582379 -0.0781875 0.00645869 -0.022199 -0.0781875 0.00570869 -0.022949 -0.0761875 0.00570869 -0.020949 -0.0771875 0.00570869 -0.0192169 -0.0781875 0.0172587 -0.019699 -0.0775625 0.00645869 -0.0198664 -0.0775625 0.0172587 -0.0198664 -0.077105 0.00645869 -0.020324 -0.0769375 0.00645869 -0.020949 -0.077105 0.00645869 -0.021574 -0.0775625 0.00645869 -0.0220315 -0.0781875 0.0180087 -0.018949 -0.077105 0.0172587 -0.020324 -0.0764554 0.0180087 -0.019949 -0.0769375 0.0172587 -0.020949 -0.077105 0.0172587 -0.021574 -0.0764554 0.0180087 -0.021949 -0.0775625 0.0172587 -0.0220315 -0.0771875 0.0180087 -0.022681 -0.0781875 0.0180087 -0.022949 0.0520042 -0.0124588 -0.0111226 0.0520042 -0.0141663 0.0106699 0.0520042 -0.0159663 0.00872946 0.0520042 -0.0122913 0.0117524 0.0520042 -0.00829131 -0.00989826 0.0520042 -0.00829131 0.00990314 0.0520042 -0.0111163 0.00872946 0.0520042 -0.00914527 -0.00647704 0.0520042 -0.0146238 0.0123774 0.0520042 -0.0124588 0.0111274 0.0520042 -0.0134413 0.00935244 0.0520042 -0.0136413 0.00935244 0.0520042 -0.0197913 -0.013414 0.0520042 -0.0135413 -0.0129976 0.0520042 -0.0124588 -0.0123726 0.0520042 -0.0141663 0.012835 0.0520042 -0.00829131 0.0134188 0.0520042 -0.0129163 0.012835 0.0520042 -0.0176683 0.00702744 0.0520042 -0.0135413 -0.0104976 0.0520042 -0.0134413 -0.00934756 0.0520042 -0.0136413 -0.00934756 0.0520042 -0.0141663 -0.010665 0.0520042 -0.0159663 -0.00872458 0.0420042 -0.0141663 0.0106699 0.0420042 -0.0135413 0.0130024 0.0520042 -0.0135413 0.0130024 0.0420042 -0.0141663 0.012835 0.0420042 -0.0146238 0.0123774 0.0420042 -0.0147913 0.0117524 0.0420042 -0.0146238 0.0111274 0.0520042 -0.0147913 0.0117524 0.0520042 -0.0146238 0.0111274 0.0520042 -0.0135413 0.0105024 0.0420042 -0.0135413 -0.0129976 0.0420042 -0.0146238 -0.0123726 0.0420042 -0.0141663 -0.0128301 0.0420042 -0.0135413 -0.0104976 0.0420042 -0.0141663 -0.010665 0.0420042 -0.0146238 -0.0111226 0.0520042 -0.0146238 -0.0111226 0.0420042 -0.0147913 -0.0117476 0.0520042 -0.0147913 -0.0117476 0.0520042 -0.0146238 -0.0123726 0.0520042 -0.0141663 -0.0128301 -0.0519958 -0.00829131 0.0134188 -0.0519958 -0.0122913 0.0117524 -0.0519958 -0.0124588 0.0123774 -0.0519958 -0.0141663 0.012835 -0.0519958 -0.0101533 -0.00798561 -0.0519958 -0.0094143 0.00702744 -0.0519958 -0.0134413 0.00935244 -0.0519958 -0.00829131 -0.013414 -0.0519958 -0.0135413 -0.0129976 -0.0519958 -0.0124588 -0.0123726 -0.0519958 -0.0116618 -0.0089936 -0.0519958 -0.0136413 -0.00934756 -0.0519958 -0.0135413 -0.0104976 -0.0519958 -0.0147913 0.0117524 -0.0519958 -0.0159663 -0.00872458 -0.0519958 -0.0141663 -0.010665 -0.0519958 -0.00829131 0.00990314 -0.0519958 -0.0197913 -0.013414 -0.0519958 -0.0197913 0.0134188 -0.0519958 -0.0146238 0.0111274 -0.0519958 -0.0159663 0.00872946 -0.0519958 -0.0136413 0.00935244 -0.0519958 -0.0129163 0.0106699 -0.0419958 -0.0147913 0.0117524 -0.0419958 -0.0141663 0.0106699 -0.0419958 -0.0146238 0.0111274 -0.0412447 -0.0135413 0.0117524 -0.0419958 -0.0141663 0.012835 -0.0419958 -0.0146238 0.0123774 -0.0519958 -0.0141663 0.0106699 -0.0519958 -0.0146238 0.0123774 -0.0519958 -0.0135413 0.0130024 -0.0412447 -0.0135413 -0.0117476 -0.0419958 -0.0146238 -0.0123726 -0.0419958 -0.0147913 -0.0117476 -0.0419958 -0.0141663 -0.0128301 -0.0419958 -0.0146238 -0.0111226 -0.0519958 -0.0141663 -0.0128301 -0.0519958 -0.0146238 -0.0123726 -0.0519958 -0.0147913 -0.0117476 -0.0519958 -0.0146238 -0.0111226 -0.0419958 -0.0141663 -0.010665 -0.051648 -0.0197913 0.0157521 -0.051648 -0.0197913 -0.0157473 0.0520042 -0.0197913 0.0134188 0.0516564 -0.00829131 0.0157521 0.0516564 -0.0197913 -0.0157473 0.0773413 0.0160087 0.0339256 0.0621361 0.0160087 0.0571989 0.0709541 0.0160087 0.0463563 0.0623568 0.0160087 0.0574021 0.0518745 0.0160087 0.0666454 0.0274251 0.0160087 0.0798767 0.0275225 0.0160087 0.0801605 0.0139536 0.0160087 0.0835966 0.0139042 0.0160087 0.0833007 4.20971e-06 0.0160087 0.0847524 -0.0518661 0.0160087 0.0666454 -0.0623484 0.0160087 0.0574021 -0.0706945 0.0160087 0.0461922 -0.0709457 0.0160087 0.0463563 -0.0818616 0.0160087 0.0207337 -0.0821525 0.0160087 0.0208073 -0.0841573 0.0160087 0.00697627 -0.0818616 0.0160087 -0.0207288 -0.0821525 0.0160087 -0.0208025 -0.0773328 0.0160087 -0.0339207 -0.0621277 0.0160087 -0.057194 -0.0518661 0.0160087 -0.0666405 -0.0138958 0.0160087 -0.0832958 4.20971e-06 0.0160087 -0.0844476 -0.0139452 0.0160087 -0.0835917 4.20971e-06 0.0160087 -0.0847476 0.0274251 0.0160087 -0.0798718 0.0275225 0.0160087 -0.0801556 0.0518745 0.0160087 -0.0666405 0.0621361 0.0160087 -0.057194 0.0623568 0.0160087 -0.0573972 0.0773413 0.0160087 -0.0339207 0.077616 0.0160087 -0.0340412 0.0818701 0.0160087 -0.0207288 0.0841658 0.0160087 0.00697627 4.20971e-06 0.0150087 0.0844524 -0.0138958 0.0160087 0.0833007 -0.0274167 0.0160087 0.0798767 -0.0401895 0.0160087 0.074274 -0.0274167 0.0150087 0.0798767 -0.0401895 0.0150087 0.074274 -0.0518661 0.0150087 0.0666454 -0.0621277 0.0160087 0.0571989 -0.0621277 0.0150087 0.0571989 -0.0706945 0.0150087 0.0461922 -0.0773328 0.0160087 0.0339256 -0.0841573 0.0150087 0.00697627 -0.0841573 0.0160087 -0.00697138 -0.0841573 0.0150087 -0.00697138 -0.0773328 0.0150087 -0.0339207 -0.0706945 0.0150087 -0.0461873 -0.0706945 0.0160087 -0.0461873 -0.0621277 0.0150087 -0.057194 -0.0518661 0.0150087 -0.0666405 -0.0401895 0.0160087 -0.0742691 -0.0401895 0.0150087 -0.0742691 -0.0274167 0.0160087 -0.0798718 -0.0274167 0.0150087 -0.0798718 -0.0138958 0.0150087 -0.0832958 -0.0520503 0.0150087 0.0668821 -0.0403323 0.0150087 0.0745378 -0.0138958 0.0150087 0.0833007 -0.0139452 0.0150087 0.0835966 4.20971e-06 0.0150087 0.0847524 0.0139042 0.0150087 0.0833007 0.0275225 0.0150087 0.0801605 0.0623568 0.0150087 0.0574021 0.0707029 0.0150087 0.0461922 0.0773413 0.0150087 0.0339256 0.0841658 0.0150087 -0.00697138 0.0844647 0.0150087 0.00700104 0.0818701 0.0150087 -0.0207288 0.0709541 0.0150087 -0.0463514 0.0623568 0.0150087 -0.0573972 0.0403408 0.0150087 -0.074533 0.040198 0.0150087 -0.0742691 0.0274251 0.0150087 -0.0798718 0.0139536 0.0150087 -0.0835917 4.20971e-06 0.0150087 -0.0844476 -0.0139452 0.0150087 -0.0835917 -0.0403323 0.0150087 -0.074533 -0.0709457 0.0150087 -0.0463514 -0.0818616 0.0150087 -0.0207288 -0.0844563 0.0150087 0.00700104 -0.0818616 0.0150087 0.0207337 -0.0773328 0.0150087 0.0339256 -0.0623484 0.0150087 0.0574021 -0.0139781 0.0162087 0.0837938 -0.0139452 0.0160087 0.0835966 -0.027579 0.0162087 0.0803496 -0.0275141 0.0160087 0.0801605 -0.0521732 0.0162087 0.0670399 -0.0403323 0.0160087 0.0745378 -0.0520503 0.0160087 0.0668821 -0.0776076 0.0160087 0.0340461 -0.0777907 0.0162087 0.0341265 -0.0823463 0.0162087 0.0208564 -0.0844563 0.0160087 0.00700104 -0.0846556 0.0162087 0.00701756 -0.0844563 0.0160087 -0.00699616 -0.0823463 0.0162087 -0.0208516 -0.0776076 0.0160087 -0.0340412 -0.0709457 0.0160087 -0.0463514 -0.0623484 0.0160087 -0.0573972 -0.0624955 0.0162087 -0.0575326 -0.0521732 0.0162087 -0.067035 -0.0520503 0.0160087 -0.0668772 -0.0404275 0.0162087 -0.0747089 -0.0403323 0.0160087 -0.074533 -0.027579 0.0162087 -0.0803447 -0.0275141 0.0160087 -0.0801556 -0.0139781 0.0162087 -0.083789 4.20971e-06 0.0148087 -0.0849476 4.20971e-06 0.0150087 -0.0847476 -0.0139781 0.0148087 -0.083789 -0.0275141 0.0150087 -0.0801556 -0.0520503 0.0150087 -0.0668772 -0.0623484 0.0150087 -0.0573972 -0.0777907 0.0148087 -0.0341216 -0.0823463 0.0148087 -0.0208516 -0.0776076 0.0150087 -0.0340412 -0.0821525 0.0150087 -0.0208025 -0.0846556 0.0148087 -0.00701267 -0.0844563 0.0150087 -0.00699616 -0.0823463 0.0148087 0.0208564 -0.0821525 0.0150087 0.0208073 -0.0776076 0.0150087 0.0340461 -0.0709457 0.0150087 0.0463563 -0.0711131 0.0148087 0.0464657 -0.0521732 0.0148087 0.0670399 -0.0404275 0.0148087 0.0747137 -0.0275141 0.0150087 0.0801605 -0.0623484 0.0135087 -0.0573972 -0.0520503 0.0135087 -0.0668772 -0.0403323 0.0135087 -0.074533 -0.0401895 0.0135087 -0.0742691 -0.0274167 0.0135087 -0.0798718 -0.0138958 0.0135087 -0.0832958 4.20971e-06 0.0135087 -0.0844476 4.20971e-06 0.0135087 -0.0847476 0.0139042 0.0135087 -0.0832958 0.0274251 0.0135087 -0.0798718 0.040198 0.0135087 -0.0742691 0.0520587 0.0135087 -0.0668772 0.0621361 0.0135087 -0.057194 0.0707029 0.0135087 -0.0461873 0.077616 0.0135087 -0.0340412 0.0821609 0.0135087 -0.0208025 0.0844647 0.0135087 -0.00699616 0.0841658 0.0135087 0.00697627 0.0844647 0.0135087 0.00700104 0.0821609 0.0135087 0.0208073 0.0773413 0.0135087 0.0339256 0.0707029 0.0135087 0.0461922 0.0709541 0.0135087 0.0463563 0.0621361 0.0135087 0.0571989 0.040198 0.0135087 0.074274 0.0403408 0.0135087 0.0745378 0.0274251 0.0135087 0.0798767 0.0275225 0.0135087 0.0801605 0.0139536 0.0135087 0.0835966 4.20971e-06 0.0135087 0.0844524 -0.0401895 0.0135087 0.074274 -0.0518661 0.0135087 0.0666454 -0.0621277 0.0135087 0.0571989 -0.0623484 0.0135087 0.0574021 -0.0706945 0.0135087 0.0461922 -0.0773328 0.0135087 0.0339256 -0.0776076 0.0135087 0.0340461 -0.0821525 0.0135087 0.0208073 -0.0818616 0.0135087 0.0207337 -0.0841573 0.0135087 0.00697627 -0.0818616 0.0135087 -0.0207288 -0.0773328 0.0135087 -0.0339207 -0.0776076 0.0135087 -0.0340412 -0.0621277 0.0135087 -0.057194 -0.0138958 0.0125087 0.0833007 -0.0138958 0.0135087 0.0833007 -0.0274167 0.0125087 0.0798767 -0.0274167 0.0135087 0.0798767 -0.0401895 0.0125087 0.074274 -0.0518661 0.0125087 0.0666454 -0.0621277 0.0125087 0.0571989 -0.0841573 0.0125087 0.00697627 -0.0841573 0.0125087 -0.00697138 -0.0841573 0.0135087 -0.00697138 -0.0706945 0.0135087 -0.0461873 -0.0706945 0.0125087 -0.0461873 -0.0518661 0.0135087 -0.0666405 -0.0518661 0.0125087 -0.0666405 -0.0401895 0.0125087 -0.0742691 -0.0139452 0.0125087 0.0835966 4.20971e-06 0.0125087 0.0844524 4.20971e-06 0.0125087 0.0847524 0.0139536 0.0125087 0.0835966 0.0274251 0.0125087 0.0798767 0.040198 0.0125087 0.074274 0.0403408 0.0125087 0.0745378 0.0518745 0.0125087 0.0666454 0.0621361 0.0125087 0.0571989 0.0623568 0.0125087 0.0574021 0.0773413 0.0125087 0.0339256 0.0821609 0.0125087 0.0208073 0.0841658 0.0125087 0.00697627 0.0844647 0.0125087 0.00700104 0.0818701 0.0125087 -0.0207288 0.0773413 0.0125087 -0.0339207 0.0821609 0.0125087 -0.0208025 0.0707029 0.0125087 -0.0461873 0.0623568 0.0125087 -0.0573972 0.0518745 0.0125087 -0.0666405 0.0274251 0.0125087 -0.0798718 0.0139042 0.0125087 -0.0832958 4.20971e-06 0.0125087 -0.0844476 0.0139536 0.0125087 -0.0835917 -0.0138958 0.0125087 -0.0832958 -0.0274167 0.0125087 -0.0798718 -0.0139452 0.0125087 -0.0835917 -0.0403323 0.0125087 -0.074533 -0.0621277 0.0125087 -0.057194 -0.0520503 0.0125087 -0.0668772 -0.0709457 0.0125087 -0.0463514 -0.0773328 0.0125087 -0.0339207 -0.0776076 0.0125087 -0.0340412 -0.0818616 0.0125087 -0.0207288 -0.0821525 0.0125087 -0.0208025 -0.0818616 0.0125087 0.0207337 -0.0776076 0.0125087 0.0340461 -0.0773328 0.0125087 0.0339256 -0.0706945 0.0125087 0.0461922 -0.0623484 0.0125087 0.0574021 -0.0518661 0.0110087 -0.0666405 -0.0403323 0.0110087 -0.074533 -0.0138958 0.0110087 -0.0832958 -0.0275141 0.0110087 -0.0801556 4.20971e-06 0.0110087 -0.0847476 0.040198 0.0110087 -0.0742691 0.0403408 0.0110087 -0.074533 0.0518745 0.0110087 -0.0666405 0.0621361 0.0110087 -0.057194 0.0520587 0.0110087 -0.0668772 0.0773413 0.0110087 -0.0339207 0.0841658 0.0110087 -0.00697138 0.0844647 0.0110087 -0.00699616 0.0841658 0.0110087 0.00697627 0.0821609 0.0110087 0.0208073 0.0773413 0.0110087 0.0339256 0.077616 0.0110087 0.0340461 0.0707029 0.0110087 0.0461922 0.0621361 0.0110087 0.0571989 0.0518745 0.0110087 0.0666454 0.040198 0.0110087 0.074274 0.0520587 0.0110087 0.0668821 0.0274251 0.0110087 0.0798767 0.0403408 0.0110087 0.0745378 0.0275225 0.0110087 0.0801605 0.0139042 0.0110087 0.0833007 0.0139536 0.0110087 0.0835966 4.20971e-06 0.0110087 0.0844524 4.20971e-06 0.0110087 0.0847524 -0.0138958 0.0110087 0.0833007 -0.0403323 0.0110087 0.0745378 -0.0401895 0.0110087 0.074274 -0.0518661 0.0110087 0.0666454 -0.0621277 0.0110087 0.0571989 -0.0623484 0.0110087 0.0574021 -0.0773328 0.0110087 0.0339256 -0.0709457 0.0110087 0.0463563 -0.0776076 0.0110087 0.0340461 -0.0841573 0.0110087 0.00697627 -0.0844563 0.0110087 0.00700104 -0.0844563 0.0110087 -0.00699616 -0.0821525 0.0110087 -0.0208025 -0.0773328 0.0110087 -0.0339207 -0.0776076 0.0110087 -0.0340412 -0.0621277 0.0110087 -0.057194 4.20971e-06 0.0100087 0.0844524 -0.0138958 0.0100087 0.0833007 -0.0274167 0.0110087 0.0798767 -0.0518661 0.0100087 0.0666454 -0.0706945 0.0110087 0.0461922 -0.0706945 0.0100087 0.0461922 -0.0818616 0.0100087 0.0207337 -0.0818616 0.0110087 0.0207337 -0.0841573 0.0110087 -0.00697138 -0.0818616 0.0110087 -0.0207288 -0.0773328 0.0100087 -0.0339207 -0.0706945 0.0110087 -0.0461873 -0.0621277 0.0100087 -0.057194 -0.0401895 0.0110087 -0.0742691 -0.0401895 0.0100087 -0.0742691 -0.0274167 0.0110087 -0.0798718 -0.0274167 0.0100087 -0.0798718 4.20971e-06 0.0110087 -0.0844476 -0.0623484 0.0100087 0.0574021 -0.0520503 0.0100087 0.0668821 -0.0401895 0.0100087 0.074274 -0.0274167 0.0100087 0.0798767 -0.0275141 0.0100087 0.0801605 0.0139042 0.0100087 0.0833007 0.0274251 0.0100087 0.0798767 0.0518745 0.0100087 0.0666454 0.0621361 0.0100087 0.0571989 0.0623568 0.0100087 0.0574021 0.0773413 0.0100087 0.0339256 0.077616 0.0100087 0.0340461 0.0844647 0.0100087 0.00700104 0.0818701 0.0100087 -0.0207288 0.0844647 0.0100087 -0.00699616 0.0707029 0.0100087 -0.0461873 0.0709541 0.0100087 -0.0463514 0.0623568 0.0100087 -0.0573972 0.0621361 0.0100087 -0.057194 0.040198 0.0100087 -0.0742691 0.0274251 0.0100087 -0.0798718 0.0403408 0.0100087 -0.074533 0.0139042 0.0100087 -0.0832958 4.20971e-06 0.0100087 -0.0847476 -0.0138958 0.0100087 -0.0832958 -0.0275141 0.0100087 -0.0801556 -0.0518661 0.0100087 -0.0666405 -0.0520503 0.0100087 -0.0668772 -0.0706945 0.0100087 -0.0461873 -0.0709457 0.0100087 -0.0463514 -0.0818616 0.0100087 -0.0207288 -0.0841573 0.0100087 -0.00697138 -0.0841573 0.0100087 0.00697627 -0.0844563 0.0100087 0.00700104 -0.0773328 0.0100087 0.0339256 -0.0821525 0.0100087 0.0208073 -0.0776076 0.0100087 0.0340461 -0.0621277 0.0100087 0.0571989 -0.0621277 0.00850869 -0.057194 -0.0401895 0.00850869 -0.0742691 -0.0403323 0.00850869 -0.074533 -0.0275141 0.00850869 -0.0801556 -0.0138958 0.00850869 -0.0832958 -0.0139452 0.00850869 -0.0835917 0.0275225 0.00850869 -0.0801556 0.0403408 0.00850869 -0.074533 0.0518745 0.00850869 -0.0666405 0.0520587 0.00850869 -0.0668772 0.0707029 0.00850869 -0.0461873 0.077616 0.00850869 -0.0340412 0.0841658 0.00850869 -0.00697138 0.0844647 0.00850869 -0.00699616 0.0844647 0.00850869 0.00700104 0.0818701 0.00850869 0.0207337 0.0773413 0.00850869 0.0339256 0.077616 0.00850869 0.0340461 0.0709541 0.00850869 0.0463563 0.0623568 0.00850869 0.0574021 0.0518745 0.00850869 0.0666454 0.0520587 0.00850869 0.0668821 0.0403408 0.00850869 0.0745378 0.0139536 0.00850869 0.0835966 -0.0274167 0.00850869 0.0798767 -0.0275141 0.00850869 0.0801605 -0.0403323 0.00850869 0.0745378 -0.0520503 0.00850869 0.0668821 -0.0621277 0.00850869 0.0571989 -0.0623484 0.00850869 0.0574021 -0.0706945 0.00850869 0.0461922 -0.0773328 0.00850869 0.0339256 -0.0821525 0.00850869 0.0208073 -0.0844563 0.00850869 0.00700104 -0.0841573 0.00850869 0.00697627 -0.0844563 0.00850869 -0.00699616 -0.0821525 0.00850869 -0.0208025 -0.0706945 0.00850869 -0.0461873 -0.0709457 0.00850869 -0.0463514 -0.0623484 0.00850869 -0.0573972 4.20971e-06 0.00850869 0.0844524 -0.0138958 0.00850869 0.0833007 -0.0274167 0.00750869 0.0798767 -0.0401895 0.00850869 0.074274 -0.0518661 0.00850869 0.0666454 -0.0706945 0.00750869 0.0461922 -0.0773328 0.00750869 0.0339256 -0.0818616 0.00850869 0.0207337 -0.0841573 0.00850869 -0.00697138 -0.0841573 0.00750869 -0.00697138 -0.0818616 0.00850869 -0.0207288 -0.0773328 0.00850869 -0.0339207 -0.0773328 0.00750869 -0.0339207 -0.0706945 0.00750869 -0.0461873 -0.0621277 0.00750869 -0.057194 -0.0518661 0.00750869 -0.0666405 -0.0518661 0.00850869 -0.0666405 -0.0274167 0.00850869 -0.0798718 -0.0274167 0.00750869 -0.0798718 4.20971e-06 0.00750869 -0.0844476 -0.0518661 0.00750869 0.0666454 -0.0401895 0.00750869 0.074274 -0.0403323 0.00750869 0.0745378 -0.0275141 0.00750869 0.0801605 -0.0138958 0.00750869 0.0833007 4.20971e-06 0.00750869 0.0844524 4.20971e-06 0.00750869 0.0847524 0.0139536 0.00750869 0.0835966 0.0275225 0.00750869 0.0801605 0.0274251 0.00750869 0.0798767 0.0403408 0.00750869 0.0745378 0.0707029 0.00750869 0.0461922 0.0841658 0.00750869 0.00697627 0.0844647 0.00750869 -0.00699616 0.0403408 0.00750869 -0.074533 0.0275225 0.00750869 -0.0801556 0.0139536 0.00750869 -0.0835917 4.20971e-06 0.00750869 -0.0847476 -0.0138958 0.00750869 -0.0832958 -0.0275141 0.00750869 -0.0801556 -0.0401895 0.00750869 -0.0742691 -0.0709457 0.00750869 -0.0463514 -0.0818616 0.00750869 -0.0207288 -0.0776076 0.00750869 -0.0340412 -0.0821525 0.00750869 -0.0208025 -0.0844563 0.00750869 -0.00699616 -0.0841573 0.00750869 0.00697627 -0.0844563 0.00750869 0.00700104 -0.0818616 0.00750869 0.0207337 -0.0776076 0.00750869 0.0340461 -0.0621277 0.00750869 0.0571989 -0.0623484 0.00750869 0.0574021 -0.0520503 0.00600869 -0.0668772 -0.0401895 0.00600869 -0.0742691 -0.0274167 0.00600869 -0.0798718 -0.0139452 0.00600869 -0.0835917 4.20971e-06 0.00600869 -0.0844476 4.20971e-06 0.00600869 -0.0847476 0.0275225 0.00600869 -0.0801556 0.0274251 0.00600869 -0.0798718 0.040198 0.00600869 -0.0742691 0.0403408 0.00600869 -0.074533 0.0520587 0.00600869 -0.0668772 0.0623568 0.00600869 -0.0573972 0.0707029 0.00600869 -0.0461873 0.0773413 0.00600869 -0.0339207 0.0709541 0.00600869 -0.0463514 0.077616 0.00600869 -0.0340412 0.0821609 0.00600869 -0.0208025 0.0841658 0.00600869 -0.00697138 0.0773413 0.00600869 0.0339256 0.0821609 0.00600869 0.0208073 0.0707029 0.00600869 0.0461922 0.077616 0.00600869 0.0340461 0.0520587 0.00600869 0.0668821 0.0275225 0.00600869 0.0801605 0.0139536 0.00600869 0.0835966 4.20971e-06 0.00600869 0.0844524 -0.0274167 0.00600869 0.0798767 -0.0139452 0.00600869 0.0835966 -0.0275141 0.00600869 0.0801605 -0.0518661 0.00600869 0.0666454 -0.0621277 0.00600869 0.0571989 -0.0706945 0.00600869 0.0461922 -0.0709457 0.00600869 0.0463563 -0.0776076 0.00600869 0.0340461 -0.0818616 0.00600869 0.0207337 -0.0841573 0.00600869 0.00697627 -0.0844563 0.00600869 0.00700104 -0.0844563 0.00600869 -0.00699616 -0.0821525 0.00600869 -0.0208025 -0.0776076 0.00600869 -0.0340412 -0.0709457 0.00600869 -0.0463514 -0.0138958 0.00600869 0.0833007 -0.0274167 0.00500869 0.0798767 -0.0401895 0.00600869 0.074274 -0.0401895 0.00500869 0.074274 -0.0621277 0.00500869 0.0571989 -0.0773328 0.00600869 0.0339256 -0.0706945 0.00500869 0.0461922 -0.0773328 0.00500869 0.0339256 -0.0841573 0.00600869 -0.00697138 -0.0841573 0.00500869 -0.00697138 -0.0818616 0.00600869 -0.0207288 -0.0773328 0.00600869 -0.0339207 -0.0706945 0.00600869 -0.0461873 -0.0773328 0.00500869 -0.0339207 -0.0621277 0.00600869 -0.057194 -0.0621277 0.00500869 -0.057194 -0.0518661 0.00600869 -0.0666405 -0.0518661 0.00500869 -0.0666405 -0.0401895 0.00500869 -0.0742691 -0.0138958 0.00600869 -0.0832958 -0.0518661 0.00500869 0.0666454 -0.0403323 0.00500869 0.0745378 -0.0275141 0.00500869 0.0801605 -0.0138958 0.00500869 0.0833007 4.20971e-06 0.00500869 0.0847524 0.0139042 0.00500869 0.0833007 0.0518745 0.00500869 0.0666454 0.0621361 0.00500869 0.0571989 0.0707029 0.00500869 0.0461922 0.0709541 0.00500869 0.0463563 0.0773413 0.00500869 0.0339256 0.0841658 0.00500869 -0.00697138 0.0773413 0.00500869 -0.0339207 0.077616 0.00500869 -0.0340412 0.0707029 0.00500869 -0.0461873 0.0623568 0.00500869 -0.0573972 0.0518745 0.00500869 -0.0666405 0.0403408 0.00500869 -0.074533 0.0274251 0.00500869 -0.0798718 0.0139042 0.00500869 -0.0832958 4.20971e-06 0.00500869 -0.0844476 4.20971e-06 0.00500869 -0.0847476 -0.0138958 0.00500869 -0.0832958 -0.0275141 0.00500869 -0.0801556 -0.0274167 0.00500869 -0.0798718 -0.0520503 0.00500869 -0.0668772 -0.0706945 0.00500869 -0.0461873 -0.0818616 0.00500869 -0.0207288 -0.0841573 0.00500869 0.00697627 -0.0844563 0.00500869 0.00700104 -0.0818616 0.00500869 0.0207337 -0.0821525 0.00500869 0.0208073 -0.0776076 0.00500869 0.0340461 -0.0623484 0.00500869 0.0574021 -0.0621277 0.00350869 -0.057194 -0.0518661 0.00350869 -0.0666405 -0.0520503 0.00350869 -0.0668772 -0.0401895 0.00350869 -0.0742691 -0.0403323 0.00350869 -0.074533 4.20971e-06 0.00350869 -0.0844476 0.0274251 0.00350869 -0.0798718 0.0275225 0.00350869 -0.0801556 0.0403408 0.00350869 -0.074533 0.0520587 0.00350869 -0.0668772 0.0773413 0.00350869 -0.0339207 0.0821609 0.00350869 -0.0208025 0.0841658 0.00350869 -0.00697138 0.0818701 0.00350869 0.0207337 0.0773413 0.00350869 0.0339256 0.077616 0.00350869 0.0340461 0.0709541 0.00350869 0.0463563 0.0623568 0.00350869 0.0574021 0.040198 0.00350869 0.074274 0.0403408 0.00350869 0.0745378 0.0274251 0.00350869 0.0798767 0.0139042 0.00350869 0.0833007 0.0275225 0.00350869 0.0801605 4.20971e-06 0.00350869 0.0847524 -0.0401895 0.00350869 0.074274 -0.0403323 0.00350869 0.0745378 -0.0621277 0.00350869 0.0571989 -0.0706945 0.00350869 0.0461922 -0.0841573 0.00350869 0.00697627 -0.0818616 0.00350869 -0.0207288 -0.0821525 0.00350869 -0.0208025 -0.0773328 0.00350869 -0.0339207 4.20971e-06 0.00350869 0.0844524 -0.0138958 0.00350869 0.0833007 -0.0274167 0.00350869 0.0798767 -0.0138958 0.00250869 0.0833007 -0.0518661 0.00250869 0.0666454 -0.0518661 0.00350869 0.0666454 -0.0773328 0.00350869 0.0339256 -0.0773328 0.00250869 0.0339256 -0.0818616 0.00350869 0.0207337 -0.0841573 0.00250869 0.00697627 -0.0841573 0.00350869 -0.00697138 -0.0841573 0.00250869 -0.00697138 -0.0773328 0.00250869 -0.0339207 -0.0706945 0.00350869 -0.0461873 -0.0518661 0.00250869 -0.0666405 -0.0274167 0.00350869 -0.0798718 -0.0138958 0.00250869 -0.0832958 -0.0138958 0.00350869 -0.0832958 4.20971e-06 0.00250869 -0.0844476 -0.0621277 0.00250869 0.0571989 -0.0401895 0.00250869 0.074274 -0.0403323 0.00250869 0.0745378 -0.0274167 0.00250869 0.0798767 -0.0139452 0.00250869 0.0835966 4.20971e-06 0.00250869 0.0844524 4.20971e-06 0.00250869 0.0847524 0.0139042 0.00250869 0.0833007 0.0139536 0.00250869 0.0835966 0.0275225 0.00250869 0.0801605 0.0403408 0.00250869 0.0745378 0.0518745 0.00250869 0.0666454 0.0520587 0.00250869 0.0668821 0.0621361 0.00250869 0.0571989 0.0623568 0.00250869 0.0574021 0.0821609 0.00250869 0.0208073 0.0844647 0.00250869 -0.00699616 0.0821609 0.00250869 -0.0208025 0.0707029 0.00250869 -0.0461873 0.0623568 0.00250869 -0.0573972 0.0403408 0.00250869 -0.074533 0.0275225 0.00250869 -0.0801556 0.0139042 0.00250869 -0.0832958 4.20971e-06 0.00250869 -0.0847476 -0.0274167 0.00250869 -0.0798718 -0.0139452 0.00250869 -0.0835917 -0.0275141 0.00250869 -0.0801556 -0.0401895 0.00250869 -0.0742691 -0.0403323 0.00250869 -0.074533 -0.0520503 0.00250869 -0.0668772 -0.0621277 0.00250869 -0.057194 -0.0623484 0.00250869 -0.0573972 -0.0706945 0.00250869 -0.0461873 -0.0776076 0.00250869 -0.0340412 -0.0818616 0.00250869 -0.0207288 -0.0844563 0.00250869 -0.00699616 -0.0844563 0.00250869 0.00700104 -0.0818616 0.00250869 0.0207337 -0.0821525 0.00250869 0.0208073 -0.0776076 0.00250869 0.0340461 -0.0706945 0.00250869 0.0461922 -0.0518661 0.00100869 -0.0666405 -0.0623484 0.00100869 -0.0573972 -0.0520503 0.00100869 -0.0668772 -0.0274167 0.00100869 -0.0798718 -0.0139452 0.00100869 -0.0835917 4.20971e-06 0.00100869 -0.0847476 0.0623568 0.00100869 -0.0573972 0.0709541 0.00100869 -0.0463514 0.0821609 0.00100869 -0.0208025 0.0841658 0.00100869 0.00697627 0.0821609 0.00100869 0.0208073 0.0773413 0.00100869 0.0339256 0.0709541 0.00100869 0.0463563 0.0623568 0.00100869 0.0574021 0.0518745 0.00100869 0.0666454 0.040198 0.00100869 0.074274 0.0403408 0.00100869 0.0745378 0.0274251 0.00100869 0.0798767 0.0139042 0.00100869 0.0833007 4.20971e-06 0.00100869 0.0844524 4.20971e-06 0.00100869 0.0847524 -0.0138958 0.00100869 0.0833007 -0.0139452 0.00100869 0.0835966 -0.0275141 0.00100869 0.0801605 -0.0401895 0.00100869 0.074274 -0.0520503 0.00100869 0.0668821 -0.0621277 0.00100869 0.0571989 -0.0709457 0.00100869 0.0463563 -0.0776076 0.00100869 0.0340461 -0.0821525 0.00100869 0.0208073 -0.0818616 0.00100869 0.0207337 -0.0841573 0.00100869 0.00697627 -0.0844563 0.00100869 0.00700104 -0.0776076 0.00100869 -0.0340412 -0.0274167 0.00100869 0.0798767 -0.0274167 8.6865e-06 0.0798767 -0.0518661 0.00100869 0.0666454 -0.0518661 8.6865e-06 0.0666454 -0.0706945 0.00100869 0.0461922 -0.0773328 0.00100869 0.0339256 -0.0773328 8.6865e-06 0.0339256 -0.0841573 0.00100869 -0.00697138 -0.0818616 0.00100869 -0.0207288 -0.0773328 0.00100869 -0.0339207 -0.0706945 0.00100869 -0.0461873 -0.0621277 0.00100869 -0.057194 -0.0401895 0.00100869 -0.0742691 -0.0274167 8.6865e-06 -0.0798718 -0.0138958 0.00100869 -0.0832958 -0.0138958 8.6865e-06 -0.0832958 4.20971e-06 0.00100869 -0.0844476 -0.0401895 8.6865e-06 0.074274 -0.0138958 8.6865e-06 0.0833007 -0.0139452 8.6865e-06 0.0835966 4.20971e-06 8.6865e-06 0.0844524 0.0139042 8.6865e-06 0.0833007 0.0139536 8.6865e-06 0.0835966 0.0275225 8.6865e-06 0.0801605 0.040198 8.6865e-06 0.074274 0.0520587 8.6865e-06 0.0668821 0.0621361 8.6865e-06 0.0571989 0.0623568 8.6865e-06 0.0574021 0.0841658 8.6865e-06 0.00697627 0.0821609 8.6865e-06 0.0208073 0.0844647 8.6865e-06 0.00700104 0.0773413 8.6865e-06 -0.0339207 0.077616 8.6865e-06 -0.0340412 0.0707029 8.6865e-06 -0.0461873 0.0621361 8.6865e-06 -0.057194 0.0518745 8.6865e-06 -0.0666405 0.0403408 8.6865e-06 -0.074533 0.0139042 8.6865e-06 -0.0832958 0.0139536 8.6865e-06 -0.0835917 4.20971e-06 8.6865e-06 -0.0847476 -0.0401895 8.6865e-06 -0.0742691 -0.0275141 8.6865e-06 -0.0801556 -0.0403323 8.6865e-06 -0.074533 -0.0518661 8.6865e-06 -0.0666405 -0.0520503 8.6865e-06 -0.0668772 -0.0623484 8.6865e-06 -0.0573972 -0.0621277 8.6865e-06 -0.057194 -0.0706945 8.6865e-06 -0.0461873 -0.0709457 8.6865e-06 -0.0463514 -0.0773328 8.6865e-06 -0.0339207 -0.0818616 8.6865e-06 -0.0207288 -0.0821525 8.6865e-06 -0.0208025 -0.0841573 8.6865e-06 -0.00697138 -0.0844563 8.6865e-06 -0.00699616 -0.0841573 8.6865e-06 0.00697627 -0.0818616 8.6865e-06 0.0207337 -0.0706945 8.6865e-06 0.0461922 -0.0621277 8.6865e-06 0.0571989 -0.0621277 -0.00149131 -0.057194 -0.0520503 -0.00149131 -0.0668772 -0.0274167 -0.00149131 -0.0798718 4.20971e-06 -0.00149131 -0.0847476 0.0403408 -0.00149131 -0.074533 0.0621361 -0.00149131 -0.057194 0.0520587 -0.00149131 -0.0668772 0.0707029 -0.00149131 -0.0461873 0.077616 -0.00149131 -0.0340412 0.0818701 -0.00149131 -0.0207288 0.0844647 -0.00149131 0.00700104 0.0841658 -0.00149131 0.00697627 0.0709541 -0.00149131 0.0463563 0.0623568 -0.00149131 0.0574021 0.0520587 -0.00149131 0.0668821 0.0139042 -0.00149131 0.0833007 0.0275225 -0.00149131 0.0801605 -0.0138958 -0.00149131 0.0833007 -0.0274167 -0.00149131 0.0798767 -0.0401895 -0.00149131 0.074274 -0.0403323 -0.00149131 0.0745378 -0.0520503 -0.00149131 0.0668821 -0.0621277 -0.00149131 0.0571989 -0.0706945 -0.00149131 0.0461922 -0.0773328 -0.00149131 0.0339256 -0.0841573 -0.00149131 0.00697627 -0.0841573 -0.00149131 -0.00697138 -0.0844563 -0.00149131 0.00700104 -0.0844563 -0.00149131 -0.00699616 -0.0818616 -0.00149131 -0.0207288 -0.0709457 -0.00149131 -0.0463514 -0.0518661 -0.00149131 0.0666454 -0.0773328 -0.00249131 0.0339256 -0.0818616 -0.00149131 0.0207337 -0.0773328 -0.00149131 -0.0339207 -0.0706945 -0.00149131 -0.0461873 -0.0706945 -0.00249131 -0.0461873 -0.0518661 -0.00149131 -0.0666405 -0.0518661 -0.00249131 -0.0666405 -0.0401895 -0.00149131 -0.0742691 -0.0274167 -0.00249131 -0.0798718 -0.0138958 -0.00149131 -0.0832958 4.20971e-06 -0.00149131 -0.0844476 -0.0621277 -0.00249131 0.0571989 -0.0518661 -0.00249131 0.0666454 -0.0401895 -0.00249131 0.074274 -0.0274167 -0.00249131 0.0798767 -0.0275141 -0.00249131 0.0801605 -0.0138958 -0.00249131 0.0833007 -0.0139452 -0.00249131 0.0835966 4.20971e-06 -0.00249131 0.0844524 0.0139042 -0.00249131 0.0833007 0.0274251 -0.00249131 0.0798767 0.0139536 -0.00249131 0.0835966 0.0275225 -0.00249131 0.0801605 0.0621361 -0.00249131 0.0571989 0.0773413 -0.00249131 0.0339256 0.0709541 -0.00249131 0.0463563 0.0818701 -0.00249131 0.0207337 0.0841658 -0.00249131 0.00697627 0.0821609 -0.00249131 0.0208073 0.0844647 -0.00249131 0.00700104 0.0818701 -0.00249131 -0.0207288 0.0773413 -0.00249131 -0.0339207 0.0621361 -0.00249131 -0.057194 0.0623568 -0.00249131 -0.0573972 0.0520587 -0.00249131 -0.0668772 0.040198 -0.00249131 -0.0742691 -0.0138958 -0.00249131 -0.0832958 -0.0139452 -0.00249131 -0.0835917 -0.0401895 -0.00249131 -0.0742691 -0.0403323 -0.00249131 -0.074533 -0.0621277 -0.00249131 -0.057194 -0.0709457 -0.00249131 -0.0463514 -0.0773328 -0.00249131 -0.0339207 -0.0818616 -0.00249131 -0.0207288 -0.0821525 -0.00249131 -0.0208025 -0.0841573 -0.00249131 -0.00697138 -0.0841573 -0.00249131 0.00697627 -0.0818616 -0.00249131 0.0207337 -0.0706945 -0.00249131 0.0461922 -0.0275141 -0.00399131 -0.0801556 0.0139042 -0.00399131 -0.0832958 0.0275225 -0.00399131 -0.0801556 0.0403408 -0.00399131 -0.074533 0.0520587 -0.00399131 -0.0668772 0.0623568 -0.00399131 -0.0573972 0.0707029 -0.00399131 -0.0461873 0.0709541 -0.00399131 -0.0463514 0.0773413 -0.00399131 -0.0339207 0.0818701 -0.00399131 -0.0207288 0.0841658 -0.00399131 -0.00697138 0.0841658 -0.00399131 0.00697627 0.0844647 -0.00399131 -0.00699616 0.0844647 -0.00399131 0.00700104 0.077616 -0.00399131 0.0340461 0.0707029 -0.00399131 0.0461922 0.0709541 -0.00399131 0.0463563 0.0621361 -0.00399131 0.0571989 0.0623568 -0.00399131 0.0574021 0.040198 -0.00399131 0.074274 0.0139536 -0.00399131 0.0835966 -0.0138958 -0.00399131 0.0833007 4.20971e-06 -0.00399131 0.0847524 -0.0274167 -0.00399131 0.0798767 -0.0275141 -0.00399131 0.0801605 -0.0401895 -0.00399131 0.074274 -0.0403323 -0.00399131 0.0745378 -0.0518661 -0.00399131 0.0666454 -0.0773328 -0.00399131 0.0339256 -0.0776076 -0.00399131 0.0340461 -0.0841573 -0.00399131 0.00697627 -0.0844563 -0.00399131 0.00700104 -0.0821525 -0.00399131 -0.0208025 -0.0773328 -0.00399131 -0.0339207 -0.0623484 -0.00399131 -0.0573972 4.20971e-06 -0.00499131 0.0844524 -0.0138958 -0.00499131 0.0833007 -0.0274167 -0.00499131 0.0798767 -0.0401895 -0.00499131 0.074274 -0.0621277 -0.00499131 0.0571989 -0.0621277 -0.00399131 0.0571989 -0.0706945 -0.00399131 0.0461922 -0.0773328 -0.00499131 0.0339256 -0.0818616 -0.00499131 0.0207337 -0.0818616 -0.00399131 0.0207337 -0.0841573 -0.00499131 0.00697627 -0.0841573 -0.00399131 -0.00697138 -0.0841573 -0.00499131 -0.00697138 -0.0818616 -0.00499131 -0.0207288 -0.0818616 -0.00399131 -0.0207288 -0.0706945 -0.00399131 -0.0461873 -0.0621277 -0.00399131 -0.057194 -0.0621277 -0.00499131 -0.057194 -0.0518661 -0.00399131 -0.0666405 -0.0401895 -0.00399131 -0.0742691 -0.0274167 -0.00399131 -0.0798718 -0.0274167 -0.00499131 -0.0798718 -0.0138958 -0.00399131 -0.0832958 4.20971e-06 -0.00399131 -0.0844476 -0.0623484 -0.00499131 0.0574021 -0.0518661 -0.00499131 0.0666454 -0.0520503 -0.00499131 0.0668821 -0.0139452 -0.00499131 0.0835966 0.0139536 -0.00499131 0.0835966 0.0518745 -0.00499131 0.0666454 0.0621361 -0.00499131 0.0571989 0.0707029 -0.00499131 0.0461922 0.0709541 -0.00499131 0.0463563 0.0773413 -0.00499131 0.0339256 0.0821609 -0.00499131 0.0208073 0.0841658 -0.00499131 0.00697627 0.0818701 -0.00499131 -0.0207288 0.0773413 -0.00499131 -0.0339207 0.0821609 -0.00499131 -0.0208025 0.077616 -0.00499131 -0.0340412 0.0707029 -0.00499131 -0.0461873 0.0709541 -0.00499131 -0.0463514 0.0621361 -0.00499131 -0.057194 0.0623568 -0.00499131 -0.0573972 0.0518745 -0.00499131 -0.0666405 0.040198 -0.00499131 -0.0742691 0.0520587 -0.00499131 -0.0668772 0.0275225 -0.00499131 -0.0801556 0.0274251 -0.00499131 -0.0798718 0.0139536 -0.00499131 -0.0835917 -0.0138958 -0.00499131 -0.0832958 -0.0139452 -0.00499131 -0.0835917 -0.0275141 -0.00499131 -0.0801556 -0.0401895 -0.00499131 -0.0742691 -0.0403323 -0.00499131 -0.074533 -0.0518661 -0.00499131 -0.0666405 -0.0520503 -0.00499131 -0.0668772 -0.0706945 -0.00499131 -0.0461873 -0.0623484 -0.00499131 -0.0573972 -0.0709457 -0.00499131 -0.0463514 -0.0773328 -0.00499131 -0.0339207 -0.0844563 -0.00499131 0.00700104 -0.0821525 -0.00499131 0.0208073 -0.0706945 -0.00499131 0.0461922 4.20971e-06 0.0135087 0.0847524 -0.0139781 0.0137087 0.0837938 -0.0139452 0.0135087 0.0835966 -0.027579 0.0137087 0.0803496 -0.0275141 0.0135087 0.0801605 -0.0403323 0.0135087 0.0745378 -0.0520503 0.0135087 0.0668821 -0.0709457 0.0135087 0.0463563 -0.0711131 0.0137087 0.0464657 -0.0777907 0.0137087 0.0341265 -0.0846556 0.0137087 0.00701756 -0.0844563 0.0135087 0.00700104 -0.0844563 0.0135087 -0.00699616 -0.0846556 0.0137087 -0.00701267 -0.0821525 0.0135087 -0.0208025 -0.0777907 0.0137087 -0.0341216 -0.0711131 0.0137087 -0.0464608 -0.0709457 0.0135087 -0.0463514 -0.0624955 0.0137087 -0.0575326 -0.0521732 0.0137087 -0.067035 -0.0404275 0.0137087 -0.0747089 -0.027579 0.0137087 -0.0803447 -0.0275141 0.0135087 -0.0801556 4.20971e-06 0.0137087 -0.0849476 -0.0139452 0.0135087 -0.0835917 -0.0139781 0.0123087 -0.083789 -0.0275141 0.0125087 -0.0801556 -0.027579 0.0123087 -0.0803447 -0.0521732 0.0123087 -0.067035 -0.0623484 0.0125087 -0.0573972 -0.0823463 0.0123087 -0.0208516 -0.0844563 0.0125087 -0.00699616 -0.0844563 0.0125087 0.00700104 -0.0821525 0.0125087 0.0208073 -0.0777907 0.0123087 0.0341265 -0.0711131 0.0123087 0.0464657 -0.0709457 0.0125087 0.0463563 -0.0624955 0.0123087 0.0575375 -0.0520503 0.0125087 0.0668821 -0.0404275 0.0123087 0.0747137 -0.0403323 0.0125087 0.0745378 -0.0275141 0.0125087 0.0801605 -0.027579 0.0123087 0.0803496 -0.0139452 0.0110087 0.0835966 -0.0139781 0.0112087 0.0837938 -0.027579 0.0112087 0.0803496 -0.0404275 0.0112087 0.0747137 -0.0275141 0.0110087 0.0801605 -0.0520503 0.0110087 0.0668821 -0.0777907 0.0112087 0.0341265 -0.0821525 0.0110087 0.0208073 -0.0823463 0.0112087 -0.0208516 -0.0777907 0.0112087 -0.0341216 -0.0711131 0.0112087 -0.0464608 -0.0709457 0.0110087 -0.0463514 -0.0624955 0.0112087 -0.0575326 -0.0623484 0.0110087 -0.0573972 -0.0520503 0.0110087 -0.0668772 -0.0521732 0.0112087 -0.067035 -0.027579 0.0112087 -0.0803447 -0.0139781 0.0112087 -0.083789 4.20971e-06 0.0112087 -0.0849476 -0.0139452 0.0110087 -0.0835917 -0.0139781 0.00980869 -0.083789 -0.0139452 0.0100087 -0.0835917 -0.027579 0.00980869 -0.0803447 -0.0404275 0.00980869 -0.0747089 -0.0403323 0.0100087 -0.074533 -0.0521732 0.00980869 -0.067035 -0.0623484 0.0100087 -0.0573972 -0.0711131 0.00980869 -0.0464608 -0.0776076 0.0100087 -0.0340412 -0.0777907 0.00980869 -0.0341216 -0.0823463 0.00980869 -0.0208516 -0.0821525 0.0100087 -0.0208025 -0.0846556 0.00980869 0.00701756 -0.0844563 0.0100087 -0.00699616 -0.0823463 0.00980869 0.0208564 -0.0711131 0.00980869 0.0464657 -0.0709457 0.0100087 0.0463563 -0.0521732 0.00980869 0.0670399 -0.0403323 0.0100087 0.0745378 -0.027579 0.00980869 0.0803496 -0.0139452 0.0100087 0.0835966 4.20971e-06 0.00850869 0.0847524 -0.0139781 0.00870869 0.0837938 -0.0139452 0.00850869 0.0835966 -0.027579 0.00870869 0.0803496 -0.0521732 0.00870869 0.0670399 -0.0624955 0.00870869 0.0575375 -0.0711131 0.00870869 0.0464657 -0.0709457 0.00850869 0.0463563 -0.0777907 0.00870869 0.0341265 -0.0776076 0.00850869 0.0340461 -0.0823463 0.00870869 0.0208564 -0.0846556 0.00870869 0.00701756 -0.0823463 0.00870869 -0.0208516 -0.0776076 0.00850869 -0.0340412 -0.0777907 0.00870869 -0.0341216 -0.0624955 0.00870869 -0.0575326 -0.0520503 0.00850869 -0.0668772 -0.027579 0.00870869 -0.0803447 4.20971e-06 0.00850869 -0.0847476 -0.0139452 0.00750869 -0.0835917 -0.0139781 0.00730869 -0.083789 -0.027579 0.00730869 -0.0803447 -0.0403323 0.00750869 -0.074533 -0.0520503 0.00750869 -0.0668772 -0.0521732 0.00730869 -0.067035 -0.0624955 0.00730869 -0.0575326 -0.0623484 0.00750869 -0.0573972 -0.0711131 0.00730869 -0.0464608 -0.0823463 0.00730869 -0.0208516 -0.0823463 0.00730869 0.0208564 -0.0821525 0.00750869 0.0208073 -0.0777907 0.00730869 0.0341265 -0.0711131 0.00730869 0.0464657 -0.0709457 0.00750869 0.0463563 -0.0624955 0.00730869 0.0575375 -0.0521732 0.00730869 0.0670399 -0.0520503 0.00750869 0.0668821 -0.0404275 0.00730869 0.0747137 -0.027579 0.00730869 0.0803496 -0.0139452 0.00750869 0.0835966 -0.0139781 0.00620869 0.0837938 -0.027579 0.00620869 0.0803496 -0.0404275 0.00620869 0.0747137 -0.0403323 0.00600869 0.0745378 -0.0521732 0.00620869 0.0670399 -0.0520503 0.00600869 0.0668821 -0.0623484 0.00600869 0.0574021 -0.0711131 0.00620869 0.0464657 -0.0821525 0.00600869 0.0208073 -0.0823463 0.00620869 0.0208564 -0.0777907 0.00620869 -0.0341216 -0.0624955 0.00620869 -0.0575326 -0.0623484 0.00600869 -0.0573972 -0.0403323 0.00600869 -0.074533 -0.0275141 0.00600869 -0.0801556 -0.0139781 0.00620869 -0.083789 -0.0139781 0.00480869 -0.083789 -0.0139452 0.00500869 -0.0835917 -0.0403323 0.00500869 -0.074533 -0.0623484 0.00500869 -0.0573972 -0.0711131 0.00480869 -0.0464608 -0.0709457 0.00500869 -0.0463514 -0.0776076 0.00500869 -0.0340412 -0.0823463 0.00480869 -0.0208516 -0.0821525 0.00500869 -0.0208025 -0.0846556 0.00480869 -0.00701267 -0.0844563 0.00500869 -0.00699616 -0.0823463 0.00480869 0.0208564 -0.0777907 0.00480869 0.0341265 -0.0709457 0.00500869 0.0463563 -0.0711131 0.00480869 0.0464657 -0.0624955 0.00480869 0.0575375 -0.0520503 0.00500869 0.0668821 -0.0404275 0.00480869 0.0747137 -0.027579 0.00480869 0.0803496 -0.0139452 0.00500869 0.0835966 4.20971e-06 0.00370869 0.0849524 -0.0139452 0.00350869 0.0835966 -0.0139781 0.00370869 0.0837938 -0.0275141 0.00350869 0.0801605 -0.0404275 0.00370869 0.0747137 -0.0520503 0.00350869 0.0668821 -0.0623484 0.00350869 0.0574021 -0.0624955 0.00370869 0.0575375 -0.0711131 0.00370869 0.0464657 -0.0709457 0.00350869 0.0463563 -0.0777907 0.00370869 0.0341265 -0.0776076 0.00350869 0.0340461 -0.0823463 0.00370869 0.0208564 -0.0821525 0.00350869 0.0208073 -0.0844563 0.00350869 0.00700104 -0.0844563 0.00350869 -0.00699616 -0.0823463 0.00370869 -0.0208516 -0.0776076 0.00350869 -0.0340412 -0.0709457 0.00350869 -0.0463514 -0.0711131 0.00370869 -0.0464608 -0.0623484 0.00350869 -0.0573972 -0.0521732 0.00370869 -0.067035 -0.0275141 0.00350869 -0.0801556 -0.0139452 0.00350869 -0.0835917 4.20971e-06 0.00370869 -0.0849476 4.20971e-06 0.00350869 -0.0847476 -0.027579 0.00230869 -0.0803447 -0.0711131 0.00230869 -0.0464608 -0.0709457 0.00250869 -0.0463514 -0.0821525 0.00250869 -0.0208025 -0.0823463 0.00230869 0.0208564 -0.0777907 0.00230869 0.0341265 -0.0709457 0.00250869 0.0463563 -0.0711131 0.00230869 0.0464657 -0.0623484 0.00250869 0.0574021 -0.0520503 0.00250869 0.0668821 -0.027579 0.00230869 0.0803496 -0.0139781 0.00230869 0.0837938 -0.0275141 0.00250869 0.0801605 -0.0403323 0.00100869 0.0745378 -0.0521732 0.00120869 0.0670399 -0.0623484 0.00100869 0.0574021 -0.0624955 0.00120869 0.0575375 -0.0711131 0.00120869 0.0464657 -0.0777907 0.00120869 0.0341265 -0.0846556 0.00120869 0.00701756 -0.0844563 0.00100869 -0.00699616 -0.0821525 0.00100869 -0.0208025 -0.0711131 0.00120869 -0.0464608 -0.0709457 0.00100869 -0.0463514 -0.0624955 0.00120869 -0.0575326 -0.0521732 0.00120869 -0.067035 -0.027579 0.00120869 -0.0803447 -0.0403323 0.00100869 -0.074533 -0.0275141 0.00100869 -0.0801556 -0.0139781 0.00120869 -0.083789 4.20971e-06 0.00120869 -0.0849476 -0.0139781 -0.000191313 -0.083789 -0.0139452 8.6865e-06 -0.0835917 -0.0521732 -0.000191313 -0.067035 -0.0776076 8.6865e-06 -0.0340412 -0.0777907 -0.000191313 -0.0341216 -0.0846556 -0.000191313 -0.00701267 -0.0846556 -0.000191313 0.00701756 -0.0844563 8.6865e-06 0.00700104 -0.0821525 8.6865e-06 0.0208073 -0.0823463 -0.000191313 0.0208564 -0.0776076 8.6865e-06 0.0340461 -0.0709457 8.6865e-06 0.0463563 -0.0711131 -0.000191313 0.0464657 -0.0624955 -0.000191313 0.0575375 -0.0623484 8.6865e-06 0.0574021 -0.0520503 8.6865e-06 0.0668821 -0.0521732 -0.000191313 0.0670399 -0.0403323 8.6865e-06 0.0745378 -0.0275141 8.6865e-06 0.0801605 4.20971e-06 -0.000191313 0.0849524 -0.0139452 -0.00149131 0.0835966 -0.027579 -0.00129131 0.0803496 -0.0275141 -0.00149131 0.0801605 -0.0624955 -0.00129131 0.0575375 -0.0623484 -0.00149131 0.0574021 -0.0709457 -0.00149131 0.0463563 -0.0777907 -0.00129131 0.0341265 -0.0776076 -0.00149131 0.0340461 -0.0846556 -0.00129131 0.00701756 -0.0821525 -0.00149131 0.0208073 -0.0846556 -0.00129131 -0.00701267 -0.0821525 -0.00149131 -0.0208025 -0.0823463 -0.00129131 -0.0208516 -0.0776076 -0.00149131 -0.0340412 -0.0777907 -0.00129131 -0.0341216 -0.0624955 -0.00129131 -0.0575326 -0.0623484 -0.00149131 -0.0573972 -0.0521732 -0.00129131 -0.067035 -0.0403323 -0.00149131 -0.074533 -0.0275141 -0.00149131 -0.0801556 -0.0139781 -0.00129131 -0.083789 -0.0139452 -0.00149131 -0.0835917 4.20971e-06 -0.00129131 -0.0849476 4.20971e-06 -0.00249131 -0.0847476 -0.0275141 -0.00249131 -0.0801556 -0.0520503 -0.00249131 -0.0668772 -0.0623484 -0.00249131 -0.0573972 -0.0711131 -0.00269131 -0.0464608 -0.0776076 -0.00249131 -0.0340412 -0.0777907 -0.00269131 -0.0341216 -0.0846556 -0.00269131 0.00701756 -0.0844563 -0.00249131 -0.00699616 -0.0844563 -0.00249131 0.00700104 -0.0821525 -0.00249131 0.0208073 -0.0776076 -0.00249131 0.0340461 -0.0709457 -0.00249131 0.0463563 -0.0711131 -0.00269131 0.0464657 -0.0624955 -0.00269131 0.0575375 -0.0623484 -0.00249131 0.0574021 -0.0521732 -0.00269131 0.0670399 -0.0520503 -0.00249131 0.0668821 -0.0403323 -0.00249131 0.0745378 -0.027579 -0.00269131 0.0803496 -0.0139781 -0.00269131 0.0837938 4.20971e-06 -0.00249131 0.0847524 -0.0139781 -0.00379131 0.0837938 -0.0139452 -0.00399131 0.0835966 -0.027579 -0.00379131 0.0803496 -0.0404275 -0.00379131 0.0747137 -0.0520503 -0.00399131 0.0668821 -0.0711131 -0.00379131 0.0464657 -0.0623484 -0.00399131 0.0574021 -0.0709457 -0.00399131 0.0463563 -0.0777907 -0.00379131 0.0341265 -0.0823463 -0.00379131 0.0208564 -0.0821525 -0.00399131 0.0208073 -0.0823463 -0.00379131 -0.0208516 -0.0844563 -0.00399131 -0.00699616 -0.0777907 -0.00379131 -0.0341216 -0.0776076 -0.00399131 -0.0340412 -0.0709457 -0.00399131 -0.0463514 -0.0711131 -0.00379131 -0.0464608 -0.0624955 -0.00379131 -0.0575326 -0.0521732 -0.00379131 -0.067035 -0.0520503 -0.00399131 -0.0668772 -0.0404275 -0.00379131 -0.0747089 -0.0403323 -0.00399131 -0.074533 -0.0139452 -0.00399131 -0.0835917 4.20971e-06 -0.00399131 -0.0847476 -0.0624955 -0.00519131 -0.0575326 -0.0776076 -0.00499131 -0.0340412 -0.0821525 -0.00499131 -0.0208025 -0.0844563 -0.00499131 -0.00699616 -0.0776076 -0.00499131 0.0340461 -0.0777907 -0.00519131 0.0341265 -0.0709457 -0.00499131 0.0463563 -0.0521732 -0.00519131 0.0670399 -0.0403323 -0.00499131 0.0745378 -0.0275141 -0.00499131 0.0801605 -0.027579 -0.00519131 0.0803496 -0.0139781 -0.00519131 0.0837938 4.20971e-06 -0.00499131 0.0847524 -0.0409958 -0.0105775 -0.00756134 -0.0409958 -0.0118914 -0.00843927 -0.0503473 -0.0118914 -0.00843927 -0.0409958 -0.0136413 -0.00874756 -0.0409958 -0.0171487 -0.00672256 -0.0503473 -0.0171487 -0.00672256 -0.0409958 -0.0171487 0.00672744 -0.0409958 -0.0156663 0.00820984 -0.0503473 -0.0171487 0.00672744 -0.0503473 -0.0105775 0.00756622 -0.0409958 -0.0118914 0.00844415 -0.0503473 -0.00993391 0.00672744 -0.0409958 -0.0096996 0.00625231 0.0503557 -0.0105775 -0.00756134 0.0503557 -0.0118914 -0.00843927 0.0420042 -0.0118914 -0.00843927 0.0503557 -0.0134413 -0.00874756 0.0420042 -0.0171487 -0.00672256 0.0503557 -0.0176913 0.00470244 0.0420042 -0.0176913 0.00470244 0.0420042 -0.0171487 0.00672744 0.0503557 -0.0136413 0.00875244 0.0420042 -0.0134413 0.00875244 0.0503557 -0.0114163 0.00820984 0.0503557 -0.00993391 0.00672744 0.0420042 -0.00993391 0.00672744 -0.0139781 -0.00779131 0.0837938 4.20971e-06 -0.00829131 0.0844524 -0.0404275 -0.00779131 0.0747137 -0.0572174 -0.00829131 0.0621111 -0.0519009 -0.00829131 0.0666182 -0.0646239 -0.00829131 0.0543624 -0.0706945 -0.00829131 0.0461922 -0.0773328 -0.00829131 0.0339256 -0.0846556 -0.00779131 -0.00701267 -0.0818083 -0.00829131 0.0209433 -0.0773328 -0.00829131 -0.0339207 -0.0823463 -0.00779131 -0.0208516 -0.0793496 -0.00829131 -0.02889 -0.0711131 -0.00779131 -0.0464608 -0.0706945 -0.00829131 -0.0461873 -0.0518661 -0.00829131 -0.0666405 -0.0521732 -0.00779131 -0.067035 -0.0533053 -0.00829131 -0.0654949 -0.0621277 -0.00829131 -0.057194 -0.0274167 -0.00829131 -0.0798718 -0.0139781 -0.00779131 -0.083789 -0.027579 0.0178087 -0.0803447 -0.0139452 0.0180087 -0.0835917 -0.0403323 0.0180087 -0.074533 -0.0404275 0.0178087 -0.0747089 -0.0521732 0.0178087 -0.067035 -0.0520503 0.0180087 -0.0668772 -0.0623484 0.0180087 -0.0573972 -0.0624955 0.0178087 -0.0575326 -0.0709457 0.0180087 -0.0463514 -0.0777907 0.0178087 -0.0341216 -0.0821525 0.0180087 -0.0208025 -0.0846556 0.0178087 -0.00701267 -0.0844563 0.0180087 -0.00699616 -0.0846556 0.0178087 0.00701756 -0.0821525 0.0180087 0.0208073 -0.0777907 0.0178087 0.0341265 -0.0709457 0.0180087 0.0463563 -0.0623484 0.0180087 0.0574021 -0.0521732 0.0178087 0.0670399 -0.0520503 0.0180087 0.0668821 -0.0404275 0.0178087 0.0747137 -0.027579 0.0178087 0.0803496 -0.0403323 0.0180087 0.0745378 -0.0139781 0.0178087 0.0837938 0.0520042 -0.0182913 0.00470244 0.0503557 -0.0176913 -0.00469756 0.0503557 -0.0156663 0.00820984 0.0503557 -0.0171487 0.00672744 0.0520042 -0.0182913 -0.00469756 0.0503557 -0.0171487 -0.00672256 0.0520042 -0.0176683 -0.00702256 0.0503557 -0.0156663 -0.00820496 0.0503557 -0.0136413 -0.00874756 0.0520042 -0.0094143 0.00702744 0.0503557 -0.0134413 0.00875244 0.0520042 -0.0116618 -0.0089936 0.0520042 -0.0101533 -0.00798561 0.0503557 -0.0096996 -0.00624743 0.0503557 -0.00939131 0.00470244 0.0520042 -0.00879131 -0.00469756 0.0520042 -0.00879131 0.00470244 -0.0503473 -0.00939131 -0.00469756 -0.0519958 -0.00879131 -0.00469756 -0.0519958 -0.00879131 0.00470244 -0.0503473 -0.00939131 0.00470244 -0.0503473 -0.0134413 0.00875244 -0.0519958 -0.0111163 0.00872946 -0.0503473 -0.0114163 0.00820984 -0.0503473 -0.0096996 -0.00624743 -0.0519958 -0.00914527 -0.00647704 -0.0503473 -0.0105775 -0.00756134 -0.0503473 -0.0136413 0.00875244 -0.0519958 -0.0134413 -0.00934756 -0.0503473 -0.0136413 -0.00874756 -0.0503473 -0.0134413 -0.00874756 -0.0503473 -0.0156663 0.00820984 -0.0519958 -0.0176683 0.00702744 -0.0503473 -0.0156663 -0.00820496 -0.0503473 -0.0176913 -0.00469756 -0.0519958 -0.0176683 -0.00702256 -0.0519958 -0.0182913 -0.00469756 -0.0503473 -0.0176913 0.00470244 -0.0519958 -0.0182913 0.00470244 -0.0462665 -0.0212913 -0.0248022 -0.0405456 -0.0212913 -0.0333436 -0.0417042 -0.0197913 -0.0342964 -0.03327 -0.0212913 -0.0406064 -0.0342207 -0.0197913 -0.0417666 -0.0254249 -0.0197913 -0.0476354 -0.0247185 -0.0212913 -0.0463121 -0.015654 -0.0197913 -0.0516775 -0.00513591 -0.0212913 -0.0522453 0.00529119 -0.0197913 -0.0537381 0.00514433 -0.0212913 -0.0522453 0.0152275 -0.0212913 -0.050242 0.0247269 -0.0212913 -0.0463121 0.0417126 -0.0197913 -0.0342964 0.0475969 -0.0197913 -0.0255109 0.0405541 -0.0212913 -0.0333436 0.0462749 -0.0212913 -0.0248022 -0.0502132 -0.0212913 0.0153146 -0.0504958 -0.0212913 0.0134188 0.0505042 -0.0212913 0.0134188 0.0466179 -0.0212913 0.0241565 0.0414723 -0.0212913 0.0321994 0.0272821 -0.0212913 0.0448596 0.0280614 -0.0197913 0.0461413 0.0187067 -0.0212913 0.0490582 0.00951269 -0.0212913 0.0516342 0.0795253 -0.00729131 -0.000822559 0.0823831 -0.00729131 0.000827441 0.0801292 -0.00729131 0.00143138 0.0817792 -0.00729131 -0.0014265 0.0717176 -0.00729131 0.0408446 0.0708249 -0.00729131 0.0389908 0.0708249 -0.00729131 0.041964 0.069284 -0.00729131 0.0419064 0.071399 -0.00729131 0.0394487 0.068459 -0.00729131 0.0404774 0.069284 -0.00729131 0.0390485 0.0413042 -0.00729131 0.0715361 0.0391892 -0.00729131 0.071136 0.0388706 -0.00729131 0.0704744 0.0419082 -0.00729131 0.0692822 0.0413042 -0.00729131 0.0686783 0.0397633 -0.00729131 0.0686206 0.0417692 -0.00729131 -0.0711311 0.0411951 -0.00729131 -0.0715889 0.0420878 -0.00729131 -0.0704695 0.0388292 -0.00729131 -0.0701023 0.0390503 -0.00729131 -0.0692773 0.0404792 -0.00729131 -0.0717523 0.0396542 -0.00729131 -0.0686734 0.0717176 -0.00729131 -0.0401054 0.071399 -0.00729131 -0.0415013 0.0717176 -0.00729131 -0.0408397 0.0708249 -0.00729131 -0.0419592 0.068459 -0.00729131 -0.0404726 0.070109 -0.00729131 -0.0421226 0.070109 -0.00729131 -0.0388226 0.0708249 -0.00729131 -0.038986 0.071399 -0.00729131 -0.0394438 -0.0411867 -0.00729131 -0.0686157 -0.0417608 -0.00729131 -0.0690736 -0.0388208 -0.00729131 -0.0701023 -0.0396458 -0.00729131 -0.0686734 -0.0396458 -0.00729131 -0.0715313 -0.0390418 -0.00729131 -0.0709273 -0.0417608 -0.00729131 -0.0711311 -0.0684505 -0.00729131 -0.0404726 -0.0692755 -0.00729131 -0.0390436 -0.0717505 -0.00729131 -0.0404726 -0.0715295 -0.00729131 -0.0396476 -0.0701005 -0.00729131 -0.0421226 -0.0686716 -0.00729131 -0.0412976 -0.0709255 -0.00729131 -0.0419015 -0.0715295 -0.00729131 -0.0412976 -0.0817708 -0.00729131 -0.0014265 -0.0801208 -0.00729131 0.00143138 -0.0795169 -0.00729131 0.000827441 -0.0823747 -0.00729131 -0.000822559 -0.0795169 -0.00729131 -0.000822559 -0.0709255 -0.00729131 0.0390485 -0.0709255 -0.00729131 0.0419064 -0.0715295 -0.00729131 0.0413024 -0.0715295 -0.00729131 0.0396524 -0.0684505 -0.00729131 0.0404774 -0.0686716 -0.00729131 0.0396524 -0.0404708 -0.00729131 0.0717572 -0.0396458 -0.00729131 0.0715361 -0.0390418 -0.00729131 0.0709322 -0.0418997 -0.00729131 0.0709322 -0.0418997 -0.00729131 0.0692822 -0.0388208 -0.00729131 0.0701072 -0.0396458 -0.00729131 0.0686783 0.0420042 -0.0156663 -0.00820496 0.0420042 -0.0176913 -0.00469756 0.0420042 -0.0096996 -0.00624743 0.0420042 -0.0105775 -0.00756134 0.0420042 -0.0114163 0.00820984 0.0420042 -0.00939131 0.00470244 0.0420042 -0.00939131 -0.00469756 0.0420042 -0.0156663 0.00820984 -0.0409958 -0.0156663 -0.00820496 -0.0409958 -0.0134413 0.00875244 -0.0409958 -0.0136413 0.00875244 -0.0409958 -0.0105775 0.00756622 -0.0409958 -0.00939131 0.00470244 -0.0409958 -0.0096996 -0.00624743 -0.0409958 -0.0134413 -0.00874756 -0.0112037 0.0300087 0.0563486 -0.0112037 0.0304087 0.0563486 -0.021981 0.0300087 0.0530793 -0.021981 0.0304087 0.0530793 -0.0406191 0.0304087 0.0406257 -0.0319133 0.0300087 0.0477704 -0.0406191 0.0300087 0.0406257 -0.0477637 0.0304087 0.0319199 -0.0530727 0.0300087 0.0219876 -0.0563419 0.0300087 0.0112104 -0.0574458 0.0300087 2.44063e-06 -0.0563419 0.0300087 -0.0112055 -0.0530727 0.0304087 -0.0219827 -0.0477637 0.0304087 -0.0319151 -0.0406191 0.0304087 -0.0406208 -0.0406191 0.0300087 -0.0406208 -0.0319133 0.0304087 -0.0477655 -0.0319133 0.0300087 -0.0477655 -0.021981 0.0300087 -0.0530744 -0.0112037 0.0300087 -0.0563437 4.20971e-06 0.0304087 -0.0574476 4.20971e-06 0.0333087 -0.0557976 4.20971e-06 0.0311087 -0.0588476 -0.0114769 0.0311087 -0.0577168 -0.0108818 0.0333087 -0.0547254 -0.0213495 0.0333087 -0.05155 -0.0326911 0.0311087 -0.0489295 -0.041609 0.0311087 -0.0416108 -0.0394523 0.0333087 -0.0394541 -0.0463918 0.0333087 -0.0309984 -0.0543661 0.0311087 -0.0225185 -0.0588458 0.0311087 2.44063e-06 -0.057715 0.0311087 0.0114835 -0.0547236 0.0333087 0.0108885 -0.0515483 0.0333087 0.0213562 -0.0489278 0.0311087 0.0326977 -0.0394523 0.0333087 0.039459 -0.0326911 0.0311087 0.0489344 -0.0213495 0.0333087 0.0515549 -0.0108818 0.0333087 0.0547303 4.20971e-06 0.0311087 0.0588524 4.20971e-06 0.0306087 0.0588524 -0.0114769 0.0311087 0.0577217 -0.0225167 0.0311087 0.0543728 -0.041609 0.0311087 0.0416157 -0.041609 0.0306087 0.0416157 -0.0543661 0.0311087 0.0225234 -0.0543661 0.0306087 0.0225234 -0.057715 0.0306087 0.0114835 -0.057715 0.0311087 -0.0114786 -0.0489278 0.0311087 -0.0326929 -0.0489278 0.0306087 -0.0326929 -0.0225167 0.0311087 -0.0543679 -0.0114769 0.0306087 -0.0577168 0.0112121 0.0304087 -0.0563437 0.0224486 0.0304087 -0.0541831 0.0325884 0.0304087 -0.0487633 0.041476 0.0304087 -0.0414694 0.0406275 0.0304087 -0.0406208 0.0477721 0.0304087 -0.0319151 0.0563503 0.0304087 -0.0112055 0.0575273 0.0304087 -0.0114396 0.0563503 0.0304087 0.0112104 0.0477721 0.0304087 0.0319199 0.0487699 0.0304087 0.0325866 0.0325884 0.0304087 0.0487681 0.0219894 0.0304087 0.0530793 4.20971e-06 0.0304087 0.0574524 4.20971e-06 0.0304087 0.0586524 -0.0114378 0.0304087 0.0575255 -0.0224402 0.0304087 0.054188 -0.0319133 0.0304087 0.0477704 -0.0414676 0.0304087 0.0414743 -0.0487615 0.0304087 0.0325866 -0.0530727 0.0304087 0.0219876 -0.0563419 0.0304087 0.0112104 -0.0575188 0.0304087 0.0114445 -0.0574458 0.0304087 2.44063e-06 -0.0575188 0.0304087 -0.0114396 -0.0563419 0.0304087 -0.0112055 -0.021981 0.0304087 -0.0530744 -0.0112037 0.0304087 -0.0563437 -0.0114769 0.0306087 0.0577217 -0.0225167 0.0306087 0.0543728 -0.0326911 0.0306087 0.0489344 -0.03258 0.0304087 0.0487681 -0.0489278 0.0306087 0.0326977 -0.0541813 0.0304087 0.0224468 -0.0588458 0.0306087 2.44063e-06 -0.057715 0.0306087 -0.0114786 -0.0586458 0.0304087 2.44063e-06 -0.0541813 0.0304087 -0.0224419 -0.0543661 0.0306087 -0.0225185 -0.0487615 0.0304087 -0.0325818 -0.041609 0.0306087 -0.0416108 -0.0414676 0.0304087 -0.0414694 -0.0326911 0.0306087 -0.0489295 -0.03258 0.0304087 -0.0487633 -0.0225167 0.0306087 -0.0543679 -0.0224402 0.0304087 -0.0541831 -0.0114378 0.0304087 -0.0575206 4.20971e-06 0.0304087 -0.0586476 0.0328411 0.0333087 0.026189 0.0394608 0.0333087 0.039459 0.0464002 0.0333087 0.0310033 0.0409512 0.0333087 0.00934832 0.0420042 0.0333087 2.44063e-06 0.0558042 0.0333087 2.44063e-06 0.0515567 0.0333087 -0.0213513 -0.0309966 0.0333087 0.0463984 -0.0182189 0.0333087 0.0378431 4.20971e-06 0.0333087 0.0558024 0.00935009 0.0333087 0.0409494 0.0182273 0.0333087 0.0378431 0.0213579 0.0333087 0.0515549 0.031005 0.0333087 0.0463984 -0.0409428 0.0333087 -0.00934344 -0.0515483 0.0333087 -0.0213513 -0.0419958 0.0333087 2.44063e-06 -0.0547236 0.0333087 -0.0108836 -0.0557958 0.0333087 2.44063e-06 -0.0378365 0.0333087 0.0182256 -0.0328327 0.0333087 0.026189 -0.0463918 0.0333087 0.0310033 0.0328411 0.0333087 -0.0261841 0.0464002 0.0333087 -0.0309984 0.0394608 0.0333087 -0.0394541 0.0261908 0.0333087 -0.0328345 0.0108903 0.0333087 -0.0547254 -0.00934167 0.0333087 -0.0409445 -0.0309966 0.0333087 -0.0463936 -0.00476851 0.0328087 -0.00990822 -0.00859594 0.0328087 -0.00685595 0.0107284 0.0328087 -0.00244529 0.0107284 0.0328087 0.00245017 4.20971e-06 0.0328087 0.0110024 0.00477693 0.0328087 0.0099131 0.0338116 0.0338087 0.0130111 0.0370592 0.0336087 0.0109361 0.0375616 0.0336087 0.00906111 0.0370592 0.0336087 0.00718611 0.0377616 0.0338087 0.00906111 0.0372324 0.0338087 0.00708611 0.0247529 0.0336087 0.0285012 0.0266279 0.0336087 0.0279988 0.0267279 0.0338087 0.028172 0.0280005 0.0336087 0.0266262 0.0287029 0.0338087 0.0247512 0.0281737 0.0338087 0.0227762 0.0247529 0.0336087 0.0210012 0.0107767 0.0338087 0.0373687 0.0127189 0.0336087 0.0329754 0.0129138 0.0338087 0.0329309 0.0119947 0.0336087 0.0314718 0.0107767 0.0338087 0.030251 -0.00539848 0.0336087 0.0329754 -0.00717946 0.0336087 0.0305622 -0.00707946 0.0338087 0.030389 -0.00563366 0.0338087 0.0318348 -0.00563366 0.0338087 0.0357848 -0.00612259 0.0336087 0.0361479 -0.00905446 0.0338087 0.0377598 -0.00707946 0.0338087 0.0372306 -0.0231175 0.0336087 0.0281298 -0.0218127 0.0336087 0.0270893 -0.0216563 0.0338087 0.027214 -0.0208936 0.0338087 0.0238722 -0.0218127 0.0336087 0.0224131 -0.0320894 0.0338087 0.0126199 -0.030715 0.0338087 0.0115239 -0.0301472 0.0336087 0.00989556 -0.0299522 0.0338087 0.00994006 -0.030715 0.0338087 0.00659832 -0.0308713 0.0336087 0.00672302 -0.0321761 0.0336087 0.00568247 -0.0318282 0.0338087 -0.00563543 -0.0305556 0.0336087 -0.00718123 -0.0303824 0.0338087 -0.00708123 -0.0303824 0.0338087 -0.0110312 -0.0338032 0.0336087 -0.0128062 -0.0228695 0.0336087 -0.0214987 -0.0227695 0.0338087 -0.0213255 -0.0214969 0.0336087 -0.0228713 -0.0209945 0.0336087 -0.0247463 -0.0213237 0.0338087 -0.0227713 -0.0214969 0.0336087 -0.0266213 -0.0207945 0.0338087 -0.0247463 -0.0213237 0.0338087 -0.0267213 -0.0228695 0.0336087 -0.0279939 -0.00734062 0.0338087 -0.0302461 -0.00612259 0.0336087 -0.0314669 -0.00596622 0.0338087 -0.0313422 -0.00539848 0.0336087 -0.0346394 -0.00612259 0.0336087 -0.036143 -0.00734062 0.0338087 -0.0373638 -0.00905446 0.0338087 -0.037755 0.00906288 0.0336087 -0.030055 0.0123105 0.0336087 -0.03193 0.0128129 0.0336087 -0.033805 0.0123105 0.0336087 -0.03568 0.0247529 0.0338087 -0.0207963 0.0280005 0.0336087 -0.0228713 0.0281737 0.0338087 -0.0227713 0.0285029 0.0336087 -0.0247463 0.0287029 0.0338087 -0.0247463 0.0280005 0.0336087 -0.0266213 0.0281737 0.0338087 -0.0267213 0.0266279 0.0336087 -0.0279939 0.0370592 0.0336087 -0.00718123 0.0372324 0.0338087 -0.00708123 0.0375616 0.0336087 -0.00905623 0.0377616 0.0338087 -0.00905623 0.0356866 0.0336087 -0.0123038 0.0357866 0.0338087 -0.012477 0.0338116 0.0336087 -0.0128062 0.0338116 0.0338087 -0.0130062 0.00191403 0.0335087 0.0201554 0.00204574 0.0338087 0.0246647 0.0023416 0.0335087 0.0246151 0.00469539 0.0335087 0.0278133 0.00603779 0.0335087 0.0282395 0.00668091 0.0335087 0.0282868 0.0217204 0.0338087 0.0194566 0.0212897 0.0335087 0.015767 0.0220461 0.0338087 0.0175278 0.0100566 0.0338087 0.00932367 0.00892649 0.0338087 0.0100001 0.00912625 0.0335087 0.0102239 0.00429524 0.0335087 0.0130131 0.00324303 0.0335087 0.0135987 0.00305043 0.0338087 0.0133687 0.00248176 0.0335087 0.0145317 -0.0164939 0.0335087 0.0117329 -0.0166503 0.0338087 0.0114769 -0.0201423 0.0335087 0.014333 -0.0203332 0.0338087 0.0141016 -0.0220377 0.0338087 0.0175278 -0.0204194 0.0335087 0.0208714 -0.0206292 0.0338087 0.0210859 -0.00785707 0.0335087 0.0281243 -0.0145958 0.0335087 0.0252904 -0.0130912 0.0338087 0.0264365 -0.0147458 0.0338087 0.0255502 -0.00793783 0.0338087 0.0284132 -0.00203732 0.0338087 0.0246647 -0.00304201 0.0338087 0.0133687 -0.00428682 0.0335087 0.0130131 -0.0113397 0.0335087 0.00941271 -0.0126343 0.0338087 0.00939742 -0.0146305 0.0335087 -0.00600471 -0.0184037 0.0335087 -0.00842011 -0.0182602 0.0338087 -0.00868357 -0.0282807 0.0335087 -0.00725044 -0.0274666 0.0335087 -0.00889087 -0.0243096 0.0338087 -0.0108485 -0.0223747 0.0338087 -0.0105607 -0.0285713 0.0338087 -0.00732495 -0.0285713 0.0338087 0.00732983 -0.0258924 0.0335087 0.0101435 -0.0276406 0.0338087 0.00915755 -0.0260202 0.0338087 0.0104149 -0.0223747 0.0338087 0.0105656 -0.0135619 0.0338087 0.00527881 -0.0133899 0.0335087 0.00399567 -0.0130944 0.0338087 0.00404747 -0.0131151 0.0338087 0.00273055 -0.0134089 0.0335087 0.00279162 -0.0131151 0.0338087 -0.00272566 -0.0133899 0.0335087 -0.00399078 -0.0138173 0.0335087 -0.00511658 -0.00190561 0.0335087 -0.0201506 -0.00598552 0.0338087 -0.0285314 -0.00233318 0.0335087 -0.0246102 -0.0027555 0.0338087 -0.0264794 -0.0147458 0.0338087 -0.0255453 -0.0206292 0.0338087 -0.021081 -0.021712 0.0338087 -0.0194518 -0.0220377 0.0338087 -0.0175229 -0.0212813 0.0335087 -0.0157621 -0.0215499 0.0338087 -0.0156285 -0.0201423 0.0335087 -0.0143281 -0.00419286 0.0338087 -0.0127233 -0.00428682 0.0335087 -0.0130082 -0.00247334 0.0335087 -0.0145268 0.0165023 0.0335087 -0.011728 0.0212897 0.0335087 -0.0157621 0.0217204 0.0338087 -0.0194518 0.0204278 0.0335087 -0.0208666 0.0146042 0.0335087 -0.0252855 0.0206377 0.0338087 -0.021081 0.00786549 0.0335087 -0.0281194 0.00204574 0.0338087 -0.0246598 0.00301394 0.0335087 -0.0263136 0.00794625 0.0338087 -0.0284084 0.00599394 0.0338087 -0.0285314 0.00603779 0.0335087 -0.0282346 0.00191403 0.0335087 -0.0201506 0.00211923 0.0335087 -0.0156752 0.00182126 0.0338087 -0.0156403 0.00221778 0.0338087 -0.0143843 0.00420128 0.0338087 -0.0127233 0.0224881 0.0335087 0.0102845 0.0223831 0.0338087 0.0105656 0.024027 0.0335087 0.0105624 0.0282891 0.0335087 -0.00725044 0.024318 0.0338087 -0.0108485 0.0224881 0.0335087 -0.0102796 0.0285797 0.0338087 -0.00732495 0.0262025 0.0338087 -0.0103237 0.0242995 0.0335087 -0.0105491 0.0182686 0.0338087 -0.00868357 0.0146389 0.0335087 -0.00600471 0.0138257 0.0335087 -0.00511658 0.0133983 0.0335087 -0.00399078 0.0134173 0.0335087 0.00279162 0.0131236 0.0338087 0.00273055 0.0146389 0.0335087 0.00600959 0.0185792 0.0311587 0.0321753 0.0223042 0.0338087 0.0303133 0.0216611 0.0338087 0.0279133 0.0185792 0.0311587 0.0284514 0.0303151 0.0338087 0.0223024 0.0327151 0.0338087 0.0216594 0.0324651 0.0311587 0.0175024 0.0321771 0.0311587 0.0164274 0.0351151 0.0338087 0.0175024 0.0327151 0.0338087 0.0133455 0.0360792 0.0311587 0.0018644 0.0374042 0.0338087 0.00415936 0.0368662 0.0311587 0.00107744 0.0371542 0.0311587 2.44063e-06 0.0175042 0.0311587 -0.0281584 0.0184371 0.0311587 -0.0283714 0.0191851 0.0311587 -0.0289679 0.021257 0.0338087 -0.0273157 0.0196003 0.0311587 -0.02983 0.0196003 0.0311587 -0.0307869 0.021257 0.0338087 -0.0333012 0.0191851 0.0311587 -0.031649 4.20971e-06 0.0311587 -0.0328476 0.00107921 0.0311587 -0.0331356 4.20971e-06 0.0338087 -0.0301976 0.00240421 0.0338087 -0.0308406 0.00416113 0.0338087 -0.0325976 0.00107921 0.0311587 -0.0368595 0.00240421 0.0338087 -0.0391545 4.20971e-06 0.0311587 -0.0371476 4.20971e-06 0.0338087 -0.0397976 -0.0150958 0.0338087 -0.0344654 -0.0164208 0.0311587 -0.0321704 -0.0133389 0.0338087 -0.0327084 -0.0158149 0.0311587 -0.031649 -0.0126958 0.0338087 -0.0303084 -0.0153458 0.0311587 -0.0303084 -0.0164208 0.0311587 -0.0284465 -0.0158149 0.0311587 -0.0289679 -0.0156338 0.0311587 -0.0292334 -0.0153997 0.0311587 -0.02983 -0.0349958 0.0338087 0.00480244 -0.0325958 0.0338087 0.00415936 -0.0331338 0.0311587 0.00107744 -0.0308389 0.0338087 0.00240244 -0.0301958 0.0338087 2.44063e-06 -0.0308389 0.0338087 -0.00239756 -0.0325958 0.0338087 -0.00415448 -0.028224 0.0338087 0.0218271 -0.0265539 0.0338087 0.0204952 -0.025627 0.0338087 0.0185705 -0.0282106 0.0311587 0.017024 -0.0303067 0.0311587 0.0153524 -0.0303067 0.0338087 0.0127024 -0.0130231 0.0338087 -0.0364317 -0.0180887 0.0338087 -0.037568 0.0131028 0.0338087 -0.00404259 -0.0239012 0.0338087 -0.0169013 0.00891069 0.0338087 0.0100142 -0.0222958 0.0338087 0.0303133 -0.0180887 0.0338087 0.0375728 -0.0208936 0.0338087 0.0256301 -0.0230307 0.0338087 0.0211924 -0.021712 0.0338087 0.0194566 -0.0215499 0.0338087 0.0156334 -0.0216563 0.0338087 0.0222884 -0.0174958 0.0338087 0.0255133 -0.00667249 0.0338087 0.0285868 -0.00927491 0.0338087 0.0406569 -0.0107683 0.0338087 0.0373687 -0.00891808 0.0338087 0.0100001 -0.00419286 0.0338087 0.0127282 -0.0129054 0.0338087 0.0329309 -0.0121427 0.0338087 0.0313471 -0.0126958 0.0338087 0.0303133 -0.00510446 0.0338087 0.0338098 -0.00220936 0.0338087 0.0143892 -0.00181284 0.0338087 0.0156452 -0.0016057 0.0338087 0.0201629 -0.00288714 0.0338087 0.0266727 -0.0349958 0.0338087 -0.00479756 -0.0364299 0.0338087 -0.00495189 -0.0296745 0.0338087 -0.00495189 -0.0397958 0.0338087 2.44063e-06 -0.0364299 0.0338087 0.00495677 -0.0407458 0.0338087 0.00495677 0.0110379 0.0338087 -0.0303842 0.0124837 0.0338087 -0.03183 0.0130129 0.0338087 -0.033805 0.0195869 0.0338087 -0.0346331 0.0213321 0.0338087 -0.0267213 0.034472 0.0338087 0.0151024 0.034472 0.0338087 0.0199024 0.0326066 0.0338087 0.026002 0.0267279 0.0338087 0.0213304 0.0265623 0.0338087 0.0204952 0.0256354 0.0338087 0.0164343 0.0265623 0.0338087 0.0145097 0.0300203 0.0338087 0.0222934 0.0296602 0.0338087 0.0222576 0.0302093 0.0338087 0.0287521 0.0290775 0.0338087 0.0221402 0.0292883 0.0338087 0.0296897 -0.0110295 0.0338087 -0.0372258 -0.00927491 0.0338087 -0.0406521 4.20971e-06 0.0338087 -0.0416976 4.20971e-06 0.0338087 -0.0292756 -0.0110295 0.0338087 -0.0303842 -0.0124753 0.0338087 -0.03183 -0.00596622 0.0338087 -0.0362677 -0.00467544 0.0338087 -0.0360657 -0.00520349 0.0338087 -0.0346839 -0.00467544 0.0338087 -0.0339295 -0.00520349 0.0338087 -0.032926 -0.00374858 0.0338087 -0.0320048 -0.00374858 0.0338087 -0.0379903 -0.00207843 0.0338087 -0.0393222 0.00416113 0.0338087 -0.0373976 0.00480421 0.0338087 -0.0349976 -0.0222958 0.0338087 -0.0303084 -0.0259953 0.0338087 -0.0325999 -0.0216527 0.0338087 -0.0327084 -0.0198958 0.0338087 -0.0344654 -0.0174958 0.0338087 -0.0351084 -0.0174958 0.0338087 -0.0255084 -0.0198958 0.0338087 -0.0261515 -0.0227695 0.0338087 -0.0281671 -0.00203732 0.0338087 -0.0246598 -0.0150958 0.0338087 -0.0261515 -0.0133389 0.0338087 -0.0279084 -0.00793783 0.0338087 -0.0284084 -0.0128176 0.0338087 -0.0292341 -0.00415222 0.0338087 -0.027849 -0.0325982 0.0338087 0.026002 -0.0375662 0.0338087 0.0180954 -0.0344636 0.0338087 0.0199024 -0.0344636 0.0338087 0.0151024 -0.0338032 0.0338087 0.0130111 -0.0230307 0.0338087 0.02831 -0.0259953 0.0338087 0.0326048 -0.0286945 0.0338087 0.0247512 -0.0239012 0.0338087 0.0117824 -0.028224 0.0338087 0.0131778 -0.0265539 0.0338087 0.0145097 -0.025627 0.0338087 0.0164343 -0.0267195 0.0338087 0.0213304 -0.0281653 0.0338087 0.0227762 0.0300329 0.0338087 0.00495677 0.0318366 0.0338087 0.00564031 0.0290775 0.0338087 0.0128647 0.0291036 0.0338087 0.0117824 0.0303151 0.0338087 0.0127024 0.0357866 0.0338087 0.0124819 0.0406587 0.0338087 0.00928156 0.0357866 0.0338087 0.00564031 0.0372324 0.0338087 0.0110361 0.0199042 0.0338087 0.0261564 0.00794625 0.0338087 0.0284132 0.0281737 0.0338087 0.0267262 0.0260037 0.0338087 0.0326048 0.0247529 0.0338087 0.0287012 0.0227779 0.0338087 0.028172 0.0239097 0.0338087 0.0117824 0.0203416 0.0338087 0.0141016 0.0215583 0.0338087 0.0156334 0.0137514 0.0338087 0.0333061 0.0128246 0.0338087 0.0313814 0.0121511 0.0338087 0.0313471 0.0206377 0.0338087 0.0210859 0.0137514 0.0338087 0.0273206 0.0147542 0.0338087 0.0255502 0.0128246 0.0338087 0.0292452 0.00906288 0.0338087 0.0298598 0.00906288 0.0338087 0.0377598 0.0213321 0.0338087 0.0267262 0.0129138 0.0338087 0.0346888 0.0121511 0.0338087 0.0362726 0.0154216 0.0338087 0.034638 0.0175042 0.0338087 0.0351133 0.0199042 0.0338087 0.0344703 0.0180972 0.0338087 0.0375728 0.0216611 0.0338087 0.0327133 0.0240184 0.0338087 0.0340936 0.00708788 0.0338087 0.0372306 0.00564208 0.0338087 0.0357848 0.00668091 0.0338087 0.0285868 -0.0299522 0.0338087 0.00818215 -0.0320894 0.0338087 0.00550228 -0.0351067 0.0338087 0.0175024 -0.037224 0.0338087 0.0110361 -0.0318282 0.0338087 -0.012477 -0.0296745 0.0338087 -0.0169013 -0.0338032 0.0338087 -0.0130062 -0.0364299 0.0338087 -0.0169013 -0.0298532 0.0338087 -0.00905623 -0.0391527 0.0338087 -0.00239756 -0.0377532 0.0338087 0.00906111 -0.0406503 0.0338087 -0.00927668 -0.0407458 0.0338087 -0.00495189 -0.0281653 0.0338087 -0.0227713 -0.0325982 0.0338087 -0.0259971 -0.0281653 0.0338087 -0.0267213 -0.029505 0.0338087 -0.029461 -0.0267195 0.0338087 -0.0281671 -0.0239012 0.0338087 -0.0292756 -0.0247445 0.0338087 -0.0286963 0.0127042 0.0338087 -0.0303084 0.0133473 0.0338087 -0.0327084 0.0151042 0.0338087 -0.0344654 0.0124837 0.0338087 -0.03578 0.0180972 0.0338087 -0.037568 0.0110379 0.0338087 -0.0372258 0.00906288 0.0338087 -0.037755 0.00495854 0.0338087 -0.0364317 0.00890854 0.0338087 -0.0292756 0.00495854 0.0338087 -0.0292756 0.00521191 0.0338087 -0.0346839 0.0267279 0.0338087 -0.0281671 0.0239097 0.0338087 -0.0292756 0.0227779 0.0338087 -0.0281671 0.0221839 0.0338087 -0.0292403 0.0195869 0.0338087 -0.0259838 0.0213321 0.0338087 -0.0227713 0.0147542 0.0338087 -0.0255453 0.0267279 0.0338087 -0.0213255 0.0291036 0.0338087 -0.0169013 0.0406587 0.0338087 -0.00927668 0.0372324 0.0338087 -0.0110312 0.0338116 0.0338087 -0.00510623 0.0357866 0.0338087 -0.00563543 0.0414053 0.0338087 -0.00498111 0.00456002 0.0338087 0.028081 0.00511288 0.0338087 0.0338098 0.00564208 0.0338087 0.0318348 0.00221778 0.0338087 0.0143892 0.00420128 0.0338087 0.0127282 0.00289556 0.0338087 0.0266727 0.00161412 0.0338087 0.0201629 4.20971e-06 0.0338087 0.0117824 0.00182126 0.0338087 0.0156452 0.0135703 0.0338087 0.00527881 0.0113567 0.0338087 0.00911283 0.0144597 0.0338087 0.0062502 0.0126427 0.0338087 0.00939742 0.0182686 0.0338087 0.00868845 0.0166587 0.0338087 0.0114769 -0.0100482 0.0338087 0.00932367 4.20971e-06 0.0338087 0.00495677 -0.0113483 0.0338087 0.00911283 -0.0203332 0.0338087 -0.0140967 -0.0166503 0.0338087 -0.011472 -0.0126343 0.0338087 -0.00939254 -0.0144513 0.0338087 0.0062502 -0.0182602 0.0338087 0.00868845 -0.0240186 0.0338087 0.0108624 -0.0296745 0.0338087 0.0117824 -0.0296745 0.0338087 0.00495677 -0.0294958 0.0338087 2.44063e-06 -0.0277017 0.0338087 -0.00907723 -0.0261941 0.0338087 -0.0103237 -0.0144513 0.0338087 -0.00624531 -0.0135619 0.0338087 -0.00527393 -0.0130944 0.0338087 -0.00404259 -0.0130231 0.0338087 -0.00495189 -0.0130231 0.0338087 0.00495677 -0.0016057 0.0338087 -0.020158 -0.00181284 0.0338087 -0.0156403 4.20971e-06 0.0338087 -0.0169013 -0.00220936 0.0338087 -0.0143843 -0.00304201 0.0338087 -0.0133638 4.20971e-06 0.0338087 -0.00495189 -0.00891808 0.0338087 -0.0099952 0.0112569 0.0338087 -0.00910652 0.0100099 0.0338087 -0.00933623 0.00892649 0.0338087 -0.0099952 0.0126427 0.0338087 -0.00939254 0.0135703 0.0338087 -0.00527393 0.0144597 0.0338087 -0.00624531 0.0166587 0.0338087 -0.011472 0.0203416 0.0338087 -0.0140967 0.0223831 0.0338087 -0.0105607 0.0215583 0.0338087 -0.0156285 0.00276392 0.0338087 -0.0264794 0.00416064 0.0338087 -0.027849 0.0151042 0.0338087 -0.0261515 0.0175042 0.0338087 -0.0255084 0.00161412 0.0338087 -0.020158 0.00305043 0.0338087 -0.0133638 0.00495854 0.0338087 -0.00495189 0.027649 0.0338087 0.00915755 0.0260286 0.0338087 0.0104149 0.0239097 0.0338087 -0.0169013 0.0220461 0.0338087 -0.0175229 0.0131028 0.0338087 0.00404747 0.00890854 0.0338087 0.00495677 0.0131236 0.0338087 -0.00272566 0.0295134 0.0338087 -0.029461 0.0292883 0.0338087 -0.0296848 0.0221839 0.0338087 -0.0313765 0.0299606 0.0338087 -0.00817727 0.0300329 0.0338087 -0.0169013 0.0320978 0.0338087 -0.0126151 0.0375746 0.0338087 -0.0180905 0.0302042 0.0338087 2.44063e-06 0.0308473 0.0338087 -0.00239756 0.0338116 0.0338087 0.00511111 0.0417042 0.0338087 2.44063e-06 0.0398042 0.0338087 2.44063e-06 0.0391611 0.0338087 0.00240244 0.0350042 0.0338087 -0.00479756 0.0374042 0.0338087 -0.00415448 0.0391611 0.0338087 -0.00239756 -0.0368914 0.0338087 -0.011519 -0.0380981 0.0338087 -0.0169418 -0.0375662 0.0338087 -0.0180905 0.0291036 0.0338087 -0.0292756 0.0298659 0.0338087 -0.0291037 0.0296829 0.0338087 -0.0169013 0.0291036 0.0338087 -0.00495189 0.0296829 0.0338087 -0.00495189 0.0277101 0.0338087 -0.00907723 0.0296829 0.0338087 0.00495677 0.0300329 0.0338087 -0.00495189 0.00503445 0.0338087 0.0124225 0.00596663 0.0338087 0.0120028 0.00495854 0.0338087 0.00495677 0.00890854 0.0338087 -0.00495189 0.0295042 0.0338087 2.44063e-06 0.0291036 0.0338087 0.00495677 0.0285797 0.0338087 0.00732983 0.0298616 0.0338087 0.00906111 0.0296829 0.0338087 0.0117824 0.0300329 0.0338087 0.0117824 0.0303908 0.0338087 0.0110361 0.00495854 0.0338087 0.0117824 -0.0199956 0.0338087 -0.0365885 -0.0182189 0.0335087 -0.0378383 -0.0261824 0.0335087 -0.0328345 -0.0328327 0.0335087 -0.0261841 -0.0419958 0.0335087 2.44063e-06 -0.0416958 0.0338087 2.44063e-06 -0.0406503 0.0338087 0.00928156 -0.0298575 0.0338087 0.0291086 -0.0328327 0.0335087 0.026189 -0.0182189 0.0335087 0.0378431 -0.02401 0.0338087 0.0340936 -0.0131078 0.0338087 0.0395873 -0.00934167 0.0335087 0.0409494 4.20971e-06 0.0335087 0.0420024 -0.00934167 0.0333087 0.0409494 -0.0261824 0.0335087 0.0328394 -0.0261824 0.0333087 0.0328394 -0.0378365 0.0335087 0.0182256 -0.0409428 0.0335087 0.00934832 -0.0409428 0.0333087 0.00934832 -0.0409428 0.0335087 -0.00934344 -0.0378365 0.0335087 -0.0182207 -0.0378365 0.0333087 -0.0182207 -0.0328327 0.0333087 -0.0261841 -0.0261824 0.0333087 -0.0328345 -0.0182189 0.0333087 -0.0378383 -0.00934167 0.0335087 -0.0409445 4.20971e-06 0.0333087 -0.0419976 -0.0174958 0.0338087 0.0351133 -0.0156338 0.0311587 0.0313883 -0.0150958 0.0338087 0.0344703 -0.0133389 0.0338087 0.0327133 -0.0156338 0.0311587 0.0292383 -0.0133389 0.0338087 0.0279133 -0.0164208 0.0311587 0.0284514 -0.0150958 0.0338087 0.0261564 -0.00911783 0.0310087 -0.010219 -0.0125155 0.0335087 -0.00966802 -0.0112485 0.0335087 -0.00940652 -0.0164939 0.0310087 -0.011728 -0.0125155 0.0310087 -0.00966802 -0.0164939 0.0335087 -0.011728 -0.0212813 0.0310087 -0.0157621 -0.0217379 0.0335087 -0.0175356 -0.021433 0.0335087 -0.0193413 -0.0217379 0.0310087 -0.0175356 -0.0145958 0.0310087 -0.0252855 -0.0145958 0.0335087 -0.0252855 -0.0204194 0.0335087 -0.0208666 -0.00785707 0.0335087 -0.0281194 -0.00667249 0.0335087 -0.0282819 -0.00785707 0.0310087 -0.0281194 -0.00211081 0.0335087 -0.0156752 -0.00428682 0.0310087 -0.0130082 -0.00323461 0.0335087 -0.0135938 -0.0184037 0.0310087 0.00842499 -0.0184037 0.0335087 0.00842499 -0.0224797 0.0335087 0.0102845 -0.0274094 0.0335087 0.00896638 -0.0291958 0.0335087 2.44063e-06 -0.0282807 0.0310087 0.00725532 -0.0282807 0.0335087 0.00725532 -0.0282807 0.0310087 -0.00725044 -0.0274094 0.0310087 -0.00896149 -0.0260552 0.0335087 -0.0100578 -0.024291 0.0335087 -0.0105491 -0.0184037 0.0310087 -0.00842011 -0.0224797 0.0310087 -0.0102796 -0.0224797 0.0335087 -0.0102796 -0.0134089 0.0335087 -0.00278674 -0.0146305 0.0310087 0.00600959 -0.0146305 0.0335087 0.00600959 -0.0138173 0.0335087 0.00512146 -0.0133899 0.0310087 0.00399567 -0.00190561 0.0335087 0.0201554 -0.00431309 0.0310087 0.0276007 -0.00468697 0.0335087 0.0278133 -0.00602937 0.0335087 0.0282395 -0.00602937 0.0310087 0.0282395 -0.00785707 0.0310087 0.0281243 -0.021433 0.0335087 0.0193462 -0.0217379 0.0335087 0.0175405 -0.0212813 0.0335087 0.015767 -0.0125155 0.0310087 0.0096729 -0.0201423 0.0310087 0.014333 -0.0101511 0.0335087 0.00960547 -0.0112485 0.0310087 0.00941141 -0.0125155 0.0335087 0.0096729 -0.00911783 0.0335087 0.0102239 -0.00428682 0.0310087 0.0130131 -0.00211081 0.0335087 0.0156801 -0.00247334 0.0310087 0.0145317 -0.00247334 0.0335087 0.0145317 -0.00323461 0.0335087 0.0135987 0.0201507 0.0335087 0.014333 0.0165023 0.0335087 0.0117329 0.0125239 0.0310087 0.0096729 0.0201507 0.0310087 0.014333 0.0212897 0.0310087 0.015767 0.0217464 0.0335087 0.0175405 0.0217464 0.0310087 0.0175405 0.0214415 0.0335087 0.0193462 0.0204278 0.0335087 0.0208714 0.0146042 0.0310087 0.0252904 0.0146042 0.0335087 0.0252904 0.00786549 0.0335087 0.0281243 0.00786549 0.0310087 0.0281243 0.00313718 0.0335087 0.0264948 0.00301394 0.0310087 0.0263185 0.0023416 0.0310087 0.0246151 0.00211923 0.0335087 0.0156801 0.00324303 0.0310087 0.0135987 0.0125239 0.0335087 0.0096729 0.0113482 0.0335087 0.00941271 0.0101168 0.0310087 0.00962142 0.0101595 0.0335087 0.00960547 0.0184121 0.0310087 -0.00842011 0.0184121 0.0335087 -0.00842011 0.0224881 0.0310087 -0.0102796 0.0292042 0.0310087 2.44063e-06 0.0292042 0.0335087 2.44063e-06 0.0282891 0.0335087 0.00725532 0.0274178 0.0335087 0.00896638 0.027475 0.0310087 0.00889575 0.0260637 0.0310087 0.0100627 0.0242995 0.0310087 0.010554 0.0184121 0.0335087 0.00842499 0.0133983 0.0310087 0.00399567 0.0138257 0.0310087 0.00512146 0.0133983 0.0335087 0.00399567 0.0138257 0.0335087 0.00512146 0.0134173 0.0310087 -0.00278674 0.0134173 0.0335087 -0.00278674 0.00191403 0.0310087 -0.0201506 0.0023416 0.0335087 -0.0246102 0.00313718 0.0310087 -0.02649 0.00432151 0.0335087 -0.0275958 0.00469539 0.0335087 -0.0278084 0.00668091 0.0335087 -0.0282819 0.0214415 0.0335087 -0.0193413 0.0214415 0.0310087 -0.0193413 0.0217464 0.0335087 -0.0175356 0.0217464 0.0310087 -0.0175356 0.0201507 0.0335087 -0.0143281 0.0212897 0.0310087 -0.0157621 0.0201507 0.0310087 -0.0143281 0.00912625 0.0335087 -0.010219 0.0101168 0.0335087 -0.00961654 0.0112569 0.0310087 -0.00940652 0.00211923 0.0310087 -0.0156752 0.00248176 0.0335087 -0.0145268 0.00324303 0.0310087 -0.0135938 0.00429524 0.0310087 -0.0130082 0.00324303 0.0335087 -0.0135938 0.00429524 0.0335087 -0.0130082 4.20971e-06 0.0310087 0.0110024 0.00860436 0.0328087 0.00686083 0.0107284 0.0310087 -0.00244529 0.00860436 0.0310087 -0.00685595 0.00860436 0.0328087 -0.00685595 0.00477693 0.0310087 -0.00990822 0.00477693 0.0328087 -0.00990822 4.20971e-06 0.0310087 -0.0109976 -0.0321761 0.0310087 0.0124397 -0.0321761 0.0336087 0.0124397 -0.0308713 0.0310087 0.0113992 -0.0308713 0.0336087 0.0113992 -0.0301472 0.0310087 0.00822665 -0.0301472 0.0336087 0.00822665 -0.0338032 0.0310087 0.00531111 -0.0218127 0.0310087 0.0270893 -0.0210885 0.0336087 0.0255856 -0.0210885 0.0336087 0.0239167 -0.0218127 0.0310087 0.0224131 -0.0231175 0.0336087 0.0213725 -0.00905446 0.0310087 0.0375598 -0.00742739 0.0310087 0.0371885 -0.00742739 0.0336087 0.0371885 -0.00717946 0.0336087 0.0370574 -0.00612259 0.0310087 0.0361479 -0.00580686 0.0310087 0.0356848 -0.00580686 0.0336087 0.0356848 -0.00539848 0.0310087 0.0346443 -0.00530446 0.0310087 0.0338098 -0.00539848 0.0336087 0.0346443 -0.00530446 0.0336087 0.0338098 -0.00580686 0.0336087 0.0319348 -0.00612259 0.0310087 0.0314718 -0.00612259 0.0336087 0.0314718 -0.00717946 0.0310087 0.0305622 -0.00742739 0.0336087 0.0304312 -0.00905446 0.0310087 0.0300598 0.0106899 0.0310087 0.0371885 0.0106899 0.0336087 0.0371885 0.0119947 0.0336087 0.0361479 0.0127189 0.0310087 0.0346443 0.0127189 0.0336087 0.0346443 0.0106899 0.0336087 0.0304312 0.0266279 0.0310087 0.0279988 0.0285029 0.0336087 0.0247512 0.0280005 0.0310087 0.0228762 0.0280005 0.0336087 0.0228762 0.0266279 0.0336087 0.0215036 0.0338116 0.0310087 0.0128111 0.0356866 0.0336087 0.0123087 0.0356866 0.0310087 0.00581351 0.0356866 0.0336087 0.00581351 0.0338116 0.0336087 0.00531111 0.0356866 0.0336087 -0.00580863 0.0375616 0.0310087 -0.00905623 0.0370592 0.0336087 -0.0109312 0.0356866 0.0310087 -0.0123038 0.0266279 0.0336087 -0.0214987 0.0247529 0.0310087 -0.0284963 0.0109379 0.0310087 -0.0305574 0.0109379 0.0336087 -0.0305574 0.0128129 0.0310087 -0.033805 0.0109379 0.0310087 -0.0370526 0.0109379 0.0336087 -0.0370526 -0.00742739 0.0336087 -0.0304263 -0.00539848 0.0310087 -0.0346394 -0.00539848 0.0336087 -0.0329705 -0.00612259 0.0310087 -0.036143 -0.00742739 0.0336087 -0.0371836 -0.0247445 0.0310087 -0.0209963 -0.0228695 0.0310087 -0.0214987 -0.0214969 0.0310087 -0.0228713 -0.0209945 0.0310087 -0.0247463 -0.0228695 0.0310087 -0.0279939 -0.0247445 0.0336087 -0.0284963 -0.0338032 0.0310087 -0.00530623 -0.0319282 0.0310087 -0.00580863 -0.0319282 0.0336087 -0.00580863 -0.0305556 0.0310087 -0.00718123 -0.0300532 0.0310087 -0.00905623 -0.0300532 0.0336087 -0.00905623 -0.0305556 0.0336087 -0.0109312 -0.0319282 0.0310087 -0.0123038 -0.0319282 0.0336087 -0.0123038 0.0175042 0.0311587 0.0324633 0.0193662 0.0311587 0.0313883 0.0196542 0.0311587 0.0303133 0.0193662 0.0311587 0.0292383 0.0313901 0.0308087 0.0193644 0.0313901 0.0311587 0.0193644 0.0321771 0.0308087 0.0185774 0.0321771 0.0311587 0.0185774 0.0324651 0.0308087 0.0175024 0.0321771 0.0308087 0.0164274 0.0313901 0.0308087 0.0156405 0.0313901 0.0311587 0.0156405 0.0368662 0.0308087 0.00107744 0.0371542 0.0308087 2.44063e-06 0.0368662 0.0311587 -0.00107256 0.0360792 0.0311587 -0.00185951 0.0184371 0.0308087 -0.0283714 0.0196003 0.0308087 -0.02983 0.0191851 0.0308087 -0.031649 0.0184371 0.0311587 -0.0322455 0.0175042 0.0311587 -0.0324584 0.00107921 0.0308087 -0.0331356 0.00215421 0.0308087 -0.0349976 0.00186616 0.0311587 -0.0339226 0.00215421 0.0311587 -0.0349976 0.00186616 0.0311587 -0.0360726 0.00186616 0.0308087 -0.0360726 4.20971e-06 0.0308087 -0.0371476 -0.0174958 0.0311587 -0.0281584 -0.0153997 0.0308087 -0.02983 -0.0153997 0.0308087 -0.0307869 -0.0158149 0.0308087 -0.031649 -0.0153997 0.0311587 -0.0307869 -0.0156338 0.0311587 -0.0313834 -0.0165629 0.0308087 -0.0322455 -0.0174958 0.0311587 -0.0324584 -0.0349958 0.0308087 0.00215244 -0.0339208 0.0308087 0.0018644 -0.0339208 0.0311587 0.0018644 -0.0328458 0.0311587 2.44063e-06 -0.0331338 0.0311587 -0.00107256 -0.0339208 0.0311587 -0.00185951 -0.0349958 0.0308087 -0.00214756 -0.0293738 0.0308087 0.0194395 -0.0293738 0.0311587 0.0194395 -0.0286257 0.0308087 0.0188429 -0.0286257 0.0311587 0.0188429 -0.0282106 0.0311587 0.0179809 -0.0282106 0.0308087 0.0179809 -0.0286257 0.0311587 0.0161619 -0.0286257 0.0308087 0.0161619 -0.0293738 0.0308087 0.0155654 -0.0293738 0.0311587 0.0155654 -0.0174958 0.0311587 0.0324633 -0.0164208 0.0311587 0.0321753 -0.0153458 0.0311587 0.0303133 -0.0156338 0.0308087 0.0292383 -0.0164208 0.0308087 0.0284514 -0.0174958 0.0308087 0.0281633 -0.0101511 0.0310087 -0.00960059 -0.0113397 0.0310087 -0.00940782 -0.0201423 0.0310087 -0.0143281 -0.0219378 0.0308087 -0.0175271 -0.021433 0.0310087 -0.0193413 -0.021619 0.0308087 -0.0194149 -0.0204194 0.0310087 -0.0208666 -0.00791091 0.0308087 -0.0283121 -0.00213594 0.0308087 -0.0246433 -0.00190561 0.0310087 -0.0201506 -0.00211081 0.0310087 -0.0156752 -0.00247334 0.0310087 -0.0145268 -0.00323461 0.0310087 -0.0135938 -0.00310621 0.0308087 -0.0134405 -0.0224797 0.0310087 0.0102845 -0.0224097 0.0308087 0.0104719 -0.024291 0.0310087 0.010554 -0.0243034 0.0308087 0.0107536 -0.0260552 0.0310087 0.0100627 -0.0274666 0.0310087 0.00889575 -0.0276233 0.0308087 0.00901999 -0.0284744 0.0308087 0.00730499 -0.0291958 0.0310087 2.44063e-06 -0.0258924 0.0310087 -0.0101386 -0.0259776 0.0308087 -0.0103195 -0.0240186 0.0308087 -0.0107575 -0.018308 0.0308087 -0.00859575 -0.0146305 0.0310087 -0.00600471 -0.0138173 0.0310087 -0.00511658 -0.0145111 0.0308087 -0.00616511 -0.0133899 0.0310087 -0.00399078 -0.0134089 0.0310087 -0.00278674 -0.0134089 0.0310087 0.00279162 -0.0131929 0.0308087 0.0040302 -0.0138173 0.0310087 0.00512146 -0.013647 0.0308087 0.00522636 -0.0145111 0.0308087 0.00616999 -0.00211081 0.0310087 0.0156801 -0.00190561 0.0310087 0.0201554 -0.00191216 0.0308087 0.0156568 -0.00213594 0.0308087 0.0246482 -0.00233318 0.0310087 0.0246151 -0.00300552 0.0310087 0.0263185 -0.00283884 0.0308087 0.026429 -0.00600014 0.0308087 0.0284374 -0.0146958 0.0308087 0.0254636 -0.0145958 0.0310087 0.0252904 -0.0122526 0.0308087 0.0267256 -0.0204194 0.0310087 0.0208714 -0.0205593 0.0308087 0.0210144 -0.021433 0.0310087 0.0193462 -0.0217379 0.0310087 0.0175405 -0.0212813 0.0310087 0.015767 -0.0219378 0.0308087 0.017532 -0.0214604 0.0308087 0.0156779 -0.0202696 0.0308087 0.0141787 -0.0164939 0.0310087 0.0117329 -0.0112485 0.0308087 0.00921141 -0.00911783 0.0310087 0.0102239 -0.00422418 0.0308087 0.0128232 -0.00323461 0.0310087 0.0135987 -0.00229736 0.0308087 0.0144367 0.0165023 0.0310087 0.0117329 0.020278 0.0308087 0.0141787 0.0219462 0.0308087 0.017532 0.0214415 0.0310087 0.0193462 0.0216274 0.0308087 0.0194198 0.0204278 0.0310087 0.0208714 0.0147042 0.0308087 0.0254636 0.00791933 0.0308087 0.0283169 0.00603779 0.0310087 0.0282395 0.00432151 0.0310087 0.0276007 0.00284726 0.0308087 0.026429 0.00214436 0.0308087 0.0246482 0.00191403 0.0310087 0.0201554 0.00211923 0.0310087 0.0156801 0.00171409 0.0308087 0.0201604 0.00248176 0.0310087 0.0145317 0.00192058 0.0308087 0.0156568 0.00230578 0.0308087 0.0144367 0.00311463 0.0308087 0.0134454 0.00429524 0.0310087 0.0130131 0.0042326 0.0308087 0.0128232 0.00912625 0.0310087 0.0102239 0.00899308 0.0308087 0.0100747 0.0100455 0.0308087 0.00943455 0.0112569 0.0310087 0.00941141 0.0112569 0.0308087 0.00921141 0.0183165 0.0308087 -0.00859575 0.0224181 0.0308087 -0.010467 0.0284828 0.0308087 -0.00730011 0.0282891 0.0310087 0.00725532 0.0284828 0.0308087 0.00730499 0.0224881 0.0310087 0.0102845 0.0183165 0.0308087 0.00860063 0.0184121 0.0310087 0.00842499 0.0146389 0.0310087 0.00600959 0.0145195 0.0308087 0.00616999 0.0134173 0.0310087 0.00279162 0.0132013 0.0308087 0.0040302 0.0133983 0.0310087 -0.00399078 0.0132215 0.0308087 -0.00274602 0.0132013 0.0308087 -0.00402532 0.0138257 0.0310087 -0.00511658 0.0146389 0.0310087 -0.00600471 0.0145195 0.0308087 -0.00616511 0.0023416 0.0310087 -0.0246102 0.00171409 0.0308087 -0.0201555 0.0029761 0.0308087 -0.0266085 0.00469539 0.0310087 -0.0278084 0.00668091 0.0310087 -0.0282819 0.0204278 0.0310087 -0.0208666 0.0146042 0.0310087 -0.0252855 0.00791933 0.0308087 -0.0283121 0.0205677 0.0308087 -0.0210095 0.020278 0.0308087 -0.0141739 0.0165023 0.0310087 -0.011728 0.0166066 0.0308087 -0.0115573 0.0125239 0.0310087 -0.00966802 0.0100909 0.0308087 -0.00941272 0.0126031 0.0308087 -0.00948437 0.0113482 0.0310087 -0.00940782 0.0113539 0.0308087 -0.00920791 0.0101595 0.0310087 -0.00960059 0.00912625 0.0310087 -0.010219 0.0042326 0.0308087 -0.0128183 0.00311463 0.0308087 -0.0134405 0.00248176 0.0310087 -0.0145268 0.00486371 0.0308087 -0.0100884 0.00876072 0.0308087 -0.00698065 0.0109234 0.0308087 -0.00248979 0.0107284 0.0310087 0.00245017 0.00860436 0.0310087 0.00686083 0.00477693 0.0310087 0.0099131 0.00486371 0.0308087 0.0100933 4.20971e-06 0.0308087 0.0112024 -0.0321761 0.0310087 0.00568247 -0.0320894 0.0308087 0.00550228 -0.0308713 0.0310087 0.00672302 -0.030715 0.0308087 0.00659832 -0.0299522 0.0308087 0.00818215 -0.0301472 0.0310087 0.00989556 -0.0299522 0.0308087 0.00994006 -0.0338032 0.0310087 0.0128111 -0.0231175 0.0310087 0.0213725 -0.0247445 0.0308087 0.0208012 -0.0210885 0.0310087 0.0239167 -0.0216563 0.0308087 0.0222884 -0.0208936 0.0308087 0.0238722 -0.0210885 0.0310087 0.0255856 -0.0208936 0.0308087 0.0256301 -0.0216563 0.0308087 0.027214 -0.0231175 0.0310087 0.0281298 -0.0230307 0.0308087 0.02831 -0.00707946 0.0308087 0.0372306 -0.00717946 0.0310087 0.0370574 -0.00563366 0.0308087 0.0357848 -0.00510446 0.0308087 0.0338098 -0.00539848 0.0310087 0.0329754 -0.00580686 0.0310087 0.0319348 -0.00707946 0.0308087 0.030389 -0.00905446 0.0308087 0.0298598 -0.00742739 0.0310087 0.0304312 0.00906288 0.0310087 0.0375598 0.00943287 0.0308087 0.0377425 0.0106899 0.0310087 0.0304312 0.00906288 0.0308087 0.0298598 0.0107767 0.0308087 0.030251 0.0119947 0.0310087 0.0314718 0.0127189 0.0310087 0.0329754 0.0121511 0.0308087 0.0313471 0.0129138 0.0308087 0.0329309 0.0129138 0.0308087 0.0346888 0.0119947 0.0310087 0.0361479 0.0280005 0.0310087 0.0266262 0.0266279 0.0310087 0.0215036 0.0285029 0.0310087 0.0247512 0.0287029 0.0308087 0.0247512 0.0279737 0.0308087 0.0270379 0.0370592 0.0310087 0.0109361 0.0357866 0.0308087 0.0124819 0.0372324 0.0308087 0.0110361 0.0356866 0.0310087 0.0123087 0.0338116 0.0310087 0.00531111 0.0370592 0.0310087 0.00718611 0.0375616 0.0310087 0.00906111 0.0372324 0.0308087 0.00708611 0.0377616 0.0308087 0.00906111 0.0370592 0.0310087 -0.00718123 0.0356866 0.0310087 -0.00580863 0.0374024 0.0308087 -0.0107021 0.0370592 0.0310087 -0.0109312 0.0372324 0.0308087 -0.0110312 0.0285029 0.0310087 -0.0247463 0.0280005 0.0310087 -0.0228713 0.0266279 0.0310087 -0.0214987 0.0266279 0.0310087 -0.0279939 0.0270397 0.0308087 -0.0279671 0.0280005 0.0310087 -0.0266213 0.00906288 0.0308087 -0.029855 0.0110379 0.0308087 -0.0303842 0.0124837 0.0308087 -0.03183 0.0123105 0.0310087 -0.03193 0.0123105 0.0310087 -0.03568 0.0107088 0.0308087 -0.0373957 0.00943287 0.0308087 -0.0377376 0.00906288 0.0310087 -0.037555 -0.00905446 0.0310087 -0.037555 -0.00742739 0.0310087 -0.0371836 -0.00734062 0.0308087 -0.0373638 -0.00539848 0.0310087 -0.0329705 -0.00612259 0.0310087 -0.0314669 -0.00742739 0.0310087 -0.0304263 -0.00596622 0.0308087 -0.0313422 -0.0247445 0.0310087 -0.0284963 -0.0214969 0.0310087 -0.0266213 -0.0213237 0.0308087 -0.0267213 -0.0338032 0.0310087 -0.0128062 -0.0305556 0.0310087 -0.0109312 -0.0318282 0.0308087 -0.012477 -0.0303824 0.0308087 -0.0110312 -0.0298532 0.0308087 -0.00905623 -0.0303824 0.0308087 -0.00708123 -0.0318282 0.0308087 -0.00563543 -0.0107004 0.0308087 0.0374006 -0.0384776 0.0308087 0.00569091 -0.0328458 0.0308087 2.44063e-06 -0.0363679 0.0308087 -0.0137917 0.00734904 0.0308087 -0.0302461 0.00597464 0.0308087 -0.0313422 0.0208173 0.0308087 -0.0328613 0.0142522 0.0308087 -0.032653 0.0281737 0.0308087 -0.0267213 0.0279737 0.0308087 -0.027033 0.0377616 0.0308087 -0.00905623 0.038486 0.0308087 -0.00568603 0.032786 0.0308087 0.0209444 0.0363763 0.0308087 0.0137966 0.0270397 0.0308087 0.0279719 0.0257997 0.0308087 0.0291195 0.0136554 0.0308087 -0.00522148 0.0136554 0.0308087 0.00522636 -0.0121427 0.0308087 0.0313471 -0.0131929 0.0308087 -0.00402532 -0.013647 0.0308087 -0.00522148 0.0153542 0.0308087 -0.0303084 0.0208029 0.0308087 -0.0247463 0.0213321 0.0308087 -0.0267213 0.0191851 0.0308087 -0.0289679 0.0196003 0.0308087 -0.0307869 0.0175042 0.0308087 -0.0324584 0.0184371 0.0308087 -0.0322455 -0.00209189 0.0308087 -0.0345191 -0.00942445 0.0308087 -0.0377376 -0.00905446 0.0308087 -0.037755 -0.00092864 0.0308087 -0.0369346 -0.00520349 0.0308087 -0.032926 -0.00520349 0.0308087 -0.0346839 -0.00596622 0.0308087 -0.0362677 4.20971e-06 0.0308087 -0.0328476 0.00107921 0.0308087 -0.0368595 0.00670698 0.0308087 -0.0383157 -0.0185708 0.0308087 -0.0284465 -0.0146958 0.0308087 -0.0254587 -0.0165629 0.0308087 -0.0283714 -0.0185708 0.0308087 -0.0321704 -0.0130045 0.0308087 -0.033805 -0.0113454 0.0308087 -0.00920791 -0.00422418 0.0308087 -0.0128183 -0.00485529 0.0308087 -0.0100884 -0.00898466 0.0308087 -0.0100698 -0.0100825 0.0308087 -0.00941272 -0.0250493 0.0308087 -0.019678 -0.0125947 0.0308087 -0.00948437 -0.0165982 0.0308087 -0.0115573 -0.0202696 0.0308087 -0.0141739 -0.0224097 0.0308087 -0.010467 -0.0214604 0.0308087 -0.015673 -0.0227695 0.0308087 -0.0281671 -0.00296768 0.0308087 -0.0266085 -0.00459672 0.0308087 -0.0279869 -0.00229736 0.0308087 -0.0144318 -0.00191216 0.0308087 -0.0156519 -0.00170567 0.0308087 -0.0201555 -0.0158149 0.0308087 -0.0289679 -0.0121688 0.0308087 -0.0304702 -0.00905446 0.0308087 -0.029855 -0.00667249 0.0308087 -0.0284819 -0.0261478 0.0308087 0.01024 -0.0320894 0.0308087 0.0126199 -0.018308 0.0308087 0.00860063 -0.0250493 0.0308087 0.0132774 -0.030715 0.0308087 0.0115239 -0.0293958 0.0308087 2.44063e-06 -0.0284744 0.0308087 -0.00730011 -0.0275636 0.0308087 -0.00908895 -0.013213 0.0308087 0.0027509 -0.0121688 0.0308087 -0.00567704 -0.013213 0.0308087 -0.00274602 -0.00170567 0.0308087 0.0201604 4.20971e-06 0.0308087 0.0132774 -0.00563366 0.0308087 0.0318348 -0.00905446 0.0308087 0.0377598 -0.00791091 0.0308087 0.0283169 -0.00420584 0.0308087 0.0277695 -0.0164208 0.0308087 0.0321753 -0.0180735 0.0308087 0.0344467 -0.0165982 0.0308087 0.0115622 -0.0207938 0.0308087 0.0132774 -0.0125947 0.0308087 0.00948925 -0.0121688 0.0308087 0.00568192 -0.0087523 0.0308087 0.00698553 0.0214688 0.0308087 0.0156779 0.0205677 0.0308087 0.0210144 0.0227779 0.0308087 0.0213304 0.0213321 0.0308087 0.0227762 0.0185792 0.0308087 0.0321753 0.0193662 0.0308087 0.0313883 0.0196542 0.0308087 0.0303133 0.0143277 0.0308087 0.0361694 0.0165714 0.0308087 0.0322504 0.0158233 0.0308087 0.0289728 0.0122611 0.0308087 0.0267256 4.20971e-06 0.0308087 0.0239079 0.00600856 0.0308087 0.0284374 0.00421426 0.0308087 0.0277695 0.00564208 0.0308087 0.0318348 -0.00898466 0.0308087 0.0100747 -0.00485529 0.0308087 0.0100933 -0.00310621 0.0308087 0.0134454 0.0121772 0.0308087 0.00568192 0.0219462 0.0308087 -0.0175271 0.0166066 0.0308087 0.0115622 0.0224181 0.0308087 0.0104719 0.0243118 0.0308087 0.0107536 0.0132215 0.0308087 0.0027509 0.0250577 0.0308087 -0.019678 0.0214688 0.0308087 -0.015673 0.024027 0.0308087 -0.0107575 0.00460514 0.0308087 -0.0279869 4.20971e-06 0.0308087 -0.019678 0.00214436 0.0308087 -0.0246433 4.20971e-06 0.0308087 -0.0111976 0.00192058 0.0308087 -0.0156519 0.0142522 0.0308087 -0.0304702 0.00230578 0.0308087 -0.0144318 0.00899308 0.0308087 -0.0100698 0.00876072 0.0308087 0.00698553 0.0109234 0.0308087 0.00249468 0.0121772 0.0308087 -0.00567704 -0.010915 0.0308087 -0.00248979 -0.0087523 0.0308087 -0.00698065 0.00906288 0.0308087 0.0377598 0.00708788 0.0308087 0.0372306 0.0107767 0.0308087 0.0373687 0.0121511 0.0308087 0.0362726 0.0142746 0.0308087 0.0257068 0.0165714 0.0308087 0.0283762 0.0175042 0.0308087 0.0281633 0.0185792 0.0308087 0.0284514 0.0213321 0.0308087 0.0267262 0.0193662 0.0308087 0.0292383 0.0227779 0.0308087 0.028172 0.0247529 0.0308087 0.0287012 0.025076 0.0308087 0.0286879 0.0267279 0.0308087 0.028172 0.0293822 0.0308087 0.0194395 0.0286342 0.0308087 0.0188429 0.0303151 0.0308087 0.0196524 0.0306317 0.0308087 0.023985 0.0303151 0.0308087 0.0153524 0.0250577 0.0308087 0.0132774 0.0281737 0.0308087 0.0227762 0.0267279 0.0308087 0.0213304 0.0247529 0.0308087 0.0208012 0.0281737 0.0308087 0.0267262 0.0303908 0.0308087 0.00708611 0.0276318 0.0308087 0.00901999 0.0261562 0.0308087 0.01024 0.0326597 0.0308087 0.0132774 0.0338116 0.0308087 0.0130111 0.0331423 0.0308087 0.00107744 0.0307234 0.0308087 -0.00659344 0.0294042 0.0308087 2.44063e-06 0.0320978 0.0308087 -0.0054974 0.0328542 0.0308087 2.44063e-06 0.0360792 0.0308087 0.0018644 0.0360792 0.0308087 -0.00185951 0.0368662 0.0308087 -0.00107256 0.0350042 0.0308087 -0.00214756 0.0357866 0.0308087 -0.00563543 0.0357866 0.0308087 0.00564031 0.0338116 0.0308087 0.00511111 0.0339292 0.0308087 -0.00185951 0.0377442 0.0308087 0.0094311 0.038486 0.0308087 0.00569091 0.0386206 0.0308087 -0.00468644 0.0372324 0.0308087 -0.00708123 0.0363763 0.0308087 -0.0137917 0.0357866 0.0308087 -0.012477 0.027572 0.0308087 -0.00908895 0.0299606 0.0308087 -0.00993518 0.025986 0.0308087 -0.0103195 0.0307234 0.0308087 -0.011519 0.0338116 0.0308087 -0.0130062 0.0326597 0.0308087 -0.019678 0.0164292 0.0308087 -0.0284465 0.0147042 0.0308087 -0.0254587 0.0216274 0.0308087 -0.0194149 0.0247529 0.0308087 -0.0207963 0.0267279 0.0308087 -0.0213255 0.0281737 0.0308087 -0.0227713 0.0287029 0.0308087 -0.0247463 0.0267279 0.0308087 -0.0281671 0.0257997 0.0308087 -0.0291146 0.0227779 0.0308087 -0.0281671 0.0239582 0.0308087 -0.0306475 0.0247529 0.0308087 -0.0286963 0.0180819 0.0308087 -0.0344418 0.0130129 0.0308087 -0.033805 0.0122255 0.0308087 -0.0369279 0.0124837 0.0308087 -0.03578 0.0110379 0.0308087 -0.0372258 0.0121772 0.0308087 -0.0304702 0.0122611 0.0308087 -0.0267208 0.00667921 0.0308087 -0.0304702 4.20971e-06 0.0308087 -0.0304702 4.20971e-06 0.0308087 -0.032653 0.00521191 0.0308087 -0.032926 0.00186616 0.0308087 -0.0339226 0.00521191 0.0308087 -0.0346839 0.00597464 0.0308087 -0.0362677 0.00931359 0.0308087 -0.0377672 -0.00734062 0.0308087 -0.0302461 -0.00092864 0.0308087 -0.0330605 -0.0180735 0.0308087 -0.0344418 -0.0208088 0.0308087 -0.0328613 -0.0193577 0.0308087 -0.0313834 -0.0207938 0.0308087 -0.0304702 -0.020941 0.0308087 -0.0327773 -0.0239498 0.0308087 -0.0306475 -0.0251054 0.0308087 -0.0297081 -0.0257913 0.0308087 -0.0291146 -0.0270313 0.0308087 -0.0279671 -0.0320099 0.0308087 -0.0220953 -0.0281653 0.0308087 -0.0227713 -0.0247445 0.0308087 -0.0207963 -0.0227695 0.0308087 -0.0213255 -0.0205593 0.0308087 -0.0210095 -0.0213237 0.0308087 -0.0227713 -0.0207945 0.0308087 -0.0247463 -0.0326512 0.0308087 -0.019678 -0.035517 0.0308087 -0.0126151 -0.0386122 0.0308087 0.00469132 -0.0331338 0.0308087 0.00107744 -0.0331338 0.0308087 -0.00107256 -0.0339208 0.0308087 -0.00185951 -0.0359286 0.0308087 -0.00193464 -0.035517 0.0308087 -0.0054974 -0.0386122 0.0308087 -0.00468644 -0.0376542 0.0308087 -0.00817727 -0.0368914 0.0308087 -0.00659344 -0.0373939 0.0308087 0.010707 -0.0365584 0.0308087 0.0132834 -0.0321686 0.0308087 0.0164274 -0.0363679 0.0308087 0.0137966 -0.0320099 0.0308087 0.0221002 -0.0282106 0.0308087 0.017024 -0.0326512 0.0308087 0.0132774 -0.0313817 0.0308087 0.0193644 -0.0306233 0.0308087 0.023985 -0.0230307 0.0308087 0.0211924 -0.021619 0.0308087 0.0194198 -0.0207938 0.0308087 0.0239079 -0.0267195 0.0308087 0.028172 -0.020941 0.0308087 0.0327821 -0.0247445 0.0308087 0.0287012 -0.0168732 0.0308087 0.0240755 -0.0153458 0.0308087 0.0303133 -0.0156338 0.0308087 0.0313883 4.20971e-06 0.0308087 -0.0388976 0.00931359 0.0305587 -0.0377672 0.0180819 0.0305587 -0.0344418 0.0320183 0.0305587 -0.0220953 0.0251138 0.0308087 -0.0297081 0.0377442 0.0308087 -0.00942622 0.0320183 0.0308087 -0.0220953 0.0386206 0.0308087 0.00469132 0.0374024 0.0308087 0.010707 0.0320183 0.0308087 0.0221002 0.0107088 0.0308087 0.0374006 0.0122255 0.0308087 0.0369328 0.00931359 0.0305587 0.0377721 0.0180819 0.0308087 0.0344467 4.20971e-06 0.0305587 0.0389024 0.00931359 0.0308087 0.0377721 0.00906288 0.0220087 -0.031705 0.00906288 0.0314087 -0.031705 0.0101129 0.0220087 -0.0319863 0.0101129 0.0314087 -0.0319863 0.0111629 0.0314087 -0.033805 0.0108815 0.0314087 -0.034855 0.00906288 0.0220087 -0.035905 -0.00800446 0.0220087 -0.0319863 -0.00741261 0.0220087 -0.0324956 -0.0072358 0.0220087 -0.032755 -0.00700711 0.0220087 -0.0333377 -0.00695446 0.0220087 -0.033805 -0.00700711 0.0314087 -0.0333377 -0.00700711 0.0314087 -0.0342723 -0.00700711 0.0220087 -0.0342723 -0.0081433 0.0314087 -0.035697 -0.00800446 0.0220087 -0.0356236 -0.0247445 0.0314087 -0.0226463 -0.0238334 0.0314087 -0.0228543 -0.0247445 0.0220087 -0.0226463 -0.0236945 0.0220087 -0.0229276 -0.0231027 0.0314087 -0.023437 -0.0229259 0.0220087 -0.0236963 -0.0226972 0.0314087 -0.0252136 -0.0231027 0.0314087 -0.0260556 -0.0238334 0.0314087 -0.0266383 -0.0231027 0.0220087 -0.0260556 -0.0236945 0.0220087 -0.026565 -0.0247445 0.0314087 -0.0268463 -0.0319845 0.0314087 -0.0101062 -0.0327532 0.0314087 -0.0108749 -0.0338032 0.0220087 -0.0111562 -0.0319845 0.0220087 0.0101111 -0.0317558 0.0314087 0.0095284 -0.0321613 0.0220087 0.00775178 -0.0327532 0.0220087 0.00724245 -0.0247445 0.0314087 0.0268512 -0.0247445 0.0220087 0.0268512 -0.0236945 0.0314087 0.0265698 -0.0236945 0.0220087 0.0265698 -0.0229259 0.0220087 0.0258012 -0.0229259 0.0314087 0.0258012 -0.0226445 0.0220087 0.0247512 -0.0226972 0.0314087 0.0242839 -0.0229259 0.0220087 0.0237012 -0.0247445 0.0220087 0.0226512 -0.0236945 0.0314087 0.0229325 -0.0231027 0.0314087 0.0234418 -0.0081433 0.0220087 0.0357019 -0.00800446 0.0220087 0.0356285 -0.0072358 0.0314087 0.0348598 -0.0072358 0.0220087 0.0348598 -0.00700711 0.0220087 0.0342771 -0.00695446 0.0314087 0.0338098 -0.00695446 0.0220087 0.0338098 -0.00700711 0.0220087 0.0333426 -0.0072358 0.0220087 0.0327598 -0.0072358 0.0314087 0.0327598 -0.00741261 0.0220087 0.0325005 -0.00800446 0.0314087 0.0319912 0.00997403 0.0220087 0.0357019 0.0107047 0.0220087 0.0351192 0.0111102 0.0220087 0.0342771 0.0107047 0.0314087 0.0351192 0.0111102 0.0314087 0.0342771 0.0111102 0.0314087 0.0333426 0.0107047 0.0220087 0.0325005 0.00997403 0.0220087 0.0319178 0.00906288 0.0314087 0.0317098 0.0258029 0.0220087 0.0265698 0.0265716 0.0220087 0.0258012 0.0268003 0.0314087 0.0252185 0.0268529 0.0314087 0.0247512 0.0268529 0.0220087 0.0247512 0.0268003 0.0314087 0.0242839 0.0256641 0.0314087 0.0228591 0.0247529 0.0220087 0.0226512 0.0258029 0.0314087 0.0229325 0.0258029 0.0220087 0.0229325 0.0263948 0.0314087 0.0234418 0.0348616 0.0314087 0.0108798 0.0359116 0.0220087 0.00906111 0.0356303 0.0220087 0.00801111 0.0359116 0.0314087 0.00906111 0.0348616 0.0220087 0.00724245 0.0356303 0.0314087 0.00801111 0.0348616 0.0314087 -0.00723757 0.0354535 0.0220087 -0.0077469 0.0356303 0.0220087 -0.00800623 0.0356303 0.0314087 -0.00800623 0.0359116 0.0314087 -0.00905623 0.035859 0.0220087 -0.00952352 0.0354535 0.0220087 -0.0103656 0.0348616 0.0314087 -0.0108749 0.0265716 0.0314087 -0.0236963 0.0268529 0.0220087 -0.0247463 0.0265716 0.0220087 -0.0257963 0.0258029 0.0314087 -0.026565 0.0104129 0.0320087 -0.0314667 0.0108815 0.0314087 -0.032755 0.0114011 0.0320087 -0.032455 0.0117629 0.0320087 -0.033805 0.0101129 0.0314087 -0.0356236 0.0104129 0.0320087 -0.0361432 -0.0081433 0.0314087 -0.0319129 -0.00741261 0.0314087 -0.0324956 -0.00642215 0.0320087 -0.0344058 -0.00741261 0.0314087 -0.0351143 -0.00694351 0.0320087 -0.0354884 -0.00905446 0.0314087 -0.035905 -0.023573 0.0320087 -0.0223137 -0.0226972 0.0314087 -0.024279 -0.0221122 0.0320087 -0.0241455 -0.0221122 0.0320087 -0.0253471 -0.023573 0.0320087 -0.0271789 -0.0327532 0.0314087 -0.00723757 -0.0319845 0.0314087 -0.00800623 -0.0317032 0.0314087 -0.00905623 -0.0311032 0.0320087 -0.00905623 -0.0338032 0.0314087 0.0111611 -0.0338032 0.0320087 0.0117611 -0.032892 0.0314087 0.0109531 -0.0321613 0.0314087 0.0103704 -0.0317558 0.0314087 0.00859381 -0.0321613 0.0314087 0.00775178 -0.0316922 0.0320087 0.00737768 -0.032892 0.0314087 0.00716907 -0.0238334 0.0314087 0.0228591 -0.0229259 0.0314087 0.0237012 -0.0221122 0.0320087 0.025352 -0.0226445 0.0314087 0.0247512 -0.0226972 0.0314087 0.0252185 -0.0226336 0.0320087 0.0264346 -0.023573 0.0320087 0.0271838 -0.0238334 0.0314087 0.0266432 -0.0231027 0.0314087 0.0260605 -0.00800446 0.0314087 0.0356285 -0.00671619 0.0320087 0.0351598 -0.00635446 0.0320087 0.0338098 -0.00671619 0.0320087 0.0324598 0.00997403 0.0314087 0.0357019 0.0102344 0.0320087 0.0362425 0.0111738 0.0320087 0.0354933 0.0107047 0.0314087 0.0325005 0.00997403 0.0314087 0.0319178 0.0247529 0.0314087 0.0226512 0.0259244 0.0320087 0.0223186 0.0268639 0.0320087 0.0230678 0.0265716 0.0314087 0.0237012 0.0273853 0.0320087 0.0241504 0.0273853 0.0320087 0.025352 0.0268639 0.0320087 0.0264346 0.0265716 0.0314087 0.0258012 0.0263948 0.0314087 0.0260605 0.0247529 0.0320087 0.0274512 0.0256641 0.0314087 0.0266432 0.0259244 0.0320087 0.0271838 0.0258029 0.0314087 0.0265698 0.0356303 0.0314087 0.0101111 0.0365116 0.0320087 0.00906111 0.0361499 0.0320087 0.00771111 0.0348616 0.0314087 0.00724245 0.0351616 0.0320087 0.00672284 0.0338116 0.0320087 -0.00635623 0.0351616 0.0320087 -0.00671796 0.0361499 0.0320087 -0.00770623 0.0365116 0.0320087 -0.00905623 0.0356303 0.0314087 -0.0101062 -0.0160668 0.0226587 0.0294883 -0.0162058 0.0226587 0.0292846 -0.0158872 0.0226587 0.0299462 -0.0162058 0.0226587 0.0313421 -0.0160668 0.0226587 0.0311383 -0.0167799 0.0226587 0.0317999 -0.0174958 0.0216673 0.0303133 0.0189332 0.0226587 0.0294883 0.0187942 0.0226587 0.0292846 0.0189332 0.0226587 0.0311383 0.0319237 0.0226587 0.0171353 0.0316051 0.0226587 0.0164737 0.0303151 0.0216673 0.0175024 0.031744 0.0226587 0.0166774 0.0319237 0.0226587 0.0178696 0.031031 0.0226587 0.018989 0.0358292 0.0226587 0.00143138 0.0350042 0.0226587 0.00165244 0.0366542 0.0226587 2.44063e-06 0.0350042 0.0216673 2.44063e-06 0.0175042 0.0216673 -0.0303084 0.0182201 0.0226587 -0.031795 0.000720118 0.0226587 -0.033511 0.00161284 0.0226587 -0.0346304 0.00165421 0.0226587 -0.0349976 0.00129423 0.0226587 -0.0360263 0.00082921 0.0226587 -0.0335686 4.20971e-06 0.0216673 -0.0349976 -0.0166708 0.0226587 -0.0288795 -0.0166708 0.0226587 -0.0317374 -0.0349958 0.0226587 0.00165244 -0.0333458 0.0226587 2.44063e-06 -0.0349958 0.0226587 -0.00164756 -0.0341708 0.0226587 -0.0014265 -0.0342799 0.0226587 -0.00148416 -0.0349958 0.0216673 2.44063e-06 -0.0337058 0.0226587 -0.00102632 -0.0335668 0.0226587 -0.000822559 -0.0335668 0.0226587 0.000827441 -0.0342799 0.0226587 0.00148904 -0.0341708 0.0226587 0.00143138 -0.0290167 0.0226587 0.0185312 -0.028698 0.0226587 0.0171353 -0.0294817 0.0226587 0.0160735 -0.0290167 0.0226587 0.0164737 -0.00247334 0.0223087 -0.0145268 -0.0145958 0.0223087 -0.0252855 -0.0101511 0.0223087 -0.00960059 -0.00300552 0.0223087 -0.0263136 -0.00785707 0.0223087 -0.0281194 -0.0212813 0.0223087 -0.0157621 -0.0201423 0.0223087 -0.0143281 -0.0125155 0.0223087 -0.00966802 0.00603779 0.0223087 -0.0282346 0.00211923 0.0223087 -0.0156752 0.00248176 0.0223087 -0.0145268 0.00324303 0.0223087 -0.0135938 0.0217464 0.0223087 -0.0175356 0.0214415 0.0223087 -0.0193413 0.0212897 0.0223087 -0.0157621 0.0125239 0.0223087 -0.00966802 0.00301394 0.0223087 -0.0263136 0.0146042 0.0223087 -0.0252855 0.00191403 0.0223087 -0.0201506 0.0260637 0.0223087 -0.0100578 0.0133983 0.0223087 -0.00399078 0.0134173 0.0223087 -0.00278674 0.0138257 0.0223087 -0.00511658 0.0184121 0.0223087 -0.00842011 0.0146389 0.0223087 -0.00600471 0.0133983 0.0223087 0.00399567 0.0292042 0.0223087 2.44063e-06 0.0259009 0.0223087 0.0101435 0.0274178 0.0223087 0.00896638 0.0184121 0.0223087 0.00842499 0.0165023 0.0223087 0.0117329 0.0125239 0.0223087 0.0096729 0.0146042 0.0223087 0.0252904 0.0101168 0.0223087 0.00962142 0.00912625 0.0223087 0.0102239 0.0214415 0.0223087 0.0193462 0.0201507 0.0223087 0.014333 0.00429524 0.0223087 0.0130131 0.00211923 0.0223087 0.0156801 0.0023416 0.0223087 0.0246151 -0.0125155 0.0223087 0.0096729 -0.0145958 0.0223087 0.0252904 -0.0164939 0.0223087 0.0117329 -0.0201423 0.0223087 0.014333 -0.0204194 0.0223087 0.0208714 -0.0217379 0.0223087 0.0175405 -0.00468697 0.0223087 0.0278133 -0.00667249 0.0223087 0.0282868 -0.00785707 0.0223087 0.0281243 -0.0274094 0.0223087 0.00896638 -0.0133899 0.0223087 0.00399567 -0.0258924 0.0223087 0.0101435 -0.0240186 0.0223087 0.0105624 -0.0224797 0.0223087 0.0102845 -0.0184037 0.0223087 0.00842499 -0.0138173 0.0223087 -0.00511658 -0.0146305 0.0223087 -0.00600471 -0.0291958 0.0223087 2.44063e-06 -0.024291 0.0223087 -0.0105491 -0.0260552 0.0223087 -0.0100578 -0.0224797 0.0223087 -0.0102796 -0.0274666 0.0223087 -0.00889087 0.0258029 0.0314087 -0.0229276 0.0268529 0.0314087 -0.0247463 0.0274529 0.0320087 -0.0247463 0.0265716 0.0314087 -0.0257963 0.0270912 0.0320087 -0.0260963 0.0247529 0.0314087 -0.0268463 0.0261029 0.0320087 -0.0270846 0.00561651 0.0320087 -0.0330184 0.00695193 0.0320087 -0.0321215 0.00789139 0.0320087 -0.0313723 0.0075291 0.0320087 -0.03062 0.00906288 0.0320087 -0.031105 0.0108304 0.0320087 -0.0307436 0.0125979 0.0320087 -0.033805 0.0114011 0.0320087 -0.035155 0.00906288 0.0320087 -0.036505 0.00789139 0.0320087 -0.0362376 0.00906288 0.0320087 -0.03734 0.0075291 0.0320087 -0.0369899 0.00695193 0.0320087 -0.0354884 0.0062991 0.0320087 -0.036009 0.00561651 0.0320087 -0.0345916 -0.00560809 0.0320087 -0.0330184 -0.00788297 0.0320087 -0.0362376 -0.00905446 0.0320087 -0.036505 -0.0104045 0.0320087 -0.0361432 -0.010822 0.0320087 -0.0368664 -0.0121159 0.0320087 -0.0355725 -0.0117545 0.0320087 -0.033805 -0.0125895 0.0320087 -0.033805 -0.00905446 0.0320087 -0.031105 -0.00788297 0.0320087 -0.0313723 -0.00752068 0.0320087 -0.03062 -0.00694351 0.0320087 -0.0321215 -0.00642215 0.0320087 -0.0332042 -0.0226336 0.0320087 -0.0264297 -0.0216831 0.0320087 -0.0229788 -0.0226336 0.0320087 -0.0230629 -0.0247445 0.0320087 -0.0220463 -0.026512 0.0320087 -0.0216849 -0.0278059 0.0320087 -0.0229788 -0.0278059 0.0320087 -0.0265138 -0.026512 0.0320087 -0.0278077 -0.0260945 0.0320087 -0.0270846 -0.0247445 0.0320087 -0.0274463 -0.0216831 0.0320087 -0.0265138 -0.0338032 0.0320087 -0.00635623 -0.0338032 0.0320087 -0.00552123 -0.0324532 0.0320087 -0.00671796 -0.0314649 0.0320087 -0.00770623 -0.0307418 0.0320087 -0.00728873 -0.0314649 0.0320087 -0.0104062 -0.0302682 0.0320087 -0.00905623 -0.0324532 0.0320087 -0.0113945 -0.0320357 0.0320087 -0.0121176 -0.0338032 0.0320087 -0.0117562 -0.0338032 0.0320087 -0.0125912 -0.0349747 0.0320087 -0.0114888 -0.0372496 0.0320087 -0.00826961 -0.0349747 0.0320087 -0.00662361 -0.0311709 0.0320087 0.00966191 -0.0311709 0.0320087 0.0084603 -0.0310394 0.0320087 0.00685707 -0.0326317 0.0320087 0.00662849 -0.0322694 0.0320087 0.00587618 -0.0338032 0.0320087 0.00636111 -0.0361415 0.0320087 0.00771111 -0.0368646 0.0320087 0.00729361 -0.0365032 0.0320087 0.00906111 -0.0373382 0.0320087 0.00906111 -0.0351532 0.0320087 0.0113994 -0.0368646 0.0320087 0.0108286 -0.0326317 0.0320087 0.0114937 -0.0322694 0.0320087 0.012246 -0.0316922 0.0320087 0.0107445 -0.0303568 0.0320087 0.00984772 -0.0212982 0.0320087 0.0255378 -0.0221122 0.0320087 0.0241504 -0.0212982 0.0320087 0.0239646 -0.0226336 0.0320087 0.0230678 -0.023573 0.0320087 0.0223186 -0.0219808 0.0320087 0.0225471 -0.0247445 0.0320087 0.0212162 -0.0270828 0.0320087 0.0234012 -0.0282795 0.0320087 0.0247512 -0.0270828 0.0320087 0.0261012 -0.0260945 0.0320087 0.0270894 -0.0247445 0.0320087 0.0274512 -0.0232107 0.0320087 0.0279361 -0.0219808 0.0320087 0.0269552 -0.0102259 0.0320087 0.0362425 -0.0105882 0.0320087 0.0369948 -0.00905446 0.0320087 0.0373448 -0.00770446 0.0320087 0.0361481 -0.00599306 0.0320087 0.0320423 -0.00770446 0.0320087 0.0314716 -0.0102259 0.0320087 0.0313772 -0.0105882 0.0320087 0.0306249 -0.0111654 0.0320087 0.0321264 -0.0116868 0.0320087 0.033209 -0.0125008 0.0320087 0.0330232 -0.0116868 0.0320087 0.0344107 0.0116952 0.0320087 0.033209 0.0125092 0.0320087 0.0345965 0.0125092 0.0320087 0.0330232 0.0111738 0.0320087 0.0321264 0.0102344 0.0320087 0.0313772 0.00729538 0.0320087 0.0307484 0.00552788 0.0320087 0.0338098 0.00636288 0.0320087 0.0338098 0.00771288 0.0320087 0.0361481 0.00729538 0.0320087 0.0368712 0.00906288 0.0320087 0.0365098 0.00906288 0.0320087 0.0373448 0.0118267 0.0320087 0.0360139 0.0116952 0.0320087 0.0344107 0.0278143 0.0320087 0.0265187 0.0265204 0.0320087 0.0278126 0.0224147 0.0320087 0.0234012 0.0247529 0.0320087 0.0212162 0.0247529 0.0320087 0.0220512 0.0265204 0.0320087 0.0216898 0.0311116 0.0320087 0.00906111 0.0303652 0.0320087 0.0082745 0.0322778 0.0320087 0.012246 0.0338116 0.0320087 0.0117611 0.0351616 0.0320087 0.0113994 0.0361499 0.0320087 0.0104111 0.0373466 0.0320087 0.00906111 0.0338116 0.0320087 0.00552611 0.0314733 0.0320087 0.00771111 0.0310478 0.0320087 0.00685707 0.0326401 0.0320087 -0.00662361 0.036873 0.0320087 -0.00728873 0.0373466 0.0320087 -0.00905623 0.0361499 0.0320087 -0.0104062 0.036873 0.0320087 -0.0108237 0.0351616 0.0320087 -0.0113945 0.0338116 0.0320087 -0.0117562 0.0326401 0.0320087 -0.0114888 0.0310478 0.0320087 -0.0112603 0.0303652 0.0320087 -0.00984284 0.0311793 0.0320087 -0.00845542 0.0303652 0.0320087 -0.00826961 0.0322778 0.0320087 -0.0058713 -0.0166708 0.0302087 0.0317423 -0.0166708 0.0226587 0.0317423 -0.0158872 0.0226587 0.0306805 -0.0158458 0.0226587 0.0303133 -0.0166708 0.0226587 0.0288844 -0.0167799 0.0226587 0.0288267 0.0175042 0.0226587 0.0319633 0.0182201 0.0226587 0.0317999 0.0183292 0.0226587 0.0317423 0.0187942 0.0226587 0.0313421 0.0191128 0.0226587 0.0306805 0.0191542 0.0226587 0.0303133 0.0191542 0.0302087 0.0303133 0.0191128 0.0226587 0.0299462 0.0189332 0.0302087 0.0294883 0.0183292 0.0302087 0.0288844 0.0183292 0.0226587 0.0288844 0.0182201 0.0226587 0.0288267 0.0175042 0.0302087 0.0286633 0.0311401 0.0226587 0.0189314 0.0316051 0.0226587 0.0185312 0.031744 0.0302087 0.0183274 0.031744 0.0226587 0.0183274 0.0319651 0.0226587 0.0175024 0.031744 0.0302087 0.0166774 0.0311401 0.0302087 0.0160735 0.0311401 0.0226587 0.0160735 0.031031 0.0226587 0.0160158 0.0358292 0.0302087 0.00143138 0.0364332 0.0226587 0.000827441 0.0366542 0.0302087 2.44063e-06 0.0364332 0.0226587 -0.000822559 0.0358292 0.0226587 -0.0014265 0.0358292 0.0302087 -0.0014265 0.0350042 0.0226587 -0.00164756 0.0350042 0.0302087 -0.00164756 0.0182201 0.0226587 -0.0288219 0.0187942 0.0226587 -0.0292797 0.0182201 0.0302087 -0.0288219 0.0191128 0.0226587 -0.0299413 0.0191128 0.0302087 -0.0299413 0.0191128 0.0226587 -0.0306756 0.0187942 0.0226587 -0.0313372 0.0182201 0.0302087 -0.031795 4.20971e-06 0.0226587 -0.0333476 4.20971e-06 0.0302087 -0.0333476 0.00082921 0.0302087 -0.0335686 0.00129423 0.0226587 -0.0339688 0.00143315 0.0226587 -0.0341726 0.00165421 0.0302087 -0.0349976 0.00161284 0.0226587 -0.0353647 0.00143315 0.0302087 -0.0358226 0.00143315 0.0226587 -0.0358226 0.00082921 0.0226587 -0.0364265 0.00082921 0.0302087 -0.0364265 0.000720118 0.0226587 -0.0364842 -0.0174958 0.0226587 -0.0286584 -0.0166708 0.0302087 -0.0288795 -0.0162058 0.0302087 -0.0292797 -0.0160668 0.0226587 -0.0294834 -0.0160668 0.0302087 -0.0294834 -0.0158872 0.0302087 -0.0299413 -0.0158458 0.0226587 -0.0303084 -0.0158872 0.0302087 -0.0306756 -0.0160668 0.0302087 -0.0311334 -0.0160668 0.0226587 -0.0311334 -0.0167799 0.0302087 -0.031795 -0.0174958 0.0226587 -0.0319584 -0.0349958 0.0302087 0.00165244 -0.0341708 0.0302087 0.00143138 -0.0337058 0.0226587 0.0010312 -0.0335668 0.0302087 0.000827441 -0.0333872 0.0226587 0.0003696 -0.0333872 0.0226587 -0.000364719 -0.0335668 0.0302087 -0.000822559 -0.0349958 0.0302087 -0.00164756 -0.0303067 0.0302087 0.0191524 -0.0294817 0.0226587 0.0189314 -0.0288777 0.0226587 0.0183274 -0.028698 0.0226587 0.0178696 -0.0286567 0.0226587 0.0175024 -0.028698 0.0302087 0.0178696 -0.0288777 0.0226587 0.0166774 -0.028698 0.0302087 0.0171353 -0.0290167 0.0302087 0.0164737 -0.0295908 0.0302087 0.0160158 -0.0303067 0.0302087 0.0158524 -0.00233318 0.0305587 -0.0246102 -0.00233318 0.0223087 -0.0246102 -0.00190561 0.0223087 -0.0201506 -0.00211081 0.0305587 -0.0156752 -0.00211081 0.0223087 -0.0156752 -0.00300552 0.0305587 -0.0263136 -0.00431309 0.0223087 -0.0275958 -0.00602937 0.0223087 -0.0282346 -0.00602937 0.0305587 -0.0282346 -0.0145958 0.0305587 -0.0252855 -0.0204194 0.0223087 -0.0208666 -0.021433 0.0223087 -0.0193413 -0.0217379 0.0223087 -0.0175356 -0.0212813 0.0305587 -0.0157621 -0.0164939 0.0223087 -0.011728 -0.00911783 0.0305587 -0.010219 -0.0113397 0.0223087 -0.00940782 -0.0101083 0.0305587 -0.00961654 -0.0125155 0.0305587 -0.00966802 -0.00911783 0.0223087 -0.010219 -0.00323461 0.0223087 -0.0135938 -0.00428682 0.0223087 -0.0130082 0.0201507 0.0223087 -0.0143281 0.0165023 0.0223087 -0.011728 0.0201507 0.0305587 -0.0143281 0.0204278 0.0223087 -0.0208666 0.0146042 0.0305587 -0.0252855 0.0204278 0.0305587 -0.0208666 0.00786549 0.0223087 -0.0281194 0.00603779 0.0305587 -0.0282346 0.00432151 0.0223087 -0.0275958 0.00301394 0.0305587 -0.0263136 0.0023416 0.0305587 -0.0246102 0.00211923 0.0305587 -0.0156752 0.0023416 0.0223087 -0.0246102 0.00324303 0.0305587 -0.0135938 0.00912625 0.0223087 -0.010219 0.00912625 0.0305587 -0.010219 0.00429524 0.0223087 -0.0130082 0.0113482 0.0223087 -0.00940782 0.0101595 0.0223087 -0.00960059 0.0224881 0.0305587 0.0102845 0.0224881 0.0223087 0.0102845 0.024027 0.0223087 0.0105624 0.024027 0.0305587 0.0105624 0.0282891 0.0223087 -0.00725044 0.0282891 0.0305587 0.00725532 0.0282891 0.0223087 0.00725532 0.027475 0.0223087 -0.00889087 0.0260637 0.0305587 -0.0100578 0.0242995 0.0223087 -0.0105491 0.0224881 0.0223087 -0.0102796 0.0242995 0.0305587 -0.0105491 0.0184121 0.0305587 -0.00842011 0.0224881 0.0305587 -0.0102796 0.0133983 0.0305587 -0.00399078 0.0138257 0.0305587 -0.00511658 0.0138257 0.0305587 0.00512146 0.0146389 0.0223087 0.00600959 0.0138257 0.0223087 0.00512146 0.0133983 0.0305587 0.00399567 0.0134173 0.0223087 0.00279162 0.0023416 0.0305587 0.0246151 0.00191403 0.0305587 0.0201554 0.00191403 0.0223087 0.0201554 0.00313718 0.0223087 0.0264948 0.00469539 0.0223087 0.0278133 0.00313718 0.0305587 0.0264948 0.00469539 0.0305587 0.0278133 0.0204278 0.0223087 0.0208714 0.0204278 0.0305587 0.0208714 0.0214415 0.0305587 0.0193462 0.0217464 0.0223087 0.0175405 0.0212897 0.0223087 0.015767 0.0165023 0.0305587 0.0117329 0.0201507 0.0305587 0.014333 0.0101595 0.0305587 0.00960547 0.00912625 0.0305587 0.0102239 0.00248176 0.0305587 0.0145317 0.00248176 0.0223087 0.0145317 0.00324303 0.0305587 0.0135987 0.00324303 0.0223087 0.0135987 -0.0201423 0.0305587 0.014333 -0.0212813 0.0223087 0.015767 -0.0212813 0.0305587 0.015767 -0.021433 0.0305587 0.0193462 -0.021433 0.0223087 0.0193462 -0.00785707 0.0305587 0.0281243 -0.00667249 0.0305587 0.0282868 -0.00190561 0.0223087 0.0201554 -0.00428682 0.0305587 0.0130131 -0.00428682 0.0223087 0.0130131 -0.00323461 0.0305587 0.0135987 -0.00323461 0.0223087 0.0135987 -0.00247334 0.0223087 0.0145317 -0.00211081 0.0223087 0.0156801 -0.0113397 0.0305587 0.00941271 -0.0112485 0.0223087 0.00941141 -0.0112485 0.0305587 0.00941141 -0.0184037 0.0305587 -0.00842011 -0.0184037 0.0223087 -0.00842011 -0.0224797 0.0305587 -0.0102796 -0.024291 0.0305587 -0.0105491 -0.0260552 0.0305587 -0.0100578 -0.0282807 0.0223087 -0.00725044 -0.0274666 0.0305587 -0.00889087 -0.0282807 0.0305587 0.00725532 -0.0291958 0.0305587 2.44063e-06 -0.0282807 0.0223087 0.00725532 -0.0282807 0.0305587 -0.00725044 -0.0258924 0.0305587 0.0101435 -0.0240186 0.0305587 0.0105624 -0.0184037 0.0305587 0.00842499 -0.0146305 0.0223087 0.00600959 -0.0134089 0.0223087 0.00279162 -0.0138173 0.0223087 0.00512146 -0.0146305 0.0305587 0.00600959 -0.0134089 0.0305587 -0.00278674 -0.0138173 0.0305587 -0.00511658 -0.0133899 0.0223087 -0.00399078 -0.0134089 0.0223087 -0.00278674 0.0221206 0.0320087 -0.0253471 0.022642 0.0320087 -0.0264297 0.0235815 0.0320087 -0.0271789 0.0265204 0.0320087 -0.0278077 0.0282879 0.0320087 -0.0247463 0.0278143 0.0320087 -0.0229788 0.0270912 0.0320087 -0.0233963 0.0265204 0.0320087 -0.0216849 0.0261029 0.0320087 -0.022408 0.0229854 0.0320087 -0.0216849 0.0247529 0.0320087 -0.0220463 0.0235815 0.0320087 -0.0223137 0.0216915 0.0320087 -0.0229788 0.0212179 0.0320087 -0.0247463 0.00906288 0.0318087 -0.03754 0.00719538 0.0318087 -0.0370396 0.00582827 0.0318087 -0.0356725 0.00532788 0.0318087 -0.033805 0.00542152 0.0318087 -0.0329738 0.00582827 0.0318087 -0.0319375 0.0062991 0.0320087 -0.0316009 0.00719538 0.0318087 -0.0305704 -0.00905446 0.0320087 -0.03734 -0.0122891 0.0318087 -0.0319375 -0.010922 0.0318087 -0.0305704 -0.0121159 0.0320087 -0.0320375 -0.010822 0.0320087 -0.0307436 -0.026612 0.0318087 -0.0279809 -0.0284795 0.0318087 -0.0247463 -0.0282795 0.0320087 -0.0247463 -0.0283859 0.0318087 -0.0239152 -0.0279791 0.0318087 -0.0228788 -0.0276647 0.0318087 -0.0224176 -0.0354237 0.0318087 -0.0124213 -0.035337 0.0320087 -0.0122412 -0.036567 0.0320087 -0.0112603 -0.0374446 0.0318087 -0.00822511 -0.0372496 0.0320087 -0.00984284 -0.036567 0.0320087 -0.00685219 -0.035337 0.0320087 -0.0058713 -0.0338032 0.0318087 -0.00532123 -0.0338032 0.0320087 0.00552611 -0.0355707 0.0320087 0.00599971 -0.0370378 0.0318087 0.00719361 -0.0356707 0.0318087 0.0122957 -0.0355707 0.0320087 0.0121225 -0.026512 0.0320087 0.0216898 -0.0278059 0.0320087 0.0229837 -0.0278059 0.0320087 0.0265187 -0.026512 0.0320087 0.0278126 -0.0247445 0.0320087 0.0282862 -0.00905446 0.0320087 0.0302748 -0.0118182 0.0320087 0.0316058 -0.0126958 0.0318087 0.034641 -0.0125008 0.0320087 0.0345965 -0.0118182 0.0320087 0.0360139 -0.0119746 0.0318087 0.0361386 -0.010675 0.0318087 0.037175 0.00719538 0.0318087 0.0305752 0.00600148 0.0320087 0.0320423 0.00532788 0.0318087 0.0338098 0.00600148 0.0320087 0.0355773 0.00719538 0.0318087 0.0370445 0.00906288 0.0318087 0.0375448 0.0229854 0.0320087 0.0216898 0.0228854 0.0318087 0.0215166 0.0215183 0.0318087 0.0228837 0.0216915 0.0320087 0.0229837 0.0210179 0.0318087 0.0247512 0.0215183 0.0318087 0.0266187 0.0212179 0.0320087 0.0247512 0.0216915 0.0320087 0.0265187 0.0229854 0.0320087 0.0278126 0.0321911 0.0318087 0.00569599 0.0322778 0.0320087 0.00587618 0.0301703 0.0318087 0.00822999 0.0300766 0.0318087 0.00906111 0.0303652 0.0320087 0.00984772 0.0310478 0.0320087 0.0112651 0.0308915 0.0318087 0.0113898 0.0319441 0.0318087 0.0122957 0.0338116 0.0318087 0.0127961 0.0338116 0.0320087 -0.0125912 0.0321911 0.0318087 -0.0124213 0.0322778 0.0320087 -0.0122412 0.0301703 0.0318087 -0.00988734 0.0301703 0.0318087 -0.00822511 0.0310478 0.0320087 -0.00685219 -0.0163958 0.0307587 0.0322186 -0.0160668 0.0302087 0.0311383 -0.0158458 0.0302087 0.0303133 -0.0155905 0.0307587 0.0314133 -0.0160668 0.0302087 0.0294883 -0.0152958 0.0307587 0.0303133 -0.0166708 0.0302087 0.0288844 -0.0155905 0.0307587 0.0292133 -0.0174958 0.0302087 0.0286633 0.0175042 0.0302087 0.0319633 0.0175042 0.0307587 0.0325133 0.0183292 0.0302087 0.0317423 0.0189332 0.0302087 0.0311383 0.0197042 0.0307587 0.0303133 0.0186042 0.0307587 0.0284081 0.0311401 0.0302087 0.0189314 0.0314151 0.0307587 0.0194077 0.0319651 0.0302087 0.0175024 0.0322204 0.0307587 0.0186024 0.0322204 0.0307587 0.0164024 0.0314151 0.0307587 0.0155972 0.0361042 0.0307587 0.0019077 0.0364332 0.0302087 0.000827441 0.0369095 0.0307587 0.00110244 0.0364332 0.0302087 -0.000822559 0.0372042 0.0307587 2.44063e-06 0.0187942 0.0302087 -0.0292797 0.0184588 0.0307587 -0.0283263 0.0191128 0.0302087 -0.0306756 0.0187942 0.0302087 -0.0313372 0.0192242 0.0307587 -0.0316801 0.0175042 0.0302087 -0.0319584 0.00110421 0.0307587 -0.0330923 0.00143315 0.0302087 -0.0341726 -0.0165412 0.0307587 -0.0322906 -0.0166708 0.0302087 -0.0317374 -0.0162058 0.0302087 -0.0313372 -0.0158458 0.0302087 -0.0303084 -0.0157758 0.0307587 -0.0289368 -0.0165412 0.0307587 -0.0283263 -0.0174958 0.0302087 -0.0286584 -0.0167799 0.0302087 -0.0288219 -0.0174958 0.0307587 -0.0281084 -0.0349958 0.0307587 0.00220244 -0.0338958 0.0307587 0.0019077 -0.0333458 0.0302087 2.44063e-06 -0.0327958 0.0307587 2.44063e-06 -0.0341708 0.0302087 -0.0014265 -0.0338958 0.0307587 -0.00190282 -0.0295908 0.0302087 0.018989 -0.0290167 0.0302087 0.0185312 -0.0293521 0.0307587 0.0194846 -0.0285867 0.0307587 0.0188741 -0.0281618 0.0307587 0.017992 -0.00190561 0.0305587 -0.0201506 -0.00191216 0.0307587 -0.0156519 -0.00213594 0.0307587 -0.0246433 -0.00431309 0.0305587 -0.0275958 -0.00283884 0.0307587 -0.0264242 -0.00785707 0.0305587 -0.0281194 -0.00600014 0.0307587 -0.0284325 -0.00791091 0.0307587 -0.0283121 -0.0204194 0.0305587 -0.0208666 -0.021433 0.0305587 -0.0193413 -0.0217379 0.0305587 -0.0175356 -0.0214604 0.0307587 -0.015673 -0.0201423 0.0305587 -0.0143281 -0.0165982 0.0307587 -0.0115573 -0.0164939 0.0305587 -0.011728 -0.0125947 0.0307587 -0.00948437 -0.00428682 0.0305587 -0.0130082 -0.00422418 0.0307587 -0.0128183 -0.00898466 0.0307587 -0.0100698 -0.00323461 0.0305587 -0.0135938 -0.00247334 0.0305587 -0.0145268 0.0125239 0.0305587 -0.00966802 0.0165023 0.0305587 -0.011728 0.0126031 0.0307587 -0.00948437 0.0166066 0.0307587 -0.0115573 0.0212897 0.0305587 -0.0157621 0.0214688 0.0307587 -0.015673 0.0217464 0.0305587 -0.0175356 0.0214415 0.0305587 -0.0193413 0.0216274 0.0307587 -0.0194149 0.0205677 0.0307587 -0.0210095 0.0147042 0.0307587 -0.0254587 0.00786549 0.0305587 -0.0281194 0.00791933 0.0307587 -0.0283121 0.00600856 0.0307587 -0.0284325 0.00432151 0.0305587 -0.0275958 0.00421426 0.0307587 -0.0277646 0.00284726 0.0307587 -0.0264242 0.00191403 0.0305587 -0.0201506 0.00192058 0.0307587 -0.0156519 0.00230578 0.0307587 -0.0144318 0.00248176 0.0305587 -0.0145268 0.00429524 0.0305587 -0.0130082 0.0042326 0.0307587 -0.0128183 0.0101168 0.0305587 -0.00961654 0.0112569 0.0305587 -0.00940652 0.0184121 0.0305587 0.00842499 0.0183165 0.0307587 0.00860063 0.0224181 0.0307587 0.0104719 0.0284828 0.0307587 0.00730499 0.0292042 0.0305587 2.44063e-06 0.0294042 0.0307587 2.44063e-06 0.0282891 0.0305587 -0.00725044 0.0284828 0.0307587 -0.00730011 0.027475 0.0305587 -0.00889087 0.0276318 0.0307587 -0.00901511 0.0261562 0.0307587 -0.0102351 0.0183165 0.0307587 -0.00859575 0.0146389 0.0305587 -0.00600471 0.0134173 0.0305587 -0.00278674 0.0132215 0.0307587 -0.00274602 0.0134173 0.0305587 0.00279162 0.0132013 0.0307587 0.0040302 0.0146389 0.0305587 0.00600959 0.00192058 0.0307587 0.0156568 0.00171409 0.0307587 0.0201604 0.00214436 0.0307587 0.0246482 0.0029761 0.0307587 0.0266134 0.0146042 0.0305587 0.0252904 0.00791933 0.0307587 0.0283169 0.0205677 0.0307587 0.0210144 0.0216274 0.0307587 0.0194198 0.0217464 0.0305587 0.0175405 0.0219462 0.0307587 0.017532 0.0212897 0.0305587 0.015767 0.0214688 0.0307587 0.0156779 0.020278 0.0307587 0.0141787 0.0100909 0.0307587 0.0094176 0.0125239 0.0305587 0.0096729 0.0113539 0.0307587 0.00921279 0.00899308 0.0307587 0.0100747 0.00429524 0.0305587 0.0130131 0.0042326 0.0307587 0.0128232 0.00230578 0.0307587 0.0144367 0.00211923 0.0305587 0.0156801 -0.0125155 0.0305587 0.0096729 -0.0164939 0.0305587 0.0117329 -0.0165982 0.0307587 0.0115622 -0.0202696 0.0307587 0.0141787 -0.0214604 0.0307587 0.0156779 -0.0217379 0.0305587 0.0175405 -0.0219378 0.0307587 0.017532 -0.0204194 0.0305587 0.0208714 -0.0205593 0.0307587 0.0210144 -0.0146958 0.0307587 0.0254636 -0.0145958 0.0305587 0.0252904 -0.00791091 0.0307587 0.0283169 -0.00233318 0.0305587 0.0246151 -0.00190561 0.0305587 0.0201554 -0.00170567 0.0307587 0.0201604 -0.00191216 0.0307587 0.0156568 -0.00211081 0.0305587 0.0156801 -0.00229736 0.0307587 0.0144367 -0.00247334 0.0305587 0.0145317 -0.00422418 0.0307587 0.0128232 -0.00911783 0.0305587 0.0102239 -0.00898466 0.0307587 0.0100747 -0.0101511 0.0305587 0.00960547 -0.0100825 0.0307587 0.0094176 -0.0261478 0.0307587 -0.0102351 -0.0276233 0.0307587 -0.00901511 -0.0293958 0.0307587 2.44063e-06 -0.0284744 0.0307587 0.00730499 -0.0274094 0.0305587 0.00896638 -0.013647 0.0307587 0.00522636 -0.0138173 0.0305587 0.00512146 -0.0133899 0.0305587 0.00399567 -0.0131929 0.0307587 0.0040302 -0.0134089 0.0305587 0.00279162 -0.013213 0.0307587 -0.00274602 -0.0133899 0.0305587 -0.00399078 -0.013647 0.0307587 -0.00522148 -0.0146305 0.0305587 -0.00600471 0.0247529 0.0320087 -0.0282813 0.0228854 0.0318087 -0.0279809 0.0229854 0.0320087 -0.0278077 0.0215183 0.0318087 -0.0266138 0.0216915 0.0320087 -0.0265138 0.0210179 0.0318087 -0.0247463 0.00744232 0.0318087 -0.0371701 0.00542152 0.0318087 -0.0346361 0.00582827 0.0307587 -0.0356725 0.00614274 0.0318087 -0.0361337 0.00532788 0.0307587 -0.033805 0.00582827 0.0307587 -0.0319375 0.00614274 0.0318087 -0.0314762 0.00906288 0.0307587 -0.03007 0.00744232 0.0318087 -0.0304398 -0.0122891 0.0318087 -0.0356725 -0.0127895 0.0307587 -0.033805 -0.0127895 0.0318087 -0.033805 -0.0122891 0.0307587 -0.0319375 -0.010922 0.0307587 -0.0305704 -0.00905446 0.0318087 -0.03007 -0.00905446 0.0307587 -0.03754 -0.00905446 0.0318087 -0.03754 -0.010922 0.0318087 -0.0370396 -0.0122891 0.0307587 -0.0356725 -0.0283859 0.0307587 -0.0239152 -0.0276647 0.0307587 -0.0224176 -0.0263651 0.0307587 -0.0213812 -0.026612 0.0318087 -0.0215117 -0.0247445 0.0307587 -0.0210113 -0.0283859 0.0318087 -0.0255774 -0.0277375 0.0307587 -0.0269807 -0.0279791 0.0318087 -0.0266138 -0.0269789 0.0307587 -0.0277393 -0.0276647 0.0318087 -0.027075 -0.0247445 0.0307587 -0.0284813 -0.0354237 0.0307587 -0.00569111 -0.0367233 0.0318087 -0.00672749 -0.0354237 0.0318087 -0.00569111 -0.0338032 0.0307587 -0.00532123 -0.0367233 0.0307587 -0.00672749 -0.0372347 0.0307587 -0.010531 -0.0374446 0.030726 -0.00988734 -0.0374446 0.0318087 -0.00988734 -0.0367233 0.0318087 -0.011385 -0.0338032 0.0318087 -0.0127912 -0.0370378 0.0307587 0.0109286 -0.0356707 0.0307587 0.0122957 -0.0338032 0.0307587 0.0127961 -0.0338032 0.0318087 0.0127961 -0.0370378 0.0318087 0.0109286 -0.0375382 0.0318087 0.00906111 -0.0375382 0.0307587 0.00906111 -0.0370378 0.0307587 0.00719361 -0.0356707 0.0318087 0.0058265 -0.0338032 0.0318087 0.00532611 -0.0338032 0.0307587 0.00532611 -0.0247445 0.0307587 0.0284862 -0.026612 0.0318087 0.0279858 -0.0279791 0.0318087 0.0266187 -0.0279791 0.0307587 0.0266187 -0.0284795 0.0318087 0.0247512 -0.0279791 0.0318087 0.0228837 -0.0284795 0.0307587 0.0247512 -0.0279791 0.0307587 0.0228837 -0.026612 0.0318087 0.0215166 -0.0247445 0.0318087 0.0210162 -0.00905446 0.0307587 0.0375448 -0.00905446 0.0318087 0.0375448 -0.0126958 0.0307587 0.034641 -0.0126958 0.0318087 0.0329787 -0.0119746 0.0318087 0.0314811 -0.010675 0.0318087 0.0304447 -0.010675 0.0307587 0.0304447 0.00744232 0.0307587 0.0304447 0.00542152 0.0318087 0.0329787 0.00542152 0.0307587 0.0329787 0.00582827 0.0318087 0.0319423 0.00614274 0.0307587 0.0314811 0.00614274 0.0318087 0.0314811 0.00542152 0.0318087 0.034641 0.00542152 0.0307587 0.034641 0.00582827 0.0318087 0.0356773 0.00614274 0.0307587 0.0361386 0.00614274 0.0318087 0.0361386 0.00744232 0.0307587 0.037175 0.00906288 0.0307587 0.0375448 0.0228854 0.0307587 0.0215166 0.0215183 0.0307587 0.0228837 0.0210179 0.0307587 0.0247512 0.0228854 0.0318087 0.0279858 0.0228854 0.0307587 0.0279858 0.0247529 0.0307587 0.0284862 0.0338116 0.0318087 0.00532611 0.0319441 0.0318087 0.0058265 0.030577 0.0307587 0.00719361 0.030577 0.0318087 0.00719361 0.0308915 0.0318087 0.00673237 0.0301703 0.0318087 0.00989222 0.030577 0.0318087 0.0109286 0.0300766 0.0307587 0.00906111 0.0321911 0.0318087 0.0124262 0.0338116 0.0307587 -0.0127912 0.0321911 0.0307587 -0.0124213 0.0308915 0.0318087 -0.011385 0.0321911 0.0307587 -0.00569111 0.0308915 0.0318087 -0.00672749 0.0321911 0.0318087 -0.00569111 0.0338116 0.0318087 -0.00532123 0.0370462 0.0307587 -0.0109237 0.0372431 0.0307587 -0.010531 4.20971e-06 0.0307587 -0.0386976 4.20971e-06 0.0307587 -0.0379476 -0.00620283 0.0307587 -0.0381965 -0.010922 0.0307587 -0.0370396 -0.0305686 0.0307587 -0.0109237 -0.0309512 0.0307587 -0.019433 -0.0326512 0.0307587 -0.019433 -0.0372347 0.0307587 0.0105359 0.0375208 0.0307587 0.00949966 0.0319441 0.0307587 0.0058265 -0.021619 0.0307587 0.0194198 -0.0208188 0.0307587 0.0239079 0.0208273 0.0307587 0.0130324 0.0153042 0.0307587 -0.0303084 0.0142272 0.0307587 -0.0304952 0.0142272 0.0307587 -0.032653 0.0164042 0.0307587 -0.0322137 0.0164042 0.0307587 -0.0284032 0.0196491 0.0307587 -0.0298189 0.0192242 0.0307587 -0.0289368 -0.0054131 0.0307587 -0.0329738 -0.00214063 0.0307587 -0.034508 0.00190947 0.0307587 -0.0338976 0.00220421 0.0307587 -0.0349976 -0.000950335 0.0307587 -0.0369797 4.20971e-06 0.0307587 -0.0371976 0.00110421 0.0307587 -0.0369028 -0.0204513 0.0307587 -0.0328497 -0.0185958 0.0307587 -0.0322137 -0.0174958 0.0307587 -0.0325084 -0.0157758 0.0307587 -0.0316801 -0.019401 0.0307587 -0.0292084 -0.0153509 0.0307587 -0.030798 -0.0153509 0.0307587 -0.0298189 -0.0146958 0.0307587 -0.0254587 -0.0208188 0.0307587 0.0130324 -0.0285867 0.0307587 0.0161308 -0.0281618 0.0307587 0.0170129 -0.0303067 0.0307587 0.0153024 -0.0293521 0.0307587 0.0155203 -0.0218244 0.0307587 0.0224224 -0.023124 0.0307587 0.0213861 -0.0247445 0.0307587 0.0210162 -0.026612 0.0307587 0.0215166 -0.0328027 0.0307587 0.0205304 -0.0325067 0.0307587 0.0175024 -0.00229736 0.0307587 -0.0144318 4.20971e-06 0.0307587 -0.00570204 -0.00310621 0.0307587 -0.0134405 4.20971e-06 0.0307587 -0.019433 -0.00170567 0.0307587 -0.0201555 -0.0283859 0.0307587 -0.0255774 -0.0208188 0.0307587 -0.0304952 -0.0211032 0.0307587 -0.0255774 -0.0205593 0.0307587 -0.0210095 -0.0263651 0.0307587 -0.0281114 -0.0256586 0.0307587 -0.0289649 -0.0235734 0.0307587 -0.0306861 -0.0219378 0.0307587 -0.0175271 -0.023124 0.0307587 -0.0213812 -0.021619 0.0307587 -0.0194149 -0.0284744 0.0307587 -0.00730011 -0.00766882 0.0307587 -0.00570204 -0.0145111 0.0307587 -0.00616511 -0.0112485 0.0307587 -0.00920653 -0.018308 0.0307587 -0.00859575 -0.0224097 0.0307587 -0.010467 -0.0202696 0.0307587 -0.0141739 -0.0243034 0.0307587 -0.0107487 0.0145195 0.0307587 -0.00616511 0.020278 0.0307587 -0.0141739 0.0224181 0.0307587 -0.010467 0.0219462 0.0307587 -0.0175271 0.0250327 0.0307587 -0.019433 0.0210179 0.0307587 -0.0247463 0.0208273 0.0307587 -0.0304952 0.0215183 0.0307587 -0.0266138 0.0109304 0.0307587 -0.0305704 0.00719538 0.0307587 -0.0305704 0.00899308 0.0307587 -0.0100698 0.0100455 0.0307587 -0.00942967 0.00311463 0.0307587 -0.0134405 0.00171409 0.0307587 -0.0201555 4.20971e-06 0.0307587 -0.0304952 0.00214436 0.0307587 -0.0246433 0.0319441 0.0307587 0.0122957 0.0308915 0.0307587 -0.011385 0.0243118 0.0307587 -0.0107487 0.0301703 0.0307587 -0.00988734 0.0301703 0.0307587 -0.00822511 0.0308915 0.0307587 -0.00672749 0.0136554 0.0307587 -0.00522148 0.0112569 0.0307587 -0.00920653 0.00767724 0.0307587 -0.00570204 0.0132013 0.0307587 -0.00402532 0.0132215 0.0307587 0.0027509 0.0145195 0.0307587 0.00616999 0.0136554 0.0307587 0.00522636 0.0126031 0.0307587 0.00948925 0.00311463 0.0307587 0.0134454 0.00460514 0.0307587 0.0279918 0.0109304 0.0307587 0.0305752 0.0142507 0.0307587 0.0257201 0.0143044 0.0307587 0.0359634 0.0165497 0.0307587 0.0322955 0.0157842 0.0307587 0.031685 0.0186042 0.0307587 0.0322186 0.0194095 0.0307587 0.0314133 0.0209767 0.0307587 0.032527 0.0208273 0.0307587 0.0239079 0.0153594 0.0307587 0.0308029 0.0153594 0.0307587 0.0298238 0.0147042 0.0307587 0.0254636 0.0165497 0.0307587 0.0283312 0.0168816 0.0307587 0.0240755 0.0194095 0.0307587 0.0292133 0.0166066 0.0307587 0.0115622 -0.0113454 0.0307587 0.00921279 -0.0196406 0.0307587 0.0298238 -0.0163958 0.0307587 0.0284081 -0.0174958 0.0307587 0.0281133 -0.0184503 0.0307587 0.0283312 -0.0174958 0.0307587 0.0325133 -0.0192158 0.0307587 0.031685 -0.0105292 0.0307587 0.0372414 -0.010675 0.0307587 0.037175 -0.0119746 0.0307587 0.0361386 -0.014296 0.0307587 0.0359634 -0.0126958 0.0307587 0.0329787 -0.0142423 0.0307587 0.0257201 -0.0119746 0.0307587 0.0314811 4.20971e-06 0.0307587 0.0239079 -0.00531946 0.0307587 0.0338098 -0.00667249 0.0307587 0.0284868 -0.00718696 0.0307587 0.0305752 -0.00581985 0.0307587 0.0319423 -0.00310621 0.0307587 0.0134454 4.20971e-06 0.0307587 0.0130324 4.20971e-06 0.0307587 0.00570692 -0.0309512 0.0307587 0.00570692 -0.0145111 0.0307587 0.00616999 -0.018308 0.0307587 0.00860063 -0.0224097 0.0307587 0.0104719 -0.0259776 0.0307587 0.0103244 -0.0275636 0.0307587 0.00909383 -0.0309512 0.0307587 -0.00570204 -0.0125947 0.0307587 0.00948925 -0.0131929 0.0307587 -0.00402532 0.03828 0.0307587 -0.00571172 0.0370462 0.0307587 -0.00718873 0.0339042 0.0307587 -0.00190282 0.025986 0.0307587 0.0103244 0.030577 0.0307587 0.0109286 0.027572 0.0307587 0.00909383 0.0328042 0.0307587 2.44063e-06 0.033099 0.0307587 -0.00109756 0.0361042 0.0307587 -0.00190282 0.0350042 0.0307587 -0.00219756 0.0356791 0.0307587 -0.00582162 0.0369095 0.0307587 -0.00109756 0.0338116 0.0307587 0.00532611 0.0350042 0.0307587 0.00220244 0.0356791 0.0307587 0.0058265 0.0370462 0.0307587 0.00719361 0.03828 0.0307587 0.0057166 0.0364419 0.0307587 0.0130402 0.0370462 0.0307587 0.0109286 0.0356791 0.0307587 0.0122957 0.0338116 0.0307587 0.0127961 0.0361893 0.0307587 0.0137256 0.0326597 0.0307587 0.0130324 0.0250327 0.0307587 0.0130324 0.0325151 0.0307587 0.0175024 0.0303739 0.0307587 0.0239893 0.0263735 0.0307587 0.0213861 0.0281703 0.0307587 0.017992 0.0283943 0.0307587 0.0239201 0.0215183 0.0307587 0.0266187 0.0263735 0.0307587 0.0281163 0.00926573 0.0307587 0.0375779 4.20971e-06 0.0307587 0.0387024 -0.0256586 0.0307587 0.0289698 -0.026612 0.0307587 0.0279858 -0.0269789 0.0307587 0.0277441 -0.0211032 0.0307587 0.0239201 -0.0211032 0.0307587 0.0255823 -0.0209683 0.0307587 0.032527 -0.023124 0.0307587 0.0281163 -0.0318453 0.0307587 0.0219865 -0.0240186 0.0307587 0.0107624 -0.0309512 0.0307587 0.0130324 -0.0321826 0.0307587 0.0124262 -0.0326512 0.0307587 0.0130324 -0.0330905 0.0307587 0.00110244 -0.0384136 0.0307587 0.00466721 -0.0371406 0.0307587 -0.000487105 -0.0330905 0.0307587 -0.00109756 -0.0359503 0.0307587 -0.00197969 -0.0319357 0.0307587 -0.00582162 -0.0359503 0.0307587 0.00198457 -0.0356707 0.0307587 0.0058265 -0.0382716 0.0307587 0.0057166 -0.0374446 0.0307587 -0.00822511 -0.0338032 0.0307587 -0.0127912 -0.0367233 0.0307587 -0.011385 -0.0354237 0.0307587 -0.0124213 -0.0318453 0.0307587 -0.0219817 -0.00905446 0.0307587 -0.03007 -0.0142188 0.0307587 -0.0304952 -0.0142188 0.0307587 -0.032653 -0.0179806 0.0307587 -0.0342647 4.20971e-06 0.0307587 -0.0327976 4.20971e-06 0.0307587 -0.032653 -0.0074339 0.0307587 -0.0304398 -0.00420584 0.0307587 -0.0277646 -0.00613432 0.0307587 -0.0361337 0.00906288 0.0307587 -0.03754 0.00719538 0.0307587 -0.0370396 0.00190947 0.0307587 -0.0360976 0.0122975 0.0307587 -0.0356725 0.0109304 0.0307587 -0.0370396 0.017989 0.0307587 -0.0342647 0.0127979 0.0307587 -0.033805 0.015599 0.0307587 -0.0292084 0.0184588 0.0307587 -0.0322906 0.0196491 0.0307587 -0.030798 0.0250814 0.0307587 -0.0294734 0.0266204 0.0307587 -0.0279809 0.0318537 0.0307587 -0.0219817 0.0266204 0.0307587 -0.0215117 0.0247529 0.0307587 -0.0210113 0.0228854 0.0307587 -0.0215117 0.0326597 0.0307587 -0.019433 0.0356791 0.0307587 -0.0122908 -0.013213 0.0307587 0.0027509 -0.00766882 0.0307587 0.00570692 0.00767724 0.0307587 0.00570692 0.0247529 0.0318087 -0.0284813 0.0228854 0.0307587 -0.0279809 0.0215183 0.0307587 -0.0228788 0.0215183 0.0318087 -0.0228788 0.0228854 0.0318087 -0.0215117 4.20971e-06 0.0305587 -0.0388976 -0.00768818 0.0307587 -0.0379253 -0.00930517 0.0305587 -0.0377672 -0.00925731 0.0307587 -0.037573 -0.0105292 0.0307587 -0.0372365 -0.00949301 0.0307587 -0.0375141 -0.0209683 0.0307587 -0.0325221 -0.0382716 0.0307587 -0.00571172 -0.0375124 0.0307587 -0.00949478 -0.0363679 0.0305587 -0.0137917 -0.0361809 0.0307587 -0.0137208 -0.0384136 0.0307587 -0.00466233 -0.0375124 0.0307587 0.00949966 -0.0386122 0.0305587 0.00469132 -0.0361809 0.0307587 0.0137256 -0.0277375 0.0307587 0.0269856 -0.0320099 0.0305587 0.0221002 -0.0257913 0.0305587 0.0291195 -0.00930517 0.0305587 0.0377721 -0.0180735 0.0305587 0.0344467 -0.0179806 0.0307587 0.0342696 -0.00949301 0.0307587 0.037519 -0.00925731 0.0307587 0.0375779 0.024842 0.0208087 -0.0247977 0.0246527 0.0208087 -0.0247234 0.0248044 0.0208087 -0.0246572 0.0247083 0.0208087 -0.0246536 0.024842 0.0208087 -0.0246949 0.033892 0.0208087 -0.00899209 0.0337087 0.0208087 -0.00905623 0.0337602 0.0208087 -0.00896714 0.0337312 0.0208087 0.00899697 0.0337113 0.0208087 0.009084 0.033863 0.0208087 0.00897202 0.033767 0.0208087 0.00915379 0.0338116 0.0208087 0.00916397 0.0339007 0.0208087 0.00900968 0.0339007 0.0208087 0.00911254 0.0246725 0.0208087 0.024687 0.024842 0.0208087 0.0246997 0.0246725 0.0208087 0.0248153 0.0247529 0.0208087 0.024854 0.024842 0.0208087 0.0248026 0.0247083 0.0208087 0.0248439 0.00896001 0.0208087 0.0338098 0.00916316 0.0208087 0.0338327 0.00910751 0.0208087 0.0337172 -0.00914354 0.0208087 0.0337584 -0.00900983 0.0208087 0.0339025 -0.00897403 0.0208087 0.0337457 -0.00905446 0.0208087 0.0339127 -0.0246931 0.0208087 0.0246621 -0.024796 0.0208087 0.0246621 -0.0248474 0.0208087 0.0247512 -0.024796 0.0208087 0.0248403 -0.0246554 0.0208087 0.0248026 -0.0338923 0.0208087 0.00911254 -0.0339061 0.0208087 0.00906111 -0.0337141 0.0208087 -0.00900479 -0.0338478 0.0208087 -0.0091489 -0.0339035 0.0208087 -0.00907912 -0.0337518 0.0208087 -0.00914531 -0.0246554 0.0208087 -0.0246949 -0.0246931 0.0208087 -0.0248354 -0.00905446 0.0208087 -0.0339078 -0.00900302 0.0208087 -0.0337159 -0.00910589 0.0208087 -0.0337159 -0.00914354 0.0208087 -0.0337535 -0.00915732 0.0208087 -0.033805 -0.00910589 0.0208087 -0.033894 -0.00900302 0.0208087 -0.033894 0.00901825 0.0208087 -0.0338976 0.00911431 0.0208087 -0.0337159 -0.0261958 -0.0207424 0.020556 -0.0255457 -0.0202913 0.0209314 -0.0258204 -0.0202913 0.0199059 -0.0255457 -0.0202913 0.0201807 -0.0265711 -0.0202913 0.0212062 -0.0254451 -0.0202913 0.020556 -0.0258204 -0.0202913 0.0212062 -0.0261958 -0.0202913 0.0213067 -0.0265711 -0.0202913 0.0199059 -0.0261958 -0.0202913 0.0198053 -0.0268459 -0.0202913 0.0201807 -0.0269465 -0.0202913 0.020556 -0.0268459 -0.0202913 0.0209314 0.0268543 -0.0202913 0.0201807 0.0265796 -0.0202913 0.0199059 0.0265796 -0.0202913 0.0212062 0.0262042 -0.0202913 0.0213067 0.0255541 -0.0202913 0.0201807 0.0255541 -0.0202913 0.0209314 0.0269549 -0.0202913 0.020556 0.0268543 -0.0202913 0.0209314 0.0258289 -0.0202913 0.0212062 0.0262042 -0.0207424 0.020556 0.0262042 -0.0202913 0.0198053 0.0258289 -0.0202913 0.0199059 0.0254535 -0.0202913 0.020556 -0.0719891 -0.00729131 0.0278117 -0.0719891 0.0175087 0.0278117 -0.0722313 0.0175087 0.0262313 -0.0722313 -0.00729131 0.0262313 -0.0730595 -0.00729131 0.0248638 -0.0730595 0.0175087 0.0248638 -0.0725393 -0.00729131 0.0263432 -0.0725393 0.0175087 0.0263432 -0.0484392 -0.00729131 0.0600826 -0.0501092 -0.00729131 0.0583769 -0.0491473 -0.00729131 0.0591055 -0.0512446 0.0175087 0.0577082 -0.0484392 0.0175087 0.0600826 -0.0501092 0.0175087 0.0583769 -0.0512446 -0.00729131 0.0577082 -0.0491473 0.0175087 0.0591055 -0.0590989 -0.00729131 0.049154 -0.0600759 -0.00729131 0.0484459 -0.0577015 -0.00729131 0.0512512 -0.0577015 0.0175087 0.0512512 -0.0600759 0.0175087 0.0484459 -0.0590989 0.0175087 0.049154 -0.0583703 0.0175087 0.0501158 -0.0583703 -0.00729131 0.0501158 -0.0263365 -0.00729131 0.0725459 -0.0262247 -0.00729131 0.0722379 -0.0263365 0.0175087 0.0725459 -0.0248571 -0.00729131 0.0730661 -0.0248571 0.0175087 0.0730661 -0.027805 -0.00729131 0.0719958 -0.0262247 0.0175087 0.0722379 -0.027805 0.0175087 0.0719958 0.0278134 -0.00729131 0.0719958 0.0262331 -0.00729131 0.0722379 0.0262331 0.0175087 0.0722379 0.0263449 -0.00729131 0.0725459 0.0248656 -0.00729131 0.0730661 0.0263449 0.0175087 0.0725459 0.0248656 0.0175087 0.0730661 0.0278134 0.0175087 0.0719958 0.0577099 -0.00729131 0.0512512 0.0600844 -0.00729131 0.0484459 0.0583787 -0.00729131 0.0501158 0.0591073 0.0175087 0.049154 0.0583787 0.0175087 0.0501158 0.0591073 -0.00729131 0.049154 0.0577099 0.0175087 0.0512512 0.0600844 0.0175087 0.0484459 0.0491557 -0.00729131 0.0591055 0.0484476 -0.00729131 0.0600826 0.0491557 0.0175087 0.0591055 0.051253 -0.00729131 0.0577082 0.0501176 0.0175087 0.0583769 0.0501176 -0.00729131 0.0583769 0.0484476 0.0175087 0.0600826 0.051253 0.0175087 0.0577082 0.0730679 0.0175087 0.0248638 0.0722397 -0.00729131 0.0262313 0.0722397 0.0175087 0.0262313 0.0719975 -0.00729131 0.0278117 0.0719975 0.0175087 0.0278117 0.0730679 -0.00729131 0.0248638 0.0725477 0.0175087 0.0263432 0.0725477 -0.00729131 0.0263432 0.0273843 0.0208087 0.0142546 0.0273843 0.0208087 0.0166892 0.0267981 0.0216205 0.0154719 0.0278544 0.0208087 0.0163143 0.0281153 0.0208087 0.0151712 0.0278544 0.0208087 0.0146295 0.0281153 0.0208087 0.0157725 0.0267981 0.0208087 0.016823 0.025628 0.0208087 0.0161474 0.025628 0.0208087 0.0147964 0.0267981 0.0208087 0.0141208 0.0261225 0.0208087 0.016642 0.0261225 0.0208087 0.0143018 0.025447 0.0208087 0.0154719 -0.0256196 0.0208087 0.0147964 -0.0256196 0.0208087 0.0161474 -0.0261141 0.0208087 0.0143018 -0.0267897 0.0208087 0.016823 -0.0261141 0.0208087 0.016642 -0.0254386 0.0208087 0.0154719 -0.0279597 0.0208087 0.0147964 -0.0279597 0.0208087 0.0161474 -0.0267897 0.0208087 0.0141208 -0.0274652 0.0208087 0.016642 -0.0274652 0.0208087 0.0143018 -0.0281407 0.0208087 0.0154719 -0.0267897 0.0216205 0.0154719 0.0586498 0.0192087 0.000725113 0.0586488 0.0202587 0.00079959 0.0582111 0.0205587 0.00719815 0.0582019 0.0202587 0.00727207 0.0585175 0.0205587 0.00400486 0.0582111 0.0202587 0.00719815 0.0582697 0.0202587 0.00713564 0.0586488 0.0205587 0.00079959 0.0586983 0.0202587 0.000869491 0.0595304 0.0205587 0.00292223 0.0595304 0.0192087 0.00292223 0.0593736 0.0192087 0.00521532 0.0582697 0.0192087 0.00713564 0.0593736 0.0205587 0.00521532 0.0586498 0.0202587 0.000725113 0.0582019 0.0192087 0.00727207 0.0586983 0.0192087 0.000869491 0.05628 0.0192087 0.0165207 0.05628 0.0202587 0.0165207 0.0552678 0.0205587 0.0196431 0.0541113 0.0202587 0.0226354 0.0540825 0.0192087 0.022704 0.056259 0.0202587 0.0165921 0.0562878 0.0202587 0.0166728 0.0541113 0.0205587 0.0226354 0.0557656 0.0205587 0.0210397 0.056259 0.0205587 0.0165921 0.0565353 0.0205587 0.0188739 0.0562878 0.0192087 0.0166728 0.0541845 0.0202587 0.022591 0.0541845 0.0192087 0.022591 0.0540825 0.0202587 0.022704 0.0557656 0.0192087 0.0210397 0.0565353 0.0192087 0.0188739 0.0459523 0.0202587 0.0364524 0.0459523 0.0192087 0.0364524 0.0460811 0.0202587 0.036371 0.0460811 0.0192087 0.036371 0.0497031 0.0192087 0.0312398 0.0497366 0.0192087 0.0310912 0.0496971 0.0202587 0.0311543 0.0459985 0.0202587 0.036394 0.0479195 0.0205587 0.0338247 0.0497031 0.0202587 0.0312398 0.0459985 0.0205587 0.036394 0.048022 0.0205587 0.0353038 0.0493475 0.0192087 0.033426 0.048022 0.0192087 0.0353038 0.0493475 0.0205587 0.033426 0.0496971 0.0205587 0.0311543 0.0497366 0.0202587 0.0310912 0.0395048 0.0202587 0.043356 0.0394497 0.0202587 0.0434061 0.0394324 0.0192087 0.04349 0.0344746 0.0202587 0.0474536 0.0345603 0.0202587 0.0474537 0.0394324 0.0202587 0.04349 0.0394497 0.0205587 0.0434061 0.0367172 0.0205587 0.0469498 0.0367172 0.0192087 0.0469498 0.0385001 0.0205587 0.0454992 0.0344746 0.0205587 0.0474536 0.0370175 0.0205587 0.0454979 0.0344143 0.0202587 0.0474973 0.0395048 0.0192087 0.043356 0.0344143 0.0192087 0.0474973 0.0345603 0.0192087 0.0474537 0.0385001 0.0192087 0.0454992 0.0262768 0.0202587 0.0524388 0.0233704 0.0205587 0.0537969 0.0263433 0.0192087 0.0524054 0.0203942 0.0202587 0.054994 0.0203942 0.0205587 0.054994 0.0204766 0.0202587 0.0550172 0.0247977 0.0205587 0.0541982 0.0226895 0.0192087 0.0551139 0.0204766 0.0192087 0.0550172 0.0262768 0.0205587 0.0524388 0.0226895 0.0205587 0.0551139 0.0262375 0.0192087 0.0525149 0.0263433 0.0202587 0.0524054 0.0262375 0.0202587 0.0525149 0.0203244 0.0202587 0.0550198 0.0247977 0.0192087 0.0541982 0.0203244 0.0192087 0.0550198 0.00472731 0.0192087 0.058462 0.011097 0.0192087 0.0576453 0.00487466 0.0192087 0.0585005 0.0111553 0.0205587 0.0575826 0.0111553 0.0202587 0.0575826 0.011097 0.0202587 0.0576453 0.00925645 0.0192087 0.0588776 0.00925645 0.0205587 0.0588776 0.00697941 0.0192087 0.0591906 0.00697941 0.0205587 0.0591906 0.00480155 0.0205587 0.0584559 0.00799038 0.0205587 0.0581062 0.0112284 0.0192087 0.0575684 0.00487466 0.0202587 0.0585005 0.00472731 0.0202587 0.058462 0.00480155 0.0202587 0.0584559 0.0112284 0.0202587 0.0575684 -0.0111469 0.0205587 0.0575826 -0.00479313 0.0202587 0.0584559 -0.00479313 0.0205587 0.0584559 -0.0111469 0.0202587 0.0575826 -0.0110885 0.0202587 0.0576453 -0.00697099 0.0192087 0.0591906 -0.00924803 0.0205587 0.0588776 -0.00924803 0.0192087 0.0588776 -0.00697099 0.0205587 0.0591906 -0.00798196 0.0205587 0.0581062 -0.00471889 0.0192087 0.058462 -0.00486624 0.0192087 0.0585005 -0.00486624 0.0202587 0.0585005 -0.01122 0.0202587 0.0575684 -0.01122 0.0192087 0.0575684 -0.0110885 0.0192087 0.0576453 -0.00471889 0.0202587 0.058462 -0.026229 0.0202587 0.0525149 -0.0263349 0.0202587 0.0524054 -0.0262683 0.0202587 0.0524388 -0.026229 0.0192087 0.0525149 -0.0263349 0.0192087 0.0524054 -0.0203159 0.0192087 0.0550198 -0.0204682 0.0202587 0.0550172 -0.0203858 0.0205587 0.054994 -0.0203858 0.0202587 0.054994 -0.0226811 0.0192087 0.0551139 -0.0247893 0.0192087 0.0541982 -0.0226811 0.0205587 0.0551139 -0.023362 0.0205587 0.0537969 -0.0247893 0.0205587 0.0541982 -0.0262683 0.0205587 0.0524388 -0.0203159 0.0202587 0.0550198 -0.0204682 0.0192087 0.0550172 -0.0344662 0.0205587 0.0474536 -0.0394963 0.0202587 0.043356 -0.0344059 0.0192087 0.0474973 -0.0344662 0.0202587 0.0474536 -0.0394413 0.0202587 0.0434061 -0.0394413 0.0205587 0.0434061 -0.0394239 0.0192087 0.04349 -0.0367088 0.0205587 0.0469498 -0.0367088 0.0192087 0.0469498 -0.0384917 0.0192087 0.0454992 -0.0370091 0.0205587 0.0454979 -0.0384917 0.0205587 0.0454992 -0.0345519 0.0192087 0.0474537 -0.0345519 0.0202587 0.0474537 -0.0394239 0.0202587 0.04349 -0.0394963 0.0192087 0.043356 -0.0344059 0.0202587 0.0474973 -0.0459439 0.0192087 0.0364524 -0.0459439 0.0202587 0.0364524 -0.0496946 0.0202587 0.0312398 -0.0497282 0.0202587 0.0310912 -0.0480136 0.0192087 0.0353038 -0.0497282 0.0192087 0.0310912 -0.0496887 0.0202587 0.0311543 -0.0460726 0.0192087 0.036371 -0.0496887 0.0205587 0.0311543 -0.0459901 0.0202587 0.036394 -0.0460726 0.0202587 0.036371 -0.0493391 0.0192087 0.033426 -0.0496946 0.0192087 0.0312398 -0.0459901 0.0205587 0.036394 -0.0479111 0.0205587 0.0338247 -0.0480136 0.0205587 0.0353038 -0.0493391 0.0205587 0.033426 -0.0552594 0.0205587 0.0196431 -0.0562506 0.0202587 0.0165921 -0.0562716 0.0202587 0.0165207 -0.0562716 0.0192087 0.0165207 -0.0541028 0.0202587 0.0226354 -0.0557571 0.0192087 0.0210397 -0.0562506 0.0205587 0.0165921 -0.0557571 0.0205587 0.0210397 -0.0565268 0.0205587 0.0188739 -0.0565268 0.0192087 0.0188739 -0.0541028 0.0205587 0.0226354 -0.0540741 0.0202587 0.022704 -0.0562794 0.0202587 0.0166728 -0.0562794 0.0192087 0.0166728 -0.0541761 0.0192087 0.022591 -0.0540741 0.0192087 0.022704 -0.0541761 0.0202587 0.022591 -0.0581935 0.0192087 0.00727207 -0.0581935 0.0202587 0.00727207 -0.0586404 0.0205587 0.00079959 -0.059522 0.0205587 0.00292223 -0.0582027 0.0205587 0.00719815 -0.0593651 0.0205587 0.00521532 -0.0593651 0.0192087 0.00521532 -0.059522 0.0192087 0.00292223 -0.0585091 0.0205587 0.00400486 -0.0582612 0.0192087 0.00713564 -0.0586413 0.0202587 0.000725113 -0.0586413 0.0192087 0.000725113 -0.0586899 0.0202587 0.000869491 -0.0586404 0.0202587 0.00079959 -0.0586899 0.0192087 0.000869491 -0.0582612 0.0202587 0.00713564 -0.0582027 0.0202587 0.00719815 -0.0268459 -0.0202913 -0.0209265 -0.0269465 -0.0202913 -0.0205511 -0.0268459 -0.0202913 -0.0201758 -0.0255457 -0.0202913 -0.0201758 -0.0261958 -0.0207424 -0.0205511 -0.0255457 -0.0202913 -0.0209265 -0.0265711 -0.0202913 -0.019901 -0.0261958 -0.0202913 -0.0198004 -0.0258204 -0.0202913 -0.0212013 -0.0258204 -0.0202913 -0.019901 -0.0254451 -0.0202913 -0.0205511 -0.0265711 -0.0202913 -0.0212013 -0.0261958 -0.0202913 -0.0213019 0.0262042 -0.0207424 -0.0205511 0.0268543 -0.0202913 -0.0201758 0.0269549 -0.0202913 -0.0205511 0.0262042 -0.0202913 -0.0198004 0.0268543 -0.0202913 -0.0209265 0.0265796 -0.0202913 -0.0212013 0.0265796 -0.0202913 -0.019901 0.0255541 -0.0202913 -0.0209265 0.0262042 -0.0202913 -0.0213019 0.0258289 -0.0202913 -0.0212013 0.0255541 -0.0202913 -0.0201758 0.0258289 -0.0202913 -0.019901 0.0254535 -0.0202913 -0.0205511 0.014875 -0.0202913 -0.0468995 0.0153875 -0.0206413 -0.0477872 0.0152502 -0.0206413 -0.0482997 0.0152502 -0.0202913 -0.0482997 0.0143625 -0.0206413 -0.0488122 0.0152502 -0.0206413 -0.0472747 0.0143625 -0.0206413 -0.0467622 0.014875 -0.0206413 -0.0468995 0.014875 -0.0206413 -0.0486749 0.0152502 -0.0202913 -0.0472747 0.0143625 -0.0202913 -0.0467622 0.0133375 -0.0202913 -0.0477872 0.014875 -0.0202913 -0.0486749 0.0153875 -0.0202913 -0.0477872 0.0143625 -0.0202913 -0.0488122 0.0134748 -0.0202913 -0.0482997 0.0143625 -0.0212572 -0.0477872 0.01385 -0.0206413 -0.0486749 0.0133375 -0.0206413 -0.0477872 0.01385 -0.0202913 -0.0486749 0.0134748 -0.0206413 -0.0482997 0.0134748 -0.0206413 -0.0472747 0.01385 -0.0206413 -0.0468995 0.0134748 -0.0202913 -0.0472747 0.01385 -0.0202913 -0.0468995 -0.0139093 -0.0202913 -0.0468637 -0.0143541 -0.0206413 -0.0467622 -0.0133548 -0.0202913 -0.0475591 -0.0133548 -0.0206413 -0.0475591 -0.0134664 -0.0206413 -0.0472747 -0.0135527 -0.0202913 -0.0471481 -0.0135527 -0.0206413 -0.0471481 -0.0133291 -0.0206413 -0.0477872 -0.0133548 -0.0202913 -0.0480153 -0.0134664 -0.0206413 -0.0482997 -0.0135527 -0.0202913 -0.0484263 -0.0138416 -0.0206413 -0.0486749 -0.0143541 -0.0202913 -0.0488122 -0.0143541 -0.0212572 -0.0477872 -0.0133548 -0.0206413 -0.0480153 -0.0143541 -0.0206413 -0.0488122 -0.0135527 -0.0206413 -0.0484263 -0.0138416 -0.0206413 -0.0468995 -0.0152418 -0.0202913 -0.0482997 -0.0148666 -0.0202913 -0.0486749 -0.0139093 -0.0202913 -0.0487107 -0.0152418 -0.0202913 -0.0472747 -0.0143541 -0.0202913 -0.0467622 -0.0153791 -0.0202913 -0.0477872 -0.0148666 -0.0206413 -0.0486749 -0.0152418 -0.0206413 -0.0482997 -0.0153791 -0.0206413 -0.0477872 -0.0152418 -0.0206413 -0.0472747 -0.0148666 -0.0206413 -0.0468995 -0.0148666 -0.0202913 -0.0468995 -0.027624 -0.00729131 -0.0719869 -0.027805 0.0175087 -0.0719909 -0.027624 0.0175087 -0.0719869 -0.0261399 -0.00729131 -0.0722649 -0.0248571 -0.00729131 -0.0730613 -0.027805 -0.00729131 -0.0719909 -0.0248571 0.0175087 -0.0730613 -0.0261399 0.0175087 -0.0722649 -0.0583703 0.0175087 -0.0501109 -0.0583703 -0.00729131 -0.0501109 -0.0577015 0.0175087 -0.0512464 -0.0600759 0.0175087 -0.048441 -0.0577015 -0.00729131 -0.0512464 -0.0600759 -0.00729131 -0.048441 -0.0590989 -0.00729131 -0.0491491 -0.0590989 0.0175087 -0.0491491 -0.0491473 -0.00729131 -0.0591007 -0.0491473 0.0175087 -0.0591007 -0.0484392 -0.00729131 -0.0600777 -0.0512446 0.0175087 -0.0577033 -0.0501092 0.0175087 -0.0583721 -0.0501092 -0.00729131 -0.0583721 -0.0484392 0.0175087 -0.0600777 -0.0512446 -0.00729131 -0.0577033 -0.0722313 -0.00729131 -0.0262265 -0.0730595 0.0175087 -0.0248589 -0.0730595 -0.00729131 -0.0248589 -0.0725393 -0.00729131 -0.0263383 -0.0719891 -0.00729131 -0.0278068 -0.0719891 0.0175087 -0.0278068 -0.0722313 0.0175087 -0.0262265 -0.0725393 0.0175087 -0.0263383 0.0719975 -0.00729131 -0.0278068 0.0725477 -0.00729131 -0.0263383 0.0725477 0.0175087 -0.0263383 0.0730679 0.0175087 -0.0248589 0.0719975 0.0175087 -0.0278068 0.0722397 -0.00729131 -0.0262265 0.0730679 -0.00729131 -0.0248589 0.0722397 0.0175087 -0.0262265 0.051253 -0.00729131 -0.0577033 0.0501176 0.0175087 -0.0583721 0.051253 0.0175087 -0.0577033 0.0501176 -0.00729131 -0.0583721 0.0484476 -0.00729131 -0.0600777 0.0491557 -0.00729131 -0.0591007 0.0484476 0.0175087 -0.0600777 0.0491557 0.0175087 -0.0591007 0.0600844 -0.00729131 -0.048441 0.0577099 -0.00729131 -0.0512464 0.0577099 0.0175087 -0.0512464 0.0583787 0.0175087 -0.0501109 0.0591073 0.0175087 -0.0491491 0.0591073 -0.00729131 -0.0491491 0.0600844 0.0175087 -0.048441 0.0583787 -0.00729131 -0.0501109 0.0248656 -0.00729131 -0.0730613 0.0261484 -0.00729131 -0.0722649 0.0248656 0.0175087 -0.0730613 0.0276324 -0.00729131 -0.0719869 0.0278134 -0.00729131 -0.0719909 0.0278134 0.0175087 -0.0719909 0.0261484 0.0175087 -0.0722649 0.0276324 0.0175087 -0.0719869 0.00135528 0.0208087 -0.0309365 4.20971e-06 0.0208087 -0.0322875 4.20971e-06 0.0216205 -0.0309365 0.000679747 0.0208087 -0.0297664 4.20971e-06 0.0208087 -0.0295854 0.000679747 0.0208087 -0.0321065 -0.00134686 0.0208087 -0.0309365 0.00117427 0.0208087 -0.031612 0.00117427 0.0208087 -0.0302609 -0.000671327 0.0208087 -0.0297664 -0.00116585 0.0208087 -0.0302609 -0.000671327 0.0208087 -0.0321065 -0.00116585 0.0208087 -0.031612 0.018892 0.0202587 -0.055523 0.0189625 0.0202587 -0.055499 0.0126436 0.0192087 -0.0572695 0.0127163 0.0205587 -0.0572534 0.0127948 0.0202587 -0.0572876 0.0127948 0.0192087 -0.0572876 0.0189625 0.0192087 -0.055499 0.0188427 0.0202587 -0.0555931 0.0147621 0.0192087 -0.0576891 0.0127163 0.0202587 -0.0572534 0.0126436 0.0202587 -0.0572695 0.018892 0.0205587 -0.055523 0.0170938 0.0205587 -0.0571147 0.0188427 0.0192087 -0.0555931 0.0147621 0.0205587 -0.0576891 0.0170938 0.0192087 -0.0571147 0.0277771 0.0192087 -0.0517123 0.0331436 0.0192087 -0.0484489 0.0284255 0.0192087 -0.0517543 0.0331436 0.0202587 -0.0484489 0.0331721 0.0205587 -0.0483681 0.0304407 0.0205587 -0.051332 0.0304407 0.0192087 -0.051332 0.032117 0.0192087 -0.0501362 0.0332335 0.0202587 -0.048326 0.0332335 0.0192087 -0.048326 0.0276266 0.0192087 -0.0517356 0.0331721 0.0202587 -0.0483681 0.0276923 0.0202587 -0.0517005 0.0277771 0.0202587 -0.0517123 0.032117 0.0205587 -0.0501362 0.0284255 0.0205587 -0.0517543 0.0276923 0.0205587 -0.0517005 0.0276266 0.0202587 -0.0517356 0.0405611 0.0192087 -0.0423646 0.0449924 0.0202587 -0.0376258 0.0406148 0.0205587 -0.042313 0.0427679 0.0192087 -0.0415085 0.0449867 0.0202587 -0.0377113 0.0443367 0.0205587 -0.0398287 0.0427679 0.0205587 -0.0415085 0.0428677 0.0205587 -0.0400293 0.0449924 0.0205587 -0.0376258 0.0405611 0.0202587 -0.0423646 0.0406997 0.0202587 -0.0423015 0.0450402 0.0202587 -0.0375686 0.0450402 0.0192087 -0.0375686 0.0449867 0.0192087 -0.0377113 0.0443367 0.0192087 -0.0398287 0.0406997 0.0192087 -0.0423015 0.0406148 0.0202587 -0.042313 0.0534761 0.0205587 -0.0240928 0.0535067 0.0202587 -0.0240249 0.0534761 0.0202587 -0.0240928 0.0504876 0.0192087 -0.0298514 0.0505255 0.0202587 -0.0297872 0.0505255 0.0205587 -0.0297872 0.0523816 0.0192087 -0.0284317 0.0534391 0.0192087 -0.0263909 0.0523816 0.0205587 -0.0284317 0.0520787 0.0205587 -0.0269804 0.0534391 0.0205587 -0.0263909 0.0506041 0.0192087 -0.0297532 0.0504876 0.0202587 -0.0298514 0.0535067 0.0192087 -0.0240249 0.0534936 0.0202587 -0.0241766 0.0534936 0.0192087 -0.0241766 0.0506041 0.0202587 -0.0297532 0.0580051 0.0192087 -0.00869907 0.0574275 0.0205587 -0.0119303 0.0566892 0.0202587 -0.0150521 0.0567557 0.0202587 -0.0149981 0.0567557 0.0192087 -0.0149981 0.057994 0.0205587 -0.00877272 0.0580335 0.0202587 -0.00884871 0.0580335 0.0192087 -0.00884871 0.0581108 0.0192087 -0.013246 0.0585784 0.0205587 -0.0109956 0.0585784 0.0192087 -0.0109956 0.0566892 0.0205587 -0.0150521 0.0581108 0.0205587 -0.013246 0.05667 0.0192087 -0.0151241 0.05667 0.0202587 -0.0151241 0.0580051 0.0202587 -0.00869907 0.057994 0.0202587 -0.00877272 -0.0566616 0.0192087 -0.0151241 -0.0566616 0.0202587 -0.0151241 -0.0579856 0.0202587 -0.00877272 -0.0579967 0.0192087 -0.00869907 -0.0574191 0.0205587 -0.0119303 -0.0566807 0.0202587 -0.0150521 -0.0580251 0.0202587 -0.00884871 -0.0580251 0.0192087 -0.00884871 -0.0581023 0.0205587 -0.013246 -0.0567473 0.0202587 -0.0149981 -0.05857 0.0205587 -0.0109956 -0.05857 0.0192087 -0.0109956 -0.0581023 0.0192087 -0.013246 -0.0567473 0.0192087 -0.0149981 -0.0566807 0.0205587 -0.0150521 -0.0579856 0.0205587 -0.00877272 -0.0579967 0.0202587 -0.00869907 -0.0504792 0.0202587 -0.0298514 -0.0504792 0.0192087 -0.0298514 -0.050517 0.0202587 -0.0297872 -0.0534982 0.0202587 -0.0240249 -0.0534852 0.0202587 -0.0241766 -0.0534852 0.0192087 -0.0241766 -0.0534306 0.0192087 -0.0263909 -0.050517 0.0205587 -0.0297872 -0.0505957 0.0202587 -0.0297532 -0.0534677 0.0202587 -0.0240928 -0.0523732 0.0192087 -0.0284317 -0.0534677 0.0205587 -0.0240928 -0.0534306 0.0205587 -0.0263909 -0.0523732 0.0205587 -0.0284317 -0.0520703 0.0205587 -0.0269804 -0.0505957 0.0192087 -0.0297532 -0.0534982 0.0192087 -0.0240249 -0.0405526 0.0202587 -0.0423646 -0.0406064 0.0202587 -0.042313 -0.044984 0.0202587 -0.0376258 -0.0443283 0.0192087 -0.0398287 -0.0406913 0.0202587 -0.0423015 -0.0427595 0.0205587 -0.0415085 -0.044984 0.0205587 -0.0376258 -0.0449783 0.0202587 -0.0377113 -0.0427595 0.0192087 -0.0415085 -0.0406064 0.0205587 -0.042313 -0.0443283 0.0205587 -0.0398287 -0.0428593 0.0205587 -0.0400293 -0.0450317 0.0192087 -0.0375686 -0.0450317 0.0202587 -0.0375686 -0.0405526 0.0192087 -0.0423646 -0.0406913 0.0192087 -0.0423015 -0.0449783 0.0192087 -0.0377113 -0.0332251 0.0192087 -0.048326 -0.0276182 0.0192087 -0.0517356 -0.0276839 0.0202587 -0.0517005 -0.0331637 0.0202587 -0.0483681 -0.0331352 0.0202587 -0.0484489 -0.0331352 0.0192087 -0.0484489 -0.0304323 0.0192087 -0.051332 -0.0304323 0.0205587 -0.051332 -0.0321085 0.0192087 -0.0501362 -0.0321085 0.0205587 -0.0501362 -0.0331637 0.0205587 -0.0483681 -0.0332251 0.0202587 -0.048326 -0.0276182 0.0202587 -0.0517356 -0.0277687 0.0202587 -0.0517123 -0.028417 0.0192087 -0.0517543 -0.0276839 0.0205587 -0.0517005 -0.0277687 0.0192087 -0.0517123 -0.028417 0.0205587 -0.0517543 -0.018954 0.0192087 -0.055499 -0.0126351 0.0202587 -0.0572695 -0.0127079 0.0202587 -0.0572534 -0.0188835 0.0202587 -0.055523 -0.0127079 0.0205587 -0.0572534 -0.0170854 0.0192087 -0.0571147 -0.0147537 0.0192087 -0.0576891 -0.0188343 0.0202587 -0.0555931 -0.0188835 0.0205587 -0.055523 -0.0170854 0.0205587 -0.0571147 -0.0147537 0.0205587 -0.0576891 -0.0188343 0.0192087 -0.0555931 -0.0126351 0.0192087 -0.0572695 -0.0127864 0.0202587 -0.0572876 -0.0127864 0.0192087 -0.0572876 -0.018954 0.0202587 -0.055499 0.00321097 0.0202587 -0.0585598 0.00321097 0.0205587 -0.0585598 0.00314461 0.0202587 -0.058614 0.00170888 0.0192087 -0.0594193 -0.00320255 0.0202587 -0.0585598 4.20971e-06 0.0205587 -0.0597176 -0.00170046 0.0192087 -0.0594193 -0.00313619 0.0202587 -0.058614 -0.00170046 0.0205587 -0.0594193 0.00170888 0.0205587 -0.0594193 -0.00320255 0.0205587 -0.0585598 -0.00327692 0.0202587 -0.0585557 0.00328534 0.0202587 -0.0585557 0.00314461 0.0192087 -0.058614 4.20971e-06 0.0192087 -0.0597176 -0.00313619 0.0192087 -0.058614 -0.00327692 0.0192087 -0.0585557 0.00328534 0.0192087 -0.0585557 + + + + + + + + + + -0.813095 0.580778 0.0396639 -0.841019 0.540224 0.029069 -0.82431 0.566098 -0.00682692 -0.849357 0.526242 -0.0407537 -0.854588 0.517168 -0.0470833 -0.862881 0.503872 0.0393682 -0.853045 0.519794 0.0461425 -0.850265 0.52449 0.0442595 -0.834446 0.54969 0.0392617 -0.499596 0.863513 0.0689133 -0.583957 0.80425 0.110347 -0.54306 0.838677 0.041326 -0.638272 0.768061 0.0518712 -0.650484 0.757365 0.0571818 -0.699186 0.713675 0.0424995 -0.764032 0.642949 0.0535898 -0.757288 0.650295 0.0602623 -0.794275 0.605945 0.0442416 -0.453123 0.887089 0.0880423 -0.490106 0.863616 0.118172 -0.460227 0.885638 0.0619366 -0.464191 0.883106 0.0681954 -0.50339 0.863795 0.0213678 -0.495693 0.867952 -0.030779 -0.413218 0.908255 -0.0657526 -0.44976 0.88911 -0.0848466 -0.466412 0.881517 -0.073408 -0.526417 0.84875 -0.0500778 -0.600891 0.798071 -0.0448684 -0.650448 0.757376 -0.0574286 -0.651838 0.756229 -0.0567802 -0.853241 0.519486 -0.0459791 -0.840767 0.539878 -0.0405179 -0.817189 0.575076 -0.0386121 -0.794276 0.605946 -0.0442146 -0.767783 0.638273 -0.0558223 -0.763777 0.642778 -0.0589987 -0.729886 0.682042 -0.0456572 -0.688544 0.723747 -0.0458002 0.032454 0.998711 0.0390254 0.033053 0.998762 0.0371797 0.0190452 0.996305 -0.0837447 0.06178 0.997905 0.0192204 -0.0481382 0.994664 0.0912435 -0.0968885 0.994895 0.0282296 -0.00679979 0.997232 0.0740407 -0.0875548 0.995935 0.0211574 0.00960363 0.999242 0.0377386 -0.0296374 0.999206 0.0266423 0.00872504 0.999726 0.0217224 -0.0521298 0.998506 0.0163552 -0.0742408 0.991376 0.107993 -0.0859257 0.994572 0.0586752 -0.0857267 0.993502 0.0748673 -0.0989319 0.993877 0.0492111 0.00554235 0.999747 0.0217908 -0.0300095 0.999366 0.0191544 -0.00877226 0.999927 0.00835089 0.0223542 0.999743 -0.00368761 -0.00451111 0.999752 0.0217935 0.036935 0.999266 -0.0102103 0.0383199 0.999183 -0.0128312 0.0626509 0.997755 0.0236423 0.0783399 0.995727 0.0488918 0.0305763 0.999451 0.0127324 0.0757434 0.995124 0.063178 0.0108745 0.999444 0.0315144 0.0627949 0.996001 0.0635462 0.00736187 0.998477 0.0546857 3.04994e-05 0.998609 0.0527222 0.0128579 0.998635 0.0506171 0.0177839 0.99857 0.0504081 0.0410143 0.997841 0.051296 0.0296114 0.997859 0.0583227 -0.0167224 0.996631 0.0802922 0.0182712 0.999062 0.0392651 -0.0463461 0.993899 0.100087 -0.0543755 0.991344 0.119498 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.632384 0.772344 0.0597931 -0.755461 0.650238 -0.0804329 -0.712082 0.638424 -0.292156 -0.50916 0.858995 -0.0537009 -0.708588 0.36336 -0.604874 -0.558453 0.754849 -0.343996 -0.456673 0.700685 -0.54817 -0.398527 0.626467 -0.669863 -0.745185 0.607571 0.274877 -0.683687 0.701499 0.201173 -0.698698 0.71452 -0.0358198 -0.534146 0.598011 0.597554 -0.537667 0.732661 0.417281 -0.634538 0.694315 0.339541 0.021045 0.713696 0.70014 -0.0385629 0.713428 0.699666 -0.189181 0.631257 0.752147 -0.20078 0.676769 0.708287 -0.392251 0.72994 0.559756 0.0202904 0.713917 0.699936 0.121143 0.712217 0.691427 0.169538 0.773352 0.610887 0.407746 0.601072 0.687354 0.412898 0.717861 0.560527 0.651133 0.648174 0.394838 0.71803 0.573363 0.394573 0.53616 0.719989 0.440623 -0.35544 0.676877 -0.644593 -0.11067 0.730805 -0.673555 -0.0985401 0.710514 -0.696749 0.108343 0.709243 -0.696589 0.198453 0.594489 -0.77923 0.323687 0.78394 -0.529778 0.375296 0.746703 -0.54917 0.611443 0.644765 -0.458712 0.486134 0.755734 -0.438794 0.688147 0.659004 -0.303591 0.757349 0.587777 -0.2845 0.631723 0.771495 -0.0756416 0.874123 0.428109 0.229414 -0.26658 0.73933 -0.618326 0.732505 0.617777 -0.285986 -0.215636 0.713143 0.66703 -0.196752 0.637718 0.744717 -0.0611252 0.733479 0.676958 -0.0177136 0.735102 0.677725 0.0034819 0.735217 0.677822 0.0977089 0.761961 0.64021 0.0899405 0.747801 0.657803 0.22571 0.736164 0.638057 0.254624 0.756804 0.602008 0.380821 0.7111 0.591026 0.402464 0.694732 0.59613 0.431849 0.74851 0.503228 0.662742 0.635164 0.396659 0.661133 0.63675 0.396803 0.516681 0.747701 0.417115 0.651305 0.732743 -0.197202 0.675571 0.73493 -0.0589997 0.732802 0.678361 0.0531741 0.712623 0.698777 0.0622762 0.602035 0.766793 0.222669 0.131884 0.698125 -0.703724 0.184464 0.777736 -0.600916 0.28701 0.721836 -0.629744 0.339011 0.727751 -0.596197 0.398657 0.714903 -0.574444 0.413989 0.751024 -0.514369 0.533628 0.693341 -0.484272 0.532731 0.742989 -0.405172 0.624217 0.7054 -0.335805 -0.200896 0.732401 -0.650561 -0.0914668 0.743927 -0.661972 -0.0832245 0.729113 -0.679314 0.0185471 0.731512 -0.681576 0.0418499 0.730778 -0.681331 -0.427297 0.62138 -0.656737 -0.401074 0.649897 -0.64558 -0.43414 0.71742 -0.544821 -0.491611 0.754014 -0.435639 -0.671111 0.617946 -0.409576 -0.67449 0.608686 -0.41781 -0.737 0.672125 -0.0712728 -0.713692 0.695594 -0.0824188 -0.611665 0.75219 -0.245105 -0.739001 0.61394 0.277409 -0.65476 0.733401 0.18279 -0.681692 0.730577 0.0394026 -0.326174 0.730315 0.600209 -0.432616 0.708672 0.55734 -0.521648 0.620334 0.585721 -0.526829 0.746055 0.40725 -0.621772 0.709469 0.331743 0.729725 0.6327 -0.259215 0.477403 0.7607 0.439797 -0.22244 0.729326 -0.646996 -0.120789 0.741698 -0.659768 -0.113649 0.729637 -0.674325 -0.0172544 0.735114 -0.677724 0.147015 0.727499 -0.670173 -0.627181 0.652815 -0.424825 -0.462623 0.766295 -0.445838 -0.409265 0.646883 -0.643463 -0.430436 0.623457 -0.652707 -0.281612 0.734797 -0.617064 -0.661276 0.622876 -0.418017 -0.661326 0.622828 -0.418012 -0.606685 0.751507 -0.259171 -0.659506 0.726963 -0.191252 -0.66253 0.743188 -0.093408 -0.722993 0.689367 -0.0453203 -0.684391 0.728791 0.021758 -0.651366 0.740487 0.165534 -0.74057 0.614266 0.272458 -0.627203 0.709485 0.321321 -0.526036 0.75218 0.396878 -0.515146 0.626142 0.585296 -0.430574 0.709602 0.557738 0.0412894 0.730795 0.681348 0.0186325 0.731508 0.681579 -0.0278727 0.731424 0.681353 -0.174036 0.634169 0.753354 -0.194082 0.7182 0.668222 -0.314858 0.735207 0.600279 0.432812 0.672245 0.600633 0.039798 0.731268 0.680929 0.140149 0.726796 0.672404 0.150179 0.739875 0.655768 0.262641 0.721354 0.640835 0.292643 0.740885 0.604524 0.411309 0.690449 0.595067 0.66451 0.620279 0.41675 0.64454 0.639855 0.418514 0.623175 0.709738 0.328519 0.642007 0.752107 -0.14887 0.678975 0.734148 -0.00444172 0.748732 0.653538 0.11085 0.741028 0.661673 0.114308 0.631066 0.73924 0.235118 0.144919 0.713629 -0.68537 0.303143 0.745799 -0.593201 0.373434 0.733275 -0.568203 0.384587 0.771326 -0.507098 0.512365 0.724327 -0.461338 0.51338 0.769084 -0.380724 0.620507 0.722211 -0.305586 -0.484897 0.508501 -0.711549 -0.401015 0.625149 -0.669609 -0.494567 0.747774 -0.442987 -0.690693 0.590894 -0.416877 -0.676946 0.605193 -0.418911 -0.625042 0.740807 -0.246022 -0.756236 0.649097 -0.0823393 -0.75572 0.649268 -0.0856699 -0.75946 0.645278 -0.0826846 -0.698931 0.714129 0.0389324 -0.681944 0.704255 0.197429 -0.746033 0.606338 0.275298 -0.639251 0.691531 0.336367 -0.53775 0.73565 0.411878 -0.532577 0.599268 0.597695 -0.437588 0.69226 0.573841 -0.184847 0.630203 0.754106 -0.197205 0.679023 0.707134 -0.323167 0.716359 0.618379 0.420935 0.645265 0.637532 0.447913 0.615983 0.648026 0.295542 0.718829 0.629237 0.23458 0.710344 0.663614 0.120632 0.729446 0.673318 0.108387 0.70922 0.696606 -0.0330184 0.713432 0.699946 0.663544 0.618501 0.42091 0.692741 0.588502 0.416863 0.499952 0.744952 0.441696 0.634455 0.698916 -0.330126 0.800878 0.553402 -0.228782 0.665957 0.705645 -0.242004 0.69924 0.714155 -0.0323422 0.767675 0.633694 0.0954299 0.772455 0.628213 0.093071 0.623136 0.74178 0.24792 -0.300961 0.6942 -0.653842 -0.116352 0.730091 -0.673371 -0.104196 0.710008 -0.696442 0.0190376 0.713753 -0.700138 0.143665 0.742616 -0.654127 0.194323 0.680613 -0.706402 0.317978 0.722132 -0.614342 0.484175 0.686832 -0.542066 0.514043 0.529092 -0.675146 0.533581 0.741697 -0.40642 0.413124 -1.19434e-07 -0.910675 0.258787 0.0151233 -0.965816 0.608761 6.00044e-07 -0.793354 0.707014 0.0161949 -0.707014 0.793357 0 -0.608757 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258817 0.965926 0 0.258817 0.707107 0 0.707107 0.707107 0 0.707107 0.258817 0 0.965926 0.13095 0.0329731 0.990841 0.382687 0 0.923878 -0.707107 0 -0.707107 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.793357 0 0.608757 -0.707008 0.016686 0.707008 -0.608757 0 0.793357 -0.258817 0 0.965926 -0.382545 0.0331382 0.923342 -0.130521 0 0.991446 0.16334 0 -0.98657 -0.130521 0 -0.991446 -0.258783 0.0162124 -0.965799 -0.382687 0 -0.923878 -0.707107 0 -0.707107 0.149222 0 0.988804 0.258785 0.0157965 0.965806 -0.130521 0 0.991446 -0.258783 0.0161759 0.9658 -0.382687 0 0.923878 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.258786 0.0166817 -0.965791 -0.382687 0 -0.923878 -0.707107 0 -0.707107 -0.608741 0.032953 -0.792684 -0.793357 0 -0.608757 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.707107 0 -0.707107 0.707107 0 -0.707107 0.382687 0 -0.923878 0.258787 0.0166386 -0.965791 0.130532 0 -0.991444 -0.130532 0 -0.991444 0.400048 0 0.916494 0.608764 0 0.793351 0.707014 0.0161651 0.707014 0.793352 0 0.608763 0.965926 0 0.258817 0.00737431 -0.906986 -0.421096 0.000747213 -0.939113 -0.343606 0 -0.935206 -0.354105 0 -0.846275 -0.532746 0.00316081 -0.911062 -0.412258 0.0157433 -0.872749 -0.487916 0.0114164 -0.889381 -0.457024 -0.0147483 -0.980457 -0.19618 -0.00594272 -0.991949 -0.126499 0.00423728 -0.996566 -0.0826956 0.00671882 -0.992175 -0.124678 0.00377804 -0.996498 -0.0835273 0 -0.977247 -0.212107 0 -0.958981 -0.283471 0 -0.952035 -0.30599 0.033564 -0.999303 0.0163216 0.00758475 -0.995007 -0.0995213 -0.00273898 -0.959466 -0.281812 -0.00968051 -0.93644 -0.350694 -0.00292135 -0.995704 -0.0925483 0.00151963 -0.999473 -0.0324166 -0.000992496 -0.994484 0.104884 0.002066 -0.966981 0.254841 0 -0.951771 0.306811 0 -0.951409 -0.30793 0.00209287 -0.966981 -0.254841 0.00671751 -0.992177 0.12466 0.00423521 -0.996569 0.0826571 0.00150548 -0.999482 0.0321546 -0.000988416 -0.99435 -0.106148 -0.00297994 -0.99574 0.0921529 -0.00604968 -0.991978 0.126267 0.0107449 -0.99992 -0.006661 -0.0028333 -0.994669 0.103077 0 -0.935206 0.354105 -0.00547796 -0.951661 0.307102 -0.00288631 -0.959492 0.281722 0.00117137 -0.976971 0.213367 0 -0.911066 0.41226 0.0215142 -0.852893 0.521642 0.0157441 -0.872745 0.487922 0.0114164 -0.889381 0.457024 0.00737432 -0.906986 0.421096 0.0120472 -0.979904 0.199105 0 -0.996505 0.0835279 0 -0.958981 0.283471 0.000747213 -0.939113 0.343607 0 -0.935206 0.354105 -0.50859 0.694747 -0.50859 -0.508591 0.694745 -0.50859 -0.694748 0.694746 -0.186155 -0.694742 0.694751 -0.186156 -0.694743 0.694751 0.186154 -0.694746 0.694747 0.186157 -0.50859 0.694747 0.508589 -0.50859 0.694747 0.508589 -0.186157 0.694745 0.694748 -0.186157 0.694745 0.694749 0.186158 0.694744 0.694749 0.186157 0.694745 0.694748 0.50859 0.694747 0.508589 0.50859 0.694747 0.508589 0.694745 0.694747 0.186159 0.694751 0.694742 0.186158 0.694751 0.694742 -0.18616 0.694747 0.694746 -0.186157 0.508591 0.694745 -0.508591 0.50859 0.694747 -0.508589 0.186158 0.694746 -0.694748 0.186157 0.694744 -0.694749 -0.186157 0.694744 -0.694749 -0.186156 0.694745 -0.694748 -0.50859 0.694747 -0.50859 -0.508591 0.694745 -0.50859 -0.694748 0.694746 -0.186155 -0.694742 0.694751 -0.186156 -0.694743 0.694751 0.186154 -0.694746 0.694747 0.186157 -0.50859 0.694747 0.50859 -0.508589 0.694749 0.508588 -0.186156 0.694748 0.694746 -0.186156 0.694747 0.694747 0.186157 0.694747 0.694747 0.186157 0.694748 0.694746 0.508588 0.694749 0.508588 0.50859 0.694747 0.508589 0.694745 0.694747 0.186159 0.694751 0.694742 0.186158 0.694751 0.694742 -0.18616 0.694747 0.694746 -0.186157 0.508591 0.694745 -0.508591 0.50859 0.694747 -0.508589 0.186158 0.694746 -0.694748 0.186158 0.694746 -0.694746 -0.186156 0.694747 -0.694747 -0.186157 0.694745 -0.694748 0.000695894 0 -1 -0.47726 -1.48879e-06 0.878762 -0.298328 0.0116939 0.954392 -0.2587 0.0301972 0.965486 -0.618014 -1.33192e-06 0.786167 -0.706563 0.039245 0.706561 -0.799967 0.000212036 0.600044 -0.999048 1.4998e-07 0.0436182 -0.965688 0.0221805 0.258756 -0.967037 0.0249824 0.253406 -0.889364 -8.82552e-05 0.457201 -0.965926 0 -0.258819 -0.923592 0.0758586 -0.375797 -0.992196 -4.28733e-07 -0.124687 -0.552128 1.91735e-08 -0.833759 -0.62909 0.0138006 -0.77721 -0.706615 0.037291 -0.706615 -0.750676 0.0124526 -0.660553 -0.849669 0 -0.527317 -0.258818 0 -0.965926 -0.159227 0.0610504 -0.985353 -0.410809 1.0178e-06 -0.911721 0.258791 0.0150527 -0.965816 0.26386 0.0178508 -0.964396 0.0341717 8.18758e-05 -0.999416 0.706573 0.038744 -0.706579 0.615893 5.76656e-07 -0.78783 0.475278 1.35684e-06 -0.879835 0.998931 2.36072e-07 -0.0462341 0.965622 0.0229605 -0.258936 0.965674 0.0228658 -0.258749 0.888457 -9.85389e-08 -0.45896 0.79882 -1.35226e-06 -0.60157 0.965927 3.55721e-06 0.258817 0.925388 0.0734971 0.371827 0.992556 -6.21869e-07 0.121791 0.554891 4.77981e-07 0.831923 0.657968 0.0198906 0.752783 0.706526 0.0404773 0.706529 0.775233 0.00888259 0.631612 0.851426 -4.60462e-07 0.524475 -0.0680206 0.000145129 0.997684 -0.0015625 0 0.999999 0.25882 0 0.965926 0.160748 0.0602728 0.985153 0.412321 1.87559e-06 0.911039 -0.884706 0.000229813 0.466149 -0.0534231 -1.67195e-05 0.998572 -0.167359 0.0581196 -0.984182 -0.258822 0 -0.965925 0.219505 0 -0.975611 0.258762 0.0214881 -0.965702 0.464537 0 -0.885554 0.965541 0.0282255 -0.258716 0.959624 0.0171344 -0.280764 0.88302 0 -0.469335 0.707105 0 -0.707108 0.789424 0.0799675 -0.608618 0.606578 0 -0.795024 0.965162 0.0397641 0.258614 0.993895 0 0.110335 0.998315 0 -0.0580239 0.707071 0.0100633 0.707071 0.857189 0 0.515002 0.931472 0 0.363813 0.417425 0 0.908712 0.564066 0 0.825729 0.746472 0.043751 0.663977 0.258819 8.09987e-05 0.965926 0.168309 0.0574403 0.984059 -0.272126 0.0284085 0.961842 -0.258762 0.0210215 0.965712 -0.465361 0 0.885121 -0.707107 -0.00166363 0.707104 -0.791279 0.0810029 0.606066 -0.607365 0 0.794423 -0.960115 0.0176763 0.279046 -0.965548 0.0279818 0.258718 -0.998371 0 0.0570575 -0.99378 0 -0.111361 -0.965146 0.0401615 -0.25861 -0.931094 0 -0.36478 -0.416938 0 -0.908935 -0.563184 0 -0.826332 -0.706712 0.0334149 -0.706712 -0.745655 0.00828749 -0.666281 -0.856637 0 -0.515919 -0.0664058 0 0.997793 -0.000923361 0 -1 -0.162411 0.000298383 -0.986723 -0.258639 0.0372294 -0.965256 0.230514 0 -0.973069 0.258787 0.0159173 -0.965803 0.474491 1.40525e-06 -0.880261 0.615202 5.99342e-07 -0.78837 0.706529 0.0403236 -0.706535 0.798288 -2.4567e-06 -0.602276 0.965661 0.0234533 -0.258745 0.965555 0.0232413 -0.259157 0.888068 -9.0565e-07 -0.459712 0.892686 6.95647e-07 0.450679 0.946723 0.0179472 0.321547 0.96519 0.0390489 0.258619 0.992667 -6.17208e-07 0.120878 0.998893 2.40183e-07 -0.0470392 0.85186 -4.33041e-07 0.52377 0.707028 0.0146758 0.707034 0.732967 0.0347662 0.679375 0.25882 0 0.965926 0.0045527 0.151637 0.988426 0.0364312 0.13344 0.990387 0.19632 0.0508209 0.979222 0.413117 1.81037e-06 0.910678 0.555606 4.55978e-07 0.831445 -0.296144 0.0360495 0.954463 -0.258791 0.0146677 0.965822 -0.476659 -1.26468e-07 0.879088 -0.617441 -7.71968e-07 0.786617 -0.706542 0.0399564 0.706542 -0.799047 0.000445297 0.601269 -0.965681 0.0225351 0.258753 -0.966804 0.024863 0.254306 -0.888638 -0.000182598 0.458608 -0.851371 -8.94063e-07 -0.524565 -0.926365 -6.4167e-07 -0.376628 -0.965161 0.0398028 -0.258613 -0.992278 4.26485e-07 -0.124033 -0.999016 -1.52487e-07 0.0443473 -0.411534 -6.95525e-07 -0.911394 -0.552784 -9.36525e-07 -0.833324 -0.706818 0.0285597 -0.706818 -0.728458 0.0144172 -0.684939 -0.834636 0.00207225 -0.550798 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965927 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 0.258817 -0.965927 0 0.258817 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258818 0 0.965926 -0.258818 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 -0.258821 0.965925 0 -0.258821 0.707107 0 -0.707107 0.707107 0 -0.707107 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965927 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 0.258817 -0.965927 0 0.258817 -0.707107 0 0.707106 -0.707107 0 0.707106 -0.258818 0 0.965926 -0.258818 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.707107 0 0.707106 0.707107 0 0.707106 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 -0.258821 0.965925 0 -0.258821 0.707107 0 -0.707107 0.707107 0 -0.707107 0.25882 0 -0.965926 0.25882 0 -0.965926 0.892615 0.00019181 -0.450819 0.780291 0.0525401 -0.623206 0.842851 -0.000534095 0.538146 0.965922 0.00298396 0.258817 0.925529 0.167838 0.33945 0.957276 0.0856029 0.276217 0.480657 -6.40662e-05 0.876909 0.547828 0.000147913 0.836591 0.696755 0.17049 0.696754 0.639831 0.306361 0.704812 0.75836 0.0566279 0.649372 0.360808 0.0485601 0.931375 0.249356 0.267929 0.93061 0.2356 0.235555 0.942871 -0.258293 0.0637347 0.963962 -0.343384 0.345268 0.873429 -0.160415 0.0837862 0.983487 -0.0564554 0 0.998405 0.122416 0 0.992479 -0.798991 0.0177263 0.601082 -0.728175 0.0968207 0.678518 -0.699656 0.144787 0.699655 -0.588254 0.000236834 0.808676 -0.479584 -5.09573e-05 0.877496 -0.998221 0.00286218 0.0595591 -0.983195 0.0147005 0.181968 -0.952435 0.096465 0.28907 -0.963757 0.0669716 0.258239 -0.901001 0.000382207 0.433818 -0.851083 -0.000152413 0.525031 -0.914888 0.000295653 -0.403709 -0.963521 0.03582 -0.265224 -0.965199 0.0387725 -0.258626 -0.996124 -7.23849e-06 -0.0879574 -0.999535 8.36083e-05 0.0304825 -0.78029 0.0525485 -0.623206 -0.793838 0.0138457 -0.607972 -0.804691 -0.000310087 -0.593694 -0.779166 -0.0134387 -0.626674 -0.740944 -0.0392249 -0.67042 -0.822534 0.0688044 -0.564539 -0.658129 -0.0641624 -0.750166 -0.752327 0.085961 -0.653157 -0.67464 0.0165468 -0.737961 -0.534907 -0.00920826 -0.844861 -0.559474 0.00040389 -0.828848 -0.455525 -0.000319792 -0.890223 -0.380547 0.017103 -0.924604 -0.319284 -0.00725349 -0.947631 -0.13339 0.0109711 -0.991003 -0.113813 0 -0.993502 0.136752 0 -0.990605 0.13449 -0.00155013 -0.990914 0.349545 0.0010034 -0.936919 0.452219 0.0493305 -0.890542 0.386505 -0.000812786 -0.922287 0.572721 0.000533748 -0.81975 0.682396 0.0595765 -0.72855 0.60863 -0.0389316 -0.792499 0.804239 0.0415503 -0.592851 0.741174 -0.0394004 -0.670156 0.797449 -0.000445584 -0.603387 0.8227 -0.0251235 -0.56792 0.793836 0.013844 -0.607974 0.986622 0.0127215 0.162528 0.999538 7.49823e-05 0.0303922 0.965926 -0.000539895 -0.258818 0.980033 0.053167 -0.191593 0.931846 0.0112839 -0.362679 -0.814096 0.00033509 -0.58073 -0.892614 0.000193026 0.450821 -0.78029 0.0525502 0.623206 0.898323 0.000985505 -0.439334 0.963573 0.0697633 -0.258187 0.960371 0.0796863 -0.267093 0.986626 0.0127195 -0.162506 0.914888 0.000294398 0.403709 0.963522 0.035819 0.265223 0.9652 0.0387719 0.258623 0.996123 -5.21973e-06 0.0879665 0.999535 8.57195e-05 -0.0305044 0.780291 0.0525418 0.623206 0.793836 0.0138453 0.607974 0.804689 -0.000311198 0.593696 0.779166 -0.0134388 0.626673 0.740949 -0.0392221 0.670414 0.82254 0.0688107 0.564529 0.658129 -0.0641624 0.750166 0.752324 0.0859541 0.653162 0.674641 0.0165444 0.73796 0.534904 -0.00921085 0.844862 0.55948 0.00040456 0.828844 0.455517 -0.000319185 0.890227 0.380546 0.017102 0.924604 0.319284 -0.00725425 0.947631 0.13339 0.0109703 0.991003 0.113814 0 0.993502 -0.136752 0 0.990605 -0.134489 -0.00155094 0.990914 -0.349543 0.00100262 0.93692 -0.452224 0.0493339 0.890539 -0.386506 -0.000812778 0.922286 -0.57272 0.000533737 0.819751 -0.682397 0.0595776 0.72855 -0.608628 -0.0389339 0.7925 -0.804237 0.0415469 0.592855 -0.741173 -0.0394013 0.670157 -0.797451 -0.000444478 0.603384 -0.822705 -0.0251247 0.567914 -0.793839 0.0138447 0.60797 -0.965925 -0.000911038 -0.25882 -0.921931 0.158566 -0.353412 -0.958464 0.0816871 -0.273266 -0.986914 0.0126457 -0.160754 -0.998221 0.00286221 -0.0595591 -0.999539 7.28539e-05 -0.0303697 -0.965925 -0.000541911 0.25882 -0.980033 0.0531669 0.191593 -0.93185 0.0112867 0.362668 -0.367859 0.0230819 -0.929595 -0.491242 -0.000970007 -0.871023 -0.70702 0.0156533 -0.70702 -0.639147 0.211524 -0.739425 -0.748423 0.0752283 -0.658941 -0.199764 0.299611 -0.932913 -0.255121 0.168448 -0.952123 -0.0604822 0 -0.998169 0.142071 0 -0.989856 0.249387 0.267493 -0.930727 0.389862 0.0075383 -0.920843 0.842823 -0.000692413 -0.538191 0.763552 0.0538623 -0.643497 0.690612 0.214734 -0.690612 0.643335 0.0980494 -0.75928 0.539128 -0.00315053 -0.842218 -0.258821 0 -0.965925 -0.258821 0 -0.965925 -0.707105 0 -0.707108 -0.707105 0 -0.707108 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258821 0 0.965925 -0.258821 0 0.965925 0.258821 0 0.965925 0.258821 0 0.965925 0.707107 0 0.707107 0.707107 0 0.707107 0.965925 0 0.258821 0.965925 0 0.258821 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707105 0 -0.707108 0.707105 0 -0.707108 0.258821 0 -0.965925 0.258821 0 -0.965925 -0.258817 0 -0.965926 -0.258817 0 -0.965926 -0.707108 0 -0.707105 -0.707108 0 -0.707105 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.707108 0 0.707105 -0.707108 0 0.707105 -0.25882 0 0.965926 -0.25882 0 0.965926 0.258822 0 0.965925 0.258822 0 0.965925 0.707107 0 0.707107 0.707107 0 0.707107 0.965925 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.707108 0 0.707105 -0.707108 0 0.707105 -0.258817 0 0.965926 -0.258817 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965925 0 0.258821 0.965925 0 0.258821 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707105 0 -0.707108 0.707105 0 -0.707108 0.258822 0 -0.965925 0.258822 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.965925 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258821 0 0.965925 -0.258821 0 0.965925 0.258821 0 0.965925 0.258821 0 0.965925 0.707107 0 0.707107 0.707107 0 0.707107 0.965925 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258821 0 -0.965925 0.258821 0 -0.965925 -0.694738 -0.508595 0.508597 -0.694743 -0.508592 0.508592 -0.694742 -0.186158 0.694751 -0.694743 -0.186158 0.69475 -0.694743 0.186158 0.69475 -0.694741 0.186159 0.694751 -0.694741 0.508594 0.508594 -0.694741 0.508594 0.508594 -0.694741 0.694752 0.186158 -0.694743 0.69475 0.186158 -0.694743 0.69475 -0.186157 -0.694741 0.694752 -0.186159 -0.694741 0.508594 -0.508594 -0.694741 0.508594 -0.508594 -0.694741 0.186158 -0.694752 -0.694742 0.186158 -0.694751 -0.694742 -0.186158 -0.694751 -0.694742 -0.186158 -0.694751 -0.694744 -0.508591 -0.508593 -0.694738 -0.508595 -0.508595 -0.694738 -0.694755 -0.186159 -0.69474 -0.694753 -0.186159 -0.69474 -0.694753 0.186159 -0.694738 -0.694754 0.18616 -0.694741 -0.694752 -0.186158 -0.694741 -0.508593 -0.508594 -0.694741 -0.508593 -0.508594 -0.694741 -0.186158 -0.694752 -0.694743 -0.186158 -0.69475 -0.694743 0.186158 -0.69475 -0.694742 0.186158 -0.694751 -0.694743 0.508591 -0.508593 -0.694738 0.508595 -0.508595 -0.694738 0.694755 -0.186158 -0.69474 0.694753 -0.186158 -0.69474 0.694753 0.186158 -0.694738 0.694754 0.186158 -0.69474 0.508594 0.508595 -0.694743 0.508592 0.508592 -0.694742 0.186158 0.694751 -0.694742 0.186158 0.694751 -0.694742 -0.186158 0.694751 -0.694741 -0.186158 0.694752 -0.694741 -0.508594 0.508594 -0.694742 -0.508593 0.508593 -0.694742 -0.694751 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186158 -0.694741 -0.508594 0.508593 -0.694738 -0.508595 0.508595 -0.694738 -0.186159 0.694755 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694738 0.186159 0.694755 -0.694738 0.508597 0.508595 -0.694743 0.508592 0.508592 -0.694742 0.694751 0.186158 -0.694742 0.694751 0.186158 -0.694742 0.694751 -0.186158 -0.694741 0.694752 -0.186158 -0.694741 0.508594 -0.508594 -0.694741 0.508594 -0.508594 -0.694741 0.186158 -0.694752 -0.694743 0.186158 -0.69475 -0.694743 -0.186158 -0.69475 -0.694741 -0.186159 -0.694751 -0.694741 -0.508593 -0.508594 -0.694738 -0.508595 -0.508595 -0.694738 -0.694755 -0.186159 -0.69474 -0.694753 -0.186159 -0.69474 -0.694753 0.186159 -0.694739 -0.694754 0.186159 -0.69474 -0.694753 -0.186158 -0.694742 -0.508593 -0.508593 -0.694738 -0.508595 -0.508596 -0.694738 -0.186158 -0.694755 -0.69474 -0.186158 -0.694753 -0.69474 0.186158 -0.694753 -0.694738 0.186159 -0.694755 -0.694738 0.508596 -0.508595 -0.694743 0.508592 -0.508592 -0.694742 0.694751 -0.186158 -0.694743 0.69475 -0.186158 -0.694743 0.69475 0.186158 -0.694742 0.694751 0.186158 -0.694743 0.508592 0.508592 -0.694741 0.508594 0.508594 -0.694741 0.186158 0.694752 -0.694743 0.186158 0.69475 -0.694743 -0.186158 0.69475 -0.694741 -0.186158 0.694752 -0.694741 -0.508594 0.508594 -0.694742 -0.508593 0.508593 -0.69474 -0.694752 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186158 -0.694743 -0.508592 0.508593 -0.694744 -0.508592 0.508592 -0.694745 -0.186157 0.694748 -0.69474 -0.186157 0.694753 -0.69474 0.186158 0.694753 -0.694744 0.186156 0.694749 -0.694744 0.508592 0.508592 -0.694743 0.508592 0.508592 -0.694741 0.694752 0.186158 -0.694741 0.694752 0.186158 -0.694741 0.694752 -0.186158 -0.694741 0.694752 -0.186158 -0.694743 0.508593 -0.508592 -0.694739 0.508595 -0.508595 -0.694738 0.186159 -0.694755 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694738 -0.186159 -0.694754 -0.694739 -0.508596 -0.508595 -0.694743 -0.508592 -0.508592 -0.694741 -0.694752 -0.186158 -0.69474 -0.694753 -0.186158 -0.69474 -0.694752 0.186158 -0.694741 -0.694752 0.186158 -0.69474 -0.694753 -0.186159 -0.694738 -0.508596 -0.508596 -0.694744 -0.508592 -0.508591 -0.694745 -0.186158 -0.694748 -0.69474 -0.186158 -0.694753 -0.69474 0.186159 -0.694753 -0.694745 0.186157 -0.694749 -0.694744 0.508592 -0.508592 -0.694738 0.508596 -0.508595 -0.694739 0.694753 -0.186159 -0.694741 0.694752 -0.186158 -0.694741 0.694752 0.186158 -0.694741 0.694752 0.186158 -0.694743 0.508593 0.508592 -0.694739 0.508595 0.508595 -0.694738 0.186158 0.694755 -0.69474 0.186158 0.694753 -0.69474 -0.186158 0.694753 -0.694738 -0.186159 0.694755 -0.694739 -0.508596 0.508595 -0.694743 -0.508592 0.508593 -0.694741 -0.694752 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186158 -0.694743 -0.508593 0.508591 -0.694738 -0.508595 0.508596 -0.694738 -0.186159 0.694755 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694738 0.186159 0.694755 -0.694738 0.508597 0.508595 -0.694743 0.508592 0.508592 -0.694742 0.694751 0.186158 -0.69474 0.694753 0.186158 -0.69474 0.694753 -0.186159 -0.694741 0.694752 -0.186158 -0.694741 0.508594 -0.508594 -0.694741 0.508594 -0.508594 -0.694741 0.186158 -0.694752 -0.694743 0.186158 -0.69475 -0.694743 -0.186158 -0.69475 -0.694741 -0.186159 -0.694751 -0.694741 -0.508593 -0.508594 -0.694741 -0.508593 -0.508594 -0.694741 -0.694752 -0.186158 -0.694742 -0.694751 -0.186158 -0.694742 -0.694751 0.186158 -0.694742 -0.694751 0.186158 -0.694742 -0.694751 -0.186157 -0.694743 -0.508592 -0.508592 -0.694739 -0.508595 -0.508596 -0.694738 -0.186158 -0.694755 -0.69474 -0.186158 -0.694753 -0.69474 0.186158 -0.694753 -0.694738 0.186159 -0.694755 -0.694738 0.508596 -0.508595 -0.694743 0.508592 -0.508592 -0.694742 0.694751 -0.186158 -0.694742 0.694751 -0.186158 -0.694742 0.694751 0.186158 -0.694742 0.694751 0.186158 -0.694743 0.508592 0.508592 -0.694741 0.508594 0.508594 -0.694741 0.186158 0.694752 -0.694743 0.186158 0.69475 -0.694743 -0.186158 0.69475 -0.694741 -0.186158 0.694752 -0.694741 -0.508594 0.508594 -0.694743 -0.508592 0.508592 -0.694742 -0.694751 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186158 -0.694741 -0.508594 0.508594 -0.694741 -0.508594 0.508594 -0.694741 -0.186158 0.694752 -0.694743 -0.186158 0.69475 -0.694743 0.186157 0.69475 -0.69474 0.186159 0.694752 -0.694738 0.508595 0.508595 -0.694738 0.508595 0.508595 -0.694738 0.694755 0.186159 -0.69474 0.694753 0.186159 -0.69474 0.694753 -0.186158 -0.694738 0.694755 -0.186159 -0.694738 0.508595 -0.508595 -0.694738 0.508595 -0.508595 -0.69474 0.186158 -0.694753 -0.694742 0.186158 -0.694751 -0.694742 -0.186158 -0.694751 -0.694741 -0.186158 -0.694752 -0.694741 -0.508594 -0.508594 -0.694741 -0.508594 -0.508594 -0.694741 -0.694752 -0.186158 -0.69474 -0.694753 -0.186158 -0.69474 -0.694753 0.186159 -0.694741 -0.694752 0.186158 -0.694738 -0.694755 -0.186159 -0.694738 -0.508595 -0.508596 -0.694743 -0.508592 -0.508592 -0.694742 -0.186158 -0.694751 -0.694743 -0.186158 -0.69475 -0.694743 0.186158 -0.69475 -0.694741 0.186158 -0.694752 -0.694741 0.508593 -0.508594 -0.694741 0.508593 -0.508594 -0.694741 0.694752 -0.186158 -0.69474 0.694753 -0.186158 -0.69474 0.694753 0.186158 -0.694742 0.694751 0.186158 -0.694742 0.508593 0.508593 -0.694741 0.508593 0.508594 -0.694741 0.186158 0.694752 -0.694742 0.186158 0.694751 -0.694742 -0.186158 0.694751 -0.694742 -0.186158 0.694751 -0.694743 -0.508592 0.508592 -0.69474 -0.508595 0.508594 -0.694738 -0.694755 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186158 -0.694744 -0.508592 0.508592 -0.694743 -0.508592 0.508592 -0.694741 -0.186158 0.694752 -0.694741 -0.186158 0.694752 -0.694741 0.186158 0.694752 -0.694741 0.186158 0.694752 -0.694743 0.508593 0.508592 -0.694744 0.508592 0.508592 -0.694745 0.694749 0.186157 -0.694747 0.694747 0.186157 -0.694747 0.694747 -0.186157 -0.694745 0.694748 -0.186158 -0.694744 0.508592 -0.508592 -0.694743 0.508592 -0.508592 -0.694741 0.186158 -0.694752 -0.69474 0.186158 -0.694753 -0.69474 -0.186158 -0.694752 -0.694741 -0.186158 -0.694752 -0.694743 -0.508593 -0.508592 -0.694744 -0.508592 -0.508592 -0.694745 -0.694748 -0.186157 -0.69474 -0.694753 -0.186157 -0.69474 -0.694753 0.186158 -0.694744 -0.694749 0.186156 -0.694745 -0.694748 -0.186157 -0.694744 -0.508592 -0.508592 -0.694743 -0.508593 -0.508592 -0.694741 -0.186158 -0.694752 -0.694741 -0.186158 -0.694752 -0.694741 0.186158 -0.694752 -0.69474 0.186159 -0.694753 -0.694738 0.508596 -0.508596 -0.694744 0.508591 -0.508592 -0.694745 0.694748 -0.186158 -0.69474 0.694753 -0.186158 -0.69474 0.694753 0.186159 -0.694745 0.694749 0.186157 -0.694744 0.508592 0.508592 -0.694738 0.508595 0.508596 -0.694739 0.186159 0.694753 -0.694741 0.186158 0.694752 -0.694741 -0.186158 0.694752 -0.694741 -0.186158 0.694752 -0.694743 -0.508593 0.508592 -0.694744 -0.508592 0.508592 -0.694745 -0.694748 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186159 -0.694741 -0.508594 0.508593 -0.694741 -0.508594 0.508593 -0.694741 -0.186158 0.694752 -0.69474 -0.186158 0.694753 -0.69474 0.186158 0.694753 -0.69474 0.186158 0.694753 -0.694738 0.508596 0.508595 -0.694738 0.508596 0.508595 -0.694738 0.694755 0.186159 -0.69474 0.694753 0.186159 -0.69474 0.694753 -0.186158 -0.694738 0.694755 -0.186159 -0.694738 0.508595 -0.508595 -0.694738 0.508595 -0.508595 -0.69474 0.186158 -0.694753 -0.69474 0.186158 -0.694753 -0.69474 -0.186158 -0.694753 -0.694741 -0.186158 -0.694752 -0.694741 -0.508594 -0.508594 -0.694741 -0.508594 -0.508594 -0.694741 -0.694752 -0.186158 -0.69474 -0.694753 -0.186158 -0.69474 -0.694753 0.186159 -0.694741 -0.694752 0.186158 -0.694738 -0.694755 -0.186159 -0.694738 -0.508595 -0.508596 -0.694742 -0.508593 -0.508593 -0.69474 -0.186158 -0.694752 -0.69474 -0.186158 -0.694753 -0.69474 0.186158 -0.694753 -0.69474 0.186159 -0.694753 -0.69474 0.508594 -0.508595 -0.694741 0.508593 -0.508594 -0.694741 0.694752 -0.186158 -0.69474 0.694753 -0.186158 -0.69474 0.694753 0.186158 -0.694741 0.694752 0.186158 -0.694741 0.508594 0.508594 -0.694741 0.508594 0.508594 -0.694741 0.186158 0.694752 -0.69474 0.186158 0.694753 -0.69474 -0.186159 0.694753 -0.694742 -0.186158 0.694751 -0.694743 -0.508592 0.508592 -0.694739 -0.508596 0.508595 -0.694738 -0.694755 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186158 -0.694743 -0.508592 0.508592 -0.694741 -0.508593 0.508594 -0.694741 -0.186158 0.694752 -0.69474 -0.186158 0.694753 -0.69474 0.186158 0.694753 -0.694741 0.186158 0.694752 -0.694741 0.508594 0.508593 -0.694743 0.508592 0.508592 -0.694742 0.694751 0.186158 -0.69474 0.694753 0.186158 -0.69474 0.694753 -0.186158 -0.69474 0.694753 -0.186158 -0.694738 0.508595 -0.508595 -0.694738 0.508595 -0.508595 -0.694738 0.186159 -0.694755 -0.69474 0.186159 -0.694753 -0.69474 -0.186159 -0.694753 -0.694738 -0.18616 -0.694754 -0.694738 -0.508595 -0.508596 -0.694738 -0.508595 -0.508596 -0.69474 -0.694753 -0.186158 -0.694742 -0.694751 -0.186158 -0.694742 -0.694751 0.186158 -0.694742 -0.694751 0.186158 -0.694741 -0.694752 -0.186158 -0.694741 -0.508594 -0.508594 -0.694739 -0.508595 -0.508596 -0.694738 -0.186159 -0.694755 -0.69474 -0.186159 -0.694753 -0.69474 0.186158 -0.694753 -0.694738 0.186159 -0.694755 -0.694738 0.508596 -0.508595 -0.694741 0.508593 -0.508594 -0.694741 0.694752 -0.186158 -0.694742 0.694751 -0.186158 -0.694742 0.694751 0.186158 -0.694742 0.694751 0.186158 -0.694743 0.508593 0.508591 -0.694738 0.508595 0.508596 -0.694738 0.186158 0.694755 -0.69474 0.186158 0.694753 -0.69474 -0.186158 0.694753 -0.694738 -0.186159 0.694755 -0.694738 -0.508596 0.508595 -0.694743 -0.508592 0.508592 -0.694742 -0.694751 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186158 -0.694743 -0.508592 0.508593 -0.694744 -0.508592 0.508592 -0.694745 -0.186157 0.694748 -0.69474 -0.186157 0.694753 -0.69474 0.186158 0.694753 -0.694744 0.186156 0.694749 -0.694744 0.508592 0.508592 -0.694743 0.508592 0.508592 -0.694741 0.694752 0.186158 -0.694741 0.694752 0.186158 -0.694741 0.694752 -0.186158 -0.694741 0.694752 -0.186158 -0.694743 0.508593 -0.508592 -0.694739 0.508595 -0.508595 -0.694738 0.186159 -0.694755 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694738 -0.186159 -0.694754 -0.694739 -0.508596 -0.508595 -0.694743 -0.508592 -0.508592 -0.694741 -0.694752 -0.186158 -0.69474 -0.694753 -0.186158 -0.69474 -0.694752 0.186158 -0.694741 -0.694752 0.186158 -0.69474 -0.694753 -0.186159 -0.694738 -0.508596 -0.508596 -0.694744 -0.508592 -0.508591 -0.694745 -0.186158 -0.694748 -0.69474 -0.186158 -0.694753 -0.69474 0.186159 -0.694753 -0.694745 0.186157 -0.694749 -0.694744 0.508592 -0.508592 -0.694738 0.508596 -0.508595 -0.694739 0.694753 -0.186159 -0.694741 0.694752 -0.186158 -0.694741 0.694752 0.186158 -0.694741 0.694752 0.186158 -0.694743 0.508592 0.508593 -0.694744 0.508592 0.508592 -0.694745 0.186158 0.694748 -0.69474 0.186158 0.694753 -0.69474 -0.186159 0.694753 -0.694745 -0.186157 0.694748 -0.694744 -0.508592 0.508592 -0.694743 -0.508592 0.508593 -0.694741 -0.694752 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186158 -0.694741 -0.508594 0.508594 -0.694741 -0.508594 0.508594 -0.694741 -0.186158 0.694752 -0.69474 -0.186158 0.694753 -0.69474 0.186158 0.694753 -0.694741 0.186158 0.694752 -0.694741 0.508594 0.508593 -0.694743 0.508592 0.508592 -0.694742 0.694751 0.186158 -0.694742 0.694751 0.186158 -0.694742 0.694751 -0.186158 -0.69474 0.694752 -0.186159 -0.694738 0.508595 -0.508595 -0.694738 0.508595 -0.508595 -0.694738 0.186159 -0.694755 -0.69474 0.186159 -0.694753 -0.69474 -0.186159 -0.694753 -0.694738 -0.18616 -0.694754 -0.694739 -0.508595 -0.508596 -0.694736 -0.508597 -0.508597 -0.694737 -0.694756 -0.186159 -0.69474 -0.694753 -0.186159 -0.69474 -0.694753 0.186159 -0.694739 -0.694754 0.186159 -0.69474 -0.694753 -0.186159 -0.69474 -0.508595 -0.508595 -0.694738 -0.508595 -0.508596 -0.694738 -0.186159 -0.694755 -0.69474 -0.186159 -0.694753 -0.69474 0.186158 -0.694753 -0.694738 0.186159 -0.694755 -0.694738 0.508596 -0.508595 -0.694741 0.508594 -0.508594 -0.694741 0.694752 -0.186158 -0.694743 0.69475 -0.186158 -0.694743 0.69475 0.186158 -0.694742 0.694751 0.186158 -0.694743 0.508593 0.508591 -0.694738 0.508595 0.508595 -0.694738 0.186158 0.694755 -0.69474 0.186158 0.694753 -0.69474 -0.186158 0.694753 -0.694738 -0.186159 0.694755 -0.694738 -0.508596 0.508595 -0.694742 -0.508593 0.508593 -0.69474 -0.694752 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186158 -0.694738 -0.508595 0.508596 -0.694743 -0.508592 0.508592 -0.694742 -0.186158 0.694751 -0.69474 -0.186158 0.694753 -0.69474 0.186159 0.694753 -0.694741 0.186158 0.694752 -0.694741 0.508594 0.508593 -0.694741 0.508594 0.508593 -0.694741 0.694752 0.186158 -0.694743 0.69475 0.186158 -0.694743 0.69475 -0.186157 -0.694741 0.694752 -0.186159 -0.694741 0.508594 -0.508594 -0.694741 0.508594 -0.508594 -0.694741 0.186158 -0.694752 -0.69474 0.186158 -0.694753 -0.69474 -0.186159 -0.694753 -0.694742 -0.186157 -0.694751 -0.694744 -0.508591 -0.508593 -0.694738 -0.508595 -0.508595 -0.694738 -0.694755 -0.186159 -0.69474 -0.694753 -0.186159 -0.69474 -0.694753 0.186159 -0.694738 -0.694754 0.18616 -0.694741 -0.694752 -0.186158 -0.694741 -0.508594 -0.508594 -0.69474 -0.508594 -0.508595 -0.69474 -0.186159 -0.694753 -0.69474 -0.186159 -0.694753 -0.69474 0.186158 -0.694753 -0.69474 0.186158 -0.694753 -0.694742 0.508592 -0.508593 -0.694738 0.508595 -0.508595 -0.694738 0.694755 -0.186158 -0.69474 0.694753 -0.186158 -0.69474 0.694753 0.186158 -0.694738 0.694755 0.186159 -0.694738 0.508595 0.508596 -0.694743 0.508592 0.508592 -0.694742 0.186158 0.694751 -0.69474 0.186158 0.694753 -0.69474 -0.186159 0.694753 -0.694741 -0.186158 0.694752 -0.694741 -0.508594 0.508594 -0.694741 -0.508594 0.508594 -0.694741 -0.694752 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186158 0 -0.965926 -0.258819 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258818 0 0.965926 0.258818 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258818 0 -0.965926 0.258818 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258818 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258818 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258818 0 0.965926 0.258818 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258818 0 -0.965926 0.258818 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707106 0 0.707107 0.707106 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 0.352147 0.935945 0.0073668 0.455287 0.890314 0.000804696 0.531252 0.847213 -0.00109541 0.732849 0.680391 0.00426686 0.779907 0.625881 -8.36655e-05 0.867979 0.496601 0.000203166 0.948587 0.316518 0.00421431 0.967793 0.25171 -0.000639195 0.995639 0.0932837 0.00132192 0.991968 -0.126485 0.00370475 0.98602 -0.166588 0 0.950717 -0.310061 0 0.797757 0.60298 0.00846601 0.839441 0.543385 0.00319768 0.883098 0.469178 -0.00110091 0.996752 -0.0805195 0.00264064 0.995519 0.0945206 0.00833995 0.988334 0.152073 0.000144997 0.962002 0.273042 -9.14115e-05 0.915086 0.403258 0.00509922 0.968481 -0.249034 0.0066296 0.963976 -0.265906 -0.00215474 0.901148 -0.433506 0.00393274 0.785828 -0.618432 0.0059526 0.770615 -0.637273 0 0.674448 -0.738322 0 0.646233 0.76314 0.00411487 0.770623 0.637278 0.00360259 0.773294 0.634037 -0.00268972 0.929828 0.367984 0.00753533 0.96397 0.265904 -0.00171428 0.994195 0.107579 0.00317807 0.993145 -0.116846 0.00728239 0.988342 -0.152074 -0.00191963 0.942966 -0.332884 0 0.839471 -0.543405 0.0159716 0.788636 -0.614653 0.0028378 0.880922 -0.473253 0 0.955713 0.294301 0.00416379 0.986018 0.166588 -0.00417948 0.967794 -0.251711 0.0201151 0.894324 -0.446968 0.00890914 0.941287 -0.337491 -0.000959671 0.991632 -0.129097 0.00117541 0.993928 0.110029 0 0.455299 -0.890339 0.0190691 0.349268 -0.936829 0.000518796 0.495808 -0.868432 -0.000703731 0.779914 -0.625886 0.0156185 0.690507 -0.723157 0.00263297 0.792651 -0.609671 -0.694744 -0.508592 0.508592 -0.694743 -0.508592 0.508592 -0.694741 -0.186158 0.694752 -0.694741 -0.186158 0.694752 -0.694741 0.186158 0.694752 -0.694741 0.186158 0.694752 -0.694743 0.508592 0.508593 -0.694739 0.508595 0.508595 -0.694738 0.694755 0.186159 -0.69474 0.694753 0.186159 -0.69474 0.694753 -0.186158 -0.694738 0.694754 -0.186159 -0.694739 0.508595 -0.508596 -0.694743 0.508592 -0.508592 -0.694741 0.186158 -0.694752 -0.69474 0.186158 -0.694753 -0.69474 -0.186158 -0.694752 -0.694741 -0.186158 -0.694752 -0.694743 -0.508593 -0.508592 -0.694744 -0.508592 -0.508592 -0.694745 -0.694748 -0.186157 -0.69474 -0.694753 -0.186157 -0.69474 -0.694753 0.186158 -0.694744 -0.694749 0.186156 -0.694745 -0.694748 -0.186157 -0.694744 -0.508592 -0.508592 -0.694743 -0.508593 -0.508592 -0.694741 -0.186158 -0.694752 -0.694741 -0.186158 -0.694752 -0.694741 0.186158 -0.694752 -0.69474 0.186159 -0.694753 -0.694738 0.508596 -0.508596 -0.694744 0.508591 -0.508592 -0.694745 0.694748 -0.186158 -0.69474 0.694753 -0.186158 -0.69474 0.694753 0.186159 -0.694745 0.694749 0.186157 -0.694744 0.508592 0.508592 -0.694738 0.508595 0.508596 -0.694739 0.186159 0.694753 -0.694741 0.186158 0.694752 -0.694741 -0.186158 0.694752 -0.694741 -0.186158 0.694752 -0.694743 -0.508593 0.508592 -0.694744 -0.508592 0.508592 -0.694745 -0.694748 0.186158 -0.69474 -0.694753 0.186158 -0.69474 -0.694753 -0.186159 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0.215409 0.414518 -0.88418 0 0.361461 -0.932387 0 0.321464 0.946922 0.117958 0.421519 0.899115 0 -0.91428 0.405082 0 -0.868801 -0.495161 -0.00189681 -0.873592 -0.486656 1.19449e-05 -0.93305 -0.359747 -0.000776174 -0.920567 -0.390583 -0.0105716 -0.930461 -0.366238 0.001089 -0.91667 -0.399645 0 -0.91428 -0.405082 0.0161404 -0.982814 -0.183893 -0.00163904 -0.969774 -0.244 0.00359199 -0.951046 -0.309027 0.0206423 -0.959095 -0.282332 0.000255946 -0.946285 -0.323333 0 -0.993017 -0.11797 -0.00086994 -0.993796 -0.111218 -0.0195737 -0.989016 -0.146503 0.00136639 -0.993878 -0.110474 -0.000176339 -0.988099 -0.153822 -0.0041886 -0.978142 -0.207897 0.00745716 -0.999972 0 0.00738229 -0.999973 -0.00045787 0.00137983 -0.999294 -0.0375559 9.89348e-07 -0.993017 0.11797 -2.28323e-08 -0.996641 0.0818942 0.0014983 -0.999335 0.0364217 0 -0.993016 0.11798 -0.0120042 -0.988929 0.147902 0.00180197 -0.992951 0.118511 -0.000309276 -0.987931 0.154897 -0.0024204 -0.983432 0.181262 0.00916963 -0.978109 0.20789 -0.00422158 -0.96772 0.251991 0.0101884 -0.946109 0.323688 -0.010142 -0.930168 0.366993 -0.00141378 -0.920963 0.389649 -4.86523e-05 -0.932642 0.360803 0.000674626 -0.951052 0.309029 0.00111608 -0.916729 0.399509 -0.0022666 -0.868799 0.49516 0 -0.873503 0.48682 -0.699067 -0.422966 0.576546 -0.699078 -0.422967 0.576532 -0.698673 -0.624732 0.348662 -0.698671 -0.624736 0.348661 -0.698671 -0.713429 0.0536387 -0.698668 -0.713432 0.0536365 -0.698667 -0.669846 -0.25134 -0.698672 -0.669843 -0.251335 -0.699073 -0.422965 -0.576539 -0.699074 -0.422964 -0.576539 -0.698671 -0.624735 -0.348662 -0.69867 -0.624735 -0.348663 -0.698671 -0.71343 -0.053636 -0.698668 -0.713433 -0.053639 -0.698669 -0.669845 0.251336 -0.698672 -0.669841 0.251337 0 -0.869082 0.494669 -0.00194657 -0.936261 0.351299 -0.00113895 -0.993017 -0.117962 -0.00401211 -0.999895 -0.0139434 -0.00216072 -0.997184 -0.0749688 0.000341962 -0.995584 0.0938782 -0.000760958 -0.948185 0.317717 -0.00243761 -0.873211 -0.487336 6.52194e-05 -0.920453 -0.390853 -2.40245e-05 -0.969415 -0.245427 0 -0.478141 -0.878283 -0.00280605 -0.62418 -0.781276 -0.00131491 -0.591517 -0.806292 -0.000132313 -0.711037 -0.703155 0.000382232 -0.802733 -0.596338 0 -0.478141 0.878283 -0.00164769 -0.565689 0.824617 -0.00231928 -0.591513 0.806292 -0.000398083 -0.65792 0.753088 -2.38106e-05 -0.969407 0.245457 5.1536e-05 -0.929182 0.369622 -0.00236519 -0.873212 0.487334 -0.00163785 -0.859474 0.511176 0.000226302 -0.776528 0.630082 -0.00125299 -0.994504 0.104691 -0.00216071 -0.997184 0.0749691 -0.000328709 -0.998807 -0.0488298 0.00109722 -0.936263 -0.351299 0 -0.943797 -0.330527 -0.701818 -0.655092 -0.279833 -0.70182 -0.65509 -0.279833 -0.70182 -0.711107 -0.0421441 -0.701819 -0.711108 -0.0421439 -0.70182 -0.683557 0.200497 -0.701817 -0.683559 0.200498 -0.701818 -0.575679 0.419578 -0.70182 -0.575677 0.419577 -0.701818 -0.655092 0.279833 -0.70182 -0.65509 0.279832 -0.70182 -0.711107 0.0421438 -0.70182 -0.575677 -0.419577 -0.701818 -0.575679 -0.419578 -0.70197 -0.682913 -0.202157 -0.691461 -0.693209 -0.203329 -0.707108 -0.702391 -0.081519 -0.701819 -0.711108 0.0421441 -2.06983e-07 -0.739511 0.673144 -2.10268e-07 -0.702716 -0.711471 -0.00222864 -0.735664 -0.677343 0.00802918 -0.767464 -0.641042 -0.000773897 -0.799767 -0.60031 0.00112542 -0.852314 -0.52303 -8.91248e-06 -0.854683 -0.51915 -8.88079e-06 -0.902353 -0.430997 -0.00383157 -0.89393 -0.448191 0.0062537 -0.940186 -0.340604 -1.576e-08 -0.933487 -0.358611 -1.37107e-08 -0.960809 -0.27721 -0.00199112 -0.969573 -0.244793 0.00770135 -0.983304 -0.181807 -6.03324e-07 -0.988879 -0.148721 -6.00299e-07 -0.995311 -0.0967249 -0.000244161 -0.998799 -0.0489959 0 -0.998854 -0.0478591 0 -0.998799 0.0489959 -5.95225e-07 -0.998799 0.0489932 -5.94269e-07 -0.988879 0.148721 -0.00357257 -0.991067 0.133317 0.00433837 -0.969566 0.244791 0.0016231 -0.735665 0.677344 -0.000940155 -0.799767 0.60031 0.0078986 -0.830907 0.556355 -0.00163186 -0.854682 0.51915 -8.87437e-06 -0.878694 0.477386 -8.89676e-06 -0.902353 0.430997 0.00649533 -0.915896 0.401364 -0.00305141 -0.9402 0.340609 0 -0.950795 0.309822 0 -0.973262 0.229699 0 0.741038 0.671463 0.00272125 0.789634 0.613573 -0.000775941 0.872089 0.489347 0.00234042 0.979535 0.201262 0.0160768 0.999756 -0.0151473 0 0.972654 0.232258 0 0.995939 -0.0900349 -0.00185773 0.999886 -0.0149545 0.00374757 0.959043 -0.283235 -0.00746111 0.999085 -0.042114 -0.00685825 0.998384 -0.0564071 -0.00639179 0.997693 -0.0675839 -0.00536586 0.995601 -0.0935418 -0.00465604 0.993506 -0.113682 0 0.670147 -0.742228 -0.00252975 0.984584 -0.174896 0.000845089 0.938823 -0.344399 -0.0006155 0.887824 -0.460184 0.00189288 0.789635 -0.613574 0.00106438 0.774893 -0.632092 0.000124151 0.693122 -0.72082 0.00180847 0.832421 0.554141 0.000123969 0.693117 0.720826 0 0.670176 0.742202 -0.00268332 0.789634 0.613573 0.000843627 0.938823 0.344399 -0.00231051 0.982424 0.186647 -0.00191966 0.984585 0.174894 -0.00090791 0.993517 0.113684 -0.000594365 0.995615 0.0935469 -0.000314766 0.997713 0.0675853 -0.000222854 0.998408 0.0564086 -0.000113926 0.999113 0.0421149 0 0.999888 0.0149538 0 0.789636 -0.613575 0.0044404 0.742971 -0.669309 -0.00077559 0.871446 -0.49049 0.00200505 0.972652 -0.232258 0.00582257 0.955845 -0.293814 0 0.994816 -0.101692 0.965862 -0.0114489 0.258804 0.965905 -0.00653878 -0.258815 0.977153 0 -0.212536 0.992749 0 0.120209 -0.928303 -0.000126205 0.371824 -0.965864 -0.0114483 0.258798 -0.707107 0 0.707107 -0.664788 -0.0108524 0.746953 -0.835357 5.3997e-05 0.549707 0.258801 -0.0123582 0.965852 0.1305 0 0.991448 -0.258819 0 0.965926 -0.130674 -0.0244989 0.991123 -0.382518 0 0.923948 0.928303 -0.000127356 0.371824 0.835344 5.2982e-05 0.549727 0.707081 -0.00846621 0.707081 0.663659 0 0.748035 0.382664 0 0.923888 -0.992749 0 0.120209 -0.977153 0 -0.212536 -0.965907 -0.00653787 -0.258809 -0.888856 0 -0.458186 -0.707106 0 -0.707108 -0.707106 0 -0.707108 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.25882 0 -0.965925 0.25882 0 -0.965925 0.707106 0 -0.707108 0.707106 0 -0.707108 0.888841 0 -0.458216 0.928303 -0.000127357 -0.371824 0.965862 -0.0114489 -0.258804 0.707107 0 -0.707107 0.664788 -0.0108524 -0.746953 0.835344 5.2982e-05 -0.549727 -0.258797 -0.0123579 -0.965853 -0.1305 0 -0.991448 0.258819 0 -0.965926 0.130673 -0.024499 -0.991123 0.382518 0 -0.923948 -0.707081 -0.00846621 -0.707081 -0.663659 0 -0.748035 -0.382656 0 -0.923891 -0.965864 -0.0114484 -0.258797 -0.928303 -0.000126205 -0.371824 -0.835357 5.3997e-05 -0.549707 -0.965906 -0.00653786 0.258809 -0.977153 0 0.212536 -0.992749 0 -0.120208 0.992749 0 -0.120208 0.977153 0 0.212536 0.965905 -0.00653877 0.258816 0.888841 0 0.458216 0.707107 0 0.707107 0.707107 0 0.707107 0.258819 0 0.965926 0.258819 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.965926 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.888856 0 0.458186 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.932209 -0.00751427 -0.361842 0.948482 0 0.316831 0.948713 2.82735e-05 0.316138 0.948705 3.60462e-05 0.316164 0.948705 3.60467e-05 0.316164 0.948622 0.000109355 0.316411 0.947813 -6.51252e-05 0.318828 0.947601 -0.000759534 0.319454 0.948397 -0.000280646 0.317084 0.9484 -0.000236941 0.317077 0.94803 0.000195699 0.318181 0.942204 0.0013299 0.335037 0.944748 0.000470136 0.327797 0.946994 -0.000209616 0.321252 0.931934 3.60169e-05 0.362629 0.937436 -0.00156731 0.348154 0.935219 -0.00405298 0.354047 0.943998 0.00300135 0.329937 0.944026 0.00302651 0.329858 0.871847 -0.00156549 0.489775 0.902376 -3.19204e-05 0.430949 0.899207 -0.00327275 0.437511 0.907781 5.82159e-05 0.419444 0.90683 0.00284296 0.421486 0.914242 -0.00523682 0.405135 0.921872 -0.0362489 0.385795 0.914118 0.0115039 0.405284 0.932352 -0.0611051 0.356352 0.918174 0.0105256 0.396038 0.919683 0.00554873 0.392622 0.922031 -0.000202649 0.387115 0.922475 0.00169107 0.386053 0.925038 0.0157615 0.379547 0.913453 9.51634e-05 0.406945 0.919143 0.00216454 0.393919 0.919407 0.00309945 0.393296 0.920226 0.00711245 0.391323 0.918128 0.00307791 0.396272 0.91332 0 0.407242 0.873524 -0.0035131 0.486769 0.898356 -0.0015579 0.439266 0.894819 0.000385071 0.446429 0.8805 -0.00583088 0.47401 0.883629 -0.0343857 0.466924 0.876525 -0.00773464 0.481295 0.869951 0.000834807 0.493138 0.87067 0.00304741 0.491859 0.869618 -0.00226049 0.493721 0.87286 0.000630253 0.48797 0.885979 -0.00252661 0.463719 0.888673 -0.0119265 0.458387 0.888495 0.00689274 0.458835 0.909254 -0.00985288 0.416125 0.908151 -0.00158017 0.418639 0.869099 -3.86385e-05 0.494638 0.864654 1.12715e-06 0.502368 0.859809 -0.000508172 0.510615 0.854895 -0.00382632 0.518787 0.85143 -0.00758219 0.524414 0.858778 0.00456626 0.512328 0.843309 -0.00266006 0.537423 0.837146 -0.0105856 0.546877 0.833112 -0.0204292 0.552727 0.830919 -0.0266873 0.555754 0.827397 -0.0381881 0.560318 0.817452 -0.0099041 0.575911 0.799124 0.00453432 0.601149 0.798043 0.00630915 0.602567 0.790254 -0.00274364 0.612773 0.785054 0.000586412 0.619428 0.782524 0.000106684 0.622621 0.706053 0.00307261 0.708152 0.723399 0.0768679 0.686138 0.706883 0.150101 0.691221 0.737015 0 0.675876 0.760028 0.00390926 0.649878 0.758211 0.0101214 0.651931 0.729835 0.0472047 0.681992 0.732321 0.0316069 0.680226 0.735629 0.0095822 0.677317 0.778481 -0.000380335 0.627668 0.757067 0.00870438 0.65328 0.756188 0.00654384 0.654322 0.730668 -0.0344005 0.681866 0.720689 0.0908796 0.687276 0.640868 0 0.767651 0.65179 0.00459469 0.758385 0.656192 0.00739018 0.754557 0.660769 0.00444841 0.750576 0.674579 -0.000800724 0.738202 0.920796 0.00171967 0.39004 0.923865 -0.00336459 0.382703 0.92972 4.88212e-05 0.368267 0.933321 -0.000199397 0.359044 0.934856 0.00794985 0.354939 0.955673 -0.029539 0.292944 0.946325 0.00168063 0.323214 0.963222 -0.00120951 0.268705 0.96926 -0.0274192 0.244505 0.971746 0.00159255 0.236025 0.977406 -0.00177007 0.211362 0.978801 -0.00797298 0.204658 0.983373 0.0126709 0.181155 0.985004 0.00127122 0.17253 0.991822 -0.00183339 0.127619 0.989713 0.0227071 0.141255 0.996123 -0.0171296 0.0862847 0.99511 0.00494362 0.0986463 0.997996 -0.00308683 0.0632003 0.998263 -0.0103038 0.0580059 0.999508 0.0161881 0.0268627 0.999797 0.000720713 0.020136 0.99966 -0.000960719 -0.0260461 0.999513 0.0242101 -0.019707 0.99797 -0.0156488 -0.0617272 0.978441 -0.00165785 -0.206519 0.97819 -0.0116171 -0.207386 0.984052 0.0173986 -0.177028 0.9842 0.000290663 -0.177062 0.990958 -0.000321811 -0.134173 0.991203 0.0147043 -0.131527 0.995487 -0.009864 -0.0943876 0.995996 0.00165492 -0.0893788 0.997114 -9.83253e-06 -0.0759253 0.998396 8.36539e-05 -0.0566092 0.919566 0.00544947 -0.392898 0.919775 0.0052286 -0.392412 0.920153 0.0048241 -0.39153 0.919364 0.00572028 -0.393365 0.919029 0.00640269 -0.394139 0.920757 0.00276691 -0.390126 0.926025 -0.00211381 -0.377457 0.929718 5.07312e-05 -0.368272 0.933365 -0.000203973 -0.358928 0.934844 0.0079901 -0.354968 0.951331 -0.0206505 -0.307479 0.950086 0.000546917 -0.311989 0.966177 -0.000880449 -0.25788 0.968076 -0.0415911 -0.247182 0.971797 0.00112953 -0.235817 0.925501 -0.02149 -0.378135 0.921825 0.00216487 -0.3876 0.905505 -0.00244396 -0.424328 0.905482 -0.00235404 -0.424378 0.888592 0.00108705 -0.458697 0.888704 -0.0157647 -0.458211 0.879139 0.0063467 -0.476524 0.868912 -0.00288409 -0.494958 0.922022 0 -0.387137 0.919883 0.00467889 -0.392164 0.930944 -0.0388816 -0.363087 0.870837 -0.000955387 -0.491572 0.872905 -0.0026448 -0.487884 0.874916 -0.00546817 -0.484245 0.877885 -0.0118451 -0.478725 0.880911 -0.0248185 -0.472631 0.880315 -0.0212967 -0.473911 0.889998 -0.00175193 -0.455962 0.89482 0.000385695 -0.446426 0.896484 -0.000524101 -0.443076 0.898446 0.000662127 -0.439084 0.89995 -0.000412553 -0.435993 0.902446 0.000515607 -0.430803 0.90378 -0.000745886 -0.427996 0.907863 0.00134597 -0.419265 0.908745 -0.000220193 -0.417352 0.914479 0.000287587 -0.404634 0.921406 -0.00948329 -0.388486 0.869087 0.00208008 -0.494655 0.868224 0.000384789 -0.496172 0.859791 -0.000512876 -0.510646 0.854871 -0.00384701 -0.518826 0.830888 -0.0267806 -0.555795 0.83308 -0.020514 -0.552772 0.837117 -0.0106393 -0.54692 0.858645 0.0181285 -0.512249 0.846917 -0.0148221 -0.531519 0.851407 -0.00761185 -0.52445 0.822166 -0.0545376 -0.56663 0.827861 -0.0183902 -0.560632 0.798082 0.00530597 -0.602526 0.797051 0.00287818 -0.603905 0.785052 -0.00239565 -0.619426 0.788159 0.00251297 -0.615466 0.783095 -0.000100839 -0.621902 0.761375 0.000840897 -0.648311 0.766187 0.0174701 -0.642381 0.712231 -0.0939048 -0.695636 0.689582 -0.000721783 -0.724208 0.699889 0.00527436 -0.714232 0.771286 0.000132488 -0.636488 0.760233 0.0034009 -0.649642 0.759747 0.00486067 -0.6502 0.758203 0.0101321 -0.65194 0.762451 0.00430091 -0.647032 0.77153 0 -0.636193 0.72993 0.0443621 -0.682081 0.718134 0.10343 -0.688176 0.735049 0.0040946 -0.678002 0.734259 0.00899071 -0.67881 0.737253 0.0200486 -0.675319 0.74 0.0349175 -0.6717 0.681224 0.000799526 -0.732075 0.67306 0.00293238 -0.739582 0.661209 0.0108184 -0.750124 0.658822 0.00860112 -0.75225 0.642916 0 -0.765936 0.948467 -4.88963e-05 -0.316875 0.941966 -0.0203644 -0.335091 0.942051 -0.0180805 -0.334983 0.947792 -0.000132373 -0.318889 0.948356 2.57556e-05 -0.317207 0.948382 -0.000427135 -0.317131 0.939936 0 -0.341352 0.937228 -0.0727587 -0.341043 0.933117 -0.110217 -0.342264 0.94101 0.00330221 -0.338362 0.942592 0.00816406 -0.333848 0.942537 0.00799682 -0.334007 0.942313 0.00759723 -0.334648 0.943116 0.0089668 -0.332343 0.943604 0.00977724 -0.330932 0 -0.603675 -0.797231 -0.00122002 -0.614684 -0.788773 0.000619847 -0.772396 -0.635141 0.00301741 -0.807406 -0.589989 1.02744e-07 -0.848779 -0.528748 0 -0.848779 0.528748 0.00298169 -0.807921 0.589283 -0.000966577 -0.748258 0.663407 0.00164508 -0.604372 0.7967 0 -0.585987 0.810321 0.411302 -0.86207 0.296084 0.480887 -0.829914 0.282827 0.508012 -0.844197 0.171044 0.499647 -0.850232 0.165707 0.506924 -0.852377 0.128383 0.504357 -0.694557 0.513044 0.416215 -0.724341 0.549632 0.526965 -0.76228 0.375815 0.497509 -0.81144 0.306674 0.487103 -0.718481 -0.496504 0.439088 -0.710626 -0.549738 0.52101 -0.773332 -0.361258 0.497508 -0.811441 -0.306675 0.444897 -0.843661 -0.300506 0.49239 -0.836907 -0.239038 0.508002 -0.844199 -0.171061 0.499633 -0.850238 -0.16572 0.506912 -0.852383 -0.128387 0.174573 -0.980785 0.0870952 0.174571 -0.980785 0.0870949 0.419354 -0.883386 0.209218 0.492323 -0.831391 0.257695 0.565474 -0.775015 0.282118 0.744012 -0.555575 0.371192 0.744006 -0.555582 0.371191 0.877619 -0.195116 0.437852 0.877623 -0.195101 0.43785 0.177711 -0.982052 0.0631919 0.176537 -0.982286 0.0628352 0.411181 -0.899755 0.146188 0.410091 -0.900311 0.145825 0.575543 -0.791748 0.204658 0.573601 -0.793311 0.204056 0.749036 -0.606671 0.266262 0.925524 -0.187336 0.329106 0.908989 -0.258759 0.326776 0.848302 -0.435193 0.301645 0.747562 -0.608679 0.265823 0.924107 -0.195059 -0.328602 0.924104 -0.195073 -0.3286 0.783451 -0.555513 -0.278586 0.783461 -0.555496 -0.278591 0.523516 -0.83143 -0.186157 0.523503 -0.83144 -0.186151 0.267987 -0.958698 -0.095293 0.184649 -0.980771 -0.0631911 0.0866432 -0.995763 -0.0308093 0.877622 -0.195116 -0.437846 0.877624 -0.195088 -0.437854 0.744011 -0.555575 -0.371193 0.744007 -0.555582 -0.371189 0.497151 -0.831457 -0.248032 0.497153 -0.831455 -0.248033 0.17457 -0.980785 -0.0870944 0.174571 -0.980785 -0.0870951 -0.765799 0.63667 -0.0905697 -0.206478 0.955811 0.209266 -0.206527 0.955869 0.208951 -0.206648 0.955921 0.208594 -0.196772 0.958073 -0.208272 -0.19671 0.957984 -0.20874 -0.196869 0.957838 -0.20926 -0.196986 0.957797 -0.209337 -0.217917 0.95162 -0.216637 -0.191742 0.965947 -0.173726 -0.275088 0.937042 -0.215124 -0.800913 0.594519 -0.0713123 -0.793868 0.605645 -0.0544811 -0.811797 0.578611 -0.0787151 -0.844096 0.530493 -0.0779697 -0.836585 0.545186 -0.0538387 -0.843062 0.534148 -0.0627117 -0.8141 0.578265 0.0533878 -0.705257 0.708054 0.0356505 -0.837443 0.543256 -0.0596776 -0.790572 0.610378 -0.0493444 -0.705272 0.70804 -0.0356512 -0.92231 0.386376 -0.00761317 -0.786798 0.616609 0.0272424 -0.841772 0.536303 0.0616297 -0.84181 0.536241 0.0616586 -0.844762 0.530907 0.0671929 -0.823726 0.561291 0.0801743 -0.80928 0.582588 0.0752102 -0.801298 0.594798 0.0643223 -0.792742 0.604808 0.075951 -0.743744 0.66066 0.10185 -0.756852 0.649933 0.0690098 -0.678983 0.725413 0.112956 -0.698044 0.712572 0.0705396 -0.639317 0.761071 0.109748 -0.640301 0.760359 0.108946 -0.61767 0.77995 0.100805 -0.453773 0.88175 0.128871 -0.317846 0.935283 0.155627 -0.550671 0.833287 -0.0489188 -0.44411 0.893127 -0.0713502 -0.427311 0.900854 -0.0765993 -0.451367 0.890911 -0.0504601 -0.553924 0.823122 0.125055 -0.579609 0.809912 0.0899799 -0.469581 0.871675 0.14027 -0.465071 0.885273 -0.000302479 -0.437385 0.896541 0.0700533 -0.42667 0.901202 0.0760772 -0.487657 0.870796 0.0624897 -0.550671 0.833287 0.0489188 -0.348412 0.936985 0.0258526 -0.420731 0.906548 -0.0340174 -0.15534 0.985945 0.0614917 -0.0995439 0.994242 0.0396625 -0.174747 0.978624 0.10844 -0.17306 0.969582 0.173094 -0.176071 0.968833 0.174245 -0.206406 0.955871 0.20906 -0.302875 0.941659 0.146783 -0.305846 0.950597 0.0531382 -0.290121 0.955097 0.0601604 -0.290235 0.955472 -0.0532685 -0.305722 0.950233 -0.0599265 -0.729616 0.681803 -0.0529599 -0.74421 0.661064 -0.0956338 -0.686421 0.72162 -0.0899532 -0.681077 0.727574 -0.0822796 -0.65165 0.751653 -0.101833 -0.639891 0.761728 -0.101539 -0.609687 0.78547 -0.10639 -0.599178 0.794733 -0.096876 -0.549546 0.827318 -0.116377 -0.512901 0.851998 -0.105032 -0.439675 0.887751 -0.136328 -0.399593 0.908025 -0.125762 -0.302082 0.939246 -0.162985 -0.17424 0.975927 -0.131178 -0.175502 0.982564 -0.0613687 -0.0689721 0.992198 -0.103856 -0.155548 0.987264 -0.0333905 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.995535 0 0.0943931 0.63285 -7.28821e-07 -0.774274 0.632733 0 -0.77437 0.639533 -8.42002e-05 -0.768764 0.651609 -0.0158437 -0.758389 0.663784 -0.0544974 -0.745937 0.664508 -0.051871 -0.745479 0.678434 -0.0142381 -0.734523 0.689479 7.09395e-05 -0.724306 0.695799 0.000284209 -0.718236 0.697013 0.000210681 -0.717058 0.725378 -0.00436999 -0.688337 0.730686 0.0232993 -0.682316 0.762684 -0.00403669 -0.646759 0.762893 -0.00424407 -0.646511 0.766828 -0.00865721 -0.641795 0.767489 -0.0104962 -0.640976 0.77829 0.00112155 -0.627904 0.793855 -0.00363239 -0.608096 0.800187 0.022907 -0.599313 0.829903 -0.0388631 -0.556552 0.824284 -0.0700497 -0.561826 0.834561 -0.0254359 -0.550328 0.837082 -0.0181821 -0.546775 0.835216 -0.0232807 -0.549429 0.847952 0.0116748 -0.529945 0.861241 -0.00510059 -0.508171 0.861192 -0.0050306 -0.508256 0.859432 -0.00228145 -0.511245 0.864025 -2.27118e-05 -0.503449 0.867158 4.73421e-05 -0.498033 0.870813 -0.00266396 -0.491607 0.872132 -0.000669157 -0.489271 0.887098 0.00209983 -0.461576 0.888419 0.007084 -0.45898 0.905757 -0.00477001 -0.423771 0.904073 -0.00795948 -0.427304 0.909156 -0.00206475 -0.416451 0.921725 -0.000272174 -0.387844 0.924182 0.00392675 -0.381932 0.912264 -0.000593898 -0.409602 0.911809 -0.000772489 -0.410615 0.949569 -0.00294323 -0.313545 0.949617 -0.00246917 -0.313404 0.93906 -0.0535664 -0.339553 0.940645 -0.018598 -0.338883 0.940835 -0.0135966 -0.338591 0.941174 -0.00429037 -0.337894 0.941327 0 -0.337496 0.941747 0.00420432 -0.336297 0.942524 0.0119946 -0.333923 0.942211 0.00897358 -0.334899 0.939963 0.00029448 -0.341277 0.940218 -0.000900123 -0.340572 0.940038 0.00170019 -0.341067 0.949993 -0.000304164 -0.312272 0.952628 -0.00501173 -0.304097 0.994941 0.00248065 -0.100435 0.995535 0 -0.0943931 0.994501 0.00632838 -0.104535 0.994123 0.0106714 -0.107732 0.995056 -0.00947223 -0.0988628 0.991261 0.00399411 -0.131857 0.991054 0.00685976 -0.133282 0.987838 -0.00300038 -0.155459 0.985515 0.00833529 -0.169384 0.979605 -0.0232017 -0.19959 0.978605 0.00582694 -0.205667 0.975388 0.000538025 -0.220495 0.96512 -0.00534591 -0.261755 0.972328 0.0346524 -0.231035 0.953272 -0.0147056 -0.301754 0.995537 0.00345484 0.0943048 0.995362 -3.06158e-06 0.0962016 0.994413 0.00914495 0.105165 0.995531 -0.0455574 0.0827226 0.993306 0.0235841 0.113079 0.993042 -0.0513723 0.10596 0.989574 0.0256214 0.141727 0.990145 -0.017542 0.138945 0.982743 0.0221405 0.183649 0.97952 -0.0617778 0.191635 0.977409 0.0277737 0.209524 0.9784 0.00224781 0.206707 0.96881 -0.00305337 0.247786 0.96895 0.0242908 0.246062 0.953272 -0.0147056 0.301754 0.952627 -0.00499442 0.304101 0.942261 0.0126029 0.334643 0.94046 -0.0209358 0.339258 0.940841 -0.0107291 0.338678 0.940384 -0.00339802 0.340099 0.941776 0.00726256 0.336163 0.942657 0.013311 0.333496 0.942525 0.0120018 0.333921 0.941746 0.00419741 0.336299 0.941327 0 0.337496 0.941174 -0.00429856 0.337895 0.940835 -0.0135966 0.338592 0.939806 -0.0358558 0.339823 0.949669 -0.00216421 0.313247 0.949536 -0.00292634 0.313645 0.949766 -0.00197337 0.312954 0.921725 -0.000270956 0.387844 0.93986 0.000290256 0.341561 0.940322 0.00164796 0.340282 0.912812 -0.014789 0.408112 0.913879 -0.0130569 0.405778 0.924553 0.00572454 0.381011 0.909203 -0.0020417 0.416349 0.905505 -0.00636386 0.424287 0.903747 -0.00334302 0.428055 0.88758 0.00763155 0.460591 0.888438 0.00235118 0.45899 0.870898 -0.000892238 0.491463 0.871918 -0.00345181 0.489639 0.867143 3.76522e-05 0.498059 0.864005 -3.23778e-05 0.503483 0.861884 -0.00108005 0.507104 0.861381 -0.00140427 0.507957 0.859424 -0.00274742 0.511257 0.847952 0.0116754 0.529945 0.835214 -0.023283 0.549432 0.695784 0.000284071 0.718251 0.837076 -0.0181976 0.546785 0.834529 -0.0255208 0.550372 0.829566 -0.0481469 0.556329 0.82269 -0.0228128 0.568033 0.793352 0.0357332 0.607713 0.800384 -0.00567287 0.599461 0.767524 0.00432337 0.641006 0.775284 -0.0328875 0.630756 0.7668 -0.00862618 0.641828 0.762888 -0.00423841 0.646517 0.762689 -0.00404109 0.646752 0.7251 0.0278815 0.688079 0.730874 -0.00528049 0.682492 0.697028 0.000208665 0.717044 0.689448 7.05072e-05 0.724335 0.678401 -0.0143333 0.734552 0.663813 -0.0536683 0.74597 0.664346 -0.056376 0.745296 0.651579 -0.0157522 0.758417 0.639498 -8.21151e-05 0.768793 0.633116 -2.38714e-06 0.774057 0.632733 0 0.77437 0.995533 -0.000860926 -0.0944149 0.998277 0.00084917 -0.0586733 0.999234 -0.011309 -0.0374599 0.9998 -0.000174755 -0.0200062 0.999298 0.000336535 0.0374623 0.999569 -0.0216058 0.0198826 0.998384 3.08203e-06 0.0568268 0 0.791593 -0.611049 0.0192921 0.793163 -0.608704 -0.00589063 0.761115 -0.64859 0.00154938 0.769166 -0.639047 -0.00651896 0.766117 -0.642668 -0.00357291 0.765033 -0.643982 -0.00700664 0.761526 -0.648097 0.00372349 0.754013 -0.656849 0.0069175 0.755064 -0.655615 -0.0283365 0.740483 -0.671478 -0.663863 0.541668 -0.515637 0 0.814851 -0.579671 -0.0133829 0.810699 -0.585311 -0.0581766 0.816284 -0.574713 -0.177093 0.838329 -0.515599 -0.00695462 0.773072 -0.63428 -0.00796616 0.764921 -0.644075 0 0.813414 0.581685 3.36411e-06 0.815243 0.579118 0 0.560322 -0.828275 5.50791e-07 0.822419 0.568882 0.000343482 0.946323 0.323222 0 0.997361 0.0725966 0 0.921383 -0.388656 -0.00134767 0.924268 -0.381742 -6.34673e-05 0.932286 -0.361722 0.000671041 0.94682 -0.321762 0.0071931 0.951028 -0.309021 -0.0042672 0.967828 -0.251578 0.00124732 0.9723 -0.233734 -3.76083e-07 0.977149 -0.212554 -3.18483e-06 0.983203 -0.182515 -0.00230788 0.984324 -0.176353 -0.000395237 0.987934 -0.154876 0.0027115 0.994101 -0.108427 -0.021047 0.988922 -0.146936 0.0392788 0.998577 -0.0360861 0 0.9974 -0.0720587 0.00102454 0.993802 0.111162 -0.019441 0.989018 0.146514 0.0372781 0.998563 0.0384904 0.000140115 0.997332 0.0730037 -0.000141639 0.997361 -0.0725966 2.67467e-06 0.933049 0.359749 -0.000638856 0.923947 0.38252 -0.00576615 0.930683 0.365781 0.0323698 0.965509 0.258349 -0.0203916 0.950855 0.308965 0.00707338 0.976671 0.214625 2.89762e-05 0.972301 0.233734 2.23918e-05 0.984011 0.17811 -0.00198224 0.983201 0.182514 -0.000116591 0.988097 0.153835 -0.0149955 0.721867 0.691869 0.0268826 0.775287 0.631037 0 0.796381 0.604796 8.37172e-06 0.796349 0.604837 -0.00218488 0.782099 0.623151 -0.00319795 0.776556 0.63004 -0.0118915 0.627705 0.77836 -0.0145205 0.63611 0.771462 -0.00166095 0.595808 0.803125 0.000293905 0.654296 0.756238 -5.05906e-07 0.65894 0.752195 -1.69348e-06 0.710456 0.703742 0 0.560322 0.828275 0.00348342 0.565046 0.825052 -0.00438992 0.455462 0.890245 0 0.476189 0.879343 0 0.921383 0.388656 -1.76912e-07 0.921382 0.388658 7.24354e-06 0.865282 0.501285 0.0312525 0.906357 0.421355 0.00738064 0.872518 0.488527 -0.00534798 0.930029 -0.367447 -2.2411e-07 0.921382 -0.388658 1.35542e-06 0.909847 -0.414944 0.00248925 0.865279 -0.501284 0.00760005 0.873134 -0.487422 0 0.796381 -0.604796 8.60484e-06 0.796343 -0.604845 5.47889e-07 0.822722 -0.568443 -0.00258316 0.781076 -0.624431 -0.00345537 0.777055 -0.629424 -0.00258322 0.780883 -0.624672 0.00570778 0.723764 -0.690023 -3.21124e-06 0.710659 -0.703537 -1.91882e-06 0.659134 -0.752026 0.000651013 0.649405 -0.760443 -0.00334435 0.596436 -0.802654 -0.0123745 0.625844 -0.77985 -0.0112101 0.62179 -0.783104 0.00355479 0.565905 -0.824463 -0.00440921 0.455462 -0.890245 0 0.476256 -0.879307 0 -0.39563 0.91841 0.000432321 -0.395167 0.918609 0.00125374 -0.394004 0.919108 0 -0.397367 0.91766 0 -0.397367 0.91766 0.000116712 -0.396857 0.91788 0.000808642 -0.394772 0.918779 0 -0.0958326 0.995398 0 -0.0958326 0.995398 0 -0.0958326 -0.995398 0 -0.0958326 -0.995398 0 -0.397367 -0.91766 0 -0.397367 -0.91766 0.000116707 -0.396857 -0.91788 0.00080865 -0.394772 -0.918779 0.00125376 -0.394004 -0.919108 0.000432321 -0.395167 -0.918609 0 -0.39563 -0.91841 0.830548 0 -0.556947 0.830549 0 -0.556946 0.830549 0 -0.556946 0.830548 -4.21031e-07 -0.556947 0.83055 1.75924e-06 -0.556943 0.830551 2.61545e-06 -0.556943 0.83055 0 -0.556944 0.830551 2.46189e-06 -0.556943 0.830552 -3.43784e-07 -0.556941 0.83055 -7.84459e-08 -0.556944 0.83055 3.70638e-07 -0.556944 0.830549 -4.28441e-06 -0.556946 0.830552 -1.46881e-06 -0.556941 0.830549 -7.19791e-07 -0.556945 0.830552 5.14685e-06 -0.556941 0.830548 1.75929e-06 -0.556947 0.83055 2.90764e-06 -0.556945 0.83055 -3.59972e-06 -0.556944 0.830549 -4.56933e-06 -0.556945 0.83055 2.67423e-06 -0.556944 0.830549 1.48369e-06 -0.556945 0.83055 3.55451e-06 -0.556945 0.830549 6.05122e-07 -0.556946 0.830549 -1.45538e-06 -0.556946 0.83055 4.31873e-06 -0.556944 0.83055 8.49634e-07 -0.556944 0.83055 2.20752e-06 -0.556944 0.830549 -1.80885e-06 -0.556945 0.830549 -1.31551e-06 -0.556945 0.830549 -1.56082e-08 -0.556945 0.83055 -9.85732e-07 -0.556944 0.83055 -2.10453e-07 -0.556944 0.830545 1.0451e-06 -0.556952 0.830556 -5.16363e-08 -0.556935 0.830549 -4.98262e-08 -0.556946 0.830549 -4.17174e-06 -0.556946 0.830549 -2.70843e-07 -0.556946 0.83055 1.97632e-07 -0.556944 0.830549 3.46698e-07 -0.556945 0.830552 -2.76234e-07 -0.556942 0.830553 -4.20138e-07 -0.55694 0.830551 1.7022e-07 -0.556942 0.830548 -4.99695e-07 -0.556948 0.830547 -3.145e-07 -0.556948 0.830552 2.83443e-07 -0.55694 0.830551 1.64779e-06 -0.556943 0.830549 -3.24434e-07 -0.556945 0.830552 1.1466e-06 -0.556941 0.83055 1.14788e-06 -0.556944 0.83055 5.85043e-07 -0.556944 0.830551 3.30538e-06 -0.556942 0.83055 -3.26064e-06 0.556944 0.830551 -2.32033e-06 0.556943 0.830551 -7.80799e-08 0.556943 0.830551 -2.69621e-07 0.556943 0.830551 -5.82836e-08 0.556942 0.830551 -4.73857e-08 0.556942 0.83055 5.05276e-07 0.556945 0.830551 0 0.556943 0.830549 1.04734e-06 0.556946 0.830548 1.04717e-06 0.556947 0.830546 1.23149e-06 0.556949 0.83055 -4.59329e-07 0.556944 0.83055 -1.84571e-06 0.556944 0.830551 -2.91838e-06 0.556943 0.830551 -8.09438e-07 0.556942 0.830551 -3.84478e-08 0.556942 0.830549 -3.29517e-06 0.556946 0.830551 3.20342e-06 0.556943 0.83055 -3.79726e-06 0.556944 0.830549 -3.85437e-06 0.556946 0.830556 5.38932e-06 0.556936 0.830549 -2.88969e-06 0.556946 0.830551 -1.28955e-06 0.556943 0.830553 4.49071e-06 0.556939 0.830549 1.33078e-06 0.556945 0.830552 8.65374e-06 0.556942 0.83055 7.91453e-08 0.556944 0.830551 -1.57499e-07 0.556943 0.830551 2.80881e-07 0.556942 0.83055 1.17485e-06 0.556944 0.83055 1.17459e-06 0.556944 0.83055 8.17777e-07 0.556944 0.830551 3.30538e-06 0.556942 0.830548 0 0.556947 0.830546 2.09416e-06 0.55695 0.83055 2.68856e-07 0.556945 0.830551 2.67635e-07 0.556942 0.83055 2.69963e-06 0.556943 0.83055 0 0.556945 0.830548 -6.12815e-06 0.556947 0.830551 5.27555e-07 0.556943 0.83055 4.57332e-06 0.556944 0.83055 2.87772e-06 0.556944 0.830551 -2.6753e-06 0.556943 0.830551 0 0.556943 0.830551 1.45211e-07 0.556943 0.83055 4.0867e-06 0.556944 0.83055 -2.08005e-07 0.556944 0.830544 1.24722e-06 0.556953 0.830552 4.97139e-07 0.556942 0.830549 4.95889e-07 0.556946 0.83055 0 0.556945 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -5.3788e-08 -0.562597 0.826731 0 -0.562597 0.826731 0 -0.531756 0.846897 -6.48977e-07 -0.531754 0.846899 0.672073 -0.269142 0.689841 0.542662 -9.85509e-05 0.839951 0.0895291 -0.560338 0.823411 0.739166 -0.0919642 0.667215 0.640779 -0.229703 0.732556 0.690359 -0.0464248 0.721976 0.654477 -0.0972404 0.749803 0.628549 0.0234371 0.777417 0.62669 0.0112692 0.779187 0.581369 -0.0257115 0.813234 0.587765 0.00739 0.808998 0.560869 -0.00732645 0.827872 0.550982 -2.22175e-05 0.834517 0.54893 -0.005816 0.835848 0.553356 0.0255541 0.832553 0.581748 -0.0119269 0.813281 0.601501 0.00183502 0.79887 0.61604 -0.0304575 0.787126 0.635573 -0.324563 0.700504 0.620369 -0.239525 0.74684 0.63093 -0.207193 0.747662 0.613752 -0.0767546 0.785759 0.614734 -0.0773872 0.784929 0.366147 -0.465349 0.805845 0.515113 -0.46047 0.722929 0.451413 -0.410122 0.792481 0.485681 -0.419697 0.766791 0.603118 -0.420898 0.677565 0.551198 -0.318367 0.771248 0.586419 -0.348467 0.731221 0.0896104 -0.538886 0.837599 0.239159 -0.497579 0.833797 0.209832 -0.522885 0.826173 0.391431 -0.478527 0.785999 0.625254 -0.0755914 0.776752 0.625727 -0.0826365 0.775652 0.641297 -0.0795641 0.763156 0.647333 -0.178614 0.740984 0.661576 -0.272372 0.698664 0.643141 -0.358631 0.676575 0.65765 -0.341538 0.671452 0.677629 -0.335413 0.654459 0.604736 -0.41479 0.679885 0.563804 -0.424622 0.708393 0.514109 -0.464589 0.721006 0.400904 -0.508244 0.76221 0.38393 -0.517732 0.76456 0.269244 -0.535875 0.800216 0.206157 -0.556928 0.804569 0.0623473 -0.544128 0.836683 0.0750843 -0.530253 0.844508 -2.71936e-07 -0.392889 0.919586 0 -0.392888 0.919587 0 -0.417265 0.908785 -1.30569e-06 -0.417259 0.908788 0.110383 -0.390487 0.913967 0.416479 -0.325571 0.848851 0.561609 -0.0462858 0.826107 0.58059 0.000390179 0.814196 0.561437 -0.0425788 0.826423 0.559243 -0.0246734 0.828637 0.557617 -0.0171707 0.829921 0.556384 -0.0125097 0.830831 0.553385 -0.00588832 0.832905 0.549471 0.000130085 0.835513 0.550322 0.00344232 0.834945 0.551064 0.0113462 0.834386 0.571674 0.0237479 0.820137 0.564694 0.118996 0.816676 0.534968 -0.0566047 0.842974 0.489127 0.00180871 0.872211 0.490263 -0.0240248 0.871243 0.466743 -0.264238 0.843996 0.432495 -0.118745 0.893783 0.425759 -0.111086 0.897992 0.426244 -0.0980411 0.89928 0.0547982 -0.416638 0.907419 0.15045 -0.44018 0.885216 0.197006 -0.482769 0.853301 0.118534 -0.383716 0.915812 0.267459 -0.401789 0.875803 0.170641 -0.367221 0.914347 0.342262 -0.388859 0.855363 0.236744 -0.329325 0.914055 0.281155 -0.335879 0.898965 0.532815 -0.0488145 0.844823 0.335285 -0.28907 0.896673 0.455472 -0.253551 0.85338 0.480654 -0.214969 0.850153 0.471443 -0.216094 0.855012 0.504388 -0.120008 0.855097 0.492718 -0.104158 0.863933 0.490853 -0.103574 0.865064 0.4911 -0.0969861 0.865687 0.484564 0.0271667 0.874334 0.571252 -0.038259 0.819882 0.56819 -0.0317302 0.822285 0.586792 0.00139744 0.809737 0.562488 -0.00602499 0.826784 0.564059 -0.000213084 0.825734 0.00424098 -0.697372 -0.716697 0.00580015 -0.701416 -0.712728 -2.79447e-06 -0.716304 -0.697789 0.00162608 -0.688165 -0.725552 0.00043584 -0.680005 -0.733208 0 -0.674207 -0.738543 0.0319476 -0.679657 -0.732834 0.0320781 -0.69702 -0.716334 0.591216 -0.0413483 -0.805452 0.614878 -0.00838367 -0.788578 0.603756 -0.0184515 -0.796956 0.600089 -0.0199268 -0.799685 0.754077 -0.127008 -0.644388 0.754411 -0.127141 -0.643972 0.752517 -0.126167 -0.646374 0.750152 -0.124565 -0.649427 0.732232 -0.111678 -0.671836 0.71833 -0.0960959 -0.689034 0.714024 -0.0905414 -0.694242 0.714527 -0.0912918 -0.693626 0.710339 -0.0923078 -0.69778 0.703983 -0.092433 -0.704176 0.68517 -0.0857941 -0.723313 0.699942 -0.0819113 -0.709487 0.643141 -0.0900254 -0.760437 0.681118 0.00327297 -0.732166 0.640346 -0.0475214 -0.766615 0.812319 -0.146202 -0.564591 0.80211 -0.0850068 -0.591095 0.797561 -0.014472 -0.603065 0.775087 -0.112673 -0.621728 0.847556 -0.243404 -0.471596 0.843922 -0.173396 -0.50767 0.844038 -0.129503 -0.520412 0.832476 -0.15297 -0.532526 0.819919 -0.160741 -0.549451 0.837085 -0.278772 -0.470717 0.860598 -0.229247 -0.454772 0.859584 -0.230759 -0.455923 0.859006 -0.239894 -0.452284 0.85697 -0.187939 -0.479876 0.76843 -0.35123 -0.534934 0.772882 -0.347274 -0.531089 0.779728 -0.342472 -0.524154 0.783056 -0.34096 -0.520162 0.782442 -0.341221 -0.520915 0.787328 -0.373018 -0.490889 0.781868 -0.396082 -0.481458 0.73234 -0.382385 -0.563436 0.697162 -0.43194 -0.572183 0.629393 -0.457228 -0.628336 0.500848 -0.574419 -0.647452 0.463949 -0.578998 -0.670458 0.317184 -0.644756 -0.695474 0.224574 -0.696104 -0.681914 0.200992 -0.694471 -0.690877 0.0338859 -0.702965 -0.710417 0.0667383 -0.714707 -0.696233 0.0537118 -0.673233 -0.737477 0.0427818 -0.69713 -0.715667 0.21023 -0.639238 -0.739715 0.238547 -0.614633 -0.751879 0.502668 -0.552553 -0.664839 0.405539 -0.61524 -0.676031 0.315494 -0.64129 -0.699436 0.677076 -0.46898 -0.56712 0.631482 -0.515855 -0.578899 0.518643 -0.563555 -0.642974 0.801149 -0.299744 -0.51799 0.808779 -0.294712 -0.508942 0.823062 -0.332419 -0.460508 0.774593 -0.365699 -0.516014 0.784449 -0.382521 -0.488178 0.714004 -0.450399 -0.536041 0.695359 -0.461137 -0.551207 0.769392 -0.333728 -0.544666 0.837993 -0.179175 -0.515426 0.758838 -0.222458 -0.612108 0.787126 -0.171889 -0.592357 0.742918 -0.13754 -0.655099 0.786106 -0.119996 -0.606332 0.758239 -0.127329 -0.639422 0.59944 -0.0201713 -0.800166 0.570535 -0.0301976 -0.820718 0.552682 -0.00108416 -0.833391 0.851271 -0.248311 -0.462254 0.845246 -0.288975 -0.449502 0.796269 -0.358492 -0.487277 0.784495 -0.382373 -0.48822 0.687848 -0.461099 -0.560583 0.672882 -0.481274 -0.561788 0.499278 -0.578902 -0.644666 0.491675 -0.587037 -0.643151 0.232059 -0.668444 -0.706634 0.227686 -0.672108 -0.704578 0.0280564 -0.693212 -0.720188 0.0327621 -0.687797 -0.725164 -1.01867e-06 -0.531756 -0.846897 0 -0.531753 -0.846899 0 -0.562598 -0.826731 2.28374e-07 -0.562597 -0.826731 0.628625 -0.279969 -0.725568 0.0293924 -0.531524 -0.846533 0.134035 -0.51122 -0.848934 0.614897 -0.373264 -0.694677 0.515964 -0.422777 -0.745011 0.523504 -0.423602 -0.739259 0.431912 -0.469164 -0.770284 0.393766 -0.465157 -0.792829 0.290189 -0.521212 -0.802576 0.211988 -0.500794 -0.839206 0.0290103 -0.579244 -0.814638 0.0455734 -0.562013 -0.825872 0.557535 -0.400681 -0.727055 0.623655 -0.258476 -0.737729 0.613654 -0.076207 -0.785889 0.581746 -0.0120593 -0.813281 0.598231 0.00376959 -0.801315 0.622504 -0.0413748 -0.781522 0.61299 -0.0776884 -0.786262 0.614149 -0.0774883 -0.785377 0.550983 -1.96656e-05 -0.834517 0.626691 0.0112744 -0.779186 0.587575 -0.0207805 -0.808903 0.58207 0.00542503 -0.813121 0.548928 -0.00581997 -0.835849 0.552453 0.0188233 -0.833332 0.557172 -0.000100344 -0.830397 0.654477 -0.097241 -0.749803 0.65404 -0.097832 -0.750107 0.673814 -0.187455 -0.714727 0.674183 -0.186964 -0.714508 0.706034 -0.279822 -0.65055 0.0906177 -0.547574 -0.831836 0.262742 -0.558645 -0.78669 0.207798 -0.542209 -0.814144 0.398414 -0.514814 -0.7591 0.384765 -0.513614 -0.766913 0.555574 -0.445688 -0.701926 0.521385 -0.433363 -0.735088 0.655175 -0.400539 -0.640558 0.61951 -0.352197 -0.701545 0.65765 -0.341539 -0.671452 0.628548 0.0234347 -0.777417 0.625727 -0.082635 -0.775653 0.655069 -0.0767733 -0.751659 0.63821 -0.133803 -0.758145 0.661575 -0.272373 -0.698664 0.628989 -0.281824 -0.724533 0.664959 -0.307479 -0.680651 0.598234 -0.343077 -0.724165 0.579807 -0.342773 -0.739142 0.139044 -0.987387 0.0757243 0.140227 -0.986807 0.0809265 0.143414 -0.98632 0.0812794 0.420358 -0.876469 0.234737 0.410028 -0.882039 0.232129 0.659875 -0.655185 0.367828 0.645539 -0.670597 0.365485 0.763027 -0.485138 0.42712 0.8068 -0.38895 0.444737 0.821071 -0.333346 0.463381 0.131565 -0.983946 0.120586 0.130342 -0.984109 0.120581 0.386951 -0.851667 0.353458 0.708236 -0.265608 0.654106 0.714068 -0.258474 0.650614 0.661848 -0.44007 0.606874 0.587151 -0.592084 0.551988 0.589285 -0.603078 0.537624 0.383131 -0.853237 0.353833 0.0898236 -0.987965 0.125926 0.101819 -0.982597 0.155357 0.109395 -0.980787 0.161525 0.189627 -0.943011 0.273446 0.310288 -0.841015 0.443187 0.316511 -0.831548 0.456452 0.474546 -0.557358 0.681292 0.474853 -0.556059 0.682138 0.559268 -0.197405 0.80514 0.559259 -0.19554 0.805601 0.737529 -0.452412 -0.501373 0.734869 -0.452234 -0.505422 0.663804 -0.52245 -0.535173 0.728538 -0.445239 -0.520572 0.729187 -0.446504 -0.518575 0.73089 -0.449475 -0.513588 0.0975446 -0.989768 -0.104135 0.0892447 -0.992 -0.0892801 0.594785 -0.520835 -0.612342 0.562115 -0.619916 -0.547477 0.464173 -0.743442 -0.481495 0.431339 -0.798636 -0.419675 0.291404 -0.906833 -0.304528 0.315644 -0.882196 -0.349426 0.252375 -0.935437 -0.247517 0.114025 -0.989856 -0.0847557 0.120505 -0.988277 -0.0937426 0.339527 -0.907262 -0.248188 0.357282 -0.892753 -0.274483 0.540252 -0.744142 -0.392912 0.530696 -0.758861 -0.37748 0.611728 -0.644414 -0.458825 0.137756 -0.987379 -0.0781424 0.150727 -0.985162 -0.0820867 0.140227 -0.986807 -0.0809269 0.411319 -0.882066 -0.229732 0.419009 -0.876499 -0.237026 0.647824 -0.670652 -0.361316 0.821072 -0.333343 -0.463382 0.806801 -0.38895 -0.444736 0.763023 -0.485146 -0.427117 0.657558 -0.655246 -0.371848 0.709761 -0.258484 -0.655305 0.130893 -0.984111 -0.119971 0.131007 -0.983947 -0.121185 0.38504 -0.853249 -0.351725 0.385027 -0.851677 -0.355528 0.589286 -0.603078 -0.537623 0.587153 -0.592084 -0.551987 0.661849 -0.44007 -0.606872 0.712561 -0.265623 -0.649385 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.997255 0.0740383 -0.000527934 -0.989167 0.146794 -1.8809e-06 -0.974796 0.223097 -4.27437e-05 -0.896888 0.442258 0 -0.898186 0.439615 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.00123229 -0.928294 -0.371844 0 -0.859939 -0.510396 0 -0.99721 -0.0746525 -0.000573073 -0.98792 -0.154961 -3.251e-05 -0.974455 -0.224582 9.54959e-07 -0.926999 -0.375065 0.00115514 -0.861793 -0.50726 0 -0.997298 0.0734608 -0.00094751 -0.975241 0.221143 1.03848e-05 -0.989055 0.147547 -3.60322e-05 -0.897336 0.441349 0 -0.898554 0.438864 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1.62483e-05 -0.929163 -0.369671 0.000992933 -0.863846 -0.503756 0 -0.897694 -0.440619 0 -0.997099 -0.0761155 0.000931883 -0.974719 -0.223434 -0.000991597 -0.997178 -0.0750648 -1.67148e-05 -0.974874 -0.222757 0 -0.997686 0.0679841 1.00197e-05 -0.975835 0.218507 0.000851178 -0.997044 0.076829 -0.00163354 -0.957306 0.289073 -0.00074543 -0.978266 0.207351 0 -0.824371 0.56605 -0.000108587 -0.89917 0.437599 -0.00144607 -0.836689 0.547676 -8.25811e-05 -0.904594 0.426275 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.896452 -0.443142 0 -0.997219 -0.0745327 0.00114891 -0.97644 -0.215785 6.52465e-05 -0.988193 -0.153216 -1.78546e-05 -0.930985 -0.365057 0.0012371 -0.866864 -0.498543 0 0.398697 0.917083 2.11739e-06 0.399009 0.916947 4.71466e-06 0.136388 0.990656 0 0.137135 0.990552 0 0 1 0 0 1 0 -0.131639 0.991298 6.74062e-06 -0.130526 0.991445 -2.05938e-06 -0.382681 0.923881 0 -0.383001 0.923748 0 -0.499998 0.866027 0 -0.499998 0.866027 0 -0.612231 0.790679 -0.00135309 -0.77277 0.634685 0.000599573 -0.636077 0.771625 -0.000331953 -0.866026 0.499999 -0.000460263 -0.85532 0.5181 0.000147806 -0.929963 0.367653 -0.000200141 -0.986285 0.16505 0 -0.99133 0.131393 0 -0.860192 -0.50997 -0.00110385 -0.928138 -0.372235 -0.000879782 -0.922186 -0.386746 -4.96709e-05 -0.973984 -0.226619 -0.00087966 -0.922184 -0.38675 -0.000879614 -0.922178 -0.386766 3.87318e-05 -0.997091 -0.0762169 0 -0.997816 -0.066062 -2.88609e-05 -0.99761 -0.0691012 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0.131454 -0.991322 0.00220219 0.0337737 -0.999427 0.000740417 0.120772 -0.99268 -0.00130006 0.383076 -0.923716 0.00126234 0.301263 -0.95354 0 0.459699 -0.888075 0 0.499991 -0.86603 -5.90673e-07 0.499999 -0.866026 0 0.500008 -0.866021 0 0.992378 -0.123229 0.000578244 0.985857 -0.167588 -0.000295589 0.933622 -0.35826 7.83863e-05 0.917175 -0.398486 4.97452e-05 0.83526 -0.549856 -0.000210939 0.846657 -0.532139 0 0.66682 -0.745219 0.00139065 0.629636 -0.776889 0.000206187 0.756095 -0.654462 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.994843 0.101424 0 0.738419 0.674342 0.00132786 0.861578 0.507624 -0.0013848 0.738926 0.673785 -3.46103e-05 0.865414 0.501057 3.59462e-05 0.95174 0.306906 0.00138145 0.993289 0.11565 -0.00289129 0.914154 0.405357 -0.00141813 0.952631 0.304125 -9.90757e-05 0.884563 -0.466421 0 0.999252 -0.0386644 8.89229e-05 0.953673 -0.300844 -0.00102031 0.994967 -0.100202 0.000986488 0.963583 -0.267409 0.000203361 0.991498 -0.130122 0.00133161 0.755771 -0.654835 -0.00181219 0.870251 -0.492606 0 0.73974 -0.672893 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.000591482 0.958886 0.283792 -0.000229321 0.982628 0.185587 0 0.99796 0.0638467 -3.02135e-06 0.986285 0.165049 3.93262e-06 0.866025 0.500001 -0.000399644 0.899612 0.436691 0 0.636084 0.77162 -0.000115116 0.617682 0.786428 4.84643e-05 0.785048 0.619435 0 0.499999 0.866026 0 0.499999 0.866026 0 0.38375 0.923437 -4.35803e-06 0.382703 0.923871 1.52918e-05 0.130525 0.991445 0 0.134319 0.990938 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0.0668853 -0.997761 -0.000174412 0.130525 -0.991445 6.10841e-06 0.197503 -0.980302 3.3988e-07 0.32276 -0.946481 -0.000174283 0.382683 -0.92388 0 0.442344 -0.896846 0 0.499999 -0.866026 0 0.499999 -0.866026 0 0.612494 -0.790475 -0.000169358 0.636079 -0.771624 0.000103205 0.783542 -0.621339 -0.000368325 0.866027 -0.499998 -0.000402728 0.862403 -0.506223 0.000135213 0.929856 -0.367925 -0.000196295 0.986286 -0.165048 0 0.99168 -0.128724 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.99135 0.131242 -0.00105821 0.950488 0.310759 0.00017394 0.986285 0.165049 -0.000123299 0.866027 0.499998 -0.000552649 0.892459 0.451129 0 0.636079 0.771624 -0.000223411 0.612555 0.790428 0.000119633 0.783417 0.621497 0 0.499999 0.866026 0 0.499999 0.866026 0 0.382455 0.923974 1.5253e-06 0.382693 0.923876 3.28649e-06 0.130525 0.991445 0 0.131074 0.991373 0 0 1 0 0 1 4.48722e-05 -0.941744 0.336329 -6.7199e-06 -0.995151 0.0983603 0 -0.995246 0.0973974 -0.000150934 -0.736101 0.676871 0.000538649 -0.819752 0.572718 0.000325932 -0.803513 0.595287 -0.000186719 -0.893638 0.448789 0.000765527 -0.96213 0.272589 0 -0.116509 0.99319 0.000146315 -0.63498 0.772529 -0.000767796 -0.47755 0.878604 0.00101163 -0.604879 0.796317 -0.000640448 -0.370378 0.928881 0.000189819 -0.465273 0.885167 -0.000180671 -0.23743 0.971404 0.000565985 -0.309569 0.950877 -0.000466253 -0.0619665 0.998078 0 -0.116509 0.99319 0 0 1 0 0 1 -2.17888e-08 -0.116509 -0.99319 0 -0.116507 -0.99319 0.00175184 -0.318728 -0.947845 -3.37113e-05 -0.203109 -0.979156 6.09448e-05 -0.425295 -0.905055 -9.3455e-05 -0.483838 -0.875158 0.000432695 -0.587502 -0.809223 0.00160993 -0.889234 -0.457449 -1.84065e-05 -0.781543 -0.623851 1.56871e-05 -0.635669 -0.771961 -0.00159185 -0.765539 -0.643387 0.000179653 -0.885519 -0.464603 -7.78215e-05 -0.957467 -0.288543 0.00017819 -0.969368 -0.245615 -0.000132361 -0.995244 -0.0974158 0 -0.997463 -0.0711832 0 0 -1 0 0 -1 0 0.131677 -0.991293 6.92932e-06 0.130525 -0.991445 -2.05702e-06 0.382683 -0.92388 0 0.383005 -0.923746 0 0.5 -0.866025 0 0.5 -0.866025 0 0.612327 -0.790604 -0.00135103 0.774649 -0.63239 0.00062401 0.636078 -0.771624 -0.000336853 0.866025 -0.500001 -0.000446848 0.856522 -0.51611 0.000146598 0.929913 -0.36778 -0.00019825 0.986286 -0.165048 0 0.991368 -0.131112 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.991719 0.128425 -0.000197744 0.986286 0.165048 3.40066e-05 0.951449 0.307805 -0.000138416 0.866025 0.500001 -0.00054706 0.893131 0.449796 0.000102853 0.782973 0.622055 -0.000170118 0.636078 0.771624 0 0.612354 0.790583 0 0.499999 0.866026 0 0.499999 0.866026 0 0.442022 0.897004 -0.000174472 0.382683 0.92388 1.82477e-06 0.321782 0.946814 4.61249e-06 0.196549 0.980494 -0.00017447 0.130525 0.991445 0 0.0664595 0.997789 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0.382683 -0.92388 0 0.134517 -0.990911 1.61119e-05 0.130525 -0.991445 -7.65213e-08 0.325008 -0.945711 -0.000258555 0.442806 -0.896617 0 0.5 -0.866025 0 0.5 -0.866025 -0.00114629 0.808975 -0.587842 -0.000168058 0.648494 -0.76122 0 0.533621 -0.845724 0 0.986286 -0.165046 0.000872194 0.636073 -0.771629 -0.000265439 0.866025 -0.500001 0.000104962 0.931873 -0.362785 -0.000209751 0.992504 -0.122216 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.708036 0.706176 -9.75764e-05 0.887814 0.460203 0.000858453 0.800717 0.599043 -0.00049176 0.870022 0.493012 0.000218785 0.740075 0.672524 0 0.995894 0.0905319 0.000944096 0.964646 0.263548 -0.00100658 0.994964 0.100233 9.31696e-05 0.953598 0.301082 0 0.994845 -0.101411 2.81461e-05 0.951321 -0.308202 0.001376 0.993257 -0.115926 -0.00288735 0.91427 -0.405096 -0.00141686 0.952677 -0.303982 0 0.738148 -0.674639 0.00131648 0.860864 -0.508833 -0.00136009 0.739081 -0.673615 -2.71325e-05 0.86539 -0.501099 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.0125133 0.999922 0.000262005 0.130837 0.991404 0.00157486 0.0660433 0.997816 -4.23579e-05 0.185752 0.982597 8.71996e-05 0.382422 0.923988 0 0.386228 0.922403 -0.00170942 0.886591 0.462551 0.000315553 0.782858 0.622201 -0.000387354 0.627842 0.778341 0 0.61143 0.791298 0 0.991096 0.133149 0.000214025 0.993237 0.116106 -7.87311e-05 0.94539 0.325941 -0.000310307 0.935972 0.352076 0.000833552 0.824956 0.565197 0 0.5 0.866026 -1.128e-06 0.499992 0.86603 0 0.500008 0.866021 0 -0.500006 -0.866022 0 -0.500006 -0.866022 0 -0.382433 -0.923983 1.60167e-06 -0.382681 -0.923881 3.09141e-06 -0.130526 -0.991445 0 -0.131039 -0.991377 0 0 -1 0 0 -1 0 0.137704 -0.990473 8.33716e-06 0.136388 -0.990656 -1.21155e-06 0.399019 -0.916943 0 0.399198 -0.916865 5.32391e-05 -0.988264 0.152757 0.0011557 -0.976328 0.216294 0 -0.997197 0.0748269 0 -0.896655 0.44273 0.00130065 -0.865577 0.500774 -1.31915e-05 -0.929832 0.367983 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.997622 -0.0689285 -0.00166124 -0.824751 -0.565494 0.000911319 -0.931122 -0.364706 0 -0.863973 -0.503539 -0.00143719 -0.836687 -0.54768 -7.11092e-05 -0.904898 -0.425628 1.44612e-05 -0.975843 -0.218474 0.000848364 -0.996978 -0.0776859 -0.00163095 -0.957188 -0.289463 -0.000749405 -0.977998 -0.208614 0 -0.997099 0.0761155 0.000931828 -0.974721 0.223425 -0.000998848 -0.997221 0.0744975 -2.18205e-05 -0.974997 0.222219 0 -0.898045 0.439903 0.00104799 -0.862432 0.506172 2.24181e-05 -0.928028 0.372512 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.897006 -0.442019 -4.48062e-05 -0.898602 -0.438764 1.78971e-05 -0.989051 -0.147572 -0.000958882 -0.974983 -0.222279 0 -0.997267 -0.0738808 9.55556e-06 -0.927003 0.375053 0 -0.988195 0.153203 -0.00119281 -0.99723 0.0743737 -3.96025e-05 -0.974848 0.22287 0.00117758 -0.86183 0.507196 -0.00125224 -0.92896 0.370178 0 -0.860315 0.509763 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.896822 -0.442392 -4.3939e-05 -0.898229 -0.439527 3.51493e-05 -0.988919 -0.148453 -0.0010956 -0.974383 -0.224892 0 -0.997151 -0.0754293 -0.000248358 -0.958343 0.285621 -1.25324e-07 -0.997845 0.0656128 0 -0.997846 0.0655955 0.000281366 -0.991433 0.130616 -6.23147e-05 -0.997126 0.0757627 4.8722e-05 -0.97424 0.225513 0.000600205 -0.877702 0.479207 -0.00111531 -0.928539 0.371233 0 -0.860403 0.509614 0 -0.991318 -0.131486 -0.00108568 -0.949943 -0.31242 0.000190676 -0.986285 -0.16505 -0.00013478 -0.866024 -0.500003 -0.000556481 -0.891822 -0.452387 0 -0.636077 -0.771625 -0.000227983 -0.612449 -0.79051 0.00012321 -0.783349 -0.621582 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.717145 0.696924 0.000618233 -0.718803 0.695214 0.00037118 -0.718653 0.695368 0 -0.674207 0.738543 0.000436108 -0.680008 0.733204 0.00147056 -0.687105 0.726556 0.00120186 -0.688164 0.725554 0 -0.698229 0.715874 -1.29672e-06 -0.417338 -0.908751 0.00544574 -0.392955 -0.919541 -1.67744e-07 -0.405186 -0.914234 0.972656 0.0010394 -0.232247 0.984222 -0.000944787 -0.176934 0.986536 -0.00164382 -0.163535 0.988716 -0.0025436 -0.149778 0.999245 -0.0117002 -0.0370507 0.918647 0 -0.39508 0.886355 -0.0936176 -0.453443 0.92638 -0.0301305 -0.375383 0.94923 -0.0084066 -0.31447 0.961105 -0.00240082 -0.276174 0.965145 -0.00104526 -0.261713 0.960728 0 -0.277491 0.961656 -0.00098723 -0.274258 0.694631 -0.0410831 0.718192 0.639587 0 0.768718 0.764115 -0.00324266 0.645072 0.677166 -0.0487072 0.734216 0.684644 -0.0452813 0.72747 0.999996 0 0.00286935 0.969163 0 0.246419 0.945245 -0.0170925 0.325915 0.899578 0.00311332 0.436749 0.781944 -0.00516192 0.623327 0.641091 0 0.767465 0.657736 0.00157791 0.753247 0.763895 0.0235889 0.64491 0.783414 -0.0093807 0.62143 0.946677 0.010371 0.322018 0.945328 0.00526462 0.326077 0.988471 -4.25641e-06 0.151412 0.999326 0.000129251 -0.0367017 0.999585 0.0213181 -0.0193561 0.98118 0.00108645 -0.193092 0.978143 0.000133749 -0.207934 0.956601 -0.0010572 -0.2914 0.916211 0.0742082 -0.393764 0.897673 0.0257881 -0.439907 0.843189 0 -0.537617 0.958001 -0.000720529 0.286766 0.961486 -0.000805526 0.274854 0.863542 0 0.504277 0.910519 -0.0386546 0.411657 0.922542 -0.0206746 0.385342 0.946258 -0.0039833 0.323389 0.98903 -0.0423214 0.14152 0.988634 -0.0430528 0.144047 0.988672 -0.0429759 0.143807 0.989774 -0.0406476 0.13673 0.960728 0 0.277491 0.9617 -0.000224797 0.274104 0.96752 0.000289422 0.252793 0.987695 -0.00257523 0.156374 0.998233 0.0377049 -0.0459362 0.752085 0 -0.659066 0.66056 -0.0449708 -0.749426 0.67282 -0.0396888 -0.738741 0.681763 -0.0360336 -0.730685 0.693932 -0.0315126 -0.71935 0.781955 0 -0.623335 0.899583 0 -0.43675 0.899583 0 -0.43675 0.969163 0 -0.24642 0.969163 0 -0.24642 0.999996 0 -0.00286935 0.641136 0 -0.767427 0.843189 0 0.537617 0.91811 0.0371502 0.394581 0.89751 0.101257 0.429211 0.95659 -0.00105772 0.291437 0.978149 0.000134168 0.207904 0.98118 0.00108735 0.193091 0.99914 0.0193321 0.0366933 0.999813 0.000117017 0.0193605 0.969163 -7.20964e-05 -0.24642 0.943863 0.0559071 -0.325573 0.899536 -0.0101981 -0.436728 0.763949 0.0203173 -0.644956 0.766084 0.0240795 -0.642289 0.657692 0.00156944 -0.753285 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.779457 0.247197 0.575621 -0.629061 0.326394 0.705513 -0.677473 0.230007 0.698661 0.0300224 0.999425 -0.0157458 -0.590256 0.136493 0.795593 -0.562171 0.139721 0.815133 0.0308537 0.999398 -0.0158553 0.0496698 0.745297 0.66488 0.0470879 0.735395 0.676001 0.0310493 0.764825 0.643489 0.0312187 0.759557 0.649692 -0.0365088 0.803725 0.59388 -0.0116609 0.85139 0.524404 -0.145434 0.837221 0.527172 -0.0447434 0.931332 0.361412 -0.119432 0.946879 0.29859 -0.0748371 0.955308 0.285982 -8.81724e-05 0.858796 0.512318 -0.0192288 0.902482 0.430299 -0.00183672 0.916057 0.401044 -0.0138516 0.877311 0.479723 -0.0384183 0.846398 0.531163 -0.000137135 0.835622 0.549306 0.00513049 0.929935 0.367688 0.00761599 0.96422 0.264994 0.0402004 0.95045 0.308267 0.0138217 0.975223 0.220791 0.00849013 0.977276 0.2118 0.0186129 0.974472 0.223735 0.00408437 0.976535 0.215321 0.0117312 0.987326 0.158272 0.0046669 0.994222 0.107243 -0.0208106 0.996642 0.0791913 -0.00443319 0.998752 0.0497386 0.027004 0.996019 -0.0849473 0.0336816 0.999198 -0.0216356 0.0114371 0.999905 -0.00774988 0.00307975 0.999991 -0.0030178 0.00104263 0.999999 -0.000368276 0.00100298 1 -0.000117627 0.0010389 0.999999 -0.000435792 0.00098251 0.999999 -0.000635334 0.000803892 0.999999 -0.000888335 0.000444284 1 0.000357354 -0.00948567 0.999922 0.00817598 -0.0817836 0.989613 0.118227 -0.244926 0.926871 0.284468 -0.186858 0.952951 0.23868 -0.293632 0.862405 0.412356 -0.525632 0.398326 0.751696 -0.472882 0.569366 0.672462 -0.434601 0.690279 0.578478 -0.414357 0.715691 0.562223 -0.34335 0.807135 0.480253 -0.16993 0.944939 0.279668 0.0242727 0.93249 0.360379 0.00310632 0.963636 0.267199 0.0402025 0.972059 0.231266 0.0379052 0.975892 0.214937 0.0656457 0.991414 0.113092 0.032863 0.989717 0.139215 -0.0431612 0.988541 0.144654 -0.0253438 0.99319 0.113713 -0.218405 0.968367 0.120683 -0.131589 0.983312 0.125629 -0.167498 0.981444 0.0933442 -0.0304999 0.998865 0.0365788 -0.235749 0.960931 0.145031 -0.216479 0.969734 0.112925 -0.215981 0.969706 0.114113 -0.183221 0.969868 0.160582 0.0042743 0.999403 0.0342951 0.0143767 0.999718 -0.0188852 0.0171759 0.999829 -0.0069047 0.029925 0.999423 -0.016083 0.0188628 0.999807 -0.00553245 0.00101942 0.999999 -0.000665557 0.00213313 0.999997 -0.00111445 0.00214876 0.999997 -0.00110919 -0.00501007 0.999981 -0.00359559 -0.00798119 0.999959 -0.00438846 0.00543958 0.99998 -0.00318046 0.00664923 0.999971 -0.00380207 0.00644623 0.999973 -0.0036648 0.00475246 0.999988 -0.00137796 0.00452021 0.999989 -0.0014341 0.000976938 0.999999 -0.0011974 0.00106117 0.999999 6.86716e-05 0.000658701 0.999999 -0.00109729 0.000894235 1 0.000111084 0.00168893 0.999998 -0.00123169 0.00104838 0.999999 0.000440883 0.00172724 0.999998 -0.000306121 0.0011395 0.999999 0.000747474 0.000237306 0.999999 0.00131673 -0.00218237 0.999991 0.00372592 -0.00175271 0.999989 0.00441962 -0.0108138 0.999916 0.00715156 -0.00260034 0.999923 0.012098 -0.00739674 0.999926 0.00962179 -0.0264194 0.99923 0.0290028 -0.00934714 0.999877 0.0125858 -0.00677249 0.999937 0.0089166 0.0169251 0.999796 -0.011024 0.0161047 0.999821 -0.00989493 0.0147134 0.999876 -0.00569846 0.0805378 0.988559 0.127534 0.097204 0.984105 0.148624 0.00966496 0.998511 0.0536947 -0.0309569 0.999469 0.0101889 -0.000963923 0.999946 0.0103008 0.0133076 0.999901 -0.00449146 0.0138049 0.999764 -0.0167784 0.0179732 0.999741 -0.0139319 0.00635758 0.999979 0.00155156 0.00728072 0.999956 -0.00587453 0.0190197 0.999815 -0.00282548 0.0125312 0.999899 -0.00676769 0.0224049 0.999665 -0.0129293 0.0215415 0.999689 -0.0125928 -0.0558071 0.996753 0.0580437 -0.0602728 0.996541 0.0572058 -0.0291255 0.999151 0.0291524 -0.0103488 0.999379 0.0336836 -0.104558 0.990752 0.0864726 -0.0492068 0.99786 0.0430596 -0.0349177 0.999008 0.0276343 -0.705831 0.300417 0.641523 -0.736658 0.188945 0.649335 -0.647656 0.509841 0.566219 -0.63461 0.173621 0.753078 -0.675148 0.161943 0.719687 -0.606947 0.467219 0.642901 -0.686176 0.431972 0.585288 -0.555289 0.690384 0.463707 -0.551014 0.701642 0.451754 -0.282 0.936755 0.20728 -0.300906 0.921847 0.244241 -0.0911879 0.994145 0.0579644 -0.108877 0.989165 0.0984772 -0.558748 0.154918 0.81474 -0.531864 0.380646 0.756459 -0.584046 0.374291 0.720275 -0.460785 0.68763 0.561109 -0.457422 0.702752 0.544889 -0.201775 0.952346 0.228744 -0.202258 0.951922 0.230078 -0.0185905 0.999776 0.0100877 -0.0270454 0.999148 0.0311878 0.00579443 0.999955 -0.00753956 0.00661014 0.999962 -0.00561975 0.00823818 0.999958 -0.00409939 -0.000930822 0.999987 0.00499589 -0.000221381 0.999998 0.00196764 -0.0571896 0.996539 0.060334 -0.0373074 0.999116 0.0193603 -0.242762 0.941445 0.233982 -0.232496 0.949675 0.209912 -0.501331 0.707026 0.49878 -0.505379 0.693318 0.513714 -0.636048 0.401469 0.658988 -0.565621 0.420509 0.709398 -0.611569 0.182793 0.769785 -0.611797 0.196941 0.766106 -0.412834 0.694206 0.589615 -0.165123 0.711824 0.682672 -0.168119 0.712803 0.680918 -0.0294166 0.723837 0.689344 -0.338518 0.651552 0.678885 -0.487959 0.661605 0.569363 -0.620207 0.585578 0.52196 -0.635778 0.584481 0.504152 -0.740887 0.505343 0.442398 -0.738328 0.489468 0.463996 -0.778606 0.47857 0.405887 -0.783166 0.450678 0.428416 -0.762313 0.472788 0.441984 0.0486594 0.749313 0.660426 0.0488343 0.744964 0.665315 -0.100266 0.772981 0.626456 0.0408509 0.753864 0.65576 0.0450367 0.745677 0.664784 -0.0829881 0.79098 0.606187 -0.0837781 0.793279 0.603067 -0.243393 0.82468 0.510551 0.0317611 0.759991 0.649157 0.035089 0.748522 0.662181 -0.0640105 0.808672 0.584767 -0.0641813 0.810352 0.582417 -0.179504 0.861055 0.475776 -0.17679 0.874032 0.452564 -0.242973 0.891268 0.38289 -0.0198873 0.972518 0.231977 -0.0365508 0.968554 0.246105 -0.017166 0.974137 0.225305 -0.0759997 0.971108 0.226216 -0.170108 0.946573 0.273975 -0.137018 0.933632 0.330996 -0.149738 0.933741 0.325126 -0.169378 0.904392 0.391645 -0.134286 0.900746 0.413067 -0.453824 0.85264 0.258937 -0.465161 0.832247 0.301645 -0.445294 0.837709 0.31616 -0.455724 0.810827 0.367253 -0.398357 0.822052 0.406869 -0.683626 0.635898 0.358174 -0.684767 0.625549 0.373876 -0.651462 0.647686 0.395096 -0.651822 0.630776 0.42101 -0.55424 0.683389 0.475182 -0.537583 0.679896 0.498744 -0.386353 0.732284 0.560796 -0.364597 0.725302 0.583957 -0.147558 0.755735 0.638038 -0.808007 0.391221 0.440534 -0.770685 0.470432 0.429813 -0.668102 0.646449 0.368434 -0.664999 0.649985 0.367825 -0.467527 0.848315 0.248558 -0.401617 0.885727 0.232792 -0.215928 0.968752 0.122042 -0.168624 0.978788 0.116363 -0.0744793 0.990693 0.113934 -0.0472722 0.990394 0.129945 -0.205323 0.955995 0.209564 -0.163842 0.949663 0.267013 -0.291425 0.9129 0.285805 -0.234608 0.906637 0.350668 -0.382323 0.81084 0.443134 -0.242939 0.816212 0.524193 -0.315494 0.782186 0.53726 -0.103104 0.778079 0.619648 -0.124883 0.7459 0.654246 0.0410307 0.738894 0.672572 0.00823274 0.712074 0.702056 0.0205833 0.999769 -0.00625408 -0.0280566 0.999259 0.0263503 -0.0241456 0.999464 0.0221194 -0.0337437 0.999066 0.0269922 -0.108903 0.990711 0.0814384 -0.163617 0.9816 0.0984409 -0.332208 0.916628 0.222333 -0.38951 0.888738 0.241716 -0.614128 0.674175 0.410287 -0.604944 0.683991 0.407675 -0.733504 0.455552 0.504425 -0.690117 0.535818 0.486453 -0.762676 0.355049 0.540616 -0.80021 0.311459 0.512501 -0.00589063 0.761115 0.64859 -0.00261869 0.764675 0.64441 -0.00370857 0.769161 0.639044 0.0130558 0.786812 0.617054 0 0.79331 0.608818 -0.55799 0.601056 0.572171 -0.0152932 0.742214 0.669989 0.00122918 0.755082 0.65563 0.00177512 0.755392 0.655271 -0.00700046 0.761524 0.648099 -0.00401121 0.764576 0.644521 -0.00626747 0.766021 0.642785 -0.0137229 0.776403 0.630087 -0.176787 0.838278 0.515787 -0.0591076 0.816538 0.574257 0 0.808704 0.588215 -0.0160827 0.813426 0.581446 -0.800447 0.165302 0.576159 -0.693858 0.0808593 0.715558 -0.73833 0.0674341 0.67106 -0.236069 0.0941756 0.967162 -0.357663 0.0257106 0.933497 -0.0436409 0.271608 0.961418 -0.083289 0.259578 0.962124 -0.0474111 0.24699 0.967858 -0.141736 0.246295 0.958775 -0.0670931 0.189646 0.979558 -0.0870122 0.196491 0.976637 -0.577621 -0.00840904 0.816262 -0.562197 0.0104004 0.826938 -0.554322 0.00112471 0.832302 -0.544017 -0.000138536 0.839074 -0.563622 -0.00352137 0.826025 -0.549821 0.000564859 0.835283 -0.567685 0.0139503 0.823128 -0.590496 0.0119158 0.806953 -0.595707 0.0205542 0.802939 -0.623201 0.0511894 0.780385 -0.643669 0.0475121 0.763828 -0.562938 -1.29645e-05 0.826499 -0.549994 -0.0184044 0.834966 -0.587183 0.00670112 0.809427 -0.586919 0.0180265 0.809445 -0.651115 0.00820163 0.758935 -0.650067 0.0461252 0.758475 -0.663845 0.0706618 0.744524 -0.457029 0.494981 0.738999 -0.177792 0.654288 0.735049 -0.467615 0.494788 0.732476 -0.456172 0.530767 0.714278 -0.511088 0.527552 0.678585 -0.495431 0.567446 0.657688 -0.538401 0.561661 0.628221 -0.776166 0.399552 0.487775 -0.724195 0.286946 0.62706 -0.730256 0.395654 0.556942 -0.707353 0.0693133 0.703454 -0.695565 0.184444 0.694384 -0.723612 0.173513 0.668042 -0.747018 0.216215 0.628661 -0.746652 0.192108 0.636871 -0.729929 0.0867113 0.678 -0.66646 0.107064 0.737813 -0.668569 0.0796969 0.739368 -0.634262 0.025238 0.772706 -0.752558 0.272504 0.599498 -0.745253 0.302666 0.594131 -0.7896 0.27665 0.547719 -0.781961 0.306812 0.54259 -0.809324 0.385991 0.442725 -0.56849 -0.0120456 0.822602 -0.568147 0.0230266 0.822605 -0.603909 0.0442939 0.795821 -0.602233 0.0771173 0.794587 -0.649246 0.067345 0.757591 -0.638011 0.184356 0.747633 -0.645082 0.182233 0.742065 -0.716921 0.216391 0.662721 -0.677666 0.231246 0.698064 -0.739136 0.256746 0.622703 -0.643967 0.295566 0.705653 -0.700836 0.373429 0.607766 -0.608521 0.413446 0.677322 -0.592115 0.463554 0.65918 -0.658589 0.452868 0.600975 -0.644635 0.48822 0.588292 -0.68988 0.47413 0.547053 -0.356692 0.149031 0.922258 -0.340875 0.318357 0.884564 -0.233356 0.327608 0.915542 -0.322293 0.36244 0.874508 -0.129857 0.376154 0.917412 -0.205085 0.406186 0.890479 -0.125508 0.328507 0.936125 -0.0831576 0.309114 0.947382 -0.235189 0.304322 0.923079 -0.141123 0.263093 0.954393 -0.244483 0.259225 0.934361 -0.245501 0.2446 0.93803 -0.149485 0.0452084 0.98773 -0.301404 0.0899033 0.949249 -0.369926 0.0370476 0.928322 -0.365809 0.148201 0.918815 -0.433525 0.0706091 0.898371 -0.431457 0.114924 0.894783 -0.481319 0.147487 0.864049 -0.560655 0.18314 0.807543 -0.527014 0.189685 0.828418 -0.604597 0.222168 0.764921 -0.56312 0.231666 0.793238 -0.479624 0.166946 0.861446 -0.527238 0.187699 0.828727 -0.462332 0.197696 0.864387 -0.438151 0.362895 0.822394 -0.319859 0.38053 0.867691 -0.40144 0.408866 0.819557 -0.153851 0.436724 0.886342 -0.16844 0.50979 0.843648 -0.0830572 0.497256 0.863619 -0.0816668 0.558714 0.82533 -0.0404682 0.550633 0.833766 -0.0953828 0.611211 0.785699 -0.115718 0.613708 0.781007 -0.00749295 0.670519 0.741854 -0.0313529 0.677647 0.734719 -0.5623 4.80756e-05 0.826933 -0.562924 0.000876921 0.826508 -0.599093 -0.00247137 0.800675 -0.59896 0.0052527 0.800762 -0.630215 0.0259668 0.775987 -0.629324 0.0485935 0.775622 -0.706328 0.0304696 0.707228 -0.697231 0.153266 0.70027 -0.755188 0.126399 0.643207 -0.788172 0.199987 0.582057 -0.7958 0.195522 0.573126 -0.815753 0.248171 0.522455 -0.833147 0.269309 0.483052 -0.438154 0.0171101 0.898737 -0.498904 -0.0728773 0.863588 -0.460808 0.0676235 0.88492 -0.49274 0.028132 0.869722 -0.489768 0.107204 0.865237 -0.528618 0.0555329 0.847042 -0.585856 0.1289 0.800099 -0.581882 0.168276 0.795674 -0.561854 0.172755 0.808997 -0.641275 0.208791 0.738358 -0.60513 0.218649 0.765513 -0.674744 0.247259 0.695402 -0.55494 0.282085 0.782604 -0.627285 0.36412 0.688426 -0.398423 0.424088 0.81327 -0.470621 0.446201 0.761197 -0.242643 0.486438 0.839347 -0.234771 0.540332 0.808037 -0.258925 0.542851 0.798919 -0.249565 0.589902 0.767941 -0.274336 0.591868 0.757913 -0.262254 0.638318 0.723721 -0.342506 0.641 0.686884 0.00448951 0.851164 0.524881 0.0175755 0.846122 0.5327 0.0469847 0.84308 0.535732 0.0259644 0.835777 0.548454 0 0.821618 0.570039 -0.00275897 0.87646 0.481467 -0.00127877 0.879715 0.475499 0.00673886 0.882342 0.47056 0.00334139 0.884441 0.46664 0.0126245 0.880335 0.474184 0.0189069 0.878893 0.476645 0.015549 0.879395 0.475839 0.000176566 0.86196 0.506976 -0.000115014 0.854748 0.519044 0 0.825902 0.563814 0 0.825902 0.563814 0.000449439 0.852634 0.522509 -0.000799139 0.861076 0.508475 -0.00497355 0.872253 0.48903 -0.00818999 0.869068 0.494625 -0.00514791 0.872421 0.488728 -0.00852911 0.834407 0.551083 -0.00383127 0.840628 0.5416 -0.00134793 0.845628 0.53377 0 0.949789 0.312893 0.00274539 0.941914 0.335844 -0.000930938 0.934913 0.354877 0.00184895 0.907767 0.41947 -0.00262651 0.912692 0.40864 0.000867368 0.886337 0.463041 0.00130085 0.885947 0.463784 0 0.755082 0.65563 0 0.724297 0.689488 1.38584e-07 0.724297 0.689489 0 0.79331 0.608818 -0.00326042 0.784903 0.61961 -0.000886708 0.769166 0.639048 -5.8058e-05 0.761128 0.648602 1.54755e-08 0.949788 0.312893 0 0.853636 0.520869 -0.0161783 0.834328 0.551031 0 0.872264 0.489036 0 0.904193 0.427123 0.00159869 0.907767 0.419471 -0.00136724 0.931766 0.363056 0 0.934913 0.354877 0 0.949788 0.312893 0 0.250192 0.968196 -0.000980927 0.239669 0.970854 0.00552561 0.312113 0.950029 -0.0225438 0.258974 0.965621 -0.0158781 0.271832 0.962214 0 0.331125 0.943587 0 0.3992 0.916864 0.00669012 0.414998 0.909798 0 0.453049 0.891486 0 0.475781 0.879564 0.00212265 0.498979 0.866612 0.000242916 0.505578 0.862781 -0.000222336 0.549005 0.835819 0.000332343 0.551085 0.834449 1.6201e-07 0.571476 0.820619 1.55558e-07 0.617859 0.786289 0 0.617859 0.786289 0 0.67798 0.73508 1.50887e-07 0.67798 0.735081 0 0.225342 0.97428 0 -0.376087 0.926584 0.00495253 -0.303816 0.952718 -0.00324296 -0.254527 0.96706 0 -0.191004 0.981589 0 -0.166351 0.986067 0.00120301 -0.108006 0.99415 -0.00570809 -0.0714502 0.997428 0 -0.0208643 0.999782 0 0.06247 0.998047 -0.00554251 0.0426419 0.999075 0.00400791 0.134448 0.990913 0 0.117055 0.993125 0 0.197714 0.98026 -0.00956166 0.167161 0.985883 -0.00294446 0.196739 0.980452 0 -0.838671 -0.544639 0 -0.838671 -0.544639 0.0351102 -0.788545 0.613974 0.000416045 -0.740938 0.671574 0.000617368 -0.741021 0.671482 0 -0.696817 0.717249 0.000597014 -0.696192 0.717855 0.000274159 -0.696431 0.717623 0.0846221 -0.814051 0.574595 0.00323818 -0.797523 0.603279 -1.96466e-07 -0.808133 0.589001 0 -0.878328 -0.478059 0.00860254 -0.919578 -0.392813 0.00191361 -0.941608 -0.336705 -0.000976674 -0.979992 -0.199035 0.00701047 -0.998224 -0.0591602 0.00813461 -0.997727 -0.0668975 -0.000883197 -0.908871 0.417076 0.00766047 -0.968496 0.24891 0.00138573 -0.959573 0.281457 2.00402e-05 -0.99246 0.12257 -0.000153168 -0.998302 0.0582598 0 0.823408 -0.56745 0 0.834269 -0.551358 0.102362 0.827504 -0.55205 0.0107417 0.87618 -0.481864 0.0189433 0.87447 -0.48471 0.0181464 0.842917 -0.537737 0.00554571 0.846537 -0.532301 -0.0263466 0.868731 -0.494582 0.0633702 0.869835 -0.489256 0.0292207 0.872725 -0.487336 -0.00239256 0.8771 -0.480301 -0.00133854 0.879735 -0.475463 0.00509218 0.878934 -0.476915 0.00189617 0.881382 -0.472401 -0.00127086 0.885749 -0.464163 -0.00422948 0.873963 -0.485974 -0.00616121 0.871328 -0.490663 -0.0103933 0.866565 -0.498957 -0.0182496 0.860634 -0.508896 -0.0251871 0.856408 -0.515685 -0.0147755 0.861971 -0.506743 0 0.821617 -0.57004 -0.00138219 0.821948 -0.569561 0.000412304 0.833089 -0.553139 -0.00191277 0.843188 -0.537615 7.53323e-05 0.883677 -0.468098 -5.30066e-05 0.894598 -0.446873 0.00230591 0.908069 -0.418813 -0.0103104 0.928589 -0.370967 0 0.939797 -0.341734 0 0.784907 -0.619614 -0.00455813 0.793302 -0.608811 -0.000886714 0.769166 -0.639048 -5.80577e-05 0.761128 -0.648602 0 0.755082 -0.65563 0 0.724297 -0.689489 0 0.724297 -0.689489 0 0.823408 -0.56745 0 0.936904 -0.349586 0.00642472 0.928619 -0.370979 0 0.908717 -0.417412 0 0.894598 -0.446873 -0.00359277 0.867232 -0.497892 5.01319e-08 0.862065 -0.506798 5.61316e-08 0.823408 -0.56745 0 0.238823 -0.971063 -0.000107709 0.266684 -0.963784 -0.00514274 0.244188 -0.969714 0 0.647132 -0.762378 -0.012854 0.666083 -0.745767 0 0.619273 -0.785176 0 0.585144 -0.810929 0.00402395 0.564838 -0.825192 -0.00299719 0.538544 -0.842592 0 0.517873 -0.855457 0 0.494909 -0.868945 0.00441228 0.463488 -0.886092 -0.0023928 0.44524 -0.895408 0 0.4127 -0.910867 0 0.382105 -0.924119 -0.000572147 0.384362 -0.923182 0.000773416 0.326369 -0.945242 0 0.328774 -0.944408 0 0.267637 -0.96352 0 -0.340802 -0.940135 0 0.22894 -0.973441 -0.000948729 0.21615 -0.97636 -0.00208955 0.205066 -0.978746 -0.00471035 0.188866 -0.981992 -0.00680378 0.179513 -0.983732 0.00205824 0.138386 -0.990376 0 0.103894 -0.994588 0 0.0465255 -0.998917 0.00477738 0.0268597 -0.999628 -0.00102421 -0.0376577 -0.99929 6.49577e-09 -0.0604365 -0.998172 1.23088e-08 -0.114521 -0.993421 0.00330492 -0.137377 -0.990513 -0.00230003 -0.21594 -0.976404 0 -0.24228 -0.970206 0 -0.340802 -0.940135 0 -0.83867 0.544639 0 -0.83867 0.544639 -8.19804e-06 -0.994037 -0.109044 0 -0.878596 0.477567 -1.96466e-07 -0.808133 -0.589 0.000352372 -0.733576 -0.679607 0.000345113 -0.733576 -0.679607 0.0848163 -0.778738 -0.621589 0.000134092 -0.95887 -0.283846 0.0289181 -0.990274 -0.136091 0.00738828 -0.968058 -0.250616 -0.000937577 -0.794043 -0.607861 0.00390162 -0.795318 -0.606181 -0.000964386 -0.905761 -0.423788 0.00188319 -0.931342 -0.364141 0.00861352 -0.919578 0.392813 0.00177856 -0.942173 0.335121 -0.00354127 -0.998242 0.0591612 0.0271774 -0.979853 0.197863 -0.0183061 -0.993166 -0.115266 0.00864554 -0.997731 0.0667634 0.000617824 -0.99877 -0.049589 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.998389 0.0567322 -0.00169971 -0.995762 0.0919517 0 -0.559169 0.829054 0.00910374 -0.511006 0.859529 -0.00585722 -0.692134 0.721746 0.00102445 -0.640634 0.767846 1.40207e-07 -0.706321 0.707892 1.52781e-05 -0.785499 0.618863 0.00499854 -0.758164 0.652045 -0.00507013 -0.879393 0.47607 0.000229446 -0.855757 0.517378 -0.00016879 -0.936953 0.349456 0.00454823 -0.913797 0.406146 -0.00860818 -0.980578 0.195938 0.0162726 -0.929927 0.367383 0.00379119 -0.962909 0.269801 0 -0.459952 0.887944 0.000402609 -0.739511 0.673144 0 -0.739411 0.673255 -0.0258623 -0.754439 0.655861 -5.10542e-05 -0.701901 0.712275 -4.55584e-05 -0.650792 0.759256 0.0015324 -0.639267 0.768984 -0.004445 -0.584017 0.811729 -4.86868e-05 -0.57163 0.820511 -1.40477e-05 -0.483601 0.875289 -0.0118585 -0.521923 0.85291 -0.00573058 -0.500324 0.865819 -1.57573e-05 -0.830933 0.556373 -0.0255686 -0.858043 0.512941 0.0373209 -0.679213 0.732992 -2.39876e-05 -0.739399 0.673268 -1.62124e-05 -0.788376 0.615194 -0.00370749 -0.822035 0.569425 -0.00368237 -0.973255 0.229697 -0.00211385 -0.972274 0.233835 0.00101769 -0.950794 0.309822 -1.02144e-05 -0.952537 0.304424 -3.69619e-05 -0.915915 0.401372 -0.0265981 -0.935376 0.352653 0.0240128 -0.87844 0.477248 -0.00714101 -0.91182 0.410528 3.80302e-06 -0.883923 0.467633 0 -0.998799 0.0489932 -0.000491397 -0.998865 0.0476199 0.000372197 -0.991073 0.133318 1.11417e-06 -0.991257 0.131946 -3.73819e-06 -0.983956 0.178412 1.90293e-06 0.815244 -0.579118 0 0.814212 -0.580568 -0.520508 0.240492 -0.819289 -0.110723 0.460642 -0.880653 -0.119857 0.662067 -0.739798 -0.0250382 0.619079 -0.784929 -0.0298605 0.517642 -0.855076 -0.668569 0.0796973 -0.739368 -0.0364406 0.267459 -0.96288 -0.301405 0.0899033 -0.949248 -0.235942 0.0941829 -0.967192 -0.25235 0.103554 -0.962079 -0.140536 0.213289 -0.966829 -0.0734902 0.192161 -0.978608 -0.529172 0.0138459 -0.848402 -0.503313 0.0165392 -0.863946 -0.450984 0.0164189 -0.892381 -0.45884 0.00057779 -0.888518 -0.372326 0.03414 -0.927474 -0.579611 -0.00679559 -0.814865 -0.568488 -0.0148421 -0.822558 -0.563666 -0.00835444 -0.82596 -0.549389 0.00193934 -0.835564 -0.574473 -0.00715665 -0.818492 -0.562191 0.0108859 -0.826936 -0.550809 -0.000137361 -0.834632 -0.549829 -1.32017e-05 -0.835277 -0.563061 -0.00970102 -0.826359 -0.562937 4.80444e-05 -0.8265 -0.562294 0.000934398 -0.826937 -0.599094 -0.00247137 -0.800675 -0.568147 0.0230265 -0.822605 -0.659675 0.0650722 -0.748728 -0.702841 0.0957145 -0.704878 -0.67076 0.0391097 -0.740642 -0.650155 0.0438988 -0.758533 -0.630616 0.0114193 -0.776011 -0.622874 0.0512146 -0.780644 -0.595681 0.0205133 -0.802959 -0.593593 0.0170383 -0.804585 -0.704094 0.0779035 -0.705821 -0.693643 0.0809508 -0.715755 -0.649189 0.0651306 -0.757834 -0.664639 0.0428769 -0.745933 -0.643477 0.0475145 -0.763989 -0.105504 0.557642 -0.823349 -0.233832 0.54623 -0.804335 -0.242643 0.486438 -0.839346 -0.389814 0.464169 -0.795357 -0.408902 0.367918 -0.835126 -0.683386 0.196199 -0.7032 -0.666592 0.287194 -0.687877 -0.749303 0.202943 -0.630365 -0.56587 0.132739 -0.81374 -0.554254 0.23122 -0.799587 -0.648833 0.151912 -0.745613 -0.63514 0.245807 -0.732241 -0.726011 0.155398 -0.669896 -0.0316396 0.665804 -0.745456 -0.04898 0.668411 -0.742177 -0.0513949 0.612854 -0.788523 -0.248263 0.595995 -0.763646 -0.259986 0.537116 -0.802442 -0.5452 0.547758 -0.634601 -0.690407 0.473921 -0.546568 -0.644647 0.488188 -0.588305 -0.666904 0.430029 -0.608534 -0.730256 0.395654 -0.556941 -0.729929 0.260952 -0.63175 -0.724195 0.286946 -0.62706 -0.733436 0.282367 -0.618337 -0.759367 0.240832 -0.604452 -0.723612 0.173514 -0.668041 -0.0913394 0.3274 -0.940461 -0.128832 0.308452 -0.942475 -0.139248 0.308209 -0.941073 -0.142035 0.237617 -0.960919 -0.0697414 0.246467 -0.966639 -0.060642 0.256921 -0.964528 -0.0491893 0.264274 -0.963193 -0.111114 0.410145 -0.905227 -0.19933 0.441412 -0.874885 -0.189337 0.442211 -0.876699 -0.186252 0.480834 -0.856802 -0.429775 0.141873 -0.891721 -0.250355 0.157483 -0.95526 -0.348407 0.252207 -0.902776 -0.238284 0.259542 -0.935873 -0.22952 0.370946 -0.899844 -0.127874 0.376218 -0.917664 -0.138089 0.38068 -0.914338 -0.350493 0.620874 -0.701192 -0.490114 0.5801 -0.650594 -0.516848 0.511757 -0.686275 -0.583705 0.486774 -0.649876 -0.608521 0.413446 -0.677322 -0.613455 0.411553 -0.674016 -0.652171 0.25464 -0.714025 -0.596298 0.271207 -0.755563 -0.611374 0.172331 -0.772349 -0.476448 0.19868 -0.85646 -0.206418 0.653203 -0.728504 -0.258925 0.65017 -0.714309 -0.275774 0.585937 -0.761988 -0.450709 0.546804 -0.705597 -0.467615 0.494788 -0.732476 -0.457029 0.494981 -0.738998 -0.480287 0.406937 -0.776999 -0.530629 0.394175 -0.750373 -0.543303 0.340788 -0.767259 -0.455951 0.252257 -0.853507 -0.847963 0.257065 -0.463548 -0.832865 0.269526 -0.483418 -0.791524 0.219656 -0.570299 -0.828794 0.174884 -0.531522 -0.740988 0.225496 -0.632525 -0.799828 0.10359 -0.591222 -0.732759 0.136538 -0.666649 -0.567741 0.000552451 -0.823207 -0.549544 0.0155336 -0.835321 -0.587064 0.0122259 -0.809449 -0.587183 0.00670113 -0.809427 -0.630818 0.00124609 -0.77593 -0.598235 0.031594 -0.800698 -0.604418 0.0305236 -0.796082 -0.603909 0.0442936 -0.795821 -0.491894 0.0606265 -0.868542 -0.491773 0.0640981 -0.868361 -0.368972 0.0772512 -0.926224 -0.37 0.0323078 -0.92847 -0.333695 0.0653147 -0.940416 -0.776852 0.398968 -0.487161 -0.749807 0.408031 -0.520865 -0.7896 0.276651 -0.547719 -0.777595 0.284051 -0.560946 -0.769892 0.18103 -0.61196 -0.746652 0.192108 -0.636871 -0.743304 0.165381 -0.648188 -0.70557 0.0948301 -0.702267 -0.698213 0.165183 -0.696572 -0.648143 0.0848786 -0.756774 -0.641839 0.15373 -0.751272 -0.589503 0.0796398 -0.803831 -0.585856 0.1289 -0.800098 -0.561339 0.0966397 -0.821924 -0.484174 0.107978 -0.868284 -0.429539 0.145277 -0.891286 -0.527238 0.1877 -0.828727 -0.352167 0.211494 -0.911729 -0.448394 0.304439 -0.840393 -0.32749 0.319752 -0.889106 -0.313692 0.422278 -0.850458 -0.222208 0.432041 -0.874051 -0.215691 0.495317 -0.84151 -0.0829219 0.504335 -0.859517 -0.0815519 0.562961 -0.82245 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.00109957 -0.912731 -0.408559 0.00619194 -0.857253 -0.514858 -0.00705122 -0.89829 -0.439346 0.00337906 -0.780311 -0.625382 1.87268e-05 -0.806985 -0.590572 -7.06092e-06 -0.730822 -0.682568 0.000974736 -0.717273 -0.696791 -0.00124638 -0.639651 -0.768665 0.00239136 -0.596264 -0.802785 -0.0018184 -0.508086 -0.861305 0 -0.477438 -0.878665 0 -0.995874 -0.09075 0.00400542 -0.990208 -0.139541 -0.00160817 -0.964358 -0.264597 3.86429e-06 -0.9506 -0.31042 -3.29171e-07 -0.935631 -0.352981 0.000236989 -0.925993 -0.37754 -6.82552e-05 -0.702716 -0.711471 6.71294e-05 -0.702937 -0.711253 7.29428e-05 -0.702951 -0.711239 0 -0.473181 -0.880965 0.00153105 -0.480184 -0.877167 -0.00147667 -0.545791 -0.83792 -0.00034167 -0.550819 -0.834624 0.000320992 -0.610296 -0.792174 0.00458033 -0.627345 -0.778728 -0.00224239 -0.666816 -0.745219 0.000699846 -0.688595 -0.725146 -0.000144284 -0.702252 -0.711929 -0.0125912 -0.983255 -0.181798 0.000457758 -0.9899 -0.141769 2.566e-06 -0.995311 -0.0967249 -8.72525e-05 -0.998866 -0.0476094 0 -0.998854 -0.0478591 -0.00837287 -0.933454 -0.358599 0.00155835 -0.946479 -0.322762 -0.000335369 -0.960809 -0.27721 -4.2619e-05 -0.962419 -0.271569 -3.72363e-05 -0.974033 -0.226406 -0.0050164 -0.852304 -0.523024 0.00229134 -0.87115 -0.491012 -0.000957067 -0.893936 -0.448194 -3.74627e-06 -0.898827 -0.438304 5.48724e-06 -0.918184 -0.396155 0.000304386 -0.721905 -0.691992 -0.00627879 -0.766323 -0.642425 -0.00690036 -0.76747 -0.641047 -1.19635e-05 -0.807788 -0.589473 -4.59567e-06 -0.833713 -0.552198 -0.152481 0.981826 -0.112996 -0.00806971 0.999909 -0.0108145 0.00513346 0.999985 0.00189408 -0.472883 0.569367 -0.67246 0.0486673 0.749091 -0.660678 -0.163599 0.903931 -0.395151 -0.0219843 0.972091 -0.233572 0.0201837 0.939968 -0.340664 -0.0182029 0.872209 -0.488795 -8.70544e-05 0.858797 -0.512317 -0.0380744 0.846517 -0.530999 -0.000140301 0.835877 -0.548916 -0.00280251 0.899602 -0.436701 -0.00804585 0.914975 -0.40343 0.000596591 0.928605 -0.371069 0.00885109 0.956111 -0.292873 0.000789098 0.963327 -0.268329 0.0370951 0.977173 -0.20918 -0.170109 0.946573 -0.273976 -0.118867 0.961377 -0.248244 -0.0841034 0.968545 -0.234194 -0.189703 0.917233 -0.350281 -0.136533 0.934147 -0.32974 -0.139368 0.93468 -0.327032 -0.114786 0.947481 -0.298503 -0.102763 0.950899 -0.291943 -0.130451 0.899852 -0.416233 -0.0581804 0.92587 -0.373336 -0.131962 0.843097 -0.521318 -0.0302768 0.849946 -0.525999 -0.0114498 0.851546 -0.524154 -0.0410639 0.78206 -0.621848 0.0338771 0.761949 -0.64675 0.0353815 0.759794 -0.6492 0.0241806 0.724289 -0.689072 -0.0298203 0.71097 -0.70259 -0.293638 0.8624 -0.412363 -0.34334 0.807148 -0.48024 0.00120689 0.999999 -0.000501039 0.00111465 0.999999 -0.000730807 -0.00168199 0.999994 -0.0030842 0.000443601 1 -0.00035823 -0.0094862 0.999922 -0.00817558 -0.0818197 0.989606 -0.118263 0.00103361 0.999999 0.000454487 0.000955215 0.999999 0.00073192 0.00104506 0.999999 0.000383669 0.00101231 0.999999 0.000176581 0.00157103 0.999997 0.00168335 0.00104309 1 -7.50315e-05 0.00150746 0.999999 0.000827953 0.00121973 0.999999 -0.00043248 0.00110223 0.999999 -0.000653536 0.00617248 0.999968 0.00501386 0.00620731 0.999968 0.00501524 0.00484453 0.999937 0.0101726 0.00708024 0.999955 0.00636536 0.00789261 0.999964 0.00311774 0.00624263 0.999962 0.00612993 0.0145136 0.999882 0.00498786 0.0162019 0.999807 0.0110764 0.0407928 0.979635 -0.196598 -0.0524684 0.979621 -0.193881 0.000407171 0.977524 -0.210823 0.00583626 0.940696 -0.3392 0.00622271 0.946249 -0.32338 0.0245761 0.966194 -0.256642 0.0142885 0.974862 -0.222349 -0.0232146 0.955867 -0.292882 0.021391 0.999748 0.00678097 -0.218432 0.968369 -0.12062 -0.216672 0.969517 -0.114415 -0.00403967 0.99994 -0.0102333 -0.0212509 0.999404 -0.0271862 -0.0522737 0.997805 -0.0406638 -0.0556399 0.997531 -0.0428563 -0.0797235 0.996267 -0.0331169 -0.144812 0.98179 -0.122959 -0.164708 0.979462 -0.116297 -0.0105464 0.996031 -0.0883775 -0.0257196 0.993149 -0.11399 -0.047263 0.990395 -0.12994 0.0813826 0.982754 -0.166046 0.0545128 0.984931 -0.164129 0.0277958 0.989295 -0.143256 -0.0292378 0.981712 -0.188112 -0.0161347 0.973418 -0.228466 -0.056706 0.973043 -0.223545 0.0143009 0.999889 0.00424848 0.0178548 0.999836 0.00298344 0.0158713 0.999867 0.00376892 0.0219968 0.999678 0.0126751 0.0216068 0.999689 0.0124321 0.0143013 0.999775 0.0156748 0.0187702 0.999807 0.00573832 0.0304205 0.999402 0.0164394 0.0305077 0.999406 0.0160397 0.0152075 0.999767 0.0153323 0.0149776 0.999669 0.0209143 0.0115614 0.999905 0.00753634 0.0388099 0.998208 -0.0455538 0.0386809 0.99827 -0.0442882 -0.160681 0.986988 0.00602265 -0.010545 0.996547 -0.0823602 0.0141512 0.999699 0.020016 0.0129203 0.999892 0.00699187 -0.0129355 0.999045 -0.0417282 -0.0312748 0.999027 0.0310925 -0.0283843 0.999508 -0.0133135 -0.0280013 0.999137 -0.030685 -0.0218769 0.999283 -0.0309015 -0.0023733 0.999363 -0.0356199 0.120081 0.975001 -0.18696 0.0217676 0.999672 -0.0135316 0.0148841 0.999848 0.00911633 -0.0969838 0.993285 -0.0630868 -0.0718959 0.995697 -0.0584692 -0.0595345 0.996542 -0.0579549 -0.0462378 0.997952 -0.0441954 -0.0354116 0.998756 -0.0351026 0.00222833 0.999996 0.00144614 0.00222587 0.999996 0.00144524 0.000679776 0.999999 0.00101663 0.000788837 0.999999 0.000838796 0.000763877 0.999999 0.000957913 -0.0252958 0.99923 -0.0299972 -0.0243532 0.999444 -0.0227901 -0.0208216 0.999702 -0.0127539 -0.00951975 0.999907 -0.00974648 -0.00583378 0.999929 -0.0104434 -0.00794172 0.999925 -0.00936683 -0.00240065 0.999986 -0.00461335 -0.00107761 0.999991 -0.00421847 0.00647458 0.999972 0.00370383 0.00536481 0.99998 0.00338201 -0.00486603 0.999982 0.00342825 -0.00661568 0.999927 0.0101225 -0.00510939 0.999979 -0.00396825 -0.613245 0.182269 -0.768576 -0.610593 0.19141 -0.768465 -0.590231 0.136491 -0.795612 -0.559431 0.140018 -0.816965 -0.560888 0.1549 -0.813271 0.00305809 0.999994 0.00140274 0.00481315 0.999988 0.00131841 0.00512577 0.999986 0.00101193 0.000857961 0.999994 -0.00322154 -0.00184058 0.999992 -0.00362673 -0.0265203 0.99923 -0.0289134 -0.0670513 0.99648 -0.0503204 -0.434244 0.660427 -0.612591 -0.316194 0.707014 -0.632576 -0.168314 0.712374 -0.681318 -0.193893 0.70295 -0.6843 -0.111152 0.718999 -0.686065 -0.800088 0.431646 -0.416584 -0.769333 0.480886 -0.420565 -0.750266 0.486894 -0.447253 -0.723659 0.51998 -0.453804 -0.611576 0.599835 -0.515919 -0.645289 0.56801 -0.510849 -0.488709 0.661496 -0.568847 0.0493329 0.750039 -0.659552 0.0361153 0.749377 -0.661158 -0.0851688 0.791607 -0.605065 -0.0814399 0.792618 -0.604255 -0.243395 0.82468 -0.51055 -0.634396 0.173838 -0.753207 -0.655818 0.167799 -0.736034 -0.660028 0.267008 -0.70219 -0.677265 0.230029 -0.698855 -0.736675 0.188816 -0.649352 -0.704753 0.303684 -0.64117 -0.7925 0.233305 -0.563483 -0.74621 0.372721 -0.551588 -0.724272 0.462045 -0.511805 -0.658568 0.503635 -0.559142 -0.676644 0.436652 -0.592864 -0.616376 0.463431 -0.636641 -0.627452 0.40404 -0.665624 -0.572376 0.418872 -0.704934 -0.577613 0.375175 -0.724988 -0.529689 0.380873 -0.757869 -0.528345 0.398301 -0.749805 -0.24493 0.926868 -0.284473 -0.186857 0.952951 -0.238682 -0.201372 0.952366 -0.229014 -0.202651 0.951901 -0.22982 -0.22477 0.950371 -0.215112 -0.250374 0.940707 -0.228875 -0.269292 0.938516 -0.21603 -0.313528 0.919916 -0.235489 -0.347901 0.913458 -0.211092 -0.608129 0.682347 -0.405686 -0.665943 0.649397 -0.367155 -0.790647 0.423716 -0.441975 -0.761901 0.473223 -0.442229 0.0486496 0.74489 -0.665411 0.0488326 0.744963 -0.665316 -0.106166 0.773705 -0.624587 -0.0967917 0.777349 -0.621579 -0.315494 0.782186 -0.53726 -0.242941 0.816212 -0.524193 -0.417423 0.805911 -0.41984 -0.361488 0.826987 -0.430602 -0.491822 0.801355 -0.340501 -0.406365 0.846702 -0.343458 -0.494496 0.823034 -0.279444 -0.423414 0.861153 -0.281313 -0.450064 0.853773 -0.261751 -0.221858 0.966959 -0.125574 -0.19909 0.97264 -0.119729 -0.799718 0.312107 -0.512874 -0.811045 0.431006 -0.395525 -0.700995 0.527847 -0.479567 -0.611215 0.67558 -0.41232 -0.545733 0.703673 -0.454993 -0.560214 0.68867 -0.460319 -0.495169 0.70869 -0.50256 -0.51128 0.691969 -0.509679 -0.451119 0.703798 -0.548781 -0.467004 0.686891 -0.556856 -0.434601 0.690279 -0.578479 -0.414358 0.715689 -0.562226 -0.0733055 0.990701 -0.114623 -0.21764 0.969613 -0.111725 -0.163008 0.968433 -0.188589 -0.224707 0.957309 -0.181839 -0.163842 0.949663 -0.267013 -0.291425 0.9129 -0.285805 -0.218614 0.903715 -0.368112 -0.258203 0.89409 -0.36597 -0.165171 0.870206 -0.464177 -0.19046 0.864736 -0.464711 -0.0628847 0.809663 -0.583516 -0.0652197 0.809312 -0.583746 0.025229 0.755178 -0.655034 0.0408287 0.753818 -0.655814 0.0333591 0.735048 -0.677194 0.0488151 0.738056 -0.672972 -0.152892 0.745016 -0.649289 -0.117628 0.756899 -0.642859 -0.397227 0.71711 -0.572682 -0.351949 0.740826 -0.572109 -0.566749 0.666629 -0.48415 -0.523637 0.697011 -0.489878 -0.673787 0.616707 -0.407041 -0.627698 0.662189 -0.409269 -0.697613 0.616395 -0.365231 -0.670468 0.644873 -0.366895 -0.667076 0.647128 -0.369099 -0.419073 0.88097 -0.219705 -0.37383 0.892298 -0.253092 -0.121049 0.990361 -0.0673183 -0.10225 0.990757 -0.0891418 -0.0423517 0.998433 -0.0365664 -0.706193 0.689917 -0.15908 -0.706285 0.68982 -0.15909 -0.707094 0.68512 -0.17501 -0.707087 0.685127 -0.175012 -0.718894 0.675338 -0.164652 -0.707068 0.582268 -0.401272 -0.707115 0.682238 -0.185848 -0.707108 0.682246 -0.185846 -0.709918 0.677881 -0.191036 -0.712446 0.674603 -0.193213 -0.712402 0.674659 -0.193181 -0.719859 0.665369 -0.197703 -0.789819 0.580047 -0.199326 -0.665841 0.699018 -0.260824 -0.709847 0.647416 -0.277435 -0.699144 0.649716 -0.298442 -0.789311 0.545755 -0.28132 -0.504643 0.748711 -0.429846 -0.654613 0.645036 -0.394222 -0.734433 0.563696 -0.377962 -0.706686 0.555343 -0.438394 -0.706765 0.555276 -0.43835 -0.706999 0.52333 -0.475687 -0.609511 0.574206 -0.546611 -0.707021 0.501745 -0.49837 -0.706417 0.458037 -0.539608 -0.708927 0.456291 -0.537794 -0.706307 0.414227 -0.574061 -0.707054 0.41367 -0.573543 -0.706855 0.380946 -0.596018 -0.719066 0.3733 -0.586166 -0.703155 0.351898 -0.617851 -0.707083 0.348967 -0.615025 -0.706779 0.314979 -0.633444 -0.679238 0.328705 -0.656193 -0.723792 0.26366 -0.637659 -0.706956 0.272217 -0.652772 -0.706942 0.232481 -0.667971 -0.692176 0.23555 -0.682209 -0.71439 0.196314 -0.671645 -0.670502 0.197855 -0.715039 -0.707081 0.176917 -0.684643 -0.706886 -0.266008 -0.655403 -0.651697 -0.258491 -0.713073 -0.787831 -0.151926 -0.596859 -0.706521 -0.152819 -0.690996 -0.706743 -0.0810224 -0.702815 -0.794098 -0.046975 -0.605972 -0.706915 -0.026633 -0.706797 -0.706641 0.0329202 -0.706806 -0.756455 0.0378132 -0.652952 -0.707087 0.0734666 -0.7033 -0.70633 0.127088 -0.696381 -0.706468 0.127053 -0.696248 -0.70711 -0.593027 0.385116 -0.707109 -0.593028 0.385117 -0.706517 -0.520628 -0.479355 -0.860973 -0.446067 -0.244439 -0.859864 -0.389872 -0.329597 -0.706793 -0.565772 -0.424671 -0.706561 -0.604818 -0.367378 -0.862069 -0.504246 -0.0507255 -0.706758 -0.638375 -0.304911 -0.706603 -0.665298 -0.241019 -0.861706 -0.484629 -0.150327 -0.706722 -0.685966 -0.173189 -0.706645 -0.6997 -0.10523 -0.706682 -0.706682 -0.0346661 -0.706682 -0.706682 0.0346661 -0.862069 -0.504246 0.0507255 -0.706645 -0.6997 0.10523 -0.706722 -0.685966 0.173189 -0.861706 -0.484629 0.150327 -0.706603 -0.665298 0.24102 -0.706758 -0.638375 0.304911 -0.860972 -0.446068 0.244439 -0.706517 -0.520628 0.479354 -0.859863 -0.389873 0.329597 -0.706792 -0.565773 0.424672 -0.70656 -0.604819 0.367378 -0.707111 -0.593027 -0.385116 -0.707109 -0.593028 -0.385117 -0.666847 -0.0575942 0.742966 -0.733594 0.0424539 0.678261 -0.706545 0.0409133 0.706484 -0.707035 0.0950795 0.700758 -0.798714 0.108027 0.591934 -0.706806 0.139864 0.693443 -0.740433 -0.171076 0.649994 -0.707094 -0.11763 0.697267 -0.705712 -0.0506233 0.706688 -0.70526 -0.174882 0.687041 -0.706905 -0.266 0.655385 -0.706886 -0.266017 0.655399 -0.707085 0.176918 0.684639 -0.790459 0.183822 0.584282 -0.695257 0.224339 0.682855 -0.716689 0.278399 0.639414 -0.706771 0.281665 0.648953 -0.707065 0.319286 0.630964 -0.701562 0.322846 0.63528 -0.710716 0.334702 0.618755 -0.755538 0.325345 0.568607 -0.706982 0.35756 0.610186 -0.707056 0.382344 0.594882 -0.673709 0.405713 0.617668 -0.707089 0.397396 0.584895 -0.707106 0.404095 0.580265 -0.720663 0.423114 0.549198 -0.618468 0.48552 0.617874 -0.74738 0.450447 0.488385 -0.706953 0.475122 0.523905 -0.706773 0.512397 0.487772 -0.7067 0.512445 0.487827 -0.707047 0.543859 0.451997 -0.598873 0.628588 0.496214 -0.706993 0.565099 0.425234 -0.706212 0.604375 0.368776 -0.712428 0.674626 0.193198 -0.709917 0.677881 0.191036 -0.707108 0.682245 0.185847 -0.707114 0.68224 0.185848 -0.706063 0.604496 0.368862 -0.706956 0.639498 0.302086 -0.706917 0.63953 0.302109 -0.706869 0.65908 0.256806 -0.738371 0.63019 0.240142 -0.700626 0.677701 0.223258 -0.722549 0.662417 0.197804 -0.719859 0.665369 0.197703 -0.712424 0.674632 0.193194 -0.707092 0.685122 0.17501 -0.706241 0.68987 0.159071 -0.718894 0.675338 0.164652 -0.707087 0.685127 0.175011 -0.706063 0.703841 0.0779915 -0.707967 0.705684 0.0281513 -0.869553 0.493831 0.00300531 -0.709719 0.693361 -0.124701 -0.870112 0.487908 -0.0696401 -0.705977 0.704386 -0.0737296 -0.707726 0.706083 -0.0238806 -0.709766 0.693314 0.124693 -0.822241 0.563842 0.0774681 -0.753966 0.650084 0.0944789 -0.644804 0.764333 0.00465151 -0.734343 0.678779 0 -0.673435 0.731829 -0.104456 -0.711736 0.695144 -0.101028 0.546018 -0.000206687 -0.837773 0.58003 -0.00110355 -0.814595 0.425068 -0.100356 -0.899581 0.12272 -0.414183 -0.901882 0.199817 -0.485853 -0.850894 0.1271 -0.389776 -0.912097 0.474939 -0.168114 -0.863811 0.422 -0.216776 -0.880298 0.356418 -0.165584 -0.919537 0.450124 -0.0970279 -0.887679 0.492386 -0.017763 -0.870195 0.492517 -0.0185729 -0.870105 0.582043 -0.00351431 -0.81315 0.571674 0.0237486 -0.820137 0.564695 0.118988 -0.816677 0.53491 -0.0568735 -0.842993 0.477527 0.01667 -0.878459 0.551062 0.0113313 -0.834387 0.550002 0.00013018 -0.835164 0.54735 0.00320412 -0.836898 0.552951 -0.00510289 -0.833198 0.555035 -0.00952391 -0.831772 0.556382 -0.0125051 -0.830833 0.558929 -0.0221932 -0.828918 0.560936 -0.0383993 -0.826968 0.571985 0.0239524 -0.819914 0.561902 -0.0528867 -0.825512 0.561613 -0.0461698 -0.826111 0.562349 -0.0163804 -0.826738 0.56847 -0.0119328 -0.822618 0.576056 -0.0369076 -0.816576 0.542194 -0.0462784 -0.838978 0.491421 -0.0874159 -0.866524 0.508002 -0.102448 -0.855242 0.424672 -0.111191 -0.898493 0.470906 -0.163336 -0.86693 0.115674 -0.382784 -0.916567 0.289792 -0.396427 -0.871129 0.223926 -0.367158 -0.902802 0.367991 -0.33789 -0.866264 0.287374 -0.335553 -0.897118 0.413709 -0.325861 -0.850094 0.408323 -0.323904 -0.853439 0.478611 -0.215257 -0.851232 0.471438 -0.216143 -0.855002 0.506465 -0.113356 -0.854777 0.510326 -0.111651 -0.852702 0 -1 0 0 -1 0 0 -1 0 0.236164 -0.628183 0.741359 0.214495 -0.603855 0.767692 0.49253 -0.582059 0.64701 0.493048 -0.582931 0.645829 0.348343 -0.632575 0.691741 0.295694 -0.635694 0.713063 0.0238274 -0.698031 0.715671 0.0327637 -0.687795 0.725165 0.0339482 -0.699551 0.713776 0.051054 -0.679121 0.732249 0.053708 -0.673234 0.737477 0.0692423 -0.709463 0.701332 0.177048 -0.692416 0.699438 0.224573 -0.696111 0.681906 0.320301 -0.64282 0.695838 0.50667 -0.55724 0.657851 0.457405 -0.607536 0.649369 0.705318 -0.40381 0.582636 0.71411 -0.424809 0.556403 0.629722 -0.456885 0.628257 0.787329 -0.373014 0.490891 0.781868 -0.396083 0.481457 0.85127 -0.248314 0.462254 0.782444 -0.341221 0.520912 0.781766 -0.341507 0.521742 0.778402 -0.343435 0.525492 0.776452 -0.344783 0.527492 0.77265 -0.347432 0.531322 0.767995 -0.351625 0.535298 0.842271 -0.255556 0.474627 0.859586 -0.230757 0.455921 0.859006 -0.239917 0.452271 0.80211 -0.0850088 0.591094 0.797561 -0.0144686 0.603065 0.775085 -0.112676 0.621729 0.76103 -0.103563 0.640396 0.812319 -0.146202 0.564591 0.819919 -0.160741 0.549451 0.842189 -0.146718 0.518836 0.843122 -0.0997644 0.528387 0.839238 -0.251801 0.48195 0.864778 -0.118524 0.487966 0.85697 -0.187939 0.479876 0.701554 -0.0923637 0.706606 0.707968 -0.0972495 0.699517 0.711067 -0.098356 0.696211 0.716742 -0.0995967 0.690189 0.733207 -0.101153 0.67244 0.745007 -0.0979919 0.65982 0.749389 -0.0960305 0.65513 0.751377 -0.0947557 0.653035 0.720222 -0.117652 0.683694 0.63989 -0.0606187 0.766072 0.680385 -0.0368402 0.731928 0.652459 -0.0881752 0.752676 0.693843 -0.0832289 0.715301 0.597254 -0.0112296 0.801974 0.600881 -0.008614 0.799292 0.595772 -0.0144856 0.803023 0.614414 -0.0393961 0.788 0.620649 -0.0449563 0.782799 0.596532 -0.0117293 0.802503 0.548575 -0.042765 0.835007 0.570887 -0.00110884 0.821028 0.755479 -0.127284 0.64269 0.770857 -0.12645 0.624332 0.756413 -0.132287 0.640577 0.78218 -0.206021 0.588005 0.758611 -0.340403 0.555549 0.776729 -0.369255 0.510238 0.828843 -0.311618 0.464664 0.808482 -0.294906 0.5093 0.816602 -0.289396 0.499412 0.808176 -0.196808 0.555084 0.772401 -0.215795 0.597352 0.619694 -0.518269 0.589387 0.678072 -0.469261 0.565697 0.676315 -0.471248 0.566148 0.774843 -0.411611 0.479786 0.848549 -0.29325 0.44042 0.845246 -0.288976 0.449502 0.788941 -0.367878 0.492177 0.788901 -0.378227 0.484333 0.677211 -0.468575 0.567294 0.683481 -0.473872 0.555247 0.493523 -0.581498 0.646757 0.497251 -0.584602 0.641079 0.228282 -0.669216 0.707133 0.23127 -0.671466 0.704023 0.0322895 -0.693057 0.720159 0.0359656 -0.719174 0.693899 0.01537 -0.717061 0.696842 0.10678 0.980726 0.163632 0.544143 0.147995 0.825837 0.532508 0.195864 0.823452 0.079383 0.989738 0.118816 0.0878886 0.9844 0.152423 0.17825 0.945911 0.27107 0.308262 0.831365 0.462392 0.299625 0.838464 0.455194 0.458749 0.555963 0.693148 0.458587 0.556228 0.693043 0.520225 0.32925 0.78801 0.106541 0.980812 -0.163267 0.11075 0.979927 -0.165763 0.0682747 0.989636 -0.126333 0.544141 0.147995 -0.825838 0.532394 0.196303 -0.823421 0.520195 0.32927 -0.788022 0.458531 0.556623 -0.692763 0.45858 0.556228 -0.693047 0.305312 0.831804 -0.463559 0.302105 0.83848 -0.453525 0.178279 0.945911 -0.271051 0.10964 -0.980699 -0.161888 0.0898236 -0.987965 -0.125926 0.101924 -0.982546 -0.155614 0.189612 -0.943011 -0.273456 0.319121 -0.831081 -0.455484 0.308202 -0.840981 -0.444706 0.475351 -0.555384 -0.682342 0.474305 -0.557358 -0.68146 0.559579 -0.195103 -0.805485 0.55904 -0.197403 -0.805299 0.730753 -0.449384 0.513862 0.729034 -0.446205 0.519047 0.732942 -0.450897 0.5094 0.734119 -0.451661 0.507023 0.736522 -0.452398 0.502863 0.340633 -0.906664 0.248857 0.339439 -0.907213 0.248488 0.664101 -0.522144 0.535103 0.72859 -0.445341 0.520411 0.526663 -0.744623 0.410078 0.575051 -0.705124 0.414869 0.450763 -0.827306 0.335227 0.100622 -0.989825 0.100605 0.111746 -0.989876 0.0875099 0.122374 -0.988311 0.0909188 0.52917 -0.621583 0.577594 0.621558 -0.521777 0.584307 0.407197 -0.799855 0.440933 0.483006 -0.744349 0.46114 0.330447 -0.881697 0.336773 0.289602 -0.906643 0.306804 0.252449 -0.935434 0.247452 0.0852154 -0.992047 0.0926382 0.899802 -0.436299 -0.000318353 0.807859 -0.589211 -0.0139153 0.842207 -0.539134 -0.00468553 0.963342 -0.268275 0.000292615 0.984409 -0.175792 -0.00606433 0.995906 -0.0904001 0 0.738438 -0.674322 -0.00037111 0.654088 -0.756418 0.00104124 0.539116 -0.842179 -0.00942904 0.488888 -0.872341 -0.00305745 0.175793 -0.984415 0.00479974 0.302037 -0.953131 -0.0177234 0.101797 -0.994805 0 0.188355 -0.468893 -0.862938 0.188143 -0.704465 -0.684348 0.187563 -0.88237 -0.431559 0.983589 -0.13555 -0.119073 0.982625 -0.183786 -0.0259032 0.983965 -0.175713 -0.0306134 0.836224 -0.543918 -0.069876 0.839905 -0.53766 -0.074043 0.548417 -0.827796 -0.11829 0.535855 -0.837084 -0.110227 0.18842 -0.933573 -0.304859 0.186925 -0.971814 -0.143653 0.174128 -0.975089 -0.137411 0.233262 -0.888203 -0.395834 0.548355 -0.763827 -0.340405 0.548347 -0.763829 -0.340412 0.836703 -0.500228 -0.222934 0.836697 -0.500233 -0.222945 0.981241 -0.176086 -0.0784786 0.982834 -0.172342 -0.0658525 0.297488 -0.770449 -0.563835 0.186772 -0.752796 -0.631201 0.54837 -0.640791 -0.537287 0.548342 -0.640791 -0.537315 0.836715 -0.419636 -0.351873 0.836693 -0.419643 -0.351915 0.982627 -0.142205 -0.119254 0.982907 -0.16114 -0.0890442 0.982725 -0.0998818 -0.155805 0.981827 -0.106107 -0.157347 0.836666 -0.306228 -0.454109 0.836645 -0.306268 -0.45412 0.548295 -0.467603 -0.69334 0.548267 -0.46763 -0.693344 0.241038 -0.542677 -0.804613 0.18771 -0.585667 -0.788517 0.983299 -0.0840636 -0.161419 0.997099 -0.0387663 -0.0655016 0.976659 -0.134049 -0.167831 0.976363 -0.134176 -0.169449 0.952586 -0.160443 -0.258531 0.914923 -0.215906 -0.341028 0.835235 -0.310773 -0.453654 0.852123 -0.307996 -0.423113 0.763117 -0.350071 -0.543234 0.767501 -0.37229 -0.521865 0.395492 -0.539929 -0.74301 0.395609 -0.654928 -0.643865 0.556985 -0.503576 -0.660438 0.548898 -0.496569 -0.672407 0.548711 -0.452857 -0.702735 0.54871 -0.452857 -0.702736 0.982938 -0.0857092 -0.16275 0.838901 -0.258958 -0.478734 0.835594 -0.258923 -0.484502 0.551756 -0.395655 -0.734182 0.548695 -0.395088 -0.736776 0.0850672 -0.664401 -0.742519 0.187349 -0.658607 -0.728791 0.187413 -0.599482 -0.778137 0.177968 -0.596657 -0.782514 0.197746 -0.535014 -0.821375 0.187229 -0.532108 -0.825716 0.187227 -0.464813 -0.865387 0.188389 -0.465171 -0.864943 0.768568 -0.465491 0.438886 0.779576 -0.338364 0.52704 0.0320615 -0.679337 0.733126 0.981887 -0.0964991 0.16305 0.835615 -0.259906 0.483938 0.835615 -0.259906 0.483938 0.982989 -0.0869005 0.161806 0.982278 -0.0865726 0.166237 0.212849 -0.472519 0.855231 0.18722 -0.464779 0.865407 0.986481 -0.109963 0.121506 0.937541 -0.180059 0.29765 0.835242 -0.310551 0.453794 0.816051 -0.313029 0.485874 0.548713 -0.452776 0.702785 0.548233 -0.522923 0.652681 0.52289 -0.516714 0.677933 0.527162 -0.512003 0.678199 0.149971 -0.671754 0.725435 0.14403 -0.680668 0.718294 0.0555736 -0.678826 0.732193 0.187493 -0.63925 0.745792 0.187114 -0.573708 0.797401 0.284608 -0.581118 0.762431 0.169303 -0.533774 0.828506 0.548712 -0.452778 0.702786 0.548708 -0.395557 0.736515 0.548709 -0.395557 0.736515 0.175521 -0.98289 0.0558515 0.187463 -0.771574 0.607891 0.982836 -0.134687 0.126064 0.278883 -0.941709 0.188172 0.982621 -0.103771 0.153909 0.982011 -0.103468 0.157954 0.836828 -0.308361 0.452364 0.833418 -0.307663 0.459083 0.548375 -0.468912 0.692392 0.545272 -0.46814 0.695358 0.186756 -0.549867 0.814106 0.185586 -0.549455 0.814651 0.982905 -0.150587 0.105929 0.981243 -0.147712 0.123872 0.836702 -0.419633 0.351907 0.836723 -0.419626 0.351864 0.548347 -0.640789 0.537313 0.548375 -0.640788 0.537285 0.228566 -0.745995 0.625498 0.188455 -0.679744 0.708825 0.983605 -0.166385 0.0695573 0.982629 -0.169507 0.0755462 0.836707 -0.50022 0.22294 0.836712 -0.500215 0.222929 0.548352 -0.763826 0.340412 0.54836 -0.763824 0.340404 0.246827 -0.885139 0.394469 0.188188 -0.863692 0.46757 0.984218 -0.175758 0.0205976 0.982162 -0.185354 0.0316626 0.840194 -0.537845 0.0692537 0.836576 -0.54272 0.0748007 0.535271 -0.836171 0.119598 0.54777 -0.829546 0.10863 0.186928 -0.971813 0.143654 0.187999 -0.920246 0.343225 0.101798 -0.994805 0 0.995906 -0.0904001 0 0.984409 -0.175792 0.00606433 0.963342 -0.268275 -0.000292615 0.899802 -0.436299 0.000318353 0.842214 -0.539138 0.00240328 0.742985 -0.668664 0.0293699 0.807859 -0.589211 0.0139153 0.175792 -0.984406 0.00650494 0.301571 -0.953442 -0.00176697 0.539135 -0.842208 0.00442559 0.489978 -0.87163 0.0135649 0.654093 -0.756414 -0.00104162 0.186084 -0.0593809 -0.980738 0.133271 -0.337762 -0.931749 0.258684 -0.365183 -0.894273 0.523165 -0.291735 -0.800743 0.707042 -0.276912 -0.650701 0.965503 -0.0789636 -0.24813 0.990277 -0.0174437 -0.138013 0.993684 -0.00772685 -0.111947 0.994847 0.00259917 -0.101359 0.980776 0.0307543 -0.192699 0.991956 0.0174678 -0.125373 0.993511 0.0104176 -0.113255 0.993674 -0.0208707 -0.110346 0.992795 -0.0646753 -0.100876 0.919733 -0.115959 -0.375028 0.83979 -0.16521 -0.517164 0.757205 -0.16723 -0.631406 0.522937 -0.218229 -0.823962 0.523055 -0.218245 -0.823883 0.221738 -0.249692 -0.942595 0.185971 -0.238054 -0.953281 0.920233 0.046924 -0.388547 0.756903 0.0970307 -0.646284 0.831068 0.0693031 -0.551837 0.523042 0.114847 -0.844534 0.555071 0.107931 -0.824771 0.246465 0.12761 -0.960714 0.194926 0.135732 -0.971381 0.989925 -0.0175305 -0.140503 0.919765 -0.0485913 -0.38945 0.919903 -0.0485937 -0.389124 0.756371 -0.0810596 -0.649101 0.756679 -0.0810574 -0.648742 0.522077 -0.105744 -0.846318 0.522432 -0.105766 -0.846096 0.185406 -0.121888 -0.975073 0.285855 -0.131645 -0.949187 0.993659 0.00202565 -0.112418 0.919994 0.00706104 -0.391869 0.920111 0.00702377 -0.391594 0.756891 0.0117202 -0.653436 0.757155 0.0116825 -0.653131 0.522684 0.0152466 -0.85239 0.522997 0.0152044 -0.852199 0.185701 0.0175282 -0.98245 0.106283 0.0267079 -0.993977 -0.208569 -0.892998 -0.398815 -0.432024 -0.208902 -0.877334 -0.293467 -0.540477 -0.788519 -0.435166 -0.562659 -0.702884 -0.215921 -0.89341 -0.39395 -0.494572 -0.206008 -0.844369 -0.0622371 -0.982528 -0.175402 -0.061641 -0.982757 -0.174325 -0.0687316 -0.982849 -0.171122 -0.077824 -0.979635 -0.185093 -0.0741165 -0.983638 -0.164202 -0.0780421 -0.983087 -0.165678 -0.0796016 -0.98313 -0.164678 -0.0796132 -0.983116 -0.164757 -0.0792436 -0.983159 -0.164677 -0.437578 -0.56273 -0.701327 -0.529999 -0.197255 -0.824737 -0.529719 -0.195942 -0.82523 -0.526627 -0.212111 -0.823209 -0.540959 -0.212218 -0.813835 -0.541246 -0.21167 -0.813786 -0.540387 -0.211573 -0.814382 -0.550689 -0.185602 -0.813814 -0.538422 -0.202897 -0.817885 -0.440511 -0.540637 -0.716702 -0.443336 -0.555891 -0.703163 -0.0420578 -0.996219 -0.0760229 -0.0408788 -0.996205 -0.076844 -0.0416429 -0.996091 -0.0778957 -0.0367091 -0.996548 -0.074467 -0.0405709 -0.995958 -0.0801316 -0.198605 -0.962633 -0.184101 -0.124518 -0.963735 -0.23603 -0.124618 -0.963652 -0.236316 -0.129239 -0.96383 -0.233086 -0.51291 -0.206157 -0.83332 -0.525437 -0.197538 -0.827584 -0.447728 -0.478779 -0.755189 -0.463284 -0.479261 -0.745438 -0.411867 -0.564864 -0.715048 -0.435083 -0.565885 -0.70034 -0.315664 -0.784385 -0.533944 -0.31964 -0.784551 -0.531329 -0.275305 -0.830734 -0.483827 -0.35796 -0.193889 -0.913385 -0.431213 -0.177164 -0.884686 -0.372256 -0.467311 -0.801901 -0.42044 -0.468377 -0.77708 -0.354277 -0.641186 -0.680712 -0.377897 -0.64222 -0.666894 -0.474272 -0.193473 -0.858857 -0.492103 -0.173373 -0.853098 -0.419171 -0.474455 -0.774073 -0.448481 -0.47529 -0.756944 -0.377269 -0.644186 -0.665352 -0.390536 -0.644819 -0.657032 -0.306519 -0.785413 -0.537748 -0.315023 -0.785872 -0.532134 -0.223531 -0.892926 -0.390791 -0.230688 -0.893203 -0.385967 -0.187593 -0.834929 -0.5174 -0.186951 -0.837688 -0.513155 -0.214017 -0.838365 -0.50134 -0.213676 -0.839428 -0.499704 -0.237837 -0.84047 -0.486871 -0.102228 -0.980704 -0.16664 -0.0732754 -0.984461 -0.159588 -0.132458 -0.963717 -0.231742 -0.129483 -0.963627 -0.233787 -0.223078 -0.8936 -0.389507 -0.216044 -0.893231 -0.394289 -0.306418 -0.785639 -0.537475 -0.317996 -0.786168 -0.529924 -0.25202 -0.842133 -0.476758 -0.237522 -0.841333 -0.485532 -0.355371 -0.637667 -0.683441 -0.315812 -0.636308 -0.703829 -0.355812 -0.550124 -0.755487 -0.293085 -0.549269 -0.782563 -0.354533 -0.154411 -0.922206 -0.332821 -0.169587 -0.927615 0.830359 0.048988 -0.555072 0.169052 0.171044 -0.970652 0.187005 0.151662 -0.970581 0.181961 0.138321 -0.973529 0.978301 -0.0349585 -0.204218 0.982059 -0.073343 -0.173727 0.957111 -0.20879 -0.200859 0.480775 -0.142611 -0.865169 0.717557 -0.394293 -0.574147 0.719401 -0.37616 -0.583923 0.806821 -0.560367 -0.187161 0.819429 -0.533398 -0.209815 0.895684 -0.406479 -0.180349 0.78538 -0.239255 -0.570908 0.787186 -0.263379 -0.557646 0.521953 -0.0552972 -0.85118 0.551742 -0.141596 -0.821907 0.161175 0.128434 -0.978533 0.165473 0.122115 -0.978625 0.904007 -0.375108 -0.205095 0.95457 -0.240567 -0.175851 0.833696 -0.107935 -0.541573 0.881876 -0.0770131 -0.465148 0.566143 0.0666961 -0.821604 0.55357 0.0657485 -0.830204 0.195055 0.157264 -0.968102 -0.306524 -0.169538 -0.936643 -0.0464092 -0.980739 -0.189729 -0.0285657 -0.980687 -0.193487 -0.242016 -0.0920616 -0.965895 -0.265253 -0.0142107 -0.964074 -0.23589 -0.539908 -0.807995 -0.233937 -0.491764 -0.838714 -0.154044 -0.834518 -0.529009 -0.155963 -0.816857 -0.555355 -0.0521829 -0.982472 -0.178956 -0.0486296 -0.987155 -0.152184 -0.0311778 -0.978855 -0.202165 -0.0862237 -0.798832 -0.595343 -0.0880836 -0.817034 -0.569821 -0.126804 -0.442294 -0.887861 -0.13365 -0.491981 -0.860287 -0.139609 -0.0138336 -0.99011 -0.153381 -0.0919948 -0.983876 0.756281 -0.622129 -0.202472 0.152592 0.107528 -0.982422 0.736861 -0.645285 -0.201602 0.67419 -0.446575 -0.588251 0.652953 -0.476343 -0.588855 0.453817 -0.173995 -0.873942 0.435374 -0.204671 -0.876675 0.16125 0.114705 -0.980225 0.153471 0.103437 -0.982725 0.672284 -0.714714 -0.192919 0.658337 -0.719909 -0.219823 0.59997 -0.540687 -0.589655 0.587337 -0.540394 -0.602502 0.397309 -0.245566 -0.884219 0.395785 -0.245232 -0.884995 0.12352 0.0873512 -0.98849 0.134812 0.0836814 -0.987331 0.499995 -0.841915 -0.20294 0.488851 -0.84416 -0.220041 0.440757 -0.663757 -0.604285 0.428653 -0.661585 -0.615274 0.284328 -0.335046 -0.898277 0.275391 -0.331318 -0.902435 0.0768603 0.048742 -0.99585 0.0722687 0.051373 -0.996061 0.300359 -0.930038 -0.21169 0.296987 -0.930141 -0.215954 0.251812 -0.748984 -0.612874 0.247349 -0.747451 -0.616551 0.147382 -0.399409 -0.904849 0.142504 -0.39632 -0.906986 0.0173921 0.0170173 -0.999704 0.0128182 0.0209933 -0.999697 0.083751 -0.973796 -0.211442 0.0869969 -0.974281 -0.207864 0.0494807 -0.794968 -0.604631 0.0439136 -0.791905 -0.609064 -0.000377385 -0.44136 -0.89733 -0.0103561 -0.431954 -0.901836 -0.0486569 -0.0138401 -0.99872 -0.0597092 0.00107003 -0.998215 -0.348571 -0.168358 0.922038 -0.0778502 -0.983023 0.166147 -0.528553 -0.197381 0.825635 -0.529133 -0.197578 0.825216 -0.442519 -0.559188 0.70106 -0.44126 -0.552545 0.707095 -0.274662 -0.842577 0.463277 -0.284756 -0.834511 0.471705 -0.0953516 -0.98134 0.166971 -0.0882057 -0.983198 0.159818 -0.0854146 -0.983128 0.161752 -0.0837926 -0.983407 0.160901 -0.0640384 -0.981843 0.178557 -0.0623317 -0.982509 0.175474 -0.068363 -0.983099 0.169831 -0.0688656 -0.982934 0.170583 -0.0780141 -0.982933 0.166604 -0.53124 -0.19452 0.824588 -0.538265 -0.206571 0.817068 -0.431896 -0.562663 0.704894 -0.43135 -0.562645 0.705243 -0.264614 -0.842108 0.469928 -0.190813 -0.831508 0.521713 -0.185681 -0.837677 0.513634 -0.214785 -0.838414 0.500929 -0.213734 -0.839475 0.4996 -0.245874 -0.840729 0.482412 -0.244513 -0.842094 0.480718 -0.263967 -0.843318 0.468119 -0.0837625 -0.983217 0.162074 -0.0810377 -0.983993 0.158716 -0.355249 -0.142755 0.923807 -0.424103 -0.230347 0.875829 -0.423923 -0.133715 0.895773 -0.479165 -0.246161 0.8425 -0.481898 -0.176976 0.858169 -0.520851 -0.223487 0.823873 -0.520442 -0.236137 0.820597 -0.296396 -0.537302 0.789592 -0.291121 -0.549244 0.783313 -0.346738 -0.550208 0.759634 -0.343818 -0.555552 0.757067 -0.387849 -0.556861 0.734492 -0.418569 -0.506632 0.75374 -0.412843 -0.565183 0.714233 -0.429304 -0.565839 0.703935 -0.544467 -0.206158 0.813053 -0.544502 -0.200218 0.814513 -0.24213 -0.0909349 0.965973 -0.153475 -0.0908678 0.983966 -0.139749 -0.0124867 0.990108 -0.134011 -0.488611 0.862149 -0.12717 -0.438518 0.889679 -0.0889375 -0.813282 0.575033 -0.0870681 -0.794658 0.600781 -0.0305475 -0.979946 0.196909 -0.0304692 -0.978034 0.206208 -0.054461 -0.979913 0.191845 -0.0532384 -0.981787 0.182375 -0.157451 -0.813108 0.560415 -0.15553 -0.831099 0.533934 -0.234557 -0.488402 0.840504 -0.236528 -0.536754 0.809907 -0.265393 -0.0127245 0.964056 -0.306548 -0.168343 0.936851 0.126388 0.0747699 0.989159 0.672691 -0.707443 0.216822 0.658237 -0.726962 0.195577 0.595959 -0.532511 0.601054 0.591376 -0.54786 0.591713 0.396531 -0.244477 0.88487 0.396498 -0.246173 0.884414 0.140807 0.0675707 0.987728 0.500003 -0.837928 0.218801 0.488925 -0.848145 0.203966 0.437934 -0.656089 0.614623 0.431407 -0.668727 0.605551 0.280812 -0.327748 0.902067 0.278568 -0.337746 0.89907 0.0700641 0.0611167 0.995669 0.0564611 0.00916057 0.998363 0.300197 -0.929137 0.215836 0.297155 -0.931063 0.211709 0.251051 -0.746201 0.616569 0.248077 -0.750082 0.613054 0.146056 -0.394911 0.907035 0.143686 -0.400301 0.905049 0.0126987 0.0322442 0.999399 -0.0427537 -0.0169575 0.998942 -0.0940461 -0.0125024 0.995489 -0.0500506 -0.00782855 0.998716 -0.00876306 -0.437871 0.898995 -0.00398437 -0.430856 0.902412 0.0460966 -0.79106 0.61 0.0453836 -0.791727 0.609186 0.089514 -0.97233 0.21578 0.0841084 -0.97456 0.207747 0.125407 -0.0206996 0.991889 0.125428 -0.189496 0.973837 0.706879 -0.265931 0.65544 0.415903 -0.315099 0.853075 0.258723 -0.369862 0.892336 0.980753 0.027124 0.193359 0.983703 0.0235345 0.178253 0.983736 0.00878026 0.179405 0.978002 0.00375114 0.208562 0.983711 -0.00247474 0.17974 0.98366 -0.0206506 0.178847 0.981311 -0.0238331 0.190948 0.983713 -0.0357819 0.176149 0.983629 -0.0504651 0.172993 0.962517 -0.092791 0.254855 0.965893 -0.0991817 0.239195 0.195076 0.163957 0.966987 0.667741 0.0957646 0.738208 0.555206 0.114121 0.823846 0.416002 0.115009 0.902062 0.304461 -0.102878 0.946953 0.1251 -0.123077 0.984481 0.414973 -0.112867 0.902806 0.415304 -0.112805 0.902661 0.666676 -0.0924266 0.739594 0.667027 -0.0923482 0.739288 0.279895 0.127209 0.951565 0.125416 0.11613 0.985284 0.125439 0.0423057 0.991199 0.31223 0.0169387 0.949856 0.415532 0.0162179 0.909434 0.415808 0.0162479 0.909307 0.667271 0.0133066 0.744696 0.667574 0.0133323 0.744424 0.83111 0.0709756 0.55156 0.858442 0.0712333 0.507941 0.858473 0.00922265 0.512776 0.858286 0.00918921 0.513089 0.85814 -0.0635882 0.509463 0.857923 -0.0636838 0.509816 0.85794 -0.149976 0.491371 0.665382 -0.242448 0.706035 0.832204 -0.141969 0.535987 0.415855 -0.232854 0.879115 0.41576 -0.232892 0.87915 0.125306 -0.254054 0.959038 -0.144666 -0.300624 0.942707 0.152616 0.107538 0.982417 0.153467 0.103423 0.982727 0.16125 0.114695 0.980226 0.431253 -0.199338 0.879935 0.458431 -0.180012 0.870309 0.650895 -0.472341 0.594332 0.676452 -0.450892 0.582331 0.736973 -0.643243 0.207627 0.756217 -0.624162 0.196359 0.480774 -0.142612 0.865169 0.639425 -0.138768 0.756227 0.819867 -0.542621 0.182705 0.80604 -0.551848 0.213924 0.906002 -0.385291 0.175248 0.893531 -0.397073 0.209607 0.960787 -0.218445 0.170794 0.950898 -0.231751 0.205143 0.984803 -0.045178 0.167696 0.169184 0.126305 0.977458 0.174938 0.119898 0.977252 0.501928 -0.103284 0.85872 0.190099 0.159906 0.968655 0.195055 0.157262 0.968103 0.564725 0.0623061 0.822924 0.553811 0.0709956 0.829611 0.822844 -0.0423965 0.566683 0.725235 -0.384375 0.571218 0.711912 -0.387065 0.585972 0.794684 -0.248907 0.553644 0.778396 -0.254918 0.573688 0.833694 -0.107937 0.541576 0.942839 -0.0254102 0.332279 0.97591 -0.0630308 0.208871 0.970067 -0.2045 0.130955 0.335355 -0.85656 0.392227 0.0311928 -0.72114 0.692086 0.568816 -0.494691 0.657061 0.28887 -0.690693 0.662946 0.0630146 -0.771653 0.632914 -0.140715 -0.816483 0.55996 0.434295 -0.452389 0.77893 0.00432304 -0.699821 0.714305 0.474172 -0.855997 0.205985 0.144813 -0.934831 0.324222 0.100404 -0.951231 0.291683 0.143053 -0.972726 0.182591 0.931396 -0.357768 0.0671156 0.921127 -0.293263 0.255972 0.852595 -0.40072 0.335417 0.822001 -0.390182 0.414816 0.798132 -0.419602 0.432341 0.788257 -0.614575 0.030784 0.603886 -0.796835 0.0193699 0.5207 -0.853301 -0.0273592 0.256479 -0.96654 0.00429596 0.184969 -0.981775 -0.0436361 0.138776 -0.825546 0.547006 0.220936 -0.791914 0.569262 -0.218806 -0.917536 0.332042 0.0581937 -0.887112 0.45787 0.892779 -0.445012 0.0700744 0.790691 -0.611507 0.0294305 0.740576 -0.612356 0.276708 0.703051 -0.6698 0.23893 0.632778 -0.646036 0.426884 0.750093 -0.398285 0.527948 0.668137 -0.513526 0.538409 0.577326 -0.59189 0.56246 0.153558 -0.982089 0.109185 0.154959 -0.981896 0.108943 0.455004 -0.870335 0.188384 0.367084 -0.834569 0.410786 0.508936 -0.735943 0.446511 0.388339 -0.667471 0.635354 0.263669 -0.742286 0.616028 0.172962 -0.675507 0.716781 0.293679 -0.59653 0.746931 0.258093 -0.84857 -0.461862 0.965731 -0.227966 -0.124078 0.792465 -0.535707 -0.291576 0.258095 -0.848569 -0.461863 0.258095 -0.909708 -0.325298 0.258094 -0.909708 -0.325298 0.258301 -0.946736 -0.192281 0.258301 -0.946736 -0.192281 0.706346 -0.693704 -0.14089 0.706041 -0.666821 -0.238444 0.706042 -0.66682 -0.238445 0.704091 -0.604934 -0.371902 0.607611 -0.697598 -0.379692 0.608425 -0.790191 -0.0736003 0.792718 -0.597393 -0.12133 0.899966 -0.427237 -0.0867713 0.965731 -0.227965 -0.124078 0.965731 -0.24439 -0.0873899 0.965731 -0.24439 -0.08739 0.964676 -0.262765 -0.018847 0.982215 -0.184003 -0.0373705 0.23901 -0.814363 -0.528854 0.258818 -0.809448 -0.527074 0.592206 -0.676144 -0.438316 0.608764 -0.665361 -0.43209 0.793347 -0.512219 -0.328987 0.878706 -0.398007 -0.263566 0.768499 -0.536624 -0.348488 0.997914 -0.0541422 -0.0351604 0.986799 -0.134992 -0.0894709 0.965919 -0.214977 -0.144172 0.96245 -0.225841 -0.15062 0.931221 -0.304928 -0.199614 0.0910899 -0.476154 0.874632 0.257664 -0.306983 0.916172 0.269562 -0.326055 0.906104 0.434154 -0.430728 0.791191 0.706043 -0.338604 0.621973 0.98219 -0.0901244 0.164866 0.926906 0.155213 0.341693 0.899817 -0.208599 0.383166 0.706043 -0.338606 0.621972 0.117195 -0.774941 0.621073 0.265893 -0.960216 -0.0853585 0.159818 -0.980807 -0.111695 0.104679 -0.994169 0.0258849 0.284723 -0.900518 0.328633 0.096795 -0.967487 0.233665 0.00321777 -0.99456 0.104115 0.980184 -0.156702 0.121174 0.970398 -0.215528 0.108973 0.967627 -0.242057 0.0714561 0.893048 -0.341561 0.292919 0.819183 -0.455148 0.348969 0.782161 -0.581554 0.22365 0.768032 -0.601713 0.219247 0.696428 -0.71521 0.0588401 0.670916 -0.739796 0.0507405 0.586647 -0.804505 -0.0928307 0.371641 -0.617419 0.693308 0.0913328 -0.563651 0.820948 0.273321 -0.787467 0.552441 0.153878 -0.710211 0.686966 0.116647 -0.711781 0.692648 0.274211 -0.623143 0.732462 0.438172 -0.754435 0.488706 0.4138 -0.769106 0.487079 0.463629 -0.584195 0.666156 0.430321 -0.610216 0.665176 0.267317 -0.668828 -0.693693 0.48772 -0.871269 -0.0549531 0.513406 -0.709363 -0.482927 0.68608 -0.676182 -0.268461 0.755375 -0.603979 -0.2542 0.816067 -0.555743 -0.158696 0.864669 -0.480581 -0.146253 0.915972 -0.400076 -0.0305526 0.907959 -0.417739 -0.0332428 0.946311 -0.323174 -0.00733289 0.0515094 -0.908814 -0.414009 0.257294 -0.946741 -0.193603 0.162132 -0.980317 -0.112656 0.2591 -0.946101 -0.19432 0.476863 -0.871748 0.112503 0.37014 -0.911868 0.177464 0.31539 -0.920855 0.229249 0.265293 -0.931221 0.249896 0.165056 -0.933017 0.319743 0.175957 -0.931963 0.316991 0.0629148 -0.860194 0.506072 0.706825 -0.408567 0.57747 0.629313 -0.511645 0.584966 0.577047 -0.717783 0.38962 0.58444 -0.712021 0.389173 0.498013 -0.843538 0.201065 0.169151 -0.965628 0.197356 0.552417 -0.827369 -0.10147 0.396342 -0.864338 -0.309569 0.378478 -0.893302 -0.242417 0.147765 -0.85639 -0.494735 -0.21079 -0.933309 -0.290693 0.144743 -0.934129 -0.326269 0.0262059 -0.716662 -0.696929 0.934955 -0.300093 -0.189218 0.0827967 -0.721606 -0.687336 0.366032 -0.834135 -0.412602 0.450197 -0.869651 -0.202556 0.145724 -0.975018 -0.167642 0.477101 -0.857031 -0.194611 0.135952 -0.985219 -0.104209 0.15578 -0.982816 -0.0990203 0.0564277 -0.768275 -0.637628 0.164837 -0.723646 -0.670198 -0.00751869 -0.900296 -0.435213 0.0489745 -0.887311 -0.458563 0.0855003 -0.903993 -0.418911 0.226921 -0.591006 -0.774092 0.970955 -0.226193 -0.0779999 0.873197 -0.325644 -0.362606 0.847906 -0.316923 -0.424989 0.887562 -0.156411 -0.433323 0.750992 -0.39788 -0.526975 0.476292 -0.593315 -0.64894 0.788433 -0.614445 -0.0288146 0.892766 -0.44502 -0.0701891 0.978615 -0.196593 -0.0605374 0.91169 -0.298895 -0.281926 0.916477 -0.261331 -0.302945 0.836982 -0.47458 -0.272462 0.747767 -0.442905 -0.494652 0.613837 -0.621582 -0.486663 0.509223 -0.561609 -0.65214 -0.196854 -0.816535 -0.542697 0.191474 -0.691888 -0.696153 0.272849 -0.749897 -0.602667 0.212275 -0.786368 -0.580142 0.334004 -0.856297 -0.393951 0.0997691 -0.950773 -0.293389 0.142752 -0.972547 -0.18378 0.551199 -0.511662 -0.659076 0.379813 -0.663963 -0.644124 0.491438 -0.729549 -0.475654 0.612722 -0.63723 -0.467451 0.691062 -0.667604 -0.277016 0.75 -0.614574 -0.244539 0.79048 -0.6117 -0.0310505 0.514527 -0.857355 -0.0143061 0.607323 -0.793531 0.0383073 0.173706 -0.984703 -0.0136734 0.257605 -0.965675 0.0333332 0.258319 -0.946946 0.191218 0.98163 -0.19047 -0.0111278 0.899978 -0.42731 0.0862874 0.792739 -0.597501 0.120654 0.258318 -0.946946 0.191219 0.258083 -0.910257 0.323769 0.258082 -0.910257 0.323769 0.258083 -0.848831 0.461388 0.258082 -0.848831 0.461388 0.706027 -0.622208 0.338206 0.706027 -0.667234 0.237329 0.706027 -0.667234 0.237328 0.704199 -0.703473 0.0960704 0.607967 -0.778254 0.157155 0.608735 -0.66006 0.440185 0.792451 -0.535887 0.291285 0.904891 -0.373969 0.203274 0.965792 -0.254189 0.0513286 0.965728 -0.244546 0.0869827 0.965728 -0.244546 0.0869826 0.964663 -0.215199 0.152034 0.984333 -0.154916 0.0842056 0.980786 -0.163615 0.106253 0.984425 -0.14794 0.0949777 0.907685 -0.351796 0.228796 0.90539 -0.355887 0.231546 0.808253 -0.494269 0.32004 0.793349 -0.510558 0.331554 0.644552 -0.641213 0.416413 0.608764 -0.664848 0.432878 0.483593 -0.734485 0.476099 0.255645 -0.809084 0.529178 0.258817 -0.808462 0.528585 0.0621553 -0.837049 0.543586 0.716763 -0.685329 0.128747 0.693795 -0.714762 0.0881116 0.786265 -0.591301 0.179305 0.976271 -0.214134 0.0322642 0.454726 -0.825919 0.333289 0.0850599 -0.990659 -0.106583 0.135206 -0.91686 -0.375617 0.540569 -0.606887 -0.582643 0.431693 -0.592826 -0.679852 0.199449 -0.631115 -0.749609 0.186441 -0.61567 -0.765631 0.360311 -0.927777 -0.0969823 0.143094 -0.971901 -0.186902 0.131299 -0.964563 -0.228863 0.365517 -0.929162 -0.0552753 0.211127 -0.965214 0.154234 0.28322 -0.945184 0.162526 0.642862 -0.651207 0.403309 0.566355 -0.743907 0.354747 0.603124 -0.541899 -0.585309 0.786022 -0.442287 -0.431916 0.769256 -0.435426 -0.4676 0.890211 -0.359742 -0.279483 0.876868 -0.359133 -0.319572 0.953679 -0.253089 -0.162613 0.968564 -0.247805 0.0218321 0.963469 -0.267757 -0.00588103 0.903147 -0.394392 0.169651 0.451795 -0.813118 0.367044 0.439436 -0.829288 0.345222 0.645475 -0.761908 0.0534542 0.787523 -0.571641 0.230291 0.776323 -0.600087 0.19292 0.892215 -0.450374 -0.0333961 0.820759 -0.546056 -0.167864 0.827392 -0.543841 -0.14021 0.714181 -0.641358 -0.280367 0.717696 -0.64118 -0.271662 0.511587 -0.741383 -0.434317 0.504307 -0.732895 -0.45666 0.169214 -0.842294 0.511769 0.0859191 -0.920925 0.380152 -0.0255243 -0.949139 0.31382 0.152713 -0.98227 0.108742 0.161635 -0.979969 0.11634 0.116397 -0.993199 0.0028269 0.0338885 -0.916546 0.398492 0.259383 -0.794502 0.549078 0.18423 -0.868642 0.459913 0.353266 -0.894471 0.274091 0.352313 -0.895334 0.272494 0.569136 -0.821493 -0.0351148 0.69143 -0.681182 0.240656 0.628046 -0.772718 -0.0920085 0.445482 -0.862576 -0.239809 0.438881 -0.855475 -0.274854 0.15229 -0.908486 -0.389178 0.167659 -0.79516 -0.582761 0.16998 -0.796874 -0.57974 0.181836 -0.703717 -0.686817 0.965718 -0.124436 -0.227826 0.770137 0.493191 -0.404538 0.932053 0.058532 -0.357562 0.899814 -0.208609 -0.383167 0.706042 -0.338619 -0.621966 0.721247 0.0479499 -0.691016 0.186826 -0.469723 -0.862819 0.25794 -0.318378 -0.912196 0.434154 -0.430728 -0.791191 0.607605 -0.379758 -0.697567 -0.761078 0.647529 -0.0382966 -0.569425 0.821549 -0.0285143 -0.128962 0.991628 -0.00654309 -0.255589 0.966772 -0.0051901 -0.351938 0.935886 -0.0160547 -0.469856 0.882427 -0.0236181 -0.699224 0.714351 -0.02809 -0.699062 0.714186 0.035356 -0.788624 0.614417 0.0237565 -0.627164 0.778326 0.0295595 -0.521567 0.852809 0.0261618 -0.255571 0.966702 0.0130604 -0.414725 0.909947 0.000951457 -0.167418 0.985849 0.00849422 0 0.895629 -0.444802 0 0.150732 -0.988575 -0.000507492 0.158236 -0.987401 0.000214571 0.365377 -0.93086 -0.0038363 0.500676 -0.865626 0.0259749 0.790656 -0.611709 0 0.923966 -0.382475 -0.00977642 0.830593 -0.556794 0.00119851 0.872432 -0.488733 -0.000786029 0.654687 -0.7559 0.00125927 0.682385 -0.730992 -0.00123571 0.458641 -0.888621 0 0.895943 0.444168 0.0258726 0.79102 0.611243 0 0.158984 0.987281 -0.095736 0.923333 0.371875 2.18245e-08 0.894662 0.446744 -0.0170841 0.799764 0.600072 0.00110652 0.872688 0.488276 -0.00073107 0.65547 0.755221 0.00130193 0.682978 0.730438 -0.000895159 0.495187 0.868786 -0.00252253 0.459916 0.887959 0.00217759 0.293695 0.955897 -0.00565514 0.0867078 0.996218 0 0.975433 0.220298 0.000642297 0.984425 0.175805 -0.000543435 0.836124 0.54854 -0.000416728 0.842213 0.539146 -5.6939e-06 0.734257 0.678872 3.11585e-05 0.539138 0.842218 0 0.119697 0.992811 -0.00175703 0.346023 0.938224 0.000785229 0.175799 0.984426 -0.000323762 0.481608 0.876387 -0.00129061 0.61766 0.786444 -0.605339 0.756591 0.247255 -0.110886 0.837019 0.535821 -0.0992143 0.82316 0.559074 -0.315225 0.766636 0.559376 -0.307353 0.760535 0.571944 -0.0474981 0.1756 0.983315 -0.206017 0.187638 0.96039 -0.0937588 0.151614 0.983983 -0.0502286 0.204704 0.977534 -0.133275 0.975643 0.174237 -0.16572 0.983472 0.0729418 -0.361509 0.88162 0.30341 -0.399971 0.887514 0.228783 -0.504673 0.831837 0.230983 -0.574756 0.757575 0.309412 -0.488346 0.649669 0.582622 -0.496201 0.653143 0.572004 -0.322704 0.429239 0.843573 -0.201309 0.498198 0.84337 -0.104051 0.394416 0.913022 -0.0675365 0.537907 0.840295 -0.128801 0.131692 0.982887 -0.276554 0.280617 0.919115 -0.414092 0.324645 0.850373 -0.641541 0.498896 0.58269 -0.635008 0.497776 0.590749 -0.765208 0.594737 0.246464 -0.75999 0.595726 0.259857 -0.615989 0.733852 0.28639 -0.150579 0.094642 0.984057 -0.150768 0.0947744 0.984016 -0.442214 0.277917 0.852765 -0.442768 0.278315 0.852348 -0.680382 0.427576 0.595197 -0.681097 0.428119 0.593987 -0.142377 0.105692 0.984154 -0.142819 0.106056 0.98405 -0.418134 0.310355 0.853723 -0.419401 0.311423 0.852713 -0.643697 0.477747 0.59784 -0.645219 0.479101 0.595109 -0.131884 0.117152 0.984318 -0.132551 0.117807 0.98415 -0.387418 0.344074 0.85529 -0.389265 0.34593 0.853701 -0.596976 0.530136 0.602143 -0.599219 0.53251 0.597804 -0.671149 0.717229 0.187458 -0.119022 0.12846 0.984546 -0.119872 0.129472 0.984311 -0.349747 0.377371 0.857478 -0.35211 0.380251 0.855235 -0.539632 0.582173 0.608171 -0.542502 0.585853 0.602054 -0.653504 0.704941 0.275664 -0.718763 0.63825 0.275712 -0.720053 0.639887 0.268455 -0.773529 0.574083 0.268479 -0.774408 0.575027 0.263888 -0.81667 0.513209 0.263946 -0.817085 0.513593 0.261905 -0.334806 0.722029 0.605458 -0.19631 0.953598 0.228283 -0.219956 0.958036 0.183808 -0.305588 0.829061 0.468267 -0.588155 0.756394 0.286255 -0.129567 0.25218 0.958967 -0.0857542 0.613309 0.785174 -0.000719786 0.655454 0.755235 -0.115625 0.790945 0.600863 -0.0483086 0.835591 0.547223 0.109077 0.664067 0.739674 -0.103814 0.927923 0.358024 0.161667 0.169175 0.972236 -0.232644 0.719302 0.654585 -0.108493 0.782737 0.612823 -0.309418 0.925378 0.218941 -0.133568 0.83923 0.527117 -0.0753878 0.164476 0.983496 -0.283403 0.431637 0.856372 -0.00276975 0.14274 0.989756 -0.430024 0.669334 0.605863 -0.459557 0.695794 0.551976 -0.598346 0.801019 0.0187353 -0.407999 0.730431 0.547729 -0.0611921 0.303761 0.950781 -0.276827 0.579601 0.766439 -0.173592 0.647148 0.742338 -0.317397 0.791994 0.521541 -0.341078 0.80861 0.479391 -0.508695 0.860936 -0.00432425 -0.294273 0.810907 0.5058 -4.05846e-05 0.539138 -0.842218 0 0.0642738 -0.997932 2.32417e-05 0.175799 -0.984426 -0.0013732 0.297146 -0.954831 -0.000503624 0.185236 -0.982694 -0.000899446 0.87568 -0.482892 0.000224037 0.715801 -0.698305 -0.000722001 0.495269 -0.868739 5.98058e-06 0.842213 -0.539146 -2.66898e-05 0.984425 -0.175805 0 0.984841 -0.17346 -0.636885 0.49513 -0.590952 -0.31209 0.758373 -0.57225 -0.311083 0.768099 -0.559688 -0.569663 0.750704 -0.334555 -0.493178 0.655204 -0.572262 -0.491748 0.646827 -0.582922 -0.0475389 0.1756 -0.983313 -0.0581288 0.289739 -0.955339 -0.081413 0.1575 -0.984157 -0.63964 0.501039 -0.582941 -0.76247 0.59249 -0.259992 -0.757785 0.645664 -0.0942277 -0.340833 0.916597 -0.209003 -0.36259 0.882905 -0.298339 -0.45412 0.860604 -0.230515 -0.55162 0.801636 -0.230424 -0.153458 0.149531 -0.976776 -0.128828 0.131659 -0.982888 -0.376534 0.381163 -0.844356 -0.248396 0.197082 -0.948398 -0.322887 0.429075 -0.843587 -0.138939 0.529163 -0.837068 -0.122812 0.311112 -0.942405 -0.0676627 0.537902 -0.840287 -0.108777 0.821547 -0.559668 -0.102235 0.8378 -0.536321 -0.13148 0.969159 -0.208431 -0.123666 0.976868 -0.174456 -0.656665 0.701976 -0.275719 -0.816614 0.513297 -0.263947 -0.817141 0.513504 -0.261905 -0.680339 0.427643 -0.595198 -0.681139 0.428051 -0.593988 -0.442187 0.27795 -0.852769 -0.442787 0.278277 -0.852351 -0.150578 0.0946549 -0.984056 -0.150779 0.094768 -0.984015 -0.773387 0.574274 -0.268482 -0.774548 0.574836 -0.263891 -0.643586 0.477891 -0.597844 -0.645325 0.478954 -0.595113 -0.41807 0.310436 -0.853725 -0.419456 0.311336 -0.852717 -0.144427 0.107249 -0.983686 -0.142769 0.10614 -0.984048 -0.718512 0.63853 -0.275716 -0.720301 0.639607 -0.268458 -0.59678 0.530349 -0.602149 -0.599407 0.532292 -0.59781 -0.387306 0.344191 -0.855293 -0.389369 0.345806 -0.853704 -0.131851 0.117185 -0.984318 -0.130559 0.116149 -0.984614 -0.615989 0.733852 -0.28639 -0.666715 0.719043 -0.196133 -0.539329 0.582443 -0.608182 -0.542791 0.585574 -0.602064 -0.349574 0.377519 -0.857483 -0.35227 0.380092 -0.85524 -0.173443 0.187246 -0.96688 -0.118408 0.130969 -0.98429 -0.0557285 0.0601473 -0.996633 -0.00117044 0.65524 -0.75542 -0.563948 0.774759 -0.285851 -0.245017 0.859918 -0.447782 -0.368424 0.927896 -0.0572142 -0.223389 0.918268 -0.326927 -0.173331 0.935755 -0.307114 -0.103519 0.911612 -0.397803 -0.0851372 0.61363 -0.78499 -0.155016 0.947882 -0.278369 -0.227873 0.958219 -0.172887 -0.0352109 0.851294 -0.523506 -0.108987 0.783264 -0.612061 -0.108453 0.782755 -0.612807 -0.232644 0.719302 -0.654585 0.161552 0.169371 -0.972221 -0.0864534 0.481193 -0.872341 -0.0315 0.411217 -0.910993 -0.382019 0.795966 -0.469575 -0.589834 0.80155 -0.0980481 -0.459556 0.695792 -0.55198 -0.430025 0.669334 -0.605863 -0.248895 0.457996 -0.8534 0.0200609 0.122652 -0.992247 -0.0552394 0.221985 -0.973484 -0.0834964 0.260292 -0.961913 -0.198398 0.403663 -0.893137 -0.316057 0.550668 -0.772575 -0.173595 0.647151 -0.742334 -0.317395 0.791993 -0.521544 -0.341079 0.80861 -0.479391 -0.522686 0.848859 0.0789819 -0.133649 0.748035 -0.650063 0 -0.982033 0.188707 0.001466 -0.963081 0.269207 0.00404909 -0.712279 0.701885 0.00579416 -0.693575 0.720362 -0.00127687 -0.807564 0.589778 0.00235923 -0.937216 0.348742 0.0109356 -0.889217 0.457354 0.00517729 -0.92683 0.375445 0 0.0508677 0.998705 0.00636505 0.0893547 0.99598 -0.00167094 -0.157265 0.987555 0.00456916 -0.362477 0.931981 0.00668495 -0.338669 0.940882 -0.00264689 -0.518289 0.855201 0 0.258819 0.965926 7.58909e-07 0.258819 0.965926 -3.02965e-07 0.258819 0.965926 -1.80156e-06 0.258818 0.965926 5.76019e-06 0.258823 0.965925 0 0.258819 0.965926 9.64484e-07 0.25882 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 3.10711e-08 0.258819 -0.965926 -6.88736e-07 0.258819 -0.965926 -5.2373e-07 0.258819 -0.965926 0.000371581 -0.712285 -0.70189 0 0.0508683 -0.998705 -6.09369e-05 -0.52439 -0.851478 0.00145452 -0.441646 -0.897188 0.00550207 -0.362476 -0.931977 -0.00336643 -0.218636 -0.975801 0.00597987 0.0870285 -0.996188 0 -0.969412 -0.245438 0.00669926 -0.916482 -0.400019 0.00295421 -0.937214 -0.348742 -0.000748778 -0.844138 -0.536125 0.00350917 -0.688761 -0.72498 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.944823 -0.327582 0.00146578 -0.968656 -0.248403 0.00404901 -0.967794 0.251711 0.00579387 -0.960835 0.277061 -0.00127701 -0.99426 0.106982 0.00235912 -0.986024 -0.166589 0.0109373 -0.998763 -0.0485025 0.00517687 -0.99038 -0.138278 0 -0.4553 0.890338 0.00636515 -0.420606 0.907221 -0.00167079 -0.629974 0.776615 0.00456927 -0.779904 0.625882 -0.000282098 -0.814983 0.579484 0.000110145 -0.9209 0.389799 0 -0.258819 0.965926 -8.348e-07 -0.258819 0.965926 4.54447e-07 -0.258819 0.965926 3.15447e-07 -0.258819 0.965926 -1.44005e-06 -0.25882 0.965926 0 -0.258819 0.965926 0 -0.195065 0.98079 0.117958 -0.084511 0.989416 0.215409 -0.0831072 -0.972981 0 -0.153159 -0.988202 9.37441e-07 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 -3.10711e-08 -0.258819 -0.965926 6.88736e-07 -0.258819 -0.965926 -1.92035e-06 -0.25882 -0.965926 0.000371383 -0.967802 -0.251713 0 -0.4553 -0.890338 -6.10881e-05 -0.879878 -0.475199 0.0014545 -0.831071 -0.556164 0.00550218 -0.779901 -0.625879 -0.0033663 -0.677244 -0.735751 0.00597993 -0.422725 -0.906238 0 -0.962255 0.272148 0.00669911 -0.993706 0.111815 0.00295414 -0.986022 0.166588 -0.000748858 -0.999108 -0.0422292 0.00350911 -0.958974 -0.283473 0 0.982033 -0.188707 0.00146599 0.963081 -0.269207 0.00404926 0.712279 -0.701885 0.00579393 0.693579 -0.720358 -0.00127675 0.807562 -0.589781 0.00235943 0.937216 -0.348742 0.0109359 0.889217 -0.457355 0.00517705 0.926833 -0.375439 0 -0.0508684 -0.998705 0.00636494 -0.089355 -0.99598 -0.00167096 0.157265 -0.987555 0.00456918 0.362478 -0.931981 0.00668486 0.338671 -0.940881 -0.00264681 0.518288 -0.855202 0 -0.258819 -0.965926 -2.27672e-07 -0.258819 -0.965926 -4.54447e-07 -0.258819 -0.965926 2.75492e-06 -0.25882 -0.965925 -3.24007e-06 -0.258817 -0.965926 0 -0.258819 -0.965926 0 -0.321464 -0.946922 0.117959 -0.42152 -0.899114 0.215407 -0.414518 0.88418 0 -0.361462 0.932387 4.50693e-08 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.258823 0.965925 5.43744e-07 -0.258819 0.965926 -4.94093e-07 -0.258819 0.965926 -3.49153e-07 -0.258819 0.965926 0.000371581 0.712285 0.70189 0 -0.0508678 0.998705 -6.09369e-05 0.52439 0.851478 0.00145452 0.441646 0.897188 0.0055021 0.362476 0.931977 -0.0033664 0.218635 0.975801 0.00597985 -0.087028 0.996188 0 0.969412 0.245438 0.00669895 0.916485 0.400012 0.00295442 0.937214 0.348742 -0.000748587 0.844138 0.536125 0.00350936 0.688759 0.724982 0 0.258819 -0.965926 -8.348e-07 0.258819 -0.965926 4.54447e-07 0.258819 -0.965926 3.1755e-06 0.258817 -0.965926 -1.44005e-06 0.25882 -0.965926 0 0.258819 -0.965926 0 0.195065 -0.98079 0.117958 0.084511 -0.989416 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.643891 0.765117 0.00906878 -0.543383 0.839436 0.00367244 -0.49981 0.866128 0.00463063 0.265909 0.963987 -0.00317906 -0.024837 0.999686 0.00844233 -0.152072 0.988333 -2.61895e-05 -0.267745 0.96349 1.02872e-05 -0.38982 0.920891 0 0.725658 0.688055 0.0106632 0.597236 0.801995 0.00452693 0.637277 0.770622 -0.000749294 0.4697 0.882826 0.00346651 0.274723 0.961517 0 0.707107 -0.707107 -2.20967e-07 0.707107 -0.707107 0 0.707106 -0.707108 0 -0.402918 -0.915236 0 -0.402918 -0.915236 0 0.0652906 -0.997866 0 0.0652906 -0.997866 0 0.518741 -0.854932 0 0.518741 -0.854932 0 -0.491222 -0.871035 -0.00165757 -0.509809 -0.860286 -0.00770959 -0.5421 -0.840278 -0.0098529 -0.546743 -0.837242 -0.00191891 -0.580507 -0.814253 0 -0.601186 -0.799109 0 -0.601186 0.799109 -0.00497413 -0.546763 0.837273 -0.0212785 -0.573101 0.819208 -0.0101355 -0.545284 0.83819 -0.0059615 -0.531025 0.847335 -0.0039285 -0.522012 0.852929 -0.00165738 -0.509807 0.860287 0 -0.491222 0.871035 0 0.518741 0.854931 0 0.518741 0.854931 0 0.0652906 0.997866 0 0.0652906 0.997866 0 -0.402918 0.915236 0 -0.402918 0.915236 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.733575 -0.679609 0.00105035 0.265911 -0.963997 0.0203008 0.135149 -0.990617 0.0157097 0.175942 -0.984275 0.0107253 0.221204 -0.975169 -0.000746073 0.37046 -0.928848 0.00133485 0.637284 -0.770628 0.0193243 0.51828 -0.854993 0.0077499 0.611525 -0.791187 0 -0.543406 -0.83947 0.0154948 -0.612229 -0.790528 -0.00373196 -0.392365 -0.919802 0.00651549 -0.152074 -0.988348 0.00187248 -0.115744 -0.993277 -8.54899e-05 0.049023 -0.998798 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0.215405 0.0831073 0.972982 0 0.153158 0.988202 -9.64484e-07 0.25882 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 -3.10711e-08 0.258819 0.965926 6.88736e-07 0.258819 0.965926 5.2373e-07 0.258819 0.965926 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.966776 -0.255625 0 -0.897121 -0.441785 -0.00691649 -0.844689 -0.535213 0.0079037 -0.973065 -0.230394 0.0189883 -0.996022 -0.0870584 0.306294 -0.886728 -0.346262 0.364248 -0.743369 -0.561005 0.748429 -0.452466 -0.4849 0.572821 -0.610446 -0.547021 0.190861 -0.909238 -0.369944 -0.300473 -0.697523 -0.650521 0.221143 -0.94284 -0.249296 0.228105 -0.822439 -0.521115 0.55068 -0.669265 -0.498835 0.518574 -0.632792 -0.575026 0.519691 -0.758383 -0.393415 0.0901656 -0.90858 -0.407863 0.127107 -0.988079 -0.0868555 0.35566 -0.821535 -0.445629 0.363254 -0.889917 -0.275852 0.586294 -0.658962 -0.471199 0.58436 -0.69874 -0.412657 0.753206 -0.440201 -0.488777 0.753087 -0.442675 -0.486723 0.102796 -0.768652 -0.631353 0.102851 -0.917684 -0.383768 0.346867 -0.711776 -0.610785 0.32965 -0.804343 -0.494332 0.560889 -0.587477 -0.583331 0.547645 -0.635015 -0.544831 0.729956 -0.414523 -0.543447 0.727364 -0.424536 -0.539176 0.138124 -0.987702 -0.0732583 0.130095 -0.988828 -0.0727657 0.801219 -0.403376 -0.441969 0.789205 -0.442818 -0.425521 0.642809 -0.678971 -0.354678 0.628417 -0.699854 -0.339553 0.40759 -0.885074 -0.224754 0.398726 -0.891164 -0.216436 0.134608 -0.988129 -0.0740398 0 -0.920489 0.39077 0.0120198 -0.864515 0.502463 0.00315896 -0.930291 0.366809 -0.00368088 -0.995466 0.0950458 0.0047118 -0.975365 0.220548 0 -0.997148 0.0754653 0.229986 -0.912764 0.337591 0.0574934 -0.979298 0.194088 0.838208 -0.413501 -0.355561 0.828582 -0.402268 -0.3894 0.521842 -0.842726 0.132265 0.351621 -0.932767 0.0794202 0.422893 -0.896703 0.130709 0.229276 -0.861135 0.453739 0.0638016 -0.945759 0.318544 0.691506 -0.691752 -0.208085 0.721726 -0.691962 -0.0173306 0.772984 -0.600975 -0.203286 0.0966615 -0.983838 -0.150731 0.151403 -0.966019 0.209487 0.400109 -0.884836 -0.2387 0.422679 -0.905551 -0.0363209 0.656177 -0.678974 -0.329282 0.662136 -0.705172 -0.253591 0.815364 -0.40341 -0.41526 0.81627 -0.408275 -0.408675 0.866735 -0.385788 -0.316129 0.688839 -0.668758 -0.279758 0.640409 -0.619353 0.454179 0.507111 -0.861593 -0.0222635 0.64851 -0.753041 -0.111196 0.225404 -0.969855 0.0926005 0.6882 -0.660887 -0.299349 0.649809 -0.748542 -0.132037 0.310302 -0.863221 -0.398198 0.43207 -0.901539 -0.0232957 0.257117 -0.95894 0.119689 0.257221 -0.958061 0.126322 0.111742 -0.914724 0.388322 0 -0.861366 -0.507985 0.00467267 -0.920478 -0.390766 0.00309476 -0.930623 -0.365967 -0.000473248 -0.97477 -0.223212 0.000669485 -0.995473 -0.0950457 0 -0.997246 -0.074163 0.225403 -0.969855 -0.0925998 0.640409 -0.619353 -0.454179 0.249509 -0.855049 0.454572 0.639397 -0.76862 0.0198611 0.111743 -0.914723 -0.388323 0.257222 -0.95806 -0.126322 0.257117 -0.95894 -0.119688 0.43207 -0.901539 0.0232957 0.310302 -0.863221 0.398198 0.649809 -0.748542 0.132037 0.685989 -0.66909 0.285897 0.703713 -0.651556 0.283307 0.866735 -0.385788 0.316129 0.405424 -0.911972 0.0627543 0.842163 -0.395085 0.366974 0.0850439 -0.991142 -0.102004 0.194317 -0.894821 -0.401915 0.0875822 -0.966709 -0.240422 0.825776 -0.424468 0.371377 0.772984 -0.600975 0.203286 0.749581 -0.653761 0.103562 0.651879 -0.750704 0.107221 0.48967 -0.853062 -0.180303 0.422892 -0.896704 -0.130708 0.19306 -0.842872 -0.50229 0.817942 -0.403374 0.410195 0.813563 -0.409537 0.41279 0.683434 -0.677043 0.273003 0.633126 -0.715633 0.294992 0.472564 -0.87652 0.0916342 0.35208 -0.92539 0.140332 0.222909 -0.97032 -0.0937582 0.0399946 -0.998768 -0.0293666 0.131578 -0.98857 0.0735953 0.138124 -0.987702 0.0732583 0.130995 -0.988705 0.0728211 0.409398 -0.885098 0.221348 0.393023 -0.893392 0.217676 0.646302 -0.679026 0.348164 0.622928 -0.70205 0.345089 0.80605 -0.403427 0.433048 0.783817 -0.443795 0.434369 0.754112 -0.440751 0.486882 0.751154 -0.443479 0.488973 0.608218 -0.671425 0.42339 0.55758 -0.69817 0.449068 0.414857 -0.852217 0.318777 0.300312 -0.881491 0.364398 0.196126 -0.96181 0.190936 0.0312528 -0.970346 0.239691 0.73183 -0.41829 0.538013 0.724567 -0.422843 0.544248 0.572801 -0.610399 0.547095 0.53043 -0.623704 0.574141 0.378182 -0.768456 0.516192 0.289941 -0.774605 0.562068 0.167584 -0.87804 0.448288 0.0347668 -0.860868 0.50764 0.140707 -0.836309 0.529895 0.227651 -0.882422 0.411712 0.364244 -0.74337 0.561005 0.590913 -0.647609 0.481066 0.74846 -0.452431 0.484885 0.526805 -0.642172 0.556859 0.582848 -0.705346 0.403455 0.423169 -0.825104 0.374342 0.230355 -0.887259 0.399636 0.227438 -0.887128 0.401591 0.00973578 -0.96673 0.255613 0 -0.997075 0.0764287 0.00588602 -0.966759 0.255621 0.00783259 -0.972891 0.23113 -0.00678464 -0.844694 0.535207 0 -0.896592 0.442857 0 -0.898709 -0.438546 0.00556667 -0.936048 -0.351827 0.000693272 -0.975761 -0.218836 -0.000522252 -0.998582 -0.0532251 0 -0.997341 -0.0728735 0.278908 -0.958957 -0.051113 0.584881 -0.767576 0.262184 0.436736 -0.889126 0.136808 0.688097 -0.654851 -0.312559 0.12669 -0.98933 -0.0719412 0.819874 -0.261741 0.509213 0.737581 -0.43734 0.514498 0.594355 -0.648971 0.474952 0.655843 -0.600139 0.457934 0.586724 -0.755439 0.291663 -0.0939682 -0.681039 0.726193 0.46196 -0.876585 0.134878 0.221285 -0.975199 -0.00439568 0.222358 -0.967713 -0.118696 0.078309 -0.933188 -0.350752 0.743952 -0.277888 0.607712 0.774819 -0.296137 0.558533 0.328438 -0.944419 -0.0141544 0.594455 -0.596472 0.5393 0.638804 -0.768796 -0.0296916 0.0586619 -0.977895 0.2007 0.178164 -0.981564 -0.069213 0.0608628 -0.996058 0.064527 0.197161 -0.9553 -0.220294 0.0637854 -0.995293 -0.0729632 0.214931 -0.906521 -0.363351 0.0687577 -0.97507 -0.210975 0.7646 -0.297418 0.571777 0.739546 -0.267329 0.617743 0.735683 -0.27005 0.621164 0.642789 -0.628201 0.438391 0.805607 -0.496785 0.322804 0.578997 -0.72231 0.378193 0.873447 -0.448261 0.19014 0.633868 -0.741763 0.219086 0.585229 -0.810111 0.0350375 0.34222 -0.938263 0.0504806 0.391829 -0.91656 -0.079932 0.315796 -0.912344 -0.26058 0.231339 -0.830034 -0.507471 0.750024 -0.275993 0.601075 0.737375 -0.284993 0.612419 0.739052 -0.531337 0.414104 0.618449 -0.712163 0.332181 0.615756 -0.711116 0.339349 0.509508 -0.859433 0.0421568 0.452727 -0.885049 0.108293 0.360099 -0.885726 0.292948 0.427879 -0.877204 0.21779 0.35103 -0.853064 0.386082 0.138258 -0.985667 0.0966672 0.749905 -0.267294 0.605141 0.785327 -0.315878 0.532431 0.748274 -0.358911 0.557915 0.137388 -0.984584 0.108258 0.153101 -0.981536 0.11466 0.41717 -0.854849 0.308549 0.401059 -0.865318 0.300626 0.645984 -0.596109 0.476821 0.624592 -0.624963 0.468302 0.744959 -0.375462 0.551421 0.770837 -0.333131 0.542986 0.7847 -0.312464 0.535362 0.781729 -0.315844 0.537719 0.65155 -0.59027 0.476513 0.598663 -0.623045 0.503407 0.45134 -0.817198 0.35844 0.325357 -0.854657 0.404603 0.214944 -0.954784 0.205396 0.032091 -0.96708 0.252439 0.777 -0.308648 0.548641 0.777504 -0.30826 0.548145 0.621777 -0.538499 0.568694 0.583749 -0.553287 0.594231 0.415247 -0.734513 0.536713 0.32131 -0.744922 0.58468 0.185487 -0.870576 0.455732 0.0366017 -0.854338 0.518427 0.493333 -0.864149 0.0993439 0.178995 -0.862019 0.47422 0.791334 -0.333238 0.512585 0.631883 -0.570738 0.524387 0.504828 -0.715576 0.482803 0.597356 -0.652442 0.466353 0.631711 -0.475286 0.612408 0.676956 -0.653102 0.339394 0.276149 -0.504479 0.818073 0.409538 -0.756256 0.51025 0.248268 -0.876213 0.413054 0.248345 -0.879307 0.406378 0.0705299 -0.978282 0.19491 0 -0.997109 0.0759787 0.00353134 -0.980718 0.195396 0.00201781 -0.97386 0.227141 -0.00261107 -0.876166 0.482002 0 -0.896937 0.442158 0 -0.935368 0.353676 0.0171797 -0.864055 0.503104 0.00663967 -0.929717 0.368216 -0.00595085 -0.998458 0.0551949 0.00451966 -0.974687 0.22353 0 -0.997114 0.0759125 0.664263 -0.704289 0.250462 -0.0516392 -0.93412 0.353204 0.126498 -0.976665 0.173561 0.350875 -0.913087 -0.207749 0.073165 -0.988869 -0.129558 0.393396 -0.911679 -0.118663 0.387329 -0.851547 -0.353333 0.394971 -0.875383 -0.278751 0.402912 -0.816957 -0.412605 0.389348 -0.800222 -0.456129 0.630375 -0.611935 -0.477664 0.144911 -0.984731 0.0964635 0.144707 -0.987966 0.0546149 0.171564 -0.984976 -0.0196867 0.026266 -0.970306 0.24045 0.0694761 -0.963388 0.258952 0.0100628 -0.994508 0.104176 0.0687186 -0.997131 0.0317419 0.00308564 -0.997146 -0.0754302 0.0384179 -0.862088 -0.505301 0.0829677 -0.832677 -0.547509 0.0601765 -0.954778 -0.291166 0.0425492 -0.987355 -0.15271 0.170077 -0.978577 -0.116017 0.114711 -0.991239 -0.0654739 0.264226 -0.762323 -0.590802 0.397711 -0.657959 -0.639465 0.424298 -0.689034 -0.58754 0.112751 -0.887233 0.447331 0.160826 -0.968055 0.192365 0.262394 -0.964957 -0.00283779 0.270241 -0.962396 0.0276338 0.329612 -0.918563 -0.218169 0.171396 -0.768205 -0.616835 0.364847 -0.874302 -0.320129 0.302968 -0.889183 -0.342876 0.193142 -0.956504 -0.218624 0.516405 -0.779245 -0.35511 0.454746 -0.831132 -0.320041 -3.01642e-06 -0.862727 -0.505671 -2.8976e-06 -0.862726 -0.505672 -2.30458e-07 -0.996025 -0.0890714 0.00147868 -0.99715 -0.0754304 -2.84276e-06 -0.956513 -0.291689 0 -0.980724 -0.195397 0 -0.897362 -0.441294 -0.00268437 -0.876166 -0.482002 0.00205732 -0.974019 -0.226458 0.00882644 -0.996532 -0.0827361 0.493333 -0.864149 -0.0993434 0.791334 -0.333236 -0.512586 0.178998 -0.862019 -0.474219 0.276118 -0.50442 -0.818119 0.409538 -0.756255 -0.510252 0.248267 -0.876212 -0.413057 0.248344 -0.879308 -0.406377 0.0705299 -0.978282 -0.19491 0.487965 -0.631534 -0.60254 0.592251 -0.667938 -0.450664 0.63171 -0.475299 -0.612399 0.623333 -0.646171 -0.440363 0.636671 -0.565157 -0.524641 0.0892425 -0.896205 -0.434572 0.144682 -0.985129 -0.0926724 0.380413 -0.782923 -0.492258 0.398911 -0.86227 -0.312026 0.625503 -0.576607 -0.525614 0.628863 -0.622636 -0.465679 0.783547 -0.311784 -0.537442 0.783763 -0.314933 -0.535287 0.105355 -0.747248 -0.656141 0.1177 -0.914787 -0.386408 0.378391 -0.674346 -0.634096 0.366267 -0.774503 -0.515746 0.609555 -0.517656 -0.600396 0.600371 -0.562748 -0.568216 0.777165 -0.308917 -0.548257 0.777298 -0.308136 -0.548508 0.137388 -0.984584 -0.108258 0.740597 -0.381986 -0.552814 0.771089 -0.332314 -0.543129 0.785601 -0.314949 -0.532577 0.749906 -0.267296 -0.60514 0.747741 -0.36693 -0.553396 0.642811 -0.59625 -0.480916 0.629193 -0.622651 -0.465211 0.41545 -0.854917 -0.310674 0.406315 -0.862668 -0.301184 0.15455 -0.98124 -0.11525 0.140859 -0.985119 -0.0984859 0 -0.997304 0.0733864 0.00381736 -0.976421 0.215841 -0.00526099 -0.998569 0.0532237 0.00558724 -0.936048 0.351828 0 -0.898361 0.439258 0.0464841 -0.947548 0.316215 0.035882 -0.995069 -0.092464 0.777861 -0.293966 -0.555442 0.763092 -0.266369 -0.588845 0.747336 -0.277931 -0.603525 0.620825 -0.709355 -0.333754 0.873448 -0.448258 -0.190138 0.61435 -0.714974 -0.333747 0.532168 -0.841458 -0.0935153 0.563258 -0.825876 0.0258807 0.328438 -0.944419 0.0141544 0.247739 -0.928642 0.276135 0.0419242 -0.98242 0.181917 0.265014 -0.868205 0.419509 0.365718 -0.929245 0.0524751 0.488154 -0.755443 0.437048 0.171915 -0.900276 -0.399936 0.524815 -0.842261 0.123151 0.633868 -0.741764 -0.219085 0.213913 -0.976746 -0.0144267 0.33064 -0.886581 -0.323498 0.454141 -0.851741 -0.261329 0.568153 -0.670375 -0.477283 0.657804 -0.595435 -0.46125 0.735432 -0.27316 -0.6201 0.740847 -0.26733 -0.616182 0.770922 -0.297328 -0.563272 0.738668 -0.294009 -0.606571 0.739052 -0.531337 -0.414104 0.805607 -0.496785 -0.322804 0.578997 -0.72231 -0.378193 0.478616 -0.863976 -0.156437 0.342952 -0.91244 -0.223241 0.231375 -0.963956 0.131352 0.0385457 -0.99824 0.0450712 0.0783084 -0.933188 0.350753 0.204676 -0.967389 0.149222 0.222373 -0.968327 0.113546 0.688094 -0.654856 0.312555 0.436737 -0.889126 -0.136808 0.584881 -0.767577 -0.262183 0.632528 -0.601954 -0.487402 0.737581 -0.43734 -0.514498 0.819874 -0.261741 -0.509213 0.222084 -0.973646 0.0518953 0.233788 -0.972284 -0.00256514 0.461959 -0.876585 -0.134878 -0.0939957 -0.68102 -0.726207 0.586724 -0.755437 -0.291666 0.647989 -0.625167 -0.435059 0 -0.971254 -0.238044 0 -0.897617 -0.440776 -0.00455689 -0.854275 -0.519801 0.00463522 -0.973256 -0.229675 0.0123317 -0.995829 -0.090405 0.453784 -0.6802 -0.57568 0.67048 -0.258144 -0.695571 0.203555 -0.836398 -0.508924 0.204616 -0.834382 -0.5118 0.347084 -0.742974 -0.572295 0.0189001 -0.971081 -0.238002 0.203918 -0.879141 -0.43073 0.612985 -0.78826 -0.0538139 0.336121 -0.7179 -0.609624 0.546121 -0.590954 -0.593739 0.546313 -0.627845 -0.554394 0.556227 -0.502111 -0.66219 0.679659 -0.213495 -0.701772 0.644811 -0.23679 -0.726739 0.648901 -0.237451 -0.722872 0.53241 -0.50131 -0.682076 0.569109 -0.633341 -0.524399 0.606162 -0.285532 -0.74232 0.663003 -0.30601 -0.683216 0.273083 -0.688186 -0.67218 0.192783 -0.82692 -0.528241 -0.00407959 -0.87249 -0.488615 0.0274992 -0.87681 -0.48005 0.191775 -0.931751 -0.308322 0.0271811 -0.934942 -0.353759 0.200234 -0.963289 -0.178832 0.0280169 -0.97385 -0.225457 0.67506 -0.212507 -0.706495 0.682469 -0.22886 -0.694161 0.495585 -0.488748 -0.717998 0.499667 -0.455809 -0.736595 0.45395 -0.556712 -0.695702 0.39692 -0.638181 -0.659681 0.265081 -0.722399 -0.638648 0.417707 -0.772078 -0.478974 0.253568 -0.845471 -0.469981 0.427963 -0.806478 -0.407971 0.254301 -0.905331 -0.340157 0.124485 -0.983262 -0.133042 0.122229 -0.983745 -0.131554 0.113935 -0.983746 -0.138789 0.119085 -0.982601 -0.142525 0.286832 -0.906747 -0.309092 0.352925 -0.847001 -0.397534 0.402474 -0.806513 -0.433071 0.557486 -0.573593 -0.600168 0.512374 -0.633259 -0.580048 0.681772 -0.223974 -0.696435 0.645846 -0.305879 -0.699515 0.626021 -0.206924 -0.751851 0.626653 -0.224217 -0.746346 0.572187 -0.449105 -0.686226 0.533857 -0.57371 -0.621171 0.502161 -0.622726 -0.600038 0.340179 -0.846916 -0.40867 0.399443 -0.800986 -0.445944 0.276064 -0.902923 -0.329422 0 -0.989116 0.14714 -0.00481288 -0.995655 0.0929912 0.00516592 -0.92128 0.388865 0 -0.898722 0.43852 0.698483 -0.483212 -0.527853 0.628414 -0.220832 -0.745874 0.611709 -0.223123 -0.758965 0.655789 -0.241396 -0.71531 0.258962 -0.902925 -0.343023 0.241792 -0.87778 -0.413569 0.297143 -0.941069 0.161538 0.313031 -0.940712 0.130661 0.391358 -0.920014 0.0203386 0.405998 -0.910863 0.0741277 0.457295 -0.859116 -0.229783 0.522281 -0.847656 -0.0932824 0.540456 -0.809018 -0.231078 0.240993 -0.91729 0.31702 0.17385 -0.971774 0.159473 0.107982 -0.843875 0.525562 0.197169 -0.977171 -0.0791226 0.0227321 -0.996177 -0.0843458 0.210326 -0.975712 0.0612282 0.00726882 -0.984636 0.174469 0.0271987 -0.981429 0.18989 0.556162 -0.743404 -0.371531 0.505628 -0.783235 -0.361777 0.470414 -0.854557 -0.220097 0.424339 -0.844847 -0.325839 0.356962 -0.934101 -0.00577131 0.297829 -0.942557 -0.151275 0.229046 -0.952491 0.200748 0.602876 -0.206968 -0.770522 0.583969 -0.448909 -0.676359 0.490024 -0.632335 -0.600024 0.481872 -0.622833 -0.616343 0.41416 -0.800297 -0.433585 0.654249 -0.242072 -0.716491 0.609855 -0.257242 -0.749603 0.634837 -0.559241 -0.533134 0.609338 -0.510812 -0.606447 0.590472 -0.680308 -0.434193 0.490135 -0.705378 -0.512064 0.436854 -0.842044 -0.316418 0.46121 -0.853107 -0.243913 0.26359 -0.948354 -0.176479 0.210697 -0.975561 0.0623448 0.161152 -0.98662 0.0247049 0.0981241 -0.91895 0.381971 0.0303364 -0.943094 0.33114 0.333412 -0.841023 -0.426048 0.238839 -0.970094 -0.0432922 0.175639 -0.981715 0.073395 0.159672 -0.953277 0.256453 -0.0685369 -0.919126 0.387955 0.740658 -0.193022 -0.643559 0.432424 -0.630591 -0.644488 0.552776 -0.555988 -0.620738 0.51133 -0.760626 -0.399988 0.453268 -0.804353 -0.384141 0.464432 -0.839544 -0.281902 0.462944 -0.875912 -0.135869 0.174979 -0.984061 0.0317338 0.180232 -0.979362 0.0914695 0.233003 -0.971513 -0.0432596 0.264465 -0.964361 0.00816618 0.272075 -0.938962 -0.210536 0 0.139418 0.990234 0.00218678 0.159373 0.987216 -0.000265737 0.311547 0.950231 0.0015486 0.439091 0.898441 0.0121094 0.538419 0.84259 0.00163526 0.621415 0.78348 0 0.991774 0.127999 0.000464639 0.992223 0.124472 -0.000545566 0.93199 0.362483 0.0132566 0.875003 0.483937 0.000346311 0.812941 0.582346 -4.19397e-05 0.720718 0.693228 0.354859 0.551525 -0.754915 0.371063 0.154324 0.915694 0.718398 0.163483 0.676149 0.875374 0.0452524 -0.481325 0.669638 0.263108 -0.694521 0.933239 0.216528 -0.286672 0.93417 0.197044 -0.297489 0.955408 0.27384 -0.110488 0.958134 0.252793 -0.134444 0.959766 0.280562 -0.0115882 0.958918 0.283675 0.00232695 0.958791 0.284111 0.000706152 0.958709 0.248862 0.137638 0.933808 0.357391 0.0165858 0.933854 0.0292521 0.356457 0.843477 0.526638 0.105828 0.950492 0.167324 0.261854 0.942897 0.329118 0.0512453 0.936725 0.349037 0.026824 0.324021 0.946018 0.00776 0.506618 0.761212 -0.404839 0.381489 0.834859 -0.396833 0.332023 0.929602 -0.160004 0.716536 0.14471 -0.682375 0.716483 0.319276 -0.620254 0.720423 0.382977 -0.578204 0.697332 0.448094 -0.55941 0.690626 0.638525 -0.33959 0.690626 0.638525 -0.33959 0.690626 0.723188 0.00593223 0.690626 0.723188 0.00593215 0.690626 0.632868 0.350019 0.690625 0.632868 0.350021 0.690625 0.389418 0.609419 0.690627 0.38942 0.609415 0.701708 0.207282 0.681645 0.53418 0.140498 0.833614 0.293773 0.955319 0.0326154 0.254447 0.959132 0.123786 0.249038 0.847508 0.468732 0.249039 0.847509 0.468731 0.24904 0.521494 0.816103 0.24904 0.521494 0.816103 0.256208 0.265225 0.929523 0.123217 0.158159 0.979695 0.570206 0.184945 -0.800413 0.637696 0.217982 -0.738802 0.595909 0.217631 -0.773 0.526954 0.549178 -0.648632 0.619967 0.208907 -0.756306 0.613516 0.214997 -0.759852 0.656749 0.503479 -0.561417 0.63026 0.554595 -0.54332 0.624897 0.684631 -0.375212 0.567663 0.751346 -0.336507 0.548714 0.820501 -0.160283 0.667587 0.715615 -0.205484 0.723586 0.651575 -0.227757 0.735988 0.481153 -0.47625 0.731322 0.490629 -0.473763 0.704219 0.258331 -0.661318 0.715418 0.164961 -0.678944 0.618082 0.0847396 -0.781533 0.0218285 0.893366 0.448799 0.129726 0.896235 0.424186 0.155556 0.950588 0.268673 0.299569 0.879369 0.370093 0.169267 0.908378 0.382358 0.12244 0.766696 0.630227 0.330578 0.929652 0.16268 0.366542 0.911291 0.187605 0.332976 0.801429 0.496828 0.186019 0.848114 0.496084 0.158044 0.742847 0.650539 0.0332459 0.748565 0.662228 0.590074 0.488495 -0.642795 0.447771 0.686538 -0.572859 0.419919 0.773821 -0.474204 0.349092 0.837303 -0.420785 0.328296 0.885626 -0.328464 0.234715 0.940226 -0.246748 0.219874 0.959024 -0.178688 0.116317 0.991119 -0.0644531 0.111274 0.99323 -0.0333471 0.000910736 0.99384 0.11082 0.666182 0.745748 -0.00781405 0.661376 0.748419 0.0494977 0.455481 0.885035 -0.0961813 0.414527 0.896181 0.158197 0.313896 0.949079 -0.0268119 0.273398 0.929338 0.248161 0.664342 0.74588 0.0480876 0.538849 0.827228 0.159169 0.512718 0.755321 0.408179 0.472795 0.784495 0.401289 0.335517 0.724525 0.602073 0.302839 0.744831 0.594571 0.102823 0.612362 0.783862 0.575668 0.192579 -0.794682 0.586236 0.200568 -0.784921 0.594573 0.487583 -0.639332 0.566984 0.536531 -0.625031 0.550285 0.668937 -0.499709 0.49762 0.731803 -0.465659 0.474402 0.815611 -0.331243 0.393669 0.878521 -0.270601 0.371814 0.916308 -0.148773 0.267088 0.961869 -0.0589203 0.251478 0.967332 0.0320571 0.132451 0.980033 0.148298 0.124397 0.972102 0.198855 0.0023668 0.942624 0.333848 0.107172 0.982347 -0.153322 0.165387 0.961687 -0.218644 0.0439544 0.996945 -0.0645601 0.0534468 0.995747 -0.0750468 0.565181 0.162418 -0.808821 0.560752 0.184927 -0.807068 0.483566 0.535982 -0.692017 0.476719 0.549848 -0.685861 0.316702 0.833216 -0.453267 0.371719 0.775466 -0.510371 0.262483 0.888154 -0.377206 0.386586 0.269321 -0.882053 0.395296 0.534522 -0.747012 0.140574 0.981333 -0.131242 0.0333009 0.923361 -0.382486 0.120653 0.936766 -0.328501 0.0307992 0.835944 -0.547951 0.494356 0.162256 -0.853982 0.518365 0.111839 -0.847815 0.441481 0.0916394 -0.892579 0.464773 0.0551902 -0.883708 0.312231 0.83328 -0.456243 0.227055 0.747903 -0.623769 0.276384 0.75552 -0.593971 0.213344 0.652585 -0.72706 0.175401 0.640982 -0.747246 0.104497 0.85668 -0.505153 0.0294195 0.717648 -0.695785 0.428795 0.508153 -0.746938 0.375772 0.396286 -0.837707 0.308934 0.377477 -0.872967 0.227494 0.608429 -0.760303 0.184085 0.413206 -0.891837 0.0878868 0.742112 -0.664489 0.0295997 0.56508 -0.824505 0.0767613 0.964963 -0.250908 0.223848 0.96826 -0.111197 0.226581 0.973972 -0.00636841 0.1282 0.620821 -0.773399 0.0720425 0.990935 -0.113389 0.0348158 0.995012 -0.0934864 0.0149612 0.998296 -0.0564023 0.0382375 0.999157 -0.0149436 0.0920992 0.892639 0.441264 0.556822 0.770705 -0.309779 0.750658 0.446871 -0.48664 0.568989 0.549295 -0.611985 0.242177 0.893783 0.377496 0.361861 0.892416 0.269538 0.176476 0.980567 0.0857007 0.0121054 0.858775 0.512209 0.172715 0.876581 0.449194 0.0869644 0.986278 0.140329 0.301149 0.944662 0.130086 -0.487602 0.849191 0.202776 0.421609 0.779788 0.462792 -0.349073 0.739965 0.574978 0.180137 0.649741 0.738504 0.0153821 0.998995 -0.0421099 0.0162237 0.997582 -0.0675764 -0.103901 0.933742 -0.342535 0.625328 0.750582 -0.213521 0.19579 0.965531 -0.171512 0.16901 0.964963 -0.200705 0.188966 0.648764 -0.737155 0.34105 0.495471 -0.79887 0.343421 0.499724 -0.795197 0.364326 0.256601 -0.895222 0.493692 0.495054 -0.714975 0.589133 0.128406 -0.797768 0.584801 0.128499 -0.800935 -0.462863 0.699957 -0.543891 0.208742 0.775341 -0.596047 0.158137 0.78406 -0.600202 0.158133 0.784058 -0.600206 0.418135 0.784058 -0.458711 0.418136 0.78406 -0.458708 0.508815 0.797875 -0.32327 0.487916 0.853258 -0.18409 0.529353 0.844011 -0.0862047 0.440436 0.896394 0.0499283 0.438479 0.897633 0.0446262 0.421002 0.866394 0.268549 0.0129576 0.766458 0.642163 0.144139 0.773217 0.617543 0.00992112 0.840914 0.541077 0.128637 0.857848 0.497544 0.147699 0.92758 0.343192 0.270392 0.910768 0.312075 0.293152 0.955979 0.0128622 0.422708 0.883643 0.201228 0.322973 0.922753 0.210273 0.307556 0.846533 0.434501 0.329324 0.840408 0.430419 0.161883 0.857866 0.487708 0.528183 0.460023 -0.713724 0.496686 0.523365 -0.692381 0.503886 0.666883 -0.548969 0.447956 0.738703 -0.50364 0.442506 0.82891 -0.342194 0.360437 0.89366 -0.267316 0.349107 0.92986 -0.116122 0.246609 0.969036 -0.0123755 0.235133 0.966281 0.10495 0.122819 0.965395 0.230062 0.114633 0.946231 0.302499 0.00263911 0.898984 0.437973 0.00205127 0.997765 0.0667945 0.082589 0.994365 -0.0664659 0.0902103 0.987103 -0.132252 0.174226 0.95136 -0.254087 0.182438 0.923558 -0.337279 0.252972 0.8641 -0.435129 0.267993 0.803319 -0.531844 0.324081 0.737928 -0.591975 0.346701 0.566662 -0.747458 0.486843 0.0355692 -0.872765 0.511443 0.0263541 -0.858913 0.50367 0.184314 -0.844005 0.448852 0.139854 -0.882594 0.546681 0.114679 -0.829451 0.50358 0.279795 -0.817387 0.575406 0.25309 -0.777723 0.603332 0.484039 -0.633796 0.548179 0.579979 -0.602598 0.611507 0.675906 -0.41135 0.54294 0.777765 -0.316698 0.543957 0.82286 -0.164354 0.478799 0.870544 -0.113598 0.436323 0.898742 0.0434116 0.485783 0.0760883 -0.870761 0.419115 0.0797807 -0.904421 0.431365 0.380098 -0.818199 0.404367 0.483975 -0.776051 0.388578 0.675792 -0.626349 0.375188 0.692858 -0.615778 0.368929 0.793139 -0.484584 0.298609 0.858338 -0.417239 0.288725 0.912996 -0.288228 0.20376 0.960009 -0.192 0.194101 0.977305 -0.0848532 0.101805 0.994171 0.0354874 0.0947705 0.989527 0.108883 0.00277906 0.969669 0.244406 0.265743 -0.102519 -0.958577 0.249723 -0.143499 -0.957625 0.319892 -0.0858029 -0.943561 0.0642659 0.97462 -0.214442 0.0587624 0.976696 -0.206424 0.0960798 0.975212 -0.199323 0.150171 0.951816 -0.267386 0.0417854 0.99517 -0.0888319 0.275309 0.214469 -0.937128 0.263662 0.263159 -0.928025 0.250561 0.457184 -0.853348 0.367493 -0.0606942 -0.928044 0.358605 -0.0355259 -0.932813 0.361407 0.26334 -0.894448 0.292329 0.493066 -0.819408 0.238116 0.492395 -0.837167 0.0686854 0.98081 -0.182468 0.0819795 0.97671 -0.198285 0.221242 0.795423 -0.564229 0.126979 -0.167497 -0.977661 0.13026 -0.174136 -0.976068 0.142854 0.20551 -0.968173 0.140234 0.214529 -0.966598 0.125312 0.426736 -0.895653 0.117786 0.456981 -0.881643 0.118189 0.607381 -0.78557 0.0445561 0.803304 -0.593901 0.0560992 0.816544 -0.57455 0.0369666 0.926419 -0.374675 0.436599 0.380122 -0.815407 0.361842 0.567098 -0.739913 0.273181 0.795356 -0.541093 0.331167 0.737899 -0.588076 0.223557 0.864007 -0.451126 0.0211203 0.987108 -0.158655 0.00479719 0.959959 -0.280099 0.0394472 0.975437 -0.216718 0.111565 0.761773 -0.638165 0.176664 0.761389 -0.623761 0.18178 0.777049 -0.60262 0.240087 0.776904 -0.582047 0.326561 0.432658 -0.840337 0.40995 0.432545 -0.803023 0.428169 0.00939686 -0.90365 0.448013 0.0760487 -0.890787 -2.45095e-07 -0.226568 -0.973995 0.000653201 0.985971 -0.166914 -1.08175e-07 0.987328 -0.158693 -0.0046841 -0.16886 -0.985629 0.00625907 0.207634 -0.978187 -3.62298e-07 0.14972 -0.988728 -3.80997e-07 0.430124 -0.90277 0.0053135 0.551633 -0.83407 0.00023924 0.611666 -0.791116 -0.000376464 0.851256 -0.524751 0.00618378 0.817816 -0.575447 -0.000235966 0.927052 -0.374932 0 0.992266 -0.124131 0.000449938 0.991774 -0.127998 -0.000546032 0.93199 -0.362483 0.0264801 0.804122 -0.593874 0.000509279 0.875078 -0.483981 -3.19837e-05 0.72034 -0.693621 0.00165171 0.620679 -0.784063 0.012098 0.538419 -0.84259 0.00153071 0.438232 -0.898861 -0.000278669 0.311011 -0.950406 0.00225969 0.159373 -0.987216 0 0.138635 -0.990344 0.806719 0.0924265 0.583662 0.171758 0.157005 -0.972548 0.737415 0.326082 -0.591514 0.631692 0.182478 -0.753437 0.54008 0.139888 -0.829906 0.948812 0.21516 -0.231219 0.95489 0.1599 -0.250232 0.956308 0.255838 -0.141496 0.960211 0.278126 -0.0253249 0.958917 0.283677 -0.00232707 0.958926 0.283646 -0.00220571 0.95908 0.249979 0.132948 0.93859 0.344012 0.0265603 0.953827 0.165859 0.250411 0.836065 0.541793 0.0863521 0.941994 0.0959475 0.321622 0.579585 0.147942 0.801371 0.665023 0.173895 0.726296 0.719492 0.249842 0.648005 0.716492 0.31926 0.620251 0.720432 0.382968 0.578197 0.537274 0.80087 0.264468 0.387129 0.814058 0.432945 0.303952 0.952655 -0.00781526 0.320351 0.945854 -0.0522956 0.33203 0.9296 0.159999 0.882433 0.0845032 -0.462787 0.698334 0.128362 -0.704169 0.690642 0.389412 -0.609403 0.690642 0.389411 -0.609403 0.690642 0.632855 -0.350012 0.690642 0.632855 -0.350012 0.690642 0.723173 -0.00593237 0.690642 0.723173 -0.00593268 0.690641 0.638512 0.339583 0.690641 0.638512 0.339584 0.697346 0.44808 0.559405 0.354888 0.551527 0.754899 0.416405 0.151107 -0.896534 0.256086 0.254898 -0.932442 0.249045 0.521492 -0.816102 0.249043 0.521493 -0.816102 0.249044 0.847508 -0.46873 0.249047 0.847506 -0.468732 0.254455 0.95913 -0.123785 0.59186 0.18489 0.784549 0.712748 0.660355 0.236478 0.743287 0.648873 0.162752 0.695196 0.51552 0.500941 0.624911 0.0793044 0.776657 0.613461 0.0822206 0.785434 0.721729 0.169186 0.671181 0.714139 0.165604 0.680133 0.708066 0.386366 0.59107 0.781744 0.509656 0.359343 0.590688 0.528809 0.609466 0.568757 0.492501 0.658755 0.588901 0.220228 0.777621 0.569278 0.25297 0.782259 0.539444 0.497414 0.679396 0.553527 0.547905 0.627223 0.451551 0.8618 0.231089 0.408655 0.829912 0.379798 0.340215 0.940321 0.00702052 0.288462 0.934411 0.208963 0.215454 0.953861 -0.209115 0.15845 0.986792 0.0336825 -0.00147062 0.829775 -0.558096 0.0191702 0.824631 -0.565347 0.0528738 0.805238 -0.59059 0.12914 0.525761 -0.840773 0.18054 0.751002 -0.635138 0.338412 0.796167 -0.501593 0.344985 0.728162 -0.592255 0.36821 0.835032 -0.408832 0.52403 0.797247 -0.299648 0.525944 0.784324 -0.328966 0.534221 0.844201 0.0439715 0.64503 0.745324 -0.168608 0.668952 0.741614 0.0501176 0.142238 0.961487 0.235184 0.181315 0.983271 0.0174329 0.260855 0.888096 0.37847 0.296208 0.933195 0.203489 0.367132 0.775416 0.513755 0.392982 0.832373 0.390795 0.447979 0.686668 0.57254 0.505443 0.678285 0.533346 0.537825 0.719728 0.439018 0.632154 0.221349 0.742554 0.612865 0.211484 0.761362 0.656923 0.539373 0.52681 0.627487 0.515373 0.583652 0.616297 0.725654 0.305949 0.570193 0.708137 0.416441 0.528164 0.847779 0.0480965 0.465367 0.856966 0.221455 0.402726 0.890013 -0.213749 0.328736 0.944301 0.0150866 0.256026 0.857665 -0.44594 0.180882 0.966024 -0.184604 0.144307 0.888304 -0.435994 0.0888195 0.912995 -0.398185 0.0312531 0.990255 -0.135716 0.075507 0.982189 -0.172057 0.0281747 0.995255 0.0931284 0.111588 0.982304 0.150423 0.0439712 0.996943 0.0645848 0.0534647 0.995744 0.075072 0.563063 0.184934 0.805456 0.562902 0.162427 0.810406 0.478523 0.549861 0.684594 0.481779 0.536011 0.69324 0.361264 0.775392 0.517933 0.321816 0.833113 0.449841 0.262532 0.88811 0.377277 0.15679 0.961699 0.224837 0.510587 0.162389 0.844352 0.129657 0.62158 0.772546 0.00585569 0.707318 0.706871 0.395361 0.534525 0.746975 0.342465 0.762039 0.549559 0.212015 0.828623 0.518106 0.0130075 0.976821 0.213663 0.17316 0.940178 0.293395 0.0110133 0.918597 0.395041 0.343132 0.244459 0.906918 0.340865 0.387437 0.856565 0.452639 0.0480986 0.890395 0.281284 0.467576 0.838005 0.111202 0.678458 0.726174 0.175452 0.642075 0.746295 0.141473 0.761856 0.632109 0.00854482 0.829533 0.558393 0.1555 0.868169 0.471278 0.194848 0.741926 0.641545 0.307886 0.67717 0.668316 0.338997 0.575464 0.744259 0.453796 0.416491 0.787784 0.498674 0.106892 0.860173 0.45115 0.0944796 0.887433 0.418133 0.78406 0.458709 0.421609 0.779788 -0.462792 0.0382381 0.999157 0.0149429 0.0153821 0.998995 0.0421099 0.556821 0.770706 0.309778 0.529354 0.84401 0.0862051 0.176476 0.980567 -0.085701 0.41333 0.851772 -0.321937 0.0869644 0.986278 -0.140329 0.384746 0.889352 -0.247031 0.242183 0.893783 -0.377491 0.162911 0.896147 -0.412772 0.130562 0.87443 -0.467254 0.0121054 0.858775 -0.512209 0.180137 0.649741 -0.738504 -0.349073 0.739965 -0.574978 0.442549 0.895516 -0.0469231 0.438344 0.897451 -0.0493586 0.226581 0.973972 0.00636836 0.508814 0.797876 0.323269 0.487916 0.853258 0.184091 0.223847 0.96826 0.111197 0.364321 0.256604 0.895223 0.584801 0.128499 0.800935 0.589137 0.128406 0.797765 0.750659 0.446869 0.486641 0.56899 0.549294 0.611986 0.493695 0.495054 0.714973 0.34105 0.495471 0.79887 0.343417 0.499717 0.795203 -0.462862 0.699958 0.543892 0.0720373 0.990936 0.113389 0.0348185 0.995011 0.0934901 0.0162237 0.997582 0.0675764 -0.103901 0.933742 0.342535 0.625328 0.750582 0.213521 0.0149612 0.998296 0.0564023 -0.487601 0.849192 -0.202777 0.301154 0.944661 -0.130086 0.208743 0.775341 0.596047 0.158137 0.78406 0.600202 0.0767631 0.964962 0.250908 0.195778 0.965534 0.17151 0.1282 0.620821 0.773399 0.188966 0.648764 0.737155 0.158137 0.78406 0.600202 0.418136 0.784059 0.458708 0.169011 0.964962 0.200706 0.0340804 0.888355 -0.45789 0.00531155 0.99767 -0.0680176 -0.00348904 0.997096 -0.0760711 0.359173 0.849367 0.386743 0.302588 0.801061 0.516471 0.273734 0.949167 0.155411 0.212705 0.921917 0.323767 0.175859 0.98153 -0.0753208 0.115047 0.985967 0.120969 0.0757433 0.955781 -0.284158 0.0190129 0.99695 -0.0756883 0.110763 0.70302 -0.702491 0.147013 0.865926 -0.478078 0.281346 0.904483 -0.320555 0.283707 0.870075 -0.403087 0.307222 0.951364 -0.0228092 0.414953 0.870408 -0.264962 0.437102 0.898342 -0.0438503 0.496827 0.846474 0.191427 0.539798 0.837951 0.0803537 0.528831 0.712828 0.460667 0.639054 0.72207 0.264999 0.50582 0.521214 0.687373 0.603134 0.550297 0.57741 0.576127 0.253286 0.777125 0.448939 0.138261 0.882801 0.418767 0.0759257 0.904914 0.425567 0.481089 0.76645 0.403513 0.379747 0.832448 0.400942 0.56747 0.719183 0.3755 0.693281 0.615111 0.319751 0.75777 0.568809 0.308665 0.80053 0.513691 0.278796 0.736993 0.615722 0.231284 0.920368 0.315325 0.192778 0.862887 0.467186 0.156398 0.982397 0.102159 0.107144 0.950851 0.290521 0.0825986 0.994364 0.0664606 0.0245564 0.965989 -0.257414 0.0898214 0.867653 -0.488989 0.139566 0.988605 -0.0564106 0.211835 0.935518 -0.282723 0.256897 0.952401 0.164124 0.330615 0.943089 -0.0357377 0.363816 0.848473 0.384358 0.431584 0.872669 0.228439 0.445365 0.681211 0.581035 0.501241 0.722825 0.475691 0.490114 0.468994 0.734733 0.531919 0.512375 0.674192 0.470315 0.134013 0.872264 0.621167 0.234503 0.74777 0.48672 0.0360187 0.872815 0.378513 0.0747084 0.922576 0.55735 0.149964 0.816622 0.274818 0.263753 0.924613 0.417115 0.379962 0.825617 0.0397741 0.975044 0.218421 0.0793788 0.976745 0.19917 0.0389867 0.974666 0.220241 0.0185092 0.975785 0.217946 0.017778 0.975592 0.21887 0.18936 -0.139 0.972019 0.36178 0.263786 0.894166 0.313658 0.432465 0.845336 0.41855 0.432438 0.798632 0.258401 -0.138856 0.956006 0.262824 -0.145967 0.953739 0.31294 -0.089566 0.94554 0.356927 -0.0655513 0.931829 0.366673 -0.0382491 0.929563 0.428596 0.0158881 0.903356 0.445517 0.0760412 0.892038 0.146904 0.154847 0.976955 0.0615154 0.975538 0.211047 0.0618889 0.976737 0.205316 0.177047 0.761353 0.623695 0.182131 0.777154 0.602378 0.242752 0.457413 0.855479 0.134773 0.951731 0.275762 0.223613 0.864008 0.451096 0.288117 0.794872 0.534011 0.30165 0.737704 0.603987 0.36193 0.5671 0.739868 0.120915 0.457069 0.881174 0.126636 0.494823 0.859717 0.0803006 0.760723 0.64409 0.0403302 0.666262 0.744626 0.0898391 0.855228 0.510405 0.0557858 0.818527 0.571753 0.0423035 0.901488 0.430731 0.0433778 0.995179 0.0879636 0.106525 0.978277 0.177838 0.0789758 0.978572 0.190156 0.221495 0.795438 0.564108 0.240304 0.777016 0.581807 0.317403 0.493138 0.809982 0.247235 0.492907 0.834217 0.265671 0.21465 0.939864 0.168481 0.214886 0.961997 0.107513 -0.198351 0.974217 0.119184 -0.227306 0.966502 -4.61233e-07 -0.22657 0.973995 0.00019448 -0.228954 0.973437 -0.000264555 0.14972 0.988728 -0.00100744 0.156545 0.98767 0.000670734 0.498838 0.866695 0.00511501 0.55163 0.834073 -5.09387e-07 0.666804 0.745233 -5.09517e-07 0.819804 0.572644 0.00449976 0.851248 0.524745 0.00149938 0.902295 0.431117 -0.00572842 0.985955 0.166912 -1.49586e-07 0.975746 0.218905 0 -0.898688 -0.438588 0.00517055 -0.92128 -0.388865 -0.00482177 -0.995655 -0.0929912 0 -0.989105 -0.147213 0.504422 -0.557483 0.659372 0.740658 -0.193022 0.643559 0.453268 -0.804353 0.384141 0.511331 -0.760625 0.399988 0.54927 -0.595105 0.586646 0.238839 -0.970094 0.0432922 0.462944 -0.875912 0.135869 0.464432 -0.839544 0.281902 -0.0685369 -0.919126 -0.387955 0.159672 -0.953277 -0.256453 0.175639 -0.981715 -0.0733952 0.175832 -0.980155 -0.0915435 0.1978 -0.979072 -0.0478909 0.225274 -0.974029 0.0227777 0.267424 -0.9626 0.0434299 0.272075 -0.938962 0.210536 0.333412 -0.841023 0.426048 0.297203 -0.941043 -0.161582 0.253466 -0.962692 -0.0947556 0.655743 -0.24142 0.715344 0.654249 -0.242075 0.71649 0.629923 -0.217707 0.74552 0.613996 -0.224621 0.756674 0.602875 -0.208826 0.770022 0.608506 -0.206973 0.766083 0.283307 -0.957173 0.0596357 0.378507 -0.921274 0.0893692 0.414016 -0.872209 0.260465 0.143751 -0.98006 -0.137181 0.272483 -0.933424 -0.233395 0.159503 -0.95334 -0.256325 0.26931 -0.878265 0.395124 0.168208 -0.985368 -0.0274892 0.0396777 -0.978047 0.204572 0.178477 -0.897348 0.403625 0.416836 -0.798753 0.433868 0.475459 -0.640245 0.603345 0.496995 -0.620891 0.60621 0.58393 -0.448909 0.676392 0.556209 -0.743383 0.371501 0.540524 -0.808986 0.23103 0.533889 -0.828155 0.170651 0.44747 -0.882215 0.146519 0.414278 -0.909345 -0.0382818 0.371788 -0.927008 -0.0492918 0.31311 -0.940678 -0.130718 0.609857 -0.257245 0.749599 0.636889 -0.503312 0.583994 0.698175 -0.483284 0.528193 0.490029 -0.705295 0.51228 0.423483 -0.862539 0.276926 0.606896 -0.572006 0.551803 0.577398 -0.725143 0.375206 0.52647 -0.697793 0.48571 0.486081 -0.82854 0.277934 0.50802 -0.82124 0.259771 0.263512 -0.948304 0.176863 0.210817 -0.975615 -0.0610835 0.209473 -0.97591 -0.0610036 0.00725498 -0.984719 -0.174 0.122016 -0.957516 -0.261297 0.00786852 -0.949168 -0.314673 0.134017 -0.905922 -0.401678 0.00952037 -0.892032 -0.451872 0.124024 -0.98326 0.133485 0.124378 -0.983128 0.134124 0.287087 -0.906755 0.30883 0.356585 -0.843863 0.400927 0.626114 -0.206922 0.751775 0.6267 -0.223142 0.746629 0.119086 -0.982601 0.142526 0.116856 -0.983102 0.140909 0.275814 -0.902928 0.329618 0.353241 -0.843866 0.403871 0.384343 -0.79994 0.460844 0.527275 -0.570727 0.629485 0.515497 -0.620538 0.590928 0.572339 -0.449103 0.686101 0.402208 -0.806517 0.433311 0.526853 -0.633671 0.566469 0.549954 -0.570811 0.609693 0.660763 -0.306003 0.685387 0.662088 -0.223135 0.715437 0 -0.997151 0.0754325 0.00416189 -0.971246 0.238042 0.00459813 -0.973104 0.23032 -0.00449688 -0.854273 0.519806 0 -0.897288 0.441445 0.302178 -0.737794 0.603612 0.675625 -0.213897 0.705535 0.644807 -0.236787 0.726743 0.295166 -0.705455 0.644368 0.257584 -0.71958 0.644868 0.192883 -0.826994 0.528088 0.168663 -0.981632 0.0891669 0.0482308 -0.941511 0.333512 0.158221 -0.961817 0.223324 0.0489079 -0.887271 0.458649 0.0136728 -0.870264 0.492396 0.397031 -0.638274 0.659525 0.45402 -0.556767 0.695612 0.487067 -0.486031 0.725631 0.514344 -0.467872 0.718711 0.682363 -0.228888 0.694256 0.648908 -0.237449 0.722867 0.681555 -0.212174 0.700332 0.606698 -0.304983 0.7341 0.593998 -0.520317 0.613544 0.489111 -0.632144 0.600969 0.384854 -0.819316 0.424981 0.42841 -0.806477 0.407504 0.254514 -0.905351 0.339944 0.206903 -0.835796 0.508563 0.203518 -0.834972 0.511275 0.347089 -0.74297 0.572298 0.453779 -0.680202 0.575682 0.670483 -0.258146 0.695567 0.55623 -0.502113 0.662186 0.550953 -0.591187 0.589023 0.521131 -0.609173 0.597772 0.336129 -0.717898 0.609622 0.612986 -0.788259 0.053813 0.203918 -0.879141 0.43073 0.0189001 -0.971081 0.238002 0 -0.860722 -0.509075 0.00554007 -0.935354 -0.353671 0.0065942 -0.929981 -0.367548 0.000787401 -0.974456 -0.224577 -0.000596879 -0.998475 -0.0551959 0 -0.99719 -0.0749211 0.389348 -0.800222 0.456129 0.630375 -0.611935 0.477664 0.374364 -0.878158 0.297809 0.400054 -0.848139 0.3473 0.402912 -0.816957 0.412605 -0.21649 -0.913186 -0.345289 0.102854 -0.958337 -0.266481 0.144911 -0.984731 -0.0964654 0.664279 -0.704271 -0.250471 0.255538 -0.965325 -0.0533633 0.143934 -0.989558 0.00760697 0.393395 -0.911679 0.118663 0.0731638 -0.988869 0.129558 0.350875 -0.913087 0.207749 0.0143758 -0.998937 0.0437958 0.299202 -0.925383 0.232689 0.240334 -0.970617 -0.0119696 0.00223216 -0.977615 0.210391 -0.00807201 -0.995994 0.089056 -3.83209e-05 -0.998872 -0.0474845 0.0349544 -0.781792 0.622558 -0.0010719 -0.801461 0.598046 -0.00372253 -0.808513 0.588467 0.0794581 -0.964112 -0.253327 0.154258 -0.976241 -0.152179 0.231953 -0.971173 0.0549684 0.0991956 -0.989622 0.103969 0.0140525 -0.746647 0.665072 0.0551358 -0.788075 0.613105 0.201743 -0.790835 0.577823 0.175001 -0.698597 0.693785 0.26812 -0.759323 0.592909 0.377308 -0.823252 0.42414 0.427499 -0.68873 0.585572 0.427103 -0.688309 0.586356 -0.000250346 -0.996056 0.0887285 0.0128976 -0.993684 0.111467 0.0361457 -0.982208 0.184285 0.0814985 -0.980691 0.177773 0.0677402 -0.997097 0.03476 0.0145008 -0.994778 -0.101023 0.00827488 -0.990523 -0.1371 0.0882143 -0.980076 -0.17796 -0.00463718 -0.87607 -0.482162 0.365485 -0.856936 0.363431 0.361283 -0.879597 0.309488 0.150753 -0.909073 0.388407 0.14922 -0.90653 0.394888 0.0228924 -0.910358 0.413187 0.0242206 -0.912278 0.408855 -0.000620938 -0.912551 0.408962 -0.000757076 -0.912358 0.409393 0.00833103 -0.91232 0.409393 -0.00504292 -0.876196 0.481928 -0.00393128 -0.874203 0.485545 0 0.9839 -0.178717 -7.4604e-05 0.984426 -0.175797 3.41073e-05 0.905516 -0.424313 0.00152464 0.842217 -0.539137 -0.000162103 0.790052 -0.613039 0.000211002 0.567052 -0.823682 0.00099742 0.539137 -0.842217 -5.23619e-05 0.377278 -0.9261 0.000197465 0.175798 -0.984426 0 0.16722 -0.98592 0 0.0774663 0.996995 0.00142992 0.175798 0.984425 -1.67649e-05 0.253254 0.9674 7.35551e-06 0.375089 0.926989 0.00101642 0.539137 0.842217 0.00319184 0.484387 0.874848 0.000506669 0.842218 0.539138 3.8213e-06 0.717855 0.696193 -2.45502e-05 0.638487 0.769632 0 0.995753 0.092066 0.00306457 0.961442 0.27499 -0.000333014 0.984426 0.175797 0.000171109 0.896539 0.442964 0.00350001 0.795383 0.606097 0 0.361853 -0.932235 0.00104658 0.252734 -0.967535 -0.00178357 0.108441 -0.994101 0.00196093 -0.13331 -0.991072 -2.21623e-05 -0.225404 -0.974265 1.38499e-05 -0.420072 -0.907491 0.00186602 -0.542001 -0.840376 -0.000813715 -0.633887 -0.773425 0.000646354 -0.80618 -0.591671 0.00206078 -0.847854 -0.530226 -1.94867e-05 -0.902112 -0.431502 4.86955e-06 -0.959307 -0.282364 0.00106839 -0.985642 -0.168843 0 -0.993148 -0.116866 0 -0.993068 0.117546 0.00106054 -0.985642 0.168843 0.000123633 -0.962758 0.270364 -0.000152844 -0.924247 0.381796 0.00173563 -0.847854 0.530226 0.000222429 -0.816006 0.578043 -0.00013285 -0.652582 0.757718 0.00196353 -0.542001 0.840376 0.0001614 -0.47071 0.882288 -0.000281727 -0.133311 0.991074 0.00080379 -0.161702 0.986839 -0.000678423 0.252734 0.967536 0 0.232028 0.972709 -6.77248e-05 0.947055 -0.321071 0.00115753 0.990291 -0.139007 0 0.984426 -0.175797 0.000382085 0.842218 -0.539138 0.00707424 0.7318 -0.681483 0.000353482 0.848918 -0.528524 0 0.175798 -0.984426 0.00238848 0.103176 -0.99466 -0.000149659 0.286868 -0.95797 0.000411308 0.539137 -0.842218 0.00317536 0.475768 -0.879565 -0.000161606 0.651212 -0.758896 0.00151092 0.539137 0.842217 0 0.0720634 0.9974 -0.00297846 0.175794 0.984423 0.00758233 0.460229 0.887768 0.00210743 0.287151 0.957883 0.00133375 0.833972 0.551806 2.89852e-05 0.762625 0.646841 -5.06878e-05 0.610741 0.791831 0 0.984426 0.175797 0.00217688 0.995913 0.0902903 2.84782e-05 0.965227 0.261414 -7.1077e-05 0.842218 0.539138 0.00631502 0.936432 0.350793 0.00355992 0.899552 0.436799 0.371041 0.154606 0.915656 0.643792 0.103629 -0.758151 0.642022 0.104826 -0.759486 0.658501 0.0909228 -0.747067 0.661609 0.0362079 -0.748974 0.683545 0.281165 -0.673582 0.879286 0.411487 -0.239863 0.738299 0.478852 -0.47499 0.827623 0.560247 0.0341303 0.747141 0.644815 -0.161227 0.511887 0.744407 0.428753 0.633287 0.741825 0.220553 0.633151 0.742641 0.218184 0.714201 0.695336 0.0801556 0.725255 0.687861 0.0291928 0.496797 0.751026 0.434917 0.318903 0.649494 0.69026 0.327326 0.719215 0.612852 0.0502227 0.526665 0.848588 0.118575 0.13637 0.983536 0.13972 0.0396177 0.989398 0.15232 -0.0268341 0.987967 0.128578 0.00263617 0.991696 0.901067 0.129824 0.413793 0.715555 0.183752 0.673955 0.98937 0.144933 -0.011924 0.989511 0.144455 0.000697439 0.989731 0.141875 0.017412 0.989904 0.138921 0.0281158 0.989931 0.131078 0.0534321 0.987391 0.0757637 0.138994 0.991423 0.0459454 0.122348 0.897921 0.273389 0.344959 0.983442 0.141446 -0.113289 0.983172 0.0557287 -0.173972 0.948425 0.126627 -0.290612 0.929021 0.101969 -0.3557 0.867319 0.138314 -0.47815 0.673732 0.0638731 -0.73621 0.697237 0.013659 -0.71671 0.655153 0.488968 0.575921 0.423861 0.358121 0.83192 0.420454 0.398092 0.815317 0.105351 0.182497 0.977546 0.0948135 0.328301 0.939803 0.711141 0.652028 0.262942 0.586886 0.620552 0.520077 0.576839 0.644981 0.501256 0.368376 0.535203 0.760169 0.36105 0.570795 0.737452 0.135102 0.424586 0.895251 0.109503 0.517728 0.848509 0.133102 0.577016 0.805814 0.542134 -0.0470731 0.838972 0.481556 0.0782503 0.872915 0.717801 0.254838 0.647935 0.669467 0.421786 0.611482 0.807669 0.466367 0.360793 0.778812 0.511794 0.362656 0.862402 0.498041 0.0906513 0.893122 0.44509 0.0650205 0.902303 0.380519 -0.202618 0.913889 0.337873 -0.225052 0.828119 0.214911 -0.517718 0.801734 0.277504 -0.529353 0.610762 0.093315 -0.786297 0.644612 0.479975 -0.595063 0.903428 0.0587741 -0.424692 0.588178 0.0119455 0.808644 0.564124 0.745358 -0.355254 0.174387 0.100843 -0.9795 0.140741 0.00288553 -0.990042 0.0601308 0.646139 -0.760847 0.101342 0.559889 -0.822347 0.0931587 0.545666 -0.832809 0.273756 0.652373 -0.70673 0.296569 0.695794 -0.654154 0.370226 0.700188 -0.610466 0.655816 0.734177 -0.175753 0.669886 0.701055 -0.244487 0.734228 0.678829 0.0100572 0.734053 0.678839 0.0185387 0.800614 0.585873 0.12558 0.798557 0.542367 0.261047 0.826859 0.456401 0.328637 0.655609 0.0943183 0.749187 0.769794 0.318092 0.553385 0.789141 0.321754 0.523193 0.712243 0.18097 0.678204 0.632669 0.11017 0.766546 0.625895 0.0781289 0.775984 0.67775 -0.0236572 0.734912 0.67319 -0.0167652 0.73928 0.861886 0.128426 0.49057 0.805036 -0.131158 0.578546 0.991892 0.127066 -0.0022489 0.991254 0.128988 0.0278984 0.980848 0.0869614 0.174282 0.994638 -0.0224484 0.100949 0.929856 0.184648 0.318234 0.898528 0.429438 -0.0907275 0.971218 0.0353042 -0.235563 0.992013 0.123421 -0.0260254 0.541829 0.120096 -0.831864 0.632897 0.173268 -0.754599 0.741875 0.0805176 -0.665686 0.764593 0.205779 -0.610781 0.878923 0.120808 -0.46141 0.418975 0.117847 -0.900318 0.496378 0.0271896 -0.867681 0.417839 0.401336 -0.815071 0.441564 0.361822 -0.82104 -0.125732 -0.0121528 -0.99199 0.106836 0.169472 -0.979727 0.0316631 0.371317 -0.927966 0.167254 0.227794 -0.959237 0.0990032 0.386059 -0.917146 0.363863 0.563831 -0.741416 0.382442 0.540684 -0.749265 0.534837 0.623104 -0.570693 0.676291 0.0441524 0.73531 0.660018 0.0612127 0.748752 0.841022 0.212033 0.497719 0.835445 0.217094 0.504877 0.918947 0.341516 0.197238 0.90203 0.366354 0.228312 0.893032 0.441086 -0.0890935 0.870243 0.491292 -0.0361825 0.781999 0.514356 -0.352016 0.768158 0.563018 -0.304869 0.640678 0.527156 -0.558246 0.49076 0.755668 -0.433729 0.483054 0.724487 -0.491708 0.341084 0.894021 -0.290498 0.422657 0.877461 -0.226769 0.38856 0.905946 -0.168173 0.415531 0.893297 -0.171334 0.4446 0.870918 -0.209362 0.411605 0.889027 -0.200531 0.416707 0.88541 -0.205924 0.419902 0.882828 -0.21047 0.421726 0.880105 -0.218087 0.422652 0.877455 -0.226798 0.422341 0.87246 -0.24585 0.421772 0.871342 -0.250744 0.420033 0.869743 -0.259075 0.422347 0.878471 -0.223408 0.422607 0.877317 -0.227418 0.422607 0.873487 -0.24171 0.422654 0.873289 -0.242342 0.415723 0.869759 -0.265881 0.411783 0.870433 -0.269781 0.399123 0.873567 -0.278535 0.422656 0.873289 0.24234 0.339145 0.894688 0.290714 0.392948 0.875901 0.279982 0.411605 0.870185 0.270848 0.416709 0.869749 0.264367 0.419901 0.869786 0.259144 0.421726 0.871237 0.251182 0.422653 0.873297 0.242317 0.422341 0.878497 0.223317 0.421772 0.879976 0.218519 0.420033 0.882756 0.210507 0.422348 0.872484 0.245751 0.422607 0.873487 0.24171 0.422607 0.877317 0.227418 0.422655 0.877461 0.226771 0.415724 0.886173 0.204622 0.411781 0.888708 0.201579 0.431348 0.877195 0.210871 0.418708 0.891702 0.171904 0.389635 0.9055 0.168091 0.341084 -0.894021 0.290498 0.420033 -0.869743 0.259075 0.421772 -0.871341 0.250744 0.422341 -0.87246 0.24585 0.422607 -0.873487 0.24171 0.422654 -0.873289 0.242342 0.415723 -0.869759 0.265881 0.411783 -0.870432 0.269781 0.399123 -0.873567 0.278535 0.339147 -0.920179 0.195578 0.392947 -0.898544 0.195479 0.411605 -0.889027 0.200531 0.416707 -0.88541 0.205924 0.419902 -0.882828 0.21047 0.421726 -0.880105 0.218087 0.422347 -0.878471 0.223408 0.422607 -0.877317 0.227418 0.422653 -0.877455 0.226797 0.422657 -0.877461 0.226769 0.3411 -0.919488 -0.195431 0.422657 -0.873287 -0.242345 0.339145 -0.894688 -0.290714 0.392947 -0.875901 -0.279982 0.411605 -0.870185 -0.270848 0.41671 -0.869749 -0.264366 0.419902 -0.869786 -0.259142 0.421726 -0.871237 -0.251184 0.422653 -0.873297 -0.242317 0.422341 -0.878497 -0.223317 0.421772 -0.879976 -0.218519 0.420033 -0.882756 -0.210507 0.422347 -0.872482 -0.24576 0.422607 -0.873487 -0.24171 0.422607 -0.877317 -0.227418 0.422655 -0.877461 -0.226771 0.415722 -0.886175 -0.204618 0.411786 -0.888705 -0.201581 0.399119 -0.895801 -0.195564 0.997522 0.0679522 -0.0182077 0.919558 0.381174 -0.0954915 0.866396 0.481564 -0.132111 0.815352 0.563592 -0.132534 0.901402 0.415221 -0.122746 0.941937 0.325415 -0.0828243 0.969672 0.23382 -0.0711674 0.981767 0.184774 -0.0446325 0.999103 0.0392053 -0.0160139 0.556312 0.802695 -0.214935 0.440941 0.868985 -0.224579 0.487492 0.836461 -0.25037 0.511369 0.827222 -0.232821 0.4918 0.839002 -0.232827 0.794485 0.586591 -0.157177 0.730242 0.659909 -0.176823 0.673151 0.717019 -0.180975 0.69302 0.702483 -0.161992 0.632985 0.747749 -0.200505 0.997522 0.0679522 0.0182077 0.919559 0.377852 0.107889 0.866395 0.483105 0.126371 0.815351 0.554354 0.167018 0.901402 0.420964 0.101309 0.941937 0.323229 0.0909793 0.969672 0.238077 0.0552772 0.981767 0.182335 0.053734 0.999103 0.0419599 0.00573422 0.556314 0.802621 0.215208 0.440964 0.864843 0.239996 0.487482 0.849587 0.201402 0.511369 0.832805 0.211984 0.491808 0.843006 0.217867 0.794487 0.586589 0.157177 0.730238 0.659914 0.176824 0.673152 0.711443 0.201781 0.693018 0.689366 0.210951 0.632988 0.747819 0.200232 0.997522 -0.0679522 -0.0182077 0.919558 -0.377853 -0.107889 0.866396 -0.483103 -0.12637 0.815351 -0.554353 -0.167018 0.901401 -0.420966 -0.101309 0.941937 -0.323229 -0.0909793 0.969672 -0.238077 -0.055277 0.981767 -0.182335 -0.0537338 0.999103 -0.0419596 -0.00573412 0.601679 -0.771527 -0.206706 0.440946 -0.86485 -0.240004 0.491808 -0.843006 -0.217867 0.511369 -0.832805 -0.211984 0.487493 -0.84958 -0.201406 0.556307 -0.802626 -0.215209 0.794487 -0.586588 -0.157177 0.730237 -0.659914 -0.176824 0.678682 -0.706817 -0.199501 0.693108 -0.691007 -0.205209 0.632985 -0.748331 -0.198319 0.601678 -0.771516 0.206752 0.440959 -0.868977 0.224576 0.491816 -0.838993 0.232825 0.511369 -0.827223 0.232819 0.487482 -0.836465 0.250374 0.556312 -0.802696 0.214936 0.678681 -0.711872 0.180636 0.693109 -0.701034 0.167786 0.632982 -0.747235 0.202417 0.919559 -0.381173 0.095491 0.866395 -0.481566 0.132112 0.815352 -0.563592 0.132535 0.794486 -0.58659 0.157177 0.730242 -0.65991 0.176823 0.997522 -0.0679522 0.0182077 0.901402 -0.41522 0.122746 0.941937 -0.325414 0.0828242 0.969672 -0.23382 0.0711674 0.981767 -0.184774 0.0446327 0.999103 -0.0392051 0.0160139 0.864337 -0.0191143 -0.50255 0.582122 0 -0.813101 0.861634 -0.0193087 -0.507163 0.863017 0.0154546 -0.504938 0.832302 -0.00417647 -0.554306 0.833628 0 -0.552326 0.806205 0 -0.591637 0.807238 0.00908932 -0.590156 0.769306 -0.00668737 -0.638846 0.770474 0 -0.637472 0.739433 0 -0.67323 0.740253 0.00367599 -0.672319 0.697768 -0.00693412 -0.716291 0.693821 -0.034839 -0.719304 0.664442 0.000562334 -0.74734 0.624976 -0.00415924 -0.780633 0.624425 0.000426304 -0.781084 0.582068 -7.1986e-05 -0.81314 0.797112 0.0483686 -0.601891 0.793361 0.0151436 -0.608563 0.756441 -0.0134575 -0.653924 0.758762 0 -0.651368 0.728375 0 -0.685179 0.721561 -0.0243497 -0.691923 0.685347 0.0439784 -0.726888 0.682426 0.0225291 -0.730607 0.622195 -0.0325725 -0.782184 0.625676 -0.00571742 -0.780062 0.582516 0.00088737 -0.812818 0.581816 0 -0.813321 0.842913 -0.082626 -0.531667 0.840197 -0.00471408 -0.542261 0.766147 0.37196 -0.524085 0.854497 -0.00277972 -0.519449 0.854497 -0.00277985 0.519449 0.766147 0.37196 0.524085 0.582516 0 0.812819 0.581815 0.00099252 0.81332 0.626346 -0.00582221 0.779523 0.625686 0 0.780075 0.6826 0 0.730793 0.6826 0 0.730793 0.721775 0 0.692128 0.721775 0 0.692128 0.758762 0 0.651368 0.758762 0 0.651368 0.793452 0 0.608632 0.793452 0 0.608632 0.825175 0 0.564878 0.837316 -0.132955 0.530307 0.853964 -0.00239671 0.520327 0.864337 -0.0191143 0.50255 0.86429 -0.0171768 0.5027 0.866846 -0.0937172 0.489689 0.841727 0.0269721 0.53923 0.813089 -0.0590491 0.579137 0.809371 -0.0181351 0.587018 0.770374 0.0160999 0.637389 0.772886 0 0.634544 0.740258 0 0.672323 0.7332 0.0282796 0.679425 0.693334 -0.0511313 0.7188 0.582068 0 0.81314 0.582122 -7.13618e-05 0.813101 0.609177 0.00024467 0.793034 0.623276 -0.0738346 0.778509 0.649743 0.0174604 0.759954 0.691123 -0.0314839 0.722051 0.795045 -0.0117113 -0.606437 0.795927 -0.0136067 -0.605239 0.79583 -0.0139009 -0.60536 0.610407 -0.0396051 -0.791097 0.611656 -0.0408658 -0.790068 0.383693 -0.0649523 -0.921174 0.384947 -0.0660482 -0.920572 0.130828 -0.0866972 -0.987607 0.131349 -0.0871228 -0.9875 0.816654 -0.0525059 -0.574734 0.214554 -0.340553 -0.915418 0.138807 -0.392198 -0.909348 0.0718065 -0.379779 -0.922286 0.34914 -0.298709 -0.888186 0.422461 -0.308139 -0.852395 0.403192 -0.303746 -0.863235 0.640874 -0.106771 -0.760185 0.834193 -0.0430366 -0.549791 0.824283 -0.0752446 -0.561156 0.755342 -0.101703 -0.647391 0.601041 -0.183762 -0.777805 0.795927 -0.0136067 0.605239 0.795045 -0.0117113 0.606437 0.79583 -0.0139009 0.60536 0.611681 -0.0394551 0.79012 0.610382 -0.0410205 0.791045 0.384969 -0.0648339 0.920649 0.383665 -0.0661703 0.921098 0.131351 -0.0866615 0.987541 0.130825 -0.0871608 0.987567 0.139997 -0.362725 0.92132 0.138851 -0.363971 0.921003 0.403473 -0.3012 0.863996 0.370587 -0.291238 0.881956 0.279013 -0.321562 0.904848 0.740983 -0.110455 0.662378 0.692808 -0.137921 0.70781 0.633345 -0.201294 0.747232 0.601352 -0.198018 0.774057 0.508959 -0.228212 0.829988 0.816654 -0.0525059 0.574734 0.783298 -0.0853443 0.61576 0.829037 -0.0904243 0.551834 0.855427 -0.0264637 0.517247 0.8651 2.47102e-05 0.5016 0.999733 -0.0225761 -0.00491025 0.87526 0 -0.483653 0.960587 0.00996655 -0.277802 0.946003 0.000858585 -0.324157 0.876932 -0.000539107 -0.480615 0.910673 0.00853843 0.41304 0.946841 -0.0235066 0.320841 0.974938 -9.35385e-05 0.222477 0.995924 7.45902e-05 0.0901955 0.992556 0.0354747 -0.11651 0.728596 -0.000167379 0.684944 0.788537 -0.0629438 0.611758 0.650852 0 0.759205 0.650855 0 0.759202 0.788538 -0.0629473 0.611756 0.7286 -0.000173516 0.684939 0.865063 2.11517e-05 0.501662 0.910675 0.00854172 0.413036 0.941685 -0.0183355 0.335996 0.974863 0.0028259 0.222789 0.999965 -0.00818103 -0.00190249 0.87526 0 -0.483653 0.994153 0.0387173 0.1008 0.994495 -0.0109409 -0.104208 0.960587 0.00996854 -0.277802 0.946001 0.000859559 -0.324161 0.876939 -0.000541417 -0.480601 0.876948 0.000543013 0.480585 0.875264 0 0.483646 0.947228 -0.000896889 0.32056 0.960544 -0.00965232 0.277959 0.994868 0.0100798 0.100682 0.999882 -0.0151035 -0.00293116 0.995922 -7.50654e-05 -0.0902183 0.974945 9.22596e-05 -0.222447 0.946841 0.0235044 -0.320841 0.910683 -0.00854033 -0.413018 0.865097 -2.47067e-05 -0.501604 0.835912 2.21426e-05 -0.548864 0.728399 0.0161908 -0.684961 0.771233 0.0542305 -0.634238 0.650861 0 -0.759197 0.650861 0 -0.759197 0.771221 0.0542202 -0.634254 0.728402 0.0161929 -0.684959 0.835916 2.38952e-05 -0.548857 0.865066 -2.24268e-05 -0.501658 0.910681 -0.00854252 -0.413022 0.946843 0.0235045 -0.320836 0.974943 9.37499e-05 -0.222454 0.995922 -7.27893e-05 -0.0902158 0.999882 -0.0151019 -0.0029252 0.875259 0 0.483655 0.994867 0.0100808 0.100684 0.970138 -0.00564372 0.242489 0.960573 -0.009961 0.277848 0.946006 -0.000863494 0.324147 0.876948 0.000544498 0.480586 0.594795 0.692647 -0.407994 0.586598 -0.300169 -0.752198 0.174244 0.96622 -0.189888 0.516217 0.342687 -0.784912 0.266306 0.875893 -0.40236 0.312019 0.921938 -0.229507 0.55759 0.115599 -0.822028 0.0342665 0.974609 -0.221278 0.0717987 0.971453 -0.226104 0.0991039 0.966092 -0.238422 0.174189 0.975549 -0.134023 0.176377 0.971213 -0.160112 0.152906 0.971061 -0.183467 0.169234 0.978886 -0.114638 0.174452 0.977962 -0.114702 0.192861 0.9736 -0.122095 0.178221 0.973633 -0.142391 0.163015 0.976989 -0.137544 0.163211 0.978602 -0.125301 0.170719 0.978543 -0.115363 0.153022 0.980222 -0.125493 0.140943 0.980249 -0.138731 0.151951 0.977478 -0.14645 0.113596 0.98482 -0.131249 0.124926 0.982056 -0.141276 0.161413 0.968988 -0.187105 0.117248 0.978903 -0.167337 0.107104 0.981141 -0.16091 0.100597 0.984883 -0.141016 0.0980216 0.986518 -0.131049 0.116688 0.979465 -0.164412 0.116269 0.982101 -0.148189 0.581282 0.359683 -0.72989 0.594433 -0.00344388 -0.804138 0.622862 0.0820477 -0.778017 0.763681 0.419317 -0.490882 0.589506 -0.168798 -0.78993 0.451838 -0.520625 -0.724425 0.478503 -0.564202 -0.672838 0.574498 -0.449892 -0.683776 0.696192 -0.396541 -0.598391 0.664856 -0.449412 -0.596653 0.740801 -0.353842 -0.570972 0.796546 0.258641 -0.546462 0.808641 0.258759 -0.52834 0.830023 0.16179 -0.533748 0.768922 0.161803 -0.618529 0.764474 -0.324205 -0.557198 0.789195 -0.323964 -0.521746 0.790549 -0.316838 -0.524067 0.832244 -0.198272 -0.517744 0.825489 -0.198325 -0.528426 0.704483 0.069452 -0.706315 0.709585 0.188209 -0.679019 0.685713 0.119917 -0.717926 0.645063 0.119834 -0.754675 0.644198 0.106388 -0.757423 0.585341 0.185497 -0.789283 0.584477 0.172903 -0.792774 0.546131 0.167943 -0.820692 0.415232 0.731573 -0.540725 0.456201 0.655679 -0.601636 0.471192 0.611519 -0.635628 0.540573 0.489583 -0.68417 0.562669 0.25068 -0.787758 0.75759 0.0822755 -0.647525 0.706159 0.419309 -0.570543 0.710695 0.360574 -0.604069 0.589816 0.650114 -0.479029 0.602502 0.614246 -0.509602 0.467285 0.55175 -0.690809 0.469521 0.540955 -0.697794 0.503311 0.540762 -0.673984 0.505795 0.528315 -0.681949 0.55519 0.52825 -0.64243 0.559358 0.509674 -0.653721 0.613325 0.509571 -0.603465 0.620748 0.478422 -0.621115 0.679201 0.478285 -0.556713 0.690049 0.432348 -0.580437 0.735606 0.432638 -0.521256 0.716067 0.489379 -0.497752 0.729913 0.489644 -0.476945 0.607604 0.692843 -0.388312 0.63541 0.650339 -0.416309 0.590369 -0.185388 -0.785554 0.760603 -0.186219 -0.621937 0.760668 -0.0934943 -0.642373 0.83718 -0.0936314 -0.538853 0.837085 0.022808 -0.546598 0.791151 0.0227179 -0.611198 0.818956 -0.0314151 -0.572996 0.823729 -0.00276925 -0.566977 0.764194 -3.0539e-06 -0.644987 0.775464 0.17279 -0.607289 0.752491 0.0704104 -0.654828 0.375414 0.729297 -0.572006 0.311438 0.835177 -0.453305 0.32918 0.835027 -0.440875 0.332025 0.830498 -0.44725 0.364201 0.830452 -0.421554 0.36895 0.823685 -0.430602 0.404141 0.823611 -0.397914 0.412842 0.812246 -0.412089 0.450998 0.812138 -0.37018 0.464633 0.795342 -0.389291 0.491722 0.795613 -0.353849 0.433885 0.849305 -0.300707 0.444259 0.849473 -0.284656 0.467623 0.829416 -0.30561 0.432921 0.829235 -0.35348 0.446 0.812366 -0.375692 0.349143 0.810465 -0.470368 0.284866 0.903066 -0.321439 0.305111 0.827401 -0.471503 0.227579 0.91017 -0.34612 0.0592868 -0.486898 -0.871444 0.129987 -0.162476 -0.978113 0.0580467 -0.0552702 -0.996783 0.0559032 -0.491667 -0.868987 0.00687096 0.880193 -0.474566 0.0491519 0.786817 -0.615227 0.0330687 0.751785 -0.658579 0.030718 0.533407 -0.845301 0.0435574 0.56684 -0.822676 0.0418782 0.307051 -0.950771 0.0535896 0.338468 -0.939451 0.04937 0.0857825 -0.99509 0.129917 0.921777 -0.365305 0.0599507 0.964031 -0.258942 0.237605 -0.460811 -0.855101 0.392575 -0.169956 -0.90388 0.129314 0.755529 -0.642225 0.0744215 0.805873 -0.587393 0.0763873 0.875614 -0.476932 0.029766 0.917618 -0.396348 0.360251 -0.302428 -0.882472 0.435251 -0.445006 -0.782641 0.357567 -0.520614 -0.775311 0.202577 -0.48257 -0.852108 0.171649 -0.627087 -0.759802 0.319481 -0.151759 -0.935361 0.283731 -0.0034059 -0.958898 0.307781 0.0971654 -0.946483 0.269545 0.247164 -0.930728 0.279791 0.34639 -0.895394 0.220752 0.4844 -0.846537 0.230664 0.572075 -0.787098 0.196936 0.649849 -0.734106 0.130708 0.84755 -0.514368 0.230949 0.73213 -0.640818 0.213838 0.812495 -0.542333 0.192042 0.82534 -0.530975 0.128297 0.908082 -0.398657 0 0.798331 -0.602218 -0.00174888 0.787767 -0.615971 0.00118396 0.533658 -0.8457 0.00813605 0.444686 -0.895649 -0.000576071 0.30732 -0.951606 0.00118741 -0.0553338 -0.998467 0.00118371 -0.0553641 -0.998466 -0.00105529 -0.500897 -0.865506 0 -0.492437 -0.870348 0.598807 -0.341122 -0.724614 0.104718 0.983188 -0.149586 0.061486 0.971626 -0.22839 0.122764 -0.00960848 -0.992389 0.513683 0.343159 -0.786366 0.619341 0.116035 -0.7765 0.668734 0.0959532 -0.737284 0.0277058 -0.600448 -0.799184 0.0913413 0.176235 -0.980101 0.127429 0.0936955 -0.987412 0.103257 0.36845 -0.923895 0.107716 0.38397 -0.917041 0.0972662 0.587775 -0.803156 0.0838848 0.618616 -0.781202 0.0831995 0.765536 -0.637991 0.0585323 0.814129 -0.577727 0.0588984 0.894708 -0.442751 0.0202112 0.953225 -0.301585 -0.00193061 0.970253 -0.242087 0.0153233 0.991318 -0.13059 0.107566 0.977762 -0.180029 0.141701 0.974766 -0.172487 0.14038 0.976397 -0.164142 0.132509 0.976363 -0.170756 0.31203 0.921928 -0.229535 0.161407 0.968985 -0.187127 0.117144 0.97892 -0.167313 0.120883 0.978062 -0.169653 0.111915 0.980263 -0.162968 0.273876 0.875069 -0.399055 0.312247 0.83816 -0.447203 0.368099 0.759346 -0.53656 0.539319 0.192794 -0.819735 0.145678 -0.385671 -0.911063 0.311414 -0.438517 -0.843045 0.307779 -0.402269 -0.862237 0.470446 -0.340805 -0.813961 0.482715 -0.395805 -0.781233 0.556226 -0.284824 -0.780697 0.595442 -0.284757 -0.751241 0.451464 0.588714 -0.670519 0.445797 0.615371 -0.650065 0.48563 0.549098 -0.680187 0.507274 0.549129 -0.664177 0.559142 0.407202 -0.722182 0.564483 0.407205 -0.718013 0.605223 0.0165269 -0.795884 0.622786 0.0165214 -0.782218 0.617854 0.112071 -0.778265 0.614114 0.116459 -0.780578 0.597069 0.201909 -0.776364 0.592693 0.145063 -0.792257 0.566925 0.214642 -0.795314 0.551865 0.138619 -0.822332 0.556785 0.116332 -0.822471 0.113942 0.982657 -0.146297 0.290098 0.879892 -0.376343 0.329531 0.838252 -0.434446 0.400433 0.756466 -0.51712 0.490293 0.595103 -0.636762 0.527084 0.133817 -0.839211 0.491993 0.441863 -0.750134 0.489129 0.398493 -0.775858 0.409067 0.663827 -0.626098 0.411959 0.637292 -0.651267 0.299483 0.835758 -0.460237 0.304135 0.823188 -0.479441 0.128204 0.972594 -0.193973 0.0894867 0.972726 -0.213999 0.0787368 0.975141 -0.207124 0.198605 0.813654 -0.546372 0.198669 0.822316 -0.533222 0.267898 0.617744 -0.739339 0.270441 0.636073 -0.722685 0.315765 0.367623 -0.874726 0.322764 0.397423 -0.858998 0.336831 0.0933159 -0.936929 0.349526 0.133393 -0.927382 0.151819 0.971023 -0.184571 0.341642 0.836118 -0.42917 0.33465 0.847715 -0.411567 0.464756 0.664331 -0.585377 0.457931 0.688925 -0.561856 0.556696 0.442323 -0.703164 0.55398 0.483024 -0.678081 0.607952 0.193027 -0.770152 0.613478 0.249385 -0.749301 0.116942 0.98159 -0.151016 0.139375 0.975786 -0.168571 0.298626 0.879872 -0.369658 0.335308 0.847722 -0.411019 0.411005 0.75643 -0.50881 0.458 0.688925 -0.561799 0.505163 0.595066 -0.625066 0.552944 0.483015 -0.678932 0.544853 0.507631 -0.667417 0.628077 0.249402 -0.737101 0.633819 -0.0955481 -0.767557 0.613791 -0.0954955 -0.783672 0.604304 -0.0567829 -0.794728 0.533726 -0.0566241 -0.84376 0.541496 -0.126111 -0.831191 0.336839 -0.125686 -0.933136 0.345407 -0.172207 -0.922518 0.110169 -0.172924 -0.978754 0.143992 -0.31073 -0.939528 -8.90276e-08 0.991435 -0.130604 0.00286805 0.984645 -0.174545 -5.68641e-07 0.953419 -0.301649 -1.34644e-06 0.83308 -0.553152 0.0124837 0.768134 -0.640167 -5.34576e-07 0.896261 -0.443528 0.00928611 -0.0096813 -0.99991 -1.76776e-06 0.176973 -0.984216 -1.73529e-06 0.49179 -0.870714 0.0135113 0.386177 -0.922326 -1.37868e-06 0.59057 -0.806987 0.00438795 0.0436221 -0.999039 -0.00521019 -0.358868 -0.933374 -1.21441e-06 -0.313989 -0.949427 0.434962 -0.440424 -0.785388 0.184772 -0.96525 -0.184801 0.0249395 -0.977817 -0.207973 0.0490975 -0.988949 -0.139893 0.042475 -0.912819 -0.40615 0.106776 -0.542168 -0.833458 0.113269 -0.5262 -0.842783 0.542344 -0.117594 -0.831886 0.552649 -0.219961 -0.803864 0.528434 -0.343402 -0.776423 0.317556 -0.830594 -0.457463 0.366725 -0.759803 -0.536855 0.414229 -0.6787 -0.606449 0.104993 -0.982933 -0.151064 0.098583 -0.985407 -0.138763 0.100038 -0.985083 -0.140015 0.0959252 -0.985919 -0.136975 0.107637 -0.982938 -0.149155 0.0975903 -0.985489 -0.138881 0.100801 -0.984015 -0.146809 0.092081 -0.983995 -0.152561 0.0868307 -0.986394 -0.139599 0.0847539 -0.985334 -0.148104 0.0807101 -0.987063 -0.138534 0.114547 -0.913043 -0.391447 0.12387 -0.9063 -0.404074 0.169283 -0.906614 -0.386515 0.186399 -0.895719 -0.403661 0.20615 -0.895822 -0.393708 0.0260507 -0.990692 -0.133608 0.0420029 -0.990582 -0.130316 0.0438724 -0.987777 -0.149573 0.0591365 -0.991088 -0.119362 0.0705695 -0.984654 -0.159616 0.0697696 -0.988533 -0.133922 0.22552 -0.883802 -0.40992 0.238648 -0.883822 -0.402375 0.242909 -0.877413 -0.413692 0.277785 -0.849265 -0.448983 0.303836 -0.849262 -0.431785 0.314966 -0.838805 -0.444074 0.311261 -0.838779 -0.446729 0.230338 -0.911813 -0.339915 0.375927 -0.46198 -0.803277 0.380561 -0.453726 -0.805796 0.324234 -0.509239 -0.797213 0.255598 -0.508337 -0.822352 0.272086 -0.47901 -0.834577 0.1893 -0.543133 -0.81803 0.564074 -0.166944 -0.808672 0.566352 -0.170874 -0.806255 0.562905 -0.234782 -0.792474 0.522553 -0.234884 -0.819614 0.516794 -0.216889 -0.828181 0.482814 -0.300776 -0.82245 0.491153 -0.300722 -0.817518 0.454937 -0.395616 -0.797823 0.43321 -0.413649 -0.800765 0.092487 -0.787412 -0.60945 0.118383 -0.757917 -0.64152 0.183494 -0.756895 -0.627248 0.199122 -0.738167 -0.644562 0.270097 -0.738772 -0.617466 0.297821 -0.708526 -0.639761 0.3269 -0.708694 -0.625211 0.35746 -0.675395 -0.64503 0.365503 -0.675442 -0.640458 0.419934 -0.591058 -0.688699 0.422207 -0.579875 -0.696768 0.471584 -0.579941 -0.664286 0.480467 -0.551074 -0.682253 0.473546 -0.551008 -0.687127 0.473211 -0.552145 -0.686445 -1.18784e-06 -0.583668 -0.811993 0.00573626 -0.529614 -0.84822 -0.00866633 -0.847139 -0.531301 0.00444957 -0.79079 -0.612071 -0.00343547 -0.984521 -0.175232 -2.82396e-07 -0.97812 -0.208041 0.358159 -0.759881 -0.542497 0.0124141 -0.993287 -0.115006 0.0788759 -0.668221 -0.73977 0.464757 -0.552156 -0.692188 0.515011 -0.343378 -0.785402 0.31306 -0.830803 -0.460174 0.0996092 -0.985169 -0.139715 0.0957842 -0.985939 -0.136927 0.184771 -0.965242 -0.184843 0.098549 -0.985402 -0.138817 0.0973123 -0.986163 -0.134212 0.105638 -0.983147 -0.149205 0.11284 -0.983168 -0.143692 0.117251 -0.982213 -0.146664 0.109393 -0.985869 -0.12687 0.107088 -0.989085 -0.101207 0.111831 -0.986956 -0.115812 0.115024 -0.985556 -0.124296 0.117858 -0.984976 -0.12622 0.112389 -0.984966 -0.131188 0.0629555 -0.990172 -0.124883 0.0725958 -0.993427 -0.0884981 0.0825994 -0.990551 -0.10948 0.0953333 -0.990655 -0.0975461 0.0950996 -0.990801 -0.0962808 0.10616 -0.98925 -0.100568 0.106353 -0.989251 -0.100359 0.0128986 -0.993121 -0.116384 0.0301056 -0.993231 -0.112187 0.0342638 -0.993599 -0.107646 0.0404878 -0.992793 -0.112799 0.0587149 -0.992739 -0.104981 0.0371732 -0.937922 -0.344848 0.038751 -0.936398 -0.348794 0.106931 -0.937068 -0.332369 0.115616 -0.933096 -0.340536 0.160971 -0.933244 -0.321161 0.175709 -0.92727 -0.330599 0.22584 -0.926985 -0.299493 0.255225 -0.912598 -0.319414 0.287625 -0.913018 -0.289257 0.314805 -0.899676 -0.302458 0.317682 -0.899703 -0.299352 0.352569 -0.878863 -0.321397 0.323835 -0.879066 -0.349819 0.353763 -0.858648 -0.370913 0.335176 -0.858644 -0.387798 0.351431 -0.84644 -0.400045 0.332562 -0.846428 -0.415888 0.339461 -0.840881 -0.421528 0.317822 -0.840869 -0.438097 0.319685 -0.839283 -0.439779 0.307269 -0.83937 -0.44838 0.222214 -0.913002 -0.342123 0.0600561 -0.826114 -0.560293 0.0627263 -0.821986 -0.566043 0.173474 -0.823556 -0.540058 0.188597 -0.812539 -0.551555 0.260636 -0.812842 -0.52092 0.285795 -0.796257 -0.533193 0.364287 -0.795579 -0.484096 0.41143 -0.755571 -0.509743 0.460988 -0.756348 -0.464142 0.502676 -0.719227 -0.479613 0.505273 -0.719256 -0.476834 0.555341 -0.661612 -0.503851 0.508775 -0.662032 -0.550329 0.550668 -0.605503 -0.57457 0.520238 -0.605517 -0.602247 0.542238 -0.571817 -0.615633 0.512298 -0.571808 -0.64077 0.521453 -0.556528 -0.64681 0.487866 -0.556514 -0.672517 0.490328 -0.55215 -0.674322 0.464734 -0.552262 -0.692119 0.404581 -0.678804 -0.612813 0.0823859 -0.660888 -0.745949 0.242502 -0.662538 -0.708686 0.235918 -0.642328 -0.729217 0.361844 -0.642499 -0.675473 0.357069 -0.612224 -0.705467 0.495415 -0.610722 -0.617724 0.514162 -0.538579 -0.66751 0.607763 -0.539863 -0.582386 0.625039 -0.473685 -0.620442 0.650572 -0.473942 -0.59341 0.678519 -0.373697 -0.632426 0.640516 -0.373963 -0.670739 0.6557 -0.277363 -0.702231 0.634872 -0.277355 -0.721118 0.638664 -0.220972 -0.737075 0.612232 -0.220954 -0.759178 0.612599 -0.19571 -0.765781 0.576796 -0.195693 -0.793102 0.576685 -0.188518 -0.794919 0.547471 -0.188566 -0.815302 0.547159 -0.117605 -0.828725 1.06038e-07 -0.670312 -0.74208 0.00184996 -0.693502 -0.720452 -0.00141016 -0.827606 -0.561307 0.00386248 -0.888245 -0.459353 -0.00149395 -0.938569 -0.345087 0.00197789 -0.988757 -0.149521 0 -0.993364 -0.115014 0.575508 -0.186908 0.796151 0.367046 -0.759274 0.537383 0.459688 -0.588611 0.664999 0.528495 -0.343161 0.776488 0.557547 -0.186864 0.808841 0.560273 -0.116339 0.820097 0.0462831 -0.607145 0.793242 0.143421 -0.552817 0.820867 0.0751096 -0.756821 0.649292 0.014832 -0.993351 0.114168 0.0127386 -0.990598 0.136212 0.0298733 -0.990705 0.132708 0.0364079 -0.99139 0.125775 0.0430561 -0.989955 0.134667 0.0563104 -0.989979 0.1295 0.0593209 -0.98934 0.132991 0.0694253 -0.988641 0.133297 0.0742641 -0.98758 0.138458 0.0777279 -0.987591 0.136466 0.0903056 -0.984317 0.15154 0.0917191 -0.98412 0.151975 0.0920662 -0.984022 0.152394 0.311894 -0.921981 0.229504 0.161389 -0.968987 0.187133 0.117409 -0.978864 0.167454 0.121636 -0.977879 0.170166 0.103104 -0.982373 0.155929 0.110651 -0.980588 0.161876 0.104957 -0.982961 0.150902 0.105745 -0.982964 0.150333 0.100475 -0.984854 0.141304 0.0985571 -0.984047 0.148115 0.139206 -0.543032 0.828093 0.186138 -0.543196 0.818713 0.258671 -0.493693 0.830275 0.419887 -0.591181 0.688622 0.42216 -0.58 0.696693 0.471533 -0.580066 0.664214 0.192505 -0.756559 0.624948 0.190738 -0.737899 0.647398 0.283454 -0.738483 0.611798 0.285542 -0.708324 0.645557 0.340857 -0.708595 0.617826 0.344458 -0.675297 0.652168 0.365457 -0.675538 0.640383 0.470586 -0.551103 0.689082 0.480416 -0.551208 0.68218 0.572738 -0.15515 0.804922 0.253414 -0.472914 0.84388 0.30605 -0.52608 0.793456 0.377218 -0.457211 0.805397 0.379511 -0.465582 0.799503 0.437829 -0.430373 0.789357 0.435692 -0.411689 0.800428 0.473637 -0.379589 0.79472 0.477552 -0.29529 0.827495 0.51338 -0.239954 0.823931 0.512987 -0.234877 0.825637 0.552719 -0.23491 0.799575 0.0689641 -0.890167 0.450386 0.0878497 -0.913612 0.396982 0.119498 -0.912951 0.390181 0.119246 -0.906232 0.405615 0.176739 -0.90654 0.383339 0.179512 -0.895674 0.40687 0.213971 -0.89583 0.389493 0.21816 -0.883808 0.413873 0.238549 -0.883925 0.402207 0.242808 -0.877521 0.413523 0.277672 -0.849397 0.448801 0.303713 -0.849395 0.43161 0.314838 -0.838949 0.443894 0.310867 -0.83892 0.446739 0.273016 -0.875154 0.39946 -2.389e-07 -0.984527 0.175233 0.00533904 -0.993446 0.11418 -0.0081164 -0.847144 0.531302 0.00395074 -0.892282 0.451461 -0.00308904 -0.583665 0.811989 -1.16663e-06 -0.607799 0.794091 0.581786 0.406896 0.704245 0.184799 0.965247 0.184789 0.123353 0.150529 0.98088 0.0834559 0.74891 0.657396 0.0176563 0.975061 0.221232 0.0837431 0.588503 0.804146 0.112435 -0.397485 0.910694 0.291109 -0.474508 0.830721 0.261055 -0.380355 0.887232 0.096125 -0.439816 0.892929 0.487481 -0.414211 0.76863 0.466075 -0.35881 0.808721 0.394239 -0.358882 0.846037 0.495057 -0.487816 0.718996 0.512597 -0.284175 0.81024 0.591826 -0.284841 0.754061 0.618918 0.00940805 0.7854 0.618589 0.00940812 0.785659 0.629097 0.135868 0.765361 0.625631 -0.212317 0.750671 0.6197 -0.213207 0.755324 0.513612 0.343399 0.786308 0.61496 0.115379 0.780072 0.597825 0.195199 0.777498 0.595686 0.150036 0.78908 0.567185 0.212585 0.795682 0.556114 0.131359 0.820659 0.553277 0.142615 0.820698 0.53895 0.117567 0.834093 0.367796 0.759845 0.536061 0.415407 0.678732 0.605607 0.318319 0.83064 0.456848 0.31266 0.83795 0.447307 0.231194 0.911723 0.339574 0.11149 0.982859 0.146824 0.105609 0.982848 0.151187 0.099258 0.985252 0.13938 0.0992852 0.985246 0.139402 0.0956435 0.985975 0.136769 0.120812 0.975851 0.181989 0.145092 0.971185 0.189074 0.138162 0.976229 0.166999 0.136572 0.976097 0.169064 0.0277059 0.971329 0.236118 0.05838 0.971582 0.229392 0.0799557 0.974312 0.210532 0.0867989 0.972594 0.2157 0.116063 0.972766 0.200637 0.119697 0.982349 0.143746 0.333178 0.847422 0.413363 0.330886 0.84739 0.415265 0.345913 0.835736 0.426485 0.294757 0.83527 0.464158 0.30947 0.822614 0.477007 0.194795 0.821737 0.53554 0.202918 0.813041 0.5457 0.0735185 0.814537 0.575434 0.034839 0.860851 0.507663 0.301698 0.87963 0.367735 0.454411 0.688561 0.56515 0.451514 0.688515 0.567523 0.471371 0.663839 0.580627 0.400829 0.663141 0.632123 0.420442 0.636478 0.646625 0.263481 0.635236 0.725984 0.275054 0.616869 0.73744 0.094915 0.618789 0.779802 0.559194 0.407012 0.722249 0.507356 0.548934 0.664275 0.485705 0.548904 0.680291 0.45092 0.607309 0.6541 0.463918 0.552217 0.692702 0.415622 0.756131 0.505495 0.547891 0.482655 0.683271 0.544887 0.482613 0.685699 0.565643 0.441837 0.696296 0.480164 0.441159 0.75817 0.500718 0.397683 0.76885 0.312571 0.39658 0.863148 0.325807 0.36678 0.871391 0.108327 0.368276 0.923384 0.101452 0.38422 0.917651 0.530831 0.206315 0.821981 0.62392 0.207048 0.753562 0.623136 0.0111321 0.782034 0.634139 0.0111353 0.773139 0.61749 -0.0569006 0.784518 0.549593 -0.0568313 0.833497 0.526097 -0.126462 0.840969 0.350434 -0.126053 0.928066 0.332023 -0.172674 0.927332 0.113336 -0.173126 0.978357 0.0933899 -0.232878 0.968011 0.125054 -0.0822407 0.988736 0.108695 0.0932531 0.989691 0.349099 0.0928857 0.932471 0.336902 0.132919 0.93211 0.541101 0.133356 0.830317 0.524737 0.192328 0.829253 0.618786 0.192686 0.761562 0.602254 0.249088 0.75845 0.604745 0.249109 0.756458 0.511285 0.594751 0.62037 0.4904 0.594864 0.636902 0.400605 0.756222 0.517343 0.329734 0.838039 0.434703 0.290339 0.879679 0.376655 0.119907 0.980756 0.154079 0.118833 0.981184 0.152174 -7.66716e-07 -0.400002 0.916514 0.00286668 -0.358875 0.933381 -2.04789e-06 -0.233897 0.972261 0.00680246 0.491777 0.870695 -1.75295e-06 0.386207 0.922412 -1.72301e-06 0.0436255 0.999048 0.012483 0.151674 0.988352 -2.05917e-06 -0.0828898 0.996559 0.00928639 0.861335 0.507952 -1.6038e-06 0.751526 0.659703 -1.65373e-06 0.590573 0.806984 0.00438888 0.833072 0.553147 -0.00520884 0.984636 0.174544 -2.26341e-07 0.975214 0.221266 0.515081 -0.343138 0.78546 0.265956 -0.875897 0.402582 0.081611 -0.668116 0.739568 0.0127252 -0.993305 0.114819 0.0594946 -0.991166 0.118535 0.0314162 -0.993835 0.106327 0.0353411 -0.993224 0.110709 0.0125583 -0.993138 0.116273 0.0683734 -0.994465 0.0797724 0.0711354 -0.992192 0.102446 0.054198 -0.992127 0.112901 0.0824684 -0.990582 0.109298 0.0957366 -0.990683 0.0968621 0.104766 -0.989252 0.102005 0.106153 -0.989273 0.100355 0.11778 -0.987109 0.108367 0.110976 -0.987139 0.115068 0.117185 -0.985018 0.126518 0.100716 -0.988005 0.117059 0.109078 -0.982592 0.15038 0.110824 -0.983387 0.143767 0.116545 -0.982427 0.145787 0.113233 -0.983753 0.139311 0.11947 -0.983744 0.134069 0.311898 -0.921966 0.22956 0.161406 -0.968973 0.187191 0.117271 -0.978883 0.16744 0.10563 -0.981436 0.160078 0.0981216 -0.985611 0.137634 0.0989525 -0.985091 0.140725 0.0797066 -0.660759 0.746354 0.228429 -0.663169 0.712761 0.249058 -0.642953 0.72428 0.341889 -0.643342 0.684999 0.375264 -0.613005 0.695271 0.474632 -0.612096 0.632505 0.531651 -0.53951 0.652898 0.592519 -0.540315 0.597479 0.638778 -0.473974 0.606062 0.639927 -0.473984 0.604841 0.688231 -0.373528 0.621944 0.629155 -0.373922 0.68143 0.666206 -0.27737 0.692269 0.627881 -0.277393 0.7272 0.645359 -0.221035 0.731201 0.60897 -0.221035 0.761773 0.615784 -0.195785 0.763202 0.575827 -0.19578 0.793784 0.577626 -0.188608 0.794213 0.54109 -0.188641 0.819534 0.557703 -0.116344 0.821846 0.0620351 -0.826122 0.560067 0.0607703 -0.821974 0.566274 0.18323 -0.823287 0.537239 0.179486 -0.812268 0.554982 0.274612 -0.812429 0.514342 0.273127 -0.795866 0.540369 0.379355 -0.794762 0.473755 0.399084 -0.75502 0.520266 0.472255 -0.75618 0.452953 0.492498 -0.71919 0.490114 0.513241 -0.719449 0.46795 0.54771 -0.662081 0.51153 0.517315 -0.662372 0.541893 0.542474 -0.605843 0.581959 0.525492 -0.605824 0.597357 0.536927 -0.572132 0.619979 0.514698 -0.572096 0.638586 0.518849 -0.556829 0.648642 0.488501 -0.556793 0.671824 0.489476 -0.552429 0.674712 0.459185 -0.552486 0.695636 0.452121 -0.58884 0.669966 0.0382724 -0.937991 0.344539 0.0376244 -0.936462 0.348747 0.112187 -0.937036 0.330723 0.110613 -0.933062 0.342288 0.168528 -0.933159 0.31751 0.168741 -0.92719 0.334433 0.234147 -0.926741 0.293813 0.248353 -0.912447 0.325209 0.293872 -0.913039 0.282841 0.308908 -0.899754 0.30825 0.322059 -0.899892 0.294062 0.347892 -0.879201 0.325541 0.328439 -0.879346 0.344787 0.348866 -0.858949 0.374833 0.337899 -0.858932 0.384785 0.348207 -0.846744 0.402215 0.333688 -0.846718 0.414392 0.337777 -0.841182 0.422279 0.317975 -0.841158 0.43743 0.319004 -0.839575 0.439716 0.306488 -0.839654 0.448381 0.358399 -0.75943 0.54297 0 -0.993385 0.114829 0.00198532 -0.988756 0.149522 -0.00149977 -0.938678 0.344793 0.00888082 -0.827682 0.561127 -0.00324055 -0.888248 0.459353 0.00184733 -0.693502 0.720452 -1.46719e-07 -0.670354 0.742041 0.0980575 0.986508 0.131095 0.184819 0.965245 0.18478 0.359394 0.759713 0.541915 0.467254 0.55195 0.69067 0.546549 0.116864 0.829233 0.314623 0.830798 0.459116 0.100448 0.984994 0.140346 0.0996112 0.98518 0.139636 0.0957471 0.985959 0.136815 0.132369 0.979642 0.150931 0.118944 0.982087 0.14614 0.11032 0.982048 0.153007 0.140822 0.983312 0.115179 0.147357 0.977717 0.149518 0.136975 0.981368 0.134743 0.12559 0.981384 0.1453 0.181467 0.975761 0.122311 0.165464 0.978585 0.122443 0.156948 0.978519 0.133669 0.0733024 0.964945 0.252008 0.0868734 0.96977 0.228035 0.334357 0.825629 0.45447 0.581419 0.64957 0.489909 0.611094 0.613556 0.500113 0.428131 0.828894 0.360053 0.45133 0.811934 0.370223 0.383206 0.812702 0.43894 0.264064 0.875339 0.405033 0.227631 0.910129 0.346192 0.467733 0.829327 0.305683 0.444362 0.849398 0.284722 0.635479 0.650242 0.416354 0.607675 0.692755 0.388357 0.222684 0.912958 0.341934 0.311759 0.835117 0.453195 0.328009 0.834989 0.441818 0.333251 0.830457 0.446414 0.362517 0.830427 0.423052 0.370649 0.823659 0.429192 0.401442 0.823621 0.400615 0.415437 0.812249 0.409467 0.44726 0.812198 0.374556 0.468095 0.795384 0.385033 0.516152 0.342911 0.784856 0.548814 0.181086 0.816095 0.589888 0.135458 0.796042 0.592538 0.121115 0.796386 0.640741 0.169696 0.748769 0.652795 0.117635 0.748345 0.701588 0.121986 0.702064 0.68934 -0.413072 0.595132 0.678925 -0.467524 0.566112 0.666731 -0.421325 0.614781 0.56961 -0.419693 0.706684 0.502199 -0.518047 0.692404 0.586596 -0.300186 0.752193 0.802911 -0.274545 0.529111 0.792588 -0.32389 0.516624 0.764158 -0.324214 0.557628 0.81842 -0.00255789 0.574615 0.807909 -0.198222 0.554969 0.831846 -0.198318 0.518365 0.820105 0.0227601 0.571761 0.844195 0.0227785 0.535552 0.83045 -0.0937273 0.549152 0.776795 -0.093687 0.622746 0.744926 -0.186654 0.640504 0.589742 -0.185406 0.786021 0.593741 -0.168666 0.78678 0.5627 0.250639 0.787749 0.554086 0.396336 0.732056 0.489756 0.612949 0.620027 0.493065 0.531938 0.688425 0.440324 0.696159 0.566989 0.0342664 0.974587 0.221374 0.163174 0.967611 0.192623 0.16267 0.97083 0.176149 0.184986 0.971809 0.146178 0.187971 0.970522 0.150845 0.186282 0.975239 0.119196 0.181754 0.976633 0.11469 0.177899 0.976616 0.12072 0.433986 0.849229 0.300776 0.491806 0.795537 0.353904 0.594864 0.69256 0.408041 0.716104 0.489299 0.497777 0.72995 0.489564 0.47697 0.763716 0.419226 0.490905 0.694022 0.418737 0.585656 0.722454 0.359916 0.590357 0.581304 0.359583 0.729921 0.688866 0.180417 0.702078 0.726947 0.0698786 0.683129 0.76349 0.0706083 0.641948 0.766042 0.0527229 0.640625 0.795997 -0.00145456 0.605299 0.405515 0.678511 0.61252 0.469539 0.540896 0.697828 0.501164 0.540743 0.675597 0.507927 0.528297 0.680377 0.552125 0.52826 0.645058 0.562355 0.509677 0.651142 0.608466 0.509637 0.608309 0.625398 0.478479 0.616389 0.672492 0.478431 0.564675 0.696355 0.432461 0.572771 0.735634 0.432574 0.52127 0.796561 0.258571 0.546471 0.808657 0.25869 0.52835 0.830032 0.16172 0.533755 0.753969 0.161491 0.636751 0.771826 0.0820298 0.630521 0.598766 0.0816579 0.796751 0.617365 -0.0034795 0.786669 0.236276 0.696487 0.677554 0.209886 0.826496 0.522353 0.134687 0.966322 0.219276 0.0478277 0.790095 0.611115 0.00687676 0.879686 0.475506 0.0317522 0.87881 0.476114 0.0418364 0.337156 0.940519 0.0431148 0.534953 0.843781 0.0313338 0.565343 0.824261 0.0602088 -0.165124 0.984433 0.0972961 -0.0608247 0.993395 0.0488821 0.0854063 0.995146 0.0509081 0.184556 0.981503 0.0517803 0.309562 0.949468 0.0317556 0.637529 0.769772 0.030605 0.751147 0.659426 0.0721096 0.753684 0.653269 0.0765803 0.920549 0.383048 0.0665266 0.920047 0.386118 0.0590835 -0.496567 0.865985 0.0521875 -0.486148 0.872317 0.232497 -0.480979 0.845343 0.204957 -0.463818 0.861896 0.128125 0.908026 0.39884 0.199694 0.812214 0.548116 0.129761 0.810183 0.571634 0.129146 0.776381 0.61689 0.229888 0.571478 0.787759 0.224892 0.525028 0.820834 0.270723 0.345841 0.898389 0.282864 0.394673 0.874197 0.248008 0.0946252 0.964126 0.337208 0.250194 0.907576 0.240416 -0.157309 0.957838 0.345303 -0.00349493 0.938485 0.170276 -0.629561 0.758063 0.392105 -0.169948 0.904086 0.310778 -0.457405 0.833185 0.549353 -0.302087 0.779073 0.321611 -0.551033 0.770019 0.394255 -0.521338 0.756815 0 -0.497439 0.867499 3.42718e-05 0.184796 0.982777 0.00121485 -0.0611146 0.99813 0.000495688 -0.0553338 0.998468 -0.000421069 -0.500898 0.865506 -0.00041126 0.309978 0.950744 0.00813649 0.444688 0.895648 0.00103971 0.53545 0.844566 9.0543e-05 0.637851 0.77016 -0.00128838 0.798329 0.60222 0 0.790999 0.611817 0 -0.829546 0.558439 -0.000738555 -0.807548 0.589802 -0.0106481 -0.739812 0.67273 -0.0224051 -0.721425 0.69213 -0.00327149 -0.634482 0.772931 0.00466083 -0.516366 0.856355 -0.0355303 -0.410796 0.911035 0.00109528 -0.327746 0.944765 -0.00190077 -0.032426 0.999472 0 0.448391 0.893837 -0.0770174 -0.123843 0.989308 0.00746773 0.0946202 0.995485 -0.0150246 0.348678 0.937122 -0.05492 0.302836 0.951459 0 0.448392 0.893837 0 -0.419719 0.907654 0.00950587 -0.331217 0.943507 -0.00175151 -0.55124 0.834345 0.00233221 -0.729507 0.683969 0.00228522 -0.730051 0.683389 0.000197592 -0.805684 0.592345 0.00349535 0.365571 0.930777 0 0.287826 0.957683 0 -0.0102202 0.999948 0.0106141 0.0962237 0.995303 0 -0.115778 0.993275 -0.0419775 -0.0338229 -0.998546 -0.00129855 -0.11592 -0.993258 0.00232606 -0.406942 -0.913451 -0.0589985 -0.34681 -0.936078 0.0150619 -0.542569 -0.839876 -0.0222232 -0.721714 -0.691834 -0.0106289 -0.739841 -0.672698 -0.000737611 -0.807576 -0.589762 0 -0.829546 -0.558439 0.000197871 -0.805649 -0.592393 0.00228881 -0.730009 -0.683433 0.00233226 -0.729507 -0.68397 0.00531783 -0.0102201 -0.999934 0 0.0952945 -0.995449 0 0.365572 -0.930783 0.00656853 0.289668 -0.957105 0 0.448391 -0.893837 0 0.448392 -0.893837 -0.0374084 0.350598 -0.935779 -0.0100641 0.290645 -0.956778 0.00760771 0.0945879 -0.995487 0 -0.63192 -0.775033 0 -0.519064 -0.854736 0.00517022 -0.419713 -0.907642 0 -0.328105 -0.944641 0 -0.115759 -0.993277 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.574975 0.818171 0.00448317 0.587047 0.809541 0.000294873 0.55537 0.831603 0 0.542367 0.840142 -0.0143834 0.340097 0.94028 -0.00112022 0.559334 0.828942 0 0.592477 0.805587 0.00959102 0.4029 0.915194 -0.00768098 -0.0652894 0.997837 0.00384084 -0.105726 0.994388 -0.00408091 -0.518736 0.854924 0 -0.53026 0.847835 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.00386009 -0.0652901 -0.997859 -0.00368711 -0.528521 -0.848912 0 -0.518741 -0.854931 0 0.595014 -0.803716 -0.000810461 0.566995 -0.823721 -0.00949635 0.4029 -0.915195 0.00633162 0.349723 -0.936832 -0.00771929 -0.0996212 -0.994996 0 0.540459 -0.84137 0 0.59894 -0.800794 0.00265308 0.574972 -0.818169 0.000261214 0.565683 -0.824623 6.59706e-06 0.541716 -0.840561 0.866025 -0.500001 -3.02107e-05 0.866022 -0.500006 3.61858e-05 0.866038 -0.499978 -1.04403e-05 0.866011 -0.500025 5.89551e-06 0.866045 -0.499966 5.68942e-08 0.866023 -0.500005 -1.17923e-05 0.866017 -0.500015 0 0.866024 -0.500002 0 0.866024 -0.500002 0 0.866025 -0.500001 1.81219e-07 0.866025 -0.5 1.01191e-06 0.866026 -0.499999 1.34377e-06 0.866026 -0.499999 1.63859e-06 0.866028 -0.499996 4.11082e-07 0.866024 -0.500003 0 0.4064 0.661311 -0.630481 0.463299 0.636603 -0.616514 0.476095 0.628878 -0.614691 0.498633 0.612929 -0.612929 0.500131 0.571603 -0.650491 0.492396 0.568904 -0.658707 0.47821 0.571411 -0.666937 0.453223 0.578878 -0.677856 0.861112 0.332655 0.384484 0.865753 0.33062 0.375716 0.863338 0.357251 0.356399 0.850466 0.372784 0.371133 0.859007 0.362249 0.361778 0.860207 0.361293 0.359877 0.863581 0.356828 0.356233 0.840531 0.389101 0.376972 0.82667 0.405287 0.390331 0.785033 0.447214 0.42863 0.867456 0.349506 0.35407 0.854545 0.37065 0.363831 0.847708 0.380081 0.370039 0.866025 -0.5 -3.63107e-05 0.866028 -0.499995 2.31222e-05 0.866022 -0.500005 0 0.866027 -0.499997 -1.04361e-06 0.866025 -0.500001 -2.51429e-06 0.866026 -0.5 -4.04517e-06 0.866024 -0.500003 -3.0964e-06 0.866045 -0.499966 -5.68945e-08 0.866011 -0.500025 -5.89555e-06 0.866038 -0.499978 1.0401e-05 0.866027 -0.499997 9.49436e-06 0.866023 -0.500004 1.50739e-06 0.866025 -0.500001 1.50738e-06 0.866024 -0.500003 -3.06385e-06 0.866027 -0.499997 0 0.866025 -0.500001 -1.85615e-05 0 0.468584 -0.883419 0.00768783 0.361075 -0.932505 0.00722938 0.356461 -0.934282 -7.37381e-05 0.246736 -0.969083 7.26936e-05 0.0863006 -0.996269 0.00696255 -0.0325444 -0.999446 -2.09965e-08 -0.113092 -0.993585 0.0141751 0.0632537 0.997897 0.00280015 -0.0911371 0.995834 0 -0.192857 0.981227 0 -0.0325465 0.99947 0 0.361085 0.932533 0 0.361085 0.932533 0.979536 -0.18836 0.0709177 0.990695 -0.133026 0.0287585 0.995854 -0.0902138 0.0116912 0.998445 -0.0556174 0.00380391 0.999807 -0.0196479 0 0.990242 -0.138593 -0.0145787 0.950374 -0.311079 0.00432824 0.91305 -0.40755 -0.0155838 0.908108 -0.418621 -0.00987491 0.879225 -0.476407 0 0.99987 -0.0161055 0 0.998943 -0.0458873 -0.00275523 0.999645 -0.0266413 0.00104681 0.985098 -0.171951 -0.00383702 0.990407 -0.128981 0.0495718 0.980393 -0.196926 0.00706767 0.877731 -0.479154 0 0.928691 -0.370554 -0.014925 0.916852 -0.396725 -0.0446308 0.943169 -0.33225 -0.00653919 0.705251 0.514358 -0.487911 0.49052 0.61011 -0.622219 0.580562 0.580979 -0.570448 0.519187 0.604337 -0.604337 0.578234 0.533672 -0.617122 0.735932 0.474025 -0.483431 0.874944 0.350205 -0.334408 0.868171 0.352631 -0.349186 0.96574 0.18229 -0.184706 0.966431 0.181676 -0.181676 0.993095 0.0829511 -0.0829511 0.993095 0.0829511 -0.0829511 0.999197 0.0283273 -0.0283273 0.999197 0.0283273 -0.0283273 0.918559 0.27924 0.279777 0.941689 0.24 0.235842 0.945252 0.231197 0.230317 0.930754 0.258843 0.258258 0.890021 0.330505 0.314053 0.899935 0.311784 0.304807 0.872019 0.346522 0.345695 0.994573 0.0736631 0.0734729 0.994443 0.0751012 0.0737785 0.965688 0.183583 0.183696 0.974238 0.151142 0.16738 0.964071 0.186304 0.18936 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.00671748 -0.999939 -0.00872805 -0.00219593 0.999927 0.011904 -0.00437363 0.99997 0.00636918 -0.00527249 0.999938 0.00975946 -0.00213768 0.999996 -0.00162953 -0.00904414 0.999695 0.0230041 -0.00505971 0.99996 0.00737968 -0.00423358 0.999972 0.0062197 -0.00307791 0.999985 0.00463208 -0.00404538 0.999974 0.00604675 0.00747055 0.999965 0.00388245 0.00714832 0.999963 0.00488353 0.00705716 0.999962 0.00518908 0.0075546 0.999965 0.00345306 0.0289466 0.981074 -0.191455 0.058863 0.87816 -0.474733 0.0092853 0.999956 -0.00101888 -0.0099681 -0.999947 0.00246217 -0.0116087 -0.999921 0.00480858 0.0201534 0.999707 -0.013379 0.0258767 0.999513 -0.0174469 -0.00913172 0.999886 -0.0120135 -0.00445933 0.999929 -0.011017 -0.0103881 0.999872 -0.0121476 -0.00866599 0.999892 -0.0118965 -0.0180182 -0.999745 0.0136456 -0.0183699 -0.999737 0.0137459 -0.00197413 0.999932 -0.0115052 -0.00501185 0.999919 -0.0116704 0.00107189 0.999952 -0.00975418 0.00259125 0.999953 -0.00939328 -0.00305179 0.99993 -0.0114205 -0.00296912 0.999931 -0.0113866 -0.0019267 0.999938 -0.0109644 0.00156857 0.999952 -0.00963653 0.000436483 0.999949 -0.010078 -0.00585806 0.999904 -0.0125793 -0.0168695 0.999655 -0.0201412 -0.0144998 0.999722 -0.0186033 -0.019468 0.999559 -0.0224147 -0.0188968 0.999581 -0.0219078 -0.019159 0.999571 -0.022138 -0.0165135 0.999665 -0.0199105 -0.0190102 0.999576 -0.0220743 -0.0190957 0.999574 -0.0220826 -0.024249 0.999292 -0.0287728 -0.00927117 0.999929 -0.00744693 -0.0210885 0.999472 -0.0247028 -0.0141887 0.999774 -0.0158291 -0.0112497 0.99988 -0.0106751 -0.00367057 0.999966 0.00742965 -0.00314399 0.999954 0.00903162 -0.00301544 0.999951 0.00942183 -0.00829548 0.999949 -0.00569731 -0.00837424 0.999948 -0.0058392 -0.00216389 0.999991 0.00365257 -7.84003e-05 0.999999 0.00158453 -8.77176e-05 0.999999 0.0015904 -0.00014999 0.999999 0.00163353 -0.000589684 0.999998 0.00194528 0.0270061 0.999306 -0.0256598 0.0230606 0.999463 -0.0232814 -0.0254189 0.999268 0.0285887 0.000110396 0.999999 0.00152017 2.57221e-05 0.999999 0.00153906 -4.16621e-05 0.999999 0.0015572 2.31579e-06 0.999999 0.00154485 -0.000361877 0.999999 0.00164934 0.00118123 0.999999 0.00120196 0.0407737 0.998979 -0.0194529 -0.0330363 0.99928 0.0186363 0.000464147 0.999999 0.00148527 0.00127371 0.999998 0.00150441 0.000927778 0.999999 0.00146158 0.00073176 0.999999 0.00144592 0.000571563 0.999999 0.00143664 0.0311122 0.999514 -0.00196113 0.0664336 0.997764 -0.00733588 -0.0365989 0.999309 0.00650877 0.00176928 0.999997 0.00161505 0.00194113 0.999997 0.00170059 0.00192909 0.999997 0.0016952 0.00136575 0.999998 0.00146022 0.00775389 0.999966 0.00288624 0.00147323 0.999998 0.00150257 0.00296073 0.999993 0.00212205 0.00137418 0.999998 0.0014637 0.00354083 0.99999 0.00274203 0.00328038 0.999991 0.00249601 0.00264017 0.999995 0.00191724 -0.00508421 0.999984 -0.00253482 -0.206196 0.969722 -0.130853 0.0272195 0.999471 0.017782 -0.0300754 0.999372 -0.0187618 0.00533502 0.999974 0.00483601 0.00558346 0.99997 0.00538017 0.00537028 0.999973 0.00496223 0.0033731 0.999991 0.00256921 0.00525363 0.999975 0.00474536 0.00528312 0.999975 0.00479946 0.00429449 0.999986 0.00299707 -0.130952 0.97713 -0.167537 -0.404267 0.759191 -0.510095 0.006785 0.99996 0.00589835 0.010371 0.999496 -0.0300018 -0.55864 0.649282 0.516096 -0.0720835 0.82776 0.556433 -0.0181857 0.855879 0.516857 -0.011891 0.783176 0.621687 0.0834461 0.537776 0.838948 0.0760489 0.776178 0.62591 0.100204 0.818304 0.565984 0.326528 0.726604 0.604505 0.29905 0.738427 0.604396 0.282434 0.719515 0.634452 0.170607 0.712577 0.680535 0.197157 0.72477 0.660179 0.177049 0.760694 0.624499 -0.299672 0.73985 0.602344 -0.280225 0.717925 0.637226 -0.257382 0.734648 0.627731 -0.227434 0.713578 0.662631 -0.20945 0.73066 0.649821 -0.167099 0.711773 0.682244 -0.15599 0.726989 0.668696 -0.101171 0.712429 0.694413 -0.0969623 0.723069 0.683937 -0.0526522 0.717926 0.694125 -0.576991 -0.475802 0.663848 -0.4631 0.292448 0.836668 -0.727393 -0.153878 0.668746 -0.665405 0.104927 0.739072 -0.758358 0.170371 0.629179 -0.818801 -0.00429895 0.574062 -0.819911 0.191866 0.539383 -0.927151 -0.342005 0.153048 -0.922388 0.0475562 0.383325 -0.9598 0.135138 0.246013 0.997993 0.0616029 0.0146952 0.941988 0.115955 0.314981 0.924033 -0.00223225 0.382307 0.848605 0.19817 0.490508 0.779817 0.317536 0.539496 0.801229 0.271695 0.533117 0.830149 0.0472372 0.555538 0.865276 -0.293752 0.406212 0.672716 0.25401 0.694934 0.732502 -0.160543 0.661564 0.665303 -0.634195 -0.393915 0.268365 -0.802663 -0.532647 0.964632 0.145545 0.219777 0.93463 0.22851 0.27249 0.896683 0.304588 0.321224 0.824126 0.414246 0.386285 0.788156 0.457279 0.411953 0.622109 0.157307 0.766965 0.524412 0.113252 0.843899 0.584068 -0.447456 0.677235 0.389319 0.225927 0.892966 0.358698 -0.175452 0.916816 0.290193 0.141388 0.946466 0.107928 0.117921 0.987141 0.100933 0.173327 0.979679 -0.102451 0.0847251 0.991123 -0.0828596 0.479653 0.873537 -0.367018 -0.397311 0.841096 -0.325759 0.114182 0.938532 -0.425892 0.140675 0.893771 -0.780879 0.321935 0.535338 -0.671594 0.457388 0.582888 -0.324961 0.72477 0.607544 -0.341634 0.758287 0.555236 -0.14187 0.808318 0.571398 -0.18872 0.801972 0.566767 -0.788097 0.457815 0.411472 -0.709071 0.535842 0.458358 -0.897825 0.303211 0.319333 -0.822914 0.413214 0.389958 -0.96525 0.143583 0.218348 0.19127 0.7993 0.56968 0.560475 0.656926 0.504298 0.34005 0.754162 0.561788 0.710308 0.536686 0.455445 0.673087 0.457592 0.581002 0.689898 0.439331 0.575352 0.659618 0.40434 0.633572 0.381408 0.643091 0.66405 0.328837 0.605411 0.724806 0.493918 0.416912 0.763039 0.421898 0.384812 0.820928 0.232212 0.630159 0.74093 0.142589 0.605422 0.783028 0.233214 0.39751 0.887467 0.116771 0.383296 0.916214 0.0512844 0.617674 0.78476 -0.0598561 0.616994 0.784688 -0.0770614 0.378498 0.922389 -0.229188 0.397255 0.888629 -0.235803 0.372369 0.897629 -0.36883 0.407604 0.835358 -0.385761 0.370029 0.845143 -0.492759 0.417598 0.763414 -0.52009 0.372049 0.768821 -0.599425 0.427667 0.676602 -0.634314 0.378326 0.674177 -0.686669 0.437032 0.580938 -0.858875 0.173097 0.482048 -0.907697 0.281394 0.311293 -0.534083 -0.721042 -0.441423 -0.997995 0.0615381 0.0147966 0.823329 0.520799 0.225606 0.988131 0.028829 -0.150883 0.9883 0.129362 -0.0807969 0.980268 0.195235 -0.0309447 0.959142 0.281099 0.0320933 0.926481 0.363327 0.0981124 0.890624 0.429449 0.149538 0.782027 0.563379 0.26653 0.675855 0.650729 0.34608 0.555116 0.721771 0.413392 0.493947 0.747018 0.44495 0.189936 0.814957 0.547511 0.200219 0.814419 0.544642 -0.190706 0.774057 0.603711 -0.190867 0.80562 0.560844 -0.312608 0.885793 -0.342997 -0.466624 0.748963 0.470442 -0.997086 0.0760856 -0.00558453 -0.996957 0.0775341 -0.0080973 -0.968299 0.225257 0.107967 -0.968137 0.228574 0.1023 -0.899002 0.380034 0.217647 -0.898961 0.381682 0.214911 -0.78758 0.52166 0.328007 -0.787596 0.523518 0.324996 -0.641298 0.64204 0.420144 -0.0475363 0.998213 -0.036198 -0.0531764 0.99697 0.0567659 0.732116 -0.312106 -0.605472 0.880434 0.213003 -0.423634 0.741925 0.324881 -0.586514 0.637118 -0.0193439 -0.770524 0.297478 -0.677853 -0.672325 0.543462 0.116099 -0.831367 0.643605 0.10218 -0.758506 0.0763233 -0.853702 -0.515138 0.092617 0.561916 -0.821993 0.361076 -0.373331 -0.854546 -0.501989 0.09997 -0.859077 -0.374981 0.118603 -0.919414 -0.101283 -0.81074 -0.576578 -0.193486 0.0989841 -0.976097 -0.0663552 0.106816 -0.992062 -0.457114 -0.473456 -0.752919 -0.428916 -0.52861 -0.732532 -0.752836 0.107514 -0.649367 -0.82764 0.0692829 -0.556966 -0.531203 -0.573096 -0.624006 -0.919566 0.120561 -0.373984 -0.957011 0.0665836 -0.282307 -0.687554 -0.519838 -0.50699 -0.988513 0.128337 -0.0798282 -0.187534 0.924533 0.331767 -0.160275 0.924131 0.346834 -0.135151 0.933306 0.332677 -0.180542 0.945407 0.271312 -0.176351 0.947684 0.266075 -0.17002 0.957527 0.232884 -0.166817 0.952187 0.255954 0.255802 0.928574 0.268915 0.341706 0.923636 0.173589 0.0896502 0.937484 0.336284 0.165942 0.913934 0.370388 0.13852 0.878497 0.457226 0.305649 0.860625 0.407312 0.159701 0.850916 0.500437 -0.0394535 0.790481 0.611214 0.242678 0.863801 0.441537 0.787456 0.607515 0.104115 0.90927 0.399004 -0.118418 0.88265 0.467551 -0.0482171 0.937155 0.216267 -0.273806 0.931007 0.310267 -0.19225 0.681535 -0.379796 -0.625512 0.963063 0.0997459 -0.25012 -0.187513 0.839461 0.510043 -0.338562 0.8162 0.468181 -0.461561 0.783887 0.415311 -0.405057 0.913915 0.0262331 -0.405046 0.913306 0.0425335 -0.401416 0.915509 0.0266054 -0.0835615 0.962529 0.257984 -0.0299464 0.951663 0.305682 -0.300273 0.940791 -0.157314 -0.165211 0.959318 -0.228944 0.415492 0.882494 -0.220389 0.194659 0.906154 -0.375491 -0.00882408 0.862094 -0.506672 -0.232281 0.846774 -0.478559 -0.224985 0.86628 -0.446027 -0.477205 0.822949 -0.30827 -0.445862 0.858707 -0.252644 -0.653271 0.757013 -0.0129462 -0.600445 0.798477 0.0435804 -0.69514 0.661696 0.280959 -0.631756 0.703473 0.325592 -0.0015219 0.874906 0.484291 -0.287973 0.89614 0.337645 -0.00473308 0.894606 0.446831 -0.0886467 0.907072 0.411537 -0.329194 0.929443 0.166633 -0.391547 0.917158 0.0742453 -0.195086 0.944381 0.264736 -0.181319 0.94645 0.267126 -0.177532 0.947356 0.266457 -0.406305 0.913117 0.0336817 -0.406348 0.913198 0.0308334 -0.405942 0.91346 0.028312 -0.17512 0.948089 0.265442 -0.174195 0.94846 0.264725 -0.167277 0.95189 0.256756 -0.406993 0.912988 0.0284587 -0.405721 0.913576 0.0277357 -0.404761 0.914013 0.0273714 -0.166529 0.952407 0.255322 -0.16586 0.953028 0.253431 -0.165598 0.95446 0.248161 -0.391358 0.919809 0.0281169 -0.360182 0.931879 0.043241 -0.268352 0.957194 0.10848 -0.200987 0.963155 0.178711 -0.431737 0.885416 -0.172167 -0.590067 -0.134734 -0.796032 -0.124883 0.984177 0.125701 -0.0651015 0.993479 0.0936055 -0.119454 0.991093 -0.0588737 -0.0434141 0.996727 -0.0681945 -0.0105634 0.870467 -0.492114 0.221167 0.875009 -0.430633 0.494333 0.745918 0.446365 -0.160462 0.74119 0.651835 0.682981 0.69675 0.219262 0.534197 0.845264 -0.0127524 0.551541 0.833585 -0.0306437 0.394765 0.89792 -0.194682 0.114481 0.980895 0.157288 -0.00718444 0.997537 0.0697788 -0.035465 0.98894 0.14401 -0.0196576 0.999385 -0.0290495 0.293598 0.913759 0.280794 0.24988 0.919562 0.303258 -0.026307 0.953352 0.300714 0.258667 0.965606 0.0264107 0.341059 0.933326 0.112168 0.0769423 0.91608 0.393544 0.126578 0.921497 0.367181 0.21453 0.922276 0.321535 0.196891 0.921564 0.334595 0.178531 0.917402 0.355668 0.172158 0.915728 0.363049 0.263279 0.918092 0.296295 0.276951 0.916314 0.289252 0.288098 0.914649 0.28358 0.161198 0.912443 0.376116 0.158858 0.911669 0.378978 0.118684 0.896125 0.427638 0.404029 0.887391 0.22203 0.430303 0.864058 0.261235 0.305376 0.868207 0.391104 0.234508 0.869658 0.434398 0.289544 0.863098 0.413794 0.296104 0.862116 0.411192 0.235734 0.862998 0.446838 0.225965 0.861779 0.454178 0.204016 0.858678 0.470159 0.327908 0.856834 0.397884 0.376707 0.846853 0.375409 0.513454 0.804063 0.299745 0.291275 0.830999 0.473919 0.141123 0.776543 0.614056 0.211934 0.783108 0.584659 0.358035 0.568724 -0.740516 0.594131 0.789234 -0.155299 0.757392 -0.0718881 -0.648991 0.811284 0.292944 -0.505967 0.807279 0.340607 -0.481963 0.777956 0.504274 -0.374823 0.765405 0.540298 -0.349618 -0.775325 0.59161 0.221062 0.367687 0.534908 -0.76071 0.0298228 0.524966 -0.850601 0.0296953 0.526054 -0.849933 -0.303787 0.504815 -0.808007 -0.301604 0.536755 -0.787991 -0.62464 0.484763 -0.612234 -0.612101 0.547769 -0.570335 -0.850967 0.433116 -0.297094 -0.822918 0.518645 -0.231978 -0.930547 0.36468 0.0330287 -0.884625 0.453883 0.106907 0.615582 0.570097 -0.544104 0.625931 0.540649 -0.562058 0.665371 0.320312 -0.6743 0.402625 0.35018 -0.845734 0.40677 0.323218 -0.85444 0.0467473 0.311324 -0.949154 0.0459521 0.319681 -0.94641 -0.313629 0.297298 -0.901804 -0.314066 0.332417 -0.889304 -0.645497 0.280216 -0.710501 -0.643929 0.352049 -0.679277 -0.878979 0.239733 -0.412217 -0.871535 0.343514 -0.349894 -0.977149 0.192085 -0.0910063 -0.952845 0.303388 -0.00657883 -0.835467 0.525662 0.16023 -0.73147 0.67481 -0.0978953 -0.775031 0.611141 -0.16073 -0.545343 0.722369 -0.425187 -0.568175 0.671517 -0.475648 -0.271683 0.720799 -0.637681 -0.276514 0.694199 -0.664551 0.010971 0.713204 -0.700871 0.0101992 0.718362 -0.695595 0.30481 0.725569 -0.616961 0.28737 0.761805 -0.580579 0.540811 0.735986 -0.407245 0.52479 0.759371 -0.384644 0.690199 0.691941 -0.211759 0.672954 0.715193 -0.188766 0.823567 0.564928 0.0509396 0.648876 0.717493 0.253305 -0.188393 0.805941 -0.56122 -0.188619 0.804561 -0.56312 -0.466072 0.733476 -0.494763 -0.312954 0.885945 0.342287 -0.641253 0.641585 -0.420908 -0.787475 0.523264 -0.325697 -0.787776 0.521351 -0.328027 -0.898887 0.381382 -0.215754 -0.899097 0.379821 -0.217624 -0.967992 0.229009 -0.102694 -0.968408 0.225172 -0.107163 -0.996933 0.0778428 0.00805079 -0.997103 0.0758504 0.00575869 0.560631 0.64805 -0.515484 0.0721197 0.827745 -0.55645 0.0182 0.855868 -0.516874 0.0118909 0.783176 -0.621686 -0.0834437 0.537786 -0.838942 -0.0760474 0.776181 -0.625907 -0.100142 0.818322 -0.56597 -0.326535 0.7266 -0.604506 -0.299049 0.738427 -0.604397 -0.282434 0.719515 -0.634452 -0.170613 0.71257 -0.68054 -0.197161 0.724763 -0.660187 -0.177048 0.760696 -0.624497 0.299673 0.739851 -0.602343 0.280225 0.717924 -0.637228 0.257377 0.734651 -0.62773 0.227431 0.713581 -0.662629 0.209443 0.730666 -0.649816 0.167093 0.71178 -0.682239 0.155989 0.726989 -0.668696 0.10117 0.712432 -0.69441 0.0969619 0.723069 -0.683937 0.0526522 0.717926 -0.694125 0.576991 -0.475811 -0.663841 0.463104 0.292443 -0.836667 0.727398 -0.153891 -0.668738 0.665434 0.10485 -0.739056 0.758396 0.170287 -0.629157 0.81878 -0.00421552 -0.574093 0.819878 0.191934 -0.539409 0.92718 -0.341881 -0.153147 0.922385 0.04755 -0.383334 0.9598 0.135138 -0.246013 -0.997993 0.0615969 -0.0147142 -0.942046 0.115776 -0.314873 -0.924077 -0.00241327 -0.382198 -0.848522 0.198333 -0.490586 -0.779831 0.317511 -0.539491 -0.801271 0.271626 -0.53309 -0.83018 0.0471204 -0.555501 -0.865275 -0.293747 -0.406216 -0.672754 0.253952 -0.694917 -0.732522 -0.160638 -0.661519 -0.665369 -0.634147 0.39388 -0.268345 -0.802666 0.532653 -0.965244 0.143512 -0.218424 -0.934555 0.228681 -0.272603 -0.897764 0.302644 -0.320041 -0.824138 0.414233 -0.386274 -0.788096 0.457349 -0.411991 -0.622109 0.157307 -0.766965 -0.524406 0.113249 -0.843903 -0.584072 -0.447351 -0.677302 -0.389319 0.225948 -0.89296 -0.358698 -0.175452 -0.916816 -0.290193 0.141388 -0.946466 -0.107927 0.11792 -0.987141 -0.100932 0.173326 -0.979679 0.102452 0.0847248 -0.991123 0.0828606 0.479646 -0.873541 0.367017 -0.397354 -0.841076 0.325752 0.114226 -0.93853 0.425869 0.140729 -0.893774 0.780792 0.322062 -0.535388 0.671686 0.45729 -0.582858 0.324961 0.724771 -0.607543 0.341631 0.758281 -0.555247 0.142567 0.808152 -0.571459 0.191078 0.801536 -0.566595 0.788206 0.457692 -0.411399 0.709173 0.53575 -0.458307 0.896748 0.305125 -0.320533 0.822834 0.413384 -0.389945 0.964638 0.145586 -0.219724 -0.188892 0.799824 -0.569739 -0.558423 0.658108 -0.505032 -0.340058 0.754159 -0.561787 -0.710394 0.536609 -0.455402 -0.673158 0.457513 -0.580982 -0.689907 0.439317 -0.575351 -0.65963 0.404327 -0.633568 -0.381402 0.643095 -0.664049 -0.328833 0.605417 -0.724802 -0.493921 0.416914 -0.763037 -0.421896 0.384811 -0.820929 -0.232218 0.630151 -0.740935 -0.14259 0.605416 -0.783032 -0.233223 0.397482 -0.887477 -0.116776 0.383267 -0.916226 -0.051285 0.617669 -0.784764 0.0598582 0.616985 -0.784695 0.0770639 0.378478 -0.922397 0.229188 0.397256 -0.888629 0.23581 0.372342 -0.897639 0.368842 0.40758 -0.835365 0.385762 0.37003 -0.845143 0.49276 0.417599 -0.763412 0.520091 0.37205 -0.76882 0.599423 0.427665 -0.676605 0.634302 0.37834 -0.674181 0.68666 0.437046 -0.580939 0.858948 0.172945 -0.481974 0.907777 0.281245 -0.311194 0.534054 -0.721055 0.441437 0.997995 0.0615442 -0.0147774 -0.21444 0.926543 -0.309084 -0.120684 0.992605 0.0130752 -0.107803 0.941298 -0.3199 0.0522103 0.940444 -0.335916 -0.919401 0.119166 0.374834 -0.985538 0.139665 0.0959631 -0.80994 0.0777196 0.581341 -0.326221 -0.0503073 0.943954 -0.491744 0.124847 0.861743 -0.479019 -0.382332 0.790167 -0.161282 0.100604 0.981767 0.358619 0.109145 0.927081 0.245589 0.105929 0.963569 0.128047 -0.15342 0.97983 0.777815 -0.240099 0.580824 0.881519 0.245767 0.403141 0.746712 -0.124039 0.65348 0.361623 0.927138 -0.0982062 0.932382 0.308079 0.189082 0.88423 0.464947 0.044288 0.911791 0.395914 0.10904 0.775948 0.53595 0.332659 0.184044 0.935703 -0.30098 0.232823 0.933689 -0.272064 0.075778 0.892034 -0.44557 0.129007 0.887593 -0.442194 0.197449 0.814759 -0.545144 0.0671888 0.805152 -0.58925 0.215613 0.772037 -0.597888 -0.0536501 0.995736 -0.075037 -0.114229 0.993455 5.61654e-06 -0.0405095 0.991584 -0.122963 0.316511 0.941916 -0.112318 0.160081 0.9737 -0.162117 -0.0594739 0.994238 -0.0891791 -0.0599109 0.994127 -0.0901261 -0.0192093 0.994709 -0.100917 -0.111242 0.952041 -0.285031 -0.148993 0.922445 -0.356224 -0.0148875 0.995722 -0.0911918 0.127875 0.968331 0.214439 -0.0155398 0.967156 0.253709 -0.0245358 0.981011 0.192396 -0.12691 0.975284 0.180872 -0.318042 0.858824 0.401585 -0.109804 0.993763 0.0194603 -0.150683 0.959873 -0.236512 0.0281436 0.9361 -0.350607 -0.325049 0.943595 0.0630256 -0.234686 0.970913 -0.0474389 -0.441266 0.859556 0.257775 -0.475043 0.82305 0.311324 -0.540001 0.723097 0.430732 0.00892731 0.96176 -0.273747 0.267092 0.962594 0.0455473 0.0750313 0.984623 -0.157761 0.230711 0.97219 0.0402329 0.0950901 0.985735 0.138867 0.227374 0.875527 0.426325 -0.0053051 0.871377 0.490585 0.0175314 0.71326 0.70068 -0.271504 0.694337 0.666469 -0.294258 0.536491 0.790942 -0.621464 0.484705 0.615502 -0.637921 0.352529 0.684676 -0.878269 0.239273 0.413996 -0.52789 -0.575207 0.624875 -0.536241 -0.567618 0.624704 -0.199032 0.886618 -0.417485 0.0135827 0.887707 -0.460208 -0.437556 0.881521 -0.177385 -0.495038 0.858737 -0.132318 -0.598318 0.800343 -0.0383109 -0.653085 0.757132 0.0152313 -0.728853 0.676776 0.103675 -0.774658 0.610994 0.163067 -0.820001 0.520485 0.238104 -0.868374 0.34533 0.355913 -0.85037 0.432862 0.299167 -0.606272 0.548389 0.575937 -0.565362 0.671631 0.478829 -0.265171 0.720724 0.640501 -0.12474 0.987518 0.0961632 -0.108917 0.99394 0.0148733 -0.134033 0.988663 0.0676857 -0.135989 0.987835 0.075421 -0.139322 0.986318 0.0881255 -0.11107 0.993466 0.026226 -0.113506 0.992724 0.0401809 -0.117656 0.990706 0.0682581 -0.0398642 0.991493 -0.123909 -0.0459295 0.991317 -0.123216 0.960012 0.106181 0.25904 0.682912 -0.380161 0.623786 0.940312 0.214254 0.264401 0.817747 0.33788 0.465969 0.818716 0.290914 0.495048 0.73245 0.331606 0.594605 0.398346 -0.501224 0.768177 0.282115 -0.721992 0.631774 0.413711 0.35201 0.839602 0.789147 0.604521 -0.108634 0.825489 0.561234 -0.0598725 0.683216 0.709667 0.172012 0.786004 0.501027 0.362173 0.628194 0.568968 0.530704 0.661449 -0.00666121 0.74996 0.623171 0.329364 0.70935 0.641438 0.10359 0.760149 0.55247 0.116854 0.825301 -0.123151 -0.757627 0.640965 -0.307374 0.297462 0.903901 0.0548676 0.319721 0.945922 0.0377243 0.525735 0.849811 0.377168 0.535223 0.755831 0.297356 0.763247 0.573615 0.550403 0.734835 0.396326 0.405983 0.895602 0.181864 0.559479 0.828665 0.0172149 0.650483 0.714279 -0.25822 0.684524 0.692704 -0.227129 0.543946 0.839117 -0.00242849 0.698431 0.687684 0.198204 0.537072 0.75756 0.371021 0.635969 0.539565 0.551737 0.368936 0.57037 0.733869 0.416818 0.323306 0.849551 0.0552584 0.311824 0.948532 0.0808503 -0.846789 0.525748 -0.0623035 0.106526 0.992356 -0.18513 0.839984 -0.510053 -0.231021 0.835362 -0.498799 -0.459207 0.785951 -0.414017 -0.520627 0.761676 -0.385742 -0.631272 0.705162 -0.322864 -0.695943 0.660884 -0.280884 -0.774758 0.593558 -0.217805 -0.83613 0.524563 -0.160375 -0.883883 0.45613 -0.103423 -0.93113 0.363164 -0.0332909 -0.952028 0.305841 0.0101836 -0.9775 0.190504 0.0905606 -0.775167 -0.42774 0.464924 -0.950551 0.0758246 0.30117 0.478902 0.785225 -0.392524 0.501314 0.778445 -0.377767 0.39827 0.891868 -0.214363 0.0777238 0.910751 -0.405576 0.201101 0.936482 -0.287333 0.296514 0.94189 -0.157873 0.0898914 0.936976 -0.337633 0.0647972 0.938157 -0.340092 0.0564987 0.939379 -0.338193 0.318324 0.943017 -0.0968979 0.31674 0.944289 -0.0894116 0.296791 0.952508 -0.0681488 0.038499 0.94623 -0.321195 0.0783796 0.966056 -0.246154 0.131749 0.977885 -0.162429 0.0661404 0.970243 -0.232924 0.0404989 0.96652 -0.253376 0.423893 0.881086 0.209768 0.20308 0.907084 0.368724 0.312962 0.726111 0.612224 0.0169968 0.719355 0.694435 0.0377012 0.526089 0.849594 -0.297977 0.504902 0.810113 -0.306277 0.332231 0.892086 -0.642142 0.280309 0.713499 -0.346575 -0.649056 0.677209 -0.730501 0.116005 0.672987 0.189923 0.814959 -0.547513 0.200176 0.814422 -0.544652 0.988747 0.127532 0.0781999 0.987733 0.0309296 0.153061 0.959552 0.279397 -0.0345995 0.97986 0.196904 0.0332145 0.89096 0.427964 -0.151781 0.9261 0.364818 -0.0961572 0.782057 0.563351 -0.266499 0.823356 0.520771 -0.225574 0.555456 0.719228 -0.417349 0.674222 0.655824 -0.339587 0.49403 0.746989 -0.444907 0.996426 0 0.0844688 0.997036 -0.0056462 0.076731 0.99958 0.00420632 0.028675 0.999784 -9.91094e-05 0.0207864 0.999606 0.000136775 -0.028059 0.999768 0.00557574 -0.020786 0.996423 -0.0069821 -0.0842138 0.997052 0 -0.0767322 0.854413 -0.513134 0.0816789 0.979488 -0.178825 0.0928715 0.979183 -0.180742 0.0923764 0.982857 -0.180651 0.0368459 0.982857 -0.180648 0.0368462 0.982857 -0.180648 -0.0368459 0.982857 -0.180651 -0.0368462 0.85492 -0.51347 -0.0738995 0.838445 -0.540106 0.0727716 0.884295 -0.466205 0.0260045 0.856305 -0.515473 0.0321019 0.855319 -0.517515 -0.0246426 0.878565 -0.476486 -0.0329364 0.829992 -0.552078 -0.079518 0.979184 -0.180742 -0.0923679 0.979494 -0.178789 -0.0928721 0.85512 -0.513099 0.0741606 0.980348 -0.178783 -0.0833891 0.854184 -0.514701 -0.0738386 0.856958 -0.514795 -0.0246879 0.856401 -0.51573 -0.0244958 0.856381 -0.515728 0.0252171 0.856957 -0.514778 0.0250526 0.854196 -0.514691 0.0737728 0.980322 -0.178766 0.08374 0.980244 -0.17923 0.0836553 0.983378 -0.179338 0.0284021 0.983321 -0.179641 0.0284511 0.98334 -0.179641 -0.0277863 0.983394 -0.179337 -0.0278378 0.980261 -0.179228 -0.0834585 0.855156 -0.513119 -0.0736085 0.247434 0.463968 -0.850594 0.287859 0.474617 -0.831791 0.208826 0.524195 -0.825598 0.340362 0.572561 -0.745874 0.20253 0.601815 -0.772528 0.0778594 0.589087 -0.80431 0.266919 0.671877 -0.690895 0.257706 0.706551 -0.65907 0.277034 0.729588 -0.625263 0.263857 0.449373 -0.853489 0.276833 0.432114 -0.858278 0.297609 0.428428 -0.853158 0.316223 0.316244 -0.894423 0.235786 0.287535 -0.928293 0.594471 0.340516 -0.728459 0.448625 0.281816 -0.848125 0.515266 -0.0517282 -0.855468 0.539608 -0.0161881 -0.841761 0.683609 -0.275534 -0.675841 0.666119 -0.305767 -0.680288 0.706038 -0.460502 -0.538003 0.737636 -0.456677 -0.497333 0.703469 -0.441036 -0.557332 0.707101 -0.500004 -0.500004 0.707101 -0.500004 -0.500004 0.697726 -0.378617 -0.608135 0.697727 -0.378616 -0.608134 0.697727 -0.0713672 -0.7128 0.697726 -0.0713675 -0.712801 0.697726 0.250534 -0.671127 0.697727 0.250534 -0.671126 0.70684 0.413464 -0.573955 0.71341 0.389983 -0.582202 0.713839 0.414841 -0.564217 0.719715 0.391798 -0.573153 0.716523 0.35451 -0.600765 0.736227 0.0690198 -0.673206 0.769516 0.0922491 -0.63193 0.809689 0.0898217 -0.579945 0.770489 0.177947 -0.612113 0.710262 0.354414 -0.60821 0.715458 0.0309089 -0.697971 0.716967 0.0340419 -0.696275 0.715575 0.0320292 -0.697801 0.642561 -0.362618 -0.674999 0.647592 -0.46827 -0.601122 0.739146 -0.513955 -0.435333 0.675463 -0.0336782 -0.736624 0.587362 -0.0270311 -0.808873 0.617961 -0.447427 -0.646478 0.605323 -0.434053 -0.66722 0.492663 -0.236964 -0.837336 0.582961 -0.337094 -0.739273 0.651786 -0.225167 -0.724207 0.613338 -0.0817857 -0.785575 0.357566 0.596927 -0.718209 0.246581 0.645746 -0.722641 0.277437 0.681803 -0.676885 0.31147 0.655386 -0.688081 0.250026 0.717337 -0.650319 0.278891 0.752099 -0.597133 0.297074 0.7345 -0.610129 0.210825 0.861908 -0.461159 0.23697 0.848544 -0.473094 0.311808 0.859609 -0.404781 0.335923 0.824588 -0.455203 0.336149 0.865777 -0.370722 0.39072 0.884928 -0.253458 0.351692 0.917897 -0.183787 0.528393 0.838094 -0.13564 0.494155 0.864778 0.0892711 0.503828 0.86085 0.071378 0.592241 0.797734 0.113454 0.718495 0.646509 0.256496 0.655892 0.701998 0.277497 0.706834 0.519242 0.480389 0.720738 0.52813 0.449016 0.703469 0.557332 0.441036 0.707099 0.500005 0.500006 0.707101 0.500004 0.500004 0.696743 0.372104 0.61326 0.696743 0.372104 0.61326 0.696743 0.0468343 0.71579 0.696744 0.0468345 0.715789 0.696744 -0.289021 0.656517 0.696743 -0.289022 0.656518 0.707084 -0.425116 0.565074 0.707082 -0.425116 0.565076 0.641638 -0.532302 0.552228 0.701919 -0.472449 0.533012 0.715899 -0.459944 0.5253 0.706651 -0.448006 0.547663 0.552189 -0.630847 0.545087 0.549753 -0.614197 0.566157 0.568568 -0.605436 0.556936 0.634894 -0.557122 0.535279 0.546912 -0.627955 0.553679 0.551478 -0.626066 0.551284 0.544887 -0.637748 0.544404 0.54938 -0.635833 0.542123 0.479112 0.718967 0.503526 0.512997 0.65465 0.555218 0.564359 0.592556 0.574784 0.143506 0.637432 0.757025 0.629573 0.663579 0.404105 0.470373 0.76028 0.448022 0.533369 0.786887 0.310365 0.534128 0.786481 0.310089 0.5008 0.851322 0.156368 0.504854 0.84885 0.156768 0.563573 0.824397 0.0524864 0.540114 0.841584 0.00374545 0.618141 0.767572 -0.169514 0.595451 0.798214 -0.0910604 0.596896 0.8019 -0.0259175 0.588683 0.80479 -0.0759321 0.68261 0.700004 -0.20985 0.708234 0.673056 -0.213073 0.673703 0.657405 -0.337554 0.706365 0.550043 -0.445535 0.70522 0.550227 -0.447118 0.707099 0.500006 -0.500005 0.707102 0.500003 -0.500003 0.696745 -0.289021 -0.656516 0.696746 -0.289021 -0.656515 0.696746 0.0468341 -0.715787 0.696745 0.0468344 -0.715788 0.696745 0.372103 -0.613259 0.696743 0.372104 -0.61326 0.707084 -0.425116 -0.565074 0.707085 -0.425114 -0.565074 0.706563 -0.450685 -0.545574 0.54268 -0.647462 -0.535062 0.57238 -0.621606 -0.534778 0.676006 -0.556919 -0.482552 0.683642 -0.557322 -0.471196 0.637973 -0.514791 -0.572696 0.548313 -0.637708 -0.541001 0.545949 -0.635888 -0.545515 0.550405 -0.62799 -0.550166 0.548027 -0.626043 -0.55474 0.566418 -0.478786 0.670772 0.593463 -0.0323539 0.804211 0.632647 -0.0896767 0.76923 0.520994 -0.295744 0.800688 0.562944 -0.343955 0.751524 0.400966 -0.180872 0.89806 0.530362 -0.400206 0.747363 0.514349 -0.383933 0.766838 0.502794 -0.43449 0.747273 0.508804 -0.447015 0.735729 0.670653 0.0882561 0.736503 0.669083 0.0872783 0.738045 0.716245 0.175915 0.675313 0.592716 0.230254 0.771797 0.757473 0.268405 0.595141 0.743536 0.273517 0.6102 0.664379 0.397228 0.633096 0.647972 0.439247 0.62225 0.648393 0.445495 0.61735 0.637078 0.433174 0.637567 0.637268 0.441411 0.631701 0.626566 0.427847 0.651431 0.616709 0.267749 0.740257 0.616712 0.267748 0.740255 0.616712 -0.0832268 0.782777 0.61671 -0.0832267 0.782778 0.61671 -0.417415 0.667408 0.616713 -0.417415 0.667406 0.626577 -0.55109 0.55109 0.62658 -0.551089 0.551089 0.626563 -0.546339 0.555817 0.621123 -0.479647 0.619794 0.592648 -0.524198 0.611543 0.607956 -0.525811 0.594905 0.622719 -0.536219 0.569817 0.572099 -0.319543 0.755378 0.659597 -0.342537 0.669029 0.738389 -0.330068 0.588079 0.584511 -0.369545 0.722346 0.521054 -0.187939 0.832575 0.52775 -0.175867 0.830994 0.555399 -0.270582 0.786332 0.484241 0.203523 0.850934 0.325771 0.0303191 0.944963 0.469759 0.0191073 0.882588 0.44639 -0.0835395 0.890931 0.461272 -0.0866073 0.883022 0.332834 0.497269 0.801215 0.374095 0.424789 0.824383 0.446059 0.383872 0.808501 0.420659 0.366652 0.829827 0.355605 0.242613 0.902598 0.499885 0.645465 0.577485 0.306397 0.672273 0.673921 0.374673 0.58156 0.722085 0.332071 0.600321 0.72756 0.352086 0.508251 0.785949 0.196712 -0.966179 0.166742 0.228364 -0.951538 0.205974 0.224287 -0.952968 0.203831 0.180834 -0.941433 0.284611 0.213255 -0.941799 0.259879 0.216731 -0.924989 0.312128 0.17823 -0.900992 0.395535 0.245902 -0.902426 0.353778 0.180023 -0.8261 0.533995 0.163294 -0.820282 0.548155 0.264975 -0.82324 0.50206 0.259234 -0.821814 0.507364 0.191865 -0.68167 0.706056 0.22268 -0.699492 0.679061 0.271006 -0.657762 0.702784 0.219105 -0.602502 0.767453 0.284203 -0.580649 0.762938 0.25867 -0.460393 0.849193 0.301039 -0.441929 0.845029 0.301175 -0.442183 0.844848 0.301235 -0.442456 0.844683 0.314353 -0.436487 0.843008 0.314638 -0.436217 0.843041 0.347609 -0.419661 0.838483 0.347888 -0.419257 0.838569 0.396593 -0.390738 0.830685 0.396821 -0.390142 0.830857 0.480116 -0.327994 0.813578 0.489987 -0.332013 0.806028 0.428935 -0.367511 0.825197 0.959055 0.238432 0.152854 0.410566 0.666282 0.622498 0.81318 0.297702 0.500112 0.700316 0.250867 0.668299 0.708714 0.177253 0.682866 0.68432 0.0735131 0.725466 0.700035 -0.0474713 0.712529 0.554449 -0.0889832 0.827447 0.566651 -0.235721 0.78952 0.741439 0.0936354 -0.664455 -0.767848 0.579814 -0.272443 0.90723 0.316961 -0.276533 0.552869 0.520038 -0.651073 0.770435 0.256999 -0.583423 0.630495 0.106863 -0.768802 0.601492 -0.194208 -0.774914 0.607814 -0.221475 -0.762568 0.64049 -0.012732 -0.767861 0.51955 -0.287671 -0.804558 0.520136 -0.28737 -0.804286 0.493433 -0.313719 -0.811236 0.494051 -0.313568 -0.810919 0.450845 -0.350957 -0.820712 0.451508 -0.350982 -0.820337 0.365122 -0.411429 -0.835112 0.365796 -0.411857 -0.834606 0.301267 -0.44243 -0.844686 0.30104 -0.441929 -0.845029 0.317906 -0.93365 -0.165028 0.242422 -0.949027 -0.201445 0.158514 -0.944497 -0.287749 0.219675 -0.935627 -0.276307 0.210465 -0.909134 -0.359416 0.0739376 -0.855118 -0.513135 0.272793 -0.876542 -0.396557 0.246051 -0.854459 -0.457557 0.215082 -0.802359 -0.55674 0.228137 -0.795252 -0.561718 0.225255 -0.756176 -0.614376 0.178079 -0.659073 -0.730692 0.336394 -0.759827 -0.556329 0.202115 -0.61076 -0.765585 0.306579 -0.574711 -0.75876 0.23891 -0.468588 -0.850498 0.959056 0.13006 0.251588 0.41057 0.265766 0.872239 0.81318 0.00776119 0.581961 0.700317 -0.116891 0.704197 0.708714 -0.187923 0.680007 0.68432 -0.29907 0.665029 0.700034 -0.397375 0.593334 0.554448 -0.490784 0.6721 0.56665 -0.5989 0.565886 0.314346 -0.799514 0.511824 0.314628 -0.7993 0.511986 0.34761 -0.782677 0.516318 0.347892 -0.782367 0.516598 0.396592 -0.75373 0.524029 0.396818 -0.753302 0.524473 0.480114 -0.69084 0.540584 0.489988 -0.690545 0.532034 0.428927 -0.730878 0.530885 0.301038 -0.805236 0.510854 0.301175 -0.805365 0.510569 0.301234 -0.805519 0.510291 0.258669 -0.823307 0.505228 0.284202 -0.884324 0.370407 0.235565 -0.900585 0.365316 0.255984 -0.929104 0.266904 0.213244 -0.949484 0.230231 0.256889 -0.961361 0.0989639 0.199316 -0.976422 0.0829004 0.264978 -0.963976 0.0231754 0.163288 -0.984463 0.0645779 0.180028 -0.98242 0.0493968 0.245906 -0.958412 -0.144835 0.178233 -0.978049 -0.107954 0.216717 -0.957138 -0.192149 0.213239 -0.945566 -0.245833 0.180847 -0.957605 -0.22425 0.224294 -0.927208 -0.299964 0.228387 -0.92704 -0.297383 0.196736 -0.920104 -0.338678 0.74144 0.251138 0.622252 -0.767851 -0.365911 0.525846 0.907229 -0.136231 0.397967 0.552868 -0.124831 0.823865 0.770435 0.0691439 0.633758 0.630495 0.291856 0.719233 0.60149 0.555645 0.573993 0.607815 0.573091 0.549661 0.640492 0.394956 0.65862 0.519548 0.651408 0.552935 0.520143 0.651006 0.552849 0.493433 0.677307 0.545692 0.494048 0.677018 0.545493 0.450844 0.714293 0.535281 0.451505 0.714127 0.534944 0.36512 0.773863 0.517516 0.365796 0.773981 0.516861 0.301267 0.805499 0.510304 0.301039 0.805235 0.510854 0.306131 0.89155 -0.333801 0.209333 0.925635 -0.315245 0.231777 0.939839 -0.250962 0.254617 0.932928 -0.254588 0.1344 0.990245 -0.0367658 0.125763 0.991592 -0.0304831 0.256791 0.96486 -0.0557151 0.246607 0.968596 -0.0317338 0.215195 0.973223 0.0807995 0.23344 0.96793 0.0928272 0.196147 0.942754 0.269708 0.249948 0.948946 0.192428 0.242675 0.901996 0.357089 0.261133 0.90353 0.33977 0.261755 0.828564 0.494941 0.255388 0.824624 0.50475 0.196714 0.966179 -0.166742 0.228366 0.951538 -0.205974 0.224288 0.952968 -0.203831 0.180841 0.941435 -0.2846 0.213236 0.941801 -0.259888 0.216712 0.924988 -0.312143 0.178211 0.900989 -0.395551 0.245901 0.902424 -0.353784 0.180023 0.8261 -0.533996 0.163278 0.820276 -0.548168 0.264967 0.823236 -0.502071 0.259234 0.821812 -0.507369 0.191865 0.68167 -0.706055 0.222679 0.699492 -0.679062 0.271005 0.657761 -0.702785 0.219102 0.602498 -0.767457 0.284202 0.580645 -0.762942 0.258669 0.46039 -0.849195 0.301038 0.441926 -0.845031 0.301174 0.44218 -0.84485 0.301234 0.442453 -0.844685 0.314356 0.436481 -0.843009 0.31463 0.436222 -0.843041 0.347605 0.419664 -0.838482 0.347889 0.419254 -0.83857 0.396592 0.390736 -0.830687 0.396821 0.390137 -0.830859 0.480639 0.328751 -0.812963 0.480537 0.327578 -0.813497 0.959057 -0.238427 -0.15285 0.410575 -0.666277 -0.622498 0.813179 -0.297703 -0.500113 0.700316 -0.250869 -0.668298 0.708714 -0.177253 -0.682866 0.68432 -0.0735122 -0.725467 0.700034 0.0474709 -0.71253 0.554449 0.0889825 -0.827447 0.566652 0.235722 -0.78952 0.74144 -0.0936348 0.664455 -0.767845 -0.579817 0.272444 0.907229 -0.316963 0.276534 0.552866 -0.520041 0.651073 0.770435 -0.256998 0.583422 0.630495 -0.106862 0.768802 0.601491 0.194208 0.774914 0.607814 0.221477 0.762568 0.64049 0.0127326 0.767861 0.519551 0.287669 0.804558 0.52014 0.287367 0.804286 0.493433 0.313719 0.811236 0.494048 0.313569 0.81092 0.450844 0.350955 0.820713 0.451509 0.350981 0.820336 0.365124 0.411428 0.835112 0.365795 0.411854 0.834608 0.301266 0.442427 0.844688 0.301039 0.441926 0.845031 0.317906 0.93365 0.165028 0.242422 0.949027 0.201445 0.158525 0.944498 0.287739 0.219677 0.935629 0.276298 0.210466 0.909134 0.359415 0.0739286 0.855113 0.513144 0.27279 0.87654 0.396565 0.246061 0.854468 0.457536 0.215085 0.802358 0.556741 0.228137 0.795252 0.561718 0.225255 0.756176 0.614376 0.178079 0.659073 0.730692 0.336394 0.759827 0.556329 0.202116 0.610762 0.765584 0.30658 0.574712 0.758759 0.238908 0.468585 0.850501 0.959056 -0.13006 -0.251587 0.41057 -0.265766 -0.872239 0.81318 -0.00776119 -0.581961 0.700317 0.116891 -0.704197 0.708714 0.187923 -0.680007 0.68432 0.299069 -0.665029 0.700035 0.397376 -0.593333 0.554448 0.490786 -0.672099 0.56665 0.5989 -0.565886 0.314348 0.799516 -0.511819 0.314644 0.799291 -0.511989 0.347611 0.782676 -0.516319 0.347885 0.782375 -0.51659 0.396594 0.753732 -0.524024 0.396824 0.753299 -0.524473 0.480639 0.691191 -0.539668 0.480536 0.690437 -0.540723 0.301038 0.805236 -0.510854 0.301175 0.805365 -0.510569 0.301235 0.805522 -0.510286 0.267686 0.819629 -0.50651 0.165105 0.777009 -0.607452 0.345915 0.907793 -0.237179 0.236058 0.900915 -0.364183 0.246844 0.932902 -0.262225 0.213287 0.951064 -0.223576 0.226172 0.952243 -0.205132 0.227764 0.969467 -0.0908651 0.225088 0.970162 -0.0901185 0.224118 0.974438 -0.0155354 0.169545 0.983521 -0.0627833 0.253061 0.956964 0.142056 0.16107 0.982425 0.0943268 0.262679 0.928101 0.26387 0.181167 0.961042 0.208749 0.221486 0.928009 0.299571 0.26424 0.907641 0.326138 0.741439 -0.251137 -0.622252 -0.767851 0.365911 -0.525846 0.907229 0.13623 -0.397965 0.552869 0.124831 -0.823865 0.770435 -0.0691439 -0.633758 0.630494 -0.291855 -0.719234 0.60149 -0.555645 -0.573993 0.607813 -0.573089 -0.549665 0.64049 -0.394957 -0.658621 0.519548 -0.651408 -0.552935 0.520143 -0.651006 -0.552849 0.493433 -0.677307 -0.545692 0.494048 -0.677018 -0.545493 0.45084 -0.714297 -0.535279 0.451508 -0.71413 -0.534939 0.365126 -0.773864 -0.517511 0.365796 -0.773981 -0.516862 0.301267 -0.805498 -0.510305 0.301039 -0.805235 -0.510854 0.317908 -0.891078 0.323905 0.242416 -0.922607 0.300053 0.158528 -0.961827 0.223064 0.219699 -0.948421 0.228538 0.21049 -0.967032 0.143327 0.0739463 -0.99712 -0.0168268 0.272792 -0.957387 0.0948392 0.24606 -0.968759 0.0309912 0.215086 -0.973233 -0.0809693 0.228135 -0.969569 -0.0888303 0.225253 -0.962056 -0.15398 0.178076 -0.936119 -0.303266 0.336395 -0.936194 -0.101881 0.202116 -0.911727 -0.357636 0.306579 -0.877094 -0.36975 0.238909 -0.831057 -0.502261 0 0.780772 0.624816 0.000751883 0.81629 0.577642 -0.000500228 0.536102 0.844153 2.10562e-05 0.483158 0.875533 -1.1498e-05 0.259441 0.965759 -0.000603826 0.137264 0.990534 -5.73614e-05 0.0590794 0.998253 4.98494e-05 -0.176838 0.98424 -0.000392959 -0.248836 0.968546 0 -0.353434 0.93546 0.00779776 -0.23571 0.971792 0.00772962 0.780749 0.624797 0.0267253 0.631021 0.775305 0.0240957 0.818083 0.574596 0.0322203 0.455827 0.889485 0.0372944 0.577474 0.815557 0.0371172 0.485774 0.873296 0.0561454 0.749606 0.659499 0.0545789 0.816975 0.574084 0.0589776 0.882357 0.466869 0.0492571 0.966237 0.252901 0.0691149 0.895208 0.440256 0.0291604 0.925882 0.376685 0.0226464 0.829895 0.557459 0.00191748 0.831465 0.555574 0.00641572 0.631356 0.775466 0.00380492 0.483154 0.875527 0.00465665 0.45633 0.889798 0.00432743 0.259438 0.96575 0.00649356 0.158047 0.98741 0.0028272 0.0590792 0.998249 0.00142281 -0.236335 0.971671 0.00483634 -0.176836 0.984228 0.000415862 -0.353434 0.935459 0.0118601 -0.192465 0.981232 0.0208174 0.139845 0.989955 0.0207402 0.15781 0.987252 0.0310368 0.359242 0.932728 0.0733134 0.964894 0.252201 0.0135959 -0.1926 0.981183 0.0146799 -0.203142 0.979039 0.00639765 -0.17272 0.98495 0.0283263 0.993384 0.111296 0.0336117 0.998409 0.0452831 0.0499434 0.934462 0.352542 0.0447108 0.883047 0.467149 0.0483564 0.815931 0.576124 0.0433023 0.750295 0.659684 0.0451914 0.646278 0.761763 0.0386826 0.577396 0.815548 0.0366922 0.315808 0.948113 0.0438791 0.358363 0.932551 0.0242025 0.139597 0.989913 0 -0.306895 0.951744 -0.00749371 -0.172718 0.984943 0 -0.0626782 0.998034 0 0.316021 0.948752 -0.0157368 0.188381 0.98197 0.000210725 0.42485 0.905264 -0.000212584 0.646939 0.762542 0.000156406 0.651254 0.75886 -0.000134372 0.816886 0.576799 0 0.818272 0.574832 0 0.93563 0.352982 0.00750202 0.969083 0.24662 0 0.993782 0.11134 0.509293 -0.22478 0.830719 0.28457 -0.230528 0.930525 0.571647 0.304606 0.761863 0.406671 0.811195 0.420216 0.311041 0.877391 0.365292 0.423353 0.708874 0.564154 0.629518 0.081514 0.772698 0.604397 0.0451082 0.795405 0.608014 0.0309205 0.793324 0.703099 0.0308941 0.71042 0.692469 0.0829975 0.716658 0.739163 0.0832009 0.668368 0.142937 -0.1505 0.978222 0.0309255 0.991681 0.124948 0.0353979 0.968503 0.246472 0.0851509 0.837372 0.539961 0.0881903 0.815083 0.572592 0.114266 0.673262 0.730521 0.11583 0.64687 0.753752 0.137021 0.463696 0.875335 0.137727 0.420801 0.896637 0.150609 0.228939 0.961719 0.14992 0.186275 0.970992 0.154189 -0.00815044 0.988008 0.151256 -0.0619571 0.986551 0.148876 -0.303475 0.941137 0.218065 0.965329 0.143483 0.100312 0.987794 0.119163 0.340341 0.853532 0.394527 0.515762 0.519908 0.680945 0.547473 0.450456 0.705239 0.627358 0.450101 0.635477 0.608529 0.483333 0.629351 0.683545 0.483615 0.546702 0.783101 0.1011 0.613622 0.774924 0.135286 0.617406 0.161297 0.980474 0.112488 0.482642 0.80961 0.334048 0.45734 0.829235 0.321262 0.595976 0.688363 0.413485 0.708506 0.554585 0.436412 0.851459 0.135208 0.506692 0.836005 0.194642 0.51304 0.0871656 0.990421 0.107093 0.129289 0.953066 0.273768 0.224277 0.853426 0.470494 0.233539 0.837684 0.493705 0.304699 0.706353 0.638924 0.315936 0.673791 0.667975 0.368442 0.517332 0.77241 0.378702 0.464201 0.800689 0.410354 0.30263 0.860247 0.416223 0.22925 0.879888 0.429068 0.0812173 0.899613 0.427707 -0.00815694 0.903881 0.384082 0.39565 0.834232 0.375521 -0.229603 0.897923 0.168826 0.980746 0.0981605 0.480624 0.831209 0.279449 0.719038 0.55516 0.41807 0.847916 0.1949 0.493003 0.847917 0.194893 0.493004 0.798892 0.194892 0.569025 0.798893 0.194884 0.569026 0.75568 0.195017 0.625232 0.656878 -0.498215 0.565944 0.726039 0.195057 0.659409 0.68093 0.194894 0.70594 0.680931 0.194882 0.705942 0.612998 0.194885 0.765672 0.612996 0.194907 0.765668 0.719045 0.555147 0.418074 0.67747 0.555148 0.48254 0.677466 0.555157 0.482536 0.630128 0.555159 0.542897 0.630126 0.555164 0.542895 0.577431 0.555162 0.598639 0.577431 0.555162 0.598639 0.519823 0.555163 0.64929 0.51982 0.555172 0.649285 0.480634 0.831202 0.279455 0.452844 0.831202 0.322546 0.452849 0.831198 0.32255 0.421207 0.831198 0.362898 0.421205 0.8312 0.362895 0.38598 0.8312 0.400157 0.385978 0.831203 0.400154 0.347471 0.831202 0.434012 0.347476 0.831197 0.434019 0.168824 0.980746 0.098159 0.159063 0.980746 0.113295 0.159059 0.980747 0.113292 0.147946 0.980747 0.127465 0.147953 0.980745 0.127471 0.13558 0.980745 0.14056 0.135579 0.980746 0.140558 0.122053 0.980746 0.152451 0.122052 0.980746 0.15245 0.113322 0.980784 0.158811 0.570875 0.195103 0.797519 0.571248 0.185397 0.799565 0.484601 0.55557 0.67565 0.488113 0.543512 0.682891 0.323497 0.831463 0.451685 0.325048 0.829349 0.45445 0.112765 0.980935 0.158272 0.116642 0.979121 0.166481 0.882314 0.4377 -0.173036 0.461959 0.847004 0.263018 0.523444 0.811618 0.25939 0.424567 0.803711 0.416883 0.407312 0.824623 0.392549 0.674665 0.719784 0.16352 0.59832 0.777297 0.19448 0.581597 0.759007 0.292667 0.978744 0.182425 0.0937126 0.999215 -0.0387366 -0.0082859 0.639327 0.184659 0.746433 0.637424 0.476004 0.605897 0.775567 0.175997 0.606235 0.916302 0.182841 0.356314 0.767677 0.518157 0.377074 0.958447 0.159607 0.236444 0.464295 0.810116 0.35797 0.205935 0.948752 0.23971 0.304935 0.928711 0.210975 0.213868 0.964037 0.157774 0.152866 0.975738 0.156739 0.145057 0.978545 0.146312 0.299754 0.869224 0.393188 0.673458 0.722085 0.158268 0.726193 0.680888 0.0950521 0.867771 0.492209 -0.0685857 0.854909 0.517051 -0.0423039 0.900146 0.128832 -0.416101 0.914757 0.180828 -0.361276 0.964811 0.105935 -0.240662 0.951927 -0.00198652 -0.30632 0.97331 0.222025 -0.0580841 0.890275 0.454949 0.0207851 0.766779 0.621619 0.160123 0.851065 0.513275 0.110622 0.812819 0.474109 0.338446 0.778473 0.528177 0.339131 0.620221 0.516987 0.589958 0.609022 0.536465 0.584207 0.919993 0.0453138 -0.389307 0.918265 0.0438642 -0.39353 0.899276 0.13012 -0.417579 0.5497 0.667958 0.50166 0.912733 0.0979619 0.396637 0.914585 0.0985768 0.392195 0.889432 0.288308 0.354667 0.889758 0.288304 0.353853 0.68716 0.114834 0.717373 0.68854 0.115143 0.715999 0.659067 0.337657 0.672026 0.659881 0.337787 0.67116 0.603406 0.543474 0.583556 0.602107 0.54337 0.584993 0.840998 0.463579 0.278956 0.840447 0.463777 0.280284 0.949043 0.303692 -0.0841964 0.981376 0.188696 -0.0359749 0.788827 0.216418 0.575253 0.997837 0.0656526 -0.00330023 0.896488 0.121469 -0.426092 0.658779 0.61708 0.430375 0.90112 0.409635 -0.142061 0.770427 0.613395 0.173751 0.77269 0.611917 0.168841 0.406185 0.72816 0.552084 0.510115 0.746653 0.426956 0.702702 -0.00128207 0.711483 0.69175 -0.000890409 0.722137 0.921469 -0.0010865 0.388451 0.917164 -0.000790767 0.398509 0.999955 -0.000709396 -0.00949018 0.999994 -0.000547481 -0.00335957 0.920191 -0.000249261 -0.39147 0.920923 -0.000204458 -0.389745 0.895268 -0.118056 -0.429602 0.873562 -0.0457316 -0.48456 0.690436 -0.192188 0.697396 0.689614 -0.192108 0.698232 0.910423 -0.16415 0.379717 0.908975 -0.16413 0.383179 0.994017 -0.108092 -0.0157127 0.994059 -0.108435 -0.00943917 0.894857 -0.0260611 -0.445592 0.920126 -0.0118036 -0.391444 0.608611 -0.546508 0.575257 0.608581 -0.546509 0.575289 0.840599 -0.466365 0.275494 0.840594 -0.466368 0.275505 0.948124 -0.306558 -0.0841639 0.948124 -0.306556 -0.084168 0.902539 -0.104144 -0.417825 0.915972 -0.0474968 -0.398422 0.457691 -0.817216 0.350254 0.457707 -0.817213 0.350238 0.711821 -0.697383 0.0834743 0.711823 -0.697381 0.0834712 0.863477 -0.458414 -0.210391 0.863476 -0.458418 -0.210386 0.864798 -0.112648 -0.489321 0.877534 -0.149461 -0.455626 0.260478 -0.963845 0.0561551 0.260481 -0.963845 0.0561525 0.454837 -0.885717 -0.0928883 0.540241 -0.823853 -0.171481 0.663508 -0.699261 -0.266068 0.749635 -0.542407 -0.379265 0.83373 -0.258385 -0.487987 0.822894 -0.350768 -0.446999 0.16203 -0.980786 -0.108652 0.156699 -0.982062 -0.104875 0.367294 -0.896881 -0.246372 0.362392 -0.899788 -0.24301 0.505626 -0.793336 -0.339059 0.586058 -0.707103 -0.395653 0.658921 -0.60876 -0.441854 0.744865 -0.44237 -0.499485 0.801323 -0.258837 -0.539337 0.814593 -0.195083 -0.546243 0.164542 -0.980775 -0.104913 0.164538 -0.980776 -0.104908 0.373001 -0.896834 -0.237821 0.478388 -0.831458 -0.282528 0.513404 -0.793258 -0.327351 0.669011 -0.608658 -0.426568 0.710921 -0.555558 -0.431215 0.756246 -0.442274 -0.482168 0.826999 -0.195065 -0.527278 0.826997 -0.195033 -0.527293 0.914283 -0.181446 -0.362165 0.931159 -0.11677 -0.345408 0.73947 -0.491979 -0.459501 0.780053 -0.431068 -0.45354 0.453795 -0.741883 -0.493639 0.515522 -0.694389 -0.502057 0.117817 -0.880717 -0.458755 0.192639 -0.854631 -0.482178 0.868142 -0.194772 -0.4565 0.875179 -0.151555 -0.459449 0.711826 -0.555558 -0.42972 0.744292 -0.495713 -0.447547 0.444449 -0.830081 -0.336795 0.502612 -0.78047 -0.371817 0.110721 -0.9752 -0.191642 0.200153 -0.947108 -0.25085 0.959022 -0.183466 -0.215912 0.958606 -0.195013 -0.207473 0.810868 -0.527796 -0.252833 0.799311 -0.553725 -0.23343 0.539611 -0.806675 -0.24103 0.519534 -0.825338 -0.221135 0.202437 -0.959289 -0.196935 0.165284 -0.972008 -0.16698 0.946378 -0.164085 -0.278289 0.946406 -0.163697 -0.278423 0.788846 -0.4654 -0.401404 0.781707 -0.482811 -0.394749 0.520012 -0.711964 -0.471905 0.495702 -0.738954 -0.45632 0.193472 -0.85711 -0.477421 0.150422 -0.879804 -0.450907 0.969478 -0.195086 0.148502 0.155023 -0.980228 0.12297 0.155028 -0.980226 0.122973 0.43971 -0.827647 0.348792 0.439708 -0.827648 0.348791 0.654358 -0.549903 0.519059 0.654355 -0.549909 0.519057 0.768818 -0.192353 0.609852 0.768819 -0.192346 0.609853 0.187338 -0.980226 0.0637239 0.187335 -0.980227 0.0637232 0.531348 -0.827648 0.180742 0.531342 -0.827652 0.18074 0.790732 -0.549906 0.268973 0.790734 -0.549903 0.268974 0.92905 -0.192344 0.316023 0.929051 -0.19234 0.316023 0.981117 -0.192478 -0.0189985 0.964248 -0.264617 -0.0143153 0.835135 -0.549905 -0.0123985 0.835141 -0.549896 -0.0123992 0.561188 -0.827647 -0.00833187 0.561177 -0.827654 -0.00833092 0.197855 -0.980227 -0.00293724 0.197855 -0.980227 -0.00293726 0.366943 -0.831455 0.417175 0.133416 -0.980775 0.142407 0.129179 -0.957509 0.257855 0.11543 -0.955941 0.269912 0.21057 -0.829536 0.517233 0.0156005 -0.861702 0.507176 0.381292 -0.65061 0.656752 0.224923 -0.711549 0.665663 0.51995 -0.40942 0.749684 0.442002 -0.458885 0.770752 0.615162 -0.141341 0.775627 0.599206 -0.156459 0.785158 0.142663 -0.92091 0.362728 0.119017 -0.915892 0.383375 0.392468 -0.755007 0.525294 0.340719 -0.769787 0.539758 0.570694 -0.490064 0.658898 0.486798 -0.553463 0.6758 0.653767 -0.170086 0.737333 0.632189 -0.195028 0.749867 0.124344 -0.793206 0.596123 0.58624 -0.122078 0.800887 0.135187 -0.776284 0.615717 0.0712815 -0.751786 0.655544 0.322012 -0.604522 0.728602 0.259234 -0.590384 0.764359 0.480351 -0.37762 0.791623 0.443172 -0.369731 0.816638 0.59583 -0.129507 0.7926 0.586181 -0.12603 0.800318 0.340633 -0.738183 0.582284 0.134819 -0.912679 0.3858 0.0845964 -0.948831 0.304241 0.14246 -0.956552 0.254389 0.631572 -0.163825 0.757812 0.623693 -0.195007 0.756954 0.53775 -0.479171 0.6937 0.497636 -0.554336 0.667135 0.175791 -0.928345 0.327526 0.32916 -0.830471 0.449413 0.097037 -0.979923 0.174169 0.0294354 -0.880767 0.472634 0.167056 -0.792107 0.587077 0.249913 -0.712076 0.656119 0.342117 -0.615251 0.710227 0.448923 -0.45569 0.768645 0.493273 -0.384958 0.780057 0.592673 -0.153574 0.790667 0.601647 -0.130987 0.787949 0.652618 -0.195092 0.73214 0.652622 -0.195075 0.732141 0.553279 -0.555537 0.620694 0.55327 -0.555554 0.620687 0.369685 -0.831463 0.414731 0.369684 -0.831464 0.414731 0.129815 -0.980785 0.145634 0.129818 -0.980784 0.145636 0.576542 -0.55539 0.599284 0.319217 -0.937695 0.137219 0.396041 -0.83106 0.390501 0.36637 -0.870689 0.328136 0.433682 -0.860986 0.265752 0.464377 -0.836254 0.291605 0.048401 -0.877452 -0.477217 0.443051 -0.892783 0.0815101 0.157678 -0.980143 0.120239 0.106971 -0.993905 0.026656 0.163969 -0.986127 -0.0258391 0.116147 -0.986844 -0.112464 0.192851 -0.963764 -0.184301 0.393263 -0.911294 -0.122014 0.435743 -0.896729 -0.0774965 0.535672 -0.841585 0.0692157 0.571591 -0.812567 0.114102 0.65383 -0.706549 0.270731 0.38625 -0.920416 -0.0603762 0.694156 -0.551728 0.462325 0.711051 -0.486853 0.507326 0.722695 -0.240954 0.647806 0.722739 -0.19864 0.66196 0.67878 -0.195004 0.707977 0.67651 -0.211831 0.70531 0.515912 -0.730728 0.447071 0.654007 -0.504725 0.563496 0.56207 -0.691959 0.453068 0.620223 -0.675515 0.398753 0.525754 -0.817957 0.233514 0.490232 -0.850238 0.191749 0.399682 -0.91457 0.0617784 0.347449 -0.937675 0.00672989 0.197858 -0.964097 -0.177114 0.280061 -0.925364 -0.255475 0.222255 -0.925821 -0.305709 0.593494 -0.800043 0.0877325 0.377158 -0.919955 -0.106934 0.449905 -0.887957 -0.0954891 0.211328 -0.931829 -0.295019 0.310003 -0.905999 -0.288208 0.0159005 -0.895868 -0.444036 0.445952 -0.841509 0.304941 0.390991 -0.868815 0.303789 0.343121 -0.932651 0.111488 0.732158 -0.234899 0.639349 0.752791 -0.192573 0.629461 0.686708 -0.555842 0.468478 0.728652 -0.48317 0.485399 0.139344 -0.982216 0.125833 0.137181 -0.99054 -0.0035607 0.147711 -0.988934 -0.0138037 0.148266 -0.977943 -0.147119 0.480335 -0.854448 0.19798 0.552521 -0.808888 0.201052 0.330785 -0.9435 0.0197193 0.429348 -0.902762 0.0260899 0.168187 -0.974155 -0.150785 0.152776 -0.97658 -0.151497 -0.00691548 -0.896257 -0.443482 0.696979 -0.210071 0.685632 0.711823 -0.187242 0.67694 0.626963 -0.514317 0.585145 0.681848 -0.433891 0.588916 0.587244 -0.608072 0.534222 0.523441 -0.848274 0.0802551 0.672007 -0.695546 0.25421 0.654817 -0.656359 0.37471 0.65278 -0.6659 0.361185 0.589266 -0.687013 0.425181 0.581701 -0.628385 0.516485 0.340805 -0.87258 0.349936 0.568738 -0.774806 0.276066 0.357979 -0.897663 0.257006 0.717967 -0.187172 0.67044 0.705263 -0.258514 0.660132 0.137097 -0.98225 0.128022 0.137101 -0.982249 0.128025 0.31837 -0.900143 0.297294 0.318351 -0.900155 0.297277 0.445256 -0.793015 0.415781 0.445265 -0.793006 0.415789 0.580086 -0.60834 0.541685 0.580085 -0.608341 0.541685 0.658179 -0.434807 0.614609 0.304962 -0.899575 0.31267 0.149053 -0.958646 0.24245 0.135568 -0.982227 0.129817 0.220182 -0.835268 0.503833 0.0159568 -0.856173 0.516443 0.347843 -0.715118 0.606309 0.332435 -0.722518 0.606181 0.71475 -0.157041 0.681521 0.691259 -0.175397 0.700997 0.564832 -0.465953 0.681068 0.574501 -0.459203 0.677556 0.433614 -0.598065 0.674016 0.717506 -0.258693 0.646732 0.796336 -0.187109 0.575187 0.494437 -0.601038 0.627922 0.650687 -0.496397 0.574628 0.382056 -0.787461 0.483672 0.43608 -0.759643 0.482468 0.417457 -0.777943 0.469611 0.144494 -0.9165 0.373026 0.125694 -0.954604 0.27006 0.410277 -0.750325 0.518349 0.115324 -0.981058 0.155646 0.166952 -0.960697 0.221786 0.107263 -0.949223 0.295754 0.159603 -0.920307 0.357157 0.0546428 -0.874656 0.481655 0.186194 -0.813174 0.551435 0.32029 -0.713223 0.62348 0.754327 -0.168137 0.634603 0.72654 -0.258556 0.636623 0.642273 -0.491569 0.588086 0.569161 -0.606783 0.554861 0.215567 -0.928813 0.301391 0.449511 -0.79262 0.411939 0.304963 -0.898877 0.314672 0.332578 -0.703794 0.627747 0.441558 -0.604389 0.663129 0.556222 -0.45868 0.692986 0.563171 -0.449731 0.693239 0.722947 -0.156137 0.673029 0.707133 -0.188827 0.681401 0.773142 -0.258735 0.579058 0.487383 -0.793227 0.365033 0.787792 -0.187299 0.586773 0.72066 -0.435108 0.53975 0.635103 -0.608591 0.47567 0.635097 -0.6086 0.475666 0.487383 -0.793227 0.365033 0.150021 -0.982277 0.112361 0.348465 -0.900254 0.260989 0.348466 -0.900253 0.260989 0.150019 -0.982278 0.112359 0.769411 -0.434454 0.468248 0.201485 -0.953251 -0.225202 0.181118 -0.981116 0.0678725 0.535605 -0.844148 0.0232962 0.853373 -0.224371 0.470544 0.854747 -0.190037 0.483004 0.81672 -0.207184 0.538557 0.819818 -0.187275 0.541134 0.585283 -0.809225 0.0509705 0.408608 -0.90936 -0.0781286 0.151837 -0.946841 -0.283615 0.212728 -0.902677 -0.374059 0.190697 -0.978573 -0.077649 0.131621 -0.991273 0.00738786 0.437003 -0.863932 0.250298 0.374688 -0.899823 0.223445 0.52745 -0.792225 0.306882 0.141702 -0.980267 -0.13783 0.499189 -0.851304 0.161529 0.47147 -0.873992 0.117701 0.670005 -0.674219 0.310681 0.721066 -0.65134 0.236263 0.668758 -0.60836 0.427389 0.559813 -0.777199 0.287352 0.777142 -0.489107 0.396011 0.823005 -0.466074 0.324711 0.593059 -0.804499 0.0325892 0.785766 -0.590162 0.185149 0.638441 -0.769119 -0.0291276 0.529964 -0.83968 -0.118639 0.478676 -0.858915 -0.182027 0.353813 -0.889713 -0.28849 0.16322 -0.889128 -0.427564 0.182179 -0.87093 -0.45639 0.859422 -0.218483 0.462233 0.428062 -0.865011 0.261761 0.612086 -0.775747 0.153517 0.405341 -0.897535 0.173582 0.17143 -0.981916 0.0803279 0.152199 -0.988068 -0.0236226 0.171991 -0.932957 -0.316244 0.201441 -0.910715 -0.360581 0.494511 -0.84322 -0.210805 0.289388 -0.937019 -0.195578 0.722383 -0.664716 -0.190567 0.523612 -0.844847 -0.109837 0.805661 -0.571148 0.157164 0.794313 -0.433745 0.425362 0.748985 -0.502407 0.431981 0.840247 -0.18723 0.508852 0.693574 -0.607668 0.386905 0.69295 -0.609241 0.385547 0.686811 -0.668959 0.284226 0.493729 -0.853591 0.166175 0.495937 -0.864748 0.0791107 0.179233 -0.981697 -0.0644009 0.161519 -0.972029 -0.170501 0.189695 -0.958469 -0.212963 0.423395 -0.900214 -0.10174 0.493311 -0.865885 0.0829921 0.56729 -0.820222 0.0736031 0.736521 -0.643918 0.207139 0.797657 -0.571941 0.191378 0.82063 -0.469588 0.32566 0.873459 -0.183429 0.451025 0.830123 -0.204802 0.518606 0.833 -0.187312 0.520601 0.81801 -0.258727 0.513731 0.158946 -0.982277 0.0993365 0.158946 -0.982277 0.0993369 0.369111 -0.900301 0.230684 0.369163 -0.900272 0.230715 0.516358 -0.793243 0.322708 0.516344 -0.793256 0.322699 0.672862 -0.608623 0.420518 0.672858 -0.608628 0.420516 0.763517 -0.435138 0.477175 0.349778 -0.899303 0.262505 0.171672 -0.963028 0.20762 0.148629 -0.981982 0.11671 0.214086 -0.849685 0.481875 0.0607167 -0.856253 0.512975 0.37854 -0.736637 0.560422 0.396936 -0.728676 0.558098 0.825759 -0.150327 0.543621 0.786944 -0.179397 0.590369 0.656236 -0.473 0.587899 0.647536 -0.478806 0.592825 0.492631 -0.621856 0.608778 0.825176 -0.258797 0.502104 0.858424 -0.24283 0.451821 0.588286 -0.600107 0.542026 0.723756 -0.508261 0.466742 0.455759 -0.786954 0.415918 0.482629 -0.773388 0.411024 0.484142 -0.77201 0.411835 0.166305 -0.924531 0.342906 0.140822 -0.955265 0.260072 0.82611 -0.160838 0.540068 0.464148 -0.763733 0.448641 0.176539 -0.928464 0.326786 0.128421 -0.949902 0.284946 0.183202 -0.965072 0.187278 0.084039 -0.87093 0.484168 0.195579 -0.831773 0.519521 0.384407 -0.716895 0.581629 0.847434 -0.172712 0.502022 0.841086 -0.194946 0.50455 0.719207 -0.503936 0.47832 0.685079 -0.553637 0.473447 0.247781 -0.930263 0.270583 0.45546 -0.829866 0.322302 0.141133 -0.978978 0.147255 0.36939 -0.726481 0.579463 0.498451 -0.628785 0.596805 0.646121 -0.463543 0.606347 0.640559 -0.469999 0.607277 0.832172 -0.13219 0.538531 0.794729 -0.188824 0.576845 0.871386 -0.194996 0.45018 0.871381 -0.195024 0.450178 0.738799 -0.555422 0.381683 0.738802 -0.555418 0.381684 0.493724 -0.83137 0.255071 0.493715 -0.831376 0.255066 0.173384 -0.980772 0.0895751 0.173388 -0.980772 0.0895765 0.897414 -0.194988 0.395762 0.564991 -0.795526 -0.218915 0.58082 -0.789506 -0.198316 0.533243 -0.840682 -0.094367 0.557791 -0.827583 -0.0630576 0.924621 -0.183556 0.333741 0.922368 -0.211574 0.323223 0.184693 -0.87893 -0.439738 0.215766 -0.88438 -0.413905 0.166111 -0.937575 -0.305551 0.208592 -0.940576 -0.267967 0.201029 -0.972275 -0.119456 0.157798 -0.974582 -0.159026 0.536481 -0.841272 0.0667062 0.511261 -0.858642 0.0366843 0.781417 -0.576374 0.239126 0.817187 -0.552828 0.163052 0.723884 -0.689751 -0.0153253 0.828941 -0.556805 0.0531464 0.896062 -0.202644 0.394979 0.664794 -0.71862 0.204043 0.764083 -0.555205 0.328519 0.489946 -0.856054 0.164695 0.520802 -0.830506 0.197549 0.150619 -0.988505 -0.0131091 0.200369 -0.979169 0.03288 0.839757 -0.542058 0.0313294 0.798356 -0.567556 0.201267 0.569583 -0.789578 -0.228343 0.574526 -0.796869 -0.186867 0.545881 -0.828802 -0.122888 0.533488 -0.842987 0.0690159 0.510401 -0.851387 0.120957 0.191401 -0.98025 0.0497579 0.196861 -0.862212 -0.46673 0.213995 -0.885292 -0.412874 0.177272 -0.926673 -0.33144 0.201305 -0.945338 -0.256539 0.169906 -0.967577 -0.186889 0.904685 -0.200397 0.376014 0.9073 -0.195031 0.372519 0.789028 -0.549195 0.275353 0.782833 -0.554463 0.282387 0.52161 -0.830908 0.193687 0.162794 -0.985896 -0.0388131 0.194291 -0.974892 -0.108794 0.525795 -0.850604 0.00353717 0.553302 -0.830965 -0.0579155 0.829859 -0.543267 0.12726 0.828058 -0.545581 0.129077 0.935399 -0.178081 0.305476 0.926247 -0.206165 0.315535 0.922356 -0.195009 0.333513 0.904017 -0.195076 0.380393 0.77489 0.555807 0.301038 0.775357 -0.555058 0.301219 0.775367 -0.555041 0.301223 0.51833 -0.831135 0.201366 0.518341 -0.831127 0.20137 0.18209 -0.980734 0.07074 0.182073 -0.980738 0.0707338 0.172659 -0.566548 0.805737 0.91984 -0.194965 0.340416 0.918167 -0.210049 0.335931 0.915818 -0.148988 0.372934 0.47098 -0.455727 0.755308 0.4492 -0.483422 0.751347 0.488796 -0.602332 0.63109 0.460806 -0.640668 0.614168 0.505523 -0.718049 0.478384 0.476095 -0.757451 0.446769 0.134371 -0.59599 0.791669 0.184241 -0.744412 0.641799 0.184458 -0.744474 0.641665 0.159128 -0.832601 0.530522 0.202264 -0.872985 0.443832 0.144588 -0.911842 0.384237 0.892595 -0.130487 0.431564 0.90373 -0.122438 0.410221 0.733147 -0.343152 0.587148 0.778825 -0.260907 0.570402 0.735955 -0.412657 0.536735 0.776322 -0.487303 0.399825 0.799819 -0.431842 0.416896 0.772093 -0.554797 0.309956 0.525219 -0.797038 0.298119 0.498027 -0.828277 0.256761 0.201604 -0.95664 0.210228 0.153344 -0.975996 0.154652 0.155347 -0.471844 0.867889 0.155236 -0.471821 0.867921 0.458403 -0.378193 0.804261 0.458019 -0.378154 0.804499 0.719456 -0.240929 0.65141 0.718882 -0.240933 0.652043 0.897518 -0.0815745 0.433367 0.89705 -0.0816523 0.43432 0.865804 -0.0287866 0.499554 0.83684 -0.109259 0.536434 0.491752 -0.182347 0.851428 0.567271 -0.145143 0.81064 0.44201 -0.299331 0.845594 0.207239 -0.0833996 0.974729 0.142067 -0.127292 0.981638 0.161865 -0.352196 0.921823 0.136097 -0.371606 0.918361 0.662509 -0.142082 0.735455 0.696985 -0.1438 0.70252 0.883333 -0.0186944 0.468374 0.207963 0 0.978137 0.207963 0 0.978137 0.500137 0 0.865946 0.500137 0 0.865946 0.669299 0 0.742993 0.669299 0 0.742993 0.866163 0 0.499761 0.866163 0 0.499761 0.895815 0.0644888 0.439723 0.894667 0.0693111 0.441323 0.716553 0.186776 0.672062 0.709067 0.200437 0.676054 0.45891 0.292831 0.83884 0.441147 0.312097 0.841418 0.162673 0.366684 0.916013 0.134536 0.387069 0.912183 0.865772 0.0300683 0.499535 0.884169 -0.0341758 0.465915 0.664398 0.120795 0.737552 0.705629 0.0681805 0.705294 0.497848 0.09557 0.861983 0.444567 0.128398 0.886495 0.207123 0.0897693 0.974188 0.141202 0.132645 0.981054 0.89937 -0.084711 0.428902 0.90712 -0.121268 0.403023 0.907233 -0.12106 0.402832 0.741097 -0.35071 0.572519 0.726008 -0.3645 0.58314 0.486015 -0.546933 0.681656 0.444192 -0.567996 0.692874 0.187358 -0.676227 0.71247 0.118423 -0.6925 0.711631 0.122012 -0.387331 0.913831 0.164034 -0.381761 0.909589 0.432784 -0.311951 0.845804 0.458134 -0.305172 0.834855 0.70665 -0.198324 0.6792 0.811685 -0.143298 0.566245 0.926658 -0.0262767 0.374987 0.137053 -0.0305062 0.990094 0.140538 -0.0306581 0.989601 0.436523 -0.0243506 0.899363 0.438638 -0.0244364 0.898332 0.802032 -0.0105939 0.597187 0.802315 -0.0106312 0.596806 0.948476 -1.5893e-05 0.316849 0.896119 0.0761092 0.437239 0.926047 0.0211115 0.376818 0.705419 0.185933 0.683968 0.809096 0.113291 0.576654 0.429971 0.267415 0.862331 0.454185 0.258843 0.852477 0.123139 0.332213 0.935132 0.159918 0.324015 0.932438 0.926511 -0.16266 0.339292 0.767575 -0.449877 0.456553 0.502943 -0.690658 0.519654 0.182993 -0.83717 0.515422 0.157757 -0.843842 0.512878 0.180793 -0.891375 0.415649 0.170341 -0.893794 0.41487 0.183839 -0.920409 0.345038 0.17485 -0.922364 0.344489 0.186142 -0.944234 0.271611 0.179317 -0.945639 0.271317 0.188092 -0.962435 0.195805 0.182463 -0.963544 0.19568 0.932981 -0.143712 0.32999 0.946714 -0.170339 0.273346 0.949535 -0.160648 0.2694 0.957691 -0.17677 0.227113 0.959895 -0.16828 0.22424 0.966915 -0.181896 0.178857 0.968475 -0.175239 0.177052 0.974057 -0.185905 0.129043 0.975225 -0.180468 0.127933 0.977591 -0.18442 0.10151 0.986552 -0.145992 0.07349 0.187791 -0.973824 0.12807 0.00390343 -0.99399 0.109401 0.186545 -0.978443 0.088607 0.188315 -0.981317 0.0394133 0.173267 -0.984117 0.0386362 0.187353 -0.982293 -0.000482843 0.187185 -0.981487 -0.0405714 0.188744 -0.981185 -0.0406519 0.185654 -0.975354 -0.119238 0.188432 -0.974795 -0.119449 0.182408 -0.963402 -0.196429 0.187709 -0.962277 -0.196949 0.979873 -0.184723 0.0756763 0.981766 -0.188369 0.0255545 0.981967 -0.187326 0.0254808 0.981945 -0.187275 -0.026703 0.981686 -0.188626 -0.0266966 0.979653 -0.184803 -0.0782794 0.97907 -0.187793 -0.0784618 0.975141 -0.180351 -0.128741 0.974048 -0.185691 -0.129418 0.968371 -0.174832 -0.17802 0.966797 -0.181988 -0.179401 0.959655 -0.168118 -0.225385 0.95754 -0.176889 -0.227657 0.949278 -0.160579 -0.270342 0.946674 -0.170302 -0.273505 0.932851 -0.143499 -0.330449 0.925598 -0.165612 -0.340354 0.769781 -0.447133 0.455533 0.789896 -0.486226 0.373696 0.792157 -0.483261 0.372755 0.803816 -0.506284 0.31234 0.805735 -0.503658 0.31164 0.815695 -0.52296 0.247294 0.81712 -0.520939 0.246855 0.825001 -0.535997 0.179111 0.826128 -0.534351 0.178833 0.831592 -0.544708 0.10839 0.832249 -0.543727 0.108272 0.835052 -0.549013 0.0356929 0.835256 -0.548703 0.0356705 0.835228 -0.548636 -0.0373147 0.83493 -0.549091 -0.0373035 0.832087 -0.54374 -0.109445 0.83152 -0.544602 -0.109465 0.826024 -0.534197 -0.179774 0.824945 -0.535823 -0.179889 0.816987 -0.520612 -0.247983 0.815529 -0.52277 -0.248242 0.805491 -0.503294 -0.312857 0.80358 -0.506051 -0.313323 0.791904 -0.483 -0.37363 0.789755 -0.486 -0.374287 0.769686 -0.44699 -0.455832 0.76432 -0.453884 -0.458044 0.492736 -0.697132 0.520786 0.516176 -0.743869 0.424525 0.512933 -0.745915 0.424866 0.526511 -0.772702 0.354567 0.523732 -0.774471 0.354823 0.53523 -0.796742 0.280591 0.533158 -0.798071 0.280759 0.542188 -0.815339 0.203113 0.540441 -0.816467 0.203238 0.546679 -0.828273 0.122906 0.545698 -0.828911 0.122967 0.548889 -0.834915 0.0404749 0.548575 -0.835121 0.0404916 0.54854 -0.835053 -0.0423107 0.548987 -0.834758 -0.0423307 0.545764 -0.828683 -0.124199 0.546623 -0.828113 -0.124229 0.540372 -0.816286 -0.204145 0.541988 -0.815204 -0.204184 0.532907 -0.797855 -0.281848 0.535082 -0.79639 -0.28187 0.523565 -0.774068 -0.355947 0.526395 -0.772153 -0.355933 0.512917 -0.745527 -0.425565 0.515978 -0.743451 -0.425496 0.492729 -0.697087 -0.520853 0.500125 -0.692205 -0.520314 0.18011 -0.947966 -0.262527 -0.00598654 -0.967533 -0.252675 0.182064 -0.936342 -0.300195 0.174867 -0.922013 -0.345419 0.183901 -0.919802 -0.34662 0.1706 -0.893498 -0.4154 0.180609 -0.890857 -0.416839 0.157857 -0.843904 -0.512744 0.181768 -0.837125 -0.515929 0.891278 0.0574331 -0.449805 0.891895 0.0570089 -0.448636 0.709044 0.166908 -0.685127 0.701165 0.169886 -0.692464 0.451539 0.26082 -0.853279 0.429507 0.265637 -0.863111 0.159007 0.325872 -0.931947 0.122625 0.32976 -0.936067 0.887931 -0.00544753 -0.459945 0.887903 -0.00545297 -0.459999 0.698466 -0.0161099 -0.715462 0.699182 -0.0160193 -0.714764 0.433918 -0.02528 -0.900598 0.436081 -0.0250744 -0.899558 0.136098 -0.0316263 -0.99019 0.139681 -0.0313547 -0.9897 0.893382 -0.0671683 -0.444248 0.892709 -0.0679172 -0.445487 0.703295 -0.201333 -0.681793 0.712348 -0.195621 -0.674013 0.43053 -0.314991 -0.845828 0.455634 -0.304938 -0.836308 0.121535 -0.39056 -0.91252 0.163051 -0.380303 -0.910376 0.906068 -0.123474 -0.404715 0.906067 -0.123477 -0.404717 0.723009 -0.368918 -0.584086 0.737699 -0.352958 -0.575518 0.442463 -0.571649 -0.690974 0.483114 -0.546221 -0.684283 0.118675 -0.695934 -0.708231 0.18567 -0.673592 -0.715402 0.891946 0.0223072 -0.451591 0.866041 -0.0167994 -0.499691 0.709046 0.0955858 -0.698654 0.667444 0.074398 -0.740934 0.440897 0.101769 -0.89177 0.495481 0.136451 -0.857834 0.134942 0.078067 -0.987773 0.206193 0.130176 -0.969814 0.89399 0.0662284 -0.443165 0.896128 0.0681039 -0.438538 0.706935 0.19187 -0.680756 0.717007 0.19691 -0.668676 0.437993 0.299102 -0.847762 0.459545 0.307566 -0.8332 0.131264 0.371221 -0.91922 0.163934 0.384031 -0.908651 0.866163 0 -0.499761 0.866163 0 -0.499761 0.669299 0 -0.742993 0.669299 0 -0.742993 0.500159 0 -0.865933 0.500159 0 -0.865933 0.207963 0 -0.978137 0.207963 0 -0.978137 0.4957 -0.133243 -0.858212 0.893889 -0.0633434 -0.443791 0.206361 -0.123871 -0.970603 0.136029 -0.0695295 -0.988262 0.16296 -0.367945 -0.915457 0.865805 -0.0287747 -0.499554 0.863607 -0.0357128 -0.5029 0.660414 -0.162405 -0.733129 0.693994 -0.13302 -0.707586 0.548748 -0.170343 -0.818449 0.441904 -0.298932 -0.84579 0.132908 -0.355305 -0.925253 0.155246 -0.471874 -0.86789 0.155356 -0.471795 -0.867914 0.45804 -0.378341 -0.804399 0.458356 -0.378017 -0.804371 0.718946 -0.241275 -0.651845 0.7194 -0.240576 -0.651604 0.897126 -0.0820571 -0.434086 0.897438 -0.0811706 -0.433609 0.129736 -0.97086 -0.201495 0.377959 -0.894536 -0.238648 0.910389 -0.143341 -0.38813 0.888567 -0.133355 -0.438937 0.514246 -0.733979 -0.443651 0.462524 -0.745289 -0.480224 0.522877 -0.795547 -0.306113 0.165436 -0.86827 -0.467694 0.197514 -0.874325 -0.443333 0.162475 -0.92902 -0.332451 0.215327 -0.962805 -0.163219 0.187625 -0.754245 -0.629215 0.921861 -0.17286 -0.34683 0.911131 -0.25877 -0.320746 0.671791 -0.593136 -0.44372 0.165022 -0.7494 -0.641224 0.494552 -0.622805 -0.606244 0.450577 -0.623753 -0.63868 0.735864 -0.412902 -0.536671 0.769551 -0.473146 -0.428864 0.855465 -0.417299 -0.306663 0.540537 -0.786658 -0.298311 0.903738 -0.122494 -0.410187 0.767768 -0.308444 -0.561601 0.728742 -0.302803 -0.614204 0.443372 -0.468027 -0.764442 0.473447 -0.47355 -0.742697 0.127597 -0.575407 -0.807852 0.176602 -0.58873 -0.788802 0.826714 -0.435133 -0.356657 0.905403 -0.187358 -0.380976 0.908391 -0.258722 -0.328464 0.8666 0.36832 -0.336666 0.74132 -0.606221 -0.287996 0.739874 -0.608263 -0.287407 0.569809 -0.791393 -0.221393 0.567922 -0.79296 -0.220632 0.40713 -0.899571 -0.158166 0.406122 -0.900097 -0.157767 0.175985 -0.982015 -0.0683873 0.174879 -0.982243 -0.0679391 0.571869 -0.792668 -0.211291 0.900442 -0.187397 -0.392539 0.90948 -0.197117 -0.366048 0.843191 -0.434477 -0.316637 0.427814 -0.897574 -0.106467 0.526531 -0.845831 -0.0856455 0.555403 -0.831431 -0.015843 0.500815 -0.863768 -0.0555778 0.574161 -0.811537 0.108379 0.215639 -0.976134 0.0257196 0.134167 -0.990667 -0.0240634 0.222406 -0.959642 0.172112 0.141366 -0.982224 0.123493 0.228313 -0.920741 0.316402 0.150312 -0.950703 0.271237 0.233641 -0.858801 0.455931 0.921239 -0.177627 -0.346073 0.934152 -0.194624 -0.299136 0.828085 -0.545449 -0.129461 0.839662 -0.542194 -0.0315261 0.554917 -0.807827 0.198703 0.746649 -0.607712 -0.270558 0.795134 -0.56085 -0.230673 0.798193 -0.56756 -0.201898 0.82973 -0.543336 -0.127802 0.522126 -0.849687 0.0736048 0.586933 -0.780178 0.216409 0.17859 -0.886832 0.426187 0.829042 -0.556674 -0.0529468 0.781393 -0.576671 -0.238487 0.562252 -0.798967 0.213367 0.58335 -0.785966 0.204841 0.528641 -0.844536 0.085421 0.541234 -0.839037 -0.0555137 0.484531 -0.857081 -0.175049 0.20768 -0.978046 -0.0172021 0.181093 -0.88363 0.431744 0.21969 -0.878763 0.423688 0.160607 -0.942198 0.294056 0.214185 -0.935418 0.281279 0.152227 -0.977351 0.147011 0.896552 -0.202821 -0.393774 0.897144 -0.194992 -0.396373 0.664232 -0.719456 -0.202925 0.764292 -0.555194 -0.328051 0.526581 -0.829851 -0.184554 0.923785 -0.209608 -0.320445 0.923084 -0.18486 -0.337257 0.7248 -0.688799 0.0148997 0.817183 -0.552966 -0.162608 0.562133 -0.823731 0.0739828 0.506437 -0.861062 -0.04577 0.207431 -0.96914 0.133195 0.144026 -0.989573 -0.00114213 0.871382 -0.195024 -0.450178 0.871384 -0.19501 -0.450179 0.738802 -0.555418 -0.381684 0.738805 -0.555412 -0.381686 0.493715 -0.831376 -0.255066 0.493717 -0.831375 -0.255067 0.173388 -0.980772 -0.0895765 0.173385 -0.980772 -0.0895749 0.794803 -0.188915 -0.576714 0.455847 -0.829911 -0.321638 0.370583 -0.727723 -0.577137 0.38386 -0.717492 -0.581255 0.498722 -0.629162 -0.596181 0.838414 -0.121996 -0.531206 0.135244 -0.978198 -0.157601 0.190038 -0.966204 -0.17417 0.121687 -0.947427 -0.29593 0.641154 -0.470746 -0.606069 0.645841 -0.463979 -0.606311 0.822155 -0.158894 -0.546638 0.842401 -0.194979 -0.502339 0.846317 -0.172155 -0.504094 0.688984 -0.553945 -0.467382 0.716296 -0.502668 -0.48399 0.249824 -0.929729 -0.27054 0.463918 -0.764279 -0.447949 0.182793 -0.931897 -0.313296 0.089445 -0.876161 -0.473646 0.190529 -0.826659 -0.529466 0.0946762 -0.881482 -0.462629 0.4819 -0.772736 -0.4131 0.203739 -0.939018 -0.277012 0.100917 -0.939941 -0.326079 0.21258 -0.967653 -0.135859 0.837376 -0.170672 -0.5193 0.841949 -0.195097 -0.503051 0.702043 -0.497114 -0.509915 0.690188 -0.554879 -0.464488 0.470302 -0.775554 -0.421107 0.464143 -0.831154 -0.306192 0.118503 -0.976262 -0.181302 0.185695 -0.821673 -0.538861 0.378568 -0.736579 -0.56048 0.397456 -0.728413 -0.558071 0.492596 -0.62187 -0.608791 0.654087 -0.471568 -0.591433 0.650483 -0.482561 -0.586521 0.795484 -0.14863 -0.587464 0.800203 -0.195613 -0.566931 0.831724 -0.195038 -0.519803 0.831723 -0.195044 -0.519802 0.705174 -0.555429 -0.440713 0.705159 -0.555457 -0.440702 0.471226 -0.831393 -0.294502 0.471245 -0.831378 -0.294514 0.165491 -0.980773 -0.103427 0.165492 -0.980773 -0.103428 0.523193 -0.826065 -0.209491 0.428258 -0.864729 -0.26237 0.53502 -0.838911 -0.099904 0.136434 -0.912184 0.386403 0.2493 -0.867219 0.431024 0.122106 -0.963187 0.239501 0.240889 -0.926562 0.288886 0.109991 -0.989705 0.0915771 0.231485 -0.962229 0.143286 0.0935332 -0.993518 -0.0646036 0.229602 -0.973277 -0.00374113 0.58387 -0.787483 0.1974 0.632267 -0.774441 0.0219292 0.805445 -0.571366 -0.15748 0.85877 -0.191231 -0.475336 0.87243 -0.20529 -0.443533 0.820469 -0.469568 -0.326092 0.797325 -0.572017 -0.192537 0.736119 -0.644018 -0.208253 0.566805 -0.820431 -0.0749957 0.831148 -0.19505 -0.520719 0.834785 -0.202455 -0.512003 0.726014 -0.554544 -0.406676 0.723958 -0.510531 -0.463943 0.692532 -0.609597 -0.385734 0.686486 -0.668863 -0.285234 0.451661 -0.880597 -0.143358 0.493216 -0.865817 -0.0842562 0.422969 -0.90059 0.100178 0.487888 -0.84986 0.199259 0.354017 -0.889608 0.288565 0.786208 -0.589761 -0.184548 0.855678 -0.222146 -0.467405 0.131547 -0.983366 0.125245 0.155006 -0.896514 0.415013 0.542051 -0.829325 0.13565 0.617439 -0.786612 -0.00328062 0.366148 -0.878651 0.306443 0.477676 -0.859682 0.181033 0.222295 -0.894003 0.389028 0.436466 -0.864199 -0.250313 0.198728 -0.978459 -0.0559001 0.122128 -0.992316 -0.0198541 0.818075 -0.206859 -0.536621 0.818475 -0.195016 -0.540432 0.613994 -0.724515 -0.313193 0.697632 -0.555291 -0.452727 0.486598 -0.830073 -0.272398 0.200796 -0.975155 0.0935629 0.463431 -0.876937 -0.127335 0.507173 -0.848936 -0.148605 0.670105 -0.674514 -0.309822 0.777167 -0.489411 -0.395586 0.852406 -0.191294 -0.486631 0.823244 -0.466123 -0.324036 0.594636 -0.803311 -0.0331411 0.721175 -0.651502 -0.235484 0.576082 -0.814931 -0.0633769 0.540234 -0.841388 -0.01463 0.408759 -0.909216 0.0790116 0.210889 -0.947277 0.241229 0.142349 -0.952152 0.27045 0.785028 -0.195027 -0.587959 0.785032 -0.194996 -0.587963 0.665587 -0.555418 -0.498503 0.665588 -0.555417 -0.498503 0.44481 -0.831358 -0.333148 0.444801 -0.831366 -0.333141 0.156209 -0.980771 -0.116995 0.156212 -0.98077 -0.116998 0.399368 -0.830163 -0.389018 0.332066 -0.703407 -0.628451 0.320409 -0.714085 -0.622431 0.11142 -0.978655 -0.172687 0.177139 -0.961919 -0.208169 0.0976591 -0.946823 -0.306575 0.720551 -0.155393 -0.675766 0.708994 -0.190451 -0.679011 0.556614 -0.459394 -0.692198 0.56284 -0.449398 -0.693724 0.441845 -0.604617 -0.662731 0.748525 -0.194981 -0.633793 0.752709 -0.167587 -0.636666 0.606872 -0.554274 -0.569638 0.636662 -0.489953 -0.595489 0.216894 -0.928464 -0.301516 0.410098 -0.750875 -0.517693 0.169039 -0.923775 -0.343608 0.0623027 -0.879637 -0.471547 0.17836 -0.807703 -0.561963 0.0667348 -0.883543 -0.463571 0.20452 -0.931944 -0.299419 0.0651066 -0.938145 -0.340065 0.214904 -0.963031 -0.162443 0.739944 -0.166168 -0.651822 0.76116 -0.258605 -0.594776 0.609289 -0.482076 -0.629579 0.568806 -0.607892 -0.554009 0.422323 -0.755295 -0.501172 0.404264 -0.790134 -0.460715 0.41887 -0.776429 -0.470857 0.304729 -0.899562 -0.312935 0.0701095 -0.976208 -0.205187 0.173356 -0.804138 -0.568604 0.347573 -0.714921 -0.606696 0.33268 -0.722064 -0.606587 0.433402 -0.597895 -0.674303 0.567629 -0.466663 -0.67825 0.570532 -0.455829 -0.683164 0.698335 -0.150819 -0.699702 0.703398 -0.185664 -0.686119 0.706037 -0.258528 -0.659299 0.716893 -0.187185 -0.671584 0.658179 -0.434807 -0.614609 0.580074 -0.608361 -0.541674 0.580096 -0.608322 -0.541695 0.445267 -0.793003 -0.415792 0.445264 -0.793007 -0.415789 0.31837 -0.900143 -0.297295 0.31835 -0.900156 -0.297276 0.137097 -0.98225 -0.128022 0.137101 -0.982249 -0.128025 0.647443 -0.667751 -0.367324 0.22288 -0.973928 -0.0422895 0.729679 -0.200275 -0.653803 0.390384 -0.868814 -0.30457 0.34349 -0.932426 -0.112235 0.390144 -0.918321 -0.0668822 0.369639 -0.929039 0.0159381 0.423227 -0.903471 0.0679698 0.406481 -0.903706 0.134496 0.00850984 -0.899741 0.436342 -0.0156799 -0.889381 0.456897 0.210648 -0.932199 0.294334 0.309994 -0.90632 0.287208 0.168178 -0.97431 0.149788 0.153186 -0.976671 0.150495 0.0647609 -0.995803 0.0646697 0.234898 -0.966919 0.0994482 0.671561 -0.69583 -0.254611 0.656309 -0.659234 -0.366973 0.671535 -0.630406 -0.389396 0.726868 -0.483667 -0.487575 0.687769 -0.552568 -0.47079 0.75191 -0.221781 -0.620842 0.0554762 -0.995617 -0.0752981 0.357668 -0.897694 -0.257329 0.430511 -0.862694 -0.265365 0.440056 -0.793155 -0.421018 0.595347 -0.607664 -0.525649 0.698475 -0.187343 -0.690677 0.709261 -0.206388 -0.674057 0.656499 -0.434851 -0.616371 0.645349 -0.509465 -0.569184 0.579585 -0.619011 -0.530006 0.589322 -0.686711 -0.425591 0.44613 -0.841201 -0.305531 0.51931 -0.821346 -0.236024 0.513518 -0.841443 -0.168144 0.561105 -0.818729 -0.12184 0.555444 -0.829989 -0.0509915 0.706113 -0.610257 -0.359152 0.656108 -0.498349 -0.566719 0.103258 -0.989629 0.0998654 0.678062 -0.207631 -0.705068 0.355333 -0.869807 -0.342308 0.323625 -0.898989 -0.295105 0.167484 -0.980551 -0.102319 0.0934132 -0.994805 -0.0404509 0.677817 -0.183693 -0.711914 0.643004 -0.431383 -0.632814 0.470671 -0.781367 -0.409799 0.555186 -0.606468 -0.56918 0.442621 -0.79102 -0.422344 0.179166 -0.983061 0.0386053 0.321154 -0.936776 -0.138961 0.439822 -0.858268 -0.264448 0.45976 -0.835534 -0.300838 0.564658 -0.687648 -0.456401 0.72578 -0.23898 -0.645083 0.718591 -0.195937 -0.66726 0.698635 -0.546517 -0.461766 0.709534 -0.481676 -0.514345 0.395259 -0.917212 0.0499227 0.622739 -0.671157 -0.402175 0.498467 -0.845805 -0.190115 0.523031 -0.81737 -0.241548 0.356271 -0.934379 -0.0027497 0.395276 -0.915915 -0.0696934 0.199419 -0.963864 0.176633 0.193816 -0.963495 0.184694 0.439924 -0.894818 -0.0759461 0.0489871 -0.877099 0.477806 0.274645 -0.928939 0.248279 0.228677 -0.922164 0.311962 0.433456 -0.898383 0.0708753 0.399184 -0.907949 0.127593 0.568643 -0.813305 -0.12321 0.541966 -0.838001 -0.0634694 0.654134 -0.706376 -0.270448 0.654075 -0.183744 -0.733774 0.648081 -0.258799 -0.716251 0.124675 -0.98229 -0.139867 0.125381 -0.982062 -0.140832 0.289635 -0.900321 -0.324859 0.290355 -0.899772 -0.325735 0.405082 -0.793342 -0.454442 0.406291 -0.791799 -0.456051 0.528036 -0.608738 -0.592128 0.52894 -0.606722 -0.59339 0.600125 -0.431956 -0.673249 0.373058 -0.792792 -0.481983 0.251116 -0.899314 -0.358017 0.0813691 -0.980755 -0.17748 0.155393 -0.957631 -0.242477 0.0734166 -0.946882 -0.313088 0.334629 -0.611265 -0.717202 0.256882 -0.715069 -0.650145 0.488959 -0.382552 -0.783947 0.453075 -0.457315 -0.765236 0.600513 -0.130286 -0.78893 0.593822 -0.154035 -0.789715 0.611004 -0.258676 -0.748172 0.623284 -0.16176 -0.765083 0.479487 -0.607756 -0.633029 0.532185 -0.478173 -0.698663 0.177025 -0.927864 -0.328223 0.340518 -0.738729 -0.581658 0.146485 -0.915612 -0.374428 0.0385271 -0.884792 -0.464391 0.156985 -0.78729 -0.596263 0.135044 -0.776234 -0.615812 0.586167 -0.126063 -0.800323 0.58449 -0.12546 -0.801642 0.124344 -0.793206 -0.596123 0.0712815 -0.751786 -0.655544 0.306879 -0.615544 -0.7259 0.274723 -0.577841 -0.768523 0.473392 -0.385514 -0.79201 0.450303 -0.360457 -0.816883 0.596705 -0.128076 -0.792174 0.210996 -0.829688 -0.516816 0.197914 -0.928829 -0.313218 0.0383063 -0.941226 -0.335599 0.209619 -0.960104 -0.185094 0.637507 -0.166167 -0.752312 0.663938 -0.258722 -0.701605 0.520857 -0.479186 -0.706462 0.490371 -0.608001 -0.624397 0.362484 -0.749473 -0.553981 0.347634 -0.791056 -0.50337 0.353071 -0.78541 -0.508402 0.264049 -0.899814 -0.347293 0.0443191 -0.976657 -0.210183 0.1429 -0.92069 -0.363193 0.0150722 -0.862004 -0.506677 0.278776 -0.728749 -0.625467 0.32795 -0.62602 -0.707494 0.475451 -0.46787 -0.745013 0.486412 -0.392254 -0.78073 0.608044 -0.158606 -0.777899 0.605639 -0.136315 -0.783977 0.189887 -0.981799 0.00367694 0.614008 -0.78921 0.0118897 0.44005 -0.897933 0.00852115 0.966642 -0.255448 0.018717 0.797281 -0.603411 0.0154377 0.261577 -0.965182 0.000801284 0.252049 -0.96559 -0.0640865 0.252044 -0.965592 -0.0640844 0.233949 -0.965591 -0.113583 0.23395 -0.965591 -0.113585 0.145041 -0.981925 -0.121603 0.202926 -0.965413 -0.163705 0.336306 -0.898552 -0.28196 0.469567 -0.790264 -0.393687 0.711567 -0.702565 0.00860562 0.687072 -0.705276 -0.174694 0.687073 -0.705274 -0.174695 0.637744 -0.705275 -0.309629 0.637743 -0.705276 -0.309628 0.548189 -0.703827 -0.451792 0.610293 -0.604759 -0.511673 0.966638 -0.255461 0.0187181 0.936461 -0.257579 -0.238104 0.936464 -0.257569 -0.238106 0.86923 -0.257567 -0.422017 0.869227 -0.257587 -0.422012 0.740707 -0.256316 -0.621012 0.740707 -0.256314 -0.621012 0.94648 -0.163845 0.278082 0.946353 -0.163986 0.278434 0.778507 -0.478753 0.405859 0.790282 -0.472315 0.39035 0.489821 -0.730353 0.476087 0.522669 -0.723286 0.451303 0.206925 -0.963594 0.169316 0.14411 -0.867684 0.475769 0.197983 -0.870386 0.450812 0.939887 -0.258544 0.223087 0.968897 -0.20728 0.135178 0.735848 -0.599603 0.314648 0.813604 -0.533351 0.231482 0.568603 -0.78642 0.241318 0.537453 -0.803457 0.256129 0.398777 -0.892101 0.212444 0.151214 -0.968936 0.195698 0.0972638 -0.975266 0.198485 0.204932 -0.949569 0.237323 0.327876 -0.897188 0.295888 0.50551 -0.78253 0.363466 0.877191 -0.15302 0.455105 0.845549 -0.258626 0.467075 0.748094 -0.498727 0.437751 0.670448 -0.608698 0.424248 0.494312 -0.792367 0.357507 0.932726 -0.120879 0.339721 0.912067 -0.179611 0.36861 0.781428 -0.435827 0.446571 0.736393 -0.489668 0.466851 0.516797 -0.69922 0.493976 0.450184 -0.73882 0.501477 0.19412 -0.859031 0.473691 0.114309 -0.877061 0.46658 0.158017 -0.982283 0.100753 0.201126 -0.965632 0.164628 0.367069 -0.900269 0.234042 0.513393 -0.79327 0.327338 0.575408 -0.706937 0.411273 0.669001 -0.608669 0.426567 0.814462 -0.258773 0.519315 0.814473 -0.258752 0.519308 0.156611 -0.982061 0.105019 0.215937 -0.965926 0.142681 0.362393 -0.899787 0.243011 0.507278 -0.791805 0.340167 0.588526 -0.707093 0.391991 0.660186 -0.606771 0.442701 0.802247 -0.258837 0.537963 0.802252 -0.258812 0.537967 0.88204 -0.141808 0.449329 0.8522 -0.0840525 0.516421 0.752967 -0.540659 0.375137 0.718304 -0.602966 0.34709 0.842385 -0.176098 0.50929 0.811214 -0.258778 0.524372 0.26071 -0.963761 -0.0565184 0.260702 -0.963763 -0.0565231 0.54369 -0.822472 0.167158 0.44782 -0.887906 0.105259 0.587919 -0.782119 0.2065 0.458044 -0.816781 -0.350806 0.458062 -0.816776 -0.350793 0.712129 -0.697012 -0.0839448 0.712136 -0.697006 -0.0839373 0.863684 -0.458164 0.210087 0.863685 -0.458161 0.210089 0.873846 -0.155599 0.460632 0.842595 -0.179186 0.507864 0.608817 -0.545852 -0.575662 0.608811 -0.545854 -0.575667 0.840797 -0.465812 -0.275827 0.840794 -0.465815 -0.275831 0.948262 -0.306184 0.083973 0.94826 -0.306193 0.0839589 0.885632 -0.0752466 0.458251 0.899332 -0.110326 0.423119 0.690502 -0.191759 -0.69745 0.690484 -0.191762 -0.697466 0.910493 -0.163642 -0.379767 0.910488 -0.163645 -0.37978 0.994075 -0.107568 0.0156272 0.994075 -0.107564 0.015641 0.918144 -0.0365389 0.394558 0.969768 -0.0870705 0.227969 0.69175 -0.00126811 -0.722136 0.703558 -0.000871714 -0.710637 0.917164 -0.00111475 -0.398508 0.922933 -0.000722542 -0.384961 0.999994 -0.000777361 0.00335975 0.999876 -0.000442683 0.0157135 0.920923 -0.000338249 0.389745 0.918758 -0.000198608 0.39482 0.918975 0.188655 0.346257 0.920011 0.0448612 0.389315 0.773484 0.610528 -0.170228 0.7704 0.613395 -0.173869 0.841141 0.463179 -0.27919 0.840408 0.463845 -0.280288 0.528757 0.715771 -0.456166 0.521282 0.718084 -0.461108 0.603574 0.542986 -0.583836 0.602041 0.543464 -0.584973 0.659015 0.337641 -0.672084 0.659949 0.337361 -0.671308 0.889441 0.288267 -0.354679 0.889833 0.287949 -0.353953 0.981403 0.188562 0.0359393 0.949083 0.303595 0.0840986 0.660953 0.616209 -0.428284 0.901395 0.409192 0.141591 0.86703 0.0609284 0.494516 0.895065 0.125808 0.427821 0.918175 0.0441522 0.393707 0.787091 0.21634 -0.577655 0.997883 0.0649525 0.00330094 0.914711 0.0966191 -0.392388 0.912747 0.097812 -0.396643 0.688601 0.113561 -0.716194 0.687232 0.11393 -0.717448 0.407399 0.824625 -0.392454 0.451189 0.836688 -0.310453 0.438616 0.839494 -0.320727 0.673566 0.722001 -0.15819 0.726185 0.680899 -0.0950402 0.905381 0.402721 0.13454 0.178914 0.971298 -0.156749 0.254103 0.951531 -0.173266 0.581865 0.758872 -0.292483 0.908672 0.219084 -0.355412 0.880632 0.325042 -0.344725 0.847998 0.18092 -0.498164 0.716833 0.170656 -0.676038 0.714213 0.181981 -0.675857 0.954111 0.130792 0.26938 0.825858 0.560274 -0.0636554 0.990209 0.0922899 -0.104737 0.944826 0.0555418 -0.322829 0.523598 0.811574 -0.259216 0.424725 0.803638 -0.416863 0.204352 0.957463 -0.203729 0.132747 0.978941 -0.155087 0.973885 0.0813382 0.211971 0.999309 0.00743281 0.0364257 0.984351 0.176176 -0.00385958 0.961555 0.272424 -0.0345987 0.851984 0.514816 -0.0953284 0.813066 0.473997 -0.338009 0.778654 0.528172 -0.338722 0.620386 0.516938 -0.589827 0.609171 0.536448 -0.584068 0.885238 0.0344499 0.463861 0.908235 0.373817 0.18807 0.935944 0.160174 0.313614 0.931438 0.277888 0.23495 0.862715 0.498469 0.0851533 0.901508 0.423788 -0.0876727 0.674755 0.719738 -0.16335 0.598492 0.777192 -0.194372 0.292577 0.927155 -0.234056 0.31196 0.921959 -0.229506 0.116644 0.979121 -0.16648 0.113322 0.980784 -0.158811 0.112769 0.980934 -0.158275 0.323215 0.831462 -0.451889 0.325313 0.829363 -0.454234 0.483518 0.555565 -0.67643 0.489171 0.543508 -0.682137 0.570186 0.195101 -0.798012 0.571973 0.185396 -0.799047 0.755678 0.195036 -0.62523 0.817612 0.195078 -0.541715 0.847917 0.194894 -0.493004 0.168826 0.980746 -0.0981604 0.168821 0.980747 -0.0981574 0.480624 0.831209 -0.279449 0.48064 0.831197 -0.279458 0.719038 0.55516 -0.41807 0.719039 0.555159 -0.41807 0.828997 0.283613 -0.482003 0.861669 0.0912825 -0.499194 0.15906 0.980747 -0.113293 0.159056 0.980748 -0.11329 0.45285 0.831196 -0.322551 0.452848 0.831198 -0.322549 0.677463 0.555161 -0.482535 0.677472 0.555145 -0.482541 0.751077 -0.386903 -0.534967 0.791775 0.194995 -0.578852 0.726039 0.195057 -0.659409 0.656875 -0.498223 -0.565941 0.630126 0.555163 -0.542895 0.630136 0.555143 -0.542904 0.421205 0.8312 -0.362896 0.421207 0.831198 -0.362897 0.14795 0.980746 -0.127469 0.147943 0.980748 -0.127463 0.135577 0.980746 -0.140557 0.135579 0.980746 -0.140558 0.38598 0.8312 -0.400157 0.385977 0.831203 -0.400153 0.577431 0.555162 -0.598639 0.57743 0.555164 -0.598638 0.68093 0.194894 -0.70594 0.680931 0.194883 -0.705941 0.122053 0.980746 -0.152451 0.122052 0.980746 -0.15245 0.347471 0.831202 -0.434012 0.347477 0.831196 -0.434019 0.519823 0.555163 -0.64929 0.51982 0.555171 -0.649286 0.612998 0.194885 -0.765672 0.612995 0.194907 -0.765668 0.0907077 0.814898 -0.572462 0.0353969 0.968505 -0.246466 0.0724897 -0.172269 -0.982379 0.226063 0.198575 -0.953658 0.200107 0.466678 -0.861492 0.325462 0.466721 -0.822342 0.230596 -0.115043 -0.966225 0.219923 0.230717 -0.947842 0.354272 0.23082 -0.906208 0.35144 0.38455 -0.853587 0.420542 0.519953 -0.743501 0.13045 0.979458 -0.153771 0.22267 0.853311 -0.471464 0.340342 0.853532 -0.394526 0.386954 0.809936 -0.440761 0.0761808 0.318188 -0.944962 0.0579666 0.650159 -0.757584 0.0784216 0.854782 -0.513028 0.0829315 0.837215 -0.540549 0.235207 0.83757 -0.493107 0.0345377 0.974382 -0.222234 0.0889364 0.974657 -0.205268 0.118813 0.960393 -0.25205 0.109406 0.978387 -0.17547 0.156259 0.9716 -0.1777 0.829347 0.0908648 -0.551296 0.756715 0.378362 -0.533127 0.786062 0.281678 -0.550241 0.440126 0.384598 -0.811402 0.464898 0.304516 -0.831348 0.490849 0.0817835 -0.867398 0.359015 -0.115068 -0.926211 0.368903 -0.0694334 -0.926871 0.437167 -0.0695803 -0.896685 0.484647 -0.018361 -0.874517 0.410322 -0.761639 -0.501539 0.810981 0.178046 -0.557323 0.758869 0.381045 -0.528132 0.686972 0.55274 -0.47175 0.674386 0.573421 -0.46518 0.45734 0.829235 -0.321262 0.482635 0.809616 -0.334044 0.161297 0.980474 -0.112488 0.165516 0.979503 -0.114796 0.757559 -0.0206874 -0.652439 0.652714 -0.0205336 -0.757326 0.638468 0.178009 -0.74878 0.652504 0.0812232 -0.753419 0.600207 0.380725 -0.70342 0.623578 0.302756 -0.720756 0.532068 0.573276 -0.623103 0.55958 0.517412 -0.647422 0.460282 0.70668 -0.537349 0.344653 0.70873 -0.615561 0.214644 0.864219 -0.455032 0.268261 0.676434 -0.685911 0.166851 0.676285 -0.717495 0.206467 0.443393 -0.872223 0.0382947 0.442178 -0.89611 0.0764722 0.19858 -0.977097 0.0765941 -0.155224 -0.984905 0.221277 -0.155342 -0.962759 0 0.993861 -0.110632 0.00749359 0.969085 -0.246614 0.00111552 0.94155 -0.33687 0 0.886141 -0.463416 0 0.818272 -0.574832 0 0.818272 -0.574832 0 0.651254 -0.75886 0 0.651254 -0.75886 0 0.319115 -0.947716 0 0.319115 -0.947716 0 0.0591527 -0.998249 0.00186719 -0.172723 -0.984969 0 -0.188935 -0.98199 0.0282912 0.993464 -0.110587 0.0153791 -0.192738 -0.98113 0.0104831 -0.206696 -0.978349 0.00598265 -0.188932 -0.981972 0.0733178 0.964893 -0.252201 0.0335043 0.998437 -0.044737 0.0492202 0.94041 -0.336462 0.0447575 0.883034 -0.467169 0.0445596 0.885261 -0.462955 0.050783 0.749909 -0.65959 0.0411213 0.817579 -0.574346 0.0453257 0.650585 -0.75808 0.0388147 0.579865 -0.813787 0.0361499 0.263465 -0.963991 0.0289828 0.318981 -0.947318 0.021838 0.0591386 -0.998011 0.00747494 0.816267 -0.577626 0.0562628 0.749599 -0.659497 0.0520835 0.882703 -0.467037 0.0631057 0.816876 -0.573351 0.00961964 -0.19229 -0.981291 0.0105745 -0.236164 -0.971656 0.0237495 0.264336 -0.964138 0.02806 0.157927 -0.987052 0.0332735 0.580172 -0.813814 0.0371056 0.456013 -0.889199 0.0372593 0.487849 -0.872133 0.0269084 0.631396 -0.774993 0.0242601 0.818427 -0.574099 0.00119504 -0.236017 -0.971748 0.00178565 -0.248802 -0.968553 0.00277471 0.158361 -0.987377 0.00394474 0.137263 -0.990527 0.00479218 0.45664 -0.889639 0.00229175 0.53608 -0.844164 0.00587664 0.631744 -0.775155 0.00615602 0.830606 -0.556826 0.0227825 0.830379 -0.556733 0.0292158 0.926152 -0.376017 0.0571744 0.905441 -0.420604 0.0595951 0.965729 -0.252618 0 -0.248802 -0.968554 0 0.81629 -0.577643 0 -0.248802 -0.968554 0 0.137264 -0.990534 0 0.137264 -0.990534 0 0.536081 -0.844167 0 0.536081 -0.844167 0 0.81629 -0.577643 0 -0.969337 0.245734 0 -0.969337 0.245734 0 -0.813491 0.581577 -0.000469774 -0.735216 0.677832 0 -0.645623 0.763656 0 -0.323519 0.946222 -0.00134463 -0.487302 0.873232 0 -0.257735 0.966216 0.781931 -0.185876 0.595007 0.777582 -0.205559 0.594232 0.717201 -0.432207 0.546644 0.656659 -0.558167 0.507197 0.0680815 -0.995556 0.0650575 0.211707 -0.965608 0.150934 0.429859 -0.838482 0.334917 0.486861 -0.79085 0.370841 0.632546 -0.60543 0.483053 0.598683 -0.205566 0.774159 0.594525 -0.224886 0.771989 0.5077 -0.557911 0.656488 0.501561 -0.569656 0.651098 0.333645 -0.838192 0.431411 0.328791 -0.84255 0.426621 0.132468 -0.976268 0.171326 0.078908 -0.985627 0.149376 0.128127 -0.242062 0.961764 0.0843997 -0.810589 0.579502 0.0703333 -0.846434 0.527828 0.100322 -0.642366 0.759804 0.112005 -0.580392 0.806598 0.115118 -0.484063 0.867428 0.126291 -0.255672 0.958479 0.375505 -0.224876 0.899126 0.372307 -0.242069 0.895986 0.316748 -0.569664 0.758389 0.312641 -0.58011 0.752149 0.207583 -0.84256 0.496992 0.204493 -0.846421 0.491685 0.0988765 -0.966453 0.237049 -0.00692642 -0.998255 0.0586419 0.0505218 -0.968099 0.245421 0.7689 -0.435088 0.468498 0.519971 -0.793255 0.316823 0.221098 -0.965902 0.134717 0.679879 -0.608673 0.409002 0.840154 -0.187347 0.508962 0.221092 -0.965904 0.134713 0.213638 -0.965904 0.146248 0.213637 -0.965904 0.146247 0.20543 -0.965902 0.157579 0.205436 -0.965901 0.157583 0.196454 -0.9659 0.168648 0.196444 -0.965904 0.16864 0.186868 -0.965904 0.179193 0.186877 -0.965901 0.179201 0.176734 -0.965901 0.189212 0.176728 -0.965903 0.189206 0.162276 -0.965856 0.201962 0.16228 -0.965854 0.201967 0.38158 -0.793012 0.474899 0.603949 -0.706985 0.367992 0.583587 -0.706985 0.399499 0.583594 -0.706976 0.399503 0.561167 -0.706966 0.430453 0.561158 -0.706978 0.430447 0.536624 -0.706978 0.460671 0.536633 -0.706966 0.460678 0.510473 -0.706967 0.489505 0.510461 -0.706982 0.489495 0.482755 -0.706983 0.516839 0.482766 -0.706967 0.51685 0.442169 -0.706681 0.552348 0.497121 -0.608348 0.618695 0.824885 -0.258744 0.50261 0.797074 -0.258743 0.545642 0.797078 -0.258727 0.545644 0.766437 -0.25872 0.58791 0.766437 -0.258721 0.58791 0.732928 -0.258721 0.62919 0.732927 -0.258727 0.629189 0.697199 -0.258726 0.668562 0.697201 -0.258716 0.668563 0.65936 -0.258716 0.705911 0.659358 -0.258727 0.705909 0.605059 -0.258551 0.75303 0.605059 -0.258552 0.75303 0.117082 -0.978982 0.166989 0.150555 -0.965923 0.210539 0.128978 -0.972973 0.191543 0.3589 -0.793334 0.491744 0.32577 -0.829075 0.454433 0.461737 -0.608758 0.645145 0.492228 -0.54325 0.68014 0.557653 -0.258792 0.788701 0.572368 -0.18531 0.798783 0.407648 -0.82434 0.392793 0.451474 -0.836577 0.310337 0.43903 -0.839361 0.320508 0.673771 -0.72184 0.158051 0.726433 -0.680664 0.0948276 0.905443 -0.402548 -0.134645 0.179126 -0.971228 0.156939 0.254539 -0.951371 0.173502 0.582025 -0.758713 0.292579 0.908686 -0.219002 0.355427 0.880627 -0.325036 0.344743 0.848027 -0.1809 0.498121 0.716828 -0.170607 0.676055 0.714218 -0.181897 0.675875 0.823264 -0.564129 0.063207 0.990214 -0.092258 0.104712 0.944825 -0.0555319 0.322835 0.523781 -0.811418 0.259336 0.424876 -0.803458 0.417056 0.204767 -0.957265 0.204242 0.133163 -0.978802 0.155612 0.95411 -0.130687 -0.269435 0.99722 0.0544188 -0.050907 0.984355 -0.176152 0.00384854 0.961576 -0.272353 0.03457 0.852041 -0.514729 0.0952935 0.813115 -0.473882 0.338053 0.778726 -0.528034 0.33877 0.620423 -0.516784 0.589923 0.609261 -0.536208 0.584193 0.885231 -0.0344735 -0.463872 0.908243 -0.373793 -0.188077 0.935942 -0.16003 -0.313692 0.931445 -0.277857 -0.234959 0.862779 -0.498345 -0.0852325 0.901573 -0.423659 0.0876303 0.674977 -0.719546 0.163282 0.598677 -0.777061 0.194324 0.293071 -0.927014 0.233996 0.31218 -0.921883 0.229509 0.918932 -0.188579 -0.346412 0.91996 -0.0449563 -0.389426 0.773669 -0.610382 0.16991 0.770628 -0.613213 0.173502 0.84128 -0.463221 0.278701 0.840613 -0.463829 0.2797 0.529088 -0.715733 0.455842 0.300333 -0.757154 0.580101 0.79796 -0.488407 0.353156 0.587772 -0.579816 0.564215 0.659569 -0.338036 0.671342 0.660425 -0.337778 0.67063 0.88962 -0.28854 0.354007 0.889998 -0.288233 0.353306 0.981358 -0.188724 -0.0363195 0.949065 -0.303555 -0.0844439 0.662203 -0.61591 0.426781 0.901427 -0.409068 -0.141748 0.867032 -0.0609484 -0.49451 0.895041 -0.125788 -0.427878 0.918138 -0.0442501 -0.393783 0.788171 -0.216773 0.576018 0.997857 -0.0653274 -0.0037138 0.91492 -0.0972095 0.391754 0.912963 -0.0984021 0.396 0.689191 -0.114286 0.71551 0.68788 -0.114641 0.716714 0.692362 0.00015514 0.72155 0.692446 -0.000245901 0.72147 0.687066 -9.70452e-06 0.726595 0.917416 -9.50861e-06 0.397929 0.917393 -8.66644e-06 0.397983 0.999993 -6.43259e-06 -0.00372499 0.999993 -5.99901e-06 -0.00369448 0.92089 -2.52976e-06 -0.389822 0.9209 -2.19433e-06 -0.389799 0.882222 0.142813 -0.448653 0.852348 0.0848897 -0.51604 0.752004 0.542545 -0.374347 0.718323 0.602938 -0.347098 0.842311 0.17653 -0.509263 0.811163 0.258783 -0.524448 0.256093 0.964832 0.0592985 0.260761 0.963742 0.0566131 0.540948 0.824656 -0.165278 0.447889 0.887886 -0.105138 0.587911 0.782124 -0.206498 0.450104 0.818656 0.356663 0.45382 0.81771 0.354115 0.708008 0.700604 0.0887668 0.709953 0.6989 0.0866373 0.862678 0.461235 -0.207482 0.863161 0.459798 -0.20866 0.873884 0.156218 -0.460351 0.842536 0.179859 -0.507725 0.598965 0.547814 0.584073 0.601335 0.547244 0.582169 0.836334 0.469227 0.283498 0.837415 0.468353 0.281748 0.947726 0.309045 -0.0794163 0.947864 0.308352 -0.0804584 0.886085 0.0761404 -0.457227 0.899639 0.111135 -0.422254 0.679353 0.193104 0.707948 0.681014 0.192792 0.706435 0.904703 0.165956 0.39239 0.906619 0.164978 0.388362 0.993893 0.110281 -0.0037546 0.994046 0.108475 -0.0102717 0.920217 0.0381365 -0.389546 0.969818 0.0874702 -0.2276 0.81648 0.183286 -0.547509 0.800621 0.258816 -0.540389 0.156605 0.982062 -0.105015 0.156751 0.982029 -0.105105 0.362392 0.899787 -0.243013 0.362508 0.89972 -0.243088 0.507272 0.791811 -0.340163 0.507514 0.791591 -0.340313 0.660201 0.606737 -0.442724 0.660385 0.606455 -0.442836 0.749277 0.431432 -0.502444 0.805775 0.183254 -0.563156 0.816583 0.0662464 -0.573415 0.471469 0.780164 -0.41117 0.308616 0.895744 -0.319999 0.104543 0.977818 -0.181503 0.191305 0.946219 -0.260908 0.730181 0.431193 -0.530008 0.622639 0.605161 -0.496086 0.462442 0.78917 -0.404176 0.800362 0.157251 -0.578526 -0.0291016 0.975645 -0.217417 0.65207 0.44322 -0.61511 0.383955 0.747274 -0.542366 0.43653 0.69396 -0.572591 0.0939977 0.908789 -0.40653 0.180463 0.863625 -0.470729 0.156999 0.290421 -0.943932 0.828635 0.0989646 -0.550972 0.798283 0.15551 -0.581859 0.67375 0.358861 -0.645972 0.619293 0.416707 -0.665456 0.445194 0.587545 -0.675717 0.366835 0.637918 -0.677121 0.178412 0.750396 -0.636455 0.0826041 0.783703 -0.615619 0.874827 0.0784647 -0.478039 0.841505 0.12217 -0.526255 0.70464 0.283006 -0.650684 0.653214 0.321479 -0.685539 0.457799 0.46251 -0.759279 0.393043 0.491516 -0.777129 -0.00450781 0.642996 -0.765856 0.136518 0.675156 -0.724932 -0.154981 0.457284 -0.875712 0.898374 0.0562266 -0.435617 0.873825 0.0744322 -0.480509 0.720073 0.186872 -0.668261 0.684568 0.201082 -0.700666 0.461677 0.300344 -0.834654 0.420842 0.30931 -0.852771 0.124203 0.387764 -0.913352 0.168226 0.571952 -0.802852 0.87757 0.0311502 -0.478436 0.896108 0.0312887 -0.442731 0.680174 0.0676292 -0.729924 0.708921 0.0671689 -0.702082 0.507986 0.0988451 -0.855675 0.44325 0.100862 -0.890706 0.210768 0.134255 -0.968273 0.14153 0.130666 -0.981272 0.877996 0 -0.478668 0.877996 0 -0.478668 0.681735 0 -0.731599 0.681735 0 -0.731599 0.510486 0 -0.859886 0.510486 0 -0.859886 0.212694 0 -0.977119 0.212694 0 -0.977119 0.904298 0.0225756 -0.426305 0.87777 -0.022699 -0.478545 0.723396 0.0962008 -0.683699 0.679991 0.0714756 -0.729728 0.452497 0.0984057 -0.88632 0.505779 0.135495 -0.851956 0.140667 0.0688465 -0.98766 0.21104 0.124472 -0.96952 0.908487 0.0661346 -0.412648 0.907553 0.065132 -0.414856 0.72418 0.187381 -0.663666 0.729444 0.190511 -0.656976 0.452509 0.290288 -0.843189 0.46786 0.297278 -0.832306 0.139608 0.357996 -0.923227 0.16527 0.369319 -0.914489 0.1686 0.477182 -0.86248 0.938878 0.0696466 -0.33713 0.913959 0.0993934 -0.393447 0.769426 0.239652 -0.592074 0.737168 0.257733 -0.624625 0.495845 0.383994 -0.778901 0.471282 0.390972 -0.790591 0.174488 0.475024 -0.8625 0.159619 0.475446 -0.865143 0.941808 0.135614 -0.307583 0.582294 0.78803 -0.199855 0.410954 0.893917 -0.178967 0.540468 0.810936 -0.224227 0.512856 0.764082 -0.391354 0.529524 0.745077 -0.405543 0.501297 0.649771 -0.571401 0.949526 0.258597 -0.177562 0.952616 0.243703 -0.182019 0.958735 0.160901 -0.23439 0.161747 0.970774 -0.177299 0.145562 0.975254 -0.166406 0.199524 0.892626 -0.40424 0.209781 0.886055 -0.413399 0.161069 0.829318 -0.535059 0.213618 0.753877 -0.621319 0.0580894 0.663066 -0.746303 0.503844 0.478118 -0.719406 0.834143 0.264277 -0.484112 0.776621 0.370972 -0.509155 0.944612 0.133143 -0.299968 0.771115 0.606716 -0.193077 0.840121 0.4702 -0.270387 0.805093 0.493098 -0.329666 0.785216 0.422947 -0.452274 0.516407 0.630843 -0.579104 0.491442 0.493565 -0.71755 0.179011 0.579751 -0.794886 0.189276 0.981924 0.000542931 0.612783 0.79025 0.00175735 0.438913 0.898529 0.00125872 0.966594 0.256299 0.00277335 0.79641 0.604753 0.00228506 0.260678 0.965409 0.00566204 0.252046 0.965591 0.0640858 0.252042 0.965592 0.0640842 0.233946 0.965592 0.113582 0.233948 0.965592 0.113583 0.14846 0.981812 0.118345 0.206884 0.965622 0.157398 0.343165 0.898557 0.273555 0.479718 0.789705 0.382409 0.710349 0.703804 0.00800807 0.687076 0.705271 0.174696 0.687075 0.705273 0.174695 0.637747 0.705271 0.309631 0.637746 0.705273 0.30963 0.55906 0.704979 0.436414 0.62321 0.603992 0.496792 0.966594 0.256298 0.00277351 0.936461 0.25758 0.238104 0.936462 0.257576 0.238105 0.869227 0.257578 0.422016 0.869226 0.257588 0.422013 0.755668 0.257105 0.602381 0.755669 0.257102 0.602382 0.344319 0.515358 0.784761 0.674924 0.258822 0.691005 0.667082 0.156363 0.72839 0.176431 0.675537 0.715906 0.0144718 0.68576 0.727684 0.191193 0.800414 0.56814 0.362099 0.788532 0.497093 0.38864 0.776189 0.496477 0.260994 0.898013 0.354195 0.0351021 0.973088 0.227744 0.227682 0.949904 0.214109 0.4292 0.597948 0.676939 0.665544 0.389197 0.636849 0.563612 0.45272 0.690931 0.27976 0.751757 0.597156 0.403856 0.713419 0.572654 0.0252076 0.912211 0.408945 0.209687 0.893422 0.397277 0.14206 0.873564 0.465515 0.0349191 0.812738 0.581582 0.303081 0.675893 0.671796 0.352475 0.513439 0.782395 0.461161 0.411277 0.786245 0.49952 0.322839 0.8039 0.620848 0.137003 0.771867 0.624291 0.115957 0.772537 0.0981159 0.601619 0.792735 0.11576 0.555371 0.823506 0.292406 0.464177 0.836085 0.0370237 0.667614 0.743586 0.151573 0.619481 0.77024 0.35776 0.556283 0.750038 0.600923 0.0921459 0.793978 0.586197 0.10058 0.803901 0.455249 0.27797 0.845861 0.443863 0.304183 0.842887 0.582815 0.103925 0.805932 0.439194 0.897223 -0.0458174 0.140861 0.808489 -0.571406 0.662829 -0.0849272 0.743939 0.570378 0.808752 0.143492 0.525038 0.847085 0.0823561 0.643141 0.765124 -0.0308959 0.0463754 0.756287 -0.652594 0.207082 0.823008 -0.528938 0.325006 0.842211 -0.430177 0.30794 0.839272 -0.448103 0.450052 0.844578 -0.29007 0.14297 0.925234 -0.351427 0.0366066 0.880636 -0.472377 0.28098 0.934846 -0.217055 0.20602 0.925801 -0.316936 0.370363 0.920697 -0.123077 0.495817 0.833742 -0.242981 0.619132 0.782525 -0.0658045 0.223635 0.884216 0.41006 0.16577 0.907313 0.386398 -0.0834607 0.994302 0.0663214 0.236487 0.863595 0.445283 0.425368 0.660827 0.618361 0.345552 0.772931 0.532138 0.587082 0.314804 0.745811 0.481637 0.628277 0.610977 0.603893 0.283866 0.744804 0.744698 0.546595 0.382961 0.752581 0.474629 0.456453 0.709117 0.696922 0.107016 -0.0680236 0.742641 -0.666226 0.663878 0.670509 0.331185 0.580652 0.704034 0.408877 0.472422 0.849289 0.235638 0.506772 0.807919 0.300749 0.333336 0.941288 0.0535092 0.386213 0.911817 0.139393 0.181375 0.975562 -0.124024 0.251235 0.967656 -0.0228396 0.0173752 0.954427 -0.29794 0.111705 0.978479 -0.173495 0.129398 0.738481 0.661742 -0.0884236 0.885446 0.456253 0.215022 0.668293 0.712145 0.0629867 0.803549 0.591897 0.335634 0.539146 0.772445 0.0969182 0.956503 0.275151 0.334456 0.773737 0.538024 0.179816 0.721057 0.669136 0.284127 0.61262 0.737543 0.483057 0.336597 0.808306 0.507672 0.287928 0.812014 0.597822 0.116445 0.793127 0.13234 0.989273 0.0618481 0.0233155 0.995405 -0.0928731 0.227722 0.960433 0.160349 0.159644 0.985302 0.060781 0.349242 0.88739 0.300946 0.296972 0.92898 0.220916 0.459893 0.774986 0.43347 0.424648 0.823673 0.375815 0.551752 0.627923 0.548892 0.0102783 0.975525 -0.219646 0.671555 0.283285 0.684663 0.645472 0.519878 0.559548 0.680761 0.249585 0.688674 0.737904 0.165411 0.654322 0.746917 0.197409 0.634936 0.765036 0.471625 0.438509 0.751525 0.192655 0.630947 0.69164 0.658246 0.297229 0.51431 0.852896 0.0897415 0.597626 0.794209 0.109883 0.35184 0.929885 -0.107342 0.0393989 0.87849 -0.476134 0.125034 0.919026 -0.373842 0.214124 0.920734 -0.326189 0.279951 0.93466 -0.219178 0.470099 0.878797 -0.0819936 0.0249082 0.995891 -0.0870621 0.166092 0.980935 0.100895 0.129452 0.986981 0.0954525 0.320683 0.923308 0.21134 0.314915 0.926024 0.208105 0.405258 0.831251 0.380509 0.419485 0.823469 0.382009 0.635113 0.553948 0.538306 0.592296 0.585876 0.553114 0.699052 0.195066 0.68795 0.706192 0.187248 0.682811 0.0510276 0.751683 -0.657548 0.139351 0.807603 -0.573025 0.215599 0.8151 -0.537707 0.317768 0.846594 -0.426969 0.296916 0.84901 -0.437063 0.521684 0.80815 -0.273387 0.453484 0.841617 -0.293315 0.647374 0.761161 -0.0392418 0.610833 0.789594 -0.0585224 0.823653 0.466069 0.323071 0.634911 0.754577 0.165837 0.771251 0.523402 0.362246 0.0338321 0.95795 -0.284933 0.115836 0.977542 -0.176052 0.191888 0.972341 -0.133159 0.254933 0.966601 -0.0263106 0.350412 0.935856 0.0372066 0.391491 0.91051 0.133067 0.494619 0.842436 0.213667 0.514382 0.806658 0.291058 0.609662 0.695563 0.380137 0.611558 0.582646 0.535277 0.667905 0.5151 0.537191 0.727501 0.203645 0.655188 0.751899 0.193024 0.630388 0.716637 0.194908 0.669659 0.716635 0.194917 0.669657 0.607688 0.55521 0.567852 0.607687 0.555213 0.567851 0.406194 0.831225 0.379567 0.406194 0.831225 0.379567 0.142673 0.98075 0.13332 0.273054 0.926283 0.259694 0.137889 0.982031 0.12885 0.371853 0.438763 0.818054 0.278292 0.44543 0.850968 0.402451 0.584865 0.704249 0.28922 0.607478 0.739812 0.432789 0.69853 0.569868 0.706853 0.0966416 0.700728 0.694728 0.134978 0.706494 0.198336 0.944153 0.263131 0.139059 0.931774 0.335349 0.11286 0.867556 0.484364 0.135011 0.86749 0.478783 0.109147 0.732206 0.672281 0.17831 0.734191 0.65511 0.0334788 0.56919 0.821524 0.169238 0.573235 0.801723 0.73187 0.144373 0.665975 0.732777 0.195052 0.651914 0.610315 0.447805 0.653442 0.616117 0.55542 0.558488 0.341561 0.825543 0.449237 0.556863 0.274591 0.783903 0.580479 0.270508 0.76803 0.549333 0.404055 0.731418 0.614528 0.445494 0.651068 0.308386 0.7352 0.603639 0.461056 0.77952 0.424 0.145857 0.947683 0.28394 0.148666 0.980785 0.126329 0.110632 0.456312 0.882916 0.112406 0.455473 0.883125 0.328631 0.348237 0.877914 0.332699 0.34571 0.87738 0.530035 0.217347 0.819648 0.69279 0.0673264 0.71799 0.622062 0.14337 0.76973 0.303751 0.285946 0.908829 0.609091 0.116916 0.784435 0.518554 0.0573058 0.853122 0.611517 0.0909164 0.78599 0.438392 0.14181 0.887526 0.0606871 0.344946 0.936659 0.136771 0.360066 0.922847 0.0528911 -0.00587306 0.998583 0.217067 0.119207 0.968851 0.108656 0 0.994079 0.206188 0.332482 0.920295 0.323313 0 0.946292 0.614061 0 0.789259 0.614061 0 0.789259 0.352368 0.701832 0.619087 -0.0625724 0.884238 0.462827 0.38115 0.568602 0.728983 0.129777 0.889078 0.438974 0.121536 0.413892 0.902176 0.76327 0.194944 0.615968 0.431533 0.777164 0.458035 0.638281 0.554937 0.533519 0.451323 0.795532 0.404274 0.405099 0.829629 0.3842 0.185095 0.958163 0.218321 0.109753 0.977824 0.178364 0.725284 0.115345 0.678719 0.746976 0.112416 0.655278 0.413206 0.644868 0.642966 0.793839 0.0693431 0.604161 0.10843 0.064494 0.99201 0.0666209 0.270287 0.960472 0.0870266 0.865874 0.492635 0.167305 0.833753 0.52618 0.103303 0.786142 0.609351 0.00935703 0.809279 0.58735 0.187199 0.661467 0.726235 0.620058 0.183286 0.762846 0.562138 0.255979 0.786432 0.559876 0.2493 0.790183 0.37179 0.403569 0.836005 0.282615 0.457255 0.843236 -0.388309 0.705609 0.592733 -0.227669 0.688381 0.688694 -0.938529 0.242012 0.246158 0.277455 0.160223 0.947284 0.319565 0.151831 0.935321 0.644072 0.05032 0.763308 0.613114 0.0554961 0.788043 0.712612 0.0894668 0.695831 0.520077 0.289331 0.803621 0.602869 0.381744 0.700586 0.558755 0.436829 0.704964 0.629676 0.47173 0.617236 0.425931 0.737651 0.523883 0.373585 0.776901 0.506812 0.15629 0.91787 0.364812 0.0963744 0.937087 0.335529 0.84229 0.195064 0.502492 0.863612 0.195 0.464918 0.826678 -0.324988 0.459332 0.727032 0.555191 0.403965 0.727018 0.555216 0.403957 0.552712 0.774722 0.307106 0.486407 0.831201 0.269284 0.409934 0.883218 0.227774 0.248846 0.958623 0.138268 0.171138 0.980742 0.0941133 0.080429 0.995758 0.0446892 0.812122 0.194898 0.549974 0.812121 0.194907 0.549973 0.688653 0.555216 0.46636 0.688669 0.555187 0.466371 0.460322 0.831219 0.311734 0.460312 0.831227 0.311726 0.161685 0.980749 0.109494 0.161684 0.980749 0.109494 0.520137 0.812067 -0.264584 0.976848 0.0652691 0.203735 0.936641 0.186341 0.296614 0.936936 0.178215 0.300651 0.95368 0.143729 0.264266 0.743403 0.296927 -0.599322 0.754122 0.296884 -0.585799 0.675248 0.105323 -0.730033 0.760672 0.133828 -0.635191 0.566233 0.109438 -0.816948 0.546411 0.323686 -0.772439 0.563041 0.325314 -0.759708 0.244677 0.112361 -0.963072 0.238516 0.11387 -0.96444 0.220521 0.309884 -0.924847 0.17631 0.319155 -0.931158 0.282563 0.514031 -0.809896 0.659481 0.709593 -0.248119 0.865081 0.501244 0.0197371 0.816033 0.568182 -0.106113 0.89856 0.431092 0.0821602 0.441958 0.835042 -0.327684 0.86737 0.483449 0.118093 0.65526 0.751963 -0.0720109 0.821295 0.559402 0.112005 0.835077 0.536294 0.122623 0.920002 0.177664 0.34933 0.98528 0.017858 0.170014 0.967301 0.0424552 0.250053 0.974312 0.128161 -0.185177 0.980549 0.124203 -0.15198 -0.0970556 0.821226 -0.562288 0.163297 0.865128 -0.474223 0.0717963 0.955681 -0.285515 -0.395845 0.836698 -0.378474 0.134842 0.988684 -0.0657313 0.902848 0.0862592 -0.421219 0.243558 0.217094 -0.945278 0.896328 0.247325 -0.368003 0.867257 0.394563 -0.303621 0.720273 0.469764 -0.51042 0.736795 0.466809 -0.489104 0.526117 0.513882 -0.677589 0.551741 0.514449 -0.656449 0.243607 0.519523 -0.818994 0.187683 0.693494 -0.695587 0.105005 0.673715 -0.731493 0.0995999 0.75141 -0.652275 0.479976 0.873939 0.0765104 0.388523 0.921374 0.0109707 0.619097 0.768324 0.162469 0.560556 0.81996 0.115946 0.783292 0.553006 0.283969 0.764563 0.588927 0.261932 0.894751 0.194929 0.401774 0.706848 0.690366 0.154146 0.967507 0.114625 0.225369 0.947982 0.0923404 0.304637 0.938602 0.340136 -0.0577403 0.945385 0.324721 -0.0283412 0.234284 0.601084 -0.764074 0.849199 0.496148 -0.180829 0.691683 0.607987 -0.389779 0.71252 0.600413 -0.36307 0.502507 0.668743 -0.547969 0.534405 0.666256 -0.520109 0.335403 0.686949 -0.644675 0.241171 0.864075 -0.441828 0.342355 0.860226 -0.377895 0.205076 0.974503 -0.0910412 0.321107 0.946936 -0.0142381 0.985437 0 0.170041 0.985437 0 0.170041 0.982414 0 -0.186716 0.866067 0.404699 -0.293508 0.906226 0 -0.422795 0.679024 0 -0.734116 0.679024 0 -0.734116 0.246236 0 -0.96921 0.246236 0 -0.96921 0.879075 0.346757 -0.327088 0.633466 0.460956 -0.621483 0.651638 0.429388 -0.625295 0.750557 0.191167 -0.632549 0.238002 0.450535 -0.860449 0.208683 0.484743 -0.849397 0.237389 0.32966 -0.913767 0.217082 0.356552 -0.908706 0.235792 0.20209 -0.950559 0.224115 0.219454 -0.949533 0.233291 0.0685306 -0.969989 0.678374 -0.0437725 -0.733412 0.757838 0.0671912 -0.648974 0.946003 0.0479101 -0.320598 0.981744 0.0331477 0.187294 0.985329 0.0148207 0.170022 0.981726 0.0906187 -0.16734 0.943062 0.0266768 -0.331546 0.899644 0.159577 -0.406418 0.754253 0.197 -0.626333 0.973689 0.093461 0.207836 0.974995 0.0905346 0.20295 0.966122 0.229947 -0.11719 0.964968 0.227787 -0.130193 0.900342 0.300073 -0.315184 0.888029 0.259384 -0.379638 0.656987 0.339441 -0.673162 0.686781 0.512572 -0.515366 0.545114 0.337455 -0.767447 0.559725 0.215166 -0.800257 0.55346 0.207909 -0.806508 0.561157 0.0842523 -0.82341 0.245959 0.0474154 -0.96812 0.969239 0.121393 0.214103 0.967989 0.117501 0.22179 0.953532 0.289497 -0.0834735 0.91449 0.352902 -0.197911 0.868585 0.393798 -0.300805 0.723244 0.473359 -0.502841 0.637387 0.495176 -0.590372 0.534336 0.52009 -0.666327 0.320237 0.533159 -0.783064 0.220333 0.524922 -0.822138 0.105834 0.51716 -0.84932 0.955417 0.142738 0.258467 0.96577 0.134633 0.221723 0.889057 0.432647 -0.149647 0.916215 0.183376 0.356264 0.047497 0.991809 -0.118572 0.208355 0.978008 -0.0094089 0.215933 0.976356 -0.010137 0.912062 0.191256 0.362717 0.93172 0.182727 0.31386 0.810795 0.570271 0.131917 0.874586 0.48451 -0.0187138 0.684021 0.695504 -0.219974 0.657876 0.705331 -0.264021 0.51518 0.779905 -0.355441 0.472742 0.783349 -0.403582 0.327069 0.821227 -0.46756 0.269137 0.814198 -0.514438 0.0563992 0.820459 -0.568917 0.214124 0.787283 -0.578219 0.103098 0.86736 -0.486886 0.411833 0.91009 0.0461528 0.440614 0.894711 0.0731567 0.577387 0.804105 0.141562 0.592075 0.789009 0.164048 0.762937 0.604205 0.22992 0.931666 0.182869 0.31394 0.948326 0.168856 0.268638 0.852908 0.521915 -0.0123215 0.909481 0.389084 -0.146485 0.718557 0.564712 -0.405927 0.694997 0.564719 -0.445052 0.540759 0.625844 -0.562049 0.504308 0.619826 -0.60124 0.340182 0.65042 -0.679139 0.290621 0.636815 -0.714147 0.136389 0.640859 -0.755445 0.0786438 0.61878 -0.781618 0.0720023 0.932625 -0.353592 0.131488 0.940213 -0.314183 0.247395 0.926951 -0.282061 0.310716 0.922457 -0.229192 0.440237 0.879543 -0.180544 0.487077 0.863691 -0.129589 0.617754 0.783679 -0.0650108 0.647223 0.762026 -0.0204898 0.838271 0.532817 0.115792 0.800165 0.560518 0.213437 0.846996 0.431235 0.310861 0.829562 0.431713 0.35419 0.909452 0.183454 0.373152 0.569585 0.791639 0.221089 0.905505 0.258777 0.336295 0.932113 -0.01618 0.361805 0.741159 0.606565 0.287685 0.741298 0.606367 0.287743 0.569752 0.791502 0.22115 0.175873 0.982043 0.0682662 0.406968 0.89968 0.157968 0.406977 0.899675 0.157971 0.17597 0.982023 0.0683014 0.125971 0.970756 0.204363 0.374152 0.894606 0.244316 0.904069 0.143244 0.402666 0.882197 0.132645 0.451811 0.511549 0.732158 0.449735 0.456542 0.744297 0.487433 0.520018 0.794294 0.314132 0.164723 0.868403 0.467699 0.194231 0.873574 0.446255 0.16148 0.929306 0.332137 0.216666 0.962166 0.165206 0.187561 0.753426 0.630215 0.916088 0.17151 0.362446 0.905649 0.258779 0.335907 0.664136 0.593229 0.454976 0.162461 0.74826 0.643206 0.491038 0.620866 0.61107 0.444202 0.622206 0.644627 0.728936 0.412073 0.54667 0.764277 0.471621 0.439835 0.851688 0.415365 0.319529 0.535251 0.786675 0.307652 0.897325 0.121898 0.424204 0.760873 0.306305 0.572058 0.722012 0.301279 0.62284 0.436812 0.466211 0.769313 0.469146 0.471791 0.746535 0.123932 0.574454 0.809101 0.176096 0.58809 0.789392 0.153401 0.471351 0.868502 0.154434 0.471061 0.868476 0.452836 0.377604 0.807685 0.45581 0.376191 0.806671 0.711836 0.241389 0.659562 0.715811 0.238342 0.656359 0.89068 0.0836062 0.446878 0.894116 0.0788863 0.440832 0.493013 0.132661 0.859849 0.890897 0.0631835 0.44979 0.205166 0.123849 0.97086 0.134898 0.0699601 0.988387 0.16243 0.367792 0.915612 0.862682 0.028645 0.504935 0.860345 0.0359162 0.508446 0.657208 0.161643 0.736172 0.690346 0.132816 0.711184 0.546533 0.169735 0.820056 0.439278 0.298519 0.847303 0.13152 0.35493 0.925596 0.152674 0 0.988277 0.206757 0.00128401 0.978391 0.353722 0 0.93535 0.497409 0 0.867516 0.499112 -3.1239e-05 0.866538 0.665966 3.23809e-05 0.745982 0.667513 0 0.744598 0.863036 0 0.505142 0.863036 0 0.505142 0.90825 -0.258748 0.328833 0.516365 -0.803906 0.295131 0.387659 -0.897121 0.211883 0.192901 -0.964396 0.180912 0.157299 -0.979936 0.122404 0.468603 -0.415129 0.779794 0.432131 -0.448808 0.782199 0.496091 -0.634007 0.593236 0.541815 -0.579712 0.608581 0.475393 -0.717625 0.508936 0.548843 -0.788808 0.276684 0.737915 -0.606097 0.296864 0.774289 -0.497206 0.391489 0.924733 -0.245275 0.291049 0.914346 -0.132819 0.382531 0.907178 -0.176715 0.381838 0.901363 -0.097702 0.4219 0.175749 -0.226968 0.957913 0.152572 -0.35726 0.921459 0.174279 -0.519227 0.836678 0.152402 -0.0596813 0.986515 0.244935 -0.178373 0.95299 0.348698 -0.16795 0.922064 0.433981 -0.171012 0.884543 0.494131 -0.140928 0.857889 0.310487 -0.432015 0.846736 0.146247 -0.616107 0.773967 0.171503 -0.731135 0.660324 0.102893 -0.79096 0.603155 0.185405 -0.836331 0.515922 0.649908 -0.228148 0.72496 0.838905 -0.0955608 0.535823 0.861975 -0.0495663 0.504521 0.817706 -0.0687673 0.571514 0.709096 -0.28835 0.643457 0.749444 -0.405253 0.523548 0.73204 -0.443392 0.517224 0.776425 -0.496164 0.388569 0.507708 -0.75639 0.41244 0.488992 -0.787703 0.374714 0.126935 -0.928966 0.347722 0.133572 -0.925989 0.353133 0.600314 -0.166735 0.782191 0.490063 -0.0922615 0.866791 0.804084 -0.0535273 0.5921 0.839224 -0.0245772 0.54323 0.813252 -0.0817434 0.576142 0.805939 0.0557973 0.589363 0.0910184 0.218316 0.971624 0.54705 0.153237 0.822955 -0.210017 0.038815 0.976927 0.100835 -0.897394 0.429555 0.0167909 -0.811215 0.584507 -0.883218 -0.449457 -0.133849 0.429543 -0.553986 0.713156 0.507426 -0.497017 0.703913 0.629128 -0.384178 0.675725 0.66933 -0.344275 0.658386 0.847146 -0.0772542 0.525714 0.825313 -0.114165 0.553014 0.823195 0.0320819 0.566852 0.802355 0.0444345 0.595191 0.595863 0.0789061 0.799201 -0.70262 -0.673196 -0.230505 0.123627 -0.974803 0.185675 0.12086 -0.975484 0.183915 0.0607563 -0.951345 0.302078 -0.229083 -0.950098 0.211741 0.252063 -0.855334 0.452622 0.121645 -0.718814 0.684477 0.170205 -0.699536 0.694031 0.208686 -0.408533 0.888567 0.369976 0.211038 0.904755 -0.982114 0.108522 0.15387 0.35017 0.025617 0.936336 0.360704 -0.164352 0.918086 0.151196 -0.204924 0.967029 0.111029 -0.446791 0.887722 -0.0335168 -0.479018 0.877165 0.127151 -0.608274 0.783476 0.479811 -0.763728 0.431856 0.566598 -0.686248 0.456104 0.678569 -0.55095 0.485796 0.728535 -0.479812 0.488894 0.850769 -0.194823 0.488094 0.785321 -0.357098 0.505719 -0.163186 0.125082 0.978634 0.80248 0.00508839 0.596658 0.590172 0.0166522 0.807106 0.596688 -0.168667 0.784548 -0.941272 -0.265867 0.208138 0.441689 -0.319157 0.83848 0.305855 -0.37153 0.876594 0.385978 -0.584078 0.714055 0.272516 -0.648833 0.710458 0.431067 -0.801817 0.413848 0.325396 -0.867241 0.376844 0.139589 0.67453 0.72493 0.864402 0.120087 0.48825 0.158246 0.787616 0.595499 0.211256 0.4181 -0.883495 0.811968 0.0803308 -0.578148 0.6348 0.219352 -0.740887 0.404149 0.343449 -0.847766 0.15585 0.552727 -0.81866 0.121446 0.445417 -0.887048 0.0805547 0.456078 -0.886287 0.825944 0.0668585 -0.559773 0.83772 0.103838 -0.536137 0.851392 0.085822 -0.517462 0.864462 0.120095 -0.488142 0.940379 -0.046011 -0.337002 -0.36315 0.725382 -0.584759 0.149577 0.61843 -0.771473 0.128074 0.561227 -0.817693 0.181997 0.838036 -0.514367 0.158179 0.787966 -0.595054 -0.532323 0.751692 -0.389347 0.167191 0.739594 -0.651957 0.139569 0.674747 -0.724732 0.186201 0.94435 -0.27117 0.174922 0.922522 -0.344029 0.18402 0.920543 -0.344581 0.172102 0.897143 -0.406835 0.0154533 0.919999 -0.391617 0.174849 0.880149 -0.441322 0.157826 0.844408 -0.511924 0.0745275 0.980295 -0.182941 0.183986 0.955869 -0.229051 0.17897 0.945836 -0.270857 0.885263 0.118968 -0.449617 0.896866 0.147245 -0.417073 0.906833 0.124672 -0.40263 0.925746 0.165578 -0.339967 0.933202 0.143826 -0.329314 0.946881 0.170328 -0.272771 0.94964 0.160842 -0.268913 0.957746 0.176835 -0.22683 0.959955 0.168323 -0.22395 0.966959 0.181923 -0.178591 0.968581 0.174992 -0.176716 0.97418 0.185712 -0.128392 0.975295 0.180512 -0.127336 0.977637 0.184407 -0.101097 0.985143 0.155105 -0.073727 0.182477 0.963764 -0.194579 0.188461 0.97508 -0.117052 0.185711 0.975607 -0.117057 0.188723 0.981285 -0.0382553 0.187241 0.981567 -0.0382947 0.187194 0.981474 0.0408391 0.188303 0.981259 0.0408964 0.185167 0.975357 0.119966 0.979829 0.185062 -0.0754139 0.981717 0.188668 -0.0252149 0.981977 0.187323 -0.0251199 0.981942 0.187266 0.0268543 0.981724 0.188408 0.0268493 0.979664 0.184534 0.0787709 0.979011 0.187882 0.0789788 0.975037 0.180336 0.129545 0.973913 0.18582 0.130245 0.968249 0.174994 0.178525 0.96674 0.181849 0.179849 0.959671 0.16813 0.225309 0.957564 0.176872 0.22757 0.641694 0.215009 -0.736206 0.66306 0.281869 -0.69347 0.670269 0.276125 -0.688836 0.695491 0.342911 -0.63143 0.702548 0.336175 -0.627226 0.730193 0.401063 -0.553143 0.736578 0.394025 -0.549724 0.764549 0.454327 -0.457222 0.770036 0.447533 -0.454709 0.790082 0.486463 -0.372993 0.792283 0.483577 -0.372078 0.803872 0.50644 -0.311944 0.805785 0.503823 -0.311246 0.815721 0.523097 -0.246918 0.817225 0.520964 -0.246455 0.825127 0.536077 -0.178287 0.826217 0.534486 -0.17802 0.831664 0.544791 -0.107413 0.832248 0.543919 -0.107309 0.835008 0.549112 -0.0351791 0.835271 0.548714 -0.0351503 0.835222 0.54863 0.0375486 0.835007 0.548957 0.0375406 0.832127 0.54354 0.110129 0.831461 0.544554 0.110154 0.825905 0.534013 0.18086 0.824774 0.535717 0.180983 0.816834 0.520538 0.24864 0.815419 0.522633 0.248891 0.805485 0.503367 0.312756 0.803599 0.506089 0.313214 0.39608 0.346906 -0.850163 0.425351 0.438271 -0.79183 0.416629 0.442727 -0.793985 0.449474 0.52947 -0.719468 0.440571 0.534547 -0.721219 0.475074 0.61531 -0.629045 0.466654 0.620441 -0.630307 0.500412 0.692955 -0.519039 0.492925 0.69769 -0.51986 0.516286 0.744242 -0.423737 0.513138 0.746228 -0.424068 0.526621 0.772843 -0.354096 0.523811 0.774632 -0.354355 0.535286 0.796863 -0.28014 0.533077 0.798279 -0.280319 0.542142 0.815597 -0.202199 0.540517 0.816646 -0.202314 0.546732 0.8284 -0.121811 0.545867 0.828962 -0.121865 0.549004 0.834868 -0.0398764 0.548587 0.835141 -0.0398987 0.548534 0.835043 0.0425896 0.548868 0.834823 0.0426044 0.545599 0.828676 0.124976 0.546586 0.828019 0.12501 0.540264 0.81605 0.205371 0.54201 0.814881 0.205412 0.532959 0.797559 0.282587 0.535044 0.796154 0.282609 0.523648 0.774073 0.355814 0.526415 0.7722 0.355802 0.172197 0.896813 0.407524 0.183929 0.919844 0.346492 0.174883 0.922059 0.345287 0.186026 0.943638 0.273754 0.179238 0.945183 0.272953 0.184371 0.955455 0.230464 0.0613055 0.980092 0.18884 0.182862 0.964193 0.192077 0.188487 0.97469 0.120217 0.174931 0.87976 0.442065 0.00389533 0.920406 0.390945 0.516042 0.743545 0.425254 0.512961 0.745634 0.425324 0.789787 0.486107 0.374081 0.791945 0.483094 0.373421 0.946706 0.170368 0.273355 0.949321 0.160605 0.270179 0.181788 0.837137 0.515903 0.157852 0.843923 0.512716 0.50011 0.692235 0.520289 0.492749 0.697093 0.520826 0.764316 0.453909 0.458026 0.769679 0.447019 0.455815 0.925604 0.165616 0.340336 0.932856 0.143508 0.330433 0.906528 0.124338 0.40342 0.89683 0.147388 0.4171 0.736347 0.393578 0.550355 0.730035 0.400844 0.55351 0.466535 0.620068 0.630763 0.474868 0.614728 0.62977 -0.526821 0.753485 0.393346 0.167211 0.739394 0.652179 0.149602 0.618224 0.771633 -0.370416 0.724377 0.581438 0.449341 0.529012 0.719888 0.440529 0.534328 0.721407 0.695404 0.342825 0.631573 0.702356 0.335859 0.627611 0.940055 -0.0450438 0.338036 0.885183 0.118972 0.449773 0.155687 0.552144 0.819084 0.128211 0.5613 0.817621 0.4253 0.437918 0.792053 0.416644 0.442627 0.794033 0.66303 0.281869 0.693499 0.67014 0.275886 0.689057 0.837759 0.104165 0.536013 0.851203 0.0854703 0.517831 0.146726 0.437979 0.886931 0.121553 0.445655 0.886914 0.404141 0.343262 0.847845 0.396159 0.346937 0.850113 0.63482 0.219438 0.740845 0.641624 0.214876 0.736306 0.812043 0.0806523 0.577998 0.825794 0.0665855 0.560027 0.726761 -0.0513189 -0.68497 0.805179 0.0528665 -0.590671 0.738093 0.0740064 -0.670628 0.572937 0.120724 -0.81066 0.809025 -0.0710669 -0.583462 0.884911 -0.0567928 -0.462285 0.847557 -0.152102 -0.508441 0.821834 -0.127944 -0.555176 0.870171 -0.0353402 -0.491481 0.819861 -0.0988115 -0.563972 0.399295 -0.645353 -0.651216 -0.503303 -0.776851 -0.378403 0.18133 -0.309392 -0.933486 0.159903 0.0291922 -0.986701 0.170731 0.258779 -0.950728 -0.967272 0.0477129 0.249215 0.353521 0.12028 -0.927662 0.343347 0.122484 -0.931188 0.850789 -0.194808 -0.488066 0.112236 -0.954958 -0.274698 0.711294 -0.554364 -0.432136 0.502753 -0.792468 -0.345303 0.45174 -0.827763 -0.332776 0.204615 -0.955568 -0.212187 0.124012 -0.974892 -0.184949 -0.803557 -0.423073 -0.418696 -0.970271 -0.143728 0.194722 0.0619235 -0.216524 -0.974312 0.0517359 0.0310428 -0.998178 0.614053 0.0443243 -0.788019 -0.589949 0.333902 -0.735167 0.0538838 0.350068 -0.935173 0.426576 -0.479088 -0.767143 0.101798 -0.644839 -0.757509 0.18162 -0.771763 -0.609423 -0.174448 -0.840702 -0.512629 0.27345 -0.795515 -0.540722 0.806406 0.032146 -0.590488 0.794272 0.0320021 -0.606718 0.810139 0.0321605 -0.585355 0.620075 0.159974 -0.768059 0.755849 0.0364883 -0.653729 0.819936 0.031894 -0.571567 0.813554 0.0321195 -0.580602 0.669097 0.0948974 -0.737091 0.596371 0.11477 -0.794462 0.544708 0.127624 -0.828858 0.808088 0.0321611 -0.588184 0.812441 0.0321656 -0.582156 0.807857 0.0321542 -0.588501 0.52428 0.132444 -0.841183 0.482099 0.141937 -0.864543 -0.694786 0.223274 -0.683682 -0.366945 0.224904 -0.902646 0.821573 0.00349585 -0.570093 0.616623 0.014271 -0.787129 0.623169 -0.155416 -0.76649 0.374709 -0.256122 -0.891064 0.34027 -0.265221 -0.90215 0.129974 -0.323607 -0.937222 0.227789 -0.575787 -0.785227 0.521602 -0.370231 -0.768675 0.848668 -0.020727 -0.528519 0.600713 -0.167709 -0.781677 0.669686 -0.344403 -0.657957 0.629629 -0.384227 -0.675231 0.706001 -0.456468 -0.541479 0.47487 -0.718176 -0.508647 0.421063 -0.754586 -0.503295 -0.011447 -0.944654 -0.327868 0.134602 -0.926867 -0.350429 0.855765 -0.0855348 -0.510244 0.887978 -0.152108 -0.434003 0.149946 -0.186778 -0.970892 0.348574 -0.168768 -0.921962 0.433787 -0.171832 -0.884479 0.49405 -0.141608 -0.857824 0.663402 -0.10993 -0.740144 0.480748 -0.824513 -0.298429 0.455382 -0.837119 -0.303081 0.361675 -0.725077 -0.58605 0.919951 -0.118031 -0.373844 0.723662 -0.434384 -0.536306 0.753034 -0.420289 -0.506258 0.466013 -0.748953 -0.471065 -0.0612185 -0.830952 -0.552965 0.166326 -0.948852 -0.268357 0.238238 -0.937627 -0.253177 0.069015 -0.994192 -0.0825838 0.0844998 -0.755662 -0.649488 0.06574 -0.581035 -0.811219 0.236367 -0.513267 -0.825038 0.159639 -0.409592 -0.898193 0.127746 -0.197212 -0.972002 0.494863 -0.629864 -0.59865 0.516493 -0.620986 -0.589585 0.598933 -0.720241 -0.350046 0.787584 -0.5119 -0.343031 0.742524 -0.551348 -0.380359 0.932 -0.160957 -0.324758 0.91386 -0.194883 -0.356204 0.862942 -0.0147897 -0.505087 0.848208 -0.0869368 -0.52248 0.789538 -0.136557 -0.598316 0.708619 -0.287486 -0.644368 0.467956 -0.413737 -0.780922 0.431586 -0.447237 -0.783398 0.187433 -0.514639 -0.836669 0.271455 -0.759391 -0.591301 0.193737 -0.794464 -0.57558 0.292065 -0.913228 -0.284099 0.211521 -0.944904 -0.249829 0.863036 0 -0.505142 0.863036 0 -0.505142 0.665983 0 -0.745967 0.667447 3.12487e-05 -0.744658 0.497409 -3.12112e-05 -0.867516 0.152632 0 -0.988283 0.206743 0.00128435 -0.978395 0.353646 0 -0.935379 0.499079 0 -0.866556 0.862682 0.0286567 -0.504935 0.833378 0.109089 -0.541831 0.489115 0.181851 -0.853051 0.565176 0.144476 -0.812221 0.439378 0.298951 -0.847099 0.206018 0.0836652 -0.974965 0.140963 0.127302 -0.981796 0.161226 0.351706 -0.922122 0.13488 0.371539 -0.918568 0.659259 0.141737 -0.738436 0.693313 0.143356 -0.706233 0.880246 0.0189643 -0.474138 0.154461 0.471111 -0.868445 0.153391 0.471298 -0.868533 0.455845 0.37637 -0.806568 0.452786 0.377428 -0.807795 0.715863 0.238657 -0.656189 0.711783 0.241073 -0.659734 0.894197 0.0793015 -0.440593 0.890598 0.0831897 -0.447119 0.53532 0.786661 -0.307566 0.885344 0.130402 -0.446275 0.905654 0.258779 -0.335892 0.912466 0.210016 -0.35114 0.909709 0.148349 -0.387843 0.374189 0.894629 -0.244177 0.520205 0.794227 -0.313993 0.471415 0.756943 -0.452553 0.501807 0.715549 -0.485983 0.4554 0.639804 -0.619082 0.131383 0.595948 -0.792202 0.18459 0.745292 -0.640677 0.179329 0.743918 -0.64376 0.159039 0.833134 -0.529711 0.201035 0.87169 -0.446924 0.1421 0.911777 -0.385318 0.200403 0.955257 -0.217536 0.144774 0.977324 -0.154525 0.466295 0.453061 -0.759806 0.771433 0.26034 -0.580616 0.726784 0.340373 -0.596599 0.897316 0.121837 -0.424241 0.727103 0.605425 -0.3237 0.786249 0.459548 -0.413071 0.764405 0.471443 -0.439802 0.729027 0.411809 -0.546748 0.484572 0.599479 -0.637037 0.443245 0.482389 -0.755536 0.171686 0.564872 -0.807121 0.900506 0.258674 -0.349537 0.900504 0.258684 -0.349536 0.741304 0.606361 -0.287742 0.741198 0.606509 -0.287703 0.56978 0.791479 -0.221161 0.569613 0.791616 -0.2211 0.406993 0.899667 -0.157977 0.406947 0.89969 -0.15796 0.17598 0.982021 -0.0683059 0.175904 0.982037 -0.0682781 0.920263 0.175376 -0.349798 0.871347 0.258596 -0.416993 0.779266 0.600484 -0.179342 0.718654 0.5646 0.405911 0.772929 0.529766 0.349182 0.899546 0.405364 0.162777 0.143545 0.620899 0.770636 0.0731103 0.637737 0.766776 0.346422 0.631019 0.694123 0.284428 0.655498 0.699588 0.545997 0.607762 0.576639 0.497981 0.637156 0.588258 0.695043 0.564585 0.445151 0.954961 0.143053 -0.259973 0.948336 0.168185 -0.269022 0.865708 0.500495 -0.00738977 0.824888 0.55563 -0.104097 0.607098 0.793413 0.043912 0.655746 0.753688 0.0441682 0.428317 0.89012 0.155662 0.497277 0.853319 0.156721 0.235066 0.938072 0.25449 0.32248 0.910604 0.258471 0.131585 0.940188 0.314217 0.208251 0.942792 0.260334 0.0496129 0.89632 0.440623 0.938134 0.177961 -0.297042 0.931378 0.187543 -0.312029 0.826937 0.542491 -0.147914 0.787932 0.566969 -0.240227 0.570161 0.806556 -0.156152 0.596559 0.788073 -0.15185 0.406696 0.911775 -0.0571373 0.446667 0.892894 -0.0568166 0.215906 0.976365 0.00983922 0.208241 0.978035 0.0091003 0.0474644 0.991845 0.11828 0.216396 0.786571 0.578341 0.056385 0.820354 0.56907 0.336724 0.803391 0.491102 0.259293 0.830953 0.492225 0.52338 0.76398 0.37737 0.463024 0.798992 0.383693 0.690734 0.68236 0.239314 0.649306 0.719193 0.247312 0.864181 0.502044 0.033803 0.902022 0.413791 0.123018 0.965784 0.134582 -0.221697 0.968142 0.116897 -0.221441 0.969085 0.121999 -0.214456 0.953532 0.289498 0.0834753 0.866149 0.403164 0.295373 0.916977 0.34639 0.197906 0.80185 0.437844 0.406606 0.636142 0.500087 0.587568 0.725655 0.463533 0.508489 0.534361 0.520086 0.66631 0.219334 0.528826 0.8199 0.322131 0.525634 0.787363 0.105822 0.517158 0.849323 0.984812 0.0356319 -0.169931 0.983312 0.0118774 -0.18154 0.981736 0.0903136 0.167448 0.646117 0.45726 0.611103 0.64009 0.432532 0.634981 0.657078 0.338473 0.673561 0.65148 0.31805 0.68878 0.664219 0.209108 0.717695 0.660022 0.195575 0.725342 0.230242 0.484521 0.843936 0.215647 0.450561 0.866309 0.233026 0.355646 0.905105 0.220817 0.328799 0.918222 0.233971 0.218402 0.947396 0.225497 0.20116 0.95325 0.974325 0.0951286 -0.204064 0.974602 0.089264 -0.205387 0.963664 0.234146 0.128557 0.967188 0.223528 0.120757 0.885194 0.310878 0.346101 0.9054 0.323175 0.275333 0.888148 0.258627 0.379874 0.89642 -0.0207587 0.442719 0.952256 0.133682 0.274478 0.946014 0.0476328 0.320606 0.667147 0.0712149 0.741514 0.67584 0.0967307 0.730673 0.234158 0.0453443 0.971141 0.245665 0.068076 0.966962 0.110512 0 0.993875 0.225097 0.405375 0.886004 0.351825 0 0.936066 0.574101 0 0.818785 0.620261 0.406931 0.670584 0.757979 0 0.65228 0.947089 0 0.32097 0.947089 0 0.32097 0.985437 0 -0.170039 0.985437 0 -0.170039 0.0659518 0.808995 0.584104 0.214806 0.915883 0.339141 0.682239 0.695435 0.225656 0.512465 0.775893 0.367926 0.209138 0.963902 0.164783 0.754033 0.101896 0.648884 0.971788 0.135934 0.192744 0.654258 0.714544 0.247736 0.7101 0.599818 0.36875 0.928654 0.363509 0.0739083 0.71652 0.471577 0.514017 0.750615 0.297231 0.590111 0.34284 0.224563 0.912158 0.112091 0.392133 0.913054 0.0898554 0.500776 0.8609 -0.453438 0.395691 0.798638 0.0256187 0.644673 0.764029 0.102253 0.739812 0.664998 0.471271 0.790262 0.391649 0.556651 0.589111 0.585737 0.495328 0.602212 0.626092 0.569705 0.218776 0.792195 0.560037 0.219984 0.798728 0.985965 0.125424 0.110194 0.984929 0.0321204 -0.169951 0.98327 0.0613661 0.171506 0.95212 0.292655 0.0884341 0.930416 0.366495 -0.0029488 0.874711 0.470837 -0.114859 0.888779 0.436202 -0.14071 0.842051 0.47953 -0.246985 0.894552 0.19492 -0.402223 0.573934 0.809315 -0.124937 0.763142 0.555016 -0.331016 0.484967 0.860764 -0.154569 0.523455 0.829911 -0.192983 0.143875 0.9891 0.0313228 0.206131 0.97826 -0.0227569 0.971488 0.187681 0.144868 0.973492 0.183837 0.136082 0.97997 0.084344 -0.180404 0.96449 0.113886 -0.238306 0.934983 0.354595 0.00825339 0.95665 0.244868 -0.157674 0.922589 0.129208 -0.363503 0.92823 0.178483 -0.326396 0.903412 0.199361 -0.379607 0.896033 0.0939889 -0.433924 -0.145015 0.232841 0.961642 -0.446932 0.13711 0.883998 0.110147 0.0812065 0.990592 0.357813 0.223731 0.906595 0.281912 0.612616 0.738395 0.360893 0.610318 0.705173 0.272066 0.814856 0.511849 0.27527 0.814427 0.510818 0.140031 0.905326 0.40097 0.444655 0.867342 0.223607 0.579183 0.802106 0.14551 0.623116 0.775801 0.0992908 0.153786 0.965102 0.211962 0.544913 0.837875 -0.0321776 0.512463 0.858697 0.00464477 0.730591 0.66243 -0.165604 0.781177 0.621375 -0.0604643 0.166582 0.860344 0.481724 0.80014 0.593592 0.0861643 0.839201 0.517218 0.168011 0.885273 0.452093 0.109106 0.924069 0.327925 0.196369 0.864001 0.397451 0.309087 0.893363 0.248651 0.374266 0.887269 0.253278 0.385491 0.902335 0.11274 0.41603 0.944231 0.0776311 0.320002 0.863614 0.194986 -0.46492 0.812124 0.194891 -0.549975 0.81212 0.194916 -0.549973 0.688662 0.5552 -0.466367 0.688659 0.555205 -0.466365 0.52237 0.775879 -0.353752 0.459863 0.831202 -0.312456 0.386928 0.884097 -0.26203 0.235282 0.958778 -0.159335 0.161233 0.980742 -0.110219 0.0757102 0.995811 -0.0512715 0.842287 0.19508 -0.50249 0.826681 -0.324979 -0.459333 0.727023 0.555205 -0.40396 0.727026 0.555202 -0.403961 0.485967 0.831219 -0.270021 0.485967 0.831219 -0.270021 0.170689 0.98075 -0.0948408 0.170692 0.980749 -0.0948422 0.519949 0.288277 -0.804083 0.15322 0.494426 -0.855609 0.10737 0.15007 -0.982828 0.0957604 0.344931 -0.933731 -0.814636 0.276024 -0.510077 0.277893 0.159333 -0.947306 0.319652 0.151069 -0.935415 0.522408 0.0924358 -0.847671 0.111472 0.809264 -0.576772 0.246613 0.73111 -0.636129 0.248218 0.729975 -0.636808 0.411446 0.600875 -0.685319 0.383702 0.628431 -0.676645 0.649452 0.299006 -0.699147 0.593289 0.370139 -0.714846 0.773702 0.0542504 -0.631223 0.697436 0.0406047 -0.715496 0.706983 0.0650654 -0.704231 0.739765 0.0534554 -0.670738 0.739062 0.0546027 -0.67142 0.706741 0.151819 -0.690991 0.14187 0.94937 -0.280304 0.273148 0.888892 -0.36778 0.29296 0.876598 -0.381773 0.396533 0.802831 -0.445224 0.431955 0.770737 -0.468379 0.511285 0.690704 -0.511387 0.610288 0.553276 -0.566952 0.72829 0.33744 -0.596429 0.764577 0.19494 -0.614346 0.698112 0.00796283 -0.715944 0.738221 0.0147857 -0.674397 0.502205 0.100134 -0.858932 0.559611 0.248515 -0.790618 0.371537 0.402259 -0.836748 0.282584 0.455648 -0.844116 -0.360632 0.701099 -0.615147 0.171849 0.651384 -0.739031 0.374396 0.54371 -0.751137 -0.653174 0.748726 0.113016 0.0269058 0.896081 -0.443074 0.146659 0.947552 -0.283964 -0.012574 0.985629 -0.168455 0.698135 0 -0.715967 0.579089 0.332654 -0.74431 0.524654 0 -0.851315 0.323363 0 -0.946275 0.206177 0.33263 -0.920244 0.1086 0 -0.994086 0.217063 0.119378 -0.968831 0.627566 0.154983 -0.762981 0.624907 0.121612 -0.771169 0.620609 0.111014 -0.776222 0.618683 0.051147 -0.783974 0.613444 0.0447935 -0.788467 0.196115 0.103334 -0.975121 0.227933 0.239673 -0.943718 0.216781 0.289677 -0.932252 0.229532 0.326513 -0.916899 0.221481 0.395127 -0.891527 0.698002 0.0737985 -0.712283 0.620206 0.139508 -0.771934 0.53166 0.216143 -0.818914 0.329224 0.34769 -0.877908 0.223327 0.399001 -0.889339 0.111264 0.456043 -0.882975 0.727475 0.133158 -0.673089 0.731875 0.199183 -0.651679 0.739374 0.195079 -0.644414 0.356589 0.40446 -0.842173 0.303831 0.471011 -0.828152 0.374744 0.550733 -0.745829 0.327737 0.631257 -0.702925 0.392945 0.67293 -0.626706 0.357044 0.750747 -0.555786 0.08893 0.914793 -0.394012 0.163887 0.849084 -0.502193 0.074133 0.791256 -0.606974 0.158957 0.713621 -0.682259 0.082635 0.628751 -0.773203 0.173138 0.524382 -0.833695 0.134371 0.502809 -0.85389 0.672559 0.139363 -0.726803 0.713878 0.10764 -0.691948 0.564467 0.286884 -0.773999 0.585607 0.250662 -0.770865 0.55265 0.400635 -0.7308 0.614404 0.439861 -0.655004 0.611876 0.448278 -0.651656 0.617043 0.555438 -0.557447 0.41696 0.768316 -0.485628 0.391981 0.830605 -0.395533 0.171833 0.939273 -0.297052 0.112098 0.979292 -0.168589 0.716632 0.194939 -0.669655 0.716637 0.19491 -0.669658 0.607695 0.555197 -0.567858 0.607688 0.555211 -0.567852 0.406194 0.831225 -0.379567 0.406194 0.831225 -0.379567 0.275367 0.926262 -0.257315 0.142596 0.98075 -0.133403 0.137905 0.982027 -0.128865 0.606321 0.555236 -0.569288 0.432794 0.900435 0.0436656 0.473347 0.823718 0.312139 0.727823 0.197748 -0.656635 0.714013 0.178455 -0.677008 0.698976 0.195088 -0.688021 0.761216 0.182443 -0.622306 0.753915 0.204969 -0.62418 0.753377 0.539239 -0.376357 0.566561 0.811531 -0.142921 0.548093 0.834312 -0.0593114 0.635131 0.771961 0.0261865 0.29633 0.849544 0.436422 0.317497 0.847091 0.426185 0.215169 0.815511 0.537256 0.139355 0.80806 0.57238 0.0507759 0.751908 0.65731 0.171307 0.892345 0.417581 0.000231576 0.90066 0.434524 0.323723 0.908995 0.262548 0.175177 0.941786 0.286969 0.391028 0.90906 0.143899 0.494621 0.833745 0.245395 0.625623 0.776829 0.0716414 0.792358 0.455794 -0.405488 0.667973 0.515065 -0.53714 0.611726 0.582559 -0.535179 0.619666 0.581083 -0.527596 0.419564 0.823434 -0.381999 0.405278 0.831251 -0.380489 0.314934 0.92602 -0.208094 0.320626 0.92334 -0.211288 0.129448 0.986984 -0.095428 0.166137 0.980929 -0.100882 0.0248851 0.995888 0.0871105 0.720662 0.686475 -0.0969439 0.738767 0.600297 -0.306376 0.692496 0.657771 -0.296289 0.609746 0.695543 -0.38004 0.461606 0.852995 -0.243555 0.547216 0.796823 -0.25618 0.311903 0.94731 -0.0729457 0.430414 0.897882 -0.0924746 0.150339 0.984236 0.0931528 0.298332 0.951881 0.0701493 -0.00850192 0.970108 0.242524 0.161967 0.961762 0.220865 0.59693 0.115694 -0.793907 0.405427 0.487135 -0.773517 0.653283 0.0678348 -0.754069 0.305198 0.514956 -0.801046 -0.286193 0.929046 -0.234451 0.269162 0.683235 -0.678779 0.343753 0.708844 -0.615933 0.301452 0.770045 -0.562278 0.380738 0.782454 -0.492752 0.0740153 0.937105 -0.341111 0.14917 0.881451 -0.448099 0.0564273 0.864872 -0.498812 0.135548 0.79493 -0.591365 0.0526406 0.749398 -0.660024 0.132279 0.674136 -0.726665 0.640745 0.767258 0.0275868 0.529984 0.844333 -0.0788544 0.663374 0.67058 -0.332051 0.431958 0.901098 0.0378803 0.205901 0.926334 0.315452 0.280655 0.935251 0.215725 0.449564 0.845007 0.289577 0.307482 0.839712 0.447591 0.325204 0.84275 0.428968 0.206629 0.823429 0.52846 0.664158 0.32499 -0.673258 0.615423 0.580473 -0.533204 0.495842 0.834053 0.241862 0.376502 0.917587 0.127591 0.564278 0.811805 -0.150212 0.47201 0.849248 -0.236609 0.580239 0.703935 -0.409633 0.645276 0.573784 -0.504371 0.658735 0.515054 -0.548441 0.693219 0.178496 -0.698274 0.705642 0.207063 -0.677639 0.0459546 0.756675 0.652174 0.141241 0.809213 0.570286 0.0366378 0.881386 0.470973 0.141383 0.925356 0.351748 0.387751 0.775486 -0.498268 0.263607 0.887658 -0.37759 0.165124 0.951008 -0.261378 0.140437 0.960874 -0.238743 -0.0171963 0.997502 -0.0685089 0.0555641 0.996379 -0.0643518 0.743648 0.191239 -0.640636 0.744753 0.199602 -0.63679 0.757353 0.472011 -0.451246 0.741484 0.549277 -0.385352 -0.0718428 0.740647 0.668042 0.708631 0.697371 -0.107311 0.621504 0.780455 0.0679844 0.483038 0.336635 -0.808301 0.434847 0.4221 -0.79545 0.512944 0.449041 -0.731609 0.454286 0.589399 -0.668007 0.588223 0.382031 -0.712774 0.631771 0.381858 -0.674574 0.465102 0.774453 -0.42884 0.625746 0.484513 -0.611302 0.400055 0.881126 -0.252138 0.277695 0.955086 -0.103425 0.282413 0.95302 -0.109522 0.125959 0.989445 0.0716389 0.160029 0.98666 0.0298937 -0.0503224 0.963731 0.262087 0.583821 0.104757 -0.805095 0.153465 0.557832 -0.815642 0.357817 0.556282 -0.750012 0.082275 0.63394 -0.768994 0.600884 0.0921443 -0.794008 0.584131 0.101726 -0.80526 0.460391 0.28317 -0.841341 0.43837 0.299714 -0.847351 0.292438 0.464144 -0.836092 0.0714672 0.574478 -0.815394 0.534799 0.606445 -0.5884 0.362121 0.788529 -0.497081 0.260992 0.898023 -0.354172 0.388619 0.776207 -0.496465 0.334159 0.765941 -0.549248 0.353458 0.509282 -0.784665 0.133338 0.635973 -0.760105 0.0603523 0.720226 -0.69111 0.109655 0.981566 -0.156535 0.149388 0.944179 -0.293613 0.092823 0.93299 -0.347727 0.139924 0.872903 -0.4674 0.142132 0.873684 -0.465269 0.615784 0.134968 -0.776269 0.629475 0.121392 -0.76748 0.437022 0.400941 -0.805145 0.521509 0.345579 -0.78013 0.347147 0.518045 -0.781741 0.191057 0.800446 -0.56814 0.034919 0.812752 -0.581563 0.302995 0.675966 -0.671762 0.349784 0.694882 -0.628323 0.563621 0.452777 -0.690887 0.547012 0.461879 -0.698173 0.71391 0.176593 -0.677604 0.641743 0.258502 -0.722041 0.14846 0.981812 -0.118345 0.479724 0.7897 -0.382412 0.343156 0.898564 -0.273547 0.755669 0.257102 -0.602381 0.623197 0.604015 -0.496781 0.206887 0.965621 -0.1574 0.233951 0.965591 -0.113584 0.233949 0.965591 -0.113584 0.252044 0.965592 -0.0640851 0.252049 0.96559 -0.0640858 0.189276 0.981924 -0.000542931 0.260678 0.965409 -0.00566206 0.438913 0.898529 -0.00125873 0.612783 0.79025 -0.00175735 0.559054 0.704986 -0.43641 0.637741 0.705278 -0.309628 0.637742 0.705277 -0.309628 0.687072 0.705276 -0.174694 0.687071 0.705277 -0.174694 0.710348 0.703805 -0.00800809 0.79641 0.604753 -0.00228506 0.755668 0.257105 -0.602381 0.869225 0.257588 -0.422015 0.869231 0.257569 -0.422014 0.936464 0.25757 -0.238104 0.936461 0.25758 -0.238105 0.966594 0.256298 -0.00277335 0.966594 0.256299 -0.00277351 0.163432 0.972237 0.16747 0.954926 0.152587 0.254624 0.410983 0.893933 0.178819 0.531252 0.753167 0.387957 0.509003 0.757914 0.408023 0.540448 0.810966 0.224164 0.937848 0.139087 0.317957 0.170341 0.867638 0.467106 0.219555 0.883922 0.412889 0.172658 0.926823 0.333448 0.200647 0.968835 0.145254 0.186751 0.761039 0.621243 0.961006 0.194963 0.196105 0.949547 0.258599 0.177449 0.736589 0.594515 0.322472 0.184733 0.760473 0.622539 0.517586 0.641577 0.566113 0.498105 0.641053 0.583903 0.785257 0.423186 0.451979 0.805126 0.493232 0.329385 0.884582 0.431074 0.178017 0.582321 0.788042 0.19973 0.945689 0.132254 0.296952 0.818142 0.326688 0.473201 0.779296 0.31571 0.541318 0.488784 0.482891 0.726572 0.507183 0.487979 0.710382 0.153594 0.583316 0.797591 0.181275 0.593165 0.784407 0.160608 0.475253 0.865066 0.941134 0.0778058 0.328957 0.914565 0.0940994 0.393341 0.906218 0.109575 0.408365 0.741238 0.259996 0.618844 0.772238 0.232907 0.591103 0.47436 0.392564 0.787957 0.498371 0.380416 0.779045 0.175498 0.474838 0.862398 0.169638 0.476996 0.862379 0.907636 0.0669063 0.414391 0.908948 0.0608848 0.412439 0.729311 0.187326 0.658039 0.728419 0.189064 0.658529 0.467496 0.287149 0.836058 0.45718 0.298894 0.837645 0.164452 0.354941 0.920311 0.142946 0.371226 0.917474 0.877573 0.0310277 0.478438 0.896209 -0.0422846 0.441612 0.676451 0.124258 0.725929 0.719944 0.0650006 0.690981 0.508302 0.0924117 0.856206 0.455891 0.126479 0.881003 0.211983 0.081673 0.973855 0.146585 0.126646 0.981057 0.212694 0 0.977119 0.212694 0 0.977119 0.510486 0 0.859886 0.510486 0 0.859886 0.681735 0 0.731599 0.681735 0 0.731599 0.877996 0 0.478668 0.877996 0 0.478668 0.136208 0.675622 0.724557 0.895365 0.0254971 0.444602 0.877435 0.0357448 0.478362 0.708317 0.0644694 0.702945 0.67992 0.0729162 0.729652 0.443927 0.107379 0.889606 0.50841 0.0900983 0.856389 0.142637 0.142902 0.979405 0.210987 0.12642 0.969279 0.874873 0.0798256 0.477729 0.897807 0.0506026 0.437472 0.685836 0.207 0.697697 0.719734 0.181782 0.670028 0.422062 0.31544 0.849918 0.461481 0.296129 0.836267 -0.0702643 0.419568 0.905001 0.156959 0.290925 0.943783 -0.0514161 0.63298 0.772459 0.843983 0.127384 0.521023 0.872903 0.0719659 0.482557 0.656237 0.327689 0.679686 0.702989 0.27634 0.655319 0.396262 0.498563 0.770981 0.456294 0.456168 0.764007 0.172552 0.59145 0.787663 0.130325 0.415015 0.900432 0.801866 0.158516 0.576093 0.825463 0.0941306 0.556552 0.624225 0.420674 0.658314 0.670188 0.352949 0.652897 0.372922 0.643061 0.668881 0.441233 0.58095 0.683966 0.089172 0.789885 0.606738 0.174088 0.743673 0.64548 0.787055 0.258725 0.560005 0.325311 0.897793 0.296885 0.46571 0.778512 0.420753 0.199906 0.948129 0.247161 0.0960305 0.976351 0.19369 0.65207 0.44322 0.61511 0.441649 0.697802 0.563931 0.378418 0.744698 0.549749 0.187722 0.868457 0.45885 0.0866261 0.904834 0.416859 0.462442 0.78917 0.404176 0.622639 0.605161 0.496086 -0.351433 0.935239 -0.0426883 0.803066 0.124086 0.582828 0.792795 0.15096 0.590498 0.156748 0.982029 0.105111 0.156609 0.982062 0.10501 0.362507 0.89972 0.24309 0.362392 0.899788 0.24301 0.507509 0.791591 0.340321 0.58532 0.707117 0.396719 0.660386 0.606454 0.442835 0.802257 0.258792 0.537969 0.80225 0.258817 0.537967 0.895583 0.118878 0.428718 0.873901 0.0461726 0.483907 0.680929 0.193463 -0.706334 0.680174 0.193387 -0.707082 0.906537 0.165715 -0.388238 0.906239 0.165709 -0.388936 0.993971 0.109148 0.0104244 0.993973 0.109173 0.00996267 0.89463 0.0256027 0.446073 0.91938 0.0117715 0.393194 0.600973 0.548172 -0.58167 0.598832 0.548191 -0.583855 0.837142 0.469115 -0.281292 0.836221 0.469566 -0.283272 0.947687 0.30881 0.0807764 0.947634 0.309283 0.0795879 0.902967 0.105138 0.416649 0.916553 0.047965 0.397026 0.453247 0.818421 -0.353207 0.449961 0.818823 -0.35646 0.709484 0.699469 -0.0858823 0.707887 0.700754 -0.0885404 0.862866 0.460137 0.209133 0.862579 0.461331 0.207679 0.864876 0.113302 0.489032 0.877723 0.150475 0.454929 0.260233 0.963935 -0.0557579 0.256213 0.964794 -0.0593864 0.454725 0.885754 0.0930867 0.537596 0.825993 0.169486 0.663455 0.699283 0.266142 0.748759 0.544246 0.37836 0.833697 0.258343 0.488065 0.822739 0.351569 0.446654 0.692411 -0.000244395 -0.721503 0.92089 -2.19406e-06 0.389822 0.919448 4.61568e-05 0.393212 0.999993 -5.93141e-05 0.00372499 0.999951 3.06516e-05 0.00993989 0.917416 -4.58362e-05 -0.397929 0.918911 8.48572e-06 -0.394464 0.687446 -2.63222e-05 -0.726236 0.693239 0.00015529 -0.720708 0.919941 -0.0454082 0.389418 0.918215 -0.0439572 0.393635 0.899241 -0.130078 0.417666 0.550129 -0.668048 -0.501068 0.912949 -0.0985485 -0.395995 0.914796 -0.0991606 -0.391555 0.889612 -0.288599 -0.353979 0.889922 -0.288595 -0.353202 0.687773 -0.11555 -0.716671 0.689114 -0.11585 -0.715332 0.659596 -0.338091 -0.671288 0.660323 -0.338207 -0.670515 0.603843 -0.543611 -0.582975 0.602576 -0.543511 -0.584378 0.841151 -0.463601 -0.278458 0.840644 -0.463784 -0.279683 0.949023 -0.303657 0.0845411 0.981329 -0.188867 0.0363582 0.789851 -0.216857 -0.573679 0.997811 -0.0660239 0.0037136 0.896456 -0.121431 0.426171 0.66006 -0.616778 -0.428842 0.901153 -0.409506 0.142225 0.770657 -0.613214 -0.173366 0.772877 -0.611763 -0.168545 0.406717 -0.728166 -0.551684 0.510455 -0.746658 -0.426542 0.882376 -0.437529 0.173149 0.462293 -0.846846 -0.262939 0.523658 -0.811438 -0.259521 0.424734 -0.80351 -0.417099 0.407549 -0.824351 -0.392872 0.674885 -0.719591 -0.163456 0.598516 -0.777159 -0.194431 0.581772 -0.758835 -0.292765 0.978759 -0.182355 -0.0936899 0.999206 0.0389507 0.00836238 0.639337 -0.184574 -0.746445 0.637395 -0.476007 -0.605925 0.739657 -0.276583 -0.613522 0.820092 -0.179232 -0.543438 0.916302 -0.182818 -0.356325 0.767669 -0.518152 -0.377098 0.958468 -0.159526 -0.23641 0.46476 -0.809947 -0.357749 0.206403 -0.948663 -0.23966 0.3051 -0.928644 -0.211031 0.214354 -0.963887 -0.158033 0.153078 -0.975664 -0.156995 0.14547 -0.978405 -0.146839 0.30031 -0.869148 -0.392931 0.67366 -0.721927 -0.158125 0.726436 -0.680659 -0.0948411 0.867836 -0.492083 0.0686654 0.85498 -0.516926 0.0423888 0.900143 -0.128743 0.416134 0.91476 -0.180743 0.361313 0.964802 -0.10587 0.240726 0.951933 0.00191183 0.306299 0.973317 -0.221987 0.0581071 0.890344 -0.454816 -0.0207202 0.766792 -0.621606 -0.160112 0.851113 -0.513201 -0.110593 0.812852 -0.474022 -0.338488 0.77853 -0.528064 -0.339176 0.62025 -0.516853 -0.590045 0.609115 -0.536226 -0.584329 0.113437 -0.980785 -0.158722 0.571261 -0.195095 -0.797245 0.571682 -0.185311 -0.799274 0.484891 -0.555558 -0.675452 0.48854 -0.543269 -0.682779 0.323713 -0.831452 -0.45155 0.325475 -0.829076 -0.454641 0.112733 -0.980978 -0.158027 0.117082 -0.978982 -0.166989 0.165146 -0.980753 -0.104166 0.470209 -0.831228 -0.296585 0.703443 -0.555248 -0.443697 0.829579 -0.194941 -0.523257 0.829582 -0.194917 -0.523259 0.782739 -0.194918 -0.591038 0.782741 -0.194909 -0.591039 0.741984 -0.19502 -0.641426 0.681429 0.403245 -0.610777 0.714382 -0.195071 -0.672016 0.67285 -0.194936 -0.713633 0.672849 -0.194946 -0.713632 0.610582 -0.194948 -0.767584 0.610583 -0.194936 -0.767586 0.703462 -0.555214 -0.44371 0.663741 -0.555214 -0.501184 0.663728 -0.55524 -0.501173 0.619324 -0.555239 -0.555111 0.619334 -0.555218 -0.55512 0.570558 -0.555219 -0.605141 0.570559 -0.555217 -0.605142 0.517759 -0.555216 -0.650893 0.517753 -0.555229 -0.650886 0.470181 -0.831251 -0.296567 0.443634 -0.831249 -0.334983 0.443644 -0.831241 -0.334991 0.413963 -0.831241 -0.371043 0.413959 -0.831244 -0.37104 0.381358 -0.831245 -0.404473 0.381349 -0.831253 -0.404463 0.346058 -0.831254 -0.435042 0.346076 -0.831233 -0.435066 0.165149 -0.980752 -0.104168 0.155823 -0.980752 -0.11766 0.155823 -0.980752 -0.11766 0.145398 -0.980752 -0.130323 0.145397 -0.980753 -0.130322 0.133947 -0.980753 -0.142065 0.133954 -0.980751 -0.142073 0.121557 -0.980751 -0.152814 0.121548 -0.980754 -0.152802 0.149512 -0.980025 -0.131135 0.662457 -0.552247 -0.506136 0.780005 -0.193497 -0.595106 0.443696 -0.829161 -0.340038 0.0755553 -0.995601 -0.0554032 0.157938 -0.966054 -0.20444 0.0903362 -0.985814 -0.141455 0.0837091 -0.976112 -0.200493 0.434139 -0.838112 -0.330291 0.332969 -0.838129 -0.432055 0.329593 -0.842494 -0.426114 0.206852 -0.842511 -0.49738 0.205286 -0.84638 -0.491425 0.0218107 -0.995862 -0.0882236 0.0252199 -0.96903 -0.24565 0.0748657 -0.846709 -0.526763 0.0770747 -0.811072 -0.579847 0.100322 -0.642366 -0.759804 0.659947 -0.557874 -0.503236 0.506458 -0.55783 -0.657515 0.502905 -0.569538 -0.650164 0.315458 -0.569556 -0.759007 0.314008 -0.58 -0.751664 0.112009 -0.580371 -0.806612 0.115123 -0.483995 -0.867465 0.778895 -0.205503 -0.59253 0.597053 -0.205511 -0.775431 0.596186 -0.224825 -0.770725 0.373827 -0.224823 -0.899838 0.374015 -0.242042 -0.895281 0.126702 -0.242049 -0.961956 0.127731 -0.255656 -0.958293 -0.000932328 -0.645623 -0.763656 0 -0.735217 -0.677832 0 -0.487234 -0.873272 -0.00037575 -0.323518 -0.946222 0 -0.257768 -0.966207 0 -0.813491 -0.581577 0 -0.969339 -0.245728 0 -0.969339 -0.245728 0 0.97799 -0.208653 0 0.97799 -0.208653 0 0.807668 -0.589638 0 0.807668 -0.589638 0 0.496722 -0.86791 0 0.496722 -0.86791 0 0.0992382 -0.995064 0 0.0992382 -0.995064 0.781073 0.185808 -0.596155 0.786767 0.158706 -0.596498 0.717469 0.4322 -0.546298 0.671739 0.529281 -0.518295 0.071184 0.995154 -0.0678316 0.2117 0.965598 -0.15101 0.443208 0.827726 -0.344146 0.486845 0.790798 -0.370973 0.633845 0.605486 -0.481276 0.603048 0.158694 -0.781761 0.607944 0.132002 -0.78293 0.518421 0.528839 -0.671989 0.526551 0.512227 -0.678504 0.343141 0.827327 -0.444731 0.34973 0.821145 -0.451009 0.138536 0.973966 -0.179441 0.0846706 0.983563 -0.159481 0.0798179 0.805091 -0.587756 0.075679 0.815434 -0.573881 0.115413 0.493403 -0.86211 0.11461 0.497136 -0.86007 0.131149 0.098381 -0.986469 0.129892 0.107949 -0.985635 0.381 0.131996 -0.915105 0.384756 0.107951 -0.916684 0.330152 0.512191 -0.792881 0.335609 0.497091 -0.800167 0.21944 0.821104 -0.52691 0.223686 0.815469 -0.53383 0.103569 0.96316 -0.248188 0.0108294 0.99513 -0.097973 0.0432495 0.977075 -0.208457 0.769368 0.43512 -0.4677 0.520288 0.793262 -0.316283 0.221238 0.965902 -0.13449 0.680283 0.608653 -0.408358 0.840661 0.187345 -0.508126 0.22124 0.965901 -0.134492 0.213697 0.965901 -0.146181 0.21369 0.965903 -0.146176 0.205431 0.965902 -0.15758 0.205434 0.965901 -0.157582 0.196452 0.965901 -0.168646 0.196448 0.965902 -0.168643 0.186872 0.965902 -0.179197 0.186878 0.9659 -0.179202 0.176735 0.9659 -0.189213 0.176729 0.965902 -0.189207 0.162109 0.965853 -0.20211 0.162116 0.96585 -0.202118 0.381168 0.793016 -0.475222 0.604321 0.706992 -0.367367 0.583718 0.706991 -0.399295 0.583734 0.706972 -0.399305 0.561167 0.706966 -0.430453 0.561158 0.706978 -0.430447 0.536624 0.706978 -0.460671 0.536627 0.706974 -0.460673 0.510467 0.706975 -0.4895 0.510467 0.706975 -0.4895 0.482761 0.706974 -0.516846 0.482766 0.706967 -0.51685 0.441721 0.706667 -0.552725 0.496576 0.608372 -0.619109 0.825401 0.258745 -0.501761 0.797261 0.258744 -0.545369 0.797265 0.258724 -0.545371 0.766437 0.25872 -0.58791 0.766437 0.258722 -0.58791 0.732928 0.258722 -0.62919 0.732927 0.258727 -0.629189 0.697199 0.258727 -0.668561 0.697198 0.258732 -0.668561 0.659356 0.258733 -0.705908 0.659357 0.258727 -0.705909 0.604412 0.258542 -0.753553 0.604418 0.258512 -0.753559 0.116436 0.979175 -0.166308 0.15024 0.965922 -0.210769 0.128533 0.972828 -0.192577 0.359037 0.793352 -0.491615 0.325069 0.829455 -0.45424 0.461152 0.608799 -0.645526 0.491924 0.543565 -0.680109 0.5564 0.258763 -0.789595 0.571666 0.185437 -0.799257 0.407309 0.824718 -0.392351 0.451156 0.836696 -0.310481 0.438588 0.8395 -0.320751 0.673579 0.721989 -0.158188 0.726191 0.680892 -0.0950448 0.905381 0.402724 0.134531 0.178864 0.971309 -0.156739 0.254025 0.951554 -0.173251 0.58183 0.758897 -0.292489 0.908674 0.219079 -0.355411 0.880648 0.324993 -0.34473 0.848027 0.180939 -0.498108 0.716829 0.170669 -0.676038 0.714204 0.18202 -0.675856 0.825865 0.560263 -0.0636628 0.990206 0.0923053 -0.104742 0.944821 0.0555888 -0.322837 0.523543 0.811611 -0.25921 0.424689 0.803669 -0.41684 0.204229 0.957518 -0.203592 0.13256 0.978996 -0.1549 0.955079 0.108347 0.275837 0.999309 0.0074383 0.0364247 0.984352 0.176172 -0.00386142 0.961557 0.272417 -0.0346015 0.851981 0.51482 -0.0953383 0.813071 0.473987 -0.338011 0.778622 0.528218 -0.338724 0.620364 0.516989 -0.589806 0.609133 0.536524 -0.584037 0.885239 0.0344486 0.46386 0.908233 0.373826 0.18806 0.935944 0.160176 0.313612 0.931439 0.277883 0.234951 0.862706 0.498488 0.0851352 0.901496 0.423812 -0.0876836 0.67477 0.719723 -0.163354 0.598454 0.777214 -0.194399 0.292572 0.927152 -0.234076 0.311922 0.921965 -0.229533 0.918951 0.188695 0.346299 0.920002 0.0449829 0.389323 0.773454 0.610583 -0.17017 0.770341 0.613476 -0.173842 0.841044 0.463405 -0.279108 0.840336 0.46405 -0.280168 0.528683 0.71585 -0.456128 0.299643 0.757183 -0.58042 0.797741 0.488552 -0.35345 0.587121 0.579982 -0.564721 0.658922 0.338118 -0.671936 0.659809 0.337852 -0.671199 0.889351 0.288686 -0.354563 0.889753 0.28836 -0.353819 0.981348 0.188833 0.0360266 0.949031 0.303732 0.0841829 0.662123 0.615974 -0.426813 0.901373 0.409232 0.141621 0.867022 0.0609397 0.49453 0.895056 0.125857 0.427826 0.918168 0.0442723 0.393709 0.78812 0.216778 -0.576086 0.997856 0.0653553 0.00334701 0.914668 0.0972288 -0.392337 0.912698 0.0984278 -0.396604 0.688558 0.114278 -0.716121 0.687171 0.114652 -0.717392 0.692412 -2.38194e-05 -0.721503 0.691734 -0.000116271 -0.722153 0.692808 -4.87782e-05 -0.721122 0.917153 -5.96013e-05 -0.398535 0.917416 -4.33461e-05 -0.397929 0.999994 -3.94311e-05 0.00335914 0.999993 -3.04166e-05 0.00372499 0.920933 -1.41958e-05 0.389721 0.92089 -1.17073e-05 0.389822 0.919941 -0.0454061 0.389418 0.918227 -0.0439651 0.393607 0.899244 -0.130077 0.417661 0.550078 -0.668156 -0.500982 0.912949 -0.0985461 -0.395995 0.914805 -0.0991613 -0.391534 0.889621 -0.28859 -0.353963 0.889915 -0.288587 -0.353226 0.687773 -0.115552 -0.71667 0.689115 -0.115852 -0.715332 0.659601 -0.338074 -0.671292 0.660371 -0.338198 -0.670472 0.603851 -0.5436 -0.582978 0.60262 -0.543502 -0.584342 0.841155 -0.463597 -0.278455 0.840638 -0.463783 -0.279701 0.949025 -0.303653 0.0845362 0.981331 -0.18886 0.0363535 0.78986 -0.216853 -0.573669 0.997811 -0.0660253 0.00371386 0.896465 -0.12145 0.426147 0.660117 -0.616752 -0.428793 0.901158 -0.409489 0.14224 0.770667 -0.613201 -0.173366 0.772885 -0.611751 -0.16855 0.406594 -0.728161 -0.551781 0.510399 -0.746742 -0.426461 0.882384 -0.437509 0.173159 0.462256 -0.846858 -0.262967 0.52355 -0.81151 -0.259511 0.424653 -0.803578 -0.417052 0.407367 -0.824535 -0.392676 0.674863 -0.719605 -0.163489 0.598459 -0.777191 -0.194476 0.581718 -0.758867 -0.292787 0.978747 -0.182406 -0.093715 0.999207 0.0389326 0.00836646 0.639333 -0.184616 -0.746438 0.637417 -0.475968 -0.605932 0.739642 -0.276609 -0.613528 0.820095 -0.179243 -0.54343 0.916298 -0.182831 -0.356329 0.767663 -0.518149 -0.377113 0.958457 -0.159568 -0.236427 0.46476 -0.809947 -0.357749 0.20636 -0.948663 -0.239697 0.305021 -0.928662 -0.211068 0.214128 -0.963946 -0.15798 0.152992 -0.975684 -0.156953 0.145179 -0.978496 -0.146521 0.30024 -0.86915 -0.392981 0.673639 -0.721937 -0.158166 0.726443 -0.68065 -0.0948499 0.86784 -0.492078 0.0686556 0.854987 -0.516914 0.0423856 0.900141 -0.128749 0.416136 0.914762 -0.180764 0.361297 0.964801 -0.105887 0.24072 0.95194 0.00186199 0.306279 0.973315 -0.221995 0.0580983 0.890347 -0.45481 -0.0207312 0.766776 -0.621617 -0.160145 0.851107 -0.513205 -0.110619 0.812853 -0.474013 -0.3385 0.778492 -0.528111 -0.33919 0.620236 -0.516903 -0.590016 0.609024 -0.536405 -0.58426 0.11328 -0.980784 -0.158842 0.570821 -0.195086 -0.797562 0.571189 -0.185352 -0.799617 0.484555 -0.55558 -0.675676 0.488078 -0.543449 -0.682967 0.323472 -0.831454 -0.451718 0.325081 -0.829257 -0.454593 0.112866 -0.980896 -0.158443 0.11675 -0.979071 -0.1667 0.16829 -0.980748 -0.0990562 0.479153 -0.831186 -0.282032 0.716783 -0.555176 -0.421903 0.845263 -0.194928 -0.497527 0.845267 -0.194903 -0.49753 0.816317 -0.19509 -0.54366 0.771826 0.31091 -0.554634 0.680528 0.18809 -0.708169 0.790733 -0.19497 -0.580283 0.754549 -0.195032 -0.626592 0.657731 0.49225 -0.570159 0.725229 -0.195064 -0.660297 0.684394 -0.194964 -0.702562 0.651672 -0.195117 -0.732976 0.612448 -0.194928 -0.766101 0.612451 -0.194895 -0.766107 0.716778 -0.555184 -0.4219 0.675424 -0.555183 -0.485359 0.675427 -0.555178 -0.485362 0.628471 -0.555178 -0.544795 0.628472 -0.555177 -0.544795 0.576302 -0.555179 -0.59971 0.576311 -0.555159 -0.59972 0.519363 -0.555158 -0.649663 0.51935 -0.555189 -0.649647 0.47914 -0.831197 -0.282024 0.451495 -0.831197 -0.324444 0.451492 -0.8312 -0.324442 0.420104 -0.831199 -0.364171 0.4201 -0.831203 -0.364166 0.385228 -0.831204 -0.400875 0.385235 -0.831197 -0.400882 0.347168 -0.831196 -0.434267 0.347169 -0.831195 -0.434269 0.168299 -0.980746 -0.099062 0.158589 -0.980746 -0.113962 0.158582 -0.980747 -0.113957 0.147558 -0.980747 -0.127911 0.147562 -0.980746 -0.127915 0.135313 -0.980746 -0.140809 0.135313 -0.980746 -0.140809 0.121942 -0.980746 -0.152535 0.121941 -0.980747 -0.152533 0.78885 -0.279384 -0.547412 0.80003 -0.193517 -0.567894 0.654864 -0.602637 -0.45605 0.679963 -0.552296 -0.482305 0.426198 -0.854761 -0.296208 0.455759 -0.829241 -0.323487 0.604674 -0.368708 -0.705992 0.61649 -0.279393 -0.736125 0.491095 -0.655495 -0.573717 0.513025 -0.602608 -0.611285 0.315533 -0.874307 -0.368817 0.334114 -0.85481 -0.397073 0.382108 -0.446739 -0.808961 0.388917 -0.368569 -0.844334 0.304639 -0.700576 -0.645282 0.316592 -0.655353 -0.685771 0.193848 -0.89091 -0.410735 0.203958 -0.874256 -0.440542 0.106594 -0.967818 -0.227962 0.0607058 -0.995746 -0.0693218 0.0946443 -0.988194 -0.120477 0.164355 -0.979858 -0.113427 0.161815 -0.980535 -0.111209 0.129556 -0.549505 -0.825384 0.124444 -0.446024 -0.886328 0.103284 -0.768157 -0.631876 0.105184 -0.70033 -0.706027 0.0725322 -0.879207 -0.470887 0.0706999 -0.891003 -0.44846 0.0260284 -0.980387 -0.195358 0.0174757 -0.99735 -0.0706254 0 -0.554176 -0.8324 0 -0.554176 -0.8324 0 -0.772287 -0.635273 -0.000324275 -0.830921 -0.556391 0 -0.881529 -0.47213 0 -0.980719 -0.195424 0 -0.980719 -0.195424 0 -0.98072 0.195418 -0.000645529 -0.881529 0.47213 0 -0.830911 0.556406 0 -0.98072 0.195418 0 -0.772262 0.635304 0 -0.554176 0.8324 0 -0.554176 0.8324 0.0815416 -0.987587 0.134249 0.80565 -0.185985 0.562439 0.783508 -0.279703 0.55487 0.73777 -0.432443 0.518352 0.65096 -0.603019 0.461105 0.144636 -0.984237 0.101779 0.217058 -0.965623 0.14303 0.421208 -0.855189 0.302053 0.501115 -0.791072 0.350841 0.649536 -0.605556 0.459788 0.12598 -0.981348 0.145208 0.114947 -0.984253 0.13429 0.312369 -0.874529 0.370979 0.336594 -0.855012 0.394537 0.485849 -0.655912 0.577694 0.517503 -0.602971 0.607138 0.598137 -0.369093 0.711339 0.622472 -0.279668 0.730968 0.394914 -0.368882 0.841409 0.375578 -0.447112 0.811808 0.321094 -0.655679 0.683362 0.299503 -0.700981 0.647243 0.206521 -0.874435 0.43899 0.190795 -0.891086 0.41178 0.100788 -0.971334 0.215294 0.059154 -0.988189 0.141365 0.0296171 -0.98029 0.195332 0.0187321 -0.987941 0.153691 0.0746775 -0.879067 0.470812 0.0694404 -0.890919 0.448822 0.0950382 -0.768766 0.632429 0.110161 -0.700723 0.704878 0.120366 -0.550147 0.826348 0.13618 -0.446714 0.884252 0.783936 -0.435116 0.442853 0.530157 -0.793246 0.299491 0.225434 -0.965899 0.12735 0.692903 -0.608686 0.386506 0.856452 -0.187294 0.481051 0.225437 -0.965898 0.127352 0.21802 -0.965898 0.139669 0.218019 -0.965899 0.139668 0.209609 -0.965895 0.152024 0.209607 -0.965895 0.152023 0.200126 -0.965895 0.164304 0.200118 -0.965898 0.164299 0.189919 -0.965898 0.17599 0.189924 -0.965896 0.175995 0.179042 -0.965896 0.187054 0.17904 -0.965896 0.187052 0.168245 -0.965903 0.196784 0.16825 -0.965901 0.19679 0.157722 -0.965901 0.205325 0.157721 -0.965902 0.205323 0.370926 -0.79325 0.482876 0.615779 -0.706972 0.34786 0.595521 -0.706972 0.381504 0.595514 -0.706979 0.381501 0.572527 -0.706957 0.415241 0.572535 -0.706948 0.415245 0.546636 -0.706948 0.448792 0.546645 -0.706936 0.448799 0.518783 -0.706936 0.480734 0.51877 -0.706953 0.480723 0.489046 -0.706954 0.510931 0.489061 -0.706933 0.510945 0.459596 -0.706971 0.537553 0.459583 -0.706989 0.53754 0.429022 -0.706957 0.562273 0.48335 -0.608639 0.629231 0.841037 -0.258706 0.475109 0.813367 -0.258706 0.521062 0.813369 -0.258697 0.521063 0.781951 -0.258682 0.56713 0.781945 -0.258706 0.567127 0.746575 -0.258706 0.612942 0.746573 -0.258715 0.612941 0.70852 -0.258715 0.656556 0.708523 -0.258703 0.656558 0.667928 -0.258703 0.697815 0.667917 -0.258751 0.697807 0.627705 -0.258777 0.73418 0.627711 -0.25875 0.734185 0.588431 -0.25875 0.766027 0.588431 -0.258748 0.766028 0.116744 -0.979074 0.166691 0.150343 -0.965921 0.210696 0.128746 -0.972864 0.192249 0.358957 -0.79335 0.491677 0.325386 -0.829241 0.454405 0.461369 -0.608758 0.645409 0.492026 -0.54343 0.680143 0.556854 -0.258806 0.789261 0.571922 -0.185352 0.799093 0.407483 -0.824509 0.39261 0.451439 -0.836575 0.310395 0.439075 -0.839341 0.320499 0.673749 -0.721852 0.158089 0.726435 -0.68066 0.0948392 0.905453 -0.402521 -0.13465 0.179022 -0.97125 0.156925 0.254407 -0.95141 0.173484 0.581967 -0.758751 0.292596 0.881057 -0.330031 0.338849 0.847994 -0.180881 0.498185 0.716836 -0.170591 0.676051 0.714211 -0.18194 0.67587 0.902493 -0.244007 0.354918 0.921001 -0.227188 0.316452 0.993948 -0.0138325 0.108975 0.823284 -0.564098 0.0632239 0.523691 -0.811476 0.259333 0.424809 -0.803514 0.417016 0.204516 -0.957375 0.203974 0.132852 -0.978894 0.155295 0.954109 -0.130711 -0.269426 0.997224 0.0543487 -0.0508926 0.984356 -0.176151 0.00385458 0.961562 -0.272401 0.0345956 0.852033 -0.514737 0.0953174 0.813106 -0.473891 0.338063 0.778673 -0.528107 0.338781 0.6204 -0.516854 0.589886 0.609173 -0.536387 0.584121 0.885236 -0.0344667 -0.463863 0.908247 -0.373784 -0.188077 0.935942 -0.160033 -0.313691 0.931442 -0.277886 -0.234936 0.862779 -0.498346 -0.0852227 0.901579 -0.423643 0.08765 0.674954 -0.719559 0.163317 0.598615 -0.777097 0.194374 0.293097 -0.926997 0.23403 0.312118 -0.921891 0.229564 0.918935 -0.188578 -0.346405 0.91995 -0.0449505 -0.389449 0.773671 -0.610377 0.169922 0.770645 -0.613193 0.173496 0.841295 -0.463202 0.278689 0.840616 -0.46382 0.279707 0.529134 -0.715714 0.455819 0.298998 -0.757233 0.580688 0.799006 -0.487879 0.351517 0.587686 -0.580013 0.564101 0.65957 -0.33803 0.671344 0.660425 -0.337773 0.670632 0.889621 -0.288536 0.354008 0.889998 -0.28823 0.353308 0.981359 -0.188715 -0.0363438 0.949069 -0.303536 -0.0844585 0.662244 -0.615889 0.426747 0.901433 -0.409051 -0.141762 0.867033 -0.0609487 -0.494509 0.895034 -0.125767 -0.427898 0.918128 -0.0442442 -0.393807 0.788233 -0.21676 0.575938 0.997857 -0.0653288 -0.00371406 0.91492 -0.0972115 0.391754 0.912962 -0.0984044 0.396001 0.689191 -0.114289 0.715509 0.68788 -0.114644 0.716714 0.691734 -0.000116271 0.722153 0.920933 -1.11329e-05 -0.389721 0.92088 -1.41897e-05 -0.389846 0.999994 -3.04297e-05 -0.00335914 0.999993 -3.94245e-05 -0.00372499 0.917153 -4.33466e-05 0.398535 0.917416 -5.96119e-05 0.397929 0.692808 -4.87782e-05 0.721122 0.692446 -2.59707e-05 0.72147 0.919983 0.0454376 -0.389315 0.918248 0.0439783 -0.393557 0.899258 0.130147 -0.417608 0.549586 0.668178 0.501492 0.912685 0.0985695 0.396599 0.914553 0.0991889 0.392115 0.889355 0.288727 0.35452 0.889677 0.288723 0.353715 0.687099 0.115551 0.717317 0.688447 0.115852 0.715974 0.658922 0.338157 0.671916 0.659723 0.338285 0.671066 0.60331 0.543736 0.58341 0.60196 0.543628 0.584904 0.840915 0.463799 0.278841 0.84037 0.463995 0.280156 0.948988 0.303847 -0.0842542 0.98132 0.188978 -0.0360344 0.789801 0.216861 0.573747 0.997811 0.0660523 -0.0033468 0.896473 0.121496 -0.426116 0.659997 0.616837 0.428854 0.901097 0.409673 -0.142102 0.770392 0.613453 0.1737 0.772659 0.611973 0.168782 0.406208 0.728226 0.55198 0.510018 0.746791 0.426832 0.882314 0.437699 -0.173035 0.461924 0.847019 0.263032 0.523396 0.811651 0.259383 0.424532 0.803738 0.416867 0.407208 0.82473 0.392432 0.674671 0.719775 0.163532 0.598307 0.777302 0.1945 0.581589 0.759007 0.292684 0.978746 0.182413 0.0937135 0.999215 -0.0387352 -0.00828634 0.639319 0.184699 0.74643 0.637431 0.475992 0.605899 0.775566 0.175999 0.606236 0.916294 0.182869 0.35632 0.767674 0.518157 0.377082 0.958451 0.159587 0.236441 0.464273 0.81013 0.357965 0.205886 0.948758 0.239729 0.304883 0.928725 0.210987 0.213738 0.964072 0.157738 0.152814 0.97575 0.156714 0.144881 0.978601 0.146118 0.299712 0.869228 0.393211 0.673462 0.72208 0.158271 0.726198 0.680883 0.095055 0.867765 0.492222 -0.0685677 0.854907 0.517054 -0.0422963 0.900146 0.128832 -0.4161 0.914757 0.180825 -0.361278 0.964811 0.105933 -0.240662 0.951927 -0.00198648 -0.30632 0.97331 0.222021 -0.0580826 0.890266 0.454966 0.0207964 0.76677 0.621628 0.160133 0.851038 0.513315 0.110644 0.812794 0.474149 0.338449 0.778454 0.528202 0.339134 0.620208 0.517023 0.58994 0.608985 0.536542 0.584175 0.150235 0.965924 0.210761 0.561914 0.258782 0.785674 0.563959 0.185435 0.804713 0.467456 0.608761 0.641011 0.487817 0.543585 0.683045 0.354181 0.793345 0.495135 0.32826 0.829436 0.451975 0.128531 0.972829 0.192572 0.116436 0.979175 0.166308 0.381167 0.793017 0.475221 0.839373 0.187333 0.510255 0.678015 0.608617 0.412166 0.769384 0.435082 0.467709 0.221238 0.965902 0.13449 0.520288 0.793262 0.316284 0.826339 0.258731 0.500223 0.797261 0.258744 0.545368 0.797265 0.258725 0.545372 0.766437 0.25872 0.58791 0.766437 0.258722 0.58791 0.732928 0.258722 0.62919 0.732927 0.258728 0.629189 0.697199 0.258727 0.668562 0.6972 0.258717 0.668563 0.659359 0.258716 0.705912 0.659358 0.258726 0.705909 0.604413 0.258542 0.753553 0.604417 0.258514 0.753559 0.605512 0.706954 0.365474 0.583724 0.706985 0.399298 0.583733 0.706972 0.399306 0.561167 0.706966 0.430453 0.561158 0.706978 0.430446 0.536624 0.706978 0.460671 0.536632 0.706966 0.460678 0.510473 0.706967 0.489506 0.510462 0.706983 0.489494 0.482756 0.706983 0.516839 0.482765 0.706968 0.51685 0.442683 0.706697 0.551916 0.494628 0.60838 0.620659 0.221238 0.965902 0.13449 0.213695 0.965902 0.146179 0.21369 0.965903 0.146176 0.205431 0.965902 0.15758 0.205437 0.9659 0.157584 0.196455 0.9659 0.168649 0.196446 0.965903 0.16864 0.18687 0.965903 0.179194 0.186878 0.9659 0.179202 0.176735 0.9659 0.189213 0.176729 0.965902 0.189207 0.162109 0.965853 0.20211 0.16211 0.965853 0.202111 0.784985 0.158747 0.59883 0.482705 0.790284 0.377422 0.446452 0.827447 0.340606 0.633834 0.605505 0.481267 0.671732 0.529294 0.51829 0.717487 0.432158 0.546308 0.782871 0.18588 0.593769 0.605625 0.132053 0.784716 0.605395 0.158731 0.779937 0.524673 0.512361 0.679857 0.520224 0.528996 0.67047 0.348614 0.821227 0.451724 0.34413 0.827409 0.443811 0.162827 0.963898 0.210685 0.0655868 0.997383 0.0304112 0.19893 0.964653 0.172837 0.382291 0.10796 0.917714 0.383501 0.132043 0.914052 0.333629 0.497212 0.80092 0.332114 0.512317 0.79198 0.222525 0.815554 0.534186 0.220532 0.821181 0.526334 0.0888922 0.97294 0.213273 0.0962882 0.984058 0.149524 0.13008 0.098395 0.986609 0.131021 0.107934 0.985487 0.114884 0.493411 0.862176 0.115117 0.497165 0.859985 0.0775914 0.805243 0.587846 0.077781 0.815578 0.573396 0.0263367 0.977649 0.208586 0.0248871 0.994609 0.100662 0 0.0992382 0.995064 0 0.0992382 0.995064 0 0.4967 0.867923 0 0.4967 0.867923 0 0.807678 0.589623 0 0.807678 0.589623 0 0.977989 0.208659 0 0.977989 0.208659 0.147636 0.982779 -0.111129 0.179218 0.982813 -0.0442574 0.181264 0.982917 0.0319086 0.171745 0.982373 0.0738009 0.171779 0.982366 0.0738174 0.505779 0.834831 0.217361 0.505805 0.834811 0.217374 0.770013 0.545499 0.330925 0.770023 0.545481 0.330931 0.902805 0.185473 0.387999 0.90281 0.185437 0.388004 0.981991 0.185459 0.036049 0.981985 0.185489 0.0360471 0.837535 0.545519 0.030711 0.837508 0.545562 0.0307072 0.550128 0.834838 0.020129 0.550066 0.834879 0.0201226 0.51186 0.858865 0.0187176 0.185491 0.982644 -0.001879 0.928945 0.185433 -0.320432 0.928931 0.185501 -0.320431 0.792286 0.545517 -0.273304 0.792162 0.54571 -0.273276 0.520371 0.834857 -0.17952 0.520063 0.835067 -0.179436 0.848014 0.441898 -0.292573 0.167609 0.982918 -0.076026 0.123631 0.983064 -0.135282 0.477872 0.780327 -0.403396 0.420249 0.835195 -0.35474 0.420403 0.835069 -0.354853 0.640265 0.545817 -0.540504 0.640319 0.545717 -0.540541 0.750843 0.185555 -0.63388 0.750846 0.185539 -0.633882 0.155422 0.982327 0.104295 0.815697 0.188533 0.546894 0.815791 0.187415 0.547139 0.815515 0.189505 0.54683 0.694137 0.549065 0.465512 0.692545 0.552068 0.464331 0.455837 0.835898 0.305756 0.451824 0.839118 0.30288 0.155028 0.982413 0.104068 0.152739 0.982947 0.102404 0.148333 0.983525 -0.103323 0.779679 0.188154 -0.597242 0.122549 0.982843 -0.137847 0.121668 0.983086 -0.136892 0.363936 0.836825 -0.408991 0.361383 0.839263 -0.406251 0.555298 0.549753 -0.624032 0.554254 0.552043 -0.622938 0.652963 0.187642 -0.733778 0.652845 0.188479 -0.733668 0.132013 0.983285 -0.125396 0.133732 0.98285 -0.126971 0.396031 0.837763 -0.375915 0.39707 0.836848 -0.376857 0.605523 0.550537 -0.574675 0.60593 0.549711 -0.575036 0.712453 0.187884 -0.6761 0.712515 0.187474 -0.676148 0.141181 0.983506 -0.113067 0.142127 0.983285 -0.113798 0.425665 0.838262 -0.340772 0.426272 0.837766 -0.341235 0.651512 0.550942 -0.521531 0.651725 0.55054 -0.52169 0.720332 -0.385586 -0.57658 0.753838 0.188006 -0.629589 0.153584 0.983258 -0.0980594 0.0975474 0.993081 -0.0653844 0.453662 0.837656 -0.304175 0.452876 0.838263 -0.303674 0.693399 0.550456 -0.464969 0.693127 0.550941 -0.4648 0.81576 0.18781 -0.54705 0.815722 0.18803 -0.54703 0.808206 0.187377 0.558294 0.793318 0.183522 0.580488 0.766541 0.301899 0.566808 0.647674 0.547359 0.530016 0.647744 0.547235 0.530059 0.38541 0.829821 0.403555 0.3855 0.829749 0.403617 0.0751456 0.972498 0.220457 0.075261 0.972469 0.220545 0.173774 0.875431 0.451024 0.846748 0.187976 -0.497677 0.86501 0.0140211 -0.501558 0.73799 0.550106 -0.390837 0.497027 0.836294 -0.231464 0.20113 0.973034 0.11292 0.132726 0.991086 -0.0115265 0.187482 0.981374 -0.0419098 0.215325 0.875902 0.431777 0.169696 0.929359 0.327865 -0.226996 0.863641 0.450108 0.190789 0.95291 0.235714 0.144364 0.979316 0.141771 0.862873 0.19583 -0.465941 0.887587 0.18921 -0.419987 0.885963 0.204191 -0.416385 0.916878 0.185029 -0.353692 0.915662 0.203596 -0.346571 0.941863 0.174468 -0.287151 0.941319 0.193919 -0.276251 0.724859 0.572776 -0.382763 0.780367 0.558299 -0.281655 0.766129 0.583259 -0.269917 0.81861 0.550652 -0.163279 0.804414 0.57526 -0.148306 0.851388 0.522893 -0.0414883 0.838813 0.54384 -0.0251144 0.462752 0.860849 -0.21166 0.530694 0.842995 -0.087883 0.494533 0.866677 -0.065635 0.559502 0.826158 0.0664842 0.52479 0.846584 0.0888295 0.583943 0.780415 0.223524 0.55528 0.795459 0.242713 0.776585 0.174662 0.605318 0.776591 0.17464 0.605316 0.578665 0.511166 0.635497 0.578739 0.511056 0.635518 0.280264 0.77678 0.563972 0.280488 0.776609 0.564097 -0.0497514 0.911644 0.407959 -0.0494617 0.911562 0.408178 0.763267 0.16226 0.625377 -0.16806 0.793101 0.585445 -0.122076 0.847373 0.516775 0.0222423 0.779725 0.625728 0.199675 0.701885 0.683731 0.199678 0.701882 0.683732 0.525595 0.461992 0.714362 0.525595 0.461993 0.714362 0.737665 0.194057 0.646678 0.75445 0.151968 0.638522 0.972672 0.1825 -0.143536 0.0850992 0.847056 0.524648 0.190019 0.849565 0.49207 0.57971 0.76074 0.29191 0.576767 0.762239 0.293824 0.855684 0.516636 0.0298763 0.859894 0.509897 0.0242576 0.956378 0.184578 -0.226434 0.95692 0.16652 -0.237855 0.96467 0.169506 -0.201692 0.963422 0.186624 -0.192329 0.854819 0.518208 0.0272989 0.850888 0.524391 0.0316717 0.569391 0.779447 0.26126 0.572512 0.77775 0.259491 0.28221 0.871485 0.401087 -0.00626545 0.876749 0.480907 0.970838 0.173099 -0.165864 0.973684 0.136949 -0.182165 0.850135 0.525766 0.0289821 0.846478 0.531444 0.0322805 0.562984 0.79511 0.225498 0.565955 0.793399 0.224084 0.335617 0.884532 0.323981 0.0388658 0.915711 0.399953 0.976341 0.175411 -0.126446 0.974407 0.189143 -0.121476 0.845726 0.532833 0.0289234 0.842616 0.537618 0.0310853 0.557315 0.809297 0.185574 0.560232 0.807533 0.184474 0.32377 0.907719 0.266869 0.195632 0.934748 0.296604 0.742501 0.134808 0.65614 0.742495 0.134818 0.656145 0.478883 0.394532 0.784229 0.478896 0.394519 0.784228 0.128699 0.599476 0.789978 0.128661 0.599498 0.789967 -0.22762 0.703554 0.673202 -0.227653 0.703563 0.673182 0.200941 0.787802 0.58223 0.994772 0.0340314 0.0962857 0.203725 0.159791 0.9659 0.206382 0.159551 0.965375 0.952714 0.0508589 0.299581 0.864945 0.0959171 0.492616 0.584303 0.139305 0.79949 0.584901 0.139192 0.799072 0.191904 0.461726 0.866015 0.208634 0.459942 0.863091 0.57383 0.405993 0.711259 0.586027 0.401606 0.703764 0.948063 0.192893 0.25292 0.951714 0.186576 0.243784 0.990735 -0.00675759 -0.135643 0.18878 0.683921 0.704709 -0.213015 0.680669 0.700938 0.564347 0.627372 0.536579 0.583864 0.617671 0.526863 0.940817 0.298136 0.161179 0.867314 0.423873 0.260958 0.99234 0.12277 -0.0137237 0.98288 0.171845 -0.066454 0.978029 0.201603 -0.0530714 0.853328 0.507661 0.11879 0.845459 0.519312 0.124556 0.573034 0.766075 0.291138 0.550595 0.779374 0.299033 0.212506 0.887839 0.408146 0.175066 0.893309 0.413945 0.732874 0.114225 0.670707 -0.295467 0.559547 0.774342 -0.295351 0.559519 0.774407 0.0708489 0.476792 0.876156 0.0709285 0.476754 0.87617 0.440795 0.313808 0.840966 0.440854 0.313764 0.840952 0.704417 0.12973 0.69783 0.727093 0.0992568 0.679326 0.209061 0 0.977903 0.209061 0 0.977903 0.59065 0 0.806928 0.59065 0 0.806928 0.868951 0 0.494897 0.868951 0 0.494897 0.955509 0 0.294962 0.995258 -0.013461 0.0963328 0.996131 0 0.0878839 0.719497 0.075022 0.690432 0.719473 0.075041 0.690454 0.411575 0.219533 0.88454 0.411543 0.21955 0.884551 0.0265702 0.333518 0.942369 0.026433 0.333569 0.942355 -0.347278 0.391412 0.852171 -0.347479 0.391456 0.852069 0.85284 -0.51388 0.0926887 0.852747 -0.510501 0.1105 0.747754 -0.450552 0.487717 0.743394 -0.445302 0.499071 0.498184 -0.300105 0.81348 0.493667 -0.295961 0.817741 0.169633 -0.102209 0.980193 0.167905 -0.100798 0.980636 0.19479 -0.0355428 0.980201 0.208891 -0.040317 0.977108 0.57275 -0.1022 0.813334 0.587202 -0.107908 0.802216 0.858951 -0.155953 0.487731 0.979967 -0.179415 0.0864578 0.979601 -0.178295 0.0926967 0.941305 -0.171781 0.290578 0.858366 -0.155613 0.488869 0.713918 0.043505 0.698876 0.713923 0.0142878 0.700078 0.594293 0.0526771 0.802521 0.392561 0.0846781 0.91582 0.386933 0.0860178 0.918087 -0.00579249 0.129434 0.991571 -0.0095967 0.130091 0.991456 -0.385781 0.152108 0.909965 -0.387148 0.152271 0.909357 0.169745 -0.101897 0.980206 0.168166 -0.100496 0.980623 0.498266 -0.299608 0.813613 0.494053 -0.295464 0.817688 0.747805 -0.449997 0.488151 0.743748 -0.444767 0.49902 0.979552 -0.178197 0.0934021 0.85296 -0.513553 0.0933957 0.853006 -0.510072 0.11049 0.20865 -0.0380654 0.977249 0.195744 -0.0329357 0.980102 0.58642 -0.109941 0.802512 0.572183 -0.10357 0.81356 0.857506 -0.157211 0.489865 0.858324 -0.157698 0.488273 0.94121 -0.171692 0.290939 0.979854 -0.179147 0.0882753 0.713996 5.65036e-05 0.70015 0.715244 -1.06926e-06 0.698875 0.711564 3.40896e-05 0.702621 0.393974 7.52008e-05 0.919121 0.399397 9.68032e-05 0.916778 -0.00584163 0.000110431 0.999983 0.00455233 0.000149349 0.99999 -0.390323 0.000657977 0.920678 -0.336775 -1.63562e-05 0.941585 -0.359898 0.000128484 0.932992 -0.368393 5.5739e-05 0.92967 -0.377 -0.000163513 0.926213 0.995966 0 0.0897269 0.955388 0.00427028 0.295322 0.995174 0 0.0981251 0.868304 0 0.496033 0.868304 0 0.496033 0.589996 0 0.807406 0.589996 0 0.807406 0.208801 0 0.977958 0.208801 0 0.977958 0.790253 -0.178483 0.586212 0.751462 -0.140858 0.644565 0.724858 -0.0776092 0.684513 0.714854 -0.0366203 0.698314 0.797419 -0.241291 0.553084 0.690128 -0.447156 0.569011 0.634332 -0.537492 0.555631 0.599363 -0.590379 0.54057 0.3667 -0.820102 0.439275 0.437407 -0.759725 0.481137 -0.0314041 -0.977453 0.208807 0.110531 -0.946503 0.303174 0.0541695 -0.962974 0.264096 0.192794 -0.918427 0.34543 0.290866 -0.869371 0.399489 0.714805 -0.0366295 0.698364 0.397148 -0.107895 0.91139 0.397358 -0.107841 0.911305 0.00456877 -0.16448 0.98637 0.00514024 -0.164377 0.986384 -0.369743 -0.193488 0.908764 -0.369134 -0.19342 0.909026 -0.136723 -0.818501 0.557999 -0.14164 -0.81919 0.555757 0.202984 -0.696104 0.688649 0.199501 -0.697742 0.688008 0.527446 -0.45684 0.716308 0.525827 -0.458274 0.716583 0.461939 -0.517158 0.720528 0.767631 -0.161944 0.620094 -0.286475 -0.54814 0.785796 -0.288821 -0.548286 0.784834 0.0754225 -0.465841 0.881648 0.073639 -0.466304 0.881554 0.443479 -0.305598 0.842577 0.442558 -0.306036 0.842903 0.596708 -0.209821 0.774542 0.733769 -0.109743 0.670477 0.802247 -0.258834 0.537964 0.0763786 -0.995763 0.0512172 0.216077 -0.965926 0.142474 0.221586 -0.964096 0.146352 0.298109 -0.933568 0.198951 0.806342 -0.241315 0.53998 0.667789 -0.594309 0.448168 0.658938 -0.608732 0.441866 0.505605 -0.793355 0.339045 0.531177 -0.769116 0.355403 0.390941 -0.882163 0.26259 0.559538 -0.789253 0.252975 0.238896 -0.96502 0.108009 0.880954 -0.255503 0.398293 0.726608 -0.603425 0.328511 0.238902 -0.965018 0.108011 0.256869 -0.96559 0.0406674 0.256869 -0.96559 0.0406674 0.259793 -0.96559 -0.0119543 0.259793 -0.96559 -0.0119543 0.252049 -0.96559 -0.0640865 0.252044 -0.965592 -0.0640844 0.233949 -0.965591 -0.113583 0.23395 -0.965591 -0.113585 0.197184 -0.965018 -0.172796 0.197183 -0.965019 -0.172795 0.461827 -0.789257 -0.404708 0.6505 -0.702622 0.288398 0.700204 -0.705284 0.110856 0.700205 -0.705283 0.110856 0.708178 -0.705282 -0.0325866 0.708182 -0.705277 -0.0325877 0.687069 -0.705279 -0.174693 0.68707 -0.705278 -0.174694 0.637741 -0.705278 -0.309628 0.63774 -0.705279 -0.309627 0.538569 -0.702618 -0.465049 0.599722 -0.603434 -0.525548 0.880961 -0.255477 0.398294 0.954375 -0.257562 0.151096 0.954369 -0.257585 0.151098 0.965234 -0.257588 -0.0444161 0.965236 -0.257577 -0.0444178 0.936461 -0.257579 -0.238104 0.936464 -0.257569 -0.238106 0.86923 -0.257567 -0.422017 0.869227 -0.257587 -0.422012 0.727123 -0.255498 -0.637192 0.727123 -0.255499 -0.637192 0.638744 -0.25866 -0.724639 0.746762 -0.194986 -0.635867 0.769969 -0.195091 -0.607525 0.763901 0.0655339 -0.641998 0.636663 -0.555307 -0.535064 0.636665 -0.555303 -0.535066 0.425529 -0.831283 -0.357623 0.425523 -0.831288 -0.357618 0.149447 -0.98076 -0.125598 0.149448 -0.98076 -0.125599 0.701667 -0.194944 -0.685318 0.701666 -0.194952 -0.685317 0.594954 -0.555304 -0.581092 0.594945 -0.555324 -0.581082 0.397646 -0.831287 -0.38838 0.39765 -0.831283 -0.388384 0.139657 -0.98076 -0.136403 0.139661 -0.980759 -0.136407 0.649896 -0.194965 -0.734591 0.523725 -0.608501 -0.596187 0.549916 -0.555323 -0.623866 0.402715 -0.793152 -0.456871 0.366894 -0.831268 -0.417592 0.172292 -0.965868 -0.193429 0.129091 -0.980759 -0.14645 0.208801 0 -0.977958 0.208801 0 -0.977958 0.590001 0 -0.807403 0.590001 0 -0.807403 0.868302 0 -0.496036 0.868302 0 -0.496036 0.955397 0 -0.295325 0.995174 0.000172843 -0.0981251 0.995966 0 -0.0897269 0.194794 -0.0355343 -0.9802 0.20867 -0.0354653 -0.977343 0.571171 -0.106905 -0.81384 0.980011 -0.178281 -0.0882894 0.979397 -0.179041 -0.0934159 0.941212 -0.17168 -0.29094 0.858303 -0.157683 -0.488315 0.857505 -0.157207 -0.489869 0.58666 -0.106273 -0.80283 0.167979 -0.100836 -0.98062 0.16989 -0.10155 -0.980217 0.493322 -0.296598 -0.817718 0.498838 -0.298373 -0.813716 0.74252 -0.446734 -0.499092 0.748891 -0.447952 -0.488367 0.851511 -0.512551 -0.110548 0.854435 -0.511087 -0.0934435 0.20681 -0.970504 0.123898 0.133765 -0.973713 0.184364 0.515664 -0.847026 -0.128987 0.471979 -0.877656 -0.0833993 0.741791 -0.560005 -0.368972 0.727552 -0.592155 -0.346439 0.82547 -0.188481 -0.532048 0.82535 -0.204688 -0.526213 0.19686 -0.978346 -0.063921 0.119443 -0.992832 0.00427626 0.477719 -0.829672 -0.28884 0.431419 -0.868412 -0.244414 0.686853 -0.554836 -0.469457 0.676759 -0.576406 -0.457988 0.791418 -0.195013 -0.579334 0.791229 -0.197204 -0.578849 0.979404 -0.179368 -0.0927095 0.208909 -0.0381269 -0.977192 0.193968 -0.0377701 -0.98028 0.587405 -0.104694 -0.802493 0.571811 -0.105192 -0.813613 0.858332 -0.155877 -0.488845 0.858993 -0.155768 -0.487717 0.941269 -0.17181 -0.290678 0.980148 -0.178418 -0.0864731 0.851176 -0.513104 -0.11056 0.854346 -0.511367 -0.092722 0.742139 -0.447306 -0.499145 0.748831 -0.44856 -0.4879 0.492985 -0.297031 -0.817764 0.498656 -0.29899 -0.813601 0.167763 -0.101085 -0.980631 0.169744 -0.101911 -0.980205 0.845545 -0.193587 -0.497571 0.851591 -0.199851 -0.484616 0.847305 -0.181211 -0.499235 0.766407 -0.58367 -0.268235 0.772181 -0.568569 -0.283665 0.590024 -0.805561 -0.0542443 0.536811 -0.843651 0.00934854 0.42799 -0.899038 0.0924933 0.0797662 -0.929227 0.360797 0.251195 -0.939431 0.233173 0.197889 -0.940026 0.277831 -0.0885357 -0.899196 0.428495 0.996131 0 -0.0878832 0.995258 -0.0134633 -0.0963335 0.955477 0 -0.295066 0.868953 0 -0.494894 0.868953 0 -0.494894 0.59065 0 -0.806928 0.59065 0 -0.806928 0.209061 0 -0.977903 0.209061 0 -0.977903 0.838611 -0.482494 -0.252845 0.863178 -0.191651 -0.467112 0.859268 -0.0942687 -0.502764 0.880912 -0.191762 -0.432692 0.754572 -0.65062 -0.0855223 0.811757 -0.549559 -0.197575 0.612477 -0.786551 0.0788056 0.136398 -0.885491 0.444186 0.0530015 -0.868385 0.49305 0.315839 -0.889527 0.330133 0.245062 -0.891204 0.381706 0.492616 -0.849019 0.191037 0.437809 -0.866154 0.241041 0.648555 -0.760299 0.0363538 0.187492 0.683415 -0.705543 0.981096 0.183413 0.0617296 0.982637 0.172468 0.0684079 0.842423 0.52314 -0.129025 0.853257 0.507989 -0.1179 0.547784 0.779834 -0.302973 0.572907 0.766725 -0.289672 0.17419 0.891914 -0.41731 0.21225 0.888734 -0.406328 0.988927 0.148033 -0.0104556 0.990258 0.139244 -0.000288865 0.8563 0.421672 -0.298233 0.865391 0.411928 -0.285329 0.561473 0.62651 -0.540586 0.580674 0.61947 -0.528274 -0.21297 0.679684 -0.701907 0.199625 0.78756 -0.583009 0.993543 0.0950314 -0.0619735 0.994465 0.0910156 -0.0525007 0.864988 0.272281 -0.421497 0.871062 0.268504 -0.411287 0.570779 0.404626 -0.714486 0.582867 0.402358 -0.705957 0.19078 0.459336 -0.867533 0.207318 0.459756 -0.863507 0.994777 0.0338659 -0.096287 0.996056 0.032698 -0.0824863 0.865091 0.0941794 -0.492695 0.872057 0.0934509 -0.480399 0.584933 0.138802 -0.799117 0.581108 0.138813 -0.8019 0.206398 0.159098 -0.965447 0.202458 0.158864 -0.966319 0.893862 -0.176229 -0.412254 0.905465 -0.174405 -0.386933 0.890273 -0.12981 -0.436536 0.883574 -0.44219 -0.15416 0.888508 -0.424011 -0.175408 0.800374 -0.598429 0.0358255 0.814476 -0.580141 0.00814669 0.662763 -0.714689 0.223529 0.686187 -0.701123 0.19384 0.480921 -0.782314 0.395853 0.516037 -0.775316 0.36413 0.181862 -0.788432 0.587624 0.318066 -0.806968 0.497631 -0.54218 -0.399358 0.739293 0.12177 -0.788063 0.603431 0.970838 0.173097 0.165865 0.956553 0.184275 0.225941 0.956749 0.167025 0.23819 0.85577 0.516477 -0.0301354 0.859735 0.510169 -0.0241475 0.579683 0.760792 -0.291828 0.576638 0.762248 -0.294053 0.20553 0.849288 -0.486279 0.190733 0.849318 -0.492219 0.963561 0.186383 0.191862 0.964531 0.169771 0.202132 0.850951 0.524276 -0.0318972 0.854748 0.518335 -0.0270907 0.572484 0.777805 -0.259387 0.569425 0.779389 -0.261357 0.202163 0.879759 -0.430295 0.18835 0.880345 -0.435336 0.972672 0.1825 0.143535 0.973684 0.136946 0.182166 0.846523 0.53136 -0.0324827 0.850082 0.525862 -0.0287936 0.565931 0.793443 -0.223986 0.563011 0.795064 -0.225592 0.199065 0.90785 -0.369029 0.186154 0.908899 -0.373161 0.974474 0.189029 0.12111 0.97627 0.175555 0.126793 0.842643 0.537566 -0.0312508 0.845691 0.532897 -0.0287678 0.560217 0.807566 -0.184377 0.557334 0.809263 -0.185666 0.196326 0.933221 -0.300924 0.184514 0.934611 -0.304068 0.244897 -0.555283 0.794787 0.206415 -0.54725 0.811117 0.557771 -0.555243 0.616925 0.529681 -0.556878 0.639785 0.742694 -0.509892 0.434069 0.724185 -0.515668 0.457866 0.877931 -0.427076 0.216431 0.868334 -0.435061 0.238157 0.948885 -0.315349 -0.0131535 0.946163 -0.323658 0.00446964 0.937517 -0.128443 -0.323365 0.940547 -0.135003 -0.311681 0.239211 -0.6909 0.682228 0.193198 -0.681319 0.70603 0.540127 -0.681468 0.493826 0.504149 -0.685864 0.524809 0.718047 -0.620561 0.315139 0.692527 -0.631951 0.347915 0.847939 -0.51754 0.114682 0.834813 -0.531769 0.142509 0.920423 -0.379669 -0.0931286 0.915981 -0.395157 -0.0694912 0.918311 -0.152359 -0.365365 0.922296 -0.165299 -0.349352 0.0684283 -0.71452 0.696261 0.909941 -0.396353 0.122114 0.907616 -0.399606 0.128644 0.879111 -0.402856 0.254696 0.922088 -0.35875 0.145093 0.955 -0.296054 0.018101 0.945548 -0.117852 -0.303398 0.221194 -0.497804 0.838608 0.530587 -0.523516 0.66664 0.541039 -0.522466 0.659019 0.227172 -0.540329 0.810208 0.220095 -0.562423 0.797018 0.313642 -0.604225 0.732489 -0.00953981 -0.569378 0.822021 0.958077 -0.164344 -0.234689 0.605799 -0.67418 0.42248 0.880746 -0.463936 0.0951268 0.883736 -0.459323 0.089625 0.951473 -0.11602 -0.285023 0.955448 -0.152604 -0.252649 0.951117 -0.14278 -0.273845 0.948405 -0.131007 -0.28873 0.949551 -0.127449 -0.286549 0.217055 -0.732752 0.644951 0.60008 -0.676225 0.427345 0.620008 -0.626677 0.472087 0.893448 -0.435097 0.111538 0.896298 -0.430746 0.105395 0.953965 -0.156281 -0.255984 0.952877 -0.148194 -0.264697 0.735862 -0.481171 0.476425 0.650784 -0.507101 0.565092 0.629582 -0.57258 0.525147 0.635217 -0.570833 0.52024 0.614258 -0.62838 0.477311 0.392879 -0.669608 0.630295 0.318298 -0.674956 0.665673 0.174458 0.875454 -0.450716 0.186384 0.981502 0.0437502 0.496158 0.836398 0.232948 0.737519 0.550097 0.391739 0.133731 0.99097 0.00973576 0.200093 0.973469 -0.110999 0.145305 0.978902 -0.143656 0.190789 0.95291 -0.235715 -0.227001 0.863639 -0.450109 0.169696 0.929359 -0.327864 0.215324 0.875902 -0.431776 0.463568 0.860756 0.210246 0.529852 0.843355 0.0895003 0.495356 0.866322 0.0641007 0.558804 0.826755 -0.0649128 0.525513 0.845978 -0.0903199 0.583445 0.78115 -0.222254 0.555569 0.794852 -0.244035 0.725354 0.572695 0.381944 0.77985 0.558492 0.282704 0.766665 0.582999 0.268956 0.818133 0.55103 0.164389 0.804929 0.5748 0.147292 0.851011 0.523426 0.0424983 0.839097 0.543449 0.024054 0.846748 0.187976 0.497678 0.86501 0.0140059 0.50156 0.862874 0.195827 0.465941 0.887346 0.189277 0.420465 0.886195 0.204098 0.415936 0.916598 0.185263 0.354297 0.915938 0.203324 0.346002 0.941592 0.174807 0.287832 0.941582 0.193561 0.275604 0.204514 -0.805685 0.555919 0.959023 -0.162177 -0.232322 0.197993 -0.887024 0.417117 0.972661 -0.175935 -0.151585 0.194171 -0.9434 0.268875 0.189248 -0.975035 0.116157 0.981183 -0.184383 -0.0572981 0.185311 -0.981782 0.0419908 0.187201 -0.981429 0.0418709 0.548249 -0.835925 0.0255533 0.548822 -0.835551 0.0254996 0.836188 -0.548425 0.00431473 0.83581 -0.549002 0.00437321 0.982508 -0.185457 -0.0168243 0.982155 -0.187333 -0.0166712 0.187603 -0.969539 0.157479 0.377246 -0.92043 0.102444 0.549223 -0.832171 0.0764535 0.550892 -0.831099 0.0761072 0.83775 -0.545902 0.0128875 0.836655 -0.547569 0.0132755 0.99502 0.0518409 -0.085133 0.981383 -0.187741 -0.0405135 0.184519 -0.960752 0.207142 0.192459 -0.959529 0.205583 0.55188 -0.824217 0.126864 0.554373 -0.822665 0.12607 0.84044 -0.541475 0.0215691 0.838747 -0.544056 0.0225144 0.980104 -0.180117 -0.0833865 0.97867 -0.188875 -0.0808115 0.188586 -0.931909 0.309807 0.439118 -0.871453 0.218508 0.555724 -0.812214 0.177423 0.559454 -0.809995 0.175839 0.844389 -0.534849 0.0307146 0.84212 -0.538313 0.0324605 0.977406 -0.17706 -0.115447 0.975853 -0.188123 -0.111001 0.185032 -0.911791 0.366606 0.199265 -0.910519 0.362284 0.561321 -0.795626 0.227813 0.565591 -0.793238 0.225567 0.849537 -0.525982 0.040376 0.846901 -0.53001 0.0429907 0.976282 -0.0212749 -0.215456 0.973736 -0.18427 -0.133729 0.968723 -0.183656 -0.16687 0.969745 -0.169233 -0.17594 0.853128 -0.518851 0.0544733 0.855935 -0.51456 0.0510181 0.573401 -0.771689 0.275151 0.568598 -0.774169 0.278135 0.441181 -0.82871 0.344383 0.191315 -0.868733 0.456839 0.190247 -0.835472 0.515551 0.207221 -0.835327 0.509203 0.577525 -0.747702 0.327728 0.582589 -0.745332 0.324145 0.863621 -0.500247 0.0625538 0.860737 -0.504643 0.0668382 0.965231 -0.164535 -0.20312 0.96487 -0.17931 -0.192026 0.961255 -0.173164 -0.214485 0.959787 -0.140796 -0.24287 0.869893 -0.486636 0.0804416 0.872845 -0.482164 0.0752348 0.593471 -0.713197 0.373019 0.587869 -0.71552 0.377414 0.416057 -0.768622 0.485918 0.196607 -0.780295 0.593705 0.153582 0.983259 0.0980581 0.753841 0.187986 0.629592 0.13601 0.983311 0.120833 0.652949 0.187666 0.733784 0.652989 0.187307 0.73384 0.555276 0.549752 0.624052 0.555603 0.548973 0.624447 0.363915 0.836819 0.409024 0.364784 0.83594 0.410046 0.122574 0.982844 0.137817 0.124027 0.982423 0.139509 0.71246 0.187862 0.676098 0.712506 0.187495 0.676151 0.605543 0.550521 0.574669 0.605917 0.549712 0.575049 0.396038 0.837776 0.375878 0.397055 0.836841 0.376888 0.0949116 0.991398 0.0901264 0.13253 0.982862 0.128137 0.779679 0.188153 0.597243 0.720332 -0.385586 0.576581 0.651517 0.550942 0.521525 0.651728 0.550522 0.521706 0.425675 0.838263 0.340759 0.426245 0.837778 0.341237 0.141193 0.983506 0.11305 0.142119 0.983284 0.113819 0.815756 0.18781 0.547055 0.815723 0.18803 0.547028 0.693411 0.550421 0.464992 0.693133 0.550941 0.464792 0.453631 0.837671 0.304181 0.452888 0.838262 0.303658 0.0975487 0.993081 0.0653855 0.148333 0.983525 0.103323 0.1872 -0.981427 -0.0419249 0.548821 -0.83555 -0.0255205 0.83581 -0.549002 -0.00435206 0.982154 -0.187333 0.0167254 0.185308 -0.981785 -0.0419371 0.189642 -0.973886 -0.12483 0.184117 -0.974893 -0.125241 0.191872 -0.960925 -0.199518 0.342293 -0.922682 -0.177463 0.975795 -0.18822 0.111341 0.98014 -0.180042 0.0831314 0.978639 -0.188925 0.0810762 0.981183 -0.184382 0.0572981 0.99502 0.0518401 0.0851329 0.981383 -0.187741 0.0405136 0.98251 -0.185451 0.0167705 0.189773 -0.951983 -0.240238 0.196598 -0.938122 -0.28509 0.183906 -0.939937 -0.287569 0.197048 -0.915268 -0.351364 0.415485 -0.861827 -0.290905 0.191525 -0.899922 -0.391738 0.203226 -0.875787 -0.437832 0.186918 -0.87708 -0.442485 0.203039 -0.844622 -0.495367 0.444709 -0.798332 -0.406079 0.196642 -0.822582 -0.533564 0.548247 -0.835926 -0.0255325 0.550894 -0.831092 -0.0761692 0.549216 -0.832182 -0.0763929 0.554381 -0.822645 -0.126165 0.551865 -0.824241 -0.126773 0.559474 -0.809951 -0.17598 0.555693 -0.812265 -0.177289 0.56562 -0.793171 -0.225728 0.561262 -0.795708 -0.227671 0.573427 -0.771601 -0.275342 0.568527 -0.774278 -0.277975 0.582627 -0.745216 -0.324345 0.577461 -0.747829 -0.327554 0.83619 -0.548423 -0.00433567 0.836652 -0.547575 -0.0132127 0.837756 -0.545891 -0.0129487 0.838737 -0.544076 -0.022414 0.840464 -0.541434 -0.0216616 0.842107 -0.538341 -0.0323166 0.844416 -0.534799 -0.0308443 0.846868 -0.530075 -0.042826 0.849577 -0.525905 -0.0405291 0.853082 -0.518944 -0.0542901 0.855995 -0.514445 -0.0511787 0.860686 -0.504757 -0.0666343 0.863665 -0.500145 -0.0627574 0.961254 -0.173124 0.214518 0.965382 -0.164157 0.202709 0.964718 -0.179614 0.192507 0.969869 -0.168968 0.175513 0.9686 -0.183888 0.16733 0.972661 -0.175935 0.151584 0.976283 -0.0212851 0.215452 0.973736 -0.184265 0.133732 0.977467 -0.176927 0.115128 0.959024 -0.162175 0.23232 0.959787 -0.140799 0.242866 0.872922 -0.481996 -0.0754207 0.869805 -0.486822 -0.0802667 0.587791 -0.715683 -0.377227 0.593538 -0.713034 -0.373222 0.193168 -0.787644 -0.585067 0.212534 -0.787458 -0.578566 0.174092 0.982671 -0.0636394 0.18432 0.982815 0.0100398 0.16363 0.983017 0.0830837 0.902809 0.185447 -0.388003 0.902811 0.185433 -0.388003 0.770012 0.545498 -0.330927 0.77003 0.545471 -0.330932 0.505778 0.83483 -0.217363 0.505816 0.834804 -0.217376 0.576481 0.778647 -0.247746 0.158417 0.982894 -0.093929 0.981985 0.18549 -0.0360486 0.981996 0.18543 -0.0360459 0.837508 0.545562 -0.0307086 0.837536 0.545519 -0.0307068 0.550081 0.834869 -0.0201263 0.550129 0.834837 -0.0201249 0.896797 0.441219 -0.0328888 0.183034 0.982814 -0.023988 0.928933 0.185493 0.320429 0.928939 0.185456 0.320433 0.792176 0.545696 0.273266 0.792282 0.545516 0.273316 0.520077 0.835062 0.179417 0.52038 0.834846 0.179545 0.487205 0.856956 0.1681 0.177994 0.982639 0.0523329 0.751009 0.184401 0.63402 0.750886 0.185523 0.633839 0.641744 0.542756 0.54183 0.640399 0.545725 0.540438 0.424055 0.831823 0.358117 0.420512 0.83508 0.3547 0.144794 0.981862 0.122402 0.142435 0.98248 0.120188 0.203691 -0.716505 -0.667181 0.955 -0.296053 -0.0181003 0.956175 -0.150824 0.250962 0.880746 -0.463937 -0.0951259 0.605799 -0.674181 -0.422479 0.629582 -0.57258 -0.525147 0.635221 -0.570832 -0.520236 0.735862 -0.481171 -0.476425 0.650784 -0.507101 -0.565092 0.541039 -0.522466 -0.659019 0.215376 -0.517706 -0.828006 0.951319 -0.142362 0.273357 0.948237 -0.131521 0.289047 0.949002 -0.129159 0.2876 0.954704 -0.144077 0.260351 0.946082 -0.11593 0.302472 0.211165 -0.747105 -0.630273 0.481295 -0.711218 -0.512371 0.600068 -0.67623 -0.427354 0.446616 -0.602043 -0.661875 0.211827 -0.587148 -0.781272 0.233688 -0.519173 -0.822101 0.957225 -0.166275 0.236799 0.883753 -0.459297 -0.0895923 0.893465 -0.435072 -0.111504 0.619995 -0.626681 -0.472098 0.614261 -0.628379 -0.477309 0.222463 -0.669184 -0.709016 -0.120481 -0.59377 -0.795564 0.879111 -0.402856 -0.254696 0.922087 -0.358752 -0.145096 0.90994 -0.396355 -0.122118 0.907617 -0.399603 -0.12864 0.8963 -0.430743 -0.105391 0.950734 -0.136821 0.278181 0.954245 -0.15564 0.25533 0.152743 0.982946 -0.102407 0.815791 0.187394 -0.547146 0.155403 0.982331 -0.104284 0.155036 0.982412 -0.104073 0.455917 0.835903 -0.305623 0.45175 0.839108 -0.303018 0.694194 0.549059 -0.465435 0.692501 0.552051 -0.464415 0.815496 0.189622 -0.546817 0.815699 0.188541 -0.546889 0.942512 -0.12841 0.308517 0.932863 -0.140294 0.33179 0.926695 -0.102296 0.361624 0.949147 -0.314581 0.0125663 0.945926 -0.324355 -0.00412324 0.878225 -0.426056 -0.217248 0.868009 -0.435969 -0.23768 0.743148 -0.508548 -0.434868 0.723783 -0.516783 -0.457246 0.558221 -0.553727 -0.61788 0.529238 -0.558149 -0.639043 0.24591 -0.55226 -0.796578 0.205529 -0.550017 -0.809469 0.919737 -0.154224 0.360971 0.921897 -0.166197 0.349978 0.920164 -0.381367 0.0886498 0.915578 -0.395997 0.0700154 0.847308 -0.517709 -0.118516 0.834338 -0.532646 -0.142016 0.715478 -0.620687 -0.320686 0.691958 -0.633075 -0.347001 0.537958 -0.680242 -0.497866 0.503478 -0.687102 -0.523833 0.239377 -0.687452 -0.685645 0.19184 -0.68408 -0.703728 0.79332 0.183494 -0.580494 0.0751387 0.972483 -0.220524 0.0752225 0.972467 -0.220568 0.385353 0.82983 -0.40359 0.385482 0.829745 -0.403642 0.647657 0.547341 -0.530055 0.647741 0.547224 -0.530073 0.766588 0.301737 -0.566831 0.808204 0.187354 -0.558305 0.906103 -0.177705 0.383925 0.106725 -0.807221 -0.580521 0.893936 -0.176193 0.41211 0.890558 -0.131944 0.435312 0.889246 -0.423017 0.174064 0.882217 -0.445807 0.151489 0.815262 -0.579011 -0.0097272 0.798339 -0.60105 -0.0373414 0.687138 -0.699681 -0.195675 0.658623 -0.717583 -0.226473 0.51705 -0.773671 -0.366185 0.477111 -0.783978 -0.39717 0.323965 -0.798522 -0.507355 0.177767 -0.7921 -0.583932 -0.309394 -0.589702 -0.746007 -0.0497792 0.911623 -0.408002 -0.0493997 0.911573 -0.408161 0.280234 0.776769 -0.564002 0.280474 0.776646 -0.564052 0.578655 0.511157 -0.635513 0.578754 0.511056 -0.635504 0.776582 0.174663 -0.605321 0.776604 0.174619 -0.605305 0.880989 -0.19174 0.432544 0.863067 -0.18795 0.468819 0.858856 -0.0926325 0.503771 0.847395 -0.453938 0.275431 0.83827 -0.482881 0.253236 0.772329 -0.622978 0.12412 0.749927 -0.655126 0.0917606 0.651279 -0.757964 -0.0364264 0.611692 -0.78725 -0.0779133 0.494801 -0.847444 -0.192382 0.436771 -0.867014 -0.23983 0.318266 -0.888075 -0.331706 0.243996 -0.892077 -0.380348 0.137717 -0.884095 -0.446553 0.0518758 -0.869295 -0.491564 -0.122082 0.847368 -0.516783 -0.168016 0.793108 -0.585448 0.0221767 0.779747 -0.625702 0.199678 0.701882 -0.683733 0.199664 0.701888 -0.683731 0.525573 0.462012 -0.714366 0.525596 0.461993 -0.714361 0.758486 0.157859 -0.632281 0.758466 0.157888 -0.632298 0.0797637 -0.929058 -0.361234 -0.0885388 -0.899007 -0.428891 0.258042 -0.93553 -0.241241 0.19363 -0.941928 -0.274371 0.429192 -0.898493 -0.092223 0.534069 -0.845351 -0.012332 0.591585 -0.80429 0.0560839 0.84565 -0.197316 0.495926 0.720127 -0.66272 0.205475 0.776226 -0.569803 0.269811 0.806296 -0.484489 0.339349 0.848092 -0.180615 0.498114 0.85161 -0.196067 0.486126 -0.22761 0.703553 -0.673206 -0.227615 0.703553 -0.673204 0.128693 0.599485 -0.789972 0.128659 0.599496 -0.78997 0.478867 0.394545 -0.784233 0.47887 0.394543 -0.784232 0.742524 0.134781 -0.656119 0.742518 0.134787 -0.656124 0.826038 -0.18834 0.531215 0.82462 -0.208874 0.525712 0.743363 -0.559514 0.366545 0.170095 -0.955743 -0.24005 0.466822 -0.880381 0.0837073 0.0333639 -0.966244 -0.255459 0.202196 -0.972249 -0.117683 0.116258 -0.993219 -0.000174808 0.194867 -0.979245 0.055726 0.429207 -0.868746 0.247106 0.518162 -0.846075 0.125166 0.723449 -0.598173 0.344688 0.792749 -0.183793 0.581179 0.790851 -0.19732 0.579327 0.73877 -0.431519 0.517698 0.67512 -0.576748 0.459972 0.597484 -0.705551 0.381065 0.384692 -0.89778 0.214481 -0.295346 0.559534 -0.774398 -0.295464 0.559534 -0.774353 0.0709387 0.476763 -0.876165 0.0708367 0.476783 -0.876162 0.440848 0.313775 -0.840951 0.440774 0.313805 -0.840979 0.7295 0.107214 -0.675525 0.729515 0.107203 -0.675511 0.169912 -0.965896 0.195383 0.538578 -0.706767 0.458709 0.538575 -0.70677 0.458707 0.197215 -0.965864 0.167969 0.335113 -0.899708 0.279686 0.143663 -0.982033 0.122359 0.77167 -0.183864 0.608867 0.182859 -0.965881 0.183403 0.182858 -0.965881 0.183402 0.499431 -0.706861 0.500916 0.499433 -0.706857 0.500918 0.169913 -0.965896 0.195383 0.399591 -0.793218 0.459491 0.46249 -0.706905 0.535153 0.520694 -0.608586 0.598749 0.588608 -0.44207 0.676842 0.725694 -0.431847 0.535608 0.761111 -0.0222086 0.648241 0.731333 -0.258647 0.631074 0.682031 -0.258646 0.684059 0.682029 -0.258657 0.684057 0.632633 -0.258701 0.729965 0.643612 -0.195009 0.740091 0.720398 0.0648445 -0.690523 -0.346205 0.391354 -0.852633 -0.347521 0.391294 -0.852126 0.0302232 0.332886 -0.942483 0.0263363 0.333233 -0.942477 0.416983 0.217854 -0.88242 0.41138 0.219087 -0.884742 0.69223 0.0912041 -0.715891 0.722132 0.0832355 -0.68673 0.713956 0.0142734 -0.700045 -0.385775 0.152215 -0.90995 -0.386086 0.152198 -0.909821 -0.00579232 0.129653 -0.991543 -0.005926 0.129653 -0.991542 0.39255 0.0850023 -0.915794 0.392467 0.0850059 -0.91583 0.594747 0.0525411 -0.802194 0.7164 0.0426868 -0.696382 0.470172 -0.788283 0.396923 0.516425 -0.827029 -0.222099 0.767817 -0.549015 -0.330212 0.901575 -0.191891 -0.387738 0.901572 -0.191909 -0.387736 0.980735 -0.191926 -0.0363644 0.980743 -0.191887 -0.0363668 0.927816 -0.191879 0.319905 0.927814 -0.191889 0.319905 0.74992 -0.191884 0.633089 0.749915 -0.191908 0.633087 0.687601 -0.436173 0.58048 0.767833 -0.548986 -0.330221 0.835263 -0.548977 -0.0309723 0.835241 -0.549011 -0.0309692 0.790162 -0.549016 0.272444 0.790174 -0.548997 0.272447 0.640061 -0.549193 0.537316 0.610031 -0.602199 0.514994 0.516414 -0.827038 -0.222092 0.561756 -0.82704 -0.0208289 0.561776 -0.827027 -0.0208309 0.531454 -0.827031 0.183241 0.531451 -0.827033 0.183241 0.43085 -0.827237 0.360621 0.198159 -0.964965 0.171978 0.160835 -0.984555 -0.0691698 0.151544 -0.980136 0.127935 0.187493 -0.980136 0.0646466 0.187498 -0.980135 0.0646481 0.198193 -0.980136 -0.0073491 0.198192 -0.980136 -0.00734905 0.182453 -0.980176 -0.0772378 0.336659 -0.930429 -0.144786 -0.390323 0.000657977 -0.920678 -0.336775 -1.63563e-05 -0.941585 -0.377 -0.000163523 -0.926213 -0.368393 5.5739e-05 -0.92967 0.714029 5.68096e-05 -0.700116 -0.359898 0.000128485 -0.932992 -0.00584163 0.00014904 -0.999983 0.00455235 0.000110319 -0.99999 0.393974 9.71221e-05 -0.919121 0.399397 7.46433e-05 -0.916778 0.711564 3.409e-05 -0.702621 0.715244 -1.06926e-06 -0.698875 0.816393 -0.183847 -0.547451 0.814745 -0.195081 -0.546017 0.690393 -0.555593 -0.463329 0.697009 -0.543871 -0.467314 0.461401 -0.831464 -0.30948 0.458461 -0.83377 -0.307637 0.299892 -0.93254 -0.201082 0.142789 -0.985063 -0.0962393 0.1566 -0.982064 -0.105011 0.6329 -0.540703 -0.554146 0.79547 -0.18371 -0.577475 0.795724 -0.182899 -0.577383 0.773232 -0.165886 -0.612041 0.652959 -0.312973 -0.689704 0.717608 -0.0472757 -0.694841 0.727025 -0.0876678 -0.680991 0.369787 -0.342147 -0.863825 0.738232 -0.117306 -0.664268 0.755496 -0.148589 -0.638081 0.397183 -0.107076 -0.911472 -0.369891 -0.192045 -0.90901 0.0525318 -0.962602 -0.265779 -0.144422 -0.816091 -0.559588 -0.140073 -0.815079 -0.562162 -0.290416 -0.545249 -0.786361 -0.28805 -0.544813 -0.787531 -0.369595 -0.192053 -0.909129 0.00456915 -0.163239 -0.986576 0.00480482 -0.16323 -0.986576 0.0741354 -0.46306 -0.883221 0.0723521 -0.463762 -0.883001 0.200256 -0.693271 -0.692295 0.197186 -0.695102 -0.69134 0.364903 -0.819939 -0.441073 0.046732 -0.963745 -0.262699 0.715207 -0.0116712 -0.698816 0.45234 -0.0968116 -0.886576 0.39728 -0.107066 -0.911431 0.442764 -0.303743 -0.843623 0.441869 -0.304315 -0.843886 0.525803 -0.454929 -0.718729 0.524342 -0.456503 -0.718798 0.634488 -0.538524 -0.554452 0.361031 -0.822487 -0.439512 0 -0.991598 0.129361 -0.0048821 -0.994523 0.1044 0.00370993 -0.943389 0.331668 0 -0.951505 0.307632 0 -0.943536 0.33127 -0.00160278 -0.951667 0.307126 0.00211216 -0.991536 0.129812 0 -0.994601 0.103776 0 -0.860695 0.50912 0 -0.860695 0.50912 0 -0.978461 -0.20643 -0.00480652 -0.952267 -0.305228 0 -0.994763 -0.102213 0 -0.860694 -0.509123 9.85066e-08 -0.860695 -0.50912 0 -0.951668 0.307129 -0.00245429 -0.978458 0.20643 0 -0.994763 0.102213 0 -0.943536 -0.331271 0.0027438 -0.951786 -0.30675 -0.00393059 -0.99148 -0.1302 0 -0.994709 -0.102732 0 -0.991598 -0.129361 0.00264766 -0.994614 -0.103617 -0.00212639 -0.943453 -0.3315 0 -0.951756 -0.306857 0.869361 -0.160761 0.467297 0.788877 -0.400222 0.466364 0.873081 -0.195099 0.446839 0.12285 -0.92758 0.352849 0.188034 -0.90335 0.385489 0.440318 -0.77388 0.455226 0.481219 -0.738977 0.471531 0.738556 -0.49056 0.462479 0.832585 -0.27833 0.478889 0.724966 -0.555034 0.407874 0.500659 -0.800114 0.330392 0.465574 -0.829396 0.308777 0.197294 -0.959989 0.198738 0.137017 -0.977318 0.161482 0.123544 -0.925305 0.358537 0.191289 -0.905833 0.377989 0.443089 -0.771649 0.456322 0.485215 -0.742478 0.461837 0.711184 -0.501873 0.492281 0.727612 -0.479875 0.490205 0.872213 -0.17014 0.458581 0.873881 -0.165126 0.457237 0.89241 -0.179463 0.414003 0.890505 -0.187137 0.414705 0.757591 -0.523477 0.389908 0.741286 -0.547643 0.38805 0.509749 -0.802983 0.308828 0.4675 -0.832247 0.298007 0.200289 -0.96153 0.188003 0.198626 -0.979992 -0.0127806 0.170788 -0.982146 0.0788756 0.132408 -0.977302 0.165378 0.522867 -0.850358 -0.0591777 0.562404 -0.825861 -0.0406821 0.807087 -0.572675 0.143713 0.821801 -0.548543 0.154089 0.929097 -0.198739 0.3119 0.930497 -0.18696 0.314994 0.911609 -0.187239 0.365938 0.909786 -0.197435 0.365115 0.789517 -0.547882 0.276566 0.773778 -0.572848 0.270394 0.536116 -0.832568 0.139322 0.494487 -0.860304 0.123934 0.145613 -0.988387 -0.0434592 0.218442 -0.950691 -0.22016 0.155013 -0.957849 -0.241861 0.9248 -0.187342 0.331132 0.883115 -0.393001 0.256238 0.933916 -0.193707 0.300464 0.149787 -0.987442 -0.0502163 0.761999 -0.607726 0.223669 0.593957 -0.791288 0.145186 0.507583 -0.856468 0.0939228 0.436568 -0.896919 0.0703242 0.206295 -0.978307 -0.0189166 0.867824 -0.43394 0.242031 0.884695 -0.387048 0.259822 0.813394 -0.56704 0.129834 0.560981 -0.826559 -0.0458312 0.528839 -0.84561 -0.0726159 0.214932 -0.951573 -0.219801 0.159136 -0.954513 -0.252151 0.934244 -0.19004 -0.301784 0.923643 -0.195077 -0.329892 0.816363 -0.561995 -0.133095 0.529156 -0.846075 0.0644314 0.563419 -0.824462 0.0531251 0.156841 -0.957282 0.242924 0.218408 -0.94856 0.2292 0.883398 -0.392242 -0.256426 0.883372 -0.392317 -0.2564 0.796305 -0.554764 -0.241113 0.50257 -0.85807 -0.105539 0.548059 -0.828512 -0.114889 0.145578 -0.988552 0.0396439 0.216891 -0.975854 0.025829 0.891252 -0.184694 -0.414196 0.87462 -0.161953 -0.456959 0.906402 -0.2334 -0.352079 0.916743 -0.196598 -0.347752 0.921177 -0.18838 -0.340509 0.922872 -0.193593 -0.332911 0.824823 -0.528413 -0.201114 0.823605 -0.55507 -0.116495 0.934365 -0.18991 -0.301489 0.917751 -0.282085 -0.279572 0.810829 -0.548053 -0.205412 0.217454 -0.952662 0.212484 0.158169 -0.956217 0.246235 0.801001 -0.551741 -0.232333 0.802893 -0.544954 -0.241637 0.527658 -0.847259 0.0610688 0.867795 -0.450579 -0.209549 0.848475 -0.489555 -0.201065 0.923704 -0.225005 -0.310072 0.923499 -0.200456 -0.327059 0.923114 -0.195525 -0.331104 0.818312 -0.537966 -0.202382 0.815371 -0.542053 -0.203344 0.813323 -0.544811 -0.204175 0.922651 -0.192196 -0.33433 0.922402 -0.190947 -0.335729 0.921968 -0.189623 -0.337665 0.807833 -0.551647 -0.207588 0.803976 -0.555728 -0.211633 0.7996 -0.55791 -0.222207 0.919288 -0.189321 -0.345061 0.917741 -0.193707 -0.346742 0.916762 -0.196541 -0.347734 0.801436 -0.549918 -0.235141 0.801651 -0.549076 -0.23637 0.802165 -0.547294 -0.238749 0.91638 -0.197741 -0.348062 0.915778 -0.199721 -0.348515 0.91424 -0.204942 -0.349521 0.804925 -0.538687 -0.24882 0.816131 -0.506508 -0.278172 0.838328 -0.446353 -0.31301 0.893236 -0.283701 -0.348773 0.906728 -0.183281 -0.379806 0.781335 -0.543337 -0.307084 0.759195 -0.543224 -0.358512 0.836233 -0.36094 -0.41284 0.796967 -0.34246 -0.497559 0.729423 -0.474345 -0.492888 0.563532 -0.825437 0.0329288 0.499482 -0.857643 -0.122332 0.536669 -0.830854 -0.147204 0.472405 -0.8303 -0.295696 0.510523 -0.799877 -0.315535 0.447793 -0.770273 -0.45405 0.485703 -0.738699 -0.467351 0.144809 -0.988782 0.036624 0.194747 -0.980664 0.0192733 0.17202 -0.981821 -0.0802292 0.136105 -0.977479 -0.161279 0.198983 -0.960223 -0.195901 0.127037 -0.926264 -0.354818 0.189422 -0.903349 -0.384811 0.87308 -0.195099 -0.446841 0.870228 -0.157715 -0.466721 0.724966 -0.555034 -0.407874 0.461931 -0.828927 -0.315436 0.503693 -0.801096 -0.323324 0.132391 -0.976436 -0.170428 0.201834 -0.96107 -0.188699 0.788 -0.401867 -0.466433 0.81447 -0.3452 -0.466343 0.728184 -0.473151 -0.49586 0.43645 -0.771832 -0.462371 0.486874 -0.739725 -0.4645 0.118302 -0.924775 -0.361657 0.193034 -0.906094 -0.376473 0.984221 0.175759 0.0204628 0.0993239 0.995027 0.00749499 0.175213 0.984374 0.0175752 0.298841 0.954059 0.0215992 0.525424 0.849758 0.0429024 0.537583 0.841997 0.0452188 0.67418 0.736755 0.051704 0.772751 0.631936 0.0592625 0.839449 0.538798 0.0708712 0.904324 0.421474 0.0675156 0.981359 0.175675 0.0779251 0.986375 0.145955 0.0759105 0.986432 0.145565 -0.0759149 0.981356 0.175674 -0.0779665 0.945278 0.318066 -0.072689 0.889667 0.451455 -0.0684136 0.839449 0.538798 -0.0708656 0.744235 0.66568 -0.0546362 0.525703 0.849499 -0.0445963 0.537645 0.842019 -0.0440641 0.390738 0.920007 -0.0301903 0.291797 0.956241 -0.0213752 0.175213 0.984374 -0.0175752 0.0993239 0.995027 -0.00749499 0.175948 0.984399 0 0.175948 0.984399 0 0.539469 0.842005 0 0.539469 0.842005 0 0.842424 0.538816 0 0.842424 0.538816 0 0.998782 0.0493493 0 0.984221 0.175759 -0.0204628 0.208728 0.0263837 0.977618 0.148473 0.036397 0.988246 0.148728 0.239632 0.959404 0.196715 0.0919067 0.976144 0.121105 0.107329 0.98682 0.143698 0.118226 0.982534 0.114618 0.157426 0.980857 0.048624 0.0808667 0.995538 0.984696 0.144733 0.0970919 0.861037 0.1291 0.491882 0.587831 0.0855969 0.804443 0.98524 0.143653 0.0930901 0.943963 0.31636 0.0940747 0.889843 0.418674 0.181358 0.88756 0.448399 0.10572 0.742789 0.661183 0.105364 0.737833 0.663441 0.124294 0.524863 0.842074 0.124224 0.517866 0.842512 0.148282 0.862155 0.128617 0.490047 0.789733 0.368933 0.490112 0.784655 0.369508 0.497775 0.64782 0.576608 0.497848 0.639965 0.575051 0.509668 0.455101 0.7301 0.509742 0.446056 0.725103 0.524652 0.571839 0.0890778 0.815515 0.524598 0.245062 0.815317 0.520318 0.244801 0.818133 0.429475 0.382221 0.818204 0.423202 0.37987 0.822556 0.300781 0.482448 0.822663 0.294064 0.477296 0.828079 -0.127769 0.935762 0.328672 -0.0177249 0.916187 0.400358 0.136076 0.88906 0.437099 0.111876 0.845959 0.52138 0.140622 0.758949 0.635785 0.388009 0.909406 0.149763 0.280235 0.955459 0.0925557 0.272982 0.96197 -0.00970144 0.349957 0.923465 0.157296 0.262709 0.867758 0.421878 0.346338 0.775065 0.528511 0.180231 0.652907 0.735682 0.237239 0.503774 0.83062 -0.0306386 0.314031 0.948918 0.124907 0.951661 0.280606 -0.0293332 0.822061 0.568643 0.0426974 0.809116 0.586096 0.032166 0.751492 0.658958 0.0699014 0.659052 0.748842 -0.0212714 0.650799 0.758952 0.101383 0.543655 0.833163 0.103499 0.542926 0.833378 -0.0223025 0.332495 0.942841 0.205951 0.243025 0.947905 -0.115774 0.150697 0.981777 0.243988 0.392638 0.886739 -0.0317 0.497158 0.867081 0.183158 0.651812 0.735931 0.14104 0.758819 0.635848 0.309704 0.863742 0.397534 0.175469 0.908873 0.378365 0.179927 0.948259 0.261592 0.0875915 0.966702 0.240447 0.124388 0.990599 0.0569262 0.107666 0.992801 -0.0524766 0.771248 0.627683 -0.105788 0.08988 0.118381 -0.988892 0.0770885 0.0684434 -0.994672 0.523175 0.839253 -0.14813 0.518992 0.845722 -0.124105 0.450415 0.722655 -0.524305 0.450496 0.733193 -0.509394 0.341064 0.549865 -0.762446 0.3129 0.473194 -0.823518 0.247449 0.401373 -0.881855 0.148659 0.239725 -0.959392 0.671911 0.729952 -0.12532 0.727197 0.649134 -0.22318 0.64431 0.570441 -0.509374 0.646577 0.578275 -0.49753 0.426012 0.377193 -0.822338 0.428989 0.383196 -0.818003 0.161028 0.14262 -0.976591 0.902058 0.418608 -0.105162 0.901672 0.422343 -0.0928101 0.786843 0.365239 -0.497472 0.78962 0.369632 -0.489769 0.521818 0.242253 -0.817936 0.524675 0.245332 -0.815186 0.14794 0.0684474 -0.986625 0.174551 0.0918896 -0.980351 0.208705 0.0302542 -0.97751 0.19792 0.024604 -0.979909 0.587497 0.0920378 -0.803976 0.573266 0.0835223 -0.815101 0.861079 0.128709 -0.491911 0.862071 0.129543 -0.489951 0.984809 0.143954 -0.097103 0.985034 0.145193 -0.0928763 0.107666 0.992801 0.0524774 -0.065803 0.970756 -0.230875 0.0365371 0.0861123 -0.995615 0.0264793 0.315037 -0.94871 0.147937 0.445221 -0.883115 -0.0305586 0.314058 -0.948912 0.243965 0.392633 -0.886747 0.0406477 0.261634 -0.964311 0.139627 0.271082 -0.952375 0.153491 0.630028 -0.761252 0.213375 0.673557 -0.707667 0.223964 0.675797 -0.702238 -0.0317129 0.497148 -0.867086 0.198459 0.568412 -0.79845 0.0271116 0.460157 -0.887424 -0.0828032 0.439475 -0.89443 0.00542177 0.843479 -0.537135 -0.0282208 0.863684 -0.503244 0.0361856 0.90936 -0.414432 0.0708569 0.961131 -0.266845 0.0875901 0.966702 -0.240447 0.124388 0.990599 -0.0569261 0.246032 0.770162 -0.588489 0.367196 0.838096 -0.403439 0.219138 0.822857 -0.524294 0.352009 0.923964 -0.149599 0.210172 0.808338 -0.549926 0.0332711 0.695551 -0.717706 -0.0434377 0.644463 -0.763401 0.143032 0.811923 -0.565971 0.0207261 0.739857 -0.672445 0.174616 0.878517 -0.444654 0.0477222 0.829246 -0.556843 0.240023 0.931229 -0.274228 0.135526 0.91857 -0.371299 0.243319 0.966286 -0.0841861 0.296335 0.955042 -0.00894317 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707108 0.707105 0 0.707108 0.707105 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707108 0.707105 0 0.707108 0.707105 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0.0379352 0.999263 -0.00582096 0.0681766 0.996899 -0.0393033 0.0609801 0.997954 -0.0192342 -0.0855496 0.994622 -0.0583777 -0.0729032 0.991693 -0.105972 -0.0549411 0.998378 -0.0149167 -0.0529494 0.991374 -0.11989 -0.0100783 0.999815 -0.0163939 -0.0370189 0.993596 -0.106752 0.017573 0.999002 -0.0410558 -0.0124828 0.99621 -0.0860857 0.0249748 0.997689 -0.0631863 0.0132786 0.997337 -0.0717141 0.0174649 0.997319 -0.071065 0.0675917 0.996131 -0.0561723 0.00924374 0.998861 -0.0468112 0.0149593 0.998776 -0.0471396 0.00652133 0.999023 -0.0437131 0.0724289 0.995383 -0.0629905 0.0726351 0.995357 -0.0631543 -0.0799936 0.996219 -0.033898 -0.0966158 0.994963 -0.026727 -0.0449689 0.995057 -0.0885409 -0.0974659 0.994066 -0.0483051 -0.0849162 0.993568 -0.0749147 0.0231701 0.998754 0.044207 0.0334681 0.998418 -0.045182 0.0349142 0.998629 -0.0390006 0.0365247 0.999244 0.0132947 0.0135912 0.999311 -0.0345437 0.0316396 0.999384 0.015185 -0.000347519 0.999843 -0.0177162 0.0202798 0.99976 0.00834016 -0.00129485 0.999996 -0.0026912 -0.00558677 0.999969 -0.00548343 0.00727825 0.999968 -0.00346421 -0.0524241 0.998436 -0.0194397 0.0114937 0.99949 -0.0297937 0.0122812 0.999479 -0.0298347 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.33267 0.943043 0 0.33267 0.943043 0 0.754961 0.655769 0 0.754961 0.655769 0 0.980317 0.197431 0 0.980317 0.197431 0 0.949948 -0.312409 0 0.949948 -0.312409 0 0.680684 -0.732577 0 0.680684 -0.732577 0 0.253613 -0.967306 0 0.253613 -0.967306 0 -0.233688 -0.972312 0 -0.233688 -0.972312 0 0.838671 -0.544639 0 0.838671 -0.544639 0 -0.413446 -0.910528 0 -0.413446 -0.910528 0 -0.081775 0.996651 0 -0.081775 0.996651 0 0.0213346 0.999772 0 0.0213346 0.999772 0 -0.557031 -0.830492 0 -0.557031 -0.830492 0 -0.858068 -0.513536 0 -0.858068 -0.513536 0 -0.995142 -0.0984518 0 -0.995142 -0.0984518 0 -0.942059 0.335446 0 -0.942059 0.335446 0 -0.708965 0.705244 0 -0.708965 0.705244 0 -0.340395 0.940282 0 -0.340395 0.940282 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.941567 0.336827 0 0.941567 0.336827 0 -0.445072 0.895495 0 -0.445072 0.895495 0 -0.459482 0.888187 0 -0.459482 0.888187 0 -0.999433 0.0336587 0 -0.999433 0.0336587 0 -0.971837 0.235655 0 -0.971837 0.235655 0 -0.834194 0.551471 0 -0.834194 0.551471 0 -0.590192 0.807263 0 -0.590192 0.807263 0 -1 0 0 -1 0 0 0.38356 -0.923516 0 0.38356 -0.923516 0 0.0814144 -0.99668 0 0.0814144 -0.99668 0 -0.380725 -0.924688 0 -0.380725 -0.924688 0 -0.759581 -0.650413 0 -0.759581 -0.650413 0 -0.972271 -0.233857 0 -0.972271 -0.233857 0 -0.245902 0.969295 0 -0.245902 0.969295 0 0.223629 0.974674 0 0.223629 0.974674 0 0.643857 0.765145 0 0.643857 0.765145 0 0.922117 0.38691 0 0.922117 0.38691 0 0.948184 0.317722 0 0.948184 0.317722 0 0.996504 -0.0835419 0 0.996504 -0.0835419 0 0.882049 -0.471158 0 0.882049 -0.471158 0 0.623514 -0.781812 0 0.623514 -0.781812 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.38356 0.923516 0 0.38356 0.923516 7.97624e-08 -0.459481 -0.888188 0 -0.459482 -0.888187 0 -0.445072 -0.895495 0 -0.445072 -0.895495 0 -0.590192 -0.807263 0 -0.590192 -0.807263 0 -0.834195 -0.55147 0 -0.834195 -0.55147 0 -0.971837 -0.235655 0 -0.971837 -0.235655 0 -0.999433 -0.0336585 0 -0.999433 -0.0336585 0 -1 0 0 -1 0 0 -0.972271 0.233857 0 -0.972271 0.233857 0 -0.759579 0.650415 0 -0.759579 0.650415 0 -0.380728 0.924687 0 -0.380728 0.924687 0 0.0814144 0.99668 0 0.0814144 0.99668 0 0.941567 -0.336827 0 0.941567 -0.336827 0 0.922118 -0.386909 0 0.922118 -0.386909 0 0.643856 -0.765147 0 0.643856 -0.765147 0 0.223632 -0.974674 0 0.223632 -0.974674 0 -0.245905 -0.969294 4.26872e-08 -0.245905 -0.969294 0 0.623514 0.781812 0 0.623514 0.781812 0 0.882049 0.471158 0 0.882049 0.471158 0 0.996504 0.0835416 0 0.996504 0.0835416 0 0.948184 -0.317722 0 0.948184 -0.317722 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.83867 0.544639 0 0.83867 0.544639 0 -0.340398 -0.940281 0 -0.340398 -0.940281 0 -0.708965 -0.705244 0 -0.708965 -0.705244 0 -0.942059 -0.335447 0 -0.942059 -0.335447 0 -0.995142 0.0984518 0 -0.995142 0.0984518 0 -0.858069 0.513535 0 -0.858069 0.513535 0 -0.557031 0.830492 0 -0.557031 0.830492 0 -0.413446 0.910529 0 -0.413446 0.910529 0 0.0213346 -0.999772 0 0.0213346 -0.999772 0 -0.0817741 -0.996651 0 -0.0817741 -0.996651 0 -0.233688 0.972312 0 -0.233688 0.972312 0 0.25361 0.967306 0 0.25361 0.967306 0 0.680686 0.732575 0 0.680686 0.732575 0 0.949948 0.312409 0 0.949948 0.312409 0 0.980317 -0.197431 0 0.980317 -0.197431 0 0.754961 -0.655769 0 0.754961 -0.655769 0 0.33267 -0.943043 0 0.33267 -0.943043 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.463583 0.70709 -0.533962 0.6284 0.704514 -0.32981 0.0855434 0.704515 0.704515 0.281904 0.479656 0.83094 0.329992 -0.366062 0.870117 0.184928 0.699623 0.690167 0.171381 0.707106 0.686025 0.0855434 0.704515 0.704515 0.540633 -0.307001 0.783241 0.356439 0.70675 0.61111 0.295557 0.706618 0.642913 0.732756 -0.204091 0.649165 0.589141 0.553014 0.589142 0.481155 0.707012 0.51829 0.427905 0.706081 0.564222 0.818014 0.551271 0.164174 0.66351 0.70709 0.244495 0.6284 0.704514 0.32981 0.628401 0.704512 0.32981 0.568862 0.706922 0.420306 0.750944 -0.0474522 0.658659 0.897002 -0.38276 0.221091 0.965389 0.033363 0.258673 0.729256 0.643235 0.233311 0.700756 0.70707 0.0948341 0.709693 0.704511 0 0.709693 0.704511 0 0.671734 0.706772 -0.221917 0.965389 0.033363 -0.258673 0.897002 -0.382761 -0.221091 0.818015 0.551271 -0.164174 0.700756 0.70707 -0.0948341 0.481155 0.707012 -0.51829 0.589144 0.553008 -0.589144 0.732757 -0.204087 -0.649166 0.547282 0.705862 -0.449712 0.628402 0.704511 -0.329811 0.503536 0.339156 -0.794622 0.540633 -0.307001 -0.783241 0.575732 -0.0343189 -0.816918 0.475923 0.653575 -0.588504 0.171371 0.707106 -0.686028 0.184933 0.699614 -0.690174 0.338619 0.296866 -0.892865 0.262651 0.705198 -0.658567 0.351536 0.70687 -0.613806 0.0569825 0.705958 -0.705958 0.116619 -0.252893 -0.96044 0.148924 0.559058 -0.815645 0.154937 0.707031 -0.690001 0.550066 0 -0.835122 0.258819 0 -0.965926 0.258819 0 -0.965926 0.704606 0.0840343 -0.704606 0.704606 0.0840344 -0.704606 0.835121 0 -0.550067 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258818 0.965926 0 0.258818 0.707106 0 0.707107 0.707106 0 0.707107 0.258819 0 0.965926 0.258819 0 0.965926 0.893931 0 -0.448204 0.707106 0 -0.707107 0.707106 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.96251 0.0840353 -0.257902 0.96251 0.0840349 -0.257902 0.998269 0 -0.0588079 0.965926 0 0.258818 0.965926 0 0.258818 0.707106 0 0.707107 0.707106 0 0.707107 0.258819 0 0.965926 0.258819 0 0.965926 0.998269 0 0.0588079 0.965926 0 -0.258818 0.965926 0 -0.258818 0.707106 0 -0.707107 0.707106 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.96251 0.0840348 0.257902 0.96251 0.084035 0.257902 0.893932 0 0.448203 0.707106 0 0.707108 0.707106 0 0.707108 0.258819 0 0.965926 0.258819 0 0.965926 0.978461 -0.174529 -0.110247 1 0 0 0.930874 0 -0.36534 0.898154 -0.0789919 -0.432528 0.826238 0 -0.563321 0.62349 0 -0.781831 0.651148 -0.0590898 -0.756647 0.221995 0.0686864 -0.972626 0.258818 0 -0.965926 0.993712 0 0.111965 0.930874 0 0.36534 0.906017 -0.0622379 0.41864 0.82622 0.00667546 0.563309 0.707031 -0.0145054 0.707033 0.651357 0.0533949 0.75689 0.518393 -0.0156428 0.854999 0.258366 0.0590899 0.964238 0.22252 0 0.974928 0.222521 0 -0.974928 0.258367 -0.0590896 -0.964238 0.467269 0 -0.884115 0.652287 0 -0.757972 0.703678 -0.0983614 -0.703678 0.826239 0 -0.56332 0.965926 0 -0.258819 0.911701 -0.201915 -0.357816 0.993712 0 -0.111965 0.993712 0 0.111965 0.95919 -0.117891 0.257014 0.930874 0 0.365341 0.826239 0 0.56332 0.703678 -0.0983611 0.703677 0.652288 0 0.757971 0.448204 0 0.893931 0.467245 -0.00896843 0.884083 0.258736 0.0251338 0.965621 0.221993 0.0687882 0.972619 0.0588079 0 0.998269 0.258818 0 0.965926 0.258818 0 0.965926 0.707107 0 0.707106 0.707107 0 0.707106 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.22252 0 0.974928 0.22252 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.62349 0 -0.781831 0.62349 0 -0.781831 0.22252 0 -0.974928 0.22252 0 -0.974928 0.222521 0 0.974928 0.222521 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900969 0 0.433883 0.900969 0 0.433883 1 0 0 1 0 0 0.900969 0 -0.433883 0.900969 0 -0.433883 0.62349 0 -0.781831 0.62349 0 -0.781831 0.222521 0 -0.974928 0.222521 0 -0.974928 0.258819 0 0.965926 0.258819 0 0.965926 0.707106 0 0.707107 0.707106 0 0.707107 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707106 0 -0.707107 0.707106 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.622729 -0.0493942 0.780877 0.258367 0.0590896 0.964238 0.222522 0 0.974928 0.993712 0 0.111965 0.930874 0 0.365341 0.898153 -0.0789914 0.432528 0.826238 0 0.563321 0.652287 0 0.757972 0.978461 -0.174529 -0.110246 1 0 0 0.930873 0 -0.365342 0.898153 -0.0789906 -0.432528 0.826239 0 -0.56332 0.62349 0 -0.781832 0.651147 -0.0590896 -0.756648 0.221996 0.0686861 -0.972625 0.25882 0 -0.965926 0.22252 0 0.974928 0.22252 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.623489 0 -0.781832 0.623489 0 -0.781832 0.22252 0 -0.974928 0.22252 0 -0.974928 0.0588079 0 -0.998269 0.257905 0.0840361 -0.962509 0.257904 0.0840345 -0.962509 0.448204 0 -0.893931 0.707106 0 -0.707107 0.707106 0 -0.707107 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.707107 0 0.707106 0.707107 0 0.707106 0.258819 0 0.965926 0.258819 0 0.965926 0.186157 0.694747 0.694747 0.186157 0.694745 0.694749 0.50859 0.694745 0.508591 0.508588 0.69475 0.508587 0.694745 0.694749 0.186156 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186156 0.694745 0.694748 -0.186156 0.508589 0.694748 -0.508589 0.508589 0.694748 -0.508589 0.186157 0.694748 -0.694745 0.186157 0.694747 -0.694746 -0.126662 0.701412 -0.701412 -0.126661 0.701412 -0.701411 -0.166266 0.697268 -0.697261 -0.166268 0.697264 -0.697264 -0.463019 0.697264 -0.547207 -0.463019 0.697265 -0.547207 -0.660125 0.697265 -0.279386 -0.660126 0.697264 -0.279386 -0.0965204 0.703809 -0.703802 -0.0965227 0.703803 -0.703807 -0.156156 0.698432 -0.698432 -0.156156 0.698432 -0.698433 -0.438732 0.698432 -0.565426 -0.438732 0.698431 -0.565427 -0.637758 0.698431 -0.324744 -0.637757 0.698432 -0.324743 -0.144415 0.699694 -0.699694 -0.144415 0.699694 -0.699695 -0.129156 0.701184 -0.701184 -0.129155 0.701186 -0.701183 -0.370514 0.701186 -0.609145 -0.370516 0.701184 -0.609146 0.186158 0.694746 0.694747 0.186157 0.694746 0.694747 0.50859 0.694746 0.50859 0.508588 0.694748 0.50859 0.694745 0.694748 0.186157 0.694748 0.694746 0.186155 0.694748 0.694745 -0.186157 0.694746 0.694747 -0.186155 0.50859 0.694747 -0.50859 0.50859 0.694746 -0.508591 0.186156 0.694746 -0.694747 0.186156 0.694747 -0.694747 0.159331 0.698074 0.698074 0.159331 0.698074 0.698074 0.446434 0.698073 0.559813 0.446434 0.698073 0.559813 0.645118 0.698073 0.310672 0.645119 0.698072 0.310671 0.716028 0.698072 0 0.716028 0.698072 0 0.645119 0.698072 -0.310673 0.645118 0.698073 -0.310671 0.446434 0.698073 -0.559813 0.446434 0.698073 -0.559813 0.159331 0.698073 -0.698074 0.159331 0.698074 -0.698074 0.186158 0.694745 0.694748 0.186158 0.694746 0.694748 0.50859 0.694746 0.50859 0.50859 0.694746 0.50859 0.694747 0.694746 0.186157 0.694747 0.694747 0.186157 0.694746 0.694746 -0.186158 0.694746 0.694747 -0.186157 0.50859 0.694747 -0.50859 0.50859 0.694747 -0.50859 0.186157 0.694747 -0.694746 0.186157 0.694747 -0.694747 0.159328 0.698075 0.698073 0.159332 0.698072 0.698075 0.446436 0.698072 0.559812 0.446434 0.698074 0.559812 0.645117 0.698074 0.310671 0.645117 0.698074 0.310671 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310673 0.645117 0.698074 -0.310672 0.446435 0.698074 -0.55981 0.446435 0.698074 -0.55981 0.159331 0.698075 -0.698072 0.159329 0.698073 -0.698075 0.186158 0.694745 0.694748 0.186158 0.694746 0.694748 0.50859 0.694746 0.50859 0.50859 0.694746 0.50859 0.694746 0.694747 0.186157 0.694747 0.694747 0.186157 0.694746 0.694746 -0.186158 0.694746 0.694747 -0.186157 0.508589 0.694747 -0.508589 0.508589 0.694747 -0.50859 0.186157 0.694747 -0.694746 0.186157 0.694747 -0.694747 0.186157 0.694747 0.694747 0.186157 0.694747 0.694746 0.508588 0.694747 0.50859 0.508591 0.694746 0.50859 0.694748 0.694745 0.186158 0.694748 0.694745 0.186158 0.694748 0.694745 -0.186158 0.694748 0.694745 -0.186158 0.50859 0.694745 -0.508592 0.50859 0.694747 -0.508589 0.186157 0.694747 -0.694746 0.186157 0.694747 -0.694747 0.159332 0.698073 0.698074 0.15933 0.698074 0.698074 0.446436 0.698073 0.559811 0.446434 0.698075 0.559812 0.645116 0.698075 0.310672 0.645117 0.698074 0.310671 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310672 0.645117 0.698074 -0.310671 0.446435 0.698074 -0.559811 0.446435 0.698073 -0.559812 0.15933 0.698073 -0.698074 0.15933 0.698074 -0.698074 0.15933 0.698074 0.698074 0.159331 0.698074 0.698074 0.446436 0.698074 0.559811 0.446434 0.698075 0.559811 0.645116 0.698075 0.310672 0.645117 0.698074 0.310671 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310671 0.645117 0.698074 -0.310672 0.446434 0.698073 -0.559814 0.446435 0.698075 -0.55981 0.159332 0.698075 -0.698072 0.159331 0.698075 -0.698072 0.15933 0.698074 0.698074 0.159331 0.698074 0.698074 0.446436 0.698074 0.559811 0.446434 0.698075 0.559811 0.645116 0.698075 0.310672 0.645117 0.698074 0.310671 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310671 0.645117 0.698074 -0.310672 0.446434 0.698073 -0.559814 0.446435 0.698075 -0.55981 0.159332 0.698075 -0.698072 0.159331 0.698075 -0.698072 0.186157 0.694747 0.694747 0.186157 0.694746 0.694747 0.508591 0.694745 0.508592 0.508587 0.694751 0.508587 0.694743 0.694751 0.186155 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186156 0.694742 0.694751 -0.186156 0.508587 0.69475 -0.508588 0.508592 0.694744 -0.508591 0.186157 0.694745 -0.694748 0.186157 0.694747 -0.694747 0.186157 0.694747 0.694747 0.186157 0.694745 0.694748 0.508591 0.694744 0.508592 0.508587 0.694751 0.508586 0.694742 0.694752 0.186155 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186156 0.694742 0.694751 -0.186155 0.508587 0.69475 -0.508588 0.508591 0.694745 -0.508591 0.186157 0.694747 -0.694746 0.186157 0.694747 -0.694746 0.508589 0.694748 0.508589 0.186156 0.694748 0.694745 0.186156 0.694747 0.694747 0.335655 0.857441 0.390038 0.585055 0.706117 0.398885 0.694745 0.694748 0.186156 0.414109 0.8956 0.162525 0.704873 0.704873 0.0794203 0.704873 0.704873 -0.0794205 0.514435 0.846379 -0.137842 0.661913 0.703126 -0.259781 0.585055 0.706117 -0.398885 0.394992 0.829435 -0.394992 0.465274 0.700863 -0.540658 0.186156 0.694748 -0.694746 0.186157 0.694747 -0.694747 0.15933 0.698074 0.698074 0.15933 0.698072 0.698076 0.330521 0.706858 0.625386 0.392438 0.777064 0.492102 0.465276 0.700861 0.54066 0.585057 0.706115 0.398885 0.525931 0.811941 0.253275 0.661912 0.703126 0.259781 0.704872 0.704874 0.0794202 0.569554 0.821954 0 0.704872 0.704874 -0.0794202 0.645115 0.698075 -0.310671 0.498578 0.84447 -0.195678 0.585054 0.706119 -0.398883 0.446433 0.698078 -0.559808 0.402222 0.787251 -0.46739 0.330524 0.706861 -0.625381 0.159331 0.698075 -0.698072 0.159331 0.698074 -0.698074 0.186156 0.694747 0.694747 0.186155 0.694751 0.694742 0.508588 0.694751 0.508587 0.508591 0.694744 0.508592 0.694747 0.694746 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186157 0.694747 0.694746 -0.186157 0.508591 0.694744 -0.508591 0.508588 0.694748 -0.508589 0.186157 0.694748 -0.694745 0.186157 0.694747 -0.694746 0.15933 0.698074 0.698074 0.15933 0.698075 0.698072 0.446434 0.698075 0.55981 0.446436 0.698071 0.559814 0.645119 0.698072 0.310673 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310672 0.645119 0.698072 -0.310673 0.446437 0.698071 -0.559813 0.446434 0.698075 -0.559811 0.15933 0.698075 -0.698072 0.159331 0.698074 -0.698074 0.159331 0.698074 0.698074 0.159331 0.698073 0.698074 0.446435 0.698074 0.559812 0.446434 0.698075 0.559811 0.645116 0.698075 0.310671 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310672 0.645115 0.698076 -0.310671 0.446434 0.698075 -0.55981 0.446435 0.698074 -0.559811 0.159331 0.698074 -0.698073 0.15933 0.698075 -0.698073 0.186157 0.694747 0.694747 0.186157 0.694746 0.694747 0.508591 0.694745 0.508592 0.508589 0.694748 0.508589 0.694745 0.694748 0.186156 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186156 0.694745 0.694748 -0.186156 0.508589 0.694748 -0.50859 0.508592 0.694744 -0.508592 0.186157 0.694745 -0.694748 0.186157 0.694747 -0.694747 0.508591 0.694745 0.50859 0.186157 0.694745 0.694749 0.186157 0.694747 0.694747 0.335653 0.857443 0.390037 0.585054 0.706119 0.398884 0.694744 0.694749 0.186157 0.414107 0.895601 0.162525 0.704873 0.704873 0.0794203 0.704873 0.704873 -0.0794203 0.514433 0.84638 -0.137842 0.661912 0.703126 -0.259782 0.585056 0.706117 -0.398884 0.394991 0.829436 -0.394991 0.465274 0.700863 -0.540658 0.186157 0.694748 -0.694745 0.186157 0.694747 -0.694747 0.15933 0.698074 0.698074 0.15933 0.698075 0.698072 0.446434 0.698075 0.55981 0.446435 0.698072 0.559813 0.645118 0.698073 0.310672 0.645118 0.698072 0.310673 0.716026 0.698074 0 0.716026 0.698074 0 0.645115 0.698075 -0.310671 0.645115 0.698076 -0.310671 0.446432 0.698078 -0.559809 0.446437 0.698072 -0.559812 0.159331 0.698072 -0.698076 0.15933 0.698074 -0.698074 0.186156 0.694747 0.694747 0.186156 0.694748 0.694745 0.50859 0.694747 0.508589 0.508591 0.694745 0.508591 0.694746 0.694747 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186157 0.694744 0.694749 -0.186157 0.508587 0.69475 -0.508588 0.508591 0.694745 -0.50859 0.186158 0.694745 -0.694748 0.186157 0.694747 -0.694747 -0.177707 0 -0.984083 -0.177707 0 -0.984083 -0.18115 0 0.983455 -0.174135 0.00100168 0.984721 -0.519671 -0.00104035 0.854366 -0.513569 0 0.858049 -0.231953 0 -0.972727 -0.231953 0 -0.972727 -0.64594 0 -0.763388 -0.64594 0 -0.763388 -0.920916 0 -0.389761 -0.920916 0 -0.389761 -0.0142608 0 0.999898 -0.202136 0.00208066 0.979355 -0.216076 0 0.976377 -0.13587 0 -0.990727 -0.13587 0 -0.990727 -0.218194 0 -0.975905 -0.218194 0 -0.975905 -0.613031 0 -0.790059 -0.613031 0 -0.790059 -0.891125 0 -0.453757 -0.891125 0 -0.453757 0.25882 0 0.965926 0.25882 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258818 0 -0.965926 0.258818 0 -0.965926 0.222521 0 0.974928 0.258818 0.00363668 0.965919 0.623486 -0.00303831 0.781829 0.652286 0 0.757973 0.826239 0 0.563319 0.900958 -0.00486816 0.433879 0.930874 0 0.365341 0.993713 0 0.111956 0.999985 -0.00547881 0 0.993713 0 -0.111956 0.930874 0 -0.365341 0.900958 -0.00486816 -0.433879 0.826239 0 -0.56332 0.623489 0 -0.781832 0.652281 -0.00363659 -0.757968 0.222519 0.00422991 -0.974919 0.258819 0 -0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707107 0.707107 0 -0.707107 0.25882 0 -0.965926 0.25882 0 -0.965926 0.222517 0 0.974929 0.258818 0.00363709 0.965919 0.623488 -0.00303805 0.781827 0.652286 0 0.757973 0.826239 0 0.563319 0.900959 -0.00486819 0.433878 0.930874 0 0.36534 0.993712 0 0.111965 0.999985 -0.00547926 0 0.993712 0 -0.111964 0.930873 0 -0.365343 0.900958 -0.00486812 -0.43388 0.826239 0 -0.563319 0.623491 0 -0.781831 0.652285 -0.00363675 -0.757965 0.22252 0.00422981 -0.974919 0.25882 0 -0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707107 0.707107 0 -0.707107 0.25882 0 -0.965926 0.25882 0 -0.965926 0.258819 0 0.965926 0.258819 0 0.965926 0.707106 0 0.707108 0.707106 0 0.707108 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707106 0 -0.707108 0.707106 0 -0.707108 0.258819 0 -0.965926 0.258819 0 -0.965926 0.222522 0 0.974928 0.258818 0.00363663 0.965919 0.623488 -0.00303839 0.781827 0.652289 0 0.757971 0.826236 0 0.563324 0.900958 -0.00486836 0.433879 0.930875 0 0.365338 0.993712 0 0.111966 0.999985 -0.0054793 0 0.993712 0 -0.111965 0.930875 0 -0.365338 0.900958 -0.00486836 -0.433879 0.826236 0 -0.563324 0.623491 0 -0.781831 0.652284 -0.0036367 -0.757966 0.222518 0.00422987 -0.97492 0.258817 0 -0.965926 0.22252 0 0.974928 0.258818 0.00363686 0.965919 0.623488 -0.00303821 0.781827 0.652287 0 0.757972 0.826237 0 0.563323 0.900958 -0.00486825 0.433879 0.930874 0 0.36534 0.993712 0 0.111966 0.999985 -0.0054793 0 0.993712 0 -0.111966 0.930873 0 -0.365342 0.900959 -0.00486807 -0.433878 0.826242 0 -0.563316 0.623488 0 -0.781833 0.652281 -0.00363663 -0.757969 0.22252 0.00422982 -0.974919 0.25882 0 -0.965926 0.22252 0 0.974928 0.258818 0.00363686 0.965919 0.623488 -0.00303821 0.781827 0.652287 0 0.757972 0.826237 0 0.563323 0.900958 -0.00486825 0.433879 0.930874 0 0.36534 0.993712 0 0.111966 0.999985 -0.0054793 0 0.993712 0 -0.111966 0.930873 0 -0.365342 0.900959 -0.00486807 -0.433878 0.826242 0 -0.563316 0.623488 0 -0.781833 0.652281 -0.00363663 -0.757969 0.22252 0.00422982 -0.974919 0.25882 0 -0.965926 0.159331 0.698074 0.698074 0.15933 0.698075 0.698073 0.446434 0.698075 0.55981 0.446435 0.698075 0.55981 0.645116 0.698075 0.310672 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310672 0.645116 0.698075 -0.310671 0.446434 0.698074 -0.559812 0.446434 0.698075 -0.559811 0.159331 0.698075 -0.698072 0.159331 0.698075 -0.698073 0.510203 0.849119 0.136709 0.373495 0.849119 0.373495 0.136709 0.849119 0.510203 0.136708 0.84912 -0.510203 0.373494 0.849119 -0.373494 0.510203 0.849119 -0.136709 0.136709 0.849119 0.510203 0.42642 0.85653 0.290728 0.514174 0.855727 0.0579288 0.483396 0.854596 -0.189719 0.136709 0.849119 -0.510203 0.340301 0.853126 -0.395439 0.42642 0.85653 -0.290728 0.514174 0.855727 -0.0579288 0.483396 0.854596 0.189719 0.340301 0.853126 0.395439 0.510203 0.849119 0.136709 0.373494 0.849119 0.373494 0.136709 0.84912 0.510202 0.136709 0.849119 -0.510203 0.373495 0.849119 -0.373495 0.510203 0.849119 -0.136709 0.136709 0.849119 0.510203 0.426421 0.856529 0.290728 0.514173 0.855727 0.0579339 0.483396 0.854596 -0.18972 0.136709 0.84912 -0.510202 0.340303 0.853126 -0.395437 0.426421 0.856529 -0.290728 0.514173 0.855727 -0.0579333 0.483397 0.854596 0.189719 0.340301 0.853126 0.395439 0.510203 0.849119 0.136709 0.373494 0.849119 0.373494 0.136709 0.84912 0.510202 0.136709 0.849119 -0.510203 0.373495 0.849119 -0.373495 0.510203 0.849119 -0.136709 0.510202 0.84912 0.136709 0.373494 0.849119 0.373495 0.136709 0.849119 0.510203 0.136709 0.849119 -0.510203 0.373494 0.849119 -0.373495 0.510202 0.84912 -0.136709 0.136709 0.849119 0.510203 0.426419 0.856529 0.290731 0.514173 0.855727 0.0579341 0.483397 0.854596 -0.189718 0.136708 0.84912 -0.510203 0.340302 0.853126 -0.395437 0.426419 0.856529 -0.290731 0.514173 0.855727 -0.0579338 0.483397 0.854596 0.189718 0.340302 0.853126 0.395437 0.136709 0.849119 0.510203 0.42642 0.856529 0.29073 0.514173 0.855727 0.0579341 0.483397 0.854596 -0.18972 0.136709 0.849119 -0.510203 0.340301 0.853126 -0.395439 0.426422 0.856529 -0.290726 0.514173 0.855727 -0.0579341 0.483397 0.854596 0.189719 0.340302 0.853126 0.395438 0.136709 0.849119 0.510203 0.42642 0.856529 0.29073 0.514173 0.855727 0.0579341 0.483397 0.854596 -0.18972 0.136709 0.849119 -0.510203 0.340301 0.853126 -0.395439 0.426422 0.856529 -0.290726 0.514173 0.855727 -0.0579341 0.483397 0.854596 0.189719 0.340302 0.853126 0.395438 0.15933 0.698074 0.698073 0.159331 0.698074 0.698073 0.446436 0.698073 0.559812 0.446433 0.698075 0.559812 0.645116 0.698075 0.310671 0.645117 0.698074 0.310671 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310671 0.645117 0.698075 -0.310671 0.446434 0.698075 -0.559811 0.446434 0.698073 -0.559813 0.159331 0.698074 -0.698073 0.159331 0.698074 -0.698073 0.186157 0.694747 0.694746 0.186156 0.694747 0.694746 0.508589 0.694748 0.508589 0.50859 0.694747 0.508589 0.694746 0.694747 0.186158 0.694746 0.694746 0.186158 0.694746 0.694746 -0.186158 0.694746 0.694747 -0.186158 0.508589 0.694747 -0.50859 0.508589 0.694748 -0.508588 0.186157 0.694748 -0.694745 0.186157 0.694747 -0.694746 0.186156 0.694748 0.694746 0.186157 0.694747 0.694746 0.50859 0.694747 0.50859 0.50859 0.694747 0.50859 0.694746 0.694747 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186157 0.694746 0.694747 -0.186157 0.50859 0.694747 -0.50859 0.50859 0.694747 -0.50859 0.186156 0.694747 -0.694747 0.186157 0.694748 -0.694746 0.186156 0.694748 0.694746 0.186157 0.694747 0.694746 0.50859 0.694747 0.508589 0.508589 0.694748 0.508589 0.694746 0.694747 0.186157 0.694746 0.694747 0.186157 0.694746 0.694747 -0.186157 0.694746 0.694747 -0.186156 0.508589 0.694748 -0.508589 0.508589 0.694747 -0.50859 0.186156 0.694747 -0.694747 0.186157 0.694749 -0.694744 0.15933 0.698075 0.698073 0.159331 0.698074 0.698073 0.446435 0.698074 0.559811 0.446435 0.698074 0.559811 0.645117 0.698074 0.310672 0.645116 0.698075 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645116 0.698074 -0.310672 0.645117 0.698074 -0.310672 0.446435 0.698074 -0.559811 0.446435 0.698074 -0.559811 0.15933 0.698074 -0.698074 0.159332 0.698076 -0.698071 0.186155 0.694748 0.694746 0.186157 0.694747 0.694746 0.50859 0.694747 0.508589 0.508589 0.694748 0.508589 0.694745 0.694748 0.186157 0.694746 0.694748 0.186157 0.694746 0.694748 -0.186157 0.694745 0.694748 -0.186156 0.50859 0.694748 -0.508588 0.50859 0.694747 -0.50859 0.186156 0.694747 -0.694747 0.186156 0.694748 -0.694746 0.186157 0.694747 0.694746 0.186156 0.694747 0.694746 0.508589 0.694748 0.508589 0.50859 0.694747 0.508589 0.694747 0.694747 0.186156 0.694744 0.694749 0.186157 0.694745 0.694749 -0.186155 0.694746 0.694747 -0.186158 0.508589 0.694747 -0.50859 0.508589 0.694748 -0.508588 0.186157 0.694748 -0.694745 0.186157 0.694747 -0.694746 0.159331 0.698074 0.698073 0.159331 0.698074 0.698073 0.446433 0.698075 0.559812 0.446435 0.698074 0.559812 0.645118 0.698073 0.310672 0.645117 0.698074 0.310673 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310671 0.645118 0.698073 -0.310673 0.446434 0.698073 -0.559813 0.446434 0.698075 -0.559811 0.159331 0.698075 -0.698073 0.159331 0.698074 -0.698073 0.186157 0.694747 0.694747 0.186157 0.694747 0.694746 0.50859 0.694747 0.508589 0.508588 0.694748 0.508589 0.694745 0.694748 0.186157 0.694746 0.694748 0.186156 0.694746 0.694748 -0.186157 0.694745 0.694748 -0.186156 0.508589 0.694748 -0.508589 0.508589 0.694748 -0.508589 0.186156 0.694748 -0.694745 0.186156 0.694748 -0.694746 0.186156 0.694747 0.694747 0.186156 0.694747 0.694747 0.50859 0.694747 0.508589 0.508588 0.694748 0.508589 0.694745 0.694748 0.186157 0.694746 0.694747 0.186157 0.694746 0.694747 -0.186157 0.694746 0.694748 -0.186156 0.508589 0.694748 -0.508589 0.508589 0.694747 -0.50859 0.186158 0.694747 -0.694746 0.186158 0.694746 -0.694746 0.15933 0.698074 0.698074 0.15933 0.698074 0.698074 0.446435 0.698074 0.559811 0.446434 0.698074 0.559811 0.645117 0.698074 0.310672 0.645116 0.698075 0.310672 0.716025 0.698074 0 0.716025 0.698074 0 0.645117 0.698074 -0.310673 0.645116 0.698075 -0.310671 0.446434 0.698076 -0.55981 0.446434 0.698076 -0.55981 0.159332 0.698076 -0.698071 0.15933 0.698074 -0.698074 0.222522 0 0.974928 0.222522 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900969 0 0.433885 0.900969 0 0.433885 1 0 0 1 0 0 0.900969 0 -0.433885 0.900969 0 -0.433885 0.623489 0 -0.781832 0.623489 0 -0.781832 0.222522 0 -0.974928 0.222522 0 -0.974928 0.22252 0 0.974928 0.258817 0.00371759 0.965919 0.623487 -0.00310584 0.781827 0.652287 0 0.757972 0.826241 0 0.563317 0.900958 -0.00497636 0.433878 0.930873 0 0.365342 0.993712 0 0.111968 0.999984 -0.00560132 0 0.993712 0 -0.111968 0.930873 0 -0.365342 0.900958 -0.00497635 -0.433878 0.826241 0 -0.563317 0.62349 0 -0.781831 0.652281 -0.00371736 -0.757968 0.222519 0.00432403 -0.974919 0.25882 0 -0.965926 0.22252 0 0.974928 0.258817 -0.00371763 0.965919 0.467275 0 0.884112 0.652286 0 0.757973 0.707093 -0.00620758 0.707093 0.826241 0 0.563317 0.930874 0 0.365341 0.965899 -0.00745578 0.258814 0.993712 0 0.111968 0.993712 0 -0.111968 0.965899 -0.00745578 -0.258814 0.930874 0 -0.365341 0.826241 0 -0.563317 0.707093 -0.00620759 -0.707094 0.652286 0 -0.757973 0.467273 0 -0.884113 0.258818 -0.00371758 -0.965919 0.222521 0 -0.974928 0.22252 0 0.974928 0.258816 -0.00371755 0.965919 0.467268 0 0.884116 0.652288 0 0.757971 0.707093 -0.00620743 0.707093 0.826238 0 0.563321 0.930874 0 0.365341 0.965899 -0.00745588 0.258812 0.993712 0 0.111965 0.993712 0 -0.111964 0.965899 -0.00745591 -0.258812 0.930874 0 -0.365341 0.826238 0 -0.563321 0.707093 -0.00620743 -0.707093 0.652288 0 -0.757971 0.467268 0 -0.884116 0.258816 -0.00371755 -0.965919 0.22252 0 -0.974928 0.258818 0 0.965926 0.258818 0 0.965926 0.707107 0 0.707106 0.707107 0 0.707106 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707107 0 -0.707106 0.707107 0 -0.707106 0.258818 0 -0.965926 0.258818 0 -0.965926 0.22252 0 0.974928 0.258816 0.00371753 0.96592 0.623487 -0.00310601 0.781828 0.652288 0 0.757971 0.826239 0 0.563319 0.900958 -0.00497644 0.433878 0.930874 0 0.365341 0.993712 0 0.111965 0.999984 -0.00560112 0 0.993712 0 -0.111965 0.930874 0 -0.365341 0.900958 -0.00497644 -0.433878 0.826239 0 -0.563319 0.62349 0 -0.781832 0.652283 -0.00371763 -0.757966 0.222518 0.00432393 -0.974919 0.258818 0 -0.965926 0.258817 0 0.965926 0.258817 0 0.965926 0.707108 0 0.707106 0.707108 0 0.707106 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707108 0 -0.707106 0.707108 0 -0.707106 0.258817 0 -0.965926 0.258817 0 -0.965926 0.258819 0 0.965926 0.258819 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258818 0.965926 0 -0.258818 0.707106 0 -0.707107 0.707106 0 -0.707107 0.25882 0 -0.965926 0.25882 0 -0.965926 0.222521 0 0.974928 0.222521 0 0.974928 0.623488 0 0.781833 0.623488 0 0.781833 0.900969 0 0.433883 0.900969 0 0.433883 1 0 0 1 0 0 0.900969 0 -0.433883 0.900969 0 -0.433883 0.623488 0 -0.781833 0.623488 0 -0.781833 0.222522 0 -0.974928 0.222522 0 -0.974928 0.258819 0 0.965926 0.258819 0 0.965926 0.707108 0 0.707106 0.707108 0 0.707106 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.258818 0 0.965926 0.258818 0 0.965926 0.707107 0 0.707106 0.707107 0 0.707106 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707106 0.707107 0 -0.707106 0.258821 0 -0.965925 0.258821 0 -0.965925 0.22252 0 0.974928 0.22252 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900968 0 -0.433885 0.900968 0 -0.433885 0.62349 0 -0.781831 0.62349 0 -0.781831 0.222524 0 -0.974927 0.222524 0 -0.974927 0.937489 0 -0.348014 0.287553 0.219467 -0.932281 0.251839 0.704005 -0.664044 0.390756 0 -0.920494 0.120536 0 -0.992709 0.120536 0 -0.992709 0.240865 0 -0.970559 0.258808 0.00911418 -0.965886 0.502036 0 -0.864847 0.394504 0.719521 -0.571538 0.602622 0 -0.798027 0.598186 0.609034 -0.520817 0.532532 0.702731 -0.471782 0.68411 0.252954 -0.68411 0.679221 0 -0.733934 0.885456 0 -0.464723 0.885456 0 -0.464723 0.805526 0 -0.59256 0.951616 0.2425 -0.188735 0.642274 0.749949 -0.158306 0.766918 0.607955 -0.205495 0.947263 0.0912189 -0.307199 1 0 0 1 0 0 0.991063 0 -0.133395 0.949036 0 0.315169 0.766918 0.607955 0.205495 0.642274 0.749949 0.158306 0.951616 0.2425 0.188735 0.991063 0 0.133394 0.885456 0 0.464723 0.885456 0 0.464723 0.773605 0 0.633668 0.532532 0.702732 0.471782 0.684112 0.252943 0.684113 0.626853 0.111035 0.771185 0.654352 0 0.75619 0.679222 0 0.733933 0.462498 0.59933 0.653375 0.394504 0.719521 0.571538 0.472611 0.473952 0.742973 0.258808 0.00912857 0.965886 0.287552 0.219481 0.932278 0.251837 0.704008 0.664041 0.390756 0 0.920494 0.500294 0 0.865855 0.120537 0 0.992709 0.120537 0 0.992709 0.240836 0 0.970566 0.159331 -0.698075 0.698072 0.159331 -0.698074 0.698074 0.446437 -0.698071 0.559814 0.446435 -0.698074 0.559811 0.604504 -0.704477 0.371871 0.507578 -0.826205 0.244437 0.159331 -0.698074 -0.698074 0.159331 -0.698073 -0.698075 0.446438 -0.69807 -0.559814 0.446435 -0.698073 -0.559812 0.645118 -0.698073 -0.310672 0.645117 -0.698074 -0.310672 0.716026 -0.698074 0 0.54547 -0.837371 -0.0356687 0.778278 -0.59228 0.208538 0.418711 -0.80583 0.418712 0.186157 -0.694747 0.694747 0.186157 -0.694748 0.694745 0.382086 -0.706719 0.595449 0.418712 -0.805829 0.418712 0.186156 -0.694747 -0.694747 0.186157 -0.694745 -0.694749 0.508591 -0.694745 -0.508591 0.508591 -0.694745 -0.508591 0.694749 -0.694745 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694747 0.186156 0.694749 -0.694745 0.186157 0.595453 -0.706716 0.382085 0.153259 -0.805831 0.571969 0.153259 -0.805828 0.571973 0.0331733 -0.706718 0.706718 0.186156 -0.69475 -0.694744 0.186157 -0.694748 -0.694745 0.508589 -0.694748 -0.508589 0.508592 -0.694744 -0.508591 0.694748 -0.694745 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694747 0.186157 0.694746 -0.694747 0.186157 0.508588 -0.694749 0.508588 0.508587 -0.69475 0.508587 0.32463 -0.706722 0.628617 0.15933 -0.698077 -0.69807 0.159331 -0.698075 -0.698072 0.446434 -0.698075 -0.559811 0.446436 -0.698072 -0.559813 0.645118 -0.698073 -0.310672 0.645115 -0.698075 -0.310671 0.716026 -0.698074 0 0.716026 -0.698074 0 0.645118 -0.698073 0.310673 0.645117 -0.698073 0.310672 0.446436 -0.698072 0.559812 0.446436 -0.698072 0.559813 0.159331 -0.698072 0.698076 0.159331 -0.698074 0.698074 0.186156 -0.694747 -0.694747 0.186157 -0.694745 -0.694749 0.508591 -0.694745 -0.508591 0.508589 -0.694748 -0.508589 0.694745 -0.694748 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694747 0.186157 0.694745 -0.694748 0.186157 0.508589 -0.694748 0.508589 0.508589 -0.694748 0.508589 0.186157 -0.694748 0.694745 0.186157 -0.694747 0.694747 0.159331 -0.698074 -0.698074 0.15933 -0.698074 -0.698073 0.446435 -0.698074 -0.559811 0.446435 -0.698073 -0.559812 0.645118 -0.698073 -0.310672 0.645117 -0.698074 -0.310672 0.716026 -0.698074 0 0.716026 -0.698074 0 0.645117 -0.698074 0.310672 0.645118 -0.698073 0.310672 0.446435 -0.698074 0.559811 0.446434 -0.698075 0.55981 0.15933 -0.698075 0.698072 0.15933 -0.698075 0.698072 0.186157 -0.694747 0.694746 0.191427 -0.509848 0.838696 0.914471 -0.322028 0.245032 0.330524 -0.706858 0.625384 0.465276 -0.70086 0.54066 0.646046 -0.406508 0.646046 0.585057 -0.706115 0.398886 0.661915 -0.703123 0.259782 0.704873 -0.704873 0.0794204 0.704873 -0.704873 -0.0794205 0.914471 -0.322028 -0.245032 0.661915 -0.703123 -0.259782 0.585057 -0.706114 -0.398886 0.646046 -0.406509 -0.646046 0.159331 -0.698074 -0.698074 0.216617 -0.547287 -0.808427 0.330525 -0.706858 -0.625385 0.465277 -0.700859 -0.540661 0.186156 -0.69475 -0.694744 0.186157 -0.694748 -0.694745 0.50859 -0.694748 -0.508589 0.508587 -0.69475 -0.508587 0.694744 -0.694749 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694747 0.186157 0.694745 -0.694749 0.186156 0.508588 -0.69475 0.508587 0.508589 -0.694748 0.508589 0.186156 -0.694748 0.694746 0.186156 -0.69475 0.694744 0.186156 -0.694747 -0.694747 0.186157 -0.694745 -0.694748 0.50859 -0.694746 -0.508591 0.508591 -0.694744 -0.508591 0.694747 -0.694746 -0.186157 0.694746 -0.694747 -0.186157 0.694746 -0.694747 0.186157 0.694745 -0.694748 0.186157 0.508588 -0.694749 0.508588 0.508589 -0.694748 0.508589 0.186157 -0.694748 0.694745 0.186157 -0.694747 0.694747 0.300748 -0.707089 -0.639981 0.15933 -0.698074 0.698074 0.15933 -0.698075 0.698072 0.330526 -0.706861 0.62538 0.507362 -0.581222 0.636211 0.465273 -0.700866 0.540656 0.585054 -0.706119 0.398883 0.787019 -0.486779 0.379008 0.661914 -0.703124 0.259782 0.704873 -0.704873 0.0794205 0.892698 -0.450656 0 0.704873 -0.704873 -0.0794204 0.661914 -0.703124 -0.259782 0.787022 -0.486773 -0.379009 0.585052 -0.706119 -0.398885 0.446432 -0.698078 -0.559809 0.545931 -0.547284 -0.634381 0.330524 -0.706858 -0.625385 0.178599 -0.723758 -0.666541 0.135547 -0.793059 -0.593872 0.0331733 -0.706718 -0.706718 0.186156 -0.69475 -0.694744 0.694748 -0.694745 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694747 0.186157 0.694748 -0.694745 0.186157 0.508589 -0.694748 0.508589 0.508589 -0.694748 0.508589 0.186156 -0.694748 0.694746 0.186156 -0.69475 0.694744 0.186157 -0.694748 -0.694745 0.382086 -0.706719 -0.595449 0.418712 -0.805829 -0.418712 0.418712 -0.805829 -0.418712 0.59545 -0.706718 -0.382085 0.694747 -0.694747 0.186156 0.694748 -0.694745 0.186157 0.50859 -0.694746 0.508591 0.508588 -0.694749 0.508588 0.186157 -0.694748 0.694745 0.186157 -0.694747 0.694746 0.571973 -0.805828 -0.153259 0.571973 -0.805827 -0.153259 0.706718 -0.706718 -0.0331733 0.186157 -0.694747 -0.694747 0.186157 -0.694747 -0.694746 0.508588 -0.694749 -0.508589 0.508591 -0.694745 -0.508591 0.628623 -0.706716 -0.324632 0.159331 -0.698074 -0.698074 0.15933 -0.698075 -0.698072 0.446434 -0.698075 -0.559811 0.446434 -0.698074 -0.559811 0.645117 -0.698074 -0.310672 0.645115 -0.698076 -0.310671 0.716024 -0.698076 0 0.716024 -0.698076 0 0.645115 -0.698076 0.310671 0.645117 -0.698074 0.310672 0.446434 -0.698074 0.559811 0.446435 -0.698074 0.559812 0.159331 -0.698073 0.698074 0.15933 -0.698075 0.698072 -0.0965219 -0.703805 0.703805 -0.0965212 -0.703807 0.703804 -0.156157 -0.698432 0.698432 -0.156156 -0.698434 0.698431 -0.438731 -0.698434 0.565425 -0.438732 -0.698431 0.565427 -0.637758 -0.698431 0.324744 -0.637757 -0.698432 0.324743 -0.144415 -0.699694 0.699694 -0.144415 -0.699694 0.699695 -0.129156 -0.701184 0.701184 -0.129156 -0.701184 0.701184 -0.370515 -0.701184 0.609146 -0.370515 -0.701184 0.609146 -0.126662 -0.701412 0.701412 -0.126662 -0.701412 0.701411 -0.166267 -0.697264 0.697264 -0.166266 -0.697267 0.697262 -0.463018 -0.697267 0.547205 -0.463019 -0.697265 0.547206 -0.660125 -0.697265 0.279386 -0.660125 -0.697265 0.279386 0.258819 0 0.965926 0.220963 -0.118069 0.968109 0.648906 0.101688 0.754043 0.623491 0 0.781831 0.826238 0 0.563321 0.89265 0.135575 0.429878 0.930874 0 0.365341 1 0 0 0.950195 0.292688 0.107061 0.993712 0 -0.111964 0.900969 0 -0.433884 0.912035 0.200169 -0.357946 0.826236 0 -0.563324 0.652288 0 -0.757972 0.621228 0.0850948 -0.778996 0.257479 -0.10169 -0.960918 0.222523 0 -0.974927 0.258819 0 0.965926 0.258819 0 0.965926 0.707106 0 0.707108 0.707106 0 0.707108 0.965925 0 0.25882 0.965925 0 0.25882 0.965925 0 -0.25882 0.965925 0 -0.25882 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.965926 0.220965 -0.118065 0.968109 0.648906 0.101691 0.754042 0.62349 0 0.781831 0.826235 0 0.563325 0.89265 0.135581 0.429878 0.930875 0 0.365338 1 0 0 0.950195 0.292688 0.107061 0.993712 0 -0.111964 0.900969 0 -0.433884 0.912034 0.200174 -0.357944 0.826235 0 -0.563325 0.652288 0 -0.757971 0.621229 0.0850937 -0.778995 0.257477 -0.101692 -0.960918 0.222521 0 -0.974928 0.258817 0 0.965926 0.258817 0 0.965926 0.707108 0 0.707106 0.707108 0 0.707106 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.222519 0 0.974928 0.222519 0 0.974928 0.623492 0 0.78183 0.623492 0 0.78183 0.900968 0 0.433885 0.900968 0 0.433885 1 0 0 1 0 0 0.900969 0 -0.433883 0.900969 0 -0.433883 0.623489 0 -0.781832 0.623489 0 -0.781832 0.222519 0 -0.974928 0.222519 0 -0.974928 0.258817 0 0.965926 0.258817 0 0.965926 0.707108 0 0.707106 0.707108 0 0.707106 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.965926 0.258819 0 0.965926 0.707106 0 0.707108 0.707106 0 0.707108 0.965926 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.707106 0 -0.707108 0.707106 0 -0.707108 0.258819 0 -0.965926 0.258819 0 -0.965926 0.22252 0 0.974928 0.22252 0 0.974928 0.623489 0 0.781832 0.623489 0 0.781832 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.62349 0 -0.781831 0.62349 0 -0.781831 0.222521 0 -0.974928 0.222521 0 -0.974928 0.222519 0 0.974928 0.222519 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900969 0 0.433883 0.900969 0 0.433883 1 0 0 1 0 0 0.900969 0 -0.433883 0.900969 0 -0.433883 0.623489 0 -0.781832 0.623489 0 -0.781832 0.222523 0 -0.974927 0.222523 0 -0.974927 0.222521 0 0.974928 0.222521 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900969 0 0.433883 0.900969 0 0.433883 1 0 0 1 0 0 0.900969 0 -0.433883 0.900969 0 -0.433883 0.623491 0 -0.781831 0.623491 0 -0.781831 0.222521 0 -0.974928 0.222521 0 -0.974928 0.25882 0 0.965926 0.25882 0 0.965926 0.707106 0 0.707107 0.707106 0 0.707107 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.25882 0 0.965925 0.25882 0 0.965925 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.222521 0 0.974928 0.222521 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900969 0 -0.433883 0.900969 0 -0.433883 0.623489 0 -0.781832 0.623489 0 -0.781832 0.222521 0 -0.974928 0.222521 0 -0.974928 0.25882 0 0.965926 0.25882 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707106 0.707107 0 -0.707106 0.258819 0 -0.965926 0.258819 0 -0.965926 0.222521 0 0.974928 0.222521 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900969 0 0.433883 0.900969 0 0.433883 1 0 0 1 0 0 0.900969 0 -0.433883 0.900969 0 -0.433883 0.62349 0 -0.781831 0.62349 0 -0.781831 0.222521 0 -0.974928 0.222521 0 -0.974928 0.222521 0 0.974928 0.222521 0 0.974928 0.467268 0 0.884116 0.467268 0 0.884116 0.652288 0 0.757971 0.652288 0 0.757971 0.826239 0 0.56332 0.826239 0 0.56332 0.930874 0 0.36534 0.930874 0 0.36534 0.993712 0 0.111965 0.993712 0 0.111965 0.993712 0 -0.111965 0.993712 0 -0.111965 0.930874 0 -0.36534 0.930874 0 -0.36534 0.826238 0 -0.563321 0.826238 0 -0.563321 0.652288 0 -0.757971 0.652288 0 -0.757971 0.467268 0 -0.884116 0.467268 0 -0.884116 0.222521 0 -0.974928 0.222521 0 -0.974928 0.258819 0 0.965926 0.258819 0 0.965926 0.707107 0 0.707106 0.707107 0 0.707106 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707106 0.707107 0 -0.707106 0.258819 0 -0.965926 0.258819 0 -0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.222521 0 -0.974928 0.222521 0 -0.974928 0.467266 0 -0.884117 0.467266 0 -0.884117 0.652289 0 -0.757971 0.652289 0 -0.757971 0.826236 0 -0.563323 0.826236 0 -0.563323 0.930874 0 -0.36534 0.930874 0 -0.36534 0.993712 0 -0.111965 0.993712 0 -0.111965 0.993712 0 0.111965 0.993712 0 0.111965 0.930874 0 0.365341 0.930874 0 0.365341 0.826239 0 0.56332 0.826239 0 0.56332 0.652288 0 0.757971 0.652288 0 0.757971 0.467272 0 0.884114 0.467272 0 0.884114 0.222521 0 0.974928 0.222521 0 0.974928 0.258819 0 0.965926 0.258819 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.965926 0.258819 0 0.965926 0.707106 0 0.707108 0.707106 0 0.707108 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707106 0 -0.707108 0.707106 0 -0.707108 0.258819 0 -0.965926 0.258819 0 -0.965926 0.222521 0 0.974928 0.222521 0 0.974928 0.62349 0 0.781832 0.62349 0 0.781832 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.62349 0 -0.781832 0.62349 0 -0.781832 0.222521 0 -0.974928 0.222521 0 -0.974928 -0.0142506 0 -0.999898 -0.202132 -0.00686639 -0.979334 -0.216077 0 -0.976376 -0.135871 0 0.990727 -0.135871 0 0.990727 -0.0309749 0 0.99952 -0.218149 0.0204791 0.975701 -0.268247 -0.0136554 0.963253 -0.612967 0.0143919 0.789977 -0.637193 -0.00719712 0.770671 -0.8911 0.00756426 0.453744 -0.895764 0 0.444531 -0.177707 0 0.984083 -0.177707 0 0.984083 -0.073278 0 0.997312 -0.231756 0.0412484 0.971899 -0.30261 0 0.953114 -0.494331 0 0.869274 -0.645617 0.0316635 0.763005 -0.700056 -0.0158424 0.713912 -0.920769 0.0179042 0.389698 -0.930169 0 0.367132 -0.18115 0 -0.983455 -0.174134 -0.00330553 -0.984716 -0.519668 0.00343314 -0.854361 -0.513569 0 -0.858049 0.186157 0.694747 -0.694747 0.186158 0.694747 -0.694746 0.50859 0.694747 -0.50859 0.481835 0.67405 -0.559903 0.585055 0.706116 -0.398887 0.694747 0.694747 -0.186157 0.697486 0.662253 -0.273742 0.704873 0.704873 -0.07942 0.704873 0.704873 0.0794199 0.704205 0.684464 0.188691 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 0.465275 0.700862 0.540659 0.514349 0.686215 0.514349 0.585056 0.706116 0.398885 0.661913 0.703125 0.259782 0.111964 0 -0.993712 0.111964 0 -0.993712 0.330279 0 -0.943883 0.330279 0 -0.943883 0.532032 0 -0.846724 0.532032 0 -0.846724 0.707107 0 -0.707107 0.707107 0 -0.707107 0.846724 0 -0.532032 0.846724 0 -0.532032 0.943883 0 -0.330279 0.943883 0 -0.330279 0.993712 0 -0.111964 0.993712 0 -0.111964 0.993712 0 0.111965 0.993712 0 0.111965 0.943883 0 0.330279 0.943883 0 0.330279 0.846724 0 0.532032 0.846724 0 0.532032 0.707107 0 0.707107 0.707107 0 0.707107 0.532032 0 0.846724 0.532032 0 0.846724 0.330279 0 0.943883 0.330279 0 0.943883 0.111964 0 0.993712 0.111964 0 0.993712 0.0794201 0.704873 0.704873 0.0794201 0.704874 0.704873 0.234278 0.704874 0.669528 0.234277 0.704878 0.669524 0.358828 0.705907 0.610686 0.507808 0.298313 0.808171 0.424322 0.706952 0.565836 0.469698 0.706617 0.529222 0.701822 0.122037 0.701822 0.69888 0.170097 0.694718 0.669524 0.704878 0.234276 0.600606 0.704878 0.377386 0.600608 0.704875 0.377387 0.533278 0.70677 0.464857 0.670654 0.364627 0.645965 0.986193 0.122785 0.111117 0.697137 0.706623 0.121174 0.669527 0.704874 0.234278 0.600606 0.704878 -0.377386 0.669524 0.704878 -0.234277 0.669528 0.704874 -0.234278 0.697137 0.706623 -0.121174 0.986193 0.122785 -0.111117 0.706472 0.706472 -0.0423673 0.706472 0.706472 0.0423673 0.670654 0.364626 -0.645965 0.533278 0.70677 -0.464857 0.600609 0.704875 -0.377387 0.694459 0.219954 -0.685089 0.702091 0.118903 -0.70209 0.695269 0.165256 -0.699494 0.469698 0.706617 -0.529222 0.377387 0.704874 -0.600609 0.377388 0.704874 -0.600609 0.234278 0.704874 -0.669528 0.234276 0.704878 -0.669524 0.0423665 0.706476 -0.706468 0.111117 0.122785 -0.986193 0.121979 0.681906 -0.721197 0.154214 0.707108 -0.690085 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 0.508589 0.694747 0.50859 0.508589 0.694747 0.50859 0.694746 0.694747 0.186158 0.694747 0.694746 0.186156 0.694747 0.694746 -0.186158 0.694747 0.694747 -0.186156 0.50859 0.694747 -0.50859 0.50859 0.694747 -0.50859 0.186157 0.694747 -0.694747 0.186157 0.694747 -0.694747 0.186157 0.694747 -0.694747 0.186157 0.694747 -0.694747 0.50859 0.694747 -0.50859 0.481836 0.67405 -0.559903 0.585054 0.706116 -0.398889 0.694747 0.694746 -0.186157 0.697486 0.662254 -0.27374 0.704873 0.704873 -0.0794201 0.704873 0.704873 0.07942 0.704205 0.684464 0.188691 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 0.465275 0.700862 0.540659 0.514349 0.686215 0.514349 0.585054 0.706116 0.398889 0.661915 0.703124 0.25978 0.186155 0.694747 0.694747 0.186157 0.694746 0.694747 0.508591 0.694746 0.508589 0.50859 0.694747 0.50859 0.694747 0.694746 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186157 0.694747 0.694747 -0.186157 0.50859 0.694747 -0.50859 0.50859 0.694747 -0.50859 0.186157 0.694746 -0.694747 0.186157 0.694747 -0.694747 0.15933 0.698074 0.698074 0.159331 0.698073 0.698074 0.446436 0.698073 0.559811 0.446435 0.698074 0.559812 0.645117 0.698074 0.310673 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310672 0.645117 0.698074 -0.310672 0.446434 0.698074 -0.559812 0.446434 0.698074 -0.559812 0.15933 0.698073 -0.698074 0.159331 0.698074 -0.698073 0.186155 0.694747 0.694747 0.186157 0.694746 0.694747 0.508591 0.694746 0.508589 0.50859 0.694747 0.50859 0.694746 0.694747 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186157 0.694747 0.694747 -0.186157 0.50859 0.694747 -0.50859 0.50859 0.694747 -0.50859 0.186157 0.694746 -0.694747 0.186157 0.694747 -0.694747 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 0.508589 0.694747 0.50859 0.50859 0.694746 0.50859 0.694747 0.694746 0.186156 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186155 0.694747 0.694746 -0.186157 0.50859 0.694746 -0.508591 0.50859 0.694747 -0.50859 0.186157 0.694747 -0.694747 0.186157 0.694747 -0.694747 0.0217334 0.70694 -0.70694 0.155847 0.713778 -0.682812 0.138791 0.711487 -0.688856 0.0699068 0.708059 -0.702685 0.0217312 0.70694 0.70694 0.0699068 0.708059 0.702685 0.138791 0.711487 0.688856 0.155847 0.713779 0.682812 0.246186 0.70554 0.664534 0.446435 0.698074 0.559812 0.446435 0.698074 0.559812 0.645117 0.698074 0.310672 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698073 -0.310672 0.645117 0.698074 -0.310672 0.446435 0.698074 -0.559812 0.446435 0.698074 -0.559812 0.246186 0.70554 -0.664534 0.15933 0.698074 0.698074 0.159331 0.698074 0.698074 0.446435 0.698074 0.559812 0.446435 0.698074 0.559812 0.645117 0.698074 0.310672 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310672 0.645117 0.698074 -0.310672 0.446434 0.698074 -0.559812 0.446435 0.698074 -0.559812 0.159332 0.698074 -0.698073 0.159331 0.698074 -0.698074 -0.156156 0.698436 -0.698429 -0.156156 0.698434 -0.69843 -0.43873 0.698435 -0.565425 -0.43873 0.698435 -0.565424 -0.637755 0.698435 -0.324742 -0.637754 0.698436 -0.324742 -0.144414 0.699698 -0.699691 -0.144415 0.699697 -0.699692 -0.129156 0.701188 -0.701181 -0.129156 0.701188 -0.701181 -0.370514 0.701188 -0.609143 -0.370515 0.701186 -0.609144 -0.126661 0.701415 -0.701409 -0.126662 0.701414 -0.70141 -0.660123 0.697267 -0.279385 -0.660123 0.697267 -0.279385 -0.463018 0.697266 -0.547206 -0.463018 0.697267 -0.547206 -0.166267 0.697266 -0.697262 -0.275486 0.413797 -0.867686 -0.0518847 0.706159 -0.70615 -0.0965202 0.70381 -0.703801 -0.096522 0.703807 -0.703804 0.15933 0.698075 0.698072 0.15933 0.698075 0.698072 0.446434 0.698075 0.559811 0.446435 0.698074 0.559811 0.645118 0.698073 0.310672 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310672 0.645118 0.698073 -0.310672 0.446435 0.698073 -0.559812 0.446435 0.698074 -0.559811 0.159331 0.698074 -0.698073 0.159331 0.698074 -0.698074 0.186157 0.694747 0.694747 0.186157 0.694748 0.694745 0.508589 0.694748 0.508589 0.508589 0.694748 0.508589 0.694745 0.694748 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186157 0.694745 0.694748 -0.186157 0.508589 0.694748 -0.508589 0.508591 0.694745 -0.508591 0.186157 0.694745 -0.694749 0.186157 0.694747 -0.694747 0.159331 0.698074 0.698074 0.159332 0.698072 0.698076 0.446436 0.698072 0.559813 0.446436 0.698072 0.559812 0.645117 0.698073 0.310673 0.645118 0.698073 0.310673 0.716026 0.698074 0 0.716026 0.698074 0 0.645116 0.698076 -0.310671 0.645117 0.698073 -0.310672 0.446435 0.698072 -0.559813 0.446434 0.698075 -0.559811 0.159331 0.698075 -0.698073 0.159331 0.698077 -0.69807 0.186158 0.694746 0.694746 0.186156 0.694751 0.694742 0.508587 0.69475 0.508588 0.508588 0.694749 0.508588 0.694746 0.694747 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186157 0.694748 0.694745 -0.186157 0.508592 0.694744 -0.508592 0.50859 0.694748 -0.508589 0.186156 0.694748 -0.694746 0.186156 0.69475 -0.694744 0.186157 0.694747 0.694747 0.186157 0.694748 0.694745 0.508589 0.694748 0.508589 0.508591 0.694745 0.508591 0.694749 0.694745 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186156 0.694749 0.694745 -0.186157 0.508591 0.694745 -0.508591 0.508591 0.694745 -0.508591 0.186157 0.694745 -0.694749 0.186157 0.694747 -0.694747 0.15933 0.698075 0.698072 0.159331 0.698074 0.698074 0.446437 0.698071 0.559814 0.446435 0.698074 0.559812 0.645118 0.698073 0.310672 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310672 0.645118 0.698073 -0.310672 0.446436 0.698073 -0.559811 0.446437 0.69807 -0.559814 0.159331 0.698073 -0.698075 0.159331 0.698074 -0.698074 0.186157 0.694747 0.694746 0.186157 0.694748 0.694745 0.508587 0.694749 0.508588 0.50859 0.694746 0.50859 0.694748 0.694745 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186156 0.694749 0.694745 -0.186157 0.50859 0.694745 -0.508591 0.508588 0.694749 -0.508588 0.186157 0.694747 -0.694746 0.186157 0.694747 -0.694747 0.186156 0.69475 0.694744 0.186157 0.694748 0.694745 0.508589 0.694748 0.508589 0.508589 0.694748 0.508589 0.694748 0.694745 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186156 0.694748 0.694745 -0.186157 0.508589 0.694748 -0.508589 0.508589 0.694748 -0.508589 0.186156 0.694748 -0.694746 0.186156 0.69475 -0.694744 0.159331 0.698074 -0.698074 0.159331 0.698072 -0.698076 0.330524 0.706858 -0.625385 0.507364 0.581215 -0.636216 0.892698 0.450656 0 0.465273 0.700866 -0.540655 0.585052 0.706119 -0.398885 0.787022 0.486773 -0.379009 0.661914 0.703124 -0.259782 0.704873 0.704873 -0.0794205 0.704873 0.704873 0.0794204 0.661914 0.703124 0.259782 0.787019 0.486779 0.379008 0.585054 0.706119 0.398883 0.446432 0.698078 0.559808 0.159331 0.698074 0.698074 0.15933 0.698075 0.698072 0.330526 0.706861 0.62538 0.545927 0.547293 0.634377 0.186157 0.694747 0.694747 0.186156 0.694748 0.694745 0.508589 0.694748 0.508589 0.508588 0.694749 0.508588 0.694745 0.694748 0.186157 0.694746 0.694747 0.186157 0.694746 0.694748 -0.186156 0.694747 0.694746 -0.186157 0.508591 0.694744 -0.508591 0.50859 0.694746 -0.50859 0.186157 0.694745 -0.694748 0.186157 0.694747 -0.694747 0.186156 0.69475 0.694744 0.186157 0.694748 0.694745 0.50859 0.694748 0.508589 0.508587 0.69475 0.508587 0.694744 0.694749 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186157 0.694745 0.694749 -0.186156 0.508588 0.69475 -0.508587 0.508589 0.694748 -0.508589 0.186156 0.694748 -0.694746 0.186156 0.69475 -0.694744 0.186157 0.694747 -0.694747 0.191427 0.509846 -0.838697 0.914471 0.322028 -0.245032 0.330525 0.706858 -0.625385 0.465277 0.700859 -0.540661 0.646046 0.406509 -0.646046 0.585057 0.706114 -0.398886 0.661915 0.703123 -0.259782 0.704873 0.704873 -0.0794205 0.704873 0.704873 0.0794204 0.914471 0.322028 0.245032 0.661915 0.703123 0.259782 0.585057 0.706115 0.398886 0.646046 0.406507 0.646046 0.15933 0.698075 0.698073 0.216617 0.547289 0.808426 0.330524 0.706858 0.625384 0.465276 0.70086 0.54066 0.0694756 -0.705398 -0.705398 0.0694758 -0.705395 -0.705401 0.205758 -0.705395 -0.678293 0.205758 -0.705396 -0.678292 0.334132 -0.705396 -0.625118 0.334132 -0.705398 -0.625116 0.449665 -0.705398 -0.547919 0.449667 -0.705395 -0.547921 0.547922 -0.705394 -0.449668 0.547919 -0.705398 -0.449665 0.625116 -0.705398 -0.334131 0.625116 -0.705397 -0.334132 0.678291 -0.705397 -0.205757 0.678292 -0.705396 -0.205758 0.705401 -0.705396 -0.0694761 0.705398 -0.705398 -0.0694758 0.705398 -0.705398 0.0694759 0.705401 -0.705395 0.069476 0.678292 -0.705396 0.205758 0.678292 -0.705396 0.205758 0.625118 -0.705396 0.334132 0.625116 -0.705398 0.334132 0.547919 -0.705398 0.449665 0.547918 -0.705399 0.449664 0.449664 -0.705399 0.547918 0.449665 -0.705398 0.547919 0.334131 -0.705398 0.625116 0.334132 -0.705396 0.625118 0.205758 -0.705396 0.678292 0.205756 -0.705402 0.678286 0.0694753 -0.705402 0.705394 0.0694758 -0.705398 0.705398 0.0980171 0 -0.995185 0.0980171 0 -0.995185 0.290285 0 -0.95694 0.290285 0 -0.95694 0.471397 0 -0.881921 0.471397 0 -0.881921 0.634393 0 -0.77301 0.634393 0 -0.77301 0.77301 0 -0.634393 0.77301 0 -0.634393 0.881921 0 -0.471397 0.881921 0 -0.471397 0.95694 0 -0.290285 0.95694 0 -0.290285 0.995185 0 -0.0980174 0.995185 0 -0.0980174 0.995185 0 0.0980174 0.995185 0 0.0980174 0.95694 0 0.290285 0.95694 0 0.290285 0.881921 0 0.471397 0.881921 0 0.471397 0.77301 0 0.634393 0.77301 0 0.634393 0.634393 0 0.77301 0.634393 0 0.77301 0.471397 0 0.881921 0.471397 0 0.881921 0.290285 0 0.95694 0.290285 0 0.95694 0.0980171 0 0.995185 0.0980171 0 0.995185 0.0575225 0.809687 0.584036 0.0575226 0.809687 0.584036 0.170357 0.809687 0.561592 0.170357 0.809687 0.561592 0.276645 0.809687 0.517566 0.276645 0.809687 0.517566 0.372301 0.809687 0.453651 0.372301 0.809687 0.45365 0.45365 0.809687 0.372301 0.453651 0.809687 0.372302 0.517566 0.809687 0.276645 0.517566 0.809687 0.276645 0.561592 0.809687 0.170357 0.561592 0.809687 0.170357 0.584036 0.809687 0.0575227 0.584036 0.809687 0.0575224 0.584036 0.809687 -0.0575227 0.584036 0.809687 -0.0575224 0.561592 0.809687 -0.170357 0.561592 0.809687 -0.170357 0.517566 0.809687 -0.276645 0.517566 0.809687 -0.276645 0.453651 0.809687 -0.372301 0.45365 0.809687 -0.372301 0.372301 0.809687 -0.45365 0.372301 0.809687 -0.45365 0.276645 0.809687 -0.517566 0.276645 0.809687 -0.517566 0.170357 0.809687 -0.561592 0.170357 0.809687 -0.561592 0.0575225 0.809687 -0.584036 0.0575224 0.809687 -0.584036 0.0980171 0 -0.995185 0.0980171 0 -0.995185 0.290285 0 -0.95694 0.290285 0 -0.95694 0.471397 0 -0.881921 0.471397 0 -0.881921 0.634393 0 -0.77301 0.634393 0 -0.77301 0.77301 0 -0.634393 0.77301 0 -0.634393 0.881921 0 -0.471397 0.881921 0 -0.471397 0.95694 0 -0.290285 0.95694 0 -0.290285 0.995185 0 -0.0980171 0.995185 0 -0.0980171 0.995185 0 0.0980171 0.995185 0 0.0980171 0.95694 0 0.290285 0.95694 0 0.290285 0.881921 0 0.471397 0.881921 0 0.471397 0.77301 0 0.634393 0.77301 0 0.634393 0.634393 0 0.77301 0.634393 0 0.77301 0.471397 0 0.881921 0.471397 0 0.881921 0.290285 0 0.95694 0.290285 0 0.95694 0.0980171 0 0.995185 0.0980171 0 0.995185 -0.0644331 -0.705637 0.705637 -0.0644333 -0.705638 0.705637 -0.191168 -0.705638 0.682297 -0.191168 -0.705637 0.682298 -0.311581 -0.705637 0.636391 -0.311581 -0.705638 0.636391 -0.421687 -0.705638 0.569435 -0.421687 -0.705638 0.569434 -0.517845 -0.705638 0.483644 -0.517846 -0.705637 0.483644 -0.596877 -0.705637 0.381857 -0.596876 -0.705637 0.381857 -0.656165 -0.705637 0.267439 -0.656164 -0.705638 0.267438 0.0584918 0.705903 0.70589 0.0584917 0.705904 0.705888 0.173879 0.705904 0.686633 0.173881 0.705896 0.686641 0.284527 0.705896 0.648656 0.284528 0.705894 0.648658 0.387413 0.705894 0.59298 0.387408 0.705903 0.592972 0.479725 0.705902 0.52112 0.479726 0.7059 0.521121 0.558957 0.7059 0.435054 0.558964 0.705891 0.435059 0.62295 0.705891 0.337124 0.622939 0.705902 0.337118 0.669931 0.705902 0.229988 0.669938 0.705895 0.22999 0.698656 0.705895 0.116585 0.698652 0.705899 0.116584 0.708313 0.705899 0 0.708313 0.705899 0 0.698653 0.705898 -0.116584 0.698657 0.705894 -0.116585 0.669939 0.705894 -0.22999 0.669933 0.7059 -0.229988 0.622943 0.705899 -0.33712 0.62295 0.70589 -0.337124 0.558964 0.705891 -0.435059 0.558961 0.705896 -0.435057 0.479729 0.705896 -0.521125 0.479725 0.705902 -0.52112 0.387408 0.705903 -0.592972 0.387413 0.705894 -0.59298 0.284528 0.705894 -0.648659 0.284527 0.705897 -0.648656 0.173881 0.705896 -0.686641 0.173879 0.705904 -0.686633 0.0584913 0.705904 -0.705888 0.058493 0.705889 -0.705903 0.0584924 -0.705891 -0.705901 0.0584923 -0.705898 -0.705894 0.160579 -0.706395 -0.689362 0.21182 -0.505439 -0.836459 0.216805 -0.703333 -0.676992 0.228528 -0.707108 -0.669159 0.284527 -0.705898 -0.648655 0.284526 -0.705898 -0.648655 0.348317 -0.707045 -0.615437 0.471368 -0.507224 -0.721482 0.398317 -0.706391 -0.585111 0.520851 -0.707106 -0.478243 0.500313 -0.706807 -0.500111 0.624503 -0.387017 -0.678391 0.458293 -0.705495 -0.540596 0.434434 -0.707109 -0.55791 0.593238 -0.707103 -0.384803 0.5681 -0.706462 -0.422106 0.694029 -0.475945 -0.540185 0.537492 -0.699805 -0.470505 0.52241 -0.7067 -0.477141 0.654603 -0.684618 -0.320614 0.809364 -0.391254 -0.438006 0.731588 -0.544807 -0.409834 0.609565 -0.697893 -0.376 0.862976 -0.40927 -0.29626 0.656498 -0.706926 -0.263183 0.646195 -0.707104 -0.287115 0.708314 -0.705898 0 0.703607 -0.707054 -0.0707948 0.842102 -0.520689 -0.140522 0.696044 -0.706356 -0.128784 0.676251 -0.706652 -0.208151 0.681512 -0.707017 0.188863 0.696044 -0.706356 0.128784 0.842102 -0.52069 0.140522 0.703607 -0.707054 0.0707948 0.708314 -0.705898 0 0.807881 -0.524606 0.268546 0.862976 -0.40927 0.29626 0.656497 -0.706927 0.263183 0.731587 -0.544809 0.409834 0.809363 -0.391257 0.438006 0.654602 -0.684619 0.320613 0.646194 -0.707105 0.287114 0.520856 -0.707106 0.478237 0.522408 -0.706701 0.47714 0.537491 -0.699807 0.470504 0.694028 -0.475948 0.540183 0.5681 -0.706462 0.422107 0.60068 -0.707014 0.373249 0.500313 -0.706807 0.500111 0.624503 -0.387015 0.678392 0.457308 -0.706804 0.53972 0.409737 -0.706772 0.576705 0.503999 -0.388439 0.771428 0.36068 -0.706839 0.608513 0.314021 -0.706879 0.633809 0.369134 -0.394399 0.84154 0.260666 -0.706724 0.65772 0.216759 -0.707043 0.673131 0.21182 -0.505439 0.836459 0.160579 -0.706395 0.689362 0.0584922 -0.705898 0.705894 0.0584924 -0.705897 0.705895 0.0584919 0.705902 0.70589 0.0584918 0.705904 0.705889 0.173879 0.705903 0.686634 0.173881 0.705896 0.686642 0.284527 0.705896 0.648657 0.284528 0.705893 0.648659 0.387413 0.705893 0.592981 0.387409 0.705902 0.592973 0.479726 0.705901 0.521121 0.479727 0.7059 0.521122 0.558958 0.705899 0.435054 0.558965 0.70589 0.43506 0.62295 0.70589 0.337124 0.62294 0.705902 0.337118 0.669932 0.705901 0.229988 0.669938 0.705895 0.22999 0.698657 0.705894 0.116585 0.698653 0.705898 0.116584 0.708314 0.705898 0 0.708314 0.705898 0 0.698653 0.705898 -0.116585 0.698657 0.705894 -0.116585 0.66994 0.705893 -0.22999 0.669934 0.705899 -0.229989 0.622943 0.705898 -0.33712 0.62295 0.70589 -0.337124 0.558965 0.70589 -0.43506 0.558961 0.705895 -0.435057 0.47973 0.705895 -0.521125 0.479725 0.705902 -0.521121 0.387408 0.705902 -0.592973 0.387414 0.705893 -0.59298 0.284528 0.705893 -0.648659 0.284527 0.705896 -0.648657 0.173881 0.705895 -0.686642 0.173879 0.705903 -0.686634 0.0584914 0.705903 -0.705889 0.058493 0.705889 -0.705904 0.0584926 -0.705889 -0.705903 0.0584918 -0.705904 -0.705888 0.173879 -0.705904 -0.686634 0.173881 -0.705896 -0.686641 0.284527 -0.705896 -0.648656 0.284528 -0.705894 -0.648659 0.387413 -0.705893 -0.59298 0.387408 -0.705903 -0.592972 0.479725 -0.705902 -0.52112 0.479729 -0.705895 -0.521125 0.558961 -0.705896 -0.435056 0.558965 -0.705891 -0.43506 0.62295 -0.70589 -0.337124 0.622943 -0.705898 -0.33712 0.669934 -0.705899 -0.229988 0.669939 -0.705894 -0.22999 0.698657 -0.705894 -0.116585 0.698653 -0.705898 -0.116584 0.708313 -0.705898 0 0.708313 -0.705898 0 0.698653 -0.705898 0.116585 0.698656 -0.705895 0.116585 0.669938 -0.705895 0.22999 0.669932 -0.705901 0.229988 0.62294 -0.705901 0.337119 0.62295 -0.70589 0.337124 0.558965 -0.705891 0.43506 0.558957 -0.7059 0.435054 0.479726 -0.7059 0.521121 0.479725 -0.705902 0.52112 0.387408 -0.705903 0.592972 0.387413 -0.705894 0.59298 0.284528 -0.705893 0.648659 0.284527 -0.705896 0.648656 0.173881 -0.705896 0.686642 0.173879 -0.705904 0.686634 0.0584917 -0.705904 0.705888 0.0584919 -0.705902 0.70589 0.0584918 0.705902 0.70589 0.0584918 0.705904 0.705888 0.173879 0.705904 0.686634 0.173881 0.705896 0.686641 0.284527 0.705896 0.648656 0.284528 0.705894 0.648659 0.387413 0.705893 0.59298 0.387408 0.705903 0.592972 0.479725 0.705902 0.521121 0.479726 0.7059 0.521122 0.558958 0.7059 0.435054 0.558964 0.705891 0.43506 0.62295 0.70589 0.337124 0.62294 0.705902 0.337118 0.669932 0.705902 0.229988 0.669938 0.705895 0.22999 0.698656 0.705895 0.116585 0.698653 0.705898 0.116584 0.708313 0.705898 0 0.708313 0.705898 0 0.698653 0.705898 -0.116585 0.698657 0.705894 -0.116585 0.669939 0.705894 -0.22999 0.669934 0.7059 -0.229989 0.622943 0.705898 -0.33712 0.62295 0.70589 -0.337124 0.558965 0.705891 -0.43506 0.558961 0.705895 -0.435057 0.47973 0.705895 -0.521125 0.479725 0.705902 -0.52112 0.387408 0.705903 -0.592972 0.387413 0.705894 -0.59298 0.284528 0.705893 -0.648659 0.284527 0.705896 -0.648656 0.173881 0.705896 -0.686642 0.173879 0.705904 -0.686634 0.0584913 0.705904 -0.705889 0.058493 0.705889 -0.705903 0.0584926 -0.705889 -0.705903 0.0584918 -0.705904 -0.705889 0.173879 -0.705904 -0.686634 0.173881 -0.705896 -0.686642 0.284527 -0.705896 -0.648657 0.284528 -0.705893 -0.648659 0.387413 -0.705893 -0.59298 0.387408 -0.705903 -0.592972 0.479726 -0.705901 -0.521121 0.47973 -0.705895 -0.521125 0.558961 -0.705896 -0.435057 0.558965 -0.705891 -0.43506 0.62295 -0.70589 -0.337124 0.622943 -0.705898 -0.33712 0.669934 -0.705899 -0.229989 0.66994 -0.705893 -0.229991 0.698657 -0.705894 -0.116585 0.698653 -0.705898 -0.116584 0.708314 -0.705898 0 0.708314 -0.705898 0 0.698653 -0.705898 0.116585 0.698656 -0.705895 0.116585 0.669938 -0.705895 0.22999 0.669932 -0.705901 0.229988 0.62294 -0.705901 0.337119 0.62295 -0.70589 0.337124 0.558965 -0.705891 0.43506 0.558957 -0.7059 0.435054 0.479726 -0.7059 0.521122 0.479725 -0.705902 0.52112 0.387408 -0.705903 0.592973 0.387414 -0.705893 0.59298 0.284528 -0.705893 0.648659 0.284527 -0.705896 0.648656 0.173881 -0.705895 0.686642 0.173879 -0.705904 0.686634 0.0584917 -0.705904 0.705889 0.0584919 -0.705902 0.70589 0.0584919 0.705902 0.70589 0.0584918 0.705904 0.705889 0.173879 0.705904 0.686634 0.173881 0.705896 0.686642 0.284527 0.705896 0.648656 0.284528 0.705893 0.648659 0.387413 0.705893 0.59298 0.387408 0.705903 0.592972 0.479725 0.705901 0.521121 0.479726 0.7059 0.521122 0.558958 0.7059 0.435054 0.558965 0.705891 0.43506 0.62295 0.70589 0.337124 0.62294 0.705902 0.337118 0.669932 0.705901 0.229988 0.669938 0.705895 0.22999 0.698657 0.705894 0.116585 0.698653 0.705898 0.116584 0.708314 0.705898 0 0.708314 0.705898 0 0.698653 0.705898 -0.116585 0.698657 0.705894 -0.116585 0.669939 0.705894 -0.22999 0.669934 0.705899 -0.229989 0.622943 0.705898 -0.33712 0.62295 0.70589 -0.337124 0.558965 0.705891 -0.43506 0.558961 0.705895 -0.435057 0.47973 0.705895 -0.521125 0.479725 0.705902 -0.52112 0.387408 0.705903 -0.592973 0.387414 0.705893 -0.59298 0.284528 0.705893 -0.648659 0.284527 0.705896 -0.648656 0.173881 0.705896 -0.686642 0.173879 0.705904 -0.686634 0.0584914 0.705904 -0.705889 0.058493 0.705889 -0.705903 0.0584926 -0.705889 -0.705903 0.0584918 -0.705904 -0.705889 0.173879 -0.705904 -0.686634 0.173881 -0.705896 -0.686642 0.284527 -0.705896 -0.648657 0.284528 -0.705893 -0.648659 0.387413 -0.705893 -0.59298 0.387408 -0.705903 -0.592972 0.479726 -0.705901 -0.521121 0.47973 -0.705895 -0.521125 0.558961 -0.705896 -0.435057 0.558965 -0.705891 -0.43506 0.62295 -0.70589 -0.337124 0.622943 -0.705898 -0.33712 0.669934 -0.705899 -0.229989 0.66994 -0.705893 -0.229991 0.698657 -0.705894 -0.116585 0.698653 -0.705898 -0.116584 0.708314 -0.705898 0 0.708314 -0.705898 0 0.698653 -0.705898 0.116585 0.698656 -0.705895 0.116585 0.669938 -0.705895 0.22999 0.669932 -0.705901 0.229988 0.62294 -0.705901 0.337119 0.62295 -0.70589 0.337124 0.558965 -0.705891 0.43506 0.558957 -0.7059 0.435054 0.479726 -0.7059 0.521122 0.479725 -0.705902 0.52112 0.387408 -0.705903 0.592973 0.387414 -0.705893 0.59298 0.284528 -0.705893 0.648659 0.284527 -0.705896 0.648656 0.173881 -0.705895 0.686642 0.173879 -0.705904 0.686634 0.0584917 -0.705904 0.705889 0.0584919 -0.705902 0.70589 0.0584918 0.705902 0.70589 0.0584918 0.705904 0.705888 0.173879 0.705904 0.686634 0.173881 0.705896 0.686641 0.284527 0.705896 0.648656 0.284528 0.705894 0.648659 0.387413 0.705893 0.59298 0.387408 0.705903 0.592972 0.479725 0.705902 0.521121 0.479726 0.7059 0.521122 0.558958 0.7059 0.435054 0.558964 0.705891 0.43506 0.62295 0.70589 0.337124 0.62294 0.705902 0.337118 0.669932 0.705902 0.229988 0.669938 0.705895 0.22999 0.698656 0.705895 0.116585 0.698653 0.705898 0.116584 0.708313 0.705898 0 0.708313 0.705898 0 0.698653 0.705898 -0.116585 0.698657 0.705894 -0.116585 0.669939 0.705894 -0.22999 0.669934 0.7059 -0.229989 0.622943 0.705898 -0.33712 0.62295 0.70589 -0.337124 0.558965 0.705891 -0.43506 0.558961 0.705895 -0.435057 0.47973 0.705895 -0.521125 0.479725 0.705902 -0.52112 0.387408 0.705903 -0.592972 0.387413 0.705894 -0.59298 0.284528 0.705893 -0.648659 0.284527 0.705896 -0.648656 0.173881 0.705896 -0.686642 0.173879 0.705904 -0.686634 0.0584913 0.705904 -0.705889 0.058493 0.705889 -0.705903 0.0584926 -0.705889 -0.705903 0.0584918 -0.705904 -0.705888 0.173879 -0.705904 -0.686634 0.173881 -0.705896 -0.686641 0.284527 -0.705896 -0.648656 0.284528 -0.705894 -0.648659 0.387413 -0.705893 -0.59298 0.387408 -0.705903 -0.592972 0.479725 -0.705902 -0.52112 0.479729 -0.705895 -0.521125 0.558961 -0.705896 -0.435056 0.558965 -0.705891 -0.43506 0.62295 -0.70589 -0.337124 0.622943 -0.705898 -0.33712 0.669934 -0.705899 -0.229988 0.669939 -0.705894 -0.22999 0.698657 -0.705894 -0.116585 0.698653 -0.705898 -0.116584 0.708313 -0.705898 0 0.708313 -0.705898 0 0.698653 -0.705898 0.116585 0.698656 -0.705895 0.116585 0.669938 -0.705895 0.22999 0.669932 -0.705901 0.229988 0.62294 -0.705901 0.337119 0.62295 -0.70589 0.337124 0.558965 -0.705891 0.43506 0.558957 -0.7059 0.435054 0.479726 -0.7059 0.521121 0.479725 -0.705902 0.52112 0.387408 -0.705903 0.592972 0.387413 -0.705894 0.59298 0.284528 -0.705893 0.648659 0.284527 -0.705896 0.648656 0.173881 -0.705896 0.686642 0.173879 -0.705904 0.686634 0.0584917 -0.705904 0.705888 0.0584919 -0.705902 0.70589 0.0584918 0.705903 0.70589 0.0584917 0.705904 0.705888 0.173879 0.705904 0.686633 0.173881 0.705896 0.686641 0.284527 0.705896 0.648656 0.284528 0.705894 0.648658 0.387413 0.705894 0.59298 0.387408 0.705903 0.592972 0.479725 0.705902 0.52112 0.479726 0.7059 0.521121 0.558957 0.7059 0.435054 0.558964 0.705891 0.435059 0.62295 0.705891 0.337124 0.622939 0.705902 0.337118 0.669931 0.705902 0.229988 0.669938 0.705895 0.22999 0.698656 0.705895 0.116585 0.698652 0.705899 0.116584 0.708313 0.705899 0 0.708313 0.705899 0 0.698653 0.705898 -0.116584 0.698657 0.705894 -0.116585 0.669939 0.705894 -0.22999 0.669933 0.7059 -0.229988 0.622943 0.705899 -0.33712 0.62295 0.70589 -0.337124 0.558964 0.705891 -0.435059 0.558961 0.705896 -0.435057 0.479729 0.705896 -0.521125 0.479725 0.705902 -0.52112 0.387408 0.705903 -0.592972 0.387413 0.705894 -0.59298 0.284528 0.705894 -0.648659 0.284527 0.705897 -0.648656 0.173881 0.705896 -0.686641 0.173879 0.705904 -0.686633 0.0584913 0.705904 -0.705888 0.058493 0.705889 -0.705903 0.0584926 -0.705889 -0.705904 0.0584918 -0.705904 -0.705889 0.173879 -0.705903 -0.686634 0.173881 -0.705896 -0.686642 0.284527 -0.705896 -0.648657 0.284528 -0.705893 -0.648659 0.387413 -0.705893 -0.592981 0.387409 -0.705902 -0.592973 0.479726 -0.705901 -0.521121 0.47973 -0.705895 -0.521125 0.558961 -0.705895 -0.435057 0.558965 -0.70589 -0.43506 0.62295 -0.70589 -0.337124 0.622943 -0.705898 -0.33712 0.669934 -0.705899 -0.229989 0.66994 -0.705893 -0.229991 0.698657 -0.705894 -0.116585 0.698653 -0.705898 -0.116584 0.708314 -0.705898 0 0.708314 -0.705898 0 0.698653 -0.705898 0.116585 0.698657 -0.705894 0.116585 0.669939 -0.705894 0.22999 0.669932 -0.705901 0.229988 0.62294 -0.705901 0.337119 0.622951 -0.705889 0.337124 0.558965 -0.70589 0.43506 0.558958 -0.7059 0.435054 0.479726 -0.7059 0.521122 0.479725 -0.705902 0.521121 0.387408 -0.705902 0.592973 0.387414 -0.705893 0.59298 0.284528 -0.705893 0.648659 0.284527 -0.705896 0.648657 0.173881 -0.705895 0.686642 0.173879 -0.705903 0.686634 0.0584918 -0.705903 0.705889 0.0584919 -0.705902 0.70589 0.0584918 0.705903 0.70589 0.0584917 0.705904 0.705888 0.173879 0.705904 0.686633 0.173881 0.705896 0.686641 0.284527 0.705896 0.648656 0.284528 0.705894 0.648658 0.387413 0.705894 0.59298 0.387408 0.705903 0.592972 0.479725 0.705902 0.52112 0.479726 0.7059 0.521121 0.558957 0.7059 0.435054 0.558964 0.705891 0.435059 0.62295 0.705891 0.337124 0.622939 0.705902 0.337118 0.669931 0.705902 0.229988 0.669938 0.705895 0.22999 0.698656 0.705895 0.116585 0.698652 0.705899 0.116584 0.708313 0.705899 0 0.708313 0.705899 0 0.698653 0.705898 -0.116584 0.698657 0.705894 -0.116585 0.669939 0.705894 -0.22999 0.669933 0.7059 -0.229988 0.622943 0.705899 -0.33712 0.62295 0.70589 -0.337124 0.558964 0.705891 -0.435059 0.558961 0.705896 -0.435057 0.479729 0.705896 -0.521125 0.479725 0.705902 -0.52112 0.387408 0.705903 -0.592972 0.387413 0.705894 -0.59298 0.284528 0.705894 -0.648659 0.284527 0.705897 -0.648656 0.173881 0.705896 -0.686641 0.173879 0.705904 -0.686633 0.0584913 0.705904 -0.705888 0.058493 0.705889 -0.705903 0.0584925 -0.70589 -0.705903 0.0584917 -0.705904 -0.705888 0.173879 -0.705904 -0.686633 0.173881 -0.705896 -0.686641 0.284527 -0.705896 -0.648656 0.284528 -0.705894 -0.648658 0.387413 -0.705894 -0.59298 0.387408 -0.705903 -0.592972 0.479725 -0.705902 -0.52112 0.479729 -0.705896 -0.521125 0.55896 -0.705896 -0.435056 0.558964 -0.705891 -0.435059 0.62295 -0.705891 -0.337124 0.622943 -0.705899 -0.33712 0.669933 -0.7059 -0.229988 0.669939 -0.705894 -0.22999 0.698656 -0.705894 -0.116585 0.698653 -0.705899 -0.116584 0.708313 -0.705899 0 0.708313 -0.705899 0 0.698652 -0.705899 0.116584 0.698656 -0.705895 0.116585 0.669938 -0.705895 0.22999 0.669932 -0.705902 0.229988 0.62294 -0.705902 0.337118 0.62295 -0.70589 0.337124 0.558964 -0.705891 0.435059 0.558957 -0.705901 0.435054 0.479726 -0.705901 0.521121 0.479725 -0.705902 0.52112 0.387408 -0.705903 0.592972 0.387413 -0.705894 0.59298 0.284528 -0.705894 0.648659 0.284527 -0.705897 0.648656 0.173881 -0.705896 0.686641 0.173879 -0.705904 0.686633 0.0584917 -0.705904 0.705888 0.0584919 -0.705903 0.70589 0.0584918 0.705903 0.70589 0.0584917 0.705904 0.705888 0.173879 0.705904 0.686633 0.173881 0.705896 0.686641 0.284527 0.705896 0.648656 0.284528 0.705894 0.648658 0.387413 0.705894 0.59298 0.387408 0.705903 0.592972 0.479725 0.705902 0.52112 0.479726 0.7059 0.521121 0.558957 0.7059 0.435054 0.558964 0.705891 0.435059 0.62295 0.705891 0.337124 0.622939 0.705902 0.337118 0.669931 0.705902 0.229988 0.669938 0.705895 0.22999 0.698656 0.705895 0.116585 0.698652 0.705899 0.116584 0.708313 0.705899 0 0.708313 0.705899 0 0.698653 0.705898 -0.116584 0.698657 0.705894 -0.116585 0.669939 0.705894 -0.22999 0.669933 0.7059 -0.229988 0.622943 0.705899 -0.33712 0.62295 0.70589 -0.337124 0.558964 0.705891 -0.435059 0.558961 0.705896 -0.435057 0.479729 0.705896 -0.521125 0.479725 0.705902 -0.52112 0.387408 0.705903 -0.592972 0.387413 0.705894 -0.59298 0.284528 0.705894 -0.648659 0.284527 0.705897 -0.648656 0.173881 0.705896 -0.686641 0.173879 0.705904 -0.686633 0.0584913 0.705904 -0.705888 0.058493 0.705889 -0.705903 0.0584925 -0.70589 -0.705903 0.0584917 -0.705904 -0.705888 0.173879 -0.705904 -0.686633 0.173881 -0.705896 -0.686641 0.284527 -0.705896 -0.648656 0.284528 -0.705894 -0.648658 0.387413 -0.705894 -0.59298 0.387408 -0.705903 -0.592972 0.479725 -0.705902 -0.52112 0.479729 -0.705896 -0.521125 0.55896 -0.705896 -0.435056 0.558964 -0.705891 -0.435059 0.62295 -0.705891 -0.337124 0.622943 -0.705899 -0.33712 0.669933 -0.7059 -0.229988 0.669939 -0.705894 -0.22999 0.698656 -0.705894 -0.116585 0.698653 -0.705899 -0.116584 0.708313 -0.705899 0 0.708313 -0.705899 0 0.698652 -0.705899 0.116584 0.698656 -0.705895 0.116585 0.669938 -0.705895 0.22999 0.669932 -0.705902 0.229988 0.62294 -0.705902 0.337118 0.62295 -0.70589 0.337124 0.558964 -0.705891 0.435059 0.558957 -0.705901 0.435054 0.479726 -0.705901 0.521121 0.479725 -0.705902 0.52112 0.387408 -0.705903 0.592972 0.387413 -0.705894 0.59298 0.284528 -0.705894 0.648659 0.284527 -0.705897 0.648656 0.173881 -0.705896 0.686641 0.173879 -0.705904 0.686633 0.0584917 -0.705904 0.705888 0.0584919 -0.705903 0.70589 0.0584919 0.705901 0.705891 0.0584919 0.705903 0.70589 0.17388 0.705903 0.686635 0.173881 0.705895 0.686643 0.284528 0.705895 0.648658 0.284529 0.705892 0.64866 0.387414 0.705892 0.592981 0.387409 0.705902 0.592973 0.479726 0.7059 0.521122 0.479727 0.705899 0.521123 0.558958 0.705899 0.435055 0.558965 0.70589 0.43506 0.622951 0.705889 0.337125 0.622941 0.705901 0.337119 0.669933 0.7059 0.229988 0.669939 0.705894 0.22999 0.698658 0.705893 0.116585 0.698654 0.705897 0.116585 0.708315 0.705897 0 0.708315 0.705897 0 0.698654 0.705897 -0.116585 0.698658 0.705893 -0.116585 0.66994 0.705893 -0.229991 0.669935 0.705898 -0.229989 0.622944 0.705897 -0.337121 0.622951 0.705889 -0.337124 0.558966 0.705889 -0.43506 0.558962 0.705894 -0.435058 0.47973 0.705894 -0.521126 0.479726 0.705901 -0.521121 0.387409 0.705901 -0.592974 0.387414 0.705892 -0.592981 0.284529 0.705892 -0.64866 0.284527 0.705895 -0.648657 0.173882 0.705894 -0.686643 0.173879 0.705903 -0.686635 0.0584914 0.705903 -0.70589 0.0584931 0.705888 -0.705904 0.0584925 -0.70589 -0.705903 0.0584917 -0.705904 -0.705888 0.173879 -0.705904 -0.686633 0.173881 -0.705896 -0.686641 0.284527 -0.705896 -0.648656 0.284528 -0.705894 -0.648658 0.387413 -0.705894 -0.59298 0.387408 -0.705903 -0.592972 0.479725 -0.705902 -0.52112 0.479729 -0.705896 -0.521125 0.55896 -0.705896 -0.435056 0.558964 -0.705891 -0.435059 0.62295 -0.705891 -0.337124 0.622943 -0.705899 -0.33712 0.669933 -0.7059 -0.229988 0.669939 -0.705894 -0.22999 0.698656 -0.705894 -0.116585 0.698653 -0.705899 -0.116584 0.708313 -0.705899 0 0.708313 -0.705899 0 0.698652 -0.705899 0.116584 0.698656 -0.705895 0.116585 0.669938 -0.705895 0.22999 0.669932 -0.705902 0.229988 0.62294 -0.705902 0.337118 0.62295 -0.70589 0.337124 0.558964 -0.705891 0.435059 0.558957 -0.705901 0.435054 0.479726 -0.705901 0.521121 0.479725 -0.705902 0.52112 0.387408 -0.705903 0.592972 0.387413 -0.705894 0.59298 0.284528 -0.705894 0.648659 0.284527 -0.705897 0.648656 0.173881 -0.705896 0.686641 0.173879 -0.705904 0.686633 0.0584917 -0.705904 0.705888 0.0584919 -0.705903 0.70589 0.0825797 0 -0.996584 0.0825797 0 -0.996584 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837166 0.546948 0 -0.837166 0.677281 0 -0.735724 0.677281 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475947 0.879474 0 -0.475947 0.945817 0 -0.3247 0.945817 0 -0.3247 0.986361 0 -0.164594 0.986361 0 -0.164594 1 0 0 1 0 0 0.986361 0 0.164594 0.986361 0 0.164594 0.945817 0 0.3247 0.945817 0 0.3247 0.879474 0 0.475947 0.879474 0 0.475947 0.789141 0 0.614213 0.789141 0 0.614213 0.677281 0 0.735724 0.677281 0 0.735724 0.546948 0 0.837166 0.546948 0 0.837166 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825797 0 0.996584 0.0825797 0 0.996584 0.0825797 0 -0.996584 0.0825797 0 -0.996584 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837166 0.546948 0 -0.837166 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475947 0.879474 0 -0.475947 0.945817 0 -0.3247 0.945817 0 -0.3247 0.986361 0 -0.164594 0.986361 0 -0.164594 1 0 0 1 0 0 0.986361 0 0.164594 0.986361 0 0.164594 0.945817 0 0.3247 0.945817 0 0.3247 0.879474 0 0.475947 0.879474 0 0.475947 0.789141 0 0.614213 0.789141 0 0.614213 0.677281 0 0.735724 0.677281 0 0.735724 0.546948 0 0.837166 0.546948 0 0.837166 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825797 0 0.996584 0.0825797 0 0.996584 0.0825797 0 -0.996584 0.0825797 0 -0.996584 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837166 0.546948 0 -0.837166 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475947 0.879474 0 -0.475947 0.945817 0 -0.3247 0.945817 0 -0.3247 0.986361 0 -0.164594 0.986361 0 -0.164594 1 0 0 1 0 0 0.986361 0 0.164594 0.986361 0 0.164594 0.945817 0 0.3247 0.945817 0 0.3247 0.879474 0 0.475947 0.879474 0 0.475947 0.789141 0 0.614213 0.789141 0 0.614213 0.677281 0 0.735724 0.677281 0 0.735724 0.546948 0 0.837166 0.546948 0 0.837166 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825797 0 0.996584 0.0825797 0 0.996584 0.0825797 0 -0.996584 0.0825797 0 -0.996584 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837166 0.546948 0 -0.837166 0.677281 0 -0.735724 0.677281 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475947 0.879474 0 -0.475947 0.945817 0 -0.3247 0.945817 0 -0.3247 0.986361 0 -0.164594 0.986361 0 -0.164594 1 0 0 1 0 0 0.986361 0 0.164594 0.986361 0 0.164594 0.945817 0 0.3247 0.945817 0 0.3247 0.879474 0 0.475947 0.879474 0 0.475947 0.789141 0 0.614213 0.789141 0 0.614213 0.677281 0 0.735724 0.677281 0 0.735724 0.546948 0 0.837166 0.546948 0 0.837166 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825797 0 0.996584 0.0825797 0 0.996584 0.0825797 0 -0.996584 0.0825797 0 -0.996584 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837166 0.546948 0 -0.837166 0.677281 0 -0.735724 0.677281 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475947 0.879474 0 -0.475947 0.945817 0 -0.3247 0.945817 0 -0.3247 0.986361 0 -0.164594 0.986361 0 -0.164594 1 0 0 1 0 0 0.986361 0 0.164594 0.986361 0 0.164594 0.945817 0 0.3247 0.945817 0 0.3247 0.879474 0 0.475947 0.879474 0 0.475947 0.789141 0 0.614213 0.789141 0 0.614213 0.677281 0 0.735724 0.677281 0 0.735724 0.546948 0 0.837166 0.546948 0 0.837166 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825797 0 0.996584 0.0825797 0 0.996584 0.0825797 0 -0.996584 0.0825797 0 -0.996584 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837166 0.546948 0 -0.837166 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475947 0.879474 0 -0.475947 0.945817 0 -0.3247 0.945817 0 -0.3247 0.986361 0 -0.164594 0.986361 0 -0.164594 1 0 0 1 0 0 0.986361 0 0.164594 0.986361 0 0.164594 0.945817 0 0.3247 0.945817 0 0.3247 0.879474 0 0.475947 0.879474 0 0.475947 0.789141 0 0.614213 0.789141 0 0.614213 0.677281 0 0.735724 0.677281 0 0.735724 0.546948 0 0.837166 0.546948 0 0.837166 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825797 0 0.996584 0.0825797 0 0.996584 0.0825797 0 -0.996584 0.0825797 0 -0.996584 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837166 0.546948 0 -0.837166 0.677281 0 -0.735724 0.677281 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475947 0.879474 0 -0.475947 0.945817 0 -0.3247 0.945817 0 -0.3247 0.986361 0 -0.164594 0.986361 0 -0.164594 1 0 0 1 0 0 0.986361 0 0.164594 0.986361 0 0.164594 0.945817 0 0.3247 0.945817 0 0.3247 0.879474 0 0.475947 0.879474 0 0.475947 0.789141 0 0.614213 0.789141 0 0.614213 0.677281 0 0.735724 0.677281 0 0.735724 0.546948 0 0.837166 0.546948 0 0.837166 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825797 0 0.996584 0.0825797 0 0.996584 0.0825797 0 -0.996584 0.0825797 0 -0.996584 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837166 0.546948 0 -0.837166 0.677281 0 -0.735724 0.677281 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475947 0.879474 0 -0.475947 0.945817 0 -0.3247 0.945817 0 -0.3247 0.986361 0 -0.164594 0.986361 0 -0.164594 1 0 0 1 0 0 0.986361 0 0.164594 0.986361 0 0.164594 0.945817 0 0.3247 0.945817 0 0.3247 0.879474 0 0.475947 0.879474 0 0.475947 0.789141 0 0.614213 0.789141 0 0.614213 0.677281 0 0.735724 0.677281 0 0.735724 0.546948 0 0.837166 0.546948 0 0.837166 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825797 0 0.996584 0.0825797 0 0.996584 0.0584918 0.705903 0.70589 0.0584917 0.705904 0.705888 0.173879 0.705904 0.686633 0.173881 0.705896 0.686641 0.284527 0.705896 0.648656 0.284528 0.705894 0.648658 0.387413 0.705894 0.59298 0.387408 0.705903 0.592972 0.479725 0.705902 0.52112 0.479726 0.7059 0.521121 0.558957 0.7059 0.435054 0.558964 0.705891 0.435059 0.62295 0.705891 0.337124 0.622939 0.705902 0.337118 0.669931 0.705902 0.229988 0.669938 0.705895 0.22999 0.698656 0.705895 0.116585 0.698652 0.705899 0.116584 0.708313 0.705899 0 0.708313 0.705899 0 0.698653 0.705898 -0.116584 0.698657 0.705894 -0.116585 0.669939 0.705894 -0.22999 0.669933 0.7059 -0.229988 0.622943 0.705899 -0.33712 0.62295 0.70589 -0.337124 0.558964 0.705891 -0.435059 0.558961 0.705896 -0.435057 0.479729 0.705896 -0.521125 0.479725 0.705902 -0.52112 0.387408 0.705903 -0.592972 0.387413 0.705894 -0.59298 0.284528 0.705894 -0.648659 0.284527 0.705897 -0.648656 0.173881 0.705896 -0.686641 0.173879 0.705904 -0.686633 0.0584913 0.705904 -0.705888 0.058493 0.705889 -0.705903 0.0584925 -0.70589 -0.705903 0.0584917 -0.705904 -0.705888 0.173879 -0.705904 -0.686633 0.173881 -0.705896 -0.686641 0.284527 -0.705896 -0.648656 0.284528 -0.705894 -0.648658 0.387413 -0.705894 -0.59298 0.387408 -0.705903 -0.592972 0.479725 -0.705902 -0.52112 0.479729 -0.705896 -0.521125 0.55896 -0.705896 -0.435056 0.558964 -0.705891 -0.435059 0.62295 -0.705891 -0.337124 0.622943 -0.705899 -0.33712 0.669933 -0.7059 -0.229988 0.669939 -0.705894 -0.22999 0.698656 -0.705894 -0.116585 0.698653 -0.705899 -0.116584 0.708313 -0.705899 0 0.708313 -0.705899 0 0.698652 -0.705899 0.116584 0.698656 -0.705895 0.116585 0.669938 -0.705895 0.22999 0.669932 -0.705902 0.229988 0.62294 -0.705902 0.337118 0.62295 -0.70589 0.337124 0.558964 -0.705891 0.435059 0.558957 -0.705901 0.435054 0.479726 -0.705901 0.521121 0.479725 -0.705902 0.52112 0.387408 -0.705903 0.592972 0.387413 -0.705894 0.59298 0.284528 -0.705894 0.648659 0.284527 -0.705897 0.648656 0.173881 -0.705896 0.686641 0.173879 -0.705904 0.686633 0.0584917 -0.705904 0.705888 0.0584919 -0.705903 0.70589 0.0825797 0 -0.996584 0.0825797 0 -0.996584 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837166 0.546948 0 -0.837166 0.677281 0 -0.735724 0.677281 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475947 0.879474 0 -0.475947 0.945817 0 -0.3247 0.945817 0 -0.3247 0.986361 0 -0.164594 0.986361 0 -0.164594 1 0 0 1 0 0 0.986361 0 0.164594 0.986361 0 0.164594 0.945817 0 0.3247 0.945817 0 0.3247 0.879474 0 0.475947 0.879474 0 0.475947 0.789141 0 0.614213 0.789141 0 0.614213 0.677281 0 0.735724 0.677281 0 0.735724 0.546948 0 0.837166 0.546948 0 0.837166 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825797 0 0.996584 0.0825797 0 0.996584 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 -0.84912 -0.510202 -0.136708 -0.84912 -0.373494 -0.373494 -0.84912 -0.136708 -0.510202 -0.84912 -0.136708 0.510202 -0.84912 -0.373494 0.373494 -0.84912 -0.510202 0.136709 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 -0.84912 -0.510202 -0.136708 -0.84912 -0.373494 -0.373494 -0.84912 -0.136708 -0.510202 -0.84912 -0.136708 0.510202 -0.84912 -0.373494 0.373494 -0.84912 -0.510202 0.136708 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0.84912 -0.510202 0.136709 0.84912 -0.373494 0.373494 0.84912 -0.136708 0.510202 0.84912 -0.136708 -0.510202 0.84912 -0.373494 -0.373494 0.84912 -0.510202 -0.136708 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0.84912 -0.510202 0.136708 0.84912 -0.373494 0.373494 0.84912 -0.136708 0.510202 0.84912 -0.136708 -0.510202 0.84912 -0.373494 -0.373494 0.84912 -0.510202 -0.136708 0.15933 0.698075 0.698073 0.159332 0.698074 0.698073 0.446435 0.698074 0.559812 0.446433 0.698074 0.559812 0.645117 0.698074 0.31067 0.645115 0.698076 0.310672 0.716024 0.698076 0 0.716024 0.698076 0 0.645116 0.698076 -0.310669 0.645116 0.698075 -0.310672 0.446434 0.698074 -0.559811 0.446434 0.698074 -0.559813 0.159333 0.698074 -0.698073 0.159332 0.698074 -0.698074 0.222521 0 0.974928 0.258817 0.00192589 0.965925 0.623489 -0.00160938 0.781831 0.652291 0 0.757968 0.826229 0 0.563335 0.900967 -0.00257862 0.43388 0.930879 0 0.365327 0.99371 0 0.11198 0.999996 -0.00290226 0 0.99371 0 -0.11198 0.930879 0 -0.365327 0.900967 -0.00257862 -0.43388 0.826229 0 -0.563335 0.623489 0 -0.781832 0.65229 -0.0019263 -0.757967 0.222523 0.00224004 -0.974925 0.25882 0 -0.965926 0.186157 -0.694747 0.694746 0.186156 -0.694746 0.694748 0.508589 -0.694745 0.508593 0.489825 -0.660382 0.569181 0.58505 -0.706116 0.398895 0.694748 -0.694746 0.186154 0.714784 -0.640619 0.28052 0.704874 -0.704871 0.0794317 0.704874 -0.704871 -0.0794317 0.714296 -0.673165 -0.191392 0.186157 -0.694746 -0.694747 0.186158 -0.694746 -0.694747 0.465279 -0.70086 -0.540658 0.520479 -0.676904 -0.520483 0.58505 -0.706116 -0.398895 0.661918 -0.703124 -0.259772 0.159333 0.698073 0.698074 0.159331 0.698074 0.698074 0.446436 0.698073 0.559811 0.446434 0.698074 0.559812 0.645115 0.698075 0.310673 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645116 0.698074 -0.310674 0.645116 0.698075 -0.310672 0.446438 0.698075 -0.559808 0.446436 0.698073 -0.559811 0.159328 0.698073 -0.698074 0.15933 0.698075 -0.698073 0.222524 0 0.974927 0.258821 0.00192595 0.965924 0.62349 -0.00160918 0.78183 0.652289 0 0.75797 0.826241 0 0.563316 0.900965 -0.00257813 0.433885 0.930872 0 0.365346 0.993712 0 0.111967 0.999996 -0.00290192 0 0.993712 0 -0.111968 0.930873 0 -0.365343 0.900965 -0.00257828 -0.433885 0.826235 0 -0.563326 0.623495 0 -0.781828 0.652293 -0.0019261 -0.757965 0.222517 0.00224016 -0.974926 0.258816 0 -0.965927 0.186157 -0.694746 0.694748 0.186158 -0.694747 0.694746 0.50859 -0.694746 0.50859 0.489825 -0.66038 0.569184 0.585057 -0.706117 0.398882 0.694746 -0.694747 0.186156 0.714785 -0.64061 0.280537 0.704874 -0.704872 0.0794218 0.704874 -0.704872 -0.0794229 0.714297 -0.673162 -0.191396 0.186154 -0.694748 -0.694746 0.186156 -0.694746 -0.694747 0.46528 -0.700861 -0.540656 0.520482 -0.676904 -0.52048 0.585054 -0.706116 -0.398889 0.661913 -0.703125 -0.259783 0.186155 0.694749 0.694744 0.186159 0.694747 0.694745 0.508589 0.694747 0.508589 0.508588 0.694748 0.50859 0.694746 0.694747 0.186157 0.694747 0.694747 0.186156 0.694747 0.694747 -0.186157 0.694746 0.694747 -0.186156 0.508589 0.694748 -0.508589 0.508589 0.694747 -0.50859 0.186155 0.694747 -0.694747 0.186154 0.694746 -0.694748 0.258817 0 0.965926 0.258817 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258817 0 -0.965926 0.258817 0 -0.965926 0.186156 -0.694746 -0.694748 0.186154 -0.694746 -0.694748 0.50859 -0.694747 -0.50859 0.508589 -0.694747 -0.50859 0.694746 -0.694747 -0.186157 0.694747 -0.694746 -0.186156 0.694747 -0.694746 0.186157 0.694746 -0.694747 0.186156 0.508589 -0.694748 0.508589 0.508589 -0.694747 0.50859 0.186155 -0.694747 0.694747 0.186158 -0.694749 0.694744 0.186156 -0.694749 -0.694745 0.186157 -0.694748 -0.694746 0.508587 -0.694749 -0.508588 0.508595 -0.694741 -0.508592 0.694754 -0.69474 -0.186157 0.694749 -0.694744 -0.186158 0.694749 -0.694745 0.186156 0.694752 -0.69474 0.186159 0.508592 -0.694743 0.508593 0.508589 -0.69475 0.508585 0.186156 -0.69475 0.694743 0.186156 -0.694747 0.694747 0.258818 0 -0.965926 0.258818 0 -0.965926 0.707106 0 -0.707107 0.707106 0 -0.707107 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258817 0.965926 0 0.258817 0.707106 0 0.707107 0.707106 0 0.707107 0.25882 0 0.965926 0.25882 0 0.965926 0.186154 -0.694749 -0.694745 0.186157 -0.694744 -0.694749 0.508593 -0.694744 -0.508591 0.508589 -0.694748 -0.508589 0.694744 -0.694749 -0.186157 0.694744 -0.694749 -0.186157 0.694745 -0.694749 0.186156 0.694745 -0.694749 0.186156 0.508589 -0.694748 0.508589 0.508589 -0.694748 0.508589 0.186156 -0.694749 0.694745 0.186156 -0.694749 0.694745 0.258816 0 -0.965927 0.258816 0 -0.965927 0.707108 0 -0.707105 0.707108 0 -0.707105 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.258819 0.965926 0 0.258819 0.707107 0 0.707107 0.707107 0 0.707107 0.258819 0 0.965926 0.258819 0 0.965926 0.186156 -0.694745 -0.694749 0.186153 -0.694748 -0.694746 0.50859 -0.694747 -0.508589 0.508588 -0.694749 -0.508588 0.694746 -0.694748 -0.186156 0.694745 -0.694749 -0.186156 0.694745 -0.694749 0.186156 0.694746 -0.694748 0.186157 0.508588 -0.694749 0.508587 0.508589 -0.694748 0.508589 0.186155 -0.694749 0.694745 0.186155 -0.694753 0.69474 0.258817 0 -0.965926 0.258817 0 -0.965926 0.707107 0 -0.707106 0.707107 0 -0.707106 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258818 0.965926 0 0.258818 0.707107 0 0.707106 0.707107 0 0.707106 0.258817 0 0.965926 0.258817 0 0.965926 0.159331 -0.698074 0.698074 0.159331 -0.698073 0.698074 0.330528 -0.706858 0.625383 0.472936 -0.651633 0.593048 0.465273 -0.700864 0.540658 0.585054 -0.706119 0.398884 0.707217 -0.619559 0.340575 0.661912 -0.703128 0.259777 0.716023 -0.698076 0 0.878512 -0.467353 0.0989871 0.704871 -0.704876 -0.0794217 0.645116 -0.698076 -0.310669 0.770332 -0.561414 -0.302328 0.585052 -0.706119 -0.398885 0.446432 -0.698076 -0.559812 0.15933 -0.698076 -0.698072 0.159332 -0.698073 -0.698074 0.330523 -0.706858 -0.625385 0.502603 -0.637411 -0.584035 0.186156 -0.694745 0.694749 0.186156 -0.69475 0.694743 0.508587 -0.694751 0.508587 0.554 -0.527881 0.643759 0.585053 -0.70612 0.398883 0.694745 -0.694749 0.186153 0.849549 -0.408778 0.333418 0.704875 -0.704871 0.0794224 0.704875 -0.704871 -0.0794224 0.795849 -0.566702 -0.213243 0.186155 -0.694749 -0.694745 0.186157 -0.694745 -0.694748 0.465274 -0.700862 -0.540659 0.569931 -0.59191 -0.569931 0.585055 -0.706117 -0.398885 0.661913 -0.703126 -0.259778 0.159332 -0.698071 0.698076 0.159333 -0.698076 0.69807 0.330521 -0.706862 0.625382 0.472936 -0.651636 0.593045 0.465273 -0.700864 0.540657 0.585056 -0.706119 0.398881 0.707213 -0.619563 0.340576 0.661911 -0.703127 0.259781 0.70487 -0.704876 0.0794219 0.793864 -0.608096 0 0.704871 -0.704875 -0.0794214 0.645116 -0.698075 -0.310672 0.770329 -0.561417 -0.302331 0.585051 -0.706119 -0.398887 0.446434 -0.698076 -0.559809 0.159331 -0.698076 -0.698072 0.159331 -0.698076 -0.698071 0.330521 -0.706862 -0.625382 0.502602 -0.637416 -0.584031 0.186156 -0.694745 -0.694749 0.186153 -0.694748 -0.694746 0.50859 -0.694747 -0.508589 0.508588 -0.694749 -0.508588 0.694746 -0.694748 -0.186156 0.694745 -0.694749 -0.186156 0.694745 -0.694749 0.186156 0.694746 -0.694748 0.186157 0.508588 -0.694749 0.508587 0.508589 -0.694748 0.508589 0.186158 -0.694749 0.694744 0.186158 -0.694744 0.694749 0.186157 0.694747 0.694747 0.186155 0.69475 0.694744 0.508586 0.694751 0.508587 0.508594 0.694743 0.50859 0.694753 0.69474 0.186157 0.694749 0.694744 0.186158 0.694749 0.694745 -0.186156 0.694753 0.69474 -0.186159 0.508593 0.694741 -0.508594 0.50859 0.694749 -0.508586 0.186156 0.694748 -0.694746 0.186156 0.694749 -0.694745 0.222521 0 0.974928 0.258819 -0.00161878 0.965924 0.467273 0 0.884113 0.652286 0 0.757973 0.707103 -0.00270296 0.707105 0.826238 0 0.563321 0.930876 0 0.365336 0.965921 -0.00324645 0.258816 0.993712 0 0.111967 0.993712 0 -0.111967 0.965921 -0.00324647 -0.258815 0.930876 0 -0.365336 0.826237 0 -0.563323 0.707103 -0.00270291 -0.707105 0.652287 0 -0.757972 0.467265 0 -0.884117 0.258818 -0.00161872 -0.965925 0.222521 0 -0.974928 0.159332 0.698071 0.698076 0.159328 0.698077 0.698071 0.446431 0.698079 0.559808 0.446434 0.698076 0.559809 0.645116 0.698076 0.310669 0.645115 0.698077 0.310669 0.716023 0.698076 0 0.716023 0.698076 0 0.645115 0.698077 -0.310669 0.645115 0.698077 -0.310669 0.446433 0.698076 -0.55981 0.446433 0.698075 -0.559811 0.15933 0.698073 -0.698075 0.159331 0.698076 -0.698072 0.222522 0 0.974928 0.258819 0.00161871 0.965924 0.623489 -0.00135245 0.781831 0.652287 0 0.757972 0.826238 0 0.563321 0.900968 -0.00216698 0.43388 0.930876 0 0.365336 0.993712 0 0.111967 0.999997 -0.00243897 0 0.993712 0 -0.111967 0.930876 0 -0.365336 0.900968 -0.00216698 -0.43388 0.826238 0 -0.563321 0.623489 0 -0.781832 0.652287 -0.00161877 -0.757971 0.222519 0.00188277 -0.974927 0.258817 0 -0.965926 0.186159 0.694744 0.694748 0.186156 0.694749 0.694745 0.50859 0.694747 0.508588 0.508587 0.694751 0.508587 0.694743 0.69475 0.186157 0.694744 0.694749 0.186157 0.694745 0.694749 -0.186156 0.694745 0.694749 -0.186156 0.508589 0.694748 -0.508589 0.508589 0.694748 -0.508589 0.186156 0.694749 -0.694745 0.186156 0.694749 -0.694745 0.222525 0 0.974927 0.258821 -0.00161869 0.965924 0.467265 0 0.884117 0.652287 0 0.757972 0.707106 -0.00270302 0.707103 0.826241 0 0.563316 0.930873 0 0.365342 0.96592 -0.00324653 0.258819 0.993712 0 0.111967 0.993712 0 -0.111967 0.965921 -0.00324654 -0.258818 0.930874 0 -0.36534 0.826235 0 -0.563326 0.707104 -0.00270284 -0.707104 0.65229 0 -0.75797 0.467265 0 -0.884117 0.258819 -0.00161871 -0.965925 0.222522 0 -0.974928 0.159328 0.698072 -0.698076 0.159329 0.698076 -0.698072 0.330521 0.706862 -0.625382 0.47294 0.651634 -0.593044 0.465277 0.700861 -0.540658 0.585056 0.706115 -0.398887 0.707218 0.619555 -0.340578 0.661913 0.703125 -0.25978 0.704873 0.704874 -0.0794203 0.793864 0.608096 0 0.704873 0.704874 0.0794193 0.645116 0.698075 0.310672 0.770327 0.56142 0.302332 0.585061 0.706115 0.39888 0.446435 0.698073 0.559813 0.159334 0.698071 0.698075 0.159331 0.698076 0.698071 0.330521 0.706862 0.625382 0.502598 0.637418 0.584032 0.222525 0 0.974927 0.258822 0.00161869 0.965924 0.467265 0 0.884117 0.652285 0 0.757974 0.707105 0.00270308 0.707103 0.826244 0 0.563313 0.930873 0 0.365342 0.965921 0.00324659 0.258817 0.993712 0 0.111963 0.993712 0 -0.111965 0.965921 0.00324652 -0.258817 0.930875 0 -0.365338 0.826237 0 -0.563322 0.707105 0.00270288 -0.707103 0.222519 0 -0.974928 0.258816 0.00161873 -0.965925 0.467265 0 -0.884117 0.65229 0 -0.75797 0.186155 0.694748 0.694746 0.186156 0.694747 0.694746 0.508589 0.694748 0.508589 0.50859 0.694747 0.508589 0.694747 0.694747 0.186155 0.694744 0.694749 0.186158 0.694744 0.694749 -0.186155 0.694745 0.694747 -0.186159 0.508589 0.694747 -0.508589 0.50859 0.694748 -0.508588 0.186157 0.694747 -0.694746 0.186156 0.694747 -0.694747 0.258817 0 0.965926 0.258817 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.707107 0 -0.707107 0.707107 0 -0.707107 0.25882 0 -0.965926 0.25882 0 -0.965926 0.186157 -0.694746 -0.694747 0.186156 -0.694747 -0.694746 0.508589 -0.694748 -0.508589 0.50859 -0.694747 -0.508589 0.694747 -0.694747 -0.186155 0.694744 -0.694749 -0.186158 0.694745 -0.694749 0.186155 0.694746 -0.694747 0.186159 0.50859 -0.694747 0.50859 0.50859 -0.694747 0.508589 0.186155 -0.694747 0.694747 0.186156 -0.694747 0.694746 0.18616 0.694745 0.694747 0.186157 0.694747 0.694746 0.508592 0.694746 0.508588 0.508589 0.694748 0.508589 0.694745 0.694748 0.186159 0.694748 0.694746 0.186157 0.694747 0.694745 -0.18616 0.694746 0.694747 -0.186157 0.508592 0.694747 -0.508588 0.508591 0.694746 -0.508589 0.186155 0.694746 -0.694747 0.186157 0.694748 -0.694746 0.222525 0 0.974927 0.258822 -0.00192594 0.965923 0.467265 0 0.884117 0.652285 0 0.757974 0.707106 -0.00321629 0.7071 0.826251 0 0.563303 0.930872 0 0.365346 0.965918 -0.00386286 0.258821 0.993712 0 0.111967 0.993712 0 -0.111968 0.965918 -0.00386277 -0.258821 0.930873 0 -0.365343 0.826244 0 -0.563312 0.707106 -0.00321605 -0.7071 0.65229 0 -0.75797 0.467265 0 -0.884117 0.258817 -0.00192598 -0.965925 0.222519 0 -0.974928 0.159332 -0.698072 0.698075 0.159334 -0.698074 0.698073 0.330522 -0.706859 0.625384 0.451633 -0.689417 0.566331 0.465274 -0.700861 0.540661 0.585066 -0.706115 0.398873 0.657191 -0.684059 0.316486 0.661912 -0.703124 0.259786 0.716026 -0.698074 0 0.753107 -0.652402 0.0848565 0.704873 -0.704874 -0.0794227 0.645116 -0.698074 -0.310673 0.691863 -0.669024 -0.271538 0.585061 -0.706115 -0.39888 0.446436 -0.698073 -0.559811 0.159329 -0.698075 -0.698073 0.159331 -0.698074 -0.698074 0.330522 -0.706859 -0.625384 0.475706 -0.684208 -0.552777 0.159324 0.698077 0.698072 0.159334 0.698072 0.698074 0.44644 0.698072 0.55981 0.446433 0.698075 0.559811 0.645115 0.698075 0.310673 0.645116 0.698074 0.310673 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698073 -0.310674 0.645117 0.698074 -0.31067 0.446432 0.698075 -0.559812 0.446433 0.698076 -0.559811 0.159334 0.698076 -0.698071 0.159328 0.698073 -0.698075 0.222513 0 0.97493 0.222513 0 0.97493 0.623496 0 0.781827 0.623496 0 0.781827 0.900968 0 0.433886 0.900968 0 0.433886 1 0 0 1 0 0 0.900968 0 -0.433886 0.900968 0 -0.433886 0.623487 0 -0.781833 0.623487 0 -0.781833 0.222525 0 -0.974927 0.222525 0 -0.974927 0.159334 -0.698072 -0.698074 0.159328 -0.698075 -0.698073 0.446432 -0.698076 -0.559812 0.446433 -0.698075 -0.559811 0.645115 -0.698075 -0.310674 0.645118 -0.698073 -0.310671 0.716026 -0.698074 0 0.716026 -0.698074 0 0.645116 -0.698074 0.310674 0.645116 -0.698075 0.310673 0.446438 -0.698076 0.559807 0.446435 -0.698072 0.559813 0.159325 -0.698071 0.698077 0.159333 -0.698076 0.698071 0.15933 -0.698076 -0.698072 0.159331 -0.698075 -0.698072 0.446433 -0.698077 -0.559809 0.446434 -0.698076 -0.55981 0.645113 -0.698077 -0.310673 0.645115 -0.698075 -0.310673 0.716023 -0.698076 0 0.716023 -0.698076 0 0.645114 -0.698076 0.310673 0.645113 -0.698077 0.310672 0.446433 -0.698076 0.55981 0.446433 -0.698077 0.559809 0.15933 -0.698075 0.698073 0.15933 -0.698074 0.698074 0.222521 0 -0.974928 0.222521 0 -0.974928 0.623489 0 -0.781832 0.623489 0 -0.781832 0.900967 0 -0.433887 0.900967 0 -0.433887 1 0 0 1 0 0 0.900968 0 0.433886 0.900968 0 0.433886 0.623489 0 0.781832 0.623489 0 0.781832 0.222521 0 0.974928 0.222521 0 0.974928 0.186155 -0.694749 -0.694745 0.186158 -0.694744 -0.694749 0.508593 -0.694744 -0.508591 0.508589 -0.694748 -0.508589 0.694744 -0.694749 -0.186157 0.694744 -0.694749 -0.186157 0.694745 -0.694749 0.186156 0.694745 -0.694749 0.186156 0.508589 -0.694748 0.508589 0.508589 -0.694748 0.508589 0.186157 -0.694749 0.694744 0.186157 -0.694749 0.694744 0.258817 0 -0.965926 0.258817 0 -0.965926 0.707108 0 -0.707105 0.707108 0 -0.707105 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.258819 0.965926 0 0.258819 0.707107 0 0.707107 0.707107 0 0.707107 0.25882 0 0.965926 0.25882 0 0.965926 0.186156 -0.694745 -0.694749 0.186153 -0.694749 -0.694745 0.508589 -0.694749 -0.508588 0.508587 -0.694751 -0.508587 0.694743 -0.69475 -0.186156 0.694747 -0.694747 -0.186156 0.694747 -0.694747 0.186157 0.694744 -0.69475 0.186155 0.508587 -0.694751 0.508586 0.508588 -0.694749 0.508588 0.186155 -0.694749 0.694745 0.186155 -0.694753 0.69474 0.258817 0 -0.965926 0.258817 0 -0.965926 0.707107 0 -0.707106 0.707107 0 -0.707106 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.707107 0 0.707106 0.707107 0 0.707106 0.258817 0 0.965926 0.258817 0 0.965926 0.186156 -0.694749 -0.694745 0.186157 -0.694748 -0.694746 0.508587 -0.694749 -0.508588 0.508589 -0.694748 -0.508589 0.694744 -0.694749 -0.186158 0.694749 -0.694744 -0.186158 0.694748 -0.694744 0.18616 0.694744 -0.694749 0.186156 0.508588 -0.694749 0.508589 0.508587 -0.694751 0.508587 0.186156 -0.69475 0.694743 0.186156 -0.694747 0.694747 0.186156 -0.694745 0.694749 0.186156 -0.694749 0.694745 0.508589 -0.694748 0.508589 0.554 -0.527883 0.643757 0.585053 -0.70612 0.398883 0.694744 -0.69475 0.186156 0.849547 -0.408779 0.333422 0.704871 -0.704875 0.0794219 0.704871 -0.704875 -0.0794219 0.795847 -0.566703 -0.213247 0.186154 -0.694749 -0.694745 0.186157 -0.694744 -0.694749 0.465278 -0.700859 -0.54066 0.569931 -0.59191 -0.569931 0.585055 -0.706117 -0.398885 0.661912 -0.703126 -0.25978 0.186158 -0.694744 0.694749 0.186159 -0.694749 0.694744 0.508589 -0.694748 0.508589 0.554003 -0.527867 0.643767 0.585058 -0.70612 0.398875 0.694743 -0.69475 0.186156 0.849553 -0.408759 0.33343 0.704871 -0.704876 0.0794173 0.704871 -0.704876 -0.0794167 0.795853 -0.566696 -0.213248 0.186157 -0.694749 -0.694744 0.186157 -0.694749 -0.694744 0.465274 -0.700863 -0.540658 0.569931 -0.59191 -0.569931 0.585056 -0.706118 -0.398883 0.66191 -0.703127 -0.259784 0.186156 -0.694745 -0.694749 0.186153 -0.694749 -0.694745 0.508589 -0.694749 -0.508588 0.508587 -0.694751 -0.508587 0.694743 -0.69475 -0.186156 0.694747 -0.694747 -0.186156 0.694747 -0.694747 0.186157 0.694744 -0.69475 0.186155 0.508587 -0.694751 0.508586 0.508588 -0.694749 0.508588 0.186158 -0.69475 0.694743 0.186158 -0.694744 0.694749 0.186157 0.694747 0.694747 0.186155 0.69475 0.694744 0.508586 0.694751 0.508587 0.508588 0.694749 0.508588 0.694743 0.69475 0.186158 0.694749 0.694744 0.186158 0.694748 0.694744 -0.18616 0.694745 0.694749 -0.186156 0.508589 0.694747 -0.50859 0.508588 0.694749 -0.508588 0.186156 0.694748 -0.694746 0.186156 0.694749 -0.694745 0.25882 0 0.965926 0.25882 0 0.965926 0.707106 0 0.707107 0.707106 0 0.707107 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 -0.258822 0.965925 0 -0.258822 0.707106 0 -0.707107 0.707106 0 -0.707107 0.258818 0 -0.965926 0.258818 0 -0.965926 0.159332 0.698071 0.698076 0.159329 0.698076 0.698072 0.446434 0.698076 0.559809 0.446434 0.698076 0.559809 0.645114 0.698077 0.310671 0.645115 0.698077 0.310671 0.716023 0.698076 0 0.716023 0.698076 0 0.645115 0.698077 -0.310671 0.645114 0.698077 -0.310671 0.446434 0.698076 -0.559809 0.446435 0.698072 -0.559813 0.159329 0.698071 -0.698076 0.159331 0.698076 -0.698072 0.222522 0 0.974928 0.258819 0.00161871 0.965925 0.62349 -0.00135246 0.78183 0.65229 0 0.75797 0.826238 0 0.563321 0.900967 -0.00216694 0.433883 0.930874 0 0.36534 0.993712 0 0.111967 0.999997 -0.00243897 0 0.993712 0 -0.111967 0.930874 0 -0.36534 0.900967 -0.00216694 -0.433883 0.826238 0 -0.563321 0.623491 0 -0.781831 0.652289 -0.00161879 -0.757969 0.222518 0.00188278 -0.974927 0.258816 0 -0.965927 0.159335 0.698071 0.698075 0.159331 0.698076 0.698071 0.446432 0.698076 0.559811 0.446435 0.698073 0.559813 0.645118 0.698073 0.310672 0.645118 0.698072 0.310673 0.716028 0.698072 0 0.716028 0.698072 0 0.64512 0.69807 -0.310674 0.645118 0.698073 -0.310672 0.446435 0.698073 -0.559812 0.446434 0.698076 -0.559809 0.159331 0.698076 -0.698071 0.159331 0.698076 -0.698072 0.222526 0 0.974927 0.258822 0.00161869 0.965924 0.623487 -0.00135243 0.781833 0.652285 0 0.757974 0.826246 0 0.56331 0.900967 -0.00216674 0.433883 0.930872 0 0.365346 0.993713 0 0.111961 0.999997 -0.00243883 0 0.993713 0 -0.11196 0.930872 0 -0.365344 0.900966 -0.00216685 -0.433884 0.82624 0 -0.563319 0.623489 0 -0.781832 0.652287 -0.00161877 -0.757971 0.222522 0.00188275 -0.974926 0.25882 0 -0.965926 0.159328 0.698072 -0.698076 0.159329 0.698076 -0.698072 0.330524 0.706862 -0.62538 0.472939 0.651636 -0.593043 0.465276 0.700863 -0.540657 0.585055 0.706117 -0.398886 0.707216 0.619558 -0.340577 0.661913 0.703125 -0.259781 0.704873 0.704874 -0.0794203 0.793864 0.608096 0 0.704873 0.704874 0.0794193 0.645116 0.698075 0.310672 0.770323 0.561425 0.302332 0.585059 0.706117 0.398879 0.446434 0.698074 0.559812 0.159334 0.698071 0.698075 0.159331 0.698076 0.698071 0.330524 0.706862 0.62538 0.502596 0.63742 0.584031 0.222525 0 0.974927 0.258822 0.0016187 0.965924 0.467269 0 0.884115 0.652285 0 0.757974 0.707105 0.00270308 0.707103 0.826244 0 0.563313 0.930873 0 0.365344 0.965921 0.00324662 0.258818 0.993712 0 0.111963 0.993712 0 -0.111965 0.965921 0.00324655 -0.258818 0.930874 0 -0.365341 0.826237 0 -0.563322 0.707105 0.00270288 -0.707103 0.222519 0 -0.974928 0.258817 0.00161874 -0.965925 0.467269 0 -0.884115 0.65229 0 -0.75797 0.186157 0.694747 0.694747 0.186158 0.694746 0.694747 0.50859 0.694745 0.508592 0.508588 0.694746 0.508592 0.694747 0.694747 0.186155 0.694748 0.694746 0.186155 0.694748 0.694746 -0.186155 0.694748 0.694746 -0.186154 0.508589 0.694746 -0.508591 0.508589 0.694746 -0.508592 0.186157 0.694746 -0.694747 0.186158 0.694746 -0.694746 0.25882 0 0.965926 0.25882 0 0.965926 0.707105 0 0.707108 0.707105 0 0.707108 0.965926 0 0.258817 0.965926 0 0.258817 0.965927 0 -0.258816 0.965927 0 -0.258816 0.707105 0 -0.707108 0.707105 0 -0.707108 0.25882 0 -0.965926 0.25882 0 -0.965926 0.186157 -0.694746 -0.694747 0.186158 -0.694746 -0.694747 0.50859 -0.694745 -0.508592 0.508588 -0.694746 -0.508592 0.694748 -0.694746 -0.186155 0.694748 -0.694746 -0.186154 0.694748 -0.694746 0.186156 0.694748 -0.694746 0.186155 0.508589 -0.694746 0.508591 0.508589 -0.694745 0.508593 0.186157 -0.694746 0.694747 0.186158 -0.694746 0.694747 0.186158 0.694746 0.694747 0.186156 0.694747 0.694747 0.50859 0.694746 0.50859 0.50859 0.694746 0.50859 0.694746 0.694747 0.186158 0.694748 0.694746 0.186157 0.694747 0.694745 -0.18616 0.694746 0.694747 -0.186157 0.50859 0.694746 -0.50859 0.50859 0.694746 -0.50859 0.186158 0.694747 -0.694746 0.186157 0.694746 -0.694748 0.258821 0 0.965925 0.258821 0 0.965925 0.707107 0 0.707107 0.707107 0 0.707107 0.965925 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258822 0.965925 0 -0.258822 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258821 0 -0.965925 0.258821 0 -0.965925 0.186159 -0.694745 -0.694748 0.186156 -0.694746 -0.694747 0.50859 -0.694746 -0.50859 0.50859 -0.694746 -0.50859 0.694746 -0.694747 -0.186159 0.694748 -0.694745 -0.186157 0.694748 -0.694745 0.186159 0.694747 -0.694746 0.186156 0.50859 -0.694746 0.50859 0.50859 -0.694746 0.50859 0.186158 -0.694747 0.694746 0.186157 -0.694746 0.694748 0.186156 0.694746 0.694748 0.186154 0.694747 0.694747 0.508589 0.694747 0.508589 0.508592 0.694746 0.508589 0.694747 0.694746 0.186157 0.694746 0.694746 0.186158 0.694747 0.694747 -0.186157 0.694746 0.694747 -0.186156 0.508589 0.694748 -0.508589 0.508589 0.694747 -0.50859 0.186155 0.694747 -0.694747 0.186158 0.694749 -0.694744 0.258817 0 0.965926 0.258817 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258817 0 -0.965926 0.258817 0 -0.965926 0.186155 -0.694749 -0.694745 0.186159 -0.694747 -0.694746 0.50859 -0.694747 -0.50859 0.508589 -0.694747 -0.50859 0.694746 -0.694747 -0.186157 0.694747 -0.694746 -0.186156 0.694747 -0.694746 0.186157 0.694747 -0.694746 0.186158 0.508591 -0.694745 0.508591 0.508592 -0.694746 0.508588 0.186155 -0.694747 0.694747 0.186154 -0.694746 0.694748 0.186157 -0.694747 -0.694747 0.186157 -0.694748 -0.694746 0.508587 -0.694749 -0.508588 0.508594 -0.694743 -0.508591 0.694753 -0.69474 -0.186157 0.694749 -0.694744 -0.186157 0.694749 -0.694745 0.186156 0.694752 -0.69474 0.186159 0.508592 -0.694743 0.508593 0.50859 -0.694749 0.508587 0.186157 -0.694748 0.694745 0.186157 -0.694747 0.694747 0.25882 0 -0.965926 0.25882 0 -0.965926 0.707106 0 -0.707107 0.707106 0 -0.707107 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258817 0.965926 0 0.258817 0.707106 0 0.707107 0.707106 0 0.707107 0.25882 0 0.965926 0.25882 0 0.965926 0.159328 -0.698076 -0.698072 0.159332 -0.698072 -0.698075 0.446437 -0.698072 -0.559812 0.446433 -0.698077 -0.55981 0.645117 -0.698075 -0.310671 0.645115 -0.698077 -0.310671 0.716023 -0.698076 0 0.716023 -0.698076 0 0.645117 -0.698075 0.310671 0.645118 -0.698073 0.310672 0.446435 -0.698073 0.559812 0.446434 -0.698076 0.559809 0.159331 -0.698076 0.698071 0.159331 -0.698076 0.698072 0.222518 0 -0.974928 0.222518 0 -0.974928 0.623491 0 -0.78183 0.623491 0 -0.78183 0.90097 0 -0.433882 0.90097 0 -0.433882 1 0 0 1 0 0 0.90097 0 0.433882 0.90097 0 0.433882 0.623489 0 0.781832 0.623489 0 0.781832 0.222522 0 0.974928 0.222522 0 0.974928 0.159334 -0.698071 -0.698075 0.159331 -0.698076 -0.698071 0.446432 -0.698076 -0.559811 0.446435 -0.698073 -0.559813 0.645119 -0.698073 -0.310672 0.645116 -0.698075 -0.310672 0.716026 -0.698074 0 0.716026 -0.698074 0 0.645117 -0.698075 0.310671 0.645118 -0.698073 0.310672 0.446436 -0.698073 0.559811 0.446437 -0.698069 0.559816 0.159331 -0.698067 0.69808 0.159332 -0.698071 0.698076 0.222525 0 -0.974927 0.222525 0 -0.974927 0.623487 0 -0.781834 0.623487 0 -0.781834 0.90097 0 -0.433882 0.90097 0 -0.433882 1 0 0 1 0 0 0.90097 0 0.433882 0.90097 0 0.433882 0.623491 0 0.78183 0.623491 0 0.78183 0.222519 0 0.974928 0.222519 0 0.974928 0.186157 -0.694747 0.694747 0.186157 -0.694748 0.694745 0.50859 -0.694749 0.508587 0.554004 -0.527871 0.643764 0.585059 -0.706111 0.39889 0.694752 -0.69474 0.186159 0.849549 -0.408778 0.333418 0.704875 -0.704871 0.0794224 0.704875 -0.704871 -0.0794222 0.795852 -0.566696 -0.213248 0.186157 -0.694747 -0.694747 0.186157 -0.694748 -0.694746 0.465273 -0.700864 -0.540657 0.569934 -0.591907 -0.569931 0.585059 -0.706111 -0.39889 0.66192 -0.703119 -0.25978 0.186156 -0.694749 0.694745 0.186156 -0.69475 0.694743 0.508587 -0.694751 0.508587 0.554 -0.527881 0.643759 0.585053 -0.706117 0.398888 0.694746 -0.694748 0.186153 0.849549 -0.408778 0.333418 0.704875 -0.704871 0.0794224 0.704875 -0.704871 -0.0794219 0.79585 -0.566701 -0.213243 0.186157 -0.694749 -0.694744 0.186156 -0.69475 -0.694744 0.465272 -0.700866 -0.540656 0.569929 -0.591914 -0.569929 0.585053 -0.706117 -0.398888 0.661913 -0.703126 -0.259778 0.186156 -0.694745 0.694749 0.186156 -0.694749 0.694745 0.508589 -0.694748 0.508589 0.554 -0.527883 0.643757 0.585053 -0.70612 0.398883 0.694744 -0.69475 0.186156 0.849547 -0.408779 0.333422 0.704871 -0.704875 0.0794219 0.704871 -0.704875 -0.0794219 0.795847 -0.566703 -0.213247 0.186159 -0.694744 -0.694748 0.186156 -0.694749 -0.694745 0.465274 -0.700863 -0.540658 0.569931 -0.59191 -0.569931 0.585055 -0.706115 -0.398889 0.661914 -0.703125 -0.25978 0.159332 -0.698071 0.698076 0.159331 -0.698067 0.69808 0.330524 -0.706854 0.625389 0.472941 -0.651627 0.593051 0.465277 -0.700861 0.540658 0.585056 -0.706115 0.398887 0.707218 -0.619555 0.340578 0.661913 -0.703126 0.25978 0.716026 -0.698074 0 0.87851 -0.467356 0.0989846 0.704873 -0.704874 -0.0794193 0.645116 -0.698075 -0.310672 0.770327 -0.56142 -0.302332 0.585061 -0.706115 -0.39888 0.446435 -0.698073 -0.559813 0.159334 -0.698071 -0.698075 0.159331 -0.698076 -0.698071 0.330521 -0.706862 -0.625382 0.502598 -0.637418 -0.584032 0.159331 0.698074 0.698074 0.159331 0.698073 0.698074 0.446437 0.698071 0.559813 0.446432 0.698076 0.559811 0.645115 0.698077 0.310669 0.645115 0.698077 0.310669 0.716023 0.698076 0 0.716023 0.698076 0 0.645116 0.698076 -0.31067 0.645115 0.698077 -0.310669 0.446433 0.698076 -0.55981 0.446434 0.698073 -0.559813 0.159331 0.698075 -0.698072 0.159331 0.698074 -0.698074 0.222521 0 0.974928 0.258819 0.00161878 0.965924 0.62349 -0.0013524 0.78183 0.652287 0 0.757972 0.826237 0 0.563323 0.900968 -0.002167 0.433881 0.930876 0 0.365336 0.993712 0 0.111967 0.999997 -0.00243897 0 0.993712 0 -0.111967 0.930876 0 -0.365336 0.900968 -0.002167 -0.433881 0.826237 0 -0.563323 0.623489 0 -0.781832 0.652287 -0.00161877 -0.757971 0.222522 0.00188275 -0.974926 0.25882 0 -0.965926 0.159329 0.698076 0.698072 0.159331 0.698073 0.698074 0.446435 0.698075 0.55981 0.446431 0.698079 0.559808 0.645113 0.698079 0.310669 0.645115 0.698077 0.310669 0.716023 0.698076 0 0.716023 0.698076 0 0.645117 0.698075 -0.310671 0.645115 0.698077 -0.310669 0.446433 0.698076 -0.55981 0.446433 0.698079 -0.559807 0.159331 0.698077 -0.69807 0.159331 0.698076 -0.698072 0.222519 0 0.974928 0.258819 0.00161885 0.965924 0.623491 -0.00135235 0.78183 0.652287 0 0.757972 0.826235 0 0.563326 0.900967 -0.00216702 0.433881 0.930876 0 0.365336 0.993712 0 0.111967 0.999997 -0.00243897 0 0.993712 0 -0.111967 0.930876 0 -0.365336 0.900967 -0.00216702 -0.433881 0.826235 0 -0.563326 0.623489 0 -0.781832 0.652287 -0.00161877 -0.757971 0.222522 0.00188275 -0.974926 0.25882 0 -0.965926 0.159332 0.698071 0.698076 0.159329 0.698076 0.698072 0.446434 0.698076 0.559809 0.446434 0.698076 0.559809 0.645114 0.698077 0.310671 0.645115 0.698077 0.310671 0.716023 0.698076 0 0.716023 0.698076 0 0.645115 0.698077 -0.310671 0.645114 0.698077 -0.310671 0.446433 0.698076 -0.559811 0.446433 0.698076 -0.55981 0.159333 0.698076 -0.69807 0.159332 0.698071 -0.698076 0.222522 0 0.974928 0.258819 0.00161871 0.965925 0.62349 -0.00135246 0.78183 0.65229 0 0.75797 0.826238 0 0.563321 0.900967 -0.00216694 0.433883 0.930874 0 0.36534 0.993712 0 0.111967 0.999997 -0.00243897 0 0.993712 0 -0.111967 0.930875 0 -0.365338 0.900967 -0.002167 -0.433883 0.826235 0 -0.563326 0.623489 0 -0.781832 0.652286 -0.00161877 -0.757971 0.222524 0.00188273 -0.974925 0.258822 0 -0.965925 0.186156 0.694745 0.694749 0.186159 0.69474 0.694753 0.508594 0.694741 0.508593 0.508593 0.694743 0.508593 0.694748 0.694745 0.186157 0.694744 0.694749 0.186157 0.694745 0.694749 -0.186156 0.694746 0.694748 -0.186157 0.508588 0.694749 -0.508587 0.508589 0.694748 -0.508589 0.186158 0.694749 -0.694744 0.186158 0.694744 -0.694749 0.222519 0 0.974928 0.258816 -0.00161873 0.965925 0.467265 0 0.884117 0.65229 0 0.75797 0.707105 -0.00270288 0.707103 0.826237 0 0.563322 0.930875 0 0.365338 0.965921 -0.00324652 0.258817 0.993712 0 0.111965 0.993712 0 -0.111963 0.965921 -0.00324659 -0.258817 0.930873 0 -0.365342 0.826244 0 -0.563313 0.707105 -0.00270308 -0.707104 0.652285 0 -0.757974 0.467265 0 -0.884117 0.258822 -0.00161869 -0.965924 0.222525 0 -0.974927 0.186157 0.694747 0.694747 0.186156 0.694747 0.694746 0.508588 0.694748 0.50859 0.50859 0.694747 0.508589 0.694747 0.694747 0.186155 0.694744 0.694749 0.186159 0.694744 0.69475 -0.186154 0.694746 0.694747 -0.186159 0.508589 0.694746 -0.508591 0.50859 0.694748 -0.508588 0.186157 0.694747 -0.694746 0.186156 0.694747 -0.694747 0.25882 0 0.965926 0.25882 0 0.965926 0.707105 0 0.707108 0.707105 0 0.707108 0.965926 0 0.258817 0.965926 0 0.258817 0.965927 0 -0.258816 0.965927 0 -0.258816 0.707105 0 -0.707108 0.707105 0 -0.707108 0.25882 0 -0.965926 0.25882 0 -0.965926 0.186157 -0.694746 -0.694747 0.186156 -0.694747 -0.694746 0.508588 -0.694748 -0.50859 0.508591 -0.694746 -0.508589 0.694748 -0.694746 -0.186155 0.694744 -0.694749 -0.186158 0.694745 -0.694749 0.186155 0.694746 -0.694747 0.186159 0.508589 -0.694746 0.508591 0.50859 -0.694747 0.508589 0.186157 -0.694747 0.694746 0.186156 -0.694746 0.694747 0.159334 0.698072 0.698074 0.159331 0.698074 0.698073 0.446433 0.698074 0.559813 0.446434 0.698073 0.559813 0.645119 0.698073 0.31067 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698075 -0.31067 0.645117 0.698073 -0.310673 0.446436 0.698073 -0.559811 0.446436 0.698073 -0.559811 0.159329 0.698074 -0.698074 0.159329 0.698073 -0.698075 0.222525 0 0.974927 0.258822 0.00192594 0.965923 0.623486 -0.00160914 0.781833 0.652285 0 0.757974 0.826244 0 0.563312 0.900967 -0.00257807 0.43388 0.930873 0 0.365343 0.993712 0 0.111967 0.999996 -0.00290192 0 0.993712 0 -0.111968 0.930873 0 -0.365343 0.900967 -0.00257807 -0.43388 0.826244 0 -0.563312 0.623491 0 -0.78183 0.652284 -0.00192575 -0.757972 0.222519 0.00224049 -0.974926 0.258822 0 -0.965925 0.186157 -0.694745 0.694748 0.186159 -0.694747 0.694746 0.50859 -0.694746 0.50859 0.489823 -0.660377 0.569188 0.58506 -0.706116 0.398879 0.694747 -0.694746 0.186156 0.714786 -0.640611 0.280534 0.704874 -0.704872 0.0794218 0.704874 -0.704872 -0.0794229 0.714297 -0.673162 -0.191396 0.18616 -0.694745 -0.694747 0.186157 -0.694746 -0.694747 0.465273 -0.700862 -0.540661 0.520482 -0.676902 -0.520482 0.58506 -0.706116 -0.398879 0.661913 -0.703125 -0.259783 0.159334 0.698072 0.698074 0.159328 0.698075 0.698073 0.446432 0.698076 0.559812 0.446438 0.698073 0.55981 0.645117 0.698073 0.310674 0.645117 0.698073 0.310673 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698075 -0.31067 0.645117 0.698073 -0.310673 0.446434 0.698072 -0.559814 0.446435 0.698073 -0.559813 0.159325 0.698071 -0.698077 0.159333 0.698076 -0.698071 0.222525 0 0.974927 0.258817 0.00192565 0.965925 0.623486 -0.00160941 0.781833 0.65229 0 0.75797 0.826235 0 0.563326 0.900965 -0.00257828 0.433885 0.930873 0 0.365342 0.993713 0 0.11196 0.999996 -0.00290175 0 0.993713 0 -0.11196 0.930873 0 -0.365342 0.900967 -0.00257808 -0.43388 0.826248 0 -0.563307 0.623487 0 -0.781833 0.652279 -0.0019257 -0.757976 0.222512 0.00224054 -0.974927 0.258817 0 -0.965926 0.186154 -0.694746 0.694748 0.186155 -0.694747 0.694747 0.508593 -0.694746 0.508587 0.489826 -0.660378 0.569185 0.585056 -0.706114 0.39889 0.694747 -0.694745 0.186159 0.714785 -0.640612 0.280533 0.704873 -0.704874 0.0794169 0.704873 -0.704874 -0.079417 0.714297 -0.673162 -0.191396 0.186155 -0.694749 -0.694745 0.186159 -0.694747 -0.694746 0.465269 -0.700863 -0.540663 0.520483 -0.676901 -0.520483 0.585062 -0.706117 -0.398875 0.661913 -0.703124 -0.259782 0.159332 -0.698074 -0.698074 0.159329 -0.698077 -0.698071 0.446431 -0.698079 -0.559808 0.446434 -0.698076 -0.559809 0.645113 -0.698077 -0.310673 0.645115 -0.698075 -0.310673 0.716023 -0.698076 0 0.716023 -0.698076 0 0.645114 -0.698076 0.310673 0.645113 -0.698077 0.310673 0.446434 -0.698076 0.55981 0.446434 -0.698077 0.559809 0.15933 -0.698075 0.698073 0.15933 -0.698074 0.698074 0.222522 0 -0.974928 0.222522 0 -0.974928 0.623489 0 -0.781832 0.623489 0 -0.781832 0.900967 0 -0.433887 0.900967 0 -0.433887 1 0 0 1 0 0 0.900967 0 0.433887 0.900967 0 0.433887 0.62349 0 0.781831 0.62349 0 0.781831 0.222521 0 0.974928 0.222521 0 0.974928 0.186157 -0.694749 -0.694744 0.186157 -0.694749 -0.694744 0.508589 -0.694748 -0.508589 0.508589 -0.694748 -0.508589 0.694744 -0.694749 -0.186157 0.694744 -0.694749 -0.186157 0.694745 -0.694749 0.186156 0.694745 -0.694749 0.186156 0.508589 -0.694748 0.508589 0.508589 -0.694748 0.508589 0.186157 -0.694749 0.694744 0.186157 -0.694749 0.694744 0.25882 0 -0.965926 0.25882 0 -0.965926 0.707107 0 -0.707107 0.707107 0 -0.707107 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.258819 0.965926 0 0.258819 0.707107 0 0.707107 0.707107 0 0.707107 0.25882 0 0.965926 0.25882 0 0.965926 0.18616 -0.694744 -0.694748 0.186156 -0.694749 -0.694744 0.508589 -0.694749 -0.508588 0.508587 -0.694751 -0.508587 0.694743 -0.69475 -0.186156 0.694747 -0.694747 -0.186156 0.694747 -0.694747 0.186157 0.694744 -0.69475 0.186155 0.508587 -0.694751 0.508586 0.50859 -0.694743 0.508594 0.186157 -0.69474 0.694753 0.186158 -0.694744 0.694749 0.258822 0 -0.965925 0.258822 0 -0.965925 0.707107 0 -0.707106 0.707107 0 -0.707106 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.707107 0 0.707106 0.707107 0 0.707106 0.258817 0 0.965926 0.258817 0 0.965926 0.258818 0 -0.965926 0.258818 0 -0.965926 0.70711 0 -0.707104 0.70711 0 -0.707104 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.70711 0 0.707104 0.70711 0 0.707104 0.258818 0 0.965926 0.258818 0 0.965926 0.258821 0 -0.965925 0.258821 0 -0.965925 0.707107 0 -0.707107 0.707107 0 -0.707107 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.707105 0 0.707109 0.707105 0 0.707109 0.258821 0 0.965925 0.258821 0 0.965925 0.222518 0 -0.974929 0.222518 0 -0.974929 0.623493 0 -0.781829 0.623493 0 -0.781829 0.90097 0 -0.433881 0.90097 0 -0.433881 1 0 0 1 0 0 0.90097 0 0.433881 0.90097 0 0.433881 0.623487 0 0.781834 0.623487 0 0.781834 0.222527 0 0.974926 0.222527 0 0.974926 0.25882 0 -0.965926 0.25882 0 -0.965926 0.707107 0 -0.707107 0.707107 0 -0.707107 0.965927 0 -0.258815 0.965927 0 -0.258815 0.965926 0 0.258817 0.965926 0 0.258817 0.707107 0 0.707107 0.707107 0 0.707107 0.25882 0 0.965926 0.25882 0 0.965926 0.258821 0 -0.965925 0.258821 0 -0.965925 0.707107 0 -0.707107 0.707107 0 -0.707107 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.707107 0 0.707107 0.707107 0 0.707107 0.258817 0 0.965926 0.258817 0 0.965926 0.222527 0 -0.974926 0.222527 0 -0.974926 0.623487 0 -0.781834 0.623487 0 -0.781834 0.900968 0 -0.433885 0.900968 0 -0.433885 1 0 0 1 0 0 0.900968 0 0.433885 0.900968 0 0.433885 0.623487 0 0.781834 0.623487 0 0.781834 0.222527 0 0.974926 0.222527 0 0.974926 0.258819 0 -0.965926 0.258819 0 -0.965926 0.707111 0 -0.707102 0.707111 0 -0.707102 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.707111 0 0.707102 0.707111 0 0.707102 0.258815 0 0.965927 0.258815 0 0.965927 0.258818 0 -0.965926 0.258818 0 -0.965926 0.70711 0 -0.707104 0.70711 0 -0.707104 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.70711 0 0.707104 0.70711 0 0.707104 0.258818 0 0.965926 0.258818 0 0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 0.707111 0 -0.707102 0.707111 0 -0.707102 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.707109 0 0.707105 0.707109 0 0.707105 0.258819 0 0.965926 0.258819 0 0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 0.707107 0 -0.707107 0.707107 0 -0.707107 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965926 0 0.258819 0.965926 0 0.258819 0.707107 0 0.707107 0.707107 0 0.707107 0.25882 0 0.965926 0.25882 0 0.965926 0.15933 -0.698074 0.698074 0.15933 -0.698075 0.698072 0.330526 -0.706862 0.625379 0.472936 -0.651638 0.593042 0.465273 -0.700864 0.540657 0.585052 -0.706119 0.398885 0.707213 -0.619562 0.340578 0.66191 -0.703127 0.259783 0.70487 -0.704876 0.0794219 0.793864 -0.608096 0 0.704871 -0.704876 -0.0794217 0.645115 -0.698075 -0.310673 0.770325 -0.561422 -0.302333 0.585052 -0.706119 -0.398885 0.446434 -0.698076 -0.559809 0.159332 -0.698074 -0.698074 0.159329 -0.698077 -0.698071 0.33052 -0.706864 -0.62538 0.502598 -0.637421 -0.584029 0.186156 -0.694749 0.694745 0.186156 -0.694749 0.694745 0.508589 -0.694748 0.508589 0.554 -0.527883 0.643757 0.585053 -0.706117 0.398888 0.694744 -0.694749 0.186157 0.849547 -0.408779 0.333422 0.704871 -0.704875 0.0794219 0.704871 -0.704875 -0.0794214 0.795848 -0.566702 -0.213247 0.186156 -0.694749 -0.694745 0.186156 -0.694749 -0.694745 0.465276 -0.700863 -0.540657 0.569929 -0.591914 -0.569929 0.585053 -0.706117 -0.398888 0.661912 -0.703126 -0.25978 0.15933 -0.698072 0.698076 0.159331 -0.698076 0.698071 0.330521 -0.706862 0.625382 0.472938 -0.651635 0.593044 0.465275 -0.700861 0.540659 0.58506 -0.706115 0.398881 0.707214 -0.619561 0.340576 0.661914 -0.703123 0.259785 0.716028 -0.698072 0 0.878507 -0.467363 0.0989807 0.704875 -0.704871 -0.0794178 0.645118 -0.698072 -0.310672 0.770327 -0.561419 -0.302333 0.585058 -0.706115 -0.398884 0.446435 -0.698073 -0.559813 0.159335 -0.698071 -0.698075 0.159331 -0.698076 -0.698071 0.330521 -0.706862 -0.625382 0.502598 -0.637418 -0.584032 0.159332 -0.698071 0.698076 0.159331 -0.698067 0.69808 0.330527 -0.706854 0.625387 0.47294 -0.651629 0.593049 0.465276 -0.700863 0.540657 0.585055 -0.706117 0.398886 0.707216 -0.619558 0.340577 0.661913 -0.703125 0.259781 0.704873 -0.704874 0.0794203 0.793864 -0.608096 0 0.704873 -0.704874 -0.0794193 0.645116 -0.698075 -0.310672 0.770323 -0.561425 -0.302332 0.585059 -0.706117 -0.398879 0.446434 -0.698074 -0.559812 0.159334 -0.698071 -0.698075 0.159331 -0.698076 -0.698071 0.330524 -0.706862 -0.62538 0.502596 -0.63742 -0.584031 0.186157 0.694747 0.694747 0.186157 0.694748 0.694746 0.508587 0.694749 0.508588 0.508588 0.694749 0.508589 0.694743 0.69475 0.186158 0.694749 0.694744 0.186158 0.694748 0.694744 -0.18616 0.694744 0.694749 -0.186156 0.508588 0.694749 -0.508589 0.508588 0.694749 -0.508588 0.186157 0.694748 -0.694745 0.186157 0.694747 -0.694747 0.222521 0 0.974928 0.258819 -0.00161878 0.965924 0.467273 0 0.884113 0.652287 0 0.757972 0.707103 -0.00270291 0.707105 0.826237 0 0.563323 0.930872 0 0.365344 0.96592 -0.00324657 0.258821 0.993712 0 0.111967 0.993712 0 -0.111967 0.96592 -0.00324659 -0.258821 0.930872 0 -0.365344 0.826237 0 -0.563323 0.707103 -0.00270291 -0.707105 0.652287 0 -0.757972 0.467265 0 -0.884117 0.258819 -0.00161871 -0.965924 0.222522 0 -0.974928 0.159328 0.698076 0.698072 0.159332 0.698072 0.698075 0.446438 0.698072 0.559811 0.446431 0.698079 0.559808 0.645112 0.698079 0.310671 0.645115 0.698077 0.310671 0.716023 0.698076 0 0.716023 0.698076 0 0.645116 0.698074 -0.310673 0.645114 0.698077 -0.310671 0.446434 0.698076 -0.559809 0.446434 0.698076 -0.559809 0.159331 0.698076 -0.698071 0.159331 0.698076 -0.698072 0.222518 0 0.974928 0.258819 0.00161885 0.965925 0.623492 -0.00135237 0.781828 0.65229 0 0.75797 0.826235 0 0.563326 0.900966 -0.00216698 0.433884 0.930874 0 0.36534 0.993712 0 0.111967 0.999997 -0.00243897 0 0.993712 0 -0.111967 0.930874 0 -0.36534 0.900966 -0.00216698 -0.433884 0.826235 0 -0.563326 0.623491 0 -0.781831 0.652289 -0.00161879 -0.757969 0.222521 0.00188276 -0.974926 0.258819 0 -0.965926 0.186158 0.694744 0.694749 0.186155 0.694749 0.694745 0.50859 0.694747 0.508588 0.508587 0.694751 0.508587 0.694743 0.69475 0.186156 0.694745 0.694749 0.186156 0.694745 0.694749 -0.186156 0.694746 0.694748 -0.186157 0.508591 0.694744 -0.508593 0.508589 0.694748 -0.508589 0.186159 0.694749 -0.694744 0.186158 0.694744 -0.694749 0.222522 0 0.974928 0.258819 -0.00161871 0.965924 0.467265 0 0.884117 0.652287 0 0.757972 0.707106 -0.00270302 0.707103 0.826243 0 0.563314 0.930872 0 0.365344 0.965921 -0.00324665 0.258818 0.993713 0 0.111961 0.993713 0 -0.111961 0.965921 -0.00324664 -0.258818 0.930873 0 -0.365343 0.82624 0 -0.563319 0.707103 -0.00270297 -0.707106 0.652285 0 -0.757974 0.467265 0 -0.884117 0.258822 -0.00161869 -0.965924 0.222526 0 -0.974927 0.186156 0.694745 0.694749 0.186159 0.69474 0.694752 0.508593 0.694743 0.508592 0.508591 0.694744 0.508591 0.694746 0.694748 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186157 0.694744 0.69475 -0.186155 0.508587 0.694751 -0.508586 0.508588 0.694749 -0.508588 0.186158 0.69475 -0.694743 0.186158 0.694744 -0.694749 0.222519 0 0.974928 0.258817 -0.00161874 0.965925 0.467269 0 0.884115 0.65229 0 0.75797 0.707105 -0.00270288 0.707103 0.826237 0 0.563322 0.930874 0 0.365341 0.965921 -0.00324655 0.258818 0.993712 0 0.111965 0.993712 0 -0.111963 0.965921 -0.00324662 -0.258818 0.930873 0 -0.365344 0.826244 0 -0.563313 0.707105 -0.00270308 -0.707104 0.652285 0 -0.757974 0.467269 0 -0.884115 0.258822 -0.0016187 -0.965924 0.222525 0 -0.974927 -0.0909337 0 0.995857 -0.0909337 0 0.995857 -0.269794 0 0.962918 -0.269794 0 0.962918 -0.43973 0 0.89813 -0.43973 0 0.89813 -0.595121 0 0.803636 -0.595121 0 0.803636 -0.730829 0 0.68256 -0.730829 0 0.68256 -0.842364 0 0.538909 -0.842364 0 0.538909 -0.926037 0 0.377433 -0.926037 0 0.377433 0.082579 0 -0.996585 0.082579 0 -0.996585 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401695 0 -0.915773 0.401695 0 -0.915773 0.546948 0 -0.837167 0.546948 0 -0.837167 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475948 0.879474 0 -0.475948 0.945817 0 -0.324699 0.945817 0 -0.324699 0.986361 0 -0.164595 0.986361 0 -0.164595 1 0 0 1 0 0 0.986361 0 0.164595 0.986361 0 0.164595 0.945817 0 0.324699 0.945817 0 0.324699 0.879474 0 0.475948 0.879474 0 0.475948 0.789141 0 0.614213 0.789141 0 0.614213 0.677282 0 0.735724 0.677282 0 0.735724 0.546948 0 0.837167 0.546948 0 0.837167 0.401695 0 0.915773 0.401695 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825795 0 0.996585 0.0825795 0 0.996585 0.082579 0 -0.996585 0.082579 0 -0.996585 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401695 0 -0.915773 0.401695 0 -0.915773 0.546948 0 -0.837167 0.546948 0 -0.837167 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475948 0.879474 0 -0.475948 0.945817 0 -0.324699 0.945817 0 -0.324699 0.986361 0 -0.164595 0.986361 0 -0.164595 1 0 0 1 0 0 0.986361 0 0.164595 0.986361 0 0.164595 0.945817 0 0.324699 0.945817 0 0.324699 0.879474 0 0.475948 0.879474 0 0.475948 0.789141 0 0.614213 0.789141 0 0.614213 0.677282 0 0.735724 0.677282 0 0.735724 0.546948 0 0.837167 0.546948 0 0.837167 0.401695 0 0.915773 0.401695 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825795 0 0.996584 0.0825795 0 0.996584 0.082579 0 -0.996585 0.082579 0 -0.996585 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401695 0 -0.915773 0.401695 0 -0.915773 0.546948 0 -0.837167 0.546948 0 -0.837167 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475948 0.879474 0 -0.475948 0.945817 0 -0.324699 0.945817 0 -0.324699 0.986361 0 -0.164595 0.986361 0 -0.164595 1 0 0 1 0 0 0.986361 0 0.164595 0.986361 0 0.164595 0.945817 0 0.324699 0.945817 0 0.324699 0.879474 0 0.475948 0.879474 0 0.475948 0.789141 0 0.614213 0.789141 0 0.614213 0.677282 0 0.735724 0.677282 0 0.735724 0.546948 0 0.837167 0.546948 0 0.837167 0.401695 0 0.915773 0.401695 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825795 0 0.996584 0.0825795 0 0.996584 0.082579 0 -0.996585 0.082579 0 -0.996585 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401695 0 -0.915773 0.401695 0 -0.915773 0.546948 0 -0.837167 0.546948 0 -0.837167 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475948 0.879474 0 -0.475948 0.945817 0 -0.324699 0.945817 0 -0.324699 0.986361 0 -0.164595 0.986361 0 -0.164595 1 0 0 1 0 0 0.986361 0 0.164595 0.986361 0 0.164595 0.945817 0 0.324699 0.945817 0 0.324699 0.879474 0 0.475948 0.879474 0 0.475948 0.789141 0 0.614213 0.789141 0 0.614213 0.677282 0 0.735724 0.677282 0 0.735724 0.546948 0 0.837167 0.546948 0 0.837167 0.401695 0 0.915773 0.401695 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825795 0 0.996584 0.0825795 0 0.996584 0.082579 0 -0.996585 0.082579 0 -0.996585 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401695 0 -0.915773 0.401695 0 -0.915773 0.546948 0 -0.837167 0.546948 0 -0.837167 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475948 0.879474 0 -0.475948 0.945817 0 -0.324699 0.945817 0 -0.324699 0.986361 0 -0.164595 0.986361 0 -0.164595 1 0 0 1 0 0 0.986361 0 0.164595 0.986361 0 0.164595 0.945817 0 0.324699 0.945817 0 0.324699 0.879474 0 0.475948 0.879474 0 0.475948 0.789141 0 0.614213 0.789141 0 0.614213 0.677282 0 0.735724 0.677282 0 0.735724 0.546948 0 0.837167 0.546948 0 0.837167 0.401695 0 0.915773 0.401695 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825795 0 0.996584 0.0825795 0 0.996584 0.082579 0 -0.996585 0.082579 0 -0.996585 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837167 0.546948 0 -0.837167 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475948 0.879474 0 -0.475948 0.945817 0 -0.324699 0.945817 0 -0.324699 0.986361 0 -0.164595 0.986361 0 -0.164595 1 0 0 1 0 0 0.986361 0 0.164595 0.986361 0 0.164595 0.945817 0 0.324699 0.945817 0 0.324699 0.879474 0 0.475948 0.879474 0 0.475948 0.789141 0 0.614213 0.789141 0 0.614213 0.677282 0 0.735724 0.677282 0 0.735724 0.546948 0 0.837167 0.546948 0 0.837167 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825795 0 0.996584 0.0825795 0 0.996584 0.082579 0 -0.996585 0.082579 0 -0.996585 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401695 0 -0.915773 0.401695 0 -0.915773 0.546948 0 -0.837167 0.546948 0 -0.837167 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475948 0.879474 0 -0.475948 0.945817 0 -0.324699 0.945817 0 -0.324699 0.986361 0 -0.164595 0.986361 0 -0.164595 1 0 0 1 0 0 0.986361 0 0.164595 0.986361 0 0.164595 0.945817 0 0.324699 0.945817 0 0.324699 0.879474 0 0.475948 0.879474 0 0.475948 0.789141 0 0.614213 0.789141 0 0.614213 0.677282 0 0.735724 0.677282 0 0.735724 0.546948 0 0.837167 0.546948 0 0.837167 0.401695 0 0.915773 0.401695 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825795 0 0.996584 0.0825795 0 0.996584 0.082579 0 -0.996585 0.082579 0 -0.996585 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401695 0 -0.915773 0.401695 0 -0.915773 0.546948 0 -0.837167 0.546948 0 -0.837167 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475948 0.879474 0 -0.475948 0.945817 0 -0.324699 0.945817 0 -0.324699 0.986361 0 -0.164595 0.986361 0 -0.164595 1 0 0 1 0 0 0.986361 0 0.164595 0.986361 0 0.164595 0.945817 0 0.324699 0.945817 0 0.324699 0.879474 0 0.475948 0.879474 0 0.475948 0.789141 0 0.614213 0.789141 0 0.614213 0.677282 0 0.735724 0.677282 0 0.735724 0.546948 0 0.837167 0.546948 0 0.837167 0.401695 0 0.915773 0.401695 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825795 0 0.996584 0.0825795 0 0.996584 0.082579 0 -0.996585 0.082579 0 -0.996585 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837167 0.546948 0 -0.837167 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475948 0.879474 0 -0.475948 0.945817 0 -0.324699 0.945817 0 -0.324699 0.986361 0 -0.164595 0.986361 0 -0.164595 1 0 0 1 0 0 0.986361 0 0.164595 0.986361 0 0.164595 0.945817 0 0.324699 0.945817 0 0.324699 0.879474 0 0.475948 0.879474 0 0.475948 0.789141 0 0.614213 0.789141 0 0.614213 0.677282 0 0.735724 0.677282 0 0.735724 0.546948 0 0.837167 0.546948 0 0.837167 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825795 0 0.996584 0.0825795 0 0.996584 0.082579 0 -0.996585 0.082579 0 -0.996585 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401695 0 -0.915773 0.401695 0 -0.915773 0.546948 0 -0.837167 0.546948 0 -0.837167 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475948 0.879474 0 -0.475948 0.945817 0 -0.324699 0.945817 0 -0.324699 0.986361 0 -0.164595 0.986361 0 -0.164595 1 0 0 1 0 0 0.986361 0 0.164595 0.986361 0 0.164595 0.945817 0 0.324699 0.945817 0 0.324699 0.879474 0 0.475948 0.879474 0 0.475948 0.789141 0 0.614213 0.789141 0 0.614213 0.677282 0 0.735724 0.677282 0 0.735724 0.546948 0 0.837167 0.546948 0 0.837167 0.401695 0 0.915773 0.401695 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825795 0 0.996584 0.0825795 0 0.996584 0.0584925 -0.70589 -0.705903 0.0584917 -0.705904 -0.705888 0.173879 -0.705904 -0.686633 0.173881 -0.705896 -0.686641 0.284527 -0.705896 -0.648656 0.284528 -0.705894 -0.648658 0.387413 -0.705894 -0.59298 0.387408 -0.705903 -0.592972 0.479725 -0.705902 -0.52112 0.479729 -0.705896 -0.521125 0.55896 -0.705896 -0.435056 0.558964 -0.705891 -0.435059 0.62295 -0.705891 -0.337124 0.622943 -0.705899 -0.33712 0.669933 -0.7059 -0.229988 0.669939 -0.705894 -0.22999 0.698656 -0.705894 -0.116585 0.698653 -0.705899 -0.116584 0.708313 -0.705899 0 0.708313 -0.705899 0 0.698652 -0.705899 0.116584 0.698656 -0.705895 0.116585 0.669938 -0.705895 0.22999 0.669932 -0.705902 0.229988 0.62294 -0.705902 0.337118 0.62295 -0.70589 0.337124 0.558964 -0.705891 0.435059 0.558957 -0.705901 0.435054 0.479726 -0.705901 0.521121 0.479725 -0.705902 0.52112 0.387408 -0.705903 0.592972 0.387413 -0.705894 0.59298 0.284528 -0.705894 0.648659 0.284527 -0.705897 0.648656 0.173881 -0.705896 0.686641 0.173879 -0.705904 0.686633 0.0584917 -0.705904 0.705888 0.0584919 -0.705903 0.70589 0.222522 0 0.974928 0.258814 -0.00571976 0.96591 0.467245 0 0.884128 0.652289 0 0.757971 0.707078 -0.00955149 0.707071 0.826246 0 0.563309 0.930871 0 0.365348 0.965862 -0.0114726 0.258803 0.993713 0 0.111956 0.993713 0 -0.111956 0.965862 -0.0114726 -0.258803 0.930871 0 -0.365348 0.826246 0 -0.563309 0.707078 -0.00955148 -0.707071 0.652289 0 -0.757971 0.467246 0 -0.884128 0.258814 -0.00571978 -0.96591 0.222522 0 -0.974928 0.258821 0 0.965925 0.258821 0 0.965925 0.707105 0 0.707109 0.707105 0 0.707109 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258821 0 -0.965925 0.258821 0 -0.965925 0.25882 0 0.965926 0.25882 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965927 0 0.258815 0.965927 0 0.258815 0.965926 0 -0.258817 0.965926 0 -0.258817 0.707107 0 -0.707107 0.707107 0 -0.707107 0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.258817 0.965926 0 0.258817 0.965927 0 -0.258815 0.965927 0 -0.258815 0.707107 0 -0.707107 0.707107 0 -0.707107 0.25882 0 -0.965926 0.25882 0 -0.965926 0.258817 0 0.965926 0.258817 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258821 0 -0.965925 0.258821 0 -0.965925 0.258818 0 0.965926 0.258818 0 0.965926 0.70711 0 0.707104 0.70711 0 0.707104 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.70711 0 -0.707104 0.70711 0 -0.707104 0.258818 0 -0.965926 0.258818 0 -0.965926 0.258815 0 0.965927 0.258815 0 0.965927 0.707111 0 0.707102 0.707111 0 0.707102 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707111 0 -0.707102 0.707111 0 -0.707102 0.258819 0 -0.965926 0.258819 0 -0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965925 0 0.258821 0.965925 0 0.258821 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707107 0 -0.707107 0.707107 0 -0.707107 0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.258819 0.965926 0 0.258819 0.965925 0 -0.258821 0.965925 0 -0.258821 0.707107 0 -0.707107 0.707107 0 -0.707107 0.25882 0 -0.965926 0.25882 0 -0.965926 0.258819 0 0.965926 0.258819 0 0.965926 0.707109 0 0.707105 0.707109 0 0.707105 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707111 0 -0.707102 0.707111 0 -0.707102 0.258819 0 -0.965926 0.258819 0 -0.965926 0.0694756 0.705398 0.705398 0.0694754 0.705402 0.705394 0.205756 0.705402 0.678287 0.205758 0.705396 0.678292 0.334132 0.705396 0.625118 0.334132 0.705398 0.625116 0.449665 0.705398 0.547919 0.449664 0.705399 0.547918 0.547918 0.705398 0.449665 0.547919 0.705398 0.449665 0.625116 0.705398 0.334131 0.625118 0.705396 0.334132 0.678292 0.705396 0.205758 0.678292 0.705396 0.205757 0.705401 0.705396 0.0694761 0.705398 0.705398 0.0694758 0.705398 0.705398 -0.0694758 0.705401 0.705396 -0.069476 0.678292 0.705396 -0.205758 0.678291 0.705397 -0.205757 0.625116 0.705397 -0.334132 0.625116 0.705398 -0.334131 0.547919 0.705398 -0.449665 0.547921 0.705395 -0.449667 0.449668 0.705394 -0.547922 0.449665 0.705398 -0.547919 0.334131 0.705398 -0.625116 0.334132 0.705396 -0.625118 0.205758 0.705396 -0.678292 0.205758 0.705396 -0.678292 0.0694759 0.705395 -0.705401 0.0694755 0.705398 -0.705398 0.0584923 0.705897 0.705895 0.336843 0.707107 0.62172 0.284527 0.705897 0.648656 0.284528 0.705895 0.648657 0.217699 0.70705 0.672821 0.203692 0.558131 0.804363 0.161552 0.706359 0.689171 0.0584923 0.705894 0.705898 0.434012 0.707106 0.558242 0.410985 0.704457 0.578646 0.48576 0.459596 0.743511 0.41076 0.623994 0.664762 0.348445 0.706204 0.616329 0.453542 0.706894 0.542771 0.598713 0.467499 0.650375 0.569946 0.554118 0.606724 0.593096 0.707103 0.385023 0.558962 0.705894 0.435058 0.55896 0.705896 0.435056 0.512294 0.707059 0.487466 0.529643 0.662733 0.529399 0.652406 0.686583 0.32089 0.780811 0.460199 0.422554 0.713336 0.575518 0.399914 0.608108 0.699963 0.374508 0.681252 0.707005 0.189844 0.788007 0.557278 0.261699 0.834878 0.469928 0.286614 0.656967 0.706905 0.262067 0.646116 0.707103 0.287297 0.696215 0.706329 0.128 0.811781 0.568033 0.135462 0.703685 0.707056 0.0699998 0.708318 0.705893 0 0.708318 0.705893 0 0.703685 0.707056 -0.0699998 0.811781 0.568033 -0.135462 0.696215 0.706329 -0.128 0.676578 0.706682 -0.206986 0.834878 0.469927 -0.286614 0.656968 0.706905 -0.262068 0.608108 0.699963 -0.374509 0.713337 0.575516 -0.399915 0.780812 0.460197 -0.422554 0.652406 0.686582 -0.320891 0.646117 0.707102 -0.287298 0.592009 0.661217 -0.460779 0.561142 0.706044 -0.431998 0.593096 0.707103 -0.385023 0.581996 0.511452 -0.632216 0.529644 0.662731 -0.5294 0.512295 0.707057 -0.487467 0.522771 0.707101 -0.476151 0.48576 0.459596 -0.743511 0.410985 0.704457 -0.578646 0.434012 0.707106 -0.558242 0.466363 0.70651 -0.532306 0.223749 0.707096 -0.670784 0.284526 0.705899 -0.648654 0.284527 0.705897 -0.648656 0.347741 0.70705 -0.615757 0.41076 0.623994 -0.664762 0.216504 0.691038 -0.689632 0.203692 0.558131 -0.804363 0.161551 0.706364 -0.689167 0.0584918 0.705899 -0.705894 0.0584928 0.705893 -0.705899 0.186158 0.694744 0.694749 0.186156 0.694748 0.694746 0.508588 0.694749 0.508589 0.508596 0.694741 0.508592 0.694755 0.694738 0.186158 0.694751 0.694742 0.186158 0.694751 0.694742 -0.186156 0.694755 0.694738 -0.186159 0.508595 0.694739 -0.508596 0.508592 0.694747 -0.508588 0.186157 0.694745 -0.694748 0.186157 0.694747 -0.694747 0.25882 0 0.965926 0.25882 0 0.965926 0.707106 0 0.707108 0.707106 0 0.707108 0.965926 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.707106 0 -0.707108 0.707106 0 -0.707108 0.258818 0 -0.965926 0.258818 0 -0.965926 0.186155 -0.69475 -0.694744 0.186156 -0.694749 -0.694745 0.508587 -0.69475 -0.508588 0.508591 -0.694745 -0.50859 0.694749 -0.694744 -0.186156 0.69474 -0.694753 -0.186156 0.694741 -0.694753 0.186154 0.694747 -0.694746 0.186158 0.508589 -0.694747 0.50859 0.508588 -0.69475 0.508588 0.186157 -0.694749 0.694744 0.186157 -0.694747 0.694747 0.159333 0.698069 0.698078 0.159329 0.698075 0.698073 0.446433 0.698077 0.55981 0.446436 0.698074 0.559811 0.645118 0.698074 0.31067 0.645117 0.698075 0.31067 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698075 -0.31067 0.645117 0.698074 -0.31067 0.446435 0.698074 -0.559812 0.446435 0.698073 -0.559813 0.15933 0.69807 -0.698077 0.159331 0.698074 -0.698074 0.222522 0 0.974928 0.222522 0 0.974928 0.623489 0 0.781832 0.623489 0 0.781832 0.90097 0 0.433881 0.90097 0 0.433881 1 0 0 1 0 0 0.90097 0 -0.433881 0.90097 0 -0.433881 0.623489 0 -0.781832 0.623489 0 -0.781832 0.222519 0 -0.974928 0.222519 0 -0.974928 0.159328 -0.69808 -0.698067 0.159333 -0.698072 -0.698075 0.446435 -0.698072 -0.559813 0.446436 -0.698071 -0.559813 0.64512 -0.698071 -0.310671 0.64511 -0.698081 -0.31067 0.716019 -0.698081 0 0.716019 -0.698081 0 0.645111 -0.698082 0.310667 0.645118 -0.698072 0.310674 0.446436 -0.698071 0.559814 0.446434 -0.698077 0.559808 0.159331 -0.698079 0.698069 0.15933 -0.698074 0.698074 0.18616 0.694742 0.694751 0.186157 0.694746 0.694747 0.508592 0.694745 0.50859 0.508588 0.694749 0.508588 0.694745 0.694748 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186157 0.694747 0.694746 -0.186157 0.508591 0.694745 -0.508591 0.508591 0.694745 -0.508591 0.186157 0.694746 -0.694747 0.186157 0.694747 -0.694747 0.258822 0 0.965925 0.258822 0 0.965925 0.707108 0 0.707105 0.707108 0 0.707105 0.965925 0 0.25882 0.965925 0 0.25882 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.186157 -0.694747 -0.694747 0.186155 -0.69475 -0.694744 0.508589 -0.694748 -0.508589 0.508593 -0.694743 -0.508591 0.694749 -0.694744 -0.186158 0.694746 -0.694746 -0.186158 0.694746 -0.694746 0.186158 0.694747 -0.694746 0.186158 0.50859 -0.694748 0.508588 0.508593 -0.694743 0.508592 0.186159 -0.694744 0.694749 0.186159 -0.69474 0.694753 0.18616 0.694742 0.69475 0.186157 0.694747 0.694747 0.508591 0.694745 0.50859 0.50859 0.694747 0.50859 0.694748 0.694745 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186156 0.694748 0.694745 -0.186157 0.50859 0.694747 -0.508589 0.508591 0.694745 -0.508591 0.186155 0.694746 -0.694747 0.186155 0.694743 -0.694751 0.258822 0 0.965925 0.258822 0 0.965925 0.707108 0 0.707106 0.707108 0 0.707106 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258818 0.965926 0 -0.258818 0.707108 0 -0.707106 0.707108 0 -0.707106 0.258817 0 -0.965926 0.258817 0 -0.965926 0.186153 -0.694754 -0.694741 0.186158 -0.694745 -0.694748 0.508591 -0.694745 -0.50859 0.508589 -0.694748 -0.508589 0.694748 -0.694745 -0.186157 0.694743 -0.69475 -0.186157 0.694744 -0.69475 0.186155 0.694747 -0.694746 0.186158 0.50859 -0.694748 0.508589 0.508591 -0.694745 0.508591 0.186159 -0.694745 0.694748 0.186159 -0.69474 0.694753 0.186158 0.694746 0.694746 0.186157 0.694749 0.694744 0.508586 0.69475 0.508589 0.50859 0.694745 0.508591 0.694749 0.694744 0.186156 0.694753 0.69474 0.186157 0.694753 0.69474 -0.186157 0.694749 0.694744 -0.186155 0.50859 0.694745 -0.508592 0.508588 0.694748 -0.50859 0.186157 0.694745 -0.694748 0.186157 0.694747 -0.694747 0.159332 0.698074 0.698074 0.159329 0.698078 0.698069 0.446432 0.698078 0.559809 0.446437 0.698071 0.559812 0.645119 0.698072 0.310673 0.645118 0.698072 0.310673 0.716026 0.698074 0 0.716026 0.698074 0 0.645115 0.698076 -0.310671 0.645118 0.698072 -0.310674 0.446437 0.698071 -0.559813 0.446437 0.698072 -0.559812 0.15933 0.698072 -0.698076 0.15933 0.698074 -0.698074 0.159328 0.69808 0.698067 0.159331 0.69808 -0.698067 0.15933 0.698072 -0.698076 0.446435 0.698072 -0.559813 0.446433 0.698077 -0.559809 0.645117 0.698075 -0.310671 0.645118 0.698072 -0.310673 0.716026 0.698074 0 0.716026 0.698074 0 0.645118 0.698073 0.310672 0.645116 0.698075 0.310672 0.501572 0.704876 0.501574 0.366531 0.808956 0.459615 0.377389 0.704872 0.600611 0.159333 0.698072 0.698075 0.186159 0.694744 0.694749 0.186155 0.694748 0.694746 0.508586 0.694752 0.508586 0.508592 0.694747 0.508588 0.694746 0.694746 0.186158 0.694741 0.694751 0.18616 0.694741 0.694752 -0.186157 0.694745 0.694747 -0.186161 0.50859 0.694746 -0.50859 0.508588 0.694752 -0.508584 0.186158 0.694748 -0.694745 0.186157 0.694747 -0.694747 0.258821 0 0.965925 0.258821 0 0.965925 0.707107 0 0.707107 0.707107 0 0.707107 0.965925 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258821 0 -0.965925 0.258821 0 -0.965925 0.186158 -0.694746 -0.694746 0.186156 -0.69475 -0.694743 0.508584 -0.694755 -0.508584 0.508587 -0.694752 -0.508585 0.694738 -0.694756 -0.186156 0.694742 -0.694751 -0.186156 0.694742 -0.694751 0.186157 0.694738 -0.694755 0.186155 0.508586 -0.694752 0.508586 0.508586 -0.694752 0.508586 0.186158 -0.694746 0.694747 0.186158 -0.694742 0.694751 0.159329 0.698074 0.698074 0.15933 0.698072 0.698075 0.446437 0.698071 0.559813 0.446438 0.698071 0.559813 0.645119 0.698072 0.310671 0.645115 0.698076 0.310672 0.716023 0.698077 0 0.716023 0.698077 0 0.645116 0.698076 -0.310669 0.645117 0.698075 -0.310671 0.446435 0.698075 -0.55981 0.446435 0.698072 -0.559814 0.159333 0.698073 -0.698074 0.159333 0.698073 -0.698073 0.222518 0 0.974929 0.222518 0 0.974929 0.62349 0 0.781831 0.62349 0 0.781831 0.90097 0 0.433881 0.90097 0 0.433881 1 0 0 1 0 0 0.90097 0 -0.433881 0.90097 0 -0.433881 0.62349 0 -0.781831 0.62349 0 -0.781831 0.222523 0 -0.974927 0.222523 0 -0.974927 0.159333 -0.698069 -0.698078 0.159331 -0.698073 -0.698074 0.446437 -0.698071 -0.559813 0.446434 -0.698074 -0.559812 0.645117 -0.698074 -0.31067 0.645117 -0.698075 -0.31067 0.716026 -0.698074 0 0.716026 -0.698074 0 0.645117 -0.698075 0.31067 0.645117 -0.698074 0.31067 0.446435 -0.698074 0.559811 0.446436 -0.698071 0.559814 0.159329 -0.698073 0.698075 0.15933 -0.698078 0.698069 0.159338 0.698068 0.698078 0.159329 0.698078 0.698069 0.446432 0.698077 0.559809 0.446435 0.698075 0.55981 0.645115 0.698075 0.310673 0.645119 0.698071 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645119 0.698071 -0.310675 0.645117 0.698075 -0.310671 0.446434 0.698075 -0.559811 0.446433 0.698077 -0.559808 0.159329 0.698078 -0.69807 0.159329 0.698079 -0.698069 0.222529 0 0.974926 0.258811 0.00889227 0.965887 0.623472 -0.00743188 0.781811 0.652291 0 0.757968 0.826233 0 0.563328 0.900904 -0.0119057 0.433855 0.930874 0 0.365341 0.993712 0 0.111965 0.99991 -0.0133996 0 0.993712 0 -0.111965 0.930874 0 -0.365341 0.900904 -0.0119057 -0.433855 0.826233 0 -0.563328 0.623489 0 -0.781832 0.652265 -0.00889521 -0.757938 0.222507 0.0103431 -0.974876 0.258813 0 -0.965928 0.18616 -0.694733 0.694759 0.186161 -0.694738 0.694754 0.508594 -0.694739 0.508596 0.572952 -0.477986 0.665775 0.585056 -0.706113 0.398892 0.694748 -0.694745 0.186157 0.883461 -0.315076 0.346732 0.704873 -0.704873 0.0794206 0.704873 -0.704873 -0.0794206 0.820556 -0.527585 -0.219867 0.186151 -0.694752 -0.694743 0.186159 -0.694738 -0.694755 0.465283 -0.700854 -0.540663 0.58505 -0.561633 -0.585051 0.585056 -0.706113 -0.398892 0.661915 -0.703123 -0.259782 0.258821 0 0.965925 0.258821 0 0.965925 0.707105 0 0.707109 0.707105 0 0.707109 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258818 0.965926 0 -0.258818 0.707105 0 -0.707109 0.707105 0 -0.707109 0.25882 0 -0.965926 0.25882 0 -0.965926 0.222522 0 0.974928 0.222522 0 0.974928 0.623489 0 0.781832 0.623489 0 0.781832 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.623491 0 -0.78183 0.623491 0 -0.78183 0.222519 0 -0.974928 0.222519 0 -0.974928 0.22252 0 0.974928 0.22252 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.62349 0 -0.781831 0.62349 0 -0.781831 0.22252 0 -0.974928 0.22252 0 -0.974928 0.159331 0.698071 0.698076 0.159332 0.698071 0.698076 0.446438 0.698069 0.559815 0.446434 0.698074 0.559813 0.645117 0.698074 0.31067 0.645117 0.698074 0.31067 0.716026 0.698074 0 0.716026 0.698074 0 0.645118 0.698074 -0.310671 0.645117 0.698074 -0.31067 0.446435 0.698074 -0.559812 0.446435 0.698071 -0.559815 0.159332 0.698073 -0.698074 0.159331 0.698071 -0.698076 0.222521 0 0.974928 0.222521 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.90097 0 0.433882 0.90097 0 0.433882 1 0 0 1 0 0 0.90097 0 -0.433882 0.90097 0 -0.433882 0.623489 0 -0.781832 0.623489 0 -0.781832 0.222522 0 -0.974928 0.222522 0 -0.974928 0.159332 -0.698074 -0.698074 0.159331 -0.698075 -0.698072 0.446434 -0.698075 -0.559811 0.446435 -0.698074 -0.559811 0.645118 -0.698073 -0.310671 0.645111 -0.69808 -0.31067 0.716019 -0.698081 0 0.716019 -0.698081 0 0.645112 -0.69808 0.310668 0.645117 -0.698073 0.310673 0.446435 -0.698074 0.559811 0.446436 -0.698072 0.559813 0.159331 -0.698072 0.698076 0.159331 -0.698074 0.698074 0.159329 0.698074 0.698074 0.159332 0.698071 0.698077 0.446437 0.698073 0.559811 0.446432 0.698077 0.559809 0.645115 0.698076 0.31067 0.645117 0.698075 0.31067 0.716026 0.698074 0 0.716026 0.698074 0 0.645119 0.698073 -0.310672 0.645117 0.698074 -0.31067 0.446435 0.698074 -0.559812 0.446434 0.698076 -0.559809 0.159331 0.698075 -0.698072 0.159331 0.698074 -0.698074 0.222519 0 0.974928 0.222519 0 0.974928 0.623491 0 0.78183 0.623491 0 0.78183 0.90097 0 0.433882 0.90097 0 0.433882 1 0 0 1 0 0 0.90097 0 -0.433882 0.90097 0 -0.433882 0.623489 0 -0.781832 0.623489 0 -0.781832 0.222522 0 -0.974928 0.222522 0 -0.974928 0.159332 -0.698074 -0.698074 0.159329 -0.698078 -0.698069 0.446432 -0.698078 -0.559809 0.446433 -0.698077 -0.559809 0.645117 -0.698075 -0.310671 0.645113 -0.698079 -0.31067 0.716019 -0.698081 0 0.716019 -0.698081 0 0.645113 -0.698079 0.310669 0.645116 -0.698075 0.310672 0.446434 -0.698077 0.559808 0.446436 -0.698072 0.559813 0.15933 -0.698072 0.698076 0.15933 -0.698074 0.698074 0.159332 0.698069 0.698078 0.159329 0.698074 0.698074 0.446436 0.698074 0.559811 0.446436 0.698074 0.559811 0.645116 0.698075 0.310672 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310672 0.645116 0.698075 -0.310672 0.446434 0.698074 -0.559812 0.446434 0.698074 -0.559812 0.159333 0.698074 -0.698073 0.159332 0.698069 -0.698078 0.222522 0 0.974928 0.222522 0 0.974928 0.623491 0 0.781831 0.623491 0 0.781831 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.623489 0 -0.781832 0.623489 0 -0.781832 0.222525 0 -0.974927 0.222525 0 -0.974927 0.159335 -0.698067 -0.69808 0.159325 -0.698085 -0.698064 0.446429 -0.698083 -0.559805 0.44643 -0.698081 -0.559806 0.645111 -0.698081 -0.310669 0.645119 -0.698073 -0.31067 0.716026 -0.698074 0 0.716026 -0.698074 0 0.645115 -0.698075 0.310671 0.645114 -0.698078 0.31067 0.446435 -0.698076 0.559809 0.446436 -0.698072 0.559813 0.159332 -0.698072 0.698075 0.159332 -0.698074 0.698074 0.186156 0.694742 0.694751 0.186159 0.694738 0.694755 0.508596 0.694739 0.508595 0.508594 0.69474 0.508594 0.69475 0.694743 0.186157 0.694746 0.694746 0.186158 0.694747 0.694747 -0.186156 0.694748 0.694745 -0.186157 0.50859 0.694747 -0.508589 0.508591 0.694745 -0.508591 0.186159 0.694747 -0.694746 0.186158 0.694742 -0.694751 0.258817 0 0.965926 0.258817 0 0.965926 0.707108 0 0.707106 0.707108 0 0.707106 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258818 0.965926 0 -0.258818 0.707108 0 -0.707106 0.707108 0 -0.707106 0.258822 0 -0.965925 0.258822 0 -0.965925 0.186161 -0.69474 -0.694753 0.186158 -0.694745 -0.694748 0.508591 -0.694745 -0.50859 0.508589 -0.694748 -0.508589 0.694748 -0.694745 -0.186157 0.694743 -0.69475 -0.186157 0.694744 -0.69475 0.186155 0.694747 -0.694746 0.186158 0.50859 -0.694748 0.508589 0.508591 -0.694745 0.508591 0.186156 -0.694744 0.694749 0.186156 -0.694753 0.69474 0.159331 0.698074 -0.698074 0.159331 0.698075 -0.698072 0.330521 0.706861 -0.625383 0.494871 0.608291 -0.620552 0.465273 0.700862 -0.54066 0.585056 0.706116 -0.398886 0.758592 0.53952 -0.365317 0.661919 0.703119 -0.259784 0.70488 0.704867 -0.0794181 0.857931 0.513765 0 0.70488 0.704867 0.0794181 0.645123 0.698068 0.310674 0.846748 0.415426 0.332325 0.585056 0.706116 0.398886 0.446434 0.698074 0.559813 0.159332 0.698074 0.698074 0.159331 0.698075 0.698072 0.330521 0.706861 0.625383 0.530276 0.582332 0.616195 0.186156 0.694747 -0.694747 0.186156 0.69475 -0.694743 0.486313 0.698174 -0.525406 0.444019 0.778264 -0.444019 0.186157 0.694747 0.694747 0.186155 0.69475 0.694743 0.508589 0.694748 0.508589 0.508589 0.694748 0.508589 0.694743 0.69475 0.186156 0.694747 0.694747 0.186156 0.694746 0.694746 -0.186158 0.694743 0.69475 -0.186156 0.598483 0.706845 -0.377079 0.0794166 0.70488 -0.704867 0.164491 0.867163 -0.470076 0.15933 0.698072 -0.698076 0.330525 0.706858 -0.625384 0.494873 0.60829 -0.620552 0.465273 0.700865 -0.540657 0.585053 0.706118 -0.398887 0.758592 0.539519 -0.365318 0.661915 0.703124 -0.259781 0.704873 0.704873 -0.0794211 0.857931 0.513765 0 0.704871 0.704875 0.0794218 0.645113 0.698079 0.31067 0.846748 0.415428 0.332322 0.585057 0.706118 0.398882 0.446433 0.698077 0.55981 0.159331 0.698067 0.69808 0.159329 0.698071 0.698076 0.330525 0.706858 0.625384 0.53028 0.582329 0.616195 0.186157 0.694747 0.694747 0.186157 0.694746 0.694748 0.508587 0.69475 0.508587 0.508593 0.694745 0.508589 0.694747 0.694746 0.186159 0.694741 0.694751 0.18616 0.694741 0.694752 -0.186157 0.694745 0.694747 -0.186161 0.50859 0.694746 -0.50859 0.508588 0.694752 -0.508584 0.186158 0.694748 -0.694745 0.186157 0.694747 -0.694747 0.222519 0 0.974928 0.258808 -0.00889412 0.965888 0.467284 0 0.884107 0.652284 0 0.757974 0.707029 -0.0148506 0.707029 0.826246 0 0.563309 0.930873 0 0.365343 0.965772 -0.0178355 0.25878 0.993712 0 0.111966 0.993712 0 -0.111966 0.965772 -0.0178356 -0.25878 0.930873 0 -0.365344 0.826246 0 -0.563309 0.707029 -0.0148506 -0.707029 0.652284 0 -0.757974 0.467296 0 -0.884101 0.258811 -0.00889465 -0.965887 0.222519 0 -0.974928 0.159332 -0.698074 0.698074 0.159331 -0.698068 0.698079 0.330538 -0.706853 0.625382 0.479465 -0.639246 0.60123 0.465276 -0.700856 0.540665 0.585067 -0.706109 0.398881 0.722592 -0.597301 0.347983 0.661912 -0.703125 0.259783 0.716026 -0.698074 0 0.91323 -0.394236 0.102898 0.704873 -0.704874 -0.079421 0.645116 -0.698074 -0.310673 0.794012 -0.52195 -0.31163 0.585067 -0.706109 -0.398881 0.446439 -0.698068 -0.559815 0.159329 -0.698074 -0.698074 0.159333 -0.698069 -0.698078 0.330547 -0.706853 -0.625378 0.510843 -0.62182 -0.593615 0.186155 0.694747 0.694747 0.186156 0.694745 0.694748 0.508591 0.694744 0.508591 0.508591 0.694744 0.508591 0.694749 0.694745 0.186155 0.694747 0.694747 0.186156 0.694747 0.694747 -0.186156 0.694748 0.694745 -0.186157 0.508591 0.694744 -0.508591 0.508591 0.694744 -0.508591 0.186158 0.694746 -0.694747 0.186157 0.694741 -0.694752 0.258816 0 0.965927 0.258816 0 0.965927 0.707107 0 0.707107 0.707107 0 0.707107 0.965927 0 0.258816 0.965927 0 0.258816 0.965926 0 -0.258818 0.965926 0 -0.258818 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258821 0 -0.965925 0.258821 0 -0.965925 0.186159 -0.694742 -0.694751 0.186156 -0.694748 -0.694746 0.508588 -0.694749 -0.508588 0.508588 -0.694749 -0.508588 0.694746 -0.694748 -0.186155 0.694742 -0.694751 -0.186156 0.694743 -0.694751 0.186154 0.694746 -0.694748 0.186156 0.508588 -0.694749 0.508588 0.508588 -0.694749 0.508588 0.186155 -0.694747 0.694746 0.186155 -0.694751 0.694743 0.186157 0.694752 0.694741 0.186161 0.694747 0.694745 0.50859 0.694746 0.50859 0.508584 0.694752 0.508588 0.694745 0.694748 0.186158 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186156 0.694748 0.694745 -0.186157 0.508591 0.694744 -0.508591 0.508591 0.694746 -0.50859 0.186158 0.694746 -0.694746 0.186157 0.694741 -0.694752 0.258821 0 0.965925 0.258821 0 0.965925 0.707107 0 0.707107 0.707107 0 0.707107 0.965925 0 0.258821 0.965925 0 0.258821 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258821 0 -0.965925 0.258821 0 -0.965925 0.186162 -0.694733 -0.694759 0.186159 -0.694738 -0.694755 0.508595 -0.694739 -0.508595 0.508592 -0.694742 -0.508594 0.694748 -0.694745 -0.186157 0.694747 -0.694747 -0.186157 0.694746 -0.694746 0.186158 0.694743 -0.69475 0.186156 0.508584 -0.694755 0.508584 0.508585 -0.694752 0.508587 0.186156 -0.694756 0.694738 0.186156 -0.694751 0.694742 0.222522 0 0.974928 0.258778 0.0178261 0.965772 0.467265 0 0.884117 0.652285 0 0.757974 0.706792 0.0297581 0.706795 0.826238 0 0.563321 0.930874 0 0.365342 0.965309 0.0357366 0.258653 0.993713 0 0.111961 0.993713 0 -0.111961 0.965309 0.0357365 -0.258652 0.930874 0 -0.365341 0.826238 0 -0.563321 0.706792 0.0297581 -0.706795 0.222522 0 -0.974928 0.258778 0.0178261 -0.965772 0.467265 0 -0.884117 0.652285 0 -0.757974 0.258819 0 0.965926 0.258819 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.22252 0 0.974928 0.258777 0.0178264 0.965773 0.467268 0 0.884116 0.652288 0 0.757971 0.706795 0.0297584 0.706792 0.826241 0 0.563317 0.930875 0 0.365339 0.965309 0.0357352 0.258654 0.993712 0 0.111967 0.993712 0 -0.111966 0.965309 0.0357356 -0.258653 0.930875 0 -0.365339 0.826235 0 -0.563325 0.706792 0.0297571 -0.706795 0.22252 0 -0.974928 0.258777 0.0178264 -0.965773 0.467268 0 -0.884116 0.652288 0 -0.757971 0.159331 0.698071 0.698076 0.15933 0.698073 0.698075 0.446434 0.698075 0.559811 0.446435 0.698074 0.559812 0.645115 0.698075 0.310674 0.645116 0.698074 0.310673 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698073 -0.310675 0.645115 0.698075 -0.310673 0.446435 0.698074 -0.559812 0.446434 0.698075 -0.559811 0.159331 0.698073 -0.698075 0.159331 0.698074 -0.698074 0.222521 0 0.974928 0.258813 0.00717268 0.965901 0.623478 -0.00599239 0.781818 0.652286 0 0.757973 0.826238 0 0.563321 0.900926 -0.00960117 0.433867 0.930872 0 0.365344 0.993712 0 0.111967 0.999942 -0.0108066 0 0.993712 0 -0.111967 0.930872 0 -0.365344 0.900926 -0.00960126 -0.433867 0.826237 0 -0.563323 0.623489 0 -0.781832 0.652271 -0.00717265 -0.757952 0.222513 0.00834232 -0.974894 0.258818 0 -0.965926 0.186157 -0.694747 0.694747 0.186157 -0.694749 0.694744 0.508588 -0.69475 0.508588 0.592519 -0.418163 0.688521 0.585056 -0.706116 0.398885 0.661913 -0.703124 0.259784 0.846814 -0.481061 0.226904 0.70488 -0.704866 0.0794229 0.70488 -0.704866 -0.0794227 0.846815 -0.48106 -0.226904 0.186155 -0.69475 -0.694744 0.186156 -0.694749 -0.694745 0.465273 -0.700865 -0.540657 0.601349 -0.52608 -0.601348 0.585056 -0.706114 -0.398888 0.661914 -0.703123 -0.259785 0.159332 0.698069 0.698078 0.159329 0.698074 0.698074 0.446436 0.698074 0.559811 0.446436 0.698074 0.559811 0.645116 0.698075 0.310672 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645117 0.698074 -0.310672 0.645116 0.698075 -0.310672 0.446436 0.698074 -0.559811 0.446436 0.69807 -0.559815 0.15933 0.698069 -0.698078 0.159331 0.698074 -0.698074 0.222522 0 0.974928 0.222522 0 0.974928 0.623491 0 0.781831 0.623491 0 0.781831 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.623491 0 -0.781831 0.623491 0 -0.781831 0.222518 0 -0.974928 0.222518 0 -0.974928 0.159327 -0.698081 -0.698068 0.159332 -0.698072 -0.698075 0.446437 -0.698072 -0.559812 0.446434 -0.698076 -0.55981 0.645113 -0.698078 -0.31067 0.645116 -0.698076 -0.310671 0.716026 -0.698074 0 0.716026 -0.698074 0 0.645115 -0.698075 0.310671 0.645114 -0.698078 0.31067 0.446435 -0.698076 0.559809 0.446434 -0.698077 0.559808 0.15933 -0.698078 0.698069 0.15933 -0.698074 0.698074 0.159335 0.698069 0.698077 0.159331 0.698074 0.698073 0.446433 0.698074 0.559813 0.446436 0.698071 0.559814 0.64512 0.69807 0.310673 0.64512 0.69807 0.310673 0.71603 0.69807 0 0.71603 0.69807 0 0.645121 0.698068 -0.310675 0.64512 0.69807 -0.310673 0.446436 0.698071 -0.559814 0.446436 0.698074 -0.559811 0.159332 0.698074 -0.698073 0.159332 0.698074 -0.698074 0.222526 0 0.974927 0.222526 0 0.974927 0.623487 0 0.781833 0.623487 0 0.781833 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900968 0 -0.433885 0.900968 0 -0.433885 0.623489 0 -0.781832 0.623489 0 -0.781832 0.222522 0 -0.974928 0.222522 0 -0.974928 0.159332 -0.698074 -0.698074 0.159329 -0.698078 -0.698069 0.446432 -0.698078 -0.559809 0.446433 -0.698077 -0.559809 0.645116 -0.698075 -0.310673 0.645118 -0.698072 -0.310673 0.716026 -0.698074 0 0.716026 -0.698074 0 0.645118 -0.698073 0.310673 0.645121 -0.698069 0.310675 0.446438 -0.698066 0.559819 0.446436 -0.698072 0.559813 0.159334 -0.698072 0.698074 0.159334 -0.698067 0.69808 0.18616 0.694742 0.69475 0.186157 0.694747 0.694746 0.50859 0.694747 0.508589 0.508588 0.694749 0.508588 0.694745 0.694748 0.186157 0.694749 0.694744 0.186156 0.694749 0.694744 -0.186158 0.694746 0.694748 -0.186156 0.508589 0.694749 -0.508588 0.50859 0.694747 -0.50859 0.186155 0.694747 -0.694747 0.186155 0.694743 -0.694751 0.258822 0 0.965925 0.258822 0 0.965925 0.707108 0 0.707106 0.707108 0 0.707106 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707108 0 -0.707106 0.707108 0 -0.707106 0.258817 0 -0.965926 0.258817 0 -0.965926 0.186154 -0.694754 -0.694741 0.186158 -0.694746 -0.694747 0.50859 -0.694747 -0.508589 0.508588 -0.69475 -0.508588 0.694744 -0.694749 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694747 0.186157 0.694745 -0.694749 0.186156 0.508588 -0.69475 0.508587 0.508589 -0.694748 0.508589 0.186159 -0.694746 0.694747 0.186159 -0.69474 0.694753 0.186157 0.694747 0.694747 0.186156 0.694749 0.694745 0.508588 0.69475 0.508587 0.508592 0.694745 0.50859 0.694749 0.694744 0.186156 0.69474 0.694753 0.186156 0.69474 0.694753 -0.186154 0.694748 0.694745 -0.186158 0.508591 0.694745 -0.50859 0.50859 0.694747 -0.508588 0.186157 0.694745 -0.694748 0.186157 0.694747 -0.694747 0.186158 0.694746 0.694746 0.186159 0.694744 0.694749 0.508593 0.694743 0.508592 0.508585 0.694752 0.508587 0.694741 0.694752 0.186156 0.694747 0.694747 0.186156 0.694746 0.694746 -0.186158 0.694743 0.69475 -0.186156 0.50859 0.694748 -0.508588 0.508592 0.694743 -0.508592 0.186157 0.694744 -0.69475 0.186157 0.694747 -0.694747 0.159329 0.69808 0.698067 0.159333 0.698072 0.698075 0.446436 0.698072 0.559813 0.446432 0.698076 0.55981 0.645116 0.698075 0.310672 0.645118 0.698073 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645118 0.698072 -0.310673 0.645117 0.698075 -0.310671 0.446433 0.698077 -0.559809 0.446435 0.698072 -0.559813 0.159331 0.698072 -0.698076 0.159331 0.69808 -0.698067 0.186157 0.694744 0.694749 0.186156 0.694745 0.694748 0.508591 0.694744 0.508591 0.50859 0.694746 0.508591 0.694746 0.694746 0.186158 0.694752 0.694741 0.186157 0.694751 0.694741 -0.18616 0.694748 0.694746 -0.186156 0.50859 0.694746 -0.50859 0.508591 0.694744 -0.508592 0.186157 0.694745 -0.694748 0.186157 0.694747 -0.694747 0.258819 0 0.965926 0.258819 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965925 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258819 0 -0.965926 0.258819 0 -0.965926 0.186156 -0.694747 -0.694747 0.186157 -0.694745 -0.694748 0.508593 -0.694742 -0.508593 0.508596 -0.694739 -0.508594 0.694754 -0.694738 -0.186161 0.694759 -0.694733 -0.18616 0.694759 -0.694733 0.186162 0.694755 -0.694738 0.186159 0.508595 -0.694739 0.508595 0.508595 -0.694739 0.508595 0.186158 -0.694741 0.694752 0.186158 -0.694742 0.694751 0.186156 0.694747 0.694747 0.186157 0.694745 0.694748 0.508591 0.694744 0.508591 0.508591 0.694744 0.508591 0.694747 0.694746 0.186158 0.694752 0.694741 0.186157 0.694751 0.694741 -0.18616 0.694747 0.694747 -0.186156 0.508589 0.694748 -0.508589 0.50859 0.694745 -0.508593 0.186159 0.694746 -0.694747 0.186159 0.694746 -0.694746 0.258818 0 0.965926 0.258818 0 0.965926 0.707107 0 0.707107 0.707107 0 0.707107 0.965925 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258822 0.965925 0 -0.258822 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258822 0 -0.965925 0.258822 0 -0.965925 0.18616 -0.694742 -0.69475 0.186157 -0.694748 -0.694746 0.508588 -0.694749 -0.508588 0.508588 -0.694749 -0.508588 0.694745 -0.694748 -0.186159 0.694751 -0.694742 -0.186158 0.694751 -0.694742 0.186159 0.694748 -0.694745 0.186157 0.508593 -0.694742 0.508593 0.50859 -0.694748 0.508587 0.186155 -0.694748 0.694746 0.186156 -0.694751 0.694742 0.159338 0.698068 0.698078 0.159329 0.698078 0.698069 0.446432 0.698077 0.559809 0.446437 0.698073 0.559811 0.645118 0.698072 0.310674 0.645119 0.698071 0.310674 0.716026 0.698074 0 0.716026 0.698074 0 0.645119 0.698071 -0.310675 0.645118 0.698072 -0.310673 0.446435 0.698073 -0.559812 0.446434 0.698077 -0.559808 0.159329 0.698078 -0.69807 0.159329 0.698079 -0.698069 0.222529 0 0.974926 0.222529 0 0.974926 0.623489 0 0.781832 0.623489 0 0.781832 0.900968 0 0.433886 0.900968 0 0.433886 1 0 0 1 0 0 0.900968 0 -0.433886 0.900968 0 -0.433886 0.623489 0 -0.781832 0.623489 0 -0.781832 0.222519 0 -0.974928 0.222519 0 -0.974928 0.159329 -0.698078 -0.69807 0.159331 -0.698074 -0.698073 0.446434 -0.698074 -0.559812 0.446431 -0.698078 -0.55981 0.645116 -0.698075 -0.310673 0.645124 -0.698067 -0.310674 0.716026 -0.698074 0 0.716026 -0.698074 0 0.645116 -0.698074 0.310673 0.645116 -0.698075 0.310673 0.446432 -0.698078 0.559809 0.446433 -0.698074 0.559813 0.159337 -0.698075 0.698071 0.159334 -0.69806 0.698086 0.258819 0 0.965926 0.258819 0 0.965926 0.707107 0 0.707106 0.707107 0 0.707106 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258818 0.965926 0 -0.258818 0.707107 0 -0.707106 0.707107 0 -0.707106 0.258818 0 -0.965926 0.258818 0 -0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.707108 0 0.707106 0.707108 0 0.707106 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707108 0 -0.707106 0.707108 0 -0.707106 0.258818 0 -0.965926 0.258818 0 -0.965926 0.22252 0 0.974928 0.22252 0 0.974928 0.62349 0 0.781832 0.62349 0 0.781832 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.62349 0 -0.781832 0.62349 0 -0.781832 0.22252 0 -0.974928 0.22252 0 -0.974928 0.186158 0.694744 0.694749 0.186157 0.694745 0.694748 0.508589 0.694747 0.50859 0.508589 0.694747 0.50859 0.694745 0.694747 0.186159 0.694751 0.694742 0.186158 0.69475 0.694742 -0.18616 0.694746 0.694747 -0.186157 0.508589 0.694747 -0.50859 0.508589 0.694747 -0.50859 0.186158 0.694746 -0.694748 0.186157 0.694744 -0.694749 0.25882 0 0.965926 0.25882 0 0.965926 0.707106 0 0.707108 0.707106 0 0.707108 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 -0.258822 0.965925 0 -0.258822 0.707106 0 -0.707108 0.707106 0 -0.707108 0.25882 0 -0.965926 0.25882 0 -0.965926 0.186157 -0.694747 -0.694747 0.186156 -0.694749 -0.694745 0.508587 -0.69475 -0.508588 0.508591 -0.694745 -0.50859 0.694748 -0.694745 -0.186159 0.694753 -0.69474 -0.186159 0.694753 -0.69474 0.186161 0.694748 -0.694745 0.186158 0.50859 -0.694745 0.508591 0.508588 -0.69475 0.508587 0.186157 -0.694749 0.694744 0.186157 -0.694747 0.694747 0.159329 0.698074 0.698074 0.159332 0.69807 0.698078 0.44644 0.69807 0.559813 0.446432 0.698077 0.559809 0.645114 0.698077 0.310672 0.645117 0.698074 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645118 0.698072 -0.310674 0.645116 0.698075 -0.310672 0.446436 0.698074 -0.559811 0.446436 0.698074 -0.559811 0.159331 0.698074 -0.698073 0.159331 0.698074 -0.698074 0.222518 0 0.974928 0.222518 0 0.974928 0.623493 0 0.781829 0.623493 0 0.781829 0.900968 0 0.433885 0.900968 0 0.433885 1 0 0 1 0 0 0.900968 0 -0.433885 0.900968 0 -0.433885 0.623491 0 -0.781831 0.623491 0 -0.781831 0.222522 0 -0.974928 0.222522 0 -0.974928 0.159331 -0.698074 -0.698074 0.159329 -0.698078 -0.69807 0.446433 -0.698078 -0.559808 0.44643 -0.698081 -0.559806 0.64511 -0.698081 -0.31067 0.645119 -0.698073 -0.310671 0.716026 -0.698074 0 0.716026 -0.698074 0 0.645118 -0.698072 0.310674 0.645112 -0.698081 0.310668 0.446433 -0.698081 0.559804 0.446436 -0.698072 0.559813 0.159329 -0.698072 0.698076 0.15933 -0.698074 0.698074 0.186158 0.694742 0.694751 0.186156 0.694746 0.694747 0.508592 0.694745 0.50859 0.508588 0.694749 0.508588 0.694745 0.694748 0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 -0.186157 0.694748 0.694745 -0.186158 0.508592 0.694742 -0.508594 0.508591 0.694745 -0.508591 0.186159 0.694747 -0.694746 0.186158 0.694742 -0.694751 0.25882 0 0.965926 0.25882 0 0.965926 0.707108 0 0.707105 0.707108 0 0.707105 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258819 0.965926 0 -0.258819 0.707105 0 -0.707108 0.707105 0 -0.707108 0.258822 0 -0.965925 0.258822 0 -0.965925 0.186161 -0.69474 -0.694753 0.186151 -0.694758 -0.694736 0.508581 -0.694758 -0.508583 0.508594 -0.694743 -0.50859 0.694745 -0.694749 -0.186156 0.694747 -0.694747 -0.186156 0.694747 -0.694747 0.186157 0.694742 -0.694752 0.186154 0.508587 -0.694753 0.508585 0.508589 -0.694748 0.508589 0.186158 -0.694745 0.694748 0.186158 -0.694746 0.694746 0.186156 0.694742 0.694751 0.186159 0.694738 0.694754 0.508595 0.69474 0.508594 0.508593 0.694742 0.508593 0.694748 0.694745 0.186158 0.694749 0.694744 0.186157 0.694749 0.694744 -0.186158 0.694746 0.694748 -0.186156 0.508589 0.694749 -0.508588 0.50859 0.694747 -0.50859 0.186159 0.694747 -0.694745 0.186158 0.694742 -0.694751 0.258817 0 0.965926 0.258817 0 0.965926 0.707108 0 0.707106 0.707108 0 0.707106 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707108 0 -0.707106 0.707108 0 -0.707106 0.258822 0 -0.965925 0.258822 0 -0.965925 0.186161 -0.69474 -0.694753 0.186158 -0.694746 -0.694747 0.50859 -0.694747 -0.508589 0.508588 -0.69475 -0.508588 0.694744 -0.694749 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694747 0.186157 0.694745 -0.694749 0.186156 0.508588 -0.69475 0.508587 0.508589 -0.694748 0.508589 0.186156 -0.694745 0.694748 0.186156 -0.694753 0.69474 0.159331 0.698074 0.698074 0.15933 0.698075 0.698073 0.446434 0.698075 0.55981 0.446435 0.698074 0.559811 0.645117 0.698073 0.310673 0.645111 0.69808 0.310672 0.716019 0.698081 0 0.716019 0.698081 0 0.645111 0.69808 -0.310669 0.645116 0.698073 -0.310674 0.446435 0.698074 -0.559811 0.446435 0.698075 -0.55981 0.15933 0.698075 -0.698072 0.15933 0.698074 -0.698074 0.159332 0.698074 0.698074 0.15933 0.698078 0.698069 0.446432 0.698078 0.559809 0.446434 0.698076 0.55981 0.645113 0.698078 0.31067 0.645119 0.698073 0.310671 0.716026 0.698074 0 0.716026 0.698074 0 0.645115 0.698076 -0.310671 0.645114 0.698078 -0.31067 0.446435 0.698076 -0.559809 0.446436 0.698072 -0.559813 0.159331 0.698072 -0.698076 0.159331 0.698074 -0.698074 0.159332 0.698067 0.69808 0.159329 0.698071 0.698076 0.446436 0.698072 0.559813 0.446432 0.698076 0.55981 0.645117 0.698074 0.31067 0.645113 0.698079 0.31067 0.716026 0.698074 0 0.716026 0.698074 0 0.645118 0.698072 -0.310673 0.645117 0.698075 -0.310671 0.446433 0.698077 -0.559809 0.446435 0.698072 -0.559813 0.159331 0.698072 -0.698076 0.159331 0.69808 -0.698067 0.159329 0.698074 0.698074 0.15933 0.698074 0.698074 0.446435 0.698075 0.55981 0.446437 0.698073 0.559811 0.645115 0.698074 0.310676 0.645117 0.698072 0.310675 0.716028 0.698071 0 0.716028 0.698071 0 0.645118 0.698071 -0.310678 0.645115 0.698075 -0.310674 0.446436 0.698075 -0.559809 0.446436 0.698075 -0.55981 0.15933 0.698074 -0.698074 0.15933 0.698074 -0.698074 0.222519 0 0.974928 0.258806 0.00889355 0.965888 0.623473 -0.00743134 0.781809 0.652291 0 0.757969 0.826231 0 0.563331 0.900902 -0.011906 0.433858 0.930873 0 0.365343 0.993712 0 0.111966 0.99991 -0.0133996 0 0.993712 0 -0.111966 0.930873 0 -0.365344 0.900902 -0.0119059 -0.433859 0.826231 0 -0.563331 0.623492 0 -0.78183 0.652265 -0.00889414 -0.757939 0.222507 0.0103448 -0.974876 0.258819 0 -0.965926 0.186157 -0.694747 0.694747 0.186156 -0.694741 0.694753 0.508595 -0.694739 0.508595 0.572954 -0.477978 0.665778 0.585058 -0.706108 0.398898 0.694755 -0.694738 0.186159 0.883469 -0.315049 0.346738 0.704886 -0.70486 0.0794229 0.704886 -0.70486 -0.0794225 0.820568 -0.527566 -0.21987 0.186156 -0.694747 -0.694747 0.186157 -0.694745 -0.694748 0.46528 -0.700858 -0.54066 0.58505 -0.561635 -0.58505 0.585056 -0.70611 -0.398896 0.661919 -0.703118 -0.259786 0.159329 0.698074 0.698074 0.159331 0.698072 0.698075 0.446437 0.698071 0.559813 0.446433 0.698075 0.559812 0.645115 0.698075 0.310673 0.64512 0.698071 0.310672 0.716028 0.698071 0 0.716028 0.698071 0 0.645119 0.698071 -0.310675 0.645117 0.698075 -0.310671 0.446435 0.698075 -0.55981 0.446435 0.698072 -0.559814 0.159333 0.698073 -0.698074 0.159332 0.698068 -0.698079 0.222519 0 0.974928 0.222519 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900968 0 0.433886 0.900968 0 0.433886 1 0 0 1 0 0 0.900968 0 -0.433886 0.900968 0 -0.433886 0.62349 0 -0.781831 0.62349 0 -0.781831 0.222524 0 -0.974927 0.222524 0 -0.974927 0.159334 -0.698069 -0.698078 0.159332 -0.698073 -0.698074 0.446437 -0.698071 -0.559813 0.446434 -0.698074 -0.559812 0.645115 -0.698075 -0.310673 0.645124 -0.698066 -0.310674 0.716034 -0.698065 0 0.716034 -0.698065 0 0.645123 -0.698066 0.310677 0.645117 -0.698074 0.31067 0.446435 -0.698074 0.559811 0.446436 -0.698071 0.559814 0.15933 -0.698073 0.698075 0.159331 -0.698078 0.698069 0.159328 0.698079 0.698069 0.159338 0.698068 0.698077 0.446437 0.698069 0.559816 0.446433 0.698073 0.559814 0.645119 0.698072 0.310671 0.645115 0.698076 0.310672 0.716026 0.698074 0 0.716026 0.698074 0 0.645116 0.698076 -0.310669 0.645121 0.698068 -0.310678 0.44644 0.698065 -0.559819 0.44644 0.698069 -0.559814 0.159331 0.698068 -0.69808 0.159331 0.698068 -0.698079 0.222519 0 0.974928 0.222519 0 0.974928 0.623489 0 0.781832 0.623489 0 0.781832 0.90097 0 0.433881 0.90097 0 0.433881 1 0 0 1 0 0 0.90097 0 -0.433881 0.90097 0 -0.433881 0.623489 0 -0.781832 0.623489 0 -0.781832 0.222519 0 -0.974928 0.222519 0 -0.974928 0.159332 -0.698061 -0.698087 0.159325 -0.698073 -0.698076 0.446434 -0.698074 -0.559812 0.446443 -0.698064 -0.559817 0.645124 -0.698066 -0.310674 0.645116 -0.698074 -0.310673 0.716026 -0.698074 0 0.716026 -0.698074 0 0.645117 -0.698075 0.31067 0.645123 -0.698067 0.310676 0.44644 -0.698064 0.55982 0.446438 -0.698073 0.55981 0.15933 -0.698074 0.698074 0.15933 -0.698078 0.698069 0.222521 0 0.974928 0.222521 0 0.974928 0.62349 0 0.781831 0.62349 0 0.781831 0.900968 0 0.433885 0.900968 0 0.433885 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.62349 0 -0.781831 0.62349 0 -0.781831 0.222521 0 -0.974928 0.222521 0 -0.974928 0.222523 0 0.974927 0.222523 0 0.974927 0.623489 0 0.781832 0.623489 0 0.781832 0.900969 0 0.433884 0.900969 0 0.433884 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.623491 0 -0.78183 0.623491 0 -0.78183 0.22252 0 -0.974928 0.22252 0 -0.974928 0.22252 0 0.974928 0.22252 0 0.974928 0.62349 0 0.781832 0.62349 0 0.781832 0.90097 0 0.433882 0.90097 0 0.433882 1 0 0 1 0 0 0.900969 0 -0.433884 0.900969 0 -0.433884 0.62349 0 -0.781832 0.62349 0 -0.781832 0.22252 0 -0.974928 0.22252 0 -0.974928 0.0980171 0 -0.995185 0.0980171 0 -0.995185 0.290285 0 -0.95694 0.290285 0 -0.95694 0.471397 0 -0.881921 0.471397 0 -0.881921 0.634393 0 -0.77301 0.634393 0 -0.77301 0.77301 0 -0.634393 0.77301 0 -0.634393 0.881921 0 -0.471397 0.881921 0 -0.471397 0.95694 0 -0.290285 0.95694 0 -0.290285 0.995185 0 -0.0980174 0.995185 0 -0.0980174 0.995185 0 0.0980174 0.995185 0 0.0980174 0.95694 0 0.290285 0.95694 0 0.290285 0.881921 0 0.471397 0.881921 0 0.471397 0.77301 0 0.634393 0.77301 0 0.634393 0.634393 0 0.773011 0.634393 0 0.773011 0.471397 0 0.881921 0.471397 0 0.881921 0.290285 0 0.95694 0.290285 0 0.95694 0.0980171 0 0.995185 0.0980171 0 0.995185 0.082579 0 -0.996585 0.082579 0 -0.996585 0.245485 0 -0.9694 0.245485 0 -0.9694 0.401696 0 -0.915773 0.401696 0 -0.915773 0.546948 0 -0.837167 0.546948 0 -0.837167 0.677282 0 -0.735724 0.677282 0 -0.735724 0.789141 0 -0.614213 0.789141 0 -0.614213 0.879474 0 -0.475948 0.879474 0 -0.475948 0.945817 0 -0.324699 0.945817 0 -0.324699 0.986361 0 -0.164595 0.986361 0 -0.164595 1 0 0 1 0 0 0.986361 0 0.164595 0.986361 0 0.164595 0.945817 0 0.324699 0.945817 0 0.324699 0.879474 0 0.475948 0.879474 0 0.475948 0.789141 0 0.614213 0.789141 0 0.614213 0.677282 0 0.735724 0.677282 0 0.735724 0.546948 0 0.837167 0.546948 0 0.837167 0.401696 0 0.915773 0.401696 0 0.915773 0.245485 0 0.9694 0.245485 0 0.9694 0.0825795 0 0.996584 0.0825795 0 0.996584 0.11675 0.851306 0.511515 0.116751 0.851306 -0.511515 0.11675 0.851305 -0.511516 0.240773 0.857008 -0.455594 0.316258 0.861807 -0.396572 0.447957 0.867639 -0.215724 0.426423 0.856531 -0.290722 0.340301 0.853127 -0.395436 0.493914 0.869511 0 0.514171 0.855729 -0.0579285 0.483393 0.854598 -0.189722 0.447957 0.867639 0.215724 0.483393 0.854598 0.189722 0.514171 0.855729 0.0579285 0.116751 0.851305 0.511516 0.240773 0.857008 0.455594 0.316258 0.861807 0.396572 0.340301 0.853127 0.395436 0.426423 0.856531 0.290722 0.13671 0.849119 0.510203 0.13671 0.849119 0.510203 0.373498 0.849118 0.373494 0.373492 0.849121 0.373494 0.5102 0.849121 0.136709 0.510201 0.849121 0.136708 0.510201 0.849121 -0.136708 0.510201 0.849121 -0.136708 0.373494 0.84912 -0.373494 0.373494 0.84912 -0.373494 0.136709 0.849121 -0.510201 0.136709 0.849121 -0.5102 0.136709 0.849121 0.510201 0.136708 0.849121 0.5102 0.373491 0.849121 0.373494 0.373494 0.84912 0.373494 0.510201 0.849121 0.136707 0.510203 0.849119 0.136706 0.510203 0.849119 -0.13671 0.510202 0.84912 -0.136707 0.373493 0.849119 -0.373496 0.373493 0.849121 -0.373493 0.136709 0.849121 -0.5102 0.136708 0.849121 -0.510201 0.136709 0.849121 0.510201 0.136708 0.849121 0.5102 0.373491 0.849121 0.373494 0.373494 0.84912 0.373494 0.510201 0.849121 0.136709 0.510203 0.849119 0.136707 0.510203 0.849119 -0.136708 0.510202 0.84912 -0.136706 0.373493 0.849119 -0.373496 0.373493 0.849121 -0.373493 0.136709 0.849121 -0.5102 0.136708 0.849121 -0.510201 0.13671 0.849119 0.510203 0.136707 0.84912 0.510202 0.373496 0.849119 0.373493 0.373493 0.849121 0.373493 0.5102 0.849121 0.136709 0.510201 0.849121 0.136708 0.510201 0.849121 -0.136708 0.510201 0.849121 -0.136708 0.373494 0.84912 -0.373494 0.373494 0.84912 -0.373494 0.136709 0.849121 -0.510201 0.136709 0.849121 -0.5102 0.136709 0.84912 0.510202 0.136708 0.849121 0.510201 0.373489 0.849122 0.373494 0.373497 0.849118 0.373494 0.510206 0.849118 0.13671 0.510206 0.849117 0.13671 0.510206 0.849117 -0.13671 0.510206 0.849118 -0.13671 0.373494 0.849118 -0.373498 0.373494 0.849121 -0.373491 0.136708 0.849121 -0.510201 0.136708 0.84912 -0.510202 0.13671 0.849119 0.510203 0.136705 0.849121 0.510201 0.373489 0.849123 0.373492 0.373497 0.849119 0.373493 0.510205 0.849118 0.13671 0.510206 0.849117 0.13671 0.510206 0.849117 -0.136709 0.510206 0.849117 -0.13671 0.373494 0.849117 -0.373501 0.373494 0.849122 -0.373489 0.136708 0.849122 -0.510199 0.136708 0.849121 -0.510201 0.136708 0.849121 0.510201 0.136708 0.849121 0.510201 0.373494 0.84912 0.373494 0.373494 0.84912 0.373494 0.510201 0.849121 0.136709 0.510201 0.849121 0.136709 0.510201 0.849121 -0.136707 0.510201 0.849121 -0.136708 0.373494 0.84912 -0.373494 0.373494 0.84912 -0.373494 0.136708 0.849121 -0.510201 0.136708 0.849121 -0.510201 0.136708 0.849121 0.510201 0.136708 0.849121 0.510201 0.373494 0.84912 0.373494 0.373494 0.84912 0.373494 0.510201 0.849121 0.136707 0.510201 0.849121 0.136708 0.510201 0.849121 -0.136709 0.510201 0.849121 -0.136709 0.373494 0.84912 -0.373494 0.373494 0.84912 -0.373494 0.136708 0.849121 -0.510201 0.136708 0.849121 -0.510201 0.13671 0.849119 0.510203 0.136708 0.84912 0.510202 0.373491 0.849121 0.373494 0.373496 0.849119 0.373494 0.510205 0.849118 0.13671 0.510206 0.849117 0.13671 0.510206 0.849117 -0.136709 0.510206 0.849117 -0.13671 0.373494 0.849117 -0.373501 0.373494 0.849122 -0.373489 0.136708 0.849122 -0.510199 0.136708 0.849121 -0.510201 0.116751 0.851305 0.511516 0.116751 0.851305 0.511516 0.327135 0.851304 0.410199 0.327127 0.851306 0.410204 0.472706 0.851306 0.227654 0.472712 0.851305 0.227646 0.52467 0.851306 0 0.52467 0.851306 0 0.472709 0.851305 -0.227655 0.472711 0.851306 -0.227646 0.327133 0.851307 -0.410197 0.327126 0.851305 -0.410204 0.116751 0.851305 -0.511515 0.116751 0.851305 -0.511516 0.136715 0.849119 0.510202 0.136709 0.84912 -0.510202 0.136706 0.849119 -0.510204 0.340301 0.853126 -0.395438 0.365491 0.856057 -0.36549 0.497111 0.857399 -0.133223 0.483396 0.854596 -0.189719 0.426421 0.85653 -0.290727 0.497111 0.857399 0.133223 0.514173 0.855728 0.0579355 0.514173 0.855728 -0.0579354 0.136708 0.84912 0.510203 0.340301 0.853126 0.395438 0.365486 0.856057 0.365495 0.426421 0.85653 0.290727 0.483396 0.854596 0.189719 0.116747 0.851306 0.511516 0.11675 0.851305 -0.511516 0.116746 0.851305 -0.511518 0.240787 0.857008 -0.455586 0.323622 0.854761 -0.405774 0.464593 0.856792 -0.223742 0.426421 0.85653 -0.290727 0.340301 0.853126 -0.395438 0.514549 0.857461 0 0.514172 0.855728 -0.0579354 0.483396 0.854596 -0.189719 0.464594 0.856792 0.223742 0.483396 0.854596 0.189719 0.514172 0.855728 0.0579354 0.11675 0.851305 0.511516 0.240788 0.857008 0.455585 0.323615 0.854762 0.405778 0.340301 0.853126 0.395438 0.426421 0.85653 0.290727 0.116751 0.851305 0.511516 0.11675 0.851305 -0.511516 0.11675 0.851306 -0.511515 0.240785 0.857008 -0.455587 0.323611 0.854762 -0.40578 0.464596 0.856792 -0.223738 0.42642 0.85653 -0.290729 0.340302 0.853126 -0.395437 0.51455 0.857461 0 0.514173 0.855728 -0.0579333 0.483396 0.854596 -0.189719 0.464596 0.856792 0.223738 0.483396 0.854596 0.189719 0.514173 0.855728 0.0579335 0.11675 0.851305 0.511516 0.240784 0.857008 0.455587 0.323611 0.854762 0.40578 0.340302 0.853126 0.395437 0.42642 0.85653 0.290729 0.136695 0.849121 0.510203 0.136708 0.84912 0.510203 0.3735 0.849119 0.37349 0.373494 0.84912 0.373494 0.510199 0.849121 0.136715 0.510203 0.84912 0.136708 0.510202 0.849119 -0.136715 0.510202 0.84912 -0.136708 0.373498 0.849121 -0.373489 0.373494 0.84912 -0.373494 0.136729 0.849122 -0.510193 0.136708 0.849119 -0.510203 0.136695 0.849121 0.510203 0.136708 0.849119 -0.510203 0.136729 0.849123 -0.510192 0.340302 0.853126 -0.395437 0.365491 0.856057 -0.36549 0.497117 0.857399 -0.1332 0.483396 0.854596 -0.189719 0.42642 0.856529 -0.290728 0.497117 0.857399 0.1332 0.514173 0.855728 0.0579335 0.514173 0.855728 -0.0579335 0.136708 0.84912 0.510203 0.340302 0.853126 0.395437 0.36549 0.856057 0.36549 0.42642 0.856529 0.290728 0.483396 0.854596 0.189719 0.136711 0.849119 0.510203 0.136707 0.84912 0.510203 0.373505 0.849118 0.373487 0.373494 0.84912 0.373494 0.510199 0.849121 0.136715 0.510202 0.84912 0.136709 0.510202 0.849119 -0.136711 0.510202 0.84912 -0.136708 0.373502 0.849121 -0.373483 0.373495 0.84912 -0.373494 0.13671 0.84912 -0.510202 0.136708 0.84912 -0.510203 0.136706 0.84912 0.510203 0.136708 0.84912 0.510203 0.373494 0.84912 0.373494 0.373494 0.84912 0.373494 0.510208 0.849118 0.136696 0.510203 0.84912 0.136708 0.510203 0.849121 -0.136695 0.510203 0.84912 -0.136708 0.37349 0.849119 -0.3735 0.373494 0.84912 -0.373494 0.136715 0.849121 -0.510199 0.136709 0.84912 -0.510202 0.116756 0.851305 0.511516 0.11675 0.851305 0.511516 0.327123 0.851306 0.410206 0.327126 0.851306 0.410204 0.472709 0.851306 0.22765 0.472712 0.851306 0.227646 0.52467 0.851306 0 0.52467 0.851306 0 0.47271 0.851305 -0.227651 0.472712 0.851306 -0.227645 0.327118 0.851304 -0.410213 0.327125 0.851306 -0.410204 0.116756 0.851306 -0.511513 0.116751 0.851306 -0.511516 0.136711 0.849119 0.510202 0.136708 0.84912 0.510202 0.373505 0.849118 0.373487 0.373494 0.84912 0.373494 0.510199 0.849121 0.136715 0.510202 0.84912 0.136709 0.510202 0.849119 -0.136711 0.510202 0.84912 -0.136708 0.373494 0.84912 -0.373494 0.373494 0.84912 -0.373494 0.13671 0.84912 -0.510202 0.136708 0.84912 -0.510202 0.136695 0.849121 0.510203 0.136708 0.84912 0.510203 0.373494 0.84912 0.373494 0.373494 0.84912 0.373494 0.510203 0.849119 0.136707 0.510202 0.84912 0.136709 0.510203 0.849121 -0.136697 0.510203 0.84912 -0.136709 0.37348 0.849116 -0.373517 0.373494 0.84912 -0.373494 0.136729 0.849122 -0.510193 0.136709 0.84912 -0.510202 0.11673 0.851307 0.511517 0.11675 0.851305 0.511516 0.327129 0.851305 0.410203 0.327127 0.851305 0.410204 0.472712 0.851305 0.227646 0.472712 0.851305 0.227646 0.524671 0.851305 0 0.524671 0.851305 0 0.472706 0.851304 -0.227664 0.472711 0.851306 -0.227647 0.327128 0.851306 -0.410202 0.327127 0.851305 -0.410204 0.116771 0.851308 -0.511508 0.116752 0.851305 -0.511516 -0.136731 0.849117 -0.510201 -0.136709 0.84912 -0.510202 -0.373472 0.849123 -0.373509 -0.373495 0.849119 -0.373494 -0.510208 0.849118 -0.136698 -0.510202 0.84912 -0.136709 -0.510203 0.84912 0.136706 -0.510203 0.84912 0.136709 -0.373494 0.84912 0.373494 -0.373494 0.84912 0.373494 -0.136696 0.849118 0.510208 -0.136708 0.84912 0.510203 -0.136731 0.849117 -0.510201 -0.136708 0.84912 0.510203 -0.136697 0.849118 0.510208 -0.340302 0.853126 0.395437 -0.365491 0.856057 0.36549 -0.497117 0.857399 0.1332 -0.483396 0.854596 0.189719 -0.42642 0.856529 0.290728 -0.497119 0.857399 -0.133191 -0.514173 0.855728 -0.0579331 -0.514173 0.855728 0.0579335 -0.136709 0.84912 -0.510202 -0.340302 0.853126 -0.395437 -0.365474 0.856056 -0.36551 -0.426421 0.856529 -0.290728 -0.483396 0.854596 -0.18972 -0.136715 0.849119 -0.510202 -0.136709 0.84912 0.510202 -0.136716 0.84912 0.510199 -0.340302 0.853126 0.395437 -0.365491 0.856057 0.36549 -0.497114 0.857399 0.133208 -0.483396 0.854596 0.189719 -0.42642 0.85653 0.290729 -0.497115 0.857399 -0.133204 -0.514173 0.855728 -0.0579333 -0.514173 0.855728 0.0579335 -0.136709 0.84912 -0.510202 -0.340301 0.853126 -0.395438 -0.365482 0.856057 -0.3655 -0.42642 0.85653 -0.290729 -0.483396 0.854596 -0.189719 -0.136706 0.84912 -0.510203 -0.136709 0.84912 -0.510202 -0.373494 0.84912 -0.373494 -0.373494 0.84912 -0.373494 -0.510193 0.849122 -0.136729 -0.510202 0.84912 -0.136709 -0.510201 0.849117 0.136731 -0.510202 0.84912 0.136709 -0.373491 0.849119 0.3735 -0.373494 0.84912 0.373494 -0.136715 0.849121 0.510199 -0.136708 0.84912 0.510203 -0.136715 0.849119 -0.510202 -0.136708 0.84912 0.510203 -0.136706 0.849119 0.510204 -0.340301 0.853126 0.395438 -0.365491 0.856057 0.36549 -0.497111 0.857399 0.133223 -0.483396 0.854596 0.189719 -0.426421 0.85653 0.290727 -0.497111 0.857399 -0.133223 -0.514173 0.855728 -0.0579355 -0.514173 0.855728 0.0579355 -0.136709 0.84912 -0.510202 -0.340301 0.853126 -0.395438 -0.365486 0.856057 -0.365495 -0.426421 0.85653 -0.290727 -0.483396 0.854596 -0.189719 -0.136715 0.849119 -0.510202 -0.136708 0.84912 -0.510203 -0.373494 0.84912 -0.373494 -0.373494 0.84912 -0.373494 -0.510202 0.84912 -0.13671 -0.510202 0.84912 -0.136708 -0.510202 0.849119 0.136715 -0.510202 0.84912 0.136709 -0.373494 0.84912 0.373494 -0.373494 0.84912 0.373494 -0.136715 0.849121 0.510199 -0.136708 0.84912 0.510203 -0.116773 0.851303 -0.511515 -0.11675 0.851306 0.511516 -0.11673 0.851304 0.511523 -0.240783 0.857008 0.455588 -0.323605 0.854763 0.405784 -0.464596 0.856792 0.223738 -0.42642 0.85653 0.290728 -0.340302 0.853126 0.395437 -0.51455 0.857461 0 -0.514173 0.855728 0.0579335 -0.483396 0.854596 0.189719 -0.464596 0.856792 -0.223738 -0.483396 0.854596 -0.189719 -0.514173 0.855728 -0.0579335 -0.11675 0.851305 -0.511516 -0.240783 0.857008 -0.455588 -0.323605 0.854763 -0.405784 -0.340302 0.853126 -0.395437 -0.42642 0.85653 -0.290728 -0.11677 0.851303 -0.511515 -0.11675 0.851305 -0.511516 -0.327129 0.851305 -0.410203 -0.327127 0.851305 -0.410204 -0.472717 0.851304 -0.227638 -0.472712 0.851305 -0.227646 -0.52467 0.851305 0 -0.52467 0.851305 0 -0.472714 0.851306 0.227637 -0.472712 0.851305 0.227646 -0.327128 0.851306 0.410202 -0.327127 0.851305 0.410204 -0.11673 0.851303 0.511524 -0.11675 0.851306 0.511516 -0.136711 0.849119 -0.510203 -0.136707 0.84912 -0.510203 -0.373494 0.84912 -0.373494 -0.373495 0.84912 -0.373494 -0.51021 0.849118 -0.136694 -0.510202 0.84912 -0.136708 -0.510203 0.849121 0.136697 -0.510203 0.84912 0.136709 -0.373494 0.84912 0.373494 -0.373495 0.84912 0.373494 -0.13671 0.84912 0.510202 -0.136708 0.84912 0.510203 -0.136715 0.849119 -0.510202 -0.136709 0.84912 -0.510202 -0.373489 0.849121 -0.373498 -0.373494 0.84912 -0.373494 -0.510208 0.849118 -0.136696 -0.510203 0.84912 -0.136708 -0.510203 0.849121 0.136695 -0.510203 0.84912 0.136708 -0.373494 0.84912 0.373494 -0.373494 0.84912 0.373494 -0.136707 0.849119 0.510203 -0.136708 0.84912 0.510203 -0.116747 0.851306 -0.511516 -0.11675 0.851305 0.511516 -0.116746 0.851305 0.511518 -0.240782 0.857008 0.455589 -0.323622 0.854761 0.405774 -0.464594 0.856792 0.223742 -0.426421 0.85653 0.290727 -0.340301 0.853126 0.395438 -0.51455 0.85746 0 -0.514173 0.855728 0.0579314 -0.483396 0.854596 0.189719 -0.464594 0.856792 -0.223742 -0.483396 0.854596 -0.189719 -0.514173 0.855728 -0.0579313 -0.116751 0.851305 -0.511516 -0.240783 0.857008 -0.455588 -0.323615 0.854762 -0.405778 -0.340301 0.853126 -0.395438 -0.426421 0.85653 -0.290726 -0.136711 0.849119 -0.510202 -0.136708 0.84912 -0.510202 -0.373483 0.849121 -0.373502 -0.373494 0.84912 -0.373494 -0.51021 0.849118 -0.136694 -0.510202 0.84912 -0.136708 -0.510203 0.849121 0.136697 -0.510203 0.84912 0.136709 -0.373494 0.84912 0.373494 -0.373495 0.84912 0.373494 -0.13671 0.84912 0.510202 -0.136708 0.84912 0.510202 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.136709 0.849121 -0.510201 -0.136708 0.849119 0.510203 -0.136709 0.84912 0.510202 -0.3403 0.853127 0.395436 -0.349257 0.869506 0.349254 -0.470862 0.873138 0.126168 -0.483393 0.854598 0.189721 -0.426422 0.856531 0.290721 -0.470862 0.873138 -0.126167 -0.514171 0.855729 -0.0579283 -0.514171 0.855729 0.0579289 -0.136707 0.849122 -0.5102 -0.340301 0.853128 -0.395433 -0.349256 0.869506 -0.349256 -0.426423 0.85653 -0.290722 -0.483393 0.854597 -0.189723 -0.116749 0.851307 -0.511514 -0.116748 0.851308 -0.511513 -0.327123 0.851307 -0.410203 -0.327129 0.851305 -0.410204 -0.472713 0.851305 -0.227643 -0.472708 0.851308 -0.227645 -0.524667 0.851307 0 -0.524668 0.851307 0 -0.472709 0.851307 0.227645 -0.472709 0.851307 0.227645 -0.327127 0.851308 0.410199 -0.327126 0.851304 0.410207 -0.11675 0.851304 0.511518 -0.116753 0.851306 0.511514 -0.136709 0.849121 -0.510201 -0.136708 0.849121 0.510201 -0.136709 0.849121 0.5102 -0.3403 0.853127 0.395436 -0.349256 0.869505 0.349259 -0.470865 0.873137 0.126169 -0.483395 0.854597 0.18972 -0.42642 0.85653 0.290727 -0.470864 0.873137 -0.126167 -0.514174 0.855727 -0.0579281 -0.514174 0.855727 0.0579292 -0.136708 0.849121 -0.5102 -0.3403 0.853127 -0.395436 -0.349256 0.869505 -0.349259 -0.42642 0.85653 -0.290727 -0.483395 0.854597 -0.18972 -0.136709 0.849121 -0.510201 -0.136706 0.849119 0.510203 -0.136709 0.849122 0.510199 -0.340301 0.853128 0.395433 -0.349257 0.869506 0.349254 -0.470862 0.873138 0.126168 -0.483392 0.854598 0.189723 -0.426422 0.856531 0.290721 -0.470862 0.873138 -0.126167 -0.514171 0.855729 -0.0579283 -0.514171 0.855729 0.0579283 -0.136707 0.849122 -0.5102 -0.340301 0.853128 -0.395433 -0.349256 0.869506 -0.349256 -0.426423 0.85653 -0.290722 -0.483393 0.854597 -0.189723 -0.136709 0.84912 -0.510202 -0.136708 0.849121 -0.510201 -0.373489 0.849122 -0.373494 -0.373497 0.849118 -0.373494 -0.510209 0.849117 -0.136704 -0.510201 0.849121 -0.136708 -0.510201 0.849122 0.136702 -0.510206 0.849117 0.13671 -0.373494 0.849118 0.373498 -0.373494 0.849121 0.373491 -0.136708 0.849121 0.510201 -0.136708 0.84912 0.510202 -0.136709 0.849121 -0.510201 -0.136707 0.849122 -0.5102 -0.373487 0.849123 -0.373494 -0.373499 0.849118 -0.373494 -0.510206 0.849117 -0.13671 -0.510206 0.849117 -0.13671 -0.510206 0.849117 0.13671 -0.510206 0.849118 0.13671 -0.373494 0.849118 0.373498 -0.373494 0.849122 0.373489 -0.136708 0.849122 0.510199 -0.136706 0.849119 0.510203 -0.136708 0.849121 -0.510201 -0.136708 0.849121 -0.510201 -0.373494 0.84912 -0.373494 -0.373494 0.84912 -0.373494 -0.510201 0.849121 -0.136707 -0.510201 0.849121 -0.136708 -0.510201 0.849121 0.136709 -0.510201 0.849121 0.136709 -0.373494 0.84912 0.373494 -0.373494 0.84912 0.373494 -0.136708 0.849121 0.510201 -0.136708 0.849121 0.510201 -0.136708 0.849121 -0.510201 -0.136708 0.849121 -0.510201 -0.373494 0.84912 -0.373494 -0.373494 0.84912 -0.373494 -0.510201 0.849121 -0.136709 -0.510201 0.849121 -0.136709 -0.510201 0.849121 0.136707 -0.510201 0.849121 0.136708 -0.373494 0.84912 0.373494 -0.373494 0.84912 0.373494 -0.136708 0.849121 0.510201 -0.136708 0.849121 0.510201 -0.136709 0.849121 -0.510201 -0.136707 0.849122 -0.5102 -0.373487 0.849123 -0.373494 -0.373499 0.849118 -0.373494 -0.510206 0.849117 -0.13671 -0.510206 0.849117 -0.13671 -0.510206 0.849117 0.13671 -0.510206 0.849118 0.13671 -0.373494 0.849118 0.373498 -0.373494 0.849121 0.373492 -0.136709 0.84912 0.510202 -0.136708 0.849119 0.510203 -0.136709 0.84912 -0.510202 -0.136708 0.849121 -0.510201 -0.373489 0.849122 -0.373494 -0.373497 0.849118 -0.373494 -0.510206 0.849118 -0.13671 -0.510206 0.849117 -0.13671 -0.510206 0.849117 0.13671 -0.510206 0.849117 0.13671 -0.373494 0.849118 0.373498 -0.373494 0.849121 0.373491 -0.136708 0.849121 0.510201 -0.136708 0.84912 0.510202 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0825795 0 0.996584 -0.0825795 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401695 0 0.915773 -0.401695 0 0.915773 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475948 -0.879474 0 0.475948 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.986361 0 0.164595 -0.986361 0 0.164595 -1 0 0 -1 0 0 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.879474 0 -0.475948 -0.879474 0 -0.475948 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.401695 0 -0.915773 -0.401695 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.082579 0 -0.996585 -0.082579 0 -0.996585 -0.0980171 0 0.995185 -0.0980171 0 0.995185 -0.290285 0 0.95694 -0.290285 0 0.95694 -0.471397 0 0.881921 -0.471397 0 0.881921 -0.634393 0 0.773011 -0.634393 0 0.773011 -0.77301 0 0.634393 -0.77301 0 0.634393 -0.881921 0 0.471397 -0.881921 0 0.471397 -0.95694 0 0.290285 -0.95694 0 0.290285 -0.995185 0 0.0980174 -0.995185 0 0.0980174 -0.995185 0 -0.0980174 -0.995185 0 -0.0980174 -0.95694 0 -0.290285 -0.95694 0 -0.290285 -0.881921 0 -0.471397 -0.881921 0 -0.471397 -0.77301 0 -0.634393 -0.77301 0 -0.634393 -0.634393 0 -0.77301 -0.634393 0 -0.77301 -0.471397 0 -0.881921 -0.471397 0 -0.881921 -0.290285 0 -0.95694 -0.290285 0 -0.95694 -0.0980171 0 -0.995185 -0.0980171 0 -0.995185 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707109 0 0.707105 -0.707109 0 0.707105 -0.258818 0 0.965926 -0.258818 0 0.965926 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258819 0 0.965926 -0.258819 0 0.965926 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707105 0 -0.707109 -0.707105 0 -0.707109 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.707105 0 0.707109 -0.707105 0 0.707109 -0.25882 0 0.965926 -0.25882 0 0.965926 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.186157 -0.694751 0.694742 -0.186155 -0.694755 0.694738 -0.508586 -0.694752 0.508586 -0.508583 -0.694755 0.508585 -0.694743 -0.69475 0.186157 -0.694747 -0.694747 0.186157 -0.694747 -0.694747 -0.186156 -0.694748 -0.694745 -0.186157 -0.508593 -0.694742 -0.508593 -0.508594 -0.694739 -0.508596 -0.186161 -0.694738 -0.694754 -0.18616 -0.694733 -0.694759 -0.258821 0 -0.965925 -0.258821 0 -0.965925 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258821 0 0.965925 -0.258821 0 0.965925 -0.18616 0.694741 -0.694751 -0.186156 0.694746 -0.694748 -0.50859 0.694746 -0.50859 -0.508592 0.694744 -0.508591 -0.694748 0.694745 -0.186157 -0.694747 0.694747 -0.186157 -0.694746 0.694746 0.186158 -0.694745 0.694748 0.186157 -0.508586 0.694752 0.508586 -0.508588 0.694747 0.508592 -0.186158 0.694746 0.694746 -0.18616 0.694751 0.694741 -0.186154 -0.694751 0.694743 -0.186156 -0.694748 0.694746 -0.508588 -0.694749 0.508588 -0.508588 -0.694749 0.508588 -0.694746 -0.694747 0.186155 -0.694743 -0.694751 0.186155 -0.694743 -0.694751 -0.186155 -0.694746 -0.694748 -0.186157 -0.508588 -0.694749 -0.508588 -0.508588 -0.694749 -0.508588 -0.186158 -0.694748 -0.694745 -0.186157 -0.694742 -0.694751 -0.258821 0 -0.965925 -0.258821 0 -0.965925 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965927 0 0.258816 -0.965927 0 0.258816 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258816 0 0.965927 -0.258816 0 0.965927 -0.186159 0.694741 -0.694751 -0.186156 0.694745 -0.694748 -0.508591 0.694744 -0.508591 -0.508591 0.694744 -0.508591 -0.694748 0.694745 -0.186156 -0.694747 0.694747 -0.186156 -0.694747 0.694747 0.186155 -0.694748 0.694745 0.186156 -0.508591 0.694744 0.508591 -0.508591 0.694744 0.508591 -0.186155 0.694745 0.694749 -0.186156 0.694747 0.694747 -0.159332 -0.698074 -0.698074 -0.159331 -0.698068 -0.698079 -0.330547 -0.706853 -0.625378 -0.479465 -0.639249 -0.601227 -0.465276 -0.700856 -0.540665 -0.585067 -0.706109 -0.398881 -0.722591 -0.597302 -0.347983 -0.661912 -0.703125 -0.259784 -0.716026 -0.698074 0 -0.91323 -0.394238 -0.102897 -0.704873 -0.704874 0.0794214 -0.645116 -0.698074 0.310672 -0.794014 -0.521948 0.311629 -0.585067 -0.706109 0.398881 -0.446438 -0.698068 0.559816 -0.159329 -0.698074 0.698074 -0.159333 -0.698069 0.698078 -0.330538 -0.706853 0.625382 -0.510845 -0.621816 0.593618 -0.222519 0 -0.974928 -0.258811 -0.00889465 -0.965887 -0.467296 0 -0.884101 -0.652284 0 -0.757974 -0.707029 -0.0148506 -0.707029 -0.826246 0 -0.563309 -0.930873 0 -0.365344 -0.965772 -0.0178356 -0.25878 -0.993712 0 -0.111966 -0.993712 0 0.111966 -0.965772 -0.0178355 0.25878 -0.930873 0 0.365343 -0.826246 0 0.563309 -0.707029 -0.0148506 0.707029 -0.652284 0 0.757974 -0.467284 0 0.884107 -0.258808 -0.00889412 0.965888 -0.222519 0 0.974928 -0.186158 0.694746 -0.694746 -0.186157 0.694748 -0.694745 -0.508586 0.694752 -0.508586 -0.508592 0.694747 -0.508588 -0.694746 0.694746 -0.186158 -0.694741 0.694751 -0.18616 -0.694741 0.694752 0.186157 -0.694746 0.694746 0.186162 -0.508591 0.694744 0.508591 -0.50859 0.69475 0.508586 -0.186157 0.694746 0.694748 -0.186157 0.694747 0.694747 -0.186154 0.694753 -0.69474 -0.186158 0.694745 -0.694748 -0.50859 0.694745 -0.508591 -0.508586 0.69475 -0.508589 -0.694745 0.694749 -0.186156 -0.694747 0.694747 -0.186156 -0.694747 0.694747 0.186157 -0.694745 0.694749 0.186156 -0.508589 0.69475 0.508586 -0.508591 0.694745 0.50859 -0.186156 0.694744 0.694749 -0.186156 0.69474 0.694753 -0.186157 0.694747 -0.694747 -0.186155 0.69475 -0.694743 -0.508589 0.694748 -0.508589 -0.508589 0.694748 -0.508589 -0.694743 0.69475 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694743 0.69475 0.186155 -0.508589 0.694748 0.508589 -0.508589 0.694748 0.508589 -0.186156 0.69475 0.694743 -0.186156 0.694747 0.694747 -0.186157 0.694747 -0.694747 -0.186156 0.694749 -0.694745 -0.508586 0.69475 -0.508589 -0.50859 0.694745 -0.508591 -0.694749 0.694744 -0.186156 -0.694753 0.69474 -0.186156 -0.694753 0.69474 0.186158 -0.694749 0.694744 0.186155 -0.50859 0.694745 0.508592 -0.508587 0.69475 0.508588 -0.186157 0.694749 0.694744 -0.186157 0.694747 0.694747 -0.159328 -0.698081 0.698068 -0.159332 -0.698072 0.698075 -0.446437 -0.698072 0.559812 -0.446433 -0.698077 0.559809 -0.645117 -0.698075 0.310671 -0.645113 -0.698078 0.31067 -0.716026 -0.698074 0 -0.716026 -0.698074 0 -0.645118 -0.698073 -0.310672 -0.645121 -0.698069 -0.310674 -0.446438 -0.698066 -0.559819 -0.446432 -0.698083 -0.559803 -0.159331 -0.698085 -0.698062 -0.159329 -0.698067 -0.69808 -0.222525 0 -0.974927 -0.222525 0 -0.974927 -0.623487 0 -0.781833 -0.623487 0 -0.781833 -0.90097 0 -0.433882 -0.90097 0 -0.433882 -1 0 0 -1 0 0 -0.90097 0 0.433882 -0.90097 0 0.433882 -0.623491 0 0.78183 -0.623491 0 0.78183 -0.222519 0 0.974928 -0.222519 0 0.974928 -0.159335 0.698069 -0.698078 -0.159331 0.698074 -0.698073 -0.446433 0.698074 -0.559813 -0.446436 0.698071 -0.559814 -0.645121 0.69807 -0.310673 -0.645118 0.698072 -0.310673 -0.716028 0.698072 0 -0.716028 0.698072 0 -0.645119 0.698072 0.310672 -0.64512 0.69807 0.310673 -0.446438 0.698071 0.559813 -0.446439 0.698067 0.559817 -0.159331 0.698065 0.698082 -0.159332 0.698069 0.698078 -0.186156 -0.69474 -0.694753 -0.186156 -0.694757 -0.694736 -0.508587 -0.694752 -0.508585 -0.592522 -0.41815 -0.688527 -0.585058 -0.706114 -0.398885 -0.661914 -0.703125 -0.25978 -0.846806 -0.481077 -0.2269 -0.704873 -0.704873 -0.0794222 -0.704873 -0.704873 0.0794222 -0.846806 -0.481079 0.2269 -0.186157 -0.694747 0.694747 -0.186158 -0.694744 0.694749 -0.465277 -0.700858 0.540662 -0.601349 -0.526076 0.601351 -0.585054 -0.706122 0.398877 -0.661909 -0.70313 0.259779 -0.222525 0 -0.974927 -0.258815 0.0071723 -0.9659 -0.623476 -0.00599256 -0.781819 -0.652285 0 -0.757974 -0.82624 0 -0.563319 -0.900929 -0.00960125 -0.433861 -0.930875 0 -0.365338 -0.993712 0 -0.111967 -0.999942 -0.0108066 0 -0.993712 0 0.111967 -0.930874 0 0.36534 -0.900929 -0.00960098 0.433861 -0.826243 0 0.563314 -0.623489 0 0.781832 -0.652271 -0.00717265 0.757952 -0.222514 0.00834229 0.974894 -0.258819 0 0.965926 -0.159335 0.698069 -0.698078 -0.159331 0.698074 -0.698073 -0.446433 0.698074 -0.559813 -0.446436 0.698071 -0.559814 -0.645121 0.69807 -0.310672 -0.645117 0.698074 -0.310672 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645117 0.698075 0.31067 -0.64512 0.69807 0.310673 -0.446436 0.698071 0.559814 -0.446436 0.698074 0.559811 -0.159331 0.698074 0.698073 -0.15933 0.698069 0.698078 -0.186157 -0.694747 0.694747 -0.186154 -0.694752 0.694742 -0.508585 -0.694753 0.508587 -0.508593 -0.694743 0.508591 -0.69475 -0.694743 0.186156 -0.69474 -0.694753 0.186156 -0.694741 -0.694754 -0.186153 -0.694749 -0.694744 -0.186158 -0.508592 -0.694742 -0.508594 -0.508587 -0.694752 -0.508585 -0.186156 -0.694752 -0.694741 -0.186156 -0.694747 -0.694747 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707105 0 -0.707108 -0.707105 0 -0.707108 -0.965927 0 -0.258816 -0.965927 0 -0.258816 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.707105 0 0.707108 -0.707105 0 0.707108 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.186157 0.694747 -0.694747 -0.186157 0.694748 -0.694746 -0.508587 0.694749 -0.508589 -0.508591 0.694745 -0.508591 -0.694748 0.694746 -0.186155 -0.694742 0.694751 -0.186156 -0.694743 0.694751 0.186154 -0.694747 0.694747 0.186157 -0.50859 0.694745 0.508592 -0.508588 0.694749 0.508588 -0.186157 0.694748 0.694745 -0.186157 0.694747 0.694747 -0.186157 -0.694747 -0.694747 -0.186157 -0.694749 -0.694744 -0.508588 -0.69475 -0.508587 -0.592519 -0.418165 -0.688519 -0.585056 -0.706114 -0.398888 -0.661917 -0.703122 -0.259779 -0.846802 -0.481084 -0.226901 -0.704867 -0.70488 -0.0794212 -0.704867 -0.70488 0.0794214 -0.846802 -0.481085 0.226901 -0.186157 -0.694747 0.694747 -0.186156 -0.694749 0.694745 -0.465273 -0.700865 0.540657 -0.601349 -0.52608 0.601348 -0.585056 -0.706114 0.398888 -0.661917 -0.703122 0.259779 -0.222522 0 -0.974928 -0.258813 0.00717237 -0.965901 -0.623478 -0.00599264 -0.781818 -0.652287 0 -0.757972 -0.826237 0 -0.563323 -0.900928 -0.00960165 -0.433862 -0.930876 0 -0.365336 -0.993712 0 -0.111967 -0.999942 -0.0108066 0 -0.993712 0 0.111967 -0.930876 0 0.365336 -0.900928 -0.00960165 0.433862 -0.826237 0 0.563323 -0.62349 0 0.781831 -0.652271 -0.0071724 0.757952 -0.222513 0.00834263 0.974894 -0.25882 0 0.965926 -0.159332 0.698071 -0.698076 -0.159331 0.698073 -0.698074 -0.446436 0.698071 -0.559814 -0.446434 0.698074 -0.559813 -0.645117 0.698074 -0.31067 -0.645118 0.698074 -0.31067 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645117 0.698075 0.31067 -0.645117 0.698074 0.31067 -0.446435 0.698074 0.559811 -0.446436 0.698069 0.559816 -0.159331 0.698071 0.698077 -0.159331 0.698071 0.698076 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.707109 0 -0.707105 -0.707109 0 -0.707105 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.258818 0 0.965926 -0.258818 0 0.965926 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.222519 0 -0.974928 -0.258776 0.0178263 -0.965773 -0.467265 0 -0.884117 -0.65229 0 -0.75797 -0.706795 0.0297575 -0.706792 -0.826238 0 -0.563321 -0.930874 0 -0.365341 -0.965309 0.0357356 -0.258655 -0.993712 0 -0.111966 -0.993712 0 0.111966 -0.965309 0.035736 0.258655 -0.930873 0 0.365342 -0.826241 0 0.563317 -0.706795 0.0297584 0.706792 -0.222522 0 0.974928 -0.258778 0.0178261 0.965772 -0.467265 0 0.884117 -0.652288 0 0.757972 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.222522 0 -0.974928 -0.222522 0 -0.974928 -0.623488 0 -0.781833 -0.623488 0 -0.781833 -0.900969 0 -0.433884 -0.900969 0 -0.433884 -1 0 0 -1 0 0 -0.900968 0 0.433885 -0.900968 0 0.433885 -0.623488 0 0.781833 -0.623488 0 0.781833 -0.222522 0 0.974928 -0.222522 0 0.974928 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.186162 -0.694733 0.694759 -0.186159 -0.694738 0.694755 -0.508595 -0.694739 0.508595 -0.508592 -0.694742 0.508594 -0.694748 -0.694745 0.186157 -0.694747 -0.694747 0.186157 -0.694747 -0.694747 -0.186156 -0.694748 -0.694745 -0.186157 -0.508593 -0.694742 -0.508593 -0.508594 -0.694739 -0.508596 -0.186155 -0.694737 -0.694757 -0.186156 -0.694751 -0.694742 -0.258813 0 -0.965928 -0.258813 0 -0.965928 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258821 0 0.965925 -0.258821 0 0.965925 -0.186151 0.694753 -0.694742 -0.186156 0.694746 -0.694748 -0.50859 0.694746 -0.50859 -0.508592 0.694744 -0.508591 -0.694748 0.694745 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186156 -0.694748 0.694745 0.186157 -0.508591 0.694744 0.508591 -0.508591 0.694746 0.50859 -0.186158 0.694746 0.694746 -0.186157 0.694741 0.694752 -0.186154 -0.694751 0.694743 -0.186156 -0.694748 0.694746 -0.508588 -0.694749 0.508588 -0.508594 -0.694742 0.508591 -0.694749 -0.694745 0.186155 -0.694742 -0.694751 0.186156 -0.694743 -0.694751 -0.186155 -0.694746 -0.694748 -0.186157 -0.508588 -0.694749 -0.508588 -0.508588 -0.694749 -0.508588 -0.186158 -0.694748 -0.694745 -0.186157 -0.694742 -0.694751 -0.258821 0 -0.965925 -0.258821 0 -0.965925 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965927 0 0.258816 -0.965927 0 0.258816 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258816 0 0.965927 -0.258816 0 0.965927 -0.186158 0.694746 -0.694746 -0.186159 0.694746 -0.694747 -0.508591 0.694744 -0.508591 -0.508587 0.694748 -0.50859 -0.694747 0.694747 -0.186156 -0.694747 0.694747 -0.186156 -0.694747 0.694747 0.186155 -0.694748 0.694745 0.186156 -0.508591 0.694744 0.508591 -0.508591 0.694744 0.508591 -0.186155 0.694745 0.694749 -0.186156 0.694747 0.694747 -0.186157 -0.694747 -0.694747 -0.186157 -0.69475 -0.694743 -0.508585 -0.694755 -0.508583 -0.572952 -0.477968 -0.665788 -0.585056 -0.706123 -0.398873 -0.694738 -0.694755 -0.186155 -0.883458 -0.315082 -0.346735 -0.704869 -0.704878 -0.0794205 -0.704869 -0.704878 0.0794206 -0.82055 -0.527595 0.219866 -0.186159 -0.694742 0.694751 -0.186157 -0.694746 0.694748 -0.46527 -0.700866 0.540658 -0.585052 -0.56163 0.585052 -0.585056 -0.706123 0.398873 -0.661905 -0.703133 0.259781 -0.222522 0 -0.974928 -0.258811 0.00889403 -0.965887 -0.623473 -0.00742974 -0.781809 -0.652284 0 -0.757974 -0.826246 0 -0.563309 -0.900906 -0.0119043 -0.433851 -0.930873 0 -0.365344 -0.993712 0 -0.111966 -0.99991 -0.0133996 0 -0.993712 0 0.111966 -0.930873 0 0.365344 -0.900906 -0.0119043 0.433851 -0.826246 0 0.563309 -0.62349 0 0.781831 -0.652259 -0.00889263 0.757944 -0.22251 0.0103446 0.974876 -0.258821 0 0.965925 -0.159331 0.698074 -0.698074 -0.159331 0.698074 -0.698074 -0.446435 0.698075 -0.55981 -0.446434 0.698075 -0.55981 -0.645117 0.698074 -0.31067 -0.645121 0.698072 -0.31067 -0.716028 0.698071 0 -0.716028 0.698071 0 -0.64512 0.698071 0.310671 -0.645119 0.698073 0.31067 -0.446436 0.698073 0.559812 -0.446436 0.698075 0.55981 -0.159331 0.698074 0.698074 -0.15933 0.698071 0.698076 -0.186154 0.694753 -0.69474 -0.186158 0.694745 -0.694748 -0.508592 0.694745 -0.50859 -0.508588 0.69475 -0.508587 -0.694744 0.694749 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186156 -0.694745 0.694749 0.186155 -0.508587 0.69475 0.508588 -0.50859 0.694745 0.508592 -0.186156 0.694744 0.694749 -0.186156 0.694753 0.69474 -0.15933 0.698074 0.698074 -0.159331 0.698078 0.698069 -0.33052 0.706864 0.62538 -0.494872 0.608293 0.620549 -0.465274 0.700864 0.540657 -0.585055 0.706119 0.398881 -0.758585 0.539532 0.365314 -0.661914 0.703124 0.259783 -0.704873 0.704873 0.0794211 -0.857931 0.513765 0 -0.704872 0.704874 -0.0794214 -0.645116 0.698076 -0.310671 -0.846744 0.415435 -0.332323 -0.585053 0.70612 -0.398884 -0.446434 0.698076 -0.55981 -0.15933 0.698074 -0.698074 -0.159331 0.698072 -0.698076 -0.330523 0.706858 -0.625385 -0.530283 0.582324 -0.616197 -0.159332 0.698074 -0.698074 -0.159331 0.698075 -0.698072 -0.446432 0.698075 -0.559812 -0.446436 0.698071 -0.559814 -0.645119 0.698072 -0.310673 -0.645123 0.698068 -0.310674 -0.716032 0.698067 0 -0.716032 0.698067 0 -0.645122 0.698068 0.310675 -0.645118 0.698073 0.310672 -0.446434 0.698074 0.559812 -0.446433 0.698075 0.559811 -0.159331 0.698075 0.698072 -0.159331 0.698074 0.698074 -0.186156 -0.694753 -0.69474 -0.186156 -0.694744 -0.694749 -0.50859 -0.694745 -0.508591 -0.592517 -0.418181 -0.688512 -0.585053 -0.706119 -0.398885 -0.661912 -0.703127 -0.259779 -0.846805 -0.481079 -0.226901 -0.70487 -0.704876 -0.07942 -0.70487 -0.704877 0.0794189 -0.846808 -0.481073 0.226901 -0.186161 -0.69474 0.694753 -0.186158 -0.694745 0.694748 -0.465274 -0.70086 0.540661 -0.601353 -0.526069 0.601354 -0.585057 -0.706119 0.398878 -0.661911 -0.703127 0.259781 -0.222519 0 -0.974928 -0.25881 0.00717246 -0.965902 -0.62348 -0.00599273 -0.781816 -0.65229 0 -0.75797 -0.826237 0 -0.563322 -0.900928 -0.00960145 -0.433862 -0.930875 0 -0.365338 -0.993712 0 -0.111965 -0.999942 -0.0108062 0 -0.993712 0 0.111963 -0.930874 0 0.365342 -0.900928 -0.00960089 0.433862 -0.826244 0 0.563313 -0.623487 0 0.781833 -0.652268 -0.00717255 0.757954 -0.222517 0.00834217 0.974893 -0.258822 0 0.965925 -0.15933 0.698069 -0.698078 -0.159327 0.698074 -0.698075 -0.446436 0.698074 -0.559811 -0.446438 0.698071 -0.559812 -0.645121 0.69807 -0.310673 -0.645118 0.698072 -0.310673 -0.716028 0.698072 0 -0.716028 0.698072 0 -0.645119 0.698072 0.310672 -0.64512 0.69807 0.310673 -0.446435 0.698071 0.559815 -0.446434 0.698074 0.559812 -0.159334 0.698074 0.698072 -0.159332 0.698069 0.698078 -0.18616 -0.69474 0.694753 -0.186158 -0.694744 0.694749 -0.508594 -0.694742 0.508592 -0.508585 -0.694752 0.508587 -0.694741 -0.694752 0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 -0.186157 -0.694744 -0.69475 -0.186155 -0.508589 -0.694748 -0.508589 -0.508589 -0.694748 -0.508589 -0.186156 -0.69475 -0.694743 -0.186156 -0.694747 -0.694747 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965925 0 0.25882 -0.965925 0 0.25882 -0.707108 0 0.707105 -0.707108 0 0.707105 -0.258822 0 0.965925 -0.258822 0 0.965925 -0.186157 0.694747 -0.694747 -0.186157 0.694746 -0.694747 -0.508591 0.694745 -0.508591 -0.508591 0.694745 -0.508591 -0.694747 0.694746 -0.186157 -0.694747 0.694747 -0.186157 -0.694746 0.694746 0.186158 -0.694745 0.694748 0.186157 -0.508589 0.694749 0.508587 -0.508591 0.694745 0.508591 -0.186159 0.694747 0.694746 -0.186158 0.694742 0.694751 -0.186157 -0.694747 0.694747 -0.186158 -0.694746 0.694747 -0.508589 -0.694748 0.508589 -0.508589 -0.694748 0.508589 -0.694748 -0.694745 0.186156 -0.69474 -0.694753 0.186156 -0.694741 -0.694753 -0.186154 -0.694747 -0.694746 -0.186158 -0.508589 -0.694748 -0.508589 -0.508589 -0.694748 -0.508589 -0.186156 -0.694745 -0.694748 -0.186156 -0.694753 -0.69474 -0.258817 0 -0.965926 -0.258817 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.186155 0.694747 -0.694747 -0.186158 0.694743 -0.69475 -0.508591 0.694745 -0.508591 -0.508591 0.694745 -0.508591 -0.694747 0.694746 -0.186155 -0.694742 0.694751 -0.186156 -0.694743 0.694751 0.186154 -0.694746 0.694748 0.186157 -0.508588 0.694749 0.508588 -0.508588 0.694749 0.508588 -0.186157 0.694748 0.694745 -0.186156 0.694742 0.694751 -0.159331 -0.698077 -0.69807 -0.15933 -0.698075 -0.698072 -0.330521 -0.706861 -0.625383 -0.486593 -0.625238 -0.610168 -0.465275 -0.700862 -0.540659 -0.585055 -0.706116 -0.398887 -0.739325 -0.571518 -0.356041 -0.661909 -0.703131 -0.259776 -0.704866 -0.70488 -0.0794211 -0.834019 -0.551736 0 -0.704866 -0.70488 0.0794214 -0.645111 -0.69808 0.31067 -0.819143 -0.47503 0.321484 -0.585058 -0.706114 0.398887 -0.446437 -0.698071 0.559813 -0.159331 -0.698074 0.698074 -0.15933 -0.698075 0.698073 -0.330527 -0.706861 0.62538 -0.519845 -0.604035 0.604072 -0.222521 0 -0.974928 -0.258812 -0.00717241 -0.965901 -0.467265 0 -0.884117 -0.652287 0 -0.757972 -0.707055 -0.0119759 -0.707057 -0.826237 0 -0.563323 -0.930876 0 -0.365336 -0.965827 -0.0143838 -0.25879 -0.993712 0 -0.111967 -0.993712 0 0.111967 -0.965826 -0.0143837 0.25879 -0.930876 0 0.365336 -0.826238 0 0.563321 -0.707055 -0.0119761 0.707057 -0.652286 0 0.757973 -0.467273 0 0.884113 -0.258813 -0.00717267 0.965901 -0.222521 0 0.974928 -0.186156 0.694747 -0.694747 -0.186157 0.694745 -0.694748 -0.508589 0.694747 -0.50859 -0.508597 0.694739 -0.508593 -0.694756 0.694737 -0.186157 -0.694751 0.694742 -0.186158 -0.694751 0.694742 0.186156 -0.694754 0.694738 0.186159 -0.508594 0.69474 0.508595 -0.508591 0.694748 0.508587 -0.186157 0.694748 0.694745 -0.186156 0.694744 0.694749 -0.258818 0 -0.965926 -0.222472 -0.0207331 -0.974719 -0.652184 0.0178264 -0.757851 -0.62349 0 -0.781831 -0.826237 0 -0.563322 -0.900712 0.0238604 -0.43376 -0.930874 0 -0.365341 -0.993712 0 -0.111966 -0.999639 0.0268536 0 -0.993712 0 0.111967 -0.930874 0 0.365341 -0.900713 0.0238596 0.433758 -0.826243 0 0.563314 -0.652288 0 0.757971 -0.623421 0.0148943 0.781744 -0.258777 -0.0178264 0.965773 -0.22252 0 0.974928 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.22252 0 -0.974928 -0.22252 0 -0.974928 -0.62349 0 -0.781832 -0.62349 0 -0.781832 -0.90097 0 -0.433882 -0.90097 0 -0.433882 -1 0 0 -1 0 0 -0.90097 0 0.433882 -0.90097 0 0.433882 -0.623488 0 0.781833 -0.623488 0 0.781833 -0.222523 0 0.974927 -0.222523 0 0.974927 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.707107 0 -0.707106 -0.707107 0 -0.707106 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.707107 0 0.707106 -0.707107 0 0.707106 -0.258818 0 0.965926 -0.258818 0 0.965926 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.159329 -0.698078 0.69807 -0.159331 -0.698074 0.698073 -0.446434 -0.698074 0.559812 -0.446443 -0.698064 0.559817 -0.645124 -0.698066 0.310674 -0.645116 -0.698074 0.310673 -0.716026 -0.698074 0 -0.716026 -0.698074 0 -0.645117 -0.698075 -0.31067 -0.645123 -0.698067 -0.310676 -0.44644 -0.698064 -0.55982 -0.446438 -0.698073 -0.55981 -0.15933 -0.698074 -0.698074 -0.159327 -0.698061 -0.698087 -0.222519 0 -0.974928 -0.222519 0 -0.974928 -0.623489 0 -0.781832 -0.623489 0 -0.781832 -0.90097 0 -0.433881 -0.90097 0 -0.433881 -1 0 0 -1 0 0 -0.90097 0 0.433881 -0.90097 0 0.433881 -0.623489 0 0.781832 -0.623489 0 0.781832 -0.222519 0 0.974928 -0.222519 0 0.974928 -0.159331 0.698068 -0.698079 -0.159331 0.698068 -0.69808 -0.446437 0.698069 -0.559816 -0.44644 0.698066 -0.559817 -0.645121 0.69807 -0.310672 -0.645114 0.698076 -0.310673 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645116 0.698076 0.310669 -0.645117 0.698075 0.310671 -0.446434 0.698075 0.559811 -0.446434 0.698069 0.559818 -0.159331 0.698068 0.69808 -0.159335 0.698078 0.698068 -0.159329 -0.698078 0.69807 -0.159332 -0.698073 0.698074 -0.446437 -0.698071 0.559813 -0.446434 -0.698074 0.559812 -0.645115 -0.698075 0.310673 -0.645116 -0.698074 0.310673 -0.716026 -0.698074 0 -0.716026 -0.698074 0 -0.645116 -0.698074 -0.310673 -0.645116 -0.698075 -0.310673 -0.446435 -0.698074 -0.559811 -0.446436 -0.698071 -0.559814 -0.159333 -0.698073 -0.698074 -0.159333 -0.698069 -0.698078 -0.222524 0 -0.974927 -0.222524 0 -0.974927 -0.62349 0 -0.781831 -0.62349 0 -0.781831 -0.900968 0 -0.433886 -0.900968 0 -0.433886 -1 0 0 -1 0 0 -0.900968 0 0.433886 -0.900968 0 0.433886 -0.62349 0 0.781831 -0.62349 0 0.781831 -0.222519 0 0.974928 -0.222519 0 0.974928 -0.159334 0.698068 -0.698078 -0.159331 0.698072 -0.698075 -0.446437 0.698071 -0.559813 -0.446433 0.698075 -0.559812 -0.645115 0.698075 -0.310673 -0.64512 0.698071 -0.310672 -0.716028 0.698071 0 -0.716028 0.698071 0 -0.645119 0.698071 0.310675 -0.645117 0.698075 0.310671 -0.446435 0.698075 0.55981 -0.446435 0.698072 0.559814 -0.15933 0.698072 0.698075 -0.15933 0.698074 0.698074 -0.186155 -0.694747 0.694747 -0.186158 -0.694741 0.694752 -0.508595 -0.694739 0.508595 -0.508595 -0.694739 0.508595 -0.694754 -0.694738 0.186161 -0.694759 -0.694733 0.18616 -0.694759 -0.694733 -0.186162 -0.694754 -0.694739 -0.186158 -0.508593 -0.694742 -0.508593 -0.508593 -0.694742 -0.508593 -0.186157 -0.694745 -0.694748 -0.186157 -0.694747 -0.694747 -0.222519 0 -0.974928 -0.258808 0.00889408 -0.965888 -0.46727 0 -0.884115 -0.652284 0 -0.757974 -0.707029 0.0148506 -0.707029 -0.826246 0 -0.563309 -0.930873 0 -0.365344 -0.965772 0.0178356 -0.25878 -0.993712 0 -0.111966 -0.993712 0 0.111966 -0.965772 0.0178355 0.25878 -0.930873 0 0.365343 -0.826246 0 0.563309 -0.707029 0.0148506 0.707029 -0.222519 0 0.974928 -0.258806 0.00889355 0.965888 -0.467257 0 0.884122 -0.652284 0 0.757974 -0.15933 0.698074 0.698074 -0.15933 0.698074 0.698074 -0.330516 0.70686 0.625386 -0.466042 0.664295 0.584395 -0.465278 0.700854 0.540667 -0.58507 0.706107 0.398883 -0.69096 0.641756 0.332752 -0.661914 0.703123 0.259784 -0.704875 0.704871 0.0794217 -0.773468 0.633836 0 -0.704875 0.704871 -0.0794213 -0.645119 0.698071 -0.310675 -0.744925 0.599675 -0.292364 -0.585068 0.706108 -0.398882 -0.44644 0.698068 -0.559815 -0.159329 0.698074 -0.698074 -0.15933 0.698074 -0.698074 -0.330525 0.70686 -0.625382 -0.493878 0.653239 -0.573902 -0.186157 0.69474 0.694753 -0.186156 0.694744 0.694749 -0.508591 0.694745 0.50859 -0.613017 0.341737 0.712338 -0.585057 0.706119 0.398879 -0.661911 0.703127 0.259781 -0.87576 0.421876 0.23466 -0.704873 0.704873 0.0794219 -0.704873 0.704873 -0.0794211 -0.875762 0.421872 -0.234659 -0.186154 0.694753 -0.69474 -0.186158 0.694745 -0.694748 -0.465276 0.70086 -0.54066 -0.619801 0.481341 -0.619804 -0.585053 0.706119 -0.398885 -0.661911 0.703127 -0.259781 -0.15933 0.698074 -0.698074 -0.159331 0.698072 -0.698076 -0.446436 0.698072 -0.559813 -0.446437 0.698071 -0.559813 -0.64512 0.698071 -0.310672 -0.645116 0.698076 -0.310671 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645119 0.698073 0.310671 -0.64512 0.698071 0.310672 -0.446435 0.698071 0.559815 -0.446433 0.698078 0.559808 -0.159331 0.698079 0.698069 -0.159331 0.698074 0.698074 -0.186156 0.694747 -0.694747 -0.186155 0.694749 -0.694745 -0.508588 0.69475 -0.508587 -0.508592 0.694745 -0.50859 -0.694749 0.694744 -0.186156 -0.69474 0.694753 -0.186156 -0.694741 0.694753 0.186154 -0.694748 0.694745 0.186158 -0.508591 0.694745 0.50859 -0.508589 0.69475 0.508586 -0.186156 0.694749 0.694745 -0.186156 0.694747 0.694747 -0.159328 -0.698081 0.698068 -0.159332 -0.698072 0.698075 -0.446438 -0.698072 0.559811 -0.446432 -0.698079 0.559808 -0.645114 -0.698078 0.31067 -0.645113 -0.698078 0.31067 -0.716026 -0.698074 0 -0.716026 -0.698074 0 -0.645118 -0.698073 -0.310673 -0.645119 -0.698072 -0.310673 -0.446437 -0.698068 -0.559817 -0.446432 -0.698083 -0.559803 -0.159331 -0.698085 -0.698062 -0.159329 -0.698067 -0.69808 -0.222525 0 -0.974927 -0.222525 0 -0.974927 -0.623488 0 -0.781833 -0.623488 0 -0.781833 -0.900969 0 -0.433884 -0.900969 0 -0.433884 -1 0 0 -1 0 0 -0.900969 0 0.433884 -0.900969 0 0.433884 -0.623492 0 0.78183 -0.623492 0 0.78183 -0.222519 0 0.974928 -0.222519 0 0.974928 -0.159335 0.698069 -0.698078 -0.159331 0.698074 -0.698073 -0.446434 0.698074 -0.559812 -0.446435 0.698072 -0.559813 -0.645118 0.698072 -0.310673 -0.645118 0.698072 -0.310673 -0.716028 0.698072 0 -0.716028 0.698072 0 -0.645118 0.698072 0.310673 -0.645118 0.698072 0.310672 -0.446437 0.698072 0.559811 -0.446439 0.698067 0.559817 -0.159331 0.698065 0.698082 -0.159332 0.698069 0.698078 -0.186157 -0.694747 0.694747 -0.186158 -0.694746 0.694747 -0.508589 -0.694748 0.508589 -0.508589 -0.694748 0.508589 -0.694748 -0.694745 0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 -0.186155 -0.694751 -0.694742 -0.186157 -0.508594 -0.694737 -0.508598 -0.508585 -0.694757 -0.508581 -0.186156 -0.694759 -0.694734 -0.186156 -0.69474 -0.694753 -0.258822 0 -0.965925 -0.258822 0 -0.965925 -0.707104 0 -0.70711 -0.707104 0 -0.70711 -0.965927 0 -0.258816 -0.965927 0 -0.258816 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.18616 0.694742 -0.69475 -0.186157 0.694747 -0.694746 -0.508588 0.694746 -0.508592 -0.508595 0.694739 -0.508595 -0.694753 0.694741 -0.186156 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186155 -0.69475 0.694743 0.186158 -0.508591 0.694745 0.508591 -0.508591 0.694745 0.508591 -0.186157 0.694747 0.694746 -0.186157 0.694742 0.694751 -0.186157 -0.694747 0.694747 -0.186155 -0.69475 0.694744 -0.508589 -0.694748 0.508589 -0.508589 -0.694748 0.508589 -0.694743 -0.69475 0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 -0.186157 -0.694744 -0.69475 -0.186155 -0.508589 -0.694748 -0.508589 -0.508589 -0.694748 -0.508589 -0.186156 -0.69475 -0.694743 -0.186156 -0.694747 -0.694747 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.186157 0.694747 -0.694747 -0.186157 0.694746 -0.694747 -0.508591 0.694745 -0.508591 -0.508591 0.694745 -0.508591 -0.694747 0.694746 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694747 0.694747 0.186157 -0.508591 0.694745 0.508591 -0.508591 0.694745 0.508591 -0.186157 0.694746 0.694747 -0.186157 0.694747 0.694747 -0.186157 -0.694747 0.694747 -0.186156 -0.694749 0.694745 -0.508587 -0.69475 0.508588 -0.508591 -0.694745 0.50859 -0.694748 -0.694745 0.18616 -0.694753 -0.69474 0.18616 -0.694753 -0.69474 -0.186161 -0.694748 -0.694745 -0.186158 -0.50859 -0.694745 -0.508591 -0.508588 -0.69475 -0.508587 -0.186157 -0.694749 -0.694744 -0.186157 -0.694747 -0.694747 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707106 0 -0.707108 -0.707106 0 -0.707108 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.707106 0 0.707108 -0.707106 0 0.707108 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.186158 0.694744 -0.694749 -0.186157 0.694745 -0.694748 -0.508589 0.694747 -0.50859 -0.508589 0.694747 -0.50859 -0.694745 0.694747 -0.186159 -0.694751 0.694742 -0.186158 -0.69475 0.694742 0.18616 -0.694746 0.694747 0.186157 -0.508589 0.694747 0.50859 -0.508589 0.694747 0.50859 -0.186158 0.694746 0.694748 -0.186157 0.694744 0.694749 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.707109 0 -0.707105 -0.707109 0 -0.707105 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.258818 0 0.965926 -0.258818 0 0.965926 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.707108 0 -0.707106 -0.707108 0 -0.707106 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707108 0 0.707106 -0.707108 0 0.707106 -0.25882 0 0.965926 -0.25882 0 0.965926 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.222521 0 -0.974928 -0.258777 0.0178262 -0.965773 -0.467265 0 -0.884117 -0.652289 0 -0.757971 -0.706794 0.0297576 -0.706793 -0.826238 0 -0.563321 -0.930874 0 -0.365341 -0.965309 0.0357365 -0.258652 -0.993713 0 -0.111961 -0.993713 0 0.111961 -0.965309 0.0357365 0.258653 -0.930874 0 0.365342 -0.826238 0 0.563321 -0.706794 0.0297576 0.706793 -0.222521 0 0.974928 -0.258778 0.0178267 0.965772 -0.467272 0 0.884114 -0.652289 0 0.757971 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.15933 -0.698078 -0.698069 -0.15933 -0.698074 -0.698074 -0.330503 -0.70686 -0.625393 -0.479469 -0.639236 -0.601238 -0.465275 -0.700866 -0.540653 -0.585051 -0.706118 -0.398889 -0.722599 -0.597292 -0.347983 -0.661919 -0.703119 -0.259784 -0.704875 -0.704872 -0.0794208 -0.813132 -0.582079 0 -0.704873 -0.704874 0.0794206 -0.645116 -0.698074 0.310673 -0.79402 -0.521939 0.311629 -0.585051 -0.706118 0.398889 -0.446431 -0.698078 0.55981 -0.15934 -0.69806 0.698086 -0.159331 -0.698074 0.698073 -0.330503 -0.70686 0.625393 -0.510859 -0.621799 0.593623 -0.222519 0 -0.974928 -0.258802 -0.00889262 -0.965889 -0.467239 0 -0.884131 -0.652291 0 -0.757968 -0.707029 -0.0148488 -0.707029 -0.826233 0 -0.563328 -0.930874 0 -0.365341 -0.965772 -0.0178354 -0.258777 -0.993712 0 -0.111965 -0.993712 0 0.111965 -0.965772 -0.0178354 0.258777 -0.930874 0 0.365341 -0.826233 0 0.563328 -0.707029 -0.0148488 0.707029 -0.652291 0 0.757968 -0.467239 0 0.884131 -0.258811 -0.00889227 0.965887 -0.222529 0 0.974926 -0.186151 0.694753 -0.694742 -0.186156 0.694746 -0.694748 -0.50859 0.694746 -0.50859 -0.508592 0.694744 -0.508591 -0.694748 0.694745 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186156 -0.694748 0.694745 0.186157 -0.508591 0.694744 0.508591 -0.508591 0.694746 0.50859 -0.186158 0.694746 0.694746 -0.186157 0.694741 0.694752 -0.186155 -0.694751 0.694743 -0.186157 -0.694748 0.694746 -0.508588 -0.694749 0.508588 -0.508594 -0.694742 0.508591 -0.694747 -0.694745 0.186158 -0.694751 -0.694742 0.186158 -0.69475 -0.694742 -0.18616 -0.694746 -0.694748 -0.186157 -0.508588 -0.694749 -0.508588 -0.508588 -0.694749 -0.508588 -0.186159 -0.694748 -0.694745 -0.186158 -0.694742 -0.694751 -0.258822 0 -0.965925 -0.258822 0 -0.965925 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258818 0 0.965926 -0.258818 0 0.965926 -0.186159 0.694746 -0.694746 -0.186158 0.694747 -0.694746 -0.508589 0.694748 -0.508589 -0.508589 0.694748 -0.508589 -0.694746 0.694747 -0.186159 -0.694752 0.694741 -0.186157 -0.694751 0.694741 0.186159 -0.694748 0.694745 0.186156 -0.508591 0.694744 0.508591 -0.50859 0.694748 0.508587 -0.186156 0.694747 0.694747 -0.186156 0.694747 0.694747 -0.186158 -0.694742 0.694751 -0.186158 -0.694741 0.694752 -0.508595 -0.694739 0.508595 -0.508595 -0.694739 0.508595 -0.694754 -0.694738 0.186161 -0.694759 -0.694733 0.18616 -0.694759 -0.694733 -0.186162 -0.694755 -0.694738 -0.186159 -0.508595 -0.694739 -0.508595 -0.508594 -0.694742 -0.508592 -0.186157 -0.694745 -0.694748 -0.186157 -0.694747 -0.694747 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.186156 0.694747 -0.694747 -0.186157 0.694745 -0.694748 -0.508591 0.694744 -0.508591 -0.50859 0.694746 -0.508591 -0.694746 0.694746 -0.186158 -0.694752 0.694741 -0.186157 -0.694751 0.694741 0.18616 -0.694748 0.694746 0.186156 -0.50859 0.694746 0.50859 -0.508591 0.694744 0.508592 -0.186157 0.694745 0.694748 -0.186156 0.694744 0.694749 -0.186154 0.694753 -0.69474 -0.186158 0.694745 -0.694748 -0.508592 0.694745 -0.50859 -0.508588 0.69475 -0.508587 -0.694744 0.694749 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694745 0.694749 0.186156 -0.508587 0.69475 0.508588 -0.50859 0.694745 0.508592 -0.186156 0.694744 0.694749 -0.186156 0.694753 0.69474 -0.186156 0.694747 -0.694747 -0.186157 0.694744 -0.694749 -0.508593 0.694743 -0.508592 -0.508589 0.694748 -0.508589 -0.694743 0.69475 -0.186157 -0.694747 0.694747 -0.186157 -0.694746 0.694746 0.186158 -0.694742 0.694752 0.186155 -0.508587 0.694753 0.508585 -0.508592 0.694743 0.508593 -0.186158 0.694744 0.694749 -0.186158 0.694746 0.694746 -0.15933 0.698074 0.698074 -0.15933 0.698075 0.698072 -0.330526 0.706861 0.62538 -0.494873 0.608292 0.620549 -0.465275 0.700862 0.540658 -0.585056 0.706116 0.398886 -0.758586 0.539528 0.365319 -0.661907 0.703131 0.25978 -0.704867 0.70488 0.0794166 -0.857917 0.513788 0 -0.704867 0.70488 -0.0794166 -0.645111 0.69808 -0.310672 -0.84675 0.415422 -0.332325 -0.585058 0.706114 -0.398887 -0.446437 0.698071 -0.559812 -0.159331 0.698074 -0.698074 -0.15933 0.698075 -0.698073 -0.330521 0.706861 -0.625383 -0.53028 0.582329 -0.616195 -0.186156 -0.694753 -0.69474 -0.186156 -0.694744 -0.694749 -0.508591 -0.694745 -0.508591 -0.592517 -0.418183 -0.688511 -0.585054 -0.706116 -0.398889 -0.661915 -0.703124 -0.25978 -0.846808 -0.481073 -0.226901 -0.704873 -0.704873 -0.0794204 -0.704873 -0.704873 0.0794193 -0.846812 -0.481067 0.226902 -0.186161 -0.69474 0.694753 -0.186158 -0.694745 0.694748 -0.465275 -0.70086 0.540661 -0.601353 -0.52607 0.601353 -0.585058 -0.706116 0.398882 -0.661914 -0.703124 0.259783 -0.222519 0 -0.974928 -0.25881 0.00717246 -0.965902 -0.623481 -0.00599276 -0.781816 -0.652291 0 -0.757969 -0.826235 0 -0.563326 -0.900927 -0.00960164 -0.433864 -0.930875 0 -0.365338 -0.993712 0 -0.111965 -0.999942 -0.0108062 0 -0.993712 0 0.111963 -0.930874 0 0.365342 -0.900927 -0.00960108 0.433864 -0.826241 0 0.563316 -0.623488 0 0.781833 -0.652269 -0.00717259 0.757953 -0.222517 0.00834217 0.974893 -0.258822 0 0.965925 -0.15933 0.698069 -0.698078 -0.159327 0.698074 -0.698075 -0.446437 0.698073 -0.55981 -0.446438 0.698073 -0.559811 -0.645118 0.698072 -0.310673 -0.645118 0.698072 -0.310673 -0.716028 0.698072 0 -0.716028 0.698072 0 -0.645118 0.698072 0.310673 -0.645118 0.698072 0.310672 -0.446435 0.698072 0.559814 -0.446434 0.698074 0.559812 -0.159334 0.698074 0.698072 -0.159332 0.698069 0.698078 -0.159336 -0.698067 0.69808 -0.159333 -0.698072 0.698075 -0.446434 -0.698073 0.559814 -0.44644 -0.698066 0.559818 -0.645121 -0.698069 0.310674 -0.645118 -0.698072 0.310674 -0.716026 -0.698074 0 -0.716026 -0.698074 0 -0.645118 -0.698072 -0.310674 -0.645116 -0.698075 -0.310672 -0.446433 -0.698077 -0.55981 -0.446432 -0.698078 -0.559809 -0.159331 -0.698079 -0.698069 -0.15933 -0.698074 -0.698074 -0.222522 0 -0.974928 -0.222522 0 -0.974928 -0.623489 0 -0.781832 -0.623489 0 -0.781832 -0.900968 0 -0.433885 -0.900968 0 -0.433885 -1 0 0 -1 0 0 -0.900969 0 0.433884 -0.900969 0 0.433884 -0.623487 0 0.781833 -0.623487 0 0.781833 -0.222526 0 0.974927 -0.222526 0 0.974927 -0.159332 0.698074 -0.698074 -0.159331 0.698074 -0.698073 -0.446435 0.698074 -0.559812 -0.446437 0.698071 -0.559813 -0.645119 0.698071 -0.310674 -0.645122 0.698068 -0.310674 -0.71603 0.69807 0 -0.71603 0.69807 0 -0.64512 0.69807 0.310674 -0.64512 0.69807 0.310673 -0.446435 0.698071 0.559815 -0.446434 0.698074 0.559812 -0.159334 0.698074 0.698072 -0.159333 0.698069 0.698078 -0.186157 -0.694747 0.694747 -0.186158 -0.694744 0.694749 -0.508594 -0.694742 0.508592 -0.508585 -0.694752 0.508587 -0.694741 -0.694752 0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 -0.186157 -0.694742 -0.694752 -0.186154 -0.508587 -0.694753 -0.508585 -0.508591 -0.694743 -0.508593 -0.186156 -0.694743 -0.69475 -0.186156 -0.694753 -0.69474 -0.258816 0 -0.965927 -0.258816 0 -0.965927 -0.707108 0 -0.707105 -0.707108 0 -0.707105 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707108 0 0.707105 -0.707108 0 0.707105 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.186155 0.694747 -0.694747 -0.186158 0.694742 -0.694751 -0.508594 0.694742 -0.508592 -0.508591 0.694745 -0.508591 -0.694746 0.694747 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694746 0.694748 0.186157 -0.508589 0.694749 0.508587 -0.508591 0.694745 0.508591 -0.186157 0.694746 0.694747 -0.186156 0.694742 0.694751 -0.186156 -0.69475 -0.694744 -0.186156 -0.694749 -0.694745 -0.508588 -0.69475 -0.508587 -0.592519 -0.418165 -0.688519 -0.585056 -0.706114 -0.398888 -0.661914 -0.703123 -0.259785 -0.846815 -0.48106 -0.226904 -0.70488 -0.704867 -0.0794227 -0.70488 -0.704866 0.0794229 -0.846814 -0.481061 0.226904 -0.186157 -0.694747 0.694747 -0.186156 -0.694749 0.694745 -0.465272 -0.700865 0.540657 -0.601349 -0.526078 0.601349 -0.585056 -0.706116 0.398885 -0.661913 -0.703124 0.259784 -0.222521 0 -0.974928 -0.258812 0.00717241 -0.965901 -0.623478 -0.00599264 -0.781818 -0.652287 0 -0.757972 -0.826237 0 -0.563323 -0.900926 -0.00960126 -0.433867 -0.930872 0 -0.365344 -0.993712 0 -0.111967 -0.999942 -0.0108066 0 -0.993712 0 0.111967 -0.930872 0 0.365344 -0.900926 -0.00960117 0.433867 -0.826238 0 0.563321 -0.623489 0 0.781832 -0.65227 -0.00717235 0.757953 -0.222513 0.00834263 0.974894 -0.25882 0 0.965926 -0.159331 0.698074 -0.698074 -0.159331 0.698073 -0.698074 -0.446434 0.698075 -0.559811 -0.446435 0.698074 -0.559812 -0.645115 0.698075 -0.310674 -0.645117 0.698073 -0.310674 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645116 0.698074 0.310674 -0.645115 0.698075 0.310673 -0.446435 0.698074 0.559812 -0.446434 0.698075 0.559811 -0.159331 0.698073 0.698075 -0.159331 0.698072 0.698076 -0.0584923 0.705893 -0.705899 -0.218117 0.45885 -0.861325 -0.14517 0.706807 -0.692351 -0.0584923 0.705899 -0.705894 -0.347741 0.707051 -0.615756 -0.284526 0.705898 -0.648655 -0.284526 0.705899 -0.648654 -0.224578 0.707099 -0.670504 -0.205543 0.673714 -0.709832 -0.410758 0.623996 -0.66476 -0.48576 0.459596 -0.743511 -0.410985 0.704457 -0.578646 -0.529644 0.662731 -0.5294 -0.562358 0.577951 -0.591377 -0.601753 0.45891 -0.653678 -0.456897 0.706812 -0.540057 -0.434012 0.707106 -0.558242 -0.512295 0.707057 -0.487467 -0.558961 0.705895 -0.435057 -0.558962 0.705894 -0.435058 -0.65539 0.674972 -0.338935 -0.753168 0.516338 -0.407594 -0.608108 0.699963 -0.374509 -0.593096 0.707103 -0.385023 -0.681252 0.707005 0.189844 -0.698657 0.705894 0.116585 -0.698654 0.705898 0.116585 -0.708314 0.705897 0 -0.708314 0.705898 0 -0.698654 0.705897 -0.116584 -0.698657 0.705894 -0.116585 -0.676578 0.706682 -0.206986 -0.834878 0.469927 -0.286614 -0.656968 0.706905 -0.262068 -0.646117 0.707102 -0.287298 -0.788007 0.557278 0.261699 -0.834877 0.469928 0.286614 -0.656967 0.706905 0.262067 -0.753167 0.516341 0.407594 -0.655389 0.674973 0.338934 -0.646116 0.707103 0.287297 -0.512294 0.707059 0.487466 -0.55896 0.705897 0.435056 -0.558963 0.705893 0.435058 -0.593096 0.707103 0.385023 -0.608108 0.699963 0.374508 -0.453542 0.706894 0.542771 -0.576332 0.514193 0.635175 -0.601754 0.458908 0.653679 -0.562355 0.577957 0.591373 -0.529643 0.662733 0.529399 -0.348445 0.706204 0.616329 -0.410758 0.623996 0.66476 -0.48576 0.459596 0.743511 -0.410985 0.704457 0.578646 -0.434012 0.707106 0.558242 -0.336829 0.707108 0.621727 -0.284526 0.705898 0.648655 -0.284528 0.705894 0.648658 -0.201849 0.706803 0.678002 -0.218117 0.45885 0.861325 -0.145172 0.706803 0.692355 -0.0584925 0.705894 0.705898 -0.058492 0.705897 0.705895 -0.0694756 0.705398 -0.705398 -0.0694758 0.705395 -0.705401 -0.205758 0.705395 -0.678293 -0.205757 0.705397 -0.678291 -0.334132 0.705397 -0.625116 -0.334131 0.705398 -0.625116 -0.449665 0.705398 -0.547919 -0.449667 0.705395 -0.547921 -0.547922 0.705394 -0.449668 -0.547919 0.705398 -0.449665 -0.625116 0.705398 -0.334131 -0.625116 0.705397 -0.334132 -0.678291 0.705397 -0.205757 -0.678292 0.705396 -0.205758 -0.705401 0.705396 -0.0694761 -0.705392 0.705405 -0.0694749 -0.705392 0.705405 0.0694752 -0.705401 0.705395 0.0694758 -0.678292 0.705396 0.205758 -0.678292 0.705396 0.205758 -0.625118 0.705396 0.334132 -0.625116 0.705398 0.334132 -0.547919 0.705398 0.449665 -0.547918 0.705399 0.449664 -0.449664 0.705399 0.547918 -0.449665 0.705398 0.547919 -0.334131 0.705398 0.625116 -0.334132 0.705397 0.625116 -0.205758 0.705397 0.678291 -0.205756 0.705401 0.678287 -0.0694753 0.705402 0.705394 -0.0694758 0.705398 0.705398 -0.222524 0 -0.974927 -0.258815 0.00571967 -0.96591 -0.62348 -0.00477997 -0.781825 -0.65229 0 -0.757969 -0.826247 0 -0.563309 -0.900942 -0.00765629 -0.433872 -0.93087 0 -0.36535 -0.993713 0 -0.111955 -0.999963 -0.00861752 0 -0.993713 0 0.111956 -0.930871 0 0.365347 -0.900943 -0.0076564 0.43387 -0.826247 0 0.563309 -0.623487 0 0.781834 -0.652276 -0.00572053 0.75796 -0.222514 0.00665358 0.974907 -0.258819 0 0.965926 -0.222518 0 -0.974929 -0.222518 0 -0.974929 -0.623493 0 -0.781829 -0.623493 0 -0.781829 -0.900968 0 -0.433885 -0.900968 0 -0.433885 -1 0 0 -1 0 0 -0.900968 0 0.433885 -0.900968 0 0.433885 -0.623487 0 0.781834 -0.623487 0 0.781834 -0.222527 0 0.974927 -0.222527 0 0.974927 -0.222527 0 -0.974927 -0.258816 0.0057193 -0.96591 -0.62348 -0.00477958 -0.781825 -0.652287 0 -0.757972 -0.82624 0 -0.563319 -0.900942 -0.00765699 -0.433872 -0.930873 0 -0.365343 -0.993713 0 -0.111954 -0.999963 -0.00861752 0 -0.993713 0 0.111956 -0.930873 0 0.365343 -0.900942 -0.00765699 0.433872 -0.82624 0 0.563319 -0.623487 0 0.781834 -0.652277 -0.00572072 0.757959 -0.222522 0.00665219 0.974905 -0.25882 0 0.965926 -0.222524 0 -0.974927 -0.258815 0.00571967 -0.96591 -0.62348 -0.00477997 -0.781825 -0.65229 0 -0.757969 -0.826247 0 -0.563309 -0.900942 -0.00765629 -0.433872 -0.93087 0 -0.36535 -0.993713 0 -0.111955 -0.999963 -0.00861752 0 -0.993713 0 0.111955 -0.93087 0 0.36535 -0.900942 -0.00765629 0.433872 -0.826247 0 0.563309 -0.623487 0 0.781834 -0.65228 -0.00572124 0.757957 -0.222514 0.00665282 0.974907 -0.258815 0 0.965927 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.70711 0 -0.707104 -0.70711 0 -0.707104 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.70711 0 0.707104 -0.70711 0 0.707104 -0.258818 0 0.965926 -0.258818 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707111 0 -0.707102 -0.707111 0 -0.707102 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707111 0 0.707102 -0.707111 0 0.707102 -0.258815 0 0.965927 -0.258815 0 0.965927 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707111 0 -0.707102 -0.707111 0 -0.707102 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707109 0 0.707105 -0.707109 0 0.707105 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.70711 0 -0.707104 -0.70711 0 -0.707104 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.70711 0 0.707104 -0.70711 0 0.707104 -0.258818 0 0.965926 -0.258818 0 0.965926 -0.0584918 -0.705903 0.70589 -0.0584917 -0.705904 0.705888 -0.173879 -0.705904 0.686634 -0.173881 -0.705895 0.686642 -0.284527 -0.705895 0.648657 -0.284528 -0.705894 0.648658 -0.387413 -0.705894 0.59298 -0.387408 -0.705903 0.592972 -0.479725 -0.705902 0.52112 -0.479726 -0.7059 0.521121 -0.558957 -0.7059 0.435054 -0.558964 -0.705891 0.435059 -0.62295 -0.705891 0.337124 -0.622939 -0.705902 0.337118 -0.669931 -0.705902 0.229988 -0.669938 -0.705895 0.22999 -0.698656 -0.705895 0.116585 -0.698652 -0.705899 0.116584 -0.708313 -0.705899 0 -0.708313 -0.705899 0 -0.698653 -0.705898 -0.116584 -0.698657 -0.705894 -0.116585 -0.669939 -0.705894 -0.22999 -0.669933 -0.7059 -0.229988 -0.622943 -0.705899 -0.33712 -0.62295 -0.70589 -0.337124 -0.558964 -0.705891 -0.435059 -0.558961 -0.705896 -0.435057 -0.479729 -0.705896 -0.521125 -0.479725 -0.705902 -0.52112 -0.387408 -0.705903 -0.592972 -0.387413 -0.705894 -0.59298 -0.284528 -0.705894 -0.648659 -0.284527 -0.705896 -0.648657 -0.173881 -0.705895 -0.686642 -0.173879 -0.705904 -0.686633 -0.0584913 -0.705904 -0.705888 -0.058493 -0.705889 -0.705903 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0825795 0 0.996584 -0.0825795 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401695 0 0.915773 -0.401695 0 0.915773 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475948 -0.879474 0 0.475948 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.986361 0 0.164595 -0.986361 0 0.164595 -1 0 0 -1 0 0 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.879474 0 -0.475948 -0.879474 0 -0.475948 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.401695 0 -0.915773 -0.401695 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.082579 0 -0.996585 -0.082579 0 -0.996585 -0.0825795 0 0.996584 -0.0825795 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401695 0 0.915773 -0.401695 0 0.915773 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475948 -0.879474 0 0.475948 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.986361 0 0.164595 -0.986361 0 0.164595 -1 0 0 -1 0 0 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.879474 0 -0.475948 -0.879474 0 -0.475948 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.401695 0 -0.915773 -0.401695 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.082579 0 -0.996585 -0.082579 0 -0.996585 -0.0825795 0 0.996584 -0.0825795 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401695 0 0.915773 -0.401695 0 0.915773 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475948 -0.879474 0 0.475948 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.986361 0 0.164595 -0.986361 0 0.164595 -1 0 0 -1 0 0 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.879474 0 -0.475948 -0.879474 0 -0.475948 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.401695 0 -0.915773 -0.401695 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.082579 0 -0.996585 -0.082579 0 -0.996585 -0.0825795 0 0.996584 -0.0825795 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401695 0 0.915773 -0.401695 0 0.915773 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475948 -0.879474 0 0.475948 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.986361 0 0.164595 -0.986361 0 0.164595 -1 0 0 -1 0 0 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.879474 0 -0.475948 -0.879474 0 -0.475948 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.401695 0 -0.915773 -0.401695 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.082579 0 -0.996585 -0.082579 0 -0.996585 -0.0825795 0 0.996584 -0.0825795 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401695 0 0.915773 -0.401695 0 0.915773 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475948 -0.879474 0 0.475948 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.986361 0 0.164595 -0.986361 0 0.164595 -1 0 0 -1 0 0 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.879474 0 -0.475948 -0.879474 0 -0.475948 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.401695 0 -0.915773 -0.401695 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.082579 0 -0.996585 -0.082579 0 -0.996585 -0.0825795 0 0.996584 -0.0825795 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401695 0 0.915773 -0.401695 0 0.915773 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475948 -0.879474 0 0.475948 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.986361 0 0.164595 -0.986361 0 0.164595 -1 0 0 -1 0 0 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.879474 0 -0.475948 -0.879474 0 -0.475948 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.401695 0 -0.915773 -0.401695 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.082579 0 -0.996585 -0.082579 0 -0.996585 -0.0825795 0 0.996584 -0.0825795 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401695 0 0.915773 -0.401695 0 0.915773 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475948 -0.879474 0 0.475948 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.986361 0 0.164595 -0.986361 0 0.164595 -1 0 0 -1 0 0 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.879474 0 -0.475948 -0.879474 0 -0.475948 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.401695 0 -0.915773 -0.401695 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.082579 0 -0.996585 -0.082579 0 -0.996585 -0.0825795 0 0.996584 -0.0825795 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401695 0 0.915773 -0.401695 0 0.915773 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475948 -0.879474 0 0.475948 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.986361 0 0.164595 -0.986361 0 0.164595 -1 0 0 -1 0 0 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.879474 0 -0.475948 -0.879474 0 -0.475948 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.401695 0 -0.915773 -0.401695 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.082579 0 -0.996585 -0.082579 0 -0.996585 -0.0825795 0 0.996584 -0.0825795 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401695 0 0.915773 -0.401695 0 0.915773 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475948 -0.879474 0 0.475948 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.986361 0 0.164595 -0.986361 0 0.164595 -1 0 0 -1 0 0 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.879474 0 -0.475948 -0.879474 0 -0.475948 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.401695 0 -0.915773 -0.401695 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.082579 0 -0.996585 -0.082579 0 -0.996585 -0.0825795 0 0.996585 -0.0825795 0 0.996585 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401695 0 0.915773 -0.401695 0 0.915773 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475948 -0.879474 0 0.475948 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.986361 0 0.164595 -0.986361 0 0.164595 -1 0 0 -1 0 0 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.879474 0 -0.475948 -0.879474 0 -0.475948 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.401695 0 -0.915773 -0.401695 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.082579 0 -0.996585 -0.082579 0 -0.996585 0.926037 0 0.377433 0.926037 0 0.377433 0.842364 0 0.538909 0.842364 0 0.538909 0.730829 0 0.68256 0.730829 0 0.68256 0.595121 0 0.803636 0.595121 0 0.803636 0.43973 0 0.89813 0.43973 0 0.89813 0.269794 0 0.962918 0.269794 0 0.962918 0.0909337 0 0.995857 0.0909337 0 0.995857 -0.92337 0 -0.38391 -0.92337 0 -0.38391 -0.830854 0 -0.55649 -0.830854 0 -0.55649 -0.70648 0 -0.707733 -0.70648 0 -0.707733 -0.555018 0 -0.831838 -0.555018 0 -0.831838 -0.382275 0 -0.924049 -0.382275 0 -0.924049 -0.194873 0 -0.980828 -0.194873 0 -0.980828 0 0 -1 0 0 -1 0.194873 0 -0.980828 0.194873 0 -0.980828 0.382275 0 -0.924049 0.382275 0 -0.924049 0.555018 0 -0.831838 0.555018 0 -0.831838 0.70648 0 -0.707733 0.70648 0 -0.707733 0.830854 0 -0.55649 0.830854 0 -0.55649 0.92337 0 -0.38391 0.92337 0 -0.38391 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.222525 0 -0.974927 -0.258822 0.00161869 -0.965924 -0.623487 -0.00135243 -0.781833 -0.652285 0 -0.757974 -0.826244 0 -0.563313 -0.900967 -0.00216683 -0.433881 -0.930873 0 -0.365342 -0.993712 0 -0.111963 -0.999997 -0.0024389 0 -0.993712 0 0.111965 -0.930875 0 0.365338 -0.900967 -0.00216696 0.433881 -0.826237 0 0.563322 -0.623491 0 0.78183 -0.652289 -0.00161879 0.757969 -0.222518 0.00188278 0.974927 -0.258817 0 0.965926 -0.159334 0.698071 -0.698075 -0.159331 0.698076 -0.698071 -0.446432 0.698076 -0.559811 -0.446435 0.698073 -0.559813 -0.645119 0.698073 -0.310672 -0.645116 0.698075 -0.310672 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645117 0.698075 0.310671 -0.645118 0.698073 0.310672 -0.446436 0.698073 0.559811 -0.446437 0.698069 0.559816 -0.159331 0.698067 0.69808 -0.159332 0.698071 0.698076 -0.258822 0 -0.965925 -0.258822 0 -0.965925 -0.707105 0 -0.707108 -0.707105 0 -0.707108 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707108 0 0.707105 -0.707108 0 0.707105 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.186159 0.694744 -0.694748 -0.186156 0.694749 -0.694745 -0.508588 0.694748 -0.50859 -0.508591 0.694744 -0.508591 -0.694746 0.694748 -0.186157 -0.694744 0.694749 -0.186157 -0.694744 0.694749 0.186157 -0.694744 0.69475 0.186156 -0.508588 0.694751 0.508586 -0.508589 0.694748 0.508589 -0.186156 0.694749 0.694745 -0.186156 0.694745 0.694749 -0.222522 0 -0.974928 -0.258819 -0.00161871 -0.965924 -0.467265 0 -0.884117 -0.652287 0 -0.757972 -0.707103 -0.00270287 -0.707106 -0.826235 0 -0.563326 -0.930876 0 -0.365336 -0.965921 -0.00324648 -0.258815 -0.993712 0 -0.111967 -0.993712 0 0.111967 -0.965921 -0.00324645 0.258816 -0.930876 0 0.365336 -0.826235 0 0.563326 -0.707103 -0.00270287 0.707106 -0.652287 0 0.757972 -0.467281 0 0.884109 -0.258819 -0.00161885 0.965924 -0.222519 0 0.974928 -0.186157 0.694749 -0.694744 -0.186156 0.69475 -0.694744 -0.508586 0.694751 -0.508588 -0.508589 0.694748 -0.508589 -0.694745 0.694748 -0.186154 -0.69474 0.694753 -0.186155 -0.694741 0.694753 0.186154 -0.694744 0.694749 0.186157 -0.508588 0.694747 0.50859 -0.508587 0.694751 0.508587 -0.186156 0.69475 0.694743 -0.186156 0.694749 0.694745 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.186157 0.694747 -0.694747 -0.186157 0.694748 -0.694746 -0.508587 0.694749 -0.508588 -0.508594 0.694743 -0.508591 -0.694753 0.69474 -0.186157 -0.694749 0.694744 -0.186157 -0.694749 0.694745 0.186156 -0.694752 0.69474 0.186159 -0.508592 0.694743 0.508593 -0.50859 0.694749 0.508587 -0.186157 0.694748 0.694745 -0.186157 0.694747 0.694747 -0.186158 -0.694744 -0.694749 -0.186158 -0.694749 -0.694744 -0.508589 -0.694748 -0.508589 -0.554003 -0.527867 -0.643767 -0.585058 -0.706118 -0.398879 -0.694746 -0.694748 -0.186157 -0.849551 -0.408768 -0.333425 -0.704871 -0.704875 -0.0794191 -0.704871 -0.704875 0.0794201 -0.795849 -0.566701 0.213248 -0.186156 -0.694745 0.694749 -0.186159 -0.69474 0.694753 -0.46528 -0.700856 0.540662 -0.569934 -0.591905 0.569934 -0.585058 -0.706113 0.398888 -0.661916 -0.703123 0.259781 -0.186157 -0.694744 0.694749 -0.186155 -0.694748 0.694745 -0.50859 -0.694747 0.508588 -0.508587 -0.694751 0.508587 -0.694743 -0.69475 0.186156 -0.694745 -0.694749 0.186156 -0.694745 -0.694749 -0.186156 -0.694746 -0.694748 -0.186157 -0.508591 -0.694744 -0.508593 -0.508589 -0.694748 -0.508589 -0.186158 -0.694749 -0.694744 -0.186157 -0.694744 -0.694749 -0.159331 -0.698076 -0.698072 -0.159331 -0.698077 -0.69807 -0.33052 -0.706864 -0.62538 -0.472936 -0.651638 -0.593042 -0.465273 -0.700864 -0.540657 -0.585051 -0.706119 -0.398887 -0.707219 -0.619556 -0.340576 -0.661913 -0.703126 -0.259778 -0.716023 -0.698076 0 -0.878511 -0.467354 -0.0989863 -0.70487 -0.704876 0.0794219 -0.645115 -0.698077 0.310669 -0.770332 -0.561415 0.302328 -0.585049 -0.706122 0.398886 -0.446431 -0.698079 0.559808 -0.159329 -0.698076 0.698072 -0.159331 -0.698073 0.698074 -0.330533 -0.70686 0.625378 -0.502598 -0.637421 0.584029 -0.186157 -0.694747 0.694747 -0.186157 -0.694748 0.694746 -0.508587 -0.694749 0.508588 -0.508594 -0.694743 0.508591 -0.694753 -0.69474 0.186157 -0.694749 -0.694744 0.186158 -0.694749 -0.694745 -0.186156 -0.694752 -0.69474 -0.186158 -0.508592 -0.694743 -0.508593 -0.50859 -0.694749 -0.508587 -0.186157 -0.694748 -0.694745 -0.186157 -0.694747 -0.694747 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.965927 0 0.258815 -0.965927 0 0.258815 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.707109 0 0.707105 -0.707109 0 0.707105 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.707111 0 -0.707102 -0.707111 0 -0.707102 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258818 0 0.965926 -0.258818 0 0.965926 -0.70711 0 0.707104 -0.70711 0 0.707104 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.70711 0 -0.707104 -0.70711 0 -0.707104 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.258815 0 0.965927 -0.258815 0 0.965927 -0.707111 0 0.707102 -0.707111 0 0.707102 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.707111 0 -0.707102 -0.707111 0 -0.707102 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965927 0 -0.258815 -0.965927 0 -0.258815 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.222517 0 0.974929 -0.222517 0 0.974929 -0.623492 0 0.78183 -0.623492 0 0.78183 -0.900968 0 0.433885 -0.900968 0 0.433885 -1 0 0 -1 0 0 -0.900968 0 -0.433885 -0.900968 0 -0.433885 -0.623492 0 -0.78183 -0.623492 0 -0.78183 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.222527 0 0.974926 -0.222527 0 0.974926 -0.623487 0 0.781834 -0.623487 0 0.781834 -0.900968 0 0.433885 -0.900968 0 0.433885 -1 0 0 -1 0 0 -0.900968 0 -0.433885 -0.900968 0 -0.433885 -0.623487 0 -0.781834 -0.623487 0 -0.781834 -0.222527 0 -0.974926 -0.222527 0 -0.974926 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.222517 0 0.974929 -0.222517 0 0.974929 -0.623492 0 0.78183 -0.623492 0 0.78183 -0.900969 0 0.433883 -0.900969 0 0.433883 -1 0 0 -1 0 0 -0.900968 0 -0.433885 -0.900968 0 -0.433885 -0.623492 0 -0.78183 -0.623492 0 -0.78183 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.258818 0 0.965926 -0.258818 0 0.965926 -0.70711 0 0.707104 -0.70711 0 0.707104 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.70711 0 -0.707104 -0.70711 0 -0.707104 -0.258818 0 -0.965926 -0.258818 0 -0.965926 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.222519 0 0.974928 -0.222519 0 0.974928 -0.623491 0 0.78183 -0.623491 0 0.78183 -0.90097 0 0.433882 -0.90097 0 0.433882 -1 0 0 -1 0 0 -0.90097 0 -0.433882 -0.90097 0 -0.433882 -0.623487 0 -0.781834 -0.623487 0 -0.781834 -0.222525 0 -0.974927 -0.222525 0 -0.974927 -0.15933 -0.698072 0.698076 -0.159333 -0.698067 0.69808 -0.446439 -0.698069 0.559815 -0.446435 -0.698073 0.559813 -0.645119 -0.698073 0.310672 -0.645116 -0.698075 0.310672 -0.716026 -0.698074 0 -0.716026 -0.698074 0 -0.645117 -0.698075 -0.310671 -0.645118 -0.698073 -0.310672 -0.446434 -0.698073 -0.559814 -0.446433 -0.698076 -0.55981 -0.159333 -0.698076 -0.69807 -0.159332 -0.698071 -0.698076 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.222522 0 0.974928 -0.222522 0 0.974928 -0.623489 0 0.781832 -0.623489 0 0.781832 -0.90097 0 0.433882 -0.90097 0 0.433882 -1 0 0 -1 0 0 -0.90097 0 -0.433882 -0.90097 0 -0.433882 -0.623491 0 -0.78183 -0.623491 0 -0.78183 -0.222518 0 -0.974928 -0.222518 0 -0.974928 -0.159331 -0.698076 0.698072 -0.159331 -0.698076 0.698071 -0.446433 -0.698076 0.55981 -0.446436 -0.698073 0.559811 -0.645119 -0.698073 0.310672 -0.645116 -0.698075 0.310672 -0.716023 -0.698076 0 -0.716023 -0.698076 0 -0.645115 -0.698077 -0.31067 -0.645116 -0.698075 -0.310672 -0.446434 -0.698077 -0.559808 -0.446435 -0.698072 -0.559813 -0.159329 -0.698071 -0.698076 -0.159331 -0.698076 -0.698072 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.186157 -0.694747 0.694747 -0.186157 -0.694748 0.694746 -0.508587 -0.694749 0.508588 -0.508594 -0.694743 0.508591 -0.694753 -0.69474 0.186157 -0.694749 -0.694744 0.186158 -0.694749 -0.694745 -0.186156 -0.694752 -0.69474 -0.186158 -0.508592 -0.694743 -0.508593 -0.50859 -0.694749 -0.508587 -0.186157 -0.694748 -0.694745 -0.186157 -0.694747 -0.694747 -0.159333 -0.698076 -0.698071 -0.159325 -0.698071 -0.698078 -0.330545 -0.706857 -0.625374 -0.451633 -0.689417 -0.566331 -0.465273 -0.70086 -0.540663 -0.585064 -0.706115 -0.398876 -0.657191 -0.684059 -0.316488 -0.661913 -0.703125 -0.259782 -0.704873 -0.704874 -0.0794217 -0.731126 -0.682243 0 -0.704873 -0.704873 0.0794217 -0.645118 -0.698073 0.310673 -0.691865 -0.669022 0.271538 -0.585055 -0.706115 0.398889 -0.446438 -0.698072 0.55981 -0.159334 -0.698072 0.698074 -0.159328 -0.698075 0.698073 -0.330499 -0.706861 0.625394 -0.475708 -0.684208 0.552776 -0.222512 0 -0.97493 -0.258816 -0.00192632 -0.965925 -0.467296 0 -0.884101 -0.652283 0 -0.757976 -0.707105 -0.00321633 -0.707102 -0.826248 0 -0.563307 -0.930873 0 -0.365342 -0.965918 -0.00386279 -0.258818 -0.993712 0 -0.111967 -0.993712 0 0.111967 -0.965918 -0.00386279 0.258818 -0.930873 0 0.365342 -0.826235 0 0.563326 -0.707105 -0.00321584 0.707102 -0.652292 0 0.757968 -0.467234 0 0.884134 -0.258816 -0.00192566 0.965925 -0.222525 0 0.974927 -0.186154 0.69475 -0.694744 -0.186159 0.694747 -0.694746 -0.508591 0.694746 -0.508589 -0.508588 0.694748 -0.50859 -0.694746 0.694747 -0.186157 -0.694747 0.694747 -0.186156 -0.694747 0.694747 0.186157 -0.694747 0.694746 0.186158 -0.508592 0.694745 0.50859 -0.508592 0.694746 0.508588 -0.186155 0.694746 0.694747 -0.186154 0.694746 0.694748 -0.159328 -0.698073 -0.698075 -0.159329 -0.698073 -0.698075 -0.330544 -0.706859 -0.625373 -0.451634 -0.689419 -0.566329 -0.465274 -0.700861 -0.540661 -0.585061 -0.706115 -0.39888 -0.657191 -0.684059 -0.316488 -0.661912 -0.703125 -0.259783 -0.704873 -0.704874 -0.0794227 -0.731126 -0.682243 0 -0.704873 -0.704873 0.0794217 -0.645117 -0.698074 0.310672 -0.691863 -0.669024 0.271538 -0.585061 -0.706115 0.39888 -0.446435 -0.698073 0.559813 -0.159333 -0.698072 0.698074 -0.159331 -0.698074 0.698074 -0.330522 -0.706859 0.625384 -0.475702 -0.684209 0.552779 -0.222518 0 -0.974929 -0.258821 -0.00192628 -0.965924 -0.467296 0 -0.884101 -0.652285 0 -0.757974 -0.707103 -0.00321612 -0.707103 -0.826244 0 -0.563312 -0.930873 0 -0.365343 -0.965918 -0.00386277 -0.258821 -0.993712 0 -0.111968 -0.993712 0 0.111967 -0.965918 -0.00386282 0.258819 -0.930873 0 0.365343 -0.826244 0 0.563312 -0.707103 -0.00321612 0.707103 -0.652285 0 0.757974 -0.467265 0 0.884117 -0.258821 -0.00192595 0.965924 -0.222524 0 0.974927 -0.186158 0.694746 -0.694747 -0.186156 0.694747 -0.694747 -0.50859 0.694746 -0.50859 -0.50859 0.694746 -0.50859 -0.694746 0.694747 -0.186159 -0.694747 0.694746 -0.186157 -0.694747 0.694746 0.186158 -0.694747 0.694747 0.186156 -0.50859 0.694746 0.50859 -0.50859 0.694746 0.50859 -0.186158 0.694747 0.694746 -0.186157 0.694746 0.694748 -0.186158 -0.694746 -0.694747 -0.186157 -0.694746 -0.694747 -0.508589 -0.694745 -0.508593 -0.489825 -0.660382 -0.569181 -0.585048 -0.706115 -0.398899 -0.694748 -0.694746 -0.186154 -0.714787 -0.640608 -0.280536 -0.704875 -0.704873 -0.0794124 -0.704875 -0.704872 0.079413 -0.714299 -0.673161 0.191393 -0.186157 -0.694746 0.694747 -0.186158 -0.694746 0.694747 -0.465279 -0.70086 0.540658 -0.520479 -0.676904 0.520483 -0.585048 -0.706115 0.398899 -0.661912 -0.703125 0.259784 -0.222524 0 -0.974927 -0.258819 0.00192587 -0.965924 -0.623489 -0.00160938 -0.781831 -0.652291 0 -0.757968 -0.826226 0 -0.563339 -0.900961 -0.00257846 -0.433892 -0.930872 0 -0.365344 -0.993713 0 -0.111953 -0.999996 -0.00290158 0 -0.993713 0 0.111954 -0.930872 0 0.365344 -0.900961 -0.00257846 0.433892 -0.826226 0 0.563339 -0.623491 0 0.78183 -0.65229 -0.00192617 0.757967 -0.22252 0.00224023 0.974926 -0.25882 0 0.965926 -0.159333 0.698073 -0.698073 -0.15933 0.698075 -0.698073 -0.446433 0.698076 -0.55981 -0.446435 0.698075 -0.55981 -0.645112 0.698076 -0.310678 -0.645119 0.698072 -0.310673 -0.716027 0.698072 0 -0.716027 0.698072 0 -0.645116 0.698072 0.31068 -0.645116 0.698075 0.310672 -0.446435 0.698075 0.55981 -0.446435 0.698076 0.559809 -0.15933 0.698075 0.698073 -0.159329 0.698074 0.698074 -0.222525 0 -0.974927 -0.258822 0.00161869 -0.965924 -0.623488 -0.00135244 -0.781832 -0.652286 0 -0.757973 -0.826241 0 -0.563316 -0.900967 -0.00216688 -0.433883 -0.930873 0 -0.365342 -0.993712 0 -0.111963 -0.999997 -0.0024389 0 -0.993712 0 0.111965 -0.930875 0 0.365338 -0.900967 -0.002167 0.433883 -0.826235 0 0.563326 -0.623492 0 0.78183 -0.65229 -0.0016188 0.757968 -0.222518 0.00188278 0.974927 -0.258817 0 0.965926 -0.159334 0.698071 -0.698075 -0.159331 0.698076 -0.698071 -0.446432 0.698076 -0.559811 -0.446434 0.698074 -0.559812 -0.645116 0.698075 -0.310672 -0.645116 0.698075 -0.310672 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645116 0.698075 0.310672 -0.645116 0.698075 0.310672 -0.446436 0.698075 0.55981 -0.446437 0.698069 0.559816 -0.159331 0.698067 0.69808 -0.159332 0.698071 0.698076 -0.258822 0 -0.965925 -0.258822 0 -0.965925 -0.707104 0 -0.70711 -0.707104 0 -0.70711 -0.965927 0 -0.258816 -0.965927 0 -0.258816 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.18616 0.694744 -0.694748 -0.186157 0.694749 -0.694744 -0.508587 0.694748 -0.508591 -0.508594 0.694741 -0.508594 -0.694751 0.694743 -0.186156 -0.694744 0.694749 -0.186157 -0.694745 0.694749 0.186155 -0.694748 0.694745 0.186157 -0.508589 0.694748 0.508589 -0.508589 0.694748 0.508589 -0.186157 0.694749 0.694744 -0.186156 0.694745 0.694749 -0.222522 0 -0.974928 -0.258819 -0.00161871 -0.965925 -0.467265 0 -0.884117 -0.652287 0 -0.757972 -0.707104 -0.00270294 -0.707104 -0.82624 0 -0.563319 -0.930874 0 -0.36534 -0.965921 -0.00324654 -0.258818 -0.993712 0 -0.111967 -0.993712 0 0.111967 -0.965921 -0.00324651 0.258818 -0.930874 0 0.36534 -0.82624 0 0.563319 -0.707104 -0.00270294 0.707104 -0.652287 0 0.757972 -0.467281 0 0.884109 -0.258819 -0.00161885 0.965925 -0.222518 0 0.974928 -0.186156 0.694749 -0.694745 -0.186156 0.694749 -0.694745 -0.508589 0.694748 -0.508589 -0.508589 0.694748 -0.508589 -0.694745 0.694749 -0.186156 -0.694745 0.694749 -0.186156 -0.694744 0.694749 0.186157 -0.694744 0.694749 0.186157 -0.508589 0.694748 0.508589 -0.508589 0.694748 0.508589 -0.186156 0.694749 0.694745 -0.186156 0.694749 0.694745 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.186157 0.694747 -0.694747 -0.186157 0.694748 -0.694746 -0.508587 0.694749 -0.508588 -0.508588 0.694749 -0.508589 -0.694743 0.69475 -0.186158 -0.694749 0.694744 -0.186157 -0.694748 0.694744 0.18616 -0.694744 0.694749 0.186156 -0.508588 0.694749 0.508589 -0.508588 0.694749 0.508588 -0.186157 0.694748 0.694745 -0.186157 0.694747 0.694747 -0.186158 -0.694744 -0.694749 -0.186158 -0.694749 -0.694744 -0.508589 -0.694748 -0.508589 -0.554003 -0.527871 -0.643765 -0.585056 -0.706118 -0.398881 -0.694746 -0.694748 -0.186156 -0.849553 -0.408763 -0.333426 -0.704873 -0.704873 -0.0794193 -0.704873 -0.704873 0.0794204 -0.79585 -0.566699 0.213248 -0.186156 -0.694745 0.694749 -0.186159 -0.69474 0.694753 -0.465281 -0.700856 0.540661 -0.569932 -0.591907 0.569932 -0.585056 -0.706113 0.398891 -0.661916 -0.703123 0.259781 -0.186158 -0.694744 0.694749 -0.186155 -0.694749 0.694745 -0.508589 -0.694748 0.508589 -0.508589 -0.694748 0.508589 -0.694748 -0.694745 0.186156 -0.694745 -0.694749 0.186156 -0.694745 -0.694749 -0.186154 -0.69475 -0.694743 -0.186158 -0.508592 -0.694741 -0.508596 -0.508589 -0.694748 -0.508589 -0.186159 -0.694749 -0.694744 -0.186158 -0.694744 -0.694749 -0.159331 -0.698076 -0.698072 -0.159331 -0.698076 -0.698071 -0.330521 -0.706862 -0.625382 -0.472938 -0.651635 -0.593044 -0.465275 -0.700861 -0.540659 -0.585058 -0.706115 -0.398884 -0.707216 -0.619558 -0.340577 -0.661912 -0.703126 -0.259781 -0.716023 -0.698076 0 -0.878511 -0.467354 -0.0989863 -0.70487 -0.704876 0.0794219 -0.645115 -0.698077 0.310671 -0.770328 -0.561419 0.30233 -0.585056 -0.706118 0.398883 -0.446433 -0.698077 0.55981 -0.159328 -0.698076 0.698072 -0.159332 -0.698072 0.698075 -0.330534 -0.706858 0.62538 -0.5026 -0.637417 0.584032 -0.186157 -0.694747 0.694747 -0.186157 -0.694748 0.694746 -0.508587 -0.694749 0.508588 -0.508588 -0.694749 0.508589 -0.694743 -0.69475 0.186158 -0.694749 -0.694744 0.186158 -0.694748 -0.694744 -0.18616 -0.694744 -0.694749 -0.186156 -0.508588 -0.694749 -0.508589 -0.508588 -0.694749 -0.508588 -0.186157 -0.694748 -0.694745 -0.186157 -0.694747 -0.694747 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.258817 0 0.965926 -0.258817 0 0.965926 -0.707107 0 0.707106 -0.707107 0 0.707106 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.707107 0 -0.707106 -0.707107 0 -0.707106 -0.258822 0 -0.965925 -0.258822 0 -0.965925 -0.186156 -0.694745 0.694749 -0.186159 -0.69474 0.694753 -0.508594 -0.694741 0.508593 -0.508586 -0.694749 0.50859 -0.694746 -0.694748 0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 -0.186156 -0.694746 -0.694748 -0.186156 -0.508588 -0.694749 -0.508587 -0.508589 -0.694748 -0.508589 -0.186158 -0.694749 -0.694744 -0.186158 -0.694744 -0.694749 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.186157 -0.694749 0.694744 -0.186157 -0.694749 0.694744 -0.508589 -0.694748 0.508589 -0.508589 -0.694748 0.508589 -0.694745 -0.694749 0.186156 -0.694745 -0.694749 0.186156 -0.694744 -0.694749 -0.186157 -0.694744 -0.694749 -0.186157 -0.508589 -0.694748 -0.508589 -0.508589 -0.694748 -0.508589 -0.186157 -0.694749 -0.694744 -0.186157 -0.694749 -0.694744 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.222519 0 0.974928 -0.222519 0 0.974928 -0.623494 0 0.781828 -0.623494 0 0.781828 -0.900967 0 0.433887 -0.900967 0 0.433887 -1 0 0 -1 0 0 -0.900967 0 -0.433887 -0.900967 0 -0.433887 -0.623493 0 -0.781829 -0.623493 0 -0.781829 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.15933 -0.698074 0.698074 -0.15933 -0.698073 0.698075 -0.446439 -0.698071 0.559812 -0.446434 -0.698076 0.559809 -0.645113 -0.698077 0.310673 -0.645114 -0.698076 0.310673 -0.716023 -0.698076 0 -0.716023 -0.698076 0 -0.645114 -0.698075 -0.310674 -0.645113 -0.698077 -0.310672 -0.446435 -0.698076 -0.559808 -0.446436 -0.698073 -0.559812 -0.15933 -0.698075 -0.698072 -0.15933 -0.698074 -0.698074 -0.186158 -0.694749 -0.694744 -0.186155 -0.694747 -0.694747 -0.508589 -0.694747 -0.50859 -0.489821 -0.660375 -0.569192 -0.585062 -0.706117 -0.398875 -0.694746 -0.694747 -0.186156 -0.714785 -0.640612 -0.280533 -0.704873 -0.704873 -0.0794217 -0.704873 -0.704873 0.0794217 -0.714297 -0.673162 0.191396 -0.186156 -0.694746 0.694748 -0.186154 -0.694746 0.694748 -0.465276 -0.700862 0.540658 -0.520484 -0.676903 0.52048 -0.585055 -0.706115 0.39889 -0.661914 -0.703124 0.259783 -0.222513 0 -0.97493 -0.258817 0.00192631 -0.965925 -0.623487 -0.00160887 -0.781833 -0.652281 0 -0.757978 -0.826248 0 -0.563307 -0.900967 -0.00257808 -0.43388 -0.930873 0 -0.365342 -0.993712 0 -0.111967 -0.999996 -0.00290192 0 -0.993712 0 0.111967 -0.930873 0 0.365342 -0.900965 -0.00257828 0.433885 -0.826235 0 0.563326 -0.623487 0 0.781833 -0.652289 -0.00192632 0.757968 -0.222525 0.00223976 0.974924 -0.258817 0 0.965926 -0.159324 0.698077 -0.698072 -0.159334 0.698072 -0.698074 -0.446434 0.698073 -0.559814 -0.446435 0.698072 -0.559813 -0.645119 0.698073 -0.310671 -0.645116 0.698074 -0.310673 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645117 0.698073 0.310674 -0.645117 0.698073 0.310673 -0.446434 0.698072 0.559814 -0.446437 0.698075 0.559808 -0.159334 0.698076 0.698071 -0.159328 0.698073 0.698075 -0.186157 -0.694745 -0.694748 -0.186159 -0.694747 -0.694746 -0.50859 -0.694746 -0.50859 -0.489823 -0.660377 -0.569188 -0.585055 -0.706114 -0.39889 -0.694747 -0.694745 -0.18616 -0.714783 -0.640617 -0.280526 -0.704872 -0.704874 -0.0794226 -0.704872 -0.704874 0.0794216 -0.714296 -0.673163 0.191397 -0.18616 -0.694745 0.694747 -0.186157 -0.694746 0.694747 -0.465273 -0.700862 0.540661 -0.520482 -0.676902 0.520482 -0.585055 -0.706114 0.39889 -0.661917 -0.703122 0.259778 -0.222519 0 -0.974928 -0.258822 0.00192627 -0.965923 -0.623491 -0.00160891 -0.781829 -0.652285 0 -0.757974 -0.826235 0 -0.563326 -0.900967 -0.00257838 -0.43388 -0.930876 0 -0.365334 -0.993712 0 -0.111968 -0.999996 -0.00290192 0 -0.993712 0 0.111967 -0.930876 0 0.365334 -0.900967 -0.00257838 0.43388 -0.826235 0 0.563326 -0.623487 0 0.781833 -0.652284 -0.00192601 0.757972 -0.222525 0.0022401 0.974924 -0.258822 0 0.965925 -0.15933 0.698073 -0.698075 -0.159329 0.698073 -0.698074 -0.446436 0.698073 -0.559811 -0.446436 0.698073 -0.559811 -0.645119 0.698073 -0.31067 -0.645116 0.698074 -0.310673 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645118 0.698074 0.31067 -0.645118 0.698073 0.310672 -0.446434 0.698073 0.559814 -0.446434 0.698074 0.559812 -0.159334 0.698074 0.698072 -0.159332 0.698073 0.698074 -0.159331 -0.698074 -0.698074 -0.159331 -0.698074 -0.698074 -0.330534 -0.706859 -0.625378 -0.451631 -0.689419 -0.566332 -0.465271 -0.700863 -0.540661 -0.58506 -0.706117 -0.398879 -0.657193 -0.684059 -0.316481 -0.661914 -0.703123 -0.259785 -0.704876 -0.704871 -0.0794126 -0.731126 -0.682243 0 -0.704876 -0.704871 0.0794131 -0.64512 -0.698073 0.310668 -0.69186 -0.669027 0.271538 -0.58506 -0.706117 0.398879 -0.446433 -0.698075 0.559812 -0.159328 -0.698074 0.698074 -0.159329 -0.698073 0.698074 -0.330545 -0.706859 0.625373 -0.4757 -0.684212 0.552779 -0.222521 0 -0.974928 -0.258819 -0.00192605 -0.965924 -0.467282 0 -0.884109 -0.652284 0 -0.757975 -0.707102 -0.00321615 -0.707105 -0.826244 0 -0.563312 -0.930872 0 -0.365344 -0.965919 -0.00386303 -0.258814 -0.993713 0 -0.111953 -0.993713 0 0.111954 -0.965919 -0.003863 0.258815 -0.930872 0 0.365344 -0.826244 0 0.563312 -0.707102 -0.00321615 0.707105 -0.652284 0 0.757975 -0.467297 0 0.8841 -0.258819 -0.00192621 0.965924 -0.222518 0 0.974929 -0.186157 0.694747 -0.694747 -0.186156 0.694747 -0.694746 -0.508588 0.694748 -0.50859 -0.50859 0.694747 -0.508589 -0.694747 0.694746 -0.186155 -0.694744 0.694749 -0.186158 -0.694744 0.694749 0.186155 -0.694745 0.694747 0.186159 -0.508589 0.694746 0.508591 -0.50859 0.694748 0.508588 -0.186157 0.694747 0.694746 -0.186156 0.694747 0.694747 -0.222519 0 -0.974928 -0.258816 -0.00161873 -0.965925 -0.467265 0 -0.884117 -0.65229 0 -0.75797 -0.707105 -0.00270288 -0.707103 -0.826237 0 -0.563322 -0.930875 0 -0.365338 -0.965921 -0.00324652 -0.258817 -0.993712 0 -0.111965 -0.993712 0 0.111963 -0.965921 -0.00324659 0.258817 -0.930873 0 0.365342 -0.826244 0 0.563313 -0.707105 -0.00270308 0.707104 -0.652285 0 0.757974 -0.467265 0 0.884117 -0.258822 -0.00161869 0.965924 -0.222525 0 0.974927 -0.186156 0.694745 -0.694749 -0.186153 0.694748 -0.694746 -0.50859 0.694747 -0.508589 -0.508588 0.694749 -0.508588 -0.694746 0.694748 -0.186156 -0.694745 0.694749 -0.186156 -0.694745 0.694749 0.186156 -0.694746 0.694748 0.186157 -0.508588 0.694749 0.508587 -0.508589 0.694748 0.508589 -0.186158 0.694749 0.694744 -0.186158 0.694744 0.694749 -0.222522 0 -0.974928 -0.258819 -0.00161871 -0.965925 -0.467265 0 -0.884117 -0.652287 0 -0.757972 -0.707104 -0.00270294 -0.707104 -0.82624 0 -0.563319 -0.930874 0 -0.36534 -0.965921 -0.00324654 -0.258818 -0.993712 0 -0.111967 -0.993712 0 0.111967 -0.96592 -0.00324653 0.258819 -0.930873 0 0.365342 -0.826246 0 0.56331 -0.707106 -0.00270312 0.707103 -0.652285 0 0.757974 -0.467265 0 0.884117 -0.258821 -0.00161869 0.965924 -0.222525 0 0.974927 -0.186156 0.694749 -0.694745 -0.186156 0.694749 -0.694745 -0.508589 0.694748 -0.508589 -0.508589 0.694748 -0.508589 -0.694745 0.694749 -0.186156 -0.694745 0.694749 -0.186156 -0.694744 0.694749 0.186157 -0.694743 0.69475 0.186156 -0.508588 0.694751 0.508586 -0.508589 0.694748 0.508589 -0.186158 0.694749 0.694744 -0.186157 0.694744 0.694749 -0.222519 0 -0.974928 -0.258817 -0.00161873 -0.965925 -0.467265 0 -0.884117 -0.652287 0 -0.757972 -0.707104 -0.00270294 -0.707104 -0.826238 0 -0.563321 -0.930876 0 -0.365336 -0.965921 -0.00324645 -0.258816 -0.993712 0 -0.111967 -0.993712 0 0.111967 -0.965921 -0.00324645 0.258816 -0.930876 0 0.365336 -0.826238 0 0.563321 -0.707104 -0.00270294 0.707104 -0.652287 0 0.757972 -0.467265 0 0.884117 -0.258819 -0.00161871 0.965924 -0.222522 0 0.974928 -0.186155 0.694749 -0.694745 -0.186157 0.694745 -0.694748 -0.508589 0.694748 -0.508589 -0.508589 0.694748 -0.508589 -0.694745 0.694748 -0.186155 -0.69474 0.694753 -0.186156 -0.694741 0.694753 0.186154 -0.694744 0.69475 0.186156 -0.508587 0.694751 0.508587 -0.508587 0.694751 0.508587 -0.186156 0.69475 0.694743 -0.186156 0.694745 0.694749 -0.222521 0 -0.974928 -0.258818 0.00161872 -0.965925 -0.623489 -0.00135245 -0.781831 -0.652287 0 -0.757972 -0.826237 0 -0.563323 -0.900968 -0.002167 -0.433881 -0.930876 0 -0.365336 -0.993712 0 -0.111967 -0.999997 -0.00243897 0 -0.993712 0 0.111967 -0.930876 0 0.365336 -0.900968 -0.00216698 0.43388 -0.826238 0 0.563321 -0.623489 0 0.781832 -0.652286 -0.0016187 0.757972 -0.22252 0.00188283 0.974926 -0.25882 0 0.965926 -0.15933 0.698076 -0.698072 -0.159332 0.698073 -0.698074 -0.446436 0.698071 -0.559814 -0.446432 0.698076 -0.559812 -0.645115 0.698077 -0.310669 -0.645116 0.698076 -0.310669 -0.716023 0.698076 0 -0.716023 0.698076 0 -0.645115 0.698077 0.310669 -0.645115 0.698077 0.310669 -0.446433 0.698076 0.55981 -0.446434 0.698072 0.559815 -0.159331 0.698073 0.698075 -0.159331 0.698074 0.698074 -0.159328 -0.698072 -0.698076 -0.159329 -0.698076 -0.698072 -0.330521 -0.706862 -0.625382 -0.47294 -0.651634 -0.593044 -0.465277 -0.700861 -0.540658 -0.585056 -0.706115 -0.398887 -0.707218 -0.619555 -0.340578 -0.661913 -0.703126 -0.25978 -0.716026 -0.698074 0 -0.87851 -0.467356 -0.0989846 -0.704873 -0.704874 0.0794193 -0.645116 -0.698075 0.310672 -0.770327 -0.56142 0.302332 -0.585061 -0.706115 0.39888 -0.446435 -0.698073 0.559813 -0.159334 -0.698071 0.698075 -0.159331 -0.698076 0.698071 -0.330521 -0.706862 0.625382 -0.502598 -0.637418 0.584032 -0.159331 -0.698076 -0.698072 -0.159331 -0.698076 -0.698071 -0.330521 -0.706862 -0.625382 -0.472938 -0.651635 -0.593044 -0.465275 -0.700861 -0.540659 -0.585058 -0.706115 -0.398884 -0.707216 -0.619558 -0.340577 -0.661912 -0.703126 -0.259781 -0.716023 -0.698076 0 -0.878511 -0.467354 -0.0989863 -0.70487 -0.704876 0.0794219 -0.645115 -0.698077 0.310671 -0.770325 -0.561423 0.302331 -0.585063 -0.706115 0.398878 -0.446435 -0.698073 0.559813 -0.159334 -0.698071 0.698075 -0.159331 -0.698076 0.698071 -0.330521 -0.706862 0.625382 -0.502598 -0.637418 0.584032 -0.159331 -0.698076 -0.698072 -0.15933 -0.698073 -0.698075 -0.330522 -0.70686 -0.625384 -0.472937 -0.651635 -0.593045 -0.465273 -0.700864 -0.540657 -0.585054 -0.706119 -0.398884 -0.707217 -0.619559 -0.340575 -0.661912 -0.703128 -0.259777 -0.70487 -0.704876 -0.0794219 -0.793864 -0.608096 0 -0.70487 -0.704876 0.0794219 -0.645115 -0.698077 0.310669 -0.770332 -0.561415 0.302328 -0.585054 -0.706119 0.398884 -0.446434 -0.698076 0.559809 -0.159332 -0.698071 0.698076 -0.159328 -0.698077 0.698071 -0.33052 -0.706864 0.62538 -0.502598 -0.637421 0.584029 -0.186156 -0.694749 -0.694745 -0.186156 -0.694748 -0.694746 -0.50859 -0.694749 -0.508586 -0.554005 -0.527868 -0.643765 -0.58506 -0.70611 -0.39889 -0.694753 -0.69474 -0.186159 -0.84955 -0.408776 -0.333418 -0.704875 -0.704871 -0.0794222 -0.704875 -0.704871 0.0794224 -0.795852 -0.566697 0.213248 -0.186157 -0.694747 0.694747 -0.186155 -0.69475 0.694744 -0.465271 -0.700866 0.540657 -0.569935 -0.591905 0.569931 -0.58506 -0.706111 0.398888 -0.66192 -0.703119 0.25978 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.222519 0 0.974928 -0.222519 0 0.974928 -0.623487 0 0.781834 -0.623487 0 0.781834 -0.90097 0 0.433882 -0.90097 0 0.433882 -1 0 0 -1 0 0 -0.90097 0 -0.433882 -0.90097 0 -0.433882 -0.623491 0 -0.78183 -0.623491 0 -0.78183 -0.222519 0 -0.974928 -0.222519 0 -0.974928 -0.159328 -0.698081 0.698068 -0.159331 -0.698076 0.698071 -0.446432 -0.698076 0.559811 -0.446435 -0.698073 0.559813 -0.645119 -0.698073 0.310672 -0.645116 -0.698075 0.310672 -0.716026 -0.698074 0 -0.716026 -0.698074 0 -0.645117 -0.698075 -0.310671 -0.645118 -0.698073 -0.310672 -0.446436 -0.698073 -0.559811 -0.446436 -0.698076 -0.559809 -0.159329 -0.698076 -0.698072 -0.159328 -0.698072 -0.698076 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.222522 0 0.974928 -0.222522 0 0.974928 -0.623489 0 0.781832 -0.623489 0 0.781832 -0.90097 0 0.433882 -0.90097 0 0.433882 -1 0 0 -1 0 0 -0.90097 0 -0.433881 -0.90097 0 -0.433881 -0.623489 0 -0.781832 -0.623489 0 -0.781832 -0.222518 0 -0.974928 -0.222518 0 -0.974928 -0.159331 -0.698076 0.698072 -0.159331 -0.698076 0.698071 -0.446433 -0.698076 0.55981 -0.446436 -0.698073 0.559811 -0.645119 -0.698073 0.310672 -0.645116 -0.698075 0.310672 -0.716023 -0.698076 0 -0.716023 -0.698076 0 -0.645115 -0.698077 -0.310669 -0.645118 -0.698073 -0.310672 -0.446435 -0.698073 -0.559812 -0.446435 -0.698072 -0.559813 -0.159329 -0.698071 -0.698076 -0.159331 -0.698076 -0.698072 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.186157 -0.694747 0.694747 -0.186155 -0.69475 0.694744 -0.508586 -0.694751 0.508587 -0.508594 -0.694743 0.50859 -0.694753 -0.69474 0.186157 -0.694749 -0.694744 0.186158 -0.694749 -0.694745 -0.186156 -0.694753 -0.69474 -0.186159 -0.508593 -0.694741 -0.508594 -0.50859 -0.694749 -0.508586 -0.186156 -0.694748 -0.694746 -0.186156 -0.694749 -0.694745 -0.186154 -0.694749 0.694745 -0.186159 -0.694747 0.694746 -0.508591 -0.694746 0.508589 -0.508589 -0.694747 0.50859 -0.694746 -0.694747 0.186157 -0.694747 -0.694746 0.186156 -0.694747 -0.694746 -0.186157 -0.694746 -0.694747 -0.186156 -0.50859 -0.694748 -0.508588 -0.508589 -0.694746 -0.508591 -0.186155 -0.694746 -0.694748 -0.186154 -0.694746 -0.694748 -0.258816 0 -0.965927 -0.258816 0 -0.965927 -0.707108 0 -0.707105 -0.707108 0 -0.707105 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707108 0 0.707105 -0.707108 0 0.707105 -0.258816 0 0.965927 -0.258816 0 0.965927 -0.186155 0.694746 -0.694748 -0.186154 0.694746 -0.694748 -0.508591 0.694746 -0.508589 -0.508588 0.694748 -0.50859 -0.694746 0.694747 -0.186157 -0.694747 0.694747 -0.186156 -0.694747 0.694747 0.186157 -0.694746 0.694747 0.186156 -0.50859 0.694748 0.508588 -0.508589 0.694747 0.508591 -0.186155 0.694746 0.694747 -0.186158 0.694749 0.694744 -0.186159 -0.694745 0.694748 -0.186156 -0.694746 0.694747 -0.508592 -0.694746 0.508588 -0.508589 -0.694748 0.508589 -0.694745 -0.694747 0.186159 -0.694748 -0.694746 0.186157 -0.694747 -0.694745 -0.18616 -0.694747 -0.694746 -0.186157 -0.508592 -0.694747 -0.508588 -0.508592 -0.694746 -0.508589 -0.186154 -0.694746 -0.694748 -0.186156 -0.694747 -0.694746 -0.258816 0 -0.965927 -0.258816 0 -0.965927 -0.70711 0 -0.707104 -0.70711 0 -0.707104 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.70711 0 0.707104 -0.70711 0 0.707104 -0.258821 0 0.965925 -0.258821 0 0.965925 -0.186154 0.694748 -0.694746 -0.186156 0.694747 -0.694747 -0.508592 0.694746 -0.508588 -0.508591 0.694747 -0.508588 -0.694746 0.694747 -0.186159 -0.694747 0.694746 -0.186157 -0.694747 0.694745 0.18616 -0.694746 0.694747 0.186156 -0.508591 0.694748 0.508587 -0.50859 0.694746 0.50859 -0.186158 0.694747 0.694746 -0.186157 0.694746 0.694748 -0.186155 -0.694748 0.694746 -0.186158 -0.694746 0.694747 -0.508591 -0.694745 0.508591 -0.508588 -0.694746 0.508592 -0.694747 -0.694747 0.186155 -0.694748 -0.694746 0.186154 -0.694748 -0.694746 -0.186156 -0.694748 -0.694746 -0.186154 -0.50859 -0.694747 -0.50859 -0.508589 -0.694745 -0.508593 -0.186157 -0.694746 -0.694747 -0.186158 -0.694746 -0.694747 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258817 0 0.965926 -0.258817 0 0.965926 -0.186157 0.694747 -0.694747 -0.186158 0.694746 -0.694747 -0.508591 0.694745 -0.508591 -0.508588 0.694747 -0.508592 -0.694747 0.694747 -0.186155 -0.694748 0.694746 -0.186154 -0.694748 0.694746 0.186156 -0.694747 0.694747 0.186154 -0.508589 0.694747 0.508589 -0.508589 0.694746 0.508592 -0.186155 0.694746 0.694748 -0.186157 0.694747 0.694746 -0.222519 0 -0.974928 -0.258816 -0.00161873 -0.965925 -0.467265 0 -0.884117 -0.652291 0 -0.757969 -0.707105 -0.00270283 -0.707103 -0.826235 0 -0.563326 -0.930875 0 -0.365338 -0.965921 -0.00324652 -0.258817 -0.993712 0 -0.111965 -0.993712 0 0.111963 -0.965921 -0.00324659 0.258817 -0.930873 0 0.365342 -0.826241 0 0.563316 -0.707105 -0.00270303 0.707103 -0.652286 0 0.757973 -0.467265 0 0.884117 -0.258822 -0.00161869 0.965924 -0.222525 0 0.974927 -0.186156 0.694745 -0.694749 -0.186153 0.694748 -0.694746 -0.50859 0.694747 -0.508589 -0.508588 0.694749 -0.508588 -0.694746 0.694748 -0.186156 -0.694747 0.694747 -0.186156 -0.694747 0.694747 0.186156 -0.694746 0.694748 0.186156 -0.508588 0.694749 0.508587 -0.508589 0.694748 0.508589 -0.186158 0.694749 0.694744 -0.186158 0.694744 0.694749 -0.222522 0 -0.974928 -0.258819 0.00161871 -0.965924 -0.623489 -0.00135245 -0.781831 -0.652287 0 -0.757972 -0.826235 0 -0.563326 -0.900966 -0.00216698 -0.433884 -0.930874 0 -0.36534 -0.993713 0 -0.11196 -0.999997 -0.00243883 0 -0.993713 0 0.111961 -0.930873 0 0.365342 -0.900967 -0.00216688 0.433883 -0.826241 0 0.563316 -0.623487 0 0.781834 -0.652284 -0.00161875 0.757973 -0.222525 0.00188273 0.974925 -0.258822 0 0.965925 -0.159331 0.698076 -0.698071 -0.159331 0.698076 -0.698071 -0.446433 0.698076 -0.55981 -0.446436 0.698073 -0.559811 -0.645117 0.698073 -0.310673 -0.64512 0.69807 -0.310673 -0.716028 0.698072 0 -0.716028 0.698072 0 -0.645118 0.698072 0.310673 -0.645118 0.698073 0.310672 -0.446434 0.698073 0.559814 -0.446433 0.698076 0.55981 -0.159333 0.698077 0.69807 -0.159332 0.698071 0.698076 -0.222518 0 -0.974928 -0.258816 -0.00161873 -0.965925 -0.467265 0 -0.884117 -0.652287 0 -0.757972 -0.707106 -0.00270302 -0.707103 -0.826243 0 -0.563314 -0.930874 0 -0.36534 -0.965921 -0.00324651 -0.258818 -0.993712 0 -0.111967 -0.993712 0 0.111967 -0.965921 -0.00324651 0.258818 -0.930874 0 0.36534 -0.826243 0 0.563314 -0.707106 -0.00270302 0.707103 -0.652287 0 0.757972 -0.467265 0 0.884117 -0.258819 -0.00161871 0.965925 -0.222522 0 0.974928 -0.186154 0.694749 -0.694745 -0.186157 0.694744 -0.694749 -0.508593 0.694744 -0.508591 -0.508589 0.694748 -0.508589 -0.694744 0.694749 -0.186157 -0.694744 0.694749 -0.186157 -0.694744 0.694749 0.186157 -0.694744 0.69475 0.186156 -0.508588 0.694751 0.508586 -0.508589 0.694748 0.508589 -0.186156 0.694749 0.694745 -0.186156 0.694745 0.694749 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.186156 0.694749 -0.694745 -0.186157 0.694748 -0.694746 -0.508587 0.694749 -0.508588 -0.508589 0.694748 -0.508589 -0.694744 0.694749 -0.186158 -0.694749 0.694744 -0.186158 -0.694748 0.694744 0.18616 -0.694744 0.694749 0.186156 -0.508588 0.694749 0.508589 -0.508587 0.694751 0.508587 -0.186156 0.69475 0.694743 -0.186156 0.694747 0.694747 -0.159328 -0.698072 -0.698076 -0.159329 -0.698076 -0.698072 -0.330521 -0.706862 -0.625382 -0.47294 -0.651634 -0.593044 -0.465276 -0.700863 -0.540656 -0.585053 -0.706117 -0.398888 -0.707218 -0.619555 -0.340578 -0.661913 -0.703125 -0.25978 -0.704873 -0.704874 -0.0794203 -0.793864 -0.608096 0 -0.704873 -0.704874 0.0794193 -0.645116 -0.698075 0.310672 -0.770327 -0.56142 0.302332 -0.585058 -0.706117 0.398882 -0.446434 -0.698074 0.559812 -0.159334 -0.698071 0.698075 -0.159331 -0.698076 0.698071 -0.330521 -0.706862 0.625382 -0.502599 -0.637418 0.584032 -0.186157 -0.694749 -0.694744 -0.186157 -0.694749 -0.694744 -0.508589 -0.694748 -0.508589 -0.554002 -0.527876 -0.643762 -0.585056 -0.706114 -0.39889 -0.694749 -0.694744 -0.186157 -0.849552 -0.408766 -0.333424 -0.704871 -0.704876 -0.0794167 -0.704871 -0.704876 0.0794172 -0.795852 -0.566696 0.213248 -0.18616 -0.694744 0.694748 -0.186157 -0.694749 0.694744 -0.465272 -0.700863 0.540659 -0.569934 -0.591905 0.569934 -0.585058 -0.706116 0.398882 -0.661914 -0.703124 0.259783 -0.159331 -0.698076 -0.698072 -0.159329 -0.698072 -0.698076 -0.330523 -0.706858 -0.625385 -0.472939 -0.651631 -0.593048 -0.465275 -0.700861 -0.540659 -0.58506 -0.706115 -0.398881 -0.707214 -0.619561 -0.340576 -0.661911 -0.703128 -0.25978 -0.716023 -0.698076 0 -0.878512 -0.467353 -0.0989871 -0.70487 -0.704876 0.0794219 -0.645115 -0.698077 0.310671 -0.770328 -0.561419 0.30233 -0.58506 -0.706115 0.398881 -0.446436 -0.698073 0.559811 -0.159332 -0.698071 0.698076 -0.159329 -0.698076 0.698072 -0.330521 -0.706862 0.625382 -0.5026 -0.637417 0.584032 -0.186157 -0.694747 0.694747 -0.186155 -0.69475 0.694744 -0.508586 -0.694751 0.508587 -0.508588 -0.694749 0.508588 -0.694743 -0.69475 0.186158 -0.694749 -0.694744 0.186158 -0.694748 -0.694744 -0.18616 -0.694745 -0.694749 -0.186156 -0.508589 -0.694747 -0.50859 -0.508588 -0.694749 -0.508588 -0.186156 -0.694748 -0.694746 -0.186156 -0.694749 -0.694745 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.258817 0 0.965926 -0.258817 0 0.965926 -0.707107 0 0.707106 -0.707107 0 0.707106 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.707107 0 -0.707106 -0.707107 0 -0.707106 -0.258817 0 -0.965926 -0.258817 0 -0.965926 -0.186153 -0.694754 0.694741 -0.186157 -0.694749 0.694745 -0.50859 -0.694747 0.508589 -0.508588 -0.694749 0.508588 -0.694746 -0.694748 0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 -0.186156 -0.694746 -0.694748 -0.186156 -0.508588 -0.694749 -0.508587 -0.508589 -0.694748 -0.508589 -0.186155 -0.694749 -0.694745 -0.186154 -0.694745 -0.694749 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.25882 0 0.965926 -0.222521 0.00353186 0.974922 -0.652284 -0.00303666 0.757968 -0.623489 0 0.781832 -0.82624 0 0.563319 -0.900961 -0.0040648 0.433881 -0.930872 0 0.365344 -0.993713 0 0.11196 -0.99999 -0.00457499 0 -0.993713 0 -0.111961 -0.930872 0 -0.365344 -0.900961 -0.00406472 -0.43388 -0.826243 0 -0.563314 -0.652287 0 -0.757972 -0.623487 -0.00253707 -0.781829 -0.258816 0.00303658 -0.965922 -0.222519 0 -0.974928 -0.186157 -0.694749 -0.694744 -0.186156 -0.694744 -0.694749 -0.508591 -0.694744 -0.508591 -0.554004 -0.52787 -0.643764 -0.585058 -0.706118 -0.39888 -0.694744 -0.694749 -0.186157 -0.849552 -0.408762 -0.333428 -0.704871 -0.704876 -0.0794173 -0.704871 -0.704876 0.0794167 -0.795853 -0.566696 0.213248 -0.186157 -0.694749 0.694744 -0.186157 -0.694749 0.694744 -0.465274 -0.700863 0.540658 -0.569931 -0.59191 0.569931 -0.585056 -0.706118 0.398883 -0.66191 -0.703127 0.259784 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.186157 -0.694747 0.694747 -0.186155 -0.69475 0.694744 -0.508586 -0.694751 0.508587 -0.508588 -0.694749 0.508588 -0.694743 -0.69475 0.186158 -0.694749 -0.694744 0.186158 -0.694748 -0.694744 -0.18616 -0.694745 -0.694749 -0.186156 -0.508589 -0.694747 -0.50859 -0.508588 -0.694749 -0.508588 -0.186156 -0.694748 -0.694746 -0.186156 -0.694749 -0.694745 -0.186154 -0.694746 -0.694748 -0.186155 -0.694747 -0.694747 -0.508589 -0.694747 -0.50859 -0.489824 -0.660381 -0.569182 -0.585053 -0.706117 -0.398889 -0.694746 -0.694747 -0.186156 -0.714785 -0.640612 -0.280533 -0.704873 -0.704873 -0.0794217 -0.704873 -0.704873 0.0794217 -0.714297 -0.673163 0.191395 -0.186155 -0.694749 0.694745 -0.186159 -0.694747 0.694746 -0.465276 -0.700862 0.540658 -0.52048 -0.676905 0.520481 -0.585053 -0.706117 0.398888 -0.661913 -0.703125 0.259782 -0.222525 0 -0.974927 -0.258817 0.00192565 -0.965925 -0.623486 -0.00160941 -0.781833 -0.65229 0 -0.75797 -0.826235 0 -0.563326 -0.900965 -0.00257828 -0.433885 -0.930873 0 -0.365342 -0.993712 0 -0.111967 -0.999996 -0.00290192 0 -0.993712 0 0.111967 -0.930873 0 0.365342 -0.900965 -0.00257828 0.433885 -0.826235 0 0.563326 -0.623496 0 0.781827 -0.652289 -0.0019258 0.757968 -0.222512 0.00224054 0.974927 -0.258817 0 0.965926 -0.159334 0.698072 -0.698074 -0.159328 0.698075 -0.698073 -0.446432 0.698076 -0.559812 -0.446433 0.698075 -0.559811 -0.645115 0.698075 -0.310673 -0.645118 0.698073 -0.310671 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645116 0.698074 0.310674 -0.645116 0.698075 0.310673 -0.446438 0.698076 0.559807 -0.446435 0.698073 0.559813 -0.159325 0.698071 0.698077 -0.159333 0.698076 0.698071 -0.159331 -0.698074 -0.698073 -0.15933 -0.698073 -0.698074 -0.330522 -0.706859 -0.625384 -0.451635 -0.689417 -0.56633 -0.465277 -0.700861 -0.540658 -0.585054 -0.706115 -0.398889 -0.657192 -0.684057 -0.316488 -0.661914 -0.703126 -0.259777 -0.704873 -0.704874 -0.0794227 -0.731126 -0.682243 0 -0.704873 -0.704873 0.0794217 -0.645117 -0.698074 0.310672 -0.691866 -0.669022 0.271534 -0.585059 -0.706115 0.398883 -0.446435 -0.698073 0.559813 -0.159334 -0.698072 0.698074 -0.159331 -0.698074 0.698074 -0.330522 -0.706859 0.625384 -0.475702 -0.684209 0.552779 -0.222519 0 -0.974928 -0.258817 -0.00192598 -0.965925 -0.467265 0 -0.884117 -0.65229 0 -0.75797 -0.707103 -0.00321588 -0.707103 -0.826235 0 -0.563326 -0.930876 0 -0.365334 -0.965919 -0.00386263 -0.258815 -0.993712 0 -0.111968 -0.993712 0 0.111967 -0.965919 -0.00386272 0.258815 -0.930875 0 0.365337 -0.826241 0 0.563316 -0.707103 -0.00321612 0.707103 -0.652285 0 0.757974 -0.467265 0 0.884117 -0.258822 -0.00192594 0.965923 -0.222525 0 0.974927 -0.186155 0.694748 -0.694746 -0.186157 0.694747 -0.694746 -0.50859 0.694746 -0.50859 -0.508592 0.694745 -0.508589 -0.694749 0.694745 -0.186156 -0.694745 0.694747 -0.186159 -0.694746 0.694748 0.186155 -0.694747 0.694746 0.186159 -0.50859 0.694746 0.50859 -0.50859 0.694746 0.50859 -0.186159 0.694747 0.694746 -0.186157 0.694746 0.694747 -0.186155 -0.694748 0.694746 -0.186156 -0.694747 0.694746 -0.508589 -0.694748 0.508589 -0.50859 -0.694747 0.508589 -0.694747 -0.694747 0.186155 -0.694744 -0.694749 0.186158 -0.694745 -0.694749 -0.186155 -0.694746 -0.694747 -0.186159 -0.50859 -0.694747 -0.50859 -0.50859 -0.694747 -0.508589 -0.186157 -0.694747 -0.694746 -0.186156 -0.694746 -0.694747 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258817 0 0.965926 -0.258817 0 0.965926 -0.186157 0.694747 -0.694747 -0.186156 0.694747 -0.694746 -0.508589 0.694748 -0.508589 -0.50859 0.694747 -0.508589 -0.694747 0.694747 -0.186155 -0.694744 0.694749 -0.186158 -0.694744 0.694749 0.186155 -0.694745 0.694747 0.186159 -0.508589 0.694747 0.508589 -0.50859 0.694748 0.508588 -0.186155 0.694747 0.694747 -0.186156 0.694748 0.694746 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.84912 0.510202 -0.136708 0.84912 0.373494 -0.373494 0.84912 0.136708 -0.510202 0.84912 0.136708 0.510202 0.84912 0.373494 0.373494 0.84912 0.510202 0.136708 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258818 0.965926 0 0.258818 0.965926 0.84912 0.510202 -0.136708 0.84912 0.373494 -0.373494 0.84912 0.136708 -0.510202 0.84912 0.136709 0.510202 0.84912 0.373494 0.373494 0.84912 0.510202 0.136709 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707107 0.707107 0 0.707107 0.707107 0 0.25882 0.965926 0 0.25882 0.965926 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.84912 0.510202 0.136708 -0.84912 0.373494 0.373494 -0.84912 0.136708 0.510202 -0.84912 0.136708 -0.510202 -0.84912 0.373494 -0.373494 -0.84912 0.510202 -0.136708 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258818 -0.965926 0 0.258818 -0.965926 -0.84912 0.510202 0.136709 -0.84912 0.373494 0.373494 -0.84912 0.136709 0.510202 -0.84912 0.136708 -0.510202 -0.84912 0.373494 -0.373494 -0.84912 0.510202 -0.136708 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258818 -0.965926 0 0.258818 -0.965926 -0.989071 0 0.147442 -0.989071 0 0.147442 -0.989071 0 -0.147442 -0.989071 0 -0.147442 0.989071 0 0.147442 0.989071 0 0.147442 0.989071 0 -0.147442 0.989071 0 -0.147442 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0825797 0 0.996584 -0.0825797 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401696 0 0.915773 -0.401696 0 0.915773 -0.546948 0 0.837166 -0.546948 0 0.837166 -0.677281 0 0.735724 -0.677281 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475947 -0.879474 0 0.475947 -0.945817 0 0.3247 -0.945817 0 0.3247 -0.986361 0 0.164594 -0.986361 0 0.164594 -1 0 0 -1 0 0 -0.986361 0 -0.164594 -0.986361 0 -0.164594 -0.945817 0 -0.3247 -0.945817 0 -0.3247 -0.879474 0 -0.475947 -0.879474 0 -0.475947 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677281 0 -0.735724 -0.677281 0 -0.735724 -0.546948 0 -0.837166 -0.546948 0 -0.837166 -0.401696 0 -0.915773 -0.401696 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.0825797 0 -0.996584 -0.0825797 0 -0.996584 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0584918 -0.705903 0.70589 -0.0584917 -0.705904 0.705888 -0.173879 -0.705904 0.686634 -0.173881 -0.705895 0.686642 -0.284527 -0.705895 0.648657 -0.284528 -0.705894 0.648658 -0.387413 -0.705894 0.59298 -0.387408 -0.705903 0.592972 -0.479725 -0.705902 0.52112 -0.479726 -0.7059 0.521121 -0.558957 -0.7059 0.435054 -0.558964 -0.705891 0.435059 -0.62295 -0.705891 0.337124 -0.622939 -0.705902 0.337118 -0.669931 -0.705902 0.229988 -0.669938 -0.705895 0.22999 -0.698656 -0.705895 0.116585 -0.698652 -0.705899 0.116584 -0.708313 -0.705899 0 -0.708313 -0.705899 0 -0.698653 -0.705898 -0.116584 -0.698657 -0.705894 -0.116585 -0.669939 -0.705894 -0.22999 -0.669933 -0.7059 -0.229988 -0.622943 -0.705899 -0.33712 -0.62295 -0.70589 -0.337124 -0.558964 -0.705891 -0.435059 -0.558961 -0.705896 -0.435057 -0.479729 -0.705896 -0.521125 -0.479725 -0.705902 -0.52112 -0.387408 -0.705903 -0.592972 -0.387413 -0.705894 -0.59298 -0.284528 -0.705894 -0.648659 -0.284527 -0.705896 -0.648657 -0.173881 -0.705895 -0.686642 -0.173879 -0.705904 -0.686633 -0.0584913 -0.705904 -0.705888 -0.058493 -0.705889 -0.705903 -0.0584925 0.70589 -0.705903 -0.0584917 0.705904 -0.705888 -0.173879 0.705904 -0.686634 -0.173881 0.705895 -0.686642 -0.284527 0.705895 -0.648657 -0.284528 0.705894 -0.648658 -0.387413 0.705894 -0.59298 -0.387408 0.705903 -0.592972 -0.479725 0.705902 -0.52112 -0.479729 0.705896 -0.521125 -0.55896 0.705896 -0.435056 -0.558964 0.705891 -0.435059 -0.62295 0.705891 -0.337124 -0.622943 0.705899 -0.33712 -0.669933 0.7059 -0.229988 -0.669939 0.705894 -0.22999 -0.698656 0.705894 -0.116585 -0.698653 0.705899 -0.116584 -0.708313 0.705899 0 -0.708313 0.705899 0 -0.698652 0.705899 0.116584 -0.698656 0.705895 0.116585 -0.669938 0.705895 0.22999 -0.669932 0.705902 0.229988 -0.62294 0.705902 0.337118 -0.62295 0.70589 0.337124 -0.558964 0.705891 0.435059 -0.558957 0.705901 0.435054 -0.479726 0.705901 0.521121 -0.479725 0.705902 0.52112 -0.387408 0.705903 0.592972 -0.387413 0.705894 0.59298 -0.284528 0.705894 0.648659 -0.284527 0.705896 0.648657 -0.173881 0.705895 0.686642 -0.173879 0.705904 0.686633 -0.0584917 0.705904 0.705888 -0.0584919 0.705903 0.70589 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0825797 0 0.996584 -0.0825797 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401696 0 0.915773 -0.401696 0 0.915773 -0.546948 0 0.837166 -0.546948 0 0.837166 -0.677281 0 0.735724 -0.677281 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475947 -0.879474 0 0.475947 -0.945817 0 0.3247 -0.945817 0 0.3247 -0.986361 0 0.164594 -0.986361 0 0.164594 -1 0 0 -1 0 0 -0.986361 0 -0.164594 -0.986361 0 -0.164594 -0.945817 0 -0.3247 -0.945817 0 -0.3247 -0.879474 0 -0.475947 -0.879474 0 -0.475947 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677281 0 -0.735724 -0.677281 0 -0.735724 -0.546948 0 -0.837166 -0.546948 0 -0.837166 -0.401696 0 -0.915773 -0.401696 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.0825797 0 -0.996584 -0.0825797 0 -0.996584 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0825797 0 0.996584 -0.0825797 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401696 0 0.915773 -0.401696 0 0.915773 -0.546948 0 0.837166 -0.546948 0 0.837166 -0.677281 0 0.735724 -0.677281 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475947 -0.879474 0 0.475947 -0.945817 0 0.3247 -0.945817 0 0.3247 -0.986361 0 0.164594 -0.986361 0 0.164594 -1 0 0 -1 0 0 -0.986361 0 -0.164594 -0.986361 0 -0.164594 -0.945817 0 -0.3247 -0.945817 0 -0.3247 -0.879474 0 -0.475947 -0.879474 0 -0.475947 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677281 0 -0.735724 -0.677281 0 -0.735724 -0.546948 0 -0.837166 -0.546948 0 -0.837166 -0.401696 0 -0.915773 -0.401696 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.0825797 0 -0.996584 -0.0825797 0 -0.996584 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0825797 0 0.996584 -0.0825797 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401696 0 0.915773 -0.401696 0 0.915773 -0.546948 0 0.837166 -0.546948 0 0.837166 -0.677281 0 0.735724 -0.677281 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475947 -0.879474 0 0.475947 -0.945817 0 0.3247 -0.945817 0 0.3247 -0.986361 0 0.164594 -0.986361 0 0.164594 -1 0 0 -1 0 0 -0.986361 0 -0.164594 -0.986361 0 -0.164594 -0.945817 0 -0.3247 -0.945817 0 -0.3247 -0.879474 0 -0.475947 -0.879474 0 -0.475947 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837166 -0.546948 0 -0.837166 -0.401696 0 -0.915773 -0.401696 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.0825797 0 -0.996584 -0.0825797 0 -0.996584 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0825797 0 0.996584 -0.0825797 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401696 0 0.915773 -0.401696 0 0.915773 -0.546948 0 0.837166 -0.546948 0 0.837166 -0.677281 0 0.735724 -0.677281 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475947 -0.879474 0 0.475947 -0.945817 0 0.3247 -0.945817 0 0.3247 -0.986361 0 0.164594 -0.986361 0 0.164594 -1 0 0 -1 0 0 -0.986361 0 -0.164594 -0.986361 0 -0.164594 -0.945817 0 -0.3247 -0.945817 0 -0.3247 -0.879474 0 -0.475947 -0.879474 0 -0.475947 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677281 0 -0.735724 -0.677281 0 -0.735724 -0.546948 0 -0.837166 -0.546948 0 -0.837166 -0.401696 0 -0.915773 -0.401696 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.0825797 0 -0.996584 -0.0825797 0 -0.996584 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0825797 0 0.996584 -0.0825797 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401696 0 0.915773 -0.401696 0 0.915773 -0.546948 0 0.837166 -0.546948 0 0.837166 -0.677281 0 0.735724 -0.677281 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475947 -0.879474 0 0.475947 -0.945817 0 0.3247 -0.945817 0 0.3247 -0.986361 0 0.164594 -0.986361 0 0.164594 -1 0 0 -1 0 0 -0.986361 0 -0.164594 -0.986361 0 -0.164594 -0.945817 0 -0.3247 -0.945817 0 -0.3247 -0.879474 0 -0.475947 -0.879474 0 -0.475947 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677281 0 -0.735724 -0.677281 0 -0.735724 -0.546948 0 -0.837166 -0.546948 0 -0.837166 -0.401696 0 -0.915773 -0.401696 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.0825797 0 -0.996584 -0.0825797 0 -0.996584 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0825797 0 0.996584 -0.0825797 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401696 0 0.915773 -0.401696 0 0.915773 -0.546948 0 0.837166 -0.546948 0 0.837166 -0.677281 0 0.735724 -0.677281 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475947 -0.879474 0 0.475947 -0.945817 0 0.3247 -0.945817 0 0.3247 -0.986361 0 0.164594 -0.986361 0 0.164594 -1 0 0 -1 0 0 -0.986361 0 -0.164594 -0.986361 0 -0.164594 -0.945817 0 -0.3247 -0.945817 0 -0.3247 -0.879474 0 -0.475947 -0.879474 0 -0.475947 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837166 -0.546948 0 -0.837166 -0.401696 0 -0.915773 -0.401696 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.0825797 0 -0.996584 -0.0825797 0 -0.996584 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0825797 0 0.996584 -0.0825797 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401696 0 0.915773 -0.401696 0 0.915773 -0.546948 0 0.837166 -0.546948 0 0.837166 -0.677281 0 0.735724 -0.677281 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475947 -0.879474 0 0.475947 -0.945817 0 0.3247 -0.945817 0 0.3247 -0.986361 0 0.164594 -0.986361 0 0.164594 -1 0 0 -1 0 0 -0.986361 0 -0.164594 -0.986361 0 -0.164594 -0.945817 0 -0.3247 -0.945817 0 -0.3247 -0.879474 0 -0.475947 -0.879474 0 -0.475947 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.546948 0 -0.837166 -0.546948 0 -0.837166 -0.401696 0 -0.915773 -0.401696 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.0825797 0 -0.996584 -0.0825797 0 -0.996584 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0825797 0 0.996584 -0.0825797 0 0.996584 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.401696 0 0.915773 -0.401696 0 0.915773 -0.546948 0 0.837166 -0.546948 0 0.837166 -0.677281 0 0.735724 -0.677281 0 0.735724 -0.789141 0 0.614213 -0.789141 0 0.614213 -0.879474 0 0.475947 -0.879474 0 0.475947 -0.945817 0 0.3247 -0.945817 0 0.3247 -0.986361 0 0.164594 -0.986361 0 0.164594 -1 0 0 -1 0 0 -0.986361 0 -0.164594 -0.986361 0 -0.164594 -0.945817 0 -0.3247 -0.945817 0 -0.3247 -0.879474 0 -0.475947 -0.879474 0 -0.475947 -0.789141 0 -0.614213 -0.789141 0 -0.614213 -0.677281 0 -0.735724 -0.677281 0 -0.735724 -0.546948 0 -0.837166 -0.546948 0 -0.837166 -0.401696 0 -0.915773 -0.401696 0 -0.915773 -0.245485 0 -0.9694 -0.245485 0 -0.9694 -0.0825797 0 -0.996584 -0.0825797 0 -0.996584 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0584918 -0.705903 0.70589 -0.0584917 -0.705904 0.705888 -0.173879 -0.705904 0.686634 -0.173881 -0.705895 0.686642 -0.284527 -0.705895 0.648657 -0.284528 -0.705894 0.648658 -0.387413 -0.705894 0.59298 -0.387408 -0.705903 0.592972 -0.479725 -0.705902 0.52112 -0.479726 -0.7059 0.521121 -0.558957 -0.7059 0.435054 -0.558964 -0.705891 0.435059 -0.62295 -0.705891 0.337124 -0.622939 -0.705902 0.337118 -0.669931 -0.705902 0.229988 -0.669938 -0.705895 0.22999 -0.698656 -0.705895 0.116585 -0.698652 -0.705899 0.116584 -0.708313 -0.705899 0 -0.708313 -0.705899 0 -0.698653 -0.705898 -0.116584 -0.698657 -0.705894 -0.116585 -0.669939 -0.705894 -0.22999 -0.669933 -0.7059 -0.229988 -0.622943 -0.705899 -0.33712 -0.62295 -0.70589 -0.337124 -0.558964 -0.705891 -0.435059 -0.558961 -0.705896 -0.435057 -0.479729 -0.705896 -0.521125 -0.479725 -0.705902 -0.52112 -0.387408 -0.705903 -0.592972 -0.387413 -0.705894 -0.59298 -0.284528 -0.705894 -0.648659 -0.284527 -0.705896 -0.648657 -0.173881 -0.705895 -0.686642 -0.173879 -0.705904 -0.686633 -0.0584913 -0.705904 -0.705888 -0.058493 -0.705889 -0.705903 -0.0584927 0.705888 -0.705904 -0.0584919 0.705903 -0.70589 -0.17388 0.705902 -0.686635 -0.173881 0.705894 -0.686643 -0.284528 0.705894 -0.648659 -0.284529 0.705892 -0.64866 -0.387414 0.705892 -0.592981 -0.387409 0.705902 -0.592973 -0.479726 0.7059 -0.521121 -0.47973 0.705894 -0.521126 -0.558962 0.705895 -0.435057 -0.558966 0.70589 -0.43506 -0.622951 0.705889 -0.337125 -0.622944 0.705897 -0.33712 -0.669935 0.705898 -0.229989 -0.669941 0.705892 -0.229991 -0.698658 0.705893 -0.116585 -0.698654 0.705897 -0.116585 -0.708315 0.705897 0 -0.708315 0.705897 0 -0.698654 0.705897 0.116585 -0.698657 0.705894 0.116585 -0.669939 0.705894 0.22999 -0.669933 0.7059 0.229988 -0.622941 0.7059 0.337119 -0.622951 0.705889 0.337124 -0.558966 0.705889 0.43506 -0.558958 0.705899 0.435055 -0.479727 0.705899 0.521122 -0.479726 0.705901 0.521121 -0.387409 0.705901 0.592974 -0.387414 0.705892 0.592981 -0.284529 0.705892 0.64866 -0.284528 0.705894 0.648658 -0.173882 0.705894 0.686643 -0.173879 0.705903 0.686635 -0.0584918 0.705902 0.70589 -0.058492 0.705901 0.705891 -0.0584918 -0.705903 0.70589 -0.0584917 -0.705904 0.705888 -0.173879 -0.705904 0.686634 -0.173881 -0.705895 0.686642 -0.284527 -0.705895 0.648657 -0.284528 -0.705894 0.648658 -0.387413 -0.705894 0.59298 -0.387408 -0.705903 0.592972 -0.479725 -0.705902 0.52112 -0.479726 -0.7059 0.521121 -0.558957 -0.7059 0.435054 -0.558964 -0.705891 0.435059 -0.62295 -0.705891 0.337124 -0.622939 -0.705902 0.337118 -0.669931 -0.705902 0.229988 -0.669938 -0.705895 0.22999 -0.698656 -0.705895 0.116585 -0.698652 -0.705899 0.116584 -0.708313 -0.705899 0 -0.708313 -0.705899 0 -0.698653 -0.705898 -0.116584 -0.698657 -0.705894 -0.116585 -0.669939 -0.705894 -0.22999 -0.669933 -0.7059 -0.229988 -0.622943 -0.705899 -0.33712 -0.62295 -0.70589 -0.337124 -0.558964 -0.705891 -0.435059 -0.558961 -0.705896 -0.435057 -0.479729 -0.705896 -0.521125 -0.479725 -0.705902 -0.52112 -0.387408 -0.705903 -0.592972 -0.387413 -0.705894 -0.59298 -0.284528 -0.705894 -0.648659 -0.284527 -0.705896 -0.648657 -0.173881 -0.705895 -0.686642 -0.173879 -0.705904 -0.686633 -0.0584913 -0.705904 -0.705888 -0.058493 -0.705889 -0.705903 -0.0584925 0.70589 -0.705903 -0.0584917 0.705904 -0.705888 -0.173879 0.705904 -0.686634 -0.173881 0.705895 -0.686642 -0.284527 0.705895 -0.648657 -0.284528 0.705894 -0.648658 -0.387413 0.705894 -0.59298 -0.387408 0.705903 -0.592972 -0.479725 0.705902 -0.52112 -0.479729 0.705896 -0.521125 -0.55896 0.705896 -0.435056 -0.558964 0.705891 -0.435059 -0.62295 0.705891 -0.337124 -0.622943 0.705899 -0.33712 -0.669933 0.7059 -0.229988 -0.669939 0.705894 -0.22999 -0.698656 0.705894 -0.116585 -0.698653 0.705899 -0.116584 -0.708313 0.705899 0 -0.708313 0.705899 0 -0.698652 0.705899 0.116584 -0.698656 0.705895 0.116585 -0.669938 0.705895 0.22999 -0.669932 0.705902 0.229988 -0.62294 0.705902 0.337118 -0.62295 0.70589 0.337124 -0.558964 0.705891 0.435059 -0.558957 0.705901 0.435054 -0.479726 0.705901 0.521121 -0.479725 0.705902 0.52112 -0.387408 0.705903 0.592972 -0.387413 0.705894 0.59298 -0.284528 0.705894 0.648659 -0.284527 0.705896 0.648657 -0.173881 0.705895 0.686642 -0.173879 0.705904 0.686633 -0.0584917 0.705904 0.705888 -0.0584919 0.705903 0.70589 -0.0584918 -0.705903 0.70589 -0.0584917 -0.705904 0.705888 -0.173879 -0.705904 0.686634 -0.173881 -0.705895 0.686642 -0.284527 -0.705895 0.648657 -0.284528 -0.705894 0.648658 -0.387413 -0.705894 0.59298 -0.387408 -0.705903 0.592972 -0.479725 -0.705902 0.52112 -0.479726 -0.7059 0.521121 -0.558957 -0.7059 0.435054 -0.558964 -0.705891 0.435059 -0.62295 -0.705891 0.337124 -0.622939 -0.705902 0.337118 -0.669931 -0.705902 0.229988 -0.669938 -0.705895 0.22999 -0.698656 -0.705895 0.116585 -0.698652 -0.705899 0.116584 -0.708313 -0.705899 0 -0.708313 -0.705899 0 -0.698653 -0.705898 -0.116584 -0.698657 -0.705894 -0.116585 -0.669939 -0.705894 -0.22999 -0.669933 -0.7059 -0.229988 -0.622943 -0.705899 -0.33712 -0.62295 -0.70589 -0.337124 -0.558964 -0.705891 -0.435059 -0.558961 -0.705896 -0.435057 -0.479729 -0.705896 -0.521125 -0.479725 -0.705902 -0.52112 -0.387408 -0.705903 -0.592972 -0.387413 -0.705894 -0.59298 -0.284528 -0.705894 -0.648659 -0.284527 -0.705896 -0.648657 -0.173881 -0.705895 -0.686642 -0.173879 -0.705904 -0.686633 -0.0584913 -0.705904 -0.705888 -0.058493 -0.705889 -0.705903 -0.0584925 0.70589 -0.705903 -0.0584917 0.705904 -0.705888 -0.173879 0.705904 -0.686634 -0.173881 0.705895 -0.686642 -0.284527 0.705895 -0.648657 -0.284528 0.705894 -0.648658 -0.387413 0.705894 -0.59298 -0.387408 0.705903 -0.592972 -0.479725 0.705902 -0.52112 -0.479729 0.705896 -0.521125 -0.55896 0.705896 -0.435056 -0.558964 0.705891 -0.435059 -0.62295 0.705891 -0.337124 -0.622943 0.705899 -0.33712 -0.669933 0.7059 -0.229988 -0.669939 0.705894 -0.22999 -0.698656 0.705894 -0.116585 -0.698653 0.705899 -0.116584 -0.708313 0.705899 0 -0.708313 0.705899 0 -0.698652 0.705899 0.116584 -0.698656 0.705895 0.116585 -0.669938 0.705895 0.22999 -0.669932 0.705902 0.229988 -0.62294 0.705902 0.337118 -0.62295 0.70589 0.337124 -0.558964 0.705891 0.435059 -0.558957 0.705901 0.435054 -0.479726 0.705901 0.521121 -0.479725 0.705902 0.52112 -0.387408 0.705903 0.592972 -0.387413 0.705894 0.59298 -0.284528 0.705894 0.648659 -0.284527 0.705896 0.648657 -0.173881 0.705895 0.686642 -0.173879 0.705904 0.686633 -0.0584917 0.705904 0.705888 -0.0584919 0.705903 0.70589 -0.0584919 -0.705902 0.70589 -0.0584918 -0.705903 0.705889 -0.173879 -0.705903 0.686634 -0.173881 -0.705895 0.686643 -0.284528 -0.705894 0.648658 -0.284528 -0.705893 0.648659 -0.387413 -0.705893 0.592981 -0.387409 -0.705902 0.592973 -0.479726 -0.705901 0.521121 -0.479727 -0.7059 0.521122 -0.558958 -0.705899 0.435054 -0.558965 -0.70589 0.43506 -0.62295 -0.70589 0.337124 -0.62294 -0.705902 0.337118 -0.669932 -0.705901 0.229988 -0.669938 -0.705895 0.22999 -0.698657 -0.705894 0.116585 -0.698653 -0.705898 0.116584 -0.708314 -0.705898 0 -0.708314 -0.705898 0 -0.698653 -0.705898 -0.116585 -0.698657 -0.705894 -0.116585 -0.66994 -0.705893 -0.22999 -0.669934 -0.705899 -0.229989 -0.622943 -0.705898 -0.33712 -0.62295 -0.70589 -0.337124 -0.558965 -0.70589 -0.43506 -0.558961 -0.705895 -0.435057 -0.47973 -0.705895 -0.521125 -0.479725 -0.705902 -0.521121 -0.387408 -0.705902 -0.592973 -0.387414 -0.705893 -0.59298 -0.284528 -0.705893 -0.648659 -0.284527 -0.705895 -0.648657 -0.173882 -0.705894 -0.686643 -0.173879 -0.705903 -0.686634 -0.0584914 -0.705903 -0.705889 -0.058493 -0.705889 -0.705904 -0.0584925 0.70589 -0.705903 -0.0584917 0.705904 -0.705888 -0.173879 0.705904 -0.686634 -0.173881 0.705895 -0.686642 -0.284527 0.705895 -0.648657 -0.284528 0.705894 -0.648658 -0.387413 0.705894 -0.59298 -0.387408 0.705903 -0.592972 -0.479725 0.705902 -0.52112 -0.479729 0.705896 -0.521125 -0.55896 0.705896 -0.435056 -0.558964 0.705891 -0.435059 -0.62295 0.705891 -0.337124 -0.622943 0.705899 -0.33712 -0.669933 0.7059 -0.229988 -0.669939 0.705894 -0.22999 -0.698656 0.705894 -0.116585 -0.698653 0.705899 -0.116584 -0.708313 0.705899 0 -0.708313 0.705899 0 -0.698652 0.705899 0.116584 -0.698656 0.705895 0.116585 -0.669938 0.705895 0.22999 -0.669932 0.705902 0.229988 -0.62294 0.705902 0.337118 -0.62295 0.70589 0.337124 -0.558964 0.705891 0.435059 -0.558957 0.705901 0.435054 -0.479726 0.705901 0.521121 -0.479725 0.705902 0.52112 -0.387408 0.705903 0.592972 -0.387413 0.705894 0.59298 -0.284528 0.705894 0.648659 -0.284527 0.705896 0.648657 -0.173881 0.705895 0.686642 -0.173879 0.705904 0.686633 -0.0584917 0.705904 0.705888 -0.0584919 0.705903 0.70589 -0.0584919 -0.705902 0.70589 -0.0584918 -0.705904 0.705889 -0.173879 -0.705903 0.686634 -0.173881 -0.705895 0.686642 -0.284528 -0.705895 0.648658 -0.284528 -0.705894 0.648659 -0.387413 -0.705893 0.59298 -0.387408 -0.705903 0.592972 -0.479725 -0.705902 0.521121 -0.479726 -0.7059 0.521122 -0.558958 -0.7059 0.435054 -0.558964 -0.705891 0.43506 -0.62295 -0.70589 0.337124 -0.62294 -0.705902 0.337118 -0.669932 -0.705902 0.229988 -0.669938 -0.705895 0.22999 -0.698656 -0.705895 0.116585 -0.698653 -0.705898 0.116584 -0.708313 -0.705898 0 -0.708313 -0.705898 0 -0.698653 -0.705898 -0.116585 -0.698657 -0.705894 -0.116585 -0.669939 -0.705894 -0.22999 -0.669934 -0.7059 -0.229989 -0.622943 -0.705898 -0.33712 -0.62295 -0.70589 -0.337124 -0.558965 -0.705891 -0.43506 -0.558961 -0.705895 -0.435057 -0.47973 -0.705895 -0.521125 -0.479725 -0.705902 -0.52112 -0.387408 -0.705903 -0.592972 -0.387413 -0.705894 -0.59298 -0.284528 -0.705893 -0.648659 -0.284527 -0.705895 -0.648657 -0.173881 -0.705895 -0.686642 -0.173879 -0.705904 -0.686634 -0.0584914 -0.705904 -0.705889 -0.058493 -0.705889 -0.705903 -0.0584926 0.705889 -0.705903 -0.0584918 0.705904 -0.705889 -0.173879 0.705903 -0.686634 -0.173881 0.705895 -0.686642 -0.284528 0.705895 -0.648658 -0.284528 0.705894 -0.648659 -0.387413 0.705893 -0.59298 -0.387408 0.705903 -0.592972 -0.479725 0.705902 -0.52112 -0.479729 0.705895 -0.521125 -0.558961 0.705896 -0.435056 -0.558965 0.705891 -0.43506 -0.62295 0.70589 -0.337124 -0.622943 0.705898 -0.33712 -0.669934 0.705899 -0.229988 -0.669939 0.705894 -0.22999 -0.698657 0.705894 -0.116585 -0.698653 0.705898 -0.116584 -0.708313 0.705898 0 -0.708313 0.705898 0 -0.698653 0.705898 0.116585 -0.698656 0.705895 0.116585 -0.669938 0.705895 0.22999 -0.669932 0.705901 0.229988 -0.62294 0.705901 0.337119 -0.62295 0.70589 0.337124 -0.558965 0.705891 0.43506 -0.558957 0.7059 0.435054 -0.479726 0.7059 0.521121 -0.479725 0.705902 0.52112 -0.387408 0.705903 0.592972 -0.387413 0.705894 0.59298 -0.284528 0.705893 0.648659 -0.284527 0.705895 0.648657 -0.173881 0.705895 0.686642 -0.173879 0.705904 0.686634 -0.0584917 0.705904 0.705889 -0.0584919 0.705902 0.70589 -0.0584919 -0.705902 0.70589 -0.0584918 -0.705904 0.705889 -0.173879 -0.705903 0.686634 -0.173881 -0.705895 0.686642 -0.284528 -0.705895 0.648658 -0.284528 -0.705893 0.648659 -0.387413 -0.705893 0.59298 -0.387408 -0.705903 0.592972 -0.479725 -0.705901 0.521121 -0.479726 -0.7059 0.521122 -0.558958 -0.7059 0.435054 -0.558965 -0.705891 0.43506 -0.62295 -0.70589 0.337124 -0.62294 -0.705902 0.337118 -0.669932 -0.705901 0.229988 -0.669938 -0.705895 0.22999 -0.698657 -0.705894 0.116585 -0.698653 -0.705898 0.116584 -0.708314 -0.705898 0 -0.708314 -0.705898 0 -0.698653 -0.705898 -0.116585 -0.698657 -0.705894 -0.116585 -0.669939 -0.705894 -0.22999 -0.669934 -0.705899 -0.229989 -0.622943 -0.705898 -0.33712 -0.62295 -0.70589 -0.337124 -0.558965 -0.705891 -0.43506 -0.558961 -0.705895 -0.435057 -0.47973 -0.705895 -0.521125 -0.479725 -0.705902 -0.52112 -0.387408 -0.705903 -0.592973 -0.387414 -0.705893 -0.59298 -0.284528 -0.705893 -0.648659 -0.284527 -0.705895 -0.648657 -0.173881 -0.705895 -0.686643 -0.173879 -0.705904 -0.686634 -0.0584914 -0.705903 -0.705889 -0.058493 -0.705889 -0.705903 -0.0584926 0.705889 -0.705903 -0.0584918 0.705904 -0.705889 -0.173879 0.705903 -0.686634 -0.173881 0.705895 -0.686642 -0.284528 0.705895 -0.648658 -0.284528 0.705893 -0.648659 -0.387413 0.705893 -0.59298 -0.387408 0.705903 -0.592972 -0.479726 0.705901 -0.521121 -0.47973 0.705895 -0.521125 -0.558961 0.705896 -0.435056 -0.558965 0.705891 -0.43506 -0.62295 0.70589 -0.337124 -0.622943 0.705898 -0.33712 -0.669934 0.705899 -0.229989 -0.669939 0.705893 -0.229991 -0.698657 0.705894 -0.116585 -0.698653 0.705898 -0.116584 -0.708314 0.705898 0 -0.708314 0.705898 0 -0.698653 0.705898 0.116585 -0.698656 0.705895 0.116585 -0.669938 0.705895 0.22999 -0.669932 0.705901 0.229988 -0.62294 0.705901 0.337119 -0.62295 0.70589 0.337124 -0.558965 0.705891 0.43506 -0.558957 0.7059 0.435054 -0.479726 0.7059 0.521122 -0.479725 0.705902 0.52112 -0.387408 0.705903 0.592973 -0.387414 0.705893 0.59298 -0.284528 0.705893 0.648659 -0.284527 0.705895 0.648657 -0.173881 0.705895 0.686642 -0.173879 0.705904 0.686634 -0.0584917 0.705904 0.705889 -0.0584919 0.705902 0.70589 -0.0584919 -0.705902 0.70589 -0.0584918 -0.705904 0.705889 -0.173879 -0.705903 0.686634 -0.173881 -0.705895 0.686642 -0.284528 -0.705895 0.648658 -0.284528 -0.705893 0.648659 -0.387413 -0.705893 0.59298 -0.387408 -0.705903 0.592972 -0.479725 -0.705901 0.521121 -0.479726 -0.7059 0.521122 -0.558958 -0.7059 0.435054 -0.558965 -0.705891 0.43506 -0.62295 -0.70589 0.337124 -0.62294 -0.705902 0.337118 -0.669932 -0.705901 0.229988 -0.669938 -0.705895 0.22999 -0.698657 -0.705894 0.116585 -0.698653 -0.705898 0.116584 -0.708314 -0.705898 0 -0.708314 -0.705898 0 -0.698653 -0.705898 -0.116585 -0.698657 -0.705894 -0.116585 -0.669939 -0.705894 -0.22999 -0.669934 -0.705899 -0.229989 -0.622943 -0.705898 -0.33712 -0.62295 -0.70589 -0.337124 -0.558965 -0.705891 -0.43506 -0.558961 -0.705895 -0.435057 -0.47973 -0.705895 -0.521125 -0.479725 -0.705902 -0.52112 -0.387408 -0.705903 -0.592973 -0.387414 -0.705893 -0.59298 -0.284528 -0.705893 -0.648659 -0.284527 -0.705895 -0.648657 -0.173881 -0.705895 -0.686643 -0.173879 -0.705904 -0.686634 -0.0584914 -0.705903 -0.705889 -0.058493 -0.705889 -0.705903 -0.0584926 0.705889 -0.705903 -0.0584918 0.705904 -0.705889 -0.173879 0.705903 -0.686634 -0.173881 0.705895 -0.686642 -0.284528 0.705895 -0.648658 -0.284528 0.705894 -0.648659 -0.387413 0.705893 -0.59298 -0.387408 0.705903 -0.592972 -0.479725 0.705902 -0.52112 -0.479729 0.705895 -0.521125 -0.558961 0.705896 -0.435056 -0.558965 0.705891 -0.43506 -0.62295 0.70589 -0.337124 -0.622943 0.705898 -0.33712 -0.669934 0.705899 -0.229988 -0.669939 0.705894 -0.22999 -0.698657 0.705894 -0.116585 -0.698653 0.705898 -0.116584 -0.708313 0.705898 0 -0.708313 0.705898 0 -0.698653 0.705898 0.116585 -0.698656 0.705895 0.116585 -0.669938 0.705895 0.22999 -0.669932 0.705901 0.229988 -0.62294 0.705901 0.337119 -0.62295 0.70589 0.337124 -0.558965 0.705891 0.43506 -0.558957 0.7059 0.435054 -0.479726 0.7059 0.521121 -0.479725 0.705902 0.52112 -0.387408 0.705903 0.592972 -0.387413 0.705894 0.59298 -0.284528 0.705893 0.648659 -0.284527 0.705895 0.648657 -0.173881 0.705895 0.686642 -0.173879 0.705904 0.686634 -0.0584917 0.705904 0.705889 -0.0584919 0.705902 0.70589 -0.0584919 -0.705902 0.70589 -0.0584918 -0.705904 0.705889 -0.173879 -0.705903 0.686634 -0.173881 -0.705895 0.686642 -0.284528 -0.705895 0.648658 -0.284528 -0.705894 0.648659 -0.387413 -0.705893 0.59298 -0.387408 -0.705903 0.592972 -0.479725 -0.705902 0.521121 -0.479726 -0.7059 0.521122 -0.558958 -0.7059 0.435054 -0.558964 -0.705891 0.43506 -0.62295 -0.70589 0.337124 -0.62294 -0.705902 0.337118 -0.669932 -0.705902 0.229988 -0.669938 -0.705895 0.22999 -0.698656 -0.705895 0.116585 -0.698653 -0.705898 0.116584 -0.708313 -0.705898 0 -0.708313 -0.705898 0 -0.698653 -0.705898 -0.116585 -0.698657 -0.705894 -0.116585 -0.669939 -0.705894 -0.22999 -0.669934 -0.7059 -0.229989 -0.622943 -0.705898 -0.33712 -0.62295 -0.70589 -0.337124 -0.558965 -0.705891 -0.43506 -0.558961 -0.705895 -0.435057 -0.47973 -0.705895 -0.521125 -0.479725 -0.705902 -0.52112 -0.387408 -0.705903 -0.592972 -0.387413 -0.705894 -0.59298 -0.284528 -0.705893 -0.648659 -0.284527 -0.705895 -0.648657 -0.173881 -0.705895 -0.686642 -0.173879 -0.705904 -0.686634 -0.0584914 -0.705904 -0.705889 -0.058493 -0.705889 -0.705903 -0.0584926 0.705889 -0.705904 -0.0584918 0.705903 -0.705889 -0.173879 0.705903 -0.686634 -0.173881 0.705895 -0.686643 -0.284528 0.705894 -0.648658 -0.284528 0.705893 -0.648659 -0.387413 0.705893 -0.592981 -0.387409 0.705902 -0.592973 -0.479726 0.705901 -0.521121 -0.47973 0.705895 -0.521125 -0.558961 0.705895 -0.435057 -0.558965 0.70589 -0.43506 -0.62295 0.70589 -0.337124 -0.622943 0.705898 -0.33712 -0.669934 0.705899 -0.229989 -0.66994 0.705893 -0.229991 -0.698657 0.705894 -0.116585 -0.698653 0.705898 -0.116584 -0.708314 0.705898 0 -0.708314 0.705898 0 -0.698653 0.705898 0.116585 -0.698657 0.705894 0.116585 -0.669939 0.705894 0.22999 -0.669932 0.705901 0.229988 -0.62294 0.705901 0.337119 -0.622951 0.705889 0.337124 -0.558965 0.70589 0.43506 -0.558958 0.7059 0.435054 -0.479726 0.7059 0.521122 -0.479725 0.705902 0.521121 -0.387408 0.705902 0.592973 -0.387414 0.705893 0.59298 -0.284528 0.705893 0.648659 -0.284527 0.705895 0.648657 -0.173882 0.705894 0.686643 -0.173879 0.705903 0.686634 -0.0584918 0.705903 0.705889 -0.0584919 0.705902 0.70589 0 -0.980785 0.195091 0 -0.980785 0.195091 0 -0.83147 0.55557 0 -0.83147 0.55557 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.19509 0.980785 0 -0.19509 0.980785 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0.0146606 -0.19507 -0.98068 -0.0110512 -0.608724 -0.793305 0 -0.55557 -0.83147 0 -0.793353 -0.608761 -0.00739418 -0.831447 -0.555555 0.0110512 -0.965867 -0.258803 0 -0.980785 -0.195091 0 -0.980785 0.195091 0 -0.980785 0.195091 0 -0.83147 0.55557 0 -0.83147 0.55557 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.19509 0.980785 0 -0.19509 0.980785 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 -0.173881 -0.705898 0.686639 -0.0584923 -0.705898 0.705894 -0.0584923 -0.705897 0.705895 -0.387411 -0.705898 0.592977 -0.314021 -0.706879 0.633809 -0.369134 -0.394399 0.84154 -0.260666 -0.706723 0.65772 -0.173881 -0.705897 0.68664 -0.499884 -0.645805 0.577106 -0.624503 -0.387015 0.678392 -0.440735 -0.706745 0.553411 -0.434434 -0.707109 0.55791 -0.38741 -0.705899 0.592976 -0.646446 -0.557284 0.521096 -0.727332 -0.387961 0.566105 -0.534068 -0.703561 0.4688 -0.520856 -0.707106 0.478237 -0.500313 -0.706807 0.500111 -0.646194 -0.707105 0.287114 -0.659376 -0.669695 0.341659 -0.774918 -0.4729 0.419365 -0.60068 -0.707014 0.373249 -0.576486 -0.70683 0.409946 -0.656497 -0.706927 0.263183 -0.862976 -0.40927 0.29626 -0.807881 -0.524606 0.268546 -0.698653 -0.705898 -0.116585 -0.708314 -0.705898 0 -0.708314 -0.705898 0 -0.698653 -0.705898 0.116584 -0.698657 -0.705894 0.116585 -0.685245 -0.707105 0.174479 -0.684573 -0.703571 0.190654 -0.646195 -0.707104 -0.287115 -0.656498 -0.706926 -0.263183 -0.862976 -0.40927 -0.29626 -0.676251 -0.706652 -0.208151 -0.698657 -0.705894 -0.116585 -0.659377 -0.669694 -0.34166 -0.77492 -0.472897 -0.419366 -0.609565 -0.697893 -0.376 -0.534069 -0.703559 -0.468801 -0.646448 -0.557281 -0.521097 -0.727333 -0.387957 -0.566106 -0.576486 -0.70683 -0.409945 -0.593238 -0.707103 -0.384803 -0.38741 -0.705899 -0.592975 -0.434434 -0.707109 -0.55791 -0.440735 -0.706745 -0.553411 -0.499885 -0.645804 -0.577107 -0.624503 -0.387017 -0.678391 -0.500313 -0.706807 -0.500111 -0.520851 -0.707106 -0.478243 -0.369134 -0.394399 -0.84154 -0.314021 -0.706879 -0.633809 -0.387411 -0.705898 -0.592977 -0.176696 -0.689412 -0.702488 -0.228528 -0.707107 -0.669159 -0.260666 -0.706723 -0.65772 -0.173881 -0.705898 -0.686639 -0.0584918 -0.705898 -0.705894 -0.0584928 -0.705891 -0.705901 -0.0584925 0.70589 -0.705903 -0.0584917 0.705904 -0.705888 -0.173879 0.705904 -0.686634 -0.173881 0.705895 -0.686642 -0.284527 0.705895 -0.648657 -0.284528 0.705894 -0.648658 -0.387413 0.705894 -0.59298 -0.387408 0.705903 -0.592972 -0.479725 0.705902 -0.52112 -0.479729 0.705896 -0.521125 -0.55896 0.705896 -0.435056 -0.558964 0.705891 -0.435059 -0.62295 0.705891 -0.337124 -0.622943 0.705899 -0.33712 -0.669933 0.7059 -0.229988 -0.669939 0.705894 -0.22999 -0.698656 0.705894 -0.116585 -0.698653 0.705899 -0.116584 -0.708313 0.705899 0 -0.708313 0.705899 0 -0.698652 0.705899 0.116584 -0.698656 0.705895 0.116585 -0.669938 0.705895 0.22999 -0.669932 0.705902 0.229988 -0.62294 0.705902 0.337118 -0.62295 0.70589 0.337124 -0.558964 0.705891 0.435059 -0.558957 0.705901 0.435054 -0.479726 0.705901 0.521121 -0.479725 0.705902 0.52112 -0.387408 0.705903 0.592972 -0.387413 0.705894 0.59298 -0.284528 0.705894 0.648659 -0.284527 0.705896 0.648657 -0.173881 0.705895 0.686642 -0.173879 0.705904 0.686633 -0.0584917 0.705904 0.705888 -0.0584919 0.705903 0.70589 0.34202 0.939693 0 0.34202 0.939693 0 0.331668 0.244169 -0.911251 0.331668 0.244169 -0.911251 0.331668 0.667082 -0.667082 0.331668 0.667082 -0.667082 0.331668 0.911251 -0.244169 0.331668 0.911251 -0.244169 0.331668 0.911251 0.244169 0.331668 0.911251 0.244169 0.331668 0.667082 0.667082 0.331668 0.667082 0.667082 0.331668 0.244169 0.911251 0.331668 0.244169 0.911251 0.34202 0 -0.939693 0.34202 0 -0.939693 0.34202 0 0.939693 0.34202 0 0.939693 0.331668 -0.911251 -0.244169 0.331668 -0.911251 -0.244169 0.331668 -0.667082 -0.667082 0.331668 -0.667082 -0.667082 0.331668 -0.244169 -0.911251 0.331668 -0.244169 -0.911251 0.336198 -0.183734 0.923695 0.336198 -0.183734 0.923695 0.336198 -0.523231 0.783071 0.336198 -0.523231 0.783071 0.336198 -0.783071 0.523231 0.336198 -0.783071 0.523231 0.336198 -0.923695 0.183735 0.336198 -0.923695 0.183734 0.34202 -0.939693 0 0.34202 -0.939693 0 -0.34202 -0.939693 0 -0.34202 -0.939693 0 -0.331668 -0.911251 -0.244169 -0.331668 -0.244169 -0.911251 -0.331668 -0.244169 -0.911251 -0.339432 -0.572619 -0.746253 -0.258733 -0.683029 -0.683029 -0.339432 -0.746252 -0.57262 -0.331667 -0.911251 -0.244169 -0.336197 -0.923695 0.183735 -0.336197 -0.923695 0.183735 -0.336197 -0.783071 0.523231 -0.336197 -0.783071 0.523231 -0.336197 -0.523232 0.783071 -0.336197 -0.523231 0.783071 -0.336197 -0.183734 0.923696 -0.336197 -0.183734 0.923696 -0.34202 0 -0.939693 -0.34202 0 -0.939693 -0.34202 0 0.939693 -0.34202 0 0.939693 -0.331667 0.911251 -0.244169 -0.331667 0.911251 -0.244169 -0.331667 0.667082 -0.667082 -0.331668 0.667082 -0.667082 -0.331668 0.244169 -0.911251 -0.331668 0.244169 -0.911251 -0.331668 0.244169 0.911251 -0.331668 0.244169 0.911251 -0.331668 0.667082 0.667082 -0.331667 0.667082 0.667082 -0.331667 0.911251 0.244169 -0.331667 0.911251 0.244169 -0.342019 0.939693 0 -0.342019 0.939693 0 -0.654491 -0.705402 -0.272118 -0.654492 -0.705402 -0.272118 -0.588916 -0.705402 -0.394444 -0.588915 -0.705402 -0.394444 -0.500758 -0.705402 -0.501646 -0.500759 -0.705402 -0.501646 -0.393401 -0.705402 -0.589613 -0.393401 -0.705402 -0.589613 -0.270959 -0.705402 -0.654973 -0.270959 -0.705402 -0.654972 -0.138128 -0.705402 -0.695218 -0.138127 -0.705403 -0.695218 0 -0.705403 -0.708807 0 -0.705403 -0.708807 0.138127 -0.705402 -0.695218 0.138127 -0.705402 -0.695218 0.270959 -0.705402 -0.654972 0.270959 -0.705402 -0.654973 0.393401 -0.705402 -0.589613 0.393401 -0.705402 -0.589613 0.500759 -0.705402 -0.501646 0.500759 -0.705402 -0.501647 0.588916 -0.705402 -0.394444 0.588916 -0.705402 -0.394444 0.654492 -0.705402 -0.272118 0.654491 -0.705403 -0.272118 -0.70321 -0.703212 -0.104829 -0.70321 -0.703211 -0.104828 0.70321 -0.703211 -0.104829 0.703211 -0.703211 -0.10483 -0.707106 -0.707108 0 -0.707106 -0.707108 0 0.707107 -0.707107 0 0.707107 -0.707107 0 -0.70321 -0.703211 0.104829 -0.70321 -0.703212 0.104828 0.703211 -0.703211 0.104829 0.70321 -0.703212 0.104829 0.656164 -0.705638 0.267439 0.656165 -0.705637 0.267439 0.596876 -0.705637 0.381857 0.596877 -0.705637 0.381857 0.517846 -0.705637 0.483644 0.517845 -0.705638 0.483644 0.421687 -0.705638 0.569434 0.421687 -0.705638 0.569435 0.311581 -0.705638 0.636391 0.311581 -0.705638 0.636391 0.191169 -0.705637 0.682298 0.191168 -0.705638 0.682297 0.0644331 -0.705638 0.705637 0.0644334 -0.705637 0.705637 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.0980171 0 0.995185 -0.0980171 0 0.995185 -0.290285 0 0.95694 -0.290285 0 0.95694 -0.471397 0 0.881921 -0.471397 0 0.881921 -0.634393 0 0.77301 -0.634393 0 0.77301 -0.77301 0 0.634393 -0.77301 0 0.634393 -0.881921 0 0.471397 -0.881921 0 0.471397 -0.95694 0 0.290285 -0.95694 0 0.290285 -0.995185 0 0.0980171 -0.995185 0 0.0980171 -0.995185 0 -0.0980171 -0.995185 0 -0.0980171 -0.95694 0 -0.290285 -0.95694 0 -0.290285 -0.881921 0 -0.471397 -0.881921 0 -0.471397 -0.77301 0 -0.634393 -0.77301 0 -0.634393 -0.634393 0 -0.77301 -0.634393 0 -0.77301 -0.471397 0 -0.881921 -0.471397 0 -0.881921 -0.290285 0 -0.95694 -0.290285 0 -0.95694 -0.0980171 0 -0.995185 -0.0980171 0 -0.995185 -0.0575225 0.809687 -0.584036 -0.0575225 0.809687 -0.584036 -0.170357 0.809687 -0.561592 -0.170357 0.809687 -0.561592 -0.276645 0.809687 -0.517566 -0.276645 0.809687 -0.517566 -0.372301 0.809687 -0.45365 -0.372301 0.809687 -0.453651 -0.45365 0.809687 -0.372301 -0.453651 0.809687 -0.372302 -0.517566 0.809687 -0.276645 -0.517566 0.809687 -0.276645 -0.561592 0.809687 -0.170357 -0.561592 0.809687 -0.170357 -0.584036 0.809687 -0.0575227 -0.584036 0.809687 -0.0575224 -0.584036 0.809687 0.0575227 -0.584036 0.809687 0.0575225 -0.561592 0.809687 0.170357 -0.561592 0.809687 0.170357 -0.517566 0.809687 0.276645 -0.517566 0.809687 0.276645 -0.453651 0.809687 0.372301 -0.45365 0.809687 0.372301 -0.372301 0.809687 0.45365 -0.372302 0.809687 0.453651 -0.276645 0.809687 0.517566 -0.276645 0.809687 0.517566 -0.170357 0.809687 0.561592 -0.170357 0.809687 0.561592 -0.0575225 0.809687 0.584036 -0.0575226 0.809687 0.584036 -0.0980171 0 0.995185 -0.0980171 0 0.995185 -0.290285 0 0.95694 -0.290285 0 0.95694 -0.471397 0 0.881921 -0.471397 0 0.881921 -0.634393 0 0.77301 -0.634393 0 0.77301 -0.77301 0 0.634393 -0.77301 0 0.634393 -0.881921 0 0.471397 -0.881921 0 0.471397 -0.95694 0 0.290285 -0.95694 0 0.290285 -0.995185 0 0.0980174 -0.995185 0 0.0980174 -0.995185 0 -0.0980174 -0.995185 0 -0.0980174 -0.95694 0 -0.290285 -0.95694 0 -0.290285 -0.881921 0 -0.471397 -0.881921 0 -0.471397 -0.77301 0 -0.634393 -0.77301 0 -0.634393 -0.634393 0 -0.77301 -0.634393 0 -0.77301 -0.471397 0 -0.881921 -0.471397 0 -0.881921 -0.290285 0 -0.95694 -0.290285 0 -0.95694 -0.0980171 0 -0.995185 -0.0980171 0 -0.995185 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0694756 -0.705398 0.705398 -0.0694754 -0.705402 0.705394 -0.205756 -0.705402 0.678287 -0.205757 -0.705397 0.678291 -0.334132 -0.705397 0.625116 -0.334131 -0.705398 0.625116 -0.449665 -0.705398 0.547919 -0.449664 -0.705399 0.547918 -0.547918 -0.705398 0.449665 -0.547919 -0.705398 0.449665 -0.625116 -0.705398 0.334131 -0.625118 -0.705396 0.334132 -0.678292 -0.705396 0.205758 -0.678292 -0.705396 0.205757 -0.705401 -0.705396 0.0694761 -0.705392 -0.705405 0.0694749 -0.705392 -0.705405 -0.0694752 -0.705401 -0.705396 -0.0694758 -0.678292 -0.705396 -0.205758 -0.678291 -0.705397 -0.205757 -0.625116 -0.705397 -0.334132 -0.625116 -0.705398 -0.334131 -0.547919 -0.705398 -0.449665 -0.547921 -0.705395 -0.449667 -0.449668 -0.705394 -0.547922 -0.449665 -0.705398 -0.547919 -0.334131 -0.705398 -0.625116 -0.334132 -0.705397 -0.625116 -0.205757 -0.705397 -0.678291 -0.205758 -0.705395 -0.678293 -0.0694759 -0.705395 -0.705401 -0.0694755 -0.705398 -0.705398 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694746 -0.508588 0.694749 -0.508589 -0.508591 0.694745 -0.508591 -0.694749 0.694745 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186156 -0.694748 0.694745 0.186157 -0.50859 0.694746 0.508591 -0.508588 0.694749 0.508588 -0.186157 0.694748 0.694745 -0.186157 0.694747 0.694746 -0.186156 0.69475 -0.694744 -0.186157 0.694748 -0.694745 -0.508589 0.694748 -0.508589 -0.508589 0.694748 -0.508589 -0.694748 0.694745 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694748 0.694745 0.186157 -0.508589 0.694748 0.508589 -0.508589 0.694748 0.508589 -0.186156 0.694748 0.694746 -0.186156 0.69475 0.694744 -0.159331 0.698074 -0.698074 -0.159332 0.698072 -0.698075 -0.446436 0.698072 -0.559812 -0.446432 0.698078 -0.559809 -0.645115 0.698076 -0.310671 -0.645118 0.698073 -0.310672 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645118 0.698073 0.310673 -0.645115 0.698076 0.310671 -0.446433 0.698078 0.559808 -0.446434 0.698075 0.559811 -0.15933 0.698075 0.698072 -0.15933 0.698074 0.698074 -0.186157 0.694747 0.694747 -0.191427 0.509847 0.838696 -0.914471 0.322028 0.245032 -0.330525 0.706861 0.625381 -0.465274 0.700863 0.540658 -0.646044 0.406513 0.646045 -0.585055 0.706118 0.398883 -0.661912 0.703126 0.259781 -0.704873 0.704873 0.0794204 -0.704873 0.704873 -0.0794204 -0.914471 0.322028 -0.245032 -0.661914 0.703124 -0.259782 -0.585056 0.706114 -0.398888 -0.646044 0.406513 -0.646045 -0.159331 0.698074 -0.698074 -0.216617 0.547288 -0.808426 -0.330523 0.706858 -0.625385 -0.465277 0.70086 -0.54066 -0.15933 0.698077 -0.69807 -0.159331 0.698075 -0.698072 -0.446434 0.698075 -0.559811 -0.446435 0.698074 -0.559812 -0.645118 0.698073 -0.310672 -0.645117 0.698074 -0.310672 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645117 0.698074 0.310672 -0.645118 0.698073 0.310672 -0.446434 0.698074 0.559812 -0.446434 0.698075 0.559811 -0.159331 0.698075 0.698072 -0.159331 0.698077 0.69807 -0.159331 0.698074 -0.698074 -0.159331 0.698073 -0.698074 -0.446435 0.698074 -0.559811 -0.446435 0.698074 -0.559811 -0.645118 0.698073 -0.310672 -0.645114 0.698077 -0.310671 -0.716022 0.698077 0 -0.716022 0.698077 0 -0.645114 0.698077 0.31067 -0.645118 0.698072 0.310673 -0.446436 0.698073 0.559812 -0.446435 0.698074 0.559811 -0.159331 0.698074 0.698073 -0.159331 0.698075 0.698073 -0.186157 0.694747 -0.694747 -0.186157 0.694746 -0.694747 -0.508591 0.694744 -0.508591 -0.508591 0.694745 -0.508591 -0.694749 0.694745 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694748 0.694745 0.186157 -0.50859 0.694746 0.50859 -0.508591 0.694745 0.508591 -0.186157 0.694747 0.694746 -0.186156 0.694748 0.694745 -0.186156 0.694747 -0.694747 -0.186157 0.694745 -0.694749 -0.508591 0.694745 -0.508591 -0.508589 0.694748 -0.508589 -0.694745 0.694748 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694745 0.694748 0.186157 -0.508589 0.694748 0.508589 -0.508589 0.694748 0.508589 -0.186157 0.694748 0.694745 -0.186157 0.694747 0.694747 -0.15933 0.698077 -0.69807 -0.159331 0.698075 -0.698072 -0.446433 0.698075 -0.559811 -0.446436 0.698072 -0.559813 -0.645118 0.698073 -0.310672 -0.645115 0.698076 -0.310671 -0.716025 0.698075 0 -0.716025 0.698075 0 -0.645117 0.698073 0.310672 -0.645117 0.698073 0.310672 -0.446436 0.698072 0.559812 -0.446436 0.698072 0.559812 -0.159331 0.698072 0.698076 -0.159331 0.698074 0.698074 -0.186156 0.69475 -0.694744 -0.186157 0.694748 -0.694745 -0.508589 0.694748 -0.508589 -0.508591 0.694745 -0.508591 -0.694746 0.694747 -0.186157 -0.694745 0.694748 -0.186156 -0.694745 0.694748 0.186157 -0.694745 0.694749 0.186156 -0.508587 0.69475 0.508588 -0.508587 0.69475 0.508588 -0.186157 0.694751 0.694742 -0.186157 0.694747 0.694747 -0.186156 0.694747 -0.694747 -0.186157 0.694745 -0.694749 -0.508591 0.694745 -0.508591 -0.508591 0.694745 -0.508591 -0.694749 0.694745 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186156 -0.694749 0.694745 0.186157 -0.508591 0.694745 0.508591 -0.508589 0.694748 0.508589 -0.186157 0.694748 0.694745 -0.186157 0.694747 0.694747 -0.186157 0.694747 -0.694747 -0.186156 0.694748 -0.694745 -0.508587 0.694749 -0.508588 -0.508591 0.694745 -0.508591 -0.694749 0.694745 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694748 0.694745 0.186157 -0.50859 0.694746 0.508591 -0.508587 0.69475 0.508587 -0.186156 0.694749 0.694745 -0.186156 0.694748 0.694745 0.707245 0.706225 0.0324278 0.707245 0.706225 0.0324278 0.704756 0.706225 -0.06757 0.704756 0.706225 -0.06757 0.660123 0.697267 -0.279385 0.660123 0.697267 -0.279385 0.463018 0.697266 -0.547206 0.463018 0.697267 -0.547206 0.21536 0.702507 -0.67831 0.196368 0.532254 -0.823496 0.0518848 0.706159 -0.70615 -0.275197 0.704311 -0.654379 -0.275196 0.704312 -0.654379 -0.429111 0.704312 -0.565517 -0.429111 0.704311 -0.565517 -0.595399 0.699239 -0.395682 -0.595397 0.699242 -0.395681 -0.704908 0.699241 -0.119024 -0.704908 0.699241 -0.119024 -0.692307 0.699241 0.17825 -0.692307 0.69924 0.178251 -0.559778 0.69924 0.444648 -0.559778 0.69924 0.444648 -0.410896 0.706224 0.576552 -0.410896 0.706224 0.576552 -0.325539 0.706224 0.628707 -0.325539 0.706224 0.628706 -0.154159 0.700709 0.696593 -0.154159 0.70071 0.696592 0.114208 0.70071 0.704246 0.114209 0.700709 0.704246 0.366404 0.700709 0.612172 0.366404 0.700709 0.612172 0.470394 0.707109 0.527945 0.399469 0.700497 0.591379 0.495783 0.129602 0.858721 0.323049 0.616932 0.717659 0.243657 0.706917 0.664003 0.346954 0.700711 0.6234 0.346955 0.70071 0.623401 0.552791 0.70071 0.451031 0.552791 0.700709 0.451031 0.680347 0.700709 0.21479 0.680347 0.700709 0.21479 0.325539 0.706224 0.628706 0.325539 0.706224 0.628707 0.410896 0.706224 0.576552 0.410896 0.706224 0.576552 0.559778 0.69924 0.444648 0.559778 0.69924 0.444648 0.692308 0.69924 0.178251 0.692307 0.699241 0.178251 0.704908 0.699241 -0.119024 0.704908 0.699241 -0.119024 0.595397 0.699242 -0.395681 0.595397 0.699241 -0.395681 0.42911 0.704312 -0.565516 0.253797 0.705553 -0.661651 0.207558 0.844592 -0.493543 0.333976 0.706931 -0.623466 0.42911 0.704312 -0.565516 0.0965206 0.703807 -0.703804 0.0965216 0.70381 -0.703801 -0.704756 0.706225 -0.0675699 -0.704756 0.706225 -0.06757 -0.707245 0.706225 0.0324278 -0.707245 0.706225 0.0324278 -0.680347 0.700709 0.21479 -0.680347 0.700709 0.21479 -0.552791 0.700709 0.451031 -0.552791 0.70071 0.451031 -0.346954 0.70071 0.623401 -0.346954 0.70071 0.6234 -0.357274 0.699587 0.618816 -0.357273 0.699588 0.618815 -0.366404 0.700709 0.612172 -0.366404 0.70071 0.612172 -0.114208 0.70071 0.704246 -0.114209 0.70071 0.704246 0.154159 0.70071 0.696592 0.154159 0.700709 0.696593 -0.381706 0.706225 0.596278 -0.381705 0.706225 0.596278 -0.29386 0.706225 0.644121 -0.293861 0.706225 0.644121 0.640369 0.699241 0.317789 0.64037 0.699239 0.31779 0.455533 0.69924 0.550957 0.455533 0.69924 0.550957 0.191784 0.69924 0.688681 -0.126661 0.701415 0.701408 -0.113965 0.632524 0.766111 0.0219078 0.706939 0.706935 0.191784 0.69924 0.688682 0.704306 0.704313 0.0888625 0.704307 0.704312 0.0888625 0.704307 0.704312 -0.0888626 0.704306 0.704313 -0.0888624 0.637754 0.698436 -0.324742 0.637755 0.698435 -0.324742 0.43873 0.698435 -0.565424 0.438731 0.698433 -0.565426 0.156156 0.698434 -0.698431 0.156156 0.698435 -0.698429 -0.293861 0.706224 -0.644122 -0.293861 0.706225 -0.644121 -0.381705 0.706225 -0.596278 -0.381706 0.706225 -0.596278 -0.526187 0.700709 -0.481802 -0.526187 0.70071 -0.481802 -0.666999 0.70071 -0.253215 -0.666999 0.70071 -0.253215 -0.713358 0.70071 0.0112293 -0.713358 0.700709 0.0112293 -0.714547 0.699587 0 -0.714547 0.699587 0 -0.713358 0.700709 -0.0112293 -0.713358 0.70071 -0.0112293 -0.666999 0.70071 0.253215 -0.666999 0.70071 0.253215 -0.526187 0.70071 0.481802 -0.526187 0.700709 0.481802 -0.707245 0.706225 -0.0324278 -0.707245 0.706225 -0.0324278 -0.704756 0.706225 0.06757 -0.704756 0.706225 0.06757 0.0449706 0.699242 0.71347 0.120896 0.456377 0.881535 -0.0518849 0.706156 0.706153 -0.249377 0.699239 0.669982 -0.664965 0.699241 0.262458 -0.664964 0.699241 0.262457 -0.500523 0.699242 0.510429 -0.500524 0.69924 0.510431 -0.349753 0.706686 0.615035 -0.251585 0.555703 0.792401 0.275196 0.704313 0.654378 0.275196 0.704312 0.654379 0.42911 0.704312 0.565516 0.429109 0.704314 0.565515 0.595396 0.699242 0.395681 0.595398 0.69924 0.395681 0.704908 0.699241 0.119024 0.704908 0.699241 0.119024 0.692306 0.699242 -0.17825 0.692307 0.69924 -0.178251 0.559778 0.69924 -0.444648 0.559778 0.69924 -0.444648 0.410896 0.706224 -0.576552 0.410895 0.706225 -0.576551 0.325539 0.706225 -0.628706 0.325539 0.706224 -0.628706 0.144414 0.699697 -0.699692 0.144414 0.699698 -0.699691 -0.357274 0.699587 -0.618816 -0.357274 0.699587 -0.618817 -0.346955 0.70071 -0.623401 -0.346954 0.70071 -0.623401 -0.55279 0.70071 -0.451031 -0.552791 0.700709 -0.451031 -0.680347 0.700709 -0.21479 -0.680346 0.70071 -0.21479 -0.325539 0.706224 -0.628706 -0.325539 0.706225 -0.628706 -0.410895 0.706225 -0.576551 -0.410896 0.706224 -0.576552 -0.559778 0.69924 -0.444648 -0.559778 0.69924 -0.444648 -0.692308 0.69924 -0.178251 -0.692306 0.699242 -0.178251 -0.704908 0.699241 0.119024 -0.704908 0.699241 0.119024 -0.595398 0.69924 0.395682 -0.595398 0.699241 0.395681 -0.42911 0.704313 0.565516 -0.429111 0.704312 0.565517 -0.275196 0.704312 0.654379 -0.275196 0.704313 0.654378 0.664965 0.699241 0.262457 0.664964 0.699241 0.262457 0.500522 0.699242 0.51043 0.500524 0.69924 0.51043 0.349753 0.706686 0.615035 0.279248 0.599307 0.750235 -0.0965214 0.703809 0.703801 -0.0518721 0.56572 0.822964 0.051885 0.706156 0.706153 0.215361 0.702506 0.67831 0.704756 0.706225 0.06757 0.704756 0.706224 0.06757 0.707245 0.706225 -0.0324278 0.707245 0.706225 -0.0324278 0.680346 0.70071 -0.21479 0.680347 0.700709 -0.21479 0.552791 0.700709 -0.451031 0.552791 0.70071 -0.451031 0.346955 0.70071 -0.623401 0.346955 0.70071 -0.623401 0.357274 0.699587 -0.618816 0.357274 0.699587 -0.618816 0.370514 0.701187 -0.609144 0.370514 0.701188 -0.609143 0.129156 0.701188 -0.701181 0.129156 0.701188 -0.701181 0.381706 0.706225 -0.596278 0.381705 0.706225 -0.596277 0.293861 0.706225 -0.644121 0.293861 0.706224 -0.644122 0.126661 0.701414 -0.70141 0.126661 0.701415 -0.701409 -0.704306 0.704313 -0.0888625 -0.704307 0.704312 -0.0888625 -0.704307 0.704312 0.0888626 -0.704306 0.704313 0.0888624 0.105188 0.699241 0.707105 -0.640369 0.699241 0.317789 -0.64037 0.699239 0.31779 -0.455533 0.69924 0.550957 -0.455533 0.69924 0.550956 -0.191784 0.69924 0.688681 -0.191784 0.69924 0.688682 -0.0219078 0.706939 0.706935 0.139979 0.616063 0.775159 0.293861 0.706225 0.644121 0.293861 0.706225 0.644121 0.381705 0.706225 0.596278 0.381706 0.706225 0.596278 0.526187 0.70071 0.481802 0.526188 0.700709 0.481803 0.667 0.700709 0.253216 0.666999 0.70071 0.253216 0.713358 0.70071 -0.0112293 0.713358 0.700709 -0.0112293 0.714547 0.699587 0 0.714547 0.699587 0 0.713358 0.70071 0.0112293 0.713358 0.70071 0.0112293 0.666999 0.70071 -0.253216 0.667 0.700709 -0.253216 0.526187 0.700709 -0.481803 0.526187 0.700709 -0.481802 -0.186158 0.694746 -0.694746 -0.186157 0.694747 -0.694746 -0.508589 0.694747 -0.50859 -0.508589 0.694747 -0.50859 -0.694747 0.694747 -0.186156 -0.694747 0.694747 -0.186156 -0.694747 0.694747 0.186157 -0.694747 0.694747 0.186156 -0.50859 0.694747 0.50859 -0.50859 0.694747 0.50859 -0.186157 0.694746 0.694747 -0.186157 0.694747 0.694747 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694747 -0.50859 0.694747 -0.50859 -0.508589 0.694747 -0.50859 -0.694746 0.694747 -0.186158 -0.694747 0.694747 -0.186157 -0.694746 0.694746 0.186158 -0.694746 0.694747 0.186157 -0.508589 0.694747 0.50859 -0.508589 0.694747 0.50859 -0.186157 0.694747 0.694747 -0.186157 0.694747 0.694747 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694747 -0.508589 0.694747 -0.50859 -0.50859 0.694746 -0.50859 -0.694747 0.694746 -0.186156 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186155 -0.694747 0.694746 0.186157 -0.50859 0.694746 0.508591 -0.50859 0.694747 0.50859 -0.186157 0.694747 0.694747 -0.186157 0.694747 0.694747 -0.159331 0.698074 -0.698074 -0.159331 0.698074 -0.698074 -0.446434 0.698074 -0.559812 -0.446435 0.698074 -0.559812 -0.645118 0.698073 -0.310671 -0.645117 0.698074 -0.310672 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645118 0.698074 0.310671 -0.645117 0.698073 0.310672 -0.446434 0.698073 0.559812 -0.446435 0.698074 0.559812 -0.15933 0.698074 0.698074 -0.15933 0.698074 0.698074 -0.186155 0.694747 -0.694747 -0.186157 0.694747 -0.694747 -0.508591 0.694746 -0.508589 -0.50859 0.694747 -0.50859 -0.694747 0.694747 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694747 0.694747 0.186157 -0.508589 0.694746 0.508591 -0.50859 0.694747 0.50859 -0.186158 0.694747 0.694746 -0.186157 0.694747 0.694747 -0.186157 0.694747 0.694747 -0.186156 0.694746 0.694747 -0.50859 0.694746 0.50859 -0.481835 0.674049 0.559904 -0.585059 0.706116 0.398881 -0.694747 0.694747 0.186157 -0.697485 0.662253 0.273744 -0.704873 0.704873 0.0794199 -0.704847 0.704847 -0.0798933 -0.704969 0.704776 -0.079431 -0.661654 0.703218 -0.260189 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694747 -0.465274 0.700862 -0.54066 -0.514349 0.686215 -0.514349 -0.585058 0.706116 -0.398882 -0.661913 0.703125 -0.259782 -0.186157 0.694747 -0.694747 -0.186157 0.694747 -0.694747 -0.508589 0.694747 -0.50859 -0.50859 0.694746 -0.50859 -0.694747 0.694746 -0.186156 -0.694746 0.694747 -0.186157 -0.694747 0.694747 0.186155 -0.694747 0.694747 0.186157 -0.508589 0.694746 0.508591 -0.50859 0.694747 0.50859 -0.186157 0.694747 0.694747 -0.186157 0.694747 0.694747 -0.159331 0.698074 -0.698074 -0.159331 0.698074 -0.698074 -0.446435 0.698074 -0.559812 -0.446435 0.698074 -0.559812 -0.645117 0.698074 -0.310672 -0.645117 0.698074 -0.310672 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645117 0.698073 0.310672 -0.645117 0.698074 0.310672 -0.446435 0.698074 0.559812 -0.446435 0.698074 0.559812 -0.15933 0.698074 0.698074 -0.159331 0.698074 0.698074 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0794197 0.704878 -0.704869 -0.0794197 0.704878 -0.704869 -0.234277 0.704878 -0.669524 -0.234278 0.704873 -0.669528 -0.32313 0.70699 -0.629089 -0.497922 0.3523 -0.792438 -0.3922 0.705784 -0.589956 -0.471757 0.706545 -0.527484 -0.702091 0.118903 -0.70209 -0.52784 0.706559 -0.471338 -0.600609 0.704874 -0.377387 -0.600609 0.704874 -0.377388 -0.641701 0.707067 -0.297114 -0.814731 0.504915 -0.285087 -0.672473 0.705439 -0.223911 -0.704873 0.704874 -0.0794201 -0.704869 0.704878 -0.0794194 -0.704869 0.704878 0.0794197 -0.704873 0.704874 0.0794199 -0.669528 0.704874 0.234278 -0.669528 0.704874 0.234278 -0.600609 0.704874 0.377388 -0.600609 0.704874 0.377387 -0.530582 0.706671 0.468079 -0.701106 0.130001 0.701106 -0.475007 0.706418 0.52473 -0.424322 0.706953 0.565835 -0.507808 0.298312 0.808172 -0.358829 0.705906 0.610687 -0.265396 0.706375 0.656201 -0.327126 0.137847 0.934873 -0.190168 0.706704 0.681473 -0.0794201 0.704874 0.704873 -0.0794202 0.704873 0.704873 -0.111965 0 0.993712 -0.111965 0 0.993712 -0.330279 0 0.943883 -0.330279 0 0.943883 -0.532032 0 0.846724 -0.532032 0 0.846724 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.846724 0 0.532032 -0.846724 0 0.532032 -0.943883 0 0.330279 -0.943883 0 0.330279 -0.993712 0 0.111965 -0.993712 0 0.111965 -0.993712 0 -0.111964 -0.993712 0 -0.111964 -0.943883 0 -0.330279 -0.943883 0 -0.330279 -0.846724 0 -0.532032 -0.846724 0 -0.532032 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.532032 0 -0.846724 -0.532032 0 -0.846724 -0.330279 0 -0.943883 -0.330279 0 -0.943883 -0.111965 0 -0.993712 -0.111965 0 -0.993712 -0.186158 0.694746 -0.694746 -0.186157 0.694747 -0.694746 -0.508589 0.694747 -0.50859 -0.50859 0.694747 -0.50859 -0.694746 0.694747 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694747 0.694747 0.186157 -0.50859 0.694747 0.50859 -0.50859 0.694747 0.50859 -0.186157 0.694747 0.694747 -0.186157 0.694747 0.694747 -0.5 0 -0.866025 -0.5 0 -0.866025 0.216077 0 -0.976376 0.202132 -0.00686639 -0.979334 0.0142506 0 -0.999898 0.580371 0 -0.814353 0.580371 0 -0.814353 0.459809 0 -0.888018 0.459809 0 -0.888018 0.78303 0 -0.621984 0.78303 0 -0.621984 0.968416 0 -0.249341 0.968416 0 -0.249341 0.986042 0 0.166494 0.986042 0 0.166494 0.832856 0 0.553489 0.832856 0 0.553489 0.38766 0 0.921802 0.38766 0 0.921802 0.604474 0 0.796625 0.604474 0 0.796625 0.135871 0 0.990727 0.135871 0 0.990727 -0.998951 0 -0.0458028 -0.998951 0 -0.0458028 -0.995435 0 0.0954395 -0.995435 0 0.0954395 -0.486308 0 -0.873788 -0.486308 0 -0.873788 -0.774817 0 -0.632186 -0.774817 0 -0.632186 -0.953605 0 -0.30106 -0.953605 0 -0.30106 -0.415065 0 -0.909792 -0.415065 0 -0.909792 -0.539142 0 -0.842215 -0.539142 0 -0.842215 -0.147139 0 -0.989116 -0.177661 0.0226847 -0.98383 0.268181 -0.0259746 -0.963018 0.218161 0.0173211 -0.975759 0.637122 -0.0165915 -0.770584 0.61301 0.00829726 -0.790032 0.895735 -0.00793098 -0.444517 0.891125 0 -0.453757 0.992134 0 0.125178 0.992134 0 0.125178 0.992134 0 -0.125178 0.992134 0 -0.125178 0.891125 0 0.453757 0.895735 0.00793098 0.444517 0.61301 -0.00829728 0.790032 0.637122 0.0165914 0.770585 0.268247 -0.0136554 0.963253 0.218149 0.0204791 0.975701 0.0309749 0 0.99952 -0.539142 0 0.842215 -0.539142 0 0.842215 -0.415065 0 0.909792 -0.415065 0 0.909792 -0.999876 0 -0.0157395 -0.999876 0 -0.0157395 -0.934897 0 0.354919 -0.934897 0 0.354919 -0.737528 0 0.675316 -0.737528 0 0.675316 -1 0 0 -1 0 0 -0.737528 0 -0.675316 -0.737528 0 -0.675316 -0.934897 0 -0.354919 -0.934897 0 -0.354919 -0.999876 0 0.0157395 -0.999876 0 0.0157395 -0.995435 0 -0.0954394 -0.995435 0 -0.0954394 -0.998951 0 0.0458028 -0.998951 0 0.0458028 -0.930169 0 -0.367132 -0.920769 -0.0179042 -0.389698 -0.700056 0.0158424 -0.713912 -0.645617 -0.0316635 -0.763005 -0.3487 0.0275253 -0.93683 -0.302609 0 -0.953115 -0.073278 0 -0.997312 0.0628673 0.0350248 -0.997407 0.13587 0 -0.990727 0.604474 0 -0.796625 0.604474 0 -0.796625 0.38766 0 -0.921802 0.38766 0 -0.921802 0.832857 0 -0.553489 0.832857 0 -0.553489 0.986042 0 -0.166494 0.986042 0 -0.166494 0.968416 0 0.249341 0.968416 0 0.249341 0.78303 0 0.621984 0.78303 0 0.621984 0.459809 0 0.888018 0.459809 0 0.888018 0.580371 0 0.814353 0.580371 0 0.814353 -0.513569 0 0.858049 -0.519668 -0.00343314 0.854361 -0.160079 0.00356101 0.987098 -0.181145 -0.00712172 0.983431 0.21607 0.0073762 0.97635 0.202136 0 0.979357 -0.5 0 0.866025 -0.5 0 0.866025 -0.953605 0 0.30106 -0.953605 0 0.30106 -0.774817 0 0.632186 -0.774817 0 0.632186 -0.486307 0 0.873788 -0.486307 0 0.873788 -0.580371 0 0.814353 -0.580371 0 0.814353 -0.459809 0 0.888018 -0.459809 0 0.888018 -0.78303 0 0.621984 -0.78303 0 0.621984 -0.968416 0 0.249341 -0.968416 0 0.249341 -0.986042 0 -0.166494 -0.986042 0 -0.166494 -0.832857 0 -0.553488 -0.832857 0 -0.553488 -0.38766 0 -0.921802 -0.38766 0 -0.921802 -0.604474 0 -0.796625 -0.604474 0 -0.796625 -0.13587 0 -0.990727 -0.0628673 0.0350248 -0.997407 0.073278 0 -0.997312 0.348832 0 -0.937185 0.302415 0.0357804 -0.952504 0.699468 -0.0439435 -0.713312 0.645784 0.0219943 -0.763203 0.929984 -0.0199552 -0.367059 0.920916 0 -0.389761 0.998951 0 0.0458028 0.998951 0 0.0458028 0.995435 0 -0.0954395 0.995435 0 -0.0954395 0.486307 0 0.873788 0.486307 0 0.873788 0.774817 0 0.632186 0.774817 0 0.632186 0.953605 0 0.30106 0.953605 0 0.30106 0.5 0 0.866025 0.5 0 0.866025 -0.216076 0 0.976376 -0.202132 0.00686603 0.979334 0.160077 -0.00635483 0.987084 0.181149 0.00317754 0.983451 0.513566 -0.00330533 0.858044 0.519672 0 0.854366 0.415065 0 0.909792 0.415065 0 0.909792 0.539142 0 0.842215 0.539142 0 0.842215 0.177707 0 0.984083 0.177707 0 0.984083 -0.992134 0 -0.125178 -0.992134 0 -0.125178 -0.992134 0 0.125178 -0.992134 0 0.125178 -0.895764 0 -0.444531 -0.8911 -0.00756426 -0.453744 -0.637193 0.00719712 -0.77067 -0.612967 -0.0143919 -0.789977 -0.268247 0.0136555 -0.963254 -0.218148 -0.0204791 -0.975701 0.147111 0.0193725 -0.98893 0.177707 0 -0.984083 0.539142 0 -0.842215 0.539142 0 -0.842215 0.415065 0 -0.909792 0.415065 0 -0.909792 0.999876 0 0.0157395 0.999876 0 0.0157395 0.934897 0 -0.354919 0.934897 0 -0.354919 0.737528 0 -0.675317 0.737528 0 -0.675317 1 0 0 1 0 0 0.737528 0 0.675317 0.737528 0 0.675317 0.934897 0 0.354919 0.934897 0 0.354919 0.999876 0 -0.0157395 0.999876 0 -0.0157395 0.995435 0 0.0954395 0.995435 0 0.0954395 0.998951 0 -0.0458028 0.998951 0 -0.0458028 0.929984 0.0199552 0.367059 0.920916 0 0.389761 0.700056 -0.0158425 0.713912 0.645617 0.0316635 0.763005 0.494331 0 0.869274 0.30261 0 0.953114 0.231756 0.0412483 0.971899 0.073278 0 0.997312 -0.604474 0 0.796625 -0.604474 0 0.796625 -0.38766 0 0.921802 -0.38766 0 0.921802 -0.832857 0 0.553488 -0.832857 0 0.553488 -0.986042 0 0.166494 -0.986042 0 0.166494 -0.968416 0 -0.249341 -0.968416 0 -0.249341 -0.78303 0 -0.621984 -0.78303 0 -0.621984 -0.459809 0 -0.888018 -0.459809 0 -0.888018 -0.580371 0 -0.814353 -0.580371 0 -0.814353 0.519672 0 -0.854366 0.513566 0.00330534 -0.858044 0.181149 -0.00317754 -0.983451 0.174135 0 -0.984722 0.5 0 -0.866025 0.5 0 -0.866025 0.953605 0 -0.30106 0.953605 0 -0.30106 0.774817 0 -0.632186 0.774817 0 -0.632186 0.486308 0 -0.873788 0.486308 0 -0.873788 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.62349 0 -0.781832 -0.62349 0 -0.781832 -0.900969 0 -0.433884 -0.900969 0 -0.433884 -1 0 0 -1 0 0 -0.900969 0 0.433884 -0.900969 0 0.433884 -0.62349 0 0.781832 -0.62349 0 0.781832 -0.222521 0 0.974928 -0.222521 0 0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.62349 0 -0.781831 -0.62349 0 -0.781831 -0.900969 0 -0.433883 -0.900969 0 -0.433883 -1 0 0 -1 0 0 -0.900969 0 0.433883 -0.900969 0 0.433883 -0.62349 0 0.781831 -0.62349 0 0.781831 -0.222521 0 0.974928 -0.222521 0 0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.623489 0 -0.781832 -0.623489 0 -0.781832 -0.900969 0 -0.433883 -0.900969 0 -0.433883 -1 0 0 -1 0 0 -0.900969 0 0.433883 -0.900969 0 0.433883 -0.623489 0 0.781832 -0.623489 0 0.781832 -0.222521 0 0.974928 -0.222521 0 0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.467266 0 -0.884117 -0.467266 0 -0.884117 -0.652288 0 -0.757971 -0.652288 0 -0.757971 -0.826237 0 -0.563323 -0.826237 0 -0.563323 -0.930874 0 -0.36534 -0.930874 0 -0.36534 -0.993712 0 -0.111965 -0.993712 0 -0.111965 -0.993712 0 0.111965 -0.993712 0 0.111965 -0.930874 0 0.365341 -0.930874 0 0.365341 -0.826239 0 0.56332 -0.826239 0 0.56332 -0.652288 0 0.757972 -0.652288 0 0.757972 -0.467271 0 0.884114 -0.467271 0 0.884114 -0.222521 0 0.974928 -0.222521 0 0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.62349 0 -0.781831 -0.62349 0 -0.781831 -0.900969 0 -0.433884 -0.900969 0 -0.433884 -1 0 0 -1 0 0 -0.900969 0 0.433884 -0.900969 0 0.433884 -0.62349 0 0.781831 -0.62349 0 0.781831 -0.222521 0 0.974928 -0.222521 0 0.974928 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707106 0 -0.707108 -0.707106 0 -0.707108 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707106 0 0.707108 -0.707106 0 0.707108 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707106 0 -0.707108 -0.707106 0 -0.707108 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707106 0 0.707108 -0.707106 0 0.707108 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.25882 0 0.965925 -0.25882 0 0.965925 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.623489 0 -0.781832 -0.623489 0 -0.781832 -0.900969 0 -0.433883 -0.900969 0 -0.433883 -1 0 0 -1 0 0 -0.900969 0 0.433884 -0.900969 0 0.433884 -0.62349 0 0.781831 -0.62349 0 0.781831 -0.222521 0 0.974928 -0.222521 0 0.974928 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707106 -0.707107 0 -0.707106 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.25882 0 -0.965925 -0.25882 0 -0.965925 -0.707106 0 -0.707108 -0.707106 0 -0.707108 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965925 0 -0.25882 -0.965925 0 -0.25882 -0.965925 0 0.25882 -0.965925 0 0.25882 -0.707106 0 0.707108 -0.707106 0 0.707108 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707106 0 -0.707108 -0.707106 0 -0.707108 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.707106 0 0.707108 -0.707106 0 0.707108 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.623489 0 -0.781832 -0.623489 0 -0.781832 -0.90097 0 -0.433882 -0.90097 0 -0.433882 -1 0 0 -1 0 0 -0.90097 0 0.433882 -0.90097 0 0.433882 -0.623489 0 0.781832 -0.623489 0 0.781832 -0.222519 0 0.974928 -0.222519 0 0.974928 -0.258817 0 -0.965926 -0.258817 0 -0.965926 -0.707108 0 -0.707106 -0.707108 0 -0.707106 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707106 0 0.707108 -0.707106 0 0.707108 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.258819 0 -0.965926 -0.220965 -0.118063 -0.968109 -0.648905 0.101692 -0.754043 -0.623489 0 -0.781832 -0.826241 0 -0.563317 -0.892651 0.135572 -0.429877 -0.930874 0 -0.365341 -1 0 0 -0.950195 0.292689 -0.107062 -0.993712 0 0.111964 -0.900969 0 0.433883 -0.912036 0.200159 0.357949 -0.826243 0 0.563314 -0.652286 0 0.757973 -0.621227 0.0850942 0.778997 -0.257476 -0.101691 0.960919 -0.222519 0 0.974928 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707106 0 -0.707108 -0.707106 0 -0.707108 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.707106 0 0.707108 -0.707106 0 0.707108 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.62349 0 -0.781831 -0.62349 0 -0.781831 -0.900969 0 -0.433884 -0.900969 0 -0.433884 -1 0 0 -1 0 0 -0.900969 0 0.433884 -0.900969 0 0.433884 -0.623489 0 0.781832 -0.623489 0 0.781832 -0.22252 0 0.974928 -0.22252 0 0.974928 -0.25882 0 -0.965925 -0.25882 0 -0.965925 -0.707106 0 -0.707108 -0.707106 0 -0.707108 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.357275 -0.699584 -0.618818 -0.357275 -0.699584 -0.618819 0.15416 -0.700706 -0.696595 -0.366405 -0.700707 -0.612174 -0.366405 -0.700708 -0.612173 -0.124076 -0.701644 -0.701642 -0.118827 -0.670075 -0.732721 0.0100772 -0.707071 -0.70707 0.15416 -0.700707 -0.696595 0.325541 -0.706221 -0.628709 0.32554 -0.706222 -0.628709 0.410897 -0.706222 -0.576554 0.410897 -0.706221 -0.576554 0.55978 -0.699237 -0.44465 0.559781 -0.699236 -0.44465 0.692312 -0.699236 -0.178252 0.692308 -0.699239 -0.178252 0.70491 -0.699239 0.119025 0.704911 -0.699238 0.119025 0.5954 -0.699238 0.395683 0.595398 -0.69924 0.395682 0.429111 -0.704312 0.565516 0.429111 -0.704311 0.565517 0.275197 -0.704311 0.65438 0.275197 -0.704311 0.65438 0.0965217 -0.703807 0.703804 0.0965214 -0.703805 0.703805 -0.704758 -0.706222 0.0675702 -0.704758 -0.706222 0.0675702 -0.707247 -0.706223 -0.0324279 -0.707247 -0.706223 -0.0324279 -0.680349 -0.700707 -0.214791 -0.680349 -0.700707 -0.214791 -0.552793 -0.700706 -0.451033 -0.552793 -0.700707 -0.451032 -0.346956 -0.700707 -0.623403 -0.346956 -0.700706 -0.623404 -0.381707 -0.706222 -0.59628 -0.381706 -0.706223 -0.596279 -0.293861 -0.706223 -0.644123 -0.293862 -0.706223 -0.644123 -0.105188 -0.699239 -0.707107 -0.105188 -0.699238 -0.707108 0.191784 -0.699238 -0.688683 0.191785 -0.699238 -0.688684 0.455535 -0.699237 -0.550959 0.455533 -0.699239 -0.550957 0.640371 -0.699239 -0.31779 0.640372 -0.699238 -0.31779 0.704309 -0.704309 -0.0888629 0.704309 -0.704309 -0.0888629 0.704309 -0.704309 0.0888629 0.704309 -0.704309 0.0888629 0.637757 -0.698432 0.324743 0.637758 -0.698431 0.324744 0.438732 -0.698431 0.565427 0.438732 -0.698432 0.565427 0.156156 -0.698433 0.698432 0.156156 -0.698432 0.698432 -0.293862 -0.706223 0.644123 -0.293862 -0.706222 0.644124 -0.381707 -0.706222 0.59628 -0.381707 -0.706222 0.59628 -0.526189 -0.700707 0.481804 -0.526189 -0.700707 0.481804 -0.667001 -0.700707 0.253216 -0.667001 -0.700708 0.253216 -0.71336 -0.700708 -0.0112293 -0.71336 -0.700708 -0.0112293 -0.714549 -0.699586 0 -0.714549 -0.699586 0 -0.71336 -0.700708 0.0112293 -0.71336 -0.700708 0.0112293 -0.667001 -0.700708 -0.253216 -0.667001 -0.700708 -0.253216 -0.526189 -0.700708 -0.481803 -0.526189 -0.700707 -0.481804 -0.707247 -0.706223 0.0324279 -0.707247 -0.706222 0.0324279 -0.704758 -0.706223 -0.0675701 -0.704759 -0.706222 -0.0675703 -0.664968 -0.699237 -0.262459 -0.664967 -0.699239 -0.262458 -0.500525 -0.699238 -0.510432 -0.500526 -0.699237 -0.510433 -0.249377 -0.699236 -0.669985 -0.249377 -0.699238 -0.669983 0.0449707 -0.699238 -0.713473 0.0449714 -0.699236 -0.713475 0.452503 -0.705931 -0.544888 0.265619 -0.898281 -0.350054 0.380289 -0.706765 -0.596544 0.324706 -0.706719 -0.628581 0.168404 -0.900714 -0.400442 0.243712 -0.706007 -0.66495 0.595398 -0.69924 -0.395682 0.5954 -0.699238 -0.395683 0.704911 -0.699238 -0.119025 0.70491 -0.699239 -0.119025 0.692309 -0.699239 0.178251 0.692312 -0.699236 0.178252 0.559781 -0.699236 0.444651 0.55978 -0.699237 0.44465 0.410897 -0.706221 0.576554 0.410897 -0.706222 0.576554 0.32554 -0.706222 0.628709 0.325541 -0.706221 0.628709 0.144415 -0.699694 0.699695 0.144415 -0.699694 0.699694 -0.357274 -0.699586 0.618817 -0.357275 -0.699584 0.618819 -0.346955 -0.700708 0.623403 -0.346956 -0.700707 0.623403 -0.552792 -0.700707 0.451032 -0.552793 -0.700706 0.451033 -0.680349 -0.700707 0.214791 -0.680348 -0.700707 0.214791 -0.32554 -0.706222 0.628708 -0.32554 -0.706222 0.628708 -0.410897 -0.706222 0.576554 -0.410897 -0.706221 0.576554 -0.55978 -0.699237 0.44465 -0.559778 -0.699239 0.444649 -0.692309 -0.699239 0.178251 -0.692309 -0.699239 0.178251 -0.70491 -0.699239 -0.119024 -0.704911 -0.699238 -0.119025 -0.5954 -0.699238 -0.395683 -0.595401 -0.699237 -0.395683 -0.243712 -0.706008 -0.664949 -0.168404 -0.900714 -0.400442 -0.301599 -0.744134 -0.596072 -0.429112 -0.70431 -0.565518 -0.429113 -0.704308 -0.56552 -0.348408 -0.707093 -0.615331 -0.0449709 -0.699236 -0.713475 -0.0449712 -0.699238 -0.713473 0.249376 -0.699238 -0.669983 0.249377 -0.699237 -0.669985 0.500526 -0.699237 -0.510432 0.500525 -0.699238 -0.510432 0.664967 -0.699239 -0.262458 0.664968 -0.699238 -0.262459 0.704758 -0.706222 -0.0675702 0.704758 -0.706223 -0.0675702 0.707247 -0.706222 0.0324279 0.707247 -0.706223 0.0324279 0.680348 -0.700707 0.214791 0.680349 -0.700707 0.214791 0.552793 -0.700706 0.451033 0.552793 -0.700707 0.451032 0.346955 -0.700707 0.623403 0.346955 -0.700707 0.623403 0.357275 -0.699585 0.618818 0.357275 -0.699585 0.618818 0.370515 -0.701185 0.609145 0.370515 -0.701184 0.609146 0.129156 -0.701184 0.701184 0.129156 -0.701184 0.701184 0.381707 -0.706223 0.596279 0.381707 -0.706222 0.59628 0.293862 -0.706222 0.644124 0.293862 -0.706223 0.644123 0.126662 -0.701413 0.701411 0.126662 -0.701412 0.701412 -0.704309 -0.704309 0.0888629 -0.704309 -0.704309 0.0888629 -0.704309 -0.704309 -0.0888629 -0.704309 -0.704309 -0.0888629 -0.640372 -0.699238 -0.31779 -0.640371 -0.699239 -0.31779 -0.455533 -0.699239 -0.550957 -0.455534 -0.699239 -0.550958 -0.191784 -0.699238 -0.688683 -0.191784 -0.699238 -0.688683 0.105188 -0.699238 -0.707108 0.105188 -0.699239 -0.707108 0.293862 -0.706223 -0.644123 0.293861 -0.706223 -0.644123 0.381706 -0.706223 -0.596279 0.381707 -0.706223 -0.596279 0.526188 -0.700708 -0.481803 0.526188 -0.700708 -0.481803 0.667001 -0.700707 -0.253216 0.667003 -0.700706 -0.253216 0.713362 -0.700706 0.0112293 0.71336 -0.700708 0.0112288 0.714549 -0.699586 0 0.714549 -0.699586 0 0.71336 -0.700708 -0.0112293 0.713362 -0.700706 -0.0112288 0.667002 -0.700706 0.253217 0.667002 -0.700707 0.253216 0.526189 -0.700707 0.481804 0.526188 -0.700708 0.481803 0.707247 -0.706223 -0.0324279 0.707247 -0.706223 -0.0324279 0.704758 -0.706222 0.0675702 0.704758 -0.706223 0.0675702 0.660125 -0.697266 0.279386 0.660125 -0.697265 0.279386 0.463019 -0.697265 0.547207 0.463018 -0.697267 0.547205 0.166267 -0.697268 0.697261 0.166267 -0.697264 0.697264 -0.429112 -0.70431 0.565518 -0.429112 -0.70431 0.565518 -0.324705 -0.706721 0.62858 -0.168404 -0.900714 0.400442 -0.243711 -0.706011 0.664947 -0.595401 -0.699237 0.395683 -0.5954 -0.699238 0.395683 -0.704911 -0.699238 0.119025 -0.70491 -0.699239 0.119025 -0.692308 -0.699239 -0.178251 -0.692309 -0.699239 -0.178251 -0.559779 -0.699239 -0.444649 -0.55978 -0.699237 -0.44465 -0.410897 -0.706221 -0.576554 -0.410897 -0.706222 -0.576554 -0.32554 -0.706222 -0.628709 -0.32554 -0.706222 -0.628708 0.366405 -0.700708 -0.612174 0.366405 -0.700707 -0.612174 0.114209 -0.700708 -0.704248 -0.15416 -0.700707 -0.696595 -0.15416 -0.700707 -0.696595 -0.0100772 -0.707071 -0.70707 0.129851 -0.666295 -0.734295 0.357275 -0.699584 -0.618819 0.357275 -0.699585 -0.618818 0.346956 -0.700706 -0.623404 0.346956 -0.700707 -0.623403 0.552792 -0.700707 -0.451032 0.552793 -0.700706 -0.451033 0.680349 -0.700707 -0.214791 0.680348 -0.700707 -0.214791 -0.15933 -0.698075 0.698072 -0.159331 -0.698073 0.698074 -0.446435 -0.698074 0.559812 -0.446434 -0.698074 0.559811 -0.645117 -0.698074 0.310672 -0.645117 -0.698074 0.310672 -0.716026 -0.698074 0 -0.716026 -0.698074 0 -0.645117 -0.698074 -0.310672 -0.645117 -0.698074 -0.310672 -0.446434 -0.698074 -0.559811 -0.446434 -0.698075 -0.559811 -0.159331 -0.698075 -0.698072 -0.159331 -0.698074 -0.698074 -0.15933 -0.698075 0.698073 -0.159331 -0.698074 0.698073 -0.446435 -0.698074 0.559811 -0.446436 -0.698073 0.559812 -0.645118 -0.698072 0.310672 -0.645114 -0.698077 0.310671 -0.716022 -0.698077 0 -0.716022 -0.698077 0 -0.645114 -0.698077 -0.31067 -0.645117 -0.698073 -0.310673 -0.446435 -0.698074 -0.559811 -0.446435 -0.698074 -0.559812 -0.159331 -0.698073 -0.698074 -0.159331 -0.698074 -0.698074 -0.15933 -0.698077 0.69807 -0.159331 -0.698075 0.698072 -0.446434 -0.698075 0.559811 -0.446435 -0.698074 0.559812 -0.645118 -0.698073 0.310672 -0.645117 -0.698074 0.310672 -0.716026 -0.698074 0 -0.716026 -0.698074 0 -0.645117 -0.698074 -0.310672 -0.645118 -0.698073 -0.310672 -0.446434 -0.698074 -0.559812 -0.446434 -0.698075 -0.559811 -0.159331 -0.698075 -0.698072 -0.159331 -0.698077 -0.69807 -0.186157 -0.694747 -0.694747 -0.191427 -0.509847 -0.838696 -0.914471 -0.322028 -0.245032 -0.330523 -0.706858 -0.625385 -0.465277 -0.70086 -0.54066 -0.646044 -0.406513 -0.646045 -0.585056 -0.706114 -0.398888 -0.661914 -0.703124 -0.259782 -0.704873 -0.704873 -0.0794204 -0.704873 -0.704873 0.0794204 -0.914471 -0.322028 0.245032 -0.661912 -0.703126 0.259781 -0.585055 -0.706118 0.398883 -0.646044 -0.406513 0.646045 -0.159331 -0.698074 0.698074 -0.216617 -0.547288 0.808426 -0.330525 -0.706861 0.625381 -0.465274 -0.700863 0.540658 -0.153082 -0.725763 -0.670697 -0.153259 -0.805828 -0.571973 -0.0331733 -0.706718 -0.706718 -0.159331 -0.698074 0.698074 -0.15933 -0.698075 0.698072 -0.446434 -0.698075 0.55981 -0.446432 -0.698078 0.559809 -0.645115 -0.698076 0.310671 -0.645118 -0.698073 0.310672 -0.716026 -0.698074 0 -0.716026 -0.698074 0 -0.645118 -0.698073 -0.310673 -0.645115 -0.698076 -0.310671 -0.446433 -0.698078 -0.559808 -0.446435 -0.698072 -0.559813 -0.300748 -0.707089 -0.639981 -0.186156 -0.694748 -0.694746 -0.175525 -0.808326 -0.561961 -0.0289557 -0.706814 -0.706807 -0.418712 -0.805829 -0.418712 -0.418712 -0.805829 -0.418712 -0.382086 -0.706719 -0.595449 -0.186156 -0.69475 0.694744 -0.186157 -0.694748 0.694745 -0.508589 -0.694748 0.508589 -0.508589 -0.694748 0.508589 -0.694748 -0.694745 0.186157 -0.694747 -0.694747 0.186157 -0.694747 -0.694747 -0.186156 -0.694748 -0.694745 -0.186157 -0.59545 -0.706718 -0.382085 -0.571973 -0.805827 -0.15326 -0.186157 -0.694747 -0.694747 -0.186157 -0.694747 -0.694746 -0.508588 -0.694749 -0.508588 -0.50859 -0.694745 -0.508591 -0.628623 -0.706716 -0.324632 -0.571973 -0.805828 -0.153259 -0.186157 -0.694747 0.694746 -0.186157 -0.694748 0.694745 -0.508587 -0.694749 0.508588 -0.50859 -0.694746 0.50859 -0.694748 -0.694745 0.186157 -0.694747 -0.694747 0.186157 -0.706718 -0.706718 -0.0331733 -0.694747 -0.694747 -0.186156 -0.694749 -0.694745 -0.186157 -0.50859 -0.694745 -0.508591 -0.508588 -0.694749 -0.508588 -0.186157 -0.694748 -0.694745 -0.186157 -0.694747 -0.694747 -0.571973 -0.805828 0.153259 -0.571973 -0.805827 0.153259 -0.706718 -0.706718 0.0331733 -0.186157 -0.694748 0.694745 -0.186156 -0.694749 0.694745 -0.508587 -0.69475 0.508588 -0.50859 -0.694746 0.50859 -0.628622 -0.706717 0.324632 -0.186157 -0.694746 0.694747 -0.694749 -0.694745 0.186157 -0.694747 -0.694747 0.186157 -0.694747 -0.694747 -0.186156 -0.694749 -0.694745 -0.186157 -0.508591 -0.694745 -0.508591 -0.508591 -0.694745 -0.508591 -0.186157 -0.694745 -0.694749 -0.186157 -0.694747 -0.694747 -0.186157 -0.694748 0.694745 -0.382086 -0.706719 0.595449 -0.418712 -0.805829 0.418712 -0.418711 -0.80583 0.418712 -0.595453 -0.706716 0.382085 -0.186156 -0.69475 -0.694744 -0.186156 -0.694748 -0.694746 -0.508589 -0.694748 -0.508589 -0.508591 -0.694745 -0.508591 -0.694746 -0.694747 -0.186157 -0.694745 -0.694748 -0.186156 -0.694745 -0.694748 0.186156 -0.694745 -0.694749 0.186156 -0.508587 -0.69475 0.508588 -0.508587 -0.69475 0.508588 -0.32463 -0.706722 0.628617 -0.153258 -0.805832 0.571968 -0.15326 -0.805828 0.571972 -0.0331733 -0.706718 0.706718 -0.159331 -0.698074 0.698074 -0.159332 -0.698072 0.698075 -0.446436 -0.698072 0.559812 -0.446436 -0.698072 0.559812 -0.645117 -0.698073 0.310672 -0.645117 -0.698073 0.310672 -0.716025 -0.698075 0 -0.716025 -0.698075 0 -0.645115 -0.698076 -0.31067 -0.645117 -0.698073 -0.310672 -0.446435 -0.698072 -0.559813 -0.446434 -0.698075 -0.559811 -0.15933 -0.698075 -0.698072 -0.15933 -0.698077 -0.69807 -0.186157 -0.694747 0.694747 -0.186157 -0.694748 0.694745 -0.508589 -0.694748 0.508589 -0.508589 -0.694748 0.508589 -0.694745 -0.694748 0.186157 -0.694747 -0.694747 0.186157 -0.694747 -0.694747 -0.186157 -0.694745 -0.694748 -0.186157 -0.508589 -0.694748 -0.508589 -0.508591 -0.694745 -0.508591 -0.186157 -0.694745 -0.694749 -0.186157 -0.694747 -0.694747 -0.186156 -0.694748 0.694745 -0.186157 -0.694747 0.694746 -0.508591 -0.694745 0.508591 -0.50859 -0.694746 0.50859 -0.694748 -0.694745 0.186157 -0.694747 -0.694747 0.186157 -0.694747 -0.694747 -0.186156 -0.694749 -0.694745 -0.186157 -0.508591 -0.694745 -0.508591 -0.508591 -0.694744 -0.508591 -0.186157 -0.694746 -0.694747 -0.186157 -0.694747 -0.694747 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.991063 0 -0.133395 -0.0864777 0 0.996254 -0.0886445 0.677618 0.730052 -0.287552 0.21948 0.932278 -0.251837 0.704008 0.664041 -0.258808 0.00912853 0.965886 -0.240836 0 0.970566 -0.205933 0 0.978566 -0.626853 0.111035 0.771185 -0.456929 0.609063 0.648273 -0.399175 0.711493 0.578306 -0.500294 0 0.865855 -0.390756 0 0.920494 -0.532532 0.702732 0.471782 -0.684112 0.252943 0.684113 -0.679222 0 0.733933 -0.654352 0 0.75619 -0.642274 0.749949 0.158306 -0.951616 0.2425 0.188735 -0.766918 0.607955 0.205495 -0.949036 0 0.315169 -0.885456 0 0.464723 -0.885456 0 0.464723 -0.773605 0 0.633668 -1 0 0 -1 0 0 -0.991063 0 0.133394 -0.951616 0.2425 -0.188735 -0.642274 0.749949 -0.158306 -0.766918 0.607955 -0.205495 -0.805526 0 -0.59256 -0.832983 0 -0.553299 -0.769062 0.495602 -0.403635 -0.893603 0 -0.448858 -0.949036 0 -0.315169 -0.598186 0.609034 -0.520817 -0.532532 0.702731 -0.471782 -0.68411 0.252954 -0.68411 -0.258808 0.00911418 -0.965886 -0.287553 0.219467 -0.932281 -0.263921 0.634154 -0.72677 -0.236416 0.745324 -0.623378 -0.417057 0 -0.90888 -0.568065 0 -0.822984 -0.568065 0 -0.822984 -0.679221 0 -0.733934 -0.120536 0 -0.992709 -0.120536 0 -0.992709 -0.240865 0 -0.970559 -0.258821 0 -0.965925 -0.258821 0 -0.965925 -0.707107 0 -0.707106 -0.707107 0 -0.707106 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707107 0 0.707106 -0.707107 0 0.707106 -0.258818 0 0.965926 -0.258818 0 0.965926 -0.222524 0 -0.974927 -0.258819 0.00371748 -0.965919 -0.623487 -0.00310601 -0.781828 -0.652288 0 -0.757971 -0.826239 0 -0.563319 -0.900957 -0.00497638 -0.43388 -0.930873 0 -0.365343 -0.993712 0 -0.111964 -0.999984 -0.00560112 0 -0.993712 0 0.111965 -0.930874 0 0.365341 -0.900958 -0.00497644 0.433878 -0.826239 0 0.563319 -0.62349 0 0.781832 -0.652283 -0.00371763 0.757966 -0.222518 0.00432393 0.974919 -0.258818 0 0.965926 -0.222522 0 -0.974928 -0.258818 0.00371753 -0.965919 -0.623486 -0.00310593 -0.781828 -0.652286 0 -0.757973 -0.826238 0 -0.563321 -0.900957 -0.0049765 -0.433879 -0.930874 0 -0.365341 -0.993712 0 -0.111964 -0.999984 -0.00560112 0 -0.993712 0 0.111965 -0.930874 0 0.365341 -0.900957 -0.0049765 0.433879 -0.826238 0 0.563321 -0.62349 0 0.781831 -0.652283 -0.00371756 0.757966 -0.22252 0.00432392 0.974919 -0.25882 0 0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.222521 0 -0.974928 -0.258818 0.00371758 -0.965919 -0.623487 -0.00310582 -0.781828 -0.652286 0 -0.757973 -0.826241 0 -0.563317 -0.900958 -0.00497638 -0.433878 -0.930874 0 -0.365341 -0.993712 0 -0.111968 -0.999984 -0.00560132 0 -0.993712 0 0.111968 -0.930874 0 0.365341 -0.900958 -0.00497638 0.433878 -0.826241 0 0.563317 -0.62349 0 0.781831 -0.652282 -0.00371737 0.757967 -0.222518 0.00432404 0.974919 -0.258819 0 0.965926 -0.22252 0 -0.974928 -0.258816 0.00371755 -0.965919 -0.467268 0 -0.884116 -0.652288 0 -0.757971 -0.707093 0.00620743 -0.707093 -0.826238 0 -0.563321 -0.930874 0 -0.365341 -0.965899 0.00745591 -0.258812 -0.993712 0 -0.111964 -0.993712 0 0.111965 -0.965899 0.00745588 0.258812 -0.930874 0 0.365341 -0.826238 0 0.563321 -0.707093 0.00620743 0.707093 -0.22252 0 0.974928 -0.258816 0.00371755 0.965919 -0.467268 0 0.884116 -0.652288 0 0.757971 -0.22252 0 -0.974928 -0.258816 -0.00371753 -0.96592 -0.467266 0 -0.884117 -0.652288 0 -0.757971 -0.707094 -0.00620748 -0.707093 -0.826239 0 -0.563319 -0.930874 0 -0.365341 -0.965899 -0.00745588 -0.258812 -0.993712 0 -0.111965 -0.993712 0 0.111965 -0.965899 -0.00745588 0.258812 -0.930874 0 0.365341 -0.826239 0 0.563319 -0.707094 -0.00620748 0.707093 -0.652288 0 0.757971 -0.467266 0 0.884117 -0.258816 -0.00371753 0.96592 -0.22252 0 0.974928 -0.22252 0 -0.974928 -0.22252 0 -0.974928 -0.62349 0 -0.781832 -0.62349 0 -0.781832 -0.900969 0 -0.433884 -0.900969 0 -0.433884 -1 0 0 -1 0 0 -0.900969 0 0.433884 -0.900969 0 0.433884 -0.62349 0 0.781832 -0.62349 0 0.781832 -0.22252 0 0.974928 -0.22252 0 0.974928 -0.22252 0 -0.974928 -0.258816 0.00371751 -0.96592 -0.467263 0 -0.884118 -0.652288 0 -0.757971 -0.707094 0.00620753 -0.707092 -0.826241 0 -0.563317 -0.930874 0 -0.365341 -0.965899 0.00745591 -0.258812 -0.993712 0 -0.111964 -0.993712 0 0.111965 -0.965899 0.00745588 0.258812 -0.930874 0 0.365341 -0.826241 0 0.563317 -0.707094 0.00620754 0.707092 -0.22252 0 0.974928 -0.258816 0.00371751 0.96592 -0.467263 0 0.884118 -0.652288 0 0.757971 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.222522 0 -0.974928 -0.258818 -0.00371752 -0.965919 -0.467265 0 -0.884117 -0.652286 0 -0.757973 -0.707093 -0.00620762 -0.707093 -0.826241 0 -0.563317 -0.930873 0 -0.365342 -0.965899 -0.00745603 -0.258811 -0.993713 0 -0.11196 -0.993713 0 0.111961 -0.965899 -0.00745601 0.258811 -0.930873 0 0.365342 -0.826241 0 0.563317 -0.707093 -0.00620757 0.707093 -0.652287 0 0.757972 -0.467263 0 0.884118 -0.258817 -0.00371749 0.965919 -0.222521 0 0.974928 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707108 0 0.707106 -0.707108 0 0.707106 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.186158 0.694746 -0.694746 -0.186157 0.694747 -0.694746 -0.50859 0.694747 -0.508589 -0.508589 0.694748 -0.508589 -0.694745 0.694748 -0.186157 -0.694746 0.694747 -0.186157 -0.694746 0.694747 0.186157 -0.694746 0.694748 0.186156 -0.508589 0.694748 0.508589 -0.508589 0.694747 0.50859 -0.186156 0.694747 0.694747 -0.186156 0.694747 0.694747 -0.159333 0.698073 -0.698073 -0.159329 0.698076 -0.698072 -0.446433 0.698076 -0.55981 -0.446433 0.698076 -0.55981 -0.645115 0.698075 -0.310672 -0.645117 0.698074 -0.310672 -0.716025 0.698074 0 -0.716025 0.698074 0 -0.645116 0.698075 0.310672 -0.645116 0.698074 0.310672 -0.446435 0.698074 0.559811 -0.446435 0.698074 0.559811 -0.15933 0.698074 0.698074 -0.15933 0.698074 0.698074 -0.159331 0.698075 -0.698073 -0.159331 0.698075 -0.698072 -0.446433 0.698075 -0.559811 -0.446434 0.698075 -0.559811 -0.645116 0.698075 -0.310672 -0.645117 0.698074 -0.310672 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645117 0.698074 0.310672 -0.645116 0.698075 0.310671 -0.446435 0.698075 0.559811 -0.446435 0.698075 0.55981 -0.159331 0.698075 0.698072 -0.15933 0.698074 0.698074 -0.186157 0.694747 -0.694746 -0.186157 0.694747 -0.694746 -0.508589 0.694748 -0.508589 -0.50859 0.694747 -0.508589 -0.694746 0.694747 -0.186158 -0.694746 0.694746 -0.186158 -0.694746 0.694746 0.186158 -0.694746 0.694747 0.186158 -0.508589 0.694747 0.508589 -0.508589 0.694748 0.508589 -0.186156 0.694747 0.694746 -0.186157 0.694747 0.694746 -0.159331 0.698074 -0.698073 -0.159331 0.698074 -0.698073 -0.446434 0.698075 -0.559811 -0.446434 0.698075 -0.559811 -0.645117 0.698075 -0.310671 -0.645117 0.698074 -0.310671 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645117 0.698074 0.310671 -0.645117 0.698075 0.31067 -0.446435 0.698075 0.559811 -0.446434 0.698074 0.559811 -0.15933 0.698074 0.698073 -0.15933 0.698074 0.698073 -0.159331 0.698075 0.698073 -0.15933 0.698074 0.698074 -0.330524 0.70686 0.625383 -0.457414 0.679544 0.573579 -0.465274 0.700863 0.540658 -0.585055 0.706117 0.398885 -0.670697 0.667715 0.32299 -0.661913 0.703125 0.259782 -0.704873 0.704874 0.0794203 -0.748045 0.663648 0 -0.704873 0.704874 -0.07942 -0.645117 0.698074 -0.310672 -0.713065 0.64282 -0.279858 -0.585055 0.706117 -0.398885 -0.446434 0.698075 -0.559811 -0.15933 0.698075 -0.698073 -0.159331 0.698074 -0.698073 -0.330524 0.70686 -0.625383 -0.482992 0.672102 -0.561246 -0.186155 0.694749 -0.694745 -0.186158 0.694747 -0.694746 -0.50859 0.694747 -0.508589 -0.508589 0.694748 -0.508589 -0.694746 0.694747 -0.186157 -0.694746 0.694747 -0.186157 -0.694746 0.694747 0.186157 -0.694746 0.694747 0.186157 -0.508589 0.694748 0.508589 -0.508589 0.694747 0.50859 -0.186156 0.694747 0.694747 -0.186156 0.694748 0.694746 -0.15933 0.698076 -0.698072 -0.159332 0.698074 -0.698073 -0.446435 0.698074 -0.559811 -0.446435 0.698074 -0.559811 -0.645117 0.698074 -0.310672 -0.645116 0.698075 -0.310672 -0.716025 0.698075 0 -0.716025 0.698075 0 -0.645116 0.698075 0.310671 -0.645116 0.698074 0.310672 -0.446435 0.698074 0.559811 -0.446435 0.698074 0.559811 -0.15933 0.698074 0.698074 -0.159331 0.698075 0.698073 -0.159331 0.698075 0.698073 -0.15933 0.698074 0.698074 -0.33052 0.70686 0.625384 -0.457414 0.679543 0.57358 -0.465275 0.700862 0.540659 -0.585058 0.706116 0.398883 -0.670697 0.667715 0.32299 -0.661913 0.703125 0.259782 -0.704873 0.704874 0.0794203 -0.748045 0.663648 0 -0.704873 0.704874 -0.07942 -0.645117 0.698074 -0.310672 -0.713065 0.64282 -0.279858 -0.585058 0.706116 -0.398883 -0.446435 0.698074 -0.559812 -0.15933 0.698075 -0.698073 -0.159331 0.698074 -0.698073 -0.33052 0.70686 -0.625384 -0.482992 0.672102 -0.561247 -0.186157 0.694747 -0.694746 -0.186156 0.694748 -0.694746 -0.508589 0.694748 -0.508589 -0.50859 0.694747 -0.508589 -0.694747 0.694747 -0.186156 -0.694744 0.694749 -0.186157 -0.694745 0.694749 0.186155 -0.694746 0.694747 0.186158 -0.508589 0.694747 0.50859 -0.508589 0.694748 0.508589 -0.186157 0.694747 0.694746 -0.186157 0.694747 0.694746 -0.186157 0.694747 -0.694746 -0.186157 0.694747 -0.694746 -0.508589 0.694748 -0.508589 -0.50859 0.694747 -0.508589 -0.694747 0.694747 -0.186156 -0.694744 0.694749 -0.186157 -0.694745 0.694749 0.186155 -0.694746 0.694747 0.186158 -0.508589 0.694747 0.508589 -0.508589 0.694748 0.508589 -0.186156 0.694747 0.694746 -0.186157 0.694747 0.694746 -0.116751 0.851305 -0.511516 -0.340301 0.853126 -0.395438 -0.483397 0.854596 -0.18972 -0.514173 0.855727 0.0579341 -0.42642 0.856529 0.29073 -0.11675 0.851305 0.511516 -0.240787 0.857008 0.455586 -0.340302 0.853126 0.395437 -0.483397 0.854596 0.189719 -0.514173 0.855727 -0.0579341 -0.426422 0.856529 -0.290726 -0.240781 0.857008 -0.45559 -0.116751 0.851305 -0.511516 -0.340301 0.853126 -0.395438 -0.483397 0.854596 -0.18972 -0.514173 0.855727 0.0579341 -0.42642 0.856529 0.29073 -0.11675 0.851305 0.511516 -0.240787 0.857008 0.455586 -0.340302 0.853126 0.395437 -0.483397 0.854596 0.189719 -0.514173 0.855727 -0.0579341 -0.426422 0.856529 -0.290726 -0.240781 0.857008 -0.45559 -0.11675 0.851305 -0.511516 -0.340301 0.853126 -0.395438 -0.483397 0.854596 -0.18972 -0.514173 0.855727 0.0579341 -0.426421 0.856529 0.290728 -0.116751 0.851305 0.511516 -0.240785 0.857008 0.455588 -0.340302 0.853126 0.395438 -0.483397 0.854596 0.18972 -0.514173 0.855727 -0.0579338 -0.426421 0.856529 -0.290728 -0.240784 0.857008 -0.455588 -0.510203 0.849119 -0.136707 -0.373494 0.849119 -0.373495 -0.136709 0.849119 -0.510203 -0.136709 0.849119 0.510203 -0.373494 0.849119 0.373495 -0.510203 0.849119 0.136707 -0.116751 0.851305 -0.511516 -0.524671 0.851305 0 -0.472712 0.851305 -0.227646 -0.327127 0.851305 -0.410204 -0.116751 0.851305 0.511516 -0.327128 0.851305 0.410204 -0.472712 0.851305 0.227647 -0.116751 0.851305 -0.511516 -0.340303 0.853126 -0.395437 -0.483396 0.854596 -0.18972 -0.514173 0.855727 0.0579337 -0.426421 0.856529 0.290728 -0.116748 0.851305 0.511517 -0.240796 0.857008 0.455582 -0.340301 0.853126 0.395439 -0.483397 0.854596 0.189719 -0.514173 0.855727 -0.0579331 -0.426421 0.856529 -0.290728 -0.240784 0.857008 -0.455588 -0.510203 0.849119 -0.136709 -0.373495 0.849119 -0.373494 -0.136709 0.849119 -0.510203 -0.136709 0.84912 0.510202 -0.373495 0.84912 0.373494 -0.510203 0.849119 0.136709 -0.11675 0.851305 -0.511516 -0.340301 0.853126 -0.395439 -0.483396 0.854596 -0.189719 -0.514173 0.855728 0.0579339 -0.42642 0.85653 0.290728 -0.11675 0.851305 0.511516 -0.240786 0.857008 0.455587 -0.340301 0.853126 0.395439 -0.483396 0.854596 0.189719 -0.514173 0.855728 -0.0579339 -0.42642 0.85653 -0.290728 -0.240786 0.857008 -0.455587 -0.136708 0.84912 -0.510203 -0.42642 0.85653 -0.290728 -0.514173 0.855728 -0.0579312 -0.483396 0.854596 0.18972 -0.136709 0.849119 0.510203 -0.340302 0.853126 0.395438 -0.426421 0.856529 0.290728 -0.514173 0.855728 0.0579315 -0.483396 0.854596 -0.189719 -0.340301 0.853126 -0.395438 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.186157 0.694748 -0.694746 -0.186156 0.694748 -0.694745 -0.508589 0.694748 -0.508589 -0.508589 0.694748 -0.508589 -0.694745 0.694748 -0.186156 -0.694746 0.694748 -0.186156 -0.694745 0.694748 0.186157 -0.694745 0.694748 0.186156 -0.508589 0.694749 0.508588 -0.508589 0.694747 0.50859 -0.186157 0.694747 0.694746 -0.186157 0.694747 0.694747 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.222522 0 -0.974928 -0.258818 -0.00363657 -0.965919 -0.467261 0 -0.884119 -0.652287 0 -0.757972 -0.707095 -0.00607258 -0.707093 -0.826242 0 -0.563316 -0.930873 0 -0.365342 -0.9659 -0.00729363 -0.258813 -0.993712 0 -0.111966 -0.993712 0 0.111966 -0.9659 -0.00729361 0.258813 -0.930874 0 0.36534 -0.826237 0 0.563323 -0.707094 -0.00607228 0.707094 -0.652289 0 0.757971 -0.467273 0 0.884113 -0.258818 -0.0036368 0.965919 -0.22252 0 0.974928 -0.222522 0 -0.974928 -0.258818 -0.00363657 -0.965919 -0.467261 0 -0.884119 -0.652287 0 -0.757972 -0.707095 -0.00607258 -0.707093 -0.826242 0 -0.563316 -0.930873 0 -0.365342 -0.9659 -0.00729363 -0.258813 -0.993712 0 -0.111966 -0.993712 0 0.111966 -0.9659 -0.00729361 0.258813 -0.930874 0 0.36534 -0.826237 0 0.563323 -0.707094 -0.00607228 0.707094 -0.652289 0 0.757971 -0.467273 0 0.884113 -0.258818 -0.0036368 0.965919 -0.22252 0 0.974928 -0.22252 0 -0.974928 -0.258816 -0.00363665 -0.96592 -0.467268 0 -0.884116 -0.652287 0 -0.757972 -0.707094 -0.00607245 -0.707094 -0.82624 0 -0.563319 -0.930873 0 -0.365342 -0.9659 -0.00729367 -0.258813 -0.993712 0 -0.111965 -0.993712 0 0.111966 -0.9659 -0.00729363 0.258813 -0.930873 0 0.365342 -0.82624 0 0.563319 -0.707094 -0.00607245 0.707094 -0.652287 0 0.757972 -0.467268 0 0.884116 -0.258818 -0.00363662 0.965919 -0.222522 0 0.974928 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707106 0 -0.707108 -0.707106 0 -0.707108 -0.965927 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 0.258816 -0.965927 0 0.258816 -0.707106 0 0.707108 -0.707106 0 0.707108 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.222522 0 -0.974928 -0.222522 0 -0.974928 -0.623489 0 -0.781832 -0.623489 0 -0.781832 -0.900969 0 -0.433884 -0.900969 0 -0.433884 -1 0 0 -1 0 0 -0.900968 0 0.433885 -0.900968 0 0.433885 -0.623491 0 0.781831 -0.623491 0 0.781831 -0.222522 0 0.974928 -0.222522 0 0.974928 -0.222522 0 -0.974928 -0.258818 -0.00363661 -0.965919 -0.467266 0 -0.884117 -0.652289 0 -0.75797 -0.707095 -0.00607238 -0.707093 -0.826239 0 -0.56332 -0.930873 0 -0.365343 -0.9659 -0.00729372 -0.258812 -0.993712 0 -0.111964 -0.993712 0 0.111965 -0.9659 -0.00729359 0.258812 -0.930874 0 0.36534 -0.826239 0 0.56332 -0.707093 -0.00607248 0.707095 -0.652286 0 0.757973 -0.46729 0 0.884104 -0.258818 -0.00363709 0.965919 -0.222517 0 0.974929 -0.222522 0 -0.974928 -0.258818 0.00363657 -0.965919 -0.467261 0 -0.884119 -0.652289 0 -0.757971 -0.707095 0.00607241 -0.707093 -0.82624 0 -0.563319 -0.930873 0 -0.365342 -0.9659 0.00729363 -0.258813 -0.993712 0 -0.111966 -0.993712 0 0.111965 -0.9659 0.00729367 0.258813 -0.930873 0 0.365342 -0.826237 0 0.563323 -0.707095 0.00607223 0.707093 -0.222522 0 0.974928 -0.258818 0.00363657 0.965919 -0.467261 0 0.884119 -0.65229 0 0.757969 -0.222521 0 -0.974928 -0.258818 -0.00363669 -0.965919 -0.467271 0 -0.884114 -0.652286 0 -0.757973 -0.707093 -0.00607248 -0.707095 -0.826239 0 -0.56332 -0.930874 0 -0.365341 -0.9659 -0.00729364 -0.258813 -0.993712 0 -0.111966 -0.993712 0 0.111966 -0.9659 -0.00729364 0.258813 -0.930874 0 0.365341 -0.826239 0 0.563319 -0.707093 -0.00607249 0.707095 -0.652286 0 0.757973 -0.46727 0 0.884115 -0.258818 -0.00363668 0.965919 -0.222521 0 0.974928 -0.222519 0 -0.974928 -0.258816 0.00363666 -0.96592 -0.623487 -0.00303837 -0.781828 -0.652287 0 -0.757972 -0.82624 0 -0.563319 -0.900958 -0.00486814 -0.433879 -0.930873 0 -0.365342 -0.993713 0 -0.11196 -0.999985 -0.00547906 0 -0.993713 0 0.111961 -0.930873 0 0.365342 -0.900958 -0.00486814 0.433879 -0.82624 0 0.563319 -0.623489 0 0.781832 -0.652283 -0.00363667 0.757967 -0.22252 0.00422983 0.974919 -0.25882 0 0.965926 -0.995435 0 0.0954395 -0.995435 0 0.0954395 -0.998951 0 -0.0458028 -0.998951 0 -0.0458028 -0.930169 0 0.367132 -0.930169 0 0.367132 -0.700144 0 0.714001 -0.700144 0 0.714001 -0.348833 0 0.937185 -0.348833 0 0.937185 0.0629069 0 0.998019 0.0629069 0 0.998019 0.604474 0 0.796625 0.604474 0 0.796625 0.38766 0 0.921802 0.38766 0 0.921802 0.832856 0 0.553489 0.832856 0 0.553489 0.986042 0 0.166494 0.986042 0 0.166494 0.968416 0 -0.249341 0.968416 0 -0.249341 0.78303 0 -0.621984 0.78303 0 -0.621984 0.459809 0 -0.888018 0.459809 0 -0.888018 0.580371 0 -0.814352 0.580371 0 -0.814352 -0.513569 0 -0.858049 -0.519671 0.00104035 -0.854366 -0.160081 -0.0010791 -0.987103 -0.18115 0.00215804 -0.983453 0.216077 -0.00223539 -0.976374 0.202136 0 -0.979357 -0.5 0 -0.866025 -0.5 0 -0.866025 -0.953605 0 -0.30106 -0.953605 0 -0.30106 -0.774817 0 -0.632186 -0.774817 0 -0.632186 -0.486308 0 -0.873788 -0.486308 0 -0.873788 -0.580371 0 -0.814352 -0.580371 0 -0.814352 -0.459809 0 -0.888018 -0.459809 0 -0.888018 -0.78303 0 -0.621984 -0.78303 0 -0.621984 -0.968416 0 -0.249341 -0.968416 0 -0.249341 -0.986042 0 0.166494 -0.986042 0 0.166494 -0.832857 0 0.553488 -0.832857 0 0.553488 -0.38766 0 0.921802 -0.38766 0 0.921802 -0.604474 0 0.796625 -0.604474 0 0.796625 -0.0629069 0 0.998019 -0.0629069 0 0.998019 0.348833 0 0.937185 0.348833 0 0.937185 0.700144 0 0.714002 0.700144 0 0.714002 0.930169 0 0.367132 0.930169 0 0.367132 0.998951 0 -0.0458028 0.998951 0 -0.0458028 0.995435 0 0.0954395 0.995435 0 0.0954395 0.486308 0 -0.873788 0.486308 0 -0.873788 0.774817 0 -0.632186 0.774817 0 -0.632186 0.953605 0 -0.30106 0.953605 0 -0.30106 0.5 0 -0.866026 0.5 0 -0.866026 -0.216077 0 -0.976376 -0.202136 -0.00208077 -0.979355 0.16008 0.00192564 -0.987102 0.18115 -0.000962896 -0.983455 0.513569 0.00100162 -0.858048 0.519672 0 -0.854366 0.415065 0 -0.909792 0.415065 0 -0.909792 0.539142 0 -0.842215 0.539142 0 -0.842215 0.177707 0 -0.984083 0.177707 0 -0.984083 -0.992134 0 0.125178 -0.992134 0 0.125178 -0.992134 0 -0.125178 -0.992134 0 -0.125178 -0.895764 0 0.444531 -0.895764 0 0.444531 -0.637209 0 0.770691 -0.637209 0 0.770691 -0.268272 0 0.963343 -0.268272 0 0.963343 0.147139 0 0.989116 0.147139 0 0.989116 0.539142 0 0.842215 0.539142 0 0.842215 0.415065 0 0.909792 0.415065 0 0.909792 0.999876 0 -0.0157395 0.999876 0 -0.0157395 0.934897 0 0.354919 0.934897 0 0.354919 0.737528 0 0.675317 0.737528 0 0.675317 1 0 0 1 0 0 0.737528 0 -0.675317 0.737528 0 -0.675317 0.934897 0 -0.354919 0.934897 0 -0.354919 0.999876 0 0.0157395 0.999876 0 0.0157395 0.995435 0 -0.0954395 0.995435 0 -0.0954395 0.998951 0 0.0458028 0.998951 0 0.0458028 0.920916 0 -0.389761 0.920916 0 -0.389761 0.64594 0 -0.763388 0.64594 0 -0.763388 0.231953 0 -0.972727 0.231953 0 -0.972727 -0.604474 0 -0.796625 -0.604474 0 -0.796625 -0.38766 0 -0.921802 -0.38766 0 -0.921802 -0.832857 0 -0.553488 -0.832857 0 -0.553488 -0.986042 0 -0.166494 -0.986042 0 -0.166494 -0.968416 0 0.249341 -0.968416 0 0.249341 -0.78303 0 0.621984 -0.78303 0 0.621984 -0.459809 0 0.888018 -0.459809 0 0.888018 -0.580371 0 0.814352 -0.580371 0 0.814352 0.519672 0 0.854366 0.513569 -0.00100162 0.858048 0.18115 0.000962895 0.983455 0.174135 0 0.984722 0.5 0 0.866025 0.5 0 0.866025 0.953605 0 0.30106 0.953605 0 0.30106 0.774817 0 0.632186 0.774817 0 0.632186 0.486307 0 0.873788 0.486307 0 0.873788 0.580371 0 0.814352 0.580371 0 0.814352 0.459809 0 0.888018 0.459809 0 0.888018 0.78303 0 0.621984 0.78303 0 0.621984 0.968416 0 0.249341 0.968416 0 0.249341 0.986042 0 -0.166494 0.986042 0 -0.166494 0.832857 0 -0.553489 0.832857 0 -0.553489 0.38766 0 -0.921802 0.38766 0 -0.921802 0.604474 0 -0.796625 0.604474 0 -0.796625 0.13587 0 -0.990727 0.13587 0 -0.990727 -0.998951 0 0.0458028 -0.998951 0 0.0458028 -0.995435 0 -0.0954394 -0.995435 0 -0.0954394 -0.486307 0 0.873788 -0.486307 0 0.873788 -0.774817 0 0.632186 -0.774817 0 0.632186 -0.953605 0 0.30106 -0.953605 0 0.30106 -0.5 0 0.866025 -0.5 0 0.866025 0.216076 0 0.976377 0.202136 0.00208066 0.979355 0.0142608 0 0.999898 -0.415065 0 0.909792 -0.415065 0 0.909792 -0.539142 0 0.842215 -0.539142 0 0.842215 -0.147139 0 0.989116 -0.147139 0 0.989116 0.268272 0 0.963343 0.268272 0 0.963343 0.637209 0 0.770691 0.637209 0 0.770691 0.895764 0 0.444531 0.895764 0 0.444531 0.992134 0 -0.125178 0.992134 0 -0.125178 0.992134 0 0.125178 0.992134 0 0.125178 0.891125 0 -0.453757 0.891125 0 -0.453757 0.613031 0 -0.790059 0.613031 0 -0.790059 0.218194 0 -0.975905 0.218194 0 -0.975905 -0.539142 0 -0.842215 -0.539142 0 -0.842215 -0.415065 0 -0.909792 -0.415065 0 -0.909792 -0.999876 0 0.0157395 -0.999876 0 0.0157395 -0.934897 0 -0.354919 -0.934897 0 -0.354919 -0.737528 0 -0.675316 -0.737528 0 -0.675316 -1 0 0 -1 0 0 -0.737528 0 0.675316 -0.737528 0 0.675316 -0.934897 0 0.354919 -0.934897 0 0.354919 -0.999876 0 -0.0157395 -0.999876 0 -0.0157395 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.15933 0.698074 -0.698074 -0.15933 0.698071 -0.698076 -0.330529 0.706857 -0.625383 -0.392441 0.777061 -0.492104 -0.465271 0.700866 -0.540657 -0.585054 0.70612 -0.398882 -0.52593 0.811942 -0.253275 -0.661912 0.703126 -0.259782 -0.704872 0.704874 -0.0794202 -0.569554 0.821954 0 -0.704873 0.704873 0.0794203 -0.645118 0.698072 0.310673 -0.49858 0.844469 0.195679 -0.585057 0.706116 0.398884 -0.446435 0.698073 0.559812 -0.402222 0.787251 0.46739 -0.330523 0.70686 0.625382 -0.15933 0.698075 0.698073 -0.159331 0.698074 0.698074 -0.186157 0.694747 -0.694747 -0.186157 0.694744 -0.694749 -0.50859 0.694745 -0.508591 -0.508588 0.69475 -0.508587 -0.694745 0.694749 -0.186156 -0.694745 0.694748 -0.186157 -0.694745 0.694748 0.186156 -0.694746 0.694747 0.186156 -0.508591 0.694745 0.50859 -0.508589 0.694748 0.508589 -0.186156 0.694748 0.694746 -0.186157 0.694747 0.694747 -0.508587 0.69475 -0.508588 -0.186157 0.694749 -0.694744 -0.186157 0.694747 -0.694746 -0.335653 0.857443 -0.390037 -0.585059 0.706115 -0.398884 -0.694749 0.694745 -0.186157 -0.414107 0.895601 -0.162525 -0.704873 0.704873 -0.0794203 -0.704873 0.704873 0.0794203 -0.514434 0.846379 0.137842 -0.661914 0.703124 0.259782 -0.585057 0.706116 0.398884 -0.394991 0.829436 0.394991 -0.465274 0.700862 0.540659 -0.186157 0.694745 0.694748 -0.186157 0.694747 0.694747 -0.159331 0.698074 -0.698074 -0.159331 0.698072 -0.698076 -0.446437 0.698069 -0.559815 -0.446436 0.698073 -0.559812 -0.645118 0.698072 -0.310673 -0.645117 0.698074 -0.310672 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645117 0.698074 0.310672 -0.645118 0.698073 0.310672 -0.446435 0.698073 0.559812 -0.446437 0.69807 0.559814 -0.159331 0.698073 0.698075 -0.159331 0.698074 0.698074 -0.186157 0.694747 -0.694746 -0.186157 0.694747 -0.694746 -0.508591 0.694745 -0.508591 -0.508591 0.694745 -0.50859 -0.694748 0.694745 -0.186158 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694748 0.694745 0.186157 -0.50859 0.694746 0.50859 -0.508592 0.694744 0.508591 -0.186157 0.694745 0.694748 -0.186157 0.694747 0.694747 -0.186156 0.694747 -0.694747 -0.186156 0.694749 -0.694745 -0.508588 0.69475 -0.508587 -0.508591 0.694745 -0.508591 -0.694748 0.694745 -0.186158 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694749 0.694745 0.186157 -0.508591 0.694745 0.50859 -0.508587 0.69475 0.508588 -0.186156 0.694749 0.694745 -0.186157 0.694747 0.694747 -0.159331 0.698074 -0.698074 -0.159331 0.698075 -0.698072 -0.446434 0.698075 -0.559811 -0.446433 0.698078 -0.559808 -0.645115 0.698076 -0.310671 -0.645115 0.698075 -0.310671 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645115 0.698075 0.310671 -0.645118 0.698073 0.310672 -0.446436 0.698072 0.559813 -0.446435 0.698072 0.559813 -0.159331 0.698072 0.698076 -0.15933 0.698074 0.698074 -0.508589 0.694748 -0.508589 -0.186157 0.694748 -0.694745 -0.186157 0.694747 -0.694747 -0.335654 0.857442 -0.390038 -0.585058 0.706115 -0.398884 -0.694747 0.694746 -0.186157 -0.414107 0.895601 -0.162525 -0.704872 0.704874 -0.0794202 -0.704872 0.704874 0.0794202 -0.514433 0.846379 0.137842 -0.661914 0.703124 0.259782 -0.585058 0.706115 0.398884 -0.394991 0.829435 0.394992 -0.465273 0.700865 0.540656 -0.186155 0.694751 0.694743 -0.186157 0.694747 0.694747 -0.186156 0.694747 -0.694747 -0.186156 0.694748 -0.694745 -0.508589 0.694748 -0.508589 -0.508589 0.694748 -0.508589 -0.694745 0.694748 -0.186157 -0.694744 0.69475 -0.186156 -0.694743 0.69475 0.186156 -0.694745 0.694748 0.186156 -0.508589 0.694748 0.508589 -0.508589 0.694748 0.508589 -0.186156 0.694748 0.694745 -0.186157 0.694747 0.694747 -0.15933 0.698075 -0.698073 -0.15933 0.698074 -0.698073 -0.330526 0.70686 -0.625381 -0.39244 0.777062 -0.492103 -0.465273 0.700864 -0.540658 -0.585056 0.706118 -0.398882 -0.525931 0.811941 -0.253275 -0.661913 0.703125 -0.259782 -0.704873 0.704874 -0.0794203 -0.569554 0.821954 0 -0.704873 0.704874 0.0794204 -0.645117 0.698074 0.310672 -0.49858 0.844469 0.195678 -0.585056 0.706118 0.398883 -0.446434 0.698075 0.559811 -0.402223 0.787249 0.467393 -0.330526 0.706859 0.625382 -0.159331 0.698073 0.698074 -0.159331 0.698074 0.698074 -0.159331 0.698074 -0.698074 -0.159331 0.698073 -0.698074 -0.446435 0.698074 -0.559812 -0.446434 0.698075 -0.559811 -0.645116 0.698075 -0.310671 -0.645117 0.698074 -0.310672 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645117 0.698074 0.310672 -0.645115 0.698076 0.310671 -0.446434 0.698075 0.55981 -0.446435 0.698074 0.559811 -0.159331 0.698074 0.698073 -0.159331 0.698074 0.698074 -0.186157 0.694748 -0.694745 -0.186157 0.694748 -0.694746 -0.50859 0.694747 -0.508589 -0.508591 0.694747 -0.508589 -0.694746 0.694747 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694746 0.694747 0.186157 -0.50859 0.694746 0.50859 -0.50859 0.694746 0.50859 -0.186157 0.694746 0.694747 -0.186157 0.694747 0.694747 -0.186157 0.694748 -0.694745 -0.186157 0.694748 -0.694746 -0.50859 0.694747 -0.508589 -0.508591 0.694746 -0.508589 -0.694747 0.694746 -0.186158 -0.694746 0.694746 -0.186158 -0.694747 0.694747 0.186157 -0.694747 0.694746 0.186157 -0.50859 0.694746 0.50859 -0.50859 0.694746 0.50859 -0.186157 0.694746 0.694747 -0.186157 0.694747 0.694747 -0.186156 0.694747 -0.694747 -0.186157 0.694746 -0.694747 -0.50859 0.694746 -0.50859 -0.508589 0.694747 -0.50859 -0.694746 0.694748 -0.186157 -0.694748 0.694746 -0.186155 -0.694748 0.694745 0.186158 -0.694746 0.694748 0.186155 -0.508589 0.694748 0.508589 -0.508589 0.694746 0.508591 -0.186158 0.694746 0.694747 -0.186157 0.694746 0.694747 -0.186157 0.694746 -0.694747 -0.186157 0.694747 -0.694746 -0.508588 0.694747 -0.50859 -0.508591 0.694746 -0.50859 -0.694749 0.694745 -0.186155 -0.694745 0.694748 -0.186157 -0.694746 0.694748 0.186154 -0.694748 0.694745 0.186158 -0.50859 0.694745 0.508591 -0.50859 0.694747 0.508589 -0.186157 0.694747 0.694746 -0.186157 0.694747 0.694746 -0.159332 0.698074 -0.698074 -0.159332 0.698074 -0.698074 -0.446435 0.698074 -0.559812 -0.446435 0.698074 -0.559812 -0.645117 0.698074 -0.310672 -0.645117 0.698074 -0.310672 -0.716026 0.698074 0 -0.716026 0.698074 0 -0.645117 0.698073 0.310673 -0.645117 0.698075 0.310671 -0.446435 0.698075 0.55981 -0.446435 0.698075 0.55981 -0.159332 0.698075 0.698072 -0.159329 0.698073 0.698075 -0.186158 0.694745 -0.694748 -0.186158 0.694745 -0.694748 -0.508592 0.694745 -0.50859 -0.508589 0.694747 -0.50859 -0.694746 0.694747 -0.186157 -0.694746 0.694747 -0.186157 -0.694747 0.694747 0.186157 -0.694746 0.694747 0.186157 -0.508589 0.694747 0.50859 -0.508589 0.694747 0.50859 -0.186157 0.694748 0.694745 -0.186157 0.694748 0.694745 -0.159329 0.698073 0.698075 -0.159332 0.698075 0.698072 -0.330519 0.706861 0.625384 -0.455832 0.682274 0.571594 -0.465276 0.700863 0.540656 -0.585054 0.706117 0.398886 -0.666992 0.672272 0.321206 -0.661913 0.703125 0.259782 -0.704873 0.704873 0.0794206 -0.743401 0.668846 0 -0.704873 0.704874 -0.079421 -0.645117 0.698074 -0.310672 -0.707241 0.650204 -0.277572 -0.585057 0.706116 -0.398884 -0.446435 0.698074 -0.559812 -0.159332 0.698074 -0.698074 -0.159332 0.698074 -0.698074 -0.330519 0.706859 -0.625385 -0.480997 0.675458 -0.558927 -0.186157 0.694746 -0.694747 -0.186157 0.694747 -0.694746 -0.508588 0.694747 -0.50859 -0.508591 0.694746 -0.50859 -0.694748 0.694745 -0.186158 -0.694748 0.694745 -0.186158 -0.694748 0.694745 0.186158 -0.694748 0.694745 0.186158 -0.50859 0.694745 0.508591 -0.50859 0.694747 0.508589 -0.186157 0.694747 0.694746 -0.186157 0.694747 0.694746 -0.15933 0.698074 -0.698074 -0.159331 0.698073 -0.698074 -0.446435 0.698073 -0.559812 -0.446435 0.698073 -0.559812 -0.645118 0.698073 -0.310672 -0.645118 0.698073 -0.310672 -0.716027 0.698073 0 -0.716027 0.698073 0 -0.645118 0.698073 0.310672 -0.645118 0.698074 0.310672 -0.446434 0.698074 0.559812 -0.446434 0.698074 0.559812 -0.159331 0.698074 0.698073 -0.159331 0.698073 0.698074 -0.707247 0.706223 -0.0324279 -0.707247 0.706223 -0.0324279 -0.704758 0.706222 0.0675702 -0.704758 0.706222 0.0675702 -0.664967 0.699238 0.262458 -0.664967 0.699239 0.262458 -0.500525 0.699238 0.510432 -0.500525 0.699239 0.510431 -0.249377 0.699239 0.669982 -0.249377 0.699238 0.669983 0.0449714 0.699238 0.713473 0.0449711 0.699239 0.713472 0.275197 0.704311 0.65438 0.275197 0.704311 0.65438 0.429111 0.704311 0.565517 0.429111 0.704312 0.565516 0.595398 0.69924 0.395682 0.5954 0.699238 0.395683 0.704911 0.699238 0.119025 0.70491 0.699239 0.119025 0.692308 0.699239 -0.178251 0.692311 0.699236 -0.178252 0.559781 0.699236 -0.44465 0.55978 0.699237 -0.44465 0.410897 0.706221 -0.576554 0.410897 0.706222 -0.576554 0.32554 0.706222 -0.628709 0.325541 0.706221 -0.628709 0.144415 0.699694 -0.699695 0.144415 0.699694 -0.699694 -0.357275 0.699584 -0.618819 -0.357275 0.699584 -0.618819 -0.346956 0.700706 -0.623404 -0.346956 0.700707 -0.623403 -0.552792 0.700707 -0.451032 -0.552793 0.700706 -0.451033 -0.680349 0.700707 -0.214791 -0.680348 0.700707 -0.214791 -0.32554 0.706222 -0.628708 -0.32554 0.706222 -0.628708 -0.410897 0.706222 -0.576554 -0.410897 0.706221 -0.576554 -0.55978 0.699237 -0.44465 -0.559779 0.699239 -0.444649 -0.692309 0.699239 -0.178251 -0.692308 0.699239 -0.178251 -0.70491 0.699239 0.119025 -0.704911 0.699238 0.119025 -0.5954 0.699238 0.395683 -0.595401 0.699237 0.395683 -0.429112 0.70431 0.565518 -0.429112 0.70431 0.565518 -0.275197 0.704311 0.65438 -0.275197 0.704311 0.65438 -0.0449714 0.699239 0.713472 -0.0449712 0.699238 0.713473 0.249377 0.699238 0.669983 0.249376 0.69924 0.669982 0.500524 0.69924 0.510431 0.500525 0.699238 0.510431 0.664967 0.699239 0.262458 0.664967 0.699239 0.262458 0.704758 0.706223 0.0675702 0.704758 0.706222 0.0675702 0.707247 0.706223 -0.0324279 0.707247 0.706223 -0.0324279 0.680349 0.700707 -0.214791 0.680349 0.700707 -0.214791 0.552793 0.700706 -0.451033 0.552793 0.700707 -0.451032 0.346956 0.700707 -0.623403 0.346956 0.700706 -0.623404 0.357275 0.699585 -0.618818 0.357275 0.699584 -0.618819 0.370515 0.701185 -0.609145 0.370515 0.701186 -0.609145 0.129156 0.701186 -0.701183 0.129156 0.701184 -0.701184 0.381707 0.706223 -0.596279 0.381706 0.706223 -0.596279 0.293861 0.706223 -0.644123 0.293862 0.706223 -0.644123 0.126662 0.701412 -0.701411 0.126661 0.701412 -0.701412 -0.704309 0.704309 -0.0888629 -0.704309 0.704309 -0.0888629 -0.704309 0.704309 0.0888629 -0.704309 0.704309 0.0888629 -0.640372 0.699238 0.31779 -0.640371 0.699238 0.31779 -0.455534 0.699238 0.550958 -0.455534 0.699239 0.550958 -0.191785 0.699239 0.688683 -0.191785 0.699238 0.688683 0.105188 0.699238 0.707108 0.105188 0.699239 0.707107 0.293862 0.706223 0.644123 0.293862 0.706222 0.644124 0.381707 0.706222 0.59628 0.381706 0.706223 0.596279 0.526188 0.700708 0.481803 0.526189 0.700707 0.481804 0.667001 0.700707 0.253216 0.667002 0.700706 0.253216 0.713362 0.700706 -0.0112293 0.71336 0.700708 -0.0112288 0.714549 0.699586 0 0.714549 0.699586 0 0.71336 0.700708 0.0112293 0.713362 0.700706 0.0112288 0.667002 0.700706 -0.253217 0.667001 0.700707 -0.253216 0.526188 0.700708 -0.481804 0.526188 0.700708 -0.481803 0.707247 0.706223 0.0324279 0.707247 0.706222 0.0324279 0.704758 0.706223 -0.0675702 0.704758 0.706222 -0.0675702 0.660126 0.697264 -0.279386 0.660125 0.697265 -0.279386 0.463019 0.697265 -0.547207 0.463019 0.697264 -0.547207 0.166267 0.697264 -0.697265 0.166267 0.697268 -0.697261 -0.452505 0.705929 -0.54489 -0.26562 0.89828 -0.350055 -0.380289 0.706764 -0.596545 -0.275198 0.704308 -0.654383 -0.229475 0.796444 -0.559481 -0.348123 0.707091 -0.615494 -0.595401 0.699237 -0.395683 -0.5954 0.699238 -0.395683 -0.704911 0.699238 -0.119025 -0.70491 0.699239 -0.119025 -0.692309 0.699239 0.178251 -0.692309 0.699239 0.178251 -0.559779 0.699239 0.444649 -0.55978 0.699237 0.44465 -0.410897 0.706221 0.576554 -0.410897 0.706222 0.576554 -0.32554 0.706222 0.628709 -0.32554 0.706222 0.628708 0.366405 0.700708 0.612174 0.366405 0.700707 0.612174 0.114209 0.700708 0.704248 -0.15416 0.700707 0.696595 -0.15416 0.700707 0.696595 -0.0100844 0.707071 0.70707 0.129851 0.666293 0.734297 0.357275 0.699585 0.618818 0.357275 0.699585 0.618818 0.346955 0.700708 0.623403 0.346956 0.700707 0.623403 0.552792 0.700707 0.451032 0.552793 0.700706 0.451033 0.680349 0.700707 0.214791 0.680348 0.700707 0.214791 0.325541 0.706221 0.628709 0.32554 0.706222 0.628709 0.410897 0.706222 0.576554 0.410897 0.706221 0.576554 0.55978 0.699237 0.44465 0.559781 0.699236 0.44465 0.692312 0.699236 0.178252 0.692309 0.699239 0.178252 0.70491 0.699239 -0.119024 0.704911 0.699238 -0.119025 0.5954 0.699238 -0.395683 0.595399 0.69924 -0.395681 0.429111 0.704312 -0.565517 0.269245 0.70469 -0.656444 0.236898 0.791555 -0.563311 0.348122 0.707092 -0.615493 0.429112 0.704309 -0.565519 0.0965211 0.703803 -0.703807 0.096522 0.703808 -0.703802 -0.704759 0.706222 -0.0675702 -0.704758 0.706223 -0.0675702 -0.707247 0.706222 0.0324279 -0.707247 0.706223 0.0324279 -0.680348 0.700707 0.214791 -0.680349 0.700707 0.214791 -0.552793 0.700706 0.451033 -0.552793 0.700707 0.451032 -0.346955 0.700707 0.623403 -0.346955 0.700708 0.623402 -0.357275 0.699584 0.618818 -0.357274 0.699586 0.618817 0.15416 0.700706 0.696596 -0.366405 0.700707 0.612174 -0.366405 0.700708 0.612173 -0.124076 0.701644 0.701642 -0.118826 0.670073 0.732723 0.0100844 0.707071 0.70707 0.154159 0.700707 0.696595 -0.381707 0.706222 0.59628 -0.381707 0.706222 0.59628 -0.293862 0.706222 0.644124 -0.293862 0.706223 0.644123 -0.105188 0.699239 0.707107 -0.105188 0.699238 0.707108 0.191785 0.699238 0.688683 0.191785 0.699238 0.688684 0.455535 0.699237 0.550959 0.455534 0.699238 0.550958 0.640371 0.699238 0.31779 0.640372 0.699238 0.31779 0.704309 0.704309 0.0888629 0.704309 0.704309 0.0888629 0.704309 0.704309 -0.0888629 0.704309 0.704309 -0.0888629 0.637757 0.698432 -0.324743 0.637758 0.698431 -0.324744 0.438732 0.698432 -0.565427 0.438733 0.69843 -0.565428 0.156156 0.698431 -0.698433 0.156156 0.698432 -0.698432 -0.293862 0.706223 -0.644123 -0.293861 0.706223 -0.644123 -0.381706 0.706223 -0.596279 -0.381707 0.706222 -0.59628 -0.526189 0.700707 -0.481804 -0.526188 0.700708 -0.481803 -0.667001 0.700707 -0.253216 -0.667001 0.700708 -0.253216 -0.71336 0.700708 0.0112293 -0.71336 0.700708 0.0112293 -0.714549 0.699586 0 -0.714549 0.699586 0 -0.71336 0.700708 -0.0112293 -0.71336 0.700708 -0.0112293 -0.667001 0.700708 0.253216 -0.667001 0.700707 0.253217 -0.526189 0.700707 0.481804 -0.526189 0.700707 0.481804 -0.186157 0.694747 -0.694747 -0.186157 0.694748 -0.694745 -0.508589 0.694748 -0.508589 -0.508589 0.694748 -0.508589 -0.694745 0.694748 -0.186157 -0.694744 0.69475 -0.186156 -0.694743 0.69475 0.186156 -0.694745 0.694749 0.186156 -0.508587 0.69475 0.508588 -0.508591 0.694745 0.50859 -0.186158 0.694745 0.694748 -0.186157 0.694747 0.694747 -0.22252 0 -0.974928 -0.258367 -0.0590912 -0.964238 -0.703677 -0.0983623 -0.703678 -0.652286 0 -0.757973 -0.467273 0 -0.884113 -0.993712 0 0.111965 -0.993712 0 -0.111965 -0.95919 -0.117891 -0.257014 -0.930874 0 -0.365341 -0.82624 0 -0.563319 -0.9117 -0.201916 0.357816 -0.965926 0 0.258819 -0.82624 0 0.563319 -0.703678 -0.0983616 0.703677 -0.652288 0 0.757971 -0.467268 0 0.884116 -0.258366 -0.0590897 0.964238 -0.22252 0 0.974928 -0.707106 0 -0.707107 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707107 0 0.707106 -0.707107 0 0.707106 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.0588079 0 -0.998269 -0.257905 0.0840361 -0.962509 -0.257904 0.0840345 -0.962509 -0.448204 0 -0.893931 -0.707106 0 -0.707107 -0.978461 -0.174529 0.110246 -1 0 0 -0.930874 0 0.365341 -0.898154 -0.0789903 0.432528 -0.82624 0 0.563319 -0.623489 0 0.781832 -0.651147 -0.0590908 0.756648 -0.221996 0.0686857 0.972625 -0.258819 0 0.965926 -0.993712 0 -0.111965 -0.930873 0 -0.365342 -0.906017 -0.0622361 -0.41864 -0.826222 0.00667499 -0.563305 -0.707032 -0.0145065 -0.707032 -0.651357 0.0533958 -0.756891 -0.51839 -0.0156427 -0.855001 -0.258367 0.0590892 -0.964238 -0.222522 0 -0.974928 -0.900969 0 0.433884 -0.623489 0 0.781832 -0.623489 0 0.781832 -0.222521 0 0.974928 -0.222521 0 0.974928 -0.997921 0.0644446 0 -0.998577 0 0.05333 -0.900969 0 0.433884 -0.84924 0.142024 -0.508548 -0.950749 0 -0.309962 -0.985408 0 -0.170209 -0.900969 0 -0.433884 -0.623489 0 -0.781832 -0.623489 0 -0.781832 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.893928 0 0.44821 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.962509 0.0840385 0.257902 -0.962509 0.0840356 0.257904 -0.998269 0 0.0588079 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.707107 0 -0.707106 -0.707107 0 -0.707106 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.550068 0 0.83512 -0.258818 0 0.965926 -0.258818 0 0.965926 -0.704605 0.0840326 0.704607 -0.704606 0.0840353 0.704605 -0.835123 0 0.550064 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.707107 0 -0.707106 -0.707107 0 -0.707106 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.0588079 0 0.998269 -0.257902 0.0840347 0.96251 -0.222415 0.0307354 0.974467 -0.414475 0 0.910061 -0.62349 0 0.781832 -0.62349 0 0.781832 -0.900969 0 0.433884 -0.900969 0 0.433884 -1 0 0 -1 0 0 -0.900969 0 -0.433884 -0.900969 0 -0.433884 -0.62349 0 -0.781832 -0.62349 0 -0.781832 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.622728 -0.0493943 -0.780878 -0.258367 0.0590895 -0.964238 -0.222522 0 -0.974928 -0.993712 0 -0.111965 -0.930874 0 -0.365341 -0.898154 -0.0789902 -0.432528 -0.82624 0 -0.563319 -0.652287 0 -0.757972 -0.978461 -0.174529 0.110246 -1 0 0 -0.930874 0 0.365341 -0.898154 -0.0789902 0.432528 -0.82624 0 0.563319 -0.623489 0 0.781832 -0.651148 -0.0590914 0.756647 -0.221995 0.0686846 0.972626 -0.258818 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.222521 0 -0.974928 -0.258367 -0.0590902 -0.964238 -0.703678 -0.098362 -0.703678 -0.652287 0 -0.757972 -0.467271 0 -0.884114 -0.993712 0 0.111965 -0.993712 0 -0.111965 -0.95919 -0.117892 -0.257015 -0.930874 0 -0.365341 -0.82624 0 -0.563318 -0.9117 -0.201915 0.357816 -0.965926 0 0.258819 -0.82624 0 0.563319 -0.703678 -0.0983616 0.703678 -0.652287 0 0.757972 -0.467271 0 0.884114 -0.258367 -0.0590902 0.964238 -0.222521 0 0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.62349 0 -0.781831 -0.62349 0 -0.781831 -0.900969 0 -0.433883 -0.900969 0 -0.433883 -1 0 0 -1 0 0 -0.900969 0 0.433883 -0.900969 0 0.433883 -0.62349 0 0.781831 -0.62349 0 0.781831 -0.222521 0 0.974928 -0.222521 0 0.974928 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.0569825 0.705958 -0.705958 -0.116619 -0.252892 -0.96044 -0.148924 0.559058 -0.815644 -0.154937 0.707031 -0.690001 -0.262651 0.705198 -0.658567 -0.338619 0.296866 -0.892865 -0.184933 0.699614 -0.690174 -0.171371 0.707106 -0.686028 -0.45026 0.706892 -0.5455 -0.575732 -0.0343189 -0.816918 -0.540633 -0.307001 -0.783241 -0.503537 0.339156 -0.794622 -0.351536 0.70687 -0.613806 -0.628397 0.704517 -0.329808 -0.547278 0.705868 -0.449709 -0.732757 -0.204086 -0.649166 -0.589144 0.553008 -0.589144 -0.481155 0.707012 -0.51829 -0.946397 -0.0811094 -0.312657 -0.818015 0.55127 -0.164174 -0.895982 0.402238 -0.188206 -0.809213 -0.552623 -0.199453 -0.67378 0.706631 -0.216085 -0.628394 0.70452 -0.329807 -0.700756 0.70707 -0.0948341 -0.709693 0.704511 0 -0.709693 0.704511 0 -0.671727 0.706778 0.221915 -0.965389 0.033363 0.258673 -0.897002 -0.38276 0.221091 -0.818014 0.551271 0.164174 -0.700756 0.70707 0.0948341 -0.634879 0.705398 0.315186 -0.87721 0.136153 0.460396 -0.590906 0.707021 0.388526 -0.547276 0.70587 0.449707 -0.732756 -0.204091 0.649165 -0.589141 0.553014 0.589142 -0.540633 -0.307001 0.783241 -0.427905 0.706081 0.564222 -0.481155 0.707012 0.51829 -0.184928 0.699623 0.690167 -0.281904 0.479655 0.83094 -0.329992 -0.366061 0.870118 -0.295557 0.706618 0.642913 -0.356439 0.70675 0.61111 -0.171381 0.707106 0.686025 -0.0855434 0.704515 0.704514 -0.0855435 0.704515 0.704515 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.510202 0.84912 -0.136708 -0.373494 0.84912 -0.373494 -0.136708 0.84912 -0.510202 -0.136708 0.84912 0.510202 -0.373494 0.84912 0.373494 -0.510202 0.84912 0.136708 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.510203 0.84912 0.136706 0.373494 0.84912 0.373494 0.136708 0.84912 0.510202 0.136708 0.84912 -0.510202 0.373494 0.84912 -0.373494 0.510203 0.84912 -0.136706 -0.510202 0.84912 -0.136708 -0.373494 0.84912 -0.373494 -0.136708 0.84912 -0.510202 -0.136708 0.84912 0.510202 -0.373494 0.84912 0.373494 -0.510202 0.84912 0.136708 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.510202 0.84912 0.136708 0.373494 0.84912 0.373494 0.136708 0.84912 0.510202 0.136708 0.84912 -0.510202 0.373494 0.84912 -0.373494 0.510202 0.84912 -0.136708 0 -1 0 0 -1 0 -0.98846 0 0.151484 -0.98846 0 0.151484 -0.855371 0 0.518016 -0.855371 0 0.518016 0 1 0 0 1 0 0.943374 0 -0.331732 0.943374 0 -0.331732 0.936439 0 -0.350832 0.936439 0 -0.350832 0 1 0 0 1 0 0.646046 0 -0.763299 0.646046 0 -0.763299 0 -1 0 0 -1 0 -0.507512 0 0.861645 -0.507512 0 0.861645 -0.809717 0 0.586821 -0.809717 0 0.586821 -0.603822 0 0.797119 -0.603822 0 0.797119 0 1 0 0 1 0 0.763299 0 -0.646045 0.763299 0 -0.646045 0 -1 0 0 -1 0 -0.797119 0 0.603822 -0.797119 0 0.603822 -0.586823 0 0.809715 -0.586823 0 0.809715 -0.861645 0 0.507512 -0.861645 0 0.507512 0 1 0 0 1 0 0.350832 0 -0.936439 0.350832 0 -0.936439 0.331733 0 -0.943374 0.331733 0 -0.943374 0 -1 0 0 -1 0 -0.518016 0 0.855371 -0.518016 0 0.855371 -0.151484 0 0.98846 -0.151484 0 0.98846 0.151484 0 0.98846 0.151484 0 0.98846 0.518016 0 0.855371 0.518016 0 0.855371 0 1 0 0 1 0 -0.331733 0 -0.943374 -0.331733 0 -0.943374 -0.350832 0 -0.936439 -0.350832 0 -0.936439 0 -1 0 0 -1 0 0.861645 0 0.507512 0.861645 0 0.507512 0.586823 0 0.809715 0.586823 0 0.809715 0.797119 0 0.603822 0.797119 0 0.603822 0 1 0 0 1 0 -0.763299 0 -0.646045 -0.763299 0 -0.646045 0 -1 0 0 -1 0 0.603822 0 0.797119 0.603822 0 0.797119 0.809717 0 0.586821 0.809717 0 0.586821 0.507511 0 0.861645 0.507511 0 0.861645 0 1 0 0 1 0 -0.646045 0 -0.763299 -0.646045 0 -0.763299 0 -1 0 0 -1 0 0.855371 0 0.518016 0.855371 0 0.518016 0.98846 0 0.151484 0.98846 0 0.151484 0 1 0 0 1 0 0 -1 0 0 -1 0 -0.943374 0 -0.331732 -0.943374 0 -0.331732 -0.936439 0 -0.350832 -0.936439 0 -0.350832 -0.11675 -0.851306 0.511515 -0.52467 -0.851306 0 -0.472711 -0.851306 0.227645 -0.327126 -0.851306 0.410204 -0.116749 -0.851306 -0.511516 -0.327126 -0.851306 -0.410204 -0.472711 -0.851306 -0.227645 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.510202 -0.84912 -0.136709 0.373495 -0.84912 -0.373493 0.136707 -0.84912 -0.510202 0.136709 -0.84912 0.510202 0.373494 -0.84912 0.373494 0.510202 -0.84912 0.136709 -0.510202 -0.84912 0.136709 -0.373494 -0.84912 0.373494 -0.136709 -0.84912 0.510202 -0.136707 -0.84912 -0.510202 -0.373495 -0.84912 -0.373493 -0.510202 -0.84912 -0.136709 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.510202 -0.84912 -0.136708 0.373494 -0.84912 -0.373494 0.136707 -0.84912 -0.510202 0.136709 -0.84912 0.510202 0.373493 -0.84912 0.373494 0.510202 -0.84912 0.136708 0.997661 -0.00392366 0.0682414 0.999916 0 0.0129539 0.995429 0 0.0955013 0.992371 0 0.123288 0.997661 -0.00392122 0.0682418 0.957563 -0.280683 0.065499 0.999162 0 0.0409323 -0.92675 0 0.375679 -0.729846 0 -0.683611 -0.860974 -0.0628608 -0.504749 -0.866964 0 -0.498372 -0.816127 0 0.577873 -0.921685 -0.062864 0.382813 -0.92675 0 0.375679 -0.997669 0 -0.0682431 -0.997669 0 -0.0682431 -0.866963 0 -0.498372 0 -1 0 0 -1 0 0 -1 0 -0.947886 0 0.318611 -0.947886 0 0.318611 -0.895683 0 -0.444694 -0.895683 0 -0.444694 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.942254 -0.00392445 0.334877 0.959345 0 0.282237 0.93275 0 0.360524 0.922303 0 0.386467 0.942254 -0.00392216 0.334877 0.904381 -0.280687 0.321417 0.951067 0 0.308985 -0.99374 0 0.111714 -0.518357 0 -0.855164 -0.692868 -0.0628564 -0.71832 -0.700355 0 -0.713795 -0.941784 0 0.336219 -0.990789 -0.062853 0.119948 -0.99374 0 0.111714 -0.942261 0 -0.33488 -0.942261 0 -0.33488 -0.700355 0 -0.713795 0 -1 0 0 -1 0 0 -1 0 -0.998697 0 0.0510434 -0.998697 0 0.0510434 -0.742493 0 -0.669853 -0.742493 0 -0.669853 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.534216 0 -0.845348 -0.534216 0 -0.845348 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.816964 -0.00392419 0.576676 0.84762 0 0.530603 0.800893 0 0.598807 0.783827 0 0.62098 0.816964 -0.0039231 0.576676 0.784129 -0.28068 0.553499 0.832435 0 0.554122 -0.98703 0 -0.160538 -0.268373 0 -0.963315 -0.473373 -0.062867 -0.878616 -0.481805 0 -0.876278 -0.997569 0 0.0696798 -0.986409 -0.0628581 -0.151811 -0.98703 0 -0.160538 -0.81697 0 -0.57668 -0.81697 0 -0.57668 -0.481805 0 -0.876278 0 -1 0 0 -1 0 0 -1 0 -0.975434 0 -0.220291 -0.975434 0 -0.220291 0.631083 -0.00392208 0.775706 0.673011 0 0.739632 0.609637 0 0.792681 0.587217 0 0.80943 0.631083 -0.00392358 0.775705 0.605718 -0.280686 0.744527 0.652066 0 0.758162 -0.907116 0 -0.420882 0.00147884 0 -0.999999 -0.218771 -0.0628687 -0.973749 -0.227521 0 -0.973773 -0.979378 0 -0.202035 -0.908872 -0.0628615 -0.412311 -0.907116 0 -0.420882 -0.631088 0 -0.775712 -0.631088 0 -0.775712 -0.227521 0 -0.973773 0 -1 0 0 -1 0 0 -1 0 -0.879828 0 -0.475292 -0.879828 0 -0.475292 -0.286327 0 -0.958132 -0.286327 0 -0.958132 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.373168 0 0.927764 0.382386 -0.280681 0.88034 0.423336 0 0.905973 0.34705 0 0.937846 0.398398 -0.00392426 0.917204 0.398398 -0.00392444 0.917204 0.448534 0 0.893766 -0.759925 0 -0.650011 0.271192 0 -0.962525 0.0520553 -0.0628608 -0.996664 0.0436374 0 -0.999047 -0.888541 0 -0.458798 -0.763928 -0.062853 -0.642233 -0.759925 0 -0.650011 -0.398402 0 -0.917211 -0.398402 0 -0.917211 0.0436374 0 -0.999047 0 -1 0 0 -1 0 0 -1 0 -0.718966 0 -0.695046 -0.718966 0 -0.695046 -0.0172182 0 -0.999852 -0.0172182 0 -0.999852 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.136166 -0.00392366 0.990678 0.190756 0 0.981638 0.109022 0 0.994039 0.0811739 0 0.9967 0.136166 -0.00392277 0.990678 0.130693 -0.280688 0.950859 0.16321 0 0.986591 -0.556374 0 -0.830932 0.520815 0 -0.85367 0.319021 -0.0628583 -0.945661 0.311558 0 -0.950227 -0.731836 0 -0.681481 -0.562328 -0.0628664 -0.824521 -0.556374 0 -0.830932 -0.136165 0 -0.990686 -0.136165 0 -0.990686 0.311558 0 -0.950227 0 -1 0 0 -1 0 0 -1 0 -0.504803 0 -0.863234 -0.504803 0 -0.863234 0.253163 0 -0.967424 0.253163 0 -0.967424 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.16321 0 0.986591 -0.130693 -0.280688 0.950859 -0.109022 0 0.994039 -0.190758 0 0.981637 -0.136166 -0.0039238 0.990678 -0.136166 -0.00392268 0.990678 -0.0811744 0 0.9967 -0.311558 0 -0.950227 0.731836 0 -0.681481 0.562328 -0.0628664 -0.824521 0.556374 0 -0.830932 -0.520815 0 -0.85367 -0.319021 -0.0628583 -0.945661 -0.311558 0 -0.950227 0.136165 0 -0.990686 0.136165 0 -0.990686 0.556374 0 -0.830932 0 -1 0 0 -1 0 0 -1 0 -0.253164 0 -0.967423 -0.253164 0 -0.967423 0.504806 0 -0.863233 0.504806 0 -0.863233 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.718966 0 -0.695046 0.718966 0 -0.695046 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.423336 0 0.905973 -0.382386 -0.280681 0.88034 -0.373168 0 0.927764 -0.448534 0 0.893766 -0.398398 -0.00392438 0.917204 -0.398398 -0.00392431 0.917204 -0.34705 0 0.937846 -0.0436374 0 -0.999047 0.888541 0 -0.458798 0.763928 -0.062853 -0.642233 0.759925 0 -0.650011 -0.271192 0 -0.962525 -0.0520553 -0.0628608 -0.996664 -0.0436374 0 -0.999047 0.398402 0 -0.917211 0.398402 0 -0.917211 0.759925 0 -0.650011 0 -1 0 0 -1 0 0 -1 0 0.0172182 0 -0.999852 0.0172182 0 -0.999852 -0.652066 0 0.758162 -0.605718 -0.280686 0.744527 -0.609637 0 0.792681 -0.673011 0 0.739632 -0.631083 -0.003922 0.775706 -0.631083 -0.00392336 0.775705 -0.587217 0 0.80943 0.227521 0 -0.973773 0.979378 0 -0.202035 0.908872 -0.0628615 -0.412311 0.907116 0 -0.420882 -0.00147884 0 -0.999999 0.218771 -0.0628686 -0.973749 0.227521 0 -0.973773 0.631088 0 -0.775712 0.631088 0 -0.775712 0.907116 0 -0.420882 0 -1 0 0 -1 0 0 -1 0 0.286327 0 -0.958132 0.286327 0 -0.958132 0.879828 0 -0.475292 0.879828 0 -0.475292 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.534216 0 -0.845348 0.534216 0 -0.845348 0.975434 0 -0.220291 0.975434 0 -0.220291 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.816964 -0.00392313 0.576676 -0.783827 0 0.62098 -0.832435 0 0.554122 -0.84762 0 0.530603 -0.816964 -0.00392415 0.576676 -0.784129 -0.28068 0.553499 -0.800893 0 0.598807 0.481805 0 -0.876278 0.997569 0 0.0696798 0.986409 -0.0628581 -0.151811 0.98703 0 -0.160538 0.268373 0 -0.963315 0.473373 -0.0628669 -0.878616 0.481805 0 -0.876278 0.81697 0 -0.57668 0.81697 0 -0.57668 0.98703 0 -0.160538 0 -1 0 0 -1 0 0 -1 0 -0.951067 0 0.308986 -0.904384 -0.280676 0.321418 -0.93275 0 0.360523 -0.959345 0 0.282237 -0.942254 -0.00392446 0.334877 -0.942254 -0.00392214 0.334877 -0.922303 0 0.386467 0.700355 0 -0.713795 0.941784 0 0.336219 0.990789 -0.062853 0.119948 0.99374 0 0.111714 0.518357 0 -0.855164 0.692868 -0.0628564 -0.71832 0.700355 0 -0.713795 0.942261 0 -0.33488 0.942261 0 -0.33488 0.99374 0 0.111714 0 -1 0 0 -1 0 0 -1 0 0.742493 0 -0.669853 0.742493 0 -0.669853 0.998697 0 0.0510434 0.998697 0 0.0510434 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.999162 0 0.0409323 -0.957563 -0.280683 0.065499 -0.995429 0 0.0955013 -0.999916 0 0.0129539 -0.997661 -0.0039237 0.068242 -0.997661 -0.00392474 0.0682418 -0.992365 0 0.123337 0.866964 0 -0.498372 0.816127 0 0.577873 0.921685 -0.062864 0.382813 0.92675 0 0.375679 0.729846 0 -0.683611 0.860974 -0.0628608 -0.504749 0.866963 0 -0.498372 0.997669 0 -0.0682431 0.997669 0 -0.0682431 0.92675 0 0.375679 0 -1 0 0 -1 0 0 -1 0 0.895673 0 -0.444714 0.895673 0 -0.444714 0.947886 0 0.318611 0.947886 0 0.318611 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.510203 0.84912 0.136706 0.373494 0.84912 0.373494 0.136708 0.84912 0.510202 0.136709 0.84912 -0.510202 0.373494 0.84912 -0.373494 0.510203 0.84912 -0.136707 -0.510202 0.84912 -0.136709 -0.373494 0.84912 -0.373494 -0.136709 0.84912 -0.510202 -0.136708 0.84912 0.510202 -0.373494 0.84912 0.373494 -0.510202 0.84912 0.136708 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.510202 0.84912 -0.136709 -0.373494 0.84912 -0.373494 -0.136709 0.84912 -0.510202 -0.136708 0.84912 0.510202 -0.373494 0.84912 0.373494 -0.510202 0.84912 0.136708 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.510202 0.84912 0.136708 0.373494 0.84912 0.373494 0.136708 0.84912 0.510202 0.136709 0.84912 -0.510202 0.373494 0.84912 -0.373494 0.510202 0.84912 -0.136709 -0.258822 0 -0.965925 -0.258822 0 -0.965925 -0.707105 0 -0.707109 -0.707105 0 -0.707109 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.707109 0 0.707105 -0.707109 0 0.707105 -0.258822 0 0.965925 -0.258822 0 0.965925 -0.510202 0.84912 -0.136709 -0.373494 0.849119 -0.373495 -0.13671 0.849119 -0.510203 -0.13671 0.84912 0.510201 -0.373495 0.84912 0.373493 -0.510202 0.84912 0.136709 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.510202 0.84912 0.136709 0.373495 0.84912 0.373493 0.136709 0.84912 0.510201 0.13671 0.849119 -0.510203 0.373493 0.84912 -0.373495 0.510202 0.84912 -0.136709 0.258821 0 0.965925 0.258821 0 0.965925 0.707109 0 0.707105 0.707109 0 0.707105 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707105 0 -0.707109 0.707105 0 -0.707109 0.258821 0 -0.965925 0.258821 0 -0.965925 -0.622972 -0.0406769 -0.781186 -0.258515 0.0486798 -0.96478 -0.222521 0 -0.974928 -0.993712 0 -0.111964 -0.930874 0 -0.365341 -0.899058 -0.0650979 -0.432964 -0.826239 0 -0.563319 -0.652283 0 -0.757976 -0.983298 -0.144398 0.110791 -1 0 0 -0.930874 0 0.365341 -0.899058 -0.0650979 0.432964 -0.826239 0 0.563319 -0.623493 0 0.781829 -0.651515 -0.0486712 0.757073 -0.222164 0.0565968 0.973365 -0.258822 0 0.965925 -0.13671 0.849119 -0.510203 -0.42642 0.85653 -0.290728 -0.514173 0.855728 -0.0579333 -0.483396 0.854596 0.189719 -0.13671 0.84912 0.510201 -0.340302 0.853126 0.395437 -0.42642 0.85653 0.290728 -0.514173 0.855728 0.0579333 -0.483396 0.854596 -0.189719 -0.340299 0.853126 -0.39544 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.510202 0.84912 0.136709 0.373495 0.84912 0.373493 0.136709 0.84912 0.510201 0.13671 0.849119 -0.510203 0.373493 0.84912 -0.373495 0.510202 0.84912 -0.136709 0.258821 0 0.965925 0.258821 0 0.965925 0.707109 0 0.707105 0.707109 0 0.707105 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.707105 0 -0.707109 0.707105 0 -0.707109 0.258821 0 -0.965925 0.258821 0 -0.965925 0.0220586 0 -0.999757 0.0220586 0 -0.999757 0 1 0 0 1 0 0.3413 0 0.939955 0.3413 0 0.939955 0 -1 0 0 -1 0 -0.184132 0 -0.982902 -0.184132 0 -0.982902 -0.527426 0 -0.849601 -0.527426 0 -0.849601 -0.861645 0 -0.507512 -0.861645 0 -0.507512 -0.586823 0 -0.809715 -0.586823 0 -0.809715 -0.797119 0 -0.603822 -0.797119 0 -0.603822 0 1 0 0 1 0 0.763299 0 0.646045 0.763299 0 0.646045 0 -1 0 0 -1 0 -0.603822 0 -0.797119 -0.603822 0 -0.797119 -0.809717 0 -0.586821 -0.809717 0 -0.586821 -0.507512 0 -0.861645 -0.507512 0 -0.861645 0 1 0 0 1 0 0.646046 0 0.763299 0.646046 0 0.763299 0 -1 0 0 -1 0 -0.855371 0 -0.518016 -0.855371 0 -0.518016 -0.98846 0 -0.151484 -0.98846 0 -0.151484 0 1 0 0 1 0 0.936439 0 0.350832 0.936439 0 0.350832 0.943374 0 0.331733 0.943374 0 0.331733 0 -1 0 0 -1 0 0 1 0 0 1 0 -0.943374 0 0.331733 -0.943374 0 0.331733 -0.936439 0 0.350832 -0.936439 0 0.350832 0 -1 0 0 -1 0 0.98846 0 -0.151484 0.98846 0 -0.151484 0.855371 0 -0.518016 0.855371 0 -0.518016 0 1 0 0 1 0 -0.646045 0 0.763299 -0.646045 0 0.763299 0 -1 0 0 -1 0 0.507511 0 -0.861645 0.507511 0 -0.861645 0.809717 0 -0.586821 0.809717 0 -0.586821 0.603822 0 -0.797119 0.603822 0 -0.797119 0 1 0 0 1 0 -0.763299 0 0.646045 -0.763299 0 0.646045 0 -1 0 0 -1 0 0.797119 0 -0.603822 0.797119 0 -0.603822 0.586823 0 -0.809715 0.586823 0 -0.809715 0.861645 0 -0.507512 0.861645 0 -0.507512 0.527426 0 -0.849601 0.527426 0 -0.849601 0.184132 0 -0.982902 0.184132 0 -0.982902 -0.0220586 0 -0.999757 -0.0220586 0 -0.999757 0 1 0 0 1 0 -0.3413 0 0.939955 -0.3413 0 0.939955 0 -1 0 0 -1 0 -0.510202 -0.84912 0.136708 -0.373493 -0.84912 0.373495 -0.13671 -0.84912 0.510202 -0.136709 -0.84912 -0.510202 -0.373494 -0.84912 -0.373494 -0.510202 -0.84912 -0.136708 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.510202 -0.84912 -0.136708 0.373494 -0.84912 -0.373494 0.136709 -0.84912 -0.510202 0.13671 -0.84912 0.510202 0.373493 -0.84912 0.373495 0.510202 -0.84912 0.136708 0.269797 0 -0.962917 0.269797 0 -0.962917 0.32265 0 -0.946518 0.269795 -0.00392398 -0.96291 0.269795 -0.00392417 -0.96291 0.216115 0 -0.976368 0.399724 0 0.916636 0.199986 0 0.979799 0.199986 0 0.979799 0.207998 -0.0570007 0.976467 0 -1 0 0 -1 0 0.119085 0 0.992884 0.119085 0 0.992884 -0.617634 0 0.786466 -0.617634 0 0.786466 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.817797 0 0.575507 -0.66139 -0.0657733 0.747153 -0.656414 0 0.754401 -0.239186 0 0.970974 -0.239186 0 0.970974 -0.656414 0 0.754401 -0.806908 0 0.590677 -0.806908 0 0.590677 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.94274 0 0.33353 -0.857359 -0.0560704 0.511656 -0.854307 0 0.519768 -0.205084 0 0.978744 -0.205084 0 0.978744 -0.580749 0 0.814083 -0.580749 0 0.814083 -0.854307 0 0.519768 0.519584 0 -0.854419 0.519584 0 -0.854419 0.566051 0 -0.82437 0.51958 -0.00392399 -0.854413 0.51958 -0.00392255 -0.854413 0.471543 0 -0.881843 0.0647039 0 0.997905 0.0647039 0 0.997905 0.135919 -0.156649 0.978257 0.073217 0 0.997316 0 -1 0 0 -1 0 0 -1 0 -0.153204 0 0.988195 -0.153204 0 0.988195 0.73083 -0.00392313 -0.682548 0.691968 0 -0.721928 0.74923 0 -0.66231 0.76745 0 -0.641109 0.73083 -0.00392123 -0.682548 0.701456 -0.280688 -0.655114 0.711896 0 -0.702285 -0.357996 0 0.933723 -0.997766 0 0.0668077 -0.95655 -0.0628581 0.284712 -0.955977 0 0.293441 -0.13475 0 0.99088 -0.349326 -0.0628542 0.934891 -0.357996 0 0.933723 -0.730835 0 0.682554 -0.730835 0 0.682554 -0.955977 0 0.293441 0 -1 0 0 -1 0 0 -1 0 -0.414149 0 0.910209 -0.414149 0 0.910209 -0.936349 0 0.35107 -0.936349 0 0.35107 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.900135 0 -0.435611 0.852191 -0.280688 -0.44157 0.874971 0 -0.484176 0.911983 0 -0.410227 0.887878 -0.00392532 -0.460061 0.887878 -0.00392228 -0.460062 0.861088 0 -0.508455 -0.596637 0 0.802512 -0.97879 0 -0.204866 -0.997893 -0.0628574 0.016082 -0.999696 0 0.0246425 -0.397067 0 0.91779 -0.588602 -0.0628621 0.805975 -0.596637 0 0.802512 -0.887885 0 0.460065 -0.887885 0 0.460065 -0.999696 0 0.0246425 0 -1 0 0 -1 0 0 -1 0 -0.644356 0 0.764726 -0.644356 0 0.764726 -0.996346 0 0.0854074 -0.996346 0 0.0854074 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.979077 -0.00392564 -0.203454 0.966325 0 -0.257326 0.984282 0 -0.176603 0.988838 0 -0.148995 0.979077 -0.00392316 -0.203454 0.939725 -0.280685 -0.195277 0.973154 0 -0.230156 -0.791027 0 0.611781 -0.887216 0 -0.461354 -0.965226 -0.0628612 -0.253745 -0.969273 0 -0.245988 -0.629972 0 0.776618 -0.784226 -0.062857 0.617283 -0.791027 0 0.611781 -0.979084 0 0.203457 -0.979084 0 0.203457 -0.969273 0 -0.245988 0 -1 0 0 -1 0 0 -1 0 -0.826777 0 0.562529 -0.826777 0 0.562529 -0.982443 0 -0.186565 -0.982443 0 -0.186565 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.826777 0 0.562529 0.826777 0 0.562529 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.979077 -0.00392313 -0.203454 -0.988838 0 -0.148995 -0.973154 0 -0.230156 -0.966325 0 -0.257326 -0.979077 -0.00392563 -0.203454 -0.939725 -0.280685 -0.195277 -0.984282 0 -0.176603 0.969273 0 -0.245988 0.629972 0 0.776618 0.784226 -0.062857 0.617283 0.791027 0 0.611781 0.887216 0 -0.461354 0.965226 -0.0628612 -0.253745 0.969273 0 -0.245988 0.979084 0 0.203457 0.979084 0 0.203457 0.791027 0 0.611781 0 -1 0 0 -1 0 0 -1 0 0.982443 0 -0.186565 0.982443 0 -0.186565 -0.874971 0 -0.484176 -0.852191 -0.280688 -0.44157 -0.900135 0 -0.435611 -0.861088 0 -0.508455 -0.887878 -0.00392229 -0.460061 -0.887878 -0.00392525 -0.460062 -0.911983 0 -0.410227 0.999696 0 0.0246425 0.397067 0 0.91779 0.588602 -0.0628621 0.805975 0.596637 0 0.802512 0.97879 0 -0.204866 0.997893 -0.0628574 0.016082 0.999696 0 0.0246425 0.887885 0 0.460065 0.887885 0 0.460065 0.596637 0 0.802512 0 -1 0 0 -1 0 0 -1 0 0.996346 0 0.0854074 0.996346 0 0.0854074 0.644356 0 0.764726 0.644356 0 0.764726 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.711896 0 -0.702285 -0.701456 -0.280688 -0.655114 -0.74923 0 -0.66231 -0.691968 0 -0.721928 -0.73083 -0.0039231 -0.682548 -0.73083 -0.0039212 -0.682548 -0.76745 0 -0.641109 0.955977 0 0.293443 0.13475 0 0.99088 0.349326 -0.0628542 0.934891 0.357996 0 0.933723 0.997766 0 0.0668077 0.95655 -0.0628585 0.284713 0.955977 0 0.293443 0.730836 0 0.682553 0.730836 0 0.682553 0.357996 0 0.933723 0 -1 0 0 -1 0 0 -1 0 0.936349 0 0.35107 0.936349 0 0.35107 0.414149 0 0.910209 0.414149 0 0.910209 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.51958 -0.00392419 -0.854413 -0.566051 0 -0.82437 -0.471543 0 -0.881843 -0.51958 -0.00392245 -0.854413 -0.519584 0 -0.854419 -0.519584 0 -0.854419 0.854307 0 0.519768 0.205084 0 0.978744 0.205084 0 0.978744 0.580749 0 0.814083 0.580749 0 0.814083 0.854307 0 0.519768 0.857359 -0.0560704 0.511656 0.94274 0 0.33353 0 -1 0 0 -1 0 0 -1 0 0.806908 0 0.590677 0.806908 0 0.590677 0.153204 0 0.988195 0.153204 0 0.988195 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.137618 0 0.990485 -0.0732045 -0.0184764 0.997146 -0.0647039 0 0.997905 -0.0647039 0 0.997905 -0.269795 -0.00392393 -0.96291 -0.32265 0 -0.946518 -0.216115 0 -0.976368 -0.269795 -0.0039242 -0.96291 -0.269797 0 -0.962917 -0.269797 0 -0.962917 0.656414 0 0.754401 0.239186 0 0.970974 0.239186 0 0.970974 0.656414 0 0.754401 0.66139 -0.0657733 0.747153 0.817797 0 0.575507 0 -1 0 0 -1 0 0.617634 0 0.786466 0.617634 0 0.786466 -0.119085 0 0.992884 -0.119085 0 0.992884 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.399724 0 0.916636 -0.207998 -0.0570007 0.976467 -0.199986 0 0.979799 -0.199986 0 0.979799 0 -1 0 -0.632206 0 0.7748 -0.496076 -0.0467565 0.867019 -0.489197 0 0.872174 -0.172368 0 0.985033 -0.172368 0 0.985033 -0.489197 0 0.872174 0 0 -1 0 0 -1 0.0553166 0 -0.998469 0 -0.00392395 -0.999992 0 -0.00392395 -0.999992 -0.0553166 0 -0.998469 0.489197 0 0.872174 0.172368 0 0.985033 0.172368 0 0.985033 0.489197 0 0.872174 0.496076 -0.0467565 0.867019 0.632206 0 0.7748 0 -1 0 0 -1 0 0 -1 0 0.382545 0 0.923937 0.382545 0 0.923937 -0.382545 0 0.923937 -0.382545 0 0.923937 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 + + + + + + + + + + + + + + +

1306 0 0 0 13 0 1302 1 1 1 13 1 1 2 2 2 13 2 13 3 2 3 1304 3 13 4 1304 4 1303 4 1301 5 1302 5 3 5 3 6 1302 6 13 6 3 7 13 7 1305 7 1305 8 13 8 0 8 1318 9 4 9 7 9 7 10 4 10 5 10 7 11 5 11 8 11 8 12 5 12 1310 12 8 13 1310 13 11 13 11 14 1310 14 1309 14 11 15 1309 15 13 15 13 16 1309 16 1307 16 13 17 1307 17 1306 17 6 18 1318 18 1319 18 1319 19 1318 19 7 19 1319 20 7 20 1320 20 1320 21 7 21 8 21 1320 22 8 22 1321 22 1321 23 8 23 1314 23 1315 24 1314 24 9 24 9 25 1314 25 8 25 9 26 8 26 1331 26 1331 27 8 27 1329 27 1329 28 8 28 10 28 10 29 8 29 11 29 10 30 11 30 12 30 1303 31 1300 31 13 31 13 32 1300 32 1299 32 13 33 1299 33 14 33 14 34 1294 34 13 34 13 35 1294 35 15 35 13 36 15 36 11 36 11 37 15 37 1326 37 11 38 1326 38 12 38 2434 39 273 39 274 39 2434 40 2417 40 273 40 273 41 2417 41 2415 41 273 42 2415 42 272 42 277 43 16 43 17 43 17 44 16 44 2497 44 17 45 2497 45 18 45 18 46 2497 46 19 46 18 47 19 47 279 47 279 48 19 48 2509 48 279 49 2509 49 276 49 28 50 2498 50 283 50 283 51 2498 51 2433 51 283 52 2433 52 277 52 277 53 2433 53 2430 53 277 54 2430 54 16 54 276 55 2509 55 20 55 20 56 2509 56 2508 56 20 57 2508 57 22 57 22 58 2508 58 21 58 22 59 21 59 274 59 274 60 21 60 2402 60 274 61 2402 61 2434 61 2415 62 23 62 272 62 272 63 23 63 24 63 272 64 24 64 269 64 269 65 24 65 2413 65 269 66 2413 66 267 66 267 67 2413 67 2412 67 267 68 2412 68 25 68 25 69 2412 69 2428 69 25 70 2428 70 265 70 265 71 2428 71 26 71 26 72 2428 72 2429 72 26 73 2429 73 282 73 282 74 2429 74 27 74 282 75 27 75 28 75 28 76 27 76 2500 76 28 77 2500 77 2498 77 32 78 9437 78 33 78 33 79 9437 79 29 79 33 80 29 80 9439 80 30 81 31 81 33 81 33 82 31 82 9434 82 33 83 9434 83 32 83 36 84 34 84 33 84 33 85 34 85 9432 85 33 86 9432 86 30 86 9439 87 35 87 33 87 33 88 35 88 9441 88 33 89 9441 89 36 89 37 90 38 90 42 90 42 91 38 91 39 91 42 92 39 92 9429 92 40 93 41 93 42 93 42 94 41 94 43 94 42 95 43 95 37 95 46 96 44 96 42 96 42 97 44 97 9431 97 42 98 9431 98 40 98 9429 99 45 99 42 99 42 100 45 100 9430 100 42 101 9430 101 46 101 9417 102 9419 102 49 102 49 103 9419 103 47 103 49 104 47 104 9421 104 48 105 9413 105 49 105 49 106 9413 106 9415 106 49 107 9415 107 9417 107 9425 108 50 108 49 108 49 109 50 109 9410 109 49 110 9410 110 48 110 9421 111 9423 111 49 111 49 112 9423 112 9424 112 49 113 9424 113 9425 113 53 114 9403 114 51 114 51 115 9403 115 9405 115 51 116 9405 116 9406 116 56 117 52 117 51 117 51 118 52 118 9401 118 51 119 9401 119 53 119 54 120 55 120 51 120 51 121 55 121 9409 121 51 122 9409 122 56 122 9406 123 57 123 51 123 51 124 57 124 58 124 51 125 58 125 54 125 59 126 9390 126 61 126 61 127 9390 127 9391 127 61 128 9391 128 9393 128 63 129 9384 129 61 129 61 130 9384 130 9386 130 61 131 9386 131 59 131 60 132 9398 132 61 132 61 133 9398 133 62 133 61 134 62 134 63 134 9393 135 9394 135 61 135 61 136 9394 136 64 136 61 137 64 137 60 137 65 138 66 138 68 138 68 139 66 139 9377 139 68 140 9377 140 67 140 71 141 9375 141 68 141 68 142 9375 142 9376 142 68 143 9376 143 65 143 9382 144 69 144 68 144 68 145 69 145 70 145 68 146 70 146 71 146 67 147 9381 147 68 147 68 148 9381 148 72 148 68 149 72 149 9382 149 75 150 73 150 74 150 74 151 73 151 9367 151 74 152 9367 152 77 152 9362 153 9363 153 74 153 74 154 9363 154 9364 154 74 155 9364 155 75 155 9371 156 9372 156 74 156 74 157 9372 157 76 157 74 158 76 158 9362 158 77 159 9368 159 74 159 74 160 9368 160 9370 160 74 161 9370 161 9371 161 9354 162 78 162 81 162 81 163 78 163 79 163 81 164 79 164 9356 164 9349 165 80 165 81 165 81 166 80 166 9351 166 81 167 9351 167 9354 167 85 168 82 168 81 168 81 169 82 169 83 169 81 170 83 170 9349 170 9356 171 9357 171 81 171 81 172 9357 172 84 172 81 173 84 173 85 173 90 174 86 174 93 174 93 175 86 175 87 175 93 176 87 176 9345 176 88 177 9341 177 93 177 93 178 9341 178 89 178 93 179 89 179 90 179 91 180 92 180 93 180 93 181 92 181 9348 181 93 182 9348 182 88 182 9345 183 9347 183 93 183 93 184 9347 184 94 184 93 185 94 185 91 185 9328 186 9330 186 97 186 97 187 9330 187 95 187 97 188 95 188 9333 188 9326 189 96 189 97 189 97 190 96 190 98 190 97 191 98 191 9328 191 100 192 9337 192 97 192 97 193 9337 193 99 193 97 194 99 194 9326 194 9333 195 9334 195 97 195 97 196 9334 196 9336 196 97 197 9336 197 100 197 9318 198 9319 198 102 198 102 199 9319 199 101 199 102 200 101 200 9320 200 9315 201 9316 201 102 201 102 202 9316 202 103 202 102 203 103 203 9318 203 9322 204 9324 204 102 204 102 205 9324 205 9325 205 102 206 9325 206 9315 206 9320 207 104 207 102 207 102 208 104 208 105 208 102 209 105 209 9322 209 110 210 9307 210 106 210 106 211 9307 211 107 211 106 212 107 212 9310 212 9303 213 108 213 106 213 106 214 108 214 109 214 106 215 109 215 110 215 9313 216 9314 216 106 216 106 217 9314 217 9302 217 106 218 9302 218 9303 218 9310 219 9311 219 106 219 106 220 9311 220 111 220 106 221 111 221 9313 221 114 222 116 222 965 222 114 223 3795 223 116 223 116 224 3795 224 1257 224 116 225 1257 225 117 225 4648 226 4646 226 118 226 112 227 113 227 3798 227 3798 228 113 228 114 228 3798 229 114 229 3801 229 3801 230 114 230 965 230 296 231 122 231 304 231 304 232 122 232 116 232 304 233 116 233 115 233 115 234 116 234 117 234 118 235 4644 235 4648 235 4648 236 4644 236 1684 236 4648 237 1684 237 119 237 119 238 1684 238 1683 238 119 239 1683 239 120 239 120 240 1683 240 968 240 120 241 968 241 122 241 122 242 968 242 121 242 122 243 121 243 116 243 124 244 123 244 125 244 124 245 125 245 286 245 123 246 126 246 125 246 125 247 126 247 3790 247 125 248 3790 248 134 248 134 249 127 249 3786 249 4653 250 128 250 129 250 129 251 128 251 130 251 129 252 130 252 4654 252 4654 253 130 253 4649 253 4654 254 4649 254 1673 254 1673 255 4649 255 9135 255 1673 256 9135 256 131 256 131 257 9135 257 969 257 969 258 9135 258 132 258 969 259 132 259 125 259 125 260 132 260 133 260 125 261 133 261 286 261 971 262 125 262 3784 262 3784 263 125 263 134 263 3784 264 134 264 3787 264 3787 265 134 265 3786 265 160 266 2837 266 158 266 2863 267 135 267 2892 267 2892 268 135 268 136 268 2892 269 136 269 137 269 137 270 136 270 138 270 137 271 138 271 2894 271 2894 272 138 272 151 272 2894 273 151 273 153 273 139 274 5548 274 2863 274 2863 275 5548 275 5557 275 2863 276 5557 276 135 276 143 277 5539 277 139 277 139 278 5539 278 140 278 139 279 140 279 5548 279 146 280 141 280 142 280 142 281 141 281 144 281 142 282 144 282 143 282 143 283 144 283 145 283 143 284 145 284 5539 284 142 285 2899 285 146 285 146 286 2899 286 2898 286 146 287 2898 287 147 287 147 288 2898 288 149 288 147 289 149 289 148 289 2837 290 160 290 149 290 149 291 160 291 150 291 149 292 150 292 148 292 151 293 152 293 153 293 153 294 152 294 5586 294 153 295 5586 295 2838 295 2838 296 5586 296 154 296 2838 297 154 297 2901 297 2901 298 154 298 5490 298 2901 299 5490 299 155 299 155 300 5490 300 156 300 155 301 156 301 2902 301 2902 302 156 302 157 302 2902 303 157 303 158 303 158 304 157 304 159 304 158 305 159 305 160 305 161 306 180 306 178 306 170 307 2888 307 2887 307 190 308 2891 308 162 308 162 309 2891 309 163 309 162 310 163 310 343 310 343 311 163 311 344 311 163 312 2889 312 344 312 344 313 2889 313 164 313 344 314 164 314 165 314 165 315 164 315 168 315 165 316 168 316 166 316 166 317 168 317 167 317 167 318 168 318 169 318 167 319 169 319 341 319 171 320 173 320 169 320 169 321 173 321 342 321 169 322 342 322 341 322 170 323 337 323 2888 323 2888 324 337 324 336 324 2888 325 336 325 171 325 171 326 336 326 172 326 171 327 172 327 173 327 182 328 334 328 174 328 174 329 334 329 333 329 174 330 333 330 175 330 175 331 333 331 176 331 175 332 176 332 2886 332 2886 333 176 333 177 333 2886 334 177 334 2887 334 2887 335 177 335 339 335 2887 336 339 336 170 336 178 337 180 337 179 337 179 338 180 338 181 338 179 339 181 339 182 339 182 340 181 340 183 340 182 341 183 341 334 341 161 342 178 342 184 342 184 343 178 343 185 343 184 344 185 344 329 344 329 345 185 345 330 345 330 346 185 346 186 346 330 347 186 347 331 347 2867 348 187 348 186 348 186 349 187 349 327 349 186 350 327 350 331 350 192 351 188 351 2867 351 2867 352 188 352 189 352 2867 353 189 353 187 353 190 354 324 354 2891 354 2891 355 324 355 191 355 2891 356 191 356 192 356 192 357 191 357 193 357 192 358 193 358 188 358 218 359 194 359 224 359 374 360 215 360 216 360 201 361 203 361 195 361 195 362 203 362 197 362 195 363 197 363 196 363 196 364 197 364 366 364 196 365 366 365 2457 365 387 366 198 366 199 366 199 367 198 367 200 367 199 368 200 368 201 368 201 369 200 369 202 369 201 370 202 370 203 370 387 371 199 371 204 371 204 372 199 372 205 372 204 373 205 373 206 373 206 374 205 374 2450 374 206 375 2450 375 385 375 385 376 2450 376 207 376 385 377 207 377 383 377 383 378 207 378 208 378 208 379 207 379 209 379 208 380 209 380 382 380 382 381 209 381 381 381 381 382 209 382 2455 382 381 383 2455 383 211 383 213 384 377 384 2456 384 377 385 376 385 2456 385 2456 386 376 386 379 386 2456 387 379 387 2455 387 2455 388 379 388 210 388 2455 389 210 389 211 389 216 390 215 390 2453 390 2456 391 212 391 213 391 213 392 212 392 2454 392 213 393 2454 393 214 393 214 394 2454 394 2453 394 214 395 2453 395 378 395 378 396 2453 396 215 396 374 397 216 397 373 397 373 398 216 398 220 398 373 399 220 399 217 399 218 400 219 400 194 400 194 401 219 401 372 401 194 402 372 402 220 402 220 403 372 403 371 403 220 404 371 404 217 404 366 405 221 405 2457 405 2457 406 221 406 222 406 2457 407 222 407 223 407 223 408 222 408 367 408 223 409 367 409 224 409 224 410 367 410 370 410 224 411 370 411 218 411 225 412 246 412 364 412 364 413 246 413 226 413 364 414 226 414 365 414 365 415 226 415 227 415 227 416 226 416 2444 416 227 417 2444 417 362 417 362 418 2444 418 2439 418 362 419 2439 419 361 419 361 420 2439 420 228 420 361 421 228 421 229 421 229 422 228 422 230 422 230 423 228 423 2442 423 230 424 2442 424 231 424 231 425 2442 425 232 425 232 426 2442 426 233 426 232 427 233 427 235 427 2441 428 234 428 233 428 233 429 234 429 358 429 233 430 358 430 235 430 236 431 2440 431 356 431 356 432 355 432 236 432 236 433 355 433 237 433 236 434 237 434 238 434 238 435 237 435 239 435 238 436 239 436 2441 436 2441 437 239 437 234 437 244 438 240 438 2440 438 2440 439 240 439 357 439 2440 440 357 440 356 440 250 441 351 441 248 441 248 442 351 442 241 442 248 443 241 443 243 443 243 444 241 444 242 444 243 445 242 445 244 445 244 446 242 446 245 446 244 447 245 447 240 447 225 448 348 448 246 448 246 449 348 449 347 449 246 450 347 450 2447 450 2447 451 347 451 2449 451 2449 452 347 452 349 452 2449 453 349 453 247 453 247 454 349 454 350 454 247 455 350 455 248 455 248 456 350 456 249 456 248 457 249 457 250 457 251 458 252 458 9449 458 251 459 9449 459 263 459 252 460 251 460 9448 460 9448 461 251 461 2062 461 9448 462 2062 462 9447 462 9447 463 2062 463 253 463 9447 464 253 464 254 464 254 465 253 465 2064 465 254 466 2064 466 9453 466 9453 467 2064 467 2066 467 9453 468 2066 468 257 468 261 469 255 469 2066 469 2066 470 255 470 256 470 2066 471 256 471 257 471 2068 472 9444 472 2070 472 2070 473 9444 473 9454 473 2070 474 9454 474 258 474 258 475 9454 475 9456 475 258 476 9456 476 259 476 259 477 9456 477 9457 477 259 478 9457 478 2061 478 2061 479 9457 479 260 479 2061 480 260 480 261 480 261 481 260 481 9460 481 261 482 9460 482 255 482 9449 483 262 483 263 483 263 484 262 484 264 484 263 485 264 485 2068 485 2068 486 264 486 9443 486 2068 487 9443 487 9444 487 25 488 265 488 266 488 266 489 265 489 280 489 25 490 266 490 267 490 267 491 266 491 268 491 267 492 268 492 269 492 269 493 268 493 270 493 269 494 270 494 272 494 272 495 270 495 271 495 272 496 271 496 273 496 273 497 271 497 2314 497 273 498 2314 498 274 498 275 499 276 499 2320 499 2320 500 276 500 20 500 2320 501 20 501 2314 501 2314 502 20 502 22 502 2314 503 22 503 274 503 281 504 283 504 2316 504 2316 505 283 505 277 505 2316 506 277 506 278 506 278 507 277 507 17 507 278 508 17 508 2318 508 2318 509 17 509 18 509 2318 510 18 510 275 510 275 511 18 511 279 511 275 512 279 512 276 512 265 513 26 513 280 513 280 514 26 514 282 514 280 515 282 515 281 515 281 516 282 516 28 516 281 517 28 517 283 517 5417 518 286 518 284 518 284 519 286 519 290 519 284 520 290 520 1114 520 1270 521 124 521 285 521 285 522 124 522 286 522 285 523 286 523 287 523 287 524 286 524 5417 524 1109 525 1113 525 9151 525 9151 526 1113 526 288 526 1111 527 1110 527 133 527 133 528 1110 528 289 528 133 529 289 529 286 529 286 530 289 530 1116 530 286 531 1116 531 290 531 9161 532 9168 532 1106 532 9151 533 291 533 1109 533 1109 534 291 534 9161 534 1109 535 9161 535 292 535 292 536 9161 536 1106 536 288 537 1111 537 9151 537 9151 538 1111 538 133 538 9151 539 133 539 293 539 293 540 133 540 132 540 293 541 132 541 9144 541 9208 542 122 542 297 542 297 543 122 543 296 543 296 544 1127 544 294 544 294 545 295 545 296 545 296 546 295 546 9206 546 296 547 9206 547 297 547 295 548 298 548 9206 548 9206 549 298 549 299 549 9206 550 299 550 9204 550 9204 551 299 551 302 551 1134 552 300 552 301 552 301 553 300 553 302 553 301 554 302 554 1133 554 1133 555 302 555 299 555 115 556 9134 556 304 556 304 557 9134 557 1261 557 1261 558 1262 558 304 558 304 559 1262 559 303 559 304 560 303 560 5397 560 1127 561 296 561 1128 561 1128 562 296 562 304 562 1128 563 304 563 1125 563 1125 564 304 564 5397 564 1125 565 5397 565 1126 565 404 566 305 566 406 566 406 567 305 567 306 567 406 568 306 568 408 568 408 569 306 569 5470 569 408 570 5470 570 307 570 307 571 5470 571 308 571 307 572 308 572 309 572 309 573 308 573 5469 573 309 574 5469 574 310 574 310 575 5469 575 5468 575 310 576 5468 576 413 576 413 577 5468 577 311 577 413 578 311 578 414 578 414 579 311 579 312 579 414 580 312 580 416 580 416 581 312 581 313 581 416 582 313 582 418 582 418 583 313 583 5467 583 418 584 5467 584 419 584 419 585 5467 585 5466 585 419 586 5466 586 421 586 421 587 5466 587 5465 587 421 588 5465 588 404 588 404 589 5465 589 305 589 322 590 5463 590 389 590 389 591 5463 591 314 591 389 592 314 592 390 592 390 593 314 593 5460 593 390 594 5460 594 391 594 391 595 5460 595 315 595 391 596 315 596 393 596 393 597 315 597 316 597 393 598 316 598 317 598 317 599 316 599 5458 599 317 600 5458 600 395 600 395 601 5458 601 5457 601 395 602 5457 602 397 602 397 603 5457 603 5455 603 397 604 5455 604 318 604 318 605 5455 605 319 605 318 606 319 606 400 606 400 607 319 607 320 607 400 608 320 608 402 608 402 609 320 609 5464 609 402 610 5464 610 388 610 388 611 5464 611 321 611 388 612 321 612 322 612 322 613 321 613 5463 613 183 614 181 614 332 614 324 615 190 615 323 615 323 616 190 616 162 616 323 617 162 617 345 617 324 618 323 618 191 618 191 619 323 619 326 619 191 620 326 620 193 620 325 621 187 621 189 621 325 622 189 622 326 622 326 623 189 623 188 623 326 624 188 624 193 624 2074 625 331 625 325 625 325 626 331 626 327 626 325 627 327 627 187 627 161 628 184 628 328 628 328 629 184 629 329 629 328 630 329 630 2074 630 2074 631 329 631 330 631 2074 632 330 632 331 632 332 633 181 633 328 633 328 634 181 634 180 634 328 635 180 635 161 635 335 636 333 636 332 636 332 637 333 637 334 637 332 638 334 638 183 638 338 639 177 639 335 639 335 640 177 640 176 640 335 641 176 641 333 641 336 642 337 642 2077 642 2077 643 337 643 170 643 2077 644 170 644 338 644 338 645 170 645 339 645 338 646 339 646 177 646 340 647 173 647 2077 647 2077 648 173 648 172 648 2077 649 172 649 336 649 166 650 167 650 346 650 346 651 167 651 341 651 346 652 341 652 340 652 340 653 341 653 342 653 340 654 342 654 173 654 162 655 343 655 345 655 345 656 343 656 344 656 345 657 344 657 346 657 346 658 344 658 165 658 346 659 165 659 166 659 230 660 231 660 359 660 234 661 239 661 2289 661 2291 662 347 662 348 662 347 663 2291 663 2290 663 347 664 2290 664 349 664 349 665 2290 665 2296 665 349 666 2296 666 350 666 2295 667 352 667 241 667 241 668 351 668 2295 668 2295 669 351 669 250 669 2295 670 250 670 2296 670 2296 671 250 671 249 671 2296 672 249 672 350 672 353 673 245 673 352 673 352 674 245 674 242 674 352 675 242 675 241 675 354 676 357 676 353 676 353 677 357 677 240 677 353 678 240 678 245 678 237 679 355 679 354 679 354 680 355 680 356 680 354 681 356 681 357 681 2289 682 239 682 354 682 354 683 239 683 237 683 234 684 2289 684 358 684 358 685 2289 685 2288 685 358 686 2288 686 235 686 359 687 231 687 2288 687 2288 688 231 688 232 688 2288 689 232 689 235 689 230 690 359 690 229 690 229 691 359 691 360 691 229 692 360 692 361 692 361 693 360 693 362 693 362 694 360 694 363 694 362 695 363 695 227 695 348 696 225 696 2291 696 2291 697 225 697 364 697 2291 698 364 698 363 698 363 699 364 699 365 699 363 700 365 700 227 700 379 701 376 701 2304 701 366 702 197 702 2305 702 2305 703 197 703 203 703 2305 704 203 704 2306 704 366 705 2305 705 221 705 221 706 2305 706 368 706 221 707 368 707 222 707 222 708 368 708 367 708 367 709 368 709 369 709 367 710 369 710 370 710 2302 711 219 711 369 711 369 712 219 712 218 712 369 713 218 713 370 713 373 714 217 714 2303 714 2303 715 217 715 371 715 2303 716 371 716 2302 716 2302 717 371 717 372 717 2302 718 372 718 219 718 373 719 2303 719 374 719 374 720 2303 720 375 720 374 721 375 721 215 721 2304 722 376 722 375 722 375 723 376 723 377 723 375 724 377 724 213 724 213 725 214 725 375 725 375 726 214 726 378 726 375 727 378 727 215 727 379 728 2304 728 210 728 210 729 2304 729 380 729 210 730 380 730 211 730 211 731 380 731 381 731 381 732 380 732 384 732 381 733 384 733 382 733 2300 734 383 734 384 734 384 735 383 735 208 735 384 736 208 736 382 736 387 737 204 737 386 737 386 738 204 738 206 738 386 739 206 739 2300 739 2300 740 206 740 385 740 2300 741 385 741 383 741 203 742 202 742 2306 742 2306 743 202 743 200 743 2306 744 200 744 386 744 386 745 200 745 198 745 386 746 198 746 387 746 403 747 388 747 2335 747 2335 748 388 748 322 748 2335 749 322 749 2331 749 2331 750 322 750 389 750 2331 751 389 751 2330 751 2330 752 389 752 390 752 2330 753 390 753 2329 753 2329 754 390 754 391 754 2329 755 391 755 392 755 392 756 391 756 393 756 392 757 393 757 2332 757 2332 758 393 758 317 758 2332 759 317 759 394 759 394 760 317 760 395 760 394 761 395 761 396 761 396 762 395 762 397 762 396 763 397 763 398 763 398 764 397 764 318 764 398 765 318 765 399 765 399 766 318 766 400 766 399 767 400 767 401 767 401 768 400 768 402 768 401 769 402 769 403 769 403 770 402 770 388 770 420 771 421 771 405 771 405 772 421 772 404 772 405 773 404 773 2120 773 2120 774 404 774 406 774 2120 775 406 775 407 775 407 776 406 776 408 776 407 777 408 777 409 777 409 778 408 778 307 778 409 779 307 779 410 779 410 780 307 780 309 780 410 781 309 781 2122 781 2122 782 309 782 310 782 2122 783 310 783 411 783 411 784 310 784 413 784 411 785 413 785 412 785 412 786 413 786 414 786 412 787 414 787 415 787 415 788 414 788 416 788 415 789 416 789 417 789 417 790 416 790 418 790 417 791 418 791 2123 791 2123 792 418 792 419 792 2123 793 419 793 420 793 420 794 419 794 421 794 422 795 460 795 423 795 5353 796 424 796 423 796 429 797 5827 797 425 797 425 798 5827 798 426 798 426 799 5827 799 5871 799 426 800 5871 800 461 800 430 801 5876 801 427 801 427 802 5876 802 428 802 427 803 428 803 425 803 425 804 428 804 5875 804 425 805 5875 805 429 805 430 806 427 806 431 806 431 807 427 807 434 807 431 808 434 808 432 808 436 809 433 809 434 809 434 810 433 810 5877 810 5877 811 5887 811 434 811 434 812 5887 812 5886 812 434 813 5886 813 432 813 440 814 435 814 439 814 439 815 435 815 5824 815 439 816 5824 816 436 816 436 817 5824 817 5823 817 436 818 5823 818 433 818 5783 819 5822 819 438 819 5822 820 437 820 438 820 438 821 437 821 5821 821 438 822 5821 822 439 822 439 823 5821 823 5861 823 439 824 5861 824 440 824 441 825 5786 825 442 825 442 826 5786 826 443 826 442 827 443 827 438 827 438 828 443 828 5790 828 438 829 5790 829 5783 829 444 830 5346 830 442 830 442 831 5346 831 445 831 442 832 445 832 441 832 445 833 5345 833 441 833 441 834 5345 834 446 834 441 835 446 835 5787 835 5787 836 446 836 447 836 5787 837 447 837 448 837 448 838 447 838 449 838 449 839 447 839 450 839 449 840 450 840 451 840 451 841 450 841 452 841 452 842 450 842 453 842 452 843 453 843 454 843 454 844 453 844 455 844 454 845 455 845 5797 845 5797 846 455 846 5798 846 5798 847 455 847 5351 847 5798 848 5351 848 456 848 456 849 5351 849 457 849 457 850 5351 850 5350 850 457 851 5350 851 458 851 458 852 5350 852 459 852 459 853 5350 853 5349 853 459 854 5349 854 460 854 460 855 5349 855 5356 855 460 856 5356 856 423 856 423 857 5356 857 5354 857 423 858 5354 858 5353 858 461 859 5911 859 426 859 426 860 5911 860 5820 860 426 861 5820 861 423 861 423 862 5820 862 462 862 423 863 462 863 422 863 490 864 5667 864 463 864 5607 865 464 865 482 865 5371 866 5459 866 482 866 465 867 493 867 466 867 466 868 493 868 467 868 466 869 467 869 468 869 468 870 467 870 5644 870 5612 871 5610 871 471 871 471 872 5610 872 469 872 471 873 469 873 467 873 467 874 469 874 470 874 467 875 470 875 5644 875 5456 876 5368 876 471 876 471 877 5368 877 5367 877 471 878 5367 878 5612 878 5367 879 472 879 5612 879 5612 880 472 880 5373 880 5612 881 5373 881 473 881 473 882 5373 882 474 882 473 883 474 883 475 883 475 884 474 884 476 884 476 885 474 885 478 885 476 886 478 886 5618 886 5618 887 478 887 477 887 477 888 478 888 5364 888 477 889 5364 889 479 889 479 890 5364 890 5361 890 479 891 5361 891 480 891 480 892 5361 892 5621 892 5621 893 5361 893 5360 893 5621 894 5360 894 5623 894 5623 895 5360 895 5624 895 5624 896 5360 896 5359 896 5624 897 5359 897 5603 897 5603 898 5359 898 5604 898 5604 899 5359 899 481 899 5604 900 481 900 464 900 464 901 481 901 5358 901 464 902 5358 902 482 902 482 903 5358 903 5357 903 482 904 5357 904 5371 904 463 905 5667 905 487 905 5667 906 483 906 487 906 487 907 483 907 484 907 487 908 484 908 5653 908 5653 909 485 909 487 909 487 910 485 910 486 910 487 911 486 911 482 911 482 912 486 912 5608 912 482 913 5608 913 5607 913 5664 914 488 914 5461 914 5461 915 488 915 489 915 5461 916 489 916 463 916 463 917 489 917 5665 917 463 918 5665 918 490 918 5664 919 5461 919 491 919 491 920 5461 920 5462 920 491 921 5462 921 5661 921 5661 922 5462 922 5663 922 5663 923 5462 923 492 923 5663 924 492 924 5660 924 465 925 5735 925 493 925 493 926 5735 926 5658 926 493 927 5658 927 492 927 492 928 5658 928 494 928 492 929 494 929 5660 929 2028 930 2141 930 2027 930 2027 931 2141 931 495 931 2027 932 495 932 2025 932 2025 933 495 933 496 933 2025 934 496 934 497 934 497 935 496 935 2140 935 497 936 2140 936 498 936 498 937 2140 937 499 937 498 938 499 938 500 938 500 939 499 939 502 939 500 940 502 940 501 940 501 941 502 941 2138 941 501 942 2138 942 2016 942 2016 943 2138 943 2137 943 2016 944 2137 944 503 944 503 945 2137 945 504 945 503 946 504 946 505 946 505 947 504 947 506 947 505 948 506 948 507 948 507 949 506 949 2143 949 507 950 2143 950 2030 950 2030 951 2143 951 2142 951 2030 952 2142 952 2028 952 2028 953 2142 953 2141 953 2014 954 523 954 508 954 508 955 523 955 509 955 508 956 509 956 510 956 510 957 509 957 511 957 510 958 511 958 2029 958 2029 959 511 959 512 959 2029 960 512 960 513 960 513 961 512 961 2157 961 513 962 2157 962 2015 962 2015 963 2157 963 514 963 2015 964 514 964 515 964 515 965 514 965 516 965 515 966 516 966 517 966 517 967 516 967 518 967 517 968 518 968 2021 968 2021 969 518 969 519 969 2021 970 519 970 2019 970 2019 971 519 971 520 971 2019 972 520 972 521 972 521 973 520 973 2155 973 521 974 2155 974 522 974 522 975 2155 975 2154 975 522 976 2154 976 2014 976 2014 977 2154 977 523 977 2042 978 2247 978 524 978 524 979 2247 979 2246 979 524 980 2246 980 2043 980 2043 981 2246 981 2241 981 2043 982 2241 982 2045 982 2045 983 2241 983 2240 983 2045 984 2240 984 525 984 525 985 2240 985 527 985 525 986 527 986 526 986 526 987 527 987 528 987 526 988 528 988 2033 988 2033 989 528 989 529 989 2033 990 529 990 531 990 531 991 529 991 530 991 531 992 530 992 532 992 532 993 530 993 2245 993 532 994 2245 994 2036 994 2036 995 2245 995 533 995 2036 996 533 996 2035 996 2035 997 533 997 534 997 2035 998 534 998 535 998 535 999 534 999 536 999 535 1000 536 1000 2042 1000 2042 1001 536 1001 2247 1001 2054 1002 546 1002 2052 1002 2052 1003 546 1003 2269 1003 2052 1004 2269 1004 2038 1004 2038 1005 2269 1005 537 1005 2038 1006 537 1006 538 1006 538 1007 537 1007 2266 1007 538 1008 2266 1008 2048 1008 2048 1009 2266 1009 2265 1009 2048 1010 2265 1010 2046 1010 2046 1011 2265 1011 2263 1011 2046 1012 2263 1012 539 1012 539 1013 2263 1013 540 1013 539 1014 540 1014 2044 1014 2044 1015 540 1015 541 1015 2044 1016 541 1016 542 1016 542 1017 541 1017 2262 1017 542 1018 2262 1018 2041 1018 2041 1019 2262 1019 2261 1019 2041 1020 2261 1020 543 1020 543 1021 2261 1021 2259 1021 543 1022 2259 1022 545 1022 545 1023 2259 1023 544 1023 545 1024 544 1024 2054 1024 2054 1025 544 1025 546 1025 547 1026 3940 1026 9428 1026 9428 1027 3940 1027 548 1027 9428 1028 548 1028 549 1028 549 1029 548 1029 3930 1029 549 1030 3930 1030 550 1030 550 1031 3930 1031 551 1031 550 1032 551 1032 552 1032 552 1033 551 1033 3931 1033 552 1034 3931 1034 553 1034 553 1035 3931 1035 3932 1035 553 1036 3932 1036 554 1036 554 1037 3932 1037 3933 1037 554 1038 3933 1038 555 1038 555 1039 3933 1039 557 1039 555 1040 557 1040 556 1040 556 1041 557 1041 3936 1041 556 1042 3936 1042 558 1042 558 1043 3936 1043 3937 1043 558 1044 3937 1044 560 1044 560 1045 3937 1045 559 1045 560 1046 559 1046 9427 1046 9427 1047 559 1047 561 1047 9427 1048 561 1048 547 1048 547 1049 561 1049 3940 1049 833 1050 562 1050 835 1050 835 1051 562 1051 563 1051 835 1052 563 1052 820 1052 820 1053 563 1053 3929 1053 820 1054 3929 1054 822 1054 822 1055 3929 1055 3928 1055 822 1056 3928 1056 564 1056 564 1057 3928 1057 3941 1057 564 1058 3941 1058 824 1058 824 1059 3941 1059 3939 1059 824 1060 3939 1060 565 1060 565 1061 3939 1061 566 1061 565 1062 566 1062 828 1062 828 1063 566 1063 3938 1063 828 1064 3938 1064 568 1064 568 1065 3938 1065 567 1065 568 1066 567 1066 569 1066 569 1067 567 1067 3935 1067 569 1068 3935 1068 570 1068 570 1069 3935 1069 571 1069 570 1070 571 1070 831 1070 831 1071 571 1071 3934 1071 831 1072 3934 1072 833 1072 833 1073 3934 1073 562 1073 9412 1074 572 1074 9414 1074 9414 1075 572 1075 3921 1075 9414 1076 3921 1076 9416 1076 9416 1077 3921 1077 573 1077 9416 1078 573 1078 9418 1078 9418 1079 573 1079 574 1079 9418 1080 574 1080 9420 1080 9420 1081 574 1081 3923 1081 9420 1082 3923 1082 575 1082 575 1083 3923 1083 576 1083 575 1084 576 1084 9422 1084 9422 1085 576 1085 578 1085 9422 1086 578 1086 577 1086 577 1087 578 1087 580 1087 577 1088 580 1088 579 1088 579 1089 580 1089 581 1089 579 1090 581 1090 582 1090 582 1091 581 1091 583 1091 582 1092 583 1092 9426 1092 9426 1093 583 1093 3926 1093 9426 1094 3926 1094 9411 1094 9411 1095 3926 1095 584 1095 9411 1096 584 1096 9412 1096 9412 1097 584 1097 572 1097 599 1098 585 1098 836 1098 836 1099 585 1099 586 1099 836 1100 586 1100 587 1100 587 1101 586 1101 3922 1101 587 1102 3922 1102 838 1102 838 1103 3922 1103 588 1103 838 1104 588 1104 840 1104 840 1105 588 1105 589 1105 840 1106 589 1106 590 1106 590 1107 589 1107 592 1107 590 1108 592 1108 591 1108 591 1109 592 1109 3927 1109 591 1110 3927 1110 593 1110 593 1111 3927 1111 594 1111 593 1112 594 1112 595 1112 595 1113 594 1113 3925 1113 595 1114 3925 1114 843 1114 843 1115 3925 1115 596 1115 843 1116 596 1116 844 1116 844 1117 596 1117 597 1117 844 1118 597 1118 598 1118 598 1119 597 1119 3924 1119 598 1120 3924 1120 599 1120 599 1121 3924 1121 585 1121 9399 1122 600 1122 9400 1122 9400 1123 600 1123 601 1123 9400 1124 601 1124 9402 1124 9402 1125 601 1125 602 1125 9402 1126 602 1126 604 1126 604 1127 602 1127 603 1127 604 1128 603 1128 9404 1128 9404 1129 603 1129 605 1129 9404 1130 605 1130 9407 1130 9407 1131 605 1131 3913 1131 9407 1132 3913 1132 606 1132 606 1133 3913 1133 3914 1133 606 1134 3914 1134 607 1134 607 1135 3914 1135 3916 1135 607 1136 3916 1136 608 1136 608 1137 3916 1137 3918 1137 608 1138 3918 1138 9408 1138 9408 1139 3918 1139 609 1139 9408 1140 609 1140 610 1140 610 1141 609 1141 611 1141 610 1142 611 1142 612 1142 612 1143 611 1143 3909 1143 612 1144 3909 1144 9399 1144 9399 1145 3909 1145 600 1145 855 1146 613 1146 614 1146 614 1147 613 1147 3912 1147 614 1148 3912 1148 849 1148 849 1149 3912 1149 3911 1149 849 1150 3911 1150 615 1150 615 1151 3911 1151 616 1151 615 1152 616 1152 617 1152 617 1153 616 1153 3910 1153 617 1154 3910 1154 850 1154 850 1155 3910 1155 3908 1155 850 1156 3908 1156 618 1156 618 1157 3908 1157 3907 1157 618 1158 3907 1158 852 1158 852 1159 3907 1159 3920 1159 852 1160 3920 1160 619 1160 619 1161 3920 1161 3919 1161 619 1162 3919 1162 620 1162 620 1163 3919 1163 3917 1163 620 1164 3917 1164 621 1164 621 1165 3917 1165 623 1165 621 1166 623 1166 622 1166 622 1167 623 1167 3915 1167 622 1168 3915 1168 855 1168 855 1169 3915 1169 613 1169 9385 1170 624 1170 9387 1170 9387 1171 624 1171 625 1171 9387 1172 625 1172 9388 1172 9388 1173 625 1173 627 1173 9388 1174 627 1174 626 1174 626 1175 627 1175 628 1175 626 1176 628 1176 9389 1176 9389 1177 628 1177 629 1177 9389 1178 629 1178 9392 1178 9392 1179 629 1179 630 1179 9392 1180 630 1180 9395 1180 9395 1181 630 1181 631 1181 9395 1182 631 1182 9396 1182 9396 1183 631 1183 3905 1183 9396 1184 3905 1184 9397 1184 9397 1185 3905 1185 632 1185 9397 1186 632 1186 633 1186 633 1187 632 1187 634 1187 633 1188 634 1188 635 1188 635 1189 634 1189 636 1189 635 1190 636 1190 637 1190 637 1191 636 1191 3901 1191 637 1192 3901 1192 9385 1192 9385 1193 3901 1193 624 1193 638 1194 639 1194 870 1194 870 1195 639 1195 640 1195 870 1196 640 1196 857 1196 857 1197 640 1197 642 1197 857 1198 642 1198 641 1198 641 1199 642 1199 644 1199 641 1200 644 1200 643 1200 643 1201 644 1201 645 1201 643 1202 645 1202 860 1202 860 1203 645 1203 3903 1203 860 1204 3903 1204 861 1204 861 1205 3903 1205 3902 1205 861 1206 3902 1206 646 1206 646 1207 3902 1207 3900 1207 646 1208 3900 1208 865 1208 865 1209 3900 1209 3906 1209 865 1210 3906 1210 647 1210 647 1211 3906 1211 648 1211 647 1212 648 1212 867 1212 867 1213 648 1213 3904 1213 867 1214 3904 1214 869 1214 869 1215 3904 1215 649 1215 869 1216 649 1216 638 1216 638 1217 649 1217 639 1217 9374 1218 650 1218 651 1218 651 1219 650 1219 652 1219 651 1220 652 1220 653 1220 653 1221 652 1221 654 1221 653 1222 654 1222 655 1222 655 1223 654 1223 656 1223 655 1224 656 1224 9378 1224 9378 1225 656 1225 657 1225 9378 1226 657 1226 9379 1226 9379 1227 657 1227 3896 1227 9379 1228 3896 1228 9380 1228 9380 1229 3896 1229 3898 1229 9380 1230 3898 1230 658 1230 658 1231 3898 1231 3892 1231 658 1232 3892 1232 659 1232 659 1233 3892 1233 660 1233 659 1234 660 1234 661 1234 661 1235 660 1235 3893 1235 661 1236 3893 1236 662 1236 662 1237 3893 1237 3894 1237 662 1238 3894 1238 9383 1238 9383 1239 3894 1239 663 1239 9383 1240 663 1240 9374 1240 9374 1241 663 1241 650 1241 680 1242 664 1242 871 1242 871 1243 664 1243 665 1243 871 1244 665 1244 666 1244 666 1245 665 1245 667 1245 666 1246 667 1246 872 1246 872 1247 667 1247 3895 1247 872 1248 3895 1248 668 1248 668 1249 3895 1249 669 1249 668 1250 669 1250 875 1250 875 1251 669 1251 670 1251 875 1252 670 1252 671 1252 671 1253 670 1253 672 1253 671 1254 672 1254 877 1254 877 1255 672 1255 673 1255 877 1256 673 1256 675 1256 675 1257 673 1257 674 1257 675 1258 674 1258 676 1258 676 1259 674 1259 677 1259 676 1260 677 1260 678 1260 678 1261 677 1261 3899 1261 678 1262 3899 1262 679 1262 679 1263 3899 1263 3897 1263 679 1264 3897 1264 680 1264 680 1265 3897 1265 664 1265 692 1266 3886 1266 681 1266 681 1267 3886 1267 682 1267 681 1268 682 1268 9365 1268 9365 1269 682 1269 3889 1269 9365 1270 3889 1270 683 1270 683 1271 3889 1271 3890 1271 683 1272 3890 1272 9366 1272 9366 1273 3890 1273 3891 1273 9366 1274 3891 1274 684 1274 684 1275 3891 1275 685 1275 684 1276 685 1276 686 1276 686 1277 685 1277 3880 1277 686 1278 3880 1278 9369 1278 9369 1279 3880 1279 687 1279 9369 1280 687 1280 688 1280 688 1281 687 1281 690 1281 688 1282 690 1282 689 1282 689 1283 690 1283 3882 1283 689 1284 3882 1284 9373 1284 9373 1285 3882 1285 691 1285 9373 1286 691 1286 9361 1286 9361 1287 691 1287 3884 1287 9361 1288 3884 1288 692 1288 692 1289 3884 1289 3886 1289 896 1290 693 1290 881 1290 881 1291 693 1291 694 1291 881 1292 694 1292 883 1292 883 1293 694 1293 695 1293 883 1294 695 1294 885 1294 885 1295 695 1295 3888 1295 885 1296 3888 1296 887 1296 887 1297 3888 1297 3887 1297 887 1298 3887 1298 888 1298 888 1299 3887 1299 3885 1299 888 1300 3885 1300 696 1300 696 1301 3885 1301 3883 1301 696 1302 3883 1302 697 1302 697 1303 3883 1303 698 1303 697 1304 698 1304 891 1304 891 1305 698 1305 3881 1305 891 1306 3881 1306 892 1306 892 1307 3881 1307 699 1307 892 1308 699 1308 701 1308 701 1309 699 1309 700 1309 701 1310 700 1310 894 1310 894 1311 700 1311 702 1311 894 1312 702 1312 896 1312 896 1313 702 1313 693 1313 9350 1314 712 1314 9352 1314 9352 1315 712 1315 703 1315 9352 1316 703 1316 9353 1316 9353 1317 703 1317 3878 1317 9353 1318 3878 1318 704 1318 704 1319 3878 1319 3879 1319 704 1320 3879 1320 9355 1320 9355 1321 3879 1321 3868 1321 9355 1322 3868 1322 705 1322 705 1323 3868 1323 3869 1323 705 1324 3869 1324 706 1324 706 1325 3869 1325 3871 1325 706 1326 3871 1326 9358 1326 9358 1327 3871 1327 3872 1327 9358 1328 3872 1328 707 1328 707 1329 3872 1329 3874 1329 707 1330 3874 1330 708 1330 708 1331 3874 1331 709 1331 708 1332 709 1332 9359 1332 9359 1333 709 1333 710 1333 9359 1334 710 1334 9360 1334 9360 1335 710 1335 711 1335 9360 1336 711 1336 9350 1336 9350 1337 711 1337 712 1337 907 1338 713 1338 715 1338 715 1339 713 1339 714 1339 715 1340 714 1340 897 1340 897 1341 714 1341 716 1341 897 1342 716 1342 717 1342 717 1343 716 1343 718 1343 717 1344 718 1344 719 1344 719 1345 718 1345 3877 1345 719 1346 3877 1346 721 1346 721 1347 3877 1347 720 1347 721 1348 720 1348 900 1348 900 1349 720 1349 3876 1349 900 1350 3876 1350 901 1350 901 1351 3876 1351 722 1351 901 1352 722 1352 903 1352 903 1353 722 1353 3875 1353 903 1354 3875 1354 904 1354 904 1355 3875 1355 3873 1355 904 1356 3873 1356 906 1356 906 1357 3873 1357 723 1357 906 1358 723 1358 724 1358 724 1359 723 1359 3870 1359 724 1360 3870 1360 907 1360 907 1361 3870 1361 713 1361 9340 1362 3855 1362 9342 1362 9342 1363 3855 1363 3857 1363 9342 1364 3857 1364 725 1364 725 1365 3857 1365 726 1365 725 1366 726 1366 9343 1366 9343 1367 726 1367 727 1367 9343 1368 727 1368 728 1368 728 1369 727 1369 3860 1369 728 1370 3860 1370 9344 1370 9344 1371 3860 1371 3862 1371 9344 1372 3862 1372 729 1372 729 1373 3862 1373 730 1373 729 1374 730 1374 9346 1374 9346 1375 730 1375 731 1375 9346 1376 731 1376 732 1376 732 1377 731 1377 3864 1377 732 1378 3864 1378 733 1378 733 1379 3864 1379 3865 1379 733 1380 3865 1380 734 1380 734 1381 3865 1381 735 1381 734 1382 735 1382 9339 1382 9339 1383 735 1383 3854 1383 9339 1384 3854 1384 9340 1384 9340 1385 3854 1385 3855 1385 918 1386 736 1386 909 1386 909 1387 736 1387 3861 1387 909 1388 3861 1388 737 1388 737 1389 3861 1389 3859 1389 737 1390 3859 1390 738 1390 738 1391 3859 1391 3858 1391 738 1392 3858 1392 910 1392 910 1393 3858 1393 739 1393 910 1394 739 1394 740 1394 740 1395 739 1395 3856 1395 740 1396 3856 1396 741 1396 741 1397 3856 1397 3867 1397 741 1398 3867 1398 912 1398 912 1399 3867 1399 3866 1399 912 1400 3866 1400 742 1400 742 1401 3866 1401 743 1401 742 1402 743 1402 915 1402 915 1403 743 1403 745 1403 915 1404 745 1404 744 1404 744 1405 745 1405 3863 1405 744 1406 3863 1406 917 1406 917 1407 3863 1407 746 1407 917 1408 746 1408 918 1408 918 1409 746 1409 736 1409 747 1410 749 1410 748 1410 748 1411 749 1411 3847 1411 748 1412 3847 1412 9329 1412 9329 1413 3847 1413 750 1413 9329 1414 750 1414 751 1414 751 1415 750 1415 752 1415 751 1416 752 1416 9331 1416 9331 1417 752 1417 3849 1417 9331 1418 3849 1418 9332 1418 9332 1419 3849 1419 753 1419 9332 1420 753 1420 754 1420 754 1421 753 1421 3851 1421 754 1422 3851 1422 9335 1422 9335 1423 3851 1423 756 1423 9335 1424 756 1424 755 1424 755 1425 756 1425 757 1425 755 1426 757 1426 758 1426 758 1427 757 1427 759 1427 758 1428 759 1428 9338 1428 9338 1429 759 1429 760 1429 9338 1430 760 1430 9327 1430 9327 1431 760 1431 3845 1431 9327 1432 3845 1432 747 1432 747 1433 3845 1433 749 1433 933 1434 3850 1434 934 1434 934 1435 3850 1435 3848 1435 934 1436 3848 1436 921 1436 921 1437 3848 1437 762 1437 921 1438 762 1438 761 1438 761 1439 762 1439 763 1439 761 1440 763 1440 923 1440 923 1441 763 1441 3846 1441 923 1442 3846 1442 925 1442 925 1443 3846 1443 764 1443 925 1444 764 1444 926 1444 926 1445 764 1445 765 1445 926 1446 765 1446 927 1446 927 1447 765 1447 3844 1447 927 1448 3844 1448 928 1448 928 1449 3844 1449 3853 1449 928 1450 3853 1450 766 1450 766 1451 3853 1451 767 1451 766 1452 767 1452 768 1452 768 1453 767 1453 769 1453 768 1454 769 1454 930 1454 930 1455 769 1455 3852 1455 930 1456 3852 1456 933 1456 933 1457 3852 1457 3850 1457 783 1458 770 1458 9317 1458 9317 1459 770 1459 3841 1459 9317 1460 3841 1460 771 1460 771 1461 3841 1461 3843 1461 771 1462 3843 1462 772 1462 772 1463 3843 1463 3832 1463 772 1464 3832 1464 773 1464 773 1465 3832 1465 774 1465 773 1466 774 1466 9321 1466 9321 1467 774 1467 775 1467 9321 1468 775 1468 776 1468 776 1469 775 1469 778 1469 776 1470 778 1470 777 1470 777 1471 778 1471 3834 1471 777 1472 3834 1472 779 1472 779 1473 3834 1473 3835 1473 779 1474 3835 1474 9323 1474 9323 1475 3835 1475 780 1475 9323 1476 780 1476 781 1476 781 1477 780 1477 3837 1477 781 1478 3837 1478 782 1478 782 1479 3837 1479 3838 1479 782 1480 3838 1480 783 1480 783 1481 3838 1481 770 1481 784 1482 785 1482 786 1482 786 1483 785 1483 3833 1483 786 1484 3833 1484 788 1484 788 1485 3833 1485 787 1485 788 1486 787 1486 938 1486 938 1487 787 1487 3842 1487 938 1488 3842 1488 789 1488 789 1489 3842 1489 3840 1489 789 1490 3840 1490 790 1490 790 1491 3840 1491 3839 1491 790 1492 3839 1492 941 1492 941 1493 3839 1493 791 1493 941 1494 791 1494 792 1494 792 1495 791 1495 793 1495 792 1496 793 1496 794 1496 794 1497 793 1497 795 1497 794 1498 795 1498 944 1498 944 1499 795 1499 3836 1499 944 1500 3836 1500 946 1500 946 1501 3836 1501 796 1501 946 1502 796 1502 947 1502 947 1503 796 1503 797 1503 947 1504 797 1504 784 1504 784 1505 797 1505 785 1505 806 1506 807 1506 9305 1506 9305 1507 807 1507 798 1507 9305 1508 798 1508 9306 1508 9306 1509 798 1509 3825 1509 9306 1510 3825 1510 799 1510 799 1511 3825 1511 3827 1511 799 1512 3827 1512 9308 1512 9308 1513 3827 1513 3829 1513 9308 1514 3829 1514 9309 1514 9309 1515 3829 1515 800 1515 9309 1516 800 1516 801 1516 801 1517 800 1517 3816 1517 801 1518 3816 1518 9312 1518 9312 1519 3816 1519 802 1519 9312 1520 802 1520 803 1520 803 1521 802 1521 3818 1521 803 1522 3818 1522 804 1522 804 1523 3818 1523 3819 1523 804 1524 3819 1524 805 1524 805 1525 3819 1525 3820 1525 805 1526 3820 1526 9304 1526 9304 1527 3820 1527 3823 1527 9304 1528 3823 1528 806 1528 806 1529 3823 1529 807 1529 819 1530 3831 1530 950 1530 950 1531 3831 1531 3830 1531 950 1532 3830 1532 808 1532 808 1533 3830 1533 3828 1533 808 1534 3828 1534 809 1534 809 1535 3828 1535 3826 1535 809 1536 3826 1536 952 1536 952 1537 3826 1537 3824 1537 952 1538 3824 1538 810 1538 810 1539 3824 1539 812 1539 810 1540 812 1540 811 1540 811 1541 812 1541 3822 1541 811 1542 3822 1542 955 1542 955 1543 3822 1543 3821 1543 955 1544 3821 1544 814 1544 814 1545 3821 1545 813 1545 814 1546 813 1546 815 1546 815 1547 813 1547 3817 1547 815 1548 3817 1548 957 1548 957 1549 3817 1549 816 1549 957 1550 816 1550 818 1550 818 1551 816 1551 817 1551 818 1552 817 1552 819 1552 819 1553 817 1553 3831 1553 834 1554 835 1554 1367 1554 1367 1555 835 1555 820 1555 1367 1556 820 1556 821 1556 821 1557 820 1557 822 1557 821 1558 822 1558 1370 1558 1370 1559 822 1559 564 1559 1370 1560 564 1560 823 1560 823 1561 564 1561 824 1561 823 1562 824 1562 825 1562 825 1563 824 1563 565 1563 825 1564 565 1564 826 1564 826 1565 565 1565 828 1565 826 1566 828 1566 827 1566 827 1567 828 1567 568 1567 827 1568 568 1568 829 1568 829 1569 568 1569 569 1569 829 1570 569 1570 1368 1570 1368 1571 569 1571 570 1571 1368 1572 570 1572 830 1572 830 1573 570 1573 831 1573 830 1574 831 1574 832 1574 832 1575 831 1575 833 1575 832 1576 833 1576 834 1576 834 1577 833 1577 835 1577 847 1578 836 1578 837 1578 837 1579 836 1579 587 1579 837 1580 587 1580 1447 1580 1447 1581 587 1581 838 1581 1447 1582 838 1582 1448 1582 1448 1583 838 1583 840 1583 1448 1584 840 1584 839 1584 839 1585 840 1585 590 1585 839 1586 590 1586 1450 1586 1450 1587 590 1587 591 1587 1450 1588 591 1588 841 1588 841 1589 591 1589 593 1589 841 1590 593 1590 842 1590 842 1591 593 1591 595 1591 842 1592 595 1592 1455 1592 1455 1593 595 1593 843 1593 1455 1594 843 1594 1456 1594 1456 1595 843 1595 844 1595 1456 1596 844 1596 845 1596 845 1597 844 1597 598 1597 845 1598 598 1598 846 1598 846 1599 598 1599 599 1599 846 1600 599 1600 847 1600 847 1601 599 1601 836 1601 1357 1602 614 1602 848 1602 848 1603 614 1603 849 1603 848 1604 849 1604 1424 1604 1424 1605 849 1605 615 1605 1424 1606 615 1606 1364 1606 1364 1607 615 1607 617 1607 1364 1608 617 1608 1358 1608 1358 1609 617 1609 850 1609 1358 1610 850 1610 851 1610 851 1611 850 1611 618 1611 851 1612 618 1612 1359 1612 1359 1613 618 1613 852 1613 1359 1614 852 1614 1360 1614 1360 1615 852 1615 619 1615 1360 1616 619 1616 1361 1616 1361 1617 619 1617 620 1617 1361 1618 620 1618 853 1618 853 1619 620 1619 621 1619 853 1620 621 1620 854 1620 854 1621 621 1621 622 1621 854 1622 622 1622 1356 1622 1356 1623 622 1623 855 1623 1356 1624 855 1624 1357 1624 1357 1625 855 1625 614 1625 1429 1626 870 1626 856 1626 856 1627 870 1627 857 1627 856 1628 857 1628 1430 1628 1430 1629 857 1629 641 1629 1430 1630 641 1630 858 1630 858 1631 641 1631 643 1631 858 1632 643 1632 859 1632 859 1633 643 1633 860 1633 859 1634 860 1634 862 1634 862 1635 860 1635 861 1635 862 1636 861 1636 863 1636 863 1637 861 1637 646 1637 863 1638 646 1638 864 1638 864 1639 646 1639 865 1639 864 1640 865 1640 866 1640 866 1641 865 1641 647 1641 866 1642 647 1642 1435 1642 1435 1643 647 1643 867 1643 1435 1644 867 1644 1426 1644 1426 1645 867 1645 869 1645 1426 1646 869 1646 868 1646 868 1647 869 1647 638 1647 868 1648 638 1648 1429 1648 1429 1649 638 1649 870 1649 880 1650 871 1650 1415 1650 1415 1651 871 1651 666 1651 1415 1652 666 1652 1416 1652 1416 1653 666 1653 872 1653 1416 1654 872 1654 873 1654 873 1655 872 1655 668 1655 873 1656 668 1656 874 1656 874 1657 668 1657 875 1657 874 1658 875 1658 1418 1658 1418 1659 875 1659 671 1659 1418 1660 671 1660 876 1660 876 1661 671 1661 877 1661 876 1662 877 1662 878 1662 878 1663 877 1663 675 1663 878 1664 675 1664 1411 1664 1411 1665 675 1665 676 1665 1411 1666 676 1666 1412 1666 1412 1667 676 1667 678 1667 1412 1668 678 1668 879 1668 879 1669 678 1669 679 1669 879 1670 679 1670 1414 1670 1414 1671 679 1671 680 1671 1414 1672 680 1672 880 1672 880 1673 680 1673 871 1673 1355 1674 881 1674 882 1674 882 1675 881 1675 883 1675 882 1676 883 1676 884 1676 884 1677 883 1677 885 1677 884 1678 885 1678 886 1678 886 1679 885 1679 887 1679 886 1680 887 1680 1349 1680 1349 1681 887 1681 888 1681 1349 1682 888 1682 1350 1682 1350 1683 888 1683 696 1683 1350 1684 696 1684 889 1684 889 1685 696 1685 697 1685 889 1686 697 1686 890 1686 890 1687 697 1687 891 1687 890 1688 891 1688 1351 1688 1351 1689 891 1689 892 1689 1351 1690 892 1690 893 1690 893 1691 892 1691 701 1691 893 1692 701 1692 1353 1692 1353 1693 701 1693 894 1693 1353 1694 894 1694 895 1694 895 1695 894 1695 896 1695 895 1696 896 1696 1355 1696 1355 1697 896 1697 881 1697 1402 1698 715 1698 1405 1698 1405 1699 715 1699 897 1699 1405 1700 897 1700 1404 1700 1404 1701 897 1701 717 1701 1404 1702 717 1702 898 1702 898 1703 717 1703 719 1703 898 1704 719 1704 1403 1704 1403 1705 719 1705 721 1705 1403 1706 721 1706 899 1706 899 1707 721 1707 900 1707 899 1708 900 1708 1406 1708 1406 1709 900 1709 901 1709 1406 1710 901 1710 1407 1710 1407 1711 901 1711 903 1711 1407 1712 903 1712 902 1712 902 1713 903 1713 904 1713 902 1714 904 1714 905 1714 905 1715 904 1715 906 1715 905 1716 906 1716 1408 1716 1408 1717 906 1717 724 1717 1408 1718 724 1718 1410 1718 1410 1719 724 1719 907 1719 1410 1720 907 1720 1402 1720 1402 1721 907 1721 715 1721 919 1722 909 1722 908 1722 908 1723 909 1723 737 1723 908 1724 737 1724 1432 1724 1432 1725 737 1725 738 1725 1432 1726 738 1726 1438 1726 1438 1727 738 1727 910 1727 1438 1728 910 1728 1439 1728 1439 1729 910 1729 740 1729 1439 1730 740 1730 911 1730 911 1731 740 1731 741 1731 911 1732 741 1732 1441 1732 1441 1733 741 1733 912 1733 1441 1734 912 1734 913 1734 913 1735 912 1735 742 1735 913 1736 742 1736 914 1736 914 1737 742 1737 915 1737 914 1738 915 1738 916 1738 916 1739 915 1739 744 1739 916 1740 744 1740 1436 1740 1436 1741 744 1741 917 1741 1436 1742 917 1742 1336 1742 1336 1743 917 1743 918 1743 1336 1744 918 1744 919 1744 919 1745 918 1745 909 1745 1345 1746 934 1746 1346 1746 1346 1747 934 1747 921 1747 1346 1748 921 1748 920 1748 920 1749 921 1749 761 1749 920 1750 761 1750 922 1750 922 1751 761 1751 923 1751 922 1752 923 1752 1347 1752 1347 1753 923 1753 925 1753 1347 1754 925 1754 924 1754 924 1755 925 1755 926 1755 924 1756 926 1756 1389 1756 1389 1757 926 1757 927 1757 1389 1758 927 1758 929 1758 929 1759 927 1759 928 1759 929 1760 928 1760 1390 1760 1390 1761 928 1761 766 1761 1390 1762 766 1762 1393 1762 1393 1763 766 1763 768 1763 1393 1764 768 1764 931 1764 931 1765 768 1765 930 1765 931 1766 930 1766 932 1766 932 1767 930 1767 933 1767 932 1768 933 1768 1345 1768 1345 1769 933 1769 934 1769 1454 1770 786 1770 935 1770 935 1771 786 1771 788 1771 935 1772 788 1772 936 1772 936 1773 788 1773 938 1773 936 1774 938 1774 937 1774 937 1775 938 1775 789 1775 937 1776 789 1776 939 1776 939 1777 789 1777 790 1777 939 1778 790 1778 1458 1778 1458 1779 790 1779 941 1779 1458 1780 941 1780 940 1780 940 1781 941 1781 792 1781 940 1782 792 1782 942 1782 942 1783 792 1783 794 1783 942 1784 794 1784 943 1784 943 1785 794 1785 944 1785 943 1786 944 1786 945 1786 945 1787 944 1787 946 1787 945 1788 946 1788 1452 1788 1452 1789 946 1789 947 1789 1452 1790 947 1790 948 1790 948 1791 947 1791 784 1791 948 1792 784 1792 1454 1792 1454 1793 784 1793 786 1793 949 1794 950 1794 951 1794 951 1795 950 1795 808 1795 951 1796 808 1796 1385 1796 1385 1797 808 1797 809 1797 1385 1798 809 1798 953 1798 953 1799 809 1799 952 1799 953 1800 952 1800 954 1800 954 1801 952 1801 810 1801 954 1802 810 1802 1379 1802 1379 1803 810 1803 811 1803 1379 1804 811 1804 1380 1804 1380 1805 811 1805 955 1805 1380 1806 955 1806 1381 1806 1381 1807 955 1807 814 1807 1381 1808 814 1808 956 1808 956 1809 814 1809 815 1809 956 1810 815 1810 1382 1810 1382 1811 815 1811 957 1811 1382 1812 957 1812 1383 1812 1383 1813 957 1813 818 1813 1383 1814 818 1814 958 1814 958 1815 818 1815 819 1815 958 1816 819 1816 949 1816 949 1817 819 1817 950 1817 6100 1818 3813 1818 959 1818 959 1819 3813 1819 960 1819 959 1820 960 1820 6107 1820 6107 1821 960 1821 961 1821 961 1822 960 1822 962 1822 961 1823 962 1823 6105 1823 6105 1824 962 1824 963 1824 963 1825 962 1825 964 1825 963 1826 964 1826 6102 1826 6102 1827 964 1827 6101 1827 6101 1828 964 1828 1486 1828 6101 1829 1486 1829 1676 1829 3802 1830 3801 1830 5974 1830 5974 1831 3801 1831 965 1831 5974 1832 965 1832 967 1832 5968 1833 5972 1833 116 1833 116 1834 5972 1834 966 1834 116 1835 966 1835 965 1835 965 1836 966 1836 5973 1836 965 1837 5973 1837 967 1837 5968 1838 116 1838 5966 1838 5966 1839 116 1839 121 1839 5966 1840 121 1840 5964 1840 5964 1841 121 1841 5962 1841 5962 1842 121 1842 968 1842 5962 1843 968 1843 1682 1843 1672 1844 131 1844 5987 1844 5987 1845 131 1845 969 1845 5987 1846 969 1846 5988 1846 5988 1847 969 1847 5989 1847 5989 1848 969 1848 125 1848 5989 1849 125 1849 5991 1849 5991 1850 125 1850 970 1850 970 1851 125 1851 971 1851 970 1852 971 1852 5992 1852 3784 1853 5996 1853 971 1853 971 1854 5996 1854 5994 1854 971 1855 5994 1855 5992 1855 6165 1856 1674 1856 972 1856 972 1857 1674 1857 973 1857 1494 1858 6159 1858 973 1858 973 1859 6159 1859 974 1859 974 1860 6162 1860 973 1860 973 1861 6162 1861 975 1861 973 1862 975 1862 972 1862 976 1863 1531 1863 3769 1863 3769 1864 6156 1864 976 1864 976 1865 6156 1865 6157 1865 976 1866 6157 1866 1494 1866 1494 1867 6157 1867 977 1867 1494 1868 977 1868 6159 1868 988 1869 3714 1869 978 1869 978 1870 3714 1870 3715 1870 978 1871 3715 1871 9435 1871 9435 1872 3715 1872 979 1872 9435 1873 979 1873 9436 1873 9436 1874 979 1874 3717 1874 9436 1875 3717 1875 9438 1875 9438 1876 3717 1876 980 1876 9438 1877 980 1877 9440 1877 9440 1878 980 1878 3719 1878 9440 1879 3719 1879 981 1879 981 1880 3719 1880 982 1880 981 1881 982 1881 9442 1881 9442 1882 982 1882 3709 1882 9442 1883 3709 1883 983 1883 983 1884 3709 1884 3710 1884 983 1885 3710 1885 984 1885 984 1886 3710 1886 985 1886 984 1887 985 1887 986 1887 986 1888 985 1888 987 1888 986 1889 987 1889 9433 1889 9433 1890 987 1890 3713 1890 9433 1891 3713 1891 988 1891 988 1892 3713 1892 3714 1892 1011 1893 1000 1893 989 1893 989 1894 1000 1894 3718 1894 989 1895 3718 1895 1002 1895 1002 1896 3718 1896 3716 1896 1002 1897 3716 1897 990 1897 990 1898 3716 1898 991 1898 990 1899 991 1899 1003 1899 1003 1900 991 1900 993 1900 1003 1901 993 1901 992 1901 992 1902 993 1902 994 1902 992 1903 994 1903 995 1903 995 1904 994 1904 996 1904 995 1905 996 1905 1005 1905 1005 1906 996 1906 3712 1906 1005 1907 3712 1907 1008 1907 1008 1908 3712 1908 997 1908 1008 1909 997 1909 1009 1909 1009 1910 997 1910 3711 1910 1009 1911 3711 1911 998 1911 998 1912 3711 1912 999 1912 998 1913 999 1913 1010 1913 1010 1914 999 1914 3720 1914 1010 1915 3720 1915 1011 1915 1011 1916 3720 1916 1000 1916 1001 1917 989 1917 1341 1917 1341 1918 989 1918 1002 1918 1341 1919 1002 1919 1342 1919 1342 1920 1002 1920 990 1920 1342 1921 990 1921 1343 1921 1343 1922 990 1922 1003 1922 1343 1923 1003 1923 1374 1923 1374 1924 1003 1924 992 1924 1374 1925 992 1925 1373 1925 1373 1926 992 1926 995 1926 1373 1927 995 1927 1004 1927 1004 1928 995 1928 1005 1928 1004 1929 1005 1929 1006 1929 1006 1930 1005 1930 1008 1930 1006 1931 1008 1931 1007 1931 1007 1932 1008 1932 1009 1932 1007 1933 1009 1933 1377 1933 1377 1934 1009 1934 998 1934 1377 1935 998 1935 1340 1935 1340 1936 998 1936 1010 1936 1340 1937 1010 1937 1339 1937 1339 1938 1010 1938 1011 1938 1339 1939 1011 1939 1001 1939 1001 1940 1011 1940 989 1940 6056 1941 1012 1941 6053 1941 6053 1942 1012 1942 3699 1942 3696 1943 1013 1943 1014 1943 1014 1944 1013 1944 1484 1944 1029 1945 3739 1945 1033 1945 5363 1946 1543 1946 5362 1946 5362 1947 1543 1947 6667 1947 6088 1948 1016 1948 1015 1948 1015 1949 1016 1949 6667 1949 1015 1950 6667 1950 6089 1950 6089 1951 6667 1951 1543 1951 6089 1952 1543 1952 3721 1952 1022 1953 1017 1953 1023 1953 1023 1954 1017 1954 6665 1954 1023 1955 6665 1955 6088 1955 6088 1956 6665 1956 6666 1956 6088 1957 6666 1957 1016 1957 1018 1958 1019 1958 1020 1958 1020 1959 1019 1959 6627 1959 1020 1960 6627 1960 1021 1960 1021 1961 6627 1961 1022 1961 1021 1962 1022 1962 6062 1962 6062 1963 1022 1963 1023 1963 1024 1964 6622 1964 1019 1964 1019 1965 6622 1965 6626 1965 1019 1966 6626 1966 6627 1966 3690 1967 1026 1967 1024 1967 1024 1968 1026 1968 6621 1968 1024 1969 6621 1969 6622 1969 3690 1970 1025 1970 1026 1970 1026 1971 1025 1971 6032 1971 1026 1972 6032 1972 6619 1972 6619 1973 6032 1973 1027 1973 6619 1974 1027 1974 1028 1974 1028 1975 1027 1975 4750 1975 1028 1976 4750 1976 6613 1976 6613 1977 4750 1977 6611 1977 1029 1978 1030 1978 1031 1978 1031 1979 1030 1979 6611 1979 1031 1980 6611 1980 1032 1980 1032 1981 6611 1981 4750 1981 1029 1982 1033 1982 1030 1982 1030 1983 1033 1983 1509 1983 1030 1984 1509 1984 6610 1984 1052 1985 1050 1985 3004 1985 3004 1986 1034 1986 1052 1986 1052 1987 1034 1987 1035 1987 1052 1988 1035 1988 1055 1988 1055 1989 1035 1989 1398 1989 1055 1990 1398 1990 1036 1990 1036 1991 1398 1991 1399 1991 1036 1992 1399 1992 1037 1992 1038 1993 2983 1993 1039 1993 1039 1994 1049 1994 1038 1994 1038 1995 1049 1995 1046 1995 1038 1996 1046 1996 1041 1996 1041 1997 1046 1997 1040 1997 1041 1998 1040 1998 1042 1998 1042 1999 1040 1999 2988 1999 1042 2000 2988 2000 1043 2000 2682 2001 2988 2001 3547 2001 3547 2002 2988 2002 1040 2002 3530 2003 1044 2003 1046 2003 1046 2004 1044 2004 1045 2004 1046 2005 1045 2005 1040 2005 1040 2006 1045 2006 3549 2006 1040 2007 3549 2007 3547 2007 1049 2008 3554 2008 1046 2008 1046 2009 3554 2009 1047 2009 1046 2010 1047 2010 3530 2010 2681 2011 3560 2011 1039 2011 1039 2012 3560 2012 1048 2012 1039 2013 1048 2013 1049 2013 1049 2014 1048 2014 3555 2014 1049 2015 3555 2015 3554 2015 3459 2016 3447 2016 1050 2016 3459 2017 1050 2017 1051 2017 1051 2018 1050 2018 1052 2018 1051 2019 1052 2019 1056 2019 1053 2020 1054 2020 1055 2020 1055 2021 1054 2021 3471 2021 1055 2022 3471 2022 1052 2022 1052 2023 3471 2023 3472 2023 1052 2024 3472 2024 1056 2024 1053 2025 1055 2025 3452 2025 3452 2026 1055 2026 1036 2026 3452 2027 1036 2027 3451 2027 3451 2028 1036 2028 1037 2028 3451 2029 1037 2029 3440 2029 2635 2030 1397 2030 2643 2030 2643 2031 1397 2031 1057 2031 2643 2032 1057 2032 2645 2032 2645 2033 1057 2033 1400 2033 2645 2034 1400 2034 1058 2034 1058 2035 1400 2035 1401 2035 1058 2036 1401 2036 2640 2036 2640 2037 1401 2037 2997 2037 1420 2038 2989 2038 1059 2038 1059 2039 2989 2039 1062 2039 1059 2040 1062 2040 1061 2040 2683 2041 1417 2041 2685 2041 2685 2042 1417 2042 1421 2042 2685 2043 1421 2043 1060 2043 1060 2044 1421 2044 1061 2044 1060 2045 1061 2045 2688 2045 2688 2046 1061 2046 1062 2046 2717 2047 1063 2047 2640 2047 2683 2048 2687 2048 2825 2048 2683 2049 2825 2049 1064 2049 1064 2050 2825 2050 1065 2050 1064 2051 1065 2051 1066 2051 1066 2052 1065 2052 1067 2052 1066 2053 1067 2053 1068 2053 1068 2054 1067 2054 1069 2054 1069 2055 1067 2055 1070 2055 1069 2056 1070 2056 1071 2056 1070 2057 2833 2057 1071 2057 1071 2058 2833 2058 2831 2058 1071 2059 2831 2059 2992 2059 2992 2060 2831 2060 1072 2060 2992 2061 1072 2061 1073 2061 1073 2062 1072 2062 1074 2062 1073 2063 1074 2063 2993 2063 2993 2064 1074 2064 2724 2064 2993 2065 2724 2065 2994 2065 2994 2066 2724 2066 1076 2066 2994 2067 1076 2067 1075 2067 1075 2068 1076 2068 2718 2068 1075 2069 2718 2069 1081 2069 2640 2070 2998 2070 2717 2070 2717 2071 2998 2071 1077 2071 2717 2072 1077 2072 2723 2072 2723 2073 1077 2073 1078 2073 2723 2074 1078 2074 2721 2074 2721 2075 1078 2075 1080 2075 2721 2076 1080 2076 1079 2076 1079 2077 1080 2077 1081 2077 1079 2078 1081 2078 1082 2078 1082 2079 1081 2079 2718 2079 2250 2080 4299 2080 7990 2080 7990 2081 4299 2081 1083 2081 7990 2082 1083 2082 7991 2082 7991 2083 1083 2083 1084 2083 1084 2084 1083 2084 7992 2084 7992 2085 1083 2085 4296 2085 7992 2086 4296 2086 1085 2086 1085 2087 4296 2087 1086 2087 1085 2088 1086 2088 1091 2088 1091 2089 1086 2089 1087 2089 1091 2090 1087 2090 1088 2090 1088 2091 4292 2091 1091 2091 1091 2092 4292 2092 1089 2092 1091 2093 1089 2093 4301 2093 1095 2094 8012 2094 8008 2094 4301 2095 1090 2095 1091 2095 1091 2096 1090 2096 1092 2096 1091 2097 1092 2097 1093 2097 1093 2098 1092 2098 1095 2098 1093 2099 1095 2099 1094 2099 1094 2100 1095 2100 8008 2100 7338 2101 7310 2101 2145 2101 2145 2102 7310 2102 7312 2102 2145 2103 7312 2103 2146 2103 2145 2104 1096 2104 7338 2104 7338 2105 1096 2105 4472 2105 7338 2106 4472 2106 1097 2106 1097 2107 4472 2107 1098 2107 1098 2108 1099 2108 1097 2108 1097 2109 1099 2109 1100 2109 1097 2110 1100 2110 4469 2110 4469 2111 4468 2111 1097 2111 1097 2112 4468 2112 4454 2112 1097 2113 4454 2113 1103 2113 4453 2114 1101 2114 2151 2114 2151 2115 7314 2115 4453 2115 4453 2116 7314 2116 1102 2116 4453 2117 1102 2117 1103 2117 1103 2118 1102 2118 7337 2118 1103 2119 7337 2119 1097 2119 1115 2120 1104 2120 1114 2120 1124 2121 1145 2121 1104 2121 1104 2122 1145 2122 1105 2122 1104 2123 1105 2123 1114 2123 292 2124 1106 2124 1108 2124 1108 2125 1106 2125 1107 2125 2180 2126 1113 2126 1108 2126 1108 2127 1113 2127 1109 2127 1108 2128 1109 2128 292 2128 2179 2129 1110 2129 1112 2129 1112 2130 1110 2130 1111 2130 1112 2131 1111 2131 2180 2131 2180 2132 1111 2132 288 2132 2180 2133 288 2133 1113 2133 1114 2134 290 2134 1115 2134 1115 2135 290 2135 1116 2135 1115 2136 1116 2136 2179 2136 2179 2137 1116 2137 289 2137 2179 2138 289 2138 1110 2138 1106 2139 9137 2139 1107 2139 1107 2140 9137 2140 1117 2140 1107 2141 1117 2141 2182 2141 2182 2142 1117 2142 1118 2142 2182 2143 1118 2143 1119 2143 1119 2144 1118 2144 1120 2144 1119 2145 1120 2145 1121 2145 1121 2146 1120 2146 1147 2146 1121 2147 1147 2147 1122 2147 1122 2148 1147 2148 1123 2148 1122 2149 1123 2149 1124 2149 1124 2150 1123 2150 1146 2150 1124 2151 1146 2151 1145 2151 1125 2152 1126 2152 1129 2152 1129 2153 1126 2153 1139 2153 1132 2154 1127 2154 1129 2154 1129 2155 1127 2155 1128 2155 1129 2156 1128 2156 1125 2156 1130 2157 298 2157 1131 2157 1131 2158 298 2158 295 2158 1131 2159 295 2159 1132 2159 1132 2160 295 2160 294 2160 1132 2161 294 2161 1127 2161 1135 2162 1133 2162 1130 2162 1130 2163 1133 2163 299 2163 1130 2164 299 2164 298 2164 1136 2165 1134 2165 1135 2165 1135 2166 1134 2166 301 2166 1135 2167 301 2167 1133 2167 2221 2168 1153 2168 1136 2168 1136 2169 1153 2169 1137 2169 1136 2170 1137 2170 1134 2170 1126 2171 1138 2171 1139 2171 1139 2172 1138 2172 1141 2172 1139 2173 1141 2173 1140 2173 1140 2174 1141 2174 1156 2174 1140 2175 1156 2175 1142 2175 1142 2176 1156 2176 1157 2176 1142 2177 1157 2177 1143 2177 1143 2178 1157 2178 1152 2178 1143 2179 1152 2179 2220 2179 2220 2180 1152 2180 1144 2180 2220 2181 1144 2181 2221 2181 2221 2182 1144 2182 1154 2182 2221 2183 1154 2183 1153 2183 4649 2184 1272 2184 9135 2184 9135 2185 1272 2185 9136 2185 5419 2186 1145 2186 1148 2186 1148 2187 1145 2187 1146 2187 1146 2188 1123 2188 1148 2188 1148 2189 1123 2189 1147 2189 1148 2190 1147 2190 1149 2190 1117 2191 1278 2191 1118 2191 1118 2192 1278 2192 1149 2192 1118 2193 1149 2193 1120 2193 1120 2194 1149 2194 1147 2194 1293 2195 1150 2195 120 2195 120 2196 1150 2196 119 2196 1144 2197 1152 2197 1151 2197 1151 2198 1152 2198 2209 2198 9132 2199 1153 2199 1151 2199 1151 2200 1153 2200 1154 2200 1151 2201 1154 2201 1144 2201 1141 2202 1155 2202 1156 2202 1156 2203 1155 2203 2209 2203 1156 2204 2209 2204 1157 2204 1157 2205 2209 2205 1152 2205 7779 2206 1217 2206 1231 2206 7555 2207 1162 2207 7543 2207 7543 2208 1162 2208 1160 2208 7543 2209 1160 2209 7544 2209 7544 2210 1160 2210 1158 2210 1158 2211 1160 2211 1159 2211 1159 2212 1160 2212 1162 2212 1159 2213 1162 2213 1161 2213 7555 2214 1163 2214 1162 2214 1162 2215 1163 2215 7563 2215 1162 2216 7563 2216 1161 2216 9162 2217 1166 2217 1159 2217 1159 2218 1166 2218 1164 2218 1159 2219 1164 2219 1158 2219 1172 2220 7516 2220 9163 2220 9163 2221 7516 2221 7529 2221 9163 2222 7529 2222 9162 2222 9162 2223 7529 2223 1165 2223 9162 2224 1165 2224 1166 2224 7574 2225 7601 2225 1177 2225 1167 2226 9139 2226 7454 2226 7454 2227 9139 2227 7420 2227 1167 2228 7454 2228 1168 2228 1168 2229 7454 2229 1169 2229 1168 2230 1169 2230 9155 2230 9155 2231 1169 2231 1170 2231 1170 2232 1169 2232 7455 2232 1170 2233 7455 2233 1172 2233 7455 2234 1171 2234 1172 2234 1172 2235 1171 2235 1173 2235 1172 2236 1173 2236 7516 2236 7516 2237 1173 2237 1175 2237 7516 2238 1175 2238 7497 2238 7464 2239 7483 2239 1176 2239 7494 2240 7505 2240 1174 2240 1174 2241 7505 2241 7497 2241 1174 2242 7497 2242 1176 2242 1176 2243 7497 2243 1175 2243 1176 2244 1175 2244 7464 2244 7574 2245 1177 2245 7583 2245 9139 2246 9140 2246 7420 2246 7420 2247 9140 2247 7597 2247 7420 2248 7597 2248 1177 2248 1177 2249 7597 2249 7582 2249 1177 2250 7582 2250 7583 2250 7601 2251 7599 2251 1178 2251 1178 2252 7599 2252 7702 2252 1178 2253 7702 2253 1179 2253 1179 2254 7702 2254 8985 2254 8985 2255 7702 2255 7699 2255 8985 2256 7699 2256 8983 2256 8983 2257 7699 2257 1181 2257 1181 2258 7699 2258 1180 2258 1181 2259 1180 2259 1182 2259 7601 2260 1178 2260 1177 2260 1177 2261 1178 2261 9004 2261 1177 2262 9004 2262 1183 2262 1183 2263 9023 2263 1177 2263 1177 2264 9023 2264 9032 2264 1177 2265 9032 2265 1185 2265 1185 2266 9032 2266 1184 2266 1185 2267 1184 2267 9033 2267 9033 2268 9051 2268 1185 2268 1185 2269 9051 2269 1186 2269 1185 2270 1186 2270 7402 2270 7402 2271 1186 2271 1187 2271 7402 2272 1187 2272 1188 2272 1188 2273 1187 2273 9072 2273 1188 2274 9072 2274 7400 2274 7400 2275 9072 2275 9071 2275 7400 2276 9071 2276 7413 2276 1197 2277 9078 2277 1189 2277 1190 2278 1191 2278 1196 2278 1196 2279 1191 2279 7367 2279 1196 2280 7367 2280 1195 2280 7386 2281 7390 2281 1192 2281 1192 2282 7390 2282 1193 2282 1192 2283 1193 2283 7367 2283 7367 2284 1193 2284 1194 2284 7367 2285 1194 2285 1195 2285 7413 2286 9071 2286 7410 2286 7410 2287 9071 2287 1197 2287 7410 2288 1197 2288 1196 2288 1196 2289 1197 2289 1189 2289 1196 2290 1189 2290 1190 2290 1198 2291 1199 2291 2347 2291 2347 2292 1199 2292 7315 2292 2347 2293 7315 2293 9078 2293 9078 2294 7315 2294 1200 2294 9078 2295 1200 2295 1189 2295 1182 2296 1180 2296 1201 2296 1201 2297 1180 2297 7694 2297 1201 2298 7694 2298 8960 2298 8960 2299 7694 2299 1202 2299 8960 2300 1202 2300 8954 2300 8954 2301 1202 2301 1204 2301 1204 2302 1202 2302 1203 2302 1204 2303 1203 2303 8955 2303 8955 2304 1203 2304 1205 2304 8955 2305 1205 2305 8956 2305 8956 2306 1205 2306 1206 2306 1206 2307 1205 2307 7639 2307 1206 2308 7639 2308 8958 2308 8958 2309 7639 2309 1208 2309 8958 2310 1208 2310 1207 2310 1207 2311 1208 2311 1209 2311 1207 2312 1209 2312 1210 2312 1210 2313 1209 2313 7637 2313 1210 2314 7637 2314 8932 2314 8932 2315 7637 2315 1211 2315 8932 2316 1211 2316 1212 2316 1212 2317 1211 2317 1214 2317 1212 2318 1214 2318 1213 2318 1213 2319 1214 2319 7634 2319 1213 2320 7634 2320 1216 2320 1225 2321 8874 2321 7623 2321 7623 2322 8874 2322 1215 2322 7623 2323 1215 2323 7624 2323 7624 2324 1215 2324 8891 2324 7624 2325 8891 2325 7625 2325 7625 2326 8891 2326 8886 2326 7625 2327 8886 2327 7626 2327 7626 2328 8886 2328 1216 2328 7626 2329 1216 2329 7633 2329 7633 2330 1216 2330 7634 2330 1217 2331 7798 2331 1231 2331 1231 2332 7798 2332 1218 2332 1231 2333 1218 2333 7808 2333 7808 2334 1219 2334 1231 2334 1231 2335 1219 2335 1220 2335 1231 2336 1220 2336 1221 2336 8847 2337 1222 2337 1223 2337 1223 2338 1222 2338 1224 2338 1223 2339 1224 2339 7621 2339 7621 2340 1224 2340 8902 2340 7621 2341 8902 2341 7622 2341 7622 2342 8902 2342 8896 2342 7622 2343 8896 2343 1225 2343 1225 2344 8896 2344 8875 2344 1225 2345 8875 2345 8874 2345 8847 2346 1223 2346 1226 2346 1226 2347 1223 2347 1227 2347 1226 2348 1227 2348 8850 2348 8850 2349 1227 2349 1228 2349 8850 2350 1228 2350 1229 2350 1229 2351 1228 2351 1230 2351 1230 2352 1228 2352 7731 2352 1230 2353 7731 2353 8832 2353 1221 2354 7842 2354 1231 2354 1231 2355 7842 2355 1237 2355 1231 2356 1237 2356 9176 2356 7732 2357 1232 2357 7886 2357 7886 2358 1232 2358 7704 2358 7886 2359 7704 2359 7709 2359 7709 2360 7708 2360 7886 2360 7886 2361 7708 2361 7706 2361 7886 2362 7706 2362 1234 2362 7706 2363 1233 2363 1234 2363 1234 2364 1233 2364 1235 2364 1234 2365 1235 2365 7871 2365 7871 2366 1235 2366 9209 2366 7871 2367 9209 2367 7868 2367 7868 2368 9209 2368 1236 2368 7868 2369 1236 2369 7866 2369 7866 2370 1236 2370 9198 2370 7866 2371 9198 2371 1237 2371 1237 2372 9198 2372 1238 2372 1237 2373 1238 2373 9176 2373 7731 2374 7732 2374 8832 2374 8832 2375 7732 2375 7886 2375 8832 2376 7886 2376 1239 2376 1239 2377 7886 2377 1240 2377 1242 2378 8771 2378 8772 2378 8772 2379 1241 2379 1242 2379 1242 2380 1241 2380 8782 2380 1242 2381 8782 2381 7886 2381 7886 2382 8782 2382 8783 2382 7886 2383 8783 2383 1240 2383 8771 2384 1242 2384 8762 2384 8762 2385 1242 2385 1243 2385 8762 2386 1243 2386 8760 2386 8760 2387 1243 2387 1244 2387 8760 2388 1244 2388 8731 2388 1244 2389 1245 2389 8731 2389 8731 2390 1245 2390 7900 2390 8731 2391 7900 2391 1246 2391 1246 2392 7900 2392 7899 2392 1246 2393 7899 2393 8735 2393 7994 2394 7989 2394 8735 2394 7949 2395 7950 2395 7994 2395 7920 2396 7919 2396 7923 2396 7927 2397 7928 2397 1247 2397 1247 2398 7928 2398 1248 2398 1247 2399 1248 2399 7923 2399 7923 2400 1248 2400 7908 2400 7923 2401 7908 2401 7920 2401 1248 2402 7949 2402 7908 2402 7908 2403 7949 2403 7994 2403 7908 2404 7994 2404 1249 2404 1249 2405 7994 2405 8735 2405 1249 2406 8735 2406 7897 2406 7897 2407 8735 2407 7899 2407 7989 2408 7988 2408 8735 2408 8735 2409 7988 2409 7999 2409 8735 2410 7999 2410 8729 2410 8729 2411 7999 2411 7971 2411 8729 2412 7971 2412 7970 2412 7742 2413 1252 2413 1250 2413 1250 2414 1252 2414 9169 2414 1250 2415 9169 2415 1251 2415 1251 2416 7753 2416 1250 2416 1250 2417 7753 2417 7743 2417 1250 2418 7743 2418 7742 2418 1253 2419 1231 2419 1252 2419 1252 2420 1231 2420 9170 2420 1252 2421 9170 2421 9169 2421 1253 2422 7763 2422 1231 2422 1231 2423 7763 2423 7770 2423 1231 2424 7770 2424 7776 2424 7776 2425 7778 2425 1231 2425 1231 2426 7778 2426 1254 2426 1231 2427 1254 2427 7779 2427 3790 2428 126 2428 1255 2428 1255 2429 126 2429 1267 2429 1267 2430 126 2430 1256 2430 1256 2431 126 2431 123 2431 1256 2432 123 2432 1269 2432 1259 2433 117 2433 1264 2433 1264 2434 117 2434 1257 2434 1264 2435 1257 2435 1263 2435 1263 2436 1257 2436 3795 2436 1263 2437 3795 2437 1258 2437 1259 2438 5400 2438 9134 2438 9134 2439 5400 2439 1260 2439 9134 2440 1260 2440 1261 2440 1261 2441 1260 2441 5399 2441 1261 2442 5399 2442 1262 2442 1258 2443 5401 2443 1263 2443 1263 2444 5401 2444 5400 2444 1263 2445 5400 2445 1264 2445 1264 2446 5400 2446 1259 2446 1265 2447 1255 2447 1266 2447 1266 2448 1255 2448 1267 2448 1267 2449 1256 2449 1266 2449 1266 2450 1256 2450 1269 2450 1266 2451 1269 2451 1268 2451 1269 2452 1270 2452 1268 2452 1268 2453 1270 2453 285 2453 1268 2454 285 2454 1271 2454 1271 2455 285 2455 287 2455 1273 2456 9136 2456 1272 2456 1272 2457 1274 2457 1273 2457 1273 2458 1274 2458 1275 2458 1273 2459 1275 2459 1276 2459 1276 2460 1275 2460 7595 2460 1276 2461 7595 2461 1277 2461 1277 2462 7595 2462 7596 2462 1277 2463 7596 2463 9140 2463 9140 2464 7596 2464 7597 2464 1149 2465 1278 2465 7558 2465 7558 2466 1278 2466 1279 2466 7558 2467 1279 2467 1280 2467 1280 2468 1279 2468 1281 2468 1280 2469 1281 2469 1282 2469 1282 2470 1281 2470 1285 2470 1282 2471 1285 2471 1284 2471 9162 2472 1159 2472 1283 2472 1283 2473 1159 2473 1284 2473 1283 2474 1284 2474 9164 2474 9164 2475 1284 2475 1285 2475 1251 2476 9169 2476 1286 2476 1286 2477 9169 2477 1287 2477 1286 2478 1287 2478 7752 2478 7752 2479 1287 2479 9173 2479 7752 2480 9173 2480 1288 2480 1288 2481 9173 2481 9175 2481 1288 2482 9175 2482 1289 2482 1289 2483 9175 2483 9132 2483 1289 2484 9132 2484 1151 2484 1235 2485 1233 2485 1290 2485 1290 2486 1233 2486 1291 2486 1290 2487 1291 2487 9210 2487 9210 2488 1291 2488 1292 2488 9210 2489 1292 2489 9211 2489 9211 2490 1292 2490 7714 2490 9211 2491 7714 2491 1293 2491 1293 2492 7714 2492 1150 2492 15 2493 1294 2493 3659 2493 3025 2494 1295 2494 3624 2494 3624 2495 1295 2495 3017 2495 3624 2496 3017 2496 3623 2496 3678 2497 2964 2497 1296 2497 1296 2498 2964 2498 2960 2498 2960 2499 2959 2499 1296 2499 1296 2500 2959 2500 1297 2500 1296 2501 1297 2501 1298 2501 1298 2502 1297 2502 1333 2502 1298 2503 1333 2503 3674 2503 3659 2504 1294 2504 3654 2504 1294 2505 14 2505 3654 2505 3654 2506 14 2506 1299 2506 3654 2507 1299 2507 3646 2507 3646 2508 1299 2508 1300 2508 3646 2509 1300 2509 1303 2509 1301 2510 3620 2510 1302 2510 1302 2511 3620 2511 3563 2511 1303 2512 1304 2512 3646 2512 3646 2513 1304 2513 2 2513 3646 2514 2 2514 3563 2514 3563 2515 2 2515 1 2515 3563 2516 1 2516 1302 2516 1301 2517 3 2517 3620 2517 3620 2518 3 2518 1305 2518 3620 2519 1305 2519 3619 2519 1305 2520 0 2520 3619 2520 3619 2521 0 2521 1306 2521 3619 2522 1306 2522 1308 2522 1308 2523 1306 2523 1307 2523 1308 2524 1307 2524 3617 2524 3617 2525 1307 2525 1309 2525 3617 2526 1309 2526 3613 2526 3613 2527 1309 2527 1310 2527 3613 2528 1310 2528 3601 2528 3601 2529 1310 2529 5 2529 3601 2530 5 2530 1311 2530 1317 2531 1312 2531 3636 2531 1324 2532 3624 2532 1312 2532 1314 2533 1316 2533 1313 2533 1314 2534 1315 2534 1316 2534 1316 2535 1315 2535 9 2535 1316 2536 9 2536 1331 2536 1311 2537 5 2537 3636 2537 3636 2538 5 2538 4 2538 3636 2539 4 2539 1317 2539 1317 2540 4 2540 1318 2540 1317 2541 1318 2541 6 2541 6 2542 1319 2542 1317 2542 1317 2543 1319 2543 1320 2543 1317 2544 1320 2544 1313 2544 1313 2545 1320 2545 1321 2545 1313 2546 1321 2546 1314 2546 1324 2547 1325 2547 1335 2547 1335 2548 1322 2548 1324 2548 1324 2549 1322 2549 3027 2549 1324 2550 3027 2550 3624 2550 3624 2551 3027 2551 1323 2551 3624 2552 1323 2552 3025 2552 1312 2553 1317 2553 1324 2553 1324 2554 1317 2554 1313 2554 1324 2555 1313 2555 1325 2555 1325 2556 1313 2556 1316 2556 1325 2557 1316 2557 1332 2557 15 2558 3659 2558 1326 2558 1326 2559 3659 2559 3665 2559 1326 2560 3665 2560 12 2560 12 2561 3665 2561 1327 2561 12 2562 1327 2562 10 2562 10 2563 1327 2563 1328 2563 10 2564 1328 2564 1329 2564 1329 2565 1328 2565 1330 2565 1329 2566 1330 2566 1331 2566 1331 2567 1330 2567 3688 2567 1331 2568 3688 2568 1316 2568 1316 2569 3688 2569 3674 2569 1316 2570 3674 2570 1332 2570 1332 2571 3674 2571 1333 2571 1332 2572 1333 2572 1325 2572 1325 2573 1333 2573 1334 2573 1325 2574 1334 2574 1335 2574 1336 2575 919 2575 1437 2575 1421 2576 1417 2576 1427 2576 2991 2577 1413 2577 1337 2577 2996 2578 1352 2578 2995 2578 2966 2579 1338 2579 1372 2579 1378 2580 1007 2580 1377 2580 1001 2581 1369 2581 1339 2581 1339 2582 1369 2582 1384 2582 1339 2583 1384 2583 1340 2583 1340 2584 1384 2584 1377 2584 1001 2585 1341 2585 1369 2585 1369 2586 1341 2586 1342 2586 1369 2587 1342 2587 1372 2587 1372 2588 1342 2588 1343 2588 1372 2589 1343 2589 1374 2589 1373 2590 1004 2590 1344 2590 1344 2591 1004 2591 3029 2591 1004 2592 1006 2592 3029 2592 3029 2593 1006 2593 1007 2593 3029 2594 1007 2594 3028 2594 3028 2595 1007 2595 1378 2595 3028 2596 1378 2596 3023 2596 931 2597 932 2597 1440 2597 1440 2598 932 2598 1345 2598 1440 2599 1345 2599 1442 2599 1442 2600 1345 2600 1346 2600 1442 2601 1346 2601 920 2601 922 2602 1347 2602 1348 2602 1348 2603 1347 2603 924 2603 1348 2604 924 2604 1453 2604 1352 2605 1433 2605 1351 2605 886 2606 1349 2606 1419 2606 1349 2607 1350 2607 1419 2607 1419 2608 1350 2608 889 2608 1419 2609 889 2609 1433 2609 1433 2610 889 2610 890 2610 1433 2611 890 2611 1351 2611 1351 2612 893 2612 1352 2612 1352 2613 893 2613 1353 2613 1352 2614 1353 2614 2995 2614 2995 2615 1353 2615 895 2615 2995 2616 895 2616 1354 2616 1354 2617 895 2617 1355 2617 1354 2618 1355 2618 2991 2618 2991 2619 1355 2619 882 2619 2991 2620 882 2620 1413 2620 1413 2621 882 2621 884 2621 1413 2622 884 2622 886 2622 853 2623 854 2623 1445 2623 1445 2624 854 2624 1356 2624 1445 2625 1356 2625 1425 2625 1425 2626 1356 2626 1357 2626 1425 2627 1357 2627 848 2627 1358 2628 851 2628 1449 2628 1449 2629 851 2629 1359 2629 1449 2630 1359 2630 1446 2630 1446 2631 1359 2631 1360 2631 1446 2632 1360 2632 1361 2632 1423 2633 1424 2633 2979 2633 2979 2634 1424 2634 1364 2634 1423 2635 2981 2635 1428 2635 2981 2636 2982 2636 1428 2636 1428 2637 2982 2637 1362 2637 1428 2638 1362 2638 2986 2638 2973 2639 2974 2639 1449 2639 1449 2640 2974 2640 1363 2640 1449 2641 1363 2641 1358 2641 1358 2642 1363 2642 2976 2642 1358 2643 2976 2643 1364 2643 1364 2644 2976 2644 2978 2644 1364 2645 2978 2645 2979 2645 1366 2646 1365 2646 1451 2646 1451 2647 1365 2647 2971 2647 1371 2648 2961 2648 1366 2648 1366 2649 2961 2649 2970 2649 1366 2650 2970 2650 1365 2650 1372 2651 829 2651 1368 2651 1366 2652 1369 2652 834 2652 834 2653 1369 2653 832 2653 834 2654 1367 2654 1366 2654 1366 2655 1367 2655 821 2655 1366 2656 821 2656 1371 2656 1372 2657 1368 2657 1369 2657 1369 2658 1368 2658 830 2658 1369 2659 830 2659 832 2659 821 2660 1370 2660 1371 2660 1371 2661 1370 2661 823 2661 1371 2662 823 2662 2968 2662 2968 2663 823 2663 825 2663 2968 2664 825 2664 1338 2664 1338 2665 825 2665 826 2665 1338 2666 826 2666 1372 2666 1372 2667 826 2667 827 2667 1372 2668 827 2668 829 2668 1373 2669 1344 2669 1374 2669 1374 2670 1344 2670 1375 2670 1374 2671 1375 2671 1372 2671 1372 2672 1375 2672 2963 2672 1372 2673 2963 2673 2966 2673 3018 2674 3019 2674 1378 2674 1378 2675 3019 2675 3021 2675 1378 2676 3021 2676 3023 2676 1376 2677 3018 2677 1381 2677 1377 2678 1384 2678 1378 2678 1378 2679 1384 2679 1385 2679 1378 2680 1385 2680 953 2680 953 2681 954 2681 1378 2681 1378 2682 954 2682 1379 2682 1378 2683 1379 2683 3018 2683 3018 2684 1379 2684 1380 2684 3018 2685 1380 2685 1381 2685 1381 2686 956 2686 1376 2686 1376 2687 956 2687 1382 2687 1376 2688 1382 2688 1459 2688 1459 2689 1382 2689 1383 2689 1383 2690 958 2690 1459 2690 1459 2691 958 2691 949 2691 1459 2692 949 2692 1384 2692 1384 2693 949 2693 951 2693 1384 2694 951 2694 1385 2694 1460 2695 3013 2695 1459 2695 1459 2696 3013 2696 3015 2696 1459 2697 3015 2697 1376 2697 1386 2698 1453 2698 1387 2698 1387 2699 1453 2699 1391 2699 1386 2700 1388 2700 1453 2700 1453 2701 1388 2701 3010 2701 1453 2702 3010 2702 1460 2702 1460 2703 3010 2703 3012 2703 1460 2704 3012 2704 3013 2704 924 2705 1389 2705 1453 2705 1453 2706 1389 2706 929 2706 1453 2707 929 2707 1391 2707 1391 2708 929 2708 1390 2708 1391 2709 1390 2709 3006 2709 3006 2710 1390 2710 1393 2710 3006 2711 1393 2711 1392 2711 1392 2712 1393 2712 931 2712 1392 2713 931 2713 1394 2713 1394 2714 931 2714 1440 2714 1394 2715 1440 2715 1395 2715 1395 2716 1440 2716 1437 2716 1395 2717 1437 2717 1396 2717 3004 2718 3003 2718 1399 2718 1399 2719 3003 2719 1397 2719 3003 2720 3001 2720 1397 2720 1397 2721 3001 2721 1396 2721 1397 2722 1396 2722 1057 2722 1057 2723 1396 2723 1437 2723 1057 2724 1437 2724 1400 2724 1398 2725 1035 2725 1399 2725 1399 2726 1035 2726 1034 2726 1399 2727 1034 2727 3004 2727 1400 2728 1437 2728 1401 2728 1401 2729 1437 2729 1431 2729 1401 2730 1431 2730 2997 2730 1409 2731 1410 2731 2996 2731 2996 2732 1410 2732 1402 2732 2996 2733 1402 2733 1352 2733 1352 2734 1402 2734 1405 2734 1403 2735 1433 2735 898 2735 898 2736 1433 2736 1352 2736 898 2737 1352 2737 1404 2737 1404 2738 1352 2738 1405 2738 1403 2739 899 2739 1433 2739 1433 2740 899 2740 1406 2740 1433 2741 1406 2741 1431 2741 1406 2742 1407 2742 1431 2742 1431 2743 1407 2743 902 2743 1431 2744 902 2744 2997 2744 2997 2745 902 2745 905 2745 2997 2746 905 2746 1409 2746 1409 2747 905 2747 1408 2747 1409 2748 1408 2748 1410 2748 886 2749 1419 2749 1413 2749 1413 2750 1419 2750 1411 2750 1413 2751 1411 2751 1412 2751 1412 2752 879 2752 1413 2752 1413 2753 879 2753 1414 2753 1413 2754 1414 2754 1337 2754 1337 2755 1414 2755 880 2755 1337 2756 880 2756 2990 2756 880 2757 1415 2757 2990 2757 2990 2758 1415 2758 1416 2758 2990 2759 1416 2759 1417 2759 1417 2760 1416 2760 873 2760 1417 2761 873 2761 1427 2761 1427 2762 873 2762 874 2762 874 2763 1418 2763 1427 2763 1427 2764 1418 2764 876 2764 1427 2765 876 2765 1419 2765 1419 2766 876 2766 878 2766 1419 2767 878 2767 1411 2767 1043 2768 1420 2768 1422 2768 1421 2769 1427 2769 1061 2769 1061 2770 1427 2770 1428 2770 1061 2771 1428 2771 1059 2771 1059 2772 1428 2772 2986 2772 1059 2773 2986 2773 1420 2773 1420 2774 2986 2774 2984 2774 1420 2775 2984 2775 1422 2775 1041 2776 1042 2776 1038 2776 1038 2777 1042 2777 1043 2777 1038 2778 1043 2778 2983 2778 2983 2779 1043 2779 1422 2779 1435 2780 1426 2780 1427 2780 858 2781 859 2781 1425 2781 1430 2782 858 2782 1428 2782 1428 2783 858 2783 1425 2783 1428 2784 1425 2784 1423 2784 1423 2785 1425 2785 848 2785 1423 2786 848 2786 1424 2786 859 2787 862 2787 1425 2787 1425 2788 862 2788 863 2788 1425 2789 863 2789 1445 2789 1445 2790 863 2790 864 2790 1445 2791 864 2791 866 2791 1426 2792 868 2792 1427 2792 1427 2793 868 2793 1429 2793 1427 2794 1429 2794 1428 2794 1428 2795 1429 2795 856 2795 1428 2796 856 2796 1430 2796 1437 2797 919 2797 1431 2797 1431 2798 919 2798 908 2798 1431 2799 908 2799 1432 2799 1432 2800 1438 2800 1431 2800 1431 2801 1438 2801 1442 2801 1431 2802 1442 2802 1433 2802 1433 2803 1442 2803 1434 2803 1433 2804 1434 2804 1419 2804 1419 2805 1434 2805 1443 2805 1419 2806 1443 2806 1427 2806 1427 2807 1443 2807 1445 2807 1427 2808 1445 2808 1435 2808 1435 2809 1445 2809 866 2809 913 2810 914 2810 1440 2810 1440 2811 914 2811 916 2811 1440 2812 916 2812 1437 2812 1437 2813 916 2813 1436 2813 1437 2814 1436 2814 1336 2814 1438 2815 1439 2815 1442 2815 1442 2816 1439 2816 911 2816 1442 2817 911 2817 1440 2817 1440 2818 911 2818 1441 2818 1440 2819 1441 2819 913 2819 920 2820 922 2820 1442 2820 1442 2821 922 2821 1348 2821 1442 2822 1348 2822 1434 2822 1434 2823 1348 2823 1457 2823 1434 2824 1457 2824 1443 2824 1443 2825 1457 2825 1444 2825 1443 2826 1444 2826 1445 2826 1445 2827 1444 2827 1446 2827 1445 2828 1446 2828 853 2828 853 2829 1446 2829 1361 2829 1449 2830 837 2830 1447 2830 1451 2831 1448 2831 839 2831 2971 2832 2973 2832 1451 2832 1451 2833 2973 2833 1449 2833 1451 2834 1449 2834 1448 2834 1448 2835 1449 2835 1447 2835 1456 2836 845 2836 1446 2836 1446 2837 845 2837 846 2837 1446 2838 846 2838 1449 2838 1449 2839 846 2839 847 2839 1449 2840 847 2840 837 2840 839 2841 1450 2841 1451 2841 1451 2842 1450 2842 841 2842 1451 2843 841 2843 1366 2843 1366 2844 841 2844 842 2844 1366 2845 842 2845 1455 2845 937 2846 939 2846 1459 2846 1452 2847 948 2847 1453 2847 1453 2848 948 2848 1454 2848 1453 2849 1454 2849 1348 2849 1348 2850 1454 2850 935 2850 1348 2851 935 2851 936 2851 1452 2852 1453 2852 945 2852 945 2853 1453 2853 1460 2853 945 2854 1460 2854 943 2854 1455 2855 1456 2855 1366 2855 1366 2856 1456 2856 1446 2856 1366 2857 1446 2857 1369 2857 1369 2858 1446 2858 1444 2858 1369 2859 1444 2859 1384 2859 1384 2860 1444 2860 1457 2860 1384 2861 1457 2861 1459 2861 1459 2862 1457 2862 1348 2862 1459 2863 1348 2863 937 2863 937 2864 1348 2864 936 2864 939 2865 1458 2865 1459 2865 1459 2866 1458 2866 940 2866 1459 2867 940 2867 1460 2867 1460 2868 940 2868 942 2868 1460 2869 942 2869 943 2869 1467 2870 1461 2870 1468 2870 6191 2871 6188 2871 4609 2871 1488 2872 1503 2872 6049 2872 1463 2873 1464 2873 1677 2873 3736 2874 3737 2874 1508 2874 1462 2875 3803 2875 1463 2875 1463 2876 3803 2876 3807 2876 1463 2877 3807 2877 1464 2877 1463 2878 6093 2878 1462 2878 1462 2879 6093 2879 6092 2879 1462 2880 6092 2880 1465 2880 1465 2881 6092 2881 3808 2881 2117 2882 1476 2882 1466 2882 1466 2883 1476 2883 1477 2883 1024 2884 1019 2884 1484 2884 6092 2885 1467 2885 3808 2885 3808 2886 1467 2886 1468 2886 3808 2887 1468 2887 1537 2887 3762 2888 3756 2888 3750 2888 3750 2889 3756 2889 1469 2889 3750 2890 1469 2890 3751 2890 3750 2891 1470 2891 1472 2891 1472 2892 1470 2892 3749 2892 1472 2893 3749 2893 3743 2893 1471 2894 3773 2894 1675 2894 3757 2895 3762 2895 3758 2895 3758 2896 3762 2896 3750 2896 3758 2897 3750 2897 1654 2897 1654 2898 3750 2898 1472 2898 1689 2899 1473 2899 4609 2899 4609 2900 1473 2900 8534 2900 4609 2901 8534 2901 8535 2901 1483 2902 3701 2902 1484 2902 1484 2903 3701 2903 1012 2903 1484 2904 1012 2904 6056 2904 1486 2905 964 2905 962 2905 1461 2906 6132 2906 1468 2906 1468 2907 6132 2907 6134 2907 1468 2908 6134 2908 1474 2908 1474 2909 6134 2909 3750 2909 1474 2910 3750 2910 1475 2910 1475 2911 3750 2911 3751 2911 1551 2912 1476 2912 1503 2912 1503 2913 1476 2913 2117 2913 1503 2914 2117 2914 2115 2914 1477 2915 1476 2915 4609 2915 4609 2916 1476 2916 1690 2916 4609 2917 1690 2917 1689 2917 8368 2918 1478 2918 8535 2918 8535 2919 1478 2919 1479 2919 8535 2920 1479 2920 4609 2920 4609 2921 1479 2921 6192 2921 4609 2922 6192 2922 6191 2922 6188 2923 6187 2923 4609 2923 4609 2924 6187 2924 1480 2924 4609 2925 1480 2925 1481 2925 1481 2926 1480 2926 2339 2926 3704 2927 1483 2927 1482 2927 1482 2928 1483 2928 1484 2928 1482 2929 1484 2929 1018 2929 1018 2930 1484 2930 1019 2930 1502 2931 1485 2931 3773 2931 3773 2932 1485 2932 3770 2932 3773 2933 3770 2933 1531 2933 962 2934 960 2934 1486 2934 1486 2935 960 2935 3813 2935 1486 2936 3813 2936 1677 2936 1677 2937 3813 2937 3815 2937 1677 2938 3815 2938 1463 2938 3744 2939 3746 2939 3749 2939 3749 2940 3746 2940 3741 2940 3749 2941 3741 2941 3743 2941 2115 2942 2114 2942 1503 2942 1503 2943 2114 2943 2112 2943 1503 2944 2112 2944 2111 2944 1495 2945 3733 2945 1506 2945 5340 2946 5338 2946 5342 2946 5342 2947 5338 2947 1487 2947 5342 2948 1487 2948 1480 2948 1480 2949 1487 2949 2341 2949 1480 2950 2341 2950 2339 2950 6049 2951 6050 2951 1488 2951 1488 2952 6050 2952 1489 2952 1488 2953 1489 2953 6054 2953 6054 2954 1489 2954 1484 2954 6054 2955 1484 2955 1490 2955 1490 2956 1484 2956 6056 2956 1491 2957 1492 2957 2334 2957 2334 2958 1492 2958 1497 2958 1693 2959 1493 2959 7107 2959 7107 2960 1493 2960 8201 2960 7107 2961 8201 2961 1518 2961 1518 2962 8201 2962 8202 2962 1494 2963 973 2963 1674 2963 1495 2964 1506 2964 1505 2964 3733 2965 1495 2965 1508 2965 1508 2966 1495 2966 5344 2966 1508 2967 5344 2967 1509 2967 1551 2968 2174 2968 1519 2968 1496 2969 1498 2969 4951 2969 1492 2970 1896 2970 1497 2970 1497 2971 1896 2971 1899 2971 1497 2972 1899 2972 1496 2972 1496 2973 1899 2973 4952 2973 1496 2974 4952 2974 1498 2974 5369 2975 1499 2975 1543 2975 2283 2976 2282 2976 1518 2976 1693 2977 8364 2977 1493 2977 1493 2978 8364 2978 8365 2978 1493 2979 8365 2979 1500 2979 1500 2980 8365 2980 1501 2980 5382 2981 1538 2981 3773 2981 3773 2982 1538 2982 6147 2982 3773 2983 6147 2983 1502 2983 2111 2984 2109 2984 1503 2984 1503 2985 2109 2985 1504 2985 1503 2986 1504 2986 6166 2986 6166 2987 1504 2987 1505 2987 6166 2988 1505 2988 6167 2988 6167 2989 1505 2989 1506 2989 5352 2990 5355 2990 5344 2990 5344 2991 5355 2991 1507 2991 5344 2992 1507 2992 1509 2992 3740 2993 3736 2993 3739 2993 3739 2994 3736 2994 1508 2994 3739 2995 1508 2995 1033 2995 1033 2996 1508 2996 1509 2996 1510 2997 1511 2997 1513 2997 1513 2998 1511 2998 1512 2998 1513 2999 1512 2999 5258 2999 3694 3000 3691 3000 1514 3000 1514 3001 3691 3001 3690 3001 1514 3002 3690 3002 1515 3002 1515 3003 3690 3003 1024 3003 1515 3004 1024 3004 1013 3004 1013 3005 1024 3005 1484 3005 1516 3006 2166 3006 1517 3006 8202 3007 1692 3007 1518 3007 1518 3008 1692 3008 8197 3008 1518 3009 8197 3009 8196 3009 1519 3010 2172 3010 1551 3010 1551 3011 2172 3011 2171 3011 1551 3012 2171 3012 1520 3012 1553 3013 4635 3013 1521 3013 1521 3014 4635 3014 1522 3014 1521 3015 1522 3015 2231 3015 2231 3016 2229 3016 1521 3016 1521 3017 2229 3017 1523 3017 1521 3018 1523 3018 8196 3018 8196 3019 1523 3019 2226 3019 8196 3020 2226 3020 1568 3020 1541 3021 2242 3021 1540 3021 1540 3022 2242 3022 1524 3022 1540 3023 1524 3023 1766 3023 1766 3024 1524 3024 1525 3024 1766 3025 1525 3025 1521 3025 1521 3026 1525 3026 2238 3026 1521 3027 2238 3027 1526 3027 1526 3028 2234 3028 4642 3028 4642 3029 2234 3029 2235 3029 4642 3030 2235 3030 4640 3030 4640 3031 2235 3031 2009 3031 1499 3032 3727 3032 3724 3032 1499 3033 5369 3033 1528 3033 1528 3034 5369 3034 1527 3034 1528 3035 1527 3035 6073 3035 6073 3036 1527 3036 1555 3036 6073 3037 1555 3037 6072 3037 2282 3038 2280 3038 1518 3038 1518 3039 2280 3039 2328 3039 1518 3040 2328 3040 1529 3040 1675 3041 3773 3041 1530 3041 1530 3042 3773 3042 1531 3042 1530 3043 1531 3043 1674 3043 1674 3044 1531 3044 976 3044 1674 3045 976 3045 1494 3045 1532 3046 3780 3046 1533 3046 1533 3047 3780 3047 1471 3047 1533 3048 1471 3048 1669 3048 1669 3049 1471 3049 1675 3049 8368 3050 8535 3050 1822 3050 1822 3051 8535 3051 1513 3051 1822 3052 1513 3052 1823 3052 1823 3053 1513 3053 5258 3053 1823 3054 5258 3054 5257 3054 1551 3055 1547 3055 1803 3055 1803 3056 1547 3056 1534 3056 1803 3057 1534 3057 5145 3057 4536 3058 1874 3058 2153 3058 2153 3059 1874 3059 1535 3059 2153 3060 1535 3060 1536 3060 1538 3061 1549 3061 1468 3061 1468 3062 1549 3062 5391 3062 1468 3063 5391 3063 1537 3063 5427 3064 5425 3064 5379 3064 5379 3065 5425 3065 1549 3065 5379 3066 1549 3066 5381 3066 5381 3067 1549 3067 1538 3067 5381 3068 1538 3068 1539 3068 1539 3069 1538 3069 5382 3069 1540 3070 1542 3070 1541 3070 1541 3071 1542 3071 5054 3071 1541 3072 5054 3072 5053 3072 4366 3073 4367 3073 4369 3073 4951 3074 7109 3074 1496 3074 1496 3075 7109 3075 7108 3075 1496 3076 7108 3076 1529 3076 1529 3077 7108 3077 7113 3077 1529 3078 7113 3078 1518 3078 1518 3079 7113 3079 7111 3079 1518 3080 7111 3080 7107 3080 1543 3081 1499 3081 3721 3081 3721 3082 1499 3082 3724 3082 3721 3083 3724 3083 3725 3083 5365 3084 5366 3084 5372 3084 5372 3085 5366 3085 5369 3085 5372 3086 5369 3086 5363 3086 5363 3087 5369 3087 1543 3087 5205 3088 5206 3088 1544 3088 1544 3089 5206 3089 1545 3089 1544 3090 1545 3090 1510 3090 1510 3091 1545 3091 1846 3091 1510 3092 1846 3092 1511 3092 1517 3093 2166 3093 1550 3093 1550 3094 2166 3094 1546 3094 1550 3095 1546 3095 1551 3095 1551 3096 1546 3096 2163 3096 1551 3097 2163 3097 1547 3097 1534 3098 2160 3098 5145 3098 5145 3099 2160 3099 2153 3099 5145 3100 2153 3100 1548 3100 1548 3101 2153 3101 1536 3101 5425 3102 2196 3102 1549 3102 1549 3103 2196 3103 2187 3103 1549 3104 2187 3104 1571 3104 4658 3105 1550 3105 1552 3105 1552 3106 1550 3106 1551 3106 1552 3107 1551 3107 2169 3107 2169 3108 1551 3108 1520 3108 1526 3109 4642 3109 1521 3109 1521 3110 4642 3110 4638 3110 1521 3111 4638 3111 1553 3111 5053 3112 4360 3112 1541 3112 1541 3113 4360 3113 4366 3113 1541 3114 4366 3114 4361 3114 4361 3115 4366 3115 4369 3115 2184 3116 2183 3116 1503 3116 1503 3117 2183 3117 1554 3117 1503 3118 1554 3118 1551 3118 1551 3119 1554 3119 2178 3119 1551 3120 2178 3120 2174 3120 2283 3121 1518 3121 1555 3121 1555 3122 1518 3122 1556 3122 1555 3123 1556 3123 6072 3123 1501 3124 5105 3124 1500 3124 1500 3125 5105 3125 1557 3125 1500 3126 1557 3126 5103 3126 4532 3127 4529 3127 4533 3127 4533 3128 4529 3128 1558 3128 4533 3129 1558 3129 4536 3129 4536 3130 1558 3130 1559 3130 4536 3131 1559 3131 1874 3131 1569 3132 2185 3132 1503 3132 1503 3133 2185 3133 1560 3133 1503 3134 1560 3134 2184 3134 4631 3135 1561 3135 4633 3135 4633 3136 1561 3136 2009 3136 4633 3137 2009 3137 2233 3137 2233 3138 2009 3138 2235 3138 5011 3139 5012 3139 5013 3139 5013 3140 5012 3140 5009 3140 5013 3141 5009 3141 1941 3141 1941 3142 5009 3142 1754 3142 1941 3143 1754 3143 1942 3143 1942 3144 1754 3144 1500 3144 1942 3145 1500 3145 1562 3145 1562 3146 1500 3146 5103 3146 1563 3147 1564 3147 4661 3147 4661 3148 1564 3148 1516 3148 4661 3149 1516 3149 1565 3149 1565 3150 1516 3150 1517 3150 1570 3151 2216 3151 2215 3151 1566 3152 5422 3152 1567 3152 1568 3153 2222 3153 8196 3153 8196 3154 2222 3154 2218 3154 8196 3155 2218 3155 1518 3155 1518 3156 2218 3156 2217 3156 1518 3157 2217 3157 1488 3157 1488 3158 2217 3158 2216 3158 1488 3159 2216 3159 1503 3159 1503 3160 2216 3160 1570 3160 1503 3161 1570 3161 1569 3161 2215 3162 2214 3162 1570 3162 1570 3163 2214 3163 2213 3163 1570 3164 2213 3164 2212 3164 2187 3165 1570 3165 1571 3165 1571 3166 1570 3166 2212 3166 1571 3167 2212 3167 1567 3167 1567 3168 2212 3168 2210 3168 1567 3169 2210 3169 1566 3169 1572 3170 8777 3170 1600 3170 6903 3171 8555 3171 6911 3171 6911 3172 8555 3172 6909 3172 6903 3173 6904 3173 8555 3173 8555 3174 6904 3174 1573 3174 8555 3175 1573 3175 1575 3175 1573 3176 6891 3176 1575 3176 1575 3177 6891 3177 6881 3177 1575 3178 6881 3178 1574 3178 1574 3179 6853 3179 1575 3179 1575 3180 6853 3180 6844 3180 1575 3181 6844 3181 1576 3181 1576 3182 6844 3182 6836 3182 1576 3183 6836 3183 6842 3183 6842 3184 6843 3184 1576 3184 1576 3185 6843 3185 6826 3185 1576 3186 6826 3186 8566 3186 8566 3187 6826 3187 1577 3187 8566 3188 1577 3188 1578 3188 1578 3189 1577 3189 6814 3189 1578 3190 6814 3190 1581 3190 1581 3191 6814 3191 6802 3191 1581 3192 6802 3192 6793 3192 6793 3193 1579 3193 1581 3193 1581 3194 1579 3194 6796 3194 1581 3195 6796 3195 1580 3195 1580 3196 6778 3196 1581 3196 1581 3197 6778 3197 1582 3197 1581 3198 1582 3198 8581 3198 1582 3199 1583 3199 8581 3199 8581 3200 1583 3200 6770 3200 8581 3201 6770 3201 1584 3201 1584 3202 6770 3202 6760 3202 1584 3203 6760 3203 8589 3203 8589 3204 6760 3204 6755 3204 8589 3205 6755 3205 1585 3205 1585 3206 6755 3206 1586 3206 1585 3207 1586 3207 1587 3207 1591 3208 8609 3208 6722 3208 6722 3209 8609 3209 1585 3209 6722 3210 1585 3210 6730 3210 6730 3211 1585 3211 1587 3211 1588 3212 1589 3212 6723 3212 6723 3213 1589 3213 1590 3213 6723 3214 1590 3214 1591 3214 1591 3215 1590 3215 6706 3215 1591 3216 6706 3216 6698 3216 6698 3217 6697 3217 1591 3217 1591 3218 6697 3218 1592 3218 1591 3219 1592 3219 6691 3219 6691 3220 6668 3220 1591 3220 1591 3221 6668 3221 6673 3221 1591 3222 6673 3222 8609 3222 8609 3223 6673 3223 1593 3223 8609 3224 1593 3224 8608 3224 8608 3225 1593 3225 1594 3225 8608 3226 1594 3226 1599 3226 8649 3227 8636 3227 6634 3227 5920 3228 8650 3228 8649 3228 8636 3229 1595 3229 6634 3229 6634 3230 1595 3230 8639 3230 6634 3231 8639 3231 6635 3231 6635 3232 8639 3232 1596 3232 6635 3233 1596 3233 6636 3233 6636 3234 1596 3234 8619 3234 6636 3235 8619 3235 1597 3235 1597 3236 8619 3236 8605 3236 1597 3237 8605 3237 6638 3237 6638 3238 8605 3238 1598 3238 6638 3239 1598 3239 1599 3239 1599 3240 1598 3240 8610 3240 1599 3241 8610 3241 8608 3241 1572 3242 1600 3242 8797 3242 8797 3243 1600 3243 6630 3243 8797 3244 6630 3244 8791 3244 8791 3245 6630 3245 1601 3245 8791 3246 1601 3246 1602 3246 1602 3247 1601 3247 1604 3247 1602 3248 1604 3248 1603 3248 1603 3249 1604 3249 6615 3249 1603 3250 6615 3250 8820 3250 8820 3251 6615 3251 1605 3251 8820 3252 1605 3252 1606 3252 1606 3253 1605 3253 1607 3253 1606 3254 1607 3254 8813 3254 8813 3255 1607 3255 1608 3255 8813 3256 1608 3256 1609 3256 1609 3257 1608 3257 1610 3257 1609 3258 1610 3258 1612 3258 1610 3259 1611 3259 1612 3259 1612 3260 1611 3260 6604 3260 1612 3261 6604 3261 6606 3261 6605 3262 6607 3262 1619 3262 1619 3263 6607 3263 1613 3263 1613 3264 1614 3264 1619 3264 1619 3265 1614 3265 1615 3265 1619 3266 1615 3266 6584 3266 6584 3267 1616 3267 1619 3267 1619 3268 1616 3268 6575 3268 1619 3269 6575 3269 6554 3269 6554 3270 6575 3270 1617 3270 6554 3271 1617 3271 6558 3271 6558 3272 1617 3272 6559 3272 1618 3273 1612 3273 1619 3273 1619 3274 1612 3274 6606 3274 1619 3275 6606 3275 6605 3275 1618 3276 1620 3276 1612 3276 1612 3277 1620 3277 1621 3277 1612 3278 1621 3278 8872 3278 8872 3279 1621 3279 1623 3279 8872 3280 1623 3280 1622 3280 1622 3281 1623 3281 1624 3281 1622 3282 1624 3282 1625 3282 1625 3283 1624 3283 1626 3283 1625 3284 1626 3284 1628 3284 1626 3285 6519 3285 1628 3285 1628 3286 6519 3286 6512 3286 1628 3287 6512 3287 6505 3287 6505 3288 1627 3288 1628 3288 1628 3289 1627 3289 6497 3289 1628 3290 6497 3290 1632 3290 1632 3291 6497 3291 1629 3291 1632 3292 1629 3292 6479 3292 1630 3293 1638 3293 8913 3293 6479 3294 6478 3294 1632 3294 1632 3295 6478 3295 1631 3295 1632 3296 1631 3296 8918 3296 8918 3297 1631 3297 1633 3297 8918 3298 1633 3298 1634 3298 1634 3299 1633 3299 6457 3299 1634 3300 6457 3300 8907 3300 8907 3301 6457 3301 1635 3301 8907 3302 1635 3302 6438 3302 6438 3303 1636 3303 8907 3303 8907 3304 1636 3304 1637 3304 8907 3305 1637 3305 8913 3305 8913 3306 1637 3306 6420 3306 8913 3307 6420 3307 1630 3307 1638 3308 6401 3308 8913 3308 8913 3309 6401 3309 6388 3309 8913 3310 6388 3310 2351 3310 2351 3311 6388 3311 1639 3311 2351 3312 1639 3312 6387 3312 6387 3313 6375 3313 2351 3313 2351 3314 6375 3314 1640 3314 2351 3315 1640 3315 2350 3315 8649 3316 6634 3316 5920 3316 5920 3317 6634 3317 6633 3317 5920 3318 6633 3318 1641 3318 1641 3319 6633 3319 1642 3319 1641 3320 1642 3320 1600 3320 1600 3321 1642 3321 1643 3321 1600 3322 1643 3322 6630 3322 2655 3323 1644 3323 1645 3323 1645 3324 1644 3324 1648 3324 1646 3325 2658 3325 1647 3325 1647 3326 2658 3326 1648 3326 1648 3327 1644 3327 1647 3327 1647 3328 1644 3328 2925 3328 1647 3329 2925 3329 1646 3329 1646 3330 2925 3330 1649 3330 1646 3331 1649 3331 2659 3331 2659 3332 1649 3332 2947 3332 2659 3333 2947 3333 2660 3333 2655 3334 5910 3334 5836 3334 5836 3335 2855 3335 2655 3335 2655 3336 2855 3336 1650 3336 2655 3337 1650 3337 1644 3337 1644 3338 1650 3338 1651 3338 1644 3339 1651 3339 2925 3339 8584 3340 5650 3340 1652 3340 1652 3341 5650 3341 5684 3341 1682 3342 968 3342 1683 3342 7682 3343 7607 3343 1675 3343 7676 3344 1653 3344 6163 3344 3764 3345 1654 3345 1472 3345 1676 3346 1486 3346 1677 3346 1655 3347 7617 3347 1657 3347 1655 3348 1657 3348 1656 3348 1656 3349 1657 3349 7616 3349 1656 3350 7616 3350 1658 3350 1658 3351 7616 3351 1659 3351 1658 3352 1659 3352 1660 3352 1660 3353 1659 3353 7619 3353 1660 3354 7619 3354 6110 3354 6110 3355 7619 3355 1661 3355 6110 3356 1661 3356 6109 3356 6109 3357 1661 3357 1662 3357 6109 3358 1662 3358 1663 3358 1663 3359 1662 3359 1664 3359 1663 3360 1664 3360 3743 3360 7678 3361 1665 3361 7630 3361 7630 3362 1665 3362 3764 3362 7630 3363 3764 3363 1664 3363 1664 3364 3764 3364 1472 3364 1664 3365 1472 3365 3743 3365 6163 3366 1653 3366 6164 3366 6164 3367 1653 3367 7673 3367 6164 3368 7673 3368 6165 3368 7676 3369 6163 3369 1666 3369 1666 3370 6163 3370 4735 3370 1666 3371 4735 3371 1667 3371 1667 3372 4735 3372 4745 3372 1667 3373 4745 3373 7678 3373 7678 3374 4745 3374 1668 3374 7678 3375 1668 3375 1665 3375 1670 3376 7607 3376 5407 3376 5407 3377 7607 3377 7690 3377 1669 3378 1675 3378 6029 3378 6029 3379 1675 3379 7607 3379 6029 3380 7607 3380 6030 3380 6030 3381 7607 3381 1670 3381 1672 3382 5986 3382 7700 3382 7700 3383 5986 3383 1671 3383 7700 3384 1671 3384 7695 3384 7695 3385 1671 3385 5407 3385 7695 3386 5407 3386 7691 3386 7691 3387 5407 3387 7690 3387 131 3388 1672 3388 1673 3388 1673 3389 1672 3389 7700 3389 1673 3390 7700 3390 4654 3390 4654 3391 7700 3391 4655 3391 1674 3392 6165 3392 1530 3392 1530 3393 6165 3393 7673 3393 1530 3394 7673 3394 1675 3394 1675 3395 7673 3395 7679 3395 1675 3396 7679 3396 7682 3396 1655 3397 1676 3397 7617 3397 7617 3398 1676 3398 1677 3398 7617 3399 1677 3399 7618 3399 7618 3400 1677 3400 1464 3400 7618 3401 1464 3401 7612 3401 3807 3402 1678 3402 1464 3402 1464 3403 1678 3403 7613 3403 1464 3404 7613 3404 7612 3404 1678 3405 5938 3405 7613 3405 7613 3406 5938 3406 5404 3406 7613 3407 5404 3407 1679 3407 1679 3408 5404 3408 5406 3408 1679 3409 5406 3409 7614 3409 7614 3410 5406 3410 1680 3410 1680 3411 5406 3411 1681 3411 1680 3412 1681 3412 1685 3412 1685 3413 1681 3413 5961 3413 1685 3414 5961 3414 1682 3414 1682 3415 1683 3415 1685 3415 1685 3416 1683 3416 1684 3416 1685 3417 1684 3417 7610 3417 4843 3418 1686 3418 8369 3418 8369 3419 1686 3419 6208 3419 8369 3420 6208 3420 6207 3420 6192 3421 1479 3421 1687 3421 1687 3422 1479 3422 8369 3422 1687 3423 8369 3423 1688 3423 1688 3424 8369 3424 6207 3424 1689 3425 1690 3425 8527 3425 8527 3426 1690 3426 4841 3426 8197 3427 1692 3427 1691 3427 1691 3428 1692 3428 4834 3428 1693 3429 7107 3429 1694 3429 1693 3430 1694 3430 8362 3430 8362 3431 1694 3431 7095 3431 8362 3432 7095 3432 7084 3432 7084 3433 7086 3433 8362 3433 8362 3434 7086 3434 7087 3434 8362 3435 7087 3435 7082 3435 1727 3436 7225 3436 1695 3436 1712 3437 8454 3437 1713 3437 6288 3438 1696 3438 1718 3438 1718 3439 1696 3439 1720 3439 1702 3440 1697 3440 1698 3440 1698 3441 1697 3441 9003 3441 1698 3442 9003 3442 1699 3442 1700 3443 1709 3443 1701 3443 1712 3444 9111 3444 8453 3444 8453 3445 9111 3445 1717 3445 8453 3446 1717 3446 1719 3446 1701 3447 9046 3447 1700 3447 1700 3448 9046 3448 1703 3448 1700 3449 1703 3449 1702 3449 1702 3450 1703 3450 9018 3450 1702 3451 9018 3451 1697 3451 9119 3452 1710 3452 7213 3452 7213 3453 1710 3453 1704 3453 1715 3454 9083 3454 1714 3454 1714 3455 9083 3455 1705 3455 1714 3456 1705 3456 6318 3456 6318 3457 1705 3457 1706 3457 6318 3458 1706 3458 1707 3458 1707 3459 1706 3459 1708 3459 1707 3460 1708 3460 1709 3460 1709 3461 1708 3461 9057 3461 1709 3462 9057 3462 1701 3462 1710 3463 9117 3463 1704 3463 1704 3464 9117 3464 9128 3464 1704 3465 9128 3465 1711 3465 1711 3466 9128 3466 9111 3466 1711 3467 9111 3467 7179 3467 7179 3468 9111 3468 1712 3468 7179 3469 1712 3469 7180 3469 7180 3470 1712 3470 1713 3470 1714 3471 6316 3471 1715 3471 1715 3472 6316 3472 1716 3472 1715 3473 1716 3473 1717 3473 1717 3474 1716 3474 1718 3474 1717 3475 1718 3475 1719 3475 1719 3476 1718 3476 1720 3476 9119 3477 7213 3477 1721 3477 1721 3478 7213 3478 7200 3478 1721 3479 7200 3479 9115 3479 9115 3480 7200 3480 1723 3480 9115 3481 1723 3481 1722 3481 1723 3482 1724 3482 1722 3482 1722 3483 1724 3483 1725 3483 1722 3484 1725 3484 1695 3484 1695 3485 1725 3485 1726 3485 1695 3486 1726 3486 1727 3486 8645 3487 1734 3487 1739 3487 6965 3488 6966 3488 1738 3488 1733 3489 8677 3489 8275 3489 1735 3490 1729 3490 1728 3490 1728 3491 1729 3491 1733 3491 1728 3492 1733 3492 1730 3492 1731 3493 8109 3493 8110 3493 8286 3494 4872 3494 1732 3494 1732 3495 4872 3495 1730 3495 1732 3496 1730 3496 8284 3496 8284 3497 1730 3497 1733 3497 8284 3498 1733 3498 8283 3498 8283 3499 1733 3499 8275 3499 8645 3500 8652 3500 1734 3500 1734 3501 8652 3501 8651 3501 1734 3502 8651 3502 1735 3502 1735 3503 8651 3503 8666 3503 1735 3504 8666 3504 1729 3504 1738 3505 6966 3505 8572 3505 8572 3506 6966 3506 1736 3506 8572 3507 1736 3507 1737 3507 1738 3508 8600 3508 6965 3508 6965 3509 8600 3509 8624 3509 6965 3510 8624 3510 1739 3510 1739 3511 8624 3511 1740 3511 1739 3512 1740 3512 8645 3512 1731 3513 8707 3513 8109 3513 8109 3514 8707 3514 8694 3514 8109 3515 8694 3515 8114 3515 8114 3516 8694 3516 1741 3516 8114 3517 1741 3517 1742 3517 1742 3518 1741 3518 1743 3518 1742 3519 1743 3519 1744 3519 1744 3520 1743 3520 2359 3520 1737 3521 1736 3521 8571 3521 8571 3522 1736 3522 6964 3522 8571 3523 6964 3523 1745 3523 1745 3524 6964 3524 1746 3524 1745 3525 1746 3525 8541 3525 1747 3526 8677 3526 8104 3526 8104 3527 8677 3527 8693 3527 8104 3528 8693 3528 1748 3528 1748 3529 8693 3529 1749 3529 1748 3530 1749 3530 8110 3530 8110 3531 1749 3531 1750 3531 8110 3532 1750 3532 1731 3532 1747 3533 8102 3533 8677 3533 8677 3534 8102 3534 1751 3534 8677 3535 1751 3535 8275 3535 8275 3536 1751 3536 8118 3536 8275 3537 8118 3537 1752 3537 1752 3538 8118 3538 1753 3538 1500 3539 1754 3539 8217 3539 8217 3540 1754 3540 1755 3540 8217 3541 1755 3541 4966 3541 4966 3542 4991 3542 8217 3542 8217 3543 4991 3543 1757 3543 8217 3544 1757 3544 1756 3544 1756 3545 1757 3545 1758 3545 4970 3546 8224 3546 4982 3546 4982 3547 8224 3547 1759 3547 4982 3548 1759 3548 5002 3548 1759 3549 8223 3549 5002 3549 5002 3550 8223 3550 1760 3550 5002 3551 1760 3551 1761 3551 1761 3552 1760 3552 1762 3552 1761 3553 1762 3553 4968 3553 1762 3554 8222 3554 4968 3554 4968 3555 8222 3555 8219 3555 4968 3556 8219 3556 1758 3556 1758 3557 8219 3557 1763 3557 1758 3558 1763 3558 1756 3558 1764 3559 8176 3559 1768 3559 8179 3560 5030 3560 8198 3560 8198 3561 5030 3561 1765 3561 1540 3562 1766 3562 1767 3562 1767 3563 1766 3563 8198 3563 1767 3564 8198 3564 5029 3564 5029 3565 8198 3565 1765 3565 1764 3566 1768 3566 8174 3566 8174 3567 1768 3567 1769 3567 8174 3568 1769 3568 1773 3568 8179 3569 1770 3569 5030 3569 5030 3570 1770 3570 8171 3570 5030 3571 8171 3571 5025 3571 5025 3572 8171 3572 1772 3572 5025 3573 1772 3573 1771 3573 1771 3574 1772 3574 1773 3574 1771 3575 1773 3575 1774 3575 1774 3576 1773 3576 1769 3576 1775 3577 1780 3577 7075 3577 7075 3578 1780 3578 7049 3578 4886 3579 7019 3579 1779 3579 1776 3580 4882 3580 1783 3580 1783 3581 4882 3581 4883 3581 1783 3582 4883 3582 7033 3582 7033 3583 4883 3583 1777 3583 7033 3584 1777 3584 1779 3584 1779 3585 1777 3585 1778 3585 1779 3586 1778 3586 4886 3586 7049 3587 1780 3587 1782 3587 1782 3588 1780 3588 1781 3588 1782 3589 1781 3589 1787 3589 1776 3590 1783 3590 1785 3590 1785 3591 1783 3591 1784 3591 1785 3592 1784 3592 1786 3592 1786 3593 1784 3593 7063 3593 1786 3594 7063 3594 1781 3594 1781 3595 7063 3595 7065 3595 1781 3596 7065 3596 1787 3596 1788 3597 5058 3597 1789 3597 1799 3598 1790 3598 5070 3598 5070 3599 1790 3599 1791 3599 5070 3600 1791 3600 5066 3600 5066 3601 1791 3601 1792 3601 5066 3602 1792 3602 5067 3602 5067 3603 1792 3603 1801 3603 1793 3604 1794 3604 1796 3604 1788 3605 1789 3605 1794 3605 1794 3606 1789 3606 1795 3606 1794 3607 1795 3607 1796 3607 5105 3608 1501 3608 1797 3608 1797 3609 1501 3609 1790 3609 1797 3610 1790 3610 1798 3610 1798 3611 1790 3611 1799 3611 1796 3612 5064 3612 1793 3612 1793 3613 5064 3613 5063 3613 1793 3614 5063 3614 1800 3614 1800 3615 5063 3615 5069 3615 1800 3616 5069 3616 1801 3616 1801 3617 5069 3617 1802 3617 1801 3618 1802 3618 5067 3618 1803 3619 5145 3619 1805 3619 1805 3620 5145 3620 5112 3620 1805 3621 5112 3621 1804 3621 1804 3622 5114 3622 1805 3622 1805 3623 5114 3623 5116 3623 1805 3624 5116 3624 1806 3624 1806 3625 5116 3625 1807 3625 1806 3626 1807 3626 7121 3626 7121 3627 1807 3627 1813 3627 5124 3628 5122 3628 7137 3628 7137 3629 5122 3629 5121 3629 7137 3630 5121 3630 1808 3630 7137 3631 7136 3631 5124 3631 5124 3632 7136 3632 1809 3632 5124 3633 1809 3633 1810 3633 1810 3634 1809 3634 1811 3634 1810 3635 1811 3635 5120 3635 5120 3636 1811 3636 5118 3636 5118 3637 1811 3637 1812 3637 5118 3638 1812 3638 1807 3638 1807 3639 1812 3639 7134 3639 1807 3640 7134 3640 1813 3640 8532 3641 1814 3641 1816 3641 1816 3642 1814 3642 5178 3642 1816 3643 5178 3643 5177 3643 1510 3644 1513 3644 1815 3644 1815 3645 1513 3645 1816 3645 1815 3646 1816 3646 5175 3646 5175 3647 1816 3647 5177 3647 1817 3648 1821 3648 8507 3648 8507 3649 1818 3649 1817 3649 1817 3650 1818 3650 8510 3650 1817 3651 8510 3651 1819 3651 1819 3652 8510 3652 8512 3652 1819 3653 8512 3653 5168 3653 5168 3654 8512 3654 8514 3654 5168 3655 8514 3655 5169 3655 8532 3656 8523 3656 1814 3656 1814 3657 8523 3657 1820 3657 1814 3658 1820 3658 1821 3658 1821 3659 1820 3659 8506 3659 1821 3660 8506 3660 8507 3660 1822 3661 1823 3661 8366 3661 8366 3662 1823 3662 1824 3662 1824 3663 5209 3663 8366 3663 8366 3664 5209 3664 5208 3664 8366 3665 5208 3665 1825 3665 1825 3666 5208 3666 1826 3666 1825 3667 1826 3667 1827 3667 1827 3668 1826 3668 8373 3668 8373 3669 1826 3669 1829 3669 8373 3670 1829 3670 1828 3670 8392 3671 1834 3671 8393 3671 8393 3672 1834 3672 8395 3672 1828 3673 1829 3673 1830 3673 1830 3674 1829 3674 5211 3674 1830 3675 5211 3675 8387 3675 8387 3676 5211 3676 1831 3676 8387 3677 1831 3677 8389 3677 8389 3678 1831 3678 5212 3678 8389 3679 5212 3679 1832 3679 1832 3680 5212 3680 5216 3680 1832 3681 5216 3681 8390 3681 8390 3682 5216 3682 1833 3682 1833 3683 5216 3683 5215 3683 1833 3684 5215 3684 8392 3684 8392 3685 5215 3685 5214 3685 8392 3686 5214 3686 1834 3686 1837 3687 6210 3687 1836 3687 1835 3688 1843 3688 1840 3688 1836 3689 6230 3689 1837 3689 1837 3690 6230 3690 1838 3690 1837 3691 1838 3691 5304 3691 5304 3692 1838 3692 1839 3692 5304 3693 1839 3693 5305 3693 5305 3694 1839 3694 1835 3694 5305 3695 1835 3695 5271 3695 5271 3696 1835 3696 1840 3696 6269 3697 1841 3697 6268 3697 6268 3698 1841 3698 5267 3698 6268 3699 5267 3699 1842 3699 1842 3700 5267 3700 5269 3700 1842 3701 5269 3701 1843 3701 1843 3702 5269 3702 1844 3702 1843 3703 1844 3703 1840 3703 1849 3704 1512 3704 1511 3704 1849 3705 1511 3705 1845 3705 1845 3706 1511 3706 1846 3706 1845 3707 1846 3707 5204 3707 1867 3708 1847 3708 1868 3708 5163 3709 8456 3709 1853 3709 1848 3710 1849 3710 1845 3710 5222 3711 1850 3711 1851 3711 1851 3712 1850 3712 1852 3712 1851 3713 1852 3713 5224 3713 5224 3714 1852 3714 5226 3714 5226 3715 1852 3715 1855 3715 5226 3716 1855 3716 5227 3716 5227 3717 1855 3717 1854 3717 5227 3718 1854 3718 5228 3718 5163 3719 1853 3719 5161 3719 8452 3720 5228 3720 1853 3720 1853 3721 5228 3721 1854 3721 1853 3722 1854 3722 5161 3722 5161 3723 1854 3723 1855 3723 5161 3724 1855 3724 1856 3724 1856 3725 1855 3725 1866 3725 1868 3726 1857 3726 1867 3726 1867 3727 1857 3727 1858 3727 1867 3728 1858 3728 1859 3728 1859 3729 1858 3729 5157 3729 1859 3730 5157 3730 1866 3730 1860 3731 5154 3731 1865 3731 1865 3732 5154 3732 1870 3732 5154 3733 1861 3733 1870 3733 1870 3734 1861 3734 1862 3734 1870 3735 1862 3735 1868 3735 1868 3736 1862 3736 1863 3736 1868 3737 1863 3737 1857 3737 5204 3738 1864 3738 1873 3738 1873 3739 1864 3739 1860 3739 1873 3740 1860 3740 1872 3740 1872 3741 1860 3741 1865 3741 1866 3742 1855 3742 1859 3742 1859 3743 1855 3743 1852 3743 1859 3744 1852 3744 1867 3744 1867 3745 1852 3745 1850 3745 1867 3746 1850 3746 1847 3746 1847 3747 1850 3747 5222 3747 1847 3748 5222 3748 1868 3748 1868 3749 5222 3749 1869 3749 1868 3750 1869 3750 1870 3750 1870 3751 1869 3751 5221 3751 1870 3752 5221 3752 1865 3752 1865 3753 5221 3753 1871 3753 1865 3754 1871 3754 1872 3754 1872 3755 1871 3755 1848 3755 1872 3756 1848 3756 1873 3756 1873 3757 1848 3757 1845 3757 1873 3758 1845 3758 5204 3758 1874 3759 1559 3759 4528 3759 4528 3760 1875 3760 1874 3760 1874 3761 1875 3761 5108 3761 1874 3762 5108 3762 1535 3762 1875 3763 4528 3763 1884 3763 5137 3764 1886 3764 1876 3764 7199 3765 1892 3765 4425 3765 4425 3766 1892 3766 4435 3766 4425 3767 4405 3767 7199 3767 7199 3768 4405 3768 4404 3768 7199 3769 4404 3769 4403 3769 4403 3770 1877 3770 7199 3770 7199 3771 1877 3771 4725 3771 7199 3772 4725 3772 3104 3772 3104 3773 4725 3773 4723 3773 3104 3774 4723 3774 1878 3774 4435 3775 1892 3775 4436 3775 4436 3776 1892 3776 1887 3776 4436 3777 1887 3777 1879 3777 1879 3778 1887 3778 4505 3778 1879 3779 4505 3779 4467 3779 1880 3780 1881 3780 1888 3780 1888 3781 1881 3781 1882 3781 1888 3782 1882 3782 1891 3782 1891 3783 1882 3783 1883 3783 5109 3784 5108 3784 1875 3784 5109 3785 1875 3785 5125 3785 5125 3786 1875 3786 5126 3786 5126 3787 1875 3787 1884 3787 5126 3788 1884 3788 5135 3788 5135 3789 1884 3789 1885 3789 5135 3790 1885 3790 1886 3790 1886 3791 1885 3791 4512 3791 1886 3792 4512 3792 1876 3792 1887 3793 5138 3793 1890 3793 1876 3794 1881 3794 5137 3794 5137 3795 1881 3795 1880 3795 5137 3796 1880 3796 1889 3796 1889 3797 1880 3797 1888 3797 1889 3798 1888 3798 1890 3798 1890 3799 1888 3799 1891 3799 1890 3800 1891 3800 1887 3800 1887 3801 1891 3801 1883 3801 1887 3802 1883 3802 4505 3802 5138 3803 1887 3803 5106 3803 5106 3804 1887 3804 1892 3804 5106 3805 1892 3805 1893 3805 1893 3806 1892 3806 7199 3806 1893 3807 7199 3807 7197 3807 1894 3808 1899 3808 1895 3808 1895 3809 1899 3809 1896 3809 1895 3810 1896 3810 1897 3810 1894 3811 1898 3811 1899 3811 1899 3812 1898 3812 1900 3812 1899 3813 1900 3813 4933 3813 1900 3814 1898 3814 1940 3814 1894 3815 1895 3815 1925 3815 1935 3816 4901 3816 4172 3816 4172 3817 4177 3817 1935 3817 1935 3818 4177 3818 4194 3818 1935 3819 4194 3819 4193 3819 4131 3820 1901 3820 1906 3820 1906 3821 1901 3821 1902 3821 1902 3822 4120 3822 1906 3822 1906 3823 4120 3823 1903 3823 1906 3824 1903 3824 1904 3824 1904 3825 1905 3825 1906 3825 1906 3826 1905 3826 1908 3826 1906 3827 1908 3827 1907 3827 1908 3828 4155 3828 1907 3828 1907 3829 4155 3829 1909 3829 1907 3830 1909 3830 4900 3830 4900 3831 1909 3831 4171 3831 4900 3832 4171 3832 4901 3832 4901 3833 4171 3833 4173 3833 4901 3834 4173 3834 4172 3834 4109 3835 4108 3835 1933 3835 1933 3836 4108 3836 1910 3836 1933 3837 1910 3837 1911 3837 1911 3838 1910 3838 4110 3838 1914 3839 1916 3839 1913 3839 1913 3840 1916 3840 4102 3840 1913 3841 4102 3841 1933 3841 1933 3842 4102 3842 4104 3842 1933 3843 4104 3843 4109 3843 1912 3844 3974 3844 1913 3844 1913 3845 3974 3845 3975 3845 1913 3846 3975 3846 1914 3846 1914 3847 3975 3847 1915 3847 1914 3848 1915 3848 1916 3848 1920 3849 1917 3849 1918 3849 1918 3850 1986 3850 1920 3850 1920 3851 1986 3851 1919 3851 1920 3852 1919 3852 3959 3852 3959 3853 3960 3853 1920 3853 1920 3854 3960 3854 3957 3854 1920 3855 3957 3855 1936 3855 1917 3856 1920 3856 1921 3856 1921 3857 1920 3857 1937 3857 1921 3858 1937 3858 1922 3858 1922 3859 1937 3859 1923 3859 1922 3860 1923 3860 4084 3860 4084 3861 1923 3861 1924 3861 1924 3862 1923 3862 1925 3862 1924 3863 1925 3863 4080 3863 4080 3864 1925 3864 1895 3864 4080 3865 1895 3865 1897 3865 4933 3866 1900 3866 1926 3866 1926 3867 1900 3867 1940 3867 1926 3868 1940 3868 4940 3868 4940 3869 1940 3869 1939 3869 1938 3870 4890 3870 1939 3870 1939 3871 4890 3871 4941 3871 1939 3872 4941 3872 4940 3872 1927 3873 4892 3873 1938 3873 1938 3874 4892 3874 1928 3874 1938 3875 1928 3875 4890 3875 4916 3876 1929 3876 1913 3876 1913 3877 1929 3877 4897 3877 1913 3878 4897 3878 1912 3878 1912 3879 4897 3879 1930 3879 1912 3880 1930 3880 1927 3880 1927 3881 1930 3881 4896 3881 1927 3882 4896 3882 4892 3882 4916 3883 1913 3883 1931 3883 1931 3884 1913 3884 1933 3884 1931 3885 1933 3885 1932 3885 1932 3886 1933 3886 1911 3886 1932 3887 1911 3887 1906 3887 1906 3888 1911 3888 4110 3888 1906 3889 4110 3889 4131 3889 4193 3890 1934 3890 1935 3890 1935 3891 1934 3891 6980 3891 1935 3892 6980 3892 6999 3892 3957 3893 3974 3893 1936 3893 1936 3894 3974 3894 1912 3894 1936 3895 1912 3895 1920 3895 1920 3896 1912 3896 1927 3896 1920 3897 1927 3897 1937 3897 1937 3898 1927 3898 1938 3898 1937 3899 1938 3899 1923 3899 1923 3900 1938 3900 1939 3900 1923 3901 1939 3901 1925 3901 1925 3902 1939 3902 1940 3902 1925 3903 1940 3903 1894 3903 1894 3904 1940 3904 1898 3904 5014 3905 1941 3905 1942 3905 5014 3906 1942 3906 1947 3906 1947 3907 1942 3907 1562 3907 1947 3908 1562 3908 5055 3908 1949 3909 4958 3909 1967 3909 1943 3910 5014 3910 1947 3910 1943 3911 1947 3911 4975 3911 1963 3912 1968 3912 1944 3912 1944 3913 1968 3913 4977 3913 1944 3914 4977 3914 1962 3914 1962 3915 4977 3915 1945 3915 1962 3916 1945 3916 1946 3916 1946 3917 1945 3917 4975 3917 1946 3918 4975 3918 1948 3918 1948 3919 4975 3919 1947 3919 1948 3920 1947 3920 5055 3920 4958 3921 1949 3921 4980 3921 4980 3922 1949 3922 1952 3922 4980 3923 1952 3923 1950 3923 1956 3924 1957 3924 1964 3924 1964 3925 1957 3925 1951 3925 1964 3926 1951 3926 1952 3926 1952 3927 1951 3927 4981 3927 1952 3928 4981 3928 1950 3928 1955 3929 8291 3929 8279 3929 1953 3930 1954 3930 1964 3930 1964 3931 1954 3931 1955 3931 1964 3932 1955 3932 1956 3932 1956 3933 1955 3933 8279 3933 1956 3934 8279 3934 1957 3934 1957 3935 8279 3935 1958 3935 1953 3936 1965 3936 1959 3936 1959 3937 1965 3937 1960 3937 1959 3938 1960 3938 5099 3938 5099 3939 1960 3939 1966 3939 5099 3940 1966 3940 1961 3940 5055 3941 5093 3941 1948 3941 1948 3942 5093 3942 5094 3942 1948 3943 5094 3943 1946 3943 1946 3944 5094 3944 5095 3944 1946 3945 5095 3945 1962 3945 1962 3946 5095 3946 5097 3946 1962 3947 5097 3947 1944 3947 1944 3948 5097 3948 1961 3948 1944 3949 1961 3949 1963 3949 1963 3950 1961 3950 1966 3950 1953 3951 1964 3951 1965 3951 1965 3952 1964 3952 1952 3952 1965 3953 1952 3953 1960 3953 1960 3954 1952 3954 1949 3954 1960 3955 1949 3955 1966 3955 1966 3956 1949 3956 1967 3956 1966 3957 1967 3957 1963 3957 1963 3958 1967 3958 4954 3958 1963 3959 4954 3959 1968 3959 2007 3960 3987 3960 3986 3960 4066 3961 2007 3961 1969 3961 1969 3962 2007 3962 3986 3962 1969 3963 3986 3963 1970 3963 1970 3964 3986 3964 1971 3964 1970 3965 1971 3965 4063 3965 4063 3966 1971 3966 3993 3966 4063 3967 3993 3967 1972 3967 1972 3968 3993 3968 3072 3968 1972 3969 3072 3969 4055 3969 2008 3970 1974 3970 1973 3970 1973 3971 1974 3971 1979 3971 1973 3972 1979 3972 1975 3972 1976 3973 4582 3973 4026 3973 4026 3974 4582 3974 1977 3974 4026 3975 1977 3975 1978 3975 1978 3976 1977 3976 1975 3976 1978 3977 1975 3977 4027 3977 4027 3978 1975 3978 1979 3978 4543 3979 1981 3979 1980 3979 1980 3980 1981 3980 1983 3980 1980 3981 1983 3981 3058 3981 1981 3982 1982 3982 1983 3982 1983 3983 1982 3983 4539 3983 1983 3984 4539 3984 1984 3984 1984 3985 4539 3985 4538 3985 1984 3986 4538 3986 1985 3986 1985 3987 4538 3987 4545 3987 1985 3988 4545 3988 6312 3988 3948 3989 3959 3989 1919 3989 3948 3990 1919 3990 1986 3990 1921 3991 1988 3991 1917 3991 1917 3992 1988 3992 3948 3992 1917 3993 3948 3993 1918 3993 1918 3994 3948 3994 1986 3994 1992 3995 1991 3995 2057 3995 2057 3996 1991 3996 4076 3996 1921 3997 1922 3997 1988 3997 1988 3998 1922 3998 1987 3998 1988 3999 1987 3999 1989 3999 1989 4000 1987 4000 4074 4000 1989 4001 4074 4001 1992 4001 1992 4002 4074 4002 1990 4002 1992 4003 1990 4003 1991 4003 2057 4004 3946 4004 1992 4004 1992 4005 3946 4005 1993 4005 1992 4006 1993 4006 1989 4006 1989 4007 1993 4007 3950 4007 1989 4008 3950 4008 1988 4008 1988 4009 3950 4009 3949 4009 1988 4010 3949 4010 3948 4010 1994 4011 2003 4011 4092 4011 4092 4012 2003 4012 2004 4012 4092 4013 2004 4013 1995 4013 1994 4014 4092 4014 3980 4014 3980 4015 4092 4015 1998 4015 3980 4016 1998 4016 1997 4016 1916 4017 1915 4017 1996 4017 1996 4018 1915 4018 1997 4018 1996 4019 1997 4019 4097 4019 4097 4020 1997 4020 1998 4020 4153 4021 1904 4021 1903 4021 4142 4022 2000 4022 1999 4022 1999 4023 2000 4023 2001 4023 1999 4024 2001 4024 4139 4024 4139 4025 2001 4025 4151 4025 4139 4026 4151 4026 4140 4026 4140 4027 4151 4027 4153 4027 4140 4028 4153 4028 4141 4028 4141 4029 4153 4029 1903 4029 2002 4030 2000 4030 6875 4030 6875 4031 2000 4031 4142 4031 2003 4032 6813 4032 2004 4032 2004 4033 6813 4033 2005 4033 2004 4034 2005 4034 1995 4034 4020 4035 6517 4035 3129 4035 3129 4036 6517 4036 2006 4036 3129 4037 2006 4037 3133 4037 4066 4038 6447 4038 2007 4038 2007 4039 6447 4039 3985 4039 2007 4040 3985 4040 3987 4040 6396 4041 1974 4041 4579 4041 4579 4042 1974 4042 2008 4042 1517 4043 7424 4043 1565 4043 1565 4044 7424 4044 7427 4044 1565 4045 7427 4045 4662 4045 7889 4046 4640 4046 7884 4046 7884 4047 4640 4047 2009 4047 7884 4048 2009 4048 2010 4048 2819 4049 2018 4049 2019 4049 2029 4050 2011 4050 510 4050 510 4051 2011 4051 2820 4051 510 4052 2820 4052 508 4052 497 4053 498 4053 2023 4053 500 4054 501 4054 2013 4054 2012 4055 2013 4055 2015 4055 2019 4056 521 4056 2819 4056 2819 4057 521 4057 522 4057 2819 4058 522 4058 2820 4058 2820 4059 522 4059 2014 4059 2820 4060 2014 4060 508 4060 2013 4061 3242 4061 500 4061 500 4062 3242 4062 9127 4062 500 4063 9127 4063 498 4063 498 4064 9127 4064 9101 4064 498 4065 9101 4065 2023 4065 513 4066 2015 4066 503 4066 503 4067 2015 4067 2013 4067 503 4068 2013 4068 2016 4068 2016 4069 2013 4069 501 4069 2021 4070 2022 4070 517 4070 517 4071 2022 4071 2017 4071 517 4072 2017 4072 515 4072 2018 4073 3285 4073 2019 4073 2019 4074 3285 4074 2020 4074 2019 4075 2020 4075 2021 4075 2021 4076 2020 4076 3230 4076 2021 4077 3230 4077 2022 4077 2023 4078 2024 4078 497 4078 497 4079 2024 4079 9104 4079 497 4080 9104 4080 2025 4080 2025 4081 9104 4081 2026 4081 2025 4082 2026 4082 2027 4082 2027 4083 2026 4083 9066 4083 2027 4084 9066 4084 2028 4084 2028 4085 9066 4085 2011 4085 2028 4086 2011 4086 2030 4086 2030 4087 2011 4087 2029 4087 2030 4088 2029 4088 507 4088 507 4089 2029 4089 513 4089 507 4090 513 4090 505 4090 505 4091 513 4091 503 4091 2017 4092 3233 4092 515 4092 515 4093 3233 4093 2031 4093 515 4094 2031 4094 2015 4094 2015 4095 2031 4095 3245 4095 2015 4096 3245 4096 2012 4096 2032 4097 2045 4097 525 4097 2032 4098 525 4098 8734 4098 2034 4099 532 4099 3341 4099 3341 4100 532 4100 2036 4100 525 4101 526 4101 8734 4101 8734 4102 526 4102 2033 4102 8734 4103 2033 4103 2034 4103 2034 4104 2033 4104 531 4104 2034 4105 531 4105 532 4105 2035 4106 535 4106 3324 4106 3324 4107 3323 4107 2035 4107 2035 4108 3323 4108 3343 4108 2035 4109 3343 4109 2036 4109 2036 4110 3343 4110 2037 4110 2036 4111 2037 4111 3341 4111 2048 4112 2049 4112 538 4112 538 4113 2049 4113 8716 4113 538 4114 8716 4114 2038 4114 2038 4115 8716 4115 2039 4115 2038 4116 2039 4116 2040 4116 2042 4117 524 4117 542 4117 542 4118 524 4118 2044 4118 2041 4119 3324 4119 542 4119 542 4120 3324 4120 535 4120 542 4121 535 4121 2042 4121 524 4122 2043 4122 2044 4122 2044 4123 2043 4123 2045 4123 2044 4124 2045 4124 539 4124 539 4125 2045 4125 2032 4125 539 4126 2032 4126 2046 4126 2046 4127 2032 4127 2047 4127 2046 4128 2047 4128 2048 4128 2048 4129 2047 4129 8718 4129 2048 4130 8718 4130 2049 4130 2040 4131 2050 4131 2038 4131 2038 4132 2050 4132 2051 4132 2038 4133 2051 4133 2052 4133 2052 4134 2051 4134 2053 4134 2052 4135 2053 4135 2054 4135 2054 4136 2053 4136 2055 4136 2054 4137 2055 4137 545 4137 545 4138 2055 4138 2056 4138 545 4139 2056 4139 543 4139 543 4140 2056 4140 3327 4140 543 4141 3327 4141 2041 4141 2041 4142 3327 4142 3326 4142 2041 4143 3326 4143 3324 4143 3942 4144 3946 4144 6762 4144 6762 4145 3946 4145 2057 4145 6762 4146 2057 4146 4076 4146 2067 4147 2069 4147 2058 4147 2067 4148 2058 4148 2060 4148 2058 4149 2059 4149 2060 4149 2060 4150 2059 4150 6518 4150 2060 4151 6518 4151 4022 4151 2069 4152 2070 4152 6498 4152 6498 4153 2070 4153 258 4153 6498 4154 258 4154 259 4154 259 4155 2061 4155 6498 4155 6498 4156 2061 4156 261 4156 6498 4157 261 4157 2065 4157 2062 4158 2067 4158 253 4158 253 4159 2067 4159 2063 4159 253 4160 2063 4160 2064 4160 2064 4161 2063 4161 2065 4161 2064 4162 2065 4162 2066 4162 2066 4163 2065 4163 261 4163 2062 4164 251 4164 2067 4164 2067 4165 251 4165 263 4165 2067 4166 263 4166 2069 4166 2069 4167 263 4167 2068 4167 2069 4168 2068 4168 2070 4168 6492 4169 3994 4169 6483 4169 6483 4170 3994 4170 6477 4170 6498 4171 2065 4171 6491 4171 6491 4172 2065 4172 4004 4172 6491 4173 4004 4173 6492 4173 6492 4174 4004 4174 2071 4174 6492 4175 2071 4175 3994 4175 6435 4176 2072 4176 2078 4176 2078 4177 2072 4177 6446 4177 2078 4178 6446 4178 2073 4178 2073 4179 6446 4179 6452 4179 2073 4180 6452 4180 4059 4180 6435 4181 2078 4181 332 4181 332 4182 2078 4182 335 4182 332 4183 328 4183 6435 4183 6435 4184 328 4184 2074 4184 6435 4185 2074 4185 6430 4185 6430 4186 2074 4186 325 4186 6430 4187 325 4187 326 4187 326 4188 323 4188 6430 4188 6430 4189 323 4189 345 4189 6430 4190 345 4190 2075 4190 345 4191 346 4191 2075 4191 2075 4192 346 4192 340 4192 2075 4193 340 4193 2076 4193 2076 4194 340 4194 2077 4194 2076 4195 2077 4195 2078 4195 2078 4196 2077 4196 338 4196 2078 4197 338 4197 335 4197 2079 4198 2080 4198 6419 4198 6419 4199 2080 4199 4023 4199 6419 4200 4023 4200 6412 4200 2075 4201 2081 4201 6430 4201 6430 4202 2081 4202 2079 4202 6430 4203 2079 4203 2082 4203 2082 4204 2079 4204 6419 4204 4584 4205 2099 4205 2085 4205 2083 4206 2084 4206 6366 4206 6366 4207 2084 4207 4584 4207 6366 4208 4584 4208 6365 4208 6365 4209 4584 4209 2085 4209 6384 4210 2086 4210 2087 4210 2087 4211 2086 4211 2083 4211 2087 4212 2083 4212 2088 4212 2088 4213 2083 4213 6366 4213 2101 4214 2089 4214 2105 4214 2092 4215 4584 4215 2090 4215 2090 4216 4584 4216 4571 4216 2090 4217 4571 4217 2091 4217 2091 4218 4571 4218 2102 4218 2092 4219 2093 4219 4584 4219 4584 4220 2093 4220 2094 4220 4584 4221 2094 4221 2099 4221 2089 4222 2095 4222 2105 4222 2105 4223 2095 4223 2096 4223 2105 4224 2096 4224 2102 4224 2102 4225 2096 4225 2097 4225 2102 4226 2097 4226 2091 4226 2094 4227 2098 4227 2099 4227 2099 4228 2098 4228 2100 4228 2099 4229 2100 4229 6353 4229 6353 4230 2100 4230 2101 4230 6353 4231 2101 4231 6363 4231 6363 4232 2101 4232 2105 4232 4568 4233 6339 4233 2107 4233 2102 4234 2103 4234 2105 4234 2105 4235 2103 4235 2104 4235 2105 4236 2104 4236 2107 4236 2107 4237 2104 4237 2106 4237 2107 4238 2106 4238 4568 4238 6591 4239 5348 4239 5344 4239 5344 4240 1495 4240 6591 4240 6591 4241 1495 4241 1505 4241 6591 4242 1505 4242 6593 4242 2108 4243 6593 4243 1504 4243 1504 4244 6593 4244 1505 4244 2110 4245 2108 4245 1504 4245 1504 4246 2109 4246 2110 4246 2110 4247 2109 4247 2111 4247 2110 4248 2111 4248 6573 4248 6561 4249 6573 4249 2112 4249 2112 4250 6573 4250 2111 4250 6562 4251 6561 4251 2112 4251 6562 4252 2112 4252 2113 4252 2112 4253 2114 4253 2113 4253 2113 4254 2114 4254 2115 4254 2113 4255 2115 4255 6565 4255 6565 4256 2115 4256 2116 4256 2116 4257 2115 4257 2117 4257 2116 4258 2117 4258 2124 4258 6543 4259 6544 4259 4597 4259 4597 4260 6544 4260 6545 4260 4597 4261 6545 4261 2118 4261 6549 4262 2119 4262 6545 4262 6545 4263 2119 4263 4620 4263 6545 4264 4620 4264 2118 4264 6549 4265 2121 4265 2119 4265 2119 4266 2121 4266 1466 4266 2119 4267 1466 4267 1477 4267 2124 4268 2120 4268 2121 4268 2121 4269 2120 4269 407 4269 2121 4270 407 4270 409 4270 411 4271 1466 4271 2122 4271 2122 4272 1466 4272 2121 4272 2122 4273 2121 4273 410 4273 410 4274 2121 4274 409 4274 417 4275 2117 4275 415 4275 415 4276 2117 4276 1466 4276 415 4277 1466 4277 412 4277 412 4278 1466 4278 411 4278 417 4279 2123 4279 2117 4279 2117 4280 2123 4280 420 4280 2117 4281 420 4281 2124 4281 2124 4282 420 4282 405 4282 2124 4283 405 4283 2120 4283 7253 4284 4375 4284 2125 4284 2125 4285 4375 4285 2126 4285 7264 4286 2125 4286 2126 4286 2126 4287 4717 4287 7264 4287 7264 4288 4717 4288 4718 4288 7264 4289 4718 4289 2127 4289 2127 4290 4718 4290 4719 4290 2127 4291 4719 4291 4700 4291 2127 4292 4700 4292 2128 4292 2128 4293 4700 4293 2134 4293 2128 4294 2134 4294 2129 4294 2136 4295 2139 4295 4431 4295 4431 4296 2139 4296 2130 4296 4431 4297 2130 4297 4414 4297 4414 4298 2130 4298 2132 4298 4414 4299 2132 4299 2131 4299 2131 4300 2132 4300 2133 4300 2129 4301 2134 4301 2133 4301 2133 4302 2134 4302 2135 4302 2133 4303 2135 4303 2131 4303 4432 4304 2143 4304 4434 4304 4434 4305 2143 4305 506 4305 4434 4306 506 4306 2136 4306 2136 4307 506 4307 504 4307 504 4308 2137 4308 2136 4308 2136 4309 2137 4309 2138 4309 2136 4310 2138 4310 2139 4310 2138 4311 502 4311 2139 4311 2139 4312 502 4312 499 4312 2139 4313 499 4313 7283 4313 7283 4314 499 4314 2140 4314 7283 4315 2140 4315 7284 4315 7284 4316 2140 4316 7287 4316 7287 4317 2140 4317 496 4317 7287 4318 496 4318 7303 4318 496 4319 495 4319 7303 4319 7303 4320 495 4320 2141 4320 7303 4321 2141 4321 4432 4321 4432 4322 2141 4322 2142 4322 4432 4323 2142 4323 2143 4323 2144 4324 7303 4324 4432 4324 4447 4325 2145 4325 2146 4325 4447 4326 2146 4326 4448 4326 2146 4327 2147 4327 4448 4327 4448 4328 2147 4328 2148 4328 4448 4329 2148 4329 4441 4329 4441 4330 2148 4330 4432 4330 4432 4331 2148 4331 7305 4331 4432 4332 7305 4332 2144 4332 4496 4333 4480 4333 2149 4333 4476 4334 4495 4334 2156 4334 2149 4335 4480 4335 2150 4335 2150 4336 4480 4336 2156 4336 2156 4337 4480 4337 4481 4337 2156 4338 4481 4338 4476 4338 4496 4339 2149 4339 1101 4339 1101 4340 2149 4340 7357 4340 1101 4341 7357 4341 2151 4341 4536 4342 2153 4342 4510 4342 4510 4343 2153 4343 2155 4343 4510 4344 2155 4344 2152 4344 511 4345 2158 4345 512 4345 512 4346 2158 4346 2156 4346 512 4347 2156 4347 2157 4347 511 4348 509 4348 2158 4348 2158 4349 509 4349 523 4349 2158 4350 523 4350 2153 4350 2153 4351 523 4351 2154 4351 2153 4352 2154 4352 2155 4352 520 4353 519 4353 4495 4353 519 4354 518 4354 4495 4354 4495 4355 518 4355 516 4355 4495 4356 516 4356 2156 4356 2156 4357 516 4357 514 4357 2156 4358 514 4358 2157 4358 4495 4359 4522 4359 520 4359 520 4360 4522 4360 4515 4360 520 4361 4515 4361 2155 4361 2155 4362 4515 4362 4514 4362 2155 4363 4514 4363 2152 4363 2159 4364 7382 4364 2153 4364 2153 4365 7382 4365 7381 4365 2153 4366 7381 4366 2158 4366 2153 4367 2160 4367 2159 4367 2159 4368 2160 4368 1534 4368 2159 4369 1534 4369 2161 4369 1547 4370 7385 4370 1534 4370 1534 4371 7385 4371 7383 4371 1534 4372 7383 4372 2161 4372 7385 4373 1547 4373 2162 4373 2162 4374 1547 4374 2163 4374 2164 4375 2162 4375 2163 4375 2163 4376 1546 4376 2164 4376 2164 4377 1546 4377 2166 4377 2164 4378 2166 4378 2165 4378 2165 4379 2166 4379 2167 4379 2167 4380 2166 4380 1516 4380 7435 4381 2169 4381 2168 4381 2168 4382 2169 4382 1520 4382 2168 4383 1520 4383 2170 4383 2170 4384 1520 4384 2171 4384 2170 4385 2171 4385 7478 4385 7478 4386 2171 4386 7475 4386 7475 4387 2171 4387 2172 4387 7475 4388 2172 4388 2173 4388 7493 4389 2173 4389 1519 4389 1519 4390 2173 4390 2172 4390 7493 4391 1519 4391 7502 4391 7502 4392 1519 4392 2174 4392 7502 4393 2174 4393 2175 4393 2175 4394 2174 4394 2178 4394 2175 4395 2178 4395 2176 4395 2176 4396 2178 4396 2177 4396 2177 4397 2178 4397 1554 4397 2177 4398 1554 4398 2181 4398 2183 4399 1124 4399 1554 4399 1554 4400 1124 4400 1104 4400 1554 4401 1104 4401 1115 4401 1115 4402 2179 4402 1554 4402 1554 4403 2179 4403 1112 4403 1554 4404 1112 4404 2181 4404 2181 4405 1112 4405 2180 4405 2182 4406 7528 4406 1107 4406 1107 4407 7528 4407 2181 4407 1107 4408 2181 4408 1108 4408 1108 4409 2181 4409 2180 4409 2182 4410 1119 4410 7528 4410 7528 4411 1119 4411 1121 4411 7528 4412 1121 4412 2183 4412 2183 4413 1121 4413 1122 4413 2183 4414 1122 4414 1124 4414 7527 4415 7528 4415 2183 4415 7527 4416 2183 4416 7526 4416 2183 4417 2184 4417 7526 4417 7526 4418 2184 4418 1560 4418 7526 4419 1560 4419 7531 4419 2185 4420 2186 4420 1560 4420 1560 4421 2186 4421 7537 4421 1560 4422 7537 4422 7531 4422 2186 4423 2185 4423 7548 4423 7548 4424 2185 4424 1569 4424 7542 4425 7548 4425 1569 4425 1569 4426 1570 4426 7542 4426 7542 4427 1570 4427 2187 4427 7542 4428 2187 4428 7550 4428 7550 4429 2187 4429 7549 4429 7549 4430 2187 4430 2196 4430 2192 4431 2189 4431 2188 4431 2188 4432 2189 4432 1148 4432 2188 4433 1148 4433 1149 4433 2193 4434 2190 4434 7568 4434 7568 4435 2190 4435 2191 4435 7568 4436 2191 4436 2192 4436 2192 4437 2191 4437 5414 4437 2192 4438 5414 4438 2189 4438 2196 4439 5425 4439 6005 4439 7568 4440 7567 4440 2193 4440 2193 4441 7567 4441 2194 4441 2193 4442 2194 4442 6007 4442 6007 4443 2194 4443 2195 4443 6007 4444 2195 4444 6008 4444 6008 4445 2195 4445 7565 4445 6008 4446 7565 4446 6005 4446 6005 4447 7565 4447 7549 4447 6005 4448 7549 4448 2196 4448 8064 4449 4672 4449 2197 4449 2197 4450 4672 4450 2198 4450 1566 4451 2210 4451 2199 4451 2199 4452 2210 4452 2200 4452 2199 4453 2200 4453 2202 4453 2200 4454 2201 4454 2202 4454 2202 4455 2201 4455 7751 4455 2202 4456 7751 4456 5956 4456 5956 4457 7751 4457 2203 4457 2205 4458 5955 4458 2203 4458 2203 4459 5955 4459 5959 4459 2203 4460 5959 4460 5956 4460 2203 4461 2204 4461 2205 4461 2205 4462 2204 4462 2207 4462 2205 4463 2207 4463 2206 4463 2206 4464 2207 4464 2208 4464 2206 4465 2208 4465 2209 4465 2209 4466 2208 4466 1151 4466 2200 4467 2210 4467 7765 4467 7765 4468 2210 4468 2212 4468 2211 4469 7765 4469 2212 4469 2212 4470 2213 4470 2211 4470 2211 4471 2213 4471 2214 4471 2211 4472 2214 4472 7771 4472 7771 4473 2214 4473 7772 4473 7772 4474 2214 4474 2215 4474 7785 4475 7772 4475 2215 4475 7785 4476 2215 4476 7786 4476 2215 4477 2216 4477 7786 4477 7786 4478 2216 4478 2217 4478 7786 4479 2217 4479 7788 4479 7788 4480 2217 4480 7789 4480 7789 4481 2217 4481 2218 4481 7789 4482 2218 4482 2219 4482 2222 4483 1129 4483 2218 4483 2218 4484 1129 4484 1139 4484 2218 4485 1139 4485 1140 4485 1140 4486 1142 4486 2218 4486 2218 4487 1142 4487 1143 4487 2218 4488 1143 4488 2219 4488 1143 4489 2220 4489 2219 4489 2219 4490 2220 4490 2221 4490 2219 4491 2221 4491 2223 4491 2223 4492 2221 4492 1136 4492 2223 4493 1136 4493 1135 4493 1135 4494 1130 4494 2223 4494 2223 4495 1130 4495 1131 4495 2223 4496 1131 4496 2222 4496 2222 4497 1131 4497 1132 4497 2222 4498 1132 4498 1129 4498 2223 4499 2222 4499 2224 4499 2224 4500 2222 4500 1568 4500 2224 4501 1568 4501 2225 4501 2225 4502 1568 4502 2226 4502 2225 4503 2226 4503 7813 4503 7813 4504 2226 4504 2227 4504 2227 4505 2226 4505 1523 4505 2227 4506 1523 4506 7802 4506 2229 4507 2228 4507 1523 4507 1523 4508 2228 4508 7802 4508 2228 4509 2229 4509 7831 4509 7831 4510 2229 4510 2231 4510 7831 4511 2231 4511 2230 4511 2230 4512 2231 4512 7833 4512 7833 4513 2231 4513 1522 4513 7833 4514 1522 4514 2232 4514 2232 4515 1522 4515 7840 4515 7840 4516 1522 4516 4635 4516 7891 4517 2233 4517 7917 4517 7917 4518 2233 4518 2235 4518 2234 4519 1526 4519 2237 4519 7917 4520 2235 4520 2236 4520 2236 4521 2235 4521 2234 4521 2236 4522 2234 4522 7922 4522 7922 4523 2234 4523 2237 4523 2237 4524 1526 4524 7939 4524 7939 4525 1526 4525 2238 4525 7934 4526 7935 4526 2238 4526 2238 4527 7935 4527 7938 4527 2238 4528 7938 4528 7939 4528 1524 4529 2242 4529 2239 4529 2238 4530 1525 4530 7934 4530 7934 4531 1525 4531 1524 4531 7934 4532 1524 4532 7933 4532 7933 4533 1524 4533 2239 4533 2239 4534 2242 4534 529 4534 529 4535 2242 4535 530 4535 529 4536 528 4536 2239 4536 2239 4537 528 4537 527 4537 2239 4538 527 4538 2248 4538 2248 4539 527 4539 2240 4539 2248 4540 2240 4540 2241 4540 1541 4541 4363 4541 2242 4541 2242 4542 4363 4542 2245 4542 2242 4543 2245 4543 530 4543 2249 4544 534 4544 2243 4544 2243 4545 534 4545 533 4545 2243 4546 533 4546 2244 4546 2244 4547 533 4547 2245 4547 2244 4548 2245 4548 4344 4548 4344 4549 2245 4549 4363 4549 2241 4550 2246 4550 2248 4550 2248 4551 2246 4551 2247 4551 2248 4552 2247 4552 2249 4552 2249 4553 2247 4553 536 4553 2249 4554 536 4554 534 4554 4310 4555 4299 4555 2250 4555 2255 4556 2251 4556 2256 4556 2256 4557 2251 4557 4310 4557 2256 4558 4310 4558 2252 4558 2252 4559 4310 4559 2250 4559 2249 4560 2253 4560 2248 4560 2248 4561 2253 4561 2255 4561 2248 4562 2255 4562 2254 4562 2254 4563 2255 4563 2256 4563 4271 4564 2264 4564 8013 4564 4281 4565 4279 4565 2257 4565 2257 4566 4279 4566 4271 4566 2257 4567 4271 4567 8015 4567 8015 4568 4271 4568 8013 4568 1095 4569 4288 4569 8012 4569 8012 4570 4288 4570 4281 4570 8012 4571 4281 4571 2258 4571 2258 4572 4281 4572 2257 4572 546 4573 4253 4573 2268 4573 546 4574 544 4574 4253 4574 4253 4575 544 4575 2259 4575 4253 4576 2259 4576 2260 4576 2260 4577 2259 4577 2261 4577 2260 4578 2261 4578 4271 4578 4271 4579 2261 4579 2262 4579 2262 4580 541 4580 4271 4580 4271 4581 541 4581 540 4581 4271 4582 540 4582 2264 4582 540 4583 2263 4583 2264 4583 2264 4584 2263 4584 2265 4584 2264 4585 2265 4585 8025 4585 8025 4586 2265 4586 2266 4586 8025 4587 2266 4587 2267 4587 2267 4588 2266 4588 8029 4588 8029 4589 2266 4589 537 4589 8029 4590 537 4590 2268 4590 2268 4591 537 4591 2269 4591 2268 4592 2269 4592 546 4592 4672 4593 8064 4593 4671 4593 4671 4594 8064 4594 2271 4594 4671 4595 2271 4595 2270 4595 2270 4596 2271 4596 2272 4596 2272 4597 2271 4597 2279 4597 2272 4598 2279 4598 4688 4598 4246 4599 2273 4599 2276 4599 2273 4600 4246 4600 2274 4600 2274 4601 4246 4601 2278 4601 2274 4602 2278 4602 8051 4602 2268 4603 4253 4603 2275 4603 2275 4604 4253 4604 4255 4604 2275 4605 4255 4605 2276 4605 2276 4606 4255 4606 2277 4606 2276 4607 2277 4607 4246 4607 4688 4608 2279 4608 2278 4608 2278 4609 2279 4609 8055 4609 2278 4610 8055 4610 8051 4610 6703 4611 6721 4611 2280 4611 2280 4612 6721 4612 2328 4612 2281 4613 6703 4613 2280 4613 2280 4614 2282 4614 2281 4614 2281 4615 2282 4615 2283 4615 2281 4616 2283 4616 2284 4616 2285 4617 2284 4617 1555 4617 1555 4618 2284 4618 2283 4618 6690 4619 2285 4619 1555 4619 1555 4620 1527 4620 6690 4620 6690 4621 1527 4621 5369 4621 6690 4622 5369 4622 5370 4622 6942 4623 4185 4623 2292 4623 2292 4624 4185 4624 2286 4624 2292 4625 2286 4625 4184 4625 2287 4626 4202 4626 6942 4626 6942 4627 4202 4627 4201 4627 6942 4628 4201 4628 4185 4628 6917 4629 6932 4629 359 4629 359 4630 6932 4630 360 4630 359 4631 2288 4631 6917 4631 6917 4632 2288 4632 2289 4632 6917 4633 2289 4633 4167 4633 4184 4634 2296 4634 2290 4634 4184 4635 2290 4635 2292 4635 2290 4636 2291 4636 2292 4636 2292 4637 2291 4637 363 4637 2292 4638 363 4638 2293 4638 2293 4639 363 4639 360 4639 2293 4640 360 4640 2294 4640 2294 4641 360 4641 6932 4641 2289 4642 354 4642 4167 4642 4167 4643 354 4643 353 4643 4167 4644 353 4644 4168 4644 4168 4645 353 4645 352 4645 4168 4646 352 4646 4184 4646 4184 4647 352 4647 2295 4647 4184 4648 2295 4648 2296 4648 6915 4649 6917 4649 4167 4649 6913 4650 4159 4650 4145 4650 4145 4651 4159 4651 4158 4651 4145 4652 4158 4652 4157 4652 6913 4653 6912 4653 4159 4653 4159 4654 6912 4654 6922 4654 4159 4655 6922 4655 2297 4655 2297 4656 6922 4656 4167 4656 4167 4657 6922 4657 6921 4657 4167 4658 6921 4658 6915 4658 4133 4659 2301 4659 6851 4659 4133 4660 6851 4660 4134 4660 4134 4661 6851 4661 2298 4661 4134 4662 2298 4662 6859 4662 6887 4663 2299 4663 6859 4663 6859 4664 2299 4664 4117 4664 6859 4665 4117 4665 4134 4665 384 4666 6850 4666 2300 4666 2300 4667 6850 4667 6851 4667 2300 4668 6851 4668 386 4668 384 4669 380 4669 6850 4669 6850 4670 380 4670 2304 4670 6850 4671 2304 4671 4098 4671 369 4672 2301 4672 2302 4672 2302 4673 2301 4673 4114 4673 2302 4674 4114 4674 2303 4674 2303 4675 4114 4675 4098 4675 2303 4676 4098 4676 375 4676 375 4677 4098 4677 2304 4677 369 4678 368 4678 2301 4678 2301 4679 368 4679 2305 4679 2301 4680 2305 4680 6851 4680 6851 4681 2305 4681 2306 4681 6851 4682 2306 4682 386 4682 6832 4683 6833 4683 4093 4683 4093 4684 6833 4684 2307 4684 2307 4685 6833 4685 4098 4685 4098 4686 6833 4686 6834 4686 4098 4687 6834 4687 6850 4687 2311 4688 2308 4688 2309 4688 2315 4689 2319 4689 2308 4689 2308 4690 2319 4690 2310 4690 2308 4691 2310 4691 2309 4691 2311 4692 2309 4692 3965 4692 3965 4693 2309 4693 2312 4693 3965 4694 2312 4694 2313 4694 270 4695 2324 4695 271 4695 271 4696 2324 4696 2319 4696 271 4697 2319 4697 2314 4697 270 4698 268 4698 2324 4698 2324 4699 268 4699 266 4699 2324 4700 266 4700 2317 4700 278 4701 2315 4701 2316 4701 2316 4702 2315 4702 3961 4702 2316 4703 3961 4703 281 4703 281 4704 3961 4704 2317 4704 281 4705 2317 4705 280 4705 280 4706 2317 4706 266 4706 278 4707 2318 4707 2315 4707 2315 4708 2318 4708 275 4708 2315 4709 275 4709 2319 4709 2319 4710 275 4710 2320 4710 2319 4711 2320 4711 2314 4711 2321 4712 6775 4712 2322 4712 2322 4713 6775 4713 3951 4713 3951 4714 6775 4714 2317 4714 2317 4715 6775 4715 2323 4715 2317 4716 2323 4716 2324 4716 4077 4717 2326 4717 6737 4717 1491 4718 2334 4718 2325 4718 2325 4719 2334 4719 6735 4719 2325 4720 6735 4720 2326 4720 2326 4721 6735 4721 6736 4721 2326 4722 6736 4722 6737 4722 4077 4723 6737 4723 4069 4723 4069 4724 6737 4724 6738 4724 4069 4725 6738 4725 2327 4725 6710 4726 2333 4726 1497 4726 6710 4727 1497 4727 6708 4727 1497 4728 1496 4728 6708 4728 6708 4729 1496 4729 1529 4729 6708 4730 1529 4730 6711 4730 2328 4731 6721 4731 1529 4731 1529 4732 6721 4732 6712 4732 1529 4733 6712 4733 6711 4733 2329 4734 2333 4734 2330 4734 2330 4735 2333 4735 6735 4735 2330 4736 6735 4736 2331 4736 394 4737 1497 4737 2332 4737 2332 4738 1497 4738 2333 4738 2332 4739 2333 4739 392 4739 392 4740 2333 4740 2329 4740 399 4741 2334 4741 398 4741 398 4742 2334 4742 1497 4742 398 4743 1497 4743 396 4743 396 4744 1497 4744 394 4744 399 4745 401 4745 2334 4745 2334 4746 401 4746 403 4746 2334 4747 403 4747 6735 4747 6735 4748 403 4748 2335 4748 6735 4749 2335 4749 2331 4749 6961 4750 3119 4750 2336 4750 2336 4751 3119 4751 3118 4751 2336 4752 3118 4752 6947 4752 3109 4753 2337 4753 3110 4753 3110 4754 2337 4754 4215 4754 4371 4755 7224 4755 3106 4755 3106 4756 7224 4756 7202 4756 3102 4757 2338 4757 2341 4757 2341 4758 2338 4758 4628 4758 2341 4759 4628 4759 2339 4759 2340 4760 3063 4760 1487 4760 1487 4761 3063 4761 3062 4761 1487 4762 3062 4762 2341 4762 2341 4763 3062 4763 3061 4763 2341 4764 3061 4764 3102 4764 5020 4765 3033 4765 5053 4765 5053 4766 3033 4766 4364 4766 5053 4767 4364 4767 4360 4767 2342 4768 7265 4768 2343 4768 2343 4769 7265 4769 7267 4769 7267 4770 7273 4770 2343 4770 2343 4771 7273 4771 7272 4771 2343 4772 7272 4772 9090 4772 1695 4773 7225 4773 2343 4773 2343 4774 7225 4774 7236 4774 2343 4775 7236 4775 7243 4775 7243 4776 7245 4776 2343 4776 2343 4777 7245 4777 7244 4777 2343 4778 7244 4778 2342 4778 2342 4779 7244 4779 2344 4779 2342 4780 2344 4780 7260 4780 9091 4781 2345 4781 7299 4781 1198 4782 2347 4782 2346 4782 2346 4783 2347 4783 9091 4783 2346 4784 9091 4784 2348 4784 2348 4785 9091 4785 7299 4785 7272 4786 7292 4786 9090 4786 9090 4787 7292 4787 2349 4787 9090 4788 2349 4788 9091 4788 9091 4789 2349 4789 7295 4789 9091 4790 7295 4790 2345 4790 2350 4791 2352 4791 2351 4791 2351 4792 2352 4792 6352 4792 2351 4793 6352 4793 8976 4793 6352 4794 2353 4794 8976 4794 8976 4795 2353 4795 6358 4795 8976 4796 6358 4796 8970 4796 8970 4797 6358 4797 2354 4797 8970 4798 2354 4798 2355 4798 2355 4799 2354 4799 6359 4799 2355 4800 6359 4800 6344 4800 6344 4801 2356 4801 2355 4801 2355 4802 2356 4802 2357 4802 2355 4803 2357 4803 1699 4803 1699 4804 2357 4804 6340 4804 1699 4805 6340 4805 1698 4805 2365 4806 8071 4806 2360 4806 2358 4807 8060 4807 2364 4807 2359 4808 1743 4808 8082 4808 8082 4809 1743 4809 2360 4809 8082 4810 2360 4810 2361 4810 2361 4811 2360 4811 8071 4811 2362 4812 2367 4812 2363 4812 8045 4813 8044 4813 2363 4813 2363 4814 8044 4814 8038 4814 2363 4815 8038 4815 2362 4815 2364 4816 2365 4816 2358 4816 2358 4817 2365 4817 2360 4817 2358 4818 2360 4818 2367 4818 2367 4819 2360 4819 2366 4819 2367 4820 2366 4820 2363 4820 8728 4821 8729 4821 7970 4821 7970 4822 8005 4822 8728 4822 8728 4823 8005 4823 8018 4823 8728 4824 8018 4824 8017 4824 8017 4825 8024 4825 8728 4825 8728 4826 8024 4826 2368 4826 8728 4827 2368 4827 8727 4827 8727 4828 2368 4828 2369 4828 8727 4829 2369 4829 2363 4829 2363 4830 2369 4830 2370 4830 2363 4831 2370 4831 8045 4831 6925 4832 6909 4832 8555 4832 8541 4833 1746 4833 2371 4833 8541 4834 2371 4834 2373 4834 2373 4835 2371 4835 6951 4835 2373 4836 6951 4836 2372 4836 2372 4837 2374 4837 2373 4837 2373 4838 2374 4838 6927 4838 2373 4839 6927 4839 2375 4839 6927 4840 6937 4840 2375 4840 2375 4841 6937 4841 2376 4841 2375 4842 2376 4842 2377 4842 2377 4843 2376 4843 2378 4843 2377 4844 2378 4844 8555 4844 8555 4845 2378 4845 2379 4845 8555 4846 2379 4846 6925 4846 3630 4847 8630 4847 2380 4847 2380 4848 8630 4848 2383 4848 2388 4849 3599 4849 2382 4849 2382 4850 3599 4850 2381 4850 2382 4851 2381 4851 2383 4851 2383 4852 2381 4852 3607 4852 2383 4853 3607 4853 2380 4853 2387 4854 2384 4854 2385 4854 2385 4855 2384 4855 8691 4855 2385 4856 8691 4856 2386 4856 2387 4857 2385 4857 2382 4857 2382 4858 2385 4858 3591 4858 2382 4859 3591 4859 2388 4859 2386 4860 2389 4860 2385 4860 2385 4861 2389 4861 2390 4861 2385 4862 2390 4862 9231 4862 2391 4863 2392 4863 3572 4863 8743 4864 2393 4864 8769 4864 3572 4865 3669 4865 2391 4865 2391 4866 3669 4866 3662 4866 2391 4867 3662 4867 2394 4867 2394 4868 3662 4868 3664 4868 2394 4869 3664 4869 3658 4869 9283 4870 9275 4870 2396 4870 2396 4871 9275 4871 9276 4871 2396 4872 9276 4872 2395 4872 2395 4873 8743 4873 2396 4873 2396 4874 8743 4874 8769 4874 2396 4875 8769 4875 2397 4875 2397 4876 8769 4876 2394 4876 2397 4877 2394 4877 3644 4877 3644 4878 2394 4878 3658 4878 3570 4879 2398 4879 9227 4879 3640 4880 3564 4880 2399 4880 2399 4881 3564 4881 3570 4881 2399 4882 3570 4882 9226 4882 9226 4883 3570 4883 9227 4883 2577 4884 2400 4884 2513 4884 2401 4885 2527 4885 2459 4885 2527 4886 2401 4886 2458 4886 21 4887 2403 4887 2402 4887 2538 4888 2536 4888 2465 4888 2465 4889 2536 4889 8680 4889 2402 4890 2403 4890 2434 4890 2404 4891 2405 4891 2506 4891 2506 4892 2405 4892 2406 4892 5733 4893 2526 4893 5731 4893 5731 4894 2526 4894 2481 4894 5731 4895 2481 4895 5675 4895 5675 4896 2481 4896 2482 4896 5675 4897 2482 4897 5677 4897 5677 4898 2482 4898 2483 4898 5715 4899 2408 4899 2407 4899 2407 4900 2408 4900 2484 4900 8585 4901 8584 4901 1652 4901 2426 4902 8587 4902 2409 4902 2409 4903 8587 4903 8585 4903 2409 4904 8585 4904 5693 4904 5693 4905 8585 4905 1652 4905 5693 4906 1652 4906 5684 4906 2426 4907 2410 4907 8587 4907 8587 4908 2410 4908 2411 4908 8587 4909 2411 4909 8588 4909 8588 4910 2411 4910 2428 4910 2428 4911 2412 4911 8588 4911 8588 4912 2412 4912 2413 4912 8588 4913 2413 4913 2414 4913 2413 4914 24 4914 2414 4914 2414 4915 24 4915 23 4915 2414 4916 23 4916 2416 4916 23 4917 2415 4917 2416 4917 2416 4918 2415 4918 2417 4918 2416 4919 2417 4919 2435 4919 2436 4920 8557 4920 2435 4920 2418 4921 8561 4921 2419 4921 8549 4922 2443 4922 8544 4922 8544 4923 2443 4923 8543 4923 8549 4924 2420 4924 2443 4924 2443 4925 2420 4925 2421 4925 2443 4926 2421 4926 2438 4926 2422 4927 2446 4927 8579 4927 8579 4928 2446 4928 2448 4928 8579 4929 2448 4929 2423 4929 2423 4930 2448 4930 8599 4930 8599 4931 2448 4931 2466 4931 8599 4932 2466 4932 2424 4932 2463 4933 2425 4933 2464 4933 2464 4934 2425 4934 8628 4934 2464 4935 8628 4935 2466 4935 2466 4936 8628 4936 8602 4936 2466 4937 8602 4937 2424 4937 2426 4938 5704 4938 2410 4938 2410 4939 5704 4939 5707 4939 2410 4940 5707 4940 2411 4940 2411 4941 5707 4941 2427 4941 2411 4942 2427 4942 2428 4942 2428 4943 2427 4943 2429 4943 2429 4944 2427 4944 27 4944 27 4945 2427 4945 2501 4945 27 4946 2501 4946 2500 4946 2430 4947 2433 4947 2496 4947 2497 4948 2431 4948 19 4948 19 4949 2431 4949 2432 4949 19 4950 2432 4950 2509 4950 2430 4951 2496 4951 16 4951 2433 4952 2498 4952 2496 4952 2496 4953 2498 4953 2499 4953 2496 4954 2499 4954 2487 4954 2417 4955 2434 4955 2435 4955 2435 4956 2434 4956 2403 4956 2435 4957 2403 4957 2436 4957 2436 4958 2403 4958 21 4958 2436 4959 21 4959 2437 4959 2438 4960 228 4960 2443 4960 2443 4961 228 4961 2439 4961 2443 4962 2439 4962 2444 4962 2469 4963 244 4963 2418 4963 2418 4964 244 4964 2440 4964 2418 4965 2440 4965 236 4965 236 4966 238 4966 2418 4966 2418 4967 238 4967 2441 4967 2418 4968 2441 4968 8561 4968 8561 4969 2441 4969 233 4969 8561 4970 233 4970 2438 4970 2438 4971 233 4971 2442 4971 2438 4972 2442 4972 228 4972 8543 4973 2443 4973 8536 4973 8536 4974 2443 4974 2444 4974 8536 4975 2444 4975 2445 4975 2445 4976 2444 4976 226 4976 2445 4977 226 4977 2422 4977 2422 4978 226 4978 246 4978 2422 4979 246 4979 2446 4979 2446 4980 246 4980 2447 4980 2446 4981 2447 4981 2448 4981 2448 4982 2447 4982 2449 4982 2448 4983 2449 4983 247 4983 2468 4984 248 4984 2469 4984 2469 4985 248 4985 243 4985 2469 4986 243 4986 244 4986 2451 4987 207 4987 2450 4987 2450 4988 205 4988 2451 4988 2451 4989 205 4989 199 4989 2451 4990 199 4990 2452 4990 2452 4991 199 4991 201 4991 2452 4992 201 4992 195 4992 2437 4993 2510 4993 220 4993 220 4994 216 4994 2437 4994 2437 4995 216 4995 2453 4995 2437 4996 2453 4996 2436 4996 2436 4997 2453 4997 2454 4997 209 4998 2419 4998 2455 4998 2455 4999 2419 4999 8557 4999 2455 5000 8557 5000 2456 5000 2456 5001 8557 5001 2436 5001 2456 5002 2436 5002 212 5002 212 5003 2436 5003 2454 5003 223 5004 2462 5004 2457 5004 2457 5005 2462 5005 2452 5005 2457 5006 2452 5006 196 5006 196 5007 2452 5007 195 5007 2511 5008 224 5008 2510 5008 2510 5009 224 5009 194 5009 2510 5010 194 5010 220 5010 2400 5011 2458 5011 2513 5011 2513 5012 2458 5012 2401 5012 2513 5013 2401 5013 2461 5013 2472 5014 2459 5014 2539 5014 2459 5015 2472 5015 2401 5015 2401 5016 2472 5016 2460 5016 2401 5017 2460 5017 2461 5017 2461 5018 2460 5018 2470 5018 2461 5019 2470 5019 2512 5019 2512 5020 2470 5020 2462 5020 2512 5021 2462 5021 2511 5021 2511 5022 2462 5022 223 5022 2511 5023 223 5023 224 5023 8680 5024 2463 5024 2465 5024 2465 5025 2463 5025 2464 5025 2465 5026 2464 5026 2471 5026 2471 5027 2464 5027 2466 5027 2471 5028 2466 5028 2467 5028 2467 5029 2466 5029 2448 5029 2467 5030 2448 5030 2468 5030 2468 5031 2448 5031 247 5031 2468 5032 247 5032 248 5032 209 5033 207 5033 2419 5033 2419 5034 207 5034 2451 5034 2419 5035 2451 5035 2418 5035 2418 5036 2451 5036 2452 5036 2418 5037 2452 5037 2469 5037 2469 5038 2452 5038 2462 5038 2469 5039 2462 5039 2468 5039 2468 5040 2462 5040 2470 5040 2468 5041 2470 5041 2467 5041 2467 5042 2470 5042 2460 5042 2467 5043 2460 5043 2471 5043 2471 5044 2460 5044 2472 5044 2471 5045 2472 5045 2465 5045 2465 5046 2472 5046 2539 5046 2465 5047 2539 5047 2538 5047 2491 5048 2493 5048 2473 5048 2473 5049 2493 5049 2571 5049 2571 5050 2493 5050 2507 5050 2571 5051 2507 5051 2521 5051 2473 5052 2543 5052 2491 5052 2491 5053 2543 5053 2557 5053 2491 5054 2557 5054 2474 5054 2474 5055 2557 5055 2475 5055 2474 5056 2475 5056 2490 5056 2490 5057 2475 5057 2476 5057 2490 5058 2476 5058 2489 5058 2489 5059 2476 5059 2553 5059 2489 5060 2553 5060 2515 5060 2524 5061 2404 5061 2478 5061 2478 5062 2404 5062 2506 5062 2478 5063 2506 5063 2480 5063 2525 5064 2524 5064 2477 5064 2477 5065 2524 5065 2478 5065 2477 5066 2478 5066 2479 5066 2479 5067 2478 5067 2480 5067 2479 5068 2480 5068 2504 5068 2526 5069 2525 5069 2481 5069 2481 5070 2525 5070 2477 5070 2481 5071 2477 5071 2482 5071 2482 5072 2477 5072 2479 5072 2482 5073 2479 5073 2483 5073 2483 5074 2479 5074 2504 5074 2483 5075 2504 5075 2502 5075 5707 5076 5656 5076 2427 5076 2427 5077 5656 5077 2484 5077 2427 5078 2484 5078 2501 5078 2501 5079 2484 5079 2408 5079 2501 5080 2408 5080 2502 5080 2502 5081 2408 5081 5715 5081 2502 5082 5715 5082 2483 5082 2483 5083 5715 5083 5714 5083 2483 5084 5714 5084 5677 5084 2485 5085 2496 5085 2486 5085 2486 5086 2496 5086 2487 5086 2486 5087 2487 5087 2488 5087 2488 5088 2487 5088 2503 5088 2488 5089 2503 5089 2492 5089 2489 5090 2485 5090 2490 5090 2490 5091 2485 5091 2486 5091 2490 5092 2486 5092 2474 5092 2474 5093 2486 5093 2488 5093 2474 5094 2488 5094 2491 5094 2491 5095 2488 5095 2492 5095 2491 5096 2492 5096 2493 5096 2493 5097 2492 5097 2505 5097 2493 5098 2505 5098 2507 5098 2515 5099 2514 5099 2489 5099 2489 5100 2514 5100 2494 5100 2489 5101 2494 5101 2485 5101 2485 5102 2494 5102 2495 5102 2485 5103 2495 5103 2496 5103 2496 5104 2495 5104 2431 5104 2496 5105 2431 5105 16 5105 16 5106 2431 5106 2497 5106 2498 5107 2500 5107 2499 5107 2499 5108 2500 5108 2501 5108 2499 5109 2501 5109 2487 5109 2487 5110 2501 5110 2502 5110 2487 5111 2502 5111 2503 5111 2503 5112 2502 5112 2504 5112 2503 5113 2504 5113 2492 5113 2492 5114 2504 5114 2480 5114 2492 5115 2480 5115 2505 5115 2505 5116 2480 5116 2506 5116 2505 5117 2506 5117 2507 5117 2507 5118 2506 5118 2406 5118 2507 5119 2406 5119 2521 5119 21 5120 2508 5120 2437 5120 2437 5121 2508 5121 2509 5121 2437 5122 2509 5122 2510 5122 2510 5123 2509 5123 2432 5123 2510 5124 2432 5124 2511 5124 2511 5125 2432 5125 2431 5125 2511 5126 2431 5126 2512 5126 2512 5127 2431 5127 2495 5127 2512 5128 2495 5128 2461 5128 2461 5129 2495 5129 2494 5129 2461 5130 2494 5130 2513 5130 2513 5131 2494 5131 2514 5131 2513 5132 2514 5132 2577 5132 2577 5133 2514 5133 2515 5133 2523 5134 2516 5134 2517 5134 2517 5135 2516 5135 2519 5135 2517 5136 2519 5136 2518 5136 2518 5137 2519 5137 2600 5137 2518 5138 2600 5138 2520 5138 2521 5139 2406 5139 2522 5139 2522 5140 2406 5140 2405 5140 2522 5141 2405 5141 2523 5141 2523 5142 2405 5142 2404 5142 2523 5143 2404 5143 2516 5143 2516 5144 2404 5144 2524 5144 2516 5145 2524 5145 2519 5145 2519 5146 2524 5146 2525 5146 2519 5147 2525 5147 2600 5147 2600 5148 2525 5148 2526 5148 2600 5149 2526 5149 2599 5149 2599 5150 2526 5150 5733 5150 2547 5151 2576 5151 2578 5151 2527 5152 2458 5152 2540 5152 2540 5153 2458 5153 2400 5153 3338 5154 3348 5154 2558 5154 2528 5155 2579 5155 2580 5155 2617 5156 2529 5156 3357 5156 2617 5157 3357 5157 2531 5157 2531 5158 3357 5158 2530 5158 2531 5159 2530 5159 2532 5159 2532 5160 2530 5160 3361 5160 2532 5161 3361 5161 3339 5161 2573 5162 3332 5162 2533 5162 2573 5163 2533 5163 8682 5163 8682 5164 2533 5164 3314 5164 8682 5165 3314 5165 8683 5165 2582 5166 3331 5166 3332 5166 2534 5167 8680 5167 2535 5167 2535 5168 8680 5168 2536 5168 2535 5169 2536 5169 2537 5169 2536 5170 2538 5170 2537 5170 2537 5171 2538 5171 2539 5171 2537 5172 2539 5172 2459 5172 8681 5173 2534 5173 2572 5173 2572 5174 2534 5174 2535 5174 2572 5175 2535 5175 2575 5175 2575 5176 2535 5176 2537 5176 2575 5177 2537 5177 2540 5177 2540 5178 2537 5178 2459 5178 2540 5179 2459 5179 2527 5179 2542 5180 2591 5180 2541 5180 2593 5181 2473 5181 2571 5181 2591 5182 2542 5182 2592 5182 2592 5183 2542 5183 2556 5183 2592 5184 2556 5184 2594 5184 2594 5185 2556 5185 2557 5185 2594 5186 2557 5186 2543 5186 2552 5187 2476 5187 2475 5187 2544 5188 2555 5188 2551 5188 2544 5189 2551 5189 2552 5189 2549 5190 2545 5190 2554 5190 2554 5191 2545 5191 2547 5191 2554 5192 2547 5192 2546 5192 2546 5193 2547 5193 2555 5193 2576 5194 2547 5194 2548 5194 2548 5195 2547 5195 2545 5195 2548 5196 2545 5196 2550 5196 2550 5197 2545 5197 2549 5197 2550 5198 2549 5198 2574 5198 2555 5199 2547 5199 2551 5199 2551 5200 2547 5200 2578 5200 2551 5201 2578 5201 2552 5201 2552 5202 2578 5202 2553 5202 2552 5203 2553 5203 2476 5203 3332 5204 2573 5204 2582 5204 2582 5205 2573 5205 2574 5205 2582 5206 2574 5206 2583 5206 2583 5207 2574 5207 2549 5207 2583 5208 2549 5208 2585 5208 2585 5209 2549 5209 2554 5209 2585 5210 2554 5210 2586 5210 2586 5211 2554 5211 2546 5211 2586 5212 2546 5212 2589 5212 2589 5213 2546 5213 2555 5213 2589 5214 2555 5214 2541 5214 2541 5215 2555 5215 2544 5215 2541 5216 2544 5216 2542 5216 2542 5217 2544 5217 2552 5217 2542 5218 2552 5218 2556 5218 2556 5219 2552 5219 2475 5219 2556 5220 2475 5220 2557 5220 2558 5221 2559 5221 2562 5221 2562 5222 2559 5222 2567 5222 2562 5223 2567 5223 2561 5223 2561 5224 2567 5224 2560 5224 2561 5225 2560 5225 2618 5225 2618 5226 2560 5226 2620 5226 2618 5227 2617 5227 2561 5227 2561 5228 2617 5228 2531 5228 2561 5229 2531 5229 2562 5229 2562 5230 2531 5230 2532 5230 2562 5231 2532 5231 2558 5231 2558 5232 2532 5232 3339 5232 2558 5233 3339 5233 3338 5233 3348 5234 2528 5234 2558 5234 2558 5235 2528 5235 2580 5235 2558 5236 2580 5236 2559 5236 2559 5237 2580 5237 2563 5237 2559 5238 2563 5238 2584 5238 2584 5239 2564 5239 2565 5239 2565 5240 2564 5240 2587 5240 2565 5241 2587 5241 2566 5241 2566 5242 2587 5242 2588 5242 2566 5243 2588 5243 2590 5243 2584 5244 2565 5244 2559 5244 2559 5245 2565 5245 2566 5245 2559 5246 2566 5246 2567 5246 2567 5247 2566 5247 2590 5247 2567 5248 2590 5248 2560 5248 2560 5249 2590 5249 2568 5249 2560 5250 2568 5250 2620 5250 2620 5251 2568 5251 2569 5251 2620 5252 2569 5252 2621 5252 2621 5253 2569 5253 2570 5253 2621 5254 2570 5254 2624 5254 2624 5255 2570 5255 2593 5255 2624 5256 2593 5256 2625 5256 2625 5257 2593 5257 2571 5257 2625 5258 2571 5258 2521 5258 8682 5259 8681 5259 2573 5259 2573 5260 8681 5260 2572 5260 2573 5261 2572 5261 2574 5261 2574 5262 2572 5262 2575 5262 2574 5263 2575 5263 2550 5263 2550 5264 2575 5264 2540 5264 2550 5265 2540 5265 2548 5265 2548 5266 2540 5266 2400 5266 2548 5267 2400 5267 2576 5267 2576 5268 2400 5268 2577 5268 2576 5269 2577 5269 2578 5269 2578 5270 2577 5270 2515 5270 2578 5271 2515 5271 2553 5271 2579 5272 2581 5272 2580 5272 2580 5273 2581 5273 3331 5273 2580 5274 3331 5274 2563 5274 2563 5275 3331 5275 2582 5275 2563 5276 2582 5276 2584 5276 2584 5277 2582 5277 2583 5277 2584 5278 2583 5278 2564 5278 2564 5279 2583 5279 2585 5279 2564 5280 2585 5280 2587 5280 2587 5281 2585 5281 2586 5281 2587 5282 2586 5282 2588 5282 2588 5283 2586 5283 2589 5283 2588 5284 2589 5284 2590 5284 2590 5285 2589 5285 2541 5285 2590 5286 2541 5286 2568 5286 2568 5287 2541 5287 2591 5287 2568 5288 2591 5288 2569 5288 2569 5289 2591 5289 2592 5289 2569 5290 2592 5290 2570 5290 2570 5291 2592 5291 2594 5291 2570 5292 2594 5292 2593 5292 2593 5293 2594 5293 2543 5293 2593 5294 2543 5294 2473 5294 2598 5295 5590 5295 2595 5295 2595 5296 5590 5296 5625 5296 2595 5297 5625 5297 8584 5297 8584 5298 5625 5298 5626 5298 8584 5299 5626 5299 5650 5299 5593 5300 2596 5300 2597 5300 2597 5301 2596 5301 5636 5301 5602 5302 5599 5302 8614 5302 5602 5303 8614 5303 5592 5303 5599 5304 5591 5304 8614 5304 8614 5305 5591 5305 5598 5305 8614 5306 5598 5306 2595 5306 2595 5307 5598 5307 5597 5307 2595 5308 5597 5308 2598 5308 2600 5309 2599 5309 2605 5309 2600 5310 2605 5310 2520 5310 2601 5311 2602 5311 2603 5311 2603 5312 2602 5312 2604 5312 2603 5313 2604 5313 2597 5313 2597 5314 2604 5314 5595 5314 2597 5315 5595 5315 5593 5315 2520 5316 2605 5316 2603 5316 2603 5317 2605 5317 2606 5317 2603 5318 2606 5318 2601 5318 2607 5319 2608 5319 2615 5319 2607 5320 2615 5320 2610 5320 2615 5321 2609 5321 2610 5321 2610 5322 2609 5322 2597 5322 2610 5323 2597 5323 8614 5323 8614 5324 2597 5324 5636 5324 8614 5325 5636 5325 5592 5325 2523 5326 3014 5326 2522 5326 2522 5327 3014 5327 3011 5327 2522 5328 3011 5328 2521 5328 2520 5329 2611 5329 2518 5329 2518 5330 2611 5330 3014 5330 2518 5331 3014 5331 2517 5331 2517 5332 3014 5332 2523 5332 2608 5333 2612 5333 3020 5333 2613 5334 2611 5334 2520 5334 2520 5335 2603 5335 2613 5335 2613 5336 2603 5336 2597 5336 2613 5337 2597 5337 2614 5337 2614 5338 2597 5338 2609 5338 2614 5339 2609 5339 3020 5339 3020 5340 2609 5340 2615 5340 3020 5341 2615 5341 2608 5341 2633 5342 3403 5342 2616 5342 2616 5343 3403 5343 3393 5343 2616 5344 3393 5344 3005 5344 3005 5345 3393 5345 2529 5345 2529 5346 2617 5346 3005 5346 3005 5347 2617 5347 2618 5347 3005 5348 2618 5348 2619 5348 2619 5349 2618 5349 2620 5349 2619 5350 2620 5350 3007 5350 3007 5351 2620 5351 3008 5351 3008 5352 2620 5352 2621 5352 3008 5353 2621 5353 2622 5353 2622 5354 2621 5354 2623 5354 2623 5355 2621 5355 2624 5355 2623 5356 2624 5356 3009 5356 3009 5357 2624 5357 2625 5357 3009 5358 2625 5358 2626 5358 2626 5359 2625 5359 2521 5359 2626 5360 2521 5360 3011 5360 2634 5361 3403 5361 2633 5361 1050 5362 3447 5362 2627 5362 2627 5363 3447 5363 3392 5363 2627 5364 3392 5364 2628 5364 2628 5365 3392 5365 3367 5365 2628 5366 3367 5366 3002 5366 3002 5367 3367 5367 2629 5367 3002 5368 2629 5368 2999 5368 2999 5369 2629 5369 2631 5369 2999 5370 2631 5370 2630 5370 2630 5371 2631 5371 2632 5371 2630 5372 2632 5372 3000 5372 3000 5373 2632 5373 3377 5373 3000 5374 3377 5374 2633 5374 2633 5375 3377 5375 3376 5375 2633 5376 3376 5376 2634 5376 1037 5377 2635 5377 3440 5377 3440 5378 2635 5378 2641 5378 3425 5379 1063 5379 2636 5379 2636 5380 1063 5380 2637 5380 2636 5381 2637 5381 3409 5381 3409 5382 2637 5382 2714 5382 3409 5383 2714 5383 3413 5383 3413 5384 2714 5384 2638 5384 3425 5385 2639 5385 1063 5385 1063 5386 2639 5386 1058 5386 1063 5387 1058 5387 2640 5387 2641 5388 2635 5388 2642 5388 2642 5389 2635 5389 2643 5389 2642 5390 2643 5390 2644 5390 2644 5391 2643 5391 3436 5391 3436 5392 2643 5392 2645 5392 3436 5393 2645 5393 3423 5393 2639 5394 2646 5394 1058 5394 1058 5395 2646 5395 3417 5395 1058 5396 3417 5396 2645 5396 2645 5397 3417 5397 3429 5397 2645 5398 3429 5398 3423 5398 2655 5399 1645 5399 2647 5399 8859 5400 5805 5400 8812 5400 8812 5401 5805 5401 5806 5401 2648 5402 5811 5402 2650 5402 2648 5403 2650 5403 5771 5403 5806 5404 5769 5404 8812 5404 8812 5405 5769 5405 2649 5405 8812 5406 2649 5406 2650 5406 2650 5407 2649 5407 5809 5407 2650 5408 5809 5408 5771 5408 5778 5409 5777 5409 2653 5409 5778 5410 2653 5410 2651 5410 5811 5411 5767 5411 2650 5411 2650 5412 5767 5412 5813 5412 2650 5413 5813 5413 2651 5413 5777 5414 2652 5414 2653 5414 2653 5415 2652 5415 5775 5415 2653 5416 5775 5416 5774 5416 5774 5417 5765 5417 2653 5417 2653 5418 5765 5418 5773 5418 2653 5419 5773 5419 2647 5419 5910 5420 2655 5420 2654 5420 2654 5421 2655 5421 2647 5421 2654 5422 2647 5422 5800 5422 5800 5423 2647 5423 5773 5423 2651 5424 2653 5424 2650 5424 2650 5425 2653 5425 2662 5425 2650 5426 2662 5426 8819 5426 8819 5427 2662 5427 3575 5427 8819 5428 3575 5428 8823 5428 2656 5429 2657 5429 1645 5429 1645 5430 1648 5430 2656 5430 2656 5431 1648 5431 2658 5431 2656 5432 2658 5432 1646 5432 1646 5433 2659 5433 2656 5433 2656 5434 2659 5434 2660 5434 2656 5435 2660 5435 2972 5435 1645 5436 2657 5436 2969 5436 3576 5437 3575 5437 2661 5437 2661 5438 3575 5438 2662 5438 2661 5439 2662 5439 2967 5439 2967 5440 2662 5440 2653 5440 2967 5441 2653 5441 2969 5441 2969 5442 2653 5442 2647 5442 2969 5443 2647 5443 1645 5443 3280 5444 2672 5444 3291 5444 3291 5445 2672 5445 2671 5445 3291 5446 2671 5446 2663 5446 2664 5447 2972 5447 2660 5447 2660 5448 2665 5448 2664 5448 2664 5449 2665 5449 2666 5449 2664 5450 2666 5450 2667 5450 2667 5451 2666 5451 2730 5451 2667 5452 2730 5452 2669 5452 2669 5453 2730 5453 2668 5453 2669 5454 2668 5454 2975 5454 2975 5455 2668 5455 2728 5455 2975 5456 2728 5456 2977 5456 2977 5457 2728 5457 2769 5457 2977 5458 2769 5458 2980 5458 2980 5459 2769 5459 2670 5459 2980 5460 2670 5460 2671 5460 2671 5461 2670 5461 2768 5461 2671 5462 2768 5462 2663 5462 2681 5463 1039 5463 2679 5463 3280 5464 2673 5464 2672 5464 2672 5465 2673 5465 3271 5465 3271 5466 3270 5466 2672 5466 2672 5467 3270 5467 3283 5467 2672 5468 3283 5468 2674 5468 2674 5469 3283 5469 2675 5469 2674 5470 2675 5470 2987 5470 2987 5471 2675 5471 2985 5471 2985 5472 2675 5472 3206 5472 2985 5473 3206 5473 2676 5473 2676 5474 3206 5474 3205 5474 2676 5475 3205 5475 2677 5475 2677 5476 3205 5476 2678 5476 2677 5477 2678 5477 2679 5477 2679 5478 2678 5478 2680 5478 2679 5479 2680 5479 2681 5479 2682 5480 3514 5480 2988 5480 2988 5481 3514 5481 2989 5481 3487 5482 2686 5482 1060 5482 2989 5483 3514 5483 3512 5483 2687 5484 2683 5484 2685 5484 2830 5485 2824 5485 2684 5485 2684 5486 2824 5486 2823 5486 2684 5487 2823 5487 3491 5487 1060 5488 2686 5488 2685 5488 2685 5489 2686 5489 3482 5489 2685 5490 3482 5490 3481 5490 2823 5491 2687 5491 3491 5491 3491 5492 2687 5492 2685 5492 3491 5493 2685 5493 3493 5493 3493 5494 2685 5494 3481 5494 2989 5495 3512 5495 1062 5495 1062 5496 3512 5496 3509 5496 1062 5497 3509 5497 2688 5497 2688 5498 3509 5498 2689 5498 2688 5499 2689 5499 1060 5499 1060 5500 2689 5500 3488 5500 1060 5501 3488 5501 3487 5501 2692 5502 3444 5502 2690 5502 2690 5503 3444 5503 2696 5503 2690 5504 2696 5504 2698 5504 2691 5505 3439 5505 3172 5505 2692 5506 3200 5506 3370 5506 2693 5507 2694 5507 3444 5507 3172 5508 2695 5508 2691 5508 2691 5509 2695 5509 2697 5509 2691 5510 2697 5510 2696 5510 2696 5511 2697 5511 3188 5511 2696 5512 3188 5512 2698 5512 2693 5513 3444 5513 2699 5513 2692 5514 3370 5514 3444 5514 3444 5515 3370 5515 3371 5515 3444 5516 3371 5516 2699 5516 2694 5517 3373 5517 3444 5517 3444 5518 3373 5518 3374 5518 3444 5519 3374 5519 3454 5519 2034 5520 2700 5520 8734 5520 8734 5521 2700 5521 8756 5521 3174 5522 8825 5522 3191 5522 3191 5523 8825 5523 8833 5523 3191 5524 8833 5524 2701 5524 8833 5525 2702 5525 2701 5525 2701 5526 2702 5526 2703 5526 2701 5527 2703 5527 3195 5527 3195 5528 2703 5528 2705 5528 3195 5529 2705 5529 2704 5529 2704 5530 2705 5530 8775 5530 2704 5531 8775 5531 3199 5531 3199 5532 8775 5532 2706 5532 3199 5533 2706 5533 2700 5533 2700 5534 2706 5534 2707 5534 2700 5535 2707 5535 8756 5535 2713 5536 8825 5536 3174 5536 2637 5537 1063 5537 2717 5537 2637 5538 2717 5538 2714 5538 2715 5539 2709 5539 2708 5539 2708 5540 2709 5540 2711 5540 2708 5541 2711 5541 2710 5541 2710 5542 2711 5542 8846 5542 2710 5543 8846 5543 2712 5543 2712 5544 8846 5544 8845 5544 2712 5545 8845 5545 3174 5545 3174 5546 8845 5546 8844 5546 3174 5547 8844 5547 2713 5547 2723 5548 8873 5548 2717 5548 2717 5549 8873 5549 8898 5549 2708 5550 2714 5550 2715 5550 2715 5551 2714 5551 2717 5551 2715 5552 2717 5552 2716 5552 2716 5553 2717 5553 8898 5553 2718 5554 2719 5554 1082 5554 1082 5555 2719 5555 2720 5555 1082 5556 2720 5556 1079 5556 1079 5557 2720 5557 8887 5557 1079 5558 8887 5558 2721 5558 2721 5559 8887 5559 2722 5559 2721 5560 2722 5560 2723 5560 2723 5561 2722 5561 8892 5561 2723 5562 8892 5562 8873 5562 2724 5563 2832 5563 1076 5563 1076 5564 2832 5564 2725 5564 1076 5565 2725 5565 2718 5565 2718 5566 2725 5566 8876 5566 2718 5567 8876 5567 2719 5567 5758 5568 5805 5568 2841 5568 2841 5569 5805 5569 8859 5569 2777 5570 2785 5570 2726 5570 2727 5571 2728 5571 2668 5571 2856 5572 2779 5572 2780 5572 2757 5573 2666 5573 2665 5573 2729 5574 2668 5574 2730 5574 2731 5575 2802 5575 2744 5575 3300 5576 2663 5576 2768 5576 2798 5577 2732 5577 2797 5577 2797 5578 2732 5578 2733 5578 2797 5579 2733 5579 2772 5579 2772 5580 2733 5580 2734 5580 2772 5581 2734 5581 3311 5581 2735 5582 3258 5582 2795 5582 2795 5583 3258 5583 3256 5583 2795 5584 3256 5584 2796 5584 2796 5585 3256 5585 2736 5585 2796 5586 2736 5586 3251 5586 2741 5587 3240 5587 3239 5587 2741 5588 3239 5588 2795 5588 2795 5589 3239 5589 2737 5589 2795 5590 2737 5590 2735 5590 3240 5591 2741 5591 2739 5591 2739 5592 2741 5592 2738 5592 2739 5593 2738 5593 3238 5593 2791 5594 9107 5594 2740 5594 2740 5595 9107 5595 2793 5595 9107 5596 2738 5596 2793 5596 2793 5597 2738 5597 2741 5597 2793 5598 2741 5598 2794 5598 2794 5599 2741 5599 2795 5599 2731 5600 2744 5600 2742 5600 2802 5601 2743 5601 2747 5601 2802 5602 2747 5602 2744 5602 2744 5603 2747 5603 2746 5603 2744 5604 2746 5604 2792 5604 2745 5605 2903 5605 2746 5605 2746 5606 2903 5606 2790 5606 2746 5607 2790 5607 2792 5607 2743 5608 2914 5608 2747 5608 2747 5609 2914 5609 2748 5609 2747 5610 2748 5610 2746 5610 2746 5611 2748 5611 2749 5611 2746 5612 2749 5612 2745 5612 2666 5613 2757 5613 2804 5613 2804 5614 2757 5614 2758 5614 2804 5615 2758 5615 2750 5615 2750 5616 2758 5616 2784 5616 2750 5617 2784 5617 2751 5617 2754 5618 2760 5618 2755 5618 2755 5619 2760 5619 2752 5619 2755 5620 2752 5620 2762 5620 2778 5621 2754 5621 2753 5621 2753 5622 2754 5622 2755 5622 2753 5623 2755 5623 2756 5623 2756 5624 2755 5624 2762 5624 2756 5625 2762 5625 2765 5625 2660 5626 2856 5626 2665 5626 2665 5627 2856 5627 2780 5627 2665 5628 2780 5628 2757 5628 2757 5629 2780 5629 2781 5629 2757 5630 2781 5630 2758 5630 2908 5631 2911 5631 2776 5631 2911 5632 2799 5632 2776 5632 2776 5633 2799 5633 2759 5633 2776 5634 2759 5634 2761 5634 2761 5635 2759 5635 2763 5635 2760 5636 2761 5636 2752 5636 2752 5637 2761 5637 2763 5637 2752 5638 2763 5638 2762 5638 2762 5639 2763 5639 2764 5639 2762 5640 2764 5640 2765 5640 2768 5641 2670 5641 2767 5641 2767 5642 2670 5642 2766 5642 2766 5643 2772 5643 2767 5643 2767 5644 2772 5644 3311 5644 2767 5645 3311 5645 2768 5645 2768 5646 3311 5646 3305 5646 2768 5647 3305 5647 3300 5647 2728 5648 2727 5648 2769 5648 2668 5649 2729 5649 2727 5649 2727 5650 2729 5650 2803 5650 2727 5651 2803 5651 2769 5651 2770 5652 2797 5652 2771 5652 2771 5653 2797 5653 2772 5653 2771 5654 2772 5654 2773 5654 2773 5655 2772 5655 2766 5655 2773 5656 2766 5656 2803 5656 2803 5657 2766 5657 2670 5657 2803 5658 2670 5658 2769 5658 2774 5659 2908 5659 2775 5659 2775 5660 2908 5660 2776 5660 2775 5661 2776 5661 2782 5661 2782 5662 2776 5662 2761 5662 2782 5663 2761 5663 2783 5663 2783 5664 2761 5664 2760 5664 2783 5665 2760 5665 2726 5665 2726 5666 2760 5666 2754 5666 2726 5667 2754 5667 2777 5667 2777 5668 2754 5668 2778 5668 2779 5669 2774 5669 2780 5669 2780 5670 2774 5670 2775 5670 2780 5671 2775 5671 2781 5671 2781 5672 2775 5672 2782 5672 2781 5673 2782 5673 2758 5673 2758 5674 2782 5674 2783 5674 2758 5675 2783 5675 2784 5675 2784 5676 2783 5676 2726 5676 2784 5677 2726 5677 2751 5677 2751 5678 2726 5678 2785 5678 2800 5679 2787 5679 2786 5679 2786 5680 2787 5680 2934 5680 2786 5681 2934 5681 2801 5681 2801 5682 2934 5682 2788 5682 2801 5683 2788 5683 2743 5683 2743 5684 2788 5684 2789 5684 2743 5685 2789 5685 2914 5685 9084 5686 2791 5686 2790 5686 2790 5687 2791 5687 2740 5687 2790 5688 2740 5688 2792 5688 2792 5689 2740 5689 2793 5689 2792 5690 2793 5690 2744 5690 2744 5691 2793 5691 2794 5691 2744 5692 2794 5692 2742 5692 2742 5693 2794 5693 2795 5693 2742 5694 2795 5694 2770 5694 2770 5695 2795 5695 2796 5695 2770 5696 2796 5696 2797 5696 2797 5697 2796 5697 3251 5697 2797 5698 3251 5698 2798 5698 2799 5699 2800 5699 2759 5699 2759 5700 2800 5700 2786 5700 2759 5701 2786 5701 2763 5701 2763 5702 2786 5702 2801 5702 2763 5703 2801 5703 2764 5703 2764 5704 2801 5704 2743 5704 2764 5705 2743 5705 2765 5705 2765 5706 2743 5706 2802 5706 2765 5707 2802 5707 2756 5707 2756 5708 2802 5708 2731 5708 2756 5709 2731 5709 2753 5709 2753 5710 2731 5710 2742 5710 2753 5711 2742 5711 2778 5711 2778 5712 2742 5712 2770 5712 2778 5713 2770 5713 2777 5713 2777 5714 2770 5714 2771 5714 2777 5715 2771 5715 2785 5715 2785 5716 2771 5716 2773 5716 2785 5717 2773 5717 2751 5717 2751 5718 2773 5718 2803 5718 2751 5719 2803 5719 2750 5719 2750 5720 2803 5720 2729 5720 2750 5721 2729 5721 2804 5721 2804 5722 2729 5722 2730 5722 2804 5723 2730 5723 2666 5723 3156 5724 3498 5724 2808 5724 3156 5725 2808 5725 3162 5725 3520 5726 3135 5726 2805 5726 2812 5727 2809 5727 2810 5727 3520 5728 2810 5728 3135 5728 3135 5729 2810 5729 2806 5729 3135 5730 2806 5730 3212 5730 2805 5731 3149 5731 3520 5731 3520 5732 3149 5732 2807 5732 3520 5733 2807 5733 2808 5733 2808 5734 2807 5734 3150 5734 2808 5735 3150 5735 3162 5735 2809 5736 3211 5736 2810 5736 2810 5737 3211 5737 3213 5737 2810 5738 3213 5738 2806 5738 3557 5739 3556 5739 2810 5739 2810 5740 3556 5740 2811 5740 2810 5741 2811 5741 2812 5741 9047 5742 2813 5742 2822 5742 2822 5743 2813 5743 9021 5743 2822 5744 9021 5744 2814 5744 2814 5745 9021 5745 2816 5745 2814 5746 2816 5746 2815 5746 2815 5747 2816 5747 9017 5747 2815 5748 9017 5748 3155 5748 3155 5749 9017 5749 9010 5749 3155 5750 9010 5750 2817 5750 2817 5751 9010 5751 2818 5751 2817 5752 2818 5752 3169 5752 2819 5753 2820 5753 2821 5753 2819 5754 2821 5754 3141 5754 3141 5755 2821 5755 9060 5755 3141 5756 9060 5756 2822 5756 2822 5757 9060 5757 9048 5757 2822 5758 9048 5758 9047 5758 2687 5759 2823 5759 2825 5759 2825 5760 2823 5760 2824 5760 2825 5761 2824 5761 2830 5761 3169 5762 2818 5762 2826 5762 2826 5763 2818 5763 2827 5763 2826 5764 2827 5764 2828 5764 2828 5765 2827 5765 8993 5765 2828 5766 8993 5766 3167 5766 3167 5767 8993 5767 2829 5767 3167 5768 2829 5768 2830 5768 2830 5769 2829 5769 8986 5769 2830 5770 8986 5770 2825 5770 2831 5771 8930 5771 1072 5771 1072 5772 8930 5772 8928 5772 1072 5773 8928 5773 1074 5773 1074 5774 8928 5774 2832 5774 1074 5775 2832 5775 2724 5775 1070 5776 8935 5776 2833 5776 2833 5777 8935 5777 8933 5777 2833 5778 8933 5778 2831 5778 2831 5779 8933 5779 2834 5779 2831 5780 2834 5780 8930 5780 1065 5781 8939 5781 1067 5781 1067 5782 8939 5782 8937 5782 1067 5783 8937 5783 1070 5783 1070 5784 8937 5784 2835 5784 1070 5785 2835 5785 8935 5785 8986 5786 8963 5786 2825 5786 2825 5787 8963 5787 8964 5787 2825 5788 8964 5788 1065 5788 1065 5789 8964 5789 8940 5789 1065 5790 8940 5790 8939 5790 2955 5791 2836 5791 2957 5791 158 5792 2837 5792 2906 5792 153 5793 2838 5793 2900 5793 2939 5794 2921 5794 2920 5794 2925 5795 1651 5795 2926 5795 5853 5796 2847 5796 2851 5796 5843 5797 2845 5797 2839 5797 5849 5798 2844 5798 2840 5798 2842 5799 5863 5799 5862 5799 8859 5800 2842 5800 2841 5800 2841 5801 2842 5801 5862 5801 2841 5802 5862 5802 5758 5802 5863 5803 2842 5803 5847 5803 5847 5804 2842 5804 2843 5804 5847 5805 2843 5805 2844 5805 5849 5806 2840 5806 2845 5806 2845 5807 2840 5807 2877 5807 2845 5808 2877 5808 2839 5808 2846 5809 2849 5809 2942 5809 2942 5810 2849 5810 5839 5810 2942 5811 5839 5811 2879 5811 2851 5812 2847 5812 2846 5812 2846 5813 2847 5813 2848 5813 2846 5814 2848 5814 2849 5814 2849 5815 2848 5815 2850 5815 2849 5816 2850 5816 5839 5816 5853 5817 2851 5817 5900 5817 5900 5818 2851 5818 2852 5818 5900 5819 2852 5819 5834 5819 5834 5820 2852 5820 2853 5820 2853 5821 2852 5821 2946 5821 2853 5822 2946 5822 2854 5822 2854 5823 2946 5823 2855 5823 2854 5824 2855 5824 5836 5824 2949 5825 2856 5825 2947 5825 2947 5826 2856 5826 2660 5826 9042 5827 9043 5827 2922 5827 2922 5828 9043 5828 9052 5828 139 5829 2865 5829 143 5829 143 5830 2865 5830 2857 5830 143 5831 2857 5831 2858 5831 2858 5832 2857 5832 9019 5832 2858 5833 9019 5833 2897 5833 2897 5834 9019 5834 9027 5834 8974 5835 2860 5835 2859 5835 2859 5836 2860 5836 2893 5836 8974 5837 8975 5837 2860 5837 2860 5838 8975 5838 2861 5838 2860 5839 2861 5839 2863 5839 2863 5840 2861 5840 2862 5840 2863 5841 2862 5841 139 5841 139 5842 2862 5842 2864 5842 139 5843 2864 5843 2865 5843 185 5844 8925 5844 186 5844 186 5845 8925 5845 2866 5845 186 5846 2866 5846 2867 5846 2867 5847 2866 5847 8908 5847 2867 5848 8908 5848 2890 5848 2890 5849 8908 5849 2895 5849 2880 5850 2882 5850 8925 5850 8925 5851 2882 5851 8924 5851 8862 5852 2868 5852 2869 5852 2869 5853 2868 5853 9451 5853 2869 5854 9451 5854 2870 5854 2844 5855 2843 5855 2840 5855 2840 5856 2843 5856 2869 5856 2840 5857 2869 5857 2877 5857 2877 5858 2869 5858 2870 5858 2877 5859 2870 5859 9450 5859 2881 5860 9459 5860 9458 5860 2871 5861 2933 5861 2932 5861 2871 5862 2932 5862 9446 5862 9459 5863 2881 5863 2872 5863 2872 5864 2881 5864 2957 5864 2872 5865 2957 5865 9452 5865 9452 5866 2957 5866 2836 5866 9452 5867 2836 5867 2873 5867 2873 5868 2836 5868 2955 5868 2873 5869 2955 5869 2874 5869 2875 5870 2876 5870 2942 5870 2942 5871 2876 5871 2940 5871 2942 5872 2940 5872 2941 5872 9450 5873 2878 5873 2877 5873 2877 5874 2878 5874 2875 5874 2877 5875 2875 5875 2839 5875 2839 5876 2875 5876 2942 5876 2839 5877 2942 5877 5843 5877 5843 5878 2942 5878 2879 5878 185 5879 178 5879 8925 5879 8925 5880 178 5880 179 5880 8925 5881 179 5881 2880 5881 2880 5882 179 5882 182 5882 2880 5883 182 5883 174 5883 174 5884 2881 5884 2880 5884 2880 5885 2881 5885 9458 5885 2880 5886 9458 5886 2882 5886 2882 5887 9458 5887 2883 5887 2882 5888 2883 5888 8924 5888 8924 5889 2883 5889 9455 5889 8924 5890 9455 5890 2884 5890 2884 5891 9455 5891 2885 5891 2884 5892 2885 5892 8862 5892 8862 5893 2885 5893 9445 5893 8862 5894 9445 5894 2868 5894 174 5895 175 5895 2881 5895 2881 5896 175 5896 2886 5896 2881 5897 2886 5897 2957 5897 2957 5898 2886 5898 2887 5898 2957 5899 2887 5899 2888 5899 2905 5900 164 5900 2889 5900 2889 5901 163 5901 2905 5901 2905 5902 163 5902 2891 5902 2905 5903 2891 5903 2890 5903 2890 5904 2891 5904 192 5904 2890 5905 192 5905 2867 5905 2956 5906 171 5906 2907 5906 2907 5907 171 5907 169 5907 2907 5908 169 5908 2905 5908 2905 5909 169 5909 168 5909 2905 5910 168 5910 164 5910 2863 5911 2892 5911 2860 5911 2860 5912 2892 5912 137 5912 2860 5913 137 5913 2893 5913 2893 5914 137 5914 2894 5914 2893 5915 2894 5915 2895 5915 2906 5916 2837 5916 2896 5916 2896 5917 2837 5917 149 5917 2896 5918 149 5918 2897 5918 149 5919 2898 5919 2897 5919 2897 5920 2898 5920 2899 5920 2897 5921 2899 5921 2858 5921 2858 5922 2899 5922 142 5922 2858 5923 142 5923 143 5923 2838 5924 2901 5924 2900 5924 2900 5925 2901 5925 155 5925 2900 5926 155 5926 2906 5926 2906 5927 155 5927 2902 5927 2906 5928 2902 5928 158 5928 2745 5929 2913 5929 2903 5929 2903 5930 2913 5930 2904 5930 2903 5931 2904 5931 2790 5931 2790 5932 2904 5932 9085 5932 2790 5933 9085 5933 9084 5933 2894 5934 153 5934 2895 5934 2895 5935 153 5935 2900 5935 2895 5936 2900 5936 2890 5936 2890 5937 2900 5937 2906 5937 2890 5938 2906 5938 2905 5938 2905 5939 2906 5939 2896 5939 2905 5940 2896 5940 2907 5940 2910 5941 2908 5941 2950 5941 2950 5942 2908 5942 2774 5942 2950 5943 2774 5943 2949 5943 2949 5944 2774 5944 2779 5944 2949 5945 2779 5945 2856 5945 2924 5946 2787 5946 2909 5946 2909 5947 2787 5947 2800 5947 2909 5948 2800 5948 2952 5948 2952 5949 2800 5949 2799 5949 2952 5950 2799 5950 2910 5950 2910 5951 2799 5951 2911 5951 2910 5952 2911 5952 2908 5952 1651 5953 1650 5953 2926 5953 2926 5954 1650 5954 2912 5954 2926 5955 2912 5955 2927 5955 2927 5956 2912 5956 2945 5956 2927 5957 2945 5957 2944 5957 2745 5958 2749 5958 2913 5958 2913 5959 2749 5959 2748 5959 2913 5960 2748 5960 2919 5960 2919 5961 2748 5961 2914 5961 2919 5962 2914 5962 2918 5962 2918 5963 2914 5963 2789 5963 2918 5964 2789 5964 2915 5964 2915 5965 2789 5965 2788 5965 2915 5966 2916 5966 2918 5966 2918 5967 2916 5967 2917 5967 2918 5968 2917 5968 2919 5968 2919 5969 2917 5969 2937 5969 2919 5970 2937 5970 2913 5970 2913 5971 2937 5971 2920 5971 2913 5972 2920 5972 2904 5972 2904 5973 2920 5973 2921 5973 2904 5974 2921 5974 9085 5974 9027 5975 9042 5975 2897 5975 2897 5976 9042 5976 2922 5976 2897 5977 2922 5977 2896 5977 2896 5978 2922 5978 2938 5978 2896 5979 2938 5979 2907 5979 2907 5980 2938 5980 2936 5980 2907 5981 2936 5981 2956 5981 2956 5982 2936 5982 2923 5982 2956 5983 2923 5983 2954 5983 2954 5984 2923 5984 2935 5984 2954 5985 2935 5985 2924 5985 2924 5986 2935 5986 2934 5986 2924 5987 2934 5987 2787 5987 1649 5988 2925 5988 2948 5988 2948 5989 2925 5989 2926 5989 2948 5990 2926 5990 2951 5990 2951 5991 2926 5991 2927 5991 2951 5992 2927 5992 2928 5992 2928 5993 2927 5993 2944 5993 2928 5994 2944 5994 2929 5994 2929 5995 2944 5995 2930 5995 2929 5996 2930 5996 2953 5996 2953 5997 2930 5997 2943 5997 2953 5998 2943 5998 2931 5998 2931 5999 2943 5999 2932 5999 2931 6000 2932 6000 2955 6000 2955 6001 2932 6001 2933 6001 2955 6002 2933 6002 2874 6002 2788 6003 2934 6003 2915 6003 2915 6004 2934 6004 2935 6004 2915 6005 2935 6005 2916 6005 2916 6006 2935 6006 2923 6006 2916 6007 2923 6007 2917 6007 2917 6008 2923 6008 2936 6008 2917 6009 2936 6009 2937 6009 2937 6010 2936 6010 2938 6010 2937 6011 2938 6011 2920 6011 2920 6012 2938 6012 2922 6012 2920 6013 2922 6013 2939 6013 2939 6014 2922 6014 9052 6014 2940 6015 9446 6015 2941 6015 2941 6016 9446 6016 2932 6016 2941 6017 2932 6017 2942 6017 2942 6018 2932 6018 2943 6018 2942 6019 2943 6019 2846 6019 2846 6020 2943 6020 2930 6020 2846 6021 2930 6021 2851 6021 2851 6022 2930 6022 2944 6022 2851 6023 2944 6023 2852 6023 2852 6024 2944 6024 2945 6024 2852 6025 2945 6025 2946 6025 2946 6026 2945 6026 2912 6026 2946 6027 2912 6027 2855 6027 2855 6028 2912 6028 1650 6028 2947 6029 1649 6029 2949 6029 2949 6030 1649 6030 2948 6030 2949 6031 2948 6031 2950 6031 2950 6032 2948 6032 2951 6032 2950 6033 2951 6033 2910 6033 2910 6034 2951 6034 2928 6034 2910 6035 2928 6035 2952 6035 2952 6036 2928 6036 2929 6036 2952 6037 2929 6037 2909 6037 2909 6038 2929 6038 2953 6038 2909 6039 2953 6039 2924 6039 2924 6040 2953 6040 2931 6040 2924 6041 2931 6041 2954 6041 2954 6042 2931 6042 2955 6042 2954 6043 2955 6043 2956 6043 2956 6044 2955 6044 2957 6044 2956 6045 2957 6045 171 6045 171 6046 2957 6046 2888 6046 2958 6047 1297 6047 2959 6047 2958 6048 2959 6048 1375 6048 2960 6049 2962 6049 2959 6049 2959 6050 2962 6050 2963 6050 2959 6051 2963 6051 1375 6051 2969 6052 2657 6052 2961 6052 2962 6053 2960 6053 2964 6053 2962 6054 2964 6054 2963 6054 2963 6055 2964 6055 3678 6055 2963 6056 3678 6056 2965 6056 2965 6057 3577 6057 2963 6057 2963 6058 3577 6058 3576 6058 2963 6059 3576 6059 2966 6059 2966 6060 3576 6060 2661 6060 2966 6061 2661 6061 1338 6061 1338 6062 2661 6062 2967 6062 1338 6063 2967 6063 2968 6063 2968 6064 2967 6064 2969 6064 2968 6065 2969 6065 1371 6065 1371 6066 2969 6066 2961 6066 2657 6067 2656 6067 2961 6067 2961 6068 2656 6068 2970 6068 2970 6069 2656 6069 1365 6069 1365 6070 2656 6070 2972 6070 1365 6071 2972 6071 2971 6071 2971 6072 2972 6072 2664 6072 2971 6073 2664 6073 2973 6073 2973 6074 2664 6074 2667 6074 2973 6075 2667 6075 2974 6075 2974 6076 2667 6076 2669 6076 2974 6077 2669 6077 1363 6077 1363 6078 2669 6078 2975 6078 1363 6079 2975 6079 2976 6079 2976 6080 2975 6080 2977 6080 2976 6081 2977 6081 2978 6081 2978 6082 2977 6082 2980 6082 2978 6083 2980 6083 2979 6083 2979 6084 2980 6084 1423 6084 1423 6085 2980 6085 2671 6085 1423 6086 2671 6086 2981 6086 2981 6087 2671 6087 2672 6087 2981 6088 2672 6088 2982 6088 1039 6089 2983 6089 1422 6089 1039 6090 1422 6090 2679 6090 2679 6091 1422 6091 2984 6091 2679 6092 2984 6092 2677 6092 2677 6093 2984 6093 2676 6093 2676 6094 2984 6094 2986 6094 2676 6095 2986 6095 2985 6095 2985 6096 2986 6096 2987 6096 2987 6097 2986 6097 1362 6097 2987 6098 1362 6098 2674 6098 2674 6099 1362 6099 2982 6099 2674 6100 2982 6100 2672 6100 2988 6101 2989 6101 1043 6101 1043 6102 2989 6102 1420 6102 1417 6103 2683 6103 1064 6103 1068 6104 1337 6104 2990 6104 1417 6105 1064 6105 2990 6105 2990 6106 1064 6106 1066 6106 2990 6107 1066 6107 1068 6107 1073 6108 1354 6108 2991 6108 1068 6109 1069 6109 1337 6109 1337 6110 1069 6110 1071 6110 1337 6111 1071 6111 2991 6111 2991 6112 1071 6112 2992 6112 2991 6113 2992 6113 1073 6113 1073 6114 2993 6114 1354 6114 1354 6115 2993 6115 2994 6115 1354 6116 2994 6116 2995 6116 2994 6117 1075 6117 2995 6117 2995 6118 1075 6118 1081 6118 2995 6119 1081 6119 2996 6119 1081 6120 1080 6120 2996 6120 2996 6121 1080 6121 1078 6121 2996 6122 1078 6122 1409 6122 2640 6123 2997 6123 2998 6123 2998 6124 2997 6124 1409 6124 2998 6125 1409 6125 1077 6125 1077 6126 1409 6126 1078 6126 1399 6127 1397 6127 1037 6127 1037 6128 1397 6128 2635 6128 3001 6129 2999 6129 1396 6129 1396 6130 2999 6130 2630 6130 1396 6131 2630 6131 1395 6131 1395 6132 2630 6132 3000 6132 1395 6133 3000 6133 1394 6133 1394 6134 3000 6134 2633 6134 2627 6135 2628 6135 3001 6135 3001 6136 2628 6136 3002 6136 3001 6137 3002 6137 2999 6137 3001 6138 3003 6138 2627 6138 2627 6139 3003 6139 3004 6139 2627 6140 3004 6140 1050 6140 1394 6141 2633 6141 2616 6141 1394 6142 2616 6142 1392 6142 2616 6143 3005 6143 1392 6143 1392 6144 3005 6144 2619 6144 1392 6145 2619 6145 3006 6145 3006 6146 2619 6146 1391 6146 2619 6147 3007 6147 1391 6147 1391 6148 3007 6148 3008 6148 1391 6149 3008 6149 1387 6149 1387 6150 3008 6150 2622 6150 1387 6151 2622 6151 1386 6151 1386 6152 2622 6152 2623 6152 1386 6153 2623 6153 1388 6153 1388 6154 2623 6154 3009 6154 1388 6155 3009 6155 3010 6155 3009 6156 2626 6156 3010 6156 3010 6157 2626 6157 3011 6157 3010 6158 3011 6158 3012 6158 3011 6159 3014 6159 3012 6159 3012 6160 3014 6160 3013 6160 3013 6161 3014 6161 3015 6161 3015 6162 3014 6162 2611 6162 3015 6163 2611 6163 1376 6163 2613 6164 1376 6164 2611 6164 3016 6165 3623 6165 3023 6165 3023 6166 3623 6166 3017 6166 3023 6167 3017 6167 3024 6167 3024 6168 3017 6168 1295 6168 1376 6169 2613 6169 3018 6169 3018 6170 2613 6170 2614 6170 3018 6171 2614 6171 3019 6171 3019 6172 2614 6172 3020 6172 3019 6173 3020 6173 3021 6173 3021 6174 3020 6174 2612 6174 3021 6175 2612 6175 3023 6175 3023 6176 2612 6176 3022 6176 3023 6177 3022 6177 3016 6177 3024 6178 1295 6178 3025 6178 1323 6179 3028 6179 3025 6179 3025 6180 3028 6180 3023 6180 3025 6181 3023 6181 3024 6181 3027 6182 1322 6182 3026 6182 3026 6183 1322 6183 1335 6183 3026 6184 1335 6184 3030 6184 1297 6185 2958 6185 1333 6185 1333 6186 2958 6186 3030 6186 1333 6187 3030 6187 1334 6187 1334 6188 3030 6188 1335 6188 1323 6189 3027 6189 3028 6189 3028 6190 3027 6190 3026 6190 3028 6191 3026 6191 3029 6191 3029 6192 3026 6192 3030 6192 3029 6193 3030 6193 1344 6193 1344 6194 3030 6194 2958 6194 1344 6195 2958 6195 1375 6195 3046 6196 5021 6196 3047 6196 4240 6197 4262 6197 3049 6197 3031 6198 3051 6198 3032 6198 5020 6199 5018 6199 3033 6199 3033 6200 5018 6200 5037 6200 3033 6201 5037 6201 4364 6201 3057 6202 3052 6202 3056 6202 3056 6203 3052 6203 4347 6203 3056 6204 4347 6204 3034 6204 3032 6205 3051 6205 3035 6205 3035 6206 3051 6206 3037 6206 3035 6207 3037 6207 3038 6207 4262 6208 4238 6208 3049 6208 3049 6209 4238 6209 3036 6209 3049 6210 3036 6210 3037 6210 3037 6211 3036 6211 4282 6211 3037 6212 4282 6212 3038 6212 3040 6213 3111 6213 3039 6213 3040 6214 3039 6214 3047 6214 3039 6215 3041 6215 3047 6215 3047 6216 3041 6216 3042 6216 3047 6217 3042 6217 3043 6217 3043 6218 3044 6218 3047 6218 3047 6219 3044 6219 3045 6219 3047 6220 3045 6220 4239 6220 3046 6221 3047 6221 3048 6221 4239 6222 4240 6222 3047 6222 3047 6223 4240 6223 3049 6223 3047 6224 3049 6224 3048 6224 3048 6225 3049 6225 3037 6225 3048 6226 3037 6226 5038 6226 5038 6227 3037 6227 3050 6227 3050 6228 3037 6228 3051 6228 3050 6229 3051 6229 3057 6229 3057 6230 3051 6230 3031 6230 3057 6231 3031 6231 3052 6231 4364 6232 5037 6232 4343 6232 4343 6233 5037 6233 3053 6233 4343 6234 3053 6234 3054 6234 3054 6235 3053 6235 3055 6235 3054 6236 3055 6236 3034 6236 3034 6237 3055 6237 5035 6237 3034 6238 5035 6238 3056 6238 3056 6239 5035 6239 5042 6239 3056 6240 5042 6240 3057 6240 3057 6241 5042 6241 5040 6241 3057 6242 5040 6242 3050 6242 6329 6243 4543 6243 6330 6243 6330 6244 4543 6244 1980 6244 6330 6245 1980 6245 3058 6245 3100 6246 3059 6246 3097 6246 3097 6247 3059 6247 5336 6247 3060 6248 3092 6248 5285 6248 5285 6249 3092 6249 3097 6249 5285 6250 3097 6250 5337 6250 5337 6251 3097 6251 5336 6251 3102 6252 3061 6252 3100 6252 3100 6253 3061 6253 3062 6253 3100 6254 3062 6254 3059 6254 3059 6255 3062 6255 3063 6255 3059 6256 3063 6256 2340 6256 3101 6257 4614 6257 4612 6257 4614 6258 3101 6258 4615 6258 4615 6259 3101 6259 3099 6259 4615 6260 3099 6260 4616 6260 4616 6261 3099 6261 3098 6261 4616 6262 3098 6262 4600 6262 3096 6263 3123 6263 3098 6263 3098 6264 3123 6264 3064 6264 3098 6265 3064 6265 4600 6265 3066 6266 3096 6266 4006 6266 4006 6267 3096 6267 3094 6267 4006 6268 3094 6268 3065 6268 3066 6269 4013 6269 3096 6269 3096 6270 4013 6270 3125 6270 3096 6271 3125 6271 3124 6271 3124 6272 3067 6272 3096 6272 3096 6273 3067 6273 3122 6273 3096 6274 3122 6274 3123 6274 3093 6275 3088 6275 3999 6275 3999 6276 3088 6276 3071 6276 3999 6277 3071 6277 3072 6277 4048 6278 3087 6278 3068 6278 3068 6279 3087 6279 3086 6279 3068 6280 3086 6280 4047 6280 4047 6281 3086 6281 3085 6281 4048 6282 3069 6282 3087 6282 3087 6283 3069 6283 3070 6283 3087 6284 3070 6284 3088 6284 3088 6285 3070 6285 4056 6285 3088 6286 4056 6286 3071 6286 3071 6287 4056 6287 4055 6287 3071 6288 4055 6288 3072 6288 3077 6289 3073 6289 3079 6289 3079 6290 3073 6290 4590 6290 3079 6291 4590 6291 4591 6291 4591 6292 4582 6292 3079 6292 3079 6293 4582 6293 1976 6293 3079 6294 1976 6294 4034 6294 4034 6295 4036 6295 3079 6295 3079 6296 4036 6296 3083 6296 3079 6297 3083 6297 3084 6297 3074 6298 3075 6298 3076 6298 3076 6299 3075 6299 3077 6299 3076 6300 3077 6300 3078 6300 3078 6301 3077 6301 3079 6301 3080 6302 3081 6302 5283 6302 5283 6303 3081 6303 3082 6303 5283 6304 3082 6304 3076 6304 3076 6305 3082 6305 4547 6305 3076 6306 4547 6306 3074 6306 3080 6307 5283 6307 4545 6307 4545 6308 5283 6308 5265 6308 4545 6309 5265 6309 6312 6309 3083 6310 3085 6310 3084 6310 3084 6311 3085 6311 3086 6311 3084 6312 3086 6312 3090 6312 3090 6313 3086 6313 3087 6313 5289 6314 5287 6314 3093 6314 3093 6315 5287 6315 3089 6315 3093 6316 3089 6316 3088 6316 3088 6317 3089 6317 5292 6317 3088 6318 5292 6318 3087 6318 3087 6319 5292 6319 5291 6319 3087 6320 5291 6320 3090 6320 3060 6321 3091 6321 3092 6321 3092 6322 3091 6322 5289 6322 3092 6323 5289 6323 3095 6323 3095 6324 5289 6324 3093 6324 3999 6325 3065 6325 3093 6325 3093 6326 3065 6326 3094 6326 3093 6327 3094 6327 3095 6327 3095 6328 3094 6328 3096 6328 3095 6329 3096 6329 3092 6329 3092 6330 3096 6330 3098 6330 3092 6331 3098 6331 3097 6331 3097 6332 3098 6332 3099 6332 3097 6333 3099 6333 3100 6333 3100 6334 3099 6334 3101 6334 3100 6335 3101 6335 3102 6335 3102 6336 3101 6336 4612 6336 3102 6337 4612 6337 2338 6337 3106 6338 7202 6338 3103 6338 1878 6339 4389 6339 3104 6339 3104 6340 4389 6340 3107 6340 4371 6341 3106 6341 3105 6341 3105 6342 3106 6342 3103 6342 3105 6343 3103 6343 4391 6343 4391 6344 3103 6344 7210 6344 4391 6345 7210 6345 3108 6345 3108 6346 7210 6346 3107 6346 3108 6347 3107 6347 4398 6347 4398 6348 3107 6348 4389 6348 3109 6349 3110 6349 3115 6349 3115 6350 3110 6350 4215 6350 3115 6351 4215 6351 3117 6351 3111 6352 3040 6352 3112 6352 3112 6353 3040 6353 3113 6353 3112 6354 3113 6354 3114 6354 3114 6355 3113 6355 8106 6355 3114 6356 8106 6356 4229 6356 4229 6357 8106 6357 3115 6357 4229 6358 3115 6358 3116 6358 3116 6359 3115 6359 3117 6359 3119 6360 6961 6360 3120 6360 3118 6361 3119 6361 4212 6361 4212 6362 3119 6362 3120 6362 4212 6363 3120 6363 4213 6363 4213 6364 3120 6364 3121 6364 4213 6365 3121 6365 4203 6365 4203 6366 3121 6366 6973 6366 4203 6367 6973 6367 4207 6367 4207 6368 6973 6368 6980 6368 4207 6369 6980 6369 1934 6369 3122 6370 3067 6370 4018 6370 3122 6371 4018 6371 3123 6371 3067 6372 3124 6372 4018 6372 4018 6373 3124 6373 3125 6373 4018 6374 3125 6374 4013 6374 4019 6375 3132 6375 3126 6375 3126 6376 3132 6376 3127 6376 3064 6377 3123 6377 3131 6377 3131 6378 3123 6378 4018 6378 3131 6379 4018 6379 3127 6379 3127 6380 4018 6380 3128 6380 3127 6381 3128 6381 3126 6381 3133 6382 3132 6382 3129 6382 3129 6383 3132 6383 4019 6383 3129 6384 4019 6384 4020 6384 4600 6385 3064 6385 3130 6385 3130 6386 3064 6386 3131 6386 3130 6387 3131 6387 4601 6387 4601 6388 3131 6388 3127 6388 4601 6389 3127 6389 4606 6389 4606 6390 3127 6390 3132 6390 4606 6391 3132 6391 4604 6391 4604 6392 3132 6392 3133 6392 3134 6393 3276 6393 3139 6393 3139 6394 3276 6394 3275 6394 3139 6395 3275 6395 3140 6395 3134 6396 3139 6396 3272 6396 3272 6397 3139 6397 3135 6397 3272 6398 3135 6398 3212 6398 3275 6399 3292 6399 3140 6399 3140 6400 3292 6400 3136 6400 3140 6401 3136 6401 3137 6401 3137 6402 3136 6402 3306 6402 3137 6403 3306 6403 2819 6403 2819 6404 3306 6404 3138 6404 2819 6405 3138 6405 2018 6405 2817 6406 3169 6406 3153 6406 2815 6407 3155 6407 3154 6407 2822 6408 2814 6408 3147 6408 3152 6409 3150 6409 2807 6409 2805 6410 3135 6410 3145 6410 3145 6411 3135 6411 3139 6411 3145 6412 3139 6412 3143 6412 3143 6413 3139 6413 3140 6413 3143 6414 3140 6414 3142 6414 3142 6415 3140 6415 3137 6415 2822 6416 3142 6416 3141 6416 3141 6417 3142 6417 3137 6417 3141 6418 3137 6418 2819 6418 2822 6419 3147 6419 3142 6419 3142 6420 3147 6420 3148 6420 3142 6421 3148 6421 3143 6421 3143 6422 3148 6422 3144 6422 3143 6423 3144 6423 3145 6423 3145 6424 3144 6424 3149 6424 3145 6425 3149 6425 2805 6425 2815 6426 3154 6426 2814 6426 2814 6427 3154 6427 3147 6427 3147 6428 3154 6428 3146 6428 3147 6429 3146 6429 3148 6429 3148 6430 3146 6430 3152 6430 3148 6431 3152 6431 3144 6431 3144 6432 3152 6432 2807 6432 3144 6433 2807 6433 3149 6433 3162 6434 3150 6434 3163 6434 3163 6435 3150 6435 3152 6435 3163 6436 3152 6436 3151 6436 3151 6437 3152 6437 3146 6437 3151 6438 3146 6438 3153 6438 3153 6439 3146 6439 3154 6439 3153 6440 3154 6440 2817 6440 2817 6441 3154 6441 3155 6441 3158 6442 3156 6442 3162 6442 3498 6443 3156 6443 3483 6443 3483 6444 3156 6444 3158 6444 3483 6445 3158 6445 3157 6445 3157 6446 3158 6446 3499 6446 3499 6447 3158 6447 3494 6447 3494 6448 3158 6448 3159 6448 3494 6449 3159 6449 3495 6449 3495 6450 3159 6450 3161 6450 3495 6451 3161 6451 3160 6451 3165 6452 3484 6452 3166 6452 3166 6453 3484 6453 3160 6453 3166 6454 3160 6454 3168 6454 3168 6455 3160 6455 3161 6455 3168 6456 3161 6456 3164 6456 3164 6457 3161 6457 3159 6457 3162 6458 3163 6458 3158 6458 3158 6459 3163 6459 3151 6459 3158 6460 3151 6460 3159 6460 3159 6461 3151 6461 3153 6461 3159 6462 3153 6462 3164 6462 2830 6463 3165 6463 3167 6463 3167 6464 3165 6464 3166 6464 3167 6465 3166 6465 2828 6465 2828 6466 3166 6466 3168 6466 2828 6467 3168 6467 2826 6467 2826 6468 3168 6468 3164 6468 2826 6469 3164 6469 3169 6469 3169 6470 3164 6470 3153 6470 3420 6471 3170 6471 3171 6471 3171 6472 3170 6472 3178 6472 2638 6473 2714 6473 2708 6473 3175 6474 3172 6474 3439 6474 3177 6475 3185 6475 3175 6475 3175 6476 3185 6476 3173 6476 3175 6477 3173 6477 3172 6477 3172 6478 3173 6478 2695 6478 2712 6479 3174 6479 3183 6479 3183 6480 3174 6480 3187 6480 3439 6481 3176 6481 3175 6481 3175 6482 3176 6482 3420 6482 3175 6483 3420 6483 3177 6483 3177 6484 3420 6484 3171 6484 3177 6485 3171 6485 3182 6485 3182 6486 3171 6486 3178 6486 3182 6487 3178 6487 3179 6487 3179 6488 3178 6488 3180 6488 3179 6489 3180 6489 2708 6489 2708 6490 3180 6490 3181 6490 2708 6491 3181 6491 2638 6491 2708 6492 2710 6492 3179 6492 3179 6493 2710 6493 2712 6493 3179 6494 2712 6494 3182 6494 3182 6495 2712 6495 3183 6495 3182 6496 3183 6496 3177 6496 3177 6497 3183 6497 3187 6497 3177 6498 3187 6498 3185 6498 2700 6499 2034 6499 3201 6499 2701 6500 3195 6500 3194 6500 3188 6501 2697 6501 3184 6501 2700 6502 3201 6502 3199 6502 2697 6503 2695 6503 3184 6503 3184 6504 2695 6504 3173 6504 3184 6505 3173 6505 3190 6505 3190 6506 3173 6506 3185 6506 3190 6507 3185 6507 3186 6507 3186 6508 3185 6508 3187 6508 3186 6509 3187 6509 3191 6509 3191 6510 3187 6510 3174 6510 2698 6511 3188 6511 3192 6511 3192 6512 3188 6512 3184 6512 3192 6513 3184 6513 3189 6513 3189 6514 3184 6514 3190 6514 3189 6515 3190 6515 3194 6515 3194 6516 3190 6516 3186 6516 3194 6517 3186 6517 2701 6517 2701 6518 3186 6518 3191 6518 2690 6519 2698 6519 3197 6519 3197 6520 2698 6520 3192 6520 3197 6521 3192 6521 3198 6521 3198 6522 3192 6522 3189 6522 3198 6523 3189 6523 3193 6523 3193 6524 3189 6524 3194 6524 3193 6525 3194 6525 2704 6525 2704 6526 3194 6526 3195 6526 2692 6527 2690 6527 3196 6527 3196 6528 2690 6528 3197 6528 3196 6529 3197 6529 3203 6529 3203 6530 3197 6530 3198 6530 3203 6531 3198 6531 3201 6531 3201 6532 3198 6532 3193 6532 3201 6533 3193 6533 3199 6533 3199 6534 3193 6534 2704 6534 2034 6535 3341 6535 3202 6535 3200 6536 2692 6536 3402 6536 3402 6537 2692 6537 3196 6537 3402 6538 3196 6538 3400 6538 3400 6539 3196 6539 3398 6539 3203 6540 3204 6540 3196 6540 3196 6541 3204 6541 3397 6541 3196 6542 3397 6542 3398 6542 2034 6543 3202 6543 3201 6543 3201 6544 3202 6544 3358 6544 3201 6545 3358 6545 3203 6545 3203 6546 3358 6546 3352 6546 3203 6547 3352 6547 3204 6547 3205 6548 3206 6548 3207 6548 2681 6549 2680 6549 3208 6549 2681 6550 3208 6550 3562 6550 3562 6551 3208 6551 3209 6551 3562 6552 3209 6552 3210 6552 2811 6553 3556 6553 3210 6553 2809 6554 2812 6554 3214 6554 3221 6555 3211 6555 2809 6555 3224 6556 3213 6556 3211 6556 3217 6557 3212 6557 3224 6557 3224 6558 3212 6558 2806 6558 3224 6559 2806 6559 3213 6559 2812 6560 2811 6560 3214 6560 3214 6561 2811 6561 3210 6561 3214 6562 3210 6562 3215 6562 3215 6563 3210 6563 3209 6563 3215 6564 3209 6564 3222 6564 3222 6565 3209 6565 3208 6565 3222 6566 3208 6566 3216 6566 3216 6567 3208 6567 2680 6567 3216 6568 2680 6568 2678 6568 3224 6569 3218 6569 3217 6569 3217 6570 3218 6570 3219 6570 3217 6571 3219 6571 3220 6571 3220 6572 3219 6572 3226 6572 3220 6573 3226 6573 3282 6573 3282 6574 3226 6574 2675 6574 3282 6575 2675 6575 3283 6575 2809 6576 3214 6576 3221 6576 3221 6577 3214 6577 3215 6577 3221 6578 3215 6578 3225 6578 3225 6579 3215 6579 3222 6579 3225 6580 3222 6580 3223 6580 3223 6581 3222 6581 3216 6581 3223 6582 3216 6582 3207 6582 3207 6583 3216 6583 2678 6583 3207 6584 2678 6584 3205 6584 3211 6585 3221 6585 3224 6585 3224 6586 3221 6586 3225 6586 3224 6587 3225 6587 3218 6587 3218 6588 3225 6588 3223 6588 3218 6589 3223 6589 3219 6589 3219 6590 3223 6590 3207 6590 3219 6591 3207 6591 3226 6591 3226 6592 3207 6592 3206 6592 3226 6593 3206 6593 2675 6593 3227 6594 3228 6594 3268 6594 2736 6595 3256 6595 3257 6595 3229 6596 3263 6596 3284 6596 3247 6597 3234 6597 3249 6597 3228 6598 3227 6598 3266 6598 3258 6599 2735 6599 3259 6599 3230 6600 3262 6600 3231 6600 3230 6601 3231 6601 2022 6601 2022 6602 3231 6602 3232 6602 2022 6603 3232 6603 2017 6603 2017 6604 3232 6604 3268 6604 2017 6605 3268 6605 3233 6605 3233 6606 3268 6606 2031 6606 2031 6607 3268 6607 3228 6607 2031 6608 3228 6608 3245 6608 3249 6609 3234 6609 3235 6609 3236 6610 2739 6610 3237 6610 3237 6611 2739 6611 3238 6611 2737 6612 3239 6612 3241 6612 3241 6613 3239 6613 3240 6613 3241 6614 3240 6614 3247 6614 3247 6615 3240 6615 2739 6615 3247 6616 2739 6616 3234 6616 3234 6617 2739 6617 3236 6617 3234 6618 3236 6618 3235 6618 3235 6619 3236 6619 3237 6619 3242 6620 2013 6620 3243 6620 3243 6621 2013 6621 2012 6621 3243 6622 2012 6622 3244 6622 3244 6623 2012 6623 3245 6623 3244 6624 3245 6624 3246 6624 3246 6625 3245 6625 3228 6625 3246 6626 3228 6626 3244 6626 3244 6627 3228 6627 3266 6627 3244 6628 3266 6628 3243 6628 2735 6629 2737 6629 3259 6629 3259 6630 2737 6630 3241 6630 3259 6631 3241 6631 3260 6631 3260 6632 3241 6632 3247 6632 3260 6633 3247 6633 3248 6633 3248 6634 3247 6634 3249 6634 3248 6635 3249 6635 3250 6635 3250 6636 3249 6636 3235 6636 3250 6637 3235 6637 3261 6637 3251 6638 2736 6638 3252 6638 3252 6639 2736 6639 3257 6639 3252 6640 3257 6640 3253 6640 3253 6641 3257 6641 3254 6641 3253 6642 3254 6642 3255 6642 3255 6643 3254 6643 3267 6643 3256 6644 3258 6644 3257 6644 3257 6645 3258 6645 3259 6645 3257 6646 3259 6646 3254 6646 3254 6647 3259 6647 3260 6647 3254 6648 3260 6648 3267 6648 3267 6649 3260 6649 3248 6649 3267 6650 3248 6650 3265 6650 3265 6651 3248 6651 3250 6651 3265 6652 3250 6652 3264 6652 3264 6653 3250 6653 3261 6653 3262 6654 3263 6654 3231 6654 3231 6655 3263 6655 3229 6655 3231 6656 3229 6656 3232 6656 3232 6657 3229 6657 3269 6657 3232 6658 3269 6658 3268 6658 9127 6659 3242 6659 3261 6659 3261 6660 3242 6660 3243 6660 3261 6661 3243 6661 3264 6661 3264 6662 3243 6662 3266 6662 3264 6663 3266 6663 3265 6663 3265 6664 3266 6664 3227 6664 3265 6665 3227 6665 3267 6665 3267 6666 3227 6666 3268 6666 3267 6667 3268 6667 3255 6667 3255 6668 3268 6668 3269 6668 3255 6669 3269 6669 3253 6669 3253 6670 3269 6670 3229 6670 3253 6671 3229 6671 3252 6671 3252 6672 3229 6672 3284 6672 3252 6673 3284 6673 3251 6673 3251 6674 3284 6674 2798 6674 3273 6675 3217 6675 3220 6675 3283 6676 3270 6676 3281 6676 3281 6677 3270 6677 3271 6677 3281 6678 3271 6678 2673 6678 3212 6679 3217 6679 3272 6679 3272 6680 3217 6680 3273 6680 3272 6681 3273 6681 3134 6681 3296 6682 3295 6682 3278 6682 3278 6683 3295 6683 3294 6683 3278 6684 3294 6684 3274 6684 3274 6685 3294 6685 3275 6685 3274 6686 3275 6686 3276 6686 3276 6687 3277 6687 3274 6687 3274 6688 3277 6688 3279 6688 3274 6689 3279 6689 3278 6689 3278 6690 3279 6690 3281 6690 3278 6691 3281 6691 3296 6691 3296 6692 3281 6692 2673 6692 3296 6693 2673 6693 3280 6693 3276 6694 3134 6694 3277 6694 3277 6695 3134 6695 3273 6695 3277 6696 3273 6696 3279 6696 3279 6697 3273 6697 3220 6697 3279 6698 3220 6698 3281 6698 3281 6699 3220 6699 3282 6699 3281 6700 3282 6700 3283 6700 2732 6701 2798 6701 3284 6701 2020 6702 3285 6702 3287 6702 3287 6703 3285 6703 2018 6703 3286 6704 2733 6704 2732 6704 2732 6705 3284 6705 3286 6705 3286 6706 3284 6706 3263 6706 3286 6707 3263 6707 3289 6707 3289 6708 3263 6708 3262 6708 3289 6709 3262 6709 3287 6709 3287 6710 3262 6710 3230 6710 3287 6711 3230 6711 2020 6711 2018 6712 3312 6712 3287 6712 3287 6713 3312 6713 3288 6713 3287 6714 3288 6714 3289 6714 3289 6715 3288 6715 3290 6715 3289 6716 3290 6716 3286 6716 3286 6717 3290 6717 2734 6717 3286 6718 2734 6718 2733 6718 3292 6719 3275 6719 3294 6719 3296 6720 3280 6720 3291 6720 3292 6721 3294 6721 3293 6721 3293 6722 3294 6722 3295 6722 3293 6723 3295 6723 3298 6723 3298 6724 3295 6724 3296 6724 3298 6725 3296 6725 3299 6725 3299 6726 3296 6726 3291 6726 3299 6727 3291 6727 2663 6727 3136 6728 3292 6728 3297 6728 3297 6729 3292 6729 3293 6729 3297 6730 3293 6730 3302 6730 3302 6731 3293 6731 3298 6731 3302 6732 3298 6732 3304 6732 3304 6733 3298 6733 3299 6733 3304 6734 3299 6734 3300 6734 3300 6735 3299 6735 2663 6735 3306 6736 3136 6736 3301 6736 3301 6737 3136 6737 3297 6737 3301 6738 3297 6738 3309 6738 3309 6739 3297 6739 3302 6739 3309 6740 3302 6740 3303 6740 3303 6741 3302 6741 3304 6741 3303 6742 3304 6742 3305 6742 3305 6743 3304 6743 3300 6743 3138 6744 3306 6744 3307 6744 3307 6745 3306 6745 3301 6745 3307 6746 3301 6746 3308 6746 3308 6747 3301 6747 3309 6747 3308 6748 3309 6748 3310 6748 3310 6749 3309 6749 3303 6749 3310 6750 3303 6750 3311 6750 3311 6751 3303 6751 3305 6751 2018 6752 3138 6752 3312 6752 3312 6753 3138 6753 3307 6753 3312 6754 3307 6754 3288 6754 3288 6755 3307 6755 3308 6755 3288 6756 3308 6756 3290 6756 3290 6757 3308 6757 3310 6757 3290 6758 3310 6758 2734 6758 2734 6759 3310 6759 3311 6759 2579 6760 2528 6760 3347 6760 3326 6761 3325 6761 3313 6761 8683 6762 3314 6762 3315 6762 3315 6763 3314 6763 3317 6763 3315 6764 3317 6764 3316 6764 3317 6765 3318 6765 3316 6765 3316 6766 3318 6766 3320 6766 3316 6767 3320 6767 3319 6767 2053 6768 3319 6768 2055 6768 2055 6769 3319 6769 3320 6769 2055 6770 3320 6770 2056 6770 2056 6771 3320 6771 3327 6771 3321 6772 3343 6772 3322 6772 3322 6773 3343 6773 3323 6773 3322 6774 3323 6774 3313 6774 3313 6775 3323 6775 3324 6775 3313 6776 3324 6776 3326 6776 3314 6777 2533 6777 3317 6777 3317 6778 2533 6778 3337 6778 3317 6779 3337 6779 3318 6779 3318 6780 3337 6780 3336 6780 3318 6781 3336 6781 3320 6781 3346 6782 3321 6782 3333 6782 3333 6783 3321 6783 3322 6783 3333 6784 3322 6784 3335 6784 3335 6785 3322 6785 3313 6785 3335 6786 3313 6786 3336 6786 3336 6787 3313 6787 3325 6787 3336 6788 3325 6788 3320 6788 3320 6789 3325 6789 3326 6789 3320 6790 3326 6790 3327 6790 3347 6791 3328 6791 2579 6791 2579 6792 3328 6792 3334 6792 2579 6793 3334 6793 2581 6793 2581 6794 3334 6794 3329 6794 2581 6795 3329 6795 3331 6795 3331 6796 3329 6796 3330 6796 3331 6797 3330 6797 3332 6797 3347 6798 3346 6798 3328 6798 3328 6799 3346 6799 3333 6799 3328 6800 3333 6800 3334 6800 3334 6801 3333 6801 3335 6801 3334 6802 3335 6802 3329 6802 3329 6803 3335 6803 3336 6803 3329 6804 3336 6804 3330 6804 3330 6805 3336 6805 3337 6805 3330 6806 3337 6806 3332 6806 3332 6807 3337 6807 2533 6807 3348 6808 3338 6808 3345 6808 3338 6809 3339 6809 3345 6809 3345 6810 3339 6810 3362 6810 3345 6811 3362 6811 3344 6811 3344 6812 3362 6812 3340 6812 3344 6813 3340 6813 3342 6813 3342 6814 3340 6814 3364 6814 3342 6815 3364 6815 2037 6815 2037 6816 3364 6816 3341 6816 2037 6817 3343 6817 3342 6817 3342 6818 3343 6818 3321 6818 3342 6819 3321 6819 3344 6819 3344 6820 3321 6820 3346 6820 3344 6821 3346 6821 3345 6821 3345 6822 3346 6822 3347 6822 3345 6823 3347 6823 3348 6823 3348 6824 3347 6824 2528 6824 3357 6825 2529 6825 3349 6825 3204 6826 3352 6826 3350 6826 3350 6827 3352 6827 3353 6827 3350 6828 3353 6828 3394 6828 3394 6829 3353 6829 3356 6829 3394 6830 3356 6830 3349 6830 3349 6831 3356 6831 3351 6831 3349 6832 3351 6832 3357 6832 3352 6833 3358 6833 3353 6833 3353 6834 3358 6834 3354 6834 3353 6835 3354 6835 3356 6835 3356 6836 3354 6836 3355 6836 3356 6837 3355 6837 3351 6837 3351 6838 3355 6838 3360 6838 3351 6839 3360 6839 3357 6839 3357 6840 3360 6840 2530 6840 3358 6841 3202 6841 3354 6841 3354 6842 3202 6842 3359 6842 3354 6843 3359 6843 3355 6843 3355 6844 3359 6844 3365 6844 3355 6845 3365 6845 3360 6845 3360 6846 3365 6846 3363 6846 3360 6847 3363 6847 2530 6847 2530 6848 3363 6848 3361 6848 3339 6849 3361 6849 3362 6849 3362 6850 3361 6850 3363 6850 3362 6851 3363 6851 3340 6851 3340 6852 3363 6852 3365 6852 3340 6853 3365 6853 3364 6853 3364 6854 3365 6854 3359 6854 3364 6855 3359 6855 3341 6855 3341 6856 3359 6856 3202 6856 2631 6857 2629 6857 3366 6857 3367 6858 3392 6858 3390 6858 3389 6859 3391 6859 3368 6859 3368 6860 3391 6860 3369 6860 3368 6861 3369 6861 3447 6861 3385 6862 3386 6862 3200 6862 3200 6863 3386 6863 3370 6863 3370 6864 3386 6864 3371 6864 3371 6865 3386 6865 3372 6865 3371 6866 3372 6866 2699 6866 2699 6867 3372 6867 2693 6867 2693 6868 3372 6868 3388 6868 2693 6869 3388 6869 2694 6869 2694 6870 3388 6870 3373 6870 3373 6871 3388 6871 3389 6871 3373 6872 3389 6872 3374 6872 3375 6873 3376 6873 3377 6873 3384 6874 3378 6874 3383 6874 3383 6875 3378 6875 3375 6875 3383 6876 3375 6876 3381 6876 3367 6877 3390 6877 2629 6877 2629 6878 3390 6878 3366 6878 3366 6879 3390 6879 3379 6879 3366 6880 3379 6880 3382 6880 3382 6881 3379 6881 3380 6881 3382 6882 3380 6882 3387 6882 3375 6883 3377 6883 3381 6883 3381 6884 3377 6884 2632 6884 3381 6885 2632 6885 2631 6885 2631 6886 3366 6886 3381 6886 3381 6887 3366 6887 3382 6887 3381 6888 3382 6888 3383 6888 3383 6889 3382 6889 3387 6889 3383 6890 3387 6890 3384 6890 3385 6891 3378 6891 3386 6891 3386 6892 3378 6892 3384 6892 3386 6893 3384 6893 3372 6893 3372 6894 3384 6894 3387 6894 3372 6895 3387 6895 3388 6895 3388 6896 3387 6896 3380 6896 3388 6897 3380 6897 3389 6897 3389 6898 3380 6898 3379 6898 3389 6899 3379 6899 3391 6899 3391 6900 3379 6900 3390 6900 3391 6901 3390 6901 3369 6901 3369 6902 3390 6902 3392 6902 3369 6903 3392 6903 3447 6903 3393 6904 3403 6904 3405 6904 3349 6905 2529 6905 3393 6905 3393 6906 3405 6906 3349 6906 3349 6907 3405 6907 3395 6907 3349 6908 3395 6908 3394 6908 3394 6909 3395 6909 3406 6909 3394 6910 3406 6910 3350 6910 3350 6911 3406 6911 3397 6911 3350 6912 3397 6912 3204 6912 3407 6913 3395 6913 3405 6913 3407 6914 3405 6914 3396 6914 3397 6915 3406 6915 3398 6915 3398 6916 3406 6916 3399 6916 3398 6917 3399 6917 3400 6917 3400 6918 3399 6918 3408 6918 3400 6919 3408 6919 3402 6919 3402 6920 3408 6920 3401 6920 3402 6921 3401 6921 3200 6921 3403 6922 2634 6922 3405 6922 3405 6923 2634 6923 3404 6923 3405 6924 3404 6924 3396 6924 2634 6925 3376 6925 3404 6925 3404 6926 3376 6926 3375 6926 3404 6927 3375 6927 3396 6927 3396 6928 3375 6928 3378 6928 3396 6929 3378 6929 3385 6929 3406 6930 3395 6930 3399 6930 3399 6931 3395 6931 3407 6931 3399 6932 3407 6932 3408 6932 3408 6933 3407 6933 3396 6933 3408 6934 3396 6934 3401 6934 3401 6935 3396 6935 3385 6935 3401 6936 3385 6936 3200 6936 3176 6937 3439 6937 3438 6937 3418 6938 3416 6938 3424 6938 2636 6939 3409 6939 3413 6939 3410 6940 3411 6940 3178 6940 3178 6941 3411 6941 3180 6941 3425 6942 2636 6942 3412 6942 3412 6943 2636 6943 3413 6943 3412 6944 3413 6944 3181 6944 3181 6945 3413 6945 2638 6945 3414 6946 3415 6946 3430 6946 2646 6947 3416 6947 3417 6947 3417 6948 3416 6948 3418 6948 3417 6949 3418 6949 3429 6949 3438 6950 3427 6950 3176 6950 3176 6951 3427 6951 3419 6951 3176 6952 3419 6952 3420 6952 3420 6953 3419 6953 3428 6953 3420 6954 3428 6954 3170 6954 3426 6955 3421 6955 3415 6955 3415 6956 3421 6956 3422 6956 3415 6957 3422 6957 3430 6957 3430 6958 3422 6958 3436 6958 3430 6959 3436 6959 3423 6959 3412 6960 3424 6960 3425 6960 3425 6961 3424 6961 3416 6961 3425 6962 3416 6962 2639 6962 2639 6963 3416 6963 2646 6963 3438 6964 3426 6964 3427 6964 3427 6965 3426 6965 3415 6965 3427 6966 3415 6966 3419 6966 3419 6967 3415 6967 3414 6967 3419 6968 3414 6968 3428 6968 3428 6969 3414 6969 3410 6969 3428 6970 3410 6970 3170 6970 3170 6971 3410 6971 3178 6971 3423 6972 3429 6972 3430 6972 3430 6973 3429 6973 3418 6973 3430 6974 3418 6974 3414 6974 3414 6975 3418 6975 3424 6975 3414 6976 3424 6976 3410 6976 3410 6977 3424 6977 3412 6977 3410 6978 3412 6978 3411 6978 3411 6979 3412 6979 3181 6979 3411 6980 3181 6980 3180 6980 3433 6981 2641 6981 2642 6981 3444 6982 3442 6982 3431 6982 3431 6983 3442 6983 3432 6983 3433 6984 2642 6984 3434 6984 3434 6985 2642 6985 2644 6985 3434 6986 2644 6986 3435 6986 3435 6987 2644 6987 3436 6987 3435 6988 3436 6988 3422 6988 3422 6989 3437 6989 3435 6989 3435 6990 3437 6990 3431 6990 3435 6991 3431 6991 3434 6991 3434 6992 3431 6992 3432 6992 3434 6993 3432 6993 3433 6993 3422 6994 3421 6994 3437 6994 3437 6995 3421 6995 3426 6995 3437 6996 3426 6996 3438 6996 3444 6997 3431 6997 2696 6997 2696 6998 3431 6998 3437 6998 2696 6999 3437 6999 2691 6999 2691 7000 3437 7000 3438 7000 2691 7001 3438 7001 3439 7001 3440 7002 2641 7002 3441 7002 3441 7003 2641 7003 3433 7003 3441 7004 3433 7004 3464 7004 3464 7005 3433 7005 3432 7005 3442 7006 3466 7006 3432 7006 3432 7007 3466 7007 3465 7007 3432 7008 3465 7008 3464 7008 3454 7009 3443 7009 3444 7009 3444 7010 3443 7010 3445 7010 3444 7011 3445 7011 3442 7011 3442 7012 3445 7012 3446 7012 3442 7013 3446 7013 3466 7013 3447 7014 3459 7014 3448 7014 3447 7015 3448 7015 3368 7015 3448 7016 3449 7016 3368 7016 3368 7017 3449 7017 3463 7017 3368 7018 3463 7018 3389 7018 3454 7019 3374 7019 3450 7019 3450 7020 3374 7020 3389 7020 3450 7021 3389 7021 3455 7021 3455 7022 3389 7022 3463 7022 1056 7023 3472 7023 3460 7023 3451 7024 3468 7024 3452 7024 3452 7025 3468 7025 3453 7025 3452 7026 3453 7026 3470 7026 3471 7027 1054 7027 3470 7027 3470 7028 1054 7028 1053 7028 3470 7029 1053 7029 3452 7029 3454 7030 3450 7030 3443 7030 3443 7031 3450 7031 3467 7031 3443 7032 3467 7032 3445 7032 3450 7033 3455 7033 3467 7033 3467 7034 3455 7034 3456 7034 3467 7035 3456 7035 3457 7035 3457 7036 3456 7036 3474 7036 3457 7037 3474 7037 3458 7037 3458 7038 3474 7038 3476 7038 3458 7039 3476 7039 3478 7039 1056 7040 3460 7040 1051 7040 3448 7041 3459 7041 1051 7041 3460 7042 3461 7042 3462 7042 1051 7043 3460 7043 3448 7043 3448 7044 3460 7044 3462 7044 3448 7045 3462 7045 3449 7045 3461 7046 3475 7046 3462 7046 3462 7047 3475 7047 3473 7047 3462 7048 3473 7048 3449 7048 3449 7049 3473 7049 3463 7049 3440 7050 3441 7050 3479 7050 3479 7051 3441 7051 3464 7051 3479 7052 3464 7052 3478 7052 3478 7053 3464 7053 3458 7053 3458 7054 3464 7054 3465 7054 3458 7055 3465 7055 3457 7055 3457 7056 3465 7056 3466 7056 3457 7057 3466 7057 3467 7057 3467 7058 3466 7058 3446 7058 3467 7059 3446 7059 3445 7059 3440 7060 3480 7060 3468 7060 3468 7061 3480 7061 3469 7061 3468 7062 3469 7062 3453 7062 3480 7063 3477 7063 3469 7063 3469 7064 3477 7064 3475 7064 3469 7065 3475 7065 3453 7065 3453 7066 3475 7066 3461 7066 3453 7067 3461 7067 3470 7067 3470 7068 3461 7068 3460 7068 3470 7069 3460 7069 3471 7069 3471 7070 3460 7070 3472 7070 3455 7071 3463 7071 3456 7071 3456 7072 3463 7072 3473 7072 3456 7073 3473 7073 3474 7073 3474 7074 3473 7074 3475 7074 3474 7075 3475 7075 3476 7075 3476 7076 3475 7076 3477 7076 3476 7077 3477 7077 3478 7077 3478 7078 3477 7078 3480 7078 3478 7079 3480 7079 3479 7079 3479 7080 3480 7080 3440 7080 3451 7081 3440 7081 3468 7081 3492 7082 3481 7082 3482 7082 3489 7083 2830 7083 2684 7083 3483 7084 3157 7084 3500 7084 3503 7085 3484 7085 3165 7085 3486 7086 3506 7086 3504 7086 3506 7087 3486 7087 3485 7087 3486 7088 2686 7088 3487 7088 3485 7089 3486 7089 3507 7089 3507 7090 3486 7090 3487 7090 3507 7091 3487 7091 3488 7091 3489 7092 2684 7092 3490 7092 3490 7093 2684 7093 3491 7093 3490 7094 3491 7094 3492 7094 3492 7095 3491 7095 3493 7095 3492 7096 3493 7096 3481 7096 3165 7097 2830 7097 3489 7097 3483 7098 3500 7098 3498 7098 3499 7099 3494 7099 3496 7099 3496 7100 3494 7100 3495 7100 3496 7101 3495 7101 3501 7101 3501 7102 3495 7102 3160 7102 3501 7103 3160 7103 3484 7103 3497 7104 3511 7104 3500 7104 3500 7105 3511 7105 3510 7105 3500 7106 3510 7106 3498 7106 3157 7107 3499 7107 3500 7107 3500 7108 3499 7108 3496 7108 3500 7109 3496 7109 3505 7109 3505 7110 3496 7110 3501 7110 3505 7111 3501 7111 3502 7111 3502 7112 3501 7112 3484 7112 3165 7113 3489 7113 3503 7113 3503 7114 3489 7114 3490 7114 3503 7115 3490 7115 3504 7115 3504 7116 3490 7116 3492 7116 3504 7117 3492 7117 3486 7117 3486 7118 3492 7118 3482 7118 3486 7119 3482 7119 2686 7119 3484 7120 3503 7120 3502 7120 3502 7121 3503 7121 3504 7121 3502 7122 3504 7122 3505 7122 3505 7123 3504 7123 3506 7123 3505 7124 3506 7124 3500 7124 3500 7125 3506 7125 3485 7125 3500 7126 3485 7126 3497 7126 3497 7127 3485 7127 3507 7127 3497 7128 3507 7128 3508 7128 3508 7129 3507 7129 3488 7129 3508 7130 3488 7130 2689 7130 3508 7131 2689 7131 3509 7131 3498 7132 3510 7132 3516 7132 3516 7133 3510 7133 3511 7133 3516 7134 3511 7134 3497 7134 3508 7135 3509 7135 3517 7135 3517 7136 3509 7136 3512 7136 3517 7137 3512 7137 3513 7137 3513 7138 3512 7138 3514 7138 3513 7139 3514 7139 3515 7139 3515 7140 3521 7140 3513 7140 3513 7141 3521 7141 3516 7141 3513 7142 3516 7142 3517 7142 3517 7143 3516 7143 3497 7143 3517 7144 3497 7144 3508 7144 3515 7145 3518 7145 3521 7145 3521 7146 3518 7146 3519 7146 3521 7147 3519 7147 3522 7147 3498 7148 3516 7148 2808 7148 2808 7149 3516 7149 3521 7149 2808 7150 3521 7150 3520 7150 3520 7151 3521 7151 3522 7151 3520 7152 3522 7152 2810 7152 3557 7153 2810 7153 3523 7153 3523 7154 2810 7154 3522 7154 3523 7155 3522 7155 3540 7155 3540 7156 3522 7156 3519 7156 3540 7157 3519 7157 3524 7157 3524 7158 3519 7158 3518 7158 3524 7159 3518 7159 3525 7159 3525 7160 3518 7160 3515 7160 3525 7161 3515 7161 3526 7161 3526 7162 3515 7162 3527 7162 3527 7163 3515 7163 3514 7163 3527 7164 3514 7164 2682 7164 3535 7165 3528 7165 3542 7165 3542 7166 3528 7166 3529 7166 3540 7167 3524 7167 3535 7167 3539 7168 3557 7168 3523 7168 3525 7169 3526 7169 3551 7169 1044 7170 3530 7170 3534 7170 1047 7171 3554 7171 3531 7171 3537 7172 3532 7172 3536 7172 3536 7173 3532 7173 3561 7173 3561 7174 3532 7174 1048 7174 3561 7175 1048 7175 3560 7175 3533 7176 3534 7176 3531 7176 3531 7177 3534 7177 3530 7177 3531 7178 3530 7178 1047 7178 3533 7179 3552 7179 3534 7179 3534 7180 3552 7180 3550 7180 3534 7181 3550 7181 3548 7181 3535 7182 3524 7182 3525 7182 3535 7183 3525 7183 3528 7183 3536 7184 3559 7184 3537 7184 3537 7185 3559 7185 3538 7185 3537 7186 3538 7186 3545 7186 3545 7187 3538 7187 3558 7187 3545 7188 3558 7188 3544 7188 3544 7189 3558 7189 3539 7189 3544 7190 3539 7190 3543 7190 3543 7191 3539 7191 3523 7191 3543 7192 3523 7192 3540 7192 3525 7193 3551 7193 3528 7193 3528 7194 3551 7194 3541 7194 3528 7195 3541 7195 3529 7195 3540 7196 3535 7196 3543 7196 3543 7197 3535 7197 3542 7197 3543 7198 3542 7198 3544 7198 3544 7199 3542 7199 3529 7199 3544 7200 3529 7200 3545 7200 3545 7201 3529 7201 3553 7201 3545 7202 3553 7202 3537 7202 3537 7203 3553 7203 3546 7203 3537 7204 3546 7204 3532 7204 3550 7205 2682 7205 3547 7205 3550 7206 3547 7206 3548 7206 3548 7207 3547 7207 3549 7207 3548 7208 3549 7208 3534 7208 3534 7209 3549 7209 1045 7209 3534 7210 1045 7210 1044 7210 3527 7211 2682 7211 3550 7211 3526 7212 3527 7212 3551 7212 3551 7213 3527 7213 3550 7213 3551 7214 3550 7214 3541 7214 3541 7215 3550 7215 3552 7215 3541 7216 3552 7216 3529 7216 3529 7217 3552 7217 3533 7217 3529 7218 3533 7218 3553 7218 3553 7219 3533 7219 3531 7219 3553 7220 3531 7220 3546 7220 3546 7221 3531 7221 3554 7221 3546 7222 3554 7222 3532 7222 3532 7223 3554 7223 3555 7223 3532 7224 3555 7224 1048 7224 3556 7225 3557 7225 3210 7225 3210 7226 3557 7226 3539 7226 3539 7227 3558 7227 3210 7227 3210 7228 3558 7228 3538 7228 3210 7229 3538 7229 3562 7229 3562 7230 3538 7230 3559 7230 3560 7231 2681 7231 3561 7231 3561 7232 2681 7232 3562 7232 3561 7233 3562 7233 3536 7233 3536 7234 3562 7234 3559 7234 3568 7235 3646 7235 3563 7235 3566 7236 3647 7236 3568 7236 3570 7237 3564 7237 3565 7237 3570 7238 3565 7238 3566 7238 3566 7239 3565 7239 3567 7239 3566 7240 3567 7240 3647 7240 3568 7241 3563 7241 3566 7241 3566 7242 3563 7242 3620 7242 3566 7243 3620 7243 3569 7243 3569 7244 3595 7244 3566 7244 3566 7245 3595 7245 3594 7245 3566 7246 3594 7246 3570 7246 3570 7247 3594 7247 3571 7247 3570 7248 3571 7248 2398 7248 3574 7249 8823 7249 3575 7249 3572 7250 2392 7250 3681 7250 3681 7251 2392 7251 3573 7251 3681 7252 3573 7252 3677 7252 3677 7253 3573 7253 3676 7253 3574 7254 3575 7254 3578 7254 3576 7255 3577 7255 3575 7255 3575 7256 3577 7256 3672 7256 3575 7257 3672 7257 3578 7257 3578 7258 3672 7258 3676 7258 3578 7259 3676 7259 3579 7259 3579 7260 3676 7260 3573 7260 2607 7261 3580 7261 2608 7261 2608 7262 3580 7262 3581 7262 8631 7263 8630 7263 3630 7263 3022 7264 2612 7264 3628 7264 3628 7265 2612 7265 2608 7265 3628 7266 2608 7266 3582 7266 3582 7267 2608 7267 3581 7267 3582 7268 3581 7268 3583 7268 3583 7269 3581 7269 8633 7269 3583 7270 8633 7270 3621 7270 3621 7271 8633 7271 8631 7271 3621 7272 8631 7272 3622 7272 3622 7273 8631 7273 3630 7273 9227 7274 2398 7274 3584 7274 3584 7275 2398 7275 3585 7275 3584 7276 3585 7276 9253 7276 9253 7277 3585 7277 3586 7277 9253 7278 3586 7278 9254 7278 9254 7279 3586 7279 3587 7279 9231 7280 3588 7280 2385 7280 2385 7281 3588 7281 3589 7281 2385 7282 3589 7282 3587 7282 3587 7283 3589 7283 9256 7283 3587 7284 9256 7284 9254 7284 3595 7285 3569 7285 3600 7285 3586 7286 3585 7286 3590 7286 3590 7287 3585 7287 3592 7287 3590 7288 3592 7288 3597 7288 3597 7289 3592 7289 3593 7289 2385 7290 3587 7290 3598 7290 3599 7291 2388 7291 3598 7291 3598 7292 2388 7292 3591 7292 3598 7293 3591 7293 2385 7293 3585 7294 2398 7294 3592 7294 3592 7295 2398 7295 3571 7295 3592 7296 3571 7296 3593 7296 3593 7297 3571 7297 3594 7297 3593 7298 3594 7298 3595 7298 3595 7299 3600 7299 3593 7299 3593 7300 3600 7300 3596 7300 3593 7301 3596 7301 3597 7301 3597 7302 3596 7302 3598 7302 3597 7303 3598 7303 3590 7303 3590 7304 3598 7304 3587 7304 3590 7305 3587 7305 3586 7305 3599 7306 3598 7306 3604 7306 3604 7307 3598 7307 3596 7307 3604 7308 3596 7308 3605 7308 3605 7309 3596 7309 3600 7309 3605 7310 3600 7310 3606 7310 3606 7311 3600 7311 3569 7311 3606 7312 3569 7312 3620 7312 3613 7313 3601 7313 3626 7313 2381 7314 3599 7314 3602 7314 3602 7315 3599 7315 3604 7315 3602 7316 3604 7316 3603 7316 3603 7317 3604 7317 3605 7317 3603 7318 3605 7318 3618 7318 3618 7319 3605 7319 3606 7319 3607 7320 2381 7320 3610 7320 3610 7321 2381 7321 3602 7321 3610 7322 3602 7322 3608 7322 3608 7323 3602 7323 3603 7323 3608 7324 3603 7324 3609 7324 3609 7325 3603 7325 3618 7325 2380 7326 3607 7326 3615 7326 3615 7327 3607 7327 3610 7327 3615 7328 3610 7328 3611 7328 3611 7329 3610 7329 3608 7329 3611 7330 3608 7330 3612 7330 3612 7331 3608 7331 3609 7331 3613 7332 3626 7332 3617 7332 3630 7333 2380 7333 3614 7333 3614 7334 2380 7334 3615 7334 3614 7335 3615 7335 3616 7335 3616 7336 3615 7336 3611 7336 3616 7337 3611 7337 3626 7337 3626 7338 3611 7338 3612 7338 3626 7339 3612 7339 3617 7339 3617 7340 3612 7340 3609 7340 3617 7341 3609 7341 1308 7341 1308 7342 3609 7342 3618 7342 1308 7343 3618 7343 3619 7343 3619 7344 3618 7344 3606 7344 3619 7345 3606 7345 3620 7345 3634 7346 3621 7346 3622 7346 3623 7347 3016 7347 3624 7347 3624 7348 3016 7348 3625 7348 3629 7349 3635 7349 1312 7349 3626 7350 3601 7350 1311 7350 3631 7351 3622 7351 3630 7351 3627 7352 3583 7352 3621 7352 3583 7353 3627 7353 3582 7353 3582 7354 3627 7354 3625 7354 3582 7355 3625 7355 3628 7355 3628 7356 3625 7356 3016 7356 3628 7357 3016 7357 3022 7357 3621 7358 3634 7358 3627 7358 3627 7359 3634 7359 3629 7359 3627 7360 3629 7360 3625 7360 3625 7361 3629 7361 1312 7361 3625 7362 1312 7362 3624 7362 3630 7363 3614 7363 3631 7363 3631 7364 3614 7364 3616 7364 3631 7365 3616 7365 3633 7365 3633 7366 3616 7366 3626 7366 3633 7367 3626 7367 3632 7367 3632 7368 3626 7368 1311 7368 3632 7369 1311 7369 3636 7369 3622 7370 3631 7370 3634 7370 3634 7371 3631 7371 3633 7371 3634 7372 3633 7372 3629 7372 3629 7373 3633 7373 3632 7373 3629 7374 3632 7374 3635 7374 3635 7375 3632 7375 3636 7375 3635 7376 3636 7376 1312 7376 9284 7377 3642 7377 3638 7377 9289 7378 9283 7378 2396 7378 3642 7379 9284 7379 2396 7379 2396 7380 9284 7380 3637 7380 2396 7381 3637 7381 9289 7381 9282 7382 9292 7382 3638 7382 3638 7383 9292 7383 9294 7383 3638 7384 9294 7384 9284 7384 3638 7385 3639 7385 9282 7385 9282 7386 3639 7386 3564 7386 9282 7387 3564 7387 3640 7387 3649 7388 3648 7388 3655 7388 3650 7389 3641 7389 3651 7389 3651 7390 3641 7390 3652 7390 3568 7391 3641 7391 3645 7391 3645 7392 3641 7392 3650 7392 3645 7393 3650 7393 3649 7393 3642 7394 2396 7394 3643 7394 3643 7395 2396 7395 2397 7395 3643 7396 2397 7396 3644 7396 3649 7397 3655 7397 3645 7397 3645 7398 3655 7398 3646 7398 3645 7399 3646 7399 3568 7399 3565 7400 3652 7400 3567 7400 3567 7401 3652 7401 3641 7401 3567 7402 3641 7402 3647 7402 3647 7403 3641 7403 3568 7403 3644 7404 3658 7404 3643 7404 3643 7405 3658 7405 3657 7405 3643 7406 3657 7406 3648 7406 3648 7407 3649 7407 3643 7407 3643 7408 3649 7408 3650 7408 3643 7409 3650 7409 3642 7409 3642 7410 3650 7410 3651 7410 3642 7411 3651 7411 3638 7411 3638 7412 3651 7412 3652 7412 3638 7413 3652 7413 3639 7413 3639 7414 3652 7414 3565 7414 3639 7415 3565 7415 3564 7415 1327 7416 3665 7416 3653 7416 3654 7417 3646 7417 3660 7417 3660 7418 3646 7418 3655 7418 3660 7419 3655 7419 3656 7419 3656 7420 3655 7420 3648 7420 3656 7421 3648 7421 3663 7421 3663 7422 3648 7422 3657 7422 3663 7423 3657 7423 3664 7423 3664 7424 3657 7424 3658 7424 3659 7425 3654 7425 3661 7425 3661 7426 3654 7426 3660 7426 3661 7427 3660 7427 3666 7427 3666 7428 3660 7428 3656 7428 3666 7429 3656 7429 3668 7429 3668 7430 3656 7430 3663 7430 3668 7431 3663 7431 3662 7431 3662 7432 3663 7432 3664 7432 3665 7433 3659 7433 3653 7433 3653 7434 3659 7434 3661 7434 3653 7435 3661 7435 3670 7435 3670 7436 3661 7436 3666 7436 3670 7437 3666 7437 3667 7437 3667 7438 3666 7438 3668 7438 3667 7439 3668 7439 3669 7439 3669 7440 3668 7440 3662 7440 1328 7441 1327 7441 3683 7441 3683 7442 1327 7442 3653 7442 3683 7443 3653 7443 3684 7443 3684 7444 3653 7444 3670 7444 3684 7445 3670 7445 3671 7445 3671 7446 3670 7446 3667 7446 3671 7447 3667 7447 3685 7447 3685 7448 3667 7448 3669 7448 3685 7449 3669 7449 3572 7449 3679 7450 3676 7450 3672 7450 1330 7451 1328 7451 3683 7451 3689 7452 3673 7452 3674 7452 3674 7453 3673 7453 3675 7453 3674 7454 3675 7454 1298 7454 1298 7455 3675 7455 1296 7455 3672 7456 3577 7456 2965 7456 3676 7457 3679 7457 3677 7457 3678 7458 1296 7458 2965 7458 2965 7459 1296 7459 3675 7459 2965 7460 3675 7460 3672 7460 3672 7461 3675 7461 3673 7461 3672 7462 3673 7462 3679 7462 3679 7463 3673 7463 3680 7463 3679 7464 3680 7464 3677 7464 3677 7465 3680 7465 3686 7465 3677 7466 3686 7466 3681 7466 3688 7467 1330 7467 3682 7467 3682 7468 1330 7468 3683 7468 3682 7469 3683 7469 3687 7469 3687 7470 3683 7470 3684 7470 3687 7471 3684 7471 3671 7471 3572 7472 3681 7472 3685 7472 3685 7473 3681 7473 3686 7473 3685 7474 3686 7474 3671 7474 3671 7475 3686 7475 3680 7475 3671 7476 3680 7476 3687 7476 3687 7477 3680 7477 3673 7477 3687 7478 3673 7478 3682 7478 3682 7479 3673 7479 3689 7479 3682 7480 3689 7480 3688 7480 3688 7481 3689 7481 3674 7481 6033 7482 1025 7482 3690 7482 6033 7483 3690 7483 3692 7483 3691 7484 3694 7484 3695 7484 3695 7485 6036 7485 3691 7485 3691 7486 6036 7486 6035 7486 3691 7487 6035 7487 3690 7487 3690 7488 6035 7488 6034 7488 3690 7489 6034 7489 3692 7489 1514 7490 1515 7490 6042 7490 6042 7491 6041 7491 1514 7491 1514 7492 6041 7492 3693 7492 1514 7493 3693 7493 3694 7493 3694 7494 3693 7494 6039 7494 3694 7495 6039 7495 3695 7495 1013 7496 3696 7496 1515 7496 1515 7497 3696 7497 6047 7497 1515 7498 6047 7498 6046 7498 6046 7499 6045 7499 1515 7499 1515 7500 6045 7500 3697 7500 1515 7501 3697 7501 6042 7501 3698 7502 3701 7502 6060 7502 6060 7503 3701 7503 3702 7503 3699 7504 1012 7504 6058 7504 6058 7505 1012 7505 3701 7505 6058 7506 3701 7506 3700 7506 3700 7507 3701 7507 3698 7507 3703 7508 3704 7508 1482 7508 3702 7509 3701 7509 1483 7509 3703 7510 3705 7510 3704 7510 3704 7511 3705 7511 3706 7511 3704 7512 3706 7512 1483 7512 1483 7513 3706 7513 6068 7513 1483 7514 6068 7514 3702 7514 1020 7515 3707 7515 1018 7515 1018 7516 3707 7516 3708 7516 1018 7517 3708 7517 1482 7517 1482 7518 3708 7518 6063 7518 1482 7519 6063 7519 3703 7519 982 7520 999 7520 3709 7520 3709 7521 999 7521 3711 7521 3709 7522 3711 7522 3710 7522 3710 7523 3711 7523 997 7523 3710 7524 997 7524 985 7524 985 7525 997 7525 3712 7525 985 7526 3712 7526 987 7526 987 7527 3712 7527 996 7527 987 7528 996 7528 3713 7528 3713 7529 996 7529 994 7529 3713 7530 994 7530 3714 7530 3714 7531 994 7531 993 7531 3714 7532 993 7532 3715 7532 3715 7533 993 7533 991 7533 3715 7534 991 7534 979 7534 979 7535 991 7535 3716 7535 979 7536 3716 7536 3717 7536 3717 7537 3716 7537 3718 7537 3717 7538 3718 7538 980 7538 980 7539 3718 7539 1000 7539 980 7540 1000 7540 3719 7540 3719 7541 1000 7541 3720 7541 3719 7542 3720 7542 982 7542 982 7543 3720 7543 999 7543 3722 7544 6089 7544 3721 7544 3722 7545 3721 7545 3723 7545 3725 7546 3724 7546 6083 7546 6083 7547 6085 7547 3725 7547 3725 7548 6085 7548 3726 7548 3725 7549 3726 7549 3721 7549 3721 7550 3726 7550 6087 7550 3721 7551 6087 7551 3723 7551 3727 7552 1499 7552 6080 7552 6080 7553 6081 7553 3727 7553 3727 7554 6081 7554 3728 7554 3727 7555 3728 7555 3724 7555 3724 7556 3728 7556 6082 7556 3724 7557 6082 7557 6083 7557 1528 7558 3732 7558 1499 7558 1499 7559 3732 7559 6078 7559 1499 7560 6078 7560 3729 7560 3729 7561 3730 7561 1499 7561 1499 7562 3730 7562 3731 7562 1499 7563 3731 7563 6080 7563 3732 7564 1528 7564 6075 7564 6075 7565 1528 7565 6073 7565 1506 7566 3733 7566 6170 7566 6170 7567 3733 7567 3734 7567 6174 7568 1508 7568 6176 7568 6176 7569 1508 7569 3735 7569 3734 7570 3733 7570 6171 7570 6171 7571 3733 7571 1508 7571 6171 7572 1508 7572 6173 7572 6173 7573 1508 7573 6174 7573 6182 7574 3736 7574 3740 7574 3735 7575 1508 7575 3737 7575 6182 7576 6184 7576 3736 7576 3736 7577 6184 7577 6185 7577 3736 7578 6185 7578 3737 7578 3737 7579 6185 7579 3738 7579 3737 7580 3738 7580 3735 7580 1029 7581 6178 7581 3739 7581 3739 7582 6178 7582 6179 7582 3739 7583 6179 7583 3740 7583 3740 7584 6179 7584 6180 7584 3740 7585 6180 7585 6182 7585 6111 7586 1663 7586 3743 7586 6111 7587 3743 7587 6112 7587 3741 7588 3746 7588 3742 7588 3742 7589 6117 7589 3741 7589 3741 7590 6117 7590 6115 7590 3741 7591 6115 7591 3743 7591 3743 7592 6115 7592 6114 7592 3743 7593 6114 7593 6112 7593 3744 7594 3749 7594 6125 7594 6125 7595 3745 7595 3744 7595 3744 7596 3745 7596 6122 7596 3744 7597 6122 7597 3746 7597 3746 7598 6122 7598 6121 7598 3746 7599 6121 7599 3742 7599 1470 7600 3747 7600 3749 7600 3749 7601 3747 7601 6130 7601 3749 7602 6130 7602 3748 7602 3748 7603 6129 7603 3749 7603 3749 7604 6129 7604 6128 7604 3749 7605 6128 7605 6125 7605 3747 7606 1470 7606 6137 7606 6137 7607 1470 7607 3750 7607 3751 7608 1469 7608 3752 7608 3752 7609 1469 7609 3754 7609 3753 7610 3756 7610 6142 7610 6142 7611 3756 7611 6143 7611 3754 7612 1469 7612 3755 7612 3755 7613 1469 7613 3756 7613 3755 7614 3756 7614 6140 7614 6140 7615 3756 7615 3753 7615 3759 7616 3757 7616 3758 7616 6143 7617 3756 7617 3762 7617 3759 7618 3760 7618 3757 7618 3757 7619 3760 7619 3761 7619 3757 7620 3761 7620 3762 7620 3762 7621 3761 7621 3763 7621 3762 7622 3763 7622 6143 7622 3764 7623 6144 7623 1654 7623 1654 7624 6144 7624 3765 7624 1654 7625 3765 7625 3758 7625 3758 7626 3765 7626 3766 7626 3758 7627 3766 7627 3759 7627 3770 7628 3767 7628 1531 7628 1531 7629 3767 7629 3768 7629 1531 7630 3768 7630 6153 7630 6153 7631 6152 7631 1531 7631 1531 7632 6152 7632 6151 7632 1531 7633 6151 7633 3769 7633 3767 7634 3770 7634 3771 7634 3771 7635 3770 7635 1485 7635 3777 7636 3772 7636 1471 7636 1471 7637 3772 7637 3776 7637 6018 7638 3773 7638 3774 7638 3774 7639 3773 7639 1471 7639 3774 7640 1471 7640 3775 7640 3775 7641 1471 7641 3776 7641 3777 7642 1471 7642 6022 7642 6022 7643 1471 7643 3780 7643 6022 7644 3780 7644 6026 7644 1533 7645 3778 7645 1532 7645 1532 7646 3778 7646 3779 7646 1532 7647 3779 7647 3780 7647 3780 7648 3779 7648 6024 7648 3780 7649 6024 7649 6026 7649 6029 7650 3781 7650 1669 7650 1669 7651 3781 7651 3782 7651 1669 7652 3782 7652 1533 7652 1533 7653 3782 7653 6031 7653 1533 7654 6031 7654 3778 7654 3787 7655 3783 7655 3784 7655 3784 7656 3783 7656 5997 7656 3784 7657 5997 7657 5996 7657 134 7658 3792 7658 127 7658 127 7659 3792 7659 3785 7659 127 7660 3785 7660 3786 7660 3786 7661 3785 7661 3788 7661 3786 7662 3788 7662 3787 7662 3787 7663 3788 7663 3783 7663 3790 7664 1255 7664 6004 7664 6004 7665 3789 7665 3790 7665 3790 7666 3789 7666 3791 7666 3790 7667 3791 7667 134 7667 134 7668 3791 7668 6002 7668 134 7669 6002 7669 3792 7669 114 7670 3793 7670 3794 7670 114 7671 3794 7671 3795 7671 3794 7672 5980 7672 3795 7672 3795 7673 5980 7673 5983 7673 3795 7674 5983 7674 3796 7674 3796 7675 5982 7675 3795 7675 3795 7676 5982 7676 3797 7676 3795 7677 3797 7677 1258 7677 3798 7678 3799 7678 112 7678 112 7679 3799 7679 5979 7679 112 7680 5979 7680 113 7680 113 7681 5979 7681 3800 7681 113 7682 3800 7682 114 7682 114 7683 3800 7683 3793 7683 3799 7684 3798 7684 5978 7684 5978 7685 3798 7685 3801 7685 5978 7686 3801 7686 3802 7686 5937 7687 1678 7687 3807 7687 1462 7688 5940 7688 3803 7688 3803 7689 5940 7689 3804 7689 3803 7690 3804 7690 5939 7690 5939 7691 3805 7691 3803 7691 3803 7692 3805 7692 3806 7692 3803 7693 3806 7693 3807 7693 3807 7694 3806 7694 5936 7694 3807 7695 5936 7695 5937 7695 1465 7696 3808 7696 3809 7696 3809 7697 5944 7697 1465 7697 1465 7698 5944 7698 5943 7698 1465 7699 5943 7699 1462 7699 1462 7700 5943 7700 5941 7700 1462 7701 5941 7701 5940 7701 1537 7702 5392 7702 3808 7702 3808 7703 5392 7703 5945 7703 3808 7704 5945 7704 3809 7704 1463 7705 3815 7705 3810 7705 3810 7706 3815 7706 6095 7706 3811 7707 3813 7707 3812 7707 3812 7708 3813 7708 6100 7708 6095 7709 3815 7709 3814 7709 3814 7710 3815 7710 3813 7710 3814 7711 3813 7711 6098 7711 6098 7712 3813 7712 3811 7712 3816 7713 816 7713 802 7713 802 7714 816 7714 3817 7714 802 7715 3817 7715 3818 7715 3818 7716 3817 7716 813 7716 3818 7717 813 7717 3819 7717 3819 7718 813 7718 3821 7718 3819 7719 3821 7719 3820 7719 3820 7720 3821 7720 3822 7720 3820 7721 3822 7721 3823 7721 3823 7722 3822 7722 812 7722 3823 7723 812 7723 807 7723 807 7724 812 7724 3824 7724 807 7725 3824 7725 798 7725 798 7726 3824 7726 3826 7726 798 7727 3826 7727 3825 7727 3825 7728 3826 7728 3828 7728 3825 7729 3828 7729 3827 7729 3827 7730 3828 7730 3830 7730 3827 7731 3830 7731 3829 7731 3829 7732 3830 7732 3831 7732 3829 7733 3831 7733 800 7733 800 7734 3831 7734 817 7734 800 7735 817 7735 3816 7735 3816 7736 817 7736 816 7736 3843 7737 787 7737 3832 7737 3832 7738 787 7738 3833 7738 3832 7739 3833 7739 774 7739 774 7740 3833 7740 785 7740 774 7741 785 7741 775 7741 775 7742 785 7742 797 7742 775 7743 797 7743 778 7743 778 7744 797 7744 796 7744 778 7745 796 7745 3834 7745 3834 7746 796 7746 3836 7746 3834 7747 3836 7747 3835 7747 3835 7748 3836 7748 795 7748 3835 7749 795 7749 780 7749 780 7750 795 7750 793 7750 780 7751 793 7751 3837 7751 3837 7752 793 7752 791 7752 3837 7753 791 7753 3838 7753 3838 7754 791 7754 3839 7754 3838 7755 3839 7755 770 7755 770 7756 3839 7756 3840 7756 770 7757 3840 7757 3841 7757 3841 7758 3840 7758 3842 7758 3841 7759 3842 7759 3843 7759 3843 7760 3842 7760 787 7760 759 7761 3844 7761 760 7761 760 7762 3844 7762 765 7762 760 7763 765 7763 3845 7763 3845 7764 765 7764 764 7764 3845 7765 764 7765 749 7765 749 7766 764 7766 3846 7766 749 7767 3846 7767 3847 7767 3847 7768 3846 7768 763 7768 3847 7769 763 7769 750 7769 750 7770 763 7770 762 7770 750 7771 762 7771 752 7771 752 7772 762 7772 3848 7772 752 7773 3848 7773 3849 7773 3849 7774 3848 7774 3850 7774 3849 7775 3850 7775 753 7775 753 7776 3850 7776 3852 7776 753 7777 3852 7777 3851 7777 3851 7778 3852 7778 769 7778 3851 7779 769 7779 756 7779 756 7780 769 7780 767 7780 756 7781 767 7781 757 7781 757 7782 767 7782 3853 7782 757 7783 3853 7783 759 7783 759 7784 3853 7784 3844 7784 735 7785 3867 7785 3854 7785 3854 7786 3867 7786 3856 7786 3854 7787 3856 7787 3855 7787 3855 7788 3856 7788 739 7788 3855 7789 739 7789 3857 7789 3857 7790 739 7790 3858 7790 3857 7791 3858 7791 726 7791 726 7792 3858 7792 3859 7792 726 7793 3859 7793 727 7793 727 7794 3859 7794 3861 7794 727 7795 3861 7795 3860 7795 3860 7796 3861 7796 736 7796 3860 7797 736 7797 3862 7797 3862 7798 736 7798 746 7798 3862 7799 746 7799 730 7799 730 7800 746 7800 3863 7800 730 7801 3863 7801 731 7801 731 7802 3863 7802 745 7802 731 7803 745 7803 3864 7803 3864 7804 745 7804 743 7804 3864 7805 743 7805 3865 7805 3865 7806 743 7806 3866 7806 3865 7807 3866 7807 735 7807 735 7808 3866 7808 3867 7808 3879 7809 714 7809 3868 7809 3868 7810 714 7810 713 7810 3868 7811 713 7811 3869 7811 3869 7812 713 7812 3870 7812 3869 7813 3870 7813 3871 7813 3871 7814 3870 7814 723 7814 3871 7815 723 7815 3872 7815 3872 7816 723 7816 3873 7816 3872 7817 3873 7817 3874 7817 3874 7818 3873 7818 3875 7818 3874 7819 3875 7819 709 7819 709 7820 3875 7820 722 7820 709 7821 722 7821 710 7821 710 7822 722 7822 3876 7822 710 7823 3876 7823 711 7823 711 7824 3876 7824 720 7824 711 7825 720 7825 712 7825 712 7826 720 7826 3877 7826 712 7827 3877 7827 703 7827 703 7828 3877 7828 718 7828 703 7829 718 7829 3878 7829 3878 7830 718 7830 716 7830 3878 7831 716 7831 3879 7831 3879 7832 716 7832 714 7832 3880 7833 700 7833 687 7833 687 7834 700 7834 699 7834 687 7835 699 7835 690 7835 690 7836 699 7836 3881 7836 690 7837 3881 7837 3882 7837 3882 7838 3881 7838 698 7838 3882 7839 698 7839 691 7839 691 7840 698 7840 3883 7840 691 7841 3883 7841 3884 7841 3884 7842 3883 7842 3885 7842 3884 7843 3885 7843 3886 7843 3886 7844 3885 7844 3887 7844 3886 7845 3887 7845 682 7845 682 7846 3887 7846 3888 7846 682 7847 3888 7847 3889 7847 3889 7848 3888 7848 695 7848 3889 7849 695 7849 3890 7849 3890 7850 695 7850 694 7850 3890 7851 694 7851 3891 7851 3891 7852 694 7852 693 7852 3891 7853 693 7853 685 7853 685 7854 693 7854 702 7854 685 7855 702 7855 3880 7855 3880 7856 702 7856 700 7856 3892 7857 677 7857 660 7857 660 7858 677 7858 674 7858 660 7859 674 7859 3893 7859 3893 7860 674 7860 673 7860 3893 7861 673 7861 3894 7861 3894 7862 673 7862 672 7862 3894 7863 672 7863 663 7863 663 7864 672 7864 670 7864 663 7865 670 7865 650 7865 650 7866 670 7866 669 7866 650 7867 669 7867 652 7867 652 7868 669 7868 3895 7868 652 7869 3895 7869 654 7869 654 7870 3895 7870 667 7870 654 7871 667 7871 656 7871 656 7872 667 7872 665 7872 656 7873 665 7873 657 7873 657 7874 665 7874 664 7874 657 7875 664 7875 3896 7875 3896 7876 664 7876 3897 7876 3896 7877 3897 7877 3898 7877 3898 7878 3897 7878 3899 7878 3898 7879 3899 7879 3892 7879 3892 7880 3899 7880 677 7880 634 7881 3900 7881 636 7881 636 7882 3900 7882 3902 7882 636 7883 3902 7883 3901 7883 3901 7884 3902 7884 3903 7884 3901 7885 3903 7885 624 7885 624 7886 3903 7886 645 7886 624 7887 645 7887 625 7887 625 7888 645 7888 644 7888 625 7889 644 7889 627 7889 627 7890 644 7890 642 7890 627 7891 642 7891 628 7891 628 7892 642 7892 640 7892 628 7893 640 7893 629 7893 629 7894 640 7894 639 7894 629 7895 639 7895 630 7895 630 7896 639 7896 649 7896 630 7897 649 7897 631 7897 631 7898 649 7898 3904 7898 631 7899 3904 7899 3905 7899 3905 7900 3904 7900 648 7900 3905 7901 648 7901 632 7901 632 7902 648 7902 3906 7902 632 7903 3906 7903 634 7903 634 7904 3906 7904 3900 7904 609 7905 3920 7905 611 7905 611 7906 3920 7906 3907 7906 611 7907 3907 7907 3909 7907 3909 7908 3907 7908 3908 7908 3909 7909 3908 7909 600 7909 600 7910 3908 7910 3910 7910 600 7911 3910 7911 601 7911 601 7912 3910 7912 616 7912 601 7913 616 7913 602 7913 602 7914 616 7914 3911 7914 602 7915 3911 7915 603 7915 603 7916 3911 7916 3912 7916 603 7917 3912 7917 605 7917 605 7918 3912 7918 613 7918 605 7919 613 7919 3913 7919 3913 7920 613 7920 3915 7920 3913 7921 3915 7921 3914 7921 3914 7922 3915 7922 623 7922 3914 7923 623 7923 3916 7923 3916 7924 623 7924 3917 7924 3916 7925 3917 7925 3918 7925 3918 7926 3917 7926 3919 7926 3918 7927 3919 7927 609 7927 609 7928 3919 7928 3920 7928 584 7929 592 7929 572 7929 572 7930 592 7930 589 7930 572 7931 589 7931 3921 7931 3921 7932 589 7932 588 7932 3921 7933 588 7933 573 7933 573 7934 588 7934 3922 7934 573 7935 3922 7935 574 7935 574 7936 3922 7936 586 7936 574 7937 586 7937 3923 7937 3923 7938 586 7938 585 7938 3923 7939 585 7939 576 7939 576 7940 585 7940 3924 7940 576 7941 3924 7941 578 7941 578 7942 3924 7942 597 7942 578 7943 597 7943 580 7943 580 7944 597 7944 596 7944 580 7945 596 7945 581 7945 581 7946 596 7946 3925 7946 581 7947 3925 7947 583 7947 583 7948 3925 7948 594 7948 583 7949 594 7949 3926 7949 3926 7950 594 7950 3927 7950 3926 7951 3927 7951 584 7951 584 7952 3927 7952 592 7952 548 7953 3928 7953 3930 7953 3930 7954 3928 7954 3929 7954 3930 7955 3929 7955 551 7955 551 7956 3929 7956 563 7956 551 7957 563 7957 3931 7957 3931 7958 563 7958 562 7958 3931 7959 562 7959 3932 7959 3932 7960 562 7960 3934 7960 3932 7961 3934 7961 3933 7961 3933 7962 3934 7962 571 7962 3933 7963 571 7963 557 7963 557 7964 571 7964 3935 7964 557 7965 3935 7965 3936 7965 3936 7966 3935 7966 567 7966 3936 7967 567 7967 3937 7967 3937 7968 567 7968 3938 7968 3937 7969 3938 7969 559 7969 559 7970 3938 7970 566 7970 559 7971 566 7971 561 7971 561 7972 566 7972 3939 7972 561 7973 3939 7973 3940 7973 3940 7974 3939 7974 3941 7974 3940 7975 3941 7975 548 7975 548 7976 3941 7976 3928 7976 3947 7977 3946 7977 3942 7977 2321 7978 2322 7978 6774 7978 6774 7979 2322 7979 3947 7979 6774 7980 3947 7980 6766 7980 6766 7981 3947 7981 3942 7981 3950 7982 1993 7982 3945 7982 3944 7983 3958 7983 3945 7983 3959 7984 3948 7984 3943 7984 3943 7985 3948 7985 3958 7985 3944 7986 3945 7986 2322 7986 1993 7987 3946 7987 3945 7987 3945 7988 3946 7988 3947 7988 3945 7989 3947 7989 2322 7989 3958 7990 3948 7990 3945 7990 3945 7991 3948 7991 3949 7991 3945 7992 3949 7992 3950 7992 3951 7993 2317 7993 3952 7993 3952 7994 2317 7994 3954 7994 3952 7995 3954 7995 3953 7995 3953 7996 3954 7996 3964 7996 3953 7997 3964 7997 3955 7997 3955 7998 3964 7998 3956 7998 3955 7999 3956 7999 3960 7999 3960 8000 3956 8000 3957 8000 2322 8001 3951 8001 3944 8001 3944 8002 3951 8002 3952 8002 3944 8003 3952 8003 3958 8003 3958 8004 3952 8004 3953 8004 3958 8005 3953 8005 3943 8005 3943 8006 3953 8006 3955 8006 3943 8007 3955 8007 3959 8007 3959 8008 3955 8008 3960 8008 3961 8009 2315 8009 3962 8009 3961 8010 3962 8010 2317 8010 3974 8011 3957 8011 3963 8011 3963 8012 3957 8012 3956 8012 3963 8013 3956 8013 3972 8013 3972 8014 3956 8014 3964 8014 3972 8015 3964 8015 3962 8015 3962 8016 3964 8016 3954 8016 3962 8017 3954 8017 2317 8017 3981 8018 3965 8018 2313 8018 2313 8019 3966 8019 3981 8019 3981 8020 3966 8020 6804 8020 3981 8021 6804 8021 2003 8021 2003 8022 6804 8022 6803 8022 2003 8023 6803 8023 6813 8023 3968 8024 2308 8024 3970 8024 3970 8025 2308 8025 2311 8025 1915 8026 3975 8026 3967 8026 3967 8027 3975 8027 3971 8027 3973 8028 3968 8028 3978 8028 3978 8029 3968 8029 3970 8029 3978 8030 3970 8030 3969 8030 3969 8031 3970 8031 2311 8031 3969 8032 2311 8032 3965 8032 3973 8033 3978 8033 3971 8033 3971 8034 3978 8034 3979 8034 3971 8035 3979 8035 3967 8035 2315 8036 2308 8036 3962 8036 3962 8037 2308 8037 3968 8037 3962 8038 3968 8038 3972 8038 3972 8039 3968 8039 3973 8039 3972 8040 3973 8040 3963 8040 3963 8041 3973 8041 3971 8041 3963 8042 3971 8042 3974 8042 3974 8043 3971 8043 3975 8043 3967 8044 1997 8044 1915 8044 1997 8045 3967 8045 3980 8045 3969 8046 3976 8046 3978 8046 3978 8047 3976 8047 3977 8047 3978 8048 3977 8048 3979 8048 3981 8049 2003 8049 1994 8049 3967 8050 3979 8050 3980 8050 3980 8051 3979 8051 3977 8051 3980 8052 3977 8052 1994 8052 1994 8053 3977 8053 3976 8053 1994 8054 3976 8054 3981 8054 3981 8055 3976 8055 3969 8055 3981 8056 3969 8056 3965 8056 6477 8057 3994 8057 3982 8057 3982 8058 3994 8058 3992 8058 3982 8059 3992 8059 3983 8059 3983 8060 3992 8060 3984 8060 3984 8061 3992 8061 3987 8061 3984 8062 3987 8062 3985 8062 3986 8063 3987 8063 3992 8063 3988 8064 3997 8064 3989 8064 3989 8065 3997 8065 3990 8065 3989 8066 3990 8066 3991 8066 3994 8067 3988 8067 3992 8067 3992 8068 3988 8068 3989 8068 3992 8069 3989 8069 3986 8069 3986 8070 3989 8070 3991 8070 3986 8071 3991 8071 1971 8071 1971 8072 3991 8072 3990 8072 1971 8073 3990 8073 3993 8073 3993 8074 3990 8074 3995 8074 3993 8075 3995 8075 3072 8075 3998 8076 4003 8076 3996 8076 4001 8077 3999 8077 3072 8077 4004 8078 4003 8078 2071 8078 2071 8079 4003 8079 3998 8079 2071 8080 3998 8080 3994 8080 3072 8081 3995 8081 4001 8081 4001 8082 3995 8082 3990 8082 4001 8083 3990 8083 3996 8083 3996 8084 3990 8084 3997 8084 3996 8085 3997 8085 3998 8085 3998 8086 3997 8086 3988 8086 3998 8087 3988 8087 3994 8087 3065 8088 3999 8088 4000 8088 4000 8089 3999 8089 4001 8089 4000 8090 4001 8090 4005 8090 4005 8091 4001 8091 3996 8091 4005 8092 3996 8092 4002 8092 4002 8093 3996 8093 4003 8093 4002 8094 4003 8094 2065 8094 2065 8095 4003 8095 4004 8095 2063 8096 2067 8096 4011 8096 2065 8097 2063 8097 4002 8097 4002 8098 2063 8098 4011 8098 4002 8099 4011 8099 4005 8099 4005 8100 4011 8100 4010 8100 4005 8101 4010 8101 4000 8101 4000 8102 4010 8102 4008 8102 4000 8103 4008 8103 3065 8103 3065 8104 4008 8104 4006 8104 3066 8105 4006 8105 4007 8105 4007 8106 4006 8106 4008 8106 4007 8107 4008 8107 4009 8107 4009 8108 4008 8108 4010 8108 4009 8109 4010 8109 4012 8109 4012 8110 4010 8110 4011 8110 4012 8111 4011 8111 2060 8111 2060 8112 4011 8112 2067 8112 4013 8113 3066 8113 4017 8113 4017 8114 3066 8114 4007 8114 4017 8115 4007 8115 4014 8115 4014 8116 4007 8116 4009 8116 4014 8117 4009 8117 4015 8117 4015 8118 4009 8118 4012 8118 4015 8119 4012 8119 4022 8119 4022 8120 4012 8120 2060 8120 4022 8121 4021 8121 4015 8121 4015 8122 4021 8122 4016 8122 4015 8123 4016 8123 4014 8123 4014 8124 4016 8124 4017 8124 4013 8125 4017 8125 4018 8125 4018 8126 4017 8126 4016 8126 4018 8127 4016 8127 3128 8127 3128 8128 4016 8128 3126 8128 3126 8129 4016 8129 4019 8129 4019 8130 4016 8130 4021 8130 4019 8131 4021 8131 4020 8131 6517 8132 4020 8132 6515 8132 6515 8133 4020 8133 4021 8133 6515 8134 4021 8134 6514 8134 6514 8135 4021 8135 4022 8135 6514 8136 4022 8136 6518 8136 6412 8137 4023 8137 6395 8137 6395 8138 4023 8138 4030 8138 6395 8139 4030 8139 4024 8139 4024 8140 4030 8140 1974 8140 4024 8141 1974 8141 6396 8141 1979 8142 1974 8142 4030 8142 4038 8143 4028 8143 4025 8143 4025 8144 4028 8144 4029 8144 4025 8145 4029 8145 4041 8145 4041 8146 4029 8146 4042 8146 1976 8147 4026 8147 4035 8147 4035 8148 4026 8148 1978 8148 4035 8149 1978 8149 4038 8149 4038 8150 1978 8150 4027 8150 4038 8151 4027 8151 4028 8151 4028 8152 4027 8152 1979 8152 4028 8153 1979 8153 4029 8153 4029 8154 1979 8154 4030 8154 4029 8155 4030 8155 4042 8155 4042 8156 4030 8156 4023 8156 3085 8157 3083 8157 4043 8157 4034 8158 1976 8158 4035 8158 4040 8159 4031 8159 4032 8159 4037 8160 4050 8160 4051 8160 4040 8161 4032 8161 4039 8161 2075 8162 4033 8162 2081 8162 2081 8163 4033 8163 4046 8163 2081 8164 4046 8164 2079 8164 2079 8165 4046 8165 4032 8165 2079 8166 4032 8166 2080 8166 2080 8167 4032 8167 4031 8167 2080 8168 4031 8168 4023 8168 4034 8169 4035 8169 4036 8169 4047 8170 3085 8170 4051 8170 4051 8171 3085 8171 4043 8171 4051 8172 4043 8172 4037 8172 4037 8173 4043 8173 4044 8173 4037 8174 4044 8174 4045 8174 4035 8175 4038 8175 4039 8175 4039 8176 4038 8176 4025 8176 4039 8177 4025 8177 4040 8177 4040 8178 4025 8178 4041 8178 4040 8179 4041 8179 4031 8179 4031 8180 4041 8180 4042 8180 4031 8181 4042 8181 4023 8181 3083 8182 4036 8182 4043 8182 4043 8183 4036 8183 4035 8183 4043 8184 4035 8184 4044 8184 4044 8185 4035 8185 4039 8185 4044 8186 4039 8186 4045 8186 4045 8187 4039 8187 4032 8187 4045 8188 4032 8188 4037 8188 4037 8189 4032 8189 4046 8189 4037 8190 4046 8190 4050 8190 4050 8191 4046 8191 4033 8191 2076 8192 2078 8192 4049 8192 3068 8193 4047 8193 4051 8193 4052 8194 3070 8194 3069 8194 3068 8195 4051 8195 4048 8195 2075 8196 2076 8196 4033 8196 4033 8197 2076 8197 4049 8197 4033 8198 4049 8198 4050 8198 4050 8199 4049 8199 4054 8199 4050 8200 4054 8200 4051 8200 4051 8201 4054 8201 4052 8201 4051 8202 4052 8202 4048 8202 4048 8203 4052 8203 3069 8203 4056 8204 3070 8204 4057 8204 4057 8205 3070 8205 4052 8205 4057 8206 4052 8206 4053 8206 4053 8207 4052 8207 4054 8207 4053 8208 4054 8208 4060 8208 4060 8209 4054 8209 4049 8209 4060 8210 4049 8210 2073 8210 2073 8211 4049 8211 2078 8211 4055 8212 4056 8212 4058 8212 4058 8213 4056 8213 4057 8213 4058 8214 4057 8214 4064 8214 4064 8215 4057 8215 4053 8215 4064 8216 4053 8216 4061 8216 4061 8217 4053 8217 4060 8217 4061 8218 4060 8218 4059 8218 4059 8219 4060 8219 2073 8219 1970 8220 4065 8220 1969 8220 4061 8221 4059 8221 4067 8221 1972 8222 4055 8222 4058 8222 1972 8223 4058 8223 4062 8223 4065 8224 1970 8224 4062 8224 4062 8225 1970 8225 4063 8225 4062 8226 4063 8226 1972 8226 4058 8227 4064 8227 4062 8227 4062 8228 4064 8228 4061 8228 4062 8229 4061 8229 4065 8229 4065 8230 4061 8230 4067 8230 4065 8231 4067 8231 1969 8231 1969 8232 4067 8232 4066 8232 6447 8233 4066 8233 6449 8233 6449 8234 4066 8234 4067 8234 6449 8235 4067 8235 6451 8235 6451 8236 4067 8236 4059 8236 6451 8237 4059 8237 6452 8237 4068 8238 4069 8238 2327 8238 2327 8239 6753 8239 4068 8239 4068 8240 6753 8240 4070 8240 4068 8241 4070 8241 4076 8241 4076 8242 4070 8242 6754 8242 4076 8243 6754 8243 6762 8243 4086 8244 4075 8244 4071 8244 4085 8245 4069 8245 4068 8245 4085 8246 4068 8246 4086 8246 4072 8247 4071 8247 1990 8247 1990 8248 4071 8248 4075 8248 1990 8249 4075 8249 1991 8249 4072 8250 1990 8250 4089 8250 4089 8251 1990 8251 4074 8251 4089 8252 4074 8252 4073 8252 4073 8253 4074 8253 1987 8253 4073 8254 1987 8254 1922 8254 4086 8255 4068 8255 4075 8255 4075 8256 4068 8256 4076 8256 4075 8257 4076 8257 1991 8257 4069 8258 4087 8258 4077 8258 4077 8259 4087 8259 4083 8259 4077 8260 4083 8260 2326 8260 2326 8261 4083 8261 4078 8261 2326 8262 4078 8262 2325 8262 1897 8263 4079 8263 4080 8263 4080 8264 4079 8264 4081 8264 4079 8265 4078 8265 4081 8265 4081 8266 4078 8266 4083 8266 4081 8267 4083 8267 4082 8267 4082 8268 4083 8268 4087 8268 1924 8269 4088 8269 4084 8269 4084 8270 4088 8270 4073 8270 4084 8271 4073 8271 1922 8271 4069 8272 4085 8272 4087 8272 4087 8273 4085 8273 4086 8273 4087 8274 4086 8274 4082 8274 4082 8275 4086 8275 4071 8275 4082 8276 4071 8276 4072 8276 1924 8277 4080 8277 4088 8277 4088 8278 4080 8278 4081 8278 4088 8279 4081 8279 4073 8279 4073 8280 4081 8280 4082 8280 4073 8281 4082 8281 4089 8281 4089 8282 4082 8282 4072 8282 1896 8283 1492 8283 1897 8283 1897 8284 1492 8284 4079 8284 1491 8285 2325 8285 1492 8285 1492 8286 2325 8286 4078 8286 1492 8287 4078 8287 4079 8287 4091 8288 1995 8288 2005 8288 6832 8289 4093 8289 4090 8289 4090 8290 4093 8290 4091 8290 4090 8291 4091 8291 6824 8291 6824 8292 4091 8292 2005 8292 4092 8293 4096 8293 1998 8293 4107 8294 1916 8294 1996 8294 4091 8295 4093 8295 4105 8295 4094 8296 4095 8296 4105 8296 4105 8297 4095 8297 4096 8297 4105 8298 4096 8298 4091 8298 4091 8299 4096 8299 4092 8299 4091 8300 4092 8300 1995 8300 1998 8301 4096 8301 4097 8301 4097 8302 4096 8302 4095 8302 4097 8303 4095 8303 1996 8303 1996 8304 4095 8304 4094 8304 1996 8305 4094 8305 4107 8305 2307 8306 4098 8306 4099 8306 4099 8307 4098 8307 4112 8307 4099 8308 4112 8308 4100 8308 4100 8309 4112 8309 4101 8309 4100 8310 4101 8310 4106 8310 4106 8311 4101 8311 4103 8311 4106 8312 4103 8312 4102 8312 4102 8313 4103 8313 4104 8313 4093 8314 2307 8314 4105 8314 4105 8315 2307 8315 4099 8315 4105 8316 4099 8316 4094 8316 4094 8317 4099 8317 4100 8317 4094 8318 4100 8318 4107 8318 4107 8319 4100 8319 4106 8319 4107 8320 4106 8320 1916 8320 1916 8321 4106 8321 4102 8321 4114 8322 2301 8322 4113 8322 1910 8323 4108 8323 4103 8323 4103 8324 4108 8324 4109 8324 4103 8325 4109 8325 4104 8325 4110 8326 1910 8326 4129 8326 4129 8327 1910 8327 4103 8327 4129 8328 4103 8328 4111 8328 4111 8329 4103 8329 4101 8329 4111 8330 4101 8330 4113 8330 4113 8331 4101 8331 4112 8331 4113 8332 4112 8332 4114 8332 4114 8333 4112 8333 4098 8333 4115 8334 6875 8334 4142 8334 4115 8335 4142 8335 4116 8335 4142 8336 4135 8336 4116 8336 4116 8337 4135 8337 2299 8337 4116 8338 2299 8338 6887 8338 4117 8339 2299 8339 4118 8339 2301 8340 4133 8340 4119 8340 4123 8341 1903 8341 4120 8341 1902 8342 1901 8342 4130 8342 4130 8343 1901 8343 4131 8343 4123 8344 4121 8344 4132 8344 4122 8345 4123 8345 4124 8345 4124 8346 4123 8346 4132 8346 4124 8347 4132 8347 4127 8347 4127 8348 4132 8348 4125 8348 4127 8349 4125 8349 4126 8349 4126 8350 4125 8350 4134 8350 4134 8351 4117 8351 4126 8351 4126 8352 4117 8352 4118 8352 4126 8353 4118 8353 4127 8353 4127 8354 4118 8354 4136 8354 4127 8355 4136 8355 4124 8355 4124 8356 4136 8356 4138 8356 4124 8357 4138 8357 4122 8357 2301 8358 4119 8358 4113 8358 4113 8359 4119 8359 4128 8359 4113 8360 4128 8360 4111 8360 4111 8361 4128 8361 4130 8361 4111 8362 4130 8362 4129 8362 4129 8363 4130 8363 4131 8363 4129 8364 4131 8364 4110 8364 4120 8365 1902 8365 4123 8365 4123 8366 1902 8366 4130 8366 4123 8367 4130 8367 4121 8367 4121 8368 4130 8368 4128 8368 4121 8369 4128 8369 4132 8369 4132 8370 4128 8370 4119 8370 4132 8371 4119 8371 4125 8371 4125 8372 4119 8372 4133 8372 4125 8373 4133 8373 4134 8373 4118 8374 2299 8374 4135 8374 4118 8375 4135 8375 4136 8375 4136 8376 4135 8376 4137 8376 4136 8377 4137 8377 4138 8377 4138 8378 4137 8378 4143 8378 4138 8379 4143 8379 4122 8379 4139 8380 4140 8380 4123 8380 4123 8381 4140 8381 4141 8381 4123 8382 4141 8382 1903 8382 4135 8383 4142 8383 4137 8383 4137 8384 4142 8384 1999 8384 4137 8385 1999 8385 4143 8385 4143 8386 1999 8386 4139 8386 4143 8387 4139 8387 4122 8387 4122 8388 4139 8388 4123 8388 4144 8389 2000 8389 2002 8389 4145 8390 4157 8390 6908 8390 6908 8391 4157 8391 4144 8391 6908 8392 4144 8392 4146 8392 4146 8393 4144 8393 2002 8393 4147 8394 4152 8394 4150 8394 4148 8395 1904 8395 4153 8395 4144 8396 4157 8396 4150 8396 4150 8397 4157 8397 4149 8397 4150 8398 4149 8398 4147 8398 2000 8399 4144 8399 2001 8399 2001 8400 4144 8400 4150 8400 2001 8401 4150 8401 4151 8401 4151 8402 4150 8402 4152 8402 4151 8403 4152 8403 4153 8403 4153 8404 4152 8404 4154 8404 4153 8405 4154 8405 4148 8405 1909 8406 4155 8406 4161 8406 1905 8407 1904 8407 4148 8407 1905 8408 4148 8408 1908 8408 4162 8409 4156 8409 4161 8409 4161 8410 4156 8410 4170 8410 4161 8411 4170 8411 1909 8411 1909 8412 4170 8412 4171 8412 4147 8413 4149 8413 4163 8413 4163 8414 4149 8414 4157 8414 4157 8415 4158 8415 4163 8415 4163 8416 4158 8416 4159 8416 4163 8417 4159 8417 4165 8417 4165 8418 4159 8418 2297 8418 4165 8419 2297 8419 4160 8419 4160 8420 2297 8420 4167 8420 4155 8421 1908 8421 4161 8421 4161 8422 1908 8422 4148 8422 4161 8423 4148 8423 4162 8423 4162 8424 4148 8424 4154 8424 4162 8425 4154 8425 4152 8425 4152 8426 4147 8426 4162 8426 4162 8427 4147 8427 4163 8427 4162 8428 4163 8428 4156 8428 4156 8429 4163 8429 4165 8429 4156 8430 4165 8430 4164 8430 4164 8431 4165 8431 4160 8431 4160 8432 4167 8432 4166 8432 4166 8433 4167 8433 4168 8433 4166 8434 4168 8434 4169 8434 4169 8435 4168 8435 4184 8435 4160 8436 4166 8436 4164 8436 4164 8437 4166 8437 4175 8437 4164 8438 4175 8438 4156 8438 4156 8439 4175 8439 4174 8439 4156 8440 4174 8440 4170 8440 4170 8441 4174 8441 4173 8441 4170 8442 4173 8442 4171 8442 4172 8443 4173 8443 4188 8443 4188 8444 4173 8444 4174 8444 4188 8445 4174 8445 4190 8445 4190 8446 4174 8446 4175 8446 4190 8447 4175 8447 4191 8447 4191 8448 4175 8448 4166 8448 4191 8449 4166 8449 4192 8449 4192 8450 4166 8450 4169 8450 6955 8451 6947 8451 3118 8451 3118 8452 4205 8452 6955 8452 6955 8453 4205 8453 4202 8453 6955 8454 4202 8454 2287 8454 4176 8455 4189 8455 4195 8455 4194 8456 4177 8456 4189 8456 4189 8457 4177 8457 4172 8457 4206 8458 1934 8458 4193 8458 4169 8459 4196 8459 4192 8459 4192 8460 4196 8460 4195 8460 4181 8461 4178 8461 4182 8461 4182 8462 4178 8462 4204 8462 4182 8463 4204 8463 4179 8463 4179 8464 4204 8464 4211 8464 4179 8465 4211 8465 4180 8465 4180 8466 4211 8466 4210 8466 4180 8467 4210 8467 4208 8467 4181 8468 4182 8468 4183 8468 4183 8469 4182 8469 4200 8469 4183 8470 4200 8470 4202 8470 4169 8471 4184 8471 4196 8471 4196 8472 4184 8472 2286 8472 4196 8473 2286 8473 4199 8473 4199 8474 2286 8474 4185 8474 4199 8475 4185 8475 4201 8475 4208 8476 4186 8476 4180 8476 4180 8477 4186 8477 4187 8477 4180 8478 4187 8478 4179 8478 4179 8479 4187 8479 4197 8479 4179 8480 4197 8480 4182 8480 4182 8481 4197 8481 4198 8481 4182 8482 4198 8482 4200 8482 4172 8483 4188 8483 4189 8483 4189 8484 4188 8484 4190 8484 4189 8485 4190 8485 4195 8485 4195 8486 4190 8486 4191 8486 4195 8487 4191 8487 4192 8487 4193 8488 4194 8488 4206 8488 4206 8489 4194 8489 4189 8489 4206 8490 4189 8490 4186 8490 4186 8491 4189 8491 4176 8491 4186 8492 4176 8492 4187 8492 4187 8493 4176 8493 4195 8493 4187 8494 4195 8494 4197 8494 4197 8495 4195 8495 4196 8495 4197 8496 4196 8496 4198 8496 4198 8497 4196 8497 4199 8497 4198 8498 4199 8498 4200 8498 4200 8499 4199 8499 4201 8499 4200 8500 4201 8500 4202 8500 4213 8501 4203 8501 4209 8501 4211 8502 4204 8502 4209 8502 4178 8503 4181 8503 4205 8503 4205 8504 4181 8504 4183 8504 4205 8505 4183 8505 4202 8505 1934 8506 4206 8506 4207 8506 4207 8507 4206 8507 4186 8507 4207 8508 4186 8508 4203 8508 4203 8509 4186 8509 4208 8509 4203 8510 4208 8510 4209 8510 4209 8511 4208 8511 4210 8511 4209 8512 4210 8512 4211 8512 4178 8513 4205 8513 4204 8513 4204 8514 4205 8514 3118 8514 4204 8515 3118 8515 4209 8515 4209 8516 3118 8516 4212 8516 4209 8517 4212 8517 4213 8517 2197 8518 2198 8518 8075 8518 8075 8519 2198 8519 4236 8519 8075 8520 4236 8520 8080 8520 8080 8521 4236 8521 8078 8521 8078 8522 4236 8522 4214 8522 8078 8523 4214 8523 4217 8523 4234 8524 4215 8524 2337 8524 2337 8525 8090 8525 4234 8525 4234 8526 8090 8526 8085 8526 4234 8527 8085 8527 4214 8527 4214 8528 8085 8528 4216 8528 4214 8529 4216 8529 4217 8529 4229 8530 4218 8530 3114 8530 4237 8531 4690 8531 4233 8531 4219 8532 4220 8532 4226 8532 4681 8533 4682 8533 4221 8533 4221 8534 4682 8534 3111 8534 4681 8535 4221 8535 4680 8535 4680 8536 4221 8536 4230 8536 4680 8537 4230 8537 4222 8537 4222 8538 4230 8538 4224 8538 4222 8539 4224 8539 4223 8539 4223 8540 4224 8540 4225 8540 4223 8541 4225 8541 4675 8541 4675 8542 4225 8542 4227 8542 4675 8543 4227 8543 4676 8543 4220 8544 4678 8544 4226 8544 4226 8545 4678 8545 4677 8545 4226 8546 4677 8546 4227 8546 4227 8547 4677 8547 4228 8547 4227 8548 4228 8548 4676 8548 4232 8549 4231 8549 3117 8549 4218 8550 4229 8550 4231 8550 4231 8551 4229 8551 3116 8551 4231 8552 3116 8552 3117 8552 3111 8553 3112 8553 4221 8553 4221 8554 3112 8554 3114 8554 4221 8555 3114 8555 4230 8555 4230 8556 3114 8556 4218 8556 4230 8557 4218 8557 4224 8557 4224 8558 4218 8558 4231 8558 4224 8559 4231 8559 4225 8559 4225 8560 4231 8560 4232 8560 4225 8561 4232 8561 4227 8561 4227 8562 4232 8562 4235 8562 4227 8563 4235 8563 4226 8563 4226 8564 4235 8564 4233 8564 4226 8565 4233 8565 4219 8565 4219 8566 4233 8566 4690 8566 3117 8567 4215 8567 4232 8567 4232 8568 4215 8568 4234 8568 4232 8569 4234 8569 4235 8569 4235 8570 4234 8570 4214 8570 4235 8571 4214 8571 4233 8571 4233 8572 4214 8572 4236 8572 4233 8573 4236 8573 4237 8573 4237 8574 4236 8574 2198 8574 4251 8575 4274 8575 4238 8575 4239 8576 3045 8576 4242 8576 4262 8577 4240 8577 4241 8577 4274 8578 4251 8578 4275 8578 4240 8579 4239 8579 4241 8579 4241 8580 4239 8580 4242 8580 4241 8581 4242 8581 4264 8581 4264 8582 4242 8582 4243 8582 4264 8583 4243 8583 4266 8583 4266 8584 4243 8584 4244 8584 4266 8585 4244 8585 4269 8585 4256 8586 4244 8586 4666 8586 4666 8587 4244 8587 4243 8587 4666 8588 4243 8588 4664 8588 4664 8589 4243 8589 4242 8589 4664 8590 4242 8590 4245 8590 4245 8591 4242 8591 3045 8591 4245 8592 3045 8592 3044 8592 4246 8593 2277 8593 4247 8593 4247 8594 2277 8594 4259 8594 4247 8595 4259 8595 4258 8595 4258 8596 4249 8596 4247 8596 4247 8597 4249 8597 4250 8597 4247 8598 4250 8598 4246 8598 4258 8599 4248 8599 4249 8599 4249 8600 4248 8600 4260 8600 4249 8601 4260 8601 4250 8601 4250 8602 4260 8602 4261 8602 4250 8603 4261 8603 4246 8603 4246 8604 4261 8604 2278 8604 4251 8605 4263 8605 4275 8605 4275 8606 4263 8606 4265 8606 4275 8607 4265 8607 4252 8607 4252 8608 4265 8608 4267 8608 4252 8609 4267 8609 4277 8609 4277 8610 4267 8610 4268 8610 4277 8611 4268 8611 4272 8611 4272 8612 4268 8612 4254 8612 4272 8613 4254 8613 4253 8613 4253 8614 4254 8614 4255 8614 4256 8615 4257 8615 4244 8615 4244 8616 4257 8616 4248 8616 4244 8617 4248 8617 4269 8617 4269 8618 4248 8618 4258 8618 4269 8619 4258 8619 4270 8619 4270 8620 4258 8620 4259 8620 4257 8621 4669 8621 4248 8621 4248 8622 4669 8622 4668 8622 4248 8623 4668 8623 4260 8623 4260 8624 4668 8624 4667 8624 4260 8625 4667 8625 4261 8625 4261 8626 4667 8626 4689 8626 4261 8627 4689 8627 2278 8627 4238 8628 4262 8628 4251 8628 4251 8629 4262 8629 4241 8629 4251 8630 4241 8630 4263 8630 4263 8631 4241 8631 4264 8631 4263 8632 4264 8632 4265 8632 4265 8633 4264 8633 4266 8633 4265 8634 4266 8634 4267 8634 4267 8635 4266 8635 4269 8635 4267 8636 4269 8636 4268 8636 4268 8637 4269 8637 4270 8637 4268 8638 4270 8638 4254 8638 4254 8639 4270 8639 4259 8639 4254 8640 4259 8640 4255 8640 4255 8641 4259 8641 2277 8641 4276 8642 4277 8642 4271 8642 4271 8643 4277 8643 4272 8643 4271 8644 4272 8644 2260 8644 2260 8645 4272 8645 4253 8645 3036 8646 4238 8646 4273 8646 4273 8647 4238 8647 4274 8647 4273 8648 4274 8648 4278 8648 4278 8649 4274 8649 4275 8649 4278 8650 4275 8650 4276 8650 4276 8651 4275 8651 4252 8651 4276 8652 4252 8652 4277 8652 4290 8653 4283 8653 4289 8653 4273 8654 4278 8654 4284 8654 4276 8655 4271 8655 4285 8655 4285 8656 4271 8656 4279 8656 4285 8657 4279 8657 4280 8657 4280 8658 4279 8658 4281 8658 3036 8659 4273 8659 4289 8659 3036 8660 4289 8660 4282 8660 4282 8661 4289 8661 4283 8661 4282 8662 4283 8662 3038 8662 4278 8663 4276 8663 4284 8663 4284 8664 4276 8664 4285 8664 4284 8665 4285 8665 4286 8665 4286 8666 4285 8666 4280 8666 4286 8667 4280 8667 4287 8667 4287 8668 4280 8668 4281 8668 4287 8669 4281 8669 4288 8669 4273 8670 4284 8670 4289 8670 4289 8671 4284 8671 4286 8671 4289 8672 4286 8672 4290 8672 4290 8673 4286 8673 4287 8673 4290 8674 4287 8674 4291 8674 4291 8675 4287 8675 4288 8675 4291 8676 4288 8676 1095 8676 4302 8677 4306 8677 4300 8677 4308 8678 4307 8678 4300 8678 4308 8679 4300 8679 4309 8679 1095 8680 4304 8680 4291 8680 4301 8681 1089 8681 4300 8681 4300 8682 1089 8682 4292 8682 1088 8683 1087 8683 4300 8683 4296 8684 4300 8684 1086 8684 4316 8685 4315 8685 4295 8685 4332 8686 4329 8686 4293 8686 4293 8687 4329 8687 4294 8687 4293 8688 4294 8688 4305 8688 4315 8689 4313 8689 4295 8689 4295 8690 4313 8690 4309 8690 4295 8691 4309 8691 4300 8691 4298 8692 4316 8692 4297 8692 4297 8693 4316 8693 4295 8693 4297 8694 4295 8694 4300 8694 4300 8695 4296 8695 4297 8695 4297 8696 4296 8696 1083 8696 4297 8697 1083 8697 4298 8697 4298 8698 1083 8698 4299 8698 4298 8699 4299 8699 4316 8699 1087 8700 1086 8700 4300 8700 4292 8701 1088 8701 4300 8701 1092 8702 1090 8702 4306 8702 4306 8703 1090 8703 4300 8703 4301 8704 4300 8704 1090 8704 4307 8705 4302 8705 4300 8705 4304 8706 4305 8706 4291 8706 4291 8707 4305 8707 4303 8707 4291 8708 4303 8708 4290 8708 4290 8709 4303 8709 4283 8709 4305 8710 4294 8710 4303 8710 4303 8711 4294 8711 3038 8711 4303 8712 3038 8712 4283 8712 1095 8713 1092 8713 4304 8713 4304 8714 1092 8714 4306 8714 4304 8715 4306 8715 4305 8715 4305 8716 4306 8716 4302 8716 4305 8717 4302 8717 4293 8717 4293 8718 4302 8718 4307 8718 4293 8719 4307 8719 4332 8719 4332 8720 4307 8720 4308 8720 4332 8721 4308 8721 4334 8721 4334 8722 4308 8722 4309 8722 4334 8723 4309 8723 4312 8723 4312 8724 4309 8724 4313 8724 4299 8725 4310 8725 4316 8725 4316 8726 4310 8726 4314 8726 4310 8727 2251 8727 4314 8727 4314 8728 2251 8728 4320 8728 4314 8729 4320 8729 4311 8729 4311 8730 4320 8730 4319 8730 4311 8731 4319 8731 4333 8731 4333 8732 4312 8732 4311 8732 4311 8733 4312 8733 4313 8733 4311 8734 4313 8734 4314 8734 4314 8735 4313 8735 4315 8735 4314 8736 4315 8736 4316 8736 4327 8737 4328 8737 4335 8737 4335 8738 4328 8738 4330 8738 4335 8739 4330 8739 4317 8739 4317 8740 4330 8740 4331 8740 4317 8741 4331 8741 4339 8741 4339 8742 4331 8742 4333 8742 4339 8743 4333 8743 4318 8743 4318 8744 4333 8744 4319 8744 4318 8745 4319 8745 4341 8745 4341 8746 4319 8746 4320 8746 4341 8747 4320 8747 2255 8747 2255 8748 4320 8748 2251 8748 2253 8749 2249 8749 4340 8749 4340 8750 2249 8750 4321 8750 4340 8751 4321 8751 4322 8751 4322 8752 4321 8752 4323 8752 4322 8753 4323 8753 4338 8753 4338 8754 4323 8754 4324 8754 4338 8755 4324 8755 4337 8755 4337 8756 4324 8756 4325 8756 4337 8757 4325 8757 4336 8757 3032 8758 3035 8758 4326 8758 4326 8759 3035 8759 3038 8759 4326 8760 3038 8760 4294 8760 3031 8761 3032 8761 4327 8761 4327 8762 3032 8762 4326 8762 4327 8763 4326 8763 4328 8763 4328 8764 4326 8764 4294 8764 4328 8765 4294 8765 4330 8765 4330 8766 4294 8766 4329 8766 4330 8767 4329 8767 4331 8767 4331 8768 4329 8768 4332 8768 4331 8769 4332 8769 4333 8769 4333 8770 4332 8770 4334 8770 4333 8771 4334 8771 4312 8771 3052 8772 3031 8772 4359 8772 4359 8773 3031 8773 4327 8773 4359 8774 4327 8774 4336 8774 4336 8775 4327 8775 4335 8775 4336 8776 4335 8776 4337 8776 4337 8777 4335 8777 4317 8777 4337 8778 4317 8778 4338 8778 4338 8779 4317 8779 4339 8779 4338 8780 4339 8780 4322 8780 4322 8781 4339 8781 4318 8781 4322 8782 4318 8782 4340 8782 4340 8783 4318 8783 4341 8783 4340 8784 4341 8784 2253 8784 2253 8785 4341 8785 2255 8785 4342 8786 4343 8786 4345 8786 4345 8787 4343 8787 3054 8787 4345 8788 3054 8788 3034 8788 4355 8789 4351 8789 4344 8789 4344 8790 4351 8790 2244 8790 4350 8791 4323 8791 2243 8791 2243 8792 4323 8792 4321 8792 2243 8793 4321 8793 2249 8793 4342 8794 4345 8794 4346 8794 4346 8795 4345 8795 4349 8795 4346 8796 4349 8796 4356 8796 3034 8797 4347 8797 4345 8797 4345 8798 4347 8798 4348 8798 4345 8799 4348 8799 4349 8799 4349 8800 4348 8800 4357 8800 4349 8801 4357 8801 4356 8801 2243 8802 2244 8802 4350 8802 4350 8803 2244 8803 4351 8803 4350 8804 4351 8804 4358 8804 4364 8805 4343 8805 4365 8805 4365 8806 4343 8806 4342 8806 4365 8807 4342 8807 4352 8807 4352 8808 4342 8808 4346 8808 4352 8809 4346 8809 4368 8809 4368 8810 4346 8810 4356 8810 4368 8811 4356 8811 4370 8811 4370 8812 4356 8812 4354 8812 4370 8813 4354 8813 4353 8813 4353 8814 4354 8814 4362 8814 4359 8815 4336 8815 4358 8815 4358 8816 4336 8816 4325 8816 4358 8817 4325 8817 4350 8817 4350 8818 4325 8818 4324 8818 4350 8819 4324 8819 4323 8819 4363 8820 4362 8820 4344 8820 4344 8821 4362 8821 4354 8821 4344 8822 4354 8822 4355 8822 4355 8823 4354 8823 4356 8823 4355 8824 4356 8824 4351 8824 4351 8825 4356 8825 4357 8825 4351 8826 4357 8826 4358 8826 4358 8827 4357 8827 4348 8827 4358 8828 4348 8828 4359 8828 4359 8829 4348 8829 4347 8829 4359 8830 4347 8830 3052 8830 4366 8831 4360 8831 4364 8831 4361 8832 4362 8832 1541 8832 1541 8833 4362 8833 4363 8833 4364 8834 4365 8834 4366 8834 4366 8835 4365 8835 4352 8835 4366 8836 4352 8836 4367 8836 4367 8837 4352 8837 4368 8837 4367 8838 4368 8838 4369 8838 4369 8839 4368 8839 4370 8839 4369 8840 4370 8840 4361 8840 4361 8841 4370 8841 4353 8841 4361 8842 4353 8842 4362 8842 7224 8843 4371 8843 7228 8843 7228 8844 4371 8844 4372 8844 7228 8845 4372 8845 7229 8845 7229 8846 4372 8846 7242 8846 7242 8847 4372 8847 4400 8847 7242 8848 4400 8848 7241 8848 7241 8849 4400 8849 4373 8849 4373 8850 4400 8850 4374 8850 4373 8851 4374 8851 7230 8851 7230 8852 4374 8852 7251 8852 7251 8853 4374 8853 4375 8853 7251 8854 4375 8854 7253 8854 4712 8855 4376 8855 4377 8855 4699 8856 4375 8856 4374 8856 4378 8857 4715 8857 4395 8857 4395 8858 4715 8858 4379 8858 4395 8859 4379 8859 4380 8859 4393 8860 4382 8860 4713 8860 4393 8861 4394 8861 4382 8861 4382 8862 4394 8862 4381 8862 4382 8863 4381 8863 4383 8863 4383 8864 4381 8864 4397 8864 4383 8865 4397 8865 4384 8865 4384 8866 4397 8866 4385 8866 4384 8867 4385 8867 4386 8867 4386 8868 4385 8868 4377 8868 4386 8869 4377 8869 4387 8869 4387 8870 4377 8870 4376 8870 4389 8871 1878 8871 4388 8871 4388 8872 4712 8872 4389 8872 4389 8873 4712 8873 4377 8873 4389 8874 4377 8874 4398 8874 4398 8875 4377 8875 4385 8875 3108 8876 4390 8876 4391 8876 4391 8877 4390 8877 4392 8877 4396 8878 4371 8878 4392 8878 4392 8879 4371 8879 3105 8879 4392 8880 3105 8880 4391 8880 4713 8881 4378 8881 4393 8881 4393 8882 4378 8882 4395 8882 4393 8883 4395 8883 4394 8883 4394 8884 4395 8884 4399 8884 4394 8885 4399 8885 4381 8885 4381 8886 4399 8886 4396 8886 4381 8887 4396 8887 4397 8887 4397 8888 4396 8888 4392 8888 4397 8889 4392 8889 4385 8889 4385 8890 4392 8890 4390 8890 4385 8891 4390 8891 4398 8891 4398 8892 4390 8892 3108 8892 4380 8893 4699 8893 4395 8893 4395 8894 4699 8894 4374 8894 4395 8895 4374 8895 4399 8895 4399 8896 4374 8896 4400 8896 4399 8897 4400 8897 4396 8897 4396 8898 4400 8898 4372 8898 4396 8899 4372 8899 4371 8899 4425 8900 4435 8900 4401 8900 4427 8901 4419 8901 4402 8901 4402 8902 4419 8902 4708 8902 4402 8903 4708 8903 4426 8903 4403 8904 4404 8904 4710 8904 4710 8905 4404 8905 4405 8905 4710 8906 4405 8906 4406 8906 4406 8907 4405 8907 4426 8907 4406 8908 4426 8908 4709 8908 4709 8909 4426 8909 4708 8909 4407 8910 4408 8910 4409 8910 4409 8911 4408 8911 4410 8911 4407 8912 4425 8912 4408 8912 4408 8913 4425 8913 4401 8913 4408 8914 4401 8914 4410 8914 4410 8915 4401 8915 4437 8915 4424 8916 4411 8916 4412 8916 4412 8917 4411 8917 4413 8917 4412 8918 4413 8918 4429 8918 4429 8919 4413 8919 4422 8919 4429 8920 4422 8920 4430 8920 4430 8921 4422 8921 4420 8921 4414 8922 2131 8922 4415 8922 4415 8923 2131 8923 2135 8923 4415 8924 2135 8924 2134 8924 2134 8925 4701 8925 4415 8925 4415 8926 4701 8926 4416 8926 4415 8927 4416 8927 4417 8927 4416 8928 4703 8928 4417 8928 4417 8929 4703 8929 4698 8929 4417 8930 4698 8930 4428 8930 4428 8931 4698 8931 4418 8931 4428 8932 4418 8932 4427 8932 4427 8933 4418 8933 4705 8933 4427 8934 4705 8934 4419 8934 4433 8935 4420 8935 4421 8935 4421 8936 4420 8936 4422 8936 4421 8937 4422 8937 4423 8937 4423 8938 4422 8938 4413 8938 4423 8939 4413 8939 4437 8939 4437 8940 4413 8940 4411 8940 4437 8941 4411 8941 4410 8941 4410 8942 4411 8942 4424 8942 4410 8943 4424 8943 4409 8943 4405 8944 4425 8944 4426 8944 4426 8945 4425 8945 4407 8945 4426 8946 4407 8946 4402 8946 4402 8947 4407 8947 4409 8947 4402 8948 4409 8948 4427 8948 4427 8949 4409 8949 4424 8949 4427 8950 4424 8950 4428 8950 4428 8951 4424 8951 4412 8951 4428 8952 4412 8952 4417 8952 4417 8953 4412 8953 4429 8953 4417 8954 4429 8954 4415 8954 4415 8955 4429 8955 4430 8955 4415 8956 4430 8956 4414 8956 4414 8957 4430 8957 4420 8957 4414 8958 4420 8958 4431 8958 4431 8959 4420 8959 4433 8959 4431 8960 4433 8960 2136 8960 4439 8961 4432 8961 4433 8961 4433 8962 4432 8962 4434 8962 4433 8963 4434 8963 2136 8963 4435 8964 4436 8964 4401 8964 4401 8965 4436 8965 4440 8965 4401 8966 4440 8966 4437 8966 4437 8967 4440 8967 4438 8967 4437 8968 4438 8968 4423 8968 4423 8969 4438 8969 4439 8969 4423 8970 4439 8970 4421 8970 4421 8971 4439 8971 4433 8971 4440 8972 4436 8972 1879 8972 4473 8973 2145 8973 4446 8973 4446 8974 2145 8974 4447 8974 4440 8975 4449 8975 4438 8975 4438 8976 4449 8976 4442 8976 4438 8977 4442 8977 4439 8977 4432 8978 4439 8978 4441 8978 4441 8979 4439 8979 4442 8979 4441 8980 4442 8980 4448 8980 4444 8981 4445 8981 4443 8981 4443 8982 4445 8982 4451 8982 4443 8983 4451 8983 4467 8983 4444 8984 4473 8984 4445 8984 4445 8985 4473 8985 4446 8985 4445 8986 4446 8986 4450 8986 4450 8987 4446 8987 4447 8987 4450 8988 4447 8988 4448 8988 4448 8989 4442 8989 4450 8989 4450 8990 4442 8990 4449 8990 4450 8991 4449 8991 4445 8991 4445 8992 4449 8992 4440 8992 4445 8993 4440 8993 4451 8993 4451 8994 4440 8994 1879 8994 4451 8995 1879 8995 4467 8995 4452 8996 4464 8996 4465 8996 4453 8997 4460 8997 4461 8997 4454 8998 4470 8998 1103 8998 4470 8999 4454 8999 4468 8999 4487 9000 4485 9000 4464 9000 4485 9001 4455 9001 4462 9001 4470 9002 4463 9002 4456 9002 4456 9003 4463 9003 4457 9003 4460 9004 4470 9004 4456 9004 4457 9005 4458 9005 4456 9005 4456 9006 4458 9006 4482 9006 4456 9007 4482 9007 4460 9007 4460 9008 4482 9008 4459 9008 4460 9009 4459 9009 4461 9009 4461 9010 4459 9010 1101 9010 4461 9011 1101 9011 4453 9011 4455 9012 4457 9012 4462 9012 4462 9013 4457 9013 4463 9013 4462 9014 4463 9014 4470 9014 4464 9015 4485 9015 4465 9015 4465 9016 4485 9016 4462 9016 4465 9017 4462 9017 4470 9017 4444 9018 4443 9018 4466 9018 4466 9019 4443 9019 4467 9019 4466 9020 4467 9020 4488 9020 4487 9021 4464 9021 4488 9021 4488 9022 4464 9022 4452 9022 4488 9023 4452 9023 4466 9023 4466 9024 4452 9024 4473 9024 4466 9025 4473 9025 4444 9025 1096 9026 2145 9026 4474 9026 4470 9027 1099 9027 1098 9027 1100 9028 1099 9028 4470 9028 4469 9029 1100 9029 4470 9029 1096 9030 4471 9030 4472 9030 4472 9031 4471 9031 4470 9031 4468 9032 4469 9032 4470 9032 4453 9033 1103 9033 4460 9033 4460 9034 1103 9034 4470 9034 1096 9035 4474 9035 4471 9035 4471 9036 4474 9036 4475 9036 4471 9037 4475 9037 4470 9037 1098 9038 4472 9038 4470 9038 2145 9039 4473 9039 4474 9039 4474 9040 4473 9040 4452 9040 4474 9041 4452 9041 4475 9041 4475 9042 4452 9042 4465 9042 4475 9043 4465 9043 4470 9043 4483 9044 4496 9044 1101 9044 4476 9045 4481 9045 4493 9045 4476 9046 4493 9046 4495 9046 4500 9047 4477 9047 4498 9047 4498 9048 4477 9048 4491 9048 4498 9049 4491 9049 4478 9049 4478 9050 4491 9050 4492 9050 4478 9051 4492 9051 4479 9051 4479 9052 4492 9052 4493 9052 4479 9053 4493 9053 4480 9053 4480 9054 4493 9054 4481 9054 1101 9055 4459 9055 4483 9055 4483 9056 4459 9056 4482 9056 4483 9057 4482 9057 4497 9057 4497 9058 4482 9058 4458 9058 4497 9059 4458 9059 4484 9059 4458 9060 4457 9060 4484 9060 4484 9061 4457 9061 4455 9061 4484 9062 4455 9062 4499 9062 4499 9063 4455 9063 4485 9063 4499 9064 4485 9064 4486 9064 4486 9065 4485 9065 4487 9065 4486 9066 4487 9066 4503 9066 4503 9067 4487 9067 4488 9067 4503 9068 4488 9068 4504 9068 1883 9069 1882 9069 4502 9069 4502 9070 1882 9070 4507 9070 4502 9071 4507 9071 4501 9071 4501 9072 4507 9072 4519 9072 4501 9073 4519 9073 4489 9073 4500 9074 4501 9074 4477 9074 4477 9075 4501 9075 4489 9075 4477 9076 4489 9076 4491 9076 4491 9077 4489 9077 4490 9077 4491 9078 4490 9078 4492 9078 4492 9079 4490 9079 4517 9079 4492 9080 4517 9080 4493 9080 4493 9081 4517 9081 4494 9081 4493 9082 4494 9082 4495 9082 4480 9083 4496 9083 4479 9083 4479 9084 4496 9084 4483 9084 4479 9085 4483 9085 4478 9085 4478 9086 4483 9086 4497 9086 4478 9087 4497 9087 4498 9087 4498 9088 4497 9088 4484 9088 4498 9089 4484 9089 4500 9089 4500 9090 4484 9090 4499 9090 4500 9091 4499 9091 4501 9091 4501 9092 4499 9092 4486 9092 4501 9093 4486 9093 4502 9093 4502 9094 4486 9094 4503 9094 4502 9095 4503 9095 1883 9095 1883 9096 4503 9096 4504 9096 1883 9097 4504 9097 4505 9097 4505 9098 4504 9098 4488 9098 4505 9099 4488 9099 4467 9099 4526 9100 4513 9100 4506 9100 4519 9101 4507 9101 4511 9101 4514 9102 4508 9102 4509 9102 4516 9103 4515 9103 4522 9103 4514 9104 4509 9104 2152 9104 2152 9105 4509 9105 4535 9105 2152 9106 4535 9106 4510 9106 4506 9107 1885 9107 1884 9107 4513 9108 4526 9108 4511 9108 4511 9109 4526 9109 4518 9109 4511 9110 4518 9110 4519 9110 1885 9111 4506 9111 4512 9111 4512 9112 4506 9112 4513 9112 4512 9113 4513 9113 1876 9113 1876 9114 4513 9114 4511 9114 1876 9115 4511 9115 1881 9115 1881 9116 4511 9116 4507 9116 1881 9117 4507 9117 1882 9117 4527 9118 4520 9118 4525 9118 4514 9119 4515 9119 4508 9119 4508 9120 4515 9120 4516 9120 4508 9121 4516 9121 4521 9121 4521 9122 4516 9122 4524 9122 4521 9123 4524 9123 4525 9123 4494 9124 4517 9124 4523 9124 4523 9125 4517 9125 4490 9125 4523 9126 4490 9126 4518 9126 4518 9127 4490 9127 4489 9127 4518 9128 4489 9128 4519 9128 4525 9129 4520 9129 4521 9129 4521 9130 4520 9130 4530 9130 4521 9131 4530 9131 4508 9131 4508 9132 4530 9132 4531 9132 4508 9133 4531 9133 4509 9133 4509 9134 4531 9134 4534 9134 4509 9135 4534 9135 4535 9135 4495 9136 4494 9136 4522 9136 4522 9137 4494 9137 4523 9137 4522 9138 4523 9138 4516 9138 4516 9139 4523 9139 4518 9139 4516 9140 4518 9140 4524 9140 4524 9141 4518 9141 4526 9141 4524 9142 4526 9142 4525 9142 4525 9143 4526 9143 4506 9143 4525 9144 4506 9144 4527 9144 4527 9145 4506 9145 1884 9145 4527 9146 1884 9146 4528 9146 4528 9147 1559 9147 1558 9147 4528 9148 1558 9148 4527 9148 4527 9149 1558 9149 4529 9149 4527 9150 4529 9150 4520 9150 4520 9151 4529 9151 4530 9151 4530 9152 4529 9152 4532 9152 4530 9153 4532 9153 4531 9153 4531 9154 4532 9154 4534 9154 4534 9155 4532 9155 4533 9155 4534 9156 4533 9156 4535 9156 4535 9157 4533 9157 4536 9157 4535 9158 4536 9158 4510 9158 4537 9159 6339 9159 4568 9159 4568 9160 4542 9160 4537 9160 4537 9161 4542 9161 4543 9161 4537 9162 4543 9162 6329 9162 4546 9163 4538 9163 4539 9163 4538 9164 4546 9164 4545 9164 4541 9165 4554 9165 4539 9165 4539 9166 4554 9166 4540 9166 4539 9167 4540 9167 4546 9167 4558 9168 4556 9168 4541 9168 4541 9169 4556 9169 4555 9169 4541 9170 4555 9170 4554 9170 4542 9171 4568 9171 4551 9171 4551 9172 4544 9172 4542 9172 4542 9173 4544 9173 4559 9173 4542 9174 4559 9174 4543 9174 4543 9175 4559 9175 4558 9175 4543 9176 4558 9176 1981 9176 1981 9177 4558 9177 4541 9177 1981 9178 4541 9178 1982 9178 1982 9179 4541 9179 4539 9179 4559 9180 4544 9180 4550 9180 4567 9181 4566 9181 4550 9181 3080 9182 4545 9182 4546 9182 3080 9183 4546 9183 3081 9183 4560 9184 3082 9184 3081 9184 3082 9185 4560 9185 4547 9185 4547 9186 4560 9186 4548 9186 4547 9187 4548 9187 3074 9187 4550 9188 4566 9188 4557 9188 4557 9189 4566 9189 4565 9189 4557 9190 4565 9190 4563 9190 4567 9191 4550 9191 4549 9191 4549 9192 4550 9192 4544 9192 4549 9193 4544 9193 4551 9193 4561 9194 4552 9194 4573 9194 4573 9195 4552 9195 2103 9195 4573 9196 2103 9196 2102 9196 4573 9197 4574 9197 4561 9197 4561 9198 4574 9198 4553 9198 4561 9199 4553 9199 4560 9199 4560 9200 4553 9200 4576 9200 4560 9201 4576 9201 4548 9201 4540 9202 4554 9202 4563 9202 4563 9203 4554 9203 4555 9203 4563 9204 4555 9204 4557 9204 4557 9205 4555 9205 4556 9205 4557 9206 4556 9206 4550 9206 4550 9207 4556 9207 4558 9207 4550 9208 4558 9208 4559 9208 3081 9209 4546 9209 4560 9209 4560 9210 4546 9210 4562 9210 4560 9211 4562 9211 4561 9211 4561 9212 4562 9212 4564 9212 4561 9213 4564 9213 4552 9213 4546 9214 4540 9214 4562 9214 4562 9215 4540 9215 4563 9215 4562 9216 4563 9216 4564 9216 4564 9217 4563 9217 4565 9217 4564 9218 4565 9218 4552 9218 4552 9219 4565 9219 4566 9219 4552 9220 4566 9220 2103 9220 2103 9221 4566 9221 4567 9221 2103 9222 4567 9222 2104 9222 2104 9223 4567 9223 4549 9223 2104 9224 4549 9224 2106 9224 2106 9225 4549 9225 4551 9225 2106 9226 4551 9226 4568 9226 4571 9227 4584 9227 4569 9227 4571 9228 4569 9228 4572 9228 4572 9229 4569 9229 4570 9229 4572 9230 4570 9230 4578 9230 3074 9231 4548 9231 3075 9231 3075 9232 4548 9232 4575 9232 2102 9233 4571 9233 4573 9233 4573 9234 4571 9234 4572 9234 4573 9235 4572 9235 4574 9235 4574 9236 4572 9236 4578 9236 4574 9237 4578 9237 4553 9237 4553 9238 4578 9238 4575 9238 4553 9239 4575 9239 4576 9239 4576 9240 4575 9240 4548 9240 4570 9241 4592 9241 4578 9241 4578 9242 4592 9242 4577 9242 4578 9243 4577 9243 4575 9243 4575 9244 4577 9244 3077 9244 4575 9245 3077 9245 3075 9245 4579 9246 2008 9246 6378 9246 6378 9247 2008 9247 4596 9247 6378 9248 4596 9248 4580 9248 4580 9249 4596 9249 2086 9249 4580 9250 2086 9250 6384 9250 4581 9251 4585 9251 4587 9251 4590 9252 3073 9252 4588 9252 4589 9253 4582 9253 4591 9253 4586 9254 4587 9254 4583 9254 4583 9255 4587 9255 4585 9255 4583 9256 4585 9256 2086 9256 4569 9257 4584 9257 4581 9257 4581 9258 4584 9258 2084 9258 4581 9259 2084 9259 4585 9259 4585 9260 2084 9260 2083 9260 4585 9261 2083 9261 2086 9261 4586 9262 4595 9262 4587 9262 4587 9263 4595 9263 4594 9263 4587 9264 4594 9264 4588 9264 4588 9265 4594 9265 4589 9265 4588 9266 4589 9266 4590 9266 4590 9267 4589 9267 4591 9267 3073 9268 3077 9268 4588 9268 4588 9269 3077 9269 4577 9269 4588 9270 4577 9270 4587 9270 4587 9271 4577 9271 4592 9271 4587 9272 4592 9272 4581 9272 4581 9273 4592 9273 4570 9273 4581 9274 4570 9274 4569 9274 2086 9275 4596 9275 4583 9275 4583 9276 4596 9276 4593 9276 4583 9277 4593 9277 4586 9277 4586 9278 4593 9278 4595 9278 4582 9279 4589 9279 1977 9279 1977 9280 4589 9280 4594 9280 1977 9281 4594 9281 1975 9281 4594 9282 4595 9282 1975 9282 1975 9283 4595 9283 4593 9283 1975 9284 4593 9284 1973 9284 1973 9285 4593 9285 4596 9285 1973 9286 4596 9286 2008 9286 6543 9287 4597 9287 4598 9287 4598 9288 4597 9288 4605 9288 4598 9289 4605 9289 6532 9289 6532 9290 4605 9290 4599 9290 4599 9291 4605 9291 3133 9291 4599 9292 3133 9292 2006 9292 4601 9293 4618 9293 3130 9293 3130 9294 4618 9294 4600 9294 4606 9295 4623 9295 4601 9295 4601 9296 4623 9296 4617 9296 4601 9297 4617 9297 4618 9297 4597 9298 4602 9298 4605 9298 4605 9299 4602 9299 4603 9299 4605 9300 4603 9300 4607 9300 4607 9301 4603 9301 4608 9301 3133 9302 4605 9302 4604 9302 4604 9303 4605 9303 4607 9303 4604 9304 4607 9304 4606 9304 4606 9305 4607 9305 4608 9305 4606 9306 4608 9306 4623 9306 4619 9307 4620 9307 2119 9307 4623 9308 4608 9308 4624 9308 4624 9309 4608 9309 4603 9309 1481 9310 4629 9310 4609 9310 4609 9311 4629 9311 2119 9311 4609 9312 2119 9312 1477 9312 4613 9313 4626 9313 2338 9313 2338 9314 4626 9314 4610 9314 2338 9315 4610 9315 4628 9315 4602 9316 4621 9316 4603 9316 4603 9317 4621 9317 4611 9317 4603 9318 4611 9318 4624 9318 4624 9319 4611 9319 4625 9319 2338 9320 4612 9320 4613 9320 4613 9321 4612 9321 4614 9321 4613 9322 4614 9322 4622 9322 4622 9323 4614 9323 4615 9323 4622 9324 4615 9324 4616 9324 4617 9325 4622 9325 4618 9325 4618 9326 4622 9326 4616 9326 4618 9327 4616 9327 4600 9327 4629 9328 4627 9328 2119 9328 2119 9329 4627 9329 4625 9329 2119 9330 4625 9330 4619 9330 4619 9331 4625 9331 4611 9331 4619 9332 4611 9332 4620 9332 4620 9333 4611 9333 4621 9333 4620 9334 4621 9334 2118 9334 2118 9335 4621 9335 4602 9335 2118 9336 4602 9336 4597 9336 4617 9337 4623 9337 4622 9337 4622 9338 4623 9338 4624 9338 4622 9339 4624 9339 4613 9339 4613 9340 4624 9340 4625 9340 4613 9341 4625 9341 4626 9341 4626 9342 4625 9342 4627 9342 4626 9343 4627 9343 4610 9343 4610 9344 4627 9344 4629 9344 4610 9345 4629 9345 4628 9345 4628 9346 4629 9346 1481 9346 4628 9347 1481 9347 2339 9347 2010 9348 2009 9348 4630 9348 4630 9349 2009 9349 1561 9349 4630 9350 1561 9350 7911 9350 7911 9351 1561 9351 4631 9351 7911 9352 4631 9352 7890 9352 7890 9353 4631 9353 4632 9353 4632 9354 4631 9354 4633 9354 4632 9355 4633 9355 4634 9355 4634 9356 4633 9356 2233 9356 4634 9357 2233 9357 7891 9357 7840 9358 4635 9358 4636 9358 4636 9359 4635 9359 1553 9359 4636 9360 1553 9360 7872 9360 7872 9361 1553 9361 4637 9361 4637 9362 1553 9362 4638 9362 4637 9363 4638 9363 4639 9363 4642 9364 7853 9364 4638 9364 4638 9365 7853 9365 7852 9365 4638 9366 7852 9366 4639 9366 7889 9367 4641 9367 4640 9367 4640 9368 4641 9368 7877 9368 4640 9369 7877 9369 4642 9369 4642 9370 7877 9370 4643 9370 4642 9371 4643 9371 7853 9371 7610 9372 1684 9372 7720 9372 7720 9373 1684 9373 4644 9373 7720 9374 4644 9374 7719 9374 7719 9375 4644 9375 118 9375 7719 9376 118 9376 4645 9376 4645 9377 118 9377 7717 9377 7717 9378 118 9378 4646 9378 7717 9379 4646 9379 7737 9379 7737 9380 4646 9380 7722 9380 7722 9381 4646 9381 4648 9381 7722 9382 4648 9382 4647 9382 4647 9383 4648 9383 7716 9383 7716 9384 4648 9384 119 9384 7716 9385 119 9385 1150 9385 1272 9386 4649 9386 7586 9386 7586 9387 4649 9387 130 9387 7586 9388 130 9388 7578 9388 7578 9389 130 9389 4650 9389 4650 9390 130 9390 128 9390 4650 9391 128 9391 4651 9391 4651 9392 128 9392 4652 9392 4652 9393 128 9393 4653 9393 4652 9394 4653 9394 7593 9394 7593 9395 4653 9395 129 9395 7593 9396 129 9396 7575 9396 7575 9397 129 9397 4654 9397 7575 9398 4654 9398 4655 9398 7445 9399 7446 9399 1550 9399 1550 9400 7446 9400 7424 9400 1550 9401 7424 9401 1517 9401 4658 9402 4656 9402 1550 9402 1550 9403 4656 9403 4657 9403 1550 9404 4657 9404 7445 9404 1552 9405 2169 9405 7435 9405 7435 9406 7436 9406 1552 9406 1552 9407 7436 9407 7437 9407 1552 9408 7437 9408 4658 9408 4658 9409 7437 9409 7438 9409 4658 9410 7438 9410 4656 9410 4659 9411 1564 9411 1563 9411 4660 9412 2167 9412 1516 9412 1564 9413 4659 9413 1516 9413 1516 9414 4659 9414 7404 9414 1516 9415 7404 9415 4660 9415 7405 9416 7407 9416 1563 9416 1563 9417 7407 9417 7408 9417 1563 9418 7408 9418 4659 9418 4661 9419 1565 9419 4662 9419 4662 9420 4663 9420 4661 9420 4661 9421 4663 9421 7419 9421 4661 9422 7419 9422 1563 9422 1563 9423 7419 9423 7396 9423 1563 9424 7396 9424 7405 9424 4690 9425 4237 9425 4683 9425 3044 9426 3043 9426 4695 9426 3043 9427 3042 9427 4695 9427 4695 9428 3042 9428 3041 9428 4695 9429 3041 9429 3039 9429 4245 9430 4696 9430 4664 9430 4664 9431 4696 9431 4693 9431 4664 9432 4693 9432 4666 9432 4666 9433 4693 9433 4665 9433 4666 9434 4665 9434 4256 9434 4667 9435 4668 9435 4684 9435 4684 9436 4668 9436 4669 9436 4684 9437 4669 9437 4665 9437 4665 9438 4669 9438 4257 9438 4665 9439 4257 9439 4256 9439 4684 9440 4686 9440 4667 9440 4667 9441 4686 9441 4670 9441 4667 9442 4670 9442 4689 9442 4687 9443 2272 9443 4688 9443 4683 9444 4671 9444 2270 9444 4671 9445 4683 9445 4672 9445 4672 9446 4683 9446 4237 9446 4672 9447 4237 9447 2198 9447 4673 9448 4220 9448 4674 9448 4674 9449 4220 9449 4219 9449 4222 9450 4223 9450 4679 9450 4679 9451 4223 9451 4675 9451 4679 9452 4675 9452 4676 9452 4676 9453 4228 9453 4679 9453 4679 9454 4228 9454 4677 9454 4679 9455 4677 9455 4673 9455 4673 9456 4677 9456 4678 9456 4673 9457 4678 9457 4220 9457 4222 9458 4679 9458 4680 9458 4680 9459 4679 9459 4694 9459 4680 9460 4694 9460 4681 9460 4681 9461 4694 9461 4695 9461 4681 9462 4695 9462 4682 9462 4682 9463 4695 9463 3039 9463 4682 9464 3039 9464 3111 9464 4692 9465 4691 9465 4685 9465 4685 9466 4691 9466 4683 9466 4685 9467 4683 9467 4687 9467 4687 9468 4683 9468 2270 9468 4687 9469 2270 9469 2272 9469 4665 9470 4692 9470 4684 9470 4684 9471 4692 9471 4685 9471 4684 9472 4685 9472 4686 9472 4686 9473 4685 9473 4687 9473 4686 9474 4687 9474 4670 9474 4670 9475 4687 9475 4688 9475 4670 9476 4688 9476 4689 9476 4689 9477 4688 9477 2278 9477 4690 9478 4683 9478 4219 9478 4219 9479 4683 9479 4691 9479 4219 9480 4691 9480 4674 9480 4674 9481 4691 9481 4692 9481 4674 9482 4692 9482 4673 9482 4673 9483 4692 9483 4665 9483 4673 9484 4665 9484 4679 9484 4679 9485 4665 9485 4693 9485 4679 9486 4693 9486 4694 9486 4694 9487 4693 9487 4696 9487 4694 9488 4696 9488 4695 9488 4695 9489 4696 9489 4245 9489 4695 9490 4245 9490 3044 9490 4697 9491 4714 9491 4716 9491 4713 9492 4729 9492 4716 9492 4388 9493 1878 9493 4723 9493 4418 9494 4698 9494 4704 9494 4699 9495 4720 9495 4375 9495 4375 9496 4720 9496 2126 9496 4702 9497 4700 9497 4719 9497 2134 9498 4700 9498 4701 9498 4701 9499 4700 9499 4702 9499 4701 9500 4702 9500 4416 9500 4416 9501 4702 9501 4722 9501 4416 9502 4722 9502 4703 9502 4418 9503 4704 9503 4705 9503 4705 9504 4704 9504 4706 9504 4705 9505 4706 9505 4419 9505 4419 9506 4706 9506 4728 9506 4419 9507 4728 9507 4708 9507 4708 9508 4728 9508 4707 9508 4708 9509 4707 9509 4709 9509 4711 9510 4725 9510 1877 9510 4709 9511 4707 9511 4406 9511 4406 9512 4707 9512 4711 9512 4406 9513 4711 9513 4710 9513 4710 9514 4711 9514 1877 9514 4710 9515 1877 9515 4403 9515 4388 9516 4723 9516 4712 9516 4723 9517 4724 9517 4712 9517 4712 9518 4724 9518 4726 9518 4712 9519 4726 9519 4376 9519 4383 9520 4384 9520 4727 9520 4727 9521 4384 9521 4386 9521 4727 9522 4386 9522 4726 9522 4726 9523 4386 9523 4387 9523 4726 9524 4387 9524 4376 9524 4729 9525 4713 9525 4727 9525 4727 9526 4713 9526 4382 9526 4727 9527 4382 9527 4383 9527 4380 9528 4379 9528 4714 9528 4714 9529 4379 9529 4715 9529 4714 9530 4715 9530 4716 9530 4716 9531 4715 9531 4378 9531 4716 9532 4378 9532 4713 9532 4699 9533 4380 9533 4720 9533 4720 9534 4380 9534 4714 9534 4720 9535 4714 9535 4721 9535 4721 9536 4714 9536 4697 9536 4717 9537 2126 9537 4718 9537 4718 9538 2126 9538 4720 9538 4718 9539 4720 9539 4719 9539 4719 9540 4720 9540 4721 9540 4719 9541 4721 9541 4702 9541 4702 9542 4721 9542 4697 9542 4702 9543 4697 9543 4722 9543 4722 9544 4697 9544 4716 9544 4723 9545 4725 9545 4724 9545 4724 9546 4725 9546 4711 9546 4724 9547 4711 9547 4726 9547 4726 9548 4711 9548 4707 9548 4726 9549 4707 9549 4727 9549 4727 9550 4707 9550 4728 9550 4727 9551 4728 9551 4729 9551 4729 9552 4728 9552 4706 9552 4729 9553 4706 9553 4716 9553 4716 9554 4706 9554 4704 9554 4716 9555 4704 9555 4722 9555 4722 9556 4704 9556 4698 9556 4722 9557 4698 9557 4703 9557 4733 9558 1656 9558 1658 9558 6126 9559 6127 9559 4731 9559 6110 9560 6113 9560 1660 9560 1660 9561 6113 9561 6116 9561 1660 9562 6116 9562 1658 9562 1658 9563 6116 9563 6118 9563 6118 9564 6119 9564 1658 9564 1658 9565 6119 9565 6120 9565 1658 9566 6120 9566 6123 9566 6126 9567 4731 9567 6124 9567 6108 9568 4730 9568 1658 9568 1658 9569 4730 9569 6106 9569 1658 9570 6106 9570 6104 9570 6123 9571 6124 9571 1658 9571 1658 9572 6124 9572 4731 9572 1658 9573 4731 9573 6108 9573 6108 9574 4731 9574 4767 9574 6104 9575 4732 9575 1658 9575 1658 9576 4732 9576 6103 9576 1658 9577 6103 9577 4733 9577 4738 9578 6155 9578 4777 9578 6163 9579 4734 9579 4735 9579 4735 9580 4734 9580 4736 9580 4735 9581 4736 9581 6161 9581 6161 9582 6160 9582 4735 9582 4735 9583 6160 9583 6158 9583 4735 9584 6158 9584 4737 9584 4738 9585 4777 9585 4741 9585 6146 9586 4739 9586 4735 9586 4735 9587 4739 9587 4740 9587 4735 9588 4740 9588 4742 9588 4737 9589 4741 9589 4735 9589 4735 9590 4741 9590 4777 9590 4735 9591 4777 9591 6146 9591 6146 9592 4777 9592 6141 9592 4742 9593 4743 9593 4735 9593 4735 9594 4743 9594 4744 9594 4735 9595 4744 9595 4745 9595 4745 9596 4744 9596 6145 9596 4745 9597 6145 9597 1668 9597 6177 9598 1032 9598 4750 9598 4746 9599 6183 9599 4750 9599 4746 9600 4750 9600 6186 9600 6186 9601 4750 9601 4747 9601 4747 9602 4750 9602 4791 9602 4747 9603 4791 9603 4748 9603 6183 9604 4749 9604 4750 9604 4750 9605 4749 9605 6181 9605 4750 9606 6181 9606 6177 9606 1027 9607 4751 9607 4750 9607 4750 9608 4751 9608 6037 9608 6037 9609 6038 9609 4750 9609 4750 9610 6038 9610 4752 9610 4750 9611 4752 9611 6040 9611 6040 9612 4753 9612 4750 9612 4750 9613 4753 9613 4754 9613 4750 9614 4754 9614 4791 9614 4791 9615 4754 9615 6043 9615 4791 9616 6043 9616 6044 9616 4755 9617 6062 9617 1023 9617 4759 9618 6076 9618 4762 9618 6088 9619 6086 9619 1023 9619 1023 9620 6086 9620 4756 9620 1023 9621 4756 9621 6084 9621 6084 9622 4757 9622 1023 9622 1023 9623 4757 9623 4758 9623 1023 9624 4758 9624 4760 9624 4759 9625 4762 9625 4761 9625 6069 9626 6067 9626 1023 9626 1023 9627 6067 9627 6066 9627 1023 9628 6066 9628 6065 9628 4760 9629 4761 9629 1023 9629 1023 9630 4761 9630 4762 9630 1023 9631 4762 9631 6069 9631 6069 9632 4762 9632 6061 9632 6065 9633 6064 9633 1023 9633 1023 9634 6064 9634 4763 9634 1023 9635 4763 9635 4755 9635 1461 9636 1467 9636 6091 9636 6094 9637 6090 9637 6136 9637 6136 9638 6090 9638 6096 9638 6136 9639 6096 9639 4768 9639 6136 9640 6135 9640 6094 9640 6094 9641 6135 9641 6133 9641 6094 9642 6133 9642 6091 9642 6091 9643 6133 9643 4764 9643 6091 9644 4764 9644 1461 9644 4765 9645 6131 9645 4770 9645 4731 9646 6127 9646 4766 9646 4765 9647 4770 9647 4766 9647 4766 9648 4770 9648 4767 9648 4766 9649 4767 9649 4731 9649 6096 9650 6097 9650 4768 9650 4768 9651 6097 9651 4769 9651 4768 9652 4769 9652 6131 9652 6131 9653 4769 9653 6099 9653 6131 9654 6099 9654 4770 9654 1538 9655 1468 9655 4773 9655 6138 9656 4771 9656 6149 9656 6149 9657 4771 9657 4779 9657 6149 9658 4779 9658 6150 9658 6149 9659 4772 9659 6138 9659 6138 9660 4772 9660 6148 9660 6138 9661 6148 9661 4773 9661 4773 9662 6148 9662 4774 9662 4773 9663 4774 9663 1538 9663 4775 9664 6154 9664 4776 9664 4777 9665 6155 9665 4778 9665 4775 9666 4776 9666 4778 9666 4778 9667 4776 9667 6141 9667 4778 9668 6141 9668 4777 9668 4779 9669 6139 9669 6150 9669 6150 9670 6139 9670 4780 9670 6150 9671 4780 9671 6154 9671 6154 9672 4780 9672 4781 9672 6154 9673 4781 9673 4776 9673 1518 9674 1488 9674 6055 9674 4782 9675 4783 9675 4785 9675 4785 9676 4783 9676 6057 9676 4785 9677 6057 9677 4784 9677 4785 9678 6074 9678 4782 9678 4782 9679 6074 9679 6071 9679 4782 9680 6071 9680 6055 9680 6055 9681 6071 9681 6070 9681 6055 9682 6070 9682 1518 9682 4786 9683 4788 9683 4790 9683 6076 9684 6077 9684 4762 9684 4762 9685 6077 9685 6061 9685 6061 9686 6077 9686 4790 9686 4790 9687 6077 9687 6079 9687 4790 9688 6079 9688 4786 9688 6057 9689 4787 9689 4784 9689 4784 9690 4787 9690 4789 9690 4784 9691 4789 9691 4788 9691 4788 9692 4789 9692 6059 9692 4788 9693 6059 9693 4790 9693 4794 9694 6048 9694 6175 9694 6044 9695 4792 9695 4791 9695 4791 9696 4792 9696 4748 9696 4748 9697 4792 9697 6175 9697 6175 9698 4792 9698 4793 9698 6175 9699 4793 9699 4794 9699 4795 9700 6172 9700 6048 9700 6048 9701 6172 9701 4796 9701 6048 9702 4796 9702 6175 9702 6168 9703 4797 9703 6052 9703 6052 9704 4797 9704 4798 9704 6052 9705 4798 9705 4795 9705 4795 9706 4798 9706 6169 9706 4795 9707 6169 9707 6172 9707 6049 9708 1503 9708 4800 9708 6052 9709 6051 9709 6168 9709 6168 9710 6051 9710 4799 9710 6168 9711 4799 9711 4800 9711 4800 9712 4799 9712 4801 9712 4800 9713 4801 9713 6049 9713 4837 9714 7052 9714 4804 9714 7042 9715 4868 9715 4802 9715 4803 9716 4837 9716 8330 9716 8330 9717 4837 9717 4804 9717 8330 9718 4804 9718 8332 9718 8332 9719 4804 9719 7021 9719 8332 9720 7021 9720 8334 9720 8334 9721 7021 9721 4805 9721 8334 9722 4805 9722 8336 9722 8336 9723 4805 9723 4807 9723 8336 9724 4807 9724 4806 9724 4806 9725 4807 9725 7030 9725 4806 9726 7030 9726 8333 9726 8333 9727 7030 9727 7041 9727 8333 9728 7041 9728 8339 9728 8339 9729 7041 9729 7042 9729 8339 9730 7042 9730 4808 9730 4808 9731 7042 9731 4802 9731 8157 9732 8235 9732 4809 9732 4809 9733 8235 9733 8237 9733 4809 9734 8237 9734 8159 9734 8159 9735 8237 9735 4810 9735 8159 9736 4810 9736 4811 9736 4811 9737 4810 9737 4812 9737 4811 9738 4812 9738 8160 9738 8160 9739 4812 9739 4813 9739 8160 9740 4813 9740 8162 9740 8162 9741 4813 9741 8241 9741 8162 9742 8241 9742 8152 9742 8152 9743 8241 9743 8245 9743 8157 9744 8189 9744 8235 9744 8235 9745 8189 9745 4814 9745 8235 9746 4814 9746 8234 9746 8234 9747 4814 9747 8221 9747 8519 9748 4821 9748 4815 9748 4815 9749 4821 9749 8496 9749 7161 9750 4855 9750 4816 9750 4816 9751 4855 9751 4817 9751 4816 9752 4817 9752 7154 9752 7154 9753 4817 9753 8500 9753 7154 9754 8500 9754 4818 9754 4818 9755 8500 9755 8499 9755 4818 9756 8499 9756 7151 9756 7151 9757 8499 9757 4819 9757 7151 9758 4819 9758 4820 9758 4820 9759 4819 9759 8498 9759 4820 9760 8498 9760 7148 9760 7148 9761 8498 9761 8496 9761 7148 9762 8496 9762 7146 9762 7146 9763 8496 9763 4821 9763 7146 9764 4821 9764 4822 9764 4823 9765 4849 9765 6252 9765 6252 9766 4849 9766 4847 9766 4847 9767 4824 9767 6252 9767 6252 9768 4824 9768 4825 9768 6252 9769 4825 9769 6255 9769 6255 9770 4825 9770 8403 9770 6255 9771 8403 9771 4826 9771 4826 9772 8403 9772 8406 9772 4826 9773 8406 9773 4827 9773 4827 9774 8406 9774 4830 9774 4827 9775 4830 9775 6256 9775 4856 9776 6271 9776 8415 9776 8415 9777 6271 9777 4828 9777 8415 9778 4828 9778 8410 9778 8410 9779 4828 9779 6256 9779 8410 9780 6256 9780 4829 9780 4829 9781 6256 9781 4830 9781 4814 9782 8189 9782 8190 9782 4831 9783 8221 9783 4814 9783 4814 9784 8190 9784 4831 9784 4831 9785 8190 9785 8193 9785 4831 9786 8193 9786 4832 9786 4832 9787 8193 9787 4833 9787 4832 9788 4833 9788 8212 9788 8212 9789 4833 9789 1691 9789 8212 9790 1691 9790 4834 9790 4837 9791 4803 9791 4838 9791 7074 9792 4836 9792 4835 9792 4835 9793 4836 9793 8362 9793 4835 9794 8362 9794 7082 9794 7074 9795 7057 9795 4836 9795 4836 9796 7057 9796 7058 9796 4836 9797 7058 9797 8352 9797 8352 9798 7058 9798 4838 9798 7052 9799 4837 9799 7053 9799 7053 9800 4837 9800 4838 9800 7053 9801 4838 9801 7059 9801 7059 9802 4838 9802 7058 9802 4821 9803 8519 9803 8515 9803 4839 9804 4822 9804 4821 9804 4821 9805 8515 9805 4839 9805 4839 9806 8515 9806 4840 9806 4839 9807 4840 9807 7117 9807 7117 9808 4840 9808 8528 9808 7117 9809 8528 9809 7126 9809 7126 9810 8528 9810 8527 9810 7126 9811 8527 9811 4841 9811 8369 9812 4842 9812 4843 9812 4843 9813 4842 9813 6222 9813 8375 9814 6248 9814 4842 9814 4842 9815 6248 9815 4844 9815 4842 9816 4844 9816 6222 9816 4848 9817 4845 9817 4846 9817 4846 9818 4845 9818 6228 9818 4846 9819 6228 9819 8375 9819 8375 9820 6228 9820 6226 9820 8375 9821 6226 9821 6248 9821 4846 9822 4847 9822 4849 9822 4848 9823 4846 9823 6241 9823 6241 9824 4846 9824 4849 9824 6241 9825 4849 9825 4823 9825 4850 9826 7167 9826 8476 9826 4851 9827 8482 9827 4853 9827 1713 9828 8454 9828 4852 9828 8482 9829 4851 9829 4852 9829 4852 9830 4851 9830 7170 9830 4852 9831 7170 9831 1713 9831 8476 9832 7167 9832 8477 9832 8477 9833 7167 9833 4854 9833 8477 9834 4854 9834 4853 9834 4853 9835 4854 9835 7166 9835 4853 9836 7166 9836 4851 9836 4850 9837 8476 9837 7161 9837 7161 9838 8476 9838 8474 9838 7161 9839 8474 9839 4855 9839 6283 9840 6271 9840 4856 9840 6283 9841 4856 9841 4858 9841 4856 9842 4857 9842 4858 9842 4858 9843 4857 9843 8425 9843 4858 9844 8425 9844 4859 9844 4859 9845 8425 9845 4860 9845 4859 9846 4860 9846 6281 9846 6281 9847 4860 9847 6289 9847 1696 9848 6288 9848 4862 9848 4860 9849 4861 9849 6289 9849 6289 9850 4861 9850 8428 9850 6289 9851 8428 9851 4862 9851 4862 9852 8428 9852 8434 9852 4862 9853 8434 9853 1696 9853 4863 9854 1752 9854 8144 9854 8144 9855 1752 9855 1753 9855 4863 9856 8144 9856 8258 9856 8258 9857 8144 9857 8134 9857 8258 9858 8134 9858 8254 9858 8254 9859 8134 9859 8137 9859 8254 9860 8137 9860 8255 9860 8255 9861 8137 9861 4864 9861 8255 9862 4864 9862 4865 9862 4865 9863 4864 9863 4867 9863 4865 9864 4867 9864 4866 9864 4866 9865 4867 9865 8136 9865 4866 9866 8136 9866 8245 9866 8245 9867 8136 9867 8135 9867 8245 9868 8135 9868 8152 9868 8306 9869 4802 9869 4868 9869 8306 9870 4868 9870 8307 9870 8307 9871 4868 9871 4869 9871 8307 9872 4869 9872 8308 9872 8308 9873 4869 9873 7005 9873 8308 9874 7005 9874 8309 9874 8309 9875 7005 9875 4870 9875 8309 9876 4870 9876 8305 9876 8305 9877 4870 9877 7006 9877 8305 9878 7006 9878 4871 9878 4872 9879 8286 9879 4873 9879 7006 9880 4874 9880 4871 9880 4871 9881 4874 9881 4875 9881 4871 9882 4875 9882 4873 9882 4873 9883 4875 9883 4876 9883 4873 9884 4876 9884 4872 9884 4925 9885 4877 9885 4923 9885 4878 9886 4889 9886 4914 9886 1775 9887 4929 9887 4881 9887 4879 9888 6993 9888 4908 9888 4918 9889 7017 9889 4885 9889 7017 9890 7002 9890 7009 9890 4879 9891 4908 9891 6999 9891 1775 9892 7083 9892 4929 9892 4929 9893 7083 9893 4880 9893 4929 9894 4880 9894 4938 9894 1786 9895 1781 9895 4881 9895 4881 9896 1781 9896 1780 9896 4881 9897 1780 9897 1775 9897 4924 9898 1785 9898 4926 9898 4926 9899 1785 9899 1786 9899 4926 9900 1786 9900 4928 9900 4928 9901 1786 9901 4881 9901 4883 9902 4882 9902 4924 9902 4924 9903 4882 9903 1776 9903 4924 9904 1776 9904 1785 9904 4924 9905 4922 9905 4883 9905 4883 9906 4922 9906 4921 9906 4883 9907 4921 9907 1777 9907 1777 9908 4921 9908 4919 9908 1777 9909 4919 9909 1778 9909 7009 9910 4884 9910 7017 9910 7017 9911 4884 9911 7018 9911 7017 9912 7018 9912 4885 9912 4885 9913 7018 9913 7019 9913 4885 9914 7019 9914 4919 9914 4919 9915 7019 9915 4886 9915 4919 9916 4886 9916 1778 9916 4903 9917 4943 9917 4905 9917 4905 9918 4943 9918 4887 9918 4905 9919 4887 9919 4915 9919 4913 9920 4888 9920 4893 9920 4878 9921 4914 9921 4887 9921 4889 9922 4941 9922 4890 9922 4889 9923 4890 9923 4914 9923 4914 9924 4890 9924 1928 9924 4914 9925 1928 9925 4891 9925 4891 9926 1928 9926 4892 9926 4891 9927 4892 9927 4896 9927 4917 9928 4893 9928 4894 9928 4894 9929 4893 9929 4888 9929 4894 9930 4888 9930 4895 9930 4895 9931 4888 9931 4915 9931 4896 9932 1930 9932 4891 9932 4891 9933 1930 9933 4897 9933 4891 9934 4897 9934 4898 9934 4898 9935 4897 9935 1929 9935 4898 9936 1929 9936 4916 9936 4899 9937 4910 9937 1906 9937 1906 9938 1907 9938 4899 9938 4899 9939 1907 9939 4900 9939 4899 9940 4900 9940 4909 9940 4909 9941 4900 9941 4901 9941 4909 9942 4901 9942 4908 9942 4908 9943 4901 9943 1935 9943 4908 9944 1935 9944 6999 9944 4902 9945 4946 9945 4927 9945 4927 9946 4946 9946 4945 9946 4927 9947 4945 9947 4903 9947 4903 9948 4945 9948 4904 9948 4903 9949 4904 9949 4943 9949 4915 9950 4888 9950 4905 9950 4905 9951 4888 9951 4913 9951 4905 9952 4913 9952 4903 9952 4903 9953 4913 9953 4906 9953 4903 9954 4906 9954 4927 9954 6993 9955 6992 9955 4908 9955 4908 9956 6992 9956 4907 9956 4908 9957 4907 9957 4909 9957 4909 9958 4907 9958 4920 9958 4909 9959 4920 9959 4899 9959 4899 9960 4920 9960 4911 9960 4899 9961 4911 9961 4910 9961 4910 9962 4911 9962 4912 9962 4910 9963 4912 9963 4917 9963 4917 9964 4912 9964 4923 9964 4917 9965 4923 9965 4893 9965 4893 9966 4923 9966 4877 9966 4893 9967 4877 9967 4913 9967 4913 9968 4877 9968 4925 9968 4913 9969 4925 9969 4906 9969 4887 9970 4914 9970 4915 9970 4915 9971 4914 9971 4891 9971 4915 9972 4891 9972 4895 9972 4895 9973 4891 9973 4898 9973 4895 9974 4898 9974 4894 9974 4894 9975 4898 9975 4916 9975 4894 9976 4916 9976 4917 9976 4917 9977 4916 9977 1931 9977 4917 9978 1931 9978 4910 9978 4910 9979 1931 9979 1932 9979 4910 9980 1932 9980 1906 9980 6992 9981 4918 9981 4907 9981 4907 9982 4918 9982 4885 9982 4907 9983 4885 9983 4920 9983 4920 9984 4885 9984 4919 9984 4920 9985 4919 9985 4911 9985 4911 9986 4919 9986 4921 9986 4911 9987 4921 9987 4912 9987 4912 9988 4921 9988 4922 9988 4912 9989 4922 9989 4923 9989 4923 9990 4922 9990 4924 9990 4923 9991 4924 9991 4925 9991 4925 9992 4924 9992 4926 9992 4925 9993 4926 9993 4906 9993 4906 9994 4926 9994 4928 9994 4906 9995 4928 9995 4927 9995 4927 9996 4928 9996 4881 9996 4927 9997 4881 9997 4902 9997 4902 9998 4881 9998 4929 9998 4902 9999 4929 9999 4948 9999 4948 10000 4929 10000 4938 10000 4933 10001 1926 10001 4930 10001 4931 10002 4932 10002 4930 10002 4930 10003 4932 10003 4953 10003 4930 10004 4953 10004 4933 10004 7105 10005 7110 10005 4934 10005 4934 10006 7110 10006 4949 10006 4934 10007 4949 10007 4939 10007 4939 10008 4949 10008 4950 10008 4939 10009 4950 10009 4944 10009 4944 10010 4950 10010 4932 10010 4944 10011 4932 10011 4935 10011 4935 10012 4932 10012 4931 10012 4936 10013 4938 10013 4937 10013 4937 10014 4938 10014 4880 10014 1926 10015 4940 10015 4942 10015 4942 10016 4878 10016 4887 10016 4939 10017 4947 10017 4934 10017 4934 10018 4947 10018 4936 10018 4934 10019 4936 10019 7105 10019 7105 10020 4936 10020 4937 10020 4878 10021 4942 10021 4889 10021 4889 10022 4942 10022 4940 10022 4889 10023 4940 10023 4941 10023 1926 10024 4942 10024 4930 10024 4930 10025 4942 10025 4887 10025 4930 10026 4887 10026 4931 10026 4931 10027 4887 10027 4943 10027 4931 10028 4943 10028 4935 10028 4935 10029 4943 10029 4904 10029 4935 10030 4904 10030 4944 10030 4944 10031 4904 10031 4945 10031 4944 10032 4945 10032 4939 10032 4939 10033 4945 10033 4946 10033 4939 10034 4946 10034 4947 10034 4947 10035 4946 10035 4902 10035 4947 10036 4902 10036 4936 10036 4936 10037 4902 10037 4948 10037 4936 10038 4948 10038 4938 10038 7109 10039 4951 10039 7110 10039 7110 10040 4951 10040 4949 10040 4949 10041 4951 10041 4950 10041 4950 10042 4951 10042 1498 10042 4950 10043 1498 10043 4932 10043 4932 10044 1498 10044 4952 10044 4932 10045 4952 10045 4953 10045 4953 10046 4952 10046 1899 10046 4953 10047 1899 10047 4933 10047 4954 10048 1967 10048 4955 10048 4970 10049 4982 10049 4971 10049 4991 10050 4966 10050 4993 10050 5010 10051 5008 10051 4956 10051 8278 10052 8270 10052 4978 10052 4980 10053 1950 10053 4957 10053 1967 10054 4958 10054 4959 10054 5007 10055 5014 10055 1943 10055 5010 10056 4956 10056 4960 10056 4956 10057 4995 10057 4960 10057 4960 10058 4995 10058 4994 10058 4960 10059 4994 10059 4961 10059 4961 10060 4994 10060 4962 10060 4962 10061 4994 10061 4964 10061 4962 10062 4964 10062 4963 10062 4963 10063 4964 10063 4993 10063 4963 10064 4993 10064 4965 10064 4965 10065 4993 10065 4967 10065 4967 10066 4993 10066 4966 10066 4967 10067 4966 10067 1755 10067 4996 10068 1758 10068 1757 10068 5002 10069 1761 10069 4997 10069 4997 10070 1761 10070 4968 10070 4997 10071 4968 10071 1758 10071 8266 10072 8257 10072 8264 10072 8264 10073 8257 10073 8242 10073 8264 10074 8242 10074 4969 10074 4969 10075 4970 10075 8264 10075 8264 10076 4970 10076 4971 10076 8264 10077 4971 10077 4972 10077 4972 10078 4971 10078 4973 10078 4972 10079 4973 10079 4974 10079 4984 10080 5006 10080 4985 10080 1943 10081 4975 10081 5007 10081 5007 10082 4975 10082 1945 10082 5007 10083 1945 10083 4976 10083 4976 10084 1945 10084 4977 10084 4976 10085 4977 10085 4955 10085 4955 10086 4977 10086 1968 10086 4955 10087 1968 10087 4954 10087 8270 10088 4974 10088 4978 10088 4978 10089 4974 10089 4973 10089 4978 10090 4973 10090 4979 10090 4979 10091 4973 10091 5005 10091 4979 10092 5005 10092 4957 10092 4957 10093 5005 10093 4959 10093 4957 10094 4959 10094 4980 10094 4980 10095 4959 10095 4958 10095 1950 10096 4981 10096 4957 10096 4957 10097 4981 10097 1951 10097 4957 10098 1951 10098 4979 10098 4979 10099 1951 10099 1957 10099 4979 10100 1957 10100 4978 10100 4978 10101 1957 10101 1958 10101 4978 10102 1958 10102 8278 10102 4982 10103 5003 10103 4971 10103 4971 10104 5003 10104 5004 10104 4971 10105 5004 10105 4973 10105 4973 10106 5004 10106 4983 10106 4973 10107 4983 10107 5005 10107 4984 10108 4985 10108 4987 10108 4987 10109 4985 10109 4986 10109 4987 10110 4986 10110 4988 10110 4988 10111 4986 10111 4989 10111 4988 10112 4989 10112 4990 10112 4990 10113 4989 10113 4996 10113 4990 10114 4996 10114 4992 10114 4992 10115 4996 10115 1757 10115 4992 10116 1757 10116 4991 10116 4991 10117 4993 10117 4992 10117 4992 10118 4993 10118 4964 10118 4992 10119 4964 10119 4990 10119 4990 10120 4964 10120 4994 10120 4990 10121 4994 10121 4988 10121 4988 10122 4994 10122 4995 10122 4988 10123 4995 10123 4987 10123 4987 10124 4995 10124 4956 10124 4987 10125 4956 10125 4984 10125 1758 10126 4996 10126 4997 10126 4997 10127 4996 10127 4989 10127 4997 10128 4989 10128 4998 10128 4998 10129 4989 10129 4986 10129 4998 10130 4986 10130 4999 10130 4999 10131 4986 10131 4985 10131 4999 10132 4985 10132 5000 10132 5000 10133 4985 10133 5006 10133 5000 10134 5006 10134 5001 10134 4982 10135 5002 10135 5003 10135 5003 10136 5002 10136 4997 10136 5003 10137 4997 10137 5004 10137 5004 10138 4997 10138 4998 10138 5004 10139 4998 10139 4983 10139 4983 10140 4998 10140 4999 10140 4983 10141 4999 10141 5005 10141 5005 10142 4999 10142 5000 10142 5005 10143 5000 10143 4959 10143 4959 10144 5000 10144 5001 10144 4959 10145 5001 10145 1967 10145 1967 10146 5001 10146 5006 10146 1967 10147 5006 10147 4955 10147 4955 10148 5006 10148 4984 10148 4955 10149 4984 10149 4976 10149 4976 10150 4984 10150 4956 10150 4976 10151 4956 10151 5007 10151 5007 10152 4956 10152 5008 10152 5007 10153 5008 10153 5014 10153 1755 10154 1754 10154 4967 10154 4967 10155 1754 10155 5009 10155 4967 10156 5009 10156 4965 10156 5012 10157 4962 10157 5009 10157 5009 10158 4962 10158 4963 10158 5009 10159 4963 10159 4965 10159 5008 10160 5010 10160 5011 10160 5011 10161 5010 10161 4960 10161 5011 10162 4960 10162 5012 10162 5012 10163 4960 10163 4961 10163 5012 10164 4961 10164 4962 10164 5011 10165 5013 10165 5008 10165 5008 10166 5013 10166 1941 10166 5008 10167 1941 10167 5014 10167 5045 10168 5041 10168 5035 10168 5015 10169 5016 10169 5024 10169 1767 10170 5029 10170 5017 10170 5017 10171 5029 10171 5027 10171 5017 10172 5027 10172 5043 10172 5036 10173 5018 10173 5019 10173 5019 10174 5018 10174 5020 10174 5021 10175 3046 10175 8123 10175 8123 10176 3046 10176 5050 10176 8123 10177 5050 10177 5052 10177 5022 10178 8130 10178 5051 10178 5051 10179 8130 10179 8119 10179 5051 10180 8119 10180 8124 10180 5023 10181 1768 10181 8176 10181 5023 10182 8176 10182 5024 10182 5024 10183 8176 10183 8151 10183 5024 10184 8151 10184 5015 10184 1768 10185 5023 10185 1769 10185 1769 10186 5023 10186 5034 10186 1769 10187 5034 10187 1774 10187 1774 10188 5034 10188 5033 10188 1774 10189 5033 10189 1771 10189 1771 10190 5033 10190 5032 10190 1771 10191 5032 10191 5025 10191 5043 10192 5027 10192 5026 10192 5026 10193 5027 10193 5028 10193 5026 10194 5028 10194 5046 10194 5046 10195 5028 10195 5031 10195 5046 10196 5031 10196 5047 10196 5029 10197 1765 10197 5027 10197 5027 10198 1765 10198 5030 10198 5027 10199 5030 10199 5028 10199 5028 10200 5030 10200 5025 10200 5028 10201 5025 10201 5031 10201 5031 10202 5025 10202 5032 10202 5031 10203 5032 10203 5047 10203 5047 10204 5032 10204 5033 10204 5047 10205 5033 10205 5049 10205 5049 10206 5033 10206 5034 10206 5049 10207 5034 10207 5051 10207 5051 10208 5034 10208 5023 10208 5051 10209 5023 10209 5022 10209 5022 10210 5023 10210 5024 10210 5045 10211 5035 10211 5044 10211 5035 10212 3055 10212 5044 10212 5044 10213 3055 10213 3053 10213 5044 10214 3053 10214 5036 10214 5036 10215 3053 10215 5037 10215 5036 10216 5037 10216 5018 10216 3046 10217 3048 10217 5050 10217 5050 10218 3048 10218 5038 10218 5050 10219 5038 10219 5039 10219 5039 10220 5038 10220 3050 10220 5039 10221 3050 10221 5048 10221 5048 10222 3050 10222 5040 10222 5048 10223 5040 10223 5041 10223 5041 10224 5040 10224 5042 10224 5041 10225 5042 10225 5035 10225 5019 10226 5017 10226 5036 10226 5036 10227 5017 10227 5043 10227 5036 10228 5043 10228 5044 10228 5044 10229 5043 10229 5026 10229 5044 10230 5026 10230 5045 10230 5045 10231 5026 10231 5046 10231 5045 10232 5046 10232 5041 10232 5041 10233 5046 10233 5047 10233 5041 10234 5047 10234 5048 10234 5048 10235 5047 10235 5049 10235 5048 10236 5049 10236 5039 10236 5039 10237 5049 10237 5051 10237 5039 10238 5051 10238 5050 10238 5050 10239 5051 10239 8124 10239 5050 10240 8124 10240 5052 10240 5020 10241 5053 10241 5054 10241 5020 10242 5054 10242 5019 10242 5019 10243 5054 10243 1542 10243 5019 10244 1542 10244 5017 10244 5017 10245 1542 10245 1540 10245 5017 10246 1540 10246 1767 10246 5057 10247 5091 10247 5078 10247 5071 10248 5104 10248 1797 10248 5093 10249 5055 10249 5102 10249 5090 10250 8293 10250 5056 10250 5056 10251 8293 10251 8292 10251 5057 10252 5078 10252 8300 10252 5058 10253 8322 10253 8311 10253 8311 10254 8322 10254 8314 10254 8311 10255 8314 10255 8313 10255 8311 10256 5079 10256 5058 10256 5058 10257 5079 10257 5059 10257 5058 10258 5059 10258 1789 10258 1789 10259 5059 10259 1795 10259 1795 10260 5059 10260 5060 10260 1795 10261 5060 10261 5061 10261 5062 10262 5063 10262 5074 10262 5074 10263 5063 10263 5064 10263 5074 10264 5064 10264 5061 10264 5061 10265 5064 10265 1796 10265 5061 10266 1796 10266 1795 10266 5072 10267 5066 10267 5065 10267 5065 10268 5066 10268 5067 10268 5065 10269 5067 10269 5068 10269 5068 10270 5067 10270 1802 10270 5068 10271 1802 10271 5062 10271 5062 10272 1802 10272 5069 10272 5062 10273 5069 10273 5063 10273 1797 10274 1798 10274 5071 10274 5071 10275 1798 10275 1799 10275 5071 10276 1799 10276 5072 10276 5072 10277 1799 10277 5070 10277 5072 10278 5070 10278 5066 10278 5080 10279 5104 10279 5082 10279 5082 10280 5104 10280 5071 10280 5082 10281 5071 10281 5083 10281 5083 10282 5071 10282 5072 10282 5083 10283 5072 10283 5085 10283 5085 10284 5072 10284 5065 10284 5085 10285 5065 10285 5086 10285 5086 10286 5065 10286 5068 10286 5086 10287 5068 10287 5073 10287 5073 10288 5068 10288 5062 10288 5073 10289 5062 10289 5088 10289 5088 10290 5062 10290 5074 10290 5088 10291 5074 10291 5075 10291 5075 10292 5074 10292 5061 10292 5075 10293 5061 10293 5076 10293 5076 10294 5061 10294 5060 10294 5076 10295 5060 10295 5077 10295 5077 10296 5060 10296 5059 10296 5077 10297 5059 10297 5078 10297 5078 10298 5059 10298 5079 10298 5078 10299 5079 10299 8300 10299 8300 10300 5079 10300 8311 10300 5102 10301 5080 10301 5081 10301 5081 10302 5080 10302 5082 10302 5081 10303 5082 10303 5092 10303 5092 10304 5082 10304 5083 10304 5092 10305 5083 10305 5084 10305 5084 10306 5083 10306 5085 10306 5084 10307 5085 10307 5096 10307 5096 10308 5085 10308 5086 10308 5096 10309 5086 10309 5087 10309 5087 10310 5086 10310 5073 10310 5087 10311 5073 10311 5098 10311 5098 10312 5073 10312 5088 10312 5098 10313 5088 10313 5089 10313 5089 10314 5088 10314 5075 10314 5089 10315 5075 10315 5100 10315 5100 10316 5075 10316 5076 10316 5100 10317 5076 10317 5101 10317 5101 10318 5076 10318 5077 10318 5101 10319 5077 10319 5056 10319 5056 10320 5077 10320 5078 10320 5056 10321 5078 10321 5090 10321 5090 10322 5078 10322 5091 10322 5102 10323 5081 10323 5093 10323 5093 10324 5081 10324 5092 10324 5093 10325 5092 10325 5094 10325 5094 10326 5092 10326 5084 10326 5094 10327 5084 10327 5095 10327 5095 10328 5084 10328 5096 10328 5095 10329 5096 10329 5097 10329 5097 10330 5096 10330 5087 10330 5097 10331 5087 10331 1961 10331 1961 10332 5087 10332 5098 10332 1961 10333 5098 10333 5099 10333 5099 10334 5098 10334 5089 10334 5099 10335 5089 10335 1959 10335 1959 10336 5089 10336 5100 10336 1959 10337 5100 10337 1953 10337 1953 10338 5100 10338 5101 10338 1953 10339 5101 10339 1954 10339 1954 10340 5101 10340 5056 10340 1954 10341 5056 10341 1955 10341 1955 10342 5056 10342 8292 10342 1955 10343 8292 10343 8291 10343 5055 10344 1562 10344 5102 10344 5102 10345 1562 10345 5103 10345 5102 10346 5103 10346 5080 10346 5080 10347 5103 10347 1557 10347 5080 10348 1557 10348 5104 10348 5104 10349 1557 10349 5105 10349 5104 10350 5105 10350 1797 10350 5106 10351 1893 10351 5134 10351 5107 10352 5133 10352 5144 10352 5134 10353 7186 10353 5133 10353 7186 10354 5134 10354 7187 10354 7187 10355 5134 10355 1893 10355 7187 10356 1893 10356 7197 10356 5108 10357 5109 10357 5139 10357 5139 10358 5109 10358 5110 10358 5139 10359 5110 10359 5111 10359 5112 10360 5146 10360 1804 10360 1804 10361 5146 10361 5113 10361 1804 10362 5113 10362 5114 10362 5114 10363 5113 10363 5115 10363 5114 10364 5115 10364 5116 10364 5116 10365 5115 10365 5140 10365 5116 10366 5140 10366 1807 10366 1807 10367 5140 10367 5117 10367 1807 10368 5117 10368 5118 10368 5118 10369 5117 10369 5119 10369 5118 10370 5119 10370 5120 10370 5120 10371 5119 10371 5123 10371 5120 10372 5123 10372 1810 10372 7178 10373 7163 10373 7177 10373 7177 10374 7163 10374 7155 10374 7177 10375 7155 10375 7157 10375 7157 10376 1808 10376 7177 10376 7177 10377 1808 10377 5121 10377 7177 10378 5121 10378 5143 10378 5143 10379 5121 10379 5122 10379 5143 10380 5122 10380 5123 10380 5123 10381 5122 10381 5124 10381 5123 10382 5124 10382 1810 10382 5109 10383 5125 10383 5110 10383 5110 10384 5125 10384 5126 10384 5110 10385 5126 10385 5129 10385 5141 10386 5127 10386 5142 10386 5142 10387 5127 10387 5128 10387 5142 10388 5128 10388 5107 10388 5111 10389 5110 10389 5130 10389 5130 10390 5110 10390 5129 10390 5130 10391 5129 10391 5131 10391 5131 10392 5129 10392 5136 10392 5131 10393 5136 10393 5141 10393 5141 10394 5136 10394 5132 10394 5141 10395 5132 10395 5127 10395 5133 10396 5107 10396 5134 10396 5134 10397 5107 10397 5128 10397 5134 10398 5128 10398 5106 10398 5126 10399 5135 10399 5129 10399 5129 10400 5135 10400 1886 10400 5129 10401 1886 10401 5136 10401 5136 10402 1886 10402 5137 10402 5136 10403 5137 10403 5132 10403 5132 10404 5137 10404 1889 10404 5132 10405 1889 10405 5127 10405 5127 10406 1889 10406 1890 10406 5127 10407 1890 10407 5128 10407 5128 10408 1890 10408 5138 10408 5128 10409 5138 10409 5106 10409 5146 10410 5139 10410 5113 10410 5113 10411 5139 10411 5111 10411 5113 10412 5111 10412 5115 10412 5115 10413 5111 10413 5130 10413 5115 10414 5130 10414 5140 10414 5140 10415 5130 10415 5131 10415 5140 10416 5131 10416 5117 10416 5117 10417 5131 10417 5141 10417 5117 10418 5141 10418 5119 10418 5119 10419 5141 10419 5142 10419 5119 10420 5142 10420 5123 10420 5123 10421 5142 10421 5107 10421 5123 10422 5107 10422 5143 10422 5143 10423 5107 10423 5144 10423 5143 10424 5144 10424 7177 10424 5112 10425 5145 10425 1548 10425 5112 10426 1548 10426 5146 10426 5146 10427 1548 10427 1536 10427 5146 10428 1536 10428 5139 10428 5139 10429 1536 10429 1535 10429 5139 10430 1535 10430 5108 10430 5188 10431 5190 10431 5199 10431 5172 10432 5147 10432 5171 10432 5148 10433 5149 10433 5195 10433 5207 10434 5150 10434 5151 10434 5174 10435 5152 10435 1815 10435 5207 10436 5151 10436 5189 10436 5204 10437 5192 10437 5191 10437 5153 10438 1860 10438 5191 10438 5191 10439 1860 10439 1864 10439 5191 10440 1864 10440 5204 10440 1862 10441 1861 10441 5153 10441 5153 10442 1861 10442 5154 10442 5153 10443 5154 10443 1860 10443 1862 10444 5153 10444 1863 10444 1863 10445 5153 10445 5155 10445 1863 10446 5155 10446 5156 10446 1866 10447 5157 10447 5158 10447 5158 10448 5157 10448 1858 10448 5158 10449 1858 10449 5156 10449 5156 10450 1858 10450 1857 10450 5156 10451 1857 10451 1863 10451 5159 10452 8460 10452 5160 10452 1866 10453 5190 10453 1856 10453 1856 10454 5190 10454 5162 10454 1856 10455 5162 10455 5161 10455 5161 10456 5162 10456 5159 10456 5161 10457 5159 10457 5163 10457 5163 10458 5159 10458 5160 10458 5163 10459 5160 10459 8456 10459 5166 10460 8455 10460 5164 10460 5164 10461 8455 10461 5165 10461 5166 10462 5164 10462 8478 10462 8478 10463 5164 10463 5167 10463 8478 10464 5167 10464 5171 10464 1819 10465 5168 10465 5167 10465 5167 10466 5168 10466 5169 10466 5167 10467 5169 10467 5171 10467 5171 10468 5169 10468 5170 10468 5171 10469 5170 10469 5172 10469 5176 10470 1814 10470 5173 10470 5173 10471 1814 10471 1821 10471 5173 10472 1821 10472 5179 10472 5179 10473 1821 10473 1817 10473 1815 10474 5175 10474 5174 10474 5174 10475 5175 10475 5177 10475 5174 10476 5177 10476 5176 10476 5176 10477 5177 10477 5178 10477 5176 10478 5178 10478 1814 10478 1817 10479 5203 10479 5179 10479 5179 10480 5203 10480 5184 10480 5179 10481 5184 10481 5173 10481 5173 10482 5184 10482 5180 10482 5173 10483 5180 10483 5176 10483 5176 10484 5180 10484 5181 10484 5176 10485 5181 10485 5174 10485 5174 10486 5181 10486 5151 10486 5174 10487 5151 10487 5152 10487 5152 10488 5151 10488 5150 10488 5203 10489 5182 10489 5184 10489 5184 10490 5182 10490 5183 10490 5184 10491 5183 10491 5180 10491 5180 10492 5183 10492 5185 10492 5180 10493 5185 10493 5181 10493 5181 10494 5185 10494 5186 10494 5181 10495 5186 10495 5151 10495 5151 10496 5186 10496 5187 10496 5151 10497 5187 10497 5189 10497 5190 10498 5188 10498 5162 10498 5162 10499 5188 10499 5164 10499 5162 10500 5164 10500 5159 10500 5159 10501 5164 10501 5165 10501 5159 10502 5165 10502 8460 10502 5182 10503 5202 10503 5183 10503 5183 10504 5202 10504 5201 10504 5183 10505 5201 10505 5185 10505 5185 10506 5201 10506 5200 10506 5185 10507 5200 10507 5186 10507 5186 10508 5200 10508 5196 10508 5186 10509 5196 10509 5187 10509 5187 10510 5196 10510 5195 10510 5187 10511 5195 10511 5189 10511 5189 10512 5195 10512 5149 10512 1866 10513 5158 10513 5190 10513 5190 10514 5158 10514 5156 10514 5190 10515 5156 10515 5199 10515 5199 10516 5156 10516 5155 10516 5199 10517 5155 10517 5198 10517 5198 10518 5155 10518 5153 10518 5198 10519 5153 10519 5197 10519 5197 10520 5153 10520 5191 10520 5197 10521 5191 10521 5194 10521 5194 10522 5191 10522 5192 10522 5194 10523 5192 10523 5193 10523 5193 10524 5148 10524 5194 10524 5194 10525 5148 10525 5195 10525 5194 10526 5195 10526 5197 10526 5197 10527 5195 10527 5196 10527 5197 10528 5196 10528 5198 10528 5198 10529 5196 10529 5200 10529 5198 10530 5200 10530 5199 10530 5199 10531 5200 10531 5201 10531 5199 10532 5201 10532 5188 10532 5188 10533 5201 10533 5202 10533 5188 10534 5202 10534 5164 10534 5164 10535 5202 10535 5182 10535 5164 10536 5182 10536 5167 10536 5167 10537 5182 10537 5203 10537 5167 10538 5203 10538 1819 10538 1819 10539 5203 10539 1817 10539 5204 10540 1846 10540 5192 10540 5192 10541 1846 10541 1545 10541 5192 10542 1545 10542 5193 10542 5205 10543 5189 10543 5206 10543 5206 10544 5189 10544 5149 10544 5206 10545 5149 10545 1545 10545 1545 10546 5149 10546 5148 10546 1545 10547 5148 10547 5193 10547 5152 10548 5150 10548 5205 10548 5205 10549 5150 10549 5207 10549 5205 10550 5207 10550 5189 10550 5205 10551 1544 10551 5152 10551 5152 10552 1544 10552 1510 10552 5152 10553 1510 10553 1815 10553 8440 10554 5240 10554 5229 10554 8419 10555 5217 10555 5213 10555 5219 10556 5259 10556 1849 10556 5209 10557 1824 10557 5241 10557 5210 10558 5208 10558 5245 10558 5245 10559 5208 10559 5209 10559 5245 10560 5209 10560 5242 10560 5242 10561 5209 10561 5241 10561 5211 10562 1829 10562 5210 10562 5210 10563 1829 10563 1826 10563 5210 10564 1826 10564 5208 10564 5210 10565 5247 10565 5211 10565 5211 10566 5247 10566 5249 10566 5211 10567 5249 10567 1831 10567 1831 10568 5249 10568 5250 10568 1831 10569 5250 10569 5212 10569 5212 10570 5250 10570 5216 10570 5216 10571 5250 10571 5252 10571 5216 10572 5252 10572 5254 10572 5213 10573 1834 10573 5255 10573 5255 10574 1834 10574 5214 10574 5255 10575 5214 10575 5254 10575 5254 10576 5214 10576 5215 10576 5254 10577 5215 10577 5216 10577 5217 10578 8423 10578 8422 10578 8422 10579 5218 10579 5217 10579 5217 10580 5218 10580 8412 10580 5217 10581 8412 10581 5213 10581 5213 10582 8412 10582 8395 10582 5213 10583 8395 10583 1834 10583 1849 10584 1848 10584 5219 10584 5219 10585 1848 10585 1871 10585 5219 10586 1871 10586 5220 10586 5220 10587 1871 10587 5221 10587 5220 10588 5221 10588 5231 10588 5231 10589 5221 10589 1869 10589 5231 10590 1869 10590 5232 10590 5232 10591 1869 10591 5222 10591 5232 10592 5222 10592 5234 10592 5234 10593 5222 10593 1851 10593 5234 10594 1851 10594 5223 10594 5223 10595 1851 10595 5224 10595 5223 10596 5224 10596 5225 10596 5225 10597 5224 10597 5226 10597 5225 10598 5226 10598 5236 10598 5236 10599 5226 10599 5227 10599 5236 10600 5227 10600 5238 10600 5238 10601 5227 10601 5228 10601 5238 10602 5228 10602 5229 10602 5229 10603 5228 10603 8452 10603 5229 10604 8452 10604 8440 10604 5243 10605 5259 10605 5244 10605 5244 10606 5259 10606 5219 10606 5244 10607 5219 10607 5246 10607 5246 10608 5219 10608 5220 10608 5246 10609 5220 10609 5230 10609 5230 10610 5220 10610 5231 10610 5230 10611 5231 10611 5248 10611 5248 10612 5231 10612 5232 10612 5248 10613 5232 10613 5233 10613 5233 10614 5232 10614 5234 10614 5233 10615 5234 10615 5251 10615 5251 10616 5234 10616 5223 10616 5251 10617 5223 10617 5253 10617 5253 10618 5223 10618 5225 10618 5253 10619 5225 10619 5235 10619 5235 10620 5225 10620 5236 10620 5235 10621 5236 10621 5237 10621 5237 10622 5236 10622 5238 10622 5237 10623 5238 10623 5256 10623 5256 10624 5238 10624 5229 10624 5256 10625 5229 10625 5239 10625 5239 10626 5229 10626 5240 10626 5241 10627 5243 10627 5242 10627 5242 10628 5243 10628 5244 10628 5242 10629 5244 10629 5245 10629 5245 10630 5244 10630 5246 10630 5245 10631 5246 10631 5210 10631 5210 10632 5246 10632 5230 10632 5210 10633 5230 10633 5247 10633 5247 10634 5230 10634 5248 10634 5247 10635 5248 10635 5249 10635 5249 10636 5248 10636 5233 10636 5249 10637 5233 10637 5250 10637 5250 10638 5233 10638 5251 10638 5250 10639 5251 10639 5252 10639 5252 10640 5251 10640 5253 10640 5252 10641 5253 10641 5254 10641 5254 10642 5253 10642 5235 10642 5254 10643 5235 10643 5255 10643 5255 10644 5235 10644 5237 10644 5255 10645 5237 10645 5213 10645 5213 10646 5237 10646 5256 10646 5213 10647 5256 10647 8419 10647 8419 10648 5256 10648 5239 10648 1824 10649 1823 10649 5241 10649 5241 10650 1823 10650 5257 10650 5241 10651 5257 10651 5243 10651 5243 10652 5257 10652 5259 10652 5257 10653 5258 10653 5259 10653 5259 10654 5258 10654 1512 10654 5259 10655 1512 10655 1849 10655 6269 10656 5278 10656 5270 10656 6276 10657 6286 10657 5260 10657 5261 10658 6296 10658 5266 10658 6295 10659 5262 10659 5263 10659 5264 10660 5265 10660 5283 10660 5261 10661 5266 10661 5277 10661 5278 10662 6269 10662 5260 10662 5260 10663 6269 10663 6270 10663 5260 10664 6270 10664 6276 10664 5269 10665 5267 10665 5270 10665 5270 10666 5267 10666 1841 10666 5270 10667 1841 10667 6269 10667 5282 10668 1844 10668 5268 10668 5268 10669 1844 10669 5269 10669 5268 10670 5269 10670 5280 10670 5280 10671 5269 10671 5270 10671 5305 10672 5271 10672 5282 10672 5282 10673 5271 10673 1840 10673 5282 10674 1840 10674 1844 10674 6198 10675 5302 10675 5329 10675 5329 10676 5302 10676 5274 10676 5301 10677 5316 10677 5317 10677 5275 10678 5272 10678 5301 10678 5301 10679 5272 10679 5300 10679 5273 10680 5275 10680 5303 10680 5303 10681 5275 10681 5301 10681 5303 10682 5301 10682 5274 10682 5274 10683 5301 10683 5317 10683 5274 10684 5317 10684 5329 10684 5273 10685 5306 10685 5275 10685 5275 10686 5306 10686 5307 10686 5275 10687 5307 10687 5272 10687 5272 10688 5307 10688 5276 10688 5260 10689 5277 10689 5278 10689 5278 10690 5277 10690 5266 10690 5278 10691 5266 10691 5270 10691 5270 10692 5266 10692 5279 10692 5270 10693 5279 10693 5280 10693 5280 10694 5279 10694 5308 10694 5280 10695 5308 10695 5268 10695 5268 10696 5308 10696 5281 10696 5268 10697 5281 10697 5282 10697 5282 10698 5281 10698 5311 10698 5262 10699 5264 10699 5263 10699 5263 10700 5264 10700 5283 10700 5263 10701 5283 10701 5284 10701 5284 10702 5283 10702 3076 10702 5284 10703 3076 10703 5309 10703 5309 10704 3076 10704 3078 10704 5309 10705 3078 10705 5310 10705 5288 10706 5289 10706 5296 10706 5296 10707 5289 10707 3091 10707 5296 10708 3091 10708 3060 10708 3060 10709 5285 10709 5296 10709 5296 10710 5285 10710 5286 10710 5296 10711 5286 10711 5298 10711 5290 10712 3089 10712 5288 10712 5288 10713 3089 10713 5287 10713 5288 10714 5287 10714 5289 10714 5293 10715 5291 10715 5290 10715 5290 10716 5291 10716 5292 10716 5290 10717 5292 10717 3089 10717 5293 10718 5290 10718 5294 10718 5294 10719 5290 10719 5288 10719 5294 10720 5288 10720 5295 10720 5295 10721 5288 10721 5296 10721 5295 10722 5296 10722 5297 10722 5297 10723 5296 10723 5298 10723 5297 10724 5298 10724 5335 10724 5333 10725 5332 10725 5300 10725 5300 10726 5332 10726 5299 10726 5300 10727 5299 10727 5301 10727 5301 10728 5299 10728 5315 10728 5301 10729 5315 10729 5316 10729 5302 10730 6210 10730 5274 10730 5274 10731 6210 10731 1837 10731 5274 10732 1837 10732 5303 10732 5303 10733 1837 10733 5304 10733 5303 10734 5304 10734 5273 10734 5273 10735 5304 10735 5305 10735 5273 10736 5305 10736 5306 10736 5306 10737 5305 10737 5282 10737 5306 10738 5282 10738 5307 10738 5307 10739 5282 10739 5311 10739 5307 10740 5311 10740 5276 10740 5276 10741 5311 10741 5312 10741 5276 10742 5312 10742 5272 10742 5272 10743 5312 10743 5313 10743 5272 10744 5313 10744 5300 10744 5300 10745 5313 10745 5314 10745 5300 10746 5314 10746 5333 10746 3078 10747 3079 10747 5310 10747 5310 10748 3079 10748 3084 10748 5310 10749 3084 10749 5293 10749 5293 10750 3084 10750 3090 10750 5293 10751 3090 10751 5291 10751 6296 10752 6295 10752 5266 10752 5266 10753 6295 10753 5263 10753 5266 10754 5263 10754 5279 10754 5279 10755 5263 10755 5284 10755 5279 10756 5284 10756 5308 10756 5308 10757 5284 10757 5309 10757 5308 10758 5309 10758 5281 10758 5281 10759 5309 10759 5310 10759 5281 10760 5310 10760 5311 10760 5311 10761 5310 10761 5293 10761 5311 10762 5293 10762 5312 10762 5312 10763 5293 10763 5294 10763 5312 10764 5294 10764 5313 10764 5313 10765 5294 10765 5295 10765 5313 10766 5295 10766 5314 10766 5314 10767 5295 10767 5297 10767 5314 10768 5297 10768 5333 10768 5333 10769 5297 10769 5335 10769 5330 10770 5316 10770 5315 10770 5316 10771 5330 10771 5317 10771 6198 10772 5329 10772 5327 10772 5324 10773 5318 10773 5326 10773 5326 10774 5318 10774 6200 10774 5326 10775 6200 10775 6199 10775 5323 10776 5341 10776 5331 10776 5331 10777 5341 10777 5319 10777 5331 10778 5319 10778 5325 10778 5334 10779 5320 10779 5321 10779 5321 10780 5320 10780 5322 10780 5321 10781 5322 10781 5323 10781 5323 10782 5322 10782 5339 10782 5323 10783 5339 10783 5341 10783 5319 10784 5324 10784 5325 10784 5325 10785 5324 10785 5326 10785 5325 10786 5326 10786 5327 10786 5327 10787 5326 10787 6199 10787 5327 10788 6199 10788 6198 10788 2340 10789 5320 10789 3059 10789 3059 10790 5320 10790 5334 10790 3059 10791 5334 10791 5336 10791 5336 10792 5334 10792 5328 10792 5329 10793 5317 10793 5327 10793 5327 10794 5317 10794 5330 10794 5327 10795 5330 10795 5325 10795 5325 10796 5330 10796 5315 10796 5325 10797 5315 10797 5331 10797 5331 10798 5315 10798 5299 10798 5331 10799 5299 10799 5323 10799 5323 10800 5299 10800 5332 10800 5323 10801 5332 10801 5321 10801 5321 10802 5332 10802 5333 10802 5321 10803 5333 10803 5334 10803 5334 10804 5333 10804 5335 10804 5334 10805 5335 10805 5328 10805 5328 10806 5335 10806 5298 10806 5328 10807 5298 10807 5336 10807 5336 10808 5298 10808 5286 10808 5336 10809 5286 10809 5337 10809 5337 10810 5286 10810 5285 10810 5320 10811 2340 10811 1487 10811 5339 10812 5322 10812 5340 10812 5340 10813 5322 10813 5320 10813 5340 10814 5320 10814 5338 10814 5338 10815 5320 10815 1487 10815 5339 10816 5340 10816 5341 10816 5341 10817 5340 10817 5342 10817 5341 10818 5342 10818 5319 10818 5319 10819 5342 10819 5324 10819 5324 10820 5342 10820 1480 10820 5324 10821 1480 10821 5318 10821 455 10822 6610 10822 1509 10822 455 10823 453 10823 6610 10823 6610 10824 453 10824 450 10824 6610 10825 450 10825 5343 10825 450 10826 447 10826 5343 10826 5343 10827 447 10827 446 10827 5343 10828 446 10828 6602 10828 6602 10829 446 10829 5345 10829 6602 10830 5345 10830 5347 10830 424 10831 5344 10831 5348 10831 5345 10832 445 10832 5347 10832 5347 10833 445 10833 5346 10833 5347 10834 5346 10834 5348 10834 5348 10835 5346 10835 444 10835 5348 10836 444 10836 424 10836 1507 10837 5355 10837 5356 10837 5356 10838 5349 10838 1507 10838 1507 10839 5349 10839 5350 10839 1507 10840 5350 10840 1509 10840 1509 10841 5350 10841 5351 10841 1509 10842 5351 10842 455 10842 5344 10843 424 10843 5352 10843 5352 10844 424 10844 5353 10844 5352 10845 5353 10845 5355 10845 5355 10846 5353 10846 5354 10846 5355 10847 5354 10847 5356 10847 6672 10848 5357 10848 6676 10848 6676 10849 5357 10849 5358 10849 6676 10850 5358 10850 6682 10850 5358 10851 481 10851 6682 10851 6682 10852 481 10852 5359 10852 6682 10853 5359 10853 5362 10853 5359 10854 5360 10854 5362 10854 5362 10855 5360 10855 5361 10855 5362 10856 5361 10856 5363 10856 5361 10857 5364 10857 5363 10857 5363 10858 5364 10858 478 10858 5363 10859 478 10859 5372 10859 5365 10860 5367 10860 5366 10860 5366 10861 5367 10861 5368 10861 5366 10862 5368 10862 5369 10862 5369 10863 5368 10863 5456 10863 5369 10864 5456 10864 5370 10864 5370 10865 5456 10865 5459 10865 5370 10866 5459 10866 6672 10866 6672 10867 5459 10867 5371 10867 6672 10868 5371 10868 5357 10868 478 10869 474 10869 5372 10869 5372 10870 474 10870 5373 10870 5372 10871 5373 10871 5365 10871 5365 10872 5373 10872 472 10872 5365 10873 472 10873 5367 10873 5374 10874 5452 10874 6019 10874 6019 10875 5452 10875 6000 10875 6019 10876 6000 10876 5376 10876 5376 10877 6000 10877 5375 10877 5376 10878 5375 10878 6017 10878 6017 10879 5375 10879 5999 10879 6017 10880 5999 10880 6015 10880 6015 10881 5999 10881 6001 10881 6015 10882 6001 10882 5429 10882 5379 10883 5381 10883 6011 10883 6011 10884 5377 10884 5379 10884 5379 10885 5377 10885 5378 10885 5379 10886 5378 10886 6006 10886 6016 10887 5380 10887 5381 10887 5381 10888 5380 10888 6014 10888 5381 10889 6014 10889 6011 10889 5381 10890 1539 10890 6016 10890 6016 10891 1539 10891 5382 10891 6016 10892 5382 10892 5383 10892 5383 10893 5382 10893 3773 10893 5383 10894 3773 10894 6018 10894 5977 10895 5384 10895 5976 10895 5976 10896 5384 10896 5946 10896 5976 10897 5946 10897 5385 10897 5385 10898 5946 10898 5387 10898 5385 10899 5387 10899 5386 10899 5386 10900 5387 10900 5388 10900 5386 10901 5388 10901 5389 10901 5389 10902 5388 10902 5390 10902 5389 10903 5390 10903 5436 10903 1549 10904 5947 10904 5391 10904 5391 10905 5947 10905 5392 10905 5391 10906 5392 10906 1537 10906 5393 10907 5949 10907 1571 10907 1571 10908 5949 10908 5394 10908 1571 10909 5394 10909 1549 10909 1549 10910 5394 10910 5948 10910 1549 10911 5948 10911 5947 10911 1567 10912 5958 10912 5395 10912 5393 10913 1571 10913 5952 10913 5952 10914 1571 10914 1567 10914 5952 10915 1567 10915 5950 10915 5950 10916 1567 10916 5395 10916 2205 10917 2206 10917 5396 10917 5396 10918 2206 10918 2209 10918 5397 10919 303 10919 5398 10919 5398 10920 303 10920 1262 10920 1262 10921 5399 10921 5398 10921 5398 10922 5399 10922 1260 10922 5398 10923 1260 10923 1155 10923 1155 10924 1260 10924 5400 10924 1155 10925 5400 10925 2209 10925 2209 10926 5400 10926 5401 10926 2209 10927 5401 10927 5396 10927 5396 10928 5401 10928 5402 10928 5396 10929 5402 10929 5403 10929 5403 10930 5402 10930 5440 10930 5403 10931 5440 10931 5954 10931 5404 10932 5935 10932 5406 10932 5406 10933 5935 10933 5934 10933 5934 10934 5405 10934 5406 10934 5406 10935 5405 10935 5969 10935 5406 10936 5969 10936 5967 10936 5967 10937 5965 10937 5406 10937 5406 10938 5965 10938 5963 10938 5406 10939 5963 10939 1681 10939 1671 10940 5985 10940 5407 10940 5407 10941 5985 10941 5412 10941 5409 10942 5995 10942 5410 10942 5412 10943 5990 10943 5408 10943 5408 10944 5990 10944 5409 10944 5408 10945 5409 10945 6025 10945 6025 10946 5409 10946 5410 10946 6028 10947 6027 10947 5407 10947 5407 10948 6027 10948 5411 10948 5407 10949 5411 10949 1670 10949 5412 10950 5408 10950 5407 10950 5407 10951 5408 10951 5413 10951 5407 10952 5413 10952 6028 10952 5414 10953 2191 10953 5418 10953 5414 10954 5418 10954 2189 10954 6010 10955 6003 10955 6009 10955 6009 10956 6003 10956 5415 10956 6009 10957 5415 10957 5418 10957 5418 10958 5415 10958 1265 10958 5418 10959 1265 10959 1266 10959 1271 10960 287 10960 5416 10960 5416 10961 287 10961 5417 10961 5416 10962 5417 10962 284 10962 1271 10963 5416 10963 1268 10963 1268 10964 5416 10964 5419 10964 1268 10965 5419 10965 1266 10965 1266 10966 5419 10966 5418 10966 5418 10967 5419 10967 1148 10967 5418 10968 1148 10968 2189 10968 5958 10969 1567 10969 5420 10969 5420 10970 1567 10970 5422 10970 5420 10971 5422 10971 5421 10971 5421 10972 5422 10972 5960 10972 5960 10973 5422 10973 5957 10973 5957 10974 5422 10974 1566 10974 5957 10975 1566 10975 2199 10975 5423 10976 5424 10976 5425 10976 5425 10977 5424 10977 5426 10977 5425 10978 5426 10978 6005 10978 5425 10979 5427 10979 5423 10979 5423 10980 5427 10980 5379 10980 5423 10981 5379 10981 6006 10981 5432 10982 5428 10982 5429 10982 5429 10983 5428 10983 6012 10983 6012 10984 5430 10984 5429 10984 5429 10985 5430 10985 6013 10985 5429 10986 6013 10986 6015 10986 5429 10987 5431 10987 5432 10987 5432 10988 5431 10988 5433 10988 5432 10989 5433 10989 6010 10989 6010 10990 5433 10990 5434 10990 6010 10991 5434 10991 6003 10991 5390 10992 5435 10992 5436 10992 5436 10993 5435 10993 5437 10993 5436 10994 5437 10994 5981 10994 5981 10995 5437 10995 5953 10995 5981 10996 5953 10996 5438 10996 5438 10997 5953 10997 5984 10997 5954 10998 5440 10998 5439 10998 5439 10999 5440 10999 5984 10999 5439 11000 5984 11000 5951 11000 5951 11001 5984 11001 5953 11001 5442 11002 5971 11002 5441 11002 5441 11003 5971 11003 5405 11003 5405 11004 5971 11004 5970 11004 5405 11005 5970 11005 5969 11005 5441 11006 5942 11006 5442 11006 5442 11007 5942 11007 5443 11007 5442 11008 5443 11008 5445 11008 5445 11009 5443 11009 5444 11009 5445 11010 5444 11010 5975 11010 5975 11011 5444 11011 5446 11011 5975 11012 5446 11012 5448 11012 5448 11013 5446 11013 5447 11013 5448 11014 5447 11014 5977 11014 5977 11015 5447 11015 5384 11015 6023 11016 5449 11016 5993 11016 5450 11017 6020 11017 5993 11017 5993 11018 6020 11018 6021 11018 5993 11019 6021 11019 6023 11019 5449 11020 6023 11020 5451 11020 5451 11021 6023 11021 5410 11021 5451 11022 5410 11022 5995 11022 5452 11023 5374 11023 5998 11023 5998 11024 5374 11024 5453 11024 5998 11025 5453 11025 5450 11025 5450 11026 5453 11026 5454 11026 5450 11027 5454 11027 6020 11027 5455 11028 5457 11028 5456 11028 5456 11029 5457 11029 5458 11029 5456 11030 5458 11030 5459 11030 5459 11031 5458 11031 316 11031 5459 11032 316 11032 482 11032 482 11033 316 11033 315 11033 482 11034 315 11034 487 11034 487 11035 315 11035 5460 11035 487 11036 5460 11036 463 11036 463 11037 5460 11037 314 11037 463 11038 314 11038 5461 11038 5461 11039 314 11039 5463 11039 5461 11040 5463 11040 5462 11040 5462 11041 5463 11041 321 11041 5462 11042 321 11042 492 11042 492 11043 321 11043 5464 11043 492 11044 5464 11044 493 11044 493 11045 5464 11045 320 11045 493 11046 320 11046 467 11046 467 11047 320 11047 319 11047 467 11048 319 11048 471 11048 471 11049 319 11049 5455 11049 471 11050 5455 11050 5456 11050 306 11051 305 11051 444 11051 444 11052 305 11052 5465 11052 444 11053 5465 11053 424 11053 424 11054 5465 11054 5466 11054 424 11055 5466 11055 423 11055 423 11056 5466 11056 5467 11056 423 11057 5467 11057 426 11057 426 11058 5467 11058 313 11058 426 11059 313 11059 425 11059 425 11060 313 11060 312 11060 425 11061 312 11061 427 11061 427 11062 312 11062 311 11062 427 11063 311 11063 434 11063 434 11064 311 11064 5468 11064 434 11065 5468 11065 436 11065 436 11066 5468 11066 5469 11066 436 11067 5469 11067 439 11067 439 11068 5469 11068 308 11068 439 11069 308 11069 438 11069 438 11070 308 11070 5470 11070 438 11071 5470 11071 442 11071 442 11072 5470 11072 306 11072 442 11073 306 11073 444 11073 5586 11074 5471 11074 5576 11074 141 11075 5527 11075 5529 11075 5472 11076 5475 11076 5473 11076 5473 11077 5475 11077 145 11077 145 11078 5475 11078 5474 11078 5474 11079 5475 11079 5476 11079 5476 11080 5536 11080 5477 11080 5477 11081 5536 11081 5478 11081 5478 11082 5536 11082 5479 11082 5478 11083 5479 11083 5480 11083 5484 11084 5481 11084 5482 11084 5482 11085 5483 11085 5484 11085 5484 11086 5483 11086 5485 11086 5484 11087 5485 11087 5486 11087 5486 11088 5485 11088 5487 11088 5486 11089 5487 11089 5488 11089 5481 11090 5484 11090 5489 11090 5489 11091 5484 11091 5491 11091 5489 11092 5491 11092 5490 11092 5490 11093 5491 11093 5498 11093 5490 11094 5498 11094 5492 11094 5496 11095 5493 11095 5494 11095 5494 11096 5495 11096 5496 11096 5496 11097 5495 11097 5497 11097 5496 11098 5497 11098 5499 11098 5492 11099 5498 11099 5499 11099 5499 11100 5498 11100 5500 11100 5499 11101 5500 11101 5496 11101 5496 11102 5500 11102 5509 11102 5501 11103 5509 11103 5502 11103 5501 11104 5502 11104 5503 11104 5509 11105 5508 11105 5504 11105 5504 11106 5505 11106 5509 11106 5509 11107 5505 11107 5506 11107 5509 11108 5506 11108 5502 11108 5502 11109 5506 11109 5507 11109 5508 11110 5509 11110 5514 11110 5510 11111 5514 11111 5515 11111 5510 11112 5515 11112 5511 11112 5514 11113 5518 11113 5512 11113 5512 11114 5513 11114 5514 11114 5514 11115 5513 11115 5516 11115 5514 11116 5516 11116 5515 11116 5515 11117 5516 11117 5517 11117 5518 11118 5514 11118 5522 11118 5519 11119 5520 11119 5521 11119 5522 11120 5531 11120 5523 11120 5521 11121 5522 11121 5519 11121 5519 11122 5522 11122 5523 11122 5519 11123 5523 11123 5524 11123 5525 11124 5526 11124 5527 11124 5527 11125 5526 11125 5528 11125 5527 11126 5528 11126 5529 11126 5522 11127 5529 11127 5530 11127 5522 11128 5530 11128 5531 11128 5532 11129 5533 11129 5479 11129 5547 11130 5546 11130 5534 11130 5534 11131 5535 11131 5547 11131 5547 11132 5535 11132 5537 11132 5547 11133 5537 11133 5536 11133 5537 11134 5538 11134 5536 11134 5479 11135 5536 11135 5539 11135 5479 11136 5539 11136 5532 11136 5556 11137 5541 11137 5540 11137 5540 11138 5541 11138 5542 11138 5540 11139 5542 11139 5543 11139 5543 11140 5544 11140 5540 11140 5540 11141 5544 11141 5545 11141 5540 11142 5545 11142 5547 11142 5546 11143 5547 11143 5548 11143 5546 11144 5548 11144 5549 11144 5558 11145 5550 11145 5556 11145 5561 11146 5551 11146 5552 11146 5552 11147 5553 11147 5561 11147 5561 11148 5553 11148 5554 11148 5561 11149 5554 11149 5540 11149 5554 11150 5555 11150 5540 11150 5556 11151 5540 11151 5557 11151 5556 11152 5557 11152 5558 11152 5572 11153 5559 11153 5565 11153 5565 11154 5559 11154 5560 11154 5565 11155 5560 11155 5563 11155 5565 11156 5567 11156 5561 11156 5551 11157 5561 11157 5562 11157 5563 11158 5564 11158 5565 11158 5565 11159 5564 11159 5566 11159 5565 11160 5566 11160 5567 11160 5568 11161 5569 11161 5582 11161 5582 11162 5569 11162 5570 11162 5582 11163 5570 11163 5565 11163 5571 11164 5572 11164 5565 11164 5573 11165 5565 11165 5570 11165 5573 11166 5570 11166 5574 11166 5574 11167 5570 11167 5575 11167 5471 11168 5577 11168 5576 11168 5576 11169 5577 11169 5578 11169 5576 11170 5578 11170 5580 11170 5582 11171 5579 11171 5568 11171 5580 11172 5581 11172 5576 11172 5576 11173 5581 11173 5583 11173 5576 11174 5583 11174 5582 11174 5582 11175 5583 11175 5584 11175 5582 11176 5584 11176 5585 11176 5586 11177 5486 11177 5587 11177 5587 11178 5486 11178 5588 11178 5589 11179 5652 11179 5627 11179 5590 11180 2598 11180 5597 11180 5598 11181 5591 11181 5599 11181 5592 11182 5636 11182 5601 11182 5636 11183 2596 11183 5634 11183 5634 11184 2596 11184 5593 11184 2601 11185 2606 11185 2605 11185 2605 11186 5631 11186 2601 11186 2601 11187 5631 11187 5632 11187 2601 11188 5632 11188 2602 11188 5593 11189 5595 11189 5594 11189 5594 11190 5595 11190 2604 11190 5594 11191 2604 11191 2602 11191 5625 11192 5590 11192 5596 11192 5596 11193 5590 11193 5640 11193 5640 11194 5590 11194 5597 11194 5640 11195 5597 11195 5638 11195 5638 11196 5597 11196 5598 11196 5638 11197 5598 11197 5600 11197 5600 11198 5598 11198 5599 11198 5600 11199 5599 11199 5601 11199 5601 11200 5599 11200 5602 11200 5601 11201 5602 11201 5592 11201 5622 11202 5624 11202 5639 11202 5639 11203 5624 11203 5603 11203 5639 11204 5603 11204 5605 11204 5605 11205 5603 11205 5604 11205 5605 11206 5604 11206 5641 11206 5604 11207 464 11207 5641 11207 5641 11208 464 11208 5607 11208 5641 11209 5607 11209 5606 11209 5606 11210 5607 11210 5608 11210 5606 11211 5608 11211 486 11211 5609 11212 5644 11212 470 11212 469 11213 5610 11213 5611 11213 5611 11214 5610 11214 5633 11214 5611 11215 5633 11215 5615 11215 5615 11216 5633 11216 5616 11216 5610 11217 5612 11217 5633 11217 5633 11218 5612 11218 473 11218 5633 11219 473 11219 5613 11219 5613 11220 473 11220 475 11220 5613 11221 475 11221 5617 11221 470 11222 469 11222 5609 11222 5609 11223 469 11223 5611 11223 5609 11224 5611 11224 5614 11224 5614 11225 5611 11225 5615 11225 5614 11226 5615 11226 5647 11226 5647 11227 5615 11227 5616 11227 5647 11228 5616 11228 5643 11228 475 11229 476 11229 5617 11229 5617 11230 476 11230 5618 11230 5617 11231 5618 11231 5619 11231 5619 11232 5618 11232 477 11232 5619 11233 477 11233 5635 11233 5635 11234 477 11234 479 11234 5635 11235 479 11235 5637 11235 5637 11236 479 11236 480 11236 5637 11237 480 11237 5620 11237 5620 11238 480 11238 5621 11238 5620 11239 5621 11239 5622 11239 5622 11240 5621 11240 5623 11240 5622 11241 5623 11241 5624 11241 5642 11242 5629 11242 5596 11242 5596 11243 5629 11243 5589 11243 5596 11244 5589 11244 5625 11244 5625 11245 5589 11245 5627 11245 5625 11246 5627 11246 5626 11246 5626 11247 5627 11247 5650 11247 5652 11248 5589 11248 5628 11248 5628 11249 5589 11249 5629 11249 5628 11250 5629 11250 5630 11250 5630 11251 5629 11251 5642 11251 5630 11252 5642 11252 5654 11252 2599 11253 5648 11253 2605 11253 2605 11254 5648 11254 5643 11254 2605 11255 5643 11255 5631 11255 5631 11256 5643 11256 5616 11256 5631 11257 5616 11257 5632 11257 5632 11258 5616 11258 5633 11258 5632 11259 5633 11259 2602 11259 2602 11260 5633 11260 5613 11260 2602 11261 5613 11261 5594 11261 5594 11262 5613 11262 5617 11262 5594 11263 5617 11263 5593 11263 5593 11264 5617 11264 5619 11264 5593 11265 5619 11265 5634 11265 5634 11266 5619 11266 5635 11266 5634 11267 5635 11267 5636 11267 5636 11268 5635 11268 5637 11268 5636 11269 5637 11269 5601 11269 5601 11270 5637 11270 5620 11270 5601 11271 5620 11271 5600 11271 5600 11272 5620 11272 5622 11272 5600 11273 5622 11273 5638 11273 5638 11274 5622 11274 5639 11274 5638 11275 5639 11275 5640 11275 5640 11276 5639 11276 5605 11276 5640 11277 5605 11277 5596 11277 5596 11278 5605 11278 5641 11278 5596 11279 5641 11279 5642 11279 5642 11280 5641 11280 5606 11280 5642 11281 5606 11281 5654 11281 5654 11282 5606 11282 486 11282 5654 11283 486 11283 485 11283 5643 11284 5681 11284 5646 11284 468 11285 5644 11285 5683 11285 5683 11286 5644 11286 5609 11286 5683 11287 5609 11287 5645 11287 5645 11288 5609 11288 5614 11288 5645 11289 5614 11289 5646 11289 5646 11290 5614 11290 5647 11290 5646 11291 5647 11291 5643 11291 5681 11292 5643 11292 5712 11292 5712 11293 5643 11293 5648 11293 5712 11294 5648 11294 5649 11294 5649 11295 5648 11295 2599 11295 5649 11296 2599 11296 5733 11296 5627 11297 5651 11297 5650 11297 5650 11298 5651 11298 5684 11298 5652 11299 5692 11299 5627 11299 5627 11300 5692 11300 5651 11300 485 11301 5653 11301 5654 11301 5654 11302 5653 11302 5669 11302 5654 11303 5669 11303 5630 11303 5630 11304 5669 11304 5751 11304 5630 11305 5751 11305 5628 11305 5628 11306 5751 11306 5655 11306 5628 11307 5655 11307 5652 11307 5652 11308 5655 11308 5737 11308 5652 11309 5737 11309 5692 11309 5709 11310 2407 11310 5656 11310 5656 11311 2407 11311 2484 11311 5657 11312 465 11312 466 11312 465 11313 5657 11313 5735 11313 5658 11314 5734 11314 5659 11314 5658 11315 5659 11315 5746 11315 5662 11316 5660 11316 5746 11316 5746 11317 5660 11317 494 11317 5746 11318 494 11318 5658 11318 5748 11319 5661 11319 5662 11319 5662 11320 5661 11320 5663 11320 5662 11321 5663 11321 5660 11321 489 11322 488 11322 5750 11322 5750 11323 488 11323 5664 11323 5750 11324 5664 11324 5748 11324 5748 11325 5664 11325 491 11325 5748 11326 491 11326 5661 11326 489 11327 5750 11327 5665 11327 5665 11328 5750 11328 5666 11328 5665 11329 5666 11329 490 11329 490 11330 5666 11330 5667 11330 5667 11331 5666 11331 5668 11331 5667 11332 5668 11332 483 11332 483 11333 5668 11333 484 11333 484 11334 5668 11334 5669 11334 484 11335 5669 11335 5653 11335 2426 11336 2409 11336 5670 11336 5670 11337 5694 11337 2426 11337 2426 11338 5694 11338 5671 11338 2426 11339 5671 11339 5704 11339 5672 11340 5673 11340 5704 11340 5704 11341 5701 11341 5703 11341 5704 11342 5699 11342 5674 11342 5720 11343 5675 11343 5676 11343 5676 11344 5675 11344 5677 11344 5676 11345 5677 11345 5718 11345 5675 11346 5722 11346 5723 11346 5675 11347 5725 11347 5726 11347 5728 11348 5730 11348 5675 11348 5678 11349 5729 11349 5679 11349 5678 11350 5679 11350 5732 11350 5679 11351 5727 11351 5680 11351 5681 11352 5682 11352 5646 11352 5646 11353 5682 11353 5736 11353 5646 11354 5736 11354 5645 11354 5645 11355 5736 11355 5657 11355 5645 11356 5657 11356 5683 11356 5683 11357 5657 11357 466 11357 5683 11358 466 11358 468 11358 5684 11359 5651 11359 5693 11359 5693 11360 5651 11360 5691 11360 5691 11361 5651 11361 5692 11361 5702 11362 5698 11362 5697 11362 5702 11363 5696 11363 5695 11363 5700 11364 5685 11364 5702 11364 5705 11365 5702 11365 5706 11365 5706 11366 5702 11366 5688 11366 5706 11367 5688 11367 5708 11367 5708 11368 5688 11368 5710 11368 5713 11369 5686 11369 5755 11369 5755 11370 5686 11370 5709 11370 5711 11371 5710 11371 5687 11371 5687 11372 5710 11372 5688 11372 5687 11373 5688 11373 5752 11373 5752 11374 5688 11374 5702 11374 5752 11375 5702 11375 5689 11375 5689 11376 5702 11376 5691 11376 5689 11377 5691 11377 5690 11377 5690 11378 5691 11378 5692 11378 5690 11379 5692 11379 5737 11379 2409 11380 5693 11380 5670 11380 5670 11381 5693 11381 5691 11381 5670 11382 5691 11382 5694 11382 5694 11383 5691 11383 5702 11383 5694 11384 5702 11384 5671 11384 5671 11385 5702 11385 5695 11385 5671 11386 5695 11386 5704 11386 5704 11387 5695 11387 5696 11387 5704 11388 5696 11388 5672 11388 5672 11389 5696 11389 5702 11389 5672 11390 5702 11390 5673 11390 5673 11391 5702 11391 5697 11391 5673 11392 5697 11392 5704 11392 5704 11393 5697 11393 5698 11393 5704 11394 5698 11394 5699 11394 5699 11395 5698 11395 5702 11395 5699 11396 5702 11396 5674 11396 5674 11397 5702 11397 5685 11397 5674 11398 5685 11398 5704 11398 5704 11399 5685 11399 5700 11399 5704 11400 5700 11400 5701 11400 5701 11401 5700 11401 5702 11401 5701 11402 5702 11402 5703 11402 5703 11403 5702 11403 5705 11403 5703 11404 5705 11404 5704 11404 5704 11405 5705 11405 5706 11405 5704 11406 5706 11406 5707 11406 5707 11407 5706 11407 5708 11407 5707 11408 5708 11408 5656 11408 5656 11409 5708 11409 5710 11409 5656 11410 5710 11410 5709 11410 5709 11411 5710 11411 5711 11411 5709 11412 5711 11412 5755 11412 5649 11413 5732 11413 5712 11413 5712 11414 5732 11414 5679 11414 5712 11415 5679 11415 5757 11415 5757 11416 5679 11416 5719 11416 5757 11417 5719 11417 5713 11417 5713 11418 5719 11418 5686 11418 5686 11419 5719 11419 5714 11419 5686 11420 5714 11420 5709 11420 5709 11421 5714 11421 5715 11421 5709 11422 5715 11422 2407 11422 5716 11423 5724 11423 5679 11423 5679 11424 5721 11424 5717 11424 5677 11425 5714 11425 5718 11425 5718 11426 5714 11426 5719 11426 5718 11427 5719 11427 5676 11427 5676 11428 5719 11428 5679 11428 5676 11429 5679 11429 5720 11429 5720 11430 5679 11430 5717 11430 5720 11431 5717 11431 5675 11431 5675 11432 5717 11432 5721 11432 5675 11433 5721 11433 5722 11433 5722 11434 5721 11434 5679 11434 5722 11435 5679 11435 5723 11435 5723 11436 5679 11436 5724 11436 5723 11437 5724 11437 5675 11437 5675 11438 5724 11438 5716 11438 5675 11439 5716 11439 5725 11439 5725 11440 5716 11440 5679 11440 5725 11441 5679 11441 5726 11441 5726 11442 5679 11442 5680 11442 5726 11443 5680 11443 5675 11443 5675 11444 5680 11444 5727 11444 5675 11445 5727 11445 5728 11445 5728 11446 5727 11446 5679 11446 5728 11447 5679 11447 5730 11447 5730 11448 5679 11448 5729 11448 5730 11449 5729 11449 5675 11449 5675 11450 5729 11450 5678 11450 5675 11451 5678 11451 5731 11451 5731 11452 5678 11452 5732 11452 5731 11453 5732 11453 5733 11453 5733 11454 5732 11454 5649 11454 5745 11455 5754 11455 5738 11455 5658 11456 5735 11456 5734 11456 5734 11457 5735 11457 5657 11457 5734 11458 5657 11458 5659 11458 5659 11459 5657 11459 5736 11459 5659 11460 5736 11460 5756 11460 5756 11461 5736 11461 5682 11461 5737 11462 5655 11462 5743 11462 5745 11463 5738 11463 5747 11463 5747 11464 5738 11464 5753 11464 5747 11465 5753 11465 5740 11465 5740 11466 5753 11466 5739 11466 5740 11467 5739 11467 5749 11467 5749 11468 5739 11468 5741 11468 5749 11469 5741 11469 5742 11469 5742 11470 5741 11470 5743 11470 5742 11471 5743 11471 5744 11471 5744 11472 5743 11472 5655 11472 5744 11473 5655 11473 5751 11473 5756 11474 5754 11474 5659 11474 5659 11475 5754 11475 5745 11475 5659 11476 5745 11476 5746 11476 5746 11477 5745 11477 5747 11477 5746 11478 5747 11478 5662 11478 5662 11479 5747 11479 5740 11479 5662 11480 5740 11480 5748 11480 5748 11481 5740 11481 5749 11481 5748 11482 5749 11482 5750 11482 5750 11483 5749 11483 5742 11483 5750 11484 5742 11484 5666 11484 5666 11485 5742 11485 5744 11485 5666 11486 5744 11486 5668 11486 5668 11487 5744 11487 5751 11487 5668 11488 5751 11488 5669 11488 5737 11489 5743 11489 5690 11489 5690 11490 5743 11490 5741 11490 5690 11491 5741 11491 5689 11491 5689 11492 5741 11492 5739 11492 5689 11493 5739 11493 5752 11493 5752 11494 5739 11494 5753 11494 5752 11495 5753 11495 5687 11495 5687 11496 5753 11496 5738 11496 5687 11497 5738 11497 5711 11497 5711 11498 5738 11498 5754 11498 5711 11499 5754 11499 5755 11499 5755 11500 5754 11500 5756 11500 5755 11501 5756 11501 5713 11501 5713 11502 5756 11502 5682 11502 5713 11503 5682 11503 5757 11503 5757 11504 5682 11504 5681 11504 5757 11505 5681 11505 5712 11505 5807 11506 5805 11506 5758 11506 5758 11507 5888 11507 5807 11507 5807 11508 5888 11508 5759 11508 5807 11509 5759 11509 5794 11509 5794 11510 5759 11510 5760 11510 5794 11511 5760 11511 5791 11511 5791 11512 5760 11512 5891 11512 5791 11513 5891 11513 5761 11513 5761 11514 5891 11514 5762 11514 5761 11515 5762 11515 5782 11515 5782 11516 5762 11516 5763 11516 5782 11517 5763 11517 5783 11517 5783 11518 5763 11518 5822 11518 5799 11519 5913 11519 5764 11519 5773 11520 5765 11520 5774 11520 5775 11521 2652 11521 5777 11521 2651 11522 5813 11522 5766 11522 5813 11523 5767 11523 5768 11523 5768 11524 5767 11524 5811 11524 2649 11525 5769 11525 5806 11525 5806 11526 5770 11526 2649 11526 2649 11527 5770 11527 5808 11527 2649 11528 5808 11528 5809 11528 5811 11529 2648 11529 5810 11529 5810 11530 2648 11530 5771 11530 5810 11531 5771 11531 5809 11531 5800 11532 5773 11532 5772 11532 5772 11533 5773 11533 5817 11533 5817 11534 5773 11534 5774 11534 5817 11535 5774 11535 5815 11535 5815 11536 5774 11536 5775 11536 5815 11537 5775 11537 5776 11537 5776 11538 5775 11538 5777 11538 5776 11539 5777 11539 5766 11539 5766 11540 5777 11540 5778 11540 5766 11541 5778 11541 2651 11541 5816 11542 457 11542 5779 11542 5779 11543 457 11543 458 11543 5779 11544 458 11544 5780 11544 5780 11545 458 11545 459 11545 5780 11546 459 11546 5781 11546 459 11547 460 11547 5781 11547 5781 11548 460 11548 422 11548 5781 11549 422 11549 5819 11549 5819 11550 422 11550 462 11550 5819 11551 462 11551 5820 11551 5782 11552 5783 11552 5790 11552 443 11553 5786 11553 5784 11553 5784 11554 5786 11554 5785 11554 5784 11555 5785 11555 5792 11555 5792 11556 5785 11556 5793 11556 5786 11557 441 11557 5785 11557 5785 11558 441 11558 5787 11558 5785 11559 5787 11559 5788 11559 5788 11560 5787 11560 448 11560 5788 11561 448 11561 5789 11561 5790 11562 443 11562 5782 11562 5782 11563 443 11563 5784 11563 5782 11564 5784 11564 5761 11564 5761 11565 5784 11565 5792 11565 5761 11566 5792 11566 5791 11566 5791 11567 5792 11567 5793 11567 5791 11568 5793 11568 5794 11568 448 11569 449 11569 5789 11569 5789 11570 449 11570 451 11570 5789 11571 451 11571 5812 11571 5812 11572 451 11572 452 11572 5812 11573 452 11573 5795 11573 5795 11574 452 11574 454 11574 5795 11575 454 11575 5796 11575 5796 11576 454 11576 5797 11576 5796 11577 5797 11577 5814 11577 5814 11578 5797 11578 5798 11578 5814 11579 5798 11579 5816 11579 5816 11580 5798 11580 456 11580 5816 11581 456 11581 457 11581 5818 11582 5802 11582 5772 11582 5772 11583 5802 11583 5799 11583 5772 11584 5799 11584 5800 11584 5800 11585 5799 11585 5764 11585 5800 11586 5764 11586 2654 11586 2654 11587 5764 11587 5910 11587 5913 11588 5799 11588 5801 11588 5801 11589 5799 11589 5802 11589 5801 11590 5802 11590 5803 11590 5803 11591 5802 11591 5818 11591 5803 11592 5818 11592 5804 11592 5805 11593 5807 11593 5806 11593 5806 11594 5807 11594 5794 11594 5806 11595 5794 11595 5770 11595 5770 11596 5794 11596 5793 11596 5770 11597 5793 11597 5808 11597 5808 11598 5793 11598 5785 11598 5808 11599 5785 11599 5809 11599 5809 11600 5785 11600 5788 11600 5809 11601 5788 11601 5810 11601 5810 11602 5788 11602 5789 11602 5810 11603 5789 11603 5811 11603 5811 11604 5789 11604 5812 11604 5811 11605 5812 11605 5768 11605 5768 11606 5812 11606 5795 11606 5768 11607 5795 11607 5813 11607 5813 11608 5795 11608 5796 11608 5813 11609 5796 11609 5766 11609 5766 11610 5796 11610 5814 11610 5766 11611 5814 11611 5776 11611 5776 11612 5814 11612 5816 11612 5776 11613 5816 11613 5815 11613 5815 11614 5816 11614 5779 11614 5815 11615 5779 11615 5817 11615 5817 11616 5779 11616 5780 11616 5817 11617 5780 11617 5772 11617 5772 11618 5780 11618 5781 11618 5772 11619 5781 11619 5818 11619 5818 11620 5781 11620 5819 11620 5818 11621 5819 11621 5804 11621 5804 11622 5819 11622 5820 11622 5804 11623 5820 11623 5911 11623 5863 11624 5847 11624 5848 11624 5867 11625 5851 11625 5849 11625 2847 11626 5853 11626 5840 11626 5897 11627 5899 11627 5900 11627 5861 11628 5821 11628 5860 11628 437 11629 5822 11629 5763 11629 5859 11630 435 11630 440 11630 5877 11631 433 11631 5908 11631 5908 11632 433 11632 5823 11632 5908 11633 5823 11633 5824 11633 5825 11634 5887 11634 5877 11634 430 11635 431 11635 5826 11635 5826 11636 431 11636 432 11636 5826 11637 432 11637 5886 11637 5871 11638 5827 11638 5828 11638 5828 11639 5827 11639 429 11639 5828 11640 429 11640 5829 11640 5829 11641 429 11641 5875 11641 5872 11642 5830 11642 5870 11642 5912 11643 5830 11643 5831 11643 5831 11644 5830 11644 5872 11644 5831 11645 5872 11645 5874 11645 5832 11646 5900 11646 5833 11646 5833 11647 5900 11647 5834 11647 5833 11648 5834 11648 5835 11648 5835 11649 5834 11649 2853 11649 5835 11650 2853 11650 5909 11650 5909 11651 2853 11651 2854 11651 5909 11652 2854 11652 5836 11652 5841 11653 5843 11653 2879 11653 5849 11654 2845 11654 5868 11654 5868 11655 2845 11655 5837 11655 5903 11656 5838 11656 5896 11656 5903 11657 5901 11657 5898 11657 2879 11658 5839 11658 5841 11658 5841 11659 5839 11659 2850 11659 5841 11660 2850 11660 5840 11660 5840 11661 2850 11661 2848 11661 5840 11662 2848 11662 2847 11662 5840 11663 5842 11663 5841 11663 5841 11664 5842 11664 5844 11664 5841 11665 5844 11665 5843 11665 5843 11666 5844 11666 5856 11666 5843 11667 5856 11667 5869 11667 5851 11668 5867 11668 5852 11668 5856 11669 5845 11669 5846 11669 5847 11670 2844 11670 5848 11670 5848 11671 2844 11671 5849 11671 5848 11672 5849 11672 5864 11672 5864 11673 5849 11673 5851 11673 5864 11674 5851 11674 5850 11674 5850 11675 5851 11675 5852 11675 5850 11676 5852 11676 5865 11676 5853 11677 5900 11677 5840 11677 5840 11678 5900 11678 5902 11678 5840 11679 5902 11679 5842 11679 5842 11680 5902 11680 5854 11680 5842 11681 5854 11681 5844 11681 5844 11682 5854 11682 5855 11682 5844 11683 5855 11683 5856 11683 5856 11684 5855 11684 5857 11684 5856 11685 5857 11685 5866 11685 5866 11686 5857 11686 5907 11686 5866 11687 5907 11687 5858 11687 5858 11688 5907 11688 5859 11688 5858 11689 5859 11689 5860 11689 5860 11690 5859 11690 440 11690 5860 11691 440 11691 5861 11691 5862 11692 5863 11692 5889 11692 5889 11693 5863 11693 5848 11693 5889 11694 5848 11694 5890 11694 5890 11695 5848 11695 5864 11695 5890 11696 5864 11696 5892 11696 5892 11697 5864 11697 5850 11697 5892 11698 5850 11698 5893 11698 5893 11699 5850 11699 5865 11699 5893 11700 5865 11700 5894 11700 5860 11701 5894 11701 5858 11701 5858 11702 5894 11702 5865 11702 5858 11703 5865 11703 5866 11703 5866 11704 5865 11704 5852 11704 5866 11705 5852 11705 5856 11705 5856 11706 5852 11706 5867 11706 5856 11707 5867 11707 5845 11707 5845 11708 5867 11708 5849 11708 5845 11709 5849 11709 5846 11709 5846 11710 5849 11710 5868 11710 5846 11711 5868 11711 5856 11711 5856 11712 5868 11712 5837 11712 5856 11713 5837 11713 5869 11713 5869 11714 5837 11714 2845 11714 5869 11715 2845 11715 5843 11715 461 11716 5871 11716 5870 11716 5870 11717 5871 11717 5828 11717 5870 11718 5828 11718 5872 11718 5872 11719 5828 11719 5829 11719 5872 11720 5829 11720 5874 11720 5874 11721 5829 11721 5875 11721 5876 11722 430 11722 5873 11722 5873 11723 430 11723 5826 11723 5873 11724 5826 11724 5884 11724 5880 11725 5912 11725 5881 11725 5881 11726 5912 11726 5831 11726 5881 11727 5831 11727 5882 11727 5882 11728 5831 11728 5874 11728 5882 11729 5874 11729 5884 11729 5884 11730 5874 11730 5875 11730 5884 11731 5875 11731 5873 11731 5873 11732 5875 11732 428 11732 5873 11733 428 11733 5876 11733 5877 11734 5908 11734 5825 11734 5825 11735 5908 11735 5906 11735 5825 11736 5906 11736 5885 11736 5885 11737 5906 11737 5905 11737 5885 11738 5905 11738 5883 11738 5883 11739 5905 11739 5904 11739 5883 11740 5904 11740 5878 11740 5878 11741 5904 11741 5903 11741 5878 11742 5903 11742 5895 11742 5879 11743 5880 11743 5895 11743 5895 11744 5880 11744 5881 11744 5895 11745 5881 11745 5878 11745 5878 11746 5881 11746 5882 11746 5878 11747 5882 11747 5883 11747 5883 11748 5882 11748 5884 11748 5883 11749 5884 11749 5885 11749 5885 11750 5884 11750 5826 11750 5885 11751 5826 11751 5825 11751 5825 11752 5826 11752 5886 11752 5825 11753 5886 11753 5887 11753 5758 11754 5862 11754 5888 11754 5888 11755 5862 11755 5889 11755 5888 11756 5889 11756 5759 11756 5759 11757 5889 11757 5890 11757 5759 11758 5890 11758 5760 11758 5760 11759 5890 11759 5892 11759 5760 11760 5892 11760 5891 11760 5891 11761 5892 11761 5893 11761 5891 11762 5893 11762 5762 11762 5762 11763 5893 11763 5894 11763 5762 11764 5894 11764 5763 11764 5763 11765 5894 11765 5860 11765 5763 11766 5860 11766 437 11766 437 11767 5860 11767 5821 11767 5909 11768 5879 11768 5835 11768 5835 11769 5879 11769 5895 11769 5835 11770 5895 11770 5833 11770 5833 11771 5895 11771 5903 11771 5833 11772 5903 11772 5832 11772 5832 11773 5903 11773 5896 11773 5832 11774 5896 11774 5900 11774 5900 11775 5896 11775 5838 11775 5900 11776 5838 11776 5897 11776 5897 11777 5838 11777 5903 11777 5897 11778 5903 11778 5899 11778 5899 11779 5903 11779 5898 11779 5899 11780 5898 11780 5900 11780 5900 11781 5898 11781 5901 11781 5900 11782 5901 11782 5902 11782 5902 11783 5901 11783 5903 11783 5902 11784 5903 11784 5854 11784 5854 11785 5903 11785 5904 11785 5854 11786 5904 11786 5855 11786 5855 11787 5904 11787 5905 11787 5855 11788 5905 11788 5857 11788 5857 11789 5905 11789 5906 11789 5857 11790 5906 11790 5907 11790 5907 11791 5906 11791 5908 11791 5907 11792 5908 11792 5859 11792 5859 11793 5908 11793 5824 11793 5859 11794 5824 11794 435 11794 5764 11795 5909 11795 5910 11795 5910 11796 5909 11796 5836 11796 5911 11797 461 11797 5804 11797 5804 11798 461 11798 5870 11798 5804 11799 5870 11799 5803 11799 5803 11800 5870 11800 5830 11800 5803 11801 5830 11801 5801 11801 5801 11802 5830 11802 5912 11802 5801 11803 5912 11803 5913 11803 5913 11804 5912 11804 5880 11804 5913 11805 5880 11805 5764 11805 5764 11806 5880 11806 5879 11806 5764 11807 5879 11807 5909 11807 5931 11808 9280 11808 5914 11808 5914 11809 9280 11809 5915 11809 5914 11810 5915 11810 5932 11810 5932 11811 5915 11811 5916 11811 5932 11812 5916 11812 5927 11812 5927 11813 5916 11813 5917 11813 5927 11814 5917 11814 5918 11814 5918 11815 5917 11815 9232 11815 5919 11816 8764 11816 5922 11816 8777 11817 8764 11817 1600 11817 1600 11818 8764 11818 5919 11818 1600 11819 5919 11819 1641 11819 1641 11820 5919 11820 5925 11820 1641 11821 5925 11821 5920 11821 5920 11822 5925 11822 5921 11822 5924 11823 8658 11823 8657 11823 5922 11824 5926 11824 5919 11824 5919 11825 5926 11825 5923 11825 5919 11826 5923 11826 5925 11826 5925 11827 5923 11827 5924 11827 5925 11828 5924 11828 5921 11828 5921 11829 5924 11829 8657 11829 5921 11830 8657 11830 5920 11830 5920 11831 8657 11831 8650 11831 5926 11832 5922 11832 5930 11832 5927 11833 5918 11833 8672 11833 8658 11834 5924 11834 5928 11834 5928 11835 5924 11835 5923 11835 5928 11836 5923 11836 5933 11836 5933 11837 5923 11837 5926 11837 5933 11838 5926 11838 5929 11838 5929 11839 5926 11839 5930 11839 5929 11840 5930 11840 5931 11840 5931 11841 5914 11841 5929 11841 5929 11842 5914 11842 5932 11842 5929 11843 5932 11843 5933 11843 5933 11844 5932 11844 5927 11844 5933 11845 5927 11845 5928 11845 5928 11846 5927 11846 8672 11846 5928 11847 8672 11847 8658 11847 5939 11848 5405 11848 3805 11848 3805 11849 5405 11849 5934 11849 3805 11850 5934 11850 3806 11850 3806 11851 5934 11851 5935 11851 3806 11852 5935 11852 5936 11852 5936 11853 5935 11853 5404 11853 5936 11854 5404 11854 5937 11854 5937 11855 5404 11855 5938 11855 5937 11856 5938 11856 1678 11856 5405 11857 5939 11857 3804 11857 5405 11858 3804 11858 5441 11858 5441 11859 3804 11859 5940 11859 5441 11860 5940 11860 5942 11860 5942 11861 5940 11861 5941 11861 5942 11862 5941 11862 5443 11862 5941 11863 5943 11863 5443 11863 5443 11864 5943 11864 5944 11864 5443 11865 5944 11865 5444 11865 5444 11866 5944 11866 3809 11866 5444 11867 3809 11867 5446 11867 5945 11868 5384 11868 3809 11868 3809 11869 5384 11869 5447 11869 3809 11870 5447 11870 5446 11870 5392 11871 5946 11871 5945 11871 5945 11872 5946 11872 5384 11872 5946 11873 5392 11873 5947 11873 5946 11874 5947 11874 5387 11874 5387 11875 5947 11875 5948 11875 5387 11876 5948 11876 5388 11876 5388 11877 5948 11877 5394 11877 5388 11878 5394 11878 5390 11878 5390 11879 5394 11879 5435 11879 5435 11880 5394 11880 5949 11880 5435 11881 5949 11881 5437 11881 5437 11882 5949 11882 5393 11882 5437 11883 5393 11883 5952 11883 5954 11884 5439 11884 5950 11884 5950 11885 5439 11885 5951 11885 5950 11886 5951 11886 5952 11886 5952 11887 5951 11887 5953 11887 5952 11888 5953 11888 5437 11888 5958 11889 5403 11889 5395 11889 5395 11890 5403 11890 5954 11890 5395 11891 5954 11891 5950 11891 5955 11892 2205 11892 5396 11892 5956 11893 5957 11893 2202 11893 2202 11894 5957 11894 2199 11894 5403 11895 5958 11895 5420 11895 5403 11896 5420 11896 5396 11896 5956 11897 5959 11897 5957 11897 5957 11898 5959 11898 5955 11898 5957 11899 5955 11899 5960 11899 5960 11900 5955 11900 5396 11900 5960 11901 5396 11901 5421 11901 5421 11902 5396 11902 5420 11902 1682 11903 5961 11903 5962 11903 5962 11904 5961 11904 1681 11904 5962 11905 1681 11905 5964 11905 1681 11906 5963 11906 5964 11906 5964 11907 5963 11907 5965 11907 5964 11908 5965 11908 5966 11908 5965 11909 5967 11909 5966 11909 5966 11910 5967 11910 5969 11910 5966 11911 5969 11911 5968 11911 5972 11912 5968 11912 5969 11912 5969 11913 5970 11913 5972 11913 5972 11914 5970 11914 5971 11914 5972 11915 5971 11915 966 11915 966 11916 5971 11916 5442 11916 966 11917 5442 11917 5973 11917 5973 11918 5442 11918 967 11918 967 11919 5442 11919 5445 11919 967 11920 5445 11920 5974 11920 5974 11921 5445 11921 5975 11921 5974 11922 5975 11922 3802 11922 5977 11923 5978 11923 5448 11923 5448 11924 5978 11924 3802 11924 5448 11925 3802 11925 5975 11925 5976 11926 3799 11926 5977 11926 5977 11927 3799 11927 5978 11927 3799 11928 5976 11928 5979 11928 5979 11929 5976 11929 5385 11929 5979 11930 5385 11930 3800 11930 3800 11931 5385 11931 5386 11931 3800 11932 5386 11932 3793 11932 3793 11933 5386 11933 5389 11933 3794 11934 3793 11934 5436 11934 5436 11935 3793 11935 5389 11935 5438 11936 5984 11936 5980 11936 5438 11937 5980 11937 5981 11937 5981 11938 5980 11938 3794 11938 5981 11939 3794 11939 5436 11939 5440 11940 5982 11940 3796 11940 5440 11941 3796 11941 5984 11941 5984 11942 3796 11942 5983 11942 5984 11943 5983 11943 5980 11943 5401 11944 1258 11944 5402 11944 5402 11945 1258 11945 3797 11945 5402 11946 3797 11946 5440 11946 5440 11947 3797 11947 5982 11947 5985 11948 1671 11948 5988 11948 5988 11949 1671 11949 5986 11949 5988 11950 5986 11950 5987 11950 5987 11951 5986 11951 1672 11951 5985 11952 5988 11952 5412 11952 5412 11953 5988 11953 5989 11953 5412 11954 5989 11954 5990 11954 5990 11955 5989 11955 5991 11955 5990 11956 5991 11956 5409 11956 5991 11957 970 11957 5409 11957 5409 11958 970 11958 5992 11958 5409 11959 5992 11959 5995 11959 5449 11960 5994 11960 5993 11960 5449 11961 5451 11961 5994 11961 5994 11962 5451 11962 5995 11962 5994 11963 5995 11963 5992 11963 5993 11964 5994 11964 5450 11964 5450 11965 5994 11965 5996 11965 5450 11966 5996 11966 5998 11966 5996 11967 5997 11967 5998 11967 5998 11968 5997 11968 5452 11968 3783 11969 6000 11969 5997 11969 5997 11970 6000 11970 5452 11970 3792 11971 6001 11971 3785 11971 3785 11972 6001 11972 5999 11972 3785 11973 5999 11973 3788 11973 3788 11974 5999 11974 5375 11974 3788 11975 5375 11975 3783 11975 3783 11976 5375 11976 6000 11976 3792 11977 6002 11977 6001 11977 6001 11978 6002 11978 5429 11978 5429 11979 6002 11979 3791 11979 6003 11980 5434 11980 3789 11980 3789 11981 5434 11981 5433 11981 3789 11982 5433 11982 3791 11982 3791 11983 5433 11983 5431 11983 3791 11984 5431 11984 5429 11984 6003 11985 3789 11985 5415 11985 5415 11986 3789 11986 6004 11986 5415 11987 6004 11987 1265 11987 1265 11988 6004 11988 1255 11988 6008 11989 6005 11989 5426 11989 6009 11990 5418 11990 6006 11990 6006 11991 5418 11991 5423 11991 5418 11992 2191 11992 5423 11992 5423 11993 2191 11993 2190 11993 5423 11994 2190 11994 5424 11994 5424 11995 2190 11995 2193 11995 5424 11996 2193 11996 5426 11996 5426 11997 2193 11997 6007 11997 5426 11998 6007 11998 6008 11998 6009 11999 6006 11999 6010 11999 6010 12000 6006 12000 5378 12000 6010 12001 5378 12001 5432 12001 5432 12002 5378 12002 5377 12002 5432 12003 5377 12003 5428 12003 5428 12004 5377 12004 6011 12004 5428 12005 6011 12005 6012 12005 6012 12006 6011 12006 5430 12006 5430 12007 6011 12007 6013 12007 6013 12008 6011 12008 6014 12008 6013 12009 6014 12009 6015 12009 6015 12010 6014 12010 5380 12010 6015 12011 5380 12011 6016 12011 6015 12012 6016 12012 6017 12012 6017 12013 6016 12013 5383 12013 6017 12014 5383 12014 5376 12014 5376 12015 5383 12015 6018 12015 5376 12016 6018 12016 6019 12016 3774 12017 5374 12017 6018 12017 6018 12018 5374 12018 6019 12018 5374 12019 3774 12019 3775 12019 3777 12020 5453 12020 3772 12020 3772 12021 5453 12021 5374 12021 3772 12022 5374 12022 3776 12022 3776 12023 5374 12023 3775 12023 6020 12024 6022 12024 6021 12024 6020 12025 5454 12025 6022 12025 6022 12026 5454 12026 5453 12026 6022 12027 5453 12027 3777 12027 6026 12028 5410 12028 6022 12028 6022 12029 5410 12029 6023 12029 6022 12030 6023 12030 6021 12030 3778 12031 5408 12031 3779 12031 3779 12032 5408 12032 6025 12032 3779 12033 6025 12033 6024 12033 6024 12034 6025 12034 5410 12034 6024 12035 5410 12035 6026 12035 5411 12036 6027 12036 6031 12036 6031 12037 6027 12037 6028 12037 6031 12038 6028 12038 3778 12038 3778 12039 6028 12039 5413 12039 3778 12040 5413 12040 5408 12040 3781 12041 6029 12041 6030 12041 6030 12042 1670 12042 3781 12042 3781 12043 1670 12043 5411 12043 3781 12044 5411 12044 3782 12044 3782 12045 5411 12045 6031 12045 6032 12046 1025 12046 6033 12046 6032 12047 6033 12047 1027 12047 6033 12048 3692 12048 1027 12048 1027 12049 3692 12049 6034 12049 1027 12050 6034 12050 4751 12050 4751 12051 6034 12051 6035 12051 4751 12052 6035 12052 6037 12052 6037 12053 6035 12053 6036 12053 6037 12054 6036 12054 6038 12054 6038 12055 6036 12055 3695 12055 6038 12056 3695 12056 4752 12056 4752 12057 3695 12057 6039 12057 4752 12058 6039 12058 6040 12058 6040 12059 6039 12059 3693 12059 6040 12060 3693 12060 4753 12060 3693 12061 6041 12061 4753 12061 4753 12062 6041 12062 6042 12062 4753 12063 6042 12063 4754 12063 4754 12064 6042 12064 6043 12064 6043 12065 6042 12065 3697 12065 6043 12066 3697 12066 6044 12066 6044 12067 3697 12067 6045 12067 6044 12068 6045 12068 4792 12068 4792 12069 6045 12069 6046 12069 4792 12070 6046 12070 4793 12070 4793 12071 6046 12071 6047 12071 4793 12072 6047 12072 4794 12072 3696 12073 4795 12073 6047 12073 6047 12074 4795 12074 6048 12074 6047 12075 6048 12075 4794 12075 6049 12076 4801 12076 6050 12076 6050 12077 4801 12077 4799 12077 6050 12078 4799 12078 1489 12078 1489 12079 4799 12079 6051 12079 1489 12080 6051 12080 1484 12080 1484 12081 6051 12081 6052 12081 1484 12082 6052 12082 1014 12082 1014 12083 6052 12083 4795 12083 1014 12084 4795 12084 3696 12084 6053 12085 4783 12085 4782 12085 1488 12086 6054 12086 6055 12086 6055 12087 6054 12087 1490 12087 6055 12088 1490 12088 4782 12088 4782 12089 1490 12089 6056 12089 4782 12090 6056 12090 6053 12090 3699 12091 4787 12091 6053 12091 6053 12092 4787 12092 6057 12092 6053 12093 6057 12093 4783 12093 4787 12094 3699 12094 6058 12094 4787 12095 6058 12095 4789 12095 4789 12096 6058 12096 3700 12096 4789 12097 3700 12097 6059 12097 6059 12098 3700 12098 3698 12098 6059 12099 3698 12099 4790 12099 4790 12100 3698 12100 6060 12100 4790 12101 6060 12101 6061 12101 6060 12102 3702 12102 6061 12102 6061 12103 3702 12103 6069 12103 3707 12104 1020 12104 1021 12104 1021 12105 6062 12105 3707 12105 3707 12106 6062 12106 4755 12106 3707 12107 4755 12107 3708 12107 3708 12108 4755 12108 6063 12108 6063 12109 4755 12109 4763 12109 6063 12110 4763 12110 3703 12110 4763 12111 6064 12111 3703 12111 3703 12112 6064 12112 6065 12112 3703 12113 6065 12113 3705 12113 3705 12114 6065 12114 3706 12114 6065 12115 6066 12115 3706 12115 3706 12116 6066 12116 6067 12116 3706 12117 6067 12117 6068 12117 6068 12118 6067 12118 6069 12118 6068 12119 6069 12119 3702 12119 1518 12120 6070 12120 1556 12120 1556 12121 6070 12121 6071 12121 1556 12122 6071 12122 6072 12122 6072 12123 6071 12123 6074 12123 6072 12124 6074 12124 6073 12124 6073 12125 6074 12125 4785 12125 6073 12126 4785 12126 6075 12126 6075 12127 4785 12127 4784 12127 6075 12128 4784 12128 3732 12128 6076 12129 3731 12129 3730 12129 6076 12130 3730 12130 6077 12130 6077 12131 3730 12131 3729 12131 6077 12132 3729 12132 6079 12132 6079 12133 3729 12133 6078 12133 6079 12134 6078 12134 4786 12134 3732 12135 4784 12135 6078 12135 6078 12136 4784 12136 4788 12136 6078 12137 4788 12137 4786 12137 4761 12138 6080 12138 4759 12138 4759 12139 6080 12139 3731 12139 4759 12140 3731 12140 6076 12140 6080 12141 4761 12141 4760 12141 6080 12142 4760 12142 6081 12142 6081 12143 4760 12143 4758 12143 6081 12144 4758 12144 3728 12144 3728 12145 4758 12145 4757 12145 3728 12146 4757 12146 6082 12146 6082 12147 4757 12147 6083 12147 6083 12148 4757 12148 6084 12148 6083 12149 6084 12149 6085 12149 6085 12150 6084 12150 4756 12150 6085 12151 4756 12151 3726 12151 3726 12152 4756 12152 6086 12152 3726 12153 6086 12153 6087 12153 6087 12154 6086 12154 6088 12154 6087 12155 6088 12155 3723 12155 3723 12156 6088 12156 3722 12156 3722 12157 6088 12157 1015 12157 3722 12158 1015 12158 6089 12158 3810 12159 6090 12159 6094 12159 1467 12160 6092 12160 6091 12160 6091 12161 6092 12161 6093 12161 6091 12162 6093 12162 6094 12162 6094 12163 6093 12163 1463 12163 6094 12164 1463 12164 3810 12164 6095 12165 6097 12165 3810 12165 3810 12166 6097 12166 6096 12166 3810 12167 6096 12167 6090 12167 6097 12168 6095 12168 3814 12168 6097 12169 3814 12169 4769 12169 4769 12170 3814 12170 6098 12170 4769 12171 6098 12171 6099 12171 6099 12172 6098 12172 3811 12172 6099 12173 3811 12173 4770 12173 4770 12174 3811 12174 3812 12174 4770 12175 3812 12175 4767 12175 3812 12176 6100 12176 4767 12176 4767 12177 6100 12177 6108 12177 6101 12178 1676 12178 1655 12178 1655 12179 1656 12179 6101 12179 6101 12180 1656 12180 4733 12180 6101 12181 4733 12181 6102 12181 6102 12182 4733 12182 6103 12182 6102 12183 6103 12183 963 12183 963 12184 6103 12184 6105 12184 6103 12185 4732 12185 6105 12185 6105 12186 4732 12186 6104 12186 6105 12187 6104 12187 961 12187 961 12188 6104 12188 6106 12188 961 12189 6106 12189 6107 12189 6107 12190 6106 12190 4730 12190 6107 12191 4730 12191 959 12191 959 12192 4730 12192 6108 12192 959 12193 6108 12193 6100 12193 6109 12194 1663 12194 6111 12194 6109 12195 6111 12195 6110 12195 6111 12196 6112 12196 6110 12196 6110 12197 6112 12197 6114 12197 6110 12198 6114 12198 6113 12198 6113 12199 6114 12199 6115 12199 6113 12200 6115 12200 6116 12200 6116 12201 6115 12201 6117 12201 6116 12202 6117 12202 6118 12202 6118 12203 6117 12203 3742 12203 6118 12204 3742 12204 6119 12204 6119 12205 3742 12205 6121 12205 6119 12206 6121 12206 6120 12206 6120 12207 6121 12207 6122 12207 6120 12208 6122 12208 6123 12208 6122 12209 3745 12209 6123 12209 6123 12210 3745 12210 6125 12210 6123 12211 6125 12211 6124 12211 6124 12212 6125 12212 6126 12212 6126 12213 6125 12213 6128 12213 6126 12214 6128 12214 6127 12214 6127 12215 6128 12215 6129 12215 6127 12216 6129 12216 4766 12216 4766 12217 6129 12217 3748 12217 4766 12218 3748 12218 4765 12218 4765 12219 3748 12219 6130 12219 4765 12220 6130 12220 6131 12220 6131 12221 6130 12221 3747 12221 6131 12222 3747 12222 4768 12222 1461 12223 4764 12223 6132 12223 6132 12224 4764 12224 6133 12224 6132 12225 6133 12225 6134 12225 6134 12226 6133 12226 6135 12226 6134 12227 6135 12227 3750 12227 3750 12228 6135 12228 6136 12228 3750 12229 6136 12229 6137 12229 6137 12230 6136 12230 4768 12230 6137 12231 4768 12231 3747 12231 3752 12232 4771 12232 6138 12232 1468 12233 1474 12233 4773 12233 4773 12234 1474 12234 1475 12234 4773 12235 1475 12235 6138 12235 6138 12236 1475 12236 3751 12236 6138 12237 3751 12237 3752 12237 3754 12238 6139 12238 3752 12238 3752 12239 6139 12239 4779 12239 3752 12240 4779 12240 4771 12240 6139 12241 3754 12241 3755 12241 6139 12242 3755 12242 4780 12242 4780 12243 3755 12243 6140 12243 4780 12244 6140 12244 4781 12244 4781 12245 6140 12245 3753 12245 4781 12246 3753 12246 4776 12246 4776 12247 3753 12247 6142 12247 4776 12248 6142 12248 6141 12248 6142 12249 6143 12249 6141 12249 6141 12250 6143 12250 6146 12250 6144 12251 3764 12251 1665 12251 1665 12252 1668 12252 6144 12252 6144 12253 1668 12253 6145 12253 6144 12254 6145 12254 3765 12254 3765 12255 6145 12255 3766 12255 3766 12256 6145 12256 4744 12256 3766 12257 4744 12257 3759 12257 4744 12258 4743 12258 3759 12258 3759 12259 4743 12259 4742 12259 3759 12260 4742 12260 3760 12260 3760 12261 4742 12261 3761 12261 4742 12262 4740 12262 3761 12262 3761 12263 4740 12263 4739 12263 3761 12264 4739 12264 3763 12264 3763 12265 4739 12265 6146 12265 3763 12266 6146 12266 6143 12266 1538 12267 4774 12267 6147 12267 6147 12268 4774 12268 6148 12268 6147 12269 6148 12269 1502 12269 1502 12270 6148 12270 4772 12270 1502 12271 4772 12271 1485 12271 1485 12272 4772 12272 6149 12272 1485 12273 6149 12273 3771 12273 3771 12274 6149 12274 6150 12274 3771 12275 6150 12275 3767 12275 6155 12276 6151 12276 6152 12276 6155 12277 6152 12277 4778 12277 4778 12278 6152 12278 6153 12278 4778 12279 6153 12279 4775 12279 4775 12280 6153 12280 3768 12280 4775 12281 3768 12281 6154 12281 6154 12282 3768 12282 3767 12282 6154 12283 3767 12283 6150 12283 4741 12284 3769 12284 4738 12284 4738 12285 3769 12285 6151 12285 4738 12286 6151 12286 6155 12286 6156 12287 3769 12287 4741 12287 6156 12288 4741 12288 6157 12288 4741 12289 4737 12289 6157 12289 6157 12290 4737 12290 6158 12290 6157 12291 6158 12291 977 12291 977 12292 6158 12292 6159 12292 6159 12293 6158 12293 6160 12293 6159 12294 6160 12294 974 12294 974 12295 6160 12295 6161 12295 974 12296 6161 12296 6162 12296 6162 12297 6161 12297 4736 12297 6162 12298 4736 12298 975 12298 4736 12299 4734 12299 975 12299 975 12300 4734 12300 6163 12300 975 12301 6163 12301 972 12301 972 12302 6163 12302 6164 12302 972 12303 6164 12303 6165 12303 6170 12304 4797 12304 6168 12304 1503 12305 6166 12305 4800 12305 4800 12306 6166 12306 6167 12306 4800 12307 6167 12307 6168 12307 6168 12308 6167 12308 1506 12308 6168 12309 1506 12309 6170 12309 3734 12310 6169 12310 6170 12310 6170 12311 6169 12311 4798 12311 6170 12312 4798 12312 4797 12312 6169 12313 3734 12313 6171 12313 6169 12314 6171 12314 6172 12314 6172 12315 6171 12315 6173 12315 6172 12316 6173 12316 4796 12316 4796 12317 6173 12317 6174 12317 4796 12318 6174 12318 6175 12318 6175 12319 6174 12319 6176 12319 6175 12320 6176 12320 4748 12320 6176 12321 3735 12321 4748 12321 4748 12322 3735 12322 4747 12322 6178 12323 1029 12323 1031 12323 1031 12324 1032 12324 6178 12324 6178 12325 1032 12325 6177 12325 6178 12326 6177 12326 6179 12326 6179 12327 6177 12327 6180 12327 6180 12328 6177 12328 6181 12328 6180 12329 6181 12329 6182 12329 6181 12330 4749 12330 6182 12330 6182 12331 4749 12331 6183 12331 6182 12332 6183 12332 6184 12332 6184 12333 6183 12333 6185 12333 6183 12334 4746 12334 6185 12334 6185 12335 4746 12335 6186 12335 6185 12336 6186 12336 3738 12336 3738 12337 6186 12337 4747 12337 3738 12338 4747 12338 3735 12338 6189 12339 5318 12339 1480 12339 1480 12340 6187 12340 6189 12340 6189 12341 6187 12341 6188 12341 6189 12342 6188 12342 6202 12342 6202 12343 6188 12343 6190 12343 6190 12344 6188 12344 6191 12344 6190 12345 6191 12345 6203 12345 6203 12346 6191 12346 6205 12346 6205 12347 6191 12347 6192 12347 6205 12348 6192 12348 1687 12348 6204 12349 1688 12349 6207 12349 6200 12350 5318 12350 6189 12350 6194 12351 6195 12351 6201 12351 6201 12352 6195 12352 6197 12352 6193 12353 6215 12353 6194 12353 6194 12354 6215 12354 6213 12354 6194 12355 6213 12355 6195 12355 6195 12356 6213 12356 6196 12356 6195 12357 6196 12357 6197 12357 6197 12358 6196 12358 6211 12358 6197 12359 6211 12359 6198 12359 6198 12360 6199 12360 6197 12360 6197 12361 6199 12361 6200 12361 6197 12362 6200 12362 6201 12362 6201 12363 6200 12363 6189 12363 6201 12364 6189 12364 6194 12364 6194 12365 6189 12365 6202 12365 6194 12366 6202 12366 6193 12366 6193 12367 6202 12367 6190 12367 6193 12368 6190 12368 6204 12368 6204 12369 6190 12369 6203 12369 6204 12370 6203 12370 1688 12370 1688 12371 6203 12371 6205 12371 1688 12372 6205 12372 1687 12372 6207 12373 6216 12373 6204 12373 6204 12374 6216 12374 6206 12374 6204 12375 6206 12375 6193 12375 6193 12376 6206 12376 6215 12376 5302 12377 6198 12377 6211 12377 6216 12378 6207 12378 6209 12378 6209 12379 6207 12379 6208 12379 6209 12380 6208 12380 1686 12380 6210 12381 5302 12381 6220 12381 6220 12382 5302 12382 6211 12382 6220 12383 6211 12383 6219 12383 6219 12384 6211 12384 6196 12384 6219 12385 6196 12385 6212 12385 6212 12386 6196 12386 6213 12386 6212 12387 6213 12387 6214 12387 6214 12388 6213 12388 6215 12388 6214 12389 6215 12389 6209 12389 6209 12390 6215 12390 6206 12390 6209 12391 6206 12391 6216 12391 1686 12392 4843 12392 6237 12392 1686 12393 6237 12393 6209 12393 6209 12394 6237 12394 6236 12394 6209 12395 6236 12395 6214 12395 6214 12396 6236 12396 6217 12396 6214 12397 6217 12397 6235 12397 6214 12398 6235 12398 6212 12398 6212 12399 6235 12399 6218 12399 6212 12400 6218 12400 6219 12400 6219 12401 6218 12401 6221 12401 6219 12402 6221 12402 6220 12402 6220 12403 6221 12403 1836 12403 6220 12404 1836 12404 6210 12404 6248 12405 6226 12405 6247 12405 6222 12406 4844 12406 6229 12406 6244 12407 6245 12407 6223 12407 6242 12408 6224 12408 6239 12408 6239 12409 6224 12409 6225 12409 6239 12410 6225 12410 6243 12410 6247 12411 6226 12411 6245 12411 6245 12412 6226 12412 6223 12412 6223 12413 6226 12413 6228 12413 6223 12414 6228 12414 6227 12414 6227 12415 6228 12415 4845 12415 6227 12416 4845 12416 4848 12416 6222 12417 6229 12417 4843 12417 6230 12418 1836 12418 6231 12418 6231 12419 1836 12419 6221 12419 6231 12420 6221 12420 6232 12420 6232 12421 6221 12421 6218 12421 6232 12422 6218 12422 6233 12422 6233 12423 6218 12423 6235 12423 6233 12424 6235 12424 6234 12424 6234 12425 6235 12425 6217 12425 6234 12426 6217 12426 6246 12426 6246 12427 6217 12427 6236 12427 6246 12428 6236 12428 6229 12428 6229 12429 6236 12429 6237 12429 6229 12430 6237 12430 4843 12430 1839 12431 1838 12431 6224 12431 6224 12432 1838 12432 6238 12432 6224 12433 6238 12433 6225 12433 6243 12434 6244 12434 6239 12434 6239 12435 6244 12435 6223 12435 6239 12436 6223 12436 6242 12436 6242 12437 6223 12437 6227 12437 6242 12438 6227 12438 6240 12438 6240 12439 6227 12439 4848 12439 6240 12440 4848 12440 6241 12440 1839 12441 6224 12441 6261 12441 6261 12442 6224 12442 6242 12442 6261 12443 6242 12443 6250 12443 6250 12444 6242 12444 6240 12444 6250 12445 6240 12445 6251 12445 6251 12446 6240 12446 6241 12446 6251 12447 6241 12447 4823 12447 1838 12448 6230 12448 6238 12448 6238 12449 6230 12449 6231 12449 6238 12450 6231 12450 6225 12450 6225 12451 6231 12451 6232 12451 6225 12452 6232 12452 6243 12452 6243 12453 6232 12453 6233 12453 6243 12454 6233 12454 6244 12454 6244 12455 6233 12455 6234 12455 6244 12456 6234 12456 6245 12456 6245 12457 6234 12457 6246 12457 6245 12458 6246 12458 6247 12458 6247 12459 6246 12459 6229 12459 6247 12460 6229 12460 6248 12460 6248 12461 6229 12461 4844 12461 1839 12462 6261 12462 6249 12462 6261 12463 6250 12463 6258 12463 6250 12464 6251 12464 6253 12464 6251 12465 4823 12465 6252 12465 6251 12466 6252 12466 6253 12466 6253 12467 6252 12467 6255 12467 6253 12468 6255 12468 6254 12468 6254 12469 6255 12469 4826 12469 6254 12470 4826 12470 6259 12470 4826 12471 4827 12471 6259 12471 6259 12472 4827 12472 6256 12472 6259 12473 6256 12473 6257 12473 6257 12474 6256 12474 4828 12474 6257 12475 4828 12475 6272 12475 6250 12476 6253 12476 6258 12476 6258 12477 6253 12477 6254 12477 6258 12478 6254 12478 6262 12478 6262 12479 6254 12479 6259 12479 6262 12480 6259 12480 6260 12480 6260 12481 6259 12481 6257 12481 6260 12482 6257 12482 6264 12482 6264 12483 6257 12483 6272 12483 6264 12484 6272 12484 6266 12484 6261 12485 6258 12485 6249 12485 6249 12486 6258 12486 6262 12486 6249 12487 6262 12487 6267 12487 6267 12488 6262 12488 6260 12488 6267 12489 6260 12489 6263 12489 6263 12490 6260 12490 6264 12490 6263 12491 6264 12491 6265 12491 6265 12492 6264 12492 6266 12492 6265 12493 6266 12493 6273 12493 1839 12494 6249 12494 1835 12494 1835 12495 6249 12495 6267 12495 1835 12496 6267 12496 1843 12496 1843 12497 6267 12497 6263 12497 1843 12498 6263 12498 1842 12498 1842 12499 6263 12499 6265 12499 1842 12500 6265 12500 6268 12500 6268 12501 6265 12501 6273 12501 6268 12502 6273 12502 6269 12502 6270 12503 6269 12503 6273 12503 4828 12504 6271 12504 6272 12504 6272 12505 6271 12505 6293 12505 6272 12506 6293 12506 6266 12506 6266 12507 6293 12507 6274 12507 6266 12508 6274 12508 6273 12508 6273 12509 6274 12509 6275 12509 6273 12510 6275 12510 6270 12510 6270 12511 6275 12511 6276 12511 6277 12512 6301 12512 6303 12512 5277 12513 5260 12513 6278 12513 6280 12514 6279 12514 6292 12514 6292 12515 6279 12515 6275 12515 6292 12516 6275 12516 6274 12516 6287 12517 6278 12517 6280 12517 6280 12518 6278 12518 6285 12518 6280 12519 6285 12519 6279 12519 6284 12520 6281 12520 6291 12520 6291 12521 6281 12521 6289 12521 6293 12522 6271 12522 6283 12522 6293 12523 6283 12523 6282 12523 6282 12524 6283 12524 4858 12524 6282 12525 4858 12525 6284 12525 6284 12526 4858 12526 4859 12526 6284 12527 4859 12527 6281 12527 6305 12528 5261 12528 5277 12528 6278 12529 5260 12529 6285 12529 6285 12530 5260 12530 6286 12530 6285 12531 6286 12531 6279 12531 6279 12532 6286 12532 6276 12532 6279 12533 6276 12533 6275 12533 5277 12534 6278 12534 6305 12534 6305 12535 6278 12535 6287 12535 6305 12536 6287 12536 6303 12536 6303 12537 6287 12537 6290 12537 6303 12538 6290 12538 6277 12538 6288 12539 6301 12539 4862 12539 4862 12540 6301 12540 6277 12540 4862 12541 6277 12541 6289 12541 6289 12542 6277 12542 6290 12542 6289 12543 6290 12543 6291 12543 6291 12544 6290 12544 6287 12544 6291 12545 6287 12545 6284 12545 6284 12546 6287 12546 6280 12546 6284 12547 6280 12547 6282 12547 6282 12548 6280 12548 6292 12548 6282 12549 6292 12549 6293 12549 6293 12550 6292 12550 6274 12550 6310 12551 6294 12551 1716 12551 1716 12552 6294 12552 1718 12552 6301 12553 6288 12553 1718 12553 6304 12554 6295 12554 6296 12554 6309 12555 6307 12555 6297 12555 6297 12556 6307 12556 6298 12556 6297 12557 6298 12557 6300 12557 6300 12558 6298 12558 6299 12558 6307 12559 5265 12559 6298 12559 6298 12560 5265 12560 5264 12560 6298 12561 5264 12561 6299 12561 6299 12562 5264 12562 5262 12562 6295 12563 6304 12563 5262 12563 5262 12564 6304 12564 6299 12564 6299 12565 6304 12565 6302 12565 6299 12566 6302 12566 6300 12566 6300 12567 6302 12567 6294 12567 6300 12568 6294 12568 6297 12568 6297 12569 6294 12569 6310 12569 6297 12570 6310 12570 6309 12570 1718 12571 6294 12571 6301 12571 6301 12572 6294 12572 6302 12572 6301 12573 6302 12573 6303 12573 6303 12574 6302 12574 6304 12574 6303 12575 6304 12575 6305 12575 6305 12576 6304 12576 6296 12576 6305 12577 6296 12577 5261 12577 6312 12578 5265 12578 6313 12578 6313 12579 5265 12579 6307 12579 6313 12580 6307 12580 6306 12580 6306 12581 6307 12581 6309 12581 6306 12582 6309 12582 6308 12582 6308 12583 6309 12583 6310 12583 6308 12584 6310 12584 6316 12584 6316 12585 6310 12585 1716 12585 1707 12586 1709 12586 6322 12586 1707 12587 6322 12587 6318 12587 1985 12588 6312 12588 6311 12588 6311 12589 6312 12589 6313 12589 6311 12590 6313 12590 6314 12590 6314 12591 6313 12591 6306 12591 6314 12592 6306 12592 6315 12592 6315 12593 6306 12593 6308 12593 6315 12594 6308 12594 1714 12594 1714 12595 6308 12595 6316 12595 1984 12596 1985 12596 6317 12596 6317 12597 1985 12597 6311 12597 6317 12598 6311 12598 6320 12598 6320 12599 6311 12599 6314 12599 6320 12600 6314 12600 6322 12600 6322 12601 6314 12601 6315 12601 6322 12602 6315 12602 6318 12602 6318 12603 6315 12603 1714 12603 1983 12604 1984 12604 6323 12604 6323 12605 1984 12605 6317 12605 6323 12606 6317 12606 6319 12606 6319 12607 6317 12607 6320 12607 6319 12608 6320 12608 6321 12608 6321 12609 6320 12609 6322 12609 6321 12610 6322 12610 1700 12610 1700 12611 6322 12611 1709 12611 3058 12612 1983 12612 6324 12612 6324 12613 1983 12613 6323 12613 6324 12614 6323 12614 6325 12614 6325 12615 6323 12615 6319 12615 6325 12616 6319 12616 6326 12616 6326 12617 6319 12617 6321 12617 6326 12618 6321 12618 1702 12618 1702 12619 6321 12619 1700 12619 6330 12620 3058 12620 6331 12620 6331 12621 3058 12621 6324 12621 6331 12622 6324 12622 6327 12622 6327 12623 6324 12623 6325 12623 6327 12624 6325 12624 6328 12624 6328 12625 6325 12625 6326 12625 6328 12626 6326 12626 6334 12626 6334 12627 6326 12627 6335 12627 6335 12628 6326 12628 1702 12628 6335 12629 1702 12629 1698 12629 6342 12630 6329 12630 6330 12630 6330 12631 6331 12631 6342 12631 6342 12632 6331 12632 6327 12632 6342 12633 6327 12633 6332 12633 6327 12634 6328 12634 6332 12634 6332 12635 6328 12635 6334 12635 6332 12636 6334 12636 6333 12636 6333 12637 6334 12637 6335 12637 6333 12638 6335 12638 6340 12638 6340 12639 6335 12639 1698 12639 2357 12640 2356 12640 6341 12640 6341 12641 2356 12641 6336 12641 6341 12642 6336 12642 6337 12642 6337 12643 6336 12643 6347 12643 6337 12644 6347 12644 6343 12644 6343 12645 6347 12645 6338 12645 6343 12646 6338 12646 4537 12646 4537 12647 6338 12647 6339 12647 6340 12648 2357 12648 6333 12648 6333 12649 2357 12649 6341 12649 6333 12650 6341 12650 6332 12650 6332 12651 6341 12651 6337 12651 6332 12652 6337 12652 6342 12652 6342 12653 6337 12653 6343 12653 6342 12654 6343 12654 6329 12654 6329 12655 6343 12655 4537 12655 6344 12656 6359 12656 6345 12656 6345 12657 6359 12657 6360 12657 6345 12658 6360 12658 6348 12658 6348 12659 6360 12659 6361 12659 6348 12660 6361 12660 6349 12660 6349 12661 6361 12661 6346 12661 6349 12662 6346 12662 2107 12662 2107 12663 6346 12663 2105 12663 2356 12664 6344 12664 6336 12664 6336 12665 6344 12665 6345 12665 6336 12666 6345 12666 6347 12666 6347 12667 6345 12667 6348 12667 6347 12668 6348 12668 6338 12668 6338 12669 6348 12669 6349 12669 6338 12670 6349 12670 6339 12670 6339 12671 6349 12671 2107 12671 2354 12672 6358 12672 6357 12672 2099 12673 6353 12673 6364 12673 6364 12674 6353 12674 6354 12674 6364 12675 6354 12675 6373 12675 6373 12676 6354 12676 6350 12676 6373 12677 6350 12677 6351 12677 6351 12678 6350 12678 6356 12678 6351 12679 6356 12679 6352 12679 6352 12680 6356 12680 2353 12680 6353 12681 6363 12681 6354 12681 6354 12682 6363 12682 6355 12682 6354 12683 6355 12683 6350 12683 6350 12684 6355 12684 6362 12684 6350 12685 6362 12685 6356 12685 6356 12686 6362 12686 6357 12686 6356 12687 6357 12687 2353 12687 2353 12688 6357 12688 6358 12688 6359 12689 2354 12689 6360 12689 6360 12690 2354 12690 6357 12690 6360 12691 6357 12691 6361 12691 6361 12692 6357 12692 6362 12692 6361 12693 6362 12693 6346 12693 6346 12694 6362 12694 6355 12694 6346 12695 6355 12695 2105 12695 2105 12696 6355 12696 6363 12696 6371 12697 6364 12697 6373 12697 2099 12698 6364 12698 2085 12698 2085 12699 6364 12699 6371 12699 2085 12700 6371 12700 6365 12700 2088 12701 6366 12701 6367 12701 6367 12702 6366 12702 6368 12702 6367 12703 6368 12703 6369 12703 6369 12704 6368 12704 6372 12704 6369 12705 6372 12705 6370 12705 6370 12706 6372 12706 6374 12706 6370 12707 6374 12707 2350 12707 2350 12708 6374 12708 2352 12708 6366 12709 6365 12709 6368 12709 6368 12710 6365 12710 6371 12710 6368 12711 6371 12711 6372 12711 6372 12712 6371 12712 6373 12712 6372 12713 6373 12713 6374 12713 6374 12714 6373 12714 6351 12714 6374 12715 6351 12715 2352 12715 2352 12716 6351 12716 6352 12716 2087 12717 2088 12717 6367 12717 1640 12718 6375 12718 6377 12718 6384 12719 2087 12719 6386 12719 6386 12720 2087 12720 6367 12720 6386 12721 6367 12721 6376 12721 6376 12722 6367 12722 6369 12722 6376 12723 6369 12723 6377 12723 6377 12724 6369 12724 6370 12724 6377 12725 6370 12725 1640 12725 1640 12726 6370 12726 2350 12726 6379 12727 6385 12727 6382 12727 4580 12728 6385 12728 6378 12728 6378 12729 6385 12729 6379 12729 6378 12730 6379 12730 4579 12730 6387 12731 1639 12731 6381 12731 6381 12732 1639 12732 6380 12732 6381 12733 6380 12733 6382 12733 6382 12734 6380 12734 6389 12734 6382 12735 6389 12735 6379 12735 6379 12736 6389 12736 6383 12736 6379 12737 6383 12737 4579 12737 4580 12738 6384 12738 6385 12738 6385 12739 6384 12739 6386 12739 6385 12740 6386 12740 6382 12740 6382 12741 6386 12741 6376 12741 6382 12742 6376 12742 6381 12742 6381 12743 6376 12743 6377 12743 6381 12744 6377 12744 6387 12744 6387 12745 6377 12745 6375 12745 1639 12746 6388 12746 6380 12746 6380 12747 6388 12747 6402 12747 6380 12748 6402 12748 6389 12748 6389 12749 6402 12749 6392 12749 6389 12750 6392 12750 6383 12750 6383 12751 6392 12751 6390 12751 6383 12752 6390 12752 4579 12752 4579 12753 6390 12753 6396 12753 6391 12754 6392 12754 6402 12754 6394 12755 6407 12755 6397 12755 6397 12756 6390 12756 6392 12756 6392 12757 6391 12757 6397 12757 6397 12758 6391 12758 6393 12758 6397 12759 6393 12759 6394 12759 6411 12760 6412 12760 6409 12760 6409 12761 6412 12761 6395 12761 6396 12762 6390 12762 4024 12762 4024 12763 6390 12763 6397 12763 4024 12764 6397 12764 6395 12764 6395 12765 6397 12765 6407 12765 6395 12766 6407 12766 6409 12766 6398 12767 6408 12767 6399 12767 6399 12768 6408 12768 6406 12768 6399 12769 6406 12769 6423 12769 6423 12770 6406 12770 6405 12770 6423 12771 6405 12771 6400 12771 6400 12772 6405 12772 6404 12772 6400 12773 6404 12773 6413 12773 6413 12774 6404 12774 6403 12774 6413 12775 6403 12775 1638 12775 1638 12776 6403 12776 6401 12776 6388 12777 6401 12777 6402 12777 6402 12778 6401 12778 6403 12778 6402 12779 6403 12779 6391 12779 6391 12780 6403 12780 6404 12780 6391 12781 6404 12781 6393 12781 6393 12782 6404 12782 6405 12782 6393 12783 6405 12783 6394 12783 6394 12784 6405 12784 6406 12784 6394 12785 6406 12785 6407 12785 6407 12786 6406 12786 6408 12786 6407 12787 6408 12787 6409 12787 6409 12788 6408 12788 6398 12788 6409 12789 6398 12789 6411 12789 6424 12790 6415 12790 6399 12790 6399 12791 6415 12791 6398 12791 6398 12792 6415 12792 6417 12792 6398 12793 6417 12793 6411 12793 6411 12794 6417 12794 6410 12794 6411 12795 6410 12795 6412 12795 6425 12796 6427 12796 6416 12796 6416 12797 6427 12797 6414 12797 6416 12798 6414 12798 6418 12798 1638 12799 1630 12799 6413 12799 6413 12800 1630 12800 6421 12800 6413 12801 6421 12801 6400 12801 6400 12802 6421 12802 6426 12802 6428 12803 6430 12803 6414 12803 6414 12804 6430 12804 2082 12804 6414 12805 2082 12805 6418 12805 6418 12806 2082 12806 6419 12806 6424 12807 6425 12807 6415 12807 6415 12808 6425 12808 6416 12808 6415 12809 6416 12809 6417 12809 6417 12810 6416 12810 6418 12810 6417 12811 6418 12811 6410 12811 6410 12812 6418 12812 6419 12812 6410 12813 6419 12813 6412 12813 1630 12814 6420 12814 6421 12814 6421 12815 6420 12815 6429 12815 6421 12816 6429 12816 6426 12816 6426 12817 6429 12817 6422 12817 6426 12818 6422 12818 6433 12818 6399 12819 6423 12819 6424 12819 6424 12820 6423 12820 6400 12820 6424 12821 6400 12821 6425 12821 6425 12822 6400 12822 6426 12822 6425 12823 6426 12823 6427 12823 6427 12824 6426 12824 6433 12824 6427 12825 6433 12825 6414 12825 6414 12826 6433 12826 6432 12826 6414 12827 6432 12827 6428 12827 6420 12828 1637 12828 6429 12828 6429 12829 1637 12829 6441 12829 6435 12830 6430 12830 6431 12830 6431 12831 6430 12831 6428 12831 6431 12832 6428 12832 6434 12832 6434 12833 6428 12833 6432 12833 6434 12834 6432 12834 6443 12834 6443 12835 6432 12835 6433 12835 6443 12836 6433 12836 6441 12836 6441 12837 6433 12837 6422 12837 6441 12838 6422 12838 6429 12838 6434 12839 6445 12839 6431 12839 6431 12840 6445 12840 2072 12840 6431 12841 2072 12841 6435 12841 6452 12842 6446 12842 6436 12842 6436 12843 6446 12843 6444 12843 6436 12844 6444 12844 6437 12844 6437 12845 6444 12845 6442 12845 1636 12846 6438 12846 6439 12846 6439 12847 6438 12847 6440 12847 6439 12848 6440 12848 6442 12848 6442 12849 6440 12849 6455 12849 6442 12850 6455 12850 6437 12850 1637 12851 1636 12851 6441 12851 6441 12852 1636 12852 6439 12852 6441 12853 6439 12853 6443 12853 6443 12854 6439 12854 6442 12854 6443 12855 6442 12855 6434 12855 6434 12856 6442 12856 6444 12856 6434 12857 6444 12857 6445 12857 6445 12858 6444 12858 6446 12858 6445 12859 6446 12859 2072 12859 6448 12860 6450 12860 6453 12860 6462 12861 6447 12861 6448 12861 6448 12862 6447 12862 6449 12862 6448 12863 6449 12863 6450 12863 6450 12864 6449 12864 6451 12864 6451 12865 6452 12865 6450 12865 6450 12866 6452 12866 6436 12866 6450 12867 6436 12867 6453 12867 1635 12868 6457 12868 6454 12868 6454 12869 6457 12869 6456 12869 6454 12870 6456 12870 6453 12870 6453 12871 6456 12871 6460 12871 6453 12872 6460 12872 6448 12872 6448 12873 6460 12873 6459 12873 6448 12874 6459 12874 6462 12874 6436 12875 6437 12875 6453 12875 6453 12876 6437 12876 6455 12876 6453 12877 6455 12877 6454 12877 6454 12878 6455 12878 6440 12878 6454 12879 6440 12879 1635 12879 1635 12880 6440 12880 6438 12880 6456 12881 6457 12881 1633 12881 6458 12882 6459 12882 6460 12882 1633 12883 6465 12883 6456 12883 6456 12884 6465 12884 6471 12884 6456 12885 6471 12885 6460 12885 6460 12886 6471 12886 6461 12886 6460 12887 6461 12887 6458 12887 3985 12888 6447 12888 6462 12888 6459 12889 6458 12889 6462 12889 6462 12890 6458 12890 6468 12890 6462 12891 6468 12891 3985 12891 6471 12892 6465 12892 6464 12892 3982 12893 3983 12893 6466 12893 3984 12894 3985 12894 6468 12894 6466 12895 6463 12895 6470 12895 6478 12896 6487 12896 6464 12896 6478 12897 6464 12897 1631 12897 1631 12898 6464 12898 6465 12898 1631 12899 6465 12899 1633 12899 6470 12900 6473 12900 6466 12900 6466 12901 6473 12901 6475 12901 6466 12902 6475 12902 3982 12902 3982 12903 6475 12903 6477 12903 3983 12904 3984 12904 6467 12904 6467 12905 3984 12905 6468 12905 6467 12906 6468 12906 6469 12906 6469 12907 6468 12907 6458 12907 6469 12908 6458 12908 6461 12908 3983 12909 6467 12909 6466 12909 6466 12910 6467 12910 6469 12910 6466 12911 6469 12911 6463 12911 6463 12912 6469 12912 6472 12912 6463 12913 6472 12913 6470 12913 6461 12914 6471 12914 6469 12914 6469 12915 6471 12915 6464 12915 6469 12916 6464 12916 6472 12916 6472 12917 6464 12917 6487 12917 6472 12918 6487 12918 6470 12918 6470 12919 6487 12919 6486 12919 6470 12920 6486 12920 6473 12920 6473 12921 6486 12921 6474 12921 6473 12922 6474 12922 6475 12922 6475 12923 6474 12923 6476 12923 6475 12924 6476 12924 6477 12924 6483 12925 6477 12925 6476 12925 6487 12926 6478 12926 6479 12926 6480 12927 6489 12927 6481 12927 6481 12928 6489 12928 6499 12928 6499 12929 6482 12929 6481 12929 6481 12930 6482 12930 6498 12930 6481 12931 6498 12931 6491 12931 6492 12932 6483 12932 6493 12932 6493 12933 6483 12933 6476 12933 6493 12934 6476 12934 6484 12934 6484 12935 6476 12935 6474 12935 6484 12936 6474 12936 6485 12936 6485 12937 6474 12937 6486 12937 6485 12938 6486 12938 6487 12938 6502 12939 6495 12939 6488 12939 6488 12940 6495 12940 6496 12940 6488 12941 6496 12941 1629 12941 6502 12942 6489 12942 6495 12942 6495 12943 6489 12943 6480 12943 6495 12944 6480 12944 6494 12944 6494 12945 6480 12945 6481 12945 6494 12946 6481 12946 6490 12946 6490 12947 6481 12947 6491 12947 6490 12948 6491 12948 6492 12948 6492 12949 6493 12949 6490 12949 6490 12950 6493 12950 6484 12950 6490 12951 6484 12951 6494 12951 6494 12952 6484 12952 6485 12952 6494 12953 6485 12953 6495 12953 6495 12954 6485 12954 6487 12954 6495 12955 6487 12955 6496 12955 6496 12956 6487 12956 6479 12956 6496 12957 6479 12957 1629 12957 1629 12958 6497 12958 6488 12958 6488 12959 6497 12959 6501 12959 2069 12960 6498 12960 6503 12960 6503 12961 6498 12961 6482 12961 6503 12962 6482 12962 6509 12962 6509 12963 6482 12963 6499 12963 6509 12964 6499 12964 6500 12964 6500 12965 6499 12965 6489 12965 6500 12966 6489 12966 6501 12966 6501 12967 6489 12967 6502 12967 6501 12968 6502 12968 6488 12968 6509 12969 6510 12969 6503 12969 6503 12970 6510 12970 2058 12970 6503 12971 2058 12971 2069 12971 6518 12972 2059 12972 6504 12972 6504 12973 2059 12973 6511 12973 6504 12974 6511 12974 6521 12974 6521 12975 6511 12975 6508 12975 1627 12976 6505 12976 6507 12976 6507 12977 6505 12977 6506 12977 6507 12978 6506 12978 6508 12978 6508 12979 6506 12979 6522 12979 6508 12980 6522 12980 6521 12980 6497 12981 1627 12981 6501 12981 6501 12982 1627 12982 6507 12982 6501 12983 6507 12983 6500 12983 6500 12984 6507 12984 6508 12984 6500 12985 6508 12985 6509 12985 6509 12986 6508 12986 6511 12986 6509 12987 6511 12987 6510 12987 6510 12988 6511 12988 2059 12988 6510 12989 2059 12989 2058 12989 6512 12990 6519 12990 6524 12990 6516 12991 6513 12991 6523 12991 6514 12992 6513 12992 6515 12992 6515 12993 6513 12993 6516 12993 6515 12994 6516 12994 6517 12994 6514 12995 6518 12995 6513 12995 6513 12996 6518 12996 6504 12996 6513 12997 6504 12997 6523 12997 6519 12998 1626 12998 6524 12998 6524 12999 1626 12999 6520 12999 6524 13000 6520 13000 6523 13000 6523 13001 6520 13001 6525 13001 6523 13002 6525 13002 6516 13002 6516 13003 6525 13003 6526 13003 6516 13004 6526 13004 6517 13004 6504 13005 6521 13005 6523 13005 6523 13006 6521 13006 6522 13006 6523 13007 6522 13007 6524 13007 6524 13008 6522 13008 6506 13008 6524 13009 6506 13009 6512 13009 6512 13010 6506 13010 6505 13010 1626 13011 1624 13011 6520 13011 6520 13012 1624 13012 6537 13012 6520 13013 6537 13013 6525 13013 6525 13014 6537 13014 6538 13014 6525 13015 6538 13015 6526 13015 6526 13016 6538 13016 6527 13016 6526 13017 6527 13017 6517 13017 6517 13018 6527 13018 2006 13018 6537 13019 1624 13019 1623 13019 6536 13020 6530 13020 6528 13020 6528 13021 6530 13021 6531 13021 6528 13022 6531 13022 6535 13022 6535 13023 6531 13023 6533 13023 1623 13024 1621 13024 6529 13024 6529 13025 1621 13025 6553 13025 6530 13026 6543 13026 6531 13026 6531 13027 6543 13027 4598 13027 6531 13028 4598 13028 6533 13028 6533 13029 4598 13029 6532 13029 6532 13030 4599 13030 6539 13030 6532 13031 6539 13031 6533 13031 6533 13032 6539 13032 6534 13032 6533 13033 6534 13033 6535 13033 6535 13034 6534 13034 6529 13034 6535 13035 6529 13035 6528 13035 6528 13036 6529 13036 6553 13036 6528 13037 6553 13037 6536 13037 1623 13038 6529 13038 6537 13038 6537 13039 6529 13039 6534 13039 6537 13040 6534 13040 6538 13040 6538 13041 6534 13041 6539 13041 6538 13042 6539 13042 6527 13042 6527 13043 6539 13043 4599 13043 6527 13044 4599 13044 2006 13044 6540 13045 6536 13045 6553 13045 6542 13046 6541 13046 6552 13046 6530 13047 6536 13047 6546 13047 6546 13048 6536 13048 6540 13048 6546 13049 6540 13049 6551 13049 6541 13050 6542 13050 6550 13050 6550 13051 6542 13051 6548 13051 6550 13052 6548 13052 2121 13052 6543 13053 6530 13053 6544 13053 6544 13054 6530 13054 6546 13054 6544 13055 6546 13055 6545 13055 6545 13056 6546 13056 6551 13056 6545 13057 6551 13057 6549 13057 1620 13058 1618 13058 6552 13058 6552 13059 1618 13059 6547 13059 6552 13060 6547 13060 6542 13060 6542 13061 6547 13061 6556 13061 6542 13062 6556 13062 6548 13062 2121 13063 6549 13063 6550 13063 6550 13064 6549 13064 6551 13064 6550 13065 6551 13065 6541 13065 6541 13066 6551 13066 6540 13066 6541 13067 6540 13067 6552 13067 6552 13068 6540 13068 6553 13068 6552 13069 6553 13069 1620 13069 1620 13070 6553 13070 1621 13070 1619 13071 6554 13071 6569 13071 1618 13072 1619 13072 6547 13072 6547 13073 1619 13073 6569 13073 6547 13074 6569 13074 6556 13074 6556 13075 6569 13075 6555 13075 6556 13076 6555 13076 6548 13076 6548 13077 6555 13077 6572 13077 6548 13078 6572 13078 2121 13078 2121 13079 6572 13079 2124 13079 6563 13080 6557 13080 6561 13080 6569 13081 6554 13081 6567 13081 6567 13082 6554 13082 6558 13082 6567 13083 6558 13083 6559 13083 6560 13084 6557 13084 6568 13084 6568 13085 6557 13085 6563 13085 6568 13086 6563 13086 6570 13086 6570 13087 6563 13087 6564 13087 6570 13088 6564 13088 6571 13088 6571 13089 6564 13089 6566 13089 6561 13090 6562 13090 6563 13090 6563 13091 6562 13091 2113 13091 6563 13092 2113 13092 6564 13092 6564 13093 2113 13093 6565 13093 6564 13094 6565 13094 6566 13094 6566 13095 6565 13095 2116 13095 6559 13096 1617 13096 6567 13096 6567 13097 1617 13097 6574 13097 6567 13098 6574 13098 6560 13098 6560 13099 6568 13099 6567 13099 6567 13100 6568 13100 6570 13100 6567 13101 6570 13101 6569 13101 6569 13102 6570 13102 6571 13102 6569 13103 6571 13103 6555 13103 6555 13104 6571 13104 6566 13104 6555 13105 6566 13105 6572 13105 6572 13106 6566 13106 2116 13106 6572 13107 2116 13107 2124 13107 6573 13108 6561 13108 6579 13108 6579 13109 6561 13109 6557 13109 6579 13110 6557 13110 6576 13110 6576 13111 6557 13111 6560 13111 6576 13112 6560 13112 6581 13112 6581 13113 6560 13113 6574 13113 6581 13114 6574 13114 6575 13114 6575 13115 6574 13115 1617 13115 1616 13116 6584 13116 6582 13116 1616 13117 6582 13117 6575 13117 6580 13118 6578 13118 6576 13118 6576 13119 6578 13119 6577 13119 6576 13120 6577 13120 6579 13120 6578 13121 2108 13121 6577 13121 6577 13122 2108 13122 2110 13122 6577 13123 2110 13123 6579 13123 6579 13124 2110 13124 6573 13124 6580 13125 6576 13125 6582 13125 6582 13126 6576 13126 6581 13126 6582 13127 6581 13127 6575 13127 2108 13128 6578 13128 6593 13128 6593 13129 6578 13129 6592 13129 6592 13130 6578 13130 6583 13130 6583 13131 6578 13131 6580 13131 6583 13132 6580 13132 6585 13132 6580 13133 6582 13133 6585 13133 6585 13134 6582 13134 6584 13134 6585 13135 6584 13135 1615 13135 1614 13136 1613 13136 6586 13136 6586 13137 1613 13137 6587 13137 6586 13138 6587 13138 6588 13138 6588 13139 6587 13139 6589 13139 6588 13140 6589 13140 6594 13140 6594 13141 6589 13141 6590 13141 6594 13142 6590 13142 6591 13142 6591 13143 6590 13143 5348 13143 1615 13144 1614 13144 6585 13144 6585 13145 1614 13145 6586 13145 6585 13146 6586 13146 6583 13146 6583 13147 6586 13147 6588 13147 6583 13148 6588 13148 6592 13148 6592 13149 6588 13149 6594 13149 6592 13150 6594 13150 6593 13150 6593 13151 6594 13151 6591 13151 1611 13152 1610 13152 6601 13152 1610 13153 1608 13153 6601 13153 6601 13154 1608 13154 6595 13154 6601 13155 6595 13155 6597 13155 6597 13156 6595 13156 6596 13156 6597 13157 6596 13157 6599 13157 6599 13158 6596 13158 6598 13158 6599 13159 6598 13159 5343 13159 5343 13160 6598 13160 6610 13160 5343 13161 6602 13161 6599 13161 6599 13162 6602 13162 6603 13162 6599 13163 6603 13163 6597 13163 6597 13164 6603 13164 6600 13164 6597 13165 6600 13165 6601 13165 6601 13166 6600 13166 6604 13166 6601 13167 6604 13167 1611 13167 6602 13168 5347 13168 6603 13168 6603 13169 5347 13169 6609 13169 6603 13170 6609 13170 6600 13170 6600 13171 6609 13171 6608 13171 6600 13172 6608 13172 6604 13172 6604 13173 6608 13173 6605 13173 6604 13174 6605 13174 6606 13174 1613 13175 6607 13175 6587 13175 6587 13176 6607 13176 6605 13176 6587 13177 6605 13177 6589 13177 6589 13178 6605 13178 6608 13178 6589 13179 6608 13179 6590 13179 6590 13180 6608 13180 6609 13180 6590 13181 6609 13181 5348 13181 5348 13182 6609 13182 5347 13182 6595 13183 1608 13183 1607 13183 6596 13184 6595 13184 6614 13184 6598 13185 6596 13185 6642 13185 6610 13186 6598 13186 6655 13186 6610 13187 6655 13187 1030 13187 1030 13188 6655 13188 6656 13188 1030 13189 6656 13189 6611 13189 6611 13190 6656 13190 6612 13190 6611 13191 6612 13191 6613 13191 6613 13192 6612 13192 6658 13192 6613 13193 6658 13193 1028 13193 1028 13194 6658 13194 6620 13194 1028 13195 6620 13195 6619 13195 6595 13196 1607 13196 6614 13196 6614 13197 1607 13197 1605 13197 6614 13198 1605 13198 6616 13198 6616 13199 1605 13199 6615 13199 6616 13200 6615 13200 6644 13200 6644 13201 6615 13201 1604 13201 6644 13202 1604 13202 6617 13202 6617 13203 1604 13203 1601 13203 6617 13204 1601 13204 6618 13204 6618 13205 1601 13205 6630 13205 6618 13206 6630 13206 6631 13206 6619 13207 6620 13207 1026 13207 1026 13208 6620 13208 6623 13208 1026 13209 6623 13209 6621 13209 6621 13210 6623 13210 6622 13210 6622 13211 6623 13211 6624 13211 6622 13212 6624 13212 6626 13212 6626 13213 6624 13213 6625 13213 6626 13214 6625 13214 6627 13214 6627 13215 6625 13215 6628 13215 6627 13216 6628 13216 1022 13216 1022 13217 6628 13217 6629 13217 1022 13218 6629 13218 1017 13218 6630 13219 1643 13219 6631 13219 6631 13220 1643 13220 1642 13220 6631 13221 1642 13221 6632 13221 6632 13222 1642 13222 6633 13222 6632 13223 6633 13223 6648 13223 6648 13224 6633 13224 6634 13224 6648 13225 6634 13225 6650 13225 6650 13226 6634 13226 6635 13226 6650 13227 6635 13227 6651 13227 6651 13228 6635 13228 6636 13228 6651 13229 6636 13229 6637 13229 6637 13230 6636 13230 1597 13230 6637 13231 1597 13231 6639 13231 6639 13232 1597 13232 6638 13232 6639 13233 6638 13233 6640 13233 6640 13234 6638 13234 1599 13234 6640 13235 1599 13235 6641 13235 6596 13236 6614 13236 6642 13236 6642 13237 6614 13237 6616 13237 6642 13238 6616 13238 6643 13238 6643 13239 6616 13239 6644 13239 6643 13240 6644 13240 6657 13240 6657 13241 6644 13241 6617 13241 6657 13242 6617 13242 6645 13242 6645 13243 6617 13243 6618 13243 6645 13244 6618 13244 6659 13244 6659 13245 6618 13245 6631 13245 6659 13246 6631 13246 6646 13246 6646 13247 6631 13247 6632 13247 6646 13248 6632 13248 6647 13248 6647 13249 6632 13249 6648 13249 6647 13250 6648 13250 6660 13250 6660 13251 6648 13251 6650 13251 6660 13252 6650 13252 6649 13252 6649 13253 6650 13253 6651 13253 6649 13254 6651 13254 6661 13254 6661 13255 6651 13255 6637 13255 6661 13256 6637 13256 6652 13256 6652 13257 6637 13257 6639 13257 6652 13258 6639 13258 6653 13258 6653 13259 6639 13259 6640 13259 6653 13260 6640 13260 6654 13260 6654 13261 6640 13261 6641 13261 6654 13262 6641 13262 6685 13262 6598 13263 6642 13263 6655 13263 6655 13264 6642 13264 6643 13264 6655 13265 6643 13265 6656 13265 6656 13266 6643 13266 6657 13266 6656 13267 6657 13267 6612 13267 6612 13268 6657 13268 6645 13268 6612 13269 6645 13269 6658 13269 6658 13270 6645 13270 6659 13270 6658 13271 6659 13271 6620 13271 6620 13272 6659 13272 6646 13272 6620 13273 6646 13273 6623 13273 6623 13274 6646 13274 6647 13274 6623 13275 6647 13275 6624 13275 6624 13276 6647 13276 6660 13276 6624 13277 6660 13277 6625 13277 6625 13278 6660 13278 6649 13278 6625 13279 6649 13279 6628 13279 6628 13280 6649 13280 6661 13280 6628 13281 6661 13281 6629 13281 6629 13282 6661 13282 6652 13282 6629 13283 6652 13283 6662 13283 6662 13284 6652 13284 6653 13284 6662 13285 6653 13285 6663 13285 6663 13286 6653 13286 6654 13286 6663 13287 6654 13287 6664 13287 6664 13288 6654 13288 6685 13288 6664 13289 6685 13289 6686 13289 1017 13290 6629 13290 6665 13290 6665 13291 6629 13291 6662 13291 6665 13292 6662 13292 6666 13292 6666 13293 6662 13293 6663 13293 6666 13294 6663 13294 1016 13294 1016 13295 6663 13295 6664 13295 1016 13296 6664 13296 6667 13296 6667 13297 6664 13297 6686 13297 6667 13298 6686 13298 5362 13298 6673 13299 6668 13299 6674 13299 6674 13300 6668 13300 6669 13300 6674 13301 6669 13301 6675 13301 6675 13302 6669 13302 6670 13302 6675 13303 6670 13303 6677 13303 6677 13304 6670 13304 6671 13304 6677 13305 6671 13305 6672 13305 6672 13306 6671 13306 5370 13306 1593 13307 6673 13307 6679 13307 6679 13308 6673 13308 6674 13308 6679 13309 6674 13309 6680 13309 6680 13310 6674 13310 6675 13310 6680 13311 6675 13311 6683 13311 6683 13312 6675 13312 6677 13312 6683 13313 6677 13313 6676 13313 6676 13314 6677 13314 6672 13314 1594 13315 1593 13315 6684 13315 6684 13316 1593 13316 6679 13316 6684 13317 6679 13317 6678 13317 6678 13318 6679 13318 6680 13318 6678 13319 6680 13319 6681 13319 6681 13320 6680 13320 6683 13320 6681 13321 6683 13321 6682 13321 6682 13322 6683 13322 6676 13322 1599 13323 1594 13323 6641 13323 6641 13324 1594 13324 6684 13324 6641 13325 6684 13325 6685 13325 6685 13326 6684 13326 6678 13326 6685 13327 6678 13327 6686 13327 6686 13328 6678 13328 6681 13328 6686 13329 6681 13329 5362 13329 5362 13330 6681 13330 6682 13330 6691 13331 1592 13331 6692 13331 6692 13332 1592 13332 6693 13332 6692 13333 6693 13333 6687 13333 6687 13334 6693 13334 6688 13334 6687 13335 6688 13335 6689 13335 6689 13336 6688 13336 6694 13336 6689 13337 6694 13337 6690 13337 6690 13338 6694 13338 2285 13338 6668 13339 6691 13339 6669 13339 6669 13340 6691 13340 6692 13340 6669 13341 6692 13341 6670 13341 6670 13342 6692 13342 6687 13342 6670 13343 6687 13343 6671 13343 6671 13344 6687 13344 6689 13344 6671 13345 6689 13345 5370 13345 5370 13346 6689 13346 6690 13346 6697 13347 6699 13347 1592 13347 1592 13348 6699 13348 6693 13348 6693 13349 6699 13349 6688 13349 6688 13350 6699 13350 6701 13350 6688 13351 6701 13351 6694 13351 6701 13352 6695 13352 6694 13352 6694 13353 6695 13353 2284 13353 6694 13354 2284 13354 2285 13354 6696 13355 6695 13355 6701 13355 6698 13356 6706 13356 6700 13356 2284 13357 6695 13357 2281 13357 2281 13358 6695 13358 6696 13358 2281 13359 6696 13359 6703 13359 6697 13360 6698 13360 6699 13360 6699 13361 6698 13361 6700 13361 6699 13362 6700 13362 6701 13362 6701 13363 6700 13363 6702 13363 6701 13364 6702 13364 6696 13364 6696 13365 6702 13365 6705 13365 6696 13366 6705 13366 6703 13366 6721 13367 6703 13367 6704 13367 6704 13368 6703 13368 6705 13368 6704 13369 6705 13369 6719 13369 6719 13370 6705 13370 6702 13370 6719 13371 6702 13371 6718 13371 6718 13372 6702 13372 6700 13372 6718 13373 6700 13373 1590 13373 1590 13374 6700 13374 6706 13374 6707 13375 6727 13375 2333 13375 6727 13376 6707 13376 6717 13376 1589 13377 1588 13377 6714 13377 1589 13378 6714 13378 1590 13378 6709 13379 6715 13379 6707 13379 6707 13380 6715 13380 6716 13380 6707 13381 6716 13381 6717 13381 6711 13382 6709 13382 6708 13382 6708 13383 6709 13383 6707 13383 6708 13384 6707 13384 6710 13384 6710 13385 6707 13385 2333 13385 6711 13386 6712 13386 6720 13386 1588 13387 6723 13387 6714 13387 6714 13388 6723 13388 6724 13388 6714 13389 6724 13389 6725 13389 6711 13390 6720 13390 6709 13390 6709 13391 6720 13391 6713 13391 6709 13392 6713 13392 6715 13392 6715 13393 6713 13393 6714 13393 6715 13394 6714 13394 6716 13394 6716 13395 6714 13395 6725 13395 6716 13396 6725 13396 6717 13396 1590 13397 6714 13397 6718 13397 6718 13398 6714 13398 6713 13398 6718 13399 6713 13399 6719 13399 6719 13400 6713 13400 6720 13400 6719 13401 6720 13401 6704 13401 6704 13402 6720 13402 6712 13402 6704 13403 6712 13403 6721 13403 6740 13404 1591 13404 6729 13404 6729 13405 1591 13405 6722 13405 6723 13406 1591 13406 6724 13406 6724 13407 1591 13407 6740 13407 6724 13408 6740 13408 6725 13408 6725 13409 6740 13409 6726 13409 6725 13410 6726 13410 6717 13410 6717 13411 6726 13411 6731 13411 6717 13412 6731 13412 6727 13412 6727 13413 6731 13413 6728 13413 6727 13414 6728 13414 2333 13414 2333 13415 6728 13415 6735 13415 6731 13416 6726 13416 6734 13416 6722 13417 6730 13417 6729 13417 6729 13418 6730 13418 6741 13418 6729 13419 6741 13419 6740 13419 6728 13420 6731 13420 6732 13420 6732 13421 6731 13421 6734 13421 6732 13422 6734 13422 6733 13422 6733 13423 6734 13423 6742 13423 6733 13424 6742 13424 6739 13424 6735 13425 6728 13425 6736 13425 6736 13426 6728 13426 6732 13426 6736 13427 6732 13427 6737 13427 6737 13428 6732 13428 6733 13428 6737 13429 6733 13429 6738 13429 6738 13430 6733 13430 6739 13430 6738 13431 6739 13431 2327 13431 6730 13432 1587 13432 6741 13432 6741 13433 1587 13433 6758 13433 6741 13434 6758 13434 6743 13434 6743 13435 6758 13435 6746 13435 6743 13436 6746 13436 6752 13436 6726 13437 6740 13437 6734 13437 6734 13438 6740 13438 6741 13438 6734 13439 6741 13439 6742 13439 6742 13440 6741 13440 6743 13440 6742 13441 6743 13441 6739 13441 6739 13442 6743 13442 6752 13442 6739 13443 6752 13443 2327 13443 6744 13444 6746 13444 6758 13444 6750 13445 6759 13445 6745 13445 6752 13446 6746 13446 6747 13446 6747 13447 6746 13447 6744 13447 6747 13448 6744 13448 6748 13448 6759 13449 6750 13449 6749 13449 6749 13450 6750 13450 6751 13450 6749 13451 6751 13451 6762 13451 2327 13452 6752 13452 6753 13452 6753 13453 6752 13453 6747 13453 6753 13454 6747 13454 4070 13454 4070 13455 6747 13455 6748 13455 4070 13456 6748 13456 6754 13456 1586 13457 6755 13457 6745 13457 6745 13458 6755 13458 6756 13458 6745 13459 6756 13459 6750 13459 6750 13460 6756 13460 6757 13460 6750 13461 6757 13461 6751 13461 1587 13462 1586 13462 6758 13462 6758 13463 1586 13463 6745 13463 6758 13464 6745 13464 6744 13464 6744 13465 6745 13465 6759 13465 6744 13466 6759 13466 6748 13466 6748 13467 6759 13467 6749 13467 6748 13468 6749 13468 6754 13468 6754 13469 6749 13469 6762 13469 6755 13470 6760 13470 6756 13470 6756 13471 6760 13471 6761 13471 6756 13472 6761 13472 6757 13472 6757 13473 6761 13473 6772 13473 6757 13474 6772 13474 6751 13474 6751 13475 6772 13475 6764 13475 6751 13476 6764 13476 6762 13476 6762 13477 6764 13477 3942 13477 1583 13478 1582 13478 6763 13478 6767 13479 6764 13479 6772 13479 6781 13480 6773 13480 6765 13480 6765 13481 6773 13481 6769 13481 6765 13482 6769 13482 6768 13482 1583 13483 6763 13483 6770 13483 3942 13484 6764 13484 6766 13484 6766 13485 6764 13485 6767 13485 6766 13486 6767 13486 6774 13486 6768 13487 6769 13487 6763 13487 6763 13488 6769 13488 6771 13488 6763 13489 6771 13489 6770 13489 6760 13490 6770 13490 6761 13490 6761 13491 6770 13491 6771 13491 6761 13492 6771 13492 6772 13492 6772 13493 6771 13493 6769 13493 6772 13494 6769 13494 6767 13494 6767 13495 6769 13495 6773 13495 6767 13496 6773 13496 6774 13496 6774 13497 6773 13497 6781 13497 6774 13498 6781 13498 2321 13498 6776 13499 6775 13499 2321 13499 6777 13500 6776 13500 6780 13500 6775 13501 6776 13501 2323 13501 2323 13502 6776 13502 6777 13502 2323 13503 6777 13503 2324 13503 6778 13504 1580 13504 6782 13504 6782 13505 1580 13505 6779 13505 6782 13506 6779 13506 6780 13506 6780 13507 6779 13507 6783 13507 6780 13508 6783 13508 6777 13508 6777 13509 6783 13509 6784 13509 6777 13510 6784 13510 2324 13510 2321 13511 6781 13511 6776 13511 6776 13512 6781 13512 6765 13512 6776 13513 6765 13513 6780 13513 6780 13514 6765 13514 6768 13514 6780 13515 6768 13515 6782 13515 6782 13516 6768 13516 6763 13516 6782 13517 6763 13517 6778 13517 6778 13518 6763 13518 1582 13518 1580 13519 6796 13519 6779 13519 6779 13520 6796 13520 6797 13520 6779 13521 6797 13521 6783 13521 6783 13522 6797 13522 6786 13522 6783 13523 6786 13523 6784 13523 6784 13524 6786 13524 6790 13524 6784 13525 6790 13525 2324 13525 2324 13526 6790 13526 2319 13526 6790 13527 6786 13527 6785 13527 6785 13528 6786 13528 6787 13528 6785 13529 6787 13529 6789 13529 6807 13530 2313 13530 6788 13530 6788 13531 2313 13531 2312 13531 6788 13532 2312 13532 6789 13532 6789 13533 2312 13533 2309 13533 6789 13534 2309 13534 6785 13534 6785 13535 2309 13535 2310 13535 6785 13536 2310 13536 6790 13536 6790 13537 2310 13537 2319 13537 6806 13538 6800 13538 6791 13538 6791 13539 6800 13539 6795 13539 6791 13540 6795 13540 6794 13540 1579 13541 6793 13541 6792 13541 6792 13542 6793 13542 6794 13542 6792 13543 6794 13543 6798 13543 6798 13544 6794 13544 6795 13544 6798 13545 6795 13545 6799 13545 6799 13546 6795 13546 6800 13546 6796 13547 1579 13547 6797 13547 6797 13548 1579 13548 6792 13548 6797 13549 6792 13549 6786 13549 6786 13550 6792 13550 6798 13550 6786 13551 6798 13551 6787 13551 6787 13552 6798 13552 6799 13552 6787 13553 6799 13553 6789 13553 6789 13554 6799 13554 6800 13554 6789 13555 6800 13555 6788 13555 6788 13556 6800 13556 6806 13556 6788 13557 6806 13557 6807 13557 6801 13558 6791 13558 6794 13558 6794 13559 6793 13559 6802 13559 6803 13560 6804 13560 6805 13560 3966 13561 2313 13561 6807 13561 6791 13562 6801 13562 6806 13562 6806 13563 6801 13563 6808 13563 6806 13564 6808 13564 6807 13564 6807 13565 6808 13565 6809 13565 6807 13566 6809 13566 3966 13566 6810 13567 6811 13567 6812 13567 6812 13568 6811 13568 6813 13568 6812 13569 6813 13569 6803 13569 6802 13570 6814 13570 6817 13570 6817 13571 6814 13571 6815 13571 6817 13572 6815 13572 6810 13572 6810 13573 6815 13573 6820 13573 6810 13574 6820 13574 6811 13574 6803 13575 6805 13575 6812 13575 6812 13576 6805 13576 6816 13576 6812 13577 6816 13577 6810 13577 6810 13578 6816 13578 6818 13578 6810 13579 6818 13579 6817 13579 6802 13580 6817 13580 6794 13580 6794 13581 6817 13581 6818 13581 6794 13582 6818 13582 6801 13582 6801 13583 6818 13583 6816 13583 6801 13584 6816 13584 6808 13584 6808 13585 6816 13585 6805 13585 6808 13586 6805 13586 6809 13586 6809 13587 6805 13587 6804 13587 6809 13588 6804 13588 3966 13588 6814 13589 1577 13589 6815 13589 6815 13590 1577 13590 6819 13590 6815 13591 6819 13591 6820 13591 6820 13592 6819 13592 6821 13592 6820 13593 6821 13593 6811 13593 6811 13594 6821 13594 6823 13594 6811 13595 6823 13595 6813 13595 6813 13596 6823 13596 2005 13596 6825 13597 6823 13597 6821 13597 6822 13598 6831 13598 6840 13598 6840 13599 6831 13599 6830 13599 2005 13600 6823 13600 6824 13600 6824 13601 6823 13601 6825 13601 6824 13602 6825 13602 4090 13602 6826 13603 6843 13603 6827 13603 6827 13604 6843 13604 6828 13604 6827 13605 6828 13605 6830 13605 6830 13606 6828 13606 6829 13606 6830 13607 6829 13607 6840 13607 1577 13608 6826 13608 6819 13608 6819 13609 6826 13609 6827 13609 6819 13610 6827 13610 6821 13610 6821 13611 6827 13611 6830 13611 6821 13612 6830 13612 6825 13612 6825 13613 6830 13613 6831 13613 6825 13614 6831 13614 4090 13614 4090 13615 6831 13615 6822 13615 4090 13616 6822 13616 6832 13616 6838 13617 6833 13617 6832 13617 6833 13618 6838 13618 6834 13618 6834 13619 6838 13619 6835 13619 6834 13620 6835 13620 6850 13620 6842 13621 6836 13621 6837 13621 6837 13622 6836 13622 6845 13622 6837 13623 6845 13623 6841 13623 6841 13624 6845 13624 6846 13624 6841 13625 6846 13625 6838 13625 6838 13626 6846 13626 6839 13626 6838 13627 6839 13627 6835 13627 6835 13628 6839 13628 6848 13628 6835 13629 6848 13629 6850 13629 6832 13630 6822 13630 6838 13630 6838 13631 6822 13631 6840 13631 6838 13632 6840 13632 6841 13632 6841 13633 6840 13633 6829 13633 6841 13634 6829 13634 6837 13634 6837 13635 6829 13635 6828 13635 6837 13636 6828 13636 6842 13636 6842 13637 6828 13637 6843 13637 6845 13638 6836 13638 6844 13638 6844 13639 6865 13639 6845 13639 6845 13640 6865 13640 6867 13640 6845 13641 6867 13641 6846 13641 6846 13642 6867 13642 6864 13642 6846 13643 6864 13643 6839 13643 6839 13644 6864 13644 6847 13644 6839 13645 6847 13645 6848 13645 6848 13646 6847 13646 6849 13646 6848 13647 6849 13647 6850 13647 6850 13648 6849 13648 6851 13648 6869 13649 6852 13649 6866 13649 2298 13650 6851 13650 6849 13650 6861 13651 6853 13651 1574 13651 6868 13652 6862 13652 6863 13652 6862 13653 6868 13653 6858 13653 6858 13654 6868 13654 6870 13654 6858 13655 6870 13655 6854 13655 6854 13656 6870 13656 6889 13656 6854 13657 6889 13657 6855 13657 6887 13658 6859 13658 6856 13658 6856 13659 6859 13659 6857 13659 6855 13660 6856 13660 6854 13660 6854 13661 6856 13661 6857 13661 6854 13662 6857 13662 6858 13662 6858 13663 6857 13663 6859 13663 6858 13664 6859 13664 6862 13664 6862 13665 6859 13665 2298 13665 6860 13666 6869 13666 6890 13666 6890 13667 6869 13667 6866 13667 6890 13668 6866 13668 6871 13668 6871 13669 6866 13669 6861 13669 6871 13670 6861 13670 6882 13670 6882 13671 6861 13671 1574 13671 2298 13672 6849 13672 6862 13672 6862 13673 6849 13673 6847 13673 6862 13674 6847 13674 6863 13674 6863 13675 6847 13675 6864 13675 6863 13676 6864 13676 6867 13676 6844 13677 6853 13677 6865 13677 6865 13678 6853 13678 6861 13678 6865 13679 6861 13679 6867 13679 6867 13680 6861 13680 6866 13680 6867 13681 6866 13681 6863 13681 6863 13682 6866 13682 6852 13682 6863 13683 6852 13683 6868 13683 6868 13684 6852 13684 6869 13684 6868 13685 6869 13685 6870 13685 6870 13686 6869 13686 6860 13686 6870 13687 6860 13687 6889 13687 6890 13688 6871 13688 6872 13688 6873 13689 6883 13689 6879 13689 4115 13690 4116 13690 6878 13690 6883 13691 6881 13691 6891 13691 6877 13692 6879 13692 6895 13692 6895 13693 6874 13693 6877 13693 6877 13694 6874 13694 6875 13694 6877 13695 6875 13695 4115 13695 6891 13696 6892 13696 6883 13696 6883 13697 6892 13697 6876 13697 6883 13698 6876 13698 6879 13698 6879 13699 6876 13699 6896 13699 6879 13700 6896 13700 6895 13700 4115 13701 6878 13701 6877 13701 6877 13702 6878 13702 6884 13702 6877 13703 6884 13703 6879 13703 6879 13704 6884 13704 6880 13704 6879 13705 6880 13705 6873 13705 1574 13706 6881 13706 6882 13706 6882 13707 6881 13707 6883 13707 6882 13708 6883 13708 6871 13708 6871 13709 6883 13709 6873 13709 6871 13710 6873 13710 6872 13710 6872 13711 6873 13711 6880 13711 6872 13712 6880 13712 6888 13712 6888 13713 6880 13713 6884 13713 6888 13714 6884 13714 6885 13714 6885 13715 6884 13715 6878 13715 6885 13716 6878 13716 6886 13716 6886 13717 6878 13717 4116 13717 6886 13718 4116 13718 6887 13718 6887 13719 6856 13719 6886 13719 6886 13720 6856 13720 6885 13720 6885 13721 6856 13721 6855 13721 6885 13722 6855 13722 6888 13722 6888 13723 6855 13723 6889 13723 6888 13724 6889 13724 6872 13724 6872 13725 6889 13725 6860 13725 6872 13726 6860 13726 6890 13726 6891 13727 1573 13727 6892 13727 6892 13728 1573 13728 6893 13728 2002 13729 6875 13729 6898 13729 6898 13730 6875 13730 6874 13730 6898 13731 6874 13731 6894 13731 6894 13732 6874 13732 6895 13732 6894 13733 6895 13733 6906 13733 6906 13734 6895 13734 6896 13734 6906 13735 6896 13735 6893 13735 6893 13736 6896 13736 6876 13736 6893 13737 6876 13737 6892 13737 6906 13738 6897 13738 6894 13738 6894 13739 6897 13739 6898 13739 2002 13740 6898 13740 4146 13740 4146 13741 6898 13741 6897 13741 4146 13742 6897 13742 6908 13742 6899 13743 6901 13743 6900 13743 6900 13744 6901 13744 6907 13744 6900 13745 6907 13745 6902 13745 6902 13746 6907 13746 6905 13746 6902 13747 6905 13747 6903 13747 6903 13748 6905 13748 6904 13748 1573 13749 6904 13749 6893 13749 6893 13750 6904 13750 6905 13750 6893 13751 6905 13751 6906 13751 6906 13752 6905 13752 6907 13752 6906 13753 6907 13753 6897 13753 6897 13754 6907 13754 6901 13754 6897 13755 6901 13755 6908 13755 6908 13756 6901 13756 6899 13756 6908 13757 6899 13757 4145 13757 6913 13758 4145 13758 6899 13758 6911 13759 6909 13759 6910 13759 6911 13760 6910 13760 6903 13760 6912 13761 6913 13761 6914 13761 6914 13762 6913 13762 6899 13762 6914 13763 6899 13763 6923 13763 6923 13764 6899 13764 6900 13764 6923 13765 6900 13765 6910 13765 6910 13766 6900 13766 6902 13766 6910 13767 6902 13767 6903 13767 6922 13768 6912 13768 6914 13768 6921 13769 6920 13769 6915 13769 6915 13770 6920 13770 6916 13770 6915 13771 6916 13771 6917 13771 6925 13772 2379 13772 6924 13772 6924 13773 2379 13773 6939 13773 6924 13774 6939 13774 6918 13774 6918 13775 6939 13775 6936 13775 6918 13776 6936 13776 6920 13776 6920 13777 6936 13777 6919 13777 6920 13778 6919 13778 6916 13778 6916 13779 6919 13779 6933 13779 6916 13780 6933 13780 6917 13780 6921 13781 6922 13781 6920 13781 6920 13782 6922 13782 6914 13782 6920 13783 6914 13783 6918 13783 6918 13784 6914 13784 6923 13784 6918 13785 6923 13785 6924 13785 6924 13786 6923 13786 6910 13786 6924 13787 6910 13787 6925 13787 6925 13788 6910 13788 6909 13788 6926 13789 2292 13789 2293 13789 6943 13790 6945 13790 6930 13790 6930 13791 6945 13791 6926 13791 6927 13792 6929 13792 6928 13792 6928 13793 6929 13793 6943 13793 6926 13794 2293 13794 6930 13794 6930 13795 2293 13795 2294 13795 6930 13796 2294 13796 6931 13796 6931 13797 2294 13797 6932 13797 6931 13798 6932 13798 6935 13798 6932 13799 6917 13799 6933 13799 6932 13800 6933 13800 6935 13800 6935 13801 6933 13801 6919 13801 6935 13802 6919 13802 6936 13802 6943 13803 6930 13803 6928 13803 6928 13804 6930 13804 6931 13804 6928 13805 6931 13805 6934 13805 6934 13806 6931 13806 6935 13806 6934 13807 6935 13807 6938 13807 6938 13808 6935 13808 6936 13808 6938 13809 6936 13809 6939 13809 6927 13810 6928 13810 6937 13810 6937 13811 6928 13811 6934 13811 6937 13812 6934 13812 2376 13812 2376 13813 6934 13813 6938 13813 2376 13814 6938 13814 2378 13814 2378 13815 6938 13815 6939 13815 2378 13816 6939 13816 2379 13816 2374 13817 2372 13817 6940 13817 6940 13818 2372 13818 6950 13818 6940 13819 6950 13819 6944 13819 6944 13820 6950 13820 6941 13820 6944 13821 6941 13821 6946 13821 6946 13822 6941 13822 6953 13822 2292 13823 6946 13823 6942 13823 6942 13824 6946 13824 6953 13824 6942 13825 6953 13825 2287 13825 6927 13826 2374 13826 6929 13826 6929 13827 2374 13827 6940 13827 6929 13828 6940 13828 6943 13828 6943 13829 6940 13829 6944 13829 6943 13830 6944 13830 6945 13830 6945 13831 6944 13831 6946 13831 6945 13832 6946 13832 6926 13832 6926 13833 6946 13833 2292 13833 6947 13834 6955 13834 6956 13834 6956 13835 6955 13835 6954 13835 6956 13836 6954 13836 6948 13836 6948 13837 6954 13837 6949 13837 6951 13838 2371 13838 6952 13838 6952 13839 2371 13839 6960 13839 6952 13840 6960 13840 6949 13840 6949 13841 6960 13841 6958 13841 6949 13842 6958 13842 6948 13842 2372 13843 6951 13843 6950 13843 6950 13844 6951 13844 6952 13844 6950 13845 6952 13845 6941 13845 6941 13846 6952 13846 6949 13846 6941 13847 6949 13847 6953 13847 6953 13848 6949 13848 6954 13848 6953 13849 6954 13849 2287 13849 2287 13850 6954 13850 6955 13850 6947 13851 6956 13851 2336 13851 2336 13852 6956 13852 6957 13852 6956 13853 6948 13853 6957 13853 6957 13854 6948 13854 6958 13854 6957 13855 6958 13855 6959 13855 6959 13856 6958 13856 6960 13856 6959 13857 6960 13857 1746 13857 1746 13858 6960 13858 2371 13858 6961 13859 2336 13859 6962 13859 6962 13860 2336 13860 6957 13860 6962 13861 6957 13861 6963 13861 6963 13862 6957 13862 6967 13862 6967 13863 6957 13863 6959 13863 6967 13864 6959 13864 6969 13864 6969 13865 6959 13865 1746 13865 6969 13866 1746 13866 6964 13866 6965 13867 1739 13867 6972 13867 6965 13868 6972 13868 6966 13868 6970 13869 6967 13869 6968 13869 6968 13870 6967 13870 6969 13870 6968 13871 6969 13871 1736 13871 1736 13872 6969 13872 6964 13872 3120 13873 6961 13873 6971 13873 6971 13874 6961 13874 6962 13874 6971 13875 6962 13875 6970 13875 6970 13876 6962 13876 6963 13876 6970 13877 6963 13877 6967 13877 3121 13878 3120 13878 6974 13878 6974 13879 3120 13879 6971 13879 6974 13880 6971 13880 6975 13880 6975 13881 6971 13881 6970 13881 6975 13882 6970 13882 6972 13882 6972 13883 6970 13883 6968 13883 6972 13884 6968 13884 6966 13884 6966 13885 6968 13885 1736 13885 6973 13886 3121 13886 6977 13886 6977 13887 3121 13887 6974 13887 6977 13888 6974 13888 6978 13888 6978 13889 6974 13889 6975 13889 6978 13890 6975 13890 6976 13890 6976 13891 6975 13891 6972 13891 6976 13892 6972 13892 1734 13892 1734 13893 6972 13893 1739 13893 6980 13894 6973 13894 6982 13894 6982 13895 6973 13895 6977 13895 6982 13896 6977 13896 6979 13896 6979 13897 6977 13897 6978 13897 6979 13898 6978 13898 6984 13898 6984 13899 6978 13899 6976 13899 6984 13900 6976 13900 1735 13900 1735 13901 6976 13901 1734 13901 6999 13902 6980 13902 6981 13902 6981 13903 6980 13903 6982 13903 6981 13904 6982 13904 6997 13904 6997 13905 6982 13905 6979 13905 6997 13906 6979 13906 6983 13906 6983 13907 6979 13907 6984 13907 6983 13908 6984 13908 1728 13908 1728 13909 6984 13909 1735 13909 6996 13910 6985 13910 6995 13910 6983 13911 1728 13911 1730 13911 6986 13912 6987 13912 6988 13912 6988 13913 6987 13913 6990 13913 6988 13914 6990 13914 6989 13914 6989 13915 6990 13915 6991 13915 6987 13916 4918 13916 6990 13916 6990 13917 4918 13917 6992 13917 6990 13918 6992 13918 6991 13918 6991 13919 6992 13919 6993 13919 6993 13920 4879 13920 6994 13920 6993 13921 6994 13921 6991 13921 6991 13922 6994 13922 6998 13922 6991 13923 6998 13923 6989 13923 6989 13924 6998 13924 6995 13924 6989 13925 6995 13925 6988 13925 6988 13926 6995 13926 6985 13926 6988 13927 6985 13927 6986 13927 4872 13928 6996 13928 1730 13928 1730 13929 6996 13929 6995 13929 1730 13930 6995 13930 6983 13930 6983 13931 6995 13931 6998 13931 6983 13932 6998 13932 6997 13932 6997 13933 6998 13933 6994 13933 6997 13934 6994 13934 6981 13934 6981 13935 6994 13935 4879 13935 6981 13936 4879 13936 6999 13936 7012 13937 7000 13937 7008 13937 7017 13938 4918 13938 7001 13938 7001 13939 4918 13939 6987 13939 7001 13940 6987 13940 7015 13940 7015 13941 6987 13941 6986 13941 7015 13942 6986 13942 6985 13942 7009 13943 7002 13943 7003 13943 7003 13944 7002 13944 7016 13944 7003 13945 7016 13945 7007 13945 7010 13946 7004 13946 7013 13946 7013 13947 7004 13947 7005 13947 7005 13948 4869 13948 7013 13948 7013 13949 4869 13949 4868 13949 7013 13950 4868 13950 7020 13950 4876 13951 4875 13951 7014 13951 4874 13952 7006 13952 7004 13952 7004 13953 7006 13953 4870 13953 7004 13954 4870 13954 7005 13954 7007 13955 7012 13955 7003 13955 7003 13956 7012 13956 7008 13956 7003 13957 7008 13957 7009 13957 7009 13958 7008 13958 4884 13958 4875 13959 4874 13959 7014 13959 7014 13960 4874 13960 7004 13960 7014 13961 7004 13961 7011 13961 7011 13962 7004 13962 7010 13962 7011 13963 7010 13963 7007 13963 7007 13964 7010 13964 7013 13964 7007 13965 7013 13965 7012 13965 7012 13966 7013 13966 7020 13966 7012 13967 7020 13967 7000 13967 4872 13968 4876 13968 6996 13968 6996 13969 4876 13969 7014 13969 6996 13970 7014 13970 6985 13970 6985 13971 7014 13971 7011 13971 6985 13972 7011 13972 7015 13972 7015 13973 7011 13973 7007 13973 7015 13974 7007 13974 7001 13974 7001 13975 7007 13975 7016 13975 7001 13976 7016 13976 7017 13976 7017 13977 7016 13977 7002 13977 7018 13978 4884 13978 7008 13978 7019 13979 7018 13979 7038 13979 7038 13980 7018 13980 7008 13980 7038 13981 7008 13981 7039 13981 7039 13982 7008 13982 7000 13982 7039 13983 7000 13983 7040 13983 7040 13984 7000 13984 7020 13984 7040 13985 7020 13985 7042 13985 7042 13986 7020 13986 4868 13986 4807 13987 4805 13987 7029 13987 7021 13988 4804 13988 7028 13988 7028 13989 4804 13989 7052 13989 7063 13990 1784 13990 7022 13990 7022 13991 1784 13991 7024 13991 7022 13992 7024 13992 7023 13992 7023 13993 7024 13993 7025 13993 7023 13994 7025 13994 7060 13994 7060 13995 7025 13995 7028 13995 7060 13996 7028 13996 7054 13996 7054 13997 7028 13997 7052 13997 1784 13998 1783 13998 7024 13998 7024 13999 1783 13999 7026 13999 7024 14000 7026 14000 7025 14000 7025 14001 7026 14001 7027 14001 7025 14002 7027 14002 7028 14002 7028 14003 7027 14003 7029 14003 7028 14004 7029 14004 7021 14004 7021 14005 7029 14005 4805 14005 7030 14006 4807 14006 7031 14006 7031 14007 4807 14007 7029 14007 7031 14008 7029 14008 7035 14008 7035 14009 7029 14009 7027 14009 7035 14010 7027 14010 7032 14010 7032 14011 7027 14011 7026 14011 7032 14012 7026 14012 7033 14012 7033 14013 7026 14013 1783 14013 7033 14014 1779 14014 7032 14014 7032 14015 1779 14015 7034 14015 7032 14016 7034 14016 7035 14016 7035 14017 7034 14017 7036 14017 7035 14018 7036 14018 7031 14018 7031 14019 7036 14019 7037 14019 7031 14020 7037 14020 7030 14020 7030 14021 7037 14021 7041 14021 1779 14022 7019 14022 7034 14022 7034 14023 7019 14023 7038 14023 7034 14024 7038 14024 7036 14024 7036 14025 7038 14025 7039 14025 7036 14026 7039 14026 7037 14026 7037 14027 7039 14027 7040 14027 7037 14028 7040 14028 7041 14028 7041 14029 7040 14029 7042 14029 7077 14030 7076 14030 7050 14030 7050 14031 7076 14031 7075 14031 4835 14032 7082 14032 7081 14032 7045 14033 7043 14033 7044 14033 7044 14034 7043 14034 7072 14034 7044 14035 7072 14035 7055 14035 7074 14036 7045 14036 7046 14036 7046 14037 7045 14037 7044 14037 7046 14038 7044 14038 7056 14038 7056 14039 7044 14039 7055 14039 7055 14040 7047 14040 7070 14040 7065 14041 7064 14041 7051 14041 7071 14042 7051 14042 7048 14042 7048 14043 7051 14043 7064 14043 7048 14044 7064 14044 7062 14044 7081 14045 7079 14045 7073 14045 7073 14046 7079 14046 7077 14046 7073 14047 7077 14047 7071 14047 7071 14048 7077 14048 7050 14048 7071 14049 7050 14049 7051 14049 7075 14050 7049 14050 7050 14050 7050 14051 7049 14051 1782 14051 7050 14052 1782 14052 7051 14052 7051 14053 1782 14053 1787 14053 7051 14054 1787 14054 7065 14054 7052 14055 7053 14055 7054 14055 7054 14056 7053 14056 7066 14056 7054 14057 7066 14057 7060 14057 7055 14058 7070 14058 7056 14058 7056 14059 7070 14059 7068 14059 7056 14060 7068 14060 7067 14060 7074 14061 7046 14061 7057 14061 7057 14062 7046 14062 7056 14062 7057 14063 7056 14063 7058 14063 7058 14064 7056 14064 7067 14064 7058 14065 7067 14065 7059 14065 7066 14066 7061 14066 7060 14066 7060 14067 7061 14067 7069 14067 7060 14068 7069 14068 7023 14068 7023 14069 7069 14069 7062 14069 7023 14070 7062 14070 7022 14070 7022 14071 7062 14071 7064 14071 7022 14072 7064 14072 7063 14072 7063 14073 7064 14073 7065 14073 7053 14074 7059 14074 7066 14074 7066 14075 7059 14075 7067 14075 7066 14076 7067 14076 7061 14076 7061 14077 7067 14077 7068 14077 7061 14078 7068 14078 7069 14078 7069 14079 7068 14079 7070 14079 7069 14080 7070 14080 7062 14080 7062 14081 7070 14081 7047 14081 7062 14082 7047 14082 7048 14082 7048 14083 7047 14083 7055 14083 7048 14084 7055 14084 7071 14084 7071 14085 7055 14085 7072 14085 7071 14086 7072 14086 7073 14086 7073 14087 7072 14087 7043 14087 7073 14088 7043 14088 7081 14088 7081 14089 7043 14089 7045 14089 7081 14090 7045 14090 4835 14090 4835 14091 7045 14091 7074 14091 1775 14092 7075 14092 7088 14092 7088 14093 7075 14093 7076 14093 7088 14094 7076 14094 7090 14094 7090 14095 7076 14095 7091 14095 7091 14096 7076 14096 7092 14096 7092 14097 7076 14097 7077 14097 7092 14098 7077 14098 7078 14098 7077 14099 7079 14099 7078 14099 7078 14100 7079 14100 7081 14100 7078 14101 7081 14101 7080 14101 7080 14102 7081 14102 7085 14102 7085 14103 7081 14103 7082 14103 7085 14104 7082 14104 7087 14104 7083 14105 1775 14105 7088 14105 7084 14106 7094 14106 7086 14106 7086 14107 7094 14107 7085 14107 7086 14108 7085 14108 7087 14108 4880 14109 7083 14109 7106 14109 7106 14110 7083 14110 7088 14110 7106 14111 7088 14111 7090 14111 7106 14112 7090 14112 7089 14112 7089 14113 7090 14113 7091 14113 7089 14114 7091 14114 7093 14114 7093 14115 7091 14115 7092 14115 7093 14116 7092 14116 7078 14116 7093 14117 7078 14117 7097 14117 7097 14118 7078 14118 7094 14118 7094 14119 7078 14119 7080 14119 7094 14120 7080 14120 7085 14120 7103 14121 7110 14121 7105 14121 7093 14122 7098 14122 7089 14122 7089 14123 7098 14123 7106 14123 7106 14124 7098 14124 7104 14124 7084 14125 7095 14125 7094 14125 7094 14126 7095 14126 7096 14126 7094 14127 7096 14127 7097 14127 7097 14128 7096 14128 7099 14128 7097 14129 7099 14129 7093 14129 7093 14130 7099 14130 7101 14130 7093 14131 7101 14131 7098 14131 7098 14132 7101 14132 7102 14132 7098 14133 7102 14133 7104 14133 7095 14134 1694 14134 7096 14134 7096 14135 1694 14135 7112 14135 7096 14136 7112 14136 7099 14136 7099 14137 7112 14137 7100 14137 7099 14138 7100 14138 7101 14138 7101 14139 7100 14139 7103 14139 7101 14140 7103 14140 7102 14140 7102 14141 7103 14141 7105 14141 7102 14142 7105 14142 7104 14142 7104 14143 7105 14143 4937 14143 7104 14144 4937 14144 7106 14144 7106 14145 4937 14145 4880 14145 7112 14146 1694 14146 7107 14146 7108 14147 7109 14147 7110 14147 7107 14148 7111 14148 7112 14148 7112 14149 7111 14149 7113 14149 7112 14150 7113 14150 7100 14150 7100 14151 7113 14151 7108 14151 7100 14152 7108 14152 7103 14152 7103 14153 7108 14153 7110 14153 1803 14154 1805 14154 7130 14154 1803 14155 7130 14155 1551 14155 1551 14156 7130 14156 7114 14156 1551 14157 7114 14157 1476 14157 1476 14158 7114 14158 7123 14158 1476 14159 7123 14159 1690 14159 1690 14160 7123 14160 7124 14160 1690 14161 7124 14161 4841 14161 4822 14162 4839 14162 7133 14162 7133 14163 4839 14163 7116 14163 7133 14164 7116 14164 7115 14164 7115 14165 7116 14165 7118 14165 7121 14166 1813 14166 7120 14166 7120 14167 1813 14167 7132 14167 7120 14168 7132 14168 7118 14168 7118 14169 7132 14169 7131 14169 7118 14170 7131 14170 7115 14170 4839 14171 7117 14171 7116 14171 7116 14172 7117 14172 7125 14172 7116 14173 7125 14173 7118 14173 7118 14174 7125 14174 7119 14174 7118 14175 7119 14175 7120 14175 7120 14176 7119 14176 7129 14176 7120 14177 7129 14177 7121 14177 7121 14178 7129 14178 1806 14178 7127 14179 7126 14179 4841 14179 7130 14180 7122 14180 7114 14180 7114 14181 7122 14181 7128 14181 7114 14182 7128 14182 7123 14182 7123 14183 7128 14183 7127 14183 7123 14184 7127 14184 7124 14184 7124 14185 7127 14185 4841 14185 7117 14186 7126 14186 7125 14186 7125 14187 7126 14187 7127 14187 7125 14188 7127 14188 7119 14188 7119 14189 7127 14189 7128 14189 7119 14190 7128 14190 7129 14190 7129 14191 7128 14191 7122 14191 7129 14192 7122 14192 1806 14192 1806 14193 7122 14193 7130 14193 1806 14194 7130 14194 1805 14194 7133 14195 7115 14195 7141 14195 7131 14196 7132 14196 7139 14196 7132 14197 1813 14197 7134 14197 7131 14198 7139 14198 7115 14198 7133 14199 7141 14199 4822 14199 7132 14200 7134 14200 7139 14200 7139 14201 7134 14201 1812 14201 7139 14202 1812 14202 7140 14202 7140 14203 1812 14203 1811 14203 7140 14204 1811 14204 7135 14204 7135 14205 1811 14205 1809 14205 7135 14206 1809 14206 7142 14206 7142 14207 1809 14207 7136 14207 7142 14208 7136 14208 7143 14208 7143 14209 7136 14209 7137 14209 7143 14210 7137 14210 7144 14210 7137 14211 1808 14211 7144 14211 7144 14212 1808 14212 7138 14212 7144 14213 7138 14213 7145 14213 7115 14214 7139 14214 7141 14214 7141 14215 7139 14215 7140 14215 7141 14216 7140 14216 7147 14216 7147 14217 7140 14217 7135 14217 7147 14218 7135 14218 7149 14218 7149 14219 7135 14219 7142 14219 7149 14220 7142 14220 7150 14220 7150 14221 7142 14221 7143 14221 7150 14222 7143 14222 7152 14222 7152 14223 7143 14223 7144 14223 7152 14224 7144 14224 7153 14224 7153 14225 7144 14225 7145 14225 7153 14226 7145 14226 7159 14226 4822 14227 7141 14227 7146 14227 7146 14228 7141 14228 7147 14228 7146 14229 7147 14229 7148 14229 7148 14230 7147 14230 7149 14230 7148 14231 7149 14231 4820 14231 4820 14232 7149 14232 7150 14232 4820 14233 7150 14233 7151 14233 7151 14234 7150 14234 7152 14234 7151 14235 7152 14235 4818 14235 4818 14236 7152 14236 7153 14236 4818 14237 7153 14237 7154 14237 7154 14238 7153 14238 7159 14238 7154 14239 7159 14239 4816 14239 7157 14240 7155 14240 7156 14240 1808 14241 7157 14241 7138 14241 7138 14242 7157 14242 7156 14242 7138 14243 7156 14243 7145 14243 7145 14244 7156 14244 7158 14244 7145 14245 7158 14245 7159 14245 7159 14246 7158 14246 7160 14246 7159 14247 7160 14247 4816 14247 4816 14248 7160 14248 7161 14248 7168 14249 7158 14249 7156 14249 7177 14250 5144 14250 7162 14250 7162 14251 5144 14251 7185 14251 7162 14252 7185 14252 7176 14252 7176 14253 7185 14253 7181 14253 7176 14254 7181 14254 7191 14254 7163 14255 7178 14255 7169 14255 7169 14256 7178 14256 7164 14256 7169 14257 7164 14257 7175 14257 7165 14258 7172 14258 7174 14258 7174 14259 7172 14259 7167 14259 7167 14260 4850 14260 7174 14260 7174 14261 4850 14261 7161 14261 7174 14262 7161 14262 7160 14262 4851 14263 7166 14263 7172 14263 7172 14264 7166 14264 4854 14264 7172 14265 4854 14265 7167 14265 7175 14266 7168 14266 7169 14266 7169 14267 7168 14267 7156 14267 7169 14268 7156 14268 7163 14268 7163 14269 7156 14269 7155 14269 7170 14270 4851 14270 7171 14270 7171 14271 4851 14271 7172 14271 7171 14272 7172 14272 7173 14272 7173 14273 7172 14273 7165 14273 7173 14274 7165 14274 7175 14274 7175 14275 7165 14275 7174 14275 7175 14276 7174 14276 7168 14276 7168 14277 7174 14277 7160 14277 7168 14278 7160 14278 7158 14278 1713 14279 7170 14279 7192 14279 7192 14280 7170 14280 7171 14280 7192 14281 7171 14281 7191 14281 7191 14282 7171 14282 7173 14282 7191 14283 7173 14283 7176 14283 7176 14284 7173 14284 7175 14284 7176 14285 7175 14285 7162 14285 7162 14286 7175 14286 7164 14286 7162 14287 7164 14287 7177 14287 7177 14288 7164 14288 7178 14288 7192 14289 7191 14289 7193 14289 7194 14290 7179 14290 7180 14290 7181 14291 7185 14291 7182 14291 7182 14292 7185 14292 7183 14292 7182 14293 7183 14293 7184 14293 7184 14294 7183 14294 7189 14294 7185 14295 5144 14295 7183 14295 7183 14296 5144 14296 5133 14296 7183 14297 5133 14297 7189 14297 7189 14298 5133 14298 7186 14298 7186 14299 7187 14299 7188 14299 7186 14300 7188 14300 7189 14300 7189 14301 7188 14301 7190 14301 7189 14302 7190 14302 7184 14302 7184 14303 7190 14303 7193 14303 7184 14304 7193 14304 7182 14304 7182 14305 7193 14305 7191 14305 7182 14306 7191 14306 7181 14306 1713 14307 7192 14307 7180 14307 7180 14308 7192 14308 7193 14308 7180 14309 7193 14309 7194 14309 7194 14310 7193 14310 7190 14310 7194 14311 7190 14311 7195 14311 7195 14312 7190 14312 7188 14312 7195 14313 7188 14313 7196 14313 7196 14314 7188 14314 7187 14314 7196 14315 7187 14315 7197 14315 7199 14316 3104 14316 7198 14316 7197 14317 7199 14317 7196 14317 7196 14318 7199 14318 7198 14318 7196 14319 7198 14319 7195 14319 7195 14320 7198 14320 7214 14320 7195 14321 7214 14321 7194 14321 7194 14322 7214 14322 7216 14322 7194 14323 7216 14323 7179 14323 7179 14324 7216 14324 1711 14324 7200 14325 7213 14325 7209 14325 7200 14326 7209 14326 1723 14326 7208 14327 7205 14327 7201 14327 7201 14328 7205 14328 7220 14328 7201 14329 7220 14329 1724 14329 1724 14330 7220 14330 1725 14330 3103 14331 7202 14331 7207 14331 7207 14332 7202 14332 7203 14332 7207 14333 7203 14333 7208 14333 7208 14334 7203 14334 7204 14334 7208 14335 7204 14335 7205 14335 7210 14336 3103 14336 7206 14336 7206 14337 3103 14337 7207 14337 7206 14338 7207 14338 7212 14338 7212 14339 7207 14339 7208 14339 7212 14340 7208 14340 7209 14340 7209 14341 7208 14341 7201 14341 7209 14342 7201 14342 1723 14342 1723 14343 7201 14343 1724 14343 3107 14344 7210 14344 7215 14344 7215 14345 7210 14345 7206 14345 7215 14346 7206 14346 7211 14346 7211 14347 7206 14347 7212 14347 7211 14348 7212 14348 7217 14348 7217 14349 7212 14349 7209 14349 7217 14350 7209 14350 1704 14350 1704 14351 7209 14351 7213 14351 3104 14352 3107 14352 7198 14352 7198 14353 3107 14353 7215 14353 7198 14354 7215 14354 7214 14354 7214 14355 7215 14355 7211 14355 7214 14356 7211 14356 7216 14356 7216 14357 7211 14357 7217 14357 7216 14358 7217 14358 1711 14358 1711 14359 7217 14359 1704 14359 1726 14360 1725 14360 7221 14360 7221 14361 1725 14361 7220 14361 7202 14362 7224 14362 7203 14362 7203 14363 7224 14363 7223 14363 7203 14364 7223 14364 7204 14364 7204 14365 7223 14365 7222 14365 7204 14366 7222 14366 7205 14366 7205 14367 7222 14367 7218 14367 7205 14368 7218 14368 7220 14368 7220 14369 7218 14369 7219 14369 7220 14370 7219 14370 7221 14370 1727 14371 1726 14371 7221 14371 1727 14372 7221 14372 7225 14372 7227 14373 7226 14373 7222 14373 7222 14374 7223 14374 7227 14374 7227 14375 7223 14375 7224 14375 7227 14376 7224 14376 7228 14376 7221 14377 7219 14377 7226 14377 7226 14378 7219 14378 7218 14378 7226 14379 7218 14379 7222 14379 7225 14380 7221 14380 7232 14380 7232 14381 7221 14381 7226 14381 7232 14382 7226 14382 7233 14382 7233 14383 7226 14383 7227 14383 7233 14384 7227 14384 7234 14384 7234 14385 7227 14385 7228 14385 7234 14386 7228 14386 7229 14386 7230 14387 7251 14387 7250 14387 7236 14388 7225 14388 7231 14388 7231 14389 7225 14389 7232 14389 7231 14390 7232 14390 7238 14390 7238 14391 7232 14391 7233 14391 7238 14392 7233 14392 7239 14392 7239 14393 7233 14393 7234 14393 7239 14394 7234 14394 7242 14394 7242 14395 7234 14395 7229 14395 7243 14396 7236 14396 7235 14396 7235 14397 7236 14397 7231 14397 7235 14398 7231 14398 7237 14398 7237 14399 7231 14399 7238 14399 7237 14400 7238 14400 7240 14400 7240 14401 7238 14401 7239 14401 7240 14402 7239 14402 7241 14402 7241 14403 7239 14403 7242 14403 7230 14404 7250 14404 4373 14404 7245 14405 7243 14405 7247 14405 7247 14406 7243 14406 7235 14406 7247 14407 7235 14407 7249 14407 7249 14408 7235 14408 7237 14408 7249 14409 7237 14409 7250 14409 7250 14410 7237 14410 7240 14410 7250 14411 7240 14411 4373 14411 4373 14412 7240 14412 7241 14412 7244 14413 7245 14413 7246 14413 7246 14414 7245 14414 7247 14414 7246 14415 7247 14415 7252 14415 7252 14416 7247 14416 7249 14416 7252 14417 7249 14417 7248 14417 7248 14418 7249 14418 7250 14418 7248 14419 7250 14419 7253 14419 7253 14420 7250 14420 7251 14420 7244 14421 7246 14421 2344 14421 2344 14422 7246 14422 7255 14422 7255 14423 7246 14423 7256 14423 7256 14424 7246 14424 7252 14424 7256 14425 7252 14425 7259 14425 7252 14426 7248 14426 7259 14426 7259 14427 7248 14427 7253 14427 7259 14428 7253 14428 2125 14428 7260 14429 2344 14429 7254 14429 7254 14430 2344 14430 7255 14430 7254 14431 7255 14431 7257 14431 7257 14432 7255 14432 7256 14432 7257 14433 7256 14433 7258 14433 7258 14434 7256 14434 7259 14434 7258 14435 7259 14435 7264 14435 7264 14436 7259 14436 2125 14436 2342 14437 7260 14437 7261 14437 7261 14438 7260 14438 7254 14438 7261 14439 7254 14439 7262 14439 7262 14440 7254 14440 7257 14440 7262 14441 7257 14441 7263 14441 7263 14442 7257 14442 7258 14442 7263 14443 7258 14443 2127 14443 2127 14444 7258 14444 7264 14444 2128 14445 2129 14445 7282 14445 7265 14446 2342 14446 7266 14446 7266 14447 2342 14447 7261 14447 7266 14448 7261 14448 7276 14448 7276 14449 7261 14449 7262 14449 7276 14450 7262 14450 7282 14450 7282 14451 7262 14451 7263 14451 7282 14452 7263 14452 2128 14452 2128 14453 7263 14453 2127 14453 7277 14454 7267 14454 7265 14454 7270 14455 7268 14455 7271 14455 7269 14456 7270 14456 7274 14456 7274 14457 7270 14457 7271 14457 7274 14458 7271 14458 7275 14458 7275 14459 7271 14459 7279 14459 7275 14460 7279 14460 7281 14460 7278 14461 7272 14461 7277 14461 7277 14462 7272 14462 7273 14462 7277 14463 7273 14463 7267 14463 2139 14464 7269 14464 2130 14464 2130 14465 7269 14465 7274 14465 2130 14466 7274 14466 2132 14466 2132 14467 7274 14467 7275 14467 2132 14468 7275 14468 2133 14468 2133 14469 7275 14469 7281 14469 2133 14470 7281 14470 2129 14470 7282 14471 7280 14471 7276 14471 7276 14472 7280 14472 7277 14472 7276 14473 7277 14473 7266 14473 7266 14474 7277 14474 7265 14474 7268 14475 7278 14475 7271 14475 7271 14476 7278 14476 7277 14476 7271 14477 7277 14477 7279 14477 7279 14478 7277 14478 7280 14478 7279 14479 7280 14479 7281 14479 7281 14480 7280 14480 7282 14480 7281 14481 7282 14481 2129 14481 7269 14482 2139 14482 7283 14482 7268 14483 7270 14483 7285 14483 7285 14484 7270 14484 7269 14484 7272 14485 7278 14485 7293 14485 7293 14486 7278 14486 7268 14486 7269 14487 7283 14487 7285 14487 7285 14488 7283 14488 7284 14488 7285 14489 7284 14489 7286 14489 7286 14490 7284 14490 7287 14490 7286 14491 7287 14491 7289 14491 7287 14492 7303 14492 7302 14492 7287 14493 7302 14493 7289 14493 7289 14494 7302 14494 7288 14494 7289 14495 7288 14495 7290 14495 7268 14496 7285 14496 7293 14496 7293 14497 7285 14497 7286 14497 7293 14498 7286 14498 7294 14498 7294 14499 7286 14499 7289 14499 7294 14500 7289 14500 7291 14500 7291 14501 7289 14501 7290 14501 7291 14502 7290 14502 7296 14502 7272 14503 7293 14503 7292 14503 7292 14504 7293 14504 7294 14504 7292 14505 7294 14505 2349 14505 2349 14506 7294 14506 7291 14506 2349 14507 7291 14507 7295 14507 7295 14508 7291 14508 7296 14508 7295 14509 7296 14509 2345 14509 7297 14510 7300 14510 7308 14510 7296 14511 7298 14511 2345 14511 2345 14512 7298 14512 7299 14512 2146 14513 7300 14513 2147 14513 2147 14514 7300 14514 7297 14514 2147 14515 7297 14515 2148 14515 7290 14516 7288 14516 7304 14516 7304 14517 7288 14517 7301 14517 7288 14518 7302 14518 7301 14518 7301 14519 7302 14519 7303 14519 7301 14520 7303 14520 2144 14520 7296 14521 7290 14521 7298 14521 7298 14522 7290 14522 7304 14522 7298 14523 7304 14523 7307 14523 7307 14524 7304 14524 7301 14524 7307 14525 7301 14525 7306 14525 7306 14526 7301 14526 2144 14526 7306 14527 2144 14527 7305 14527 7305 14528 2148 14528 7306 14528 7306 14529 2148 14529 7297 14529 7306 14530 7297 14530 7307 14530 7307 14531 7297 14531 7308 14531 7307 14532 7308 14532 7298 14532 7298 14533 7308 14533 7309 14533 7298 14534 7309 14534 7299 14534 7299 14535 7309 14535 2348 14535 2146 14536 7312 14536 7300 14536 7300 14537 7312 14537 7313 14537 7300 14538 7313 14538 7308 14538 7310 14539 7311 14539 7312 14539 7312 14540 7311 14540 7340 14540 7312 14541 7340 14541 7313 14541 2346 14542 2348 14542 7309 14542 2346 14543 7309 14543 1198 14543 7308 14544 7313 14544 7309 14544 7309 14545 7313 14545 7341 14545 7309 14546 7341 14546 1198 14546 7320 14547 7331 14547 7332 14547 7316 14548 7314 14548 2151 14548 1199 14549 1200 14549 7315 14549 7329 14550 7331 14550 7327 14550 7327 14551 7331 14551 7320 14551 7327 14552 7320 14552 7362 14552 2151 14553 7358 14553 7316 14553 7316 14554 7358 14554 7317 14554 7316 14555 7317 14555 7319 14555 7319 14556 7317 14556 7360 14556 7319 14557 7360 14557 7318 14557 1102 14558 7314 14558 7334 14558 7334 14559 7314 14559 7316 14559 7334 14560 7316 14560 7332 14560 7332 14561 7316 14561 7319 14561 7332 14562 7319 14562 7320 14562 7320 14563 7319 14563 7318 14563 7320 14564 7318 14564 7362 14564 7343 14565 7324 14565 7321 14565 7338 14566 1097 14566 7339 14566 7339 14567 1097 14567 7322 14567 7339 14568 7322 14568 7323 14568 7321 14569 7324 14569 7342 14569 7342 14570 7324 14570 7344 14570 7342 14571 7344 14571 1199 14571 1199 14572 7344 14572 7325 14572 1199 14573 7325 14573 1200 14573 7346 14574 7326 14574 7328 14574 7328 14575 7326 14575 7345 14575 7362 14576 7328 14576 7327 14576 7327 14577 7328 14577 7345 14577 7327 14578 7345 14578 7329 14578 7329 14579 7345 14579 7330 14579 7329 14580 7330 14580 7331 14580 7331 14581 7330 14581 7333 14581 7331 14582 7333 14582 7332 14582 7332 14583 7333 14583 7335 14583 7332 14584 7335 14584 7334 14584 7334 14585 7335 14585 7336 14585 7334 14586 7336 14586 1102 14586 1102 14587 7336 14587 7337 14587 7310 14588 7338 14588 7311 14588 7311 14589 7338 14589 7339 14589 7311 14590 7339 14590 7340 14590 7340 14591 7339 14591 7323 14591 7340 14592 7323 14592 7313 14592 7322 14593 7343 14593 7323 14593 7323 14594 7343 14594 7321 14594 7323 14595 7321 14595 7313 14595 7313 14596 7321 14596 7342 14596 7313 14597 7342 14597 7341 14597 7341 14598 7342 14598 1199 14598 7341 14599 1199 14599 1198 14599 1097 14600 7337 14600 7322 14600 7322 14601 7337 14601 7336 14601 7322 14602 7336 14602 7343 14602 7343 14603 7336 14603 7335 14603 7343 14604 7335 14604 7324 14604 7324 14605 7335 14605 7333 14605 7324 14606 7333 14606 7344 14606 7344 14607 7333 14607 7330 14607 7344 14608 7330 14608 7325 14608 7325 14609 7330 14609 7345 14609 7325 14610 7345 14610 1200 14610 1200 14611 7345 14611 7326 14611 1200 14612 7326 14612 1189 14612 1189 14613 7326 14613 7346 14613 1189 14614 7346 14614 1190 14614 7347 14615 7348 14615 7346 14615 7346 14616 7348 14616 1190 14616 7347 14617 7363 14617 7349 14617 7349 14618 7363 14618 7361 14618 7349 14619 7361 14619 7352 14619 7352 14620 7361 14620 7359 14620 7357 14621 2149 14621 7350 14621 7350 14622 2149 14622 7351 14622 7350 14623 7351 14623 7359 14623 7359 14624 7351 14624 7366 14624 7359 14625 7366 14625 7352 14625 2150 14626 2156 14626 7364 14626 7364 14627 2156 14627 7373 14627 7364 14628 7373 14628 7365 14628 7365 14629 7373 14629 7353 14629 7365 14630 7353 14630 7354 14630 7354 14631 7353 14631 7371 14631 7354 14632 7371 14632 7355 14632 7355 14633 7371 14633 7370 14633 7355 14634 7370 14634 7356 14634 7356 14635 7370 14635 7367 14635 7356 14636 7367 14636 1191 14636 2151 14637 7357 14637 7358 14637 7358 14638 7357 14638 7350 14638 7358 14639 7350 14639 7317 14639 7317 14640 7350 14640 7359 14640 7317 14641 7359 14641 7360 14641 7360 14642 7359 14642 7361 14642 7360 14643 7361 14643 7318 14643 7318 14644 7361 14644 7363 14644 7318 14645 7363 14645 7362 14645 7362 14646 7363 14646 7347 14646 7362 14647 7347 14647 7328 14647 7328 14648 7347 14648 7346 14648 2149 14649 2150 14649 7351 14649 7351 14650 2150 14650 7364 14650 7351 14651 7364 14651 7366 14651 7366 14652 7364 14652 7365 14652 7366 14653 7365 14653 7352 14653 7352 14654 7365 14654 7354 14654 7352 14655 7354 14655 7349 14655 7349 14656 7354 14656 7355 14656 7349 14657 7355 14657 7347 14657 7347 14658 7355 14658 7356 14658 7347 14659 7356 14659 7348 14659 7348 14660 7356 14660 1191 14660 7348 14661 1191 14661 1190 14661 1192 14662 7367 14662 7368 14662 7368 14663 7367 14663 7370 14663 7368 14664 7370 14664 7369 14664 7369 14665 7370 14665 7371 14665 7369 14666 7371 14666 7372 14666 7372 14667 7371 14667 7353 14667 7372 14668 7353 14668 2158 14668 2158 14669 7353 14669 7373 14669 2158 14670 7373 14670 2156 14670 7374 14671 7388 14671 7384 14671 7384 14672 7388 14672 7375 14672 7384 14673 7375 14673 7376 14673 7376 14674 7375 14674 7377 14674 7376 14675 7377 14675 7378 14675 7390 14676 7386 14676 7379 14676 7379 14677 7386 14677 7380 14677 7381 14678 7382 14678 7378 14678 7378 14679 7382 14679 2159 14679 7378 14680 2159 14680 7376 14680 7376 14681 2159 14681 2161 14681 7376 14682 2161 14682 7384 14682 7384 14683 2161 14683 7383 14683 7384 14684 7383 14684 7374 14684 7374 14685 7383 14685 7385 14685 7386 14686 1192 14686 7380 14686 7380 14687 1192 14687 7368 14687 7380 14688 7368 14688 7387 14688 7387 14689 7368 14689 7369 14689 7387 14690 7369 14690 7372 14690 7388 14691 7379 14691 7375 14691 7375 14692 7379 14692 7380 14692 7375 14693 7380 14693 7377 14693 7377 14694 7380 14694 7387 14694 7377 14695 7387 14695 7378 14695 7378 14696 7387 14696 7372 14696 7378 14697 7372 14697 7381 14697 7381 14698 7372 14698 2158 14698 7385 14699 2162 14699 7374 14699 7374 14700 2162 14700 7389 14700 7374 14701 7389 14701 7388 14701 7388 14702 7389 14702 7391 14702 7388 14703 7391 14703 7379 14703 7379 14704 7391 14704 7390 14704 7390 14705 7391 14705 1193 14705 7391 14706 7389 14706 7392 14706 1194 14707 1193 14707 7391 14707 1194 14708 7391 14708 1195 14708 1195 14709 7391 14709 7394 14709 7394 14710 7391 14710 7392 14710 7389 14711 2162 14711 7392 14711 7392 14712 2162 14712 2164 14712 7392 14713 2164 14713 7394 14713 7394 14714 2164 14714 2165 14714 2165 14715 2167 14715 7403 14715 2165 14716 7403 14716 7394 14716 7394 14717 7403 14717 7393 14717 7394 14718 7393 14718 1196 14718 7394 14719 1196 14719 1195 14719 7418 14720 7417 14720 7406 14720 7406 14721 7417 14721 7415 14721 7406 14722 7415 14722 7395 14722 7418 14723 7396 14723 7419 14723 7411 14724 7404 14724 4659 14724 7402 14725 7401 14725 7397 14725 7397 14726 7401 14726 7416 14726 7397 14727 7416 14727 7398 14727 7398 14728 7416 14728 7399 14728 7398 14729 7399 14729 7425 14729 7425 14730 7399 14730 4663 14730 7425 14731 4663 14731 4662 14731 7413 14732 7414 14732 7400 14732 7400 14733 7414 14733 7401 14733 7400 14734 7401 14734 1188 14734 1188 14735 7401 14735 7402 14735 7403 14736 2167 14736 4660 14736 7404 14737 7411 14737 4660 14737 7396 14738 7418 14738 7405 14738 7405 14739 7418 14739 7406 14739 7405 14740 7406 14740 7407 14740 7407 14741 7406 14741 7395 14741 7407 14742 7395 14742 7408 14742 7413 14743 7410 14743 7409 14743 7409 14744 7410 14744 7412 14744 7409 14745 7412 14745 7415 14745 7415 14746 7412 14746 7411 14746 7415 14747 7411 14747 7395 14747 7395 14748 7411 14748 4659 14748 7395 14749 4659 14749 7408 14749 4660 14750 7411 14750 7403 14750 7403 14751 7411 14751 7412 14751 7403 14752 7412 14752 7393 14752 7393 14753 7412 14753 7410 14753 7393 14754 7410 14754 1196 14754 7413 14755 7409 14755 7414 14755 7414 14756 7409 14756 7415 14756 7414 14757 7415 14757 7401 14757 7401 14758 7415 14758 7417 14758 7401 14759 7417 14759 7416 14759 7416 14760 7417 14760 7418 14760 7416 14761 7418 14761 7399 14761 7399 14762 7418 14762 7419 14762 7399 14763 7419 14763 4663 14763 1177 14764 1185 14764 7421 14764 7420 14765 1177 14765 7422 14765 7422 14766 1177 14766 7421 14766 7422 14767 7421 14767 7452 14767 7452 14768 7421 14768 7423 14768 7452 14769 7423 14769 7450 14769 7450 14770 7423 14770 7426 14770 7450 14771 7426 14771 7449 14771 7449 14772 7426 14772 7463 14772 7463 14773 7426 14773 7427 14773 7463 14774 7427 14774 7424 14774 1185 14775 7402 14775 7421 14775 7421 14776 7402 14776 7397 14776 7421 14777 7397 14777 7423 14777 7423 14778 7397 14778 7398 14778 7423 14779 7398 14779 7426 14779 7426 14780 7398 14780 7425 14780 7426 14781 7425 14781 7427 14781 7427 14782 7425 14782 4662 14782 7451 14783 7461 14783 7460 14783 1173 14784 1171 14784 7443 14784 7454 14785 7428 14785 1169 14785 1169 14786 7428 14786 7456 14786 1169 14787 7456 14787 7455 14787 7431 14788 7429 14788 7430 14788 7430 14789 7429 14789 7432 14789 7468 14790 7431 14790 7470 14790 7470 14791 7431 14791 7430 14791 7470 14792 7430 14792 7433 14792 7433 14793 7430 14793 7432 14793 7433 14794 7432 14794 7434 14794 7435 14795 7470 14795 7436 14795 7436 14796 7470 14796 7433 14796 7436 14797 7433 14797 7437 14797 7437 14798 7433 14798 7434 14798 7437 14799 7434 14799 7438 14799 7458 14800 7439 14800 7441 14800 7441 14801 7439 14801 7428 14801 7428 14802 7439 14802 7440 14802 7428 14803 7440 14803 7456 14803 7460 14804 7458 14804 7451 14804 7451 14805 7458 14805 7441 14805 7451 14806 7441 14806 7442 14806 7442 14807 7441 14807 7428 14807 7442 14808 7428 14808 7453 14808 7453 14809 7428 14809 7454 14809 1175 14810 1173 14810 7465 14810 7465 14811 1173 14811 7443 14811 7465 14812 7443 14812 7467 14812 7467 14813 7443 14813 7447 14813 4657 14814 7462 14814 7445 14814 7445 14815 7462 14815 7444 14815 7445 14816 7444 14816 7446 14816 7446 14817 7444 14817 7463 14817 7446 14818 7463 14818 7424 14818 7468 14819 7467 14819 7431 14819 7431 14820 7467 14820 7447 14820 7431 14821 7447 14821 7429 14821 7429 14822 7447 14822 7457 14822 7429 14823 7457 14823 7432 14823 7432 14824 7457 14824 7448 14824 7432 14825 7448 14825 7434 14825 7434 14826 7448 14826 7459 14826 7434 14827 7459 14827 7438 14827 7438 14828 7459 14828 7462 14828 7438 14829 7462 14829 4656 14829 4656 14830 7462 14830 4657 14830 7449 14831 7461 14831 7450 14831 7450 14832 7461 14832 7451 14832 7450 14833 7451 14833 7452 14833 7452 14834 7451 14834 7442 14834 7452 14835 7442 14835 7422 14835 7422 14836 7442 14836 7453 14836 7422 14837 7453 14837 7420 14837 7420 14838 7453 14838 7454 14838 1171 14839 7455 14839 7443 14839 7443 14840 7455 14840 7456 14840 7443 14841 7456 14841 7447 14841 7447 14842 7456 14842 7440 14842 7447 14843 7440 14843 7457 14843 7457 14844 7440 14844 7439 14844 7457 14845 7439 14845 7448 14845 7448 14846 7439 14846 7458 14846 7448 14847 7458 14847 7459 14847 7459 14848 7458 14848 7460 14848 7459 14849 7460 14849 7462 14849 7462 14850 7460 14850 7461 14850 7462 14851 7461 14851 7444 14851 7444 14852 7461 14852 7449 14852 7444 14853 7449 14853 7463 14853 7464 14854 1175 14854 7465 14854 7464 14855 7465 14855 7466 14855 7466 14856 7465 14856 7467 14856 7466 14857 7467 14857 7469 14857 7467 14858 7468 14858 7469 14858 7469 14859 7468 14859 7470 14859 7469 14860 7470 14860 7471 14860 7471 14861 7470 14861 7435 14861 7471 14862 7435 14862 2168 14862 7484 14863 7486 14863 7472 14863 7472 14864 7486 14864 7476 14864 7472 14865 7476 14865 7489 14865 7481 14866 7473 14866 7474 14866 2173 14867 7489 14867 7475 14867 7475 14868 7489 14868 7476 14868 7475 14869 7476 14869 7478 14869 7478 14870 7476 14870 7477 14870 7478 14871 7477 14871 2170 14871 2170 14872 7477 14872 7479 14872 2170 14873 7479 14873 2168 14873 7471 14874 7473 14874 7469 14874 7469 14875 7473 14875 7481 14875 7469 14876 7481 14876 7466 14876 7483 14877 7464 14877 7480 14877 7480 14878 7464 14878 7466 14878 7480 14879 7466 14879 7485 14879 7485 14880 7466 14880 7481 14880 7485 14881 7481 14881 7487 14881 7487 14882 7481 14882 7474 14882 1176 14883 7483 14883 7482 14883 7482 14884 7483 14884 7480 14884 7482 14885 7480 14885 7484 14885 7484 14886 7480 14886 7485 14886 7484 14887 7485 14887 7486 14887 7486 14888 7485 14888 7487 14888 7486 14889 7487 14889 7476 14889 7476 14890 7487 14890 7474 14890 7476 14891 7474 14891 7477 14891 7477 14892 7474 14892 7473 14892 7477 14893 7473 14893 7479 14893 7479 14894 7473 14894 7471 14894 7479 14895 7471 14895 2168 14895 7488 14896 1174 14896 1176 14896 1176 14897 7482 14897 7488 14897 7488 14898 7482 14898 7484 14898 7488 14899 7484 14899 7508 14899 7508 14900 7484 14900 7472 14900 7508 14901 7472 14901 7490 14901 7490 14902 7472 14902 7489 14902 7490 14903 7489 14903 7491 14903 7491 14904 7489 14904 7492 14904 7492 14905 7489 14905 2173 14905 7492 14906 2173 14906 7493 14906 7494 14907 1174 14907 7506 14907 7506 14908 1174 14908 7488 14908 7506 14909 7488 14909 7508 14909 7514 14910 7517 14910 7497 14910 2177 14911 2181 14911 7495 14911 7495 14912 2181 14912 7496 14912 7495 14913 7496 14913 7503 14913 7497 14914 7505 14914 7514 14914 7514 14915 7505 14915 7498 14915 7514 14916 7498 14916 7499 14916 7499 14917 7498 14917 7500 14917 7499 14918 7500 14918 7512 14918 7512 14919 7500 14919 7507 14919 7512 14920 7507 14920 7501 14920 7501 14921 7507 14921 7509 14921 7501 14922 7509 14922 7511 14922 7511 14923 7509 14923 7510 14923 7510 14924 7502 14924 7511 14924 7511 14925 7502 14925 2175 14925 7511 14926 2175 14926 2176 14926 7503 14927 7496 14927 7504 14927 7504 14928 7496 14928 7522 14928 7504 14929 7522 14929 7513 14929 7513 14930 7522 14930 7519 14930 7513 14931 7519 14931 7515 14931 7505 14932 7494 14932 7498 14932 7498 14933 7494 14933 7506 14933 7498 14934 7506 14934 7500 14934 7500 14935 7506 14935 7508 14935 7500 14936 7508 14936 7507 14936 7507 14937 7508 14937 7490 14937 7507 14938 7490 14938 7509 14938 7509 14939 7490 14939 7491 14939 7509 14940 7491 14940 7510 14940 7510 14941 7491 14941 7492 14941 7510 14942 7492 14942 7502 14942 7502 14943 7492 14943 7493 14943 2176 14944 2177 14944 7511 14944 7511 14945 2177 14945 7495 14945 7511 14946 7495 14946 7501 14946 7501 14947 7495 14947 7503 14947 7501 14948 7503 14948 7512 14948 7512 14949 7503 14949 7504 14949 7512 14950 7504 14950 7499 14950 7499 14951 7504 14951 7513 14951 7499 14952 7513 14952 7514 14952 7514 14953 7513 14953 7515 14953 7514 14954 7515 14954 7517 14954 7515 14955 7516 14955 7517 14955 7517 14956 7516 14956 7497 14956 7522 14957 7521 14957 7518 14957 7529 14958 7516 14958 7530 14958 7530 14959 7516 14959 7515 14959 7530 14960 7515 14960 7518 14960 7518 14961 7515 14961 7519 14961 7518 14962 7519 14962 7522 14962 2181 14963 7528 14963 7520 14963 7521 14964 7522 14964 7520 14964 7520 14965 7522 14965 7496 14965 7520 14966 7496 14966 2181 14966 7525 14967 7520 14967 7528 14967 7520 14968 7525 14968 7521 14968 1166 14969 1165 14969 7533 14969 1166 14970 7533 14970 1164 14970 7523 14971 7532 14971 7525 14971 7525 14972 7532 14972 7524 14972 7525 14973 7524 14973 7521 14973 7531 14974 7523 14974 7526 14974 7526 14975 7523 14975 7525 14975 7526 14976 7525 14976 7527 14976 7527 14977 7525 14977 7528 14977 7531 14978 7537 14978 7536 14978 1165 14979 7529 14979 7533 14979 7533 14980 7529 14980 7530 14980 7533 14981 7530 14981 7518 14981 7531 14982 7536 14982 7523 14982 7523 14983 7536 14983 7534 14983 7523 14984 7534 14984 7532 14984 7532 14985 7534 14985 7533 14985 7532 14986 7533 14986 7524 14986 7524 14987 7533 14987 7518 14987 7524 14988 7518 14988 7521 14988 1164 14989 7533 14989 7540 14989 7540 14990 7533 14990 7534 14990 7540 14991 7534 14991 7539 14991 7539 14992 7534 14992 7536 14992 7539 14993 7536 14993 7535 14993 7535 14994 7536 14994 7537 14994 7535 14995 7537 14995 2186 14995 2186 14996 7548 14996 7535 14996 7535 14997 7548 14997 7538 14997 7535 14998 7538 14998 7539 14998 7539 14999 7538 14999 7546 14999 7539 15000 7546 15000 7540 15000 7540 15001 7546 15001 7541 15001 7540 15002 7541 15002 1164 15002 1164 15003 7541 15003 1158 15003 7547 15004 7552 15004 7545 15004 7544 15005 1158 15005 7541 15005 7550 15006 7552 15006 7542 15006 7542 15007 7552 15007 7547 15007 7542 15008 7547 15008 7548 15008 7543 15009 7544 15009 7556 15009 7556 15010 7544 15010 7541 15010 7556 15011 7541 15011 7545 15011 7545 15012 7541 15012 7546 15012 7545 15013 7546 15013 7547 15013 7547 15014 7546 15014 7538 15014 7547 15015 7538 15015 7548 15015 7550 15016 7549 15016 7564 15016 7550 15017 7564 15017 7552 15017 7552 15018 7564 15018 7551 15018 7552 15019 7551 15019 7545 15019 7545 15020 7551 15020 7553 15020 7545 15021 7553 15021 7556 15021 7553 15022 7554 15022 7556 15022 7556 15023 7554 15023 7555 15023 7556 15024 7555 15024 7543 15024 1284 15025 1159 15025 1161 15025 7573 15026 7557 15026 1280 15026 1280 15027 7557 15027 7558 15027 7558 15028 7557 15028 2188 15028 7558 15029 2188 15029 1149 15029 7566 15030 7559 15030 7570 15030 7570 15031 7559 15031 7560 15031 7570 15032 7560 15032 7561 15032 7561 15033 7560 15033 7562 15033 7561 15034 7562 15034 7569 15034 1280 15035 1282 15035 7573 15035 7573 15036 1282 15036 1284 15036 7573 15037 1284 15037 7572 15037 7572 15038 1284 15038 1161 15038 7572 15039 1161 15039 7571 15039 7571 15040 1161 15040 7563 15040 7571 15041 7563 15041 1163 15041 7565 15042 2195 15042 7559 15042 7559 15043 2195 15043 2194 15043 7559 15044 2194 15044 7560 15044 7549 15045 7565 15045 7564 15045 7564 15046 7565 15046 7559 15046 7564 15047 7559 15047 7551 15047 7551 15048 7559 15048 7566 15048 7551 15049 7566 15049 7553 15049 2194 15050 7567 15050 7560 15050 7560 15051 7567 15051 7568 15051 7560 15052 7568 15052 7562 15052 7562 15053 7568 15053 2192 15053 7562 15054 2192 15054 7569 15054 7553 15055 7571 15055 7554 15055 7554 15056 7571 15056 1163 15056 7554 15057 1163 15057 7555 15057 7553 15058 7566 15058 7571 15058 7571 15059 7566 15059 7570 15059 7571 15060 7570 15060 7572 15060 7572 15061 7570 15061 7561 15061 7572 15062 7561 15062 7573 15062 7573 15063 7561 15063 7569 15063 7573 15064 7569 15064 7557 15064 7557 15065 7569 15065 2192 15065 7557 15066 2192 15066 2188 15066 7602 15067 7581 15067 7603 15067 7593 15068 7575 15068 7577 15068 7602 15069 7601 15069 7581 15069 7581 15070 7601 15070 7574 15070 7581 15071 7574 15071 7583 15071 7584 15072 7702 15072 7599 15072 4655 15073 7701 15073 7575 15073 7575 15074 7701 15074 7576 15074 7575 15075 7576 15075 7577 15075 7578 15076 4650 15076 7587 15076 7587 15077 4650 15077 4651 15077 7587 15078 4651 15078 7594 15078 7604 15079 7579 15079 7580 15079 7580 15080 7579 15080 7603 15080 7580 15081 7603 15081 7598 15081 7598 15082 7603 15082 7581 15082 7598 15083 7581 15083 7582 15083 7582 15084 7581 15084 7583 15084 7599 15085 7600 15085 7584 15085 7584 15086 7600 15086 7592 15086 7584 15087 7592 15087 7591 15087 7588 15088 1274 15088 7585 15088 7585 15089 1274 15089 1272 15089 7585 15090 1272 15090 7586 15090 7586 15091 7578 15091 7585 15091 7585 15092 7578 15092 7587 15092 7585 15093 7587 15093 7588 15093 7588 15094 7587 15094 7594 15094 7588 15095 7594 15095 7589 15095 7589 15096 7594 15096 7590 15096 7701 15097 7591 15097 7576 15097 7576 15098 7591 15098 7592 15098 7576 15099 7592 15099 7577 15099 7577 15100 7592 15100 7590 15100 7577 15101 7590 15101 7593 15101 7593 15102 7590 15102 7594 15102 7593 15103 7594 15103 4652 15103 4652 15104 7594 15104 4651 15104 1275 15105 7604 15105 7595 15105 7595 15106 7604 15106 7580 15106 7595 15107 7580 15107 7596 15107 7596 15108 7580 15108 7598 15108 7596 15109 7598 15109 7597 15109 7597 15110 7598 15110 7582 15110 7599 15111 7601 15111 7600 15111 7600 15112 7601 15112 7602 15112 7600 15113 7602 15113 7592 15113 7592 15114 7602 15114 7603 15114 7592 15115 7603 15115 7590 15115 7590 15116 7603 15116 7579 15116 7590 15117 7579 15117 7589 15117 7589 15118 7579 15118 7604 15118 7589 15119 7604 15119 7588 15119 7588 15120 7604 15120 1275 15120 7588 15121 1275 15121 1274 15121 7691 15122 7690 15122 7605 15122 7694 15123 1180 15123 7606 15123 7607 15124 7682 15124 7683 15124 7608 15125 7712 15125 7660 15125 7609 15126 7731 15126 1228 15126 7725 15127 7609 15127 7640 15127 7712 15128 7725 15128 7658 15128 7661 15129 1685 15129 7660 15129 7660 15130 1685 15130 7610 15130 7660 15131 7610 15131 7608 15131 7609 15132 1228 15132 7640 15132 7640 15133 1228 15133 1227 15133 7640 15134 1227 15134 7641 15134 7641 15135 1227 15135 1223 15135 7641 15136 1223 15136 7642 15136 7663 15137 7614 15137 7661 15137 7661 15138 7614 15138 1680 15138 7661 15139 1680 15139 1685 15139 7611 15140 7612 15140 7664 15140 7664 15141 7612 15141 7613 15141 7664 15142 7613 15142 7663 15142 7663 15143 7613 15143 1679 15143 7663 15144 1679 15144 7614 15144 7620 15145 7616 15145 7615 15145 7615 15146 7616 15146 1657 15146 7615 15147 1657 15147 7665 15147 7665 15148 1657 15148 7617 15148 7665 15149 7617 15149 7611 15149 7611 15150 7617 15150 7618 15150 7611 15151 7618 15151 7612 15151 1661 15152 7619 15152 7620 15152 7620 15153 7619 15153 1659 15153 7620 15154 1659 15154 7616 15154 1223 15155 7621 15155 7642 15155 7642 15156 7621 15156 7622 15156 7642 15157 7622 15157 7643 15157 7643 15158 7622 15158 1225 15158 7643 15159 1225 15159 7645 15159 7645 15160 1225 15160 7623 15160 7645 15161 7623 15161 7648 15161 7648 15162 7623 15162 7624 15162 7648 15163 7624 15163 7649 15163 7649 15164 7624 15164 7625 15164 7649 15165 7625 15165 7651 15165 7651 15166 7625 15166 7626 15166 7651 15167 7626 15167 7627 15167 7627 15168 7626 15168 7633 15168 7627 15169 7633 15169 7652 15169 7620 15170 7628 15170 1661 15170 1661 15171 7628 15171 7668 15171 1661 15172 7668 15172 1662 15172 1662 15173 7668 15173 7629 15173 1662 15174 7629 15174 1664 15174 1664 15175 7629 15175 7631 15175 1664 15176 7631 15176 7630 15176 7630 15177 7631 15177 7632 15177 7633 15178 7634 15178 7652 15178 7652 15179 7634 15179 1214 15179 7652 15180 1214 15180 7635 15180 7635 15181 1214 15181 1211 15181 7635 15182 1211 15182 7636 15182 7636 15183 1211 15183 7637 15183 7636 15184 7637 15184 7655 15184 7655 15185 7637 15185 1209 15185 7655 15186 1209 15186 7657 15186 7657 15187 1209 15187 1208 15187 7657 15188 1208 15188 7638 15188 7638 15189 1208 15189 7639 15189 7638 15190 7639 15190 7681 15190 7725 15191 7640 15191 7658 15191 7658 15192 7640 15192 7641 15192 7658 15193 7641 15193 7659 15193 7659 15194 7641 15194 7642 15194 7659 15195 7642 15195 7662 15195 7662 15196 7642 15196 7643 15196 7662 15197 7643 15197 7644 15197 7644 15198 7643 15198 7645 15198 7644 15199 7645 15199 7646 15199 7646 15200 7645 15200 7648 15200 7646 15201 7648 15201 7647 15201 7647 15202 7648 15202 7649 15202 7647 15203 7649 15203 7666 15203 7666 15204 7649 15204 7651 15204 7666 15205 7651 15205 7650 15205 7650 15206 7651 15206 7627 15206 7650 15207 7627 15207 7667 15207 7667 15208 7627 15208 7652 15208 7667 15209 7652 15209 7653 15209 7653 15210 7652 15210 7635 15210 7653 15211 7635 15211 7669 15211 7669 15212 7635 15212 7636 15212 7669 15213 7636 15213 7654 15213 7654 15214 7636 15214 7655 15214 7654 15215 7655 15215 7656 15215 7656 15216 7655 15216 7657 15216 7656 15217 7657 15217 7670 15217 7670 15218 7657 15218 7638 15218 7670 15219 7638 15219 7671 15219 7671 15220 7638 15220 7681 15220 7671 15221 7681 15221 7672 15221 7712 15222 7658 15222 7660 15222 7660 15223 7658 15223 7659 15223 7660 15224 7659 15224 7661 15224 7661 15225 7659 15225 7662 15225 7661 15226 7662 15226 7663 15226 7663 15227 7662 15227 7644 15227 7663 15228 7644 15228 7664 15228 7664 15229 7644 15229 7646 15229 7664 15230 7646 15230 7611 15230 7611 15231 7646 15231 7647 15231 7611 15232 7647 15232 7665 15232 7665 15233 7647 15233 7666 15233 7665 15234 7666 15234 7615 15234 7615 15235 7666 15235 7650 15235 7615 15236 7650 15236 7620 15236 7620 15237 7650 15237 7667 15237 7620 15238 7667 15238 7628 15238 7628 15239 7667 15239 7653 15239 7628 15240 7653 15240 7668 15240 7668 15241 7653 15241 7669 15241 7668 15242 7669 15242 7629 15242 7629 15243 7669 15243 7654 15243 7629 15244 7654 15244 7631 15244 7631 15245 7654 15245 7656 15245 7631 15246 7656 15246 7632 15246 7632 15247 7656 15247 7670 15247 7632 15248 7670 15248 7677 15248 7677 15249 7670 15249 7671 15249 7677 15250 7671 15250 7675 15250 7675 15251 7671 15251 7672 15251 7675 15252 7672 15252 7674 15252 7673 15253 1653 15253 7674 15253 7674 15254 1653 15254 7676 15254 7674 15255 7676 15255 7675 15255 7675 15256 7676 15256 1666 15256 7675 15257 1666 15257 7677 15257 7677 15258 1666 15258 1667 15258 7677 15259 1667 15259 7632 15259 7632 15260 1667 15260 7678 15260 7632 15261 7678 15261 7630 15261 7679 15262 7673 15262 7684 15262 7684 15263 7673 15263 7674 15263 7684 15264 7674 15264 7685 15264 7685 15265 7674 15265 7672 15265 7685 15266 7672 15266 7680 15266 7680 15267 7672 15267 7681 15267 7680 15268 7681 15268 1205 15268 1205 15269 7681 15269 7639 15269 7682 15270 7679 15270 7683 15270 7683 15271 7679 15271 7684 15271 7683 15272 7684 15272 7688 15272 7688 15273 7684 15273 7685 15273 7688 15274 7685 15274 7686 15274 7686 15275 7685 15275 7680 15275 7686 15276 7680 15276 1203 15276 1203 15277 7680 15277 1205 15277 1203 15278 1202 15278 7686 15278 7686 15279 1202 15279 7687 15279 7686 15280 7687 15280 7688 15280 7688 15281 7687 15281 7689 15281 7688 15282 7689 15282 7683 15282 7683 15283 7689 15283 7605 15283 7683 15284 7605 15284 7607 15284 7607 15285 7605 15285 7690 15285 7695 15286 7691 15286 7692 15286 7692 15287 7691 15287 7605 15287 7692 15288 7605 15288 7693 15288 7693 15289 7605 15289 7689 15289 7693 15290 7689 15290 7606 15290 7606 15291 7689 15291 7687 15291 7606 15292 7687 15292 7694 15292 7694 15293 7687 15293 1202 15293 7700 15294 7695 15294 7696 15294 7696 15295 7695 15295 7692 15295 7696 15296 7692 15296 7697 15296 7697 15297 7692 15297 7693 15297 7697 15298 7693 15298 7698 15298 7698 15299 7693 15299 7606 15299 7698 15300 7606 15300 7699 15300 7699 15301 7606 15301 1180 15301 4655 15302 7700 15302 7701 15302 7701 15303 7700 15303 7696 15303 7701 15304 7696 15304 7591 15304 7591 15305 7696 15305 7697 15305 7591 15306 7697 15306 7584 15306 7584 15307 7697 15307 7698 15307 7584 15308 7698 15308 7702 15308 7702 15309 7698 15309 7699 15309 7739 15310 1232 15310 7732 15310 7609 15311 7724 15311 7731 15311 7731 15312 7724 15312 7726 15312 7703 15313 7728 15313 7731 15313 7707 15314 7704 15314 1232 15314 1233 15315 7706 15315 7705 15315 7705 15316 7706 15316 7708 15316 7705 15317 7708 15317 7707 15317 7707 15318 7708 15318 7709 15318 7707 15319 7709 15319 7704 15319 7741 15320 7740 15320 7710 15320 7710 15321 7740 15321 7721 15321 7735 15322 7718 15322 7738 15322 7718 15323 7735 15323 7711 15323 7712 15324 7608 15324 7711 15324 7711 15325 7735 15325 7712 15325 7712 15326 7735 15326 7729 15326 7712 15327 7729 15327 7725 15327 1233 15328 7705 15328 1291 15328 1291 15329 7705 15329 7713 15329 1291 15330 7713 15330 1292 15330 1292 15331 7713 15331 7715 15331 1292 15332 7715 15332 7714 15332 7714 15333 7715 15333 7716 15333 7714 15334 7716 15334 1150 15334 7717 15335 7738 15335 4645 15335 4645 15336 7738 15336 7718 15336 4645 15337 7718 15337 7719 15337 7719 15338 7718 15338 7711 15338 7719 15339 7711 15339 7720 15339 7720 15340 7711 15340 7608 15340 7720 15341 7608 15341 7610 15341 7721 15342 7736 15342 7710 15342 7710 15343 7736 15343 7737 15343 7710 15344 7737 15344 7741 15344 7741 15345 7737 15345 7722 15345 7741 15346 7722 15346 4647 15346 7733 15347 7730 15347 7729 15347 7733 15348 7729 15348 7734 15348 7729 15349 7723 15349 7727 15349 7609 15350 7725 15350 7724 15350 7724 15351 7725 15351 7729 15351 7724 15352 7729 15352 7726 15352 7726 15353 7729 15353 7727 15353 7726 15354 7727 15354 7731 15354 7731 15355 7727 15355 7723 15355 7731 15356 7723 15356 7703 15356 7703 15357 7723 15357 7729 15357 7703 15358 7729 15358 7728 15358 7728 15359 7729 15359 7730 15359 7728 15360 7730 15360 7731 15360 7731 15361 7730 15361 7733 15361 7731 15362 7733 15362 7732 15362 7732 15363 7733 15363 7734 15363 7732 15364 7734 15364 7739 15364 7739 15365 7734 15365 7729 15365 7739 15366 7729 15366 7721 15366 7721 15367 7729 15367 7735 15367 7721 15368 7735 15368 7736 15368 7736 15369 7735 15369 7738 15369 7736 15370 7738 15370 7737 15370 7737 15371 7738 15371 7717 15371 1232 15372 7739 15372 7707 15372 7707 15373 7739 15373 7721 15373 7707 15374 7721 15374 7705 15374 7705 15375 7721 15375 7740 15375 7705 15376 7740 15376 7713 15376 7713 15377 7740 15377 7741 15377 7713 15378 7741 15378 7715 15378 7715 15379 7741 15379 4647 15379 7715 15380 4647 15380 7716 15380 7742 15381 7743 15381 7754 15381 7743 15382 7753 15382 7748 15382 2200 15383 7761 15383 7756 15383 7756 15384 7761 15384 7745 15384 7756 15385 7745 15385 7744 15385 7744 15386 7745 15386 7746 15386 7744 15387 7746 15387 7760 15387 7752 15388 1288 15388 7747 15388 7747 15389 1288 15389 7759 15389 7747 15390 7759 15390 7757 15390 7743 15391 7748 15391 7754 15391 7754 15392 7748 15392 7749 15392 7754 15393 7749 15393 7755 15393 2204 15394 7750 15394 2207 15394 2207 15395 7750 15395 7758 15395 2207 15396 7758 15396 2208 15396 2208 15397 7758 15397 1289 15397 2208 15398 1289 15398 1151 15398 2204 15399 2203 15399 7750 15399 7750 15400 2203 15400 7751 15400 7750 15401 7751 15401 7756 15401 7756 15402 7751 15402 2201 15402 7756 15403 2201 15403 2200 15403 7757 15404 7755 15404 7747 15404 7747 15405 7755 15405 7749 15405 7747 15406 7749 15406 7752 15406 7752 15407 7749 15407 7748 15407 7752 15408 7748 15408 1286 15408 1286 15409 7748 15409 7753 15409 1286 15410 7753 15410 1251 15410 1252 15411 7742 15411 7760 15411 7760 15412 7742 15412 7754 15412 7760 15413 7754 15413 7744 15413 7744 15414 7754 15414 7755 15414 7744 15415 7755 15415 7756 15415 7756 15416 7755 15416 7757 15416 7756 15417 7757 15417 7750 15417 7750 15418 7757 15418 7759 15418 7750 15419 7759 15419 7758 15419 7758 15420 7759 15420 1288 15420 7758 15421 1288 15421 1289 15421 1252 15422 7760 15422 1253 15422 1253 15423 7760 15423 7768 15423 7768 15424 7760 15424 7764 15424 7764 15425 7760 15425 7746 15425 7764 15426 7746 15426 7762 15426 2200 15427 7765 15427 7761 15427 7761 15428 7765 15428 7762 15428 7761 15429 7762 15429 7745 15429 7745 15430 7762 15430 7746 15430 7763 15431 1253 15431 7768 15431 7763 15432 7768 15432 7770 15432 7764 15433 7762 15433 7774 15433 7774 15434 7762 15434 7766 15434 7774 15435 7766 15435 7767 15435 7762 15436 7765 15436 7766 15436 7766 15437 7765 15437 2211 15437 7766 15438 2211 15438 7767 15438 7767 15439 2211 15439 7771 15439 7764 15440 7774 15440 7768 15440 7768 15441 7774 15441 7769 15441 7768 15442 7769 15442 7770 15442 7771 15443 7772 15443 7767 15443 7767 15444 7772 15444 7773 15444 7767 15445 7773 15445 7774 15445 7774 15446 7773 15446 7775 15446 7774 15447 7775 15447 7769 15447 7769 15448 7775 15448 7790 15448 7769 15449 7790 15449 7770 15449 7770 15450 7790 15450 7776 15450 7796 15451 7777 15451 7783 15451 7780 15452 7778 15452 7776 15452 7791 15453 7779 15453 7780 15453 7780 15454 7779 15454 1254 15454 7780 15455 1254 15455 7778 15455 7781 15456 7796 15456 7782 15456 7782 15457 7796 15457 7783 15457 7782 15458 7783 15458 7787 15458 7787 15459 7783 15459 7784 15459 7787 15460 7784 15460 7793 15460 7772 15461 7785 15461 7793 15461 7793 15462 7785 15462 7786 15462 7793 15463 7786 15463 7787 15463 7787 15464 7786 15464 7788 15464 7787 15465 7788 15465 7782 15465 7782 15466 7788 15466 7789 15466 7782 15467 7789 15467 7781 15467 7781 15468 7789 15468 2219 15468 7773 15469 7792 15469 7775 15469 7775 15470 7792 15470 7780 15470 7775 15471 7780 15471 7790 15471 7790 15472 7780 15472 7776 15472 7777 15473 7791 15473 7783 15473 7783 15474 7791 15474 7780 15474 7783 15475 7780 15475 7784 15475 7784 15476 7780 15476 7792 15476 7784 15477 7792 15477 7793 15477 7793 15478 7792 15478 7773 15478 7793 15479 7773 15479 7772 15479 1217 15480 7779 15480 7794 15480 7794 15481 7779 15481 7791 15481 7794 15482 7791 15482 7795 15482 7795 15483 7791 15483 7777 15483 7795 15484 7777 15484 7816 15484 7816 15485 7777 15485 7796 15485 7816 15486 7796 15486 7797 15486 7797 15487 7796 15487 7781 15487 7797 15488 7781 15488 2223 15488 2223 15489 7781 15489 2219 15489 7798 15490 1217 15490 7814 15490 7814 15491 1217 15491 7794 15491 7814 15492 7794 15492 7795 15492 7806 15493 7799 15493 7800 15493 7800 15494 7799 15494 7801 15494 7800 15495 7801 15495 7823 15495 2227 15496 7802 15496 7804 15496 7804 15497 7802 15497 7803 15497 7804 15498 7803 15498 7805 15498 7805 15499 7803 15499 7826 15499 7805 15500 7826 15500 7806 15500 7806 15501 7826 15501 7807 15501 7806 15502 7807 15502 7799 15502 7808 15503 1218 15503 7821 15503 7821 15504 1218 15504 7815 15504 7821 15505 7815 15505 7820 15505 7820 15506 7815 15506 7809 15506 7820 15507 7809 15507 7819 15507 7819 15508 7809 15508 7810 15508 7819 15509 7810 15509 7818 15509 7818 15510 7810 15510 7811 15510 7818 15511 7811 15511 7812 15511 7812 15512 7811 15512 7817 15512 7817 15513 2224 15513 7812 15513 7812 15514 2224 15514 2225 15514 7812 15515 2225 15515 7813 15515 1218 15516 7798 15516 7815 15516 7815 15517 7798 15517 7814 15517 7815 15518 7814 15518 7809 15518 7809 15519 7814 15519 7795 15519 7809 15520 7795 15520 7810 15520 7810 15521 7795 15521 7816 15521 7810 15522 7816 15522 7811 15522 7811 15523 7816 15523 7797 15523 7811 15524 7797 15524 7817 15524 7817 15525 7797 15525 2223 15525 7817 15526 2223 15526 2224 15526 7813 15527 2227 15527 7812 15527 7812 15528 2227 15528 7804 15528 7812 15529 7804 15529 7818 15529 7818 15530 7804 15530 7805 15530 7818 15531 7805 15531 7819 15531 7819 15532 7805 15532 7806 15532 7819 15533 7806 15533 7820 15533 7820 15534 7806 15534 7800 15534 7820 15535 7800 15535 7821 15535 7821 15536 7800 15536 7823 15536 7821 15537 7823 15537 7808 15537 1219 15538 7808 15538 7835 15538 7835 15539 7808 15539 7823 15539 7835 15540 7823 15540 7822 15540 7822 15541 7823 15541 7824 15541 7823 15542 7801 15542 7824 15542 7824 15543 7801 15543 7799 15543 7824 15544 7799 15544 7825 15544 7799 15545 7807 15545 7825 15545 7825 15546 7807 15546 7826 15546 7825 15547 7826 15547 2228 15547 2228 15548 7826 15548 7803 15548 2228 15549 7803 15549 7802 15549 1221 15550 1220 15550 7827 15550 7827 15551 1220 15551 7834 15551 7827 15552 7834 15552 7837 15552 7824 15553 7825 15553 7836 15553 7836 15554 7825 15554 7830 15554 7836 15555 7830 15555 7828 15555 7828 15556 7830 15556 7829 15556 7828 15557 7829 15557 7838 15557 7838 15558 7829 15558 7832 15558 7825 15559 2228 15559 7830 15559 7830 15560 2228 15560 7831 15560 7830 15561 7831 15561 7829 15561 7829 15562 7831 15562 2230 15562 7829 15563 2230 15563 7832 15563 7832 15564 2230 15564 7833 15564 1220 15565 1219 15565 7834 15565 7834 15566 1219 15566 7835 15566 7834 15567 7835 15567 7837 15567 7837 15568 7835 15568 7822 15568 7837 15569 7822 15569 7824 15569 7824 15570 7836 15570 7837 15570 7837 15571 7836 15571 7828 15571 7837 15572 7828 15572 7827 15572 7827 15573 7828 15573 7838 15573 7827 15574 7838 15574 7839 15574 7839 15575 7838 15575 7832 15575 7839 15576 7832 15576 7841 15576 7841 15577 7832 15577 7833 15577 7841 15578 7833 15578 2232 15578 2232 15579 7840 15579 7873 15579 2232 15580 7873 15580 7841 15580 7873 15581 7850 15581 7841 15581 7841 15582 7850 15582 7846 15582 7841 15583 7846 15583 7839 15583 7846 15584 7882 15584 7839 15584 7839 15585 7882 15585 7857 15585 7839 15586 7857 15586 7827 15586 7827 15587 7857 15587 7842 15587 7827 15588 7842 15588 1221 15588 7874 15589 7853 15589 4643 15589 4643 15590 7877 15590 7879 15590 7844 15591 7876 15591 7847 15591 7843 15592 7844 15592 7848 15592 7877 15593 4641 15593 7878 15593 7882 15594 7846 15594 7845 15594 7845 15595 7846 15595 7855 15595 7844 15596 7847 15596 7848 15596 7848 15597 7847 15597 7849 15597 7848 15598 7849 15598 7855 15598 7855 15599 7849 15599 7880 15599 7855 15600 7880 15600 7845 15600 7850 15601 7873 15601 7851 15601 7872 15602 4637 15602 7851 15602 7851 15603 4637 15603 4639 15603 7851 15604 4639 15604 7874 15604 7874 15605 4639 15605 7852 15605 7874 15606 7852 15606 7853 15606 7843 15607 7848 15607 7854 15607 7854 15608 7848 15608 7855 15608 7854 15609 7855 15609 7856 15609 7856 15610 7855 15610 7846 15610 7856 15611 7846 15611 7850 15611 1237 15612 7842 15612 7865 15612 7865 15613 7842 15613 7857 15613 7865 15614 7857 15614 7881 15614 7867 15615 7864 15615 7858 15615 7867 15616 7859 15616 7869 15616 7869 15617 7859 15617 7860 15617 7869 15618 7860 15618 7870 15618 7870 15619 7860 15619 7862 15619 1234 15620 7870 15620 7861 15620 7861 15621 7870 15621 7862 15621 7861 15622 7862 15622 7888 15622 7888 15623 7862 15623 7878 15623 7888 15624 7878 15624 7863 15624 7863 15625 7878 15625 4641 15625 7863 15626 4641 15626 7889 15626 7881 15627 7858 15627 7865 15627 7865 15628 7858 15628 7864 15628 7865 15629 7864 15629 1237 15629 1237 15630 7864 15630 7867 15630 1237 15631 7867 15631 7866 15631 7866 15632 7867 15632 7869 15632 7866 15633 7869 15633 7868 15633 7868 15634 7869 15634 7870 15634 7868 15635 7870 15635 7871 15635 7871 15636 7870 15636 1234 15636 7872 15637 7851 15637 4636 15637 4636 15638 7851 15638 7873 15638 4636 15639 7873 15639 7840 15639 7850 15640 7851 15640 7856 15640 7856 15641 7851 15641 7874 15641 7856 15642 7874 15642 7854 15642 7854 15643 7874 15643 4643 15643 7854 15644 4643 15644 7843 15644 7843 15645 4643 15645 7879 15645 7843 15646 7879 15646 7844 15646 7844 15647 7879 15647 7875 15647 7844 15648 7875 15648 7876 15648 7877 15649 7878 15649 7879 15649 7879 15650 7878 15650 7862 15650 7879 15651 7862 15651 7875 15651 7875 15652 7862 15652 7860 15652 7875 15653 7860 15653 7876 15653 7876 15654 7860 15654 7859 15654 7876 15655 7859 15655 7847 15655 7847 15656 7859 15656 7867 15656 7847 15657 7867 15657 7849 15657 7849 15658 7867 15658 7858 15658 7849 15659 7858 15659 7880 15659 7880 15660 7858 15660 7881 15660 7880 15661 7881 15661 7845 15661 7845 15662 7881 15662 7857 15662 7845 15663 7857 15663 7882 15663 7886 15664 1234 15664 7861 15664 1243 15665 1242 15665 7907 15665 7907 15666 1242 15666 7885 15666 7907 15667 7885 15667 7906 15667 7906 15668 7885 15668 7887 15668 7906 15669 7887 15669 7903 15669 7903 15670 7887 15670 7883 15670 7903 15671 7883 15671 7901 15671 7901 15672 7883 15672 7913 15672 7913 15673 7883 15673 7884 15673 7913 15674 7884 15674 2010 15674 1242 15675 7886 15675 7885 15675 7885 15676 7886 15676 7861 15676 7885 15677 7861 15677 7887 15677 7887 15678 7861 15678 7888 15678 7887 15679 7888 15679 7883 15679 7883 15680 7888 15680 7863 15680 7883 15681 7863 15681 7884 15681 7884 15682 7863 15682 7889 15682 7898 15683 7896 15683 7910 15683 7890 15684 4632 15684 7892 15684 4634 15685 7891 15685 7915 15685 4632 15686 4634 15686 7892 15686 7892 15687 4634 15687 7915 15687 7892 15688 7915 15688 7893 15688 7893 15689 7915 15689 7914 15689 7893 15690 7914 15690 7909 15690 7894 15691 7912 15691 7902 15691 7902 15692 7912 15692 7895 15692 7902 15693 7895 15693 7904 15693 7904 15694 7895 15694 7910 15694 7904 15695 7910 15695 7905 15695 7905 15696 7910 15696 1244 15696 1244 15697 7910 15697 7896 15697 1244 15698 7896 15698 1245 15698 1249 15699 7897 15699 7898 15699 7898 15700 7897 15700 7899 15700 7898 15701 7899 15701 7896 15701 7896 15702 7899 15702 7900 15702 7896 15703 7900 15703 1245 15703 7913 15704 7894 15704 7901 15704 7901 15705 7894 15705 7902 15705 7901 15706 7902 15706 7903 15706 7903 15707 7902 15707 7904 15707 7903 15708 7904 15708 7906 15708 7906 15709 7904 15709 7905 15709 7906 15710 7905 15710 7907 15710 7907 15711 7905 15711 1244 15711 7907 15712 1244 15712 1243 15712 7908 15713 1249 15713 7909 15713 7909 15714 1249 15714 7898 15714 7909 15715 7898 15715 7893 15715 7893 15716 7898 15716 7910 15716 7893 15717 7910 15717 7892 15717 7892 15718 7910 15718 7895 15718 7892 15719 7895 15719 7890 15719 7890 15720 7895 15720 7912 15720 7890 15721 7912 15721 7911 15721 7911 15722 7912 15722 7894 15722 7911 15723 7894 15723 4630 15723 4630 15724 7894 15724 7913 15724 4630 15725 7913 15725 2010 15725 7920 15726 7908 15726 7909 15726 7920 15727 7909 15727 7916 15727 7909 15728 7914 15728 7916 15728 7916 15729 7914 15729 7915 15729 7916 15730 7915 15730 7917 15730 7917 15731 7915 15731 7891 15731 7916 15732 7917 15732 2236 15732 7925 15733 7923 15733 7918 15733 7918 15734 7923 15734 7919 15734 7918 15735 7919 15735 7921 15735 7921 15736 7919 15736 7920 15736 7920 15737 7916 15737 7921 15737 7921 15738 7916 15738 2236 15738 7921 15739 2236 15739 7918 15739 7918 15740 2236 15740 7922 15740 7918 15741 7922 15741 7925 15741 7925 15742 7922 15742 2237 15742 1247 15743 7923 15743 7924 15743 7924 15744 7923 15744 7925 15744 7924 15745 7925 15745 7930 15745 7930 15746 7925 15746 7926 15746 7926 15747 7925 15747 2237 15747 7926 15748 2237 15748 7939 15748 7927 15749 7929 15749 7928 15749 7928 15750 7929 15750 7941 15750 7928 15751 7941 15751 1248 15751 7930 15752 7926 15752 7940 15752 7940 15753 7926 15753 7937 15753 7940 15754 7937 15754 7931 15754 7931 15755 7937 15755 7936 15755 7931 15756 7936 15756 7932 15756 7932 15757 7936 15757 7942 15757 7933 15758 7942 15758 7934 15758 7934 15759 7942 15759 7936 15759 7934 15760 7936 15760 7935 15760 7935 15761 7936 15761 7937 15761 7935 15762 7937 15762 7938 15762 7938 15763 7937 15763 7926 15763 7938 15764 7926 15764 7939 15764 7927 15765 1247 15765 7929 15765 7929 15766 1247 15766 7924 15766 7929 15767 7924 15767 7930 15767 7930 15768 7940 15768 7929 15768 7929 15769 7940 15769 7931 15769 7929 15770 7931 15770 7941 15770 7941 15771 7931 15771 7932 15771 7941 15772 7932 15772 7944 15772 7944 15773 7932 15773 7942 15773 7944 15774 7942 15774 7945 15774 7945 15775 7942 15775 7933 15775 7945 15776 7933 15776 2239 15776 7949 15777 1248 15777 7943 15777 7943 15778 1248 15778 7941 15778 7943 15779 7941 15779 7961 15779 7961 15780 7941 15780 7944 15780 7961 15781 7944 15781 7964 15781 7964 15782 7944 15782 7945 15782 7964 15783 7945 15783 7946 15783 7946 15784 7945 15784 2239 15784 7946 15785 2239 15785 2248 15785 7960 15786 7943 15786 7961 15786 7957 15787 7953 15787 7967 15787 7956 15788 7947 15788 7979 15788 7948 15789 7950 15789 7960 15789 7960 15790 7950 15790 7949 15790 7960 15791 7949 15791 7943 15791 7994 15792 7950 15792 7951 15792 7951 15793 7950 15793 7948 15793 7951 15794 7948 15794 7995 15794 7952 15795 7953 15795 7954 15795 7954 15796 7953 15796 7957 15796 7954 15797 7957 15797 7958 15797 7947 15798 7956 15798 7981 15798 7981 15799 7956 15799 7955 15799 7981 15800 7955 15800 7982 15800 7982 15801 7955 15801 2252 15801 7982 15802 2252 15802 2250 15802 2256 15803 2252 15803 7968 15803 7968 15804 2252 15804 7955 15804 7968 15805 7955 15805 7967 15805 7967 15806 7955 15806 7956 15806 7967 15807 7956 15807 7957 15807 7957 15808 7956 15808 7979 15808 7957 15809 7979 15809 7958 15809 7995 15810 7948 15810 7959 15810 7959 15811 7948 15811 7960 15811 7959 15812 7960 15812 7966 15812 7966 15813 7960 15813 7961 15813 7966 15814 7961 15814 7962 15814 7962 15815 7961 15815 7964 15815 7962 15816 7964 15816 7963 15816 7963 15817 7964 15817 7946 15817 7963 15818 7946 15818 7965 15818 7965 15819 7946 15819 2248 15819 7965 15820 2248 15820 2254 15820 7958 15821 7995 15821 7954 15821 7954 15822 7995 15822 7959 15822 7954 15823 7959 15823 7952 15823 7952 15824 7959 15824 7966 15824 7952 15825 7966 15825 7953 15825 7953 15826 7966 15826 7962 15826 7953 15827 7962 15827 7967 15827 7967 15828 7962 15828 7963 15828 7967 15829 7963 15829 7968 15829 7968 15830 7963 15830 7965 15830 7968 15831 7965 15831 2256 15831 2256 15832 7965 15832 2254 15832 7969 15833 7970 15833 7997 15833 7997 15834 7970 15834 7971 15834 7997 15835 7971 15835 7999 15835 8007 15836 8006 15836 7976 15836 7976 15837 8006 15837 7972 15837 7976 15838 7972 15838 7975 15838 7975 15839 7972 15839 7973 15839 7973 15840 7972 15840 7974 15840 7973 15841 7974 15841 7998 15841 7973 15842 1085 15842 7975 15842 7975 15843 1085 15843 1091 15843 7975 15844 1091 15844 7976 15844 7976 15845 1091 15845 1093 15845 7976 15846 1093 15846 8007 15846 8007 15847 1093 15847 1094 15847 7979 15848 7977 15848 7996 15848 7996 15849 7977 15849 7985 15849 7996 15850 7985 15850 7986 15850 8002 15851 7983 15851 7978 15851 7978 15852 7983 15852 7980 15852 7978 15853 7980 15853 8004 15853 7979 15854 7947 15854 7983 15854 7983 15855 7947 15855 7981 15855 7983 15856 7981 15856 7980 15856 7980 15857 7981 15857 7982 15857 7988 15858 7987 15858 7999 15858 7999 15859 7987 15859 7984 15859 7979 15860 7983 15860 7977 15860 7977 15861 7983 15861 8002 15861 7977 15862 8002 15862 7985 15862 7985 15863 8002 15863 7984 15863 7985 15864 7984 15864 7986 15864 7986 15865 7984 15865 7987 15865 7986 15866 7987 15866 7993 15866 7993 15867 7987 15867 7988 15867 7993 15868 7988 15868 7989 15868 7982 15869 2250 15869 7980 15869 7980 15870 2250 15870 7990 15870 7980 15871 7990 15871 8004 15871 8004 15872 7990 15872 7991 15872 7998 15873 8000 15873 7973 15873 7973 15874 8000 15874 8001 15874 7973 15875 8001 15875 1085 15875 1085 15876 8001 15876 8003 15876 1085 15877 8003 15877 7992 15877 7992 15878 8003 15878 1084 15878 7989 15879 7994 15879 7993 15879 7993 15880 7994 15880 7951 15880 7993 15881 7951 15881 7986 15881 7986 15882 7951 15882 7995 15882 7986 15883 7995 15883 7996 15883 7996 15884 7995 15884 7958 15884 7996 15885 7958 15885 7979 15885 8006 15886 7969 15886 7972 15886 7972 15887 7969 15887 7997 15887 7972 15888 7997 15888 7974 15888 7974 15889 7997 15889 7999 15889 7974 15890 7999 15890 7998 15890 7998 15891 7999 15891 7984 15891 7998 15892 7984 15892 8000 15892 8000 15893 7984 15893 8002 15893 8000 15894 8002 15894 8001 15894 8001 15895 8002 15895 7978 15895 8001 15896 7978 15896 8003 15896 8003 15897 7978 15897 8004 15897 8003 15898 8004 15898 1084 15898 1084 15899 8004 15899 7991 15899 8005 15900 7970 15900 7969 15900 8012 15901 8006 15901 8008 15901 8008 15902 8006 15902 8007 15902 8008 15903 8007 15903 1094 15903 8018 15904 8005 15904 8019 15904 8019 15905 8005 15905 7969 15905 8019 15906 7969 15906 8009 15906 8009 15907 7969 15907 8006 15907 8009 15908 8006 15908 8010 15908 8010 15909 8006 15909 8012 15909 8022 15910 8026 15910 8027 15910 8026 15911 8022 15911 8011 15911 8028 15912 8011 15912 8014 15912 8014 15913 8011 15913 8022 15913 8014 15914 8022 15914 8016 15914 8020 15915 8010 15915 8021 15915 8021 15916 8010 15916 8012 15916 8021 15917 8012 15917 2258 15917 2264 15918 8028 15918 8013 15918 8013 15919 8028 15919 8014 15919 8013 15920 8014 15920 8015 15920 8015 15921 8014 15921 8016 15921 8015 15922 8016 15922 2257 15922 8017 15923 8018 15923 8023 15923 8023 15924 8018 15924 8019 15924 8023 15925 8019 15925 8020 15925 8020 15926 8019 15926 8009 15926 8020 15927 8009 15927 8010 15927 2258 15928 2257 15928 8021 15928 8021 15929 2257 15929 8016 15929 8021 15930 8016 15930 8020 15930 8020 15931 8016 15931 8022 15931 8020 15932 8022 15932 8023 15932 8023 15933 8022 15933 8027 15933 8023 15934 8027 15934 8017 15934 8017 15935 8027 15935 8024 15935 8028 15936 2264 15936 8025 15936 8026 15937 8011 15937 8032 15937 8032 15938 8011 15938 8028 15938 8024 15939 8027 15939 8035 15939 8035 15940 8027 15940 8026 15940 8028 15941 8025 15941 8032 15941 8032 15942 8025 15942 2267 15942 8032 15943 2267 15943 8033 15943 8033 15944 2267 15944 8029 15944 8033 15945 8029 15945 8031 15945 8029 15946 2268 15946 8030 15946 8029 15947 8030 15947 8031 15947 8031 15948 8030 15948 8041 15948 8031 15949 8041 15949 8047 15949 8026 15950 8032 15950 8035 15950 8035 15951 8032 15951 8033 15951 8035 15952 8033 15952 8034 15952 8034 15953 8033 15953 8031 15953 8034 15954 8031 15954 8036 15954 8036 15955 8031 15955 8047 15955 8036 15956 8047 15956 8037 15956 8024 15957 8035 15957 2368 15957 2368 15958 8035 15958 8034 15958 2368 15959 8034 15959 2369 15959 2369 15960 8034 15960 8036 15960 2369 15961 8036 15961 2370 15961 2370 15962 8036 15962 8037 15962 2370 15963 8037 15963 8045 15963 8040 15964 8030 15964 2268 15964 8038 15965 8044 15965 8039 15965 8030 15966 8040 15966 8041 15966 8043 15967 8042 15967 8040 15967 8040 15968 8042 15968 8048 15968 8040 15969 8048 15969 8041 15969 8038 15970 8039 15970 2362 15970 2273 15971 8043 15971 2276 15971 2276 15972 8043 15972 8040 15972 2276 15973 8040 15973 2275 15973 2275 15974 8040 15974 2268 15974 2273 15975 2274 15975 8046 15975 8044 15976 8045 15976 8039 15976 8039 15977 8045 15977 8037 15977 8039 15978 8037 15978 8047 15978 2273 15979 8046 15979 8043 15979 8043 15980 8046 15980 8050 15980 8043 15981 8050 15981 8042 15981 8042 15982 8050 15982 8039 15982 8042 15983 8039 15983 8048 15983 8048 15984 8039 15984 8047 15984 8048 15985 8047 15985 8041 15985 2362 15986 8039 15986 8049 15986 8049 15987 8039 15987 8050 15987 8049 15988 8050 15988 8053 15988 8053 15989 8050 15989 8046 15989 8053 15990 8046 15990 8054 15990 8054 15991 8046 15991 2274 15991 8054 15992 2274 15992 8051 15992 8055 15993 2279 15993 8059 15993 2367 15994 2362 15994 8049 15994 2358 15995 2367 15995 8052 15995 8052 15996 2367 15996 8049 15996 8052 15997 8049 15997 8057 15997 8057 15998 8049 15998 8053 15998 8057 15999 8053 15999 8059 15999 8059 16000 8053 16000 8054 16000 8059 16001 8054 16001 8055 16001 8055 16002 8054 16002 8051 16002 8060 16003 2358 16003 8056 16003 8056 16004 2358 16004 8052 16004 8056 16005 8052 16005 8062 16005 8062 16006 8052 16006 8057 16006 8062 16007 8057 16007 8058 16007 8058 16008 8057 16008 8059 16008 8058 16009 8059 16009 2271 16009 2271 16010 8059 16010 2279 16010 2364 16011 8060 16011 8061 16011 8061 16012 8060 16012 8056 16012 8061 16013 8056 16013 8065 16013 8065 16014 8056 16014 8062 16014 8065 16015 8062 16015 8063 16015 8063 16016 8062 16016 8058 16016 8063 16017 8058 16017 8064 16017 8064 16018 8058 16018 2271 16018 2197 16019 8070 16019 8064 16019 8064 16020 8070 16020 8063 16020 8063 16021 8070 16021 8065 16021 8065 16022 8070 16022 8069 16022 8065 16023 8069 16023 8061 16023 8069 16024 8068 16024 8061 16024 8061 16025 8068 16025 2365 16025 8061 16026 2365 16026 2364 16026 4217 16027 4216 16027 8077 16027 8071 16028 2365 16028 8066 16028 8066 16029 2365 16029 8068 16029 8066 16030 8068 16030 8067 16030 8067 16031 8068 16031 8069 16031 8067 16032 8069 16032 8074 16032 8074 16033 8069 16033 8070 16033 8074 16034 8070 16034 8075 16034 8075 16035 8070 16035 2197 16035 2361 16036 8071 16036 8072 16036 8072 16037 8071 16037 8066 16037 8072 16038 8066 16038 8073 16038 8073 16039 8066 16039 8067 16039 8073 16040 8067 16040 8079 16040 8079 16041 8067 16041 8074 16041 8079 16042 8074 16042 8080 16042 8080 16043 8074 16043 8075 16043 4217 16044 8077 16044 8078 16044 8082 16045 2361 16045 8076 16045 8076 16046 2361 16046 8072 16046 8076 16047 8072 16047 8084 16047 8084 16048 8072 16048 8073 16048 8084 16049 8073 16049 8077 16049 8077 16050 8073 16050 8079 16050 8077 16051 8079 16051 8078 16051 8078 16052 8079 16052 8080 16052 2359 16053 8082 16053 8081 16053 8081 16054 8082 16054 8076 16054 8081 16055 8076 16055 8088 16055 8088 16056 8076 16056 8084 16056 8088 16057 8084 16057 8083 16057 8083 16058 8084 16058 8077 16058 8083 16059 8077 16059 8085 16059 8085 16060 8077 16060 4216 16060 8093 16061 1742 16061 1744 16061 8086 16062 8091 16062 8087 16062 8087 16063 8089 16063 8086 16063 8086 16064 8089 16064 8090 16064 8086 16065 8090 16065 2337 16065 8081 16066 8088 16066 8087 16066 8087 16067 8088 16067 8083 16067 8087 16068 8083 16068 8089 16068 8089 16069 8083 16069 8085 16069 8089 16070 8085 16070 8090 16070 8091 16071 8092 16071 8087 16071 8087 16072 8092 16072 8093 16072 8087 16073 8093 16073 8081 16073 8081 16074 8093 16074 1744 16074 8081 16075 1744 16075 2359 16075 2337 16076 3109 16076 8086 16076 8086 16077 3109 16077 8111 16077 8086 16078 8111 16078 8091 16078 8091 16079 8111 16079 8113 16079 8091 16080 8113 16080 8092 16080 8092 16081 8113 16081 8094 16081 8092 16082 8094 16082 8093 16082 8093 16083 8094 16083 8114 16083 8093 16084 8114 16084 1742 16084 1748 16085 8110 16085 8095 16085 1748 16086 8095 16086 8104 16086 3113 16087 3040 16087 8097 16087 8097 16088 3040 16088 8096 16088 8097 16089 8096 16089 8098 16089 8098 16090 8096 16090 8099 16090 8098 16091 8099 16091 8101 16091 8101 16092 8099 16092 8100 16092 8101 16093 8100 16093 1747 16093 1747 16094 8100 16094 8102 16094 8106 16095 3113 16095 8103 16095 8103 16096 3113 16096 8097 16096 8103 16097 8097 16097 8108 16097 8108 16098 8097 16098 8098 16098 8108 16099 8098 16099 8095 16099 8095 16100 8098 16100 8101 16100 8095 16101 8101 16101 8104 16101 8104 16102 8101 16102 1747 16102 3115 16103 8106 16103 8105 16103 8105 16104 8106 16104 8103 16104 8105 16105 8103 16105 8112 16105 8112 16106 8103 16106 8108 16106 8112 16107 8108 16107 8107 16107 8107 16108 8108 16108 8095 16108 8107 16109 8095 16109 8109 16109 8109 16110 8095 16110 8110 16110 3109 16111 3115 16111 8111 16111 8111 16112 3115 16112 8105 16112 8111 16113 8105 16113 8113 16113 8113 16114 8105 16114 8112 16114 8113 16115 8112 16115 8094 16115 8094 16116 8112 16116 8107 16116 8094 16117 8107 16117 8114 16117 8114 16118 8107 16118 8109 16118 3047 16119 5021 16119 8117 16119 1751 16120 8102 16120 8115 16120 8115 16121 8102 16121 8100 16121 8115 16122 8100 16122 8116 16122 8116 16123 8100 16123 8099 16123 8116 16124 8099 16124 8117 16124 8117 16125 8099 16125 8096 16125 8117 16126 8096 16126 3047 16126 3047 16127 8096 16127 3040 16127 8115 16128 8126 16128 1751 16128 1751 16129 8126 16129 8118 16129 8143 16130 1753 16130 8118 16130 8128 16131 8124 16131 8119 16131 8116 16132 8117 16132 8120 16132 8120 16133 8117 16133 8122 16133 8120 16134 8122 16134 8121 16134 8121 16135 8122 16135 8125 16135 8117 16136 5021 16136 8122 16136 8122 16137 5021 16137 8123 16137 8122 16138 8123 16138 8125 16138 8125 16139 8123 16139 5052 16139 8124 16140 8128 16140 5052 16140 5052 16141 8128 16141 8125 16141 8125 16142 8128 16142 8127 16142 8125 16143 8127 16143 8121 16143 8121 16144 8127 16144 8126 16144 8121 16145 8126 16145 8120 16145 8120 16146 8126 16146 8115 16146 8120 16147 8115 16147 8116 16147 8118 16148 8126 16148 8143 16148 8143 16149 8126 16149 8127 16149 8143 16150 8127 16150 8141 16150 8141 16151 8127 16151 8128 16151 8141 16152 8128 16152 8129 16152 8129 16153 8128 16153 8119 16153 8129 16154 8119 16154 8130 16154 8142 16155 8143 16155 8141 16155 5022 16156 5024 16156 8138 16156 8131 16157 8133 16157 8148 16157 8148 16158 8133 16158 8154 16158 8148 16159 8154 16159 8132 16159 8140 16160 8138 16160 8131 16160 8131 16161 8138 16161 8139 16161 8131 16162 8139 16162 8133 16162 8147 16163 8137 16163 8146 16163 8146 16164 8137 16164 8134 16164 8150 16165 8152 16165 8135 16165 8150 16166 8135 16166 8149 16166 8135 16167 8136 16167 8149 16167 8149 16168 8136 16168 4867 16168 8149 16169 4867 16169 8147 16169 8147 16170 4867 16170 4864 16170 8147 16171 4864 16171 8137 16171 8129 16172 8130 16172 5022 16172 8138 16173 5024 16173 8139 16173 8139 16174 5024 16174 5016 16174 8139 16175 5016 16175 8133 16175 8133 16176 5016 16176 5015 16176 8133 16177 5015 16177 8154 16177 5022 16178 8138 16178 8129 16178 8129 16179 8138 16179 8140 16179 8129 16180 8140 16180 8141 16180 8141 16181 8140 16181 8145 16181 8141 16182 8145 16182 8142 16182 1753 16183 8143 16183 8144 16183 8144 16184 8143 16184 8142 16184 8144 16185 8142 16185 8134 16185 8134 16186 8142 16186 8145 16186 8134 16187 8145 16187 8146 16187 8146 16188 8145 16188 8140 16188 8146 16189 8140 16189 8147 16189 8147 16190 8140 16190 8131 16190 8147 16191 8131 16191 8149 16191 8149 16192 8131 16192 8148 16192 8149 16193 8148 16193 8150 16193 8150 16194 8148 16194 8132 16194 8151 16195 8176 16195 8155 16195 8162 16196 8152 16196 8167 16196 8167 16197 8152 16197 8150 16197 8167 16198 8150 16198 8153 16198 8153 16199 8150 16199 8132 16199 8153 16200 8132 16200 8155 16200 8155 16201 8132 16201 8154 16201 8155 16202 8154 16202 8151 16202 8151 16203 8154 16203 5015 16203 8171 16204 8156 16204 8168 16204 8156 16205 8178 16205 8169 16205 8178 16206 8177 16206 8158 16206 8177 16207 8189 16207 8157 16207 8177 16208 8157 16208 8158 16208 8158 16209 8157 16209 4809 16209 8158 16210 4809 16210 8164 16210 8164 16211 4809 16211 8159 16211 8164 16212 8159 16212 8165 16212 8159 16213 4811 16213 8165 16213 8165 16214 4811 16214 8160 16214 8165 16215 8160 16215 8161 16215 8161 16216 8160 16216 8162 16216 8161 16217 8162 16217 8167 16217 8178 16218 8158 16218 8169 16218 8169 16219 8158 16219 8164 16219 8169 16220 8164 16220 8163 16220 8163 16221 8164 16221 8165 16221 8163 16222 8165 16222 8170 16222 8170 16223 8165 16223 8161 16223 8170 16224 8161 16224 8166 16224 8166 16225 8161 16225 8167 16225 8166 16226 8167 16226 8153 16226 8156 16227 8169 16227 8168 16227 8168 16228 8169 16228 8163 16228 8168 16229 8163 16229 8172 16229 8172 16230 8163 16230 8170 16230 8172 16231 8170 16231 8173 16231 8173 16232 8170 16232 8166 16232 8173 16233 8166 16233 8175 16233 8175 16234 8166 16234 8153 16234 8175 16235 8153 16235 8155 16235 8171 16236 8168 16236 1772 16236 1772 16237 8168 16237 8172 16237 1772 16238 8172 16238 1773 16238 1773 16239 8172 16239 8173 16239 1773 16240 8173 16240 8174 16240 8174 16241 8173 16241 8175 16241 8174 16242 8175 16242 1764 16242 1764 16243 8175 16243 8155 16243 1764 16244 8155 16244 8176 16244 8156 16245 8171 16245 1770 16245 8177 16246 8178 16246 8186 16246 8189 16247 8177 16247 8191 16247 8178 16248 8156 16248 8180 16248 8180 16249 8156 16249 1770 16249 8180 16250 1770 16250 8182 16250 8182 16251 1770 16251 8179 16251 8182 16252 8179 16252 8183 16252 8178 16253 8180 16253 8186 16253 8186 16254 8180 16254 8182 16254 8186 16255 8182 16255 8181 16255 8181 16256 8182 16256 8183 16256 8181 16257 8183 16257 8187 16257 8179 16258 8198 16258 8183 16258 8183 16259 8198 16259 8184 16259 8183 16260 8184 16260 8187 16260 8187 16261 8184 16261 8185 16261 8187 16262 8185 16262 8195 16262 8177 16263 8186 16263 8191 16263 8191 16264 8186 16264 8181 16264 8191 16265 8181 16265 8192 16265 8192 16266 8181 16266 8187 16266 8192 16267 8187 16267 8188 16267 8188 16268 8187 16268 8195 16268 8188 16269 8195 16269 8194 16269 8189 16270 8191 16270 8190 16270 8190 16271 8191 16271 8192 16271 8190 16272 8192 16272 8193 16272 8193 16273 8192 16273 8188 16273 8193 16274 8188 16274 4833 16274 4833 16275 8188 16275 8194 16275 4833 16276 8194 16276 1691 16276 8185 16277 1521 16277 8195 16277 8195 16278 1521 16278 8196 16278 8195 16279 8196 16279 8194 16279 8194 16280 8196 16280 8197 16280 8194 16281 8197 16281 1691 16281 8185 16282 8184 16282 1521 16282 1521 16283 8184 16283 8198 16283 1521 16284 8198 16284 1766 16284 1500 16285 8217 16285 8216 16285 1500 16286 8216 16286 1493 16286 1493 16287 8216 16287 8199 16287 1493 16288 8199 16288 8201 16288 8201 16289 8199 16289 8200 16289 8201 16290 8200 16290 8202 16290 8202 16291 8200 16291 4834 16291 8202 16292 4834 16292 1692 16292 8221 16293 4831 16293 8204 16293 8204 16294 4831 16294 8203 16294 8204 16295 8203 16295 8205 16295 8205 16296 8203 16296 8206 16296 1763 16297 8219 16297 8209 16297 8209 16298 8219 16298 8207 16298 8209 16299 8207 16299 8206 16299 8206 16300 8207 16300 8218 16300 8206 16301 8218 16301 8205 16301 4831 16302 4832 16302 8203 16302 8203 16303 4832 16303 8208 16303 8203 16304 8208 16304 8206 16304 8206 16305 8208 16305 8214 16305 8206 16306 8214 16306 8209 16306 8209 16307 8214 16307 8215 16307 8209 16308 8215 16308 1763 16308 1763 16309 8215 16309 1756 16309 8216 16310 8210 16310 8199 16310 8199 16311 8210 16311 8211 16311 8199 16312 8211 16312 8200 16312 8200 16313 8211 16313 8213 16313 8200 16314 8213 16314 4834 16314 4834 16315 8213 16315 8212 16315 4832 16316 8212 16316 8208 16316 8208 16317 8212 16317 8213 16317 8208 16318 8213 16318 8214 16318 8214 16319 8213 16319 8211 16319 8214 16320 8211 16320 8215 16320 8215 16321 8211 16321 8210 16321 8215 16322 8210 16322 1756 16322 1756 16323 8210 16323 8216 16323 1756 16324 8216 16324 8217 16324 8204 16325 8205 16325 8227 16325 8218 16326 8207 16326 8220 16326 8207 16327 8219 16327 8222 16327 8218 16328 8220 16328 8205 16328 8204 16329 8227 16329 8221 16329 8207 16330 8222 16330 8220 16330 8220 16331 8222 16331 1762 16331 8220 16332 1762 16332 8228 16332 8228 16333 1762 16333 1760 16333 8228 16334 1760 16334 8230 16334 8230 16335 1760 16335 8223 16335 8230 16336 8223 16336 8231 16336 8231 16337 8223 16337 1759 16337 8231 16338 1759 16338 8232 16338 8232 16339 1759 16339 8224 16339 8232 16340 8224 16340 8225 16340 8224 16341 4970 16341 8225 16341 8225 16342 4970 16342 8243 16342 8225 16343 8243 16343 8226 16343 8205 16344 8220 16344 8227 16344 8227 16345 8220 16345 8228 16345 8227 16346 8228 16346 8236 16346 8236 16347 8228 16347 8230 16347 8236 16348 8230 16348 8229 16348 8229 16349 8230 16349 8231 16349 8229 16350 8231 16350 8238 16350 8238 16351 8231 16351 8232 16351 8238 16352 8232 16352 8239 16352 8239 16353 8232 16353 8225 16353 8239 16354 8225 16354 8233 16354 8233 16355 8225 16355 8226 16355 8233 16356 8226 16356 8240 16356 8221 16357 8227 16357 8234 16357 8234 16358 8227 16358 8236 16358 8234 16359 8236 16359 8235 16359 8235 16360 8236 16360 8229 16360 8235 16361 8229 16361 8237 16361 8237 16362 8229 16362 8238 16362 8237 16363 8238 16363 4810 16363 4810 16364 8238 16364 8239 16364 4810 16365 8239 16365 4812 16365 4812 16366 8239 16366 8233 16366 4812 16367 8233 16367 4813 16367 4813 16368 8233 16368 8240 16368 4813 16369 8240 16369 8241 16369 4969 16370 8242 16370 8247 16370 4970 16371 4969 16371 8243 16371 8243 16372 4969 16372 8247 16372 8243 16373 8247 16373 8226 16373 8226 16374 8247 16374 8259 16374 8226 16375 8259 16375 8240 16375 8240 16376 8259 16376 8244 16376 8240 16377 8244 16377 8241 16377 8241 16378 8244 16378 8245 16378 8246 16379 8259 16379 8247 16379 8264 16380 4972 16380 8248 16380 8248 16381 4972 16381 8249 16381 8248 16382 8249 16382 8262 16382 8262 16383 8249 16383 8250 16383 8262 16384 8250 16384 8272 16384 8257 16385 8266 16385 8256 16385 8256 16386 8266 16386 8265 16386 8256 16387 8265 16387 8263 16387 8251 16388 8253 16388 8252 16388 8252 16389 8253 16389 4865 16389 4865 16390 4866 16390 8252 16390 8252 16391 4866 16391 8245 16391 8252 16392 8245 16392 8244 16392 8258 16393 8254 16393 8253 16393 8253 16394 8254 16394 8255 16394 8253 16395 8255 16395 4865 16395 8263 16396 8246 16396 8256 16396 8256 16397 8246 16397 8247 16397 8256 16398 8247 16398 8257 16398 8257 16399 8247 16399 8242 16399 4863 16400 8258 16400 8260 16400 8260 16401 8258 16401 8253 16401 8260 16402 8253 16402 8261 16402 8261 16403 8253 16403 8251 16403 8261 16404 8251 16404 8263 16404 8263 16405 8251 16405 8252 16405 8263 16406 8252 16406 8246 16406 8246 16407 8252 16407 8244 16407 8246 16408 8244 16408 8259 16408 1752 16409 4863 16409 8274 16409 8274 16410 4863 16410 8260 16410 8274 16411 8260 16411 8272 16411 8272 16412 8260 16412 8261 16412 8272 16413 8261 16413 8262 16413 8262 16414 8261 16414 8263 16414 8262 16415 8263 16415 8248 16415 8248 16416 8263 16416 8265 16416 8248 16417 8265 16417 8264 16417 8264 16418 8265 16418 8266 16418 8274 16419 8272 16419 8276 16419 8282 16420 8283 16420 8275 16420 8250 16421 8249 16421 8273 16421 8273 16422 8249 16422 8267 16422 8273 16423 8267 16423 8271 16423 8271 16424 8267 16424 8268 16424 8249 16425 4972 16425 8267 16425 8267 16426 4972 16426 4974 16426 8267 16427 4974 16427 8268 16427 8268 16428 4974 16428 8270 16428 8270 16429 8278 16429 8269 16429 8270 16430 8269 16430 8268 16430 8268 16431 8269 16431 8277 16431 8268 16432 8277 16432 8271 16432 8271 16433 8277 16433 8276 16433 8271 16434 8276 16434 8273 16434 8273 16435 8276 16435 8272 16435 8273 16436 8272 16436 8250 16436 1752 16437 8274 16437 8275 16437 8275 16438 8274 16438 8276 16438 8275 16439 8276 16439 8282 16439 8282 16440 8276 16440 8277 16440 8282 16441 8277 16441 8281 16441 8281 16442 8277 16442 8269 16442 8281 16443 8269 16443 8280 16443 8280 16444 8269 16444 8278 16444 8280 16445 8278 16445 1958 16445 8279 16446 8291 16446 8288 16446 1958 16447 8279 16447 8280 16447 8280 16448 8279 16448 8288 16448 8280 16449 8288 16449 8281 16449 8281 16450 8288 16450 8287 16450 8281 16451 8287 16451 8282 16451 8282 16452 8287 16452 8296 16452 8282 16453 8296 16453 8283 16453 8283 16454 8296 16454 8284 16454 8296 16455 8285 16455 8284 16455 8284 16456 8285 16456 1732 16456 8297 16457 8286 16457 1732 16457 8299 16458 5090 16458 5091 16458 8287 16459 8288 16459 8289 16459 8289 16460 8288 16460 8290 16460 8289 16461 8290 16461 8295 16461 8295 16462 8290 16462 8294 16462 8288 16463 8291 16463 8290 16463 8290 16464 8291 16464 8292 16464 8290 16465 8292 16465 8294 16465 8294 16466 8292 16466 8293 16466 5090 16467 8299 16467 8293 16467 8293 16468 8299 16468 8294 16468 8294 16469 8299 16469 8298 16469 8294 16470 8298 16470 8295 16470 8295 16471 8298 16471 8285 16471 8295 16472 8285 16472 8289 16472 8289 16473 8285 16473 8296 16473 8289 16474 8296 16474 8287 16474 1732 16475 8285 16475 8297 16475 8297 16476 8285 16476 8298 16476 8297 16477 8298 16477 8316 16477 8316 16478 8298 16478 8299 16478 8316 16479 8299 16479 8310 16479 8310 16480 8299 16480 5091 16480 8310 16481 5091 16481 5057 16481 8318 16482 8297 16482 8316 16482 8300 16483 8311 16483 8301 16483 8320 16484 8312 16484 8302 16484 8302 16485 8312 16485 8328 16485 8302 16486 8328 16486 8326 16486 8315 16487 8301 16487 8320 16487 8320 16488 8301 16488 8303 16488 8320 16489 8303 16489 8312 16489 8304 16490 8305 16490 8319 16490 8319 16491 8305 16491 4871 16491 8324 16492 4802 16492 8306 16492 8324 16493 8306 16493 8321 16493 8306 16494 8307 16494 8321 16494 8321 16495 8307 16495 8308 16495 8321 16496 8308 16496 8304 16496 8304 16497 8308 16497 8309 16497 8304 16498 8309 16498 8305 16498 8310 16499 5057 16499 8300 16499 8301 16500 8311 16500 8303 16500 8303 16501 8311 16501 8313 16501 8303 16502 8313 16502 8312 16502 8312 16503 8313 16503 8314 16503 8312 16504 8314 16504 8328 16504 8300 16505 8301 16505 8310 16505 8310 16506 8301 16506 8315 16506 8310 16507 8315 16507 8316 16507 8316 16508 8315 16508 8317 16508 8316 16509 8317 16509 8318 16509 8286 16510 8297 16510 4873 16510 4873 16511 8297 16511 8318 16511 4873 16512 8318 16512 4871 16512 4871 16513 8318 16513 8317 16513 4871 16514 8317 16514 8319 16514 8319 16515 8317 16515 8315 16515 8319 16516 8315 16516 8304 16516 8304 16517 8315 16517 8320 16517 8304 16518 8320 16518 8321 16518 8321 16519 8320 16519 8302 16519 8321 16520 8302 16520 8324 16520 8324 16521 8302 16521 8326 16521 8322 16522 5058 16522 8327 16522 4808 16523 4802 16523 8323 16523 8323 16524 4802 16524 8324 16524 8323 16525 8324 16525 8325 16525 8325 16526 8324 16526 8326 16526 8325 16527 8326 16527 8327 16527 8327 16528 8326 16528 8328 16528 8327 16529 8328 16529 8322 16529 8322 16530 8328 16530 8314 16530 1801 16531 8329 16531 8341 16531 8329 16532 8351 16532 8340 16532 8351 16533 8349 16533 8331 16533 8349 16534 4803 16534 8330 16534 8349 16535 8330 16535 8331 16535 8331 16536 8330 16536 8332 16536 8331 16537 8332 16537 8335 16537 8333 16538 8338 16538 8337 16538 8332 16539 8334 16539 8335 16539 8335 16540 8334 16540 8336 16540 8335 16541 8336 16541 8337 16541 8337 16542 8336 16542 4806 16542 8337 16543 4806 16543 8333 16543 8333 16544 8339 16544 8338 16544 8338 16545 8339 16545 4808 16545 8338 16546 4808 16546 8323 16546 8351 16547 8331 16547 8340 16547 8340 16548 8331 16548 8335 16548 8340 16549 8335 16549 8342 16549 8342 16550 8335 16550 8337 16550 8342 16551 8337 16551 8343 16551 8343 16552 8337 16552 8338 16552 8343 16553 8338 16553 8345 16553 8345 16554 8338 16554 8323 16554 8345 16555 8323 16555 8325 16555 8329 16556 8340 16556 8341 16556 8341 16557 8340 16557 8342 16557 8341 16558 8342 16558 8346 16558 8346 16559 8342 16559 8343 16559 8346 16560 8343 16560 8344 16560 8344 16561 8343 16561 8345 16561 8344 16562 8345 16562 8347 16562 8347 16563 8345 16563 8325 16563 8347 16564 8325 16564 8327 16564 1801 16565 8341 16565 1800 16565 1800 16566 8341 16566 8346 16566 1800 16567 8346 16567 1793 16567 1793 16568 8346 16568 8344 16568 1793 16569 8344 16569 1794 16569 1794 16570 8344 16570 8347 16570 1794 16571 8347 16571 1788 16571 1788 16572 8347 16572 8327 16572 1788 16573 8327 16573 5058 16573 4838 16574 4803 16574 8348 16574 8348 16575 4803 16575 8349 16575 8348 16576 8349 16576 8350 16576 8350 16577 8349 16577 8351 16577 8350 16578 8351 16578 8358 16578 8358 16579 8351 16579 8329 16579 8352 16580 4838 16580 8353 16580 8353 16581 4838 16581 8348 16581 8353 16582 8348 16582 8354 16582 8354 16583 8348 16583 8350 16583 8354 16584 8350 16584 8357 16584 8357 16585 8350 16585 8358 16585 4836 16586 8352 16586 8360 16586 8360 16587 8352 16587 8353 16587 8360 16588 8353 16588 8355 16588 8355 16589 8353 16589 8354 16589 8355 16590 8354 16590 8356 16590 8356 16591 8354 16591 8357 16591 8356 16592 8357 16592 1791 16592 1791 16593 8357 16593 8358 16593 1791 16594 8358 16594 1792 16594 1792 16595 8358 16595 8329 16595 1792 16596 8329 16596 1801 16596 8362 16597 4836 16597 8363 16597 8363 16598 4836 16598 8360 16598 8363 16599 8360 16599 8359 16599 8359 16600 8360 16600 8355 16600 8359 16601 8355 16601 8361 16601 8361 16602 8355 16602 8356 16602 8361 16603 8356 16603 1790 16603 1790 16604 8356 16604 1791 16604 1693 16605 8362 16605 8363 16605 1693 16606 8363 16606 8364 16606 8364 16607 8363 16607 8359 16607 8364 16608 8359 16608 8365 16608 8359 16609 8361 16609 8365 16609 8365 16610 8361 16610 1790 16610 8365 16611 1790 16611 1501 16611 1822 16612 8366 16612 8367 16612 8381 16613 1478 16613 8367 16613 8367 16614 1478 16614 8368 16614 8367 16615 8368 16615 1822 16615 8381 16616 8383 16616 1478 16616 1478 16617 8383 16617 8369 16617 1478 16618 8369 16618 1479 16618 1827 16619 8373 16619 8379 16619 4847 16620 4846 16620 8384 16620 8384 16621 4846 16621 8376 16621 8384 16622 8376 16622 8372 16622 8372 16623 8376 16623 8371 16623 1828 16624 1830 16624 8370 16624 8370 16625 1830 16625 8386 16625 8370 16626 8386 16626 8371 16626 8371 16627 8386 16627 8385 16627 8371 16628 8385 16628 8372 16628 8373 16629 1828 16629 8379 16629 8379 16630 1828 16630 8370 16630 8379 16631 8370 16631 8374 16631 8374 16632 8370 16632 8371 16632 8374 16633 8371 16633 8377 16633 8377 16634 8371 16634 8376 16634 8377 16635 8376 16635 8375 16635 8375 16636 8376 16636 4846 16636 8375 16637 4842 16637 8377 16637 8377 16638 4842 16638 8378 16638 8377 16639 8378 16639 8374 16639 8374 16640 8378 16640 8382 16640 8374 16641 8382 16641 8379 16641 8379 16642 8382 16642 8380 16642 8379 16643 8380 16643 1827 16643 1827 16644 8380 16644 1825 16644 8366 16645 1825 16645 8367 16645 8367 16646 1825 16646 8380 16646 8367 16647 8380 16647 8381 16647 8381 16648 8380 16648 8382 16648 8381 16649 8382 16649 8383 16649 8383 16650 8382 16650 8378 16650 8383 16651 8378 16651 8369 16651 8369 16652 8378 16652 4842 16652 8384 16653 8372 16653 8401 16653 8385 16654 8386 16654 8388 16654 8386 16655 1830 16655 8387 16655 8385 16656 8388 16656 8372 16656 8384 16657 8401 16657 4847 16657 8386 16658 8387 16658 8388 16658 8388 16659 8387 16659 8389 16659 8388 16660 8389 16660 8397 16660 8397 16661 8389 16661 1832 16661 8397 16662 1832 16662 8398 16662 8398 16663 1832 16663 8390 16663 8398 16664 8390 16664 8399 16664 8399 16665 8390 16665 1833 16665 8399 16666 1833 16666 8400 16666 8400 16667 1833 16667 8392 16667 8400 16668 8392 16668 8391 16668 8391 16669 8392 16669 8393 16669 8391 16670 8393 16670 8394 16670 8393 16671 8395 16671 8394 16671 8394 16672 8395 16672 8413 16672 8394 16673 8413 16673 8396 16673 8372 16674 8388 16674 8401 16674 8401 16675 8388 16675 8397 16675 8401 16676 8397 16676 8402 16676 8402 16677 8397 16677 8398 16677 8402 16678 8398 16678 8404 16678 8404 16679 8398 16679 8399 16679 8404 16680 8399 16680 8405 16680 8405 16681 8399 16681 8400 16681 8405 16682 8400 16682 8407 16682 8407 16683 8400 16683 8391 16683 8407 16684 8391 16684 8408 16684 8408 16685 8391 16685 8394 16685 8408 16686 8394 16686 8409 16686 8409 16687 8394 16687 8396 16687 8409 16688 8396 16688 8414 16688 4847 16689 8401 16689 4824 16689 4824 16690 8401 16690 8402 16690 4824 16691 8402 16691 4825 16691 4825 16692 8402 16692 8404 16692 4825 16693 8404 16693 8403 16693 8403 16694 8404 16694 8405 16694 8403 16695 8405 16695 8406 16695 8406 16696 8405 16696 8407 16696 8406 16697 8407 16697 4830 16697 4830 16698 8407 16698 8408 16698 4830 16699 8408 16699 4829 16699 4829 16700 8408 16700 8409 16700 4829 16701 8409 16701 8410 16701 8410 16702 8409 16702 8414 16702 8410 16703 8414 16703 8415 16703 8412 16704 5218 16704 8411 16704 8395 16705 8412 16705 8413 16705 8413 16706 8412 16706 8411 16706 8413 16707 8411 16707 8396 16707 8396 16708 8411 16708 8417 16708 8396 16709 8417 16709 8414 16709 8414 16710 8417 16710 8433 16710 8414 16711 8433 16711 8415 16711 8415 16712 8433 16712 4856 16712 8416 16713 8417 16713 8411 16713 5217 16714 8419 16714 8418 16714 8418 16715 8419 16715 8420 16715 8418 16716 8420 16716 8421 16716 8421 16717 8420 16717 8438 16717 8421 16718 8438 16718 8435 16718 8422 16719 8423 16719 8424 16719 8424 16720 8423 16720 8436 16720 8424 16721 8436 16721 8429 16721 4860 16722 8425 16722 8432 16722 8425 16723 4857 16723 8432 16723 8432 16724 4857 16724 4856 16724 8432 16725 4856 16725 8433 16725 8432 16726 8426 16726 4860 16726 4860 16727 8426 16727 8427 16727 4860 16728 8427 16728 4861 16728 4861 16729 8427 16729 8428 16729 8429 16730 8416 16730 8424 16730 8424 16731 8416 16731 8411 16731 8424 16732 8411 16732 8422 16732 8422 16733 8411 16733 5218 16733 8434 16734 8428 16734 8430 16734 8430 16735 8428 16735 8427 16735 8430 16736 8427 16736 8431 16736 8431 16737 8427 16737 8426 16737 8431 16738 8426 16738 8429 16738 8429 16739 8426 16739 8432 16739 8429 16740 8432 16740 8416 16740 8416 16741 8432 16741 8433 16741 8416 16742 8433 16742 8417 16742 1696 16743 8434 16743 8437 16743 8437 16744 8434 16744 8430 16744 8437 16745 8430 16745 8435 16745 8435 16746 8430 16746 8431 16746 8435 16747 8431 16747 8421 16747 8421 16748 8431 16748 8429 16748 8421 16749 8429 16749 8418 16749 8418 16750 8429 16750 8436 16750 8418 16751 8436 16751 5217 16751 5217 16752 8436 16752 8423 16752 8437 16753 8435 16753 8445 16753 8447 16754 1719 16754 1720 16754 8438 16755 8420 16755 8444 16755 8444 16756 8420 16756 8439 16756 8444 16757 8439 16757 8443 16757 8443 16758 8439 16758 8441 16758 8420 16759 8419 16759 8439 16759 8439 16760 8419 16760 5239 16760 8439 16761 5239 16761 8441 16761 8441 16762 5239 16762 5240 16762 5240 16763 8440 16763 8446 16763 5240 16764 8446 16764 8441 16764 8441 16765 8446 16765 8442 16765 8441 16766 8442 16766 8443 16766 8443 16767 8442 16767 8445 16767 8443 16768 8445 16768 8444 16768 8444 16769 8445 16769 8435 16769 8444 16770 8435 16770 8438 16770 1696 16771 8437 16771 1720 16771 1720 16772 8437 16772 8445 16772 1720 16773 8445 16773 8447 16773 8447 16774 8445 16774 8442 16774 8447 16775 8442 16775 8448 16775 8448 16776 8442 16776 8446 16776 8448 16777 8446 16777 8451 16777 8451 16778 8446 16778 8440 16778 8451 16779 8440 16779 8452 16779 1853 16780 8456 16780 8450 16780 8453 16781 1719 16781 8464 16781 8464 16782 1719 16782 8447 16782 8464 16783 8447 16783 8449 16783 8449 16784 8447 16784 8448 16784 8449 16785 8448 16785 8450 16785 8450 16786 8448 16786 8451 16786 8450 16787 8451 16787 1853 16787 1853 16788 8451 16788 8452 16788 8464 16789 8463 16789 8453 16789 8453 16790 8463 16790 1712 16790 8467 16791 8454 16791 1712 16791 8459 16792 5165 16792 8455 16792 8449 16793 8450 16793 8462 16793 8462 16794 8450 16794 8457 16794 8462 16795 8457 16795 8461 16795 8461 16796 8457 16796 8458 16796 8450 16797 8456 16797 8457 16797 8457 16798 8456 16798 5160 16798 8457 16799 5160 16799 8458 16799 8458 16800 5160 16800 8460 16800 5165 16801 8459 16801 8460 16801 8460 16802 8459 16802 8458 16802 8458 16803 8459 16803 8465 16803 8458 16804 8465 16804 8461 16804 8461 16805 8465 16805 8463 16805 8461 16806 8463 16806 8462 16806 8462 16807 8463 16807 8464 16807 8462 16808 8464 16808 8449 16808 1712 16809 8463 16809 8467 16809 8467 16810 8463 16810 8465 16810 8467 16811 8465 16811 8468 16811 8468 16812 8465 16812 8459 16812 8468 16813 8459 16813 8479 16813 8479 16814 8459 16814 8455 16814 8479 16815 8455 16815 5166 16815 8466 16816 8467 16816 8468 16816 8478 16817 5171 16817 8471 16817 8472 16818 8469 16818 8485 16818 8485 16819 8469 16819 8470 16819 8485 16820 8470 16820 8489 16820 8480 16821 8471 16821 8472 16821 8472 16822 8471 16822 8473 16822 8472 16823 8473 16823 8469 16823 8484 16824 4853 16824 8483 16824 8483 16825 4853 16825 8482 16825 8487 16826 4855 16826 8474 16826 8487 16827 8474 16827 8475 16827 8475 16828 8474 16828 8476 16828 8475 16829 8476 16829 8484 16829 8484 16830 8476 16830 8477 16830 8484 16831 8477 16831 4853 16831 8479 16832 5166 16832 8478 16832 8471 16833 5171 16833 8473 16833 8473 16834 5171 16834 5147 16834 8473 16835 5147 16835 8469 16835 8469 16836 5147 16836 5172 16836 8469 16837 5172 16837 8470 16837 8478 16838 8471 16838 8479 16838 8479 16839 8471 16839 8480 16839 8479 16840 8480 16840 8468 16840 8468 16841 8480 16841 8481 16841 8468 16842 8481 16842 8466 16842 8454 16843 8467 16843 4852 16843 4852 16844 8467 16844 8466 16844 4852 16845 8466 16845 8482 16845 8482 16846 8466 16846 8481 16846 8482 16847 8481 16847 8483 16847 8483 16848 8481 16848 8480 16848 8483 16849 8480 16849 8484 16849 8484 16850 8480 16850 8472 16850 8484 16851 8472 16851 8475 16851 8475 16852 8472 16852 8485 16852 8475 16853 8485 16853 8487 16853 8487 16854 8485 16854 8489 16854 5170 16855 5169 16855 8490 16855 4817 16856 4855 16856 8486 16856 8486 16857 4855 16857 8487 16857 8486 16858 8487 16858 8488 16858 8488 16859 8487 16859 8489 16859 8488 16860 8489 16860 8490 16860 8490 16861 8489 16861 8470 16861 8490 16862 8470 16862 5170 16862 5170 16863 8470 16863 5172 16863 8488 16864 8490 16864 8513 16864 8491 16865 8519 16865 4815 16865 8492 16866 8517 16866 8495 16866 8495 16867 8517 16867 8491 16867 1820 16868 8493 16868 8494 16868 8494 16869 8493 16869 8492 16869 8491 16870 4815 16870 8495 16870 8495 16871 4815 16871 8496 16871 8495 16872 8496 16872 8497 16872 8497 16873 8496 16873 8498 16873 8497 16874 8498 16874 8502 16874 8502 16875 8498 16875 4819 16875 8502 16876 4819 16876 8504 16876 8504 16877 4819 16877 8499 16877 8504 16878 8499 16878 8505 16878 8505 16879 8499 16879 8500 16879 8505 16880 8500 16880 8501 16880 8501 16881 8500 16881 4817 16881 8501 16882 4817 16882 8486 16882 8492 16883 8495 16883 8494 16883 8494 16884 8495 16884 8497 16884 8494 16885 8497 16885 8508 16885 8508 16886 8497 16886 8502 16886 8508 16887 8502 16887 8503 16887 8503 16888 8502 16888 8504 16888 8503 16889 8504 16889 8509 16889 8509 16890 8504 16890 8505 16890 8509 16891 8505 16891 8511 16891 8511 16892 8505 16892 8501 16892 8511 16893 8501 16893 8513 16893 8513 16894 8501 16894 8486 16894 8513 16895 8486 16895 8488 16895 1820 16896 8494 16896 8506 16896 8506 16897 8494 16897 8508 16897 8506 16898 8508 16898 8507 16898 8507 16899 8508 16899 8503 16899 8507 16900 8503 16900 1818 16900 1818 16901 8503 16901 8509 16901 1818 16902 8509 16902 8510 16902 8510 16903 8509 16903 8511 16903 8510 16904 8511 16904 8512 16904 8512 16905 8511 16905 8513 16905 8512 16906 8513 16906 8514 16906 8514 16907 8513 16907 8490 16907 8514 16908 8490 16908 5169 16908 8518 16909 8515 16909 8519 16909 8493 16910 8522 16910 8492 16910 8492 16911 8522 16911 8516 16911 8492 16912 8516 16912 8517 16912 8517 16913 8516 16913 8518 16913 8517 16914 8518 16914 8491 16914 8491 16915 8518 16915 8519 16915 4840 16916 8515 16916 8526 16916 8526 16917 8515 16917 8518 16917 8526 16918 8518 16918 8520 16918 8520 16919 8518 16919 8516 16919 8520 16920 8516 16920 8521 16920 8521 16921 8516 16921 8522 16921 8521 16922 8522 16922 8523 16922 8523 16923 8522 16923 8493 16923 8523 16924 8493 16924 1820 16924 8528 16925 4840 16925 8524 16925 8524 16926 4840 16926 8526 16926 8524 16927 8526 16927 8525 16927 8525 16928 8526 16928 8520 16928 8525 16929 8520 16929 8531 16929 8531 16930 8520 16930 8521 16930 8531 16931 8521 16931 8532 16931 8532 16932 8521 16932 8523 16932 8527 16933 8528 16933 8533 16933 8533 16934 8528 16934 8524 16934 8533 16935 8524 16935 8529 16935 8529 16936 8524 16936 8525 16936 8529 16937 8525 16937 8530 16937 8530 16938 8525 16938 8531 16938 8530 16939 8531 16939 1816 16939 1816 16940 8531 16940 8532 16940 1689 16941 8527 16941 8533 16941 1689 16942 8533 16942 1473 16942 1473 16943 8533 16943 8529 16943 1473 16944 8529 16944 8534 16944 8534 16945 8529 16945 8530 16945 8534 16946 8530 16946 8535 16946 8535 16947 8530 16947 1816 16947 8535 16948 1816 16948 1513 16948 2421 16949 2420 16949 8550 16949 8549 16950 8544 16950 8548 16950 8543 16951 8536 16951 8542 16951 8536 16952 2445 16952 8542 16952 8542 16953 2445 16953 8537 16953 8542 16954 8537 16954 8538 16954 8538 16955 8537 16955 8539 16955 8538 16956 8539 16956 8540 16956 8540 16957 8539 16957 8556 16957 8540 16958 8556 16958 2373 16958 2373 16959 8556 16959 8541 16959 2373 16960 2375 16960 8540 16960 8540 16961 2375 16961 8545 16961 8540 16962 8545 16962 8538 16962 8538 16963 8545 16963 8547 16963 8538 16964 8547 16964 8542 16964 8542 16965 8547 16965 8548 16965 8542 16966 8548 16966 8543 16966 8543 16967 8548 16967 8544 16967 2375 16968 2377 16968 8545 16968 8545 16969 2377 16969 8546 16969 8545 16970 8546 16970 8547 16970 8547 16971 8546 16971 8553 16971 8547 16972 8553 16972 8548 16972 8548 16973 8553 16973 8550 16973 8548 16974 8550 16974 8549 16974 8549 16975 8550 16975 2420 16975 2438 16976 2421 16976 8551 16976 8551 16977 2421 16977 8550 16977 8551 16978 8550 16978 8552 16978 8552 16979 8550 16979 8553 16979 8552 16980 8553 16980 8554 16980 8554 16981 8553 16981 8546 16981 8554 16982 8546 16982 8555 16982 8555 16983 8546 16983 2377 16983 2422 16984 8579 16984 8578 16984 1745 16985 8541 16985 8556 16985 8571 16986 1745 16986 8574 16986 8574 16987 1745 16987 8556 16987 8574 16988 8556 16988 8575 16988 8575 16989 8556 16989 8539 16989 8575 16990 8539 16990 8578 16990 8578 16991 8539 16991 8537 16991 8578 16992 8537 16992 2422 16992 2422 16993 8537 16993 2445 16993 2435 16994 8557 16994 8569 16994 8566 16995 1578 16995 8558 16995 8561 16996 2438 16996 8563 16996 8563 16997 2438 16997 8551 16997 8563 16998 8551 16998 8559 16998 8559 16999 8551 16999 8552 16999 8559 17000 8552 17000 8560 17000 8560 17001 8552 17001 8554 17001 8560 17002 8554 17002 1575 17002 1575 17003 8554 17003 8555 17003 2419 17004 8561 17004 8562 17004 8562 17005 8561 17005 8563 17005 8562 17006 8563 17006 8564 17006 8564 17007 8563 17007 8559 17007 8564 17008 8559 17008 8567 17008 8567 17009 8559 17009 8560 17009 8567 17010 8560 17010 1576 17010 1576 17011 8560 17011 1575 17011 8557 17012 2419 17012 8569 17012 8569 17013 2419 17013 8562 17013 8569 17014 8562 17014 8565 17014 8565 17015 8562 17015 8564 17015 8565 17016 8564 17016 8558 17016 8558 17017 8564 17017 8567 17017 8558 17018 8567 17018 8566 17018 8566 17019 8567 17019 1576 17019 2416 17020 2435 17020 8583 17020 8583 17021 2435 17021 8569 17021 8583 17022 8569 17022 8568 17022 8568 17023 8569 17023 8565 17023 8568 17024 8565 17024 8570 17024 8570 17025 8565 17025 8558 17025 8570 17026 8558 17026 1581 17026 1581 17027 8558 17027 1578 17027 1737 17028 8571 17028 8574 17028 8572 17029 1737 17029 8573 17029 8573 17030 1737 17030 8574 17030 8573 17031 8574 17031 8576 17031 8576 17032 8574 17032 8575 17032 8576 17033 8575 17033 8577 17033 8577 17034 8575 17034 8578 17034 8577 17035 8578 17035 2423 17035 2423 17036 8578 17036 8579 17036 8597 17037 8580 17037 8584 17037 1581 17038 8581 17038 8570 17038 8570 17039 8581 17039 8582 17039 8570 17040 8582 17040 8568 17040 8583 17041 8568 17041 8591 17041 8586 17042 2414 17042 8595 17042 8595 17043 2414 17043 2416 17043 8595 17044 2416 17044 8583 17044 8584 17045 8585 17045 8597 17045 8597 17046 8585 17046 8587 17046 8597 17047 8587 17047 8586 17047 8586 17048 8587 17048 8588 17048 8586 17049 8588 17049 2414 17049 8581 17050 1584 17050 8582 17050 8582 17051 1584 17051 8589 17051 8582 17052 8589 17052 8592 17052 8592 17053 8589 17053 1585 17053 8592 17054 1585 17054 8590 17054 8590 17055 1585 17055 8609 17055 8590 17056 8609 17056 8594 17056 8568 17057 8582 17057 8591 17057 8591 17058 8582 17058 8592 17058 8591 17059 8592 17059 8593 17059 8593 17060 8592 17060 8590 17060 8593 17061 8590 17061 8596 17061 8596 17062 8590 17062 8594 17062 8596 17063 8594 17063 8607 17063 8583 17064 8591 17064 8595 17064 8595 17065 8591 17065 8593 17065 8595 17066 8593 17066 8586 17066 8586 17067 8593 17067 8596 17067 8586 17068 8596 17068 8597 17068 8597 17069 8596 17069 8607 17069 8597 17070 8607 17070 8580 17070 1738 17071 8572 17071 8601 17071 8601 17072 8572 17072 8573 17072 8601 17073 8573 17073 8603 17073 8603 17074 8573 17074 8576 17074 8603 17075 8576 17075 8598 17075 8598 17076 8576 17076 8577 17076 8598 17077 8577 17077 8599 17077 8599 17078 8577 17078 2423 17078 8600 17079 1738 17079 8601 17079 2424 17080 8602 17080 8627 17080 8599 17081 2424 17081 8598 17081 8598 17082 2424 17082 8627 17082 8598 17083 8627 17083 8603 17083 8603 17084 8627 17084 8626 17084 8603 17085 8626 17085 8601 17085 8601 17086 8626 17086 8604 17086 8601 17087 8604 17087 8600 17087 8600 17088 8604 17088 8624 17088 1598 17089 8605 17089 8618 17089 2595 17090 8584 17090 8606 17090 8606 17091 8584 17091 8580 17091 8606 17092 8580 17092 8612 17092 8612 17093 8580 17093 8607 17093 8612 17094 8607 17094 8611 17094 8611 17095 8607 17095 8594 17095 8611 17096 8594 17096 8608 17096 8608 17097 8594 17097 8609 17097 8608 17098 8610 17098 8611 17098 8611 17099 8610 17099 8615 17099 8611 17100 8615 17100 8612 17100 8612 17101 8615 17101 8616 17101 8612 17102 8616 17102 8606 17102 8606 17103 8616 17103 8613 17103 8606 17104 8613 17104 2595 17104 2595 17105 8613 17105 8614 17105 8610 17106 1598 17106 8615 17106 8615 17107 1598 17107 8618 17107 8615 17108 8618 17108 8616 17108 8616 17109 8618 17109 8617 17109 8616 17110 8617 17110 8613 17110 8613 17111 8617 17111 8622 17111 8613 17112 8622 17112 8614 17112 8614 17113 8622 17113 2610 17113 8605 17114 8619 17114 8618 17114 8618 17115 8619 17115 8620 17115 8618 17116 8620 17116 8617 17116 8617 17117 8620 17117 8621 17117 8617 17118 8621 17118 8622 17118 8622 17119 8621 17119 8623 17119 8622 17120 8623 17120 2610 17120 2610 17121 8623 17121 2607 17121 1740 17122 8624 17122 8644 17122 8644 17123 8624 17123 8604 17123 8644 17124 8604 17124 8625 17124 8625 17125 8604 17125 8626 17125 8625 17126 8626 17126 8642 17126 8642 17127 8626 17127 8627 17127 8642 17128 8627 17128 8628 17128 8628 17129 8627 17129 8602 17129 3581 17130 3580 17130 8638 17130 8649 17131 8648 17131 8636 17131 8632 17132 8629 17132 8631 17132 8631 17133 8629 17133 8630 17133 8636 17134 8648 17134 8634 17134 8634 17135 8648 17135 8646 17135 8634 17136 8646 17136 8632 17136 8632 17137 8646 17137 8629 17137 8631 17138 8633 17138 8632 17138 8632 17139 8633 17139 8637 17139 8632 17140 8637 17140 8634 17140 8634 17141 8637 17141 8635 17141 8634 17142 8635 17142 8636 17142 8636 17143 8635 17143 8639 17143 8636 17144 8639 17144 1595 17144 8633 17145 3581 17145 8637 17145 8637 17146 3581 17146 8638 17146 8637 17147 8638 17147 8635 17147 8635 17148 8638 17148 8641 17148 8635 17149 8641 17149 8639 17149 8639 17150 8641 17150 8640 17150 8639 17151 8640 17151 1596 17151 8619 17152 1596 17152 8620 17152 8620 17153 1596 17153 8640 17153 8620 17154 8640 17154 8621 17154 8621 17155 8640 17155 8641 17155 8621 17156 8641 17156 8623 17156 8623 17157 8641 17157 8638 17157 8623 17158 8638 17158 2607 17158 2607 17159 8638 17159 3580 17159 8645 17160 1740 17160 8644 17160 8628 17161 2425 17161 8642 17161 8642 17162 2425 17162 8643 17162 8642 17163 8643 17163 8625 17163 8625 17164 8643 17164 8656 17164 8625 17165 8656 17165 8644 17165 8644 17166 8656 17166 8654 17166 8644 17167 8654 17167 8645 17167 8645 17168 8654 17168 8652 17168 2383 17169 8630 17169 8629 17169 2383 17170 8629 17170 8660 17170 8660 17171 8629 17171 8646 17171 8660 17172 8646 17172 8661 17172 8661 17173 8646 17173 8647 17173 8647 17174 8646 17174 8648 17174 8647 17175 8648 17175 8663 17175 8663 17176 8648 17176 8649 17176 8663 17177 8649 17177 8650 17177 8651 17178 8652 17178 8653 17178 8653 17179 8652 17179 8654 17179 8653 17180 8654 17180 8655 17180 8655 17181 8654 17181 8656 17181 8655 17182 8656 17182 8669 17182 8669 17183 8656 17183 8643 17183 8669 17184 8643 17184 2463 17184 2463 17185 8643 17185 2425 17185 8657 17186 8658 17186 8664 17186 8664 17187 8658 17187 8673 17187 8664 17188 8673 17188 8662 17188 8662 17189 8673 17189 8671 17189 8662 17190 8671 17190 8659 17190 8659 17191 8671 17191 8670 17191 8659 17192 8670 17192 2382 17192 2382 17193 8670 17193 2387 17193 2382 17194 2383 17194 8659 17194 8659 17195 2383 17195 8660 17195 8659 17196 8660 17196 8662 17196 8662 17197 8660 17197 8661 17197 8662 17198 8661 17198 8664 17198 8650 17199 8657 17199 8663 17199 8663 17200 8657 17200 8664 17200 8663 17201 8664 17201 8647 17201 8647 17202 8664 17202 8661 17202 8666 17203 8651 17203 8653 17203 1729 17204 8666 17204 8665 17204 8665 17205 8666 17205 8653 17205 8665 17206 8653 17206 8667 17206 8667 17207 8653 17207 8655 17207 8667 17208 8655 17208 8668 17208 8668 17209 8655 17209 8669 17209 8668 17210 8669 17210 8680 17210 8680 17211 8669 17211 2463 17211 2384 17212 2387 17212 8674 17212 8674 17213 2387 17213 8670 17213 8674 17214 8670 17214 8675 17214 8675 17215 8670 17215 8671 17215 8675 17216 8671 17216 8676 17216 8676 17217 8671 17217 8673 17217 5918 17218 8676 17218 8672 17218 8672 17219 8676 17219 8673 17219 8672 17220 8673 17220 8658 17220 8691 17221 2384 17221 8690 17221 8690 17222 2384 17222 8674 17222 8690 17223 8674 17223 8689 17223 8689 17224 8674 17224 8675 17224 8689 17225 8675 17225 8686 17225 8686 17226 8675 17226 8676 17226 8686 17227 8676 17227 8684 17227 8684 17228 8676 17228 5918 17228 1733 17229 1729 17229 8665 17229 8678 17230 8677 17230 1733 17230 1733 17231 8665 17231 8678 17231 8678 17232 8665 17232 8667 17232 8678 17233 8667 17233 8702 17233 8702 17234 8667 17234 8668 17234 8702 17235 8668 17235 8679 17235 8680 17236 2534 17236 8668 17236 8668 17237 2534 17237 8681 17237 8668 17238 8681 17238 8679 17238 8679 17239 8681 17239 8682 17239 8679 17240 8682 17240 8683 17240 8684 17241 5918 17241 9232 17241 8684 17242 9232 17242 8686 17242 9232 17243 8685 17243 8686 17243 8686 17244 8685 17244 8687 17244 8686 17245 8687 17245 8689 17245 8689 17246 8687 17246 8688 17246 8689 17247 8688 17247 8690 17247 8690 17248 8688 17248 2386 17248 8690 17249 2386 17249 8691 17249 8694 17250 8707 17250 8695 17250 1731 17251 1750 17251 8692 17251 1749 17252 8693 17252 8701 17252 8701 17253 8693 17253 8677 17253 8696 17254 1741 17254 8694 17254 8694 17255 8695 17255 8696 17255 8696 17256 8695 17256 8706 17256 8696 17257 8706 17257 8697 17257 8697 17258 8706 17258 8700 17258 8697 17259 8700 17259 8698 17259 2053 17260 8709 17260 3319 17260 3319 17261 8709 17261 8699 17261 3319 17262 8699 17262 8700 17262 8700 17263 8699 17263 8710 17263 8700 17264 8710 17264 8698 17264 8677 17265 8678 17265 8701 17265 8701 17266 8678 17266 8702 17266 8701 17267 8702 17267 8703 17267 8703 17268 8702 17268 8679 17268 8703 17269 8679 17269 8704 17269 8704 17270 8679 17270 8683 17270 8704 17271 8683 17271 3315 17271 3316 17272 3319 17272 8705 17272 8705 17273 3319 17273 8700 17273 8705 17274 8700 17274 8708 17274 8708 17275 8700 17275 8706 17275 8708 17276 8706 17276 8692 17276 8692 17277 8706 17277 8695 17277 8692 17278 8695 17278 1731 17278 1731 17279 8695 17279 8707 17279 3315 17280 3316 17280 8704 17280 8704 17281 3316 17281 8705 17281 8704 17282 8705 17282 8703 17282 8703 17283 8705 17283 8708 17283 8703 17284 8708 17284 8701 17284 8701 17285 8708 17285 8692 17285 8701 17286 8692 17286 1749 17286 1749 17287 8692 17287 1750 17287 8711 17288 1743 17288 1741 17288 2053 17289 2051 17289 8709 17289 8709 17290 2051 17290 8713 17290 8709 17291 8713 17291 8699 17291 8699 17292 8713 17292 8710 17292 1741 17293 8696 17293 8711 17293 8711 17294 8696 17294 8697 17294 8711 17295 8697 17295 8712 17295 8712 17296 8697 17296 8713 17296 8713 17297 8697 17297 8698 17297 8713 17298 8698 17298 8710 17298 8712 17299 8713 17299 8714 17299 8713 17300 2051 17300 2050 17300 1743 17301 8711 17301 8720 17301 8720 17302 8711 17302 8712 17302 8713 17303 2050 17303 8714 17303 8714 17304 2050 17304 2040 17304 8714 17305 2040 17305 8715 17305 8715 17306 2040 17306 2039 17306 8715 17307 2039 17307 8721 17307 8721 17308 2039 17308 8716 17308 8721 17309 8716 17309 8722 17309 8722 17310 8716 17310 2049 17310 8722 17311 2049 17311 8717 17311 2049 17312 8718 17312 8717 17312 8717 17313 8718 17313 8719 17313 8717 17314 8719 17314 8742 17314 8712 17315 8714 17315 8720 17315 8720 17316 8714 17316 8715 17316 8720 17317 8715 17317 8723 17317 8723 17318 8715 17318 8721 17318 8723 17319 8721 17319 8724 17319 8724 17320 8721 17320 8722 17320 8724 17321 8722 17321 8725 17321 8725 17322 8722 17322 8717 17322 8725 17323 8717 17323 8726 17323 8726 17324 8717 17324 8742 17324 8726 17325 8742 17325 8741 17325 1743 17326 8720 17326 2360 17326 2360 17327 8720 17327 8723 17327 2360 17328 8723 17328 2366 17328 2366 17329 8723 17329 8724 17329 2366 17330 8724 17330 2363 17330 2363 17331 8724 17331 8725 17331 2363 17332 8725 17332 8727 17332 8727 17333 8725 17333 8726 17333 8727 17334 8726 17334 8728 17334 8728 17335 8726 17335 8741 17335 8728 17336 8741 17336 8729 17336 8735 17337 8729 17337 8741 17337 8731 17338 1246 17338 8730 17338 8760 17339 8731 17339 8759 17339 8759 17340 8731 17340 8730 17340 8759 17341 8730 17341 8732 17341 8732 17342 8730 17342 8737 17342 8732 17343 8737 17343 8733 17343 8733 17344 8737 17344 8739 17344 8733 17345 8739 17345 8734 17345 8734 17346 8739 17346 2032 17346 1246 17347 8735 17347 8730 17347 8730 17348 8735 17348 8736 17348 8730 17349 8736 17349 8737 17349 8737 17350 8736 17350 8738 17350 8737 17351 8738 17351 8739 17351 8739 17352 8738 17352 8740 17352 8739 17353 8740 17353 2032 17353 2032 17354 8740 17354 2047 17354 8735 17355 8741 17355 8736 17355 8736 17356 8741 17356 8742 17356 8736 17357 8742 17357 8738 17357 8738 17358 8742 17358 8719 17358 8738 17359 8719 17359 8740 17359 8740 17360 8719 17360 8718 17360 8740 17361 8718 17361 2047 17361 8743 17362 2395 17362 8745 17362 8743 17363 8745 17363 8744 17363 8744 17364 8745 17364 9279 17364 8744 17365 9279 17365 8751 17365 8751 17366 9279 17366 8747 17366 8751 17367 8747 17367 8746 17367 8746 17368 8747 17368 8749 17368 8749 17369 8747 17369 9280 17369 8749 17370 9280 17370 5931 17370 2393 17371 8743 17371 8748 17371 8748 17372 8743 17372 8744 17372 8748 17373 8744 17373 8750 17373 5931 17374 5930 17374 8749 17374 8749 17375 5930 17375 8754 17375 8749 17376 8754 17376 8746 17376 8746 17377 8754 17377 8750 17377 8746 17378 8750 17378 8751 17378 8751 17379 8750 17379 8744 17379 8769 17380 2393 17380 8752 17380 8752 17381 2393 17381 8748 17381 8752 17382 8748 17382 8767 17382 8767 17383 8748 17383 8750 17383 8767 17384 8750 17384 8753 17384 8753 17385 8750 17385 8754 17385 8753 17386 8754 17386 5922 17386 5922 17387 8754 17387 5930 17387 8756 17388 2707 17388 8757 17388 8757 17389 2707 17389 8774 17389 8757 17390 8774 17390 8758 17390 8758 17391 8774 17391 8773 17391 8758 17392 8773 17392 8761 17392 8761 17393 8773 17393 8755 17393 8761 17394 8755 17394 8762 17394 8762 17395 8755 17395 8771 17395 8734 17396 8756 17396 8733 17396 8733 17397 8756 17397 8757 17397 8733 17398 8757 17398 8732 17398 8732 17399 8757 17399 8758 17399 8732 17400 8758 17400 8759 17400 8759 17401 8758 17401 8761 17401 8759 17402 8761 17402 8760 17402 8760 17403 8761 17403 8762 17403 8763 17404 8764 17404 8777 17404 2391 17405 2394 17405 8765 17405 8765 17406 2394 17406 8770 17406 8765 17407 8770 17407 8780 17407 8780 17408 8770 17408 8768 17408 8780 17409 8768 17409 8766 17409 8766 17410 8768 17410 8763 17410 8766 17411 8763 17411 8778 17411 8778 17412 8763 17412 8777 17412 5922 17413 8764 17413 8753 17413 8753 17414 8764 17414 8763 17414 8753 17415 8763 17415 8767 17415 8767 17416 8763 17416 8768 17416 8767 17417 8768 17417 8752 17417 8752 17418 8768 17418 8770 17418 8752 17419 8770 17419 8769 17419 8769 17420 8770 17420 2394 17420 8772 17421 8771 17421 8755 17421 1241 17422 8772 17422 8784 17422 8784 17423 8772 17423 8755 17423 8784 17424 8755 17424 8785 17424 8785 17425 8755 17425 8773 17425 8785 17426 8773 17426 8787 17426 8787 17427 8773 17427 8774 17427 8787 17428 8774 17428 8786 17428 2706 17429 8775 17429 8776 17429 8786 17430 8774 17430 8776 17430 8776 17431 8774 17431 2707 17431 8776 17432 2707 17432 2706 17432 8777 17433 1572 17433 8778 17433 8778 17434 1572 17434 8800 17434 8778 17435 8800 17435 8766 17435 8766 17436 8800 17436 8779 17436 8766 17437 8779 17437 8780 17437 8780 17438 8779 17438 8801 17438 8780 17439 8801 17439 8765 17439 8765 17440 8801 17440 2392 17440 8765 17441 2392 17441 2391 17441 8784 17442 8804 17442 8781 17442 1241 17443 8784 17443 8782 17443 8782 17444 8784 17444 8781 17444 8782 17445 8781 17445 8783 17445 8804 17446 8784 17446 8805 17446 8805 17447 8784 17447 8785 17447 8805 17448 8785 17448 8806 17448 8775 17449 2705 17449 8776 17449 8776 17450 2705 17450 8807 17450 8776 17451 8807 17451 8786 17451 8786 17452 8807 17452 8788 17452 8786 17453 8788 17453 8787 17453 8787 17454 8788 17454 8806 17454 8787 17455 8806 17455 8785 17455 3578 17456 3579 17456 8795 17456 1602 17457 1603 17457 8792 17457 8792 17458 1603 17458 8789 17458 8792 17459 8789 17459 8793 17459 8793 17460 8789 17460 8790 17460 8793 17461 8790 17461 8796 17461 8796 17462 8790 17462 8822 17462 8796 17463 8822 17463 3574 17463 3574 17464 8822 17464 8823 17464 8791 17465 1602 17465 8799 17465 8799 17466 1602 17466 8792 17466 8799 17467 8792 17467 8794 17467 8794 17468 8792 17468 8793 17468 8794 17469 8793 17469 8795 17469 8795 17470 8793 17470 8796 17470 8795 17471 8796 17471 3578 17471 3578 17472 8796 17472 3574 17472 8797 17473 8791 17473 8798 17473 8798 17474 8791 17474 8799 17474 8798 17475 8799 17475 8802 17475 8802 17476 8799 17476 8794 17476 8802 17477 8794 17477 8803 17477 8803 17478 8794 17478 8795 17478 8803 17479 8795 17479 3573 17479 3573 17480 8795 17480 3579 17480 1572 17481 8797 17481 8800 17481 8800 17482 8797 17482 8798 17482 8800 17483 8798 17483 8779 17483 8779 17484 8798 17484 8802 17484 8779 17485 8802 17485 8801 17485 8801 17486 8802 17486 8803 17486 8801 17487 8803 17487 2392 17487 2392 17488 8803 17488 3573 17488 1240 17489 8783 17489 8781 17489 1239 17490 1240 17490 8839 17490 8839 17491 1240 17491 8781 17491 8839 17492 8781 17492 8838 17492 8838 17493 8781 17493 8804 17493 8838 17494 8804 17494 8837 17494 8837 17495 8804 17495 8805 17495 8837 17496 8805 17496 8835 17496 8835 17497 8805 17497 8806 17497 8835 17498 8806 17498 8834 17498 8834 17499 8806 17499 8788 17499 8834 17500 8788 17500 2702 17500 2702 17501 8788 17501 8807 17501 2702 17502 8807 17502 2703 17502 2703 17503 8807 17503 2705 17503 1606 17504 8813 17504 8816 17504 1609 17505 1612 17505 8814 17505 8814 17506 1612 17506 8808 17506 8814 17507 8808 17507 8809 17507 8809 17508 8808 17508 8810 17508 8809 17509 8810 17509 8811 17509 8811 17510 8810 17510 8860 17510 8811 17511 8860 17511 8812 17511 8812 17512 8860 17512 8859 17512 8813 17513 1609 17513 8816 17513 8816 17514 1609 17514 8814 17514 8816 17515 8814 17515 8818 17515 8818 17516 8814 17516 8809 17516 8818 17517 8809 17517 8815 17517 8815 17518 8809 17518 8811 17518 8815 17519 8811 17519 2650 17519 2650 17520 8811 17520 8812 17520 8820 17521 1606 17521 8817 17521 8817 17522 1606 17522 8816 17522 8817 17523 8816 17523 8821 17523 8821 17524 8816 17524 8818 17524 8821 17525 8818 17525 8824 17525 8824 17526 8818 17526 8815 17526 8824 17527 8815 17527 8819 17527 8819 17528 8815 17528 2650 17528 1603 17529 8820 17529 8789 17529 8789 17530 8820 17530 8817 17530 8789 17531 8817 17531 8790 17531 8790 17532 8817 17532 8821 17532 8790 17533 8821 17533 8822 17533 8822 17534 8821 17534 8824 17534 8822 17535 8824 17535 8823 17535 8823 17536 8824 17536 8819 17536 8833 17537 8825 17537 8826 17537 8826 17538 8825 17538 8843 17538 8826 17539 8843 17539 8827 17539 8827 17540 8843 17540 8855 17540 8827 17541 8855 17541 8836 17541 8836 17542 8855 17542 8829 17542 8836 17543 8829 17543 8828 17543 8828 17544 8829 17544 8830 17544 8828 17545 8830 17545 8831 17545 8831 17546 8830 17546 8842 17546 8831 17547 8842 17547 8832 17547 8832 17548 8842 17548 1230 17548 2702 17549 8833 17549 8834 17549 8834 17550 8833 17550 8826 17550 8834 17551 8826 17551 8835 17551 8835 17552 8826 17552 8827 17552 8835 17553 8827 17553 8837 17553 8837 17554 8827 17554 8836 17554 8837 17555 8836 17555 8838 17555 8838 17556 8836 17556 8828 17556 8838 17557 8828 17557 8839 17557 8839 17558 8828 17558 8831 17558 8839 17559 8831 17559 1239 17559 1239 17560 8831 17560 8832 17560 8858 17561 2711 17561 2709 17561 8841 17562 8840 17562 8851 17562 8851 17563 8840 17563 8854 17563 8829 17564 8841 17564 8830 17564 8830 17565 8841 17565 8851 17565 8830 17566 8851 17566 8842 17566 8842 17567 8851 17567 1230 17567 8825 17568 2713 17568 8843 17568 8843 17569 2713 17569 8856 17569 8843 17570 8856 17570 8855 17570 2713 17571 8844 17571 8856 17571 8856 17572 8844 17572 8845 17572 8856 17573 8845 17573 8857 17573 8857 17574 8845 17574 8846 17574 8848 17575 1222 17575 8847 17575 8852 17576 8906 17576 8853 17576 8853 17577 8906 17577 8848 17577 8853 17578 8848 17578 8849 17578 8849 17579 8848 17579 8847 17579 8849 17580 8847 17580 1226 17580 8854 17581 8850 17581 8851 17581 8851 17582 8850 17582 1229 17582 8851 17583 1229 17583 1230 17583 2709 17584 8852 17584 8858 17584 8858 17585 8852 17585 8853 17585 8858 17586 8853 17586 8840 17586 8840 17587 8853 17587 8849 17587 8840 17588 8849 17588 8854 17588 8854 17589 8849 17589 1226 17589 8854 17590 1226 17590 8850 17590 8829 17591 8855 17591 8841 17591 8841 17592 8855 17592 8856 17592 8841 17593 8856 17593 8840 17593 8840 17594 8856 17594 8857 17594 8840 17595 8857 17595 8858 17595 8858 17596 8857 17596 8846 17596 8858 17597 8846 17597 2711 17597 8859 17598 8860 17598 8864 17598 8923 17599 2884 17599 8862 17599 8922 17600 8923 17600 8863 17600 8867 17601 8922 17601 8861 17601 8923 17602 8862 17602 8863 17602 8863 17603 8862 17603 2869 17603 8863 17604 2869 17604 8865 17604 8865 17605 2869 17605 2843 17605 8865 17606 2843 17606 8864 17606 8864 17607 2843 17607 2842 17607 8864 17608 2842 17608 8859 17608 8922 17609 8863 17609 8861 17609 8861 17610 8863 17610 8865 17610 8861 17611 8865 17611 8866 17611 8866 17612 8865 17612 8864 17612 8866 17613 8864 17613 8868 17613 8868 17614 8864 17614 8860 17614 8868 17615 8860 17615 8810 17615 8867 17616 8861 17616 8870 17616 8870 17617 8861 17617 8866 17617 8870 17618 8866 17618 8871 17618 8871 17619 8866 17619 8868 17619 8871 17620 8868 17620 8869 17620 8869 17621 8868 17621 8810 17621 8869 17622 8810 17622 8808 17622 1632 17623 8867 17623 1628 17623 1628 17624 8867 17624 8870 17624 1628 17625 8870 17625 1625 17625 1625 17626 8870 17626 8871 17626 1625 17627 8871 17627 1622 17627 1622 17628 8871 17628 8869 17628 1622 17629 8869 17629 8872 17629 8872 17630 8869 17630 8808 17630 8872 17631 8808 17631 1612 17631 2715 17632 2716 17632 8905 17632 1224 17633 1222 17633 8848 17633 8873 17634 8892 17634 8893 17634 8874 17635 8875 17635 8895 17635 8887 17636 2720 17636 8888 17636 8876 17637 2725 17637 8877 17637 1216 17638 8886 17638 8881 17638 2725 17639 2832 17639 8877 17639 8877 17640 2832 17640 8927 17640 8877 17641 8927 17641 8878 17641 8878 17642 8927 17642 8879 17642 8878 17643 8879 17643 8882 17643 8882 17644 8879 17644 8926 17644 8882 17645 8926 17645 1213 17645 1213 17646 8926 17646 1212 17646 2719 17647 8876 17647 8880 17647 8880 17648 8876 17648 8877 17648 8880 17649 8877 17649 8884 17649 8884 17650 8877 17650 8878 17650 8884 17651 8878 17651 8881 17651 8881 17652 8878 17652 8882 17652 8881 17653 8882 17653 1216 17653 1216 17654 8882 17654 1213 17654 2720 17655 2719 17655 8888 17655 8888 17656 2719 17656 8880 17656 8888 17657 8880 17657 8883 17657 8883 17658 8880 17658 8884 17658 8883 17659 8884 17659 8885 17659 8885 17660 8884 17660 8881 17660 8885 17661 8881 17661 8891 17661 8891 17662 8881 17662 8886 17662 2722 17663 8887 17663 8894 17663 8894 17664 8887 17664 8888 17664 8894 17665 8888 17665 8889 17665 8889 17666 8888 17666 8883 17666 8889 17667 8883 17667 8890 17667 8890 17668 8883 17668 8885 17668 8890 17669 8885 17669 1215 17669 1215 17670 8885 17670 8891 17670 8892 17671 2722 17671 8893 17671 8893 17672 2722 17672 8894 17672 8893 17673 8894 17673 8897 17673 8897 17674 8894 17674 8889 17674 8897 17675 8889 17675 8895 17675 8895 17676 8889 17676 8890 17676 8895 17677 8890 17677 8874 17677 8874 17678 8890 17678 1215 17678 8875 17679 8896 17679 8895 17679 8895 17680 8896 17680 8903 17680 8895 17681 8903 17681 8897 17681 8897 17682 8903 17682 8900 17682 8897 17683 8900 17683 8893 17683 8893 17684 8900 17684 8899 17684 8893 17685 8899 17685 8873 17685 8873 17686 8899 17686 8898 17686 2716 17687 8898 17687 8905 17687 8905 17688 8898 17688 8899 17688 8905 17689 8899 17689 8904 17689 8904 17690 8899 17690 8900 17690 8904 17691 8900 17691 8901 17691 8901 17692 8900 17692 8903 17692 8901 17693 8903 17693 8902 17693 8902 17694 8903 17694 8896 17694 8902 17695 1224 17695 8901 17695 8901 17696 1224 17696 8848 17696 8901 17697 8848 17697 8904 17697 8904 17698 8848 17698 8906 17698 8904 17699 8906 17699 8905 17699 8905 17700 8906 17700 8852 17700 8905 17701 8852 17701 2715 17701 2715 17702 8852 17702 2709 17702 8924 17703 2884 17703 8923 17703 1634 17704 8907 17704 8914 17704 8908 17705 2866 17705 8916 17705 8913 17706 2351 17706 8909 17706 8909 17707 2351 17707 8978 17707 8909 17708 8978 17708 8910 17708 8910 17709 8978 17709 8911 17709 8910 17710 8911 17710 8917 17710 8917 17711 8911 17711 8912 17711 8917 17712 8912 17712 2895 17712 2895 17713 8912 17713 2893 17713 8907 17714 8913 17714 8914 17714 8914 17715 8913 17715 8909 17715 8914 17716 8909 17716 8915 17716 8915 17717 8909 17717 8910 17717 8915 17718 8910 17718 8916 17718 8916 17719 8910 17719 8917 17719 8916 17720 8917 17720 8908 17720 8908 17721 8917 17721 2895 17721 8918 17722 1634 17722 8919 17722 8919 17723 1634 17723 8914 17723 8919 17724 8914 17724 8920 17724 8920 17725 8914 17725 8915 17725 8920 17726 8915 17726 8921 17726 8921 17727 8915 17727 8916 17727 8921 17728 8916 17728 8925 17728 8925 17729 8916 17729 2866 17729 1632 17730 8918 17730 8867 17730 8867 17731 8918 17731 8919 17731 8867 17732 8919 17732 8922 17732 8922 17733 8919 17733 8920 17733 8922 17734 8920 17734 8923 17734 8923 17735 8920 17735 8921 17735 8923 17736 8921 17736 8924 17736 8924 17737 8921 17737 8925 17737 8927 17738 2832 17738 8928 17738 8879 17739 8927 17739 8929 17739 8926 17740 8879 17740 8948 17740 1212 17741 8926 17741 8947 17741 8927 17742 8928 17742 8929 17742 8929 17743 8928 17743 8930 17743 8929 17744 8930 17744 8931 17744 8931 17745 8930 17745 2834 17745 8931 17746 2834 17746 8934 17746 8952 17747 8958 17747 8951 17747 8951 17748 8958 17748 1207 17748 8951 17749 1207 17749 8950 17749 8950 17750 1207 17750 1210 17750 8950 17751 1210 17751 8947 17751 8947 17752 1210 17752 8932 17752 8947 17753 8932 17753 1212 17753 2834 17754 8933 17754 8934 17754 8934 17755 8933 17755 8935 17755 8934 17756 8935 17756 8943 17756 8943 17757 8935 17757 2835 17757 8943 17758 2835 17758 8936 17758 2835 17759 8937 17759 8936 17759 8936 17760 8937 17760 8939 17760 8936 17761 8939 17761 8938 17761 8938 17762 8939 17762 8940 17762 8938 17763 8940 17763 8941 17763 8941 17764 8940 17764 8964 17764 8879 17765 8929 17765 8948 17765 8948 17766 8929 17766 8931 17766 8948 17767 8931 17767 8949 17767 8949 17768 8931 17768 8934 17768 8949 17769 8934 17769 8942 17769 8942 17770 8934 17770 8943 17770 8942 17771 8943 17771 8944 17771 8944 17772 8943 17772 8936 17772 8944 17773 8936 17773 8945 17773 8945 17774 8936 17774 8938 17774 8945 17775 8938 17775 8946 17775 8946 17776 8938 17776 8941 17776 8946 17777 8941 17777 8962 17777 8926 17778 8948 17778 8947 17778 8947 17779 8948 17779 8949 17779 8947 17780 8949 17780 8950 17780 8950 17781 8949 17781 8942 17781 8950 17782 8942 17782 8951 17782 8951 17783 8942 17783 8944 17783 8951 17784 8944 17784 8952 17784 8952 17785 8944 17785 8945 17785 8952 17786 8945 17786 8957 17786 8957 17787 8945 17787 8946 17787 8957 17788 8946 17788 8953 17788 8953 17789 8946 17789 8962 17789 8953 17790 8962 17790 8961 17790 8960 17791 8954 17791 8961 17791 8961 17792 8954 17792 1204 17792 8961 17793 1204 17793 8953 17793 8953 17794 1204 17794 8955 17794 8953 17795 8955 17795 8957 17795 8957 17796 8955 17796 8956 17796 8957 17797 8956 17797 8952 17797 8952 17798 8956 17798 1206 17798 8952 17799 1206 17799 8958 17799 1201 17800 8960 17800 8959 17800 8959 17801 8960 17801 8961 17801 8959 17802 8961 17802 8980 17802 8980 17803 8961 17803 8962 17803 8980 17804 8962 17804 8987 17804 8987 17805 8962 17805 8941 17805 8987 17806 8941 17806 8963 17806 8963 17807 8941 17807 8964 17807 2864 17808 2862 17808 8969 17808 2861 17809 8975 17809 8968 17809 8974 17810 2859 17810 8979 17810 2355 17811 1699 17811 8965 17811 8965 17812 1699 17812 8967 17812 8965 17813 8967 17813 8966 17813 8966 17814 8967 17814 9001 17814 8966 17815 9001 17815 8969 17815 8969 17816 9001 17816 9000 17816 8969 17817 9000 17817 2864 17817 2864 17818 9000 17818 2865 17818 8970 17819 2355 17819 8971 17819 8971 17820 2355 17820 8965 17820 8971 17821 8965 17821 8973 17821 8973 17822 8965 17822 8966 17822 8973 17823 8966 17823 8968 17823 8968 17824 8966 17824 8969 17824 8968 17825 8969 17825 2861 17825 2861 17826 8969 17826 2862 17826 8976 17827 8970 17827 8977 17827 8977 17828 8970 17828 8971 17828 8977 17829 8971 17829 8972 17829 8972 17830 8971 17830 8973 17830 8972 17831 8973 17831 8979 17831 8979 17832 8973 17832 8968 17832 8979 17833 8968 17833 8974 17833 8974 17834 8968 17834 8975 17834 2351 17835 8976 17835 8978 17835 8978 17836 8976 17836 8977 17836 8978 17837 8977 17837 8911 17837 8911 17838 8977 17838 8972 17838 8911 17839 8972 17839 8912 17839 8912 17840 8972 17840 8979 17840 8912 17841 8979 17841 2893 17841 2893 17842 8979 17842 2859 17842 8986 17843 2829 17843 8992 17843 9005 17844 8984 17844 8994 17844 8997 17845 1182 17845 1201 17845 8959 17846 8980 17846 8990 17846 8990 17847 8980 17847 8987 17847 8995 17848 8991 17848 8989 17848 8989 17849 8991 17849 8988 17849 8981 17850 8995 17850 8982 17850 8982 17851 8995 17851 8989 17851 8982 17852 8989 17852 9009 17852 9009 17853 8989 17853 2818 17853 1181 17854 8996 17854 8983 17854 8983 17855 8996 17855 8994 17855 8983 17856 8994 17856 8985 17856 8985 17857 8994 17857 8984 17857 8985 17858 8984 17858 1179 17858 8963 17859 8986 17859 8987 17859 8987 17860 8986 17860 8992 17860 8987 17861 8992 17861 8990 17861 8988 17862 8993 17862 8989 17862 8989 17863 8993 17863 2827 17863 8989 17864 2827 17864 2818 17864 1201 17865 8959 17865 8997 17865 8997 17866 8959 17866 8990 17866 8997 17867 8990 17867 8991 17867 8991 17868 8990 17868 8992 17868 8991 17869 8992 17869 8988 17869 8988 17870 8992 17870 2829 17870 8988 17871 2829 17871 8993 17871 8981 17872 9005 17872 8995 17872 8995 17873 9005 17873 8994 17873 8995 17874 8994 17874 8991 17874 8991 17875 8994 17875 8996 17875 8991 17876 8996 17876 8997 17876 8997 17877 8996 17877 1181 17877 8997 17878 1181 17878 1182 17878 2857 17879 2865 17879 9000 17879 9003 17880 1697 17880 9002 17880 9019 17881 2857 17881 8998 17881 8998 17882 2857 17882 9000 17882 8998 17883 9000 17883 8999 17883 8999 17884 9000 17884 9001 17884 8999 17885 9001 17885 9002 17885 9002 17886 9001 17886 8967 17886 9002 17887 8967 17887 9003 17887 9003 17888 8967 17888 1699 17888 1178 17889 1179 17889 8984 17889 9004 17890 1178 17890 9011 17890 9011 17891 1178 17891 8984 17891 9011 17892 8984 17892 9013 17892 9013 17893 8984 17893 9005 17893 9013 17894 9005 17894 9006 17894 9006 17895 9005 17895 8981 17895 9006 17896 8981 17896 9007 17896 9007 17897 8981 17897 8982 17897 9007 17898 8982 17898 9008 17898 9008 17899 8982 17899 9009 17899 9008 17900 9009 17900 9010 17900 9010 17901 9009 17901 2818 17901 1183 17902 9004 17902 9024 17902 9024 17903 9004 17903 9011 17903 9024 17904 9011 17904 9012 17904 9012 17905 9011 17905 9013 17905 9012 17906 9013 17906 9014 17906 9014 17907 9013 17907 9006 17907 9014 17908 9006 17908 9015 17908 9015 17909 9006 17909 9007 17909 9015 17910 9007 17910 9016 17910 9016 17911 9007 17911 9008 17911 9016 17912 9008 17912 9017 17912 9017 17913 9008 17913 9010 17913 9018 17914 1703 17914 9020 17914 9027 17915 9019 17915 9028 17915 9028 17916 9019 17916 8998 17916 9028 17917 8998 17917 9031 17917 9031 17918 8998 17918 8999 17918 9031 17919 8999 17919 9020 17919 9020 17920 8999 17920 9002 17920 9020 17921 9002 17921 9018 17921 9018 17922 9002 17922 1697 17922 9023 17923 1183 17923 9024 17923 2816 17924 9021 17924 9041 17924 9032 17925 9023 17925 9022 17925 9022 17926 9023 17926 9024 17926 9022 17927 9024 17927 9035 17927 9035 17928 9024 17928 9012 17928 9035 17929 9012 17929 9038 17929 9038 17930 9012 17930 9014 17930 9038 17931 9014 17931 9025 17931 9025 17932 9014 17932 9015 17932 9025 17933 9015 17933 9026 17933 9026 17934 9015 17934 9016 17934 9026 17935 9016 17935 9041 17935 9041 17936 9016 17936 9017 17936 9041 17937 9017 17937 2816 17937 9042 17938 9027 17938 9044 17938 9044 17939 9027 17939 9028 17939 9044 17940 9028 17940 9029 17940 9029 17941 9028 17941 9031 17941 9029 17942 9031 17942 9030 17942 9030 17943 9031 17943 9020 17943 9030 17944 9020 17944 9046 17944 9046 17945 9020 17945 1703 17945 1184 17946 9032 17946 9022 17946 9033 17947 1184 17947 9050 17947 9050 17948 1184 17948 9022 17948 9050 17949 9022 17949 9034 17949 9034 17950 9022 17950 9035 17950 9034 17951 9035 17951 9036 17951 9036 17952 9035 17952 9038 17952 9036 17953 9038 17953 9037 17953 9037 17954 9038 17954 9025 17954 9037 17955 9025 17955 9039 17955 9039 17956 9025 17956 9026 17956 9039 17957 9026 17957 9040 17957 9040 17958 9026 17958 9041 17958 9040 17959 9041 17959 2813 17959 2813 17960 9041 17960 9021 17960 9043 17961 9042 17961 9044 17961 9052 17962 9043 17962 9053 17962 9053 17963 9043 17963 9044 17963 9053 17964 9044 17964 9045 17964 9045 17965 9044 17965 9029 17965 9045 17966 9029 17966 9056 17966 9056 17967 9029 17967 9030 17967 9056 17968 9030 17968 1701 17968 1701 17969 9030 17969 9046 17969 2813 17970 9047 17970 9040 17970 9040 17971 9047 17971 9048 17971 9040 17972 9048 17972 9039 17972 9039 17973 9048 17973 9049 17973 9039 17974 9049 17974 9037 17974 9037 17975 9049 17975 9062 17975 9037 17976 9062 17976 9036 17976 9059 17977 1186 17977 9051 17977 9036 17978 9062 17978 9034 17978 9034 17979 9062 17979 9059 17979 9034 17980 9059 17980 9050 17980 9050 17981 9059 17981 9051 17981 9050 17982 9051 17982 9033 17982 2939 17983 9052 17983 9065 17983 9065 17984 9052 17984 9053 17984 9065 17985 9053 17985 9054 17985 9054 17986 9053 17986 9045 17986 9054 17987 9045 17987 9055 17987 9055 17988 9045 17988 9056 17988 9055 17989 9056 17989 9057 17989 9057 17990 9056 17990 1701 17990 1187 17991 1186 17991 9058 17991 9058 17992 1186 17992 9059 17992 9058 17993 9059 17993 9063 17993 9049 17994 9048 17994 9060 17994 9062 17995 9049 17995 9061 17995 9049 17996 9060 17996 9061 17996 9061 17997 9060 17997 2821 17997 9061 17998 2821 17998 2820 17998 2820 17999 9070 17999 9061 17999 9061 18000 9070 18000 9063 18000 9061 18001 9063 18001 9062 18001 9062 18002 9063 18002 9059 18002 9072 18003 1187 18003 9073 18003 9073 18004 1187 18004 9058 18004 9073 18005 9058 18005 9067 18005 9067 18006 9058 18006 9063 18006 9067 18007 9063 18007 9069 18007 9069 18008 9063 18008 9070 18008 2921 18009 2939 18009 9064 18009 9064 18010 2939 18010 9065 18010 9064 18011 9065 18011 9081 18011 9081 18012 9065 18012 9054 18012 9081 18013 9054 18013 9082 18013 9082 18014 9054 18014 9055 18014 9082 18015 9055 18015 1708 18015 1708 18016 9055 18016 9057 18016 9075 18017 9066 18017 2026 18017 9074 18018 9067 18018 9068 18018 9068 18019 9067 18019 9069 18019 9068 18020 9069 18020 2011 18020 2011 18021 9069 18021 9070 18021 2011 18022 9070 18022 2820 18022 9071 18023 9072 18023 9073 18023 2011 18024 9066 18024 9068 18024 9068 18025 9066 18025 9075 18025 9068 18026 9075 18026 9074 18026 9074 18027 9075 18027 9076 18027 2026 18028 9077 18028 9075 18028 9075 18029 9077 18029 9098 18029 9075 18030 9098 18030 9076 18030 9076 18031 9098 18031 9097 18031 9076 18032 9097 18032 9079 18032 9073 18033 9067 18033 9071 18033 9071 18034 9067 18034 9074 18034 9071 18035 9074 18035 1197 18035 1197 18036 9074 18036 9076 18036 1197 18037 9076 18037 9078 18037 9078 18038 9076 18038 9079 18038 9078 18039 9079 18039 2347 18039 1706 18040 1705 18040 9080 18040 9085 18041 2921 18041 9087 18041 9087 18042 2921 18042 9064 18042 9087 18043 9064 18043 9088 18043 9088 18044 9064 18044 9081 18044 9088 18045 9081 18045 9080 18045 9080 18046 9081 18046 9082 18046 9080 18047 9082 18047 1706 18047 1706 18048 9082 18048 1708 18048 9083 18049 1715 18049 9108 18049 9084 18050 9085 18050 9109 18050 9109 18051 9085 18051 9087 18051 9109 18052 9087 18052 9086 18052 9086 18053 9087 18053 9088 18053 9086 18054 9088 18054 9108 18054 9108 18055 9088 18055 9080 18055 9108 18056 9080 18056 9083 18056 9083 18057 9080 18057 1705 18057 9096 18058 9098 18058 9077 18058 9099 18059 9112 18059 9095 18059 9112 18060 9089 18060 9093 18060 9089 18061 1695 18061 2343 18061 9089 18062 2343 18062 9093 18062 9093 18063 2343 18063 9090 18063 9093 18064 9090 18064 9094 18064 9094 18065 9090 18065 9091 18065 9094 18066 9091 18066 9092 18066 9091 18067 2347 18067 9092 18067 9092 18068 2347 18068 9079 18068 9092 18069 9079 18069 9097 18069 9112 18070 9093 18070 9095 18070 9095 18071 9093 18071 9094 18071 9095 18072 9094 18072 9100 18072 9100 18073 9094 18073 9092 18073 9100 18074 9092 18074 9096 18074 9096 18075 9092 18075 9097 18075 9096 18076 9097 18076 9098 18076 9099 18077 9095 18077 9106 18077 9106 18078 9095 18078 9100 18078 9106 18079 9100 18079 9105 18079 9105 18080 9100 18080 9096 18080 9105 18081 9096 18081 9103 18081 9103 18082 9096 18082 9077 18082 9103 18083 9077 18083 2026 18083 2023 18084 9101 18084 9102 18084 2026 18085 9104 18085 9103 18085 9103 18086 9104 18086 2024 18086 9103 18087 2024 18087 9105 18087 9105 18088 2024 18088 2023 18088 9105 18089 2023 18089 9106 18089 9106 18090 2023 18090 9102 18090 9106 18091 9102 18091 9099 18091 2791 18092 9084 18092 9109 18092 2791 18093 9109 18093 9107 18093 3238 18094 2738 18094 9120 18094 9120 18095 2738 18095 9107 18095 9108 18096 1715 18096 1717 18096 9107 18097 9109 18097 9120 18097 9120 18098 9109 18098 9086 18098 9120 18099 9086 18099 9110 18099 9110 18100 9086 18100 9108 18100 9110 18101 9108 18101 9129 18101 9129 18102 9108 18102 1717 18102 9129 18103 1717 18103 9111 18103 9113 18104 1722 18104 1695 18104 1695 18105 9089 18105 9113 18105 9113 18106 9089 18106 9112 18106 9113 18107 9112 18107 9131 18107 9131 18108 9112 18108 9099 18108 9131 18109 9099 18109 9114 18109 9099 18110 9102 18110 9114 18110 9114 18111 9102 18111 9101 18111 9114 18112 9101 18112 9127 18112 9130 18113 9113 18113 9131 18113 1722 18114 9113 18114 9115 18114 9115 18115 9113 18115 9130 18115 9115 18116 9130 18116 1721 18116 1721 18117 9130 18117 9118 18117 9128 18118 9117 18118 9116 18118 9116 18119 9117 18119 1710 18119 9116 18120 1710 18120 9118 18120 9118 18121 1710 18121 9119 18121 9118 18122 9119 18122 1721 18122 9122 18123 9110 18123 9129 18123 3237 18124 3238 18124 9120 18124 9127 18125 3261 18125 9126 18125 9126 18126 3261 18126 3235 18126 9126 18127 3235 18127 9124 18127 9124 18128 3235 18128 3237 18128 9124 18129 3237 18129 9121 18129 9121 18130 3237 18130 9120 18130 9121 18131 9120 18131 9110 18131 9110 18132 9122 18132 9121 18132 9121 18133 9122 18133 9123 18133 9121 18134 9123 18134 9124 18134 9124 18135 9123 18135 9125 18135 9124 18136 9125 18136 9126 18136 9126 18137 9125 18137 9114 18137 9126 18138 9114 18138 9127 18138 9111 18139 9128 18139 9129 18139 9129 18140 9128 18140 9116 18140 9129 18141 9116 18141 9122 18141 9122 18142 9116 18142 9118 18142 9122 18143 9118 18143 9123 18143 9123 18144 9118 18144 9130 18144 9123 18145 9130 18145 9125 18145 9125 18146 9130 18146 9131 18146 9125 18147 9131 18147 9114 18147 1153 18148 9132 18148 1137 18148 1137 18149 9132 18149 9133 18149 1137 18150 9133 18150 1134 18150 1134 18151 9133 18151 300 18151 1126 18152 5397 18152 1138 18152 1138 18153 5397 18153 5398 18153 1138 18154 5398 18154 1141 18154 1141 18155 5398 18155 1155 18155 115 18156 117 18156 9134 18156 9134 18157 117 18157 1259 18157 122 18158 9208 18158 120 18158 120 18159 9208 18159 9215 18159 120 18160 9215 18160 1293 18160 124 18161 1270 18161 123 18161 123 18162 1270 18162 1269 18162 9144 18163 132 18163 9141 18163 9141 18164 132 18164 9135 18164 9141 18165 9135 18165 9136 18165 1106 18166 9168 18166 9137 18166 9137 18167 9168 18167 9138 18167 9137 18168 9138 18168 1117 18168 1117 18169 9138 18169 1278 18169 1145 18170 5419 18170 1105 18170 1105 18171 5419 18171 5416 18171 1105 18172 5416 18172 1114 18172 1114 18173 5416 18173 284 18173 1167 18174 9148 18174 9139 18174 9139 18175 9148 18175 1277 18175 9139 18176 1277 18176 9140 18176 9144 18177 9141 18177 9142 18177 9144 18178 9142 18178 9145 18178 9145 18179 9142 18179 9143 18179 9145 18180 9143 18180 9147 18180 9148 18181 9147 18181 1277 18181 1277 18182 9147 18182 9143 18182 1277 18183 9143 18183 1276 18183 1276 18184 9143 18184 9142 18184 1276 18185 9142 18185 1273 18185 1273 18186 9142 18186 9141 18186 1273 18187 9141 18187 9136 18187 293 18188 9144 18188 9150 18188 9150 18189 9144 18189 9145 18189 9150 18190 9145 18190 9146 18190 9146 18191 9145 18191 9147 18191 9146 18192 9147 18192 9149 18192 9149 18193 9147 18193 9148 18193 9149 18194 9148 18194 1168 18194 1168 18195 9148 18195 1167 18195 1168 18196 9155 18196 9149 18196 9149 18197 9155 18197 9156 18197 9149 18198 9156 18198 9146 18198 9146 18199 9156 18199 9158 18199 9146 18200 9158 18200 9150 18200 9150 18201 9158 18201 9152 18201 9150 18202 9152 18202 293 18202 9161 18203 291 18203 9152 18203 9152 18204 291 18204 9151 18204 9152 18205 9151 18205 293 18205 9167 18206 9160 18206 9153 18206 9153 18207 9160 18207 9159 18207 9153 18208 9159 18208 9154 18208 9154 18209 9159 18209 9157 18209 9154 18210 9157 18210 1172 18210 1172 18211 9157 18211 1170 18211 9155 18212 1170 18212 9156 18212 9156 18213 1170 18213 9157 18213 9156 18214 9157 18214 9158 18214 9158 18215 9157 18215 9159 18215 9158 18216 9159 18216 9152 18216 9152 18217 9159 18217 9160 18217 9152 18218 9160 18218 9161 18218 9161 18219 9160 18219 9167 18219 9161 18220 9167 18220 9168 18220 9162 18221 1283 18221 9163 18221 9163 18222 1283 18222 9154 18222 9163 18223 9154 18223 1172 18223 1278 18224 9138 18224 9165 18224 9164 18225 1285 18225 9166 18225 9166 18226 1285 18226 1281 18226 9166 18227 1281 18227 9165 18227 9165 18228 1281 18228 1279 18228 9165 18229 1279 18229 1278 18229 1283 18230 9164 18230 9154 18230 9154 18231 9164 18231 9166 18231 9154 18232 9166 18232 9153 18232 9153 18233 9166 18233 9165 18233 9153 18234 9165 18234 9167 18234 9167 18235 9165 18235 9138 18235 9167 18236 9138 18236 9168 18236 9170 18237 1231 18237 9181 18237 1287 18238 9169 18238 9170 18238 9181 18239 9185 18239 9172 18239 9172 18240 9185 18240 9171 18240 9172 18241 9171 18241 9174 18241 9174 18242 9171 18242 300 18242 9174 18243 300 18243 9133 18243 9170 18244 9181 18244 1287 18244 1287 18245 9181 18245 9172 18245 1287 18246 9172 18246 9173 18246 9173 18247 9172 18247 9174 18247 9173 18248 9174 18248 9175 18248 9175 18249 9174 18249 9133 18249 9175 18250 9133 18250 9132 18250 9198 18251 9197 18251 1238 18251 1236 18252 9200 18252 9198 18252 9195 18253 9194 18253 9176 18253 9176 18254 9177 18254 9193 18254 9176 18255 9191 18255 9178 18255 9179 18256 9188 18256 9176 18256 9186 18257 9180 18257 9202 18257 9185 18258 9181 18258 9187 18258 9187 18259 9181 18259 1231 18259 9187 18260 1231 18260 9176 18260 9202 18261 9189 18261 9190 18261 302 18262 300 18262 9203 18262 9203 18263 300 18263 9171 18263 9192 18264 9182 18264 9202 18264 9202 18265 9183 18265 9184 18265 9171 18266 9185 18266 9202 18266 9202 18267 9185 18267 9187 18267 9202 18268 9187 18268 9186 18268 9186 18269 9187 18269 9176 18269 9186 18270 9176 18270 9180 18270 9180 18271 9176 18271 9188 18271 9180 18272 9188 18272 9202 18272 9202 18273 9188 18273 9179 18273 9202 18274 9179 18274 9189 18274 9189 18275 9179 18275 9176 18275 9189 18276 9176 18276 9190 18276 9190 18277 9176 18277 9178 18277 9190 18278 9178 18278 9202 18278 9202 18279 9178 18279 9191 18279 9202 18280 9191 18280 9192 18280 9192 18281 9191 18281 9176 18281 9192 18282 9176 18282 9182 18282 9182 18283 9176 18283 9193 18283 9182 18284 9193 18284 9202 18284 9202 18285 9193 18285 9177 18285 9202 18286 9177 18286 9183 18286 9183 18287 9177 18287 9176 18287 9183 18288 9176 18288 9184 18288 9184 18289 9176 18289 9194 18289 9184 18290 9194 18290 9202 18290 9202 18291 9194 18291 9195 18291 9202 18292 9195 18292 9196 18292 9176 18293 1238 18293 9195 18293 9195 18294 1238 18294 9197 18294 9195 18295 9197 18295 9196 18295 9196 18296 9197 18296 9198 18296 9196 18297 9198 18297 9199 18297 9199 18298 9198 18298 9200 18298 9199 18299 9200 18299 9201 18299 9171 18300 9202 18300 9203 18300 9203 18301 9202 18301 9196 18301 9203 18302 9196 18302 9205 18302 9205 18303 9196 18303 9199 18303 9205 18304 9199 18304 9207 18304 9207 18305 9199 18305 9201 18305 9207 18306 9201 18306 9214 18306 302 18307 9203 18307 9204 18307 9204 18308 9203 18308 9205 18308 9204 18309 9205 18309 9206 18309 9206 18310 9205 18310 9207 18310 9206 18311 9207 18311 297 18311 297 18312 9207 18312 9214 18312 297 18313 9214 18313 9208 18313 9209 18314 1235 18314 1290 18314 9200 18315 1236 18315 9209 18315 1290 18316 9210 18316 9212 18316 9212 18317 9210 18317 9211 18317 9212 18318 9211 18318 9213 18318 9213 18319 9211 18319 1293 18319 9213 18320 1293 18320 9215 18320 9209 18321 1290 18321 9200 18321 9200 18322 1290 18322 9212 18322 9200 18323 9212 18323 9201 18323 9201 18324 9212 18324 9213 18324 9201 18325 9213 18325 9214 18325 9214 18326 9213 18326 9215 18326 9214 18327 9215 18327 9208 18327 5916 18328 5915 18328 9229 18328 3640 18329 2399 18329 9281 18329 9281 18330 2399 18330 9216 18330 9281 18331 9216 18331 9217 18331 9217 18332 9216 18332 9265 18332 9265 18333 9216 18333 9218 18333 9265 18334 9218 18334 9219 18334 9219 18335 9218 18335 9220 18335 9220 18336 9218 18336 9229 18336 9220 18337 9229 18337 9221 18337 9221 18338 9229 18338 5915 18338 9221 18339 5915 18339 9280 18339 9232 18340 5917 18340 9222 18340 9222 18341 5917 18341 9230 18341 9222 18342 9230 18342 9234 18342 9234 18343 9230 18343 9223 18343 9223 18344 9230 18344 9224 18344 9223 18345 9224 18345 9235 18345 9235 18346 9224 18346 9237 18346 9237 18347 9224 18347 9228 18347 9237 18348 9228 18348 9225 18348 9225 18349 9228 18349 9263 18349 9263 18350 9228 18350 9226 18350 9263 18351 9226 18351 9227 18351 2399 18352 9226 18352 9216 18352 9216 18353 9226 18353 9228 18353 9216 18354 9228 18354 9218 18354 9218 18355 9228 18355 9224 18355 9218 18356 9224 18356 9229 18356 9229 18357 9224 18357 9230 18357 9229 18358 9230 18358 5916 18358 5916 18359 9230 18359 5917 18359 8688 18360 9240 18360 2386 18360 2386 18361 9240 18361 2389 18361 9244 18362 9246 18362 9252 18362 9240 18363 9241 18363 2389 18363 2389 18364 9241 18364 9244 18364 2389 18365 9244 18365 2390 18365 2390 18366 9244 18366 9252 18366 2390 18367 9252 18367 9231 18367 8685 18368 9232 18368 9222 18368 8687 18369 8685 18369 9233 18369 8688 18370 8687 18370 9238 18370 8685 18371 9222 18371 9233 18371 9233 18372 9222 18372 9234 18372 9233 18373 9234 18373 9239 18373 9234 18374 9223 18374 9239 18374 9239 18375 9223 18375 9235 18375 9239 18376 9235 18376 9236 18376 9236 18377 9235 18377 9237 18377 9236 18378 9237 18378 9250 18378 8687 18379 9233 18379 9238 18379 9238 18380 9233 18380 9239 18380 9238 18381 9239 18381 9242 18381 9242 18382 9239 18382 9236 18382 9242 18383 9236 18383 9243 18383 9243 18384 9236 18384 9250 18384 9243 18385 9250 18385 9245 18385 8688 18386 9238 18386 9240 18386 9240 18387 9238 18387 9242 18387 9240 18388 9242 18388 9241 18388 9241 18389 9242 18389 9243 18389 9241 18390 9243 18390 9244 18390 9244 18391 9243 18391 9245 18391 9244 18392 9245 18392 9246 18392 9247 18393 9227 18393 3584 18393 9248 18394 9262 18394 9247 18394 9262 18395 9248 18395 9259 18395 9259 18396 9248 18396 9255 18396 9259 18397 9255 18397 9258 18397 9250 18398 9237 18398 9225 18398 9263 18399 9249 18399 9225 18399 9225 18400 9249 18400 9261 18400 9225 18401 9261 18401 9250 18401 9250 18402 9261 18402 9260 18402 9250 18403 9260 18403 9245 18403 9245 18404 9260 18404 9251 18404 9245 18405 9251 18405 9246 18405 9246 18406 9251 18406 9252 18406 9247 18407 3584 18407 9248 18407 9248 18408 3584 18408 9253 18408 9248 18409 9253 18409 9255 18409 9253 18410 9254 18410 9255 18410 9255 18411 9254 18411 9256 18411 9255 18412 9256 18412 9258 18412 9258 18413 9256 18413 3589 18413 9258 18414 3589 18414 9257 18414 9257 18415 3589 18415 3588 18415 9257 18416 3588 18416 9231 18416 9231 18417 9252 18417 9257 18417 9257 18418 9252 18418 9251 18418 9257 18419 9251 18419 9258 18419 9258 18420 9251 18420 9260 18420 9258 18421 9260 18421 9259 18421 9259 18422 9260 18422 9261 18422 9259 18423 9261 18423 9262 18423 9262 18424 9261 18424 9249 18424 9262 18425 9249 18425 9247 18425 9247 18426 9249 18426 9263 18426 9247 18427 9263 18427 9227 18427 9219 18428 9220 18428 9271 18428 9275 18429 9283 18429 9270 18429 9270 18430 9283 18430 9286 18430 9217 18431 9265 18431 9264 18431 9264 18432 9265 18432 9267 18432 9264 18433 9267 18433 9266 18433 9266 18434 9267 18434 9268 18434 9266 18435 9268 18435 9269 18435 9269 18436 9268 18436 9270 18436 9269 18437 9270 18437 9285 18437 9285 18438 9270 18438 9286 18438 9265 18439 9219 18439 9267 18439 9267 18440 9219 18440 9271 18440 9267 18441 9271 18441 9268 18441 9268 18442 9271 18442 9273 18442 9268 18443 9273 18443 9270 18443 9270 18444 9273 18444 9274 18444 9270 18445 9274 18445 9275 18445 9220 18446 9221 18446 9271 18446 9271 18447 9221 18447 9272 18447 9271 18448 9272 18448 9273 18448 9273 18449 9272 18449 9278 18449 9273 18450 9278 18450 9274 18450 9274 18451 9278 18451 9277 18451 9274 18452 9277 18452 9275 18452 9275 18453 9277 18453 9276 18453 2395 18454 9276 18454 8745 18454 8745 18455 9276 18455 9277 18455 8745 18456 9277 18456 9279 18456 9279 18457 9277 18457 9278 18457 9279 18458 9278 18458 8747 18458 8747 18459 9278 18459 9272 18459 8747 18460 9272 18460 9280 18460 9280 18461 9272 18461 9221 18461 9293 18462 3640 18462 9281 18462 9282 18463 3640 18463 9293 18463 9286 18464 9283 18464 9289 18464 9288 18465 3637 18465 9284 18465 9269 18466 9285 18466 9287 18466 9287 18467 9285 18467 9286 18467 9287 18468 9286 18468 9288 18468 9288 18469 9286 18469 9289 18469 9288 18470 9289 18470 3637 18470 9266 18471 9269 18471 9290 18471 9290 18472 9269 18472 9287 18472 9290 18473 9287 18473 9297 18473 9297 18474 9287 18474 9288 18474 9297 18475 9288 18475 9296 18475 9296 18476 9288 18476 9284 18476 9296 18477 9284 18477 9294 18477 9295 18478 9292 18478 9291 18478 9291 18479 9292 18479 9282 18479 9291 18480 9282 18480 9298 18480 9298 18481 9282 18481 9293 18481 9298 18482 9293 18482 9299 18482 9299 18483 9293 18483 9281 18483 9290 18484 9300 18484 9266 18484 9266 18485 9300 18485 9301 18485 9266 18486 9301 18486 9264 18486 9264 18487 9301 18487 9217 18487 9294 18488 9292 18488 9296 18488 9296 18489 9292 18489 9295 18489 9296 18490 9295 18490 9297 18490 9297 18491 9295 18491 9291 18491 9297 18492 9291 18492 9290 18492 9290 18493 9291 18493 9298 18493 9290 18494 9298 18494 9300 18494 9300 18495 9298 18495 9299 18495 9300 18496 9299 18496 9301 18496 9301 18497 9299 18497 9281 18497 9301 18498 9281 18498 9217 18498 9302 18499 9304 18499 9303 18499 9303 18500 9304 18500 806 18500 9303 18501 806 18501 108 18501 108 18502 806 18502 9305 18502 108 18503 9305 18503 109 18503 109 18504 9305 18504 9306 18504 109 18505 9306 18505 110 18505 110 18506 9306 18506 799 18506 110 18507 799 18507 9307 18507 9307 18508 799 18508 9308 18508 9307 18509 9308 18509 107 18509 107 18510 9308 18510 9309 18510 107 18511 9309 18511 9310 18511 9310 18512 9309 18512 801 18512 9310 18513 801 18513 9311 18513 9311 18514 801 18514 9312 18514 9311 18515 9312 18515 111 18515 111 18516 9312 18516 803 18516 111 18517 803 18517 9313 18517 9313 18518 803 18518 804 18518 9313 18519 804 18519 9314 18519 9314 18520 804 18520 805 18520 9314 18521 805 18521 9302 18521 9302 18522 805 18522 9304 18522 9325 18523 782 18523 9315 18523 9315 18524 782 18524 783 18524 9315 18525 783 18525 9316 18525 9316 18526 783 18526 9317 18526 9316 18527 9317 18527 103 18527 103 18528 9317 18528 771 18528 103 18529 771 18529 9318 18529 9318 18530 771 18530 772 18530 9318 18531 772 18531 9319 18531 9319 18532 772 18532 773 18532 9319 18533 773 18533 101 18533 101 18534 773 18534 9321 18534 101 18535 9321 18535 9320 18535 9320 18536 9321 18536 776 18536 9320 18537 776 18537 104 18537 104 18538 776 18538 777 18538 104 18539 777 18539 105 18539 105 18540 777 18540 779 18540 105 18541 779 18541 9322 18541 9322 18542 779 18542 9323 18542 9322 18543 9323 18543 9324 18543 9324 18544 9323 18544 781 18544 9324 18545 781 18545 9325 18545 9325 18546 781 18546 782 18546 99 18547 9327 18547 9326 18547 9326 18548 9327 18548 747 18548 9326 18549 747 18549 96 18549 96 18550 747 18550 748 18550 96 18551 748 18551 98 18551 98 18552 748 18552 9329 18552 98 18553 9329 18553 9328 18553 9328 18554 9329 18554 751 18554 9328 18555 751 18555 9330 18555 9330 18556 751 18556 9331 18556 9330 18557 9331 18557 95 18557 95 18558 9331 18558 9332 18558 95 18559 9332 18559 9333 18559 9333 18560 9332 18560 754 18560 9333 18561 754 18561 9334 18561 9334 18562 754 18562 9335 18562 9334 18563 9335 18563 9336 18563 9336 18564 9335 18564 755 18564 9336 18565 755 18565 100 18565 100 18566 755 18566 758 18566 100 18567 758 18567 9337 18567 9337 18568 758 18568 9338 18568 9337 18569 9338 18569 99 18569 99 18570 9338 18570 9327 18570 9348 18571 9339 18571 88 18571 88 18572 9339 18572 9340 18572 88 18573 9340 18573 9341 18573 9341 18574 9340 18574 9342 18574 9341 18575 9342 18575 89 18575 89 18576 9342 18576 725 18576 89 18577 725 18577 90 18577 90 18578 725 18578 9343 18578 90 18579 9343 18579 86 18579 86 18580 9343 18580 728 18580 86 18581 728 18581 87 18581 87 18582 728 18582 9344 18582 87 18583 9344 18583 9345 18583 9345 18584 9344 18584 729 18584 9345 18585 729 18585 9347 18585 9347 18586 729 18586 9346 18586 9347 18587 9346 18587 94 18587 94 18588 9346 18588 732 18588 94 18589 732 18589 91 18589 91 18590 732 18590 733 18590 91 18591 733 18591 92 18591 92 18592 733 18592 734 18592 92 18593 734 18593 9348 18593 9348 18594 734 18594 9339 18594 83 18595 9360 18595 9349 18595 9349 18596 9360 18596 9350 18596 9349 18597 9350 18597 80 18597 80 18598 9350 18598 9352 18598 80 18599 9352 18599 9351 18599 9351 18600 9352 18600 9353 18600 9351 18601 9353 18601 9354 18601 9354 18602 9353 18602 704 18602 9354 18603 704 18603 78 18603 78 18604 704 18604 9355 18604 78 18605 9355 18605 79 18605 79 18606 9355 18606 705 18606 79 18607 705 18607 9356 18607 9356 18608 705 18608 706 18608 9356 18609 706 18609 9357 18609 9357 18610 706 18610 9358 18610 9357 18611 9358 18611 84 18611 84 18612 9358 18612 707 18612 84 18613 707 18613 85 18613 85 18614 707 18614 708 18614 85 18615 708 18615 82 18615 82 18616 708 18616 9359 18616 82 18617 9359 18617 83 18617 83 18618 9359 18618 9360 18618 76 18619 9361 18619 9362 18619 9362 18620 9361 18620 692 18620 9362 18621 692 18621 9363 18621 9363 18622 692 18622 681 18622 9363 18623 681 18623 9364 18623 9364 18624 681 18624 9365 18624 9364 18625 9365 18625 75 18625 75 18626 9365 18626 683 18626 75 18627 683 18627 73 18627 73 18628 683 18628 9366 18628 73 18629 9366 18629 9367 18629 9367 18630 9366 18630 684 18630 9367 18631 684 18631 77 18631 77 18632 684 18632 686 18632 77 18633 686 18633 9368 18633 9368 18634 686 18634 9369 18634 9368 18635 9369 18635 9370 18635 9370 18636 9369 18636 688 18636 9370 18637 688 18637 9371 18637 9371 18638 688 18638 689 18638 9371 18639 689 18639 9372 18639 9372 18640 689 18640 9373 18640 9372 18641 9373 18641 76 18641 76 18642 9373 18642 9361 18642 70 18643 9383 18643 71 18643 71 18644 9383 18644 9374 18644 71 18645 9374 18645 9375 18645 9375 18646 9374 18646 651 18646 9375 18647 651 18647 9376 18647 9376 18648 651 18648 653 18648 9376 18649 653 18649 65 18649 65 18650 653 18650 655 18650 65 18651 655 18651 66 18651 66 18652 655 18652 9378 18652 66 18653 9378 18653 9377 18653 9377 18654 9378 18654 9379 18654 9377 18655 9379 18655 67 18655 67 18656 9379 18656 9380 18656 67 18657 9380 18657 9381 18657 9381 18658 9380 18658 658 18658 9381 18659 658 18659 72 18659 72 18660 658 18660 659 18660 72 18661 659 18661 9382 18661 9382 18662 659 18662 661 18662 9382 18663 661 18663 69 18663 69 18664 661 18664 662 18664 69 18665 662 18665 70 18665 70 18666 662 18666 9383 18666 62 18667 637 18667 63 18667 63 18668 637 18668 9385 18668 63 18669 9385 18669 9384 18669 9384 18670 9385 18670 9387 18670 9384 18671 9387 18671 9386 18671 9386 18672 9387 18672 9388 18672 9386 18673 9388 18673 59 18673 59 18674 9388 18674 626 18674 59 18675 626 18675 9390 18675 9390 18676 626 18676 9389 18676 9390 18677 9389 18677 9391 18677 9391 18678 9389 18678 9392 18678 9391 18679 9392 18679 9393 18679 9393 18680 9392 18680 9395 18680 9393 18681 9395 18681 9394 18681 9394 18682 9395 18682 9396 18682 9394 18683 9396 18683 64 18683 64 18684 9396 18684 9397 18684 64 18685 9397 18685 60 18685 60 18686 9397 18686 633 18686 60 18687 633 18687 9398 18687 9398 18688 633 18688 635 18688 9398 18689 635 18689 62 18689 62 18690 635 18690 637 18690 9409 18691 612 18691 56 18691 56 18692 612 18692 9399 18692 56 18693 9399 18693 52 18693 52 18694 9399 18694 9400 18694 52 18695 9400 18695 9401 18695 9401 18696 9400 18696 9402 18696 9401 18697 9402 18697 53 18697 53 18698 9402 18698 604 18698 53 18699 604 18699 9403 18699 9403 18700 604 18700 9404 18700 9403 18701 9404 18701 9405 18701 9405 18702 9404 18702 9407 18702 9405 18703 9407 18703 9406 18703 9406 18704 9407 18704 606 18704 9406 18705 606 18705 57 18705 57 18706 606 18706 607 18706 57 18707 607 18707 58 18707 58 18708 607 18708 608 18708 58 18709 608 18709 54 18709 54 18710 608 18710 9408 18710 54 18711 9408 18711 55 18711 55 18712 9408 18712 610 18712 55 18713 610 18713 9409 18713 9409 18714 610 18714 612 18714 9410 18715 9411 18715 48 18715 48 18716 9411 18716 9412 18716 48 18717 9412 18717 9413 18717 9413 18718 9412 18718 9414 18718 9413 18719 9414 18719 9415 18719 9415 18720 9414 18720 9416 18720 9415 18721 9416 18721 9417 18721 9417 18722 9416 18722 9418 18722 9417 18723 9418 18723 9419 18723 9419 18724 9418 18724 9420 18724 9419 18725 9420 18725 47 18725 47 18726 9420 18726 575 18726 47 18727 575 18727 9421 18727 9421 18728 575 18728 9422 18728 9421 18729 9422 18729 9423 18729 9423 18730 9422 18730 577 18730 9423 18731 577 18731 9424 18731 9424 18732 577 18732 579 18732 9424 18733 579 18733 9425 18733 9425 18734 579 18734 582 18734 9425 18735 582 18735 50 18735 50 18736 582 18736 9426 18736 50 18737 9426 18737 9410 18737 9410 18738 9426 18738 9411 18738 9431 18739 9427 18739 40 18739 40 18740 9427 18740 547 18740 40 18741 547 18741 41 18741 41 18742 547 18742 9428 18742 41 18743 9428 18743 43 18743 43 18744 9428 18744 549 18744 43 18745 549 18745 37 18745 37 18746 549 18746 550 18746 37 18747 550 18747 38 18747 38 18748 550 18748 552 18748 38 18749 552 18749 39 18749 39 18750 552 18750 553 18750 39 18751 553 18751 9429 18751 9429 18752 553 18752 554 18752 9429 18753 554 18753 45 18753 45 18754 554 18754 555 18754 45 18755 555 18755 9430 18755 9430 18756 555 18756 556 18756 9430 18757 556 18757 46 18757 46 18758 556 18758 558 18758 46 18759 558 18759 44 18759 44 18760 558 18760 560 18760 44 18761 560 18761 9431 18761 9431 18762 560 18762 9427 18762 9432 18763 9433 18763 30 18763 30 18764 9433 18764 988 18764 30 18765 988 18765 31 18765 31 18766 988 18766 978 18766 31 18767 978 18767 9434 18767 9434 18768 978 18768 9435 18768 9434 18769 9435 18769 32 18769 32 18770 9435 18770 9436 18770 32 18771 9436 18771 9437 18771 9437 18772 9436 18772 9438 18772 9437 18773 9438 18773 29 18773 29 18774 9438 18774 9440 18774 29 18775 9440 18775 9439 18775 9439 18776 9440 18776 981 18776 9439 18777 981 18777 35 18777 35 18778 981 18778 9442 18778 35 18779 9442 18779 9441 18779 9441 18780 9442 18780 983 18780 9441 18781 983 18781 36 18781 36 18782 983 18782 984 18782 36 18783 984 18783 34 18783 34 18784 984 18784 986 18784 34 18785 986 18785 9432 18785 9432 18786 986 18786 9433 18786 9443 18787 2868 18787 9444 18787 9444 18788 2868 18788 9445 18788 9444 18789 9445 18789 9454 18789 9453 18790 2871 18790 254 18790 254 18791 2871 18791 9446 18791 254 18792 9446 18792 9447 18792 9447 18793 9446 18793 2940 18793 9447 18794 2940 18794 9448 18794 9448 18795 2940 18795 2876 18795 9448 18796 2876 18796 252 18796 252 18797 2876 18797 2875 18797 252 18798 2875 18798 9449 18798 9449 18799 2875 18799 2878 18799 9449 18800 2878 18800 262 18800 262 18801 2878 18801 9450 18801 262 18802 9450 18802 264 18802 264 18803 9450 18803 2870 18803 264 18804 2870 18804 9443 18804 9443 18805 2870 18805 9451 18805 9443 18806 9451 18806 2868 18806 9452 18807 2873 18807 257 18807 257 18808 2873 18808 2874 18808 257 18809 2874 18809 9453 18809 9453 18810 2874 18810 2933 18810 9453 18811 2933 18811 2871 18811 9445 18812 2885 18812 9454 18812 9454 18813 2885 18813 9455 18813 9454 18814 9455 18814 9456 18814 9456 18815 9455 18815 2883 18815 9456 18816 2883 18816 9457 18816 9457 18817 2883 18817 9458 18817 9457 18818 9458 18818 260 18818 260 18819 9458 18819 9459 18819 260 18820 9459 18820 9460 18820 9460 18821 9459 18821 2872 18821 9460 18822 2872 18822 255 18822 255 18823 2872 18823 9452 18823 255 18824 9452 18824 256 18824 256 18825 9452 18825 257 18825 9468 18826 9461 18826 9479 18826 9479 18827 9461 18827 9464 18827 9465 18828 9462 18828 9461 18828 9461 18829 9462 18829 9463 18829 9461 18830 9463 18830 9464 18830 9465 18831 9461 18831 9470 18831 9470 18832 9461 18832 9484 18832 9470 18833 9484 18833 9466 18833 9477 18834 9475 18834 9479 18834 9479 18835 9475 18835 9467 18835 9479 18836 9467 18836 9468 18836 9469 18837 9470 18837 9471 18837 9471 18838 9470 18838 9466 18838 9471 18839 9466 18839 9472 18839 9472 18840 9466 18840 9490 18840 9485 18841 9468 18841 9473 18841 9473 18842 9468 18842 9467 18842 9473 18843 9467 18843 9474 18843 9474 18844 9467 18844 9475 18844 9474 18845 9475 18845 9476 18845 9476 18846 9475 18846 9477 18846 9476 18847 9477 18847 9478 18847 9478 18848 9477 18848 9479 18848 9482 18849 9464 18849 9494 18849 9494 18850 9464 18850 9463 18850 9494 18851 9463 18851 9480 18851 9480 18852 9463 18852 9462 18852 9480 18853 9462 18853 9481 18853 9481 18854 9462 18854 9465 18854 9464 18855 9482 18855 9479 18855 9479 18856 9482 18856 9478 18856 9465 18857 9470 18857 9481 18857 9481 18858 9470 18858 9483 18858 9492 18859 9484 18859 9461 18859 9492 18860 9461 18860 9493 18860 9493 18861 9461 18861 9468 18861 9493 18862 9468 18862 9485 18862 9483 18863 9470 18863 9486 18863 9486 18864 9470 18864 9469 18864 9486 18865 9469 18865 9487 18865 9487 18866 9469 18866 9471 18866 9487 18867 9471 18867 9488 18867 9488 18868 9471 18868 9472 18868 9488 18869 9472 18869 9489 18869 9489 18870 9472 18870 9490 18870 9489 18871 9490 18871 9491 18871 9491 18872 9490 18872 9466 18872 9491 18873 9466 18873 9492 18873 9492 18874 9466 18874 9484 18874 9478 18875 9482 18875 9493 18875 9493 18876 9482 18876 9494 18876 9491 18877 9492 18877 9483 18877 9483 18878 9492 18878 9493 18878 9483 18879 9493 18879 9481 18879 9481 18880 9493 18880 9494 18880 9481 18881 9494 18881 9480 18881 9488 18882 9489 18882 9487 18882 9487 18883 9489 18883 9491 18883 9487 18884 9491 18884 9486 18884 9486 18885 9491 18885 9483 18885 9474 18886 9476 18886 9473 18886 9473 18887 9476 18887 9478 18887 9473 18888 9478 18888 9485 18888 9485 18889 9478 18889 9493 18889 9507 18890 9520 18890 9500 18890 9495 18891 9497 18891 9496 18891 9496 18892 9497 18892 9535 18892 9498 18893 9532 18893 9534 18893 9534 18894 9532 18894 9522 18894 9534 18895 9522 18895 9499 18895 9499 18896 9522 18896 9520 18896 9499 18897 9520 18897 9535 18897 9535 18898 9520 18898 9507 18898 9535 18899 9507 18899 9496 18899 9500 18900 9501 18900 9507 18900 9507 18901 9501 18901 9502 18901 9507 18902 9502 18902 9525 18902 9503 18903 9505 18903 9504 18903 9504 18904 9505 18904 9506 18904 9504 18905 9506 18905 9508 18905 9508 18906 9506 18906 9507 18906 9508 18907 9507 18907 9523 18907 9523 18908 9507 18908 9525 18908 9509 18909 9510 18909 9513 18909 9518 18910 9533 18910 9509 18910 9536 18911 9511 18911 9510 18911 9510 18912 9511 18912 9512 18912 9510 18913 9512 18913 9513 18913 9527 18914 9528 18914 9529 18914 9513 18915 9524 18915 9514 18915 9529 18916 9530 18916 9527 18916 9527 18917 9530 18917 9515 18917 9527 18918 9515 18918 9513 18918 9513 18919 9515 18919 9516 18919 9513 18920 9516 18920 9524 18920 9517 18921 9518 18921 9531 18921 9531 18922 9518 18922 9509 18922 9531 18923 9509 18923 9521 18923 9521 18924 9509 18924 9513 18924 9521 18925 9513 18925 9519 18925 9519 18926 9513 18926 9514 18926 9519 18927 9514 18927 9526 18927 9499 18928 9535 18928 9509 18928 9509 18929 9535 18929 9510 18929 9519 18930 9500 18930 9520 18930 9519 18931 9520 18931 9521 18931 9521 18932 9520 18932 9522 18932 9521 18933 9522 18933 9531 18933 9516 18934 9523 18934 9525 18934 9516 18935 9525 18935 9524 18935 9524 18936 9525 18936 9502 18936 9524 18937 9502 18937 9514 18937 9514 18938 9502 18938 9501 18938 9514 18939 9501 18939 9526 18939 9526 18940 9501 18940 9500 18940 9526 18941 9500 18941 9519 18941 9516 18942 9515 18942 9523 18942 9523 18943 9515 18943 9508 18943 9513 18944 9507 18944 9527 18944 9527 18945 9507 18945 9506 18945 9527 18946 9506 18946 9528 18946 9528 18947 9506 18947 9505 18947 9528 18948 9505 18948 9529 18948 9529 18949 9505 18949 9503 18949 9529 18950 9503 18950 9530 18950 9530 18951 9503 18951 9504 18951 9530 18952 9504 18952 9515 18952 9515 18953 9504 18953 9508 18953 9531 18954 9522 18954 9517 18954 9517 18955 9522 18955 9532 18955 9517 18956 9532 18956 9518 18956 9518 18957 9532 18957 9498 18957 9518 18958 9498 18958 9533 18958 9533 18959 9498 18959 9534 18959 9533 18960 9534 18960 9509 18960 9509 18961 9534 18961 9499 18961 9510 18962 9535 18962 9536 18962 9536 18963 9535 18963 9497 18963 9536 18964 9497 18964 9511 18964 9511 18965 9497 18965 9495 18965 9511 18966 9495 18966 9512 18966 9512 18967 9495 18967 9496 18967 9512 18968 9496 18968 9513 18968 9513 18969 9496 18969 9507 18969 9540 18970 9547 18970 9548 18970 9563 18971 9565 18971 9562 18971 9562 18972 9565 18972 9567 18972 9558 18973 9560 18973 9537 18973 9537 18974 9560 18974 9538 18974 9537 18975 9538 18975 9539 18975 9539 18976 9538 18976 9547 18976 9539 18977 9547 18977 9567 18977 9567 18978 9547 18978 9540 18978 9567 18979 9540 18979 9562 18979 9548 18980 9541 18980 9540 18980 9540 18981 9541 18981 9542 18981 9540 18982 9542 18982 9543 18982 9554 18983 9544 18983 9552 18983 9552 18984 9544 18984 9546 18984 9552 18985 9546 18985 9545 18985 9545 18986 9546 18986 9540 18986 9545 18987 9540 18987 9551 18987 9551 18988 9540 18988 9543 18988 9546 18989 9573 18989 9540 18989 9540 18990 9573 18990 9568 18990 9538 18991 9577 18991 9578 18991 9538 18992 9578 18992 9547 18992 9547 18993 9578 18993 9549 18993 9547 18994 9549 18994 9548 18994 9548 18995 9549 18995 9574 18995 9548 18996 9574 18996 9541 18996 9541 18997 9574 18997 9575 18997 9541 18998 9575 18998 9542 18998 9542 18999 9575 18999 9550 18999 9542 19000 9550 19000 9543 19000 9543 19001 9550 19001 9576 19001 9543 19002 9576 19002 9551 19002 9572 19003 9545 19003 9576 19003 9576 19004 9545 19004 9551 19004 9545 19005 9572 19005 9552 19005 9552 19006 9572 19006 9553 19006 9552 19007 9553 19007 9554 19007 9554 19008 9553 19008 9555 19008 9554 19009 9555 19009 9544 19009 9544 19010 9555 19010 9556 19010 9544 19011 9556 19011 9546 19011 9546 19012 9556 19012 9573 19012 9570 19013 9571 19013 9567 19013 9567 19014 9571 19014 9539 19014 9539 19015 9571 19015 9537 19015 9537 19016 9571 19016 9557 19016 9537 19017 9557 19017 9558 19017 9558 19018 9557 19018 9559 19018 9558 19019 9559 19019 9560 19019 9560 19020 9559 19020 9561 19020 9560 19021 9561 19021 9538 19021 9538 19022 9561 19022 9577 19022 9540 19023 9568 19023 9562 19023 9562 19024 9568 19024 9569 19024 9562 19025 9569 19025 9563 19025 9563 19026 9569 19026 9564 19026 9563 19027 9564 19027 9565 19027 9565 19028 9564 19028 9566 19028 9565 19029 9566 19029 9567 19029 9567 19030 9566 19030 9570 19030 9549 19031 9578 19031 9568 19031 9568 19032 9578 19032 9571 19032 9564 19033 9569 19033 9566 19033 9566 19034 9569 19034 9568 19034 9566 19035 9568 19035 9570 19035 9570 19036 9568 19036 9571 19036 9573 19037 9556 19037 9555 19037 9576 19038 9568 19038 9572 19038 9572 19039 9568 19039 9573 19039 9572 19040 9573 19040 9553 19040 9553 19041 9573 19041 9555 19041 9574 19042 9549 19042 9575 19042 9575 19043 9549 19043 9568 19043 9575 19044 9568 19044 9550 19044 9550 19045 9568 19045 9576 19045 9559 19046 9557 19046 9561 19046 9561 19047 9557 19047 9571 19047 9561 19048 9571 19048 9577 19048 9577 19049 9571 19049 9578 19049 9580 19050 9579 19050 9601 19050 9579 19051 9580 19051 9589 19051 9589 19052 9580 19052 9581 19052 9589 19053 9581 19053 9592 19053 9582 19054 9583 19054 9584 19054 9584 19055 9583 19055 9585 19055 9584 19056 9585 19056 9586 19056 9586 19057 9585 19057 9580 19057 9586 19058 9580 19058 9587 19058 9587 19059 9580 19059 9601 19059 9587 19060 9601 19060 9604 19060 9598 19061 9588 19061 9594 19061 9594 19062 9588 19062 9589 19062 9594 19063 9589 19063 9593 19063 9593 19064 9589 19064 9592 19064 9586 19065 9587 19065 9612 19065 9612 19066 9587 19066 9606 19066 9581 19067 9590 19067 9592 19067 9592 19068 9590 19068 9591 19068 9592 19069 9591 19069 9593 19069 9593 19070 9591 19070 9595 19070 9593 19071 9595 19071 9594 19071 9594 19072 9595 19072 9596 19072 9594 19073 9596 19073 9598 19073 9598 19074 9596 19074 9597 19074 9598 19075 9597 19075 9588 19075 9588 19076 9597 19076 9599 19076 9588 19077 9599 19077 9589 19077 9589 19078 9599 19078 9609 19078 9609 19079 9602 19079 9589 19079 9589 19080 9602 19080 9579 19080 9585 19081 9608 19081 9600 19081 9585 19082 9600 19082 9580 19082 9580 19083 9600 19083 9590 19083 9580 19084 9590 19084 9581 19084 9579 19085 9602 19085 9601 19085 9601 19086 9602 19086 9603 19086 9601 19087 9603 19087 9604 19087 9604 19088 9603 19088 9605 19088 9604 19089 9605 19089 9587 19089 9587 19090 9605 19090 9606 19090 9586 19091 9612 19091 9584 19091 9584 19092 9612 19092 9611 19092 9584 19093 9611 19093 9582 19093 9582 19094 9611 19094 9610 19094 9582 19095 9610 19095 9583 19095 9583 19096 9610 19096 9607 19096 9583 19097 9607 19097 9585 19097 9585 19098 9607 19098 9608 19098 9590 19099 9600 19099 9609 19099 9609 19100 9600 19100 9602 19100 9612 19101 9606 19101 9600 19101 9595 19102 9591 19102 9590 19102 9606 19103 9605 19103 9600 19103 9600 19104 9605 19104 9603 19104 9600 19105 9603 19105 9602 19105 9609 19106 9599 19106 9597 19106 9590 19107 9609 19107 9595 19107 9595 19108 9609 19108 9597 19108 9595 19109 9597 19109 9596 19109 9610 19110 9611 19110 9607 19110 9607 19111 9611 19111 9612 19111 9607 19112 9612 19112 9608 19112 9608 19113 9612 19113 9600 19113 21347 19114 9613 19114 9632 19114 9614 19115 9615 19115 20104 19115 21301 19116 20115 19116 20113 19116 9617 19117 20113 19117 21224 19117 21224 19118 20113 19118 9616 19118 9617 19119 9618 19119 20113 19119 20113 19120 9618 19120 21300 19120 20113 19121 21300 19121 21301 19121 9620 19122 21229 19122 9616 19122 9616 19123 21229 19123 9619 19123 9616 19124 9619 19124 21224 19124 9666 19125 9620 19125 9624 19125 9666 19126 9667 19126 9620 19126 9620 19127 9667 19127 9621 19127 9620 19128 9621 19128 21229 19128 9622 19129 21285 19129 21129 19129 21286 19130 21290 19130 9625 19130 9625 19131 21290 19131 9623 19131 9625 19132 9623 19132 9624 19132 9624 19133 9623 19133 21294 19133 9624 19134 21294 19134 9666 19134 9622 19135 21129 19135 9625 19135 9625 19136 21129 19136 9656 19136 9625 19137 9656 19137 21286 19137 21285 19138 9622 19138 9626 19138 9626 19139 9622 19139 9628 19139 9626 19140 9628 19140 9629 19140 9614 19141 21120 19141 9615 19141 9615 19142 21120 19142 9627 19142 9615 19143 9627 19143 9628 19143 9628 19144 9627 19144 21269 19144 9628 19145 21269 19145 9629 19145 9613 19146 9639 19146 9632 19146 9632 19147 9639 19147 9641 19147 9632 19148 9641 19148 20104 19148 20104 19149 9641 19149 21349 19149 20104 19150 21349 19150 9614 19150 9630 19151 9631 19151 20103 19151 20103 19152 9631 19152 9632 19152 9632 19153 9631 19153 9633 19153 9632 19154 9633 19154 21347 19154 9634 19155 9635 19155 20102 19155 20102 19156 9635 19156 9636 19156 20102 19157 9636 19157 20103 19157 20103 19158 9636 19158 21342 19158 20103 19159 21342 19159 9630 19159 21363 19160 21121 19160 9637 19160 21363 19161 9637 19161 20102 19161 20102 19162 9637 19162 9638 19162 20102 19163 9638 19163 9634 19163 9639 19164 21348 19164 9725 19164 9725 19165 21348 19165 9640 19165 9725 19166 9640 19166 21358 19166 9639 19167 9725 19167 9641 19167 9641 19168 9725 19168 9723 19168 9641 19169 9723 19169 9642 19169 9642 19170 9723 19170 9644 19170 9642 19171 9644 19171 9643 19171 9643 19172 9644 19172 9645 19172 9643 19173 9645 19173 9647 19173 9647 19174 9645 19174 9646 19174 9647 19175 9646 19175 21350 19175 21350 19176 9646 19176 9648 19176 21350 19177 9648 19177 21351 19177 21120 19178 21119 19178 9649 19178 9649 19179 21119 19179 21354 19179 9649 19180 21354 19180 9797 19180 9797 19181 21354 19181 21112 19181 9797 19182 21112 19182 9799 19182 21120 19183 9649 19183 9627 19183 9627 19184 9649 19184 9650 19184 9627 19185 9650 19185 9651 19185 9651 19186 9650 19186 9796 19186 9651 19187 9796 19187 21270 19187 21270 19188 9796 19188 9652 19188 21270 19189 9652 19189 21279 19189 21279 19190 9652 19190 21118 19190 21279 19191 21118 19191 9653 19191 21129 19192 9654 19192 9804 19192 9804 19193 9654 19193 21284 19193 9804 19194 21284 19194 9655 19194 9655 19195 21284 19195 21283 19195 9655 19196 21283 19196 9806 19196 9806 19197 21283 19197 21281 19197 9806 19198 21281 19198 21103 19198 21129 19199 9804 19199 9656 19199 9656 19200 9804 19200 9803 19200 9656 19201 9803 19201 21287 19201 21287 19202 9803 19202 9657 19202 21287 19203 9657 19203 21288 19203 21288 19204 9657 19204 20826 19204 21288 19205 20826 19205 21289 19205 9813 19206 9659 19206 9658 19206 9658 19207 9659 19207 21297 19207 9658 19208 21297 19208 9814 19208 9814 19209 21297 19209 9660 19209 9814 19210 9660 19210 9661 19210 9661 19211 9660 19211 21295 19211 9661 19212 21295 19212 9663 19212 9663 19213 21295 19213 9662 19213 9663 19214 9662 19214 9664 19214 9813 19215 9665 19215 9659 19215 9659 19216 9665 19216 9811 19216 9659 19217 9811 19217 9666 19217 9666 19218 9811 19218 9810 19218 9666 19219 9810 19219 9667 19219 9667 19220 9810 19220 9668 19220 9667 19221 9668 19221 21299 19221 21299 19222 9668 19222 9809 19222 21299 19223 9809 19223 21102 19223 9824 19224 9670 19224 9669 19224 9669 19225 9670 19225 21222 19225 9670 19226 9822 19226 21222 19226 21222 19227 9822 19227 9671 19227 21222 19228 9671 19228 9672 19228 9672 19229 9671 19229 9821 19229 9672 19230 9821 19230 9673 19230 9673 19231 9821 19231 9819 19231 9819 19232 9674 19232 9673 19232 9673 19233 9674 19233 9818 19233 9673 19234 9818 19234 9675 19234 9818 19235 9817 19235 9675 19235 9675 19236 9817 19236 9676 19236 9675 19237 9676 19237 9677 19237 9677 19238 9676 19238 9678 19238 9677 19239 9678 19239 9617 19239 9617 19240 9678 19240 9679 19240 9617 19241 9679 19241 9618 19241 9618 19242 9679 19242 20808 19242 9618 19243 20808 19243 21096 19243 21078 19244 21077 19244 9680 19244 21078 19245 9680 19245 9826 19245 9826 19246 9680 19246 9681 19246 9826 19247 9681 19247 9682 19247 9682 19248 9681 19248 21253 19248 9682 19249 21253 19249 9683 19249 9683 19250 21253 19250 21256 19250 9683 19251 21256 19251 9684 19251 9684 19252 21256 19252 21255 19252 9684 19253 21255 19253 9830 19253 9830 19254 21255 19254 9685 19254 9830 19255 9685 19255 9832 19255 9686 19256 21067 19256 21308 19256 9686 19257 21308 19257 9833 19257 9833 19258 21308 19258 9687 19258 9833 19259 9687 19259 9834 19259 9834 19260 9687 19260 21306 19260 9834 19261 21306 19261 9688 19261 9688 19262 21306 19262 21305 19262 9688 19263 21305 19263 9835 19263 9835 19264 21305 19264 21161 19264 9835 19265 21161 19265 9836 19265 9836 19266 21161 19266 21162 19266 9836 19267 21162 19267 9689 19267 9689 19268 21162 19268 21163 19268 9689 19269 21163 19269 21076 19269 21059 19270 21058 19270 21312 19270 21059 19271 21312 19271 9690 19271 9690 19272 21312 19272 9691 19272 9690 19273 9691 19273 9692 19273 9692 19274 9691 19274 9693 19274 9692 19275 9693 19275 9840 19275 9840 19276 9693 19276 9695 19276 9840 19277 9695 19277 9694 19277 9694 19278 9695 19278 9696 19278 9694 19279 9696 19279 9842 19279 9842 19280 9696 19280 9697 19280 9842 19281 9697 19281 9698 19281 9698 19282 9697 19282 21066 19282 9698 19283 21066 19283 21065 19283 20785 19284 21049 19284 21319 19284 20785 19285 21319 19285 9843 19285 9843 19286 21319 19286 9699 19286 9843 19287 9699 19287 9845 19287 9845 19288 9699 19288 9700 19288 9845 19289 9700 19289 9701 19289 9701 19290 9700 19290 21125 19290 9701 19291 21125 19291 9702 19291 9702 19292 21125 19292 9704 19292 9702 19293 9704 19293 9703 19293 9703 19294 9704 19294 21324 19294 9703 19295 21324 19295 21055 19295 9709 19296 9705 19296 21180 19296 21180 19297 9705 19297 9706 19297 21180 19298 9706 19298 21039 19298 9707 19299 9852 19299 9708 19299 9708 19300 9852 19300 9851 19300 9708 19301 9851 19301 9709 19301 9709 19302 9851 19302 9849 19302 9709 19303 9849 19303 9705 19303 9707 19304 9708 19304 9710 19304 9710 19305 9708 19305 21174 19305 9710 19306 21174 19306 9853 19306 9853 19307 21174 19307 9712 19307 9853 19308 9712 19308 9711 19308 9711 19309 9712 19309 9713 19309 9711 19310 9713 19310 9854 19310 9854 19311 9713 19311 21045 19311 9854 19312 21045 19312 9856 19312 21030 19313 21328 19313 21334 19313 21030 19314 21334 19314 9859 19314 9859 19315 21334 19315 9714 19315 9859 19316 9714 19316 9715 19316 9715 19317 9714 19317 21141 19317 9715 19318 21141 19318 9861 19318 9861 19319 21141 19319 9716 19319 9861 19320 9716 19320 9717 19320 9717 19321 9716 19321 21336 19321 9717 19322 21336 19322 9718 19322 9718 19323 21336 19323 9719 19323 9718 19324 9719 19324 9864 19324 9864 19325 9719 19325 21031 19325 9864 19326 21031 19326 21032 19326 9635 19327 21337 19327 20759 19327 9635 19328 20759 19328 9636 19328 9636 19329 20759 19329 9874 19329 9636 19330 9874 19330 21341 19330 21341 19331 9874 19331 9720 19331 21341 19332 9720 19332 21340 19332 21340 19333 9720 19333 9871 19333 21340 19334 9871 19334 21343 19334 21343 19335 9871 19335 9869 19335 21343 19336 9869 19336 9721 19336 9721 19337 9869 19337 9867 19337 9721 19338 9867 19338 21198 19338 21198 19339 9867 19339 9866 19339 21198 19340 9866 19340 21023 19340 9722 19341 9648 19341 9646 19341 9722 19342 9646 19342 20752 19342 20752 19343 9646 19343 9645 19343 20752 19344 9645 19344 20750 19344 20750 19345 9645 19345 9644 19345 20750 19346 9644 19346 20749 19346 20749 19347 9644 19347 9723 19347 20749 19348 9723 19348 9724 19348 9724 19349 9723 19349 9725 19349 9724 19350 9725 19350 20748 19350 20748 19351 9725 19351 21358 19351 20748 19352 21358 19352 21010 19352 20735 19353 21310 19353 9875 19353 9875 19354 21310 19354 21263 19354 20712 19355 21254 19355 9878 19355 9878 19356 21254 19356 9726 19356 9878 19357 9726 19357 9880 19357 9880 19358 9726 19358 9727 19358 9880 19359 9727 19359 20984 19359 20984 19360 9727 19360 9728 19360 9886 19361 9729 19361 9888 19361 9888 19362 9729 19362 20956 19362 20668 19363 9730 19363 9731 19363 9731 19364 9730 19364 21272 19364 9731 19365 21272 19365 9889 19365 9889 19366 21272 19366 21274 19366 9889 19367 21274 19367 20670 19367 20670 19368 21274 19368 20936 19368 20932 19369 21213 19369 20908 19369 20908 19370 21213 19370 20910 19370 9732 19371 21185 19371 20641 19371 20641 19372 21185 19372 9733 19372 20641 19373 9733 19373 20639 19373 20639 19374 9733 19374 20905 19374 20623 19375 21159 19375 9892 19375 9892 19376 21159 19376 9734 19376 9892 19377 9734 19377 9895 19377 9895 19378 9734 19378 9735 19378 9895 19379 9735 19379 9736 19379 9736 19380 9735 19380 21166 19380 9736 19381 21166 19381 9737 19381 9737 19382 21166 19382 9738 19382 9737 19383 9738 19383 9739 19383 9739 19384 9738 19384 9740 19384 9739 19385 9740 19385 20613 19385 20613 19386 9740 19386 9741 19386 20612 19387 9742 19387 9899 19387 9899 19388 9742 19388 21318 19388 9899 19389 21318 19389 9901 19389 9901 19390 21318 19390 9743 19390 9901 19391 9743 19391 9904 19391 9904 19392 9743 19392 21316 19392 9904 19393 21316 19393 9744 19393 9744 19394 21316 19394 9745 19394 9744 19395 9745 19395 9906 19395 9906 19396 9745 19396 9746 19396 9906 19397 9746 19397 9747 19397 9747 19398 9746 19398 21320 19398 9747 19399 21320 19399 20605 19399 20605 19400 21320 19400 20876 19400 9907 19401 21150 19401 9748 19401 9748 19402 21150 19402 21149 19402 9748 19403 21149 19403 9909 19403 9909 19404 21149 19404 9749 19404 9909 19405 9749 19405 9751 19405 9751 19406 9749 19406 9750 19406 9751 19407 9750 19407 9912 19407 9912 19408 9750 19408 21152 19408 9912 19409 21152 19409 9913 19409 9913 19410 21152 19410 9752 19410 9913 19411 9752 19411 20873 19411 20873 19412 9752 19412 20875 19412 9914 19413 21146 19413 9916 19413 9916 19414 21146 19414 21145 19414 9916 19415 21145 19415 9917 19415 9917 19416 21145 19416 9753 19416 9917 19417 9753 19417 9754 19417 9754 19418 9753 19418 9755 19418 9754 19419 9755 19419 9921 19419 9921 19420 9755 19420 21142 19420 9921 19421 21142 19421 9756 19421 9756 19422 21142 19422 9757 19422 9756 19423 9757 19423 9758 19423 9758 19424 9757 19424 9759 19424 9758 19425 9759 19425 20582 19425 20582 19426 9759 19426 21332 19426 20864 19427 9760 19427 9761 19427 9761 19428 9760 19428 21137 19428 9761 19429 21137 19429 9925 19429 9925 19430 21137 19430 9763 19430 9925 19431 9763 19431 9762 19431 9762 19432 9763 19432 21134 19432 9762 19433 21134 19433 9764 19433 9764 19434 21134 19434 21344 19434 9764 19435 21344 19435 9765 19435 9765 19436 21344 19436 21138 19436 9765 19437 21138 19437 9930 19437 9930 19438 21138 19438 9766 19438 20572 19439 21278 19439 9767 19439 9767 19440 21278 19440 21271 19440 9767 19441 21271 19441 9768 19441 9768 19442 21271 19442 21276 19442 9768 19443 21276 19443 9769 19443 9769 19444 21276 19444 21275 19444 9769 19445 21275 19445 9934 19445 9934 19446 21275 19446 9770 19446 9934 19447 9770 19447 9936 19447 9936 19448 9770 19448 9772 19448 9936 19449 9772 19449 9771 19449 9771 19450 9772 19450 21282 19450 9937 19451 9773 19451 9938 19451 9938 19452 9773 19452 9774 19452 9938 19453 9774 19453 9940 19453 9940 19454 9774 19454 9775 19454 9940 19455 9775 19455 9776 19455 9776 19456 9775 19456 9777 19456 9776 19457 9777 19457 9943 19457 9943 19458 9777 19458 21296 19458 9943 19459 21296 19459 9944 19459 9944 19460 21296 19460 9778 19460 9944 19461 9778 19461 9779 19461 9779 19462 9778 19462 9780 19462 9779 19463 9780 19463 9781 19463 9781 19464 9780 19464 9782 19464 20555 19465 9783 19465 9784 19465 9784 19466 9783 19466 21234 19466 9784 19467 21234 19467 9785 19467 9785 19468 21234 19468 9786 19468 9785 19469 9786 19469 9950 19469 9950 19470 9786 19470 21232 19470 9950 19471 21232 19471 9952 19471 9952 19472 21232 19472 21231 19472 9952 19473 21231 19473 9787 19473 9787 19474 21231 19474 21226 19474 9787 19475 21226 19475 9955 19475 9955 19476 21226 19476 21225 19476 9955 19477 21225 19477 20842 19477 20842 19478 21225 19478 20843 19478 20841 19479 21241 19479 9957 19479 9957 19480 21241 19480 21242 19480 9957 19481 21242 19481 9788 19481 9788 19482 21242 19482 9789 19482 9788 19483 9789 19483 9790 19483 9790 19484 9789 19484 21239 19484 9790 19485 21239 19485 9963 19485 9963 19486 21239 19486 9791 19486 9963 19487 9791 19487 9792 19487 9792 19488 9791 19488 21244 19488 9792 19489 21244 19489 9966 19489 9966 19490 21244 19490 9793 19490 9966 19491 9793 19491 9967 19491 9967 19492 9793 19492 21243 19492 9794 19493 21118 19493 9652 19493 9794 19494 9652 19494 9795 19494 9795 19495 9652 19495 9796 19495 9795 19496 9796 19496 20525 19496 20525 19497 9796 19497 9650 19497 20525 19498 9650 19498 20526 19498 20526 19499 9650 19499 9649 19499 20526 19500 9649 19500 20528 19500 20528 19501 9649 19501 9797 19501 20528 19502 9797 19502 9798 19502 9798 19503 9797 19503 9799 19503 9798 19504 9799 19504 20827 19504 9800 19505 20826 19505 9657 19505 9800 19506 9657 19506 9801 19506 9801 19507 9657 19507 9803 19507 9801 19508 9803 19508 9802 19508 9802 19509 9803 19509 9804 19509 9802 19510 9804 19510 20520 19510 20520 19511 9804 19511 9655 19511 20520 19512 9655 19512 9805 19512 9805 19513 9655 19513 9806 19513 9805 19514 9806 19514 9807 19514 9807 19515 9806 19515 21103 19515 9807 19516 21103 19516 20521 19516 20508 19517 20509 19517 9668 19517 9668 19518 20509 19518 9808 19518 9668 19519 9808 19519 9809 19519 9668 19520 9810 19520 20508 19520 20508 19521 9810 19521 9811 19521 20508 19522 9811 19522 9812 19522 9812 19523 9811 19523 9665 19523 9665 19524 9813 19524 9812 19524 9812 19525 9813 19525 9658 19525 9812 19526 9658 19526 9815 19526 9658 19527 9814 19527 9815 19527 9815 19528 9814 19528 9661 19528 9815 19529 9661 19529 20513 19529 9661 19530 9663 19530 20513 19530 20513 19531 9663 19531 9664 19531 20513 19532 9664 19532 20511 19532 20505 19533 20808 19533 9679 19533 20505 19534 9679 19534 9816 19534 9816 19535 9679 19535 9678 19535 9816 19536 9678 19536 20506 19536 9678 19537 9676 19537 20506 19537 20506 19538 9676 19538 9817 19538 20506 19539 9817 19539 20495 19539 9817 19540 9818 19540 20495 19540 20495 19541 9818 19541 9674 19541 20495 19542 9674 19542 20496 19542 20496 19543 9674 19543 9819 19543 20496 19544 9819 19544 9820 19544 9819 19545 9821 19545 9820 19545 9820 19546 9821 19546 9671 19546 9820 19547 9671 19547 9823 19547 9823 19548 9671 19548 9822 19548 9822 19549 9670 19549 9823 19549 9823 19550 9670 19550 9824 19550 9823 19551 9824 19551 9825 19551 20484 19552 21078 19552 9826 19552 20484 19553 9826 19553 9827 19553 9827 19554 9826 19554 9682 19554 9827 19555 9682 19555 9828 19555 9828 19556 9682 19556 9683 19556 9828 19557 9683 19557 9829 19557 9829 19558 9683 19558 9684 19558 9829 19559 9684 19559 20486 19559 20486 19560 9684 19560 9830 19560 20486 19561 9830 19561 9831 19561 9831 19562 9830 19562 9832 19562 9831 19563 9832 19563 20796 19563 20795 19564 9686 19564 9833 19564 20795 19565 9833 19565 20480 19565 20480 19566 9833 19566 9834 19566 20480 19567 9834 19567 20481 19567 20481 19568 9834 19568 9688 19568 20481 19569 9688 19569 20468 19569 20468 19570 9688 19570 9835 19570 20468 19571 9835 19571 20470 19571 20470 19572 9835 19572 9836 19572 20470 19573 9836 19573 20473 19573 20473 19574 9836 19574 9689 19574 20473 19575 9689 19575 9837 19575 9837 19576 9689 19576 21076 19576 9837 19577 21076 19577 20474 19577 9838 19578 21059 19578 9690 19578 9838 19579 9690 19579 20465 19579 20465 19580 9690 19580 9692 19580 20465 19581 9692 19581 9839 19581 9839 19582 9692 19582 9840 19582 9839 19583 9840 19583 20467 19583 20467 19584 9840 19584 9694 19584 20467 19585 9694 19585 9841 19585 9841 19586 9694 19586 9842 19586 9841 19587 9842 19587 20454 19587 20454 19588 9842 19588 9698 19588 20454 19589 9698 19589 20456 19589 20456 19590 9698 19590 21065 19590 20456 19591 21065 19591 20786 19591 20439 19592 20785 19592 9843 19592 20439 19593 9843 19593 9844 19593 9844 19594 9843 19594 9845 19594 9844 19595 9845 19595 20442 19595 20442 19596 9845 19596 9701 19596 20442 19597 9701 19597 20444 19597 20444 19598 9701 19598 9702 19598 20444 19599 9702 19599 9846 19599 9846 19600 9702 19600 9703 19600 9846 19601 9703 19601 20446 19601 20446 19602 9703 19602 21055 19602 20446 19603 21055 19603 20448 19603 20428 19604 9847 19604 9705 19604 9705 19605 9847 19605 9848 19605 9705 19606 9848 19606 9706 19606 9705 19607 9849 19607 20428 19607 20428 19608 9849 19608 9851 19608 20428 19609 9851 19609 9850 19609 9850 19610 9851 19610 9852 19610 9852 19611 9707 19611 9850 19611 9850 19612 9707 19612 9710 19612 9850 19613 9710 19613 20437 19613 9710 19614 9853 19614 20437 19614 20437 19615 9853 19615 9711 19615 20437 19616 9711 19616 9855 19616 9711 19617 9854 19617 9855 19617 9855 19618 9854 19618 9856 19618 9855 19619 9856 19619 9857 19619 9858 19620 21030 19620 9859 19620 9858 19621 9859 19621 20424 19621 20424 19622 9859 19622 9715 19622 20424 19623 9715 19623 9860 19623 9860 19624 9715 19624 9861 19624 9860 19625 9861 19625 20414 19625 20414 19626 9861 19626 9717 19626 20414 19627 9717 19627 9862 19627 9862 19628 9717 19628 9718 19628 9862 19629 9718 19629 9863 19629 9863 19630 9718 19630 9864 19630 9863 19631 9864 19631 9865 19631 9865 19632 9864 19632 21032 19632 9865 19633 21032 19633 20767 19633 9868 19634 9866 19634 9867 19634 9868 19635 9867 19635 20404 19635 20404 19636 9867 19636 9869 19636 20404 19637 9869 19637 9870 19637 9870 19638 9869 19638 9871 19638 9870 19639 9871 19639 20405 19639 20405 19640 9871 19640 9720 19640 20405 19641 9720 19641 9872 19641 9872 19642 9720 19642 9874 19642 9872 19643 9874 19643 9873 19643 9873 19644 9874 19644 20759 19644 9873 19645 20759 19645 20409 19645 20382 19646 20735 19646 20383 19646 20383 19647 20735 19647 9875 19647 20722 19648 20721 19648 9876 19648 20722 19649 9876 19649 20994 19649 20994 19650 9876 19650 9877 19650 20994 19651 9877 19651 20992 19651 20377 19652 20712 19652 20376 19652 20376 19653 20712 19653 9878 19653 20376 19654 9878 19654 9879 19654 9879 19655 9878 19655 9880 19655 9879 19656 9880 19656 9881 19656 9881 19657 9880 19657 20984 19657 9882 19658 9883 19658 9884 19658 9884 19659 9883 19659 20361 19659 9884 19660 20361 19660 20965 19660 9885 19661 9886 19661 9887 19661 9887 19662 9886 19662 9888 19662 20667 19663 20668 19663 20357 19663 20357 19664 20668 19664 9731 19664 20357 19665 9731 19665 20358 19665 20358 19666 9731 19666 9889 19666 20358 19667 9889 19667 20671 19667 20671 19668 9889 19668 20670 19668 9890 19669 20623 19669 9891 19669 9891 19670 20623 19670 9892 19670 9891 19671 9892 19671 9893 19671 9893 19672 9892 19672 9895 19672 9893 19673 9895 19673 9894 19673 9894 19674 9895 19674 9736 19674 9894 19675 9736 19675 9896 19675 9896 19676 9736 19676 9737 19676 9896 19677 9737 19677 9897 19677 9897 19678 9737 19678 9739 19678 9897 19679 9739 19679 9898 19679 9898 19680 9739 19680 20613 19680 20317 19681 20612 19681 9899 19681 20317 19682 9899 19682 9900 19682 9900 19683 9899 19683 9901 19683 9900 19684 9901 19684 9978 19684 9978 19685 9901 19685 9902 19685 9902 19686 9901 19686 9904 19686 9902 19687 9904 19687 9903 19687 9903 19688 9904 19688 9979 19688 9979 19689 9904 19689 9744 19689 9979 19690 9744 19690 9905 19690 9905 19691 9744 19691 9982 19691 9982 19692 9744 19692 9906 19692 9982 19693 9906 19693 9980 19693 9980 19694 9906 19694 9747 19694 9980 19695 9747 19695 9981 19695 9981 19696 9747 19696 20605 19696 9981 19697 20605 19697 20315 19697 20604 19698 9907 19698 9984 19698 9984 19699 9907 19699 9748 19699 9984 19700 9748 19700 9908 19700 9908 19701 9748 19701 9909 19701 9908 19702 9909 19702 9910 19702 9910 19703 9909 19703 9751 19703 9910 19704 9751 19704 9985 19704 9985 19705 9751 19705 9912 19705 9985 19706 9912 19706 9911 19706 9911 19707 9912 19707 9913 19707 9911 19708 9913 19708 20593 19708 20593 19709 9913 19709 20873 19709 9915 19710 9914 19710 9916 19710 9915 19711 9916 19711 9986 19711 9986 19712 9916 19712 9917 19712 9986 19713 9917 19713 9989 19713 9989 19714 9917 19714 9918 19714 9918 19715 9917 19715 9754 19715 9918 19716 9754 19716 9988 19716 9988 19717 9754 19717 9919 19717 9919 19718 9754 19718 9921 19718 9919 19719 9921 19719 9920 19719 9920 19720 9921 19720 9987 19720 9987 19721 9921 19721 9756 19721 9987 19722 9756 19722 9922 19722 9922 19723 9756 19723 9758 19723 9922 19724 9758 19724 9923 19724 9923 19725 9758 19725 20582 19725 9923 19726 20582 19726 20581 19726 9924 19727 20864 19727 9990 19727 9990 19728 20864 19728 9761 19728 9990 19729 9761 19729 9991 19729 9991 19730 9761 19730 9925 19730 9991 19731 9925 19731 9926 19731 9926 19732 9925 19732 9762 19732 9926 19733 9762 19733 9927 19733 9927 19734 9762 19734 9764 19734 9927 19735 9764 19735 9928 19735 9928 19736 9764 19736 9765 19736 9928 19737 9765 19737 9929 19737 9929 19738 9765 19738 9930 19738 20571 19739 20572 19739 9992 19739 9992 19740 20572 19740 9767 19740 9992 19741 9767 19741 9931 19741 9931 19742 9767 19742 9768 19742 9931 19743 9768 19743 9932 19743 9932 19744 9768 19744 9769 19744 9932 19745 9769 19745 9933 19745 9933 19746 9769 19746 9934 19746 9933 19747 9934 19747 9935 19747 9935 19748 9934 19748 9936 19748 9935 19749 9936 19749 20302 19749 20302 19750 9936 19750 9771 19750 9993 19751 9937 19751 9938 19751 9993 19752 9938 19752 9998 19752 9998 19753 9938 19753 9940 19753 9998 19754 9940 19754 9939 19754 9939 19755 9940 19755 9941 19755 9941 19756 9940 19756 9776 19756 9941 19757 9776 19757 9997 19757 9997 19758 9776 19758 9942 19758 9942 19759 9776 19759 9943 19759 9942 19760 9943 19760 9996 19760 9996 19761 9943 19761 9994 19761 9994 19762 9943 19762 9944 19762 9994 19763 9944 19763 9995 19763 9995 19764 9944 19764 9779 19764 9995 19765 9779 19765 9945 19765 9945 19766 9779 19766 9781 19766 9945 19767 9781 19767 9946 19767 9947 19768 20555 19768 9784 19768 9947 19769 9784 19769 9948 19769 9948 19770 9784 19770 9785 19770 9948 19771 9785 19771 9949 19771 9949 19772 9785 19772 9999 19772 9999 19773 9785 19773 9950 19773 9999 19774 9950 19774 9951 19774 9951 19775 9950 19775 9953 19775 9953 19776 9950 19776 9952 19776 9953 19777 9952 19777 9954 19777 9954 19778 9952 19778 10000 19778 10000 19779 9952 19779 9787 19779 10000 19780 9787 19780 10001 19780 10001 19781 9787 19781 9955 19781 10001 19782 9955 19782 9956 19782 9956 19783 9955 19783 20842 19783 9956 19784 20842 19784 20543 19784 10003 19785 20841 19785 9957 19785 10003 19786 9957 19786 9958 19786 9958 19787 9957 19787 9788 19787 9958 19788 9788 19788 9959 19788 9959 19789 9788 19789 9960 19789 9960 19790 9788 19790 9790 19790 9960 19791 9790 19791 10005 19791 10005 19792 9790 19792 9961 19792 9961 19793 9790 19793 9963 19793 9961 19794 9963 19794 9962 19794 9962 19795 9963 19795 9964 19795 9964 19796 9963 19796 9792 19796 9964 19797 9792 19797 9965 19797 9965 19798 9792 19798 9966 19798 9965 19799 9966 19799 10004 19799 10004 19800 9966 19800 9967 19800 10004 19801 9967 19801 9968 19801 20397 19802 9969 19802 10078 19802 10078 19803 9969 19803 20747 19803 10078 19804 20747 19804 9970 19804 9970 19805 20747 19805 20746 19805 9970 19806 20746 19806 9971 19806 9971 19807 20746 19807 20745 19807 9971 19808 20745 19808 9972 19808 9972 19809 20745 19809 9974 19809 9972 19810 9974 19810 9973 19810 9973 19811 9974 19811 9975 19811 9973 19812 9975 19812 9976 19812 9976 19813 9975 19813 20756 19813 9976 19814 20756 19814 10082 19814 10082 19815 20756 19815 20755 19815 9977 19816 9893 19816 9894 19816 9891 19817 9893 19817 9977 19817 9890 19818 9891 19818 9977 19818 9977 19819 9897 19819 9898 19819 9896 19820 9897 19820 9977 19820 9894 19821 9896 19821 9977 19821 20320 19822 20317 19822 9900 19822 9978 19823 9902 19823 20320 19823 9903 19824 9979 19824 20320 19824 9905 19825 9982 19825 20320 19825 20320 19826 9981 19826 20315 19826 9980 19827 9981 19827 20320 19827 9982 19828 9980 19828 20320 19828 9979 19829 9905 19829 20320 19829 9902 19830 9903 19830 20320 19830 9900 19831 9978 19831 20320 19831 9983 19832 9908 19832 9910 19832 9984 19833 9908 19833 9983 19833 20604 19834 9984 19834 9983 19834 9983 19835 9911 19835 20593 19835 9985 19836 9911 19836 9983 19836 9910 19837 9985 19837 9983 19837 20312 19838 9915 19838 9986 19838 9989 19839 9918 19839 20312 19839 9988 19840 9919 19840 20312 19840 9920 19841 9987 19841 20312 19841 20312 19842 9923 19842 20581 19842 9922 19843 9923 19843 20312 19843 9987 19844 9922 19844 20312 19844 9919 19845 9920 19845 20312 19845 9918 19846 9988 19846 20312 19846 9986 19847 9989 19847 20312 19847 20305 19848 9991 19848 9926 19848 9990 19849 9991 19849 20305 19849 9924 19850 9990 19850 20305 19850 20305 19851 9928 19851 9929 19851 9927 19852 9928 19852 20305 19852 9926 19853 9927 19853 20305 19853 20304 19854 9931 19854 9932 19854 9992 19855 9931 19855 20304 19855 20571 19856 9992 19856 20304 19856 20304 19857 9935 19857 20302 19857 9933 19858 9935 19858 20304 19858 9932 19859 9933 19859 20304 19859 20297 19860 9993 19860 9998 19860 9939 19861 9941 19861 20297 19861 9997 19862 9942 19862 20297 19862 9996 19863 9994 19863 20297 19863 20297 19864 9945 19864 9946 19864 9995 19865 9945 19865 20297 19865 9994 19866 9995 19866 20297 19866 9942 19867 9996 19867 20297 19867 9941 19868 9997 19868 20297 19868 9998 19869 9939 19869 20297 19869 10002 19870 9947 19870 9948 19870 9949 19871 9999 19871 10002 19871 9951 19872 9953 19872 10002 19872 9954 19873 10000 19873 10002 19873 10002 19874 9956 19874 20543 19874 10001 19875 9956 19875 10002 19875 10000 19876 10001 19876 10002 19876 9953 19877 9954 19877 10002 19877 9999 19878 9951 19878 10002 19878 9948 19879 9949 19879 10002 19879 20291 19880 10003 19880 9958 19880 9959 19881 9960 19881 20291 19881 10005 19882 9961 19882 20291 19882 9962 19883 9964 19883 20291 19883 20291 19884 10004 19884 9968 19884 9965 19885 10004 19885 20291 19885 9964 19886 9965 19886 20291 19886 9961 19887 9962 19887 20291 19887 9960 19888 10005 19888 20291 19888 9958 19889 9959 19889 20291 19889 10006 19890 20530 19890 10084 19890 10084 19891 20530 19891 20531 19891 10084 19892 20531 19892 10085 19892 10085 19893 20531 19893 10007 19893 10085 19894 10007 19894 10086 19894 10086 19895 10007 19895 10008 19895 10086 19896 10008 19896 10089 19896 10089 19897 10008 19897 20534 19897 10089 19898 20534 19898 10010 19898 10010 19899 20534 19899 10009 19899 10010 19900 10009 19900 10092 19900 10092 19901 10009 19901 20524 19901 10092 19902 20524 19902 10011 19902 10011 19903 20524 19903 20280 19903 10012 19904 10013 19904 10014 19904 10014 19905 10013 19905 10015 19905 10014 19906 10015 19906 10016 19906 10016 19907 10015 19907 20522 19907 10016 19908 20522 19908 10097 19908 10097 19909 20522 19909 20514 19909 10097 19910 20514 19910 10017 19910 10017 19911 20514 19911 10018 19911 10017 19912 10018 19912 10101 19912 10101 19913 10018 19913 10019 19913 10101 19914 10019 19914 10020 19914 10020 19915 10019 19915 20517 19915 20262 19916 20512 19916 10103 19916 10103 19917 20512 19917 10021 19917 10103 19918 10021 19918 10107 19918 10107 19919 10021 19919 20510 19919 10107 19920 20510 19920 10108 19920 10108 19921 20510 19921 10022 19921 10108 19922 10022 19922 10024 19922 10024 19923 10022 19923 10023 19923 10024 19924 10023 19924 10112 19924 10112 19925 10023 19925 10026 19925 10112 19926 10026 19926 10025 19926 10025 19927 10026 19927 20271 19927 20185 19928 10027 19928 10115 19928 10115 19929 10027 19929 10028 19929 10115 19930 10028 19930 10030 19930 10030 19931 10028 19931 10029 19931 10030 19932 10029 19932 10031 19932 10031 19933 10029 19933 20501 19933 10031 19934 20501 19934 10116 19934 10116 19935 20501 19935 10032 19935 10116 19936 10032 19936 10033 19936 10033 19937 10032 19937 20502 19937 10033 19938 20502 19938 10034 19938 10034 19939 20502 19939 20504 19939 10118 19940 10035 19940 10036 19940 10036 19941 10035 19941 20488 19941 10036 19942 20488 19942 10121 19942 10121 19943 20488 19943 20490 19943 10121 19944 20490 19944 10037 19944 10037 19945 20490 19945 20491 19945 10037 19946 20491 19946 10123 19946 10123 19947 20491 19947 20493 19947 10123 19948 20493 19948 10038 19948 10038 19949 20493 19949 10039 19949 10038 19950 10039 19950 10125 19950 10125 19951 10039 19951 20482 19951 10125 19952 20482 19952 10040 19952 10040 19953 20482 19953 10041 19953 10126 19954 10042 19954 10043 19954 10043 19955 10042 19955 10044 19955 10043 19956 10044 19956 10128 19956 10128 19957 10044 19957 20475 19957 10128 19958 20475 19958 10046 19958 10046 19959 20475 19959 10045 19959 10046 19960 10045 19960 10129 19960 10129 19961 10045 19961 20477 19961 10129 19962 20477 19962 10047 19962 10047 19963 20477 19963 20478 19963 10047 19964 20478 19964 20153 19964 20153 19965 20478 19965 20479 19965 10131 19966 20457 19966 10048 19966 10048 19967 20457 19967 10049 19967 10048 19968 10049 19968 10132 19968 10132 19969 10049 19969 20458 19969 10132 19970 20458 19970 10134 19970 10134 19971 20458 19971 20460 19971 10134 19972 20460 19972 10135 19972 10135 19973 20460 19973 10051 19973 10135 19974 10051 19974 10050 19974 10050 19975 10051 19975 20462 19975 10050 19976 20462 19976 20236 19976 20236 19977 20462 19977 20237 19977 10136 19978 20447 19978 10137 19978 10137 19979 20447 19979 20449 19979 10137 19980 20449 19980 10053 19980 10053 19981 20449 19981 10052 19981 10053 19982 10052 19982 10138 19982 10138 19983 10052 19983 10054 19983 10138 19984 10054 19984 10139 19984 10139 19985 10054 19985 10055 19985 10139 19986 10055 19986 10142 19986 10142 19987 10055 19987 10056 19987 10142 19988 10056 19988 10143 19988 10143 19989 10056 19989 20451 19989 10143 19990 20451 19990 10144 19990 10144 19991 20451 19991 20438 19991 20145 19992 20436 19992 10146 19992 10146 19993 20436 19993 20435 19993 10146 19994 20435 19994 10147 19994 10147 19995 20435 19995 10058 19995 10147 19996 10058 19996 10057 19996 10057 19997 10058 19997 10059 19997 10057 19998 10059 19998 10060 19998 10060 19999 10059 19999 10061 19999 10060 20000 10061 20000 10149 20000 10149 20001 10061 20001 10062 20001 10149 20002 10062 20002 20134 20002 20134 20003 10062 20003 20430 20003 20226 20004 20416 20004 10063 20004 10063 20005 20416 20005 20417 20005 10063 20006 20417 20006 10064 20006 10064 20007 20417 20007 10065 20007 10064 20008 10065 20008 10152 20008 10152 20009 10065 20009 20420 20009 10152 20010 20420 20010 10066 20010 10066 20011 20420 20011 10067 20011 10066 20012 10067 20012 10155 20012 10155 20013 10067 20013 10068 20013 10155 20014 10068 20014 10069 20014 10069 20015 10068 20015 20422 20015 10070 20016 20407 20016 10071 20016 10071 20017 20407 20017 20408 20017 10071 20018 20408 20018 10156 20018 10156 20019 20408 20019 20411 20019 10156 20020 20411 20020 10157 20020 10157 20021 20411 20021 10072 20021 10157 20022 10072 20022 10074 20022 10074 20023 10072 20023 10073 20023 10074 20024 10073 20024 10075 20024 10075 20025 10073 20025 20400 20025 10075 20026 20400 20026 10076 20026 10076 20027 20400 20027 20401 20027 10076 20028 20401 20028 20118 20028 20118 20029 20401 20029 20403 20029 13373 20030 20397 20030 13375 20030 13375 20031 20397 20031 10078 20031 13375 20032 10078 20032 10077 20032 10077 20033 10078 20033 9970 20033 10077 20034 9970 20034 10079 20034 10079 20035 9970 20035 9971 20035 10079 20036 9971 20036 10080 20036 10080 20037 9971 20037 9972 20037 10080 20038 9972 20038 10081 20038 10081 20039 9972 20039 9973 20039 10081 20040 9973 20040 13379 20040 13379 20041 9973 20041 9976 20041 13379 20042 9976 20042 13564 20042 13564 20043 9976 20043 10082 20043 10083 20044 10006 20044 10084 20044 10083 20045 10084 20045 13388 20045 13388 20046 10084 20046 10085 20046 13388 20047 10085 20047 13390 20047 13390 20048 10085 20048 10087 20048 10087 20049 10085 20049 10086 20049 10087 20050 10086 20050 10088 20050 10088 20051 10086 20051 10090 20051 10090 20052 10086 20052 10089 20052 10090 20053 10089 20053 13385 20053 13385 20054 10089 20054 13386 20054 13386 20055 10089 20055 10010 20055 13386 20056 10010 20056 10091 20056 10091 20057 10010 20057 10092 20057 10091 20058 10092 20058 13383 20058 13383 20059 10092 20059 10011 20059 13383 20060 10011 20060 10093 20060 13551 20061 10012 20061 10094 20061 10094 20062 10012 20062 10014 20062 10094 20063 10014 20063 10095 20063 10095 20064 10014 20064 13398 20064 13398 20065 10014 20065 10016 20065 13398 20066 10016 20066 13399 20066 13399 20067 10016 20067 13397 20067 13397 20068 10016 20068 10097 20068 13397 20069 10097 20069 13395 20069 13395 20070 10097 20070 10096 20070 10096 20071 10097 20071 10017 20071 10096 20072 10017 20072 13394 20072 13394 20073 10017 20073 10098 20073 10098 20074 10017 20074 10101 20074 10098 20075 10101 20075 10099 20075 10099 20076 10101 20076 10100 20076 10100 20077 10101 20077 10020 20077 10100 20078 10020 20078 13546 20078 20193 20079 20262 20079 10102 20079 10102 20080 20262 20080 10103 20080 10102 20081 10103 20081 13405 20081 13405 20082 10103 20082 10104 20082 10104 20083 10103 20083 10107 20083 10104 20084 10107 20084 10105 20084 10105 20085 10107 20085 10106 20085 10106 20086 10107 20086 10108 20086 10106 20087 10108 20087 10109 20087 10109 20088 10108 20088 13401 20088 13401 20089 10108 20089 10024 20089 13401 20090 10024 20090 10110 20090 10110 20091 10024 20091 10111 20091 10111 20092 10024 20092 10112 20092 10111 20093 10112 20093 10113 20093 10113 20094 10112 20094 13400 20094 13400 20095 10112 20095 10025 20095 13400 20096 10025 20096 10114 20096 13540 20097 20185 20097 13407 20097 13407 20098 20185 20098 10115 20098 13407 20099 10115 20099 13409 20099 13409 20100 10115 20100 10030 20100 13409 20101 10030 20101 13410 20101 13410 20102 10030 20102 10031 20102 13410 20103 10031 20103 13412 20103 13412 20104 10031 20104 10116 20104 13412 20105 10116 20105 10117 20105 10117 20106 10116 20106 10033 20106 10117 20107 10033 20107 13533 20107 13533 20108 10033 20108 10034 20108 13524 20109 10118 20109 10036 20109 13524 20110 10036 20110 10119 20110 10119 20111 10036 20111 10121 20111 10119 20112 10121 20112 13422 20112 13422 20113 10121 20113 10120 20113 10120 20114 10121 20114 10037 20114 10120 20115 10037 20115 13423 20115 13423 20116 10037 20116 10122 20116 10122 20117 10037 20117 10123 20117 10122 20118 10123 20118 13420 20118 13420 20119 10123 20119 13418 20119 13418 20120 10123 20120 10038 20120 13418 20121 10038 20121 10124 20121 10124 20122 10038 20122 10125 20122 10124 20123 10125 20123 13415 20123 13415 20124 10125 20124 10040 20124 13415 20125 10040 20125 13523 20125 20162 20126 10126 20126 10127 20126 10127 20127 10126 20127 10043 20127 10127 20128 10043 20128 13425 20128 13425 20129 10043 20129 10128 20129 13425 20130 10128 20130 13426 20130 13426 20131 10128 20131 10046 20131 13426 20132 10046 20132 13428 20132 13428 20133 10046 20133 10129 20133 13428 20134 10129 20134 10130 20134 10130 20135 10129 20135 10047 20135 10130 20136 10047 20136 20154 20136 20154 20137 10047 20137 20153 20137 13429 20138 10131 20138 13431 20138 13431 20139 10131 20139 10048 20139 13431 20140 10048 20140 13433 20140 13433 20141 10048 20141 10132 20141 13433 20142 10132 20142 10133 20142 10133 20143 10132 20143 10134 20143 10133 20144 10134 20144 13434 20144 13434 20145 10134 20145 10135 20145 13434 20146 10135 20146 13436 20146 13436 20147 10135 20147 10050 20147 13436 20148 10050 20148 13504 20148 13504 20149 10050 20149 20236 20149 20148 20150 10136 20150 13438 20150 13438 20151 10136 20151 10137 20151 13438 20152 10137 20152 13440 20152 13440 20153 10137 20153 10053 20153 13440 20154 10053 20154 13442 20154 13442 20155 10053 20155 10138 20155 13442 20156 10138 20156 13443 20156 13443 20157 10138 20157 10139 20157 13443 20158 10139 20158 10140 20158 10140 20159 10139 20159 10142 20159 10140 20160 10142 20160 10141 20160 10141 20161 10142 20161 10143 20161 10141 20162 10143 20162 13447 20162 13447 20163 10143 20163 10144 20163 13487 20164 20145 20164 13449 20164 13449 20165 20145 20165 10146 20165 13449 20166 10146 20166 10145 20166 10145 20167 10146 20167 10147 20167 10145 20168 10147 20168 13454 20168 13454 20169 10147 20169 10057 20169 13454 20170 10057 20170 13456 20170 13456 20171 10057 20171 10060 20171 13456 20172 10060 20172 10148 20172 10148 20173 10060 20173 10149 20173 10148 20174 10149 20174 20136 20174 20136 20175 10149 20175 20134 20175 13458 20176 20226 20176 13459 20176 13459 20177 20226 20177 10063 20177 13459 20178 10063 20178 10150 20178 10150 20179 10063 20179 10064 20179 10150 20180 10064 20180 10151 20180 10151 20181 10064 20181 10152 20181 10151 20182 10152 20182 10153 20182 10153 20183 10152 20183 10066 20183 10153 20184 10066 20184 10154 20184 10154 20185 10066 20185 10155 20185 10154 20186 10155 20186 13462 20186 13462 20187 10155 20187 10069 20187 20123 20188 10070 20188 13463 20188 13463 20189 10070 20189 10071 20189 13463 20190 10071 20190 13465 20190 13465 20191 10071 20191 10156 20191 13465 20192 10156 20192 13468 20192 13468 20193 10156 20193 10157 20193 13468 20194 10157 20194 10158 20194 10158 20195 10157 20195 10074 20195 10158 20196 10074 20196 10159 20196 10159 20197 10074 20197 10075 20197 10159 20198 10075 20198 10160 20198 10160 20199 10075 20199 10076 20199 10160 20200 10076 20200 20117 20200 20117 20201 10076 20201 20118 20201 20084 20202 20086 20202 10168 20202 19845 20203 21381 20203 10161 20203 10161 20204 21381 20204 21382 20204 10161 20205 21382 20205 19927 20205 10162 20206 20115 20206 10163 20206 10163 20207 20115 20207 21381 20207 10163 20208 21381 20208 10251 20208 10251 20209 21381 20209 19845 20209 19927 20210 21382 20210 20096 20210 20096 20211 21382 20211 21380 20211 20096 20212 21380 20212 10164 20212 21379 20213 20091 20213 10165 20213 21379 20214 10165 20214 21380 20214 21380 20215 10165 20215 10166 20215 21380 20216 10166 20216 10164 20216 10168 20217 20086 20217 21379 20217 21379 20218 20086 20218 20087 20218 21379 20219 20087 20219 20091 20219 21376 20220 19846 20220 10167 20220 21376 20221 10167 20221 10168 20221 10168 20222 10167 20222 20083 20222 10168 20223 20083 20223 20084 20223 10169 20224 20080 20224 21376 20224 21376 20225 20080 20225 20074 20225 21376 20226 20074 20226 19846 20226 19848 20227 10181 20227 21372 20227 21372 20228 10181 20228 10184 20228 21372 20229 10184 20229 10169 20229 10169 20230 10184 20230 10170 20230 10169 20231 10170 20231 20080 20231 19848 20232 21372 20232 20065 20232 20065 20233 21372 20233 10171 20233 20065 20234 10171 20234 10173 20234 10173 20235 10171 20235 10172 20235 10173 20236 10172 20236 20064 20236 20061 20237 20062 20237 10172 20237 10172 20238 20062 20238 20063 20238 10172 20239 20063 20239 20064 20239 20061 20240 10172 20240 20060 20240 20060 20241 10172 20241 10175 20241 20060 20242 10175 20242 20057 20242 19874 20243 10193 20243 21365 20243 21365 20244 10193 20244 10174 20244 21365 20245 10174 20245 10175 20245 10175 20246 10174 20246 20056 20246 10175 20247 20056 20247 20057 20247 21363 20248 20101 20248 21365 20248 21365 20249 20101 20249 10176 20249 21365 20250 10176 20250 19874 20250 10177 20251 19838 20251 20073 20251 20073 20252 19838 20252 10178 20252 20073 20253 10178 20253 10180 20253 10180 20254 10178 20254 10179 20254 10180 20255 10179 20255 10181 20255 10181 20256 10179 20256 10183 20256 19553 20257 10182 20257 10359 20257 10359 20258 10182 20258 20079 20258 10359 20259 20079 20259 10357 20259 10357 20260 20079 20260 20082 20260 10357 20261 20082 20261 10356 20261 10356 20262 20082 20262 20081 20262 10356 20263 20081 20263 10183 20263 10183 20264 20081 20264 10184 20264 10183 20265 10184 20265 10181 20265 10187 20266 10360 20266 10173 20266 10185 20267 19835 20267 10186 20267 10186 20268 19835 20268 10187 20268 10186 20269 10187 20269 20064 20269 20064 20270 10187 20270 10173 20270 19547 20271 20067 20271 10188 20271 10188 20272 20067 20272 10189 20272 10188 20273 10189 20273 10190 20273 10190 20274 10189 20274 20066 20274 10190 20275 20066 20275 10361 20275 10361 20276 20066 20276 10191 20276 10361 20277 10191 20277 10360 20277 10360 20278 10191 20278 10192 20278 10360 20279 10192 20279 10173 20279 10200 20280 10193 20280 19828 20280 19828 20281 10193 20281 19874 20281 19828 20282 19874 20282 19875 20282 10370 20283 19907 20283 10195 20283 10195 20284 19907 20284 10194 20284 10195 20285 10194 20285 10367 20285 10367 20286 10194 20286 10196 20286 10367 20287 10196 20287 10197 20287 10197 20288 10196 20288 19887 20288 10197 20289 19887 20289 10198 20289 10198 20290 19887 20290 10199 20290 10198 20291 10199 20291 10200 20291 10200 20292 10199 20292 10201 20292 10200 20293 10201 20293 10193 20293 10381 20294 19820 20294 10380 20294 10380 20295 19820 20295 19849 20295 10380 20296 19849 20296 10378 20296 10378 20297 19849 20297 19850 20297 10378 20298 19850 20298 10202 20298 10202 20299 19850 20299 20049 20299 10202 20300 20049 20300 10375 20300 10375 20301 20049 20301 20051 20301 10375 20302 20051 20302 10374 20302 10374 20303 20051 20303 20052 20303 10374 20304 20052 20304 10371 20304 10371 20305 20052 20305 10203 20305 10371 20306 10203 20306 19827 20306 19827 20307 10203 20307 10204 20307 10205 20308 20030 20308 10388 20308 10388 20309 20030 20309 10206 20309 10388 20310 10206 20310 10386 20310 10386 20311 10206 20311 10207 20311 10386 20312 10207 20312 10385 20312 10385 20313 10207 20313 19867 20313 10385 20314 19867 20314 10208 20314 10208 20315 19867 20315 19868 20315 10208 20316 19868 20316 10383 20316 10383 20317 19868 20317 20036 20317 10383 20318 20036 20318 19536 20318 19536 20319 20036 20319 20038 20319 10209 20320 10211 20320 10210 20320 10210 20321 10211 20321 20005 20321 10210 20322 20005 20322 10393 20322 10393 20323 20005 20323 20003 20323 10393 20324 20003 20324 10391 20324 10391 20325 20003 20325 10212 20325 10391 20326 10212 20326 10213 20326 10213 20327 10212 20327 20022 20327 10213 20328 20022 20328 10214 20328 10214 20329 20022 20329 20024 20329 10214 20330 20024 20330 10389 20330 10389 20331 20024 20331 10216 20331 10389 20332 10216 20332 10215 20332 10215 20333 10216 20333 20025 20333 20013 20334 19804 20334 10217 20334 10217 20335 19804 20335 10395 20335 10222 20336 10218 20336 19997 20336 10395 20337 10219 20337 10217 20337 10217 20338 10219 20338 10220 20338 10217 20339 10220 20339 19997 20339 19997 20340 10220 20340 10221 20340 19997 20341 10221 20341 10222 20341 10222 20342 10398 20342 10218 20342 10218 20343 10398 20343 10224 20343 10218 20344 10224 20344 10223 20344 10224 20345 10225 20345 10223 20345 10223 20346 10225 20346 10401 20346 10223 20347 10401 20347 10226 20347 19526 20348 20001 20348 10227 20348 10227 20349 20001 20349 10226 20349 10227 20350 10226 20350 10228 20350 10228 20351 10226 20351 10401 20351 10411 20352 19984 20352 10409 20352 10409 20353 19984 20353 19983 20353 10409 20354 19983 20354 10229 20354 10229 20355 19983 20355 19981 20355 10229 20356 19981 20356 10230 20356 10230 20357 19981 20357 10231 20357 10230 20358 10231 20358 10406 20358 10406 20359 10231 20359 19936 20359 10406 20360 19936 20360 10232 20360 10232 20361 19936 20361 19935 20361 10232 20362 19935 20362 10405 20362 10405 20363 19935 20363 19995 20363 19784 20364 19973 20364 10233 20364 10233 20365 19973 20365 19974 20365 10233 20366 19974 20366 10415 20366 10415 20367 19974 20367 10234 20367 10415 20368 10234 20368 10235 20368 10235 20369 10234 20369 10236 20369 10235 20370 10236 20370 10237 20370 10237 20371 10236 20371 19947 20371 10237 20372 19947 20372 10238 20372 10238 20373 19947 20373 10239 20373 10238 20374 10239 20374 10240 20374 10240 20375 10239 20375 19787 20375 19845 20376 10249 20376 10250 20376 10242 20377 19782 20377 19514 20377 19514 20378 10241 20378 10242 20378 10242 20379 10241 20379 10243 20379 10242 20380 10243 20380 19863 20380 10243 20381 10427 20381 19863 20381 19863 20382 10427 20382 10426 20382 19863 20383 10426 20383 10244 20383 10426 20384 10425 20384 10244 20384 10244 20385 10425 20385 10245 20385 10244 20386 10245 20386 10246 20386 10245 20387 10422 20387 10246 20387 10246 20388 10422 20388 10421 20388 10246 20389 10421 20389 10247 20389 10247 20390 10421 20390 10248 20390 10247 20391 10248 20391 10249 20391 10249 20392 10248 20392 10418 20392 10249 20393 10418 20393 10250 20393 19845 20394 10250 20394 10251 20394 10251 20395 10250 20395 19498 20395 10251 20396 19498 20396 19923 20396 10439 20397 10440 20397 20097 20397 10257 20398 10252 20398 10437 20398 10437 20399 10252 20399 10253 20399 10437 20400 10253 20400 10434 20400 10434 20401 10253 20401 10254 20401 10434 20402 10254 20402 10431 20402 10431 20403 10254 20403 10255 20403 10431 20404 10255 20404 10256 20404 10256 20405 10255 20405 19766 20405 20097 20406 20095 20406 10439 20406 10439 20407 20095 20407 10166 20407 10439 20408 10166 20408 10257 20408 10257 20409 10166 20409 10165 20409 10257 20410 10165 20410 10252 20410 10262 20411 10263 20411 10258 20411 10258 20412 10263 20412 10259 20412 10258 20413 10259 20413 10443 20413 10443 20414 10259 20414 10260 20414 10443 20415 10260 20415 19492 20415 19492 20416 10260 20416 10261 20416 10265 20417 20083 20417 10262 20417 10262 20418 20083 20418 10167 20418 10262 20419 10167 20419 10263 20419 19764 20420 10264 20420 10447 20420 10447 20421 10264 20421 10266 20421 10447 20422 10266 20422 10265 20422 10265 20423 10266 20423 10267 20423 10265 20424 10267 20424 20083 20424 19478 20425 19756 20425 10268 20425 10268 20426 19756 20426 19949 20426 10268 20427 19949 20427 10454 20427 10454 20428 19949 20428 19932 20428 10454 20429 19932 20429 10451 20429 10451 20430 19932 20430 10269 20430 10451 20431 10269 20431 10450 20431 10450 20432 10269 20432 19971 20432 10450 20433 19971 20433 10449 20433 10449 20434 19971 20434 19972 20434 10449 20435 19972 20435 10270 20435 10270 20436 19972 20436 19890 20436 10270 20437 19890 20437 19485 20437 19485 20438 19890 20438 19963 20438 19731 20439 10272 20439 10271 20439 10271 20440 10272 20440 19734 20440 10460 20441 19959 20441 10462 20441 10462 20442 19959 20442 20023 20442 10462 20443 20023 20443 10464 20443 10464 20444 20023 20444 20021 20444 10464 20445 20021 20445 10465 20445 10465 20446 20021 20446 19711 20446 19707 20447 19708 20447 19419 20447 19419 20448 19708 20448 10273 20448 19409 20449 19678 20449 10274 20449 10274 20450 19678 20450 10275 20450 10274 20451 10275 20451 19679 20451 19679 20452 10275 20452 19948 20452 10276 20453 19646 20453 19390 20453 19390 20454 19646 20454 19897 20454 10467 20455 19908 20455 10469 20455 10469 20456 19908 20456 19901 20456 10469 20457 19901 20457 10277 20457 10277 20458 19901 20458 19900 20458 10277 20459 19900 20459 10278 20459 10278 20460 19900 20460 19629 20460 19620 20461 10479 20461 10480 20461 19620 20462 10480 20462 10279 20462 10279 20463 10480 20463 10481 20463 10279 20464 10481 20464 10280 20464 10280 20465 10481 20465 10282 20465 10280 20466 10282 20466 10281 20466 10281 20467 10282 20467 10478 20467 10281 20468 10478 20468 10283 20468 10478 20469 10477 20469 10283 20469 10283 20470 10477 20470 10285 20470 10283 20471 10285 20471 10284 20471 10284 20472 10285 20472 10286 20472 10286 20473 10287 20473 10284 20473 10284 20474 10287 20474 10475 20474 10284 20475 10475 20475 10288 20475 10288 20476 10475 20476 19615 20476 10288 20477 19615 20477 10289 20477 10290 20478 19040 20478 10291 20478 10291 20479 19040 20479 10516 20479 10291 20480 10516 20480 20085 20480 20085 20481 10516 20481 10292 20481 20085 20482 10292 20482 10293 20482 10293 20483 10292 20483 10518 20483 10293 20484 10518 20484 10294 20484 10294 20485 10518 20485 10519 20485 10294 20486 10519 20486 20090 20486 20090 20487 10519 20487 10295 20487 20090 20488 10295 20488 10296 20488 10296 20489 10295 20489 10297 20489 19604 20490 10298 20490 10299 20490 19604 20491 10299 20491 20078 20491 20078 20492 10299 20492 10301 20492 20078 20493 10301 20493 10300 20493 10300 20494 10301 20494 10528 20494 10300 20495 10528 20495 10302 20495 10302 20496 10528 20496 10526 20496 10302 20497 10526 20497 10303 20497 10526 20498 10525 20498 10303 20498 10303 20499 10525 20499 10304 20499 10303 20500 10304 20500 10307 20500 10307 20501 10304 20501 10305 20501 10305 20502 10306 20502 10307 20502 10307 20503 10306 20503 10309 20503 10307 20504 10309 20504 10308 20504 10308 20505 10309 20505 10522 20505 10308 20506 10522 20506 19598 20506 10310 20507 19597 20507 19886 20507 19886 20508 19597 20508 10529 20508 19886 20509 10529 20509 20058 20509 20058 20510 10529 20510 10311 20510 20058 20511 10311 20511 10312 20511 10312 20512 10311 20512 10530 20512 10312 20513 10530 20513 10313 20513 10313 20514 10530 20514 10531 20514 10313 20515 10531 20515 19883 20515 19883 20516 10531 20516 10315 20516 19883 20517 10315 20517 10314 20517 10314 20518 10315 20518 19590 20518 19589 20519 19017 20519 19876 20519 19876 20520 19017 20520 10533 20520 19876 20521 10533 20521 10316 20521 10316 20522 10533 20522 10318 20522 10316 20523 10318 20523 10317 20523 10317 20524 10318 20524 10534 20524 10317 20525 10534 20525 19873 20525 19873 20526 10534 20526 10535 20526 19873 20527 10535 20527 10319 20527 10319 20528 10535 20528 10320 20528 10319 20529 10320 20529 20055 20529 20055 20530 10320 20530 10321 20530 20055 20531 10321 20531 19880 20531 19880 20532 10321 20532 19010 20532 19871 20533 19582 20533 10322 20533 10322 20534 19582 20534 10323 20534 10322 20535 10323 20535 10324 20535 10324 20536 10323 20536 10325 20536 10324 20537 10325 20537 19866 20537 19866 20538 10325 20538 10327 20538 19866 20539 10327 20539 10326 20539 10326 20540 10327 20540 10538 20540 10326 20541 10538 20541 20027 20541 20027 20542 10538 20542 10539 20542 20027 20543 10539 20543 10328 20543 10328 20544 10539 20544 19002 20544 20010 20545 10541 20545 20014 20545 20014 20546 10541 20546 10329 20546 20014 20547 10329 20547 10330 20547 10330 20548 10329 20548 10331 20548 10330 20549 10331 20549 20006 20549 20006 20550 10331 20550 10543 20550 20006 20551 10543 20551 20002 20551 20002 20552 10543 20552 10332 20552 20002 20553 10332 20553 10333 20553 10333 20554 10332 20554 10545 20554 10333 20555 10545 20555 10334 20555 10334 20556 10545 20556 10547 20556 19991 20557 10335 20557 10336 20557 10336 20558 10335 20558 10552 20558 10336 20559 10552 20559 10337 20559 10337 20560 10552 20560 10553 20560 10337 20561 10553 20561 10338 20561 10338 20562 10553 20562 10339 20562 10338 20563 10339 20563 10340 20563 10340 20564 10339 20564 10341 20564 10340 20565 10341 20565 19988 20565 19988 20566 10341 20566 10556 20566 19988 20567 10556 20567 19987 20567 19987 20568 10556 20568 10342 20568 19987 20569 10342 20569 19989 20569 19989 20570 10342 20570 10549 20570 19979 20571 10343 20571 19978 20571 19978 20572 10343 20572 10344 20572 19978 20573 10344 20573 19942 20573 19942 20574 10344 20574 10346 20574 19942 20575 10346 20575 10345 20575 10345 20576 10346 20576 10560 20576 10345 20577 10560 20577 10347 20577 10347 20578 10560 20578 10348 20578 10347 20579 10348 20579 10349 20579 10349 20580 10348 20580 10350 20580 10349 20581 10350 20581 19941 20581 19941 20582 10350 20582 10352 20582 19941 20583 10352 20583 10351 20583 10351 20584 10352 20584 19562 20584 19838 20585 18850 20585 10178 20585 10178 20586 18850 20586 10353 20586 10178 20587 10353 20587 10179 20587 10179 20588 10353 20588 10354 20588 10179 20589 10354 20589 10183 20589 10183 20590 10354 20590 10355 20590 10183 20591 10355 20591 10356 20591 10356 20592 10355 20592 10609 20592 10356 20593 10609 20593 10357 20593 10357 20594 10609 20594 10358 20594 10357 20595 10358 20595 10359 20595 10359 20596 10358 20596 10611 20596 10359 20597 10611 20597 19553 20597 19553 20598 10611 20598 10613 20598 19835 20599 19552 20599 10187 20599 10187 20600 19552 20600 10601 20600 10187 20601 10601 20601 10360 20601 10360 20602 10601 20602 10362 20602 10360 20603 10362 20603 10361 20603 10361 20604 10362 20604 10363 20604 10361 20605 10363 20605 10190 20605 10190 20606 10363 20606 10603 20606 10190 20607 10603 20607 10188 20607 10188 20608 10603 20608 10604 20608 10188 20609 10604 20609 19547 20609 19547 20610 10604 20610 10364 20610 19828 20611 10595 20611 10200 20611 10200 20612 10595 20612 10365 20612 10200 20613 10365 20613 10198 20613 10198 20614 10365 20614 10596 20614 10198 20615 10596 20615 10197 20615 10197 20616 10596 20616 10366 20616 10197 20617 10366 20617 10367 20617 10367 20618 10366 20618 10368 20618 10367 20619 10368 20619 10195 20619 10195 20620 10368 20620 10369 20620 10195 20621 10369 20621 10370 20621 10370 20622 10369 20622 10599 20622 19827 20623 10372 20623 10371 20623 10371 20624 10372 20624 10373 20624 10371 20625 10373 20625 10374 20625 10374 20626 10373 20626 10588 20626 10374 20627 10588 20627 10375 20627 10375 20628 10588 20628 10376 20628 10375 20629 10376 20629 10202 20629 10202 20630 10376 20630 10377 20630 10202 20631 10377 20631 10378 20631 10378 20632 10377 20632 10379 20632 10378 20633 10379 20633 10380 20633 10380 20634 10379 20634 10592 20634 10380 20635 10592 20635 10381 20635 10381 20636 10592 20636 18867 20636 19536 20637 10382 20637 10383 20637 10383 20638 10382 20638 10384 20638 10383 20639 10384 20639 10208 20639 10208 20640 10384 20640 10581 20640 10208 20641 10581 20641 10385 20641 10385 20642 10581 20642 10582 20642 10385 20643 10582 20643 10386 20643 10386 20644 10582 20644 10584 20644 10386 20645 10584 20645 10388 20645 10388 20646 10584 20646 10387 20646 10388 20647 10387 20647 10205 20647 10205 20648 10387 20648 10586 20648 10215 20649 18885 20649 10389 20649 10389 20650 18885 20650 10390 20650 10389 20651 10390 20651 10214 20651 10214 20652 10390 20652 10573 20652 10214 20653 10573 20653 10213 20653 10213 20654 10573 20654 10392 20654 10213 20655 10392 20655 10391 20655 10391 20656 10392 20656 10394 20656 10391 20657 10394 20657 10393 20657 10393 20658 10394 20658 10575 20658 10393 20659 10575 20659 10210 20659 10210 20660 10575 20660 10576 20660 10210 20661 10576 20661 10209 20661 10209 20662 10576 20662 10579 20662 19804 20663 19530 20663 10395 20663 10395 20664 19530 20664 10653 20664 10395 20665 10653 20665 10219 20665 10219 20666 10653 20666 10396 20666 10219 20667 10396 20667 10220 20667 10220 20668 10396 20668 10397 20668 10220 20669 10397 20669 10221 20669 10221 20670 10397 20670 10651 20670 10221 20671 10651 20671 10222 20671 10222 20672 10651 20672 10650 20672 10222 20673 10650 20673 10398 20673 10398 20674 10650 20674 10399 20674 10398 20675 10399 20675 10224 20675 10224 20676 10399 20676 10400 20676 10224 20677 10400 20677 10225 20677 10225 20678 10400 20678 10649 20678 10225 20679 10649 20679 10401 20679 10401 20680 10649 20680 10648 20680 10401 20681 10648 20681 10228 20681 10228 20682 10648 20682 10402 20682 10228 20683 10402 20683 10227 20683 10227 20684 10402 20684 10403 20684 10227 20685 10403 20685 19526 20685 19526 20686 10403 20686 10404 20686 10405 20687 18820 20687 10232 20687 10232 20688 18820 20688 10641 20688 10232 20689 10641 20689 10406 20689 10406 20690 10641 20690 10407 20690 10406 20691 10407 20691 10230 20691 10230 20692 10407 20692 10408 20692 10230 20693 10408 20693 10229 20693 10229 20694 10408 20694 10645 20694 10229 20695 10645 20695 10409 20695 10409 20696 10645 20696 10410 20696 10409 20697 10410 20697 10411 20697 10411 20698 10410 20698 18814 20698 10240 20699 10412 20699 10238 20699 10238 20700 10412 20700 10413 20700 10238 20701 10413 20701 10237 20701 10237 20702 10413 20702 10414 20702 10237 20703 10414 20703 10235 20703 10235 20704 10414 20704 10638 20704 10235 20705 10638 20705 10415 20705 10415 20706 10638 20706 10639 20706 10415 20707 10639 20707 10233 20707 10233 20708 10639 20708 10640 20708 10233 20709 10640 20709 19784 20709 19784 20710 10640 20710 10416 20710 10417 20711 19498 20711 10628 20711 10628 20712 19498 20712 10250 20712 10628 20713 10250 20713 10629 20713 10629 20714 10250 20714 10418 20714 10629 20715 10418 20715 10419 20715 10419 20716 10418 20716 10248 20716 10419 20717 10248 20717 10420 20717 10420 20718 10248 20718 10421 20718 10420 20719 10421 20719 10632 20719 10632 20720 10421 20720 10422 20720 10632 20721 10422 20721 10423 20721 10423 20722 10422 20722 10245 20722 10423 20723 10245 20723 10633 20723 10633 20724 10245 20724 10425 20724 10633 20725 10425 20725 10424 20725 10424 20726 10425 20726 10426 20726 10424 20727 10426 20727 10634 20727 10634 20728 10426 20728 10427 20728 10634 20729 10427 20729 10428 20729 10428 20730 10427 20730 10243 20730 10428 20731 10243 20731 10429 20731 10429 20732 10243 20732 10241 20732 10429 20733 10241 20733 10430 20733 10430 20734 10241 20734 19514 20734 10256 20735 10432 20735 10431 20735 10431 20736 10432 20736 10433 20736 10431 20737 10433 20737 10434 20737 10434 20738 10433 20738 10435 20738 10434 20739 10435 20739 10437 20739 10437 20740 10435 20740 10436 20740 10437 20741 10436 20741 10257 20741 10257 20742 10436 20742 10624 20742 10257 20743 10624 20743 10439 20743 10439 20744 10624 20744 10438 20744 10439 20745 10438 20745 10440 20745 10440 20746 10438 20746 10441 20746 19492 20747 10442 20747 10443 20747 10443 20748 10442 20748 10444 20748 10443 20749 10444 20749 10258 20749 10258 20750 10444 20750 10618 20750 10258 20751 10618 20751 10262 20751 10262 20752 10618 20752 10445 20752 10262 20753 10445 20753 10265 20753 10265 20754 10445 20754 10446 20754 10265 20755 10446 20755 10447 20755 10447 20756 10446 20756 10620 20756 10447 20757 10620 20757 19764 20757 19764 20758 10620 20758 10621 20758 19485 20759 10448 20759 10270 20759 10270 20760 10448 20760 18802 20760 10270 20761 18802 20761 10449 20761 10449 20762 18802 20762 18803 20762 10449 20763 18803 20763 10450 20763 10450 20764 18803 20764 10452 20764 10450 20765 10452 20765 10451 20765 10451 20766 10452 20766 10453 20766 10451 20767 10453 20767 10454 20767 10454 20768 10453 20768 10455 20768 10454 20769 10455 20769 10268 20769 10268 20770 10455 20770 10456 20770 10268 20771 10456 20771 19478 20771 19478 20772 10456 20772 18806 20772 19471 20773 10457 20773 19742 20773 19742 20774 10457 20774 10458 20774 19742 20775 10458 20775 19739 20775 19461 20776 19731 20776 18961 20776 18961 20777 19731 20777 10271 20777 10459 20778 10460 20778 18980 20778 18980 20779 10460 20779 10462 20779 18980 20780 10462 20780 10461 20780 10461 20781 10462 20781 10464 20781 10461 20782 10464 20782 10463 20782 10463 20783 10464 20783 10465 20783 10463 20784 10465 20784 18975 20784 10466 20785 10276 20785 19391 20785 19391 20786 10276 20786 19390 20786 19373 20787 10467 20787 10468 20787 10468 20788 10467 20788 10469 20788 10468 20789 10469 20789 10470 20789 10470 20790 10469 20790 10471 20790 10471 20791 10469 20791 10277 20791 10471 20792 10277 20792 10472 20792 10472 20793 10277 20793 10278 20793 10472 20794 10278 20794 18943 20794 10473 20795 19361 20795 10563 20795 10473 20796 10563 20796 19621 20796 19621 20797 10563 20797 10565 20797 19621 20798 10565 20798 19359 20798 19351 20799 19615 20799 10474 20799 10474 20800 19615 20800 10475 20800 10474 20801 10475 20801 10476 20801 10475 20802 10287 20802 10476 20802 10476 20803 10287 20803 10286 20803 10476 20804 10286 20804 19047 20804 19047 20805 10286 20805 10285 20805 10285 20806 10477 20806 19047 20806 19047 20807 10477 20807 10478 20807 19047 20808 10478 20808 10483 20808 10479 20809 19054 20809 10480 20809 10480 20810 19054 20810 10482 20810 10480 20811 10482 20811 10481 20811 10481 20812 10482 20812 10483 20812 10481 20813 10483 20813 10282 20813 10282 20814 10483 20814 10478 20814 19350 20815 10484 20815 10512 20815 19350 20816 10512 20816 10485 20816 10485 20817 10512 20817 10486 20817 10485 20818 10486 20818 10487 20818 10487 20819 10486 20819 10488 20819 10487 20820 10488 20820 18798 20820 18798 20821 10488 20821 10510 20821 18798 20822 10510 20822 18795 20822 18795 20823 10510 20823 10505 20823 18795 20824 10505 20824 10489 20824 10489 20825 10505 20825 10506 20825 10489 20826 10506 20826 10490 20826 10490 20827 10506 20827 10491 20827 10490 20828 10491 20828 18777 20828 18777 20829 10491 20829 10492 20829 18777 20830 10492 20830 18776 20830 18776 20831 10492 20831 10503 20831 18776 20832 10503 20832 10493 20832 10493 20833 10503 20833 10501 20833 10493 20834 10501 20834 18773 20834 18773 20835 10501 20835 10500 20835 18773 20836 10500 20836 10494 20836 10494 20837 10500 20837 10499 20837 10494 20838 10499 20838 18784 20838 18784 20839 10499 20839 10495 20839 18784 20840 10495 20840 18783 20840 18783 20841 10495 20841 19336 20841 18783 20842 19336 20842 10496 20842 10497 20843 19336 20843 10495 20843 10497 20844 10495 20844 10498 20844 10498 20845 10495 20845 10499 20845 10498 20846 10499 20846 19168 20846 19168 20847 10499 20847 19170 20847 19170 20848 10499 20848 10500 20848 19170 20849 10500 20849 19147 20849 19147 20850 10500 20850 19090 20850 19090 20851 10500 20851 10501 20851 19090 20852 10501 20852 10502 20852 10492 20853 10504 20853 10503 20853 10503 20854 10504 20854 19081 20854 10503 20855 19081 20855 10501 20855 10501 20856 19081 20856 19088 20856 10501 20857 19088 20857 10502 20857 10491 20858 10507 20858 10492 20858 10492 20859 10507 20859 19141 20859 10492 20860 19141 20860 10504 20860 10510 20861 19290 20861 10505 20861 10505 20862 19290 20862 19214 20862 10505 20863 19214 20863 10506 20863 10506 20864 19214 20864 19218 20864 10506 20865 19218 20865 10491 20865 10491 20866 19218 20866 19294 20866 10491 20867 19294 20867 10507 20867 19304 20868 10508 20868 10510 20868 10510 20869 10508 20869 10509 20869 10510 20870 10509 20870 19290 20870 19304 20871 10510 20871 19284 20871 19284 20872 10510 20872 10488 20872 19284 20873 10488 20873 19285 20873 19285 20874 10488 20874 10511 20874 10511 20875 10488 20875 10486 20875 10511 20876 10486 20876 19198 20876 19198 20877 10486 20877 10512 20877 19198 20878 10512 20878 10515 20878 10484 20879 19093 20879 10513 20879 10484 20880 10513 20880 10512 20880 10512 20881 10513 20881 10514 20881 10512 20882 10514 20882 10515 20882 19040 20883 19041 20883 10516 20883 10516 20884 19041 20884 10517 20884 10516 20885 10517 20885 10292 20885 10292 20886 10517 20886 19124 20886 10292 20887 19124 20887 10518 20887 10518 20888 19124 20888 19176 20888 10518 20889 19176 20889 10519 20889 10519 20890 19176 20890 19123 20890 10519 20891 19123 20891 10295 20891 10295 20892 19123 20892 10520 20892 10295 20893 10520 20893 10297 20893 10297 20894 10520 20894 10521 20894 19029 20895 10522 20895 10523 20895 10523 20896 10522 20896 10309 20896 10523 20897 10309 20897 10524 20897 10309 20898 10306 20898 10524 20898 10524 20899 10306 20899 10305 20899 10524 20900 10305 20900 19071 20900 19071 20901 10305 20901 10304 20901 10304 20902 10525 20902 19071 20902 19071 20903 10525 20903 10526 20903 19071 20904 10526 20904 19183 20904 10298 20905 19068 20905 10299 20905 10299 20906 19068 20906 10527 20906 10299 20907 10527 20907 10301 20907 10301 20908 10527 20908 19183 20908 10301 20909 19183 20909 10528 20909 10528 20910 19183 20910 10526 20910 19597 20911 19111 20911 10529 20911 10529 20912 19111 20912 19110 20912 10529 20913 19110 20913 10311 20913 10311 20914 19110 20914 19109 20914 10311 20915 19109 20915 10530 20915 10530 20916 19109 20916 19107 20916 10530 20917 19107 20917 10531 20917 10531 20918 19107 20918 10532 20918 10531 20919 10532 20919 10315 20919 10315 20920 10532 20920 19113 20920 10315 20921 19113 20921 19590 20921 19590 20922 19113 20922 19112 20922 19017 20923 19018 20923 10533 20923 10533 20924 19018 20924 19104 20924 10533 20925 19104 20925 10318 20925 10318 20926 19104 20926 19103 20926 10318 20927 19103 20927 10534 20927 10534 20928 19103 20928 19098 20928 10534 20929 19098 20929 10535 20929 10535 20930 19098 20930 19100 20930 10535 20931 19100 20931 10320 20931 10320 20932 19100 20932 19102 20932 10320 20933 19102 20933 10321 20933 10321 20934 19102 20934 10536 20934 10321 20935 10536 20935 19010 20935 19010 20936 10536 20936 19012 20936 19582 20937 10537 20937 10323 20937 10323 20938 10537 20938 19196 20938 10323 20939 19196 20939 10325 20939 10325 20940 19196 20940 19195 20940 10325 20941 19195 20941 10327 20941 10327 20942 19195 20942 19194 20942 10327 20943 19194 20943 10538 20943 10538 20944 19194 20944 10540 20944 10538 20945 10540 20945 10539 20945 10539 20946 10540 20946 19272 20946 10539 20947 19272 20947 19002 20947 19002 20948 19272 20948 19273 20948 10541 20949 19297 20949 10329 20949 10329 20950 19297 20950 10542 20950 10329 20951 10542 20951 10331 20951 10331 20952 10542 20952 19292 20952 10331 20953 19292 20953 10543 20953 10543 20954 19292 20954 19291 20954 10543 20955 19291 20955 10332 20955 10332 20956 19291 20956 10544 20956 10332 20957 10544 20957 10545 20957 10545 20958 10544 20958 10546 20958 10545 20959 10546 20959 10547 20959 10547 20960 10546 20960 10548 20960 19086 20961 18992 20961 10549 20961 10342 20962 19089 20962 10549 20962 10549 20963 19089 20963 19087 20963 10549 20964 19087 20964 19086 20964 10335 20965 19139 20965 10550 20965 10550 20966 10551 20966 10335 20966 10335 20967 10551 20967 19137 20967 10335 20968 19137 20968 10552 20968 10552 20969 19137 20969 10554 20969 10552 20970 10554 20970 10553 20970 10553 20971 10554 20971 19085 20971 10553 20972 19085 20972 10339 20972 10339 20973 19085 20973 19084 20973 10339 20974 19084 20974 10341 20974 10341 20975 19084 20975 10555 20975 10341 20976 10555 20976 10556 20976 10556 20977 10555 20977 19083 20977 10556 20978 19083 20978 10342 20978 10342 20979 19083 20979 10557 20979 10342 20980 10557 20980 19089 20980 10343 20981 10558 20981 10344 20981 10344 20982 10558 20982 10559 20982 10344 20983 10559 20983 10346 20983 10346 20984 10559 20984 19157 20984 10346 20985 19157 20985 10560 20985 10560 20986 19157 20986 19159 20986 10560 20987 19159 20987 10348 20987 10348 20988 19159 20988 19154 20988 10348 20989 19154 20989 10350 20989 10350 20990 19154 20990 19153 20990 10350 20991 19153 20991 10352 20991 10352 20992 19153 20992 19165 20992 10352 20993 19165 20993 19562 20993 19562 20994 19165 20994 19166 20994 18974 20995 10561 20995 10562 20995 10562 20996 10561 20996 19278 20996 10562 20997 19278 20997 19445 20997 19445 20998 19278 20998 19277 20998 19445 20999 19277 20999 19444 20999 19444 21000 19277 21000 19317 21000 10457 21001 19260 21001 10458 21001 10458 21002 19260 21002 19263 21002 19361 21003 10564 21003 10563 21003 10563 21004 10564 21004 10566 21004 10563 21005 10566 21005 10565 21005 10565 21006 10566 21006 19259 21006 10567 21007 19242 21007 19380 21007 19380 21008 19242 21008 18932 21008 18915 21009 10568 21009 19067 21009 19067 21010 10568 21010 10569 21010 19067 21011 10569 21011 10570 21011 10570 21012 10569 21012 19399 21012 10570 21013 19399 21013 19055 21013 19055 21014 19399 21014 19400 21014 19055 21015 19400 21015 10571 21015 18892 21016 19173 21016 19428 21016 19428 21017 19173 21017 19145 21017 18885 21018 18886 21018 10390 21018 10390 21019 18886 21019 19289 21019 10390 21020 19289 21020 10573 21020 10573 21021 19289 21021 10572 21021 10573 21022 10572 21022 10392 21022 10392 21023 10572 21023 10574 21023 10392 21024 10574 21024 10394 21024 10394 21025 10574 21025 19287 21025 10394 21026 19287 21026 10575 21026 10575 21027 19287 21027 10577 21027 10575 21028 10577 21028 10576 21028 10576 21029 10577 21029 10578 21029 10576 21030 10578 21030 10579 21030 10579 21031 10578 21031 19216 21031 10382 21032 10580 21032 10384 21032 10384 21033 10580 21033 19207 21033 10384 21034 19207 21034 10581 21034 10581 21035 19207 21035 19078 21035 10581 21036 19078 21036 10582 21036 10582 21037 19078 21037 10583 21037 10582 21038 10583 21038 10584 21038 10584 21039 10583 21039 19210 21039 10584 21040 19210 21040 10387 21040 10387 21041 19210 21041 10585 21041 10387 21042 10585 21042 10586 21042 10586 21043 10585 21043 18871 21043 10372 21044 19200 21044 10373 21044 10373 21045 19200 21045 10587 21045 10373 21046 10587 21046 10588 21046 10588 21047 10587 21047 10589 21047 10588 21048 10589 21048 10376 21048 10376 21049 10589 21049 19204 21049 10376 21050 19204 21050 10377 21050 10377 21051 19204 21051 10590 21051 10377 21052 10590 21052 10379 21052 10379 21053 10590 21053 10591 21053 10379 21054 10591 21054 10592 21054 10592 21055 10591 21055 10593 21055 10592 21056 10593 21056 18867 21056 18867 21057 10593 21057 10594 21057 10595 21058 18866 21058 10365 21058 10365 21059 18866 21059 19091 21059 10365 21060 19091 21060 10596 21060 10596 21061 19091 21061 10597 21061 10596 21062 10597 21062 10366 21062 10366 21063 10597 21063 10598 21063 10366 21064 10598 21064 10368 21064 10368 21065 10598 21065 19096 21065 10368 21066 19096 21066 10369 21066 10369 21067 19096 21067 19095 21067 10369 21068 19095 21068 10599 21068 10599 21069 19095 21069 10600 21069 19552 21070 19193 21070 10601 21070 10601 21071 19193 21071 19191 21071 10601 21072 19191 21072 10362 21072 10362 21073 19191 21073 19189 21073 10362 21074 19189 21074 10363 21074 10363 21075 19189 21075 10602 21075 10363 21076 10602 21076 10603 21076 10603 21077 10602 21077 19187 21077 10603 21078 19187 21078 10604 21078 10604 21079 19187 21079 10605 21079 10604 21080 10605 21080 10364 21080 10364 21081 10605 21081 10606 21081 18850 21082 19180 21082 10353 21082 10353 21083 19180 21083 10607 21083 10353 21084 10607 21084 10354 21084 10354 21085 10607 21085 19300 21085 10354 21086 19300 21086 10355 21086 10355 21087 19300 21087 10608 21087 10355 21088 10608 21088 10609 21088 10609 21089 10608 21089 10610 21089 10609 21090 10610 21090 10358 21090 10358 21091 10610 21091 10612 21091 10358 21092 10612 21092 10611 21092 10611 21093 10612 21093 10614 21093 10611 21094 10614 21094 10613 21094 10613 21095 10614 21095 10615 21095 10442 21096 10616 21096 10444 21096 10444 21097 10616 21097 10617 21097 10444 21098 10617 21098 10618 21098 10618 21099 10617 21099 10619 21099 10618 21100 10619 21100 10445 21100 10445 21101 10619 21101 19184 21101 10445 21102 19184 21102 10446 21102 10446 21103 19184 21103 19177 21103 10446 21104 19177 21104 10620 21104 10620 21105 19177 21105 10622 21105 10620 21106 10622 21106 10621 21106 10621 21107 10622 21107 19125 21107 10432 21108 10623 21108 10433 21108 10433 21109 10623 21109 19133 21109 10433 21110 19133 21110 10435 21110 10435 21111 19133 21111 19134 21111 10435 21112 19134 21112 10436 21112 10436 21113 19134 21113 19128 21113 10436 21114 19128 21114 10624 21114 10624 21115 19128 21115 10625 21115 10624 21116 10625 21116 10438 21116 10438 21117 10625 21117 10626 21117 10438 21118 10626 21118 10441 21118 10441 21119 10626 21119 10627 21119 19057 21120 18832 21120 10417 21120 10417 21121 10628 21121 19057 21121 19057 21122 10628 21122 10629 21122 19057 21123 10629 21123 10631 21123 10423 21124 19060 21124 10630 21124 10629 21125 10419 21125 10631 21125 10631 21126 10419 21126 10420 21126 10631 21127 10420 21127 10630 21127 10630 21128 10420 21128 10632 21128 10630 21129 10632 21129 10423 21129 10423 21130 10633 21130 19060 21130 19060 21131 10633 21131 10424 21131 19060 21132 10424 21132 19061 21132 19061 21133 10424 21133 10634 21133 19061 21134 10634 21134 10636 21134 10430 21135 10635 21135 10429 21135 10429 21136 10635 21136 10636 21136 10429 21137 10636 21137 10428 21137 10428 21138 10636 21138 10634 21138 10412 21139 19160 21139 10413 21139 10413 21140 19160 21140 10637 21140 10413 21141 10637 21141 10414 21141 10414 21142 10637 21142 19221 21142 10414 21143 19221 21143 10638 21143 10638 21144 19221 21144 19220 21144 10638 21145 19220 21145 10639 21145 10639 21146 19220 21146 19172 21146 10639 21147 19172 21147 10640 21147 10640 21148 19172 21148 19171 21148 10640 21149 19171 21149 10416 21149 10416 21150 19171 21150 19161 21150 18820 21151 10642 21151 10641 21151 10641 21152 10642 21152 10643 21152 10641 21153 10643 21153 10407 21153 10407 21154 10643 21154 10644 21154 10407 21155 10644 21155 10408 21155 10408 21156 10644 21156 10646 21156 10408 21157 10646 21157 10645 21157 10645 21158 10646 21158 19162 21158 10645 21159 19162 21159 10410 21159 10410 21160 19162 21160 19149 21160 10410 21161 19149 21161 18814 21161 18814 21162 19149 21162 19148 21162 18808 21163 10404 21163 10647 21163 10647 21164 10404 21164 10403 21164 10400 21165 19318 21165 19321 21165 10403 21166 10402 21166 10647 21166 10647 21167 10402 21167 10648 21167 10647 21168 10648 21168 19321 21168 19321 21169 10648 21169 10649 21169 19321 21170 10649 21170 10400 21170 10400 21171 10399 21171 19318 21171 19318 21172 10399 21172 10650 21172 19318 21173 10650 21173 10652 21173 10650 21174 10651 21174 10652 21174 10652 21175 10651 21175 10397 21175 10652 21176 10397 21176 19136 21176 19530 21177 19293 21177 10653 21177 10653 21178 19293 21178 19136 21178 10653 21179 19136 21179 10396 21179 10396 21180 19136 21180 10397 21180 18772 21181 10672 21181 10673 21181 18772 21182 10673 21182 10654 21182 10654 21183 10673 21183 10675 21183 10654 21184 10675 21184 18726 21184 18726 21185 10675 21185 10655 21185 18726 21186 10655 21186 18727 21186 18727 21187 10655 21187 10656 21187 18727 21188 10656 21188 18728 21188 18728 21189 10656 21189 10658 21189 18728 21190 10658 21190 10657 21190 10657 21191 10658 21191 10659 21191 10657 21192 10659 21192 10660 21192 10660 21193 10659 21193 10679 21193 10660 21194 10679 21194 18732 21194 18732 21195 10679 21195 10680 21195 18732 21196 10680 21196 10661 21196 10661 21197 10680 21197 10682 21197 10661 21198 10682 21198 10662 21198 10662 21199 10682 21199 10664 21199 10662 21200 10664 21200 10663 21200 10663 21201 10664 21201 10685 21201 10663 21202 10685 21202 18735 21202 18735 21203 10685 21203 10666 21203 18735 21204 10666 21204 10665 21204 10665 21205 10666 21205 10667 21205 10665 21206 10667 21206 18736 21206 18736 21207 10667 21207 10668 21207 18736 21208 10668 21208 10669 21208 10669 21209 10668 21209 10687 21209 10669 21210 10687 21210 10670 21210 10670 21211 10687 21211 18712 21211 10670 21212 18712 21212 18739 21212 10672 21213 18693 21213 10671 21213 10672 21214 10671 21214 10673 21214 10673 21215 10671 21215 10674 21215 10673 21216 10674 21216 10675 21216 10675 21217 10674 21217 10676 21217 10675 21218 10676 21218 10655 21218 10655 21219 10676 21219 10677 21219 10655 21220 10677 21220 10656 21220 10656 21221 10677 21221 10678 21221 10656 21222 10678 21222 10658 21222 10658 21223 10678 21223 10697 21223 10658 21224 10697 21224 10659 21224 10659 21225 10697 21225 10695 21225 10659 21226 10695 21226 10679 21226 10679 21227 10695 21227 10681 21227 10679 21228 10681 21228 10680 21228 10680 21229 10681 21229 10693 21229 10680 21230 10693 21230 10682 21230 10682 21231 10693 21231 10683 21231 10682 21232 10683 21232 10664 21232 10664 21233 10683 21233 10691 21233 10664 21234 10691 21234 10685 21234 10685 21235 10691 21235 10684 21235 10685 21236 10684 21236 10666 21236 10666 21237 10684 21237 10690 21237 10666 21238 10690 21238 10667 21238 10667 21239 10690 21239 10686 21239 10667 21240 10686 21240 10668 21240 10668 21241 10686 21241 10688 21241 10668 21242 10688 21242 10687 21242 10687 21243 10688 21243 18711 21243 10687 21244 18711 21244 18712 21244 18782 21245 18711 21245 10688 21245 18782 21246 10688 21246 10689 21246 10689 21247 10688 21247 10686 21247 10689 21248 10686 21248 18785 21248 18785 21249 10686 21249 10690 21249 18785 21250 10690 21250 18786 21250 18786 21251 10690 21251 10684 21251 18786 21252 10684 21252 18774 21252 18774 21253 10684 21253 10691 21253 18774 21254 10691 21254 18775 21254 18775 21255 10691 21255 10683 21255 18775 21256 10683 21256 10692 21256 10692 21257 10683 21257 10693 21257 10692 21258 10693 21258 10694 21258 10694 21259 10693 21259 10681 21259 10694 21260 10681 21260 18778 21260 18778 21261 10681 21261 10695 21261 18778 21262 10695 21262 10696 21262 10696 21263 10695 21263 10697 21263 10696 21264 10697 21264 18779 21264 18779 21265 10697 21265 10678 21265 18779 21266 10678 21266 18796 21266 18796 21267 10678 21267 10677 21267 18796 21268 10677 21268 18797 21268 18797 21269 10677 21269 10676 21269 18797 21270 10676 21270 10698 21270 10698 21271 10676 21271 10674 21271 10698 21272 10674 21272 10699 21272 10699 21273 10674 21273 10671 21273 10699 21274 10671 21274 18799 21274 18799 21275 10671 21275 18693 21275 18799 21276 18693 21276 18692 21276 10700 21277 18691 21277 18725 21277 10700 21278 18725 21278 13592 21278 13592 21279 18725 21279 10701 21279 13592 21280 10701 21280 13591 21280 13591 21281 10701 21281 10702 21281 13591 21282 10702 21282 13590 21282 13590 21283 10702 21283 18729 21283 13590 21284 18729 21284 10703 21284 10703 21285 18729 21285 18730 21285 10703 21286 18730 21286 13587 21286 13587 21287 18730 21287 10704 21287 13587 21288 10704 21288 10705 21288 10705 21289 10704 21289 18731 21289 10705 21290 18731 21290 13586 21290 13586 21291 18731 21291 10706 21291 13586 21292 10706 21292 13583 21292 13583 21293 10706 21293 18733 21293 13583 21294 18733 21294 13582 21294 13582 21295 18733 21295 10708 21295 13582 21296 10708 21296 10707 21296 10707 21297 10708 21297 18734 21297 10707 21298 18734 21298 13580 21298 13580 21299 18734 21299 10709 21299 13580 21300 10709 21300 10710 21300 10710 21301 10709 21301 10711 21301 10710 21302 10711 21302 13577 21302 13577 21303 10711 21303 18737 21303 13577 21304 18737 21304 13575 21304 13575 21305 18737 21305 10712 21305 13575 21306 10712 21306 13574 21306 13574 21307 10712 21307 18738 21307 13574 21308 18738 21308 10713 21308 10714 21309 12186 21309 12188 21309 10714 21310 12188 21310 10716 21310 10716 21311 12188 21311 10715 21311 10716 21312 10715 21312 15747 21312 15747 21313 10715 21313 10717 21313 15747 21314 10717 21314 10718 21314 10718 21315 10717 21315 12190 21315 10718 21316 12190 21316 10719 21316 10719 21317 12190 21317 10720 21317 10719 21318 10720 21318 10721 21318 10721 21319 10720 21319 10722 21319 10721 21320 10722 21320 10723 21320 10723 21321 10722 21321 17247 21321 10723 21322 17247 21322 18581 21322 10724 21323 10725 21323 10726 21323 10724 21324 10726 21324 10727 21324 10727 21325 10726 21325 12206 21325 10727 21326 12206 21326 10729 21326 10729 21327 12206 21327 10728 21327 10729 21328 10728 21328 10730 21328 10730 21329 10728 21329 10731 21329 10730 21330 10731 21330 12413 21330 12413 21331 10731 21331 12203 21331 12413 21332 12203 21332 10732 21332 10732 21333 12203 21333 12201 21333 10732 21334 12201 21334 12412 21334 12412 21335 12201 21335 10734 21335 12412 21336 10734 21336 10733 21336 10733 21337 10734 21337 10735 21337 10733 21338 10735 21338 12409 21338 12409 21339 10735 21339 10736 21339 12409 21340 10736 21340 12406 21340 12406 21341 10736 21341 10737 21341 12406 21342 10737 21342 12405 21342 12405 21343 10737 21343 10738 21343 12405 21344 10738 21344 12403 21344 12403 21345 10738 21345 10740 21345 12403 21346 10740 21346 10739 21346 10739 21347 10740 21347 10742 21347 10739 21348 10742 21348 10741 21348 10741 21349 10742 21349 10743 21349 10741 21350 10743 21350 12402 21350 12402 21351 10743 21351 10744 21351 12402 21352 10744 21352 10745 21352 10745 21353 10744 21353 10746 21353 10745 21354 10746 21354 12399 21354 12399 21355 10746 21355 12195 21355 12399 21356 12195 21356 10747 21356 10747 21357 12195 21357 10749 21357 10747 21358 10749 21358 10748 21358 10748 21359 10749 21359 15716 21359 10748 21360 15716 21360 15492 21360 12363 21361 12364 21361 15873 21361 15873 21362 12364 21362 10750 21362 10750 21363 12364 21363 10751 21363 10751 21364 12364 21364 10752 21364 10751 21365 10752 21365 16022 21365 16022 21366 10752 21366 16020 21366 16020 21367 10752 21367 10753 21367 16020 21368 10753 21368 16018 21368 16018 21369 10753 21369 16023 21369 16023 21370 10753 21370 10754 21370 16023 21371 10754 21371 16014 21371 15784 21372 15785 21372 10758 21372 10758 21373 15785 21373 15779 21373 10758 21374 15779 21374 10754 21374 10754 21375 15779 21375 16011 21375 10754 21376 16011 21376 16014 21376 15794 21377 10755 21377 10756 21377 10756 21378 10755 21378 10757 21378 10756 21379 10757 21379 10758 21379 10758 21380 10757 21380 15790 21380 10758 21381 15790 21381 15784 21381 10759 21382 15995 21382 10760 21382 10760 21383 15995 21383 10756 21383 10756 21384 15995 21384 10761 21384 10756 21385 10761 21385 15794 21385 10762 21386 15773 21386 10760 21386 10760 21387 15773 21387 15766 21387 10760 21388 15766 21388 10759 21388 12370 21389 15987 21389 12368 21389 12368 21390 15987 21390 15991 21390 12368 21391 15991 21391 10762 21391 10762 21392 15991 21392 10763 21392 10762 21393 10763 21393 15773 21393 15798 21394 15799 21394 10764 21394 10764 21395 15799 21395 15800 21395 10764 21396 15800 21396 12370 21396 12370 21397 15800 21397 15986 21397 12370 21398 15986 21398 15987 21398 15798 21399 10764 21399 10765 21399 10765 21400 10764 21400 10767 21400 10765 21401 10767 21401 10768 21401 12372 21402 10771 21402 10766 21402 12372 21403 10766 21403 10767 21403 10767 21404 10766 21404 15983 21404 10767 21405 15983 21405 10768 21405 12373 21406 15803 21406 10769 21406 10769 21407 15836 21407 12373 21407 12373 21408 15836 21408 10770 21408 12373 21409 10770 21409 12372 21409 12372 21410 10770 21410 15833 21410 12372 21411 15833 21411 10771 21411 15803 21412 12373 21412 15804 21412 15804 21413 12373 21413 10772 21413 15804 21414 10772 21414 15805 21414 15805 21415 10772 21415 10773 21415 10773 21416 10772 21416 10774 21416 10773 21417 10774 21417 15761 21417 15761 21418 10774 21418 10775 21418 10775 21419 10774 21419 10776 21419 10775 21420 10776 21420 15856 21420 15856 21421 10776 21421 15976 21421 15976 21422 10776 21422 12376 21422 15976 21423 12376 21423 10777 21423 10777 21424 12376 21424 12378 21424 10777 21425 12378 21425 18481 21425 18453 21426 10778 21426 12377 21426 18453 21427 12377 21427 18099 21427 18099 21428 12377 21428 10779 21428 18099 21429 10779 21429 10780 21429 10780 21430 10779 21430 12375 21430 10780 21431 12375 21431 10781 21431 10781 21432 12375 21432 10782 21432 10781 21433 10782 21433 10783 21433 10783 21434 10782 21434 12374 21434 10783 21435 12374 21435 10784 21435 10784 21436 12374 21436 10785 21436 10784 21437 10785 21437 18103 21437 18103 21438 10785 21438 10786 21438 18103 21439 10786 21439 10787 21439 10787 21440 10786 21440 12371 21440 10787 21441 12371 21441 18105 21441 18105 21442 12371 21442 12369 21442 18105 21443 12369 21443 10788 21443 10788 21444 12369 21444 10790 21444 10788 21445 10790 21445 10789 21445 10789 21446 10790 21446 10791 21446 10789 21447 10791 21447 18109 21447 18109 21448 10791 21448 10792 21448 18109 21449 10792 21449 18110 21449 18110 21450 10792 21450 10793 21450 18110 21451 10793 21451 18112 21451 18112 21452 10793 21452 12367 21452 18112 21453 12367 21453 18114 21453 18114 21454 12367 21454 12366 21454 18114 21455 12366 21455 18117 21455 18117 21456 12366 21456 12365 21456 18117 21457 12365 21457 10794 21457 10794 21458 12365 21458 10795 21458 10794 21459 10795 21459 18118 21459 18118 21460 10795 21460 10796 21460 18118 21461 10796 21461 18120 21461 18120 21462 10796 21462 12362 21462 18120 21463 12362 21463 10797 21463 18440 21464 12379 21464 12381 21464 18440 21465 12381 21465 10798 21465 10798 21466 12381 21466 10799 21466 10798 21467 10799 21467 18038 21467 18038 21468 10799 21468 12382 21468 18038 21469 12382 21469 18039 21469 18039 21470 12382 21470 12383 21470 18039 21471 12383 21471 18040 21471 18040 21472 12383 21472 12384 21472 18040 21473 12384 21473 18041 21473 18041 21474 12384 21474 12385 21474 18041 21475 12385 21475 18043 21475 18043 21476 12385 21476 10800 21476 18043 21477 10800 21477 10801 21477 10801 21478 10800 21478 10802 21478 10801 21479 10802 21479 10803 21479 10803 21480 10802 21480 12387 21480 10803 21481 12387 21481 18048 21481 18048 21482 12387 21482 10804 21482 18048 21483 10804 21483 18049 21483 18049 21484 10804 21484 12389 21484 18049 21485 12389 21485 10805 21485 10805 21486 12389 21486 10806 21486 10805 21487 10806 21487 18050 21487 18050 21488 10806 21488 10807 21488 18050 21489 10807 21489 18052 21489 18052 21490 10807 21490 10808 21490 18052 21491 10808 21491 18054 21491 18054 21492 10808 21492 12391 21492 18054 21493 12391 21493 10809 21493 10809 21494 12391 21494 12395 21494 10809 21495 12395 21495 10810 21495 10810 21496 12395 21496 12396 21496 10810 21497 12396 21497 10811 21497 10811 21498 12396 21498 10812 21498 10811 21499 10812 21499 18056 21499 18056 21500 10812 21500 10813 21500 18056 21501 10813 21501 18058 21501 18416 21502 10814 21502 12397 21502 18416 21503 12397 21503 18008 21503 18008 21504 12397 21504 12394 21504 18008 21505 12394 21505 18009 21505 18009 21506 12394 21506 12393 21506 18009 21507 12393 21507 10815 21507 10815 21508 12393 21508 12392 21508 10815 21509 12392 21509 10816 21509 10816 21510 12392 21510 10817 21510 10816 21511 10817 21511 10818 21511 10818 21512 10817 21512 12390 21512 10818 21513 12390 21513 18012 21513 18012 21514 12390 21514 10819 21514 18012 21515 10819 21515 10820 21515 10820 21516 10819 21516 10821 21516 10820 21517 10821 21517 18015 21517 18015 21518 10821 21518 10822 21518 18015 21519 10822 21519 18016 21519 18016 21520 10822 21520 12388 21520 18016 21521 12388 21521 10823 21521 10823 21522 12388 21522 10824 21522 10823 21523 10824 21523 10826 21523 10826 21524 10824 21524 10825 21524 10826 21525 10825 21525 10827 21525 10827 21526 10825 21526 12386 21526 10827 21527 12386 21527 10828 21527 10828 21528 12386 21528 10829 21528 10828 21529 10829 21529 18020 21529 18020 21530 10829 21530 10830 21530 18020 21531 10830 21531 18021 21531 18021 21532 10830 21532 10831 21532 18021 21533 10831 21533 10832 21533 10832 21534 10831 21534 10833 21534 10832 21535 10833 21535 10834 21535 10834 21536 10833 21536 12380 21536 10834 21537 12380 21537 10835 21537 10835 21538 12380 21538 10836 21538 10835 21539 10836 21539 18395 21539 17958 21540 18394 21540 10837 21540 17958 21541 10837 21541 10838 21541 10838 21542 10837 21542 10839 21542 10838 21543 10839 21543 10840 21543 10840 21544 10839 21544 12345 21544 10840 21545 12345 21545 17959 21545 17959 21546 12345 21546 12347 21546 17959 21547 12347 21547 17961 21547 17961 21548 12347 21548 12348 21548 17961 21549 12348 21549 10841 21549 10841 21550 12348 21550 12351 21550 10841 21551 12351 21551 10842 21551 10842 21552 12351 21552 10843 21552 10842 21553 10843 21553 17963 21553 17963 21554 10843 21554 10845 21554 17963 21555 10845 21555 10844 21555 10844 21556 10845 21556 12354 21556 10844 21557 12354 21557 10846 21557 10846 21558 12354 21558 12355 21558 10846 21559 12355 21559 17965 21559 17965 21560 12355 21560 10848 21560 17965 21561 10848 21561 10847 21561 10847 21562 10848 21562 12357 21562 10847 21563 12357 21563 10849 21563 10849 21564 12357 21564 12359 21564 10849 21565 12359 21565 17967 21565 17967 21566 12359 21566 10850 21566 17967 21567 10850 21567 17968 21567 17968 21568 10850 21568 10851 21568 17968 21569 10851 21569 17969 21569 17969 21570 10851 21570 10852 21570 17969 21571 10852 21571 10853 21571 10853 21572 10852 21572 10854 21572 10853 21573 10854 21573 17971 21573 17971 21574 10854 21574 10855 21574 17971 21575 10855 21575 10856 21575 10856 21576 10855 21576 15587 21576 10856 21577 15587 21577 10857 21577 10858 21578 18371 21578 10859 21578 10858 21579 10859 21579 17919 21579 17919 21580 10859 21580 12361 21580 17919 21581 12361 21581 17920 21581 17920 21582 12361 21582 10861 21582 17920 21583 10861 21583 10860 21583 10860 21584 10861 21584 10862 21584 10860 21585 10862 21585 17922 21585 17922 21586 10862 21586 12360 21586 17922 21587 12360 21587 17924 21587 17924 21588 12360 21588 12358 21588 17924 21589 12358 21589 10863 21589 10863 21590 12358 21590 10865 21590 10863 21591 10865 21591 10864 21591 10864 21592 10865 21592 12356 21592 10864 21593 12356 21593 17926 21593 17926 21594 12356 21594 10866 21594 17926 21595 10866 21595 17927 21595 17927 21596 10866 21596 12353 21596 17927 21597 12353 21597 10867 21597 10867 21598 12353 21598 10868 21598 10867 21599 10868 21599 10869 21599 10869 21600 10868 21600 12352 21600 10869 21601 12352 21601 17929 21601 17929 21602 12352 21602 12350 21602 17929 21603 12350 21603 10870 21603 10870 21604 12350 21604 12349 21604 10870 21605 12349 21605 10871 21605 10871 21606 12349 21606 12346 21606 10871 21607 12346 21607 10872 21607 10872 21608 12346 21608 10873 21608 10872 21609 10873 21609 17933 21609 17933 21610 10873 21610 12344 21610 17933 21611 12344 21611 10874 21611 10874 21612 12344 21612 10875 21612 10874 21613 10875 21613 17935 21613 17935 21614 10875 21614 10876 21614 17935 21615 10876 21615 17936 21615 17868 21616 18351 21616 12318 21616 17868 21617 12318 21617 10877 21617 10877 21618 12318 21618 12319 21618 10877 21619 12319 21619 10878 21619 10878 21620 12319 21620 12321 21620 10878 21621 12321 21621 10879 21621 10879 21622 12321 21622 12323 21622 10879 21623 12323 21623 10880 21623 10880 21624 12323 21624 12324 21624 10880 21625 12324 21625 17869 21625 17869 21626 12324 21626 12326 21626 17869 21627 12326 21627 17870 21627 17870 21628 12326 21628 10881 21628 17870 21629 10881 21629 10882 21629 10882 21630 10881 21630 12328 21630 10882 21631 12328 21631 17871 21631 17871 21632 12328 21632 10883 21632 17871 21633 10883 21633 10884 21633 10884 21634 10883 21634 12330 21634 10884 21635 12330 21635 10885 21635 10885 21636 12330 21636 12332 21636 10885 21637 12332 21637 17873 21637 17873 21638 12332 21638 12334 21638 17873 21639 12334 21639 10886 21639 10886 21640 12334 21640 12336 21640 10886 21641 12336 21641 17875 21641 17875 21642 12336 21642 12337 21642 17875 21643 12337 21643 17876 21643 17876 21644 12337 21644 12339 21644 17876 21645 12339 21645 10887 21645 10887 21646 12339 21646 12341 21646 10887 21647 12341 21647 17879 21647 17879 21648 12341 21648 12342 21648 17879 21649 12342 21649 10888 21649 10888 21650 12342 21650 12343 21650 10888 21651 12343 21651 10889 21651 10889 21652 12343 21652 15605 21652 10889 21653 15605 21653 17883 21653 17828 21654 10890 21654 10891 21654 17828 21655 10891 21655 17830 21655 17830 21656 10891 21656 10892 21656 17830 21657 10892 21657 17831 21657 17831 21658 10892 21658 12340 21658 17831 21659 12340 21659 17832 21659 17832 21660 12340 21660 10893 21660 17832 21661 10893 21661 17834 21661 17834 21662 10893 21662 12338 21662 17834 21663 12338 21663 17836 21663 17836 21664 12338 21664 12335 21664 17836 21665 12335 21665 10894 21665 10894 21666 12335 21666 12333 21666 10894 21667 12333 21667 10895 21667 10895 21668 12333 21668 10896 21668 10895 21669 10896 21669 17837 21669 17837 21670 10896 21670 12331 21670 17837 21671 12331 21671 10897 21671 10897 21672 12331 21672 12329 21672 10897 21673 12329 21673 17838 21673 17838 21674 12329 21674 12327 21674 17838 21675 12327 21675 17839 21675 17839 21676 12327 21676 10898 21676 17839 21677 10898 21677 10899 21677 10899 21678 10898 21678 12325 21678 10899 21679 12325 21679 10900 21679 10900 21680 12325 21680 10901 21680 10900 21681 10901 21681 17841 21681 17841 21682 10901 21682 12322 21682 17841 21683 12322 21683 10902 21683 10902 21684 12322 21684 10903 21684 10902 21685 10903 21685 17842 21685 17842 21686 10903 21686 12320 21686 17842 21687 12320 21687 17843 21687 17843 21688 12320 21688 10904 21688 17843 21689 10904 21689 10905 21689 10905 21690 10904 21690 15625 21690 10905 21691 15625 21691 17845 21691 18320 21692 18319 21692 10907 21692 18320 21693 10907 21693 10906 21693 10906 21694 10907 21694 10908 21694 10906 21695 10908 21695 17778 21695 17778 21696 10908 21696 12300 21696 17778 21697 12300 21697 17779 21697 17779 21698 12300 21698 12301 21698 17779 21699 12301 21699 17780 21699 17780 21700 12301 21700 10909 21700 17780 21701 10909 21701 10910 21701 10910 21702 10909 21702 12303 21702 10910 21703 12303 21703 10911 21703 10911 21704 12303 21704 12304 21704 10911 21705 12304 21705 10913 21705 10913 21706 12304 21706 10912 21706 10913 21707 10912 21707 17782 21707 17782 21708 10912 21708 10914 21708 17782 21709 10914 21709 10915 21709 10915 21710 10914 21710 12306 21710 10915 21711 12306 21711 10916 21711 10916 21712 12306 21712 12309 21712 10916 21713 12309 21713 10917 21713 10917 21714 12309 21714 12310 21714 10917 21715 12310 21715 17786 21715 17786 21716 12310 21716 12313 21716 17786 21717 12313 21717 17787 21717 17787 21718 12313 21718 12314 21718 17787 21719 12314 21719 17788 21719 17788 21720 12314 21720 10919 21720 17788 21721 10919 21721 10918 21721 10918 21722 10919 21722 10920 21722 10918 21723 10920 21723 17790 21723 17790 21724 10920 21724 12317 21724 17790 21725 12317 21725 17793 21725 17793 21726 12317 21726 10922 21726 17793 21727 10922 21727 10921 21727 10921 21728 10922 21728 18295 21728 10921 21729 18295 21729 17794 21729 17741 21730 10923 21730 10924 21730 17741 21731 10924 21731 10925 21731 10925 21732 10924 21732 10926 21732 10925 21733 10926 21733 10927 21733 10927 21734 10926 21734 10928 21734 10927 21735 10928 21735 10929 21735 10929 21736 10928 21736 12316 21736 10929 21737 12316 21737 10930 21737 10930 21738 12316 21738 12315 21738 10930 21739 12315 21739 10931 21739 10931 21740 12315 21740 12312 21740 10931 21741 12312 21741 17746 21741 17746 21742 12312 21742 12311 21742 17746 21743 12311 21743 10932 21743 10932 21744 12311 21744 12308 21744 10932 21745 12308 21745 10933 21745 10933 21746 12308 21746 12307 21746 10933 21747 12307 21747 10934 21747 10934 21748 12307 21748 10935 21748 10934 21749 10935 21749 10936 21749 10936 21750 10935 21750 12305 21750 10936 21751 12305 21751 10937 21751 10937 21752 12305 21752 12302 21752 10937 21753 12302 21753 17750 21753 17750 21754 12302 21754 10938 21754 17750 21755 10938 21755 10939 21755 10939 21756 10938 21756 10940 21756 10939 21757 10940 21757 17752 21757 17752 21758 10940 21758 10941 21758 17752 21759 10941 21759 10942 21759 10942 21760 10941 21760 12299 21760 10942 21761 12299 21761 17754 21761 17754 21762 12299 21762 12298 21762 17754 21763 12298 21763 10943 21763 10943 21764 12298 21764 12297 21764 10943 21765 12297 21765 10944 21765 10944 21766 12297 21766 12296 21766 10944 21767 12296 21767 17758 21767 17681 21768 12271 21768 12272 21768 17681 21769 12272 21769 10945 21769 10945 21770 12272 21770 12274 21770 10945 21771 12274 21771 17682 21771 17682 21772 12274 21772 12275 21772 17682 21773 12275 21773 17685 21773 17685 21774 12275 21774 12277 21774 17685 21775 12277 21775 17686 21775 17686 21776 12277 21776 10946 21776 17686 21777 10946 21777 17687 21777 17687 21778 10946 21778 12279 21778 17687 21779 12279 21779 17690 21779 17690 21780 12279 21780 12281 21780 17690 21781 12281 21781 17691 21781 17691 21782 12281 21782 12282 21782 17691 21783 12282 21783 17692 21783 17692 21784 12282 21784 12284 21784 17692 21785 12284 21785 10947 21785 10947 21786 12284 21786 12285 21786 10947 21787 12285 21787 10948 21787 10948 21788 12285 21788 12288 21788 10948 21789 12288 21789 17695 21789 17695 21790 12288 21790 12289 21790 17695 21791 12289 21791 17697 21791 17697 21792 12289 21792 10949 21792 17697 21793 10949 21793 10950 21793 10950 21794 10949 21794 10951 21794 10950 21795 10951 21795 10952 21795 10952 21796 10951 21796 12292 21796 10952 21797 12292 21797 17698 21797 17698 21798 12292 21798 10953 21798 17698 21799 10953 21799 10954 21799 10954 21800 10953 21800 12293 21800 10954 21801 12293 21801 17699 21801 17699 21802 12293 21802 10955 21802 17699 21803 10955 21803 17700 21803 17700 21804 10955 21804 15643 21804 17700 21805 15643 21805 10956 21805 17650 21806 12295 21806 12294 21806 17650 21807 12294 21807 17651 21807 17651 21808 12294 21808 10957 21808 17651 21809 10957 21809 17652 21809 17652 21810 10957 21810 10958 21810 17652 21811 10958 21811 17654 21811 17654 21812 10958 21812 12291 21812 17654 21813 12291 21813 10959 21813 10959 21814 12291 21814 12290 21814 10959 21815 12290 21815 10960 21815 10960 21816 12290 21816 10961 21816 10960 21817 10961 21817 10963 21817 10963 21818 10961 21818 10962 21818 10963 21819 10962 21819 10964 21819 10964 21820 10962 21820 12287 21820 10964 21821 12287 21821 10965 21821 10965 21822 12287 21822 12286 21822 10965 21823 12286 21823 10966 21823 10966 21824 12286 21824 12283 21824 10966 21825 12283 21825 17657 21825 17657 21826 12283 21826 10967 21826 17657 21827 10967 21827 10968 21827 10968 21828 10967 21828 12280 21828 10968 21829 12280 21829 10969 21829 10969 21830 12280 21830 12278 21830 10969 21831 12278 21831 10970 21831 10970 21832 12278 21832 12276 21832 10970 21833 12276 21833 10971 21833 10971 21834 12276 21834 10973 21834 10971 21835 10973 21835 10972 21835 10972 21836 10973 21836 10974 21836 10972 21837 10974 21837 17658 21837 17658 21838 10974 21838 12273 21838 17658 21839 12273 21839 17659 21839 17659 21840 12273 21840 10975 21840 17659 21841 10975 21841 17660 21841 17660 21842 10975 21842 10976 21842 17660 21843 10976 21843 17661 21843 18237 21844 12246 21844 10977 21844 18237 21845 10977 21845 10978 21845 10978 21846 10977 21846 12247 21846 10978 21847 12247 21847 17590 21847 17590 21848 12247 21848 12248 21848 17590 21849 12248 21849 17591 21849 17591 21850 12248 21850 12252 21850 17591 21851 12252 21851 17593 21851 17593 21852 12252 21852 12253 21852 17593 21853 12253 21853 10979 21853 10979 21854 12253 21854 12255 21854 10979 21855 12255 21855 10980 21855 10980 21856 12255 21856 12256 21856 10980 21857 12256 21857 17595 21857 17595 21858 12256 21858 12257 21858 17595 21859 12257 21859 10981 21859 10981 21860 12257 21860 12260 21860 10981 21861 12260 21861 17597 21861 17597 21862 12260 21862 10982 21862 17597 21863 10982 21863 17598 21863 17598 21864 10982 21864 12262 21864 17598 21865 12262 21865 10983 21865 10983 21866 12262 21866 10984 21866 10983 21867 10984 21867 17601 21867 17601 21868 10984 21868 12265 21868 17601 21869 12265 21869 17602 21869 17602 21870 12265 21870 10985 21870 17602 21871 10985 21871 17603 21871 17603 21872 10985 21872 10986 21872 17603 21873 10986 21873 17605 21873 17605 21874 10986 21874 10987 21874 17605 21875 10987 21875 17606 21875 17606 21876 10987 21876 12268 21876 17606 21877 12268 21877 10988 21877 10988 21878 12268 21878 12270 21878 10988 21879 12270 21879 17607 21879 17607 21880 12270 21880 10989 21880 17607 21881 10989 21881 18219 21881 10990 21882 10991 21882 12269 21882 10990 21883 12269 21883 10992 21883 10992 21884 12269 21884 10994 21884 10992 21885 10994 21885 10993 21885 10993 21886 10994 21886 12267 21886 10993 21887 12267 21887 10995 21887 10995 21888 12267 21888 12266 21888 10995 21889 12266 21889 10996 21889 10996 21890 12266 21890 10997 21890 10996 21891 10997 21891 17555 21891 17555 21892 10997 21892 10998 21892 17555 21893 10998 21893 10999 21893 10999 21894 10998 21894 12264 21894 10999 21895 12264 21895 17557 21895 17557 21896 12264 21896 12263 21896 17557 21897 12263 21897 11000 21897 11000 21898 12263 21898 12261 21898 11000 21899 12261 21899 17558 21899 17558 21900 12261 21900 12259 21900 17558 21901 12259 21901 17560 21901 17560 21902 12259 21902 12258 21902 17560 21903 12258 21903 11001 21903 11001 21904 12258 21904 11003 21904 11001 21905 11003 21905 11002 21905 11002 21906 11003 21906 12254 21906 11002 21907 12254 21907 17562 21907 17562 21908 12254 21908 12251 21908 17562 21909 12251 21909 17563 21909 17563 21910 12251 21910 12250 21910 17563 21911 12250 21911 11004 21911 11004 21912 12250 21912 12249 21912 11004 21913 12249 21913 17567 21913 17567 21914 12249 21914 11006 21914 17567 21915 11006 21915 11005 21915 11005 21916 11006 21916 11007 21916 11005 21917 11007 21917 11009 21917 11009 21918 11007 21918 11008 21918 11009 21919 11008 21919 17569 21919 17487 21920 18196 21920 11010 21920 17487 21921 11010 21921 11011 21921 11011 21922 11010 21922 12229 21922 11011 21923 12229 21923 11012 21923 11012 21924 12229 21924 11013 21924 11012 21925 11013 21925 17489 21925 17489 21926 11013 21926 12232 21926 17489 21927 12232 21927 17492 21927 17492 21928 12232 21928 12233 21928 17492 21929 12233 21929 11014 21929 11014 21930 12233 21930 12234 21930 11014 21931 12234 21931 11015 21931 11015 21932 12234 21932 11016 21932 11015 21933 11016 21933 11018 21933 11018 21934 11016 21934 11017 21934 11018 21935 11017 21935 11019 21935 11019 21936 11017 21936 12236 21936 11019 21937 12236 21937 17495 21937 17495 21938 12236 21938 11021 21938 17495 21939 11021 21939 11020 21939 11020 21940 11021 21940 12239 21940 11020 21941 12239 21941 17497 21941 17497 21942 12239 21942 11022 21942 17497 21943 11022 21943 17499 21943 17499 21944 11022 21944 11023 21944 17499 21945 11023 21945 11024 21945 11024 21946 11023 21946 12242 21946 11024 21947 12242 21947 11025 21947 11025 21948 12242 21948 11026 21948 11025 21949 11026 21949 17504 21949 17504 21950 11026 21950 11027 21950 17504 21951 11027 21951 17506 21951 17506 21952 11027 21952 12243 21952 17506 21953 12243 21953 17507 21953 17507 21954 12243 21954 12245 21954 17507 21955 12245 21955 17509 21955 17509 21956 12245 21956 15672 21956 17509 21957 15672 21957 17511 21957 17445 21958 15670 21958 12244 21958 17445 21959 12244 21959 17446 21959 17446 21960 12244 21960 11028 21960 17446 21961 11028 21961 11029 21961 11029 21962 11028 21962 11030 21962 11029 21963 11030 21963 17449 21963 17449 21964 11030 21964 12241 21964 17449 21965 12241 21965 11031 21965 11031 21966 12241 21966 11032 21966 11031 21967 11032 21967 17452 21967 17452 21968 11032 21968 11033 21968 17452 21969 11033 21969 11034 21969 11034 21970 11033 21970 12240 21970 11034 21971 12240 21971 11035 21971 11035 21972 12240 21972 12238 21972 11035 21973 12238 21973 17454 21973 17454 21974 12238 21974 12237 21974 17454 21975 12237 21975 17456 21975 17456 21976 12237 21976 12235 21976 17456 21977 12235 21977 11036 21977 11036 21978 12235 21978 11037 21978 11036 21979 11037 21979 17459 21979 17459 21980 11037 21980 11039 21980 17459 21981 11039 21981 11038 21981 11038 21982 11039 21982 11040 21982 11038 21983 11040 21983 11041 21983 11041 21984 11040 21984 11042 21984 11041 21985 11042 21985 17461 21985 17461 21986 11042 21986 12231 21986 17461 21987 12231 21987 11043 21987 11043 21988 12231 21988 12230 21988 11043 21989 12230 21989 11044 21989 11044 21990 12230 21990 11045 21990 11044 21991 11045 21991 11046 21991 11046 21992 11045 21992 12228 21992 11046 21993 12228 21993 17466 21993 17466 21994 12228 21994 11047 21994 17466 21995 11047 21995 11048 21995 17391 21996 18158 21996 11049 21996 17391 21997 11049 21997 11050 21997 11050 21998 11049 21998 11051 21998 11050 21999 11051 21999 11052 21999 11052 22000 11051 22000 12209 22000 11052 22001 12209 22001 11053 22001 11053 22002 12209 22002 11054 22002 11053 22003 11054 22003 17395 22003 17395 22004 11054 22004 11056 22004 17395 22005 11056 22005 11055 22005 11055 22006 11056 22006 11058 22006 11055 22007 11058 22007 11057 22007 11057 22008 11058 22008 11059 22008 11057 22009 11059 22009 17398 22009 17398 22010 11059 22010 12212 22010 17398 22011 12212 22011 17399 22011 17399 22012 12212 22012 12214 22012 17399 22013 12214 22013 17400 22013 17400 22014 12214 22014 12215 22014 17400 22015 12215 22015 17402 22015 17402 22016 12215 22016 11060 22016 17402 22017 11060 22017 17403 22017 17403 22018 11060 22018 12218 22018 17403 22019 12218 22019 11061 22019 11061 22020 12218 22020 11062 22020 11061 22021 11062 22021 17406 22021 17406 22022 11062 22022 12220 22022 17406 22023 12220 22023 11063 22023 11063 22024 12220 22024 12222 22024 11063 22025 12222 22025 11064 22025 11064 22026 12222 22026 12224 22026 11064 22027 12224 22027 17409 22027 17409 22028 12224 22028 12225 22028 17409 22029 12225 22029 17411 22029 17411 22030 12225 22030 11065 22030 17411 22031 11065 22031 17412 22031 17412 22032 11065 22032 11066 22032 17412 22033 11066 22033 18135 22033 11067 22034 18094 22034 18037 22034 11067 22035 18037 22035 11068 22035 11068 22036 18037 22036 11069 22036 11068 22037 11069 22037 18119 22037 18119 22038 11069 22038 11070 22038 18119 22039 11070 22039 18116 22039 18116 22040 11070 22040 11071 22040 18116 22041 11071 22041 18115 22041 18115 22042 11071 22042 11072 22042 18115 22043 11072 22043 18113 22043 18113 22044 11072 22044 18042 22044 18113 22045 18042 22045 18111 22045 18111 22046 18042 22046 18044 22046 18111 22047 18044 22047 18108 22047 18108 22048 18044 22048 18045 22048 18108 22049 18045 22049 18107 22049 18107 22050 18045 22050 18046 22050 18107 22051 18046 22051 11073 22051 11073 22052 18046 22052 18047 22052 11073 22053 18047 22053 18106 22053 18106 22054 18047 22054 11074 22054 18106 22055 11074 22055 11075 22055 11075 22056 11074 22056 11076 22056 11075 22057 11076 22057 18104 22057 18104 22058 11076 22058 18051 22058 18104 22059 18051 22059 18102 22059 18102 22060 18051 22060 18053 22060 18102 22061 18053 22061 18101 22061 18101 22062 18053 22062 11077 22062 18101 22063 11077 22063 18100 22063 18100 22064 11077 22064 18055 22064 18100 22065 18055 22065 11078 22065 11078 22066 18055 22066 11079 22066 11078 22067 11079 22067 11080 22067 11080 22068 11079 22068 11081 22068 11080 22069 11081 22069 11082 22069 11082 22070 11081 22070 11083 22070 11082 22071 11083 22071 18071 22071 11084 22072 17997 22072 11085 22072 11084 22073 11085 22073 11087 22073 11087 22074 11085 22074 11086 22074 11087 22075 11086 22075 11089 22075 11089 22076 11086 22076 11088 22076 11089 22077 11088 22077 18022 22077 18022 22078 11088 22078 11090 22078 18022 22079 11090 22079 11091 22079 11091 22080 11090 22080 17960 22080 11091 22081 17960 22081 18019 22081 18019 22082 17960 22082 17962 22082 18019 22083 17962 22083 11092 22083 11092 22084 17962 22084 11093 22084 11092 22085 11093 22085 18018 22085 18018 22086 11093 22086 17964 22086 18018 22087 17964 22087 18017 22087 18017 22088 17964 22088 11094 22088 18017 22089 11094 22089 11095 22089 11095 22090 11094 22090 17966 22090 11095 22091 17966 22091 18014 22091 18014 22092 17966 22092 11096 22092 18014 22093 11096 22093 18013 22093 18013 22094 11096 22094 11097 22094 18013 22095 11097 22095 18011 22095 18011 22096 11097 22096 11099 22096 18011 22097 11099 22097 11098 22097 11098 22098 11099 22098 11100 22098 11098 22099 11100 22099 18010 22099 18010 22100 11100 22100 11101 22100 18010 22101 11101 22101 11103 22101 11103 22102 11101 22102 11102 22102 11103 22103 11102 22103 11104 22103 11104 22104 11102 22104 11105 22104 11104 22105 11105 22105 18007 22105 18007 22106 11105 22106 17970 22106 18007 22107 17970 22107 18006 22107 18006 22108 17970 22108 11106 22108 18006 22109 11106 22109 18005 22109 11107 22110 17913 22110 11108 22110 11107 22111 11108 22111 17934 22111 17934 22112 11108 22112 11109 22112 17934 22113 11109 22113 11110 22113 11110 22114 11109 22114 11111 22114 11110 22115 11111 22115 11112 22115 11112 22116 11111 22116 11113 22116 11112 22117 11113 22117 17932 22117 17932 22118 11113 22118 11114 22118 17932 22119 11114 22119 17931 22119 17931 22120 11114 22120 11115 22120 17931 22121 11115 22121 17930 22121 17930 22122 11115 22122 11116 22122 17930 22123 11116 22123 17928 22123 17928 22124 11116 22124 11117 22124 17928 22125 11117 22125 11118 22125 11118 22126 11117 22126 11119 22126 11118 22127 11119 22127 11120 22127 11120 22128 11119 22128 17872 22128 11120 22129 17872 22129 17925 22129 17925 22130 17872 22130 11121 22130 17925 22131 11121 22131 11122 22131 11122 22132 11121 22132 17874 22132 11122 22133 17874 22133 11123 22133 11123 22134 17874 22134 11124 22134 11123 22135 11124 22135 11125 22135 11125 22136 11124 22136 11126 22136 11125 22137 11126 22137 17923 22137 17923 22138 11126 22138 17877 22138 17923 22139 17877 22139 11127 22139 11127 22140 17877 22140 17878 22140 11127 22141 17878 22141 17921 22141 17921 22142 17878 22142 17880 22142 17921 22143 17880 22143 11128 22143 11128 22144 17880 22144 17881 22144 11128 22145 17881 22145 17918 22145 17918 22146 17881 22146 17882 22146 17918 22147 17882 22147 17917 22147 17821 22148 17776 22148 11129 22148 17821 22149 11129 22149 17844 22149 17844 22150 11129 22150 17777 22150 17844 22151 17777 22151 11131 22151 11131 22152 17777 22152 11130 22152 11131 22153 11130 22153 11133 22153 11133 22154 11130 22154 11132 22154 11133 22155 11132 22155 11134 22155 11134 22156 11132 22156 11135 22156 11134 22157 11135 22157 11136 22157 11136 22158 11135 22158 11137 22158 11136 22159 11137 22159 17840 22159 17840 22160 11137 22160 17781 22160 17840 22161 17781 22161 11138 22161 11138 22162 17781 22162 11139 22162 11138 22163 11139 22163 11140 22163 11140 22164 11139 22164 17783 22164 11140 22165 17783 22165 11141 22165 11141 22166 17783 22166 11142 22166 11141 22167 11142 22167 11143 22167 11143 22168 11142 22168 17784 22168 11143 22169 17784 22169 11144 22169 11144 22170 17784 22170 17785 22170 11144 22171 17785 22171 11145 22171 11145 22172 17785 22172 11146 22172 11145 22173 11146 22173 11148 22173 11148 22174 11146 22174 11147 22174 11148 22175 11147 22175 17835 22175 17835 22176 11147 22176 11149 22176 17835 22177 11149 22177 17833 22177 17833 22178 11149 22178 17789 22178 17833 22179 17789 22179 11150 22179 11150 22180 17789 22180 17791 22180 11150 22181 17791 22181 11151 22181 11151 22182 17791 22182 17792 22182 11151 22183 17792 22183 17829 22183 17829 22184 17792 22184 17803 22184 17829 22185 17803 22185 17827 22185 17757 22186 17680 22186 11152 22186 17757 22187 11152 22187 17756 22187 17756 22188 11152 22188 17683 22188 17756 22189 17683 22189 17755 22189 17755 22190 17683 22190 17684 22190 17755 22191 17684 22191 11153 22191 11153 22192 17684 22192 11154 22192 11153 22193 11154 22193 17753 22193 17753 22194 11154 22194 11156 22194 17753 22195 11156 22195 11155 22195 11155 22196 11156 22196 17688 22196 11155 22197 17688 22197 17751 22197 17751 22198 17688 22198 17689 22198 17751 22199 17689 22199 17749 22199 17749 22200 17689 22200 11158 22200 17749 22201 11158 22201 11157 22201 11157 22202 11158 22202 17693 22202 11157 22203 17693 22203 17748 22203 17748 22204 17693 22204 11159 22204 17748 22205 11159 22205 11160 22205 11160 22206 11159 22206 11161 22206 11160 22207 11161 22207 11162 22207 11162 22208 11161 22208 17694 22208 11162 22209 17694 22209 17747 22209 17747 22210 17694 22210 17696 22210 17747 22211 17696 22211 17745 22211 17745 22212 17696 22212 11163 22212 17745 22213 11163 22213 17744 22213 17744 22214 11163 22214 11164 22214 17744 22215 11164 22215 17743 22215 17743 22216 11164 22216 11165 22216 17743 22217 11165 22217 11166 22217 11166 22218 11165 22218 11167 22218 11166 22219 11167 22219 11169 22219 11169 22220 11167 22220 11168 22220 11169 22221 11168 22221 17742 22221 17742 22222 11168 22222 17701 22222 17742 22223 17701 22223 11170 22223 17643 22224 11171 22224 11173 22224 17643 22225 11173 22225 11172 22225 11172 22226 11173 22226 11174 22226 11172 22227 11174 22227 11175 22227 11175 22228 11174 22228 11176 22228 11175 22229 11176 22229 11177 22229 11177 22230 11176 22230 17592 22230 11177 22231 17592 22231 11179 22231 11179 22232 17592 22232 11178 22232 11179 22233 11178 22233 11180 22233 11180 22234 11178 22234 17594 22234 11180 22235 17594 22235 11181 22235 11181 22236 17594 22236 11182 22236 11181 22237 11182 22237 11183 22237 11183 22238 11182 22238 11185 22238 11183 22239 11185 22239 11184 22239 11184 22240 11185 22240 17596 22240 11184 22241 17596 22241 11186 22241 11186 22242 17596 22242 11187 22242 11186 22243 11187 22243 17656 22243 17656 22244 11187 22244 17599 22244 17656 22245 17599 22245 11188 22245 11188 22246 17599 22246 17600 22246 11188 22247 17600 22247 11190 22247 11190 22248 17600 22248 11189 22248 11190 22249 11189 22249 17655 22249 17655 22250 11189 22250 11191 22250 17655 22251 11191 22251 11192 22251 11192 22252 11191 22252 17604 22252 11192 22253 17604 22253 11193 22253 11193 22254 17604 22254 11194 22254 11193 22255 11194 22255 11195 22255 11195 22256 11194 22256 11196 22256 11195 22257 11196 22257 17653 22257 17653 22258 11196 22258 11198 22258 17653 22259 11198 22259 11197 22259 11197 22260 11198 22260 17624 22260 11197 22261 17624 22261 17649 22261 11199 22262 17545 22262 11200 22262 11199 22263 11200 22263 17568 22263 17568 22264 11200 22264 11201 22264 17568 22265 11201 22265 17566 22265 17566 22266 11201 22266 17488 22266 17566 22267 17488 22267 17565 22267 17565 22268 17488 22268 17490 22268 17565 22269 17490 22269 11202 22269 11202 22270 17490 22270 17491 22270 11202 22271 17491 22271 17564 22271 17564 22272 17491 22272 11203 22272 17564 22273 11203 22273 17561 22273 17561 22274 11203 22274 17493 22274 17561 22275 17493 22275 11204 22275 11204 22276 17493 22276 11205 22276 11204 22277 11205 22277 17559 22277 17559 22278 11205 22278 17494 22278 17559 22279 17494 22279 11206 22279 11206 22280 17494 22280 17496 22280 11206 22281 17496 22281 11207 22281 11207 22282 17496 22282 11208 22282 11207 22283 11208 22283 11209 22283 11209 22284 11208 22284 17498 22284 11209 22285 17498 22285 17556 22285 17556 22286 17498 22286 17500 22286 17556 22287 17500 22287 11210 22287 11210 22288 17500 22288 17501 22288 11210 22289 17501 22289 17554 22289 17554 22290 17501 22290 17502 22290 17554 22291 17502 22291 17553 22291 17553 22292 17502 22292 17503 22292 17553 22293 17503 22293 11211 22293 11211 22294 17503 22294 17505 22294 11211 22295 17505 22295 17552 22295 17552 22296 17505 22296 17508 22296 17552 22297 17508 22297 17551 22297 17551 22298 17508 22298 17510 22298 17551 22299 17510 22299 17528 22299 17465 22300 17390 22300 17392 22300 17465 22301 17392 22301 17464 22301 17464 22302 17392 22302 17393 22302 17464 22303 17393 22303 17463 22303 17463 22304 17393 22304 17394 22304 17463 22305 17394 22305 11212 22305 11212 22306 17394 22306 11213 22306 11212 22307 11213 22307 17462 22307 17462 22308 11213 22308 17396 22308 17462 22309 17396 22309 11214 22309 11214 22310 17396 22310 17397 22310 11214 22311 17397 22311 17460 22311 17460 22312 17397 22312 11215 22312 17460 22313 11215 22313 17458 22313 17458 22314 11215 22314 11216 22314 17458 22315 11216 22315 17457 22315 17457 22316 11216 22316 11217 22316 17457 22317 11217 22317 11218 22317 11218 22318 11217 22318 17401 22318 11218 22319 17401 22319 17455 22319 17455 22320 17401 22320 11219 22320 17455 22321 11219 22321 11220 22321 11220 22322 11219 22322 17404 22322 11220 22323 17404 22323 17453 22323 17453 22324 17404 22324 17405 22324 17453 22325 17405 22325 11221 22325 11221 22326 17405 22326 17407 22326 11221 22327 17407 22327 17451 22327 17451 22328 17407 22328 11222 22328 17451 22329 11222 22329 17450 22329 17450 22330 11222 22330 17408 22330 17450 22331 17408 22331 17448 22331 17448 22332 17408 22332 17410 22332 17448 22333 17410 22333 17447 22333 17447 22334 17410 22334 11223 22334 17447 22335 11223 22335 11224 22335 11224 22336 11223 22336 17413 22336 11224 22337 17413 22337 17444 22337 17315 22338 12227 22338 11225 22338 17315 22339 11225 22339 11226 22339 11226 22340 11225 22340 12226 22340 11226 22341 12226 22341 17317 22341 17317 22342 12226 22342 12223 22342 17317 22343 12223 22343 11227 22343 11227 22344 12223 22344 12221 22344 11227 22345 12221 22345 11228 22345 11228 22346 12221 22346 11229 22346 11228 22347 11229 22347 17318 22347 17318 22348 11229 22348 12219 22348 17318 22349 12219 22349 11230 22349 11230 22350 12219 22350 12217 22350 11230 22351 12217 22351 11231 22351 11231 22352 12217 22352 12216 22352 11231 22353 12216 22353 11232 22353 11232 22354 12216 22354 11233 22354 11232 22355 11233 22355 17322 22355 17322 22356 11233 22356 11235 22356 17322 22357 11235 22357 11234 22357 11234 22358 11235 22358 12213 22358 11234 22359 12213 22359 11237 22359 11237 22360 12213 22360 11236 22360 11237 22361 11236 22361 11238 22361 11238 22362 11236 22362 11239 22362 11238 22363 11239 22363 17324 22363 17324 22364 11239 22364 12211 22364 17324 22365 12211 22365 17325 22365 17325 22366 12211 22366 12210 22366 17325 22367 12210 22367 11240 22367 11240 22368 12210 22368 11241 22368 11240 22369 11241 22369 17326 22369 17326 22370 11241 22370 12208 22370 17326 22371 12208 22371 11242 22371 11242 22372 12208 22372 12207 22372 11242 22373 12207 22373 17329 22373 17329 22374 12207 22374 17364 22374 17329 22375 17364 22375 17365 22375 17277 22376 15717 22376 11243 22376 17277 22377 11243 22377 11244 22377 11244 22378 11243 22378 12194 22378 11244 22379 12194 22379 17279 22379 17279 22380 12194 22380 11245 22380 17279 22381 11245 22381 11246 22381 11246 22382 11245 22382 11247 22382 11246 22383 11247 22383 11248 22383 11248 22384 11247 22384 11249 22384 11248 22385 11249 22385 17282 22385 17282 22386 11249 22386 11250 22386 17282 22387 11250 22387 11251 22387 11251 22388 11250 22388 12196 22388 11251 22389 12196 22389 17284 22389 17284 22390 12196 22390 12197 22390 17284 22391 12197 22391 11252 22391 11252 22392 12197 22392 12198 22392 11252 22393 12198 22393 11253 22393 11253 22394 12198 22394 12199 22394 11253 22395 12199 22395 11254 22395 11254 22396 12199 22396 12200 22396 11254 22397 12200 22397 11256 22397 11256 22398 12200 22398 11255 22398 11256 22399 11255 22399 11257 22399 11257 22400 11255 22400 12202 22400 11257 22401 12202 22401 17254 22401 17254 22402 12202 22402 11258 22402 17254 22403 11258 22403 17255 22403 17255 22404 11258 22404 12204 22404 17255 22405 12204 22405 11259 22405 11259 22406 12204 22406 12205 22406 11259 22407 12205 22407 11260 22407 11260 22408 12205 22408 11261 22408 11260 22409 11261 22409 17258 22409 17258 22410 11261 22410 11262 22410 17258 22411 11262 22411 17259 22411 17259 22412 11262 22412 11263 22412 17259 22413 11263 22413 17261 22413 17330 22414 17275 22414 11264 22414 17330 22415 11264 22415 11265 22415 11265 22416 11264 22416 17278 22416 11265 22417 17278 22417 17328 22417 17328 22418 17278 22418 11266 22418 17328 22419 11266 22419 17327 22419 17327 22420 11266 22420 17280 22420 17327 22421 17280 22421 11267 22421 11267 22422 17280 22422 17281 22422 11267 22423 17281 22423 11268 22423 11268 22424 17281 22424 11270 22424 11268 22425 11270 22425 11269 22425 11269 22426 11270 22426 17283 22426 11269 22427 17283 22427 11271 22427 11271 22428 17283 22428 17285 22428 11271 22429 17285 22429 17323 22429 17323 22430 17285 22430 11272 22430 17323 22431 11272 22431 17321 22431 17321 22432 11272 22432 17286 22432 17321 22433 17286 22433 11274 22433 11274 22434 17286 22434 11273 22434 11274 22435 11273 22435 11275 22435 11275 22436 11273 22436 17252 22436 11275 22437 17252 22437 17320 22437 17320 22438 17252 22438 11276 22438 17320 22439 11276 22439 17319 22439 17319 22440 11276 22440 17253 22440 17319 22441 17253 22441 11277 22441 11277 22442 17253 22442 17256 22442 11277 22443 17256 22443 11278 22443 11278 22444 17256 22444 11280 22444 11278 22445 11280 22445 11279 22445 11279 22446 11280 22446 17257 22446 11279 22447 17257 22447 11281 22447 11281 22448 17257 22448 17260 22448 11281 22449 17260 22449 17316 22449 17316 22450 17260 22450 11282 22450 17316 22451 11282 22451 17287 22451 11291 22452 17217 22452 11283 22452 11283 22453 17217 22453 11284 22453 11283 22454 11284 22454 11286 22454 11286 22455 11284 22455 11285 22455 11286 22456 11285 22456 11287 22456 11287 22457 11285 22457 11288 22457 11287 22458 11288 22458 11293 22458 11293 22459 11288 22459 17214 22459 11293 22460 17214 22460 11289 22460 11289 22461 17214 22461 11290 22461 11289 22462 11290 22462 11292 22462 11292 22463 11290 22463 17213 22463 17237 22464 11286 22464 11287 22464 11283 22465 11286 22465 17237 22465 11291 22466 11283 22466 17237 22466 17237 22467 11289 22467 11292 22467 11293 22468 11289 22468 17237 22468 11287 22469 11293 22469 17237 22469 11294 22470 17236 22470 11295 22470 11295 22471 17236 22471 11296 22471 11295 22472 11296 22472 11302 22472 11302 22473 11296 22473 17207 22473 11302 22474 17207 22474 11303 22474 11303 22475 17207 22475 17206 22475 11303 22476 17206 22476 11297 22476 11297 22477 17206 22477 11298 22477 11297 22478 11298 22478 11299 22478 11299 22479 11298 22479 17227 22479 11299 22480 17227 22480 11300 22480 11300 22481 17227 22481 11301 22481 17231 22482 11302 22482 11303 22482 11295 22483 11302 22483 17231 22483 11294 22484 11295 22484 17231 22484 17231 22485 11299 22485 11300 22485 11297 22486 11299 22486 17231 22486 11303 22487 11297 22487 17231 22487 17194 22488 17173 22488 11310 22488 11310 22489 17173 22489 11304 22489 11310 22490 11304 22490 11309 22490 11309 22491 11304 22491 17174 22491 11309 22492 17174 22492 11305 22492 11305 22493 17174 22493 11306 22493 11305 22494 11306 22494 11311 22494 11311 22495 11306 22495 17160 22495 11311 22496 17160 22496 11307 22496 11307 22497 17160 22497 11308 22497 11307 22498 11308 22498 17197 22498 17197 22499 11308 22499 17179 22499 11312 22500 11309 22500 11305 22500 11310 22501 11309 22501 11312 22501 17194 22502 11310 22502 11312 22502 11312 22503 11307 22503 17197 22503 11311 22504 11307 22504 11312 22504 11305 22505 11311 22505 11312 22505 11313 22506 17193 22506 11314 22506 11314 22507 17193 22507 11315 22507 11314 22508 11315 22508 11318 22508 11318 22509 11315 22509 17169 22509 11318 22510 17169 22510 11316 22510 11316 22511 17169 22511 17163 22511 11316 22512 17163 22512 11320 22512 11320 22513 17163 22513 11317 22513 11320 22514 11317 22514 11319 22514 11319 22515 11317 22515 17177 22515 11319 22516 17177 22516 17185 22516 17185 22517 17177 22517 17186 22517 11321 22518 11318 22518 11316 22518 11314 22519 11318 22519 11321 22519 11313 22520 11314 22520 11321 22520 11321 22521 11319 22521 17185 22521 11320 22522 11319 22522 11321 22522 11316 22523 11320 22523 11321 22523 11326 22524 17159 22524 11327 22524 11327 22525 17159 22525 13948 22525 11327 22526 13948 22526 11322 22526 11322 22527 13948 22527 13947 22527 11322 22528 13947 22528 11330 22528 11330 22529 13947 22529 11323 22529 11330 22530 11323 22530 11331 22530 11331 22531 11323 22531 13944 22531 11331 22532 13944 22532 11324 22532 11324 22533 13944 22533 11325 22533 11324 22534 11325 22534 11333 22534 11333 22535 11325 22535 13956 22535 11333 22536 13956 22536 17144 22536 17144 22537 13956 22537 17151 22537 17140 22538 11326 22538 11327 22538 17140 22539 11327 22539 11336 22539 11336 22540 11327 22540 11322 22540 11336 22541 11322 22541 11328 22541 11328 22542 11322 22542 11337 22542 11337 22543 11322 22543 11330 22543 11337 22544 11330 22544 11329 22544 11329 22545 11330 22545 11338 22545 11338 22546 11330 22546 11331 22546 11338 22547 11331 22547 11332 22547 11332 22548 11331 22548 11343 22548 11343 22549 11331 22549 11324 22549 11343 22550 11324 22550 11341 22550 11341 22551 11324 22551 11333 22551 11341 22552 11333 22552 11334 22552 11334 22553 11333 22553 17144 22553 11334 22554 17144 22554 11339 22554 17141 22555 17140 22555 17069 22555 17069 22556 17140 22556 11336 22556 17069 22557 11336 22557 11335 22557 11336 22558 11328 22558 11335 22558 11335 22559 11328 22559 11337 22559 11335 22560 11337 22560 17067 22560 17067 22561 11337 22561 11329 22561 11329 22562 11338 22562 17067 22562 17067 22563 11338 22563 11332 22563 17067 22564 11332 22564 11342 22564 11339 22565 17076 22565 11334 22565 11334 22566 17076 22566 11340 22566 11334 22567 11340 22567 11341 22567 11341 22568 11340 22568 11342 22568 11341 22569 11342 22569 11343 22569 11343 22570 11342 22570 11332 22570 11344 22571 11345 22571 11346 22571 11346 22572 11345 22572 11347 22572 11346 22573 11347 22573 11348 22573 11348 22574 11347 22574 13933 22574 11348 22575 13933 22575 11349 22575 11349 22576 13933 22576 11351 22576 11349 22577 11351 22577 11350 22577 11350 22578 11351 22578 11352 22578 11350 22579 11352 22579 11353 22579 11353 22580 11352 22580 13942 22580 11353 22581 13942 22581 11361 22581 11361 22582 13942 22582 11354 22582 11361 22583 11354 22583 17126 22583 17126 22584 11354 22584 13941 22584 11363 22585 11344 22585 11346 22585 11363 22586 11346 22586 11364 22586 11364 22587 11346 22587 11348 22587 11364 22588 11348 22588 11355 22588 11355 22589 11348 22589 11356 22589 11356 22590 11348 22590 11349 22590 11356 22591 11349 22591 11357 22591 11357 22592 11349 22592 11358 22592 11358 22593 11349 22593 11350 22593 11358 22594 11350 22594 11359 22594 11359 22595 11350 22595 11360 22595 11360 22596 11350 22596 11353 22596 11360 22597 11353 22597 11369 22597 11369 22598 11353 22598 11361 22598 11369 22599 11361 22599 11367 22599 11367 22600 11361 22600 17126 22600 11367 22601 17126 22601 17116 22601 11362 22602 11363 22602 17043 22602 17043 22603 11363 22603 11364 22603 17043 22604 11364 22604 17042 22604 11364 22605 11355 22605 17042 22605 17042 22606 11355 22606 11356 22606 17042 22607 11356 22607 11365 22607 11365 22608 11356 22608 11357 22608 11357 22609 11358 22609 11365 22609 11365 22610 11358 22610 11359 22610 11365 22611 11359 22611 11366 22611 17116 22612 11368 22612 11367 22612 11367 22613 11368 22613 11370 22613 11367 22614 11370 22614 11369 22614 11369 22615 11370 22615 11366 22615 11369 22616 11366 22616 11360 22616 11360 22617 11366 22617 11359 22617 11371 22618 13928 22618 11372 22618 11372 22619 13928 22619 11373 22619 11372 22620 11373 22620 11374 22620 11374 22621 11373 22621 13927 22621 11374 22622 13927 22622 11375 22622 11375 22623 13927 22623 13926 22623 11375 22624 13926 22624 11376 22624 11376 22625 13926 22625 11377 22625 11376 22626 11377 22626 11378 22626 11378 22627 11377 22627 11379 22627 11378 22628 11379 22628 17101 22628 17101 22629 11379 22629 13924 22629 11386 22630 11371 22630 11385 22630 11385 22631 11371 22631 11372 22631 11385 22632 11372 22632 11384 22632 11384 22633 11372 22633 11374 22633 11384 22634 11374 22634 11380 22634 11380 22635 11374 22635 11375 22635 11380 22636 11375 22636 11381 22636 11381 22637 11375 22637 11376 22637 11381 22638 11376 22638 11382 22638 11382 22639 11376 22639 11378 22639 11382 22640 11378 22640 17100 22640 17100 22641 11378 22641 17101 22641 17100 22642 17020 22642 11382 22642 11382 22643 17020 22643 17022 22643 11382 22644 17022 22644 11381 22644 11381 22645 17022 22645 11383 22645 11381 22646 11383 22646 11380 22646 11380 22647 11383 22647 17015 22647 11380 22648 17015 22648 11384 22648 11384 22649 17015 22649 17016 22649 11384 22650 17016 22650 11385 22650 11385 22651 17016 22651 17017 22651 11385 22652 17017 22652 11386 22652 11386 22653 17017 22653 17096 22653 17088 22654 11388 22654 11387 22654 11387 22655 11388 22655 15881 22655 11387 22656 15881 22656 11395 22656 11395 22657 15881 22657 11389 22657 11395 22658 11389 22658 11397 22658 11397 22659 11389 22659 15888 22659 11397 22660 15888 22660 11398 22660 11398 22661 15888 22661 11390 22661 11398 22662 11390 22662 11400 22662 11400 22663 11390 22663 11391 22663 11400 22664 11391 22664 11392 22664 11392 22665 11391 22665 11393 22665 17083 22666 17088 22666 17077 22666 17077 22667 17088 22667 11387 22667 17077 22668 11387 22668 11394 22668 11394 22669 11387 22669 11395 22669 11394 22670 11395 22670 17068 22670 17068 22671 11395 22671 11397 22671 17068 22672 11397 22672 11396 22672 11396 22673 11397 22673 11398 22673 11396 22674 11398 22674 11399 22674 11399 22675 11398 22675 11400 22675 11399 22676 11400 22676 11401 22676 11401 22677 11400 22677 11392 22677 17059 22678 15939 22678 11408 22678 11408 22679 15939 22679 15938 22679 11408 22680 15938 22680 11409 22680 11409 22681 15938 22681 15936 22681 11409 22682 15936 22682 11410 22682 11410 22683 15936 22683 11403 22683 11410 22684 11403 22684 11402 22684 11402 22685 11403 22685 11404 22685 11402 22686 11404 22686 11411 22686 11411 22687 11404 22687 11405 22687 11411 22688 11405 22688 11406 22688 11406 22689 11405 22689 15933 22689 17038 22690 17059 22690 11407 22690 11407 22691 17059 22691 11408 22691 11407 22692 11408 22692 17039 22692 17039 22693 11408 22693 11409 22693 17039 22694 11409 22694 17040 22694 17040 22695 11409 22695 11410 22695 17040 22696 11410 22696 17041 22696 17041 22697 11410 22697 11402 22697 17041 22698 11402 22698 17044 22698 17044 22699 11402 22699 11411 22699 17044 22700 11411 22700 17049 22700 17049 22701 11411 22701 11406 22701 17029 22702 15846 22702 11418 22702 11418 22703 15846 22703 15853 22703 11418 22704 15853 22704 11412 22704 11412 22705 15853 22705 11413 22705 11412 22706 11413 22706 11414 22706 11414 22707 11413 22707 15855 22707 11414 22708 15855 22708 11415 22708 11415 22709 15855 22709 11416 22709 11415 22710 11416 22710 11420 22710 11420 22711 11416 22711 15839 22711 11420 22712 15839 22712 17025 22712 17025 22713 15839 22713 17030 22713 17023 22714 17029 22714 11417 22714 11417 22715 17029 22715 11418 22715 11417 22716 11418 22716 17014 22716 17014 22717 11418 22717 11412 22717 17014 22718 11412 22718 11419 22718 11419 22719 11412 22719 11414 22719 11419 22720 11414 22720 17018 22720 17018 22721 11414 22721 11415 22721 17018 22722 11415 22722 17019 22722 17019 22723 11415 22723 11420 22723 17019 22724 11420 22724 11421 22724 11421 22725 11420 22725 17025 22725 15886 22726 15885 22726 17006 22726 17006 22727 11422 22727 15886 22727 15886 22728 11422 22728 11423 22728 15886 22729 11423 22729 15887 22729 11423 22730 11463 22730 15887 22730 15887 22731 11463 22731 11465 22731 15887 22732 11465 22732 11424 22732 11424 22733 11465 22733 11425 22733 11424 22734 11425 22734 15890 22734 11425 22735 11466 22735 15890 22735 15890 22736 11466 22736 11467 22736 15890 22737 11467 22737 15891 22737 11467 22738 11468 22738 15891 22738 15891 22739 11468 22739 11426 22739 15891 22740 11426 22740 15893 22740 11427 22741 11428 22741 11429 22741 11429 22742 11428 22742 15893 22742 11429 22743 15893 22743 11470 22743 11470 22744 15893 22744 11426 22744 15935 22745 11478 22745 15930 22745 15930 22746 11478 22746 11480 22746 15930 22747 11480 22747 11430 22747 11480 22748 11481 22748 11430 22748 11430 22749 11481 22749 11482 22749 11430 22750 11482 22750 11432 22750 11432 22751 11482 22751 11431 22751 11431 22752 11485 22752 11432 22752 11432 22753 11485 22753 11486 22753 11432 22754 11486 22754 15927 22754 16953 22755 15925 22755 11489 22755 11489 22756 15925 22756 11433 22756 11489 22757 11433 22757 11488 22757 11488 22758 11433 22758 15927 22758 11488 22759 15927 22759 11487 22759 11487 22760 15927 22760 11486 22760 15970 22761 15969 22761 11496 22761 11496 22762 11434 22762 15970 22762 15970 22763 11434 22763 11435 22763 15970 22764 11435 22764 11437 22764 11435 22765 11436 22765 11437 22765 11437 22766 11436 22766 11438 22766 11437 22767 11438 22767 11439 22767 11438 22768 11499 22768 11439 22768 11439 22769 11499 22769 11440 22769 11439 22770 11440 22770 15932 22770 15932 22771 11440 22771 11441 22771 15932 22772 11441 22772 11442 22772 11441 22773 11443 22773 11442 22773 11442 22774 11443 22774 11447 22774 11442 22775 11447 22775 11445 22775 11504 22776 15967 22776 11444 22776 11444 22777 15967 22777 11445 22777 11444 22778 11445 22778 11446 22778 11446 22779 11445 22779 11447 22779 16978 22780 15851 22780 11521 22780 11521 22781 15851 22781 11448 22781 11521 22782 11448 22782 11449 22782 11449 22783 11448 22783 15850 22783 11449 22784 15850 22784 11519 22784 11519 22785 15850 22785 15843 22785 11519 22786 15843 22786 11517 22786 11517 22787 15843 22787 15842 22787 11517 22788 15842 22788 11450 22788 11450 22789 15842 22789 11451 22789 11450 22790 11451 22790 11514 22790 11514 22791 11451 22791 11452 22791 11453 22792 16977 22792 11464 22792 11464 22793 16977 22793 11455 22793 11464 22794 11455 22794 11454 22794 11454 22795 11455 22795 11456 22795 11454 22796 11456 22796 11457 22796 11457 22797 11456 22797 11458 22797 11457 22798 11458 22798 11460 22798 11460 22799 11458 22799 11459 22799 11460 22800 11459 22800 11469 22800 11469 22801 11459 22801 11462 22801 11469 22802 11462 22802 11461 22802 11461 22803 11462 22803 13922 22803 17006 22804 11453 22804 11422 22804 11422 22805 11453 22805 11464 22805 11422 22806 11464 22806 11423 22806 11423 22807 11464 22807 11463 22807 11463 22808 11464 22808 11454 22808 11463 22809 11454 22809 11465 22809 11465 22810 11454 22810 11425 22810 11425 22811 11454 22811 11457 22811 11425 22812 11457 22812 11466 22812 11466 22813 11457 22813 11467 22813 11467 22814 11457 22814 11460 22814 11467 22815 11460 22815 11468 22815 11468 22816 11460 22816 11426 22816 11426 22817 11460 22817 11469 22817 11426 22818 11469 22818 11470 22818 11470 22819 11469 22819 11429 22819 11429 22820 11469 22820 11461 22820 11429 22821 11461 22821 11427 22821 11471 22822 13900 22822 11479 22822 11479 22823 13900 22823 11473 22823 11479 22824 11473 22824 11472 22824 11472 22825 11473 22825 13899 22825 11472 22826 13899 22826 11483 22826 11483 22827 13899 22827 13912 22827 11483 22828 13912 22828 11484 22828 11484 22829 13912 22829 11474 22829 11484 22830 11474 22830 11475 22830 11475 22831 11474 22831 11476 22831 11475 22832 11476 22832 11477 22832 11477 22833 11476 22833 13909 22833 11477 22834 13909 22834 11490 22834 11490 22835 13909 22835 16962 22835 11478 22836 11471 22836 11479 22836 11478 22837 11479 22837 11480 22837 11480 22838 11479 22838 11472 22838 11480 22839 11472 22839 11481 22839 11481 22840 11472 22840 11482 22840 11482 22841 11472 22841 11483 22841 11482 22842 11483 22842 11431 22842 11431 22843 11483 22843 11485 22843 11485 22844 11483 22844 11484 22844 11485 22845 11484 22845 11486 22845 11486 22846 11484 22846 11487 22846 11487 22847 11484 22847 11475 22847 11487 22848 11475 22848 11488 22848 11488 22849 11475 22849 11477 22849 11488 22850 11477 22850 11489 22850 11489 22851 11477 22851 11490 22851 11489 22852 11490 22852 16953 22852 11497 22853 13894 22853 11498 22853 11498 22854 13894 22854 13893 22854 11498 22855 13893 22855 11491 22855 11491 22856 13893 22856 13891 22856 11491 22857 13891 22857 11500 22857 11500 22858 13891 22858 11492 22858 11500 22859 11492 22859 11501 22859 11501 22860 11492 22860 11493 22860 11501 22861 11493 22861 11502 22861 11502 22862 11493 22862 11494 22862 11502 22863 11494 22863 11503 22863 11503 22864 11494 22864 11495 22864 11496 22865 11497 22865 11434 22865 11434 22866 11497 22866 11498 22866 11434 22867 11498 22867 11435 22867 11435 22868 11498 22868 11436 22868 11436 22869 11498 22869 11491 22869 11436 22870 11491 22870 11438 22870 11438 22871 11491 22871 11499 22871 11499 22872 11491 22872 11500 22872 11499 22873 11500 22873 11440 22873 11440 22874 11500 22874 11441 22874 11441 22875 11500 22875 11501 22875 11441 22876 11501 22876 11443 22876 11443 22877 11501 22877 11447 22877 11447 22878 11501 22878 11502 22878 11447 22879 11502 22879 11446 22879 11446 22880 11502 22880 11444 22880 11444 22881 11502 22881 11503 22881 11444 22882 11503 22882 11504 22882 13885 22883 16933 22883 16926 22883 16926 22884 11505 22884 13885 22884 13885 22885 11505 22885 11522 22885 13885 22886 11522 22886 13873 22886 11522 22887 11506 22887 13873 22887 13873 22888 11506 22888 11508 22888 13873 22889 11508 22889 11507 22889 11508 22890 11520 22890 11507 22890 11507 22891 11520 22891 11509 22891 11507 22892 11509 22892 13875 22892 13875 22893 11509 22893 11518 22893 13875 22894 11518 22894 13878 22894 11518 22895 11510 22895 13878 22895 13878 22896 11510 22896 11511 22896 13878 22897 11511 22897 11513 22897 16938 22898 11512 22898 11515 22898 11515 22899 11512 22899 11513 22899 11515 22900 11513 22900 11516 22900 11516 22901 11513 22901 11511 22901 16938 22902 11515 22902 11514 22902 11514 22903 11515 22903 11450 22903 11515 22904 11516 22904 11450 22904 11450 22905 11516 22905 11511 22905 11450 22906 11511 22906 11517 22906 11511 22907 11510 22907 11517 22907 11517 22908 11510 22908 11518 22908 11517 22909 11518 22909 11519 22909 11518 22910 11509 22910 11519 22910 11519 22911 11509 22911 11520 22911 11519 22912 11520 22912 11449 22912 11520 22913 11508 22913 11449 22913 11449 22914 11508 22914 11506 22914 11449 22915 11506 22915 11521 22915 16926 22916 16978 22916 11505 22916 11505 22917 16978 22917 11521 22917 11505 22918 11521 22918 11522 22918 11522 22919 11521 22919 11506 22919 11523 22920 16924 22920 11525 22920 11525 22921 16924 22921 13869 22921 11525 22922 13869 22922 11526 22922 11526 22923 13869 22923 13868 22923 11526 22924 13868 22924 11527 22924 11527 22925 13868 22925 11524 22925 11527 22926 11524 22926 11528 22926 11528 22927 11524 22927 13866 22927 11528 22928 13866 22928 11530 22928 11530 22929 13866 22929 13865 22929 11530 22930 13865 22930 16912 22930 16912 22931 13865 22931 16916 22931 11538 22932 11523 22932 11536 22932 11536 22933 11523 22933 11525 22933 11536 22934 11525 22934 11535 22934 11535 22935 11525 22935 11526 22935 11535 22936 11526 22936 11534 22936 11534 22937 11526 22937 11527 22937 11534 22938 11527 22938 11529 22938 11529 22939 11527 22939 11528 22939 11529 22940 11528 22940 11532 22940 11532 22941 11528 22941 11530 22941 11532 22942 11530 22942 11531 22942 11531 22943 11530 22943 16912 22943 11531 22944 16858 22944 11532 22944 11532 22945 16858 22945 16859 22945 11532 22946 16859 22946 11529 22946 11529 22947 16859 22947 16860 22947 11529 22948 16860 22948 11534 22948 11534 22949 16860 22949 11533 22949 11534 22950 11533 22950 11535 22950 11535 22951 11533 22951 11537 22951 11535 22952 11537 22952 11536 22952 11536 22953 11537 22953 16851 22953 11536 22954 16851 22954 11538 22954 11538 22955 16851 22955 16904 22955 16898 22956 11539 22956 11545 22956 11545 22957 11539 22957 13857 22957 11545 22958 13857 22958 11540 22958 11540 22959 13857 22959 11541 22959 11540 22960 11541 22960 11542 22960 11542 22961 11541 22961 11543 22961 11542 22962 11543 22962 11549 22962 11549 22963 11543 22963 13855 22963 11549 22964 13855 22964 11550 22964 11550 22965 13855 22965 13864 22965 11550 22966 13864 22966 16890 22966 16890 22967 13864 22967 11544 22967 11552 22968 16898 22968 11553 22968 11553 22969 16898 22969 11545 22969 11553 22970 11545 22970 11546 22970 11546 22971 11545 22971 11554 22971 11554 22972 11545 22972 11540 22972 11554 22973 11540 22973 11547 22973 11547 22974 11540 22974 11555 22974 11555 22975 11540 22975 11542 22975 11555 22976 11542 22976 11548 22976 11548 22977 11542 22977 11557 22977 11557 22978 11542 22978 11549 22978 11557 22979 11549 22979 11558 22979 11558 22980 11549 22980 11559 22980 11559 22981 11549 22981 11550 22981 11559 22982 11550 22982 11563 22982 11563 22983 11550 22983 11561 22983 11561 22984 11550 22984 16890 22984 11561 22985 16890 22985 11551 22985 16821 22986 16820 22986 11552 22986 11552 22987 11553 22987 16821 22987 16821 22988 11553 22988 11546 22988 16821 22989 11546 22989 16823 22989 11546 22990 11554 22990 16823 22990 16823 22991 11554 22991 11547 22991 16823 22992 11547 22992 16831 22992 16831 22993 11547 22993 11555 22993 16831 22994 11555 22994 11556 22994 11555 22995 11548 22995 11556 22995 11556 22996 11548 22996 11557 22996 11556 22997 11557 22997 11560 22997 11557 22998 11558 22998 11560 22998 11560 22999 11558 22999 11559 22999 11560 23000 11559 23000 11562 23000 11551 23001 16828 23001 11561 23001 11561 23002 16828 23002 11562 23002 11561 23003 11562 23003 11563 23003 11563 23004 11562 23004 11559 23004 16882 23005 13845 23005 11571 23005 11571 23006 13845 23006 13844 23006 11571 23007 13844 23007 11564 23007 11564 23008 13844 23008 13843 23008 11564 23009 13843 23009 11565 23009 11565 23010 13843 23010 11567 23010 11565 23011 11567 23011 11566 23011 11566 23012 11567 23012 13842 23012 11566 23013 13842 23013 11574 23013 11574 23014 13842 23014 11568 23014 11574 23015 11568 23015 11569 23015 11569 23016 11568 23016 13840 23016 11569 23017 13840 23017 16875 23017 16875 23018 13840 23018 11570 23018 11583 23019 16882 23019 11582 23019 11582 23020 16882 23020 11571 23020 11582 23021 11571 23021 11581 23021 11581 23022 11571 23022 11564 23022 11581 23023 11564 23023 11572 23023 11572 23024 11564 23024 11565 23024 11572 23025 11565 23025 11573 23025 11573 23026 11565 23026 11566 23026 11573 23027 11566 23027 11578 23027 11578 23028 11566 23028 11574 23028 11578 23029 11574 23029 11575 23029 11575 23030 11574 23030 11569 23030 11575 23031 11569 23031 11576 23031 11576 23032 11569 23032 16875 23032 11576 23033 16874 23033 11575 23033 11575 23034 16874 23034 11577 23034 11575 23035 11577 23035 11578 23035 11578 23036 11577 23036 16801 23036 11578 23037 16801 23037 11573 23037 11573 23038 16801 23038 11579 23038 11573 23039 11579 23039 11572 23039 11572 23040 11579 23040 16803 23040 11572 23041 16803 23041 11581 23041 11581 23042 16803 23042 11580 23042 11581 23043 11580 23043 11582 23043 11582 23044 11580 23044 16794 23044 11582 23045 16794 23045 11583 23045 11583 23046 16794 23046 11584 23046 11593 23047 11585 23047 11587 23047 11587 23048 11585 23048 11586 23048 11587 23049 11586 23049 11596 23049 11596 23050 11586 23050 15769 23050 11596 23051 15769 23051 11597 23051 11597 23052 15769 23052 15768 23052 11597 23053 15768 23053 11588 23053 11588 23054 15768 23054 11589 23054 11588 23055 11589 23055 11599 23055 11599 23056 11589 23056 11591 23056 11599 23057 11591 23057 11590 23057 11590 23058 11591 23058 15771 23058 11590 23059 15771 23059 11592 23059 11592 23060 15771 23060 16868 23060 16867 23061 11593 23061 11594 23061 11594 23062 11593 23062 11587 23062 11594 23063 11587 23063 11595 23063 11595 23064 11587 23064 11596 23064 11595 23065 11596 23065 16849 23065 16849 23066 11596 23066 11597 23066 16849 23067 11597 23067 16850 23067 16850 23068 11597 23068 11588 23068 16850 23069 11588 23069 11598 23069 11598 23070 11588 23070 11599 23070 11598 23071 11599 23071 16852 23071 16852 23072 11599 23072 11590 23072 16852 23073 11590 23073 16853 23073 16853 23074 11590 23074 11592 23074 11607 23075 11600 23075 11608 23075 11608 23076 11600 23076 11601 23076 11608 23077 11601 23077 11609 23077 11609 23078 11601 23078 15777 23078 11609 23079 15777 23079 11602 23079 11602 23080 15777 23080 11603 23080 11602 23081 11603 23081 11610 23081 11610 23082 11603 23082 11604 23082 11610 23083 11604 23083 11605 23083 11605 23084 11604 23084 11606 23084 11605 23085 11606 23085 16834 23085 16834 23086 11606 23086 16842 23086 16840 23087 11607 23087 16829 23087 16829 23088 11607 23088 11608 23088 16829 23089 11608 23089 16830 23089 16830 23090 11608 23090 11609 23090 16830 23091 11609 23091 16832 23091 16832 23092 11609 23092 11602 23092 16832 23093 11602 23093 16822 23093 16822 23094 11602 23094 11610 23094 16822 23095 11610 23095 11611 23095 11611 23096 11610 23096 11605 23096 11611 23097 11605 23097 16833 23097 16833 23098 11605 23098 16834 23098 11619 23099 15869 23099 11620 23099 11620 23100 15869 23100 11612 23100 11620 23101 11612 23101 11622 23101 11622 23102 11612 23102 15876 23102 11622 23103 15876 23103 11613 23103 11613 23104 15876 23104 11614 23104 11613 23105 11614 23105 11615 23105 11615 23106 11614 23106 15879 23106 11615 23107 15879 23107 11625 23107 11625 23108 15879 23108 11616 23108 11625 23109 11616 23109 11617 23109 11617 23110 11616 23110 15878 23110 11618 23111 11619 23111 16800 23111 16800 23112 11619 23112 11620 23112 16800 23113 11620 23113 11621 23113 11621 23114 11620 23114 11622 23114 11621 23115 11622 23115 16802 23115 16802 23116 11622 23116 11613 23116 16802 23117 11613 23117 11623 23117 11623 23118 11613 23118 11615 23118 11623 23119 11615 23119 11624 23119 11624 23120 11615 23120 11625 23120 11624 23121 11625 23121 11626 23121 11626 23122 11625 23122 11617 23122 11665 23123 15767 23123 11664 23123 11664 23124 15767 23124 11627 23124 11664 23125 11627 23125 11628 23125 11628 23126 11627 23126 11629 23126 11628 23127 11629 23127 11661 23127 11661 23128 11629 23128 11630 23128 11661 23129 11630 23129 11660 23129 11660 23130 11630 23130 11631 23130 11660 23131 11631 23131 11659 23131 11659 23132 11631 23132 15787 23132 11659 23133 15787 23133 11632 23133 11632 23134 15787 23134 16788 23134 15791 23135 11672 23135 11633 23135 11633 23136 11672 23136 11635 23136 11633 23137 11635 23137 11634 23137 11635 23138 11636 23138 11634 23138 11634 23139 11636 23139 11674 23139 11634 23140 11674 23140 11637 23140 11637 23141 11674 23141 11638 23141 11638 23142 11676 23142 11637 23142 11637 23143 11676 23143 11639 23143 11637 23144 11639 23144 11640 23144 16776 23145 16775 23145 11641 23145 11641 23146 16775 23146 15792 23146 11641 23147 15792 23147 11679 23147 11679 23148 15792 23148 11640 23148 11679 23149 11640 23149 11678 23149 11678 23150 11640 23150 11639 23150 11642 23151 16774 23151 11643 23151 11643 23152 16774 23152 11689 23152 11643 23153 11689 23153 15778 23153 11689 23154 11644 23154 15778 23154 15778 23155 11644 23155 11691 23155 15778 23156 11691 23156 11646 23156 11646 23157 11691 23157 11645 23157 11645 23158 11693 23158 11646 23158 11646 23159 11693 23159 11647 23159 11646 23160 11647 23160 11650 23160 16766 23161 15782 23161 11648 23161 11648 23162 15782 23162 11649 23162 11648 23163 11649 23163 11696 23163 11696 23164 11649 23164 11650 23164 11696 23165 11650 23165 11695 23165 11695 23166 11650 23166 11647 23166 11716 23167 16026 23167 11717 23167 11717 23168 16026 23168 11651 23168 11717 23169 11651 23169 11714 23169 11714 23170 11651 23170 16025 23170 11714 23171 16025 23171 11712 23171 11712 23172 16025 23172 16017 23172 11712 23173 16017 23173 11711 23173 11711 23174 16017 23174 11652 23174 11711 23175 11652 23175 11709 23175 11709 23176 11652 23176 16021 23176 11709 23177 16021 23177 16762 23177 16762 23178 16021 23178 16764 23178 16754 23179 13834 23179 11653 23179 11653 23180 13834 23180 13833 23180 11653 23181 13833 23181 11662 23181 11662 23182 13833 23182 11654 23182 11662 23183 11654 23183 11663 23183 11663 23184 11654 23184 13832 23184 11663 23185 13832 23185 11656 23185 11656 23186 13832 23186 11655 23186 11656 23187 11655 23187 11657 23187 11657 23188 11655 23188 11658 23188 11657 23189 11658 23189 16746 23189 16746 23190 11658 23190 13830 23190 11632 23191 16754 23191 11659 23191 11659 23192 16754 23192 11653 23192 11659 23193 11653 23193 11660 23193 11660 23194 11653 23194 11662 23194 11660 23195 11662 23195 11661 23195 11661 23196 11662 23196 11663 23196 11661 23197 11663 23197 11628 23197 11628 23198 11663 23198 11656 23198 11628 23199 11656 23199 11664 23199 11664 23200 11656 23200 11657 23200 11664 23201 11657 23201 11665 23201 11665 23202 11657 23202 16746 23202 16737 23203 13818 23203 11673 23203 11673 23204 13818 23204 13817 23204 11673 23205 13817 23205 11675 23205 11675 23206 13817 23206 13828 23206 11675 23207 13828 23207 11677 23207 11677 23208 13828 23208 11666 23208 11677 23209 11666 23209 11667 23209 11667 23210 11666 23210 11668 23210 11667 23211 11668 23211 11669 23211 11669 23212 11668 23212 11670 23212 11669 23213 11670 23213 11680 23213 11680 23214 11670 23214 13823 23214 11680 23215 13823 23215 16721 23215 16721 23216 13823 23216 11671 23216 11672 23217 16737 23217 11673 23217 11672 23218 11673 23218 11635 23218 11635 23219 11673 23219 11675 23219 11635 23220 11675 23220 11636 23220 11636 23221 11675 23221 11674 23221 11674 23222 11675 23222 11677 23222 11674 23223 11677 23223 11638 23223 11638 23224 11677 23224 11676 23224 11676 23225 11677 23225 11667 23225 11676 23226 11667 23226 11639 23226 11639 23227 11667 23227 11678 23227 11678 23228 11667 23228 11669 23228 11678 23229 11669 23229 11679 23229 11679 23230 11669 23230 11680 23230 11679 23231 11680 23231 11641 23231 11641 23232 11680 23232 16721 23232 11641 23233 16721 23233 16776 23233 11688 23234 11682 23234 11681 23234 11681 23235 11682 23235 13809 23235 11681 23236 13809 23236 11690 23236 11690 23237 13809 23237 11683 23237 11690 23238 11683 23238 11692 23238 11692 23239 11683 23239 11684 23239 11692 23240 11684 23240 11685 23240 11685 23241 11684 23241 13806 23241 11685 23242 13806 23242 11694 23242 11694 23243 13806 23243 13805 23243 11694 23244 13805 23244 11697 23244 11697 23245 13805 23245 11687 23245 11697 23246 11687 23246 11686 23246 11686 23247 11687 23247 13816 23247 16774 23248 11688 23248 11681 23248 16774 23249 11681 23249 11689 23249 11689 23250 11681 23250 11690 23250 11689 23251 11690 23251 11644 23251 11644 23252 11690 23252 11691 23252 11691 23253 11690 23253 11692 23253 11691 23254 11692 23254 11645 23254 11645 23255 11692 23255 11693 23255 11693 23256 11692 23256 11685 23256 11693 23257 11685 23257 11647 23257 11647 23258 11685 23258 11695 23258 11695 23259 11685 23259 11694 23259 11695 23260 11694 23260 11696 23260 11696 23261 11694 23261 11697 23261 11696 23262 11697 23262 11648 23262 11648 23263 11697 23263 11686 23263 11648 23264 11686 23264 16766 23264 11698 23265 13802 23265 11715 23265 11715 23266 11699 23266 11698 23266 11698 23267 11699 23267 11718 23267 11698 23268 11718 23268 11700 23268 11718 23269 11719 23269 11700 23269 11700 23270 11719 23270 11701 23270 11700 23271 11701 23271 13793 23271 11701 23272 11713 23272 13793 23272 13793 23273 11713 23273 11702 23273 13793 23274 11702 23274 13794 23274 13794 23275 11702 23275 11703 23275 13794 23276 11703 23276 11704 23276 11703 23277 11710 23277 11704 23277 11704 23278 11710 23278 11705 23278 11704 23279 11705 23279 13797 23279 11707 23280 13798 23280 11708 23280 11708 23281 13798 23281 13797 23281 11708 23282 13797 23282 11706 23282 11706 23283 13797 23283 11705 23283 11707 23284 11708 23284 16762 23284 16762 23285 11708 23285 11709 23285 11708 23286 11706 23286 11709 23286 11709 23287 11706 23287 11705 23287 11709 23288 11705 23288 11711 23288 11705 23289 11710 23289 11711 23289 11711 23290 11710 23290 11703 23290 11711 23291 11703 23291 11712 23291 11703 23292 11702 23292 11712 23292 11712 23293 11702 23293 11713 23293 11712 23294 11713 23294 11714 23294 11713 23295 11701 23295 11714 23295 11714 23296 11701 23296 11719 23296 11714 23297 11719 23297 11717 23297 11715 23298 11716 23298 11699 23298 11699 23299 11716 23299 11717 23299 11699 23300 11717 23300 11718 23300 11718 23301 11717 23301 11719 23301 16685 23302 11720 23302 11729 23302 11729 23303 11720 23303 11721 23303 11729 23304 11721 23304 11722 23304 11722 23305 11721 23305 13783 23305 11722 23306 13783 23306 11723 23306 11723 23307 13783 23307 11724 23307 11723 23308 11724 23308 11725 23308 11725 23309 11724 23309 11726 23309 11725 23310 11726 23310 11733 23310 11733 23311 11726 23311 11728 23311 11733 23312 11728 23312 11727 23312 11727 23313 11728 23313 16686 23313 11738 23314 16685 23314 11737 23314 11737 23315 16685 23315 11729 23315 11737 23316 11729 23316 11735 23316 11735 23317 11729 23317 11722 23317 11735 23318 11722 23318 11730 23318 11730 23319 11722 23319 11723 23319 11730 23320 11723 23320 11731 23320 11731 23321 11723 23321 11725 23321 11731 23322 11725 23322 11732 23322 11732 23323 11725 23323 11733 23323 11732 23324 11733 23324 11734 23324 11734 23325 11733 23325 11727 23325 11734 23326 16664 23326 11732 23326 11732 23327 16664 23327 16589 23327 11732 23328 16589 23328 11731 23328 11731 23329 16589 23329 16591 23329 11731 23330 16591 23330 11730 23330 11730 23331 16591 23331 16592 23331 11730 23332 16592 23332 11735 23332 11735 23333 16592 23333 11736 23333 11735 23334 11736 23334 11737 23334 11737 23335 11736 23335 16595 23335 11737 23336 16595 23336 11738 23336 11738 23337 16595 23337 16596 23337 16659 23338 16663 23338 11739 23338 11739 23339 16663 23339 11740 23339 11739 23340 11740 23340 11748 23340 11748 23341 11740 23341 11741 23341 11748 23342 11741 23342 11742 23342 11742 23343 11741 23343 11743 23343 11742 23344 11743 23344 11752 23344 11752 23345 11743 23345 11744 23345 11752 23346 11744 23346 11745 23346 11745 23347 11744 23347 13772 23347 11745 23348 13772 23348 16660 23348 16660 23349 13772 23349 13771 23349 16644 23350 16659 23350 11746 23350 11746 23351 16659 23351 11739 23351 11746 23352 11739 23352 11747 23352 11747 23353 11739 23353 11748 23353 11747 23354 11748 23354 11749 23354 11749 23355 11748 23355 11742 23355 11749 23356 11742 23356 11750 23356 11750 23357 11742 23357 11752 23357 11750 23358 11752 23358 11751 23358 11751 23359 11752 23359 11745 23359 11751 23360 11745 23360 11753 23360 11753 23361 11745 23361 16660 23361 11753 23362 11754 23362 11751 23362 11751 23363 11754 23363 11755 23363 11751 23364 11755 23364 11750 23364 11750 23365 11755 23365 11756 23365 11750 23366 11756 23366 11749 23366 11749 23367 11756 23367 11757 23367 11749 23368 11757 23368 11747 23368 11747 23369 11757 23369 11758 23369 11747 23370 11758 23370 11746 23370 11746 23371 11758 23371 11759 23371 11746 23372 11759 23372 16644 23372 16644 23373 11759 23373 16569 23373 16631 23374 13764 23374 11767 23374 11767 23375 13764 23375 13763 23375 11767 23376 13763 23376 11760 23376 11760 23377 13763 23377 13761 23377 11760 23378 13761 23378 11761 23378 11761 23379 13761 23379 11762 23379 11761 23380 11762 23380 11763 23380 11763 23381 11762 23381 13759 23381 11763 23382 13759 23382 11770 23382 11770 23383 13759 23383 13758 23383 11770 23384 13758 23384 11764 23384 11764 23385 13758 23385 16632 23385 11765 23386 16631 23386 11766 23386 11766 23387 16631 23387 11767 23387 11766 23388 11767 23388 11774 23388 11774 23389 11767 23389 11760 23389 11774 23390 11760 23390 11768 23390 11768 23391 11760 23391 11761 23391 11768 23392 11761 23392 11773 23392 11773 23393 11761 23393 11763 23393 11773 23394 11763 23394 11771 23394 11771 23395 11763 23395 11770 23395 11771 23396 11770 23396 11769 23396 11769 23397 11770 23397 11764 23397 11769 23398 16551 23398 11771 23398 11771 23399 16551 23399 11772 23399 11771 23400 11772 23400 11773 23400 11773 23401 11772 23401 16552 23401 11773 23402 16552 23402 11768 23402 11768 23403 16552 23403 16540 23403 11768 23404 16540 23404 11774 23404 11774 23405 16540 23405 11775 23405 11774 23406 11775 23406 11766 23406 11766 23407 11775 23407 16544 23407 11766 23408 16544 23408 11765 23408 11765 23409 16544 23409 11776 23409 16615 23410 11777 23410 11782 23410 11782 23411 11777 23411 15899 23411 11782 23412 15899 23412 11783 23412 11783 23413 15899 23413 15898 23413 11783 23414 15898 23414 11778 23414 11778 23415 15898 23415 11779 23415 11778 23416 11779 23416 11784 23416 11784 23417 11779 23417 11780 23417 11784 23418 11780 23418 11787 23418 11787 23419 11780 23419 11781 23419 11787 23420 11781 23420 16606 23420 16606 23421 11781 23421 16607 23421 16605 23422 16615 23422 16590 23422 16590 23423 16615 23423 11782 23423 16590 23424 11782 23424 16593 23424 16593 23425 11782 23425 11783 23425 16593 23426 11783 23426 16594 23426 16594 23427 11783 23427 11778 23427 16594 23428 11778 23428 11785 23428 11785 23429 11778 23429 11784 23429 11785 23430 11784 23430 11786 23430 11786 23431 11784 23431 11787 23431 11786 23432 11787 23432 11788 23432 11788 23433 11787 23433 16606 23433 16587 23434 15943 23434 11793 23434 11793 23435 15943 23435 11789 23435 11793 23436 11789 23436 11794 23436 11794 23437 11789 23437 15902 23437 11794 23438 15902 23438 11796 23438 11796 23439 15902 23439 15901 23439 11796 23440 15901 23440 11798 23440 11798 23441 15901 23441 11790 23441 11798 23442 11790 23442 11799 23442 11799 23443 11790 23443 15905 23443 11799 23444 15905 23444 11800 23444 11800 23445 15905 23445 11792 23445 11800 23446 11792 23446 11791 23446 11791 23447 11792 23447 15906 23447 16575 23448 16587 23448 16576 23448 16576 23449 16587 23449 11793 23449 16576 23450 11793 23450 16577 23450 16577 23451 11793 23451 11794 23451 16577 23452 11794 23452 11795 23452 11795 23453 11794 23453 11796 23453 11795 23454 11796 23454 11797 23454 11797 23455 11796 23455 11798 23455 11797 23456 11798 23456 16568 23456 16568 23457 11798 23457 11799 23457 16568 23458 11799 23458 11801 23458 11801 23459 11799 23459 11800 23459 11801 23460 11800 23460 16570 23460 16570 23461 11800 23461 11791 23461 11812 23462 11802 23462 11814 23462 11814 23463 11802 23463 11803 23463 11814 23464 11803 23464 11805 23464 11805 23465 11803 23465 11804 23465 11805 23466 11804 23466 11815 23466 11815 23467 11804 23467 15866 23467 11815 23468 15866 23468 11806 23468 11806 23469 15866 23469 11807 23469 11806 23470 11807 23470 11808 23470 11808 23471 11807 23471 11809 23471 11808 23472 11809 23472 11817 23472 11817 23473 11809 23473 11810 23473 11817 23474 11810 23474 16553 23474 16553 23475 11810 23475 11811 23475 16561 23476 11812 23476 11813 23476 11813 23477 11812 23477 11814 23477 11813 23478 11814 23478 16539 23478 16539 23479 11814 23479 11805 23479 16539 23480 11805 23480 16541 23480 16541 23481 11805 23481 11815 23481 16541 23482 11815 23482 16542 23482 16542 23483 11815 23483 11806 23483 16542 23484 11806 23484 16543 23484 16543 23485 11806 23485 11808 23485 16543 23486 11808 23486 11816 23486 11816 23487 11808 23487 11817 23487 11816 23488 11817 23488 16545 23488 16545 23489 11817 23489 16553 23489 16049 23490 11856 23490 11818 23490 11818 23491 11856 23491 11819 23491 11818 23492 11819 23492 16054 23492 11819 23493 11820 23493 16054 23493 16054 23494 11820 23494 11858 23494 16054 23495 11858 23495 16055 23495 16055 23496 11858 23496 11860 23496 11860 23497 11821 23497 16055 23497 16055 23498 11821 23498 11824 23498 16055 23499 11824 23499 11823 23499 11822 23500 16058 23500 11863 23500 11863 23501 16058 23501 16057 23501 11863 23502 16057 23502 11862 23502 11862 23503 16057 23503 11823 23503 11862 23504 11823 23504 11861 23504 11861 23505 11823 23505 11824 23505 16533 23506 16532 23506 11825 23506 11825 23507 16532 23507 11869 23507 11825 23508 11869 23508 15919 23508 11869 23509 11826 23509 15919 23509 15919 23510 11826 23510 11827 23510 15919 23511 11827 23511 15920 23511 15920 23512 11827 23512 11828 23512 11828 23513 11873 23513 15920 23513 15920 23514 11873 23514 11874 23514 15920 23515 11874 23515 15921 23515 16486 23516 15904 23516 11877 23516 11877 23517 15904 23517 15922 23517 11877 23518 15922 23518 11829 23518 11829 23519 15922 23519 15921 23519 11829 23520 15921 23520 11875 23520 11875 23521 15921 23521 11874 23521 15948 23522 16478 23522 15764 23522 15764 23523 16478 23523 11830 23523 15764 23524 11830 23524 11831 23524 11830 23525 11887 23525 11831 23525 11831 23526 11887 23526 11832 23526 11831 23527 11832 23527 15910 23527 15910 23528 11832 23528 11833 23528 11833 23529 11834 23529 15910 23529 15910 23530 11834 23530 11835 23530 15910 23531 11835 23531 11838 23531 16522 23532 15945 23532 11836 23532 11836 23533 15945 23533 16069 23533 11836 23534 16069 23534 11837 23534 11837 23535 16069 23535 11838 23535 11837 23536 11838 23536 11839 23536 11839 23537 11838 23537 11835 23537 15867 23538 16107 23538 16515 23538 16515 23539 11898 23539 15867 23539 15867 23540 11898 23540 11840 23540 15867 23541 11840 23541 11841 23541 11840 23542 11842 23542 11841 23542 11841 23543 11842 23543 11900 23543 11841 23544 11900 23544 16072 23544 16072 23545 11900 23545 11901 23545 16072 23546 11901 23546 11843 23546 11901 23547 11902 23547 11843 23547 11843 23548 11902 23548 11903 23548 11843 23549 11903 23549 11846 23549 11903 23550 11844 23550 11846 23550 11846 23551 11844 23551 11845 23551 11846 23552 11845 23552 15861 23552 16458 23553 11847 23553 11848 23553 11848 23554 11847 23554 15861 23554 11848 23555 15861 23555 11904 23555 11904 23556 15861 23556 11845 23556 11857 23557 11849 23557 11851 23557 11851 23558 11849 23558 11850 23558 11851 23559 11850 23559 11859 23559 11859 23560 11850 23560 13745 23560 11859 23561 13745 23561 11852 23561 11852 23562 13745 23562 13743 23562 11852 23563 13743 23563 11853 23563 11853 23564 13743 23564 13755 23564 11853 23565 13755 23565 11854 23565 11854 23566 13755 23566 13754 23566 11854 23567 13754 23567 11864 23567 11864 23568 13754 23568 13753 23568 11864 23569 13753 23569 11855 23569 11855 23570 13753 23570 16503 23570 11856 23571 11857 23571 11851 23571 11856 23572 11851 23572 11819 23572 11819 23573 11851 23573 11859 23573 11819 23574 11859 23574 11820 23574 11820 23575 11859 23575 11858 23575 11858 23576 11859 23576 11852 23576 11858 23577 11852 23577 11860 23577 11860 23578 11852 23578 11821 23578 11821 23579 11852 23579 11853 23579 11821 23580 11853 23580 11824 23580 11824 23581 11853 23581 11861 23581 11861 23582 11853 23582 11854 23582 11861 23583 11854 23583 11862 23583 11862 23584 11854 23584 11864 23584 11862 23585 11864 23585 11863 23585 11863 23586 11864 23586 11855 23586 11863 23587 11855 23587 11822 23587 16494 23588 13734 23588 11870 23588 11870 23589 13734 23589 13733 23589 11870 23590 13733 23590 11871 23590 11871 23591 13733 23591 11865 23591 11871 23592 11865 23592 11872 23592 11872 23593 11865 23593 13731 23593 11872 23594 13731 23594 11866 23594 11866 23595 13731 23595 13730 23595 11866 23596 13730 23596 11876 23596 11876 23597 13730 23597 13728 23597 11876 23598 13728 23598 11867 23598 11867 23599 13728 23599 13726 23599 11867 23600 13726 23600 11868 23600 11868 23601 13726 23601 13742 23601 16532 23602 16494 23602 11870 23602 16532 23603 11870 23603 11869 23603 11869 23604 11870 23604 11871 23604 11869 23605 11871 23605 11826 23605 11826 23606 11871 23606 11827 23606 11827 23607 11871 23607 11872 23607 11827 23608 11872 23608 11828 23608 11828 23609 11872 23609 11873 23609 11873 23610 11872 23610 11866 23610 11873 23611 11866 23611 11874 23611 11874 23612 11866 23612 11875 23612 11875 23613 11866 23613 11876 23613 11875 23614 11876 23614 11829 23614 11829 23615 11876 23615 11867 23615 11829 23616 11867 23616 11877 23616 11877 23617 11867 23617 11868 23617 11877 23618 11868 23618 16486 23618 11878 23619 13716 23619 11886 23619 11886 23620 13716 23620 13715 23620 11886 23621 13715 23621 11888 23621 11888 23622 13715 23622 11879 23622 11888 23623 11879 23623 11889 23623 11889 23624 11879 23624 11880 23624 11889 23625 11880 23625 11881 23625 11881 23626 11880 23626 13714 23626 11881 23627 13714 23627 11882 23627 11882 23628 13714 23628 13725 23628 11882 23629 13725 23629 11883 23629 11883 23630 13725 23630 11884 23630 11883 23631 11884 23631 11885 23631 11885 23632 11884 23632 16480 23632 16478 23633 11878 23633 11886 23633 16478 23634 11886 23634 11830 23634 11830 23635 11886 23635 11888 23635 11830 23636 11888 23636 11887 23636 11887 23637 11888 23637 11832 23637 11832 23638 11888 23638 11889 23638 11832 23639 11889 23639 11833 23639 11833 23640 11889 23640 11834 23640 11834 23641 11889 23641 11881 23641 11834 23642 11881 23642 11835 23642 11835 23643 11881 23643 11839 23643 11839 23644 11881 23644 11882 23644 11839 23645 11882 23645 11837 23645 11837 23646 11882 23646 11883 23646 11837 23647 11883 23647 11836 23647 11836 23648 11883 23648 11885 23648 11836 23649 11885 23649 16522 23649 11897 23650 11891 23650 11890 23650 11890 23651 11891 23651 13708 23651 11890 23652 13708 23652 11899 23652 11899 23653 13708 23653 11892 23653 11899 23654 11892 23654 11893 23654 11893 23655 11892 23655 11894 23655 11893 23656 11894 23656 11895 23656 11895 23657 11894 23657 13706 23657 11895 23658 13706 23658 11905 23658 11905 23659 13706 23659 13705 23659 11905 23660 13705 23660 11896 23660 11896 23661 13705 23661 13703 23661 16515 23662 11897 23662 11898 23662 11898 23663 11897 23663 11890 23663 11898 23664 11890 23664 11840 23664 11840 23665 11890 23665 11842 23665 11842 23666 11890 23666 11899 23666 11842 23667 11899 23667 11900 23667 11900 23668 11899 23668 11901 23668 11901 23669 11899 23669 11893 23669 11901 23670 11893 23670 11902 23670 11902 23671 11893 23671 11903 23671 11903 23672 11893 23672 11895 23672 11903 23673 11895 23673 11844 23673 11844 23674 11895 23674 11845 23674 11845 23675 11895 23675 11905 23675 11845 23676 11905 23676 11904 23676 11904 23677 11905 23677 11848 23677 11848 23678 11905 23678 11896 23678 11848 23679 11896 23679 16458 23679 16453 23680 11906 23680 11912 23680 11912 23681 11906 23681 13607 23681 11912 23682 13607 23682 11914 23682 11914 23683 13607 23683 11907 23683 11914 23684 11907 23684 11916 23684 11916 23685 11907 23685 11908 23685 11916 23686 11908 23686 11917 23686 11917 23687 11908 23687 11909 23687 11917 23688 11909 23688 11918 23688 11918 23689 11909 23689 13605 23689 11918 23690 13605 23690 16454 23690 16454 23691 13605 23691 11910 23691 16439 23692 16453 23692 11911 23692 11911 23693 16453 23693 11912 23693 11911 23694 11912 23694 11913 23694 11913 23695 11912 23695 11914 23695 11913 23696 11914 23696 11920 23696 11920 23697 11914 23697 11916 23697 11920 23698 11916 23698 11915 23698 11915 23699 11916 23699 11917 23699 11915 23700 11917 23700 11919 23700 11919 23701 11917 23701 11918 23701 11919 23702 11918 23702 16435 23702 16435 23703 11918 23703 16454 23703 16435 23704 16369 23704 11919 23704 11919 23705 16369 23705 16370 23705 11919 23706 16370 23706 11915 23706 11915 23707 16370 23707 16371 23707 11915 23708 16371 23708 11920 23708 11920 23709 16371 23709 11921 23709 11920 23710 11921 23710 11913 23710 11913 23711 11921 23711 11922 23711 11913 23712 11922 23712 11911 23712 11911 23713 11922 23713 11923 23713 11911 23714 11923 23714 16439 23714 16439 23715 11923 23715 16440 23715 11933 23716 11924 23716 11934 23716 11934 23717 11924 23717 11925 23717 11934 23718 11925 23718 11938 23718 11938 23719 11925 23719 11926 23719 11938 23720 11926 23720 11927 23720 11927 23721 11926 23721 13630 23721 11927 23722 13630 23722 11928 23722 11928 23723 13630 23723 13628 23723 11928 23724 13628 23724 11929 23724 11929 23725 13628 23725 11930 23725 11929 23726 11930 23726 11941 23726 11941 23727 11930 23727 13626 23727 11941 23728 13626 23728 11931 23728 11931 23729 13626 23729 16429 23729 11932 23730 11933 23730 11934 23730 11932 23731 11934 23731 11935 23731 11935 23732 11934 23732 11938 23732 11935 23733 11938 23733 11936 23733 11936 23734 11938 23734 11937 23734 11937 23735 11938 23735 11927 23735 11937 23736 11927 23736 11942 23736 11942 23737 11927 23737 11939 23737 11939 23738 11927 23738 11928 23738 11939 23739 11928 23739 11944 23739 11944 23740 11928 23740 11940 23740 11940 23741 11928 23741 11929 23741 11940 23742 11929 23742 11948 23742 11948 23743 11929 23743 11941 23743 11948 23744 11941 23744 11946 23744 11946 23745 11941 23745 11931 23745 11946 23746 11931 23746 16412 23746 16338 23747 11932 23747 16337 23747 16337 23748 11932 23748 11935 23748 16337 23749 11935 23749 16336 23749 11935 23750 11936 23750 16336 23750 16336 23751 11936 23751 11937 23751 16336 23752 11937 23752 11943 23752 11943 23753 11937 23753 11942 23753 11942 23754 11939 23754 11943 23754 11943 23755 11939 23755 11944 23755 11943 23756 11944 23756 11945 23756 16412 23757 16411 23757 11946 23757 11946 23758 16411 23758 11947 23758 11946 23759 11947 23759 11948 23759 11948 23760 11947 23760 11945 23760 11948 23761 11945 23761 11940 23761 11940 23762 11945 23762 11944 23762 11954 23763 13688 23763 11955 23763 11955 23764 13688 23764 13686 23764 11955 23765 13686 23765 11949 23765 11949 23766 13686 23766 11950 23766 11949 23767 11950 23767 11958 23767 11958 23768 11950 23768 13684 23768 11958 23769 13684 23769 11951 23769 11951 23770 13684 23770 13683 23770 11951 23771 13683 23771 11961 23771 11961 23772 13683 23772 11952 23772 11961 23773 11952 23773 11962 23773 11962 23774 11952 23774 13697 23774 11962 23775 13697 23775 11953 23775 11953 23776 13697 23776 13696 23776 16407 23777 11954 23777 11955 23777 16407 23778 11955 23778 11964 23778 11964 23779 11955 23779 11949 23779 11964 23780 11949 23780 11956 23780 11956 23781 11949 23781 11957 23781 11957 23782 11949 23782 11958 23782 11957 23783 11958 23783 11965 23783 11965 23784 11958 23784 11959 23784 11959 23785 11958 23785 11951 23785 11959 23786 11951 23786 11960 23786 11960 23787 11951 23787 11970 23787 11970 23788 11951 23788 11961 23788 11970 23789 11961 23789 11968 23789 11968 23790 11961 23790 11962 23790 11968 23791 11962 23791 11966 23791 11966 23792 11962 23792 11953 23792 11966 23793 11953 23793 16399 23793 16317 23794 16407 23794 11963 23794 11963 23795 16407 23795 11964 23795 11963 23796 11964 23796 16316 23796 11964 23797 11956 23797 16316 23797 16316 23798 11956 23798 11957 23798 16316 23799 11957 23799 16315 23799 16315 23800 11957 23800 11965 23800 11965 23801 11959 23801 16315 23801 16315 23802 11959 23802 11960 23802 16315 23803 11960 23803 11969 23803 16399 23804 16387 23804 11966 23804 11966 23805 16387 23805 11967 23805 11966 23806 11967 23806 11968 23806 11968 23807 11967 23807 11969 23807 11968 23808 11969 23808 11970 23808 11970 23809 11969 23809 11960 23809 16386 23810 11971 23810 11972 23810 11972 23811 11971 23811 15797 23811 11972 23812 15797 23812 11984 23812 11984 23813 15797 23813 11973 23813 11984 23814 11973 23814 11974 23814 11974 23815 11973 23815 15796 23815 11974 23816 15796 23816 11975 23816 11975 23817 15796 23817 16153 23817 11975 23818 16153 23818 11976 23818 11976 23819 16153 23819 11977 23819 11976 23820 11977 23820 11978 23820 11978 23821 11977 23821 11980 23821 11978 23822 11980 23822 11979 23822 11979 23823 11980 23823 16376 23823 16375 23824 16386 23824 11981 23824 11981 23825 16386 23825 11972 23825 11981 23826 11972 23826 11982 23826 11982 23827 11972 23827 11984 23827 11982 23828 11984 23828 11983 23828 11983 23829 11984 23829 11974 23829 11983 23830 11974 23830 11985 23830 11985 23831 11974 23831 11975 23831 11985 23832 11975 23832 11986 23832 11986 23833 11975 23833 11976 23833 11986 23834 11976 23834 11987 23834 11987 23835 11976 23835 11978 23835 11987 23836 11978 23836 16372 23836 16372 23837 11978 23837 11979 23837 16359 23838 16361 23838 11988 23838 11988 23839 16361 23839 15807 23839 11988 23840 15807 23840 11994 23840 11994 23841 15807 23841 11990 23841 11994 23842 11990 23842 11989 23842 11989 23843 11990 23843 15808 23843 11989 23844 15808 23844 11997 23844 11997 23845 15808 23845 11991 23845 11997 23846 11991 23846 11998 23846 11998 23847 11991 23847 11992 23847 11998 23848 11992 23848 16346 23848 16346 23849 11992 23849 15813 23849 16351 23850 16359 23850 11993 23850 11993 23851 16359 23851 11988 23851 11993 23852 11988 23852 16335 23852 16335 23853 11988 23853 11994 23853 16335 23854 11994 23854 11995 23854 11995 23855 11994 23855 11989 23855 11995 23856 11989 23856 11996 23856 11996 23857 11989 23857 11997 23857 11996 23858 11997 23858 16339 23858 16339 23859 11997 23859 11998 23859 16339 23860 11998 23860 16340 23860 16340 23861 11998 23861 16346 23861 12006 23862 15975 23862 12007 23862 12007 23863 15975 23863 12000 23863 12007 23864 12000 23864 11999 23864 11999 23865 12000 23865 12002 23865 11999 23866 12002 23866 12001 23866 12001 23867 12002 23867 15974 23867 12001 23868 15974 23868 12011 23868 12011 23869 15974 23869 12003 23869 12011 23870 12003 23870 12012 23870 12012 23871 12003 23871 12004 23871 12012 23872 12004 23872 16328 23872 16328 23873 12004 23873 15972 23873 12005 23874 12006 23874 16313 23874 16313 23875 12006 23875 12007 23875 16313 23876 12007 23876 16314 23876 16314 23877 12007 23877 11999 23877 16314 23878 11999 23878 12008 23878 12008 23879 11999 23879 12001 23879 12008 23880 12001 23880 12009 23880 12009 23881 12001 23881 12011 23881 12009 23882 12011 23882 12010 23882 12010 23883 12011 23883 12012 23883 12010 23884 12012 23884 16319 23884 16319 23885 12012 23885 16328 23885 16307 23886 12013 23886 18592 23886 18592 23887 12013 23887 12014 23887 18592 23888 12014 23888 12015 23888 12015 23889 12014 23889 12016 23889 12015 23890 12016 23890 12017 23890 12017 23891 12016 23891 16160 23891 12017 23892 16160 23892 18590 23892 18590 23893 16160 23893 12018 23893 18590 23894 12018 23894 12019 23894 12019 23895 12018 23895 15993 23895 12019 23896 15993 23896 12020 23896 12020 23897 15993 23897 12021 23897 16300 23898 16301 23898 18597 23898 18597 23899 16301 23899 12022 23899 18597 23900 12022 23900 12024 23900 12024 23901 12022 23901 12023 23901 12024 23902 12023 23902 18599 23902 18599 23903 12023 23903 15829 23903 18599 23904 15829 23904 12025 23904 12025 23905 15829 23905 12026 23905 12025 23906 12026 23906 18600 23906 18600 23907 12026 23907 15826 23907 18600 23908 15826 23908 12027 23908 12027 23909 15826 23909 15827 23909 16294 23910 16295 23910 12028 23910 12028 23911 16295 23911 12029 23911 12028 23912 12029 23912 18602 23912 18602 23913 12029 23913 15982 23913 18602 23914 15982 23914 18603 23914 18603 23915 15982 23915 12030 23915 18603 23916 12030 23916 12031 23916 12031 23917 12030 23917 12032 23917 12031 23918 12032 23918 12033 23918 12033 23919 12032 23919 15981 23919 12033 23920 15981 23920 18606 23920 18606 23921 15981 23921 12034 23921 18606 23922 12034 23922 12035 23922 12035 23923 12034 23923 16289 23923 12036 23924 12037 23924 18613 23924 18613 23925 12037 23925 12038 23925 18613 23926 12038 23926 18611 23926 18611 23927 12038 23927 16008 23927 18611 23928 16008 23928 18610 23928 18610 23929 16008 23929 12039 23929 18610 23930 12039 23930 12040 23930 12040 23931 12039 23931 16007 23931 12040 23932 16007 23932 12041 23932 12041 23933 16007 23933 12042 23933 12041 23934 12042 23934 18612 23934 18612 23935 12042 23935 16282 23935 18620 23936 12043 23936 12044 23936 12044 23937 12043 23937 15999 23937 12044 23938 15999 23938 12045 23938 12045 23939 15999 23939 12046 23939 12045 23940 12046 23940 18618 23940 18618 23941 12046 23941 15996 23941 18618 23942 15996 23942 12047 23942 12047 23943 15996 23943 12049 23943 12047 23944 12049 23944 12048 23944 12048 23945 12049 23945 16003 23945 12048 23946 16003 23946 18619 23946 18619 23947 16003 23947 16001 23947 16279 23948 16030 23948 18623 23948 18623 23949 16030 23949 16031 23949 18623 23950 16031 23950 18624 23950 18624 23951 16031 23951 16032 23951 18624 23952 16032 23952 12050 23952 12050 23953 16032 23953 12051 23953 12050 23954 12051 23954 12052 23954 12052 23955 12051 23955 12053 23955 12052 23956 12053 23956 18629 23956 18629 23957 12053 23957 12054 23957 18629 23958 12054 23958 12056 23958 12056 23959 12054 23959 12055 23959 12056 23960 12055 23960 12057 23960 12057 23961 12055 23961 16274 23961 16273 23962 16042 23962 12058 23962 12058 23963 16042 23963 12059 23963 12058 23964 12059 23964 18633 23964 18633 23965 12059 23965 16040 23965 18633 23966 16040 23966 18632 23966 18632 23967 16040 23967 16034 23967 18632 23968 16034 23968 18637 23968 18637 23969 16034 23969 12060 23969 18637 23970 12060 23970 18636 23970 18636 23971 12060 23971 16038 23971 18636 23972 16038 23972 18634 23972 18634 23973 16038 23973 12061 23973 16267 23974 16268 23974 12063 23974 12063 23975 16268 23975 12062 23975 12063 23976 12062 23976 12064 23976 12064 23977 12062 23977 16045 23977 12064 23978 16045 23978 12065 23978 12065 23979 16045 23979 12066 23979 12065 23980 12066 23980 18641 23980 18641 23981 12066 23981 15918 23981 18641 23982 15918 23982 18638 23982 18638 23983 15918 23983 15916 23983 18638 23984 15916 23984 12067 23984 12067 23985 15916 23985 12068 23985 12069 23986 12070 23986 18644 23986 18644 23987 12070 23987 12071 23987 18644 23988 12071 23988 18645 23988 18645 23989 12071 23989 12072 23989 18645 23990 12072 23990 12073 23990 12073 23991 12072 23991 16065 23991 12073 23992 16065 23992 18646 23992 18646 23993 16065 23993 12074 23993 18646 23994 12074 23994 18643 23994 18643 23995 12074 23995 16063 23995 18643 23996 16063 23996 12075 23996 12075 23997 16063 23997 16062 23997 18649 23998 12076 23998 12077 23998 12077 23999 12076 23999 12078 23999 12077 24000 12078 24000 18652 24000 18652 24001 12078 24001 12079 24001 18652 24002 12079 24002 12080 24002 12080 24003 12079 24003 12081 24003 12080 24004 12081 24004 18653 24004 18653 24005 12081 24005 16071 24005 18653 24006 16071 24006 12082 24006 12082 24007 16071 24007 16076 24007 12082 24008 16076 24008 12083 24008 12083 24009 16076 24009 16074 24009 15820 24010 12084 24010 12085 24010 12085 24011 12129 24011 15820 24011 15820 24012 12129 24012 12086 24012 15820 24013 12086 24013 15822 24013 12086 24014 12087 24014 15822 24014 15822 24015 12087 24015 12130 24015 15822 24016 12130 24016 12088 24016 12130 24017 12089 24017 12088 24017 12088 24018 12089 24018 12132 24018 12088 24019 12132 24019 15823 24019 15823 24020 12132 24020 12135 24020 15823 24021 12135 24021 12090 24021 12135 24022 12091 24022 12090 24022 12090 24023 12091 24023 12136 24023 12090 24024 12136 24024 12093 24024 12139 24025 15816 24025 12092 24025 12092 24026 15816 24026 12093 24026 12092 24027 12093 24027 12137 24027 12137 24028 12093 24028 12136 24028 16244 24029 12145 24029 12094 24029 12094 24030 12145 24030 12095 24030 12094 24031 12095 24031 12096 24031 12095 24032 12097 24032 12096 24032 12096 24033 12097 24033 12098 24033 12096 24034 12098 24034 12100 24034 12100 24035 12098 24035 12099 24035 12099 24036 12146 24036 12100 24036 12100 24037 12146 24037 12101 24037 12100 24038 12101 24038 15825 24038 16238 24039 15835 24039 12102 24039 12102 24040 15835 24040 15815 24040 12102 24041 15815 24041 12103 24041 12103 24042 15815 24042 15825 24042 12103 24043 15825 24043 12148 24043 12148 24044 15825 24044 12101 24044 15809 24045 12104 24045 12105 24045 12105 24046 12157 24046 15809 24046 15809 24047 12157 24047 12158 24047 15809 24048 12158 24048 12106 24048 12158 24049 12159 24049 12106 24049 12106 24050 12159 24050 12107 24050 12106 24051 12107 24051 15810 24051 15810 24052 12107 24052 12108 24052 15810 24053 12108 24053 15811 24053 12108 24054 12161 24054 15811 24054 15811 24055 12161 24055 12162 24055 15811 24056 12162 24056 12109 24056 12162 24057 12164 24057 12109 24057 12109 24058 12164 24058 12166 24058 12109 24059 12166 24059 12112 24059 16177 24060 12110 24060 12167 24060 12167 24061 12110 24061 12112 24061 12167 24062 12112 24062 12111 24062 12111 24063 12112 24063 12166 24063 16102 24064 16226 24064 16225 24064 16225 24065 12177 24065 16102 24065 16102 24066 12177 24066 12113 24066 16102 24067 12113 24067 12114 24067 12113 24068 12179 24068 12114 24068 12114 24069 12179 24069 12115 24069 12114 24070 12115 24070 12116 24070 12115 24071 12180 24071 12116 24071 12116 24072 12180 24072 12118 24072 12116 24073 12118 24073 12117 24073 12117 24074 12118 24074 12183 24074 12117 24075 12183 24075 15857 24075 12183 24076 12119 24076 15857 24076 15857 24077 12119 24077 12120 24077 15857 24078 12120 24078 12121 24078 16218 24079 16216 24079 12185 24079 12185 24080 16216 24080 12121 24080 12185 24081 12121 24081 12184 24081 12184 24082 12121 24082 12120 24082 12128 24083 16215 24083 12122 24083 12122 24084 16215 24084 12123 24084 12122 24085 12123 24085 12131 24085 12131 24086 12123 24086 13634 24086 12131 24087 13634 24087 12133 24087 12133 24088 13634 24088 12124 24088 12133 24089 12124 24089 12134 24089 12134 24090 12124 24090 12125 24090 12134 24091 12125 24091 12126 24091 12126 24092 12125 24092 12127 24092 12126 24093 12127 24093 12138 24093 12138 24094 12127 24094 13632 24094 12085 24095 12128 24095 12129 24095 12129 24096 12128 24096 12122 24096 12129 24097 12122 24097 12086 24097 12086 24098 12122 24098 12087 24098 12087 24099 12122 24099 12131 24099 12087 24100 12131 24100 12130 24100 12130 24101 12131 24101 12089 24101 12089 24102 12131 24102 12133 24102 12089 24103 12133 24103 12132 24103 12132 24104 12133 24104 12135 24104 12135 24105 12133 24105 12134 24105 12135 24106 12134 24106 12091 24106 12091 24107 12134 24107 12136 24107 12136 24108 12134 24108 12126 24108 12136 24109 12126 24109 12137 24109 12137 24110 12126 24110 12092 24110 12092 24111 12126 24111 12138 24111 12092 24112 12138 24112 12139 24112 16200 24113 13646 24113 12140 24113 12140 24114 13646 24114 13645 24114 12140 24115 13645 24115 12141 24115 12141 24116 13645 24116 12142 24116 12141 24117 12142 24117 12147 24117 12147 24118 12142 24118 13643 24118 12147 24119 13643 24119 12143 24119 12143 24120 13643 24120 13641 24120 12143 24121 13641 24121 12149 24121 12149 24122 13641 24122 13656 24122 12149 24123 13656 24123 12150 24123 12150 24124 13656 24124 12144 24124 12150 24125 12144 24125 12151 24125 12151 24126 12144 24126 16201 24126 12145 24127 16200 24127 12140 24127 12145 24128 12140 24128 12095 24128 12095 24129 12140 24129 12141 24129 12095 24130 12141 24130 12097 24130 12097 24131 12141 24131 12098 24131 12098 24132 12141 24132 12147 24132 12098 24133 12147 24133 12099 24133 12099 24134 12147 24134 12146 24134 12146 24135 12147 24135 12143 24135 12146 24136 12143 24136 12101 24136 12101 24137 12143 24137 12148 24137 12148 24138 12143 24138 12149 24138 12148 24139 12149 24139 12103 24139 12103 24140 12149 24140 12150 24140 12103 24141 12150 24141 12102 24141 12102 24142 12150 24142 12151 24142 12102 24143 12151 24143 16238 24143 12156 24144 16188 24144 12152 24144 12152 24145 16188 24145 13659 24145 12152 24146 13659 24146 12153 24146 12153 24147 13659 24147 13657 24147 12153 24148 13657 24148 12160 24148 12160 24149 13657 24149 12154 24149 12160 24150 12154 24150 12163 24150 12163 24151 12154 24151 13668 24151 12163 24152 13668 24152 12165 24152 12165 24153 13668 24153 12155 24153 12165 24154 12155 24154 12168 24154 12168 24155 12155 24155 13667 24155 12105 24156 12156 24156 12157 24156 12157 24157 12156 24157 12152 24157 12157 24158 12152 24158 12158 24158 12158 24159 12152 24159 12159 24159 12159 24160 12152 24160 12153 24160 12159 24161 12153 24161 12107 24161 12107 24162 12153 24162 12108 24162 12108 24163 12153 24163 12160 24163 12108 24164 12160 24164 12161 24164 12161 24165 12160 24165 12162 24165 12162 24166 12160 24166 12163 24166 12162 24167 12163 24167 12164 24167 12164 24168 12163 24168 12166 24168 12166 24169 12163 24169 12165 24169 12166 24170 12165 24170 12111 24170 12111 24171 12165 24171 12167 24171 12167 24172 12165 24172 12168 24172 12167 24173 12168 24173 16177 24173 12176 24174 12169 24174 12178 24174 12178 24175 12169 24175 12170 24175 12178 24176 12170 24176 12181 24176 12181 24177 12170 24177 12171 24177 12181 24178 12171 24178 12182 24178 12182 24179 12171 24179 13678 24179 12182 24180 13678 24180 12172 24180 12172 24181 13678 24181 12174 24181 12172 24182 12174 24182 12173 24182 12173 24183 12174 24183 12175 24183 12173 24184 12175 24184 16164 24184 16164 24185 12175 24185 13674 24185 16225 24186 12176 24186 12177 24186 12177 24187 12176 24187 12178 24187 12177 24188 12178 24188 12113 24188 12113 24189 12178 24189 12179 24189 12179 24190 12178 24190 12181 24190 12179 24191 12181 24191 12115 24191 12115 24192 12181 24192 12180 24192 12180 24193 12181 24193 12182 24193 12180 24194 12182 24194 12118 24194 12118 24195 12182 24195 12183 24195 12183 24196 12182 24196 12172 24196 12183 24197 12172 24197 12119 24197 12119 24198 12172 24198 12120 24198 12120 24199 12172 24199 12173 24199 12120 24200 12173 24200 12184 24200 12184 24201 12173 24201 12185 24201 12185 24202 12173 24202 16164 24202 12185 24203 16164 24203 16218 24203 12186 24204 15728 24204 12187 24204 12186 24205 12187 24205 12188 24205 12188 24206 12187 24206 15953 24206 12188 24207 15953 24207 10715 24207 10715 24208 15953 24208 12189 24208 10715 24209 12189 24209 10717 24209 10717 24210 12189 24210 12191 24210 10717 24211 12191 24211 12190 24211 12190 24212 12191 24212 12192 24212 12190 24213 12192 24213 10720 24213 10720 24214 12192 24214 12193 24214 10720 24215 12193 24215 10722 24215 10722 24216 12193 24216 15957 24216 10722 24217 15957 24217 17247 24217 15717 24218 15716 24218 10749 24218 15717 24219 10749 24219 11243 24219 11243 24220 10749 24220 12195 24220 11243 24221 12195 24221 12194 24221 12194 24222 12195 24222 10746 24222 12194 24223 10746 24223 11245 24223 11245 24224 10746 24224 10744 24224 11245 24225 10744 24225 11247 24225 11247 24226 10744 24226 10743 24226 11247 24227 10743 24227 11249 24227 11249 24228 10743 24228 10742 24228 11249 24229 10742 24229 11250 24229 11250 24230 10742 24230 10740 24230 11250 24231 10740 24231 12196 24231 12196 24232 10740 24232 10738 24232 12196 24233 10738 24233 12197 24233 12197 24234 10738 24234 10737 24234 12197 24235 10737 24235 12198 24235 12198 24236 10737 24236 10736 24236 12198 24237 10736 24237 12199 24237 12199 24238 10736 24238 10735 24238 12199 24239 10735 24239 12200 24239 12200 24240 10735 24240 10734 24240 12200 24241 10734 24241 11255 24241 11255 24242 10734 24242 12201 24242 11255 24243 12201 24243 12202 24243 12202 24244 12201 24244 12203 24244 12202 24245 12203 24245 11258 24245 11258 24246 12203 24246 10731 24246 11258 24247 10731 24247 12204 24247 12204 24248 10731 24248 10728 24248 12204 24249 10728 24249 12205 24249 12205 24250 10728 24250 12206 24250 12205 24251 12206 24251 11261 24251 11261 24252 12206 24252 10726 24252 11261 24253 10726 24253 11262 24253 11262 24254 10726 24254 10725 24254 11262 24255 10725 24255 11263 24255 18158 24256 17364 24256 12207 24256 18158 24257 12207 24257 11049 24257 11049 24258 12207 24258 12208 24258 11049 24259 12208 24259 11051 24259 11051 24260 12208 24260 11241 24260 11051 24261 11241 24261 12209 24261 12209 24262 11241 24262 12210 24262 12209 24263 12210 24263 11054 24263 11054 24264 12210 24264 12211 24264 11054 24265 12211 24265 11056 24265 11056 24266 12211 24266 11239 24266 11056 24267 11239 24267 11058 24267 11058 24268 11239 24268 11236 24268 11058 24269 11236 24269 11059 24269 11059 24270 11236 24270 12213 24270 11059 24271 12213 24271 12212 24271 12212 24272 12213 24272 11235 24272 12212 24273 11235 24273 12214 24273 12214 24274 11235 24274 11233 24274 12214 24275 11233 24275 12215 24275 12215 24276 11233 24276 12216 24276 12215 24277 12216 24277 11060 24277 11060 24278 12216 24278 12217 24278 11060 24279 12217 24279 12218 24279 12218 24280 12217 24280 12219 24280 12218 24281 12219 24281 11062 24281 11062 24282 12219 24282 11229 24282 11062 24283 11229 24283 12220 24283 12220 24284 11229 24284 12221 24284 12220 24285 12221 24285 12222 24285 12222 24286 12221 24286 12223 24286 12222 24287 12223 24287 12224 24287 12224 24288 12223 24288 12226 24288 12224 24289 12226 24289 12225 24289 12225 24290 12226 24290 11225 24290 12225 24291 11225 24291 11065 24291 11065 24292 11225 24292 12227 24292 11065 24293 12227 24293 11066 24293 18196 24294 11047 24294 12228 24294 18196 24295 12228 24295 11010 24295 11010 24296 12228 24296 11045 24296 11010 24297 11045 24297 12229 24297 12229 24298 11045 24298 12230 24298 12229 24299 12230 24299 11013 24299 11013 24300 12230 24300 12231 24300 11013 24301 12231 24301 12232 24301 12232 24302 12231 24302 11042 24302 12232 24303 11042 24303 12233 24303 12233 24304 11042 24304 11040 24304 12233 24305 11040 24305 12234 24305 12234 24306 11040 24306 11039 24306 12234 24307 11039 24307 11016 24307 11016 24308 11039 24308 11037 24308 11016 24309 11037 24309 11017 24309 11017 24310 11037 24310 12235 24310 11017 24311 12235 24311 12236 24311 12236 24312 12235 24312 12237 24312 12236 24313 12237 24313 11021 24313 11021 24314 12237 24314 12238 24314 11021 24315 12238 24315 12239 24315 12239 24316 12238 24316 12240 24316 12239 24317 12240 24317 11022 24317 11022 24318 12240 24318 11033 24318 11022 24319 11033 24319 11023 24319 11023 24320 11033 24320 11032 24320 11023 24321 11032 24321 12242 24321 12242 24322 11032 24322 12241 24322 12242 24323 12241 24323 11026 24323 11026 24324 12241 24324 11030 24324 11026 24325 11030 24325 11027 24325 11027 24326 11030 24326 11028 24326 11027 24327 11028 24327 12243 24327 12243 24328 11028 24328 12244 24328 12243 24329 12244 24329 12245 24329 12245 24330 12244 24330 15670 24330 12245 24331 15670 24331 15672 24331 12246 24332 11008 24332 11007 24332 12246 24333 11007 24333 10977 24333 10977 24334 11007 24334 11006 24334 10977 24335 11006 24335 12247 24335 12247 24336 11006 24336 12249 24336 12247 24337 12249 24337 12248 24337 12248 24338 12249 24338 12250 24338 12248 24339 12250 24339 12252 24339 12252 24340 12250 24340 12251 24340 12252 24341 12251 24341 12253 24341 12253 24342 12251 24342 12254 24342 12253 24343 12254 24343 12255 24343 12255 24344 12254 24344 11003 24344 12255 24345 11003 24345 12256 24345 12256 24346 11003 24346 12258 24346 12256 24347 12258 24347 12257 24347 12257 24348 12258 24348 12259 24348 12257 24349 12259 24349 12260 24349 12260 24350 12259 24350 12261 24350 12260 24351 12261 24351 10982 24351 10982 24352 12261 24352 12263 24352 10982 24353 12263 24353 12262 24353 12262 24354 12263 24354 12264 24354 12262 24355 12264 24355 10984 24355 10984 24356 12264 24356 10998 24356 10984 24357 10998 24357 12265 24357 12265 24358 10998 24358 10997 24358 12265 24359 10997 24359 10985 24359 10985 24360 10997 24360 12266 24360 10985 24361 12266 24361 10986 24361 10986 24362 12266 24362 12267 24362 10986 24363 12267 24363 10987 24363 10987 24364 12267 24364 10994 24364 10987 24365 10994 24365 12268 24365 12268 24366 10994 24366 12269 24366 12268 24367 12269 24367 12270 24367 12270 24368 12269 24368 10991 24368 12270 24369 10991 24369 10989 24369 12271 24370 10976 24370 10975 24370 12271 24371 10975 24371 12272 24371 12272 24372 10975 24372 12273 24372 12272 24373 12273 24373 12274 24373 12274 24374 12273 24374 10974 24374 12274 24375 10974 24375 12275 24375 12275 24376 10974 24376 10973 24376 12275 24377 10973 24377 12277 24377 12277 24378 10973 24378 12276 24378 12277 24379 12276 24379 10946 24379 10946 24380 12276 24380 12278 24380 10946 24381 12278 24381 12279 24381 12279 24382 12278 24382 12280 24382 12279 24383 12280 24383 12281 24383 12281 24384 12280 24384 10967 24384 12281 24385 10967 24385 12282 24385 12282 24386 10967 24386 12283 24386 12282 24387 12283 24387 12284 24387 12284 24388 12283 24388 12286 24388 12284 24389 12286 24389 12285 24389 12285 24390 12286 24390 12287 24390 12285 24391 12287 24391 12288 24391 12288 24392 12287 24392 10962 24392 12288 24393 10962 24393 12289 24393 12289 24394 10962 24394 10961 24394 12289 24395 10961 24395 10949 24395 10949 24396 10961 24396 12290 24396 10949 24397 12290 24397 10951 24397 10951 24398 12290 24398 12291 24398 10951 24399 12291 24399 12292 24399 12292 24400 12291 24400 10958 24400 12292 24401 10958 24401 10953 24401 10953 24402 10958 24402 10957 24402 10953 24403 10957 24403 12293 24403 12293 24404 10957 24404 12294 24404 12293 24405 12294 24405 10955 24405 10955 24406 12294 24406 12295 24406 10955 24407 12295 24407 15643 24407 18319 24408 12296 24408 12297 24408 18319 24409 12297 24409 10907 24409 10907 24410 12297 24410 12298 24410 10907 24411 12298 24411 10908 24411 10908 24412 12298 24412 12299 24412 10908 24413 12299 24413 12300 24413 12300 24414 12299 24414 10941 24414 12300 24415 10941 24415 12301 24415 12301 24416 10941 24416 10940 24416 12301 24417 10940 24417 10909 24417 10909 24418 10940 24418 10938 24418 10909 24419 10938 24419 12303 24419 12303 24420 10938 24420 12302 24420 12303 24421 12302 24421 12304 24421 12304 24422 12302 24422 12305 24422 12304 24423 12305 24423 10912 24423 10912 24424 12305 24424 10935 24424 10912 24425 10935 24425 10914 24425 10914 24426 10935 24426 12307 24426 10914 24427 12307 24427 12306 24427 12306 24428 12307 24428 12308 24428 12306 24429 12308 24429 12309 24429 12309 24430 12308 24430 12311 24430 12309 24431 12311 24431 12310 24431 12310 24432 12311 24432 12312 24432 12310 24433 12312 24433 12313 24433 12313 24434 12312 24434 12315 24434 12313 24435 12315 24435 12314 24435 12314 24436 12315 24436 12316 24436 12314 24437 12316 24437 10919 24437 10919 24438 12316 24438 10928 24438 10919 24439 10928 24439 10920 24439 10920 24440 10928 24440 10926 24440 10920 24441 10926 24441 12317 24441 12317 24442 10926 24442 10924 24442 12317 24443 10924 24443 10922 24443 10922 24444 10924 24444 10923 24444 10922 24445 10923 24445 18295 24445 18351 24446 15625 24446 10904 24446 18351 24447 10904 24447 12318 24447 12318 24448 10904 24448 12320 24448 12318 24449 12320 24449 12319 24449 12319 24450 12320 24450 10903 24450 12319 24451 10903 24451 12321 24451 12321 24452 10903 24452 12322 24452 12321 24453 12322 24453 12323 24453 12323 24454 12322 24454 10901 24454 12323 24455 10901 24455 12324 24455 12324 24456 10901 24456 12325 24456 12324 24457 12325 24457 12326 24457 12326 24458 12325 24458 10898 24458 12326 24459 10898 24459 10881 24459 10881 24460 10898 24460 12327 24460 10881 24461 12327 24461 12328 24461 12328 24462 12327 24462 12329 24462 12328 24463 12329 24463 10883 24463 10883 24464 12329 24464 12331 24464 10883 24465 12331 24465 12330 24465 12330 24466 12331 24466 10896 24466 12330 24467 10896 24467 12332 24467 12332 24468 10896 24468 12333 24468 12332 24469 12333 24469 12334 24469 12334 24470 12333 24470 12335 24470 12334 24471 12335 24471 12336 24471 12336 24472 12335 24472 12338 24472 12336 24473 12338 24473 12337 24473 12337 24474 12338 24474 10893 24474 12337 24475 10893 24475 12339 24475 12339 24476 10893 24476 12340 24476 12339 24477 12340 24477 12341 24477 12341 24478 12340 24478 10892 24478 12341 24479 10892 24479 12342 24479 12342 24480 10892 24480 10891 24480 12342 24481 10891 24481 12343 24481 12343 24482 10891 24482 10890 24482 12343 24483 10890 24483 15605 24483 18394 24484 10876 24484 10875 24484 18394 24485 10875 24485 10837 24485 10837 24486 10875 24486 12344 24486 10837 24487 12344 24487 10839 24487 10839 24488 12344 24488 10873 24488 10839 24489 10873 24489 12345 24489 12345 24490 10873 24490 12346 24490 12345 24491 12346 24491 12347 24491 12347 24492 12346 24492 12349 24492 12347 24493 12349 24493 12348 24493 12348 24494 12349 24494 12350 24494 12348 24495 12350 24495 12351 24495 12351 24496 12350 24496 12352 24496 12351 24497 12352 24497 10843 24497 10843 24498 12352 24498 10868 24498 10843 24499 10868 24499 10845 24499 10845 24500 10868 24500 12353 24500 10845 24501 12353 24501 12354 24501 12354 24502 12353 24502 10866 24502 12354 24503 10866 24503 12355 24503 12355 24504 10866 24504 12356 24504 12355 24505 12356 24505 10848 24505 10848 24506 12356 24506 10865 24506 10848 24507 10865 24507 12357 24507 12357 24508 10865 24508 12358 24508 12357 24509 12358 24509 12359 24509 12359 24510 12358 24510 12360 24510 12359 24511 12360 24511 10850 24511 10850 24512 12360 24512 10862 24512 10850 24513 10862 24513 10851 24513 10851 24514 10862 24514 10861 24514 10851 24515 10861 24515 10852 24515 10852 24516 10861 24516 12361 24516 10852 24517 12361 24517 10854 24517 10854 24518 12361 24518 10859 24518 10854 24519 10859 24519 10855 24519 10855 24520 10859 24520 18371 24520 10855 24521 18371 24521 15587 24521 12363 24522 12362 24522 10796 24522 12363 24523 10796 24523 12364 24523 12364 24524 10796 24524 10795 24524 12364 24525 10795 24525 10752 24525 10752 24526 10795 24526 12365 24526 10752 24527 12365 24527 10753 24527 10753 24528 12365 24528 12366 24528 10753 24529 12366 24529 10754 24529 10754 24530 12366 24530 12367 24530 10754 24531 12367 24531 10758 24531 10758 24532 12367 24532 10793 24532 10758 24533 10793 24533 10756 24533 10756 24534 10793 24534 10792 24534 10756 24535 10792 24535 10760 24535 10760 24536 10792 24536 10791 24536 10760 24537 10791 24537 10762 24537 10762 24538 10791 24538 10790 24538 10762 24539 10790 24539 12368 24539 12368 24540 10790 24540 12369 24540 12368 24541 12369 24541 12370 24541 12370 24542 12369 24542 12371 24542 12370 24543 12371 24543 10764 24543 10764 24544 12371 24544 10786 24544 10764 24545 10786 24545 10767 24545 10767 24546 10786 24546 10785 24546 10767 24547 10785 24547 12372 24547 12372 24548 10785 24548 12374 24548 12372 24549 12374 24549 12373 24549 12373 24550 12374 24550 10782 24550 12373 24551 10782 24551 10772 24551 10772 24552 10782 24552 12375 24552 10772 24553 12375 24553 10774 24553 10774 24554 12375 24554 10779 24554 10774 24555 10779 24555 10776 24555 10776 24556 10779 24556 12377 24556 10776 24557 12377 24557 12376 24557 12376 24558 12377 24558 10778 24558 12376 24559 10778 24559 12378 24559 12379 24560 10836 24560 12380 24560 12379 24561 12380 24561 12381 24561 12381 24562 12380 24562 10833 24562 12381 24563 10833 24563 10799 24563 10799 24564 10833 24564 10831 24564 10799 24565 10831 24565 12382 24565 12382 24566 10831 24566 10830 24566 12382 24567 10830 24567 12383 24567 12383 24568 10830 24568 10829 24568 12383 24569 10829 24569 12384 24569 12384 24570 10829 24570 12386 24570 12384 24571 12386 24571 12385 24571 12385 24572 12386 24572 10825 24572 12385 24573 10825 24573 10800 24573 10800 24574 10825 24574 10824 24574 10800 24575 10824 24575 10802 24575 10802 24576 10824 24576 12388 24576 10802 24577 12388 24577 12387 24577 12387 24578 12388 24578 10822 24578 12387 24579 10822 24579 10804 24579 10804 24580 10822 24580 10821 24580 10804 24581 10821 24581 12389 24581 12389 24582 10821 24582 10819 24582 12389 24583 10819 24583 10806 24583 10806 24584 10819 24584 12390 24584 10806 24585 12390 24585 10807 24585 10807 24586 12390 24586 10817 24586 10807 24587 10817 24587 10808 24587 10808 24588 10817 24588 12392 24588 10808 24589 12392 24589 12391 24589 12391 24590 12392 24590 12393 24590 12391 24591 12393 24591 12395 24591 12395 24592 12393 24592 12394 24592 12395 24593 12394 24593 12396 24593 12396 24594 12394 24594 12397 24594 12396 24595 12397 24595 10812 24595 10812 24596 12397 24596 10814 24596 10812 24597 10814 24597 10813 24597 15492 24598 14476 24598 13292 24598 15492 24599 13292 24599 10748 24599 10748 24600 13292 24600 12398 24600 10748 24601 12398 24601 10747 24601 10747 24602 12398 24602 13294 24602 10747 24603 13294 24603 12399 24603 12399 24604 13294 24604 13296 24604 12399 24605 13296 24605 10745 24605 10745 24606 13296 24606 12400 24606 10745 24607 12400 24607 12402 24607 12402 24608 12400 24608 12401 24608 12402 24609 12401 24609 10741 24609 10741 24610 12401 24610 13299 24610 10741 24611 13299 24611 10739 24611 10739 24612 13299 24612 13301 24612 10739 24613 13301 24613 12403 24613 12403 24614 13301 24614 12404 24614 12403 24615 12404 24615 12405 24615 12405 24616 12404 24616 12407 24616 12405 24617 12407 24617 12406 24617 12406 24618 12407 24618 12408 24618 12406 24619 12408 24619 12409 24619 12409 24620 12408 24620 13304 24620 12409 24621 13304 24621 10733 24621 10733 24622 13304 24622 12410 24622 10733 24623 12410 24623 12412 24623 12412 24624 12410 24624 12411 24624 12412 24625 12411 24625 10732 24625 10732 24626 12411 24626 13306 24626 10732 24627 13306 24627 12413 24627 12413 24628 13306 24628 13307 24628 12413 24629 13307 24629 10730 24629 10730 24630 13307 24630 12414 24630 10730 24631 12414 24631 10729 24631 10729 24632 12414 24632 12415 24632 10729 24633 12415 24633 10727 24633 10727 24634 12415 24634 13311 24634 10727 24635 13311 24635 10724 24635 15478 24636 12416 24636 13321 24636 13321 24637 12416 24637 12417 24637 13321 24638 12417 24638 13322 24638 13322 24639 12417 24639 13323 24639 13323 24640 12417 24640 12418 24640 13323 24641 12418 24641 13318 24641 13318 24642 12418 24642 13320 24642 13320 24643 12418 24643 12419 24643 13320 24644 12419 24644 12420 24644 12420 24645 12419 24645 12421 24645 12421 24646 12419 24646 12422 24646 12421 24647 12422 24647 12423 24647 12423 24648 12422 24648 13315 24648 13315 24649 12422 24649 12424 24649 13315 24650 12424 24650 13316 24650 13316 24651 12424 24651 13312 24651 13312 24652 12424 24652 14285 24652 13312 24653 14285 24653 12425 24653 14020 24654 14293 24654 13324 24654 13324 24655 14293 24655 14399 24655 13324 24656 14399 24656 13326 24656 13326 24657 14399 24657 12426 24657 13326 24658 12426 24658 12427 24658 12427 24659 12426 24659 12428 24659 12427 24660 12428 24660 13327 24660 13327 24661 12428 24661 14030 24661 13327 24662 14030 24662 12429 24662 12429 24663 14030 24663 12430 24663 12429 24664 12430 24664 15464 24664 15464 24665 12430 24665 15466 24665 13328 24666 15463 24666 12431 24666 12431 24667 15463 24667 14299 24667 12431 24668 14299 24668 12433 24668 12433 24669 14299 24669 12432 24669 12433 24670 12432 24670 13330 24670 13330 24671 12432 24671 14302 24671 13330 24672 14302 24672 13333 24672 13333 24673 14302 24673 12434 24673 13333 24674 12434 24674 12435 24674 12435 24675 12434 24675 14307 24675 12435 24676 14307 24676 15459 24676 15459 24677 14307 24677 12436 24677 15457 24678 14268 24678 13337 24678 13337 24679 14268 24679 14267 24679 13337 24680 14267 24680 12437 24680 12437 24681 14267 24681 12439 24681 12437 24682 12439 24682 12438 24682 12438 24683 12439 24683 12440 24683 12438 24684 12440 24684 13338 24684 13338 24685 12440 24685 12441 24685 13338 24686 12441 24686 12442 24686 12442 24687 12441 24687 12444 24687 12442 24688 12444 24688 12443 24688 12443 24689 12444 24689 14271 24689 14003 24690 14279 24690 13340 24690 13340 24691 14279 24691 12445 24691 13340 24692 12445 24692 13342 24692 13342 24693 12445 24693 14277 24693 13342 24694 14277 24694 12446 24694 12446 24695 14277 24695 12447 24695 12446 24696 12447 24696 12448 24696 12448 24697 12447 24697 14274 24697 12448 24698 14274 24698 12449 24698 12449 24699 14274 24699 12450 24699 12449 24700 12450 24700 15447 24700 15447 24701 12450 24701 14401 24701 13346 24702 14244 24702 13347 24702 13347 24703 14244 24703 14254 24703 13347 24704 14254 24704 13349 24704 13349 24705 14254 24705 12451 24705 13349 24706 12451 24706 13350 24706 13350 24707 12451 24707 14250 24707 13350 24708 14250 24708 12452 24708 12452 24709 14250 24709 12453 24709 12452 24710 12453 24710 12454 24710 12454 24711 12453 24711 14032 24711 12454 24712 14032 24712 15438 24712 15438 24713 14032 24713 15439 24713 13355 24714 14355 24714 12455 24714 12455 24715 14355 24715 12456 24715 12455 24716 12456 24716 12457 24716 12457 24717 12456 24717 14351 24717 12457 24718 14351 24718 12458 24718 12458 24719 14351 24719 14350 24719 12458 24720 14350 24720 12459 24720 12459 24721 14350 24721 12460 24721 12459 24722 12460 24722 13357 24722 13357 24723 12460 24723 14353 24723 13357 24724 14353 24724 15431 24724 15431 24725 14353 24725 15432 24725 13972 24726 14366 24726 13359 24726 13359 24727 14366 24727 12461 24727 13359 24728 12461 24728 13363 24728 13363 24729 12461 24729 14365 24729 13363 24730 14365 24730 12462 24730 12462 24731 14365 24731 14364 24731 12462 24732 14364 24732 12463 24732 12463 24733 14364 24733 12465 24733 12463 24734 12465 24734 12464 24734 12464 24735 12465 24735 14362 24735 12464 24736 14362 24736 15423 24736 15423 24737 14362 24737 14361 24737 12466 24738 14432 24738 12467 24738 12467 24739 14432 24739 14323 24739 12467 24740 14323 24740 12468 24740 12468 24741 14323 24741 14322 24741 12468 24742 14322 24742 12469 24742 12469 24743 14322 24743 14327 24743 12469 24744 14327 24744 12470 24744 12470 24745 14327 24745 14326 24745 12470 24746 14326 24746 13369 24746 13369 24747 14326 24747 12471 24747 13369 24748 12471 24748 12472 24748 12472 24749 12471 24749 12473 24749 12474 24750 15413 24750 13370 24750 13370 24751 15413 24751 14329 24751 13370 24752 14329 24752 12475 24752 12475 24753 14329 24753 12476 24753 12475 24754 12476 24754 12477 24754 12477 24755 12476 24755 12478 24755 12477 24756 12478 24756 13371 24756 13371 24757 12478 24757 12479 24757 13371 24758 12479 24758 12481 24758 12481 24759 12479 24759 12480 24759 12481 24760 12480 24760 13962 24760 13962 24761 12480 24761 12482 24761 13573 24762 14478 24762 12483 24762 13573 24763 12483 24763 12485 24763 12485 24764 12483 24764 12484 24764 12485 24765 12484 24765 13576 24765 13576 24766 12484 24766 12486 24766 13576 24767 12486 24767 12487 24767 12487 24768 12486 24768 13290 24768 12487 24769 13290 24769 13578 24769 13578 24770 13290 24770 12488 24770 13578 24771 12488 24771 13579 24771 13579 24772 12488 24772 12489 24772 13579 24773 12489 24773 13581 24773 13581 24774 12489 24774 13287 24774 13581 24775 13287 24775 12490 24775 12490 24776 13287 24776 13286 24776 12490 24777 13286 24777 13584 24777 13584 24778 13286 24778 12491 24778 13584 24779 12491 24779 13585 24779 13585 24780 12491 24780 12492 24780 13585 24781 12492 24781 12494 24781 12494 24782 12492 24782 12493 24782 12494 24783 12493 24783 13588 24783 13588 24784 12493 24784 12495 24784 13588 24785 12495 24785 13589 24785 13589 24786 12495 24786 13282 24786 13589 24787 13282 24787 12496 24787 12496 24788 13282 24788 13281 24788 12496 24789 13281 24789 12497 24789 12497 24790 13281 24790 12498 24790 12497 24791 12498 24791 13593 24791 13593 24792 12498 24792 12499 24792 13593 24793 12499 24793 13594 24793 12500 24794 13310 24794 12503 24794 12507 24795 14139 24795 13308 24795 13308 24796 14139 24796 12501 24796 13308 24797 12501 24797 13309 24797 13309 24798 12501 24798 12502 24798 13309 24799 12502 24799 12503 24799 12503 24800 12502 24800 14314 24800 12503 24801 14314 24801 12500 24801 14129 24802 12504 24802 13305 24802 13305 24803 12504 24803 12505 24803 13305 24804 12505 24804 13308 24804 13308 24805 12505 24805 12506 24805 13308 24806 12506 24806 12507 24806 14129 24807 13305 24807 14124 24807 14124 24808 13305 24808 12510 24808 14124 24809 12510 24809 14125 24809 12508 24810 14118 24810 12509 24810 12509 24811 14118 24811 14119 24811 12509 24812 14119 24812 12510 24812 12510 24813 14119 24813 12511 24813 12510 24814 12511 24814 14125 24814 12516 24815 12513 24815 12512 24815 12512 24816 12513 24816 12509 24816 12509 24817 12513 24817 12514 24817 12509 24818 12514 24818 12508 24818 12517 24819 14147 24819 12518 24819 12518 24820 14147 24820 14031 24820 12518 24821 14031 24821 12512 24821 12512 24822 14031 24822 12515 24822 12512 24823 12515 24823 12516 24823 12517 24824 12518 24824 14289 24824 14289 24825 12518 24825 13303 24825 14289 24826 13303 24826 14288 24826 14288 24827 13303 24827 13302 24827 14288 24828 13302 24828 14287 24828 14287 24829 13302 24829 14283 24829 14283 24830 13302 24830 13300 24830 14283 24831 13300 24831 12519 24831 12519 24832 13300 24832 14103 24832 14103 24833 13300 24833 12520 24833 14103 24834 12520 24834 12521 24834 14278 24835 14281 24835 13298 24835 13298 24836 14281 24836 12522 24836 13298 24837 12522 24837 12520 24837 12520 24838 12522 24838 14280 24838 12520 24839 14280 24839 12521 24839 13297 24840 14076 24840 13298 24840 13298 24841 14076 24841 14077 24841 13298 24842 14077 24842 14278 24842 14098 24843 13297 24843 13295 24843 14098 24844 12523 24844 13297 24844 13297 24845 12523 24845 14089 24845 13297 24846 14089 24846 14076 24846 12530 24847 13295 24847 12529 24847 12530 24848 12524 24848 13295 24848 13295 24849 12524 24849 12525 24849 13295 24850 12525 24850 14098 24850 14261 24851 12526 24851 13293 24851 13293 24852 12526 24852 12527 24852 13293 24853 12527 24853 12529 24853 12529 24854 12527 24854 12528 24854 12529 24855 12528 24855 12530 24855 14261 24856 13293 24856 14260 24856 14260 24857 13293 24857 13291 24857 14260 24858 13291 24858 14084 24858 14084 24859 13291 24859 12531 24859 14084 24860 12531 24860 12532 24860 15367 24861 14198 24861 12540 24861 12540 24862 14198 24862 12533 24862 12540 24863 12533 24863 12534 24863 12534 24864 12533 24864 14196 24864 12534 24865 14196 24865 12542 24865 12542 24866 14196 24866 14207 24866 12542 24867 14207 24867 12543 24867 12543 24868 14207 24868 12535 24868 12543 24869 12535 24869 12544 24869 12544 24870 12535 24870 12536 24870 12544 24871 12536 24871 15361 24871 15361 24872 12536 24872 12537 24872 15349 24873 15367 24873 12538 24873 12538 24874 15367 24874 12540 24874 12538 24875 12540 24875 12539 24875 12539 24876 12540 24876 12534 24876 12539 24877 12534 24877 12541 24877 12541 24878 12534 24878 12542 24878 12541 24879 12542 24879 12547 24879 12547 24880 12542 24880 12543 24880 12547 24881 12543 24881 12546 24881 12546 24882 12543 24882 12544 24882 12546 24883 12544 24883 12545 24883 12545 24884 12544 24884 15361 24884 12545 24885 13919 24885 12546 24885 12546 24886 13919 24886 13921 24886 12546 24887 13921 24887 12547 24887 12547 24888 13921 24888 13913 24888 12547 24889 13913 24889 12541 24889 12541 24890 13913 24890 13914 24890 12541 24891 13914 24891 12539 24891 12539 24892 13914 24892 12548 24892 12539 24893 12548 24893 12538 24893 12538 24894 12548 24894 12549 24894 12538 24895 12549 24895 15349 24895 15349 24896 12549 24896 13915 24896 15340 24897 15342 24897 12550 24897 12550 24898 15342 24898 12551 24898 12550 24899 12551 24899 12552 24899 12552 24900 12551 24900 14225 24900 12552 24901 14225 24901 12554 24901 12554 24902 14225 24902 12553 24902 12554 24903 12553 24903 12562 24903 12562 24904 12553 24904 12555 24904 12562 24905 12555 24905 12557 24905 12557 24906 12555 24906 12556 24906 12557 24907 12556 24907 12565 24907 12565 24908 12556 24908 12558 24908 12565 24909 12558 24909 15333 24909 15333 24910 12558 24910 14221 24910 15332 24911 15340 24911 12559 24911 12559 24912 15340 24912 12550 24912 12559 24913 12550 24913 12567 24913 12567 24914 12550 24914 12552 24914 12567 24915 12552 24915 12560 24915 12560 24916 12552 24916 12554 24916 12560 24917 12554 24917 12561 24917 12561 24918 12554 24918 12562 24918 12561 24919 12562 24919 12563 24919 12563 24920 12562 24920 12557 24920 12563 24921 12557 24921 12564 24921 12564 24922 12557 24922 12565 24922 12564 24923 12565 24923 15326 24923 15326 24924 12565 24924 15333 24924 15326 24925 13907 24925 12564 24925 12564 24926 13907 24926 13908 24926 12564 24927 13908 24927 12563 24927 12563 24928 13908 24928 12566 24928 12563 24929 12566 24929 12561 24929 12561 24930 12566 24930 13910 24930 12561 24931 13910 24931 12560 24931 12560 24932 13910 24932 13911 24932 12560 24933 13911 24933 12567 24933 12567 24934 13911 24934 12568 24934 12567 24935 12568 24935 12559 24935 12559 24936 12568 24936 12569 24936 12559 24937 12569 24937 15332 24937 15332 24938 12569 24938 13901 24938 12574 24939 15320 24939 12576 24939 12576 24940 15320 24940 14213 24940 12576 24941 14213 24941 12570 24941 12570 24942 14213 24942 14211 24942 12570 24943 14211 24943 12578 24943 12578 24944 14211 24944 12571 24944 12578 24945 12571 24945 12579 24945 12579 24946 12571 24946 12572 24946 12579 24947 12572 24947 12582 24947 12582 24948 12572 24948 14210 24948 12582 24949 14210 24949 12573 24949 12573 24950 14210 24950 15316 24950 15301 24951 12574 24951 12575 24951 12575 24952 12574 24952 12576 24952 12575 24953 12576 24953 12577 24953 12577 24954 12576 24954 12570 24954 12577 24955 12570 24955 12584 24955 12584 24956 12570 24956 12578 24956 12584 24957 12578 24957 12583 24957 12583 24958 12578 24958 12579 24958 12583 24959 12579 24959 12580 24959 12580 24960 12579 24960 12582 24960 12580 24961 12582 24961 12581 24961 12581 24962 12582 24962 12573 24962 12581 24963 13888 24963 12580 24963 12580 24964 13888 24964 13889 24964 12580 24965 13889 24965 12583 24965 12583 24966 13889 24966 13890 24966 12583 24967 13890 24967 12584 24967 12584 24968 13890 24968 12585 24968 12584 24969 12585 24969 12577 24969 12577 24970 12585 24970 13892 24970 12577 24971 13892 24971 12575 24971 12575 24972 13892 24972 12586 24972 12575 24973 12586 24973 15301 24973 15301 24974 12586 24974 12587 24974 12588 24975 14235 24975 12589 24975 12589 24976 14235 24976 14234 24976 12589 24977 14234 24977 12590 24977 12590 24978 14234 24978 12591 24978 12590 24979 12591 24979 12597 24979 12597 24980 12591 24980 12592 24980 12597 24981 12592 24981 12598 24981 12598 24982 12592 24982 12593 24982 12598 24983 12593 24983 12594 24983 12594 24984 12593 24984 12595 24984 12594 24985 12595 24985 12600 24985 12600 24986 12595 24986 14232 24986 15284 24987 12588 24987 12596 24987 12596 24988 12588 24988 12589 24988 12596 24989 12589 24989 12604 24989 12604 24990 12589 24990 12590 24990 12604 24991 12590 24991 12603 24991 12603 24992 12590 24992 12597 24992 12603 24993 12597 24993 12602 24993 12602 24994 12597 24994 12598 24994 12602 24995 12598 24995 12599 24995 12599 24996 12598 24996 12594 24996 12599 24997 12594 24997 15287 24997 15287 24998 12594 24998 12600 24998 15287 24999 12601 24999 12599 24999 12599 25000 12601 25000 13886 25000 12599 25001 13886 25001 12602 25001 12602 25002 13886 25002 13874 25002 12602 25003 13874 25003 12603 25003 12603 25004 13874 25004 13876 25004 12603 25005 13876 25005 12604 25005 12604 25006 13876 25006 13877 25006 12604 25007 13877 25007 12596 25007 12596 25008 13877 25008 12605 25008 12596 25009 12605 25009 15284 25009 15284 25010 12605 25010 15285 25010 12696 25011 14195 25011 12606 25011 12606 25012 14195 25012 14208 25012 12606 25013 14208 25013 12698 25013 12698 25014 14208 25014 12608 25014 12698 25015 12608 25015 12607 25015 12607 25016 12608 25016 12609 25016 12607 25017 12609 25017 12700 25017 12700 25018 12609 25018 12610 25018 12700 25019 12610 25019 12611 25019 12611 25020 12610 25020 14204 25020 12611 25021 14204 25021 12612 25021 12612 25022 14204 25022 15276 25022 12701 25023 12613 25023 12615 25023 12615 25024 12613 25024 12614 25024 12615 25025 12614 25025 12616 25025 12616 25026 12614 25026 12617 25026 12616 25027 12617 25027 12703 25027 12703 25028 12617 25028 12618 25028 12703 25029 12618 25029 12704 25029 12704 25030 12618 25030 12619 25030 12704 25031 12619 25031 12706 25031 12706 25032 12619 25032 14226 25032 12706 25033 14226 25033 12708 25033 12708 25034 14226 25034 14222 25034 12708 25035 14222 25035 12620 25035 12620 25036 14222 25036 15266 25036 12711 25037 12710 25037 14241 25037 15261 25038 12622 25038 12621 25038 12621 25039 12622 25039 12623 25039 12621 25040 12623 25040 14237 25040 14237 25041 12623 25041 12624 25041 14237 25042 12624 25042 12625 25042 12625 25043 12624 25043 12716 25043 12625 25044 12716 25044 14236 25044 14236 25045 12716 25045 12715 25045 14236 25046 12715 25046 12626 25046 12626 25047 12715 25047 12713 25047 12626 25048 12713 25048 12627 25048 12627 25049 12713 25049 12711 25049 12627 25050 12711 25050 14240 25050 14240 25051 12711 25051 14241 25051 12635 25052 15260 25052 12628 25052 12628 25053 15260 25053 12629 25053 12628 25054 12629 25054 12630 25054 12630 25055 12629 25055 12631 25055 12630 25056 12631 25056 12632 25056 12632 25057 12631 25057 12633 25057 12632 25058 12633 25058 12638 25058 12638 25059 12633 25059 15196 25059 12638 25060 15196 25060 12634 25060 12634 25061 15196 25061 15197 25061 12634 25062 15197 25062 15252 25062 15252 25063 15197 25063 15199 25063 12644 25064 12635 25064 12643 25064 12643 25065 12635 25065 12628 25065 12643 25066 12628 25066 12636 25066 12636 25067 12628 25067 12630 25067 12636 25068 12630 25068 12637 25068 12637 25069 12630 25069 12632 25069 12637 25070 12632 25070 12640 25070 12640 25071 12632 25071 12638 25071 12640 25072 12638 25072 12639 25072 12639 25073 12638 25073 12634 25073 12639 25074 12634 25074 15250 25074 15250 25075 12634 25075 15252 25075 15250 25076 13954 25076 12639 25076 12639 25077 13954 25077 13955 25077 12639 25078 13955 25078 12640 25078 12640 25079 13955 25079 12641 25079 12640 25080 12641 25080 12637 25080 12637 25081 12641 25081 12642 25081 12637 25082 12642 25082 12636 25082 12636 25083 12642 25083 13945 25083 12636 25084 13945 25084 12643 25084 12643 25085 13945 25085 13946 25085 12643 25086 13946 25086 12644 25086 12644 25087 13946 25087 15243 25087 12645 25088 15179 25088 12646 25088 12646 25089 15179 25089 12647 25089 12646 25090 12647 25090 12655 25090 12655 25091 12647 25091 12648 25091 12655 25092 12648 25092 12657 25092 12657 25093 12648 25093 15168 25093 12657 25094 15168 25094 12649 25094 12649 25095 15168 25095 12651 25095 12649 25096 12651 25096 12650 25096 12650 25097 12651 25097 12652 25097 12650 25098 12652 25098 12658 25098 12658 25099 12652 25099 15170 25099 12658 25100 15170 25100 12653 25100 12653 25101 15170 25101 15171 25101 15236 25102 12645 25102 12665 25102 12665 25103 12645 25103 12646 25103 12665 25104 12646 25104 12654 25104 12654 25105 12646 25105 12655 25105 12654 25106 12655 25106 12663 25106 12663 25107 12655 25107 12657 25107 12663 25108 12657 25108 12656 25108 12656 25109 12657 25109 12649 25109 12656 25110 12649 25110 12661 25110 12661 25111 12649 25111 12650 25111 12661 25112 12650 25112 12659 25112 12659 25113 12650 25113 12658 25113 12659 25114 12658 25114 15229 25114 15229 25115 12658 25115 12653 25115 15229 25116 13940 25116 12659 25116 12659 25117 13940 25117 12660 25117 12659 25118 12660 25118 12661 25118 12661 25119 12660 25119 13943 25119 12661 25120 13943 25120 12656 25120 12656 25121 13943 25121 12662 25121 12656 25122 12662 25122 12663 25122 12663 25123 12662 25123 13932 25123 12663 25124 13932 25124 12654 25124 12654 25125 13932 25125 12664 25125 12654 25126 12664 25126 12665 25126 12665 25127 12664 25127 13934 25127 12665 25128 13934 25128 15236 25128 15236 25129 13934 25129 13935 25129 15222 25130 12666 25130 12667 25130 12667 25131 12666 25131 15156 25131 12667 25132 15156 25132 12668 25132 12668 25133 15156 25133 12669 25133 12668 25134 12669 25134 12670 25134 12670 25135 12669 25135 12671 25135 12670 25136 12671 25136 12678 25136 12678 25137 12671 25137 12672 25137 12678 25138 12672 25138 12679 25138 12679 25139 12672 25139 12673 25139 12679 25140 12673 25140 12680 25140 12680 25141 12673 25141 12674 25141 12680 25142 12674 25142 12682 25142 12682 25143 12674 25143 15147 25143 12675 25144 15222 25144 12667 25144 12675 25145 12667 25145 12685 25145 12685 25146 12667 25146 12668 25146 12685 25147 12668 25147 12676 25147 12676 25148 12668 25148 12687 25148 12687 25149 12668 25149 12670 25149 12687 25150 12670 25150 12688 25150 12688 25151 12670 25151 12690 25151 12690 25152 12670 25152 12678 25152 12690 25153 12678 25153 12677 25153 12677 25154 12678 25154 12694 25154 12694 25155 12678 25155 12679 25155 12694 25156 12679 25156 12681 25156 12681 25157 12679 25157 12680 25157 12681 25158 12680 25158 12692 25158 12692 25159 12680 25159 12682 25159 12692 25160 12682 25160 12683 25160 15208 25161 12675 25161 12684 25161 12684 25162 12675 25162 12685 25162 12684 25163 12685 25163 12686 25163 12685 25164 12676 25164 12686 25164 12686 25165 12676 25165 12687 25165 12686 25166 12687 25166 12689 25166 12689 25167 12687 25167 12688 25167 12688 25168 12690 25168 12689 25168 12689 25169 12690 25169 12677 25169 12689 25170 12677 25170 13925 25170 12683 25171 12691 25171 12692 25171 12692 25172 12691 25172 12693 25172 12692 25173 12693 25173 12681 25173 12681 25174 12693 25174 13925 25174 12681 25175 13925 25175 12694 25175 12694 25176 13925 25176 12677 25176 15189 25177 12696 25177 12695 25177 12695 25178 12696 25178 12606 25178 12695 25179 12606 25179 15195 25179 15195 25180 12606 25180 12698 25180 15195 25181 12698 25181 12697 25181 12697 25182 12698 25182 12607 25182 12697 25183 12607 25183 12699 25183 12699 25184 12607 25184 12700 25184 12699 25185 12700 25185 15198 25185 15198 25186 12700 25186 12611 25186 15198 25187 12611 25187 15181 25187 15181 25188 12611 25188 12612 25188 15166 25189 12701 25189 15180 25189 15180 25190 12701 25190 12615 25190 15180 25191 12615 25191 15167 25191 15167 25192 12615 25192 12616 25192 15167 25193 12616 25193 15169 25193 15169 25194 12616 25194 12703 25194 15169 25195 12703 25195 12702 25195 12702 25196 12703 25196 12704 25196 12702 25197 12704 25197 12705 25197 12705 25198 12704 25198 12706 25198 12705 25199 12706 25199 12707 25199 12707 25200 12706 25200 12708 25200 12707 25201 12708 25201 12709 25201 12709 25202 12708 25202 12620 25202 15155 25203 12710 25203 15157 25203 15157 25204 12710 25204 12711 25204 15157 25205 12711 25205 12712 25205 12712 25206 12711 25206 12713 25206 12712 25207 12713 25207 12714 25207 12714 25208 12713 25208 12715 25208 12714 25209 12715 25209 15158 25209 15158 25210 12715 25210 12716 25210 15158 25211 12716 25211 15159 25211 15159 25212 12716 25212 12624 25212 15159 25213 12624 25213 15146 25213 15146 25214 12624 25214 12623 25214 15146 25215 12623 25215 15148 25215 15148 25216 12623 25216 12622 25216 15134 25217 14345 25217 12717 25217 12717 25218 14345 25218 14344 25218 12717 25219 14344 25219 12720 25219 12720 25220 14344 25220 14339 25220 12720 25221 14339 25221 12722 25221 12722 25222 14339 25222 14343 25222 12722 25223 14343 25223 12723 25223 12723 25224 14343 25224 14342 25224 12723 25225 14342 25225 12724 25225 12724 25226 14342 25226 14341 25226 12724 25227 14341 25227 12725 25227 12725 25228 14341 25228 14349 25228 12725 25229 14349 25229 12718 25229 12718 25230 14349 25230 14346 25230 12719 25231 15134 25231 12736 25231 12736 25232 15134 25232 12717 25232 12736 25233 12717 25233 12734 25233 12734 25234 12717 25234 12720 25234 12734 25235 12720 25235 12721 25235 12721 25236 12720 25236 12722 25236 12721 25237 12722 25237 12731 25237 12731 25238 12722 25238 12723 25238 12731 25239 12723 25239 12729 25239 12729 25240 12723 25240 12724 25240 12729 25241 12724 25241 12728 25241 12728 25242 12724 25242 12725 25242 12728 25243 12725 25243 12726 25243 12726 25244 12725 25244 12718 25244 12726 25245 12727 25245 12728 25245 12728 25246 12727 25246 13752 25246 12728 25247 13752 25247 12729 25247 12729 25248 13752 25248 12730 25248 12729 25249 12730 25249 12731 25249 12731 25250 12730 25250 12732 25250 12731 25251 12732 25251 12721 25251 12721 25252 12732 25252 12733 25252 12721 25253 12733 25253 12734 25253 12734 25254 12733 25254 12735 25254 12734 25255 12735 25255 12736 25255 12736 25256 12735 25256 13744 25256 12736 25257 13744 25257 12719 25257 12719 25258 13744 25258 13746 25258 12743 25259 15123 25259 12745 25259 12745 25260 15123 25260 12737 25260 12745 25261 12737 25261 12738 25261 12738 25262 12737 25262 14331 25262 12738 25263 14331 25263 12739 25263 12739 25264 14331 25264 12740 25264 12739 25265 12740 25265 12741 25265 12741 25266 12740 25266 14041 25266 12741 25267 14041 25267 12749 25267 12749 25268 14041 25268 14039 25268 12749 25269 14039 25269 12750 25269 12750 25270 14039 25270 12742 25270 12750 25271 12742 25271 15110 25271 15110 25272 12742 25272 15117 25272 15115 25273 12743 25273 12744 25273 12744 25274 12743 25274 12745 25274 12744 25275 12745 25275 12754 25275 12754 25276 12745 25276 12738 25276 12754 25277 12738 25277 12746 25277 12746 25278 12738 25278 12739 25278 12746 25279 12739 25279 12747 25279 12747 25280 12739 25280 12741 25280 12747 25281 12741 25281 12748 25281 12748 25282 12741 25282 12749 25282 12748 25283 12749 25283 12751 25283 12751 25284 12749 25284 12750 25284 12751 25285 12750 25285 15109 25285 15109 25286 12750 25286 15110 25286 15109 25287 15108 25287 12751 25287 12751 25288 15108 25288 12752 25288 12751 25289 12752 25289 12748 25289 12748 25290 12752 25290 13727 25290 12748 25291 13727 25291 12747 25291 12747 25292 13727 25292 12753 25292 12747 25293 12753 25293 12746 25293 12746 25294 12753 25294 13729 25294 12746 25295 13729 25295 12754 25295 12754 25296 13729 25296 12755 25296 12754 25297 12755 25297 12744 25297 12744 25298 12755 25298 13732 25298 12744 25299 13732 25299 15115 25299 15115 25300 13732 25300 15102 25300 12764 25301 15100 25301 12765 25301 12765 25302 15100 25302 12756 25302 12765 25303 12756 25303 12757 25303 12757 25304 12756 25304 12758 25304 12757 25305 12758 25305 12767 25305 12767 25306 12758 25306 14194 25306 12767 25307 14194 25307 12768 25307 12768 25308 14194 25308 14193 25308 12768 25309 14193 25309 12759 25309 12759 25310 14193 25310 12761 25310 12759 25311 12761 25311 12760 25311 12760 25312 12761 25312 12762 25312 12760 25313 12762 25313 12763 25313 12763 25314 12762 25314 14190 25314 15097 25315 12764 25315 12778 25315 12778 25316 12764 25316 12765 25316 12778 25317 12765 25317 12776 25317 12776 25318 12765 25318 12757 25318 12776 25319 12757 25319 12775 25319 12775 25320 12757 25320 12767 25320 12775 25321 12767 25321 12766 25321 12766 25322 12767 25322 12768 25322 12766 25323 12768 25323 12772 25323 12772 25324 12768 25324 12759 25324 12772 25325 12759 25325 12770 25325 12770 25326 12759 25326 12760 25326 12770 25327 12760 25327 12769 25327 12769 25328 12760 25328 12763 25328 12769 25329 13724 25329 12770 25329 12770 25330 13724 25330 12771 25330 12770 25331 12771 25331 12772 25331 12772 25332 12771 25332 12773 25332 12772 25333 12773 25333 12766 25333 12766 25334 12773 25334 13713 25334 12766 25335 13713 25335 12775 25335 12775 25336 13713 25336 12774 25336 12775 25337 12774 25337 12776 25337 12776 25338 12774 25338 12777 25338 12776 25339 12777 25339 12778 25339 12778 25340 12777 25340 12779 25340 12778 25341 12779 25341 15097 25341 15097 25342 12779 25342 13717 25342 15087 25343 12780 25343 12785 25343 12785 25344 12780 25344 14169 25344 12785 25345 14169 25345 12786 25345 12786 25346 14169 25346 12781 25346 12786 25347 12781 25347 12787 25347 12787 25348 12781 25348 12782 25348 12787 25349 12782 25349 12788 25349 12788 25350 12782 25350 14171 25350 12788 25351 14171 25351 12791 25351 12791 25352 14171 25352 12784 25352 12791 25353 12784 25353 12783 25353 12783 25354 12784 25354 14174 25354 15070 25355 15087 25355 12797 25355 12797 25356 15087 25356 12785 25356 12797 25357 12785 25357 12796 25357 12796 25358 12785 25358 12786 25358 12796 25359 12786 25359 12795 25359 12795 25360 12786 25360 12787 25360 12795 25361 12787 25361 12792 25361 12792 25362 12787 25362 12788 25362 12792 25363 12788 25363 12789 25363 12789 25364 12788 25364 12791 25364 12789 25365 12791 25365 12790 25365 12790 25366 12791 25366 12783 25366 12790 25367 13702 25367 12789 25367 12789 25368 13702 25368 13704 25368 12789 25369 13704 25369 12792 25369 12792 25370 13704 25370 12793 25370 12792 25371 12793 25371 12795 25371 12795 25372 12793 25372 12794 25372 12795 25373 12794 25373 12796 25373 12796 25374 12794 25374 13707 25374 12796 25375 13707 25375 12797 25375 12797 25376 13707 25376 12798 25376 12797 25377 12798 25377 15070 25377 15070 25378 12798 25378 13709 25378 12800 25379 14051 25379 12799 25379 12799 25380 12897 25380 12800 25380 12800 25381 12897 25381 12801 25381 12800 25382 12801 25382 12802 25382 12801 25383 12896 25383 12802 25383 12802 25384 12896 25384 12803 25384 12802 25385 12803 25385 12804 25385 12803 25386 12895 25386 12804 25386 12804 25387 12895 25387 12893 25387 12804 25388 12893 25388 12805 25388 12805 25389 12893 25389 12806 25389 12805 25390 12806 25390 14053 25390 12806 25391 12892 25391 14053 25391 14053 25392 12892 25392 12890 25392 14053 25393 12890 25393 14046 25393 12886 25394 14047 25394 12887 25394 12887 25395 14047 25395 14046 25395 12887 25396 14046 25396 12807 25396 12807 25397 14046 25397 12890 25397 14035 25398 14955 25398 14044 25398 14044 25399 14955 25399 12808 25399 14044 25400 12808 25400 12809 25400 12809 25401 12808 25401 12814 25401 15063 25402 14414 25402 12810 25402 12810 25403 14414 25403 14037 25403 12810 25404 14037 25404 12811 25404 12811 25405 14037 25405 12812 25405 12811 25406 12812 25406 12902 25406 12902 25407 12812 25407 12813 25407 12902 25408 12813 25408 12814 25408 12814 25409 12813 25409 14045 25409 12814 25410 14045 25410 12809 25410 14178 25411 15051 25411 12815 25411 14178 25412 12815 25412 12817 25412 12815 25413 12816 25413 12817 25413 12817 25414 12816 25414 12819 25414 12817 25415 12819 25415 12818 25415 12819 25416 12820 25416 12818 25416 12818 25417 12820 25417 12912 25417 12818 25418 12912 25418 14180 25418 12912 25419 12911 25419 14180 25419 14180 25420 12911 25420 12910 25420 14180 25421 12910 25421 12821 25421 12821 25422 12910 25422 12909 25422 12821 25423 12909 25423 12822 25423 12909 25424 12908 25424 12822 25424 12822 25425 12908 25425 12827 25425 12822 25426 12827 25426 12825 25426 12905 25427 12823 25427 12824 25427 12824 25428 12823 25428 12825 25428 12824 25429 12825 25429 12826 25429 12826 25430 12825 25430 12827 25430 15036 25431 12828 25431 12829 25431 12829 25432 12828 25432 14974 25432 12829 25433 14974 25433 12830 25433 12830 25434 14974 25434 14973 25434 12830 25435 14973 25435 12831 25435 12831 25436 14973 25436 14972 25436 12831 25437 14972 25437 12838 25437 12838 25438 14972 25438 12832 25438 12838 25439 12832 25439 12833 25439 12833 25440 12832 25440 14970 25440 12833 25441 14970 25441 12841 25441 12841 25442 14970 25442 15045 25442 15034 25443 15036 25443 12834 25443 12834 25444 15036 25444 12829 25444 12834 25445 12829 25445 12844 25445 12844 25446 12829 25446 12845 25446 12845 25447 12829 25447 12830 25447 12845 25448 12830 25448 12835 25448 12835 25449 12830 25449 12836 25449 12836 25450 12830 25450 12831 25450 12836 25451 12831 25451 12848 25451 12848 25452 12831 25452 12837 25452 12837 25453 12831 25453 12838 25453 12837 25454 12838 25454 12839 25454 12839 25455 12838 25455 12840 25455 12840 25456 12838 25456 12833 25456 12840 25457 12833 25457 12851 25457 12851 25458 12833 25458 12842 25458 12842 25459 12833 25459 12841 25459 12842 25460 12841 25460 15024 25460 12843 25461 13791 25461 15034 25461 15034 25462 12834 25462 12843 25462 12843 25463 12834 25463 12844 25463 12843 25464 12844 25464 12846 25464 12844 25465 12845 25465 12846 25465 12846 25466 12845 25466 12835 25466 12846 25467 12835 25467 12847 25467 12847 25468 12835 25468 12836 25468 12847 25469 12836 25469 13784 25469 12836 25470 12848 25470 13784 25470 13784 25471 12848 25471 12837 25471 13784 25472 12837 25472 12849 25472 12837 25473 12839 25473 12849 25473 12849 25474 12839 25474 12840 25474 12849 25475 12840 25475 13785 25475 15024 25476 12850 25476 12842 25476 12842 25477 12850 25477 13785 25477 12842 25478 13785 25478 12851 25478 12851 25479 13785 25479 12840 25479 15015 25480 12852 25480 12853 25480 12853 25481 12852 25481 14452 25481 12853 25482 14452 25482 12854 25482 12854 25483 14452 25483 14453 25483 12854 25484 14453 25484 12855 25484 12855 25485 14453 25485 12856 25485 12855 25486 12856 25486 12857 25486 12857 25487 12856 25487 12858 25487 12857 25488 12858 25488 12863 25488 12863 25489 12858 25489 14455 25489 12863 25490 14455 25490 15006 25490 15006 25491 14455 25491 12859 25491 15013 25492 15015 25492 12868 25492 12868 25493 15015 25493 12853 25493 12868 25494 12853 25494 12860 25494 12860 25495 12853 25495 12854 25495 12860 25496 12854 25496 12866 25496 12866 25497 12854 25497 12855 25497 12866 25498 12855 25498 12861 25498 12861 25499 12855 25499 12857 25499 12861 25500 12857 25500 12862 25500 12862 25501 12857 25501 12863 25501 12862 25502 12863 25502 12864 25502 12864 25503 12863 25503 15006 25503 12864 25504 13770 25504 12862 25504 12862 25505 13770 25505 12865 25505 12862 25506 12865 25506 12861 25506 12861 25507 12865 25507 13773 25507 12861 25508 13773 25508 12866 25508 12866 25509 13773 25509 13774 25509 12866 25510 13774 25510 12860 25510 12860 25511 13774 25511 13775 25511 12860 25512 13775 25512 12868 25512 12868 25513 13775 25513 12867 25513 12868 25514 12867 25514 15013 25514 15013 25515 12867 25515 14999 25515 12869 25516 14998 25516 12870 25516 12870 25517 14998 25517 14943 25517 12870 25518 14943 25518 12871 25518 12871 25519 14943 25519 14945 25519 12871 25520 14945 25520 12876 25520 12876 25521 14945 25521 14946 25521 12876 25522 14946 25522 12872 25522 12872 25523 14946 25523 12873 25523 12872 25524 12873 25524 12879 25524 12879 25525 12873 25525 12874 25525 12879 25526 12874 25526 12881 25526 12881 25527 12874 25527 12875 25527 14990 25528 12869 25528 12885 25528 12885 25529 12869 25529 12870 25529 12885 25530 12870 25530 12883 25530 12883 25531 12870 25531 12871 25531 12883 25532 12871 25532 12877 25532 12877 25533 12871 25533 12876 25533 12877 25534 12876 25534 12878 25534 12878 25535 12876 25535 12872 25535 12878 25536 12872 25536 12880 25536 12880 25537 12872 25537 12879 25537 12880 25538 12879 25538 14985 25538 14985 25539 12879 25539 12881 25539 14985 25540 13756 25540 12880 25540 12880 25541 13756 25541 13757 25541 12880 25542 13757 25542 12878 25542 12878 25543 13757 25543 12882 25543 12878 25544 12882 25544 12877 25544 12877 25545 12882 25545 13760 25545 12877 25546 13760 25546 12883 25546 12883 25547 13760 25547 12884 25547 12883 25548 12884 25548 12885 25548 12885 25549 12884 25549 13762 25549 12885 25550 13762 25550 14990 25550 14990 25551 13762 25551 14976 25551 12886 25552 12887 25552 12888 25552 12888 25553 12887 25553 12889 25553 12887 25554 12807 25554 12889 25554 12889 25555 12807 25555 12890 25555 12889 25556 12890 25556 12891 25556 12890 25557 12892 25557 12891 25557 12891 25558 12892 25558 12806 25558 12891 25559 12806 25559 14971 25559 12806 25560 12893 25560 14971 25560 14971 25561 12893 25561 12895 25561 14971 25562 12895 25562 12894 25562 12895 25563 12803 25563 12894 25563 12894 25564 12803 25564 12896 25564 12894 25565 12896 25565 12898 25565 12799 25566 14969 25566 12897 25566 12897 25567 14969 25567 12898 25567 12897 25568 12898 25568 12801 25568 12801 25569 12898 25569 12896 25569 12899 25570 15063 25570 12900 25570 12900 25571 15063 25571 12810 25571 12900 25572 12810 25572 12901 25572 12901 25573 12810 25573 12811 25573 12901 25574 12811 25574 14454 25574 14454 25575 12811 25575 12902 25575 14454 25576 12902 25576 12903 25576 12903 25577 12902 25577 12814 25577 12903 25578 12814 25578 12904 25578 12904 25579 12814 25579 12808 25579 12904 25580 12808 25580 14456 25580 14456 25581 12808 25581 14955 25581 12905 25582 12824 25582 12906 25582 12906 25583 12824 25583 14944 25583 12824 25584 12826 25584 14944 25584 14944 25585 12826 25585 12827 25585 14944 25586 12827 25586 12907 25586 12827 25587 12908 25587 12907 25587 12907 25588 12908 25588 12909 25588 12907 25589 12909 25589 14947 25589 12909 25590 12910 25590 14947 25590 14947 25591 12910 25591 12911 25591 14947 25592 12911 25592 12913 25592 12911 25593 12912 25593 12913 25593 12913 25594 12912 25594 12820 25594 12913 25595 12820 25595 12914 25595 12815 25596 14936 25596 12816 25596 12816 25597 14936 25597 12914 25597 12816 25598 12914 25598 12819 25598 12819 25599 12914 25599 12820 25599 14935 25600 14059 25600 12921 25600 12921 25601 14059 25601 14058 25601 12921 25602 14058 25602 12915 25602 12915 25603 14058 25603 12916 25603 12915 25604 12916 25604 12917 25604 12917 25605 12916 25605 12918 25605 12917 25606 12918 25606 12924 25606 12924 25607 12918 25607 14398 25607 12924 25608 14398 25608 12926 25608 12926 25609 14398 25609 12919 25609 12926 25610 12919 25610 12920 25610 12920 25611 12919 25611 14068 25611 12920 25612 14068 25612 14921 25612 14921 25613 14068 25613 14067 25613 14919 25614 14935 25614 12921 25614 14919 25615 12921 25615 12922 25615 12922 25616 12921 25616 12915 25616 12922 25617 12915 25617 12923 25617 12923 25618 12915 25618 12929 25618 12929 25619 12915 25619 12917 25619 12929 25620 12917 25620 12930 25620 12930 25621 12917 25621 12932 25621 12932 25622 12917 25622 12924 25622 12932 25623 12924 25623 12934 25623 12934 25624 12924 25624 12925 25624 12925 25625 12924 25625 12926 25625 12925 25626 12926 25626 12927 25626 12927 25627 12926 25627 12920 25627 12927 25628 12920 25628 12936 25628 12936 25629 12920 25629 14921 25629 12936 25630 14921 25630 14911 25630 13835 25631 14919 25631 12928 25631 12928 25632 14919 25632 12922 25632 12928 25633 12922 25633 12931 25633 12931 25634 12922 25634 12923 25634 12923 25635 12929 25635 12931 25635 12931 25636 12929 25636 12930 25636 12931 25637 12930 25637 12933 25637 12930 25638 12932 25638 12933 25638 12933 25639 12932 25639 12934 25639 12933 25640 12934 25640 13831 25640 14911 25641 12935 25641 12936 25641 12936 25642 12935 25642 13829 25642 12936 25643 13829 25643 12927 25643 12927 25644 13829 25644 13831 25644 12927 25645 13831 25645 12925 25645 12925 25646 13831 25646 12934 25646 14910 25647 14075 25647 12942 25647 12942 25648 14075 25648 12937 25648 12942 25649 12937 25649 12943 25649 12943 25650 12937 25650 14073 25650 12943 25651 14073 25651 12945 25651 12945 25652 14073 25652 12938 25652 12945 25653 12938 25653 12946 25653 12946 25654 12938 25654 14071 25654 12946 25655 14071 25655 12939 25655 12939 25656 14071 25656 12940 25656 12939 25657 12940 25657 12949 25657 12949 25658 12940 25658 12941 25658 12949 25659 12941 25659 14902 25659 14902 25660 12941 25660 14903 25660 12957 25661 14910 25661 12955 25661 12955 25662 14910 25662 12942 25662 12955 25663 12942 25663 12954 25663 12954 25664 12942 25664 12943 25664 12954 25665 12943 25665 12944 25665 12944 25666 12943 25666 12945 25666 12944 25667 12945 25667 12953 25667 12953 25668 12945 25668 12946 25668 12953 25669 12946 25669 12947 25669 12947 25670 12946 25670 12939 25670 12947 25671 12939 25671 12948 25671 12948 25672 12939 25672 12949 25672 12948 25673 12949 25673 12950 25673 12950 25674 12949 25674 14902 25674 12950 25675 12951 25675 12948 25675 12948 25676 12951 25676 13824 25676 12948 25677 13824 25677 12947 25677 12947 25678 13824 25678 12952 25678 12947 25679 12952 25679 12953 25679 12953 25680 12952 25680 13825 25680 12953 25681 13825 25681 12944 25681 12944 25682 13825 25682 13826 25682 12944 25683 13826 25683 12954 25683 12954 25684 13826 25684 13827 25684 12954 25685 13827 25685 12955 25685 12955 25686 13827 25686 12956 25686 12955 25687 12956 25687 12957 25687 12957 25688 12956 25688 14889 25688 12958 25689 14888 25689 12959 25689 12959 25690 14888 25690 14091 25690 12959 25691 14091 25691 12960 25691 12960 25692 14091 25692 12961 25692 12960 25693 12961 25693 12962 25693 12962 25694 12961 25694 14096 25694 12962 25695 14096 25695 12968 25695 12968 25696 14096 25696 14095 25696 12968 25697 14095 25697 12969 25697 12969 25698 14095 25698 14094 25698 12969 25699 14094 25699 12971 25699 12971 25700 14094 25700 12963 25700 12971 25701 12963 25701 14876 25701 14876 25702 12963 25702 14883 25702 12977 25703 12958 25703 12964 25703 12964 25704 12958 25704 12959 25704 12964 25705 12959 25705 12975 25705 12975 25706 12959 25706 12960 25706 12975 25707 12960 25707 12965 25707 12965 25708 12960 25708 12962 25708 12965 25709 12962 25709 12966 25709 12966 25710 12962 25710 12968 25710 12966 25711 12968 25711 12967 25711 12967 25712 12968 25712 12969 25712 12967 25713 12969 25713 12972 25713 12972 25714 12969 25714 12971 25714 12972 25715 12971 25715 12970 25715 12970 25716 12971 25716 14876 25716 12970 25717 14875 25717 12972 25717 12972 25718 14875 25718 12973 25718 12972 25719 12973 25719 12967 25719 12967 25720 12973 25720 12974 25720 12967 25721 12974 25721 12966 25721 12966 25722 12974 25722 13804 25722 12966 25723 13804 25723 12965 25723 12965 25724 13804 25724 13807 25724 12965 25725 13807 25725 12975 25725 12975 25726 13807 25726 12976 25726 12975 25727 12976 25727 12964 25727 12964 25728 12976 25728 13808 25728 12964 25729 13808 25729 12977 25729 12977 25730 13808 25730 13810 25730 12978 25731 14265 25731 12984 25731 12984 25732 14265 25732 14259 25732 12984 25733 14259 25733 12979 25733 12979 25734 14259 25734 14258 25734 12979 25735 14258 25735 12980 25735 12980 25736 14258 25736 12981 25736 12980 25737 12981 25737 12982 25737 12982 25738 12981 25738 14256 25738 12982 25739 14256 25739 12985 25739 12985 25740 14256 25740 14255 25740 12985 25741 14255 25741 14854 25741 14854 25742 14255 25742 14388 25742 14861 25743 12978 25743 12992 25743 12992 25744 12978 25744 12984 25744 12992 25745 12984 25745 12983 25745 12983 25746 12984 25746 12979 25746 12983 25747 12979 25747 12989 25747 12989 25748 12979 25748 12980 25748 12989 25749 12980 25749 12988 25749 12988 25750 12980 25750 12982 25750 12988 25751 12982 25751 12987 25751 12987 25752 12982 25752 12985 25752 12987 25753 12985 25753 14845 25753 14845 25754 12985 25754 14854 25754 14845 25755 12986 25755 12987 25755 12987 25756 12986 25756 13803 25756 12987 25757 13803 25757 12988 25757 12988 25758 13803 25758 13792 25758 12988 25759 13792 25759 12989 25759 12989 25760 13792 25760 12990 25760 12989 25761 12990 25761 12983 25761 12983 25762 12990 25762 12991 25762 12983 25763 12991 25763 12992 25763 12992 25764 12991 25764 13795 25764 12992 25765 13795 25765 14861 25765 14861 25766 13795 25766 13796 25766 14751 25767 12993 25767 12994 25767 12994 25768 12993 25768 14064 25768 12994 25769 14064 25769 13072 25769 13072 25770 14064 25770 14066 25770 13072 25771 14066 25771 13073 25771 13073 25772 14066 25772 14057 25772 13073 25773 14057 25773 13076 25773 13076 25774 14057 25774 14056 25774 13076 25775 14056 25775 13077 25775 13077 25776 14056 25776 12995 25776 13077 25777 12995 25777 14842 25777 14842 25778 12995 25778 12996 25778 14831 25779 14830 25779 13078 25779 13078 25780 14830 25780 12997 25780 13078 25781 12997 25781 13080 25781 13080 25782 12997 25782 14097 25782 13080 25783 14097 25783 12998 25783 12998 25784 14097 25784 12999 25784 12998 25785 12999 25785 13000 25785 13000 25786 12999 25786 14099 25786 13000 25787 14099 25787 13001 25787 13001 25788 14099 25788 13003 25788 13001 25789 13003 25789 13002 25789 13002 25790 13003 25790 14087 25790 13083 25791 13004 25791 13084 25791 13084 25792 13004 25792 13005 25792 13084 25793 13005 25793 13086 25793 13086 25794 13005 25794 14086 25794 13086 25795 14086 25795 13087 25795 13087 25796 14086 25796 14085 25796 13087 25797 14085 25797 13088 25797 13088 25798 14085 25798 13006 25798 13088 25799 13006 25799 13090 25799 13090 25800 13006 25800 14083 25800 13090 25801 14083 25801 13091 25801 13091 25802 14083 25802 14082 25802 13091 25803 14082 25803 13007 25803 13007 25804 14082 25804 14081 25804 14818 25805 14759 25805 13015 25805 13015 25806 14759 25806 13008 25806 13015 25807 13008 25807 13009 25807 13009 25808 13008 25808 14760 25808 13009 25809 14760 25809 13010 25809 13010 25810 14760 25810 13011 25810 13010 25811 13011 25811 13016 25811 13016 25812 13011 25812 14761 25812 13016 25813 14761 25813 13017 25813 13017 25814 14761 25814 13012 25814 13017 25815 13012 25815 13013 25815 13013 25816 13012 25816 14820 25816 14805 25817 14818 25817 13014 25817 13014 25818 14818 25818 13015 25818 13014 25819 13015 25819 13025 25819 13025 25820 13015 25820 13009 25820 13025 25821 13009 25821 13023 25821 13023 25822 13009 25822 13010 25822 13023 25823 13010 25823 13021 25823 13021 25824 13010 25824 13016 25824 13021 25825 13016 25825 13018 25825 13018 25826 13016 25826 13017 25826 13018 25827 13017 25827 14800 25827 14800 25828 13017 25828 13013 25828 14800 25829 13019 25829 13018 25829 13018 25830 13019 25830 13020 25830 13018 25831 13020 25831 13021 25831 13021 25832 13020 25832 13022 25832 13021 25833 13022 25833 13023 25833 13023 25834 13022 25834 13024 25834 13023 25835 13024 25835 13025 25835 13025 25836 13024 25836 13867 25836 13025 25837 13867 25837 13014 25837 13014 25838 13867 25838 13026 25838 13014 25839 13026 25839 14805 25839 14805 25840 13026 25840 14807 25840 14794 25841 14799 25841 13028 25841 13028 25842 14799 25842 13027 25842 13028 25843 13027 25843 13036 25843 13036 25844 13027 25844 14740 25844 13036 25845 14740 25845 13029 25845 13029 25846 14740 25846 13030 25846 13029 25847 13030 25847 13037 25847 13037 25848 13030 25848 14742 25848 13037 25849 14742 25849 13031 25849 13031 25850 14742 25850 13032 25850 13031 25851 13032 25851 13033 25851 13033 25852 13032 25852 13034 25852 13035 25853 14794 25853 13044 25853 13044 25854 14794 25854 13028 25854 13044 25855 13028 25855 13043 25855 13043 25856 13028 25856 13036 25856 13043 25857 13036 25857 13041 25857 13041 25858 13036 25858 13029 25858 13041 25859 13029 25859 13040 25859 13040 25860 13029 25860 13037 25860 13040 25861 13037 25861 13038 25861 13038 25862 13037 25862 13031 25862 13038 25863 13031 25863 14785 25863 14785 25864 13031 25864 13033 25864 14785 25865 14786 25865 13038 25865 13038 25866 14786 25866 13039 25866 13038 25867 13039 25867 13040 25867 13040 25868 13039 25868 13863 25868 13040 25869 13863 25869 13041 25869 13041 25870 13863 25870 13042 25870 13041 25871 13042 25871 13043 25871 13043 25872 13042 25872 13856 25872 13043 25873 13856 25873 13044 25873 13044 25874 13856 25874 13045 25874 13044 25875 13045 25875 13035 25875 13035 25876 13045 25876 14780 25876 13053 25877 13046 25877 13054 25877 13054 25878 13046 25878 14721 25878 13054 25879 14721 25879 13047 25879 13047 25880 14721 25880 14723 25880 13047 25881 14723 25881 13055 25881 13055 25882 14723 25882 13048 25882 13055 25883 13048 25883 13050 25883 13050 25884 13048 25884 13049 25884 13050 25885 13049 25885 13051 25885 13051 25886 13049 25886 13052 25886 13051 25887 13052 25887 13056 25887 13056 25888 13052 25888 14727 25888 13056 25889 14727 25889 14769 25889 14769 25890 14727 25890 14773 25890 13068 25891 13053 25891 13065 25891 13065 25892 13053 25892 13054 25892 13065 25893 13054 25893 13063 25893 13063 25894 13054 25894 13047 25894 13063 25895 13047 25895 13062 25895 13062 25896 13047 25896 13055 25896 13062 25897 13055 25897 13061 25897 13061 25898 13055 25898 13050 25898 13061 25899 13050 25899 13059 25899 13059 25900 13050 25900 13051 25900 13059 25901 13051 25901 13058 25901 13058 25902 13051 25902 13056 25902 13058 25903 13056 25903 13057 25903 13057 25904 13056 25904 14769 25904 13057 25905 13853 25905 13058 25905 13058 25906 13853 25906 13854 25906 13058 25907 13854 25907 13059 25907 13059 25908 13854 25908 13060 25908 13059 25909 13060 25909 13061 25909 13061 25910 13060 25910 13841 25910 13061 25911 13841 25911 13062 25911 13062 25912 13841 25912 13064 25912 13062 25913 13064 25913 13063 25913 13063 25914 13064 25914 13066 25914 13063 25915 13066 25915 13065 25915 13065 25916 13066 25916 13067 25916 13065 25917 13067 25917 13068 25917 13068 25918 13067 25918 13069 25918 14750 25919 14751 25919 13070 25919 13070 25920 14751 25920 12994 25920 13070 25921 12994 25921 13071 25921 13071 25922 12994 25922 13072 25922 13071 25923 13072 25923 14762 25923 14762 25924 13072 25924 13073 25924 14762 25925 13073 25925 13074 25925 13074 25926 13073 25926 13076 25926 13074 25927 13076 25927 13075 25927 13075 25928 13076 25928 13077 25928 13075 25929 13077 25929 14763 25929 14763 25930 13077 25930 14842 25930 14739 25931 14831 25931 14741 25931 14741 25932 14831 25932 13078 25932 14741 25933 13078 25933 13079 25933 13079 25934 13078 25934 13080 25934 13079 25935 13080 25935 13081 25935 13081 25936 13080 25936 12998 25936 13081 25937 12998 25937 14743 25937 14743 25938 12998 25938 13000 25938 14743 25939 13000 25939 13082 25939 13082 25940 13000 25940 13001 25940 13082 25941 13001 25941 14735 25941 14735 25942 13001 25942 13002 25942 14722 25943 13083 25943 14724 25943 14724 25944 13083 25944 13084 25944 14724 25945 13084 25945 13085 25945 13085 25946 13084 25946 13086 25946 13085 25947 13086 25947 14725 25947 14725 25948 13086 25948 13087 25948 14725 25949 13087 25949 14726 25949 14726 25950 13087 25950 13088 25950 14726 25951 13088 25951 13089 25951 13089 25952 13088 25952 13090 25952 13089 25953 13090 25953 14714 25953 14714 25954 13090 25954 13091 25954 14714 25955 13091 25955 14716 25955 14716 25956 13091 25956 13007 25956 13097 25957 14106 25957 13098 25957 13098 25958 14106 25958 13092 25958 13098 25959 13092 25959 13099 25959 13099 25960 13092 25960 14110 25960 13099 25961 14110 25961 13101 25961 13101 25962 14110 25962 13093 25962 13101 25963 13093 25963 13103 25963 13103 25964 13093 25964 13094 25964 13103 25965 13094 25965 13104 25965 13104 25966 13094 25966 14112 25966 13104 25967 14112 25967 13095 25967 13095 25968 14112 25968 14703 25968 13096 25969 13097 25969 13110 25969 13110 25970 13097 25970 13098 25970 13110 25971 13098 25971 13109 25971 13109 25972 13098 25972 13099 25972 13109 25973 13099 25973 13100 25973 13100 25974 13099 25974 13101 25974 13100 25975 13101 25975 13102 25975 13102 25976 13101 25976 13103 25976 13102 25977 13103 25977 13106 25977 13106 25978 13103 25978 13104 25978 13106 25979 13104 25979 14693 25979 14693 25980 13104 25980 13095 25980 14693 25981 13631 25981 13106 25981 13106 25982 13631 25982 13105 25982 13106 25983 13105 25983 13102 25983 13102 25984 13105 25984 13633 25984 13102 25985 13633 25985 13100 25985 13100 25986 13633 25986 13107 25986 13100 25987 13107 25987 13109 25987 13109 25988 13107 25988 13108 25988 13109 25989 13108 25989 13110 25989 13110 25990 13108 25990 13635 25990 13110 25991 13635 25991 13096 25991 13096 25992 13635 25992 14691 25992 13116 25993 13111 25993 13117 25993 13117 25994 13111 25994 13112 25994 13117 25995 13112 25995 13118 25995 13118 25996 13112 25996 14116 25996 13118 25997 14116 25997 13120 25997 13120 25998 14116 25998 14115 25998 13120 25999 14115 25999 13113 25999 13113 26000 14115 26000 14114 26000 13113 26001 14114 26001 13121 26001 13121 26002 14114 26002 14113 26002 13121 26003 14113 26003 13114 26003 13114 26004 14113 26004 13115 26004 13114 26005 13115 26005 14675 26005 14675 26006 13115 26006 14120 26006 14674 26007 13116 26007 13128 26007 13128 26008 13116 26008 13117 26008 13128 26009 13117 26009 13125 26009 13125 26010 13117 26010 13118 26010 13125 26011 13118 26011 13119 26011 13119 26012 13118 26012 13120 26012 13119 26013 13120 26013 13124 26013 13124 26014 13120 26014 13113 26014 13124 26015 13113 26015 13123 26015 13123 26016 13113 26016 13121 26016 13123 26017 13121 26017 13122 26017 13122 26018 13121 26018 13114 26018 13122 26019 13114 26019 14672 26019 14672 26020 13114 26020 14675 26020 14672 26021 13653 26021 13122 26021 13122 26022 13653 26022 13654 26022 13122 26023 13654 26023 13123 26023 13123 26024 13654 26024 13655 26024 13123 26025 13655 26025 13124 26025 13124 26026 13655 26026 13640 26026 13124 26027 13640 26027 13119 26027 13119 26028 13640 26028 13642 26028 13119 26029 13642 26029 13125 26029 13125 26030 13642 26030 13126 26030 13125 26031 13126 26031 13128 26031 13128 26032 13126 26032 13127 26032 13128 26033 13127 26033 14674 26033 14674 26034 13127 26034 13644 26034 13137 26035 14123 26035 13129 26035 13129 26036 14123 26036 13130 26036 13129 26037 13130 26037 13131 26037 13131 26038 13130 26038 13132 26038 13131 26039 13132 26039 13133 26039 13133 26040 13132 26040 14131 26040 13133 26041 14131 26041 13140 26041 13140 26042 14131 26042 13135 26042 13140 26043 13135 26043 13134 26043 13134 26044 13135 26044 14132 26044 13134 26045 14132 26045 13136 26045 13136 26046 14132 26046 14300 26046 13150 26047 13137 26047 13138 26047 13138 26048 13137 26048 13129 26048 13138 26049 13129 26049 13146 26049 13146 26050 13129 26050 13131 26050 13146 26051 13131 26051 13139 26051 13139 26052 13131 26052 13133 26052 13139 26053 13133 26053 13143 26053 13143 26054 13133 26054 13140 26054 13143 26055 13140 26055 13141 26055 13141 26056 13140 26056 13134 26056 13141 26057 13134 26057 13142 26057 13142 26058 13134 26058 13136 26058 13142 26059 13666 26059 13141 26059 13141 26060 13666 26060 13144 26060 13141 26061 13144 26061 13143 26061 13143 26062 13144 26062 13145 26062 13143 26063 13145 26063 13139 26063 13139 26064 13145 26064 13147 26064 13139 26065 13147 26065 13146 26065 13146 26066 13147 26066 13148 26066 13146 26067 13148 26067 13138 26067 13138 26068 13148 26068 13149 26068 13138 26069 13149 26069 13150 26069 13150 26070 13149 26070 13658 26070 14637 26071 13151 26071 13162 26071 13162 26072 13151 26072 14136 26072 13162 26073 14136 26073 13152 26073 13152 26074 14136 26074 14137 26074 13152 26075 14137 26075 13153 26075 13153 26076 14137 26076 13155 26076 13153 26077 13155 26077 13154 26077 13154 26078 13155 26078 13156 26078 13154 26079 13156 26079 13157 26079 13157 26080 13156 26080 13158 26080 13157 26081 13158 26081 13164 26081 13164 26082 13158 26082 13159 26082 14636 26083 14637 26083 13160 26083 13160 26084 14637 26084 13162 26084 13160 26085 13162 26085 13161 26085 13161 26086 13162 26086 13152 26086 13161 26087 13152 26087 13168 26087 13168 26088 13152 26088 13153 26088 13168 26089 13153 26089 13163 26089 13163 26090 13153 26090 13154 26090 13163 26091 13154 26091 13166 26091 13166 26092 13154 26092 13157 26092 13166 26093 13157 26093 14629 26093 14629 26094 13157 26094 13164 26094 14629 26095 13165 26095 13166 26095 13166 26096 13165 26096 13167 26096 13166 26097 13167 26097 13163 26097 13163 26098 13167 26098 13675 26098 13163 26099 13675 26099 13168 26099 13168 26100 13675 26100 13676 26100 13168 26101 13676 26101 13161 26101 13161 26102 13676 26102 13677 26102 13161 26103 13677 26103 13160 26103 13160 26104 13677 26104 13169 26104 13160 26105 13169 26105 14636 26105 14636 26106 13169 26106 13679 26106 14622 26107 14623 26107 13170 26107 13170 26108 14623 26108 13171 26108 13170 26109 13171 26109 13267 26109 13267 26110 13171 26110 14144 26110 13267 26111 14144 26111 13173 26111 13173 26112 14144 26112 13172 26112 13173 26113 13172 26113 13268 26113 13268 26114 13172 26114 13174 26114 13268 26115 13174 26115 13175 26115 13175 26116 13174 26116 13177 26116 13175 26117 13177 26117 13176 26117 13176 26118 13177 26118 13178 26118 13176 26119 13178 26119 14620 26119 14620 26120 13178 26120 14149 26120 14619 26121 14034 26121 13180 26121 13180 26122 14034 26122 13179 26122 13180 26123 13179 26123 13181 26123 13181 26124 13179 26124 13182 26124 13181 26125 13182 26125 13183 26125 13183 26126 13182 26126 14143 26126 13183 26127 14143 26127 13272 26127 13272 26128 14143 26128 13184 26128 13272 26129 13184 26129 13185 26129 13185 26130 13184 26130 14128 26130 13185 26131 14128 26131 13186 26131 13186 26132 14128 26132 14126 26132 13186 26133 14126 26133 13187 26133 13187 26134 14126 26134 14133 26134 13188 26135 13189 26135 13273 26135 13273 26136 13189 26136 14313 26136 13273 26137 14313 26137 13190 26137 13190 26138 14313 26138 13192 26138 13190 26139 13192 26139 13191 26139 13191 26140 13192 26140 14317 26140 13191 26141 14317 26141 13193 26141 13193 26142 14317 26142 14315 26142 13193 26143 14315 26143 13277 26143 13277 26144 14315 26144 13194 26144 13277 26145 13194 26145 13195 26145 13195 26146 13194 26146 13196 26146 13195 26147 13196 26147 14493 26147 14493 26148 13196 26148 14610 26148 14609 26149 13197 26149 13206 26149 13206 26150 13197 26150 13198 26150 13206 26151 13198 26151 13209 26151 13209 26152 13198 26152 13200 26152 13209 26153 13200 26153 13199 26153 13199 26154 13200 26154 14553 26154 13199 26155 14553 26155 13212 26155 13212 26156 14553 26156 13201 26156 13212 26157 13201 26157 13215 26157 13215 26158 13201 26158 13202 26158 13215 26159 13202 26159 13203 26159 13203 26160 13202 26160 13204 26160 13203 26161 13204 26161 13205 26161 13205 26162 13204 26162 14546 26162 13217 26163 14609 26163 13206 26163 13217 26164 13206 26164 13207 26164 13207 26165 13206 26165 13209 26165 13207 26166 13209 26166 13208 26166 13208 26167 13209 26167 13219 26167 13219 26168 13209 26168 13199 26168 13219 26169 13199 26169 13210 26169 13210 26170 13199 26170 13211 26170 13211 26171 13199 26171 13212 26171 13211 26172 13212 26172 13220 26172 13220 26173 13212 26173 13213 26173 13213 26174 13212 26174 13215 26174 13213 26175 13215 26175 13214 26175 13214 26176 13215 26176 13203 26176 13214 26177 13203 26177 13216 26177 13216 26178 13203 26178 13205 26178 13216 26179 13205 26179 14585 26179 14596 26180 13217 26180 13218 26180 13218 26181 13217 26181 13207 26181 13218 26182 13207 26182 13606 26182 13207 26183 13208 26183 13606 26183 13606 26184 13208 26184 13219 26184 13606 26185 13219 26185 13221 26185 13221 26186 13219 26186 13210 26186 13210 26187 13211 26187 13221 26187 13221 26188 13211 26188 13220 26188 13221 26189 13220 26189 13222 26189 14585 26190 14584 26190 13216 26190 13216 26191 14584 26191 13604 26191 13216 26192 13604 26192 13214 26192 13214 26193 13604 26193 13222 26193 13214 26194 13222 26194 13213 26194 13213 26195 13222 26195 13220 26195 14583 26196 13223 26196 13229 26196 13229 26197 13223 26197 13224 26197 13229 26198 13224 26198 13225 26198 13225 26199 13224 26199 14517 26199 13225 26200 14517 26200 13231 26200 13231 26201 14517 26201 14518 26201 13231 26202 14518 26202 13232 26202 13232 26203 14518 26203 13226 26203 13232 26204 13226 26204 13227 26204 13227 26205 13226 26205 14520 26205 13227 26206 14520 26206 13233 26206 13233 26207 14520 26207 13228 26207 13233 26208 13228 26208 14573 26208 14573 26209 13228 26209 14579 26209 13240 26210 14583 26210 13239 26210 13239 26211 14583 26211 13229 26211 13239 26212 13229 26212 13230 26212 13230 26213 13229 26213 13225 26213 13230 26214 13225 26214 13238 26214 13238 26215 13225 26215 13231 26215 13238 26216 13231 26216 13237 26216 13237 26217 13231 26217 13232 26217 13237 26218 13232 26218 13236 26218 13236 26219 13232 26219 13227 26219 13236 26220 13227 26220 13235 26220 13235 26221 13227 26221 13233 26221 13235 26222 13233 26222 13234 26222 13234 26223 13233 26223 14573 26223 13234 26224 14571 26224 13235 26224 13235 26225 14571 26225 13624 26225 13235 26226 13624 26226 13236 26226 13236 26227 13624 26227 13625 26227 13236 26228 13625 26228 13237 26228 13237 26229 13625 26229 13627 26229 13237 26230 13627 26230 13238 26230 13238 26231 13627 26231 13629 26231 13238 26232 13629 26232 13230 26232 13230 26233 13629 26233 13615 26233 13230 26234 13615 26234 13239 26234 13239 26235 13615 26235 13241 26235 13239 26236 13241 26236 13240 26236 13240 26237 13241 26237 13616 26237 13242 26238 14505 26238 13243 26238 13243 26239 14505 26239 13244 26239 13243 26240 13244 26240 13245 26240 13245 26241 13244 26241 14507 26241 13245 26242 14507 26242 13253 26242 13253 26243 14507 26243 14509 26243 13253 26244 14509 26244 13255 26244 13255 26245 14509 26245 13246 26245 13255 26246 13246 26246 13247 26246 13247 26247 13246 26247 13249 26247 13247 26248 13249 26248 13248 26248 13248 26249 13249 26249 13250 26249 13248 26250 13250 26250 13251 26250 13251 26251 13250 26251 14498 26251 13264 26252 13242 26252 13263 26252 13263 26253 13242 26253 13243 26253 13263 26254 13243 26254 13252 26254 13252 26255 13243 26255 13245 26255 13252 26256 13245 26256 13254 26256 13254 26257 13245 26257 13253 26257 13254 26258 13253 26258 13261 26258 13261 26259 13253 26259 13255 26259 13261 26260 13255 26260 13256 26260 13256 26261 13255 26261 13247 26261 13256 26262 13247 26262 13258 26262 13258 26263 13247 26263 13248 26263 13258 26264 13248 26264 13257 26264 13257 26265 13248 26265 13251 26265 13257 26266 13259 26266 13258 26266 13258 26267 13259 26267 13260 26267 13258 26268 13260 26268 13256 26268 13256 26269 13260 26269 13681 26269 13256 26270 13681 26270 13261 26270 13261 26271 13681 26271 13682 26271 13261 26272 13682 26272 13254 26272 13254 26273 13682 26273 13262 26273 13254 26274 13262 26274 13252 26274 13252 26275 13262 26275 13685 26275 13252 26276 13685 26276 13263 26276 13263 26277 13685 26277 13687 26277 13263 26278 13687 26278 13264 26278 13264 26279 13687 26279 13265 26279 14542 26280 14622 26280 14552 26280 14552 26281 14622 26281 13170 26281 14552 26282 13170 26282 13266 26282 13266 26283 13170 26283 13267 26283 13266 26284 13267 26284 14543 26284 14543 26285 13267 26285 13173 26285 14543 26286 13173 26286 14544 26286 14544 26287 13173 26287 13268 26287 14544 26288 13268 26288 14545 26288 14545 26289 13268 26289 13175 26289 14545 26290 13175 26290 14547 26290 14547 26291 13175 26291 13176 26291 14547 26292 13176 26292 13269 26292 13269 26293 13176 26293 14620 26293 14531 26294 14619 26294 14532 26294 14532 26295 14619 26295 13180 26295 14532 26296 13180 26296 13270 26296 13270 26297 13180 26297 13181 26297 13270 26298 13181 26298 14519 26298 14519 26299 13181 26299 13183 26299 14519 26300 13183 26300 13271 26300 13271 26301 13183 26301 13272 26301 13271 26302 13272 26302 14521 26302 14521 26303 13272 26303 13185 26303 14521 26304 13185 26304 14522 26304 14522 26305 13185 26305 13186 26305 14522 26306 13186 26306 14523 26306 14523 26307 13186 26307 13187 26307 14506 26308 13188 26308 14508 26308 14508 26309 13188 26309 13273 26309 14508 26310 13273 26310 13274 26310 13274 26311 13273 26311 13190 26311 13274 26312 13190 26312 13275 26312 13275 26313 13190 26313 13191 26313 13275 26314 13191 26314 14510 26314 14510 26315 13191 26315 13193 26315 14510 26316 13193 26316 13276 26316 13276 26317 13193 26317 13277 26317 13276 26318 13277 26318 14511 26318 14511 26319 13277 26319 13195 26319 14511 26320 13195 26320 13278 26320 13278 26321 13195 26321 14493 26321 13279 26322 12499 26322 12498 26322 13279 26323 12498 26323 14167 26323 14167 26324 12498 26324 13281 26324 14167 26325 13281 26325 13280 26325 13280 26326 13281 26326 13282 26326 13280 26327 13282 26327 14385 26327 14385 26328 13282 26328 12495 26328 14385 26329 12495 26329 13283 26329 13283 26330 12495 26330 12493 26330 13283 26331 12493 26331 14163 26331 14163 26332 12493 26332 12492 26332 14163 26333 12492 26333 13284 26333 13284 26334 12492 26334 12491 26334 13284 26335 12491 26335 14165 26335 14165 26336 12491 26336 13286 26336 14165 26337 13286 26337 13285 26337 13285 26338 13286 26338 13287 26338 13285 26339 13287 26339 13288 26339 13288 26340 13287 26340 12489 26340 13288 26341 12489 26341 13289 26341 13289 26342 12489 26342 12488 26342 13289 26343 12488 26343 14157 26343 14157 26344 12488 26344 13290 26344 14157 26345 13290 26345 14154 26345 14154 26346 13290 26346 12486 26346 14154 26347 12486 26347 14155 26347 14155 26348 12486 26348 12484 26348 14155 26349 12484 26349 14436 26349 14436 26350 12484 26350 12483 26350 14436 26351 12483 26351 14438 26351 14438 26352 12483 26352 14478 26352 14438 26353 14478 26353 14477 26353 14476 26354 12531 26354 13291 26354 14476 26355 13291 26355 13292 26355 13292 26356 13291 26356 13293 26356 13292 26357 13293 26357 12398 26357 12398 26358 13293 26358 12529 26358 12398 26359 12529 26359 13294 26359 13294 26360 12529 26360 13295 26360 13294 26361 13295 26361 13296 26361 13296 26362 13295 26362 13297 26362 13296 26363 13297 26363 12400 26363 12400 26364 13297 26364 13298 26364 12400 26365 13298 26365 12401 26365 12401 26366 13298 26366 12520 26366 12401 26367 12520 26367 13299 26367 13299 26368 12520 26368 13300 26368 13299 26369 13300 26369 13301 26369 13301 26370 13300 26370 13302 26370 13301 26371 13302 26371 12404 26371 12404 26372 13302 26372 13303 26372 12404 26373 13303 26373 12407 26373 12407 26374 13303 26374 12518 26374 12407 26375 12518 26375 12408 26375 12408 26376 12518 26376 12512 26376 12408 26377 12512 26377 13304 26377 13304 26378 12512 26378 12509 26378 13304 26379 12509 26379 12410 26379 12410 26380 12509 26380 12510 26380 12410 26381 12510 26381 12411 26381 12411 26382 12510 26382 13305 26382 12411 26383 13305 26383 13306 26383 13306 26384 13305 26384 13308 26384 13306 26385 13308 26385 13307 26385 13307 26386 13308 26386 13309 26386 13307 26387 13309 26387 12414 26387 12414 26388 13309 26388 12503 26388 12414 26389 12503 26389 12415 26389 12415 26390 12503 26390 13310 26390 12415 26391 13310 26391 13311 26391 15495 26392 14026 26392 15478 26392 12425 26393 14021 26393 13312 26393 13312 26394 14021 26394 13313 26394 13312 26395 13313 26395 13316 26395 13316 26396 13313 26396 13314 26396 15494 26397 12423 26397 13314 26397 13314 26398 12423 26398 13315 26398 13314 26399 13315 26399 13316 26399 13319 26400 12420 26400 15494 26400 15494 26401 12420 26401 12421 26401 15494 26402 12421 26402 12423 26402 13317 26403 13318 26403 13319 26403 13319 26404 13318 26404 13320 26404 13319 26405 13320 26405 12420 26405 15478 26406 13321 26406 15495 26406 15495 26407 13321 26407 13322 26407 15495 26408 13322 26408 13317 26408 13317 26409 13322 26409 13323 26409 13317 26410 13323 26410 13318 26410 15504 26411 14020 26411 15498 26411 15498 26412 14020 26412 13324 26412 15498 26413 13324 26413 13325 26413 13325 26414 13324 26414 13326 26414 13325 26415 13326 26415 15502 26415 15502 26416 13326 26416 12427 26416 15502 26417 12427 26417 15503 26417 15503 26418 12427 26418 13327 26418 15503 26419 13327 26419 15505 26419 15505 26420 13327 26420 12429 26420 15505 26421 12429 26421 14015 26421 14015 26422 12429 26422 15464 26422 14014 26423 13328 26423 15506 26423 15506 26424 13328 26424 12431 26424 15506 26425 12431 26425 13329 26425 13329 26426 12431 26426 12433 26426 13329 26427 12433 26427 15510 26427 15510 26428 12433 26428 13330 26428 15510 26429 13330 26429 13331 26429 13331 26430 13330 26430 13333 26430 13331 26431 13333 26431 13332 26431 13332 26432 13333 26432 12435 26432 13332 26433 12435 26433 13334 26433 13334 26434 12435 26434 15459 26434 13335 26435 15457 26435 13336 26435 13336 26436 15457 26436 13337 26436 13336 26437 13337 26437 15514 26437 15514 26438 13337 26438 12437 26438 15514 26439 12437 26439 15515 26439 15515 26440 12437 26440 12438 26440 15515 26441 12438 26441 15511 26441 15511 26442 12438 26442 13338 26442 15511 26443 13338 26443 15516 26443 15516 26444 13338 26444 12442 26444 15516 26445 12442 26445 14004 26445 14004 26446 12442 26446 12443 26446 15517 26447 14003 26447 13339 26447 13339 26448 14003 26448 13340 26448 13339 26449 13340 26449 13341 26449 13341 26450 13340 26450 13342 26450 13341 26451 13342 26451 13343 26451 13343 26452 13342 26452 12446 26452 13343 26453 12446 26453 13344 26453 13344 26454 12446 26454 12448 26454 13344 26455 12448 26455 15518 26455 15518 26456 12448 26456 12449 26456 15518 26457 12449 26457 13995 26457 13995 26458 12449 26458 15447 26458 13345 26459 13346 26459 15522 26459 15522 26460 13346 26460 13347 26460 15522 26461 13347 26461 13348 26461 13348 26462 13347 26462 13349 26462 13348 26463 13349 26463 15521 26463 15521 26464 13349 26464 13350 26464 15521 26465 13350 26465 13351 26465 13351 26466 13350 26466 12452 26466 13351 26467 12452 26467 13352 26467 13352 26468 12452 26468 12454 26468 13352 26469 12454 26469 13353 26469 13353 26470 12454 26470 15438 26470 13980 26471 13355 26471 13354 26471 13354 26472 13355 26472 12455 26472 13354 26473 12455 26473 13356 26473 13356 26474 12455 26474 12457 26474 13356 26475 12457 26475 15525 26475 15525 26476 12457 26476 12458 26476 15525 26477 12458 26477 15523 26477 15523 26478 12458 26478 12459 26478 15523 26479 12459 26479 15524 26479 15524 26480 12459 26480 13357 26480 15524 26481 13357 26481 13358 26481 13358 26482 13357 26482 15431 26482 15529 26483 13972 26483 13360 26483 13360 26484 13972 26484 13359 26484 13360 26485 13359 26485 13361 26485 13361 26486 13359 26486 13363 26486 13361 26487 13363 26487 13362 26487 13362 26488 13363 26488 12462 26488 13362 26489 12462 26489 13364 26489 13364 26490 12462 26490 12463 26490 13364 26491 12463 26491 13365 26491 13365 26492 12463 26492 12464 26492 13365 26493 12464 26493 13971 26493 13971 26494 12464 26494 15423 26494 15533 26495 12466 26495 15534 26495 15534 26496 12466 26496 12467 26496 15534 26497 12467 26497 13366 26497 13366 26498 12467 26498 12468 26498 13366 26499 12468 26499 15537 26499 15537 26500 12468 26500 12469 26500 15537 26501 12469 26501 13367 26501 13367 26502 12469 26502 12470 26502 13367 26503 12470 26503 15532 26503 15532 26504 12470 26504 13369 26504 15532 26505 13369 26505 13368 26505 13368 26506 13369 26506 12472 26506 15541 26507 12474 26507 15546 26507 15546 26508 12474 26508 13370 26508 15546 26509 13370 26509 15545 26509 15545 26510 13370 26510 12475 26510 15545 26511 12475 26511 15544 26511 15544 26512 12475 26512 12477 26512 15544 26513 12477 26513 15543 26513 15543 26514 12477 26514 13371 26514 15543 26515 13371 26515 13372 26515 13372 26516 13371 26516 12481 26516 13372 26517 12481 26517 15542 26517 15542 26518 12481 26518 13962 26518 13569 26519 13373 26519 13374 26519 13374 26520 13373 26520 13375 26520 13374 26521 13375 26521 13376 26521 13376 26522 13375 26522 10077 26522 13376 26523 10077 26523 13377 26523 13377 26524 10077 26524 10079 26524 13377 26525 10079 26525 21387 26525 21387 26526 10079 26526 10080 26526 21387 26527 10080 26527 13378 26527 13378 26528 10080 26528 10081 26528 13378 26529 10081 26529 21389 26529 21389 26530 10081 26530 13379 26530 21389 26531 13379 26531 13380 26531 13380 26532 13379 26532 13564 26532 13389 26533 13381 26533 10083 26533 10093 26534 13382 26534 13383 26534 13383 26535 13382 26535 21393 26535 13383 26536 21393 26536 10091 26536 10091 26537 21393 26537 13384 26537 21392 26538 13385 26538 13384 26538 13384 26539 13385 26539 13386 26539 13384 26540 13386 26540 10091 26540 13387 26541 10088 26541 21392 26541 21392 26542 10088 26542 10090 26542 21392 26543 10090 26543 13385 26543 10083 26544 13388 26544 13389 26544 13389 26545 13388 26545 13390 26545 13389 26546 13390 26546 13387 26546 13387 26547 13390 26547 10087 26547 13387 26548 10087 26548 10088 26548 13391 26549 13392 26549 13551 26549 13546 26550 21398 26550 10100 26550 10100 26551 21398 26551 21397 26551 10100 26552 21397 26552 10099 26552 10099 26553 21397 26553 13393 26553 21395 26554 13394 26554 13393 26554 13393 26555 13394 26555 10098 26555 13393 26556 10098 26556 10099 26556 13396 26557 13395 26557 21395 26557 21395 26558 13395 26558 10096 26558 21395 26559 10096 26559 13394 26559 21394 26560 13399 26560 13396 26560 13396 26561 13399 26561 13397 26561 13396 26562 13397 26562 13395 26562 13551 26563 10094 26563 13391 26563 13391 26564 10094 26564 10095 26564 13391 26565 10095 26565 21394 26565 21394 26566 10095 26566 13398 26566 21394 26567 13398 26567 13399 26567 13404 26568 13545 26568 20193 26568 10114 26569 21404 26569 13400 26569 13400 26570 21404 26570 21406 26570 13400 26571 21406 26571 10113 26571 10113 26572 21406 26572 21403 26572 13402 26573 10110 26573 21403 26573 21403 26574 10110 26574 10111 26574 21403 26575 10111 26575 10113 26575 13403 26576 10109 26576 13402 26576 13402 26577 10109 26577 13401 26577 13402 26578 13401 26578 10110 26578 21401 26579 10105 26579 13403 26579 13403 26580 10105 26580 10106 26580 13403 26581 10106 26581 10109 26581 20193 26582 10102 26582 13404 26582 13404 26583 10102 26583 13405 26583 13404 26584 13405 26584 21401 26584 21401 26585 13405 26585 10104 26585 21401 26586 10104 26586 10105 26586 13539 26587 13540 26587 13406 26587 13406 26588 13540 26588 13407 26588 13406 26589 13407 26589 13408 26589 13408 26590 13407 26590 13409 26590 13408 26591 13409 26591 21407 26591 21407 26592 13409 26592 13410 26592 21407 26593 13410 26593 13411 26593 13411 26594 13410 26594 13412 26594 13411 26595 13412 26595 13413 26595 13413 26596 13412 26596 10117 26596 13413 26597 10117 26597 13414 26597 13414 26598 10117 26598 13533 26598 13421 26599 13525 26599 13524 26599 13523 26600 21413 26600 13415 26600 13415 26601 21413 26601 13416 26601 13415 26602 13416 26602 10124 26602 10124 26603 13416 26603 13417 26603 13419 26604 13420 26604 13417 26604 13417 26605 13420 26605 13418 26605 13417 26606 13418 26606 10124 26606 21410 26607 13423 26607 13419 26607 13419 26608 13423 26608 10122 26608 13419 26609 10122 26609 13420 26609 13524 26610 10119 26610 13421 26610 13421 26611 10119 26611 13422 26611 13421 26612 13422 26612 21410 26612 21410 26613 13422 26613 10120 26613 21410 26614 10120 26614 13423 26614 13521 26615 20162 26615 21415 26615 21415 26616 20162 26616 10127 26616 21415 26617 10127 26617 13424 26617 13424 26618 10127 26618 13425 26618 13424 26619 13425 26619 21416 26619 21416 26620 13425 26620 13426 26620 21416 26621 13426 26621 13427 26621 13427 26622 13426 26622 13428 26622 13427 26623 13428 26623 21417 26623 21417 26624 13428 26624 10130 26624 21417 26625 10130 26625 13517 26625 13517 26626 10130 26626 20154 26626 13505 26627 13429 26627 13430 26627 13430 26628 13429 26628 13431 26628 13430 26629 13431 26629 13432 26629 13432 26630 13431 26630 13433 26630 13432 26631 13433 26631 21420 26631 21420 26632 13433 26632 10133 26632 21420 26633 10133 26633 21419 26633 21419 26634 10133 26634 13434 26634 21419 26635 13434 26635 13435 26635 13435 26636 13434 26636 13436 26636 13435 26637 13436 26637 13503 26637 13503 26638 13436 26638 13504 26638 13437 26639 20148 26639 21422 26639 21422 26640 20148 26640 13438 26640 21422 26641 13438 26641 13439 26641 13439 26642 13438 26642 13440 26642 13439 26643 13440 26643 21423 26643 21423 26644 13440 26644 13442 26644 21423 26645 13442 26645 13441 26645 13441 26646 13442 26646 13443 26646 13441 26647 13443 26647 13444 26647 13444 26648 13443 26648 10140 26648 13444 26649 10140 26649 13445 26649 13445 26650 10140 26650 10141 26650 13445 26651 10141 26651 13446 26651 13446 26652 10141 26652 13447 26652 13448 26653 13487 26653 13450 26653 13450 26654 13487 26654 13449 26654 13450 26655 13449 26655 13451 26655 13451 26656 13449 26656 10145 26656 13451 26657 10145 26657 13452 26657 13452 26658 10145 26658 13454 26658 13452 26659 13454 26659 13453 26659 13453 26660 13454 26660 13456 26660 13453 26661 13456 26661 13455 26661 13455 26662 13456 26662 10148 26662 13455 26663 10148 26663 13457 26663 13457 26664 10148 26664 20136 26664 21427 26665 13458 26665 21432 26665 21432 26666 13458 26666 13459 26666 21432 26667 13459 26667 13460 26667 13460 26668 13459 26668 10150 26668 13460 26669 10150 26669 21431 26669 21431 26670 10150 26670 10151 26670 21431 26671 10151 26671 21430 26671 21430 26672 10151 26672 10153 26672 21430 26673 10153 26673 21429 26673 21429 26674 10153 26674 10154 26674 21429 26675 10154 26675 13461 26675 13461 26676 10154 26676 13462 26676 13480 26677 20123 26677 21434 26677 21434 26678 20123 26678 13463 26678 21434 26679 13463 26679 13464 26679 13464 26680 13463 26680 13465 26680 13464 26681 13465 26681 13466 26681 13466 26682 13465 26682 13468 26682 13466 26683 13468 26683 13467 26683 13467 26684 13468 26684 10158 26684 13467 26685 10158 26685 13469 26685 13469 26686 10158 26686 10159 26686 13469 26687 10159 26687 13470 26687 13470 26688 10159 26688 10160 26688 13470 26689 10160 26689 13471 26689 13471 26690 10160 26690 20117 26690 13471 26691 20117 26691 21435 26691 21435 26692 20117 26692 20119 26692 21435 26693 20119 26693 13472 26693 13472 26694 20119 26694 13473 26694 13472 26695 13473 26695 13475 26695 13475 26696 13473 26696 13474 26696 13475 26697 13474 26697 13476 26697 13476 26698 13474 26698 13477 26698 13476 26699 13477 26699 13478 26699 13478 26700 13477 26700 13479 26700 13478 26701 13479 26701 13480 26701 13480 26702 13479 26702 20123 26702 21428 26703 13461 26703 13462 26703 13458 26704 21427 26704 20133 26704 20133 26705 21427 26705 21433 26705 20133 26706 21433 26706 13484 26706 13484 26707 21433 26707 13481 26707 13482 26708 20131 26708 13481 26708 13481 26709 20131 26709 13483 26709 13481 26710 13483 26710 13484 26710 13485 26711 20127 26711 13482 26711 13482 26712 20127 26712 20128 26712 13482 26713 20128 26713 20131 26713 13462 26714 20124 26714 21428 26714 21428 26715 20124 26715 20125 26715 21428 26716 20125 26716 13485 26716 13485 26717 20125 26717 20126 26717 13485 26718 20126 26718 20127 26718 13486 26719 13457 26719 20136 26719 13487 26720 13448 26720 20144 26720 20144 26721 13448 26721 21426 26721 20144 26722 21426 26722 20143 26722 20143 26723 21426 26723 13489 26723 13491 26724 13488 26724 13489 26724 13489 26725 13488 26725 13490 26725 13489 26726 13490 26726 20143 26726 21425 26727 13494 26727 13491 26727 13491 26728 13494 26728 13492 26728 13491 26729 13492 26729 13488 26729 20136 26730 20137 26730 13486 26730 13486 26731 20137 26731 13493 26731 13486 26732 13493 26732 21425 26732 21425 26733 13493 26733 20139 26733 21425 26734 20139 26734 13494 26734 13446 26735 13447 26735 13495 26735 13495 26736 13447 26736 13496 26736 13495 26737 13496 26737 21421 26737 21421 26738 13496 26738 13498 26738 21421 26739 13498 26739 13497 26739 13497 26740 13498 26740 13499 26740 13497 26741 13499 26741 13500 26741 13500 26742 13499 26742 13501 26742 13500 26743 13501 26743 21424 26743 21424 26744 13501 26744 13502 26744 21424 26745 13502 26745 13437 26745 13437 26746 13502 26746 20148 26746 13513 26747 13503 26747 13504 26747 13429 26748 13505 26748 20152 26748 20152 26749 13505 26749 13506 26749 20152 26750 13506 26750 20151 26750 20151 26751 13506 26751 13508 26751 13511 26752 13507 26752 13508 26752 13508 26753 13507 26753 13509 26753 13508 26754 13509 26754 20151 26754 13516 26755 13510 26755 13511 26755 13511 26756 13510 26756 13512 26756 13511 26757 13512 26757 13507 26757 13504 26758 13514 26758 13513 26758 13513 26759 13514 26759 13515 26759 13513 26760 13515 26760 13516 26760 13516 26761 13515 26761 20149 26761 13516 26762 20149 26762 13510 26762 13517 26763 20154 26763 13518 26763 13518 26764 20154 26764 20156 26764 13518 26765 20156 26765 21418 26765 21418 26766 20156 26766 20157 26766 21418 26767 20157 26767 13519 26767 13519 26768 20157 26768 20159 26768 13519 26769 20159 26769 13520 26769 13520 26770 20159 26770 20161 26770 13520 26771 20161 26771 21414 26771 21414 26772 20161 26772 13522 26772 21414 26773 13522 26773 13521 26773 13521 26774 13522 26774 20162 26774 21411 26775 21413 26775 13523 26775 13524 26776 13525 26776 13526 26776 13526 26777 13525 26777 13527 26777 13526 26778 13527 26778 13528 26778 13528 26779 13527 26779 21412 26779 13530 26780 20173 26780 21412 26780 21412 26781 20173 26781 20175 26781 21412 26782 20175 26782 13528 26782 13529 26783 20171 26783 13530 26783 13530 26784 20171 26784 20172 26784 13530 26785 20172 26785 20173 26785 13531 26786 20168 26786 13529 26786 13529 26787 20168 26787 20169 26787 13529 26788 20169 26788 20171 26788 13523 26789 20165 26789 21411 26789 21411 26790 20165 26790 20166 26790 21411 26791 20166 26791 13531 26791 13531 26792 20166 26792 13532 26792 13531 26793 13532 26793 20168 26793 13414 26794 13533 26794 13534 26794 13534 26795 13533 26795 20177 26795 13534 26796 20177 26796 13535 26796 13535 26797 20177 26797 20178 26797 13535 26798 20178 26798 21408 26798 21408 26799 20178 26799 20179 26799 21408 26800 20179 26800 13536 26800 13536 26801 20179 26801 13537 26801 13536 26802 13537 26802 13538 26802 13538 26803 13537 26803 20183 26803 13538 26804 20183 26804 21409 26804 21409 26805 20183 26805 20184 26805 21409 26806 20184 26806 13539 26806 13539 26807 20184 26807 13540 26807 21404 26808 10114 26808 13541 26808 13541 26809 10114 26809 20186 26809 13541 26810 20186 26810 21405 26810 21405 26811 20186 26811 20187 26811 21405 26812 20187 26812 13542 26812 13542 26813 20187 26813 20190 26813 13542 26814 20190 26814 21402 26814 21402 26815 20190 26815 13544 26815 21402 26816 13544 26816 13543 26816 13543 26817 13544 26817 20195 26817 13543 26818 20195 26818 13545 26818 13545 26819 20195 26819 20193 26819 21398 26820 13546 26820 13547 26820 13547 26821 13546 26821 13548 26821 13547 26822 13548 26822 21400 26822 21400 26823 13548 26823 13549 26823 21400 26824 13549 26824 13550 26824 13550 26825 13549 26825 20198 26825 13550 26826 20198 26826 21399 26826 21399 26827 20198 26827 20199 26827 21399 26828 20199 26828 21396 26828 21396 26829 20199 26829 20201 26829 21396 26830 20201 26830 13392 26830 13392 26831 20201 26831 13551 26831 13552 26832 13382 26832 10093 26832 10083 26833 13381 26833 13553 26833 13553 26834 13381 26834 13555 26834 13553 26835 13555 26835 13554 26835 13554 26836 13555 26836 13557 26836 13559 26837 13556 26837 13557 26837 13557 26838 13556 26838 20209 26838 13557 26839 20209 26839 13554 26839 13558 26840 13560 26840 13559 26840 13559 26841 13560 26841 20208 26841 13559 26842 20208 26842 13556 26842 21391 26843 20205 26843 13558 26843 13558 26844 20205 26844 13561 26844 13558 26845 13561 26845 13560 26845 10093 26846 13562 26846 13552 26846 13552 26847 13562 26847 13563 26847 13552 26848 13563 26848 21391 26848 21391 26849 13563 26849 20204 26849 21391 26850 20204 26850 20205 26850 13380 26851 13564 26851 21388 26851 21388 26852 13564 26852 13565 26852 21388 26853 13565 26853 21390 26853 21390 26854 13565 26854 13566 26854 21390 26855 13566 26855 13567 26855 13567 26856 13566 26856 20212 26856 13567 26857 20212 26857 21386 26857 21386 26858 20212 26858 20213 26858 21386 26859 20213 26859 13568 26859 13568 26860 20213 26860 13570 26860 13568 26861 13570 26861 13569 26861 13569 26862 13570 26862 13373 26862 18677 26863 13571 26863 18676 26863 18676 26864 13571 26864 15405 26864 18676 26865 15405 26865 18673 26865 18673 26866 15405 26866 15406 26866 18673 26867 15406 26867 18671 26867 18671 26868 15406 26868 13572 26868 18671 26869 13572 26869 10713 26869 10713 26870 13572 26870 13573 26870 10713 26871 13573 26871 13574 26871 13574 26872 13573 26872 12485 26872 13574 26873 12485 26873 13575 26873 13575 26874 12485 26874 13576 26874 13575 26875 13576 26875 13577 26875 13577 26876 13576 26876 12487 26876 13577 26877 12487 26877 10710 26877 10710 26878 12487 26878 13578 26878 10710 26879 13578 26879 13580 26879 13580 26880 13578 26880 13579 26880 13580 26881 13579 26881 10707 26881 10707 26882 13579 26882 13581 26882 10707 26883 13581 26883 13582 26883 13582 26884 13581 26884 12490 26884 13582 26885 12490 26885 13583 26885 13583 26886 12490 26886 13584 26886 13583 26887 13584 26887 13586 26887 13586 26888 13584 26888 13585 26888 13586 26889 13585 26889 10705 26889 10705 26890 13585 26890 12494 26890 10705 26891 12494 26891 13587 26891 13587 26892 12494 26892 13588 26892 13587 26893 13588 26893 10703 26893 10703 26894 13588 26894 13589 26894 10703 26895 13589 26895 13590 26895 13590 26896 13589 26896 12496 26896 13590 26897 12496 26897 13591 26897 13591 26898 12496 26898 12497 26898 13591 26899 12497 26899 13592 26899 13592 26900 12497 26900 13593 26900 13592 26901 13593 26901 10700 26901 10700 26902 13593 26902 13594 26902 10700 26903 13594 26903 18690 26903 18690 26904 13594 26904 15393 26904 18690 26905 15393 26905 18689 26905 18689 26906 15393 26906 13595 26906 18689 26907 13595 26907 18688 26907 18688 26908 13595 26908 15395 26908 18688 26909 15395 26909 18686 26909 18686 26910 15395 26910 15397 26910 18686 26911 15397 26911 13596 26911 13596 26912 15397 26912 15398 26912 13596 26913 15398 26913 13597 26913 13597 26914 15398 26914 15399 26914 13597 26915 15399 26915 18682 26915 18682 26916 15399 26916 13598 26916 18682 26917 13598 26917 18681 26917 18681 26918 13598 26918 13599 26918 18681 26919 13599 26919 18680 26919 18680 26920 13599 26920 13600 26920 18680 26921 13600 26921 18679 26921 18679 26922 13600 26922 13602 26922 18679 26923 13602 26923 13601 26923 13601 26924 13602 26924 13603 26924 13601 26925 13603 26925 18677 26925 18677 26926 13603 26926 13571 26926 14586 26927 16455 26927 14584 26927 14584 26928 16455 26928 11910 26928 14584 26929 11910 26929 13604 26929 13604 26930 11910 26930 13605 26930 13604 26931 13605 26931 13222 26931 13222 26932 13605 26932 11909 26932 13222 26933 11909 26933 13221 26933 13221 26934 11909 26934 11908 26934 13221 26935 11908 26935 13606 26935 13606 26936 11908 26936 11907 26936 13606 26937 11907 26937 13218 26937 13218 26938 11907 26938 13607 26938 13218 26939 13607 26939 14596 26939 14596 26940 13607 26940 11906 26940 14596 26941 11906 26941 13608 26941 13608 26942 11906 26942 13609 26942 13608 26943 13609 26943 14593 26943 14593 26944 13609 26944 13610 26944 14593 26945 13610 26945 14592 26945 14592 26946 13610 26946 13611 26946 14592 26947 13611 26947 14590 26947 14590 26948 13611 26948 13612 26948 14590 26949 13612 26949 13613 26949 13613 26950 13612 26950 13614 26950 13613 26951 13614 26951 14586 26951 14586 26952 13614 26952 16455 26952 13629 26953 13630 26953 13615 26953 13615 26954 13630 26954 11926 26954 13615 26955 11926 26955 13241 26955 13241 26956 11926 26956 11925 26956 13241 26957 11925 26957 13616 26957 13616 26958 11925 26958 11924 26958 13616 26959 11924 26959 14567 26959 14567 26960 11924 26960 16434 26960 14567 26961 16434 26961 14568 26961 14568 26962 16434 26962 13617 26962 14568 26963 13617 26963 13618 26963 13618 26964 13617 26964 13619 26964 13618 26965 13619 26965 13620 26965 13620 26966 13619 26966 13622 26966 13620 26967 13622 26967 13621 26967 13621 26968 13622 26968 13623 26968 13621 26969 13623 26969 14571 26969 14571 26970 13623 26970 16429 26970 14571 26971 16429 26971 13624 26971 13624 26972 16429 26972 13626 26972 13624 26973 13626 26973 13625 26973 13625 26974 13626 26974 11930 26974 13625 26975 11930 26975 13627 26975 13627 26976 11930 26976 13628 26976 13627 26977 13628 26977 13629 26977 13629 26978 13628 26978 13630 26978 13631 26979 13632 26979 13105 26979 13105 26980 13632 26980 12127 26980 13105 26981 12127 26981 13633 26981 13633 26982 12127 26982 12125 26982 13633 26983 12125 26983 13107 26983 13107 26984 12125 26984 12124 26984 13107 26985 12124 26985 13108 26985 13108 26986 12124 26986 13634 26986 13108 26987 13634 26987 13635 26987 13635 26988 13634 26988 12123 26988 13635 26989 12123 26989 14691 26989 14691 26990 12123 26990 16215 26990 14691 26991 16215 26991 13636 26991 13636 26992 16215 26992 16214 26992 13636 26993 16214 26993 13637 26993 13637 26994 16214 26994 16213 26994 13637 26995 16213 26995 14687 26995 14687 26996 16213 26996 13638 26996 14687 26997 13638 26997 14686 26997 14686 26998 13638 26998 16210 26998 14686 26999 16210 26999 14684 26999 14684 27000 16210 27000 13639 27000 14684 27001 13639 27001 13631 27001 13631 27002 13639 27002 13632 27002 13640 27003 13641 27003 13642 27003 13642 27004 13641 27004 13643 27004 13642 27005 13643 27005 13126 27005 13126 27006 13643 27006 12142 27006 13126 27007 12142 27007 13127 27007 13127 27008 12142 27008 13645 27008 13127 27009 13645 27009 13644 27009 13644 27010 13645 27010 13646 27010 13644 27011 13646 27011 13647 27011 13647 27012 13646 27012 13648 27012 13647 27013 13648 27013 14668 27013 14668 27014 13648 27014 16204 27014 14668 27015 16204 27015 14670 27015 14670 27016 16204 27016 16203 27016 14670 27017 16203 27017 13649 27017 13649 27018 16203 27018 13650 27018 13649 27019 13650 27019 13651 27019 13651 27020 13650 27020 13652 27020 13651 27021 13652 27021 13653 27021 13653 27022 13652 27022 16201 27022 13653 27023 16201 27023 13654 27023 13654 27024 16201 27024 12144 27024 13654 27025 12144 27025 13655 27025 13655 27026 12144 27026 13656 27026 13655 27027 13656 27027 13640 27027 13640 27028 13656 27028 13641 27028 13147 27029 12154 27029 13148 27029 13148 27030 12154 27030 13657 27030 13148 27031 13657 27031 13149 27031 13149 27032 13657 27032 13659 27032 13149 27033 13659 27033 13658 27033 13658 27034 13659 27034 16188 27034 13658 27035 16188 27035 13660 27035 13660 27036 16188 27036 13661 27036 13660 27037 13661 27037 13662 27037 13662 27038 13661 27038 16186 27038 13662 27039 16186 27039 13663 27039 13663 27040 16186 27040 16185 27040 13663 27041 16185 27041 13664 27041 13664 27042 16185 27042 16183 27042 13664 27043 16183 27043 14646 27043 14646 27044 16183 27044 13665 27044 14646 27045 13665 27045 13666 27045 13666 27046 13665 27046 13667 27046 13666 27047 13667 27047 13144 27047 13144 27048 13667 27048 12155 27048 13144 27049 12155 27049 13145 27049 13145 27050 12155 27050 13668 27050 13145 27051 13668 27051 13147 27051 13147 27052 13668 27052 12154 27052 14624 27053 16174 27053 13669 27053 13669 27054 16174 27054 16172 27054 13669 27055 16172 27055 13670 27055 13670 27056 16172 27056 13671 27056 13670 27057 13671 27057 14627 27057 14627 27058 13671 27058 13672 27058 14627 27059 13672 27059 14628 27059 14628 27060 13672 27060 13673 27060 14628 27061 13673 27061 13165 27061 13165 27062 13673 27062 13674 27062 13165 27063 13674 27063 13167 27063 13167 27064 13674 27064 12175 27064 13167 27065 12175 27065 13675 27065 13675 27066 12175 27066 12174 27066 13675 27067 12174 27067 13676 27067 13676 27068 12174 27068 13678 27068 13676 27069 13678 27069 13677 27069 13677 27070 13678 27070 12171 27070 13677 27071 12171 27071 13169 27071 13169 27072 12171 27072 12170 27072 13169 27073 12170 27073 13679 27073 13679 27074 12170 27074 12169 27074 13679 27075 12169 27075 13680 27075 13680 27076 12169 27076 16176 27076 13680 27077 16176 27077 14624 27077 14624 27078 16176 27078 16174 27078 13260 27079 13697 27079 13681 27079 13681 27080 13697 27080 11952 27080 13681 27081 11952 27081 13682 27081 13682 27082 11952 27082 13683 27082 13682 27083 13683 27083 13262 27083 13262 27084 13683 27084 13684 27084 13262 27085 13684 27085 13685 27085 13685 27086 13684 27086 11950 27086 13685 27087 11950 27087 13687 27087 13687 27088 11950 27088 13686 27088 13687 27089 13686 27089 13265 27089 13265 27090 13686 27090 13688 27090 13265 27091 13688 27091 13689 27091 13689 27092 13688 27092 13690 27092 13689 27093 13690 27093 13691 27093 13691 27094 13690 27094 16410 27094 13691 27095 16410 27095 14556 27095 14556 27096 16410 27096 13692 27096 14556 27097 13692 27097 13694 27097 13694 27098 13692 27098 13693 27098 13694 27099 13693 27099 13695 27099 13695 27100 13693 27100 16408 27100 13695 27101 16408 27101 13259 27101 13259 27102 16408 27102 13696 27102 13259 27103 13696 27103 13260 27103 13260 27104 13696 27104 13697 27104 13711 27105 13712 27105 15073 27105 15073 27106 13712 27106 16470 27106 15073 27107 16470 27107 13698 27107 13698 27108 16470 27108 16468 27108 13698 27109 16468 27109 13699 27109 13699 27110 16468 27110 13700 27110 13699 27111 13700 27111 13701 27111 13701 27112 13700 27112 16467 27112 13701 27113 16467 27113 13702 27113 13702 27114 16467 27114 13703 27114 13702 27115 13703 27115 13704 27115 13704 27116 13703 27116 13705 27116 13704 27117 13705 27117 12793 27117 12793 27118 13705 27118 13706 27118 12793 27119 13706 27119 12794 27119 12794 27120 13706 27120 11894 27120 12794 27121 11894 27121 13707 27121 13707 27122 11894 27122 11892 27122 13707 27123 11892 27123 12798 27123 12798 27124 11892 27124 13708 27124 12798 27125 13708 27125 13709 27125 13709 27126 13708 27126 11891 27126 13709 27127 11891 27127 13710 27127 13710 27128 11891 27128 16472 27128 13710 27129 16472 27129 13711 27129 13711 27130 16472 27130 13712 27130 13713 27131 13714 27131 12774 27131 12774 27132 13714 27132 11880 27132 12774 27133 11880 27133 12777 27133 12777 27134 11880 27134 11879 27134 12777 27135 11879 27135 12779 27135 12779 27136 11879 27136 13715 27136 12779 27137 13715 27137 13717 27137 13717 27138 13715 27138 13716 27138 13717 27139 13716 27139 13718 27139 13718 27140 13716 27140 16485 27140 13718 27141 16485 27141 13719 27141 13719 27142 16485 27142 13720 27142 13719 27143 13720 27143 13721 27143 13721 27144 13720 27144 16484 27144 13721 27145 16484 27145 13722 27145 13722 27146 16484 27146 16482 27146 13722 27147 16482 27147 15090 27147 15090 27148 16482 27148 13723 27148 15090 27149 13723 27149 13724 27149 13724 27150 13723 27150 16480 27150 13724 27151 16480 27151 12771 27151 12771 27152 16480 27152 11884 27152 12771 27153 11884 27153 12773 27153 12773 27154 11884 27154 13725 27154 12773 27155 13725 27155 13713 27155 13713 27156 13725 27156 13714 27156 12752 27157 13726 27157 13727 27157 13727 27158 13726 27158 13728 27158 13727 27159 13728 27159 12753 27159 12753 27160 13728 27160 13730 27160 12753 27161 13730 27161 13729 27161 13729 27162 13730 27162 13731 27162 13729 27163 13731 27163 12755 27163 12755 27164 13731 27164 11865 27164 12755 27165 11865 27165 13732 27165 13732 27166 11865 27166 13733 27166 13732 27167 13733 27167 15102 27167 15102 27168 13733 27168 13734 27168 15102 27169 13734 27169 15103 27169 15103 27170 13734 27170 13735 27170 15103 27171 13735 27171 13736 27171 13736 27172 13735 27172 13737 27172 13736 27173 13737 27173 13738 27173 13738 27174 13737 27174 13739 27174 13738 27175 13739 27175 15107 27175 15107 27176 13739 27176 13740 27176 15107 27177 13740 27177 13741 27177 13741 27178 13740 27178 16495 27178 13741 27179 16495 27179 15108 27179 15108 27180 16495 27180 13742 27180 15108 27181 13742 27181 12752 27181 12752 27182 13742 27182 13726 27182 12732 27183 13755 27183 12733 27183 12733 27184 13755 27184 13743 27184 12733 27185 13743 27185 12735 27185 12735 27186 13743 27186 13745 27186 12735 27187 13745 27187 13744 27187 13744 27188 13745 27188 11850 27188 13744 27189 11850 27189 13746 27189 13746 27190 11850 27190 11849 27190 13746 27191 11849 27191 13747 27191 13747 27192 11849 27192 16509 27192 13747 27193 16509 27193 15125 27193 15125 27194 16509 27194 13748 27194 15125 27195 13748 27195 13749 27195 13749 27196 13748 27196 13750 27196 13749 27197 13750 27197 15128 27197 15128 27198 13750 27198 16506 27198 15128 27199 16506 27199 13751 27199 13751 27200 16506 27200 16505 27200 13751 27201 16505 27201 12727 27201 12727 27202 16505 27202 16503 27202 12727 27203 16503 27203 13752 27203 13752 27204 16503 27204 13753 27204 13752 27205 13753 27205 12730 27205 12730 27206 13753 27206 13754 27206 12730 27207 13754 27207 12732 27207 12732 27208 13754 27208 13755 27208 13767 27209 16633 27209 13756 27209 13756 27210 16633 27210 16632 27210 13756 27211 16632 27211 13757 27211 13757 27212 16632 27212 13758 27212 13757 27213 13758 27213 12882 27213 12882 27214 13758 27214 13759 27214 12882 27215 13759 27215 13760 27215 13760 27216 13759 27216 11762 27216 13760 27217 11762 27217 12884 27217 12884 27218 11762 27218 13761 27218 12884 27219 13761 27219 13762 27219 13762 27220 13761 27220 13763 27220 13762 27221 13763 27221 14976 27221 14976 27222 13763 27222 13764 27222 14976 27223 13764 27223 13765 27223 13765 27224 13764 27224 16639 27224 13765 27225 16639 27225 14979 27225 14979 27226 16639 27226 16638 27226 14979 27227 16638 27227 13766 27227 13766 27228 16638 27228 16636 27228 13766 27229 16636 27229 14982 27229 14982 27230 16636 27230 16635 27230 14982 27231 16635 27231 14984 27231 14984 27232 16635 27232 16634 27232 14984 27233 16634 27233 13767 27233 13767 27234 16634 27234 16633 27234 15004 27235 13782 27235 13768 27235 13768 27236 13782 27236 13769 27236 13768 27237 13769 27237 13770 27237 13770 27238 13769 27238 13771 27238 13770 27239 13771 27239 12865 27239 12865 27240 13771 27240 13772 27240 12865 27241 13772 27241 13773 27241 13773 27242 13772 27242 11744 27242 13773 27243 11744 27243 13774 27243 13774 27244 11744 27244 11743 27244 13774 27245 11743 27245 13775 27245 13775 27246 11743 27246 11741 27246 13775 27247 11741 27247 12867 27247 12867 27248 11741 27248 11740 27248 12867 27249 11740 27249 14999 27249 14999 27250 11740 27250 16663 27250 14999 27251 16663 27251 13776 27251 13776 27252 16663 27252 13777 27252 13776 27253 13777 27253 13778 27253 13778 27254 13777 27254 16662 27254 13778 27255 16662 27255 15001 27255 15001 27256 16662 27256 13780 27256 15001 27257 13780 27257 13779 27257 13779 27258 13780 27258 13781 27258 13779 27259 13781 27259 15004 27259 15004 27260 13781 27260 13782 27260 12843 27261 12846 27261 13783 27261 13783 27262 12846 27262 12847 27262 13783 27263 12847 27263 11724 27263 11724 27264 12847 27264 13784 27264 11724 27265 13784 27265 11726 27265 11726 27266 13784 27266 12849 27266 11726 27267 12849 27267 11728 27267 11728 27268 12849 27268 13785 27268 11728 27269 13785 27269 16686 27269 16686 27270 13785 27270 12850 27270 16686 27271 12850 27271 13786 27271 13786 27272 12850 27272 15023 27272 13786 27273 15023 27273 16687 27273 16687 27274 15023 27274 15022 27274 16687 27275 15022 27275 16688 27275 16688 27276 15022 27276 13787 27276 16688 27277 13787 27277 13788 27277 13788 27278 13787 27278 13789 27278 13788 27279 13789 27279 16690 27279 16690 27280 13789 27280 13790 27280 16690 27281 13790 27281 11720 27281 11720 27282 13790 27282 13791 27282 11720 27283 13791 27283 11721 27283 11721 27284 13791 27284 12843 27284 11721 27285 12843 27285 13783 27285 13802 27286 11698 27286 13803 27286 13803 27287 11698 27287 11700 27287 13803 27288 11700 27288 13792 27288 13792 27289 11700 27289 13793 27289 13792 27290 13793 27290 12990 27290 12990 27291 13793 27291 13794 27291 12990 27292 13794 27292 12991 27292 12991 27293 13794 27293 11704 27293 12991 27294 11704 27294 13795 27294 13795 27295 11704 27295 13797 27295 13795 27296 13797 27296 13796 27296 13796 27297 13797 27297 13798 27297 13796 27298 13798 27298 14852 27298 14852 27299 13798 27299 16706 27299 14852 27300 16706 27300 13799 27300 13799 27301 16706 27301 16705 27301 13799 27302 16705 27302 13800 27302 13800 27303 16705 27303 16703 27303 13800 27304 16703 27304 14847 27304 14847 27305 16703 27305 13801 27305 14847 27306 13801 27306 14846 27306 14846 27307 13801 27307 16702 27307 14846 27308 16702 27308 12986 27308 12986 27309 16702 27309 13802 27309 12986 27310 13802 27310 13803 27310 12973 27311 11687 27311 12974 27311 12974 27312 11687 27312 13805 27312 12974 27313 13805 27313 13804 27313 13804 27314 13805 27314 13806 27314 13804 27315 13806 27315 13807 27315 13807 27316 13806 27316 11684 27316 13807 27317 11684 27317 12976 27317 12976 27318 11684 27318 11683 27318 12976 27319 11683 27319 13808 27319 13808 27320 11683 27320 13809 27320 13808 27321 13809 27321 13810 27321 13810 27322 13809 27322 11682 27322 13810 27323 11682 27323 14869 27323 14869 27324 11682 27324 13811 27324 14869 27325 13811 27325 13812 27325 13812 27326 13811 27326 13813 27326 13812 27327 13813 27327 13814 27327 13814 27328 13813 27328 13815 27328 13814 27329 13815 27329 14872 27329 14872 27330 13815 27330 16719 27330 14872 27331 16719 27331 14874 27331 14874 27332 16719 27332 16718 27332 14874 27333 16718 27333 14875 27333 14875 27334 16718 27334 13816 27334 14875 27335 13816 27335 12973 27335 12973 27336 13816 27336 11687 27336 13827 27337 13828 27337 12956 27337 12956 27338 13828 27338 13817 27338 12956 27339 13817 27339 14889 27339 14889 27340 13817 27340 13818 27340 14889 27341 13818 27341 14890 27341 14890 27342 13818 27342 13819 27342 14890 27343 13819 27343 14891 27343 14891 27344 13819 27344 13820 27344 14891 27345 13820 27345 13821 27345 13821 27346 13820 27346 16735 27346 13821 27347 16735 27347 14894 27347 14894 27348 16735 27348 13822 27348 14894 27349 13822 27349 14896 27349 14896 27350 13822 27350 16734 27350 14896 27351 16734 27351 12951 27351 12951 27352 16734 27352 11671 27352 12951 27353 11671 27353 13824 27353 13824 27354 11671 27354 13823 27354 13824 27355 13823 27355 12952 27355 12952 27356 13823 27356 11670 27356 12952 27357 11670 27357 13825 27357 13825 27358 11670 27358 11668 27358 13825 27359 11668 27359 13826 27359 13826 27360 11668 27360 11666 27360 13826 27361 11666 27361 13827 27361 13827 27362 11666 27362 13828 27362 13839 27363 16747 27363 12935 27363 12935 27364 16747 27364 13830 27364 12935 27365 13830 27365 13829 27365 13829 27366 13830 27366 11658 27366 13829 27367 11658 27367 13831 27367 13831 27368 11658 27368 11655 27368 13831 27369 11655 27369 12933 27369 12933 27370 11655 27370 13832 27370 12933 27371 13832 27371 12931 27371 12931 27372 13832 27372 11654 27372 12931 27373 11654 27373 12928 27373 12928 27374 11654 27374 13833 27374 12928 27375 13833 27375 13835 27375 13835 27376 13833 27376 13834 27376 13835 27377 13834 27377 14920 27377 14920 27378 13834 27378 16752 27378 14920 27379 16752 27379 13836 27379 13836 27380 16752 27380 13837 27380 13836 27381 13837 27381 14916 27381 14916 27382 13837 27382 13838 27382 14916 27383 13838 27383 14915 27383 14915 27384 13838 27384 16751 27384 14915 27385 16751 27385 14914 27385 14914 27386 16751 27386 16749 27386 14914 27387 16749 27387 13839 27387 13839 27388 16749 27388 16747 27388 13854 27389 13840 27389 13060 27389 13060 27390 13840 27390 11568 27390 13060 27391 11568 27391 13841 27391 13841 27392 11568 27392 13842 27392 13841 27393 13842 27393 13064 27393 13064 27394 13842 27394 11567 27394 13064 27395 11567 27395 13066 27395 13066 27396 11567 27396 13843 27396 13066 27397 13843 27397 13067 27397 13067 27398 13843 27398 13844 27398 13067 27399 13844 27399 13069 27399 13069 27400 13844 27400 13845 27400 13069 27401 13845 27401 14765 27401 14765 27402 13845 27402 13846 27402 14765 27403 13846 27403 13847 27403 13847 27404 13846 27404 13848 27404 13847 27405 13848 27405 13849 27405 13849 27406 13848 27406 16885 27406 13849 27407 16885 27407 13850 27407 13850 27408 16885 27408 16884 27408 13850 27409 16884 27409 13851 27409 13851 27410 16884 27410 13852 27410 13851 27411 13852 27411 13853 27411 13853 27412 13852 27412 11570 27412 13853 27413 11570 27413 13854 27413 13854 27414 11570 27414 13840 27414 13863 27415 13855 27415 13042 27415 13042 27416 13855 27416 11543 27416 13042 27417 11543 27417 13856 27417 13856 27418 11543 27418 11541 27418 13856 27419 11541 27419 13045 27419 13045 27420 11541 27420 13857 27420 13045 27421 13857 27421 14780 27421 14780 27422 13857 27422 11539 27422 14780 27423 11539 27423 14781 27423 14781 27424 11539 27424 16903 27424 14781 27425 16903 27425 13858 27425 13858 27426 16903 27426 16902 27426 13858 27427 16902 27427 13859 27427 13859 27428 16902 27428 16901 27428 13859 27429 16901 27429 14783 27429 14783 27430 16901 27430 13860 27430 14783 27431 13860 27431 13861 27431 13861 27432 13860 27432 13862 27432 13861 27433 13862 27433 14786 27433 14786 27434 13862 27434 11544 27434 14786 27435 11544 27435 13039 27435 13039 27436 11544 27436 13864 27436 13039 27437 13864 27437 13863 27437 13863 27438 13864 27438 13855 27438 13872 27439 16918 27439 13019 27439 13019 27440 16918 27440 16916 27440 13019 27441 16916 27441 13020 27441 13020 27442 16916 27442 13865 27442 13020 27443 13865 27443 13022 27443 13022 27444 13865 27444 13866 27444 13022 27445 13866 27445 13024 27445 13024 27446 13866 27446 11524 27446 13024 27447 11524 27447 13867 27447 13867 27448 11524 27448 13868 27448 13867 27449 13868 27449 13026 27449 13026 27450 13868 27450 13869 27450 13026 27451 13869 27451 14807 27451 14807 27452 13869 27452 16924 27452 14807 27453 16924 27453 14808 27453 14808 27454 16924 27454 16923 27454 14808 27455 16923 27455 14810 27455 14810 27456 16923 27456 16922 27456 14810 27457 16922 27457 14804 27457 14804 27458 16922 27458 16921 27458 14804 27459 16921 27459 13870 27459 13870 27460 16921 27460 13871 27460 13870 27461 13871 27461 13872 27461 13872 27462 13871 27462 16918 27462 13886 27463 13873 27463 13874 27463 13874 27464 13873 27464 11507 27464 13874 27465 11507 27465 13876 27465 13876 27466 11507 27466 13875 27466 13876 27467 13875 27467 13877 27467 13877 27468 13875 27468 13878 27468 13877 27469 13878 27469 12605 27469 12605 27470 13878 27470 11513 27470 12605 27471 11513 27471 15285 27471 15285 27472 11513 27472 11512 27472 15285 27473 11512 27473 13879 27473 13879 27474 11512 27474 13881 27474 13879 27475 13881 27475 13880 27475 13880 27476 13881 27476 16937 27476 13880 27477 16937 27477 13882 27477 13882 27478 16937 27478 13883 27478 13882 27479 13883 27479 15282 27479 15282 27480 13883 27480 16935 27480 15282 27481 16935 27481 15280 27481 15280 27482 16935 27482 13884 27482 15280 27483 13884 27483 12601 27483 12601 27484 13884 27484 16933 27484 12601 27485 16933 27485 13886 27485 13886 27486 16933 27486 13885 27486 13886 27487 13885 27487 13873 27487 13898 27488 13887 27488 15307 27488 15307 27489 13887 27489 16946 27489 15307 27490 16946 27490 13888 27490 13888 27491 16946 27491 11495 27491 13888 27492 11495 27492 13889 27492 13889 27493 11495 27493 11494 27493 13889 27494 11494 27494 13890 27494 13890 27495 11494 27495 11493 27495 13890 27496 11493 27496 12585 27496 12585 27497 11493 27497 11492 27497 12585 27498 11492 27498 13892 27498 13892 27499 11492 27499 13891 27499 13892 27500 13891 27500 12586 27500 12586 27501 13891 27501 13893 27501 12586 27502 13893 27502 12587 27502 12587 27503 13893 27503 13894 27503 12587 27504 13894 27504 15302 27504 15302 27505 13894 27505 16952 27505 15302 27506 16952 27506 15304 27506 15304 27507 16952 27507 16951 27507 15304 27508 16951 27508 13895 27508 13895 27509 16951 27509 13897 27509 13895 27510 13897 27510 13896 27510 13896 27511 13897 27511 16949 27511 13896 27512 16949 27512 13898 27512 13898 27513 16949 27513 13887 27513 13911 27514 13912 27514 12568 27514 12568 27515 13912 27515 13899 27515 12568 27516 13899 27516 12569 27516 12569 27517 13899 27517 11473 27517 12569 27518 11473 27518 13901 27518 13901 27519 11473 27519 13900 27519 13901 27520 13900 27520 13902 27520 13902 27521 13900 27521 13903 27521 13902 27522 13903 27522 13904 27522 13904 27523 13903 27523 16966 27523 13904 27524 16966 27524 15323 27524 15323 27525 16966 27525 16964 27525 15323 27526 16964 27526 15324 27526 15324 27527 16964 27527 13905 27527 15324 27528 13905 27528 13906 27528 13906 27529 13905 27529 16963 27529 13906 27530 16963 27530 13907 27530 13907 27531 16963 27531 16962 27531 13907 27532 16962 27532 13908 27532 13908 27533 16962 27533 13909 27533 13908 27534 13909 27534 12566 27534 12566 27535 13909 27535 11476 27535 12566 27536 11476 27536 13910 27536 13910 27537 11476 27537 11474 27537 13910 27538 11474 27538 13911 27538 13911 27539 11474 27539 13912 27539 13921 27540 11462 27540 13913 27540 13913 27541 11462 27541 11459 27541 13913 27542 11459 27542 13914 27542 13914 27543 11459 27543 11458 27543 13914 27544 11458 27544 12548 27544 12548 27545 11458 27545 11456 27545 12548 27546 11456 27546 12549 27546 12549 27547 11456 27547 11455 27547 12549 27548 11455 27548 13915 27548 13915 27549 11455 27549 16977 27549 13915 27550 16977 27550 13916 27550 13916 27551 16977 27551 13917 27551 13916 27552 13917 27552 15352 27552 15352 27553 13917 27553 16976 27553 15352 27554 16976 27554 13918 27554 13918 27555 16976 27555 16974 27555 13918 27556 16974 27556 15345 27556 15345 27557 16974 27557 16973 27557 15345 27558 16973 27558 15343 27558 15343 27559 16973 27559 13920 27559 15343 27560 13920 27560 13919 27560 13919 27561 13920 27561 13922 27561 13919 27562 13922 27562 13921 27562 13921 27563 13922 27563 11462 27563 13923 27564 17109 27564 12691 27564 12691 27565 17109 27565 13924 27565 12691 27566 13924 27566 12693 27566 12693 27567 13924 27567 11379 27567 12693 27568 11379 27568 13925 27568 13925 27569 11379 27569 11377 27569 13925 27570 11377 27570 12689 27570 12689 27571 11377 27571 13926 27571 12689 27572 13926 27572 12686 27572 12686 27573 13926 27573 13927 27573 12686 27574 13927 27574 12684 27574 12684 27575 13927 27575 11373 27575 12684 27576 11373 27576 15208 27576 15208 27577 11373 27577 13928 27577 15208 27578 13928 27578 15210 27578 15210 27579 13928 27579 13929 27579 15210 27580 13929 27580 15206 27580 15206 27581 13929 27581 17113 27581 15206 27582 17113 27582 15204 27582 15204 27583 17113 27583 17111 27583 15204 27584 17111 27584 15203 27584 15203 27585 17111 27585 13930 27585 15203 27586 13930 27586 13931 27586 13931 27587 13930 27587 17110 27587 13931 27588 17110 27588 13923 27588 13923 27589 17110 27589 17109 27589 13932 27590 11351 27590 12664 27590 12664 27591 11351 27591 13933 27591 12664 27592 13933 27592 13934 27592 13934 27593 13933 27593 11347 27593 13934 27594 11347 27594 13935 27594 13935 27595 11347 27595 11345 27595 13935 27596 11345 27596 15224 27596 15224 27597 11345 27597 13936 27597 15224 27598 13936 27598 13937 27598 13937 27599 13936 27599 17139 27599 13937 27600 17139 27600 15226 27600 15226 27601 17139 27601 13938 27601 15226 27602 13938 27602 15227 27602 15227 27603 13938 27603 17137 27603 15227 27604 17137 27604 15230 27604 15230 27605 17137 27605 13939 27605 15230 27606 13939 27606 13940 27606 13940 27607 13939 27607 13941 27607 13940 27608 13941 27608 12660 27608 12660 27609 13941 27609 11354 27609 12660 27610 11354 27610 13943 27610 13943 27611 11354 27611 13942 27611 13943 27612 13942 27612 12662 27612 12662 27613 13942 27613 11352 27613 12662 27614 11352 27614 13932 27614 13932 27615 11352 27615 11351 27615 11325 27616 13944 27616 12642 27616 12642 27617 13944 27617 11323 27617 12642 27618 11323 27618 13945 27618 13945 27619 11323 27619 13947 27619 13945 27620 13947 27620 13946 27620 13946 27621 13947 27621 13948 27621 13946 27622 13948 27622 15243 27622 15243 27623 13948 27623 17159 27623 15243 27624 17159 27624 15244 27624 15244 27625 17159 27625 17158 27625 15244 27626 17158 27626 15246 27626 15246 27627 17158 27627 17156 27627 15246 27628 17156 27628 13949 27628 13949 27629 17156 27629 13950 27629 13949 27630 13950 27630 13951 27630 13951 27631 13950 27631 17153 27631 13951 27632 17153 27632 13952 27632 13952 27633 17153 27633 13953 27633 13952 27634 13953 27634 13954 27634 13954 27635 13953 27635 17151 27635 13954 27636 17151 27636 13955 27636 13955 27637 17151 27637 13956 27637 13955 27638 13956 27638 12641 27638 12641 27639 13956 27639 11325 27639 12641 27640 11325 27640 12642 27640 15539 27641 15542 27641 13962 27641 12474 27642 15541 27642 15412 27642 15412 27643 15541 27643 13957 27643 15412 27644 13957 27644 15410 27644 15410 27645 13957 27645 13960 27645 13958 27646 15409 27646 13960 27646 13960 27647 15409 27647 13959 27647 13960 27648 13959 27648 15410 27648 15540 27649 13965 27649 13958 27649 13958 27650 13965 27650 13961 27650 13958 27651 13961 27651 15409 27651 13962 27652 13963 27652 15539 27652 15539 27653 13963 27653 13964 27653 15539 27654 13964 27654 15540 27654 15540 27655 13964 27655 15408 27655 15540 27656 15408 27656 13965 27656 13368 27657 12472 27657 15536 27657 15536 27658 12472 27658 15414 27658 15536 27659 15414 27659 15535 27659 15535 27660 15414 27660 13966 27660 15535 27661 13966 27661 13967 27661 13967 27662 13966 27662 15416 27662 13967 27663 15416 27663 15538 27663 15538 27664 15416 27664 15419 27664 15538 27665 15419 27665 13968 27665 13968 27666 15419 27666 13970 27666 13968 27667 13970 27667 13969 27667 13969 27668 13970 27668 15421 27668 13969 27669 15421 27669 15533 27669 15533 27670 15421 27670 12466 27670 15528 27671 13971 27671 15423 27671 13972 27672 15529 27672 15430 27672 15430 27673 15529 27673 13973 27673 15430 27674 13973 27674 15427 27674 15427 27675 13973 27675 15530 27675 15531 27676 15425 27676 15530 27676 15530 27677 15425 27677 15426 27677 15530 27678 15426 27678 15427 27678 13979 27679 13974 27679 15531 27679 15531 27680 13974 27680 13975 27680 15531 27681 13975 27681 15425 27681 15423 27682 13976 27682 15528 27682 15528 27683 13976 27683 13977 27683 15528 27684 13977 27684 13979 27684 13979 27685 13977 27685 13978 27685 13979 27686 13978 27686 13974 27686 13985 27687 13358 27687 15431 27687 13355 27688 13980 27688 13981 27688 13981 27689 13980 27689 15526 27689 13981 27690 15526 27690 13982 27690 13982 27691 15526 27691 15527 27691 13984 27692 13983 27692 15527 27692 15527 27693 13983 27693 15436 27693 15527 27694 15436 27694 13982 27694 13988 27695 15433 27695 13984 27695 13984 27696 15433 27696 15434 27696 13984 27697 15434 27697 13983 27697 15431 27698 13986 27698 13985 27698 13985 27699 13986 27699 13987 27699 13985 27700 13987 27700 13988 27700 13988 27701 13987 27701 13989 27701 13988 27702 13989 27702 15433 27702 13353 27703 15438 27703 13990 27703 13990 27704 15438 27704 15441 27704 13990 27705 15441 27705 15520 27705 15520 27706 15441 27706 15442 27706 15520 27707 15442 27707 13991 27707 13991 27708 15442 27708 15443 27708 13991 27709 15443 27709 13992 27709 13992 27710 15443 27710 13993 27710 13992 27711 13993 27711 13994 27711 13994 27712 13993 27712 15445 27712 13994 27713 15445 27713 13345 27713 13345 27714 15445 27714 13346 27714 13995 27715 15447 27715 15519 27715 15519 27716 15447 27716 15448 27716 15519 27717 15448 27717 13996 27717 13996 27718 15448 27718 13998 27718 13996 27719 13998 27719 13997 27719 13997 27720 13998 27720 15450 27720 13997 27721 15450 27721 13999 27721 13999 27722 15450 27722 14000 27722 13999 27723 14000 27723 14001 27723 14001 27724 14000 27724 14002 27724 14001 27725 14002 27725 15517 27725 15517 27726 14002 27726 14003 27726 14004 27727 12443 27727 14005 27727 14005 27728 12443 27728 15453 27728 14005 27729 15453 27729 15512 27729 15512 27730 15453 27730 15455 27730 15512 27731 15455 27731 14006 27731 14006 27732 15455 27732 15456 27732 14006 27733 15456 27733 14007 27733 14007 27734 15456 27734 14008 27734 14007 27735 14008 27735 15513 27735 15513 27736 14008 27736 14009 27736 15513 27737 14009 27737 13335 27737 13335 27738 14009 27738 15457 27738 13334 27739 15459 27739 14011 27739 14011 27740 15459 27740 14010 27740 14011 27741 14010 27741 14012 27741 14012 27742 14010 27742 14013 27742 14012 27743 14013 27743 15507 27743 15507 27744 14013 27744 15460 27744 15507 27745 15460 27745 15508 27745 15508 27746 15460 27746 15461 27746 15508 27747 15461 27747 15509 27747 15509 27748 15461 27748 15462 27748 15509 27749 15462 27749 14014 27749 14014 27750 15462 27750 13328 27750 14015 27751 15464 27751 15497 27751 15497 27752 15464 27752 15465 27752 15497 27753 15465 27753 15499 27753 15499 27754 15465 27754 14016 27754 15499 27755 14016 27755 15500 27755 15500 27756 14016 27756 14017 27756 15500 27757 14017 27757 15501 27757 15501 27758 14017 27758 15468 27758 15501 27759 15468 27759 14018 27759 14018 27760 15468 27760 14019 27760 14018 27761 14019 27761 15504 27761 15504 27762 14019 27762 14020 27762 14021 27763 12425 27763 15496 27763 15496 27764 12425 27764 14022 27764 15496 27765 14022 27765 14023 27765 14023 27766 14022 27766 15471 27766 14023 27767 15471 27767 14024 27767 14024 27768 15471 27768 15473 27768 14024 27769 15473 27769 15493 27769 15493 27770 15473 27770 15475 27770 15493 27771 15475 27771 14025 27771 14025 27772 15475 27772 15477 27772 14025 27773 15477 27773 14026 27773 14026 27774 15477 27774 15478 27774 14223 27775 14220 27775 14422 27775 14376 27776 14027 27776 14377 27776 15373 27777 14363 27777 14360 27777 15378 27778 14427 27778 14028 27778 14029 27779 14352 27779 15376 27779 14030 27780 12428 27780 14404 27780 14147 27781 14105 27781 14031 27781 12527 27782 14264 27782 12528 27782 15439 27783 14032 27783 14247 27783 14163 27784 14162 27784 13283 27784 14033 27785 14153 27785 14483 27785 14623 27786 14290 27786 14284 27786 14034 27787 14618 27787 14160 27787 14663 27788 14662 27788 14126 27788 15388 27789 15387 27789 14035 27789 12756 27790 15058 27790 12758 27790 12758 27791 15058 27791 15057 27791 12758 27792 15057 27792 14194 27792 14194 27793 15057 27793 15056 27793 12756 27794 15100 27794 15058 27794 15058 27795 15100 27795 14430 27795 15058 27796 14430 27796 15060 27796 15060 27797 14430 27797 14036 27797 14042 27798 14037 27798 14414 27798 15123 27799 15122 27799 14042 27799 15123 27800 14042 27800 12737 27800 12812 27801 15117 27801 14038 27801 15117 27802 12742 27802 14038 27802 14038 27803 12742 27803 14039 27803 14038 27804 14039 27804 14040 27804 14040 27805 14039 27805 14041 27805 14040 27806 14041 27806 12740 27806 14331 27807 12737 27807 14336 27807 15122 27808 14043 27808 14042 27808 14042 27809 14043 27809 15121 27809 14042 27810 15121 27810 14037 27810 14037 27811 15121 27811 15120 27811 14037 27812 15120 27812 12812 27812 12812 27813 15120 27813 15118 27813 12812 27814 15118 27814 15117 27814 14035 27815 14044 27815 15388 27815 15388 27816 14044 27816 12809 27816 15388 27817 12809 27817 15384 27817 15384 27818 12809 27818 14045 27818 15384 27819 14045 27819 14038 27819 14038 27820 14045 27820 12813 27820 14038 27821 12813 27821 12812 27821 14053 27822 14046 27822 14246 27822 14246 27823 14046 27823 14047 27823 14047 27824 15069 27824 14048 27824 14048 27825 15069 27825 14049 27825 14048 27826 14049 27826 14340 27826 14340 27827 14049 27827 15067 27827 14340 27828 15067 27828 15065 27828 12804 27829 15379 27829 14052 27829 15065 27830 14050 27830 14340 27830 14340 27831 14050 27831 14051 27831 14340 27832 14051 27832 14338 27832 14338 27833 14051 27833 12800 27833 14338 27834 12800 27834 14052 27834 14052 27835 12800 27835 12802 27835 14052 27836 12802 27836 12804 27836 12805 27837 14053 27837 14247 27837 14054 27838 14055 27838 14291 27838 14291 27839 14055 27839 12996 27839 12995 27840 14056 27840 14396 27840 14396 27841 14056 27841 14057 27841 14396 27842 14057 27842 12919 27842 12919 27843 14057 27843 14066 27843 14069 27844 14058 27844 14280 27844 14280 27845 14058 27845 14059 27845 14280 27846 14059 27846 12521 27846 14059 27847 14060 27847 12521 27847 12521 27848 14060 27848 14061 27848 12521 27849 14061 27849 14103 27849 14103 27850 14061 27850 14934 27850 14103 27851 14934 27851 14063 27851 14063 27852 14934 27852 14062 27852 14063 27853 14062 27853 12993 27853 12993 27854 14062 27854 14065 27854 12993 27855 14065 27855 14064 27855 14064 27856 14065 27856 14067 27856 14064 27857 14067 27857 14066 27857 14066 27858 14067 27858 14068 27858 14066 27859 14068 27859 12919 27859 14397 27860 14398 27860 14400 27860 14400 27861 14398 27861 12918 27861 14400 27862 12918 27862 14069 27862 14069 27863 12918 27863 12916 27863 14069 27864 12916 27864 14058 27864 12938 27865 14073 27865 14070 27865 12941 27866 12940 27866 14411 27866 14411 27867 12940 27867 14071 27867 14075 27868 14076 27868 14089 27868 14070 27869 14073 27869 14072 27869 14072 27870 14073 27870 12937 27870 14072 27871 12937 27871 14088 27871 14903 27872 14412 27872 14074 27872 14074 27873 14412 27873 14278 27873 14074 27874 14278 27874 14905 27874 14905 27875 14278 27875 14077 27875 14075 27876 14909 27876 14076 27876 14076 27877 14909 27877 14907 27877 14076 27878 14907 27878 14077 27878 14077 27879 14907 27879 14906 27879 14077 27880 14906 27880 14905 27880 14078 27881 14829 27881 14257 27881 14257 27882 14829 27882 14079 27882 14257 27883 14079 27883 14375 27883 14375 27884 14079 27884 14827 27884 14375 27885 14827 27885 14080 27885 14081 27886 14082 27886 14376 27886 14376 27887 14082 27887 14083 27887 14376 27888 14083 27888 13006 27888 13005 27889 13004 27889 14084 27889 14084 27890 13004 27890 14260 27890 14085 27891 14086 27891 14228 27891 14228 27892 14086 27892 13005 27892 14087 27893 13003 27893 14162 27893 14087 27894 14411 27894 14070 27894 14070 27895 14411 27895 14071 27895 14070 27896 14071 27896 12938 27896 12937 27897 14075 27897 14088 27897 14088 27898 14075 27898 14089 27898 14088 27899 14089 27899 14090 27899 14090 27900 14089 27900 14835 27900 14270 27901 12961 27901 14091 27901 12525 27902 14092 27902 14098 27902 14098 27903 14092 27903 14093 27903 14098 27904 14093 27904 14886 27904 14097 27905 14884 27905 14883 27905 12963 27906 14094 27906 14383 27906 14383 27907 14094 27907 14095 27907 14383 27908 14095 27908 14270 27908 14270 27909 14095 27909 14096 27909 14270 27910 14096 27910 12961 27910 14884 27911 14097 27911 14885 27911 14885 27912 14097 27912 12997 27912 14885 27913 12997 27913 14886 27913 12997 27914 14830 27914 14886 27914 14886 27915 14830 27915 14832 27915 14886 27916 14832 27916 14098 27916 14098 27917 14832 27917 14835 27917 14098 27918 14835 27918 12523 27918 12523 27919 14835 27919 14089 27919 14099 27920 12999 27920 14100 27920 14100 27921 12999 27921 14097 27921 14100 27922 14097 27922 14383 27922 14383 27923 14097 27923 14883 27923 14383 27924 14883 27924 12963 27924 14063 27925 14101 27925 14103 27925 14103 27926 14101 27926 14102 27926 14103 27927 14102 27927 12519 27927 12519 27928 14102 27928 14104 27928 12519 27929 14104 27929 14283 27929 14708 27930 14105 27930 14106 27930 14106 27931 14105 27931 14107 27931 14106 27932 14107 27932 13092 27932 13092 27933 14107 27933 14110 27933 14031 27934 14109 27934 12515 27934 12515 27935 14109 27935 14108 27935 12515 27936 14108 27936 12516 27936 14708 27937 14707 27937 14105 27937 14105 27938 14707 27938 14705 27938 14105 27939 14705 27939 14031 27939 14031 27940 14705 27940 14704 27940 14031 27941 14704 27941 14109 27941 14110 27942 14111 27942 13093 27942 13093 27943 14111 27943 14294 27943 13093 27944 14294 27944 13094 27944 13094 27945 14294 27945 14292 27945 13094 27946 14292 27946 14112 27946 14112 27947 14292 27947 14703 27947 14113 27948 14618 27948 13115 27948 13115 27949 14618 27949 14140 27949 13115 27950 14140 27950 14120 27950 14113 27951 14114 27951 14618 27951 14618 27952 14114 27952 14115 27952 14618 27953 14115 27953 14160 27953 14160 27954 14115 27954 14116 27954 14160 27955 14116 27955 13112 27955 14681 27956 14117 27956 14118 27956 14118 27957 14117 27957 14678 27957 14118 27958 14678 27958 14119 27958 14119 27959 14678 27959 14677 27959 14119 27960 14677 27960 14120 27960 14681 27961 14118 27961 14121 27961 14121 27962 14118 27962 12508 27962 14121 27963 12508 27963 13111 27963 13111 27964 12508 27964 14404 27964 13111 27965 14404 27965 13112 27965 13132 27966 13130 27966 14122 27966 14122 27967 13130 27967 14123 27967 14133 27968 14124 27968 14616 27968 14616 27969 14124 27969 14125 27969 14616 27970 14125 27970 12511 27970 14663 27971 14126 27971 14127 27971 14127 27972 14126 27972 14128 27972 14127 27973 14128 27973 14665 27973 14665 27974 14128 27974 13184 27974 14665 27975 13184 27975 14123 27975 12504 27976 14129 27976 14300 27976 14300 27977 14129 27977 14130 27977 13132 27978 14122 27978 14131 27978 14131 27979 14122 27979 14428 27979 14131 27980 14428 27980 13135 27980 13135 27981 14428 27981 14298 27981 13135 27982 14298 27982 14132 27982 14130 27983 14129 27983 14661 27983 14661 27984 14129 27984 14124 27984 14661 27985 14124 27985 14662 27985 14662 27986 14124 27986 14133 27986 14662 27987 14133 27987 14126 27987 14134 27988 14306 27988 14645 27988 14645 27989 14306 27989 14135 27989 14645 27990 14135 27990 13151 27990 13151 27991 14433 27991 14136 27991 14136 27992 14433 27992 14309 27992 14136 27993 14309 27993 14137 27993 14137 27994 14309 27994 13155 27994 14139 27995 14638 27995 12501 27995 12501 27996 14638 27996 13159 27996 12501 27997 13159 27997 12502 27997 12502 27998 13159 27998 13158 27998 12502 27999 13158 27999 13156 27999 14134 28000 14642 28000 14306 28000 14306 28001 14642 28001 14138 28001 14306 28002 14138 28002 14139 28002 14139 28003 14138 28003 14640 28003 14139 28004 14640 28004 14638 28004 14120 28005 14140 28005 14119 28005 14119 28006 14140 28006 14141 28006 14119 28007 14141 28007 12511 28007 12511 28008 14141 28008 14142 28008 12511 28009 14142 28009 14616 28009 14123 28010 13184 28010 14122 28010 14122 28011 13184 28011 14143 28011 14122 28012 14143 28012 14158 28012 14158 28013 14143 28013 13182 28013 14158 28014 13182 28014 13179 28014 14623 28015 14284 28015 13171 28015 13177 28016 13174 28016 14107 28016 14107 28017 13174 28017 13172 28017 14107 28018 13172 28018 14395 28018 14395 28019 13172 28019 14144 28019 14395 28020 14144 28020 13171 28020 12517 28021 14289 28021 14145 28021 14145 28022 14146 28022 12517 28022 12517 28023 14146 28023 14621 28023 12517 28024 14621 28024 14147 28024 14147 28025 14621 28025 14148 28025 14147 28026 14148 28026 14105 28026 14105 28027 14148 28027 14149 28027 14105 28028 14149 28028 14107 28028 14107 28029 14149 28029 13178 28029 14107 28030 13178 28030 13177 28030 14492 28031 14391 28031 14491 28031 14491 28032 14391 28032 14390 28032 14421 28033 14488 28033 14150 28033 14150 28034 14488 28034 14151 28034 14150 28035 14151 28035 14380 28035 14486 28036 14418 28036 14484 28036 14484 28037 14418 28037 14416 28037 14484 28038 14416 28038 14033 28038 14033 28039 14416 28039 14415 28039 14033 28040 14415 28040 14153 28040 14483 28041 14153 28041 14152 28041 14152 28042 14153 28042 14441 28042 14152 28043 14441 28043 14481 28043 14447 28044 14477 28044 14442 28044 14157 28045 14154 28045 14158 28045 14158 28046 14154 28046 14155 28046 14158 28047 14155 28047 14122 28047 14161 28048 13289 28048 14156 28048 14156 28049 13289 28049 14157 28049 14156 28050 14157 28050 14159 28050 14159 28051 14157 28051 14158 28051 14159 28052 14158 28052 14160 28052 14160 28053 14158 28053 13179 28053 14160 28054 13179 28054 14034 28054 14409 28055 13285 28055 14161 28055 14161 28056 13285 28056 13288 28056 14161 28057 13288 28057 13289 28057 14087 28058 14162 28058 14411 28058 14411 28059 14162 28059 14163 28059 14411 28060 14163 28060 14164 28060 14164 28061 14163 28061 13284 28061 14164 28062 13284 28062 14409 28062 14409 28063 13284 28063 14165 28063 14409 28064 14165 28064 13285 28064 14166 28065 13280 28065 14385 28065 13280 28066 14166 28066 14167 28066 14167 28067 14166 28067 14386 28067 14167 28068 14386 28068 14373 28068 14316 28069 14443 28069 15086 28069 15086 28070 14443 28070 12780 28070 12780 28071 14168 28071 14169 28071 14169 28072 14168 28072 14170 28072 14169 28073 14170 28073 12781 28073 12781 28074 14170 28074 12782 28074 14171 28075 14172 28075 12784 28075 12784 28076 14172 28076 14173 28076 12784 28077 14173 28077 14174 28077 15048 28078 14176 28078 14316 28078 14316 28079 14176 28079 14175 28079 14316 28080 14175 28080 12500 28080 14176 28081 14177 28081 14175 28081 14175 28082 14177 28082 15052 28082 14175 28083 15052 28083 14179 28083 14179 28084 15052 28084 15051 28084 15051 28085 14178 28085 14179 28085 14179 28086 14178 28086 12817 28086 14179 28087 12817 28087 14173 28087 14173 28088 12817 28088 12818 28088 14173 28089 12818 28089 14180 28089 14174 28090 14173 28090 15081 28090 15081 28091 14173 28091 14180 28091 15081 28092 14180 28092 15082 28092 15082 28093 14180 28093 14181 28093 14181 28094 14180 28094 12821 28094 14181 28095 12821 28095 14182 28095 14182 28096 12821 28096 12822 28096 14182 28097 12822 28097 14183 28097 14183 28098 12822 28098 12825 28098 14183 28099 12825 28099 15086 28099 15086 28100 12825 28100 12823 28100 15086 28101 12823 28101 14316 28101 14316 28102 12823 28102 14184 28102 14316 28103 14184 28103 15048 28103 15100 28104 14185 28104 14430 28104 14430 28105 14185 28105 14186 28105 14430 28106 14186 28106 14187 28106 14187 28107 14186 28107 14188 28107 14187 28108 14188 28108 14321 28108 14321 28109 14188 28109 14189 28109 14321 28110 14189 28110 14319 28110 14190 28111 12762 28111 14191 28111 14191 28112 12762 28112 12761 28112 14191 28113 12761 28113 14192 28113 14192 28114 12761 28114 14193 28114 14192 28115 14193 28115 15387 28115 15387 28116 14193 28116 14194 28116 15387 28117 14194 28117 14035 28117 14035 28118 14194 28118 15056 28118 14206 28119 14207 28119 14196 28119 15276 28120 14204 28120 14245 28120 12535 28121 14208 28121 12536 28121 12536 28122 14208 28122 14195 28122 12536 28123 14195 28123 12537 28123 14206 28124 14196 28124 14197 28124 14197 28125 14196 28125 12533 28125 14197 28126 12533 28126 14029 28126 14029 28127 12533 28127 14198 28127 14029 28128 14198 28128 14352 28128 14352 28129 14198 28129 14199 28129 14352 28130 14199 28130 15366 28130 14392 28131 14200 28131 14393 28131 15366 28132 15364 28132 14352 28132 14352 28133 15364 28133 14201 28133 14352 28134 14201 28134 14392 28134 14200 28135 14392 28135 15274 28135 15274 28136 14392 28136 14201 28136 15274 28137 14201 28137 15272 28137 14201 28138 15363 28138 15272 28138 15272 28139 15363 28139 15362 28139 15272 28140 15362 28140 14202 28140 14202 28141 15362 28141 12537 28141 14202 28142 12537 28142 14203 28142 14203 28143 12537 28143 14195 28143 14204 28144 12610 28144 14253 28144 14253 28145 12610 28145 14205 28145 14253 28146 14205 28146 14252 28146 12610 28147 12609 28147 14205 28147 14205 28148 12609 28148 12608 28148 14205 28149 12608 28149 14206 28149 14206 28150 12608 28150 14208 28150 14206 28151 14208 28151 14207 28151 14207 28152 14208 28152 12535 28152 14367 28153 15268 28153 14381 28153 12614 28154 12613 28154 14219 28154 14219 28155 12613 28155 15269 28155 14219 28156 15269 28156 12571 28156 15318 28157 15317 28157 14367 28157 15317 28158 14209 28158 14367 28158 14367 28159 14209 28159 15316 28159 14367 28160 15316 28160 15268 28160 15268 28161 15316 28161 14210 28161 15268 28162 14210 28162 15269 28162 15269 28163 14210 28163 12572 28163 15269 28164 12572 28164 12571 28164 12571 28165 14211 28165 14219 28165 14219 28166 14211 28166 14213 28166 14219 28167 14213 28167 14212 28167 14212 28168 14213 28168 15320 28168 14212 28169 15320 28169 15373 28169 15373 28170 15320 28170 14214 28170 15373 28171 14214 28171 14363 28171 14363 28172 14214 28172 14215 28172 14363 28173 14215 28173 14216 28173 14217 28174 12617 28174 14218 28174 14218 28175 12617 28175 12614 28175 14218 28176 12614 28176 15374 28176 15374 28177 12614 28177 14219 28177 15338 28178 15336 28178 14220 28178 14220 28179 15336 28179 15334 28179 14220 28180 15334 28180 14221 28180 15339 28181 15338 28181 14222 28181 14222 28182 15338 28182 14220 28182 14222 28183 14220 28183 15266 28183 15266 28184 14220 28184 14223 28184 15266 28185 14223 28185 14224 28185 12555 28186 12553 28186 14028 28186 14028 28187 12553 28187 14225 28187 14028 28188 14225 28188 14217 28188 14217 28189 14225 28189 12551 28189 14217 28190 12551 28190 15342 28190 15339 28191 14222 28191 15341 28191 15341 28192 14222 28192 14226 28192 15341 28193 14226 28193 15342 28193 15342 28194 14226 28194 12619 28194 15342 28195 12619 28195 14217 28195 14217 28196 12619 28196 12618 28196 14217 28197 12618 28197 12617 28197 14427 28198 12558 28198 14028 28198 14028 28199 12558 28199 12556 28199 14028 28200 12556 28200 12555 28200 14227 28201 14376 28201 14228 28201 14228 28202 14376 28202 13006 28202 14228 28203 13006 28203 14085 28203 14227 28204 15262 28204 14376 28204 14376 28205 15262 28205 14229 28205 14376 28206 14229 28206 15261 28206 14230 28207 14231 28207 15261 28207 15261 28208 14231 28208 15298 28208 15261 28209 15298 28209 14376 28209 14376 28210 15298 28210 14232 28210 14376 28211 14232 28211 14027 28211 14027 28212 14232 28212 12595 28212 14027 28213 12595 28213 12593 28213 12626 28214 14233 28214 14236 28214 14236 28215 14233 28215 15372 28215 12592 28216 12591 28216 15370 28216 15370 28217 12591 28217 14234 28217 15370 28218 14234 28218 15372 28218 15372 28219 14234 28219 14235 28219 15372 28220 14235 28220 14236 28220 14236 28221 14235 28221 15300 28221 14236 28222 15300 28222 12625 28222 15261 28223 12621 28223 14230 28223 14230 28224 12621 28224 14237 28224 14230 28225 14237 28225 14238 28225 14238 28226 14237 28226 12625 28226 14238 28227 12625 28227 14239 28227 14239 28228 12625 28228 15300 28228 13005 28229 14084 28229 14228 28229 14228 28230 14084 28230 12532 28230 14228 28231 12532 28231 15369 28231 12626 28232 12627 28232 14233 28232 14233 28233 12627 28233 14240 28233 14233 28234 14240 28234 14242 28234 14242 28235 14240 28235 14241 28235 14242 28236 14241 28236 15369 28236 15369 28237 14241 28237 15265 28237 15369 28238 15265 28238 14228 28238 14228 28239 15265 28239 14243 28239 14228 28240 14243 28240 14227 28240 14204 28241 14253 28241 14245 28241 14245 28242 14253 28242 14244 28242 14245 28243 14244 28243 14248 28243 14053 28244 14246 28244 14247 28244 14247 28245 14246 28245 15440 28245 14247 28246 15440 28246 15439 28246 14248 28247 15446 28247 14245 28247 14245 28248 15446 28248 15444 28248 14245 28249 15444 28249 14246 28249 14246 28250 15444 28250 14249 28250 14246 28251 14249 28251 15440 28251 12804 28252 12805 28252 15379 28252 15379 28253 12805 28253 14247 28253 15379 28254 14247 28254 14251 28254 14251 28255 14247 28255 14032 28255 14032 28256 12453 28256 14251 28256 14251 28257 12453 28257 14250 28257 14251 28258 14250 28258 14252 28258 14252 28259 14250 28259 12451 28259 14252 28260 12451 28260 14253 28260 14253 28261 12451 28261 14254 28261 14253 28262 14254 28262 14244 28262 14255 28263 14256 28263 14375 28263 14375 28264 14256 28264 12981 28264 14375 28265 12981 28265 14257 28265 14257 28266 12981 28266 14258 28266 14257 28267 14258 28267 14259 28267 13004 28268 14078 28268 14260 28268 14260 28269 14078 28269 14257 28269 14260 28270 14257 28270 14261 28270 14261 28271 14257 28271 14259 28271 14261 28272 14259 28272 12526 28272 14863 28273 14262 28273 14264 28273 14264 28274 14262 28274 14388 28274 14863 28275 14264 28275 14263 28275 14263 28276 14264 28276 12527 28276 14263 28277 12527 28277 14866 28277 14259 28278 14265 28278 12526 28278 12526 28279 14265 28279 14868 28279 12526 28280 14868 28280 12527 28280 12527 28281 14868 28281 14266 28281 12527 28282 14266 28282 14866 28282 14264 28283 12440 28283 12439 28283 12440 28284 14264 28284 12441 28284 12441 28285 14264 28285 14387 28285 12441 28286 14387 28286 12444 28286 12439 28287 14267 28287 14264 28287 14264 28288 14267 28288 14268 28288 14264 28289 14268 28289 12528 28289 12528 28290 14268 28290 15458 28290 12528 28291 15458 28291 12530 28291 12530 28292 15458 28292 14272 28292 14273 28293 14269 28293 14270 28293 14270 28294 14269 28294 15454 28294 14270 28295 15454 28295 14271 28295 14272 28296 14273 28296 12530 28296 12530 28297 14273 28297 14270 28297 12530 28298 14270 28298 12524 28298 12524 28299 14270 28299 14091 28299 12524 28300 14091 28300 12525 28300 12525 28301 14091 28301 14888 28301 12525 28302 14888 28302 14092 28302 12447 28303 14412 28303 14274 28303 14274 28304 14412 28304 14410 28304 14274 28305 14410 28305 12450 28305 14278 28306 14275 28306 14281 28306 14281 28307 14275 28307 15452 28307 14281 28308 15452 28308 15451 28308 14276 28309 15449 28309 14400 28309 14400 28310 15449 28310 14401 28310 12447 28311 14277 28311 14412 28311 14412 28312 14277 28312 12445 28312 14412 28313 12445 28313 14278 28313 14278 28314 12445 28314 14279 28314 14278 28315 14279 28315 14275 28315 14280 28316 12522 28316 14069 28316 14069 28317 12522 28317 14281 28317 14069 28318 14281 28318 14400 28318 14400 28319 14281 28319 15451 28319 14400 28320 15451 28320 14276 28320 15472 28321 14282 28321 14288 28321 14104 28322 14054 28322 14283 28322 14283 28323 14054 28323 14291 28323 14283 28324 14291 28324 14287 28324 14284 28325 14285 28325 12424 28325 15472 28326 14288 28326 14286 28326 14286 28327 14288 28327 14287 28327 14286 28328 14287 28328 15474 28328 14282 28329 14285 28329 14288 28329 14288 28330 14285 28330 14284 28330 14288 28331 14284 28331 14289 28331 14289 28332 14284 28332 14290 28332 14289 28333 14290 28333 14145 28333 12418 28334 14291 28334 12419 28334 12419 28335 14291 28335 14284 28335 12419 28336 14284 28336 12422 28336 12422 28337 14284 28337 12424 28337 12418 28338 12417 28338 14291 28338 14291 28339 12417 28339 12416 28339 14291 28340 12416 28340 14287 28340 14287 28341 12416 28341 15476 28341 14287 28342 15476 28342 15474 28342 14108 28343 14703 28343 12516 28343 12516 28344 14703 28344 14292 28344 12516 28345 14292 28345 12513 28345 12513 28346 14292 28346 14294 28346 12513 28347 14294 28347 12514 28347 14293 28348 15470 28348 14294 28348 14293 28349 14294 28349 14399 28349 14404 28350 12428 28350 14405 28350 14405 28351 12428 28351 12426 28351 14405 28352 12426 28352 14399 28352 15470 28353 14295 28353 14294 28353 14294 28354 14295 28354 15469 28354 14294 28355 15469 28355 12514 28355 12514 28356 15469 28356 14296 28356 12514 28357 14296 28357 12508 28357 14296 28358 15467 28358 12508 28358 12508 28359 15467 28359 15466 28359 12508 28360 15466 28360 14404 28360 14404 28361 15466 28361 12430 28361 14404 28362 12430 28362 14030 28362 14301 28363 14298 28363 14297 28363 14297 28364 14298 28364 15463 28364 14434 28365 14299 28365 15463 28365 14300 28366 14132 28366 12504 28366 12504 28367 14132 28367 14298 28367 12504 28368 14298 28368 12505 28368 12505 28369 14298 28369 14301 28369 14307 28370 12434 28370 14135 28370 14135 28371 12434 28371 14302 28371 14135 28372 14302 28372 14434 28372 14434 28373 14302 28373 12432 28373 14434 28374 12432 28374 14299 28374 14301 28375 14303 28375 12505 28375 12505 28376 14303 28376 14304 28376 12505 28377 14304 28377 12506 28377 12506 28378 14304 28378 14305 28378 12506 28379 14305 28379 12436 28379 14139 28380 12507 28380 14306 28380 14306 28381 12507 28381 12506 28381 14306 28382 12506 28382 14135 28382 14135 28383 12506 28383 12436 28383 14135 28384 12436 28384 14307 28384 12502 28385 14614 28385 14311 28385 13189 28386 14308 28386 14309 28386 14309 28387 14308 28387 14310 28387 13156 28388 13155 28388 12502 28388 12502 28389 13155 28389 14309 28389 12502 28390 14309 28390 14614 28390 14614 28391 14309 28391 14310 28391 14311 28392 14312 28392 12502 28392 12502 28393 14312 28393 14610 28393 12502 28394 14610 28394 14314 28394 13192 28395 14313 28395 14316 28395 14316 28396 14313 28396 13189 28396 14610 28397 13196 28397 14314 28397 14314 28398 13196 28398 13194 28398 14314 28399 13194 28399 12500 28399 12500 28400 13194 28400 14315 28400 12500 28401 14315 28401 14316 28401 14316 28402 14315 28402 14317 28402 14316 28403 14317 28403 13192 28403 14171 28404 12782 28404 14172 28404 14172 28405 12782 28405 14170 28405 14172 28406 14170 28406 14318 28406 14318 28407 14170 28407 14168 28407 14318 28408 14168 28408 14325 28408 14190 28409 14191 28409 14319 28409 14319 28410 14191 28410 14320 28410 14319 28411 14320 28411 14321 28411 14321 28412 14320 28412 15389 28412 14321 28413 15389 28413 14327 28413 14327 28414 14322 28414 14321 28414 14321 28415 14322 28415 14323 28415 14321 28416 14323 28416 14432 28416 15422 28417 14324 28417 14431 28417 14431 28418 14324 28418 15420 28418 14431 28419 15420 28419 14168 28419 14168 28420 15420 28420 15418 28420 14168 28421 15418 28421 15417 28421 15417 28422 15415 28422 14168 28422 14168 28423 15415 28423 12473 28423 14168 28424 12473 28424 14325 28424 14325 28425 12473 28425 12471 28425 14325 28426 12471 28426 15389 28426 15389 28427 12471 28427 14326 28427 15389 28428 14326 28428 14327 28428 12479 28429 12478 28429 15383 28429 15383 28430 12478 28430 14402 28430 15383 28431 14402 28431 14347 28431 12479 28432 15383 28432 12480 28432 12480 28433 15383 28433 14328 28433 12480 28434 14328 28434 12482 28434 12478 28435 12476 28435 14402 28435 14402 28436 12476 28436 14329 28436 14402 28437 14329 28437 15413 28437 14330 28438 15407 28438 14336 28438 12740 28439 14331 28439 14040 28439 14040 28440 14331 28440 14336 28440 14040 28441 14336 28441 14328 28441 14328 28442 14336 28442 15407 28442 14328 28443 15407 28443 12482 28443 15413 28444 15411 28444 14333 28444 15411 28445 14332 28445 14333 28445 14333 28446 14332 28446 14334 28446 14333 28447 14334 28447 14336 28447 14336 28448 14334 28448 14335 28448 14336 28449 14335 28449 14330 28449 14337 28450 15138 28450 14340 28450 14052 28451 15382 28451 14338 28451 14338 28452 15382 28452 14343 28452 14338 28453 14343 28453 14339 28453 14340 28454 15138 28454 14402 28454 14348 28455 14341 28455 15382 28455 15382 28456 14341 28456 14342 28456 15382 28457 14342 28457 14343 28457 14339 28458 14344 28458 14338 28458 14338 28459 14344 28459 14345 28459 14338 28460 14345 28460 14340 28460 14340 28461 14345 28461 15140 28461 14340 28462 15140 28462 14337 28462 15138 28463 15136 28463 14402 28463 14402 28464 15136 28464 15135 28464 14402 28465 15135 28465 14347 28465 14347 28466 15135 28466 14346 28466 14347 28467 14346 28467 14348 28467 14348 28468 14346 28468 14349 28468 14348 28469 14349 28469 14341 28469 14352 28470 14350 28470 15376 28470 15376 28471 14350 28471 14351 28471 15376 28472 14351 28472 15378 28472 15432 28473 14353 28473 14352 28473 14352 28474 14353 28474 12460 28474 14352 28475 12460 28475 14350 28475 14359 28476 14354 28476 14357 28476 14351 28477 12456 28477 15378 28477 15378 28478 12456 28478 14355 28478 15378 28479 14355 28479 14427 28479 14427 28480 14355 28480 15437 28480 15437 28481 15435 28481 14427 28481 14427 28482 15435 28482 14356 28482 14427 28483 14356 28483 14357 28483 14357 28484 14356 28484 14358 28484 14357 28485 14358 28485 14359 28485 14360 28486 14365 28486 14368 28486 14368 28487 14365 28487 12461 28487 14361 28488 14362 28488 14363 28488 14363 28489 14362 28489 12465 28489 14363 28490 12465 28490 14360 28490 14360 28491 12465 28491 14364 28491 14360 28492 14364 28492 14365 28492 14371 28493 15424 28493 14377 28493 14366 28494 15429 28494 14027 28494 15424 28495 14361 28495 14377 28495 14377 28496 14361 28496 14363 28496 14377 28497 14363 28497 14367 28497 14367 28498 14363 28498 14216 28498 14367 28499 14216 28499 15318 28499 12461 28500 14366 28500 14368 28500 14368 28501 14366 28501 14027 28501 14368 28502 14027 28502 15370 28502 15370 28503 14027 28503 12593 28503 15370 28504 12593 28504 12592 28504 15429 28505 15428 28505 14027 28505 14027 28506 15428 28506 14369 28506 14027 28507 14369 28507 14377 28507 14377 28508 14369 28508 14370 28508 14377 28509 14370 28509 14371 28509 14372 28510 14374 28510 14375 28510 14386 28511 14374 28511 14373 28511 14373 28512 14374 28512 14372 28512 14373 28513 14372 28513 14378 28513 14080 28514 14081 28514 14375 28514 14375 28515 14081 28515 14376 28515 14375 28516 14376 28516 14372 28516 14372 28517 14376 28517 14377 28517 14372 28518 14377 28518 14378 28518 14378 28519 14377 28519 14367 28519 14378 28520 14367 28520 14379 28520 14379 28521 14367 28521 14381 28521 14379 28522 14381 28522 14380 28522 14380 28523 14381 28523 15267 28523 13003 28524 14099 28524 14162 28524 14162 28525 14099 28525 14100 28525 14162 28526 14100 28526 14384 28526 14384 28527 14100 28527 14383 28527 14384 28528 14383 28528 14382 28528 14382 28529 14383 28529 14270 28529 14382 28530 14270 28530 14387 28530 14387 28531 14270 28531 14271 28531 14387 28532 14271 28532 12444 28532 13283 28533 14162 28533 14385 28533 14385 28534 14162 28534 14384 28534 14385 28535 14384 28535 14166 28535 14166 28536 14384 28536 14382 28536 14166 28537 14382 28537 14386 28537 14386 28538 14382 28538 14387 28538 14386 28539 14387 28539 14374 28539 14374 28540 14387 28540 14264 28540 14374 28541 14264 28541 14375 28541 14375 28542 14264 28542 14388 28542 14375 28543 14388 28543 14255 28543 14151 28544 14389 28544 14380 28544 14380 28545 14389 28545 14390 28545 14380 28546 14390 28546 14379 28546 14379 28547 14390 28547 14391 28547 14379 28548 14391 28548 14378 28548 14378 28549 14391 28549 14492 28549 14378 28550 14492 28550 14373 28550 14373 28551 14492 28551 13279 28551 14373 28552 13279 28552 14167 28552 13171 28553 14284 28553 14395 28553 14395 28554 14284 28554 14291 28554 14395 28555 14291 28555 14396 28555 14396 28556 14291 28556 12996 28556 14396 28557 12996 28557 12995 28557 14047 28558 14048 28558 14246 28558 14246 28559 14048 28559 14392 28559 14246 28560 14392 28560 14245 28560 14245 28561 14392 28561 14393 28561 14245 28562 14393 28562 15276 28562 14110 28563 14107 28563 14111 28563 14111 28564 14107 28564 14395 28564 14111 28565 14395 28565 14394 28565 14394 28566 14395 28566 14396 28566 14394 28567 14396 28567 14397 28567 14397 28568 14396 28568 12919 28568 14397 28569 12919 28569 14398 28569 14399 28570 14294 28570 14405 28570 14405 28571 14294 28571 14111 28571 14405 28572 14111 28572 14406 28572 14406 28573 14111 28573 14394 28573 14406 28574 14394 28574 14407 28574 14407 28575 14394 28575 14397 28575 14407 28576 14397 28576 14408 28576 14408 28577 14397 28577 14400 28577 14408 28578 14400 28578 14410 28578 14410 28579 14400 28579 14401 28579 14410 28580 14401 28580 12450 28580 15413 28581 14333 28581 14402 28581 14402 28582 14333 28582 14403 28582 14402 28583 14403 28583 14340 28583 14340 28584 14403 28584 14424 28584 14340 28585 14424 28585 14048 28585 14048 28586 14424 28586 14426 28586 14048 28587 14426 28587 14392 28587 14392 28588 14426 28588 14357 28588 14392 28589 14357 28589 14352 28589 14352 28590 14357 28590 14354 28590 14352 28591 14354 28591 15432 28591 13112 28592 14404 28592 14160 28592 14160 28593 14404 28593 14405 28593 14160 28594 14405 28594 14159 28594 14159 28595 14405 28595 14406 28595 14159 28596 14406 28596 14156 28596 14156 28597 14406 28597 14407 28597 14156 28598 14407 28598 14161 28598 14161 28599 14407 28599 14408 28599 14161 28600 14408 28600 14409 28600 14409 28601 14408 28601 14410 28601 14409 28602 14410 28602 14164 28602 14164 28603 14410 28603 14412 28603 14164 28604 14412 28604 14411 28604 14411 28605 14412 28605 14903 28605 14411 28606 14903 28606 12941 28606 14413 28607 14153 28607 14414 28607 14414 28608 14153 28608 14415 28608 14414 28609 14415 28609 14042 28609 14042 28610 14415 28610 14416 28610 14042 28611 14416 28611 14423 28611 14423 28612 14416 28612 14418 28612 14423 28613 14418 28613 14417 28613 14417 28614 14418 28614 14486 28614 14417 28615 14486 28615 14419 28615 14419 28616 14486 28616 14420 28616 14419 28617 14420 28617 14425 28617 14425 28618 14420 28618 14421 28618 14425 28619 14421 28619 14422 28619 14422 28620 14421 28620 14150 28620 14422 28621 14150 28621 14223 28621 14223 28622 14150 28622 14380 28622 14223 28623 14380 28623 14224 28623 14224 28624 14380 28624 15267 28624 12737 28625 14042 28625 14336 28625 14336 28626 14042 28626 14423 28626 14336 28627 14423 28627 14333 28627 14333 28628 14423 28628 14417 28628 14333 28629 14417 28629 14403 28629 14403 28630 14417 28630 14419 28630 14403 28631 14419 28631 14424 28631 14424 28632 14419 28632 14425 28632 14424 28633 14425 28633 14426 28633 14426 28634 14425 28634 14422 28634 14426 28635 14422 28635 14357 28635 14357 28636 14422 28636 14220 28636 14357 28637 14220 28637 14427 28637 14427 28638 14220 28638 14221 28638 14427 28639 14221 28639 12558 28639 15463 28640 14298 28640 14434 28640 14434 28641 14298 28641 14428 28641 14434 28642 14428 28642 14429 28642 14429 28643 14428 28643 14122 28643 14429 28644 14122 28644 14435 28644 14435 28645 14122 28645 14155 28645 14435 28646 14155 28646 14436 28646 14413 28647 14036 28647 14153 28647 14153 28648 14036 28648 14430 28648 14153 28649 14430 28649 14441 28649 14441 28650 14430 28650 14187 28650 14441 28651 14187 28651 14440 28651 14440 28652 14187 28652 14321 28652 14440 28653 14321 28653 14431 28653 14431 28654 14321 28654 14432 28654 14431 28655 14432 28655 15422 28655 13151 28656 14135 28656 14433 28656 14433 28657 14135 28657 14434 28657 14433 28658 14434 28658 14444 28658 14444 28659 14434 28659 14429 28659 14444 28660 14429 28660 14446 28660 14446 28661 14429 28661 14435 28661 14446 28662 14435 28662 14437 28662 14437 28663 14435 28663 14436 28663 14437 28664 14436 28664 14438 28664 12780 28665 14443 28665 14168 28665 14168 28666 14443 28666 14445 28666 14168 28667 14445 28667 14431 28667 14431 28668 14445 28668 14439 28668 14431 28669 14439 28669 14440 28669 14440 28670 14439 28670 14447 28670 14440 28671 14447 28671 14441 28671 14441 28672 14447 28672 14442 28672 14441 28673 14442 28673 14481 28673 13189 28674 14309 28674 14316 28674 14316 28675 14309 28675 14433 28675 14316 28676 14433 28676 14443 28676 14443 28677 14433 28677 14444 28677 14443 28678 14444 28678 14445 28678 14445 28679 14444 28679 14446 28679 14445 28680 14446 28680 14439 28680 14439 28681 14446 28681 14437 28681 14439 28682 14437 28682 14447 28682 14447 28683 14437 28683 14438 28683 14447 28684 14438 28684 14477 28684 15018 28685 14957 28685 15019 28685 15019 28686 14957 28686 14958 28686 15019 28687 14958 28687 15020 28687 15020 28688 14958 28688 14448 28688 15020 28689 14448 28689 14449 28689 14449 28690 14448 28690 14450 28690 14449 28691 14450 28691 14451 28691 14451 28692 14450 28692 14960 28692 14451 28693 14960 28693 12852 28693 12852 28694 14960 28694 12899 28694 12852 28695 12899 28695 14452 28695 14452 28696 12899 28696 12900 28696 14452 28697 12900 28697 14453 28697 14453 28698 12900 28698 12901 28698 14453 28699 12901 28699 12856 28699 12856 28700 12901 28700 14454 28700 12856 28701 14454 28701 12858 28701 12858 28702 14454 28702 12903 28702 12858 28703 12903 28703 14455 28703 14455 28704 12903 28704 12904 28704 14455 28705 12904 28705 12859 28705 12859 28706 12904 28706 14456 28706 12859 28707 14456 28707 15016 28707 15016 28708 14456 28708 14954 28708 15016 28709 14954 28709 15018 28709 15018 28710 14954 28710 14957 28710 13311 28711 13310 28711 14457 28711 13311 28712 14457 28712 15479 28712 15479 28713 14457 28713 15391 28713 15479 28714 15391 28714 14458 28714 14458 28715 15391 28715 15390 28715 14458 28716 15390 28716 14459 28716 14459 28717 15390 28717 15386 28717 14459 28718 15386 28718 14460 28718 14460 28719 15386 28719 14461 28719 14460 28720 14461 28720 14462 28720 14462 28721 14461 28721 15385 28721 14462 28722 15385 28722 15482 28722 15482 28723 15385 28723 14463 28723 15482 28724 14463 28724 14464 28724 14464 28725 14463 28725 14465 28725 14464 28726 14465 28726 15484 28726 15484 28727 14465 28727 14466 28727 15484 28728 14466 28728 14467 28728 14467 28729 14466 28729 15380 28729 14467 28730 15380 28730 14468 28730 14468 28731 15380 28731 15381 28731 14468 28732 15381 28732 14469 28732 14469 28733 15381 28733 14470 28733 14469 28734 14470 28734 14471 28734 14471 28735 14470 28735 15377 28735 14471 28736 15377 28736 15486 28736 15486 28737 15377 28737 14472 28737 15486 28738 14472 28738 15488 28738 15488 28739 14472 28739 15375 28739 15488 28740 15375 28740 15489 28740 15489 28741 15375 28741 15371 28741 15489 28742 15371 28742 14473 28742 14473 28743 15371 28743 14474 28743 14473 28744 14474 28744 14475 28744 14475 28745 14474 28745 15368 28745 14475 28746 15368 28746 15491 28746 15491 28747 15368 28747 12531 28747 15491 28748 12531 28748 14476 28748 14477 28749 14478 28749 14479 28749 14477 28750 14479 28750 14442 28750 14442 28751 14479 28751 14480 28751 14442 28752 14480 28752 14481 28752 14481 28753 14480 28753 14482 28753 14481 28754 14482 28754 14152 28754 14152 28755 14482 28755 15404 28755 14152 28756 15404 28756 14483 28756 14483 28757 15404 28757 15403 28757 14483 28758 15403 28758 14033 28758 14033 28759 15403 28759 15402 28759 14033 28760 15402 28760 14484 28760 14484 28761 15402 28761 14485 28761 14484 28762 14485 28762 14486 28762 14486 28763 14485 28763 15401 28763 14486 28764 15401 28764 14420 28764 14420 28765 15401 28765 15400 28765 14420 28766 15400 28766 14421 28766 14421 28767 15400 28767 14487 28767 14421 28768 14487 28768 14488 28768 14488 28769 14487 28769 14489 28769 14488 28770 14489 28770 14151 28770 14151 28771 14489 28771 15396 28771 14151 28772 15396 28772 14389 28772 14389 28773 15396 28773 14490 28773 14389 28774 14490 28774 14390 28774 14390 28775 14490 28775 15394 28775 14390 28776 15394 28776 14491 28776 14491 28777 15394 28777 15392 28777 14491 28778 15392 28778 14492 28778 14492 28779 15392 28779 12499 28779 14492 28780 12499 28780 13279 28780 13278 28781 14493 28781 14494 28781 14494 28782 14493 28782 14611 28782 14494 28783 14611 28783 14495 28783 14495 28784 14611 28784 14612 28784 14495 28785 14612 28785 14501 28785 14501 28786 14612 28786 14496 28786 14501 28787 14496 28787 14503 28787 14503 28788 14496 28788 14613 28788 14503 28789 14613 28789 14504 28789 14504 28790 14613 28790 14497 28790 14504 28791 14497 28791 14506 28791 14506 28792 14497 28792 13188 28792 13250 28793 14511 28793 14498 28793 14498 28794 14511 28794 13278 28794 14498 28795 13278 28795 14499 28795 14499 28796 13278 28796 14494 28796 14499 28797 14494 28797 14500 28797 14500 28798 14494 28798 14495 28798 14500 28799 14495 28799 14564 28799 14564 28800 14495 28800 14501 28800 14564 28801 14501 28801 14502 28801 14502 28802 14501 28802 14503 28802 14502 28803 14503 28803 14566 28803 14566 28804 14503 28804 14504 28804 14566 28805 14504 28805 14505 28805 14505 28806 14504 28806 14506 28806 14505 28807 14506 28807 13244 28807 13244 28808 14506 28808 14508 28808 13244 28809 14508 28809 14507 28809 14507 28810 14508 28810 13274 28810 14507 28811 13274 28811 14509 28811 14509 28812 13274 28812 13275 28812 14509 28813 13275 28813 13246 28813 13246 28814 13275 28814 14510 28814 13246 28815 14510 28815 13249 28815 13249 28816 14510 28816 13276 28816 13249 28817 13276 28817 13250 28817 13250 28818 13276 28818 14511 28818 14523 28819 13187 28819 14524 28819 14524 28820 13187 28820 14512 28820 14524 28821 14512 28821 14526 28821 14526 28822 14512 28822 14615 28822 14526 28823 14615 28823 14513 28823 14513 28824 14615 28824 14515 28824 14513 28825 14515 28825 14514 28825 14514 28826 14515 28826 14617 28826 14514 28827 14617 28827 14530 28827 14530 28828 14617 28828 14516 28828 14530 28829 14516 28829 14531 28829 14531 28830 14516 28830 14619 28830 14517 28831 13270 28831 14518 28831 14518 28832 13270 28832 14519 28832 14518 28833 14519 28833 13226 28833 13226 28834 14519 28834 13271 28834 13226 28835 13271 28835 14520 28835 14520 28836 13271 28836 14521 28836 14520 28837 14521 28837 13228 28837 13228 28838 14521 28838 14522 28838 13228 28839 14522 28839 14579 28839 14579 28840 14522 28840 14523 28840 14579 28841 14523 28841 14580 28841 14580 28842 14523 28842 14524 28842 14580 28843 14524 28843 14525 28843 14525 28844 14524 28844 14526 28844 14525 28845 14526 28845 14527 28845 14527 28846 14526 28846 14513 28846 14527 28847 14513 28847 14528 28847 14528 28848 14513 28848 14514 28848 14528 28849 14514 28849 14529 28849 14529 28850 14514 28850 14530 28850 14529 28851 14530 28851 13223 28851 13223 28852 14530 28852 14531 28852 13223 28853 14531 28853 13224 28853 13224 28854 14531 28854 14532 28854 13224 28855 14532 28855 14517 28855 14517 28856 14532 28856 13270 28856 13269 28857 14620 28857 14533 28857 14533 28858 14620 28858 14534 28858 14533 28859 14534 28859 14535 28859 14535 28860 14534 28860 14536 28860 14535 28861 14536 28861 14537 28861 14537 28862 14536 28862 14538 28862 14537 28863 14538 28863 14551 28863 14551 28864 14538 28864 14540 28864 14551 28865 14540 28865 14539 28865 14539 28866 14540 28866 14541 28866 14539 28867 14541 28867 14542 28867 14542 28868 14541 28868 14622 28868 14553 28869 14543 28869 13201 28869 13201 28870 14543 28870 14544 28870 13201 28871 14544 28871 13202 28871 13202 28872 14544 28872 14545 28872 13202 28873 14545 28873 13204 28873 13204 28874 14545 28874 14547 28874 13204 28875 14547 28875 14546 28875 14546 28876 14547 28876 13269 28876 14546 28877 13269 28877 14548 28877 14548 28878 13269 28878 14533 28878 14548 28879 14533 28879 14606 28879 14606 28880 14533 28880 14535 28880 14606 28881 14535 28881 14549 28881 14549 28882 14535 28882 14537 28882 14549 28883 14537 28883 14608 28883 14608 28884 14537 28884 14551 28884 14608 28885 14551 28885 14550 28885 14550 28886 14551 28886 14539 28886 14550 28887 14539 28887 13197 28887 13197 28888 14539 28888 14542 28888 13197 28889 14542 28889 13198 28889 13198 28890 14542 28890 14552 28890 13198 28891 14552 28891 13200 28891 13200 28892 14552 28892 13266 28892 13200 28893 13266 28893 14553 28893 14553 28894 13266 28894 14543 28894 13264 28895 13265 28895 14554 28895 14554 28896 13265 28896 13689 28896 14554 28897 13689 28897 14562 28897 14562 28898 13689 28898 13691 28898 14562 28899 13691 28899 14555 28899 14555 28900 13691 28900 14556 28900 14555 28901 14556 28901 14559 28901 14559 28902 14556 28902 13694 28902 14559 28903 13694 28903 14557 28903 14557 28904 13694 28904 13695 28904 14557 28905 13695 28905 13257 28905 13257 28906 13695 28906 13259 28906 13257 28907 13251 28907 14557 28907 14557 28908 13251 28908 14558 28908 14557 28909 14558 28909 14559 28909 14559 28910 14558 28910 14560 28910 14559 28911 14560 28911 14555 28911 14555 28912 14560 28912 14561 28912 14555 28913 14561 28913 14562 28913 14562 28914 14561 28914 14563 28914 14562 28915 14563 28915 14554 28915 14554 28916 14563 28916 14565 28916 14554 28917 14565 28917 13264 28917 13264 28918 14565 28918 13242 28918 13251 28919 14498 28919 14558 28919 14558 28920 14498 28920 14499 28920 14558 28921 14499 28921 14560 28921 14560 28922 14499 28922 14500 28922 14560 28923 14500 28923 14561 28923 14561 28924 14500 28924 14564 28924 14561 28925 14564 28925 14563 28925 14563 28926 14564 28926 14502 28926 14563 28927 14502 28927 14565 28927 14565 28928 14502 28928 14566 28928 14565 28929 14566 28929 13242 28929 13242 28930 14566 28930 14505 28930 13240 28931 13616 28931 14576 28931 14576 28932 13616 28932 14567 28932 14576 28933 14567 28933 14575 28933 14575 28934 14567 28934 14568 28934 14575 28935 14568 28935 14569 28935 14569 28936 14568 28936 13618 28936 14569 28937 13618 28937 14570 28937 14570 28938 13618 28938 13620 28938 14570 28939 13620 28939 14572 28939 14572 28940 13620 28940 13621 28940 14572 28941 13621 28941 13234 28941 13234 28942 13621 28942 14571 28942 13234 28943 14573 28943 14572 28943 14572 28944 14573 28944 14578 28944 14572 28945 14578 28945 14570 28945 14570 28946 14578 28946 14574 28946 14570 28947 14574 28947 14569 28947 14569 28948 14574 28948 14581 28948 14569 28949 14581 28949 14575 28949 14575 28950 14581 28950 14582 28950 14575 28951 14582 28951 14576 28951 14576 28952 14582 28952 14577 28952 14576 28953 14577 28953 13240 28953 13240 28954 14577 28954 14583 28954 14573 28955 14579 28955 14578 28955 14578 28956 14579 28956 14580 28956 14578 28957 14580 28957 14574 28957 14574 28958 14580 28958 14525 28958 14574 28959 14525 28959 14581 28959 14581 28960 14525 28960 14527 28960 14581 28961 14527 28961 14582 28961 14582 28962 14527 28962 14528 28962 14582 28963 14528 28963 14577 28963 14577 28964 14528 28964 14529 28964 14577 28965 14529 28965 14583 28965 14583 28966 14529 28966 13223 28966 14586 28967 14584 28967 14585 28967 14585 28968 14597 28968 14586 28968 14586 28969 14597 28969 14587 28969 14586 28970 14587 28970 13613 28970 14587 28971 14599 28971 13613 28971 13613 28972 14599 28972 14588 28972 13613 28973 14588 28973 14590 28973 14590 28974 14588 28974 14589 28974 14590 28975 14589 28975 14592 28975 14589 28976 14591 28976 14592 28976 14592 28977 14591 28977 14601 28977 14592 28978 14601 28978 14593 28978 14601 28979 14602 28979 14593 28979 14593 28980 14602 28980 14594 28980 14593 28981 14594 28981 13608 28981 13217 28982 14596 28982 14595 28982 14595 28983 14596 28983 13608 28983 14595 28984 13608 28984 14603 28984 14603 28985 13608 28985 14594 28985 14585 28986 13205 28986 14597 28986 14597 28987 13205 28987 14598 28987 14597 28988 14598 28988 14587 28988 14587 28989 14598 28989 14599 28989 14599 28990 14598 28990 14600 28990 14599 28991 14600 28991 14588 28991 14588 28992 14600 28992 14589 28992 14589 28993 14600 28993 14605 28993 14589 28994 14605 28994 14591 28994 14591 28995 14605 28995 14601 28995 14601 28996 14605 28996 14607 28996 14601 28997 14607 28997 14602 28997 14602 28998 14607 28998 14594 28998 14594 28999 14607 28999 14604 28999 14594 29000 14604 29000 14603 29000 14603 29001 14604 29001 14595 29001 14595 29002 14604 29002 14609 29002 14595 29003 14609 29003 13217 29003 13205 29004 14546 29004 14598 29004 14598 29005 14546 29005 14548 29005 14598 29006 14548 29006 14600 29006 14600 29007 14548 29007 14606 29007 14600 29008 14606 29008 14605 29008 14605 29009 14606 29009 14549 29009 14605 29010 14549 29010 14607 29010 14607 29011 14549 29011 14608 29011 14607 29012 14608 29012 14604 29012 14604 29013 14608 29013 14550 29013 14604 29014 14550 29014 14609 29014 14609 29015 14550 29015 13197 29015 14493 29016 14610 29016 14611 29016 14611 29017 14610 29017 14312 29017 14611 29018 14312 29018 14612 29018 14612 29019 14312 29019 14311 29019 14612 29020 14311 29020 14496 29020 14496 29021 14311 29021 14614 29021 14496 29022 14614 29022 14613 29022 14613 29023 14614 29023 14310 29023 14613 29024 14310 29024 14497 29024 14497 29025 14310 29025 14308 29025 14497 29026 14308 29026 13188 29026 13188 29027 14308 29027 13189 29027 13187 29028 14133 29028 14512 29028 14512 29029 14133 29029 14616 29029 14512 29030 14616 29030 14615 29030 14615 29031 14616 29031 14142 29031 14615 29032 14142 29032 14515 29032 14515 29033 14142 29033 14141 29033 14515 29034 14141 29034 14617 29034 14617 29035 14141 29035 14140 29035 14617 29036 14140 29036 14516 29036 14516 29037 14140 29037 14618 29037 14516 29038 14618 29038 14619 29038 14619 29039 14618 29039 14034 29039 14620 29040 14149 29040 14534 29040 14534 29041 14149 29041 14148 29041 14534 29042 14148 29042 14536 29042 14536 29043 14148 29043 14621 29043 14536 29044 14621 29044 14538 29044 14538 29045 14621 29045 14146 29045 14538 29046 14146 29046 14540 29046 14540 29047 14146 29047 14145 29047 14540 29048 14145 29048 14541 29048 14541 29049 14145 29049 14290 29049 14541 29050 14290 29050 14622 29050 14622 29051 14290 29051 14623 29051 14636 29052 13679 29052 14635 29052 14635 29053 13679 29053 13680 29053 14635 29054 13680 29054 14634 29054 14634 29055 13680 29055 14624 29055 14634 29056 14624 29056 14625 29056 14625 29057 14624 29057 13669 29057 14625 29058 13669 29058 14626 29058 14626 29059 13669 29059 13670 29059 14626 29060 13670 29060 14633 29060 14633 29061 13670 29061 14627 29061 14633 29062 14627 29062 14630 29062 14630 29063 14627 29063 14628 29063 14630 29064 14628 29064 14629 29064 14629 29065 14628 29065 13165 29065 14629 29066 13164 29066 14630 29066 14630 29067 13164 29067 14631 29067 14630 29068 14631 29068 14633 29068 14633 29069 14631 29069 14632 29069 14633 29070 14632 29070 14626 29070 14626 29071 14632 29071 14639 29071 14626 29072 14639 29072 14625 29072 14625 29073 14639 29073 14641 29073 14625 29074 14641 29074 14634 29074 14634 29075 14641 29075 14643 29075 14634 29076 14643 29076 14635 29076 14635 29077 14643 29077 14644 29077 14635 29078 14644 29078 14636 29078 14636 29079 14644 29079 14637 29079 13164 29080 13159 29080 14631 29080 14631 29081 13159 29081 14638 29081 14631 29082 14638 29082 14632 29082 14632 29083 14638 29083 14640 29083 14632 29084 14640 29084 14639 29084 14639 29085 14640 29085 14138 29085 14639 29086 14138 29086 14641 29086 14641 29087 14138 29087 14642 29087 14641 29088 14642 29088 14643 29088 14643 29089 14642 29089 14134 29089 14643 29090 14134 29090 14644 29090 14644 29091 14134 29091 14645 29091 14644 29092 14645 29092 14637 29092 14637 29093 14645 29093 13151 29093 13666 29094 13142 29094 14646 29094 14646 29095 13142 29095 14647 29095 14646 29096 14647 29096 13664 29096 13664 29097 14647 29097 14650 29097 14650 29098 14648 29098 13664 29098 13664 29099 14648 29099 14652 29099 13664 29100 14652 29100 13663 29100 14652 29101 14653 29101 13663 29101 13663 29102 14653 29102 14655 29102 13663 29103 14655 29103 13662 29103 13150 29104 13658 29104 14659 29104 14659 29105 13658 29105 13660 29105 14659 29106 13660 29106 14649 29106 14649 29107 13660 29107 13662 29107 14649 29108 13662 29108 14657 29108 14657 29109 13662 29109 14655 29109 13142 29110 13136 29110 14660 29110 13142 29111 14660 29111 14647 29111 14647 29112 14660 29112 14651 29112 14647 29113 14651 29113 14650 29113 14650 29114 14651 29114 14648 29114 14648 29115 14651 29115 14654 29115 14648 29116 14654 29116 14652 29116 14652 29117 14654 29117 14653 29117 14653 29118 14654 29118 14656 29118 14653 29119 14656 29119 14655 29119 14655 29120 14656 29120 14657 29120 14657 29121 14656 29121 14664 29121 14657 29122 14664 29122 14649 29122 14649 29123 14664 29123 14658 29123 14649 29124 14658 29124 14659 29124 14659 29125 14658 29125 13137 29125 14659 29126 13137 29126 13150 29126 13136 29127 14300 29127 14660 29127 14660 29128 14300 29128 14130 29128 14660 29129 14130 29129 14651 29129 14651 29130 14130 29130 14661 29130 14651 29131 14661 29131 14654 29131 14654 29132 14661 29132 14662 29132 14654 29133 14662 29133 14656 29133 14656 29134 14662 29134 14663 29134 14656 29135 14663 29135 14664 29135 14664 29136 14663 29136 14127 29136 14664 29137 14127 29137 14658 29137 14658 29138 14127 29138 14665 29138 14658 29139 14665 29139 13137 29139 13137 29140 14665 29140 14123 29140 14674 29141 13644 29141 14666 29141 14666 29142 13644 29142 13647 29142 14666 29143 13647 29143 14667 29143 14667 29144 13647 29144 14668 29144 14667 29145 14668 29145 14669 29145 14669 29146 14668 29146 14670 29146 14669 29147 14670 29147 14673 29147 14673 29148 14670 29148 13649 29148 14673 29149 13649 29149 14671 29149 14671 29150 13649 29150 13651 29150 14671 29151 13651 29151 14672 29151 14672 29152 13651 29152 13653 29152 14672 29153 14675 29153 14671 29153 14671 29154 14675 29154 14676 29154 14671 29155 14676 29155 14673 29155 14673 29156 14676 29156 14679 29156 14673 29157 14679 29157 14669 29157 14669 29158 14679 29158 14680 29158 14669 29159 14680 29159 14667 29159 14667 29160 14680 29160 14682 29160 14667 29161 14682 29161 14666 29161 14666 29162 14682 29162 14683 29162 14666 29163 14683 29163 14674 29163 14674 29164 14683 29164 13116 29164 14675 29165 14120 29165 14676 29165 14676 29166 14120 29166 14677 29166 14676 29167 14677 29167 14679 29167 14679 29168 14677 29168 14678 29168 14679 29169 14678 29169 14680 29169 14680 29170 14678 29170 14117 29170 14680 29171 14117 29171 14682 29171 14682 29172 14117 29172 14681 29172 14682 29173 14681 29173 14683 29173 14683 29174 14681 29174 14121 29174 14683 29175 14121 29175 13116 29175 13116 29176 14121 29176 13111 29176 13631 29177 14693 29177 14684 29177 14684 29178 14693 29178 14695 29178 14684 29179 14695 29179 14686 29179 14686 29180 14695 29180 14697 29180 14697 29181 14685 29181 14686 29181 14686 29182 14685 29182 14699 29182 14686 29183 14699 29183 14687 29183 14699 29184 14688 29184 14687 29184 14687 29185 14688 29185 14689 29185 14687 29186 14689 29186 13637 29186 13096 29187 14691 29187 14690 29187 14690 29188 14691 29188 13636 29188 14690 29189 13636 29189 14692 29189 14692 29190 13636 29190 13637 29190 14692 29191 13637 29191 14701 29191 14701 29192 13637 29192 14689 29192 14693 29193 13095 29193 14694 29193 14693 29194 14694 29194 14695 29194 14695 29195 14694 29195 14696 29195 14695 29196 14696 29196 14697 29196 14697 29197 14696 29197 14685 29197 14685 29198 14696 29198 14698 29198 14685 29199 14698 29199 14699 29199 14699 29200 14698 29200 14688 29200 14688 29201 14698 29201 14700 29201 14688 29202 14700 29202 14689 29202 14689 29203 14700 29203 14701 29203 14701 29204 14700 29204 14706 29204 14701 29205 14706 29205 14692 29205 14692 29206 14706 29206 14702 29206 14692 29207 14702 29207 14690 29207 14690 29208 14702 29208 13097 29208 14690 29209 13097 29209 13096 29209 13095 29210 14703 29210 14694 29210 14694 29211 14703 29211 14108 29211 14694 29212 14108 29212 14696 29212 14696 29213 14108 29213 14109 29213 14696 29214 14109 29214 14698 29214 14698 29215 14109 29215 14704 29215 14698 29216 14704 29216 14700 29216 14700 29217 14704 29217 14705 29217 14700 29218 14705 29218 14706 29218 14706 29219 14705 29219 14707 29219 14706 29220 14707 29220 14702 29220 14702 29221 14707 29221 14708 29221 14702 29222 14708 29222 13097 29222 13097 29223 14708 29223 14106 29223 14716 29224 13007 29224 14710 29224 14710 29225 13007 29225 14709 29225 14710 29226 14709 29226 14711 29226 14711 29227 14709 29227 14825 29227 14711 29228 14825 29228 14718 29228 14718 29229 14825 29229 14826 29229 14718 29230 14826 29230 14719 29230 14719 29231 14826 29231 14712 29231 14719 29232 14712 29232 14713 29232 14713 29233 14712 29233 14828 29233 14713 29234 14828 29234 14722 29234 14722 29235 14828 29235 13083 29235 14727 29236 14714 29236 14773 29236 14773 29237 14714 29237 14716 29237 14773 29238 14716 29238 14715 29238 14715 29239 14716 29239 14710 29239 14715 29240 14710 29240 14776 29240 14776 29241 14710 29241 14711 29241 14776 29242 14711 29242 14717 29242 14717 29243 14711 29243 14718 29243 14717 29244 14718 29244 14720 29244 14720 29245 14718 29245 14719 29245 14720 29246 14719 29246 14779 29246 14779 29247 14719 29247 14713 29247 14779 29248 14713 29248 13046 29248 13046 29249 14713 29249 14722 29249 13046 29250 14722 29250 14721 29250 14721 29251 14722 29251 14724 29251 14721 29252 14724 29252 14723 29252 14723 29253 14724 29253 13085 29253 14723 29254 13085 29254 13048 29254 13048 29255 13085 29255 14725 29255 13048 29256 14725 29256 13049 29256 13049 29257 14725 29257 14726 29257 13049 29258 14726 29258 13052 29258 13052 29259 14726 29259 13089 29259 13052 29260 13089 29260 14727 29260 14727 29261 13089 29261 14714 29261 13002 29262 14841 29262 14735 29262 14735 29263 14841 29263 14736 29263 14841 29264 14728 29264 14736 29264 14736 29265 14728 29265 14840 29265 14736 29266 14840 29266 14729 29266 14840 29267 14839 29267 14729 29267 14729 29268 14839 29268 14838 29268 14729 29269 14838 29269 14731 29269 14838 29270 14730 29270 14731 29270 14731 29271 14730 29271 14837 29271 14731 29272 14837 29272 14732 29272 14837 29273 14836 29273 14732 29273 14732 29274 14836 29274 14834 29274 14732 29275 14834 29275 14734 29275 14831 29276 14739 29276 14733 29276 14733 29277 14739 29277 14734 29277 14733 29278 14734 29278 14833 29278 14833 29279 14734 29279 14834 29279 14742 29280 14743 29280 13032 29280 13032 29281 14743 29281 13082 29281 13032 29282 13082 29282 13034 29282 13034 29283 13082 29283 14735 29283 13034 29284 14735 29284 14795 29284 14795 29285 14735 29285 14736 29285 14795 29286 14736 29286 14737 29286 14737 29287 14736 29287 14729 29287 14737 29288 14729 29288 14797 29288 14797 29289 14729 29289 14731 29289 14797 29290 14731 29290 14738 29290 14738 29291 14731 29291 14732 29291 14738 29292 14732 29292 14798 29292 14798 29293 14732 29293 14734 29293 14798 29294 14734 29294 14799 29294 14799 29295 14734 29295 14739 29295 14799 29296 14739 29296 13027 29296 13027 29297 14739 29297 14741 29297 13027 29298 14741 29298 14740 29298 14740 29299 14741 29299 13079 29299 14740 29300 13079 29300 13030 29300 13030 29301 13079 29301 13081 29301 13030 29302 13081 29302 14742 29302 14742 29303 13081 29303 14743 29303 14763 29304 14842 29304 14764 29304 14764 29305 14842 29305 14744 29305 14764 29306 14744 29306 14745 29306 14745 29307 14744 29307 14746 29307 14745 29308 14746 29308 14754 29308 14754 29309 14746 29309 14843 29309 14754 29310 14843 29310 14748 29310 14748 29311 14843 29311 14747 29311 14748 29312 14747 29312 14756 29312 14756 29313 14747 29313 14844 29313 14756 29314 14844 29314 14758 29314 14758 29315 14844 29315 14749 29315 14758 29316 14749 29316 14750 29316 14750 29317 14749 29317 14751 29317 14752 29318 14764 29318 14821 29318 14821 29319 14764 29319 14745 29319 14821 29320 14745 29320 14753 29320 14753 29321 14745 29321 14754 29321 14753 29322 14754 29322 14823 29322 14823 29323 14754 29323 14748 29323 14823 29324 14748 29324 14755 29324 14755 29325 14748 29325 14756 29325 14755 29326 14756 29326 14757 29326 14757 29327 14756 29327 14758 29327 14757 29328 14758 29328 14759 29328 14759 29329 14758 29329 14750 29329 14759 29330 14750 29330 13008 29330 13008 29331 14750 29331 13070 29331 13008 29332 13070 29332 14760 29332 14760 29333 13070 29333 13071 29333 14760 29334 13071 29334 13011 29334 13011 29335 13071 29335 14762 29335 13011 29336 14762 29336 14761 29336 14761 29337 14762 29337 13074 29337 14761 29338 13074 29338 13012 29338 13012 29339 13074 29339 13075 29339 13012 29340 13075 29340 14820 29340 14820 29341 13075 29341 14763 29341 14820 29342 14763 29342 14752 29342 14752 29343 14763 29343 14764 29343 13068 29344 13069 29344 14766 29344 14766 29345 13069 29345 14765 29345 14766 29346 14765 29346 14767 29346 14767 29347 14765 29347 13847 29347 14767 29348 13847 29348 14771 29348 14771 29349 13847 29349 13849 29349 14771 29350 13849 29350 14768 29350 14768 29351 13849 29351 13850 29351 14768 29352 13850 29352 14770 29352 14770 29353 13850 29353 13851 29353 14770 29354 13851 29354 13057 29354 13057 29355 13851 29355 13853 29355 13057 29356 14769 29356 14770 29356 14770 29357 14769 29357 14774 29357 14770 29358 14774 29358 14768 29358 14768 29359 14774 29359 14775 29359 14768 29360 14775 29360 14771 29360 14771 29361 14775 29361 14777 29361 14771 29362 14777 29362 14767 29362 14767 29363 14777 29363 14778 29363 14767 29364 14778 29364 14766 29364 14766 29365 14778 29365 14772 29365 14766 29366 14772 29366 13068 29366 13068 29367 14772 29367 13053 29367 14769 29368 14773 29368 14774 29368 14774 29369 14773 29369 14715 29369 14774 29370 14715 29370 14775 29370 14775 29371 14715 29371 14776 29371 14775 29372 14776 29372 14777 29372 14777 29373 14776 29373 14717 29373 14777 29374 14717 29374 14778 29374 14778 29375 14717 29375 14720 29375 14778 29376 14720 29376 14772 29376 14772 29377 14720 29377 14779 29377 14772 29378 14779 29378 13053 29378 13053 29379 14779 29379 13046 29379 13035 29380 14780 29380 14792 29380 14792 29381 14780 29381 14781 29381 14792 29382 14781 29382 14791 29382 14791 29383 14781 29383 13858 29383 14791 29384 13858 29384 14782 29384 14782 29385 13858 29385 13859 29385 14782 29386 13859 29386 14788 29386 14788 29387 13859 29387 14783 29387 14788 29388 14783 29388 14784 29388 14784 29389 14783 29389 13861 29389 14784 29390 13861 29390 14785 29390 14785 29391 13861 29391 14786 29391 14785 29392 13033 29392 14784 29392 14784 29393 13033 29393 14787 29393 14784 29394 14787 29394 14788 29394 14788 29395 14787 29395 14789 29395 14788 29396 14789 29396 14782 29396 14782 29397 14789 29397 14790 29397 14782 29398 14790 29398 14791 29398 14791 29399 14790 29399 14796 29399 14791 29400 14796 29400 14792 29400 14792 29401 14796 29401 14793 29401 14792 29402 14793 29402 13035 29402 13035 29403 14793 29403 14794 29403 13033 29404 13034 29404 14787 29404 14787 29405 13034 29405 14795 29405 14787 29406 14795 29406 14789 29406 14789 29407 14795 29407 14737 29407 14789 29408 14737 29408 14790 29408 14790 29409 14737 29409 14797 29409 14790 29410 14797 29410 14796 29410 14796 29411 14797 29411 14738 29411 14796 29412 14738 29412 14793 29412 14793 29413 14738 29413 14798 29413 14793 29414 14798 29414 14794 29414 14794 29415 14798 29415 14799 29415 13019 29416 14800 29416 13872 29416 13872 29417 14800 29417 14801 29417 13872 29418 14801 29418 13870 29418 14801 29419 14813 29419 13870 29419 13870 29420 14813 29420 14802 29420 13870 29421 14802 29421 14804 29421 14804 29422 14802 29422 14803 29422 14803 29423 14814 29423 14804 29423 14804 29424 14814 29424 14816 29424 14804 29425 14816 29425 14810 29425 14805 29426 14807 29426 14806 29426 14806 29427 14807 29427 14808 29427 14806 29428 14808 29428 14809 29428 14809 29429 14808 29429 14810 29429 14809 29430 14810 29430 14811 29430 14811 29431 14810 29431 14816 29431 14800 29432 13013 29432 14819 29432 14800 29433 14819 29433 14801 29433 14801 29434 14819 29434 14812 29434 14801 29435 14812 29435 14813 29435 14813 29436 14812 29436 14802 29436 14802 29437 14812 29437 14822 29437 14802 29438 14822 29438 14803 29438 14803 29439 14822 29439 14814 29439 14814 29440 14822 29440 14815 29440 14814 29441 14815 29441 14816 29441 14816 29442 14815 29442 14811 29442 14811 29443 14815 29443 14824 29443 14811 29444 14824 29444 14809 29444 14809 29445 14824 29445 14817 29445 14809 29446 14817 29446 14806 29446 14806 29447 14817 29447 14818 29447 14806 29448 14818 29448 14805 29448 13013 29449 14820 29449 14819 29449 14819 29450 14820 29450 14752 29450 14819 29451 14752 29451 14812 29451 14812 29452 14752 29452 14821 29452 14812 29453 14821 29453 14822 29453 14822 29454 14821 29454 14753 29454 14822 29455 14753 29455 14815 29455 14815 29456 14753 29456 14823 29456 14815 29457 14823 29457 14824 29457 14824 29458 14823 29458 14755 29458 14824 29459 14755 29459 14817 29459 14817 29460 14755 29460 14757 29460 14817 29461 14757 29461 14818 29461 14818 29462 14757 29462 14759 29462 13007 29463 14081 29463 14709 29463 14709 29464 14081 29464 14080 29464 14709 29465 14080 29465 14825 29465 14825 29466 14080 29466 14827 29466 14825 29467 14827 29467 14826 29467 14826 29468 14827 29468 14079 29468 14826 29469 14079 29469 14712 29469 14712 29470 14079 29470 14829 29470 14712 29471 14829 29471 14828 29471 14828 29472 14829 29472 14078 29472 14828 29473 14078 29473 13083 29473 13083 29474 14078 29474 13004 29474 14832 29475 14830 29475 14831 29475 14831 29476 14733 29476 14832 29476 14832 29477 14733 29477 14833 29477 14832 29478 14833 29478 14835 29478 14833 29479 14834 29479 14835 29479 14835 29480 14834 29480 14836 29480 14835 29481 14836 29481 14090 29481 14836 29482 14837 29482 14090 29482 14090 29483 14837 29483 14730 29483 14090 29484 14730 29484 14088 29484 14088 29485 14730 29485 14838 29485 14088 29486 14838 29486 14072 29486 14838 29487 14839 29487 14072 29487 14072 29488 14839 29488 14840 29488 14072 29489 14840 29489 14070 29489 13002 29490 14087 29490 14841 29490 14841 29491 14087 29491 14070 29491 14841 29492 14070 29492 14728 29492 14728 29493 14070 29493 14840 29493 14842 29494 12996 29494 14744 29494 14744 29495 12996 29495 14055 29495 14744 29496 14055 29496 14746 29496 14746 29497 14055 29497 14054 29497 14746 29498 14054 29498 14843 29498 14843 29499 14054 29499 14104 29499 14843 29500 14104 29500 14747 29500 14747 29501 14104 29501 14102 29501 14747 29502 14102 29502 14844 29502 14844 29503 14102 29503 14101 29503 14844 29504 14101 29504 14749 29504 14749 29505 14101 29505 14063 29505 14749 29506 14063 29506 14751 29506 14751 29507 14063 29507 12993 29507 12986 29508 14845 29508 14846 29508 14846 29509 14845 29509 14855 29509 14846 29510 14855 29510 14847 29510 14847 29511 14855 29511 14857 29511 14857 29512 14848 29512 14847 29512 14847 29513 14848 29513 14849 29513 14847 29514 14849 29514 13800 29514 14849 29515 14859 29515 13800 29515 13800 29516 14859 29516 14850 29516 13800 29517 14850 29517 13799 29517 14861 29518 13796 29518 14851 29518 14851 29519 13796 29519 14852 29519 14851 29520 14852 29520 14853 29520 14853 29521 14852 29521 13799 29521 14853 29522 13799 29522 14860 29522 14860 29523 13799 29523 14850 29523 14845 29524 14854 29524 14862 29524 14845 29525 14862 29525 14855 29525 14855 29526 14862 29526 14856 29526 14855 29527 14856 29527 14857 29527 14857 29528 14856 29528 14848 29528 14848 29529 14856 29529 14864 29529 14848 29530 14864 29530 14849 29530 14849 29531 14864 29531 14859 29531 14859 29532 14864 29532 14858 29532 14859 29533 14858 29533 14850 29533 14850 29534 14858 29534 14860 29534 14860 29535 14858 29535 14865 29535 14860 29536 14865 29536 14853 29536 14853 29537 14865 29537 14867 29537 14853 29538 14867 29538 14851 29538 14851 29539 14867 29539 12978 29539 14851 29540 12978 29540 14861 29540 14854 29541 14388 29541 14862 29541 14862 29542 14388 29542 14262 29542 14862 29543 14262 29543 14856 29543 14856 29544 14262 29544 14863 29544 14856 29545 14863 29545 14864 29545 14864 29546 14863 29546 14263 29546 14864 29547 14263 29547 14858 29547 14858 29548 14263 29548 14866 29548 14858 29549 14866 29549 14865 29549 14865 29550 14866 29550 14266 29550 14865 29551 14266 29551 14867 29551 14867 29552 14266 29552 14868 29552 14867 29553 14868 29553 12978 29553 12978 29554 14868 29554 14265 29554 12977 29555 13810 29555 14882 29555 14882 29556 13810 29556 14869 29556 14882 29557 14869 29557 14881 29557 14881 29558 14869 29558 13812 29558 14881 29559 13812 29559 14870 29559 14870 29560 13812 29560 13814 29560 14870 29561 13814 29561 14871 29561 14871 29562 13814 29562 14872 29562 14871 29563 14872 29563 14873 29563 14873 29564 14872 29564 14874 29564 14873 29565 14874 29565 12970 29565 12970 29566 14874 29566 14875 29566 12970 29567 14876 29567 14873 29567 14873 29568 14876 29568 14877 29568 14873 29569 14877 29569 14871 29569 14871 29570 14877 29570 14878 29570 14871 29571 14878 29571 14870 29571 14870 29572 14878 29572 14879 29572 14870 29573 14879 29573 14881 29573 14881 29574 14879 29574 14880 29574 14881 29575 14880 29575 14882 29575 14882 29576 14880 29576 14887 29576 14882 29577 14887 29577 12977 29577 12977 29578 14887 29578 12958 29578 14876 29579 14883 29579 14877 29579 14877 29580 14883 29580 14884 29580 14877 29581 14884 29581 14878 29581 14878 29582 14884 29582 14885 29582 14878 29583 14885 29583 14879 29583 14879 29584 14885 29584 14886 29584 14879 29585 14886 29585 14880 29585 14880 29586 14886 29586 14093 29586 14880 29587 14093 29587 14887 29587 14887 29588 14093 29588 14092 29588 14887 29589 14092 29589 12958 29589 12958 29590 14092 29590 14888 29590 12957 29591 14889 29591 14901 29591 14901 29592 14889 29592 14890 29592 14901 29593 14890 29593 14892 29593 14892 29594 14890 29594 14891 29594 14892 29595 14891 29595 14898 29595 14898 29596 14891 29596 13821 29596 14898 29597 13821 29597 14893 29597 14893 29598 13821 29598 14894 29598 14893 29599 14894 29599 14895 29599 14895 29600 14894 29600 14896 29600 14895 29601 14896 29601 12950 29601 12950 29602 14896 29602 12951 29602 12950 29603 14902 29603 14895 29603 14895 29604 14902 29604 14897 29604 14895 29605 14897 29605 14893 29605 14893 29606 14897 29606 14904 29606 14893 29607 14904 29607 14898 29607 14898 29608 14904 29608 14899 29608 14898 29609 14899 29609 14892 29609 14892 29610 14899 29610 14900 29610 14892 29611 14900 29611 14901 29611 14901 29612 14900 29612 14908 29612 14901 29613 14908 29613 12957 29613 12957 29614 14908 29614 14910 29614 14902 29615 14903 29615 14897 29615 14897 29616 14903 29616 14074 29616 14897 29617 14074 29617 14904 29617 14904 29618 14074 29618 14905 29618 14904 29619 14905 29619 14899 29619 14899 29620 14905 29620 14906 29620 14899 29621 14906 29621 14900 29621 14900 29622 14906 29622 14907 29622 14900 29623 14907 29623 14908 29623 14908 29624 14907 29624 14909 29624 14908 29625 14909 29625 14910 29625 14910 29626 14909 29626 14075 29626 13839 29627 12935 29627 14911 29627 14911 29628 14912 29628 13839 29628 13839 29629 14912 29629 14913 29629 13839 29630 14913 29630 14914 29630 14913 29631 14923 29631 14914 29631 14914 29632 14923 29632 14924 29632 14914 29633 14924 29633 14915 29633 14924 29634 14926 29634 14915 29634 14915 29635 14926 29635 14927 29635 14915 29636 14927 29636 14916 29636 14916 29637 14927 29637 14928 29637 14916 29638 14928 29638 13836 29638 14928 29639 14917 29639 13836 29639 13836 29640 14917 29640 14918 29640 13836 29641 14918 29641 14920 29641 14919 29642 13835 29642 14931 29642 14931 29643 13835 29643 14920 29643 14931 29644 14920 29644 14930 29644 14930 29645 14920 29645 14918 29645 14911 29646 14921 29646 14912 29646 14912 29647 14921 29647 14922 29647 14912 29648 14922 29648 14913 29648 14913 29649 14922 29649 14923 29649 14923 29650 14922 29650 14925 29650 14923 29651 14925 29651 14924 29651 14924 29652 14925 29652 14926 29652 14926 29653 14925 29653 14933 29653 14926 29654 14933 29654 14927 29654 14927 29655 14933 29655 14928 29655 14928 29656 14933 29656 14929 29656 14928 29657 14929 29657 14917 29657 14917 29658 14929 29658 14918 29658 14918 29659 14929 29659 14932 29659 14918 29660 14932 29660 14930 29660 14930 29661 14932 29661 14931 29661 14931 29662 14932 29662 14935 29662 14931 29663 14935 29663 14919 29663 14921 29664 14067 29664 14922 29664 14922 29665 14067 29665 14065 29665 14922 29666 14065 29666 14925 29666 14925 29667 14065 29667 14062 29667 14925 29668 14062 29668 14933 29668 14933 29669 14062 29669 14934 29669 14933 29670 14934 29670 14929 29670 14929 29671 14934 29671 14061 29671 14929 29672 14061 29672 14932 29672 14932 29673 14061 29673 14060 29673 14932 29674 14060 29674 14935 29674 14935 29675 14060 29675 14059 29675 14936 29676 12815 29676 14937 29676 14936 29677 14937 29677 14949 29677 14949 29678 14937 29678 15053 29678 14949 29679 15053 29679 14950 29679 14950 29680 15053 29680 15054 29680 14950 29681 15054 29681 14951 29681 15054 29682 15050 29682 14951 29682 14951 29683 15050 29683 14938 29683 14951 29684 14938 29684 14953 29684 14938 29685 15049 29685 14953 29685 14953 29686 15049 29686 14939 29686 14953 29687 14939 29687 14940 29687 14939 29688 14941 29688 14940 29688 14940 29689 14941 29689 15047 29689 14940 29690 15047 29690 14942 29690 14942 29691 15047 29691 12905 29691 14942 29692 12905 29692 12906 29692 14952 29693 14940 29693 14997 29693 14997 29694 14940 29694 14942 29694 14997 29695 14942 29695 14998 29695 14998 29696 14942 29696 12906 29696 14998 29697 12906 29697 14943 29697 14943 29698 12906 29698 14944 29698 14943 29699 14944 29699 14945 29699 14945 29700 14944 29700 12907 29700 14945 29701 12907 29701 14946 29701 14946 29702 12907 29702 14947 29702 14946 29703 14947 29703 12873 29703 12873 29704 14947 29704 12913 29704 12873 29705 12913 29705 12874 29705 12874 29706 12913 29706 12914 29706 12874 29707 12914 29707 12875 29707 12875 29708 12914 29708 14936 29708 12875 29709 14936 29709 14948 29709 14948 29710 14936 29710 14949 29710 14948 29711 14949 29711 14993 29711 14993 29712 14949 29712 14950 29712 14993 29713 14950 29713 14995 29713 14995 29714 14950 29714 14951 29714 14995 29715 14951 29715 14996 29715 14996 29716 14951 29716 14953 29716 14996 29717 14953 29717 14952 29717 14952 29718 14953 29718 14940 29718 14456 29719 14955 29719 14954 29719 14954 29720 14955 29720 14956 29720 14954 29721 14956 29721 14957 29721 14957 29722 14956 29722 15055 29722 14957 29723 15055 29723 14958 29723 14958 29724 15055 29724 15059 29724 14958 29725 15059 29725 14448 29725 14448 29726 15059 29726 14959 29726 14448 29727 14959 29727 14450 29727 14450 29728 14959 29728 15061 29728 14450 29729 15061 29729 14960 29729 14960 29730 15061 29730 15062 29730 14960 29731 15062 29731 12899 29731 12899 29732 15062 29732 15063 29732 14969 29733 12799 29733 14961 29733 14961 29734 12799 29734 15064 29734 14961 29735 15064 29735 14962 29735 14962 29736 15064 29736 14963 29736 14962 29737 14963 29737 14967 29737 14967 29738 14963 29738 15066 29738 14967 29739 15066 29739 14964 29739 14964 29740 15066 29740 15068 29740 14964 29741 15068 29741 14965 29741 14965 29742 15068 29742 14966 29742 14965 29743 14966 29743 12888 29743 12888 29744 14966 29744 12886 29744 15039 29745 15041 29745 14967 29745 14967 29746 15041 29746 14968 29746 14967 29747 14968 29747 14962 29747 14962 29748 14968 29748 15042 29748 14962 29749 15042 29749 14961 29749 14961 29750 15042 29750 15044 29750 14961 29751 15044 29751 14969 29751 14969 29752 15044 29752 15045 29752 14969 29753 15045 29753 12898 29753 12898 29754 15045 29754 14970 29754 12898 29755 14970 29755 12894 29755 12894 29756 14970 29756 12832 29756 12894 29757 12832 29757 14971 29757 14971 29758 12832 29758 14972 29758 14971 29759 14972 29759 12891 29759 12891 29760 14972 29760 14973 29760 12891 29761 14973 29761 12889 29761 12889 29762 14973 29762 14974 29762 12889 29763 14974 29763 12888 29763 12888 29764 14974 29764 12828 29764 12888 29765 12828 29765 14965 29765 14965 29766 12828 29766 14975 29766 14965 29767 14975 29767 14964 29767 14964 29768 14975 29768 15039 29768 14964 29769 15039 29769 14967 29769 14990 29770 14976 29770 14977 29770 14977 29771 14976 29771 13765 29771 14977 29772 13765 29772 14978 29772 14978 29773 13765 29773 14979 29773 14978 29774 14979 29774 14980 29774 14980 29775 14979 29775 13766 29775 14980 29776 13766 29776 14981 29776 14981 29777 13766 29777 14982 29777 14981 29778 14982 29778 14986 29778 14986 29779 14982 29779 14984 29779 14986 29780 14984 29780 14983 29780 14983 29781 14984 29781 13767 29781 14983 29782 13767 29782 14985 29782 14985 29783 13767 29783 13756 29783 14985 29784 12881 29784 14983 29784 14983 29785 12881 29785 14992 29785 14983 29786 14992 29786 14986 29786 14986 29787 14992 29787 14994 29787 14986 29788 14994 29788 14981 29788 14981 29789 14994 29789 14987 29789 14981 29790 14987 29790 14980 29790 14980 29791 14987 29791 14988 29791 14980 29792 14988 29792 14978 29792 14978 29793 14988 29793 14989 29793 14978 29794 14989 29794 14977 29794 14977 29795 14989 29795 14991 29795 14977 29796 14991 29796 14990 29796 14990 29797 14991 29797 12869 29797 12881 29798 12875 29798 14992 29798 14992 29799 12875 29799 14948 29799 14992 29800 14948 29800 14994 29800 14994 29801 14948 29801 14993 29801 14994 29802 14993 29802 14987 29802 14987 29803 14993 29803 14995 29803 14987 29804 14995 29804 14988 29804 14988 29805 14995 29805 14996 29805 14988 29806 14996 29806 14989 29806 14989 29807 14996 29807 14952 29807 14989 29808 14952 29808 14991 29808 14991 29809 14952 29809 14997 29809 14991 29810 14997 29810 12869 29810 12869 29811 14997 29811 14998 29811 15013 29812 14999 29812 15000 29812 15000 29813 14999 29813 13776 29813 15000 29814 13776 29814 15011 29814 15011 29815 13776 29815 13778 29815 15011 29816 13778 29816 15009 29816 15009 29817 13778 29817 15001 29817 15009 29818 15001 29818 15002 29818 15002 29819 15001 29819 13779 29819 15002 29820 13779 29820 15003 29820 15003 29821 13779 29821 15004 29821 15003 29822 15004 29822 15005 29822 15005 29823 15004 29823 13768 29823 15005 29824 13768 29824 12864 29824 12864 29825 13768 29825 13770 29825 12864 29826 15006 29826 15005 29826 15005 29827 15006 29827 15007 29827 15005 29828 15007 29828 15003 29828 15003 29829 15007 29829 15017 29829 15003 29830 15017 29830 15002 29830 15002 29831 15017 29831 15008 29831 15002 29832 15008 29832 15009 29832 15009 29833 15008 29833 15010 29833 15009 29834 15010 29834 15011 29834 15011 29835 15010 29835 15012 29835 15011 29836 15012 29836 15000 29836 15000 29837 15012 29837 15014 29837 15000 29838 15014 29838 15013 29838 15013 29839 15014 29839 15015 29839 15006 29840 12859 29840 15007 29840 15007 29841 12859 29841 15016 29841 15007 29842 15016 29842 15017 29842 15017 29843 15016 29843 15018 29843 15017 29844 15018 29844 15008 29844 15008 29845 15018 29845 15019 29845 15008 29846 15019 29846 15010 29846 15010 29847 15019 29847 15020 29847 15010 29848 15020 29848 15012 29848 15012 29849 15020 29849 14449 29849 15012 29850 14449 29850 15014 29850 15014 29851 14449 29851 14451 29851 15014 29852 14451 29852 15015 29852 15015 29853 14451 29853 12852 29853 15034 29854 13791 29854 15033 29854 15033 29855 13791 29855 13790 29855 15033 29856 13790 29856 15021 29856 15021 29857 13790 29857 13789 29857 15021 29858 13789 29858 15030 29858 15030 29859 13789 29859 13787 29859 15030 29860 13787 29860 15028 29860 15028 29861 13787 29861 15022 29861 15028 29862 15022 29862 15027 29862 15027 29863 15022 29863 15023 29863 15027 29864 15023 29864 15024 29864 15024 29865 15023 29865 12850 29865 12841 29866 15025 29866 15024 29866 15024 29867 15025 29867 15027 29867 15025 29868 15046 29868 15027 29868 15027 29869 15046 29869 15026 29869 15027 29870 15026 29870 15028 29870 15026 29871 15043 29871 15028 29871 15028 29872 15043 29872 15029 29872 15028 29873 15029 29873 15030 29873 15029 29874 15031 29874 15030 29874 15030 29875 15031 29875 15032 29875 15030 29876 15032 29876 15021 29876 15032 29877 15040 29877 15021 29877 15021 29878 15040 29878 15038 29878 15021 29879 15038 29879 15033 29879 15036 29880 15034 29880 15035 29880 15035 29881 15034 29881 15033 29881 15035 29882 15033 29882 15037 29882 15037 29883 15033 29883 15038 29883 14975 29884 12828 29884 15036 29884 15036 29885 15035 29885 14975 29885 14975 29886 15035 29886 15037 29886 14975 29887 15037 29887 15039 29887 15037 29888 15038 29888 15039 29888 15039 29889 15038 29889 15040 29889 15039 29890 15040 29890 15041 29890 15040 29891 15032 29891 15041 29891 15041 29892 15032 29892 15031 29892 15041 29893 15031 29893 14968 29893 14968 29894 15031 29894 15029 29894 14968 29895 15029 29895 15042 29895 15029 29896 15043 29896 15042 29896 15042 29897 15043 29897 15026 29897 15042 29898 15026 29898 15044 29898 12841 29899 15045 29899 15025 29899 15025 29900 15045 29900 15044 29900 15025 29901 15044 29901 15046 29901 15046 29902 15044 29902 15026 29902 12823 29903 12905 29903 14184 29903 14184 29904 12905 29904 15047 29904 14184 29905 15047 29905 15048 29905 15048 29906 15047 29906 14941 29906 14941 29907 14939 29907 15048 29907 15048 29908 14939 29908 15049 29908 15048 29909 15049 29909 14176 29909 15049 29910 14938 29910 14176 29910 14176 29911 14938 29911 15050 29911 14176 29912 15050 29912 14177 29912 12815 29913 15051 29913 14937 29913 14937 29914 15051 29914 15052 29914 14937 29915 15052 29915 15053 29915 15053 29916 15052 29916 14177 29916 15053 29917 14177 29917 15054 29917 15054 29918 14177 29918 15050 29918 14955 29919 14035 29919 14956 29919 14956 29920 14035 29920 15056 29920 14956 29921 15056 29921 15055 29921 15055 29922 15056 29922 15057 29922 15055 29923 15057 29923 15059 29923 15059 29924 15057 29924 15058 29924 15059 29925 15058 29925 14959 29925 14959 29926 15058 29926 15060 29926 14959 29927 15060 29927 15061 29927 15061 29928 15060 29928 14036 29928 15061 29929 14036 29929 15062 29929 15062 29930 14036 29930 14413 29930 15062 29931 14413 29931 15063 29931 15063 29932 14413 29932 14414 29932 12799 29933 14051 29933 15064 29933 15064 29934 14051 29934 14050 29934 15064 29935 14050 29935 14963 29935 14963 29936 14050 29936 15065 29936 14963 29937 15065 29937 15066 29937 15066 29938 15065 29938 15067 29938 15066 29939 15067 29939 15068 29939 15068 29940 15067 29940 14049 29940 15068 29941 14049 29941 14966 29941 14966 29942 14049 29942 15069 29942 14966 29943 15069 29943 12886 29943 12886 29944 15069 29944 14047 29944 15070 29945 13709 29945 15071 29945 15071 29946 13709 29946 13710 29946 15071 29947 13710 29947 15072 29947 15072 29948 13710 29948 13711 29948 15072 29949 13711 29949 15078 29949 15078 29950 13711 29950 15073 29950 15078 29951 15073 29951 15076 29951 15076 29952 15073 29952 13698 29952 15076 29953 13698 29953 15075 29953 15075 29954 13698 29954 13699 29954 15075 29955 13699 29955 15074 29955 15074 29956 13699 29956 13701 29956 15074 29957 13701 29957 12790 29957 12790 29958 13701 29958 13702 29958 12790 29959 12783 29959 15074 29959 15074 29960 12783 29960 15079 29960 15074 29961 15079 29961 15075 29961 15075 29962 15079 29962 15080 29962 15075 29963 15080 29963 15076 29963 15076 29964 15080 29964 15077 29964 15076 29965 15077 29965 15078 29965 15078 29966 15077 29966 15083 29966 15078 29967 15083 29967 15072 29967 15072 29968 15083 29968 15084 29968 15072 29969 15084 29969 15071 29969 15071 29970 15084 29970 15085 29970 15071 29971 15085 29971 15070 29971 15070 29972 15085 29972 15087 29972 12783 29973 14174 29973 15079 29973 15079 29974 14174 29974 15081 29974 15079 29975 15081 29975 15080 29975 15080 29976 15081 29976 15082 29976 15080 29977 15082 29977 15077 29977 15077 29978 15082 29978 14181 29978 15077 29979 14181 29979 15083 29979 15083 29980 14181 29980 14182 29980 15083 29981 14182 29981 15084 29981 15084 29982 14182 29982 14183 29982 15084 29983 14183 29983 15085 29983 15085 29984 14183 29984 15086 29984 15085 29985 15086 29985 15087 29985 15087 29986 15086 29986 12780 29986 15097 29987 13717 29987 15096 29987 15096 29988 13717 29988 13718 29988 15096 29989 13718 29989 15088 29989 15088 29990 13718 29990 13719 29990 15088 29991 13719 29991 15095 29991 15095 29992 13719 29992 13721 29992 15095 29993 13721 29993 15089 29993 15089 29994 13721 29994 13722 29994 15089 29995 13722 29995 15091 29995 15091 29996 13722 29996 15090 29996 15091 29997 15090 29997 12769 29997 12769 29998 15090 29998 13724 29998 12769 29999 12763 29999 15091 29999 15091 30000 12763 30000 15092 30000 15091 30001 15092 30001 15089 30001 15089 30002 15092 30002 15093 30002 15089 30003 15093 30003 15095 30003 15095 30004 15093 30004 15094 30004 15095 30005 15094 30005 15088 30005 15088 30006 15094 30006 15098 30006 15088 30007 15098 30007 15096 30007 15096 30008 15098 30008 15099 30008 15096 30009 15099 30009 15097 30009 15097 30010 15099 30010 12764 30010 12763 30011 14190 30011 15092 30011 15092 30012 14190 30012 14319 30012 15092 30013 14319 30013 15093 30013 15093 30014 14319 30014 14189 30014 15093 30015 14189 30015 15094 30015 15094 30016 14189 30016 14188 30016 15094 30017 14188 30017 15098 30017 15098 30018 14188 30018 14186 30018 15098 30019 14186 30019 15099 30019 15099 30020 14186 30020 14185 30020 15099 30021 14185 30021 12764 30021 12764 30022 14185 30022 15100 30022 15115 30023 15102 30023 15101 30023 15101 30024 15102 30024 15103 30024 15101 30025 15103 30025 15104 30025 15104 30026 15103 30026 13736 30026 15104 30027 13736 30027 15105 30027 15105 30028 13736 30028 13738 30028 15105 30029 13738 30029 15106 30029 15106 30030 13738 30030 15107 30030 15106 30031 15107 30031 15111 30031 15111 30032 15107 30032 13741 30032 15111 30033 13741 30033 15109 30033 15109 30034 13741 30034 15108 30034 15109 30035 15110 30035 15111 30035 15111 30036 15110 30036 15119 30036 15111 30037 15119 30037 15106 30037 15106 30038 15119 30038 15112 30038 15106 30039 15112 30039 15105 30039 15105 30040 15112 30040 15113 30040 15105 30041 15113 30041 15104 30041 15104 30042 15113 30042 15114 30042 15104 30043 15114 30043 15101 30043 15101 30044 15114 30044 15116 30044 15101 30045 15116 30045 15115 30045 15115 30046 15116 30046 12743 30046 15110 30047 15117 30047 15119 30047 15119 30048 15117 30048 15118 30048 15119 30049 15118 30049 15112 30049 15112 30050 15118 30050 15120 30050 15112 30051 15120 30051 15113 30051 15113 30052 15120 30052 15121 30052 15113 30053 15121 30053 15114 30053 15114 30054 15121 30054 14043 30054 15114 30055 14043 30055 15116 30055 15116 30056 14043 30056 15122 30056 15116 30057 15122 30057 12743 30057 12743 30058 15122 30058 15123 30058 12719 30059 13746 30059 15124 30059 15124 30060 13746 30060 13747 30060 15124 30061 13747 30061 15133 30061 15133 30062 13747 30062 15125 30062 15133 30063 15125 30063 15131 30063 15131 30064 15125 30064 13749 30064 15131 30065 13749 30065 15126 30065 15126 30066 13749 30066 15128 30066 15126 30067 15128 30067 15127 30067 15127 30068 15128 30068 13751 30068 15127 30069 13751 30069 12726 30069 12726 30070 13751 30070 12727 30070 12726 30071 12718 30071 15127 30071 15127 30072 12718 30072 15129 30072 15127 30073 15129 30073 15126 30073 15126 30074 15129 30074 15130 30074 15126 30075 15130 30075 15131 30075 15131 30076 15130 30076 15132 30076 15131 30077 15132 30077 15133 30077 15133 30078 15132 30078 15137 30078 15133 30079 15137 30079 15124 30079 15124 30080 15137 30080 15139 30080 15124 30081 15139 30081 12719 30081 12719 30082 15139 30082 15134 30082 12718 30083 14346 30083 15129 30083 15129 30084 14346 30084 15135 30084 15129 30085 15135 30085 15130 30085 15130 30086 15135 30086 15136 30086 15130 30087 15136 30087 15132 30087 15132 30088 15136 30088 15138 30088 15132 30089 15138 30089 15137 30089 15137 30090 15138 30090 14337 30090 15137 30091 14337 30091 15139 30091 15139 30092 14337 30092 15140 30092 15139 30093 15140 30093 15134 30093 15134 30094 15140 30094 14345 30094 15148 30095 12622 30095 15141 30095 15141 30096 12622 30096 15142 30096 15141 30097 15142 30097 15150 30097 15150 30098 15142 30098 15143 30098 15150 30099 15143 30099 15153 30099 15153 30100 15143 30100 15144 30100 15153 30101 15144 30101 15154 30101 15154 30102 15144 30102 15263 30102 15154 30103 15263 30103 15145 30103 15145 30104 15263 30104 15264 30104 15145 30105 15264 30105 15155 30105 15155 30106 15264 30106 12710 30106 12674 30107 15146 30107 15147 30107 15147 30108 15146 30108 15148 30108 15147 30109 15148 30109 15149 30109 15149 30110 15148 30110 15141 30110 15149 30111 15141 30111 15220 30111 15220 30112 15141 30112 15150 30112 15220 30113 15150 30113 15151 30113 15151 30114 15150 30114 15153 30114 15151 30115 15153 30115 15152 30115 15152 30116 15153 30116 15154 30116 15152 30117 15154 30117 15223 30117 15223 30118 15154 30118 15145 30118 15223 30119 15145 30119 12666 30119 12666 30120 15145 30120 15155 30120 12666 30121 15155 30121 15156 30121 15156 30122 15155 30122 15157 30122 15156 30123 15157 30123 12669 30123 12669 30124 15157 30124 12712 30124 12669 30125 12712 30125 12671 30125 12671 30126 12712 30126 12714 30126 12671 30127 12714 30127 12672 30127 12672 30128 12714 30128 15158 30128 12672 30129 15158 30129 12673 30129 12673 30130 15158 30130 15159 30130 12673 30131 15159 30131 12674 30131 12674 30132 15159 30132 15146 30132 12709 30133 12620 30133 15173 30133 15173 30134 12620 30134 15160 30134 15173 30135 15160 30135 15174 30135 15174 30136 15160 30136 15161 30136 15174 30137 15161 30137 15162 30137 15162 30138 15161 30138 15163 30138 15162 30139 15163 30139 15176 30139 15176 30140 15163 30140 15164 30140 15176 30141 15164 30141 15177 30141 15177 30142 15164 30142 15165 30142 15177 30143 15165 30143 15166 30143 15166 30144 15165 30144 12701 30144 12648 30145 15167 30145 15168 30145 15168 30146 15167 30146 15169 30146 15168 30147 15169 30147 12651 30147 12651 30148 15169 30148 12702 30148 12651 30149 12702 30149 12652 30149 12652 30150 12702 30150 12705 30150 12652 30151 12705 30151 15170 30151 15170 30152 12705 30152 12707 30152 15170 30153 12707 30153 15171 30153 15171 30154 12707 30154 12709 30154 15171 30155 12709 30155 15238 30155 15238 30156 12709 30156 15173 30156 15238 30157 15173 30157 15172 30157 15172 30158 15173 30158 15174 30158 15172 30159 15174 30159 15240 30159 15240 30160 15174 30160 15162 30160 15240 30161 15162 30161 15175 30161 15175 30162 15162 30162 15176 30162 15175 30163 15176 30163 15178 30163 15178 30164 15176 30164 15177 30164 15178 30165 15177 30165 15179 30165 15179 30166 15177 30166 15166 30166 15179 30167 15166 30167 12647 30167 12647 30168 15166 30168 15180 30168 12647 30169 15180 30169 12648 30169 12648 30170 15180 30170 15167 30170 12612 30171 15277 30171 15181 30171 15181 30172 15277 30172 15182 30172 15277 30173 15183 30173 15182 30173 15182 30174 15183 30174 15278 30174 15182 30175 15278 30175 15191 30175 15278 30176 15275 30176 15191 30176 15191 30177 15275 30177 15184 30177 15191 30178 15184 30178 15185 30178 15184 30179 15273 30179 15185 30179 15185 30180 15273 30180 15186 30180 15185 30181 15186 30181 15194 30181 15186 30182 15271 30182 15194 30182 15194 30183 15271 30183 15187 30183 15194 30184 15187 30184 15188 30184 12696 30185 15189 30185 15270 30185 15270 30186 15189 30186 15188 30186 15270 30187 15188 30187 15190 30187 15190 30188 15188 30188 15187 30188 15254 30189 15182 30189 15256 30189 15256 30190 15182 30190 15191 30190 15256 30191 15191 30191 15192 30191 15192 30192 15191 30192 15185 30192 15192 30193 15185 30193 15193 30193 15193 30194 15185 30194 15194 30194 15193 30195 15194 30195 15259 30195 15259 30196 15194 30196 15188 30196 15259 30197 15188 30197 15260 30197 15260 30198 15188 30198 15189 30198 15260 30199 15189 30199 12629 30199 12629 30200 15189 30200 12695 30200 12629 30201 12695 30201 12631 30201 12631 30202 12695 30202 15195 30202 12631 30203 15195 30203 12633 30203 12633 30204 15195 30204 12697 30204 12633 30205 12697 30205 15196 30205 15196 30206 12697 30206 12699 30206 15196 30207 12699 30207 15197 30207 15197 30208 12699 30208 15198 30208 15197 30209 15198 30209 15199 30209 15199 30210 15198 30210 15181 30210 15199 30211 15181 30211 15254 30211 15254 30212 15181 30212 15182 30212 13923 30213 12691 30213 12683 30213 12683 30214 15213 30214 13923 30214 13923 30215 15213 30215 15200 30215 13923 30216 15200 30216 13931 30216 15200 30217 15201 30217 13931 30217 13931 30218 15201 30218 15202 30218 13931 30219 15202 30219 15203 30219 15202 30220 15214 30220 15203 30220 15203 30221 15214 30221 15215 30221 15203 30222 15215 30222 15204 30222 15204 30223 15215 30223 15205 30223 15204 30224 15205 30224 15206 30224 15205 30225 15207 30225 15206 30225 15206 30226 15207 30226 15212 30226 15206 30227 15212 30227 15210 30227 12675 30228 15208 30228 15209 30228 15209 30229 15208 30229 15210 30229 15209 30230 15210 30230 15211 30230 15211 30231 15210 30231 15212 30231 12683 30232 12682 30232 15213 30232 15213 30233 12682 30233 15218 30233 15213 30234 15218 30234 15200 30234 15200 30235 15218 30235 15201 30235 15201 30236 15218 30236 15219 30236 15201 30237 15219 30237 15202 30237 15202 30238 15219 30238 15214 30238 15214 30239 15219 30239 15221 30239 15214 30240 15221 30240 15215 30240 15215 30241 15221 30241 15205 30241 15205 30242 15221 30242 15216 30242 15205 30243 15216 30243 15207 30243 15207 30244 15216 30244 15212 30244 15212 30245 15216 30245 15217 30245 15212 30246 15217 30246 15211 30246 15211 30247 15217 30247 15209 30247 15209 30248 15217 30248 15222 30248 15209 30249 15222 30249 12675 30249 12682 30250 15147 30250 15218 30250 15218 30251 15147 30251 15149 30251 15218 30252 15149 30252 15219 30252 15219 30253 15149 30253 15220 30253 15219 30254 15220 30254 15221 30254 15221 30255 15220 30255 15151 30255 15221 30256 15151 30256 15216 30256 15216 30257 15151 30257 15152 30257 15216 30258 15152 30258 15217 30258 15217 30259 15152 30259 15223 30259 15217 30260 15223 30260 15222 30260 15222 30261 15223 30261 12666 30261 15236 30262 13935 30262 15235 30262 15235 30263 13935 30263 15224 30263 15235 30264 15224 30264 15225 30264 15225 30265 15224 30265 13937 30265 15225 30266 13937 30266 15232 30266 15232 30267 13937 30267 15226 30267 15232 30268 15226 30268 15231 30268 15231 30269 15226 30269 15227 30269 15231 30270 15227 30270 15228 30270 15228 30271 15227 30271 15230 30271 15228 30272 15230 30272 15229 30272 15229 30273 15230 30273 13940 30273 15229 30274 12653 30274 15228 30274 15228 30275 12653 30275 15237 30275 15228 30276 15237 30276 15231 30276 15231 30277 15237 30277 15239 30277 15231 30278 15239 30278 15232 30278 15232 30279 15239 30279 15233 30279 15232 30280 15233 30280 15225 30280 15225 30281 15233 30281 15234 30281 15225 30282 15234 30282 15235 30282 15235 30283 15234 30283 15241 30283 15235 30284 15241 30284 15236 30284 15236 30285 15241 30285 12645 30285 12653 30286 15171 30286 15237 30286 15237 30287 15171 30287 15238 30287 15237 30288 15238 30288 15239 30288 15239 30289 15238 30289 15172 30289 15239 30290 15172 30290 15233 30290 15233 30291 15172 30291 15240 30291 15233 30292 15240 30292 15234 30292 15234 30293 15240 30293 15175 30293 15234 30294 15175 30294 15241 30294 15241 30295 15175 30295 15178 30295 15241 30296 15178 30296 12645 30296 12645 30297 15178 30297 15179 30297 12644 30298 15243 30298 15242 30298 15242 30299 15243 30299 15244 30299 15242 30300 15244 30300 15245 30300 15245 30301 15244 30301 15246 30301 15245 30302 15246 30302 15247 30302 15247 30303 15246 30303 13949 30303 15247 30304 13949 30304 15248 30304 15248 30305 13949 30305 13951 30305 15248 30306 13951 30306 15249 30306 15249 30307 13951 30307 13952 30307 15249 30308 13952 30308 15250 30308 15250 30309 13952 30309 13954 30309 15250 30310 15252 30310 15249 30310 15249 30311 15252 30311 15253 30311 15249 30312 15253 30312 15248 30312 15248 30313 15253 30313 15255 30313 15248 30314 15255 30314 15247 30314 15247 30315 15255 30315 15257 30315 15247 30316 15257 30316 15245 30316 15245 30317 15257 30317 15251 30317 15245 30318 15251 30318 15242 30318 15242 30319 15251 30319 15258 30319 15242 30320 15258 30320 12644 30320 12644 30321 15258 30321 12635 30321 15252 30322 15199 30322 15253 30322 15253 30323 15199 30323 15254 30323 15253 30324 15254 30324 15255 30324 15255 30325 15254 30325 15256 30325 15255 30326 15256 30326 15257 30326 15257 30327 15256 30327 15192 30327 15257 30328 15192 30328 15251 30328 15251 30329 15192 30329 15193 30329 15251 30330 15193 30330 15258 30330 15258 30331 15193 30331 15259 30331 15258 30332 15259 30332 12635 30332 12635 30333 15259 30333 15260 30333 12622 30334 15261 30334 15142 30334 15142 30335 15261 30335 14229 30335 15142 30336 14229 30336 15143 30336 15143 30337 14229 30337 15262 30337 15143 30338 15262 30338 15144 30338 15144 30339 15262 30339 14227 30339 15144 30340 14227 30340 15263 30340 15263 30341 14227 30341 14243 30341 15263 30342 14243 30342 15264 30342 15264 30343 14243 30343 15265 30343 15264 30344 15265 30344 12710 30344 12710 30345 15265 30345 14241 30345 12620 30346 15266 30346 15160 30346 15160 30347 15266 30347 14224 30347 15160 30348 14224 30348 15161 30348 15161 30349 14224 30349 15267 30349 15161 30350 15267 30350 15163 30350 15163 30351 15267 30351 14381 30351 15163 30352 14381 30352 15164 30352 15164 30353 14381 30353 15268 30353 15164 30354 15268 30354 15165 30354 15165 30355 15268 30355 15269 30355 15165 30356 15269 30356 12701 30356 12701 30357 15269 30357 12613 30357 14203 30358 14195 30358 12696 30358 12696 30359 15270 30359 14203 30359 14203 30360 15270 30360 15190 30360 14203 30361 15190 30361 14202 30361 15190 30362 15187 30362 14202 30362 14202 30363 15187 30363 15271 30363 14202 30364 15271 30364 15272 30364 15271 30365 15186 30365 15272 30365 15272 30366 15186 30366 15273 30366 15272 30367 15273 30367 15274 30367 15274 30368 15273 30368 15184 30368 15274 30369 15184 30369 14200 30369 15184 30370 15275 30370 14200 30370 14200 30371 15275 30371 15278 30371 14200 30372 15278 30372 14393 30372 12612 30373 15276 30373 15277 30373 15277 30374 15276 30374 14393 30374 15277 30375 14393 30375 15183 30375 15183 30376 14393 30376 15278 30376 12601 30377 15287 30377 15280 30377 15280 30378 15287 30378 15279 30378 15280 30379 15279 30379 15282 30379 15282 30380 15279 30380 15289 30380 15289 30381 15281 30381 15282 30381 15282 30382 15281 30382 15283 30382 15282 30383 15283 30383 13882 30383 15283 30384 15290 30384 13882 30384 13882 30385 15290 30385 15291 30385 13882 30386 15291 30386 13880 30386 15284 30387 15285 30387 15296 30387 15296 30388 15285 30388 13879 30388 15296 30389 13879 30389 15286 30389 15286 30390 13879 30390 13880 30390 15286 30391 13880 30391 15293 30391 15293 30392 13880 30392 15291 30392 15287 30393 12600 30393 15297 30393 15287 30394 15297 30394 15279 30394 15279 30395 15297 30395 15288 30395 15279 30396 15288 30396 15289 30396 15289 30397 15288 30397 15281 30397 15281 30398 15288 30398 15299 30398 15281 30399 15299 30399 15283 30399 15283 30400 15299 30400 15290 30400 15290 30401 15299 30401 15292 30401 15290 30402 15292 30402 15291 30402 15291 30403 15292 30403 15293 30403 15293 30404 15292 30404 15294 30404 15293 30405 15294 30405 15286 30405 15286 30406 15294 30406 15295 30406 15286 30407 15295 30407 15296 30407 15296 30408 15295 30408 12588 30408 15296 30409 12588 30409 15284 30409 12600 30410 14232 30410 15297 30410 15297 30411 14232 30411 15298 30411 15297 30412 15298 30412 15288 30412 15288 30413 15298 30413 14231 30413 15288 30414 14231 30414 15299 30414 15299 30415 14231 30415 14230 30415 15299 30416 14230 30416 15292 30416 15292 30417 14230 30417 14238 30417 15292 30418 14238 30418 15294 30418 15294 30419 14238 30419 14239 30419 15294 30420 14239 30420 15295 30420 15295 30421 14239 30421 15300 30421 15295 30422 15300 30422 12588 30422 12588 30423 15300 30423 14235 30423 15301 30424 12587 30424 15313 30424 15313 30425 12587 30425 15302 30425 15313 30426 15302 30426 15303 30426 15303 30427 15302 30427 15304 30427 15303 30428 15304 30428 15310 30428 15310 30429 15304 30429 13895 30429 15310 30430 13895 30430 15309 30430 15309 30431 13895 30431 13896 30431 15309 30432 13896 30432 15305 30432 15305 30433 13896 30433 13898 30433 15305 30434 13898 30434 15306 30434 15306 30435 13898 30435 15307 30435 15306 30436 15307 30436 12581 30436 12581 30437 15307 30437 13888 30437 12581 30438 12573 30438 15306 30438 15306 30439 12573 30439 15315 30439 15306 30440 15315 30440 15305 30440 15305 30441 15315 30441 15308 30441 15305 30442 15308 30442 15309 30442 15309 30443 15308 30443 15319 30443 15309 30444 15319 30444 15310 30444 15310 30445 15319 30445 15311 30445 15310 30446 15311 30446 15303 30446 15303 30447 15311 30447 15312 30447 15303 30448 15312 30448 15313 30448 15313 30449 15312 30449 15314 30449 15313 30450 15314 30450 15301 30450 15301 30451 15314 30451 12574 30451 12573 30452 15316 30452 15315 30452 15315 30453 15316 30453 14209 30453 15315 30454 14209 30454 15308 30454 15308 30455 14209 30455 15317 30455 15308 30456 15317 30456 15319 30456 15319 30457 15317 30457 15318 30457 15319 30458 15318 30458 15311 30458 15311 30459 15318 30459 14216 30459 15311 30460 14216 30460 15312 30460 15312 30461 14216 30461 14215 30461 15312 30462 14215 30462 15314 30462 15314 30463 14215 30463 14214 30463 15314 30464 14214 30464 12574 30464 12574 30465 14214 30465 15320 30465 15332 30466 13901 30466 15321 30466 15321 30467 13901 30467 13902 30467 15321 30468 13902 30468 15322 30468 15322 30469 13902 30469 13904 30469 15322 30470 13904 30470 15330 30470 15330 30471 13904 30471 15323 30471 15330 30472 15323 30472 15328 30472 15328 30473 15323 30473 15324 30473 15328 30474 15324 30474 15325 30474 15325 30475 15324 30475 13906 30475 15325 30476 13906 30476 15326 30476 15326 30477 13906 30477 13907 30477 15326 30478 15333 30478 15325 30478 15325 30479 15333 30479 15327 30479 15325 30480 15327 30480 15328 30480 15328 30481 15327 30481 15335 30481 15328 30482 15335 30482 15330 30482 15330 30483 15335 30483 15329 30483 15330 30484 15329 30484 15322 30484 15322 30485 15329 30485 15337 30485 15322 30486 15337 30486 15321 30486 15321 30487 15337 30487 15331 30487 15321 30488 15331 30488 15332 30488 15332 30489 15331 30489 15340 30489 15333 30490 14221 30490 15327 30490 15327 30491 14221 30491 15334 30491 15327 30492 15334 30492 15335 30492 15335 30493 15334 30493 15336 30493 15335 30494 15336 30494 15329 30494 15329 30495 15336 30495 15338 30495 15329 30496 15338 30496 15337 30496 15337 30497 15338 30497 15339 30497 15337 30498 15339 30498 15331 30498 15331 30499 15339 30499 15341 30499 15331 30500 15341 30500 15340 30500 15340 30501 15341 30501 15342 30501 13919 30502 12545 30502 15343 30502 15343 30503 12545 30503 15344 30503 15343 30504 15344 30504 15345 30504 15345 30505 15344 30505 15355 30505 15355 30506 15356 30506 15345 30506 15345 30507 15356 30507 15346 30507 15345 30508 15346 30508 13918 30508 15346 30509 15347 30509 13918 30509 13918 30510 15347 30510 15348 30510 13918 30511 15348 30511 15352 30511 15349 30512 13915 30512 15350 30512 15350 30513 13915 30513 13916 30513 15350 30514 13916 30514 15351 30514 15351 30515 13916 30515 15352 30515 15351 30516 15352 30516 15353 30516 15353 30517 15352 30517 15348 30517 12545 30518 15361 30518 15354 30518 12545 30519 15354 30519 15344 30519 15344 30520 15354 30520 15357 30520 15344 30521 15357 30521 15355 30521 15355 30522 15357 30522 15356 30522 15356 30523 15357 30523 15358 30523 15356 30524 15358 30524 15346 30524 15346 30525 15358 30525 15347 30525 15347 30526 15358 30526 15359 30526 15347 30527 15359 30527 15348 30527 15348 30528 15359 30528 15353 30528 15353 30529 15359 30529 15365 30529 15353 30530 15365 30530 15351 30530 15351 30531 15365 30531 15360 30531 15351 30532 15360 30532 15350 30532 15350 30533 15360 30533 15367 30533 15350 30534 15367 30534 15349 30534 15361 30535 12537 30535 15354 30535 15354 30536 12537 30536 15362 30536 15354 30537 15362 30537 15357 30537 15357 30538 15362 30538 15363 30538 15357 30539 15363 30539 15358 30539 15358 30540 15363 30540 14201 30540 15358 30541 14201 30541 15359 30541 15359 30542 14201 30542 15364 30542 15359 30543 15364 30543 15365 30543 15365 30544 15364 30544 15366 30544 15365 30545 15366 30545 15360 30545 15360 30546 15366 30546 14199 30546 15360 30547 14199 30547 15367 30547 15367 30548 14199 30548 14198 30548 12532 30549 12531 30549 15368 30549 14474 30550 14242 30550 15368 30550 15368 30551 14242 30551 15369 30551 15368 30552 15369 30552 12532 30552 14368 30553 15370 30553 15371 30553 15371 30554 15370 30554 15372 30554 15371 30555 15372 30555 14474 30555 14474 30556 15372 30556 14233 30556 14474 30557 14233 30557 14242 30557 14368 30558 15371 30558 14360 30558 14360 30559 15371 30559 15375 30559 14360 30560 15375 30560 15373 30560 14218 30561 15374 30561 14472 30561 14472 30562 15374 30562 14219 30562 14472 30563 14219 30563 15375 30563 15375 30564 14219 30564 14212 30564 15375 30565 14212 30565 15373 30565 14218 30566 14472 30566 14217 30566 14217 30567 14472 30567 15377 30567 14217 30568 15377 30568 14028 30568 14470 30569 14029 30569 15376 30569 14470 30570 15376 30570 15377 30570 15377 30571 15376 30571 15378 30571 15377 30572 15378 30572 14028 30572 14052 30573 15379 30573 14465 30573 14465 30574 15379 30574 14251 30574 14465 30575 14251 30575 14466 30575 14466 30576 14251 30576 14252 30576 14466 30577 14252 30577 15380 30577 15380 30578 14252 30578 14205 30578 15380 30579 14205 30579 15381 30579 15381 30580 14205 30580 14206 30580 15381 30581 14206 30581 14470 30581 14470 30582 14206 30582 14197 30582 14470 30583 14197 30583 14029 30583 14052 30584 14465 30584 15382 30584 15382 30585 14465 30585 14463 30585 15382 30586 14463 30586 14348 30586 15385 30587 15383 30587 14463 30587 14463 30588 15383 30588 14347 30588 14463 30589 14347 30589 14348 30589 15384 30590 14038 30590 14461 30590 14461 30591 14038 30591 14040 30591 14461 30592 14040 30592 15385 30592 15385 30593 14040 30593 14328 30593 15385 30594 14328 30594 15383 30594 14191 30595 14192 30595 15386 30595 15386 30596 14192 30596 15387 30596 15386 30597 15387 30597 14461 30597 14461 30598 15387 30598 15388 30598 14461 30599 15388 30599 15384 30599 14318 30600 14325 30600 15390 30600 15390 30601 14325 30601 15389 30601 15390 30602 15389 30602 15386 30602 15386 30603 15389 30603 14320 30603 15386 30604 14320 30604 14191 30604 14318 30605 15390 30605 14172 30605 14172 30606 15390 30606 15391 30606 14172 30607 15391 30607 14173 30607 14173 30608 15391 30608 14179 30608 14179 30609 15391 30609 14457 30609 14179 30610 14457 30610 14175 30610 14175 30611 14457 30611 13310 30611 14175 30612 13310 30612 12500 30612 13594 30613 12499 30613 15392 30613 13594 30614 15392 30614 15393 30614 15393 30615 15392 30615 15394 30615 15393 30616 15394 30616 13595 30616 13595 30617 15394 30617 14490 30617 13595 30618 14490 30618 15395 30618 15395 30619 14490 30619 15396 30619 15395 30620 15396 30620 15397 30620 15397 30621 15396 30621 14489 30621 15397 30622 14489 30622 15398 30622 15398 30623 14489 30623 14487 30623 15398 30624 14487 30624 15399 30624 15399 30625 14487 30625 15400 30625 15399 30626 15400 30626 13598 30626 13598 30627 15400 30627 15401 30627 13598 30628 15401 30628 13599 30628 13599 30629 15401 30629 14485 30629 13599 30630 14485 30630 13600 30630 13600 30631 14485 30631 15402 30631 13600 30632 15402 30632 13602 30632 13602 30633 15402 30633 15403 30633 13602 30634 15403 30634 13603 30634 13603 30635 15403 30635 15404 30635 13603 30636 15404 30636 13571 30636 13571 30637 15404 30637 14482 30637 13571 30638 14482 30638 15405 30638 15405 30639 14482 30639 14480 30639 15405 30640 14480 30640 15406 30640 15406 30641 14480 30641 14479 30641 15406 30642 14479 30642 13572 30642 13572 30643 14479 30643 14478 30643 13572 30644 14478 30644 13573 30644 13962 30645 12482 30645 15407 30645 13962 30646 15407 30646 13963 30646 13963 30647 15407 30647 14330 30647 13963 30648 14330 30648 13964 30648 13964 30649 14330 30649 15408 30649 15408 30650 14330 30650 14335 30650 15408 30651 14335 30651 13965 30651 13965 30652 14335 30652 13961 30652 13961 30653 14335 30653 14334 30653 13961 30654 14334 30654 15409 30654 15409 30655 14334 30655 13959 30655 13959 30656 14334 30656 14332 30656 13959 30657 14332 30657 15410 30657 15410 30658 14332 30658 15411 30658 15410 30659 15411 30659 15412 30659 15412 30660 15411 30660 15413 30660 15412 30661 15413 30661 12474 30661 12472 30662 12473 30662 15414 30662 15414 30663 12473 30663 15415 30663 15414 30664 15415 30664 13966 30664 13966 30665 15415 30665 15417 30665 13966 30666 15417 30666 15416 30666 15416 30667 15417 30667 15418 30667 15416 30668 15418 30668 15419 30668 15419 30669 15418 30669 15420 30669 15419 30670 15420 30670 13970 30670 13970 30671 15420 30671 14324 30671 13970 30672 14324 30672 15421 30672 15421 30673 14324 30673 15422 30673 15421 30674 15422 30674 12466 30674 12466 30675 15422 30675 14432 30675 15423 30676 14361 30676 15424 30676 15423 30677 15424 30677 13976 30677 13976 30678 15424 30678 14371 30678 13976 30679 14371 30679 13977 30679 13977 30680 14371 30680 13978 30680 13978 30681 14371 30681 14370 30681 13978 30682 14370 30682 13974 30682 13974 30683 14370 30683 13975 30683 13975 30684 14370 30684 14369 30684 13975 30685 14369 30685 15425 30685 15425 30686 14369 30686 15426 30686 15426 30687 14369 30687 15428 30687 15426 30688 15428 30688 15427 30688 15427 30689 15428 30689 15429 30689 15427 30690 15429 30690 15430 30690 15430 30691 15429 30691 14366 30691 15430 30692 14366 30692 13972 30692 15431 30693 15432 30693 14354 30693 15431 30694 14354 30694 13986 30694 13986 30695 14354 30695 14359 30695 13986 30696 14359 30696 13987 30696 13987 30697 14359 30697 13989 30697 13989 30698 14359 30698 14358 30698 13989 30699 14358 30699 15433 30699 15433 30700 14358 30700 15434 30700 15434 30701 14358 30701 14356 30701 15434 30702 14356 30702 13983 30702 13983 30703 14356 30703 15436 30703 15436 30704 14356 30704 15435 30704 15436 30705 15435 30705 13982 30705 13982 30706 15435 30706 15437 30706 13982 30707 15437 30707 13981 30707 13981 30708 15437 30708 14355 30708 13981 30709 14355 30709 13355 30709 15438 30710 15439 30710 15441 30710 15441 30711 15439 30711 15440 30711 15441 30712 15440 30712 15442 30712 15442 30713 15440 30713 14249 30713 15442 30714 14249 30714 15443 30714 15443 30715 14249 30715 15444 30715 15443 30716 15444 30716 13993 30716 13993 30717 15444 30717 15446 30717 13993 30718 15446 30718 15445 30718 15445 30719 15446 30719 14248 30719 15445 30720 14248 30720 13346 30720 13346 30721 14248 30721 14244 30721 15447 30722 14401 30722 15448 30722 15448 30723 14401 30723 15449 30723 15448 30724 15449 30724 13998 30724 13998 30725 15449 30725 14276 30725 13998 30726 14276 30726 15450 30726 15450 30727 14276 30727 15451 30727 15450 30728 15451 30728 14000 30728 14000 30729 15451 30729 15452 30729 14000 30730 15452 30730 14002 30730 14002 30731 15452 30731 14275 30731 14002 30732 14275 30732 14003 30732 14003 30733 14275 30733 14279 30733 12443 30734 14271 30734 15453 30734 15453 30735 14271 30735 15454 30735 15453 30736 15454 30736 15455 30736 15455 30737 15454 30737 14269 30737 15455 30738 14269 30738 15456 30738 15456 30739 14269 30739 14273 30739 15456 30740 14273 30740 14008 30740 14008 30741 14273 30741 14272 30741 14008 30742 14272 30742 14009 30742 14009 30743 14272 30743 15458 30743 14009 30744 15458 30744 15457 30744 15457 30745 15458 30745 14268 30745 15459 30746 12436 30746 14010 30746 14010 30747 12436 30747 14305 30747 14010 30748 14305 30748 14013 30748 14013 30749 14305 30749 14304 30749 14013 30750 14304 30750 15460 30750 15460 30751 14304 30751 14303 30751 15460 30752 14303 30752 15461 30752 15461 30753 14303 30753 14301 30753 15461 30754 14301 30754 15462 30754 15462 30755 14301 30755 14297 30755 15462 30756 14297 30756 13328 30756 13328 30757 14297 30757 15463 30757 15464 30758 15466 30758 15465 30758 15465 30759 15466 30759 15467 30759 15465 30760 15467 30760 14016 30760 14016 30761 15467 30761 14296 30761 14016 30762 14296 30762 14017 30762 14017 30763 14296 30763 15469 30763 14017 30764 15469 30764 15468 30764 15468 30765 15469 30765 14295 30765 15468 30766 14295 30766 14019 30766 14019 30767 14295 30767 15470 30767 14019 30768 15470 30768 14020 30768 14020 30769 15470 30769 14293 30769 12425 30770 14285 30770 14022 30770 14022 30771 14285 30771 14282 30771 14022 30772 14282 30772 15471 30772 15471 30773 14282 30773 15472 30773 15471 30774 15472 30774 15473 30774 15473 30775 15472 30775 14286 30775 15473 30776 14286 30776 15475 30776 15475 30777 14286 30777 15474 30777 15475 30778 15474 30778 15477 30778 15477 30779 15474 30779 15476 30779 15477 30780 15476 30780 15478 30780 15478 30781 15476 30781 12416 30781 10724 30782 13311 30782 15479 30782 10724 30783 15479 30783 15480 30783 15480 30784 15479 30784 14458 30784 15480 30785 14458 30785 15481 30785 15481 30786 14458 30786 14459 30786 15481 30787 14459 30787 18523 30787 18523 30788 14459 30788 14460 30788 18523 30789 14460 30789 18520 30789 18520 30790 14460 30790 14462 30790 18520 30791 14462 30791 18518 30791 18518 30792 14462 30792 15482 30792 18518 30793 15482 30793 18517 30793 18517 30794 15482 30794 14464 30794 18517 30795 14464 30795 15483 30795 15483 30796 14464 30796 15484 30796 15483 30797 15484 30797 18515 30797 18515 30798 15484 30798 14467 30798 18515 30799 14467 30799 15485 30799 15485 30800 14467 30800 14468 30800 15485 30801 14468 30801 18513 30801 18513 30802 14468 30802 14469 30802 18513 30803 14469 30803 18511 30803 18511 30804 14469 30804 14471 30804 18511 30805 14471 30805 15487 30805 15487 30806 14471 30806 15486 30806 15487 30807 15486 30807 18509 30807 18509 30808 15486 30808 15488 30808 18509 30809 15488 30809 18507 30809 18507 30810 15488 30810 15489 30810 18507 30811 15489 30811 18506 30811 18506 30812 15489 30812 14473 30812 18506 30813 14473 30813 18503 30813 18503 30814 14473 30814 14475 30814 18503 30815 14475 30815 15490 30815 15490 30816 14475 30816 15491 30816 15490 30817 15491 30817 18502 30817 18502 30818 15491 30818 14476 30818 18502 30819 14476 30819 15492 30819 14024 30820 15493 30820 14025 30820 13319 30821 15494 30821 14024 30821 14024 30822 15494 30822 13314 30822 13317 30823 13319 30823 15495 30823 15495 30824 13319 30824 14024 30824 15495 30825 14024 30825 14026 30825 14026 30826 14024 30826 14025 30826 15496 30827 14023 30827 14021 30827 14021 30828 14023 30828 14024 30828 14021 30829 14024 30829 13313 30829 13313 30830 14024 30830 13314 30830 14015 30831 15497 30831 15504 30831 15504 30832 15497 30832 15499 30832 15498 30833 13325 30833 15504 30833 15504 30834 13325 30834 15502 30834 15499 30835 15500 30835 15504 30835 15504 30836 15500 30836 15501 30836 15504 30837 15501 30837 14018 30837 15502 30838 15503 30838 15504 30838 15504 30839 15503 30839 15505 30839 15504 30840 15505 30840 14015 30840 15508 30841 13331 30841 13332 30841 14014 30842 15506 30842 13329 30842 14012 30843 15507 30843 14011 30843 14011 30844 15507 30844 15508 30844 14011 30845 15508 30845 13334 30845 13334 30846 15508 30846 13332 30846 15508 30847 15509 30847 13331 30847 13331 30848 15509 30848 14014 30848 13331 30849 14014 30849 15510 30849 15510 30850 14014 30850 13329 30850 15515 30851 15511 30851 15516 30851 14005 30852 15512 30852 14006 30852 15516 30853 14004 30853 15513 30853 15513 30854 14004 30854 14005 30854 15513 30855 14005 30855 14007 30855 14007 30856 14005 30856 14006 30856 15514 30857 15515 30857 13336 30857 13336 30858 15515 30858 15516 30858 13336 30859 15516 30859 13335 30859 13335 30860 15516 30860 15513 30860 14001 30861 15517 30861 13339 30861 15518 30862 13995 30862 15519 30862 13343 30863 13344 30863 15518 30863 13339 30864 13341 30864 13343 30864 15519 30865 13996 30865 13997 30865 13343 30866 15518 30866 13339 30866 13339 30867 15518 30867 15519 30867 13339 30868 15519 30868 14001 30868 14001 30869 15519 30869 13997 30869 14001 30870 13997 30870 13999 30870 15521 30871 13351 30871 13352 30871 13991 30872 13992 30872 13994 30872 15520 30873 13991 30873 13990 30873 13990 30874 13991 30874 15521 30874 13990 30875 15521 30875 13353 30875 13353 30876 15521 30876 13352 30876 13348 30877 15521 30877 15522 30877 15522 30878 15521 30878 13991 30878 15522 30879 13991 30879 13345 30879 13345 30880 13991 30880 13994 30880 15526 30881 13980 30881 13354 30881 15524 30882 13358 30882 13985 30882 15525 30883 15523 30883 15524 30883 13354 30884 13356 30884 15525 30884 13985 30885 13988 30885 13984 30885 15525 30886 15524 30886 13354 30886 13354 30887 15524 30887 13985 30887 13354 30888 13985 30888 15526 30888 15526 30889 13985 30889 13984 30889 15526 30890 13984 30890 15527 30890 15528 30891 13979 30891 15531 30891 15529 30892 13360 30892 13973 30892 13973 30893 13360 30893 13361 30893 13365 30894 13971 30894 13973 30894 13973 30895 13971 30895 15528 30895 13973 30896 15528 30896 15530 30896 15530 30897 15528 30897 15531 30897 13361 30898 13362 30898 13973 30898 13973 30899 13362 30899 13364 30899 13973 30900 13364 30900 13365 30900 15537 30901 13367 30901 15532 30901 15532 30902 13967 30902 15538 30902 15533 30903 15534 30903 13366 30903 15535 30904 13967 30904 15536 30904 15536 30905 13967 30905 15532 30905 15536 30906 15532 30906 13368 30906 13366 30907 15537 30907 15533 30907 15533 30908 15537 30908 15532 30908 15533 30909 15532 30909 13969 30909 13969 30910 15532 30910 15538 30910 13969 30911 15538 30911 13968 30911 15542 30912 15539 30912 15540 30912 15542 30913 15541 30913 15546 30913 13957 30914 15541 30914 13960 30914 13960 30915 15541 30915 15542 30915 13960 30916 15542 30916 13958 30916 13958 30917 15542 30917 15540 30917 15543 30918 13372 30918 15544 30918 15544 30919 13372 30919 15542 30919 15544 30920 15542 30920 15545 30920 15545 30921 15542 30921 15546 30921 10813 30922 10814 30922 18415 30922 10813 30923 18415 30923 18417 30923 18417 30924 18415 30924 18414 30924 18417 30925 18414 30925 18419 30925 18419 30926 18414 30926 15547 30926 18419 30927 15547 30927 18420 30927 18420 30928 15547 30928 18411 30928 18420 30929 18411 30929 15548 30929 15548 30930 18411 30930 18409 30930 15548 30931 18409 30931 15549 30931 15549 30932 18409 30932 18408 30932 15549 30933 18408 30933 18422 30933 18422 30934 18408 30934 15550 30934 18422 30935 15550 30935 18425 30935 18425 30936 15550 30936 15551 30936 18425 30937 15551 30937 18426 30937 18426 30938 15551 30938 18402 30938 18426 30939 18402 30939 15552 30939 15552 30940 18402 30940 15553 30940 15552 30941 15553 30941 15554 30941 15554 30942 15553 30942 15555 30942 15554 30943 15555 30943 18428 30943 18428 30944 15555 30944 18401 30944 18428 30945 18401 30945 18430 30945 18430 30946 18401 30946 18399 30946 18430 30947 18399 30947 18433 30947 18433 30948 18399 30948 15556 30948 18433 30949 15556 30949 18434 30949 18434 30950 15556 30950 15557 30950 18434 30951 15557 30951 18435 30951 18435 30952 15557 30952 15558 30952 18435 30953 15558 30953 18437 30953 18437 30954 15558 30954 15559 30954 18437 30955 15559 30955 15560 30955 15560 30956 15559 30956 15561 30956 15560 30957 15561 30957 15562 30957 15562 30958 15561 30958 10836 30958 15562 30959 10836 30959 12379 30959 12378 30960 10778 30960 18452 30960 12378 30961 18452 30961 18480 30961 18480 30962 18452 30962 18451 30962 18480 30963 18451 30963 15563 30963 15563 30964 18451 30964 15564 30964 15563 30965 15564 30965 18482 30965 18482 30966 15564 30966 18448 30966 18482 30967 18448 30967 15565 30967 15565 30968 18448 30968 15566 30968 15565 30969 15566 30969 15567 30969 15567 30970 15566 30970 15568 30970 15567 30971 15568 30971 15569 30971 15569 30972 15568 30972 18446 30972 15569 30973 18446 30973 15570 30973 15570 30974 18446 30974 15571 30974 15570 30975 15571 30975 15572 30975 15572 30976 15571 30976 15573 30976 15572 30977 15573 30977 15574 30977 15574 30978 15573 30978 15575 30978 15574 30979 15575 30979 18488 30979 18488 30980 15575 30980 15576 30980 18488 30981 15576 30981 18491 30981 18491 30982 15576 30982 15577 30982 18491 30983 15577 30983 15578 30983 15578 30984 15577 30984 15579 30984 15578 30985 15579 30985 18493 30985 18493 30986 15579 30986 18441 30986 18493 30987 18441 30987 15580 30987 15580 30988 18441 30988 15581 30988 15580 30989 15581 30989 18496 30989 18496 30990 15581 30990 15582 30990 18496 30991 15582 30991 15583 30991 15583 30992 15582 30992 15584 30992 15583 30993 15584 30993 15585 30993 15585 30994 15584 30994 15586 30994 15585 30995 15586 30995 18500 30995 18500 30996 15586 30996 12362 30996 18500 30997 12362 30997 12363 30997 15587 30998 18371 30998 15588 30998 15587 30999 15588 30999 15589 30999 15589 31000 15588 31000 15590 31000 15589 31001 15590 31001 18373 31001 18373 31002 15590 31002 15591 31002 18373 31003 15591 31003 15592 31003 15592 31004 15591 31004 18368 31004 15592 31005 18368 31005 15593 31005 15593 31006 18368 31006 18365 31006 15593 31007 18365 31007 18375 31007 18375 31008 18365 31008 18364 31008 18375 31009 18364 31009 15594 31009 15594 31010 18364 31010 15595 31010 15594 31011 15595 31011 18378 31011 18378 31012 15595 31012 18361 31012 18378 31013 18361 31013 15596 31013 15596 31014 18361 31014 18358 31014 15596 31015 18358 31015 18380 31015 18380 31016 18358 31016 18357 31016 18380 31017 18357 31017 18382 31017 18382 31018 18357 31018 15597 31018 18382 31019 15597 31019 18384 31019 18384 31020 15597 31020 18356 31020 18384 31021 18356 31021 18386 31021 18386 31022 18356 31022 15598 31022 18386 31023 15598 31023 15599 31023 15599 31024 15598 31024 15600 31024 15599 31025 15600 31025 18387 31025 18387 31026 15600 31026 18354 31026 18387 31027 18354 31027 18389 31027 18389 31028 18354 31028 15601 31028 18389 31029 15601 31029 15602 31029 15602 31030 15601 31030 15604 31030 15602 31031 15604 31031 15603 31031 15603 31032 15604 31032 18352 31032 15603 31033 18352 31033 18392 31033 18392 31034 18352 31034 10876 31034 18392 31035 10876 31035 18394 31035 15605 31036 10890 31036 18332 31036 15605 31037 18332 31037 15606 31037 15606 31038 18332 31038 18331 31038 15606 31039 18331 31039 15607 31039 15607 31040 18331 31040 15609 31040 15607 31041 15609 31041 15608 31041 15608 31042 15609 31042 15610 31042 15608 31043 15610 31043 18335 31043 18335 31044 15610 31044 15611 31044 18335 31045 15611 31045 18337 31045 18337 31046 15611 31046 18328 31046 18337 31047 18328 31047 18338 31047 18338 31048 18328 31048 18326 31048 18338 31049 18326 31049 18339 31049 18339 31050 18326 31050 18325 31050 18339 31051 18325 31051 15612 31051 15612 31052 18325 31052 15613 31052 15612 31053 15613 31053 18340 31053 18340 31054 15613 31054 15614 31054 18340 31055 15614 31055 15615 31055 15615 31056 15614 31056 15616 31056 15615 31057 15616 31057 15617 31057 15617 31058 15616 31058 15618 31058 15617 31059 15618 31059 15619 31059 15619 31060 15618 31060 18322 31060 15619 31061 18322 31061 18343 31061 18343 31062 18322 31062 15620 31062 18343 31063 15620 31063 18345 31063 18345 31064 15620 31064 15621 31064 18345 31065 15621 31065 18346 31065 18346 31066 15621 31066 15622 31066 18346 31067 15622 31067 15623 31067 15623 31068 15622 31068 18321 31068 15623 31069 18321 31069 18347 31069 18347 31070 18321 31070 15624 31070 18347 31071 15624 31071 18350 31071 18350 31072 15624 31072 15625 31072 18350 31073 15625 31073 18351 31073 18295 31074 10923 31074 15626 31074 18295 31075 15626 31075 18297 31075 18297 31076 15626 31076 18293 31076 18297 31077 18293 31077 15627 31077 15627 31078 18293 31078 18292 31078 15627 31079 18292 31079 18299 31079 18299 31080 18292 31080 15628 31080 18299 31081 15628 31081 15629 31081 15629 31082 15628 31082 18290 31082 15629 31083 18290 31083 18302 31083 18302 31084 18290 31084 18289 31084 18302 31085 18289 31085 18303 31085 18303 31086 18289 31086 18287 31086 18303 31087 18287 31087 18305 31087 18305 31088 18287 31088 18286 31088 18305 31089 18286 31089 18307 31089 18307 31090 18286 31090 15631 31090 18307 31091 15631 31091 15630 31091 15630 31092 15631 31092 18284 31092 15630 31093 18284 31093 15632 31093 15632 31094 18284 31094 18282 31094 15632 31095 18282 31095 18311 31095 18311 31096 18282 31096 15633 31096 18311 31097 15633 31097 15634 31097 15634 31098 15633 31098 18279 31098 15634 31099 18279 31099 18314 31099 18314 31100 18279 31100 15635 31100 18314 31101 15635 31101 15636 31101 15636 31102 15635 31102 15637 31102 15636 31103 15637 31103 18316 31103 18316 31104 15637 31104 15638 31104 18316 31105 15638 31105 15639 31105 15639 31106 15638 31106 15641 31106 15639 31107 15641 31107 15640 31107 15640 31108 15641 31108 18275 31108 15640 31109 18275 31109 15642 31109 15642 31110 18275 31110 12296 31110 15642 31111 12296 31111 18319 31111 15643 31112 12295 31112 15644 31112 15643 31113 15644 31113 18259 31113 18259 31114 15644 31114 18257 31114 18259 31115 18257 31115 18260 31115 18260 31116 18257 31116 18256 31116 18260 31117 18256 31117 18261 31117 18261 31118 18256 31118 18254 31118 18261 31119 18254 31119 18263 31119 18263 31120 18254 31120 18253 31120 18263 31121 18253 31121 15645 31121 15645 31122 18253 31122 18251 31122 15645 31123 18251 31123 18266 31123 18266 31124 18251 31124 18250 31124 18266 31125 18250 31125 15646 31125 15646 31126 18250 31126 18248 31126 15646 31127 18248 31127 18268 31127 18268 31128 18248 31128 15647 31128 18268 31129 15647 31129 15649 31129 15649 31130 15647 31130 15648 31130 15649 31131 15648 31131 15650 31131 15650 31132 15648 31132 18247 31132 15650 31133 18247 31133 15651 31133 15651 31134 18247 31134 15652 31134 15651 31135 15652 31135 18269 31135 18269 31136 15652 31136 18246 31136 18269 31137 18246 31137 15653 31137 15653 31138 18246 31138 18244 31138 15653 31139 18244 31139 18270 31139 18270 31140 18244 31140 18243 31140 18270 31141 18243 31141 15654 31141 15654 31142 18243 31142 15656 31142 15654 31143 15656 31143 15655 31143 15655 31144 15656 31144 18240 31144 15655 31145 18240 31145 15657 31145 15657 31146 18240 31146 18239 31146 15657 31147 18239 31147 18274 31147 18274 31148 18239 31148 10976 31148 18274 31149 10976 31149 12271 31149 10989 31150 10991 31150 15658 31150 10989 31151 15658 31151 18220 31151 18220 31152 15658 31152 18217 31152 18220 31153 18217 31153 18222 31153 18222 31154 18217 31154 15660 31154 18222 31155 15660 31155 15659 31155 15659 31156 15660 31156 18215 31156 15659 31157 18215 31157 18223 31157 18223 31158 18215 31158 15661 31158 18223 31159 15661 31159 18224 31159 18224 31160 15661 31160 18213 31160 18224 31161 18213 31161 18225 31161 18225 31162 18213 31162 15662 31162 18225 31163 15662 31163 18227 31163 18227 31164 15662 31164 18212 31164 18227 31165 18212 31165 18229 31165 18229 31166 18212 31166 18210 31166 18229 31167 18210 31167 18230 31167 18230 31168 18210 31168 15663 31168 18230 31169 15663 31169 15664 31169 15664 31170 15663 31170 18208 31170 15664 31171 18208 31171 18231 31171 18231 31172 18208 31172 18207 31172 18231 31173 18207 31173 18233 31173 18233 31174 18207 31174 18205 31174 18233 31175 18205 31175 15665 31175 15665 31176 18205 31176 15666 31176 15665 31177 15666 31177 18234 31177 18234 31178 15666 31178 18203 31178 18234 31179 18203 31179 15667 31179 15667 31180 18203 31180 18201 31180 15667 31181 18201 31181 15668 31181 15668 31182 18201 31182 18200 31182 15668 31183 18200 31183 18236 31183 18236 31184 18200 31184 18198 31184 18236 31185 18198 31185 15669 31185 15669 31186 18198 31186 11008 31186 15669 31187 11008 31187 12246 31187 15672 31188 15670 31188 15671 31188 15672 31189 15671 31189 18179 31189 18179 31190 15671 31190 18177 31190 18179 31191 18177 31191 18180 31191 18180 31192 18177 31192 18174 31192 18180 31193 18174 31193 18181 31193 18181 31194 18174 31194 15674 31194 18181 31195 15674 31195 15673 31195 15673 31196 15674 31196 18172 31196 15673 31197 18172 31197 15675 31197 15675 31198 18172 31198 18170 31198 15675 31199 18170 31199 15676 31199 15676 31200 18170 31200 18169 31200 15676 31201 18169 31201 18184 31201 18184 31202 18169 31202 15677 31202 18184 31203 15677 31203 15679 31203 15679 31204 15677 31204 15678 31204 15679 31205 15678 31205 15680 31205 15680 31206 15678 31206 15682 31206 15680 31207 15682 31207 15681 31207 15681 31208 15682 31208 18165 31208 15681 31209 18165 31209 18186 31209 18186 31210 18165 31210 15683 31210 18186 31211 15683 31211 18187 31211 18187 31212 15683 31212 15684 31212 18187 31213 15684 31213 18188 31213 18188 31214 15684 31214 15685 31214 18188 31215 15685 31215 18190 31215 18190 31216 15685 31216 18163 31216 18190 31217 18163 31217 18193 31217 18193 31218 18163 31218 15686 31218 18193 31219 15686 31219 15687 31219 15687 31220 15686 31220 18162 31220 15687 31221 18162 31221 18194 31221 18194 31222 18162 31222 18160 31222 18194 31223 18160 31223 18195 31223 18195 31224 18160 31224 11047 31224 18195 31225 11047 31225 18196 31225 11066 31226 12227 31226 15688 31226 11066 31227 15688 31227 18136 31227 18136 31228 15688 31228 15689 31228 18136 31229 15689 31229 18138 31229 18138 31230 15689 31230 17382 31230 18138 31231 17382 31231 15690 31231 15690 31232 17382 31232 17381 31232 15690 31233 17381 31233 15691 31233 15691 31234 17381 31234 15692 31234 15691 31235 15692 31235 15693 31235 15693 31236 15692 31236 17380 31236 15693 31237 17380 31237 18143 31237 18143 31238 17380 31238 15694 31238 18143 31239 15694 31239 18144 31239 18144 31240 15694 31240 17376 31240 18144 31241 17376 31241 15695 31241 15695 31242 17376 31242 15696 31242 15695 31243 15696 31243 18145 31243 18145 31244 15696 31244 17374 31244 18145 31245 17374 31245 18148 31245 18148 31246 17374 31246 17371 31246 18148 31247 17371 31247 15697 31247 15697 31248 17371 31248 17370 31248 15697 31249 17370 31249 18150 31249 18150 31250 17370 31250 15698 31250 18150 31251 15698 31251 18151 31251 18151 31252 15698 31252 15699 31252 18151 31253 15699 31253 18153 31253 18153 31254 15699 31254 15700 31254 18153 31255 15700 31255 18154 31255 18154 31256 15700 31256 15701 31256 18154 31257 15701 31257 18155 31257 18155 31258 15701 31258 15702 31258 18155 31259 15702 31259 18156 31259 18156 31260 15702 31260 17366 31260 18156 31261 17366 31261 15703 31261 15703 31262 17366 31262 17364 31262 15703 31263 17364 31263 18158 31263 11263 31264 10725 31264 18524 31264 11263 31265 18524 31265 17339 31265 17339 31266 18524 31266 18522 31266 17339 31267 18522 31267 17341 31267 17341 31268 18522 31268 18521 31268 17341 31269 18521 31269 15704 31269 15704 31270 18521 31270 18519 31270 15704 31271 18519 31271 17343 31271 17343 31272 18519 31272 15705 31272 17343 31273 15705 31273 15707 31273 15707 31274 15705 31274 15706 31274 15707 31275 15706 31275 15708 31275 15708 31276 15706 31276 18516 31276 15708 31277 18516 31277 17347 31277 17347 31278 18516 31278 15709 31278 17347 31279 15709 31279 17348 31279 17348 31280 15709 31280 18514 31280 17348 31281 18514 31281 17350 31281 17350 31282 18514 31282 18512 31282 17350 31283 18512 31283 15710 31283 15710 31284 18512 31284 15711 31284 15710 31285 15711 31285 17352 31285 17352 31286 15711 31286 18510 31286 17352 31287 18510 31287 15712 31287 15712 31288 18510 31288 15714 31288 15712 31289 15714 31289 15713 31289 15713 31290 15714 31290 18508 31290 15713 31291 18508 31291 17356 31291 17356 31292 18508 31292 18505 31292 17356 31293 18505 31293 17357 31293 17357 31294 18505 31294 18504 31294 17357 31295 18504 31295 17359 31295 17359 31296 18504 31296 18501 31296 17359 31297 18501 31297 17361 31297 17361 31298 18501 31298 15715 31298 17361 31299 15715 31299 17363 31299 17363 31300 15715 31300 15716 31300 17363 31301 15716 31301 15717 31301 15718 31302 17250 31302 16137 31302 15718 31303 16137 31303 15719 31303 15719 31304 16137 31304 15720 31304 15719 31305 15720 31305 15721 31305 15721 31306 15720 31306 15950 31306 15721 31307 15950 31307 15722 31307 15722 31308 15950 31308 15723 31308 15722 31309 15723 31309 18587 31309 18587 31310 15723 31310 15724 31310 18587 31311 15724 31311 15725 31311 15725 31312 15724 31312 15726 31312 15725 31313 15726 31313 15727 31313 15727 31314 15726 31314 15728 31314 15727 31315 15728 31315 12186 31315 17248 31316 15729 31316 15730 31316 17248 31317 15730 31317 15731 31317 15731 31318 15730 31318 16095 31318 15731 31319 16095 31319 18566 31319 18566 31320 16095 31320 15732 31320 18566 31321 15732 31321 18568 31321 18568 31322 15732 31322 16098 31322 18568 31323 16098 31323 18569 31323 18569 31324 16098 31324 15733 31324 18569 31325 15733 31325 18571 31325 18571 31326 15733 31326 15960 31326 18571 31327 15960 31327 15735 31327 15735 31328 15960 31328 15734 31328 15735 31329 15734 31329 18573 31329 18573 31330 15734 31330 16146 31330 18573 31331 16146 31331 15736 31331 15736 31332 16146 31332 15738 31332 15736 31333 15738 31333 15737 31333 15737 31334 15738 31334 16149 31334 15737 31335 16149 31335 15739 31335 15739 31336 16149 31336 16148 31336 15739 31337 16148 31337 18577 31337 18577 31338 16148 31338 15963 31338 18577 31339 15963 31339 18578 31339 18578 31340 15963 31340 15740 31340 18578 31341 15740 31341 17251 31341 10721 31342 10723 31342 18583 31342 10723 31343 18581 31343 18583 31343 18583 31344 18581 31344 18582 31344 18583 31345 18582 31345 15742 31345 15742 31346 18582 31346 15741 31346 15742 31347 15741 31347 15743 31347 15743 31348 15741 31348 18580 31348 18580 31349 15741 31349 15744 31349 18580 31350 15744 31350 18564 31350 18564 31351 18565 31351 18580 31351 18580 31352 18565 31352 18567 31352 18580 31353 18567 31353 18570 31353 15746 31354 18584 31354 10714 31354 10714 31355 18584 31355 18585 31355 10714 31356 18585 31356 15749 31356 18574 31357 18575 31357 18572 31357 18572 31358 18575 31358 18576 31358 18572 31359 18576 31359 15745 31359 15746 31360 10714 31360 18583 31360 18583 31361 10714 31361 10716 31361 18583 31362 10716 31362 15747 31362 15747 31363 10718 31363 18583 31363 18583 31364 10718 31364 10719 31364 18583 31365 10719 31365 10721 31365 18570 31366 15748 31366 18580 31366 18580 31367 15748 31367 18572 31367 18580 31368 18572 31368 18579 31368 18579 31369 18572 31369 15745 31369 15749 31370 18586 31370 10714 31370 10714 31371 18586 31371 18588 31371 10714 31372 18588 31372 18589 31372 15750 31373 18559 31373 15751 31373 15751 31374 18559 31374 18562 31374 18670 31375 18555 31375 18457 31375 18457 31376 18555 31376 18554 31376 18668 31377 18545 31377 15752 31377 15752 31378 18545 31378 18542 31378 18666 31379 18552 31379 18665 31379 18665 31380 18552 31380 18546 31380 18476 31381 18535 31381 15753 31381 15753 31382 18535 31382 18475 31382 18662 31383 15754 31383 18661 31383 18661 31384 15754 31384 18539 31384 15755 31385 18533 31385 15756 31385 15756 31386 18533 31386 18470 31386 18473 31387 18472 31387 18657 31387 18657 31388 18472 31388 18526 31388 15757 31389 16111 31389 15758 31389 15897 31390 16052 31390 16056 31390 18495 31391 16136 31391 15759 31391 16022 31392 15760 31392 10751 31392 10765 31393 15819 31393 15798 31393 15761 31394 15858 31394 16108 31394 15858 31395 15761 31395 10775 31395 15730 31396 15762 31396 16095 31396 17212 31397 16083 31397 16088 31397 15957 31398 12193 31398 16079 31398 15950 31399 15763 31399 15952 31399 17176 31400 17165 31400 16159 31400 15948 31401 15764 31401 15908 31401 17001 31402 15765 31402 15937 31402 16045 31403 12062 31403 15912 31403 16052 31404 15897 31404 15899 31404 16102 31405 12114 31405 16103 31405 11971 31406 16384 31406 15819 31406 11603 31407 15777 31407 15781 31407 16788 31408 15787 31408 15994 31408 10759 31409 15766 31409 16789 31409 16789 31410 15766 31410 16791 31410 16791 31411 15766 31411 15773 31411 16791 31412 15773 31412 15774 31412 15767 31413 11591 31413 11627 31413 11627 31414 11591 31414 11589 31414 15768 31415 15769 31415 15788 31415 15788 31416 15769 31416 11586 31416 15788 31417 11586 31417 15990 31417 15990 31418 11586 31418 11585 31418 15990 31419 11585 31419 15992 31419 15775 31420 15770 31420 16784 31420 16784 31421 15770 31421 16868 31421 16784 31422 16868 31422 15767 31422 15767 31423 16868 31423 15771 31423 15767 31424 15771 31424 11591 31424 10763 31425 15991 31425 15772 31425 15772 31426 16871 31426 10763 31426 10763 31427 16871 31427 16869 31427 10763 31428 16869 31428 15773 31428 15773 31429 16869 31429 15770 31429 15773 31430 15770 31430 15774 31430 15774 31431 15770 31431 15775 31431 11634 31432 15789 31432 11633 31432 11633 31433 15789 31433 16848 31433 11633 31434 16848 31434 15776 31434 11600 31435 16141 31435 11601 31435 11601 31436 16141 31436 16143 31436 11601 31437 16143 31437 15777 31437 11642 31438 11643 31438 16012 31438 16012 31439 11643 31439 15778 31439 16012 31440 15778 31440 11646 31440 16010 31441 16011 31441 16773 31441 16773 31442 16011 31442 15779 31442 15783 31443 16842 31443 11606 31443 16842 31444 15783 31444 15779 31444 15779 31445 15783 31445 15780 31445 15779 31446 15780 31446 16773 31446 11646 31447 11650 31447 15781 31447 15781 31448 11650 31448 11649 31448 15781 31449 11649 31449 11603 31449 11603 31450 11649 31450 15782 31450 11603 31451 15782 31451 11604 31451 11604 31452 15782 31452 16767 31452 11604 31453 16767 31453 11606 31453 11606 31454 16767 31454 16769 31454 11606 31455 16769 31455 15783 31455 15785 31456 15784 31456 15776 31456 15776 31457 15784 31457 15790 31457 15776 31458 15790 31458 11633 31458 15776 31459 16845 31459 15785 31459 15785 31460 16845 31460 15786 31460 15785 31461 15786 31461 15779 31461 15779 31462 15786 31462 16843 31462 15779 31463 16843 31463 16842 31463 15994 31464 15787 31464 15998 31464 15998 31465 15787 31465 11631 31465 15998 31466 11631 31466 11630 31466 11589 31467 15768 31467 11627 31467 11627 31468 15768 31468 15788 31468 11627 31469 15788 31469 11629 31469 11629 31470 15788 31470 16163 31470 11629 31471 16163 31471 11630 31471 11637 31472 16141 31472 11634 31472 11634 31473 16141 31473 11600 31473 11634 31474 11600 31474 15789 31474 11637 31475 11640 31475 16140 31475 16140 31476 11640 31476 15792 31476 16140 31477 15792 31477 16002 31477 10757 31478 16782 31478 15790 31478 15790 31479 16782 31479 15791 31479 15790 31480 15791 31480 11633 31480 15792 31481 16775 31481 16002 31481 16002 31482 16775 31482 15793 31482 16002 31483 15793 31483 15794 31483 15794 31484 15793 31484 16778 31484 15794 31485 16778 31485 10755 31485 16778 31486 16780 31486 10755 31486 10755 31487 16780 31487 15795 31487 10755 31488 15795 31488 10757 31488 10757 31489 15795 31489 16781 31489 10757 31490 16781 31490 16782 31490 11977 31491 16153 31491 16162 31491 16379 31492 16378 31492 16161 31492 16161 31493 16378 31493 16376 31493 16161 31494 16376 31494 16162 31494 16162 31495 16376 31495 11980 31495 16162 31496 11980 31496 11977 31496 16153 31497 15796 31497 15821 31497 15821 31498 15796 31498 11973 31498 15821 31499 11973 31499 15797 31499 15819 31500 16384 31500 15798 31500 15798 31501 16384 31501 16383 31501 15798 31502 16383 31502 15799 31502 15799 31503 16383 31503 16382 31503 15799 31504 16382 31504 15800 31504 16356 31505 10769 31505 15801 31505 15801 31506 10769 31506 15803 31506 15801 31507 15803 31507 15802 31507 15802 31508 15803 31508 15804 31508 11992 31509 11991 31509 16119 31509 16119 31510 11991 31510 15808 31510 15807 31511 16361 31511 15804 31511 15804 31512 16361 31512 16360 31512 15804 31513 16360 31513 15802 31513 15804 31514 15805 31514 16237 31514 12106 31515 15810 31515 16119 31515 16237 31516 16236 31516 15804 31516 15804 31517 16236 31517 15806 31517 15804 31518 15806 31518 15807 31518 15807 31519 15806 31519 16234 31519 15807 31520 16234 31520 11990 31520 11990 31521 16234 31521 16232 31521 11990 31522 16232 31522 15808 31522 15808 31523 16232 31523 12104 31523 15808 31524 12104 31524 16119 31524 16119 31525 12104 31525 15809 31525 16119 31526 15809 31526 12106 31526 15810 31527 15811 31527 15812 31527 15811 31528 12109 31528 15812 31528 15812 31529 12109 31529 12112 31529 15812 31530 12112 31530 15805 31530 15805 31531 12112 31531 12110 31531 15805 31532 12110 31532 16237 31532 15813 31533 11992 31533 15951 31533 16139 31534 15825 31534 16352 31534 16352 31535 15825 31535 15814 31535 15814 31536 15825 31536 15815 31536 15814 31537 15815 31537 16356 31537 16356 31538 15815 31538 15836 31538 16356 31539 15836 31539 10769 31539 10765 31540 10768 31540 16253 31540 15797 31541 11971 31541 15821 31541 15821 31542 11971 31542 15819 31542 15821 31543 15819 31543 12084 31543 12084 31544 15819 31544 16247 31544 16253 31545 10768 31545 15816 31545 15816 31546 10768 31546 15983 31546 15816 31547 15983 31547 12093 31547 12093 31548 15983 31548 15817 31548 12093 31549 15817 31549 12090 31549 16253 31550 15818 31550 10765 31550 10765 31551 15818 31551 16251 31551 10765 31552 16251 31552 15819 31552 15819 31553 16251 31553 16250 31553 15819 31554 16250 31554 16247 31554 12084 31555 15820 31555 15821 31555 15821 31556 15820 31556 15822 31556 15821 31557 15822 31557 16154 31557 16154 31558 15822 31558 12088 31558 16154 31559 12088 31559 15823 31559 16150 31560 15824 31560 16244 31560 16244 31561 12094 31561 16150 31561 16150 31562 12094 31562 12096 31562 16150 31563 12096 31563 16139 31563 16139 31564 12096 31564 12100 31564 16139 31565 12100 31565 15825 31565 15826 31566 15824 31566 15827 31566 15827 31567 15824 31567 15984 31567 15827 31568 15984 31568 15828 31568 15828 31569 15984 31569 15985 31569 15826 31570 12026 31570 15824 31570 15824 31571 12026 31571 15829 31571 15824 31572 15829 31572 16244 31572 16244 31573 15829 31573 12023 31573 16244 31574 12023 31574 16246 31574 16246 31575 12023 31575 15832 31575 10771 31576 15830 31576 16297 31576 10770 31577 15831 31577 15833 31577 15833 31578 15831 31578 16242 31578 15833 31579 16242 31579 15832 31579 12023 31580 12022 31580 15832 31580 15832 31581 12022 31581 16301 31581 15832 31582 16301 31582 15833 31582 15833 31583 16301 31583 15834 31583 15833 31584 15834 31584 10771 31584 10771 31585 15834 31585 16299 31585 10771 31586 16299 31586 15830 31586 15815 31587 15835 31587 15836 31587 15836 31588 15835 31588 16239 31588 15836 31589 16239 31589 10770 31589 10770 31590 16239 31590 15837 31590 10770 31591 15837 31591 15831 31591 15849 31592 17032 31592 15875 31592 15838 31593 15839 31593 11416 31593 16028 31594 15840 31594 15841 31594 15841 31595 15840 31595 15843 31595 15841 31596 15843 31596 15850 31596 15845 31597 11452 31597 18499 31597 18499 31598 11452 31598 11451 31598 18499 31599 11451 31599 15840 31599 15840 31600 11451 31600 15842 31600 15840 31601 15842 31601 15843 31601 15853 31602 15846 31602 15844 31602 15844 31603 15846 31603 16114 31603 15844 31604 16114 31604 16979 31604 15838 31605 11416 31605 18499 31605 18499 31606 11416 31606 15855 31606 18499 31607 15855 31607 15845 31607 15846 31608 15847 31608 16114 31608 16114 31609 15847 31609 17036 31609 16114 31610 17036 31610 15875 31610 15875 31611 17036 31611 15848 31611 15875 31612 15848 31612 15849 31612 15850 31613 11448 31613 15841 31613 15841 31614 11448 31614 15851 31614 15841 31615 15851 31615 16114 31615 16114 31616 15851 31616 15852 31616 16114 31617 15852 31617 16979 31617 15853 31618 15844 31618 11413 31618 11413 31619 15844 31619 15854 31619 11413 31620 15854 31620 15855 31620 15855 31621 15854 31621 16984 31621 15855 31622 16984 31622 15845 31622 15839 31623 15838 31623 17030 31623 17030 31624 15838 31624 15872 31624 17030 31625 15872 31625 17032 31625 16217 31626 10775 31626 15856 31626 15976 31627 12121 31627 15856 31627 15856 31628 12121 31628 16216 31628 15856 31629 16216 31629 16217 31629 12114 31630 12116 31630 16103 31630 16103 31631 12116 31631 12117 31631 16103 31632 12117 31632 15976 31632 15976 31633 12117 31633 15857 31633 15976 31634 15857 31634 12121 31634 16217 31635 16219 31635 10775 31635 10775 31636 16219 31636 16221 31636 10775 31637 16221 31637 15858 31637 15858 31638 16221 31638 16230 31638 15858 31639 16230 31639 16108 31639 16230 31640 16229 31640 16108 31640 16108 31641 16229 31641 16226 31641 16108 31642 16226 31642 16104 31642 16104 31643 16226 31643 16102 31643 15865 31644 16106 31644 15859 31644 15859 31645 15971 31645 16563 31645 11803 31646 11802 31646 15862 31646 15862 31647 11802 31647 16567 31647 15862 31648 16567 31648 16566 31648 15860 31649 15861 31649 15863 31649 15863 31650 15861 31650 11847 31650 15863 31651 11847 31651 15864 31651 15864 31652 16511 31652 15866 31652 15862 31653 15863 31653 11803 31653 11803 31654 15863 31654 15864 31654 11803 31655 15864 31655 11804 31655 11804 31656 15864 31656 15866 31656 16563 31657 16562 31657 15859 31657 15859 31658 16562 31658 11811 31658 15859 31659 11811 31659 15865 31659 15865 31660 11811 31660 16513 31660 16072 31661 11843 31661 15860 31661 15860 31662 11843 31662 11846 31662 15860 31663 11846 31663 15861 31663 11811 31664 11810 31664 16513 31664 16513 31665 11810 31665 11809 31665 16513 31666 11809 31666 16511 31666 16511 31667 11809 31667 11807 31667 16511 31668 11807 31668 15866 31668 16105 31669 16107 31669 15758 31669 15758 31670 16107 31670 15867 31670 15758 31671 15867 31671 15868 31671 15868 31672 15867 31672 11841 31672 15868 31673 11841 31673 16072 31673 16114 31674 11612 31674 15870 31674 15870 31675 11612 31675 15869 31675 15869 31676 16816 31676 15870 31676 15870 31677 16816 31677 16815 31677 15870 31678 16815 31678 15871 31678 17032 31679 15872 31679 15875 31679 15875 31680 15872 31680 15873 31680 15875 31681 15873 31681 10750 31681 15871 31682 15874 31682 15760 31682 15760 31683 15874 31683 16813 31683 15760 31684 16813 31684 10751 31684 10750 31685 15879 31685 15875 31685 15875 31686 15879 31686 11614 31686 15875 31687 11614 31687 16114 31687 16114 31688 11614 31688 15876 31688 16114 31689 15876 31689 11612 31689 16813 31690 15877 31690 10751 31690 10751 31691 15877 31691 15878 31691 10751 31692 15878 31692 10750 31692 10750 31693 15878 31693 11616 31693 10750 31694 11616 31694 15879 31694 15880 31695 16091 31695 11388 31695 11388 31696 16091 31696 15882 31696 11388 31697 15882 31697 15881 31697 15881 31698 15882 31698 11389 31698 15884 31699 17011 31699 16091 31699 15883 31700 17085 31700 15894 31700 16041 31701 17009 31701 17007 31701 15880 31702 17087 31702 16091 31702 16091 31703 17087 31703 17085 31703 16091 31704 17085 31704 15884 31704 15884 31705 17085 31705 15883 31705 17007 31706 15885 31706 16037 31706 16037 31707 15885 31707 18490 31707 15885 31708 15886 31708 18490 31708 18490 31709 15886 31709 15887 31709 18490 31710 15887 31710 18492 31710 18492 31711 15887 31711 11424 31711 18492 31712 11424 31712 15890 31712 15917 31713 15889 31713 15911 31713 15911 31714 15889 31714 15888 31714 15888 31715 15889 31715 11390 31715 11390 31716 15889 31716 18492 31716 11390 31717 18492 31717 11391 31717 11391 31718 18492 31718 15890 31718 11391 31719 15890 31719 11393 31719 11393 31720 15890 31720 15891 31720 11393 31721 15891 31721 15892 31721 15892 31722 15891 31722 15893 31722 15892 31723 15893 31723 15894 31723 15894 31724 15893 31724 11428 31724 15894 31725 11428 31725 15883 31725 11777 31726 16616 31726 16081 31726 16616 31727 15895 31727 16081 31727 16081 31728 15895 31728 15896 31728 16081 31729 15896 31729 16612 31729 16607 31730 16087 31730 16608 31730 16608 31731 16087 31731 16082 31731 16608 31732 16082 31732 16611 31732 11781 31733 11780 31733 15912 31733 15912 31734 11780 31734 18489 31734 18489 31735 11780 31735 11779 31735 18489 31736 11779 31736 15897 31736 15897 31737 11779 31737 15898 31737 15897 31738 15898 31738 15899 31738 15900 31739 15903 31739 11790 31739 11790 31740 15901 31740 15900 31740 15900 31741 15901 31741 15902 31741 15900 31742 15902 31742 18483 31742 18483 31743 15902 31743 11789 31743 18483 31744 11789 31744 15943 31744 15906 31745 11792 31745 16524 31745 16524 31746 11792 31746 16523 31746 18485 31747 15922 31747 15903 31747 15903 31748 15922 31748 15904 31748 15903 31749 15904 31749 11790 31749 11790 31750 15904 31750 16523 31750 11790 31751 16523 31751 15905 31751 15905 31752 16523 31752 11792 31752 15906 31753 16094 31753 15907 31753 15907 31754 16094 31754 16124 31754 15907 31755 16124 31755 16126 31755 15943 31756 16586 31756 15910 31756 16125 31757 15908 31757 15909 31757 15909 31758 15908 31758 15764 31758 15909 31759 15764 31759 16586 31759 16586 31760 15764 31760 11831 31760 16586 31761 11831 31761 15910 31761 16265 31762 15915 31762 15882 31762 15882 31763 15915 31763 15911 31763 15882 31764 15911 31764 11389 31764 11389 31765 15911 31765 15888 31765 12062 31766 16268 31766 15912 31766 15912 31767 16268 31767 16087 31767 15912 31768 16087 31768 11781 31768 11781 31769 16087 31769 16607 31769 16268 31770 15913 31770 16087 31770 16087 31771 15913 31771 15914 31771 16087 31772 15914 31772 16266 31772 12066 31773 16046 31773 15917 31773 15915 31774 12068 31774 15911 31774 15911 31775 12068 31775 15916 31775 15911 31776 15916 31776 15917 31776 15917 31777 15916 31777 15918 31777 15917 31778 15918 31778 12066 31778 11825 31779 15919 31779 16060 31779 16060 31780 15919 31780 15920 31780 16060 31781 15920 31781 18485 31781 18485 31782 15920 31782 15921 31782 18485 31783 15921 31783 15922 31783 15906 31784 16524 31784 16094 31784 16094 31785 16524 31785 15923 31785 16094 31786 15923 31786 16528 31786 16533 31787 16059 31787 15924 31787 15924 31788 16059 31788 16093 31788 15924 31789 16093 31789 16530 31789 15927 31790 11433 31790 16033 31790 16033 31791 11433 31791 15925 31791 16033 31792 15925 31792 15926 31792 15925 31793 16996 31793 15926 31793 15926 31794 16996 31794 16998 31794 15926 31795 16998 31795 16999 31795 15927 31796 16033 31796 11432 31796 11432 31797 16033 31797 15928 31797 11432 31798 15928 31798 11430 31798 11430 31799 15928 31799 15929 31799 11430 31800 15929 31800 15930 31800 15930 31801 15929 31801 15931 31801 15930 31802 15931 31802 15935 31802 15936 31803 15931 31803 11403 31803 11403 31804 15931 31804 18498 31804 11403 31805 18498 31805 11404 31805 11404 31806 18498 31806 15934 31806 18497 31807 11437 31807 15934 31807 15934 31808 11437 31808 11439 31808 15934 31809 11439 31809 15932 31809 11445 31810 17064 31810 11442 31810 11442 31811 17064 31811 17063 31811 11442 31812 17063 31812 15932 31812 15932 31813 17063 31813 15933 31813 15932 31814 15933 31814 15934 31814 15934 31815 15933 31815 11405 31815 15934 31816 11405 31816 11404 31816 15935 31817 15931 31817 17004 31817 17004 31818 15931 31818 15936 31818 17004 31819 15936 31819 15765 31819 15765 31820 15936 31820 15938 31820 15765 31821 15938 31821 15937 31821 15937 31822 15938 31822 15939 31822 15937 31823 15939 31823 15940 31823 15940 31824 15939 31824 15941 31824 15940 31825 15941 31825 15942 31825 15943 31826 15910 31826 18483 31826 18483 31827 15910 31827 11838 31827 18483 31828 11838 31828 15944 31828 15944 31829 11838 31829 16069 31829 15944 31830 16069 31830 18484 31830 15945 31831 15946 31831 16075 31831 16075 31832 15946 31832 15947 31832 16075 31833 15947 31833 16521 31833 15948 31834 15908 31834 15949 31834 15949 31835 15908 31835 16123 31835 15949 31836 16123 31836 16520 31836 15720 31837 16138 31837 15950 31837 15950 31838 16138 31838 15951 31838 15950 31839 15951 31839 15763 31839 15726 31840 15952 31840 15955 31840 15726 31841 15724 31841 15952 31841 15952 31842 15724 31842 15723 31842 15952 31843 15723 31843 15950 31843 12189 31844 15953 31844 15954 31844 15954 31845 15953 31845 12187 31845 15954 31846 12187 31846 15955 31846 15955 31847 12187 31847 15728 31847 15955 31848 15728 31848 15726 31848 15956 31849 12192 31849 12191 31849 15957 31850 16079 31850 17205 31850 15958 31851 17221 31851 17205 31851 17221 31852 15958 31852 16083 31852 15762 31853 15730 31853 16096 31853 16096 31854 15730 31854 15729 31854 16096 31855 15729 31855 17212 31855 16095 31856 16100 31856 15732 31856 15732 31857 16100 31857 15959 31857 15732 31858 15959 31858 16098 31858 16145 31859 15734 31859 16129 31859 16129 31860 15734 31860 15960 31860 16129 31861 15960 31861 16099 31861 16099 31862 15960 31862 15733 31862 16099 31863 15733 31863 16098 31863 16152 31864 17164 31864 15961 31864 16148 31865 15962 31865 15963 31865 15963 31866 15962 31866 16147 31866 15963 31867 16147 31867 15740 31867 15964 31868 15965 31868 15966 31868 15965 31869 15964 31869 15967 31869 15967 31870 15964 31870 16132 31870 15967 31871 16132 31871 11445 31871 11445 31872 16132 31872 17061 31872 11445 31873 17061 31873 17064 31873 16990 31874 16993 31874 16136 31874 16136 31875 16993 31875 15968 31875 16136 31876 15968 31876 15759 31876 15759 31877 15968 31877 15969 31877 15759 31878 15969 31878 18497 31878 18497 31879 15969 31879 15970 31879 18497 31880 15970 31880 11437 31880 16566 31881 15971 31881 15862 31881 15862 31882 15971 31882 15859 31882 15862 31883 15859 31883 18481 31883 18481 31884 15859 31884 10777 31884 12004 31885 15859 31885 15972 31885 15972 31886 15859 31886 16103 31886 15972 31887 16103 31887 16329 31887 16333 31888 16332 31888 15976 31888 15976 31889 16332 31889 16331 31889 15976 31890 16331 31890 16103 31890 16103 31891 16331 31891 15973 31891 16103 31892 15973 31892 16329 31892 12002 31893 10777 31893 15974 31893 15974 31894 10777 31894 15859 31894 15974 31895 15859 31895 12003 31895 12003 31896 15859 31896 12004 31896 12002 31897 12000 31897 10777 31897 10777 31898 12000 31898 15975 31898 10777 31899 15975 31899 15976 31899 15976 31900 15975 31900 15977 31900 15976 31901 15977 31901 16333 31901 16295 31902 16293 31902 15761 31902 15805 31903 10773 31903 15812 31903 15812 31904 10773 31904 15978 31904 15812 31905 15978 31905 15979 31905 15761 31906 16293 31906 10773 31906 10773 31907 16293 31907 15980 31907 10773 31908 15980 31908 15978 31908 15979 31909 16290 31909 15812 31909 15812 31910 16290 31910 16289 31910 15812 31911 16289 31911 16109 31911 16289 31912 12034 31912 16109 31912 16109 31913 12034 31913 15981 31913 16109 31914 15981 31914 12032 31914 12032 31915 12030 31915 16108 31915 16108 31916 12030 31916 15982 31916 16108 31917 15982 31917 15761 31917 15761 31918 15982 31918 12029 31918 15761 31919 12029 31919 16295 31919 15983 31920 10766 31920 15817 31920 15817 31921 10766 31921 10771 31921 15817 31922 10771 31922 15984 31922 15984 31923 10771 31923 16297 31923 15984 31924 16297 31924 15985 31924 16160 31925 12016 31925 16161 31925 16161 31926 12016 31926 12014 31926 16161 31927 12014 31927 12013 31927 16382 31928 16379 31928 15800 31928 15800 31929 16379 31929 16161 31929 15800 31930 16161 31930 15986 31930 15986 31931 16161 31931 12013 31931 15986 31932 12013 31932 16308 31932 16308 31933 16305 31933 15986 31933 15986 31934 16305 31934 15988 31934 15986 31935 15988 31935 15987 31935 15987 31936 15988 31936 16304 31936 15987 31937 16304 31937 15989 31937 15989 31938 12021 31938 15987 31938 15987 31939 12021 31939 15990 31939 15987 31940 15990 31940 15991 31940 15991 31941 15990 31941 15992 31941 15991 31942 15992 31942 15772 31942 12021 31943 15993 31943 15990 31943 15990 31944 15993 31944 12018 31944 15990 31945 12018 31945 16160 31945 16789 31946 16788 31946 10759 31946 10759 31947 16788 31947 15994 31947 10759 31948 15994 31948 15995 31948 15995 31949 15994 31949 15998 31949 15995 31950 15998 31950 10761 31950 16002 31951 12049 31951 15996 31951 15794 31952 10761 31952 16006 31952 15996 31953 12046 31953 15997 31953 15997 31954 12046 31954 15999 31954 15997 31955 15999 31955 15998 31955 15998 31956 15999 31956 12043 31956 15998 31957 12043 31957 16000 31957 16006 31958 16280 31958 15794 31958 15794 31959 16280 31959 16001 31959 15794 31960 16001 31960 16002 31960 16002 31961 16001 31961 16003 31961 16002 31962 16003 31962 12049 31962 16000 31963 16281 31963 15998 31963 15998 31964 16281 31964 16004 31964 15998 31965 16004 31965 10761 31965 10761 31966 16004 31966 16005 31966 10761 31967 16005 31967 16006 31967 16282 31968 12042 31968 16024 31968 16024 31969 12042 31969 16007 31969 16024 31970 16007 31970 12039 31970 12039 31971 16008 31971 16009 31971 16010 31972 11642 31972 16011 31972 16011 31973 11642 31973 16012 31973 16011 31974 16012 31974 16014 31974 16014 31975 16012 31975 16013 31975 16008 31976 12038 31976 16009 31976 16009 31977 12038 31977 12037 31977 16009 31978 12037 31978 16012 31978 16012 31979 12037 31979 16288 31979 16012 31980 16288 31980 16013 31980 16013 31981 16285 31981 16014 31981 16014 31982 16285 31982 16283 31982 16014 31983 16283 31983 16023 31983 16023 31984 16283 31984 16015 31984 16023 31985 16015 31985 16016 31985 15871 31986 15760 31986 15870 31986 15870 31987 15760 31987 16017 31987 15870 31988 16017 31988 16025 31988 16018 31989 16757 31989 16758 31989 16758 31990 16760 31990 16018 31990 16018 31991 16760 31991 16019 31991 16018 31992 16019 31992 16020 31992 16020 31993 16019 31993 16764 31993 16020 31994 16764 31994 16022 31994 16022 31995 16764 31995 16021 31995 16022 31996 16021 31996 15760 31996 15760 31997 16021 31997 11652 31997 15760 31998 11652 31998 16017 31998 16016 31999 16282 31999 16023 31999 16023 32000 16282 32000 16024 32000 16023 32001 16024 32001 16018 32001 16018 32002 16024 32002 16756 32002 16018 32003 16756 32003 16757 32003 16025 32004 11651 32004 15870 32004 15870 32005 11651 32005 16026 32005 15870 32006 16026 32006 16024 32006 16024 32007 16026 32007 16755 32007 16024 32008 16755 32008 16756 32008 15841 32009 16276 32009 16027 32009 16278 32010 16115 32010 16029 32010 15841 32011 16027 32011 16028 32011 16028 32012 16027 32012 16275 32012 16028 32013 16275 32013 16274 32013 16274 32014 12055 32014 16028 32014 16028 32015 12055 32015 12054 32015 16028 32016 12054 32016 18495 32016 16278 32017 16029 32017 16030 32017 16030 32018 16029 32018 16136 32018 16030 32019 16136 32019 16031 32019 12054 32020 12053 32020 18495 32020 18495 32021 12053 32021 12051 32021 18495 32022 12051 32022 16136 32022 16136 32023 12051 32023 16032 32023 16136 32024 16032 32024 16031 32024 16097 32025 16035 32025 16033 32025 16034 32026 16040 32026 16041 32026 16035 32027 16036 32027 16033 32027 16033 32028 16036 32028 18494 32028 16033 32029 18494 32029 15928 32029 17007 32030 16037 32030 16041 32030 16041 32031 16037 32031 16039 32031 16041 32032 16039 32032 16034 32032 16044 32033 16272 32033 16270 32033 16035 32034 12061 32034 16036 32034 16036 32035 12061 32035 16038 32035 16036 32036 16038 32036 16039 32036 16039 32037 16038 32037 12060 32037 16039 32038 12060 32038 16034 32038 16040 32039 12059 32039 16041 32039 16041 32040 12059 32040 16042 32040 16041 32041 16042 32041 16044 32041 16044 32042 16042 32042 16043 32042 16044 32043 16043 32043 16272 32043 12066 32044 16045 32044 16046 32044 16046 32045 16045 32045 15912 32045 16046 32046 15912 32046 16047 32046 16047 32047 15912 32047 18489 32047 16048 32048 16053 32048 16081 32048 16049 32049 11818 32049 16052 32049 16064 32050 16050 32050 16051 32050 15899 32051 11777 32051 16052 32051 16052 32052 11777 32052 16081 32052 16052 32053 16081 32053 16049 32053 16049 32054 16081 32054 16053 32054 11818 32055 16054 32055 16052 32055 16052 32056 16054 32056 16055 32056 16052 32057 16055 32057 16056 32057 16056 32058 16055 32058 11823 32058 16056 32059 11823 32059 18487 32059 18487 32060 11823 32060 16057 32060 18487 32061 16057 32061 16066 32061 16066 32062 16057 32062 16058 32062 16066 32063 16058 32063 16064 32063 16064 32064 16058 32064 16538 32064 16064 32065 16538 32065 16050 32065 16064 32066 16063 32066 12074 32066 16533 32067 11825 32067 16059 32067 16059 32068 11825 32068 16060 32068 16059 32069 16060 32069 16061 32069 16061 32070 16060 32070 16260 32070 16061 32071 16258 32071 16059 32071 16059 32072 16258 32072 16256 32072 16059 32073 16256 32073 16064 32073 16064 32074 16256 32074 16062 32074 16064 32075 16062 32075 16063 32075 12074 32076 16065 32076 16064 32076 16064 32077 16065 32077 16067 32077 16064 32078 16067 32078 16066 32078 16065 32079 12072 32079 16067 32079 16067 32080 12072 32080 12071 32080 16067 32081 12071 32081 18486 32081 18486 32082 12071 32082 12070 32082 18486 32083 12070 32083 16060 32083 16060 32084 12070 32084 16262 32084 16060 32085 16262 32085 16260 32085 12081 32086 12079 32086 16070 32086 16070 32087 12079 32087 16068 32087 12079 32088 12078 32088 16068 32088 16068 32089 12078 32089 12076 32089 16068 32090 12076 32090 16073 32090 16069 32091 15945 32091 18484 32091 18484 32092 15945 32092 16075 32092 18484 32093 16075 32093 16070 32093 16070 32094 16075 32094 16071 32094 16070 32095 16071 32095 12081 32095 16072 32096 15860 32096 15868 32096 15868 32097 15860 32097 16068 32097 15868 32098 16068 32098 15758 32098 15758 32099 16068 32099 16073 32099 15758 32100 16073 32100 15757 32100 16112 32101 16254 32101 16110 32101 16110 32102 16254 32102 16074 32102 16110 32103 16074 32103 16075 32103 16075 32104 16074 32104 16076 32104 16075 32105 16076 32105 16071 32105 12192 32106 15956 32106 12193 32106 12193 32107 15956 32107 16077 32107 12193 32108 16077 32108 16079 32108 16079 32109 16077 32109 16093 32109 16079 32110 16093 32110 16078 32110 16078 32111 16093 32111 16059 32111 16078 32112 16059 32112 16080 32112 16080 32113 16059 32113 16064 32113 16080 32114 16064 32114 16081 32114 16081 32115 16064 32115 16051 32115 16081 32116 16051 32116 16048 32116 17205 32117 16079 32117 15958 32117 15958 32118 16079 32118 16078 32118 15958 32119 16078 32119 16084 32119 16084 32120 16078 32120 16080 32120 16084 32121 16080 32121 16085 32121 16085 32122 16080 32122 16081 32122 16085 32123 16081 32123 16082 32123 16082 32124 16081 32124 16612 32124 16082 32125 16612 32125 16611 32125 16083 32126 15958 32126 16088 32126 16088 32127 15958 32127 16084 32127 16088 32128 16084 32128 16089 32128 16089 32129 16084 32129 16085 32129 16089 32130 16085 32130 16086 32130 16086 32131 16085 32131 16082 32131 16086 32132 16082 32132 16091 32132 16091 32133 16082 32133 16087 32133 16091 32134 16087 32134 15882 32134 15882 32135 16087 32135 16266 32135 15882 32136 16266 32136 16265 32136 17212 32137 16088 32137 16096 32137 16096 32138 16088 32138 16089 32138 16096 32139 16089 32139 16090 32139 16090 32140 16089 32140 16086 32140 16090 32141 16086 32141 16044 32141 16044 32142 16086 32142 16091 32142 16044 32143 16091 32143 16041 32143 16041 32144 16091 32144 17011 32144 16041 32145 17011 32145 17009 32145 12189 32146 15954 32146 12191 32146 12191 32147 15954 32147 16092 32147 12191 32148 16092 32148 15956 32148 15956 32149 16092 32149 16124 32149 15956 32150 16124 32150 16077 32150 16077 32151 16124 32151 16094 32151 16077 32152 16094 32152 16093 32152 16093 32153 16094 32153 16528 32153 16093 32154 16528 32154 16530 32154 16095 32155 15762 32155 16100 32155 16100 32156 15762 32156 16096 32156 16100 32157 16096 32157 16101 32157 16101 32158 16096 32158 16090 32158 16101 32159 16090 32159 15926 32159 15926 32160 16090 32160 16044 32160 15926 32161 16044 32161 16033 32161 16033 32162 16044 32162 16270 32162 16033 32163 16270 32163 16097 32163 16098 32164 15959 32164 16099 32164 16099 32165 15959 32165 16100 32165 16099 32166 16100 32166 16131 32166 16131 32167 16100 32167 16101 32167 16131 32168 16101 32168 15940 32168 15940 32169 16101 32169 15926 32169 15940 32170 15926 32170 15937 32170 15937 32171 15926 32171 16999 32171 15937 32172 16999 32172 17001 32172 16102 32173 16103 32173 16104 32173 16104 32174 16103 32174 15859 32174 16104 32175 15859 32175 16105 32175 16105 32176 15859 32176 16106 32176 16105 32177 16106 32177 16107 32177 12032 32178 16108 32178 16109 32178 16109 32179 16108 32179 16104 32179 16109 32180 16104 32180 16117 32180 16117 32181 16104 32181 16105 32181 16117 32182 16105 32182 16118 32182 16118 32183 16105 32183 15758 32183 16118 32184 15758 32184 16110 32184 16110 32185 15758 32185 16111 32185 16110 32186 16111 32186 16112 32186 12039 32187 16009 32187 16024 32187 16024 32188 16009 32188 16134 32188 16024 32189 16134 32189 15870 32189 15870 32190 16134 32190 16113 32190 15870 32191 16113 32191 16114 32191 16114 32192 16113 32192 16029 32192 16114 32193 16029 32193 15841 32193 15841 32194 16029 32194 16115 32194 15841 32195 16115 32195 16276 32195 15810 32196 15812 32196 16119 32196 16119 32197 15812 32197 16109 32197 16119 32198 16109 32198 16116 32198 16116 32199 16109 32199 16117 32199 16116 32200 16117 32200 16120 32200 16120 32201 16117 32201 16118 32201 16120 32202 16118 32202 16121 32202 16121 32203 16118 32203 16110 32203 16121 32204 16110 32204 16122 32204 16122 32205 16110 32205 16075 32205 16122 32206 16075 32206 16123 32206 16123 32207 16075 32207 16521 32207 16123 32208 16521 32208 16520 32208 11992 32209 16119 32209 15951 32209 15951 32210 16119 32210 16116 32210 15951 32211 16116 32211 15763 32211 15763 32212 16116 32212 16120 32212 15763 32213 16120 32213 15952 32213 15952 32214 16120 32214 16121 32214 15952 32215 16121 32215 15955 32215 15955 32216 16121 32216 16122 32216 15955 32217 16122 32217 15954 32217 15954 32218 16122 32218 16123 32218 15954 32219 16123 32219 16092 32219 16092 32220 16123 32220 15908 32220 16092 32221 15908 32221 16124 32221 16124 32222 15908 32222 16125 32222 16124 32223 16125 32223 16126 32223 15777 32224 16143 32224 15781 32224 15781 32225 16143 32225 16127 32225 15781 32226 16127 32226 16133 32226 16133 32227 16127 32227 16145 32227 16133 32228 16145 32228 16128 32228 16128 32229 16145 32229 16129 32229 16128 32230 16129 32230 16130 32230 16130 32231 16129 32231 16099 32231 16130 32232 16099 32232 16135 32232 16135 32233 16099 32233 16131 32233 16135 32234 16131 32234 15964 32234 15964 32235 16131 32235 15940 32235 15964 32236 15940 32236 16132 32236 16132 32237 15940 32237 15942 32237 16132 32238 15942 32238 17061 32238 11646 32239 15781 32239 16012 32239 16012 32240 15781 32240 16133 32240 16012 32241 16133 32241 16009 32241 16009 32242 16133 32242 16128 32242 16009 32243 16128 32243 16134 32243 16134 32244 16128 32244 16130 32244 16134 32245 16130 32245 16113 32245 16113 32246 16130 32246 16135 32246 16113 32247 16135 32247 16029 32247 16029 32248 16135 32248 15964 32248 16029 32249 15964 32249 16136 32249 16136 32250 15964 32250 15966 32250 16136 32251 15966 32251 16990 32251 15720 32252 16137 32252 16138 32252 16138 32253 16137 32253 16150 32253 16138 32254 16150 32254 15951 32254 15951 32255 16150 32255 16139 32255 15951 32256 16139 32256 15813 32256 15813 32257 16139 32257 16352 32257 11637 32258 16140 32258 16141 32258 16141 32259 16140 32259 16142 32259 16141 32260 16142 32260 16143 32260 16143 32261 16142 32261 16144 32261 16143 32262 16144 32262 16127 32262 16127 32263 16144 32263 15738 32263 16127 32264 15738 32264 16145 32264 16145 32265 15738 32265 16146 32265 16145 32266 16146 32266 15734 32266 15996 32267 15997 32267 16002 32267 16002 32268 15997 32268 16147 32268 16002 32269 16147 32269 16140 32269 16140 32270 16147 32270 15962 32270 16140 32271 15962 32271 16142 32271 16142 32272 15962 32272 16148 32272 16142 32273 16148 32273 16144 32273 16144 32274 16148 32274 16149 32274 16144 32275 16149 32275 15738 32275 12090 32276 15817 32276 15823 32276 15823 32277 15817 32277 15984 32277 15823 32278 15984 32278 16154 32278 16154 32279 15984 32279 15824 32279 16154 32280 15824 32280 16157 32280 16157 32281 15824 32281 16150 32281 16157 32282 16150 32282 16158 32282 16158 32283 16150 32283 16137 32283 16158 32284 16137 32284 17250 32284 11630 32285 16163 32285 15998 32285 15998 32286 16163 32286 16151 32286 15998 32287 16151 32287 15997 32287 15997 32288 16151 32288 16152 32288 15997 32289 16152 32289 16147 32289 16147 32290 16152 32290 15961 32290 16147 32291 15961 32291 15740 32291 16153 32292 15821 32292 16162 32292 16162 32293 15821 32293 16154 32293 16162 32294 16154 32294 16155 32294 16155 32295 16154 32295 16157 32295 16155 32296 16157 32296 16156 32296 16156 32297 16157 32297 16158 32297 16156 32298 16158 32298 16159 32298 16159 32299 16158 32299 17250 32299 16159 32300 17250 32300 17176 32300 16160 32301 16161 32301 15990 32301 15990 32302 16161 32302 16162 32302 15990 32303 16162 32303 15788 32303 15788 32304 16162 32304 16155 32304 15788 32305 16155 32305 16163 32305 16163 32306 16155 32306 16156 32306 16163 32307 16156 32307 16151 32307 16151 32308 16156 32308 16159 32308 16151 32309 16159 32309 16152 32309 16152 32310 16159 32310 17165 32310 16152 32311 17165 32311 17164 32311 16218 32312 16164 32312 16165 32312 16218 32313 16165 32313 16166 32313 16166 32314 16165 32314 16171 32314 16166 32315 16171 32315 16167 32315 16167 32316 16171 32316 16220 32316 16220 32317 16171 32317 16168 32317 16220 32318 16168 32318 16222 32318 16222 32319 16168 32319 16223 32319 16223 32320 16168 32320 16169 32320 16223 32321 16169 32321 16224 32321 16224 32322 16169 32322 16170 32322 16170 32323 16169 32323 16173 32323 16170 32324 16173 32324 16228 32324 16228 32325 16173 32325 16175 32325 16228 32326 16175 32326 16227 32326 16227 32327 16175 32327 12176 32327 16227 32328 12176 32328 16225 32328 16164 32329 13674 32329 16165 32329 16165 32330 13674 32330 13673 32330 16165 32331 13673 32331 16171 32331 16171 32332 13673 32332 13672 32332 16171 32333 13672 32333 16168 32333 16168 32334 13672 32334 13671 32334 16168 32335 13671 32335 16169 32335 16169 32336 13671 32336 16172 32336 16169 32337 16172 32337 16173 32337 16173 32338 16172 32338 16174 32338 16173 32339 16174 32339 16175 32339 16175 32340 16174 32340 16176 32340 16175 32341 16176 32341 12176 32341 12176 32342 16176 32342 12169 32342 16177 32343 12168 32343 16178 32343 16178 32344 12168 32344 16181 32344 16178 32345 16181 32345 16179 32345 16179 32346 16181 32346 16182 32346 16179 32347 16182 32347 16235 32347 16235 32348 16182 32348 16184 32348 16235 32349 16184 32349 16233 32349 16233 32350 16184 32350 16180 32350 16233 32351 16180 32351 16231 32351 16231 32352 16180 32352 16187 32352 16231 32353 16187 32353 12105 32353 12105 32354 16187 32354 12156 32354 12168 32355 13667 32355 16181 32355 16181 32356 13667 32356 13665 32356 16181 32357 13665 32357 16182 32357 16182 32358 13665 32358 16183 32358 16182 32359 16183 32359 16184 32359 16184 32360 16183 32360 16185 32360 16184 32361 16185 32361 16180 32361 16180 32362 16185 32362 16186 32362 16180 32363 16186 32363 16187 32363 16187 32364 16186 32364 13661 32364 16187 32365 13661 32365 12156 32365 12156 32366 13661 32366 16188 32366 16238 32367 12151 32367 16189 32367 16189 32368 12151 32368 16190 32368 16189 32369 16190 32369 16191 32369 16191 32370 16190 32370 16240 32370 16240 32371 16190 32371 16202 32371 16240 32372 16202 32372 16192 32372 16192 32373 16202 32373 16241 32373 16241 32374 16202 32374 16193 32374 16241 32375 16193 32375 16194 32375 16194 32376 16193 32376 16195 32376 16195 32377 16193 32377 16197 32377 16195 32378 16197 32378 16196 32378 16196 32379 16197 32379 16243 32379 16243 32380 16197 32380 16199 32380 16243 32381 16199 32381 16198 32381 16198 32382 16199 32382 16245 32382 16245 32383 16199 32383 16200 32383 16245 32384 16200 32384 12145 32384 12151 32385 16201 32385 16190 32385 16190 32386 16201 32386 13652 32386 16190 32387 13652 32387 16202 32387 16202 32388 13652 32388 13650 32388 16202 32389 13650 32389 16193 32389 16193 32390 13650 32390 16203 32390 16193 32391 16203 32391 16197 32391 16197 32392 16203 32392 16204 32392 16197 32393 16204 32393 16199 32393 16199 32394 16204 32394 13648 32394 16199 32395 13648 32395 16200 32395 16200 32396 13648 32396 13646 32396 12139 32397 12138 32397 16205 32397 16205 32398 12138 32398 16208 32398 16205 32399 16208 32399 16206 32399 16206 32400 16208 32400 16209 32400 16206 32401 16209 32401 16252 32401 16252 32402 16209 32402 16211 32402 16252 32403 16211 32403 16249 32403 16249 32404 16211 32404 16212 32404 16249 32405 16212 32405 16248 32405 16248 32406 16212 32406 16207 32406 16248 32407 16207 32407 12085 32407 12085 32408 16207 32408 12128 32408 12138 32409 13632 32409 16208 32409 16208 32410 13632 32410 13639 32410 16208 32411 13639 32411 16209 32411 16209 32412 13639 32412 16210 32412 16209 32413 16210 32413 16211 32413 16211 32414 16210 32414 13638 32414 16211 32415 13638 32415 16212 32415 16212 32416 13638 32416 16213 32416 16212 32417 16213 32417 16207 32417 16207 32418 16213 32418 16214 32418 16207 32419 16214 32419 12128 32419 12128 32420 16214 32420 16215 32420 16216 32421 16218 32421 16217 32421 16217 32422 16218 32422 16166 32422 16217 32423 16166 32423 16219 32423 16166 32424 16167 32424 16219 32424 16219 32425 16167 32425 16220 32425 16219 32426 16220 32426 16221 32426 16221 32427 16220 32427 16222 32427 16222 32428 16223 32428 16221 32428 16221 32429 16223 32429 16224 32429 16221 32430 16224 32430 16230 32430 16225 32431 16226 32431 16227 32431 16227 32432 16226 32432 16229 32432 16227 32433 16229 32433 16228 32433 16228 32434 16229 32434 16230 32434 16228 32435 16230 32435 16170 32435 16170 32436 16230 32436 16224 32436 12105 32437 12104 32437 16231 32437 16231 32438 12104 32438 16232 32438 16231 32439 16232 32439 16233 32439 16233 32440 16232 32440 16234 32440 16233 32441 16234 32441 16235 32441 16235 32442 16234 32442 15806 32442 16235 32443 15806 32443 16179 32443 16179 32444 15806 32444 16236 32444 16179 32445 16236 32445 16178 32445 16178 32446 16236 32446 16237 32446 16178 32447 16237 32447 16177 32447 16177 32448 16237 32448 12110 32448 16239 32449 15835 32449 16238 32449 16238 32450 16189 32450 16239 32450 16239 32451 16189 32451 16191 32451 16239 32452 16191 32452 15837 32452 16191 32453 16240 32453 15837 32453 15837 32454 16240 32454 16192 32454 15837 32455 16192 32455 15831 32455 15831 32456 16192 32456 16241 32456 15831 32457 16241 32457 16242 32457 16241 32458 16194 32458 16242 32458 16242 32459 16194 32459 16195 32459 16242 32460 16195 32460 15832 32460 16195 32461 16196 32461 15832 32461 15832 32462 16196 32462 16243 32462 15832 32463 16243 32463 16246 32463 12145 32464 16244 32464 16245 32464 16245 32465 16244 32465 16246 32465 16245 32466 16246 32466 16198 32466 16198 32467 16246 32467 16243 32467 12085 32468 12084 32468 16248 32468 16248 32469 12084 32469 16247 32469 16248 32470 16247 32470 16249 32470 16249 32471 16247 32471 16250 32471 16249 32472 16250 32472 16252 32472 16252 32473 16250 32473 16251 32473 16252 32474 16251 32474 16206 32474 16206 32475 16251 32475 15818 32475 16206 32476 15818 32476 16205 32476 16205 32477 15818 32477 16253 32477 16205 32478 16253 32478 12139 32478 12139 32479 16253 32479 15816 32479 12083 32480 16074 32480 18655 32480 18655 32481 16074 32481 16254 32481 18655 32482 16254 32482 16255 32482 16255 32483 16254 32483 16112 32483 16255 32484 16112 32484 18654 32484 18654 32485 16112 32485 16111 32485 18654 32486 16111 32486 18651 32486 18651 32487 16111 32487 15757 32487 18651 32488 15757 32488 18650 32488 18650 32489 15757 32489 16073 32489 18650 32490 16073 32490 18649 32490 18649 32491 16073 32491 12076 32491 12075 32492 16062 32492 16257 32492 16257 32493 16062 32493 16256 32493 16257 32494 16256 32494 18648 32494 18648 32495 16256 32495 16258 32495 18648 32496 16258 32496 18647 32496 18647 32497 16258 32497 16061 32497 18647 32498 16061 32498 16259 32498 16259 32499 16061 32499 16260 32499 16259 32500 16260 32500 16261 32500 16261 32501 16260 32501 16262 32501 16261 32502 16262 32502 12069 32502 12069 32503 16262 32503 12070 32503 12067 32504 12068 32504 16263 32504 16263 32505 12068 32505 15915 32505 16263 32506 15915 32506 18642 32506 18642 32507 15915 32507 16265 32507 18642 32508 16265 32508 16264 32508 16264 32509 16265 32509 16266 32509 16264 32510 16266 32510 18640 32510 18640 32511 16266 32511 15914 32511 18640 32512 15914 32512 18639 32512 18639 32513 15914 32513 15913 32513 18639 32514 15913 32514 16267 32514 16267 32515 15913 32515 16268 32515 18634 32516 12061 32516 16269 32516 16269 32517 12061 32517 16035 32517 16269 32518 16035 32518 18635 32518 18635 32519 16035 32519 16097 32519 18635 32520 16097 32520 18630 32520 18630 32521 16097 32521 16270 32521 18630 32522 16270 32522 16271 32522 16271 32523 16270 32523 16272 32523 16271 32524 16272 32524 18631 32524 18631 32525 16272 32525 16043 32525 18631 32526 16043 32526 16273 32526 16273 32527 16043 32527 16042 32527 12057 32528 16274 32528 18627 32528 18627 32529 16274 32529 16275 32529 18627 32530 16275 32530 18628 32530 18628 32531 16275 32531 16027 32531 18628 32532 16027 32532 18625 32532 18625 32533 16027 32533 16276 32533 18625 32534 16276 32534 16277 32534 16277 32535 16276 32535 16115 32535 16277 32536 16115 32536 18626 32536 18626 32537 16115 32537 16278 32537 18626 32538 16278 32538 16279 32538 16279 32539 16278 32539 16030 32539 18619 32540 16001 32540 18617 32540 18617 32541 16001 32541 16280 32541 18617 32542 16280 32542 18615 32542 18615 32543 16280 32543 16006 32543 18615 32544 16006 32544 18616 32544 18616 32545 16006 32545 16005 32545 18616 32546 16005 32546 18614 32546 18614 32547 16005 32547 16004 32547 18614 32548 16004 32548 18622 32548 18622 32549 16004 32549 16281 32549 18622 32550 16281 32550 18621 32550 18621 32551 16281 32551 16000 32551 18621 32552 16000 32552 18620 32552 18620 32553 16000 32553 12043 32553 18612 32554 16282 32554 18608 32554 18608 32555 16282 32555 16016 32555 18608 32556 16016 32556 18607 32556 18607 32557 16016 32557 16015 32557 18607 32558 16015 32558 18609 32558 18609 32559 16015 32559 16283 32559 18609 32560 16283 32560 16284 32560 16284 32561 16283 32561 16285 32561 16284 32562 16285 32562 16286 32562 16286 32563 16285 32563 16013 32563 16286 32564 16013 32564 16287 32564 16287 32565 16013 32565 16288 32565 16287 32566 16288 32566 12036 32566 12036 32567 16288 32567 12037 32567 12035 32568 16289 32568 18605 32568 18605 32569 16289 32569 16290 32569 18605 32570 16290 32570 18604 32570 18604 32571 16290 32571 15979 32571 18604 32572 15979 32572 16291 32572 16291 32573 15979 32573 15978 32573 16291 32574 15978 32574 16292 32574 16292 32575 15978 32575 15980 32575 16292 32576 15980 32576 18601 32576 18601 32577 15980 32577 16293 32577 18601 32578 16293 32578 16294 32578 16294 32579 16293 32579 16295 32579 12027 32580 15827 32580 18595 32580 18595 32581 15827 32581 15828 32581 18595 32582 15828 32582 18598 32582 18598 32583 15828 32583 15985 32583 18598 32584 15985 32584 16296 32584 16296 32585 15985 32585 16297 32585 16296 32586 16297 32586 18594 32586 18594 32587 16297 32587 15830 32587 18594 32588 15830 32588 16298 32588 16298 32589 15830 32589 16299 32589 16298 32590 16299 32590 18596 32590 18596 32591 16299 32591 15834 32591 18596 32592 15834 32592 16300 32592 16300 32593 15834 32593 16301 32593 12020 32594 12021 32594 18593 32594 18593 32595 12021 32595 15989 32595 18593 32596 15989 32596 16302 32596 16302 32597 15989 32597 16304 32597 16302 32598 16304 32598 16303 32598 16303 32599 16304 32599 15988 32599 16303 32600 15988 32600 18591 32600 18591 32601 15988 32601 16305 32601 18591 32602 16305 32602 16306 32602 16306 32603 16305 32603 16308 32603 16306 32604 16308 32604 16307 32604 16307 32605 16308 32605 12013 32605 16309 32606 16310 32606 16392 32606 16392 32607 16310 32607 16311 32607 16392 32608 16311 32608 16389 32608 16389 32609 16311 32609 16325 32609 16389 32610 16325 32610 16312 32610 16312 32611 16325 32611 16327 32611 16312 32612 16327 32612 16387 32612 16387 32613 16327 32613 12005 32613 16387 32614 12005 32614 11967 32614 11967 32615 12005 32615 16313 32615 11967 32616 16313 32616 11969 32616 11969 32617 16313 32617 16314 32617 11969 32618 16314 32618 16315 32618 16315 32619 16314 32619 12008 32619 16315 32620 12008 32620 16316 32620 16316 32621 12008 32621 12009 32621 16316 32622 12009 32622 11963 32622 11963 32623 12009 32623 12010 32623 11963 32624 12010 32624 16317 32624 16317 32625 12010 32625 16319 32625 16317 32626 16319 32626 16396 32626 16396 32627 16319 32627 16320 32627 16396 32628 16320 32628 16318 32628 16318 32629 16320 32629 16322 32629 16318 32630 16322 32630 16309 32630 16309 32631 16322 32631 16310 32631 16319 32632 16328 32632 16320 32632 16320 32633 16328 32633 16321 32633 16320 32634 16321 32634 16322 32634 16322 32635 16321 32635 16330 32635 16322 32636 16330 32636 16310 32636 16310 32637 16330 32637 16323 32637 16310 32638 16323 32638 16311 32638 16311 32639 16323 32639 16324 32639 16311 32640 16324 32640 16325 32640 16325 32641 16324 32641 16326 32641 16325 32642 16326 32642 16327 32642 16327 32643 16326 32643 16334 32643 16327 32644 16334 32644 12005 32644 12005 32645 16334 32645 12006 32645 16328 32646 15972 32646 16321 32646 16321 32647 15972 32647 16329 32647 16321 32648 16329 32648 16330 32648 16330 32649 16329 32649 15973 32649 16330 32650 15973 32650 16323 32650 16323 32651 15973 32651 16331 32651 16323 32652 16331 32652 16324 32652 16324 32653 16331 32653 16332 32653 16324 32654 16332 32654 16326 32654 16326 32655 16332 32655 16333 32655 16326 32656 16333 32656 16334 32656 16334 32657 16333 32657 15977 32657 16334 32658 15977 32658 12006 32658 12006 32659 15977 32659 15975 32659 16414 32660 16349 32660 16411 32660 16411 32661 16349 32661 16351 32661 16411 32662 16351 32662 11947 32662 11947 32663 16351 32663 11993 32663 11947 32664 11993 32664 11945 32664 11945 32665 11993 32665 16335 32665 11945 32666 16335 32666 11943 32666 11943 32667 16335 32667 11995 32667 11943 32668 11995 32668 16336 32668 16336 32669 11995 32669 11996 32669 16336 32670 11996 32670 16337 32670 16337 32671 11996 32671 16339 32671 16337 32672 16339 32672 16338 32672 16338 32673 16339 32673 16340 32673 16338 32674 16340 32674 16421 32674 16421 32675 16340 32675 16347 32675 16421 32676 16347 32676 16341 32676 16341 32677 16347 32677 16342 32677 16341 32678 16342 32678 16417 32678 16417 32679 16342 32679 16343 32679 16417 32680 16343 32680 16416 32680 16416 32681 16343 32681 16344 32681 16416 32682 16344 32682 16345 32682 16345 32683 16344 32683 16348 32683 16345 32684 16348 32684 16414 32684 16414 32685 16348 32685 16349 32685 16340 32686 16346 32686 16347 32686 16347 32687 16346 32687 16353 32687 16347 32688 16353 32688 16342 32688 16342 32689 16353 32689 16354 32689 16342 32690 16354 32690 16343 32690 16343 32691 16354 32691 16355 32691 16343 32692 16355 32692 16344 32692 16344 32693 16355 32693 16357 32693 16344 32694 16357 32694 16348 32694 16348 32695 16357 32695 16358 32695 16348 32696 16358 32696 16349 32696 16349 32697 16358 32697 16350 32697 16349 32698 16350 32698 16351 32698 16351 32699 16350 32699 16359 32699 16346 32700 15813 32700 16353 32700 16353 32701 15813 32701 16352 32701 16353 32702 16352 32702 16354 32702 16354 32703 16352 32703 15814 32703 16354 32704 15814 32704 16355 32704 16355 32705 15814 32705 16356 32705 16355 32706 16356 32706 16357 32706 16357 32707 16356 32707 15801 32707 16357 32708 15801 32708 16358 32708 16358 32709 15801 32709 15802 32709 16358 32710 15802 32710 16350 32710 16350 32711 15802 32711 16360 32711 16350 32712 16360 32712 16359 32712 16359 32713 16360 32713 16361 32713 11982 32714 11983 32714 11921 32714 11921 32715 11983 32715 11985 32715 11921 32716 11985 32716 11922 32716 11922 32717 11985 32717 11986 32717 11922 32718 11986 32718 11923 32718 11923 32719 11986 32719 11987 32719 11923 32720 11987 32720 16440 32720 16440 32721 11987 32721 16372 32721 16440 32722 16372 32722 16362 32722 16362 32723 16372 32723 16373 32723 16362 32724 16373 32724 16363 32724 16363 32725 16373 32725 16364 32725 16363 32726 16364 32726 16438 32726 16438 32727 16364 32727 16366 32727 16438 32728 16366 32728 16365 32728 16365 32729 16366 32729 16367 32729 16365 32730 16367 32730 16436 32730 16436 32731 16367 32731 16368 32731 16436 32732 16368 32732 16369 32732 16369 32733 16368 32733 16375 32733 16369 32734 16375 32734 16370 32734 16370 32735 16375 32735 11981 32735 16370 32736 11981 32736 16371 32736 16371 32737 11981 32737 11982 32737 16371 32738 11982 32738 11921 32738 16372 32739 11979 32739 16373 32739 16373 32740 11979 32740 16377 32740 16373 32741 16377 32741 16364 32741 16364 32742 16377 32742 16374 32742 16364 32743 16374 32743 16366 32743 16366 32744 16374 32744 16380 32744 16366 32745 16380 32745 16367 32745 16367 32746 16380 32746 16381 32746 16367 32747 16381 32747 16368 32747 16368 32748 16381 32748 16385 32748 16368 32749 16385 32749 16375 32749 16375 32750 16385 32750 16386 32750 11979 32751 16376 32751 16377 32751 16377 32752 16376 32752 16378 32752 16377 32753 16378 32753 16374 32753 16374 32754 16378 32754 16379 32754 16374 32755 16379 32755 16380 32755 16380 32756 16379 32756 16382 32756 16380 32757 16382 32757 16381 32757 16381 32758 16382 32758 16383 32758 16381 32759 16383 32759 16385 32759 16385 32760 16383 32760 16384 32760 16385 32761 16384 32761 16386 32761 16386 32762 16384 32762 11971 32762 16312 32763 16387 32763 16399 32763 16399 32764 16400 32764 16312 32764 16312 32765 16400 32765 16388 32765 16312 32766 16388 32766 16389 32766 16388 32767 16402 32767 16389 32767 16389 32768 16402 32768 16390 32768 16389 32769 16390 32769 16392 32769 16390 32770 16391 32770 16392 32770 16392 32771 16391 32771 16393 32771 16392 32772 16393 32772 16309 32772 16309 32773 16393 32773 16394 32773 16309 32774 16394 32774 16318 32774 16394 32775 16395 32775 16318 32775 16318 32776 16395 32776 16405 32776 16318 32777 16405 32777 16396 32777 16407 32778 16317 32778 16397 32778 16397 32779 16317 32779 16396 32779 16397 32780 16396 32780 16398 32780 16398 32781 16396 32781 16405 32781 16399 32782 11953 32782 16400 32782 16400 32783 11953 32783 16401 32783 16400 32784 16401 32784 16388 32784 16388 32785 16401 32785 16402 32785 16402 32786 16401 32786 16409 32786 16402 32787 16409 32787 16390 32787 16390 32788 16409 32788 16391 32788 16391 32789 16409 32789 16403 32789 16391 32790 16403 32790 16393 32790 16393 32791 16403 32791 16394 32791 16394 32792 16403 32792 16404 32792 16394 32793 16404 32793 16395 32793 16395 32794 16404 32794 16405 32794 16405 32795 16404 32795 16406 32795 16405 32796 16406 32796 16398 32796 16398 32797 16406 32797 16397 32797 16397 32798 16406 32798 11954 32798 16397 32799 11954 32799 16407 32799 11953 32800 13696 32800 16401 32800 16401 32801 13696 32801 16408 32801 16401 32802 16408 32802 16409 32802 16409 32803 16408 32803 13693 32803 16409 32804 13693 32804 16403 32804 16403 32805 13693 32805 13692 32805 16403 32806 13692 32806 16404 32806 16404 32807 13692 32807 16410 32807 16404 32808 16410 32808 16406 32808 16406 32809 16410 32809 13690 32809 16406 32810 13690 32810 11954 32810 11954 32811 13690 32811 13688 32811 16414 32812 16411 32812 16412 32812 16412 32813 16413 32813 16414 32813 16414 32814 16413 32814 16422 32814 16414 32815 16422 32815 16345 32815 16422 32816 16423 32816 16345 32816 16345 32817 16423 32817 16415 32817 16345 32818 16415 32818 16416 32818 16415 32819 16425 32819 16416 32819 16416 32820 16425 32820 16418 32820 16416 32821 16418 32821 16417 32821 16417 32822 16418 32822 16419 32822 16417 32823 16419 32823 16341 32823 16419 32824 16426 32824 16341 32824 16341 32825 16426 32825 16427 32825 16341 32826 16427 32826 16421 32826 11932 32827 16338 32827 16420 32827 16420 32828 16338 32828 16421 32828 16420 32829 16421 32829 16428 32829 16428 32830 16421 32830 16427 32830 16412 32831 11931 32831 16413 32831 16413 32832 11931 32832 16430 32832 16413 32833 16430 32833 16422 32833 16422 32834 16430 32834 16423 32834 16423 32835 16430 32835 16424 32835 16423 32836 16424 32836 16415 32836 16415 32837 16424 32837 16425 32837 16425 32838 16424 32838 16431 32838 16425 32839 16431 32839 16418 32839 16418 32840 16431 32840 16419 32840 16419 32841 16431 32841 16432 32841 16419 32842 16432 32842 16426 32842 16426 32843 16432 32843 16427 32843 16427 32844 16432 32844 16433 32844 16427 32845 16433 32845 16428 32845 16428 32846 16433 32846 16420 32846 16420 32847 16433 32847 11933 32847 16420 32848 11933 32848 11932 32848 11931 32849 16429 32849 16430 32849 16430 32850 16429 32850 13623 32850 16430 32851 13623 32851 16424 32851 16424 32852 13623 32852 13622 32852 16424 32853 13622 32853 16431 32853 16431 32854 13622 32854 13619 32854 16431 32855 13619 32855 16432 32855 16432 32856 13619 32856 13617 32856 16432 32857 13617 32857 16433 32857 16433 32858 13617 32858 16434 32858 16433 32859 16434 32859 11933 32859 11933 32860 16434 32860 11924 32860 16369 32861 16435 32861 16436 32861 16436 32862 16435 32862 16437 32862 16436 32863 16437 32863 16365 32863 16437 32864 16445 32864 16365 32864 16365 32865 16445 32865 16446 32865 16365 32866 16446 32866 16438 32866 16438 32867 16446 32867 16447 32867 16447 32868 16449 32868 16438 32868 16438 32869 16449 32869 16442 32869 16438 32870 16442 32870 16363 32870 16439 32871 16440 32871 16452 32871 16452 32872 16440 32872 16362 32872 16452 32873 16362 32873 16441 32873 16441 32874 16362 32874 16363 32874 16441 32875 16363 32875 16450 32875 16450 32876 16363 32876 16442 32876 16435 32877 16454 32877 16443 32877 16435 32878 16443 32878 16437 32878 16437 32879 16443 32879 16444 32879 16437 32880 16444 32880 16445 32880 16445 32881 16444 32881 16446 32881 16446 32882 16444 32882 16448 32882 16446 32883 16448 32883 16447 32883 16447 32884 16448 32884 16449 32884 16449 32885 16448 32885 16456 32885 16449 32886 16456 32886 16442 32886 16442 32887 16456 32887 16450 32887 16450 32888 16456 32888 16451 32888 16450 32889 16451 32889 16441 32889 16441 32890 16451 32890 16457 32890 16441 32891 16457 32891 16452 32891 16452 32892 16457 32892 16453 32892 16452 32893 16453 32893 16439 32893 16454 32894 11910 32894 16443 32894 16443 32895 11910 32895 16455 32895 16443 32896 16455 32896 16444 32896 16444 32897 16455 32897 13614 32897 16444 32898 13614 32898 16448 32898 16448 32899 13614 32899 13612 32899 16448 32900 13612 32900 16456 32900 16456 32901 13612 32901 13611 32901 16456 32902 13611 32902 16451 32902 16451 32903 13611 32903 13610 32903 16451 32904 13610 32904 16457 32904 16457 32905 13610 32905 13609 32905 16457 32906 13609 32906 16453 32906 16453 32907 13609 32907 11906 32907 16458 32908 11896 32908 16465 32908 16458 32909 16465 32909 16510 32909 16510 32910 16465 32910 16466 32910 16510 32911 16466 32911 16512 32911 16512 32912 16466 32912 16459 32912 16459 32913 16466 32913 16461 32913 16459 32914 16461 32914 16460 32914 16460 32915 16461 32915 16514 32915 16514 32916 16461 32916 16469 32916 16514 32917 16469 32917 16462 32917 16462 32918 16469 32918 16517 32918 16517 32919 16469 32919 16463 32919 16517 32920 16463 32920 16516 32920 16516 32921 16463 32921 16471 32921 16516 32922 16471 32922 16464 32922 16464 32923 16471 32923 11897 32923 16464 32924 11897 32924 16515 32924 11896 32925 13703 32925 16465 32925 16465 32926 13703 32926 16467 32926 16465 32927 16467 32927 16466 32927 16466 32928 16467 32928 13700 32928 16466 32929 13700 32929 16461 32929 16461 32930 13700 32930 16468 32930 16461 32931 16468 32931 16469 32931 16469 32932 16468 32932 16470 32932 16469 32933 16470 32933 16463 32933 16463 32934 16470 32934 13712 32934 16463 32935 13712 32935 16471 32935 16471 32936 13712 32936 16472 32936 16471 32937 16472 32937 11897 32937 11897 32938 16472 32938 11891 32938 16522 32939 11885 32939 16474 32939 16474 32940 11885 32940 16473 32940 16474 32941 16473 32941 16475 32941 16475 32942 16473 32942 16481 32942 16475 32943 16481 32943 16519 32943 16519 32944 16481 32944 16483 32944 16519 32945 16483 32945 16518 32945 16518 32946 16483 32946 16476 32946 16518 32947 16476 32947 16477 32947 16477 32948 16476 32948 16479 32948 16477 32949 16479 32949 16478 32949 16478 32950 16479 32950 11878 32950 11885 32951 16480 32951 16473 32951 16473 32952 16480 32952 13723 32952 16473 32953 13723 32953 16481 32953 16481 32954 13723 32954 16482 32954 16481 32955 16482 32955 16483 32955 16483 32956 16482 32956 16484 32956 16483 32957 16484 32957 16476 32957 16476 32958 16484 32958 13720 32958 16476 32959 13720 32959 16479 32959 16479 32960 13720 32960 16485 32960 16479 32961 16485 32961 11878 32961 11878 32962 16485 32962 13716 32962 16486 32963 11868 32963 16487 32963 16487 32964 11868 32964 16488 32964 16487 32965 16488 32965 16525 32965 16525 32966 16488 32966 16489 32966 16489 32967 16488 32967 16496 32967 16489 32968 16496 32968 16526 32968 16526 32969 16496 32969 16527 32969 16527 32970 16496 32970 16490 32970 16527 32971 16490 32971 16491 32971 16491 32972 16490 32972 16529 32972 16529 32973 16490 32973 16497 32973 16529 32974 16497 32974 16492 32974 16492 32975 16497 32975 16531 32975 16531 32976 16497 32976 16498 32976 16531 32977 16498 32977 16534 32977 16534 32978 16498 32978 16493 32978 16493 32979 16498 32979 16494 32979 16493 32980 16494 32980 16532 32980 11868 32981 13742 32981 16488 32981 16488 32982 13742 32982 16495 32982 16488 32983 16495 32983 16496 32983 16496 32984 16495 32984 13740 32984 16496 32985 13740 32985 16490 32985 16490 32986 13740 32986 13739 32986 16490 32987 13739 32987 16497 32987 16497 32988 13739 32988 13737 32988 16497 32989 13737 32989 16498 32989 16498 32990 13737 32990 13735 32990 16498 32991 13735 32991 16494 32991 16494 32992 13735 32992 13734 32992 11822 32993 11855 32993 16537 32993 16537 32994 11855 32994 16499 32994 16537 32995 16499 32995 16536 32995 16536 32996 16499 32996 16504 32996 16536 32997 16504 32997 16500 32997 16500 32998 16504 32998 16507 32998 16500 32999 16507 32999 16535 32999 16535 33000 16507 33000 16501 33000 16535 33001 16501 33001 16502 33001 16502 33002 16501 33002 16508 33002 16502 33003 16508 33003 11856 33003 11856 33004 16508 33004 11857 33004 11855 33005 16503 33005 16499 33005 16499 33006 16503 33006 16505 33006 16499 33007 16505 33007 16504 33007 16504 33008 16505 33008 16506 33008 16504 33009 16506 33009 16507 33009 16507 33010 16506 33010 13750 33010 16507 33011 13750 33011 16501 33011 16501 33012 13750 33012 13748 33012 16501 33013 13748 33013 16508 33013 16508 33014 13748 33014 16509 33014 16508 33015 16509 33015 11857 33015 11857 33016 16509 33016 11849 33016 11847 33017 16458 33017 15864 33017 15864 33018 16458 33018 16510 33018 15864 33019 16510 33019 16511 33019 16510 33020 16512 33020 16511 33020 16511 33021 16512 33021 16459 33021 16511 33022 16459 33022 16513 33022 16513 33023 16459 33023 16460 33023 16460 33024 16514 33024 16513 33024 16513 33025 16514 33025 16462 33025 16513 33026 16462 33026 15865 33026 16515 33027 16107 33027 16464 33027 16464 33028 16107 33028 16106 33028 16464 33029 16106 33029 16516 33029 16516 33030 16106 33030 15865 33030 16516 33031 15865 33031 16517 33031 16517 33032 15865 33032 16462 33032 16478 33033 15948 33033 16477 33033 16477 33034 15948 33034 15949 33034 16477 33035 15949 33035 16518 33035 16518 33036 15949 33036 16520 33036 16518 33037 16520 33037 16519 33037 16519 33038 16520 33038 16521 33038 16519 33039 16521 33039 16475 33039 16475 33040 16521 33040 15947 33040 16475 33041 15947 33041 16474 33041 16474 33042 15947 33042 15946 33042 16474 33043 15946 33043 16522 33043 16522 33044 15946 33044 15945 33044 16523 33045 15904 33045 16486 33045 16486 33046 16487 33046 16523 33046 16523 33047 16487 33047 16525 33047 16523 33048 16525 33048 16524 33048 16525 33049 16489 33049 16524 33049 16524 33050 16489 33050 16526 33050 16524 33051 16526 33051 15923 33051 15923 33052 16526 33052 16527 33052 15923 33053 16527 33053 16528 33053 16527 33054 16491 33054 16528 33054 16528 33055 16491 33055 16529 33055 16528 33056 16529 33056 16530 33056 16529 33057 16492 33057 16530 33057 16530 33058 16492 33058 16531 33058 16530 33059 16531 33059 15924 33059 16532 33060 16533 33060 16493 33060 16493 33061 16533 33061 15924 33061 16493 33062 15924 33062 16534 33062 16534 33063 15924 33063 16531 33063 11856 33064 16049 33064 16502 33064 16502 33065 16049 33065 16053 33065 16502 33066 16053 33066 16535 33066 16535 33067 16053 33067 16048 33067 16535 33068 16048 33068 16500 33068 16500 33069 16048 33069 16051 33069 16500 33070 16051 33070 16536 33070 16536 33071 16051 33071 16050 33071 16536 33072 16050 33072 16537 33072 16537 33073 16050 33073 16538 33073 16537 33074 16538 33074 11822 33074 11822 33075 16538 33075 16058 33075 16539 33076 16541 33076 16540 33076 16540 33077 16541 33077 16542 33077 16540 33078 16542 33078 11775 33078 11775 33079 16542 33079 16543 33079 11775 33080 16543 33080 16544 33080 16544 33081 16543 33081 11816 33081 16544 33082 11816 33082 11776 33082 11776 33083 11816 33083 16545 33083 11776 33084 16545 33084 16546 33084 16546 33085 16545 33085 16555 33085 16546 33086 16555 33086 16547 33086 16547 33087 16555 33087 16556 33087 16547 33088 16556 33088 16548 33088 16548 33089 16556 33089 16558 33089 16548 33090 16558 33090 16617 33090 16617 33091 16558 33091 16559 33091 16617 33092 16559 33092 16549 33092 16549 33093 16559 33093 16550 33093 16549 33094 16550 33094 16551 33094 16551 33095 16550 33095 16561 33095 16551 33096 16561 33096 11772 33096 11772 33097 16561 33097 11813 33097 11772 33098 11813 33098 16552 33098 16552 33099 11813 33099 16539 33099 16552 33100 16539 33100 16540 33100 16545 33101 16553 33101 16555 33101 16555 33102 16553 33102 16554 33102 16555 33103 16554 33103 16556 33103 16556 33104 16554 33104 16557 33104 16556 33105 16557 33105 16558 33105 16558 33106 16557 33106 16564 33106 16558 33107 16564 33107 16559 33107 16559 33108 16564 33108 16565 33108 16559 33109 16565 33109 16550 33109 16550 33110 16565 33110 16560 33110 16550 33111 16560 33111 16561 33111 16561 33112 16560 33112 11812 33112 16553 33113 11811 33113 16554 33113 16554 33114 11811 33114 16562 33114 16554 33115 16562 33115 16557 33115 16557 33116 16562 33116 16563 33116 16557 33117 16563 33117 16564 33117 16564 33118 16563 33118 15971 33118 16564 33119 15971 33119 16565 33119 16565 33120 15971 33120 16566 33120 16565 33121 16566 33121 16560 33121 16560 33122 16566 33122 16567 33122 16560 33123 16567 33123 11812 33123 11812 33124 16567 33124 11802 33124 11757 33125 11797 33125 11758 33125 11758 33126 11797 33126 16568 33126 11758 33127 16568 33127 11759 33127 11759 33128 16568 33128 11801 33128 11759 33129 11801 33129 16569 33129 16569 33130 11801 33130 16570 33130 16569 33131 16570 33131 16645 33131 16645 33132 16570 33132 16578 33132 16645 33133 16578 33133 16646 33133 16646 33134 16578 33134 16571 33134 16646 33135 16571 33135 16641 33135 16641 33136 16571 33136 16580 33136 16641 33137 16580 33137 16572 33137 16572 33138 16580 33138 16581 33138 16572 33139 16581 33139 16573 33139 16573 33140 16581 33140 16574 33140 16573 33141 16574 33141 11754 33141 11754 33142 16574 33142 16575 33142 11754 33143 16575 33143 11755 33143 11755 33144 16575 33144 16576 33144 11755 33145 16576 33145 11756 33145 11756 33146 16576 33146 16577 33146 11756 33147 16577 33147 11757 33147 11757 33148 16577 33148 11795 33148 11757 33149 11795 33149 11797 33149 16570 33150 11791 33150 16578 33150 16578 33151 11791 33151 16579 33151 16578 33152 16579 33152 16571 33152 16571 33153 16579 33153 16583 33153 16571 33154 16583 33154 16580 33154 16580 33155 16583 33155 16584 33155 16580 33156 16584 33156 16581 33156 16581 33157 16584 33157 16585 33157 16581 33158 16585 33158 16574 33158 16574 33159 16585 33159 16582 33159 16574 33160 16582 33160 16575 33160 16575 33161 16582 33161 16587 33161 11791 33162 15906 33162 16579 33162 16579 33163 15906 33163 15907 33163 16579 33164 15907 33164 16583 33164 16583 33165 15907 33165 16126 33165 16583 33166 16126 33166 16584 33166 16584 33167 16126 33167 16125 33167 16584 33168 16125 33168 16585 33168 16585 33169 16125 33169 15909 33169 16585 33170 15909 33170 16582 33170 16582 33171 15909 33171 16586 33171 16582 33172 16586 33172 16587 33172 16587 33173 16586 33173 15943 33173 16588 33174 16604 33174 16664 33174 16664 33175 16604 33175 16605 33175 16664 33176 16605 33176 16589 33176 16589 33177 16605 33177 16590 33177 16589 33178 16590 33178 16591 33178 16591 33179 16590 33179 16593 33179 16591 33180 16593 33180 16592 33180 16592 33181 16593 33181 16594 33181 16592 33182 16594 33182 11736 33182 11736 33183 16594 33183 11785 33183 11736 33184 11785 33184 16595 33184 16595 33185 11785 33185 11786 33185 16595 33186 11786 33186 16596 33186 16596 33187 11786 33187 11788 33187 16596 33188 11788 33188 16672 33188 16672 33189 11788 33189 16597 33189 16672 33190 16597 33190 16671 33190 16671 33191 16597 33191 16600 33191 16671 33192 16600 33192 16670 33192 16670 33193 16600 33193 16598 33193 16670 33194 16598 33194 16668 33194 16668 33195 16598 33195 16601 33195 16668 33196 16601 33196 16665 33196 16665 33197 16601 33197 16599 33197 16665 33198 16599 33198 16588 33198 16588 33199 16599 33199 16604 33199 11788 33200 16606 33200 16597 33200 16597 33201 16606 33201 16609 33201 16597 33202 16609 33202 16600 33202 16600 33203 16609 33203 16610 33203 16600 33204 16610 33204 16598 33204 16598 33205 16610 33205 16602 33205 16598 33206 16602 33206 16601 33206 16601 33207 16602 33207 16613 33207 16601 33208 16613 33208 16599 33208 16599 33209 16613 33209 16603 33209 16599 33210 16603 33210 16604 33210 16604 33211 16603 33211 16614 33211 16604 33212 16614 33212 16605 33212 16605 33213 16614 33213 16615 33213 16606 33214 16607 33214 16609 33214 16609 33215 16607 33215 16608 33215 16609 33216 16608 33216 16610 33216 16610 33217 16608 33217 16611 33217 16610 33218 16611 33218 16602 33218 16602 33219 16611 33219 16612 33219 16602 33220 16612 33220 16613 33220 16613 33221 16612 33221 15896 33221 16613 33222 15896 33222 16603 33222 16603 33223 15896 33223 15895 33223 16603 33224 15895 33224 16614 33224 16614 33225 15895 33225 16616 33225 16614 33226 16616 33226 16615 33226 16615 33227 16616 33227 11777 33227 16551 33228 11769 33228 16549 33228 16549 33229 11769 33229 16624 33229 16549 33230 16624 33230 16617 33230 16624 33231 16618 33231 16617 33231 16617 33232 16618 33232 16619 33232 16617 33233 16619 33233 16548 33233 16548 33234 16619 33234 16620 33234 16620 33235 16627 33235 16548 33235 16548 33236 16627 33236 16621 33236 16548 33237 16621 33237 16547 33237 11765 33238 11776 33238 16622 33238 16622 33239 11776 33239 16546 33239 16622 33240 16546 33240 16623 33240 16623 33241 16546 33241 16547 33241 16623 33242 16547 33242 16630 33242 16630 33243 16547 33243 16621 33243 11769 33244 11764 33244 16625 33244 11769 33245 16625 33245 16624 33245 16624 33246 16625 33246 16626 33246 16624 33247 16626 33247 16618 33247 16618 33248 16626 33248 16619 33248 16619 33249 16626 33249 16628 33249 16619 33250 16628 33250 16620 33250 16620 33251 16628 33251 16627 33251 16627 33252 16628 33252 16629 33252 16627 33253 16629 33253 16621 33253 16621 33254 16629 33254 16630 33254 16630 33255 16629 33255 16637 33255 16630 33256 16637 33256 16623 33256 16623 33257 16637 33257 16640 33257 16623 33258 16640 33258 16622 33258 16622 33259 16640 33259 16631 33259 16622 33260 16631 33260 11765 33260 11764 33261 16632 33261 16625 33261 16625 33262 16632 33262 16633 33262 16625 33263 16633 33263 16626 33263 16626 33264 16633 33264 16634 33264 16626 33265 16634 33265 16628 33265 16628 33266 16634 33266 16635 33266 16628 33267 16635 33267 16629 33267 16629 33268 16635 33268 16636 33268 16629 33269 16636 33269 16637 33269 16637 33270 16636 33270 16638 33270 16637 33271 16638 33271 16640 33271 16640 33272 16638 33272 16639 33272 16640 33273 16639 33273 16631 33273 16631 33274 16639 33274 13764 33274 11754 33275 11753 33275 16573 33275 16573 33276 11753 33276 16648 33276 16573 33277 16648 33277 16572 33277 16648 33278 16649 33278 16572 33278 16572 33279 16649 33279 16642 33279 16572 33280 16642 33280 16641 33280 16641 33281 16642 33281 16643 33281 16643 33282 16652 33282 16641 33282 16641 33283 16652 33283 16653 33283 16641 33284 16653 33284 16646 33284 16644 33285 16569 33285 16658 33285 16658 33286 16569 33286 16645 33286 16658 33287 16645 33287 16656 33287 16656 33288 16645 33288 16646 33288 16656 33289 16646 33289 16647 33289 16647 33290 16646 33290 16653 33290 11753 33291 16660 33291 16661 33291 11753 33292 16661 33292 16648 33292 16648 33293 16661 33293 16650 33293 16648 33294 16650 33294 16649 33294 16649 33295 16650 33295 16642 33295 16642 33296 16650 33296 16651 33296 16642 33297 16651 33297 16643 33297 16643 33298 16651 33298 16652 33298 16652 33299 16651 33299 16654 33299 16652 33300 16654 33300 16653 33300 16653 33301 16654 33301 16647 33301 16647 33302 16654 33302 16655 33302 16647 33303 16655 33303 16656 33303 16656 33304 16655 33304 16657 33304 16656 33305 16657 33305 16658 33305 16658 33306 16657 33306 16659 33306 16658 33307 16659 33307 16644 33307 16660 33308 13771 33308 16661 33308 16661 33309 13771 33309 13769 33309 16661 33310 13769 33310 16650 33310 16650 33311 13769 33311 13782 33311 16650 33312 13782 33312 16651 33312 16651 33313 13782 33313 13781 33313 16651 33314 13781 33314 16654 33314 16654 33315 13781 33315 13780 33315 16654 33316 13780 33316 16655 33316 16655 33317 13780 33317 16662 33317 16655 33318 16662 33318 16657 33318 16657 33319 16662 33319 13777 33319 16657 33320 13777 33320 16659 33320 16659 33321 13777 33321 16663 33321 16588 33322 16664 33322 11734 33322 11734 33323 16673 33323 16588 33323 16588 33324 16673 33324 16674 33324 16588 33325 16674 33325 16665 33325 16674 33326 16676 33326 16665 33326 16665 33327 16676 33327 16666 33327 16665 33328 16666 33328 16668 33328 16666 33329 16667 33329 16668 33329 16668 33330 16667 33330 16669 33330 16668 33331 16669 33331 16670 33331 16670 33332 16669 33332 16679 33332 16670 33333 16679 33333 16671 33333 16679 33334 16680 33334 16671 33334 16671 33335 16680 33335 16682 33335 16671 33336 16682 33336 16672 33336 11738 33337 16596 33337 16684 33337 16684 33338 16596 33338 16672 33338 16684 33339 16672 33339 16683 33339 16683 33340 16672 33340 16682 33340 11734 33341 11727 33341 16673 33341 16673 33342 11727 33342 16675 33342 16673 33343 16675 33343 16674 33343 16674 33344 16675 33344 16676 33344 16676 33345 16675 33345 16677 33345 16676 33346 16677 33346 16666 33346 16666 33347 16677 33347 16667 33347 16667 33348 16677 33348 16678 33348 16667 33349 16678 33349 16669 33349 16669 33350 16678 33350 16679 33350 16679 33351 16678 33351 16689 33351 16679 33352 16689 33352 16680 33352 16680 33353 16689 33353 16682 33353 16682 33354 16689 33354 16681 33354 16682 33355 16681 33355 16683 33355 16683 33356 16681 33356 16684 33356 16684 33357 16681 33357 16685 33357 16684 33358 16685 33358 11738 33358 11727 33359 16686 33359 16675 33359 16675 33360 16686 33360 13786 33360 16675 33361 13786 33361 16677 33361 16677 33362 13786 33362 16687 33362 16677 33363 16687 33363 16678 33363 16678 33364 16687 33364 16688 33364 16678 33365 16688 33365 16689 33365 16689 33366 16688 33366 13788 33366 16689 33367 13788 33367 16681 33367 16681 33368 13788 33368 16690 33368 16681 33369 16690 33369 16685 33369 16685 33370 16690 33370 11720 33370 11716 33371 11715 33371 16691 33371 16691 33372 11715 33372 16692 33372 16691 33373 16692 33373 16693 33373 16693 33374 16692 33374 16694 33374 16694 33375 16692 33375 16696 33375 16694 33376 16696 33376 16695 33376 16695 33377 16696 33377 16697 33377 16697 33378 16696 33378 16699 33378 16697 33379 16699 33379 16698 33379 16698 33380 16699 33380 16759 33380 16759 33381 16699 33381 16704 33381 16759 33382 16704 33382 16761 33382 16761 33383 16704 33383 16765 33383 16765 33384 16704 33384 16701 33384 16765 33385 16701 33385 16700 33385 16700 33386 16701 33386 16763 33386 16763 33387 16701 33387 11707 33387 16763 33388 11707 33388 16762 33388 11715 33389 13802 33389 16692 33389 16692 33390 13802 33390 16702 33390 16692 33391 16702 33391 16696 33391 16696 33392 16702 33392 13801 33392 16696 33393 13801 33393 16699 33393 16699 33394 13801 33394 16703 33394 16699 33395 16703 33395 16704 33395 16704 33396 16703 33396 16705 33396 16704 33397 16705 33397 16701 33397 16701 33398 16705 33398 16706 33398 16701 33399 16706 33399 11707 33399 11707 33400 16706 33400 13798 33400 16766 33401 11686 33401 16768 33401 16768 33402 11686 33402 16717 33402 16768 33403 16717 33403 16770 33403 16770 33404 16717 33404 16707 33404 16707 33405 16717 33405 16708 33405 16707 33406 16708 33406 16771 33406 16771 33407 16708 33407 16709 33407 16709 33408 16708 33408 16711 33408 16709 33409 16711 33409 16772 33409 16772 33410 16711 33410 16710 33410 16710 33411 16711 33411 16714 33411 16710 33412 16714 33412 16712 33412 16712 33413 16714 33413 16713 33413 16713 33414 16714 33414 16720 33414 16713 33415 16720 33415 16715 33415 16715 33416 16720 33416 16716 33416 16716 33417 16720 33417 11688 33417 16716 33418 11688 33418 16774 33418 11686 33419 13816 33419 16717 33419 16717 33420 13816 33420 16718 33420 16717 33421 16718 33421 16708 33421 16708 33422 16718 33422 16719 33422 16708 33423 16719 33423 16711 33423 16711 33424 16719 33424 13815 33424 16711 33425 13815 33425 16714 33425 16714 33426 13815 33426 13813 33426 16714 33427 13813 33427 16720 33427 16720 33428 13813 33428 13811 33428 16720 33429 13811 33429 11688 33429 11688 33430 13811 33430 11682 33430 16776 33431 16721 33431 16722 33431 16722 33432 16721 33432 16723 33432 16722 33433 16723 33433 16777 33433 16777 33434 16723 33434 16779 33434 16779 33435 16723 33435 16733 33435 16779 33436 16733 33436 16724 33436 16724 33437 16733 33437 16725 33437 16725 33438 16733 33438 16727 33438 16725 33439 16727 33439 16726 33439 16726 33440 16727 33440 16728 33440 16728 33441 16727 33441 16730 33441 16728 33442 16730 33442 16729 33442 16729 33443 16730 33443 16731 33443 16731 33444 16730 33444 16736 33444 16731 33445 16736 33445 16783 33445 16783 33446 16736 33446 16732 33446 16732 33447 16736 33447 16737 33447 16732 33448 16737 33448 11672 33448 16721 33449 11671 33449 16723 33449 16723 33450 11671 33450 16734 33450 16723 33451 16734 33451 16733 33451 16733 33452 16734 33452 13822 33452 16733 33453 13822 33453 16727 33453 16727 33454 13822 33454 16735 33454 16727 33455 16735 33455 16730 33455 16730 33456 16735 33456 13820 33456 16730 33457 13820 33457 16736 33457 16736 33458 13820 33458 13819 33458 16736 33459 13819 33459 16737 33459 16737 33460 13819 33460 13818 33460 11665 33461 16746 33461 16748 33461 11665 33462 16748 33462 16738 33462 16738 33463 16748 33463 16739 33463 16738 33464 16739 33464 16785 33464 16785 33465 16739 33465 16740 33465 16740 33466 16739 33466 16750 33466 16740 33467 16750 33467 16786 33467 16786 33468 16750 33468 16741 33468 16741 33469 16750 33469 16742 33469 16741 33470 16742 33470 16787 33470 16787 33471 16742 33471 16743 33471 16743 33472 16742 33472 16744 33472 16743 33473 16744 33473 16790 33473 16790 33474 16744 33474 16753 33474 16790 33475 16753 33475 16745 33475 16745 33476 16753 33476 16754 33476 16745 33477 16754 33477 11632 33477 16746 33478 13830 33478 16748 33478 16748 33479 13830 33479 16747 33479 16748 33480 16747 33480 16739 33480 16739 33481 16747 33481 16749 33481 16739 33482 16749 33482 16750 33482 16750 33483 16749 33483 16751 33483 16750 33484 16751 33484 16742 33484 16742 33485 16751 33485 13838 33485 16742 33486 13838 33486 16744 33486 16744 33487 13838 33487 13837 33487 16744 33488 13837 33488 16753 33488 16753 33489 13837 33489 16752 33489 16753 33490 16752 33490 16754 33490 16754 33491 16752 33491 13834 33491 16755 33492 16026 33492 11716 33492 11716 33493 16691 33493 16755 33493 16755 33494 16691 33494 16693 33494 16755 33495 16693 33495 16756 33495 16693 33496 16694 33496 16756 33496 16756 33497 16694 33497 16695 33497 16756 33498 16695 33498 16757 33498 16757 33499 16695 33499 16697 33499 16757 33500 16697 33500 16758 33500 16697 33501 16698 33501 16758 33501 16758 33502 16698 33502 16759 33502 16758 33503 16759 33503 16760 33503 16759 33504 16761 33504 16760 33504 16760 33505 16761 33505 16765 33505 16760 33506 16765 33506 16019 33506 16762 33507 16764 33507 16763 33507 16763 33508 16764 33508 16019 33508 16763 33509 16019 33509 16700 33509 16700 33510 16019 33510 16765 33510 16767 33511 15782 33511 16766 33511 16766 33512 16768 33512 16767 33512 16767 33513 16768 33513 16770 33513 16767 33514 16770 33514 16769 33514 16770 33515 16707 33515 16769 33515 16769 33516 16707 33516 16771 33516 16769 33517 16771 33517 15783 33517 15783 33518 16771 33518 16709 33518 15783 33519 16709 33519 15780 33519 16709 33520 16772 33520 15780 33520 15780 33521 16772 33521 16710 33521 15780 33522 16710 33522 16773 33522 16710 33523 16712 33523 16773 33523 16773 33524 16712 33524 16713 33524 16773 33525 16713 33525 16010 33525 16774 33526 11642 33526 16716 33526 16716 33527 11642 33527 16010 33527 16716 33528 16010 33528 16715 33528 16715 33529 16010 33529 16713 33529 15793 33530 16775 33530 16776 33530 16776 33531 16722 33531 15793 33531 15793 33532 16722 33532 16777 33532 15793 33533 16777 33533 16778 33533 16777 33534 16779 33534 16778 33534 16778 33535 16779 33535 16724 33535 16778 33536 16724 33536 16780 33536 16724 33537 16725 33537 16780 33537 16780 33538 16725 33538 16726 33538 16780 33539 16726 33539 15795 33539 15795 33540 16726 33540 16728 33540 15795 33541 16728 33541 16781 33541 16728 33542 16729 33542 16781 33542 16781 33543 16729 33543 16731 33543 16781 33544 16731 33544 16782 33544 11672 33545 15791 33545 16732 33545 16732 33546 15791 33546 16782 33546 16732 33547 16782 33547 16783 33547 16783 33548 16782 33548 16731 33548 15767 33549 11665 33549 16784 33549 16784 33550 11665 33550 16738 33550 16784 33551 16738 33551 15775 33551 16738 33552 16785 33552 15775 33552 15775 33553 16785 33553 16740 33553 15775 33554 16740 33554 15774 33554 15774 33555 16740 33555 16786 33555 16786 33556 16741 33556 15774 33556 15774 33557 16741 33557 16787 33557 15774 33558 16787 33558 16791 33558 11632 33559 16788 33559 16745 33559 16745 33560 16788 33560 16789 33560 16745 33561 16789 33561 16790 33561 16790 33562 16789 33562 16791 33562 16790 33563 16791 33563 16743 33563 16743 33564 16791 33564 16787 33564 16795 33565 16792 33565 16806 33565 16806 33566 16792 33566 16804 33566 16804 33567 16792 33567 16793 33567 16804 33568 16793 33568 11626 33568 11626 33569 16793 33569 11584 33569 11626 33570 11584 33570 11624 33570 11624 33571 11584 33571 16794 33571 11624 33572 16794 33572 11623 33572 11623 33573 16794 33573 11580 33573 11623 33574 11580 33574 16802 33574 16806 33575 16808 33575 16795 33575 16795 33576 16808 33576 16797 33576 16795 33577 16797 33577 16796 33577 16796 33578 16797 33578 16811 33578 16796 33579 16811 33579 16798 33579 16798 33580 16811 33580 16799 33580 16798 33581 16799 33581 16874 33581 16874 33582 16799 33582 11618 33582 16874 33583 11618 33583 11577 33583 11577 33584 11618 33584 16800 33584 11577 33585 16800 33585 16801 33585 16801 33586 16800 33586 11621 33586 16801 33587 11621 33587 11579 33587 11579 33588 11621 33588 16802 33588 11579 33589 16802 33589 16803 33589 16803 33590 16802 33590 11580 33590 11626 33591 11617 33591 16804 33591 16804 33592 11617 33592 16805 33592 16804 33593 16805 33593 16806 33593 16806 33594 16805 33594 16807 33594 16806 33595 16807 33595 16808 33595 16808 33596 16807 33596 16809 33596 16808 33597 16809 33597 16797 33597 16797 33598 16809 33598 16814 33598 16797 33599 16814 33599 16811 33599 16811 33600 16814 33600 16810 33600 16811 33601 16810 33601 16799 33601 16799 33602 16810 33602 16812 33602 16799 33603 16812 33603 11618 33603 11618 33604 16812 33604 11619 33604 11617 33605 15878 33605 16805 33605 16805 33606 15878 33606 15877 33606 16805 33607 15877 33607 16807 33607 16807 33608 15877 33608 16813 33608 16807 33609 16813 33609 16809 33609 16809 33610 16813 33610 15874 33610 16809 33611 15874 33611 16814 33611 16814 33612 15874 33612 15871 33612 16814 33613 15871 33613 16810 33613 16810 33614 15871 33614 16815 33614 16810 33615 16815 33615 16812 33615 16812 33616 16815 33616 16816 33616 16812 33617 16816 33617 11619 33617 11619 33618 16816 33618 15869 33618 16824 33619 16817 33619 16835 33619 16835 33620 16817 33620 16819 33620 16819 33621 16817 33621 16818 33621 16819 33622 16818 33622 16833 33622 16833 33623 16818 33623 16820 33623 16833 33624 16820 33624 11611 33624 11611 33625 16820 33625 16821 33625 11611 33626 16821 33626 16822 33626 16822 33627 16821 33627 16823 33627 16822 33628 16823 33628 16832 33628 16835 33629 16836 33629 16824 33629 16824 33630 16836 33630 16825 33630 16824 33631 16825 33631 16889 33631 16889 33632 16825 33632 16826 33632 16889 33633 16826 33633 16827 33633 16827 33634 16826 33634 16839 33634 16827 33635 16839 33635 16828 33635 16828 33636 16839 33636 16840 33636 16828 33637 16840 33637 11562 33637 11562 33638 16840 33638 16829 33638 11562 33639 16829 33639 11560 33639 11560 33640 16829 33640 16830 33640 11560 33641 16830 33641 11556 33641 11556 33642 16830 33642 16832 33642 11556 33643 16832 33643 16831 33643 16831 33644 16832 33644 16823 33644 16833 33645 16834 33645 16819 33645 16819 33646 16834 33646 16841 33646 16819 33647 16841 33647 16835 33647 16835 33648 16841 33648 16844 33648 16835 33649 16844 33649 16836 33649 16836 33650 16844 33650 16837 33650 16836 33651 16837 33651 16825 33651 16825 33652 16837 33652 16838 33652 16825 33653 16838 33653 16826 33653 16826 33654 16838 33654 16846 33654 16826 33655 16846 33655 16839 33655 16839 33656 16846 33656 16847 33656 16839 33657 16847 33657 16840 33657 16840 33658 16847 33658 11607 33658 16834 33659 16842 33659 16841 33659 16841 33660 16842 33660 16843 33660 16841 33661 16843 33661 16844 33661 16844 33662 16843 33662 15786 33662 16844 33663 15786 33663 16837 33663 16837 33664 15786 33664 16845 33664 16837 33665 16845 33665 16838 33665 16838 33666 16845 33666 15776 33666 16838 33667 15776 33667 16846 33667 16846 33668 15776 33668 16848 33668 16846 33669 16848 33669 16847 33669 16847 33670 16848 33670 15789 33670 16847 33671 15789 33671 11607 33671 11607 33672 15789 33672 11600 33672 11595 33673 16849 33673 11533 33673 11533 33674 16849 33674 16850 33674 11533 33675 16850 33675 11537 33675 11537 33676 16850 33676 11598 33676 11537 33677 11598 33677 16851 33677 16851 33678 11598 33678 16852 33678 16851 33679 16852 33679 16904 33679 16904 33680 16852 33680 16853 33680 16904 33681 16853 33681 16854 33681 16854 33682 16853 33682 16855 33682 16854 33683 16855 33683 16907 33683 16907 33684 16855 33684 16856 33684 16907 33685 16856 33685 16908 33685 16908 33686 16856 33686 16863 33686 16908 33687 16863 33687 16911 33687 16911 33688 16863 33688 16864 33688 16911 33689 16864 33689 16857 33689 16857 33690 16864 33690 16866 33690 16857 33691 16866 33691 16858 33691 16858 33692 16866 33692 16867 33692 16858 33693 16867 33693 16859 33693 16859 33694 16867 33694 11594 33694 16859 33695 11594 33695 16860 33695 16860 33696 11594 33696 11595 33696 16860 33697 11595 33697 11533 33697 16853 33698 11592 33698 16855 33698 16855 33699 11592 33699 16861 33699 16855 33700 16861 33700 16856 33700 16856 33701 16861 33701 16862 33701 16856 33702 16862 33702 16863 33702 16863 33703 16862 33703 16870 33703 16863 33704 16870 33704 16864 33704 16864 33705 16870 33705 16872 33705 16864 33706 16872 33706 16866 33706 16866 33707 16872 33707 16865 33707 16866 33708 16865 33708 16867 33708 16867 33709 16865 33709 11593 33709 11592 33710 16868 33710 16861 33710 16861 33711 16868 33711 15770 33711 16861 33712 15770 33712 16862 33712 16862 33713 15770 33713 16869 33713 16862 33714 16869 33714 16870 33714 16870 33715 16869 33715 16871 33715 16870 33716 16871 33716 16872 33716 16872 33717 16871 33717 15772 33717 16872 33718 15772 33718 16865 33718 16865 33719 15772 33719 15992 33719 16865 33720 15992 33720 11593 33720 11593 33721 15992 33721 11585 33721 11583 33722 11584 33722 16881 33722 16881 33723 11584 33723 16793 33723 16881 33724 16793 33724 16880 33724 16880 33725 16793 33725 16792 33725 16880 33726 16792 33726 16878 33726 16878 33727 16792 33727 16795 33727 16878 33728 16795 33728 16873 33728 16873 33729 16795 33729 16796 33729 16873 33730 16796 33730 16876 33730 16876 33731 16796 33731 16798 33731 16876 33732 16798 33732 11576 33732 11576 33733 16798 33733 16874 33733 11576 33734 16875 33734 16876 33734 16876 33735 16875 33735 16883 33735 16876 33736 16883 33736 16873 33736 16873 33737 16883 33737 16877 33737 16873 33738 16877 33738 16878 33738 16878 33739 16877 33739 16879 33739 16878 33740 16879 33740 16880 33740 16880 33741 16879 33741 16886 33741 16880 33742 16886 33742 16881 33742 16881 33743 16886 33743 16887 33743 16881 33744 16887 33744 11583 33744 11583 33745 16887 33745 16882 33745 16875 33746 11570 33746 16883 33746 16883 33747 11570 33747 13852 33747 16883 33748 13852 33748 16877 33748 16877 33749 13852 33749 16884 33749 16877 33750 16884 33750 16879 33750 16879 33751 16884 33751 16885 33751 16879 33752 16885 33752 16886 33752 16886 33753 16885 33753 13848 33753 16886 33754 13848 33754 16887 33754 16887 33755 13848 33755 13846 33755 16887 33756 13846 33756 16882 33756 16882 33757 13846 33757 13845 33757 11552 33758 16820 33758 16895 33758 16895 33759 16820 33759 16818 33759 16895 33760 16818 33760 16894 33760 16894 33761 16818 33761 16817 33761 16894 33762 16817 33762 16893 33762 16893 33763 16817 33763 16824 33763 16893 33764 16824 33764 16888 33764 16888 33765 16824 33765 16889 33765 16888 33766 16889 33766 16891 33766 16891 33767 16889 33767 16827 33767 16891 33768 16827 33768 11551 33768 11551 33769 16827 33769 16828 33769 11551 33770 16890 33770 16891 33770 16891 33771 16890 33771 16899 33771 16891 33772 16899 33772 16888 33772 16888 33773 16899 33773 16892 33773 16888 33774 16892 33774 16893 33774 16893 33775 16892 33775 16900 33775 16893 33776 16900 33776 16894 33776 16894 33777 16900 33777 16896 33777 16894 33778 16896 33778 16895 33778 16895 33779 16896 33779 16897 33779 16895 33780 16897 33780 11552 33780 11552 33781 16897 33781 16898 33781 16890 33782 11544 33782 16899 33782 16899 33783 11544 33783 13862 33783 16899 33784 13862 33784 16892 33784 16892 33785 13862 33785 13860 33785 16892 33786 13860 33786 16900 33786 16900 33787 13860 33787 16901 33787 16900 33788 16901 33788 16896 33788 16896 33789 16901 33789 16902 33789 16896 33790 16902 33790 16897 33790 16897 33791 16902 33791 16903 33791 16897 33792 16903 33792 16898 33792 16898 33793 16903 33793 11539 33793 11538 33794 16904 33794 16905 33794 16905 33795 16904 33795 16854 33795 16905 33796 16854 33796 16906 33796 16906 33797 16854 33797 16907 33797 16906 33798 16907 33798 16914 33798 16914 33799 16907 33799 16908 33799 16914 33800 16908 33800 16909 33800 16909 33801 16908 33801 16911 33801 16909 33802 16911 33802 16910 33802 16910 33803 16911 33803 16857 33803 16910 33804 16857 33804 11531 33804 11531 33805 16857 33805 16858 33805 11531 33806 16912 33806 16910 33806 16910 33807 16912 33807 16917 33807 16910 33808 16917 33808 16909 33808 16909 33809 16917 33809 16913 33809 16909 33810 16913 33810 16914 33810 16914 33811 16913 33811 16919 33811 16914 33812 16919 33812 16906 33812 16906 33813 16919 33813 16920 33813 16906 33814 16920 33814 16905 33814 16905 33815 16920 33815 16915 33815 16905 33816 16915 33816 11538 33816 11538 33817 16915 33817 11523 33817 16912 33818 16916 33818 16917 33818 16917 33819 16916 33819 16918 33819 16917 33820 16918 33820 16913 33820 16913 33821 16918 33821 13871 33821 16913 33822 13871 33822 16919 33822 16919 33823 13871 33823 16921 33823 16919 33824 16921 33824 16920 33824 16920 33825 16921 33825 16922 33825 16920 33826 16922 33826 16915 33826 16915 33827 16922 33827 16923 33827 16915 33828 16923 33828 11523 33828 11523 33829 16923 33829 16924 33829 16978 33830 16926 33830 16925 33830 16925 33831 16926 33831 16927 33831 16925 33832 16927 33832 16928 33832 16928 33833 16927 33833 16980 33833 16980 33834 16927 33834 16934 33834 16980 33835 16934 33835 16981 33835 16981 33836 16934 33836 16982 33836 16982 33837 16934 33837 16936 33837 16982 33838 16936 33838 16929 33838 16929 33839 16936 33839 16983 33839 16983 33840 16936 33840 16931 33840 16983 33841 16931 33841 16930 33841 16930 33842 16931 33842 16985 33842 16985 33843 16931 33843 16932 33843 16985 33844 16932 33844 16987 33844 16987 33845 16932 33845 16986 33845 16986 33846 16932 33846 16938 33846 16986 33847 16938 33847 11514 33847 16926 33848 16933 33848 16927 33848 16927 33849 16933 33849 13884 33849 16927 33850 13884 33850 16934 33850 16934 33851 13884 33851 16935 33851 16934 33852 16935 33852 16936 33852 16936 33853 16935 33853 13883 33853 16936 33854 13883 33854 16931 33854 16931 33855 13883 33855 16937 33855 16931 33856 16937 33856 16932 33856 16932 33857 16937 33857 13881 33857 16932 33858 13881 33858 16938 33858 16938 33859 13881 33859 11512 33859 11504 33860 11503 33860 16945 33860 11504 33861 16945 33861 16988 33861 16988 33862 16945 33862 16947 33862 16988 33863 16947 33863 16989 33863 16989 33864 16947 33864 16939 33864 16939 33865 16947 33865 16948 33865 16939 33866 16948 33866 16940 33866 16940 33867 16948 33867 16941 33867 16941 33868 16948 33868 16950 33868 16941 33869 16950 33869 16991 33869 16991 33870 16950 33870 16994 33870 16994 33871 16950 33871 16943 33871 16994 33872 16943 33872 16942 33872 16942 33873 16943 33873 16944 33873 16942 33874 16944 33874 16992 33874 16992 33875 16944 33875 11497 33875 16992 33876 11497 33876 11496 33876 11503 33877 11495 33877 16945 33877 16945 33878 11495 33878 16946 33878 16945 33879 16946 33879 16947 33879 16947 33880 16946 33880 13887 33880 16947 33881 13887 33881 16948 33881 16948 33882 13887 33882 16949 33882 16948 33883 16949 33883 16950 33883 16950 33884 16949 33884 13897 33884 16950 33885 13897 33885 16943 33885 16943 33886 13897 33886 16951 33886 16943 33887 16951 33887 16944 33887 16944 33888 16951 33888 16952 33888 16944 33889 16952 33889 11497 33889 11497 33890 16952 33890 13894 33890 16953 33891 11490 33891 16995 33891 16995 33892 11490 33892 16954 33892 16995 33893 16954 33893 16997 33893 16997 33894 16954 33894 16955 33894 16955 33895 16954 33895 16956 33895 16955 33896 16956 33896 16957 33896 16957 33897 16956 33897 17000 33897 17000 33898 16956 33898 16959 33898 17000 33899 16959 33899 16958 33899 16958 33900 16959 33900 17002 33900 17002 33901 16959 33901 16965 33901 17002 33902 16965 33902 17003 33902 17003 33903 16965 33903 16960 33903 16960 33904 16965 33904 16967 33904 16960 33905 16967 33905 16961 33905 16961 33906 16967 33906 17005 33906 17005 33907 16967 33907 11471 33907 17005 33908 11471 33908 11478 33908 11490 33909 16962 33909 16954 33909 16954 33910 16962 33910 16963 33910 16954 33911 16963 33911 16956 33911 16956 33912 16963 33912 13905 33912 16956 33913 13905 33913 16959 33913 16959 33914 13905 33914 16964 33914 16959 33915 16964 33915 16965 33915 16965 33916 16964 33916 16966 33916 16965 33917 16966 33917 16967 33917 16967 33918 16966 33918 13903 33918 16967 33919 13903 33919 11471 33919 11471 33920 13903 33920 13900 33920 11427 33921 11461 33921 17013 33921 17013 33922 11461 33922 16971 33922 17013 33923 16971 33923 16968 33923 16968 33924 16971 33924 16969 33924 16968 33925 16969 33925 17012 33925 17012 33926 16969 33926 16972 33926 17012 33927 16972 33927 17010 33927 17010 33928 16972 33928 16970 33928 17010 33929 16970 33929 17008 33929 17008 33930 16970 33930 16975 33930 17008 33931 16975 33931 17006 33931 17006 33932 16975 33932 11453 33932 11461 33933 13922 33933 16971 33933 16971 33934 13922 33934 13920 33934 16971 33935 13920 33935 16969 33935 16969 33936 13920 33936 16973 33936 16969 33937 16973 33937 16972 33937 16972 33938 16973 33938 16974 33938 16972 33939 16974 33939 16970 33939 16970 33940 16974 33940 16976 33940 16970 33941 16976 33941 16975 33941 16975 33942 16976 33942 13917 33942 16975 33943 13917 33943 11453 33943 11453 33944 13917 33944 16977 33944 15852 33945 15851 33945 16978 33945 16978 33946 16925 33946 15852 33946 15852 33947 16925 33947 16928 33947 15852 33948 16928 33948 16979 33948 16928 33949 16980 33949 16979 33949 16979 33950 16980 33950 16981 33950 16979 33951 16981 33951 15844 33951 16981 33952 16982 33952 15844 33952 15844 33953 16982 33953 16929 33953 15844 33954 16929 33954 15854 33954 15854 33955 16929 33955 16983 33955 15854 33956 16983 33956 16984 33956 16983 33957 16930 33957 16984 33957 16984 33958 16930 33958 16985 33958 16984 33959 16985 33959 15845 33959 11514 33960 11452 33960 16986 33960 16986 33961 11452 33961 15845 33961 16986 33962 15845 33962 16987 33962 16987 33963 15845 33963 16985 33963 15967 33964 11504 33964 15965 33964 15965 33965 11504 33965 16988 33965 15965 33966 16988 33966 15966 33966 16988 33967 16989 33967 15966 33967 15966 33968 16989 33968 16939 33968 15966 33969 16939 33969 16990 33969 16990 33970 16939 33970 16940 33970 16940 33971 16941 33971 16990 33971 16990 33972 16941 33972 16991 33972 16990 33973 16991 33973 16993 33973 11496 33974 15969 33974 16992 33974 16992 33975 15969 33975 15968 33975 16992 33976 15968 33976 16942 33976 16942 33977 15968 33977 16993 33977 16942 33978 16993 33978 16994 33978 16994 33979 16993 33979 16991 33979 16996 33980 15925 33980 16953 33980 16953 33981 16995 33981 16996 33981 16996 33982 16995 33982 16997 33982 16996 33983 16997 33983 16998 33983 16997 33984 16955 33984 16998 33984 16998 33985 16955 33985 16957 33985 16998 33986 16957 33986 16999 33986 16999 33987 16957 33987 17000 33987 16999 33988 17000 33988 17001 33988 17000 33989 16958 33989 17001 33989 17001 33990 16958 33990 17002 33990 17001 33991 17002 33991 15765 33991 17002 33992 17003 33992 15765 33992 15765 33993 17003 33993 16960 33993 15765 33994 16960 33994 17004 33994 11478 33995 15935 33995 17005 33995 17005 33996 15935 33996 17004 33996 17005 33997 17004 33997 16961 33997 16961 33998 17004 33998 16960 33998 17006 33999 15885 33999 17008 33999 17008 34000 15885 34000 17007 34000 17008 34001 17007 34001 17010 34001 17010 34002 17007 34002 17009 34002 17010 34003 17009 34003 17012 34003 17012 34004 17009 34004 17011 34004 17012 34005 17011 34005 16968 34005 16968 34006 17011 34006 15884 34006 16968 34007 15884 34007 17013 34007 17013 34008 15884 34008 15883 34008 17013 34009 15883 34009 11427 34009 11427 34010 15883 34010 11428 34010 17022 34011 11417 34011 11383 34011 11383 34012 11417 34012 17014 34012 11383 34013 17014 34013 17015 34013 17015 34014 17014 34014 11419 34014 17015 34015 11419 34015 17016 34015 17016 34016 11419 34016 17018 34016 17016 34017 17018 34017 17017 34017 17017 34018 17018 34018 17019 34018 17017 34019 17019 34019 17096 34019 17096 34020 17019 34020 11421 34020 17096 34021 11421 34021 17097 34021 17097 34022 11421 34022 17024 34022 17097 34023 17024 34023 17099 34023 17099 34024 17024 34024 17026 34024 17099 34025 17026 34025 17094 34025 17094 34026 17026 34026 17027 34026 17094 34027 17027 34027 17090 34027 17090 34028 17027 34028 17028 34028 17090 34029 17028 34029 17089 34029 17089 34030 17028 34030 17021 34030 17089 34031 17021 34031 17020 34031 17020 34032 17021 34032 17023 34032 17020 34033 17023 34033 17022 34033 17022 34034 17023 34034 11417 34034 11421 34035 17025 34035 17024 34035 17024 34036 17025 34036 17031 34036 17024 34037 17031 34037 17026 34037 17026 34038 17031 34038 17033 34038 17026 34039 17033 34039 17027 34039 17027 34040 17033 34040 17034 34040 17027 34041 17034 34041 17028 34041 17028 34042 17034 34042 17035 34042 17028 34043 17035 34043 17021 34043 17021 34044 17035 34044 17037 34044 17021 34045 17037 34045 17023 34045 17023 34046 17037 34046 17029 34046 17025 34047 17030 34047 17031 34047 17031 34048 17030 34048 17032 34048 17031 34049 17032 34049 17033 34049 17033 34050 17032 34050 15849 34050 17033 34051 15849 34051 17034 34051 17034 34052 15849 34052 15848 34052 17034 34053 15848 34053 17035 34053 17035 34054 15848 34054 17036 34054 17035 34055 17036 34055 17037 34055 17037 34056 17036 34056 15847 34056 17037 34057 15847 34057 17029 34057 17029 34058 15847 34058 15846 34058 17117 34059 17058 34059 11368 34059 11368 34060 17058 34060 17038 34060 11368 34061 17038 34061 11370 34061 11370 34062 17038 34062 11407 34062 11370 34063 11407 34063 11366 34063 11366 34064 11407 34064 17039 34064 11366 34065 17039 34065 11365 34065 11365 34066 17039 34066 17040 34066 11365 34067 17040 34067 17042 34067 17042 34068 17040 34068 17041 34068 17042 34069 17041 34069 17043 34069 17043 34070 17041 34070 17044 34070 17043 34071 17044 34071 11362 34071 11362 34072 17044 34072 17049 34072 11362 34073 17049 34073 17124 34073 17124 34074 17049 34074 17050 34074 17124 34075 17050 34075 17123 34075 17123 34076 17050 34076 17051 34076 17123 34077 17051 34077 17045 34077 17045 34078 17051 34078 17046 34078 17045 34079 17046 34079 17120 34079 17120 34080 17046 34080 17055 34080 17120 34081 17055 34081 17048 34081 17048 34082 17055 34082 17047 34082 17048 34083 17047 34083 17117 34083 17117 34084 17047 34084 17058 34084 17049 34085 11406 34085 17062 34085 17049 34086 17062 34086 17050 34086 17050 34087 17062 34087 17065 34087 17050 34088 17065 34088 17051 34088 17051 34089 17065 34089 17066 34089 17051 34090 17066 34090 17046 34090 17066 34091 17052 34091 17046 34091 17046 34092 17052 34092 17053 34092 17046 34093 17053 34093 17055 34093 17053 34094 17054 34094 17055 34094 17055 34095 17054 34095 17060 34095 17055 34096 17060 34096 17047 34096 17060 34097 17056 34097 17047 34097 17047 34098 17056 34098 17057 34098 17047 34099 17057 34099 17058 34099 17058 34100 17057 34100 17059 34100 17058 34101 17059 34101 17038 34101 15939 34102 17059 34102 15941 34102 15941 34103 17059 34103 17057 34103 15941 34104 17057 34104 15942 34104 17057 34105 17056 34105 15942 34105 15942 34106 17056 34106 17060 34106 15942 34107 17060 34107 17061 34107 17061 34108 17060 34108 17054 34108 17054 34109 17053 34109 17061 34109 17061 34110 17053 34110 17052 34110 17061 34111 17052 34111 17064 34111 11406 34112 15933 34112 17062 34112 17062 34113 15933 34113 17063 34113 17062 34114 17063 34114 17065 34114 17065 34115 17063 34115 17064 34115 17065 34116 17064 34116 17066 34116 17066 34117 17064 34117 17052 34117 11340 34118 17077 34118 11342 34118 11342 34119 17077 34119 11394 34119 11342 34120 11394 34120 17067 34120 17067 34121 11394 34121 17068 34121 17067 34122 17068 34122 11335 34122 11335 34123 17068 34123 11396 34123 11335 34124 11396 34124 17069 34124 17069 34125 11396 34125 11399 34125 17069 34126 11399 34126 17141 34126 17141 34127 11399 34127 11401 34127 17141 34128 11401 34128 17070 34128 17070 34129 11401 34129 17078 34129 17070 34130 17078 34130 17071 34130 17071 34131 17078 34131 17072 34131 17071 34132 17072 34132 17142 34132 17142 34133 17072 34133 17081 34133 17142 34134 17081 34134 17073 34134 17073 34135 17081 34135 17074 34135 17073 34136 17074 34136 17143 34136 17143 34137 17074 34137 17075 34137 17143 34138 17075 34138 17076 34138 17076 34139 17075 34139 17083 34139 17076 34140 17083 34140 11340 34140 11340 34141 17083 34141 17077 34141 11401 34142 11392 34142 17078 34142 17078 34143 11392 34143 17079 34143 17078 34144 17079 34144 17072 34144 17072 34145 17079 34145 17080 34145 17072 34146 17080 34146 17081 34146 17081 34147 17080 34147 17082 34147 17081 34148 17082 34148 17074 34148 17074 34149 17082 34149 17086 34149 17074 34150 17086 34150 17075 34150 17075 34151 17086 34151 17084 34151 17075 34152 17084 34152 17083 34152 17083 34153 17084 34153 17088 34153 11392 34154 11393 34154 17079 34154 17079 34155 11393 34155 15892 34155 17079 34156 15892 34156 17080 34156 17080 34157 15892 34157 15894 34157 17080 34158 15894 34158 17082 34158 17082 34159 15894 34159 17085 34159 17082 34160 17085 34160 17086 34160 17086 34161 17085 34161 17087 34161 17086 34162 17087 34162 17084 34162 17084 34163 17087 34163 15880 34163 17084 34164 15880 34164 17088 34164 17088 34165 15880 34165 11388 34165 17020 34166 17100 34166 17089 34166 17089 34167 17100 34167 17103 34167 17089 34168 17103 34168 17090 34168 17103 34169 17091 34169 17090 34169 17090 34170 17091 34170 17092 34170 17090 34171 17092 34171 17094 34171 17094 34172 17092 34172 17104 34172 17104 34173 17106 34173 17094 34173 17094 34174 17106 34174 17093 34174 17094 34175 17093 34175 17099 34175 11386 34176 17096 34176 17095 34176 17095 34177 17096 34177 17097 34177 17095 34178 17097 34178 17098 34178 17098 34179 17097 34179 17099 34179 17098 34180 17099 34180 17107 34180 17107 34181 17099 34181 17093 34181 17100 34182 17101 34182 17102 34182 17100 34183 17102 34183 17103 34183 17103 34184 17102 34184 17108 34184 17103 34185 17108 34185 17091 34185 17091 34186 17108 34186 17092 34186 17092 34187 17108 34187 17105 34187 17092 34188 17105 34188 17104 34188 17104 34189 17105 34189 17106 34189 17106 34190 17105 34190 17112 34190 17106 34191 17112 34191 17093 34191 17093 34192 17112 34192 17107 34192 17107 34193 17112 34193 17114 34193 17107 34194 17114 34194 17098 34194 17098 34195 17114 34195 17115 34195 17098 34196 17115 34196 17095 34196 17095 34197 17115 34197 11371 34197 17095 34198 11371 34198 11386 34198 17101 34199 13924 34199 17102 34199 17102 34200 13924 34200 17109 34200 17102 34201 17109 34201 17108 34201 17108 34202 17109 34202 17110 34202 17108 34203 17110 34203 17105 34203 17105 34204 17110 34204 13930 34204 17105 34205 13930 34205 17112 34205 17112 34206 13930 34206 17111 34206 17112 34207 17111 34207 17114 34207 17114 34208 17111 34208 17113 34208 17114 34209 17113 34209 17115 34209 17115 34210 17113 34210 13929 34210 17115 34211 13929 34211 11371 34211 11371 34212 13929 34212 13928 34212 17117 34213 11368 34213 17116 34213 17116 34214 17127 34214 17117 34214 17117 34215 17127 34215 17118 34215 17117 34216 17118 34216 17048 34216 17118 34217 17119 34217 17048 34217 17048 34218 17119 34218 17129 34218 17048 34219 17129 34219 17120 34219 17129 34220 17131 34220 17120 34220 17120 34221 17131 34221 17121 34221 17120 34222 17121 34222 17045 34222 17045 34223 17121 34223 17122 34223 17045 34224 17122 34224 17123 34224 17122 34225 17132 34225 17123 34225 17123 34226 17132 34226 17133 34226 17123 34227 17133 34227 17124 34227 11363 34228 11362 34228 17125 34228 17125 34229 11362 34229 17124 34229 17125 34230 17124 34230 17135 34230 17135 34231 17124 34231 17133 34231 17116 34232 17126 34232 17127 34232 17127 34233 17126 34233 17128 34233 17127 34234 17128 34234 17118 34234 17118 34235 17128 34235 17119 34235 17119 34236 17128 34236 17130 34236 17119 34237 17130 34237 17129 34237 17129 34238 17130 34238 17131 34238 17131 34239 17130 34239 17138 34239 17131 34240 17138 34240 17121 34240 17121 34241 17138 34241 17122 34241 17122 34242 17138 34242 17134 34242 17122 34243 17134 34243 17132 34243 17132 34244 17134 34244 17133 34244 17133 34245 17134 34245 17136 34245 17133 34246 17136 34246 17135 34246 17135 34247 17136 34247 17125 34247 17125 34248 17136 34248 11344 34248 17125 34249 11344 34249 11363 34249 17126 34250 13941 34250 17128 34250 17128 34251 13941 34251 13939 34251 17128 34252 13939 34252 17130 34252 17130 34253 13939 34253 17137 34253 17130 34254 17137 34254 17138 34254 17138 34255 17137 34255 13938 34255 17138 34256 13938 34256 17134 34256 17134 34257 13938 34257 17139 34257 17134 34258 17139 34258 17136 34258 17136 34259 17139 34259 13936 34259 17136 34260 13936 34260 11344 34260 11344 34261 13936 34261 11345 34261 17140 34262 17141 34262 17150 34262 17150 34263 17141 34263 17070 34263 17150 34264 17070 34264 17149 34264 17149 34265 17070 34265 17071 34265 17149 34266 17071 34266 17148 34266 17148 34267 17071 34267 17142 34267 17148 34268 17142 34268 17147 34268 17147 34269 17142 34269 17073 34269 17147 34270 17073 34270 17145 34270 17145 34271 17073 34271 17143 34271 17145 34272 17143 34272 11339 34272 11339 34273 17143 34273 17076 34273 11339 34274 17144 34274 17145 34274 17145 34275 17144 34275 17146 34275 17145 34276 17146 34276 17147 34276 17147 34277 17146 34277 17152 34277 17147 34278 17152 34278 17148 34278 17148 34279 17152 34279 17154 34279 17148 34280 17154 34280 17149 34280 17149 34281 17154 34281 17155 34281 17149 34282 17155 34282 17150 34282 17150 34283 17155 34283 17157 34283 17150 34284 17157 34284 17140 34284 17140 34285 17157 34285 11326 34285 17144 34286 17151 34286 17146 34286 17146 34287 17151 34287 13953 34287 17146 34288 13953 34288 17152 34288 17152 34289 13953 34289 17153 34289 17152 34290 17153 34290 17154 34290 17154 34291 17153 34291 13950 34291 17154 34292 13950 34292 17155 34292 17155 34293 13950 34293 17156 34293 17155 34294 17156 34294 17157 34294 17157 34295 17156 34295 17158 34295 17157 34296 17158 34296 11326 34296 11326 34297 17158 34297 17159 34297 11306 34298 17174 34298 15961 34298 11306 34299 15961 34299 17160 34299 17160 34300 15961 34300 17180 34300 17160 34301 17180 34301 11308 34301 17193 34302 17161 34302 17162 34302 17162 34303 17161 34303 17192 34303 17162 34304 17192 34304 17178 34304 11317 34305 17163 34305 17176 34305 17176 34306 17163 34306 17166 34306 17176 34307 17166 34307 17165 34307 18540 34308 17164 34308 18541 34308 18541 34309 17164 34309 17165 34309 18541 34310 17165 34310 18534 34310 18534 34311 17165 34311 17166 34311 18540 34312 17167 34312 17164 34312 17164 34313 17167 34313 18537 34313 17164 34314 18537 34314 15961 34314 15961 34315 18537 34315 18536 34315 15961 34316 18536 34316 17180 34316 17191 34317 17168 34317 17249 34317 17163 34318 17169 34318 17166 34318 17166 34319 17169 34319 11315 34319 17166 34320 11315 34320 17170 34320 17170 34321 11315 34321 17193 34321 17170 34322 17193 34322 17171 34322 17171 34323 17193 34323 17162 34323 17204 34324 17172 34324 17173 34324 17173 34325 17172 34325 15961 34325 17173 34326 15961 34326 11304 34326 11304 34327 15961 34327 17174 34327 17168 34328 17175 34328 17249 34328 17249 34329 17175 34329 17186 34329 17249 34330 17186 34330 17176 34330 17176 34331 17186 34331 17177 34331 17176 34332 17177 34332 11317 34332 17204 34333 17203 34333 17172 34333 17172 34334 17203 34334 17202 34334 17172 34335 17202 34335 17200 34335 17192 34336 17191 34336 17178 34336 17178 34337 17191 34337 17249 34337 17178 34338 17249 34338 18525 34338 18525 34339 17249 34339 17172 34339 11308 34340 17180 34340 17179 34340 17179 34341 17180 34341 17181 34341 17179 34342 17181 34342 17182 34342 17182 34343 17181 34343 17183 34343 17182 34344 17183 34344 17200 34344 17200 34345 17183 34345 18531 34345 17200 34346 18531 34346 17172 34346 17172 34347 18531 34347 18529 34347 17172 34348 18529 34348 18525 34348 11321 34349 17188 34349 17189 34349 17187 34350 17188 34350 11321 34350 17185 34351 17187 34351 11321 34351 11321 34352 17184 34352 11313 34352 17190 34353 17184 34353 11321 34353 17189 34354 17190 34354 11321 34354 17185 34355 17186 34355 17187 34355 17187 34356 17186 34356 17175 34356 17187 34357 17175 34357 17188 34357 17188 34358 17175 34358 17168 34358 17188 34359 17168 34359 17189 34359 17189 34360 17168 34360 17191 34360 17189 34361 17191 34361 17190 34361 17190 34362 17191 34362 17192 34362 17190 34363 17192 34363 17184 34363 17184 34364 17192 34364 17161 34364 17184 34365 17161 34365 11313 34365 11313 34366 17161 34366 17193 34366 11312 34367 17199 34367 17201 34367 17198 34368 17199 34368 11312 34368 17197 34369 17198 34369 11312 34369 11312 34370 17196 34370 17194 34370 17195 34371 17196 34371 11312 34371 17201 34372 17195 34372 11312 34372 17197 34373 17179 34373 17198 34373 17198 34374 17179 34374 17182 34374 17198 34375 17182 34375 17199 34375 17199 34376 17182 34376 17200 34376 17199 34377 17200 34377 17201 34377 17201 34378 17200 34378 17202 34378 17201 34379 17202 34379 17195 34379 17195 34380 17202 34380 17203 34380 17195 34381 17203 34381 17196 34381 17196 34382 17203 34382 17204 34382 17196 34383 17204 34383 17194 34383 17194 34384 17204 34384 17173 34384 17211 34385 11298 34385 17205 34385 17205 34386 11298 34386 17206 34386 17205 34387 17206 34387 17207 34387 17208 34388 17223 34388 17236 34388 17236 34389 17223 34389 17205 34389 17236 34390 17205 34390 11296 34390 11296 34391 17205 34391 17207 34391 17215 34392 17209 34392 16083 34392 17221 34393 17210 34393 17205 34393 17205 34394 17210 34394 18547 34394 17205 34395 18547 34395 17211 34395 11290 34396 17212 34396 17213 34396 17213 34397 17212 34397 17222 34397 17213 34398 17222 34398 17242 34398 11290 34399 17214 34399 17212 34399 17212 34400 17214 34400 11288 34400 17212 34401 11288 34401 16083 34401 16083 34402 11288 34402 11285 34402 16083 34403 11285 34403 17215 34403 17215 34404 11285 34404 11284 34404 17215 34405 11284 34405 18553 34405 18553 34406 11284 34406 17217 34406 18553 34407 17217 34407 17216 34407 17216 34408 17217 34408 17219 34408 18561 34409 18560 34409 17222 34409 17208 34410 17235 34410 17223 34410 17223 34411 17235 34411 17218 34411 17223 34412 17218 34412 17224 34412 17217 34413 17220 34413 17219 34413 17219 34414 17220 34414 17245 34414 17219 34415 17245 34415 18560 34415 18560 34416 17245 34416 17244 34416 18560 34417 17244 34417 17222 34417 17222 34418 17244 34418 17243 34418 17222 34419 17243 34419 17242 34419 17209 34420 18550 34420 16083 34420 16083 34421 18550 34421 18543 34421 16083 34422 18543 34422 17221 34422 17221 34423 18543 34423 18544 34423 17221 34424 18544 34424 17210 34424 18561 34425 17222 34425 18563 34425 18563 34426 17222 34426 17223 34426 18563 34427 17223 34427 18557 34427 18557 34428 17223 34428 17224 34428 18557 34429 17224 34429 17225 34429 17225 34430 17224 34430 17234 34430 17225 34431 17234 34431 17226 34431 17226 34432 17234 34432 11301 34432 17226 34433 11301 34433 17211 34433 17211 34434 11301 34434 17227 34434 17211 34435 17227 34435 11298 34435 17231 34436 17230 34436 17228 34436 17229 34437 17230 34437 17231 34437 11300 34438 17229 34438 17231 34438 17231 34439 17232 34439 11294 34439 17233 34440 17232 34440 17231 34440 17228 34441 17233 34441 17231 34441 11300 34442 11301 34442 17229 34442 17229 34443 11301 34443 17234 34443 17229 34444 17234 34444 17230 34444 17230 34445 17234 34445 17224 34445 17230 34446 17224 34446 17228 34446 17228 34447 17224 34447 17218 34447 17228 34448 17218 34448 17233 34448 17233 34449 17218 34449 17235 34449 17233 34450 17235 34450 17232 34450 17232 34451 17235 34451 17208 34451 17232 34452 17208 34452 11294 34452 11294 34453 17208 34453 17236 34453 17237 34454 17238 34454 17239 34454 17240 34455 17238 34455 17237 34455 11292 34456 17240 34456 17237 34456 17237 34457 17246 34457 11291 34457 17241 34458 17246 34458 17237 34458 17239 34459 17241 34459 17237 34459 11292 34460 17213 34460 17240 34460 17240 34461 17213 34461 17242 34461 17240 34462 17242 34462 17238 34462 17238 34463 17242 34463 17243 34463 17238 34464 17243 34464 17239 34464 17239 34465 17243 34465 17244 34465 17239 34466 17244 34466 17241 34466 17241 34467 17244 34467 17245 34467 17241 34468 17245 34468 17246 34468 17246 34469 17245 34469 17220 34469 17246 34470 17220 34470 11291 34470 11291 34471 17220 34471 17217 34471 15957 34472 17205 34472 17247 34472 17247 34473 17205 34473 17223 34473 17212 34474 15729 34474 17222 34474 17222 34475 15729 34475 17248 34475 17176 34476 17250 34476 17249 34476 17249 34477 17250 34477 15718 34477 15740 34478 15961 34478 17251 34478 17251 34479 15961 34479 17172 34479 11273 34480 11256 34480 17252 34480 17252 34481 11256 34481 11257 34481 17252 34482 11257 34482 11276 34482 11276 34483 11257 34483 17254 34483 11276 34484 17254 34484 17253 34484 17253 34485 17254 34485 17255 34485 17253 34486 17255 34486 17256 34486 17256 34487 17255 34487 11259 34487 17256 34488 11259 34488 11280 34488 11280 34489 11259 34489 11260 34489 11280 34490 11260 34490 17257 34490 17257 34491 11260 34491 17258 34491 17257 34492 17258 34492 17260 34492 17260 34493 17258 34493 17259 34493 17260 34494 17259 34494 11282 34494 11282 34495 17259 34495 17261 34495 11282 34496 17261 34496 17288 34496 17288 34497 17261 34497 17340 34497 17288 34498 17340 34498 17289 34498 17289 34499 17340 34499 17342 34499 17289 34500 17342 34500 17290 34500 17290 34501 17342 34501 17344 34501 17290 34502 17344 34502 17262 34502 17262 34503 17344 34503 17345 34503 17262 34504 17345 34504 17294 34504 17294 34505 17345 34505 17263 34505 17294 34506 17263 34506 17264 34506 17264 34507 17263 34507 17265 34507 17264 34508 17265 34508 17297 34508 17297 34509 17265 34509 17346 34509 17297 34510 17346 34510 17266 34510 17266 34511 17346 34511 17267 34511 17266 34512 17267 34512 17268 34512 17268 34513 17267 34513 17349 34513 17268 34514 17349 34514 17299 34514 17299 34515 17349 34515 17351 34515 17299 34516 17351 34516 17269 34516 17269 34517 17351 34517 17270 34517 17269 34518 17270 34518 17271 34518 17271 34519 17270 34519 17353 34519 17271 34520 17353 34520 17303 34520 17303 34521 17353 34521 17354 34521 17303 34522 17354 34522 17272 34522 17272 34523 17354 34523 17355 34523 17272 34524 17355 34524 17273 34524 17273 34525 17355 34525 17358 34525 17273 34526 17358 34526 17306 34526 17306 34527 17358 34527 17360 34527 17306 34528 17360 34528 17308 34528 17308 34529 17360 34529 17362 34529 17308 34530 17362 34530 17274 34530 17274 34531 17362 34531 17276 34531 17274 34532 17276 34532 17275 34532 17275 34533 17276 34533 17277 34533 17275 34534 17277 34534 11264 34534 11264 34535 17277 34535 11244 34535 11264 34536 11244 34536 17278 34536 17278 34537 11244 34537 17279 34537 17278 34538 17279 34538 11266 34538 11266 34539 17279 34539 11246 34539 11266 34540 11246 34540 17280 34540 17280 34541 11246 34541 11248 34541 17280 34542 11248 34542 17281 34542 17281 34543 11248 34543 17282 34543 17281 34544 17282 34544 11270 34544 11270 34545 17282 34545 11251 34545 11270 34546 11251 34546 17283 34546 17283 34547 11251 34547 17284 34547 17283 34548 17284 34548 17285 34548 17285 34549 17284 34549 11252 34549 17285 34550 11252 34550 11272 34550 11272 34551 11252 34551 11253 34551 11272 34552 11253 34552 17286 34552 17286 34553 11253 34553 11254 34553 17286 34554 11254 34554 11273 34554 11273 34555 11254 34555 11256 34555 17287 34556 11282 34556 17288 34556 17287 34557 17288 34557 17313 34557 17313 34558 17288 34558 17289 34558 17313 34559 17289 34559 17291 34559 17291 34560 17289 34560 17290 34560 17291 34561 17290 34561 17292 34561 17292 34562 17290 34562 17262 34562 17292 34563 17262 34563 17293 34563 17293 34564 17262 34564 17294 34564 17293 34565 17294 34565 17295 34565 17295 34566 17294 34566 17264 34566 17295 34567 17264 34567 17296 34567 17296 34568 17264 34568 17297 34568 17296 34569 17297 34569 17337 34569 17337 34570 17297 34570 17266 34570 17337 34571 17266 34571 17336 34571 17336 34572 17266 34572 17268 34572 17336 34573 17268 34573 17298 34573 17298 34574 17268 34574 17299 34574 17298 34575 17299 34575 17300 34575 17300 34576 17299 34576 17269 34576 17300 34577 17269 34577 17334 34577 17334 34578 17269 34578 17271 34578 17334 34579 17271 34579 17301 34579 17301 34580 17271 34580 17303 34580 17301 34581 17303 34581 17302 34581 17302 34582 17303 34582 17272 34582 17302 34583 17272 34583 17304 34583 17304 34584 17272 34584 17273 34584 17304 34585 17273 34585 17305 34585 17305 34586 17273 34586 17306 34586 17305 34587 17306 34587 17307 34587 17307 34588 17306 34588 17308 34588 17307 34589 17308 34589 17309 34589 17309 34590 17308 34590 17274 34590 17309 34591 17274 34591 17310 34591 17310 34592 17274 34592 17275 34592 17310 34593 17275 34593 17330 34593 17295 34594 17338 34594 17293 34594 17293 34595 17338 34595 17311 34595 17293 34596 17311 34596 17292 34596 17292 34597 17311 34597 17312 34597 17292 34598 17312 34598 17291 34598 17291 34599 17312 34599 17383 34599 17291 34600 17383 34600 17313 34600 17313 34601 17383 34601 17314 34601 17313 34602 17314 34602 17287 34602 17287 34603 17314 34603 17315 34603 17287 34604 17315 34604 17316 34604 17316 34605 17315 34605 11226 34605 17316 34606 11226 34606 11281 34606 11281 34607 11226 34607 17317 34607 11281 34608 17317 34608 11279 34608 11279 34609 17317 34609 11227 34609 11279 34610 11227 34610 11278 34610 11278 34611 11227 34611 11228 34611 11278 34612 11228 34612 11277 34612 11277 34613 11228 34613 17318 34613 11277 34614 17318 34614 17319 34614 17319 34615 17318 34615 11230 34615 17319 34616 11230 34616 17320 34616 17320 34617 11230 34617 11231 34617 17320 34618 11231 34618 11275 34618 11275 34619 11231 34619 11232 34619 11275 34620 11232 34620 11274 34620 11274 34621 11232 34621 17322 34621 11274 34622 17322 34622 17321 34622 17321 34623 17322 34623 11234 34623 17321 34624 11234 34624 17323 34624 17323 34625 11234 34625 11237 34625 17323 34626 11237 34626 11271 34626 11271 34627 11237 34627 11238 34627 11271 34628 11238 34628 11269 34628 11269 34629 11238 34629 17324 34629 11269 34630 17324 34630 11268 34630 11268 34631 17324 34631 17325 34631 11268 34632 17325 34632 11267 34632 11267 34633 17325 34633 11240 34633 11267 34634 11240 34634 17327 34634 17327 34635 11240 34635 17326 34635 17327 34636 17326 34636 17328 34636 17328 34637 17326 34637 11242 34637 17328 34638 11242 34638 11265 34638 11265 34639 11242 34639 17329 34639 11265 34640 17329 34640 17330 34640 17330 34641 17329 34641 17365 34641 17330 34642 17365 34642 17310 34642 17310 34643 17365 34643 17331 34643 17310 34644 17331 34644 17309 34644 17309 34645 17331 34645 17367 34645 17309 34646 17367 34646 17307 34646 17307 34647 17367 34647 17332 34647 17307 34648 17332 34648 17305 34648 17305 34649 17332 34649 17368 34649 17305 34650 17368 34650 17304 34650 17304 34651 17368 34651 17369 34651 17304 34652 17369 34652 17302 34652 17302 34653 17369 34653 17333 34653 17302 34654 17333 34654 17301 34654 17301 34655 17333 34655 17372 34655 17301 34656 17372 34656 17334 34656 17334 34657 17372 34657 17373 34657 17334 34658 17373 34658 17300 34658 17300 34659 17373 34659 17375 34659 17300 34660 17375 34660 17298 34660 17298 34661 17375 34661 17335 34661 17298 34662 17335 34662 17336 34662 17336 34663 17335 34663 17377 34663 17336 34664 17377 34664 17337 34664 17337 34665 17377 34665 17378 34665 17337 34666 17378 34666 17296 34666 17296 34667 17378 34667 17379 34667 17296 34668 17379 34668 17295 34668 17295 34669 17379 34669 17338 34669 17261 34670 11263 34670 17339 34670 17261 34671 17339 34671 17340 34671 17340 34672 17339 34672 17341 34672 17340 34673 17341 34673 17342 34673 17342 34674 17341 34674 15704 34674 17342 34675 15704 34675 17344 34675 17344 34676 15704 34676 17343 34676 17344 34677 17343 34677 17345 34677 17345 34678 17343 34678 15707 34678 17345 34679 15707 34679 17263 34679 17263 34680 15707 34680 15708 34680 17263 34681 15708 34681 17265 34681 17265 34682 15708 34682 17347 34682 17265 34683 17347 34683 17346 34683 17346 34684 17347 34684 17348 34684 17346 34685 17348 34685 17267 34685 17267 34686 17348 34686 17350 34686 17267 34687 17350 34687 17349 34687 17349 34688 17350 34688 15710 34688 17349 34689 15710 34689 17351 34689 17351 34690 15710 34690 17352 34690 17351 34691 17352 34691 17270 34691 17270 34692 17352 34692 15712 34692 17270 34693 15712 34693 17353 34693 17353 34694 15712 34694 15713 34694 17353 34695 15713 34695 17354 34695 17354 34696 15713 34696 17356 34696 17354 34697 17356 34697 17355 34697 17355 34698 17356 34698 17357 34698 17355 34699 17357 34699 17358 34699 17358 34700 17357 34700 17359 34700 17358 34701 17359 34701 17360 34701 17360 34702 17359 34702 17361 34702 17360 34703 17361 34703 17362 34703 17362 34704 17361 34704 17363 34704 17362 34705 17363 34705 17276 34705 17276 34706 17363 34706 15717 34706 17276 34707 15717 34707 17277 34707 17365 34708 17364 34708 17366 34708 17365 34709 17366 34709 17331 34709 17331 34710 17366 34710 15702 34710 17331 34711 15702 34711 17367 34711 17367 34712 15702 34712 15701 34712 17367 34713 15701 34713 17332 34713 17332 34714 15701 34714 15700 34714 17332 34715 15700 34715 17368 34715 17368 34716 15700 34716 15699 34716 17368 34717 15699 34717 17369 34717 17369 34718 15699 34718 15698 34718 17369 34719 15698 34719 17333 34719 17333 34720 15698 34720 17370 34720 17333 34721 17370 34721 17372 34721 17372 34722 17370 34722 17371 34722 17372 34723 17371 34723 17373 34723 17373 34724 17371 34724 17374 34724 17373 34725 17374 34725 17375 34725 17375 34726 17374 34726 15696 34726 17375 34727 15696 34727 17335 34727 17335 34728 15696 34728 17376 34728 17335 34729 17376 34729 17377 34729 17377 34730 17376 34730 15694 34730 17377 34731 15694 34731 17378 34731 17378 34732 15694 34732 17380 34732 17378 34733 17380 34733 17379 34733 17379 34734 17380 34734 15692 34734 17379 34735 15692 34735 17338 34735 17338 34736 15692 34736 17381 34736 17338 34737 17381 34737 17311 34737 17311 34738 17381 34738 17382 34738 17311 34739 17382 34739 17312 34739 17312 34740 17382 34740 15689 34740 17312 34741 15689 34741 17383 34741 17383 34742 15689 34742 15688 34742 17383 34743 15688 34743 17314 34743 17314 34744 15688 34744 12227 34744 17314 34745 12227 34745 17315 34745 17427 34746 17384 34746 17440 34746 17440 34747 17384 34747 17385 34747 17440 34748 17385 34748 17387 34748 17387 34749 17385 34749 17386 34749 17387 34750 17386 34750 17388 34750 17388 34751 17386 34751 18157 34751 17388 34752 18157 34752 17389 34752 17389 34753 18157 34753 18159 34753 17389 34754 18159 34754 17390 34754 17390 34755 18159 34755 17391 34755 17390 34756 17391 34756 17392 34756 17392 34757 17391 34757 11050 34757 17392 34758 11050 34758 17393 34758 17393 34759 11050 34759 11052 34759 17393 34760 11052 34760 17394 34760 17394 34761 11052 34761 11053 34761 17394 34762 11053 34762 11213 34762 11213 34763 11053 34763 17395 34763 11213 34764 17395 34764 17396 34764 17396 34765 17395 34765 11055 34765 17396 34766 11055 34766 17397 34766 17397 34767 11055 34767 11057 34767 17397 34768 11057 34768 11215 34768 11215 34769 11057 34769 17398 34769 11215 34770 17398 34770 11216 34770 11216 34771 17398 34771 17399 34771 11216 34772 17399 34772 11217 34772 11217 34773 17399 34773 17400 34773 11217 34774 17400 34774 17401 34774 17401 34775 17400 34775 17402 34775 17401 34776 17402 34776 11219 34776 11219 34777 17402 34777 17403 34777 11219 34778 17403 34778 17404 34778 17404 34779 17403 34779 11061 34779 17404 34780 11061 34780 17405 34780 17405 34781 11061 34781 17406 34781 17405 34782 17406 34782 17407 34782 17407 34783 17406 34783 11063 34783 17407 34784 11063 34784 11222 34784 11222 34785 11063 34785 11064 34785 11222 34786 11064 34786 17408 34786 17408 34787 11064 34787 17409 34787 17408 34788 17409 34788 17410 34788 17410 34789 17409 34789 17411 34789 17410 34790 17411 34790 11223 34790 11223 34791 17411 34791 17412 34791 11223 34792 17412 34792 17413 34792 17413 34793 17412 34793 18135 34793 17413 34794 18135 34794 17429 34794 17429 34795 18135 34795 18137 34795 17429 34796 18137 34796 17431 34796 17431 34797 18137 34797 18139 34797 17431 34798 18139 34798 17414 34798 17414 34799 18139 34799 18140 34799 17414 34800 18140 34800 17415 34800 17415 34801 18140 34801 18141 34801 17415 34802 18141 34802 17416 34802 17416 34803 18141 34803 17417 34803 17416 34804 17417 34804 17418 34804 17418 34805 17417 34805 18142 34805 17418 34806 18142 34806 17419 34806 17419 34807 18142 34807 17420 34807 17419 34808 17420 34808 17422 34808 17422 34809 17420 34809 17421 34809 17422 34810 17421 34810 17423 34810 17423 34811 17421 34811 18146 34811 17423 34812 18146 34812 17437 34812 17437 34813 18146 34813 18147 34813 17437 34814 18147 34814 17424 34814 17424 34815 18147 34815 18149 34815 17424 34816 18149 34816 17425 34816 17425 34817 18149 34817 17426 34817 17425 34818 17426 34818 17438 34818 17438 34819 17426 34819 18152 34819 17438 34820 18152 34820 17427 34820 17427 34821 18152 34821 17384 34821 17444 34822 17413 34822 17429 34822 17444 34823 17429 34823 17428 34823 17428 34824 17429 34824 17431 34824 17428 34825 17431 34825 17430 34825 17430 34826 17431 34826 17414 34826 17430 34827 17414 34827 17432 34827 17432 34828 17414 34828 17415 34828 17432 34829 17415 34829 17433 34829 17433 34830 17415 34830 17416 34830 17433 34831 17416 34831 17434 34831 17434 34832 17416 34832 17418 34832 17434 34833 17418 34833 17481 34833 17481 34834 17418 34834 17419 34834 17481 34835 17419 34835 17480 34835 17480 34836 17419 34836 17422 34836 17480 34837 17422 34837 17478 34837 17478 34838 17422 34838 17423 34838 17478 34839 17423 34839 17435 34839 17435 34840 17423 34840 17437 34840 17435 34841 17437 34841 17436 34841 17436 34842 17437 34842 17424 34842 17436 34843 17424 34843 17476 34843 17476 34844 17424 34844 17425 34844 17476 34845 17425 34845 17474 34845 17474 34846 17425 34846 17438 34846 17474 34847 17438 34847 17439 34847 17439 34848 17438 34848 17427 34848 17439 34849 17427 34849 17471 34849 17471 34850 17427 34850 17440 34850 17471 34851 17440 34851 17441 34851 17441 34852 17440 34852 17387 34852 17441 34853 17387 34853 17442 34853 17442 34854 17387 34854 17388 34854 17442 34855 17388 34855 17468 34855 17468 34856 17388 34856 17389 34856 17468 34857 17389 34857 17467 34857 17467 34858 17389 34858 17390 34858 17467 34859 17390 34859 17465 34859 17434 34860 17482 34860 17433 34860 17433 34861 17482 34861 18173 34861 17433 34862 18173 34862 17432 34862 17432 34863 18173 34863 18175 34863 17432 34864 18175 34864 17430 34864 17430 34865 18175 34865 18176 34865 17430 34866 18176 34866 17428 34866 17428 34867 18176 34867 17443 34867 17428 34868 17443 34868 17444 34868 17444 34869 17443 34869 17445 34869 17444 34870 17445 34870 11224 34870 11224 34871 17445 34871 17446 34871 11224 34872 17446 34872 17447 34872 17447 34873 17446 34873 11029 34873 17447 34874 11029 34874 17448 34874 17448 34875 11029 34875 17449 34875 17448 34876 17449 34876 17450 34876 17450 34877 17449 34877 11031 34877 17450 34878 11031 34878 17451 34878 17451 34879 11031 34879 17452 34879 17451 34880 17452 34880 11221 34880 11221 34881 17452 34881 11034 34881 11221 34882 11034 34882 17453 34882 17453 34883 11034 34883 11035 34883 17453 34884 11035 34884 11220 34884 11220 34885 11035 34885 17454 34885 11220 34886 17454 34886 17455 34886 17455 34887 17454 34887 17456 34887 17455 34888 17456 34888 11218 34888 11218 34889 17456 34889 11036 34889 11218 34890 11036 34890 17457 34890 17457 34891 11036 34891 17459 34891 17457 34892 17459 34892 17458 34892 17458 34893 17459 34893 11038 34893 17458 34894 11038 34894 17460 34894 17460 34895 11038 34895 11041 34895 17460 34896 11041 34896 11214 34896 11214 34897 11041 34897 17461 34897 11214 34898 17461 34898 17462 34898 17462 34899 17461 34899 11043 34899 17462 34900 11043 34900 11212 34900 11212 34901 11043 34901 11044 34901 11212 34902 11044 34902 17463 34902 17463 34903 11044 34903 11046 34903 17463 34904 11046 34904 17464 34904 17464 34905 11046 34905 17466 34905 17464 34906 17466 34906 17465 34906 17465 34907 17466 34907 11048 34907 17465 34908 11048 34908 17467 34908 17467 34909 11048 34909 17469 34909 17467 34910 17469 34910 17468 34910 17468 34911 17469 34911 18161 34911 17468 34912 18161 34912 17442 34912 17442 34913 18161 34913 17470 34913 17442 34914 17470 34914 17441 34914 17441 34915 17470 34915 17472 34915 17441 34916 17472 34916 17471 34916 17471 34917 17472 34917 18164 34917 17471 34918 18164 34918 17439 34918 17439 34919 18164 34919 17473 34919 17439 34920 17473 34920 17474 34920 17474 34921 17473 34921 17475 34921 17474 34922 17475 34922 17476 34922 17476 34923 17475 34923 17477 34923 17476 34924 17477 34924 17436 34924 17436 34925 17477 34925 18166 34925 17436 34926 18166 34926 17435 34926 17435 34927 18166 34927 18167 34927 17435 34928 18167 34928 17478 34928 17478 34929 18167 34929 18168 34929 17478 34930 18168 34930 17480 34930 17480 34931 18168 34931 17479 34931 17480 34932 17479 34932 17481 34932 17481 34933 17479 34933 18171 34933 17481 34934 18171 34934 17434 34934 17434 34935 18171 34935 17482 34935 17527 34936 18191 34936 17483 34936 17483 34937 18191 34937 18192 34937 17483 34938 18192 34938 17541 34938 17541 34939 18192 34939 17484 34939 17541 34940 17484 34940 17543 34940 17543 34941 17484 34941 17486 34941 17543 34942 17486 34942 17485 34942 17485 34943 17486 34943 18197 34943 17485 34944 18197 34944 17545 34944 17545 34945 18197 34945 17487 34945 17545 34946 17487 34946 11200 34946 11200 34947 17487 34947 11011 34947 11200 34948 11011 34948 11201 34948 11201 34949 11011 34949 11012 34949 11201 34950 11012 34950 17488 34950 17488 34951 11012 34951 17489 34951 17488 34952 17489 34952 17490 34952 17490 34953 17489 34953 17492 34953 17490 34954 17492 34954 17491 34954 17491 34955 17492 34955 11014 34955 17491 34956 11014 34956 11203 34956 11203 34957 11014 34957 11015 34957 11203 34958 11015 34958 17493 34958 17493 34959 11015 34959 11018 34959 17493 34960 11018 34960 11205 34960 11205 34961 11018 34961 11019 34961 11205 34962 11019 34962 17494 34962 17494 34963 11019 34963 17495 34963 17494 34964 17495 34964 17496 34964 17496 34965 17495 34965 11020 34965 17496 34966 11020 34966 11208 34966 11208 34967 11020 34967 17497 34967 11208 34968 17497 34968 17498 34968 17498 34969 17497 34969 17499 34969 17498 34970 17499 34970 17500 34970 17500 34971 17499 34971 11024 34971 17500 34972 11024 34972 17501 34972 17501 34973 11024 34973 11025 34973 17501 34974 11025 34974 17502 34974 17502 34975 11025 34975 17504 34975 17502 34976 17504 34976 17503 34976 17503 34977 17504 34977 17506 34977 17503 34978 17506 34978 17505 34978 17505 34979 17506 34979 17507 34979 17505 34980 17507 34980 17508 34980 17508 34981 17507 34981 17509 34981 17508 34982 17509 34982 17510 34982 17510 34983 17509 34983 17511 34983 17510 34984 17511 34984 17512 34984 17512 34985 17511 34985 18178 34985 17512 34986 18178 34986 17530 34986 17530 34987 18178 34987 18182 34987 17530 34988 18182 34988 17514 34988 17514 34989 18182 34989 17513 34989 17514 34990 17513 34990 17515 34990 17515 34991 17513 34991 18183 34991 17515 34992 18183 34992 17516 34992 17516 34993 18183 34993 17517 34993 17516 34994 17517 34994 17532 34994 17532 34995 17517 34995 17519 34995 17532 34996 17519 34996 17518 34996 17518 34997 17519 34997 17520 34997 17518 34998 17520 34998 17535 34998 17535 34999 17520 34999 18185 34999 17535 35000 18185 35000 17521 35000 17521 35001 18185 35001 17522 35001 17521 35002 17522 35002 17536 35002 17536 35003 17522 35003 17523 35003 17536 35004 17523 35004 17537 35004 17537 35005 17523 35005 17524 35005 17537 35006 17524 35006 17525 35006 17525 35007 17524 35007 17526 35007 17525 35008 17526 35008 17539 35008 17539 35009 17526 35009 18189 35009 17539 35010 18189 35010 17527 35010 17527 35011 18189 35011 18191 35011 17528 35012 17510 35012 17512 35012 17528 35013 17512 35013 17529 35013 17529 35014 17512 35014 17530 35014 17529 35015 17530 35015 17549 35015 17549 35016 17530 35016 17514 35016 17549 35017 17514 35017 17548 35017 17548 35018 17514 35018 17515 35018 17548 35019 17515 35019 17531 35019 17531 35020 17515 35020 17516 35020 17531 35021 17516 35021 17583 35021 17583 35022 17516 35022 17532 35022 17583 35023 17532 35023 17533 35023 17533 35024 17532 35024 17518 35024 17533 35025 17518 35025 17580 35025 17580 35026 17518 35026 17535 35026 17580 35027 17535 35027 17534 35027 17534 35028 17535 35028 17521 35028 17534 35029 17521 35029 17578 35029 17578 35030 17521 35030 17536 35030 17578 35031 17536 35031 17577 35031 17577 35032 17536 35032 17537 35032 17577 35033 17537 35033 17576 35033 17576 35034 17537 35034 17525 35034 17576 35035 17525 35035 17538 35035 17538 35036 17525 35036 17539 35036 17538 35037 17539 35037 17574 35037 17574 35038 17539 35038 17527 35038 17574 35039 17527 35039 17540 35039 17540 35040 17527 35040 17483 35040 17540 35041 17483 35041 17572 35041 17572 35042 17483 35042 17541 35042 17572 35043 17541 35043 17542 35043 17542 35044 17541 35044 17543 35044 17542 35045 17543 35045 17544 35045 17544 35046 17543 35046 17485 35046 17544 35047 17485 35047 17570 35047 17570 35048 17485 35048 17545 35048 17570 35049 17545 35049 11199 35049 17583 35050 17546 35050 17531 35050 17531 35051 17546 35051 17547 35051 17531 35052 17547 35052 17548 35052 17548 35053 17547 35053 18216 35053 17548 35054 18216 35054 17549 35054 17549 35055 18216 35055 17550 35055 17549 35056 17550 35056 17529 35056 17529 35057 17550 35057 18218 35057 17529 35058 18218 35058 17528 35058 17528 35059 18218 35059 10990 35059 17528 35060 10990 35060 17551 35060 17551 35061 10990 35061 10992 35061 17551 35062 10992 35062 17552 35062 17552 35063 10992 35063 10993 35063 17552 35064 10993 35064 11211 35064 11211 35065 10993 35065 10995 35065 11211 35066 10995 35066 17553 35066 17553 35067 10995 35067 10996 35067 17553 35068 10996 35068 17554 35068 17554 35069 10996 35069 17555 35069 17554 35070 17555 35070 11210 35070 11210 35071 17555 35071 10999 35071 11210 35072 10999 35072 17556 35072 17556 35073 10999 35073 17557 35073 17556 35074 17557 35074 11209 35074 11209 35075 17557 35075 11000 35075 11209 35076 11000 35076 11207 35076 11207 35077 11000 35077 17558 35077 11207 35078 17558 35078 11206 35078 11206 35079 17558 35079 17560 35079 11206 35080 17560 35080 17559 35080 17559 35081 17560 35081 11001 35081 17559 35082 11001 35082 11204 35082 11204 35083 11001 35083 11002 35083 11204 35084 11002 35084 17561 35084 17561 35085 11002 35085 17562 35085 17561 35086 17562 35086 17564 35086 17564 35087 17562 35087 17563 35087 17564 35088 17563 35088 11202 35088 11202 35089 17563 35089 11004 35089 11202 35090 11004 35090 17565 35090 17565 35091 11004 35091 17567 35091 17565 35092 17567 35092 17566 35092 17566 35093 17567 35093 11005 35093 17566 35094 11005 35094 17568 35094 17568 35095 11005 35095 11009 35095 17568 35096 11009 35096 11199 35096 11199 35097 11009 35097 17569 35097 11199 35098 17569 35098 17570 35098 17570 35099 17569 35099 18199 35099 17570 35100 18199 35100 17544 35100 17544 35101 18199 35101 17571 35101 17544 35102 17571 35102 17542 35102 17542 35103 17571 35103 18202 35103 17542 35104 18202 35104 17572 35104 17572 35105 18202 35105 17573 35105 17572 35106 17573 35106 17540 35106 17540 35107 17573 35107 18204 35107 17540 35108 18204 35108 17574 35108 17574 35109 18204 35109 17575 35109 17574 35110 17575 35110 17538 35110 17538 35111 17575 35111 18206 35111 17538 35112 18206 35112 17576 35112 17576 35113 18206 35113 18209 35113 17576 35114 18209 35114 17577 35114 17577 35115 18209 35115 18211 35115 17577 35116 18211 35116 17578 35116 17578 35117 18211 35117 17579 35117 17578 35118 17579 35118 17534 35118 17534 35119 17579 35119 17581 35119 17534 35120 17581 35120 17580 35120 17580 35121 17581 35121 17582 35121 17580 35122 17582 35122 17533 35122 17533 35123 17582 35123 18214 35123 17533 35124 18214 35124 17583 35124 17583 35125 18214 35125 17546 35125 17584 35126 17623 35126 17640 35126 17640 35127 17623 35127 18235 35127 17640 35128 18235 35128 17585 35128 17585 35129 18235 35129 17586 35129 17585 35130 17586 35130 17641 35130 17641 35131 17586 35131 17587 35131 17641 35132 17587 35132 17588 35132 17588 35133 17587 35133 17589 35133 17588 35134 17589 35134 11171 35134 11171 35135 17589 35135 18237 35135 11171 35136 18237 35136 11173 35136 11173 35137 18237 35137 10978 35137 11173 35138 10978 35138 11174 35138 11174 35139 10978 35139 17590 35139 11174 35140 17590 35140 11176 35140 11176 35141 17590 35141 17591 35141 11176 35142 17591 35142 17592 35142 17592 35143 17591 35143 17593 35143 17592 35144 17593 35144 11178 35144 11178 35145 17593 35145 10979 35145 11178 35146 10979 35146 17594 35146 17594 35147 10979 35147 10980 35147 17594 35148 10980 35148 11182 35148 11182 35149 10980 35149 17595 35149 11182 35150 17595 35150 11185 35150 11185 35151 17595 35151 10981 35151 11185 35152 10981 35152 17596 35152 17596 35153 10981 35153 17597 35153 17596 35154 17597 35154 11187 35154 11187 35155 17597 35155 17598 35155 11187 35156 17598 35156 17599 35156 17599 35157 17598 35157 10983 35157 17599 35158 10983 35158 17600 35158 17600 35159 10983 35159 17601 35159 17600 35160 17601 35160 11189 35160 11189 35161 17601 35161 17602 35161 11189 35162 17602 35162 11191 35162 11191 35163 17602 35163 17603 35163 11191 35164 17603 35164 17604 35164 17604 35165 17603 35165 17605 35165 17604 35166 17605 35166 11194 35166 11194 35167 17605 35167 17606 35167 11194 35168 17606 35168 11196 35168 11196 35169 17606 35169 10988 35169 11196 35170 10988 35170 11198 35170 11198 35171 10988 35171 17607 35171 11198 35172 17607 35172 17624 35172 17624 35173 17607 35173 18219 35173 17624 35174 18219 35174 17625 35174 17625 35175 18219 35175 18221 35175 17625 35176 18221 35176 17608 35176 17608 35177 18221 35177 17609 35177 17608 35178 17609 35178 17627 35178 17627 35179 17609 35179 17610 35179 17627 35180 17610 35180 17628 35180 17628 35181 17610 35181 17611 35181 17628 35182 17611 35182 17612 35182 17612 35183 17611 35183 17613 35183 17612 35184 17613 35184 17614 35184 17614 35185 17613 35185 18226 35185 17614 35186 18226 35186 17615 35186 17615 35187 18226 35187 18228 35187 17615 35188 18228 35188 17631 35188 17631 35189 18228 35189 17616 35189 17631 35190 17616 35190 17618 35190 17618 35191 17616 35191 17617 35191 17618 35192 17617 35192 17632 35192 17632 35193 17617 35193 17619 35193 17632 35194 17619 35194 17634 35194 17634 35195 17619 35195 17620 35195 17634 35196 17620 35196 17635 35196 17635 35197 17620 35197 18232 35197 17635 35198 18232 35198 17621 35198 17621 35199 18232 35199 17622 35199 17621 35200 17622 35200 17584 35200 17584 35201 17622 35201 17623 35201 17649 35202 17624 35202 17625 35202 17649 35203 17625 35203 17648 35203 17648 35204 17625 35204 17608 35204 17648 35205 17608 35205 17626 35205 17626 35206 17608 35206 17627 35206 17626 35207 17627 35207 17645 35207 17645 35208 17627 35208 17628 35208 17645 35209 17628 35209 17644 35209 17644 35210 17628 35210 17612 35210 17644 35211 17612 35211 17674 35211 17674 35212 17612 35212 17614 35212 17674 35213 17614 35213 17629 35213 17629 35214 17614 35214 17615 35214 17629 35215 17615 35215 17630 35215 17630 35216 17615 35216 17631 35216 17630 35217 17631 35217 17672 35217 17672 35218 17631 35218 17618 35218 17672 35219 17618 35219 17670 35219 17670 35220 17618 35220 17632 35220 17670 35221 17632 35221 17633 35221 17633 35222 17632 35222 17634 35222 17633 35223 17634 35223 17666 35223 17666 35224 17634 35224 17635 35224 17666 35225 17635 35225 17636 35225 17636 35226 17635 35226 17621 35226 17636 35227 17621 35227 17637 35227 17637 35228 17621 35228 17584 35228 17637 35229 17584 35229 17638 35229 17638 35230 17584 35230 17640 35230 17638 35231 17640 35231 17639 35231 17639 35232 17640 35232 17585 35232 17639 35233 17585 35233 17664 35233 17664 35234 17585 35234 17641 35234 17664 35235 17641 35235 17642 35235 17642 35236 17641 35236 17588 35236 17642 35237 17588 35237 17662 35237 17662 35238 17588 35238 11171 35238 17662 35239 11171 35239 17643 35239 17674 35240 17675 35240 17644 35240 17644 35241 17675 35241 18255 35241 17644 35242 18255 35242 17645 35242 17645 35243 18255 35243 17646 35243 17645 35244 17646 35244 17626 35244 17626 35245 17646 35245 17647 35245 17626 35246 17647 35246 17648 35246 17648 35247 17647 35247 18258 35247 17648 35248 18258 35248 17649 35248 17649 35249 18258 35249 17650 35249 17649 35250 17650 35250 11197 35250 11197 35251 17650 35251 17651 35251 11197 35252 17651 35252 17653 35252 17653 35253 17651 35253 17652 35253 17653 35254 17652 35254 11195 35254 11195 35255 17652 35255 17654 35255 11195 35256 17654 35256 11193 35256 11193 35257 17654 35257 10959 35257 11193 35258 10959 35258 11192 35258 11192 35259 10959 35259 10960 35259 11192 35260 10960 35260 17655 35260 17655 35261 10960 35261 10963 35261 17655 35262 10963 35262 11190 35262 11190 35263 10963 35263 10964 35263 11190 35264 10964 35264 11188 35264 11188 35265 10964 35265 10965 35265 11188 35266 10965 35266 17656 35266 17656 35267 10965 35267 10966 35267 17656 35268 10966 35268 11186 35268 11186 35269 10966 35269 17657 35269 11186 35270 17657 35270 11184 35270 11184 35271 17657 35271 10968 35271 11184 35272 10968 35272 11183 35272 11183 35273 10968 35273 10969 35273 11183 35274 10969 35274 11181 35274 11181 35275 10969 35275 10970 35275 11181 35276 10970 35276 11180 35276 11180 35277 10970 35277 10971 35277 11180 35278 10971 35278 11179 35278 11179 35279 10971 35279 10972 35279 11179 35280 10972 35280 11177 35280 11177 35281 10972 35281 17658 35281 11177 35282 17658 35282 11175 35282 11175 35283 17658 35283 17659 35283 11175 35284 17659 35284 11172 35284 11172 35285 17659 35285 17660 35285 11172 35286 17660 35286 17643 35286 17643 35287 17660 35287 17661 35287 17643 35288 17661 35288 17662 35288 17662 35289 17661 35289 18238 35289 17662 35290 18238 35290 17642 35290 17642 35291 18238 35291 17663 35291 17642 35292 17663 35292 17664 35292 17664 35293 17663 35293 18241 35293 17664 35294 18241 35294 17639 35294 17639 35295 18241 35295 18242 35295 17639 35296 18242 35296 17638 35296 17638 35297 18242 35297 18245 35297 17638 35298 18245 35298 17637 35298 17637 35299 18245 35299 17665 35299 17637 35300 17665 35300 17636 35300 17636 35301 17665 35301 17667 35301 17636 35302 17667 35302 17666 35302 17666 35303 17667 35303 17668 35303 17666 35304 17668 35304 17633 35304 17633 35305 17668 35305 17669 35305 17633 35306 17669 35306 17670 35306 17670 35307 17669 35307 17671 35307 17670 35308 17671 35308 17672 35308 17672 35309 17671 35309 18249 35309 17672 35310 18249 35310 17630 35310 17630 35311 18249 35311 17673 35311 17630 35312 17673 35312 17629 35312 17629 35313 17673 35313 18252 35313 17629 35314 18252 35314 17674 35314 17674 35315 18252 35315 17675 35315 17731 35316 18271 35316 17733 35316 17733 35317 18271 35317 17676 35317 17733 35318 17676 35318 17677 35318 17677 35319 17676 35319 18272 35319 17677 35320 18272 35320 17678 35320 17678 35321 18272 35321 18273 35321 17678 35322 18273 35322 17736 35322 17736 35323 18273 35323 17679 35323 17736 35324 17679 35324 17680 35324 17680 35325 17679 35325 17681 35325 17680 35326 17681 35326 11152 35326 11152 35327 17681 35327 10945 35327 11152 35328 10945 35328 17683 35328 17683 35329 10945 35329 17682 35329 17683 35330 17682 35330 17684 35330 17684 35331 17682 35331 17685 35331 17684 35332 17685 35332 11154 35332 11154 35333 17685 35333 17686 35333 11154 35334 17686 35334 11156 35334 11156 35335 17686 35335 17687 35335 11156 35336 17687 35336 17688 35336 17688 35337 17687 35337 17690 35337 17688 35338 17690 35338 17689 35338 17689 35339 17690 35339 17691 35339 17689 35340 17691 35340 11158 35340 11158 35341 17691 35341 17692 35341 11158 35342 17692 35342 17693 35342 17693 35343 17692 35343 10947 35343 17693 35344 10947 35344 11159 35344 11159 35345 10947 35345 10948 35345 11159 35346 10948 35346 11161 35346 11161 35347 10948 35347 17695 35347 11161 35348 17695 35348 17694 35348 17694 35349 17695 35349 17697 35349 17694 35350 17697 35350 17696 35350 17696 35351 17697 35351 10950 35351 17696 35352 10950 35352 11163 35352 11163 35353 10950 35353 10952 35353 11163 35354 10952 35354 11164 35354 11164 35355 10952 35355 17698 35355 11164 35356 17698 35356 11165 35356 11165 35357 17698 35357 10954 35357 11165 35358 10954 35358 11167 35358 11167 35359 10954 35359 17699 35359 11167 35360 17699 35360 11168 35360 11168 35361 17699 35361 17700 35361 11168 35362 17700 35362 17701 35362 17701 35363 17700 35363 10956 35363 17701 35364 10956 35364 17717 35364 17717 35365 10956 35365 17703 35365 17717 35366 17703 35366 17702 35366 17702 35367 17703 35367 17704 35367 17702 35368 17704 35368 17719 35368 17719 35369 17704 35369 18262 35369 17719 35370 18262 35370 17705 35370 17705 35371 18262 35371 18264 35371 17705 35372 18264 35372 17706 35372 17706 35373 18264 35373 18265 35373 17706 35374 18265 35374 17707 35374 17707 35375 18265 35375 17708 35375 17707 35376 17708 35376 17722 35376 17722 35377 17708 35377 17709 35377 17722 35378 17709 35378 17710 35378 17710 35379 17709 35379 18267 35379 17710 35380 18267 35380 17711 35380 17711 35381 18267 35381 17712 35381 17711 35382 17712 35382 17725 35382 17725 35383 17712 35383 17713 35383 17725 35384 17713 35384 17727 35384 17727 35385 17713 35385 17714 35385 17727 35386 17714 35386 17728 35386 17728 35387 17714 35387 17715 35387 17728 35388 17715 35388 17729 35388 17729 35389 17715 35389 17716 35389 17729 35390 17716 35390 17731 35390 17731 35391 17716 35391 18271 35391 11170 35392 17701 35392 17717 35392 11170 35393 17717 35393 17740 35393 17740 35394 17717 35394 17702 35394 17740 35395 17702 35395 17718 35395 17718 35396 17702 35396 17719 35396 17718 35397 17719 35397 17720 35397 17720 35398 17719 35398 17705 35398 17720 35399 17705 35399 17737 35399 17737 35400 17705 35400 17706 35400 17737 35401 17706 35401 17721 35401 17721 35402 17706 35402 17707 35402 17721 35403 17707 35403 17723 35403 17723 35404 17707 35404 17722 35404 17723 35405 17722 35405 17724 35405 17724 35406 17722 35406 17710 35406 17724 35407 17710 35407 17767 35407 17767 35408 17710 35408 17711 35408 17767 35409 17711 35409 17765 35409 17765 35410 17711 35410 17725 35410 17765 35411 17725 35411 17726 35411 17726 35412 17725 35412 17727 35412 17726 35413 17727 35413 17764 35413 17764 35414 17727 35414 17728 35414 17764 35415 17728 35415 17730 35415 17730 35416 17728 35416 17729 35416 17730 35417 17729 35417 17763 35417 17763 35418 17729 35418 17731 35418 17763 35419 17731 35419 17732 35419 17732 35420 17731 35420 17733 35420 17732 35421 17733 35421 17734 35421 17734 35422 17733 35422 17677 35422 17734 35423 17677 35423 17735 35423 17735 35424 17677 35424 17678 35424 17735 35425 17678 35425 17761 35425 17761 35426 17678 35426 17736 35426 17761 35427 17736 35427 17759 35427 17759 35428 17736 35428 17680 35428 17759 35429 17680 35429 17757 35429 17721 35430 17770 35430 17737 35430 17737 35431 17770 35431 18291 35431 17737 35432 18291 35432 17720 35432 17720 35433 18291 35433 17738 35433 17720 35434 17738 35434 17718 35434 17718 35435 17738 35435 17739 35435 17718 35436 17739 35436 17740 35436 17740 35437 17739 35437 18294 35437 17740 35438 18294 35438 11170 35438 11170 35439 18294 35439 17741 35439 11170 35440 17741 35440 17742 35440 17742 35441 17741 35441 10925 35441 17742 35442 10925 35442 11169 35442 11169 35443 10925 35443 10927 35443 11169 35444 10927 35444 11166 35444 11166 35445 10927 35445 10929 35445 11166 35446 10929 35446 17743 35446 17743 35447 10929 35447 10930 35447 17743 35448 10930 35448 17744 35448 17744 35449 10930 35449 10931 35449 17744 35450 10931 35450 17745 35450 17745 35451 10931 35451 17746 35451 17745 35452 17746 35452 17747 35452 17747 35453 17746 35453 10932 35453 17747 35454 10932 35454 11162 35454 11162 35455 10932 35455 10933 35455 11162 35456 10933 35456 11160 35456 11160 35457 10933 35457 10934 35457 11160 35458 10934 35458 17748 35458 17748 35459 10934 35459 10936 35459 17748 35460 10936 35460 11157 35460 11157 35461 10936 35461 10937 35461 11157 35462 10937 35462 17749 35462 17749 35463 10937 35463 17750 35463 17749 35464 17750 35464 17751 35464 17751 35465 17750 35465 10939 35465 17751 35466 10939 35466 11155 35466 11155 35467 10939 35467 17752 35467 11155 35468 17752 35468 17753 35468 17753 35469 17752 35469 10942 35469 17753 35470 10942 35470 11153 35470 11153 35471 10942 35471 17754 35471 11153 35472 17754 35472 17755 35472 17755 35473 17754 35473 10943 35473 17755 35474 10943 35474 17756 35474 17756 35475 10943 35475 10944 35475 17756 35476 10944 35476 17757 35476 17757 35477 10944 35477 17758 35477 17757 35478 17758 35478 17759 35478 17759 35479 17758 35479 18276 35479 17759 35480 18276 35480 17761 35480 17761 35481 18276 35481 17760 35481 17761 35482 17760 35482 17735 35482 17735 35483 17760 35483 18277 35483 17735 35484 18277 35484 17734 35484 17734 35485 18277 35485 17762 35485 17734 35486 17762 35486 17732 35486 17732 35487 17762 35487 18278 35487 17732 35488 18278 35488 17763 35488 17763 35489 18278 35489 18280 35489 17763 35490 18280 35490 17730 35490 17730 35491 18280 35491 18281 35491 17730 35492 18281 35492 17764 35492 17764 35493 18281 35493 18283 35493 17764 35494 18283 35494 17726 35494 17726 35495 18283 35495 18285 35495 17726 35496 18285 35496 17765 35496 17765 35497 18285 35497 17766 35497 17765 35498 17766 35498 17767 35498 17767 35499 17766 35499 17768 35499 17767 35500 17768 35500 17724 35500 17724 35501 17768 35501 17769 35501 17724 35502 17769 35502 17723 35502 17723 35503 17769 35503 18288 35503 17723 35504 18288 35504 17721 35504 17721 35505 18288 35505 17770 35505 17771 35506 18315 35506 17772 35506 17772 35507 18315 35507 17773 35507 17772 35508 17773 35508 17774 35508 17774 35509 17773 35509 17775 35509 17774 35510 17775 35510 17818 35510 17818 35511 17775 35511 18317 35511 17818 35512 18317 35512 17820 35512 17820 35513 18317 35513 18318 35513 17820 35514 18318 35514 17776 35514 17776 35515 18318 35515 18320 35515 17776 35516 18320 35516 11129 35516 11129 35517 18320 35517 10906 35517 11129 35518 10906 35518 17777 35518 17777 35519 10906 35519 17778 35519 17777 35520 17778 35520 11130 35520 11130 35521 17778 35521 17779 35521 11130 35522 17779 35522 11132 35522 11132 35523 17779 35523 17780 35523 11132 35524 17780 35524 11135 35524 11135 35525 17780 35525 10910 35525 11135 35526 10910 35526 11137 35526 11137 35527 10910 35527 10911 35527 11137 35528 10911 35528 17781 35528 17781 35529 10911 35529 10913 35529 17781 35530 10913 35530 11139 35530 11139 35531 10913 35531 17782 35531 11139 35532 17782 35532 17783 35532 17783 35533 17782 35533 10915 35533 17783 35534 10915 35534 11142 35534 11142 35535 10915 35535 10916 35535 11142 35536 10916 35536 17784 35536 17784 35537 10916 35537 10917 35537 17784 35538 10917 35538 17785 35538 17785 35539 10917 35539 17786 35539 17785 35540 17786 35540 11146 35540 11146 35541 17786 35541 17787 35541 11146 35542 17787 35542 11147 35542 11147 35543 17787 35543 17788 35543 11147 35544 17788 35544 11149 35544 11149 35545 17788 35545 10918 35545 11149 35546 10918 35546 17789 35546 17789 35547 10918 35547 17790 35547 17789 35548 17790 35548 17791 35548 17791 35549 17790 35549 17793 35549 17791 35550 17793 35550 17792 35550 17792 35551 17793 35551 10921 35551 17792 35552 10921 35552 17803 35552 17803 35553 10921 35553 17794 35553 17803 35554 17794 35554 17804 35554 17804 35555 17794 35555 18296 35555 17804 35556 18296 35556 17805 35556 17805 35557 18296 35557 18298 35557 17805 35558 18298 35558 17795 35558 17795 35559 18298 35559 17796 35559 17795 35560 17796 35560 17808 35560 17808 35561 17796 35561 18300 35561 17808 35562 18300 35562 17797 35562 17797 35563 18300 35563 18301 35563 17797 35564 18301 35564 17798 35564 17798 35565 18301 35565 18304 35565 17798 35566 18304 35566 17809 35566 17809 35567 18304 35567 18306 35567 17809 35568 18306 35568 17811 35568 17811 35569 18306 35569 18308 35569 17811 35570 18308 35570 17799 35570 17799 35571 18308 35571 18309 35571 17799 35572 18309 35572 17813 35572 17813 35573 18309 35573 18310 35573 17813 35574 18310 35574 17800 35574 17800 35575 18310 35575 17801 35575 17800 35576 17801 35576 17802 35576 17802 35577 17801 35577 18312 35577 17802 35578 18312 35578 17816 35578 17816 35579 18312 35579 18313 35579 17816 35580 18313 35580 17771 35580 17771 35581 18313 35581 18315 35581 17827 35582 17803 35582 17804 35582 17827 35583 17804 35583 17806 35583 17806 35584 17804 35584 17805 35584 17806 35585 17805 35585 17825 35585 17825 35586 17805 35586 17795 35586 17825 35587 17795 35587 17823 35587 17823 35588 17795 35588 17808 35588 17823 35589 17808 35589 17807 35589 17807 35590 17808 35590 17797 35590 17807 35591 17797 35591 17822 35591 17822 35592 17797 35592 17798 35592 17822 35593 17798 35593 17862 35593 17862 35594 17798 35594 17809 35594 17862 35595 17809 35595 17810 35595 17810 35596 17809 35596 17811 35596 17810 35597 17811 35597 17859 35597 17859 35598 17811 35598 17799 35598 17859 35599 17799 35599 17812 35599 17812 35600 17799 35600 17813 35600 17812 35601 17813 35601 17814 35601 17814 35602 17813 35602 17800 35602 17814 35603 17800 35603 17856 35603 17856 35604 17800 35604 17802 35604 17856 35605 17802 35605 17815 35605 17815 35606 17802 35606 17816 35606 17815 35607 17816 35607 17854 35607 17854 35608 17816 35608 17771 35608 17854 35609 17771 35609 17852 35609 17852 35610 17771 35610 17772 35610 17852 35611 17772 35611 17817 35611 17817 35612 17772 35612 17774 35612 17817 35613 17774 35613 17849 35613 17849 35614 17774 35614 17818 35614 17849 35615 17818 35615 17846 35615 17846 35616 17818 35616 17820 35616 17846 35617 17820 35617 17819 35617 17819 35618 17820 35618 17776 35618 17819 35619 17776 35619 17821 35619 17822 35620 18329 35620 17807 35620 17807 35621 18329 35621 18330 35621 17807 35622 18330 35622 17823 35622 17823 35623 18330 35623 17824 35623 17823 35624 17824 35624 17825 35624 17825 35625 17824 35625 18333 35625 17825 35626 18333 35626 17806 35626 17806 35627 18333 35627 17826 35627 17806 35628 17826 35628 17827 35628 17827 35629 17826 35629 17828 35629 17827 35630 17828 35630 17829 35630 17829 35631 17828 35631 17830 35631 17829 35632 17830 35632 11151 35632 11151 35633 17830 35633 17831 35633 11151 35634 17831 35634 11150 35634 11150 35635 17831 35635 17832 35635 11150 35636 17832 35636 17833 35636 17833 35637 17832 35637 17834 35637 17833 35638 17834 35638 17835 35638 17835 35639 17834 35639 17836 35639 17835 35640 17836 35640 11148 35640 11148 35641 17836 35641 10894 35641 11148 35642 10894 35642 11145 35642 11145 35643 10894 35643 10895 35643 11145 35644 10895 35644 11144 35644 11144 35645 10895 35645 17837 35645 11144 35646 17837 35646 11143 35646 11143 35647 17837 35647 10897 35647 11143 35648 10897 35648 11141 35648 11141 35649 10897 35649 17838 35649 11141 35650 17838 35650 11140 35650 11140 35651 17838 35651 17839 35651 11140 35652 17839 35652 11138 35652 11138 35653 17839 35653 10899 35653 11138 35654 10899 35654 17840 35654 17840 35655 10899 35655 10900 35655 17840 35656 10900 35656 11136 35656 11136 35657 10900 35657 17841 35657 11136 35658 17841 35658 11134 35658 11134 35659 17841 35659 10902 35659 11134 35660 10902 35660 11133 35660 11133 35661 10902 35661 17842 35661 11133 35662 17842 35662 11131 35662 11131 35663 17842 35663 17843 35663 11131 35664 17843 35664 17844 35664 17844 35665 17843 35665 10905 35665 17844 35666 10905 35666 17821 35666 17821 35667 10905 35667 17845 35667 17821 35668 17845 35668 17819 35668 17819 35669 17845 35669 17847 35669 17819 35670 17847 35670 17846 35670 17846 35671 17847 35671 17848 35671 17846 35672 17848 35672 17849 35672 17849 35673 17848 35673 17850 35673 17849 35674 17850 35674 17817 35674 17817 35675 17850 35675 17851 35675 17817 35676 17851 35676 17852 35676 17852 35677 17851 35677 17853 35677 17852 35678 17853 35678 17854 35678 17854 35679 17853 35679 18323 35679 17854 35680 18323 35680 17815 35680 17815 35681 18323 35681 17855 35681 17815 35682 17855 35682 17856 35682 17856 35683 17855 35683 18324 35683 17856 35684 18324 35684 17814 35684 17814 35685 18324 35685 17857 35685 17814 35686 17857 35686 17812 35686 17812 35687 17857 35687 17858 35687 17812 35688 17858 35688 17859 35688 17859 35689 17858 35689 17860 35689 17859 35690 17860 35690 17810 35690 17810 35691 17860 35691 17861 35691 17810 35692 17861 35692 17862 35692 17862 35693 17861 35693 18327 35693 17862 35694 18327 35694 17822 35694 17822 35695 18327 35695 18329 35695 17908 35696 17864 35696 17863 35696 17863 35697 17864 35697 17865 35697 17863 35698 17865 35698 17909 35698 17909 35699 17865 35699 18348 35699 17909 35700 18348 35700 17866 35700 17866 35701 18348 35701 18349 35701 17866 35702 18349 35702 17911 35702 17911 35703 18349 35703 17867 35703 17911 35704 17867 35704 17913 35704 17913 35705 17867 35705 17868 35705 17913 35706 17868 35706 11108 35706 11108 35707 17868 35707 10877 35707 11108 35708 10877 35708 11109 35708 11109 35709 10877 35709 10878 35709 11109 35710 10878 35710 11111 35710 11111 35711 10878 35711 10879 35711 11111 35712 10879 35712 11113 35712 11113 35713 10879 35713 10880 35713 11113 35714 10880 35714 11114 35714 11114 35715 10880 35715 17869 35715 11114 35716 17869 35716 11115 35716 11115 35717 17869 35717 17870 35717 11115 35718 17870 35718 11116 35718 11116 35719 17870 35719 10882 35719 11116 35720 10882 35720 11117 35720 11117 35721 10882 35721 17871 35721 11117 35722 17871 35722 11119 35722 11119 35723 17871 35723 10884 35723 11119 35724 10884 35724 17872 35724 17872 35725 10884 35725 10885 35725 17872 35726 10885 35726 11121 35726 11121 35727 10885 35727 17873 35727 11121 35728 17873 35728 17874 35728 17874 35729 17873 35729 10886 35729 17874 35730 10886 35730 11124 35730 11124 35731 10886 35731 17875 35731 11124 35732 17875 35732 11126 35732 11126 35733 17875 35733 17876 35733 11126 35734 17876 35734 17877 35734 17877 35735 17876 35735 10887 35735 17877 35736 10887 35736 17878 35736 17878 35737 10887 35737 17879 35737 17878 35738 17879 35738 17880 35738 17880 35739 17879 35739 10888 35739 17880 35740 10888 35740 17881 35740 17881 35741 10888 35741 10889 35741 17881 35742 10889 35742 17882 35742 17882 35743 10889 35743 17883 35743 17882 35744 17883 35744 17884 35744 17884 35745 17883 35745 17885 35745 17884 35746 17885 35746 17897 35746 17897 35747 17885 35747 17886 35747 17897 35748 17886 35748 17887 35748 17887 35749 17886 35749 18334 35749 17887 35750 18334 35750 17899 35750 17899 35751 18334 35751 17888 35751 17899 35752 17888 35752 17889 35752 17889 35753 17888 35753 18336 35753 17889 35754 18336 35754 17901 35754 17901 35755 18336 35755 17890 35755 17901 35756 17890 35756 17902 35756 17902 35757 17890 35757 17891 35757 17902 35758 17891 35758 17893 35758 17893 35759 17891 35759 17892 35759 17893 35760 17892 35760 17894 35760 17894 35761 17892 35761 17895 35761 17894 35762 17895 35762 17904 35762 17904 35763 17895 35763 18341 35763 17904 35764 18341 35764 17905 35764 17905 35765 18341 35765 18342 35765 17905 35766 18342 35766 17906 35766 17906 35767 18342 35767 17896 35767 17906 35768 17896 35768 17907 35768 17907 35769 17896 35769 18344 35769 17907 35770 18344 35770 17908 35770 17908 35771 18344 35771 17864 35771 17917 35772 17882 35772 17884 35772 17917 35773 17884 35773 17915 35773 17915 35774 17884 35774 17897 35774 17915 35775 17897 35775 17898 35775 17898 35776 17897 35776 17887 35776 17898 35777 17887 35777 17914 35777 17914 35778 17887 35778 17899 35778 17914 35779 17899 35779 17900 35779 17900 35780 17899 35780 17889 35780 17900 35781 17889 35781 17954 35781 17954 35782 17889 35782 17901 35782 17954 35783 17901 35783 17953 35783 17953 35784 17901 35784 17902 35784 17953 35785 17902 35785 17903 35785 17903 35786 17902 35786 17893 35786 17903 35787 17893 35787 17952 35787 17952 35788 17893 35788 17894 35788 17952 35789 17894 35789 17951 35789 17951 35790 17894 35790 17904 35790 17951 35791 17904 35791 17949 35791 17949 35792 17904 35792 17905 35792 17949 35793 17905 35793 17947 35793 17947 35794 17905 35794 17906 35794 17947 35795 17906 35795 17946 35795 17946 35796 17906 35796 17907 35796 17946 35797 17907 35797 17944 35797 17944 35798 17907 35798 17908 35798 17944 35799 17908 35799 17943 35799 17943 35800 17908 35800 17863 35800 17943 35801 17863 35801 17940 35801 17940 35802 17863 35802 17909 35802 17940 35803 17909 35803 17937 35803 17937 35804 17909 35804 17866 35804 17937 35805 17866 35805 17910 35805 17910 35806 17866 35806 17911 35806 17910 35807 17911 35807 17912 35807 17912 35808 17911 35808 17913 35808 17912 35809 17913 35809 11107 35809 17954 35810 18366 35810 17900 35810 17900 35811 18366 35811 18367 35811 17900 35812 18367 35812 17914 35812 17914 35813 18367 35813 18369 35813 17914 35814 18369 35814 17898 35814 17898 35815 18369 35815 18370 35815 17898 35816 18370 35816 17915 35816 17915 35817 18370 35817 17916 35817 17915 35818 17916 35818 17917 35818 17917 35819 17916 35819 10858 35819 17917 35820 10858 35820 17918 35820 17918 35821 10858 35821 17919 35821 17918 35822 17919 35822 11128 35822 11128 35823 17919 35823 17920 35823 11128 35824 17920 35824 17921 35824 17921 35825 17920 35825 10860 35825 17921 35826 10860 35826 11127 35826 11127 35827 10860 35827 17922 35827 11127 35828 17922 35828 17923 35828 17923 35829 17922 35829 17924 35829 17923 35830 17924 35830 11125 35830 11125 35831 17924 35831 10863 35831 11125 35832 10863 35832 11123 35832 11123 35833 10863 35833 10864 35833 11123 35834 10864 35834 11122 35834 11122 35835 10864 35835 17926 35835 11122 35836 17926 35836 17925 35836 17925 35837 17926 35837 17927 35837 17925 35838 17927 35838 11120 35838 11120 35839 17927 35839 10867 35839 11120 35840 10867 35840 11118 35840 11118 35841 10867 35841 10869 35841 11118 35842 10869 35842 17928 35842 17928 35843 10869 35843 17929 35843 17928 35844 17929 35844 17930 35844 17930 35845 17929 35845 10870 35845 17930 35846 10870 35846 17931 35846 17931 35847 10870 35847 10871 35847 17931 35848 10871 35848 17932 35848 17932 35849 10871 35849 10872 35849 17932 35850 10872 35850 11112 35850 11112 35851 10872 35851 17933 35851 11112 35852 17933 35852 11110 35852 11110 35853 17933 35853 10874 35853 11110 35854 10874 35854 17934 35854 17934 35855 10874 35855 17935 35855 17934 35856 17935 35856 11107 35856 11107 35857 17935 35857 17936 35857 11107 35858 17936 35858 17912 35858 17912 35859 17936 35859 18353 35859 17912 35860 18353 35860 17910 35860 17910 35861 18353 35861 17938 35861 17910 35862 17938 35862 17937 35862 17937 35863 17938 35863 17939 35863 17937 35864 17939 35864 17940 35864 17940 35865 17939 35865 17941 35865 17940 35866 17941 35866 17943 35866 17943 35867 17941 35867 17942 35867 17943 35868 17942 35868 17944 35868 17944 35869 17942 35869 17945 35869 17944 35870 17945 35870 17946 35870 17946 35871 17945 35871 18355 35871 17946 35872 18355 35872 17947 35872 17947 35873 18355 35873 17948 35873 17947 35874 17948 35874 17949 35874 17949 35875 17948 35875 17950 35875 17949 35876 17950 35876 17951 35876 17951 35877 17950 35877 18359 35877 17951 35878 18359 35878 17952 35878 17952 35879 18359 35879 18360 35879 17952 35880 18360 35880 17903 35880 17903 35881 18360 35881 18362 35881 17903 35882 18362 35882 17953 35882 17953 35883 18362 35883 18363 35883 17953 35884 18363 35884 17954 35884 17954 35885 18363 35885 18366 35885 17955 35886 18388 35886 17992 35886 17992 35887 18388 35887 17956 35887 17992 35888 17956 35888 17994 35888 17994 35889 17956 35889 18390 35889 17994 35890 18390 35890 17957 35890 17957 35891 18390 35891 18391 35891 17957 35892 18391 35892 17996 35892 17996 35893 18391 35893 18393 35893 17996 35894 18393 35894 17997 35894 17997 35895 18393 35895 17958 35895 17997 35896 17958 35896 11085 35896 11085 35897 17958 35897 10838 35897 11085 35898 10838 35898 11086 35898 11086 35899 10838 35899 10840 35899 11086 35900 10840 35900 11088 35900 11088 35901 10840 35901 17959 35901 11088 35902 17959 35902 11090 35902 11090 35903 17959 35903 17961 35903 11090 35904 17961 35904 17960 35904 17960 35905 17961 35905 10841 35905 17960 35906 10841 35906 17962 35906 17962 35907 10841 35907 10842 35907 17962 35908 10842 35908 11093 35908 11093 35909 10842 35909 17963 35909 11093 35910 17963 35910 17964 35910 17964 35911 17963 35911 10844 35911 17964 35912 10844 35912 11094 35912 11094 35913 10844 35913 10846 35913 11094 35914 10846 35914 17966 35914 17966 35915 10846 35915 17965 35915 17966 35916 17965 35916 11096 35916 11096 35917 17965 35917 10847 35917 11096 35918 10847 35918 11097 35918 11097 35919 10847 35919 10849 35919 11097 35920 10849 35920 11099 35920 11099 35921 10849 35921 17967 35921 11099 35922 17967 35922 11100 35922 11100 35923 17967 35923 17968 35923 11100 35924 17968 35924 11101 35924 11101 35925 17968 35925 17969 35925 11101 35926 17969 35926 11102 35926 11102 35927 17969 35927 10853 35927 11102 35928 10853 35928 11105 35928 11105 35929 10853 35929 17971 35929 11105 35930 17971 35930 17970 35930 17970 35931 17971 35931 10856 35931 17970 35932 10856 35932 11106 35932 11106 35933 10856 35933 10857 35933 11106 35934 10857 35934 17972 35934 17972 35935 10857 35935 18372 35935 17972 35936 18372 35936 17973 35936 17973 35937 18372 35937 18374 35937 17973 35938 18374 35938 17974 35938 17974 35939 18374 35939 17975 35939 17974 35940 17975 35940 17986 35940 17986 35941 17975 35941 17976 35941 17986 35942 17976 35942 17977 35942 17977 35943 17976 35943 18376 35943 17977 35944 18376 35944 17978 35944 17978 35945 18376 35945 18377 35945 17978 35946 18377 35946 17979 35946 17979 35947 18377 35947 18379 35947 17979 35948 18379 35948 17988 35948 17988 35949 18379 35949 18381 35949 17988 35950 18381 35950 17980 35950 17980 35951 18381 35951 17982 35951 17980 35952 17982 35952 17981 35952 17981 35953 17982 35953 17983 35953 17981 35954 17983 35954 17984 35954 17984 35955 17983 35955 18383 35955 17984 35956 18383 35956 17989 35956 17989 35957 18383 35957 18385 35957 17989 35958 18385 35958 17990 35958 17990 35959 18385 35959 17985 35959 17990 35960 17985 35960 17955 35960 17955 35961 17985 35961 18388 35961 18005 35962 11106 35962 17972 35962 18005 35963 17972 35963 18003 35963 18003 35964 17972 35964 17973 35964 18003 35965 17973 35965 18001 35965 18001 35966 17973 35966 17974 35966 18001 35967 17974 35967 18000 35967 18000 35968 17974 35968 17986 35968 18000 35969 17986 35969 17999 35969 17999 35970 17986 35970 17977 35970 17999 35971 17977 35971 17998 35971 17998 35972 17977 35972 17978 35972 17998 35973 17978 35973 18035 35973 18035 35974 17978 35974 17979 35974 18035 35975 17979 35975 17987 35975 17987 35976 17979 35976 17988 35976 17987 35977 17988 35977 18034 35977 18034 35978 17988 35978 17980 35978 18034 35979 17980 35979 18033 35979 18033 35980 17980 35980 17981 35980 18033 35981 17981 35981 18032 35981 18032 35982 17981 35982 17984 35982 18032 35983 17984 35983 18030 35983 18030 35984 17984 35984 17989 35984 18030 35985 17989 35985 18029 35985 18029 35986 17989 35986 17990 35986 18029 35987 17990 35987 17991 35987 17991 35988 17990 35988 17955 35988 17991 35989 17955 35989 18027 35989 18027 35990 17955 35990 17992 35990 18027 35991 17992 35991 17993 35991 17993 35992 17992 35992 17994 35992 17993 35993 17994 35993 18025 35993 18025 35994 17994 35994 17957 35994 18025 35995 17957 35995 17995 35995 17995 35996 17957 35996 17996 35996 17995 35997 17996 35997 18023 35997 18023 35998 17996 35998 17997 35998 18023 35999 17997 35999 11084 35999 17998 36000 18410 36000 17999 36000 17999 36001 18410 36001 18412 36001 17999 36002 18412 36002 18000 36002 18000 36003 18412 36003 18413 36003 18000 36004 18413 36004 18001 36004 18001 36005 18413 36005 18002 36005 18001 36006 18002 36006 18003 36006 18003 36007 18002 36007 18004 36007 18003 36008 18004 36008 18005 36008 18005 36009 18004 36009 18416 36009 18005 36010 18416 36010 18006 36010 18006 36011 18416 36011 18008 36011 18006 36012 18008 36012 18007 36012 18007 36013 18008 36013 18009 36013 18007 36014 18009 36014 11104 36014 11104 36015 18009 36015 10815 36015 11104 36016 10815 36016 11103 36016 11103 36017 10815 36017 10816 36017 11103 36018 10816 36018 18010 36018 18010 36019 10816 36019 10818 36019 18010 36020 10818 36020 11098 36020 11098 36021 10818 36021 18012 36021 11098 36022 18012 36022 18011 36022 18011 36023 18012 36023 10820 36023 18011 36024 10820 36024 18013 36024 18013 36025 10820 36025 18015 36025 18013 36026 18015 36026 18014 36026 18014 36027 18015 36027 18016 36027 18014 36028 18016 36028 11095 36028 11095 36029 18016 36029 10823 36029 11095 36030 10823 36030 18017 36030 18017 36031 10823 36031 10826 36031 18017 36032 10826 36032 18018 36032 18018 36033 10826 36033 10827 36033 18018 36034 10827 36034 11092 36034 11092 36035 10827 36035 10828 36035 11092 36036 10828 36036 18019 36036 18019 36037 10828 36037 18020 36037 18019 36038 18020 36038 11091 36038 11091 36039 18020 36039 18021 36039 11091 36040 18021 36040 18022 36040 18022 36041 18021 36041 10832 36041 18022 36042 10832 36042 11089 36042 11089 36043 10832 36043 10834 36043 11089 36044 10834 36044 11087 36044 11087 36045 10834 36045 10835 36045 11087 36046 10835 36046 11084 36046 11084 36047 10835 36047 18395 36047 11084 36048 18395 36048 18023 36048 18023 36049 18395 36049 18024 36049 18023 36050 18024 36050 17995 36050 17995 36051 18024 36051 18396 36051 17995 36052 18396 36052 18025 36052 18025 36053 18396 36053 18026 36053 18025 36054 18026 36054 17993 36054 17993 36055 18026 36055 18397 36055 17993 36056 18397 36056 18027 36056 18027 36057 18397 36057 18398 36057 18027 36058 18398 36058 17991 36058 17991 36059 18398 36059 18028 36059 17991 36060 18028 36060 18029 36060 18029 36061 18028 36061 18400 36061 18029 36062 18400 36062 18030 36062 18030 36063 18400 36063 18031 36063 18030 36064 18031 36064 18032 36064 18032 36065 18031 36065 18403 36065 18032 36066 18403 36066 18033 36066 18033 36067 18403 36067 18404 36067 18033 36068 18404 36068 18034 36068 18034 36069 18404 36069 18405 36069 18034 36070 18405 36070 17987 36070 17987 36071 18405 36071 18406 36071 17987 36072 18406 36072 18035 36072 18035 36073 18406 36073 18407 36073 18035 36074 18407 36074 17998 36074 17998 36075 18407 36075 18410 36075 18087 36076 18070 36076 18089 36076 18089 36077 18070 36077 18436 36077 18089 36078 18436 36078 18090 36078 18090 36079 18436 36079 18438 36079 18090 36080 18438 36080 18091 36080 18091 36081 18438 36081 18036 36081 18091 36082 18036 36082 18093 36082 18093 36083 18036 36083 18439 36083 18093 36084 18439 36084 18094 36084 18094 36085 18439 36085 18440 36085 18094 36086 18440 36086 18037 36086 18037 36087 18440 36087 10798 36087 18037 36088 10798 36088 11069 36088 11069 36089 10798 36089 18038 36089 11069 36090 18038 36090 11070 36090 11070 36091 18038 36091 18039 36091 11070 36092 18039 36092 11071 36092 11071 36093 18039 36093 18040 36093 11071 36094 18040 36094 11072 36094 11072 36095 18040 36095 18041 36095 11072 36096 18041 36096 18042 36096 18042 36097 18041 36097 18043 36097 18042 36098 18043 36098 18044 36098 18044 36099 18043 36099 10801 36099 18044 36100 10801 36100 18045 36100 18045 36101 10801 36101 10803 36101 18045 36102 10803 36102 18046 36102 18046 36103 10803 36103 18048 36103 18046 36104 18048 36104 18047 36104 18047 36105 18048 36105 18049 36105 18047 36106 18049 36106 11074 36106 11074 36107 18049 36107 10805 36107 11074 36108 10805 36108 11076 36108 11076 36109 10805 36109 18050 36109 11076 36110 18050 36110 18051 36110 18051 36111 18050 36111 18052 36111 18051 36112 18052 36112 18053 36112 18053 36113 18052 36113 18054 36113 18053 36114 18054 36114 11077 36114 11077 36115 18054 36115 10809 36115 11077 36116 10809 36116 18055 36116 18055 36117 10809 36117 10810 36117 18055 36118 10810 36118 11079 36118 11079 36119 10810 36119 10811 36119 11079 36120 10811 36120 11081 36120 11081 36121 10811 36121 18056 36121 11081 36122 18056 36122 11083 36122 11083 36123 18056 36123 18058 36123 11083 36124 18058 36124 18057 36124 18057 36125 18058 36125 18418 36125 18057 36126 18418 36126 18059 36126 18059 36127 18418 36127 18060 36127 18059 36128 18060 36128 18061 36128 18061 36129 18060 36129 18062 36129 18061 36130 18062 36130 18063 36130 18063 36131 18062 36131 18421 36131 18063 36132 18421 36132 18076 36132 18076 36133 18421 36133 18423 36133 18076 36134 18423 36134 18077 36134 18077 36135 18423 36135 18424 36135 18077 36136 18424 36136 18064 36136 18064 36137 18424 36137 18065 36137 18064 36138 18065 36138 18080 36138 18080 36139 18065 36139 18427 36139 18080 36140 18427 36140 18066 36140 18066 36141 18427 36141 18067 36141 18066 36142 18067 36142 18082 36142 18082 36143 18067 36143 18429 36143 18082 36144 18429 36144 18085 36144 18085 36145 18429 36145 18068 36145 18085 36146 18068 36146 18069 36146 18069 36147 18068 36147 18431 36147 18069 36148 18431 36148 18086 36148 18086 36149 18431 36149 18432 36149 18086 36150 18432 36150 18087 36150 18087 36151 18432 36151 18070 36151 18071 36152 11083 36152 18057 36152 18071 36153 18057 36153 18072 36153 18072 36154 18057 36154 18059 36154 18072 36155 18059 36155 18073 36155 18073 36156 18059 36156 18061 36156 18073 36157 18061 36157 18074 36157 18074 36158 18061 36158 18063 36158 18074 36159 18063 36159 18096 36159 18096 36160 18063 36160 18076 36160 18096 36161 18076 36161 18075 36161 18075 36162 18076 36162 18077 36162 18075 36163 18077 36163 18134 36163 18134 36164 18077 36164 18064 36164 18134 36165 18064 36165 18078 36165 18078 36166 18064 36166 18080 36166 18078 36167 18080 36167 18079 36167 18079 36168 18080 36168 18066 36168 18079 36169 18066 36169 18081 36169 18081 36170 18066 36170 18082 36170 18081 36171 18082 36171 18083 36171 18083 36172 18082 36172 18085 36172 18083 36173 18085 36173 18084 36173 18084 36174 18085 36174 18069 36174 18084 36175 18069 36175 18131 36175 18131 36176 18069 36176 18086 36176 18131 36177 18086 36177 18128 36177 18128 36178 18086 36178 18087 36178 18128 36179 18087 36179 18088 36179 18088 36180 18087 36180 18089 36180 18088 36181 18089 36181 18126 36181 18126 36182 18089 36182 18090 36182 18126 36183 18090 36183 18124 36183 18124 36184 18090 36184 18091 36184 18124 36185 18091 36185 18092 36185 18092 36186 18091 36186 18093 36186 18092 36187 18093 36187 18121 36187 18121 36188 18093 36188 18094 36188 18121 36189 18094 36189 11067 36189 18075 36190 18095 36190 18096 36190 18096 36191 18095 36191 18097 36191 18096 36192 18097 36192 18074 36192 18074 36193 18097 36193 18449 36193 18074 36194 18449 36194 18073 36194 18073 36195 18449 36195 18450 36195 18073 36196 18450 36196 18072 36196 18072 36197 18450 36197 18098 36197 18072 36198 18098 36198 18071 36198 18071 36199 18098 36199 18453 36199 18071 36200 18453 36200 11082 36200 11082 36201 18453 36201 18099 36201 11082 36202 18099 36202 11080 36202 11080 36203 18099 36203 10780 36203 11080 36204 10780 36204 11078 36204 11078 36205 10780 36205 10781 36205 11078 36206 10781 36206 18100 36206 18100 36207 10781 36207 10783 36207 18100 36208 10783 36208 18101 36208 18101 36209 10783 36209 10784 36209 18101 36210 10784 36210 18102 36210 18102 36211 10784 36211 18103 36211 18102 36212 18103 36212 18104 36212 18104 36213 18103 36213 10787 36213 18104 36214 10787 36214 11075 36214 11075 36215 10787 36215 18105 36215 11075 36216 18105 36216 18106 36216 18106 36217 18105 36217 10788 36217 18106 36218 10788 36218 11073 36218 11073 36219 10788 36219 10789 36219 11073 36220 10789 36220 18107 36220 18107 36221 10789 36221 18109 36221 18107 36222 18109 36222 18108 36222 18108 36223 18109 36223 18110 36223 18108 36224 18110 36224 18111 36224 18111 36225 18110 36225 18112 36225 18111 36226 18112 36226 18113 36226 18113 36227 18112 36227 18114 36227 18113 36228 18114 36228 18115 36228 18115 36229 18114 36229 18117 36229 18115 36230 18117 36230 18116 36230 18116 36231 18117 36231 10794 36231 18116 36232 10794 36232 18119 36232 18119 36233 10794 36233 18118 36233 18119 36234 18118 36234 11068 36234 11068 36235 18118 36235 18120 36235 11068 36236 18120 36236 11067 36236 11067 36237 18120 36237 10797 36237 11067 36238 10797 36238 18121 36238 18121 36239 10797 36239 18122 36239 18121 36240 18122 36240 18092 36240 18092 36241 18122 36241 18123 36241 18092 36242 18123 36242 18124 36242 18124 36243 18123 36243 18125 36243 18124 36244 18125 36244 18126 36244 18126 36245 18125 36245 18127 36245 18126 36246 18127 36246 18088 36246 18088 36247 18127 36247 18129 36247 18088 36248 18129 36248 18128 36248 18128 36249 18129 36249 18130 36249 18128 36250 18130 36250 18131 36250 18131 36251 18130 36251 18442 36251 18131 36252 18442 36252 18084 36252 18084 36253 18442 36253 18443 36253 18084 36254 18443 36254 18083 36254 18083 36255 18443 36255 18444 36255 18083 36256 18444 36256 18081 36256 18081 36257 18444 36257 18132 36257 18081 36258 18132 36258 18079 36258 18079 36259 18132 36259 18133 36259 18079 36260 18133 36260 18078 36260 18078 36261 18133 36261 18445 36261 18078 36262 18445 36262 18134 36262 18134 36263 18445 36263 18447 36263 18134 36264 18447 36264 18075 36264 18075 36265 18447 36265 18095 36265 18135 36266 11066 36266 18136 36266 18135 36267 18136 36267 18137 36267 18137 36268 18136 36268 18138 36268 18137 36269 18138 36269 18139 36269 18139 36270 18138 36270 15690 36270 18139 36271 15690 36271 18140 36271 18140 36272 15690 36272 15691 36272 18140 36273 15691 36273 18141 36273 18141 36274 15691 36274 15693 36274 18141 36275 15693 36275 17417 36275 17417 36276 15693 36276 18143 36276 17417 36277 18143 36277 18142 36277 18142 36278 18143 36278 18144 36278 18142 36279 18144 36279 17420 36279 17420 36280 18144 36280 15695 36280 17420 36281 15695 36281 17421 36281 17421 36282 15695 36282 18145 36282 17421 36283 18145 36283 18146 36283 18146 36284 18145 36284 18148 36284 18146 36285 18148 36285 18147 36285 18147 36286 18148 36286 15697 36286 18147 36287 15697 36287 18149 36287 18149 36288 15697 36288 18150 36288 18149 36289 18150 36289 17426 36289 17426 36290 18150 36290 18151 36290 17426 36291 18151 36291 18152 36291 18152 36292 18151 36292 18153 36292 18152 36293 18153 36293 17384 36293 17384 36294 18153 36294 18154 36294 17384 36295 18154 36295 17385 36295 17385 36296 18154 36296 18155 36296 17385 36297 18155 36297 17386 36297 17386 36298 18155 36298 18156 36298 17386 36299 18156 36299 18157 36299 18157 36300 18156 36300 15703 36300 18157 36301 15703 36301 18159 36301 18159 36302 15703 36302 18158 36302 18159 36303 18158 36303 17391 36303 11048 36304 11047 36304 18160 36304 11048 36305 18160 36305 17469 36305 17469 36306 18160 36306 18162 36306 17469 36307 18162 36307 18161 36307 18161 36308 18162 36308 15686 36308 18161 36309 15686 36309 17470 36309 17470 36310 15686 36310 18163 36310 17470 36311 18163 36311 17472 36311 17472 36312 18163 36312 15685 36312 17472 36313 15685 36313 18164 36313 18164 36314 15685 36314 15684 36314 18164 36315 15684 36315 17473 36315 17473 36316 15684 36316 15683 36316 17473 36317 15683 36317 17475 36317 17475 36318 15683 36318 18165 36318 17475 36319 18165 36319 17477 36319 17477 36320 18165 36320 15682 36320 17477 36321 15682 36321 18166 36321 18166 36322 15682 36322 15678 36322 18166 36323 15678 36323 18167 36323 18167 36324 15678 36324 15677 36324 18167 36325 15677 36325 18168 36325 18168 36326 15677 36326 18169 36326 18168 36327 18169 36327 17479 36327 17479 36328 18169 36328 18170 36328 17479 36329 18170 36329 18171 36329 18171 36330 18170 36330 18172 36330 18171 36331 18172 36331 17482 36331 17482 36332 18172 36332 15674 36332 17482 36333 15674 36333 18173 36333 18173 36334 15674 36334 18174 36334 18173 36335 18174 36335 18175 36335 18175 36336 18174 36336 18177 36336 18175 36337 18177 36337 18176 36337 18176 36338 18177 36338 15671 36338 18176 36339 15671 36339 17443 36339 17443 36340 15671 36340 15670 36340 17443 36341 15670 36341 17445 36341 17511 36342 15672 36342 18179 36342 17511 36343 18179 36343 18178 36343 18178 36344 18179 36344 18180 36344 18178 36345 18180 36345 18182 36345 18182 36346 18180 36346 18181 36346 18182 36347 18181 36347 17513 36347 17513 36348 18181 36348 15673 36348 17513 36349 15673 36349 18183 36349 18183 36350 15673 36350 15675 36350 18183 36351 15675 36351 17517 36351 17517 36352 15675 36352 15676 36352 17517 36353 15676 36353 17519 36353 17519 36354 15676 36354 18184 36354 17519 36355 18184 36355 17520 36355 17520 36356 18184 36356 15679 36356 17520 36357 15679 36357 18185 36357 18185 36358 15679 36358 15680 36358 18185 36359 15680 36359 17522 36359 17522 36360 15680 36360 15681 36360 17522 36361 15681 36361 17523 36361 17523 36362 15681 36362 18186 36362 17523 36363 18186 36363 17524 36363 17524 36364 18186 36364 18187 36364 17524 36365 18187 36365 17526 36365 17526 36366 18187 36366 18188 36366 17526 36367 18188 36367 18189 36367 18189 36368 18188 36368 18190 36368 18189 36369 18190 36369 18191 36369 18191 36370 18190 36370 18193 36370 18191 36371 18193 36371 18192 36371 18192 36372 18193 36372 15687 36372 18192 36373 15687 36373 17484 36373 17484 36374 15687 36374 18194 36374 17484 36375 18194 36375 17486 36375 17486 36376 18194 36376 18195 36376 17486 36377 18195 36377 18197 36377 18197 36378 18195 36378 18196 36378 18197 36379 18196 36379 17487 36379 17569 36380 11008 36380 18198 36380 17569 36381 18198 36381 18199 36381 18199 36382 18198 36382 18200 36382 18199 36383 18200 36383 17571 36383 17571 36384 18200 36384 18201 36384 17571 36385 18201 36385 18202 36385 18202 36386 18201 36386 18203 36386 18202 36387 18203 36387 17573 36387 17573 36388 18203 36388 15666 36388 17573 36389 15666 36389 18204 36389 18204 36390 15666 36390 18205 36390 18204 36391 18205 36391 17575 36391 17575 36392 18205 36392 18207 36392 17575 36393 18207 36393 18206 36393 18206 36394 18207 36394 18208 36394 18206 36395 18208 36395 18209 36395 18209 36396 18208 36396 15663 36396 18209 36397 15663 36397 18211 36397 18211 36398 15663 36398 18210 36398 18211 36399 18210 36399 17579 36399 17579 36400 18210 36400 18212 36400 17579 36401 18212 36401 17581 36401 17581 36402 18212 36402 15662 36402 17581 36403 15662 36403 17582 36403 17582 36404 15662 36404 18213 36404 17582 36405 18213 36405 18214 36405 18214 36406 18213 36406 15661 36406 18214 36407 15661 36407 17546 36407 17546 36408 15661 36408 18215 36408 17546 36409 18215 36409 17547 36409 17547 36410 18215 36410 15660 36410 17547 36411 15660 36411 18216 36411 18216 36412 15660 36412 18217 36412 18216 36413 18217 36413 17550 36413 17550 36414 18217 36414 15658 36414 17550 36415 15658 36415 18218 36415 18218 36416 15658 36416 10991 36416 18218 36417 10991 36417 10990 36417 18219 36418 10989 36418 18220 36418 18219 36419 18220 36419 18221 36419 18221 36420 18220 36420 18222 36420 18221 36421 18222 36421 17609 36421 17609 36422 18222 36422 15659 36422 17609 36423 15659 36423 17610 36423 17610 36424 15659 36424 18223 36424 17610 36425 18223 36425 17611 36425 17611 36426 18223 36426 18224 36426 17611 36427 18224 36427 17613 36427 17613 36428 18224 36428 18225 36428 17613 36429 18225 36429 18226 36429 18226 36430 18225 36430 18227 36430 18226 36431 18227 36431 18228 36431 18228 36432 18227 36432 18229 36432 18228 36433 18229 36433 17616 36433 17616 36434 18229 36434 18230 36434 17616 36435 18230 36435 17617 36435 17617 36436 18230 36436 15664 36436 17617 36437 15664 36437 17619 36437 17619 36438 15664 36438 18231 36438 17619 36439 18231 36439 17620 36439 17620 36440 18231 36440 18233 36440 17620 36441 18233 36441 18232 36441 18232 36442 18233 36442 15665 36442 18232 36443 15665 36443 17622 36443 17622 36444 15665 36444 18234 36444 17622 36445 18234 36445 17623 36445 17623 36446 18234 36446 15667 36446 17623 36447 15667 36447 18235 36447 18235 36448 15667 36448 15668 36448 18235 36449 15668 36449 17586 36449 17586 36450 15668 36450 18236 36450 17586 36451 18236 36451 17587 36451 17587 36452 18236 36452 15669 36452 17587 36453 15669 36453 17589 36453 17589 36454 15669 36454 12246 36454 17589 36455 12246 36455 18237 36455 17661 36456 10976 36456 18239 36456 17661 36457 18239 36457 18238 36457 18238 36458 18239 36458 18240 36458 18238 36459 18240 36459 17663 36459 17663 36460 18240 36460 15656 36460 17663 36461 15656 36461 18241 36461 18241 36462 15656 36462 18243 36462 18241 36463 18243 36463 18242 36463 18242 36464 18243 36464 18244 36464 18242 36465 18244 36465 18245 36465 18245 36466 18244 36466 18246 36466 18245 36467 18246 36467 17665 36467 17665 36468 18246 36468 15652 36468 17665 36469 15652 36469 17667 36469 17667 36470 15652 36470 18247 36470 17667 36471 18247 36471 17668 36471 17668 36472 18247 36472 15648 36472 17668 36473 15648 36473 17669 36473 17669 36474 15648 36474 15647 36474 17669 36475 15647 36475 17671 36475 17671 36476 15647 36476 18248 36476 17671 36477 18248 36477 18249 36477 18249 36478 18248 36478 18250 36478 18249 36479 18250 36479 17673 36479 17673 36480 18250 36480 18251 36480 17673 36481 18251 36481 18252 36481 18252 36482 18251 36482 18253 36482 18252 36483 18253 36483 17675 36483 17675 36484 18253 36484 18254 36484 17675 36485 18254 36485 18255 36485 18255 36486 18254 36486 18256 36486 18255 36487 18256 36487 17646 36487 17646 36488 18256 36488 18257 36488 17646 36489 18257 36489 17647 36489 17647 36490 18257 36490 15644 36490 17647 36491 15644 36491 18258 36491 18258 36492 15644 36492 12295 36492 18258 36493 12295 36493 17650 36493 10956 36494 15643 36494 18259 36494 10956 36495 18259 36495 17703 36495 17703 36496 18259 36496 18260 36496 17703 36497 18260 36497 17704 36497 17704 36498 18260 36498 18261 36498 17704 36499 18261 36499 18262 36499 18262 36500 18261 36500 18263 36500 18262 36501 18263 36501 18264 36501 18264 36502 18263 36502 15645 36502 18264 36503 15645 36503 18265 36503 18265 36504 15645 36504 18266 36504 18265 36505 18266 36505 17708 36505 17708 36506 18266 36506 15646 36506 17708 36507 15646 36507 17709 36507 17709 36508 15646 36508 18268 36508 17709 36509 18268 36509 18267 36509 18267 36510 18268 36510 15649 36510 18267 36511 15649 36511 17712 36511 17712 36512 15649 36512 15650 36512 17712 36513 15650 36513 17713 36513 17713 36514 15650 36514 15651 36514 17713 36515 15651 36515 17714 36515 17714 36516 15651 36516 18269 36516 17714 36517 18269 36517 17715 36517 17715 36518 18269 36518 15653 36518 17715 36519 15653 36519 17716 36519 17716 36520 15653 36520 18270 36520 17716 36521 18270 36521 18271 36521 18271 36522 18270 36522 15654 36522 18271 36523 15654 36523 17676 36523 17676 36524 15654 36524 15655 36524 17676 36525 15655 36525 18272 36525 18272 36526 15655 36526 15657 36526 18272 36527 15657 36527 18273 36527 18273 36528 15657 36528 18274 36528 18273 36529 18274 36529 17679 36529 17679 36530 18274 36530 12271 36530 17679 36531 12271 36531 17681 36531 17758 36532 12296 36532 18275 36532 17758 36533 18275 36533 18276 36533 18276 36534 18275 36534 15641 36534 18276 36535 15641 36535 17760 36535 17760 36536 15641 36536 15638 36536 17760 36537 15638 36537 18277 36537 18277 36538 15638 36538 15637 36538 18277 36539 15637 36539 17762 36539 17762 36540 15637 36540 15635 36540 17762 36541 15635 36541 18278 36541 18278 36542 15635 36542 18279 36542 18278 36543 18279 36543 18280 36543 18280 36544 18279 36544 15633 36544 18280 36545 15633 36545 18281 36545 18281 36546 15633 36546 18282 36546 18281 36547 18282 36547 18283 36547 18283 36548 18282 36548 18284 36548 18283 36549 18284 36549 18285 36549 18285 36550 18284 36550 15631 36550 18285 36551 15631 36551 17766 36551 17766 36552 15631 36552 18286 36552 17766 36553 18286 36553 17768 36553 17768 36554 18286 36554 18287 36554 17768 36555 18287 36555 17769 36555 17769 36556 18287 36556 18289 36556 17769 36557 18289 36557 18288 36557 18288 36558 18289 36558 18290 36558 18288 36559 18290 36559 17770 36559 17770 36560 18290 36560 15628 36560 17770 36561 15628 36561 18291 36561 18291 36562 15628 36562 18292 36562 18291 36563 18292 36563 17738 36563 17738 36564 18292 36564 18293 36564 17738 36565 18293 36565 17739 36565 17739 36566 18293 36566 15626 36566 17739 36567 15626 36567 18294 36567 18294 36568 15626 36568 10923 36568 18294 36569 10923 36569 17741 36569 17794 36570 18295 36570 18297 36570 17794 36571 18297 36571 18296 36571 18296 36572 18297 36572 15627 36572 18296 36573 15627 36573 18298 36573 18298 36574 15627 36574 18299 36574 18298 36575 18299 36575 17796 36575 17796 36576 18299 36576 15629 36576 17796 36577 15629 36577 18300 36577 18300 36578 15629 36578 18302 36578 18300 36579 18302 36579 18301 36579 18301 36580 18302 36580 18303 36580 18301 36581 18303 36581 18304 36581 18304 36582 18303 36582 18305 36582 18304 36583 18305 36583 18306 36583 18306 36584 18305 36584 18307 36584 18306 36585 18307 36585 18308 36585 18308 36586 18307 36586 15630 36586 18308 36587 15630 36587 18309 36587 18309 36588 15630 36588 15632 36588 18309 36589 15632 36589 18310 36589 18310 36590 15632 36590 18311 36590 18310 36591 18311 36591 17801 36591 17801 36592 18311 36592 15634 36592 17801 36593 15634 36593 18312 36593 18312 36594 15634 36594 18314 36594 18312 36595 18314 36595 18313 36595 18313 36596 18314 36596 15636 36596 18313 36597 15636 36597 18315 36597 18315 36598 15636 36598 18316 36598 18315 36599 18316 36599 17773 36599 17773 36600 18316 36600 15639 36600 17773 36601 15639 36601 17775 36601 17775 36602 15639 36602 15640 36602 17775 36603 15640 36603 18317 36603 18317 36604 15640 36604 15642 36604 18317 36605 15642 36605 18318 36605 18318 36606 15642 36606 18319 36606 18318 36607 18319 36607 18320 36607 17845 36608 15625 36608 15624 36608 17845 36609 15624 36609 17847 36609 17847 36610 15624 36610 18321 36610 17847 36611 18321 36611 17848 36611 17848 36612 18321 36612 15622 36612 17848 36613 15622 36613 17850 36613 17850 36614 15622 36614 15621 36614 17850 36615 15621 36615 17851 36615 17851 36616 15621 36616 15620 36616 17851 36617 15620 36617 17853 36617 17853 36618 15620 36618 18322 36618 17853 36619 18322 36619 18323 36619 18323 36620 18322 36620 15618 36620 18323 36621 15618 36621 17855 36621 17855 36622 15618 36622 15616 36622 17855 36623 15616 36623 18324 36623 18324 36624 15616 36624 15614 36624 18324 36625 15614 36625 17857 36625 17857 36626 15614 36626 15613 36626 17857 36627 15613 36627 17858 36627 17858 36628 15613 36628 18325 36628 17858 36629 18325 36629 17860 36629 17860 36630 18325 36630 18326 36630 17860 36631 18326 36631 17861 36631 17861 36632 18326 36632 18328 36632 17861 36633 18328 36633 18327 36633 18327 36634 18328 36634 15611 36634 18327 36635 15611 36635 18329 36635 18329 36636 15611 36636 15610 36636 18329 36637 15610 36637 18330 36637 18330 36638 15610 36638 15609 36638 18330 36639 15609 36639 17824 36639 17824 36640 15609 36640 18331 36640 17824 36641 18331 36641 18333 36641 18333 36642 18331 36642 18332 36642 18333 36643 18332 36643 17826 36643 17826 36644 18332 36644 10890 36644 17826 36645 10890 36645 17828 36645 17883 36646 15605 36646 15606 36646 17883 36647 15606 36647 17885 36647 17885 36648 15606 36648 15607 36648 17885 36649 15607 36649 17886 36649 17886 36650 15607 36650 15608 36650 17886 36651 15608 36651 18334 36651 18334 36652 15608 36652 18335 36652 18334 36653 18335 36653 17888 36653 17888 36654 18335 36654 18337 36654 17888 36655 18337 36655 18336 36655 18336 36656 18337 36656 18338 36656 18336 36657 18338 36657 17890 36657 17890 36658 18338 36658 18339 36658 17890 36659 18339 36659 17891 36659 17891 36660 18339 36660 15612 36660 17891 36661 15612 36661 17892 36661 17892 36662 15612 36662 18340 36662 17892 36663 18340 36663 17895 36663 17895 36664 18340 36664 15615 36664 17895 36665 15615 36665 18341 36665 18341 36666 15615 36666 15617 36666 18341 36667 15617 36667 18342 36667 18342 36668 15617 36668 15619 36668 18342 36669 15619 36669 17896 36669 17896 36670 15619 36670 18343 36670 17896 36671 18343 36671 18344 36671 18344 36672 18343 36672 18345 36672 18344 36673 18345 36673 17864 36673 17864 36674 18345 36674 18346 36674 17864 36675 18346 36675 17865 36675 17865 36676 18346 36676 15623 36676 17865 36677 15623 36677 18348 36677 18348 36678 15623 36678 18347 36678 18348 36679 18347 36679 18349 36679 18349 36680 18347 36680 18350 36680 18349 36681 18350 36681 17867 36681 17867 36682 18350 36682 18351 36682 17867 36683 18351 36683 17868 36683 17936 36684 10876 36684 18352 36684 17936 36685 18352 36685 18353 36685 18353 36686 18352 36686 15604 36686 18353 36687 15604 36687 17938 36687 17938 36688 15604 36688 15601 36688 17938 36689 15601 36689 17939 36689 17939 36690 15601 36690 18354 36690 17939 36691 18354 36691 17941 36691 17941 36692 18354 36692 15600 36692 17941 36693 15600 36693 17942 36693 17942 36694 15600 36694 15598 36694 17942 36695 15598 36695 17945 36695 17945 36696 15598 36696 18356 36696 17945 36697 18356 36697 18355 36697 18355 36698 18356 36698 15597 36698 18355 36699 15597 36699 17948 36699 17948 36700 15597 36700 18357 36700 17948 36701 18357 36701 17950 36701 17950 36702 18357 36702 18358 36702 17950 36703 18358 36703 18359 36703 18359 36704 18358 36704 18361 36704 18359 36705 18361 36705 18360 36705 18360 36706 18361 36706 15595 36706 18360 36707 15595 36707 18362 36707 18362 36708 15595 36708 18364 36708 18362 36709 18364 36709 18363 36709 18363 36710 18364 36710 18365 36710 18363 36711 18365 36711 18366 36711 18366 36712 18365 36712 18368 36712 18366 36713 18368 36713 18367 36713 18367 36714 18368 36714 15591 36714 18367 36715 15591 36715 18369 36715 18369 36716 15591 36716 15590 36716 18369 36717 15590 36717 18370 36717 18370 36718 15590 36718 15588 36718 18370 36719 15588 36719 17916 36719 17916 36720 15588 36720 18371 36720 17916 36721 18371 36721 10858 36721 10857 36722 15587 36722 15589 36722 10857 36723 15589 36723 18372 36723 18372 36724 15589 36724 18373 36724 18372 36725 18373 36725 18374 36725 18374 36726 18373 36726 15592 36726 18374 36727 15592 36727 17975 36727 17975 36728 15592 36728 15593 36728 17975 36729 15593 36729 17976 36729 17976 36730 15593 36730 18375 36730 17976 36731 18375 36731 18376 36731 18376 36732 18375 36732 15594 36732 18376 36733 15594 36733 18377 36733 18377 36734 15594 36734 18378 36734 18377 36735 18378 36735 18379 36735 18379 36736 18378 36736 15596 36736 18379 36737 15596 36737 18381 36737 18381 36738 15596 36738 18380 36738 18381 36739 18380 36739 17982 36739 17982 36740 18380 36740 18382 36740 17982 36741 18382 36741 17983 36741 17983 36742 18382 36742 18384 36742 17983 36743 18384 36743 18383 36743 18383 36744 18384 36744 18386 36744 18383 36745 18386 36745 18385 36745 18385 36746 18386 36746 15599 36746 18385 36747 15599 36747 17985 36747 17985 36748 15599 36748 18387 36748 17985 36749 18387 36749 18388 36749 18388 36750 18387 36750 18389 36750 18388 36751 18389 36751 17956 36751 17956 36752 18389 36752 15602 36752 17956 36753 15602 36753 18390 36753 18390 36754 15602 36754 15603 36754 18390 36755 15603 36755 18391 36755 18391 36756 15603 36756 18392 36756 18391 36757 18392 36757 18393 36757 18393 36758 18392 36758 18394 36758 18393 36759 18394 36759 17958 36759 18395 36760 10836 36760 15561 36760 18395 36761 15561 36761 18024 36761 18024 36762 15561 36762 15559 36762 18024 36763 15559 36763 18396 36763 18396 36764 15559 36764 15558 36764 18396 36765 15558 36765 18026 36765 18026 36766 15558 36766 15557 36766 18026 36767 15557 36767 18397 36767 18397 36768 15557 36768 15556 36768 18397 36769 15556 36769 18398 36769 18398 36770 15556 36770 18399 36770 18398 36771 18399 36771 18028 36771 18028 36772 18399 36772 18401 36772 18028 36773 18401 36773 18400 36773 18400 36774 18401 36774 15555 36774 18400 36775 15555 36775 18031 36775 18031 36776 15555 36776 15553 36776 18031 36777 15553 36777 18403 36777 18403 36778 15553 36778 18402 36778 18403 36779 18402 36779 18404 36779 18404 36780 18402 36780 15551 36780 18404 36781 15551 36781 18405 36781 18405 36782 15551 36782 15550 36782 18405 36783 15550 36783 18406 36783 18406 36784 15550 36784 18408 36784 18406 36785 18408 36785 18407 36785 18407 36786 18408 36786 18409 36786 18407 36787 18409 36787 18410 36787 18410 36788 18409 36788 18411 36788 18410 36789 18411 36789 18412 36789 18412 36790 18411 36790 15547 36790 18412 36791 15547 36791 18413 36791 18413 36792 15547 36792 18414 36792 18413 36793 18414 36793 18002 36793 18002 36794 18414 36794 18415 36794 18002 36795 18415 36795 18004 36795 18004 36796 18415 36796 10814 36796 18004 36797 10814 36797 18416 36797 18058 36798 10813 36798 18417 36798 18058 36799 18417 36799 18418 36799 18418 36800 18417 36800 18419 36800 18418 36801 18419 36801 18060 36801 18060 36802 18419 36802 18420 36802 18060 36803 18420 36803 18062 36803 18062 36804 18420 36804 15548 36804 18062 36805 15548 36805 18421 36805 18421 36806 15548 36806 15549 36806 18421 36807 15549 36807 18423 36807 18423 36808 15549 36808 18422 36808 18423 36809 18422 36809 18424 36809 18424 36810 18422 36810 18425 36810 18424 36811 18425 36811 18065 36811 18065 36812 18425 36812 18426 36812 18065 36813 18426 36813 18427 36813 18427 36814 18426 36814 15552 36814 18427 36815 15552 36815 18067 36815 18067 36816 15552 36816 15554 36816 18067 36817 15554 36817 18429 36817 18429 36818 15554 36818 18428 36818 18429 36819 18428 36819 18068 36819 18068 36820 18428 36820 18430 36820 18068 36821 18430 36821 18431 36821 18431 36822 18430 36822 18433 36822 18431 36823 18433 36823 18432 36823 18432 36824 18433 36824 18434 36824 18432 36825 18434 36825 18070 36825 18070 36826 18434 36826 18435 36826 18070 36827 18435 36827 18436 36827 18436 36828 18435 36828 18437 36828 18436 36829 18437 36829 18438 36829 18438 36830 18437 36830 15560 36830 18438 36831 15560 36831 18036 36831 18036 36832 15560 36832 15562 36832 18036 36833 15562 36833 18439 36833 18439 36834 15562 36834 12379 36834 18439 36835 12379 36835 18440 36835 10797 36836 12362 36836 15586 36836 10797 36837 15586 36837 18122 36837 18122 36838 15586 36838 15584 36838 18122 36839 15584 36839 18123 36839 18123 36840 15584 36840 15582 36840 18123 36841 15582 36841 18125 36841 18125 36842 15582 36842 15581 36842 18125 36843 15581 36843 18127 36843 18127 36844 15581 36844 18441 36844 18127 36845 18441 36845 18129 36845 18129 36846 18441 36846 15579 36846 18129 36847 15579 36847 18130 36847 18130 36848 15579 36848 15577 36848 18130 36849 15577 36849 18442 36849 18442 36850 15577 36850 15576 36850 18442 36851 15576 36851 18443 36851 18443 36852 15576 36852 15575 36852 18443 36853 15575 36853 18444 36853 18444 36854 15575 36854 15573 36854 18444 36855 15573 36855 18132 36855 18132 36856 15573 36856 15571 36856 18132 36857 15571 36857 18133 36857 18133 36858 15571 36858 18446 36858 18133 36859 18446 36859 18445 36859 18445 36860 18446 36860 15568 36860 18445 36861 15568 36861 18447 36861 18447 36862 15568 36862 15566 36862 18447 36863 15566 36863 18095 36863 18095 36864 15566 36864 18448 36864 18095 36865 18448 36865 18097 36865 18097 36866 18448 36866 15564 36866 18097 36867 15564 36867 18449 36867 18449 36868 15564 36868 18451 36868 18449 36869 18451 36869 18450 36869 18450 36870 18451 36870 18452 36870 18450 36871 18452 36871 18098 36871 18098 36872 18452 36872 10778 36872 18098 36873 10778 36873 18453 36873 15752 36874 18542 36874 18669 36874 18669 36875 18542 36875 18549 36875 18669 36876 18549 36876 18454 36876 18454 36877 18549 36877 18551 36877 18454 36878 18551 36878 18455 36878 18455 36879 18551 36879 18456 36879 18455 36880 18456 36880 18670 36880 18670 36881 18456 36881 18555 36881 18457 36882 18554 36882 18664 36882 18664 36883 18554 36883 18558 36883 18664 36884 18558 36884 18458 36884 18458 36885 18558 36885 18459 36885 18458 36886 18459 36886 15750 36886 15750 36887 18459 36887 18559 36887 15751 36888 18562 36888 18460 36888 18460 36889 18562 36889 18462 36889 18460 36890 18462 36890 18461 36890 18461 36891 18462 36891 18556 36891 18461 36892 18556 36892 18666 36892 18666 36893 18556 36893 18552 36893 18665 36894 18546 36894 18548 36894 18665 36895 18548 36895 18464 36895 18464 36896 18548 36896 18463 36896 18464 36897 18463 36897 18667 36897 18667 36898 18463 36898 18465 36898 18667 36899 18465 36899 18466 36899 18466 36900 18465 36900 18545 36900 18466 36901 18545 36901 18668 36901 15754 36902 18662 36902 18538 36902 18538 36903 18662 36903 18658 36903 18538 36904 18658 36904 18467 36904 18467 36905 18658 36905 18659 36905 18467 36906 18659 36906 18468 36906 18468 36907 18659 36907 18469 36907 18468 36908 18469 36908 18470 36908 18470 36909 18469 36909 15756 36909 18533 36910 15755 36910 18532 36910 18532 36911 15755 36911 18656 36911 18532 36912 18656 36912 18530 36912 18530 36913 18656 36913 18471 36913 18530 36914 18471 36914 18526 36914 18526 36915 18471 36915 18657 36915 18472 36916 18473 36916 18528 36916 18528 36917 18473 36917 18474 36917 18528 36918 18474 36918 18527 36918 18527 36919 18474 36919 18663 36919 18527 36920 18663 36920 18475 36920 18475 36921 18663 36921 15753 36921 18535 36922 18476 36922 18477 36922 18477 36923 18476 36923 18660 36923 18477 36924 18660 36924 18478 36924 18478 36925 18660 36925 18479 36925 18478 36926 18479 36926 18539 36926 18539 36927 18479 36927 18661 36927 15563 36928 15862 36928 18480 36928 18480 36929 15862 36929 18481 36929 18480 36930 18481 36930 12378 36930 15565 36931 16068 36931 18482 36931 18482 36932 16068 36932 15860 36932 18482 36933 15860 36933 15563 36933 15563 36934 15860 36934 15863 36934 15563 36935 15863 36935 15862 36935 15944 36936 15565 36936 18483 36936 18483 36937 15565 36937 15567 36937 15944 36938 18484 36938 15565 36938 15565 36939 18484 36939 16070 36939 15565 36940 16070 36940 16068 36940 18485 36941 15567 36941 16060 36941 16060 36942 15567 36942 15569 36942 18485 36943 15903 36943 15567 36943 15567 36944 15903 36944 15900 36944 15567 36945 15900 36945 18483 36945 18487 36946 16066 36946 15570 36946 15570 36947 16066 36947 16067 36947 15570 36948 16067 36948 15569 36948 15569 36949 16067 36949 18486 36949 15569 36950 18486 36950 16060 36950 18487 36951 15570 36951 16056 36951 16056 36952 15570 36952 15572 36952 16056 36953 15572 36953 15897 36953 18491 36954 15917 36954 18488 36954 18488 36955 15917 36955 16046 36955 18488 36956 16046 36956 15574 36956 15574 36957 16046 36957 16047 36957 15574 36958 16047 36958 15572 36958 15572 36959 16047 36959 18489 36959 15572 36960 18489 36960 15897 36960 16037 36961 18490 36961 15578 36961 15578 36962 18490 36962 18492 36962 15578 36963 18492 36963 18491 36963 18491 36964 18492 36964 15889 36964 18491 36965 15889 36965 15917 36965 16037 36966 15578 36966 16039 36966 16039 36967 15578 36967 18493 36967 16039 36968 18493 36968 16036 36968 15931 36969 15929 36969 15580 36969 15580 36970 15929 36970 15928 36970 15580 36971 15928 36971 18493 36971 18493 36972 15928 36972 18494 36972 18493 36973 18494 36973 16036 36973 15583 36974 18495 36974 18496 36974 18496 36975 18495 36975 15759 36975 15759 36976 18497 36976 18496 36976 18496 36977 18497 36977 15934 36977 18496 36978 15934 36978 15580 36978 15580 36979 15934 36979 18498 36979 15580 36980 18498 36980 15931 36980 15585 36981 15840 36981 15583 36981 15583 36982 15840 36982 16028 36982 15583 36983 16028 36983 18495 36983 15872 36984 15838 36984 15585 36984 15585 36985 15838 36985 18499 36985 15585 36986 18499 36986 15840 36986 15585 36987 18500 36987 15872 36987 15872 36988 18500 36988 12363 36988 15872 36989 12363 36989 15873 36989 15492 36990 15716 36990 15715 36990 15492 36991 15715 36991 18502 36991 18502 36992 15715 36992 18501 36992 18502 36993 18501 36993 15490 36993 15490 36994 18501 36994 18504 36994 15490 36995 18504 36995 18503 36995 18503 36996 18504 36996 18505 36996 18503 36997 18505 36997 18506 36997 18506 36998 18505 36998 18508 36998 18506 36999 18508 36999 18507 36999 18507 37000 18508 37000 15714 37000 18507 37001 15714 37001 18509 37001 18509 37002 15714 37002 18510 37002 18509 37003 18510 37003 15487 37003 15487 37004 18510 37004 15711 37004 15487 37005 15711 37005 18511 37005 18511 37006 15711 37006 18512 37006 18511 37007 18512 37007 18513 37007 18513 37008 18512 37008 18514 37008 18513 37009 18514 37009 15485 37009 15485 37010 18514 37010 15709 37010 15485 37011 15709 37011 18515 37011 18515 37012 15709 37012 18516 37012 18515 37013 18516 37013 15483 37013 15483 37014 18516 37014 15706 37014 15483 37015 15706 37015 18517 37015 18517 37016 15706 37016 15705 37016 18517 37017 15705 37017 18518 37017 18518 37018 15705 37018 18519 37018 18518 37019 18519 37019 18520 37019 18520 37020 18519 37020 18521 37020 18520 37021 18521 37021 18523 37021 18523 37022 18521 37022 18522 37022 18523 37023 18522 37023 15481 37023 15481 37024 18522 37024 18524 37024 15481 37025 18524 37025 15480 37025 15480 37026 18524 37026 10725 37026 15480 37027 10725 37027 10724 37027 18472 37028 18525 37028 18526 37028 18526 37029 18525 37029 18529 37029 18475 37030 17171 37030 18527 37030 18527 37031 17171 37031 17162 37031 18527 37032 17162 37032 18528 37032 18528 37033 17162 37033 17178 37033 18528 37034 17178 37034 18472 37034 18472 37035 17178 37035 18525 37035 18526 37036 18529 37036 18530 37036 18530 37037 18529 37037 18531 37037 18530 37038 18531 37038 18532 37038 18532 37039 18531 37039 17183 37039 18532 37040 17183 37040 18533 37040 18533 37041 17183 37041 17181 37041 18535 37042 17170 37042 18475 37042 18475 37043 17170 37043 17171 37043 17180 37044 18470 37044 17181 37044 17181 37045 18470 37045 18533 37045 18539 37046 18541 37046 18478 37046 18478 37047 18541 37047 18534 37047 18478 37048 18534 37048 18477 37048 18477 37049 18534 37049 17166 37049 18477 37050 17166 37050 18535 37050 18535 37051 17166 37051 17170 37051 18470 37052 17180 37052 18468 37052 18468 37053 17180 37053 18536 37053 18468 37054 18536 37054 18467 37054 18467 37055 18536 37055 18537 37055 18467 37056 18537 37056 18538 37056 18538 37057 18537 37057 17167 37057 18538 37058 17167 37058 15754 37058 15754 37059 17167 37059 18540 37059 15754 37060 18540 37060 18539 37060 18539 37061 18540 37061 18541 37061 18545 37062 18544 37062 18542 37062 18542 37063 18544 37063 18543 37063 17210 37064 18544 37064 18545 37064 18546 37065 17211 37065 18548 37065 18548 37066 17211 37066 18547 37066 18548 37067 18547 37067 18463 37067 18463 37068 18547 37068 17210 37068 18463 37069 17210 37069 18465 37069 18465 37070 17210 37070 18545 37070 18542 37071 18543 37071 18549 37071 18549 37072 18543 37072 18550 37072 18549 37073 18550 37073 18551 37073 18551 37074 18550 37074 17209 37074 18551 37075 17209 37075 18456 37075 18456 37076 17209 37076 17215 37076 18456 37077 17215 37077 18555 37077 18555 37078 17215 37078 18553 37078 18552 37079 17226 37079 18546 37079 18546 37080 17226 37080 17211 37080 17216 37081 18554 37081 18553 37081 18553 37082 18554 37082 18555 37082 18562 37083 18563 37083 18462 37083 18462 37084 18563 37084 18557 37084 18462 37085 18557 37085 18556 37085 18556 37086 18557 37086 17225 37086 18556 37087 17225 37087 18552 37087 18552 37088 17225 37088 17226 37088 18554 37089 17216 37089 18558 37089 18558 37090 17216 37090 17219 37090 18558 37091 17219 37091 18459 37091 18459 37092 17219 37092 18560 37092 18459 37093 18560 37093 18559 37093 18559 37094 18560 37094 18561 37094 18559 37095 18561 37095 18562 37095 18562 37096 18561 37096 18563 37096 15744 37097 17248 37097 15731 37097 15744 37098 15731 37098 18564 37098 18564 37099 15731 37099 18566 37099 18564 37100 18566 37100 18565 37100 18565 37101 18566 37101 18568 37101 18565 37102 18568 37102 18567 37102 18567 37103 18568 37103 18569 37103 18567 37104 18569 37104 18570 37104 18570 37105 18569 37105 18571 37105 18570 37106 18571 37106 15748 37106 15748 37107 18571 37107 15735 37107 15748 37108 15735 37108 18572 37108 18572 37109 15735 37109 18573 37109 18572 37110 18573 37110 18574 37110 18574 37111 18573 37111 15736 37111 18574 37112 15736 37112 18575 37112 18575 37113 15736 37113 15737 37113 18575 37114 15737 37114 18576 37114 18576 37115 15737 37115 15739 37115 18576 37116 15739 37116 15745 37116 15745 37117 15739 37117 18577 37117 15745 37118 18577 37118 18579 37118 18579 37119 18577 37119 18578 37119 18579 37120 18578 37120 18580 37120 18580 37121 18578 37121 17251 37121 18580 37122 17251 37122 15743 37122 17222 37123 17248 37123 15741 37123 15741 37124 17248 37124 15744 37124 17251 37125 17172 37125 15743 37125 15743 37126 17172 37126 15742 37126 18582 37127 17223 37127 15741 37127 15741 37128 17223 37128 17222 37128 17249 37129 18583 37129 17172 37129 17172 37130 18583 37130 15742 37130 17247 37131 17223 37131 18581 37131 18581 37132 17223 37132 18582 37132 17249 37133 15718 37133 18583 37133 18583 37134 15718 37134 15746 37134 15746 37135 15718 37135 15719 37135 15746 37136 15719 37136 18584 37136 18584 37137 15719 37137 15721 37137 18584 37138 15721 37138 18585 37138 18585 37139 15721 37139 15722 37139 18585 37140 15722 37140 15749 37140 15749 37141 15722 37141 18587 37141 15749 37142 18587 37142 18586 37142 18586 37143 18587 37143 15725 37143 18586 37144 15725 37144 18588 37144 18588 37145 15725 37145 15727 37145 18588 37146 15727 37146 18589 37146 18589 37147 15727 37147 12186 37147 18589 37148 12186 37148 10714 37148 12019 37149 12020 37149 18590 37149 18590 37150 12020 37150 18593 37150 16306 37151 16307 37151 18591 37151 18591 37152 16307 37152 18592 37152 18591 37153 18592 37153 16303 37153 12017 37154 18590 37154 12015 37154 12015 37155 18590 37155 18593 37155 12015 37156 18593 37156 18592 37156 18592 37157 18593 37157 16302 37157 18592 37158 16302 37158 16303 37158 16296 37159 18594 37159 16298 37159 18595 37160 18597 37160 12027 37160 12027 37161 18597 37161 12024 37161 16300 37162 18597 37162 18596 37162 18596 37163 18597 37163 18595 37163 18596 37164 18595 37164 16298 37164 16298 37165 18595 37165 18598 37165 16298 37166 18598 37166 16296 37166 12024 37167 18599 37167 12027 37167 12027 37168 18599 37168 12025 37168 12027 37169 12025 37169 18600 37169 18606 37170 12035 37170 18605 37170 16292 37171 18601 37171 16291 37171 16291 37172 18601 37172 16294 37172 16291 37173 16294 37173 18604 37173 18602 37174 18603 37174 12028 37174 12028 37175 18603 37175 12031 37175 18604 37176 16294 37176 18605 37176 18605 37177 16294 37177 12028 37177 18605 37178 12028 37178 18606 37178 18606 37179 12028 37179 12031 37179 18606 37180 12031 37180 12033 37180 18612 37181 18608 37181 18613 37181 18607 37182 18609 37182 18608 37182 18608 37183 18609 37183 16284 37183 12036 37184 18613 37184 16287 37184 16287 37185 18613 37185 18608 37185 16287 37186 18608 37186 16286 37186 16286 37187 18608 37187 16284 37187 12040 37188 12041 37188 18610 37188 18610 37189 12041 37189 18612 37189 18610 37190 18612 37190 18611 37190 18611 37191 18612 37191 18613 37191 18618 37192 12047 37192 12048 37192 18616 37193 18614 37193 18618 37193 18618 37194 18614 37194 18622 37194 18615 37195 18616 37195 18617 37195 18617 37196 18616 37196 18618 37196 18617 37197 18618 37197 18619 37197 18619 37198 18618 37198 12048 37198 12044 37199 12045 37199 18620 37199 18620 37200 12045 37200 18618 37200 18620 37201 18618 37201 18621 37201 18621 37202 18618 37202 18622 37202 18623 37203 18624 37203 18625 37203 18624 37204 12050 37204 18625 37204 18625 37205 12050 37205 12052 37205 18625 37206 12052 37206 18629 37206 16277 37207 18626 37207 18625 37207 18625 37208 18626 37208 16279 37208 18625 37209 16279 37209 18623 37209 18627 37210 18628 37210 12057 37210 12057 37211 18628 37211 18625 37211 12057 37212 18625 37212 12056 37212 12056 37213 18625 37213 18629 37213 18630 37214 16271 37214 18637 37214 16271 37215 18631 37215 16273 37215 18632 37216 18637 37216 18633 37216 18633 37217 18637 37217 16271 37217 18633 37218 16271 37218 12058 37218 12058 37219 16271 37219 16273 37219 16269 37220 18635 37220 18634 37220 18634 37221 18635 37221 18630 37221 18634 37222 18630 37222 18636 37222 18636 37223 18630 37223 18637 37223 12064 37224 12065 37224 18641 37224 18638 37225 12067 37225 18641 37225 18641 37226 12067 37226 16263 37226 16267 37227 12063 37227 18639 37227 18639 37228 12063 37228 12064 37228 18639 37229 12064 37229 18640 37229 18640 37230 12064 37230 18641 37230 18640 37231 18641 37231 16264 37231 16264 37232 18641 37232 16263 37232 16264 37233 16263 37233 18642 37233 18645 37234 12073 37234 18646 37234 18643 37235 12075 37235 18646 37235 18646 37236 12075 37236 16257 37236 12069 37237 18644 37237 16261 37237 16261 37238 18644 37238 18645 37238 16261 37239 18645 37239 16259 37239 16259 37240 18645 37240 18646 37240 16259 37241 18646 37241 18647 37241 18647 37242 18646 37242 16257 37242 18647 37243 16257 37243 18648 37243 18652 37244 12080 37244 18653 37244 12082 37245 12083 37245 18653 37245 18653 37246 12083 37246 18655 37246 18649 37247 12077 37247 18650 37247 18650 37248 12077 37248 18652 37248 18650 37249 18652 37249 18651 37249 18651 37250 18652 37250 18653 37250 18651 37251 18653 37251 18654 37251 18654 37252 18653 37252 18655 37252 18654 37253 18655 37253 16255 37253 18473 37254 18657 37254 18662 37254 18473 37255 18662 37255 18474 37255 18471 37256 18656 37256 18657 37256 18657 37257 18656 37257 15755 37257 18657 37258 15755 37258 15756 37258 18658 37259 18662 37259 18659 37259 18659 37260 18662 37260 18657 37260 18659 37261 18657 37261 18469 37261 18469 37262 18657 37262 15756 37262 18661 37263 18479 37263 18660 37263 18660 37264 18476 37264 18661 37264 18661 37265 18476 37265 15753 37265 18661 37266 15753 37266 18662 37266 18662 37267 15753 37267 18663 37267 18662 37268 18663 37268 18474 37268 18457 37269 18664 37269 18665 37269 18665 37270 18664 37270 18458 37270 15751 37271 18460 37271 18461 37271 18458 37272 15750 37272 18665 37272 18665 37273 15750 37273 15751 37273 18665 37274 15751 37274 18666 37274 18666 37275 15751 37275 18461 37275 18667 37276 18466 37276 18464 37276 18464 37277 18466 37277 18668 37277 18464 37278 18668 37278 18665 37278 18665 37279 18668 37279 18670 37279 18665 37280 18670 37280 18457 37280 18454 37281 18455 37281 18669 37281 18669 37282 18455 37282 18670 37282 18669 37283 18670 37283 15752 37283 15752 37284 18670 37284 18668 37284 10713 37285 18738 37285 18672 37285 10713 37286 18672 37286 18671 37286 18671 37287 18672 37287 18674 37287 18671 37288 18674 37288 18673 37288 18673 37289 18674 37289 18742 37289 18673 37290 18742 37290 18676 37290 18676 37291 18742 37291 18675 37291 18676 37292 18675 37292 18677 37292 18677 37293 18675 37293 18678 37293 18677 37294 18678 37294 13601 37294 13601 37295 18678 37295 18745 37295 13601 37296 18745 37296 18679 37296 18679 37297 18745 37297 18746 37297 18679 37298 18746 37298 18680 37298 18680 37299 18746 37299 18748 37299 18680 37300 18748 37300 18681 37300 18681 37301 18748 37301 18750 37301 18681 37302 18750 37302 18682 37302 18682 37303 18750 37303 18683 37303 18682 37304 18683 37304 13597 37304 13597 37305 18683 37305 18684 37305 13597 37306 18684 37306 13596 37306 13596 37307 18684 37307 18685 37307 13596 37308 18685 37308 18686 37308 18686 37309 18685 37309 18687 37309 18686 37310 18687 37310 18688 37310 18688 37311 18687 37311 18751 37311 18688 37312 18751 37312 18689 37312 18689 37313 18751 37313 18752 37313 18689 37314 18752 37314 18690 37314 18690 37315 18752 37315 18691 37315 18690 37316 18691 37316 10700 37316 18692 37317 18693 37317 18694 37317 18692 37318 18694 37318 18695 37318 18695 37319 18694 37319 18723 37319 18695 37320 18723 37320 18696 37320 18696 37321 18723 37321 18697 37321 18696 37322 18697 37322 18801 37322 18801 37323 18697 37323 18698 37323 18801 37324 18698 37324 18699 37324 18699 37325 18698 37325 18721 37325 18699 37326 18721 37326 18700 37326 18700 37327 18721 37327 18701 37327 18700 37328 18701 37328 18788 37328 18788 37329 18701 37329 18720 37329 18788 37330 18720 37330 18790 37330 18790 37331 18720 37331 18702 37331 18790 37332 18702 37332 18791 37332 18791 37333 18702 37333 18703 37333 18791 37334 18703 37334 18704 37334 18704 37335 18703 37335 18717 37335 18704 37336 18717 37336 18705 37336 18705 37337 18717 37337 18706 37337 18705 37338 18706 37338 18794 37338 18794 37339 18706 37339 18715 37339 18794 37340 18715 37340 18707 37340 18707 37341 18715 37341 18708 37341 18707 37342 18708 37342 18780 37342 18780 37343 18708 37343 18714 37343 18780 37344 18714 37344 18709 37344 18709 37345 18714 37345 18713 37345 18709 37346 18713 37346 18710 37346 18710 37347 18713 37347 18711 37347 18710 37348 18711 37348 18782 37348 18712 37349 18711 37349 18713 37349 18712 37350 18713 37350 18753 37350 18753 37351 18713 37351 18714 37351 18753 37352 18714 37352 18754 37352 18754 37353 18714 37353 18708 37353 18754 37354 18708 37354 18755 37354 18755 37355 18708 37355 18715 37355 18755 37356 18715 37356 18716 37356 18716 37357 18715 37357 18706 37357 18716 37358 18706 37358 18757 37358 18757 37359 18706 37359 18717 37359 18757 37360 18717 37360 18718 37360 18718 37361 18717 37361 18703 37361 18718 37362 18703 37362 18719 37362 18719 37363 18703 37363 18702 37363 18719 37364 18702 37364 18759 37364 18759 37365 18702 37365 18720 37365 18759 37366 18720 37366 18760 37366 18760 37367 18720 37367 18701 37367 18760 37368 18701 37368 18763 37368 18763 37369 18701 37369 18721 37369 18763 37370 18721 37370 18722 37370 18722 37371 18721 37371 18698 37371 18722 37372 18698 37372 18765 37372 18765 37373 18698 37373 18697 37373 18765 37374 18697 37374 18767 37374 18767 37375 18697 37375 18723 37375 18767 37376 18723 37376 18769 37376 18769 37377 18723 37377 18694 37377 18769 37378 18694 37378 18724 37378 18724 37379 18694 37379 18693 37379 18724 37380 18693 37380 10672 37380 18691 37381 18772 37381 18725 37381 18725 37382 18772 37382 10654 37382 18725 37383 10654 37383 10701 37383 10701 37384 10654 37384 18726 37384 10701 37385 18726 37385 10702 37385 10702 37386 18726 37386 18727 37386 10702 37387 18727 37387 18729 37387 18729 37388 18727 37388 18728 37388 18729 37389 18728 37389 18730 37389 18730 37390 18728 37390 10657 37390 18730 37391 10657 37391 10704 37391 10704 37392 10657 37392 10660 37392 10704 37393 10660 37393 18731 37393 18731 37394 10660 37394 18732 37394 18731 37395 18732 37395 10706 37395 10706 37396 18732 37396 10661 37396 10706 37397 10661 37397 18733 37397 18733 37398 10661 37398 10662 37398 18733 37399 10662 37399 10708 37399 10708 37400 10662 37400 10663 37400 10708 37401 10663 37401 18734 37401 18734 37402 10663 37402 18735 37402 18734 37403 18735 37403 10709 37403 10709 37404 18735 37404 10665 37404 10709 37405 10665 37405 10711 37405 10711 37406 10665 37406 18736 37406 10711 37407 18736 37407 18737 37407 18737 37408 18736 37408 10669 37408 18737 37409 10669 37409 10712 37409 10712 37410 10669 37410 10670 37410 10712 37411 10670 37411 18738 37411 18738 37412 10670 37412 18739 37412 18738 37413 18739 37413 18672 37413 18672 37414 18739 37414 18740 37414 18672 37415 18740 37415 18674 37415 18674 37416 18740 37416 18741 37416 18674 37417 18741 37417 18742 37417 18742 37418 18741 37418 18756 37418 18742 37419 18756 37419 18675 37419 18675 37420 18756 37420 18743 37420 18675 37421 18743 37421 18678 37421 18678 37422 18743 37422 18744 37422 18678 37423 18744 37423 18745 37423 18745 37424 18744 37424 18758 37424 18745 37425 18758 37425 18746 37425 18746 37426 18758 37426 18747 37426 18746 37427 18747 37427 18748 37427 18748 37428 18747 37428 18761 37428 18748 37429 18761 37429 18750 37429 18750 37430 18761 37430 18749 37430 18750 37431 18749 37431 18683 37431 18683 37432 18749 37432 18762 37432 18683 37433 18762 37433 18684 37433 18684 37434 18762 37434 18764 37434 18684 37435 18764 37435 18685 37435 18685 37436 18764 37436 18766 37436 18685 37437 18766 37437 18687 37437 18687 37438 18766 37438 18768 37438 18687 37439 18768 37439 18751 37439 18751 37440 18768 37440 18770 37440 18751 37441 18770 37441 18752 37441 18752 37442 18770 37442 18771 37442 18752 37443 18771 37443 18691 37443 18691 37444 18771 37444 18772 37444 18739 37445 18712 37445 18753 37445 18739 37446 18753 37446 18740 37446 18740 37447 18753 37447 18754 37447 18740 37448 18754 37448 18741 37448 18741 37449 18754 37449 18755 37449 18741 37450 18755 37450 18756 37450 18756 37451 18755 37451 18716 37451 18756 37452 18716 37452 18743 37452 18743 37453 18716 37453 18757 37453 18743 37454 18757 37454 18744 37454 18744 37455 18757 37455 18718 37455 18744 37456 18718 37456 18758 37456 18758 37457 18718 37457 18719 37457 18758 37458 18719 37458 18747 37458 18747 37459 18719 37459 18759 37459 18747 37460 18759 37460 18761 37460 18761 37461 18759 37461 18760 37461 18761 37462 18760 37462 18749 37462 18749 37463 18760 37463 18763 37463 18749 37464 18763 37464 18762 37464 18762 37465 18763 37465 18722 37465 18762 37466 18722 37466 18764 37466 18764 37467 18722 37467 18765 37467 18764 37468 18765 37468 18766 37468 18766 37469 18765 37469 18767 37469 18766 37470 18767 37470 18768 37470 18768 37471 18767 37471 18769 37471 18768 37472 18769 37472 18770 37472 18770 37473 18769 37473 18724 37473 18770 37474 18724 37474 18771 37474 18771 37475 18724 37475 10672 37475 18771 37476 10672 37476 18772 37476 10494 37477 18774 37477 18773 37477 18773 37478 18774 37478 18775 37478 18773 37479 18775 37479 10493 37479 10493 37480 18775 37480 10692 37480 10493 37481 10692 37481 18776 37481 18776 37482 10692 37482 10694 37482 18776 37483 10694 37483 18777 37483 18777 37484 10694 37484 18778 37484 18777 37485 18778 37485 10490 37485 10490 37486 18778 37486 10696 37486 10490 37487 10696 37487 10489 37487 10489 37488 10696 37488 18779 37488 10489 37489 18779 37489 18795 37489 18793 37490 18707 37490 19339 37490 19339 37491 18707 37491 18780 37491 19339 37492 18780 37492 18781 37492 18781 37493 18780 37493 18709 37493 18781 37494 18709 37494 19337 37494 19337 37495 18709 37495 18710 37495 19337 37496 18710 37496 10496 37496 10496 37497 18710 37497 18782 37497 10496 37498 18782 37498 18783 37498 18783 37499 18782 37499 10689 37499 18783 37500 10689 37500 18784 37500 18784 37501 10689 37501 18785 37501 18784 37502 18785 37502 10494 37502 10494 37503 18785 37503 18786 37503 10494 37504 18786 37504 18774 37504 19347 37505 18699 37505 19346 37505 19346 37506 18699 37506 18700 37506 19346 37507 18700 37507 19345 37507 19345 37508 18700 37508 18788 37508 19345 37509 18788 37509 18787 37509 18787 37510 18788 37510 18790 37510 18787 37511 18790 37511 18789 37511 18789 37512 18790 37512 18791 37512 18789 37513 18791 37513 19342 37513 19342 37514 18791 37514 18704 37514 19342 37515 18704 37515 18792 37515 18792 37516 18704 37516 18705 37516 18792 37517 18705 37517 18793 37517 18793 37518 18705 37518 18794 37518 18793 37519 18794 37519 18707 37519 18779 37520 18796 37520 18795 37520 18795 37521 18796 37521 18797 37521 18795 37522 18797 37522 18798 37522 18798 37523 18797 37523 10698 37523 18798 37524 10698 37524 10487 37524 10487 37525 10698 37525 10699 37525 10487 37526 10699 37526 10485 37526 10485 37527 10699 37527 18799 37527 10485 37528 18799 37528 19350 37528 19350 37529 18799 37529 18692 37529 19350 37530 18692 37530 18800 37530 18800 37531 18692 37531 18695 37531 18800 37532 18695 37532 19348 37532 19348 37533 18695 37533 18696 37533 19348 37534 18696 37534 19347 37534 19347 37535 18696 37535 18801 37535 19347 37536 18801 37536 18699 37536 10452 37537 18803 37537 18804 37537 19484 37538 19482 37538 10448 37538 10448 37539 19482 37539 18804 37539 10448 37540 18804 37540 18802 37540 18802 37541 18804 37541 18803 37541 10452 37542 18804 37542 10453 37542 10453 37543 18804 37543 18805 37543 10453 37544 18805 37544 19479 37544 10456 37545 10455 37545 18806 37545 18806 37546 10455 37546 10453 37546 18806 37547 10453 37547 18807 37547 18807 37548 10453 37548 19479 37548 10404 37549 18808 37549 19527 37549 19527 37550 18808 37550 19140 37550 19527 37551 19140 37551 18809 37551 18809 37552 19140 37552 19143 37552 18809 37553 19143 37553 18810 37553 18810 37554 19143 37554 18812 37554 18810 37555 18812 37555 18811 37555 18811 37556 18812 37556 18813 37556 18811 37557 18813 37557 19529 37557 19529 37558 18813 37558 19142 37558 19529 37559 19142 37559 19530 37559 19530 37560 19142 37560 19293 37560 18814 37561 19148 37561 18815 37561 18815 37562 19148 37562 18816 37562 18815 37563 18816 37563 18817 37563 18817 37564 18816 37564 19146 37564 18817 37565 19146 37565 19522 37565 19522 37566 19146 37566 18818 37566 19522 37567 18818 37567 19524 37567 19524 37568 18818 37568 18819 37568 19524 37569 18819 37569 19525 37569 19525 37570 18819 37570 19082 37570 19525 37571 19082 37571 18820 37571 18820 37572 19082 37572 10642 37572 10416 37573 19161 37573 19516 37573 19516 37574 19161 37574 18821 37574 19516 37575 18821 37575 19517 37575 19517 37576 18821 37576 19164 37576 19517 37577 19164 37577 19519 37577 19519 37578 19164 37578 19163 37578 19519 37579 19163 37579 18822 37579 18822 37580 19163 37580 18823 37580 18822 37581 18823 37581 18824 37581 18824 37582 18823 37582 19155 37582 18824 37583 19155 37583 19520 37583 19520 37584 19155 37584 18825 37584 19520 37585 18825 37585 10412 37585 10412 37586 18825 37586 19160 37586 10635 37587 10430 37587 18828 37587 18828 37588 10430 37588 19513 37588 18826 37589 19063 37589 18829 37589 19513 37590 18827 37590 18828 37590 18828 37591 18827 37591 19511 37591 18828 37592 19511 37592 18829 37592 18829 37593 19511 37593 19509 37593 18829 37594 19509 37594 18826 37594 18826 37595 19508 37595 19063 37595 19063 37596 19508 37596 19507 37596 19063 37597 19507 37597 18830 37597 19507 37598 19504 37598 18830 37598 18830 37599 19504 37599 18831 37599 18830 37600 18831 37600 18833 37600 10417 37601 18832 37601 19500 37601 19500 37602 18832 37602 18833 37602 19500 37603 18833 37603 19501 37603 19501 37604 18833 37604 18831 37604 10441 37605 10627 37605 18834 37605 18834 37606 10627 37606 19126 37606 18834 37607 19126 37607 18835 37607 18835 37608 19126 37608 18836 37608 18835 37609 18836 37609 19494 37609 19494 37610 18836 37610 19049 37610 19494 37611 19049 37611 19495 37611 19495 37612 19049 37612 18837 37612 19495 37613 18837 37613 18838 37613 18838 37614 18837 37614 19053 37614 18838 37615 19053 37615 19497 37615 19497 37616 19053 37616 19050 37616 19497 37617 19050 37617 10432 37617 10432 37618 19050 37618 10623 37618 10621 37619 19125 37619 19487 37619 19487 37620 19125 37620 18839 37620 19487 37621 18839 37621 19489 37621 19489 37622 18839 37622 18840 37622 19489 37623 18840 37623 18841 37623 18841 37624 18840 37624 18842 37624 18841 37625 18842 37625 19491 37625 19491 37626 18842 37626 19174 37626 19491 37627 19174 37627 18844 37627 18844 37628 19174 37628 18843 37628 18844 37629 18843 37629 18845 37629 18845 37630 18843 37630 19175 37630 18845 37631 19175 37631 10442 37631 10442 37632 19175 37632 10616 37632 10613 37633 10615 37633 19555 37633 19555 37634 10615 37634 18846 37634 19555 37635 18846 37635 18847 37635 18847 37636 18846 37636 18848 37636 18847 37637 18848 37637 19558 37637 19558 37638 18848 37638 19182 37638 19558 37639 19182 37639 19559 37639 19559 37640 19182 37640 18849 37640 19559 37641 18849 37641 19561 37641 19561 37642 18849 37642 19178 37642 19561 37643 19178 37643 18850 37643 18850 37644 19178 37644 19180 37644 10364 37645 10606 37645 18851 37645 18851 37646 10606 37646 18852 37646 18851 37647 18852 37647 18853 37647 18853 37648 18852 37648 18855 37648 18853 37649 18855 37649 18854 37649 18854 37650 18855 37650 18857 37650 18854 37651 18857 37651 18856 37651 18856 37652 18857 37652 18858 37652 18856 37653 18858 37653 18859 37653 18859 37654 18858 37654 19114 37654 18859 37655 19114 37655 19552 37655 19552 37656 19114 37656 19193 37656 10599 37657 10600 37657 19542 37657 19542 37658 10600 37658 18860 37658 19542 37659 18860 37659 18861 37659 18861 37660 18860 37660 18862 37660 18861 37661 18862 37661 19544 37661 19544 37662 18862 37662 19101 37662 19544 37663 19101 37663 18863 37663 18863 37664 19101 37664 19099 37664 18863 37665 19099 37665 18864 37665 18864 37666 19099 37666 19097 37666 18864 37667 19097 37667 19546 37667 19546 37668 19097 37668 18865 37668 19546 37669 18865 37669 10595 37669 10595 37670 18865 37670 18866 37670 18867 37671 10594 37671 19538 37671 19538 37672 10594 37672 19074 37672 19538 37673 19074 37673 18868 37673 18868 37674 19074 37674 19075 37674 18868 37675 19075 37675 18869 37675 18869 37676 19075 37676 19076 37676 18869 37677 19076 37677 18870 37677 18870 37678 19076 37678 19197 37678 18870 37679 19197 37679 19541 37679 19541 37680 19197 37680 19199 37680 19541 37681 19199 37681 10372 37681 10372 37682 19199 37682 19200 37682 10586 37683 18871 37683 19535 37683 19535 37684 18871 37684 19212 37684 19535 37685 19212 37685 18872 37685 18872 37686 19212 37686 18873 37686 18872 37687 18873 37687 18874 37687 18874 37688 18873 37688 18875 37688 18874 37689 18875 37689 18876 37689 18876 37690 18875 37690 18877 37690 18876 37691 18877 37691 18878 37691 18878 37692 18877 37692 19205 37692 18878 37693 19205 37693 10382 37693 10382 37694 19205 37694 10580 37694 10579 37695 19216 37695 19531 37695 19531 37696 19216 37696 19217 37696 19531 37697 19217 37697 18879 37697 18879 37698 19217 37698 18880 37698 18879 37699 18880 37699 18881 37699 18881 37700 18880 37700 18882 37700 18881 37701 18882 37701 19533 37701 19533 37702 18882 37702 19215 37702 19533 37703 19215 37703 18883 37703 18883 37704 19215 37704 18884 37704 18883 37705 18884 37705 18885 37705 18885 37706 18884 37706 18886 37706 19433 37707 19227 37707 18887 37707 18887 37708 19227 37708 19225 37708 18887 37709 19225 37709 18889 37709 18889 37710 19225 37710 18888 37710 18889 37711 18888 37711 19430 37711 19430 37712 18888 37712 19224 37712 19430 37713 19224 37713 18890 37713 18890 37714 19224 37714 19219 37714 18890 37715 19219 37715 18891 37715 18891 37716 19219 37716 19173 37716 18891 37717 19173 37717 18892 37717 19428 37718 19145 37718 19427 37718 19427 37719 19145 37719 19158 37719 19427 37720 19158 37720 19425 37720 19425 37721 19158 37721 19156 37721 19425 37722 19156 37722 19424 37722 19424 37723 19156 37723 18893 37723 19424 37724 18893 37724 19422 37724 19422 37725 18893 37725 18895 37725 19422 37726 18895 37726 18894 37726 18894 37727 18895 37727 19152 37727 18894 37728 19152 37728 19417 37728 19417 37729 19152 37729 19151 37729 19417 37730 19151 37730 19418 37730 19418 37731 19151 37731 19233 37731 19418 37732 19233 37732 19435 37732 19435 37733 19233 37733 19231 37733 19435 37734 19231 37734 19436 37734 19436 37735 19231 37735 19229 37735 19436 37736 19229 37736 19438 37736 19438 37737 19229 37737 18896 37737 19438 37738 18896 37738 18898 37738 18898 37739 18896 37739 18897 37739 18897 37740 19046 37740 18898 37740 18898 37741 19046 37741 19312 37741 18898 37742 19312 37742 18899 37742 18899 37743 19312 37743 19311 37743 18899 37744 19311 37744 19223 37744 18899 37745 19223 37745 18900 37745 18900 37746 19223 37746 18901 37746 18900 37747 18901 37747 18902 37747 18902 37748 18901 37748 19222 37748 18902 37749 19222 37749 19433 37749 19433 37750 19222 37750 19227 37750 19410 37751 18919 37751 18903 37751 18903 37752 18919 37752 18904 37752 18903 37753 18904 37753 18905 37753 18905 37754 18904 37754 18906 37754 18905 37755 18906 37755 19405 37755 19405 37756 18906 37756 19052 37756 19405 37757 19052 37757 19404 37757 19404 37758 19052 37758 18907 37758 19404 37759 18907 37759 19403 37759 19403 37760 18907 37760 19051 37760 19403 37761 19051 37761 18908 37761 18908 37762 19051 37762 18909 37762 18911 37763 18908 37763 18909 37763 18914 37764 18910 37764 18912 37764 18912 37765 18910 37765 18911 37765 18912 37766 18911 37766 18913 37766 18913 37767 18911 37767 18909 37767 18910 37768 18914 37768 10571 37768 10571 37769 18914 37769 19055 37769 10568 37770 18915 37770 19397 37770 19397 37771 18915 37771 19066 37771 19397 37772 19066 37772 19413 37772 19413 37773 19066 37773 19065 37773 19413 37774 19065 37774 19415 37774 19415 37775 19065 37775 19064 37775 19415 37776 19064 37776 19416 37776 19416 37777 19064 37777 18916 37777 19416 37778 18916 37778 18917 37778 18917 37779 18916 37779 19059 37779 19411 37780 18917 37780 19058 37780 19058 37781 18917 37781 19059 37781 19411 37782 19058 37782 19408 37782 19408 37783 19058 37783 19234 37783 19408 37784 19234 37784 18918 37784 18918 37785 19234 37785 19236 37785 18918 37786 19236 37786 19410 37786 19410 37787 19236 37787 18919 37787 18920 37788 19248 37788 18921 37788 18921 37789 19248 37789 18922 37789 18921 37790 18922 37790 19391 37790 19391 37791 18922 37791 18926 37791 18927 37792 18923 37792 19246 37792 19246 37793 18923 37793 18924 37793 19246 37794 18924 37794 19247 37794 19247 37795 18924 37795 19387 37795 19247 37796 19387 37796 18925 37796 19391 37797 18926 37797 10466 37797 10466 37798 18926 37798 18925 37798 10466 37799 18925 37799 19388 37799 19388 37800 18925 37800 19387 37800 18923 37801 18927 37801 19382 37801 19382 37802 18927 37802 19245 37802 19382 37803 19245 37803 19384 37803 19384 37804 19245 37804 18928 37804 19384 37805 18928 37805 19381 37805 19381 37806 18928 37806 18930 37806 19381 37807 18930 37807 18929 37807 18929 37808 18930 37808 18931 37808 18929 37809 18931 37809 10567 37809 10567 37810 18931 37810 19242 37810 19380 37811 18932 37811 19379 37811 19379 37812 18932 37812 19241 37812 19379 37813 19241 37813 19394 37813 19394 37814 19241 37814 19240 37814 19394 37815 19240 37815 19395 37815 19395 37816 19240 37816 18933 37816 19395 37817 18933 37817 18934 37817 18934 37818 18933 37818 18935 37818 18934 37819 18935 37819 18937 37819 18937 37820 18935 37820 18936 37820 19392 37821 18937 37821 18938 37821 18938 37822 18937 37822 18936 37822 19392 37823 18938 37823 18939 37823 18939 37824 18938 37824 19250 37824 18939 37825 19250 37825 18940 37825 18940 37826 19250 37826 19249 37826 18940 37827 19249 37827 18920 37827 18920 37828 19249 37828 19248 37828 19375 37829 19254 37829 18941 37829 18941 37830 19254 37830 19253 37830 18941 37831 19253 37831 18943 37831 18943 37832 19253 37832 19115 37832 18942 37833 19118 37833 19372 37833 19372 37834 19373 37834 18942 37834 18942 37835 19373 37835 10468 37835 18942 37836 10468 37836 19120 37836 18943 37837 19115 37837 10472 37837 10472 37838 19115 37838 18944 37838 10472 37839 18944 37839 10471 37839 10471 37840 18944 37840 19120 37840 10471 37841 19120 37841 10470 37841 10470 37842 19120 37842 10468 37842 19372 37843 19118 37843 19370 37843 19370 37844 19118 37844 18945 37844 19370 37845 18945 37845 19371 37845 19371 37846 18945 37846 18946 37846 19371 37847 18946 37847 19367 37847 19367 37848 18946 37848 18947 37848 19367 37849 18947 37849 19366 37849 19366 37850 18947 37850 18948 37850 19366 37851 18948 37851 18949 37851 18949 37852 18948 37852 18950 37852 18949 37853 18950 37853 18951 37853 18951 37854 18950 37854 19237 37854 18951 37855 19237 37855 19364 37855 19364 37856 19237 37856 19238 37856 19364 37857 19238 37857 19360 37857 19360 37858 19238 37858 19239 37858 19360 37859 19239 37859 19361 37859 19361 37860 19239 37860 10564 37860 18953 37861 10565 37861 18952 37861 18952 37862 10565 37862 19259 37862 18953 37863 18952 37863 19377 37863 19377 37864 18952 37864 19257 37864 19377 37865 19257 37865 18954 37865 18954 37866 19257 37866 19256 37866 18954 37867 19256 37867 19375 37867 19375 37868 19256 37868 19254 37868 10458 37869 19263 37869 18955 37869 18955 37870 19263 37870 19266 37870 18955 37871 19266 37871 19466 37871 19466 37872 19266 37872 19267 37872 19466 37873 19267 37873 18956 37873 18956 37874 19267 37874 19269 37874 18956 37875 19269 37875 19464 37875 19464 37876 19269 37876 19280 37876 19464 37877 19280 37877 19462 37877 19462 37878 19280 37878 18957 37878 19462 37879 18957 37879 18958 37879 18958 37880 18957 37880 18960 37880 18958 37881 18960 37881 18959 37881 18959 37882 18960 37882 19211 37882 18959 37883 19211 37883 18961 37883 18961 37884 19211 37884 18964 37884 18962 37885 19457 37885 19270 37885 19270 37886 19457 37886 18963 37886 19270 37887 18963 37887 19271 37887 18963 37888 19459 37888 19271 37888 19271 37889 19459 37889 19460 37889 19271 37890 19460 37890 18965 37890 18961 37891 18964 37891 19461 37891 19461 37892 18964 37892 18965 37892 19461 37893 18965 37893 18966 37893 18966 37894 18965 37894 19460 37894 19457 37895 18962 37895 18967 37895 18967 37896 18962 37896 19274 37896 18967 37897 19274 37897 18968 37897 18968 37898 19274 37898 18969 37898 18968 37899 18969 37899 19473 37899 19473 37900 18969 37900 18970 37900 19473 37901 18970 37901 19476 37901 19476 37902 18970 37902 19275 37902 19476 37903 19275 37903 19477 37903 19477 37904 19275 37904 18971 37904 19469 37905 19477 37905 19262 37905 19262 37906 19477 37906 18971 37906 19469 37907 19262 37907 19470 37907 19470 37908 19262 37908 19261 37908 19470 37909 19261 37909 10457 37909 10457 37910 19261 37910 19260 37910 18987 37911 19230 37911 19449 37911 19449 37912 19230 37912 19232 37912 19449 37913 19232 37913 18972 37913 18972 37914 19232 37914 18973 37914 18972 37915 18973 37915 18974 37915 18974 37916 18973 37916 10561 37916 19444 37917 19317 37917 19443 37917 19443 37918 19317 37918 19315 37918 19443 37919 19315 37919 18975 37919 18975 37920 19315 37920 18978 37920 18976 37921 19268 37921 18977 37921 18975 37922 18978 37922 10463 37922 10463 37923 18978 37923 19308 37923 10463 37924 19308 37924 10461 37924 10461 37925 19308 37925 18979 37925 10461 37926 18979 37926 18980 37926 18980 37927 18979 37927 18976 37927 18980 37928 18976 37928 10459 37928 10459 37929 18976 37929 18977 37929 18977 37930 19268 37930 19440 37930 19440 37931 19268 37931 18981 37931 19440 37932 18981 37932 18982 37932 18982 37933 18981 37933 19265 37933 18982 37934 19265 37934 18983 37934 18983 37935 19265 37935 19264 37935 18983 37936 19264 37936 18984 37936 18984 37937 19264 37937 19044 37937 18984 37938 19044 37938 19455 37938 19455 37939 19044 37939 19283 37939 18985 37940 19455 37940 18986 37940 18986 37941 19455 37941 19283 37941 18985 37942 18986 37942 19452 37942 19452 37943 18986 37943 19281 37943 19452 37944 19281 37944 19453 37944 19453 37945 19281 37945 19228 37945 19453 37946 19228 37946 18987 37946 18987 37947 19228 37947 19230 37947 19562 37948 19166 37948 18988 37948 18988 37949 19166 37949 19167 37949 18988 37950 19167 37950 19563 37950 19563 37951 19167 37951 19169 37951 19563 37952 19169 37952 19564 37952 19564 37953 19169 37953 18989 37953 19564 37954 18989 37954 19565 37954 19565 37955 18989 37955 18990 37955 19565 37956 18990 37956 18991 37956 18991 37957 18990 37957 19144 37957 18991 37958 19144 37958 10343 37958 10343 37959 19144 37959 10558 37959 10549 37960 18992 37960 19567 37960 19567 37961 18992 37961 18993 37961 19567 37962 18993 37962 19569 37962 19569 37963 18993 37963 19080 37963 19569 37964 19080 37964 18994 37964 18994 37965 19080 37965 18996 37965 18994 37966 18996 37966 18995 37966 18995 37967 18996 37967 19079 37967 18995 37968 19079 37968 19573 37968 19573 37969 19079 37969 18997 37969 19573 37970 18997 37970 10335 37970 10335 37971 18997 37971 19139 37971 10547 37972 10548 37972 18998 37972 18998 37973 10548 37973 18999 37973 18998 37974 18999 37974 19000 37974 19000 37975 18999 37975 19296 37975 19000 37976 19296 37976 19001 37976 19001 37977 19296 37977 19295 37977 19001 37978 19295 37978 19576 37978 19576 37979 19295 37979 19299 37979 19576 37980 19299 37980 19577 37980 19577 37981 19299 37981 19298 37981 19577 37982 19298 37982 10541 37982 10541 37983 19298 37983 19297 37983 19002 37984 19273 37984 19003 37984 19003 37985 19273 37985 19209 37985 19003 37986 19209 37986 19004 37986 19004 37987 19209 37987 19005 37987 19004 37988 19005 37988 19006 37988 19006 37989 19005 37989 19208 37989 19006 37990 19208 37990 19007 37990 19007 37991 19208 37991 19286 37991 19007 37992 19286 37992 19009 37992 19009 37993 19286 37993 19008 37993 19009 37994 19008 37994 19581 37994 19581 37995 19008 37995 19077 37995 19581 37996 19077 37996 19582 37996 19582 37997 19077 37997 10537 37997 19010 37998 19012 37998 19011 37998 19011 37999 19012 37999 19013 37999 19011 38000 19013 38000 19585 38000 19585 38001 19013 38001 19014 38001 19585 38002 19014 38002 19586 38002 19586 38003 19014 38003 19106 38003 19586 38004 19106 38004 19587 38004 19587 38005 19106 38005 19105 38005 19587 38006 19105 38006 19015 38006 19015 38007 19105 38007 19016 38007 19015 38008 19016 38008 19017 38008 19017 38009 19016 38009 19018 38009 19111 38010 19597 38010 19019 38010 19019 38011 19597 38011 19020 38011 19019 38012 19020 38012 19021 38012 19020 38013 19022 38013 19021 38013 19021 38014 19022 38014 19595 38014 19021 38015 19595 38015 19023 38015 19595 38016 19594 38016 19023 38016 19023 38017 19594 38017 19024 38017 19023 38018 19024 38018 19119 38018 19119 38019 19024 38019 19028 38019 19119 38020 19028 38020 19117 38020 19590 38021 19112 38021 19025 38021 19025 38022 19112 38022 19116 38022 19025 38023 19116 38023 19026 38023 19026 38024 19116 38024 19117 38024 19026 38025 19117 38025 19027 38025 19027 38026 19117 38026 19028 38026 10522 38027 19029 38027 19600 38027 19600 38028 19029 38028 19030 38028 19600 38029 19030 38029 19031 38029 19031 38030 19030 38030 19032 38030 19031 38031 19032 38031 19601 38031 19601 38032 19032 38032 19033 38032 19601 38033 19033 38033 19602 38033 19602 38034 19033 38034 19034 38034 19602 38035 19034 38035 19603 38035 19603 38036 19034 38036 19035 38036 19603 38037 19035 38037 10298 38037 10298 38038 19035 38038 19068 38038 10297 38039 10521 38039 19606 38039 19606 38040 10521 38040 19036 38040 19606 38041 19036 38041 19608 38041 19608 38042 19036 38042 19037 38042 19608 38043 19037 38043 19609 38043 19609 38044 19037 38044 19038 38044 19609 38045 19038 38045 19039 38045 19039 38046 19038 38046 19132 38046 19039 38047 19132 38047 19611 38047 19611 38048 19132 38048 19131 38048 19611 38049 19131 38049 19614 38049 19614 38050 19131 38050 19130 38050 19614 38051 19130 38051 19040 38051 19040 38052 19130 38052 19041 38052 19323 38053 19042 38053 19043 38053 19044 38054 19264 38054 19314 38054 19315 38055 19316 38055 19309 38055 10564 38056 19239 38056 19251 38056 19247 38057 18925 38057 19045 38057 19312 38058 19046 38058 19282 38058 19334 38059 19354 38059 19353 38059 19334 38060 19353 38060 19048 38060 19129 38061 10623 38061 19050 38061 19047 38062 10483 38062 19333 38062 19333 38063 10483 38063 18836 38063 18906 38064 18904 38064 19129 38064 19353 38065 19351 38065 19048 38065 19048 38066 19351 38066 10474 38066 19048 38067 10474 38067 19333 38067 19333 38068 10474 38068 10476 38068 19333 38069 10476 38069 19047 38069 18836 38070 10483 38070 19049 38070 19049 38071 10483 38071 10482 38071 19049 38072 10482 38072 18837 38072 18837 38073 10482 38073 19054 38073 18837 38074 19054 38074 19053 38074 18909 38075 19051 38075 19050 38075 19050 38076 19051 38076 18907 38076 19050 38077 18907 38077 19129 38077 19129 38078 18907 38078 19052 38078 19129 38079 19052 38079 18906 38079 19063 38080 10497 38080 19067 38080 19050 38081 19053 38081 18909 38081 18909 38082 19053 38082 19054 38082 18909 38083 19054 38083 18913 38083 18913 38084 19054 38084 19358 38084 18913 38085 19358 38085 18912 38085 18912 38086 19358 38086 19356 38086 18912 38087 19356 38087 18914 38087 18914 38088 19356 38088 19062 38088 18914 38089 19062 38089 19055 38089 19055 38090 19062 38090 10570 38090 19063 38091 18830 38091 10497 38091 10497 38092 18830 38092 18833 38092 10497 38093 18833 38093 19056 38093 19056 38094 18833 38094 18832 38094 19056 38095 18832 38095 19334 38095 19334 38096 18832 38096 19057 38096 19058 38097 19059 38097 19226 38097 19226 38098 19059 38098 18916 38098 19226 38099 18916 38099 19064 38099 19057 38100 10631 38100 19334 38100 19334 38101 10631 38101 10630 38101 19334 38102 10630 38102 19354 38102 19354 38103 10630 38103 19060 38103 19354 38104 19060 38104 19062 38104 19062 38105 19060 38105 19061 38105 19061 38106 10636 38106 19062 38106 19062 38107 10636 38107 10635 38107 19062 38108 10635 38108 10570 38108 10570 38109 10635 38109 18828 38109 10570 38110 18828 38110 19067 38110 19067 38111 18828 38111 18829 38111 19067 38112 18829 38112 19063 38112 19064 38113 19065 38113 19226 38113 19226 38114 19065 38114 19066 38114 19226 38115 19066 38115 10497 38115 10497 38116 19066 38116 18915 38116 10497 38117 18915 38117 19067 38117 19035 38118 19070 38118 19068 38118 19068 38119 19070 38119 19069 38119 19068 38120 19069 38120 10527 38120 19035 38121 19034 38121 19070 38121 19070 38122 19034 38122 19033 38122 19070 38123 19033 38123 19244 38123 19244 38124 19033 38124 19032 38124 19183 38125 19186 38125 19071 38125 19071 38126 19186 38126 19073 38126 19032 38127 19030 38127 19244 38127 19244 38128 19030 38128 19029 38128 19244 38129 19029 38129 19072 38129 19072 38130 19029 38130 10523 38130 19072 38131 10523 38131 19073 38131 19073 38132 10523 38132 10524 38132 19073 38133 10524 38133 19071 38133 19075 38134 19074 38134 19194 38134 19075 38135 19194 38135 19076 38135 19196 38136 10537 38136 19198 38136 19198 38137 10537 38137 19077 38137 19198 38138 19077 38138 10511 38138 10511 38139 19077 38139 19008 38139 10511 38140 19008 38140 19286 38140 10583 38141 19078 38141 19209 38141 19079 38142 18996 38142 10504 38142 10504 38143 18996 38143 19080 38143 10504 38144 19080 38144 19081 38144 19081 38145 19080 38145 18993 38145 19081 38146 18993 38146 19088 38146 19088 38147 18993 38147 18992 38147 18818 38148 19089 38148 18819 38148 18819 38149 19089 38149 10557 38149 18819 38150 10557 38150 19082 38150 19082 38151 10557 38151 19083 38151 19082 38152 19083 38152 10642 38152 19138 38153 19150 38153 10554 38153 10555 38154 19084 38154 19150 38154 19150 38155 19084 38155 19085 38155 19150 38156 19085 38156 10554 38156 18992 38157 19086 38157 19088 38157 19088 38158 19086 38158 19087 38158 19088 38159 19087 38159 10502 38159 10502 38160 19087 38160 19089 38160 10502 38161 19089 38161 19090 38161 19090 38162 19089 38162 18818 38162 19043 38163 19042 38163 19092 38163 19042 38164 19091 38164 19092 38164 19092 38165 19091 38165 18866 38165 19092 38166 18866 38166 19093 38166 19093 38167 18866 38167 18865 38167 18862 38168 18860 38168 19094 38168 19094 38169 18860 38169 10600 38169 19094 38170 10600 38170 19119 38170 19119 38171 10600 38171 19095 38171 19119 38172 19095 38172 19023 38172 19023 38173 19095 38173 19096 38173 19023 38174 19096 38174 19021 38174 19021 38175 19096 38175 10598 38175 19021 38176 10598 38176 19042 38176 19042 38177 10598 38177 10597 38177 19042 38178 10597 38178 19091 38178 18865 38179 19097 38179 19098 38179 19098 38180 19097 38180 19099 38180 19098 38181 19099 38181 19100 38181 19100 38182 19099 38182 19101 38182 19100 38183 19101 38183 19102 38183 19102 38184 19101 38184 18862 38184 19102 38185 18862 38185 10536 38185 10536 38186 18862 38186 19094 38186 19203 38187 19013 38187 19094 38187 19094 38188 19013 38188 19012 38188 19094 38189 19012 38189 10536 38189 19098 38190 19103 38190 18865 38190 18865 38191 19103 38191 19104 38191 18865 38192 19104 38192 19093 38192 19093 38193 19104 38193 19018 38193 19093 38194 19018 38194 10513 38194 19018 38195 19016 38195 10513 38195 10513 38196 19016 38196 19105 38196 10513 38197 19105 38197 19201 38197 19201 38198 19105 38198 19106 38198 19201 38199 19106 38199 19203 38199 19203 38200 19106 38200 19014 38200 19203 38201 19014 38201 19013 38201 19107 38202 19109 38202 19108 38202 19108 38203 19109 38203 19323 38203 19109 38204 19110 38204 19323 38204 19323 38205 19110 38205 19111 38205 19323 38206 19111 38206 19042 38206 19042 38207 19111 38207 19019 38207 19042 38208 19019 38208 19021 38208 18946 38209 19112 38209 19113 38209 19045 38210 18948 38210 18947 38210 19114 38211 18858 38211 19113 38211 18947 38212 18946 38212 18855 38212 18855 38213 18946 38213 19113 38213 18855 38214 19113 38214 18857 38214 18857 38215 19113 38215 18858 38215 19113 38216 10532 38216 19114 38216 19114 38217 10532 38217 19107 38217 19114 38218 19107 38218 19192 38218 19192 38219 19107 38219 19108 38219 19192 38220 19108 38220 19190 38220 19094 38221 18944 38221 19115 38221 19094 38222 19115 38222 19255 38222 19112 38223 18946 38223 19116 38223 19116 38224 18946 38224 18945 38224 19116 38225 18945 38225 19117 38225 19117 38226 18945 38226 19118 38226 19117 38227 19118 38227 19119 38227 19119 38228 19118 38228 18942 38228 19119 38229 18942 38229 19094 38229 19094 38230 18942 38230 19120 38230 19094 38231 19120 38231 18944 38231 19121 38232 19330 38232 10521 38232 10521 38233 10520 38233 19121 38233 19121 38234 10520 38234 19123 38234 19121 38235 19123 38235 19122 38235 19122 38236 19123 38236 19176 38236 19176 38237 19124 38237 10622 38237 10622 38238 19124 38238 19125 38238 19125 38239 19124 38239 10517 38239 19125 38240 10517 38240 18839 38240 18839 38241 10517 38241 19041 38241 18839 38242 19041 38242 18840 38242 18836 38243 19126 38243 19333 38243 19333 38244 19126 38244 10627 38244 19333 38245 10627 38245 19127 38245 19127 38246 10627 38246 10626 38246 19127 38247 10626 38247 19330 38247 19330 38248 10626 38248 10625 38248 19330 38249 10625 38249 10521 38249 10521 38250 10625 38250 19128 38250 10521 38251 19128 38251 19134 38251 19130 38252 19129 38252 19041 38252 19041 38253 19129 38253 19243 38253 19041 38254 19243 38254 18840 38254 19130 38255 19131 38255 19129 38255 19129 38256 19131 38256 19132 38256 19129 38257 19132 38257 10623 38257 10623 38258 19132 38258 19038 38258 10623 38259 19038 38259 19133 38259 19133 38260 19038 38260 19037 38260 19133 38261 19037 38261 19134 38261 19134 38262 19037 38262 19036 38262 19134 38263 19036 38263 10521 38263 19309 38264 19318 38264 19135 38264 19135 38265 19318 38265 10652 38265 19135 38266 10652 38266 19136 38266 10554 38267 19137 38267 19138 38267 19138 38268 19137 38268 10551 38268 19138 38269 10551 38269 19319 38269 19319 38270 10551 38270 10550 38270 19319 38271 10550 38271 19320 38271 19320 38272 10550 38272 19139 38272 19320 38273 19139 38273 10647 38273 10647 38274 19139 38274 18997 38274 10647 38275 18997 38275 18808 38275 18808 38276 18997 38276 19079 38276 18808 38277 19079 38277 19140 38277 19140 38278 19079 38278 10504 38278 19140 38279 10504 38279 19143 38279 19143 38280 10504 38280 19141 38280 19293 38281 19142 38281 10507 38281 10507 38282 19142 38282 18813 38282 10507 38283 18813 38283 19141 38283 19141 38284 18813 38284 18812 38284 19141 38285 18812 38285 19143 38285 19156 38286 10558 38286 19144 38286 19145 38287 10637 38287 19160 38287 18818 38288 19146 38288 19090 38288 19090 38289 19146 38289 18816 38289 19090 38290 18816 38290 19147 38290 19147 38291 18816 38291 19148 38291 19147 38292 19148 38292 19170 38292 19170 38293 19148 38293 19149 38293 19170 38294 19149 38294 19162 38294 10644 38295 19150 38295 19144 38295 19156 38296 19144 38296 18893 38296 18893 38297 19144 38297 19150 38297 18893 38298 19150 38298 18895 38298 19083 38299 10555 38299 10642 38299 10642 38300 10555 38300 19150 38300 10642 38301 19150 38301 10643 38301 10643 38302 19150 38302 10644 38302 19233 38303 19151 38303 19150 38303 19150 38304 19151 38304 19152 38304 19150 38305 19152 38305 18895 38305 19163 38306 19165 38306 19153 38306 19159 38307 18825 38307 19154 38307 19154 38308 18825 38308 19155 38308 19154 38309 19155 38309 19153 38309 19153 38310 19155 38310 18823 38310 19153 38311 18823 38311 19163 38311 10558 38312 19156 38312 10559 38312 10559 38313 19156 38313 19158 38313 10559 38314 19158 38314 19157 38314 19157 38315 19158 38315 19145 38315 19157 38316 19145 38316 19159 38316 19159 38317 19145 38317 19160 38317 19159 38318 19160 38318 18825 38318 19164 38319 18821 38319 10498 38319 10498 38320 18821 38320 19161 38320 10498 38321 19161 38321 10497 38321 18989 38322 19170 38322 18990 38322 18990 38323 19170 38323 19162 38323 18990 38324 19162 38324 19144 38324 19144 38325 19162 38325 10646 38325 19144 38326 10646 38326 10644 38326 19163 38327 19164 38327 19165 38327 19165 38328 19164 38328 10498 38328 19165 38329 10498 38329 19166 38329 19166 38330 10498 38330 19168 38330 19166 38331 19168 38331 19167 38331 19167 38332 19168 38332 19170 38332 19167 38333 19170 38333 19169 38333 19169 38334 19170 38334 18989 38334 19161 38335 19171 38335 10497 38335 10497 38336 19171 38336 19172 38336 10497 38337 19172 38337 19220 38337 10637 38338 19145 38338 19221 38338 19221 38339 19145 38339 19173 38339 19221 38340 19173 38340 19219 38340 19175 38341 18843 38341 19244 38341 19244 38342 18843 38342 19174 38342 19244 38343 19174 38343 19243 38343 19243 38344 19174 38344 18842 38344 19243 38345 18842 38345 18840 38345 19175 38346 19244 38346 10616 38346 10616 38347 19244 38347 19072 38347 10616 38348 19072 38348 10617 38348 19176 38349 10622 38349 19122 38349 19122 38350 10622 38350 19177 38350 19122 38351 19177 38351 19329 38351 10617 38352 19072 38352 10619 38352 10619 38353 19072 38353 19073 38353 10619 38354 19073 38354 19184 38354 19178 38355 19179 38355 19180 38355 19180 38356 19179 38356 19181 38356 19180 38357 19181 38357 10607 38357 10607 38358 19181 38358 19300 38358 19178 38359 18849 38359 19179 38359 19179 38360 18849 38360 19182 38360 19179 38361 19182 38361 19070 38361 19070 38362 19182 38362 18848 38362 10614 38363 19069 38363 10615 38363 10615 38364 19069 38364 19070 38364 10615 38365 19070 38365 18846 38365 18846 38366 19070 38366 18848 38366 10614 38367 10612 38367 19069 38367 19069 38368 10612 38368 19186 38368 19069 38369 19186 38369 10527 38369 10527 38370 19186 38370 19183 38370 19177 38371 19184 38371 19329 38371 19329 38372 19184 38372 19073 38372 19329 38373 19073 38373 19328 38373 19328 38374 19073 38374 19186 38374 19328 38375 19186 38375 19185 38375 19185 38376 19186 38376 10612 38376 19185 38377 10612 38377 10610 38377 10606 38378 10605 38378 19179 38378 19179 38379 10605 38379 19187 38379 19190 38380 19188 38380 10602 38380 10602 38381 19189 38381 19190 38381 19190 38382 19189 38382 19191 38382 19190 38383 19191 38383 19192 38383 19192 38384 19191 38384 19193 38384 19192 38385 19193 38385 19114 38385 19194 38386 19195 38386 19076 38386 19076 38387 19195 38387 19196 38387 19076 38388 19196 38388 19197 38388 19197 38389 19196 38389 19198 38389 19197 38390 19198 38390 19199 38390 19199 38391 19198 38391 10515 38391 19199 38392 10515 38392 19200 38392 19200 38393 10515 38393 10514 38393 19200 38394 10514 38394 10587 38394 10587 38395 10514 38395 10513 38395 10587 38396 10513 38396 10589 38396 10589 38397 10513 38397 19201 38397 10593 38398 19203 38398 10594 38398 10594 38399 19203 38399 19202 38399 10594 38400 19202 38400 19074 38400 19074 38401 19202 38401 10540 38401 19074 38402 10540 38402 19194 38402 10593 38403 10591 38403 19203 38403 19203 38404 10591 38404 10590 38404 19203 38405 10590 38405 19201 38405 19201 38406 10590 38406 19204 38406 19201 38407 19204 38407 10589 38407 19205 38408 19303 38408 10580 38408 10580 38409 19303 38409 19206 38409 10580 38410 19206 38410 19207 38410 19207 38411 19206 38411 19208 38411 19207 38412 19208 38412 19078 38412 19078 38413 19208 38413 19005 38413 19078 38414 19005 38414 19209 38414 19209 38415 19273 38415 10583 38415 10583 38416 19273 38416 19211 38416 10583 38417 19211 38417 19210 38417 19210 38418 19211 38418 18960 38418 19210 38419 18960 38419 10585 38419 10585 38420 18960 38420 18957 38420 10585 38421 18957 38421 18871 38421 18871 38422 18957 38422 19279 38422 18871 38423 19279 38423 19212 38423 19212 38424 19279 38424 19213 38424 19205 38425 18877 38425 19303 38425 19303 38426 18877 38426 18875 38426 19303 38427 18875 38427 19213 38427 19213 38428 18875 38428 18873 38428 19213 38429 18873 38429 19212 38429 19289 38430 18886 38430 19290 38430 18880 38431 19218 38431 18882 38431 18882 38432 19218 38432 19214 38432 18882 38433 19214 38433 19215 38433 19215 38434 19214 38434 19290 38434 19215 38435 19290 38435 18884 38435 18884 38436 19290 38436 18886 38436 10578 38437 19310 38437 19216 38437 19216 38438 19310 38438 19218 38438 19216 38439 19218 38439 19217 38439 19217 38440 19218 38440 18880 38440 19289 38441 19288 38441 10572 38441 10572 38442 19288 38442 10574 38442 19224 38443 10497 38443 19219 38443 19219 38444 10497 38444 19220 38444 19219 38445 19220 38445 19221 38445 19222 38446 18901 38446 19226 38446 19226 38447 18901 38447 19223 38447 19224 38448 18888 38448 10497 38448 10497 38449 18888 38449 19225 38449 10497 38450 19225 38450 19226 38450 19226 38451 19225 38451 19227 38451 19226 38452 19227 38452 19222 38452 19046 38453 18897 38453 19282 38453 19282 38454 18897 38454 18896 38454 19282 38455 18896 38455 19228 38455 19228 38456 18896 38456 19229 38456 19228 38457 19229 38457 19230 38457 19230 38458 19229 38458 19231 38458 19230 38459 19231 38459 19232 38459 19232 38460 19231 38460 19233 38460 19252 38461 18919 38461 19236 38461 19058 38462 19226 38462 19234 38462 19234 38463 19226 38463 19235 38463 19234 38464 19235 38464 19236 38464 19252 38465 18933 38465 18919 38465 18919 38466 18933 38466 19240 38466 18919 38467 19240 38467 18904 38467 18948 38468 19045 38468 18950 38468 18950 38469 19045 38469 18925 38469 18950 38470 18925 38470 19237 38470 19237 38471 18925 38471 18926 38471 19237 38472 18926 38472 19238 38472 19238 38473 18926 38473 18922 38473 19238 38474 18922 38474 19239 38474 18855 38475 18852 38475 18947 38475 18947 38476 18852 38476 10606 38476 18947 38477 10606 38477 19045 38477 19045 38478 10606 38478 19179 38478 19045 38479 19179 38479 19247 38479 19240 38480 19241 38480 18904 38480 18904 38481 19241 38481 18932 38481 18904 38482 18932 38482 19129 38482 19129 38483 18932 38483 19242 38483 19129 38484 19242 38484 19243 38484 19243 38485 19242 38485 18931 38485 18931 38486 18930 38486 19243 38486 19243 38487 18930 38487 18928 38487 19243 38488 18928 38488 19244 38488 19244 38489 18928 38489 19245 38489 19244 38490 19245 38490 19070 38490 19070 38491 19245 38491 18927 38491 19070 38492 18927 38492 19179 38492 19179 38493 18927 38493 19246 38493 19179 38494 19246 38494 19247 38494 18922 38495 19248 38495 19239 38495 19239 38496 19248 38496 19249 38496 19239 38497 19249 38497 19251 38497 19251 38498 19249 38498 19250 38498 19250 38499 18938 38499 19251 38499 19251 38500 18938 38500 18936 38500 19251 38501 18936 38501 19252 38501 19252 38502 18936 38502 18935 38502 19252 38503 18935 38503 18933 38503 19115 38504 19253 38504 19255 38504 19255 38505 19253 38505 19254 38505 19255 38506 19254 38506 19258 38506 19258 38507 19254 38507 19256 38507 19258 38508 19256 38508 19257 38508 19257 38509 18952 38509 19258 38509 19258 38510 18952 38510 19259 38510 19258 38511 19259 38511 10566 38511 19263 38512 19260 38512 19314 38512 19314 38513 19260 38513 19261 38513 19314 38514 19261 38514 19262 38514 19314 38515 19264 38515 19263 38515 19263 38516 19264 38516 19265 38516 19263 38517 19265 38517 19266 38517 19266 38518 19265 38518 18981 38518 19266 38519 18981 38519 19267 38519 19267 38520 18981 38520 19268 38520 19267 38521 19268 38521 19269 38521 19269 38522 19268 38522 18976 38522 19269 38523 18976 38523 19280 38523 18962 38524 19270 38524 19094 38524 19094 38525 19270 38525 19271 38525 19094 38526 19271 38526 19203 38526 19203 38527 19271 38527 18965 38527 19203 38528 18965 38528 19202 38528 19202 38529 18965 38529 18964 38529 19202 38530 18964 38530 10540 38530 10540 38531 18964 38531 19211 38531 10540 38532 19211 38532 19272 38532 19272 38533 19211 38533 19273 38533 18962 38534 19094 38534 19274 38534 19274 38535 19094 38535 19255 38535 19274 38536 19255 38536 18969 38536 18969 38537 19255 38537 18970 38537 18970 38538 19255 38538 19258 38538 18970 38539 19258 38539 19275 38539 19262 38540 18971 38540 19314 38540 19314 38541 18971 38541 19276 38541 19314 38542 19276 38542 19313 38542 19317 38543 19277 38543 19138 38543 19138 38544 19277 38544 19278 38544 19138 38545 19278 38545 19150 38545 19150 38546 19278 38546 10561 38546 19150 38547 10561 38547 19233 38547 19233 38548 10561 38548 18973 38548 19233 38549 18973 38549 19232 38549 18957 38550 19280 38550 19279 38550 19279 38551 19280 38551 18976 38551 19279 38552 18976 38552 19213 38552 19213 38553 18976 38553 18979 38553 19228 38554 19281 38554 19282 38554 19282 38555 19281 38555 18986 38555 19282 38556 18986 38556 19283 38556 19284 38557 19285 38557 19303 38557 19303 38558 19285 38558 10511 38558 19303 38559 10511 38559 19206 38559 19206 38560 10511 38560 19286 38560 19206 38561 19286 38561 19208 38561 10578 38562 10577 38562 19310 38562 19310 38563 10577 38563 19287 38563 19310 38564 19287 38564 19307 38564 19307 38565 19287 38565 10574 38565 19307 38566 10574 38566 19305 38566 19305 38567 10574 38567 19288 38567 19305 38568 19288 38568 19304 38568 19304 38569 19288 38569 10508 38569 19289 38570 19290 38570 19288 38570 19288 38571 19290 38571 10509 38571 19288 38572 10509 38572 10508 38572 19310 38573 19291 38573 19292 38573 10548 38574 10546 38574 19135 38574 19135 38575 10546 38575 10544 38575 19136 38576 19293 38576 19135 38576 19135 38577 19293 38577 10507 38577 19135 38578 10507 38578 10548 38578 10548 38579 10507 38579 18999 38579 19218 38580 19299 38580 19294 38580 19294 38581 19299 38581 19295 38581 19294 38582 19295 38582 10507 38582 10507 38583 19295 38583 19296 38583 10507 38584 19296 38584 18999 38584 19292 38585 10542 38585 19310 38585 19310 38586 10542 38586 19297 38586 19310 38587 19297 38587 19218 38587 19218 38588 19297 38588 19298 38588 19218 38589 19298 38589 19299 38589 10610 38590 10608 38590 19185 38590 19185 38591 10608 38591 19300 38591 19185 38592 19300 38592 19301 38592 19301 38593 19300 38593 19181 38593 19301 38594 19181 38594 19302 38594 19302 38595 19181 38595 19179 38595 19302 38596 19179 38596 19188 38596 19188 38597 19179 38597 19187 38597 19188 38598 19187 38598 10602 38598 19284 38599 19303 38599 19304 38599 19304 38600 19303 38600 19213 38600 19304 38601 19213 38601 19305 38601 19305 38602 19213 38602 19306 38602 19305 38603 19306 38603 19307 38603 18979 38604 19308 38604 19213 38604 19213 38605 19308 38605 18978 38605 19213 38606 18978 38606 19306 38606 19306 38607 18978 38607 19315 38607 19306 38608 19315 38608 19307 38608 19307 38609 19315 38609 19309 38609 19307 38610 19309 38610 19310 38610 19310 38611 19309 38611 19135 38611 19310 38612 19135 38612 19291 38612 19291 38613 19135 38613 10544 38613 19223 38614 19311 38614 19322 38614 19322 38615 19311 38615 19312 38615 19322 38616 19312 38616 19313 38616 19313 38617 19312 38617 19282 38617 19313 38618 19282 38618 19314 38618 19314 38619 19282 38619 19283 38619 19314 38620 19283 38620 19044 38620 19236 38621 19235 38621 19252 38621 19252 38622 19235 38622 19258 38622 19252 38623 19258 38623 19251 38623 19251 38624 19258 38624 10566 38624 19251 38625 10566 38625 10564 38625 19315 38626 19317 38626 19316 38626 19316 38627 19317 38627 19138 38627 19316 38628 19138 38628 19309 38628 19309 38629 19138 38629 19319 38629 19309 38630 19319 38630 19318 38630 19318 38631 19319 38631 19320 38631 19318 38632 19320 38632 19321 38632 19321 38633 19320 38633 10647 38633 19223 38634 19322 38634 19226 38634 19226 38635 19322 38635 19313 38635 19226 38636 19313 38636 19235 38636 19235 38637 19313 38637 19276 38637 19235 38638 19276 38638 19258 38638 19258 38639 19276 38639 18971 38639 19258 38640 18971 38640 19275 38640 19093 38641 10484 38641 19349 38641 19093 38642 19349 38642 19092 38642 19092 38643 19349 38643 19324 38643 19092 38644 19324 38644 19043 38644 19043 38645 19324 38645 19323 38645 19323 38646 19324 38646 19325 38646 19323 38647 19325 38647 19108 38647 19108 38648 19325 38648 19190 38648 19190 38649 19325 38649 19326 38649 19190 38650 19326 38650 19188 38650 19188 38651 19326 38651 19344 38651 19188 38652 19344 38652 19302 38652 19302 38653 19344 38653 19301 38653 19301 38654 19344 38654 19343 38654 19301 38655 19343 38655 19185 38655 19185 38656 19343 38656 19327 38656 19185 38657 19327 38657 19328 38657 19328 38658 19327 38658 19341 38658 19328 38659 19341 38659 19329 38659 19329 38660 19341 38660 19340 38660 19329 38661 19340 38661 19122 38661 19122 38662 19340 38662 19331 38662 19122 38663 19331 38663 19121 38663 19121 38664 19331 38664 19330 38664 19330 38665 19331 38665 19338 38665 19330 38666 19338 38666 19127 38666 19127 38667 19338 38667 19333 38667 19333 38668 19338 38668 19332 38668 19333 38669 19332 38669 19048 38669 19048 38670 19332 38670 19334 38670 19334 38671 19332 38671 19335 38671 19334 38672 19335 38672 19056 38672 19056 38673 19335 38673 19336 38673 19056 38674 19336 38674 10497 38674 10496 38675 19336 38675 19335 38675 10496 38676 19335 38676 19337 38676 19337 38677 19335 38677 19332 38677 19337 38678 19332 38678 18781 38678 18781 38679 19332 38679 19338 38679 18781 38680 19338 38680 19339 38680 19339 38681 19338 38681 19331 38681 19339 38682 19331 38682 18793 38682 18793 38683 19331 38683 19340 38683 18793 38684 19340 38684 18792 38684 18792 38685 19340 38685 19341 38685 18792 38686 19341 38686 19342 38686 19342 38687 19341 38687 19327 38687 19342 38688 19327 38688 18789 38688 18789 38689 19327 38689 19343 38689 18789 38690 19343 38690 18787 38690 18787 38691 19343 38691 19344 38691 18787 38692 19344 38692 19345 38692 19345 38693 19344 38693 19326 38693 19345 38694 19326 38694 19346 38694 19346 38695 19326 38695 19325 38695 19346 38696 19325 38696 19347 38696 19347 38697 19325 38697 19324 38697 19347 38698 19324 38698 19348 38698 19348 38699 19324 38699 19349 38699 19348 38700 19349 38700 18800 38700 18800 38701 19349 38701 10484 38701 18800 38702 10484 38702 19350 38702 19615 38703 19351 38703 19616 38703 19616 38704 19351 38704 19353 38704 19616 38705 19353 38705 19352 38705 19352 38706 19353 38706 19354 38706 19352 38707 19354 38707 19617 38707 19617 38708 19354 38708 19062 38708 19617 38709 19062 38709 19355 38709 19355 38710 19062 38710 19356 38710 19355 38711 19356 38711 19357 38711 19357 38712 19356 38712 19358 38712 19357 38713 19358 38713 10479 38713 10479 38714 19358 38714 19054 38714 10565 38715 18953 38715 19359 38715 19359 38716 18953 38716 19376 38716 19363 38717 19360 38717 19622 38717 19622 38718 19360 38718 19361 38718 19622 38719 19361 38719 10473 38719 19623 38720 18951 38720 19362 38720 19362 38721 18951 38721 19364 38721 19362 38722 19364 38722 19363 38722 19363 38723 19364 38723 19360 38723 18951 38724 19623 38724 18949 38724 18949 38725 19623 38725 19365 38725 18949 38726 19365 38726 19366 38726 19366 38727 19365 38727 19368 38727 19366 38728 19368 38728 19367 38728 19367 38729 19368 38729 19625 38729 19367 38730 19625 38730 19371 38730 19371 38731 19625 38731 19627 38731 19374 38732 19372 38732 19369 38732 19369 38733 19372 38733 19370 38733 19369 38734 19370 38734 19627 38734 19627 38735 19370 38735 19371 38735 19372 38736 19374 38736 19373 38736 19373 38737 19374 38737 10467 38737 19631 38738 19375 38738 19630 38738 19630 38739 19375 38739 18941 38739 19630 38740 18941 38740 10278 38740 10278 38741 18941 38741 18943 38741 19376 38742 18953 38742 19633 38742 19633 38743 18953 38743 19377 38743 19633 38744 19377 38744 19632 38744 19632 38745 19377 38745 18954 38745 19632 38746 18954 38746 19631 38746 19631 38747 18954 38747 19375 38747 19635 38748 19380 38748 19378 38748 19378 38749 19380 38749 19379 38749 19378 38750 19379 38750 19393 38750 19393 38751 19379 38751 19394 38751 19380 38752 19635 38752 19637 38752 19380 38753 19637 38753 10567 38753 10567 38754 19637 38754 19639 38754 10567 38755 19639 38755 18929 38755 18929 38756 19639 38756 19640 38756 18929 38757 19640 38757 19381 38757 19381 38758 19640 38758 19383 38758 19381 38759 19383 38759 19384 38759 19385 38760 18923 38760 19643 38760 19643 38761 18923 38761 19382 38761 19643 38762 19382 38762 19383 38762 19383 38763 19382 38763 19384 38763 18923 38764 19385 38764 19386 38764 18923 38765 19386 38765 18924 38765 18924 38766 19386 38766 19644 38766 18924 38767 19644 38767 19387 38767 19387 38768 19644 38768 19388 38768 19388 38769 19644 38769 10276 38769 19388 38770 10276 38770 10466 38770 19648 38771 18920 38771 19389 38771 19389 38772 18920 38772 18921 38772 19389 38773 18921 38773 19390 38773 19390 38774 18921 38774 19391 38774 19652 38775 19392 38775 19651 38775 19651 38776 19392 38776 18939 38776 19651 38777 18939 38777 19649 38777 19649 38778 18939 38778 18940 38778 19649 38779 18940 38779 19648 38779 19648 38780 18940 38780 18920 38780 18937 38781 19392 38781 19653 38781 19653 38782 19392 38782 19652 38782 19393 38783 19394 38783 19655 38783 19655 38784 19394 38784 19395 38784 19655 38785 19395 38785 19396 38785 19396 38786 19395 38786 18934 38786 19396 38787 18934 38787 19653 38787 19653 38788 18934 38788 18937 38788 19662 38789 10568 38789 19659 38789 19659 38790 10568 38790 19397 38790 19659 38791 19397 38791 19658 38791 19658 38792 19397 38792 19413 38792 10568 38793 19662 38793 19663 38793 10568 38794 19663 38794 10569 38794 10569 38795 19663 38795 19398 38795 10569 38796 19398 38796 19399 38796 19399 38797 19398 38797 19401 38797 19399 38798 19401 38798 19400 38798 19400 38799 19401 38799 10571 38799 10571 38800 19401 38800 19402 38800 10571 38801 19402 38801 18910 38801 19669 38802 18908 38802 19667 38802 19667 38803 18908 38803 18911 38803 19667 38804 18911 38804 19402 38804 19402 38805 18911 38805 18910 38805 18908 38806 19669 38806 19403 38806 19403 38807 19669 38807 19671 38807 19403 38808 19671 38808 19404 38808 19404 38809 19671 38809 19672 38809 19404 38810 19672 38810 19405 38810 19405 38811 19672 38811 19673 38811 19405 38812 19673 38812 18905 38812 18905 38813 19673 38813 19407 38813 19406 38814 19410 38814 19677 38814 19677 38815 19410 38815 18903 38815 19677 38816 18903 38816 19407 38816 19407 38817 18903 38817 18905 38817 19679 38818 19411 38818 19408 38818 19679 38819 19408 38819 10274 38819 10274 38820 19408 38820 18918 38820 10274 38821 18918 38821 19409 38821 19409 38822 18918 38822 19410 38822 19409 38823 19410 38823 19406 38823 18917 38824 19411 38824 19412 38824 19412 38825 19411 38825 19679 38825 19658 38826 19413 38826 19414 38826 19414 38827 19413 38827 19415 38827 19414 38828 19415 38828 19681 38828 19681 38829 19415 38829 19416 38829 19681 38830 19416 38830 19412 38830 19412 38831 19416 38831 18917 38831 19420 38832 19417 38832 19683 38832 19683 38833 19417 38833 19418 38833 19683 38834 19418 38834 19419 38834 19419 38835 19418 38835 19435 38835 19417 38836 19420 38836 18894 38836 18894 38837 19420 38837 19421 38837 18894 38838 19421 38838 19422 38838 19422 38839 19421 38839 19423 38839 19422 38840 19423 38840 19424 38840 19424 38841 19423 38841 19686 38841 19424 38842 19686 38842 19425 38842 19425 38843 19686 38843 19688 38843 19429 38844 19428 38844 19426 38844 19426 38845 19428 38845 19427 38845 19426 38846 19427 38846 19688 38846 19688 38847 19427 38847 19425 38847 19428 38848 19429 38848 18892 38848 18892 38849 19429 38849 19691 38849 18892 38850 19691 38850 18891 38850 18891 38851 19691 38851 19692 38851 18891 38852 19692 38852 18890 38852 18890 38853 19692 38853 19431 38853 18890 38854 19431 38854 19430 38854 19430 38855 19431 38855 19432 38855 19430 38856 19432 38856 18889 38856 19696 38857 19433 38857 19695 38857 19695 38858 19433 38858 18887 38858 19695 38859 18887 38859 19432 38859 19432 38860 18887 38860 18889 38860 19702 38861 18899 38861 19434 38861 19434 38862 18899 38862 18900 38862 19434 38863 18900 38863 19698 38863 19698 38864 18900 38864 18902 38864 19698 38865 18902 38865 19696 38865 19696 38866 18902 38866 19433 38866 18898 38867 18899 38867 19704 38867 19704 38868 18899 38868 19702 38868 19419 38869 19435 38869 19436 38869 19419 38870 19436 38870 19707 38870 19707 38871 19436 38871 19438 38871 19707 38872 19438 38872 19437 38872 19437 38873 19438 38873 18898 38873 19437 38874 18898 38874 19704 38874 19441 38875 18977 38875 19439 38875 19439 38876 18977 38876 19440 38876 19439 38877 19440 38877 19725 38877 19725 38878 19440 38878 18982 38878 18977 38879 19441 38879 10459 38879 10459 38880 19441 38880 10460 38880 19712 38881 19444 38881 19442 38881 19442 38882 19444 38882 19443 38882 19442 38883 19443 38883 10465 38883 10465 38884 19443 38884 18975 38884 19444 38885 19712 38885 19446 38885 19444 38886 19446 38886 19445 38886 19445 38887 19446 38887 19447 38887 19445 38888 19447 38888 10562 38888 10562 38889 19447 38889 19448 38889 10562 38890 19448 38890 18974 38890 18974 38891 19448 38891 19714 38891 18974 38892 19714 38892 18972 38892 19717 38893 18987 38893 19716 38893 19716 38894 18987 38894 19449 38894 19716 38895 19449 38895 19714 38895 19714 38896 19449 38896 18972 38896 19719 38897 18985 38897 19450 38897 19450 38898 18985 38898 19452 38898 19450 38899 19452 38899 19451 38899 19451 38900 19452 38900 19453 38900 19451 38901 19453 38901 19717 38901 19717 38902 19453 38902 18987 38902 19455 38903 18985 38903 19454 38903 19454 38904 18985 38904 19719 38904 19725 38905 18982 38905 19724 38905 19724 38906 18982 38906 18983 38906 19724 38907 18983 38907 19721 38907 19721 38908 18983 38908 18984 38908 19721 38909 18984 38909 19454 38909 19454 38910 18984 38910 19455 38910 19727 38911 19457 38911 19456 38911 19456 38912 19457 38912 18967 38912 19456 38913 18967 38913 19472 38913 19472 38914 18967 38914 18968 38914 18963 38915 19457 38915 19458 38915 19458 38916 19457 38916 19727 38916 18963 38917 19458 38917 19459 38917 19459 38918 19458 38918 19730 38918 19459 38919 19730 38919 19460 38919 19460 38920 19730 38920 18966 38920 18966 38921 19730 38921 19731 38921 18966 38922 19731 38922 19461 38922 19732 38923 18958 38923 19733 38923 19733 38924 18958 38924 18959 38924 19733 38925 18959 38925 10271 38925 10271 38926 18959 38926 18961 38926 18958 38927 19732 38927 19462 38927 19462 38928 19732 38928 19463 38928 19462 38929 19463 38929 19464 38929 19464 38930 19463 38930 19465 38930 19464 38931 19465 38931 18956 38931 18956 38932 19465 38932 19467 38932 18956 38933 19467 38933 19466 38933 19466 38934 19467 38934 19468 38934 19739 38935 10458 38935 19737 38935 19737 38936 10458 38936 18955 38936 19737 38937 18955 38937 19468 38937 19468 38938 18955 38938 19466 38938 19745 38939 19469 38939 19470 38939 19745 38940 19470 38940 19744 38940 19744 38941 19470 38941 10457 38941 19744 38942 10457 38942 19471 38942 19477 38943 19469 38943 19475 38943 19475 38944 19469 38944 19745 38944 19472 38945 18968 38945 19748 38945 19748 38946 18968 38946 19473 38946 19748 38947 19473 38947 19474 38947 19474 38948 19473 38948 19476 38948 19474 38949 19476 38949 19475 38949 19475 38950 19476 38950 19477 38950 19478 38951 18806 38951 19754 38951 19754 38952 18806 38952 18807 38952 19754 38953 18807 38953 19753 38953 19753 38954 18807 38954 19479 38954 19753 38955 19479 38955 19752 38955 19752 38956 19479 38956 18805 38956 19752 38957 18805 38957 19480 38957 19480 38958 18805 38958 18804 38958 19480 38959 18804 38959 19481 38959 19481 38960 18804 38960 19482 38960 19481 38961 19482 38961 19483 38961 19483 38962 19482 38962 19484 38962 19483 38963 19484 38963 19485 38963 19485 38964 19484 38964 10448 38964 19764 38965 10621 38965 19486 38965 19486 38966 10621 38966 19487 38966 19486 38967 19487 38967 19488 38967 19488 38968 19487 38968 19489 38968 19488 38969 19489 38969 19762 38969 19762 38970 19489 38970 18841 38970 19762 38971 18841 38971 19490 38971 19490 38972 18841 38972 19491 38972 19490 38973 19491 38973 19759 38973 19759 38974 19491 38974 18844 38974 19759 38975 18844 38975 19757 38975 19757 38976 18844 38976 18845 38976 19757 38977 18845 38977 19492 38977 19492 38978 18845 38978 10442 38978 10440 38979 10441 38979 19773 38979 19773 38980 10441 38980 18834 38980 19773 38981 18834 38981 19493 38981 19493 38982 18834 38982 18835 38982 19493 38983 18835 38983 19770 38983 19770 38984 18835 38984 19494 38984 19770 38985 19494 38985 19767 38985 19767 38986 19494 38986 19495 38986 19767 38987 19495 38987 19496 38987 19496 38988 19495 38988 18838 38988 19496 38989 18838 38989 19765 38989 19765 38990 18838 38990 19497 38990 19765 38991 19497 38991 10256 38991 10256 38992 19497 38992 10432 38992 19498 38993 10417 38993 19499 38993 19499 38994 10417 38994 19500 38994 19499 38995 19500 38995 19776 38995 19776 38996 19500 38996 19501 38996 19776 38997 19501 38997 19502 38997 19502 38998 19501 38998 18831 38998 19502 38999 18831 38999 19503 38999 19503 39000 18831 39000 19504 39000 19503 39001 19504 39001 19505 39001 19505 39002 19504 39002 19507 39002 19505 39003 19507 39003 19506 39003 19506 39004 19507 39004 19508 39004 19506 39005 19508 39005 19779 39005 19779 39006 19508 39006 18826 39006 19779 39007 18826 39007 19780 39007 19780 39008 18826 39008 19509 39008 19780 39009 19509 39009 19510 39009 19510 39010 19509 39010 19511 39010 19510 39011 19511 39011 19512 39011 19512 39012 19511 39012 18827 39012 19512 39013 18827 39013 19783 39013 19783 39014 18827 39014 19513 39014 19783 39015 19513 39015 19514 39015 19514 39016 19513 39016 10430 39016 19784 39017 10416 39017 19515 39017 19515 39018 10416 39018 19516 39018 19515 39019 19516 39019 19794 39019 19794 39020 19516 39020 19517 39020 19794 39021 19517 39021 19518 39021 19518 39022 19517 39022 19519 39022 19518 39023 19519 39023 19790 39023 19790 39024 19519 39024 18822 39024 19790 39025 18822 39025 19789 39025 19789 39026 18822 39026 18824 39026 19789 39027 18824 39027 19786 39027 19786 39028 18824 39028 19520 39028 19786 39029 19520 39029 10240 39029 10240 39030 19520 39030 10412 39030 10411 39031 18814 39031 19521 39031 19521 39032 18814 39032 18815 39032 19521 39033 18815 39033 19795 39033 19795 39034 18815 39034 18817 39034 19795 39035 18817 39035 19797 39035 19797 39036 18817 39036 19522 39036 19797 39037 19522 39037 19523 39037 19523 39038 19522 39038 19524 39038 19523 39039 19524 39039 19796 39039 19796 39040 19524 39040 19525 39040 19796 39041 19525 39041 10405 39041 10405 39042 19525 39042 18820 39042 19526 39043 10404 39043 19803 39043 19803 39044 10404 39044 19527 39044 19803 39045 19527 39045 19800 39045 19800 39046 19527 39046 18809 39046 19800 39047 18809 39047 19806 39047 19806 39048 18809 39048 18810 39048 19806 39049 18810 39049 19805 39049 19805 39050 18810 39050 18811 39050 19805 39051 18811 39051 19528 39051 19528 39052 18811 39052 19529 39052 19528 39053 19529 39053 19804 39053 19804 39054 19529 39054 19530 39054 10209 39055 10579 39055 19810 39055 19810 39056 10579 39056 19531 39056 19810 39057 19531 39057 19809 39057 19809 39058 19531 39058 18879 39058 19809 39059 18879 39059 19532 39059 19532 39060 18879 39060 18881 39060 19532 39061 18881 39061 19812 39061 19812 39062 18881 39062 19533 39062 19812 39063 19533 39063 19534 39063 19534 39064 19533 39064 18883 39064 19534 39065 18883 39065 10215 39065 10215 39066 18883 39066 18885 39066 10205 39067 10586 39067 19816 39067 19816 39068 10586 39068 19535 39068 19816 39069 19535 39069 19815 39069 19815 39070 19535 39070 18872 39070 19815 39071 18872 39071 19814 39071 19814 39072 18872 39072 18874 39072 19814 39073 18874 39073 19819 39073 19819 39074 18874 39074 18876 39074 19819 39075 18876 39075 19817 39075 19817 39076 18876 39076 18878 39076 19817 39077 18878 39077 19536 39077 19536 39078 18878 39078 10382 39078 10381 39079 18867 39079 19537 39079 19537 39080 18867 39080 19538 39080 19537 39081 19538 39081 19823 39081 19823 39082 19538 39082 18868 39082 19823 39083 18868 39083 19539 39083 19539 39084 18868 39084 18869 39084 19539 39085 18869 39085 19824 39085 19824 39086 18869 39086 18870 39086 19824 39087 18870 39087 19540 39087 19540 39088 18870 39088 19541 39088 19540 39089 19541 39089 19827 39089 19827 39090 19541 39090 10372 39090 10370 39091 10599 39091 19833 39091 19833 39092 10599 39092 19542 39092 19833 39093 19542 39093 19832 39093 19832 39094 19542 39094 18861 39094 19832 39095 18861 39095 19831 39095 19831 39096 18861 39096 19544 39096 19831 39097 19544 39097 19543 39097 19543 39098 19544 39098 18863 39098 19543 39099 18863 39099 19545 39099 19545 39100 18863 39100 18864 39100 19545 39101 18864 39101 19829 39101 19829 39102 18864 39102 19546 39102 19829 39103 19546 39103 19828 39103 19828 39104 19546 39104 10595 39104 19547 39105 10364 39105 19548 39105 19548 39106 10364 39106 18851 39106 19548 39107 18851 39107 19549 39107 19549 39108 18851 39108 18853 39108 19549 39109 18853 39109 19550 39109 19550 39110 18853 39110 18854 39110 19550 39111 18854 39111 19836 39111 19836 39112 18854 39112 18856 39112 19836 39113 18856 39113 19551 39113 19551 39114 18856 39114 18859 39114 19551 39115 18859 39115 19835 39115 19835 39116 18859 39116 19552 39116 19553 39117 10613 39117 19554 39117 19554 39118 10613 39118 19555 39118 19554 39119 19555 39119 19556 39119 19556 39120 19555 39120 18847 39120 19556 39121 18847 39121 19557 39121 19557 39122 18847 39122 19558 39122 19557 39123 19558 39123 19839 39123 19839 39124 19558 39124 19559 39124 19839 39125 19559 39125 19560 39125 19560 39126 19559 39126 19561 39126 19560 39127 19561 39127 19838 39127 19838 39128 19561 39128 18850 39128 10351 39129 19562 39129 19937 39129 19937 39130 19562 39130 18988 39130 19937 39131 18988 39131 19938 39131 19938 39132 18988 39132 19563 39132 19938 39133 19563 39133 19939 39133 19939 39134 19563 39134 19564 39134 19939 39135 19564 39135 19982 39135 19982 39136 19564 39136 19565 39136 19982 39137 19565 39137 19980 39137 19980 39138 19565 39138 18991 39138 19980 39139 18991 39139 19979 39139 19979 39140 18991 39140 10343 39140 19989 39141 10549 39141 19566 39141 19566 39142 10549 39142 19567 39142 19566 39143 19567 39143 19568 39143 19568 39144 19567 39144 19569 39144 19568 39145 19569 39145 19570 39145 19570 39146 19569 39146 18994 39146 19570 39147 18994 39147 19571 39147 19571 39148 18994 39148 18995 39148 19571 39149 18995 39149 19572 39149 19572 39150 18995 39150 19573 39150 19572 39151 19573 39151 19991 39151 19991 39152 19573 39152 10335 39152 10334 39153 10547 39153 20007 39153 20007 39154 10547 39154 18998 39154 20007 39155 18998 39155 19574 39155 19574 39156 18998 39156 19000 39156 19574 39157 19000 39157 19575 39157 19575 39158 19000 39158 19001 39158 19575 39159 19001 39159 20009 39159 20009 39160 19001 39160 19576 39160 20009 39161 19576 39161 20008 39161 20008 39162 19576 39162 19577 39162 20008 39163 19577 39163 20010 39163 20010 39164 19577 39164 10541 39164 10328 39165 19002 39165 19578 39165 19578 39166 19002 39166 19003 39166 19578 39167 19003 39167 19869 39167 19869 39168 19003 39168 19004 39168 19869 39169 19004 39169 19579 39169 19579 39170 19004 39170 19006 39170 19579 39171 19006 39171 19870 39171 19870 39172 19006 39172 19007 39172 19870 39173 19007 39173 19580 39173 19580 39174 19007 39174 19009 39174 19580 39175 19009 39175 19872 39175 19872 39176 19009 39176 19581 39176 19872 39177 19581 39177 19871 39177 19871 39178 19581 39178 19582 39178 19880 39179 19010 39179 19583 39179 19583 39180 19010 39180 19011 39180 19583 39181 19011 39181 20050 39181 20050 39182 19011 39182 19585 39182 20050 39183 19585 39183 19584 39183 19584 39184 19585 39184 19586 39184 19584 39185 19586 39185 19588 39185 19588 39186 19586 39186 19587 39186 19588 39187 19587 39187 19881 39187 19881 39188 19587 39188 19015 39188 19881 39189 19015 39189 19589 39189 19589 39190 19015 39190 19017 39190 10314 39191 19590 39191 19025 39191 10314 39192 19025 39192 19885 39192 19885 39193 19025 39193 19026 39193 19885 39194 19026 39194 19905 39194 19905 39195 19026 39195 19027 39195 19905 39196 19027 39196 19591 39196 19591 39197 19027 39197 19028 39197 19591 39198 19028 39198 19592 39198 19028 39199 19024 39199 19592 39199 19592 39200 19024 39200 19594 39200 19592 39201 19594 39201 19593 39201 19593 39202 19594 39202 19595 39202 19595 39203 19022 39203 19593 39203 19593 39204 19022 39204 19020 39204 19593 39205 19020 39205 19596 39205 19596 39206 19020 39206 19597 39206 19596 39207 19597 39207 10310 39207 19598 39208 10522 39208 19599 39208 19599 39209 10522 39209 19600 39209 19599 39210 19600 39210 20075 39210 20075 39211 19600 39211 19031 39211 20075 39212 19031 39212 19847 39212 19847 39213 19031 39213 19601 39213 19847 39214 19601 39214 20076 39214 20076 39215 19601 39215 19602 39215 20076 39216 19602 39216 20077 39216 20077 39217 19602 39217 19603 39217 20077 39218 19603 39218 19604 39218 19604 39219 19603 39219 10298 39219 10296 39220 10297 39220 19605 39220 19605 39221 10297 39221 19606 39221 19605 39222 19606 39222 19607 39222 19607 39223 19606 39223 19608 39223 19607 39224 19608 39224 19610 39224 19610 39225 19608 39225 19609 39225 19610 39226 19609 39226 20088 39226 20088 39227 19609 39227 19039 39227 20088 39228 19039 39228 19612 39228 19612 39229 19039 39229 19611 39229 19612 39230 19611 39230 19613 39230 19613 39231 19611 39231 19614 39231 19613 39232 19614 39232 10290 39232 10290 39233 19614 39233 19040 39233 10289 39234 19615 39234 19926 39234 19926 39235 19615 39235 19616 39235 19926 39236 19616 39236 20100 39236 20100 39237 19616 39237 19352 39237 20100 39238 19352 39238 20099 39238 20099 39239 19352 39239 19617 39239 20099 39240 19617 39240 19618 39240 19618 39241 19617 39241 19355 39241 19618 39242 19355 39242 19619 39242 19619 39243 19355 39243 19357 39243 19619 39244 19357 39244 19620 39244 19620 39245 19357 39245 10479 39245 19359 39246 19376 39246 19891 39246 19891 39247 19376 39247 19889 39247 19888 39248 19894 39248 19363 39248 19359 39249 19891 39249 19621 39249 19621 39250 19891 39250 19892 39250 19621 39251 19892 39251 10473 39251 10473 39252 19892 39252 19888 39252 10473 39253 19888 39253 19622 39253 19622 39254 19888 39254 19363 39254 19363 39255 19894 39255 19362 39255 19362 39256 19894 39256 19895 39256 19362 39257 19895 39257 19623 39257 19623 39258 19895 39258 19896 39258 19623 39259 19896 39259 19365 39259 19365 39260 19896 39260 19898 39260 19365 39261 19898 39261 19368 39261 19368 39262 19898 39262 19624 39262 19368 39263 19624 39263 19625 39263 19625 39264 19624 39264 19626 39264 19625 39265 19626 39265 19627 39265 19627 39266 19626 39266 20069 39266 19627 39267 20069 39267 19369 39267 19369 39268 20069 39268 19884 39268 19369 39269 19884 39269 19374 39269 19374 39270 19884 39270 19628 39270 19374 39271 19628 39271 10467 39271 10467 39272 19628 39272 19908 39272 10278 39273 19629 39273 19630 39273 19630 39274 19629 39274 19904 39274 19630 39275 19904 39275 19631 39275 19631 39276 19904 39276 19903 39276 19631 39277 19903 39277 19632 39277 19632 39278 19903 39278 19902 39278 19632 39279 19902 39279 19633 39279 19633 39280 19902 39280 19634 39280 19633 39281 19634 39281 19376 39281 19376 39282 19634 39282 19889 39282 19393 39283 19657 39283 19378 39283 19378 39284 19657 39284 19911 39284 19378 39285 19911 39285 19635 39285 19635 39286 19911 39286 19636 39286 19635 39287 19636 39287 19637 39287 19637 39288 19636 39288 19638 39288 19637 39289 19638 39289 19639 39289 19639 39290 19638 39290 19909 39290 19639 39291 19909 39291 19640 39291 19640 39292 19909 39292 19641 39292 19640 39293 19641 39293 19383 39293 19383 39294 19641 39294 19642 39294 19383 39295 19642 39295 19643 39295 19643 39296 19642 39296 19914 39296 19643 39297 19914 39297 19385 39297 19385 39298 19914 39298 19915 39298 19385 39299 19915 39299 19386 39299 19386 39300 19915 39300 19916 39300 19386 39301 19916 39301 19644 39301 19644 39302 19916 39302 19645 39302 19644 39303 19645 39303 10276 39303 10276 39304 19645 39304 19646 39304 19390 39305 19897 39305 19389 39305 19389 39306 19897 39306 19647 39306 19389 39307 19647 39307 19648 39307 19648 39308 19647 39308 19650 39308 19648 39309 19650 39309 19649 39309 19649 39310 19650 39310 19865 39310 19649 39311 19865 39311 19651 39311 19651 39312 19865 39312 19864 39312 19651 39313 19864 39313 19652 39313 19652 39314 19864 39314 19919 39314 19653 39315 19652 39315 19917 39315 19917 39316 19652 39316 19919 39316 19653 39317 19917 39317 19396 39317 19396 39318 19917 39318 19654 39318 19396 39319 19654 39319 19655 39319 19655 39320 19654 39320 19656 39320 19655 39321 19656 39321 19393 39321 19393 39322 19656 39322 19657 39322 19658 39323 19660 39323 19659 39323 19659 39324 19660 39324 19920 39324 19659 39325 19920 39325 19662 39325 19662 39326 19920 39326 19661 39326 19662 39327 19661 39327 19663 39327 19663 39328 19661 39328 19664 39328 19663 39329 19664 39329 19398 39329 19398 39330 19664 39330 19925 39330 19398 39331 19925 39331 19401 39331 19401 39332 19925 39332 19665 39332 19401 39333 19665 39333 19402 39333 19402 39334 19665 39334 19924 39334 19670 39335 19669 39335 20098 39335 20098 39336 19669 39336 19667 39336 20098 39337 19667 39337 19666 39337 19666 39338 19667 39338 19668 39338 19668 39339 19667 39339 19402 39339 19668 39340 19402 39340 19924 39340 19669 39341 19670 39341 19671 39341 19671 39342 19670 39342 20093 39342 19671 39343 20093 39343 19672 39343 19672 39344 20093 39344 19674 39344 19672 39345 19674 39345 19673 39345 19673 39346 19674 39346 19675 39346 19673 39347 19675 39347 19407 39347 19407 39348 19675 39348 19676 39348 19407 39349 19676 39349 19677 39349 19677 39350 19676 39350 19928 39350 19677 39351 19928 39351 19406 39351 19406 39352 19928 39352 19930 39352 19406 39353 19930 39353 19409 39353 19409 39354 19930 39354 19678 39354 19412 39355 19679 39355 19680 39355 19680 39356 19679 39356 19948 39356 19412 39357 19680 39357 19681 39357 19681 39358 19680 39358 19950 39358 19681 39359 19950 39359 19414 39359 19414 39360 19950 39360 19682 39360 19414 39361 19682 39361 19658 39361 19658 39362 19682 39362 19660 39362 19419 39363 10273 39363 19683 39363 19683 39364 10273 39364 19953 39364 19683 39365 19953 39365 19420 39365 19420 39366 19953 39366 19684 39366 19420 39367 19684 39367 19421 39367 19421 39368 19684 39368 19933 39368 19421 39369 19933 39369 19423 39369 19423 39370 19933 39370 19685 39370 19423 39371 19685 39371 19686 39371 19686 39372 19685 39372 19687 39372 19686 39373 19687 39373 19688 39373 19688 39374 19687 39374 19934 39374 19690 39375 19429 39375 19943 39375 19943 39376 19429 39376 19426 39376 19943 39377 19426 39377 19977 39377 19688 39378 19934 39378 19426 39378 19426 39379 19934 39379 19689 39379 19426 39380 19689 39380 19977 39380 19429 39381 19690 39381 19691 39381 19691 39382 19690 39382 19945 39382 19691 39383 19945 39383 19692 39383 19692 39384 19945 39384 19946 39384 19692 39385 19946 39385 19431 39385 19431 39386 19946 39386 19693 39386 19431 39387 19693 39387 19432 39387 19432 39388 19693 39388 19694 39388 19432 39389 19694 39389 19695 39389 19695 39390 19694 39390 19697 39390 19695 39391 19697 39391 19696 39391 19696 39392 19697 39392 19699 39392 19696 39393 19699 39393 19698 39393 19698 39394 19699 39394 19700 39394 19698 39395 19700 39395 19434 39395 19434 39396 19700 39396 19701 39396 19434 39397 19701 39397 19702 39397 19702 39398 19701 39398 19703 39398 19704 39399 19702 39399 19705 39399 19705 39400 19702 39400 19703 39400 19704 39401 19705 39401 19437 39401 19437 39402 19705 39402 19706 39402 19437 39403 19706 39403 19707 39403 19707 39404 19706 39404 19708 39404 19725 39405 19726 39405 19439 39405 19439 39406 19726 39406 19709 39406 19439 39407 19709 39407 19441 39407 19441 39408 19709 39408 19710 39408 19441 39409 19710 39409 10460 39409 10460 39410 19710 39410 19959 39410 10465 39411 19711 39411 19442 39411 19442 39412 19711 39412 20004 39412 19442 39413 20004 39413 19712 39413 19712 39414 20004 39414 19713 39414 19712 39415 19713 39415 19446 39415 19446 39416 19713 39416 19998 39416 19446 39417 19998 39417 19447 39417 19447 39418 19998 39418 19999 39418 19447 39419 19999 39419 19448 39419 19448 39420 19999 39420 19955 39420 19448 39421 19955 39421 19714 39421 19714 39422 19955 39422 19954 39422 19714 39423 19954 39423 19716 39423 19716 39424 19954 39424 19715 39424 19716 39425 19715 39425 19717 39425 19717 39426 19715 39426 19718 39426 19717 39427 19718 39427 19451 39427 19451 39428 19718 39428 19862 39428 19451 39429 19862 39429 19450 39429 19450 39430 19862 39430 19720 39430 19450 39431 19720 39431 19719 39431 19719 39432 19720 39432 19956 39432 19454 39433 19719 39433 19722 39433 19722 39434 19719 39434 19956 39434 19454 39435 19722 39435 19721 39435 19721 39436 19722 39436 19723 39436 19721 39437 19723 39437 19724 39437 19724 39438 19723 39438 19861 39438 19724 39439 19861 39439 19725 39439 19725 39440 19861 39440 19726 39440 19472 39441 19964 39441 19456 39441 19456 39442 19964 39442 19728 39442 19456 39443 19728 39443 19727 39443 19727 39444 19728 39444 19962 39444 19727 39445 19962 39445 19458 39445 19458 39446 19962 39446 19729 39446 19458 39447 19729 39447 19730 39447 19730 39448 19729 39448 19960 39448 19730 39449 19960 39449 19731 39449 19731 39450 19960 39450 10272 39450 19735 39451 19732 39451 20028 39451 20028 39452 19732 39452 19733 39452 20028 39453 19733 39453 20045 39453 20045 39454 19733 39454 10271 39454 20045 39455 10271 39455 19734 39455 19732 39456 19735 39456 19463 39456 19463 39457 19735 39457 20029 39457 19463 39458 20029 39458 19465 39458 19465 39459 20029 39459 19952 39459 19465 39460 19952 39460 19467 39460 19467 39461 19952 39461 19958 39461 19467 39462 19958 39462 19468 39462 19468 39463 19958 39463 19736 39463 19468 39464 19736 39464 19737 39464 19737 39465 19736 39465 19738 39465 19737 39466 19738 39466 19739 39466 19739 39467 19738 39467 19741 39467 19967 39468 19745 39468 19740 39468 19740 39469 19745 39469 19744 39469 19740 39470 19744 39470 19743 39470 19739 39471 19741 39471 19742 39471 19742 39472 19741 39472 19743 39472 19742 39473 19743 39473 19471 39473 19471 39474 19743 39474 19744 39474 19475 39475 19745 39475 19746 39475 19746 39476 19745 39476 19967 39476 19475 39477 19746 39477 19474 39477 19474 39478 19746 39478 19747 39478 19474 39479 19747 39479 19748 39479 19748 39480 19747 39480 19966 39480 19748 39481 19966 39481 19472 39481 19472 39482 19966 39482 19964 39482 19485 39483 19963 39483 19483 39483 19483 39484 19963 39484 19749 39484 19483 39485 19749 39485 19481 39485 19481 39486 19749 39486 19750 39486 19481 39487 19750 39487 19480 39487 19480 39488 19750 39488 19751 39488 19480 39489 19751 39489 19752 39489 19752 39490 19751 39490 19969 39490 19752 39491 19969 39491 19753 39491 19753 39492 19969 39492 19968 39492 19753 39493 19968 39493 19754 39493 19754 39494 19968 39494 19755 39494 19754 39495 19755 39495 19478 39495 19478 39496 19755 39496 19756 39496 19492 39497 10261 39497 19757 39497 19757 39498 10261 39498 19758 39498 19757 39499 19758 39499 19759 39499 19759 39500 19758 39500 19760 39500 19759 39501 19760 39501 19490 39501 19490 39502 19760 39502 19761 39502 19490 39503 19761 39503 19762 39503 19762 39504 19761 39504 19763 39504 19762 39505 19763 39505 19488 39505 19488 39506 19763 39506 19913 39506 19488 39507 19913 39507 19486 39507 19486 39508 19913 39508 19910 39508 19486 39509 19910 39509 19764 39509 19764 39510 19910 39510 10264 39510 10256 39511 19766 39511 19765 39511 19765 39512 19766 39512 20092 39512 19765 39513 20092 39513 19496 39513 19496 39514 20092 39514 19768 39514 19496 39515 19768 39515 19767 39515 19767 39516 19768 39516 19769 39516 19767 39517 19769 39517 19770 39517 19770 39518 19769 39518 19771 39518 19770 39519 19771 39519 19493 39519 19493 39520 19771 39520 19772 39520 19493 39521 19772 39521 19773 39521 19773 39522 19772 39522 19774 39522 19773 39523 19774 39523 10440 39523 10440 39524 19774 39524 20097 39524 19923 39525 19498 39525 19775 39525 19775 39526 19498 39526 19499 39526 19505 39527 19778 39527 19777 39527 19499 39528 19776 39528 19775 39528 19775 39529 19776 39529 19502 39529 19775 39530 19502 39530 19777 39530 19777 39531 19502 39531 19503 39531 19777 39532 19503 39532 19505 39532 19505 39533 19506 39533 19778 39533 19778 39534 19506 39534 19779 39534 19778 39535 19779 39535 19922 39535 19779 39536 19780 39536 19922 39536 19922 39537 19780 39537 19510 39537 19922 39538 19510 39538 19781 39538 19514 39539 19782 39539 19783 39539 19783 39540 19782 39540 19781 39540 19783 39541 19781 39541 19512 39541 19512 39542 19781 39542 19510 39542 19515 39543 20111 39543 19784 39543 19784 39544 20111 39544 19785 39544 19784 39545 19785 39545 19973 39545 10240 39546 19787 39546 19786 39546 19786 39547 19787 39547 19788 39547 19786 39548 19788 39548 19789 39548 19789 39549 19788 39549 19791 39549 19789 39550 19791 39550 19790 39550 19790 39551 19791 39551 19792 39551 19790 39552 19792 39552 19518 39552 19518 39553 19792 39553 19793 39553 19518 39554 19793 39554 19794 39554 19794 39555 19793 39555 19976 39555 19794 39556 19976 39556 19515 39556 19515 39557 19976 39557 19975 39557 19515 39558 19975 39558 20111 39558 19521 39559 19986 39559 10411 39559 10411 39560 19986 39560 19985 39560 10411 39561 19985 39561 19984 39561 19795 39562 19799 39562 19521 39562 19521 39563 19799 39563 19859 39563 19521 39564 19859 39564 19986 39564 10405 39565 19995 39565 19796 39565 19796 39566 19995 39566 19994 39566 19796 39567 19994 39567 19523 39567 19523 39568 19994 39568 19993 39568 19523 39569 19993 39569 19797 39569 19797 39570 19993 39570 19798 39570 19797 39571 19798 39571 19795 39571 19795 39572 19798 39572 19996 39572 19795 39573 19996 39573 19799 39573 19800 39574 19806 39574 20015 39574 20001 39575 19526 39575 19801 39575 19801 39576 19526 39576 19803 39576 19801 39577 19803 39577 19802 39577 19802 39578 19803 39578 19800 39578 19802 39579 19800 39579 20109 39579 20109 39580 19800 39580 20015 39580 19804 39581 20013 39581 19528 39581 19528 39582 20013 39582 20012 39582 19528 39583 20012 39583 19805 39583 19805 39584 20012 39584 19807 39584 19805 39585 19807 39585 19806 39585 19806 39586 19807 39586 19808 39586 19806 39587 19808 39587 20015 39587 19532 39588 19855 39588 19809 39588 19809 39589 19855 39589 20018 39589 19809 39590 20018 39590 19810 39590 19810 39591 20018 39591 20011 39591 19810 39592 20011 39592 10209 39592 10209 39593 20011 39593 10211 39593 19812 39594 19811 39594 19532 39594 19532 39595 19811 39595 20106 39595 19532 39596 20106 39596 19855 39596 10215 39597 20025 39597 19534 39597 19534 39598 20025 39598 20020 39598 19534 39599 20020 39599 19812 39599 19812 39600 20020 39600 19813 39600 19812 39601 19813 39601 19811 39601 19817 39602 19536 39602 20038 39602 19819 39603 19853 39603 19814 39603 19814 39604 19853 39604 20033 39604 19814 39605 20033 39605 19815 39605 19815 39606 20033 39606 20032 39606 19815 39607 20032 39607 19816 39607 19816 39608 20032 39608 20031 39608 19816 39609 20031 39609 10205 39609 10205 39610 20031 39610 20030 39610 20038 39611 20034 39611 19817 39611 19817 39612 20034 39612 19818 39612 19817 39613 19818 39613 19819 39613 19819 39614 19818 39614 19854 39614 19819 39615 19854 39615 19853 39615 19820 39616 10381 39616 19821 39616 19821 39617 10381 39617 19537 39617 19821 39618 19537 39618 19822 39618 19822 39619 19537 39619 19823 39619 19822 39620 19823 39620 20040 39620 20040 39621 19823 39621 19539 39621 20040 39622 19539 39622 20042 39622 20042 39623 19539 39623 19824 39623 20042 39624 19824 39624 20043 39624 20043 39625 19824 39625 19540 39625 20043 39626 19540 39626 19825 39626 19825 39627 19540 39627 19826 39627 19826 39628 19540 39628 19827 39628 19826 39629 19827 39629 10204 39629 19828 39630 19875 39630 19829 39630 19829 39631 19875 39631 19830 39631 19829 39632 19830 39632 19545 39632 19545 39633 19830 39633 19879 39633 19545 39634 19879 39634 19543 39634 19543 39635 19879 39635 19878 39635 19543 39636 19878 39636 19831 39636 19831 39637 19878 39637 19877 39637 19831 39638 19877 39638 19832 39638 19832 39639 19877 39639 19834 39639 19832 39640 19834 39640 19833 39640 19833 39641 19834 39641 20054 39641 19833 39642 20054 39642 10370 39642 10370 39643 20054 39643 19907 39643 19835 39644 10185 39644 19551 39644 19551 39645 10185 39645 19899 39645 19551 39646 19899 39646 19836 39646 19836 39647 19899 39647 19837 39647 19836 39648 19837 39648 19550 39648 19550 39649 19837 39649 20071 39649 19550 39650 20071 39650 19549 39650 19549 39651 20071 39651 20070 39651 19549 39652 20070 39652 19548 39652 19548 39653 20070 39653 20068 39653 19548 39654 20068 39654 19547 39654 19547 39655 20068 39655 20067 39655 19838 39656 10177 39656 19560 39656 19560 39657 10177 39657 19840 39657 19560 39658 19840 39658 19839 39658 19839 39659 19840 39659 19841 39659 19839 39660 19841 39660 19557 39660 19557 39661 19841 39661 19842 39661 19557 39662 19842 39662 19556 39662 19556 39663 19842 39663 19843 39663 19556 39664 19843 39664 19554 39664 19554 39665 19843 39665 19844 39665 19554 39666 19844 39666 19553 39666 19553 39667 19844 39667 10182 39667 10249 39668 19845 39668 10161 39668 10252 39669 10165 39669 20091 39669 10263 39670 10167 39670 19846 39670 19847 39671 19844 39671 19758 39671 10180 39672 10181 39672 19848 39672 20065 39673 20072 39673 19848 39673 10194 39674 19906 39674 10196 39674 19849 39675 20046 39675 19850 39675 19851 39676 19852 39676 20039 39676 19853 39677 19854 39677 20107 39677 20019 39678 20026 39678 20107 39678 19855 39679 20106 39679 19856 39679 19802 39680 20109 39680 19858 39680 19857 39681 20000 39681 19858 39681 19986 39682 19859 39682 19860 39682 10269 39683 19932 39683 19931 39683 19861 39684 19970 39684 19741 39684 19720 39685 19862 39685 19951 39685 19952 39686 20029 39686 19957 39686 20098 39687 20094 39687 19670 39687 10242 39688 19863 39688 19668 39688 19682 39689 19950 39689 19921 39689 19864 39690 19865 39690 19918 39690 19657 39691 19656 39691 19931 39691 20058 39692 10312 39692 20059 39692 10324 39693 19866 39693 19965 39693 19866 39694 10326 39694 20028 39694 20028 39695 10326 39695 20027 39695 19868 39696 19869 39696 20036 39696 20036 39697 19869 39697 19579 39697 19867 39698 10328 39698 19868 39698 19868 39699 10328 39699 19578 39699 19868 39700 19578 39700 19869 39700 20037 39701 19870 39701 19851 39701 19851 39702 19870 39702 19580 39702 10322 39703 19852 39703 19871 39703 19871 39704 19852 39704 19851 39704 19871 39705 19851 39705 19872 39705 19872 39706 19851 39706 19580 39706 20101 39707 19589 39707 19876 39707 10317 39708 19873 39708 19877 39708 19877 39709 19873 39709 19834 39709 19834 39710 19873 39710 10319 39710 19834 39711 10319 39711 20055 39711 19874 39712 10176 39712 19875 39712 19875 39713 10176 39713 20101 39713 19875 39714 20101 39714 10316 39714 10316 39715 20101 39715 19876 39715 19877 39716 19878 39716 10317 39716 10317 39717 19878 39717 19879 39717 10317 39718 19879 39718 10316 39718 10316 39719 19879 39719 19830 39719 10316 39720 19830 39720 19875 39720 19880 39721 19583 39721 19850 39721 19850 39722 19583 39722 20050 39722 19850 39723 20050 39723 20049 39723 19589 39724 20101 39724 19881 39724 19881 39725 20101 39725 19882 39725 19881 39726 19882 39726 19588 39726 10312 39727 10313 39727 20069 39727 10313 39728 19883 39728 20069 39728 20069 39729 19883 39729 10314 39729 20069 39730 10314 39730 19884 39730 19884 39731 10314 39731 19885 39731 19884 39732 19885 39732 19905 39732 20060 39733 20057 39733 19886 39733 19905 39734 19591 39734 19906 39734 19906 39735 19591 39735 19592 39735 19906 39736 19592 39736 10196 39736 10196 39737 19592 39737 19593 39737 10196 39738 19593 39738 19887 39738 19887 39739 19593 39739 19596 39739 19887 39740 19596 39740 10310 39740 19918 39741 19894 39741 19888 39741 19634 39742 19963 39742 19889 39742 19889 39743 19963 39743 19890 39743 19889 39744 19890 39744 19891 39744 19891 39745 19890 39745 19972 39745 19891 39746 19972 39746 19892 39746 19893 39747 19626 39747 19624 39747 19918 39748 19865 39748 19894 39748 19894 39749 19865 39749 19650 39749 19894 39750 19650 39750 19895 39750 19895 39751 19650 39751 19647 39751 19895 39752 19647 39752 19896 39752 19896 39753 19647 39753 19897 39753 19896 39754 19897 39754 19898 39754 19898 39755 19897 39755 19646 39755 19898 39756 19646 39756 19645 39756 19837 39757 19899 39757 20059 39757 10312 39758 20069 39758 20059 39758 20059 39759 20069 39759 20071 39759 20059 39760 20071 39760 19837 39760 20047 39761 19900 39761 19901 39761 19634 39762 19902 39762 19963 39762 19963 39763 19902 39763 19903 39763 19963 39764 19903 39764 19961 39764 19961 39765 19903 39765 19904 39765 19961 39766 19904 39766 20047 39766 20047 39767 19904 39767 19629 39767 20047 39768 19629 39768 19900 39768 19905 39769 19906 39769 19884 39769 19884 39770 19906 39770 10194 39770 19884 39771 10194 39771 19628 39771 19628 39772 10194 39772 19907 39772 19628 39773 19907 39773 19908 39773 19908 39774 19907 39774 20054 39774 19908 39775 20054 39775 19901 39775 19909 39776 19638 39776 19763 39776 19913 39777 19912 39777 19910 39777 19910 39778 19912 39778 20089 39778 19910 39779 20089 39779 10264 39779 19930 39780 19928 39780 19911 39780 19911 39781 19928 39781 19929 39781 19911 39782 19929 39782 19636 39782 19636 39783 19929 39783 19912 39783 19636 39784 19912 39784 19638 39784 19638 39785 19912 39785 19913 39785 19638 39786 19913 39786 19763 39786 19760 39787 19914 39787 19761 39787 19761 39788 19914 39788 19642 39788 19761 39789 19642 39789 19763 39789 19763 39790 19642 39790 19641 39790 19763 39791 19641 39791 19909 39791 20072 39792 19893 39792 19841 39792 19760 39793 19758 39793 19914 39793 19914 39794 19758 39794 19844 39794 19914 39795 19844 39795 19915 39795 19915 39796 19844 39796 19843 39796 19915 39797 19843 39797 19916 39797 19916 39798 19843 39798 19842 39798 19842 39799 19841 39799 19916 39799 19916 39800 19841 39800 19893 39800 19916 39801 19893 39801 19645 39801 19645 39802 19893 39802 19624 39802 19645 39803 19624 39803 19898 39803 19656 39804 19654 39804 19931 39804 19931 39805 19654 39805 19917 39805 19931 39806 19917 39806 19918 39806 19918 39807 19917 39807 19919 39807 19918 39808 19919 39808 19864 39808 19944 39809 19920 39809 19921 39809 19921 39810 19920 39810 19660 39810 19921 39811 19660 39811 19682 39811 19778 39812 19922 39812 19944 39812 19775 39813 19777 39813 10162 39813 10162 39814 19777 39814 19778 39814 19922 39815 19664 39815 19944 39815 19944 39816 19664 39816 19661 39816 19944 39817 19661 39817 19920 39817 19775 39818 10162 39818 19923 39818 19923 39819 10162 39819 10163 39819 19923 39820 10163 39820 10251 39820 10242 39821 19668 39821 19782 39821 19782 39822 19668 39822 19924 39822 19782 39823 19924 39823 19781 39823 19781 39824 19924 39824 19665 39824 19781 39825 19665 39825 19922 39825 19922 39826 19665 39826 19925 39826 19922 39827 19925 39827 19664 39827 19926 39828 10161 39828 10289 39828 10289 39829 10161 39829 19927 39829 10279 39830 10280 39830 20094 39830 20094 39831 10280 39831 10281 39831 20094 39832 10281 39832 20096 39832 10281 39833 10283 39833 20096 39833 20096 39834 10283 39834 10284 39834 20096 39835 10284 39835 19927 39835 19927 39836 10284 39836 10288 39836 19927 39837 10288 39837 10289 39837 19928 39838 19676 39838 19929 39838 19929 39839 19676 39839 19675 39839 19929 39840 19675 39840 19912 39840 19912 39841 19675 39841 19674 39841 19911 39842 19657 39842 19930 39842 19930 39843 19657 39843 19931 39843 19930 39844 19931 39844 19678 39844 19678 39845 19931 39845 10275 39845 10275 39846 19931 39846 19932 39846 10275 39847 19932 39847 19948 39847 19933 39848 19684 39848 19992 39848 19685 39849 19995 39849 19687 39849 19687 39850 19995 39850 19935 39850 19687 39851 19935 39851 19934 39851 19934 39852 19935 39852 19936 39852 19934 39853 19936 39853 19689 39853 19689 39854 19936 39854 10231 39854 20114 39855 19937 39855 19860 39855 19860 39856 19937 39856 19938 39856 19860 39857 19938 39857 19939 39857 10347 39858 10349 39858 19940 39858 19940 39859 10349 39859 19941 39859 19940 39860 19941 39860 20114 39860 20114 39861 19941 39861 10351 39861 20114 39862 10351 39862 19937 39862 19942 39863 10345 39863 19977 39863 19977 39864 10345 39864 10347 39864 10347 39865 19940 39865 19977 39865 19977 39866 19940 39866 19792 39866 19977 39867 19792 39867 19943 39867 10162 39868 10236 39868 10234 39868 19778 39869 19944 39869 10162 39869 10162 39870 19944 39870 19947 39870 10162 39871 19947 39871 10236 39871 19792 39872 19791 39872 19943 39872 19943 39873 19791 39873 19788 39873 19943 39874 19788 39874 19690 39874 19690 39875 19788 39875 19787 39875 19690 39876 19787 39876 19945 39876 19945 39877 19787 39877 10239 39877 19945 39878 10239 39878 19946 39878 19946 39879 10239 39879 19947 39879 19946 39880 19947 39880 19693 39880 19693 39881 19947 39881 19944 39881 19693 39882 19944 39882 19694 39882 19701 39883 19700 39883 19921 39883 19921 39884 19700 39884 19699 39884 19921 39885 19699 39885 19944 39885 19944 39886 19699 39886 19697 39886 19944 39887 19697 39887 19694 39887 19705 39888 19703 39888 19755 39888 19755 39889 19703 39889 19756 39889 19948 39890 19932 39890 19680 39890 19680 39891 19932 39891 19949 39891 19680 39892 19949 39892 19950 39892 19950 39893 19949 39893 19756 39893 19950 39894 19756 39894 19921 39894 19921 39895 19756 39895 19703 39895 19921 39896 19703 39896 19701 39896 19951 39897 10273 39897 19708 39897 19705 39898 19755 39898 19706 39898 19706 39899 19755 39899 19968 39899 19706 39900 19968 39900 19708 39900 19952 39901 19957 39901 19958 39901 20004 39902 19711 39902 10212 39902 10212 39903 19711 39903 20022 39903 19951 39904 19862 39904 10273 39904 10273 39905 19862 39905 19718 39905 10273 39906 19718 39906 19953 39906 19953 39907 19718 39907 19715 39907 19953 39908 19715 39908 19684 39908 19684 39909 19715 39909 19954 39909 19684 39910 19954 39910 19992 39910 19992 39911 19954 39911 19955 39911 19992 39912 19955 39912 19999 39912 19861 39913 19723 39913 19970 39913 19970 39914 19723 39914 19722 39914 19970 39915 19722 39915 19951 39915 19951 39916 19722 39916 19956 39916 19951 39917 19956 39917 19720 39917 19957 39918 20023 39918 19958 39918 19958 39919 20023 39919 19959 39919 19958 39920 19959 39920 19736 39920 19736 39921 19959 39921 19710 39921 19736 39922 19710 39922 19738 39922 19738 39923 19710 39923 19709 39923 19738 39924 19709 39924 19741 39924 19741 39925 19709 39925 19726 39925 19741 39926 19726 39926 19861 39926 10272 39927 19960 39927 20047 39927 19960 39928 19729 39928 20047 39928 20047 39929 19729 39929 19962 39929 20047 39930 19962 39930 19961 39930 19961 39931 19962 39931 19728 39931 19961 39932 19728 39932 19963 39932 19963 39933 19728 39933 19964 39933 19963 39934 19964 39934 19966 39934 19866 39935 20028 39935 19965 39935 19965 39936 20028 39936 20045 39936 19965 39937 20045 39937 20044 39937 19966 39938 19747 39938 19963 39938 19963 39939 19747 39939 19746 39939 19963 39940 19746 39940 19749 39940 19749 39941 19746 39941 19967 39941 19749 39942 19967 39942 19750 39942 19750 39943 19967 39943 19740 39943 19750 39944 19740 39944 19970 39944 19970 39945 19740 39945 19743 39945 19970 39946 19743 39946 19741 39946 19708 39947 19968 39947 19951 39947 19951 39948 19968 39948 19969 39948 19951 39949 19969 39949 19970 39949 19970 39950 19969 39950 19751 39950 19970 39951 19751 39951 19750 39951 10269 39952 19931 39952 19971 39952 19971 39953 19931 39953 19918 39953 19971 39954 19918 39954 19972 39954 19972 39955 19918 39955 19888 39955 19972 39956 19888 39956 19892 39956 19785 39957 20116 39957 19973 39957 19973 39958 20116 39958 10162 39958 19973 39959 10162 39959 19974 39959 19974 39960 10162 39960 10234 39960 20111 39961 19975 39961 20112 39961 20112 39962 19975 39962 19976 39962 20112 39963 19976 39963 19940 39963 19940 39964 19976 39964 19793 39964 19940 39965 19793 39965 19792 39965 19942 39966 19977 39966 19978 39966 19978 39967 19977 39967 19689 39967 19978 39968 19689 39968 19979 39968 19979 39969 19689 39969 10231 39969 19979 39970 10231 39970 19980 39970 19980 39971 10231 39971 19981 39971 19980 39972 19981 39972 19982 39972 19982 39973 19981 39973 19983 39973 19982 39974 19983 39974 19939 39974 19939 39975 19983 39975 19984 39975 19939 39976 19984 39976 19860 39976 19860 39977 19984 39977 19985 39977 19860 39978 19985 39978 19986 39978 19993 39979 19987 39979 19989 39979 19571 39980 20000 39980 19570 39980 19570 39981 20000 39981 19857 39981 19570 39982 19857 39982 19568 39982 10338 39983 10340 39983 19993 39983 19993 39984 10340 39984 19988 39984 19993 39985 19988 39985 19987 39985 19568 39986 19857 39986 19566 39986 19566 39987 19857 39987 20110 39987 19566 39988 20110 39988 19989 39988 19989 39989 20110 39989 19990 39989 19989 39990 19990 39990 19993 39990 19571 39991 19572 39991 20000 39991 20000 39992 19572 39992 19991 39992 20000 39993 19991 39993 19992 39993 19991 39994 10336 39994 19992 39994 19992 39995 10336 39995 10337 39995 19992 39996 10337 39996 10338 39996 19993 39997 19994 39997 10338 39997 10338 39998 19994 39998 19995 39998 10338 39999 19995 39999 19992 39999 19992 40000 19995 40000 19685 40000 19992 40001 19685 40001 19933 40001 19799 40002 19996 40002 19990 40002 19990 40003 19996 40003 19798 40003 19990 40004 19798 40004 19993 40004 20004 40005 10217 40005 19713 40005 19713 40006 10217 40006 19997 40006 19713 40007 19997 40007 19998 40007 19998 40008 19997 40008 10218 40008 19998 40009 10218 40009 19999 40009 19999 40010 10218 40010 10223 40010 19999 40011 10223 40011 19992 40011 19992 40012 10223 40012 10226 40012 19992 40013 10226 40013 20000 40013 20000 40014 10226 40014 20001 40014 20000 40015 20001 40015 19858 40015 19858 40016 20001 40016 19801 40016 19858 40017 19801 40017 19802 40017 20002 40018 10333 40018 10217 40018 10212 40019 20003 40019 20004 40019 20004 40020 20003 40020 20005 40020 20004 40021 20005 40021 10217 40021 10217 40022 20005 40022 20006 40022 10217 40023 20006 40023 20002 40023 19574 40024 20012 40024 20007 40024 20007 40025 20012 40025 10334 40025 20008 40026 19856 40026 20009 40026 20009 40027 19856 40027 20017 40027 20009 40028 20017 40028 19575 40028 20008 40029 20010 40029 20011 40029 10334 40030 20012 40030 10333 40030 10333 40031 20012 40031 20013 40031 10333 40032 20013 40032 10217 40032 20011 40033 20010 40033 10211 40033 10211 40034 20010 40034 20014 40034 10211 40035 20014 40035 20005 40035 20005 40036 20014 40036 10330 40036 20005 40037 10330 40037 20006 40037 20015 40038 19808 40038 20016 40038 20016 40039 19808 40039 19807 40039 20016 40040 19807 40040 20108 40040 20108 40041 19807 40041 20012 40041 20108 40042 20012 40042 20017 40042 20017 40043 20012 40043 19574 40043 20017 40044 19574 40044 19575 40044 20008 40045 20011 40045 19856 40045 19856 40046 20011 40046 20018 40046 19856 40047 20018 40047 19855 40047 19811 40048 19813 40048 20019 40048 20019 40049 19813 40049 20020 40049 20019 40050 20020 40050 20026 40050 19711 40051 20021 40051 20022 40051 20022 40052 20021 40052 20023 40052 20022 40053 20023 40053 20024 40053 20024 40054 20023 40054 19957 40054 20024 40055 19957 40055 10216 40055 10216 40056 19957 40056 20026 40056 10216 40057 20026 40057 20025 40057 20025 40058 20026 40058 20020 40058 20027 40059 10328 40059 20028 40059 20028 40060 10328 40060 19867 40060 20028 40061 19867 40061 19735 40061 19735 40062 19867 40062 10207 40062 19735 40063 10207 40063 20029 40063 20029 40064 10207 40064 10206 40064 20029 40065 10206 40065 19957 40065 19957 40066 10206 40066 20030 40066 19957 40067 20030 40067 20026 40067 20030 40068 20031 40068 20026 40068 20026 40069 20031 40069 20032 40069 20026 40070 20032 40070 20107 40070 20107 40071 20032 40071 20033 40071 20107 40072 20033 40072 19853 40072 20038 40073 20035 40073 20034 40073 20034 40074 20035 40074 19818 40074 19579 40075 19870 40075 20036 40075 20036 40076 19870 40076 20037 40076 20036 40077 20037 40077 20038 40077 20038 40078 20037 40078 20105 40078 20038 40079 20105 40079 20035 40079 19852 40080 19822 40080 20040 40080 19852 40081 20040 40081 20039 40081 20039 40082 20040 40082 20042 40082 20039 40083 20042 40083 20041 40083 20041 40084 20042 40084 20043 40084 20041 40085 20043 40085 19825 40085 10322 40086 10324 40086 19852 40086 19852 40087 10324 40087 19965 40087 19852 40088 19965 40088 19822 40088 19822 40089 19965 40089 20044 40089 19822 40090 20044 40090 19821 40090 19821 40091 20044 40091 20045 40091 19821 40092 20045 40092 19820 40092 19820 40093 20045 40093 19734 40093 19820 40094 19734 40094 19849 40094 19849 40095 19734 40095 10272 40095 19849 40096 10272 40096 20046 40096 20046 40097 10272 40097 20047 40097 20046 40098 20047 40098 19850 40098 19850 40099 20047 40099 20048 40099 19850 40100 20048 40100 19880 40100 20049 40101 20050 40101 20051 40101 20051 40102 20050 40102 19584 40102 20051 40103 19584 40103 20052 40103 20052 40104 19584 40104 19588 40104 20052 40105 19588 40105 10203 40105 10203 40106 19588 40106 19882 40106 10203 40107 19882 40107 10204 40107 10204 40108 19882 40108 20053 40108 10204 40109 20053 40109 19826 40109 19901 40110 20054 40110 20047 40110 20047 40111 20054 40111 19834 40111 20047 40112 19834 40112 20048 40112 20048 40113 19834 40113 20055 40113 20048 40114 20055 40114 19880 40114 10193 40115 10201 40115 10174 40115 10174 40116 10201 40116 10199 40116 10174 40117 10199 40117 20056 40117 20056 40118 10199 40118 19887 40118 20056 40119 19887 40119 20057 40119 20057 40120 19887 40120 10310 40120 20057 40121 10310 40121 19886 40121 19886 40122 20058 40122 20060 40122 20060 40123 20058 40123 20059 40123 20060 40124 20059 40124 20061 40124 20061 40125 20059 40125 19899 40125 20061 40126 19899 40126 20062 40126 20062 40127 19899 40127 10185 40127 20062 40128 10185 40128 20063 40128 20063 40129 10185 40129 10186 40129 20063 40130 10186 40130 20064 40130 10173 40131 10192 40131 20065 40131 20065 40132 10192 40132 10191 40132 20065 40133 10191 40133 20072 40133 10191 40134 20066 40134 20072 40134 20072 40135 20066 40135 10189 40135 20072 40136 10189 40136 19893 40136 19893 40137 10189 40137 20067 40137 19893 40138 20067 40138 19626 40138 19626 40139 20067 40139 20068 40139 19626 40140 20068 40140 20069 40140 20069 40141 20068 40141 20070 40141 20069 40142 20070 40142 20071 40142 19841 40143 19840 40143 20072 40143 20072 40144 19840 40144 10177 40144 20072 40145 10177 40145 19848 40145 19848 40146 10177 40146 20073 40146 19848 40147 20073 40147 10180 40147 20074 40148 20080 40148 10260 40148 10308 40149 19598 40149 10260 40149 20078 40150 10300 40150 20080 40150 10260 40151 19598 40151 10261 40151 10261 40152 19598 40152 19599 40152 10261 40153 19599 40153 19758 40153 19758 40154 19599 40154 20075 40154 19758 40155 20075 40155 19847 40155 19847 40156 20076 40156 19844 40156 19844 40157 20076 40157 20077 40157 19844 40158 20077 40158 10182 40158 10182 40159 20077 40159 20079 40159 20080 40160 10170 40160 20078 40160 20078 40161 10170 40161 20079 40161 20078 40162 20079 40162 19604 40162 19604 40163 20079 40163 20077 40163 10300 40164 10302 40164 20080 40164 20080 40165 10302 40165 10303 40165 20080 40166 10303 40166 10260 40166 10260 40167 10303 40167 10307 40167 10260 40168 10307 40168 10308 40168 10184 40169 20081 40169 10170 40169 10170 40170 20081 40170 20082 40170 10170 40171 20082 40171 20079 40171 20074 40172 10260 40172 19846 40172 19846 40173 10260 40173 10259 40173 19846 40174 10259 40174 10263 40174 10266 40175 20084 40175 10267 40175 10267 40176 20084 40176 20083 40176 19610 40177 19766 40177 10255 40177 10266 40178 10264 40178 20084 40178 20084 40179 10264 40179 20089 40179 20084 40180 20089 40180 20086 40180 20086 40181 20089 40181 10291 40181 20086 40182 10291 40182 20085 40182 20085 40183 10293 40183 20086 40183 20086 40184 10293 40184 10294 40184 20086 40185 10294 40185 20087 40185 20087 40186 10294 40186 20090 40186 20087 40187 20090 40187 20091 40187 19610 40188 20088 40188 19912 40188 20088 40189 19612 40189 19912 40189 19912 40190 19612 40190 19613 40190 19912 40191 19613 40191 20089 40191 20089 40192 19613 40192 10290 40192 20089 40193 10290 40193 10291 40193 20090 40194 10296 40194 10254 40194 10254 40195 10296 40195 19605 40195 10254 40196 19605 40196 10255 40196 10255 40197 19605 40197 19607 40197 10255 40198 19607 40198 19610 40198 20090 40199 10254 40199 20091 40199 20091 40200 10254 40200 10253 40200 20091 40201 10253 40201 10252 40201 19610 40202 19912 40202 19766 40202 19766 40203 19912 40203 19674 40203 19766 40204 19674 40204 20092 40204 20092 40205 19674 40205 20093 40205 20092 40206 20093 40206 19768 40206 19768 40207 20093 40207 19670 40207 19768 40208 19670 40208 19769 40208 19769 40209 19670 40209 20094 40209 19769 40210 20094 40210 19771 40210 19771 40211 20094 40211 20096 40211 19771 40212 20096 40212 19772 40212 10166 40213 20095 40213 10164 40213 10164 40214 20095 40214 20097 40214 10164 40215 20097 40215 20096 40215 20096 40216 20097 40216 19774 40216 20096 40217 19774 40217 19772 40217 10279 40218 20094 40218 19620 40218 19620 40219 20094 40219 20098 40219 19620 40220 20098 40220 19619 40220 19619 40221 20098 40221 19666 40221 19619 40222 19666 40222 19618 40222 19618 40223 19666 40223 19668 40223 19618 40224 19668 40224 20099 40224 20099 40225 19668 40225 19863 40225 20099 40226 19863 40226 20100 40226 20100 40227 19863 40227 10244 40227 20100 40228 10244 40228 19926 40228 19926 40229 10244 40229 10246 40229 19926 40230 10246 40230 10161 40230 10161 40231 10246 40231 10247 40231 10161 40232 10247 40232 10249 40232 20016 40233 20108 40233 9622 40233 20101 40234 21363 40234 19882 40234 19882 40235 21363 40235 20102 40235 19825 40236 20102 40236 20041 40236 20041 40237 20102 40237 20103 40237 19825 40238 19826 40238 20102 40238 20102 40239 19826 40239 20053 40239 20102 40240 20053 40240 19882 40240 20105 40241 20037 40241 9632 40241 9632 40242 20037 40242 19851 40242 9632 40243 19851 40243 20103 40243 20103 40244 19851 40244 20039 40244 20103 40245 20039 40245 20041 40245 19854 40246 9632 40246 20104 40246 19854 40247 19818 40247 9632 40247 9632 40248 19818 40248 20035 40248 9632 40249 20035 40249 20105 40249 9615 40250 9628 40250 20106 40250 20106 40251 9628 40251 19856 40251 20106 40252 19811 40252 9615 40252 9615 40253 19811 40253 20019 40253 9615 40254 20019 40254 20104 40254 20104 40255 20019 40255 20107 40255 20104 40256 20107 40256 19854 40256 9622 40257 20108 40257 9628 40257 9628 40258 20108 40258 20017 40258 9628 40259 20017 40259 19856 40259 20016 40260 9622 40260 20015 40260 20015 40261 9622 40261 9625 40261 20015 40262 9625 40262 20109 40262 19990 40263 20110 40263 9624 40263 9624 40264 20110 40264 19857 40264 9624 40265 19857 40265 9625 40265 9625 40266 19857 40266 19858 40266 9625 40267 19858 40267 20109 40267 19990 40268 9624 40268 19799 40268 19799 40269 9624 40269 9620 40269 19799 40270 9620 40270 19859 40270 20113 40271 19785 40271 20111 40271 20111 40272 20112 40272 20113 40272 20113 40273 20112 40273 19940 40273 20113 40274 19940 40274 9616 40274 9616 40275 19940 40275 20114 40275 9616 40276 20114 40276 9620 40276 9620 40277 20114 40277 19860 40277 9620 40278 19860 40278 19859 40278 20115 40279 10162 40279 20113 40279 20113 40280 10162 40280 20116 40280 20113 40281 20116 40281 19785 40281 20117 40282 20118 40282 20119 40282 20119 40283 20118 40283 20120 40283 20119 40284 20120 40284 13473 40284 13473 40285 20120 40285 20216 40285 13473 40286 20216 40286 13474 40286 13474 40287 20216 40287 20121 40287 13474 40288 20121 40288 13477 40288 13477 40289 20121 40289 20122 40289 13477 40290 20122 40290 13479 40290 13479 40291 20122 40291 20219 40291 13479 40292 20219 40292 20123 40292 20123 40293 20219 40293 10070 40293 13462 40294 10069 40294 20221 40294 13462 40295 20221 40295 20124 40295 20124 40296 20221 40296 20222 40296 20124 40297 20222 40297 20125 40297 20125 40298 20222 40298 20126 40298 20126 40299 20222 40299 20129 40299 20126 40300 20129 40300 20127 40300 20127 40301 20129 40301 20128 40301 20128 40302 20129 40302 20130 40302 20128 40303 20130 40303 20131 40303 20131 40304 20130 40304 13483 40304 13483 40305 20130 40305 20224 40305 13483 40306 20224 40306 13484 40306 13484 40307 20224 40307 20132 40307 13484 40308 20132 40308 20133 40308 20133 40309 20132 40309 20226 40309 20133 40310 20226 40310 13458 40310 20136 40311 20134 40311 20135 40311 20136 40312 20135 40312 20137 40312 20137 40313 20135 40313 20138 40313 20137 40314 20138 40314 13493 40314 13493 40315 20138 40315 20139 40315 20139 40316 20138 40316 20228 40316 20139 40317 20228 40317 13494 40317 13494 40318 20228 40318 13492 40318 13492 40319 20228 40319 20140 40319 13492 40320 20140 40320 13488 40320 13488 40321 20140 40321 13490 40321 13490 40322 20140 40322 20141 40322 13490 40323 20141 40323 20143 40323 20143 40324 20141 40324 20142 40324 20143 40325 20142 40325 20144 40325 20144 40326 20142 40326 20145 40326 20144 40327 20145 40327 13487 40327 13447 40328 10144 40328 13496 40328 13496 40329 10144 40329 20232 40329 13496 40330 20232 40330 13498 40330 13498 40331 20232 40331 20233 40331 13498 40332 20233 40332 13499 40332 13499 40333 20233 40333 20234 40333 13499 40334 20234 40334 13501 40334 13501 40335 20234 40335 20146 40335 13501 40336 20146 40336 13502 40336 13502 40337 20146 40337 20147 40337 13502 40338 20147 40338 20148 40338 20148 40339 20147 40339 10136 40339 13504 40340 20236 40340 20238 40340 13504 40341 20238 40341 13514 40341 13514 40342 20238 40342 20239 40342 13514 40343 20239 40343 13515 40343 13515 40344 20239 40344 20149 40344 20149 40345 20239 40345 20150 40345 20149 40346 20150 40346 13510 40346 13510 40347 20150 40347 13512 40347 13512 40348 20150 40348 20240 40348 13512 40349 20240 40349 13507 40349 13507 40350 20240 40350 13509 40350 13509 40351 20240 40351 20241 40351 13509 40352 20241 40352 20151 40352 20151 40353 20241 40353 20243 40353 20151 40354 20243 40354 20152 40354 20152 40355 20243 40355 10131 40355 20152 40356 10131 40356 13429 40356 20153 40357 20251 40357 20154 40357 20154 40358 20251 40358 20156 40358 20251 40359 20155 40359 20156 40359 20156 40360 20155 40360 20252 40360 20156 40361 20252 40361 20157 40361 20252 40362 20158 40362 20157 40362 20157 40363 20158 40363 20248 40363 20157 40364 20248 40364 20159 40364 20248 40365 20247 40365 20159 40365 20159 40366 20247 40366 20160 40366 20159 40367 20160 40367 20161 40367 20160 40368 20245 40368 20161 40368 20161 40369 20245 40369 20164 40369 20161 40370 20164 40370 13522 40370 10126 40371 20162 40371 20244 40371 20244 40372 20162 40372 13522 40372 20244 40373 13522 40373 20163 40373 20163 40374 13522 40374 20164 40374 13523 40375 10040 40375 20165 40375 20165 40376 10040 40376 20253 40376 20165 40377 20253 40377 20166 40377 20166 40378 20253 40378 13532 40378 13532 40379 20253 40379 20167 40379 13532 40380 20167 40380 20168 40380 20168 40381 20167 40381 20169 40381 20169 40382 20167 40382 20170 40382 20169 40383 20170 40383 20171 40383 20171 40384 20170 40384 20172 40384 20172 40385 20170 40385 20174 40385 20172 40386 20174 40386 20173 40386 20173 40387 20174 40387 20175 40387 20175 40388 20174 40388 20176 40388 20175 40389 20176 40389 13528 40389 13528 40390 20176 40390 13526 40390 13526 40391 20176 40391 10118 40391 13526 40392 10118 40392 13524 40392 13533 40393 10034 40393 20177 40393 20177 40394 10034 40394 20257 40394 20177 40395 20257 40395 20178 40395 20178 40396 20257 40396 20180 40396 20178 40397 20180 40397 20179 40397 20179 40398 20180 40398 20181 40398 20179 40399 20181 40399 13537 40399 13537 40400 20181 40400 20182 40400 13537 40401 20182 40401 20183 40401 20183 40402 20182 40402 20260 40402 20183 40403 20260 40403 20184 40403 20184 40404 20260 40404 20261 40404 20184 40405 20261 40405 13540 40405 13540 40406 20261 40406 20185 40406 10025 40407 20272 40407 10114 40407 10114 40408 20272 40408 20186 40408 20272 40409 20274 40409 20186 40409 20186 40410 20274 40410 20270 40410 20186 40411 20270 40411 20187 40411 20270 40412 20269 40412 20187 40412 20187 40413 20269 40413 20188 40413 20187 40414 20188 40414 20190 40414 20188 40415 20189 40415 20190 40415 20190 40416 20189 40416 20191 40416 20190 40417 20191 40417 13544 40417 20191 40418 20265 40418 13544 40418 13544 40419 20265 40419 20196 40419 13544 40420 20196 40420 20195 40420 20262 40421 20193 40421 20192 40421 20192 40422 20193 40422 20195 40422 20192 40423 20195 40423 20194 40423 20194 40424 20195 40424 20196 40424 13546 40425 10020 40425 13548 40425 13548 40426 10020 40426 20197 40426 13548 40427 20197 40427 13549 40427 13549 40428 20197 40428 20275 40428 13549 40429 20275 40429 20198 40429 20198 40430 20275 40430 20200 40430 20198 40431 20200 40431 20199 40431 20199 40432 20200 40432 20202 40432 20199 40433 20202 40433 20201 40433 20201 40434 20202 40434 20278 40434 20201 40435 20278 40435 13551 40435 13551 40436 20278 40436 10012 40436 10093 40437 10011 40437 13562 40437 13562 40438 10011 40438 20203 40438 13562 40439 20203 40439 13563 40439 13563 40440 20203 40440 20204 40440 20204 40441 20203 40441 20206 40441 20204 40442 20206 40442 20205 40442 20205 40443 20206 40443 13561 40443 13561 40444 20206 40444 20207 40444 13561 40445 20207 40445 13560 40445 13560 40446 20207 40446 20208 40446 20208 40447 20207 40447 20284 40447 20208 40448 20284 40448 13556 40448 13556 40449 20284 40449 20209 40449 20209 40450 20284 40450 20210 40450 20209 40451 20210 40451 13554 40451 13554 40452 20210 40452 13553 40452 13553 40453 20210 40453 10006 40453 13553 40454 10006 40454 10083 40454 13564 40455 10082 40455 13565 40455 13565 40456 10082 40456 20392 40456 13565 40457 20392 40457 13566 40457 13566 40458 20392 40458 20211 40458 13566 40459 20211 40459 20212 40459 20212 40460 20211 40460 20393 40460 20212 40461 20393 40461 20213 40461 20213 40462 20393 40462 20395 40462 20213 40463 20395 40463 13570 40463 13570 40464 20395 40464 20214 40464 13570 40465 20214 40465 13373 40465 13373 40466 20214 40466 20397 40466 20118 40467 20403 40467 20120 40467 20120 40468 20403 40468 20215 40468 20120 40469 20215 40469 20216 40469 20216 40470 20215 40470 20217 40470 20216 40471 20217 40471 20121 40471 20121 40472 20217 40472 20218 40472 20121 40473 20218 40473 20122 40473 20122 40474 20218 40474 20406 40474 20122 40475 20406 40475 20219 40475 20219 40476 20406 40476 20220 40476 20219 40477 20220 40477 10070 40477 10070 40478 20220 40478 20407 40478 10069 40479 20422 40479 20221 40479 20221 40480 20422 40480 20423 40480 20221 40481 20423 40481 20222 40481 20222 40482 20423 40482 20425 40482 20222 40483 20425 40483 20129 40483 20129 40484 20425 40484 20426 40484 20129 40485 20426 40485 20130 40485 20130 40486 20426 40486 20223 40486 20130 40487 20223 40487 20224 40487 20224 40488 20223 40488 20225 40488 20224 40489 20225 40489 20132 40489 20132 40490 20225 40490 20415 40490 20132 40491 20415 40491 20226 40491 20226 40492 20415 40492 20416 40492 20134 40493 20430 40493 20135 40493 20135 40494 20430 40494 20227 40494 20135 40495 20227 40495 20138 40495 20138 40496 20227 40496 20429 40496 20138 40497 20429 40497 20228 40497 20228 40498 20429 40498 20229 40498 20228 40499 20229 40499 20140 40499 20140 40500 20229 40500 20230 40500 20140 40501 20230 40501 20141 40501 20141 40502 20230 40502 20427 40502 20141 40503 20427 40503 20142 40503 20142 40504 20427 40504 20231 40504 20142 40505 20231 40505 20145 40505 20145 40506 20231 40506 20436 40506 10144 40507 20438 40507 20232 40507 20232 40508 20438 40508 20440 40508 20232 40509 20440 40509 20233 40509 20233 40510 20440 40510 20441 40510 20233 40511 20441 40511 20234 40511 20234 40512 20441 40512 20235 40512 20234 40513 20235 40513 20146 40513 20146 40514 20235 40514 20443 40514 20146 40515 20443 40515 20147 40515 20147 40516 20443 40516 20445 40516 20147 40517 20445 40517 10136 40517 10136 40518 20445 40518 20447 40518 20236 40519 20237 40519 20238 40519 20238 40520 20237 40520 20464 40520 20238 40521 20464 40521 20239 40521 20239 40522 20464 40522 20466 40522 20239 40523 20466 40523 20150 40523 20150 40524 20466 40524 20452 40524 20150 40525 20452 40525 20240 40525 20240 40526 20452 40526 20453 40526 20240 40527 20453 40527 20241 40527 20241 40528 20453 40528 20242 40528 20241 40529 20242 40529 20243 40529 20243 40530 20242 40530 20455 40530 20243 40531 20455 40531 10131 40531 10131 40532 20455 40532 20457 40532 20472 40533 10042 40533 10126 40533 10126 40534 20244 40534 20472 40534 20472 40535 20244 40535 20163 40535 20472 40536 20163 40536 20471 40536 20163 40537 20164 40537 20471 40537 20471 40538 20164 40538 20245 40538 20471 40539 20245 40539 20469 40539 20245 40540 20160 40540 20469 40540 20469 40541 20160 40541 20247 40541 20469 40542 20247 40542 20246 40542 20246 40543 20247 40543 20248 40543 20246 40544 20248 40544 20249 40544 20248 40545 20158 40545 20249 40545 20249 40546 20158 40546 20252 40546 20249 40547 20252 40547 20250 40547 20153 40548 20479 40548 20251 40548 20251 40549 20479 40549 20250 40549 20251 40550 20250 40550 20155 40550 20155 40551 20250 40551 20252 40551 10040 40552 10041 40552 20253 40552 20253 40553 10041 40553 20485 40553 20253 40554 20485 40554 20167 40554 20167 40555 20485 40555 20254 40555 20167 40556 20254 40556 20170 40556 20170 40557 20254 40557 20255 40557 20170 40558 20255 40558 20174 40558 20174 40559 20255 40559 20256 40559 20174 40560 20256 40560 20176 40560 20176 40561 20256 40561 20487 40561 20176 40562 20487 40562 10118 40562 10118 40563 20487 40563 10035 40563 10034 40564 20504 40564 20257 40564 20257 40565 20504 40565 20258 40565 20257 40566 20258 40566 20180 40566 20180 40567 20258 40567 20259 40567 20180 40568 20259 40568 20181 40568 20181 40569 20259 40569 20507 40569 20181 40570 20507 40570 20182 40570 20182 40571 20507 40571 20494 40571 20182 40572 20494 40572 20260 40572 20260 40573 20494 40573 20497 40573 20260 40574 20497 40574 20261 40574 20261 40575 20497 40575 20498 40575 20261 40576 20498 40576 20185 40576 20185 40577 20498 40577 10027 40577 20263 40578 20512 40578 20262 40578 20262 40579 20192 40579 20263 40579 20263 40580 20192 40580 20194 40580 20263 40581 20194 40581 20264 40581 20194 40582 20196 40582 20264 40582 20264 40583 20196 40583 20265 40583 20264 40584 20265 40584 20266 40584 20265 40585 20191 40585 20266 40585 20266 40586 20191 40586 20189 40586 20266 40587 20189 40587 20267 40587 20267 40588 20189 40588 20188 40588 20267 40589 20188 40589 20268 40589 20188 40590 20269 40590 20268 40590 20268 40591 20269 40591 20270 40591 20268 40592 20270 40592 20273 40592 10025 40593 20271 40593 20272 40593 20272 40594 20271 40594 20273 40594 20272 40595 20273 40595 20274 40595 20274 40596 20273 40596 20270 40596 10020 40597 20517 40597 20197 40597 20197 40598 20517 40598 20518 40598 20197 40599 20518 40599 20275 40599 20275 40600 20518 40600 20519 40600 20275 40601 20519 40601 20200 40601 20200 40602 20519 40602 20276 40602 20200 40603 20276 40603 20202 40603 20202 40604 20276 40604 20277 40604 20202 40605 20277 40605 20278 40605 20278 40606 20277 40606 20279 40606 20278 40607 20279 40607 10012 40607 10012 40608 20279 40608 10013 40608 10011 40609 20280 40609 20203 40609 20203 40610 20280 40610 20281 40610 20203 40611 20281 40611 20206 40611 20206 40612 20281 40612 20282 40612 20206 40613 20282 40613 20207 40613 20207 40614 20282 40614 20283 40614 20207 40615 20283 40615 20284 40615 20284 40616 20283 40616 20527 40616 20284 40617 20527 40617 20210 40617 20210 40618 20527 40618 20529 40618 20210 40619 20529 40619 10006 40619 10006 40620 20529 40620 20530 40620 20291 40621 9968 40621 20290 40621 20538 40622 20288 40622 20291 40622 20289 40623 20539 40623 20291 40623 20540 40624 20287 40624 20291 40624 20285 40625 20286 40625 20291 40625 20291 40626 20542 40626 10003 40626 20541 40627 20542 40627 20291 40627 20286 40628 20541 40628 20291 40628 20287 40629 20285 40629 20291 40629 20539 40630 20540 40630 20291 40630 20288 40631 20289 40631 20291 40631 20290 40632 20538 40632 20291 40632 10002 40633 20543 40633 20544 40633 20545 40634 20546 40634 10002 40634 20294 40635 20547 40635 10002 40635 20548 40636 20550 40636 10002 40636 20292 40637 20293 40637 10002 40637 10002 40638 20554 40638 9947 40638 20553 40639 20554 40639 10002 40639 20293 40640 20553 40640 10002 40640 20550 40641 20292 40641 10002 40641 20547 40642 20548 40642 10002 40642 20546 40643 20294 40643 10002 40643 20544 40644 20545 40644 10002 40644 20297 40645 9946 40645 20300 40645 20556 40646 20557 40646 20297 40646 20559 40647 20299 40647 20297 40647 20560 40648 20295 40648 20297 40648 20298 40649 20296 40649 20297 40649 20297 40650 20564 40650 9993 40650 20563 40651 20564 40651 20297 40651 20296 40652 20563 40652 20297 40652 20295 40653 20298 40653 20297 40653 20299 40654 20560 40654 20297 40654 20557 40655 20559 40655 20297 40655 20300 40656 20556 40656 20297 40656 20304 40657 20566 40657 20303 40657 20301 40658 20566 40658 20304 40658 20302 40659 20301 40659 20304 40659 20304 40660 20569 40660 20571 40660 20568 40661 20569 40661 20304 40661 20303 40662 20568 40662 20304 40662 20305 40663 9929 40663 20573 40663 20305 40664 20576 40664 20578 40664 20574 40665 20576 40665 20305 40665 20573 40666 20574 40666 20305 40666 20305 40667 20306 40667 9924 40667 20579 40668 20306 40668 20305 40668 20578 40669 20579 40669 20305 40669 20312 40670 20581 40670 20307 40670 20311 40671 20584 40671 20312 40671 20585 40672 20308 40672 20312 40672 20309 40673 20587 40673 20312 40673 20589 40674 20310 40674 20312 40674 20312 40675 20592 40675 9915 40675 20590 40676 20592 40676 20312 40676 20310 40677 20590 40677 20312 40677 20587 40678 20589 40678 20312 40678 20308 40679 20309 40679 20312 40679 20584 40680 20585 40680 20312 40680 20307 40681 20311 40681 20312 40681 9983 40682 20596 40682 20599 40682 20313 40683 20596 40683 9983 40683 20593 40684 20313 40684 9983 40684 9983 40685 20314 40685 20604 40685 20602 40686 20314 40686 9983 40686 20599 40687 20602 40687 9983 40687 20320 40688 20315 40688 20324 40688 20325 40689 20607 40689 20320 40689 20323 40690 20609 40690 20320 40690 20316 40691 20610 40691 20320 40691 20322 40692 20321 40692 20320 40692 20320 40693 20319 40693 20317 40693 20318 40694 20319 40694 20320 40694 20321 40695 20318 40695 20320 40695 20610 40696 20322 40696 20320 40696 20609 40697 20316 40697 20320 40697 20607 40698 20323 40698 20320 40698 20324 40699 20325 40699 20320 40699 9977 40700 9898 40700 20614 40700 20326 40701 20615 40701 9977 40701 20616 40702 20617 40702 9977 40702 20327 40703 20619 40703 9977 40703 9977 40704 20328 40704 9890 40704 20329 40705 20328 40705 9977 40705 20619 40706 20329 40706 9977 40706 20617 40707 20327 40707 9977 40707 20615 40708 20616 40708 9977 40708 20614 40709 20326 40709 9977 40709 20330 40710 20628 40710 20644 40710 20644 40711 20628 40711 20331 40711 20644 40712 20331 40712 20645 40712 20645 40713 20331 40713 20643 40713 20634 40714 20635 40714 20636 40714 20337 40715 20640 40715 20331 40715 20331 40716 20640 40716 20332 40716 20331 40717 20332 40717 20643 40717 20630 40718 20631 40718 20333 40718 20333 40719 20631 40719 20334 40719 20333 40720 20334 40720 20625 40720 20625 40721 20334 40721 20331 40721 20625 40722 20331 40722 20626 40722 20626 40723 20331 40723 20628 40723 20636 40724 20335 40724 20634 40724 20634 40725 20335 40725 20336 40725 20634 40726 20336 40726 20331 40726 20331 40727 20336 40727 20638 40727 20331 40728 20638 40728 20337 40728 20663 40729 20345 40729 20664 40729 20664 40730 20345 40730 20347 40730 20664 40731 20347 40731 20660 40731 20660 40732 20347 40732 20662 40732 20652 40733 20338 40733 20654 40733 20339 40734 20340 40734 20347 40734 20347 40735 20340 40735 20341 40735 20347 40736 20341 40736 20662 40736 20342 40737 20343 40737 20344 40737 20344 40738 20343 40738 20649 40738 20344 40739 20649 40739 20646 40739 20646 40740 20649 40740 20347 40740 20646 40741 20347 40741 20647 40741 20647 40742 20347 40742 20345 40742 20654 40743 20346 40743 20652 40743 20652 40744 20346 40744 20658 40744 20652 40745 20658 40745 20347 40745 20347 40746 20658 40746 20348 40746 20347 40747 20348 40747 20339 40747 20669 40748 20672 40748 20349 40748 20350 40749 20351 40749 20352 40749 20352 40750 20351 40750 20356 40750 20352 40751 20356 40751 20354 40751 20349 40752 20674 40752 20669 40752 20669 40753 20674 40753 20675 40753 20669 40754 20675 40754 20356 40754 20356 40755 20675 40755 20353 40755 20356 40756 20353 40756 20354 40756 20683 40757 20682 40757 20355 40757 20355 40758 20682 40758 20356 40758 20355 40759 20356 40759 20685 40759 20685 40760 20356 40760 20351 40760 20357 40761 20358 40761 20667 40761 20667 40762 20358 40762 20671 40762 20667 40763 20671 40763 20666 40763 20666 40764 20671 40764 20356 40764 20666 40765 20356 40765 20359 40765 20359 40766 20356 40766 20682 40766 20366 40767 20360 40767 20362 40767 20362 40768 20360 40768 20361 40768 20361 40769 9883 40769 20362 40769 20362 40770 9883 40770 20363 40770 20362 40771 20363 40771 20364 40771 20696 40772 20697 40772 20365 40772 20365 40773 20697 40773 20366 40773 20365 40774 20366 40774 20693 40774 20693 40775 20366 40775 20362 40775 20364 40776 20367 40776 20362 40776 20362 40777 20367 40777 20705 40777 20362 40778 20705 40778 20703 40778 20369 40779 20689 40779 20690 40779 20703 40780 20368 40780 20362 40780 20362 40781 20368 40781 20688 40781 20362 40782 20688 40782 9887 40782 9887 40783 20688 40783 20369 40783 9887 40784 20369 40784 9885 40784 9885 40785 20369 40785 20690 40785 20375 40786 20710 40786 20374 40786 20721 40787 20370 40787 9876 40787 9876 40788 20370 40788 20371 40788 9876 40789 20371 40789 9877 40789 20718 40790 20717 40790 20371 40790 20371 40791 20717 40791 20715 40791 20371 40792 20715 40792 9877 40792 20370 40793 20372 40793 20371 40793 20371 40794 20372 40794 20373 40794 20371 40795 20373 40795 20374 40795 20374 40796 20373 40796 20707 40796 20374 40797 20707 40797 20375 40797 20376 40798 9879 40798 20377 40798 20377 40799 9879 40799 9881 40799 20377 40800 9881 40800 20378 40800 20378 40801 9881 40801 20713 40801 20378 40802 20713 40802 20371 40802 20371 40803 20713 40803 20719 40803 20371 40804 20719 40804 20718 40804 20732 40805 20379 40805 20381 40805 20380 40806 20738 40806 20739 40806 20739 40807 20738 40807 20387 40807 20739 40808 20387 40808 20737 40808 20381 40809 20382 40809 20732 40809 20732 40810 20382 40810 20383 40810 20732 40811 20383 40811 20387 40811 20387 40812 20383 40812 20384 40812 20387 40813 20384 40813 20737 40813 20385 40814 20386 40814 20743 40814 20743 40815 20386 40815 20387 40815 20743 40816 20387 40816 20744 40816 20744 40817 20387 40817 20738 40817 20390 40818 20388 40818 20389 40818 20386 40819 20724 40819 20387 40819 20387 40820 20724 40820 20390 40820 20387 40821 20390 40821 20728 40821 20728 40822 20390 40822 20389 40822 20728 40823 20389 40823 20391 40823 10082 40824 20755 40824 20392 40824 20392 40825 20755 40825 20753 40825 20392 40826 20753 40826 20211 40826 20211 40827 20753 40827 20751 40827 20211 40828 20751 40828 20393 40828 20393 40829 20751 40829 20394 40829 20393 40830 20394 40830 20395 40830 20395 40831 20394 40831 20396 40831 20395 40832 20396 40832 20214 40832 20214 40833 20396 40833 20398 40833 20214 40834 20398 40834 20397 40834 20397 40835 20398 40835 9969 40835 10072 40836 20413 40836 10073 40836 10073 40837 20413 40837 20399 40837 10073 40838 20399 40838 20400 40838 20400 40839 20399 40839 20765 40839 20400 40840 20765 40840 20401 40840 20401 40841 20765 40841 20402 40841 20401 40842 20402 40842 20403 40842 20403 40843 20402 40843 9868 40843 20403 40844 9868 40844 20215 40844 20215 40845 9868 40845 20404 40845 20215 40846 20404 40846 20217 40846 20217 40847 20404 40847 9870 40847 20217 40848 9870 40848 20218 40848 20218 40849 9870 40849 20405 40849 20218 40850 20405 40850 20406 40850 20406 40851 20405 40851 9872 40851 20406 40852 9872 40852 20220 40852 20220 40853 9872 40853 9873 40853 20220 40854 9873 40854 20407 40854 20407 40855 9873 40855 20409 40855 20407 40856 20409 40856 20408 40856 20408 40857 20409 40857 20410 40857 20408 40858 20410 40858 20411 40858 20411 40859 20410 40859 20412 40859 20411 40860 20412 40860 10072 40860 10072 40861 20412 40861 20413 40861 20426 40862 20414 40862 20223 40862 20223 40863 20414 40863 9862 40863 20223 40864 9862 40864 20225 40864 20225 40865 9862 40865 9863 40865 20225 40866 9863 40866 20415 40866 20415 40867 9863 40867 9865 40867 20415 40868 9865 40868 20416 40868 20416 40869 9865 40869 20767 40869 20416 40870 20767 40870 20417 40870 20417 40871 20767 40871 20418 40871 20417 40872 20418 40872 10065 40872 10065 40873 20418 40873 20419 40873 10065 40874 20419 40874 20420 40874 20420 40875 20419 40875 20421 40875 20420 40876 20421 40876 10067 40876 10067 40877 20421 40877 20770 40877 10067 40878 20770 40878 10068 40878 10068 40879 20770 40879 20771 40879 10068 40880 20771 40880 20422 40880 20422 40881 20771 40881 9858 40881 20422 40882 9858 40882 20423 40882 20423 40883 9858 40883 20424 40883 20423 40884 20424 40884 20425 40884 20425 40885 20424 40885 9860 40885 20425 40886 9860 40886 20426 40886 20426 40887 9860 40887 20414 40887 20427 40888 20230 40888 9850 40888 9850 40889 20230 40889 20229 40889 9850 40890 20229 40890 20428 40890 20428 40891 20229 40891 20429 40891 20428 40892 20429 40892 9847 40892 9847 40893 20429 40893 20227 40893 9847 40894 20227 40894 9848 40894 9848 40895 20227 40895 20430 40895 9848 40896 20430 40896 20431 40896 20431 40897 20430 40897 10062 40897 20431 40898 10062 40898 20432 40898 20432 40899 10062 40899 10061 40899 20432 40900 10061 40900 20774 40900 20774 40901 10061 40901 10059 40901 20774 40902 10059 40902 20433 40902 20433 40903 10059 40903 10058 40903 20433 40904 10058 40904 20434 40904 20434 40905 10058 40905 20435 40905 20434 40906 20435 40906 9857 40906 9857 40907 20435 40907 20436 40907 9857 40908 20436 40908 9855 40908 9855 40909 20436 40909 20231 40909 9855 40910 20231 40910 20437 40910 20437 40911 20231 40911 20427 40911 20437 40912 20427 40912 9850 40912 20451 40913 20784 40913 20438 40913 20438 40914 20784 40914 20439 40914 20438 40915 20439 40915 20440 40915 20440 40916 20439 40916 9844 40916 20440 40917 9844 40917 20441 40917 20441 40918 9844 40918 20442 40918 20441 40919 20442 40919 20235 40919 20235 40920 20442 40920 20444 40920 20235 40921 20444 40921 20443 40921 20443 40922 20444 40922 9846 40922 20443 40923 9846 40923 20445 40923 20445 40924 9846 40924 20446 40924 20445 40925 20446 40925 20447 40925 20447 40926 20446 40926 20448 40926 20447 40927 20448 40927 20449 40927 20449 40928 20448 40928 20779 40928 20449 40929 20779 40929 10052 40929 10052 40930 20779 40930 20780 40930 10052 40931 20780 40931 10054 40931 10054 40932 20780 40932 20782 40932 10054 40933 20782 40933 10055 40933 10055 40934 20782 40934 20450 40934 10055 40935 20450 40935 10056 40935 10056 40936 20450 40936 20783 40936 10056 40937 20783 40937 20451 40937 20451 40938 20783 40938 20784 40938 20452 40939 20467 40939 20453 40939 20453 40940 20467 40940 9841 40940 20453 40941 9841 40941 20242 40941 20242 40942 9841 40942 20454 40942 20242 40943 20454 40943 20455 40943 20455 40944 20454 40944 20456 40944 20455 40945 20456 40945 20457 40945 20457 40946 20456 40946 20786 40946 20457 40947 20786 40947 10049 40947 10049 40948 20786 40948 20787 40948 10049 40949 20787 40949 20458 40949 20458 40950 20787 40950 20459 40950 20458 40951 20459 40951 20460 40951 20460 40952 20459 40952 20461 40952 20460 40953 20461 40953 10051 40953 10051 40954 20461 40954 20463 40954 10051 40955 20463 40955 20462 40955 20462 40956 20463 40956 20790 40956 20462 40957 20790 40957 20237 40957 20237 40958 20790 40958 9838 40958 20237 40959 9838 40959 20464 40959 20464 40960 9838 40960 20465 40960 20464 40961 20465 40961 20466 40961 20466 40962 20465 40962 9839 40962 20466 40963 9839 40963 20452 40963 20452 40964 9839 40964 20467 40964 20246 40965 20468 40965 20469 40965 20469 40966 20468 40966 20470 40966 20469 40967 20470 40967 20471 40967 20471 40968 20470 40968 20473 40968 20471 40969 20473 40969 20472 40969 20472 40970 20473 40970 9837 40970 20472 40971 9837 40971 10042 40971 10042 40972 9837 40972 20474 40972 10042 40973 20474 40973 10044 40973 10044 40974 20474 40974 20791 40974 10044 40975 20791 40975 20475 40975 20475 40976 20791 40976 20792 40976 20475 40977 20792 40977 10045 40977 10045 40978 20792 40978 20476 40978 10045 40979 20476 40979 20477 40979 20477 40980 20476 40980 20793 40980 20477 40981 20793 40981 20478 40981 20478 40982 20793 40982 20794 40982 20478 40983 20794 40983 20479 40983 20479 40984 20794 40984 20795 40984 20479 40985 20795 40985 20250 40985 20250 40986 20795 40986 20480 40986 20250 40987 20480 40987 20249 40987 20249 40988 20480 40988 20481 40988 20249 40989 20481 40989 20246 40989 20246 40990 20481 40990 20468 40990 10039 40991 20800 40991 20482 40991 20482 40992 20800 40992 20483 40992 20482 40993 20483 40993 10041 40993 10041 40994 20483 40994 20484 40994 10041 40995 20484 40995 20485 40995 20485 40996 20484 40996 9827 40996 20485 40997 9827 40997 20254 40997 20254 40998 9827 40998 9828 40998 20254 40999 9828 40999 20255 40999 20255 41000 9828 41000 9829 41000 20255 41001 9829 41001 20256 41001 20256 41002 9829 41002 20486 41002 20256 41003 20486 41003 20487 41003 20487 41004 20486 41004 9831 41004 20487 41005 9831 41005 10035 41005 10035 41006 9831 41006 20796 41006 10035 41007 20796 41007 20488 41007 20488 41008 20796 41008 20489 41008 20488 41009 20489 41009 20490 41009 20490 41010 20489 41010 20797 41010 20490 41011 20797 41011 20491 41011 20491 41012 20797 41012 20492 41012 20491 41013 20492 41013 20493 41013 20493 41014 20492 41014 20799 41014 20493 41015 20799 41015 10039 41015 10039 41016 20799 41016 20800 41016 20507 41017 20495 41017 20494 41017 20494 41018 20495 41018 20496 41018 20494 41019 20496 41019 20497 41019 20497 41020 20496 41020 9820 41020 20497 41021 9820 41021 20498 41021 20498 41022 9820 41022 9823 41022 20498 41023 9823 41023 10027 41023 10027 41024 9823 41024 9825 41024 10027 41025 9825 41025 10028 41025 10028 41026 9825 41026 20499 41026 10028 41027 20499 41027 10029 41027 10029 41028 20499 41028 20804 41028 10029 41029 20804 41029 20501 41029 20501 41030 20804 41030 20500 41030 20501 41031 20500 41031 10032 41031 10032 41032 20500 41032 20806 41032 10032 41033 20806 41033 20502 41033 20502 41034 20806 41034 20503 41034 20502 41035 20503 41035 20504 41035 20504 41036 20503 41036 20505 41036 20504 41037 20505 41037 20258 41037 20258 41038 20505 41038 9816 41038 20258 41039 9816 41039 20259 41039 20259 41040 9816 41040 20506 41040 20259 41041 20506 41041 20507 41041 20507 41042 20506 41042 20495 41042 20264 41043 20266 41043 9812 41043 9812 41044 20266 41044 20267 41044 9812 41045 20267 41045 20508 41045 20508 41046 20267 41046 20268 41046 20508 41047 20268 41047 20509 41047 20509 41048 20268 41048 20273 41048 20509 41049 20273 41049 9808 41049 9808 41050 20273 41050 20271 41050 9808 41051 20271 41051 20817 41051 20817 41052 20271 41052 10026 41052 20817 41053 10026 41053 20816 41053 20816 41054 10026 41054 10023 41054 20816 41055 10023 41055 20815 41055 20815 41056 10023 41056 10022 41056 20815 41057 10022 41057 20812 41057 20812 41058 10022 41058 20510 41058 20812 41059 20510 41059 20809 41059 20809 41060 20510 41060 10021 41060 20809 41061 10021 41061 20511 41061 20511 41062 10021 41062 20512 41062 20511 41063 20512 41063 20513 41063 20513 41064 20512 41064 20263 41064 20513 41065 20263 41065 9815 41065 9815 41066 20263 41066 20264 41066 9815 41067 20264 41067 9812 41067 20523 41068 20515 41068 20514 41068 20514 41069 20515 41069 20822 41069 20514 41070 20822 41070 10018 41070 10018 41071 20822 41071 20823 41071 10018 41072 20823 41072 10019 41072 10019 41073 20823 41073 20516 41073 10019 41074 20516 41074 20517 41074 20517 41075 20516 41075 9800 41075 20517 41076 9800 41076 20518 41076 20518 41077 9800 41077 9801 41077 20518 41078 9801 41078 20519 41078 20519 41079 9801 41079 9802 41079 20519 41080 9802 41080 20276 41080 20276 41081 9802 41081 20520 41081 20276 41082 20520 41082 20277 41082 20277 41083 20520 41083 9805 41083 20277 41084 9805 41084 20279 41084 20279 41085 9805 41085 9807 41085 20279 41086 9807 41086 10013 41086 10013 41087 9807 41087 20521 41087 10013 41088 20521 41088 10015 41088 10015 41089 20521 41089 20819 41089 10015 41090 20819 41090 20522 41090 20522 41091 20819 41091 20523 41091 20522 41092 20523 41092 20514 41092 20524 41093 20536 41093 20280 41093 20280 41094 20536 41094 9794 41094 20280 41095 9794 41095 20281 41095 20281 41096 9794 41096 9795 41096 20281 41097 9795 41097 20282 41097 20282 41098 9795 41098 20525 41098 20282 41099 20525 41099 20283 41099 20283 41100 20525 41100 20526 41100 20283 41101 20526 41101 20527 41101 20527 41102 20526 41102 20528 41102 20527 41103 20528 41103 20529 41103 20529 41104 20528 41104 9798 41104 20529 41105 9798 41105 20530 41105 20530 41106 9798 41106 20827 41106 20530 41107 20827 41107 20531 41107 20531 41108 20827 41108 20829 41108 20531 41109 20829 41109 10007 41109 10007 41110 20829 41110 20532 41110 10007 41111 20532 41111 10008 41111 10008 41112 20532 41112 20533 41112 10008 41113 20533 41113 20534 41113 20534 41114 20533 41114 20535 41114 20534 41115 20535 41115 10009 41115 10009 41116 20535 41116 20832 41116 10009 41117 20832 41117 20524 41117 20524 41118 20832 41118 20536 41118 9968 41119 9967 41119 20290 41119 20290 41120 9967 41120 20537 41120 20290 41121 20537 41121 20538 41121 20538 41122 20537 41122 20288 41122 20288 41123 20537 41123 20834 41123 20288 41124 20834 41124 20289 41124 20289 41125 20834 41125 20539 41125 20539 41126 20834 41126 20835 41126 20539 41127 20835 41127 20540 41127 20540 41128 20835 41128 20287 41128 20287 41129 20835 41129 20837 41129 20287 41130 20837 41130 20285 41130 20285 41131 20837 41131 20286 41131 20286 41132 20837 41132 20839 41132 20286 41133 20839 41133 20541 41133 20541 41134 20839 41134 20542 41134 20542 41135 20839 41135 20841 41135 20542 41136 20841 41136 10003 41136 20543 41137 20842 41137 20544 41137 20544 41138 20842 41138 20844 41138 20544 41139 20844 41139 20545 41139 20545 41140 20844 41140 20546 41140 20546 41141 20844 41141 20845 41141 20546 41142 20845 41142 20294 41142 20294 41143 20845 41143 20547 41143 20547 41144 20845 41144 20549 41144 20547 41145 20549 41145 20548 41145 20548 41146 20549 41146 20550 41146 20550 41147 20549 41147 20551 41147 20550 41148 20551 41148 20292 41148 20292 41149 20551 41149 20293 41149 20293 41150 20551 41150 20552 41150 20293 41151 20552 41151 20553 41151 20553 41152 20552 41152 20554 41152 20554 41153 20552 41153 20555 41153 20554 41154 20555 41154 9947 41154 9946 41155 9781 41155 20300 41155 20300 41156 9781 41156 20848 41156 20300 41157 20848 41157 20556 41157 20556 41158 20848 41158 20557 41158 20557 41159 20848 41159 20558 41159 20557 41160 20558 41160 20559 41160 20559 41161 20558 41161 20299 41161 20299 41162 20558 41162 20850 41162 20299 41163 20850 41163 20560 41163 20560 41164 20850 41164 20295 41164 20295 41165 20850 41165 20561 41165 20295 41166 20561 41166 20298 41166 20298 41167 20561 41167 20296 41167 20296 41168 20561 41168 20562 41168 20296 41169 20562 41169 20563 41169 20563 41170 20562 41170 20564 41170 20564 41171 20562 41171 9937 41171 20564 41172 9937 41172 9993 41172 20302 41173 9771 41173 20301 41173 20301 41174 9771 41174 20565 41174 20301 41175 20565 41175 20566 41175 20566 41176 20565 41176 20855 41176 20566 41177 20855 41177 20303 41177 20303 41178 20855 41178 20567 41178 20303 41179 20567 41179 20568 41179 20568 41180 20567 41180 20857 41180 20568 41181 20857 41181 20569 41181 20569 41182 20857 41182 20570 41182 20569 41183 20570 41183 20571 41183 20571 41184 20570 41184 20572 41184 9929 41185 9930 41185 20573 41185 20573 41186 9930 41186 20575 41186 20573 41187 20575 41187 20574 41187 20574 41188 20575 41188 20859 41188 20574 41189 20859 41189 20576 41189 20576 41190 20859 41190 20577 41190 20576 41191 20577 41191 20578 41191 20578 41192 20577 41192 20861 41192 20578 41193 20861 41193 20579 41193 20579 41194 20861 41194 20862 41194 20579 41195 20862 41195 20306 41195 20306 41196 20862 41196 20580 41196 20306 41197 20580 41197 9924 41197 9924 41198 20580 41198 20864 41198 20581 41199 20582 41199 20307 41199 20307 41200 20582 41200 20583 41200 20307 41201 20583 41201 20311 41201 20311 41202 20583 41202 20584 41202 20584 41203 20583 41203 20866 41203 20584 41204 20866 41204 20585 41204 20585 41205 20866 41205 20308 41205 20308 41206 20866 41206 20586 41206 20308 41207 20586 41207 20309 41207 20309 41208 20586 41208 20587 41208 20587 41209 20586 41209 20588 41209 20587 41210 20588 41210 20589 41210 20589 41211 20588 41211 20310 41211 20310 41212 20588 41212 20591 41212 20310 41213 20591 41213 20590 41213 20590 41214 20591 41214 20592 41214 20592 41215 20591 41215 9914 41215 20592 41216 9914 41216 9915 41216 20873 41217 20874 41217 20593 41217 20593 41218 20874 41218 20313 41218 20874 41219 20594 41219 20313 41219 20313 41220 20594 41220 20595 41220 20313 41221 20595 41221 20596 41221 20595 41222 20597 41222 20596 41222 20596 41223 20597 41223 20598 41223 20596 41224 20598 41224 20599 41224 20598 41225 20870 41225 20599 41225 20599 41226 20870 41226 20600 41226 20599 41227 20600 41227 20602 41227 20600 41228 20601 41228 20602 41228 20602 41229 20601 41229 20869 41229 20602 41230 20869 41230 20314 41230 9907 41231 20604 41231 20603 41231 20603 41232 20604 41232 20314 41232 20603 41233 20314 41233 20868 41233 20868 41234 20314 41234 20869 41234 20315 41235 20605 41235 20324 41235 20324 41236 20605 41236 20606 41236 20324 41237 20606 41237 20325 41237 20325 41238 20606 41238 20607 41238 20607 41239 20606 41239 20608 41239 20607 41240 20608 41240 20323 41240 20323 41241 20608 41241 20609 41241 20609 41242 20608 41242 20878 41242 20609 41243 20878 41243 20316 41243 20316 41244 20878 41244 20610 41244 20610 41245 20878 41245 20611 41245 20610 41246 20611 41246 20322 41246 20322 41247 20611 41247 20321 41247 20321 41248 20611 41248 20880 41248 20321 41249 20880 41249 20318 41249 20318 41250 20880 41250 20319 41250 20319 41251 20880 41251 20612 41251 20319 41252 20612 41252 20317 41252 9898 41253 20613 41253 20882 41253 9898 41254 20882 41254 20614 41254 20614 41255 20882 41255 20883 41255 20614 41256 20883 41256 20326 41256 20326 41257 20883 41257 20615 41257 20615 41258 20883 41258 20618 41258 20615 41259 20618 41259 20616 41259 20616 41260 20618 41260 20617 41260 20617 41261 20618 41261 20620 41261 20617 41262 20620 41262 20327 41262 20327 41263 20620 41263 20619 41263 20619 41264 20620 41264 20621 41264 20619 41265 20621 41265 20329 41265 20329 41266 20621 41266 20622 41266 20329 41267 20622 41267 20328 41267 20328 41268 20622 41268 20623 41268 20328 41269 20623 41269 9890 41269 20624 41270 20625 41270 20887 41270 20887 41271 20625 41271 20626 41271 20887 41272 20626 41272 20627 41272 20627 41273 20626 41273 20628 41273 20625 41274 20624 41274 20333 41274 20333 41275 20624 41275 20629 41275 20333 41276 20629 41276 20630 41276 20630 41277 20629 41277 20890 41277 20630 41278 20890 41278 20631 41278 20631 41279 20890 41279 20632 41279 20631 41280 20632 41280 20334 41280 20334 41281 20632 41281 20892 41281 20895 41282 20634 41282 20633 41282 20633 41283 20634 41283 20331 41283 20633 41284 20331 41284 20892 41284 20892 41285 20331 41285 20334 41285 20634 41286 20895 41286 20635 41286 20635 41287 20895 41287 20896 41287 20635 41288 20896 41288 20636 41288 20636 41289 20896 41289 20897 41289 20636 41290 20897 41290 20335 41290 20335 41291 20897 41291 20637 41291 20335 41292 20637 41292 20336 41292 20336 41293 20637 41293 20899 41293 20642 41294 20337 41294 20901 41294 20901 41295 20337 41295 20638 41295 20901 41296 20638 41296 20899 41296 20899 41297 20638 41297 20336 41297 20639 41298 20643 41298 20332 41298 20639 41299 20332 41299 20641 41299 20641 41300 20332 41300 20640 41300 20641 41301 20640 41301 9732 41301 9732 41302 20640 41302 20337 41302 9732 41303 20337 41303 20642 41303 20645 41304 20643 41304 20903 41304 20903 41305 20643 41305 20639 41305 20627 41306 20628 41306 20907 41306 20907 41307 20628 41307 20330 41307 20907 41308 20330 41308 20906 41308 20906 41309 20330 41309 20644 41309 20906 41310 20644 41310 20903 41310 20903 41311 20644 41311 20645 41311 20648 41312 20646 41312 20909 41312 20909 41313 20646 41313 20647 41313 20909 41314 20647 41314 20908 41314 20908 41315 20647 41315 20345 41315 20646 41316 20648 41316 20344 41316 20344 41317 20648 41317 20912 41317 20344 41318 20912 41318 20342 41318 20342 41319 20912 41319 20914 41319 20342 41320 20914 41320 20343 41320 20343 41321 20914 41321 20915 41321 20343 41322 20915 41322 20649 41322 20649 41323 20915 41323 20651 41323 20919 41324 20652 41324 20650 41324 20650 41325 20652 41325 20347 41325 20650 41326 20347 41326 20651 41326 20651 41327 20347 41327 20649 41327 20652 41328 20919 41328 20338 41328 20338 41329 20919 41329 20653 41329 20338 41330 20653 41330 20654 41330 20654 41331 20653 41331 20922 41331 20654 41332 20922 41332 20346 41332 20346 41333 20922 41333 20655 41333 20346 41334 20655 41334 20658 41334 20658 41335 20655 41335 20656 41335 20657 41336 20339 41336 20925 41336 20925 41337 20339 41337 20348 41337 20925 41338 20348 41338 20656 41338 20656 41339 20348 41339 20658 41339 20929 41340 20662 41340 20659 41340 20659 41341 20662 41341 20341 41341 20659 41342 20341 41342 20928 41342 20928 41343 20341 41343 20340 41343 20928 41344 20340 41344 20657 41344 20657 41345 20340 41345 20339 41345 20660 41346 20662 41346 20661 41346 20661 41347 20662 41347 20929 41347 20908 41348 20345 41348 20663 41348 20908 41349 20663 41349 20932 41349 20932 41350 20663 41350 20664 41350 20932 41351 20664 41351 20931 41351 20931 41352 20664 41352 20660 41352 20931 41353 20660 41353 20661 41353 20665 41354 20666 41354 20933 41354 20933 41355 20666 41355 20359 41355 20933 41356 20359 41356 20950 41356 20950 41357 20359 41357 20682 41357 20666 41358 20665 41358 20667 41358 20667 41359 20665 41359 20668 41359 20939 41360 20669 41360 20937 41360 20937 41361 20669 41361 20356 41361 20937 41362 20356 41362 20670 41362 20670 41363 20356 41363 20671 41363 20669 41364 20939 41364 20672 41364 20672 41365 20939 41365 20941 41365 20672 41366 20941 41366 20349 41366 20349 41367 20941 41367 20673 41367 20349 41368 20673 41368 20674 41368 20674 41369 20673 41369 20676 41369 20674 41370 20676 41370 20675 41370 20675 41371 20676 41371 20678 41371 20945 41372 20354 41372 20677 41372 20677 41373 20354 41373 20353 41373 20677 41374 20353 41374 20678 41374 20678 41375 20353 41375 20675 41375 20946 41376 20351 41376 20679 41376 20679 41377 20351 41377 20350 41377 20679 41378 20350 41378 20680 41378 20680 41379 20350 41379 20352 41379 20680 41380 20352 41380 20945 41380 20945 41381 20352 41381 20354 41381 20685 41382 20351 41382 20948 41382 20948 41383 20351 41383 20946 41383 20950 41384 20682 41384 20681 41384 20681 41385 20682 41385 20683 41385 20681 41386 20683 41386 20684 41386 20684 41387 20683 41387 20355 41387 20684 41388 20355 41388 20948 41388 20948 41389 20355 41389 20685 41389 20686 41390 20369 41390 20687 41390 20687 41391 20369 41391 20688 41391 20687 41392 20688 41392 20971 41392 20971 41393 20688 41393 20368 41393 20369 41394 20686 41394 20689 41394 20689 41395 20686 41395 20691 41395 20689 41396 20691 41396 20690 41396 20690 41397 20691 41397 20692 41397 20690 41398 20692 41398 9885 41398 9885 41399 20692 41399 9886 41399 20694 41400 20693 41400 20955 41400 20955 41401 20693 41401 20362 41401 20955 41402 20362 41402 9888 41402 9888 41403 20362 41403 9887 41403 20693 41404 20694 41404 20365 41404 20365 41405 20694 41405 20695 41405 20365 41406 20695 41406 20696 41406 20696 41407 20695 41407 20959 41407 20696 41408 20959 41408 20697 41408 20697 41409 20959 41409 20961 41409 20697 41410 20961 41410 20366 41410 20366 41411 20961 41411 20699 41411 20965 41412 20361 41412 20698 41412 20698 41413 20361 41413 20360 41413 20698 41414 20360 41414 20699 41414 20699 41415 20360 41415 20366 41415 20701 41416 20364 41416 20363 41416 20701 41417 20363 41417 20700 41417 20700 41418 20363 41418 9883 41418 20700 41419 9883 41419 9882 41419 20367 41420 20364 41420 20968 41420 20968 41421 20364 41421 20701 41421 20971 41422 20368 41422 20702 41422 20702 41423 20368 41423 20703 41423 20702 41424 20703 41424 20704 41424 20704 41425 20703 41425 20705 41425 20704 41426 20705 41426 20968 41426 20968 41427 20705 41427 20367 41427 20706 41428 20373 41428 20973 41428 20973 41429 20373 41429 20372 41429 20973 41430 20372 41430 20972 41430 20972 41431 20372 41431 20370 41431 20373 41432 20706 41432 20707 41432 20707 41433 20706 41433 20708 41433 20707 41434 20708 41434 20375 41434 20375 41435 20708 41435 20977 41435 20375 41436 20977 41436 20710 41436 20710 41437 20977 41437 20709 41437 20710 41438 20709 41438 20374 41438 20374 41439 20709 41439 20979 41439 20711 41440 20378 41440 20982 41440 20982 41441 20378 41441 20371 41441 20982 41442 20371 41442 20979 41442 20979 41443 20371 41443 20374 41443 20378 41444 20711 41444 20377 41444 20377 41445 20711 41445 20712 41445 20988 41446 20719 41446 20985 41446 20985 41447 20719 41447 20713 41447 20985 41448 20713 41448 20984 41448 20984 41449 20713 41449 9881 41449 20714 41450 20715 41450 20716 41450 20716 41451 20715 41451 20717 41451 20716 41452 20717 41452 20990 41452 20990 41453 20717 41453 20718 41453 20990 41454 20718 41454 20988 41454 20988 41455 20718 41455 20719 41455 9877 41456 20715 41456 20992 41456 20992 41457 20715 41457 20714 41457 20972 41458 20370 41458 20720 41458 20720 41459 20370 41459 20721 41459 20720 41460 20721 41460 20722 41460 20725 41461 20390 41461 20723 41461 20723 41462 20390 41462 20724 41462 20723 41463 20724 41463 21009 41463 21009 41464 20724 41464 20386 41464 20390 41465 20725 41465 20388 41465 20388 41466 20725 41466 20726 41466 20388 41467 20726 41467 20389 41467 20389 41468 20726 41468 20727 41468 20389 41469 20727 41469 20391 41469 20391 41470 20727 41470 20729 41470 20391 41471 20729 41471 20728 41471 20728 41472 20729 41472 20733 41472 20730 41473 20732 41473 20731 41473 20731 41474 20732 41474 20387 41474 20731 41475 20387 41475 20733 41475 20733 41476 20387 41476 20728 41476 20732 41477 20730 41477 20379 41477 20379 41478 20730 41478 21000 41478 20379 41479 21000 41479 20381 41479 20381 41480 21000 41480 20734 41480 20381 41481 20734 41481 20382 41481 20382 41482 20734 41482 20735 41482 20740 41483 20737 41483 20736 41483 20736 41484 20737 41484 20384 41484 20736 41485 20384 41485 9875 41485 9875 41486 20384 41486 20383 41486 21005 41487 20738 41487 21003 41487 21003 41488 20738 41488 20380 41488 21003 41489 20380 41489 21002 41489 21002 41490 20380 41490 20739 41490 21002 41491 20739 41491 20740 41491 20740 41492 20739 41492 20737 41492 20744 41493 20738 41493 20741 41493 20741 41494 20738 41494 21005 41494 21009 41495 20386 41495 20742 41495 20742 41496 20386 41496 20385 41496 20742 41497 20385 41497 21007 41497 21007 41498 20385 41498 20743 41498 21007 41499 20743 41499 20741 41499 20741 41500 20743 41500 20744 41500 9975 41501 9974 41501 20758 41501 20758 41502 9974 41502 20745 41502 20758 41503 20745 41503 21014 41503 21014 41504 20745 41504 20746 41504 21014 41505 20746 41505 21012 41505 21012 41506 20746 41506 20747 41506 21012 41507 20747 41507 21010 41507 21010 41508 20747 41508 9969 41508 21010 41509 9969 41509 20748 41509 20748 41510 9969 41510 20398 41510 20748 41511 20398 41511 9724 41511 9724 41512 20398 41512 20396 41512 9724 41513 20396 41513 20749 41513 20749 41514 20396 41514 20394 41514 20749 41515 20394 41515 20750 41515 20750 41516 20394 41516 20751 41516 20750 41517 20751 41517 20752 41517 20752 41518 20751 41518 20753 41518 20752 41519 20753 41519 9722 41519 9722 41520 20753 41520 20755 41520 9722 41521 20755 41521 20754 41521 20754 41522 20755 41522 20756 41522 20754 41523 20756 41523 20757 41523 20757 41524 20756 41524 9975 41524 20757 41525 9975 41525 20758 41525 20409 41526 20759 41526 21016 41526 20409 41527 21016 41527 20410 41527 20410 41528 21016 41528 20760 41528 20410 41529 20760 41529 20412 41529 20760 41530 21019 41530 20412 41530 20412 41531 21019 41531 20761 41531 20412 41532 20761 41532 20413 41532 20761 41533 21017 41533 20413 41533 20413 41534 21017 41534 20762 41534 20413 41535 20762 41535 20399 41535 20399 41536 20762 41536 20763 41536 20399 41537 20763 41537 20765 41537 20763 41538 20764 41538 20765 41538 20765 41539 20764 41539 21022 41539 20765 41540 21022 41540 20402 41540 20402 41541 21022 41541 20766 41541 20766 41542 21024 41542 20402 41542 20402 41543 21024 41543 9866 41543 20402 41544 9866 41544 9868 41544 20767 41545 21032 41545 21033 41545 20767 41546 21033 41546 20418 41546 20418 41547 21033 41547 21025 41547 20418 41548 21025 41548 20419 41548 20419 41549 21025 41549 21027 41549 20419 41550 21027 41550 20421 41550 20421 41551 21027 41551 20768 41551 20421 41552 20768 41552 20770 41552 20770 41553 20768 41553 20769 41553 20770 41554 20769 41554 20771 41554 20771 41555 20769 41555 21030 41555 20771 41556 21030 41556 9858 41556 20433 41557 20434 41557 20772 41557 20772 41558 20434 41558 9857 41558 20772 41559 9857 41559 9856 41559 20772 41560 21044 41560 20433 41560 20433 41561 21044 41561 21042 41561 20433 41562 21042 41562 20774 41562 20774 41563 21042 41563 21040 41563 21040 41564 20773 41564 20774 41564 20774 41565 20773 41565 20775 41565 20774 41566 20775 41566 20432 41566 20775 41567 20776 41567 20432 41567 20432 41568 20776 41568 20777 41568 20432 41569 20777 41569 20431 41569 20777 41570 21038 41570 20431 41570 20431 41571 21038 41571 9706 41571 20431 41572 9706 41572 9848 41572 20448 41573 21055 41573 20778 41573 20448 41574 20778 41574 20779 41574 20779 41575 20778 41575 21054 41575 20779 41576 21054 41576 20780 41576 20780 41577 21054 41577 21053 41577 20780 41578 21053 41578 20782 41578 20782 41579 21053 41579 20781 41579 20782 41580 20781 41580 20450 41580 20450 41581 20781 41581 21047 41581 20450 41582 21047 41582 20783 41582 20783 41583 21047 41583 21048 41583 20783 41584 21048 41584 20784 41584 20784 41585 21048 41585 20785 41585 20784 41586 20785 41586 20439 41586 20786 41587 21065 41587 21064 41587 20786 41588 21064 41588 20787 41588 20787 41589 21064 41589 20788 41589 20787 41590 20788 41590 20459 41590 20459 41591 20788 41591 21061 41591 20459 41592 21061 41592 20461 41592 20461 41593 21061 41593 21060 41593 20461 41594 21060 41594 20463 41594 20463 41595 21060 41595 20789 41595 20463 41596 20789 41596 20790 41596 20790 41597 20789 41597 21059 41597 20790 41598 21059 41598 9838 41598 20474 41599 21076 41599 21075 41599 20474 41600 21075 41600 20791 41600 20791 41601 21075 41601 21072 41601 20791 41602 21072 41602 20792 41602 20792 41603 21072 41603 21071 41603 20792 41604 21071 41604 20476 41604 20476 41605 21071 41605 21069 41605 20476 41606 21069 41606 20793 41606 20793 41607 21069 41607 21068 41607 20793 41608 21068 41608 20794 41608 20794 41609 21068 41609 9686 41609 20794 41610 9686 41610 20795 41610 20796 41611 9832 41611 21082 41611 20796 41612 21082 41612 20489 41612 20489 41613 21082 41613 21081 41613 20489 41614 21081 41614 20797 41614 20797 41615 21081 41615 21080 41615 20797 41616 21080 41616 20492 41616 20492 41617 21080 41617 20798 41617 20492 41618 20798 41618 20799 41618 20799 41619 20798 41619 20801 41619 20799 41620 20801 41620 20800 41620 20800 41621 20801 41621 20802 41621 20800 41622 20802 41622 20483 41622 20483 41623 20802 41623 21078 41623 20483 41624 21078 41624 20484 41624 20804 41625 20499 41625 20803 41625 20803 41626 20499 41626 9825 41626 20803 41627 9825 41627 9824 41627 20803 41628 21089 41628 20804 41628 20804 41629 21089 41629 21087 41629 20804 41630 21087 41630 20500 41630 20500 41631 21087 41631 21085 41631 21085 41632 20805 41632 20500 41632 20500 41633 20805 41633 21090 41633 20500 41634 21090 41634 20806 41634 21090 41635 21092 41635 20806 41635 20806 41636 21092 41636 21094 41636 20806 41637 21094 41637 20503 41637 21094 41638 20807 41638 20503 41638 20503 41639 20807 41639 20808 41639 20503 41640 20808 41640 20505 41640 20511 41641 9664 41641 20810 41641 20511 41642 20810 41642 20809 41642 20809 41643 20810 41643 20811 41643 20809 41644 20811 41644 20812 41644 20812 41645 20811 41645 20813 41645 20812 41646 20813 41646 20815 41646 20815 41647 20813 41647 20814 41647 20815 41648 20814 41648 20816 41648 20816 41649 20814 41649 21100 41649 20816 41650 21100 41650 20817 41650 20817 41651 21100 41651 9809 41651 20817 41652 9809 41652 9808 41652 20521 41653 21103 41653 20818 41653 20521 41654 20818 41654 20819 41654 20819 41655 20818 41655 21104 41655 20819 41656 21104 41656 20523 41656 21104 41657 21107 41657 20523 41657 20523 41658 21107 41658 21106 41658 20523 41659 21106 41659 20515 41659 21106 41660 20820 41660 20515 41660 20515 41661 20820 41661 20821 41661 20515 41662 20821 41662 20822 41662 20822 41663 20821 41663 21108 41663 20822 41664 21108 41664 20823 41664 21108 41665 21109 41665 20823 41665 20823 41666 21109 41666 20824 41666 20823 41667 20824 41667 20516 41667 20516 41668 20824 41668 20825 41668 20825 41669 21111 41669 20516 41669 20516 41670 21111 41670 20826 41670 20516 41671 20826 41671 9800 41671 20827 41672 9799 41672 20828 41672 20827 41673 20828 41673 20829 41673 20829 41674 20828 41674 21114 41674 20829 41675 21114 41675 20532 41675 20532 41676 21114 41676 20830 41676 20532 41677 20830 41677 20533 41677 20533 41678 20830 41678 20831 41678 20533 41679 20831 41679 20535 41679 20535 41680 20831 41680 21116 41680 20535 41681 21116 41681 20832 41681 20832 41682 21116 41682 21117 41682 20832 41683 21117 41683 20536 41683 20536 41684 21117 41684 21118 41684 20536 41685 21118 41685 9794 41685 9967 41686 21243 41686 20537 41686 20537 41687 21243 41687 20833 41687 20537 41688 20833 41688 20834 41688 20834 41689 20833 41689 20836 41689 20834 41690 20836 41690 20835 41690 20835 41691 20836 41691 20838 41691 20835 41692 20838 41692 20837 41692 20837 41693 20838 41693 20840 41693 20837 41694 20840 41694 20839 41694 20839 41695 20840 41695 21240 41695 20839 41696 21240 41696 20841 41696 20841 41697 21240 41697 21241 41697 20842 41698 20843 41698 20844 41698 20844 41699 20843 41699 21227 41699 20844 41700 21227 41700 20845 41700 20845 41701 21227 41701 21228 41701 20845 41702 21228 41702 20549 41702 20549 41703 21228 41703 20846 41703 20549 41704 20846 41704 20551 41704 20551 41705 20846 41705 21236 41705 20551 41706 21236 41706 20552 41706 20552 41707 21236 41707 20847 41707 20552 41708 20847 41708 20555 41708 20555 41709 20847 41709 9783 41709 9781 41710 9782 41710 20848 41710 20848 41711 9782 41711 20849 41711 20848 41712 20849 41712 20558 41712 20558 41713 20849 41713 20851 41713 20558 41714 20851 41714 20850 41714 20850 41715 20851 41715 21293 41715 20850 41716 21293 41716 20561 41716 20561 41717 21293 41717 20852 41717 20561 41718 20852 41718 20562 41718 20562 41719 20852 41719 20853 41719 20562 41720 20853 41720 9937 41720 9937 41721 20853 41721 9773 41721 9771 41722 21282 41722 20565 41722 20565 41723 21282 41723 20854 41723 20565 41724 20854 41724 20855 41724 20855 41725 20854 41725 20856 41725 20855 41726 20856 41726 20567 41726 20567 41727 20856 41727 20858 41727 20567 41728 20858 41728 20857 41728 20857 41729 20858 41729 21280 41729 20857 41730 21280 41730 20570 41730 20570 41731 21280 41731 21277 41731 20570 41732 21277 41732 20572 41732 20572 41733 21277 41733 21278 41733 9930 41734 9766 41734 20575 41734 20575 41735 9766 41735 20860 41735 20575 41736 20860 41736 20859 41736 20859 41737 20860 41737 21140 41737 20859 41738 21140 41738 20577 41738 20577 41739 21140 41739 21139 41739 20577 41740 21139 41740 20861 41740 20861 41741 21139 41741 21346 41741 20861 41742 21346 41742 20862 41742 20862 41743 21346 41743 20863 41743 20862 41744 20863 41744 20580 41744 20580 41745 20863 41745 21345 41745 20580 41746 21345 41746 20864 41746 20864 41747 21345 41747 9760 41747 20582 41748 21332 41748 20583 41748 20583 41749 21332 41749 20865 41749 20583 41750 20865 41750 20866 41750 20866 41751 20865 41751 21143 41751 20866 41752 21143 41752 20586 41752 20586 41753 21143 41753 21144 41753 20586 41754 21144 41754 20588 41754 20588 41755 21144 41755 21339 41755 20588 41756 21339 41756 20591 41756 20591 41757 21339 41757 21147 41757 20591 41758 21147 41758 9914 41758 9914 41759 21147 41759 21146 41759 20867 41760 21150 41760 9907 41760 9907 41761 20603 41761 20867 41761 20867 41762 20603 41762 20868 41762 20867 41763 20868 41763 21151 41763 20868 41764 20869 41764 21151 41764 21151 41765 20869 41765 20601 41765 21151 41766 20601 41766 21153 41766 20601 41767 20600 41767 21153 41767 21153 41768 20600 41768 20870 41768 21153 41769 20870 41769 21154 41769 21154 41770 20870 41770 20598 41770 21154 41771 20598 41771 20871 41771 20598 41772 20597 41772 20871 41772 20871 41773 20597 41773 20595 41773 20871 41774 20595 41774 20872 41774 20873 41775 20875 41775 20874 41775 20874 41776 20875 41776 20872 41776 20874 41777 20872 41777 20594 41777 20594 41778 20872 41778 20595 41778 20605 41779 20876 41779 20606 41779 20606 41780 20876 41780 20877 41780 20606 41781 20877 41781 20608 41781 20608 41782 20877 41782 21314 41782 20608 41783 21314 41783 20878 41783 20878 41784 21314 41784 20879 41784 20878 41785 20879 41785 20611 41785 20611 41786 20879 41786 21317 41786 20611 41787 21317 41787 20880 41787 20880 41788 21317 41788 20881 41788 20880 41789 20881 41789 20612 41789 20612 41790 20881 41790 9742 41790 20613 41791 9741 41791 20882 41791 20882 41792 9741 41792 20884 41792 20882 41793 20884 41793 20883 41793 20883 41794 20884 41794 20885 41794 20883 41795 20885 41795 20618 41795 20618 41796 20885 41796 20886 41796 20618 41797 20886 41797 20620 41797 20620 41798 20886 41798 21158 41798 20620 41799 21158 41799 20621 41799 20621 41800 21158 41800 21157 41800 20621 41801 21157 41801 20622 41801 20622 41802 21157 41802 21160 41802 20622 41803 21160 41803 20623 41803 20623 41804 21160 41804 21159 41804 20627 41805 20888 41805 20887 41805 20887 41806 20888 41806 21171 41806 20887 41807 21171 41807 20624 41807 20624 41808 21171 41808 20889 41808 20624 41809 20889 41809 20629 41809 20629 41810 20889 41810 20891 41810 20629 41811 20891 41811 20890 41811 20890 41812 20891 41812 21335 41812 20890 41813 21335 41813 20632 41813 20632 41814 21335 41814 20893 41814 20632 41815 20893 41815 20892 41815 20892 41816 20893 41816 20894 41816 20892 41817 20894 41817 20633 41817 20633 41818 20894 41818 21155 41818 20633 41819 21155 41819 20895 41819 20895 41820 21155 41820 21175 41820 20895 41821 21175 41821 20896 41821 20896 41822 21175 41822 21181 41822 20896 41823 21181 41823 20897 41823 20897 41824 21181 41824 21179 41824 20897 41825 21179 41825 20637 41825 20637 41826 21179 41826 20898 41826 20637 41827 20898 41827 20899 41827 20899 41828 20898 41828 21188 41828 20899 41829 21188 41829 20901 41829 20901 41830 21188 41830 20900 41830 20901 41831 20900 41831 20642 41831 20642 41832 20900 41832 20902 41832 20642 41833 20902 41833 9732 41833 9732 41834 20902 41834 21185 41834 20903 41835 20639 41835 20904 41835 20904 41836 20639 41836 20905 41836 20903 41837 20904 41837 20906 41837 20906 41838 20904 41838 21169 41838 20906 41839 21169 41839 20907 41839 20907 41840 21169 41840 21167 41840 20907 41841 21167 41841 20627 41841 20627 41842 21167 41842 20888 41842 20908 41843 20910 41843 20909 41843 20909 41844 20910 41844 20911 41844 20909 41845 20911 41845 20648 41845 20648 41846 20911 41846 21191 41846 20648 41847 21191 41847 20912 41847 20912 41848 21191 41848 20913 41848 20912 41849 20913 41849 20914 41849 20914 41850 20913 41850 21193 41850 20914 41851 21193 41851 20915 41851 20915 41852 21193 41852 20916 41852 20915 41853 20916 41853 20651 41853 20651 41854 20916 41854 20917 41854 20651 41855 20917 41855 20650 41855 20650 41856 20917 41856 20918 41856 20650 41857 20918 41857 20919 41857 20919 41858 20918 41858 20920 41858 20919 41859 20920 41859 20653 41859 20653 41860 20920 41860 20921 41860 20653 41861 20921 41861 20922 41861 20922 41862 20921 41862 20923 41862 20922 41863 20923 41863 20655 41863 20655 41864 20923 41864 20924 41864 20655 41865 20924 41865 20656 41865 20656 41866 20924 41866 21205 41866 20656 41867 21205 41867 20925 41867 20925 41868 21205 41868 21203 41868 20925 41869 21203 41869 20657 41869 20657 41870 21203 41870 20926 41870 20657 41871 20926 41871 20928 41871 20928 41872 20926 41872 20927 41872 20928 41873 20927 41873 20659 41873 20659 41874 20927 41874 21202 41874 20659 41875 21202 41875 20929 41875 20929 41876 21202 41876 20930 41876 20661 41877 20929 41877 21200 41877 21200 41878 20929 41878 20930 41878 20661 41879 21200 41879 20931 41879 20931 41880 21200 41880 21201 41880 20931 41881 21201 41881 20932 41881 20932 41882 21201 41882 21213 41882 20950 41883 21217 41883 20933 41883 20933 41884 21217 41884 20934 41884 20933 41885 20934 41885 20665 41885 20665 41886 20934 41886 20935 41886 20665 41887 20935 41887 20668 41887 20668 41888 20935 41888 9730 41888 20670 41889 20936 41889 20937 41889 20937 41890 20936 41890 20938 41890 20937 41891 20938 41891 20939 41891 20939 41892 20938 41892 20940 41892 20939 41893 20940 41893 20941 41893 20941 41894 20940 41894 20942 41894 20941 41895 20942 41895 20673 41895 20673 41896 20942 41896 20943 41896 20673 41897 20943 41897 20676 41897 20676 41898 20943 41898 21208 41898 20676 41899 21208 41899 20678 41899 20678 41900 21208 41900 21192 41900 20678 41901 21192 41901 20677 41901 20677 41902 21192 41902 20944 41902 20677 41903 20944 41903 20945 41903 20945 41904 20944 41904 21190 41904 20945 41905 21190 41905 20680 41905 20680 41906 21190 41906 21212 41906 20680 41907 21212 41907 20679 41907 20679 41908 21212 41908 21215 41908 20679 41909 21215 41909 20946 41909 20946 41910 21215 41910 20947 41910 20948 41911 20946 41911 21216 41911 21216 41912 20946 41912 20947 41912 20948 41913 21216 41913 20684 41913 20684 41914 21216 41914 20949 41914 20684 41915 20949 41915 20681 41915 20681 41916 20949 41916 21218 41916 20681 41917 21218 41917 20950 41917 20950 41918 21218 41918 21217 41918 20971 41919 20951 41919 20687 41919 20687 41920 20951 41920 20952 41920 20687 41921 20952 41921 20686 41921 20686 41922 20952 41922 20953 41922 20686 41923 20953 41923 20691 41923 20691 41924 20953 41924 20954 41924 20691 41925 20954 41925 20692 41925 20692 41926 20954 41926 21221 41926 20692 41927 21221 41927 9886 41927 9886 41928 21221 41928 9729 41928 20957 41929 20694 41929 21235 41929 21235 41930 20694 41930 20955 41930 21235 41931 20955 41931 21233 41931 9888 41932 20956 41932 20955 41932 20955 41933 20956 41933 21223 41933 20955 41934 21223 41934 21233 41934 20694 41935 20957 41935 20695 41935 20695 41936 20957 41936 20958 41936 20695 41937 20958 41937 20959 41937 20959 41938 20958 41938 20960 41938 20959 41939 20960 41939 20961 41939 20961 41940 20960 41940 20962 41940 20961 41941 20962 41941 20699 41941 20699 41942 20962 41942 20963 41942 20699 41943 20963 41943 20698 41943 20698 41944 20963 41944 21237 41944 20698 41945 21237 41945 20965 41945 20965 41946 21237 41946 21219 41946 20967 41947 20701 41947 20964 41947 20964 41948 20701 41948 20700 41948 20964 41949 20700 41949 20966 41949 20965 41950 21219 41950 9884 41950 9884 41951 21219 41951 20966 41951 9884 41952 20966 41952 9882 41952 9882 41953 20966 41953 20700 41953 20968 41954 20701 41954 20969 41954 20969 41955 20701 41955 20967 41955 20968 41956 20969 41956 20704 41956 20704 41957 20969 41957 21220 41957 20704 41958 21220 41958 20702 41958 20702 41959 21220 41959 20970 41959 20702 41960 20970 41960 20971 41960 20971 41961 20970 41961 20951 41961 20972 41962 21267 41962 20973 41962 20973 41963 21267 41963 20974 41963 20973 41964 20974 41964 20706 41964 20706 41965 20974 41965 20975 41965 20706 41966 20975 41966 20708 41966 20708 41967 20975 41967 20976 41967 20708 41968 20976 41968 20977 41968 20977 41969 20976 41969 20978 41969 20977 41970 20978 41970 20709 41970 20709 41971 20978 41971 21131 41971 20709 41972 21131 41972 20979 41972 20979 41973 21131 41973 20980 41973 20982 41974 20979 41974 20980 41974 20983 41975 20711 41975 21250 41975 21250 41976 20711 41976 20982 41976 21250 41977 20982 41977 20981 41977 20981 41978 20982 41978 20980 41978 20711 41979 20983 41979 20712 41979 20712 41980 20983 41980 21254 41980 20984 41981 9728 41981 20985 41981 20985 41982 9728 41982 20986 41982 20985 41983 20986 41983 20988 41983 20988 41984 20986 41984 20987 41984 20988 41985 20987 41985 20990 41985 20990 41986 20987 41986 20989 41986 20990 41987 20989 41987 20716 41987 20716 41988 20989 41988 21257 41988 20716 41989 21257 41989 20714 41989 20714 41990 21257 41990 20991 41990 20992 41991 20714 41991 20993 41991 20993 41992 20714 41992 20991 41992 21238 41993 21267 41993 20972 41993 20992 41994 20993 41994 20994 41994 20994 41995 20993 41995 20995 41995 20994 41996 20995 41996 20722 41996 20722 41997 20995 41997 21238 41997 20722 41998 21238 41998 20720 41998 20720 41999 21238 41999 20972 41999 21009 42000 21184 42000 20723 42000 20723 42001 21184 42001 21186 42001 20723 42002 21186 42002 20725 42002 20725 42003 21186 42003 21187 42003 20725 42004 21187 42004 20726 42004 20726 42005 21187 42005 21189 42005 20726 42006 21189 42006 20727 42006 20727 42007 21189 42007 20996 42007 20727 42008 20996 42008 20729 42008 20729 42009 20996 42009 20997 42009 20729 42010 20997 42010 20733 42010 20733 42011 20997 42011 21182 42011 20733 42012 21182 42012 20731 42012 20731 42013 21182 42013 20998 42013 20731 42014 20998 42014 20730 42014 20730 42015 20998 42015 20999 42015 20730 42016 20999 42016 21000 42016 21000 42017 20999 42017 21265 42017 21000 42018 21265 42018 20734 42018 20734 42019 21265 42019 21264 42019 20734 42020 21264 42020 20735 42020 20735 42021 21264 42021 21310 42021 9875 42022 21263 42022 20736 42022 20736 42023 21263 42023 21262 42023 20736 42024 21262 42024 20740 42024 20740 42025 21262 42025 21261 42025 20740 42026 21261 42026 21002 42026 21002 42027 21261 42027 21001 42027 21002 42028 21001 42028 21003 42028 21003 42029 21001 42029 21004 42029 21003 42030 21004 42030 21005 42030 21005 42031 21004 42031 21355 42031 20741 42032 21005 42032 21006 42032 21006 42033 21005 42033 21355 42033 20741 42034 21006 42034 21007 42034 21007 42035 21006 42035 21268 42035 21007 42036 21268 42036 20742 42036 20742 42037 21268 42037 21008 42037 20742 42038 21008 42038 21009 42038 21009 42039 21008 42039 21184 42039 21010 42040 21358 42040 21011 42040 21010 42041 21011 42041 21012 42041 21012 42042 21011 42042 21013 42042 21012 42043 21013 42043 21014 42043 21014 42044 21013 42044 21015 42044 21014 42045 21015 42045 20758 42045 20758 42046 21015 42046 21361 42046 20758 42047 21361 42047 20757 42047 20757 42048 21361 42048 21362 42048 20757 42049 21362 42049 20754 42049 20754 42050 21362 42050 9648 42050 20754 42051 9648 42051 9722 42051 20759 42052 21337 42052 21016 42052 21016 42053 21337 42053 21338 42053 21018 42054 21019 42054 21338 42054 21338 42055 21019 42055 20760 42055 21338 42056 20760 42056 21016 42056 20763 42057 20762 42057 21020 42057 21020 42058 20762 42058 21017 42058 21020 42059 21017 42059 21018 42059 21018 42060 21017 42060 20761 42060 21018 42061 20761 42061 21019 42061 20763 42062 21020 42062 20764 42062 20764 42063 21020 42063 21021 42063 20764 42064 21021 42064 21022 42064 21022 42065 21021 42065 21199 42065 21022 42066 21199 42066 20766 42066 20766 42067 21199 42067 21024 42067 21024 42068 21199 42068 21023 42068 21024 42069 21023 42069 9866 42069 21033 42070 21034 42070 21025 42070 21025 42071 21034 42071 21026 42071 21025 42072 21026 42072 21027 42072 21027 42073 21026 42073 21028 42073 21027 42074 21028 42074 20768 42074 20768 42075 21028 42075 21029 42075 20768 42076 21029 42076 20769 42076 20769 42077 21029 42077 21328 42077 20769 42078 21328 42078 21030 42078 21031 42079 21368 42079 21032 42079 21032 42080 21368 42080 21367 42080 21032 42081 21367 42081 21033 42081 21033 42082 21367 42082 21124 42082 21033 42083 21124 42083 21034 42083 20773 42084 21172 42084 20775 42084 20775 42085 21172 42085 21035 42085 20775 42086 21035 42086 20776 42086 20776 42087 21035 42087 21036 42087 20776 42088 21036 42088 20777 42088 20777 42089 21036 42089 21037 42089 20777 42090 21037 42090 21038 42090 21038 42091 21037 42091 21039 42091 21038 42092 21039 42092 9706 42092 20773 42093 21040 42093 21172 42093 21172 42094 21040 42094 21042 42094 21172 42095 21042 42095 21041 42095 21041 42096 21042 42096 21044 42096 21041 42097 21044 42097 21043 42097 21043 42098 21044 42098 20772 42098 21043 42099 20772 42099 21176 42099 21176 42100 20772 42100 9856 42100 21176 42101 9856 42101 21045 42101 20781 42102 21050 42102 21047 42102 21047 42103 21050 42103 21046 42103 21047 42104 21046 42104 21048 42104 21048 42105 21046 42105 21049 42105 21048 42106 21049 42106 20785 42106 21053 42107 21371 42107 20781 42107 20781 42108 21371 42108 21323 42108 20781 42109 21323 42109 21050 42109 21325 42110 21051 42110 21053 42110 21053 42111 21051 42111 21052 42111 21053 42112 21052 42112 21371 42112 21053 42113 21054 42113 21325 42113 21325 42114 21054 42114 20778 42114 21325 42115 20778 42115 21326 42115 21326 42116 20778 42116 21055 42116 21326 42117 21055 42117 21324 42117 21128 42118 21056 42118 21060 42118 21060 42119 21056 42119 21057 42119 21060 42120 21057 42120 20789 42120 20789 42121 21057 42121 21058 42121 20789 42122 21058 42122 21059 42122 21128 42123 21060 42123 21375 42123 21375 42124 21060 42124 21061 42124 21375 42125 21061 42125 21062 42125 21062 42126 21061 42126 20788 42126 21062 42127 20788 42127 21063 42127 21063 42128 20788 42128 21064 42128 21063 42129 21064 42129 21321 42129 21321 42130 21064 42130 21065 42130 21321 42131 21065 42131 21066 42131 21304 42132 21303 42132 21068 42132 21068 42133 21303 42133 21067 42133 21068 42134 21067 42134 9686 42134 21304 42135 21068 42135 21378 42135 21378 42136 21068 42136 21069 42136 21378 42137 21069 42137 21070 42137 21070 42138 21069 42138 21071 42138 21070 42139 21071 42139 21073 42139 21073 42140 21071 42140 21072 42140 21073 42141 21072 42141 21074 42141 21074 42142 21072 42142 21075 42142 21074 42143 21075 42143 21164 42143 21164 42144 21075 42144 21076 42144 21164 42145 21076 42145 21163 42145 21384 42146 21077 42146 21078 42146 21384 42147 21078 42147 21245 42147 21245 42148 21078 42148 20802 42148 21245 42149 20802 42149 21246 42149 21246 42150 20802 42150 20801 42150 21246 42151 20801 42151 21247 42151 21247 42152 20801 42152 20798 42152 21247 42153 20798 42153 21079 42153 21079 42154 20798 42154 21080 42154 21079 42155 21080 42155 21249 42155 21249 42156 21080 42156 21081 42156 21249 42157 21081 42157 21251 42157 21251 42158 21081 42158 21082 42158 21251 42159 21082 42159 21083 42159 21083 42160 21082 42160 9832 42160 21083 42161 9832 42161 9685 42161 21088 42162 20803 42162 21084 42162 21084 42163 20803 42163 9824 42163 21084 42164 9824 42164 9669 42164 20805 42165 21085 42165 21086 42165 21086 42166 21085 42166 21087 42166 21086 42167 21087 42167 21088 42167 21088 42168 21087 42168 21089 42168 21088 42169 21089 42169 20803 42169 20805 42170 21086 42170 21090 42170 21090 42171 21086 42171 21091 42171 21090 42172 21091 42172 21092 42172 21092 42173 21091 42173 21093 42173 21092 42174 21093 42174 21094 42174 21094 42175 21093 42175 21095 42175 21094 42176 21095 42176 20807 42176 20807 42177 21095 42177 21096 42177 20807 42178 21096 42178 20808 42178 9664 42179 9662 42179 21097 42179 9664 42180 21097 42180 20810 42180 20810 42181 21097 42181 21098 42181 20810 42182 21098 42182 20811 42182 20811 42183 21098 42183 21099 42183 20811 42184 21099 42184 20813 42184 20813 42185 21099 42185 21298 42185 20813 42186 21298 42186 20814 42186 20814 42187 21298 42187 21101 42187 20814 42188 21101 42188 21100 42188 21100 42189 21101 42189 21102 42189 21100 42190 21102 42190 9809 42190 21103 42191 21281 42191 20818 42191 20818 42192 21281 42192 21130 42192 21105 42193 21107 42193 21130 42193 21130 42194 21107 42194 21104 42194 21130 42195 21104 42195 20818 42195 21108 42196 20821 42196 21110 42196 21110 42197 20821 42197 20820 42197 21110 42198 20820 42198 21105 42198 21105 42199 20820 42199 21106 42199 21105 42200 21106 42200 21107 42200 21108 42201 21110 42201 21109 42201 21109 42202 21110 42202 21273 42202 21109 42203 21273 42203 20824 42203 20824 42204 21273 42204 21206 42204 20824 42205 21206 42205 20825 42205 20825 42206 21206 42206 21111 42206 21111 42207 21206 42207 21289 42207 21111 42208 21289 42208 20826 42208 9799 42209 21112 42209 21113 42209 9799 42210 21113 42210 20828 42210 20828 42211 21113 42211 21207 42211 20828 42212 21207 42212 21114 42212 21114 42213 21207 42213 21209 42213 21114 42214 21209 42214 20830 42214 20830 42215 21209 42215 21210 42215 20830 42216 21210 42216 20831 42216 20831 42217 21210 42217 21211 42217 20831 42218 21211 42218 21116 42218 21116 42219 21211 42219 21115 42219 21116 42220 21115 42220 21117 42220 21117 42221 21115 42221 9653 42221 21117 42222 9653 42222 21118 42222 21119 42223 21120 42223 9614 42223 21349 42224 21353 42224 9614 42224 21121 42225 21122 42225 9637 42225 21122 42226 21121 42226 21123 42226 21124 42227 21367 42227 21331 42227 21148 42228 21330 42228 21331 42228 21125 42229 21126 42229 21127 42229 21323 42230 21371 42230 21370 42230 21056 42231 21128 42231 21377 42231 21165 42232 21313 42232 21377 42232 9659 42233 9666 42233 21294 42233 9654 42234 21129 42234 21285 42234 9770 42235 21275 42235 21130 42235 21131 42236 21132 42236 20980 42236 20974 42237 21156 42237 20975 42237 20960 42238 20958 42238 21097 42238 21235 42239 21230 42239 20957 42239 21133 42240 20935 42240 20934 42240 21344 42241 21134 42241 21135 42241 21135 42242 21134 42242 21136 42242 21134 42243 9763 42243 21136 42243 21136 42244 9763 42244 21137 42244 21136 42245 21137 42245 9760 42245 21138 42246 20918 42246 9766 42246 9766 42247 20918 42247 20917 42247 21196 42248 21346 42248 21139 42248 21139 42249 21140 42249 20917 42249 20917 42250 21140 42250 20860 42250 20917 42251 20860 42251 9766 42251 21123 42252 9753 42252 21145 42252 21332 42253 9759 42253 9714 42253 9714 42254 9759 42254 9757 42254 9714 42255 9757 42255 21141 42255 21141 42256 9757 42256 21142 42256 21141 42257 21142 42257 9716 42257 9716 42258 21142 42258 9755 42258 9716 42259 9755 42259 21336 42259 20865 42260 21021 42260 21143 42260 21143 42261 21021 42261 21020 42261 21143 42262 21020 42262 21144 42262 21144 42263 21020 42263 21018 42263 21123 42264 21145 42264 21122 42264 21122 42265 21145 42265 21146 42265 21122 42266 21146 42266 9637 42266 9637 42267 21146 42267 21147 42267 9637 42268 21147 42268 21339 42268 21148 42269 21369 42269 9749 42269 9749 42270 21149 42270 21148 42270 21148 42271 21149 42271 21150 42271 21148 42272 21150 42272 21330 42272 21150 42273 20867 42273 21330 42273 21330 42274 20867 42274 21151 42274 21330 42275 21151 42275 21329 42275 9750 42276 21173 42276 21152 42276 21152 42277 21173 42277 21175 42277 21152 42278 21175 42278 9752 42278 21155 42279 20872 42279 21175 42279 21175 42280 20872 42280 20875 42280 21175 42281 20875 42281 9752 42281 21151 42282 21153 42282 21329 42282 21329 42283 21153 42283 21154 42283 21329 42284 21154 42284 21155 42284 21155 42285 21154 42285 20871 42285 21155 42286 20871 42286 20872 42286 21164 42287 20885 42287 21074 42287 21074 42288 20885 42288 20884 42288 21156 42289 21157 42289 21158 42289 20975 42290 21156 42290 20976 42290 21311 42291 21159 42291 21156 42291 21156 42292 21159 42292 21160 42292 21156 42293 21160 42293 21157 42293 20978 42294 21162 42294 21131 42294 21131 42295 21162 42295 21161 42295 21131 42296 21161 42296 21132 42296 20978 42297 20976 42297 21162 42297 21162 42298 20976 42298 21156 42298 21162 42299 21156 42299 21163 42299 21163 42300 21156 42300 21158 42300 21163 42301 21158 42301 21164 42301 21164 42302 21158 42302 20886 42302 21164 42303 20886 42303 20885 42303 21165 42304 21309 42304 9740 42304 9740 42305 9738 42305 21165 42305 21165 42306 9738 42306 21166 42306 21165 42307 21166 42307 21313 42307 21313 42308 21166 42308 9735 42308 21313 42309 9735 42309 21311 42309 21311 42310 9735 42310 9734 42310 21311 42311 9734 42311 21159 42311 21167 42312 21168 42312 20888 42312 20888 42313 21168 42313 21170 42313 20905 42314 21183 42314 20904 42314 20904 42315 21183 42315 21168 42315 20904 42316 21168 42316 21169 42316 21169 42317 21168 42317 21167 42317 21335 42318 20891 42318 21204 42318 21204 42319 20891 42319 20889 42319 21204 42320 20889 42320 21170 42320 21170 42321 20889 42321 21171 42321 21170 42322 21171 42322 20888 42322 21039 42323 21037 42323 21126 42323 21045 42324 9713 42324 21173 42324 21036 42325 21035 42325 21327 42325 21327 42326 21035 42326 21172 42326 21327 42327 21172 42327 21041 42327 21180 42328 21181 42328 9709 42328 9709 42329 21181 42329 21175 42329 9713 42330 9712 42330 21173 42330 21173 42331 9712 42331 21174 42331 21173 42332 21174 42332 21175 42332 21175 42333 21174 42333 9708 42333 21175 42334 9708 42334 9709 42334 21043 42335 21176 42335 21177 42335 21177 42336 21176 42336 21045 42336 21177 42337 21045 42337 21178 42337 21178 42338 21045 42338 21173 42338 21178 42339 21173 42339 21369 42339 21369 42340 21173 42340 9750 42340 21369 42341 9750 42341 9749 42341 21179 42342 21181 42342 21189 42342 21189 42343 21181 42343 20996 42343 21180 42344 21039 42344 21181 42344 21181 42345 21039 42345 21126 42345 21181 42346 21126 42346 20996 42346 20996 42347 21126 42347 21125 42347 20996 42348 21125 42348 20997 42348 20997 42349 21125 42349 9700 42349 20997 42350 9700 42350 21182 42350 21182 42351 9700 42351 9699 42351 21182 42352 9699 42352 20998 42352 20905 42353 9733 42353 21183 42353 21183 42354 9733 42354 21185 42354 21183 42355 21185 42355 21184 42355 21184 42356 21185 42356 20902 42356 21184 42357 20902 42357 21186 42357 21186 42358 20902 42358 20900 42358 21186 42359 20900 42359 21187 42359 21187 42360 20900 42360 21188 42360 21187 42361 21188 42361 21189 42361 21189 42362 21188 42362 20898 42362 21189 42363 20898 42363 21179 42363 21212 42364 21190 42364 20910 42364 21213 42365 21201 42365 21214 42365 20910 42366 21190 42366 20911 42366 20911 42367 21190 42367 20944 42367 20911 42368 20944 42368 21191 42368 21191 42369 20944 42369 21192 42369 21191 42370 21192 42370 20913 42370 20913 42371 21192 42371 21208 42371 20913 42372 21208 42372 21193 42372 21193 42373 21208 42373 21194 42373 21193 42374 21194 42374 20916 42374 21197 42375 21359 42375 21196 42375 21139 42376 20917 42376 21196 42376 21196 42377 20917 42377 21195 42377 21196 42378 21195 42378 21197 42378 21204 42379 20924 42379 20923 42379 20918 42380 21198 42380 20920 42380 20920 42381 21198 42381 21023 42381 20920 42382 21023 42382 20921 42382 20921 42383 21023 42383 21199 42383 20921 42384 21199 42384 20923 42384 21202 42385 21168 42385 20930 42385 20930 42386 21168 42386 21214 42386 20930 42387 21214 42387 21200 42387 21200 42388 21214 42388 21201 42388 21202 42389 20927 42389 21168 42389 21168 42390 20927 42390 20926 42390 21168 42391 20926 42391 21170 42391 21170 42392 20926 42392 21203 42392 21170 42393 21203 42393 21204 42393 21204 42394 21203 42394 21205 42394 21204 42395 21205 42395 20924 42395 21273 42396 21292 42396 21206 42396 21206 42397 21292 42397 21291 42397 21206 42398 21291 42398 21289 42398 21208 42399 21209 42399 21194 42399 21194 42400 21209 42400 21207 42400 21194 42401 21207 42401 21353 42401 21208 42402 20943 42402 21209 42402 21209 42403 20943 42403 20942 42403 21209 42404 20942 42404 21210 42404 21210 42405 20942 42405 20940 42405 21210 42406 20940 42406 21211 42406 21211 42407 20940 42407 20938 42407 21211 42408 20938 42408 21115 42408 20910 42409 21213 42409 21212 42409 21212 42410 21213 42410 21214 42410 21212 42411 21214 42411 21215 42411 21215 42412 21214 42412 20947 42412 21357 42413 20949 42413 21216 42413 20964 42414 21217 42414 21357 42414 21357 42415 21217 42415 21218 42415 21357 42416 21218 42416 20949 42416 20964 42417 20966 42417 21217 42417 21217 42418 20966 42418 21219 42418 21217 42419 21219 42419 20934 42419 20934 42420 21219 42420 21237 42420 20934 42421 21237 42421 21133 42421 20970 42422 21220 42422 21258 42422 20970 42423 21258 42423 20951 42423 20951 42424 21258 42424 20952 42424 20952 42425 21258 42425 21252 42425 20952 42426 21252 42426 20953 42426 20953 42427 21252 42427 20954 42427 20954 42428 21252 42428 21301 42428 20954 42429 21301 42429 21221 42429 21301 42430 21095 42430 21093 42430 21093 42431 21091 42431 21301 42431 21301 42432 21091 42432 21086 42432 21301 42433 21086 42433 21221 42433 21221 42434 21086 42434 21088 42434 21221 42435 21088 42435 9729 42435 9729 42436 21088 42436 20956 42436 9672 42437 9673 42437 21224 42437 9673 42438 9675 42438 21224 42438 21224 42439 9675 42439 9677 42439 21224 42440 9677 42440 9617 42440 21222 42441 21223 42441 9669 42441 9669 42442 21223 42442 20956 42442 9669 42443 20956 42443 21084 42443 21084 42444 20956 42444 21088 42444 9619 42445 21227 42445 20843 42445 9619 42446 20843 42446 21224 42446 21224 42447 20843 42447 21225 42447 21224 42448 21225 42448 21226 42448 21226 42449 21231 42449 21224 42449 21224 42450 21231 42450 21223 42450 21224 42451 21223 42451 9672 42451 9672 42452 21223 42452 21222 42452 21227 42453 9619 42453 21228 42453 21228 42454 9619 42454 21229 42454 21228 42455 21229 42455 20846 42455 20846 42456 21229 42456 21230 42456 20846 42457 21230 42457 21236 42457 21231 42458 21232 42458 21223 42458 21223 42459 21232 42459 9786 42459 21223 42460 9786 42460 21233 42460 21233 42461 9786 42461 21234 42461 21233 42462 21234 42462 21235 42462 21235 42463 21234 42463 9783 42463 21235 42464 9783 42464 21230 42464 21230 42465 9783 42465 20847 42465 21230 42466 20847 42466 21236 42466 21097 42467 20958 42467 21098 42467 21237 42468 20963 42468 21133 42468 21133 42469 20963 42469 20962 42469 21133 42470 20962 42470 21292 42470 21292 42471 20962 42471 20960 42471 21292 42472 20960 42472 9662 42472 9662 42473 20960 42473 21097 42473 21259 42474 20969 42474 21357 42474 21357 42475 20969 42475 20967 42475 21357 42476 20967 42476 20964 42476 21001 42477 21261 42477 21267 42477 21238 42478 20995 42478 21356 42478 20838 42479 20836 42479 21248 42479 21248 42480 20836 42480 20833 42480 21248 42481 20833 42481 21383 42481 21132 42482 21307 42482 21239 42482 21239 42483 21307 42483 9791 42483 20840 42484 21250 42484 21240 42484 21240 42485 21250 42485 20981 42485 21240 42486 20981 42486 21241 42486 21241 42487 20981 42487 20980 42487 21241 42488 20980 42488 21242 42488 21242 42489 20980 42489 21132 42489 21242 42490 21132 42490 9789 42490 9789 42491 21132 42491 21239 42491 20833 42492 21243 42492 21383 42492 21383 42493 21243 42493 9793 42493 21383 42494 9793 42494 21307 42494 21307 42495 9793 42495 21244 42495 21307 42496 21244 42496 9791 42496 21245 42497 21246 42497 21248 42497 21248 42498 21246 42498 21247 42498 21248 42499 21247 42499 21079 42499 20840 42500 20838 42500 21250 42500 21250 42501 20838 42501 21248 42501 21250 42502 21248 42502 21249 42502 21249 42503 21248 42503 21079 42503 21249 42504 21251 42504 21250 42504 21250 42505 21251 42505 21083 42505 21250 42506 21083 42506 20983 42506 9728 42507 9727 42507 21252 42507 21252 42508 9727 42508 21256 42508 21252 42509 21256 42509 21301 42509 21301 42510 21256 42510 21253 42510 21301 42511 21253 42511 9681 42511 21083 42512 9685 42512 20983 42512 20983 42513 9685 42513 21255 42513 20983 42514 21255 42514 21254 42514 21254 42515 21255 42515 21256 42515 21254 42516 21256 42516 9726 42516 9726 42517 21256 42517 9727 42517 21258 42518 20991 42518 21257 42518 21257 42519 20989 42519 21258 42519 21258 42520 20989 42520 20987 42520 21258 42521 20987 42521 21252 42521 21252 42522 20987 42522 20986 42522 21252 42523 20986 42523 9728 42523 21220 42524 20969 42524 21258 42524 21258 42525 20969 42525 21259 42525 21258 42526 21259 42526 20991 42526 20991 42527 21259 42527 21356 42527 20991 42528 21356 42528 20993 42528 20993 42529 21356 42529 20995 42529 21266 42530 9697 42530 21260 42530 21260 42531 9697 42531 9696 42531 21260 42532 9696 42532 9695 42532 21267 42533 21261 42533 20974 42533 20974 42534 21261 42534 21262 42534 20974 42535 21262 42535 21156 42535 21156 42536 21262 42536 21263 42536 21156 42537 21263 42537 21310 42537 21310 42538 21264 42538 9693 42538 9693 42539 21264 42539 21265 42539 9693 42540 21265 42540 9695 42540 9695 42541 21265 42541 20999 42541 9695 42542 20999 42542 21260 42542 21260 42543 20999 42543 20998 42543 21260 42544 20998 42544 21266 42544 21267 42545 21238 42545 21001 42545 21001 42546 21238 42546 21356 42546 21001 42547 21356 42547 21004 42547 21004 42548 21356 42548 21355 42548 21184 42549 21008 42549 21183 42549 21183 42550 21008 42550 21268 42550 21183 42551 21268 42551 21006 42551 9627 42552 9651 42552 21269 42552 21269 42553 9651 42553 21270 42553 21269 42554 21270 42554 21279 42554 9629 42555 21269 42555 21277 42555 21276 42556 21271 42556 21115 42556 20935 42557 21133 42557 9730 42557 9730 42558 21133 42558 21292 42558 9730 42559 21292 42559 21272 42559 21272 42560 21292 42560 21273 42560 21272 42561 21273 42561 21274 42561 21274 42562 21273 42562 21110 42562 21274 42563 21110 42563 20936 42563 20936 42564 21110 42564 21105 42564 20936 42565 21105 42565 20938 42565 20938 42566 21105 42566 21130 42566 20938 42567 21130 42567 21115 42567 21115 42568 21130 42568 21275 42568 21115 42569 21275 42569 21276 42569 21277 42570 21269 42570 21278 42570 21278 42571 21269 42571 21279 42571 21278 42572 21279 42572 21271 42572 21271 42573 21279 42573 9653 42573 21271 42574 9653 42574 21115 42574 20854 42575 21285 42575 20856 42575 20856 42576 21285 42576 9626 42576 20856 42577 9626 42577 20858 42577 20858 42578 9626 42578 9629 42578 20858 42579 9629 42579 21280 42579 21280 42580 9629 42580 21277 42580 9770 42581 21130 42581 9772 42581 9772 42582 21130 42582 21281 42582 9772 42583 21281 42583 21282 42583 21282 42584 21281 42584 21283 42584 21282 42585 21283 42585 20854 42585 20854 42586 21283 42586 21285 42586 21285 42587 21283 42587 21284 42587 21285 42588 21284 42588 9654 42588 21288 42589 21286 42589 21287 42589 21287 42590 21286 42590 9656 42590 9773 42591 20853 42591 21291 42591 21288 42592 21289 42592 21286 42592 21286 42593 21289 42593 21291 42593 21286 42594 21291 42594 21290 42594 21290 42595 21291 42595 20853 42595 21290 42596 20853 42596 20852 42596 9773 42597 21291 42597 9774 42597 9774 42598 21291 42598 21292 42598 9774 42599 21292 42599 9775 42599 20852 42600 21293 42600 21290 42600 21290 42601 21293 42601 20851 42601 21290 42602 20851 42602 9623 42602 9623 42603 20851 42603 20849 42603 9623 42604 20849 42604 21294 42604 21294 42605 20849 42605 9782 42605 9782 42606 9780 42606 9660 42606 9660 42607 9780 42607 21295 42607 21295 42608 9780 42608 9778 42608 21295 42609 9778 42609 9662 42609 9662 42610 9778 42610 21296 42610 9662 42611 21296 42611 21292 42611 21292 42612 21296 42612 9777 42612 21292 42613 9777 42613 9775 42613 9782 42614 9660 42614 21294 42614 21294 42615 9660 42615 21297 42615 21294 42616 21297 42616 9659 42616 20958 42617 20957 42617 21098 42617 21098 42618 20957 42618 21230 42618 21098 42619 21230 42619 21099 42619 21099 42620 21230 42620 21229 42620 21099 42621 21229 42621 21298 42621 9667 42622 21299 42622 9621 42622 9621 42623 21299 42623 21102 42623 9621 42624 21102 42624 21229 42624 21229 42625 21102 42625 21101 42625 21229 42626 21101 42626 21298 42626 21095 42627 21301 42627 21096 42627 21096 42628 21301 42628 21300 42628 21096 42629 21300 42629 9618 42629 21384 42630 21385 42630 21077 42630 21077 42631 21385 42631 21301 42631 21077 42632 21301 42632 9680 42632 9680 42633 21301 42633 9681 42633 21308 42634 21067 42634 21307 42634 21307 42635 21067 42635 21302 42635 21302 42636 21067 42636 21303 42636 21302 42637 21303 42637 21304 42637 21161 42638 21305 42638 21132 42638 21132 42639 21305 42639 21306 42639 21132 42640 21306 42640 21307 42640 21307 42641 21306 42641 9687 42641 21307 42642 9687 42642 21308 42642 20884 42643 9741 42643 21074 42643 21074 42644 9741 42644 9740 42644 21074 42645 9740 42645 21073 42645 21073 42646 9740 42646 21309 42646 21073 42647 21309 42647 21070 42647 21070 42648 21309 42648 21378 42648 21310 42649 9693 42649 21156 42649 21156 42650 9693 42650 9691 42650 21156 42651 9691 42651 21311 42651 21311 42652 9691 42652 21312 42652 21311 42653 21312 42653 21313 42653 21313 42654 21312 42654 21058 42654 21313 42655 21058 42655 21377 42655 21377 42656 21058 42656 21057 42656 21377 42657 21057 42657 21056 42657 21314 42658 20877 42658 9697 42658 21319 42659 21317 42659 20879 42659 9746 42660 9745 42660 21315 42660 21315 42661 9745 42661 21316 42661 21315 42662 21316 42662 21374 42662 21374 42663 21316 42663 9743 42663 21374 42664 9743 42664 21370 42664 21370 42665 9743 42665 21318 42665 21317 42666 21319 42666 20881 42666 20881 42667 21319 42667 21049 42667 20881 42668 21049 42668 9742 42668 9742 42669 21049 42669 21046 42669 9742 42670 21046 42670 21318 42670 20998 42671 9699 42671 21266 42671 21266 42672 9699 42672 21319 42672 21266 42673 21319 42673 9697 42673 9697 42674 21319 42674 20879 42674 9697 42675 20879 42675 21314 42675 9746 42676 21315 42676 21320 42676 21320 42677 21315 42677 21322 42677 21320 42678 21322 42678 20876 42678 20876 42679 21322 42679 21321 42679 20876 42680 21321 42680 20877 42680 20877 42681 21321 42681 21066 42681 20877 42682 21066 42682 9697 42682 21375 42683 21062 42683 21322 42683 21322 42684 21062 42684 21063 42684 21322 42685 21063 42685 21321 42685 21318 42686 21046 42686 21370 42686 21370 42687 21046 42687 21050 42687 21370 42688 21050 42688 21323 42688 21326 42689 21324 42689 21127 42689 21127 42690 21324 42690 9704 42690 21127 42691 9704 42691 21125 42691 21373 42692 21051 42692 21325 42692 21325 42693 21326 42693 21373 42693 21373 42694 21326 42694 21127 42694 21373 42695 21127 42695 21327 42695 21327 42696 21127 42696 21126 42696 21327 42697 21126 42697 21036 42697 21036 42698 21126 42698 21037 42698 20893 42699 21334 42699 20894 42699 20894 42700 21334 42700 21328 42700 20894 42701 21328 42701 21155 42701 21155 42702 21328 42702 21029 42702 21155 42703 21029 42703 21329 42703 21329 42704 21029 42704 21028 42704 21329 42705 21028 42705 21330 42705 21330 42706 21028 42706 21026 42706 21330 42707 21026 42707 21331 42707 21331 42708 21026 42708 21034 42708 21331 42709 21034 42709 21124 42709 21332 42710 9714 42710 21333 42710 21333 42711 9714 42711 21334 42711 21333 42712 21334 42712 21204 42712 21204 42713 21334 42713 20893 42713 21204 42714 20893 42714 21335 42714 9755 42715 9753 42715 21336 42715 21336 42716 9753 42716 21123 42716 21336 42717 21123 42717 9719 42717 9719 42718 21123 42718 21364 42718 9719 42719 21364 42719 21031 42719 21031 42720 21364 42720 21366 42720 21031 42721 21366 42721 21368 42721 9635 42722 9634 42722 21337 42722 21337 42723 9634 42723 9638 42723 21337 42724 9638 42724 21338 42724 21338 42725 9638 42725 9637 42725 21338 42726 9637 42726 21018 42726 21018 42727 9637 42727 21339 42727 21018 42728 21339 42728 21144 42728 20923 42729 21199 42729 21204 42729 21204 42730 21199 42730 21021 42730 21204 42731 21021 42731 21333 42731 21333 42732 21021 42732 20865 42732 21333 42733 20865 42733 21332 42733 21340 42734 21342 42734 21341 42734 21341 42735 21342 42735 9636 42735 21340 42736 21343 42736 21342 42736 21342 42737 21343 42737 21136 42737 21342 42738 21136 42738 9630 42738 9630 42739 21136 42739 9760 42739 9630 42740 9760 42740 21345 42740 21138 42741 21344 42741 20918 42741 20918 42742 21344 42742 21135 42742 20918 42743 21135 42743 21198 42743 21198 42744 21135 42744 21136 42744 21198 42745 21136 42745 9721 42745 9721 42746 21136 42746 21343 42746 21345 42747 20863 42747 9630 42747 9630 42748 20863 42748 21346 42748 9630 42749 21346 42749 9631 42749 9631 42750 21346 42750 21196 42750 9631 42751 21196 42751 9633 42751 9633 42752 21196 42752 21359 42752 9633 42753 21359 42753 21347 42753 21347 42754 21359 42754 9640 42754 21347 42755 9640 42755 9613 42755 9613 42756 9640 42756 21348 42756 9613 42757 21348 42757 9639 42757 9641 42758 9642 42758 21349 42758 21349 42759 9642 42759 9643 42759 21349 42760 9643 42760 21353 42760 9643 42761 9647 42761 21353 42761 21353 42762 9647 42762 21350 42762 21353 42763 21350 42763 21194 42763 21194 42764 21350 42764 21351 42764 21194 42765 21351 42765 20916 42765 20916 42766 21351 42766 21352 42766 20916 42767 21352 42767 20917 42767 20917 42768 21352 42768 21360 42768 20917 42769 21360 42769 21195 42769 21207 42770 21113 42770 21353 42770 21353 42771 21113 42771 21112 42771 21353 42772 21112 42772 9614 42772 9614 42773 21112 42773 21354 42773 9614 42774 21354 42774 21119 42774 21006 42775 21355 42775 21183 42775 21183 42776 21355 42776 21356 42776 21183 42777 21356 42777 21168 42777 21168 42778 21356 42778 21259 42778 21168 42779 21259 42779 21214 42779 21214 42780 21259 42780 21357 42780 21214 42781 21357 42781 20947 42781 20947 42782 21357 42782 21216 42782 21358 42783 9640 42783 21359 42783 21358 42784 21359 42784 21011 42784 21011 42785 21359 42785 21197 42785 21011 42786 21197 42786 21013 42786 21013 42787 21197 42787 21195 42787 21013 42788 21195 42788 21015 42788 21015 42789 21195 42789 21360 42789 21015 42790 21360 42790 21361 42790 21361 42791 21360 42791 21352 42791 21361 42792 21352 42792 21362 42792 21362 42793 21352 42793 21351 42793 21362 42794 21351 42794 9648 42794 21121 42795 21363 42795 21123 42795 21123 42796 21363 42796 21365 42796 21123 42797 21365 42797 21364 42797 21364 42798 21365 42798 21366 42798 10175 42799 21331 42799 21367 42799 10175 42800 21367 42800 21365 42800 21365 42801 21367 42801 21368 42801 21365 42802 21368 42802 21366 42802 21177 42803 21178 42803 10172 42803 10172 42804 21178 42804 21369 42804 10172 42805 21369 42805 10175 42805 10175 42806 21369 42806 21148 42806 10175 42807 21148 42807 21331 42807 21372 42808 21327 42808 10171 42808 10171 42809 21327 42809 21041 42809 10171 42810 21041 42810 10172 42810 10172 42811 21041 42811 21043 42811 10172 42812 21043 42812 21177 42812 21052 42813 21051 42813 21373 42813 21370 42814 21371 42814 10169 42814 10169 42815 21371 42815 21052 42815 10169 42816 21052 42816 21372 42816 21372 42817 21052 42817 21373 42817 21372 42818 21373 42818 21327 42818 21370 42819 10169 42819 21374 42819 21374 42820 10169 42820 21376 42820 21374 42821 21376 42821 21315 42821 21377 42822 21128 42822 10168 42822 10168 42823 21128 42823 21375 42823 10168 42824 21375 42824 21376 42824 21376 42825 21375 42825 21322 42825 21376 42826 21322 42826 21315 42826 21377 42827 10168 42827 21165 42827 21165 42828 10168 42828 21379 42828 21165 42829 21379 42829 21309 42829 21309 42830 21379 42830 21378 42830 21378 42831 21379 42831 21380 42831 21378 42832 21380 42832 21304 42832 21382 42833 21307 42833 21380 42833 21380 42834 21307 42834 21302 42834 21380 42835 21302 42835 21304 42835 21384 42836 21245 42836 21381 42836 21381 42837 21245 42837 21248 42837 21381 42838 21248 42838 21382 42838 21382 42839 21248 42839 21383 42839 21382 42840 21383 42840 21307 42840 21384 42841 21381 42841 21385 42841 21385 42842 21381 42842 20115 42842 21385 42843 20115 42843 21301 42843 13568 42844 13569 42844 21386 42844 21386 42845 13569 42845 13374 42845 21386 42846 13374 42846 13376 42846 13376 42847 13377 42847 21386 42847 21386 42848 13377 42848 21387 42848 21386 42849 21387 42849 13378 42849 13380 42850 21388 42850 21390 42850 13378 42851 21389 42851 21386 42851 21386 42852 21389 42852 13380 42852 21386 42853 13380 42853 13567 42853 13567 42854 13380 42854 21390 42854 21392 42855 13384 42855 21393 42855 13381 42856 13389 42856 13387 42856 13557 42857 13555 42857 13559 42857 13559 42858 13555 42858 13552 42858 13559 42859 13552 42859 13558 42859 13558 42860 13552 42860 21391 42860 13387 42861 21392 42861 13381 42861 13381 42862 21392 42862 21393 42862 13381 42863 21393 42863 13555 42863 13555 42864 21393 42864 13382 42864 13555 42865 13382 42865 13552 42865 13391 42866 21394 42866 21397 42866 21400 42867 13550 42867 21399 42867 13391 42868 21397 42868 13392 42868 21394 42869 13396 42869 21397 42869 21397 42870 13396 42870 21395 42870 21397 42871 21395 42871 13393 42871 13392 42872 21397 42872 21396 42872 21396 42873 21397 42873 21398 42873 21396 42874 21398 42874 21399 42874 21399 42875 21398 42875 13547 42875 21399 42876 13547 42876 21400 42876 13543 42877 13545 42877 21402 42877 21402 42878 13545 42878 13404 42878 21402 42879 13404 42879 21401 42879 21401 42880 13403 42880 21402 42880 21402 42881 13403 42881 13402 42881 21402 42882 13402 42882 21403 42882 21404 42883 13541 42883 21405 42883 21403 42884 21406 42884 21402 42884 21402 42885 21406 42885 21404 42885 21402 42886 21404 42886 13542 42886 13542 42887 21404 42887 21405 42887 13534 42888 13535 42888 21407 42888 13535 42889 21408 42889 21407 42889 21407 42890 21408 42890 13536 42890 21407 42891 13536 42891 13538 42891 13411 42892 13413 42892 21407 42892 21407 42893 13413 42893 13414 42893 21407 42894 13414 42894 13534 42894 13406 42895 13408 42895 13539 42895 13539 42896 13408 42896 21407 42896 13539 42897 21407 42897 21409 42897 21409 42898 21407 42898 13538 42898 13527 42899 13525 42899 13421 42899 13531 42900 13529 42900 21411 42900 21411 42901 13529 42901 13530 42901 21410 42902 21413 42902 13421 42902 13421 42903 21413 42903 21411 42903 13421 42904 21411 42904 13527 42904 13527 42905 21411 42905 13530 42905 13527 42906 13530 42906 21412 42906 21410 42907 13419 42907 21413 42907 21413 42908 13419 42908 13417 42908 21413 42909 13417 42909 13416 42909 21414 42910 13521 42910 21415 42910 21417 42911 13517 42911 13518 42911 13427 42912 21417 42912 21416 42912 21416 42913 21417 42913 21414 42913 21416 42914 21414 42914 13424 42914 13424 42915 21414 42915 21415 42915 13520 42916 21414 42916 13519 42916 13519 42917 21414 42917 21417 42917 13519 42918 21417 42918 21418 42918 21418 42919 21417 42919 13518 42919 13516 42920 13511 42920 13508 42920 13435 42921 13503 42921 21419 42921 21419 42922 13503 42922 13513 42922 13506 42923 13505 42923 13508 42923 13508 42924 13505 42924 13430 42924 13513 42925 13516 42925 21419 42925 21419 42926 13516 42926 13508 42926 21419 42927 13508 42927 21420 42927 21420 42928 13508 42928 13430 42928 21420 42929 13430 42929 13432 42929 21422 42930 13439 42930 13445 42930 21421 42931 13497 42931 13500 42931 21422 42932 13445 42932 13437 42932 13439 42933 21423 42933 13445 42933 13445 42934 21423 42934 13441 42934 13445 42935 13441 42935 13444 42935 13437 42936 13445 42936 21424 42936 21424 42937 13445 42937 13446 42937 21424 42938 13446 42938 13500 42938 13500 42939 13446 42939 13495 42939 13500 42940 13495 42940 21421 42940 21426 42941 13455 42941 13457 42941 21426 42942 13448 42942 13450 42942 13491 42943 13489 42943 21425 42943 21425 42944 13489 42944 21426 42944 21425 42945 21426 42945 13486 42945 13486 42946 21426 42946 13457 42946 13453 42947 13455 42947 13452 42947 13452 42948 13455 42948 21426 42948 13452 42949 21426 42949 13451 42949 13451 42950 21426 42950 13450 42950 21433 42951 21427 42951 21432 42951 21428 42952 21432 42952 13460 42952 21428 42953 13485 42953 13482 42953 21429 42954 13461 42954 21430 42954 21430 42955 13461 42955 21428 42955 21430 42956 21428 42956 21431 42956 21431 42957 21428 42957 13460 42957 21432 42958 21428 42958 21433 42958 21433 42959 21428 42959 13482 42959 21433 42960 13482 42960 13481 42960 13480 42961 21434 42961 21435 42961 21434 42962 13464 42962 13466 42962 13478 42963 13480 42963 13476 42963 13476 42964 13480 42964 21435 42964 13476 42965 21435 42965 13475 42965 13475 42966 21435 42966 13472 42966 13471 42967 21435 42967 13470 42967 13470 42968 21435 42968 21434 42968 13470 42969 21434 42969 13469 42969 13469 42970 21434 42970 13466 42970 13469 42971 13466 42971 13467 42971 21436 42972 21437 42972 21441 42972 21442 42973 21437 42973 21436 42973 21443 42974 21442 42974 21436 42974 21436 42975 21438 42975 21445 42975 21439 42976 21438 42976 21436 42976 21441 42977 21439 42977 21436 42977 21440 42978 21445 42978 21443 42978 21443 42979 21445 42979 21438 42979 21437 42980 21442 42980 21441 42980 21441 42981 21442 42981 21443 42981 21441 42982 21443 42982 21439 42982 21439 42983 21443 42983 21438 42983 21446 42984 21444 42984 21447 42984 21447 42985 21444 42985 21445 42985 21447 42986 21445 42986 21448 42986 21448 42987 21445 42987 21440 42987 21436 42988 21446 42988 21447 42988 21444 42989 21446 42989 21436 42989 21445 42990 21444 42990 21436 42990 21436 42991 21440 42991 21443 42991 21448 42992 21440 42992 21436 42992 21447 42993 21448 42993 21436 42993 21458 42994 21456 42994 21455 42994 21451 42995 21456 42995 21458 42995 21452 42996 21451 42996 21458 42996 21458 42997 21450 42997 21459 42997 21449 42998 21450 42998 21458 42998 21455 42999 21449 42999 21458 42999 21451 43000 21452 43000 21457 43000 21460 43001 21459 43001 21453 43001 21453 43002 21459 43002 21450 43002 21453 43003 21450 43003 21461 43003 21461 43004 21450 43004 21454 43004 21455 43005 21456 43005 21449 43005 21449 43006 21456 43006 21451 43006 21449 43007 21451 43007 21450 43007 21450 43008 21451 43008 21457 43008 21450 43009 21457 43009 21454 43009 21458 43010 21453 43010 21461 43010 21460 43011 21453 43011 21458 43011 21459 43012 21460 43012 21458 43012 21458 43013 21457 43013 21452 43013 21454 43014 21457 43014 21458 43014 21461 43015 21454 43015 21458 43015 21467 43016 21464 43016 21469 43016 21469 43017 21464 43017 21463 43017 21462 43018 21463 43018 21465 43018 21465 43019 21463 43019 21464 43019 21465 43020 21464 43020 21466 43020 21466 43021 21464 43021 21467 43021 21462 43022 21465 43022 21468 43022 21468 43023 21465 43023 21466 43023 21466 43024 21467 43024 21468 43024 21468 43025 21467 43025 21469 43025 21468 43026 21469 43026 21462 43026 21462 43027 21469 43027 21463 43027 21476 43028 21470 43028 21471 43028 21471 43029 21470 43029 21472 43029 21476 43030 21473 43030 21470 43030 21470 43031 21473 43031 21474 43031 21477 43032 21474 43032 21475 43032 21475 43033 21474 43033 21473 43033 21475 43034 21473 43034 21471 43034 21471 43035 21473 43035 21476 43035 21470 43036 21474 43036 21472 43036 21472 43037 21474 43037 21477 43037 21472 43038 21477 43038 21471 43038 21471 43039 21477 43039 21475 43039 21478 43040 21479 43040 21485 43040 21485 43041 21479 43041 21480 43041 21479 43042 21482 43042 21480 43042 21480 43043 21482 43043 21481 43043 21481 43044 21482 43044 21484 43044 21484 43045 21482 43045 21483 43045 21485 43046 21484 43046 21478 43046 21478 43047 21484 43047 21483 43047 21478 43048 21483 43048 21479 43048 21479 43049 21483 43049 21482 43049 21481 43050 21484 43050 21480 43050 21480 43051 21484 43051 21485 43051 21489 43052 21487 43052 21486 43052 21486 43053 21487 43053 21491 43053 21491 43054 21493 43054 21486 43054 21486 43055 21493 43055 21488 43055 21486 43056 21488 43056 21489 43056 21489 43057 21488 43057 21490 43057 21493 43058 21492 43058 21488 43058 21488 43059 21492 43059 21490 43059 21489 43060 21490 43060 21487 43060 21487 43061 21490 43061 21492 43061 21487 43062 21492 43062 21491 43062 21491 43063 21492 43063 21493 43063 21494 43064 21501 43064 21495 43064 21495 43065 21501 43065 21496 43065 21495 43066 21496 43066 21498 43066 21498 43067 21496 43067 21500 43067 21494 43068 21495 43068 21497 43068 21497 43069 21495 43069 21498 43069 21498 43070 21500 43070 21497 43070 21497 43071 21500 43071 21499 43071 21497 43072 21499 43072 21494 43072 21494 43073 21499 43073 21501 43073 21500 43074 21496 43074 21499 43074 21499 43075 21496 43075 21501 43075 21506 43076 21508 43076 21504 43076 21504 43077 21508 43077 21502 43077 21503 43078 21509 43078 21507 43078 21507 43079 21509 43079 21505 43079 21507 43080 21505 43080 21504 43080 21504 43081 21505 43081 21506 43081 21502 43082 21503 43082 21504 43082 21504 43083 21503 43083 21507 43083 21502 43084 21508 43084 21503 43084 21503 43085 21508 43085 21509 43085 21505 43086 21509 43086 21506 43086 21506 43087 21509 43087 21508 43087 21515 43088 21514 43088 21510 43088 21510 43089 21514 43089 21512 43089 21510 43090 21512 43090 21511 43090 21511 43091 21512 43091 21516 43091 21517 43092 21514 43092 21513 43092 21513 43093 21514 43093 21515 43093 21510 43094 21511 43094 21515 43094 21515 43095 21511 43095 21513 43095 21511 43096 21516 43096 21513 43096 21513 43097 21516 43097 21517 43097 21517 43098 21516 43098 21514 43098 21514 43099 21516 43099 21512 43099 21523 43100 21518 43100 21519 43100 21519 43101 21518 43101 21520 43101 21519 43102 21520 43102 21521 43102 21521 43103 21520 43103 21522 43103 21523 43104 21519 43104 21525 43104 21525 43105 21519 43105 21521 43105 21522 43106 21520 43106 21524 43106 21524 43107 21520 43107 21518 43107 21518 43108 21523 43108 21524 43108 21524 43109 21523 43109 21525 43109 21524 43110 21525 43110 21522 43110 21522 43111 21525 43111 21521 43111 21528 43112 21536 43112 21526 43112 21528 43113 21530 43113 21532 43113 21531 43114 21530 43114 21528 43114 21526 43115 21531 43115 21528 43115 21528 43116 21527 43116 21533 43116 21529 43117 21527 43117 21528 43117 21532 43118 21529 43118 21528 43118 21535 43119 21539 43119 21534 43119 21530 43120 21531 43120 21532 43120 21532 43121 21531 43121 21534 43121 21532 43122 21534 43122 21529 43122 21537 43123 21533 43123 21534 43123 21534 43124 21533 43124 21527 43124 21534 43125 21527 43125 21529 43125 21538 43126 21535 43126 21536 43126 21536 43127 21535 43127 21534 43127 21536 43128 21534 43128 21526 43128 21526 43129 21534 43129 21531 43129 21528 43130 21534 43130 21539 43130 21537 43131 21534 43131 21528 43131 21533 43132 21537 43132 21528 43132 21528 43133 21538 43133 21536 43133 21535 43134 21538 43134 21528 43134 21539 43135 21535 43135 21528 43135 21552 43136 21540 43136 21545 43136 21542 43137 21540 43137 21552 43137 21548 43138 21542 43138 21552 43138 21552 43139 21544 43139 21543 43139 21541 43140 21544 43140 21552 43140 21545 43141 21541 43141 21552 43141 21547 43142 21549 43142 21542 43142 21542 43143 21549 43143 21543 43143 21542 43144 21543 43144 21544 43144 21544 43145 21541 43145 21542 43145 21542 43146 21541 43146 21545 43146 21542 43147 21545 43147 21540 43147 21551 43148 21547 43148 21546 43148 21546 43149 21547 43149 21542 43149 21546 43150 21542 43150 21550 43150 21550 43151 21542 43151 21548 43151 21552 43152 21547 43152 21551 43152 21549 43153 21547 43153 21552 43153 21543 43154 21549 43154 21552 43154 21552 43155 21550 43155 21548 43155 21546 43156 21550 43156 21552 43156 21551 43157 21546 43157 21552 43157 21568 43158 21553 43158 21554 43158 21554 43159 21553 43159 21567 43159 21557 43160 21555 43160 21558 43160 21556 43161 21568 43161 21558 43161 21558 43162 21568 43162 21554 43162 21558 43163 21554 43163 21557 43163 21557 43164 21554 43164 21560 43164 21561 43165 21569 43165 21563 43165 21558 43166 21555 43166 21559 43166 21559 43167 21555 43167 21566 43167 21559 43168 21566 43168 21565 43168 21560 43169 21554 43169 21561 43169 21560 43170 21561 43170 21562 43170 21562 43171 21561 43171 21563 43171 21562 43172 21563 43172 21566 43172 21566 43173 21563 43173 21564 43173 21566 43174 21564 43174 21565 43174 21560 43175 21562 43175 21557 43175 21557 43176 21562 43176 21566 43176 21557 43177 21566 43177 21555 43177 21553 43178 21569 43178 21567 43178 21567 43179 21569 43179 21561 43179 21556 43180 21559 43180 21568 43180 21568 43181 21559 43181 21565 43181 21559 43182 21556 43182 21558 43182 21553 43183 21568 43183 21565 43183 21564 43184 21563 43184 21565 43184 21565 43185 21563 43185 21569 43185 21565 43186 21569 43186 21553 43186 21561 43187 21554 43187 21567 43187 21574 43188 21570 43188 21575 43188 21575 43189 21570 43189 21571 43189 21572 43190 21577 43190 21573 43190 21584 43191 21574 43191 21573 43191 21573 43192 21574 43192 21575 43192 21573 43193 21575 43193 21572 43193 21572 43194 21575 43194 21579 43194 21576 43195 21581 43195 21586 43195 21573 43196 21577 43196 21582 43196 21582 43197 21577 43197 21578 43197 21582 43198 21578 43198 21583 43198 21579 43199 21575 43199 21576 43199 21579 43200 21576 43200 21580 43200 21580 43201 21576 43201 21586 43201 21580 43202 21586 43202 21578 43202 21578 43203 21586 43203 21585 43203 21578 43204 21585 43204 21583 43204 21578 43205 21577 43205 21580 43205 21580 43206 21577 43206 21572 43206 21580 43207 21572 43207 21579 43207 21570 43208 21581 43208 21571 43208 21571 43209 21581 43209 21576 43209 21584 43210 21582 43210 21574 43210 21574 43211 21582 43211 21583 43211 21582 43212 21584 43212 21573 43212 21570 43213 21574 43213 21583 43213 21585 43214 21586 43214 21583 43214 21583 43215 21586 43215 21581 43215 21583 43216 21581 43216 21570 43216 21576 43217 21575 43217 21571 43217 21587 43218 21589 43218 21588 43218 21588 43219 21589 43219 21590 43219 21589 43220 21587 43220 21594 43220 21592 43221 21588 43221 21590 43221 21600 43222 21599 43222 21590 43222 21590 43223 21599 43223 21591 43223 21590 43224 21591 43224 21592 43224 21596 43225 21593 43225 21603 43225 21588 43226 21592 43226 21593 43226 21593 43227 21592 43227 21603 43227 21595 43228 21597 43228 21594 43228 21587 43229 21588 43229 21594 43229 21594 43230 21588 43230 21593 43230 21594 43231 21593 43231 21595 43231 21595 43232 21593 43232 21602 43232 21596 43233 21591 43233 21599 43233 21594 43234 21597 43234 21589 43234 21589 43235 21597 43235 21598 43235 21589 43236 21598 43236 21590 43236 21602 43237 21593 43237 21596 43237 21602 43238 21596 43238 21601 43238 21601 43239 21596 43239 21599 43239 21601 43240 21599 43240 21598 43240 21598 43241 21599 43241 21600 43241 21598 43242 21600 43242 21590 43242 21598 43243 21597 43243 21601 43243 21601 43244 21597 43244 21595 43244 21601 43245 21595 43245 21602 43245 21592 43246 21591 43246 21603 43246 21603 43247 21591 43247 21596 43247 21618 43248 21617 43248 21605 43248 21605 43249 21617 43249 21604 43249 21615 43250 21614 43250 21607 43250 21616 43251 21618 43251 21607 43251 21607 43252 21618 43252 21605 43252 21607 43253 21605 43253 21615 43253 21615 43254 21605 43254 21610 43254 21609 43255 21606 43255 21620 43255 21607 43256 21614 43256 21608 43256 21608 43257 21614 43257 21611 43257 21608 43258 21611 43258 21619 43258 21610 43259 21605 43259 21609 43259 21610 43260 21609 43260 21613 43260 21613 43261 21609 43261 21620 43261 21613 43262 21620 43262 21611 43262 21611 43263 21620 43263 21612 43263 21611 43264 21612 43264 21619 43264 21611 43265 21614 43265 21613 43265 21613 43266 21614 43266 21615 43266 21613 43267 21615 43267 21610 43267 21617 43268 21606 43268 21604 43268 21604 43269 21606 43269 21609 43269 21616 43270 21608 43270 21618 43270 21618 43271 21608 43271 21619 43271 21608 43272 21616 43272 21607 43272 21617 43273 21618 43273 21619 43273 21612 43274 21620 43274 21619 43274 21619 43275 21620 43275 21606 43275 21619 43276 21606 43276 21617 43276 21609 43277 21605 43277 21604 43277 21625 43278 21624 43278 21622 43278 21622 43279 21624 43279 21621 43279 21622 43280 21621 43280 21630 43280 21635 43281 21637 43281 21624 43281 21624 43282 21637 43282 21623 43282 21624 43283 21623 43283 21621 43283 21621 43284 21623 43284 21633 43284 21634 43285 21632 43285 21636 43285 21624 43286 21625 43286 21626 43286 21626 43287 21625 43287 21631 43287 21626 43288 21631 43288 21629 43288 21630 43289 21621 43289 21634 43289 21630 43290 21634 43290 21627 43290 21627 43291 21634 43291 21636 43291 21627 43292 21636 43292 21631 43292 21631 43293 21636 43293 21628 43293 21631 43294 21628 43294 21629 43294 21630 43295 21627 43295 21622 43295 21622 43296 21627 43296 21631 43296 21622 43297 21631 43297 21625 43297 21623 43298 21632 43298 21633 43298 21633 43299 21632 43299 21634 43299 21635 43300 21626 43300 21637 43300 21637 43301 21626 43301 21629 43301 21626 43302 21635 43302 21624 43302 21628 43303 21636 43303 21629 43303 21629 43304 21636 43304 21632 43304 21629 43305 21632 43305 21637 43305 21637 43306 21632 43306 21623 43306 21634 43307 21621 43307 21633 43307 21638 43308 21650 43308 21642 43308 21642 43309 21650 43309 21654 43309 21649 43310 21648 43310 21653 43310 21652 43311 21638 43311 21653 43311 21653 43312 21638 43312 21642 43312 21653 43313 21642 43313 21649 43313 21649 43314 21642 43314 21641 43314 21643 43315 21639 43315 21644 43315 21653 43316 21648 43316 21651 43316 21651 43317 21648 43317 21647 43317 21651 43318 21647 43318 21640 43318 21641 43319 21642 43319 21643 43319 21641 43320 21643 43320 21645 43320 21645 43321 21643 43321 21644 43321 21645 43322 21644 43322 21647 43322 21647 43323 21644 43323 21646 43323 21647 43324 21646 43324 21640 43324 21647 43325 21648 43325 21645 43325 21645 43326 21648 43326 21649 43326 21645 43327 21649 43327 21641 43327 21650 43328 21639 43328 21654 43328 21654 43329 21639 43329 21643 43329 21652 43330 21651 43330 21638 43330 21638 43331 21651 43331 21640 43331 21651 43332 21652 43332 21653 43332 21650 43333 21638 43333 21640 43333 21646 43334 21644 43334 21640 43334 21640 43335 21644 43335 21639 43335 21640 43336 21639 43336 21650 43336 21643 43337 21642 43337 21654 43337 21655 43338 21658 43338 21664 43338 21664 43339 21658 43339 21656 43339 21664 43340 21656 43340 21657 43340 21668 43341 21669 43341 21658 43341 21658 43342 21669 43342 21665 43342 21658 43343 21665 43343 21656 43343 21656 43344 21665 43344 21671 43344 21667 43345 21666 43345 21660 43345 21658 43346 21655 43346 21659 43346 21659 43347 21655 43347 21661 43347 21659 43348 21661 43348 21670 43348 21657 43349 21656 43349 21667 43349 21657 43350 21667 43350 21663 43350 21663 43351 21667 43351 21660 43351 21663 43352 21660 43352 21661 43352 21661 43353 21660 43353 21662 43353 21661 43354 21662 43354 21670 43354 21661 43355 21655 43355 21663 43355 21663 43356 21655 43356 21664 43356 21663 43357 21664 43357 21657 43357 21665 43358 21666 43358 21671 43358 21671 43359 21666 43359 21667 43359 21668 43360 21659 43360 21669 43360 21669 43361 21659 43361 21670 43361 21659 43362 21668 43362 21658 43362 21665 43363 21669 43363 21670 43363 21662 43364 21660 43364 21670 43364 21670 43365 21660 43365 21666 43365 21670 43366 21666 43366 21665 43366 21667 43367 21656 43367 21671 43367 21673 43368 21672 43368 21676 43368 21676 43369 21672 43369 21675 43369 21672 43370 21673 43370 21674 43370 21682 43371 21681 43371 21675 43371 21675 43372 21681 43372 21688 43372 21675 43373 21688 43373 21676 43373 21676 43374 21688 43374 21677 43374 21678 43375 21680 43375 21687 43375 21686 43376 21674 43376 21684 43376 21684 43377 21674 43377 21680 43377 21684 43378 21680 43378 21679 43378 21673 43379 21676 43379 21674 43379 21674 43380 21676 43380 21677 43380 21674 43381 21677 43381 21680 43381 21680 43382 21677 43382 21687 43382 21678 43383 21688 43383 21681 43383 21674 43384 21686 43384 21672 43384 21672 43385 21686 43385 21685 43385 21672 43386 21685 43386 21675 43386 21679 43387 21680 43387 21678 43387 21679 43388 21678 43388 21683 43388 21683 43389 21678 43389 21681 43389 21683 43390 21681 43390 21685 43390 21685 43391 21681 43391 21682 43391 21685 43392 21682 43392 21675 43392 21679 43393 21683 43393 21684 43393 21684 43394 21683 43394 21685 43394 21684 43395 21685 43395 21686 43395 21677 43396 21688 43396 21687 43396 21687 43397 21688 43397 21678 43397 21694 43398 21693 43398 21699 43398 21699 43399 21693 43399 21692 43399 21699 43400 21692 43400 21689 43400 21690 43401 21704 43401 21693 43401 21693 43402 21704 43402 21691 43402 21693 43403 21691 43403 21692 43403 21692 43404 21691 43404 21705 43404 21702 43405 21701 43405 21697 43405 21693 43406 21694 43406 21703 43406 21703 43407 21694 43407 21700 43407 21703 43408 21700 43408 21695 43408 21689 43409 21692 43409 21702 43409 21689 43410 21702 43410 21696 43410 21696 43411 21702 43411 21697 43411 21696 43412 21697 43412 21700 43412 21700 43413 21697 43413 21698 43413 21700 43414 21698 43414 21695 43414 21689 43415 21696 43415 21699 43415 21699 43416 21696 43416 21700 43416 21699 43417 21700 43417 21694 43417 21691 43418 21701 43418 21705 43418 21705 43419 21701 43419 21702 43419 21690 43420 21703 43420 21704 43420 21704 43421 21703 43421 21695 43421 21703 43422 21690 43422 21693 43422 21691 43423 21704 43423 21695 43423 21698 43424 21697 43424 21695 43424 21695 43425 21697 43425 21701 43425 21695 43426 21701 43426 21691 43426 21702 43427 21692 43427 21705 43427 21706 43428 21713 43428 21707 43428 21707 43429 21713 43429 21716 43429 21709 43430 21708 43430 21711 43430 21711 43431 21708 43431 21718 43431 21708 43432 21709 43432 21712 43432 21706 43433 21711 43433 21718 43433 21717 43434 21710 43434 21718 43434 21718 43435 21710 43435 21713 43435 21718 43436 21713 43436 21706 43436 21716 43437 21715 43437 21707 43437 21711 43438 21706 43438 21715 43438 21715 43439 21706 43439 21707 43439 21720 43440 21714 43440 21712 43440 21709 43441 21711 43441 21712 43441 21712 43442 21711 43442 21715 43442 21712 43443 21715 43443 21720 43443 21720 43444 21715 43444 21719 43444 21716 43445 21713 43445 21710 43445 21712 43446 21714 43446 21708 43446 21708 43447 21714 43447 21722 43447 21708 43448 21722 43448 21718 43448 21719 43449 21715 43449 21716 43449 21719 43450 21716 43450 21721 43450 21721 43451 21716 43451 21710 43451 21721 43452 21710 43452 21722 43452 21722 43453 21710 43453 21717 43453 21722 43454 21717 43454 21718 43454 21719 43455 21721 43455 21720 43455 21720 43456 21721 43456 21722 43456 21720 43457 21722 43457 21714 43457 21729 43458 21724 43458 21723 43458 21723 43459 21724 43459 21727 43459 21723 43460 21727 43460 21733 43460 21725 43461 21726 43461 21724 43461 21724 43462 21726 43462 21738 43462 21724 43463 21738 43463 21727 43463 21727 43464 21738 43464 21734 43464 21739 43465 21737 43465 21728 43465 21724 43466 21729 43466 21735 43466 21735 43467 21729 43467 21731 43467 21735 43468 21731 43468 21736 43468 21733 43469 21727 43469 21739 43469 21733 43470 21739 43470 21730 43470 21730 43471 21739 43471 21728 43471 21730 43472 21728 43472 21731 43472 21731 43473 21728 43473 21732 43473 21731 43474 21732 43474 21736 43474 21733 43475 21730 43475 21723 43475 21723 43476 21730 43476 21731 43476 21723 43477 21731 43477 21729 43477 21738 43478 21737 43478 21734 43478 21734 43479 21737 43479 21739 43479 21725 43480 21735 43480 21726 43480 21726 43481 21735 43481 21736 43481 21735 43482 21725 43482 21724 43482 21732 43483 21728 43483 21736 43483 21736 43484 21728 43484 21737 43484 21736 43485 21737 43485 21726 43485 21726 43486 21737 43486 21738 43486 21739 43487 21727 43487 21734 43487 21742 43488 21753 43488 21748 43488 21748 43489 21753 43489 21756 43489 21748 43490 21756 43490 21744 43490 21750 43491 21751 43491 21753 43491 21753 43492 21751 43492 21740 43492 21753 43493 21740 43493 21756 43493 21756 43494 21740 43494 21741 43494 21755 43495 21749 43495 21746 43495 21753 43496 21742 43496 21752 43496 21752 43497 21742 43497 21743 43497 21752 43498 21743 43498 21754 43498 21744 43499 21756 43499 21755 43499 21744 43500 21755 43500 21745 43500 21745 43501 21755 43501 21746 43501 21745 43502 21746 43502 21743 43502 21743 43503 21746 43503 21747 43503 21743 43504 21747 43504 21754 43504 21743 43505 21742 43505 21745 43505 21745 43506 21742 43506 21748 43506 21745 43507 21748 43507 21744 43507 21740 43508 21749 43508 21741 43508 21741 43509 21749 43509 21755 43509 21750 43510 21752 43510 21751 43510 21751 43511 21752 43511 21754 43511 21752 43512 21750 43512 21753 43512 21740 43513 21751 43513 21754 43513 21747 43514 21746 43514 21754 43514 21754 43515 21746 43515 21749 43515 21754 43516 21749 43516 21740 43516 21755 43517 21756 43517 21741 43517 21761 43518 21757 43518 21758 43518 21768 43519 21757 43519 21761 43519 21769 43520 21768 43520 21761 43520 21761 43521 21763 43521 21764 43521 21759 43522 21763 43522 21761 43522 21758 43523 21759 43523 21761 43523 21761 43524 21760 43524 21767 43524 21766 43525 21760 43525 21761 43525 21764 43526 21766 43526 21761 43526 21761 43527 21765 43527 21769 43527 21762 43528 21765 43528 21761 43528 21767 43529 21762 43529 21761 43529 21763 43530 21769 43530 21764 43530 21764 43531 21769 43531 21765 43531 21760 43532 21766 43532 21767 43532 21767 43533 21766 43533 21764 43533 21767 43534 21764 43534 21762 43534 21762 43535 21764 43535 21765 43535 21757 43536 21768 43536 21758 43536 21758 43537 21768 43537 21769 43537 21758 43538 21769 43538 21759 43538 21759 43539 21769 43539 21763 43539 21770 43540 21771 43540 21772 43540 21776 43541 21771 43541 21770 43541 21773 43542 21776 43542 21770 43542 21770 43543 21775 43543 21778 43543 21774 43544 21775 43544 21770 43544 21772 43545 21774 43545 21770 43545 21776 43546 21773 43546 21781 43546 21779 43547 21778 43547 21777 43547 21777 43548 21778 43548 21775 43548 21777 43549 21775 43549 21782 43549 21782 43550 21775 43550 21780 43550 21772 43551 21771 43551 21774 43551 21774 43552 21771 43552 21776 43552 21774 43553 21776 43553 21775 43553 21775 43554 21776 43554 21781 43554 21775 43555 21781 43555 21780 43555 21770 43556 21777 43556 21782 43556 21779 43557 21777 43557 21770 43557 21778 43558 21779 43558 21770 43558 21770 43559 21781 43559 21773 43559 21780 43560 21781 43560 21770 43560 21782 43561 21780 43561 21770 43561 21789 43562 21793 43562 21790 43562 21790 43563 21793 43563 21783 43563 21790 43564 21783 43564 21788 43564 21788 43565 21783 43565 21792 43565 21788 43566 21792 43566 21784 43566 21784 43567 21792 43567 21796 43567 21784 43568 21796 43568 21785 43568 21785 43569 21796 43569 21786 43569 21785 43570 21786 43570 21791 43570 21791 43571 21786 43571 21795 43571 21791 43572 21795 43572 21787 43572 21787 43573 21795 43573 21797 43573 21799 43574 21788 43574 21784 43574 21790 43575 21788 43575 21799 43575 21789 43576 21790 43576 21799 43576 21799 43577 21791 43577 21787 43577 21785 43578 21791 43578 21799 43578 21784 43579 21785 43579 21799 43579 21792 43580 21783 43580 21796 43580 21796 43581 21783 43581 21793 43581 21807 43582 21806 43582 21793 43582 21793 43583 21806 43583 21794 43583 21793 43584 21794 43584 21798 43584 21786 43585 21796 43585 21795 43585 21795 43586 21796 43586 21793 43586 21795 43587 21793 43587 21797 43587 21797 43588 21793 43588 21798 43588 21797 43589 21798 43589 21802 43589 21799 43590 21803 43590 21801 43590 21800 43591 21803 43591 21799 43591 21787 43592 21800 43592 21799 43592 21799 43593 21805 43593 21789 43593 21804 43594 21805 43594 21799 43594 21801 43595 21804 43595 21799 43595 21787 43596 21797 43596 21800 43596 21800 43597 21797 43597 21802 43597 21800 43598 21802 43598 21803 43598 21803 43599 21802 43599 21798 43599 21803 43600 21798 43600 21801 43600 21801 43601 21798 43601 21794 43601 21801 43602 21794 43602 21804 43602 21804 43603 21794 43603 21806 43603 21804 43604 21806 43604 21805 43604 21805 43605 21806 43605 21807 43605 21805 43606 21807 43606 21789 43606 21789 43607 21807 43607 21793 43607 21813 43608 21825 43608 21808 43608 21808 43609 21825 43609 21809 43609 21808 43610 21809 43610 21830 43610 21815 43611 21811 43611 21810 43611 21810 43612 21811 43612 21812 43612 21810 43613 21812 43613 21813 43613 21813 43614 21812 43614 21814 43614 21813 43615 21814 43615 21825 43615 21815 43616 21810 43616 21822 43616 21822 43617 21810 43617 21816 43617 21822 43618 21816 43618 21817 43618 21817 43619 21816 43619 21818 43619 21817 43620 21818 43620 21824 43620 21824 43621 21818 43621 21828 43621 21824 43622 21828 43622 21819 43622 21819 43623 21828 43623 21820 43623 21819 43624 21820 43624 21823 43624 21821 43625 21809 43625 21825 43625 21814 43626 21812 43626 21821 43626 21811 43627 21815 43627 21821 43627 21822 43628 21817 43628 21821 43628 21821 43629 21819 43629 21823 43629 21824 43630 21819 43630 21821 43630 21817 43631 21824 43631 21821 43631 21815 43632 21822 43632 21821 43632 21812 43633 21811 43633 21821 43633 21825 43634 21814 43634 21821 43634 21826 43635 21827 43635 21830 43635 21828 43636 21818 43636 21808 43636 21830 43637 21827 43637 21808 43637 21808 43638 21827 43638 21820 43638 21808 43639 21820 43639 21828 43639 21818 43640 21816 43640 21808 43640 21808 43641 21816 43641 21810 43641 21808 43642 21810 43642 21813 43642 21837 43643 21829 43643 21830 43643 21830 43644 21829 43644 21831 43644 21830 43645 21831 43645 21826 43645 21821 43646 21833 43646 21834 43646 21832 43647 21833 43647 21821 43647 21823 43648 21832 43648 21821 43648 21821 43649 21836 43649 21809 43649 21835 43650 21836 43650 21821 43650 21834 43651 21835 43651 21821 43651 21823 43652 21820 43652 21832 43652 21832 43653 21820 43653 21827 43653 21832 43654 21827 43654 21833 43654 21833 43655 21827 43655 21826 43655 21833 43656 21826 43656 21834 43656 21834 43657 21826 43657 21831 43657 21834 43658 21831 43658 21835 43658 21835 43659 21831 43659 21829 43659 21835 43660 21829 43660 21836 43660 21836 43661 21829 43661 21837 43661 21836 43662 21837 43662 21809 43662 21809 43663 21837 43663 21830 43663 21843 43664 21839 43664 21838 43664 21838 43665 21839 43665 21840 43665 21841 43666 21842 43666 21838 43666 21838 43667 21842 43667 21843 43667 21842 43668 21844 43668 21843 43668 21843 43669 21844 43669 21839 43669 21839 43670 21844 43670 21840 43670 21840 43671 21844 43671 21845 43671 21838 43672 21840 43672 21841 43672 21841 43673 21840 43673 21845 43673 21841 43674 21845 43674 21842 43674 21842 43675 21845 43675 21844 43675 21846 43676 21848 43676 21847 43676 21847 43677 21848 43677 21850 43677 21851 43678 21849 43678 21852 43678 21852 43679 21849 43679 21853 43679 21852 43680 21853 43680 21847 43680 21847 43681 21853 43681 21846 43681 21850 43682 21851 43682 21847 43682 21847 43683 21851 43683 21852 43683 21850 43684 21848 43684 21851 43684 21851 43685 21848 43685 21849 43685 21853 43686 21849 43686 21846 43686 21846 43687 21849 43687 21848 43687 21859 43688 21858 43688 21854 43688 21854 43689 21858 43689 21855 43689 21854 43690 21855 43690 21856 43690 21856 43691 21855 43691 21860 43691 21857 43692 21858 43692 21861 43692 21861 43693 21858 43693 21859 43693 21854 43694 21856 43694 21859 43694 21859 43695 21856 43695 21861 43695 21856 43696 21860 43696 21861 43696 21861 43697 21860 43697 21857 43697 21857 43698 21860 43698 21858 43698 21858 43699 21860 43699 21855 43699 21864 43700 21863 43700 21862 43700 21862 43701 21863 43701 21868 43701 21862 43702 21868 43702 21866 43702 21866 43703 21868 43703 21867 43703 21864 43704 21862 43704 21865 43704 21865 43705 21862 43705 21866 43705 21866 43706 21867 43706 21865 43706 21865 43707 21867 43707 21869 43707 21865 43708 21869 43708 21864 43708 21864 43709 21869 43709 21863 43709 21867 43710 21868 43710 21869 43710 21869 43711 21868 43711 21863 43711 21870 43712 21875 43712 21871 43712 21871 43713 21875 43713 21876 43713 21876 43714 21873 43714 21871 43714 21871 43715 21873 43715 21872 43715 21871 43716 21872 43716 21870 43716 21870 43717 21872 43717 21874 43717 21873 43718 21877 43718 21872 43718 21872 43719 21877 43719 21874 43719 21870 43720 21874 43720 21875 43720 21875 43721 21874 43721 21877 43721 21875 43722 21877 43722 21876 43722 21876 43723 21877 43723 21873 43723 21878 43724 21882 43724 21881 43724 21881 43725 21882 43725 21883 43725 21878 43726 21880 43726 21882 43726 21882 43727 21880 43727 21884 43727 21885 43728 21884 43728 21879 43728 21879 43729 21884 43729 21880 43729 21879 43730 21880 43730 21881 43730 21881 43731 21880 43731 21878 43731 21882 43732 21884 43732 21883 43732 21883 43733 21884 43733 21885 43733 21883 43734 21885 43734 21881 43734 21881 43735 21885 43735 21879 43735 21891 43736 21886 43736 21893 43736 21893 43737 21886 43737 21887 43737 21886 43738 21892 43738 21887 43738 21887 43739 21892 43739 21888 43739 21888 43740 21892 43740 21889 43740 21889 43741 21892 43741 21890 43741 21893 43742 21889 43742 21891 43742 21891 43743 21889 43743 21890 43743 21891 43744 21890 43744 21886 43744 21886 43745 21890 43745 21892 43745 21888 43746 21889 43746 21887 43746 21887 43747 21889 43747 21893 43747 21894 43748 21896 43748 21895 43748 21895 43749 21896 43749 21900 43749 21895 43750 21900 43750 21897 43750 21897 43751 21900 43751 21901 43751 21897 43752 21901 43752 21898 43752 21898 43753 21901 43753 21899 43753 21898 43754 21894 43754 21897 43754 21897 43755 21894 43755 21895 43755 21898 43756 21899 43756 21894 43756 21894 43757 21899 43757 21896 43757 21900 43758 21896 43758 21901 43758 21901 43759 21896 43759 21899 43759 21904 43760 21909 43760 21902 43760 21907 43761 21909 43761 21904 43761 21903 43762 21907 43762 21904 43762 21904 43763 21905 43763 21906 43763 21910 43764 21905 43764 21904 43764 21902 43765 21910 43765 21904 43765 21909 43766 21907 43766 21911 43766 21911 43767 21907 43767 21903 43767 21912 43768 21911 43768 21908 43768 21908 43769 21911 43769 21903 43769 21908 43770 21903 43770 21914 43770 21914 43771 21903 43771 21913 43771 21902 43772 21909 43772 21910 43772 21910 43773 21909 43773 21911 43773 21910 43774 21911 43774 21905 43774 21905 43775 21911 43775 21906 43775 21904 43776 21912 43776 21908 43776 21911 43777 21912 43777 21904 43777 21906 43778 21911 43778 21904 43778 21904 43779 21913 43779 21903 43779 21914 43780 21913 43780 21904 43780 21908 43781 21914 43781 21904 43781 21918 43782 21926 43782 21924 43782 21924 43783 21926 43783 21915 43783 21916 43784 21921 43784 21915 43784 21915 43785 21921 43785 21917 43785 21915 43786 21917 43786 21924 43786 21924 43787 21917 43787 21925 43787 21918 43788 21924 43788 21919 43788 21920 43789 21923 43789 21919 43789 21919 43790 21923 43790 21929 43790 21919 43791 21929 43791 21918 43791 21926 43792 21918 43792 21927 43792 21927 43793 21918 43793 21929 43793 21917 43794 21920 43794 21925 43794 21925 43795 21920 43795 21919 43795 21916 43796 21922 43796 21921 43796 21921 43797 21922 43797 21928 43797 21922 43798 21916 43798 21915 43798 21930 43799 21923 43799 21928 43799 21928 43800 21923 43800 21920 43800 21928 43801 21920 43801 21921 43801 21921 43802 21920 43802 21917 43802 21919 43803 21924 43803 21925 43803 21915 43804 21926 43804 21922 43804 21922 43805 21926 43805 21927 43805 21922 43806 21927 43806 21928 43806 21929 43807 21923 43807 21927 43807 21927 43808 21923 43808 21930 43808 21927 43809 21930 43809 21928 43809 21939 43810 21934 43810 21940 43810 21940 43811 21934 43811 21932 43811 21934 43812 21939 43812 21942 43812 21932 43813 21938 43813 21937 43813 21941 43814 21940 43814 21931 43814 21931 43815 21940 43815 21932 43815 21931 43816 21932 43816 21933 43816 21933 43817 21932 43817 21937 43817 21944 43818 21943 43818 21948 43818 21942 43819 21935 43819 21934 43819 21934 43820 21935 43820 21945 43820 21934 43821 21945 43821 21932 43821 21946 43822 21933 43822 21936 43822 21936 43823 21933 43823 21937 43823 21936 43824 21937 43824 21945 43824 21945 43825 21937 43825 21938 43825 21945 43826 21938 43826 21932 43826 21947 43827 21935 43827 21943 43827 21943 43828 21935 43828 21942 43828 21939 43829 21940 43829 21942 43829 21942 43830 21940 43830 21941 43830 21942 43831 21941 43831 21943 43831 21943 43832 21941 43832 21948 43832 21931 43833 21933 43833 21944 43833 21944 43834 21933 43834 21946 43834 21944 43835 21946 43835 21943 43835 21943 43836 21946 43836 21947 43836 21936 43837 21945 43837 21946 43837 21946 43838 21945 43838 21935 43838 21946 43839 21935 43839 21947 43839 21941 43840 21931 43840 21948 43840 21948 43841 21931 43841 21944 43841 21961 43842 21949 43842 21965 43842 21965 43843 21949 43843 21958 43843 21956 43844 21957 43844 21950 43844 21960 43845 21961 43845 21950 43845 21950 43846 21961 43846 21965 43846 21950 43847 21965 43847 21956 43847 21956 43848 21965 43848 21951 43848 21959 43849 21964 43849 21952 43849 21950 43850 21957 43850 21953 43850 21953 43851 21957 43851 21954 43851 21953 43852 21954 43852 21962 43852 21951 43853 21965 43853 21959 43853 21951 43854 21959 43854 21955 43854 21955 43855 21959 43855 21952 43855 21955 43856 21952 43856 21954 43856 21954 43857 21952 43857 21963 43857 21954 43858 21963 43858 21962 43858 21951 43859 21955 43859 21956 43859 21956 43860 21955 43860 21954 43860 21956 43861 21954 43861 21957 43861 21949 43862 21964 43862 21958 43862 21958 43863 21964 43863 21959 43863 21960 43864 21953 43864 21961 43864 21961 43865 21953 43865 21962 43865 21953 43866 21960 43866 21950 43866 21949 43867 21961 43867 21962 43867 21963 43868 21952 43868 21962 43868 21962 43869 21952 43869 21964 43869 21962 43870 21964 43870 21949 43870 21959 43871 21965 43871 21958 43871 21966 43872 21968 43872 21975 43872 21975 43873 21968 43873 21970 43873 21975 43874 21970 43874 21971 43874 21967 43875 21979 43875 21968 43875 21968 43876 21979 43876 21969 43876 21968 43877 21969 43877 21970 43877 21970 43878 21969 43878 21978 43878 21982 43879 21977 43879 21972 43879 21968 43880 21966 43880 21980 43880 21980 43881 21966 43881 21976 43881 21980 43882 21976 43882 21981 43882 21971 43883 21970 43883 21982 43883 21971 43884 21982 43884 21974 43884 21974 43885 21982 43885 21972 43885 21974 43886 21972 43886 21976 43886 21976 43887 21972 43887 21973 43887 21976 43888 21973 43888 21981 43888 21971 43889 21974 43889 21975 43889 21975 43890 21974 43890 21976 43890 21975 43891 21976 43891 21966 43891 21969 43892 21977 43892 21978 43892 21978 43893 21977 43893 21982 43893 21967 43894 21980 43894 21979 43894 21979 43895 21980 43895 21981 43895 21980 43896 21967 43896 21968 43896 21969 43897 21979 43897 21981 43897 21973 43898 21972 43898 21981 43898 21981 43899 21972 43899 21977 43899 21981 43900 21977 43900 21969 43900 21982 43901 21970 43901 21978 43901 21983 43902 21996 43902 21985 43902 21985 43903 21996 43903 21997 43903 21984 43904 21988 43904 21999 43904 21998 43905 21983 43905 21999 43905 21999 43906 21983 43906 21985 43906 21999 43907 21985 43907 21984 43907 21984 43908 21985 43908 21994 43908 21986 43909 21987 43909 21991 43909 21999 43910 21988 43910 21989 43910 21989 43911 21988 43911 21992 43911 21989 43912 21992 43912 21990 43912 21994 43913 21985 43913 21986 43913 21994 43914 21986 43914 21995 43914 21995 43915 21986 43915 21991 43915 21995 43916 21991 43916 21992 43916 21992 43917 21991 43917 21993 43917 21992 43918 21993 43918 21990 43918 21994 43919 21995 43919 21984 43919 21984 43920 21995 43920 21992 43920 21984 43921 21992 43921 21988 43921 21996 43922 21987 43922 21997 43922 21997 43923 21987 43923 21986 43923 21998 43924 21989 43924 21983 43924 21983 43925 21989 43925 21990 43925 21989 43926 21998 43926 21999 43926 21996 43927 21983 43927 21990 43927 21993 43928 21991 43928 21990 43928 21990 43929 21991 43929 21987 43929 21990 43930 21987 43930 21996 43930 21986 43931 21985 43931 21997 43931 22001 43932 22009 43932 22000 43932 22000 43933 22009 43933 22013 43933 22009 43934 22001 43934 22005 43934 22003 43935 22000 43935 22013 43935 22012 43936 22011 43936 22013 43936 22013 43937 22011 43937 22007 43937 22013 43938 22007 43938 22003 43938 22006 43939 22002 43939 22016 43939 22000 43940 22003 43940 22002 43940 22002 43941 22003 43941 22016 43941 22004 43942 22014 43942 22005 43942 22001 43943 22000 43943 22005 43943 22005 43944 22000 43944 22002 43944 22005 43945 22002 43945 22004 43945 22004 43946 22002 43946 22015 43946 22006 43947 22007 43947 22011 43947 22005 43948 22014 43948 22009 43948 22009 43949 22014 43949 22008 43949 22009 43950 22008 43950 22013 43950 22015 43951 22002 43951 22006 43951 22015 43952 22006 43952 22010 43952 22010 43953 22006 43953 22011 43953 22010 43954 22011 43954 22008 43954 22008 43955 22011 43955 22012 43955 22008 43956 22012 43956 22013 43956 22008 43957 22014 43957 22010 43957 22010 43958 22014 43958 22004 43958 22010 43959 22004 43959 22015 43959 22003 43960 22007 43960 22016 43960 22016 43961 22007 43961 22006 43961 22024 43962 22019 43962 22031 43962 22031 43963 22019 43963 22026 43963 22031 43964 22026 43964 22028 43964 22017 43965 22018 43965 22019 43965 22019 43966 22018 43966 22033 43966 22019 43967 22033 43967 22026 43967 22026 43968 22033 43968 22020 43968 22021 43969 22022 43969 22023 43969 22019 43970 22024 43970 22025 43970 22025 43971 22024 43971 22030 43971 22025 43972 22030 43972 22032 43972 22028 43973 22026 43973 22021 43973 22028 43974 22021 43974 22029 43974 22029 43975 22021 43975 22023 43975 22029 43976 22023 43976 22030 43976 22030 43977 22023 43977 22027 43977 22030 43978 22027 43978 22032 43978 22028 43979 22029 43979 22031 43979 22031 43980 22029 43980 22030 43980 22031 43981 22030 43981 22024 43981 22033 43982 22022 43982 22020 43982 22020 43983 22022 43983 22021 43983 22017 43984 22025 43984 22018 43984 22018 43985 22025 43985 22032 43985 22025 43986 22017 43986 22019 43986 22033 43987 22018 43987 22032 43987 22027 43988 22023 43988 22032 43988 22032 43989 22023 43989 22022 43989 22032 43990 22022 43990 22033 43990 22021 43991 22026 43991 22020 43991 22043 43992 22035 43992 22045 43992 22045 43993 22035 43993 22036 43993 22045 43994 22036 43994 22040 43994 22034 43995 22048 43995 22035 43995 22035 43996 22048 43996 22046 43996 22035 43997 22046 43997 22036 43997 22036 43998 22046 43998 22047 43998 22041 43999 22050 43999 22037 43999 22035 44000 22043 44000 22038 44000 22038 44001 22043 44001 22039 44001 22038 44002 22039 44002 22049 44002 22040 44003 22036 44003 22041 44003 22040 44004 22041 44004 22044 44004 22044 44005 22041 44005 22037 44005 22044 44006 22037 44006 22039 44006 22039 44007 22037 44007 22042 44007 22039 44008 22042 44008 22049 44008 22039 44009 22043 44009 22044 44009 22044 44010 22043 44010 22045 44010 22044 44011 22045 44011 22040 44011 22046 44012 22050 44012 22047 44012 22047 44013 22050 44013 22041 44013 22034 44014 22038 44014 22048 44014 22048 44015 22038 44015 22049 44015 22038 44016 22034 44016 22035 44016 22046 44017 22048 44017 22049 44017 22042 44018 22037 44018 22049 44018 22049 44019 22037 44019 22050 44019 22049 44020 22050 44020 22046 44020 22041 44021 22036 44021 22047 44021 22052 44022 22051 44022 22054 44022 22054 44023 22051 44023 22062 44023 22063 44024 22052 44024 22053 44024 22053 44025 22052 44025 22054 44025 22053 44026 22054 44026 22066 44026 22066 44027 22054 44027 22061 44027 22055 44028 22056 44028 22059 44028 22065 44029 22068 44029 22057 44029 22057 44030 22068 44030 22058 44030 22057 44031 22058 44031 22059 44031 22059 44032 22058 44032 22060 44032 22059 44033 22060 44033 22055 44033 22055 44034 22060 44034 22061 44034 22055 44035 22061 44035 22054 44035 22060 44036 22058 44036 22061 44036 22061 44037 22058 44037 22068 44037 22061 44038 22068 44038 22066 44038 22051 44039 22056 44039 22062 44039 22062 44040 22056 44040 22055 44040 22063 44041 22064 44041 22052 44041 22052 44042 22064 44042 22067 44042 22064 44043 22063 44043 22053 44043 22057 44044 22059 44044 22065 44044 22065 44045 22059 44045 22056 44045 22065 44046 22056 44046 22067 44046 22067 44047 22056 44047 22051 44047 22067 44048 22051 44048 22052 44048 22055 44049 22054 44049 22062 44049 22053 44050 22066 44050 22064 44050 22064 44051 22066 44051 22068 44051 22064 44052 22068 44052 22067 44052 22067 44053 22068 44053 22065 44053 22081 44054 22069 44054 22072 44054 22072 44055 22069 44055 22084 44055 22070 44056 22081 44056 22071 44056 22071 44057 22081 44057 22072 44057 22071 44058 22072 44058 22073 44058 22073 44059 22072 44059 22077 44059 22076 44060 22080 44060 22074 44060 22075 44061 22079 44061 22074 44061 22074 44062 22079 44062 22078 44062 22074 44063 22078 44063 22076 44063 22076 44064 22078 44064 22077 44064 22076 44065 22077 44065 22072 44065 22077 44066 22078 44066 22073 44066 22073 44067 22078 44067 22079 44067 22069 44068 22080 44068 22084 44068 22084 44069 22080 44069 22076 44069 22070 44070 22082 44070 22081 44070 22081 44071 22082 44071 22083 44071 22082 44072 22070 44072 22071 44072 22069 44073 22081 44073 22083 44073 22075 44074 22074 44074 22083 44074 22083 44075 22074 44075 22080 44075 22083 44076 22080 44076 22069 44076 22076 44077 22072 44077 22084 44077 22071 44078 22073 44078 22082 44078 22082 44079 22073 44079 22079 44079 22082 44080 22079 44080 22083 44080 22083 44081 22079 44081 22075 44081 22092 44082 22089 44082 22096 44082 22085 44083 22086 44083 22087 44083 22087 44084 22086 44084 22094 44084 22087 44085 22094 44085 22098 44085 22090 44086 22099 44086 22094 44086 22094 44087 22099 44087 22088 44087 22094 44088 22088 44088 22098 44088 22095 44089 22086 44089 22089 44089 22089 44090 22086 44090 22085 44090 22097 44091 22102 44091 22085 44091 22085 44092 22102 44092 22101 44092 22085 44093 22101 44093 22089 44093 22089 44094 22101 44094 22096 44094 22092 44095 22100 44095 22091 44095 22099 44096 22090 44096 22091 44096 22091 44097 22090 44097 22093 44097 22091 44098 22093 44098 22092 44098 22092 44099 22093 44099 22095 44099 22092 44100 22095 44100 22089 44100 22090 44101 22094 44101 22093 44101 22093 44102 22094 44102 22086 44102 22093 44103 22086 44103 22095 44103 22101 44104 22100 44104 22096 44104 22096 44105 22100 44105 22092 44105 22097 44106 22087 44106 22102 44106 22102 44107 22087 44107 22098 44107 22087 44108 22097 44108 22085 44108 22099 44109 22091 44109 22088 44109 22088 44110 22091 44110 22100 44110 22088 44111 22100 44111 22098 44111 22098 44112 22100 44112 22101 44112 22098 44113 22101 44113 22102 44113

+
+
+
+
+ + + + + + + + + + + + + + +
diff --git a/robots/b1_description/meshes/thigh.dae b/robots/b1_description/meshes/thigh.dae new file mode 100644 index 0000000..9ad1af7 --- /dev/null +++ b/robots/b1_description/meshes/thigh.dae @@ -0,0 +1,63 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + 周四 2月 24 03:20:23 2022 + 周四 2月 24 03:20:23 2022 + + + + + + + + + 0.016529 -0.0285533 -0.0349882 0.0310557 -0.0287533 -0.0234171 0.0205266 -0.0285533 0.032807 0.0237855 -0.0285533 0.0305263 0.0193996 -0.0285533 0.033486 0.0292298 -0.0285533 0.0253603 0.0269878 -0.0287533 0.0280133 0.0336623 -0.0285533 0.0190869 0.0327377 -0.0285533 0.020633 0.0386256 -0.0285533 0.00232499 0.0358632 -0.0285533 0.0145345 0.0383814 -0.0287533 -0.00630004 0.0386708 -0.0285533 -0.00137602 0.0357578 -0.0287533 -0.0153033 0.0328001 -0.0285533 -0.0205291 0.0333566 -0.0285533 -0.0196119 0.035144 -0.0285533 -0.0161924 0.0166145 -0.0287533 -0.035169 0.030896 -0.0285533 -0.0232967 0.0110308 -0.0285533 -0.0370911 0.0140456 -0.0285533 -0.0360572 0.0158245 -0.0285533 -0.0353125 0.00767485 -0.0285533 -0.0379282 -0.00163402 -0.0287533 -0.0388637 0.0177197 -0.0275033 -0.0343102 0.01908 -0.0285533 -0.0336648 0.0194147 -0.0275033 -0.0333802 0.0204175 -0.0275033 -0.0317272 0.0204596 -0.0285533 -0.0297943 0.0204596 -0.0275033 -0.0297943 0.0195296 -0.0285533 -0.0280993 0.0325012 -0.0275033 -0.020851 0.0308063 -0.0285533 -0.0217811 0.0335041 -0.0275033 -0.0191981 0.0335041 -0.0285533 -0.0191981 0.0335462 -0.0285533 -0.0172652 0.0326162 -0.0275033 -0.0155702 0.0309632 -0.0275033 -0.0145673 0.0309632 -0.0285533 -0.0145673 0.03757 -0.0285533 -0.00345721 0.03757 -0.0275033 -0.00345721 0.0385729 -0.0275033 -0.00180428 0.0385729 -0.0285533 -0.00180428 0.038615 -0.0275033 0.000128639 0.0386941 -0.0285533 -0.000303478 0.0376849 -0.0275033 0.00182363 0.0376849 -0.0285533 0.00182363 0.036032 -0.0275033 0.00282652 0.036032 -0.0285533 0.00282652 0.0315678 -0.0285533 0.0132106 0.0312942 -0.0275033 0.0131544 0.0315678 -0.0275033 0.0132106 0.0328318 -0.0275033 0.0137858 0.0331771 -0.0275033 0.0196159 0.0343077 -0.0285533 0.0177265 0.0344083 -0.0275033 0.0166177 0.0342657 -0.0275033 0.0157936 0.0339432 -0.0275033 0.0150219 0.0171057 -0.0285533 0.0263393 0.0190387 -0.0275033 0.0262972 0.0190387 -0.0285533 0.0262972 0.0203027 -0.0275033 0.0268724 0.0207336 -0.0275033 0.0272273 0.0217365 -0.0285533 0.0288802 0.0214141 -0.0275033 0.0281085 0.0217365 -0.0275033 0.0288802 0.0217786 -0.0275033 0.0308131 0.0208486 -0.0275033 0.0325081 0.0191956 -0.0275033 0.033511 0.0042119 -0.0275033 0.0364127 0.00345474 -0.0275033 0.0375769 0.00325417 -0.0275033 0.0377713 0.00402027 -0.0275033 0.0331772 0.0043427 -0.0275033 0.033949 0.00448532 -0.0275033 0.0347731 0.00438477 -0.0285533 0.0358819 0.00438477 -0.0275033 0.0358819 0.00333981 -0.0275033 0.032296 0.00290886 -0.0275033 0.0319412 0.00164482 -0.0275033 0.031366 0.00137122 -0.0275033 0.0313098 0.00164482 -0.0285533 0.031366 -0.0157961 -0.0275033 0.0342725 -0.013386 -0.0285533 0.0321054 -0.0143437 -0.0275033 0.033464 -0.0135776 -0.0285533 0.02887 -0.0135776 -0.0275033 0.02887 -0.014689 -0.0285533 0.027634 -0.0162267 -0.0285533 0.0270025 -0.0162267 -0.0275033 0.0270025 -0.0272297 -0.0275033 0.0207405 -0.0264726 -0.0275033 0.0195763 -0.0261992 -0.0275033 0.0179367 -0.0266642 -0.0285533 0.0163409 -0.0277756 -0.0285533 0.0151048 -0.0277756 -0.0275033 0.0151048 -0.0309726 -0.0285533 0.0145717 -0.0339514 -0.0275033 0.00434956 -0.0314105 -0.0275033 -0.00028124 -0.0312679 -0.0275033 0.000542885 -0.0315413 -0.0275033 0.00218248 -0.031733 -0.0275033 -0.00105297 -0.031733 -0.0285533 -0.00105297 -0.0328444 -0.0275033 -0.002289 -0.0341084 -0.0275033 -0.0028642 -0.0360413 -0.0275033 -0.00282213 -0.0281918 -0.0275033 -0.0140568 -0.0279913 -0.0285533 -0.0142512 -0.0271033 -0.0275033 -0.0178791 -0.0270612 -0.0275033 -0.0159462 -0.0281062 -0.0275033 -0.019532 -0.0300748 -0.0275033 -0.0205183 -0.0317341 -0.0285533 -0.02042 -0.0171151 -0.0275033 -0.0263349 -0.0154621 -0.0285533 -0.0273378 -0.0154621 -0.0275033 -0.0273378 -0.0145321 -0.0275033 -0.0290328 -0.0145742 -0.0285533 -0.0309657 -0.0155771 -0.0275033 -0.0326186 -0.0172721 -0.0275033 -0.0335487 0.00296228 -0.0285533 -0.0352103 0.00249723 -0.0275033 -0.0368062 0.00181677 -0.0275033 -0.0376874 0.00249723 -0.0285533 -0.0368062 0.00138582 -0.0275033 -0.0380422 0.000121777 -0.0275033 -0.0386174 -0.000310341 -0.0285533 -0.0386966 0.00281966 -0.0275033 -0.0360345 0.00268886 -0.0285533 -0.0335708 0.0195296 -0.0275033 -0.0280993 0.0202255 -0.0273033 -0.0316713 0.0192763 -0.0273033 -0.0332357 0.0157867 -0.0275033 -0.0342681 0.00327225 -0.0287533 0.0280149 0.00340883 -0.0285533 0.028161 0.00458718 -0.0285533 0.0263819 0.00483589 -0.0285533 0.0242625 0.0154105 -0.0287533 0.0248017 0.0260692 -0.0285533 0.00361153 0.027695 -0.0287533 0.00249303 0.0288221 -0.0287533 0.000938536 0.0291799 -0.0287533 -0.000947949 0.0293798 -0.0285533 -0.000954457 -0.0122838 -0.0285533 -0.00624396 -0.0248246 -0.0285533 0.0231714 -0.0257354 -0.0291033 0.0246568 -0.0264052 -0.0285533 0.0254136 -0.0251598 -0.0291033 0.0266321 -0.0245709 -0.0285533 0.0274536 -0.0342225 -0.0285533 0.00768215 -0.0351333 -0.0291033 0.00916753 -0.0350486 -0.0291033 0.0105968 -0.0345577 -0.0291033 0.0111429 -0.0355292 -0.0285533 0.0108644 -0.0348746 -0.0285533 0.0115924 -0.0339688 -0.0285533 0.0119643 -0.0273211 -0.0285533 -0.0250379 -0.0274822 -0.0285533 -0.0240721 -0.0265536 -0.0285533 -0.0224041 -0.0246705 -0.0285533 -0.0220901 -0.0113859 -0.0285533 -0.0351215 -0.0119337 -0.0285533 -0.0341231 -0.0113182 -0.0285533 -0.032011 0.00672717 -0.0285533 -0.0355157 0.00671359 -0.0291033 -0.0343866 0.00617936 -0.0285533 -0.0345173 0.00673217 -0.0291033 -0.0335327 0.00717522 -0.0291033 -0.0328025 0.00792401 -0.0291033 -0.0323916 0.0321267 -0.0285533 -0.0114258 0.0315625 -0.0285533 -0.0106256 0.0314015 -0.0285533 -0.00965982 0.032156 -0.0291033 -0.00898735 0.0316754 -0.0285533 -0.00871983 0.0344535 -0.0291033 0.00990725 0.03363 -0.0285533 0.0104932 0.0330411 -0.0291033 0.00967174 0.0328508 -0.0291033 0.00951498 0.0327243 -0.0285533 0.0101213 0.0325502 -0.0291033 0.0091257 0.0317957 -0.0285533 0.00845322 0.0319567 -0.0285533 0.00748746 0.0323891 -0.0291033 0.00793087 0.0324655 -0.0291033 0.00769639 0.0335302 -0.0291033 0.00673904 0.0328886 -0.0291033 0.00709621 0.0333763 -0.0285533 0.006211 0.0328 -0.0291033 0.00718208 0.0246612 -0.0285533 0.0220945 0.0236876 -0.0285533 0.0226852 0.023674 -0.0291033 0.0238143 0.0236926 -0.0291033 0.0246682 0.0231645 -0.0285533 0.0248221 0.0237553 -0.0285533 0.0257957 0.0241356 -0.0291033 0.0253984 0.0247537 -0.0285533 0.0263435 -0.00878724 -0.0291033 0.0324146 -0.00894112 -0.0285533 0.0318865 -0.00942885 -0.0291033 0.0327718 -0.00997273 -0.0291033 0.0340962 -0.0103607 -0.0285533 0.033163 -0.00976729 -0.0291033 0.0348012 -0.00859702 -0.0291033 0.0356262 -0.0095932 -0.0285533 0.0357968 -0.00786399 -0.0291033 0.0355828 -0.00868749 -0.0285533 0.0361687 -0.00771011 -0.0285533 0.0361108 0.0333519 -0.0273033 -0.0173127 0.0335462 -0.0275033 -0.0172652 0.0308063 -0.0275033 -0.0217811 0.0307587 -0.0273033 -0.0215868 0.0375405 -0.0273033 0.00168532 0.0384207 -0.0273033 8.10912e-05 0.035875 -0.0275033 -0.00438724 0.0339421 -0.0275033 -0.00434517 0.0330434 -0.0273033 0.0194672 0.0333777 -0.0275033 0.0194215 0.0341349 -0.0275033 0.0182573 0.0343077 -0.0275033 0.0177265 0.0332628 -0.0275033 0.0141407 0.0191397 -0.0273033 0.033319 0.020648 -0.0275033 0.0327025 0.0216057 -0.0275033 0.0313439 0.0216795 -0.0273033 0.0297161 0.0218792 -0.0275033 0.0297043 0.0187651 -0.0275033 0.026241 0.00312044 -0.0273033 0.0376225 0.00384552 -0.0273033 0.0332745 0.00279363 -0.0273033 0.0321047 0.00133832 -0.0273033 0.0315071 -0.000288102 -0.0275033 0.0314081 -0.015852 -0.0273033 0.0340805 -0.0144774 -0.0273033 0.0333153 -0.013386 -0.0275033 0.0321054 -0.013571 -0.0273033 0.0320295 -0.0131126 -0.0275033 0.0304658 -0.0133122 -0.0273033 0.0304777 -0.014689 -0.0275033 0.027634 -0.0148043 -0.0273033 0.0277974 -0.0162596 -0.0273033 0.0271998 -0.0273742 -0.0273033 0.0206022 -0.0262997 -0.0275033 0.0190455 -0.0263418 -0.0275033 0.0171126 -0.0266642 -0.0275033 0.0163409 -0.0265338 -0.0273033 0.0171685 -0.0273447 -0.0275033 0.0154597 -0.027483 -0.0273033 0.0156041 -0.0290397 -0.0275033 0.0145296 -0.0309726 -0.0275033 0.0145717 -0.0322985 -0.0275033 0.00334667 -0.0340074 -0.0273033 0.00415755 -0.0313685 -0.0275033 0.00165168 -0.0316026 -0.0273033 -0.000225285 -0.0324134 -0.0275033 -0.00193417 -0.0325517 -0.0273033 -0.0017897 -0.0297001 -0.0273033 -0.0134403 -0.0279913 -0.0275033 -0.0142512 -0.0274191 -0.0273033 -0.0154914 -0.0272341 -0.0275033 -0.0154154 -0.0271603 -0.0273033 -0.0170432 -0.0269607 -0.0275033 -0.017055 -0.0274257 -0.0275033 -0.0186508 -0.0286524 -0.0273033 -0.0197234 -0.0285371 -0.0275033 -0.0198869 -0.0298012 -0.0275033 -0.0204621 -0.0301077 -0.0273033 -0.020321 -0.0156066 -0.0273033 -0.0274761 -0.0147264 -0.0273033 -0.0290803 -0.0145742 -0.0275033 -0.0309657 -0.0173196 -0.0273033 -0.0333544 -0.019205 -0.0275033 -0.0335066 0.00266746 -0.0273033 -0.0341491 0.00178723 -0.0273033 -0.0325449 0.00193169 -0.0275033 -0.0324066 0.000278769 -0.0275033 -0.0314037 0.00268886 -0.0275033 -0.0335708 0.00286172 -0.0275033 -0.0341016 0.00296228 -0.0275033 -0.0352103 0.00262765 -0.0273033 -0.0359785 7.42284e-05 -0.0273033 -0.0384232 -0.0201137 -0.0370033 0.0168614 -0.018714 -0.0370033 0.0161641 -0.00702224 -0.0370033 0.0120663 -0.00817565 -0.0287533 0.0121836 -0.00706774 -0.0287533 0.0120629 -0.00590272 -0.0370033 0.0123676 0.00327225 -0.0370033 0.0280149 0.00439937 -0.0287533 0.0263132 0.0134311 -0.0287533 0.0058872 0.013519 -0.0287533 0.00586293 0.027695 -0.0370033 0.00249303 0.0288221 -0.0370033 0.000938536 0.0291799 -0.0370033 -0.000947949 -0.0253123 -0.0291033 0.0240566 -0.0257354 -0.0366533 0.0246568 -0.0258562 -0.0366533 0.0253811 -0.0258562 -0.0291033 0.0253811 -0.0251598 -0.0366533 0.0266321 -0.0256507 -0.0291033 0.0260861 -0.0244805 -0.0366533 0.0269111 -0.0244805 -0.0291033 0.0269111 -0.0237474 -0.0291033 0.0268677 -0.0347102 -0.0291033 0.00856735 -0.0347102 -0.0366533 0.00856735 -0.0352541 -0.0366533 0.00989185 -0.0352541 -0.0291033 0.00989185 -0.0350486 -0.0366533 0.0105968 -0.0338784 -0.0291033 0.0114218 -0.0331453 -0.0291033 0.0113784 -0.0257476 -0.0366533 -0.0257863 -0.0263893 -0.0291033 -0.0254291 -0.0264779 -0.0366533 -0.0253433 -0.0268123 -0.0291033 -0.024829 -0.0268887 -0.0366533 -0.0245945 -0.0269331 -0.0291033 -0.0241047 -0.0267277 -0.0366533 -0.0233997 -0.0267277 -0.0291033 -0.0233997 -0.0262367 -0.0291033 -0.0228536 -0.0255574 -0.0291033 -0.0225747 -0.0102584 -0.0291033 -0.0351842 -0.0109886 -0.0291033 -0.0347412 -0.0113995 -0.0291033 -0.0339924 -0.0114439 -0.0366533 -0.0335026 -0.0113809 -0.0291033 -0.0331385 -0.0109378 -0.0366533 -0.0324083 -0.0109378 -0.0291033 -0.0324083 -0.0107474 -0.0366533 -0.0322515 -0.010189 -0.0291033 -0.0319974 -0.0100682 -0.0366533 -0.0319726 -0.00933513 -0.0291033 -0.032016 -0.00933513 -0.0366533 -0.032016 0.00712445 -0.0366533 -0.0351354 0.00712445 -0.0291033 -0.0351354 0.00666917 -0.0366533 -0.0338967 0.00687461 -0.0366533 -0.0331918 0.0073656 -0.0366533 -0.0326457 0.00804488 -0.0366533 -0.0323668 0.0324944 -0.0366533 -0.0110168 0.0324944 -0.0291033 -0.0110168 0.0320713 -0.0291033 -0.0104167 0.0319505 -0.0366533 -0.00969234 0.0319505 -0.0291033 -0.00969234 0.032647 -0.0291033 -0.00844131 0.0333262 -0.0366533 -0.00816237 0.0333262 -0.0291033 -0.00816237 0.0328 -0.0366533 0.00718208 0.0323447 -0.0291033 0.0084207 0.0323891 -0.0366533 0.00793087 0.0324077 -0.0366533 0.00878477 0.0324077 -0.0291033 0.00878477 0.0328508 -0.0366533 0.00951498 0.0335996 -0.0366533 0.00992584 0.0337204 -0.0291033 0.00995067 0.0335996 -0.0291033 0.00992584 0.0241735 -0.0366533 0.0229797 0.0240849 -0.0366533 0.0230655 0.0240849 -0.0291033 0.0230655 0.023674 -0.0366533 0.0238143 0.0236296 -0.0366533 0.0243042 0.024326 -0.0366533 0.0255552 0.0248844 -0.0291033 0.0258093 0.0248844 -0.0366533 0.0258093 0.0250053 -0.0366533 0.0258341 -0.00878724 -0.0366533 0.0324146 -0.00942885 -0.0366533 0.0327718 -0.00985194 -0.0366533 0.0333719 -0.00985194 -0.0291033 0.0333719 -0.00976729 -0.0366533 0.0348012 -0.0092763 -0.0291033 0.0353473 -0.00859702 -0.0366533 0.0356262 -0.00786399 -0.0366533 0.0355828 0.0164863 -0.0279033 -0.0286109 0.0163876 -0.0273033 -0.0280191 0.0163324 -0.0279033 -0.0286425 0.015276 -0.0273033 -0.0284755 0.0153794 -0.0279033 -0.0291654 0.0149968 -0.0279033 -0.0296609 0.0141364 -0.0273033 -0.0305226 0.0147354 -0.0279033 -0.0305581 0.0143341 -0.0273033 -0.0317079 0.0148891 -0.0279033 -0.03148 0.0154276 -0.0279033 -0.0322438 0.0150264 -0.0273033 -0.03269 -0.0246707 -0.0366533 0.0236994 -0.0253123 -0.0366533 0.0240566 -0.0256507 -0.0366533 0.0260861 -0.0242091 -0.0376448 0.0252836 -0.0340686 -0.0366533 0.00821018 -0.0351333 -0.0366533 0.00916753 -0.033607 -0.0376448 0.00979429 -0.0338784 -0.0366533 0.0114218 -0.0331453 -0.0366533 0.0113784 -0.0345577 -0.0366533 0.0111429 -0.0268701 -0.0366533 -0.0237406 -0.0256783 -0.0366533 -0.0225995 -0.0264271 -0.0366533 -0.0230104 -0.0262367 -0.0366533 -0.0228536 -0.0269331 -0.0366533 -0.0241047 -0.0268123 -0.0366533 -0.024829 -0.025286 -0.0376448 -0.0242022 -0.0102584 -0.0366533 -0.0351842 -0.0113809 -0.0366533 -0.0331385 -0.0112384 -0.0366533 -0.0327976 -0.010189 -0.0366533 -0.0319974 -0.0113231 -0.0366533 -0.0342269 -0.0113995 -0.0366533 -0.0339924 -0.0109 -0.0366533 -0.034827 -0.0109886 -0.0366533 -0.0347412 0.00671359 -0.0366533 -0.0343866 0.00673217 -0.0366533 -0.0335327 0.00792401 -0.0366533 -0.0323916 0.00717522 -0.0366533 -0.0328025 0.00678996 -0.0366533 -0.0346211 0.00831628 -0.0376448 -0.0339943 0.00721305 -0.0366533 -0.0352212 0.032156 -0.0366533 -0.00898735 0.0320713 -0.0366533 -0.0104167 0.0335976 -0.0376448 -0.0097899 0.032647 -0.0366533 -0.00844131 0.0344535 -0.0366533 0.00990725 0.0241356 -0.0366533 0.0253984 0.023835 -0.0366533 0.0250091 0.0236926 -0.0366533 0.0246682 0.0237504 -0.0366533 0.0235798 -0.00997273 -0.0366533 0.0340962 -0.0092763 -0.0366533 0.0353473 0.0291629 -0.0273033 -0.0207453 0.0279757 -0.0279033 -0.0189509 0.027822 -0.0279033 -0.018029 0.027223 -0.0273033 -0.0179935 0.0280834 -0.0279033 -0.0171317 0.0283626 -0.0273033 -0.0159464 0.0294742 -0.0273033 -0.0154899 0.0306737 -0.0273033 -0.015561 0.0334702 -0.0279033 -0.00221159 0.0330368 -0.0273033 -0.00262652 0.0323645 -0.0273033 -0.00140123 0.0323949 -0.0273033 -3.93454e-06 0.0344878 -0.0279033 0.00128047 0.0355746 -0.0279033 0.00125681 0.02864 -0.0279033 0.0163393 0.0292275 -0.0279033 0.0183554 0.0288126 -0.0273033 0.0187888 0.0300379 -0.0273033 0.0194611 0.0166338 -0.0279033 0.0284729 0.0161109 -0.0279033 0.0294259 0.0155281 -0.0273033 0.0292832 0.0166984 -0.0279033 0.031442 0.0162835 -0.0273033 0.0318754 0.0176514 -0.0279033 0.0319649 0.0187382 -0.0279033 0.0319413 -0.000760027 -0.0279033 0.0335416 -0.00125928 -0.0279033 0.0355814 -0.00069541 -0.0279033 0.0365108 -0.00183532 -0.0273033 0.0357493 0.000114952 -0.0273033 0.0376165 -0.0174286 -0.0279033 0.0286705 -0.0183579 -0.0279033 0.0292344 -0.0187913 -0.0273033 0.0288195 -0.0194636 -0.0273033 0.0300448 -0.0194332 -0.0273033 0.0314421 -0.0182933 -0.0279033 0.0322036 -0.0187082 -0.0273033 0.0326369 -0.0174829 -0.0273033 0.0333093 -0.030683 -0.0273033 0.0155654 -0.0313317 -0.0279033 0.016596 -0.0317329 -0.0273033 0.0161498 -0.0324252 -0.0273033 0.0171319 -0.0326229 -0.0273033 0.0183172 -0.0314833 -0.0273033 0.0203643 -0.0303717 -0.0273033 0.0208208 -0.0291722 -0.0273033 0.0207497 -0.0357518 -0.0273033 -0.00182846 -0.0364005 -0.0279033 -0.000797843 -0.0368017 -0.0273033 -0.001244 -0.037494 -0.0273033 -0.000261892 -0.0373555 -0.0273033 0.00207698 -0.0344089 -0.0279033 0.00277985 -0.0311333 -0.0273033 -0.0141709 -0.0310346 -0.0279033 -0.0147628 -0.0322448 -0.0273033 -0.0146274 -0.0321414 -0.0279033 -0.0153173 -0.0330482 -0.0273033 -0.0155209 -0.032524 -0.0279033 -0.0158127 -0.0333844 -0.0273033 -0.0166745 -0.0327053 -0.0279033 -0.0162466 -0.0185054 -0.0279033 -0.0278494 -0.01937 -0.0279033 -0.0282044 -0.0201762 -0.0279033 -0.0293332 -0.0207826 -0.0273033 -0.0305627 -0.0201998 -0.0279033 -0.03042 -0.0201026 -0.0279033 -0.0307185 -0.0187475 -0.0279033 -0.0319369 -0.0201103 -0.0273033 -0.031788 -0.00197615 -0.0279033 -0.0332731 -0.00263338 -0.0273033 -0.0330392 -0.00335837 -0.0273033 -0.0342341 -0.00260104 -0.0279033 -0.0339681 -0.00286251 -0.0279033 -0.0348654 -0.00338877 -0.0273033 -0.0356314 -0.00280598 -0.0279033 -0.0354888 -0.00271646 -0.0273033 -0.0368567 -0.00135371 -0.0279033 -0.0370057 -0.0021703 -0.0279033 -0.0365511 -0.00152158 -0.0273033 -0.0375817 -0.00228307 -0.0279033 -0.0364418 -0.00270878 -0.0279033 -0.0357872 0.0153148 -0.0279033 -0.0321345 0.0147919 -0.0279033 -0.0311815 0.0147919 -0.0373033 -0.0311815 0.0148156 -0.0279033 -0.0300948 0.0156217 -0.0279033 -0.0289659 0.0153794 -0.0373033 -0.0291654 0.0163324 -0.0373033 -0.0286425 0.0174192 -0.0373033 -0.0286661 0.0293308 -0.0373033 -0.0201693 0.0293308 -0.0279033 -0.0201693 0.0285142 -0.0279033 -0.0197147 0.0279021 -0.0373033 -0.0175656 0.028466 -0.0373033 -0.0166363 0.0287083 -0.0279033 -0.0164368 0.0287083 -0.0373033 -0.0164368 0.0295729 -0.0279033 -0.0160818 0.029419 -0.0373033 -0.0161134 0.0334702 -0.0373033 -0.00221159 0.0329473 -0.0279033 -0.00125858 0.0329709 -0.0279033 -0.000171799 0.0335348 -0.0373033 0.000757557 0.0344878 -0.0373033 0.00128047 0.0335348 -0.0279033 0.000757557 0.0355746 -0.0373033 0.00125681 0.0300923 -0.0279033 0.0148224 0.0291629 -0.0279033 0.0153863 0.02864 -0.0373033 0.0163393 0.0286637 -0.0373033 0.0174261 0.0286637 -0.0279033 0.0174261 0.0301806 -0.0373033 0.0188783 0.0301806 -0.0279033 0.0188783 0.0166338 -0.0373033 0.0284729 0.0175632 -0.0279033 0.027909 0.0161345 -0.0373033 0.0305127 0.0161345 -0.0279033 0.0305127 -0.000760027 -0.0373033 0.0335416 -0.00128294 -0.0279033 0.0344947 -0.00069541 -0.0373033 0.0365108 0.00134438 -0.0373033 0.03701 0.000257597 -0.0279033 0.0370337 -0.0187836 -0.0373033 0.029889 -0.0188808 -0.0373033 0.0301874 -0.0188808 -0.0279033 0.0301874 -0.0188572 -0.0279033 0.0312742 -0.0186759 -0.0373033 0.0317081 -0.0182933 -0.0373033 0.0322036 -0.018051 -0.0373033 0.0324031 -0.0173403 -0.0373033 0.0327265 -0.0171865 -0.0373033 0.0327581 -0.0173403 -0.0279033 0.0327265 -0.0318702 -0.0373033 0.0173599 -0.0320239 -0.0373033 0.0182817 -0.0318702 -0.0279033 0.0173599 -0.0320239 -0.0279033 0.0182817 -0.0317625 -0.0279033 0.019179 -0.0311376 -0.0373033 0.0198739 -0.030273 -0.0373033 0.0202289 -0.0311376 -0.0279033 0.0198739 -0.030273 -0.0279033 0.0202289 -0.0293401 -0.0279033 0.0201737 -0.036939 -0.0279033 -3.39789e-05 -0.036939 -0.0373033 -3.39789e-05 -0.0370362 -0.0373033 0.00026446 -0.0370927 -0.0279033 0.000887879 -0.0368312 -0.0279033 0.00178514 -0.0368312 -0.0373033 0.00178514 -0.0362063 -0.0373033 0.0024801 -0.0362063 -0.0279033 0.0024801 -0.0354956 -0.0373033 0.00280351 -0.0353418 -0.0279033 0.00283511 -0.0310346 -0.0373033 -0.0147628 -0.0311884 -0.0279033 -0.0147944 -0.0318991 -0.0279033 -0.0151178 -0.0327053 -0.0373033 -0.0162466 -0.0327855 -0.0373033 -0.01671 -0.0327855 -0.0279033 -0.01671 -0.0327289 -0.0279033 -0.0173334 -0.0326317 -0.0279033 -0.0176319 -0.0327289 -0.0373033 -0.0173334 -0.032206 -0.0279033 -0.0182864 -0.0320933 -0.0279033 -0.0183957 -0.0312767 -0.0279033 -0.0188503 -0.0195641 -0.0279033 -0.0314823 -0.0196769 -0.0373033 -0.031373 -0.0196769 -0.0279033 -0.031373 -0.0201998 -0.0373033 -0.03042 -0.0202563 -0.0279033 -0.0297966 -0.0202563 -0.0373033 -0.0297966 -0.0199949 -0.0279033 -0.0288993 -0.0196123 -0.0279033 -0.0284039 -0.0196123 -0.0373033 -0.0284039 -0.01937 -0.0373033 -0.0282044 -0.0186593 -0.0279033 -0.027881 -0.0185054 -0.0373033 -0.0278494 -0.00286251 -0.0373033 -0.0348654 -0.00278233 -0.0373033 -0.034402 -0.00278233 -0.0279033 -0.034402 -0.00221845 -0.0373033 -0.0334726 -0.00221845 -0.0279033 -0.0334726 -0.00197615 -0.0373033 -0.0332731 -0.00126544 -0.0279033 -0.0329497 -0.00111161 -0.0279033 -0.0329181 -0.000178662 -0.0373033 -0.0329734 -0.0324238 -0.0285033 -0.0214969 -0.0385412 -0.0285033 0.00530711 0.000181286 -0.0285033 0.0389017 -0.00140576 -0.0285033 0.038877 0.00162468 -0.0285033 0.0388681 0.00162468 -0.0287533 0.0388681 -0.0166238 -0.0285033 0.0351734 -0.00772387 -0.0287533 0.0381286 -0.0109425 -0.0285033 0.0373328 -0.00772387 -0.0285033 0.0381286 -0.0166238 -0.0287533 0.0351734 -0.0353583 -0.0285033 0.0162297 -0.0337856 -0.0285033 -0.0192865 -0.0369227 -0.0287533 -0.0122564 -0.0369227 -0.0285033 -0.0122564 -0.0387836 -0.0285033 -0.0030651 -0.029181 -0.0285033 -0.0257262 -0.0269971 -0.0287533 -0.0280089 -0.0329162 -0.0287533 -0.0207352 -0.0292843 -0.0285033 -0.0256086 -0.0315771 -0.0285033 -0.022722 -0.0196155 -0.0285033 -0.0335928 -0.0269971 -0.0285033 -0.0280089 -0.0108879 -0.0287533 -0.0373444 -0.0195093 -0.0287533 -0.0336546 -0.0195093 -0.0285033 -0.0336546 -0.0386389 -0.0283033 -0.000127814 -0.0389042 -0.0285033 0.000188149 -0.0388755 -0.0285033 0.00150875 -0.0338913 -0.0285033 0.00455598 -0.0358879 -0.0283033 0.0044062 -0.0375897 -0.0283033 0.00347243 -0.0333302 -0.0285033 -0.0197714 -0.0317943 -0.0285033 -0.0206264 -0.0342894 -0.0283033 -0.015785 -0.0341581 -0.0283033 -0.0182586 -0.0344211 -0.0285033 -0.0181285 -0.0344326 -0.0283033 -0.0166124 -0.032965 -0.0285033 -0.0136057 -0.029584 -0.0285033 -0.0130419 -0.031306 -0.0283033 -0.0131352 -0.0328498 -0.0283033 -0.0137692 -0.0207448 -0.0285033 -0.0329076 -0.0206674 -0.0283033 -0.0327093 -0.0216289 -0.0283033 -0.0313452 -0.021814 -0.0285033 -0.0314212 -0.0218025 -0.0283033 -0.0308123 -0.0221031 -0.0285033 -0.0296872 -0.0216113 -0.0285033 -0.0279995 -0.0187769 -0.0283033 -0.0262218 -0.0188098 -0.0285033 -0.0260246 -0.0190515 -0.0283033 -0.0262783 0.000282966 -0.0283033 -0.0313893 0.00033892 -0.0285033 -0.0311973 -0.00141592 -0.0285033 -0.0310933 -0.00292684 -0.0283033 -0.0319245 -0.00404271 -0.0283033 -0.0331655 -0.00421746 -0.0285033 -0.0330683 -0.00470928 -0.0285033 -0.034756 -0.00442012 -0.0285033 -0.0364899 -0.00340726 -0.0285033 -0.0379267 0.0179368 -0.0285033 -0.02689 0.0162149 -0.0283033 -0.0269834 0.016182 -0.0285033 -0.0267861 0.0128886 -0.0285033 -0.0304487 0.0133628 -0.0283033 -0.0321067 0.0143244 -0.0283033 -0.0334708 0.0290268 -0.0283033 -0.0145107 0.026318 -0.0283033 -0.017104 0.0260815 -0.0285033 -0.0190922 0.0270651 -0.0285033 -0.0208848 0.0288691 -0.0283033 -0.0217534 0.0323937 -0.0283033 0.00194939 0.0322554 -0.0285033 0.00209386 0.0313868 -0.0283033 0.000289828 0.0311948 -0.0285033 0.000345783 0.0313446 -0.0283033 -0.00165086 0.0311503 -0.0285033 -0.0016984 0.0322783 -0.0283033 -0.00335265 0.0321339 -0.0285033 -0.00349096 0.0338819 -0.0285033 -0.00455158 0.0297407 -0.0285033 0.0206753 0.0279482 -0.0285033 0.0196917 0.0270796 -0.0283033 0.0178877 0.0270373 -0.0283033 0.015947 0.0268431 -0.0285033 0.0158995 0.0172116 -0.0285033 0.0337619 0.0155574 -0.0283033 0.0326339 0.0145504 -0.0283033 0.0309743 0.0143584 -0.0285033 0.0310303 0.0145082 -0.0283033 0.0290336 0.0152975 -0.0285033 0.0271935 0.0171015 -0.0283033 0.0263249 0.00180601 -0.0283033 0.0385942 0.00150189 -0.0285033 0.038873 -0.000348254 -0.0285033 0.0312017 -0.00209633 -0.0285033 0.0322623 -0.00195186 -0.0283033 0.0324006 -0.00307989 -0.0285033 0.0340548 -0.00303541 -0.0285033 0.036099 -0.00183647 -0.0283033 0.0377026 -0.000182225 -0.0285033 0.0388307 -0.000134676 -0.0283033 0.0386364 -0.0178902 -0.0283033 0.0270864 -0.0194821 -0.0285033 0.0277495 -0.020495 -0.0285033 0.0291862 -0.0195497 -0.0283033 0.0280933 -0.02031 -0.0283033 0.0292622 -0.0204835 -0.0283033 0.0297951 -0.0207841 -0.0285033 0.0309202 -0.0174579 -0.0283033 0.0343856 -0.0174908 -0.0285033 0.0345829 -0.0181354 -0.0285033 0.0344186 -0.0192934 -0.0285033 0.0337832 -0.0194344 -0.0283033 0.0333954 -0.0332041 -0.0283033 0.0199815 -0.0333965 -0.0283033 0.0167331 -0.032435 -0.0283033 0.015369 -0.0335816 -0.0285033 0.0166571 -0.0288225 -0.0285033 0.0219498 -0.0305774 -0.0285033 0.0220537 -0.0320883 -0.0283033 0.0212225 -0.0329145 -0.0285033 0.0207423 -0.0335997 -0.0285033 0.019613 -0.00181405 -0.0283033 0.0108524 -0.00645781 -0.0285033 0.00915626 -0.0096158 -0.0283033 0.00535253 -0.0109854 -0.0283033 0.00065257 -0.0111851 -0.0285033 0.000664394 -0.00308218 -0.0283033 -0.0105585 -0.00313814 -0.0285033 -0.0107505 -0.000325099 -0.0283033 -0.029196 -0.000327294 -0.0285033 -0.029396 0.0201044 -0.0283033 -0.016857 0.0200484 -0.0285033 -0.017049 0.0220518 -0.0285033 -0.0171766 0.0251215 -0.0283033 -0.0148744 0.0147206 -0.0283033 0.00578379 0.0147453 -0.0285033 0.00558531 -0.0082316 -0.0285033 0.0119916 -0.00702224 -0.0283033 0.0120663 -0.0260785 -0.0285033 -0.00360713 -0.0244526 -0.0285033 -0.00377833 -0.014328 -0.0283033 -0.0252847 -0.0122893 -0.0283033 -0.0253856 -0.0122526 -0.0285033 -0.0255822 -0.0104244 -0.0283033 -0.0245557 -0.00987861 -0.0281533 0.0325119 -0.00976316 -0.0285033 0.0324 -0.0103145 -0.0285033 0.033182 -0.010414 -0.0281533 0.0334875 -0.0104719 -0.0285033 0.0341258 -0.0102042 -0.0285033 0.0350444 -0.00981246 -0.0281533 0.0355517 -0.00883676 -0.0281533 0.036087 -0.00956439 -0.0285033 0.0357559 -0.00867927 -0.0285033 0.0361194 -0.0248106 -0.0285033 0.0232194 -0.0248106 -0.0281533 0.0232194 -0.0261979 -0.0281533 0.0244669 -0.0260876 -0.0281533 0.0263293 -0.0254478 -0.0281533 0.0270408 -0.0236076 -0.0285033 0.0273477 -0.0342085 -0.0285033 0.00773015 -0.0342085 -0.0281533 0.00773015 -0.0350445 -0.0285033 0.00819555 -0.0350445 -0.0281533 0.00819555 -0.0339606 -0.0281533 0.011915 -0.0330055 -0.0285033 0.0118584 -0.0258875 -0.0281533 -0.0262663 -0.0272749 -0.0281533 -0.0250189 -0.0273744 -0.0285033 -0.0247134 -0.0273744 -0.0281533 -0.0247134 -0.0274323 -0.0281533 -0.0240751 -0.0271646 -0.0281533 -0.0231565 -0.0267729 -0.0285033 -0.0226492 -0.0267729 -0.0281533 -0.0226492 -0.0265248 -0.0281533 -0.022445 -0.0246845 -0.0281533 -0.0221381 -0.0256397 -0.0281533 -0.0220815 -0.0257972 -0.0285033 -0.0221139 -0.0103983 -0.0285033 -0.0356642 -0.0113498 -0.0281533 -0.035087 -0.0112343 -0.0285033 -0.0351988 -0.0117856 -0.0285033 -0.0344168 -0.0118851 -0.0281533 -0.0341113 -0.0116753 -0.0285033 -0.0325544 -0.0110355 -0.0285033 -0.0318429 -0.0103079 -0.0281533 -0.0315118 0.00771477 -0.0285033 -0.0360584 0.00625214 -0.0281533 -0.0333928 0.00682944 -0.0281533 -0.0324413 0.00682944 -0.0285033 -0.0324413 0.00780514 -0.0281533 -0.0319059 0.0089178 -0.0285033 -0.0319302 0.0314514 -0.0285033 -0.00966278 0.0316088 -0.0281533 -0.0106066 0.0314514 -0.0281533 -0.00966278 0.0317191 -0.0281533 -0.00874415 0.0323589 -0.0285033 -0.00803264 0.0323589 -0.0281533 -0.00803264 0.033244 -0.0285033 -0.00766918 0.033244 -0.0281533 -0.00766918 0.0333903 -0.0285033 0.006259 0.0325543 -0.0285033 0.00672441 0.0325543 -0.0281533 0.00672441 0.032003 -0.0281533 0.00750646 0.0318456 -0.0285033 0.00845026 0.0321133 -0.0281533 0.00936889 0.0336382 -0.0281533 0.0104439 0.0238391 -0.0285033 0.0226079 0.0246752 -0.0281533 0.0221425 0.0238391 -0.0281533 0.0226079 0.0232878 -0.0285033 0.0233899 0.0232878 -0.0281533 0.0233899 0.0231305 -0.0285033 0.0243337 0.0233981 -0.0285033 0.0252523 0.0240379 -0.0285033 0.0259639 0.0240379 -0.0281533 0.0259639 0.024923 -0.0285033 0.0263273 -0.0360455 -0.0283033 -0.00283653 -0.0377051 -0.0283033 -0.00182961 -0.0377051 -0.0257033 -0.00182961 -0.0386389 -0.0257033 -0.000127814 -0.0385966 -0.0283033 0.00181287 -0.0385966 -0.0257033 0.00181287 -0.0358879 -0.0257033 0.0044062 -0.0339472 -0.0283033 0.00436396 -0.02964 -0.0257033 -0.0132339 -0.0315807 -0.0283033 -0.0131917 -0.0332825 -0.0283033 -0.0141254 -0.0339657 -0.0257033 -0.0150102 -0.0339657 -0.0283033 -0.0150102 -0.0344326 -0.0257033 -0.0166124 -0.0343316 -0.0257033 -0.0177257 -0.0343316 -0.0283033 -0.0177257 -0.0333979 -0.0283033 -0.0194275 -0.0333979 -0.0257033 -0.0194275 -0.0331965 -0.0283033 -0.0196227 -0.0317383 -0.0257033 -0.0204344 -0.0187769 -0.0257033 -0.0262218 -0.0190515 -0.0257033 -0.0262783 -0.0203207 -0.0283033 -0.0268558 -0.0207533 -0.0283033 -0.027212 -0.0214365 -0.0257033 -0.0280968 -0.0214365 -0.0283033 -0.0280968 -0.0217603 -0.0283033 -0.0288716 -0.0217603 -0.0257033 -0.0288716 -0.0219035 -0.0283033 -0.029699 -0.0218025 -0.0257033 -0.0308123 -0.0208687 -0.0257033 -0.0325141 -0.0208687 -0.0283033 -0.0325141 -0.0206674 -0.0257033 -0.0327093 -0.0192092 -0.0257033 -0.033521 -0.00327353 -0.0283033 -0.037778 -0.00327353 -0.0257033 -0.037778 -0.00423511 -0.0283033 -0.036414 -0.00423511 -0.0257033 -0.036414 -0.00450963 -0.0283033 -0.0347678 -0.00450963 -0.0257033 -0.0347678 -0.00292684 -0.0257033 -0.0319245 -0.00138302 -0.0283033 -0.0312906 -0.00138302 -0.0257033 -0.0312906 0.0157825 -0.0283033 -0.0342825 0.0133628 -0.0257033 -0.0321067 0.0131892 -0.0257033 -0.0315738 0.0130883 -0.0283033 -0.0304606 0.0132314 -0.0257033 -0.0296331 0.0135552 -0.0283033 -0.0288583 0.014671 -0.0283033 -0.0276173 0.014671 -0.0257033 -0.0276173 0.0159402 -0.0257033 -0.0270398 0.0178808 -0.0257033 -0.027082 0.0288691 -0.0257033 -0.0217534 0.0272096 -0.0283033 -0.0207465 0.0272096 -0.0257033 -0.0207465 0.0262758 -0.0283033 -0.0190447 0.027325 -0.0283033 -0.0154444 0.027325 -0.0257033 -0.0154444 0.0290268 -0.0257033 -0.0145107 0.0339379 -0.0283033 -0.00435957 0.0322783 -0.0257033 -0.00335265 0.0313446 -0.0257033 -0.00165086 0.0323937 -0.0257033 0.00194939 0.0340955 -0.0283033 0.00288316 0.0340955 -0.0257033 0.00288316 0.0296307 -0.0283033 0.0132383 0.0296307 -0.0257033 0.0132383 0.0279711 -0.0283033 0.0142452 0.0279711 -0.0257033 0.0142452 0.0270373 -0.0257033 0.015947 0.0280865 -0.0283033 0.0195473 0.0297883 -0.0283033 0.020481 0.0297883 -0.0257033 0.020481 0.031729 -0.0257033 0.0204388 0.015442 -0.0283033 0.0273318 0.0145082 -0.0257033 0.0290336 0.0145504 -0.0257033 0.0309743 0.0172592 -0.0283033 0.0335676 0.0191998 -0.0257033 0.0335254 -0.00195186 -0.0257033 0.0324006 -0.00288563 -0.0283033 0.0341024 -0.00288563 -0.0257033 0.0341024 -0.00284339 -0.0257033 0.0360431 -0.00284339 -0.0283033 0.0360431 -0.000134676 -0.0257033 0.0386364 -0.0178902 -0.0257033 0.0270864 -0.0193484 -0.0283033 0.0278982 -0.0195497 -0.0257033 0.0280933 -0.0204835 -0.0257033 0.0297951 -0.0205845 -0.0283033 0.0309084 -0.0204413 -0.0257033 0.0317358 -0.0204413 -0.0283033 0.0317358 -0.0201176 -0.0283033 0.0325106 -0.0190017 -0.0283033 0.0337516 -0.0177326 -0.0283033 0.0343292 -0.0177326 -0.0257033 0.0343292 -0.0157919 -0.0257033 0.0342869 -0.0157919 -0.0283033 0.0342869 -0.0309768 -0.0283033 0.0145573 -0.0326363 -0.0257033 0.0155642 -0.0333965 -0.0257033 0.0167331 -0.0335701 -0.0257033 0.017266 -0.0336711 -0.0257033 0.0183793 -0.0335279 -0.0257033 0.0192067 -0.0336711 -0.0283033 0.0183793 -0.0332041 -0.0257033 0.0199815 -0.0325209 -0.0257033 0.0208663 -0.0305445 -0.0283033 0.0218565 -0.0308191 -0.0257033 0.0218 -0.00735954 -0.0265033 -0.0081774 -0.00735954 -0.0283033 -0.0081774 -0.0101802 -0.0283033 -0.00417621 -0.0101802 -0.0265033 -0.00417621 -0.00634257 -0.0283033 0.0089928 -0.00634257 -0.0265033 0.0089928 -0.00181405 -0.0265033 0.0108524 0.00307285 -0.0265033 0.0105629 0.00825353 -0.0283033 -0.012206 -0.000325099 -0.0258033 -0.029196 0.0203683 -0.0258033 -0.0169252 0.0220206 -0.0283033 -0.0169791 0.0238064 -0.0283033 -0.0162734 0.023881 -0.0258033 -0.0162216 -0.0260225 -0.0258033 -0.00341512 -0.0244673 -0.0283033 -0.00357887 -0.014328 -0.0258033 -0.0252847 -0.0136973 -0.0258033 -0.0254192 -0.0118708 -0.0258033 -0.0252861 -0.0091347 -0.0283033 -0.0229736 -0.0134404 -0.0283033 -0.00588281 -0.0134404 -0.0258033 -0.00588281 -0.0116221 -0.0258033 -0.00725898 -0.00946677 -0.0255033 0.0386611 -0.00956439 -0.0281533 0.0357559 -0.0116451 -0.0255033 0.0374659 -0.0129339 -0.0255033 0.0353416 -0.0102042 -0.0281533 0.0350444 -0.0103898 -0.0281533 0.0346002 -0.012988 -0.0255033 0.0328575 -0.00966853 -0.0255033 0.0293904 -0.0117928 -0.0255033 0.0306792 -0.0103145 -0.0281533 0.033182 -0.0104719 -0.0281533 0.0341258 0.00690388 -0.0260033 -0.0414257 0.00690388 -0.0258033 -0.0414257 0.0159492 -0.0260033 -0.0388497 0.0312265 -0.0258033 -0.02808 0.0419219 -0.0258033 -0.00248105 0.0419219 -0.0260033 -0.00248105 0.0414232 -0.0258033 0.00691074 0.0388473 -0.0260033 0.0159561 0.0388473 -0.0258033 0.0159561 0.0280776 -0.0260033 0.0312334 0.0204239 -0.0260033 0.0366993 0.0204239 -0.0258033 0.0366993 0.0116619 -0.0255033 0.0400369 0.0280776 -0.0258033 0.0312334 0.0343231 -0.0258033 0.0242015 0.0340779 -0.0255033 0.0240286 0.0416224 -0.0255033 -0.00246331 0.0366924 -0.0258033 -0.0204264 0.0403181 -0.0258033 -0.0117483 0.0400301 -0.0255033 -0.0116644 0.0411374 -0.0255033 -0.00679623 0.0240218 -0.0255033 -0.0340804 0.0205214 -0.0255033 -0.0362962 0.0241946 -0.0258033 -0.0343256 0.020083 -0.0255033 -0.0365406 0.0159492 -0.0258033 -0.0388497 0.0158353 -0.0255033 -0.0385722 -0.00680309 -0.0255033 -0.0411399 -0.00248791 -0.0258033 -0.0419243 -0.00284876 -0.0255033 -0.0416007 -0.00247017 -0.0255033 -0.0416249 -0.0256466 -0.0281533 0.0236848 -0.0286493 -0.0255033 0.0234602 -0.0263553 -0.0281533 0.0254107 -0.028403 -0.0255033 0.0276182 -0.0245627 -0.0281533 0.0274043 -0.0236076 -0.0281533 0.0273477 -0.0249986 -0.0255033 0.0300182 -0.0368164 -0.0255033 0.00622501 -0.0355958 -0.0281533 0.0089776 -0.0357532 -0.0281533 0.00992141 -0.0380472 -0.0255033 0.00797099 -0.0354855 -0.0281533 0.01084 -0.0348457 -0.0281533 0.0115515 -0.0378009 -0.0255033 0.012129 -0.0330055 -0.0281533 0.0118584 -0.0343965 -0.0255033 0.0145289 -0.0257972 -0.0281533 -0.0221139 -0.0280517 -0.0255033 -0.020279 -0.0300776 -0.0255033 -0.0239184 -0.0273502 -0.0281533 -0.0236007 -0.0266289 -0.0255033 -0.0288105 -0.0267236 -0.0281533 -0.0258009 -0.0284954 -0.0255033 -0.0277715 -0.026839 -0.0281533 -0.025689 -0.0110355 -0.0281533 -0.0318429 -0.0112836 -0.0281533 -0.0320471 -0.0116753 -0.0281533 -0.0325544 -0.0118609 -0.0281533 -0.0329986 -0.011943 -0.0281533 -0.033473 -0.0144051 -0.0255033 -0.0322572 -0.0111397 -0.0255033 -0.0382084 -0.0117856 -0.0281533 -0.0344168 0.00676329 -0.0281533 -0.0354811 0.00484913 -0.0255033 -0.0373138 0.00622793 -0.0281533 -0.0345054 0.00365391 -0.0255033 -0.0351355 0.00717512 -0.0255033 -0.0293319 0.0096592 -0.0255033 -0.029386 0.0321601 -0.0281533 -0.0113886 0.0291574 -0.0255033 -0.0116132 0.028806 -0.0255033 -0.0095061 0.0328081 -0.0255033 -0.00505528 0.0350492 -0.0255033 0.0130052 0.0333903 -0.0281533 0.006259 0.0315061 -0.0255033 0.00421688 0.0318456 -0.0281533 0.00845026 0.0297979 -0.0255033 0.0106578 0.0327531 -0.0281533 0.0100804 0.0239338 -0.0255033 0.0195983 0.0220673 -0.0255033 0.0206373 0.0231305 -0.0281533 0.0243337 0.0204851 -0.0255033 0.0244904 0.0233981 -0.0281533 0.0252523 0.0210827 -0.0255033 0.0265413 0.0225111 -0.0255033 0.0281298 0.024923 -0.0281533 0.0263273 0.0278936 -0.0255033 0.00271788 0.0291799 -0.0258033 -0.000947949 0.00930953 -0.0258033 -0.0127848 -0.0124045 -0.0258033 -0.00640343 0.00468108 -0.0255033 0.0264163 0.0021027 -0.0258033 0.0287997 0.0288132 -0.0255033 -0.0219454 0.0262758 -0.0257033 -0.0190447 0.0260815 -0.0255033 -0.0190922 0.026318 -0.0257033 -0.017104 0.026126 -0.0255033 -0.017048 0.0271866 -0.0255033 -0.0153 0.0130394 -0.0255033 -0.0295772 0.0142384 -0.0257033 -0.0279736 0.0141001 -0.0255033 -0.0278291 0.0135552 -0.0257033 -0.0288583 0.014123 -0.0257033 -0.0332756 0.0139785 -0.0255033 -0.0334139 0.0130883 -0.0257033 -0.0304606 -0.0018713 -0.0255033 -0.0387818 -0.00340726 -0.0255033 -0.0379267 -0.00470928 -0.0255033 -0.034756 -0.00404271 -0.0257033 -0.0331655 -0.00304207 -0.0255033 -0.0317611 -0.0171109 -0.0257033 -0.0263205 -0.0204359 -0.0255033 -0.0266923 -0.0203207 -0.0257033 -0.0268558 -0.0207533 -0.0257033 -0.027212 -0.0221031 -0.0255033 -0.0296872 -0.0219035 -0.0257033 -0.029699 -0.0216289 -0.0257033 -0.0313452 -0.0313389 -0.0255033 -0.012938 -0.031306 -0.0257033 -0.0131352 -0.0315807 -0.0257033 -0.0131917 -0.0328498 -0.0257033 -0.0137692 -0.0332825 -0.0257033 -0.0141254 -0.0341404 -0.0255033 -0.0149129 -0.0342894 -0.0257033 -0.015785 -0.0341581 -0.0257033 -0.0182586 -0.0331965 -0.0257033 -0.0196227 -0.0388331 -0.0255033 -0.000175362 -0.0387886 -0.0255033 0.00186882 -0.037728 -0.0255033 0.0036169 -0.0375897 -0.0257033 0.00347243 -0.0359355 -0.0255033 0.00460046 -0.0288785 -0.0257033 0.0217578 -0.0320883 -0.0257033 0.0212225 -0.0309768 -0.0257033 0.0145573 -0.0310327 -0.0255033 0.0143653 -0.0337644 -0.0255033 0.0172185 -0.0206333 -0.0255033 0.0317918 -0.0194344 -0.0257033 0.0333954 -0.0177801 -0.0255033 0.0345234 -0.00307989 -0.0255033 0.0340548 -0.00303541 -0.0255033 0.036099 -0.00183647 -0.0257033 0.0377026 -0.00197479 -0.0255033 0.0378471 -0.000182225 -0.0255033 0.0388307 0.00186196 -0.0255033 0.0387862 0.0171015 -0.0257033 0.0263249 0.0170456 -0.0255033 0.0261329 0.015442 -0.0257033 0.0273318 0.0152975 -0.0255033 0.0271935 0.0143139 -0.0255033 0.0289861 0.0155574 -0.0257033 0.0326339 0.0143584 -0.0255033 0.0310303 0.015419 -0.0255033 0.0327783 0.0172592 -0.0257033 0.0335676 0.0268431 -0.0255033 0.0158995 0.0270796 -0.0257033 0.0178877 0.0280865 -0.0257033 0.0195473 0.0279482 -0.0255033 0.0196917 0.0338819 -0.0255033 -0.00455158 0.0313868 -0.0257033 0.000289828 0.0322554 -0.0255033 0.00209386 0.034048 -0.0255033 0.00307742 0.0360362 -0.0257033 0.00284092 -0.0164134 -0.0289033 -0.0563057 -0.00511301 -0.0289033 -0.0584249 -0.00513043 -0.0287033 -0.0586242 0.0282083 -0.0289033 -0.0514162 0.037826 -0.0287033 -0.0450774 0.0457377 -0.0289033 -0.0367056 0.0521975 -0.0287033 -0.0271687 0.0520201 -0.0289033 -0.0270764 0.0584224 -0.0289033 -0.00510615 0.0586217 -0.0287033 -0.00512357 0.0584952 -0.0287033 0.00641236 0.0559298 -0.0289033 0.0176418 0.0450749 -0.0287033 0.0378328 0.0449217 -0.0289033 0.0377043 0.0367031 -0.0289033 0.0457445 0.0368283 -0.0287033 0.0459005 0.0271663 -0.0287033 0.0522043 0.0270739 -0.0289033 0.0520269 -0.00513043 -0.0282033 -0.0586242 0.00640549 -0.0287033 -0.0584977 0.0176951 -0.0282033 -0.056123 0.0176951 -0.0287033 -0.056123 0.0283045 -0.0287033 -0.0515916 0.0458936 -0.0282033 -0.0368308 0.0458936 -0.0287033 -0.0368308 0.0521975 -0.0282033 -0.0271687 0.0564952 -0.0287033 -0.0164625 0.0561206 -0.0287033 0.0177019 0.0515891 -0.0287033 0.0283113 0.0368283 -0.0282033 0.0459005 0.0271663 -0.0282033 0.0522043 0.01646 -0.0282033 0.0565021 0.01646 -0.0287033 0.0565021 0.0156067 -0.0260033 0.0535739 0.0450749 -0.0282033 0.0378328 0.0427386 -0.0260033 0.0358722 0.0515891 -0.0282033 0.0283113 0.0561206 -0.0282033 0.0177019 0.0489152 -0.0260033 0.0268442 0.0584952 -0.0282033 0.00641236 0.0532118 -0.0260033 0.0167846 0.0586217 -0.0282033 -0.00512357 0.0554633 -0.0260033 0.00608014 0.0555833 -0.0260033 -0.00485792 0.0564952 -0.0282033 -0.0164625 0.053567 -0.0260033 -0.0156092 0.049492 -0.0260033 -0.0257605 0.0435149 -0.0260033 -0.0349218 0.037826 -0.0282033 -0.0450774 0.0358653 -0.0260033 -0.042741 0.0283045 -0.0282033 -0.0515916 0.00640549 -0.0282033 -0.0584977 0.00607328 -0.0260033 -0.0554658 -0.00486478 -0.0260033 -0.0555857 -0.00500849 -0.0293033 -0.0572295 0.027631 -0.0289033 -0.0503642 0.036926 -0.0289033 -0.0440049 0.036926 -0.0293033 -0.0440049 0.0448018 -0.0293033 -0.0359545 0.0509556 -0.0289033 -0.0265223 0.0509556 -0.0293033 -0.0265223 0.0551511 -0.0293033 -0.0160708 0.0551511 -0.0289033 -0.0160708 0.0547854 -0.0289033 0.0172809 0.0503617 -0.0289033 0.0276379 0.0547854 -0.0293033 0.0172809 0.0359521 -0.0289033 0.0448086 0.0265199 -0.0289033 0.0509625 0.00546369 -0.0791033 0.0537246 -0.00435662 -0.0791033 0.0538265 -0.014033 -0.0791033 0.0521482 -0.0232454 -0.0791033 0.0487451 -0.0136433 -0.0806033 0.0506997 -0.0225998 -0.0806033 0.0473911 -0.0390847 -0.0791033 0.0372681 0.0237062 -0.0413033 0.0813678 0.0368619 -0.0415033 0.0765356 0.0489561 -0.0415033 0.0694237 0.0367751 -0.0413033 0.0763554 0.0595741 -0.0413033 0.060276 0.0686823 -0.0413033 0.0496476 0.076096 -0.0415033 0.0377538 0.0810805 -0.0413033 0.024655 0.0812718 -0.0415033 0.0247132 0.0842306 -0.0415033 0.0109985 0.0840323 -0.0413033 0.0109726 0.083237 -0.0415033 -0.0169485 0.083041 -0.0413033 -0.0169086 0.079125 -0.0413033 -0.0303468 0.0732229 -0.0415033 -0.0430586 0.0651366 -0.0415033 -0.0545241 0.0552734 -0.0415033 -0.0645024 0.0313337 -0.0415033 -0.0789561 0.0312599 -0.0413033 -0.0787702 0.0179102 -0.0415033 -0.0830373 0.017868 -0.0413033 -0.0828418 -0.0237155 -0.0413033 -0.0813634 -0.0237715 -0.0671033 -0.0815554 -0.0100234 -0.0671033 -0.0843549 -0.0236316 -0.0676033 -0.0810754 -0.00996442 -0.0676033 -0.0838584 0.00399798 -0.0671033 -0.0848535 0.00397442 -0.0676033 -0.084354 0.043829 -0.0676033 -0.072181 0.0439024 -0.0671033 -0.0727211 0.0553684 -0.0676033 -0.0637601 0.046834 -0.0676033 -0.0702683 0.0651366 -0.0671033 -0.0545241 0.0777313 -0.0676033 -0.0329966 0.0848917 -0.0671033 -0.00301615 0.083289 -0.0676033 -0.0139249 0.0788449 -0.0676033 -0.0302394 0.0842636 -0.0676033 0.00553969 0.0818261 -0.0676033 0.0208715 0.0837348 -0.0676033 0.0109338 0.0812718 -0.0671033 0.0247132 0.0772511 -0.0676033 0.0341101 0.0638639 -0.0676033 0.0552527 0.0548837 -0.0676033 0.0641822 0.0489561 -0.0671033 0.0694237 0.0486679 -0.0676033 0.0690151 0.0366449 -0.0676033 0.0760851 0.0236223 -0.0676033 0.0810798 0.0368619 -0.0645033 0.0765356 0.0367751 -0.0643033 0.0763554 0.0597147 -0.0645033 0.0604182 0.0595741 -0.0643033 0.060276 0.0686823 -0.0643033 0.0496476 0.0759169 -0.0643033 0.037665 0.0812718 -0.0645033 0.0247132 0.0842306 -0.0645033 0.0109985 0.0848917 -0.0645033 -0.00301615 0.083237 -0.0645033 -0.0169485 0.0793117 -0.0645033 -0.0304184 0.0732229 -0.0645033 -0.0430586 0.0552734 -0.0645033 -0.0645024 0.0551433 -0.0643033 -0.0643505 0.0439024 -0.0645033 -0.0727211 0.0179102 -0.0645033 -0.0830373 0.00398856 -0.0643033 -0.0846537 -0.00999981 -0.0643033 -0.0841563 -0.0237715 -0.0645033 -0.0815554 -0.0237155 -0.0633033 -0.0813634 -0.00999981 -0.0633033 -0.0841563 0.0313337 -0.0631033 -0.0789561 0.0551433 -0.0633033 -0.0643505 0.0651366 -0.0631033 -0.0545241 0.0649832 -0.0633033 -0.0543958 0.0793117 -0.0631033 -0.0304184 0.083237 -0.0631033 -0.0169485 0.0846918 -0.0633033 -0.00300905 0.0812718 -0.0631033 0.0247132 0.0759169 -0.0633033 0.037665 0.0688444 -0.0631033 0.0497647 0.0686823 -0.0633033 0.0496476 0.0595741 -0.0633033 0.060276 0.0597147 -0.0631033 0.0604182 0.0489561 -0.0631033 0.0694237 0.0367751 -0.0633033 0.0763554 0.0237062 -0.0633033 0.0813678 0.0237062 -0.0618033 0.0813678 0.0489561 -0.0620033 0.0694237 0.0597147 -0.0620033 0.0604182 0.0688444 -0.0620033 0.0497647 0.0759169 -0.0618033 0.037665 0.0810805 -0.0618033 0.024655 0.083237 -0.0620033 -0.0169485 0.0793117 -0.0620033 -0.0304184 0.0651366 -0.0620033 -0.0545241 0.0552734 -0.0620033 -0.0645024 0.0312599 -0.0618033 -0.0787702 0.017868 -0.0618033 -0.0828418 0.00398856 -0.0618033 -0.0846537 -0.0237715 -0.0620033 -0.0815554 -0.00999981 -0.0608033 -0.0841563 0.00398856 -0.0608033 -0.0846537 0.017868 -0.0608033 -0.0828418 0.0312599 -0.0608033 -0.0787702 0.0313337 -0.0606033 -0.0789561 0.043799 -0.0608033 -0.0725499 0.0649832 -0.0608033 -0.0543958 0.0732229 -0.0606033 -0.0430586 0.0793117 -0.0606033 -0.0304184 0.079125 -0.0608033 -0.0303468 0.083237 -0.0606033 -0.0169485 0.083041 -0.0608033 -0.0169086 0.0846918 -0.0608033 -0.00300905 0.0842306 -0.0606033 0.0109985 0.0759169 -0.0608033 0.037665 0.0686823 -0.0608033 0.0496476 0.0489561 -0.0606033 0.0694237 0.0488408 -0.0608033 0.0692603 0.0367751 -0.0608033 0.0763554 0.0237621 -0.0606033 0.0815598 0.0237062 -0.0608033 0.0813678 0.0237062 -0.0593033 0.0813678 0.0489561 -0.0595033 0.0694237 0.0595741 -0.0593033 0.060276 0.0688444 -0.0595033 0.0497647 0.0686823 -0.0593033 0.0496476 0.0812718 -0.0595033 0.0247132 0.0848917 -0.0595033 -0.00301615 0.083237 -0.0595033 -0.0169485 0.079125 -0.0593033 -0.0303468 0.0649832 -0.0593033 -0.0543958 0.0439024 -0.0595033 -0.0727211 0.0313337 -0.0595033 -0.0789561 0.0312599 -0.0593033 -0.0787702 0.0179102 -0.0595033 -0.0830373 -0.0100234 -0.0595033 -0.0843549 -0.0237715 -0.0595033 -0.0815554 -0.0237155 -0.0593033 -0.0813634 -0.0237155 -0.0583033 -0.0813634 -0.0100234 -0.0581033 -0.0843549 -0.00999981 -0.0583033 -0.0841563 0.00398856 -0.0583033 -0.0846537 0.017868 -0.0583033 -0.0828418 0.0312599 -0.0583033 -0.0787702 0.0313337 -0.0581033 -0.0789561 0.0552734 -0.0581033 -0.0645024 0.0649832 -0.0583033 -0.0543958 0.0732229 -0.0581033 -0.0430586 0.079125 -0.0583033 -0.0303468 0.083237 -0.0581033 -0.0169485 0.0688444 -0.0581033 0.0497647 0.0759169 -0.0583033 0.037665 0.0686823 -0.0583033 0.0496476 0.0595741 -0.0583033 0.060276 0.0489561 -0.0581033 0.0694237 0.0368619 -0.0581033 0.0765356 0.0237621 -0.0581033 0.0815598 0.0237062 -0.0568033 0.0813678 0.0489561 -0.0570033 0.0694237 0.0367751 -0.0568033 0.0763554 0.076096 -0.0570033 0.0377538 0.0812718 -0.0570033 0.0247132 0.0840323 -0.0568033 0.0109726 0.0793117 -0.0570033 -0.0304184 0.083041 -0.0568033 -0.0169086 0.0732229 -0.0570033 -0.0430586 0.0730505 -0.0568033 -0.0429572 0.0552734 -0.0570033 -0.0645024 0.0551433 -0.0568033 -0.0643505 0.043799 -0.0568033 -0.0725499 0.0313337 -0.0570033 -0.0789561 0.00398856 -0.0568033 -0.0846537 -0.0100234 -0.0570033 -0.0843549 -0.0237155 -0.0558033 -0.0813634 -0.00999981 -0.0558033 -0.0841563 0.00399798 -0.0556033 -0.0848535 0.00398856 -0.0558033 -0.0846537 0.0179102 -0.0556033 -0.0830373 0.0312599 -0.0558033 -0.0787702 0.0552734 -0.0556033 -0.0645024 0.0732229 -0.0556033 -0.0430586 0.083041 -0.0558033 -0.0169086 0.0848917 -0.0556033 -0.00301615 0.0846918 -0.0558033 -0.00300905 0.0810805 -0.0558033 0.024655 0.076096 -0.0556033 0.0377538 0.0759169 -0.0558033 0.037665 0.0688444 -0.0556033 0.0497647 0.0595741 -0.0558033 0.060276 0.0488408 -0.0558033 0.0692603 0.0367751 -0.0558033 0.0763554 0.0237621 -0.0556033 0.0815598 0.0237062 -0.0543033 0.0813678 0.0368619 -0.0545033 0.0765356 0.0367751 -0.0543033 0.0763554 0.0488408 -0.0543033 0.0692603 0.0597147 -0.0545033 0.0604182 0.0595741 -0.0543033 0.060276 0.0686823 -0.0543033 0.0496476 0.076096 -0.0545033 0.0377538 0.0810805 -0.0543033 0.024655 0.0846918 -0.0543033 -0.00300905 0.083237 -0.0545033 -0.0169485 0.0793117 -0.0545033 -0.0304184 0.0649832 -0.0543033 -0.0543958 0.0552734 -0.0545033 -0.0645024 0.0551433 -0.0543033 -0.0643505 0.0439024 -0.0545033 -0.0727211 0.0313337 -0.0545033 -0.0789561 0.043799 -0.0543033 -0.0725499 0.0312599 -0.0543033 -0.0787702 0.0179102 -0.0545033 -0.0830373 0.00399798 -0.0545033 -0.0848535 0.017868 -0.0543033 -0.0828418 0.00398856 -0.0543033 -0.0846537 -0.00999981 -0.0543033 -0.0841563 -0.0237155 -0.0533033 -0.0813634 -0.0100234 -0.0531033 -0.0843549 -0.00999981 -0.0533033 -0.0841563 0.00399798 -0.0531033 -0.0848535 0.017868 -0.0533033 -0.0828418 0.0313337 -0.0531033 -0.0789561 0.0312599 -0.0533033 -0.0787702 0.043799 -0.0533033 -0.0725499 0.0552734 -0.0531033 -0.0645024 0.0649832 -0.0533033 -0.0543958 0.0651366 -0.0531033 -0.0545241 0.0730505 -0.0533033 -0.0429572 0.079125 -0.0533033 -0.0303468 0.0793117 -0.0531033 -0.0304184 0.083237 -0.0531033 -0.0169485 0.083041 -0.0533033 -0.0169086 0.0848917 -0.0531033 -0.00301615 0.0846918 -0.0533033 -0.00300905 0.0810805 -0.0533033 0.024655 0.076096 -0.0531033 0.0377538 0.0688444 -0.0531033 0.0497647 0.0597147 -0.0531033 0.0604182 0.0686823 -0.0533033 0.0496476 0.0595741 -0.0533033 0.060276 0.0488408 -0.0533033 0.0692603 0.0368619 -0.0531033 0.0765356 0.0368619 -0.0520033 0.0765356 0.0367751 -0.0518033 0.0763554 0.0489561 -0.0520033 0.0694237 0.0597147 -0.0520033 0.0604182 0.0688444 -0.0520033 0.0497647 0.0686823 -0.0518033 0.0496476 0.076096 -0.0520033 0.0377538 0.0759169 -0.0518033 0.037665 0.0810805 -0.0518033 0.024655 0.0840323 -0.0518033 0.0109726 0.0846918 -0.0518033 -0.00300905 0.0848917 -0.0520033 -0.00301615 0.083237 -0.0520033 -0.0169485 0.0793117 -0.0520033 -0.0304184 0.0651366 -0.0520033 -0.0545241 0.0179102 -0.0520033 -0.0830373 0.017868 -0.0518033 -0.0828418 0.00398856 -0.0518033 -0.0846537 0.00399798 -0.0520033 -0.0848535 -0.0100234 -0.0520033 -0.0843549 -0.0237715 -0.0520033 -0.0815554 -0.00999981 -0.0508033 -0.0841563 0.0179102 -0.0506033 -0.0830373 0.017868 -0.0508033 -0.0828418 0.0312599 -0.0508033 -0.0787702 0.0439024 -0.0506033 -0.0727211 0.043799 -0.0508033 -0.0725499 0.0552734 -0.0506033 -0.0645024 0.0651366 -0.0506033 -0.0545241 0.0649832 -0.0508033 -0.0543958 0.0793117 -0.0506033 -0.0304184 0.079125 -0.0508033 -0.0303468 0.083041 -0.0508033 -0.0169086 0.0846918 -0.0508033 -0.00300905 0.076096 -0.0506033 0.0377538 0.0688444 -0.0506033 0.0497647 0.0686823 -0.0508033 0.0496476 0.0597147 -0.0506033 0.0604182 0.0595741 -0.0508033 0.060276 0.0367751 -0.0508033 0.0763554 0.0489561 -0.0495033 0.0694237 0.0367751 -0.0493033 0.0763554 0.0488408 -0.0493033 0.0692603 0.0597147 -0.0495033 0.0604182 0.0595741 -0.0493033 0.060276 0.0688444 -0.0495033 0.0497647 0.0810805 -0.0493033 0.024655 0.0840323 -0.0493033 0.0109726 0.0842306 -0.0495033 0.0109985 0.0848917 -0.0495033 -0.00301615 0.083041 -0.0493033 -0.0169086 0.0732229 -0.0495033 -0.0430586 0.0730505 -0.0493033 -0.0429572 0.0651366 -0.0495033 -0.0545241 0.0552734 -0.0495033 -0.0645024 0.0551433 -0.0493033 -0.0643505 0.043799 -0.0493033 -0.0725499 0.0313337 -0.0495033 -0.0789561 0.0312599 -0.0493033 -0.0787702 0.017868 -0.0493033 -0.0828418 -0.0100234 -0.0495033 -0.0843549 -0.00999981 -0.0493033 -0.0841563 -0.0100234 -0.0481033 -0.0843549 0.00399798 -0.0481033 -0.0848535 0.0313337 -0.0481033 -0.0789561 0.0312599 -0.0483033 -0.0787702 0.043799 -0.0483033 -0.0725499 0.0651366 -0.0481033 -0.0545241 0.0732229 -0.0481033 -0.0430586 0.079125 -0.0483033 -0.0303468 0.083237 -0.0481033 -0.0169485 0.083041 -0.0483033 -0.0169086 0.0840323 -0.0483033 0.0109726 0.0812718 -0.0481033 0.0247132 0.0810805 -0.0483033 0.024655 0.076096 -0.0481033 0.0377538 0.0759169 -0.0483033 0.037665 0.0688444 -0.0481033 0.0497647 0.0686823 -0.0483033 0.0496476 0.0597147 -0.0481033 0.0604182 0.0489561 -0.0481033 0.0694237 0.0488408 -0.0483033 0.0692603 0.0368619 -0.0481033 0.0765356 0.0367751 -0.0483033 0.0763554 0.0367751 -0.0468033 0.0763554 0.0597147 -0.0470033 0.0604182 0.0688444 -0.0470033 0.0497647 0.076096 -0.0470033 0.0377538 0.0812718 -0.0470033 0.0247132 0.0842306 -0.0470033 0.0109985 0.0840323 -0.0468033 0.0109726 0.0848917 -0.0470033 -0.00301615 0.0793117 -0.0470033 -0.0304184 0.0649832 -0.0468033 -0.0543958 0.043799 -0.0468033 -0.0725499 0.0313337 -0.0470033 -0.0789561 0.017868 -0.0468033 -0.0828418 0.00398856 -0.0468033 -0.0846537 -0.0237715 -0.0470033 -0.0815554 -0.0237155 -0.0458033 -0.0813634 0.0179102 -0.0456033 -0.0830373 0.017868 -0.0458033 -0.0828418 0.0312599 -0.0458033 -0.0787702 0.0551433 -0.0458033 -0.0643505 0.0651366 -0.0456033 -0.0545241 0.0649832 -0.0458033 -0.0543958 0.0730505 -0.0458033 -0.0429572 0.0732229 -0.0456033 -0.0430586 0.079125 -0.0458033 -0.0303468 0.0848917 -0.0456033 -0.00301615 0.0840323 -0.0458033 0.0109726 0.0812718 -0.0456033 0.0247132 0.0686823 -0.0458033 0.0496476 0.0595741 -0.0458033 0.060276 0.0489561 -0.0456033 0.0694237 0.0368619 -0.0456033 0.0765356 0.0237621 -0.0456033 0.0815598 -0.00996442 -0.0633033 -0.0838584 0.00397442 -0.0643033 -0.084354 0.0178047 -0.0633033 -0.0825486 0.0178047 -0.0643033 -0.0825486 0.043644 -0.0633033 -0.072293 0.0311492 -0.0643033 -0.0784914 0.043644 -0.0643033 -0.072293 0.054948 -0.0633033 -0.0641227 0.0647532 -0.0643033 -0.0542032 0.0727919 -0.0633033 -0.0428051 0.0788449 -0.0643033 -0.0302394 0.0827471 -0.0633033 -0.0168487 0.084392 -0.0633033 -0.00299839 0.0837348 -0.0643033 0.0109338 0.0837348 -0.0633033 0.0109338 0.0807935 -0.0643033 0.0245677 0.0593632 -0.0633033 0.0600626 0.0486679 -0.0643033 0.0690151 0.0366449 -0.0633033 0.0760851 0.0366449 -0.0643033 0.0760851 0.0236223 -0.0643033 0.0810798 0.00397442 -0.0608033 -0.084354 -0.00996442 -0.0618033 -0.0838584 0.00397442 -0.0618033 -0.084354 0.0178047 -0.0618033 -0.0825486 0.054948 -0.0608033 -0.0641227 0.0647532 -0.0618033 -0.0542032 0.0647532 -0.0608033 -0.0542032 0.0727919 -0.0608033 -0.0428051 0.0788449 -0.0608033 -0.0302394 0.0727919 -0.0618033 -0.0428051 0.0827471 -0.0608033 -0.0168487 0.0827471 -0.0618033 -0.0168487 0.084392 -0.0608033 -0.00299839 0.0837348 -0.0608033 0.0109338 0.0837348 -0.0618033 0.0109338 0.0807935 -0.0618033 0.0245677 0.0486679 -0.0608033 0.0690151 0.0366449 -0.0608033 0.0760851 0.0486679 -0.0618033 0.0690151 0.00397442 -0.0583033 -0.084354 0.0178047 -0.0593033 -0.0825486 0.0311492 -0.0593033 -0.0784914 0.0311492 -0.0583033 -0.0784914 0.043644 -0.0583033 -0.072293 0.054948 -0.0583033 -0.0641227 0.0647532 -0.0583033 -0.0542032 0.0647532 -0.0593033 -0.0542032 0.0727919 -0.0593033 -0.0428051 0.0788449 -0.0593033 -0.0302394 0.084392 -0.0593033 -0.00299839 0.084392 -0.0583033 -0.00299839 0.0807935 -0.0583033 0.0245677 0.0684392 -0.0583033 0.0494718 0.0684392 -0.0593033 0.0494718 0.0593632 -0.0593033 0.0600626 0.0486679 -0.0583033 0.0690151 0.0236223 -0.0583033 0.0810798 0.0236223 -0.0593033 0.0810798 0.00397442 -0.0558033 -0.084354 0.00397442 -0.0568033 -0.084354 0.043644 -0.0558033 -0.072293 0.0311492 -0.0568033 -0.0784914 0.043644 -0.0568033 -0.072293 0.054948 -0.0558033 -0.0641227 0.0788449 -0.0558033 -0.0302394 0.0727919 -0.0568033 -0.0428051 0.0827471 -0.0558033 -0.0168487 0.0827471 -0.0568033 -0.0168487 0.084392 -0.0568033 -0.00299839 0.084392 -0.0558033 -0.00299839 0.0837348 -0.0558033 0.0109338 0.0684392 -0.0558033 0.0494718 0.0684392 -0.0568033 0.0494718 0.0593632 -0.0568033 0.0600626 0.0486679 -0.0558033 0.0690151 0.0366449 -0.0558033 0.0760851 0.0366449 -0.0568033 0.0760851 -0.0236316 -0.0543033 -0.0810754 0.00397442 -0.0533033 -0.084354 0.0178047 -0.0543033 -0.0825486 0.0311492 -0.0533033 -0.0784914 0.0311492 -0.0543033 -0.0784914 0.054948 -0.0533033 -0.0641227 0.0647532 -0.0543033 -0.0542032 0.0727919 -0.0533033 -0.0428051 0.0788449 -0.0533033 -0.0302394 0.084392 -0.0543033 -0.00299839 0.0807935 -0.0533033 0.0245677 0.0756481 -0.0533033 0.0375316 0.0807935 -0.0543033 0.0245677 0.0684392 -0.0533033 0.0494718 0.0684392 -0.0543033 0.0494718 0.0593632 -0.0543033 0.0600626 0.0593632 -0.0533033 0.0600626 0.0236223 -0.0533033 0.0810798 0.0366449 -0.0543033 0.0760851 -0.0236316 -0.0508033 -0.0810754 -0.00996442 -0.0508033 -0.0838584 0.0178047 -0.0518033 -0.0825486 0.0311492 -0.0518033 -0.0784914 0.054948 -0.0518033 -0.0641227 0.0647532 -0.0518033 -0.0542032 0.0788449 -0.0518033 -0.0302394 0.0788449 -0.0508033 -0.0302394 0.0827471 -0.0508033 -0.0168487 0.0837348 -0.0508033 0.0109338 0.0684392 -0.0508033 0.0494718 0.0593632 -0.0508033 0.0600626 0.0486679 -0.0508033 0.0690151 0.0593632 -0.0518033 0.0600626 0.0236223 -0.0518033 0.0810798 -0.0236316 -0.0483033 -0.0810754 -0.00996442 -0.0483033 -0.0838584 -0.00996442 -0.0493033 -0.0838584 0.00397442 -0.0493033 -0.084354 0.0178047 -0.0483033 -0.0825486 0.0178047 -0.0493033 -0.0825486 0.043644 -0.0483033 -0.072293 0.043644 -0.0493033 -0.072293 0.0647532 -0.0483033 -0.0542032 0.0727919 -0.0493033 -0.0428051 0.084392 -0.0483033 -0.00299839 0.0837348 -0.0483033 0.0109338 0.0837348 -0.0493033 0.0109338 0.0807935 -0.0493033 0.0245677 0.0756481 -0.0483033 0.0375316 0.0684392 -0.0493033 0.0494718 0.0486679 -0.0493033 0.0690151 0.0366449 -0.0493033 0.0760851 0.0366449 -0.0483033 0.0760851 0.00397442 -0.0458033 -0.084354 0.0311492 -0.0468033 -0.0784914 0.043644 -0.0468033 -0.072293 0.054948 -0.0458033 -0.0641227 0.0647532 -0.0468033 -0.0542032 0.0727919 -0.0468033 -0.0428051 0.0727919 -0.0458033 -0.0428051 0.0788449 -0.0468033 -0.0302394 0.0827471 -0.0468033 -0.0168487 0.0827471 -0.0458033 -0.0168487 0.084392 -0.0468033 -0.00299839 0.0837348 -0.0468033 0.0109338 0.0807935 -0.0468033 0.0245677 0.0756481 -0.0458033 0.0375316 0.0684392 -0.0458033 0.0494718 0.0684392 -0.0468033 0.0494718 0.0486679 -0.0468033 0.0690151 0.0489561 -0.0445033 0.0694237 0.0488408 -0.0443033 0.0692603 0.0597147 -0.0445033 0.0604182 0.0688444 -0.0445033 0.0497647 0.0759169 -0.0443033 0.037665 0.0812718 -0.0445033 0.0247132 0.0840323 -0.0443033 0.0109726 0.0848917 -0.0445033 -0.00301615 0.0793117 -0.0445033 -0.0304184 0.0730505 -0.0443033 -0.0429572 0.0649832 -0.0443033 -0.0543958 0.043799 -0.0443033 -0.0725499 0.0439024 -0.0445033 -0.0727211 0.0312599 -0.0443033 -0.0787702 0.017868 -0.0443033 -0.0828418 -0.0100234 -0.0445033 -0.0843549 -0.00999981 -0.0443033 -0.0841563 0.017868 -0.0433033 -0.0828418 0.0313337 -0.0431033 -0.0789561 0.0793117 -0.0431033 -0.0304184 0.079125 -0.0433033 -0.0303468 0.083237 -0.0431033 -0.0169485 0.0840323 -0.0433033 0.0109726 0.0842306 -0.0431033 0.0109985 0.0812718 -0.0431033 0.0247132 0.0810805 -0.0433033 0.024655 0.0688444 -0.0431033 0.0497647 0.0595741 -0.0433033 0.060276 0.0367751 -0.0433033 0.0763554 -0.00996442 -0.0433033 -0.0838584 0.00397442 -0.0443033 -0.084354 0.0178047 -0.0443033 -0.0825486 0.0311492 -0.0433033 -0.0784914 0.043644 -0.0433033 -0.072293 0.0311492 -0.0443033 -0.0784914 0.043644 -0.0443033 -0.072293 0.054948 -0.0443033 -0.0641227 0.0647532 -0.0433033 -0.0542032 0.0647532 -0.0443033 -0.0542032 0.0727919 -0.0443033 -0.0428051 0.0788449 -0.0443033 -0.0302394 0.0788449 -0.0433033 -0.0302394 0.0827471 -0.0433033 -0.0168487 0.0827471 -0.0443033 -0.0168487 0.084392 -0.0433033 -0.00299839 0.084392 -0.0443033 -0.00299839 0.0837348 -0.0433033 0.0109338 0.0807935 -0.0433033 0.0245677 0.0807935 -0.0443033 0.0245677 0.0756481 -0.0443033 0.0375316 0.0684392 -0.0433033 0.0494718 0.0684392 -0.0443033 0.0494718 0.0486679 -0.0443033 0.0690151 0.0366449 -0.0443033 0.0760851 0.0236223 -0.0433033 0.0810798 -0.0433119 -0.0722283 0.00151124 -0.0529126 -0.0722283 0.00430898 -0.0530406 -0.0717708 0.00386972 -0.0532154 -0.0716033 0.00326968 -0.0533903 -0.0717708 0.00266964 -0.0439176 -0.0722283 -0.000567366 -0.0535183 -0.0722283 0.00223038 -0.0434399 -0.0717708 0.00107198 -0.0436148 -0.0716033 0.000471936 -0.0437896 -0.0717708 -0.000128105 -0.0368652 -0.0717708 0.0236335 -0.0464659 -0.0717708 0.0264313 -0.0370401 -0.0716033 0.0230335 -0.0466407 -0.0716033 0.0258312 -0.0468156 -0.0717708 0.0252312 -0.0373898 -0.0728533 0.0218334 -0.0469436 -0.0722283 0.0247919 -0.0366904 -0.0728533 0.0242336 -0.0367372 -0.0722283 0.0240728 -0.037343 -0.0722283 0.0219942 -0.0372149 -0.0717708 0.0224334 -0.036319 -0.0728533 0.0228234 0.0367279 -0.0722283 -0.0240684 0.0463285 -0.0722283 -0.0268661 0.0368559 -0.0717708 -0.0236291 0.0464566 -0.0717708 -0.0264269 0.0466314 -0.0716033 -0.0258268 0.0372056 -0.0717708 -0.0224291 0.0373336 -0.0722283 -0.0219898 0.0469343 -0.0722283 -0.0247875 0.0373805 -0.0728533 -0.021829 0.0370308 -0.0716033 -0.0230291 0.036681 -0.0728533 -0.0242292 0.0363097 -0.0728533 -0.022819 0.0433026 -0.0722283 -0.00150685 0.0434306 -0.0717708 -0.00106758 0.0437803 -0.0717708 0.000132497 0.053381 -0.0717708 -0.00266524 0.0535558 -0.0728533 -0.0020652 0.0436054 -0.0716033 -0.000467544 0.0428844 -0.0728533 -0.000257412 0.0439083 -0.0722283 0.000571758 -0.0812852 -0.0420533 0.000563402 -0.0805858 -0.0420533 0.00296357 -0.081411 -0.0413033 0.00370614 -0.0818384 -0.0528533 0.000899042 -0.0818384 -0.0420533 0.000899042 -0.0821497 -0.0528533 0.00146631 -0.0821497 -0.0420533 0.00146631 -0.0821356 -0.0528533 0.0021132 -0.0821356 -0.0420533 0.0021132 -0.0817999 -0.0528533 0.00266639 -0.0812327 -0.0528533 0.00297765 -0.0817999 -0.0420533 0.00266639 -0.0812327 -0.0420533 0.00297765 -0.0823186 -0.0536033 0.00320813 -0.0828556 -0.0536033 0.00232303 -0.0706238 -0.0420533 -0.0377378 -0.071449 -0.0413033 -0.0369952 -0.0712707 -0.0420533 -0.0377237 -0.0723566 -0.0413033 -0.0374933 -0.0718379 -0.0420533 -0.038035 -0.0721736 -0.0420533 -0.0385882 -0.0729161 -0.0413033 -0.0394134 -0.071533 -0.0413033 -0.040858 -0.0724181 -0.0413033 -0.040321 -0.0722213 -0.0420533 -0.038864 -0.0718764 -0.0420533 -0.0398023 -0.0721298 -0.0528533 -0.0394127 -0.0721298 -0.0420533 -0.0394127 -0.0721876 -0.0420533 -0.0392351 -0.0722213 -0.0528533 -0.038864 -0.0720656 -0.0528533 -0.0383299 -0.0720656 -0.0420533 -0.0383299 -0.0716937 -0.0420533 -0.0379162 -0.0716937 -0.0528533 -0.0379162 -0.0711791 -0.0528533 -0.0377049 -0.0713025 -0.0536033 -0.0369651 -0.0721258 -0.0536033 -0.0373032 -0.0718093 -0.0528533 -0.0398674 -0.0434401 -0.0413033 -0.0705884 -0.0428983 -0.0420533 -0.0700698 -0.0431955 -0.0420533 -0.0688556 -0.0439381 -0.0413033 -0.0696808 -0.0439155 -0.0413033 -0.0686458 -0.0423451 -0.0420533 -0.0704054 -0.0432096 -0.0528533 -0.0695025 -0.0432096 -0.0420533 -0.0695025 -0.0428598 -0.0528533 -0.0683024 -0.0428598 -0.0420533 -0.0683024 -0.0422926 -0.0528533 -0.0679912 -0.0422926 -0.0420533 -0.0679912 -0.0416457 -0.0528533 -0.0680052 -0.0431955 -0.0528533 -0.0688556 -0.0439155 -0.0536033 -0.0686458 -0.0439381 -0.0536033 -0.0696808 -0.0428983 -0.0528533 -0.0700698 -0.0434401 -0.0536033 -0.0705884 -0.0801521 -0.0676033 0.00445167 -0.0813467 -0.0673033 0.00422943 -0.0813961 -0.0676033 0.00452535 -0.083382 -0.0676033 0.00312539 -0.0835256 -0.0676033 0.000699891 -0.0826071 -0.0673033 -9.55153e-05 -0.0802361 -0.0536033 0.00416365 -0.0813467 -0.0536033 0.00422943 -0.0823759 -0.0536033 0.0038068 -0.0823759 -0.0673033 0.0038068 -0.0831199 -0.0536033 0.00297947 -0.0834311 -0.0536033 0.0019113 -0.0831199 -0.0673033 0.00297947 -0.0832481 -0.0536033 0.000813847 -0.0834311 -0.0673033 0.0019113 -0.0832481 -0.0673033 0.000813847 -0.0816349 -0.0536033 -0.00063668 -0.0715678 -0.0673033 -0.0365096 -0.0716392 -0.0676033 -0.0362182 -0.0727024 -0.0673033 -0.0371321 -0.0729098 -0.0676033 -0.0369154 -0.0736932 -0.0676033 -0.0396036 -0.072996 -0.0676033 -0.0408743 -0.0733736 -0.0536033 -0.0382385 -0.0733736 -0.0673033 -0.0382385 -0.0734018 -0.0673033 -0.0395323 -0.0734018 -0.0536033 -0.0395323 -0.0727793 -0.0536033 -0.0406668 -0.0716729 -0.0536033 -0.0413381 -0.0727793 -0.0673033 -0.0406668 -0.0716729 -0.0673033 -0.0413381 -0.0434358 -0.0673033 -0.067162 -0.0436087 -0.0676033 -0.0669168 -0.044491 -0.0673033 -0.0690575 -0.0445855 -0.0676033 -0.0702689 -0.0438676 -0.0676033 -0.0712874 -0.0426948 -0.0673033 -0.0716055 -0.0427788 -0.0676033 -0.0718935 -0.041296 -0.0536033 -0.0668052 -0.041296 -0.0673033 -0.0668052 -0.0424066 -0.0673033 -0.0667394 -0.0441798 -0.0536033 -0.0679893 -0.0441798 -0.0673033 -0.0679893 -0.044491 -0.0536033 -0.0690575 -0.044308 -0.0536033 -0.070155 -0.044308 -0.0673033 -0.070155 -0.043667 -0.0536033 -0.0710643 -0.0426948 -0.0536033 -0.0716055 -0.043667 -0.0673033 -0.0710643 -0.0814508 -0.0676033 -0.00251518 -0.0832134 -0.0673033 -0.00582925 -0.0825909 -0.0673033 -0.00696378 -0.0835048 -0.0676033 -0.00590057 -0.0814845 -0.0673033 -0.00763506 -0.0828076 -0.0676033 -0.00717125 -0.0760086 -0.0676033 -0.0306386 -0.0767604 -0.0676033 -0.0318778 -0.0764724 -0.0673033 -0.0319617 -0.0765006 -0.0673033 -0.0332555 -0.076792 -0.0676033 -0.0333268 -0.0680434 -0.0673033 -0.0473236 -0.0690156 -0.0673033 -0.0467825 -0.0699341 -0.0676033 -0.0459871 -0.0698396 -0.0673033 -0.0447757 -0.0697905 -0.0676033 -0.0435616 -0.0695284 -0.0673033 -0.0437075 -0.0690729 -0.0673033 -0.0431177 -0.0687844 -0.0673033 -0.0428802 -0.0666446 -0.0673033 -0.0425233 -0.0677552 -0.0673033 -0.0424575 -0.0679384 -0.0673033 -0.0424951 -0.0678046 -0.0676033 -0.0421616 -0.0505371 -0.0676033 -0.0659846 -0.05013 -0.0673033 -0.0662685 -0.0502457 -0.0673033 -0.0659132 -0.0500018 -0.0673033 -0.0641029 -0.047118 -0.0673033 -0.0629187 -0.047034 -0.0676033 -0.0626307 -0.0484831 -0.0676033 -0.0625992 -0.0484118 -0.0673033 -0.0628906 -0.0492578 -0.0673033 -0.0632756 -0.0815684 -0.0413033 -0.00792308 -0.0828076 -0.0413033 -0.00717125 -0.0832134 -0.0416033 -0.00582925 -0.0835048 -0.0413033 -0.00590057 -0.0834733 -0.0413033 -0.00445153 -0.0827214 -0.0413033 -0.00321239 -0.0813794 -0.0416033 -0.00280658 -0.0814508 -0.0413033 -0.00251518 -0.0800017 -0.0413033 -0.00254671 -0.0825909 -0.0416033 -0.00696378 -0.0831852 -0.0673033 -0.00453546 -0.0831852 -0.0416033 -0.00453546 -0.082514 -0.0416033 -0.00342909 -0.082514 -0.0673033 -0.00342909 -0.0813794 -0.0673033 -0.00280658 -0.0800856 -0.0673033 -0.00283473 -0.0765006 -0.0416033 -0.0332555 -0.0764724 -0.0416033 -0.0319617 -0.076792 -0.0413033 -0.0333268 -0.0758011 -0.0416033 -0.0308553 -0.0746666 -0.0416033 -0.0302328 -0.0733728 -0.0416033 -0.030261 -0.0732889 -0.0413033 -0.029973 -0.0747717 -0.0416033 -0.0350613 -0.0758781 -0.0673033 -0.03439 -0.0758781 -0.0416033 -0.03439 -0.0758011 -0.0673033 -0.0308553 -0.0746666 -0.0673033 -0.0302328 -0.0733728 -0.0673033 -0.030261 -0.0680434 -0.0416033 -0.0473236 -0.0681274 -0.0413033 -0.0476117 -0.0691498 -0.0416033 -0.0466524 -0.0693665 -0.0413033 -0.0468598 -0.0697723 -0.0416033 -0.0455178 -0.0697442 -0.0416033 -0.044224 -0.0690729 -0.0416033 -0.0431177 -0.0692804 -0.0413033 -0.042901 -0.0666446 -0.0416033 -0.0425233 -0.0691498 -0.0673033 -0.0466524 -0.0696566 -0.0673033 -0.0458731 -0.0697723 -0.0673033 -0.0455178 -0.0697442 -0.0673033 -0.044224 -0.0679384 -0.0416033 -0.0424951 -0.0486008 -0.0413033 -0.0680071 -0.049489 -0.0416033 -0.0671779 -0.05013 -0.0416033 -0.0662685 -0.050313 -0.0416033 -0.0651711 -0.0502639 -0.0413033 -0.063957 -0.0492578 -0.0416033 -0.0632756 -0.0494307 -0.0413033 -0.0630304 -0.0482286 -0.0416033 -0.0628529 -0.048278 -0.0413033 -0.062557 -0.0485168 -0.0673033 -0.0677191 -0.0496232 -0.0673033 -0.0670478 -0.050313 -0.0673033 -0.0651711 -0.0502176 -0.0673033 -0.0646195 -0.0500018 -0.0416033 -0.0641029 -0.0495463 -0.0673033 -0.0635131 -0.047118 -0.0416033 -0.0629187 0.0688531 -0.0420533 -0.0431886 0.0680465 -0.0420533 -0.0424634 0.067955 -0.0420533 -0.0419146 0.0681107 -0.0420533 -0.0413806 0.0672063 -0.0413033 -0.0418703 0.0684826 -0.0420533 -0.0409669 0.0688739 -0.0413033 -0.0400158 0.0695526 -0.0420533 -0.0407885 0.0683671 -0.0420533 -0.042918 0.0682999 -0.0528533 -0.042853 0.0681107 -0.0528533 -0.0413806 0.0683384 -0.0528533 -0.0410856 0.0689972 -0.0420533 -0.0407556 0.0680465 -0.0528533 -0.0424634 0.0679887 -0.0528533 -0.0422857 0.067955 -0.0528533 -0.0419146 0.0680028 -0.0528533 -0.0416388 0.0689057 -0.0528533 -0.0407744 0.0684826 -0.0528533 -0.0409669 0.0377213 -0.0420533 -0.0712638 0.0374908 -0.0413033 -0.0723497 0.0377354 -0.0420533 -0.0706169 0.0369928 -0.0413033 -0.0714421 0.038071 -0.0420533 -0.0700637 0.0386383 -0.0420533 -0.0697524 0.039495 -0.0413033 -0.0690465 0.0385857 -0.0420533 -0.0721667 0.0380325 -0.0420533 -0.0718311 0.0387298 -0.0528533 -0.0697336 0.0392851 -0.0528533 -0.0697665 0.0380997 -0.0528533 -0.0718961 0.0375982 -0.0536033 -0.0724538 0.0380325 -0.0528533 -0.0718311 0.0377791 -0.0528533 -0.0714414 0.0377213 -0.0528533 -0.0712638 0.0376876 -0.0528533 -0.0708927 0.037188 -0.0536033 -0.0699938 0.0377354 -0.0528533 -0.0706169 0.0378433 -0.0528533 -0.0703586 0.038071 -0.0528533 -0.0700637 0.0382152 -0.0528533 -0.0699449 0.0386383 -0.0528533 -0.0697524 -0.00224144 -0.0413033 -0.078986 -0.00197157 -0.0420533 -0.0796957 -0.00314906 -0.0413033 -0.079484 -0.00206313 -0.0420533 -0.0797145 -0.00248617 -0.0420533 -0.079907 -0.00285813 -0.0420533 -0.0803206 -0.00368609 -0.0413033 -0.0803691 -0.00292226 -0.0420533 -0.0814035 -0.0032106 -0.0413033 -0.0823117 -0.0023255 -0.0413033 -0.0828488 -0.00260174 -0.0420533 -0.0818581 -0.00211567 -0.0420533 -0.0821287 -0.00260174 -0.0528533 -0.0818581 -0.00266886 -0.0528533 -0.0817931 -0.00266886 -0.0420533 -0.0817931 -0.00298012 -0.0528533 -0.0812258 -0.00298012 -0.0420533 -0.0812258 -0.00301377 -0.0528533 -0.0808547 -0.00301377 -0.0420533 -0.0808547 -0.00296604 -0.0528533 -0.0805789 -0.00296604 -0.0420533 -0.0805789 -0.00248617 -0.0528533 -0.079907 -0.0026304 -0.0420533 -0.0800257 -0.00211567 -0.0528533 -0.0821287 -0.0032106 -0.0536033 -0.0823117 -0.00370861 -0.0536033 -0.0814041 -0.00292226 -0.0528533 -0.0814035 -0.00285813 -0.0528533 -0.0803206 -0.0026304 -0.0528533 -0.0800257 -0.00314906 -0.0536033 -0.079484 -0.00141624 -0.0528533 -0.0797286 -0.00120641 -0.0536033 -0.0790085 -0.00197157 -0.0528533 -0.0796957 -0.00206313 -0.0528533 -0.0797145 -0.00224144 -0.0536033 -0.078986 0.0685372 -0.0676033 -0.0392688 0.0668027 -0.0673033 -0.0412891 0.0665147 -0.0676033 -0.0412052 0.0664831 -0.0676033 -0.0426542 0.0671803 -0.0676033 -0.0439249 0.0686085 -0.0536033 -0.0395602 0.0686085 -0.0673033 -0.0395602 0.067474 -0.0673033 -0.0401827 0.0668027 -0.0536033 -0.0412891 0.0667745 -0.0536033 -0.0425829 0.0667745 -0.0673033 -0.0425829 0.067397 -0.0536033 -0.0437174 0.067397 -0.0673033 -0.0437174 0.0381521 -0.0676033 -0.0736548 0.0369129 -0.0676033 -0.072903 0.0371296 -0.0673033 -0.0726955 0.0362472 -0.0676033 -0.0701832 0.0365071 -0.0673033 -0.071561 0.0397188 -0.0676033 -0.0682784 0.0383411 -0.0673033 -0.0685383 0.0382698 -0.0676033 -0.0682469 0.037495 -0.0673033 -0.0689233 0.0372065 -0.0673033 -0.0691608 0.037495 -0.0536033 -0.0689233 0.0367511 -0.0673033 -0.0697506 0.0367511 -0.0536033 -0.0697506 0.0365353 -0.0673033 -0.0702672 0.0364398 -0.0673033 -0.0708188 0.0364398 -0.0536033 -0.0708188 0.0366228 -0.0673033 -0.0719162 0.0366228 -0.0536033 -0.0719162 0.0372639 -0.0536033 -0.0728256 0.038236 -0.0673033 -0.0733668 -0.00337924 -0.0676033 -0.0786401 -0.00343752 -0.0673033 -0.0827876 -0.00106652 -0.0673033 -0.0785285 -0.00217718 -0.0536033 -0.0784627 -0.00217718 -0.0673033 -0.0784627 -0.00320639 -0.0673033 -0.0788853 -0.0039503 -0.0673033 -0.0797127 -0.00407857 -0.0536033 -0.0818783 -0.00426158 -0.0673033 -0.0807808 -0.00407857 -0.0673033 -0.0818783 0.0645331 -0.0676033 -0.0504987 0.0441376 -0.0676033 -0.0700253 0.0431152 -0.0673033 -0.069066 0.0426084 -0.0673033 -0.0682868 0.0422013 -0.0676033 -0.0680028 0.0422328 -0.0676033 -0.0665538 0.0424254 -0.0673033 -0.0671893 0.0425208 -0.0673033 -0.0666377 0.0434806 -0.0673033 -0.0652938 0.0442553 -0.0676033 -0.0646174 0.0429846 -0.0676033 -0.0653146 0.0319593 -0.0673033 -0.0764656 0.0309871 -0.0673033 -0.0759244 0.0307865 -0.0676033 -0.0761475 0.0302304 -0.0673033 -0.0746597 0.0302585 -0.0673033 -0.073366 0.0309298 -0.0673033 -0.0722596 0.0310454 -0.0676033 -0.0717769 0.0312183 -0.0673033 -0.0720221 0.0334421 -0.0676033 -0.0713772 0.0322475 -0.0673033 -0.0715994 0.00336028 -0.0676033 -0.0828603 0.0026423 -0.0676033 -0.0818418 0.00280411 -0.0673033 -0.0813726 0.0027368 -0.0673033 -0.0806304 0.0660998 -0.0413033 -0.0451224 0.0648559 -0.0413033 -0.0450487 0.0649052 -0.0416033 -0.0453446 0.0637031 -0.0413033 -0.045522 0.0635875 -0.0416033 -0.0460047 0.0631321 -0.0416033 -0.0465946 0.0625213 -0.0413033 -0.047645 0.0628208 -0.0416033 -0.0476627 0.0636449 -0.0416033 -0.0496695 0.0635106 -0.0416033 -0.0495394 0.0635106 -0.0673033 -0.0495394 0.0630038 -0.0416033 -0.0487602 0.0628881 -0.0673033 -0.0484049 0.0628881 -0.0416033 -0.0484049 0.0629163 -0.0416033 -0.0471111 0.0629163 -0.0673033 -0.0471111 0.0635875 -0.0673033 -0.0460047 0.063876 -0.0416033 -0.0457672 0.0647221 -0.0673033 -0.0453822 0.0647221 -0.0416033 -0.0453822 0.0430488 -0.0413033 -0.0694192 0.0426084 -0.0416033 -0.0682868 0.0423309 -0.0413033 -0.0684007 0.0421259 -0.0413033 -0.0671716 0.0427366 -0.0416033 -0.0661212 0.0424745 -0.0413033 -0.0659752 0.0433077 -0.0413033 -0.0650486 0.0434806 -0.0416033 -0.0652938 0.0456204 -0.0416033 -0.064937 0.0444604 -0.0413033 -0.0645753 0.0442216 -0.0673033 -0.0697373 0.0432494 -0.0416033 -0.0691961 0.0424927 -0.0673033 -0.0679315 0.0424254 -0.0416033 -0.0671893 0.0427366 -0.0673033 -0.0661212 0.0431921 -0.0673033 -0.0655313 0.0445098 -0.0416033 -0.0648712 0.0443266 -0.0673033 -0.0649088 0.0306362 -0.0413033 -0.0760017 0.029939 -0.0413033 -0.0747311 0.0299705 -0.0413033 -0.073282 0.0309298 -0.0416033 -0.0722596 0.031993 -0.0413033 -0.0713457 0.0334421 -0.0413033 -0.0713772 0.0319593 -0.0416033 -0.0764656 0.0308529 -0.0673033 -0.0757943 0.0308529 -0.0416033 -0.0757943 0.0303461 -0.0673033 -0.075015 0.0301631 -0.0673033 -0.0739176 0.0302304 -0.0416033 -0.0746597 0.0302585 -0.0416033 -0.073366 0.0304743 -0.0673033 -0.0728494 0.0320643 -0.0673033 -0.0716371 0.0320643 -0.0416033 -0.0716371 0.00361914 -0.0413033 -0.0784897 0.00379199 -0.0416033 -0.0787349 0.00278596 -0.0413033 -0.0794163 0.00304808 -0.0416033 -0.0795622 0.00243733 -0.0413033 -0.0806127 0.0027368 -0.0416033 -0.0806304 0.00280411 -0.0416033 -0.0813726 0.0026423 -0.0413033 -0.0818418 0.00336028 -0.0413033 -0.0828603 0.00482121 -0.0416033 -0.0783123 0.00593186 -0.0673033 -0.0783781 0.00463807 -0.0416033 -0.0783499 0.00482121 -0.0673033 -0.0783123 0.00463807 -0.0673033 -0.0783499 0.00350354 -0.0416033 -0.0789724 0.00379199 -0.0673033 -0.0787349 0.00350354 -0.0673033 -0.0789724 0.00304808 -0.0673033 -0.0795622 0.00283226 -0.0416033 -0.0800788 0.00283226 -0.0673033 -0.0800788 0.00291981 -0.0416033 -0.0817279 0.00291981 -0.0673033 -0.0817279 0.00342662 -0.0416033 -0.0825071 0.00342662 -0.0673033 -0.0825071 0.00356087 -0.0416033 -0.0826372 0.00356087 -0.0673033 -0.0826372 -0.0694178 -0.0420533 0.0432259 -0.0699324 -0.0420533 0.0430146 -0.0711323 -0.0413033 0.0425525 -0.0703044 -0.0420533 0.0426009 -0.0695619 -0.0420533 0.0407929 -0.0703685 -0.0420533 0.0415181 -0.070048 -0.0528533 0.0410634 -0.070048 -0.0420533 0.0410634 -0.0701151 -0.0420533 0.0411285 -0.0703685 -0.0528533 0.0415181 -0.0704263 -0.0528533 0.0416958 -0.0704263 -0.0420533 0.0416958 -0.07046 -0.0528533 0.0420668 -0.07046 -0.0420533 0.0420668 -0.0703044 -0.0528533 0.0426009 -0.0704123 -0.0420533 0.0423427 -0.0699324 -0.0528533 0.0430146 -0.0700766 -0.0420533 0.0428958 -0.0695094 -0.0420533 0.0432071 -0.0694178 -0.0528533 0.0432259 -0.0706568 -0.0536033 0.0406098 -0.0701151 -0.0528533 0.0411285 -0.0711548 -0.0536033 0.0415175 -0.0704123 -0.0528533 0.0423427 -0.0700766 -0.0528533 0.0428958 -0.0686526 -0.0536033 0.0439131 -0.0696877 -0.0536033 0.0439356 -0.0695094 -0.0528533 0.0432071 -0.0403894 -0.0413033 0.0695879 -0.0408874 -0.0413033 0.0704955 -0.0392419 -0.0420533 0.0721852 -0.0397805 -0.0528533 0.0700415 -0.0398477 -0.0420533 0.0701066 -0.0398477 -0.0528533 0.0701066 -0.0401011 -0.0528533 0.0704962 -0.0401589 -0.0420533 0.0706738 -0.0401448 -0.0420533 0.0713207 -0.0398092 -0.0420533 0.0718739 -0.039665 -0.0528533 0.0719927 -0.0392419 -0.0528533 0.0721852 -0.0391504 -0.0528533 0.072204 -0.038595 -0.0420533 0.0721711 -0.0395043 -0.0536033 0.0690509 -0.040282 -0.0536033 0.0694838 -0.0401589 -0.0528533 0.0706738 -0.0409413 -0.0536033 0.0710893 -0.0401926 -0.0528533 0.0710449 -0.0401448 -0.0528533 0.0713207 -0.0400369 -0.0528533 0.071579 -0.0398092 -0.0528533 0.0718739 -0.0392737 -0.0536033 0.0729438 0.0014069 -0.0420533 0.0797329 0.000920841 -0.0420533 0.0800035 0.000508809 -0.0420533 0.0810069 0.000664448 -0.0420533 0.081541 9.14305e-06 -0.0413033 0.0819058 0.00142764 -0.0413033 0.0829058 0.00231617 -0.0413033 0.0828532 0.000853716 -0.0528533 0.0800686 0.000600314 -0.0528533 0.0804582 0.000600314 -0.0420533 0.0804582 0.00055654 -0.0528533 0.0812827 0.00103641 -0.0420533 0.0819547 0.00103641 -0.0528533 0.0819547 0.00155101 -0.0420533 0.082166 0.00210634 -0.0420533 0.0821331 0.00119707 -0.0536033 0.0790129 0.000311973 -0.0536033 0.0795499 0.000542461 -0.0528533 0.0806359 0.000508809 -0.0528533 0.0810069 0.00231617 -0.0536033 0.0828532 0.00145945 -0.0528533 0.0821472 0.000892179 -0.0528533 0.0818359 0.000664448 -0.0528533 0.081541 -0.0684288 -0.0676033 0.0446811 -0.0698779 -0.0676033 0.0447127 -0.0711485 -0.0676033 0.0440154 -0.0719004 -0.0676033 0.0427763 -0.0716405 -0.0673033 0.0413986 -0.0719319 -0.0676033 0.0413273 -0.0712347 -0.0676033 0.0400566 -0.0685127 -0.0673033 0.0443931 -0.0698065 -0.0673033 0.0444213 -0.0709411 -0.0536033 0.0437987 -0.0716124 -0.0536033 0.0426924 -0.0709411 -0.0673033 0.0437987 -0.0716124 -0.0673033 0.0426924 -0.0716405 -0.0536033 0.0413986 -0.071018 -0.0673033 0.040264 -0.0396104 -0.0676033 0.0736907 -0.0413449 -0.0673033 0.0716704 -0.0407506 -0.0673033 0.0692421 -0.0382453 -0.0673033 0.0733712 -0.0395391 -0.0536033 0.0733993 -0.0395391 -0.0673033 0.0733993 -0.0406737 -0.0673033 0.0727768 -0.0406737 -0.0536033 0.0727768 -0.0407506 -0.0536033 0.0692421 -0.0413731 -0.0673033 0.0703766 -0.0396442 -0.0673033 0.0685708 0.00245606 -0.0673033 0.0833332 0.00109095 -0.0676033 0.0836527 2.7736e-05 -0.0673033 0.0827388 -0.000963098 -0.0676033 0.0802674 0.00105719 -0.0673033 0.0785329 0.00116227 -0.0536033 0.0833614 0.00116227 -0.0673033 0.0833614 -0.000643543 -0.0673033 0.0816325 -0.000643543 -0.0536033 0.0816325 -0.000671699 -0.0536033 0.0803387 -0.000671699 -0.0673033 0.0803387 -4.91892e-05 -0.0536033 0.0792041 -4.91892e-05 -0.0673033 0.0792041 -0.0661091 -0.0676033 0.0451268 -0.0671316 -0.0673033 0.046086 -0.0680455 -0.0676033 0.0471493 -0.0677541 -0.0673033 0.0472206 -0.0675101 -0.0673033 0.0490309 -0.0672621 -0.0676033 0.0498374 -0.0645424 -0.0676033 0.0505031 -0.0670546 -0.0673033 0.0496207 -0.0442309 -0.0673033 0.0697417 -0.0463708 -0.0673033 0.0693849 -0.0471147 -0.0673033 0.0685575 -0.0468025 -0.0676033 0.0652595 -0.0344738 -0.0673033 0.0723409 -0.0349806 -0.0673033 0.0731201 -0.0352581 -0.0676033 0.0730062 -0.0354631 -0.0676033 0.0742353 -0.0350963 -0.0673033 0.0734754 -0.0351145 -0.0676033 0.0754317 -0.0342813 -0.0676033 0.0763583 -0.0343969 -0.0673033 0.0758756 -0.0341085 -0.0673033 0.0761131 -0.0330792 -0.0673033 0.0765357 -0.0331286 -0.0676033 0.0768316 -0.0332624 -0.0673033 0.0764981 -0.00726427 -0.0676033 0.0788463 -0.00773739 -0.0673033 0.0809304 -0.00764193 -0.0673033 0.081482 -0.00792995 -0.0676033 0.081566 -0.00445839 -0.0676033 0.0834708 -0.00742611 -0.0673033 0.0819986 -0.0669973 -0.0416033 0.0459559 -0.0681209 -0.0413033 0.0479805 -0.0675101 -0.0416033 0.0490309 -0.0677722 -0.0413033 0.0491768 -0.066939 -0.0413033 0.0501035 -0.065737 -0.0416033 0.0502809 -0.0657863 -0.0413033 0.0505768 -0.0645424 -0.0413033 0.0505031 -0.0660252 -0.0673033 0.0454148 -0.0660252 -0.0416033 0.0454148 -0.0676384 -0.0416033 0.0468653 -0.0676384 -0.0673033 0.0468653 -0.0678214 -0.0673033 0.0479627 -0.0678214 -0.0416033 0.0479627 -0.0677259 -0.0673033 0.0485144 -0.0667662 -0.0416033 0.0498583 -0.0667662 -0.0673033 0.0498583 -0.0646263 -0.0416033 0.0502151 -0.0659201 -0.0673033 0.0502433 -0.0466019 -0.0416033 0.0654825 -0.0457137 -0.0413033 0.0646534 -0.0468025 -0.0413033 0.0652595 -0.0475205 -0.0413033 0.0662779 -0.047426 -0.0416033 0.0674893 -0.0471147 -0.0416033 0.0685575 -0.0473768 -0.0413033 0.0687034 -0.0463708 -0.0416033 0.0693849 -0.0453909 -0.0413033 0.0701034 -0.0456298 -0.0673033 0.0649414 -0.0466019 -0.0673033 0.0654825 -0.0456298 -0.0416033 0.0649414 -0.0472429 -0.0673033 0.0663919 -0.0472429 -0.0416033 0.0663919 -0.047426 -0.0673033 0.0674893 -0.0453416 -0.0673033 0.0698075 -0.0453416 -0.0416033 0.0698075 -0.0330792 -0.0416033 0.0765357 -0.0332624 -0.0416033 0.0764981 -0.0342813 -0.0413033 0.0763583 -0.0341085 -0.0416033 0.0761131 -0.0351145 -0.0413033 0.0754317 -0.0354631 -0.0413033 0.0742353 -0.0351636 -0.0416033 0.0742176 -0.0352581 -0.0413033 0.0730062 -0.0345402 -0.0413033 0.0719877 -0.0334514 -0.0413033 0.0713816 -0.0344738 -0.0416033 0.0723409 -0.0349806 -0.0416033 0.0731201 -0.0333675 -0.0673033 0.0716696 -0.0343396 -0.0416033 0.0722108 -0.0343396 -0.0673033 0.0722108 -0.0350963 -0.0416033 0.0734754 -0.0351636 -0.0673033 0.0742176 -0.0350682 -0.0673033 0.0747692 -0.0348524 -0.0673033 0.0752858 -0.0350682 -0.0416033 0.0747692 -0.0348524 -0.0416033 0.0752858 -0.0343969 -0.0416033 0.0758756 -0.00602513 -0.0413033 0.0780944 -0.00755438 -0.0416033 0.079833 -0.00783189 -0.0413033 0.079719 -0.00803686 -0.0413033 0.0809482 -0.00773739 -0.0416033 0.0809304 -0.0066822 -0.0416033 0.0828259 -0.00768823 -0.0413033 0.0821445 -0.00685505 -0.0413033 0.0830711 -0.00570233 -0.0413033 0.0835445 -0.00454233 -0.0416033 0.0831828 -0.0059412 -0.0416033 0.0783824 -0.00691332 -0.0416033 0.0789236 -0.00704757 -0.0673033 0.0790537 -0.00755438 -0.0673033 0.079833 -0.00767008 -0.0673033 0.0801883 -0.00697065 -0.0673033 0.0825884 -0.00742611 -0.0416033 0.0819986 -0.0066822 -0.0673033 0.0828259 -0.00565298 -0.0416033 0.0832486 -0.00583612 -0.0673033 0.0832109 -0.00454233 -0.0673033 0.0831828 0.0800904 -0.0420533 -0.00268859 0.0797699 -0.0420533 -0.00223391 0.0807206 -0.0420533 -0.000526119 0.0805764 -0.0528533 -0.00295917 0.0800904 -0.0528533 -0.00268859 0.0796784 -0.0420533 -0.00168519 0.079834 -0.0528533 -0.0011511 0.079834 -0.0420533 -0.0011511 0.080206 -0.0528533 -0.000737433 0.080206 -0.0420533 -0.000737433 0.0812759 -0.0528533 -0.00055901 0.0807206 -0.0528533 -0.000526119 0.0791787 -0.0536033 -0.000786304 0.0796784 -0.0528533 -0.00168519 0.0789297 -0.0536033 -0.00164084 0.0797699 -0.0528533 -0.00223391 0.0795889 -0.0536033 -0.00324629 0.0700612 -0.0420533 0.0380778 0.069044 -0.0413033 0.0395018 0.0700997 -0.0420533 0.0398452 0.0713139 -0.0420533 0.0401424 0.0704887 -0.0413033 0.0408849 0.0706144 -0.0528533 0.0377422 0.0700612 -0.0528533 0.0380778 0.06975 -0.0420533 0.0386451 0.0697641 -0.0420533 0.039292 0.070667 -0.0420533 0.0401565 0.0715237 -0.0536033 0.0408624 0.070667 -0.0528533 0.0401565 0.0700997 -0.0528533 0.0398452 0.0697641 -0.0528533 0.039292 0.06975 -0.0528533 0.0386451 0.0695195 -0.0536033 0.0375592 0.0408298 -0.0420533 0.0687349 0.040136 -0.0413033 0.06845 0.0402386 -0.0413033 0.0701825 0.0412659 -0.0420533 0.0702314 0.0417805 -0.0420533 0.0704427 0.0416364 -0.0528533 0.0680096 0.0416364 -0.0420533 0.0680096 0.0411503 -0.0420533 0.0682802 0.0411503 -0.0528533 0.0682802 0.0408298 -0.0528533 0.0687349 0.0407383 -0.0420533 0.0692836 0.0408939 -0.0420533 0.0698177 0.0417805 -0.0528533 0.0704427 0.0412659 -0.0528533 0.0702314 0.0408337 -0.0536033 0.0708444 0.0408939 -0.0528533 0.0698177 0.0402386 -0.0536033 0.0701825 0.0407383 -0.0528533 0.0692836 0.0406488 -0.0536033 0.0677225 0.0805149 -0.0673033 0.000706855 0.0804656 -0.0676033 0.00100277 0.0794857 -0.0673033 0.000284226 0.0793129 -0.0676033 0.000529424 0.0784305 -0.0673033 -0.00161128 0.078336 -0.0676033 -0.00282269 0.0786136 -0.0673033 -0.00270873 0.079054 -0.0676033 -0.00384117 0.0802267 -0.0673033 -0.00415926 0.0816256 -0.0673033 0.000641072 0.0794857 -0.0536033 0.000284226 0.0787418 -0.0673033 -0.000543107 0.0784305 -0.0536033 -0.00161128 0.0792546 -0.0673033 -0.00361809 0.0802267 -0.0536033 -0.00415926 0.0703698 -0.0673033 0.0413706 0.0702985 -0.0676033 0.041662 0.0692353 -0.0673033 0.0407481 0.0690278 -0.0676033 0.0409648 0.068276 -0.0676033 0.0397257 0.0685358 -0.0673033 0.0383479 0.0691583 -0.0673033 0.0372134 0.0689416 -0.0676033 0.0370059 0.0716636 -0.0673033 0.0413425 0.0692353 -0.0536033 0.0407481 0.068564 -0.0673033 0.0396417 0.0685358 -0.0536033 0.0383479 0.0403728 -0.0676033 0.0714982 0.039191 -0.0676033 0.0693753 0.0394904 -0.0673033 0.0693575 0.0401139 -0.0676033 0.0671276 0.0403145 -0.0673033 0.0673507 0.0415749 -0.0673033 0.0716757 0.0405456 -0.0536033 0.071253 0.0405456 -0.0673033 0.071253 0.0398017 -0.0673033 0.0704257 0.0394904 -0.0536033 0.0693575 0.0396735 -0.0536033 0.0682601 0.0396735 -0.0673033 0.0682601 0.0403145 -0.0536033 0.0673507 0.0412866 -0.0536033 0.0668095 0.0412866 -0.0673033 0.0668095 0.0774413 -0.0666033 -0.021018 0.076762 -0.0666033 -0.0212969 0.076762 -0.0676033 -0.0212969 0.076271 -0.0676033 -0.021843 0.076271 -0.0666033 -0.021843 0.0760655 -0.0666033 -0.022548 0.0761863 -0.0666033 -0.0232723 0.0761863 -0.0676033 -0.0232723 0.0766094 -0.0666033 -0.0238725 0.0766094 -0.0676033 -0.0238725 0.0774833 -0.0676033 0.0204392 0.0770403 -0.0666033 0.019709 0.0770403 -0.0676033 0.019709 0.0770217 -0.0666033 0.0188551 0.0770217 -0.0676033 0.0188551 0.0781627 -0.0666033 0.0176633 0.0589291 -0.0676033 0.0575676 0.0581961 -0.0666033 0.057611 0.0581961 -0.0676033 0.057611 0.0575168 -0.0666033 0.0573321 0.0575168 -0.0676033 0.0573321 0.0570258 -0.0666033 0.0567861 0.0580059 -0.0676033 0.0543994 0.0189691 -0.0666033 -0.0769993 0.0182898 -0.0666033 -0.0772783 0.0182898 -0.0676033 -0.0772783 0.0177988 -0.0676033 -0.0778243 0.0175934 -0.0676033 -0.0785293 0.0177142 -0.0666033 -0.0792536 0.0177142 -0.0676033 -0.0792536 0.0187789 -0.0666033 -0.080211 0.0564383 -0.0676033 -0.0568859 0.0557052 -0.0666033 -0.0568424 0.0557052 -0.0676033 -0.0568424 0.055026 -0.0676033 -0.0571214 0.054535 -0.0676033 -0.0576674 0.0544503 -0.0666033 -0.0590967 0.0544503 -0.0676033 -0.0590967 0.0548734 -0.0666033 -0.0596969 0.055515 -0.0666033 -0.0600541 0.055515 -0.0676033 -0.0600541 -0.0596179 -0.0666033 -0.0547873 -0.0596179 -0.0676033 -0.0547873 -0.0600609 -0.0666033 -0.0555175 -0.0596687 -0.0666033 -0.0571202 -0.0789051 -0.0666033 -0.0176154 -0.0795844 -0.0666033 -0.0178944 -0.0789051 -0.0676033 -0.0176154 -0.0795844 -0.0676033 -0.0178944 -0.0800754 -0.0666033 -0.0184404 -0.0800754 -0.0676033 -0.0184404 -0.0802808 -0.0676033 -0.0191454 -0.0797369 -0.0666033 -0.0204699 -0.08016 -0.0676033 -0.0198697 -0.0797369 -0.0676033 -0.0204699 -0.0772604 -0.0676033 0.024234 -0.0786727 -0.0666033 0.0239985 -0.0791637 -0.0666033 0.0234525 -0.0793691 -0.0676033 0.0227475 -0.0792483 -0.0676033 0.0220232 -0.0788252 -0.0666033 0.021423 -0.0569367 -0.0666033 0.059823 -0.0562574 -0.0676033 0.0601019 -0.0569367 -0.0676033 0.059823 -0.0574277 -0.0676033 0.0592769 -0.0575123 -0.0676033 0.0578476 -0.0570892 -0.0666033 0.0572474 -0.0570892 -0.0676033 0.0572474 -0.0187882 -0.0676033 0.0802153 -0.0196421 -0.0676033 0.0802339 -0.0196421 -0.0666033 0.0802339 -0.0203909 -0.0666033 0.0798231 -0.0204417 -0.0666033 0.0774902 -0.0208525 -0.0676033 0.078239 -0.0197115 -0.0666033 0.0770471 0.0814752 -0.0673033 0.00763946 0.0803152 -0.0676033 0.00800115 0.0785914 -0.0673033 0.00645528 0.0791625 -0.0676033 0.00752781 0.0779806 -0.0676033 0.00540484 0.0781856 -0.0676033 0.0041757 0.0800763 -0.0673033 0.00283913 0.0748463 -0.0676033 0.0353537 0.072334 -0.0673033 0.0344714 0.0713747 -0.0676033 0.0334489 0.0713432 -0.0676033 0.0319999 0.0720404 -0.0676033 0.0307292 0.0733635 -0.0673033 0.0302654 0.068118 -0.0676033 0.047616 0.0657214 -0.0676033 0.0472164 0.0648882 -0.0676033 0.0462898 0.0648391 -0.0673033 0.0450757 0.0647445 -0.0676033 0.0438643 0.0654625 -0.0676033 0.0428458 0.0666352 -0.0673033 0.0425277 0.0471086 -0.0673033 0.0629231 0.0459359 -0.0676033 0.0632412 0.0460023 -0.0673033 0.0635944 0.045013 -0.0676033 0.0654888 0.0485075 -0.0673033 0.0677234 0.0473968 -0.0673033 0.0677892 0.0485914 -0.0676033 0.0680115 0.0472137 -0.0673033 0.0677516 0.0473475 -0.0676033 0.0680851 0.0463676 -0.0673033 0.0673666 0.0814752 -0.0416033 0.00763946 0.0801101 -0.0413033 0.00795901 0.0788394 -0.0413033 0.0072618 0.0790469 -0.0416033 0.0070451 0.0782801 -0.0416033 0.0053871 0.0789699 -0.0416033 0.00351041 0.078056 -0.0413033 0.00457361 0.0791042 -0.0673033 0.00338029 0.0784631 -0.0416033 0.00428965 0.0784631 -0.0673033 0.00428965 0.0782801 -0.0673033 0.0053871 0.0783474 -0.0416033 0.00464494 0.0783756 -0.0416033 0.00593873 0.0785914 -0.0416033 0.00645528 0.0793353 -0.0673033 0.00728261 0.0793353 -0.0416033 0.00728261 0.0801814 -0.0416033 0.00766761 0.0803645 -0.0673033 0.00770524 0.0747624 -0.0416033 0.0350657 0.0724496 -0.0413033 0.0349541 0.0716165 -0.0413033 0.0340275 0.0716628 -0.0416033 0.033365 0.0715673 -0.0416033 0.0328134 0.0721908 -0.0413033 0.0305835 0.0723914 -0.0416033 0.0308065 0.0732796 -0.0413033 0.0299774 0.0722571 -0.0673033 0.0309367 0.0722571 -0.0416033 0.0309367 0.0717503 -0.0416033 0.0317159 0.0716346 -0.0673033 0.0320712 0.0716346 -0.0416033 0.0320712 0.0716628 -0.0673033 0.033365 0.0718786 -0.0416033 0.0338815 0.072334 -0.0416033 0.0344714 0.0736517 -0.0416033 0.0351315 0.0734686 -0.0673033 0.0350939 0.0734686 -0.0416033 0.0350939 0.0726225 -0.0416033 0.0347089 0.0650221 -0.0416033 0.0439782 0.0651503 -0.0416033 0.0461438 0.0658942 -0.0416033 0.0469712 0.0669235 -0.0416033 0.0473938 0.0668741 -0.0413033 0.0476897 0.0656631 -0.0673033 0.0430689 0.0656631 -0.0416033 0.0430689 0.0650221 -0.0673033 0.0439782 0.0648391 -0.0416033 0.0450757 0.0651503 -0.0673033 0.0461438 0.0658942 -0.0673033 0.0469712 0.0669235 -0.0673033 0.0473938 0.0485914 -0.0413033 0.0680115 0.0473968 -0.0416033 0.0677892 0.0473475 -0.0413033 0.0680851 0.0461948 -0.0413033 0.0676118 0.0463676 -0.0416033 0.0673666 0.0453616 -0.0413033 0.0666852 0.0453124 -0.0416033 0.0654711 0.045013 -0.0413033 0.0654888 0.0452179 -0.0413033 0.0642597 0.0471086 -0.0416033 0.0629231 0.0461365 -0.0416033 0.0634643 0.0461365 -0.0673033 0.0634643 0.0460023 -0.0416033 0.0635944 0.0454955 -0.0673033 0.0643736 0.0453798 -0.0673033 0.0647289 0.0454955 -0.0416033 0.0643736 0.0453798 -0.0416033 0.0647289 0.0453124 -0.0673033 0.0654711 0.0454079 -0.0673033 0.0660227 0.0454079 -0.0416033 0.0660227 0.0456237 -0.0673033 0.0665393 0.0456237 -0.0416033 0.0665393 0.0460792 -0.0673033 0.0671291 0.0460792 -0.0416033 0.0671291 0.0472137 -0.0416033 0.0677516 0.0151031 -0.0791033 0.0518458 -0.00435662 -0.0676033 0.0538265 -0.014033 -0.0676033 0.0521482 -0.031689 -0.0791033 0.0437298 -0.0451878 -0.0676033 0.0295739 -0.0237715 -0.0415033 -0.0815554 -0.0100234 -0.0431033 -0.0843549 -0.0100234 -0.0415033 -0.0843549 0.00399798 -0.0415033 -0.0848535 0.00399798 -0.0431033 -0.0848535 0.0179102 -0.0431033 -0.0830373 0.0439024 -0.0415033 -0.0727211 0.0439024 -0.0431033 -0.0727211 0.0552734 -0.0431033 -0.0645024 0.0651366 -0.0431033 -0.0545241 0.0793117 -0.0415033 -0.0304184 0.0732229 -0.0431033 -0.0430586 0.0848917 -0.0415033 -0.00301615 0.0848917 -0.0431033 -0.00301615 0.076096 -0.0431033 0.0377538 0.0688444 -0.0415033 0.0497647 0.0597147 -0.0415033 0.0604182 0.0597147 -0.0431033 0.0604182 0.0489561 -0.0431033 0.0694237 0.0368619 -0.0431033 0.0765356 0.00399798 -0.0445033 -0.0848535 -0.0100234 -0.0456033 -0.0843549 0.00399798 -0.0456033 -0.0848535 0.0179102 -0.0445033 -0.0830373 0.0313337 -0.0445033 -0.0789561 0.0313337 -0.0456033 -0.0789561 0.0439024 -0.0456033 -0.0727211 0.0552734 -0.0445033 -0.0645024 0.0552734 -0.0456033 -0.0645024 0.0651366 -0.0445033 -0.0545241 0.0732229 -0.0445033 -0.0430586 0.0793117 -0.0456033 -0.0304184 0.083237 -0.0445033 -0.0169485 0.083237 -0.0456033 -0.0169485 0.0842306 -0.0445033 0.0109985 0.0842306 -0.0456033 0.0109985 0.076096 -0.0445033 0.0377538 0.076096 -0.0456033 0.0377538 0.0688444 -0.0456033 0.0497647 0.0597147 -0.0456033 0.0604182 0.0368619 -0.0445033 0.0765356 0.0237621 -0.0445033 0.0815598 -0.0100234 -0.0470033 -0.0843549 -0.0237715 -0.0481033 -0.0815554 0.00399798 -0.0470033 -0.0848535 0.0179102 -0.0470033 -0.0830373 0.0179102 -0.0481033 -0.0830373 0.0439024 -0.0470033 -0.0727211 0.0439024 -0.0481033 -0.0727211 0.0552734 -0.0470033 -0.0645024 0.0552734 -0.0481033 -0.0645024 0.0651366 -0.0470033 -0.0545241 0.0732229 -0.0470033 -0.0430586 0.0793117 -0.0481033 -0.0304184 0.083237 -0.0470033 -0.0169485 0.0848917 -0.0481033 -0.00301615 0.0842306 -0.0481033 0.0109985 0.0489561 -0.0470033 0.0694237 0.0368619 -0.0470033 0.0765356 -0.0100234 -0.0506033 -0.0843549 0.00399798 -0.0495033 -0.0848535 0.00399798 -0.0506033 -0.0848535 0.0179102 -0.0495033 -0.0830373 0.0313337 -0.0506033 -0.0789561 0.0439024 -0.0495033 -0.0727211 0.0732229 -0.0506033 -0.0430586 0.0793117 -0.0495033 -0.0304184 0.083237 -0.0495033 -0.0169485 0.083237 -0.0506033 -0.0169485 0.0848917 -0.0506033 -0.00301615 0.0842306 -0.0506033 0.0109985 0.0812718 -0.0495033 0.0247132 0.0812718 -0.0506033 0.0247132 0.076096 -0.0495033 0.0377538 0.0489561 -0.0506033 0.0694237 0.0368619 -0.0495033 0.0765356 0.0368619 -0.0506033 0.0765356 0.0179102 -0.0531033 -0.0830373 0.0313337 -0.0520033 -0.0789561 0.0439024 -0.0520033 -0.0727211 0.0439024 -0.0531033 -0.0727211 0.0552734 -0.0520033 -0.0645024 0.0732229 -0.0520033 -0.0430586 0.0732229 -0.0531033 -0.0430586 0.0842306 -0.0531033 0.0109985 0.0842306 -0.0520033 0.0109985 0.0812718 -0.0531033 0.0247132 0.0812718 -0.0520033 0.0247132 0.0489561 -0.0531033 0.0694237 0.0237621 -0.0520033 0.0815598 -0.0237715 -0.0556033 -0.0815554 -0.0100234 -0.0545033 -0.0843549 -0.0100234 -0.0556033 -0.0843549 0.0313337 -0.0556033 -0.0789561 0.0439024 -0.0556033 -0.0727211 0.0651366 -0.0545033 -0.0545241 0.0732229 -0.0545033 -0.0430586 0.0651366 -0.0556033 -0.0545241 0.0793117 -0.0556033 -0.0304184 0.083237 -0.0556033 -0.0169485 0.0848917 -0.0545033 -0.00301615 0.0842306 -0.0556033 0.0109985 0.0842306 -0.0545033 0.0109985 0.0812718 -0.0545033 0.0247132 0.0812718 -0.0556033 0.0247132 0.0688444 -0.0545033 0.0497647 0.0489561 -0.0545033 0.0694237 0.0597147 -0.0556033 0.0604182 0.0489561 -0.0556033 0.0694237 0.0237621 -0.0545033 0.0815598 0.0368619 -0.0556033 0.0765356 0.00399798 -0.0570033 -0.0848535 0.00399798 -0.0581033 -0.0848535 0.0179102 -0.0570033 -0.0830373 0.0179102 -0.0581033 -0.0830373 0.0439024 -0.0570033 -0.0727211 0.0439024 -0.0581033 -0.0727211 0.0651366 -0.0570033 -0.0545241 0.0651366 -0.0581033 -0.0545241 0.0793117 -0.0581033 -0.0304184 0.083237 -0.0570033 -0.0169485 0.0848917 -0.0581033 -0.00301615 0.0848917 -0.0570033 -0.00301615 0.0842306 -0.0570033 0.0109985 0.0842306 -0.0581033 0.0109985 0.0812718 -0.0581033 0.0247132 0.076096 -0.0581033 0.0377538 0.0688444 -0.0570033 0.0497647 0.0597147 -0.0570033 0.0604182 0.0597147 -0.0581033 0.0604182 0.0368619 -0.0570033 0.0765356 0.0237621 -0.0570033 0.0815598 -0.0100234 -0.0606033 -0.0843549 0.00399798 -0.0595033 -0.0848535 0.00399798 -0.0606033 -0.0848535 0.0179102 -0.0606033 -0.0830373 0.0552734 -0.0595033 -0.0645024 0.0439024 -0.0606033 -0.0727211 0.0552734 -0.0606033 -0.0645024 0.0651366 -0.0595033 -0.0545241 0.0651366 -0.0606033 -0.0545241 0.0732229 -0.0595033 -0.0430586 0.0793117 -0.0595033 -0.0304184 0.0848917 -0.0606033 -0.00301615 0.0842306 -0.0595033 0.0109985 0.0812718 -0.0606033 0.0247132 0.076096 -0.0595033 0.0377538 0.076096 -0.0606033 0.0377538 0.0597147 -0.0595033 0.0604182 0.0688444 -0.0606033 0.0497647 0.0597147 -0.0606033 0.0604182 0.0368619 -0.0595033 0.0765356 0.0237621 -0.0595033 0.0815598 0.0368619 -0.0606033 0.0765356 -0.0100234 -0.0645033 -0.0843549 0.00399798 -0.0645033 -0.0848535 0.0179102 -0.0671033 -0.0830373 0.0313337 -0.0645033 -0.0789561 0.0313337 -0.0671033 -0.0789561 0.0651366 -0.0645033 -0.0545241 0.0552734 -0.0671033 -0.0645024 0.0732229 -0.0671033 -0.0430586 0.0793117 -0.0671033 -0.0304184 0.083237 -0.0671033 -0.0169485 0.0842306 -0.0671033 0.0109985 0.076096 -0.0645033 0.0377538 0.076096 -0.0671033 0.0377538 0.0688444 -0.0645033 0.0497647 0.0688444 -0.0671033 0.0497647 0.0489561 -0.0645033 0.0694237 0.0597147 -0.0671033 0.0604182 0.0368619 -0.0671033 0.0765356 -0.0237715 -0.0631033 -0.0815554 -0.0100234 -0.0620033 -0.0843549 -0.0100234 -0.0631033 -0.0843549 0.00399798 -0.0631033 -0.0848535 0.00399798 -0.0620033 -0.0848535 0.0179102 -0.0620033 -0.0830373 0.0179102 -0.0631033 -0.0830373 0.0313337 -0.0620033 -0.0789561 0.0439024 -0.0620033 -0.0727211 0.0439024 -0.0631033 -0.0727211 0.0552734 -0.0631033 -0.0645024 0.0732229 -0.0620033 -0.0430586 0.0732229 -0.0631033 -0.0430586 0.0848917 -0.0620033 -0.00301615 0.0848917 -0.0631033 -0.00301615 0.0842306 -0.0620033 0.0109985 0.0812718 -0.0620033 0.0247132 0.0842306 -0.0631033 0.0109985 0.076096 -0.0620033 0.0377538 0.076096 -0.0631033 0.0377538 0.0368619 -0.0620033 0.0765356 0.0368619 -0.0631033 0.0765356 0.0237621 -0.0620033 0.0815598 -0.00999981 -0.0413033 -0.0841563 0.00398856 -0.0413033 -0.0846537 0.0179102 -0.0411033 -0.0830373 0.043799 -0.0413033 -0.0725499 0.0551433 -0.0413033 -0.0643505 0.0732229 -0.0411033 -0.0430586 0.0649832 -0.0413033 -0.0543958 0.0793117 -0.0411033 -0.0304184 0.0730505 -0.0413033 -0.0429572 0.0846918 -0.0413033 -0.00300905 0.0759169 -0.0413033 0.037665 0.0688444 -0.0411033 0.0497647 0.0488408 -0.0413033 0.0692603 0.0489561 -0.0411033 0.0694237 0.0368619 -0.0411033 0.0765356 0.0237621 -0.0411033 0.0815598 0.077251 -0.0350033 -0.0242296 0.0766094 -0.0350033 -0.0238725 0.0761863 -0.0350033 -0.0232723 0.0760655 -0.0350033 -0.022548 0.076271 -0.0398033 -0.021843 0.076271 -0.0350033 -0.021843 0.076762 -0.0398033 -0.0212969 0.076762 -0.0350033 -0.0212969 0.0774325 -0.0398033 0.0181063 0.0774325 -0.0350033 0.0181063 0.0770217 -0.0398033 0.0188551 0.0774833 -0.0398033 0.0204392 0.0774833 -0.0350033 0.0204392 0.0782321 -0.0398033 0.0208501 0.079086 -0.0350033 0.0208315 0.0572757 -0.0398033 0.0548425 0.0572757 -0.0350033 0.0548425 0.0568648 -0.0350033 0.0555912 0.0568834 -0.0350033 0.0564451 0.0568834 -0.0398033 0.0564451 0.0573264 -0.0398033 0.0571754 0.0573264 -0.0350033 0.0571754 0.0176564 -0.0398033 -0.0781652 0.0176378 -0.0350033 -0.0790191 0.0176564 -0.0350033 -0.0781652 0.0180994 -0.0398033 -0.077435 0.0180994 -0.0350033 -0.077435 0.055515 -0.0398033 -0.0600541 0.0543926 -0.0398033 -0.0580083 0.0543926 -0.0350033 -0.0580083 0.0555844 -0.0350033 -0.0568673 -0.0788252 -0.0350033 0.021423 -0.0792483 -0.0350033 0.0220232 -0.0793691 -0.0350033 0.0227475 -0.0793061 -0.0398033 0.0231115 -0.0791637 -0.0398033 0.0234525 -0.0791637 -0.0350033 0.0234525 -0.0788631 -0.0398033 0.0238417 -0.0781143 -0.0398033 0.0242526 -0.0772604 -0.0350033 0.024234 -0.0790953 -0.0398033 -0.0208271 -0.0797369 -0.0350033 -0.0204699 -0.0802364 -0.0398033 -0.0196352 -0.0802808 -0.0398033 -0.0191454 -0.0802808 -0.0350033 -0.0191454 -0.0795844 -0.0398033 -0.0178944 -0.0795844 -0.0350033 -0.0178944 -0.0781721 -0.0398033 -0.0176589 -0.0596687 -0.0398033 -0.0571202 -0.0595801 -0.0350033 -0.0572061 -0.0600032 -0.0398033 -0.0566059 -0.0600032 -0.0350033 -0.0566059 -0.0600795 -0.0398033 -0.0563714 -0.0601239 -0.0398033 -0.0558816 -0.0600609 -0.0398033 -0.0555175 -0.0596179 -0.0398033 -0.0547873 -0.0594275 -0.0350033 -0.0546305 -0.0594275 -0.0398033 -0.0546305 -0.0587482 -0.0350033 -0.0543516 -0.0588691 -0.0398033 -0.0543764 -0.0197115 -0.0350033 0.0770471 -0.0203531 -0.0398033 0.0774043 -0.0203531 -0.0350033 0.0774043 -0.0207762 -0.0398033 0.0780045 -0.0208969 -0.0350033 0.0787288 -0.0570892 -0.0350033 0.0572474 -0.0575123 -0.0398033 0.0578476 -0.0576331 -0.0350033 0.0585719 -0.0575701 -0.0398033 0.058936 -0.0574277 -0.0350033 0.0592769 -0.0569367 -0.0350033 0.059823 -0.0571271 -0.0398033 0.0596662 -0.0569367 -0.0398033 0.059823 -0.0562574 -0.0350033 0.0601019 -0.0563783 -0.0398033 0.0600771 0.01646 -0.0295033 0.0565021 0.0271663 -0.0295033 0.0522043 0.0164041 -0.0293033 0.0563101 0.0270739 -0.0293033 0.0520269 0.0367031 -0.0293033 0.0457445 0.0449217 -0.0293033 0.0377043 0.0561206 -0.0295033 0.0177019 0.0514137 -0.0293033 0.0282151 0.0582964 -0.0293033 0.00639057 0.0584224 -0.0293033 -0.00510615 0.0563032 -0.0293033 -0.0164066 0.0521975 -0.0295033 -0.0271687 0.0520201 -0.0293033 -0.0270764 0.0457377 -0.0293033 -0.0367056 0.0176951 -0.0295033 -0.056123 0.00638371 -0.0293033 -0.0582988 -0.0164134 -0.0293033 -0.0563057 0.0489561 -0.0356033 0.0694237 0.0368619 -0.0356033 0.0765356 0.0688444 -0.0356033 0.0497647 0.0683053 -0.0350033 0.0494862 0.0597147 -0.0356033 0.0604182 0.0593492 -0.0350033 0.0599359 0.071619 -0.0350033 0.0445553 0.0806978 -0.0350033 0.0245387 0.0742799 -0.0350033 0.0399612 0.0825404 -0.0350033 0.0173584 0.0842306 -0.0356033 0.0109985 0.0848917 -0.0356033 -0.00301615 0.0841822 -0.0350033 0.00524524 0.083237 -0.0356033 -0.0169485 0.0793117 -0.0356033 -0.0304184 0.0727057 -0.0350033 -0.0427544 0.0681864 -0.0350033 -0.0496455 0.0732229 -0.0356033 -0.0430586 0.0646765 -0.0350033 -0.054139 0.0602944 -0.0350033 -0.0589804 0.0641289 -0.0350033 -0.0547866 0.0443552 -0.0350033 -0.0717412 0.054883 -0.0350033 -0.0640468 0.0411848 -0.0350033 -0.0736073 0.0435923 -0.0350033 -0.0722074 0.0179102 -0.0356033 -0.0830373 0.0313337 -0.0356033 -0.0789561 0.00396971 -0.0350033 -0.0842541 0.0177836 -0.0350033 -0.0824508 0.000974609 -0.0350033 -0.0843421 -0.0100234 -0.0356033 -0.0843549 -0.00995263 -0.0350033 -0.0837591 -0.0812457 -0.0350033 -0.00247304 -0.0813794 -0.0353033 -0.00280658 -0.082514 -0.0353033 -0.00342909 -0.0829694 -0.0353033 -0.00401891 -0.0831852 -0.0353033 -0.00453546 -0.0832807 -0.0353033 -0.00508709 -0.0814845 -0.0353033 -0.00763506 -0.0824566 -0.0353033 -0.0070939 -0.0825909 -0.0353033 -0.00696378 -0.0830977 -0.0353033 -0.00618454 -0.0832134 -0.0353033 -0.00582925 -0.0832134 -0.0411033 -0.00582925 -0.0822255 -0.0353033 -0.00319158 -0.0800856 -0.0353033 -0.00283473 -0.0800856 -0.0411033 -0.00283473 -0.0811963 -0.0353033 -0.00276895 -0.0813794 -0.0411033 -0.00280658 -0.082514 -0.0411033 -0.00342909 -0.081427 -0.0413033 -0.00261231 -0.0826523 -0.0413033 -0.00328462 -0.0831852 -0.0411033 -0.00453546 -0.0833773 -0.0413033 -0.00447951 -0.0825909 -0.0411033 -0.00696378 -0.0814845 -0.0411033 -0.00763506 -0.0758781 -0.0353033 -0.03439 -0.0764724 -0.0353033 -0.0319617 -0.076792 -0.0350033 -0.0333268 -0.0767604 -0.0350033 -0.0318778 -0.0758011 -0.0353033 -0.0308553 -0.0746666 -0.0353033 -0.0302328 -0.0747379 -0.0350033 -0.0299414 -0.0765006 -0.0353033 -0.0332555 -0.0746666 -0.0411033 -0.0302328 -0.0733728 -0.0411033 -0.030261 -0.0758011 -0.0411033 -0.0308553 -0.0764724 -0.0411033 -0.0319617 -0.0759395 -0.0413033 -0.0307109 -0.0766644 -0.0413033 -0.0319058 -0.0765006 -0.0411033 -0.0332555 -0.0758781 -0.0411033 -0.03439 -0.0766948 -0.0413033 -0.0333031 -0.0748276 -0.0413033 -0.0352533 -0.0692162 -0.0350033 -0.0470055 -0.0696566 -0.0353033 -0.0458731 -0.0699341 -0.0350033 -0.0459871 -0.0697905 -0.0350033 -0.0435616 -0.0677552 -0.0353033 -0.0424575 -0.0680434 -0.0353033 -0.0473236 -0.0690156 -0.0353033 -0.0467825 -0.0696566 -0.0411033 -0.0458731 -0.0698396 -0.0353033 -0.0447757 -0.0697442 -0.0411033 -0.044224 -0.0695284 -0.0411033 -0.0437075 -0.0695284 -0.0353033 -0.0437075 -0.0687844 -0.0411033 -0.0428802 -0.0687844 -0.0353033 -0.0428802 -0.0666446 -0.0353033 -0.0425233 -0.0666446 -0.0411033 -0.0425233 -0.0692943 -0.0413033 -0.0467907 -0.0691498 -0.0411033 -0.0466524 -0.0697723 -0.0411033 -0.0455178 -0.0698396 -0.0411033 -0.0447757 -0.0679859 -0.0413033 -0.0423009 -0.0679384 -0.0411033 -0.0424951 -0.0690729 -0.0411033 -0.0431177 -0.0498399 -0.0350033 -0.0672552 -0.0505371 -0.0350033 -0.0659846 -0.0497538 -0.0350033 -0.0632964 -0.0484118 -0.0353033 -0.0628906 -0.0484831 -0.0350033 -0.0625992 -0.047034 -0.0350033 -0.0626307 -0.0496232 -0.0411033 -0.0670478 -0.0496232 -0.0353033 -0.0670478 -0.0502457 -0.0353033 -0.0659132 -0.0502176 -0.0353033 -0.0646195 -0.0495463 -0.0353033 -0.0635131 -0.0484118 -0.0411033 -0.0628906 -0.047062 -0.0413033 -0.0627267 -0.0495463 -0.0411033 -0.0635131 -0.0502176 -0.0411033 -0.0646195 -0.0502457 -0.0411033 -0.0659132 -0.0800402 -0.0350033 0.0048357 -0.0800962 -0.0352033 0.00464368 -0.081429 -0.0352033 0.00472262 -0.0816487 -0.0352033 0.00467747 -0.0814619 -0.0350033 0.0049199 -0.0838495 -0.0352033 0.00105026 -0.0817748 -0.0352033 -0.00111671 -0.0818308 -0.0350033 -0.00130873 -0.0831025 -0.0352033 -0.000311178 -0.0718128 -0.0352033 -0.0418181 -0.0732849 -0.0350033 -0.0411509 -0.0738875 -0.0352033 -0.0396511 -0.0740817 -0.0350033 -0.0396987 -0.0730481 -0.0352033 -0.0367709 -0.0428347 -0.0352033 -0.0720855 -0.0443068 -0.0350033 -0.0714183 -0.0451037 -0.0350033 -0.0699661 -0.0450676 -0.0350033 -0.06831 -0.0440701 -0.0352033 -0.0670383 -0.0411561 -0.0352033 -0.0663251 -0.0427562 -0.0350033 -0.0660971 -0.0822357 -0.0380033 0.000518687 -0.0824411 -0.0382533 0.00139499 -0.0824236 -0.0382533 0.00219713 -0.081304 -0.0382533 0.00326904 -0.0813692 -0.0411533 0.000275383 -0.0813692 -0.0382533 0.000275383 -0.0820551 -0.0382533 0.000691575 -0.0820074 -0.0382533 0.00288309 -0.0820074 -0.0411533 0.00288309 -0.0805019 -0.0411533 0.00325159 -0.081304 -0.0411533 0.00326904 -0.0824236 -0.0411533 0.00219713 -0.0821111 -0.0413033 0.00299144 -0.0824411 -0.0411533 0.00139499 -0.0820551 -0.0411533 0.000691575 -0.0821635 -0.0413033 0.000587842 -0.0720931 -0.0382533 -0.0400098 -0.0722737 -0.0380033 -0.0401827 -0.0724616 -0.0382533 -0.0385043 -0.0720454 -0.0382533 -0.0378183 -0.0727016 -0.0380033 -0.0384343 -0.071342 -0.0382533 -0.0374323 -0.0705398 -0.0382533 -0.0374498 -0.0720931 -0.0411533 -0.0400098 -0.072479 -0.0411533 -0.0393064 -0.072479 -0.0382533 -0.0393064 -0.071342 -0.0411533 -0.0374323 -0.0720454 -0.0411533 -0.0378183 -0.0726056 -0.0413033 -0.0384623 -0.0724616 -0.0411533 -0.0385043 -0.0726247 -0.0413033 -0.0393421 -0.0714071 -0.0411533 -0.040426 -0.043115 -0.0382533 -0.0702772 -0.0432956 -0.0380033 -0.0704501 -0.043501 -0.0382533 -0.0695738 -0.0437438 -0.0380033 -0.0696333 -0.0430673 -0.0382533 -0.0680857 -0.0432402 -0.0380033 -0.0679051 -0.0424233 -0.0380033 -0.0674569 -0.0424291 -0.0382533 -0.0706934 -0.0434835 -0.0382533 -0.0687717 -0.0430673 -0.0411533 -0.0680857 -0.0423639 -0.0411533 -0.0676998 -0.0423639 -0.0382533 -0.0676998 -0.0423996 -0.0413033 -0.0675541 -0.0434835 -0.0411533 -0.0687717 -0.0436275 -0.0413033 -0.0687297 -0.043501 -0.0411533 -0.0695738 -0.043115 -0.0411533 -0.0702772 -0.0436467 -0.0413033 -0.0696095 -0.0424291 -0.0411533 -0.0706934 -0.0831025 -0.0380033 -0.000311178 -0.0829414 -0.0352033 -0.000467315 -0.0837106 -0.0352033 0.00062392 -0.0839303 -0.0352033 0.00194086 -0.0838157 -0.0380033 0.00260281 -0.0838157 -0.0352033 0.00260281 -0.0835567 -0.0352033 0.00322267 -0.0830102 -0.0352033 0.00393046 -0.0830102 -0.0380033 0.00393046 -0.0800962 -0.0380033 0.00464368 -0.0816487 -0.0380033 0.00467747 -0.082664 -0.0352033 0.00421547 -0.0731404 -0.0380033 -0.0410126 -0.0731404 -0.0352033 -0.0410126 -0.0738537 -0.0352033 -0.0380986 -0.0716867 -0.0352033 -0.0360239 -0.0701341 -0.0380033 -0.0360577 -0.0441624 -0.0352033 -0.07128 -0.0448756 -0.0380033 -0.068366 -0.0449094 -0.0352033 -0.0699185 -0.0448756 -0.0352033 -0.068366 -0.0440701 -0.0380033 -0.0670383 -0.0427086 -0.0380033 -0.0662913 -0.0427086 -0.0352033 -0.0662913 -0.0411561 -0.0380033 -0.0663251 -0.0671316 -0.0353033 0.046086 -0.0661091 -0.0350033 0.0451268 -0.0677259 -0.0353033 0.0485144 -0.0672621 -0.0350033 0.0498374 -0.0659914 -0.0350033 0.0505347 -0.0646263 -0.0353033 0.0502151 -0.0660252 -0.0353033 0.0454148 -0.0671316 -0.0411033 0.046086 -0.0677541 -0.0353033 0.0472206 -0.0670546 -0.0353033 0.0496207 -0.0659201 -0.0353033 0.0502433 -0.0645704 -0.0413033 0.0504071 -0.0659201 -0.0411033 0.0502433 -0.0670546 -0.0411033 0.0496207 -0.0679179 -0.0413033 0.0485703 -0.0677259 -0.0411033 0.0485144 -0.0677541 -0.0411033 0.0472206 -0.0679483 -0.0413033 0.047173 -0.067276 -0.0413033 0.0459477 -0.045596 -0.0350033 0.0700613 -0.0455247 -0.0353033 0.0697699 -0.0468667 -0.0350033 0.069364 -0.0476185 -0.0350033 0.0681249 -0.0473305 -0.0353033 0.068041 -0.0467361 -0.0353033 0.0656127 -0.0457137 -0.0350033 0.0646534 -0.0472429 -0.0353033 0.0663919 -0.0476501 -0.0350033 0.0666759 -0.047426 -0.0353033 0.0674893 -0.0472429 -0.0411033 0.0663919 -0.0473587 -0.0353033 0.0667472 -0.0471147 -0.0353033 0.0685575 -0.0471147 -0.0411033 0.0685575 -0.0463708 -0.0411033 0.0693849 -0.0466592 -0.0353033 0.0691473 -0.0463708 -0.0353033 0.0693849 -0.0453416 -0.0411033 0.0698075 -0.046486 -0.0413033 0.0695483 -0.0472894 -0.0413033 0.0686548 -0.047426 -0.0411033 0.0674893 -0.0476256 -0.0413033 0.0675012 -0.0466019 -0.0411033 0.0654825 -0.047428 -0.0413033 0.0663159 -0.0467356 -0.0413033 0.0653338 -0.0334514 -0.0350033 0.0713816 -0.0349806 -0.0353033 0.0731201 -0.0354631 -0.0350033 0.0742353 -0.0331286 -0.0350033 0.0768316 -0.0333675 -0.0411033 0.0716696 -0.0343396 -0.0353033 0.0722108 -0.0344738 -0.0411033 0.0723409 -0.0350963 -0.0411033 0.0734754 -0.0351636 -0.0353033 0.0742176 -0.0351636 -0.0411033 0.0742176 -0.0348524 -0.0353033 0.0752858 -0.0350682 -0.0411033 0.0747692 -0.0343969 -0.0411033 0.0758756 -0.0341085 -0.0353033 0.0761131 -0.0330792 -0.0353033 0.0765357 -0.0332624 -0.0411033 0.0764981 -0.0319686 -0.0411033 0.07647 -0.0346183 -0.0413033 0.0722026 -0.0349806 -0.0411033 0.0731201 -0.0348524 -0.0411033 0.0752858 -0.0341085 -0.0411033 0.0761131 -0.00583612 -0.0353033 0.0832109 -0.00697065 -0.0353033 0.0825884 -0.00717811 -0.0350033 0.0828051 -0.00742611 -0.0353033 0.0819986 -0.00792995 -0.0350033 0.081566 -0.00773739 -0.0353033 0.0809304 -0.00796148 -0.0350033 0.0801169 -0.00704757 -0.0353033 0.0790537 -0.00726427 -0.0350033 0.0788463 -0.00767008 -0.0353033 0.0801883 -0.0059412 -0.0353033 0.0783824 -0.00755438 -0.0353033 0.079833 -0.00755438 -0.0411033 0.079833 -0.00773739 -0.0411033 0.0809304 -0.00764193 -0.0353033 0.081482 -0.0066822 -0.0353033 0.0828259 -0.00565298 -0.0411033 0.0832486 -0.00448637 -0.0413033 0.0833748 -0.00568588 -0.0413033 0.0834458 -0.00679743 -0.0413033 0.0829894 -0.0066822 -0.0411033 0.0828259 -0.00742611 -0.0411033 0.0819986 -0.00691332 -0.0411033 0.0789236 -0.0697386 -0.0350033 0.0451493 -0.0683729 -0.0352033 0.0448731 -0.0699254 -0.0352033 0.0449069 -0.0720924 -0.0352033 0.0428323 -0.0721723 -0.0350033 0.0407774 -0.0719873 -0.0352033 0.0408534 -0.0713518 -0.0350033 0.0396134 -0.0713792 -0.0352033 0.0399183 -0.0409728 -0.0350033 0.0734463 -0.0410194 -0.0352033 0.073138 -0.0411117 -0.0352033 0.0688963 -0.0418588 -0.0352033 0.0702578 -0.041825 -0.0352033 0.0718103 -0.0411577 -0.0350033 0.0732824 -0.000249252 -0.0352033 0.0787022 -0.000864596 -0.0352033 0.0823922 -0.00143778 -0.0350033 0.0811222 0.00126315 -0.0352033 0.0838922 0.00123026 -0.0350033 0.0840894 -0.0707003 -0.0382533 0.0424266 -0.0695807 -0.0382533 0.0434985 -0.0687785 -0.0382533 0.043481 -0.0696401 -0.0380033 0.0437413 -0.0703318 -0.0382533 0.040921 -0.0707177 -0.0382533 0.0416244 -0.0702841 -0.0382533 0.0431125 -0.0695807 -0.0411533 0.0434985 -0.0687785 -0.0411533 0.043481 -0.0702841 -0.0411533 0.0431125 -0.0703878 -0.0413033 0.0432209 -0.0707003 -0.0411533 0.0424266 -0.0708443 -0.0413033 0.0424686 -0.0708634 -0.0413033 0.0415888 -0.0707177 -0.0411533 0.0416244 -0.0703318 -0.0411533 0.040921 -0.0704401 -0.0413033 0.0408173 -0.0696458 -0.0411533 0.0405048 -0.0391997 -0.0382533 0.0724999 -0.0393133 -0.0382533 0.0724766 -0.0399819 -0.0380033 0.0724422 -0.0405175 -0.0380033 0.0718465 -0.0404329 -0.0382533 0.0714047 -0.0404921 -0.0382533 0.0710626 -0.0407416 -0.0380033 0.0710774 -0.0406098 -0.0380033 0.0702873 -0.0403786 -0.0382533 0.0703822 -0.0394484 -0.0380033 0.0692429 -0.0399811 -0.0382533 0.0698184 -0.0400644 -0.0382533 0.0698991 -0.0400644 -0.0411533 0.0698991 -0.0404503 -0.0382533 0.0706025 -0.0404503 -0.0411533 0.0706025 -0.0400167 -0.0411533 0.0720906 -0.0402991 -0.0382533 0.0717249 -0.0400167 -0.0382533 0.0720906 -0.0398378 -0.0382533 0.0722379 -0.0385111 -0.0411533 0.0724591 -0.0393133 -0.0411533 0.0724766 -0.0401204 -0.0413033 0.0721989 -0.0404329 -0.0411533 0.0714047 -0.040596 -0.0413033 0.0705668 0.00132297 -0.0382533 0.0794449 0.000553097 -0.0380033 0.0795946 0.000720254 -0.0382533 0.0797805 0.000402326 -0.0382533 0.0816869 0.000863553 -0.0382533 0.0821999 0.00150166 -0.0382533 0.0824619 0.00071951 -0.0380033 0.0824042 0.00146054 -0.0380033 0.0827085 0.00132297 -0.0411533 0.0794449 0.000720254 -0.0411533 0.0797805 0.000322801 -0.0382533 0.0803443 0.000209333 -0.0382533 0.0810247 0.000863553 -0.0411533 0.0821999 0.00150166 -0.0411533 0.0824619 0.00219027 -0.0382533 0.0824211 0.00147699 -0.0413033 0.0826099 0.000777127 -0.0413033 0.0823225 0.000402326 -0.0411533 0.0816869 0.000271265 -0.0413033 0.0817599 0.000209333 -0.0411533 0.0810247 0.000322801 -0.0411533 0.0803443 0.000184044 -0.0413033 0.0802873 -0.0700515 -0.0352033 0.0391127 -0.0712181 -0.0352033 0.0397621 -0.0713792 -0.0380033 0.0399183 -0.0721262 -0.0380033 0.0412797 -0.0721262 -0.0352033 0.0412797 -0.0722069 -0.0352033 0.0421703 -0.0720924 -0.0380033 0.0428323 -0.0718334 -0.0352033 0.0434521 -0.0712868 -0.0352033 0.0441599 -0.0712868 -0.0380033 0.0441599 -0.0709407 -0.0352033 0.0444449 -0.0683729 -0.0380033 0.0448731 -0.0697057 -0.0352033 0.0449521 -0.0699254 -0.0380033 0.0449069 -0.0397841 -0.0352033 0.0680908 -0.0411117 -0.0380033 0.0688963 -0.0418588 -0.0380033 0.0702578 -0.039658 -0.0380033 0.073885 -0.039658 -0.0352033 0.073885 -0.00101852 -0.0380033 0.0797935 -0.00101852 -0.0352033 0.0797935 -0.00123813 -0.0380033 0.0811104 -0.00123813 -0.0352033 0.0811104 -0.000864596 -0.0380033 0.0823922 0.00126315 -0.0380033 0.0838922 2.81017e-05 -0.0352033 0.083385 0.00259594 -0.0352033 0.0838132 0.0648559 -0.0350033 -0.0450487 0.0637031 -0.0350033 -0.045522 0.063876 -0.0353033 -0.0457672 0.0625213 -0.0350033 -0.047645 0.0629163 -0.0353033 -0.0471111 0.0627263 -0.0350033 -0.0488741 0.0628881 -0.0353033 -0.0484049 0.0630038 -0.0353033 -0.0487602 0.0636449 -0.0353033 -0.0496695 0.0645331 -0.0350033 -0.0504987 0.0634443 -0.0350033 -0.0498926 0.064617 -0.0411033 -0.0502107 0.0635106 -0.0353033 -0.0495394 0.0628881 -0.0411033 -0.0484049 0.0628208 -0.0353033 -0.0476627 0.0629163 -0.0411033 -0.0471111 0.0631321 -0.0353033 -0.0465946 0.0635875 -0.0353033 -0.0460047 0.0660159 -0.0353033 -0.0454104 0.0649052 -0.0353033 -0.0453446 0.0647221 -0.0411033 -0.0453822 0.0647221 -0.0353033 -0.0453822 0.0635875 -0.0411033 -0.0460047 0.0635106 -0.0411033 -0.0495394 0.0626938 -0.0413033 -0.0484524 0.0430488 -0.0350033 -0.0694192 0.0424254 -0.0353033 -0.0671893 0.0421259 -0.0350033 -0.0671716 0.0434806 -0.0353033 -0.0652938 0.0445098 -0.0353033 -0.0648712 0.0444604 -0.0350033 -0.0645753 0.0432494 -0.0411033 -0.0691961 0.0432494 -0.0353033 -0.0691961 0.0426084 -0.0353033 -0.0682868 0.0424254 -0.0411033 -0.0671893 0.0427366 -0.0353033 -0.0661212 0.0445098 -0.0411033 -0.0648712 0.0456204 -0.0411033 -0.064937 0.0456764 -0.0413033 -0.064745 0.0434806 -0.0411033 -0.0652938 0.0427366 -0.0411033 -0.0661212 0.0425619 -0.0413033 -0.0660239 0.0426084 -0.0411033 -0.0682868 0.0424234 -0.0413033 -0.0683628 0.0431157 -0.0413033 -0.0693449 0.0442216 -0.0411033 -0.0697373 0.0318753 -0.0350033 -0.0767536 0.0309298 -0.0353033 -0.0722596 0.0307223 -0.0350033 -0.0720429 0.0334421 -0.0350033 -0.0713772 0.0319593 -0.0353033 -0.0764656 0.0308529 -0.0411033 -0.0757943 0.0302304 -0.0411033 -0.0746597 0.0308529 -0.0353033 -0.0757943 0.0302304 -0.0353033 -0.0746597 0.0302585 -0.0411033 -0.073366 0.0302585 -0.0353033 -0.073366 0.0320643 -0.0353033 -0.0716371 0.0333581 -0.0411033 -0.0716652 0.0333581 -0.0353033 -0.0716652 0.0320643 -0.0411033 -0.0716371 0.0309298 -0.0411033 -0.0722596 0.0300665 -0.0413033 -0.07331 0.0300361 -0.0413033 -0.0747073 0.0307084 -0.0413033 -0.0759326 0.00593186 -0.0353033 -0.0783781 0.00477186 -0.0350033 -0.0780164 0.00482121 -0.0353033 -0.0783123 0.00463807 -0.0353033 -0.0783499 0.00350354 -0.0353033 -0.0789724 0.00304808 -0.0353033 -0.0795622 0.00291981 -0.0353033 -0.0817279 0.00336028 -0.0350033 -0.0828603 0.00444906 -0.0350033 -0.0834664 0.00356087 -0.0353033 -0.0826372 0.00453299 -0.0353033 -0.0831784 0.00453299 -0.0411033 -0.0831784 0.00342662 -0.0411033 -0.0825071 0.00342662 -0.0353033 -0.0825071 0.00280411 -0.0411033 -0.0813726 0.00280411 -0.0353033 -0.0813726 0.0027368 -0.0353033 -0.0806304 0.00283226 -0.0353033 -0.0800788 0.00283226 -0.0411033 -0.0800788 0.00379199 -0.0353033 -0.0787349 0.00463807 -0.0411033 -0.0783499 0.00593186 -0.0411033 -0.0783781 0.00459053 -0.0413033 -0.0781556 0.00350354 -0.0411033 -0.0789724 0.00264025 -0.0413033 -0.0800228 0.00260984 -0.0413033 -0.0814201 0.00328215 -0.0413033 -0.0826454 0.0670632 -0.0350033 -0.0443681 0.0662427 -0.0350033 -0.0432041 0.0662081 -0.0352033 -0.0418112 0.0674743 -0.0352033 -0.0395366 0.0687094 -0.0352033 -0.0390294 0.0367685 -0.0352033 -0.0730413 0.036624 -0.0350033 -0.0731796 0.0358272 -0.0350033 -0.0717274 0.0360552 -0.0352033 -0.0701273 0.0358632 -0.0350033 -0.0700713 0.0382222 -0.0352033 -0.0680526 0.0381747 -0.0350033 -0.0678584 0.0397748 -0.0352033 -0.0680864 -0.00266123 -0.0350033 -0.0840008 -0.00487421 -0.0350033 -0.0816894 -0.00483817 -0.0350033 -0.0800334 -0.00384062 -0.0352033 -0.0787617 -0.00247918 -0.0352033 -0.0780147 -0.00397893 -0.0350033 -0.0786172 -0.000926633 -0.0352033 -0.0780484 0.0688343 -0.0382533 -0.040483 0.0681657 -0.0380033 -0.0405174 0.0681309 -0.0382533 -0.0408689 0.0676301 -0.0380033 -0.041113 0.0678486 -0.0382533 -0.0412346 0.0677148 -0.0382533 -0.0415549 0.0675378 -0.0380033 -0.0426723 0.0679993 -0.0380033 -0.043327 0.0680832 -0.0382533 -0.0430605 0.0687692 -0.0382533 -0.0434766 0.0681665 -0.0382533 -0.0431411 0.067769 -0.0382533 -0.0425773 0.0676973 -0.0382533 -0.042357 0.0676556 -0.0382533 -0.0418969 0.0689479 -0.0382533 -0.0404597 0.0683098 -0.0382533 -0.0407217 0.0688343 -0.0411533 -0.040483 0.0680272 -0.0413033 -0.0407606 0.0681309 -0.0411533 -0.0408689 0.0677148 -0.0411533 -0.0415549 0.0675707 -0.0413033 -0.0415129 0.0676973 -0.0411533 -0.042357 0.0680832 -0.0411533 -0.0430605 0.0376352 -0.0380033 -0.0722114 0.0374299 -0.0382533 -0.0713351 0.0372073 -0.0380033 -0.070463 0.0378635 -0.0382533 -0.069847 0.0376906 -0.0380033 -0.0696664 0.0385075 -0.0380033 -0.0692182 0.039439 -0.0380033 -0.0692385 0.0378158 -0.0411533 -0.0720385 0.0385018 -0.0382533 -0.0724547 0.0378158 -0.0382533 -0.0720385 0.0378635 -0.0411533 -0.069847 0.0374473 -0.0382533 -0.070533 0.0385669 -0.0411533 -0.069461 0.0385669 -0.0382533 -0.069461 0.0393691 -0.0411533 -0.0694785 0.0377598 -0.0413033 -0.0697387 0.0374473 -0.0411533 -0.070533 0.0374299 -0.0411533 -0.0713351 -0.00306614 -0.0380033 -0.0821734 -0.00327151 -0.0382533 -0.0812971 -0.00351435 -0.0380033 -0.0813566 -0.00325406 -0.0382533 -0.080495 -0.00349407 -0.0380033 -0.080425 -0.00213445 -0.0382533 -0.0794231 -0.00301075 -0.0380033 -0.0796285 -0.00219389 -0.0380033 -0.0791802 -0.00133231 -0.0382533 -0.0794405 -0.00126236 -0.0380033 -0.0792005 -0.00219961 -0.0411533 -0.0824167 -0.00288556 -0.0382533 -0.0820006 -0.00325406 -0.0411533 -0.080495 -0.00283786 -0.0411533 -0.079809 -0.00283786 -0.0382533 -0.079809 -0.00133231 -0.0411533 -0.0794405 -0.00213445 -0.0411533 -0.0794231 -0.00217012 -0.0413033 -0.0792774 -0.00339807 -0.0413033 -0.080453 -0.00327151 -0.0411533 -0.0812971 -0.00288556 -0.0411533 -0.0820006 0.0683635 -0.0380033 -0.0448687 0.0683635 -0.0352033 -0.0448687 0.067197 -0.0352033 -0.0442193 0.067197 -0.0380033 -0.0442193 0.0662081 -0.0380033 -0.0418112 0.0664277 -0.0352033 -0.0431281 0.0665816 -0.0380033 -0.0405294 0.0665816 -0.0352033 -0.0405294 0.0687094 -0.0380033 -0.0390294 0.0380961 -0.0352033 -0.0738468 0.0367685 -0.0380033 -0.0730413 0.0360214 -0.0380033 -0.0716798 0.0360214 -0.0352033 -0.0716798 0.0368608 -0.0352033 -0.0687996 -0.00260528 -0.0352033 -0.0838088 -0.00393293 -0.0380033 -0.0830033 -0.00393293 -0.0352033 -0.0830033 -0.00467994 -0.0380033 -0.0816419 -0.00464615 -0.0380033 -0.0800893 -0.00467994 -0.0352033 -0.0816419 -0.00464615 -0.0352033 -0.0800893 -0.00384062 -0.0380033 -0.0787617 -0.00247918 -0.0380033 -0.0780147 0.0800763 -0.0353033 0.00283913 0.0791042 -0.0353033 0.00338029 0.0784631 -0.0353033 0.00428965 0.0779806 -0.0350033 0.00540484 0.0783293 -0.0350033 0.0066012 0.0791625 -0.0350033 0.00752781 0.0784631 -0.0411033 0.00428965 0.0782801 -0.0411033 0.0053871 0.0782801 -0.0353033 0.0053871 0.0785914 -0.0411033 0.00645528 0.0785914 -0.0353033 0.00645528 0.0793353 -0.0353033 0.00728261 0.0793353 -0.0411033 0.00728261 0.0803645 -0.0353033 0.00770524 0.0803645 -0.0411033 0.00770524 0.0780805 -0.0413033 0.00539893 0.0782781 -0.0413033 0.00421368 0.0791042 -0.0411033 0.00338029 0.0800763 -0.0411033 0.00283913 0.0733972 -0.0350033 0.0353853 0.0721266 -0.0350033 0.0346881 0.0713747 -0.0350033 0.0334489 0.0718786 -0.0353033 0.0338815 0.0716628 -0.0353033 0.033365 0.0723914 -0.0353033 0.0308065 0.0723914 -0.0411033 0.0308065 0.0722571 -0.0353033 0.0309367 0.0717503 -0.0353033 0.0317159 0.0716346 -0.0411033 0.0320712 0.0716346 -0.0353033 0.0320712 0.0715673 -0.0353033 0.0328134 0.0716628 -0.0411033 0.033365 0.0718786 -0.0411033 0.0338815 0.072334 -0.0353033 0.0344714 0.0726225 -0.0411033 0.0347089 0.0726225 -0.0353033 0.0347089 0.0734686 -0.0353033 0.0350939 0.0736517 -0.0353033 0.0351315 0.0747624 -0.0353033 0.0350657 0.0733075 -0.0413033 0.0300734 0.0721126 -0.0413033 0.0307984 0.0722571 -0.0411033 0.0309367 0.0717503 -0.0411033 0.0317159 0.0715673 -0.0411033 0.0328134 0.0714707 -0.0413033 0.0334209 0.072334 -0.0411033 0.0344714 0.0721957 -0.0413033 0.0346158 0.0736517 -0.0411033 0.0351315 0.0734686 -0.0411033 0.0350939 0.0665513 -0.0350033 0.0422397 0.0656631 -0.0353033 0.0430689 0.0654625 -0.0350033 0.0428458 0.0650221 -0.0353033 0.0439782 0.0651503 -0.0353033 0.0461438 0.0648882 -0.0350033 0.0462898 0.0668741 -0.0350033 0.0476897 0.0666352 -0.0411033 0.0425277 0.0650221 -0.0411033 0.0439782 0.0648391 -0.0411033 0.0450757 0.0651503 -0.0411033 0.0461438 0.0648391 -0.0353033 0.0450757 0.0658942 -0.0353033 0.0469712 0.0669235 -0.0411033 0.0473938 0.0669235 -0.0353033 0.0473938 0.0680341 -0.0411033 0.047328 0.0668906 -0.0413033 0.0475911 0.0658942 -0.0411033 0.0469712 0.065779 -0.0413033 0.0471346 0.0646394 -0.0413033 0.0450875 0.0648371 -0.0413033 0.0439023 0.0656631 -0.0411033 0.0430689 0.0655294 -0.0413033 0.0429201 0.0665793 -0.0413033 0.0423357 0.0473968 -0.0353033 0.0677892 0.0472137 -0.0353033 0.0677516 0.0463676 -0.0353033 0.0673666 0.0460792 -0.0353033 0.0671291 0.0461948 -0.0350033 0.0676118 0.0453616 -0.0350033 0.0666852 0.0454079 -0.0353033 0.0660227 0.0459359 -0.0350033 0.0632412 0.0471086 -0.0411033 0.0629231 0.0461365 -0.0353033 0.0634643 0.0460023 -0.0353033 0.0635944 0.0460023 -0.0411033 0.0635944 0.0454955 -0.0353033 0.0643736 0.0453798 -0.0353033 0.0647289 0.0453124 -0.0353033 0.0654711 0.0456237 -0.0353033 0.0665393 0.0454079 -0.0411033 0.0660227 0.0472137 -0.0411033 0.0677516 0.0471662 -0.0413033 0.0679459 0.0460792 -0.0411033 0.0671291 0.0459409 -0.0413033 0.0672736 0.0453798 -0.0411033 0.0647289 0.0458578 -0.0413033 0.0634561 0.0780122 -0.0352033 -0.00247232 0.0778179 -0.0350033 -0.00251987 0.078046 -0.0352033 -0.00091977 0.077854 -0.0350033 -0.000863815 0.0718035 -0.0352033 0.0418225 0.0704378 -0.0350033 0.0420987 0.0702509 -0.0352033 0.0418563 0.0691204 -0.0350033 0.0415577 0.0680839 -0.0352033 0.0397816 0.0677697 -0.0350033 0.0391315 0.068004 -0.0350033 0.0377268 0.068189 -0.0352033 0.0378027 0.0399802 -0.0352033 0.0669789 0.0398465 -0.0350033 0.0668302 0.0390259 -0.0350033 0.0679942 0.0389913 -0.0352033 0.0693871 0.0387917 -0.0350033 0.0693989 0.0393649 -0.0352033 0.0706689 0.0391901 -0.0350033 0.0707662 0.0401423 -0.0350033 0.0718252 0.0414926 -0.0352033 0.0721688 0.0428254 -0.0352033 0.0720899 0.0805577 -0.0382533 -0.000253533 0.0796814 -0.0380033 -0.000458909 0.0795719 -0.0382533 -0.00100518 0.0794381 -0.0382533 -0.00132544 0.0791981 -0.0380033 -0.0012555 0.0793789 -0.0382533 -0.00166745 0.0804925 -0.0382533 -0.00324719 0.079626 -0.0380033 -0.00300389 0.0791778 -0.0380033 -0.00218703 0.0794206 -0.0382533 -0.00212759 0.0798066 -0.0382533 -0.002831 0.0794923 -0.0382533 -0.00234787 0.0794923 -0.0411533 -0.00234787 0.0798543 -0.0382533 -0.00063949 0.0800331 -0.0382533 -0.000492235 0.0806712 -0.0411533 -0.000230205 0.0813598 -0.0382533 -0.000270991 0.0813598 -0.0411533 -0.000270991 0.0800331 -0.0411533 -0.000492235 0.0795719 -0.0411533 -0.00100518 0.0793789 -0.0411533 -0.00166745 0.0793536 -0.0413033 -0.00240485 0.0798898 -0.0411533 -0.00291167 0.0797895 -0.0413033 -0.00302321 0.0704605 -0.0380033 0.0372142 0.0699278 -0.0382533 0.0377897 0.0697606 -0.0380033 0.0376038 0.0692991 -0.0380033 0.0382586 0.0691673 -0.0380033 0.0390487 0.069927 -0.0380033 0.0404135 0.0700711 -0.0382533 0.0402092 0.0706681 -0.0380033 0.0407178 0.0705305 -0.0411533 0.0374542 0.0695303 -0.0382533 0.0383535 0.0698445 -0.0411533 0.0378704 0.0695303 -0.0411533 0.0383535 0.0694586 -0.0411533 0.0385738 0.0694169 -0.0382533 0.0390339 0.0694169 -0.0411533 0.0390339 0.0696098 -0.0382533 0.0396962 0.0707092 -0.0382533 0.0404712 0.0697362 -0.0413033 0.0377667 0.069476 -0.0411533 0.0393759 0.0705956 -0.0411533 0.0404479 0.0700711 -0.0411533 0.0402092 0.0698922 -0.0411533 0.0400619 0.0697885 -0.0413033 0.0401702 0.0696098 -0.0411533 0.0396962 0.0401892 -0.0380033 0.0693161 0.0406318 -0.0382533 0.0699636 0.041093 -0.0382533 0.0704766 0.04169 -0.0380033 0.0709852 0.0415524 -0.0382533 0.0677216 0.0409497 -0.0382533 0.0680571 0.0405523 -0.0382533 0.0686209 0.0404388 -0.0382533 0.0693014 0.041093 -0.0411533 0.0704766 0.0417311 -0.0411533 0.0707386 0.0417311 -0.0382533 0.0707386 0.0424197 -0.0411533 0.0706978 0.0424617 -0.0413033 0.0708418 0.0410066 -0.0413033 0.0705992 0.0406318 -0.0411533 0.0699636 0.0404388 -0.0411533 0.0693014 0.040289 -0.0413033 0.0693102 0.0405523 -0.0411533 0.0686209 0.0404135 -0.0413033 0.068564 0.0409497 -0.0411533 0.0680571 0.0408494 -0.0413033 0.0679456 0.0787592 -0.0380033 -0.00383376 0.0780122 -0.0380033 -0.00247232 0.0787592 -0.0352033 -0.00383376 0.078046 -0.0380033 -0.00091977 0.0788515 -0.0352033 0.000407881 0.0802129 -0.0380033 0.00115489 0.0802129 -0.0352033 0.00115489 0.0701248 -0.0380033 0.0360621 0.0687972 -0.0380033 0.0368676 0.0689583 -0.0352033 0.0367115 0.0687972 -0.0352033 0.0368676 0.0680502 -0.0352033 0.0382291 0.0680502 -0.0380033 0.0382291 0.0679694 -0.0352033 0.0391197 0.0683429 -0.0352033 0.0404015 0.0688895 -0.0380033 0.0411093 0.0688895 -0.0352033 0.0411093 0.0692356 -0.0352033 0.0413943 0.0704707 -0.0352033 0.0419014 0.0411468 -0.0352033 0.0663295 0.0389913 -0.0380033 0.0693871 0.0392109 -0.0352033 0.0680702 0.0393649 -0.0380033 0.0706689 0.0402576 -0.0352033 0.0716617 0.0428254 -0.0380033 0.0720899 -0.0164694 -0.0350033 -0.0564977 -0.00513043 -0.0350033 -0.0586242 -0.00513043 -0.0295033 -0.0586242 0.00640549 -0.0295033 -0.0584977 0.0283045 -0.0295033 -0.0515916 0.0283045 -0.0350033 -0.0515916 0.037826 -0.0295033 -0.0450774 0.037826 -0.0350033 -0.0450774 0.0458936 -0.0295033 -0.0368308 0.0521975 -0.0350033 -0.0271687 0.0564952 -0.0295033 -0.0164625 0.0564952 -0.0350033 -0.0164625 0.0586217 -0.0295033 -0.00512357 0.0584952 -0.0295033 0.00641236 0.0584952 -0.0350033 0.00641236 0.0561206 -0.0350033 0.0177019 0.0515891 -0.0295033 0.0283113 0.0515891 -0.0350033 0.0283113 0.0450749 -0.0295033 0.0378328 0.0450749 -0.0350033 0.0378328 0.0368283 -0.0295033 0.0459005 0.0271663 -0.0350033 0.0522043 -0.0237715 -0.0411033 -0.0815554 -0.0100234 -0.0411033 -0.0843549 0.00399798 -0.0356033 -0.0848535 0.00399798 -0.0411033 -0.0848535 0.0313337 -0.0411033 -0.0789561 0.0439024 -0.0356033 -0.0727211 0.0439024 -0.0411033 -0.0727211 0.0552734 -0.0356033 -0.0645024 0.0552734 -0.0411033 -0.0645024 0.0651366 -0.0411033 -0.0545241 0.0651366 -0.0356033 -0.0545241 0.083237 -0.0411033 -0.0169485 0.0848917 -0.0411033 -0.00301615 0.0842306 -0.0411033 0.0109985 0.0812718 -0.0411033 0.0247132 0.0812718 -0.0356033 0.0247132 0.076096 -0.0356033 0.0377538 0.076096 -0.0411033 0.0377538 0.0597147 -0.0411033 0.0604182 0.0237621 -0.0356033 0.0815598 0.0769433 -0.0401033 -0.0235012 0.0766094 -0.0398033 -0.0238725 0.0761863 -0.0398033 -0.0232723 0.0760655 -0.0398033 -0.022548 0.0767072 -0.0401033 -0.0220858 0.0775234 -0.0401033 -0.0215105 0.0774413 -0.0398033 -0.021018 0.0781627 -0.0398033 0.0176633 0.0770403 -0.0398033 0.019709 0.0783508 -0.0401033 0.0203651 0.0580059 -0.0398033 0.0543994 0.0576363 -0.0401033 0.0551877 0.0568648 -0.0398033 0.0555912 0.0580752 -0.0398033 0.0575862 0.0189186 -0.0401033 -0.0797316 0.0180487 -0.0398033 -0.0797679 0.0181228 -0.0401033 -0.0789004 0.0181357 -0.0401033 -0.0783049 0.0176378 -0.0398033 -0.0790191 0.0184447 -0.0401033 -0.0777957 0.0188482 -0.0398033 -0.0770242 0.0189669 -0.0401033 -0.0775091 0.0197021 -0.0398033 -0.0770427 0.0547848 -0.0398033 -0.059611 0.0548589 -0.0401033 -0.0587435 0.054374 -0.0398033 -0.0588622 0.0548356 -0.0398033 -0.0572781 0.0557031 -0.0401033 -0.0573522 0.0555844 -0.0398033 -0.0568673 -0.0785532 -0.0401033 0.0218541 -0.0779956 -0.0401033 0.0237676 -0.0786727 -0.0398033 0.0239985 -0.0785178 -0.0401033 0.0234811 -0.0788397 -0.0401033 0.0223763 -0.0793691 -0.0398033 0.0227475 -0.0788268 -0.0401033 0.0229719 -0.0789138 -0.0398033 0.0215088 -0.0792483 -0.0398033 0.0220232 -0.0793247 -0.0398033 0.0222576 -0.0789557 -0.0401033 -0.0203477 -0.079026 -0.0398033 -0.0176403 -0.0783118 -0.0401033 -0.0181382 -0.0789073 -0.0401033 -0.0181252 -0.0797385 -0.0401033 -0.018921 -0.0800754 -0.0398033 -0.0184404 -0.0797748 -0.0398033 -0.0180511 -0.0802178 -0.0398033 -0.0187813 -0.0798255 -0.0398033 -0.020384 -0.08016 -0.0398033 -0.0198697 -0.0797514 -0.0401033 -0.0195165 -0.0589385 -0.0398033 -0.0575632 -0.0587504 -0.0401033 -0.0548614 -0.0595816 -0.0401033 -0.0556572 -0.0599185 -0.0398033 -0.0551766 -0.059308 -0.0401033 -0.0567749 -0.0595946 -0.0401033 -0.0562527 -0.0203143 -0.0401033 0.0781941 -0.0203985 -0.0401033 0.0786993 -0.0208969 -0.0398033 0.0787288 -0.0206915 -0.0398033 0.0794338 -0.0202553 -0.0401033 0.0791909 -0.0202005 -0.0398033 0.0799798 -0.0194391 -0.0401033 0.0797663 -0.0195212 -0.0398033 0.0802588 -0.0189279 -0.0401033 0.079736 -0.0555244 -0.0398033 0.0600585 -0.0562596 -0.0401033 0.0595921 -0.0574277 -0.0398033 0.0592769 -0.0568172 -0.0401033 0.0576786 -0.0571778 -0.0398033 0.0573333 -0.0571037 -0.0401033 0.0582008 -0.0575887 -0.0398033 0.0580821 -0.0576331 -0.0398033 0.0585719 0.0153148 -0.0373033 -0.0321345 0.0167318 -0.0385033 -0.0307067 0.0167329 -0.0385033 -0.0306535 0.0148156 -0.0373033 -0.0300948 0.0168605 -0.0385033 -0.0305835 0.029844 -0.0385033 -0.0182243 0.0299471 -0.0385033 -0.0180544 0.0298938 -0.0385033 -0.0180532 0.0298472 -0.0385033 -0.0180789 0.027822 -0.0373033 -0.018029 0.0280834 -0.0373033 -0.0171317 0.0284014 -0.0373033 -0.0196054 0.0279757 -0.0373033 -0.0189509 0.0298184 -0.0385033 -0.0181776 0.0278785 -0.0373033 -0.0186524 0.0329473 -0.0373033 -0.00125858 0.0329709 -0.0373033 -0.000171799 0.0349626 -0.0385033 -0.000659409 0.0291629 -0.0373033 0.0153863 0.0306087 -0.0385033 0.0169129 0.0292275 -0.0373033 0.0183554 0.0181219 -0.0385033 0.0298264 0.0180508 -0.0385033 0.0299007 0.0161109 -0.0373033 0.0294259 0.0180519 -0.0385033 0.0299539 0.0180796 -0.0385033 0.0299995 0.0166984 -0.0373033 0.031442 0.0176514 -0.0373033 0.0319649 0.000169328 -0.0373033 0.0329778 0.000656939 -0.0385033 0.0349695 -0.00128294 -0.0373033 0.0344947 -0.00125928 -0.0373033 0.0355814 0.000658097 -0.0385033 0.0350227 0.000257597 -0.0373033 0.0370337 -0.0169003 -0.0385033 0.0307707 -0.0169309 -0.0385033 0.0307367 -0.0188572 -0.0373033 0.0312742 -0.0189374 -0.0373033 0.0308108 -0.0182451 -0.0373033 0.0291251 -0.0169362 -0.0385033 0.0306476 -0.0183579 -0.0373033 0.0292344 -0.0305151 -0.0373033 0.0161414 -0.0313317 -0.0373033 0.016596 -0.0300228 -0.0385033 0.0181185 -0.0300303 -0.0385033 0.0181636 -0.0300175 -0.0385033 0.0182076 -0.0317625 -0.0373033 0.019179 -0.0299445 -0.0385033 0.018259 -0.0298988 -0.0385033 0.0182563 -0.0355839 -0.0373033 -0.00125242 -0.0350675 -0.0385033 0.000838018 -0.0364486 -0.0373033 0.0022806 -0.0370927 -0.0373033 0.000887879 -0.0350951 -0.0385033 0.000792496 -0.0370125 -0.0373033 0.00135124 -0.0365133 -0.0373033 -0.000688547 -0.0306604 -0.0385033 -0.0167354 -0.0307061 -0.0385033 -0.0167327 -0.0321414 -0.0373033 -0.0153173 -0.0318991 -0.0373033 -0.0151178 -0.0311884 -0.0373033 -0.0147944 -0.030779 -0.0385033 -0.0167841 -0.032524 -0.0373033 -0.0158127 -0.0307918 -0.0385033 -0.0168281 -0.0320933 -0.0373033 -0.0183957 -0.032206 -0.0373033 -0.0182864 -0.0326317 -0.0373033 -0.0176319 -0.0175725 -0.0373033 -0.0279046 -0.0186593 -0.0373033 -0.027881 -0.0199949 -0.0373033 -0.0288993 -0.0182312 -0.0385033 -0.0298465 -0.0201762 -0.0373033 -0.0293332 -0.0182588 -0.0385033 -0.029892 -0.0182599 -0.0385033 -0.0299452 -0.0201026 -0.0373033 -0.0307185 -0.0182343 -0.0385033 -0.0299919 -0.0195641 -0.0373033 -0.0314823 -0.00111161 -0.0373033 -0.0329181 -0.000790643 -0.0385033 -0.0348896 -0.00126544 -0.0373033 -0.0329497 -0.000837324 -0.0385033 -0.0349152 -0.00260104 -0.0373033 -0.0339681 -0.000864944 -0.0385033 -0.0349607 -0.00280598 -0.0373033 -0.0354888 -0.00270878 -0.0373033 -0.0357872 -0.000840489 -0.0385033 -0.0350607 -0.00228307 -0.0373033 -0.0364418 -0.0021703 -0.0373033 -0.0365511 -0.000794966 -0.0385033 -0.0350883 -0.00135371 -0.0373033 -0.0370057 -0.00042076 -0.0373033 -0.0370609 -0.000266931 -0.0373033 -0.0370293 -0.000676311 -0.0385033 -0.0350396 -0.00070692 -0.0385033 -0.0350736 0.00106867 -0.0373033 -0.0360109 0.00133014 -0.0373033 -0.0351137 0.00124995 -0.0373033 -0.035577 -0.000671033 -0.0385033 -0.0349504 0.0012736 -0.0373033 -0.0344903 -0.0166431 -0.0373033 -0.0284685 -0.0180601 -0.0385033 -0.0298963 -0.0161202 -0.0373033 -0.0294215 -0.0167078 -0.0373033 -0.0314376 -0.0176608 -0.0373033 -0.0319605 -0.0312767 -0.0373033 -0.0188503 -0.0303437 -0.0373033 -0.0189056 -0.0307179 -0.0385033 -0.0169329 -0.0292369 -0.0373033 -0.018351 -0.0288543 -0.0373033 -0.0178556 -0.0305904 -0.0385033 -0.0168629 -0.028673 -0.0373033 -0.0174217 -0.0305892 -0.0385033 -0.0168097 -0.0285928 -0.0373033 -0.0169583 -0.0286494 -0.0373033 -0.0163349 -0.0306148 -0.0385033 -0.016763 -0.0349276 -0.0385033 0.000840207 -0.0350252 -0.0385033 0.00066496 -0.0349795 -0.0385033 0.000662253 -0.0329802 -0.0373033 0.000176191 -0.0349065 -0.0385033 0.000713684 -0.0335441 -0.0373033 -0.000753165 -0.0349012 -0.0385033 0.00080279 -0.0329566 -0.0373033 0.00126297 -0.0334795 -0.0373033 0.00221598 -0.0293401 -0.0373033 0.0201737 -0.0298277 -0.0385033 0.018182 -0.0278878 -0.0373033 0.0186568 -0.0298565 -0.0385033 0.0180832 -0.0279115 -0.0373033 0.01757 -0.0284754 -0.0373033 0.0166407 -0.0299032 -0.0385033 0.0180576 -0.0294284 -0.0373033 0.0161178 -0.0156311 -0.0373033 0.0289703 -0.0167423 -0.0385033 0.0306579 -0.0147447 -0.0373033 0.0305625 -0.0150062 -0.0373033 0.0296652 -0.0162535 -0.0373033 0.0327028 -0.0167667 -0.0385033 0.0307578 -0.0153241 -0.0373033 0.0321389 -0.0148984 -0.0373033 0.0314844 -0.0148012 -0.0373033 0.0311859 0.000825632 -0.0385033 0.0350704 0.000852008 -0.0385033 0.035033 0.00269945 -0.0373033 0.0357916 0.000859539 -0.0385033 0.0349878 0.000846731 -0.0385033 0.0349439 0.000728075 -0.0385033 0.0348952 0.0187382 -0.0373033 0.0319413 0.0182195 -0.0385033 0.0300016 0.0182458 -0.0385033 0.0299642 0.0200933 -0.0373033 0.0307228 0.0182406 -0.0385033 0.0298751 0.0199855 -0.0373033 0.0289037 0.0193607 -0.0373033 0.0282088 0.0181676 -0.0385033 0.0298237 0.0184961 -0.0373033 0.0278538 0.0312673 -0.0373033 0.0188547 0.0307486 -0.0385033 0.016915 0.0320839 -0.0373033 0.0184001 0.0327761 -0.0373033 0.0167144 0.0310252 -0.0373033 0.0147672 0.030651 -0.0385033 0.0167398 0.0300923 -0.0373033 0.0148224 0.0343995 -0.0373033 -0.00277546 0.0349583 -0.0385033 -0.000858082 0.0354863 -0.0373033 -0.00279911 0.0350582 -0.0385033 -0.000833626 0.0368219 -0.0373033 -0.00178075 0.0364393 -0.0373033 -0.00227621 0.036197 -0.0373033 -0.00247571 0.0370834 -0.0373033 -0.000883487 0.0350613 -0.0385033 -0.000688188 0.0370268 -0.0373033 -0.000260068 0.0298895 -0.0385033 -0.0182519 0.0299352 -0.0385033 -0.0182546 0.0299776 -0.0385033 -0.0182372 0.0300082 -0.0385033 -0.0182032 0.0300134 -0.0385033 -0.0181141 0.030021 -0.0385033 -0.0181592 0.0320146 -0.0373033 -0.0182773 0.0299871 -0.0385033 -0.0180767 0.0314352 -0.0373033 -0.0167009 0.0318609 -0.0373033 -0.0173555 0.0319581 -0.0373033 -0.0176539 0.0171771 -0.0373033 -0.0327537 0.0168486 -0.0385033 -0.0307837 0.017331 -0.0373033 -0.0327221 0.016891 -0.0385033 -0.0307664 0.0169216 -0.0385033 -0.0307323 0.0186665 -0.0373033 -0.0317037 0.018284 -0.0373033 -0.0321992 0.0188715 -0.0373033 -0.030183 0.018928 -0.0373033 -0.0308064 0.0183486 -0.0373033 -0.02923 0.0187743 -0.0373033 -0.0298846 0.057227 -0.0293033 -0.00500163 0.0376974 -0.0293033 -0.0449242 0.027631 -0.0293033 -0.0503642 0.0282083 -0.0293033 -0.0514162 0.017274 -0.0293033 -0.0547879 0.0176349 -0.0293033 -0.0559323 0.006253 -0.0293033 -0.057106 -0.00511301 -0.0293033 -0.0584249 -0.0265292 -0.0293033 -0.0509581 -0.0270832 -0.0293033 -0.0520225 -0.044931 -0.0293033 -0.0376999 -0.0547947 -0.0293033 -0.0172765 -0.0571128 -0.0293033 -0.00625547 -0.0584318 -0.0293033 0.00511054 -0.0572363 -0.0293033 0.00500602 -0.0563125 -0.0293033 0.0164109 -0.050965 -0.0293033 0.0265267 -0.0448111 -0.0293033 0.0359589 -0.0276404 -0.0293033 0.0503686 -0.0377067 -0.0293033 0.0449285 -0.0282176 -0.0293033 0.0514206 -0.0172833 -0.0293033 0.0547922 0.0160684 -0.0293033 0.055158 0.0265199 -0.0293033 0.0509625 0.0359521 -0.0293033 0.0448086 0.0440025 -0.0293033 0.0369329 0.0503617 -0.0293033 0.0276379 0.0571035 -0.0293033 0.00625986 0.0559298 -0.0293033 0.0176418 0.0799467 -0.0413033 -0.000369636 0.0797738 -0.0413033 -0.000124438 0.0794408 -0.0413033 -0.000932222 0.0792291 -0.0413033 -0.00165858 0.0791787 -0.0413033 -0.000786304 0.0789297 -0.0413033 -0.00164084 0.0790761 -0.0413033 -0.0025188 0.0795889 -0.0413033 -0.00324629 0.0803666 -0.0413033 -0.00367922 0.0813303 -0.0413033 -0.00341035 0.0821018 -0.0413033 -0.00298704 0.0828463 -0.0413033 -0.00231864 0.0821541 -0.0413033 -0.00058345 0.0814018 -0.0413033 -0.000126981 0.0806465 -0.0413033 -8.22485e-05 0.0814857 -0.0413033 0.000161039 0.0805972 -0.0413033 0.000213665 0.0726612 -0.0413033 0.0388418 0.0729606 -0.0413033 0.038824 0.0725367 -0.0413033 0.039588 0.0721008 -0.0413033 0.0402064 0.0714398 -0.0413033 0.0405744 0.07056 -0.0413033 0.0405936 0.069581 -0.0413033 0.0403869 0.069332 -0.0413033 0.0394179 0.0693129 -0.0413033 0.0385381 0.0690215 -0.0413033 0.0384668 0.0695195 -0.0413033 0.0375592 0.0704885 -0.0413033 0.0373102 0.0704046 -0.0413033 0.0370222 0.0712931 -0.0413033 0.0369695 0.0719436 -0.0413033 0.0375528 0.0799924 -0.0413033 0.00255111 0.0800204 -0.0413033 0.00264711 0.0789705 -0.0413033 0.00323157 0.0787532 -0.0413033 0.00330294 0.0780876 -0.0413033 0.00602266 0.0784167 -0.0413033 0.00655256 0.0792201 -0.0413033 0.00744608 0.0803316 -0.0413033 0.00790251 0.0815591 -0.0413033 0.00792748 0.0815311 -0.0413033 0.00783147 0.0834639 -0.0413033 0.00445592 0.0827121 -0.0413033 0.00321678 0.0814414 -0.0413033 0.00251957 0.0736024 -0.0413033 0.0354274 0.073421 -0.0413033 0.0352881 0.0714403 -0.0413033 0.0320236 0.0712678 -0.0413033 0.0328311 0.0714728 -0.0413033 0.031602 0.0747048 -0.0413033 0.030043 0.0759993 -0.0413033 0.030643 0.0766551 -0.0413033 0.0319102 0.0767511 -0.0413033 0.0318822 0.0760854 -0.0413033 0.0346019 0.0748183 -0.0413033 0.0352577 0.0649756 -0.0413033 0.0462411 0.0648882 -0.0413033 0.0462898 0.0645396 -0.0413033 0.0450934 0.0647445 -0.0413033 0.0438643 0.0654625 -0.0413033 0.0428458 0.0679766 -0.0413033 0.0423053 0.0680004 -0.0413033 0.0422081 0.069271 -0.0413033 0.0429054 0.0700229 -0.0413033 0.0441445 0.0700544 -0.0413033 0.0455935 0.069285 -0.0413033 0.0467951 0.0693572 -0.0413033 0.0468642 0.068118 -0.0413033 0.047616 0.0657214 -0.0413033 0.0472164 0.0452159 -0.0413033 0.0660787 0.0451855 -0.0413033 0.0646814 0.0459359 -0.0413033 0.0632412 0.0470247 -0.0413033 0.0626351 0.0484737 -0.0413033 0.0626036 0.0496753 -0.0413033 0.063373 0.0504307 -0.0413033 0.0659652 0.0505278 -0.0413033 0.065989 0.0485635 -0.0413033 0.0679155 0.0498306 -0.0413033 0.0672596 0.0405007 -0.0413033 0.0700366 0.0399896 -0.0413033 0.069328 0.0406488 -0.0413033 0.0677225 0.0415105 -0.0413033 0.0675776 0.0414265 -0.0413033 0.0672896 0.0424616 -0.0413033 0.0672671 0.0433692 -0.0413033 0.0677651 0.0436373 -0.0413033 0.0696139 0.0439287 -0.0413033 0.0696852 0.0434307 -0.0413033 0.0705928 0.0416571 -0.0413033 0.0711825 0.0417064 -0.0413033 0.0708866 0.0408337 -0.0413033 0.0708444 -0.00773939 -0.0413033 0.079757 -0.00704705 -0.0413033 0.0787749 -0.00711391 -0.0413033 0.0787005 -0.00599715 -0.0413033 0.0781904 -0.00459986 -0.0413033 0.07816 -0.00457609 -0.0413033 0.0780629 -0.00337456 -0.0413033 0.0788323 -0.00264958 -0.0413033 0.0800272 -0.00252204 -0.0413033 0.0814483 -0.00445839 -0.0413033 0.0834708 -0.00760086 -0.0413033 0.0820959 -0.00793704 -0.0413033 0.0809423 -0.0331286 -0.0413033 0.0768316 -0.0333099 -0.0413033 0.0766924 -0.0345352 -0.0413033 0.0760201 -0.0352602 -0.0413033 0.0748252 -0.0352906 -0.0413033 0.0734279 -0.0320023 -0.0413033 0.0713501 -0.0307317 -0.0413033 0.0720473 -0.0299798 -0.0413033 0.0732864 -0.0300454 -0.0413033 0.0747117 -0.0306455 -0.0413033 0.0760061 -0.0319126 -0.0413033 0.076662 -0.0318847 -0.0413033 0.076758 -0.0477254 -0.0413033 0.0675071 -0.0456857 -0.0413033 0.0647494 -0.0430631 -0.0413033 0.0653913 -0.0422106 -0.0413033 0.0680072 -0.0429801 -0.0413033 0.0692087 -0.0441749 -0.0413033 0.0699337 -0.044147 -0.0413033 0.0700297 -0.0453745 -0.0413033 0.0700048 -0.0465436 -0.0413033 0.0696301 -0.0659677 -0.0413033 0.0504375 -0.0671929 -0.0413033 0.0497652 -0.0679159 -0.0413033 0.0467513 -0.0671979 -0.0413033 0.0457329 -0.0661091 -0.0413033 0.0451268 -0.0634586 -0.0413033 0.0458647 -0.0626376 -0.0413033 0.0470316 -0.0627032 -0.0413033 0.0484568 -0.062606 -0.0413033 0.0484806 0.000604275 -0.0413033 0.0825677 5.95958e-05 -0.0413033 0.0810335 -0.000239879 -0.0413033 0.0810513 -9.34702e-05 -0.0413033 0.0801733 0.000419372 -0.0413033 0.0794458 0.00061996 -0.0413033 0.0796689 0.00128101 -0.0413033 0.0793009 0.00216078 -0.0413033 0.0792818 0.00338873 -0.0413033 0.0804574 0.00340788 -0.0413033 0.0813372 0.00298457 -0.0413033 0.0821087 0.00223224 -0.0413033 0.0825651 -0.0370947 -0.0413033 0.0717307 -0.0384691 -0.0413033 0.0726031 -0.0383852 -0.0413033 0.0728911 -0.0393489 -0.0413033 0.0726223 -0.0394202 -0.0413033 0.0729137 -0.0403279 -0.0413033 0.0724156 -0.0405769 -0.0413033 0.0714466 -0.0408649 -0.0413033 0.0715306 -0.0401727 -0.0413033 0.0697954 -0.0394204 -0.0413033 0.0693389 -0.0395043 -0.0413033 0.0690509 -0.0386651 -0.0413033 0.0692942 -0.0379653 -0.0413033 0.0695815 -0.0371973 -0.0413033 0.0699982 -0.0374594 -0.0413033 0.0701441 -0.0369483 -0.0413033 0.0708527 -0.0373722 -0.0413033 0.0716168 -0.0680755 -0.0413033 0.0432571 -0.0678749 -0.0413033 0.0434801 -0.0687366 -0.0413033 0.043625 -0.0686526 -0.0413033 0.0439131 -0.0696877 -0.0413033 0.0439356 -0.0696163 -0.0413033 0.0436442 -0.0705953 -0.0413033 0.0434376 -0.0711548 -0.0413033 0.0415175 -0.0706568 -0.0413033 0.0406098 -0.0697717 -0.0413033 0.0400728 -0.0688832 -0.0413033 0.0400202 -0.0682327 -0.0413033 0.0406035 -0.0674647 -0.0413033 0.0410201 -0.0672157 -0.0413033 0.0418747 0.00598782 -0.0413033 -0.078186 0.0060158 -0.0413033 -0.07809 0.00703772 -0.0413033 -0.0787705 0.00773005 -0.0413033 -0.0797526 0.0079277 -0.0413033 -0.0809379 0.00792061 -0.0413033 -0.0815616 0.00759152 -0.0413033 -0.0820915 0.0067881 -0.0413033 -0.082985 0.00444906 -0.0413033 -0.0834664 0.00336523 -0.0413033 -0.0788279 0.00477186 -0.0413033 -0.0780164 0.0350178 -0.0413033 -0.0753787 0.0351052 -0.0413033 -0.0754273 0.034464 -0.0413033 -0.0720577 0.0320168 -0.0413033 -0.0714428 0.0307223 -0.0413033 -0.0720429 0.0307915 -0.0413033 -0.0721151 0.0319033 -0.0413033 -0.0766576 0.0318753 -0.0413033 -0.0767536 0.0342144 -0.0413033 -0.0762722 0.0422257 -0.0413033 -0.0671775 0.0441656 -0.0413033 -0.0699293 0.0441376 -0.0413033 -0.0700253 0.0475132 -0.0413033 -0.0680925 0.0475436 -0.0413033 -0.0666952 0.0468713 -0.0413033 -0.06547 0.0476407 -0.0413033 -0.0666715 0.0457044 -0.0413033 -0.064649 0.0444769 -0.0413033 -0.0646739 0.0433653 -0.0413033 -0.0651304 0.0646745 -0.0413033 -0.045188 0.0634492 -0.0413033 -0.0458603 0.06287 -0.0413033 -0.0464486 0.0627242 -0.0413033 -0.0470552 0.0627263 -0.0413033 -0.0488741 0.0633661 -0.0413033 -0.0496777 0.0634443 -0.0413033 -0.0498926 0.064561 -0.0413033 -0.0504027 0.0657605 -0.0413033 -0.0504738 0.0668721 -0.0413033 -0.0500173 0.0680046 -0.0413033 -0.0485939 0.0680361 -0.0413033 -0.0471449 0.067814 -0.0413033 -0.0467849 0.0673389 -0.0413033 -0.0458742 8.41366e-05 -0.0413033 -0.0801689 -0.000629293 -0.0413033 -0.0796645 -0.00129034 -0.0413033 -0.0792965 -0.0029416 -0.0413033 -0.0797007 -0.00370861 -0.0413033 -0.0814041 -0.00341721 -0.0413033 -0.0813328 -0.00299391 -0.0413033 -0.0821043 -0.00224157 -0.0413033 -0.0825608 -0.000786461 -0.0413033 -0.0823181 -0.00143698 -0.0413033 -0.0829014 -6.89294e-05 -0.0413033 -0.0810292 -0.000193377 -0.0413033 -0.0802829 0.0392644 -0.0413033 -0.0729394 0.0406325 -0.0413033 -0.0710671 0.0407855 -0.0413033 -0.0702069 0.0402727 -0.0413033 -0.0694794 0.0385313 -0.0413033 -0.0693154 0.0384599 -0.0413033 -0.069024 0.0375523 -0.0413033 -0.069522 0.0373033 -0.0413033 -0.070491 0.0370153 -0.0413033 -0.0704071 0.0372842 -0.0413033 -0.0713708 0.0377075 -0.0413033 -0.0721423 0.0384598 -0.0413033 -0.0725987 0.0392151 -0.0413033 -0.0726435 0.0383759 -0.0413033 -0.0728867 0.0674554 -0.0413033 -0.0410158 0.0675516 -0.0413033 -0.0423927 0.0673528 -0.0413033 -0.0427483 0.0679749 -0.0413033 -0.0431642 0.0678656 -0.0413033 -0.0434757 0.069607 -0.0413033 -0.0436398 0.070835 -0.0413033 -0.0424642 0.071123 -0.0413033 -0.0425481 0.0711455 -0.0413033 -0.0415131 0.0704308 -0.0413033 -0.0408129 0.0696785 -0.0413033 -0.0403564 0.0697624 -0.0413033 -0.0400684 0.0687987 -0.0413033 -0.0403373 0.0680505 -0.0413033 -0.0403539 -0.0496846 -0.0413033 -0.0633686 -0.0504096 -0.0413033 -0.0645635 -0.0506125 -0.0413033 -0.0651533 -0.0504075 -0.0413033 -0.0663825 -0.05044 -0.0413033 -0.0659608 -0.0497677 -0.0413033 -0.0671861 -0.0496896 -0.0413033 -0.067401 -0.0485728 -0.0413033 -0.0679111 -0.0471517 -0.0413033 -0.0680386 -0.0458811 -0.0413033 -0.0673414 -0.0451292 -0.0413033 -0.0661023 -0.0457949 -0.0413033 -0.0633825 -0.047034 -0.0413033 -0.0626307 -0.0484593 -0.0413033 -0.0626963 -0.0668834 -0.0413033 -0.0476853 -0.0649849 -0.0413033 -0.0462367 -0.0657307 -0.0413033 -0.047212 -0.0648975 -0.0413033 -0.0462854 -0.0648464 -0.0413033 -0.0438979 -0.0647539 -0.0413033 -0.0438599 -0.0665886 -0.0413033 -0.0423313 -0.0654719 -0.0413033 -0.0428414 -0.0665606 -0.0413033 -0.0422353 -0.0680097 -0.0413033 -0.0422038 -0.0692112 -0.0413033 -0.0429732 -0.0700322 -0.0413033 -0.0441401 -0.0699362 -0.0413033 -0.0441681 -0.0699666 -0.0413033 -0.0455654 -0.0700637 -0.0413033 -0.0455891 -0.0680994 -0.0413033 -0.0475156 -0.0733169 -0.0413033 -0.030069 -0.0747142 -0.0413033 -0.0300386 -0.0747379 -0.0413033 -0.0299414 -0.0760086 -0.0413033 -0.0306386 -0.0767604 -0.0413033 -0.0318778 -0.0760225 -0.0413033 -0.0345284 -0.0760948 -0.0413033 -0.0345975 -0.0736281 -0.0413033 -0.0353244 -0.0725166 -0.0413033 -0.0348679 -0.072459 -0.0413033 -0.0349497 -0.0716258 -0.0413033 -0.0340231 -0.071377 -0.0413033 -0.0328208 -0.072267 -0.0413033 -0.0306534 -0.0800297 -0.0413033 -0.00264272 -0.0834077 -0.0413033 -0.0058768 -0.0827354 -0.0413033 -0.0071021 -0.0815405 -0.0413033 -0.00782708 -0.080341 -0.0413033 -0.00789812 -0.0792294 -0.0413033 -0.00744168 -0.078426 -0.0413033 -0.00654816 -0.0791718 -0.0413033 -0.00752342 -0.0782875 -0.0413033 -0.00420929 -0.078195 -0.0413033 -0.0041713 -0.0417158 -0.0413033 -0.0708822 -0.0410159 -0.0413033 -0.0705948 -0.04051 -0.0413033 -0.0700322 -0.0402479 -0.0413033 -0.0701781 -0.0399989 -0.0413033 -0.0693236 -0.0408587 -0.0413033 -0.0679412 -0.0415198 -0.0413033 -0.0675732 -0.0414359 -0.0413033 -0.0672852 -0.043171 -0.0413033 -0.0679774 -0.0424709 -0.0413033 -0.0672627 -0.0433785 -0.0413033 -0.0677607 -0.0432234 -0.0413033 -0.070381 -0.042555 -0.0413033 -0.0711255 -0.0416664 -0.0413033 -0.0711781 -0.0698368 -0.0413033 -0.0376738 -0.0704139 -0.0413033 -0.0370178 -0.0713776 -0.0413033 -0.0372866 -0.0721491 -0.0413033 -0.03771 -0.0728936 -0.0413033 -0.0383784 -0.0722014 -0.0413033 -0.0401135 -0.0714491 -0.0413033 -0.04057 -0.0706938 -0.0413033 -0.0406147 -0.0698211 -0.0413033 -0.0405726 -0.0692764 -0.0413033 -0.0390384 -0.0694009 -0.0413033 -0.0382921 -0.068977 -0.0413033 -0.0390562 -0.0691234 -0.0413033 -0.0381782 -0.079188 -0.0413033 0.000790696 -0.0790854 -0.0413033 0.00252319 -0.0797988 -0.0413033 0.0030276 -0.0804599 -0.0413033 0.0033956 -0.0813397 -0.0413033 0.00341474 -0.080376 -0.0413033 0.00368362 -0.0825676 -0.0413033 0.0022391 -0.0823186 -0.0413033 0.00320813 -0.0825868 -0.0413033 0.00135932 -0.0828556 -0.0413033 0.00232303 -0.0828782 -0.0413033 0.001288 -0.0823802 -0.0413033 0.000380376 -0.0814111 -0.0413033 0.000131373 -0.0806065 -0.0413033 -0.000209273 -0.0552166 -0.0401033 0.05933 -0.0564476 -0.0398033 0.0568902 -0.0555937 -0.0398033 0.0568717 -0.055323 -0.0401033 0.0575338 -0.0548449 -0.0398033 0.0572825 -0.0548373 -0.0401033 0.0584063 -0.0545443 -0.0398033 0.0576718 -0.0549215 -0.0401033 0.0589115 -0.0543833 -0.0398033 0.0588666 -0.0548828 -0.0398033 0.0597013 -0.0547942 -0.0398033 0.0596154 -0.0187882 -0.0398033 0.0802153 -0.0181321 -0.0401033 0.0789048 -0.0184541 -0.0401033 0.0778 -0.0181088 -0.0398033 0.0774394 -0.0189763 -0.0401033 0.0775135 -0.0582054 -0.0398033 -0.0576067 -0.0574714 -0.0401033 -0.0565388 -0.0578138 -0.0401033 -0.0569196 -0.0575261 -0.0398033 -0.0573277 -0.0570352 -0.0398033 -0.0567817 -0.0568741 -0.0398033 -0.0555869 -0.0573281 -0.0401033 -0.0560472 -0.0568297 -0.0398033 -0.0560767 -0.0580152 -0.0398033 -0.054395 -0.0577074 -0.0401033 -0.0551235 -0.0574124 -0.0401033 -0.055542 -0.0784444 -0.0401033 -0.020378 -0.0779707 -0.0401033 -0.0201835 -0.0774926 -0.0398033 -0.0204348 -0.077683 -0.0398033 -0.0205916 -0.077485 -0.0401033 -0.019311 -0.0776283 -0.0401033 -0.0198027 -0.077192 -0.0398033 -0.0200455 -0.077031 -0.0398033 -0.0188507 -0.0778643 -0.0401033 -0.0183873 -0.0769526 -0.0401033 0.0235056 -0.0781836 -0.0398033 0.0210658 -0.0774506 -0.0398033 0.0210224 -0.077059 -0.0401033 0.0217094 -0.0767713 -0.0398033 0.0213013 -0.0773297 -0.0398033 0.0210472 -0.0761379 -0.0398033 0.0221883 -0.0767166 -0.0401033 0.0220902 -0.0761193 -0.0398033 0.0230422 -0.0765733 -0.0401033 0.0225819 -0.0766188 -0.0398033 0.0238769 0.0569821 -0.0401033 -0.0590297 0.0569273 -0.0398033 -0.0598186 0.0556547 -0.0401033 -0.0595747 0.0195624 -0.0401033 -0.0775221 0.0200099 -0.0401033 -0.0777712 0.020305 -0.0401033 -0.0781897 0.0203892 -0.0401033 -0.0786949 0.0202459 -0.0401033 -0.0791865 0.0206822 -0.0398033 -0.0794294 0.0201912 -0.0398033 -0.0799754 0.0194298 -0.0401033 -0.0797619 0.0187789 -0.0398033 -0.080211 0.0592369 -0.0401033 0.0568392 0.0595707 -0.0398033 0.0572105 0.059532 -0.0401033 0.0564206 0.0594729 -0.0401033 0.0554238 0.0599092 -0.0398033 0.055181 0.0793938 -0.0401033 0.020103 0.079086 -0.0398033 0.0208315 0.0797276 -0.0398033 0.0204743 0.0796888 -0.0401033 0.0196845 0.0801507 -0.0398033 0.0198741 0.0797731 -0.0401033 0.0191793 0.0796298 -0.0401033 0.0186877 0.0802715 -0.0398033 0.0191498 0.0792874 -0.0401033 0.0183069 0.080066 -0.0398033 0.0184448 0.0788137 -0.0401033 0.0181123 0.0788958 -0.0398033 0.0176198 0.0783024 -0.0401033 0.0181426 0.0780346 -0.0401033 -0.0215408 0.0781743 -0.0398033 -0.0210614 0.0793154 -0.0398033 -0.0222532 0.0788304 -0.0401033 -0.0223719 0.0788174 -0.0401033 -0.0229675 0.0785084 -0.0401033 -0.0234767 0.0773907 -0.0401033 -0.0237503 0.077251 -0.0398033 -0.0242296 -0.0694454 -0.0350033 -0.0273661 -0.0625193 -0.0350033 -0.0511642 -0.0706025 -0.0350033 0.0461635 -0.059943 -0.0350033 0.0535358 -0.0125059 -0.0350033 0.0808696 0.082783 -0.0350033 0.00138539 0.00249695 -0.0350033 -0.0843107 -0.0786548 -0.0350033 0.0128175 0.0755585 -0.0350033 0.0374872 0.0457044 -0.0350033 -0.064649 -0.0345402 -0.0350033 0.0719877 -0.0352581 -0.0350033 0.0730062 -0.037101 -0.0350033 0.0683556 -0.03984 -0.0350033 0.0678988 -0.0469528 -0.0350033 0.0654052 -0.042994 -0.0350033 0.065319 -0.0412562 -0.0350033 0.068758 -0.042053 -0.0350033 0.0702102 -0.0548923 -0.0350033 0.0640512 -0.044147 -0.0350033 0.0700297 -0.0397055 -0.0350033 0.0740793 -0.0399978 -0.0350033 0.0742684 -0.0436016 -0.0350033 0.0722118 -0.042017 -0.0350033 0.0718663 -0.0732267 -0.0350033 0.0314441 -0.0684514 -0.0350033 0.0388847 -0.0661039 -0.0350033 0.0427537 -0.0669007 -0.0350033 0.0442059 -0.0724066 -0.0350033 0.0421821 -0.0760121 -0.0350033 0.0322558 -0.072715 -0.0350033 0.0427588 -0.0720081 -0.0350033 0.0435494 -0.0710559 -0.0350033 0.0446084 0.0723111 -0.0350033 -0.0412278 0.0673591 -0.0350033 -0.0393731 0.0614875 -0.0350033 -0.0539842 0.0659821 -0.0350033 -0.0505303 0.0683076 -0.0350033 -0.0450608 0.0664069 -0.0350033 -0.0404321 0.0660084 -0.0350033 -0.0417993 0.0660998 -0.0350033 -0.0451224 0.06287 -0.0350033 -0.0464486 0.0433077 -0.0350033 -0.0650486 0.0424745 -0.0350033 -0.0659752 0.0423309 -0.0350033 -0.0684007 0.0412469 -0.0350033 -0.0687536 0.0468573 -0.0350033 -0.0693597 0.0476407 -0.0350033 -0.0666715 -0.00252673 -0.0350033 -0.0778204 0.0013423 -0.0350033 -0.0801679 0.000545483 -0.0350033 -0.0787157 -0.00407739 -0.0350033 -0.0831416 0.000447019 -0.0350033 -0.0832401 0.0398307 -0.0350033 -0.0678944 0.0420437 -0.0350033 -0.0702058 0.0420076 -0.0350033 -0.0718619 0.0399885 -0.0350033 -0.074264 0.0311123 -0.0350033 -0.0783984 0.0396962 -0.0350033 -0.0740749 0.031993 -0.0350033 -0.0713457 0.0299705 -0.0350033 -0.073282 0.029939 -0.0350033 -0.0747311 0.0306362 -0.0350033 -0.0760017 0.0310286 -0.0350033 -0.0784316 0.0345308 -0.0350033 -0.0719833 0.034272 -0.0350033 -0.0763539 0.0351052 -0.0350033 -0.0754273 0.0352488 -0.0350033 -0.0730018 0.0273636 -0.0350033 -0.0694385 0.0777137 -0.0350033 -0.0327815 0.0699636 -0.0350033 -0.0450968 0.0814414 -0.0350033 0.00251957 0.0799924 -0.0350033 0.00255111 0.0789036 -0.0350033 0.00315721 0.0781856 -0.0350033 0.0041757 0.0834639 -0.0350033 0.00445592 0.0836357 -0.0350033 0.0109208 0.0803152 -0.0350033 0.00800115 0.0764729 -0.0350033 0.00322424 0.0713432 -0.0350033 0.0319999 0.0720404 -0.0350033 0.0307292 0.0767826 -0.0350033 0.0333312 0.0732796 -0.0350033 0.0299774 0.0808397 -0.0350033 0.0240668 0.0767511 -0.0350033 0.0318822 0.0680004 -0.0350033 0.0422081 0.0736237 -0.0350033 0.0411578 0.069271 -0.0350033 0.0429054 0.0718594 -0.0350033 0.0420145 0.0693572 -0.0350033 0.0468642 0.0683581 -0.0350033 0.0494132 0.068118 -0.0350033 0.047616 0.0657214 -0.0350033 0.0472164 0.0645396 -0.0350033 0.0450934 0.0647445 -0.0350033 0.0438643 0.0484737 -0.0350033 0.0626036 0.0497444 -0.0350033 0.0633008 0.0539818 -0.0350033 0.0614943 0.0504963 -0.0350033 0.0645399 0.045013 -0.0350033 0.0654888 0.043797 -0.0350033 0.0627765 0.0452179 -0.0350033 0.0642597 0.0470247 -0.0350033 0.0626351 0.0592929 -0.0350033 0.0599915 0.0498306 -0.0350033 0.0672596 0.0486103 -0.0350033 0.0689334 0.0485914 -0.0350033 0.0680115 0.0461313 -0.0350033 0.0706166 0.0473475 -0.0350033 0.0680851 0.0688245 -0.0350033 0.0365628 0.0566598 -0.0350033 0.0310936 0.0681682 -0.0350033 0.0404988 0.0786454 -0.0350033 -0.0128131 0.0786147 -0.0350033 -0.00397207 0.0738891 -0.0350033 -0.0114271 0.0787132 -0.0350033 0.000552346 0.0842921 -0.0350033 -0.00299483 0.0843393 -0.0350033 0.00101168 0.0840344 -0.0350033 -0.00099832 0.0832376 -0.0350033 0.000453881 0.0818214 -0.0350033 0.00131312 0.0780267 -0.0350033 0.00277143 0.0801654 -0.0350033 0.00134916 0.0831391 -0.0350033 -0.00407053 0.0839984 -0.0350033 -0.00265437 -0.049158 -0.0350033 -0.0449049 -0.0368376 -0.0350033 -0.0458961 -0.064287 -0.0350033 -0.0173321 -0.0378353 -0.0350033 0.0450817 -0.0283138 -0.0350033 0.0515959 -0.0177044 -0.0350033 0.0561274 0.0635011 -0.0350033 0.00700436 0.0539355 -0.0350033 -0.0258208 0.0586217 -0.0350033 -0.00512357 0.0593635 -0.0350033 -0.00719416 0.0458936 -0.0350033 -0.0368308 0.0469619 -0.0350033 -0.0497513 0.00640549 -0.0350033 -0.0584977 0.0176951 -0.0350033 -0.056123 0.0069975 -0.0350033 -0.0635036 -0.0178703 -0.0350033 0.0824385 -0.0129587 -0.0350033 0.0793158 -0.00602513 -0.0350033 0.0780944 -0.00590744 -0.0350033 0.0835023 0.0202851 -0.0350033 0.0696281 -8.7133e-05 -0.0350033 0.0835485 -0.00103934 -0.0350033 0.0824895 -0.00255358 -0.0350033 0.0799992 -0.00120353 -0.0350033 0.0797175 -0.00330541 -0.0350033 0.0787601 -0.000382977 -0.0350033 0.0785535 0.0099433 -0.0350033 0.0837635 0.00406806 -0.0350033 0.083146 0.00299236 -0.0350033 0.0842989 0.00194582 -0.0350033 0.0841274 -0.00445839 -0.0350033 0.0834708 -0.027373 -0.0350033 0.0694429 -0.0307317 -0.0350033 0.0720473 -0.0263671 -0.0350033 0.0728945 -0.025246 -0.0350033 0.0767417 -0.0299483 -0.0350033 0.0747355 -0.0311217 -0.0350033 0.0784028 -0.0306455 -0.0350033 0.0760061 -0.0318847 -0.0350033 0.076758 -0.0342813 -0.0350033 0.0763583 -0.0351145 -0.0350033 0.0754317 -0.0380495 -0.0350033 0.0740432 -0.0778273 -0.0350033 0.00252426 -0.0833752 -0.0350033 -0.00629849 -0.0723446 -0.0350033 0.0109787 -0.0780969 -0.0350033 -0.00601827 -0.0788487 -0.0350033 -0.00725741 -0.0823984 -0.0350033 -0.00294638 -0.0830751 -0.0350033 -0.000616035 -0.0832316 -0.0350033 -0.00387299 -0.0835802 -0.0350033 -0.00506935 -0.0801747 -0.0350033 -0.00134477 -0.0827793 -0.0350033 0.00437893 -0.0814401 -0.0350033 0.0136292 -0.0837315 -0.0350033 0.00331995 -0.0843014 -0.0350033 0.00299923 -0.0841299 -0.0350033 0.00195268 -0.0841916 -0.0350033 -0.00524085 -0.0838957 -0.0350033 0.000547949 -0.0701391 -0.0350033 -0.0447579 -0.0683675 -0.0350033 -0.0494089 -0.0646558 -0.0350033 -0.0457068 -0.0646243 -0.0350033 -0.0442578 -0.0653215 -0.0350033 -0.0429871 -0.0681775 -0.0350033 -0.0404944 -0.0665606 -0.0350033 -0.0422353 -0.0678046 -0.0350033 -0.0421616 -0.0691297 -0.0350033 -0.0415533 -0.0689573 -0.0350033 -0.042635 -0.0718687 -0.0350033 -0.0420101 -0.0721665 -0.0350033 -0.0436738 -0.073633 -0.0350033 -0.0411534 -0.0755679 -0.0350033 -0.0374828 -0.0740457 -0.0350033 -0.0380426 -0.0712772 -0.0350033 -0.0328267 -0.0760948 -0.0350033 -0.0345975 -0.0731864 -0.0350033 -0.0366265 -0.0736117 -0.0350033 -0.035423 -0.0717342 -0.0350033 -0.0358297 -0.0716258 -0.0350033 -0.0340231 -0.0486008 -0.0350033 -0.0680071 -0.0462041 -0.0350033 -0.0676074 -0.0442084 -0.0350033 -0.0668939 -0.0452273 -0.0350033 -0.0642553 -0.0474078 -0.0350033 -0.0697679 -0.0236036 -0.0350033 -0.0809794 -0.0224259 -0.0350033 -0.076938 -0.0366109 -0.0350033 -0.0759906 -0.0391994 -0.0350033 -0.0707618 -0.038801 -0.0350033 -0.0693945 -0.0781836 -0.0350033 0.0210658 -0.0773297 -0.0350033 0.0210472 -0.0761193 -0.0350033 0.0230422 -0.0779934 -0.0350033 0.0242774 -0.0786727 -0.0350033 0.0239985 0.0058981 -0.0350033 -0.0834979 0.00716878 -0.0350033 -0.0828007 0.00792061 -0.0350033 -0.0815616 0.00725494 -0.0350033 -0.0788419 0.0060158 -0.0350033 -0.07809 0.00321738 -0.0350033 -0.0764754 0.00361914 -0.0350033 -0.0784897 0.00278596 -0.0350033 -0.0794163 0.00243733 -0.0350033 -0.0806127 0.00108593 -0.0350033 -0.0837896 0.0026423 -0.0350033 -0.0818418 0.0180487 -0.0350033 -0.0797679 0.0187789 -0.0350033 -0.080211 0.0207668 -0.0350033 -0.0780001 0.0207474 -0.0350033 -0.0817552 0.024218 -0.0350033 -0.080795 0.0252367 -0.0350033 -0.0767373 0.0208876 -0.0350033 -0.0787244 0.0548356 -0.0350033 -0.0572781 0.054374 -0.0350033 -0.0588622 0.0547848 -0.0350033 -0.059611 0.0552562 -0.0350033 -0.063725 0.0469435 -0.0350033 -0.0654008 0.055515 -0.0350033 -0.0600541 0.0562481 -0.0350033 -0.0600975 0.0599336 -0.0350033 -0.0535314 0.0578677 -0.0350033 -0.0613632 0.0569273 -0.0350033 -0.0598186 0.0576238 -0.0350033 -0.0585675 0.057503 -0.0350033 -0.0578432 0.0722751 -0.0350033 -0.0428838 0.0787515 -0.0350033 -0.0302036 0.0826491 -0.0350033 -0.0168287 0.0792968 -0.0350033 -0.0231071 0.0831587 -0.0350033 -0.0140968 0.0789045 -0.0350033 -0.0215045 0.0774413 -0.0350033 -0.021018 0.0732174 -0.0350033 -0.0314398 0.0770217 -0.0350033 0.0188551 0.0770403 -0.0350033 0.019709 0.0728876 -0.0350033 0.0263647 0.0781627 -0.0350033 0.0176633 0.0793089 -0.0350033 0.0129562 0.0795751 -0.0350033 0.0178988 0.0782321 -0.0350033 0.0208501 0.0815591 -0.0350033 0.00792748 0.0808627 -0.0350033 0.0125034 0.0835217 -0.0350033 0.0117612 0.0817736 -0.0350033 0.0206717 0.0580752 -0.0350033 0.0575862 0.0594182 -0.0350033 0.0546349 0.0638305 -0.0350033 0.0551383 0.061419 -0.0350033 0.0578127 0.053529 -0.0350033 0.0599405 0.0427468 -0.0350033 0.0661015 0.0442498 -0.0350033 0.0643303 0.0450583 -0.0350033 0.0683144 0.044199 -0.0350033 0.0668983 0.0442975 -0.0350033 0.0714227 0.0428814 -0.0350033 0.0722819 0.0414597 -0.0350033 0.0723661 0.0366015 -0.0350033 0.075995 0.0235943 -0.0350033 0.0809838 0.0207379 -0.0350033 0.071182 -0.0176471 -0.0350033 0.0790235 -0.0207762 -0.0350033 0.0780045 -0.0176657 -0.0350033 0.0781696 -0.0188576 -0.0350033 0.0770285 -0.0207567 -0.0350033 0.0817596 -0.0187882 -0.0350033 0.0802153 -0.0195212 -0.0350033 0.0802588 -0.0202005 -0.0350033 0.0799798 -0.0206915 -0.0350033 0.0794338 -0.0564476 -0.0350033 0.0568902 -0.0511711 -0.0350033 0.0625168 -0.0575123 -0.0350033 0.0578476 -0.0690891 -0.0350033 0.0456427 -0.0680139 -0.0350033 0.0485983 -0.0681958 -0.0350033 0.0496499 -0.0646858 -0.0350033 0.0541434 -0.0680455 -0.0350033 0.0471493 -0.0673483 -0.0350033 0.0458786 -0.0634536 -0.0350033 0.049897 -0.0645424 -0.0350033 0.0505031 -0.062779 -0.0350033 0.0438038 -0.0625307 -0.0350033 0.0476494 -0.0767441 -0.0350033 -0.0252392 -0.0760086 -0.0350033 -0.0306386 -0.08016 -0.0350033 -0.0198697 -0.081783 -0.0350033 -0.0206674 -0.0826572 -0.0350033 -0.00731698 -0.083531 -0.0350033 -0.0117568 -0.0793182 -0.0350033 -0.0129518 -0.0789051 -0.0350033 -0.0176154 -0.0800754 -0.0350033 -0.0184404 -0.0535383 -0.0350033 -0.0599361 -0.0505056 -0.0350033 -0.0645355 -0.0599185 -0.0350033 -0.0551766 -0.0614284 -0.0350033 -0.0578083 -0.0601239 -0.0350033 -0.0558816 -0.0518851 -0.0350033 -0.0542631 -0.0580152 -0.0350033 -0.054395 0.00487055 -0.0350033 -0.0708024 -0.000870678 -0.0350033 -0.0778564 -0.0202945 -0.0350033 -0.0696237 -0.0186413 -0.0350033 -0.0639507 -0.0603923 -0.0350033 -0.0438654 0.0367225 -0.0350033 -0.0686552 0.0279638 -0.0350033 -0.067379 0.0167295 -0.0350033 -0.0663396 0.0197021 -0.0350033 -0.0770427 0.0188482 -0.0350033 -0.0770242 0.0310868 -0.0350033 -0.0566623 0.00759765 -0.0350033 -0.0614441 0.0173296 -0.0350033 -0.0642801 0.0146025 -0.0350033 -0.0736384 0.0129494 -0.0350033 -0.0793114 -0.0515984 -0.0350033 -0.0283069 -0.0597922 -0.0350033 -0.041806 -0.0271756 -0.0350033 -0.0521999 -0.0497582 -0.0350033 -0.0469643 -0.0165143 -0.0350033 -0.056652 0.0700981 -0.0350033 -0.0389163 0.0686765 -0.0350033 -0.0388321 -0.0701075 -0.0350033 0.0389207 -0.0669166 -0.0350033 0.0296053 0.0723353 -0.0350033 -0.0109743 0.0684611 -0.0350033 -0.0300537 0.0697887 -0.0350033 0.0157305 0.0669527 -0.0350033 0.00599853 0.0669073 -0.0350033 -0.0296009 0.0504134 -0.0350033 -0.0507571 -0.05427 -0.0350033 0.0518826 -0.057106 -0.0350033 0.0421506 -0.0612436 -0.0350033 0.0279521 -0.0736452 -0.0350033 -0.014605 0.069436 -0.0350033 0.0273705 0.0663371 -0.0350033 0.0167364 0.0628151 -0.0350033 -0.00819999 0.0573871 -0.0350033 -0.0268266 0.0473145 -0.0350033 -0.0613913 0.043863 -0.0350033 -0.0603854 -0.0418128 -0.0350033 0.0597897 -0.0449117 -0.0350033 0.0491555 -0.0477478 -0.0350033 0.0394235 -0.0522068 -0.0350033 0.0271731 -0.0565045 -0.0350033 0.0164669 -0.058631 -0.0350033 0.00512796 -0.0673859 -0.0350033 -0.0279663 -0.0566692 -0.0350033 -0.0310892 -0.0688339 -0.0350033 -0.0365584 -0.0438723 -0.0350033 0.0603898 -0.0469712 -0.0350033 0.0497557 -0.0498072 -0.0350033 0.0400237 -0.0539448 -0.0350033 0.0258252 -0.0593728 -0.0350033 0.00719855 -0.0666716 -0.0350033 0.0093255 -0.0663465 -0.0350033 -0.016732 -0.0732889 -0.0350033 -0.029973 0.0625099 -0.0350033 0.0511686 0.0613888 -0.0350033 0.0473214 0.060383 -0.0350033 0.0438698 0.0497488 -0.0350033 0.0469687 -0.0310961 -0.0350033 0.0566667 -0.0167388 -0.0350033 0.066344 -0.0146119 -0.0350033 0.0736428 0.0518758 -0.0350033 0.0542675 0.0421438 -0.0350033 0.0571035 0.0507547 -0.0350033 0.0504203 0.0410227 -0.0350033 0.0532563 0.0400168 -0.0350033 0.0498047 0.0368283 -0.0350033 0.0459005 0.018632 -0.0350033 0.0639551 -0.015733 -0.0350033 0.0697956 0.0175108 -0.0350033 0.0601079 0.016505 -0.0350033 0.0566564 -0.0397841 -0.0380033 0.0680908 -0.0401483 -0.0380033 0.0696325 -0.0360308 -0.0380033 0.0716842 -0.0371964 -0.0380033 0.0713989 -0.0376446 -0.0380033 0.0722158 -0.0410194 -0.0380033 0.073138 -0.0392408 -0.0380033 0.0727465 -0.041825 -0.0380033 0.0718103 0.0100141 -0.0411033 0.0843593 -0.00400731 -0.0356033 0.0848578 -0.00400731 -0.0411033 0.0848578 -0.031343 -0.0356033 0.0789605 -0.031343 -0.0411033 0.0789605 -0.0651459 -0.0411033 0.0545285 -0.0732322 -0.0411033 0.043063 -0.0732322 -0.0356033 0.043063 -0.079321 -0.0411033 0.0304228 -0.0832464 -0.0411033 0.0169529 -0.084901 -0.0356033 0.00302054 -0.084901 -0.0411033 0.00302054 -0.08424 -0.0356033 -0.0109941 -0.0812812 -0.0356033 -0.0247088 -0.08424 -0.0411033 -0.0109941 -0.0597241 -0.0411033 -0.0604138 0.01646 -0.0350033 0.0565021 0.0051211 -0.0295033 0.0586285 0.0051211 -0.0350033 0.0586285 -0.00641483 -0.0350033 0.058502 -0.00641483 -0.0295033 0.058502 -0.0283138 -0.0295033 0.0515959 -0.0522068 -0.0295033 0.0271731 -0.045903 -0.0350033 0.0368352 -0.0565045 -0.0295033 0.0164669 -0.058631 -0.0295033 0.00512796 -0.0585045 -0.0350033 -0.00640796 -0.0561299 -0.0295033 -0.0176975 -0.0561299 -0.0350033 -0.0176975 -0.0450842 -0.0295033 -0.0378284 -0.0450842 -0.0350033 -0.0378284 -0.0271756 -0.0295033 -0.0521999 -0.0164694 -0.0295033 -0.0564977 0.044153 -0.0380033 0.0712844 0.044153 -0.0352033 0.0712844 0.0449001 -0.0380033 0.0699229 0.0449001 -0.0352033 0.0699229 0.0440607 -0.0352033 0.0670427 0.0426993 -0.0380033 0.0662957 0.0404133 -0.0380033 0.0700852 0.040949 -0.0380033 0.0706809 0.0402576 -0.0380033 0.0716617 0.0414926 -0.0380033 0.0721688 0.0424897 -0.0380033 0.0709378 0.0432863 -0.0380033 0.0704545 0.0437345 -0.0380033 0.0696376 0.0432309 -0.0380033 0.0679095 0.0448663 -0.0380033 0.0683704 0.0440607 -0.0380033 0.0670427 0.0414825 -0.0380033 0.0674816 0.0411468 -0.0380033 0.0663295 0.0407825 -0.0380033 0.0678712 0.0399802 -0.0380033 0.0669789 0.040321 -0.0380033 0.068526 0.0392109 -0.0380033 0.0680702 0.0731311 -0.0352033 0.041017 0.0737393 -0.0380033 0.0400819 0.0738781 -0.0352033 0.0396555 0.0739589 -0.0352033 0.0387649 0.0738443 -0.0352033 0.038103 0.0735854 -0.0352033 0.0374831 0.0735854 -0.0380033 0.0374831 0.0730388 -0.0352033 0.0367753 0.0701248 -0.0352033 0.0360621 0.0702509 -0.0380033 0.0418563 0.0718035 -0.0380033 0.0418225 0.0722643 -0.0380033 0.0401871 0.07297 -0.0380033 0.0411731 0.0727125 -0.0380033 0.0393702 0.0693914 -0.0380033 0.0398178 0.0680839 -0.0380033 0.0397816 0.0714576 -0.0380033 0.0359832 0.0726927 -0.0380033 0.0364903 0.0722089 -0.0380033 0.0376421 0.0739589 -0.0380033 0.0387649 0.0817655 -0.0352033 0.0011211 0.0830931 -0.0352033 0.00031557 0.0838064 -0.0380033 -0.00259841 0.0816394 -0.0380033 -0.00467308 0.0816394 -0.0352033 -0.00467308 0.0800868 -0.0380033 -0.00463929 0.0800868 -0.0352033 -0.00463929 0.0788515 -0.0380033 0.000407881 0.0804982 -0.0380033 -1.07013e-05 0.0814298 -0.0380033 -3.09741e-05 0.0817655 -0.0380033 0.0011211 0.0830931 -0.0380033 0.00031557 0.0822264 -0.0380033 -0.000514295 0.0838402 -0.0380033 -0.00104587 0.0830008 -0.0380033 -0.00392607 0.0804226 -0.0380033 -0.00348721 0.0415524 -0.0411533 0.0677216 0.0423546 -0.0411533 0.0677042 0.0423902 -0.0413033 0.0675585 0.0434742 -0.0411533 0.0687761 0.0431617 -0.0413033 0.0679818 0.0436182 -0.0413033 0.0687341 0.043214 -0.0413033 0.0703854 0.0424197 -0.0382533 0.0706978 0.0431057 -0.0411533 0.0702816 0.0434916 -0.0411533 0.0695782 0.0434916 -0.0382533 0.0695782 0.043058 -0.0411533 0.0680901 0.0434742 -0.0382533 0.0687761 0.0423546 -0.0382533 0.0677042 0.0431057 -0.0382533 0.0702816 0.0437142 -0.0380033 0.0687061 0.043058 -0.0382533 0.0680901 0.042414 -0.0380033 0.0674613 0.0720005 -0.0411533 0.0400949 0.072398 -0.0411533 0.0395311 0.0724495 -0.0413033 0.0381154 0.0724522 -0.0411533 0.0385086 0.0723184 -0.0411533 0.0381884 0.0720361 -0.0411533 0.0378227 0.0712191 -0.0411533 0.0374134 0.0713326 -0.0411533 0.0374367 0.0712438 -0.0413033 0.0372654 0.0713978 -0.0411533 0.0404304 0.0713978 -0.0382533 0.0404304 0.0720837 -0.0411533 0.0400142 0.0724697 -0.0382533 0.0393108 0.0724697 -0.0411533 0.0393108 0.0725114 -0.0411533 0.0388507 0.0724522 -0.0382533 0.0385086 0.0720361 -0.0382533 0.0378227 0.0718572 -0.0411533 0.0376754 0.0714677 -0.0380033 0.0406704 0.0720837 -0.0382533 0.0400142 0.0726923 -0.0380033 0.0384387 0.0713921 -0.0380033 0.0371939 0.0713326 -0.0382533 0.0374367 0.0705305 -0.0382533 0.0374542 0.0804925 -0.0411533 -0.00324719 0.0804506 -0.0413033 -0.0033912 0.0812947 -0.0411533 -0.00326465 0.0824317 -0.0411533 -0.00139059 0.0825583 -0.0413033 -0.00223471 0.0820458 -0.0411533 -0.000687183 0.0825774 -0.0413033 -0.00135493 0.0820458 -0.0382533 -0.000687183 0.0824143 -0.0411533 -0.00219274 0.0819981 -0.0411533 -0.0028787 0.0824143 -0.0382533 -0.00219274 0.0812947 -0.0382533 -0.00326465 0.0824317 -0.0382533 -0.00139059 0.0826746 -0.0380033 -0.00133116 0.0819981 -0.0382533 -0.0028787 0.0826543 -0.0380033 -0.00226269 0.082171 -0.0380033 -0.00305928 0.0813541 -0.0380033 -0.00350748 0.0450943 -0.0350033 0.0699705 0.0448663 -0.0352033 0.0683704 0.0426993 -0.0352033 0.0662957 0.0410908 -0.0350033 0.0661375 0.0700689 -0.0350033 0.0358701 0.0717249 -0.0350033 0.035834 0.0716774 -0.0352033 0.0360283 0.0726927 -0.0352033 0.0364903 0.0731771 -0.0350033 0.0366309 0.0740364 -0.0350033 0.038047 0.0732756 -0.0350033 0.0411553 0.0737393 -0.0352033 0.0400819 0.0740724 -0.0350033 0.0397031 0.0838402 -0.0352033 -0.00104587 0.0838064 -0.0352033 -0.00259841 0.0830008 -0.0352033 -0.00392607 0.0816869 -0.0350033 -0.00486734 0.0800309 -0.0350033 -0.0048313 0.0485075 -0.0411033 0.0677234 0.0494796 -0.0411033 0.0671823 0.0497583 -0.0413033 0.0671905 0.0504002 -0.0413033 0.0645679 0.0492485 -0.0411033 0.06328 0.0482193 -0.0411033 0.0628573 0.0470527 -0.0413033 0.0627311 0.04845 -0.0413033 0.0627007 0.0485075 -0.0353033 0.0677234 0.0496139 -0.0411033 0.0670522 0.0496139 -0.0353033 0.0670522 0.0501207 -0.0411033 0.0662729 0.0502364 -0.0411033 0.0659176 0.0502364 -0.0353033 0.0659176 0.0503037 -0.0411033 0.0651755 0.0503037 -0.0353033 0.0651755 0.0502082 -0.0411033 0.0646238 0.0499924 -0.0353033 0.0641073 0.0499924 -0.0411033 0.0641073 0.049537 -0.0411033 0.0635175 0.049537 -0.0353033 0.0635175 0.0484024 -0.0411033 0.062895 0.0482193 -0.0353033 0.0628573 0.0471086 -0.0353033 0.0629231 0.0484024 -0.0353033 0.062895 0.0492485 -0.0353033 0.06328 0.0502082 -0.0353033 0.0646238 0.0505278 -0.0350033 0.065989 0.0501207 -0.0353033 0.0662729 0.0494796 -0.0353033 0.0671823 0.067929 -0.0411033 0.0424995 0.0692019 -0.0413033 0.0429776 0.0699269 -0.0413033 0.0441725 0.0699573 -0.0413033 0.0455698 0.0691405 -0.0411033 0.0466567 0.0680901 -0.0413033 0.04752 0.0691405 -0.0353033 0.0466567 0.069763 -0.0411033 0.0455222 0.069763 -0.0353033 0.0455222 0.0697348 -0.0411033 0.0442284 0.0697348 -0.0353033 0.0442284 0.0690636 -0.0411033 0.043122 0.0690636 -0.0353033 0.043122 0.067929 -0.0353033 0.0424995 0.0666352 -0.0353033 0.0425277 0.0680341 -0.0353033 0.047328 0.0700544 -0.0350033 0.0455935 0.0700229 -0.0350033 0.0441445 0.0757918 -0.0411033 0.0308597 0.0759301 -0.0413033 0.0307153 0.0764912 -0.0411033 0.0332599 0.0766855 -0.0413033 0.0333075 0.0760132 -0.0413033 0.0345327 0.0747624 -0.0411033 0.0350657 0.0758687 -0.0411033 0.0343944 0.0764631 -0.0411033 0.0319661 0.0764631 -0.0353033 0.0319661 0.0746573 -0.0411033 0.0302372 0.0757918 -0.0353033 0.0308597 0.0733635 -0.0411033 0.0302654 0.0733635 -0.0353033 0.0302654 0.0748463 -0.0350033 0.0353537 0.0760854 -0.0350033 0.0346019 0.0758687 -0.0353033 0.0343944 0.0764912 -0.0353033 0.0332599 0.0759993 -0.0350033 0.030643 0.0747286 -0.0350033 0.0299458 0.0746573 -0.0353033 0.0302372 0.0814176 -0.0413033 0.0026167 0.0826429 -0.0413033 0.00328902 0.0833679 -0.0413033 0.0044839 0.0833983 -0.0413033 0.00588119 0.082726 -0.0413033 0.00710649 0.0814752 -0.0411033 0.00763946 0.0825816 -0.0411033 0.00696818 0.0825816 -0.0353033 0.00696818 0.0832041 -0.0411033 0.00583364 0.0831759 -0.0411033 0.00453986 0.0831759 -0.0353033 0.00453986 0.0825046 -0.0411033 0.00343348 0.0813701 -0.0411033 0.00281097 0.0813701 -0.0353033 0.00281097 0.0814752 -0.0353033 0.00763946 0.0832041 -0.0353033 0.00583364 0.0827983 -0.0350033 0.00717564 0.0834955 -0.0350033 0.00590497 0.0825046 -0.0353033 0.00343348 0.0827121 -0.0350033 0.00321678 -0.000926633 -0.0380033 -0.0780484 0.000401018 -0.0352033 -0.078854 0.000401018 -0.0380033 -0.078854 0.00111424 -0.0352033 -0.081768 -0.00105273 -0.0380033 -0.0838426 0.000308708 -0.0352033 -0.0830956 -0.00105273 -0.0352033 -0.0838426 0.00111424 -0.0380033 -0.081768 3.08957e-05 -0.0380033 -0.0810351 0.00114803 -0.0380033 -0.0802154 -0.000100873 -0.0380033 -0.0802449 -0.000562431 -0.0380033 -0.0795902 -0.00260528 -0.0380033 -0.0838088 -0.00226955 -0.0380033 -0.0826568 0.000308708 -0.0380033 -0.0830956 -0.000728843 -0.0380033 -0.0823998 0.0411024 -0.0380033 -0.0688919 0.0411024 -0.0352033 -0.0688919 0.0418494 -0.0352033 -0.0702534 0.0418156 -0.0380033 -0.0718059 0.0418156 -0.0352033 -0.0718059 0.0405082 -0.0380033 -0.0718421 0.0418494 -0.0380033 -0.0702534 0.0407323 -0.0380033 -0.071073 0.0397748 -0.0380033 -0.0680864 0.0382222 -0.0380033 -0.0680526 0.0368608 -0.0380033 -0.0687996 0.0360552 -0.0380033 -0.0701273 0.037187 -0.0380033 -0.0713945 0.0380961 -0.0380033 -0.0738468 0.0384318 -0.0380033 -0.0726947 0.0392315 -0.0380033 -0.0727421 0.0396487 -0.0380033 -0.0738806 0.0410101 -0.0380033 -0.0731336 0.0713698 -0.0352033 -0.0399139 0.0721168 -0.0380033 -0.0412753 0.072083 -0.0352033 -0.0428279 0.072083 -0.0380033 -0.0428279 0.0712775 -0.0352033 -0.0441555 0.0699161 -0.0352033 -0.0449025 0.0699161 -0.0380033 -0.0449025 0.0674743 -0.0380033 -0.0395366 0.0689068 -0.0380033 -0.0402131 0.0700422 -0.0380033 -0.0391083 0.070503 -0.0380033 -0.0407437 0.0713698 -0.0380033 -0.0399139 0.0712775 -0.0380033 -0.0441555 0.0696308 -0.0380033 -0.0437369 0.067406 -0.0380033 -0.0418821 0.0664277 -0.0380033 -0.0431281 -0.001511 -0.0411533 -0.0824575 -0.000872887 -0.0411533 -0.0821955 -0.00148632 -0.0413033 -0.0826055 -0.000411659 -0.0411533 -0.0816826 -0.000280598 -0.0413033 -0.0817555 -0.000218667 -0.0411533 -0.0810203 -0.000729587 -0.0411533 -0.0797761 -0.000729587 -0.0382533 -0.0797761 -0.000332134 -0.0411533 -0.0803399 -0.000411659 -0.0382533 -0.0816826 -0.001511 -0.0382533 -0.0824575 -0.00219961 -0.0382533 -0.0824167 -0.000332134 -0.0382533 -0.0803399 -0.000218667 -0.0382533 -0.0810203 -0.000193225 -0.0380033 -0.0818041 -0.000872887 -0.0382533 -0.0821955 -0.00146987 -0.0380033 -0.0827041 0.0399149 -0.0413033 -0.0723561 0.0404208 -0.0413033 -0.0717935 0.0404827 -0.0411533 -0.0710583 0.0403693 -0.0411533 -0.0703778 0.040508 -0.0413033 -0.0703209 0.0400721 -0.0413033 -0.0697025 0.0399718 -0.0411533 -0.069814 0.039411 -0.0413033 -0.0693345 0.0393691 -0.0382533 -0.0694785 0.0403693 -0.0382533 -0.0703778 0.0404827 -0.0382533 -0.0710583 0.0402897 -0.0411533 -0.0717205 0.0402897 -0.0382533 -0.0717205 0.0398285 -0.0382533 -0.0722335 0.0398285 -0.0411533 -0.0722335 0.0391904 -0.0411533 -0.0724955 0.0385018 -0.0411533 -0.0724547 0.0391904 -0.0382533 -0.0724955 0.0399718 -0.0382533 -0.069814 0.040139 -0.0380033 -0.0696281 0.0406005 -0.0380033 -0.0702829 0.0399725 -0.0380033 -0.0724378 0.0703225 -0.0411533 -0.0409166 0.0708541 -0.0413033 -0.0415844 0.0707084 -0.0411533 -0.04162 0.0705571 -0.0411533 -0.0427425 0.0703785 -0.0413033 -0.0432165 0.0702748 -0.0411533 -0.0431081 0.0700959 -0.0411533 -0.0432554 0.0687692 -0.0411533 -0.0434766 0.0687272 -0.0413033 -0.0436207 0.0696365 -0.0411533 -0.0405004 0.0696365 -0.0382533 -0.0405004 0.0702392 -0.0411533 -0.040836 0.0706367 -0.0411533 -0.0413998 0.0707084 -0.0382533 -0.04162 0.0707501 -0.0411533 -0.0420802 0.070691 -0.0411533 -0.0424222 0.070691 -0.0382533 -0.0424222 0.0702748 -0.0382533 -0.0431081 0.0695713 -0.0411533 -0.0434941 0.0694578 -0.0411533 -0.0435174 0.0686993 -0.0380033 -0.0437167 0.0694578 -0.0382533 -0.0435174 0.0695713 -0.0382533 -0.0434941 0.0700959 -0.0382533 -0.0432554 0.0704476 -0.0380033 -0.0432887 0.0705571 -0.0382533 -0.0427425 0.070931 -0.0380033 -0.0424921 0.0707501 -0.0382533 -0.0420802 0.0709512 -0.0380033 -0.0415606 0.0706367 -0.0382533 -0.0413998 0.0697064 -0.0380033 -0.0402604 0.0702392 -0.0382533 -0.040836 0.0703225 -0.0382533 -0.0409166 0.00114803 -0.0352033 -0.0802154 0.00130626 -0.0350033 -0.0818239 -0.00100518 -0.0350033 -0.0840369 0.0380402 -0.0350033 -0.0740388 0.0399338 -0.0350033 -0.0740069 0.0396487 -0.0352033 -0.0738806 0.0410101 -0.0352033 -0.0731336 0.0411484 -0.0350033 -0.073278 0.0700422 -0.0352033 -0.0391083 0.0721168 -0.0352033 -0.0412753 0.0715143 -0.0350033 -0.0397756 0.0714158 -0.0350033 -0.0443 0.00447704 -0.0413033 -0.0833704 0.00564365 -0.0411033 -0.0832442 0.00567655 -0.0413033 -0.0834414 0.00772805 -0.0411033 -0.080926 0.00754504 -0.0411033 -0.0798286 0.00690399 -0.0411033 -0.0789192 0.00703824 -0.0353033 -0.0790493 0.00766075 -0.0353033 -0.0801839 0.00772805 -0.0353033 -0.080926 0.00741678 -0.0353033 -0.0819942 0.00696131 -0.0353033 -0.082584 0.00741678 -0.0411033 -0.0819942 0.00667286 -0.0411033 -0.0828215 0.00582678 -0.0353033 -0.0832065 0.00667286 -0.0353033 -0.0828215 0.00763259 -0.0353033 -0.0814777 0.00795215 -0.0350033 -0.0801125 0.00754504 -0.0353033 -0.0798286 0.0331028 -0.0413033 -0.0767286 0.034843 -0.0411033 -0.0752814 0.0351543 -0.0411033 -0.0742132 0.035354 -0.0413033 -0.074225 0.0349713 -0.0411033 -0.0731158 0.0351563 -0.0413033 -0.0730398 0.0334141 -0.0413033 -0.0714732 0.0343302 -0.0411033 -0.0722064 0.0343302 -0.0353033 -0.0722064 0.034843 -0.0353033 -0.0752814 0.0340991 -0.0411033 -0.0761087 0.0340991 -0.0353033 -0.0761087 0.0330699 -0.0411033 -0.0765313 0.0319593 -0.0411033 -0.0764656 0.0349713 -0.0353033 -0.0731158 0.0351543 -0.0353033 -0.0742132 0.0354538 -0.0350033 -0.0742309 0.0330699 -0.0353033 -0.0765313 0.0331193 -0.0350033 -0.0768273 0.0455154 -0.0411033 -0.0697655 0.0455629 -0.0413033 -0.0699597 0.0467882 -0.0413033 -0.0692874 0.0473493 -0.0411033 -0.0667428 0.0456204 -0.0353033 -0.064937 0.0467268 -0.0411033 -0.0656083 0.0467268 -0.0353033 -0.0656083 0.0473212 -0.0411033 -0.0680366 0.0473212 -0.0353033 -0.0680366 0.0466499 -0.0411033 -0.069143 0.0473493 -0.0353033 -0.0667428 0.0476092 -0.0350033 -0.0681205 0.0466499 -0.0353033 -0.069143 0.0455154 -0.0353033 -0.0697655 0.0455867 -0.0350033 -0.0700569 0.0442216 -0.0353033 -0.0697373 0.0441376 -0.0350033 -0.0700253 0.0660718 -0.0413033 -0.0452184 0.0660159 -0.0411033 -0.0454104 0.0671217 -0.0413033 -0.0458028 0.067629 -0.0411033 -0.0468609 0.0677447 -0.0411033 -0.0472162 0.0680117 -0.0413033 -0.0479702 0.0677166 -0.0411033 -0.04851 0.0676755 -0.0413033 -0.0491238 0.0667569 -0.0411033 -0.0498539 0.0659108 -0.0411033 -0.0502389 0.066988 -0.0411033 -0.0459515 0.0671222 -0.0411033 -0.0460817 0.0677447 -0.0353033 -0.0472162 0.067812 -0.0411033 -0.0479584 0.0675008 -0.0411033 -0.0490265 0.0670453 -0.0353033 -0.0496164 0.0670453 -0.0411033 -0.0496164 0.0657276 -0.0411033 -0.0502765 0.0659108 -0.0353033 -0.0502389 0.0673389 -0.0350033 -0.0458742 0.0671222 -0.0353033 -0.0460817 0.0680361 -0.0350033 -0.0471449 0.0680046 -0.0350033 -0.0485939 0.0677166 -0.0353033 -0.04851 0.0672528 -0.0350033 -0.0498331 0.064617 -0.0353033 -0.0502107 0.00463682 -0.0380033 0.0800937 0.00383128 -0.0352033 0.0787661 0.00246985 -0.0380033 0.078019 0.00246985 -0.0352033 0.078019 2.81017e-05 -0.0380033 0.083385 0.00259594 -0.0380033 0.0838132 0.00305681 -0.0380033 0.0821778 0.00392359 -0.0380033 0.0830077 0.00467061 -0.0380033 0.0816463 0.00300142 -0.0380033 0.0796328 0.00383128 -0.0380033 0.0787661 0.00125303 -0.0380033 0.0792049 0.000917299 -0.0380033 0.0780528 -0.000249252 -0.0380033 0.0787022 9.1539e-05 -0.0380033 0.0802493 -4.02292e-05 -0.0380033 0.0810395 0.000183891 -0.0380033 0.0818085 -0.0381054 -0.0380033 0.0738512 -0.0367778 -0.0380033 0.0730457 -0.0360308 -0.0352033 0.0716842 -0.03595 -0.0352033 0.0707936 -0.0360646 -0.0380033 0.0701317 -0.0360646 -0.0352033 0.0701317 -0.0368701 -0.0380033 0.068804 -0.0372162 -0.0352033 0.068519 -0.0382315 -0.0380033 0.068057 -0.0382315 -0.0352033 0.068057 -0.0670452 -0.0380033 0.0440676 -0.0671375 -0.0352033 0.039826 -0.068499 -0.0352033 0.039079 -0.0709606 -0.0380033 0.041565 -0.0709403 -0.0380033 0.0424965 -0.070457 -0.0380033 0.0432931 -0.0687086 -0.0380033 0.0437211 -0.0674841 -0.0380033 0.0414893 -0.0662982 -0.0380033 0.0427062 -0.0679674 -0.0380033 0.0406928 -0.066332 -0.0380033 0.0411536 -0.0671375 -0.0380033 0.039826 -0.0687843 -0.0380033 0.0402445 -0.0697158 -0.0380033 0.0402648 -0.068499 -0.0380033 0.039079 -0.0700515 -0.0380033 0.0391127 -0.0705124 -0.0380033 0.0407481 0.00282853 -0.0411533 0.0798134 0.00293226 -0.0413033 0.0797051 0.00326218 -0.0411533 0.0813015 0.00287622 -0.0411533 0.0820049 0.00219027 -0.0411533 0.0824211 0.00287622 -0.0382533 0.0820049 0.00326218 -0.0382533 0.0813015 0.00324472 -0.0411533 0.0804994 0.00212512 -0.0382533 0.0794275 0.00212512 -0.0411533 0.0794275 0.00226022 -0.0380033 0.0826612 0.00350501 -0.0380033 0.081361 0.00324472 -0.0382533 0.0804994 0.00348474 -0.0380033 0.0804294 0.00282853 -0.0382533 0.0798134 0.00218456 -0.0380033 0.0791846 -0.0393784 -0.0411533 0.0694829 -0.0386898 -0.0411533 0.0694421 -0.0375905 -0.0411533 0.0702171 -0.0372477 -0.0413033 0.0708705 -0.0373975 -0.0411533 0.0708794 -0.0379084 -0.0411533 0.0721236 -0.0378081 -0.0413033 0.0722351 -0.0378252 -0.0382533 0.0720429 -0.0375109 -0.0411533 0.0715598 -0.0374392 -0.0382533 0.0713395 -0.0378729 -0.0382533 0.0698514 -0.0380517 -0.0411533 0.0697041 -0.0380517 -0.0382533 0.0697041 -0.0385763 -0.0382533 0.0694654 -0.0393784 -0.0382533 0.0694829 -0.0385168 -0.0380033 0.0692226 -0.0377 -0.0380033 0.0696708 -0.0372166 -0.0380033 0.0704674 -0.0375905 -0.0382533 0.0702171 -0.0374567 -0.0382533 0.0705374 -0.0373975 -0.0382533 0.0708794 -0.0385111 -0.0382533 0.0724591 -0.0384412 -0.0380033 0.0726991 -0.0375109 -0.0382533 0.0715598 -0.0689572 -0.0411533 0.040464 -0.0696878 -0.0413033 0.0403608 -0.0689325 -0.0413033 0.0403161 -0.0683191 -0.0411533 0.0407261 -0.0678579 -0.0411533 0.041239 -0.0677268 -0.0413033 0.0411661 -0.0675152 -0.0413033 0.0418924 -0.0676649 -0.0411533 0.0419013 -0.0677784 -0.0411533 0.0425817 -0.0676396 -0.0413033 0.0426387 -0.0680926 -0.0382533 0.0430648 -0.0681758 -0.0411533 0.0431455 -0.0677784 -0.0382533 0.0425817 -0.0677066 -0.0382533 0.0423614 -0.0676649 -0.0382533 0.0419013 -0.0677241 -0.0382533 0.0415593 -0.0681403 -0.0382533 0.0408733 -0.0683191 -0.0382533 0.0407261 -0.0696458 -0.0382533 0.0405048 -0.0688437 -0.0382533 0.0404874 -0.0678579 -0.0382533 0.041239 -0.067912 -0.0380033 0.0432377 -0.0674638 -0.0380033 0.0424209 0.0026519 -0.0350033 0.0840052 0.00392359 -0.0352033 0.0830077 0.00467061 -0.0352033 0.0816463 0.00463682 -0.0352033 0.0800937 0.00486487 -0.0350033 0.0816938 0.00482883 -0.0350033 0.0800378 0.0039696 -0.0350033 0.0786216 0.00251739 -0.0350033 0.0778248 0.000917299 -0.0352033 0.0780528 0.000861345 -0.0350033 0.0778608 -0.0384184 -0.0350033 0.0678146 -0.0384513 -0.0352033 0.0680119 -0.0368701 -0.0352033 0.068804 -0.0361488 -0.0350033 0.0694145 -0.0363235 -0.0352033 0.0695118 -0.0357504 -0.0350033 0.0707818 -0.0359846 -0.0350033 0.0721865 -0.0361696 -0.0352033 0.0721106 -0.0368052 -0.0350033 0.0733505 -0.0381054 -0.0352033 0.0738512 -0.0369389 -0.0352033 0.0732018 -0.0367778 -0.0352033 0.0730457 -0.0670452 -0.0352033 0.0440676 -0.0683169 -0.0350033 0.0450651 -0.0662982 -0.0352033 0.0427062 -0.066332 -0.0352033 0.0411536 -0.06614 -0.0350033 0.0410977 -0.0669992 -0.0350033 0.0396815 -0.00351288 -0.0411033 0.0789768 -0.00281344 -0.0411033 0.081377 -0.00261917 -0.0413033 0.0814245 -0.00329149 -0.0413033 0.0826498 -0.00343595 -0.0411033 0.0825115 -0.00454233 -0.0411033 0.0831828 -0.00454233 -0.0353033 0.0831828 -0.00343595 -0.0353033 0.0825115 -0.00281344 -0.0353033 0.081377 -0.0028416 -0.0411033 0.0800832 -0.00464741 -0.0411033 0.0783543 -0.0059412 -0.0411033 0.0783824 -0.00464741 -0.0353033 0.0783543 -0.00321925 -0.0350033 0.082719 -0.00252204 -0.0350033 0.0814483 -0.0028416 -0.0353033 0.0800832 -0.00351288 -0.0353033 0.0789768 -0.00457609 -0.0350033 0.0780629 -0.0334234 -0.0413033 0.0714776 -0.0320261 -0.0413033 0.0714472 -0.0309391 -0.0411033 0.072264 -0.0302679 -0.0411033 0.0733704 -0.0308008 -0.0413033 0.0721195 -0.0300758 -0.0413033 0.0733144 -0.0302397 -0.0411033 0.0746641 -0.0307177 -0.0413033 0.075937 -0.0308622 -0.0411033 0.0757987 -0.0320737 -0.0411033 0.0716415 -0.0309391 -0.0353033 0.072264 -0.0319686 -0.0353033 0.07647 -0.0308622 -0.0353033 0.0757987 -0.0302397 -0.0353033 0.0746641 -0.0302679 -0.0353033 0.0733704 -0.0299798 -0.0350033 0.0732864 -0.0320737 -0.0353033 0.0716415 -0.0333675 -0.0353033 0.0716696 -0.0320023 -0.0350033 0.0713501 -0.0442884 -0.0413033 0.064719 -0.0423382 -0.0413033 0.0665862 -0.0423077 -0.0413033 0.0679834 -0.0442309 -0.0411033 0.0697417 -0.0431245 -0.0411033 0.0690704 -0.0442309 -0.0353033 0.0697417 -0.042502 -0.0411033 0.0679359 -0.0431245 -0.0353033 0.0690704 -0.042502 -0.0353033 0.0679359 -0.0425302 -0.0411033 0.0666421 -0.0432014 -0.0411033 0.0655357 -0.0425302 -0.0353033 0.0666421 -0.0432014 -0.0353033 0.0655357 -0.044336 -0.0411033 0.0649132 -0.0456298 -0.0411033 0.0649414 -0.0429078 -0.0350033 0.0692779 -0.0422106 -0.0350033 0.0680072 -0.0422421 -0.0350033 0.0665582 -0.044336 -0.0353033 0.0649132 -0.0442647 -0.0350033 0.0646218 -0.0456298 -0.0353033 0.0649414 -0.0646263 -0.0411033 0.0502151 -0.0633755 -0.0413033 0.0496821 -0.0635199 -0.0411033 0.0495438 -0.0630131 -0.0411033 0.0487646 -0.0628974 -0.0411033 0.0484093 -0.0627336 -0.0413033 0.0470595 -0.0660252 -0.0411033 0.0454148 -0.0660811 -0.0413033 0.0452228 -0.0646839 -0.0413033 0.0451923 -0.0647314 -0.0411033 0.0453866 -0.0635969 -0.0411033 0.0460091 -0.0631414 -0.0411033 0.0465989 -0.0628301 -0.0411033 0.0476671 -0.0629256 -0.0411033 0.0471155 -0.0631414 -0.0353033 0.0465989 -0.0638853 -0.0411033 0.0457716 -0.0649145 -0.0353033 0.045349 -0.0636542 -0.0353033 0.0496739 -0.0630131 -0.0353033 0.0487646 -0.0627356 -0.0350033 0.0488785 -0.0628301 -0.0353033 0.0476671 -0.0628793 -0.0350033 0.046453 -0.0638853 -0.0353033 0.0457716 -0.0637125 -0.0350033 0.0455264 -0.0648652 -0.0350033 0.0450531 -0.0399895 -0.0380033 -0.0669745 -0.0399895 -0.0352033 -0.0669745 -0.0392203 -0.0380033 -0.0680658 -0.0392203 -0.0352033 -0.0680658 -0.0390007 -0.0380033 -0.0693827 -0.0390007 -0.0352033 -0.0693827 -0.0415019 -0.0380033 -0.0721645 -0.0404227 -0.0380033 -0.0700808 -0.0409583 -0.0380033 -0.0706765 -0.0393742 -0.0380033 -0.0706645 -0.0402669 -0.0380033 -0.0716573 -0.0416993 -0.0380033 -0.0709808 -0.042499 -0.0380033 -0.0709334 -0.0428347 -0.0380033 -0.0720855 -0.0441624 -0.0380033 -0.07128 -0.0449094 -0.0380033 -0.0699185 -0.0437235 -0.0380033 -0.0687017 -0.0407919 -0.0380033 -0.0678668 -0.0403303 -0.0380033 -0.0685216 -0.0701341 -0.0352033 -0.0360577 -0.0689676 -0.0380033 -0.0367071 -0.0681983 -0.0352033 -0.0377983 -0.0681983 -0.0380033 -0.0377983 -0.0679787 -0.0380033 -0.0391153 -0.0683523 -0.0380033 -0.0403971 -0.0683523 -0.0352033 -0.0403971 -0.069245 -0.0380033 -0.0413899 -0.0718128 -0.0380033 -0.0418181 -0.07048 -0.0352033 -0.041897 -0.0693084 -0.0380033 -0.0382542 -0.0691766 -0.0380033 -0.0390443 -0.0694007 -0.0380033 -0.0398134 -0.07048 -0.0380033 -0.041897 -0.0714771 -0.0380033 -0.040666 -0.0727219 -0.0380033 -0.0393658 -0.0738875 -0.0380033 -0.0396511 -0.0722183 -0.0380033 -0.0376377 -0.0738537 -0.0380033 -0.0380986 -0.0730481 -0.0380033 -0.0367709 -0.0714014 -0.0380033 -0.0371895 -0.0716867 -0.0380033 -0.0360239 -0.0787685 -0.0380033 0.00383815 -0.0780215 -0.0380033 0.00247671 -0.0780553 -0.0352033 0.000924162 -0.0788608 -0.0352033 -0.000403489 -0.0817748 -0.0380033 -0.00111671 -0.0780553 -0.0380033 0.000924162 -0.0792704 -0.0380033 0.00244722 -0.0804319 -0.0380033 0.0034916 -0.0813634 -0.0380033 0.00351188 -0.0821803 -0.0380033 0.00306367 -0.0826636 -0.0380033 0.00226708 -0.0838495 -0.0380033 0.00105026 -0.0826839 -0.0380033 0.00133555 -0.0814391 -0.0380033 3.53661e-05 -0.0802223 -0.0380033 -0.0011505 -0.0788608 -0.0380033 -0.000403489 -0.042471 -0.0413033 -0.0708374 -0.0417404 -0.0411533 -0.0707342 -0.0406411 -0.0411533 -0.0699592 -0.0402984 -0.0413033 -0.0693058 -0.0405616 -0.0411533 -0.0686165 -0.040959 -0.0411533 -0.0680527 -0.0404228 -0.0413033 -0.0685596 -0.0415618 -0.0411533 -0.0677172 -0.0415618 -0.0382533 -0.0677172 -0.040959 -0.0382533 -0.0680527 -0.0405616 -0.0382533 -0.0686165 -0.0404481 -0.0411533 -0.069297 -0.0406411 -0.0382533 -0.0699592 -0.0411023 -0.0411533 -0.0704722 -0.0414918 -0.0380033 -0.0674772 -0.0404481 -0.0382533 -0.069297 -0.0401986 -0.0380033 -0.0693117 -0.0411023 -0.0382533 -0.0704722 -0.0417404 -0.0382533 -0.0707342 -0.0707185 -0.0411533 -0.0404668 -0.069994 -0.0413033 -0.0403274 -0.0694881 -0.0413033 -0.0397648 -0.0695397 -0.0411533 -0.0383491 -0.0704979 -0.0413033 -0.0373058 -0.0705398 -0.0411533 -0.0374498 -0.0699371 -0.0411533 -0.0377853 -0.0694262 -0.0411533 -0.0390295 -0.0695397 -0.0382533 -0.0383491 -0.0694262 -0.0382533 -0.0390295 -0.0696192 -0.0411533 -0.0396918 -0.0700804 -0.0411533 -0.0402048 -0.0704699 -0.0380033 -0.0372098 -0.0699371 -0.0382533 -0.0377853 -0.0697699 -0.0380033 -0.0375994 -0.0696192 -0.0382533 -0.0396918 -0.0700804 -0.0382533 -0.0402048 -0.0699364 -0.0380033 -0.0404091 -0.0707185 -0.0382533 -0.0404668 -0.0714071 -0.0382533 -0.040426 -0.0706774 -0.0380033 -0.0407134 -0.0806559 -0.0413033 8.66405e-05 -0.0806805 -0.0411533 0.000234597 -0.0800424 -0.0411533 0.000496627 -0.0795812 -0.0411533 0.00100957 -0.079956 -0.0413033 0.000374028 -0.0794501 -0.0413033 0.000936614 -0.0792385 -0.0413033 0.00166297 -0.0793629 -0.0413033 0.00240924 -0.0798991 -0.0411533 0.00291606 -0.0805019 -0.0382533 0.00325159 -0.0798991 -0.0382533 0.00291606 -0.0795017 -0.0411533 0.00235226 -0.0795017 -0.0382533 0.00235226 -0.0793882 -0.0411533 0.00167184 -0.0800424 -0.0382533 0.000496627 -0.0806805 -0.0382533 0.000234597 -0.079732 -0.0380033 0.00310196 -0.0793882 -0.0382533 0.00167184 -0.0791387 -0.0380033 0.00165706 -0.0795812 -0.0382533 0.00100957 -0.0793628 -0.0380033 0.000887975 -0.0798984 -0.0380033 0.000292295 -0.0806394 -0.0380033 -1.19974e-05 -0.0411001 -0.0350033 -0.0661331 -0.0398558 -0.0350033 -0.0668258 -0.0390353 -0.0350033 -0.0679898 -0.0393742 -0.0352033 -0.0706645 -0.0402669 -0.0352033 -0.0716573 -0.0401517 -0.0350033 -0.0718208 -0.0415019 -0.0352033 -0.0721645 -0.041469 -0.0350033 -0.0723617 -0.0428907 -0.0350033 -0.0722775 -0.0689676 -0.0352033 -0.0367071 -0.0700782 -0.0350033 -0.0358657 -0.0680133 -0.0350033 -0.0377224 -0.0679787 -0.0352033 -0.0391153 -0.0677791 -0.0350033 -0.0391271 -0.069245 -0.0352033 -0.0413899 -0.0704471 -0.0350033 -0.0420943 -0.0787685 -0.0352033 0.00383815 -0.0780215 -0.0352033 0.00247671 -0.0786241 -0.0350033 0.00397646 -0.0778633 -0.0350033 0.000868207 -0.0802223 -0.0352033 -0.0011505 -0.0787225 -0.0350033 -0.000547954 -0.0458671 -0.0413033 -0.0634517 -0.0451948 -0.0413033 -0.064677 -0.0452252 -0.0413033 -0.0660743 -0.0454172 -0.0411033 -0.0660183 -0.0471755 -0.0413033 -0.0679415 -0.0460885 -0.0411033 -0.0671247 -0.0459502 -0.0413033 -0.0672692 -0.047118 -0.0353033 -0.0629187 -0.0461458 -0.0353033 -0.0634599 -0.047118 -0.0411033 -0.0629187 -0.0460116 -0.0411033 -0.06359 -0.0455048 -0.0411033 -0.0643693 -0.0453891 -0.0411033 -0.0647245 -0.0453218 -0.0353033 -0.0654667 -0.0453218 -0.0411033 -0.0654667 -0.0456331 -0.0353033 -0.0665349 -0.0456331 -0.0411033 -0.0665349 -0.046377 -0.0411033 -0.0673622 -0.046377 -0.0353033 -0.0673622 -0.0472231 -0.0411033 -0.0677472 -0.0485168 -0.0353033 -0.0677191 -0.0485168 -0.0411033 -0.0677191 -0.0459453 -0.0350033 -0.0632368 -0.0455048 -0.0353033 -0.0643693 -0.0450223 -0.0350033 -0.0654844 -0.0453709 -0.0350033 -0.0666808 -0.0474062 -0.0353033 -0.0677848 -0.0473568 -0.0350033 -0.0680808 -0.0655387 -0.0413033 -0.0429158 -0.0655382 -0.0411033 -0.0431946 -0.0650314 -0.0411033 -0.0439738 -0.0646487 -0.0413033 -0.0450831 -0.0649438 -0.0411033 -0.0456229 -0.0651597 -0.0411033 -0.0461395 -0.0656151 -0.0411033 -0.0467293 -0.0657883 -0.0413033 -0.0471303 -0.0669328 -0.0411033 -0.0473894 -0.0668999 -0.0413033 -0.0475867 -0.0656724 -0.0411033 -0.0430645 -0.0655382 -0.0353033 -0.0431946 -0.0649157 -0.0353033 -0.0443291 -0.0649157 -0.0411033 -0.0443291 -0.0648484 -0.0411033 -0.0450713 -0.0649438 -0.0353033 -0.0456229 -0.0656151 -0.0353033 -0.0467293 -0.0659036 -0.0411033 -0.0469668 -0.0667497 -0.0411033 -0.0473518 -0.0680434 -0.0411033 -0.0473236 -0.0654077 -0.0350033 -0.046946 -0.0667497 -0.0353033 -0.0473518 -0.0666783 -0.0350033 -0.0476432 -0.0681274 -0.0350033 -0.0476117 -0.073661 -0.0411033 -0.0351271 -0.0726318 -0.0411033 -0.0347045 -0.0718879 -0.0411033 -0.0338771 -0.0717132 -0.0413033 -0.0339744 -0.0715766 -0.0411033 -0.032809 -0.0724007 -0.0411033 -0.0308022 -0.0715746 -0.0413033 -0.0316355 -0.0717596 -0.0411033 -0.0317115 -0.0724007 -0.0353033 -0.0308022 -0.0718879 -0.0353033 -0.0338771 -0.0726318 -0.0353033 -0.0347045 -0.073661 -0.0353033 -0.0351271 -0.0747717 -0.0411033 -0.0350613 -0.0733728 -0.0353033 -0.030261 -0.0717596 -0.0353033 -0.0317115 -0.0722001 -0.0350033 -0.0305791 -0.0714821 -0.0350033 -0.0315976 -0.0715766 -0.0353033 -0.032809 -0.072459 -0.0350033 -0.0349497 -0.0747717 -0.0353033 -0.0350613 -0.0748556 -0.0350033 -0.0353493 -0.0789798 -0.0413033 -0.00322718 -0.0789793 -0.0411033 -0.00350601 -0.0783568 -0.0411033 -0.00464055 -0.0780898 -0.0413033 -0.00539454 -0.0783849 -0.0411033 -0.00593433 -0.0790562 -0.0411033 -0.00704071 -0.0803739 -0.0411033 -0.00770085 -0.0791135 -0.0411033 -0.0033759 -0.0784725 -0.0411033 -0.00428526 -0.0783568 -0.0353033 -0.00464055 -0.0782895 -0.0411033 -0.00538271 -0.0783849 -0.0353033 -0.00593433 -0.0786007 -0.0411033 -0.00645088 -0.0801907 -0.0353033 -0.00766322 -0.0793446 -0.0411033 -0.00727822 -0.0801907 -0.0411033 -0.00766322 -0.0800017 -0.0350033 -0.00254671 -0.0789793 -0.0353033 -0.00350601 -0.0787626 -0.0350033 -0.00329855 -0.0780654 -0.0350033 -0.00456922 -0.0790562 -0.0353033 -0.00704071 -0.0801194 -0.0350033 -0.00795462 -0.0815684 -0.0350033 -0.00792308 -0.0237715 -0.0356033 -0.0815554 -0.0593023 -0.0350033 -0.0599871 -0.0489654 -0.0356033 -0.0694193 -0.0486196 -0.0350033 -0.068929 -0.0368713 -0.0356033 -0.0765312 -0.0638398 -0.0350033 -0.0551339 -0.0597241 -0.0356033 -0.0604138 -0.0742893 -0.0350033 -0.0399568 -0.0688537 -0.0356033 -0.0497603 -0.0683147 -0.0350033 -0.0494818 -0.0761054 -0.0356033 -0.0377494 -0.0807071 -0.0350033 -0.0245343 -0.0808491 -0.0350033 -0.0240624 -0.0787608 -0.0350033 0.0302079 -0.079321 -0.0356033 0.0304228 -0.0832464 -0.0356033 0.0169529 -0.0826584 -0.0350033 0.0168331 -0.083645 -0.0350033 -0.0109164 -0.0651459 -0.0356033 0.0545285 -0.0552827 -0.0356033 0.0645068 -0.0641382 -0.0350033 0.054791 -0.0411941 -0.0350033 0.0736116 -0.0552655 -0.0350033 0.0637294 -0.0578771 -0.0350033 0.0613676 -0.0364818 -0.0350033 0.0760571 -0.0439117 -0.0356033 0.0727255 -0.0374069 -0.0350033 0.0756064 -0.0242273 -0.0350033 0.0807994 -0.031038 -0.0350033 0.078436 -0.0179195 -0.0356033 0.0830417 -0.017793 -0.0350033 0.0824552 -0.00397904 -0.0350033 0.0842585 0.0100141 -0.0356033 0.0843593 -0.0368376 -0.0295033 -0.0458961 -0.0367125 -0.0293033 -0.0457401 -0.0514231 -0.0293033 -0.0282107 -0.0515984 -0.0295033 -0.0283069 -0.0559392 -0.0293033 -0.0176374 -0.0583057 -0.0293033 -0.00638618 -0.0585045 -0.0295033 -0.00640796 -0.0520294 -0.0293033 0.0270808 -0.045903 -0.0295033 0.0368352 -0.045747 -0.0293033 0.03671 -0.0378353 -0.0295033 0.0450817 -0.0176443 -0.0293033 0.0559367 -0.0177044 -0.0295033 0.0561274 -0.00639304 -0.0293033 0.0583032 0.00510368 -0.0293033 0.0584293 -0.0555244 -0.0350033 0.0600585 -0.0547942 -0.0350033 0.0596154 -0.0544597 -0.0398033 0.0591011 -0.0543833 -0.0350033 0.0588666 -0.0543389 -0.0398033 0.0583768 -0.0544019 -0.0398033 0.0580127 -0.0544019 -0.0350033 0.0580127 -0.0548449 -0.0350033 0.0572825 -0.0550353 -0.0398033 0.0571258 -0.0555937 -0.0350033 0.0568717 -0.0557146 -0.0398033 0.0568468 -0.018058 -0.0398033 0.0797723 -0.018058 -0.0350033 0.0797723 -0.0176471 -0.0398033 0.0790235 -0.0176657 -0.0398033 0.0781696 -0.0181088 -0.0350033 0.0774394 -0.0188576 -0.0398033 0.0770285 -0.0197115 -0.0398033 0.0770471 -0.0573736 -0.0398033 -0.0547522 -0.057285 -0.0398033 -0.0548381 -0.057285 -0.0350033 -0.0548381 -0.0568741 -0.0350033 -0.0555869 -0.0569505 -0.0398033 -0.0553524 -0.0568927 -0.0350033 -0.0564408 -0.0568927 -0.0398033 -0.0564408 -0.0573358 -0.0398033 -0.057171 -0.0573358 -0.0350033 -0.057171 -0.0580846 -0.0350033 -0.0575818 -0.0580846 -0.0398033 -0.0575818 -0.0589385 -0.0350033 -0.0575632 -0.0775305 -0.0398033 -0.018016 -0.0781721 -0.0350033 -0.0176589 -0.0774419 -0.0350033 -0.0181019 -0.0774419 -0.0398033 -0.0181019 -0.0771074 -0.0398033 -0.0186162 -0.077031 -0.0350033 -0.0188507 -0.0769866 -0.0398033 -0.0193405 -0.0770496 -0.0398033 -0.0197046 -0.0770496 -0.0350033 -0.0197046 -0.0774926 -0.0350033 -0.0204348 -0.0782414 -0.0398033 -0.0208457 -0.0782414 -0.0350033 -0.0208457 -0.0783623 -0.0398033 -0.0208705 -0.0790953 -0.0350033 -0.0208271 -0.0772604 -0.0398033 0.024234 -0.0765302 -0.0350033 0.023791 -0.0765302 -0.0398033 0.023791 -0.0761957 -0.0398033 0.0232767 -0.0760749 -0.0398033 0.0225524 -0.0762803 -0.0398033 0.0218474 -0.0761379 -0.0350033 0.0221883 -0.0765809 -0.0350033 0.0214581 -0.0765809 -0.0398033 0.0214581 0.0564383 -0.0398033 -0.0568859 0.0564383 -0.0350033 -0.0568859 0.0570799 -0.0398033 -0.057243 0.0570799 -0.0350033 -0.057243 0.057503 -0.0398033 -0.0578432 0.0576238 -0.0398033 -0.0585675 0.0574183 -0.0398033 -0.0592725 0.0574183 -0.0350033 -0.0592725 0.0562481 -0.0398033 -0.0600975 0.0203437 -0.0398033 -0.0773999 0.0203437 -0.0350033 -0.0773999 0.0207668 -0.0398033 -0.0780001 0.0208876 -0.0398033 -0.0787244 0.0206822 -0.0350033 -0.0794294 0.0201912 -0.0350033 -0.0799754 0.0195119 -0.0398033 -0.0802544 0.0195119 -0.0350033 -0.0802544 0.0589291 -0.0398033 0.0575676 0.0589291 -0.0350033 0.0575676 0.0595707 -0.0350033 0.0572105 0.0599938 -0.0398033 0.0566103 0.0599938 -0.0350033 0.0566103 0.0601146 -0.0398033 0.055886 0.0601146 -0.0350033 0.055886 0.0599092 -0.0350033 0.055181 0.0594182 -0.0398033 0.0546349 0.0587389 -0.0398033 0.054356 0.0587389 -0.0350033 0.054356 0.0580059 -0.0350033 0.0543994 0.0797276 -0.0350033 0.0204743 0.0801507 -0.0350033 0.0198741 0.0802715 -0.0350033 0.0191498 0.080066 -0.0350033 0.0184448 0.0795751 -0.0398033 0.0178988 0.0788958 -0.0350033 0.0176198 0.0781743 -0.0350033 -0.0210614 0.0789045 -0.0398033 -0.0215045 0.0792968 -0.0398033 -0.0231071 0.0793154 -0.0350033 -0.0222532 0.0788537 -0.0398033 -0.0238374 0.0788537 -0.0350033 -0.0238374 0.0781049 -0.0350033 -0.0242482 0.0781049 -0.0398033 -0.0242482 0.00999047 -0.0413033 0.0841607 -0.0179195 -0.0411033 0.0830417 -0.0178773 -0.0413033 0.0828462 -0.0312692 -0.0413033 0.0787746 -0.0438083 -0.0413033 0.0725543 -0.0439117 -0.0411033 0.0727255 -0.0552827 -0.0411033 0.0645068 -0.0649926 -0.0413033 0.0544001 -0.0730598 -0.0413033 0.0429616 -0.0791343 -0.0413033 0.0303512 -0.0847012 -0.0413033 0.00301344 -0.0840416 -0.0413033 -0.0109682 -0.0812812 -0.0411033 -0.0247088 -0.0761054 -0.0411033 -0.0377494 -0.0759262 -0.0413033 -0.0376606 -0.0688537 -0.0411033 -0.0497603 -0.0686916 -0.0413033 -0.0496432 -0.0489654 -0.0411033 -0.0694193 -0.0368713 -0.0411033 -0.0765312 0.0766482 -0.0401033 -0.0230826 0.076564 -0.0401033 -0.0225775 0.0785439 -0.0401033 -0.0218497 0.0770497 -0.0401033 -0.021705 0.0779862 -0.0401033 -0.0237632 0.0775196 -0.0401033 0.0195693 0.0789463 -0.0401033 0.0203521 0.0778286 -0.0401033 0.0200786 0.0777932 -0.0401033 0.0184516 0.0775067 -0.0401033 0.0189738 0.0596162 -0.0401033 0.0559155 0.0576717 -0.0401033 0.0568147 0.0581939 -0.0401033 0.0571012 0.0587894 -0.0401033 0.0570883 0.0573627 -0.0401033 0.0563055 0.0573498 -0.0401033 0.0557099 0.0581456 -0.0401033 0.0548788 0.0586568 -0.0401033 0.0548485 0.0591305 -0.0401033 0.055043 0.0184093 -0.0401033 -0.0794226 0.0199035 -0.0401033 -0.0795674 0.0562986 -0.0401033 -0.0573652 0.0567461 -0.0401033 -0.0576143 0.0570411 -0.0401033 -0.0580329 0.0551455 -0.0401033 -0.0592657 0.0571254 -0.0401033 -0.058538 0.0566397 -0.0401033 -0.0594105 0.0561659 -0.0401033 -0.059605 0.0551809 -0.0401033 -0.0576388 0.0548719 -0.0401033 -0.058148 -0.0774001 -0.0401033 0.0237547 -0.0766575 -0.0401033 0.023087 -0.0775327 -0.0401033 0.0215149 -0.0780439 -0.0401033 0.0215451 -0.0794295 -0.0401033 -0.0184118 -0.0794649 -0.0401033 -0.0200388 -0.0775692 -0.0401033 -0.0188059 -0.0582875 -0.0401033 -0.0571142 -0.0581549 -0.0401033 -0.0548744 -0.0587988 -0.0401033 -0.0570839 -0.0592726 -0.0401033 -0.0551479 -0.0181451 -0.0401033 0.0783093 -0.0199128 -0.0401033 0.0795717 -0.0200192 -0.0401033 0.0777756 -0.0184186 -0.0401033 0.079427 -0.0195718 -0.0401033 0.0775265 -0.0549806 -0.0401033 0.0579147 -0.0570908 -0.0401033 0.0587963 -0.0567818 -0.0401033 0.0593055 -0.0556641 -0.0401033 0.0595791 -0.0563079 -0.0401033 0.0573696 -0.0557967 -0.0401033 0.0573393 0.0100141 -0.0631033 0.0843593 -0.00400731 -0.0631033 0.0848578 -0.0179195 -0.0620033 0.0830417 -0.031343 -0.0620033 0.0789605 -0.0439117 -0.0631033 0.0727255 -0.0552827 -0.0631033 0.0645068 -0.0552827 -0.0620033 0.0645068 -0.0651459 -0.0620033 0.0545285 -0.0732322 -0.0620033 0.043063 -0.079321 -0.0620033 0.0304228 -0.079321 -0.0631033 0.0304228 -0.0832464 -0.0631033 0.0169529 -0.08424 -0.0620033 -0.0109941 -0.0761054 -0.0620033 -0.0377494 -0.0688537 -0.0631033 -0.0497603 -0.0688537 -0.0620033 -0.0497603 -0.0597241 -0.0620033 -0.0604138 -0.0368713 -0.0620033 -0.0765312 -0.0368713 -0.0631033 -0.0765312 0.0237621 -0.0671033 0.0815598 0.0100141 -0.0645033 0.0843593 0.0100141 -0.0671033 0.0843593 -0.0179195 -0.0671033 0.0830417 -0.031343 -0.0645033 0.0789605 -0.0439117 -0.0645033 0.0727255 -0.0439117 -0.0671033 0.0727255 -0.0552827 -0.0645033 0.0645068 -0.0651459 -0.0645033 0.0545285 -0.0732322 -0.0671033 0.043063 -0.0732322 -0.0645033 0.043063 -0.079321 -0.0645033 0.0304228 -0.0832464 -0.0645033 0.0169529 -0.0832464 -0.0671033 0.0169529 -0.084901 -0.0645033 0.00302054 -0.084901 -0.0671033 0.00302054 -0.08424 -0.0645033 -0.0109941 -0.0688537 -0.0645033 -0.0497603 -0.0489654 -0.0671033 -0.0694193 -0.0368713 -0.0645033 -0.0765312 0.0100141 -0.0595033 0.0843593 -0.00400731 -0.0606033 0.0848578 -0.0179195 -0.0595033 0.0830417 -0.0179195 -0.0606033 0.0830417 -0.031343 -0.0606033 0.0789605 -0.0439117 -0.0606033 0.0727255 -0.0552827 -0.0595033 0.0645068 -0.0651459 -0.0606033 0.0545285 -0.0732322 -0.0595033 0.043063 -0.079321 -0.0595033 0.0304228 -0.079321 -0.0606033 0.0304228 -0.0832464 -0.0595033 0.0169529 -0.0832464 -0.0606033 0.0169529 -0.084901 -0.0606033 0.00302054 -0.084901 -0.0595033 0.00302054 -0.08424 -0.0606033 -0.0109941 -0.0812812 -0.0606033 -0.0247088 -0.0812812 -0.0595033 -0.0247088 -0.0761054 -0.0595033 -0.0377494 -0.0688537 -0.0595033 -0.0497603 -0.0597241 -0.0595033 -0.0604138 -0.0597241 -0.0606033 -0.0604138 -0.0489654 -0.0595033 -0.0694193 -0.0368713 -0.0606033 -0.0765312 -0.0368713 -0.0595033 -0.0765312 -0.0237715 -0.0606033 -0.0815554 -0.0179195 -0.0570033 0.0830417 -0.031343 -0.0570033 0.0789605 -0.0439117 -0.0581033 0.0727255 -0.0439117 -0.0570033 0.0727255 -0.0732322 -0.0570033 0.043063 -0.0832464 -0.0570033 0.0169529 -0.084901 -0.0570033 0.00302054 -0.084901 -0.0581033 0.00302054 -0.0761054 -0.0570033 -0.0377494 -0.0761054 -0.0581033 -0.0377494 -0.0688537 -0.0581033 -0.0497603 -0.0597241 -0.0570033 -0.0604138 -0.0597241 -0.0581033 -0.0604138 -0.0489654 -0.0581033 -0.0694193 -0.0368713 -0.0570033 -0.0765312 -0.0368713 -0.0581033 -0.0765312 -0.0237715 -0.0570033 -0.0815554 0.0100141 -0.0556033 0.0843593 -0.00400731 -0.0545033 0.0848578 -0.0179195 -0.0545033 0.0830417 -0.0179195 -0.0556033 0.0830417 -0.031343 -0.0545033 0.0789605 -0.031343 -0.0556033 0.0789605 -0.0439117 -0.0545033 0.0727255 -0.0552827 -0.0545033 0.0645068 -0.0732322 -0.0545033 0.043063 -0.0651459 -0.0556033 0.0545285 -0.079321 -0.0545033 0.0304228 -0.084901 -0.0545033 0.00302054 -0.084901 -0.0556033 0.00302054 -0.08424 -0.0545033 -0.0109941 -0.08424 -0.0556033 -0.0109941 -0.0812812 -0.0545033 -0.0247088 -0.0761054 -0.0545033 -0.0377494 -0.0812812 -0.0556033 -0.0247088 -0.0688537 -0.0545033 -0.0497603 -0.0761054 -0.0556033 -0.0377494 -0.0489654 -0.0556033 -0.0694193 -0.0489654 -0.0545033 -0.0694193 -0.00400731 -0.0520033 0.0848578 -0.031343 -0.0531033 0.0789605 -0.0439117 -0.0520033 0.0727255 -0.0552827 -0.0531033 0.0645068 -0.079321 -0.0520033 0.0304228 -0.0732322 -0.0531033 0.043063 -0.08424 -0.0520033 -0.0109941 -0.0812812 -0.0531033 -0.0247088 -0.0761054 -0.0520033 -0.0377494 -0.0688537 -0.0531033 -0.0497603 -0.0597241 -0.0520033 -0.0604138 -0.0489654 -0.0531033 -0.0694193 -0.0368713 -0.0531033 -0.0765312 0.0237621 -0.0495033 0.0815598 0.0100141 -0.0506033 0.0843593 -0.031343 -0.0495033 0.0789605 -0.0439117 -0.0495033 0.0727255 -0.031343 -0.0506033 0.0789605 -0.0439117 -0.0506033 0.0727255 -0.0552827 -0.0506033 0.0645068 -0.0651459 -0.0506033 0.0545285 -0.0651459 -0.0495033 0.0545285 -0.0732322 -0.0495033 0.043063 -0.0732322 -0.0506033 0.043063 -0.079321 -0.0495033 0.0304228 -0.079321 -0.0506033 0.0304228 -0.08424 -0.0495033 -0.0109941 -0.0761054 -0.0506033 -0.0377494 -0.0688537 -0.0506033 -0.0497603 -0.0597241 -0.0495033 -0.0604138 -0.0489654 -0.0495033 -0.0694193 -0.0368713 -0.0495033 -0.0765312 -0.0237715 -0.0495033 -0.0815554 -0.0368713 -0.0506033 -0.0765312 0.0237621 -0.0481033 0.0815598 -0.00400731 -0.0470033 0.0848578 -0.00400731 -0.0481033 0.0848578 -0.0439117 -0.0470033 0.0727255 -0.0651459 -0.0470033 0.0545285 -0.0732322 -0.0470033 0.043063 -0.079321 -0.0470033 0.0304228 -0.0832464 -0.0470033 0.0169529 -0.0832464 -0.0481033 0.0169529 -0.084901 -0.0470033 0.00302054 -0.0812812 -0.0470033 -0.0247088 -0.0761054 -0.0481033 -0.0377494 -0.0688537 -0.0470033 -0.0497603 -0.0688537 -0.0481033 -0.0497603 -0.0489654 -0.0470033 -0.0694193 -0.0489654 -0.0481033 -0.0694193 -0.0179195 -0.0456033 0.0830417 -0.031343 -0.0456033 0.0789605 -0.031343 -0.0445033 0.0789605 -0.0439117 -0.0445033 0.0727255 -0.0651459 -0.0456033 0.0545285 -0.079321 -0.0456033 0.0304228 -0.0832464 -0.0445033 0.0169529 -0.084901 -0.0445033 0.00302054 -0.08424 -0.0445033 -0.0109941 -0.0812812 -0.0445033 -0.0247088 -0.0812812 -0.0456033 -0.0247088 -0.0761054 -0.0445033 -0.0377494 -0.0688537 -0.0445033 -0.0497603 -0.0489654 -0.0445033 -0.0694193 -0.0368713 -0.0445033 -0.0765312 0.0100141 -0.0415033 0.0843593 -0.0179195 -0.0415033 0.0830417 -0.031343 -0.0415033 0.0789605 -0.0439117 -0.0415033 0.0727255 -0.0439117 -0.0431033 0.0727255 -0.0552827 -0.0415033 0.0645068 -0.0552827 -0.0431033 0.0645068 -0.0651459 -0.0415033 0.0545285 -0.0732322 -0.0431033 0.043063 -0.079321 -0.0415033 0.0304228 -0.0832464 -0.0431033 0.0169529 -0.084901 -0.0431033 0.00302054 -0.0812812 -0.0415033 -0.0247088 -0.0688537 -0.0415033 -0.0497603 -0.0688537 -0.0431033 -0.0497603 -0.0597241 -0.0415033 -0.0604138 -0.0597241 -0.0431033 -0.0604138 -0.0368713 -0.0431033 -0.0765312 0.0502102 -0.0676033 0.0198634 0.0502102 -0.0791033 0.0198634 0.0457826 -0.0676033 0.0286296 0.0457826 -0.0791033 0.0286296 0.0398406 -0.0676033 0.0364488 0.0325806 -0.0676033 0.0430626 0.0325806 -0.0791033 0.0430626 0.0151031 -0.0676033 0.0518458 -0.0528348 -0.0791033 -0.0111771 -0.0496434 -0.0676033 -0.021258 -0.0496434 -0.0791033 -0.021258 -0.0445487 -0.0791033 -0.0305236 -0.0377461 -0.0676033 -0.0386189 -0.0294963 -0.0676033 -0.0452332 -0.0201157 -0.0676033 -0.0501131 -0.00996404 -0.0676033 -0.0530714 0.0110811 -0.0676033 -0.0528476 0.0211676 -0.0676033 -0.0496741 0.0211676 -0.0791033 -0.0496741 0.0304423 -0.0676033 -0.0445958 0.0451785 -0.0676033 -0.0295695 -0.0513673 -0.0806033 -0.0108666 0.0488153 -0.0806033 0.0193117 0.0146835 -0.0806033 0.0504057 0.0316755 -0.0806033 0.0418665 0.0235693 -0.0806033 0.0469119 -0.0366977 -0.0806033 -0.037546 0.00531179 -0.0806033 0.0522323 -0.00423574 -0.0806033 0.0523314 0.0522322 -0.0806033 -0.00124576 -0.0308089 -0.0806033 0.0425151 -0.0379992 -0.0806033 0.036233 -0.0439327 -0.0806033 0.0287524 0.0447251 -0.0806033 -0.027007 -0.0447344 -0.0806033 0.0270114 -0.0522416 -0.0806033 0.00125015 0.000553581 -0.0806033 -0.0524948 0.0107731 -0.0806033 -0.0513796 0.0205795 -0.0806033 -0.0482942 0.0295965 -0.0806033 -0.043357 0.0374786 -0.0806033 -0.0367573 -0.0470305 -0.0770033 0.0186016 -0.0406823 -0.0687033 0.00696063 -0.0369193 -0.0729533 0.0198735 -0.0458974 -0.0727533 0.0224898 0.0507841 -0.0727533 -0.00568428 0.0470212 -0.0687033 -0.0185972 0.041633 -0.0687033 -0.00723601 -0.0642446 -0.0676033 0.0548203 -0.0681062 -0.0676033 0.049942 0.000739272 -0.0676033 -0.0844445 0.0311903 -0.0676033 -0.078475 -0.0443038 -0.0676033 0.0382116 0.0526887 -0.0676033 -0.00504073 0.0452179 -0.0676033 0.0642597 0.0497444 -0.0676033 0.0633008 0.0540377 -0.0676033 0.0616863 -0.0413297 -0.0676033 -0.071925 0.0632939 -0.0676033 -0.0497469 0.0647532 -0.0676033 -0.0542032 0.0659821 -0.0676033 -0.0505303 0.0646507 -0.0676033 -0.0450908 0.0660998 -0.0676033 -0.0451224 0.0673389 -0.0676033 -0.0458742 0.0680361 -0.0676033 -0.0471449 0.0672665 -0.0676033 -0.039966 0.0699862 -0.0676033 -0.0393004 0.0680046 -0.0676033 -0.0485939 0.0696634 -0.0676033 -0.0447504 0.0680969 -0.0676033 -0.0499376 0.0727919 -0.0676033 -0.0428051 0.0719979 -0.0676033 -0.0421541 0.0428985 -0.0676033 -0.0692735 0.0409579 -0.0676033 -0.0690303 0.0416551 -0.0676033 -0.0703009 0.0298636 -0.0676033 -0.0738998 0.034595 -0.0676033 -0.0760879 0.0375555 -0.0676033 -0.0756354 0.0333244 -0.0676033 -0.0767851 0.0318753 -0.0676033 -0.0767536 0.0252367 -0.0676033 -0.0767373 0.0300686 -0.0676033 -0.075129 0.0362157 -0.0676033 -0.0716323 0.0321981 -0.0676033 -0.0713035 0.0369991 -0.0676033 -0.0689441 0.0302122 -0.0676033 -0.0727035 0.0440264 -0.0676033 -0.0720607 0.0416236 -0.0676033 -0.07175 0.0408718 -0.0676033 -0.0729891 0.043644 -0.0676033 -0.072293 0.0625967 -0.0676033 -0.0484762 0.0633801 -0.0676033 -0.045788 0.0685972 -0.0676033 -0.0303017 0.0668513 -0.0676033 -0.0297929 0.0626282 -0.0676033 -0.0470272 0.0419578 -0.0676033 -0.0598303 0.0395749 -0.0676033 -0.0680072 0.054948 -0.0676033 -0.0641227 0.0471225 -0.0676033 -0.0613353 0.0457044 -0.0676033 -0.064649 0.0467931 -0.0676033 -0.0652551 0.0477161 -0.0676033 -0.0675027 0.0473675 -0.0676033 -0.0686991 0.0815918 -0.0676033 -0.00447881 0.0801428 -0.0676033 -0.00444728 0.0741371 -0.0676033 -0.011291 0.0781311 -0.0676033 -0.00159354 0.0781628 -0.0676033 0.00252347 0.0784797 -0.0676033 -0.000397188 0.084392 -0.0676033 -0.00299839 0.0836459 -0.0676033 -0.00109342 0.0844418 -0.0676033 0.00077057 0.0829487 -0.0676033 0.00017726 0.075744 -0.0676033 0.0373377 0.0737592 -0.0676033 0.0387767 0.0756481 -0.0676033 0.0375316 0.0693572 -0.0676033 0.0468642 0.0717475 -0.0676033 0.0416305 0.0728363 -0.0676033 0.0410244 0.0684392 -0.0676033 0.0494718 0.0700544 -0.0676033 0.0455935 0.0723083 -0.0676033 0.0436215 0.0700229 -0.0676033 0.0441445 0.069271 -0.0676033 0.0429054 0.0680004 -0.0676033 0.0422081 0.0665513 -0.0676033 0.0422397 0.0682444 -0.0676033 0.0382766 0.0598278 -0.0676033 0.0419646 0.0645396 -0.0676033 0.0450934 0.0699137 -0.0676033 0.0361026 0.0734106 -0.0676033 0.0375804 0.0733972 -0.0676033 0.0353853 0.0815591 -0.0676033 0.00792748 0.0836272 -0.0676033 0.0117288 0.0827121 -0.0676033 0.00321678 0.0817095 -0.0676033 0.000929092 0.0827271 -0.0676033 0.00119338 0.0789036 -0.0676033 0.00315721 0.0764169 -0.0676033 0.00303223 0.064432 -0.0676033 0.0172915 0.0721266 -0.0676033 0.0346881 0.0695967 -0.0676033 0.0157865 0.0774325 -0.0676033 0.0181063 0.0781627 -0.0676033 0.0176633 0.0793089 -0.0676033 0.0129562 0.0788958 -0.0676033 0.0176198 0.0795751 -0.0676033 0.0178988 0.0747286 -0.0676033 0.0299458 0.0782321 -0.0676033 0.0208501 0.079086 -0.0676033 0.0208315 0.0807935 -0.0676033 0.0245677 0.0758459 -0.0676033 0.0371303 0.0760854 -0.0676033 0.0346019 0.0767511 -0.0676033 0.0318822 0.0759993 -0.0676033 0.030643 -0.0497538 -0.0676033 -0.0632964 -0.0505056 -0.0676033 -0.0645355 -0.0484558 -0.0676033 -0.0691664 -0.0498399 -0.0676033 -0.0672552 -0.0447905 -0.0676033 -0.0690398 -0.0444419 -0.0676033 -0.0678434 -0.0453709 -0.0676033 -0.0666808 -0.042456 -0.0676033 -0.0664435 -0.0366543 -0.0676033 -0.0760807 -0.0462041 -0.0676033 -0.0676074 0.0498306 -0.0676033 0.0672596 0.0453616 -0.0676033 0.0666852 0.0461948 -0.0676033 0.0676118 0.0470247 -0.0676033 0.0626351 0.00995509 -0.0676033 0.0838628 -0.00796148 -0.0676033 0.0801169 0.00253999 -0.0676033 0.0836212 -0.00398375 -0.0676033 0.0843584 0.00369297 -0.0676033 0.0789105 0.00444481 -0.0676033 0.0801497 -0.00279529 -0.0676033 0.0794207 0.0024223 -0.0676033 0.0782133 0.000973254 -0.0676033 0.0782449 -0.000265887 -0.0676033 0.0789967 -0.00336961 -0.0676033 0.0828647 -0.000931563 -0.0676033 0.0817164 -0.00244666 -0.0676033 0.0806171 -0.00017973 -0.0676033 0.0829555 -0.0118228 -0.0676033 0.0836212 -0.00590744 -0.0676033 0.0835023 -0.00717811 -0.0676033 0.0828051 -0.0124499 -0.0676033 0.0810616 -0.000982588 -0.0676033 -0.0782405 -0.00222652 -0.0676033 -0.0781668 -0.0202945 -0.0676033 -0.0696237 0.000949869 -0.0676033 -0.0835416 0.000922229 -0.0676033 -0.081712 0.000170397 -0.0676033 -0.0829512 -0.0036381 -0.0676033 -0.0830107 -0.00435608 -0.0676033 -0.0819922 -0.00456106 -0.0676033 -0.0807631 -0.02237 -0.0676033 -0.0767459 -0.00421243 -0.0676033 -0.0795667 -0.0801194 -0.0676033 -0.00795462 -0.0780654 -0.0676033 -0.00456922 -0.0837442 -0.0676033 -0.0109294 -0.0834733 -0.0676033 -0.00445153 -0.0827214 -0.0676033 -0.00321239 -0.0828077 -0.0676033 -0.000318595 -0.078913 -0.0676033 0.00369984 -0.0782158 -0.0676033 0.00242916 -0.0787626 -0.0676033 -0.00329855 -0.0782473 -0.0676033 0.000980117 -0.0800017 -0.0676033 -0.00254671 -0.0789992 -0.0676033 -0.000259024 -0.0825488 -0.0676033 0.004052 -0.0837306 -0.0676033 0.00192903 -0.0842729 -0.0676033 -0.0055353 -0.0731708 -0.0676033 0.0316362 -0.0691451 -0.0676033 0.0454507 -0.0666221 -0.0676033 0.0430565 -0.0664171 -0.0676033 0.0418274 -0.0687516 -0.0676033 0.0392311 -0.041633 -0.0676033 0.0717544 -0.0436533 -0.0676033 0.0722974 -0.0408811 -0.0676033 0.0729935 -0.0416645 -0.0676033 0.0703053 -0.044147 -0.0676033 0.0700297 -0.0438383 -0.0676033 0.0721854 -0.0453909 -0.0676033 0.0701034 -0.0364983 -0.0676033 0.0696091 -0.0363546 -0.0676033 0.0720346 -0.0375648 -0.0676033 0.0756397 -0.0765809 -0.0676033 0.0214581 -0.0773297 -0.0676033 0.0210472 -0.0779934 -0.0676033 0.0242774 -0.0757641 -0.0676033 0.0323919 -0.081304 -0.0676033 0.0133812 -0.0788252 -0.0676033 0.021423 -0.0844013 -0.0676033 0.00300278 -0.0791637 -0.0676033 0.0234525 -0.0788542 -0.0676033 0.0302438 -0.0422421 -0.0676033 0.0665582 -0.0422106 -0.0676033 0.0680072 -0.0397281 -0.0676033 0.0682828 -0.0409673 -0.0676033 0.0690347 -0.0457137 -0.0676033 0.0646534 -0.0477254 -0.0676033 0.0675071 -0.0473768 -0.0676033 0.0687034 -0.0465436 -0.0676033 0.0696301 -0.0468434 -0.0676033 0.0702727 -0.0747379 -0.0676033 -0.0299414 -0.0732889 -0.0676033 -0.029973 -0.0722001 -0.0676033 -0.0305791 -0.0675402 -0.0676033 -0.0279213 -0.0786164 -0.0676033 -0.0308522 -0.0760948 -0.0676033 -0.0345975 -0.0756574 -0.0676033 -0.0375272 -0.0736617 -0.0676033 -0.0381545 -0.0689573 -0.0676033 -0.042635 -0.068527 -0.0676033 -0.0402998 -0.0717568 -0.0676033 -0.0416261 -0.0701391 -0.0676033 -0.0447579 -0.0693602 -0.0676033 -0.0412264 -0.0748556 -0.0676033 -0.0353493 -0.0699231 -0.0676033 -0.0360982 -0.0662689 -0.0676033 -0.0371631 -0.0320023 -0.0676033 0.0713501 -0.0345402 -0.0676033 0.0719877 -0.0328608 -0.0676033 0.0777986 -0.0306455 -0.0676033 0.0760061 0.0535609 -0.0676033 0.0204595 0.0384845 -0.0676033 0.0452614 0.0242429 -0.0676033 0.0482521 0.00546369 -0.0676033 0.0537246 0.0151647 -0.0676033 0.0520571 -0.034195 -0.0676033 0.0460326 -0.031689 -0.0676033 0.0437298 -0.0528348 -0.0676033 -0.0111771 -0.0445487 -0.0676033 -0.0305236 -0.0484179 -0.0676033 -0.0423651 0.0341857 -0.0676033 -0.0460282 0.0385495 -0.0676033 -0.0378075 -0.0653215 -0.0676033 -0.0429871 -0.0598371 -0.0676033 -0.0419603 -0.0646558 -0.0676033 -0.0457068 -0.0666783 -0.0676033 -0.0476432 -0.0684744 -0.0676033 -0.0494316 -0.0681274 -0.0676033 -0.0476117 -0.0692162 -0.0676033 -0.0470055 0.0459879 -0.0676033 0.0708294 0.0441137 -0.0676033 0.0645783 0.0439224 -0.0676033 0.0671872 0.0207939 -0.0676033 0.071374 0.0393959 -0.0676033 0.0681461 0.0395396 -0.0676033 0.0705716 0.0415255 -0.0676033 0.0719716 0.0596086 -0.0676033 0.0547917 0.0596593 -0.0676033 0.0571246 0.0625099 -0.0676033 0.0511686 0.0668741 -0.0676033 0.0476897 0.0593632 -0.0676033 0.0600626 0.0588598 -0.0676033 0.0543808 0.0518758 -0.0676033 0.0542675 0.0570258 -0.0676033 0.0567861 0.0504963 -0.0676033 0.0645399 0.0573643 -0.0676033 0.0547566 0.0569412 -0.0676033 0.0553568 0.0826864 -0.0676033 0.0171484 0.0810547 -0.0676033 0.0124475 0.080066 -0.0676033 0.0184448 0.0836144 -0.0676033 -0.00254246 0.0828625 -0.0676033 -0.0037816 0.0788537 -0.0676033 -0.0238374 0.0792968 -0.0676033 -0.0231071 0.0827471 -0.0676033 -0.0168487 0.0793154 -0.0676033 -0.0222532 0.0731615 -0.0676033 -0.0316318 0.071075 -0.0676033 -0.0399065 0.077251 -0.0676033 -0.0242296 0.0760655 -0.0676033 -0.022548 0.0774413 -0.0676033 -0.021018 0.0787014 -0.0676033 -0.0126211 0.0781743 -0.0676033 -0.0210614 0.0642353 -0.0676033 -0.0548159 0.0605303 -0.0676033 -0.0588817 0.0616795 -0.0676033 -0.0540402 0.0578047 -0.0676033 -0.0615598 0.0599336 -0.0676033 -0.0535314 0.0571177 -0.0676033 -0.0596618 0.0563689 -0.0676033 -0.0600727 0.0548734 -0.0676033 -0.0596969 0.0311492 -0.0676033 -0.0784914 0.0208246 -0.0676033 -0.0790885 0.0209245 -0.0676033 -0.0818133 0.0196328 -0.0676033 -0.0802295 0.0204323 -0.0676033 -0.0774858 0.0146025 -0.0676033 -0.0736384 0.0181373 -0.0676033 -0.0798538 0.0189691 -0.0676033 -0.0769993 0.0187789 -0.0676033 -0.080211 0.0178047 -0.0676033 -0.0825486 0.0129494 -0.0676033 -0.0793114 0.00792061 -0.0676033 -0.0815616 0.00370399 -0.0676033 -0.0843663 0.00361914 -0.0676033 -0.0784897 0.00477186 -0.0676033 -0.0780164 0.00302536 -0.0676033 -0.0764194 0.0060158 -0.0676033 -0.07809 0.00243733 -0.0676033 -0.0806127 0.00278596 -0.0676033 -0.0794163 -0.0573358 -0.0676033 -0.057171 -0.0593726 -0.0676033 -0.0600582 -0.0589385 -0.0676033 -0.0575632 -0.0596687 -0.0676033 -0.0571202 -0.0600795 -0.0676033 -0.0563714 -0.0600609 -0.0676033 -0.0555175 -0.0588691 -0.0676033 -0.0543764 -0.057285 -0.0676033 -0.0548381 -0.0782414 -0.0676033 -0.0208457 -0.0809625 -0.0676033 -0.0240317 -0.0818354 -0.0676033 -0.0208671 -0.0793182 -0.0676033 -0.0129518 -0.0781721 -0.0676033 -0.0176589 -0.0736452 -0.0676033 -0.014605 -0.0774419 -0.0676033 -0.0181019 -0.0836365 -0.0676033 -0.0117244 -0.0786727 -0.0676033 0.0239985 -0.0728012 -0.0676033 0.0428095 -0.062606 -0.0676033 0.0484806 -0.0628349 -0.0676033 0.0436118 -0.0673483 -0.0676033 0.0458786 -0.0680139 -0.0676033 0.0485983 -0.0659914 -0.0676033 0.0505347 -0.0633032 -0.0676033 0.0497513 -0.0475205 -0.0676033 0.0662779 -0.05427 -0.0676033 0.0518826 -0.0497349 -0.0676033 0.0682569 -0.0555937 -0.0676033 0.0568717 -0.059943 -0.0676033 0.0535358 -0.0564476 -0.0676033 0.0568902 -0.0555244 -0.0676033 0.0600585 -0.0547942 -0.0676033 0.0596154 -0.0576331 -0.0676033 0.0585719 -0.0203909 -0.0676033 0.0798231 -0.0204417 -0.0676033 0.0774902 -0.025246 -0.0676033 0.0767417 -0.0311586 -0.0676033 0.0784957 -0.0208339 -0.0676033 0.0790929 -0.0178141 -0.0676033 0.082553 -0.0129587 -0.0676033 0.0793158 -0.0181466 -0.0676033 0.0798582 -0.0177235 -0.0676033 0.079258 -0.0178082 -0.0676033 0.0778287 -0.0182991 -0.0676033 0.0772826 -0.0189784 -0.0676033 0.0770037 -0.0390847 -0.0676033 0.0372681 -0.045066 -0.0676033 0.0492005 -0.0483296 -0.0676033 0.0243971 -0.047958 -0.0676033 0.0392765 -0.0571619 -0.0676033 0.0419586 -0.0667657 -0.0676033 0.040631 -0.0675989 -0.0676033 0.0397044 -0.0538695 -0.0676033 0.00538649 -0.0575236 -0.0676033 0.00645135 -0.0519837 -0.0676033 0.025462 -0.0611877 -0.0676033 0.0281441 -0.0668606 -0.0676033 0.0297973 -0.0787107 -0.0676033 0.0126255 -0.0607871 -0.0676033 -0.018352 -0.0644413 -0.0676033 -0.0172872 -0.0667276 -0.0676033 0.00913349 -0.0724006 -0.0676033 0.0107867 -0.0232454 -0.0676033 0.0487451 -0.0359301 -0.0676033 0.0669467 -0.0414119 -0.0676033 0.0481356 -0.0395843 -0.0676033 0.0680116 -0.042994 -0.0676033 0.065319 -0.0535703 -0.0676033 -0.0204551 -0.0566692 -0.0676033 -0.0310892 -0.0767441 -0.0676033 -0.0252392 -0.0774926 -0.0676033 -0.0204348 -0.046035 -0.0676033 -0.0341881 -0.0638861 -0.0676033 -0.0289862 0.0436049 -0.0676033 0.0628325 0.0202851 -0.0676033 0.0696281 -0.00602513 -0.0676033 0.0780944 0.0568204 -0.0676033 0.0560811 0.053529 -0.0676033 0.0599405 0.018632 -0.0676033 0.0639551 -0.0176027 -0.0676033 0.0785337 -0.0146119 -0.0676033 0.0736428 -0.0518851 -0.0676033 -0.0542631 -0.0535383 -0.0676033 -0.0599361 0.0419518 -0.0676033 0.0571595 0.0392696 -0.0676033 0.0479555 0.0159498 -0.0676033 0.0547512 -0.0279282 -0.0676033 0.0675377 -0.0299798 -0.0676033 0.0732864 -0.0307317 -0.0676033 0.0720473 0.0491936 -0.0676033 0.0450636 0.0484086 -0.0676033 0.0423695 -0.017294 -0.0676033 0.0644388 -0.0180791 -0.0676033 0.0617447 -0.035145 -0.0676033 0.0696408 -0.0287132 -0.0676033 0.0648436 0.0180698 -0.0676033 -0.0617403 0.00814576 -0.0676033 -0.0588484 0.00736067 -0.0676033 -0.0615425 -0.0151741 -0.0676033 -0.0520527 -0.0159591 -0.0676033 -0.0547468 -0.049203 -0.0676033 -0.0450592 -0.059052 -0.0676033 -0.0392662 -0.067054 -0.0676033 -0.0398572 -0.0683833 -0.0676033 -0.0378743 -0.0681784 -0.0676033 -0.0391035 0.0279188 -0.0676033 -0.0675333 0.0172847 -0.0676033 -0.0644344 0.00467854 -0.0676033 -0.0707464 -0.0186413 -0.0676033 -0.0639507 -0.0625193 -0.0676033 -0.0511642 0.0590427 -0.0676033 0.0392706 0.0310868 -0.0676033 -0.0566623 0.0204526 -0.0676033 -0.0535634 0.0287039 -0.0676033 -0.0648393 0.000569531 -0.0676033 -0.0539948 0.0543295 -0.0676033 -0.0583724 0.0502214 -0.0676033 -0.0507012 0.0783293 -0.0676033 0.0066012 0.0667047 -0.0676033 0.00586247 0.0529769 -0.0676033 0.0104403 0.0571391 -0.0676033 -0.0269627 0.0450567 -0.0676033 -0.0491961 0.0723912 -0.0676033 -0.0107823 0.062679 -0.0676033 -0.00795202 0.06154 -0.0676033 0.00736754 0.0539912 -0.0676033 0.000671999 0.0519744 -0.0676033 -0.0254576 0.0575143 -0.0676033 -0.00644696 0.0485075 -0.0416033 0.0677234 0.0502364 -0.0673033 0.0659176 0.0496139 -0.0416033 0.0670522 0.0502364 -0.0416033 0.0659176 0.0502082 -0.0673033 0.0646238 0.049537 -0.0673033 0.0635175 0.0484024 -0.0673033 0.062895 0.0484024 -0.0416033 0.062895 0.0502082 -0.0416033 0.0646238 0.0504963 -0.0413033 0.0645399 0.049537 -0.0416033 0.0635175 0.0497444 -0.0413033 0.0633008 0.0691405 -0.0673033 0.0466567 0.0691405 -0.0416033 0.0466567 0.0697348 -0.0673033 0.0442284 0.0697348 -0.0416033 0.0442284 0.0680341 -0.0416033 0.047328 0.069763 -0.0416033 0.0455222 0.0690636 -0.0416033 0.043122 0.067929 -0.0416033 0.0424995 0.0666352 -0.0416033 0.0425277 0.0665513 -0.0413033 0.0422397 0.0747624 -0.0673033 0.0350657 0.0758687 -0.0673033 0.0343944 0.0758687 -0.0416033 0.0343944 0.0764912 -0.0416033 0.0332599 0.0764631 -0.0416033 0.0319661 0.0757918 -0.0673033 0.0308597 0.0757918 -0.0416033 0.0308597 0.0733635 -0.0416033 0.0302654 0.0748463 -0.0413033 0.0353537 0.0767826 -0.0413033 0.0333312 0.0747286 -0.0413033 0.0299458 0.0746573 -0.0416033 0.0302372 0.0825816 -0.0673033 0.00696818 0.0825816 -0.0416033 0.00696818 0.0831759 -0.0673033 0.00453986 0.0825046 -0.0673033 0.00343348 0.0813701 -0.0673033 0.00281097 0.0813701 -0.0416033 0.00281097 0.0827983 -0.0413033 0.00717564 0.0832041 -0.0416033 0.00583364 0.0834955 -0.0413033 0.00590497 0.0831759 -0.0416033 0.00453986 0.0825046 -0.0416033 0.00343348 0.0800763 -0.0416033 0.00283913 0.0484737 -0.0676033 0.0626036 0.0505278 -0.0676033 0.065989 0.0496139 -0.0673033 0.0670522 0.067929 -0.0673033 0.0424995 0.0690636 -0.0673033 0.043122 0.069763 -0.0673033 0.0455222 0.0680341 -0.0673033 0.047328 0.0746573 -0.0673033 0.0302372 0.0732796 -0.0676033 0.0299774 0.0764631 -0.0673033 0.0319661 0.0764912 -0.0673033 0.0332599 0.0767826 -0.0676033 0.0333312 0.0799924 -0.0676033 0.00255111 0.0814414 -0.0676033 0.00251957 0.0832041 -0.0673033 0.00583364 0.0834639 -0.0676033 0.00445592 0.0834955 -0.0676033 0.00590497 0.0827983 -0.0676033 0.00717564 -0.0197115 -0.0676033 0.0770471 -0.0182991 -0.0666033 0.0772826 -0.0178082 -0.0666033 0.0778287 -0.0176027 -0.0666033 0.0785337 -0.0177235 -0.0666033 0.079258 -0.0555937 -0.0666033 0.0568717 -0.0548449 -0.0676033 0.0572825 -0.0544019 -0.0676033 0.0580127 -0.0543833 -0.0666033 0.0588666 -0.0543833 -0.0676033 0.0588666 -0.0555244 -0.0666033 0.0600585 -0.0781836 -0.0676033 0.0210658 -0.0773297 -0.0666033 0.0210472 -0.0761379 -0.0666033 0.0221883 -0.0761379 -0.0676033 0.0221883 -0.0761193 -0.0676033 0.0230422 -0.0772604 -0.0666033 0.024234 -0.0765302 -0.0676033 0.023791 -0.0790953 -0.0676033 -0.0208271 -0.0782414 -0.0666033 -0.0208457 -0.0774926 -0.0666033 -0.0204348 -0.0770496 -0.0666033 -0.0197046 -0.0770496 -0.0676033 -0.0197046 -0.077031 -0.0666033 -0.0188507 -0.077031 -0.0676033 -0.0188507 -0.0589385 -0.0666033 -0.0575632 -0.0580846 -0.0676033 -0.0575818 -0.0573358 -0.0666033 -0.057171 -0.0568927 -0.0676033 -0.0564408 -0.0568741 -0.0666033 -0.0555869 -0.0568741 -0.0676033 -0.0555869 -0.0580152 -0.0666033 -0.054395 -0.0580152 -0.0676033 -0.054395 0.0563689 -0.0666033 -0.0600727 0.0571177 -0.0666033 -0.0596618 0.0575608 -0.0676033 -0.0589316 0.0575793 -0.0666033 -0.0580777 0.0571685 -0.0666033 -0.0573289 0.0575793 -0.0676033 -0.0580777 0.0571685 -0.0676033 -0.0573289 0.0564383 -0.0666033 -0.0568859 0.0208246 -0.0666033 -0.0790885 0.0203816 -0.0676033 -0.0798187 0.0208432 -0.0666033 -0.0782346 0.0208432 -0.0676033 -0.0782346 0.0197021 -0.0666033 -0.0770427 0.0197021 -0.0676033 -0.0770427 0.0596086 -0.0666033 0.0547917 0.0600516 -0.0676033 0.0555219 0.0600702 -0.0666033 0.0563758 0.0600702 -0.0676033 0.0563758 0.0596593 -0.0666033 0.0571246 0.0589291 -0.0666033 0.0575676 0.0795751 -0.0666033 0.0178988 0.0802715 -0.0666033 0.0191498 0.0801507 -0.0666033 0.0198741 0.0802715 -0.0676033 0.0191498 0.0801507 -0.0676033 0.0198741 0.0797276 -0.0676033 0.0204743 0.0781049 -0.0666033 -0.0242482 0.0788537 -0.0666033 -0.0238374 0.0781049 -0.0676033 -0.0242482 0.0793154 -0.0666033 -0.0222532 0.0789045 -0.0666033 -0.0215045 0.0781743 -0.0666033 -0.0210614 0.0789045 -0.0676033 -0.0215045 0.0399896 -0.0536033 0.069328 0.040136 -0.0536033 0.06845 0.0414265 -0.0536033 0.0672896 0.0424616 -0.0536033 0.0672671 0.0425804 -0.0536033 0.0667814 0.0439062 -0.0536033 0.0686502 0.0443862 -0.0536033 0.0685103 0.0439287 -0.0536033 0.0696852 0.0444144 -0.0536033 0.0698041 0.0437919 -0.0536033 0.0709386 0.0425456 -0.0536033 0.0711298 0.0416571 -0.0536033 0.0711825 0.0415749 -0.0536033 0.0716757 0.0398017 -0.0536033 0.0704257 0.043715 -0.0536033 0.0674039 0.0425804 -0.0673033 0.0667814 0.043715 -0.0673033 0.0674039 0.0444144 -0.0673033 0.0698041 0.0437919 -0.0673033 0.0709386 0.0426855 -0.0536033 0.0716099 0.0426855 -0.0673033 0.0716099 0.0412027 -0.0676033 0.0665215 0.0426518 -0.0676033 0.06649 0.0443862 -0.0673033 0.0685103 0.0446743 -0.0676033 0.0684263 0.0447058 -0.0676033 0.0698754 0.0440086 -0.0676033 0.0711461 0.0427694 -0.0676033 0.0718979 0.0729606 -0.0536033 0.038824 0.0731485 -0.0536033 0.0377263 0.0726357 -0.0536033 0.0408013 0.0704887 -0.0536033 0.0408849 0.0703698 -0.0536033 0.0413706 0.069581 -0.0536033 0.0403869 0.069044 -0.0536033 0.0395018 0.068564 -0.0536033 0.0396417 0.0690215 -0.0536033 0.0384668 0.0691583 -0.0536033 0.0372134 0.0712931 -0.0536033 0.0369695 0.0702647 -0.0536033 0.0365421 0.0721165 -0.0536033 0.0373076 0.0713754 -0.0536033 0.0364763 0.0724046 -0.0536033 0.036899 0.0713754 -0.0673033 0.0364763 0.0724046 -0.0673033 0.036899 0.0731485 -0.0673033 0.0377263 0.0734598 -0.0536033 0.0387945 0.0734598 -0.0673033 0.0387945 0.0732768 -0.0536033 0.0398919 0.0732768 -0.0673033 0.0398919 0.0726357 -0.0673033 0.0408013 0.0716636 -0.0536033 0.0413425 0.0702647 -0.0673033 0.0365421 0.0701808 -0.0676033 0.0362541 0.0714247 -0.0676033 0.0361804 0.0725774 -0.0676033 0.0366538 0.0735543 -0.0676033 0.0400059 0.0797738 -0.0536033 -0.000124438 0.0805149 -0.0536033 0.000706855 0.0787418 -0.0536033 -0.000543107 0.0786136 -0.0536033 -0.00270873 0.0790761 -0.0536033 -0.0025188 0.0792546 -0.0536033 -0.00361809 0.0803666 -0.0536033 -0.00367922 0.0823093 -0.0536033 -0.00320374 0.0828463 -0.0536033 -0.00231864 0.0828688 -0.0536033 -0.00128361 0.0833263 -0.0536033 -0.00245853 0.0833545 -0.0536033 -0.00116474 0.0823708 -0.0536033 -0.000375984 0.0814857 -0.0536033 0.000161039 0.082732 -0.0536033 -3.02067e-05 0.0805972 -0.0536033 0.000213665 0.0815205 -0.0536033 -0.00418741 0.0826551 -0.0536033 -0.0035649 0.0815205 -0.0673033 -0.00418741 0.0826551 -0.0673033 -0.0035649 0.0833263 -0.0673033 -0.00245853 0.0833545 -0.0673033 -0.00116474 0.0816256 -0.0536033 0.000641072 0.082732 -0.0673033 -3.02067e-05 0.0428505 -0.0528533 0.0683068 0.0433692 -0.0536033 0.0677651 0.042889 -0.0528533 0.0700742 0.0423358 -0.0528533 0.0704098 0.0434307 -0.0536033 0.0705928 0.0432002 -0.0528533 0.0695069 0.0431862 -0.0528533 0.06886 0.0422832 -0.0528533 0.0679955 0.0423358 -0.0420533 0.0704098 0.0425456 -0.0413033 0.0711298 0.042889 -0.0420533 0.0700742 0.0432002 -0.0420533 0.0695069 0.0431862 -0.0420533 0.06886 0.0428505 -0.0420533 0.0683068 0.0439062 -0.0413033 0.0686502 0.0422832 -0.0420533 0.0679955 0.0704046 -0.0536033 0.0370222 0.0716844 -0.0528533 0.0379206 0.0727116 -0.0536033 0.0379695 0.072212 -0.0528533 0.0388684 0.0721204 -0.0528533 0.0394171 0.0728142 -0.0536033 0.039702 0.0723014 -0.0536033 0.0404295 0.0713139 -0.0528533 0.0401424 0.0717999 -0.0528533 0.0398718 0.072212 -0.0420533 0.0388684 0.0720563 -0.0528533 0.0383343 0.0720563 -0.0420533 0.0383343 0.0711697 -0.0528533 0.0377093 0.0711697 -0.0420533 0.0377093 0.0706144 -0.0420533 0.0377422 0.0715237 -0.0413033 0.0408624 0.0717999 -0.0420533 0.0398718 0.0721204 -0.0420533 0.0394171 0.0723014 -0.0413033 0.0404295 0.0728142 -0.0413033 0.039702 0.0727116 -0.0413033 0.0379695 0.0716844 -0.0420533 0.0379206 0.0721165 -0.0413033 0.0373076 0.0817906 -0.0528533 -0.002662 0.0814017 -0.0536033 -0.00370175 0.0821403 -0.0528533 -0.00146192 0.0818291 -0.0528533 -0.00089465 0.0812759 -0.0420533 -0.00055901 0.0818291 -0.0420533 -0.00089465 0.0821263 -0.0528533 -0.00210881 0.0821263 -0.0420533 -0.00210881 0.0817906 -0.0420533 -0.002662 0.0812233 -0.0528533 -0.00297325 0.0812233 -0.0420533 -0.00297325 0.0821403 -0.0420533 -0.00146192 0.0823708 -0.0413033 -0.000375984 0.0828688 -0.0413033 -0.00128361 0.0823093 -0.0413033 -0.00320374 0.0814017 -0.0413033 -0.00370175 0.0805764 -0.0420533 -0.00295917 -0.00343595 -0.0416033 0.0825115 -0.0035702 -0.0673033 0.0826416 -0.00292915 -0.0673033 0.0817323 -0.00281344 -0.0673033 0.081377 -0.00281344 -0.0416033 0.081377 -0.0028416 -0.0416033 0.0800832 -0.00305741 -0.0673033 0.0795666 -0.00351288 -0.0416033 0.0789768 -0.00351288 -0.0673033 0.0789768 -0.00380133 -0.0673033 0.0787393 -0.00464741 -0.0673033 0.0783543 -0.00483054 -0.0673033 0.0783167 -0.00321925 -0.0413033 0.082719 -0.00255358 -0.0413033 0.0799992 -0.00464741 -0.0416033 0.0783543 -0.00330541 -0.0413033 0.0787601 -0.0319686 -0.0416033 0.07647 -0.0308622 -0.0416033 0.0757987 -0.0302397 -0.0673033 0.0746641 -0.0302397 -0.0416033 0.0746641 -0.0299483 -0.0413033 0.0747355 -0.0302679 -0.0416033 0.0733704 -0.0309391 -0.0416033 0.072264 -0.0320737 -0.0416033 0.0716415 -0.0333675 -0.0416033 0.0716696 -0.0431245 -0.0673033 0.0690704 -0.0442309 -0.0416033 0.0697417 -0.042502 -0.0673033 0.0679359 -0.0425302 -0.0673033 0.0666421 -0.042502 -0.0416033 0.0679359 -0.044336 -0.0673033 0.0649132 -0.044336 -0.0416033 0.0649132 -0.0431245 -0.0416033 0.0690704 -0.0429078 -0.0413033 0.0692779 -0.0425302 -0.0416033 0.0666421 -0.0422421 -0.0413033 0.0665582 -0.0432014 -0.0416033 0.0655357 -0.042994 -0.0413033 0.065319 -0.0442647 -0.0413033 0.0646218 -0.0629256 -0.0416033 0.0471155 -0.0629256 -0.0673033 0.0471155 -0.0635969 -0.0416033 0.0460091 -0.0635969 -0.0673033 0.0460091 -0.0647314 -0.0416033 0.0453866 -0.0635199 -0.0416033 0.0495438 -0.0628974 -0.0416033 0.0484093 -0.0633032 -0.0413033 0.0497513 -0.0633894 -0.0413033 0.0457924 -0.0646601 -0.0413033 0.0450952 -0.00343595 -0.0673033 0.0825115 -0.00265163 -0.0676033 0.0818462 -0.00274614 -0.0673033 0.0806348 -0.0028416 -0.0673033 0.0800832 -0.00362848 -0.0676033 0.0784941 -0.0059412 -0.0673033 0.0783824 -0.00478119 -0.0676033 0.0780208 -0.0320737 -0.0673033 0.0716415 -0.0334514 -0.0676033 0.0713816 -0.0309391 -0.0673033 0.072264 -0.0302679 -0.0673033 0.0733704 -0.0299483 -0.0676033 0.0747355 -0.0308622 -0.0673033 0.0757987 -0.0319686 -0.0673033 0.07647 -0.0318847 -0.0676033 0.076758 -0.0432014 -0.0673033 0.0655357 -0.0442647 -0.0676033 0.0646218 -0.0429078 -0.0676033 0.0692779 -0.0647314 -0.0673033 0.0453866 -0.0646601 -0.0676033 0.0450952 -0.0633894 -0.0676033 0.0457924 -0.0626376 -0.0676033 0.0470316 -0.0628974 -0.0673033 0.0484093 -0.0635199 -0.0673033 0.0495438 -0.0646263 -0.0673033 0.0502151 0.00367675 -0.0536033 0.0803735 0.00369928 -0.0536033 0.0814085 0.00320127 -0.0536033 0.0823161 0.00128114 -0.0536033 0.0828757 0.00245606 -0.0536033 0.0833332 0.000373513 -0.0536033 0.0823777 2.7736e-05 -0.0536033 0.0827388 -0.00016351 -0.0536033 0.0814926 -0.000186035 -0.0536033 0.0804576 0.0022321 -0.0536033 0.0789904 0.00105719 -0.0536033 0.0785329 0.00319706 -0.0536033 0.0788897 0.00216784 -0.0536033 0.0784671 0.00319706 -0.0673033 0.0788897 0.00348551 -0.0673033 0.0791272 0.00394097 -0.0673033 0.079717 0.00394097 -0.0536033 0.079717 0.00425225 -0.0536033 0.0807852 0.00415679 -0.0673033 0.0802336 0.00406924 -0.0536033 0.0818827 0.00418494 -0.0673033 0.0815274 0.00342818 -0.0536033 0.082792 0.00377913 -0.0676033 0.0828694 0.00447634 -0.0676033 0.0815987 0.00356243 -0.0673033 0.0826619 0.00406924 -0.0673033 0.0818827 0.00425225 -0.0673033 0.0807852 0.00235098 -0.0673033 0.0785047 -0.0375043 -0.0536033 0.0689277 -0.0375617 -0.0536033 0.0695264 -0.0384693 -0.0536033 0.0690283 -0.0413731 -0.0536033 0.0703766 -0.0413449 -0.0536033 0.0716704 -0.0370021 -0.0536033 0.0714465 -0.0366322 -0.0536033 0.0719206 -0.0372732 -0.0536033 0.07283 -0.0383852 -0.0536033 0.0728911 -0.0382453 -0.0536033 0.0733712 -0.0400971 -0.0536033 0.0726057 -0.0406922 -0.0536033 0.0719438 -0.0407949 -0.0536033 0.0702113 -0.0396442 -0.0536033 0.0685708 -0.0385335 -0.0536033 0.0685051 -0.0375043 -0.0673033 0.0689277 -0.0367604 -0.0536033 0.069755 -0.0367604 -0.0673033 0.069755 -0.0364491 -0.0536033 0.0708232 -0.0366322 -0.0673033 0.0719206 -0.0385335 -0.0673033 0.0685051 -0.0384842 -0.0676033 0.0682091 -0.0373315 -0.0676033 0.0686825 -0.0364491 -0.0673033 0.0708232 -0.0361497 -0.0676033 0.0708055 -0.0372732 -0.0673033 0.07283 -0.0370726 -0.0676033 0.0730531 -0.0381614 -0.0676033 0.0736592 -0.0685127 -0.0536033 0.0443931 -0.0698065 -0.0536033 0.0444213 -0.0705953 -0.0536033 0.0434376 -0.0711323 -0.0536033 0.0425525 -0.071018 -0.0536033 0.040264 -0.0688832 -0.0536033 0.0400202 -0.0670278 -0.0536033 0.0407769 -0.0672157 -0.0536033 0.0418747 -0.0668996 -0.0536033 0.0429426 -0.0699116 -0.0536033 0.0395928 -0.0699116 -0.0673033 0.0395928 -0.068801 -0.0673033 0.039527 -0.068801 -0.0536033 0.039527 -0.0677717 -0.0536033 0.0399496 -0.0677717 -0.0673033 0.0399496 -0.0670278 -0.0673033 0.0407769 -0.0667166 -0.0536033 0.0418451 -0.0668996 -0.0673033 0.0429426 -0.0675406 -0.0536033 0.0438519 -0.0675406 -0.0673033 0.0438519 -0.0699956 -0.0676033 0.0393048 -0.0667166 -0.0673033 0.0418451 -0.06734 -0.0676033 0.044075 0.0020538 -0.0528533 0.0797189 0.0029567 -0.0528533 0.0805833 0.00313973 -0.0536033 0.0794884 0.00297078 -0.0528533 0.0812302 0.00210634 -0.0528533 0.0821331 0.00265953 -0.0528533 0.0817975 0.00262106 -0.0528533 0.0800301 0.0029567 -0.0420533 0.0805833 0.00262106 -0.0420533 0.0800301 0.0014069 -0.0528533 0.0797329 0.00265953 -0.0420533 0.0817975 0.00320127 -0.0413033 0.0823161 0.00369928 -0.0413033 0.0814085 0.00297078 -0.0420533 0.0812302 0.00367675 -0.0413033 0.0803735 0.00313973 -0.0413033 0.0794884 0.0022321 -0.0413033 0.0789904 0.0020538 -0.0420533 0.0797189 0.00119707 -0.0413033 0.0790129 -0.0392945 -0.0528533 0.0697709 -0.0380803 -0.0528533 0.0700681 -0.0370246 -0.0536033 0.0704115 -0.0377306 -0.0528533 0.0712682 -0.0375001 -0.0536033 0.0723541 -0.0380419 -0.0528533 0.0718354 -0.038595 -0.0528533 0.0721711 -0.038109 -0.0420533 0.0719005 -0.0380419 -0.0420533 0.0718354 -0.0377447 -0.0528533 0.0706213 -0.0377447 -0.0420533 0.0706213 -0.0378526 -0.0420533 0.070363 -0.0392945 -0.0420533 0.0697709 -0.0386476 -0.0528533 0.0697568 -0.0387392 -0.0420533 0.069738 -0.0382245 -0.0420533 0.0699493 -0.0386158 -0.0413033 0.0689982 -0.0386476 -0.0420533 0.0697568 -0.0377924 -0.0413033 0.0693363 -0.0380803 -0.0420533 0.0700681 -0.037697 -0.0420533 0.0708971 -0.0377306 -0.0420533 0.0712682 -0.0377885 -0.0420533 0.0714458 -0.0376075 -0.0413033 0.0724582 -0.0678749 -0.0536033 0.0434801 -0.0688625 -0.0528533 0.043193 -0.0683093 -0.0528533 0.0428574 -0.0680559 -0.0528533 0.0424678 -0.0673621 -0.0536033 0.0427526 -0.067998 -0.0528533 0.0422901 -0.0680121 -0.0528533 0.0416432 -0.0674647 -0.0536033 0.0410201 -0.0680598 -0.0536033 0.0403583 -0.0683477 -0.0528533 0.04109 -0.068492 -0.0528533 0.0409713 -0.0697717 -0.0536033 0.0400728 -0.068915 -0.0528533 0.0407788 -0.0695619 -0.0528533 0.0407929 -0.0690066 -0.0420533 0.04076 -0.0690066 -0.0528533 0.04076 -0.068492 -0.0420533 0.0409713 -0.06812 -0.0420533 0.0413849 -0.06812 -0.0528533 0.0413849 -0.067998 -0.0420533 0.0422901 -0.0679644 -0.0528533 0.041919 -0.0680559 -0.0420533 0.0424678 -0.0683764 -0.0420533 0.0429224 -0.0683764 -0.0528533 0.0429224 -0.0688625 -0.0420533 0.043193 -0.068915 -0.0420533 0.0407788 -0.0680598 -0.0413033 0.0403583 -0.0683477 -0.0420533 0.04109 -0.0680121 -0.0420533 0.0416432 -0.0679644 -0.0420533 0.041919 -0.0673621 -0.0413033 0.0427526 -0.0683093 -0.0420533 0.0428574 0.00690399 -0.0673033 -0.0789192 0.00690399 -0.0416033 -0.0789192 0.00754504 -0.0416033 -0.0798286 0.00772805 -0.0673033 -0.080926 0.00763259 -0.0673033 -0.0814777 0.00772805 -0.0416033 -0.080926 0.00741678 -0.0673033 -0.0819942 0.00763259 -0.0416033 -0.0814777 0.00741678 -0.0416033 -0.0819942 0.00696131 -0.0673033 -0.082584 0.00696131 -0.0416033 -0.082584 0.00667286 -0.0673033 -0.0828215 0.00667286 -0.0416033 -0.0828215 0.00582678 -0.0673033 -0.0832065 0.00564365 -0.0416033 -0.0832442 0.00453299 -0.0673033 -0.0831784 0.00453299 -0.0416033 -0.0831784 0.0058981 -0.0413033 -0.0834979 0.00582678 -0.0416033 -0.0832065 0.00716878 -0.0413033 -0.0828007 0.00766075 -0.0416033 -0.0801839 0.00795215 -0.0413033 -0.0801125 0.00593186 -0.0416033 -0.0783781 0.00725494 -0.0413033 -0.0788419 0.00703824 -0.0416033 -0.0790493 0.0333581 -0.0416033 -0.0716652 0.0344645 -0.0673033 -0.0723365 0.0343302 -0.0416033 -0.0722064 0.035087 -0.0673033 -0.073471 0.0351543 -0.0416033 -0.0742132 0.0350588 -0.0673033 -0.0747648 0.034843 -0.0416033 -0.0752814 0.0340991 -0.0416033 -0.0761087 0.0340991 -0.0673033 -0.0761087 0.033253 -0.0673033 -0.0764937 0.0349713 -0.0416033 -0.0731158 0.0345308 -0.0413033 -0.0719833 0.0352488 -0.0413033 -0.0730018 0.0354538 -0.0413033 -0.0742309 0.034272 -0.0413033 -0.0763539 0.0330699 -0.0416033 -0.0765313 0.0331193 -0.0413033 -0.0768273 0.0456204 -0.0673033 -0.064937 0.0467268 -0.0416033 -0.0656083 0.0473493 -0.0416033 -0.0667428 0.0463614 -0.0673033 -0.0693805 0.0455154 -0.0673033 -0.0697655 0.0455154 -0.0416033 -0.0697655 0.0453322 -0.0673033 -0.0698031 0.0469435 -0.0413033 -0.0654008 0.0476092 -0.0413033 -0.0681205 0.0473212 -0.0416033 -0.0680366 0.0466499 -0.0416033 -0.069143 0.0468573 -0.0413033 -0.0693597 0.0442216 -0.0416033 -0.0697373 0.0455867 -0.0413033 -0.0700569 0.0671222 -0.0673033 -0.0460817 0.0660159 -0.0416033 -0.0454104 0.0677447 -0.0673033 -0.0472162 0.0677447 -0.0416033 -0.0472162 0.0677166 -0.0416033 -0.04851 0.0670453 -0.0416033 -0.0496164 0.0659108 -0.0673033 -0.0502389 0.064617 -0.0673033 -0.0502107 0.0659108 -0.0416033 -0.0502389 0.0671222 -0.0416033 -0.0460817 0.0672528 -0.0413033 -0.0498331 0.064617 -0.0416033 -0.0502107 0.0659821 -0.0413033 -0.0505303 0.0645331 -0.0413033 -0.0504987 0.00725494 -0.0676033 -0.0788419 0.00703824 -0.0673033 -0.0790493 0.00754504 -0.0673033 -0.0798286 0.00795215 -0.0676033 -0.0801125 0.00766075 -0.0673033 -0.0801839 0.00716878 -0.0676033 -0.0828007 0.00444906 -0.0676033 -0.0834664 0.0058981 -0.0676033 -0.0834979 0.00564365 -0.0673033 -0.0832442 0.0333581 -0.0673033 -0.0716652 0.0346812 -0.0676033 -0.072129 0.0353784 -0.0676033 -0.0733997 0.0349713 -0.0673033 -0.0731158 0.0351543 -0.0673033 -0.0742132 0.0353469 -0.0676033 -0.0748488 0.0343876 -0.0673033 -0.0758712 0.034843 -0.0673033 -0.0752814 0.0465926 -0.0673033 -0.0654781 0.0467268 -0.0673033 -0.0656083 0.0475111 -0.0676033 -0.0662736 0.0472336 -0.0673033 -0.0663875 0.0473493 -0.0673033 -0.0667428 0.0474166 -0.0673033 -0.067485 0.0473212 -0.0673033 -0.0680366 0.0471053 -0.0673033 -0.0685531 0.0465343 -0.0676033 -0.0696257 0.0466499 -0.0673033 -0.069143 0.0453816 -0.0676033 -0.070099 0.0670453 -0.0673033 -0.0496164 0.0672528 -0.0676033 -0.0498331 0.0677166 -0.0673033 -0.04851 0.0660159 -0.0673033 -0.0454104 -0.00368609 -0.0536033 -0.0803691 -0.00426158 -0.0536033 -0.0807808 -0.00343752 -0.0536033 -0.0827876 -0.0023255 -0.0536033 -0.0828488 -0.00246539 -0.0536033 -0.0833288 -0.000613609 -0.0536033 -0.0825633 0.000634209 -0.0536033 -0.0816281 0.000662366 -0.0536033 -0.0803343 3.98557e-05 -0.0536033 -0.0791998 -0.00106652 -0.0536033 -0.0785285 -0.00320639 -0.0536033 -0.0788853 -0.0039503 -0.0536033 -0.0797127 -0.0011716 -0.0536033 -0.083357 -3.70695e-05 -0.0536033 -0.0827345 0.000634209 -0.0673033 -0.0816281 0.000662366 -0.0673033 -0.0803343 3.98557e-05 -0.0673033 -0.0791998 -0.00246539 -0.0673033 -0.0833288 -0.00254932 -0.0676033 -0.0836168 -0.00110028 -0.0676033 -0.0836484 -0.0011716 -0.0673033 -0.083357 -3.70695e-05 -0.0673033 -0.0827345 0.000953764 -0.0676033 -0.080263 0.000256553 -0.0676033 -0.0789923 0.0370853 -0.0536033 -0.0717263 0.0383759 -0.0536033 -0.0728867 0.0395298 -0.0536033 -0.0733949 0.0406643 -0.0536033 -0.0727724 0.0408556 -0.0536033 -0.0715262 0.0413356 -0.0536033 -0.071666 0.0407412 -0.0536033 -0.0692377 0.0386065 -0.0536033 -0.0689939 0.0396349 -0.0536033 -0.0685664 0.0385242 -0.0536033 -0.0685007 0.0377831 -0.0536033 -0.069332 0.0369389 -0.0536033 -0.0708484 0.038236 -0.0536033 -0.0733668 0.0406643 -0.0673033 -0.0727724 0.0413638 -0.0536033 -0.0703723 0.0413638 -0.0673033 -0.0703723 0.0396011 -0.0676033 -0.0736863 0.0395298 -0.0673033 -0.0733949 0.0413356 -0.0673033 -0.071666 0.0407412 -0.0673033 -0.0692377 0.0396349 -0.0673033 -0.0685664 0.067474 -0.0536033 -0.0401827 0.0672827 -0.0536033 -0.041429 0.0672602 -0.0536033 -0.042464 0.0677582 -0.0536033 -0.0433717 0.0686433 -0.0536033 -0.0439087 0.0685034 -0.0536033 -0.0443887 0.070586 -0.0536033 -0.0434332 0.071123 -0.0536033 -0.0425481 0.0706475 -0.0536033 -0.0406054 0.0699023 -0.0536033 -0.0395884 0.0687274 -0.0536033 -0.0400459 0.0678197 -0.0536033 -0.0405439 0.0697972 -0.0673033 -0.0444169 0.0697972 -0.0536033 -0.0444169 0.0706433 -0.0673033 -0.0440319 0.0709317 -0.0536033 -0.0437944 0.0713872 -0.0673033 -0.0432045 0.071603 -0.0536033 -0.042688 0.071603 -0.0673033 -0.042688 0.0716985 -0.0673033 -0.0421364 0.0716312 -0.0673033 -0.0413942 0.0716312 -0.0536033 -0.0413942 0.0699023 -0.0673033 -0.0395884 0.0708744 -0.0673033 -0.0401295 0.0710087 -0.0673033 -0.0402597 0.0710087 -0.0536033 -0.0402597 0.0715155 -0.0673033 -0.0410389 0.071793 -0.0676033 -0.0409249 0.0716493 -0.0676033 -0.0433504 0.0709317 -0.0673033 -0.0437944 0.0708161 -0.0676033 -0.0442771 0.0685034 -0.0673033 -0.0443887 0.0684195 -0.0676033 -0.0446767 0.0696141 -0.0673033 -0.0444545 -0.000930174 -0.0528533 -0.0799991 -0.000428706 -0.0536033 -0.0794414 8.41366e-05 -0.0536033 -0.0801689 0.000230546 -0.0536033 -0.0810469 -1.84766e-05 -0.0536033 -0.0819014 -0.000673781 -0.0528533 -0.0815366 -0.00156034 -0.0528533 -0.0821616 -0.00143698 -0.0536033 -0.0829014 -0.00104574 -0.0528533 -0.0819503 -0.00156034 -0.0420533 -0.0821616 -0.00146878 -0.0528533 -0.0821428 -0.000673781 -0.0420533 -0.0815366 -0.000901512 -0.0528533 -0.0818315 -0.000565873 -0.0528533 -0.0812784 -0.000565873 -0.0420533 -0.0812784 -0.000518142 -0.0420533 -0.0810025 -0.000551795 -0.0420533 -0.0806315 -0.000518142 -0.0528533 -0.0810025 -0.000551795 -0.0528533 -0.0806315 -0.000609648 -0.0420533 -0.0804538 -0.000609648 -0.0528533 -0.0804538 -0.00086305 -0.0528533 -0.0800642 -0.000930174 -0.0420533 -0.0799991 -0.00141624 -0.0420533 -0.0797286 -0.00146878 -0.0420533 -0.0821428 -0.00104574 -0.0420533 -0.0819503 -0.000613609 -0.0413033 -0.0825633 -0.000901512 -0.0420533 -0.0818315 -1.84766e-05 -0.0413033 -0.0819014 0.000230546 -0.0413033 -0.0810469 -0.00120641 -0.0413033 -0.0790085 -0.000428706 -0.0413033 -0.0794414 -0.00086305 -0.0420533 -0.0800642 0.039495 -0.0536033 -0.0690465 0.0403801 -0.0536033 -0.0695835 0.0398383 -0.0528533 -0.0701022 0.0400917 -0.0528533 -0.0704918 0.0408781 -0.0536033 -0.0704911 0.0392326 -0.0528533 -0.0721808 0.0396556 -0.0528533 -0.0719883 0.0394109 -0.0536033 -0.0729093 0.0403185 -0.0536033 -0.0724113 0.0401496 -0.0528533 -0.0706694 0.0401832 -0.0420533 -0.0710405 0.0401832 -0.0528533 -0.0710405 0.0401355 -0.0528533 -0.0713163 0.0400276 -0.0528533 -0.0715746 0.0397999 -0.0528533 -0.0718695 0.0396556 -0.0420533 -0.0719883 0.0385857 -0.0528533 -0.0721667 0.0392851 -0.0420533 -0.0697665 0.0397712 -0.0420533 -0.0700371 0.0400917 -0.0420533 -0.0704918 0.0409319 -0.0413033 -0.0710849 0.0400276 -0.0420533 -0.0715746 0.0406829 -0.0413033 -0.0719394 0.0400878 -0.0413033 -0.0726013 0.039141 -0.0420533 -0.0721996 0.0688531 -0.0528533 -0.0431886 0.0695 -0.0528533 -0.0432027 0.0700673 -0.0528533 -0.0428915 0.0696783 -0.0536033 -0.0439312 0.0704029 -0.0528533 -0.0423383 0.070417 -0.0528533 -0.0416914 0.0701058 -0.0528533 -0.0411241 0.0711455 -0.0536033 -0.0415131 0.0695526 -0.0528533 -0.0407885 0.0697624 -0.0536033 -0.0400684 0.0701058 -0.0420533 -0.0411241 0.0704029 -0.0420533 -0.0423383 0.0695 -0.0420533 -0.0432027 0.0706475 -0.0413033 -0.0406054 0.070417 -0.0420533 -0.0416914 0.0700673 -0.0420533 -0.0428915 0.070586 -0.0413033 -0.0434332 0.0696783 -0.0413033 -0.0439312 0.0686433 -0.0413033 -0.0439087 -0.0461458 -0.0673033 -0.0634599 -0.0460116 -0.0416033 -0.06359 -0.0453891 -0.0416033 -0.0647245 -0.0453218 -0.0673033 -0.0654667 -0.0472231 -0.0416033 -0.0677472 -0.0474062 -0.0673033 -0.0677848 -0.0454172 -0.0416033 -0.0660183 -0.0450977 -0.0413033 -0.0646532 -0.0460885 -0.0416033 -0.0671247 -0.0485168 -0.0416033 -0.0677191 -0.0656724 -0.0416033 -0.0430645 -0.0655382 -0.0673033 -0.0431946 -0.0650314 -0.0673033 -0.0439738 -0.0648484 -0.0416033 -0.0450713 -0.0648484 -0.0673033 -0.0450713 -0.0649438 -0.0673033 -0.0456229 -0.0651597 -0.0416033 -0.0461395 -0.0659036 -0.0416033 -0.0469668 -0.0669328 -0.0416033 -0.0473894 -0.0667497 -0.0673033 -0.0473518 -0.0650314 -0.0416033 -0.0439738 -0.0645489 -0.0413033 -0.045089 -0.0724007 -0.0416033 -0.0308022 -0.0724007 -0.0673033 -0.0308022 -0.0722664 -0.0416033 -0.0309323 -0.0717596 -0.0673033 -0.0317115 -0.0717596 -0.0416033 -0.0317115 -0.0716439 -0.0416033 -0.0320668 -0.0715766 -0.0673033 -0.032809 -0.0715766 -0.0416033 -0.032809 -0.0718879 -0.0673033 -0.0338771 -0.0723434 -0.0673033 -0.034467 -0.0726318 -0.0416033 -0.0347045 -0.0734779 -0.0673033 -0.0350895 -0.0734779 -0.0416033 -0.0350895 -0.073661 -0.0416033 -0.0351271 -0.073661 -0.0673033 -0.0351271 -0.0736117 -0.0413033 -0.035423 -0.0748556 -0.0413033 -0.0353493 -0.0723434 -0.0416033 -0.034467 -0.0718879 -0.0416033 -0.0338771 -0.0712772 -0.0413033 -0.0328267 -0.0716721 -0.0416033 -0.0333606 -0.0714821 -0.0413033 -0.0315976 -0.0722001 -0.0413033 -0.0305791 -0.0800856 -0.0416033 -0.00283473 -0.0791135 -0.0416033 -0.0033759 -0.0784725 -0.0673033 -0.00428526 -0.0786007 -0.0416033 -0.00645088 -0.0793446 -0.0416033 -0.00727822 -0.0793446 -0.0673033 -0.00727822 -0.0814845 -0.0416033 -0.00763506 -0.0789129 -0.0413033 -0.00315282 -0.0784725 -0.0416033 -0.00428526 -0.07799 -0.0413033 -0.00540045 -0.0782895 -0.0416033 -0.00538271 -0.0783386 -0.0413033 -0.0065968 -0.0803245 -0.0413033 -0.00799676 -0.0803739 -0.0416033 -0.00770085 -0.0459453 -0.0676033 -0.0632368 -0.0460116 -0.0673033 -0.06359 -0.0452273 -0.0676033 -0.0642553 -0.0455048 -0.0673033 -0.0643693 -0.0453891 -0.0673033 -0.0647245 -0.0450223 -0.0676033 -0.0654844 -0.0454172 -0.0673033 -0.0660183 -0.0456331 -0.0673033 -0.0665349 -0.0460885 -0.0673033 -0.0671247 -0.0486008 -0.0676033 -0.0680071 -0.0473568 -0.0676033 -0.0680808 -0.0472231 -0.0673033 -0.0677472 -0.046377 -0.0673033 -0.0673622 -0.0665606 -0.0676033 -0.0422353 -0.0646243 -0.0676033 -0.0442578 -0.0649157 -0.0673033 -0.0443291 -0.0651597 -0.0673033 -0.0461395 -0.0659036 -0.0673033 -0.0469668 -0.0654077 -0.0676033 -0.046946 -0.0656151 -0.0673033 -0.0467293 -0.0722664 -0.0673033 -0.0309323 -0.0714821 -0.0676033 -0.0315976 -0.0716439 -0.0673033 -0.0320668 -0.0712772 -0.0676033 -0.0328267 -0.0716258 -0.0676033 -0.0340231 -0.0716721 -0.0673033 -0.0333606 -0.0726318 -0.0673033 -0.0347045 -0.072459 -0.0676033 -0.0349497 -0.0747717 -0.0673033 -0.0350613 -0.0736117 -0.0676033 -0.035423 -0.0789793 -0.0673033 -0.00350601 -0.0780969 -0.0676033 -0.00601827 -0.0783568 -0.0673033 -0.00464055 -0.0782895 -0.0673033 -0.00538271 -0.0783849 -0.0673033 -0.00593433 -0.0786007 -0.0673033 -0.00645088 -0.0788487 -0.0676033 -0.00725741 -0.0815684 -0.0676033 -0.00792308 -0.0801907 -0.0673033 -0.00766322 -0.0790562 -0.0673033 -0.00704071 -0.042555 -0.0536033 -0.0711255 -0.0415199 -0.0536033 -0.071148 -0.0414011 -0.0536033 -0.0716336 -0.0402665 -0.0536033 -0.0710111 -0.0406123 -0.0536033 -0.07065 -0.0400753 -0.0536033 -0.0697649 -0.0400527 -0.0536033 -0.0687298 -0.0395671 -0.0536033 -0.068611 -0.0414359 -0.0536033 -0.0672852 -0.0424709 -0.0536033 -0.0672627 -0.0424066 -0.0536033 -0.0667394 -0.0433785 -0.0536033 -0.0677607 -0.0434358 -0.0536033 -0.067162 -0.0395952 -0.0536033 -0.0699048 -0.0395952 -0.0673033 -0.0699048 -0.0395671 -0.0673033 -0.068611 -0.0401896 -0.0536033 -0.0674764 -0.0414011 -0.0673033 -0.0716336 -0.0402665 -0.0673033 -0.0710111 -0.0400591 -0.0676033 -0.0712278 -0.0393072 -0.0676033 -0.0699887 -0.0401896 -0.0673033 -0.0674764 -0.0392757 -0.0676033 -0.0685396 -0.0399729 -0.0676033 -0.067269 -0.041212 -0.0676033 -0.0665171 -0.0695904 -0.0536033 -0.0403825 -0.0705623 -0.0536033 -0.0414038 -0.071533 -0.0536033 -0.040858 -0.0723107 -0.0536033 -0.0404251 -0.0684778 -0.0536033 -0.0390857 -0.0690308 -0.0536033 -0.0384624 -0.0695288 -0.0536033 -0.0375548 -0.0693019 -0.0536033 -0.0370789 -0.070274 -0.0536033 -0.0365377 -0.0715678 -0.0536033 -0.0365096 -0.072721 -0.0536033 -0.0379651 -0.0727024 -0.0536033 -0.0371321 -0.07297 -0.0536033 -0.0388197 -0.0728236 -0.0536033 -0.0396976 -0.069533 -0.0536033 -0.0409812 -0.069533 -0.0673033 -0.0409812 -0.0687891 -0.0536033 -0.0401539 -0.0684778 -0.0673033 -0.0390857 -0.0686609 -0.0536033 -0.0379883 -0.0693019 -0.0673033 -0.0370789 -0.0705623 -0.0673033 -0.0414038 -0.0705129 -0.0676033 -0.0416998 -0.0687891 -0.0673033 -0.0401539 -0.0686609 -0.0673033 -0.0379883 -0.0691013 -0.0676033 -0.0368558 -0.070274 -0.0673033 -0.0365377 -0.0701901 -0.0676033 -0.0362497 -0.0828782 -0.0536033 0.001288 -0.0826071 -0.0536033 -9.55153e-05 -0.0823802 -0.0536033 0.000380376 -0.079188 -0.0536033 0.000790696 -0.0792066 -0.0536033 -4.23264e-05 -0.078939 -0.0536033 0.00164523 -0.0785072 -0.0536033 0.00235784 -0.0795983 -0.0536033 0.00325068 -0.080376 -0.0536033 0.00368362 -0.081411 -0.0536033 0.00370614 -0.0803412 -0.0536033 -0.000664837 -0.0803412 -0.0673033 -0.000664837 -0.0792066 -0.0673033 -4.23264e-05 -0.0785353 -0.0536033 0.00106405 -0.0791297 -0.0536033 0.00349237 -0.0791297 -0.0673033 0.00349237 -0.0816349 -0.0673033 -0.00063668 -0.0817189 -0.0676033 -0.0009247 -0.0802698 -0.0676033 -0.000956235 -0.0785353 -0.0673033 0.00106405 -0.0785072 -0.0673033 0.00235784 -0.0802361 -0.0673033 0.00416365 -0.0405508 -0.0536033 -0.0678222 -0.0410925 -0.0528533 -0.0683409 -0.0408391 -0.0528533 -0.0687305 -0.0407953 -0.0528533 -0.069555 -0.0423451 -0.0528533 -0.0704054 -0.041131 -0.0528533 -0.0701082 -0.0416457 -0.0420533 -0.0680052 -0.0411596 -0.0420533 -0.0682758 -0.0407812 -0.0528533 -0.0689081 -0.0407476 -0.0528533 -0.0692792 -0.0409032 -0.0528533 -0.0698133 -0.0409032 -0.0420533 -0.0698133 -0.0412752 -0.0420533 -0.070227 -0.0412752 -0.0528533 -0.070227 -0.0416982 -0.0528533 -0.0704195 -0.0408391 -0.0420533 -0.0687305 -0.0406582 -0.0413033 -0.0677181 -0.0401453 -0.0413033 -0.0684456 -0.0407476 -0.0420533 -0.0692792 -0.0408431 -0.0413033 -0.07084 -0.0417898 -0.0420533 -0.0704383 -0.0713232 -0.0528533 -0.040138 -0.070498 -0.0536033 -0.0408806 -0.0690533 -0.0536033 -0.0394974 -0.0697593 -0.0528533 -0.0386407 -0.0700706 -0.0528533 -0.0380735 -0.0704139 -0.0536033 -0.0370178 -0.0706238 -0.0528533 -0.0377378 -0.0698172 -0.0420533 -0.0384631 -0.0697257 -0.0420533 -0.0390118 -0.0697734 -0.0528533 -0.0392876 -0.070109 -0.0528533 -0.0398408 -0.070109 -0.0420533 -0.0398408 -0.0706763 -0.0528533 -0.0401521 -0.0713232 -0.0420533 -0.040138 -0.0707679 -0.0420533 -0.0401709 -0.0706763 -0.0420533 -0.0401521 -0.0706445 -0.0413033 -0.0409107 -0.0702533 -0.0420533 -0.0399596 -0.0698813 -0.0420533 -0.0395459 -0.069226 -0.0413033 -0.0399107 -0.0697734 -0.0420533 -0.0392876 -0.0697593 -0.0420533 -0.0386407 -0.0696362 -0.0413033 -0.0374507 -0.0701377 -0.0420533 -0.0380084 -0.0700706 -0.0420533 -0.0380735 -0.0812852 -0.0528533 0.000563402 -0.0814951 -0.0536033 -0.000156647 -0.0806065 -0.0536033 -0.000209273 -0.0797832 -0.0536033 0.00012883 -0.0802153 -0.0528533 0.000741825 -0.0796877 -0.0528533 0.00168958 -0.0797792 -0.0528533 0.0022383 -0.0790854 -0.0536033 0.00252319 -0.0800997 -0.0528533 0.00269298 -0.0805858 -0.0528533 0.00296357 -0.0797792 -0.0420533 0.0022383 -0.0796877 -0.0420533 0.00168958 -0.0798433 -0.0528533 0.00115549 -0.0807299 -0.0528533 0.000530511 -0.0807299 -0.0420533 0.000530511 -0.0800997 -0.0420533 0.00269298 -0.0795983 -0.0413033 0.00325068 -0.078939 -0.0413033 0.00164523 -0.0798433 -0.0420533 0.00115549 -0.0802153 -0.0420533 0.000741825 -0.0797832 -0.0413033 0.00012883 -0.0814951 -0.0413033 -0.000156647 0.0461652 -0.0676033 -0.0274267 0.0463285 -0.0734783 -0.0268661 0.0461652 -0.0791033 -0.0274267 0.0464566 -0.0739359 -0.0264269 0.0471488 -0.0676033 -0.0240514 0.0474019 -0.0709739 -0.0231829 0.0473029 -0.0727533 -0.0235227 0.0468063 -0.0717708 -0.0252268 0.053509 -0.0722283 -0.00222598 0.0536723 -0.0676033 -0.00166542 0.0532061 -0.0716033 -0.00326529 0.0525346 -0.0729533 -0.00556944 0.0528564 -0.0728533 -0.00446537 0.0529032 -0.0722283 -0.00430459 0.0523604 -0.0704283 -0.00616755 0.0530312 -0.0717708 -0.00386533 0.0469343 -0.0734783 -0.0247875 0.0474019 -0.0747328 -0.0231829 0.0476839 -0.0762414 -0.0222151 0.0468063 -0.0739359 -0.0252268 0.0466314 -0.0741033 -0.0258268 0.0518842 -0.0769803 -0.0078016 0.0536723 -0.0791033 -0.00166542 0.0486038 -0.0776033 -0.0190584 0.0512337 -0.0776033 -0.0100337 0.0436054 -0.0741033 -0.000467544 0.0439083 -0.0734783 0.000571758 0.0437803 -0.0739359 0.000132497 0.0439552 -0.0728533 0.000732538 0.053509 -0.0734783 -0.00222598 0.053381 -0.0739359 -0.00266524 0.0532061 -0.0741033 -0.00326529 0.0434306 -0.0739359 -0.00106758 0.0433026 -0.0734783 -0.00150685 0.0530312 -0.0739359 -0.00386533 0.0432557 -0.0728533 -0.00166763 0.0529032 -0.0734783 -0.00430459 0.0372056 -0.0739359 -0.0224291 0.0367279 -0.0734783 -0.0240684 0.0469811 -0.0728533 -0.0246268 0.0373336 -0.0734783 -0.0219898 0.0370308 -0.0741033 -0.0230291 0.0368559 -0.0739359 -0.0236291 0.0462817 -0.0728533 -0.0270269 -0.0463379 -0.0722283 0.0268705 -0.046291 -0.0728533 0.0270313 -0.0474865 -0.0704283 0.022929 -0.0524449 -0.0747328 0.00591366 -0.0536817 -0.0676033 0.00166982 -0.052698 -0.0676033 0.00504513 -0.0523697 -0.0704283 0.00617194 -0.0528657 -0.0728533 0.00446976 -0.0521629 -0.0762414 0.0068814 -0.0536817 -0.0791033 0.00166982 -0.0533903 -0.0739359 0.00266964 -0.0535183 -0.0734783 0.00223038 -0.0471581 -0.0676033 0.0240558 -0.0486132 -0.0681033 0.0190628 -0.0486132 -0.0776033 0.0190628 -0.0474865 -0.0752783 0.022929 -0.0473122 -0.0729533 0.0235271 -0.0473122 -0.0727533 0.0235271 -0.0370401 -0.0741033 0.0230335 -0.0368652 -0.0739359 0.0236335 -0.0469905 -0.0728533 0.0246311 -0.0469436 -0.0734783 0.0247919 -0.037343 -0.0734783 0.0219942 -0.0372149 -0.0739359 0.0224334 -0.0468156 -0.0739359 0.0252312 -0.0466407 -0.0741033 0.0258312 -0.0464659 -0.0739359 0.0264313 -0.0367372 -0.0734783 0.0240728 -0.0463379 -0.0734783 0.0268705 -0.0439645 -0.0728533 -0.000728146 -0.0428937 -0.0728533 0.000261804 -0.0433119 -0.0734783 0.00151124 -0.0432651 -0.0728533 0.00167202 -0.0535652 -0.0728533 0.00206959 -0.0439176 -0.0734783 -0.000567366 -0.0437896 -0.0739359 -0.000128105 -0.0532154 -0.0741033 0.00326968 -0.0436148 -0.0741033 0.000471936 -0.0434399 -0.0739359 0.00107198 -0.0530406 -0.0739359 0.00386972 -0.0529126 -0.0734783 0.00430898 -0.0461745 -0.0676033 0.0274311 -0.0451878 -0.0791033 0.0295739 -0.0461745 -0.0791033 0.0274311 -0.0540005 -0.0676033 -0.000667607 0.0451785 -0.0791033 -0.0295695 0.0486679 -0.0433033 0.0690151 0.0366449 -0.0433033 0.0760851 0.0488408 -0.0433033 0.0692603 0.00999047 -0.0433033 0.0841607 -0.00398375 -0.0433033 0.0843584 -0.00399789 -0.0433033 0.0846581 -0.0312692 -0.0433033 0.0787746 -0.0311586 -0.0433033 0.0784957 -0.0549574 -0.0433033 0.0641271 -0.0551526 -0.0433033 0.0643549 -0.0647625 -0.0433033 0.0542076 -0.0649926 -0.0433033 0.0544001 -0.0728012 -0.0433033 0.0428095 -0.0730598 -0.0433033 0.0429616 -0.0791343 -0.0433033 0.0303512 -0.0844013 -0.0433033 0.00300278 -0.0837442 -0.0433033 -0.0109294 -0.0808028 -0.0433033 -0.0245634 -0.0595835 -0.0433033 -0.0602716 -0.0488502 -0.0433033 -0.0692559 -0.0367845 -0.0433033 -0.076351 -0.0237155 -0.0433033 -0.0813634 -0.00999981 -0.0433033 -0.0841563 0.00398856 -0.0433033 -0.0846537 0.00397442 -0.0433033 -0.084354 0.0178047 -0.0433033 -0.0825486 0.0312599 -0.0433033 -0.0787702 0.054948 -0.0433033 -0.0641227 0.043799 -0.0433033 -0.0725499 0.0551433 -0.0433033 -0.0643505 0.0649832 -0.0433033 -0.0543958 0.0727919 -0.0433033 -0.0428051 0.0730505 -0.0433033 -0.0429572 0.083041 -0.0433033 -0.0169086 0.0846918 -0.0433033 -0.00300905 0.0756481 -0.0433033 0.0375316 0.0759169 -0.0433033 0.037665 0.0686823 -0.0433033 0.0496476 0.0593632 -0.0433033 0.0600626 0.0236223 -0.0443033 0.0810798 0.00995509 -0.0433033 0.0838628 -0.00398375 -0.0443033 0.0843584 -0.0178141 -0.0433033 0.082553 -0.0311586 -0.0443033 0.0784957 -0.0436533 -0.0433033 0.0722974 -0.0647625 -0.0443033 0.0542076 -0.0788542 -0.0433033 0.0302438 -0.0827564 -0.0433033 0.0168531 -0.0844013 -0.0443033 0.00300278 -0.0756574 -0.0433033 -0.0375272 -0.0756574 -0.0443033 -0.0375272 -0.0684485 -0.0443033 -0.0494674 -0.0684485 -0.0433033 -0.0494674 -0.0593726 -0.0433033 -0.0600582 -0.0486773 -0.0433033 -0.0690107 -0.0486773 -0.0443033 -0.0690107 -0.0366543 -0.0433033 -0.0760807 -0.0236316 -0.0433033 -0.0810754 -0.0236316 -0.0443033 -0.0810754 0.00995509 -0.0443033 0.0838628 0.00999047 -0.0443033 0.0841607 0.0237062 -0.0443033 0.0813678 0.0367751 -0.0443033 0.0763554 0.0593632 -0.0443033 0.0600626 0.0595741 -0.0443033 0.060276 0.0686823 -0.0443033 0.0496476 0.0837348 -0.0443033 0.0109338 0.0810805 -0.0443033 0.024655 0.0846918 -0.0443033 -0.00300905 0.083041 -0.0443033 -0.0169086 0.079125 -0.0443033 -0.0303468 0.0551433 -0.0443033 -0.0643505 0.00398856 -0.0443033 -0.0846537 -0.00996442 -0.0443033 -0.0838584 -0.0237155 -0.0443033 -0.0813634 -0.0366543 -0.0443033 -0.0760807 -0.0593726 -0.0443033 -0.0600582 -0.0595835 -0.0443033 -0.0602716 -0.0808028 -0.0443033 -0.0245634 -0.0837442 -0.0443033 -0.0109294 -0.0827564 -0.0443033 0.0168531 -0.0791343 -0.0443033 0.0303512 -0.0788542 -0.0443033 0.0302438 -0.0728012 -0.0443033 0.0428095 -0.0730598 -0.0443033 0.0429616 -0.0549574 -0.0443033 0.0641271 -0.0436533 -0.0443033 0.0722974 -0.0178141 -0.0443033 0.082553 0.0237621 -0.0431033 0.0815598 0.0237062 -0.0433033 0.0813678 0.0100141 -0.0431033 0.0843593 -0.00400731 -0.0431033 0.0848578 -0.0179195 -0.0431033 0.0830417 -0.031343 -0.0431033 0.0789605 -0.0178773 -0.0433033 0.0828462 -0.0438083 -0.0433033 0.0725543 -0.0651459 -0.0431033 0.0545285 -0.079321 -0.0431033 0.0304228 -0.0830504 -0.0433033 0.016913 -0.0847012 -0.0433033 0.00301344 -0.08424 -0.0431033 -0.0109941 -0.0840416 -0.0433033 -0.0109682 -0.0812812 -0.0431033 -0.0247088 -0.0810898 -0.0433033 -0.0246506 -0.0761054 -0.0431033 -0.0377494 -0.0759262 -0.0433033 -0.0376606 -0.0686916 -0.0433033 -0.0496432 -0.0489654 -0.0431033 -0.0694193 -0.0237715 -0.0431033 -0.0815554 -0.0237715 -0.0445033 -0.0815554 -0.0367845 -0.0443033 -0.076351 -0.0488502 -0.0443033 -0.0692559 -0.0597241 -0.0445033 -0.0604138 -0.0686916 -0.0443033 -0.0496432 -0.0759262 -0.0443033 -0.0376606 -0.0810898 -0.0443033 -0.0246506 -0.0840416 -0.0443033 -0.0109682 -0.0847012 -0.0443033 0.00301344 -0.0830504 -0.0443033 0.016913 -0.079321 -0.0445033 0.0304228 -0.0732322 -0.0445033 0.043063 -0.0651459 -0.0445033 0.0545285 -0.0649926 -0.0443033 0.0544001 -0.0552827 -0.0445033 0.0645068 -0.0551526 -0.0443033 0.0643549 -0.0438083 -0.0443033 0.0725543 -0.0312692 -0.0443033 0.0787746 -0.0179195 -0.0445033 0.0830417 -0.0178773 -0.0443033 0.0828462 -0.00400731 -0.0445033 0.0848578 0.0100141 -0.0445033 0.0843593 -0.00399789 -0.0443033 0.0846581 0.0759169 -0.0458033 0.037665 0.0593632 -0.0458033 0.0600626 0.0486679 -0.0458033 0.0690151 0.0488408 -0.0458033 0.0692603 0.0366449 -0.0458033 0.0760851 0.0367751 -0.0458033 0.0763554 0.00999047 -0.0458033 0.0841607 -0.0178773 -0.0458033 0.0828462 -0.0312692 -0.0458033 0.0787746 -0.0438083 -0.0458033 0.0725543 -0.0549574 -0.0458033 0.0641271 -0.0649926 -0.0458033 0.0544001 -0.0728012 -0.0458033 0.0428095 -0.0791343 -0.0458033 0.0303512 -0.0830504 -0.0458033 0.016913 -0.0844013 -0.0458033 0.00300278 -0.0840416 -0.0458033 -0.0109682 -0.0756574 -0.0458033 -0.0375272 -0.0684485 -0.0458033 -0.0494674 -0.0686916 -0.0458033 -0.0496432 -0.0488502 -0.0458033 -0.0692559 -0.0486773 -0.0458033 -0.0690107 -0.0366543 -0.0458033 -0.0760807 -0.0236316 -0.0458033 -0.0810754 -0.0367845 -0.0458033 -0.076351 -0.00999981 -0.0458033 -0.0841563 -0.00996442 -0.0458033 -0.0838584 0.0178047 -0.0458033 -0.0825486 0.00398856 -0.0458033 -0.0846537 0.0311492 -0.0458033 -0.0784914 0.043644 -0.0458033 -0.072293 0.043799 -0.0458033 -0.0725499 0.0647532 -0.0458033 -0.0542032 0.0788449 -0.0458033 -0.0302394 0.083041 -0.0458033 -0.0169086 0.0846918 -0.0458033 -0.00300905 0.084392 -0.0458033 -0.00299839 0.0837348 -0.0458033 0.0109338 0.0807935 -0.0458033 0.0245677 0.0810805 -0.0458033 0.024655 0.0236223 -0.0468033 0.0810798 0.0236223 -0.0458033 0.0810798 0.00995509 -0.0458033 0.0838628 0.00995509 -0.0468033 0.0838628 -0.00398375 -0.0458033 0.0843584 -0.00398375 -0.0468033 0.0843584 -0.0178141 -0.0458033 0.082553 -0.0178141 -0.0468033 0.082553 -0.0311586 -0.0458033 0.0784957 -0.0436533 -0.0458033 0.0722974 -0.0647625 -0.0458033 0.0542076 -0.0788542 -0.0458033 0.0302438 -0.0788542 -0.0468033 0.0302438 -0.0827564 -0.0458033 0.0168531 -0.0827564 -0.0468033 0.0168531 -0.0844013 -0.0468033 0.00300278 -0.0837442 -0.0468033 -0.0109294 -0.0837442 -0.0458033 -0.0109294 -0.0808028 -0.0458033 -0.0245634 -0.0593726 -0.0468033 -0.0600582 -0.0593726 -0.0458033 -0.0600582 -0.0366543 -0.0468033 -0.0760807 -0.0236316 -0.0468033 -0.0810754 0.054948 -0.0468033 -0.0641227 0.0551433 -0.0468033 -0.0643505 0.0312599 -0.0468033 -0.0787702 0.0178047 -0.0468033 -0.0825486 0.00397442 -0.0468033 -0.084354 -0.00996442 -0.0468033 -0.0838584 -0.00999981 -0.0468033 -0.0841563 -0.0367845 -0.0468033 -0.076351 -0.0486773 -0.0468033 -0.0690107 -0.0684485 -0.0468033 -0.0494674 -0.0595835 -0.0468033 -0.0602716 -0.0759262 -0.0468033 -0.0376606 -0.0756574 -0.0468033 -0.0375272 -0.0808028 -0.0468033 -0.0245634 -0.0840416 -0.0468033 -0.0109682 -0.0830504 -0.0468033 0.016913 -0.0728012 -0.0468033 0.0428095 -0.0730598 -0.0468033 0.0429616 -0.0647625 -0.0468033 0.0542076 -0.0549574 -0.0468033 0.0641271 -0.0551526 -0.0468033 0.0643549 -0.0436533 -0.0468033 0.0722974 -0.0438083 -0.0468033 0.0725543 -0.0311586 -0.0468033 0.0784957 -0.0312692 -0.0468033 0.0787746 -0.0178773 -0.0468033 0.0828462 -0.00399789 -0.0468033 0.0846581 0.00999047 -0.0468033 0.0841607 0.0237062 -0.0468033 0.0813678 0.0366449 -0.0468033 0.0760851 0.0593632 -0.0468033 0.0600626 0.0488408 -0.0468033 0.0692603 0.0595741 -0.0468033 0.060276 0.0686823 -0.0468033 0.0496476 0.0756481 -0.0468033 0.0375316 0.0759169 -0.0468033 0.037665 0.0810805 -0.0468033 0.024655 0.0846918 -0.0468033 -0.00300905 0.083041 -0.0468033 -0.0169086 0.079125 -0.0468033 -0.0303468 0.0730505 -0.0468033 -0.0429572 -0.0593726 -0.0483033 -0.0600582 -0.0595835 -0.0483033 -0.0602716 -0.0488502 -0.0483033 -0.0692559 -0.00999981 -0.0483033 -0.0841563 0.00397442 -0.0483033 -0.084354 0.00398856 -0.0483033 -0.0846537 0.017868 -0.0483033 -0.0828418 0.0311492 -0.0483033 -0.0784914 0.054948 -0.0483033 -0.0641227 0.0551433 -0.0483033 -0.0643505 0.0649832 -0.0483033 -0.0543958 0.0727919 -0.0483033 -0.0428051 0.0730505 -0.0483033 -0.0429572 0.0788449 -0.0483033 -0.0302394 0.0827471 -0.0483033 -0.0168487 0.0846918 -0.0483033 -0.00300905 0.0807935 -0.0483033 0.0245677 0.0684392 -0.0483033 0.0494718 0.0593632 -0.0483033 0.0600626 0.0595741 -0.0483033 0.060276 0.0486679 -0.0483033 0.0690151 0.00995509 -0.0483033 0.0838628 -0.00398375 -0.0483033 0.0843584 0.00999047 -0.0483033 0.0841607 -0.0178141 -0.0483033 0.082553 -0.0178773 -0.0483033 0.0828462 -0.0436533 -0.0483033 0.0722974 -0.0551526 -0.0483033 0.0643549 -0.0647625 -0.0483033 0.0542076 -0.0728012 -0.0483033 0.0428095 -0.0649926 -0.0483033 0.0544001 -0.0730598 -0.0483033 0.0429616 -0.0830504 -0.0483033 0.016913 -0.0827564 -0.0483033 0.0168531 -0.0840416 -0.0483033 -0.0109682 -0.0810898 -0.0483033 -0.0246506 -0.0808028 -0.0483033 -0.0245634 -0.0756574 -0.0483033 -0.0375272 0.0236223 -0.0483033 0.0810798 -0.00398375 -0.0493033 0.0843584 -0.0311586 -0.0483033 0.0784957 -0.0311586 -0.0493033 0.0784957 -0.0549574 -0.0483033 0.0641271 -0.0436533 -0.0493033 0.0722974 -0.0647625 -0.0493033 0.0542076 -0.0728012 -0.0493033 0.0428095 -0.0788542 -0.0483033 0.0302438 -0.0827564 -0.0493033 0.0168531 -0.0844013 -0.0483033 0.00300278 -0.0837442 -0.0483033 -0.0109294 -0.0837442 -0.0493033 -0.0109294 -0.0684485 -0.0483033 -0.0494674 -0.0684485 -0.0493033 -0.0494674 -0.0593726 -0.0493033 -0.0600582 -0.0486773 -0.0483033 -0.0690107 -0.0366543 -0.0493033 -0.0760807 -0.0366543 -0.0483033 -0.0760807 0.0647532 -0.0493033 -0.0542032 0.054948 -0.0493033 -0.0641227 0.0311492 -0.0493033 -0.0784914 0.00398856 -0.0493033 -0.0846537 -0.0236316 -0.0493033 -0.0810754 -0.0237155 -0.0493033 -0.0813634 -0.0367845 -0.0493033 -0.076351 -0.0486773 -0.0493033 -0.0690107 -0.0595835 -0.0493033 -0.0602716 -0.0756574 -0.0493033 -0.0375272 -0.0808028 -0.0493033 -0.0245634 -0.0810898 -0.0493033 -0.0246506 -0.0844013 -0.0493033 0.00300278 -0.0788542 -0.0493033 0.0302438 -0.0730598 -0.0493033 0.0429616 -0.0649926 -0.0493033 0.0544001 -0.0549574 -0.0493033 0.0641271 -0.0551526 -0.0493033 0.0643549 -0.0312692 -0.0493033 0.0787746 -0.0178141 -0.0493033 0.082553 0.00995509 -0.0493033 0.0838628 0.0236223 -0.0493033 0.0810798 0.0237062 -0.0493033 0.0813678 0.0593632 -0.0493033 0.0600626 0.0756481 -0.0493033 0.0375316 0.0686823 -0.0493033 0.0496476 0.0759169 -0.0493033 0.037665 0.084392 -0.0493033 -0.00299839 0.0846918 -0.0493033 -0.00300905 0.0827471 -0.0493033 -0.0168487 0.0788449 -0.0493033 -0.0302394 0.079125 -0.0493033 -0.0303468 0.0649832 -0.0493033 -0.0543958 0.00999047 -0.0508033 0.0841607 -0.00398375 -0.0508033 0.0843584 -0.0311586 -0.0508033 0.0784957 -0.0178773 -0.0508033 0.0828462 -0.0312692 -0.0508033 0.0787746 -0.0551526 -0.0508033 0.0643549 -0.0649926 -0.0508033 0.0544001 -0.0647625 -0.0508033 0.0542076 -0.0788542 -0.0508033 0.0302438 -0.0830504 -0.0508033 0.016913 -0.0847012 -0.0508033 0.00301344 -0.0840416 -0.0508033 -0.0109682 -0.0808028 -0.0508033 -0.0245634 -0.0684485 -0.0508033 -0.0494674 -0.0488502 -0.0508033 -0.0692559 -0.0366543 -0.0508033 -0.0760807 -0.0367845 -0.0508033 -0.076351 -0.0237155 -0.0508033 -0.0813634 0.00397442 -0.0508033 -0.084354 0.0178047 -0.0508033 -0.0825486 0.00398856 -0.0508033 -0.0846537 0.0311492 -0.0508033 -0.0784914 0.043644 -0.0508033 -0.072293 0.054948 -0.0508033 -0.0641227 0.0551433 -0.0508033 -0.0643505 0.0647532 -0.0508033 -0.0542032 0.0727919 -0.0508033 -0.0428051 0.0730505 -0.0508033 -0.0429572 0.084392 -0.0508033 -0.00299839 0.0840323 -0.0508033 0.0109726 0.0807935 -0.0508033 0.0245677 0.0756481 -0.0508033 0.0375316 0.0810805 -0.0508033 0.024655 0.0759169 -0.0508033 0.037665 0.0366449 -0.0508033 0.0760851 0.0488408 -0.0508033 0.0692603 0.0236223 -0.0508033 0.0810798 0.0237062 -0.0508033 0.0813678 0.00995509 -0.0508033 0.0838628 -0.00398375 -0.0518033 0.0843584 -0.0178141 -0.0508033 0.082553 -0.0311586 -0.0518033 0.0784957 -0.0436533 -0.0508033 0.0722974 -0.0436533 -0.0518033 0.0722974 -0.0549574 -0.0508033 0.0641271 -0.0647625 -0.0518033 0.0542076 -0.0728012 -0.0518033 0.0428095 -0.0728012 -0.0508033 0.0428095 -0.0827564 -0.0508033 0.0168531 -0.0827564 -0.0518033 0.0168531 -0.0844013 -0.0508033 0.00300278 -0.0844013 -0.0518033 0.00300278 -0.0837442 -0.0518033 -0.0109294 -0.0837442 -0.0508033 -0.0109294 -0.0808028 -0.0518033 -0.0245634 -0.0756574 -0.0508033 -0.0375272 -0.0593726 -0.0508033 -0.0600582 -0.0593726 -0.0518033 -0.0600582 -0.0486773 -0.0508033 -0.0690107 -0.0486773 -0.0518033 -0.0690107 -0.0366543 -0.0518033 -0.0760807 -0.0236316 -0.0518033 -0.0810754 0.0827471 -0.0518033 -0.0168487 0.083041 -0.0518033 -0.0169086 0.079125 -0.0518033 -0.0303468 0.0727919 -0.0518033 -0.0428051 0.0730505 -0.0518033 -0.0429572 0.0649832 -0.0518033 -0.0543958 0.0551433 -0.0518033 -0.0643505 0.043644 -0.0518033 -0.072293 0.043799 -0.0518033 -0.0725499 0.0312599 -0.0518033 -0.0787702 0.00397442 -0.0518033 -0.084354 -0.00996442 -0.0518033 -0.0838584 -0.00999981 -0.0518033 -0.0841563 -0.0237155 -0.0518033 -0.0813634 -0.0367845 -0.0518033 -0.076351 -0.0488502 -0.0518033 -0.0692559 -0.0595835 -0.0518033 -0.0602716 -0.0684485 -0.0518033 -0.0494674 -0.0756574 -0.0518033 -0.0375272 -0.0810898 -0.0518033 -0.0246506 -0.0788542 -0.0518033 0.0302438 -0.0791343 -0.0518033 0.0303512 -0.0549574 -0.0518033 0.0641271 -0.0551526 -0.0518033 0.0643549 -0.0438083 -0.0518033 0.0725543 -0.0312692 -0.0518033 0.0787746 -0.0178141 -0.0518033 0.082553 0.00995509 -0.0518033 0.0838628 0.00999047 -0.0518033 0.0841607 0.0237062 -0.0518033 0.0813678 0.0366449 -0.0518033 0.0760851 0.0486679 -0.0518033 0.0690151 0.0488408 -0.0518033 0.0692603 0.0595741 -0.0518033 0.060276 0.0684392 -0.0518033 0.0494718 0.0756481 -0.0518033 0.0375316 0.0807935 -0.0518033 0.0245677 0.0837348 -0.0518033 0.0109338 0.084392 -0.0518033 -0.00299839 -0.00398375 -0.0533033 0.0843584 -0.0178141 -0.0533033 0.082553 -0.0178773 -0.0533033 0.0828462 -0.0311586 -0.0533033 0.0784957 -0.0549574 -0.0533033 0.0641271 -0.0438083 -0.0533033 0.0725543 -0.0647625 -0.0533033 0.0542076 -0.0728012 -0.0533033 0.0428095 -0.0830504 -0.0533033 0.016913 -0.0844013 -0.0533033 0.00300278 -0.0756574 -0.0533033 -0.0375272 -0.0810898 -0.0533033 -0.0246506 -0.0593726 -0.0533033 -0.0600582 -0.0486773 -0.0533033 -0.0690107 -0.0595835 -0.0533033 -0.0602716 -0.0236316 -0.0533033 -0.0810754 -0.00996442 -0.0533033 -0.0838584 0.0178047 -0.0533033 -0.0825486 0.00398856 -0.0533033 -0.0846537 0.043644 -0.0533033 -0.072293 0.0551433 -0.0533033 -0.0643505 0.0647532 -0.0533033 -0.0542032 0.0827471 -0.0533033 -0.0168487 0.084392 -0.0533033 -0.00299839 0.0837348 -0.0533033 0.0109338 0.0840323 -0.0533033 0.0109726 0.0759169 -0.0533033 0.037665 0.0486679 -0.0533033 0.0690151 0.0367751 -0.0533033 0.0763554 0.0366449 -0.0533033 0.0760851 0.0237062 -0.0533033 0.0813678 0.00995509 -0.0533033 0.0838628 0.00995509 -0.0543033 0.0838628 -0.00398375 -0.0543033 0.0843584 -0.0436533 -0.0533033 0.0722974 -0.0311586 -0.0543033 0.0784957 -0.0436533 -0.0543033 0.0722974 -0.0549574 -0.0543033 0.0641271 -0.0647625 -0.0543033 0.0542076 -0.0728012 -0.0543033 0.0428095 -0.0788542 -0.0533033 0.0302438 -0.0827564 -0.0543033 0.0168531 -0.0827564 -0.0533033 0.0168531 -0.0837442 -0.0533033 -0.0109294 -0.0837442 -0.0543033 -0.0109294 -0.0808028 -0.0533033 -0.0245634 -0.0808028 -0.0543033 -0.0245634 -0.0684485 -0.0533033 -0.0494674 -0.0684485 -0.0543033 -0.0494674 -0.0593726 -0.0543033 -0.0600582 -0.0486773 -0.0543033 -0.0690107 -0.0366543 -0.0533033 -0.0760807 -0.0366543 -0.0543033 -0.0760807 0.083041 -0.0543033 -0.0169086 0.0788449 -0.0543033 -0.0302394 0.0727919 -0.0543033 -0.0428051 0.079125 -0.0543033 -0.0303468 0.0730505 -0.0543033 -0.0429572 0.054948 -0.0543033 -0.0641227 0.043644 -0.0543033 -0.072293 0.00397442 -0.0543033 -0.084354 -0.00996442 -0.0543033 -0.0838584 -0.0237155 -0.0543033 -0.0813634 -0.0595835 -0.0543033 -0.0602716 -0.0686916 -0.0543033 -0.0496432 -0.0756574 -0.0543033 -0.0375272 -0.0810898 -0.0543033 -0.0246506 -0.0840416 -0.0543033 -0.0109682 -0.0844013 -0.0543033 0.00300278 -0.0847012 -0.0543033 0.00301344 -0.0788542 -0.0543033 0.0302438 -0.0830504 -0.0543033 0.016913 -0.0730598 -0.0543033 0.0429616 -0.0649926 -0.0543033 0.0544001 -0.0438083 -0.0543033 0.0725543 -0.0178141 -0.0543033 0.082553 -0.0178773 -0.0543033 0.0828462 0.0236223 -0.0543033 0.0810798 0.0486679 -0.0543033 0.0690151 0.0756481 -0.0543033 0.0375316 0.0759169 -0.0543033 0.037665 0.0837348 -0.0543033 0.0109338 0.0840323 -0.0543033 0.0109726 0.0827471 -0.0543033 -0.0168487 -0.0686916 -0.0558033 -0.0496432 -0.0595835 -0.0558033 -0.0602716 -0.0486773 -0.0558033 -0.0690107 -0.0488502 -0.0558033 -0.0692559 -0.0367845 -0.0558033 -0.076351 -0.0366543 -0.0558033 -0.0760807 -0.0236316 -0.0558033 -0.0810754 -0.00996442 -0.0558033 -0.0838584 0.0178047 -0.0558033 -0.0825486 0.0311492 -0.0558033 -0.0784914 0.017868 -0.0558033 -0.0828418 0.043799 -0.0558033 -0.0725499 0.0551433 -0.0558033 -0.0643505 0.0647532 -0.0558033 -0.0542032 0.0649832 -0.0558033 -0.0543958 0.0727919 -0.0558033 -0.0428051 0.0730505 -0.0558033 -0.0429572 0.079125 -0.0558033 -0.0303468 0.0840323 -0.0558033 0.0109726 0.0807935 -0.0558033 0.0245677 0.0756481 -0.0558033 0.0375316 0.0686823 -0.0558033 0.0496476 0.0593632 -0.0558033 0.0600626 0.00995509 -0.0558033 0.0838628 0.00999047 -0.0558033 0.0841607 -0.00399789 -0.0558033 0.0846581 -0.0178141 -0.0558033 0.082553 -0.0178773 -0.0558033 0.0828462 -0.0436533 -0.0558033 0.0722974 -0.0438083 -0.0558033 0.0725543 -0.0551526 -0.0558033 0.0643549 -0.0549574 -0.0558033 0.0641271 -0.0730598 -0.0558033 0.0429616 -0.0788542 -0.0558033 0.0302438 -0.0830504 -0.0558033 0.016913 -0.0837442 -0.0558033 -0.0109294 -0.0847012 -0.0558033 0.00301344 -0.0840416 -0.0558033 -0.0109682 -0.0810898 -0.0558033 -0.0246506 0.0236223 -0.0568033 0.0810798 0.0236223 -0.0558033 0.0810798 -0.00398375 -0.0558033 0.0843584 -0.00398375 -0.0568033 0.0843584 -0.0311586 -0.0558033 0.0784957 -0.0549574 -0.0568033 0.0641271 -0.0647625 -0.0558033 0.0542076 -0.0647625 -0.0568033 0.0542076 -0.0728012 -0.0568033 0.0428095 -0.0728012 -0.0558033 0.0428095 -0.0827564 -0.0558033 0.0168531 -0.0844013 -0.0558033 0.00300278 -0.0827564 -0.0568033 0.0168531 -0.0837442 -0.0568033 -0.0109294 -0.0808028 -0.0568033 -0.0245634 -0.0808028 -0.0558033 -0.0245634 -0.0756574 -0.0558033 -0.0375272 -0.0684485 -0.0558033 -0.0494674 -0.0593726 -0.0558033 -0.0600582 -0.0366543 -0.0568033 -0.0760807 0.054948 -0.0568033 -0.0641227 0.0312599 -0.0568033 -0.0787702 0.0178047 -0.0568033 -0.0825486 0.017868 -0.0568033 -0.0828418 -0.00996442 -0.0568033 -0.0838584 -0.0236316 -0.0568033 -0.0810754 -0.00999981 -0.0568033 -0.0841563 -0.0237155 -0.0568033 -0.0813634 -0.0486773 -0.0568033 -0.0690107 -0.0593726 -0.0568033 -0.0600582 -0.0488502 -0.0568033 -0.0692559 -0.0684485 -0.0568033 -0.0494674 -0.0756574 -0.0568033 -0.0375272 -0.0759262 -0.0568033 -0.0376606 -0.0840416 -0.0568033 -0.0109682 -0.0844013 -0.0568033 0.00300278 -0.0788542 -0.0568033 0.0302438 -0.0436533 -0.0568033 0.0722974 -0.0311586 -0.0568033 0.0784957 -0.0178773 -0.0568033 0.0828462 -0.0178141 -0.0568033 0.082553 0.00995509 -0.0568033 0.0838628 0.0486679 -0.0568033 0.0690151 0.0488408 -0.0568033 0.0692603 0.0595741 -0.0568033 0.060276 0.0686823 -0.0568033 0.0496476 0.0756481 -0.0568033 0.0375316 0.0807935 -0.0568033 0.0245677 0.0759169 -0.0568033 0.037665 0.0810805 -0.0568033 0.024655 0.0837348 -0.0568033 0.0109338 0.0846918 -0.0568033 -0.00300905 0.0788449 -0.0568033 -0.0302394 0.079125 -0.0568033 -0.0303468 0.0647532 -0.0568033 -0.0542032 0.0649832 -0.0568033 -0.0543958 -0.0837442 -0.0583033 -0.0109294 -0.0840416 -0.0583033 -0.0109682 -0.0810898 -0.0583033 -0.0246506 -0.0759262 -0.0583033 -0.0376606 -0.0684485 -0.0583033 -0.0494674 -0.0686916 -0.0583033 -0.0496432 -0.0486773 -0.0583033 -0.0690107 -0.0366543 -0.0583033 -0.0760807 -0.0367845 -0.0583033 -0.076351 -0.00996442 -0.0583033 -0.0838584 0.0178047 -0.0583033 -0.0825486 0.043799 -0.0583033 -0.0725499 0.0551433 -0.0583033 -0.0643505 0.0730505 -0.0583033 -0.0429572 0.0727919 -0.0583033 -0.0428051 0.0788449 -0.0583033 -0.0302394 0.0827471 -0.0583033 -0.0168487 0.083041 -0.0583033 -0.0169086 0.0846918 -0.0583033 -0.00300905 0.0837348 -0.0583033 0.0109338 0.0840323 -0.0583033 0.0109726 0.0810805 -0.0583033 0.024655 0.0756481 -0.0583033 0.0375316 0.0593632 -0.0583033 0.0600626 0.0488408 -0.0583033 0.0692603 0.0366449 -0.0583033 0.0760851 0.0367751 -0.0583033 0.0763554 0.00995509 -0.0583033 0.0838628 0.00999047 -0.0583033 0.0841607 -0.00398375 -0.0583033 0.0843584 -0.00399789 -0.0583033 0.0846581 -0.0178141 -0.0583033 0.082553 -0.0549574 -0.0583033 0.0641271 -0.0551526 -0.0583033 0.0643549 -0.0647625 -0.0583033 0.0542076 -0.0728012 -0.0583033 0.0428095 -0.0788542 -0.0583033 0.0302438 -0.0730598 -0.0583033 0.0429616 -0.0827564 -0.0583033 0.0168531 -0.00398375 -0.0593033 0.0843584 -0.0178141 -0.0593033 0.082553 -0.0311586 -0.0583033 0.0784957 -0.0436533 -0.0583033 0.0722974 -0.0549574 -0.0593033 0.0641271 -0.0827564 -0.0593033 0.0168531 -0.0844013 -0.0583033 0.00300278 -0.0837442 -0.0593033 -0.0109294 -0.0808028 -0.0583033 -0.0245634 -0.0808028 -0.0593033 -0.0245634 -0.0756574 -0.0583033 -0.0375272 -0.0593726 -0.0583033 -0.0600582 -0.0684485 -0.0593033 -0.0494674 -0.0486773 -0.0593033 -0.0690107 -0.0236316 -0.0583033 -0.0810754 0.00999047 -0.0593033 0.0841607 0.0366449 -0.0593033 0.0760851 0.0367751 -0.0593033 0.0763554 0.0486679 -0.0593033 0.0690151 0.0488408 -0.0593033 0.0692603 0.0756481 -0.0593033 0.0375316 0.0759169 -0.0593033 0.037665 0.0810805 -0.0593033 0.024655 0.0807935 -0.0593033 0.0245677 0.0837348 -0.0593033 0.0109338 0.0840323 -0.0593033 0.0109726 0.0846918 -0.0593033 -0.00300905 0.0827471 -0.0593033 -0.0168487 0.083041 -0.0593033 -0.0169086 0.0730505 -0.0593033 -0.0429572 0.054948 -0.0593033 -0.0641227 0.043644 -0.0593033 -0.072293 0.0551433 -0.0593033 -0.0643505 0.043799 -0.0593033 -0.0725499 0.017868 -0.0593033 -0.0828418 0.00397442 -0.0593033 -0.084354 0.00398856 -0.0593033 -0.0846537 -0.00999981 -0.0593033 -0.0841563 -0.00996442 -0.0593033 -0.0838584 -0.0236316 -0.0593033 -0.0810754 -0.0366543 -0.0593033 -0.0760807 -0.0488502 -0.0593033 -0.0692559 -0.0593726 -0.0593033 -0.0600582 -0.0595835 -0.0593033 -0.0602716 -0.0686916 -0.0593033 -0.0496432 -0.0756574 -0.0593033 -0.0375272 -0.0810898 -0.0593033 -0.0246506 -0.0840416 -0.0593033 -0.0109682 -0.0844013 -0.0593033 0.00300278 -0.0788542 -0.0593033 0.0302438 -0.0830504 -0.0593033 0.016913 -0.0728012 -0.0593033 0.0428095 -0.0791343 -0.0593033 0.0303512 -0.0647625 -0.0593033 0.0542076 -0.0436533 -0.0593033 0.0722974 -0.0438083 -0.0593033 0.0725543 -0.0311586 -0.0593033 0.0784957 -0.0312692 -0.0593033 0.0787746 0.00995509 -0.0593033 0.0838628 -0.0593726 -0.0608033 -0.0600582 -0.0486773 -0.0608033 -0.0690107 -0.0236316 -0.0608033 -0.0810754 -0.00996442 -0.0608033 -0.0838584 0.0178047 -0.0608033 -0.0825486 0.0311492 -0.0608033 -0.0784914 0.043644 -0.0608033 -0.072293 0.0551433 -0.0608033 -0.0643505 0.0730505 -0.0608033 -0.0429572 0.0840323 -0.0608033 0.0109726 0.0810805 -0.0608033 0.024655 0.0807935 -0.0608033 0.0245677 0.0756481 -0.0608033 0.0375316 0.0684392 -0.0608033 0.0494718 0.0593632 -0.0608033 0.0600626 0.0595741 -0.0608033 0.060276 0.0236223 -0.0608033 0.0810798 0.00999047 -0.0608033 0.0841607 -0.00399789 -0.0608033 0.0846581 -0.0178773 -0.0608033 0.0828462 -0.0551526 -0.0608033 0.0643549 -0.0728012 -0.0608033 0.0428095 -0.0730598 -0.0608033 0.0429616 -0.0791343 -0.0608033 0.0303512 -0.0830504 -0.0608033 0.016913 -0.0837442 -0.0608033 -0.0109294 -0.0840416 -0.0608033 -0.0109682 -0.0810898 -0.0608033 -0.0246506 -0.0686916 -0.0608033 -0.0496432 0.00995509 -0.0608033 0.0838628 -0.00398375 -0.0608033 0.0843584 -0.0178141 -0.0608033 0.082553 -0.0311586 -0.0608033 0.0784957 -0.0178141 -0.0618033 0.082553 -0.0436533 -0.0608033 0.0722974 -0.0549574 -0.0608033 0.0641271 -0.0647625 -0.0608033 0.0542076 -0.0647625 -0.0618033 0.0542076 -0.0728012 -0.0618033 0.0428095 -0.0788542 -0.0608033 0.0302438 -0.0827564 -0.0608033 0.0168531 -0.0844013 -0.0608033 0.00300278 -0.0844013 -0.0618033 0.00300278 -0.0808028 -0.0608033 -0.0245634 -0.0808028 -0.0618033 -0.0245634 -0.0756574 -0.0608033 -0.0375272 -0.0756574 -0.0618033 -0.0375272 -0.0684485 -0.0608033 -0.0494674 -0.0593726 -0.0618033 -0.0600582 -0.0486773 -0.0618033 -0.0690107 -0.0366543 -0.0608033 -0.0760807 0.0788449 -0.0618033 -0.0302394 0.083041 -0.0618033 -0.0169086 0.079125 -0.0618033 -0.0303468 0.0730505 -0.0618033 -0.0429572 0.054948 -0.0618033 -0.0641227 0.0649832 -0.0618033 -0.0543958 0.043644 -0.0618033 -0.072293 0.0551433 -0.0618033 -0.0643505 0.0311492 -0.0618033 -0.0784914 0.043799 -0.0618033 -0.0725499 -0.00999981 -0.0618033 -0.0841563 -0.0236316 -0.0618033 -0.0810754 -0.0237155 -0.0618033 -0.0813634 -0.0366543 -0.0618033 -0.0760807 -0.0367845 -0.0618033 -0.076351 -0.0488502 -0.0618033 -0.0692559 -0.0595835 -0.0618033 -0.0602716 -0.0686916 -0.0618033 -0.0496432 -0.0684485 -0.0618033 -0.0494674 -0.0837442 -0.0618033 -0.0109294 -0.0847012 -0.0618033 0.00301344 -0.0827564 -0.0618033 0.0168531 -0.0788542 -0.0618033 0.0302438 -0.0730598 -0.0618033 0.0429616 -0.0649926 -0.0618033 0.0544001 -0.0549574 -0.0618033 0.0641271 -0.0436533 -0.0618033 0.0722974 -0.0551526 -0.0618033 0.0643549 -0.0311586 -0.0618033 0.0784957 -0.0178773 -0.0618033 0.0828462 -0.00398375 -0.0618033 0.0843584 0.00995509 -0.0618033 0.0838628 0.00999047 -0.0618033 0.0841607 0.0236223 -0.0618033 0.0810798 0.0366449 -0.0618033 0.0760851 0.0367751 -0.0618033 0.0763554 0.0488408 -0.0618033 0.0692603 0.0593632 -0.0618033 0.0600626 0.0595741 -0.0618033 0.060276 0.0684392 -0.0618033 0.0494718 0.0756481 -0.0618033 0.0375316 0.0686823 -0.0618033 0.0496476 0.0840323 -0.0618033 0.0109726 0.084392 -0.0618033 -0.00299839 0.0846918 -0.0618033 -0.00300905 -0.0595835 -0.0633033 -0.0602716 -0.0486773 -0.0633033 -0.0690107 -0.0367845 -0.0633033 -0.076351 0.00397442 -0.0633033 -0.084354 0.00398856 -0.0633033 -0.0846537 0.0311492 -0.0633033 -0.0784914 0.017868 -0.0633033 -0.0828418 0.0312599 -0.0633033 -0.0787702 0.043799 -0.0633033 -0.0725499 0.0647532 -0.0633033 -0.0542032 0.0730505 -0.0633033 -0.0429572 0.0788449 -0.0633033 -0.0302394 0.079125 -0.0633033 -0.0303468 0.083041 -0.0633033 -0.0169086 0.0807935 -0.0633033 0.0245677 0.0840323 -0.0633033 0.0109726 0.0810805 -0.0633033 0.024655 0.0756481 -0.0633033 0.0375316 0.0684392 -0.0633033 0.0494718 0.0486679 -0.0633033 0.0690151 0.0488408 -0.0633033 0.0692603 0.00995509 -0.0633033 0.0838628 -0.00398375 -0.0633033 0.0843584 -0.0311586 -0.0633033 0.0784957 -0.0436533 -0.0633033 0.0722974 -0.0312692 -0.0633033 0.0787746 -0.0438083 -0.0633033 0.0725543 -0.0549574 -0.0633033 0.0641271 -0.0647625 -0.0633033 0.0542076 -0.0649926 -0.0633033 0.0544001 -0.0728012 -0.0633033 0.0428095 -0.0730598 -0.0633033 0.0429616 -0.0788542 -0.0633033 0.0302438 -0.0791343 -0.0633033 0.0303512 -0.0827564 -0.0633033 0.0168531 -0.0830504 -0.0633033 0.016913 -0.0837442 -0.0633033 -0.0109294 -0.0810898 -0.0633033 -0.0246506 -0.0756574 -0.0633033 -0.0375272 -0.0684485 -0.0633033 -0.0494674 0.0236223 -0.0633033 0.0810798 -0.00398375 -0.0643033 0.0843584 -0.0178141 -0.0633033 0.082553 -0.0311586 -0.0643033 0.0784957 -0.0436533 -0.0643033 0.0722974 -0.0549574 -0.0643033 0.0641271 -0.0647625 -0.0643033 0.0542076 -0.0844013 -0.0633033 0.00300278 -0.0844013 -0.0643033 0.00300278 -0.0837442 -0.0643033 -0.0109294 -0.0808028 -0.0633033 -0.0245634 -0.0756574 -0.0643033 -0.0375272 -0.0684485 -0.0643033 -0.0494674 -0.0593726 -0.0633033 -0.0600582 -0.0593726 -0.0643033 -0.0600582 -0.0366543 -0.0633033 -0.0760807 -0.0366543 -0.0643033 -0.0760807 -0.0236316 -0.0633033 -0.0810754 -0.0236316 -0.0643033 -0.0810754 0.0827471 -0.0643033 -0.0168487 0.079125 -0.0643033 -0.0303468 0.0727919 -0.0643033 -0.0428051 0.0730505 -0.0643033 -0.0429572 0.0649832 -0.0643033 -0.0543958 0.054948 -0.0643033 -0.0641227 0.043799 -0.0643033 -0.0725499 0.0312599 -0.0643033 -0.0787702 0.017868 -0.0643033 -0.0828418 -0.00996442 -0.0643033 -0.0838584 -0.0237155 -0.0643033 -0.0813634 -0.0486773 -0.0643033 -0.0690107 -0.0367845 -0.0643033 -0.076351 -0.0686916 -0.0643033 -0.0496432 -0.0808028 -0.0643033 -0.0245634 -0.0810898 -0.0643033 -0.0246506 -0.0827564 -0.0643033 0.0168531 -0.0830504 -0.0643033 0.016913 -0.0788542 -0.0643033 0.0302438 -0.0728012 -0.0643033 0.0428095 -0.0649926 -0.0643033 0.0544001 -0.0178141 -0.0643033 0.082553 0.00995509 -0.0643033 0.0838628 -0.00399789 -0.0643033 0.0846581 0.0237062 -0.0643033 0.0813678 0.0593632 -0.0643033 0.0600626 0.0488408 -0.0643033 0.0692603 0.0684392 -0.0643033 0.0494718 0.0756481 -0.0643033 0.0375316 0.0810805 -0.0643033 0.024655 0.084392 -0.0643033 -0.00299839 0.0840323 -0.0643033 0.0109726 0.0846918 -0.0643033 -0.00300905 0.083041 -0.0643033 -0.0169086 0.0237062 -0.0458033 0.0813678 0.0100141 -0.0456033 0.0843593 -0.00400731 -0.0456033 0.0848578 -0.00399789 -0.0458033 0.0846581 -0.0439117 -0.0456033 0.0727255 -0.0552827 -0.0456033 0.0645068 -0.0551526 -0.0458033 0.0643549 -0.0730598 -0.0458033 0.0429616 -0.0732322 -0.0456033 0.043063 -0.0832464 -0.0456033 0.0169529 -0.0847012 -0.0458033 0.00301344 -0.084901 -0.0456033 0.00302054 -0.08424 -0.0456033 -0.0109941 -0.0810898 -0.0458033 -0.0246506 -0.0761054 -0.0456033 -0.0377494 -0.0759262 -0.0458033 -0.0376606 -0.0688537 -0.0456033 -0.0497603 -0.0595835 -0.0458033 -0.0602716 -0.0597241 -0.0456033 -0.0604138 -0.0489654 -0.0456033 -0.0694193 -0.0368713 -0.0456033 -0.0765312 -0.0237715 -0.0456033 -0.0815554 -0.0237155 -0.0468033 -0.0813634 -0.0368713 -0.0470033 -0.0765312 -0.0488502 -0.0468033 -0.0692559 -0.0597241 -0.0470033 -0.0604138 -0.0686916 -0.0468033 -0.0496432 -0.0761054 -0.0470033 -0.0377494 -0.0810898 -0.0468033 -0.0246506 -0.08424 -0.0470033 -0.0109941 -0.0847012 -0.0468033 0.00301344 -0.0791343 -0.0468033 0.0303512 -0.0649926 -0.0468033 0.0544001 -0.0552827 -0.0470033 0.0645068 -0.031343 -0.0470033 0.0789605 -0.0179195 -0.0470033 0.0830417 0.0100141 -0.0470033 0.0843593 0.0237621 -0.0470033 0.0815598 0.0237062 -0.0483033 0.0813678 0.0100141 -0.0481033 0.0843593 -0.00399789 -0.0483033 0.0846581 -0.0179195 -0.0481033 0.0830417 -0.031343 -0.0481033 0.0789605 -0.0312692 -0.0483033 0.0787746 -0.0439117 -0.0481033 0.0727255 -0.0552827 -0.0481033 0.0645068 -0.0438083 -0.0483033 0.0725543 -0.0651459 -0.0481033 0.0545285 -0.0732322 -0.0481033 0.043063 -0.0791343 -0.0483033 0.0303512 -0.079321 -0.0481033 0.0304228 -0.084901 -0.0481033 0.00302054 -0.08424 -0.0481033 -0.0109941 -0.0847012 -0.0483033 0.00301344 -0.0812812 -0.0481033 -0.0247088 -0.0759262 -0.0483033 -0.0376606 -0.0597241 -0.0481033 -0.0604138 -0.0686916 -0.0483033 -0.0496432 -0.0368713 -0.0481033 -0.0765312 -0.0367845 -0.0483033 -0.076351 -0.0237155 -0.0483033 -0.0813634 -0.0488502 -0.0493033 -0.0692559 -0.0688537 -0.0495033 -0.0497603 -0.0686916 -0.0493033 -0.0496432 -0.0761054 -0.0495033 -0.0377494 -0.0812812 -0.0495033 -0.0247088 -0.0759262 -0.0493033 -0.0376606 -0.0840416 -0.0493033 -0.0109682 -0.084901 -0.0495033 0.00302054 -0.0847012 -0.0493033 0.00301344 -0.0832464 -0.0495033 0.0169529 -0.0830504 -0.0493033 0.016913 -0.0791343 -0.0493033 0.0303512 -0.0552827 -0.0495033 0.0645068 -0.0438083 -0.0493033 0.0725543 -0.0179195 -0.0495033 0.0830417 -0.0178773 -0.0493033 0.0828462 -0.00400731 -0.0495033 0.0848578 -0.00399789 -0.0493033 0.0846581 0.0100141 -0.0495033 0.0843593 0.00999047 -0.0493033 0.0841607 0.0237621 -0.0506033 0.0815598 -0.00399789 -0.0508033 0.0846581 -0.00400731 -0.0506033 0.0848578 -0.0179195 -0.0506033 0.0830417 -0.0438083 -0.0508033 0.0725543 -0.0730598 -0.0508033 0.0429616 -0.0791343 -0.0508033 0.0303512 -0.0832464 -0.0506033 0.0169529 -0.084901 -0.0506033 0.00302054 -0.08424 -0.0506033 -0.0109941 -0.0810898 -0.0508033 -0.0246506 -0.0812812 -0.0506033 -0.0247088 -0.0759262 -0.0508033 -0.0376606 -0.0686916 -0.0508033 -0.0496432 -0.0597241 -0.0506033 -0.0604138 -0.0489654 -0.0506033 -0.0694193 -0.0595835 -0.0508033 -0.0602716 -0.0237715 -0.0506033 -0.0815554 -0.0368713 -0.0520033 -0.0765312 -0.0489654 -0.0520033 -0.0694193 -0.0686916 -0.0518033 -0.0496432 -0.0688537 -0.0520033 -0.0497603 -0.0759262 -0.0518033 -0.0376606 -0.0812812 -0.0520033 -0.0247088 -0.0840416 -0.0518033 -0.0109682 -0.0847012 -0.0518033 0.00301344 -0.084901 -0.0520033 0.00302054 -0.0830504 -0.0518033 0.016913 -0.0832464 -0.0520033 0.0169529 -0.0732322 -0.0520033 0.043063 -0.0730598 -0.0518033 0.0429616 -0.0649926 -0.0518033 0.0544001 -0.0651459 -0.0520033 0.0545285 -0.0552827 -0.0520033 0.0645068 -0.031343 -0.0520033 0.0789605 -0.0179195 -0.0520033 0.0830417 -0.0178773 -0.0518033 0.0828462 -0.00399789 -0.0518033 0.0846581 0.0100141 -0.0520033 0.0843593 0.0237621 -0.0531033 0.0815598 0.0100141 -0.0531033 0.0843593 0.00999047 -0.0533033 0.0841607 -0.00399789 -0.0533033 0.0846581 -0.00400731 -0.0531033 0.0848578 -0.0179195 -0.0531033 0.0830417 -0.0312692 -0.0533033 0.0787746 -0.0439117 -0.0531033 0.0727255 -0.0551526 -0.0533033 0.0643549 -0.0651459 -0.0531033 0.0545285 -0.0649926 -0.0533033 0.0544001 -0.0730598 -0.0533033 0.0429616 -0.079321 -0.0531033 0.0304228 -0.0791343 -0.0533033 0.0303512 -0.0832464 -0.0531033 0.0169529 -0.084901 -0.0531033 0.00302054 -0.0847012 -0.0533033 0.00301344 -0.08424 -0.0531033 -0.0109941 -0.0840416 -0.0533033 -0.0109682 -0.0761054 -0.0531033 -0.0377494 -0.0759262 -0.0533033 -0.0376606 -0.0686916 -0.0533033 -0.0496432 -0.0597241 -0.0531033 -0.0604138 -0.0488502 -0.0533033 -0.0692559 -0.0237715 -0.0531033 -0.0815554 -0.0367845 -0.0533033 -0.076351 -0.0237715 -0.0545033 -0.0815554 -0.0368713 -0.0545033 -0.0765312 -0.0367845 -0.0543033 -0.076351 -0.0488502 -0.0543033 -0.0692559 -0.0597241 -0.0545033 -0.0604138 -0.0759262 -0.0543033 -0.0376606 -0.0832464 -0.0545033 0.0169529 -0.0791343 -0.0543033 0.0303512 -0.0651459 -0.0545033 0.0545285 -0.0551526 -0.0543033 0.0643549 -0.0312692 -0.0543033 0.0787746 -0.00399789 -0.0543033 0.0846581 0.0100141 -0.0545033 0.0843593 0.00999047 -0.0543033 0.0841607 0.0237062 -0.0558033 0.0813678 -0.00400731 -0.0556033 0.0848578 -0.0312692 -0.0558033 0.0787746 -0.0439117 -0.0556033 0.0727255 -0.0552827 -0.0556033 0.0645068 -0.0649926 -0.0558033 0.0544001 -0.0732322 -0.0556033 0.043063 -0.079321 -0.0556033 0.0304228 -0.0832464 -0.0556033 0.0169529 -0.0791343 -0.0558033 0.0303512 -0.0759262 -0.0558033 -0.0376606 -0.0688537 -0.0556033 -0.0497603 -0.0597241 -0.0556033 -0.0604138 -0.0368713 -0.0556033 -0.0765312 -0.0489654 -0.0570033 -0.0694193 -0.0367845 -0.0568033 -0.076351 -0.0595835 -0.0568033 -0.0602716 -0.0688537 -0.0570033 -0.0497603 -0.0686916 -0.0568033 -0.0496432 -0.0812812 -0.0570033 -0.0247088 -0.0810898 -0.0568033 -0.0246506 -0.08424 -0.0570033 -0.0109941 -0.0847012 -0.0568033 0.00301344 -0.0830504 -0.0568033 0.016913 -0.079321 -0.0570033 0.0304228 -0.0791343 -0.0568033 0.0303512 -0.0730598 -0.0568033 0.0429616 -0.0651459 -0.0570033 0.0545285 -0.0649926 -0.0568033 0.0544001 -0.0552827 -0.0570033 0.0645068 -0.0551526 -0.0568033 0.0643549 -0.0438083 -0.0568033 0.0725543 -0.0312692 -0.0568033 0.0787746 -0.00400731 -0.0570033 0.0848578 -0.00399789 -0.0568033 0.0846581 0.00999047 -0.0568033 0.0841607 0.0100141 -0.0570033 0.0843593 0.0237062 -0.0583033 0.0813678 0.0100141 -0.0581033 0.0843593 -0.00400731 -0.0581033 0.0848578 -0.0179195 -0.0581033 0.0830417 -0.0178773 -0.0583033 0.0828462 -0.031343 -0.0581033 0.0789605 -0.0312692 -0.0583033 0.0787746 -0.0438083 -0.0583033 0.0725543 -0.0552827 -0.0581033 0.0645068 -0.0651459 -0.0581033 0.0545285 -0.0649926 -0.0583033 0.0544001 -0.0732322 -0.0581033 0.043063 -0.079321 -0.0581033 0.0304228 -0.0791343 -0.0583033 0.0303512 -0.0832464 -0.0581033 0.0169529 -0.0830504 -0.0583033 0.016913 -0.0847012 -0.0583033 0.00301344 -0.08424 -0.0581033 -0.0109941 -0.0812812 -0.0581033 -0.0247088 -0.0595835 -0.0583033 -0.0602716 -0.0488502 -0.0583033 -0.0692559 -0.0237715 -0.0581033 -0.0815554 -0.0367845 -0.0593033 -0.076351 -0.0759262 -0.0593033 -0.0376606 -0.08424 -0.0595033 -0.0109941 -0.0847012 -0.0593033 0.00301344 -0.0730598 -0.0593033 0.0429616 -0.0651459 -0.0595033 0.0545285 -0.0649926 -0.0593033 0.0544001 -0.0551526 -0.0593033 0.0643549 -0.0439117 -0.0595033 0.0727255 -0.031343 -0.0595033 0.0789605 -0.0178773 -0.0593033 0.0828462 -0.00399789 -0.0593033 0.0846581 -0.00400731 -0.0595033 0.0848578 0.0100141 -0.0606033 0.0843593 -0.0312692 -0.0608033 0.0787746 -0.0552827 -0.0606033 0.0645068 -0.0438083 -0.0608033 0.0725543 -0.0649926 -0.0608033 0.0544001 -0.0732322 -0.0606033 0.043063 -0.0847012 -0.0608033 0.00301344 -0.0761054 -0.0606033 -0.0377494 -0.0759262 -0.0608033 -0.0376606 -0.0688537 -0.0606033 -0.0497603 -0.0595835 -0.0608033 -0.0602716 -0.0489654 -0.0606033 -0.0694193 -0.0488502 -0.0608033 -0.0692559 -0.0367845 -0.0608033 -0.076351 -0.0237155 -0.0608033 -0.0813634 -0.0489654 -0.0620033 -0.0694193 -0.0759262 -0.0618033 -0.0376606 -0.0812812 -0.0620033 -0.0247088 -0.0810898 -0.0618033 -0.0246506 -0.0840416 -0.0618033 -0.0109682 -0.084901 -0.0620033 0.00302054 -0.0832464 -0.0620033 0.0169529 -0.0830504 -0.0618033 0.016913 -0.0791343 -0.0618033 0.0303512 -0.0439117 -0.0620033 0.0727255 -0.0438083 -0.0618033 0.0725543 -0.0312692 -0.0618033 0.0787746 -0.00400731 -0.0620033 0.0848578 0.0100141 -0.0620033 0.0843593 -0.00399789 -0.0618033 0.0846581 0.0237621 -0.0631033 0.0815598 0.00999047 -0.0633033 0.0841607 -0.00399789 -0.0633033 0.0846581 -0.0179195 -0.0631033 0.0830417 -0.0178773 -0.0633033 0.0828462 -0.031343 -0.0631033 0.0789605 -0.0551526 -0.0633033 0.0643549 -0.0651459 -0.0631033 0.0545285 -0.0732322 -0.0631033 0.043063 -0.0847012 -0.0633033 0.00301344 -0.084901 -0.0631033 0.00302054 -0.08424 -0.0631033 -0.0109941 -0.0840416 -0.0633033 -0.0109682 -0.0812812 -0.0631033 -0.0247088 -0.0761054 -0.0631033 -0.0377494 -0.0759262 -0.0633033 -0.0376606 -0.0686916 -0.0633033 -0.0496432 -0.0597241 -0.0631033 -0.0604138 -0.0489654 -0.0631033 -0.0694193 -0.0488502 -0.0633033 -0.0692559 -0.0489654 -0.0645033 -0.0694193 -0.0488502 -0.0643033 -0.0692559 -0.0597241 -0.0645033 -0.0604138 -0.0595835 -0.0643033 -0.0602716 -0.0761054 -0.0645033 -0.0377494 -0.0759262 -0.0643033 -0.0376606 -0.0812812 -0.0645033 -0.0247088 -0.0840416 -0.0643033 -0.0109682 -0.0847012 -0.0643033 0.00301344 -0.0791343 -0.0643033 0.0303512 -0.0730598 -0.0643033 0.0429616 -0.0551526 -0.0643033 0.0643549 -0.0438083 -0.0643033 0.0725543 -0.0312692 -0.0643033 0.0787746 -0.0179195 -0.0645033 0.0830417 -0.0178773 -0.0643033 0.0828462 -0.00400731 -0.0645033 0.0848578 0.00999047 -0.0643033 0.0841607 0.0237621 -0.0645033 0.0815598 -0.0411159 -0.0690116 0.00547265 -0.0506417 -0.0707283 0.0062096 -0.0417291 -0.0712035 0.00336834 -0.0507072 -0.0745032 0.00598465 -0.0416636 -0.0749783 0.00359329 -0.050094 -0.076695 0.00808896 -0.0502269 -0.0764607 0.0076328 -0.0412488 -0.0764607 0.00501649 -0.0374859 -0.0764607 0.0179294 -0.0370711 -0.0749783 0.0193526 -0.0460492 -0.0749783 0.0219689 -0.0369193 -0.0727533 0.0198735 -0.0372512 -0.0698895 0.0187347 -0.046464 -0.0692459 0.0205457 -0.0376188 -0.0690116 0.0174732 0.0390032 -0.0687033 -0.0162606 0.0465875 -0.0690116 -0.0200851 0.0384366 -0.0692459 -0.0182048 0.0380219 -0.0707283 -0.019628 0.0460399 -0.0707283 -0.0219645 0.0459743 -0.0712035 -0.0221895 0.0378701 -0.0727533 -0.0201489 0.0458881 -0.0727533 -0.0224854 0.0458881 -0.0729533 -0.0224854 0.0460399 -0.0749783 -0.0219645 0.0464546 -0.0764607 -0.0205413 0.0502176 -0.0764607 -0.00762841 0.0426143 -0.0749783 -0.00386867 0.0506323 -0.0749783 -0.00620521 0.0426143 -0.0707283 -0.00386867 0.0421996 -0.0692459 -0.00529187 0.049651 -0.0687033 -0.00957255 -0.00400731 -0.0671033 0.0848578 -0.0311997 -0.0676033 0.0784794 -0.031343 -0.0671033 0.0789605 -0.0552827 -0.0671033 0.0645068 -0.0651459 -0.0671033 0.0545285 -0.057814 -0.0676033 0.0615642 -0.0549574 -0.0676033 0.0641271 -0.0647625 -0.0676033 0.0542076 -0.0708185 -0.0676033 0.0460152 -0.0827564 -0.0676033 0.0168531 -0.079321 -0.0671033 0.0304228 -0.0726913 -0.0676033 0.0429958 -0.08424 -0.0671033 -0.0109941 -0.0757533 -0.0676033 -0.0373333 -0.0772604 -0.0676033 -0.0341057 -0.0812812 -0.0671033 -0.0247088 -0.0808028 -0.0676033 -0.0245634 -0.0695098 -0.0676033 -0.0479649 -0.0723176 -0.0676033 -0.0436171 -0.0688537 -0.0671033 -0.0497603 -0.0761054 -0.0671033 -0.0377494 -0.0597241 -0.0671033 -0.0604138 -0.0548931 -0.0676033 -0.0641778 -0.0684485 -0.0676033 -0.0494674 -0.0486773 -0.0676033 -0.0690107 -0.0368713 -0.0671033 -0.0765312 -0.0368713 -0.0415033 -0.0765312 -0.0367845 -0.0413033 -0.076351 -0.0489654 -0.0415033 -0.0694193 -0.0488502 -0.0413033 -0.0692559 -0.0595835 -0.0413033 -0.0602716 -0.0761054 -0.0415033 -0.0377494 -0.0810898 -0.0413033 -0.0246506 -0.08424 -0.0415033 -0.0109941 -0.084901 -0.0415033 0.00302054 -0.0832464 -0.0415033 0.0169529 -0.0830504 -0.0413033 0.016913 -0.0732322 -0.0415033 0.043063 -0.0551526 -0.0413033 0.0643549 -0.00399789 -0.0413033 0.0846581 -0.00400731 -0.0415033 0.0848578 0.0237621 -0.0415033 0.0815598 0.049651 -0.0770033 -0.00957255 0.0523604 -0.0752783 -0.00616755 0.0473029 -0.0729533 -0.0235227 0.0459743 -0.0745032 -0.0221895 0.0470212 -0.0770033 -0.0185972 0.0465875 -0.076695 -0.0200851 0.048106 -0.0772494 -0.0207668 0.04622 -0.0758171 -0.0213466 0.0525346 -0.0727533 -0.00556944 0.0507841 -0.0729533 -0.00568428 0.0512337 -0.0681033 -0.0100337 0.0518842 -0.0687263 -0.0078016 0.0502176 -0.0692459 -0.00762841 0.0506323 -0.0707283 -0.00620521 0.048106 -0.0684573 -0.0207668 0.0464546 -0.0692459 -0.0205413 0.0476839 -0.0694653 -0.0222151 0.04622 -0.0698895 -0.0213466 0.0486038 -0.0681033 -0.0190584 -0.0496604 -0.0687033 0.00957694 -0.051243 -0.0681033 0.0100381 -0.0479627 -0.0687263 0.0212949 -0.0470305 -0.0687033 0.0186016 -0.0460492 -0.0707283 0.0219689 -0.0462293 -0.0698895 0.021351 -0.0507935 -0.0727533 0.00568867 -0.0502269 -0.0692459 0.0076328 -0.0518935 -0.0687263 0.00780599 -0.0504616 -0.0698895 0.00682752 -0.0458974 -0.0729533 0.0224898 -0.052544 -0.0729533 0.00557384 -0.0507935 -0.0729533 0.00568867 -0.052544 -0.0727533 0.00557384 -0.046464 -0.0764607 0.0205457 -0.0479627 -0.0769803 0.0212949 -0.0496604 -0.0770033 0.00957694 -0.0517409 -0.0772494 0.00832973 -0.0506417 -0.0749783 0.0062096 -0.0504616 -0.0758171 0.00682752 -0.051243 -0.0776033 0.0100381 -0.0525006 -0.0806033 -0.000649002 -0.0540005 -0.0791033 -0.000667607 -0.0482646 -0.0806033 -0.0206674 -0.0433114 -0.0806033 -0.0296757 -0.0377461 -0.0791033 -0.0386189 -0.0286771 -0.0806033 -0.0439767 -0.0294963 -0.0791033 -0.0452332 -0.0201157 -0.0791033 -0.0501131 -0.0195571 -0.0806033 -0.048721 -0.00968739 -0.0806033 -0.0515972 -0.00996404 -0.0791033 -0.0530714 0.000569531 -0.0791033 -0.0539948 0.0110811 -0.0791033 -0.0528476 0.0304423 -0.0791033 -0.0445958 0.0385495 -0.0791033 -0.0378075 0.0439234 -0.0806033 -0.0287481 0.0539912 -0.0791033 0.000671999 0.0524913 -0.0806033 0.000653394 0.0529769 -0.0791033 0.0104403 0.0515052 -0.0806033 0.0101504 0.0445107 -0.0806033 0.0278344 0.0387338 -0.0806033 0.0354364 0.0398406 -0.0791033 0.0364488 0.0242429 -0.0791033 0.0482521 0.0792968 -0.0666033 -0.0231071 0.077251 -0.0666033 -0.0242296 0.0788958 -0.0666033 0.0176198 0.079086 -0.0666033 0.0208315 0.0782321 -0.0666033 0.0208501 0.0797276 -0.0666033 0.0204743 0.080066 -0.0666033 0.0184448 0.0774833 -0.0666033 0.0204392 0.0774325 -0.0666033 0.0181063 0.0600516 -0.0666033 0.0555219 0.0568204 -0.0666033 0.0560811 0.0588598 -0.0666033 0.0543808 0.0580059 -0.0666033 0.0543994 0.0573643 -0.0666033 0.0547566 0.0569412 -0.0666033 0.0553568 0.0181373 -0.0666033 -0.0798538 0.0177988 -0.0666033 -0.0778243 0.0175934 -0.0666033 -0.0785293 0.0203816 -0.0666033 -0.0798187 0.0196328 -0.0666033 -0.0802295 0.0204323 -0.0666033 -0.0774858 0.0543295 -0.0666033 -0.0583724 0.055026 -0.0666033 -0.0571214 0.054535 -0.0666033 -0.0576674 0.0575608 -0.0666033 -0.0589316 -0.0600795 -0.0666033 -0.0563714 -0.0588691 -0.0666033 -0.0543764 -0.057285 -0.0666033 -0.0548381 -0.0580846 -0.0666033 -0.0575818 -0.0568927 -0.0666033 -0.0564408 -0.0802808 -0.0666033 -0.0191454 -0.0790953 -0.0666033 -0.0208271 -0.08016 -0.0666033 -0.0198697 -0.0774419 -0.0666033 -0.0181019 -0.0781721 -0.0666033 -0.0176589 -0.0793691 -0.0666033 0.0227475 -0.0761193 -0.0666033 0.0230422 -0.0765302 -0.0666033 0.023791 -0.0765809 -0.0666033 0.0214581 -0.0781836 -0.0666033 0.0210658 -0.0792483 -0.0666033 0.0220232 -0.0779934 -0.0666033 0.0242774 -0.0575123 -0.0666033 0.0578476 -0.0547942 -0.0666033 0.0596154 -0.0562574 -0.0666033 0.0601019 -0.0544019 -0.0666033 0.0580127 -0.0574277 -0.0666033 0.0592769 -0.0576331 -0.0666033 0.0585719 -0.0548449 -0.0666033 0.0572825 -0.0564476 -0.0666033 0.0568902 -0.0189784 -0.0666033 0.0770037 -0.0208339 -0.0666033 0.0790929 -0.0187882 -0.0666033 0.0802153 -0.0208525 -0.0666033 0.078239 -0.0181466 -0.0666033 0.0798582 0.0378701 -0.0729533 -0.0201489 0.0427661 -0.0727533 -0.00334774 0.0421996 -0.0764607 -0.00529187 0.0427661 -0.0729533 -0.00334774 0.041633 -0.0770033 -0.00723601 0.0390032 -0.0770033 -0.0162606 0.0380219 -0.0749783 -0.019628 0.0384366 -0.0764607 -0.0182048 -0.0418154 -0.0729533 0.00307236 -0.0380524 -0.0687033 0.0159852 -0.0370056 -0.0712035 0.0195775 -0.0380524 -0.0770033 0.0159852 -0.0414835 -0.0698895 0.00421121 -0.0406823 -0.0770033 0.00696063 -0.0418154 -0.0727533 0.00307236 0.00499916 -0.0289033 0.0572339 0.00499916 -0.0293033 0.0572339 -0.0172833 -0.0289033 0.0547922 -0.00626233 -0.0293033 0.0571104 -0.0369353 -0.0293033 0.0440093 -0.050965 -0.0289033 0.0265267 -0.0572363 -0.0289033 0.00500602 -0.0551604 -0.0293033 0.0160752 -0.0547947 -0.0289033 -0.0172765 -0.050371 -0.0293033 -0.0276335 -0.0440118 -0.0293033 -0.0369285 -0.0440118 -0.0289033 -0.0369285 -0.0359614 -0.0293033 -0.0448042 -0.0265292 -0.0289033 -0.0509581 -0.0160777 -0.0289033 -0.0551536 -0.0160777 -0.0293033 -0.0551536 -0.0156161 -0.0260033 -0.0535695 -0.0164694 -0.0282033 -0.0564977 -0.0368376 -0.0282033 -0.0458961 -0.0427479 -0.0260033 -0.0358678 -0.0515984 -0.0282033 -0.0283069 -0.0532211 -0.0260033 -0.0167802 -0.058631 -0.0282033 0.00512796 -0.0535763 -0.0260033 0.0156136 -0.0495013 -0.0260033 0.0257649 -0.045903 -0.0282033 0.0368352 -0.0358747 -0.0260033 0.0427454 -0.0378353 -0.0282033 0.0450817 -0.0268466 -0.0260033 0.048922 -0.00641483 -0.0282033 0.058502 -0.00608261 -0.0260033 0.0554702 0.00485545 -0.0260033 0.0555901 0.0051211 -0.0282033 0.0586285 0.0051211 -0.0287033 0.0586285 -0.00641483 -0.0287033 0.058502 -0.0177044 -0.0282033 0.0561274 -0.0177044 -0.0287033 0.0561274 -0.0283138 -0.0282033 0.0515959 -0.0522068 -0.0287033 0.0271731 -0.0522068 -0.0282033 0.0271731 -0.0565045 -0.0282033 0.0164669 -0.058631 -0.0287033 0.00512796 -0.0585045 -0.0282033 -0.00640796 -0.0585045 -0.0287033 -0.00640796 -0.0561299 -0.0282033 -0.0176975 -0.0450842 -0.0287033 -0.0378284 -0.0450842 -0.0282033 -0.0378284 -0.0271756 -0.0287033 -0.0521999 -0.0271756 -0.0282033 -0.0521999 0.0571035 -0.0289033 0.00625986 0.0514137 -0.0289033 0.0282151 0.0440025 -0.0289033 0.0369329 0.0160684 -0.0289033 0.055158 0.0164041 -0.0289033 0.0563101 -0.00626233 -0.0289033 0.0571104 -0.0276404 -0.0289033 0.0503686 -0.0176443 -0.0289033 0.0559367 -0.0369353 -0.0289033 0.0440093 -0.0448111 -0.0289033 0.0359589 -0.045747 -0.0289033 0.03671 -0.0563125 -0.0289033 0.0164109 -0.0551604 -0.0289033 0.0160752 -0.0584318 -0.0289033 0.00511054 -0.0571128 -0.0289033 -0.00625547 -0.0583057 -0.0289033 -0.00638618 -0.0559392 -0.0289033 -0.0176374 -0.050371 -0.0289033 -0.0276335 -0.044931 -0.0289033 -0.0376999 -0.0359614 -0.0289033 -0.0448042 -0.00500849 -0.0289033 -0.0572295 0.006253 -0.0289033 -0.057106 0.017274 -0.0289033 -0.0547879 0.00638371 -0.0289033 -0.0582988 0.0176349 -0.0289033 -0.0559323 0.0376974 -0.0289033 -0.0449242 0.0448018 -0.0289033 -0.0359545 0.0563032 -0.0289033 -0.0164066 0.057227 -0.0289033 -0.00500163 0.0582964 -0.0289033 0.00639057 0.00510368 -0.0289033 0.0584293 -0.00639304 -0.0289033 0.0583032 -0.0283138 -0.0287033 0.0515959 -0.0282176 -0.0289033 0.0514206 -0.0377067 -0.0289033 0.0449285 -0.0378353 -0.0287033 0.0450817 -0.045903 -0.0287033 0.0368352 -0.0520294 -0.0289033 0.0270808 -0.0565045 -0.0287033 0.0164669 -0.0561299 -0.0287033 -0.0176975 -0.0515984 -0.0287033 -0.0283069 -0.0514231 -0.0289033 -0.0282107 -0.0367125 -0.0289033 -0.0457401 -0.0368376 -0.0287033 -0.0458961 -0.0270832 -0.0289033 -0.0520225 -0.0164694 -0.0287033 -0.0564977 0.0241946 -0.0260033 -0.0343256 0.0167778 -0.0260033 -0.0532143 -0.00248791 -0.0260033 -0.0419243 -0.0117552 -0.0260033 -0.0403206 -0.0257674 -0.0260033 -0.0494945 -0.0280869 -0.0260033 -0.031229 -0.0349287 -0.0260033 -0.0435174 0.0414232 -0.0260033 0.00691074 0.0403181 -0.0260033 -0.0117483 0.0366924 -0.0260033 -0.0204264 0.0312265 -0.0260033 -0.02808 0.0268373 -0.0260033 -0.0489176 -0.0167871 -0.0260033 0.0532186 0.00247858 -0.0260033 0.0419287 0.0117458 -0.0260033 0.040325 0.0257581 -0.0260033 0.0494989 0.0349194 -0.0260033 0.0435217 0.0343231 -0.0260033 0.0242015 -0.0489245 -0.0260033 -0.0268398 -0.0554727 -0.0260033 -0.00607575 -0.0419312 -0.0260033 0.00248544 -0.0555926 -0.0260033 0.00486231 -0.0312359 -0.0260033 0.0280844 -0.0435242 -0.0260033 0.0349262 -0.0242039 -0.0260033 0.03433 0.00735021 -0.0265033 0.0081818 -0.00308218 -0.0265033 -0.0105585 -0.0109854 -0.0265033 0.00065257 -0.0096158 -0.0265033 0.00535253 0.0360922 -0.0255033 0.00303294 0.0374944 -0.0257033 0.00202918 0.038456 -0.0257033 0.000665132 0.038641 -0.0255033 0.000741103 0.0389301 -0.0255033 -0.000992868 0.0384383 -0.0255033 -0.00268058 0.0371477 -0.0257033 -0.0038243 0.0356039 -0.0257033 -0.00445825 0.0372629 -0.0255033 -0.00398777 0.0356368 -0.0255033 -0.00465552 0.0317849 -0.0255033 0.0206308 0.0333209 -0.0255033 0.0197758 0.0344232 -0.0257033 0.0166168 0.0341311 -0.0255033 0.0149173 0.0328405 -0.0257033 0.0137736 0.0207918 -0.0255033 0.0328624 0.0216196 -0.0257033 0.0313496 0.0220938 -0.0255033 0.0296916 0.0218941 -0.0257033 0.0297034 0.0214272 -0.0257033 0.0281012 0.0188004 -0.0255033 0.026029 -0.000292299 -0.0257033 0.0313937 0.00164838 -0.0257033 0.0313514 0.00303274 -0.0255033 0.0317655 0.00403338 -0.0257033 0.0331699 0.00450029 -0.0257033 0.0347722 0.00469994 -0.0255033 0.0347604 0.00441079 -0.0255033 0.0364943 0.00339792 -0.0255033 0.0379311 0.0032642 -0.0257033 0.0377824 0.00346557 -0.0257033 0.0375872 -0.0143337 -0.0257033 0.0334752 -0.0133721 -0.0257033 0.0321111 -0.0131871 -0.0255033 0.0321871 -0.0130976 -0.0257033 0.030465 -0.0133898 -0.0255033 0.0287654 -0.0146804 -0.0257033 0.0276217 -0.0145651 -0.0255033 0.0274582 -0.0292779 -0.0255033 0.0142614 -0.0293108 -0.0257033 0.0144586 -0.027767 -0.0257033 0.0150926 -0.0266511 -0.0257033 0.0163336 -0.0264763 -0.0255033 0.0162363 -0.0263274 -0.0257033 0.0171084 -0.0259845 -0.0255033 0.017924 -0.0262737 -0.0255033 0.019658 -0.0262851 -0.0257033 0.0190491 -0.0274203 -0.0257033 0.0209461 -0.0272866 -0.0255033 0.0210948 -0.0338913 -0.0255033 0.00455598 -0.0321432 -0.0255033 0.00349536 -0.0311596 -0.0255033 0.0017028 -0.0313961 -0.0257033 -0.000285436 -0.0312041 -0.0255033 -0.000341391 -0.0322647 -0.0255033 -0.00208946 -0.0341049 -0.0257033 -0.00287877 -0.0360455 -0.0257033 -0.00283653 -0.0340573 -0.0255033 -0.00307303 -0.0279804 -0.0257033 -0.0142408 -0.0270467 -0.0257033 -0.0159426 -0.027836 -0.0255033 -0.0141025 -0.0270889 -0.0257033 -0.0178833 -0.0268969 -0.0255033 -0.0179393 -0.0280958 -0.0257033 -0.0195429 -0.0297501 -0.0255033 -0.0206709 -0.0170549 -0.0255033 -0.0261285 -0.0154513 -0.0257033 -0.0273274 -0.0153068 -0.0255033 -0.0271891 -0.0143233 -0.0255033 -0.0289817 -0.0143678 -0.0255033 -0.0310259 -0.0155667 -0.0257033 -0.0326295 -0.0172685 -0.0257033 -0.0335632 -0.0154284 -0.0255033 -0.0327739 -0.0192651 -0.0255033 -0.033713 0.00194253 -0.0257033 -0.0323962 0.00208699 -0.0255033 -0.0322579 0.00283406 -0.0257033 -0.0360387 0.00307056 -0.0255033 -0.0340504 0.00302607 -0.0255033 -0.0360946 0.00182714 -0.0257033 -0.0376982 0.00196545 -0.0255033 -0.0378427 0.000172891 -0.0255033 -0.0388263 0.000125343 -0.0257033 -0.038632 0.0179368 -0.0255033 -0.02689 0.0196849 -0.0255033 -0.0279506 0.0206684 -0.0255033 -0.0297432 0.0204319 -0.0257033 -0.0317314 0.019425 -0.0257033 -0.033391 0.0177232 -0.0257033 -0.0343248 0.0157825 -0.0257033 -0.0342825 0.0177708 -0.0255033 -0.034519 0.0310234 -0.0255033 -0.0143609 0.0327715 -0.0255033 -0.0154215 0.0335608 -0.0257033 -0.0172616 0.0335185 -0.0257033 -0.0192023 0.0337105 -0.0255033 -0.0192583 0.0326499 -0.0255033 -0.0210063 0.0325116 -0.0257033 -0.0208619 0.00641208 -0.0258033 0.014462 0.00611625 -0.0255033 0.0145119 0.00746717 -0.0258033 0.0188161 0.00718133 -0.0255033 0.0189072 0.0104151 -0.0258033 0.0245601 0.0102329 -0.0255033 0.0247984 0.0257034 -0.0255033 0.014471 0.0262871 -0.0255033 0.0126039 0.0257759 -0.0258033 0.010757 0.0248413 -0.0258033 0.00918205 0.0233466 -0.0258033 0.00812402 0.0147206 -0.0258033 0.00578379 0.0134433 -0.0255033 0.00557263 0.0113584 -0.0255033 0.00710437 0.0113472 -0.0255033 0.00712231 0.00829949 -0.0255033 0.0105189 0.00665943 -0.0255033 0.0119824 0.00614555 -0.0255033 0.0131951 -0.00950997 -0.0255033 0.0125579 -0.0125621 -0.0258033 0.0158799 -0.0155853 -0.0255033 0.0192282 -0.0163249 -0.0255033 0.0210392 -0.0159719 -0.0258033 0.0229227 -0.0162632 -0.0255033 0.0229944 -0.0151739 -0.0258033 0.0245711 -0.0154109 -0.0255033 0.0247551 -0.0137741 -0.0258033 0.0257518 0.000319058 -0.0255033 0.0295004 -0.00518157 -0.0255033 0.0290444 -0.00694672 -0.0258033 0.028365 0.00463726 -0.0258033 0.0242859 0.0049352 -0.0255033 0.0242508 0.00235097 -0.0258033 0.0156455 0.00262728 -0.0255033 0.0155286 0.00168164 -0.0258033 0.0146444 -0.000484297 -0.0258033 0.0136938 -0.000473794 -0.0255033 0.013394 -0.00577357 -0.0255033 0.0120968 -0.00826286 -0.0258033 0.0122104 -0.00835497 -0.0255033 0.0119249 -0.0200339 -0.0258033 -0.00293395 -0.0156309 -0.0255033 -0.00195178 -0.0244673 -0.0258033 -0.00357887 -0.0199698 -0.0255033 -0.00322703 -0.0244452 -0.0255033 -0.00387805 -0.0263834 -0.0255033 -0.00361306 -0.0262818 -0.0258033 -0.00333079 -0.029489 -0.0255033 0.000962103 -0.0283266 -0.0255033 0.00825553 -0.0239842 -0.0255033 0.016526 -0.0238157 -0.0258033 0.0162778 -0.0153211 -0.0258033 0.0132385 -0.0185346 -0.0255033 0.0164045 -0.0118421 -0.0258033 0.00878369 -0.0118369 -0.0255033 0.00629181 -0.0136624 -0.0258033 0.00107703 -0.0133634 -0.0255033 0.00105349 -0.0139811 -0.0258033 -8.42358e-05 -0.0137382 -0.0255033 -0.0257164 -0.0117872 -0.0255033 -0.0255742 -0.0102568 -0.0258033 -0.0244209 -0.0122893 -0.0258033 -0.0253856 -0.0210965 -0.0258033 -0.0201912 -0.0155782 -0.0255033 -0.0250521 -0.0254513 -0.0258033 -0.0143194 -0.0257127 -0.0255033 -0.0144666 -0.0262964 -0.0255033 -0.0125995 -0.0260694 -0.0255033 -0.0106565 -0.0248507 -0.0258033 -0.00917766 -0.0250712 -0.0255033 -0.00897423 -0.0192044 -0.0255033 -0.00635453 -0.00759446 -0.0255033 -0.0110411 -0.0113677 -0.0255033 -0.00709997 -0.00691803 -0.0258033 -0.012145 0.00950063 -0.0255033 -0.0125535 0.0160203 -0.0258033 -0.0210879 0.0163156 -0.0255033 -0.0210348 0.0159625 -0.0258033 -0.0229183 0.0162539 -0.0255033 -0.02299 0.0137648 -0.0258033 -0.0257474 0.0139062 -0.0255033 -0.026012 0.00693738 -0.0258033 -0.0283606 0.0070087 -0.0255033 -0.028652 -0.00476411 -0.0255033 -0.0261942 -0.00464659 -0.0258033 -0.0242815 -0.00447768 -0.0258033 -0.026105 -0.00358106 -0.0258033 -0.0277018 -0.00380635 -0.0255033 -0.0278999 -0.00328159 -0.0258033 -0.0280106 -0.00150782 -0.0258033 -0.0290206 -0.00409942 -0.0255033 -0.0198036 -0.00263661 -0.0255033 -0.0155242 -0.00190453 -0.0255033 -0.0144293 0.00698871 -0.0255033 -0.0117629 0.00816631 -0.0258033 -0.0121793 0.0200246 -0.0258033 0.00293834 0.0244359 -0.0255033 0.00388245 0.024458 -0.0258033 0.00358326 0.0260971 -0.0255033 0.00370753 0.0294797 -0.0255033 -0.000957711 0.0185253 -0.0255033 -0.0164001 0.0251215 -0.0258033 -0.0148744 0.0240546 -0.0255033 -0.0164663 0.0221995 -0.0258033 -0.0169471 0.0222584 -0.0255033 -0.0172412 0.0201044 -0.0258033 -0.016857 0.0187047 -0.0258033 -0.0161597 0.0121256 -0.0255033 -0.0100403 0.0118327 -0.0258033 -0.0087793 0.0115435 -0.0255033 -0.0088589 0.0136531 -0.0258033 -0.00107264 0.013354 -0.0255033 -0.0010491 0.0137026 -0.0255033 0.000221033 0.0146971 -0.0258033 0.00104989 0.0157263 -0.0258033 0.00167504 0.0156216 -0.0255033 0.00195617 0.0268297 -0.0281533 0.0256934 0.027365 -0.0281533 0.0247177 0.0273408 -0.0281533 0.0236051 0.0345933 -0.0281533 0.0103873 0.0355448 -0.0281533 0.00980999 0.037459 -0.0255033 0.0116426 0.0360802 -0.0281533 0.00883429 0.0386542 -0.0255033 0.0094643 0.0386001 -0.0255033 0.00698023 0.035133 -0.0255033 0.00366077 0.035686 -0.0281533 -0.00927875 0.03826 -0.0255033 -0.00864874 0.0369171 -0.0255033 -0.0132571 0.0347388 -0.0255033 -0.0144523 0.0329961 -0.0281533 -0.011854 0.00975383 -0.0281533 -0.0323956 0.0115257 -0.0255033 -0.030425 0.0103051 -0.0281533 -0.0331776 0.0127565 -0.0255033 -0.032171 0.0104625 -0.0281533 -0.0341214 0.0131079 -0.0255033 -0.0342781 0.0125102 -0.0255033 -0.036329 0.00955506 -0.0281533 -0.0357516 0.0110819 -0.0255033 -0.0379175 0.00771477 -0.0281533 -0.0360584 -0.0063296 -0.0255033 -0.0302806 -0.00770841 -0.0281533 -0.033089 -0.00513438 -0.0255033 -0.0324589 -0.00518845 -0.0255033 -0.034943 -0.00830992 -0.0281533 -0.0351531 -0.0064773 -0.0255033 -0.0370673 -0.0103983 -0.0281533 -0.0356642 -0.0086556 -0.0255033 -0.0382625 -0.0241449 -0.0255033 -0.0288646 -0.0237992 -0.0281533 -0.0257552 -0.0206777 -0.0255033 -0.0255451 -0.0232219 -0.0281533 -0.0248037 -0.0239431 -0.0255033 -0.0195939 -0.0218189 -0.0255033 -0.0208827 -0.0232972 -0.0281533 -0.0233855 -0.0322641 -0.0255033 0.0144026 -0.032054 -0.0281533 0.0112811 -0.0289446 -0.0255033 0.0109354 -0.0289987 -0.0255033 0.00845138 -0.0228662 -0.0255033 0.0298919 -0.0195467 -0.0255033 0.0264247 -0.0221449 -0.0281533 0.024682 -0.0196008 -0.0255033 0.0239406 -0.0208896 -0.0255033 0.0218164 -0.025552 -0.0255033 0.0206752 0.0114392 -0.0255033 -0.00754595 -0.0115528 -0.0255033 0.00886329 -0.0069827 -0.0255033 0.038607 -0.0139156 -0.0255033 0.0260164 -0.00701804 -0.0255033 0.0286564 -0.0128979 -0.0255033 0.0304531 -0.0161913 -0.0255033 0.0267905 -0.0142 -0.0255033 0.0336239 -0.00686387 -0.0255033 0.0411342 -0.00485846 -0.0255033 0.0373182 -0.00151825 -0.0255033 0.0416747 -0.0037173 -0.0255033 0.0326558 -0.00500616 -0.0255033 0.0305315 -0.00209633 -0.0255033 0.0322623 0.00158242 -0.0255033 0.029313 -0.000348254 -0.0255033 0.0312017 0.00347712 -0.0255033 0.0282341 0.000810298 -0.0255033 0.0136869 0.0018952 -0.0255033 0.0144337 0.00409009 -0.0255033 0.019808 0.00140659 -0.0255033 0.0310977 0.00420812 -0.0255033 0.0330727 0.00246084 -0.0255033 0.0416292 -0.0298843 -0.0255033 0.00354904 -0.0271121 -0.0255033 0.013062 -0.0301398 -0.0255033 0.0131138 -0.0363726 -0.0255033 0.0137175 -0.0405134 -0.0255033 0.00664651 -0.0383986 -0.0255033 0.0100781 -0.0349499 -0.0255033 0.00518597 -0.0324658 -0.0255033 0.00513191 -0.0302875 -0.0255033 0.00632713 0.00370797 -0.0255033 -0.0326514 0.00697337 -0.0255033 -0.0386026 0.00910583 -0.0255033 -0.0387289 0.0353347 -0.0255033 0.0129315 0.0385698 -0.0255033 0.0158422 0.0312284 -0.0255033 0.00317051 0.0320327 -0.0255033 0.00394114 0.0317846 -0.0255033 0.00300843 0.0323684 -0.0255033 0.00380601 0.0326489 -0.0255033 0.00371483 0.0292002 -0.0255033 0.00860695 0.0312262 -0.0255033 0.0122463 0.0313295 -0.0255033 0.0129424 0.0332023 -0.0255033 0.0130578 0.0295516 -0.0255033 0.00649984 0.0262419 -0.0255033 0.00462364 0.0307824 -0.0255033 0.00475387 0.0370376 -0.0255033 0.0191531 0.0346935 -0.0255033 0.0130716 0.0368077 -0.0255033 0.0195915 -0.0278863 -0.0255033 -0.0310059 -0.0131162 -0.0255033 -0.030133 -0.0144591 -0.0255033 -0.0347413 -0.0172209 -0.0255033 -0.0337575 -0.021814 -0.0255033 -0.0314212 -0.0188098 -0.0255033 -0.0260246 -0.0219666 -0.0255033 -0.0276694 -0.0216113 -0.0255033 -0.0279995 -0.020494 -0.0255033 -0.0244796 -0.0109379 -0.0255033 -0.0289377 -0.00845385 -0.0255033 -0.0289918 -0.0208011 -0.0255033 -0.032858 -0.0202873 -0.0255033 -0.0364327 -0.0132639 -0.0255033 -0.0369196 -0.00544151 -0.0255033 -0.0363631 -0.0227051 -0.0255033 -0.0313323 -0.0311467 -0.0255033 -0.0214186 -0.02948 -0.0255033 -0.0218675 -0.0340872 -0.0255033 -0.0240242 -0.029443 -0.0255033 -0.0295321 -0.0297262 -0.0255033 -0.0260255 -0.0206236 -0.0255033 -0.023061 -0.0213132 -0.0255033 -0.0203987 -0.0100631 -0.0255033 -0.0246501 -0.0240311 -0.0255033 0.0340848 -0.0269747 -0.0255033 0.0292067 -0.0230679 -0.0255033 0.0206212 -0.0252024 -0.0255033 0.0196151 -0.0179461 -0.0255033 0.0268944 -0.0157359 -0.0255033 0.0344789 -0.0195727 -0.0255033 0.0335399 -0.0196942 -0.0255033 0.027955 -0.0207419 -0.0255033 0.028603 -0.0206778 -0.0255033 0.0297476 0.030211 -0.0255033 -0.00364257 0.0321339 -0.0255033 -0.00349096 0.0311503 -0.0255033 -0.0016984 0.0411273 -0.0255033 0.00686139 0.0373113 -0.0255033 0.00485599 0.0376281 -0.0255033 0.0021779 0.0329557 -0.0255033 0.0136101 0.0341012 -0.0255033 0.0131219 0.0346229 -0.0255033 0.016605 0.0364157 -0.0255033 0.020311 0.0343337 -0.0255033 0.018339 0.0325883 -0.0255033 0.0260134 0.029885 -0.0255033 0.0228637 0.0264178 -0.0255033 0.0195442 0.0234652 -0.0255033 0.00784844 0.0250618 -0.0255033 0.00897862 0.0260601 -0.0255033 0.0106609 0.0295747 -0.0255033 0.0130463 0.0278266 -0.0255033 0.0141069 0.0208365 -0.0255033 0.0223833 0.0213039 -0.0255033 0.020403 0.0285961 -0.0255033 0.0207394 0.0297407 -0.0255033 0.0206753 0.0268875 -0.0255033 0.0179437 0.0192558 -0.0255033 0.0337174 0.020278 -0.0255033 0.0364371 0.0155688 -0.0255033 0.0250565 0.021602 -0.0255033 0.0280039 0.0244871 -0.0255033 0.0289412 0.0218046 -0.0255033 0.0314256 0.0266196 -0.0255033 0.0288149 0.0287438 -0.0255033 0.0275261 0.027877 -0.0255033 0.0310103 0.0299391 -0.0255033 0.0253478 0.0204266 -0.0255033 0.0266967 0.0172116 -0.0255033 0.0337619 0.0144026 -0.0255033 0.0255771 0.0122249 -0.0255033 0.0256849 -0.0276517 -0.0255033 0.0149291 -0.0327808 -0.0255033 0.0154259 -0.0335978 -0.0255033 0.014952 -0.0377413 -0.0255033 0.0161595 -0.0337199 -0.0255033 0.0192627 -0.0326593 -0.0255033 0.0210107 -0.0308667 -0.0255033 0.0219943 -0.0290007 -0.0255033 0.0255674 -0.0288225 -0.0255033 0.0219498 -0.0274185 -0.0255033 0.0217143 -0.0397131 -0.0255033 -0.00603314 -0.0378496 -0.0255033 -0.00196792 -0.0361015 -0.0255033 -0.00302854 -0.0332274 -0.0255033 -0.00792314 -0.0363699 -0.0255033 0.00543904 -0.0416317 -0.0255033 0.0024677 -0.0260756 -0.0255033 -0.0194676 -0.0279575 -0.0255033 -0.0196873 -0.0317943 -0.0255033 -0.0206264 -0.0333302 -0.0255033 -0.0197714 -0.0343431 -0.0255033 -0.0183346 -0.029584 -0.0255033 -0.0130419 -0.0346322 -0.0255033 -0.0166006 0.00685453 -0.0255033 -0.0411298 -0.00141592 -0.0255033 -0.0310933 0.00033892 -0.0255033 -0.0311973 0.00499682 -0.0255033 -0.0305271 -0.00343943 -0.0255033 -0.0294928 -0.00421746 -0.0255033 -0.0330683 -0.00442012 -0.0255033 -0.0364899 0.0158926 -0.0255033 -0.0268455 0.0154015 -0.0255033 -0.0247507 0.0182169 -0.0255033 -0.0229146 0.0129949 -0.0255033 -0.0316214 0.0157266 -0.0255033 -0.0344745 0.0197414 -0.0255033 -0.0362479 0.0195633 -0.0255033 -0.0335355 0.0274388 -0.0255033 -0.0131555 0.0240956 -0.0255033 -0.0246277 0.0270651 -0.0255033 -0.0208848 0.0308574 -0.0255033 -0.0219899 0.0310035 -0.0255033 -0.0278795 0.0364303 -0.0255033 -0.0202804 0.033755 -0.0255033 -0.0172141 0.00885521 -0.0255033 0.0231085 0.00993017 -0.0255033 0.00226748 0.0122541 -0.0255033 0.00613878 0.0199605 -0.0255033 0.00323142 0.0147576 -0.0255033 0.00548608 0.019195 -0.0255033 0.00635892 -0.0111257 -0.0255033 0.0084034 -0.0070478 -0.0255033 0.0117636 -0.0147669 -0.0255033 -0.00548168 -0.0234745 -0.0255033 -0.00784405 -0.0276847 -0.0255033 -0.00953835 -0.0268524 -0.0255033 -0.0158951 -0.012135 -0.0255033 0.0100447 -0.0127838 -0.0255033 0.0156779 -0.0151096 -0.0255033 0.0134513 -0.0196597 -0.0255033 0.0179999 -0.0200298 -0.0255033 0.0171494 -0.0220767 -0.0255033 0.0172798 -0.025389 -0.0255033 0.0150317 -0.0291444 -0.0255033 -0.000963486 -0.0280458 -0.0255033 -0.002582 -0.0145052 -0.0255033 -0.00126803 -0.0137119 -0.0255033 -0.000216641 -0.0114485 -0.0255033 0.00755034 -0.00886454 -0.0255033 -0.0231041 -0.00719066 -0.0255033 -0.0189028 -0.00612559 -0.0255033 -0.0145075 -0.00615488 -0.0255033 -0.0131907 -0.00666877 -0.0255033 -0.011978 -0.00139076 -0.0255033 -0.00475429 -0.0122235 -0.0255033 -0.00616422 0.0203024 -0.0255033 -0.0172178 0.015576 -0.0255033 -0.0192238 0.00715799 -0.0255033 -0.00724549 0.00825024 -0.0255033 -0.0118912 0.00576423 -0.0255033 -0.0120924 0.0151003 -0.0255033 -0.0134469 0.0127745 -0.0255033 -0.0156735 -0.00494453 -0.0255033 -0.0242464 0.000352833 -0.0255033 -0.0305979 -0.00223717 -0.0255033 -0.029068 -0.000328391 -0.0255033 -0.029496 -0.00819591 -0.0255033 -0.0281067 -0.00473389 -0.0255033 -0.0162265 -0.000819632 -0.0255033 -0.0136825 0.00336573 -0.0255033 -0.00614038 0.0290976 -0.0255033 0.0010574 0.0144959 -0.0255033 0.00127242 0.0198043 -0.0255033 -0.0366924 0.0147549 -0.0255033 -0.0347948 0.020624 -0.0255033 -0.0317874 0.0209508 -0.0255033 -0.0360499 0.0237596 -0.0255033 -0.0245298 0.0383489 -0.0255033 -0.0163653 0.0303882 -0.0255033 -0.0133592 0.038206 -0.0255033 -0.0111328 0.0322547 -0.0255033 -0.0143982 0.0370648 -0.0255033 -0.00647044 0.0349406 -0.0255033 -0.00518158 0.030832 -0.0255033 -0.00586673 -0.0411367 -0.0255033 -0.006857 -0.032965 -0.0255033 -0.0136057 -0.0385791 -0.0255033 -0.0158378 0.0289792 -0.0255033 -0.0143164 0.0253797 -0.0255033 -0.0150273 0.0232034 -0.0255033 -0.0243677 0.0265465 -0.0255033 -0.0128955 0.0283173 -0.0255033 -0.00825114 0.0271027 -0.0255033 -0.0130576 0.0298749 -0.0255033 -0.00354465 0.0294037 -0.0255033 -0.00745521 0.00758513 -0.0255033 0.0110455 0.00907705 -0.0255033 0.00985524 0.00804756 -0.0255033 0.00992567 0.0118275 -0.0255033 -0.00628742 -0.0138979 -0.0255033 -0.00110957 -0.0133565 -0.0255033 -0.00559479 0.0293187 -0.0255033 -0.00338257 0.0311948 -0.0255033 0.000345783 0.0321206 -0.0255033 0.00291051 0.00329107 -0.0255033 0.0113118 0.00613791 -0.0255033 0.00337259 0.00138143 -0.0255033 0.00475868 0.000464461 -0.0255033 -0.0133896 -0.0116712 -0.0255033 -0.0400326 -0.0365786 -0.0255033 -0.0200288 -0.0343324 -0.0258033 -0.0241971 -0.0388566 -0.0258033 -0.0159517 -0.0414326 -0.0258033 -0.00690635 -0.0413259 -0.0255033 -0.00560532 -0.0419312 -0.0258033 0.00248544 -0.0400394 -0.0255033 0.0116688 -0.0367017 -0.0258033 0.0204308 -0.0364396 -0.0255033 0.0202848 -0.0310128 -0.0255033 0.0278838 -0.0205307 -0.0255033 0.0363006 -0.0158446 -0.0255033 0.0385766 -0.013522 -0.0255033 0.0394505 -0.00691321 -0.0258033 0.0414301 0.0117458 -0.0258033 0.040325 0.00247858 -0.0258033 0.0419287 -0.00691321 -0.0260033 0.0414301 -0.0159586 -0.0258033 0.0388541 -0.0159586 -0.0260033 0.0388541 -0.0242039 -0.0258033 0.03433 -0.0312359 -0.0258033 0.0280844 -0.0403274 -0.0258033 0.0117527 -0.0367017 -0.0260033 0.0204308 -0.0403274 -0.0260033 0.0117527 -0.0414326 -0.0260033 -0.00690635 -0.0388566 -0.0260033 -0.0159517 -0.0280869 -0.0258033 -0.031229 -0.0343324 -0.0260033 -0.0241971 -0.0204332 -0.0258033 -0.0366949 -0.0204332 -0.0260033 -0.0366949 -0.0117552 -0.0258033 -0.0403206 -0.00677262 -0.0281533 0.0354855 -0.00366324 -0.0255033 0.0351399 -0.00718446 -0.0255033 0.0293363 -0.0116221 -0.0283033 -0.00725898 -0.00776438 -0.0283033 -0.0112884 -0.0135284 -0.0283033 -0.00585853 -0.0233559 -0.0258033 -0.00811962 -0.0191258 -0.0258033 -0.00664407 -0.01473 -0.0258033 -0.0057794 -0.0257852 -0.0258033 -0.0107526 -0.0248507 -0.0283033 -0.00917766 -0.0257852 -0.0283033 -0.0107526 -0.0259977 -0.0258033 -0.0125715 -0.0259977 -0.0283033 -0.0125715 -0.0154198 -0.0258033 -0.0247973 -0.0254513 -0.0283033 -0.0143194 -0.00642141 -0.0283033 -0.0144576 -0.00642141 -0.0258033 -0.0144576 -0.0074765 -0.0283033 -0.0188117 -0.0074765 -0.0258033 -0.0188117 -0.0091347 -0.0258033 -0.0229736 -0.00776438 -0.0258033 -0.0112884 -0.00691803 -0.0283033 -0.012145 -0.0064482 -0.0258033 -0.0132537 -0.018714 -0.0283033 0.0161641 -0.018714 -0.0258033 0.0161641 -0.0201137 -0.0258033 0.0168614 -0.0203777 -0.0283033 0.0169295 -0.02203 -0.0258033 0.0169835 -0.0222089 -0.0283033 0.0169514 -0.0251309 -0.0258033 0.0148788 -0.0280386 -0.0283033 0.0081716 -0.0280386 -0.0258033 0.0081716 -0.0291892 -0.0258033 0.000952341 -0.0288666 -0.0258033 -0.000850338 -0.027838 -0.0258033 -0.00236554 -0.0147064 -0.0283033 -0.0010455 -0.0147064 -0.0258033 -0.0010455 -0.0157356 -0.0258033 -0.00167065 -0.0121018 -0.0283033 0.00643262 -0.0118421 -0.0283033 0.00878369 -0.0123743 -0.0258033 0.00986387 -0.0117467 -0.0258033 0.00758328 -0.0121018 -0.0258033 0.00643262 0.00380007 -0.0283033 0.0198847 0.00380007 -0.0258033 0.0198847 0.00463726 -0.0283033 0.0242859 0.00439937 -0.0258033 0.0263132 0.00327225 -0.0258033 0.0280149 0.00149849 -0.0258033 0.029025 0.000315766 -0.0258033 0.0292004 -0.0159719 -0.0283033 0.0229227 -0.0160297 -0.0258033 0.0210923 -0.00931886 -0.0283033 0.0127892 -0.00931886 -0.0258033 0.0127892 -0.0153373 -0.0258033 0.0193969 -0.00590272 -0.0283033 0.0123676 -0.00590272 -0.0258033 0.0123676 -0.00706774 -0.0258033 0.0120629 -0.000484297 -0.0283033 0.0136938 0.00068973 -0.0258033 0.0139616 0.0191165 -0.0258033 0.00664846 0.0259884 -0.0258033 0.0125759 0.0259884 -0.0283033 0.0125759 0.0154105 -0.0258033 0.0248017 0.0210872 -0.0283033 0.0201956 0.0210872 -0.0258033 0.0201956 0.025442 -0.0283033 0.0143238 0.025442 -0.0258033 0.0143238 0.0143186 -0.0258033 0.0252891 0.0154105 -0.0283033 0.0248017 0.013688 -0.0258033 0.0254236 0.013688 -0.0283033 0.0254236 0.0118615 -0.0283033 0.0252905 0.0122799 -0.0258033 0.02539 0.00912536 -0.0283033 0.022978 0.00912536 -0.0258033 0.022978 0.0069087 -0.0283033 0.0121494 0.00643886 -0.0283033 0.0132581 0.0069087 -0.0258033 0.0121494 0.00643886 -0.0258033 0.0132581 0.0116128 -0.0258033 0.00726337 0.00775505 -0.0258033 0.0112928 0.013519 -0.0258033 0.00586293 0.0134311 -0.0283033 0.0058872 0.0124318 -0.0258033 0.00638055 0.0116128 -0.0283033 0.00726337 0.0153117 -0.0258033 -0.0132341 0.012365 -0.0258033 -0.00985948 0.0291799 -0.0283033 -0.000947949 0.0280293 -0.0258033 -0.00816721 0.0288221 -0.0258033 0.000938536 0.0278287 -0.0283033 0.00236993 0.027695 -0.0258033 0.00249303 0.0260132 -0.0258033 0.00341951 0.0157263 -0.0283033 0.00167504 0.0146971 -0.0283033 0.00104989 0.0139718 -0.0258033 8.86278e-05 0.0120924 -0.0258033 -0.00642823 0.0136531 -0.0283033 -0.00107264 0.0117374 -0.0258033 -0.00757889 0.0120924 -0.0283033 -0.00642823 -0.0038094 -0.0258033 -0.0198803 -0.0038094 -0.0283033 -0.0198803 -0.0044087 -0.0283033 -0.0263088 -0.00328159 -0.0283033 -0.0280106 -0.00211204 -0.0258033 -0.0287953 0.0151646 -0.0258033 -0.0245667 0.0159625 -0.0283033 -0.0229183 0.0160203 -0.0283033 -0.0210879 0.0125527 -0.0258033 -0.0158755 0.015328 -0.0283033 -0.0193925 0.015328 -0.0258033 -0.0193925 0.0070584 -0.0283033 -0.0120585 0.00701291 -0.0258033 -0.0120619 0.00816631 -0.0283033 -0.0121793 0.000474964 -0.0258033 -0.0136894 0.00589339 -0.0258033 -0.0123632 -0.0023603 -0.0258033 -0.0156411 -0.00169097 -0.0283033 -0.01464 -0.00169097 -0.0258033 -0.01464 -0.000699064 -0.0258033 -0.0139572 -0.000699064 -0.0283033 -0.0139572 0.0101708 -0.0283033 0.0041806 0.0101708 -0.0265033 0.0041806 0.0109761 -0.0283033 -0.000648177 0.0109761 -0.0265033 -0.000648177 0.00960647 -0.0265033 -0.00534814 0.00633324 -0.0283033 -0.00898841 0.00633324 -0.0265033 -0.00898841 0.00180471 -0.0283033 -0.010848 0.00180471 -0.0265033 -0.010848 -0.0288785 -0.0283033 0.0217578 -0.0272189 -0.0257033 0.0207509 -0.0264587 -0.0257033 0.019582 -0.0262851 -0.0283033 0.0190491 -0.0261842 -0.0257033 0.0179358 -0.0263274 -0.0283033 0.0171084 -0.0273343 -0.0257033 0.0154488 -0.0290361 -0.0257033 0.0145151 -0.0133721 -0.0283033 0.0321111 -0.0130976 -0.0283033 0.030465 -0.0135645 -0.0283033 0.0288627 -0.0135645 -0.0257033 0.0288627 -0.0162242 -0.0283033 0.0269878 -0.0162242 -0.0257033 0.0269878 0.00180601 -0.0257033 0.0385942 0.00346557 -0.0283033 0.0375872 0.00422578 -0.0257033 0.0364184 0.00439934 -0.0257033 0.0358854 0.0043571 -0.0257033 0.0339448 0.00335018 -0.0283033 0.0322852 0.00335018 -0.0257033 0.0322852 0.0029175 -0.0257033 0.0319289 -0.000292299 -0.0283033 0.0313937 0.00137369 -0.0257033 0.031295 0.00164838 -0.0283033 0.0313514 0.0191998 -0.0283033 0.0335254 0.0216196 -0.0283033 0.0313496 0.020658 -0.0257033 0.0327136 0.0203113 -0.0257033 0.0268602 0.0187675 -0.0257033 0.0262262 0.0187675 -0.0283033 0.0262262 0.0331872 -0.0257033 0.0196271 0.0341487 -0.0257033 0.018263 0.0339563 -0.0257033 0.0150146 0.0312966 -0.0283033 0.0131396 0.0312966 -0.0257033 0.0131396 0.0360362 -0.0283033 0.00284092 0.038456 -0.0283033 0.000665132 0.0386295 -0.0283033 0.000132206 0.0387305 -0.0257033 -0.000981043 0.0385873 -0.0283033 -0.00180848 0.0382636 -0.0257033 -0.0025833 0.0339379 -0.0257033 -0.00435957 0.0358786 -0.0283033 -0.00440181 0.0309674 -0.0257033 -0.0145529 0.032627 -0.0257033 -0.0155598 0.0324256 -0.0283033 -0.0153647 0.0333872 -0.0283033 -0.0167287 0.0331948 -0.0283033 -0.0199771 0.0325116 -0.0283033 -0.0208619 0.0320789 -0.0283033 -0.0212181 0.0308098 -0.0257033 -0.0217956 0.0308098 -0.0283033 -0.0217956 0.0195404 -0.0283033 -0.0280889 0.0195404 -0.0257033 -0.0280889 0.0204742 -0.0257033 -0.0297907 0.019425 -0.0283033 -0.033391 0.000282966 -0.0257033 -0.0313893 0.00287629 -0.0257033 -0.034098 0.00287629 -0.0283033 -0.034098 0.00283406 -0.0283033 -0.0360387 -0.00181534 -0.0283033 -0.0385898 -0.00181534 -0.0257033 -0.0385898 -0.0154513 -0.0283033 -0.0273274 -0.0145175 -0.0283033 -0.0290292 -0.0145598 -0.0283033 -0.0309699 -0.0145175 -0.0257033 -0.0290292 -0.0145598 -0.0257033 -0.0309699 -0.0192092 -0.0283033 -0.033521 -0.0270467 -0.0283033 -0.0159426 -0.0280958 -0.0283033 -0.0195429 -0.0297976 -0.0283033 -0.0204766 -0.0297976 -0.0257033 -0.0204766 -0.0317383 -0.0283033 -0.0204344 -0.0339472 -0.0257033 0.00436396 -0.0322877 -0.0283033 0.00335705 -0.0313539 -0.0283033 0.00165525 -0.0322877 -0.0257033 0.00335705 -0.0313961 -0.0283033 -0.000285436 -0.0313539 -0.0257033 0.00165525 -0.0324031 -0.0257033 -0.001945 0.0258782 -0.0285033 0.0262707 0.0258782 -0.0281533 0.0262707 0.027365 -0.0285033 0.0247177 0.0273408 -0.0285033 0.0236051 0.0267635 -0.0285033 0.0226536 0.0267635 -0.0281533 0.0226536 0.0246752 -0.0285033 0.0221425 0.0257878 -0.0281533 0.0221182 0.0355448 -0.0285033 0.00980999 0.0360802 -0.0285033 0.00883429 0.036056 -0.0281533 0.00772163 0.0354787 -0.0285033 0.00677015 0.0354787 -0.0281533 0.00677015 0.034503 -0.0281533 0.00623479 0.0341992 -0.0281533 -0.00772576 0.0351506 -0.0281533 -0.00830306 0.035686 -0.0285033 -0.00927875 0.0356618 -0.0281533 -0.0103914 0.0350845 -0.0281533 -0.0113429 0.0341088 -0.0281533 -0.0118783 0.0089178 -0.0281533 -0.0319302 0.0103051 -0.0285033 -0.0331776 0.0104625 -0.0285033 -0.0341214 0.0101948 -0.0281533 -0.03504 0.00955506 -0.0285033 -0.0357516 0.00866993 -0.0285033 -0.036115 0.00866993 -0.0281533 -0.036115 -0.00919525 -0.0281533 -0.031536 -0.00824376 -0.0281533 -0.0321133 -0.00824376 -0.0285033 -0.0321133 -0.00773262 -0.0285033 -0.0342016 -0.00773262 -0.0281533 -0.0342016 -0.00928562 -0.0281533 -0.0356885 -0.023733 -0.0281533 -0.0227154 -0.0238485 -0.0285033 -0.0226035 -0.0231977 -0.0281533 -0.0236911 -0.0232972 -0.0285033 -0.0233855 -0.0231398 -0.0285033 -0.0243293 -0.0231398 -0.0281533 -0.0243293 -0.0234075 -0.0281533 -0.025248 -0.0240472 -0.0281533 -0.0259595 -0.0247749 -0.0281533 -0.0262906 -0.0249324 -0.0285033 -0.0263229 -0.032054 -0.0285033 0.0112811 -0.0315186 -0.0281533 0.0103054 -0.0315186 -0.0285033 0.0103054 -0.0315428 -0.0281533 0.00919278 -0.0315428 -0.0285033 0.00919278 -0.0321201 -0.0285033 0.00824129 -0.0321201 -0.0281533 0.00824129 -0.0330958 -0.0285033 0.00770593 -0.0330958 -0.0281533 0.00770593 -0.0226561 -0.0281533 0.0267704 -0.0221207 -0.0281533 0.0257947 -0.0236979 -0.0285033 0.0231952 -0.0227222 -0.0281533 0.0237306 -0.0236979 -0.0281533 0.0231952 -0.00677262 -0.0285033 0.0354855 -0.0077241 -0.0281533 0.0360628 -0.00623726 -0.0281533 0.0345098 -0.00626147 -0.0281533 0.0333972 -0.00683877 -0.0285033 0.0324457 -0.00683877 -0.0281533 0.0324457 -0.00781447 -0.0281533 0.0319103 -0.00892713 -0.0285033 0.0319346 -0.00892713 -0.0281533 0.0319346 -0.0124411 -0.0283033 -0.00637616 -0.0123227 -0.0285033 -0.00621498 -0.01473 -0.0283033 -0.0057794 -0.0147546 -0.0285033 -0.00558092 -0.0191258 -0.0283033 -0.00664407 -0.0233559 -0.0283033 -0.00811962 -0.021241 -0.0285033 -0.0203295 -0.0210965 -0.0283033 -0.0201912 -0.0154198 -0.0283033 -0.0247973 -0.0143839 -0.0285033 -0.0254767 -0.00728594 -0.0285033 -0.0188724 -0.0064482 -0.0283033 -0.0132537 -0.00675186 -0.0285033 -0.0120337 -0.0076511 -0.0285033 -0.0111235 -0.0122148 -0.0285033 0.00998445 -0.0153211 -0.0283033 0.0132385 -0.0151801 -0.0285033 0.0133803 -0.0185944 -0.0285033 0.0163244 -0.0238904 -0.0283033 0.016226 -0.0251309 -0.0283033 0.0148788 -0.025303 -0.0285033 0.0149807 -0.0291892 -0.0283033 0.000952341 -0.0282306 -0.0285033 0.00822756 -0.0293891 -0.0285033 0.000958849 -0.0288314 -0.0283033 -0.000934144 -0.0277043 -0.0283033 -0.00248864 -0.0260225 -0.0283033 -0.00341512 -0.0200339 -0.0283033 -0.00293395 -0.0157356 -0.0283033 -0.00167065 -0.0199912 -0.0285033 -0.00312934 -0.0156658 -0.0285033 -0.00185807 -0.0145723 -0.0285033 -0.00119385 -0.0139811 -0.0283033 -8.42358e-05 -0.0138016 -0.0285033 -0.000172506 -0.0136624 -0.0283033 0.00107703 -0.0117467 -0.0283033 0.00758328 -0.0115479 -0.0285033 0.00756132 -0.0123743 -0.0283033 0.00986387 -0.0116492 -0.0285033 0.00883676 0.00235097 -0.0283033 0.0156455 0.00446835 -0.0283033 0.0261094 0.00483589 -0.0285033 0.0242625 0.00357172 -0.0283033 0.0277062 0.00218612 -0.0285033 0.0289815 0.0021027 -0.0283033 0.0287997 0.000315766 -0.0283033 0.0292004 -0.0137741 -0.0283033 0.0257518 -0.00694672 -0.0283033 0.028365 -0.0042956 -0.0285033 0.0290874 -0.0151739 -0.0283033 0.0245711 -0.0153319 -0.0285033 0.0246938 -0.0162265 -0.0285033 0.0210569 -0.0160297 -0.0283033 0.0210923 -0.0153373 -0.0283033 0.0193969 -0.0125621 -0.0283033 0.0158799 -0.0127099 -0.0285033 0.0157453 -0.00817565 -0.0283033 0.0121836 -0.000477295 -0.0285033 0.0134939 0.00068973 -0.0283033 0.0139616 0.00168164 -0.0283033 0.0146444 0.0191165 -0.0283033 0.00664846 0.0233466 -0.0283033 0.00812402 0.0248413 -0.0283033 0.00918205 0.0249883 -0.0285033 0.00904643 0.0257759 -0.0283033 0.010757 0.0259654 -0.0285033 0.0106929 0.0261875 -0.0285033 0.0125946 0.0192392 -0.0285033 0.0222291 0.0256163 -0.0285033 0.0144219 0.0137153 -0.0285033 0.0256217 0.0102474 -0.0283033 0.0244253 0.0118058 -0.0285033 0.0254826 0.00746717 -0.0283033 0.0188161 0.00641208 -0.0283033 0.014462 0.00621486 -0.0285033 0.0144953 0.00624332 -0.0285033 0.0132161 0.00674252 -0.0285033 0.0120381 0.00775505 -0.0283033 0.0112928 0.0114432 -0.0285033 0.00715737 0.0123952 -0.0283033 0.00640782 0.0122745 -0.0285033 0.00624835 0.0122054 -0.0285033 -0.00998006 0.0153117 -0.0283033 -0.0132341 0.0187047 -0.0283033 -0.0161597 0.0185851 -0.0285033 -0.01632 0.0252936 -0.0285033 -0.0149763 0.0280293 -0.0283033 -0.00816721 0.0282213 -0.0285033 -0.00822316 0.0288573 -0.0283033 0.00085473 0.0279672 -0.0285033 0.00251424 0.0262724 -0.0283033 0.00333518 0.024458 -0.0283033 0.00358326 0.0200246 -0.0283033 0.00293834 0.0199819 -0.0285033 0.00313373 0.0156565 -0.0285033 0.00186246 0.0145629 -0.0285033 0.00119824 0.0139718 -0.0283033 8.86278e-05 0.0137923 -0.0285033 0.000176898 0.0134537 -0.0285033 -0.00105694 0.0119158 -0.0285033 -0.00633436 0.0117374 -0.0283033 -0.00757889 0.0118327 -0.0283033 -0.0087793 0.0115386 -0.0285033 -0.00755693 0.012365 -0.0283033 -0.00985948 -0.00254451 -0.0285033 -0.0155632 -0.00464659 -0.0283033 -0.0242815 -0.00459651 -0.0285033 -0.0263775 -0.00150782 -0.0283033 -0.0290206 0.0137648 -0.0283033 -0.0257474 0.00698493 -0.0285033 -0.0285549 0.00693738 -0.0283033 -0.0283606 0.0151646 -0.0283033 -0.0245667 0.0153225 -0.0285033 -0.0246894 0.0162172 -0.0285033 -0.0210525 0.0154933 -0.0285033 -0.0192801 0.0125527 -0.0283033 -0.0158755 0.00930953 -0.0283033 -0.0127848 0.00580728 -0.0285033 -0.0121827 0.00831494 -0.0285033 -0.0120157 0.000474964 -0.0283033 -0.0136894 0.00589339 -0.0283033 -0.0123632 -0.000779443 -0.0285033 -0.0137741 -0.00183335 -0.0285033 -0.0144996 -0.0023603 -0.0283033 -0.0156411 0.00644848 -0.0285033 -0.00915187 0.00960647 -0.0283033 -0.00534814 0.00978121 -0.0285033 -0.00544542 0.00735021 -0.0283033 0.0081818 0.00748393 -0.0285033 0.00833052 0.00307285 -0.0283033 0.0105629 -0.0290361 -0.0283033 0.0145151 -0.0273343 -0.0283033 0.0154488 -0.0260909 -0.0285033 0.0190966 -0.0270744 -0.0285033 0.0208892 -0.0272189 -0.0283033 0.0207509 -0.0179461 -0.0285033 0.0268944 -0.0161913 -0.0285033 0.0267905 -0.0146804 -0.0283033 0.0276217 -0.0145651 -0.0285033 0.0274582 -0.0128979 -0.0285033 0.0304531 -0.0143337 -0.0283033 0.0334752 -0.0142 -0.0285033 0.0336239 0.0043571 -0.0283033 0.0339448 0.00439934 -0.0283033 0.0358854 0.0045936 -0.0285033 0.035933 0.00361004 -0.0285033 0.0377255 0.0196062 -0.0285033 0.0335972 0.0203113 -0.0283033 0.0268602 0.0188004 -0.0285033 0.026029 0.021602 -0.0285033 0.0280039 0.0214272 -0.0283033 0.0281012 0.0218941 -0.0283033 0.0297034 0.020658 -0.0283033 0.0327136 0.0207918 -0.0285033 0.0328624 0.031729 -0.0283033 0.0204388 0.0313295 -0.0285033 0.0129424 0.0328405 -0.0283033 0.0137736 0.0339563 -0.0283033 0.0150146 0.0344232 -0.0283033 0.0166168 0.0341311 -0.0285033 0.0149173 0.0346229 -0.0285033 0.016605 0.0344117 -0.0285033 0.0181329 0.0341487 -0.0283033 0.018263 0.0331872 -0.0283033 0.0196271 0.0337763 -0.0285033 0.0192909 0.0333209 -0.0285033 0.0197758 0.0376958 -0.0283033 0.001834 0.0378402 -0.0285033 0.00197231 0.0388238 -0.0285033 0.000179754 0.0388661 -0.0285033 -0.00150436 0.0387305 -0.0283033 -0.000981043 0.0382636 -0.0283033 -0.0025833 0.0371477 -0.0283033 -0.0038243 0.0375804 -0.0283033 -0.00346804 0.0310234 -0.0285033 -0.0143609 0.0309674 -0.0283033 -0.0145529 0.032627 -0.0283033 -0.0155598 0.0335722 -0.0285033 -0.0166527 0.0335608 -0.0283033 -0.0172616 0.0336617 -0.0283033 -0.0183749 0.0335185 -0.0283033 -0.0192023 0.0329052 -0.0285033 -0.0207379 0.0321942 -0.0285033 -0.0213816 0.0305351 -0.0283033 -0.0218521 0.0195633 -0.0285033 -0.0335355 0.0204319 -0.0283033 -0.0317314 0.020624 -0.0285033 -0.0317874 0.0204742 -0.0283033 -0.0297907 0.0196849 -0.0285033 -0.0279506 0.0178808 -0.0283033 -0.027082 0.0157266 -0.0285033 -0.0344745 0.0177232 -0.0283033 -0.0343248 0.0177708 -0.0285033 -0.034519 0.000125343 -0.0283033 -0.038632 0.00208699 -0.0285033 -0.0322579 0.00307056 -0.0285033 -0.0340504 0.00194253 -0.0283033 -0.0323962 0.00302607 -0.0285033 -0.0360946 0.00182714 -0.0283033 -0.0376982 0.00196545 -0.0285033 -0.0378427 -0.0172685 -0.0283033 -0.0335632 -0.0192651 -0.0285033 -0.033713 -0.0172209 -0.0285033 -0.0337575 -0.0155667 -0.0283033 -0.0326295 -0.0143678 -0.0285033 -0.0310259 -0.0153068 -0.0285033 -0.0271891 -0.0171109 -0.0283033 -0.0263205 -0.0279575 -0.0285033 -0.0196873 -0.0268969 -0.0285033 -0.0179393 -0.0270889 -0.0283033 -0.0178833 -0.0279804 -0.0283033 -0.0142408 -0.02964 -0.0283033 -0.0132339 -0.0341049 -0.0283033 -0.00287877 -0.0361015 -0.0285033 -0.00302854 -0.0324031 -0.0283033 -0.001945 -0.0338707 -0.0285033 0.0183911 -0.0368621 -0.0285033 -0.00975618 -0.00212168 -0.0285033 -0.031121 0.0107828 -0.0285033 -0.0373721 -0.0101026 -0.0285033 0.00886057 0.0116399 -0.0285033 -0.00883237 -0.00947308 -0.0285033 0.0278358 0.00622793 -0.0285033 -0.0345054 0.0133804 -0.0285033 -0.028761 0.00625214 -0.0285033 -0.0333928 0.00780514 -0.0285033 -0.0319059 0.0141906 -0.0285033 -0.0336195 0.0131778 -0.0285033 -0.0321827 0.00975383 -0.0285033 -0.0323956 0.00676329 -0.0285033 -0.0354811 0.00453823 -0.0285033 -0.0353354 -0.0154284 -0.0285033 -0.0327739 -0.011943 -0.0285033 -0.033473 -0.0108879 -0.0285033 -0.0373444 -0.00928562 -0.0285033 -0.0356885 -0.00919525 -0.0285033 -0.031536 -0.00304207 -0.0285033 -0.0317611 -0.0273502 -0.0285033 -0.0236007 -0.0256256 -0.0285033 -0.0144175 -0.0246845 -0.0285033 -0.0221381 -0.026839 -0.0285033 -0.025689 -0.0234075 -0.0285033 -0.025248 -0.0204359 -0.0285033 -0.0266923 -0.0240472 -0.0285033 -0.0259595 -0.00749326 -0.0285033 -0.00832612 -0.0114525 -0.0285033 -0.00715297 -0.0261968 -0.0285033 -0.0125902 -0.0191782 -0.0285033 -0.00645104 -0.023435 -0.0285033 -0.00793591 -0.0278367 -0.0285033 -0.00263854 -0.0284976 -0.0285033 -0.0234348 -0.0103029 -0.0285033 -0.0247146 -0.020217 -0.0285033 -0.0258478 -0.0155254 -0.0285033 -0.0249671 -0.0170549 -0.0285033 -0.0261285 -0.00625266 -0.0285033 -0.0132117 -0.0062242 -0.0285033 -0.0144909 -0.00853012 -0.0285033 -0.0292535 -0.00895459 -0.0285033 -0.0230606 -0.0261354 -0.0285033 0.0170524 -0.0240061 -0.0285033 0.0163891 -0.0222481 -0.0285033 0.0171476 -0.0203437 -0.0285033 0.0197564 -0.0203337 -0.0285033 0.0171247 -0.0312041 -0.0285033 -0.000341391 -0.0311596 -0.0285033 0.0017028 -0.0321432 -0.0285033 0.00349536 -0.027196 -0.0285033 0.0153044 -0.0290151 -0.0285033 -0.00101339 -0.0322647 -0.0285033 -0.00208946 -0.0295637 -0.0285033 -0.011883 -0.0259747 -0.0285033 -0.0106885 -0.0249977 -0.0285033 -0.00904204 -0.0119252 -0.0285033 0.00633875 -0.0134631 -0.0285033 0.00106134 0.00399342 -0.0285033 0.0198336 0.00253517 -0.0285033 0.0155676 0.00182401 -0.0285033 0.014504 0.00186196 -0.0285033 0.0387862 0.0108785 -0.0285033 0.0373488 0.00454911 -0.0285033 0.0338888 0.00668346 -0.0285033 0.022953 0.0046593 -0.0285033 0.0261689 0.000317961 -0.0285033 0.0294004 0.00169593 -0.0285033 0.0311572 0.00348849 -0.0285033 0.0321407 0.00372192 -0.0285033 0.0278383 -0.00197479 -0.0285033 0.0378471 -0.00623726 -0.0285033 0.0345098 -0.00781447 -0.0285033 0.0319103 -0.00699426 -0.0285033 0.0285593 -0.00626147 -0.0285033 0.0333972 -0.0077241 -0.0285033 0.0360628 -0.0155027 -0.0285033 0.0192844 -0.0162582 -0.0285033 0.0185658 -0.00944627 -0.0285033 0.012635 -0.00700611 -0.0285033 0.0118669 -0.00581662 -0.0285033 0.0121871 0.0268875 -0.0285033 0.0179437 0.0278266 -0.0285033 0.0141069 0.0295747 -0.0285033 0.0130463 0.0234256 -0.0285033 0.0079403 0.0329069 -0.0285033 0.0207396 0.0238654 -0.0285033 0.0307175 0.0268297 -0.0285033 0.0256934 0.0208873 -0.0285033 0.0206876 0.0204266 -0.0285033 0.0266967 0.015516 -0.0285033 0.0249715 0.0170456 -0.0285033 0.0261329 0.0143139 -0.0285033 0.0289861 0.0101183 -0.0285033 0.0245781 0.015419 -0.0285033 0.0327783 0.00370933 -0.0285033 0.0127471 0.00727661 -0.0285033 0.0188768 0.00894526 -0.0285033 0.023065 0.00764177 -0.0285033 0.0111279 -0.00184695 -0.0285033 0.0110496 0.000770109 -0.0285033 0.0137785 0.0031288 -0.0285033 0.0107549 0.0103558 -0.0285033 0.00425657 0.0133751 -0.0285033 0.00569519 0.0161568 -0.0285033 -0.0229661 0.0185423 -0.0285033 -0.0259016 0.0271866 -0.0285033 -0.0153 0.0191688 -0.0285033 0.00645543 0.0244432 -0.0285033 0.00378272 0.0263402 -0.0285033 0.00352336 0.0100933 -0.0285033 -0.00885618 0.026126 -0.0285033 -0.017048 0.0239187 -0.0285033 -0.0164389 0.0127006 -0.0285033 -0.0157409 0.0151708 -0.0285033 -0.0133759 -0.00341817 -0.0285033 -0.0281567 -0.00484522 -0.0285033 -0.0242581 -0.00551075 -0.0285033 -0.0188923 -0.00400275 -0.0285033 -0.0198292 0.00428626 -0.0285033 -0.029083 0.00514893 -0.0285033 -0.0332397 0.00183761 -0.0285033 -0.0110452 0.000467962 -0.0285033 -0.0134895 0.00704511 -0.0285033 -0.011859 0.00943693 -0.0285033 -0.0126306 0.0132712 -0.0285033 0.00204918 0.0111757 -0.0285033 -0.000660002 -0.00979055 -0.0285033 0.00544981 -0.0103652 -0.0285033 -0.00425218 -0.0132805 -0.0285033 -0.00204478 -0.0134779 -0.0285033 -0.005665 0.0194999 -0.0285033 0.033659 0.0192558 -0.0285033 0.0337174 0.0207355 -0.0285033 0.032912 0.0220607 -0.0285033 0.0320386 0.0218046 -0.0285033 0.0314256 0.0220938 -0.0285033 0.0296916 0.0212317 -0.0285033 0.0203339 0.0257878 -0.0285033 0.0221182 0.0317849 -0.0285033 0.0206308 0.0320864 -0.0285033 0.0205296 0.036056 -0.0285033 0.00772163 0.034503 -0.0285033 0.00623479 0.0277623 -0.0285033 0.00573775 0.0345933 -0.0285033 0.0103873 0.0361095 -0.0285033 0.0144583 0.037327 -0.0285033 0.0109364 0.032003 -0.0285033 0.00750646 0.0321133 -0.0285033 0.00936889 0.0327531 -0.0285033 0.0100804 0.0329557 -0.0285033 0.0136101 0.0336382 -0.0285033 0.0104439 0.0289792 -0.0285033 -0.0143164 0.0293798 -0.0285033 -0.000954457 0.0290425 -0.0285033 0.000930162 0.0350607 -0.0285033 0.00361092 0.034048 -0.0285033 0.00307742 0.0360922 -0.0285033 0.00303294 0.0351506 -0.0285033 -0.00830306 0.0359261 -0.0285033 -0.00459607 0.0341992 -0.0285033 -0.00772576 0.0341088 -0.0285033 -0.0118783 0.0350845 -0.0285033 -0.0113429 0.0353489 -0.0285033 -0.0162253 0.0383814 -0.0285033 -0.00630004 0.0356618 -0.0285033 -0.0103914 0.0317191 -0.0285033 -0.00874415 0.0329961 -0.0285033 -0.011854 0.0325594 -0.0285033 -0.0152159 0.0321601 -0.0285033 -0.0113886 0.0316088 -0.0285033 -0.0106066 0.0387793 -0.0285033 -0.00186443 0.0385319 -0.0285033 -0.00530272 0.0377187 -0.0285033 -0.00361251 0.0338614 -0.0285033 -0.0183867 0.0310557 -0.0285033 -0.0234171 0.030568 -0.0285033 -0.0220494 0.0288132 -0.0285033 -0.0219454 0.0138591 -0.0285033 -0.0259238 0.0145558 -0.0285033 -0.0274538 0.0258406 -0.0285033 -0.0280285 0.0206684 -0.0285033 -0.0297432 0.0166145 -0.0285033 -0.035169 0.0101948 -0.0285033 -0.03504 0.00771454 -0.0285033 -0.0381242 0.000172891 -0.0285033 -0.0388263 -0.000190619 -0.0285033 -0.0388974 0.00315679 -0.0285033 -0.0326592 -0.00156378 -0.0285033 -0.0292126 -0.00914082 -0.0285033 -0.0313492 -0.00770841 -0.0285033 -0.033089 -0.00830992 -0.0285033 -0.0351531 -0.00429001 -0.0285033 -0.038661 -0.0018713 -0.0285033 -0.0387818 -0.00163402 -0.0285033 -0.0388637 -0.00151122 -0.0285033 -0.0388686 -0.0143233 -0.0285033 -0.0289817 -0.0101504 -0.0285033 -0.0314794 -0.0258875 -0.0285033 -0.0262663 -0.0220701 -0.0285033 -0.0320342 -0.0208011 -0.0285033 -0.032858 -0.0297501 -0.0285033 -0.0206709 -0.0329162 -0.0285033 -0.0207352 -0.0346322 -0.0285033 -0.0166006 -0.0341404 -0.0285033 -0.0149129 -0.0313389 -0.0285033 -0.012938 -0.027836 -0.0285033 -0.0141025 -0.0268524 -0.0285033 -0.0158951 -0.0340573 -0.0285033 -0.00307303 -0.0378496 -0.0285033 -0.00196792 -0.0388331 -0.0285033 -0.000175362 -0.0359355 -0.0285033 0.00460046 -0.0289885 -0.0285033 0.0143208 -0.0348457 -0.0285033 0.0115515 -0.0357671 -0.0285033 0.0153077 -0.0354855 -0.0285033 0.01084 -0.0310327 -0.0285033 0.0143653 -0.0355958 -0.0285033 0.0089776 -0.0387886 -0.0285033 0.00186882 -0.0383908 -0.0285033 0.00630443 -0.037728 -0.0285033 0.0036169 -0.0357532 -0.0285033 0.00992141 -0.0339606 -0.0285033 0.011915 -0.0325687 -0.0285033 0.0152203 -0.0322035 -0.0285033 0.021386 -0.0226994 -0.0285033 0.0315959 -0.0202923 -0.0285033 0.0326079 -0.0221449 -0.0285033 0.024682 -0.0227222 -0.0285033 0.0237306 -0.027642 -0.0285033 0.0218832 -0.0313915 -0.0285033 0.0229821 -0.0310651 -0.0285033 0.0234215 -0.0256466 -0.0285033 0.0236848 -0.0221207 -0.0285033 0.0257947 -0.0226561 -0.0285033 0.0267704 -0.0245627 -0.0285033 0.0274043 -0.0261979 -0.0285033 0.0244669 -0.0263553 -0.0285033 0.0254107 -0.0245579 -0.0285033 0.0301742 -0.0260876 -0.0285033 0.0263293 -0.0254478 -0.0285033 0.0270408 -0.0161661 -0.0285033 0.0229705 -0.0138684 -0.0285033 0.0259282 -0.0133898 -0.0285033 0.0287654 -0.013284 -0.0285033 0.0287718 -0.0131871 -0.0285033 0.0321871 -0.0157359 -0.0285033 0.0344789 0.01579 -0.0285033 -0.0355469 0.0144177 -0.0285033 -0.0361254 0.00771454 -0.0287533 -0.0381242 0.00139643 -0.0285033 -0.0388726 0.0245486 -0.0287533 -0.0301698 0.0245486 -0.0285033 -0.0301698 0.0192841 -0.0285033 -0.0337788 0.018126 -0.0285033 -0.0344142 0.0335904 -0.0285033 -0.0196086 0.0357578 -0.0285033 -0.0153033 0.0388949 -0.0285033 -0.000183757 0.0369133 -0.0285033 0.0122608 0.0369133 -0.0287533 0.0122608 0.0387742 -0.0287533 0.00306949 0.0387742 -0.0285033 0.00306949 0.0329069 -0.0287533 0.0207396 0.0269878 -0.0285033 0.0280133 0.0194999 -0.0287533 0.033659 -0.000178662 -0.0279033 -0.0329734 0.000750694 -0.0279033 -0.0335373 0.000637924 -0.0373033 -0.033428 0.000750694 -0.0373033 -0.0335373 0.0012736 -0.0279033 -0.0344903 0.00117641 -0.0373033 -0.0341918 0.000686077 -0.0373033 -0.0365064 0.000443777 -0.0373033 -0.0367059 -0.000266931 -0.0279033 -0.0370293 -0.0161439 -0.0373033 -0.0305083 -0.0187475 -0.0373033 -0.0319369 -0.0176608 -0.0279033 -0.0319605 -0.0301016 -0.0373033 -0.014818 -0.0301016 -0.0279033 -0.014818 -0.029285 -0.0373033 -0.0152726 -0.0291723 -0.0373033 -0.0153819 -0.0287465 -0.0279033 -0.0160365 -0.0287465 -0.0373033 -0.0160365 -0.028673 -0.0279033 -0.0174217 -0.0294792 -0.0373033 -0.0185506 -0.0294792 -0.0279033 -0.0185506 -0.0301899 -0.0373033 -0.018874 -0.0301899 -0.0279033 -0.018874 -0.0344089 -0.0373033 0.00277985 -0.0335923 -0.0373033 0.00232528 -0.0334795 -0.0279033 0.00221598 -0.0330538 -0.0373033 0.00156141 -0.0329566 -0.0279033 0.00126297 -0.0329001 -0.0373033 0.000639555 -0.0331615 -0.0373033 -0.000257711 -0.0329802 -0.0279033 0.000176191 -0.0337864 -0.0373033 -0.000952671 -0.0344971 -0.0373033 -0.00127607 -0.034651 -0.0373033 -0.00130768 -0.0284107 -0.0373033 0.0196098 -0.0279115 -0.0279033 0.01757 -0.0284754 -0.0279033 0.0166407 -0.0294284 -0.0279033 0.0161178 -0.0162535 -0.0279033 0.0327028 -0.0148984 -0.0279033 0.0314844 -0.0147447 -0.0279033 0.0305625 -0.0148249 -0.0373033 0.0300991 -0.0153888 -0.0373033 0.0291698 -0.0156311 -0.0279033 0.0289703 -0.0163418 -0.0373033 0.0286469 -0.0174286 -0.0373033 0.0286705 0.00134438 -0.0279033 0.03701 0.00216097 -0.0373033 0.0365555 0.00216097 -0.0279033 0.0365555 0.00269945 -0.0279033 0.0357916 0.00285318 -0.0373033 0.0348697 0.00285318 -0.0279033 0.0348697 0.00259171 -0.0373033 0.0339725 0.00259171 -0.0279033 0.0339725 0.00196682 -0.0373033 0.0332775 0.00110228 -0.0373033 0.0329225 0.00110228 -0.0279033 0.0329225 0.000169328 -0.0279033 0.0329778 0.0195548 -0.0373033 0.0314867 0.020247 -0.0373033 0.029801 0.020247 -0.0279033 0.029801 0.0199855 -0.0279033 0.0289037 0.0193607 -0.0279033 0.0282088 0.0175632 -0.0373033 0.027909 0.0184961 -0.0279033 0.0278538 0.0312673 -0.0279033 0.0188547 0.0320839 -0.0279033 0.0184001 0.0326224 -0.0373033 0.0176363 0.0325147 -0.0373033 0.0158171 0.0327761 -0.0279033 0.0167144 0.0318898 -0.0373033 0.0151222 0.0318898 -0.0279033 0.0151222 0.0363912 -0.0279033 0.000802235 0.0365039 -0.0373033 0.000692939 0.0369296 -0.0279033 3.83709e-05 0.0369296 -0.0373033 3.83709e-05 0.0370834 -0.0279033 -0.000883487 0.0370032 -0.0373033 -0.00134685 0.036197 -0.0279033 -0.00247571 0.0353325 -0.0279033 -0.00283072 0.0343995 -0.0279033 -0.00277546 0.0305058 -0.0373033 -0.016137 0.0305058 -0.0279033 -0.016137 0.0313224 -0.0373033 -0.0165916 0.0319344 -0.0373033 -0.0187407 0.0317531 -0.0373033 -0.0191746 0.0319344 -0.0279033 -0.0187407 0.0313706 -0.0373033 -0.01967 0.0311283 -0.0373033 -0.0198695 0.0313706 -0.0279033 -0.01967 0.0304175 -0.0373033 -0.0201929 0.0302637 -0.0373033 -0.0202246 0.0304175 -0.0279033 -0.0201929 0.0182358 -0.0373033 -0.0291207 0.0188715 -0.0279033 -0.030183 0.0188478 -0.0279033 -0.0312698 0.0188478 -0.0373033 -0.0312698 0.018284 -0.0279033 -0.0321992 0.0180417 -0.0373033 -0.0323987 0.017331 -0.0279033 -0.0327221 0.0162442 -0.0279033 -0.0326984 0.0162442 -0.0373033 -0.0326984 -1.07973e-05 -0.0273033 -0.0323973 0.00124995 -0.0279033 -0.035577 0.00182599 -0.0273033 -0.0357449 0.000686077 -0.0279033 -0.0365064 0.00110101 -0.0273033 -0.0369398 -0.000124286 -0.0273033 -0.0376121 -0.0175725 -0.0279033 -0.0279046 -0.0174046 -0.0273033 -0.0273286 -0.0166431 -0.0279033 -0.0284685 -0.0161202 -0.0279033 -0.0294215 -0.0162097 -0.0273033 -0.0280536 -0.0161439 -0.0279033 -0.0305083 -0.0155678 -0.0273033 -0.0306761 -0.0167078 -0.0279033 -0.0314376 -0.0162928 -0.0273033 -0.031871 -0.0189154 -0.0273033 -0.0325129 -0.0303437 -0.0279033 -0.0189056 -0.0292369 -0.0279033 -0.018351 -0.0288219 -0.0273033 -0.0187844 -0.0288543 -0.0279033 -0.0178556 -0.0285928 -0.0279033 -0.0169583 -0.0286494 -0.0279033 -0.0163349 -0.0280666 -0.0273033 -0.0161923 -0.029285 -0.0279033 -0.0152726 -0.0287389 -0.0273033 -0.014967 -0.0291723 -0.0279033 -0.0153819 -0.034241 -0.0273033 0.00335589 -0.0330461 -0.0273033 0.00263091 -0.0335441 -0.0279033 -0.000753165 -0.0344971 -0.0279033 -0.00127607 -0.0355839 -0.0279033 -0.00125242 -0.0284107 -0.0279033 0.0196098 -0.0279773 -0.0273033 0.0200247 -0.0278878 -0.0279033 0.0186568 -0.0273354 -0.0273033 0.0174022 -0.0280604 -0.0273033 0.0162073 -0.0305151 -0.0279033 0.0161414 -0.0160856 -0.0273033 0.0332788 -0.0154369 -0.0279033 0.0322482 -0.0150357 -0.0273033 0.0326944 -0.0143434 -0.0273033 0.0317123 -0.0150062 -0.0279033 0.0296652 -0.0152854 -0.0273033 0.0284799 -0.0163969 -0.0273033 0.0280234 -0.0164956 -0.0279033 0.0286153 0.00151224 -0.0273033 0.0375861 0.00311595 -0.0273033 0.0336806 0.00196682 -0.0279033 0.0332775 0.00231252 -0.0273033 0.0327871 0.0195548 -0.0279033 0.0314867 0.019956 -0.0273033 0.0319329 0.0200933 -0.0279033 0.0307228 0.020846 -0.0273033 0.0297655 0.0205098 -0.0273033 0.0286119 0.0197064 -0.0273033 0.0277184 0.0185948 -0.0273033 0.0272619 0.0173953 -0.0273033 0.027333 0.0314352 -0.0273033 0.0194307 0.0326224 -0.0279033 0.0176363 0.0325147 -0.0279033 0.0158171 0.0330389 -0.0273033 0.0155253 0.0322355 -0.0273033 0.0146318 0.0310252 -0.0279033 0.0147672 0.0311239 -0.0273033 0.0141753 0.0368219 -0.0279033 -0.00178075 0.0314352 -0.0279033 -0.0167009 0.0318686 -0.0273033 -0.016286 0.0319581 -0.0279033 -0.0176539 0.0325409 -0.0273033 -0.0175113 0.0325105 -0.0273033 -0.0189085 0.0305602 -0.0273033 -0.0207757 -0.00713378 -0.0366533 0.0351398 -0.00674151 -0.0366533 0.0335371 -0.00832562 -0.0376448 0.0339987 0.0252767 -0.0376448 0.0242066 0.0268794 -0.0366533 0.0245989 0.0350951 -0.0366533 0.00955009 0.0339918 -0.0376448 0.00832315 0.0354335 -0.0366533 0.0075206 0.0351329 -0.0366533 0.00713131 0.0343841 -0.0366533 0.00672045 0.0355759 -0.0366533 0.00786152 0.0352003 -0.0366533 -0.00939762 0.0340593 -0.0366533 -0.00820579 0.0347895 -0.0366533 -0.00864883 0.0339899 -0.0366533 -0.0113926 0.0347387 -0.0366533 -0.0109817 0.00785466 -0.0366533 -0.0355784 0.00975795 -0.0366533 -0.0347969 0.0099634 -0.0366533 -0.0340919 0.00950812 -0.0366533 -0.0328532 0.00877791 -0.0366533 -0.0324102 -0.00860493 -0.0366533 -0.032459 -0.00979676 -0.0376448 -0.0336001 -0.00821265 -0.0366533 -0.0340617 -0.0086557 -0.0366533 -0.0347919 -0.0236833 -0.0366533 -0.0238099 -0.0236389 -0.0366533 -0.0242998 -0.0250146 -0.0366533 -0.0258297 -0.0243353 -0.0366533 -0.0255508 -0.0240942 -0.0366533 -0.0230611 -0.0320043 -0.0366533 0.0101866 -0.0320229 -0.0366533 0.00933266 -0.0324151 -0.0366533 0.0109354 -0.0324659 -0.0366533 0.00860246 -0.0226064 -0.0366533 0.0256758 -0.0237474 -0.0366533 0.0268677 -0.0238168 -0.0366533 0.0236809 -0.022625 -0.0366533 0.0248219 -0.0254513 -0.0370033 -0.0143194 -0.0116221 -0.0370033 -0.00725898 -0.01473 -0.0370033 -0.0057794 -0.0191258 -0.0370033 -0.00664407 -0.0259977 -0.0370033 -0.0125715 -0.0248507 -0.0370033 -0.00917766 -0.00691803 -0.0370033 -0.012145 -0.0154198 -0.0370033 -0.0247973 -0.0091347 -0.0370033 -0.0229736 -0.0210965 -0.0370033 -0.0201912 -0.0074765 -0.0370033 -0.0188117 -0.00642141 -0.0370033 -0.0144576 -0.0038094 -0.0370033 -0.0198803 -0.0023603 -0.0370033 -0.0156411 -0.00169097 -0.0370033 -0.01464 0.0125527 -0.0370033 -0.0158755 0.015328 -0.0370033 -0.0193925 -0.00211204 -0.0370033 -0.0287953 -0.000325099 -0.0370033 -0.029196 -0.00464659 -0.0370033 -0.0242815 0.023881 -0.0370033 -0.0162216 0.0118327 -0.0370033 -0.0087793 0.0117374 -0.0370033 -0.00757889 0.0221995 -0.0370033 -0.0169471 0.0203683 -0.0370033 -0.0169252 0.0187047 -0.0370033 -0.0161597 0.0260132 -0.0370033 0.00341951 0.024458 -0.0370033 0.00358326 0.0259884 -0.0370033 0.0125759 0.0257759 -0.0370033 0.010757 0.0116128 -0.0370033 0.00726337 0.025442 -0.0370033 0.0143238 0.0248413 -0.0370033 0.00918205 0.0233466 -0.0370033 0.00812402 0.0210872 -0.0370033 0.0201956 0.0104151 -0.0370033 0.0245601 0.0122799 -0.0370033 0.02539 0.0143186 -0.0370033 0.0252891 0.0154105 -0.0370033 0.0248017 0.00746717 -0.0370033 0.0188161 0.00641208 -0.0370033 0.014462 0.00643886 -0.0370033 0.0132581 0.00068973 -0.0370033 0.0139616 -0.000484297 -0.0370033 0.0136938 -0.0159719 -0.0370033 0.0229227 -0.0160297 -0.0370033 0.0210923 -0.0151739 -0.0370033 0.0245711 -0.0137741 -0.0370033 0.0257518 -0.0125621 -0.0370033 0.0158799 0.00439937 -0.0370033 0.0263132 0.000315766 -0.0370033 0.0292004 0.00463726 -0.0370033 0.0242859 -0.00694672 -0.0370033 0.028365 0.00168164 -0.0370033 0.0146444 -0.0200339 -0.0370033 -0.00293395 -0.0291892 -0.0370033 0.000952341 -0.0147064 -0.0370033 -0.0010455 -0.0157356 -0.0370033 -0.00167065 -0.02203 -0.0370033 0.0169835 -0.0244673 -0.0370033 -0.00357887 -0.0288666 -0.0370033 -0.000850338 -0.0251309 -0.0370033 0.0148788 0.0174192 -0.0279033 -0.0286661 0.0183486 -0.0279033 -0.02923 0.0175871 -0.0273033 -0.0280901 0.018782 -0.0273033 -0.0288151 0.0194239 -0.0273033 -0.0314377 0.0174736 -0.0273033 -0.0333049 -0.00280296 -0.0273033 -0.0321003 -0.00140809 -0.0273033 -0.0323669 0.00118409 -0.0273033 -0.0331223 0.000222814 -0.0273033 -0.0315957 0.0018564 -0.0273033 -0.0343476 0.00167846 -0.0273033 -0.0375429 -0.00175519 -0.0273033 -0.0383833 -0.0214301 -0.0273033 -0.0312635 -0.0207522 -0.0273033 -0.0291654 -0.0200272 -0.0273033 -0.0279705 -0.0188019 -0.0273033 -0.0272982 -0.0187415 -0.0273033 -0.0264339 -0.017171 -0.0273033 -0.0265269 -0.0155374 -0.0273033 -0.0292789 -0.0147662 -0.0273033 -0.0309098 -0.0157154 -0.0273033 -0.0324742 -0.0175181 -0.0273033 -0.0325433 -0.0299338 -0.0273033 -0.014242 -0.0315296 -0.0273033 -0.0134005 -0.0283256 -0.0273033 -0.0142055 -0.028097 -0.0273033 -0.0175896 -0.0276005 -0.0273033 -0.0185536 -0.0300472 -0.0273033 -0.0194568 -0.0314445 -0.0273033 -0.0194263 -0.0316781 -0.0273033 -0.020228 -0.0324944 -0.0273033 -0.0188419 -0.0331868 -0.0273033 -0.0178598 -0.034083 -0.0273033 -0.0158452 -0.0376917 -0.0273033 0.000923354 -0.0380851 -0.0273033 0.00248312 -0.036552 -0.0273033 0.0029705 -0.0354405 -0.0273033 0.00342694 -0.0355779 -0.0273033 0.00425057 -0.0323738 -0.0273033 0.00140562 -0.032443 -0.0273033 0.00320836 -0.0315627 -0.0273033 0.00160413 -0.0324042 -0.0273033 8.32657e-06 -0.0331292 -0.0273033 -0.00118656 -0.0343545 -0.0273033 -0.00185887 -0.034156 -0.0273033 -0.00266993 -0.03736 -0.0273033 -0.00186491 -0.0319644 -0.0273033 0.0210468 -0.0305091 -0.0273033 0.0216444 -0.0289386 -0.0273033 0.0215514 -0.027305 -0.0273033 0.0187995 -0.026494 -0.0273033 0.018998 -0.0292857 -0.0273033 0.015535 -0.0290872 -0.0273033 0.0147239 -0.0309166 -0.0273033 0.0147637 -0.0331977 -0.0273033 0.0168148 -0.0334564 -0.0273033 0.0183666 -0.0322867 -0.0273033 0.0194708 -0.0144819 -0.0273033 0.0293734 -0.0137524 -0.0273033 0.0289673 -0.0175964 -0.0273033 0.0280945 -0.01783 -0.0273033 0.0272928 -0.0193944 -0.0273033 0.028242 -0.0141458 -0.0273033 0.030527 1.46377e-06 -0.0273033 0.0324017 -0.00119342 -0.0273033 0.0331267 -0.00179656 -0.0273033 0.0325493 -0.00186573 -0.0273033 0.034352 -0.00267679 -0.0273033 0.0341535 -0.00111034 -0.0273033 0.0369442 -0.00168779 -0.0273033 0.0375473 0.00256214 -0.0273033 0.0370016 0.00325448 -0.0273033 0.0360195 0.00402689 -0.0273033 0.0363367 0.00345213 -0.0273033 0.0348343 0.00428567 -0.0273033 0.0347849 0.00120097 -0.0273033 0.0323307 0.0205143 -0.0273033 0.0325538 0.0206483 -0.0273033 0.0309508 0.0214207 -0.0273033 0.0312679 0.0212394 -0.0273033 0.0282057 0.0201875 -0.0273033 0.0270359 0.0187322 -0.0273033 0.0264383 0.0171617 -0.0273033 0.0265313 0.0155973 -0.0273033 0.0274805 0.0162004 -0.0273033 0.028058 0.0155585 -0.0273033 0.0306805 0.015706 -0.0273033 0.0324786 0.0175088 -0.0273033 0.0325477 0.0189061 -0.0273033 0.0325173 0.0342086 -0.0273033 0.0166296 0.0337685 -0.0273033 0.0151192 0.0327166 -0.0273033 0.0139493 0.0312613 -0.0273033 0.0133517 0.0299244 -0.0273033 0.0142464 0.0296908 -0.0273033 0.0134447 0.0287295 -0.0273033 0.0149714 0.0280572 -0.0273033 0.0161967 0.0280876 -0.0273033 0.0175939 0.027286 -0.0273033 0.0178276 0.0324851 -0.0273033 0.0188463 0.0331774 -0.0273033 0.0178642 0.0339498 -0.0273033 0.0181813 0.0333751 -0.0273033 0.0166789 0.0383809 -0.0273033 -0.00174833 0.0373461 -0.0273033 -0.00207259 0.0376823 -0.0273033 -0.000918962 0.0374847 -0.0273033 0.000266284 0.0367923 -0.0273033 0.0012484 0.035976 -0.0273033 0.00263451 0.0357424 -0.0273033 0.00183285 0.0343451 -0.0273033 0.00186326 0.0331198 -0.0273033 0.00119095 0.0342317 -0.0273033 -0.0033515 0.033998 -0.0273033 -0.00415316 0.0358275 -0.0273033 -0.00419297 0.0354312 -0.0273033 -0.00342255 0.0374317 -0.0273033 -0.00331274 0.0365427 -0.0273033 -0.00296611 0.0274207 -0.0273033 -0.0191788 0.0273649 -0.0273033 -0.0205978 0.028113 -0.0273033 -0.0201609 0.0323629 -0.0273033 -0.0207066 0.0317855 -0.0273033 -0.0201034 0.0333121 -0.0273033 -0.0191422 0.0324717 -0.0273033 -0.0157085 0.0309073 -0.0273033 -0.0147593 0.0274736 -0.0273033 -0.0155997 0.0265245 -0.0273033 -0.0171642 0.0275592 -0.0273033 -0.0168399 -0.00672292 -0.0366533 0.034391 -0.00718455 -0.0366533 0.0328069 -0.00718455 -0.0291033 0.0328069 -0.00793334 -0.0366533 0.032396 0.0257383 -0.0366533 0.0257907 0.0257383 -0.0291033 0.0257907 0.0264685 -0.0366533 0.0253477 0.0268608 -0.0366533 0.023745 0.0268608 -0.0291033 0.023745 0.0264178 -0.0366533 0.0230148 0.0264178 -0.0291033 0.0230148 0.025669 -0.0366533 0.0226039 0.0248151 -0.0366533 0.0226225 0.0351837 -0.0291033 0.00946421 0.0351837 -0.0366533 0.00946421 0.0355182 -0.0366533 0.00894991 0.0355945 -0.0366533 0.00871542 0.0356389 -0.0366533 0.00822559 0.0355759 -0.0291033 0.00786152 0.0349425 -0.0366533 0.00697456 0.0342632 -0.0366533 0.00669562 0.0335302 -0.0366533 0.00673904 0.0351817 -0.0366533 -0.0102515 0.033136 -0.0366533 -0.011374 0.033136 -0.0291033 -0.011374 0.00941951 -0.0366533 -0.0327674 0.00941951 -0.0291033 -0.0327674 0.00984261 -0.0366533 -0.0333675 0.00950812 -0.0291033 -0.0328532 0.00991897 -0.0366533 -0.033602 0.0099634 -0.0291033 -0.0340919 0.00990039 -0.0366533 -0.0344559 0.00975795 -0.0291033 -0.0347969 0.00945735 -0.0366533 -0.0351861 0.00945735 -0.0291033 -0.0351861 0.00926697 -0.0366533 -0.0353429 0.00926697 -0.0291033 -0.0353429 0.00870856 -0.0291033 -0.035597 0.00870856 -0.0366533 -0.035597 0.00858769 -0.0366533 -0.0356218 0.00858769 -0.0291033 -0.0356218 -0.00860493 -0.0291033 -0.032459 -0.00819407 -0.0366533 -0.0332078 -0.00821265 -0.0291033 -0.0340617 -0.0086557 -0.0291033 -0.0347919 -0.00940449 -0.0366533 -0.0352028 -0.00940449 -0.0291033 -0.0352028 -0.0248244 -0.0366533 -0.0226181 -0.0248244 -0.0291033 -0.0226181 -0.0241828 -0.0366533 -0.0229753 -0.0237597 -0.0366533 -0.0235754 -0.0240942 -0.0291033 -0.0230611 -0.0237019 -0.0366533 -0.0246638 -0.0237019 -0.0291033 -0.0246638 -0.0238444 -0.0366533 -0.0250048 -0.024145 -0.0366533 -0.025394 -0.024145 -0.0291033 -0.025394 -0.0248937 -0.0366533 -0.0258049 -0.0248937 -0.0291033 -0.0258049 -0.0257476 -0.0291033 -0.0257863 -0.0332147 -0.0366533 0.0081916 -0.0230172 -0.0366533 0.0264246 -0.0226064 -0.0291033 0.0256758 -0.022625 -0.0291033 0.0248219 -0.023068 -0.0366533 0.0240917 -0.023068 -0.0291033 0.0240917 -0.0238168 -0.0291033 0.0236809 -0.0091347 -0.0287533 -0.0229736 -0.0074765 -0.0287533 -0.0188117 -0.00642141 -0.0287533 -0.0144576 -0.0102568 -0.0370033 -0.0244209 -0.0118708 -0.0370033 -0.0252861 -0.0118708 -0.0287533 -0.0252861 -0.0136973 -0.0370033 -0.0254192 -0.0136973 -0.0287533 -0.0254192 -0.0257852 -0.0370033 -0.0107526 -0.0233559 -0.0370033 -0.00811962 -0.0248507 -0.0287533 -0.00917766 -0.01473 -0.0287533 -0.0057794 -0.0233559 -0.0287533 -0.00811962 -0.0124411 -0.0370033 -0.00637616 -0.0116221 -0.0287533 -0.00725898 -0.0124045 -0.0287533 -0.00640343 -0.0135284 -0.0370033 -0.00585853 -0.0134404 -0.0287533 -0.00588281 -0.00776438 -0.0370033 -0.0112884 -0.0064482 -0.0287533 -0.0132537 -0.0064482 -0.0370033 -0.0132537 0.00930953 -0.0287533 -0.0127848 0.00930953 -0.0370033 -0.0127848 0.015328 -0.0287533 -0.0193925 0.0160203 -0.0370033 -0.0210879 0.0160203 -0.0287533 -0.0210879 0.0159625 -0.0370033 -0.0229183 0.0151646 -0.0370033 -0.0245667 0.0151646 -0.0287533 -0.0245667 0.0137648 -0.0287533 -0.0257474 -0.000325099 -0.0287533 -0.029196 0.00693738 -0.0370033 -0.0283606 0.0137648 -0.0370033 -0.0257474 -0.00358106 -0.0370033 -0.0277018 -0.00447768 -0.0370033 -0.026105 -0.00358106 -0.0287533 -0.0277018 -0.000699064 -0.0287533 -0.0139572 -0.000699064 -0.0370033 -0.0139572 0.00589339 -0.0370033 -0.0123632 0.000474964 -0.0370033 -0.0136894 0.00825353 -0.0370033 -0.012206 0.00816631 -0.0287533 -0.0121793 0.0070584 -0.0370033 -0.0120585 0.00589339 -0.0287533 -0.0123632 0.0200246 -0.0370033 0.00293834 0.024458 -0.0287533 0.00358326 0.0260132 -0.0287533 0.00341951 0.0251215 -0.0287533 -0.0148744 0.0251215 -0.0370033 -0.0148744 0.0280293 -0.0287533 -0.00816721 0.0280293 -0.0370033 -0.00816721 0.023881 -0.0287533 -0.0162216 0.0203683 -0.0287533 -0.0169252 0.012365 -0.0370033 -0.00985948 0.0153117 -0.0370033 -0.0132341 0.0187047 -0.0287533 -0.0161597 0.0117374 -0.0287533 -0.00757889 0.0136531 -0.0370033 -0.00107264 0.0120924 -0.0370033 -0.00642823 0.0120924 -0.0287533 -0.00642823 0.0157263 -0.0370033 0.00167504 0.0146971 -0.0287533 0.00104989 0.0146971 -0.0370033 0.00104989 0.0139718 -0.0370033 8.86278e-05 0.0136531 -0.0287533 -0.00107264 0.00912536 -0.0370033 0.022978 0.00746717 -0.0287533 0.0188161 0.0104151 -0.0287533 0.0245601 0.0122799 -0.0287533 0.02539 0.0210872 -0.0287533 0.0201956 0.0147206 -0.0370033 0.00578379 0.0191165 -0.0370033 0.00664846 0.0233466 -0.0287533 0.00812402 0.0116128 -0.0287533 0.00726337 0.0123952 -0.0370033 0.00640782 0.0134311 -0.0370033 0.0058872 0.00775505 -0.0370033 0.0112928 0.00775505 -0.0287533 0.0112928 0.00643886 -0.0287533 0.0132581 0.0069087 -0.0370033 0.0121494 -0.0153373 -0.0287533 0.0193969 -0.0153373 -0.0370033 0.0193969 -0.0137741 -0.0287533 0.0257518 -0.00694672 -0.0287533 0.028365 0.00149849 -0.0370033 0.029025 0.00149849 -0.0287533 0.029025 0.00235097 -0.0287533 0.0156455 0.00235097 -0.0370033 0.0156455 0.00380007 -0.0287533 0.0198847 0.00380007 -0.0370033 0.0198847 0.00068973 -0.0287533 0.0139616 -0.00590272 -0.0287533 0.0123676 -0.00931886 -0.0287533 0.0127892 -0.00826286 -0.0287533 0.0122104 -0.00931886 -0.0370033 0.0127892 -0.00817565 -0.0370033 0.0121836 -0.0200339 -0.0287533 -0.00293395 -0.0262818 -0.0370033 -0.00333079 -0.027838 -0.0370033 -0.00236554 -0.0262818 -0.0287533 -0.00333079 -0.0291892 -0.0287533 0.000952341 -0.0280386 -0.0370033 0.0081716 -0.0251309 -0.0287533 0.0148788 -0.0238157 -0.0370033 0.0162778 -0.0201137 -0.0287533 0.0168614 -0.0123743 -0.0370033 0.00986387 -0.0153211 -0.0287533 0.0132385 -0.0153211 -0.0370033 0.0132385 -0.018714 -0.0287533 0.0161641 -0.0121018 -0.0370033 0.00643262 -0.0117467 -0.0370033 0.00758328 -0.0117467 -0.0287533 0.00758328 -0.0118421 -0.0370033 0.00878369 -0.0157356 -0.0287533 -0.00167065 -0.0147064 -0.0287533 -0.0010455 -0.0139811 -0.0287533 -8.42358e-05 -0.0139811 -0.0370033 -8.42358e-05 -0.0136624 -0.0370033 0.00107703 0.0144726 -0.0273033 -0.029369 0.013743 -0.0273033 -0.0289629 0.0147949 -0.0273033 -0.027793 0.0178207 -0.0273033 -0.0272884 0.0194543 -0.0273033 -0.0300404 0.0193851 -0.0273033 -0.0282376 0.0202653 -0.0273033 -0.0298419 0.0186989 -0.0273033 -0.0326326 0.0160763 -0.0273033 -0.0332745 0.0176721 -0.0273033 -0.0341159 0.0144681 -0.0273033 -0.0333109 -0.00312978 -0.0273033 -0.0376181 -0.0032635 -0.0275033 -0.0377669 -0.00346407 -0.0275033 -0.0375725 -0.00422123 -0.0275033 -0.0364083 -0.00403623 -0.0273033 -0.0363323 -0.0043941 -0.0275033 -0.0358775 -0.004295 -0.0273033 -0.0347805 -0.00449465 -0.0275033 -0.0347687 -0.00385486 -0.0273033 -0.0332701 -0.0029182 -0.0275033 -0.0319368 -0.00134766 -0.0273033 -0.0315027 -0.019149 -0.0273033 -0.0333146 -0.0205236 -0.0273033 -0.0325494 -0.0218885 -0.0275033 -0.0296999 -0.0216888 -0.0273033 -0.0297118 -0.0212487 -0.0273033 -0.0282014 -0.0201968 -0.0273033 -0.0270315 -0.0332426 -0.0273033 -0.0192788 -0.0341228 -0.0273033 -0.0176746 -0.0344176 -0.0275033 -0.0166133 -0.0339526 -0.0275033 -0.0150175 -0.0331338 -0.0273033 -0.0142807 -0.0359854 -0.0273033 -0.00263012 -0.0374937 -0.0275033 -0.00201363 -0.0382664 -0.0273033 -0.000579071 -0.0386243 -0.0275033 -0.000124247 -0.0387248 -0.0275033 0.000984548 -0.0385252 -0.0273033 0.000972723 -0.0370332 -0.0273033 0.00365297 -0.0375793 -0.0275033 0.0034616 -0.0358843 -0.0275033 0.00439163 -0.0356107 -0.0275033 0.00444784 -0.0322912 -0.0273033 0.0155289 -0.0324249 -0.0275033 0.0153802 -0.0326255 -0.0275033 0.0155746 -0.0335135 -0.0275033 0.0192025 -0.033191 -0.0275033 0.0199742 -0.0330163 -0.0273033 0.019877 -0.0325106 -0.0275033 0.0208554 -0.0320796 -0.0275033 0.0212103 -0.030542 -0.0275033 0.0218417 -0.0288827 -0.0275033 0.0217434 -0.0195389 -0.0275033 0.0281037 -0.0202747 -0.0273033 0.0298463 -0.0202349 -0.0273033 0.0316757 -0.019424 -0.0275033 0.0333846 -0.0192857 -0.0273033 0.0332401 -0.0176814 -0.0273033 0.0341203 -0.00194103 -0.0275033 0.032411 -0.000232148 -0.0273033 0.0316001 -0.00287106 -0.0275033 0.0341059 -0.00263698 -0.0273033 0.0359829 -0.00282899 -0.0275033 0.0360389 -0.00250656 -0.0275033 0.0368106 -0.0018261 -0.0275033 0.0376918 -0.00139515 -0.0275033 0.0380466 -0.00013111 -0.0275033 0.0386218 -8.3562e-05 -0.0273033 0.0384276 0.00174586 -0.0273033 0.0383877 0.0171057 -0.0275033 0.0263393 0.0145228 -0.0275033 0.0290372 0.014717 -0.0273033 0.0290847 0.0145648 -0.0275033 0.0309701 0.0147569 -0.0273033 0.0309142 0.0173103 -0.0273033 0.0333588 0.0272462 -0.0273033 0.0159981 0.0279819 -0.0275033 0.0142556 0.0281264 -0.0273033 0.0143939 0.0272248 -0.0275033 0.0154198 0.027094 -0.0275033 0.0178835 0.0282352 -0.0273033 0.019392 0.0274164 -0.0275033 0.0186552 0.0285278 -0.0275033 0.0198913 0.0298394 -0.0273033 0.0202722 0.0316688 -0.0273033 0.0202324 0.0324336 -0.0273033 -0.00320397 0.0315534 -0.0273033 -0.00159974 0.0314012 -0.0275033 0.000285632 0.0315932 -0.0273033 0.000229677 0.0325424 -0.0273033 0.00179409 0.0341466 -0.0273033 0.00267432 0.0340991 -0.0275033 0.00286859 0.0289293 -0.0273033 -0.021547 0.0272204 -0.0275033 -0.0207361 0.0262904 -0.0275033 -0.0190411 0.0264846 -0.0273033 -0.0189936 0.0290779 -0.0273033 -0.0147195 -0.00713378 -0.0291033 0.0351398 -0.00672292 -0.0291033 0.034391 -0.00674151 -0.0291033 0.0335371 -0.0068042 -0.0285533 0.0324096 -0.00793334 -0.0291033 0.032396 -0.00780259 -0.0285533 0.0318618 0.0258922 -0.0285533 0.0263187 0.0264685 -0.0291033 0.0253477 0.0268794 -0.0291033 0.0245989 0.0273888 -0.0285533 0.0235911 0.025669 -0.0291033 0.0226039 0.0257997 -0.0285533 0.0220697 0.0248151 -0.0291033 0.0226225 0.0355945 -0.0291033 0.00871542 0.0361288 -0.0285533 0.00884618 0.036104 -0.0285533 0.00770764 0.0351329 -0.0291033 0.00713131 0.0355132 -0.0285533 0.00673403 0.0343841 -0.0291033 0.00672045 0.0345149 -0.0285533 0.00618622 0.0340593 -0.0291033 -0.00820579 0.0347895 -0.0291033 -0.00864883 0.0352003 -0.0291033 -0.00939762 0.0351817 -0.0291033 -0.0102515 0.0347387 -0.0291033 -0.0109817 0.0339899 -0.0291033 -0.0113926 0.0341207 -0.0285533 -0.0119268 0.0329821 -0.0285533 -0.011902 0.00770078 -0.0285533 -0.0361064 0.00785466 -0.0291033 -0.0355784 0.00883931 -0.0285533 -0.0361312 0.00990039 -0.0291033 -0.0344559 0.0104532 -0.0285533 -0.0334713 0.00991897 -0.0291033 -0.033602 0.00984261 -0.0291033 -0.0333675 0.00877791 -0.0291033 -0.0324102 0.0099054 -0.0285533 -0.0324729 -0.00918126 -0.0285533 -0.031488 -0.00819407 -0.0291033 -0.0332078 -0.00927373 -0.0285533 -0.035737 -0.0104123 -0.0285533 -0.0357123 -0.0236833 -0.0291033 -0.0238099 -0.0236969 -0.0285533 -0.0226808 -0.0324151 -0.0291033 0.0109354 -0.0320043 -0.0291033 0.0101866 -0.0320229 -0.0291033 0.00933266 -0.0324659 -0.0291033 0.00860246 -0.0320856 -0.0285533 0.00820518 -0.0332147 -0.0291033 0.0081916 -0.0340686 -0.0291033 0.00821018 -0.0330839 -0.0285533 0.00765737 -0.0235936 -0.0285533 0.0273957 -0.0230172 -0.0291033 0.0264246 -0.02262 -0.0285533 0.026805 -0.0220721 -0.0285533 0.0258066 -0.0220969 -0.0285533 0.024668 -0.0246707 -0.0291033 0.0236994 -0.0062242 -0.0285533 -0.0144909 -0.0102568 -0.0287533 -0.0244209 -0.0101277 -0.0285533 -0.0245737 -0.0154198 -0.0287533 -0.0247973 -0.0210965 -0.0287533 -0.0201912 -0.0254513 -0.0287533 -0.0143194 -0.0259977 -0.0287533 -0.0125715 -0.0256256 -0.0285533 -0.0144175 -0.0257852 -0.0287533 -0.0107526 -0.0191258 -0.0287533 -0.00664407 -0.0191782 -0.0285533 -0.00645104 -0.0147546 -0.0285533 -0.00558092 -0.00776438 -0.0287533 -0.0112884 -0.00691803 -0.0287533 -0.012145 -0.00625266 -0.0285533 -0.0132117 0.0125527 -0.0287533 -0.0158755 0.0159625 -0.0287533 -0.0229183 0.0153225 -0.0285533 -0.0246894 0.00693738 -0.0287533 -0.0283606 -0.00211204 -0.0287533 -0.0287953 -0.00447768 -0.0287533 -0.026105 -0.00466863 -0.0285533 -0.0261645 -0.00464659 -0.0287533 -0.0242815 -0.0038094 -0.0287533 -0.0198803 -0.00484522 -0.0285533 -0.0242581 -0.0023603 -0.0287533 -0.0156411 -0.00169097 -0.0287533 -0.01464 -0.00183335 -0.0285533 -0.0144996 0.000474964 -0.0287533 -0.0136894 0.00580728 -0.0285533 -0.0121827 0.00701291 -0.0287533 -0.0120619 0.00699678 -0.0285533 -0.0118625 0.00822227 -0.0285533 -0.0119872 0.0157263 -0.0287533 0.00167504 0.0156565 -0.0285533 0.00186246 0.0200246 -0.0287533 0.00293834 0.0199819 -0.0285533 0.00313373 0.0244432 -0.0285533 0.00378272 0.0282213 -0.0285533 -0.00822316 0.0252936 -0.0285533 -0.0149763 0.0239967 -0.0285533 -0.0163847 0.0221995 -0.0287533 -0.0169471 0.0203244 -0.0285533 -0.0171203 0.0153117 -0.0287533 -0.0132341 0.0151708 -0.0285533 -0.0133759 0.012365 -0.0287533 -0.00985948 0.0118327 -0.0287533 -0.0087793 0.0134537 -0.0285533 -0.00105694 0.0139718 -0.0287533 8.86278e-05 0.00641208 -0.0287533 0.014462 0.00621486 -0.0285533 0.0144953 0.00894526 -0.0285533 0.023065 0.00912536 -0.0287533 0.022978 0.0143186 -0.0287533 0.0252891 0.0122432 -0.0285533 0.0255866 0.0256163 -0.0285533 0.0144219 0.025442 -0.0287533 0.0143238 0.0208681 -0.0285533 0.020707 0.0259884 -0.0287533 0.0125759 0.0261875 -0.0285533 0.0125946 0.0257759 -0.0287533 0.010757 0.0248413 -0.0287533 0.00918205 0.0249883 -0.0285533 0.00904643 0.0191165 -0.0287533 0.00664846 0.0191688 -0.0285533 0.00645543 0.0114432 -0.0285533 0.00715737 0.0147206 -0.0287533 0.00578379 0.0124318 -0.0287533 0.00638055 0.00764177 -0.0285533 0.0111279 0.0069087 -0.0287533 0.0121494 -0.0125621 -0.0287533 0.0158799 -0.0127099 -0.0285533 0.0157453 -0.0160297 -0.0287533 0.0210923 -0.0159719 -0.0287533 0.0229227 -0.0161661 -0.0285533 0.0229705 -0.0151739 -0.0287533 0.0245711 0.000317961 -0.0285533 0.0294004 -0.00648715 -0.0285533 0.0286786 0.000315766 -0.0287533 0.0292004 0.00463726 -0.0287533 0.0242859 0.00253517 -0.0285533 0.0155676 0.00182401 -0.0285533 0.014504 0.00168164 -0.0287533 0.0146444 -0.000484297 -0.0287533 0.0136938 -0.00705445 -0.0285533 0.0118634 -0.0156658 -0.0285533 -0.00185807 -0.0199912 -0.0285533 -0.00312934 -0.0244673 -0.0287533 -0.00357887 -0.0244526 -0.0285533 -0.00377833 -0.027838 -0.0287533 -0.00236554 -0.0279765 -0.0285533 -0.00250985 -0.0288666 -0.0287533 -0.000850338 -0.0280386 -0.0287533 0.0081716 -0.025303 -0.0285533 0.0149807 -0.023928 -0.0285533 0.0164433 -0.0238157 -0.0287533 0.0162778 -0.02203 -0.0287533 0.0169835 -0.0220611 -0.0285533 0.017181 -0.0185944 -0.0285533 0.0163244 -0.0123743 -0.0287533 0.00986387 -0.0122148 -0.0285533 0.00998445 -0.0118421 -0.0287533 0.00878369 -0.0116492 -0.0285533 0.00883676 -0.0115479 -0.0285533 0.00756132 -0.0136624 -0.0287533 0.00107703 -0.0121018 -0.0287533 0.00643262 -0.0134631 -0.0285533 0.00106134 -0.0138016 -0.0285533 -0.000172506 -0.0145723 -0.0285533 -0.00119385 0.0158427 -0.0273033 -0.0340761 0.0143344 -0.0275033 -0.0334596 0.0135617 -0.0273033 -0.0320251 0.0131032 -0.0275033 -0.0304614 0.0133029 -0.0273033 -0.0304733 0.0146797 -0.0275033 -0.0276296 0.0162502 -0.0273033 -0.0271954 -0.00181114 -0.0275033 -0.0385754 -0.00346407 -0.0285533 -0.0375725 -0.0040296 -0.0275033 -0.0331728 -0.00435203 -0.0275033 -0.0339446 -0.00334914 -0.0275033 -0.0322916 -0.00165415 -0.0275033 -0.0313616 -0.00138055 -0.0275033 -0.0313054 -0.0206573 -0.0275033 -0.0326981 -0.0216151 -0.0275033 -0.0313395 -0.0218885 -0.0285533 -0.0296999 -0.0214234 -0.0285533 -0.0281041 -0.0214234 -0.0275033 -0.0281041 -0.020312 -0.0275033 -0.026868 -0.020312 -0.0285533 -0.026868 -0.0171151 -0.0285533 -0.0263349 -0.0187744 -0.0275033 -0.0262366 -0.019205 -0.0285533 -0.0335066 -0.0296442 -0.0275033 -0.0132483 -0.0296442 -0.0285533 -0.0132483 -0.0315771 -0.0275033 -0.0132063 -0.0313035 -0.0285533 -0.01315 -0.0328411 -0.0275033 -0.0137814 -0.0328411 -0.0285533 -0.0137814 -0.0332721 -0.0275033 -0.0141363 -0.034275 -0.0275033 -0.0157892 -0.0344176 -0.0285533 -0.0166133 -0.0343171 -0.0275033 -0.0177221 -0.0341877 -0.0285533 -0.018142 -0.0341442 -0.0275033 -0.0182529 -0.0336716 -0.0285533 -0.0190825 -0.033387 -0.0275033 -0.0194171 -0.0331865 -0.0285533 -0.0196115 -0.0317341 -0.0275033 -0.02042 -0.0371484 -0.0275033 0.00381643 -0.0382598 -0.0275033 0.0025804 -0.0385822 -0.0275033 0.00180867 -0.0386243 -0.0285533 -0.000124247 -0.0376943 -0.0275033 -0.00181924 -0.0384514 -0.0275033 -0.000655042 -0.0308156 -0.0285533 0.0217855 -0.0308156 -0.0275033 0.0217855 -0.0328095 -0.0285533 0.0205335 -0.0336561 -0.0275033 0.0183784 -0.0335555 -0.0275033 0.0172696 -0.0333827 -0.0275033 0.0167388 -0.0181488 -0.0285533 0.0341852 -0.017729 -0.0275033 0.0343146 -0.0190893 -0.0285533 0.0336692 -0.0204269 -0.0275033 0.0317316 -0.0204269 -0.0285533 0.0317316 -0.0204689 -0.0285533 0.0297987 -0.0204689 -0.0275033 0.0297987 -0.017886 -0.0275033 0.0271008 0.00180181 -0.0275033 0.0385798 -0.00297161 -0.0275033 0.0352147 -0.00297161 -0.0285533 0.0352147 -0.00269819 -0.0275033 0.0335752 -0.00269819 -0.0285533 0.0335752 -0.000288102 -0.0285533 0.0314081 0.0154528 -0.0285533 0.0273422 0.0154528 -0.0275033 0.0273422 0.0145648 -0.0285533 0.0309701 0.0155677 -0.0285533 0.032623 0.0155677 -0.0275033 0.032623 0.0172627 -0.0285533 0.0335531 0.0172627 -0.0275033 0.0335531 0.0296349 -0.0275033 0.0132527 0.0269513 -0.0285533 0.0170594 0.0269513 -0.0275033 0.0170594 0.0270519 -0.0275033 0.0159506 0.0274164 -0.0285533 0.0186552 0.0280969 -0.0275033 0.0195364 0.0300654 -0.0285533 0.0205227 0.0297918 -0.0275033 0.0204665 0.0317248 -0.0275033 0.0204244 0.0322892 -0.0275033 -0.00334228 0.0313591 -0.0275033 -0.00164729 0.0314012 -0.0285533 0.000285632 0.0324041 -0.0275033 0.00193856 0.0340991 -0.0285533 0.00286859 0.0290303 -0.0275033 -0.0145252 0.0273353 -0.0275033 -0.0154553 0.0263324 -0.0275033 -0.0171082 0.0263324 -0.0285533 -0.0171082 0.0272204 -0.0285533 -0.0207361 0.0288733 -0.0275033 -0.021739 -0.0385842 -0.0285533 -0.00304933 -0.0385822 -0.0285533 0.00180867 0.0341784 -0.0285533 0.0181464 0.00620414 -0.0285533 -0.0333788 0.0104428 -0.0285533 -0.0372609 0.00893179 -0.0285533 -0.0318822 0.00779325 -0.0285533 -0.0318574 0.00679486 -0.0285533 -0.0324052 -0.0172721 -0.0285533 -0.0335487 -0.0103198 -0.0285533 -0.0314632 -0.0155771 -0.0285533 -0.0326186 -0.0119089 -0.0285533 -0.0329846 -0.0106221 -0.0285533 -0.0364323 -0.00334914 -0.0285533 -0.0322916 -0.00765984 -0.0285533 -0.0330771 -0.00435203 -0.0285533 -0.0339446 -0.00768462 -0.0285533 -0.0342156 -0.0227959 -0.0285533 -0.0273699 -0.0259015 -0.0285533 -0.0263144 -0.024763 -0.0285533 -0.0263391 -0.0237646 -0.0285533 -0.0257913 -0.0231739 -0.0285533 -0.0248177 -0.0231491 -0.0285533 -0.0236792 -0.0256479 -0.0285533 -0.0220322 -0.0272082 -0.0285533 -0.0231321 -0.023686 -0.0285533 0.0231466 -0.02568 -0.0285533 0.0236476 -0.0226876 -0.0285533 0.0236944 -0.0162265 -0.0285533 0.0210569 -0.0155027 -0.0285533 0.0192844 -0.0163507 -0.0285533 0.0183376 -0.0195389 -0.0285533 0.0281037 -0.017886 -0.0285533 0.0271008 -0.0153319 -0.0285533 0.0246938 -0.0262442 -0.0285533 0.0244479 -0.0261313 -0.0285533 0.0263536 -0.0257583 -0.0285533 0.0288889 -0.0254767 -0.0285533 0.0270817 -0.0114525 -0.0285533 -0.00715297 -0.00160063 -0.0285533 -0.00547448 -0.0076511 -0.0285533 -0.0111235 -0.00675186 -0.0285533 -0.0120337 -0.0118151 -0.0285533 -0.0254782 -0.00895459 -0.0285533 -0.0230606 -0.00728594 -0.0285533 -0.0188724 -0.0298012 -0.0285533 -0.0204621 -0.0281062 -0.0285533 -0.019532 -0.0271033 -0.0285533 -0.0178791 -0.0270612 -0.0285533 -0.0159462 -0.0261968 -0.0285533 -0.0125902 -0.0351615 -0.0285533 -0.00999657 -0.0339526 -0.0285533 -0.0150175 -0.032747 -0.0285533 -0.0206286 -0.0285286 -0.0285533 -0.0234518 -0.0292392 -0.0285533 -0.0253559 -0.026757 -0.0285533 -0.0258381 -0.0259747 -0.0285533 -0.0106885 -0.0290518 -0.0285533 -0.00092577 -0.0249977 -0.0285533 -0.00904204 -0.0263495 -0.0285533 -0.00351897 -0.023435 -0.0285533 -0.00793591 -0.0133845 -0.0285533 -0.00569079 0.0122054 -0.0285533 -0.00998006 0.00943693 -0.0285533 -0.0126306 0.0127006 -0.0285533 -0.0157409 0.0154933 -0.0285533 -0.0192801 0.0185851 -0.0285533 -0.01632 0.0162172 -0.0285533 -0.0210525 0.0161568 -0.0285533 -0.0229661 0.0104284 -0.0285533 -0.0346098 0.0114544 -0.0285533 -0.0351033 0.0138591 -0.0285533 -0.0259238 0.00698493 -0.0285533 -0.0285549 0.00173113 -0.0285533 -0.0322122 -0.000327294 -0.0285533 -0.029396 -0.00219546 -0.0285533 -0.0289771 0.000278769 -0.0285533 -0.0314037 -0.00373125 -0.0285533 -0.0278339 0.000467962 -0.0285533 -0.0134895 -0.000779443 -0.0285533 -0.0137741 -0.00254451 -0.0285533 -0.0155632 -0.00400275 -0.0285533 -0.0198292 -0.0054422 -0.0285533 -0.0186571 -0.00853711 -0.0285533 -0.0292775 0.0262904 -0.0285533 -0.0190411 0.0273353 -0.0285533 -0.0154553 0.0290303 -0.0285533 -0.0145252 0.0222388 -0.0285533 -0.0171432 0.0116399 -0.0285533 -0.00883237 0.0115386 -0.0285533 -0.00755693 0.00576598 -0.0285533 -0.0076212 0.0137923 -0.0285533 0.000176898 0.0145629 -0.0285533 0.00119824 0.0134686 -0.0285533 0.00566939 0.0147453 -0.0285533 0.00558531 0.00624332 -0.0285533 0.0132161 0.00674252 -0.0285533 0.0120381 0.00727661 -0.0285533 0.0188768 0.0145228 -0.0285533 0.0290372 0.0143746 -0.0285533 0.0254811 0.00668346 -0.0285533 0.022953 0.0102936 -0.0285533 0.024719 0.015516 -0.0285533 0.0249715 0.0208486 -0.0285533 0.0325081 0.0217786 -0.0285533 0.0308131 0.0207336 -0.0285533 0.0272273 0.0268658 -0.0285533 0.025728 0.026849 -0.0285533 0.0278692 0.0274136 -0.0285533 0.0247296 0.026675 -0.0285533 0.0171272 0.0231398 -0.0285533 0.0236836 0.0212317 -0.0285533 0.0203339 0.0229338 -0.0285533 0.0183921 0.0267981 -0.0285533 0.0226175 0.0234256 -0.0285533 0.0079403 0.00895791 -0.0285533 0.00333216 0.0123134 -0.0285533 0.00621937 -0.00832427 -0.0285533 0.0120201 -0.00944627 -0.0285533 0.012635 -0.00621347 -0.0285533 0.0333832 -0.00618869 -0.0285533 0.0345217 -0.0067365 -0.0285533 0.0355201 -0.00768418 -0.0285533 0.0379326 -0.00699426 -0.0285533 0.0285593 -0.0138684 -0.0285533 0.0259282 -0.013308 -0.0285533 0.0287787 -0.00979659 -0.0285533 0.0323628 -0.0105218 -0.0285533 0.0341288 -0.0102478 -0.0285533 0.0350688 0.000142487 -0.0285533 0.038678 -0.00139515 -0.0285533 0.0380466 -0.00250656 -0.0285533 0.0368106 -0.00174046 -0.0285533 0.0322166 0.0043427 -0.0285533 0.033949 0.00155444 -0.0285533 0.029217 0.00333981 -0.0285533 0.032296 0.000770109 -0.0285533 0.0137785 0.00364079 -0.0285533 0.0125118 0.00399342 -0.0285533 0.0198336 -0.000477295 -0.0285533 0.0134939 -0.00581662 -0.0285533 0.0121871 -0.028128 -0.0285533 0.0141394 -0.0293133 -0.0285533 0.0144734 -0.0151801 -0.0285533 0.0133803 -0.0200578 -0.0285533 0.0170534 -0.0282306 -0.0285533 0.00822756 -0.0261992 -0.0285533 0.0179367 -0.00577531 -0.0285533 0.00762559 -0.0119252 -0.0285533 0.00633875 -0.00896724 -0.0285533 -0.00332777 0.0323301 -0.0285533 -0.00799178 0.0357346 -0.0285533 -0.00926687 0.0381841 -0.0285533 -0.00626763 0.0355739 -0.0285533 -0.0152246 0.0357098 -0.0285533 -0.0104054 0.0236323 -0.0285533 0.00668609 0.0276698 -0.0285533 0.00550952 0.0278274 -0.0285533 0.00264293 0.0324041 -0.0285533 0.00193856 0.0290057 -0.0285533 0.00101778 0.0313591 -0.0285533 -0.00164729 0.0297736 -0.0285533 -0.014421 0.0322892 -0.0285533 -0.00334228 0.0332358 -0.0285533 -0.00761987 0.0339421 -0.0285533 -0.00434517 0.0342131 -0.0285533 -0.00767775 0.0351191 -0.0285533 -0.011379 0.0326162 -0.0285533 -0.0155702 0.0351868 -0.0285533 -0.00826848 0.035875 -0.0285533 -0.00438724 0.0383413 -0.0285533 -0.00522042 0.038615 -0.0285533 0.000128639 0.0349922 -0.0285533 0.00337569 0.0385748 -0.0285533 0.00305372 0.0355809 -0.0285533 0.00984456 0.0325209 -0.0285533 0.00668723 0.0346073 -0.0285533 0.0104353 0.0367235 -0.0285533 0.0121977 0.0332628 -0.0285533 0.0141407 0.0342657 -0.0285533 0.0157936 0.0320696 -0.0285533 0.00939321 0.0296349 -0.0285533 0.0132527 0.0259654 -0.0285533 0.0106929 0.0281825 -0.0285533 0.0140612 0.0272248 -0.0285533 0.0154198 0.0285278 -0.0285533 0.0198913 0.0333777 -0.0285533 0.0194215 0.0317248 -0.0285533 0.0204244 0.0191956 -0.0285533 0.033511 0.0196095 -0.0285533 0.0333635 0.00180181 -0.0285533 0.0385798 0.0108226 -0.0285533 0.0371567 0.00345474 -0.0285533 0.0375769 -0.0165384 -0.0285533 0.0349926 -0.0157961 -0.0285533 0.0342725 -0.017729 -0.0285533 0.0343146 -0.0131126 -0.0285533 0.0304658 -0.0143437 -0.0285533 0.033464 -0.0244317 -0.0285533 0.030019 -0.019424 -0.0285533 0.0333846 -0.0264726 -0.0285533 0.0195763 -0.0260785 -0.0285533 0.0211724 -0.0277106 -0.0285533 0.021648 -0.0274303 -0.0285533 0.0209349 -0.0288827 -0.0285533 0.0217434 -0.0309054 -0.0285533 0.023301 -0.0325106 -0.0285533 0.0208554 -0.0312679 -0.0285533 0.000542885 -0.0293891 -0.0285533 0.000958849 -0.0315413 -0.0285533 0.00218248 -0.0313199 -0.0285533 0.00318605 -0.03147 -0.0285533 0.0103173 -0.0358843 -0.0285533 0.00439163 -0.0339514 -0.0285533 0.00434956 -0.0324991 -0.0285533 0.00354106 -0.0314948 -0.0285533 0.00917879 -0.0356421 -0.0285533 0.00895861 -0.0381934 -0.0285533 0.00627203 -0.0358031 -0.0285533 0.00992437 -0.0320179 -0.0285533 0.0113157 -0.0326255 -0.0285533 0.0155746 -0.0351533 -0.0285533 0.0161968 -0.0329915 -0.0285533 0.0119064 -0.0335135 -0.0285533 0.0192025 -0.0335555 -0.0285533 0.0172696 -0.0350779 -0.0285533 0.00815837 -0.0375793 -0.0285533 0.0034616 -0.0383506 -0.0285533 0.00522481 -0.034382 -0.0285533 -0.00292041 -0.0328444 -0.0285533 -0.002289 -0.0367936 -0.0285533 -0.00952095 -0.0376943 -0.0285533 -0.00181924 -0.0360413 -0.0285533 -0.00282213 -0.0206573 -0.0285533 -0.0326981 -0.0268583 -0.0285533 -0.0278648 -0.0216151 -0.0285533 -0.0313395 -0.0155254 -0.0285533 -0.0249671 -0.021241 -0.0285533 -0.0203295 -0.0187744 -0.0285533 -0.0262366 -0.0221922 -0.0285533 -0.0252983 -0.0145321 -0.0285533 -0.0290328 -0.0137246 -0.0285533 -0.0256174 -0.0166509 -0.0285533 -0.0349348 -0.0180011 -0.0285533 -0.0342588 -0.0196188 -0.0285533 -0.0333591 -0.00138288 -0.0285533 -0.0386733 -0.00181114 -0.0285533 -0.0385754 -0.00162564 -0.0285533 -0.0386638 -0.00323068 -0.0285533 -0.0385631 -0.00473259 -0.0285533 -0.0384079 -0.0043941 -0.0285533 -0.0358775 -0.00827534 -0.0285533 -0.0351892 -0.00165415 -0.0285533 -0.0313616 -0.00820765 -0.0285533 -0.0320787 -0.00914082 -0.0285533 -0.0313492 0.00451423 -0.0285533 -0.0353284 0.00511793 -0.0285533 -0.0332568 -0.00015182 -0.0285533 -0.0386736 0.00138582 -0.0285533 -0.0380422 0.0098377 -0.0285533 -0.0355834 0.0143344 -0.0285533 -0.0334596 0.0157867 -0.0285533 -0.0342681 0.0177197 -0.0285533 -0.0343102 0.0181395 -0.0285533 -0.0341808 0.0194147 -0.0285533 -0.0333802 0.0244223 -0.0285533 -0.0300147 0.0204175 -0.0285533 -0.0317272 0.0259092 -0.0285533 -0.0277932 0.0185868 -0.0285533 -0.0256594 0.0178767 -0.0285533 -0.0270964 0.0288733 -0.0285533 -0.021739 0.0325012 -0.0285533 -0.020851 0.0015913 -0.0285533 0.00547887 0.0119158 -0.0285533 -0.00633436 0.0133766 -0.0285533 -0.032101 0.0133766 -0.0275033 -0.032101 0.0131032 -0.0285533 -0.0304614 0.0135683 -0.0285533 -0.0288656 0.0135683 -0.0275033 -0.0288656 0.0146797 -0.0285533 -0.0276296 0.0162173 -0.0285533 -0.0269982 0.0162173 -0.0275033 -0.0269982 0.0178767 -0.0275033 -0.0270964 -0.0108319 -0.0285533 -0.0371524 -0.020536 -0.0285533 -0.0328026 -0.019409 -0.0285533 -0.0334816 -0.0312266 -0.0285533 -0.0228644 -0.0288345 -0.0285533 -0.0258151 -0.0387836 -0.0287533 -0.0030651 -0.0367328 -0.0285533 -0.0121933 -0.0386801 -0.0285533 0.00138041 -0.0383908 -0.0287533 0.00630443 -0.0387035 -0.0285533 0.00030787 -0.0355832 -0.0285533 0.015229 -0.033366 -0.0285533 0.0196163 -0.0357671 -0.0287533 0.0153077 -0.0310651 -0.0287533 0.0234215 -0.0245579 -0.0287533 0.0301742 0.000301008 -0.0285533 0.038701 -0.00367287 -0.0285533 0.038528 -0.0110401 -0.0285533 0.0370954 0.00137355 -0.0285533 0.0386776 0.00161631 -0.0285533 0.0386682 0.0108785 -0.0287533 0.0373488 0.0169344 -0.0385033 -0.0306884 0.0169268 -0.0385033 -0.0306432 0.0167574 -0.0385033 -0.0307534 0.0168072 -0.0385033 -0.0305824 0.0167606 -0.0385033 -0.030608 0.0169005 -0.0385033 -0.0306058 0.0168029 -0.0385033 -0.030781 0.0298195 -0.0385033 -0.0181244 0.0350858 -0.0385033 -0.000788104 0.0348871 -0.0385033 -0.00078378 0.0348883 -0.0385033 -0.000730546 0.0349159 -0.0385033 -0.000685023 0.035087 -0.0385033 -0.00073487 0.0350115 -0.0385033 -0.00085924 0.0349127 -0.0385033 -0.000830461 0.0350158 -0.0385033 -0.000660568 0.0307086 -0.0385033 0.0169373 0.0306055 -0.0385033 0.0167674 0.0307825 -0.0385033 0.0168325 0.0307697 -0.0385033 0.0167885 0.0306554 -0.0385033 0.0169385 0.030581 -0.0385033 0.0168673 0.0305799 -0.0385033 0.0168141 0.0306967 -0.0385033 0.0167371 0.0307391 -0.0385033 0.0167545 0.030775 -0.0385033 0.0168776 0.0181795 -0.0385033 0.0300239 0.01821 -0.0385033 0.0298411 0.0182534 -0.0385033 0.0299191 0.0181262 -0.0385033 0.0300251 0.0180764 -0.0385033 0.029854 0.000785633 -0.0385033 0.0350927 0.000773774 -0.0385033 0.0348924 0.000816122 -0.0385033 0.0349098 0.000732399 -0.0385033 0.0350938 0.000685717 -0.0385033 0.0350682 0.000682552 -0.0385033 0.0349228 -0.0169437 -0.0385033 0.0306928 -0.0169098 -0.0385033 0.0306102 -0.0168698 -0.0385033 0.0305879 -0.0167411 -0.0385033 0.0307111 -0.0167699 -0.0385033 0.0306124 -0.0168122 -0.0385033 0.0307854 -0.0168166 -0.0385033 0.0305868 -0.0168579 -0.0385033 0.0307881 -0.0299964 -0.0385033 0.0180811 -0.0298289 -0.0385033 0.0181288 -0.0299564 -0.0385033 0.0180588 -0.0299869 -0.0385033 0.0182416 -0.0298533 -0.0385033 0.0182287 -0.0350707 -0.0385033 0.00069258 -0.0349371 -0.0385033 0.000679643 -0.0348937 -0.0385033 0.000757635 -0.0350208 -0.0385033 0.000863632 -0.0349676 -0.0385033 0.000862474 -0.0350963 -0.0385033 0.000739262 -0.030618 -0.0385033 -0.0169085 -0.0306647 -0.0385033 -0.0169341 -0.0307579 -0.0385033 -0.0169107 -0.0307843 -0.0385033 -0.0168732 -0.0307484 -0.0385033 -0.0167501 -0.0181888 -0.0385033 -0.0300195 -0.0181312 -0.0385033 -0.029822 -0.0180857 -0.0385033 -0.0298496 -0.0180889 -0.0385033 -0.0299951 -0.0181356 -0.0385033 -0.0300207 -0.0180613 -0.0385033 -0.0299495 -0.0181845 -0.0385033 -0.0298208 -0.000866103 -0.0385033 -0.035014 -0.000663503 -0.0385033 -0.0349956 -0.00069741 -0.0385033 -0.034913 -0.000737409 -0.0385033 -0.0348908 -0.000749267 -0.0385033 -0.035091 -0.019198 -0.0796033 0.0277858 -0.0196181 -0.0796033 0.0263443 -0.0188889 -0.0796033 0.0265228 -0.01991 -0.0796033 0.0265068 -0.0201574 -0.0796033 0.0271095 -0.0188658 -0.0796033 0.0275842 -0.0192296 -0.0796033 0.0263359 -0.0186873 -0.0796033 0.026855 -0.0186788 -0.0796033 0.0272436 -0.020064 -0.0796033 0.0274302 -0.0201025 -0.0796033 0.0267799 -0.019408 -0.0800544 0.0270651 -0.0195315 -0.0796033 0.0278056 -0.0198406 -0.0796033 0.0276787 0.0314417 -0.0796033 0.0129241 0.0314186 -0.0796033 0.0118627 0.0301787 -0.0796033 0.0126149 0.0301702 -0.0796033 0.0122264 0.0311095 -0.0796033 0.0131256 0.0316286 -0.0796033 0.0125834 0.0307209 -0.0796033 0.0131341 0.0316202 -0.0796033 0.0121949 0.0303803 -0.0796033 0.0129472 0.0310779 -0.0796033 0.0116757 0.0308994 -0.0800544 0.0124049 0.0306894 -0.0796033 0.0116842 0.0303572 -0.0796033 0.0118858 -0.0613427 -0.0666033 0.0468427 -0.0613427 -0.0418033 0.0468427 -0.0620173 -0.0418033 0.0453933 -0.0620173 -0.0666033 0.0453933 -0.0622817 -0.0418033 0.0455868 -0.0622817 -0.0666033 0.0455868 -0.0631951 -0.0418033 0.0443121 -0.0631951 -0.0666033 0.0443121 -0.0317851 -0.0666033 0.070066 -0.0306578 -0.0666033 0.0704964 -0.0330623 -0.0666033 0.0697416 -0.0306578 -0.0418033 0.0704964 -0.0297047 -0.0418033 0.0712363 -0.0317851 -0.0418033 0.070066 -0.0330623 -0.0418033 0.0697416 -0.0297047 -0.0666033 0.0712363 -0.0420276 -0.0418033 0.064446 -0.0420276 -0.0666033 0.064446 -0.0429962 -0.0666033 0.0637264 -0.0429962 -0.0418033 0.0637264 -0.0441323 -0.0666033 0.0633199 -0.0441323 -0.0418033 0.0633199 -0.0410679 -0.0418033 0.065349 -0.0410679 -0.0666033 0.065349 -0.00656149 -0.0666033 0.0769008 -0.00343187 -0.0418033 0.0771037 -0.00343187 -0.0666033 0.0771037 -0.00499771 -0.0418033 0.0770182 -0.00499771 -0.0666033 0.0770182 -0.00497651 -0.0666033 0.0766912 -0.00497651 -0.0418033 0.0766912 -0.00656149 -0.0418033 0.0769008 0.0468359 -0.0418033 0.0613402 0.0468359 -0.0666033 0.0613402 0.0453864 -0.0666033 0.0620149 0.04558 -0.0418033 0.0622793 0.04558 -0.0666033 0.0622793 0.0443052 -0.0666033 0.0631926 0.0443052 -0.0418033 0.0631926 0.0453864 -0.0418033 0.0620149 0.0697347 -0.0666033 0.0330599 0.0712295 -0.0666033 0.0297022 0.0704895 -0.0418033 0.0306554 0.0704895 -0.0666033 0.0306554 0.0700591 -0.0666033 0.0317827 0.0700591 -0.0418033 0.0317827 0.0697347 -0.0418033 0.0330599 0.0712295 -0.0418033 0.0297022 0.0637195 -0.0666033 0.0429937 0.0637195 -0.0418033 0.0429937 0.0653421 -0.0666033 0.0410654 0.0644391 -0.0418033 0.0420251 0.0644391 -0.0666033 0.0420251 0.0633131 -0.0666033 0.0441299 0.0653421 -0.0418033 0.0410654 0.0633131 -0.0418033 0.0441299 0.0770968 -0.0418033 0.0034294 0.0766843 -0.0666033 0.00497404 0.076894 -0.0666033 0.00655902 0.0766843 -0.0418033 0.00497404 0.0770113 -0.0418033 0.00499524 0.0770968 -0.0666033 0.0034294 0.0770113 -0.0666033 0.00499524 0.076894 -0.0418033 0.00655902 0.0309815 -0.0385033 0.00638174 0.0303684 -0.0385033 0.00604532 0.0304252 -0.0385033 0.00865477 0.0300472 -0.0376915 0.00735765 0.0286985 -0.0385033 0.00743754 0.0288667 -0.0385033 0.00801481 0.0313443 -0.0385033 0.00697966 0.0296692 -0.0385033 0.00606053 0.0313595 -0.0385033 0.00767886 0.0310231 -0.0385033 0.008292 0.0298249 -0.0385033 0.00869032 0.0291438 -0.0385033 0.006353 0.0287974 -0.0385033 0.00684444 0.0292687 -0.0385033 0.00846192 -0.0214006 -0.0376915 0.0223501 -0.0202201 -0.0385033 0.021693 -0.0206221 -0.0385033 0.0212458 -0.0204972 -0.0385033 0.0233548 -0.0201508 -0.0385033 0.0228633 -0.0200519 -0.0385033 0.0222702 -0.0211784 -0.0385033 0.0210174 -0.0226977 -0.0385033 0.0227281 -0.0210226 -0.0385033 0.0236472 -0.0223349 -0.0385033 0.023326 -0.0217218 -0.0385033 0.0236625 -0.0223765 -0.0385033 0.0214158 -0.0217786 -0.0385033 0.021053 -0.0227129 -0.0385033 0.0220289 0.057891 -0.0390533 -0.00937423 0.0565011 -0.0401033 -0.0157115 0.0565011 -0.0390533 -0.0157115 0.0579613 -0.0401033 -0.0138485 0.0579297 -0.0390533 -0.00945063 0.057891 -0.0387533 -0.00937423 0.056521 -0.0390533 -0.0156397 0.0565881 -0.0390533 -0.0155865 0.056521 -0.0387533 -0.0156397 0.0579613 -0.0387533 -0.0138485 0.0584522 -0.0387533 -0.0116031 0.0584522 -0.0401033 -0.0116031 0.0572917 -0.0387533 -0.0125257 0.0579028 -0.0390533 -0.0093007 0.0579028 -0.0401033 -0.0093007 0.0579297 -0.0401033 -0.00945063 0.0565881 -0.0401033 -0.0155865 0.0586452 -0.0401033 0.000116283 0.0586452 -0.0390533 0.000116283 0.0582654 -0.0401033 0.00666753 0.058645 -0.0390533 0.000190767 0.0594156 -0.0387533 0.00459874 0.0583317 -0.0390533 0.00653041 0.058645 -0.0387533 0.000190767 0.0595486 -0.0401033 0.00230415 0.0594156 -0.0401033 0.00459874 0.0582738 -0.0387533 0.00659353 0.058547 -0.0387533 0.00339722 0.0595486 -0.0387533 0.00230415 0.0586952 -0.0390533 0.00026015 0.0582654 -0.0390533 0.00666753 0.0582738 -0.0390533 0.00659353 0.0583317 -0.0401033 0.00653041 0.0586952 -0.0401033 0.00026015 0.0544071 -0.0401033 0.0220273 0.055972 -0.0401033 0.0204597 0.0567192 -0.0401033 0.0182861 0.0564489 -0.0401033 0.0160876 0.0543343 -0.0390533 0.0220724 0.0543063 -0.0390533 0.0221414 0.0543063 -0.0401033 0.0221414 0.0564395 -0.0401033 0.0159356 0.0564395 -0.0390533 0.0159356 0.0544071 -0.0390533 0.0220273 0.0543343 -0.0387533 0.0220724 0.0564193 -0.0387533 0.0160073 0.0564193 -0.0390533 0.0160073 0.0567192 -0.0387533 0.0182861 0.0564489 -0.0390533 0.0160876 0.055972 -0.0387533 0.0204597 0.0554598 -0.0387533 0.0190684 0.048259 -0.0387533 0.0333255 0.0500088 -0.0390533 0.0306368 0.0463192 -0.0401033 0.0359734 0.0500477 -0.0390533 0.0305732 0.0463648 -0.0390533 0.0359145 0.0464471 -0.0390533 0.0358907 0.0463648 -0.0387533 0.0359145 0.0500088 -0.0387533 0.0306368 0.0500156 -0.0390533 0.0307221 0.0496828 -0.0401033 0.032912 0.0483769 -0.0387533 0.0348034 0.0483769 -0.0401033 0.0348034 0.0496828 -0.0387533 0.032912 0.0463192 -0.0390533 0.0359734 0.0464471 -0.0401033 0.0358907 0.0500156 -0.0401033 0.0307221 0.0500477 -0.0401033 0.0305732 0.0399436 -0.0401033 0.0429435 0.0398726 -0.0390533 0.0430783 0.0350419 -0.0401033 0.0470923 0.0398891 -0.0390533 0.0429942 0.0389613 -0.0401033 0.0450971 0.0371935 -0.0387533 0.046566 0.0371935 -0.0401033 0.046566 0.0398891 -0.0387533 0.0429942 0.0389613 -0.0387533 0.0450971 0.0374787 -0.0387533 0.0451111 0.0349563 -0.0387533 0.0470931 0.0348965 -0.0401033 0.0471375 0.0350419 -0.0390533 0.0470923 0.0348965 -0.0390533 0.0471375 0.0349563 -0.0390533 0.0470931 0.0398726 -0.0401033 0.0430783 0.0399436 -0.0390533 0.0429435 0.0239185 -0.0387533 0.0535513 0.0268106 -0.0387533 0.0521632 0.0208853 -0.0401033 0.0548058 0.0209549 -0.0390533 0.0547792 0.0210375 -0.0390533 0.0548016 0.0268106 -0.0390533 0.0521632 0.0253499 -0.0387533 0.0539377 0.0267721 -0.0390533 0.0522397 0.0253499 -0.0401033 0.0539377 0.0232513 -0.0387533 0.0548753 0.0209549 -0.0387533 0.0547792 0.0208853 -0.0390533 0.0548058 0.0232513 -0.0401033 0.0548753 0.0210375 -0.0401033 0.0548016 0.0267721 -0.0401033 0.0522397 0.0268768 -0.0401033 0.0521291 0.0268768 -0.0390533 0.0521291 0.00539897 -0.0387533 0.0584027 0.008584 -0.0387533 0.0580199 0.0117433 -0.0390533 0.0574635 0.0117433 -0.0387533 0.0574635 0.0053248 -0.0390533 0.0584096 0.00539897 -0.0390533 0.0584027 0.0053248 -0.0401033 0.0584096 0.00547254 -0.0390533 0.0584466 0.00758433 -0.0387533 0.0591148 0.0116856 -0.0390533 0.0575268 0.009858 -0.0387533 0.0587782 0.00547254 -0.0401033 0.0584466 0.0118163 -0.0401033 0.0574486 0.0118163 -0.0390533 0.0574486 0.0116856 -0.0401033 0.0575268 0.00758433 -0.0401033 0.0591148 0.009858 -0.0401033 0.0587782 -0.0104987 -0.0401033 0.057757 -0.0104987 -0.0390533 0.057757 -0.0041209 -0.0401033 0.0585076 -0.0041209 -0.0390533 0.0585076 -0.010631 -0.0390533 0.0576815 -0.0105577 -0.0390533 0.057695 -0.010631 -0.0401033 0.0576815 -0.00419519 -0.0390533 0.0585023 -0.00738749 -0.0387533 0.0581857 -0.00636531 -0.0401033 0.0592596 -0.00636531 -0.0387533 0.0592596 -0.00864548 -0.0401033 0.0589702 -0.00419519 -0.0387533 0.0585023 -0.00864548 -0.0387533 0.0589702 -0.0105577 -0.0387533 0.057695 -0.00426784 -0.0401033 0.0585477 -0.00426784 -0.0390533 0.0585477 -0.0198229 -0.0390533 0.0552024 -0.0198229 -0.0387533 0.0552024 -0.0257317 -0.0390533 0.0527084 -0.0197528 -0.0401033 0.0552275 -0.0197528 -0.0390533 0.0552275 -0.0199051 -0.0401033 0.0552264 -0.0257317 -0.0387533 0.0527084 -0.0256916 -0.0390533 0.0527841 -0.0256916 -0.0401033 0.0527841 -0.0199051 -0.0390533 0.0552264 -0.0221169 -0.0387533 0.0553461 -0.0221169 -0.0401033 0.0553461 -0.0242344 -0.0401033 0.0544523 -0.0242344 -0.0387533 0.0544523 -0.0228114 -0.0387533 0.0540362 -0.0257986 -0.0390533 0.0526757 -0.0257986 -0.0401033 0.0526757 -0.0340665 -0.0390533 0.0478095 -0.0390532 -0.0390533 0.0437633 -0.0389794 -0.0390533 0.0438965 -0.0390532 -0.0401033 0.0437633 -0.0380264 -0.0401033 0.045896 -0.0362285 -0.0401033 0.047328 -0.0389794 -0.0401033 0.0438965 -0.0340665 -0.0401033 0.0478095 -0.0339201 -0.0401033 0.0478516 -0.0339809 -0.0390533 0.0478085 -0.0339201 -0.0390533 0.0478516 -0.0389976 -0.0390533 0.0438128 -0.0339809 -0.0387533 0.0478085 -0.0380264 -0.0387533 0.045896 -0.0362285 -0.0387533 0.047328 -0.0365439 -0.0387533 0.0458793 -0.0389976 -0.0387533 0.0438128 -0.0494118 -0.0401033 0.0316053 -0.0456189 -0.0390533 0.036869 -0.0494118 -0.0390533 0.0316053 -0.0456189 -0.0387533 0.036869 -0.0493716 -0.0390533 0.031668 -0.0493716 -0.0387533 0.031668 -0.0493767 -0.0390533 0.0317535 -0.0457016 -0.0390533 0.0368469 -0.0476536 -0.0387533 0.0357999 -0.0489984 -0.0387533 0.033936 -0.0489984 -0.0401033 0.033936 -0.0493767 -0.0401033 0.0317535 -0.0475664 -0.0387533 0.0343199 -0.045572 -0.0390533 0.0369269 -0.0476536 -0.0401033 0.0357999 -0.0457016 -0.0401033 0.0368469 -0.045572 -0.0401033 0.0369269 -0.053874 -0.0390533 0.0231953 -0.0561061 -0.0390533 0.0171035 -0.0539477 -0.0401033 0.0231517 -0.0561123 -0.0390533 0.0172557 -0.053874 -0.0387533 0.0231953 -0.0539477 -0.0390533 0.0231517 -0.0555447 -0.0387533 0.0216169 -0.0563369 -0.0387533 0.0194593 -0.0563369 -0.0401033 0.0194593 -0.0561123 -0.0401033 0.0172557 -0.0550615 -0.0387533 0.0202153 -0.0560843 -0.0387533 0.0171747 -0.0561061 -0.0401033 0.0171035 -0.0560843 -0.0390533 0.0171747 -0.0555447 -0.0401033 0.0216169 -0.0538445 -0.0401033 0.0232637 -0.0538445 -0.0390533 0.0232637 -0.0316379 -0.0796033 -0.012579 -0.0316295 -0.0796033 -0.0121905 -0.031451 -0.0796033 -0.0129197 -0.0310872 -0.0796033 -0.0116713 -0.0309088 -0.0800544 -0.0124005 -0.0303896 -0.0796033 -0.0129428 -0.0311188 -0.0796033 -0.0131213 -0.0314279 -0.0796033 -0.0118583 -0.0301796 -0.0796033 -0.012222 -0.0303665 -0.0796033 -0.0118814 -0.0306987 -0.0796033 -0.0116798 -0.030188 -0.0796033 -0.0126106 -0.0307303 -0.0796033 -0.0131297 0.0201279 -0.0796033 -0.0268822 0.0196087 -0.0796033 -0.0263399 0.019941 -0.0796033 -0.0265415 0.0193987 -0.0800544 -0.0270607 0.0195772 -0.0796033 -0.0277899 0.0191887 -0.0796033 -0.0277814 0.0199179 -0.0796033 -0.0276029 0.0187428 -0.0796033 -0.0266955 0.0201194 -0.0796033 -0.0272707 0.0192752 -0.0796033 -0.0263202 0.0187042 -0.0796033 -0.0273458 0.0186493 -0.0796033 -0.0270163 0.0188967 -0.0796033 -0.0276189 0.0189662 -0.0796033 -0.0264471 0.000696699 -0.0799533 -0.048912 0.00109527 -0.0799533 -0.0491339 0.00109527 -0.0796033 -0.0491339 0.0013581 -0.0799533 -0.0495067 0.0013581 -0.0796033 -0.0495067 0.00143314 -0.0799533 -0.0499567 0.00143314 -0.0796033 -0.0499567 0.00100051 -0.0799533 -0.0507338 0.00130551 -0.0796033 -0.0503946 0.000578532 -0.0796033 -0.0509071 0.000123162 -0.0799533 -0.0508801 0.000578532 -0.0799533 -0.0509071 0.00130551 -0.0799533 -0.0503946 0.00100051 -0.0796033 -0.0507338 -0.000585681 -0.0796033 -0.0501398 -0.000298913 -0.0796033 -0.0491557 -0.000574137 -0.0796033 -0.0496093 0.00040993 -0.0805692 -0.0498961 -0.000585681 -0.0799533 -0.0501398 -0.000574137 -0.0799533 -0.0496093 -0.000330452 -0.0799533 -0.0506049 -0.000298913 -0.0799533 -0.0491557 0.000123162 -0.0796033 -0.0508801 -0.000330452 -0.0796033 -0.0506049 0.000166245 -0.0799533 -0.0489005 0.000166245 -0.0796033 -0.0489005 0.000696699 -0.0796033 -0.048912 -0.0268731 -0.0796033 -0.0408779 -0.0261643 -0.0799533 -0.0416182 -0.026451 -0.0796033 -0.0426023 -0.0269162 -0.0799533 -0.0428575 -0.0269162 -0.0796033 -0.0428575 -0.0274466 -0.0796033 -0.042846 -0.0261758 -0.0799533 -0.0421487 -0.0271599 -0.0805692 -0.0418619 -0.0264195 -0.0799533 -0.0411531 -0.0274466 -0.0799533 -0.042846 -0.026451 -0.0799533 -0.0426023 -0.028108 -0.0796033 -0.0422513 -0.0273285 -0.0796033 -0.0408509 -0.0281831 -0.0796033 -0.0418013 -0.0261643 -0.0796033 -0.0416182 -0.0261758 -0.0796033 -0.0421487 -0.0264195 -0.0796033 -0.0411531 -0.0273285 -0.0799533 -0.0408509 -0.0278452 -0.0799533 -0.0426241 -0.028108 -0.0799533 -0.0422513 -0.0278452 -0.0796033 -0.0426241 -0.0281831 -0.0799533 -0.0418013 -0.0280555 -0.0799533 -0.0413634 -0.0280555 -0.0796033 -0.0413634 -0.0277505 -0.0799533 -0.0410242 -0.0277505 -0.0796033 -0.0410242 -0.0268731 -0.0799533 -0.0408779 -0.0468452 -0.0418033 -0.0613358 -0.0453233 -0.0666033 -0.0620647 -0.0443145 -0.0666033 -0.0631882 -0.0466703 -0.0666033 -0.0613826 -0.0468452 -0.0666033 -0.0613358 -0.0443145 -0.0418033 -0.0631882 -0.0466703 -0.0418033 -0.0613826 -0.0453233 -0.0418033 -0.0620647 -0.0700684 -0.0666033 -0.0317783 -0.0704989 -0.0666033 -0.030651 -0.0712388 -0.0418033 -0.0296978 -0.0704989 -0.0418033 -0.030651 -0.069744 -0.0666033 -0.0330555 -0.0712388 -0.0666033 -0.0296978 -0.0700684 -0.0418033 -0.0317783 -0.069744 -0.0418033 -0.0330555 -0.0644485 -0.0418033 -0.0420207 -0.0637289 -0.0666033 -0.0429893 -0.0637289 -0.0418033 -0.0429893 -0.0633224 -0.0666033 -0.0441255 -0.0644485 -0.0666033 -0.0420207 -0.0653515 -0.0666033 -0.041061 -0.0653515 -0.0418033 -0.041061 -0.0633224 -0.0418033 -0.0441255 -0.0771062 -0.0666033 -0.00342501 -0.0766937 -0.0666033 -0.00496965 -0.0769033 -0.0666033 -0.00655462 -0.0770206 -0.0418033 -0.00499084 -0.0770206 -0.0666033 -0.00499084 -0.0769033 -0.0418033 -0.00655462 -0.0766937 -0.0418033 -0.00496965 -0.0771062 -0.0418033 -0.00342501 0.0613334 -0.0666033 -0.0468384 0.062008 -0.0666033 -0.0453889 0.0622724 -0.0666033 -0.0455824 0.0631857 -0.0666033 -0.0443077 0.0613334 -0.0418033 -0.0468384 0.0622724 -0.0418033 -0.0455824 0.0631857 -0.0418033 -0.0443077 0.062008 -0.0418033 -0.0453889 0.0296953 -0.0666033 -0.0712319 0.033053 -0.0418033 -0.0697372 0.0306485 -0.0418033 -0.070492 0.0296953 -0.0418033 -0.0712319 0.0317758 -0.0418033 -0.0700616 0.033053 -0.0666033 -0.0697372 0.0306485 -0.0666033 -0.070492 0.0317758 -0.0666033 -0.0700616 0.0410585 -0.0666033 -0.0653446 0.0410585 -0.0418033 -0.0653446 0.0420183 -0.0418033 -0.0644416 0.0429869 -0.0418033 -0.063722 0.0429869 -0.0666033 -0.063722 0.044123 -0.0666033 -0.0633156 0.044123 -0.0418033 -0.0633156 0.0420183 -0.0666033 -0.0644416 0.00487691 -0.0666033 -0.0766937 0.0063795 -0.0666033 -0.076842 0.00655215 -0.0666033 -0.0768964 0.0063795 -0.0418033 -0.076842 0.00342253 -0.0666033 -0.0770993 0.00487691 -0.0418033 -0.0766937 0.00342253 -0.0418033 -0.0770993 0.00655215 -0.0418033 -0.0768964 -0.00833936 -0.0385033 -0.0310135 -0.00866057 -0.0376915 -0.0297012 -0.00903857 -0.0385033 -0.0309983 -0.00736345 -0.0385033 -0.0300792 -0.00984106 -0.0385033 -0.029044 -0.00991038 -0.0385033 -0.0302144 -0.00772623 -0.0385033 -0.0306771 -0.00734823 -0.0385033 -0.02938 -0.00768466 -0.0385033 -0.0287668 -0.00828257 -0.0385033 -0.0284041 -0.00888281 -0.0385033 -0.0283685 -0.00943902 -0.0385033 -0.0285969 -0.00956393 -0.0385033 -0.0307058 -0.0100093 -0.0385033 -0.0296213 -0.00381893 -0.0387533 -0.0585236 0.00259423 -0.0387533 -0.0585902 -0.00381893 -0.0390533 -0.0585236 0.00259423 -0.0390533 -0.0585902 -0.00389326 -0.0401033 -0.0585188 -0.00389326 -0.0390533 -0.0585188 -0.00197674 -0.0387533 -0.0595144 0.000422581 -0.0387533 -0.0596153 -0.00375314 -0.0401033 -0.0585785 0.00252732 -0.0390533 -0.0586437 0.00252732 -0.0401033 -0.0586437 0.00266864 -0.0390533 -0.0585868 0.00266864 -0.0401033 -0.0585868 -0.00375314 -0.0390533 -0.0585785 -0.00197674 -0.0401033 -0.0595144 0.000422581 -0.0401033 -0.0596153 0.0183766 -0.0401033 -0.055693 0.0182559 -0.0390533 -0.0557858 0.0183059 -0.0390533 -0.0557163 0.0182559 -0.0401033 -0.0557858 0.0148543 -0.0401033 -0.0577976 0.0128014 -0.0401033 -0.0576392 0.0148543 -0.0387533 -0.0577976 0.0167982 -0.0387533 -0.0571186 0.0167982 -0.0401033 -0.0571186 0.0120397 -0.0401033 -0.0573978 0.0121126 -0.0390533 -0.0573824 0.0120397 -0.0390533 -0.0573978 0.0183766 -0.0390533 -0.055693 0.0121126 -0.0387533 -0.0573824 0.0121907 -0.0401033 -0.0574175 0.0128014 -0.0387533 -0.0576392 0.0183059 -0.0387533 -0.0557163 0.0121907 -0.0390533 -0.0574175 0.0299473 -0.0387533 -0.050423 0.0271454 -0.0387533 -0.0519852 0.0326595 -0.0390533 -0.0487099 0.0327214 -0.0401033 -0.0486684 0.0270794 -0.0401033 -0.0520197 0.0270794 -0.0390533 -0.0520197 0.0272301 -0.0390533 -0.0519979 0.0294376 -0.0387533 -0.0518152 0.0314137 -0.0387533 -0.0506415 0.0326595 -0.0387533 -0.0487099 0.0326301 -0.0390533 -0.0487904 0.0327214 -0.0390533 -0.0486684 0.0314137 -0.0401033 -0.0506415 0.0294376 -0.0401033 -0.0518152 0.0326301 -0.0401033 -0.0487904 0.0272301 -0.0401033 -0.0519979 0.0271454 -0.0390533 -0.0519852 0.0445906 -0.0390533 -0.0380909 0.0424412 -0.0387533 -0.0404722 0.044639 -0.0390533 -0.0380342 0.0401647 -0.0390533 -0.0427324 0.0402497 -0.0390533 -0.0427217 0.0402497 -0.0401033 -0.0427217 0.042326 -0.0401033 -0.0419503 0.0439121 -0.0387533 -0.0402869 0.0401647 -0.0387533 -0.0427324 0.042326 -0.0387533 -0.0419503 0.0445906 -0.0387533 -0.0380909 0.0401104 -0.0401033 -0.0427834 0.0401104 -0.0390533 -0.0427834 0.044639 -0.0401033 -0.0380342 0.044584 -0.0390533 -0.0381762 0.044584 -0.0401033 -0.0381762 0.0439121 -0.0401033 -0.0402869 0.0532456 -0.0390533 -0.024579 0.0532143 -0.0390533 -0.0246466 0.0532456 -0.0401033 -0.024579 0.0502048 -0.0387533 -0.0303101 0.053231 -0.0390533 -0.0247306 0.0502048 -0.0390533 -0.0303101 0.0502837 -0.0390533 -0.0302769 0.0531534 -0.0387533 -0.0269442 0.0531534 -0.0401033 -0.0269442 0.053231 -0.0401033 -0.0247306 0.0532143 -0.0387533 -0.0246466 0.051787 -0.0387533 -0.0275195 0.0520749 -0.0387533 -0.0289739 0.0501662 -0.0401033 -0.0303739 0.0501662 -0.0390533 -0.0303739 0.0502837 -0.0401033 -0.0302769 0.0520749 -0.0401033 -0.0289739 -0.0586396 -0.0390533 0.00133338 -0.0581238 -0.0401033 0.00787533 -0.0581338 -0.0390533 0.00780151 -0.0581238 -0.0390533 0.00787533 -0.0584733 -0.0387533 0.00461157 -0.0586378 -0.0387533 0.00140784 -0.0586378 -0.0390533 0.00140784 -0.0586396 -0.0401033 0.00133338 -0.058193 -0.0390533 0.00773962 -0.0586866 -0.0390533 0.00147825 -0.0586866 -0.0401033 0.00147825 -0.0581338 -0.0387533 0.00780151 -0.0593167 -0.0401033 0.00583086 -0.0594974 -0.0401033 0.00353952 -0.0594974 -0.0387533 0.00353952 -0.0593167 -0.0387533 0.00583086 -0.058193 -0.0401033 0.00773962 -0.0580928 -0.0390533 -0.00809699 -0.0568428 -0.0387533 -0.0144633 -0.0568244 -0.0390533 -0.0145355 -0.0568244 -0.0401033 -0.0145355 -0.0568428 -0.0390533 -0.0144633 -0.0575487 -0.0387533 -0.011334 -0.0582456 -0.0387533 -0.0126426 -0.0580824 -0.0387533 -0.00817075 -0.0580824 -0.0390533 -0.00817075 -0.0581227 -0.0390533 -0.00824632 -0.0582456 -0.0401033 -0.0126426 -0.0569087 -0.0401033 -0.0144087 -0.0586898 -0.0387533 -0.0103875 -0.0580928 -0.0401033 -0.00809699 -0.0569087 -0.0390533 -0.0144087 -0.0586898 -0.0401033 -0.0103875 -0.0581227 -0.0401033 -0.00824632 -0.0537536 -0.0401033 -0.0234686 -0.0507951 -0.0390533 -0.0293262 -0.0507951 -0.0401033 -0.0293262 -0.0508323 -0.0390533 -0.0292616 -0.0537237 -0.0390533 -0.0235369 -0.0523563 -0.0387533 -0.0264388 -0.0508323 -0.0387533 -0.0292616 -0.0537421 -0.0390533 -0.0236205 -0.0537237 -0.0387533 -0.0235369 -0.0526743 -0.0401033 -0.0278869 -0.0537105 -0.0387533 -0.0258353 -0.0526743 -0.0387533 -0.0278869 -0.0509106 -0.0390533 -0.0292268 -0.0509106 -0.0401033 -0.0292268 -0.0537105 -0.0401033 -0.0258353 -0.0537421 -0.0401033 -0.0236205 -0.0537536 -0.0390533 -0.0234686 -0.040999 -0.0390533 -0.0419417 -0.0453809 -0.0390533 -0.0371572 -0.0417711 -0.0401033 -0.0417362 -0.0448625 -0.0401033 -0.0391499 -0.0435878 -0.0387533 -0.0407669 -0.0448625 -0.0387533 -0.0391499 -0.0453809 -0.0387533 -0.0371572 -0.0417711 -0.0387533 -0.0417362 -0.045428 -0.0401033 -0.0370995 -0.0453761 -0.0401033 -0.0372427 -0.040999 -0.0401033 -0.0419417 -0.0410522 -0.0390533 -0.0418896 -0.0435878 -0.0401033 -0.0407669 -0.0453761 -0.0390533 -0.0372427 -0.045428 -0.0390533 -0.0370995 -0.0410522 -0.0387533 -0.0418896 -0.0411369 -0.0390533 -0.0418772 -0.0411369 -0.0401033 -0.0418772 -0.0337337 -0.0390533 -0.0479788 -0.0281625 -0.0390533 -0.0514464 -0.0282278 -0.0390533 -0.0514106 -0.033645 -0.0390533 -0.0481026 -0.033645 -0.0401033 -0.0481026 -0.0303138 -0.0401033 -0.0512566 -0.0323917 -0.0401033 -0.0500528 -0.0336727 -0.0387533 -0.0480216 -0.0323917 -0.0387533 -0.0500528 -0.0282278 -0.0387533 -0.0514106 -0.0283127 -0.0401033 -0.0514215 -0.0283127 -0.0390533 -0.0514215 -0.0337337 -0.0401033 -0.0479788 -0.0281625 -0.0401033 -0.0514464 -0.0336727 -0.0390533 -0.0480216 -0.0303138 -0.0387533 -0.0512566 -0.0195378 -0.0390533 -0.0552995 -0.0149927 -0.0387533 -0.0575235 -0.0132376 -0.0401033 -0.0571355 -0.0195378 -0.0401033 -0.0552995 -0.0133102 -0.0390533 -0.0571186 -0.019419 -0.0401033 -0.0553948 -0.0167128 -0.0387533 -0.0573329 -0.0182659 -0.0387533 -0.0565696 -0.0194676 -0.0390533 -0.0553243 -0.0133102 -0.0387533 -0.0571186 -0.0194676 -0.0387533 -0.0553243 -0.019419 -0.0390533 -0.0553948 -0.0132376 -0.0390533 -0.0571355 -0.013389 -0.0390533 -0.057152 -0.0167128 -0.0401033 -0.0573329 -0.0182659 -0.0401033 -0.0565696 -0.0149927 -0.0401033 -0.0575235 -0.013389 -0.0401033 -0.057152 -0.036308 9.13249e-07 9.08655e-05 -0.0365826 -3.3303e-06 -0.00241785 0.0684721 5.34114e-05 -0.00332943 0.0684698 5.26947e-05 -0.00325859 0.0679483 -3.3303e-06 0.00416056 0.0683073 2.25252e-06 0.00172806 0.0688404 2.09813e-05 -0.00331771 0.069225 -3.3303e-06 -0.00821523 0.0682281 -3.3303e-06 -0.0205934 0.0687596 -3.3303e-06 -0.0169158 -0.0367897 0.000156054 -0.00768451 -0.0370403 2.00025e-05 -0.00956801 -0.0488143 0.00044083 -0.281428 -0.0488519 0.000364712 -0.281428 -0.049529 0.00030424 -0.281785 -0.0495438 0.000251987 -0.281764 -0.0495927 0.000141454 -0.281695 -0.0496458 6.99051e-05 -0.281621 -0.0493446 7.04062e-05 -0.281428 -0.049684 0.00030424 -0.281863 -0.0495066 0.00049667 -0.281816 -0.0498555 0.000141454 -0.28178 -0.0498555 3.3389e-05 -0.281616 -0.049688 3.3389e-05 -0.281562 -0.0497675 3.3389e-05 -0.281602 -0.0497175 0.000141454 -0.281758 -0.053502 -3.3303e-06 -0.281428 -0.0498555 0.00030424 -0.281889 -0.053511 0.000206945 -0.281835 -0.0535124 0.000323807 -0.281896 -0.0535058 2.80723e-05 -0.281601 -0.053507 5.19303e-05 -0.281655 -0.0535098 0.000143111 -0.281781 -0.053513 0.000432413 -0.281924 -0.0535686 0.00030613 -0.281884 -0.0538126 0.00049667 -0.281611 -0.0537925 0.000276712 -0.281632 -0.0537214 0.000115174 -0.281574 -0.0535696 0.00049667 -0.281922 -0.0536317 0.00049667 -0.281903 -0.053731 0.00049667 -0.281834 -0.0537307 0.000337078 -0.2818 -0.0536264 0.000311596 -0.281867 -0.0536068 1.56075e-05 -0.281422 -0.0536129 1.79975e-05 -0.281422 -0.0536158 2.65349e-05 -0.281515 -0.0537873 0.000210814 -0.281531 -0.0535042 6.5436e-06 -0.281525 -0.0536185 5.31645e-05 -0.281605 -0.053621 9.6593e-05 -0.281689 -0.0536232 0.0001555 -0.281762 -0.0535658 0.00014505 -0.281776 -0.0537269 0.000202778 -0.281709 -0.0537947 0.00049667 -0.281731 -0.053796 0.00037732 -0.2817 0.0133536 4.68255e-05 -0.278042 0.0114431 -3.3303e-06 -0.281429 0.0133904 0.000228991 -0.278429 0.0133814 0.000162775 -0.278334 0.0118372 0.000143116 -0.281429 0.011636 2.7574e-05 -0.281429 0.0133593 6.3388e-05 -0.278101 0.0119659 0.000323611 -0.281429 0.0120004 0.00049667 -0.281429 0.0133937 0.00049667 -0.278598 0.013401 0.000436419 -0.278575 0.0134335 0.00044882 -0.278485 0.0134519 0.000397317 -0.2784 0.013585 0.000181865 -0.277687 0.0135061 0.000247929 -0.278107 0.0134988 0.000119478 -0.277893 0.0135215 8.45377e-05 -0.277673 0.0134018 0.000377045 -0.278549 0.0134128 0.000394605 -0.278534 0.0133766 0.000135597 -0.278284 0.0134183 0.000205985 -0.27833 0.0134224 0.000109774 -0.278108 0.013381 2.73194e-05 -0.277873 0.0134156 0.000279476 -0.278437 0.0134218 0.000412625 -0.278518 0.0134471 0.000255807 -0.278323 0.0134735 0.000173325 -0.278111 0.0133368 1.21645e-05 -0.277865 0.0133679 1.74017e-06 -0.277639 0.0134264 1.95058e-05 -0.277652 0.0134241 5.04766e-05 -0.277881 0.0133937 0.0177631 -0.278598 0.0134335 0.0177631 -0.278485 0.013417 0.000472569 -0.278543 0.0131188 0.0197879 -0.279143 0.0133112 0.0187906 -0.278766 0.00496517 0.0244836 -0.052678 0.00419089 0.0242426 -0.0484021 0.00240376 0.0245322 -0.0463991 0.00389914 0.0250529 -0.0467415 0.00466493 0.0250465 -0.0477077 0.00264186 0.0249787 -0.0460388 0.0027988 0.0250422 -0.0458072 0.000293653 0.0249072 -0.0450423 -0.00193367 0.0248547 -0.0446795 -0.00477258 0.0246546 -0.045727 -0.00642596 0.0244264 -0.0477489 -0.00703469 0.0244259 -0.0481711 -0.00461186 0.0246038 -0.045971 -0.00225358 0.0247749 -0.0450201 0.00420984 0.0248041 -0.048002 -0.00430043 0.0240037 -0.0463714 -0.00400534 0.0238824 -0.0462059 -0.00330115 0.0239434 -0.0458587 -0.000387666 0.0241396 -0.0454339 -0.00212741 0.0241786 -0.0454944 -0.00597257 0.0238222 -0.0480114 -0.00601585 0.0239754 -0.0479939 0.00496232 0.0241181 -0.0520229 0.00491785 0.024381 -0.0526633 0.00499468 0.0241464 -0.0514022 0.00494745 0.0244815 -0.0502945 0.00406479 0.0245368 -0.0480933 0.00551256 0.0250079 -0.0495583 0.0044299 0.0249835 -0.0478605 0.00538099 0.0249289 -0.0502272 0.00199455 0.0242344 -0.0462058 0.000221947 0.0244602 -0.0454731 0.000222173 0.0241698 -0.045529 -0.00618286 0.0242521 -0.0479015 -0.00433335 0.0241543 -0.0463403 -0.00444961 0.0244276 -0.0461971 -0.00214415 0.024327 -0.0454541 -0.00219306 0.0245971 -0.045283 0.000246773 0.0247281 -0.0453018 0.00249692 0.0247992 -0.0462558 0.00511972 0.02475 -0.0502706 0.0544407 0.00799667 0.0313945 0.0542225 0.00799667 0.0311801 0.0522476 0.0122595 0.0298814 0.0535877 0.0104028 0.0314145 0.0545285 0.00799667 0.0322241 0.0535545 0.0101574 0.0307857 0.0536383 0.0103094 0.0310849 0.0503317 0.0155334 0.0273332 0.0501154 0.015869 0.0276283 0.0501199 0.0155386 0.0282978 0.057756 0.0126275 0.0223661 0.0580337 0.0127404 0.0222066 0.056562 0.0145952 0.0214548 0.0545723 0.0160095 0.0213577 0.0508763 0.0172945 0.0233845 0.0500834 0.0168501 0.025453 0.050258 0.0157201 0.0274845 0.053738 0.0160189 0.021599 0.0528913 0.0164467 0.0218678 0.0559752 0.014107 0.021695 0.0544086 0.0157217 0.0215004 0.0525456 0.0168015 0.0220018 0.0525316 0.016699 0.0220339 0.0544665 0.015821 0.0214706 0.0560726 0.0141919 0.0217135 0.056171 0.014287 0.0217082 0.0574699 0.0124483 0.0223982 0.0505153 0.0148526 0.0277311 0.0510828 0.0138837 0.0287392 0.0521748 0.0121457 0.0297658 0.0510383 0.0137843 0.0286591 0.0520906 0.0120437 0.0296891 0.0511109 0.0140831 0.0289446 0.0522865 0.0123507 0.0300018 0.0523005 0.0124389 0.030152 0.0503311 0.0153373 0.0271957 0.0501739 0.0162435 0.0258076 0.0503402 0.0154347 0.0272615 0.0509467 0.017097 0.0234266 0.0501805 0.0166568 0.0254008 0.0502071 0.0165558 0.0253699 0.0511082 0.013985 0.0288354 0.0546523 0.0161621 0.0211851 0.0546976 0.0162613 0.0209792 0.0534137 0.0169284 0.0211993 0.0525224 0.0171634 0.0217555 0.0507658 0.0174632 0.0233135 0.0499356 0.0170129 0.0254871 0.0506284 0.0175875 0.0232224 0.0502833 0.0175394 0.0238013 0.0563767 0.0144641 0.0216251 0.0525502 0.0169978 0.0218996 0.0510887 0.0141726 0.0290622 0.0522404 0.0125514 0.0304552 0.0509745 0.0143073 0.0292984 0.0520775 0.0125782 0.0307396 0.0582377 0.0127678 0.0219724 0.0573516 0.0123537 0.0223685 0.0604245 0.00799667 0.0237793 0.0603741 0.00799667 0.0238197 0.0574748 0.0124519 0.0223988 0.0600495 0.00799667 0.023959 0.0599552 0.00799667 0.0239708 0.0596836 0.00799667 0.0239457 0.0658153 0.0128075 -0.0261361 0.066338 0.0129561 -0.0257673 0.0672195 0.00799667 -0.0262549 0.066113 0.0128983 -0.0260099 0.0671381 0.00799667 -0.0263013 0.0648108 0.0151788 -0.0259156 0.0653045 0.0153963 -0.0255385 0.065408 0.0154181 -0.0252551 0.0635837 0.017491 -0.0254548 0.0650909 0.0153118 -0.0257847 0.0632278 0.017201 -0.0256128 0.0645436 0.0150374 -0.0259155 0.0631184 0.0171003 -0.025603 0.0638694 0.0176429 -0.0249194 0.0637722 0.0176114 -0.0252037 0.0617636 0.0193934 -0.0248337 0.0598358 0.019535 -0.0343234 0.0583106 0.0204728 -0.032956 0.0574731 0.0211063 -0.0288532 0.0585472 0.0206865 -0.0270634 0.058427 0.0208637 -0.0269268 0.0601026 0.0200605 -0.0258073 0.0619186 0.0190066 -0.0253033 0.0600686 0.0202302 -0.0256053 0.0619936 0.0191591 -0.0250671 0.05778 0.0204668 -0.0289436 0.0576579 0.0204299 -0.0301712 0.0577386 0.0203433 -0.0308641 0.0581494 0.0200586 -0.0320498 0.0584776 0.0198454 -0.0325927 0.0584914 0.0199612 -0.0326283 0.0594776 0.0191513 -0.0336157 0.0611908 0.017573 -0.0343942 0.0584892 0.0200787 -0.0326758 0.0598058 0.0190482 -0.0338499 0.0613716 0.0177777 -0.0344871 0.0616548 0.0185723 -0.0255264 0.0617265 0.0186834 -0.0255072 0.0600606 0.0197238 -0.0260044 0.0586118 0.0202284 -0.027224 0.05813 0.0203864 -0.0279856 0.0586184 0.0203451 -0.0272012 0.0633433 0.0173016 -0.025594 0.0615648 0.01815 -0.0352741 0.059326 0.0198878 -0.0342812 0.0574368 0.0209808 -0.0310109 0.0577432 0.0207956 -0.0324731 0.0575782 0.0211628 -0.0279044 0.0589652 0.0207397 -0.0260678 0.0598731 0.0193761 -0.034094 0.0598433 0.0191626 -0.0339129 0.0584323 0.0203 -0.0328025 0.0577094 0.0205786 -0.0309022 0.0577469 0.0207024 -0.0289296 0.0576055 0.0208025 -0.0309534 0.0576412 0.0209268 -0.0288983 0.0586104 0.0204633 -0.0271665 0.0600862 0.0198408 -0.0259565 0.0617969 0.0187966 -0.0254637 0.0640901 0.0131191 -0.035083 0.064304 0.0132057 -0.0353052 0.0654666 0.00799667 -0.0356294 0.064416 0.0132639 -0.0356001 0.0644125 0.0132842 -0.0358966 0.0633045 0.0158404 -0.0353552 0.0632066 0.0157497 -0.035064 0.0630139 0.015615 -0.0348469 0.0615846 0.0181046 -0.0349806 0.0615182 0.0179733 -0.034695 0.0612851 0.0176765 -0.0344281 -0.00952345 0.0100578 0.0409207 -0.00909274 0.0122027 0.0398213 -0.0105971 0.00799667 0.0423952 -0.010827 0.00799667 0.0424331 -0.011138 0.00848817 0.0421257 -0.0100357 0.0119771 0.0400828 -0.00872552 0.0141753 0.038282 -0.00479822 0.0165898 0.0369847 -0.0069147 0.0155717 0.0373815 -0.00741053 0.015412 0.0373844 -0.00827382 0.0139675 0.0385071 -0.00256776 0.0168902 0.0375911 -0.00100962 0.0162298 0.039162 -0.000865359 0.0163891 0.0391322 -0.00055686 0.0164001 0.0392899 -0.00269214 0.0163415 0.037772 -0.00267348 0.0165368 0.0377545 -0.000424692 0.01482 0.0408456 -0.000406779 0.0133595 0.042521 -0.000347893 0.0139322 0.041722 -0.00115673 0.0159449 0.0391361 -0.00118314 0.0158482 0.0391106 -0.00797177 0.0136782 0.0384668 -0.00706556 0.0145506 0.0378064 -0.00656062 0.0151386 0.0375516 -0.00790151 0.0135788 0.0384167 -0.00816099 0.0138775 0.0385149 -0.00887887 0.0119962 0.0396871 -0.008059 0.0137793 0.0385008 -0.0089681 0.0120978 0.0397616 -0.00465173 0.0160456 0.0372263 -0.00470669 0.0162404 0.0371978 -0.00349266 0.0163127 0.0374309 -0.000659793 0.0120676 0.044602 -0.000380855 0.0120914 0.044781 -0.00085523 0.0119553 0.0443579 -0.00193873 0.0169585 0.0378097 -0.00249048 0.0170156 0.0374603 -0.00379843 0.0169401 0.036958 -0.00482566 0.0167096 0.0368213 -0.000384674 0.0134648 0.0426151 -0.000933452 0.011774 0.0440907 -0.000261052 0.0136594 0.0428024 -0.000335941 0.0135666 0.0427106 -4.82894e-05 0.0137984 0.0429561 -5.61134e-05 0.0152595 0.0410611 -0.00954978 0.0124118 0.0398284 -0.00923198 0.0122901 0.039852 -0.00676885 0.0154208 0.0374977 -0.0066255 0.0152359 0.0375505 -0.00475737 0.0164285 0.0371153 -0.00263103 0.0167259 0.037693 -0.00111873 0.0160425 0.0391538 -0.000249271 0.015109 0.0410015 -0.000384362 0.01492 0.0409039 -0.000921367 0.0116583 0.0439534 -0.00160465 0.00799667 0.0471054 -0.00135287 0.0101419 0.0459372 -0.00187646 0.00799667 0.0469291 -0.00208121 0.00799667 0.0465516 -0.00155506 0.0100481 0.0456646 -0.00107767 0.0101713 0.0461011 -0.0382993 0.00799667 -0.027996 -0.0371977 0.012809 -0.0280637 -0.0385456 0.00799667 -0.0281153 -0.0387998 0.00799667 -0.0284157 -0.0388516 0.00799667 -0.0285529 -0.0376468 0.0129623 -0.0284781 -0.0374618 0.0129009 -0.0282221 -0.0358583 0.0149951 -0.0280849 -0.0365857 0.0154074 -0.0288282 -0.034878 0.0174973 -0.028631 -0.0365167 0.0153755 -0.0285402 -0.0347341 0.0173704 -0.0283727 -0.0363469 0.015282 -0.0282836 -0.0345313 0.0171806 -0.0282109 -0.034428 0.0170814 -0.0281769 -0.0361055 0.0151423 -0.028124 -0.0313039 0.019577 -0.0272321 -0.0329498 0.0186565 -0.0280798 -0.030989 0.0193081 -0.0203895 -0.0320641 0.0183623 -0.0196515 -0.0324606 0.0181869 -0.019464 -0.0297009 0.0200364 -0.0226261 -0.0299152 0.0198886 -0.0219639 -0.0299166 0.0200023 -0.0219382 -0.0305621 0.019466 -0.0208661 -0.0309611 0.0191957 -0.0204293 -0.029547 0.0203964 -0.0238647 -0.0349381 0.0175406 -0.0289195 -0.0302542 0.0205606 -0.0269348 -0.0312466 0.0200732 -0.0275966 -0.0311426 0.0201774 -0.0277888 -0.0294917 0.0206223 -0.0216199 -0.030016 0.0203344 -0.0206789 -0.0309859 0.0196367 -0.0201847 -0.0309059 0.0198038 -0.0199987 -0.0298189 0.0203357 -0.0218209 -0.0296745 0.0205108 -0.0217209 -0.0299887 0.0204784 -0.0258704 -0.0330395 0.0188615 -0.0282463 -0.0330763 0.0190152 -0.0284762 -0.0310037 0.0194221 -0.0203348 -0.0325193 0.0182976 -0.0194025 -0.0339365 0.0166593 -0.0191634 -0.0300811 0.0200327 -0.0257465 -0.0300669 0.0202607 -0.0257928 -0.0313191 0.0196902 -0.0272797 -0.0311554 0.0195317 -0.0270992 -0.0328908 0.0185466 -0.0280286 -0.0307802 0.019902 -0.0198075 -0.0326118 0.018653 -0.018967 -0.0342801 0.0171973 -0.0183319 -0.029145 0.020829 -0.0227969 -0.029278 0.0207932 -0.0238637 -0.0298531 0.0206546 -0.0259707 -0.0342367 0.0169488 -0.0189168 -0.0325985 0.0185032 -0.0192145 -0.0299015 0.0201175 -0.0219053 -0.0294429 0.0206154 -0.0238622 -0.0313097 0.0199038 -0.0274174 -0.0369085 0.0127006 -0.0184857 -0.0377335 0.00799667 -0.0188299 -0.0365051 0.0125478 -0.0189788 -0.0378533 0.00799667 -0.0187192 -0.0358615 0.015007 -0.0185425 -0.0343477 0.0170653 -0.0186419 -0.034054 0.0167706 -0.0191073 -0.0354926 0.0147792 -0.0190346 -0.0357234 0.0149183 -0.018835 -0.0367568 0.0126411 -0.0187784 -0.037618 0.00031019 -0.00508286 -0.0376605 0.000308665 -0.00559212 -0.0378246 0.000211756 -0.00759439 -0.0351668 0.000319457 0.0128779 -0.0357222 0.000202699 0.0106703 -0.0301628 0.000327203 0.0247829 -0.0315754 0.000207405 0.0221223 -0.0331989 0.000323125 0.0185799 -0.0343633 0.000320672 0.0154695 -0.00404181 0.00030953 0.0475096 -0.0106713 0.00031509 0.0442971 -0.0109786 0.00020026 0.0441014 -0.0118755 0.000316174 0.0435839 -0.0163942 0.000320296 0.0404937 -0.0216514 0.000324609 0.0358995 -0.0292228 0.000327546 0.0263582 0.00611095 0.000191131 0.0504165 0.000181123 0.000193808 0.0489782 0.0121425 0.000189061 0.0511565 0.0115727 0.000300503 0.0511366 0.0101305 0.000301073 0.0510078 0.0243697 8.49024e-05 0.0504478 0.0182715 0.00018766 0.0511933 0.0243339 -3.3303e-06 0.0502383 0.0182569 -3.3303e-06 0.0509142 0.0121534 1.80465e-05 0.050988 0.00614121 1.82766e-05 0.0502502 0.0121468 8.59119e-05 0.0510901 0.00612283 8.69227e-05 0.0503512 -0.00556195 0.000196927 0.0468544 -0.0109457 9.13949e-05 0.044045 -0.0160286 9.30066e-05 0.0406716 -0.0160676 0.000203536 0.0407235 -0.0207384 0.000206391 0.0367715 -0.0248932 0.000208325 0.0323375 -0.0285313 0.000208823 0.0274219 -0.0315178 9.49146e-05 0.0220935 -0.0339739 0.000204448 0.0165386 -0.033913 9.34558e-05 0.0165165 0.0182627 1.78909e-05 0.0510249 0.018268 8.5229e-05 0.0511268 0.000200407 8.82312e-05 0.048915 -0.00553561 8.97593e-05 0.0467942 -0.010893 1.92908e-05 0.0439548 -0.0159655 1.96548e-05 0.0405875 -0.0206939 9.44138e-05 0.0367247 -0.0248438 9.53691e-05 0.0322963 -0.0247624 2.0187e-05 0.0322284 -0.0284776 9.56151e-05 0.0273868 -0.0314232 2.00847e-05 0.0220462 -0.033814 1.97561e-05 0.0164806 -0.035659 9.25948e-05 0.0106554 -0.0367114 9.31068e-05 0.00461221 -0.0366384 0.00032011 0.00582062 -0.0367759 0.000203739 0.00461959 -0.0378164 0.000187708 -0.00759477 -0.03775 8.52545e-05 -0.00760149 -0.0375399 -3.32351e-06 -0.00761854 0.000643984 -3.3303e-06 0.0488233 0.000230547 1.85739e-05 0.0488163 -0.00549397 1.89206e-05 0.0466991 -0.00544852 -3.3303e-06 0.0465952 -0.0158963 -3.3303e-06 0.0404955 -0.0206211 1.9972e-05 0.0366482 -0.0205412 -3.3303e-06 0.0365642 -0.024673 -3.3303e-06 0.0321539 -0.0282912 -3.3303e-06 0.0272649 -0.0283888 2.02423e-05 0.0273287 -0.0313192 -3.3303e-06 0.0219942 -0.0337055 -3.3303e-06 0.0164412 -0.0355568 1.95619e-05 0.0106314 -0.036607 1.96774e-05 0.00460025 0.0623516 0.000195042 0.0226332 0.0592394 0.000194937 0.0279202 0.0616659 0.000308979 0.0239618 0.0555316 0.000193845 0.0328134 0.0555452 0.000307077 0.0328251 0.0466355 0.000302551 0.0410995 0.0414797 0.000188932 0.044413 0.036027 0.00018772 0.0471031 0.036035 0.000298704 0.0471219 0.030328 0.000187037 0.049138 0.0243845 0.0002977 0.050534 0.024381 0.00018699 0.0505136 0.0622929 8.88356e-05 0.0226031 0.0513094 0.000192252 0.0372135 0.0554813 8.82497e-05 0.0327705 0.0512644 8.74702e-05 0.0371649 0.0465848 8.66271e-05 0.0410304 0.0466241 0.000190526 0.0410839 0.0414469 8.5849e-05 0.0443551 0.036001 8.5258e-05 0.0470417 0.0303092 8.49254e-05 0.049074 0.0591846 8.87838e-05 0.0278835 0.0590987 1.86994e-05 0.0278259 0.0413964 1.80322e-05 0.0442662 0.0359613 1.78975e-05 0.0469477 0.0302805 1.78217e-05 0.0489762 0.0590049 -3.3303e-06 0.0277631 0.0554028 1.85781e-05 0.0327035 0.0511944 1.8401e-05 0.0370895 0.0511181 -3.3303e-06 0.0370073 0.0465242 1.82093e-05 0.0409476 0.035918 -3.3303e-06 0.0468457 0.0302494 -3.3303e-06 0.04887 0.0243526 1.78164e-05 0.0503474 0.0699854 0.000185029 -0.0106312 0.069835 0.000298351 -0.014119 0.0687551 0.000186884 -0.0221242 0.0699129 7.84524e-05 -0.0106295 0.0697211 -3.3303e-06 -0.00809013 0.0698171 1.75985e-05 -0.0106272 0.0697071 -3.3303e-06 -0.0106245 0.070007 0.000294998 -0.0106317 0.0692945 0.000182767 0.000887325 0.0667413 0.000302419 0.0120503 0.0666543 8.10223e-05 0.0120225 0.0691216 1.4837e-05 0.000862158 0.0692281 8.28479e-05 0.000877707 0.0697133 1.73094e-05 -0.00486825 0.0693596 -3.3303e-06 -0.0160713 0.0667228 0.00019043 0.0120444 0.0693737 -3.3303e-06 -0.00202268 0.0666274 3.99042e-05 0.011931 0.0646072 1.85173e-05 0.017346 0.0622008 1.87111e-05 0.0225559 0.0684805 -3.3303e-06 -0.0220736 0.0682494 -3.3303e-06 -0.0232737 0.0323879 -3.3303e-06 -0.190528 0.0578552 -3.3303e-06 -0.0741552 0.0577926 -3.3303e-06 -0.0744457 0.0685893 1.78047e-05 -0.0220936 0.0647214 -3.3303e-06 -0.0412042 0.0626098 -3.3303e-06 -0.0515974 0.05863 8.66874e-05 -0.0715746 0.0686894 8.48509e-05 -0.0221121 0.0253747 1.78523e-05 -0.223092 0.0476757 0.00020707 -0.12211 0.0369464 0.000325397 -0.171106 0.0255419 0.000193988 -0.223129 0.0312516 0.000318105 -0.197119 0.0587137 0.000306231 -0.0715926 0.0585389 0.000306462 -0.0724057 0.0534655 0.000315936 -0.09576 0.0483567 0.000325219 -0.119065 0.0586955 0.000192435 -0.0715887 0.0476119 9.38049e-05 -0.122096 0.0585281 1.75753e-05 -0.0715527 0.0475073 1.91334e-05 -0.122073 0.0169444 -3.3303e-06 -0.259334 0.0146455 1.95058e-05 -0.272092 0.0254767 8.75558e-05 -0.223114 0.0148264 0.00029667 -0.272132 0.0148041 0.000181865 -0.272127 0.0147406 8.45377e-05 -0.272113 -0.047055 0.000320237 -0.159654 -0.0500136 0.000300742 -0.212829 -0.0443144 0.000233276 -0.11019 -0.0442433 9.48777e-05 -0.110194 -0.0442886 0.000160604 -0.110191 -0.0455813 0.000325424 -0.13306 -0.0387564 -3.3303e-06 -0.0232568 -0.0405967 9.81532e-06 -0.0486225 -0.0376483 1.78962e-05 -0.00760922 -0.0436399 -3.3303e-06 -0.103264 -0.043545 -3.3303e-06 -0.101539 -0.0428679 -3.3303e-06 -0.0892798 -0.0441125 1.08025e-05 -0.110201 -0.0420171 -3.3303e-06 -0.0741444 -0.040064 -3.3303e-06 -0.0417857 -0.0436505 0.000321922 -0.0980158 -0.0407236 8.74713e-05 -0.0486146 -0.0378155 0.000185189 -0.00759618 -0.0407694 0.00014848 -0.0486116 -0.0407976 0.000216749 -0.0486097 -0.037821 0.00021243 -0.00759446 -0.0509623 0.000297396 -0.234725 -0.0538016 0.00029667 -0.281411 -0.0511906 -3.3303e-06 -0.247152 -0.0512969 1.62337e-05 -0.247146 -0.0497141 -3.3303e-06 -0.212846 -0.0498196 1.59027e-05 -0.21284 -0.0514682 0.000184456 -0.247135 -0.049993 0.000187349 -0.212831 -0.0537109 8.16399e-05 -0.281416 -0.0525178 -3.3303e-06 -0.263587 -0.0526598 1.56075e-05 -0.264268 -0.0499244 8.304e-05 -0.212834 -0.0537798 0.000184403 -0.281412 -0.0513994 8.16651e-05 -0.247139 0.0127875 0.0195174 -0.27983 0.0125986 0.0194967 -0.280213 0.00968633 0.019627 -0.295329 0.00965078 0.0195835 -0.295321 0.00963522 0.0195688 -0.295318 0.00954632 0.0195153 -0.295298 0.0110549 0.0194967 -0.287752 0.0131007 0.0197278 -0.279193 0.0130986 0.0197229 -0.279198 0.0130283 0.0196306 -0.279341 0.00900708 0.0197967 -0.298672 0.00973767 0.0197967 -0.29534 -0.0438937 0.019627 -0.334257 -0.0537667 0.0195153 -0.312391 -0.0499238 0.0194967 -0.323955 -0.0500184 0.0195153 -0.323999 -0.050188 0.0197238 -0.324077 -0.0501485 0.019627 -0.324059 -0.050101 0.0195688 -0.324037 -0.0524165 0.0197967 -0.318404 -0.047364 0.0197967 -0.329373 -0.0495744 0.0194967 -0.324696 -0.0170125 0.0194967 -0.366507 -0.0222653 0.0194967 -0.360237 -0.0278748 0.0194967 -0.353402 -0.0437811 0.0195153 -0.334168 -0.0432594 0.0194967 -0.334654 -0.0436994 0.0194967 -0.334104 -0.0471083 0.0194967 -0.329216 -0.0122977 0.0194967 -0.370264 -0.0170728 0.0195153 -0.366594 0.0107783 0.0195128 -0.37121 0.0237 0.019512 -0.352011 0.0236874 0.0194967 -0.350416 0.0224014 0.0194967 -0.342288 0.0115773 0.0194967 -0.318143 0.017492 0.0194967 -0.331198 0.0216112 0.0194967 -0.34029 0.00827293 0.0195153 -0.301109 0.00781004 0.0194967 -0.307031 -0.0545816 0.0194967 -0.301392 -0.0546927 0.019518 -0.30139 -0.0547654 0.0197967 -0.306359 -0.0539857 0.0197967 -0.31229 -0.0547565 0.0197238 -0.306358 -0.0539501 0.0197238 -0.312427 -0.0539074 0.019627 -0.312418 -0.053856 0.0195688 -0.312408 -0.05457 0.0195153 -0.306345 -0.0546608 0.0195688 -0.306351 -0.0548613 0.0196884 -0.301385 -0.054713 0.019627 -0.306355 -0.0439349 0.0197967 -0.334289 -0.0363198 0.0197238 -0.34357 -0.0172132 0.0197967 -0.366731 -0.0210944 0.0197238 -0.362123 -0.0210607 0.019627 -0.362095 -0.0172067 0.0197238 -0.366725 -0.012426 0.019627 -0.370475 -0.0362861 0.019627 -0.343542 -0.0171755 0.019627 -0.366694 -0.017138 0.0195688 -0.366658 -0.0107056 0.0194967 -0.371147 -0.00968058 0.0195153 -0.371749 -0.0123465 0.019512 -0.370345 -0.0209499 0.0195153 -0.362004 -0.0210202 0.0195688 -0.362062 -0.0361753 0.0195153 -0.343451 -0.0362457 0.0195688 -0.343509 -0.0438526 0.0195688 -0.334224 -0.0439279 0.0197238 -0.334284 -0.0363268 0.0197967 -0.343576 -0.00689009 0.0197212 -0.37298 -0.00687783 0.019627 -0.372939 -0.0038855 0.0194971 -0.373395 -0.00689291 0.0197967 -0.372989 -0.0125068 0.0196307 -0.370429 -0.0123989 0.0195688 -0.370431 -0.0068628 0.0195688 -0.372889 -0.0068068 0.0194967 -0.372702 -0.00683572 0.0195142 -0.372798 -0.000903715 0.0197967 -0.373981 -0.000892611 0.0194967 -0.373681 0.00507661 0.0194967 -0.373146 0.00246499 0.0197967 -0.37387 0.00537936 0.0194967 -0.373078 0.0133773 0.0195153 -0.369682 0.015769 0.0195142 -0.367817 0.0171313 0.0197967 -0.366796 0.0158946 0.0197213 -0.367958 0.0178316 0.0194971 -0.365624 0.0158314 0.0195688 -0.367887 0.0158661 0.019627 -0.367926 0.0108225 0.0195688 -0.371297 0.0108462 0.019627 -0.371344 0.0104085 0.0197967 -0.371619 0.0107756 0.0196448 -0.371392 0.0238954 0.0197238 -0.352028 0.022127 0.0194967 -0.358465 0.0224429 0.0195153 -0.357907 0.0237999 0.0195688 -0.35202 0.0237751 0.0195153 -0.34901 0.0236055 0.0194967 -0.352004 0.0236396 0.0197238 -0.345961 0.0231641 0.0197967 -0.343756 0.0236485 0.0197967 -0.34596 0.0226188 0.0197219 -0.357969 0.0218172 0.0197967 -0.359977 0.0234494 0.0195131 -0.345994 0.0227623 0.0195153 -0.343065 0.0235451 0.0195688 -0.345978 0.0217893 0.0195688 -0.340211 0.0217032 0.0195141 -0.340249 0.0117504 0.0195153 -0.318273 0.00918526 0.0194967 -0.312814 0.00836563 0.0194967 -0.310301 0.0218854 0.0197967 -0.340168 0.0200263 0.0197967 -0.336064 0.0142998 0.0197967 -0.323425 0.00946382 0.0197967 -0.312702 0.0225781 0.019627 -0.357955 0.0218768 0.0197238 -0.340172 0.0218371 0.019627 -0.340189 0.0119206 0.0197238 -0.318196 0.00945547 0.0197238 -0.312706 0.0225288 0.0195688 -0.357937 0.023852 0.019627 -0.352025 0.0235967 0.019627 -0.345969 0.0118333 0.0195688 -0.318235 0.0118809 0.019627 -0.318214 0.00941502 0.019627 -0.312722 0.00936643 0.0195688 -0.312741 0.00972889 0.0197238 -0.295338 0.00971683 0.0196856 -0.295335 0.00836198 0.0195688 -0.301127 0.00805513 0.0197967 -0.306193 0.00809996 0.0197238 -0.307006 0.00805656 0.019627 -0.30701 0.00845582 0.0197238 -0.301147 0.00841319 0.019627 -0.301138 -0.0548021 0.019688 -0.299912 -0.0547356 0.0195854 -0.299916 -0.0547948 0.0195857 -0.301387 -0.0545229 0.0194967 -0.299928 -0.0543485 0.0192254 -0.296815 -0.0546337 0.0195179 -0.299922 -0.0538748 0.00781672 -0.282737 -0.0546287 0.0194135 -0.296766 -0.0544851 0.0187436 -0.293793 -0.0545624 0.019312 -0.296788 -0.0537947 0.00149667 -0.281731 -0.0538128 0.00469058 -0.282007 -0.053731 0.00149667 -0.281834 -0.0536505 0.0105625 -0.284378 -0.0536895 0.00771888 -0.283013 -0.0535131 0.00149667 -0.281928 -0.0538686 0.0106047 -0.284293 -0.0537476 0.0046721 -0.282114 -0.0536432 0.00466042 -0.282185 -0.0537645 0.0105711 -0.284357 -0.0539705 0.0131978 -0.286127 -0.0538666 0.0131547 -0.286184 -0.0539919 0.0153719 -0.288427 -0.0540955 0.0154234 -0.288378 -0.0542404 0.0172259 -0.290989 -0.0541373 0.0171675 -0.291027 -0.0542976 0.0184794 -0.293897 -0.0544601 0.0192456 -0.296805 -0.0541855 0.0184609 -0.29391 -0.0540246 0.0171511 -0.291043 -0.0496723 0.00049667 -0.281899 -0.0496723 0.00149667 -0.281899 -0.0498555 0.00049667 -0.281928 -0.0507376 0.00935114 -0.283386 -0.051565 0.0114603 -0.284937 -0.051083 0.00917471 -0.283619 -0.0513485 0.0114882 -0.284907 -0.0499102 0.00419136 -0.282092 -0.0506853 0.00929238 -0.283278 -0.0506904 0.00670733 -0.282699 -0.0509373 0.00771608 -0.283036 -0.0509184 0.00923552 -0.283557 -0.0511486 0.011564 -0.284804 -0.0501168 0.00415012 -0.282124 -0.0505566 0.00674118 -0.282692 -0.0504264 0.0067837 -0.282654 -0.0503111 0.00683168 -0.282587 -0.050847 0.00927215 -0.283509 -0.0507862 0.00931119 -0.283451 -0.0510729 0.0116151 -0.284731 -0.0512212 0.0165939 -0.289097 -0.0524201 0.0194967 -0.299928 -0.0509803 0.0117335 -0.284558 -0.0510139 0.0116755 -0.284644 -0.0516136 0.0193279 -0.29548 -0.051747 0.0191299 -0.295523 -0.0515146 0.0175225 -0.29136 -0.0513359 0.0178897 -0.291173 -0.0518613 0.0194967 -0.297451 -0.0519497 0.0189982 -0.295545 -0.0517162 0.0174024 -0.291413 -0.051311 0.0149489 -0.287714 -0.0515117 0.0148478 -0.287794 -0.0521289 0.0194967 -0.298698 -0.0520647 0.018384 -0.293698 -0.051935 0.0173609 -0.291423 -0.0509659 0.0194967 -0.28447 -0.0509012 0.010845 -0.283967 -0.0506795 0.0194967 -0.283264 -0.0502193 0.00688102 -0.282496 -0.0488061 0.00049667 -0.281428 -0.0497296 0.00423856 -0.281989 -0.0495066 0.00149667 -0.281816 -0.0488061 0.0194967 -0.281428 -0.0403558 -0.00240333 -0.100496 -0.0386433 -0.00240333 -0.0996301 -0.0375933 -0.00240333 -0.0993487 -0.0368246 -0.00240333 -0.0964801 -0.0356771 -0.00240333 -0.0958176 -0.0375932 -0.00240333 -0.0957114 -0.0386432 -0.00240333 -0.0954301 -0.0403557 -0.00240333 -0.0945639 -0.0404619 -0.00240333 -0.0964801 -0.0416094 -0.00240333 -0.0958175 -0.0420683 -0.00240333 -0.09753 -0.0407433 -0.00240333 -0.0975301 -0.0404619 -0.00240333 -0.0985801 -0.0416094 -0.00240333 -0.0992425 0.0454768 -0.00240333 -0.111098 0.048443 -0.00240333 -0.110711 0.0475768 -0.00240333 -0.108998 0.048443 -0.00240333 -0.107286 0.0465269 -0.00240333 -0.10718 0.0471894 -0.00240333 -0.106032 0.0436582 -0.00240333 -0.107948 0.0433768 -0.00240333 -0.108998 0.0436582 -0.00240333 -0.110048 0.0317096 -0.00240333 -0.16518 0.0327596 -0.00240333 -0.163573 0.0306596 -0.00240333 -0.166998 0.0297935 -0.00240333 -0.165286 0.0293346 -0.00240333 -0.166998 0.0297934 -0.00240333 -0.168711 0.0309409 -0.00240333 -0.168048 0.0317096 -0.00240333 -0.168817 0.031047 -0.00240333 -0.169964 0.0327596 -0.00240333 -0.169098 0.0338096 -0.00240333 -0.168817 0.034472 -0.00240333 -0.169964 0.0348596 -0.00240333 -0.166998 0.0361846 -0.00240333 -0.166998 0.0357257 -0.00240333 -0.165286 0.0338096 -0.00240333 -0.16518 0.0344721 -0.00240333 -0.164032 -0.0448822 -0.00240333 -0.155105 -0.0440161 -0.00240333 -0.156817 -0.0437347 -0.00240333 -0.157867 -0.0429661 -0.00240333 -0.158636 -0.0419161 -0.00240333 -0.158918 -0.0419161 -0.00240333 -0.160242 -0.0402036 -0.00240333 -0.159784 -0.0400974 -0.00240333 -0.155768 -0.0389499 -0.00240333 -0.155105 -0.040866 -0.00240333 -0.154999 -0.0402035 -0.00240333 -0.153851 0.0186622 -0.00240333 -0.221948 0.0175147 -0.00240333 -0.221286 0.0183809 -0.00240333 -0.222998 0.0170559 -0.00240333 -0.222998 0.0175147 -0.00240333 -0.224711 0.0187683 -0.00240333 -0.225964 0.0204808 -0.00240333 -0.225098 0.0222995 -0.00240333 -0.224048 0.0225809 -0.00240333 -0.222998 0.023447 -0.00240333 -0.224711 0.023447 -0.00240333 -0.221286 0.0194309 -0.00240333 -0.221179 0.00784444 -0.00240333 -0.273385 0.00861309 -0.00240333 -0.274153 0.00966307 -0.00240333 -0.27576 0.0107131 -0.00240333 -0.274153 0.0117631 -0.00240333 -0.272335 0.0130881 -0.00240333 -0.272335 0.0114818 -0.00240333 -0.271285 0.0126293 -0.00240333 -0.270622 0.0107131 -0.00240333 -0.270516 0.0113756 -0.00240333 -0.269369 -0.0495019 -0.00240333 -0.277033 -0.0501644 -0.00240333 -0.27818 -0.0484519 -0.00240333 -0.277314 -0.0463518 -0.00240333 -0.275214 -0.0466332 -0.00240333 -0.274164 -0.0474018 -0.00240333 -0.273395 -0.0484518 -0.00240333 -0.273114 -0.0495018 -0.00240333 -0.273395 -0.0484518 -0.00240333 -0.271789 -0.0502705 -0.00240333 -0.274164 -0.051418 -0.00240333 -0.273501 -0.0505518 -0.00240333 -0.275214 -0.0502705 -0.00240333 -0.276264 -0.00614786 0.00249667 0.0439737 -0.00672285 0.00249667 0.0449696 -0.00709954 0.00249667 0.043022 -0.00809546 0.00249667 0.0435971 -0.00809551 0.00249667 0.0398471 -0.00614792 0.00249667 0.0394704 -0.00672294 0.00249667 0.0384744 -0.00484794 0.00249667 0.037972 -0.00297294 0.00249667 0.0384744 -0.00160032 0.00249667 0.039847 -0.00224789 0.00249667 0.041722 -0.00259621 0.00249667 0.043022 -0.00109789 0.00249667 0.041722 -0.00354786 0.00249667 0.0439737 -0.00484785 0.00249667 0.045472 0.0520697 0.00249667 0.0260015 0.0514221 0.00249667 0.0278765 0.0509197 0.00249667 0.0260015 0.052418 0.00249667 0.0247015 0.0533697 0.00249667 0.0237498 0.0527947 0.00249667 0.0227539 0.0559697 0.00249667 0.0237498 0.0572697 0.00249667 0.0260015 0.0579173 0.00249667 0.0241265 0.0579173 0.00249667 0.0278765 0.0546698 0.00249667 0.0286015 0.0565448 0.00249667 0.0292491 0.0533697 0.00249667 0.0282532 0.0546698 0.00249667 0.0297515 0.0524181 0.00249667 0.0273015 0.0595546 0.00249667 -0.0299986 0.0599029 0.00249667 -0.0312986 0.058907 0.00249667 -0.0318736 0.0608546 0.00249667 -0.0322502 0.0602796 0.00249667 -0.0332462 0.0621546 0.00249667 -0.0325986 0.0621546 0.00249667 -0.0337486 0.0644063 0.00249667 -0.0312986 0.0647546 0.00249667 -0.0299986 0.0654022 0.00249667 -0.0281236 0.0640297 0.00249667 -0.026751 0.0634547 0.00249667 -0.027747 0.0602797 0.00249667 -0.026751 -0.0359517 0.00249667 -0.0269239 -0.0340766 0.00249667 -0.0210764 -0.0366767 0.00249667 -0.0236763 -0.0378267 0.00249667 -0.0236763 -0.0373243 0.00249667 -0.0255513 -0.0498555 0.00149667 -0.281928 -0.0535288 0.00465753 -0.282207 -0.0535752 0.00771312 -0.283035 -0.053753 0.0131433 -0.286203 -0.05217 0.0189546 -0.295544 -0.0538788 0.0153578 -0.288444 -0.0517291 0.0148116 -0.287815 -0.0538089 0.0142248 -0.2872 0.00785418 0.0194967 -0.303071 0.00944463 0.0194967 -0.295276 -0.00283421 0.0194967 -0.373529 -0.00433931 0.0194967 -0.352498 0.0233528 0.0194967 -0.34601 -9.21146e-06 0.0194967 -0.354998 0.00499085 0.0194967 -0.349998 0.00432095 0.0194967 -0.352498 -0.0515623 0.0194967 -0.295275 -0.051687 0.0194967 -0.296449 -0.0544662 0.0194967 -0.306337 -0.0534649 0.0194967 -0.313346 -0.0521311 0.0194967 -0.318312 0.0107341 0.0194967 -0.371123 0.0129394 0.0194967 -0.369849 0.015702 0.0194967 -0.367741 0.0189415 0.0194967 -0.364231 0.0196537 0.0194967 -0.363229 -0.0498502 0.0194967 -0.282096 -0.0524138 0.0194967 -0.299902 -0.00250909 0.0194967 -0.345668 -0.0509659 0.0117925 -0.28447 -0.0511301 0.0152555 -0.287445 0.0675676 0.00799667 -0.0257383 0.0655413 0.00799667 -0.0361501 0.0655482 0.00799667 -0.0358834 0.0634546 0.00799667 -0.0322503 0.0666017 0.00799667 -0.0263668 0.0668755 0.00799667 -0.0263798 0.0653053 0.00799667 -0.0354155 0.0650807 0.00799667 -0.035265 0.0649203 0.00799667 -0.0352119 0.0621546 0.00799667 -0.0325986 0.0599029 0.00799667 -0.0312986 0.0597932 0.00799667 -0.0338292 0.0576568 0.00799667 -0.030138 0.0581278 0.00799667 -0.02799 0.0595604 0.00799667 -0.0263216 0.0634547 0.00799667 -0.027747 0.0631184 0.00799667 -0.025603 0.0673583 0.00799667 -0.0261406 0.0665614 0.00799667 -0.0309456 0.0674559 0.00799667 -0.0260175 0.0675103 0.00799667 -0.0259179 0.0611908 0.00799667 -0.0343942 0.0638113 0.0131114 -0.0349688 0.0627851 0.0154741 -0.0347438 0.066443 0.00897665 -0.026332 0.0654945 0.0128141 -0.026124 0.0661334 0.0105299 -0.0262641 0.0627206 0.01758 -0.0255343 0.0616126 0.00799667 -0.0255314 0.0609122 0.0190981 -0.0256735 0.0600259 0.0196086 -0.026034 0.0595767 0.0198291 -0.0263102 0.0591915 0.0200004 -0.0266119 0.0580181 0.0204171 -0.028227 0.0582599 0.00799667 -0.0322528 -0.0380273 0.00799667 -0.0183935 -0.0363284 0.00799667 -0.0249763 -0.0327767 0.00799667 -0.025928 -0.0353767 0.00799667 -0.025928 -0.0384727 0.00799667 -0.0234154 -0.0363283 0.00799667 -0.0223763 -0.0379176 0.00799667 -0.018636 -0.0374934 0.00799667 -0.0189542 -0.0372879 0.00799667 -0.0189922 -0.0305929 0.00799667 -0.020828 -0.0309275 0.00799667 -0.0268908 -0.0343247 0.00799667 -0.0281695 -0.0380275 0.00799667 -0.0279651 -0.038737 0.00799667 -0.0283089 -0.0361931 0.0125519 -0.0190527 -0.0338286 0.00799667 -0.0191832 -0.036895 0.0127988 -0.0280276 -0.00789054 0.00799667 0.0384065 -0.00744789 0.00799667 0.041722 -0.0100768 0.00799667 0.0419539 -0.00709954 0.00799667 0.043022 -0.0102693 0.00799667 0.0422031 -0.0105353 0.00799667 0.0423728 -0.0109457 0.00799667 0.0424258 -0.0110958 0.00799667 0.0423886 -0.00209981 0.00799667 0.0462812 -0.00354786 0.00799667 0.0439737 -0.00209614 0.00799667 0.0462465 -0.00224789 0.00799667 0.041722 -0.0004019 0.00799667 0.0424171 -0.00259624 0.00799667 0.040422 -0.00484793 0.00799667 0.039122 -0.00484786 0.00799667 0.044322 -0.00198547 0.00799667 0.0467886 -0.0020627 0.00799667 0.0466188 -0.0108728 0.00799667 0.042549 -0.00614786 0.00799667 0.0439737 -0.00182201 0.00799667 0.0469793 -0.00766172 0.00799667 0.0443947 -0.000880965 0.0115548 0.0438465 -0.00150625 0.00987335 0.0450141 -0.000880965 0.00799667 0.0438465 -0.00199221 0.00799667 0.0459215 -0.00881482 0.0118934 0.0395975 0.0533697 0.00799667 0.0237498 0.052418 0.00799667 0.0247015 0.0504637 0.00799667 0.0244016 0.0524181 0.00799667 0.0273015 0.0546698 0.00799667 0.0286015 0.0568816 0.00799667 0.0293042 0.0605852 0.00799667 0.0235817 0.0545741 0.00799667 0.0316702 0.0545928 0.00799667 0.0317535 0.054601 0.00799667 0.0319616 0.0545735 0.00799667 0.032107 0.0559697 0.00799667 0.0237498 0.0572697 0.00799667 0.0260015 0.0602078 0.00799667 0.0239127 0.0572488 0.00799667 0.0223139 0.058463 0.0102357 0.0231631 0.059387 0.00799667 0.0238093 0.0520906 0.00799667 0.0296891 0.0533046 0.0101363 0.0305381 0.0510174 0.00799667 0.0286303 0.0502078 0.00799667 0.0265857 0.0502144 0.0157596 0.0266333 0.050219 0.0164559 0.0253372 0.0517241 0.00799667 0.0225996 0.0514691 0.0168673 0.0228385 0.0509718 0.0168923 0.0234372 0.0505872 0.0168165 0.0241087 0.0504591 0.0167526 0.0244138 0.0543501 0.0156236 0.0215129 0.0536879 0.00799667 0.0216099 0.0525108 0.0165975 0.0220532 0.0517314 0.0168221 0.0225933 0.0572488 0.0122579 0.0223139 0.0558861 0.00799667 0.021669 0.0559824 0.0140984 0.0216972 0.0549144 0.0151834 0.0215082 0.00193918 0.0202967 -0.0497021 0.00419079 0.0202967 -0.0544021 -0.00100537 0.0202967 -0.0548021 -0.00394983 0.0202967 -0.053102 -0.00620152 0.0202967 -0.054402 -0.00394979 0.0202967 -0.049702 -0.00620144 0.0202967 -0.048402 -0.00270529 0.0202967 -0.0484576 -0.00400526 0.0202967 -0.0462059 -0.00100528 0.0202967 -0.0480021 0.000694713 0.0202967 -0.0484576 0.000600171 0.0317031 -0.270191 0.0131251 0.0198475 -0.27909 0.0114671 0.0210275 -0.286315 0.0133454 0.0188651 -0.278656 0.0145518 0.0196143 -0.272095 0.0106525 0.023515 -0.286137 -0.00273156 0.0318042 -0.30033 -0.00520104 0.0319967 -0.299933 -0.00263202 0.0318123 -0.306559 -0.00288503 0.0319967 -0.314836 -0.000915156 0.0319967 -0.318809 0.000855206 0.0319967 -0.321527 -0.0459634 0.0311582 -0.308452 -0.0402567 0.0319967 -0.315889 -0.0431728 0.0312121 -0.321756 -0.0372125 0.0319967 -0.32533 -0.0394222 0.0319967 -0.294616 -0.0393323 0.0315443 -0.264747 -0.0449724 0.0310948 -0.294068 -0.042148 0.0317823 -0.294224 -0.0458528 0.0311301 -0.301777 -0.0405405 0.0319967 -0.301891 -0.0518705 0.0217195 -0.263039 -0.0546481 0.0195209 -0.296746 -0.0542407 0.02152 -0.293556 -0.0548224 0.0197991 -0.299911 -0.0548574 0.0197979 -0.300648 -0.0548815 0.0197967 -0.301385 -0.05422 0.0222566 -0.309584 -0.0525241 0.0225694 -0.317413 -0.0496186 0.0228828 -0.324881 -0.0517677 0.020721 -0.320282 -0.0539857 0.0203296 -0.31229 -0.0451205 0.0251919 -0.331484 -0.0402214 0.0254342 -0.337801 -0.0392409 0.02183 -0.340025 -0.0199541 0.0274551 -0.362826 -0.0177171 0.0253249 -0.366197 -0.0130005 0.0258201 -0.370176 -0.0145081 0.0279616 -0.368598 -0.00758078 0.0281653 -0.372344 -0.00374388 0.0281653 -0.373293 0.000197377 0.0281653 -0.373591 0.0107948 0.0259967 -0.371428 0.0115482 0.0281653 -0.370567 0.0171312 0.0259967 -0.366796 0.0150745 0.0259967 -0.368664 0.0218172 0.0259967 -0.359977 0.020672 0.0259967 -0.362173 0.0235509 0.028157 -0.351236 0.0235719 0.0259985 -0.354462 0.0231634 0.0256839 -0.343754 0.0234129 0.0280847 -0.347288 0.0171245 0.024207 -0.32966 0.0177631 0.0272322 -0.332443 0.0109369 0.0259497 -0.317859 0.00923715 0.0256355 -0.314209 0.00884522 0.021661 -0.310915 0.00716909 0.0250296 -0.30615 0.00737581 0.0247267 -0.301955 0.00808157 0.0225945 -0.302068 0.00809202 0.0208088 -0.303762 0.0201705 0.0315692 -0.351058 0.0175398 0.0319967 -0.354007 0.0197247 0.0315702 -0.354417 0.01871 0.0315701 -0.357647 0.0166535 0.0319967 -0.356806 0.0140895 0.0319967 -0.361187 0.0171691 0.0315701 -0.360665 0.0151484 0.0315701 -0.363382 0.0134837 0.0319967 -0.361911 0.0113036 0.0319967 -0.363998 0.0127 0.0315701 -0.365726 0.00860781 0.0319967 -0.365801 0.00989722 0.0315701 -0.367626 0.00354172 0.0315701 -0.369905 0.00177221 0.0319967 -0.367909 0.000148432 0.0319967 -0.367997 0.0167201 0.0319967 -0.345134 0.0151523 0.0319967 -0.342464 0.015123 0.0319967 -0.342418 0.00513693 0.0313234 -0.320486 0.0120394 0.0318706 -0.335036 0.00320493 0.0318366 -0.321362 0.00107826 0.0318283 -0.317906 -0.00130712 0.0318203 -0.312554 -0.000183004 0.031221 -0.306457 -0.00020602 0.0311873 -0.300736 0.00363977 0.0309379 -0.270607 0.00438425 0.028622 -0.301474 0.00426818 0.0287626 -0.306271 0.00510505 0.0289032 -0.310963 0.00864841 0.0291897 -0.318895 0.016069 0.029785 -0.33321 0.00998706 0.0276601 -0.318289 0.00970061 0.027535 -0.271433 0.00596505 0.0270002 -0.3062 0.0066819 0.0272174 -0.310572 0.00780078 0.0253325 -0.310295 0.00823485 0.0274347 -0.314664 0.0170599 0.0285798 -0.332761 0.00613415 0.026783 -0.301755 0.00921929 0.025914 -0.285823 -0.0507754 0.026769 -0.316884 -0.0492041 0.0286129 -0.316408 -0.0505365 0.0285007 -0.309079 -0.0522799 0.0265956 -0.309318 -0.0507347 0.0283836 -0.301672 -0.0525958 0.0264147 -0.301632 -0.0515698 0.0224226 -0.26308 -0.0546669 0.0219305 -0.301588 0.00470348 0.0298047 -0.284832 0.00719951 0.0280595 -0.28538 0.00222174 0.0301178 -0.301126 0.0021712 0.0301961 -0.306358 0.00315638 0.0302744 -0.311447 0.0068223 0.0290438 -0.315304 0.00699413 0.0304339 -0.319645 0.0197355 0.0300261 -0.340388 0.0211659 0.0277515 -0.339739 0.0226091 0.0279462 -0.343423 0.0220437 0.0301807 -0.347447 0.0222171 0.0302143 -0.351166 0.0217169 0.0302184 -0.354863 0.0230153 0.0281658 -0.355153 0.0205998 0.0302182 -0.35842 0.0189034 0.0302182 -0.361742 0.0218314 0.0281653 -0.358924 0.0200338 0.0281653 -0.362444 0.0166783 0.0302182 -0.364735 0.0176753 0.0281653 -0.365616 0.0148196 0.0281653 -0.368349 0.0079522 0.0281653 -0.372207 0.00413291 0.0281653 -0.373224 0.000185735 0.0302182 -0.37226 -0.00715366 0.0302182 -0.371084 -0.013669 0.0301236 -0.367522 -0.0112031 0.0281111 -0.370763 -0.0163659 0.030019 -0.36496 -0.0174014 0.0277364 -0.365908 -0.0188284 0.0298885 -0.361903 -0.0300969 0.0261619 -0.350321 -0.0385657 0.0289504 -0.336442 -0.048104 0.0269428 -0.324147 -0.0490697 0.0249495 -0.324615 -0.0518904 0.0247072 -0.317221 -0.0535169 0.0244654 -0.309488 -0.0539163 0.0242132 -0.301604 -0.0520629 0.0261871 -0.293676 -0.0534515 0.0238958 -0.2936 -0.0484348 0.0299851 -0.301722 -0.0483821 0.0300503 -0.308784 -0.0450823 0.0311851 -0.315161 -0.0402158 0.0312391 -0.328063 -0.0337319 0.0319967 -0.331353 -0.00320963 0.0315701 -0.369964 -0.00494198 0.0319967 -0.367308 -0.00959195 0.0315641 -0.367775 -0.0108496 0.0319967 -0.364186 -0.0123814 0.0315474 -0.365871 -0.0130478 0.0319967 -0.361923 -0.0154544 0.0319967 -0.358617 0.00711264 0.0293678 -0.271081 0.00190128 0.0310524 -0.284218 0.000968685 0.0312547 -0.311989 0.00311693 0.0312885 -0.316982 0.00507668 0.0303527 -0.316095 0.0134696 0.0314662 -0.334388 0.0148444 0.0307653 -0.333765 0.0175407 0.031524 -0.341382 0.0190589 0.0315457 -0.344454 0.0212083 0.0301165 -0.34383 0.0199427 0.0315611 -0.34769 0.0139833 0.0302182 -0.367314 0.0108968 0.0302182 -0.369406 0.00681413 0.0315701 -0.369033 0.00750315 0.0302182 -0.370955 0.00389965 0.0302182 -0.371914 0.000167871 0.0315701 -0.370218 -0.00649828 0.0315701 -0.36915 -0.00353309 0.0302182 -0.371979 -0.0105674 0.030193 -0.369584 -0.0147769 0.0315224 -0.363506 -0.0171011 0.031491 -0.360485 -0.0266485 0.0313471 -0.347491 -0.0287363 0.0292882 -0.349204 -0.0360252 0.0312661 -0.334357 -0.0431853 0.0288379 -0.330134 -0.045061 0.0301754 -0.322671 -0.046743 0.0287254 -0.323487 -0.0472623 0.0301128 -0.315821 -0.0476875 0.0299031 -0.293918 -0.0443485 0.0297513 -0.264065 -0.0501059 0.0282363 -0.293784 -0.04851 0.0267377 -0.263497 -0.00853047 0.0319967 -0.365807 0.00606435 0.0319967 -0.366942 -9.21786e-06 0.0319967 -0.355498 -9.07704e-06 0.0319967 -0.344498 -0.00510734 0.0319967 -0.305972 -0.037313 0.0319967 -0.280579 -0.0392879 0.0319967 -0.319872 -0.0405971 0.0319967 -0.313803 0.00475396 0.0319967 -0.352748 0.00274079 0.0319967 -0.354761 0.0173381 0.0319967 -0.354803 -0.0409341 0.0319967 -0.305825 -0.00275909 0.0319967 -0.345235 0.00549085 0.0319967 -0.349998 0.0176889 0.0319967 -0.348112 0.0179435 0.0319967 -0.35094 -0.0035324 0.0319967 -0.313106 -0.0152215 0.0319967 -0.358943 -0.00550915 0.0319967 -0.349998 -0.0210231 0.0319967 -0.350615 -0.00477225 0.0319967 -0.347248 -0.00299218 0.0319967 -0.271406 -0.00491486 0.0319967 -0.29687 -0.0137724 0.0319967 -0.268233 -0.0350225 0.0319949 -0.265336 -0.0527805 0.0085312 -0.262915 -0.0527805 0.00029667 -0.262915 -0.0515437 0.000296351 -0.247924 -0.0504726 0.00713942 -0.234808 -0.0487042 0.00756863 -0.213008 -0.0492302 0.00589647 -0.212936 -0.0504004 0.000297666 -0.220394 -0.0469626 0.0140051 -0.225054 -0.0487402 0.0141946 -0.233831 -0.0512198 0.00734516 -0.245106 -0.0507756 0.0149254 -0.245184 -0.0498541 0.0107075 -0.234904 -0.0471415 0.0109615 -0.213221 -0.0499065 0.0144873 -0.239812 0.0255594 0.000308208 -0.223133 0.0206217 0.000300126 -0.244478 0.0180867 0.0073921 -0.254553 0.0195693 0.0105597 -0.244389 0.0187279 0.01401 -0.243856 0.0176581 0.0146254 -0.254549 0.0201233 0.00715874 -0.24443 -0.0265415 0.0283402 -0.248396 -0.0165545 0.0282907 -0.249759 -0.0514049 0.0154428 -0.249924 -0.0431114 0.028108 -0.254215 -0.0425131 0.0305897 -0.264315 -0.0382534 0.0317445 -0.264893 -0.00286487 0.0319948 -0.26972 0.0122664 0.0249078 -0.261792 0.0119736 0.0251414 -0.271743 0.0135012 0.0226721 -0.271951 0.019438 0.013974 -0.234119 0.0166625 0.0174242 -0.233751 0.0166374 0.0181863 -0.243991 0.0130571 0.020042 -0.233276 0.0132619 0.0215383 -0.243516 0.00463951 0.0231183 -0.232143 0.0061816 0.0212948 -0.220491 0.00897723 0.021882 -0.232733 0.0148898 0.0183393 -0.221678 0.0180694 0.0163357 -0.222111 0.00904777 0.0239263 -0.242931 -0.00052882 0.0260501 -0.241611 -0.00448529 0.0242554 -0.230874 -0.023113 0.0242536 -0.228334 -0.0406606 0.0201655 -0.225948 -0.0461651 0.0236701 -0.245755 -0.0417915 0.0264521 -0.246327 -0.0380729 0.0297837 -0.254891 -0.0328295 0.0301815 -0.255609 -0.0493682 0.0196932 -0.24535 -0.0435443 0.0218019 -0.23576 -0.0368164 0.0279974 -0.246993 -0.0392795 0.0241198 -0.236334 -0.0316416 0.0283921 -0.2477 -0.0345918 0.0254827 -0.236967 -0.0248481 0.0262043 -0.238282 -0.0176351 0.0300653 -0.257685 -0.00237821 0.0301881 -0.259765 -0.0276915 0.0301185 -0.256312 -0.00754782 0.0301161 -0.259059 0.00289437 0.0297299 -0.260481 -0.00137461 0.0284026 -0.251833 0.00792919 0.0279797 -0.261179 0.0153227 0.0206388 -0.26224 0.0172145 0.0149893 -0.257724 -0.0442525 0.0175054 -0.22544 -0.0365589 0.021978 -0.226521 -0.0322118 0.0231442 -0.227117 -0.0138055 0.0245442 -0.229595 -0.0121778 0.0229967 -0.217988 -0.0474867 0.0250954 -0.253638 -0.0505911 0.0208466 -0.25324 -0.04821 0.0189925 -0.240024 -0.0469537 0.0184357 -0.235304 -0.0489843 0.0142406 -0.235033 0.016267 0.0193918 -0.254318 0.0131273 0.0233872 -0.253851 0.00881014 0.0262526 -0.253234 0.00436965 0.0254069 -0.242285 0.00384231 0.0279128 -0.252543 -0.00545098 0.0262025 -0.240927 -0.0151691 0.0263169 -0.239597 -0.00652168 0.0283369 -0.251126 -0.0297441 0.0319967 -0.266055 0.0515905 0.0175048 0.0221723 0.0503971 0.0185126 0.0204173 -0.011241 0.00799667 0.0423174 -0.0108379 0.00968172 0.0415685 0.059254 0.000308559 0.0279299 0.0623671 0.000308703 0.0226412 0.0661934 0.00337391 0.0133025 0.0693167 0.000291871 0.000890539 0.0691925 0.00251979 0.00175094 0.054829 0.000306723 0.0336466 0.0173964 0.000298736 0.0512523 0.0352564 0.0048237 0.0471745 0.0303338 0.000297765 0.0491579 0.0405932 0.004752 0.0446317 0.0455966 0.00465144 0.0415105 0.0414896 0.000300367 0.0444304 -0.00015034 0.00464924 0.0485276 -0.000583735 0.000306999 0.0487573 0.00293557 0.000304726 0.0497564 0.0117879 0.00482356 0.050867 0.000254755 0.0149375 0.0416757 -0.00583183 0.0163398 0.0368837 -0.0102962 0.0168971 0.03305 -0.0104005 0.0146394 0.0365737 -0.0112957 0.00435469 0.0434485 -0.0261381 0.000327159 0.0308053 0.0586015 0.0154412 0.0162078 0.0556801 0.0155764 0.0210154 0.0593724 0.0133382 0.0190036 0.0534238 0.0104362 0.0316842 0.0696252 0.000301036 -0.016411 0.0681046 0.0111172 -0.00396959 0.0686544 0.00861899 -0.000813184 0.0638012 0.0147138 0.00486985 0.0688979 0.00695724 0.00052347 0.0612923 0.00394667 0.0241275 0.065871 0.0065974 0.012846 0.0607804 0.00771371 0.0234363 0.0601142 0.0108356 0.0215318 0.0654209 0.00929233 0.0114008 0.052467 0.0172821 0.0215873 0.0643681 0.013341 0.00727298 0.0649071 0.0114805 0.00944653 0.0670607 0.0102303 0.00438103 0.0695395 0.00666734 -0.0060834 0.0690928 0.00492953 0.00149301 0.0697975 0.00454223 -0.0114073 0.069988 0.00260151 -0.0102595 0.0699673 0.000296072 -0.0118427 0.0319868 0.0202309 0.0307611 0.0434885 0.0155892 0.0342567 0.0443209 0.0127216 0.037693 0.0342541 0.0131817 0.0429494 0.0335426 0.0161369 0.0392368 0.0593256 0.011008 0.0227176 0.0544217 0.00799667 0.032387 0.053812 0.0085223 0.032767 0.0450565 0.00908607 0.0403561 0.0293466 0.00950532 0.0477212 0.0348601 0.00942143 0.0458525 0.0417053 0.0195917 0.0263783 0.042618 0.0179622 0.0304911 0.0497214 0.0169966 0.0258514 0.032788 0.0185738 0.0351804 0.0215444 0.0204445 0.0333524 0.011108 0.0185731 0.0384954 0.000237228 0.0127152 0.0443751 0.01143 0.0161364 0.0426431 0.000206302 0.0155808 0.0407773 -0.0377466 0.000302499 -0.00660368 -0.0377054 0.000305865 -0.00612521 -0.0367587 0.00674383 -0.000505551 -0.036691 0.00592462 0.00127715 -0.0356204 0.00988678 0.0029366 -0.0355615 0.00867349 0.00560832 -0.0272718 0.0164791 0.0122017 0.000122265 0.0179517 0.0368532 -0.0196777 0.0153693 0.0273092 -0.0336146 0.0111223 0.00978091 -0.0336738 0.00862249 0.0129973 -0.030847 0.0130807 0.0137421 0.0221554 0.0187781 0.0379093 0.0227161 0.0163198 0.0420984 0.0117006 0.0131813 0.0464487 0.0232291 0.0133353 0.0459396 0.000205391 0.013861 0.0430505 -0.000334631 0.0122006 0.0446918 0.000152457 0.00908174 0.0472034 0.0059537 0.00928014 0.0486664 0.0118554 0.00942115 0.0494471 0.00576352 0.00475114 0.0500508 0.0178333 0.00486685 0.0509725 0.0177746 0.00950543 0.0495423 0.02363 0.0095334 0.0489601 0.0238119 0.00488122 0.0503763 0.0296425 0.0048668 0.0491006 0.0401143 0.00928185 0.0433857 0.0543979 0.00436187 0.0337025 0.0513221 0.000304907 0.0372271 -0.00983466 0.012441 0.0397109 -0.0105569 0.0119267 0.039797 -0.0198768 0.01328 0.0302759 -0.0240541 0.0124197 0.0264576 -0.0236952 0.0158316 0.0209247 0.0695457 0.0058461 -0.0130139 0.0693786 0.000303622 -0.0184133 0.0692694 0.00664075 -0.0148052 0.0691642 0.00859523 -0.00847745 0.0687536 0.00978405 -0.0111381 0.0662455 0.0131669 0.000498289 0.0577979 0.0169466 0.0131312 0.0626403 0.0166262 -0.000179448 0.0561598 0.0189363 0.00668174 0.0485212 0.0205091 0.0127667 0.0303376 0.0222129 0.0215428 0.0107333 0.0202301 0.033986 0.00992652 0.0222119 0.0245899 -1.52656e-05 0.0195793 0.0325844 -0.0102435 0.0184722 0.0292091 -0.0195253 0.0168611 0.0240641 -0.0274912 0.0146018 0.0174686 -0.0277929 0.0114042 0.0222671 -0.0310357 0.0101716 0.0177631 -0.0337428 0.0069599 0.0143648 -0.0366518 0.00459571 0.00287495 -0.0355449 0.00672064 0.00801364 -0.0280015 0.00923438 0.0243352 -0.0338678 0.00493132 0.0153659 -0.0282907 0.00655822 0.0258969 -0.0204691 0.00768383 0.035061 -0.0201235 0.0107914 0.0329783 -0.0376047 0.000310577 -0.00492227 -0.0366822 0.00262897 0.00401368 -0.0356307 0.00384194 0.00975673 -0.0340969 0.0025207 0.0156562 -0.0287281 0.00335402 0.0264732 -0.0209968 0.0039315 0.0359354 -0.0378087 0.000297667 -0.00728788 -0.0138606 0.0237943 -0.010862 -0.0187779 0.0214698 0.00351371 -0.0304945 0.0174794 0.0003192 -0.0336107 0.0150274 -0.00100129 -0.0298258 0.019658 -0.00868538 -0.0361322 0.0123464 -0.00782561 0.0689489 0.000301552 -0.0211439 0.0687755 0.000297556 -0.0221279 0.0687082 0.0078335 -0.018445 0.0678128 0.0104358 -0.0219967 0.0663052 0.0150174 -0.014574 0.0656659 0.0160212 -0.021704 0.0636249 0.0176471 -0.0125153 0.0431153 0.0241594 -0.0186296 0.0407889 0.0243884 -0.0183125 0.0328091 0.0249824 -0.0172245 0.0176831 0.0246641 0.00457873 0.00828453 0.0244831 0.00552059 -0.00103864 0.0239252 0.00562825 -0.00167936 0.0249822 -0.0125227 -0.00986393 0.0242823 -0.0114068 -0.0368986 0.00798618 -0.00412798 -0.0357436 0.0117396 -0.00249124 -0.0336115 0.0126703 0.00622383 -0.0268366 0.019199 0.00150736 -0.030728 0.0148445 0.00931332 -0.0192746 0.0188241 0.0172819 -0.0101154 0.0229515 0.00493033 -0.0101975 0.0204561 0.0211956 -0.000350204 0.0215645 0.0236866 0.0202699 0.0224243 0.0238547 0.0269941 0.0244846 0.00283273 0.0360575 0.0239493 0.000353767 0.039839 0.0215808 0.0177891 0.0447216 0.0230301 -0.00276546 0.0528416 0.0216359 -0.00641428 0.0602877 0.0194169 -0.0104344 0.0653799 0.0149577 -0.00379495 0.0675106 0.0126636 -0.0074678 0.0679199 0.0115874 -0.0165436 0.0457484 0.00992284 -0.11874 -0.0441146 0.000324341 -0.106458 -0.0442255 0.00627361 -0.13348 0.042647 0.000328353 -0.145089 0.0414621 0.00631214 -0.145161 0.0476876 0.000325968 -0.122112 0.063388 0.00799743 -0.0468777 0.0664451 0.0129714 -0.0254855 0.0672816 0.01241 -0.0219243 0.0621754 0.0195022 -0.0212281 0.0611184 0.0197732 -0.0249609 0.0599933 0.0203278 -0.0253854 0.0582707 0.020973 -0.0267782 0.0571269 0.0211851 -0.0301991 0.0555609 0.022137 -0.0203264 0.0500456 0.0232591 -0.0195744 0.0321592 0.0250197 -0.0171359 0.0283772 0.0247248 -0.0469116 -0.00539553 0.0246915 -0.0423164 0.00545179 0.0253341 -0.0134949 0.0183209 0.0254788 -0.0152493 0.0235768 0.0253766 -0.0159659 -0.0296814 0.0207691 -0.0260792 -0.0187408 0.0230202 -0.0101966 -0.0292338 0.0208983 -0.0249288 -0.0290775 0.0209096 -0.0238687 -0.0238445 0.0218923 -0.00950082 -0.0316824 0.0193434 -0.0191363 -0.03441 0.0157838 -0.00806039 -0.0369269 0.0127451 -0.0181868 -0.035812 0.0131992 -0.00786926 -0.0358861 0.0150306 -0.0182429 -0.0343694 0.0171015 -0.0183263 -0.0219448 0.0230882 -0.0379786 -0.0239349 0.0221712 -0.0616978 -0.0060012 0.0241937 -0.0561128 -0.00489826 0.0242241 -0.0570531 -0.00319513 0.0242896 -0.0578963 -0.0077677 0.0236117 -0.0642781 0.00846626 0.0241726 -0.066662 0.00268158 0.0246062 -0.0571372 0.0113476 0.025213 -0.0455436 0.00108808 0.0249968 -0.0449643 0.0632964 0.0158721 -0.0356503 0.0625612 0.0122161 -0.0470521 0.0578539 0.01924 -0.0472392 0.0608876 0.0161986 -0.047202 0.0630351 0.016314 -0.0355933 -0.0321745 0.0196431 -0.0284065 -0.038334 0.0121695 -0.0332986 -0.0377209 0.0129833 -0.0287659 -0.0388777 0.00799667 -0.0287039 -0.0380507 0.00799667 -0.0181283 -0.0378368 0.000297939 -0.0075934 -0.0367215 0.0102934 -0.00774527 -0.0284899 0.0175831 -0.138395 -0.0347249 0.015286 -0.136423 -0.0457899 0.00604457 -0.160073 -0.0443042 0.00897503 -0.160583 -0.0395745 0.0153493 -0.18806 -0.0424962 0.0163845 -0.213854 -0.0443452 0.0114097 -0.187102 -0.0450357 0.0139578 -0.213508 -0.0467019 0.0116926 -0.213281 -0.0426555 0.00931839 -0.133986 -0.0422371 0.0114826 -0.161268 -0.0474687 0.00592008 -0.186462 -0.0391039 0.0127506 -0.107194 -0.0370035 0.0150103 -0.163004 -0.0278016 0.0197904 -0.190377 -0.0325029 0.0208602 -0.215217 -0.0261108 0.0185087 -0.109086 -0.0311346 0.0174596 -0.164984 -0.0187654 0.0208831 -0.168888 -0.0215651 0.0209635 -0.191539 -0.0299985 0.021424 -0.215558 -0.0229822 0.0224802 -0.216515 -0.0393418 0.018391 -0.214284 -0.0418373 0.0168764 -0.213944 -0.0338788 0.0179823 -0.189192 -0.0377032 0.0138342 -0.135503 -0.0404284 0.0118906 -0.134674 0.00392269 0.0209658 -0.195011 0.000716392 0.0217643 -0.172268 0.00457968 0.0221606 -0.145701 0.0369349 0.0158636 -0.117616 0.0401684 0.0143412 -0.118027 0.0261479 0.0146181 -0.171607 0.0317132 0.011205 -0.171347 0.0370627 0.0115577 -0.145235 0.0310179 0.0147908 -0.14538 -0.00222898 0.0225099 -0.14504 -0.0104134 0.0220503 -0.205049 -0.00585898 0.022066 -0.171654 0.0102103 0.0197797 -0.195556 0.000373878 0.0222793 -0.219699 0.00222626 0.0213043 -0.206738 -0.00315462 0.0226443 -0.219218 -0.00734846 0.0229004 -0.218646 0.00926923 0.022629 -0.11407 0.0113708 0.021172 -0.145928 0.0163567 0.0217168 -0.114996 0.0180892 0.0196121 -0.145861 0.0137778 0.0194482 -0.17228 0.0242867 0.00759335 -0.222959 0.039742 0.00930848 -0.145218 0.0358085 0.00607731 -0.171197 0.0341834 0.00896872 -0.171281 0.0302801 0.00593963 -0.197061 0.0247885 0.00589886 -0.223027 0.0289365 0.00883174 -0.19697 0.0223225 0.0117072 -0.222691 0.0206873 0.0138847 -0.222468 0.0206165 0.013965 -0.222459 0.0173813 0.0168412 -0.222018 0.0163263 0.0179288 -0.196034 0.0096916 0.0203865 -0.220969 0.00728197 0.0208868 -0.172429 0.00563003 0.0248865 -0.0528365 0.0579786 0.00768597 -0.0723711 0.0571805 0.0117159 -0.0723142 0.0526128 0.0183011 -0.0718413 0.0539603 0.0210818 -0.0472141 0.0489154 0.0200225 -0.0714286 0.0409766 0.0219216 -0.0705459 0.0526782 0.00718613 -0.0955669 0.0472946 0.00667949 -0.118934 0.0495191 0.0139802 -0.0948893 0.0432217 0.0124716 -0.118417 0.0302377 0.0183574 -0.116767 0.0233573 0.0202876 -0.115894 0.0358357 0.0199947 -0.0922585 0.0208977 0.0224143 -0.0894495 0.0431031 0.0178895 -0.0936594 0.0465522 0.016311 -0.0943174 0.0555398 0.0154718 -0.0721588 0.0515541 0.0108246 -0.095307 -0.0299867 0.0210298 -0.0357751 -0.0336527 0.019038 -0.0347681 -0.0318045 0.020257 -0.0604248 -0.0365798 0.016032 -0.0339169 -0.0391866 0.00798729 -0.0328942 -0.040252 0.000304267 -0.0401027 -0.0414323 0.000307316 -0.0587764 -0.0408213 0.0076831 -0.0589016 -0.0418567 0.00717053 -0.0826784 -0.0399271 0.0116875 -0.0590756 -0.0381921 0.0153882 -0.0593807 -0.0323493 0.0183181 -0.0833707 -0.0353652 0.0183094 -0.0598478 -0.0248904 0.0202423 -0.0839766 0.0247456 0.023666 -0.0687091 0.0455468 0.0230342 -0.0471718 -0.0230643 0.021302 -0.203291 -0.00884882 0.0218485 -0.193576 0.00212654 0.0229539 -0.113112 -0.0156121 0.021161 -0.142259 -0.0121262 0.0216907 -0.111114 0.0220241 0.0151158 -0.196456 0.0269265 0.0112604 -0.196818 0.0201232 0.0174019 -0.171963 0.0246733 0.0174972 -0.145634 0.0056871 0.0232317 -0.0870218 -0.00964202 0.0223668 -0.0852826 -0.0329577 0.0163787 -0.108088 -0.0357959 0.0166078 -0.0830891 -0.0362116 0.0148751 -0.107615 -0.0386738 0.0140815 -0.0828646 -0.0406613 0.0108152 -0.0827344 -0.0413401 0.00992799 -0.106867 -0.0428417 0.00664636 -0.106645 0.0148264 0.0169967 -0.272132 0.0141299 0.0173799 -0.275308 0.0141299 0.00029667 -0.275308 0.0136073 0.00029667 -0.277692 0.013518 0.000323348 -0.278099 0.0697195 -3.3303e-06 -0.00797206 -0.045076 -3.3303e-06 -0.210336 -0.0419161 -3.3303e-06 -0.160543 -0.0435472 -3.3303e-06 -0.161907 -0.041916 -3.3303e-06 -0.153093 -0.0340766 -3.3303e-06 -0.0196264 -0.0305693 -3.3303e-06 -0.0257014 -0.0320517 -3.3303e-06 -0.0271838 0.00054471 -3.3303e-06 -0.0487174 0.00209468 -3.3303e-06 -0.0514021 -0.00368998 -3.3303e-06 -0.049852 -0.00255529 -3.3303e-06 -0.0487174 -0.00369002 -3.3303e-06 -0.052952 -0.0194629 -3.3303e-06 -0.0411747 0.0621546 -3.3303e-06 -0.0340486 0.0601296 -3.3303e-06 -0.033506 0.0581046 -3.3303e-06 -0.0299985 0.0656621 -3.3303e-06 -0.0279736 0.0668908 -3.3303e-06 -0.0302649 0.0641796 -3.3303e-06 -0.033506 0.0624617 -3.3303e-06 -0.0411757 -0.0300267 -3.3303e-06 -0.0236764 -0.0194626 -3.3303e-06 -0.0160395 -0.0324719 -3.3303e-06 -0.0160393 -0.0382062 -3.3303e-06 -0.0160315 -0.0382897 -3.3303e-06 -0.01711 -0.0375841 -3.3303e-06 -0.0216513 -0.0381267 -3.3303e-06 -0.0236763 -0.0418692 -3.3303e-06 -0.0993925 -0.0324726 -3.3303e-06 -0.0741534 -0.0349183 -3.3303e-06 -0.0975301 -0.0381587 -3.3303e-06 -0.0741533 -0.0435465 -3.3303e-06 -0.103264 -0.0405058 -3.3303e-06 -0.100756 -0.045142 -3.3303e-06 -0.154955 -0.0468808 -3.3303e-06 -0.161908 -0.038159 -3.3303e-06 -0.103264 -0.0400535 -3.3303e-06 -0.153592 -0.0381598 -3.3303e-06 -0.161907 -0.0386433 -3.3303e-06 -0.101255 -0.03977 -3.3303e-06 -0.103264 -0.043548 -3.3303e-06 -0.218529 -0.0450761 -3.3303e-06 -0.217786 -0.048302 -3.3303e-06 -0.215923 -0.0485492 -3.3303e-06 -0.191921 -0.0418501 -3.3303e-06 -0.215923 -0.041351 -3.3303e-06 -0.214061 -0.0397711 -3.3303e-06 -0.190529 -0.0418501 -3.3303e-06 -0.212198 -0.0503143 -3.3303e-06 -0.271988 -0.0435483 -3.3303e-06 -0.247666 -0.0452259 -3.3303e-06 -0.273352 -0.0435487 -3.3303e-06 -0.277499 -0.0498555 -3.3303e-06 -0.281428 -0.0465894 -3.3303e-06 -0.27844 -0.0435476 -3.3303e-06 -0.190529 -0.0484718 -3.3303e-06 -0.190529 -0.0375841 -3.3303e-06 -0.0257013 -0.038158 -3.3303e-06 -0.0232697 -0.040022 -3.3303e-06 -0.0411553 -0.0374217 -3.3303e-06 -0.0124522 -0.0371103 -3.3303e-06 -0.0100951 -0.0361457 -3.3303e-06 0.00282007 -0.0364581 -3.3303e-06 -0.00242831 -0.0372307 -3.3303e-06 -0.0100537 -0.0375379 -3.3303e-06 -0.00761871 -0.0363733 -3.3303e-06 8.94675e-05 -0.0364925 -3.3303e-06 0.00458714 -0.0354449 -3.3303e-06 0.010605 -0.00282294 -3.3303e-06 0.0382146 -0.00484784 -3.3303e-06 0.045772 0.0002634 -3.3303e-06 0.0487087 -0.00687294 -3.3303e-06 0.0382146 -0.019462 -3.3303e-06 0.0338623 -0.00889789 -3.3303e-06 0.0417221 -0.0108354 -3.3303e-06 0.0438561 0.0121605 -3.3303e-06 0.050877 0.00616122 -3.3303e-06 0.0501402 0.0546697 -3.3303e-06 0.0219515 0.0566947 -3.3303e-06 0.0224941 0.0642222 -3.3303e-06 0.0179741 0.0499115 -3.3303e-06 0.014276 0.0506197 -3.3303e-06 0.0260015 0.0464581 -3.3303e-06 0.0408576 0.0511623 -3.3303e-06 0.0280265 0.0526448 -3.3303e-06 0.0295089 0.0499117 -3.3303e-06 0.0338614 0.0553172 -3.3303e-06 0.0326304 0.0546698 -3.3303e-06 0.0300515 0.0566948 -3.3303e-06 0.0295089 0.0621004 -3.3303e-06 0.0225043 0.0697167 -3.3303e-06 -0.0077948 0.0689889 -3.3303e-06 -0.00324488 0.0683861 -3.3303e-06 0.00170649 0.0674201 -3.3303e-06 0.00660028 0.0690199 -3.3303e-06 0.000847546 0.0665515 -3.3303e-06 0.0116565 0.0689515 -3.3303e-06 -0.0150765 0.0668123 -3.3303e-06 -0.0160406 0.0687944 0.000153447 -0.0132188 0.0473394 -3.3303e-06 -0.105772 0.0487028 -3.3303e-06 -0.107136 0.0499228 -3.3303e-06 -0.110539 0.0487028 -3.3303e-06 -0.110861 0.0473393 -3.3303e-06 -0.112224 0.0472635 -3.3303e-06 -0.122652 0.0436143 -3.3303e-06 -0.112224 0.0436144 -3.3303e-06 -0.105772 0.0364846 -3.3303e-06 -0.166998 0.0359855 -3.3303e-06 -0.168861 0.034622 -3.3303e-06 -0.170224 0.0295336 -3.3303e-06 -0.168861 0.0266203 -3.3303e-06 -0.19053 0.0290346 -3.3303e-06 -0.166998 0.0266206 -3.3303e-06 -0.161908 0.0386557 -3.3303e-06 -0.161907 0.00401567 -3.3303e-06 -0.21853 0.0237068 -3.3303e-06 -0.224861 0.0252666 -3.3303e-06 -0.223068 0.0186183 -3.3303e-06 -0.226224 0.0167559 -3.3303e-06 -0.222998 0.0262598 -3.3303e-06 -0.21853 0.0223433 -3.3303e-06 -0.226224 0.0204808 -3.3303e-06 -0.226723 0.022594 -3.3303e-06 -0.234895 0.0195458 -3.3303e-06 -0.247644 0.00966306 -3.3303e-06 -0.27606 0.00966316 -3.3303e-06 -0.26861 0.00643719 -3.3303e-06 -0.270472 0.00401486 -3.3303e-06 -0.281429 0.0133143 -3.3303e-06 -0.277627 -0.0397715 -3.3303e-06 -0.218529 -0.0397718 -3.3303e-06 -0.247666 -0.0397722 -3.3303e-06 -0.277499 -0.0397723 -3.3303e-06 -0.281428 -0.0400536 -3.3303e-06 -0.160043 -0.0397707 -3.3303e-06 -0.161907 -0.0381602 -3.3303e-06 -0.190529 -0.0381605 -3.3303e-06 -0.218529 -0.0367808 -3.3303e-06 -0.100756 -0.032473 -3.3303e-06 -0.103264 -0.0324741 -3.3303e-06 -0.190529 -0.0324745 -3.3303e-06 -0.218529 -0.0381609 -3.3303e-06 -0.247666 -0.0324749 -3.3303e-06 -0.247666 -0.0381613 -3.3303e-06 -0.277499 -0.0324752 -3.3303e-06 -0.277499 -0.00100536 -3.3303e-06 -0.0545021 -0.0194634 -3.3303e-06 -0.0741536 0.000647131 -3.3303e-06 -0.103264 0.00064638 -3.3303e-06 -0.161908 -0.0194648 -3.3303e-06 -0.190529 0.000646014 -3.3303e-06 -0.190529 0.000645655 -3.3303e-06 -0.218529 -0.0194656 -3.3303e-06 -0.247666 -0.019466 -3.3303e-06 -0.277499 0.000645282 -3.3303e-06 -0.247666 0.0006449 -3.3303e-06 -0.2775 0.00167933 -3.3303e-06 -0.0529521 0.000647503 -3.3303e-06 -0.0741538 0.00401714 -3.3303e-06 -0.103264 0.00401529 -3.3303e-06 -0.247666 0.00401491 -3.3303e-06 -0.2775 -0.0405057 -3.3303e-06 -0.0943041 -0.0397696 -3.3303e-06 -0.0741533 -0.0381582 -3.3303e-06 -0.0411745 -0.0324722 -3.3303e-06 -0.0411745 -0.0194637 -3.3303e-06 -0.103264 -0.0324738 -3.3303e-06 -0.161908 -0.0194645 -3.3303e-06 -0.161908 -0.0194652 -3.3303e-06 -0.218529 -0.019466 -3.3303e-06 -0.281428 0.0624619 -3.3303e-06 -0.023271 0.0668122 -3.3303e-06 -0.023271 -0.0324715 -3.3303e-06 0.0142771 -0.0320516 -3.3303e-06 -0.020169 -0.0305692 -3.3303e-06 -0.0216514 0.0624624 -3.3303e-06 0.0142759 0.062462 -3.3303e-06 -0.0160405 -0.0194622 -3.3303e-06 0.0142769 0.000648636 -3.3303e-06 0.0142767 -0.0194627 -3.3303e-06 -0.0232699 0.000648247 -3.3303e-06 -0.0160397 0.000648155 -3.3303e-06 -0.0232702 0.000647926 -3.3303e-06 -0.041175 0.000648886 -3.3303e-06 0.0338621 0.0040189 -3.3303e-06 0.033862 0.00401826 -3.3303e-06 -0.0160398 0.00167937 -3.3303e-06 -0.0498521 0.00401865 -3.3303e-06 0.0142766 0.0266229 -3.3303e-06 0.0142763 0.0266225 -3.3303e-06 -0.0160401 0.00401817 -3.3303e-06 -0.0232702 0.0266222 -3.3303e-06 -0.0411753 0.00401794 -3.3303e-06 -0.041175 0.00401752 -3.3303e-06 -0.0741539 0.00401639 -3.3303e-06 -0.161908 0.00401603 -3.3303e-06 -0.19053 0.0266186 -3.3303e-06 -0.21689 0.0391096 -3.3303e-06 -0.159835 0.0266214 -3.3303e-06 -0.103265 0.039119 -3.3303e-06 -0.0741543 0.0266218 -3.3303e-06 -0.0741542 0.0391195 -3.3303e-06 -0.0411754 0.0266224 -3.3303e-06 -0.0232705 0.0391197 -3.3303e-06 -0.0232707 0.0391198 -3.3303e-06 -0.0160402 0.0266232 -3.3303e-06 0.0338617 0.0413415 -3.3303e-06 0.0441695 0.0391202 -3.3303e-06 0.0142762 0.0499111 -3.3303e-06 -0.0160404 0.049911 -3.3303e-06 -0.0232708 0.0499108 -3.3303e-06 -0.0411756 0.0499104 -3.3303e-06 -0.0741545 0.0391187 -3.3303e-06 -0.103265 0.04991 -3.3303e-06 -0.103265 0.0454769 -3.3303e-06 -0.105273 -0.0545636 0.0201512 -0.308516 -0.0527092 0.0205812 -0.317469 -0.0503186 0.0197967 -0.323813 -0.0503177 0.020901 -0.323813 -0.049779 0.0209607 -0.324959 -0.0466321 0.0212624 -0.330528 -0.0440464 0.0197967 -0.334148 -0.0440464 0.0214722 -0.334147 -0.0211013 0.0197967 -0.362128 -0.0347776 0.0222128 -0.345463 -0.0190919 0.0197967 -0.364577 -0.0190466 0.0251092 -0.364632 -0.0113969 0.0259118 -0.371122 -0.0133286 0.0197967 -0.369963 -0.00578663 0.0197967 -0.373292 -0.00537671 0.0259967 -0.373389 -0.00380814 0.0259967 -0.373694 0.00287336 0.0259967 -0.373823 0.00514104 0.0197967 -0.373439 0.00420402 0.0259967 -0.373624 0.0159009 0.0197967 -0.367966 0.0174319 0.0259967 -0.366484 0.0199027 0.0197967 -0.363397 0.0222069 0.0259967 -0.359078 0.0226277 0.0197967 -0.357972 0.023907 0.025992 -0.351998 0.0239069 0.0197967 -0.351999 0.0239575 0.0259836 -0.351258 0.0236723 0.0258188 -0.34611 0.0230361 0.0256536 -0.343299 0.021352 0.025296 -0.33899 0.0127053 0.0228554 -0.319906 0.0116345 0.022527 -0.317543 0.00994491 0.0197967 -0.313813 0.00994554 0.022027 -0.313815 0.00810892 0.0197967 -0.307005 0.00805338 0.021086 -0.306113 0.00828773 0.0206117 -0.302102 0.00846461 0.0197967 -0.301149 0.0130837 0.0196946 -0.279228 0.0129798 0.0195945 -0.279439 -0.045076 -0.00240333 -0.210636 -0.0468947 -0.00240333 -0.213011 -0.047176 -0.00240333 -0.214061 -0.0480421 -0.00240333 -0.212348 -0.0468947 -0.00240333 -0.215111 -0.0480422 -0.00240333 -0.215773 -0.046126 -0.00240333 -0.215879 -0.045076 -0.00240333 -0.216161 -0.0432574 -0.00240333 -0.215111 -0.0421099 -0.00240333 -0.212348 -0.044026 -0.00240333 -0.212242 -0.0537143 0.0182903 -0.279831 -0.0543242 0.017412 -0.290878 -0.0542775 0.0169018 -0.290033 -0.0541783 0.0155889 -0.288236 -0.0540526 0.0133374 -0.285958 -0.0539909 0.011879 -0.284842 -0.0539501 0.0107136 -0.284102 -0.053834 0.00524241 -0.281999 -0.0538126 0.00149667 -0.281611 -0.0538125 0.000470496 -0.28161 -0.0537199 0.00029667 -0.279932 -0.0538071 0.00039667 -0.281511 -0.0538106 0.000381894 -0.281575 -0.0538067 0.000319347 -0.281503 -0.0527805 0.0169947 -0.262915 -0.00410532 -3.3303e-06 -0.051402 -0.00410532 0.0199967 -0.051402 -0.00368998 0.0199967 -0.049852 -0.00255529 0.0199967 -0.0487174 -0.00100529 -3.3303e-06 -0.0483021 -0.00100529 0.0199967 -0.0483021 0.00054471 0.0199967 -0.0487174 0.00209468 0.0199967 -0.0514021 0.00167933 0.0199967 -0.0529521 0.000544641 -3.3303e-06 -0.0540868 0.000544641 0.0199967 -0.0540868 -0.00255536 0.0199967 -0.0540867 -0.00255536 -3.3303e-06 -0.0540867 -0.00697319 0.0234842 -0.0507813 -0.00400539 0.0202967 -0.0565982 -0.00625086 0.0233864 -0.0543146 -0.00700533 0.0202967 -0.051402 -0.00100525 0.0235928 -0.0574021 -0.0010054 0.0202967 -0.0574021 -0.00164317 0.023557 -0.0573679 -0.00400524 0.0234421 -0.0565983 0.00199461 0.0202967 -0.0565983 0.00199463 0.0237869 -0.0565983 9.78802e-05 0.0236589 -0.0572998 0.00359605 0.0239196 -0.0552527 0.00419075 0.0239824 -0.0544023 0.00499468 0.0202967 -0.0514022 0.00427401 0.0242398 -0.0485509 0.0048918 0.0241903 -0.0502958 0.00419087 0.0202967 -0.0484021 0.00401769 0.0242472 -0.0481204 0.00199474 0.0202967 -0.046206 0.00237396 0.024243 -0.0464442 -0.00100568 0.0241051 -0.0454021 -0.00100525 0.0202967 -0.0454021 -0.00211629 0.0240335 -0.0455058 -0.00687604 0.023517 -0.0501632 -0.00620119 0.0236389 -0.0484016 -0.00560681 0.0237164 -0.0475515 -0.00650262 0.0150424 0.0375373 -0.00793324 0.0135346 0.0384462 -0.00881482 0.00799667 0.0395975 -0.00595613 0.00799667 0.0373606 -0.00600022 0.0153974 0.037372 -0.00517731 0.0158395 0.0372343 -0.00375707 0.00799667 0.0373562 -0.00376684 0.0162724 0.0373538 -0.000603394 0.00799667 0.0402273 -0.00181851 0.00799667 0.0383944 -0.000589916 0.015113 0.0402659 -0.000870931 0.015552 0.0396166 -0.00180669 0.0161761 0.0384052 -0.00205054 0.0162482 0.0381971 -0.000493848 0.012805 0.0428586 -0.000404341 0.0132563 0.0424325 -0.000446692 0.0147213 0.0407842 -0.0343247 0.0169806 -0.0281695 -0.0328268 0.00799667 -0.0279993 -0.0327655 0.0184878 -0.0279811 -0.029781 0.0201379 -0.0250168 -0.0299999 0.0200635 -0.0255816 -0.0309336 0.0196475 -0.0268968 -0.0297803 0.00799667 -0.0250147 -0.0295767 0.0201579 -0.0236764 -0.0296591 0.00799667 -0.022819 -0.0323586 0.00799667 -0.0195173 -0.0338286 0.0165588 -0.0191832 -0.0303267 0.00249667 -0.0236764 -0.0303267 0.00029667 -0.0236764 -0.0308291 0.00249667 -0.0218014 -0.0322016 0.00249667 -0.0204288 -0.0322016 0.00029667 -0.0204288 -0.0340766 0.00249667 -0.0199264 -0.0340766 0.00029667 -0.0199264 -0.0359516 0.00249667 -0.0204287 -0.0373242 0.00249667 -0.0218013 -0.0373242 0.00029667 -0.0218013 -0.0378267 0.00029667 -0.0236763 -0.0340767 0.00249667 -0.0274264 -0.0359517 0.00029667 -0.0269239 -0.0322017 0.00249667 -0.026924 -0.0308291 0.00249667 -0.0255514 -0.0308291 0.00029667 -0.0255514 0.0659046 0.00029667 -0.0299986 0.0654022 0.00029667 -0.0281236 0.0621547 0.00249667 -0.0262486 0.0621547 0.00029667 -0.0262486 0.0602797 0.00029667 -0.026751 0.0589071 0.00249667 -0.0281236 0.0589071 0.00029667 -0.0281236 0.0584046 0.00249667 -0.0299986 0.058907 0.00029667 -0.0318736 0.0640296 0.00249667 -0.0332462 0.0654022 0.00249667 -0.0318736 0.0640296 0.00029667 -0.0332462 0.0659046 0.00249667 -0.0299986 0.0565448 0.00029667 0.0292491 0.0527948 0.00029667 0.0292491 0.0527948 0.00249667 0.0292491 0.0514221 0.00029667 0.0278765 0.0514221 0.00249667 0.0241265 0.0514221 0.00029667 0.0241265 0.0546697 0.00249667 0.0222515 0.0527947 0.00029667 0.0227539 0.0546697 0.00029667 0.0222515 0.0565447 0.00249667 0.0227539 0.0584197 0.00249667 0.0260014 -0.00160027 0.00249667 0.043597 -0.00160027 0.00029667 0.043597 -0.00297285 0.00249667 0.0449696 -0.00297285 0.00029667 0.0449696 -0.00484785 0.00029667 0.045472 -0.00672285 0.00029667 0.0449696 -0.00809546 0.00029667 0.0435971 -0.00859789 0.00249667 0.0417221 -0.00859789 0.00029667 0.0417221 -0.00809551 0.00029667 0.0398471 -0.00672294 0.00029667 0.0384744 -0.00484794 0.00029667 0.037972 -0.00297294 0.00029667 0.0384744 -0.00160032 0.00029667 0.039847 -0.0516778 -0.00210333 -0.273351 -0.0516778 -3.3303e-06 -0.273351 -0.0484518 -0.00210333 -0.271489 -0.0484518 -3.3303e-06 -0.271489 -0.0465893 -3.3303e-06 -0.271988 -0.0452259 -0.00210333 -0.277077 -0.0447268 -3.3303e-06 -0.275214 -0.0452259 -3.3303e-06 -0.277077 -0.0484519 -3.3303e-06 -0.278939 -0.0503144 -0.00210333 -0.27844 -0.0503144 -3.3303e-06 -0.27844 -0.0516778 -0.00210333 -0.277076 -0.0516778 -3.3303e-06 -0.277076 -0.0521768 -0.00210333 -0.275214 -0.0521768 -3.3303e-06 -0.275214 0.00780065 -3.3303e-06 -0.269109 0.00780065 -0.00210333 -0.269109 0.00966316 -0.00210333 -0.26861 0.0115257 -0.00210333 -0.269109 0.0115257 -3.3303e-06 -0.269109 0.0133881 -0.00210333 -0.272335 0.0128891 -3.3303e-06 -0.270472 0.0133881 -3.3303e-06 -0.272335 0.012889 -0.00210333 -0.274197 0.012889 -3.3303e-06 -0.274197 0.0115256 -3.3303e-06 -0.275561 0.0115256 -0.00210333 -0.275561 0.00780057 -0.00210333 -0.275561 0.00780057 -3.3303e-06 -0.275561 0.00643714 -3.3303e-06 -0.274197 0.00593811 -3.3303e-06 -0.272335 -0.0483019 -3.3303e-06 -0.212198 -0.0469385 -0.00210333 -0.210835 -0.0469385 -3.3303e-06 -0.210835 -0.0432135 -0.00210333 -0.210835 -0.0418501 -0.00210333 -0.212198 -0.0432135 -3.3303e-06 -0.210835 -0.0432136 -3.3303e-06 -0.217286 -0.0432136 -0.00210333 -0.217286 -0.0469386 -0.00210333 -0.217286 -0.0469386 -3.3303e-06 -0.217286 -0.048801 -3.3303e-06 -0.21406 0.0172549 -3.3303e-06 -0.221136 0.0186184 -0.00210333 -0.219772 0.0186184 -3.3303e-06 -0.219772 0.0204809 -3.3303e-06 -0.219273 0.0223434 -3.3303e-06 -0.219772 0.0237068 -3.3303e-06 -0.221136 0.0242059 -0.00210333 -0.222998 0.0242059 -3.3303e-06 -0.222998 0.0223433 -0.00210333 -0.226224 0.0186183 -0.00210333 -0.226224 0.0172549 -3.3303e-06 -0.224861 0.0172549 -0.00210333 -0.221136 -0.0437785 -0.00210333 -0.153592 -0.0437785 -3.3303e-06 -0.153592 -0.041916 -0.00210333 -0.153093 -0.0400535 -0.00210333 -0.153592 -0.0386901 -3.3303e-06 -0.154955 -0.0381911 -0.00210333 -0.156818 -0.0381911 -3.3303e-06 -0.156818 -0.0386901 -0.00210333 -0.15868 -0.0386901 -3.3303e-06 -0.15868 -0.0419161 -0.00210333 -0.160543 -0.0437786 -0.00210333 -0.160043 -0.0437786 -3.3303e-06 -0.160043 -0.045142 -3.3303e-06 -0.15868 -0.0456411 -0.00210333 -0.156817 -0.0456411 -3.3303e-06 -0.156817 0.0308971 -0.00210333 -0.163772 0.0295337 -3.3303e-06 -0.165136 0.0308971 -3.3303e-06 -0.163772 0.0327596 -3.3303e-06 -0.163273 0.0346221 -0.00210333 -0.163772 0.0359856 -0.00210333 -0.165136 0.0346221 -3.3303e-06 -0.163772 0.0359856 -3.3303e-06 -0.165136 0.0364846 -0.00210333 -0.166998 0.0359855 -0.00210333 -0.168861 0.0327595 -0.00210333 -0.170723 0.0327595 -3.3303e-06 -0.170723 0.030897 -3.3303e-06 -0.170224 0.0295336 -0.00210333 -0.168861 0.0422509 -0.00210333 -0.107136 0.0422509 -3.3303e-06 -0.107136 0.0454769 -0.00210333 -0.105273 0.0487028 -0.00210333 -0.107136 0.0492018 -3.3303e-06 -0.108998 0.0454768 -3.3303e-06 -0.112723 0.0422509 -0.00210333 -0.110861 0.0422509 -3.3303e-06 -0.110861 0.0417518 -0.00210333 -0.108998 0.0417518 -3.3303e-06 -0.108998 -0.0418692 -3.3303e-06 -0.0956675 -0.0386432 -3.3303e-06 -0.0938051 -0.0367807 -3.3303e-06 -0.0943042 -0.0354173 -0.00210333 -0.0956676 -0.0354173 -3.3303e-06 -0.0956676 -0.0354173 -3.3303e-06 -0.0993926 -0.0367808 -0.00210333 -0.100756 -0.0386433 -0.00210333 -0.101255 -0.0423683 -3.3303e-06 -0.09753 0.0114818 0.00859667 -0.271285 0.0107131 0.00859667 -0.270516 0.00966311 0.00985848 -0.272335 0.00784444 0.00859667 -0.273385 0.00966314 0.00859667 -0.270235 0.00966314 -0.00240333 -0.270235 0.00861313 0.00859667 -0.270516 0.00861313 -0.00240333 -0.270516 0.00784447 0.00859667 -0.271285 0.00784447 -0.00240333 -0.271285 0.00756311 0.00859667 -0.272335 0.00756311 -0.00240333 -0.272335 0.00861309 0.00859667 -0.274153 0.00966308 0.00859667 -0.274435 0.00966308 -0.00240333 -0.274435 0.0107131 0.00859667 -0.274153 0.0114818 0.00859667 -0.273385 0.0114818 -0.00240333 -0.273385 0.0117631 0.00859667 -0.272335 -0.0484518 0.00859667 -0.273114 -0.0474018 0.00859667 -0.273395 -0.0484518 0.00985848 -0.275214 -0.0484519 0.00859667 -0.277314 -0.0495019 0.00859667 -0.277033 -0.0463518 0.00859667 -0.275214 -0.0466332 0.00859667 -0.274164 -0.0495018 0.00859667 -0.273395 -0.0502705 0.00859667 -0.274164 -0.0505518 0.00859667 -0.275214 -0.0502705 0.00859667 -0.276264 -0.0474019 0.00859667 -0.277033 -0.0474019 -0.00240333 -0.277033 -0.0466332 0.00859667 -0.276264 -0.0466332 -0.00240333 -0.276264 0.0222995 0.00859667 -0.221948 0.0183809 0.00859667 -0.222998 0.0222995 0.00859667 -0.224048 0.0215308 0.00859667 -0.224817 0.0204809 0.00985848 -0.222998 0.0225809 0.00859667 -0.222998 0.0215309 0.00859667 -0.221179 0.0222995 -0.00240333 -0.221948 0.0215309 -0.00240333 -0.221179 0.0204809 0.00859667 -0.220898 0.0204809 -0.00240333 -0.220898 0.0194309 0.00859667 -0.221179 0.0186622 0.00859667 -0.221948 0.0186622 -0.00240333 -0.224048 0.0186622 0.00859667 -0.224048 0.0194308 -0.00240333 -0.224817 0.0194308 0.00859667 -0.224817 0.0204808 0.00859667 -0.225098 0.0215308 -0.00240333 -0.224817 -0.0432574 0.00859667 -0.213011 -0.045076 0.00985848 -0.214061 -0.046126 0.00859667 -0.212242 -0.045076 0.00859667 -0.211961 -0.046126 0.00859667 -0.215879 -0.0468947 0.00859667 -0.215111 -0.0432574 0.00859667 -0.215111 -0.042976 -0.00240333 -0.214061 -0.044026 0.00859667 -0.212242 -0.0432574 -0.00240333 -0.213011 -0.045076 -0.00240333 -0.211961 -0.046126 -0.00240333 -0.212242 -0.0468947 0.00859667 -0.213011 -0.047176 0.00859667 -0.214061 -0.045076 0.00859667 -0.216161 -0.044026 0.00859667 -0.215879 -0.044026 -0.00240333 -0.215879 -0.042976 0.00859667 -0.214061 0.0338096 0.00859667 -0.16518 0.0345783 0.00859667 -0.165948 0.0327596 0.00859667 -0.164898 0.0327596 0.00985848 -0.166998 0.0317096 0.00859667 -0.168817 0.0309409 0.00859667 -0.165948 0.0306596 0.00859667 -0.166998 0.0338096 0.00859667 -0.168817 0.0345782 0.00859667 -0.168048 0.0327596 0.00859667 -0.169098 0.0345783 -0.00240333 -0.165948 0.0327596 -0.00240333 -0.164898 0.0317096 0.00859667 -0.16518 0.0309409 -0.00240333 -0.165948 0.0309409 0.00859667 -0.168048 0.0348596 0.00859667 -0.166998 0.0345782 -0.00240333 -0.168048 -0.0419161 0.00985848 -0.156818 -0.040866 0.00859667 -0.154999 -0.0400974 0.00859667 -0.155768 -0.0437347 0.00859667 -0.155767 -0.042966 0.00859667 -0.154999 -0.041916 0.00859667 -0.154718 -0.0440161 0.00859667 -0.156817 -0.0437347 0.00859667 -0.157867 -0.0408661 0.00859667 -0.158636 -0.0398161 -0.00240333 -0.156818 -0.041916 -0.00240333 -0.154718 -0.042966 -0.00240333 -0.154999 -0.0437347 -0.00240333 -0.155767 -0.0429661 0.00859667 -0.158636 -0.0419161 0.00859667 -0.158918 -0.0408661 -0.00240333 -0.158636 -0.0400974 0.00859667 -0.157868 -0.0398161 0.00859667 -0.156818 -0.0400974 -0.00240333 -0.157868 0.0465269 0.00859667 -0.10718 0.0444269 0.00859667 -0.10718 0.0444268 0.00859667 -0.110817 0.0454768 0.00859667 -0.111098 0.0454768 0.00985848 -0.108998 0.0475768 0.00859667 -0.108998 0.0472955 0.00859667 -0.107948 0.0472955 -0.00240333 -0.107948 0.0454769 0.00859667 -0.106898 0.0454769 -0.00240333 -0.106898 0.0444269 -0.00240333 -0.10718 0.0436582 0.00859667 -0.107948 0.0433768 0.00859667 -0.108998 0.0436582 0.00859667 -0.110048 0.0444268 -0.00240333 -0.110817 0.0465268 0.00859667 -0.110817 0.0465268 -0.00240333 -0.110817 0.0472955 0.00859667 -0.110048 0.0472955 -0.00240333 -0.110048 -0.0386433 0.00985848 -0.0975301 -0.0368246 0.00859667 -0.0964801 -0.0404619 0.00859667 -0.0964801 -0.0407433 0.00859667 -0.0975301 -0.0386433 0.00859667 -0.0996301 -0.0365433 0.00859667 -0.0975301 -0.0375932 0.00859667 -0.0957114 -0.0386432 0.00859667 -0.0954301 -0.0396932 0.00859667 -0.0957114 -0.0396932 -0.00240333 -0.0957114 -0.0404619 0.00859667 -0.0985801 -0.0396933 0.00859667 -0.0993487 -0.0396933 -0.00240333 -0.0993487 -0.0375933 0.00859667 -0.0993487 -0.0368246 -0.00240333 -0.0985801 -0.0368246 0.00859667 -0.0985801 -0.0365433 -0.00240333 -0.0975301 -0.00500915 0.0194967 -0.349998 -0.00433924 0.0314967 -0.347498 -0.00433924 0.0194967 -0.347498 -9.08344e-06 0.0194967 -0.344998 -0.00250909 0.0314967 -0.345668 0.00249091 0.0194967 -0.345668 0.00432101 0.0314967 -0.347498 0.00432101 0.0194967 -0.347498 0.0024908 0.0194967 -0.354328 0.00432095 0.0314967 -0.352498 0.0024908 0.0314967 -0.354328 -9.21146e-06 0.0314967 -0.354998 -0.0025092 0.0194967 -0.354328 -0.00259621 0.00799667 0.043022 -0.00484786 0.00249667 0.044322 -0.00709958 0.00799667 0.040422 -0.00744789 0.00249667 0.041722 -0.00709958 0.00249667 0.040422 -0.00614792 0.00799667 0.0394704 -0.00484793 0.00249667 0.039122 -0.00354792 0.00799667 0.0394703 -0.00354792 0.00249667 0.0394703 -0.00259624 0.00249667 0.040422 0.0569214 0.00799667 0.0273015 0.0569214 0.00249667 0.0273015 0.0559697 0.00799667 0.0282531 0.0559697 0.00249667 0.0282531 0.0533697 0.00799667 0.0282532 0.0520697 0.00799667 0.0260015 0.0546697 0.00799667 0.0234015 0.0546697 0.00249667 0.0234015 0.0569214 0.00249667 0.0247015 0.0569214 0.00799667 0.0247015 0.0647546 0.00799667 -0.0299986 0.0644063 0.00799667 -0.0286986 0.0644063 0.00249667 -0.0286986 0.0621547 0.00799667 -0.0273986 0.0621547 0.00249667 -0.0273986 0.0608547 0.00799667 -0.0277469 0.0608547 0.00249667 -0.0277469 0.059903 0.00799667 -0.0286986 0.059903 0.00249667 -0.0286986 0.0595546 0.00799667 -0.0299986 0.0608546 0.00799667 -0.0322502 0.0634546 0.00249667 -0.0322503 0.0644063 0.00799667 -0.0312986 -0.0314767 0.00799667 -0.0236764 -0.031825 0.00799667 -0.0223764 -0.0314767 0.00249667 -0.0236764 -0.031825 0.00249667 -0.0223764 -0.0327767 0.00799667 -0.0214247 -0.0327767 0.00249667 -0.0214247 -0.0340766 0.00799667 -0.0210764 -0.0353766 0.00799667 -0.0214247 -0.0353766 0.00249667 -0.0214247 -0.0366767 0.00799667 -0.0236763 -0.0363283 0.00249667 -0.0223763 -0.0363284 0.00249667 -0.0249763 -0.0353767 0.00249667 -0.025928 -0.0340767 0.00249667 -0.0262764 -0.0340767 0.00799667 -0.0262764 -0.031825 0.00799667 -0.0249764 -0.0327767 0.00249667 -0.025928 -0.031825 0.00249667 -0.0249764 0.0640297 0.00029667 -0.026751 0.0641797 -3.3303e-06 -0.0264912 0.0621547 -3.3303e-06 -0.0259486 0.0601297 -3.3303e-06 -0.0264912 0.0586472 -3.3303e-06 -0.0279736 0.0584046 0.00029667 -0.0299986 0.0586472 -3.3303e-06 -0.0320236 0.0602796 0.00029667 -0.0332462 0.0621546 0.00029667 -0.0337486 0.0654022 0.00029667 -0.0318736 0.065662 -3.3303e-06 -0.0320236 0.0662046 -3.3303e-06 -0.0299987 0.0581772 -3.3303e-06 0.0280265 0.0546698 0.00029667 0.0297515 0.0509197 0.00029667 0.0260015 0.0511623 -3.3303e-06 0.0239765 0.0526447 -3.3303e-06 0.0224941 0.0565447 0.00029667 0.0227539 0.0579173 0.00029667 0.0241265 0.0581771 -3.3303e-06 0.0239765 0.0587197 -3.3303e-06 0.0260014 0.0584197 0.00029667 0.0260014 0.0579173 0.00029667 0.0278765 -0.00134046 -3.3303e-06 0.043747 -0.00282285 -3.3303e-06 0.0452294 -0.00687285 -3.3303e-06 0.0452294 -0.00835527 -3.3303e-06 0.0437471 -0.00835532 -3.3303e-06 0.0396971 -0.00484795 -3.3303e-06 0.037672 -0.00134052 -3.3303e-06 0.039697 -0.00109789 0.00029667 0.041722 -0.000797893 -3.3303e-06 0.041722 -0.0359516 0.00029667 -0.0204287 -0.0361016 -3.3303e-06 -0.0201689 -0.0373243 0.00029667 -0.0255513 -0.0361017 -3.3303e-06 -0.0271837 -0.0340767 0.00029667 -0.0274264 -0.0340767 -3.3303e-06 -0.0277264 -0.0322017 0.00029667 -0.026924 -0.0308291 0.00029667 -0.0218014 0.0436144 -0.00210333 -0.105772 0.0437644 -0.00240333 -0.106032 0.0454769 -0.00240333 -0.105573 0.0473394 -0.00210333 -0.105772 0.0489018 -0.00240333 -0.108998 0.0492018 -0.00210333 -0.108998 0.0487028 -0.00210333 -0.110861 0.0471893 -0.00240333 -0.111965 0.0454768 -0.00240333 -0.112423 0.0473393 -0.00210333 -0.112224 0.0437643 -0.00240333 -0.111965 0.0454768 -0.00210333 -0.112723 0.0436143 -0.00210333 -0.112224 0.0425107 -0.00240333 -0.110711 0.0420518 -0.00240333 -0.108998 0.0425107 -0.00240333 -0.107286 -0.0423683 -0.00210333 -0.09753 -0.0418692 -0.00210333 -0.0956675 -0.0405057 -0.00210333 -0.0943041 -0.0386432 -0.00240333 -0.0941051 -0.0386432 -0.00210333 -0.0938051 -0.0369307 -0.00240333 -0.094564 -0.0367807 -0.00210333 -0.0943042 -0.0349183 -0.00210333 -0.0975301 -0.0352183 -0.00240333 -0.0975301 -0.0356771 -0.00240333 -0.0992426 -0.0354173 -0.00210333 -0.0993926 -0.0369308 -0.00240333 -0.100496 -0.0386433 -0.00240333 -0.100955 -0.0405058 -0.00210333 -0.100756 -0.0418692 -0.00210333 -0.0993925 -0.045142 -0.00210333 -0.154955 -0.0436285 -0.00240333 -0.153851 -0.041916 -0.00240333 -0.153393 -0.0386901 -0.00210333 -0.154955 -0.0384911 -0.00240333 -0.156818 -0.03895 -0.00240333 -0.15853 -0.0400536 -0.00210333 -0.160043 -0.0436286 -0.00240333 -0.159784 -0.0448822 -0.00240333 -0.15853 -0.045142 -0.00210333 -0.15868 -0.0453411 -0.00240333 -0.156817 0.0295337 -0.00210333 -0.165136 0.0310471 -0.00240333 -0.164032 0.0327596 -0.00210333 -0.163273 0.0357257 -0.00240333 -0.168711 0.034622 -0.00210333 -0.170224 0.0327595 -0.00240333 -0.170423 0.030897 -0.00210333 -0.170224 0.0290346 -0.00210333 -0.166998 0.0187684 -0.00240333 -0.220032 0.0204809 -0.00210333 -0.219273 0.0204809 -0.00240333 -0.219573 0.0221934 -0.00240333 -0.220032 0.0223434 -0.00210333 -0.219772 0.0239059 -0.00240333 -0.222998 0.0237068 -0.00210333 -0.221136 0.0237068 -0.00210333 -0.224861 0.0221933 -0.00240333 -0.225964 0.0204808 -0.00240333 -0.226423 0.0204808 -0.00210333 -0.226723 0.0172549 -0.00210333 -0.224861 0.0167559 -0.00210333 -0.222998 -0.0467885 -0.00240333 -0.211094 -0.0483019 -0.00210333 -0.212198 -0.045076 -0.00210333 -0.210336 -0.0433635 -0.00240333 -0.211094 -0.041651 -0.00240333 -0.214061 -0.041351 -0.00210333 -0.214061 -0.0421099 -0.00240333 -0.215773 -0.0433636 -0.00240333 -0.217027 -0.0418501 -0.00210333 -0.215923 -0.0450761 -0.00210333 -0.217786 -0.0450761 -0.00240333 -0.217486 -0.0467886 -0.00240333 -0.217027 -0.048302 -0.00210333 -0.215923 -0.048501 -0.00240333 -0.21406 -0.048801 -0.00210333 -0.21406 0.00593811 -0.00210333 -0.272335 0.006697 -0.00240333 -0.270622 0.00643719 -0.00210333 -0.270472 0.00795065 -0.00240333 -0.269369 0.00966316 -0.00240333 -0.26891 0.0128891 -0.00210333 -0.270472 0.0126292 -0.00240333 -0.274047 0.0113756 -0.00240333 -0.275301 0.00966306 -0.00210333 -0.27606 0.00795057 -0.00240333 -0.275301 0.00643714 -0.00210333 -0.274197 0.00669695 -0.00240333 -0.274047 0.00623811 -0.00240333 -0.272335 -0.0503143 -0.00210333 -0.271988 -0.0501643 -0.00240333 -0.272248 -0.0467393 -0.00240333 -0.272248 -0.0454857 -0.00240333 -0.273502 -0.0465893 -0.00210333 -0.271988 -0.0450268 -0.00240333 -0.275214 -0.0452259 -0.00210333 -0.273352 -0.0447268 -0.00210333 -0.275214 -0.0454857 -0.00240333 -0.276927 -0.0465894 -0.00210333 -0.27844 -0.0467394 -0.00240333 -0.27818 -0.0484519 -0.00210333 -0.278939 -0.0484519 -0.00240333 -0.278639 -0.051418 -0.00240333 -0.276926 -0.0518768 -0.00240333 -0.275214 -9.08344e-06 0.0314967 -0.344998 0.00249091 0.0314967 -0.345668 0.00274091 0.0319967 -0.345235 0.00499085 0.0314967 -0.349998 0.00475403 0.0319967 -0.347248 -0.0025092 0.0314967 -0.354328 -0.00433931 0.0314967 -0.352498 -0.00275921 0.0319967 -0.354761 -0.00477232 0.0319967 -0.352748 -0.00500915 0.0314967 -0.349998 -0.0536317 0.00149667 -0.281903 -0.0535131 0.00049667 -0.281928 -0.00744954 0.0241795 -0.0526277 -0.00760577 0.0242 -0.0532977 -0.00771972 0.0243142 -0.0500253 -0.0074039 0.0242698 -0.0500897 -0.00675906 0.0241834 -0.0551529 -0.00238777 0.0242833 -0.0578019 -0.000102775 0.02444 -0.0581778 0.000156279 0.0244128 -0.0578338 0.00434587 0.0247005 -0.0551148 0.00494 0.0247895 -0.054701 0.0052444 0.0247756 -0.0527502 -0.00713024 0.0241008 -0.050139 -0.0065022 0.02415 -0.0549855 -0.00715687 0.0240078 -0.0525686 -0.00472518 0.0241888 -0.0568018 -0.00231994 0.0241101 -0.0575175 0.0025215 0.0245572 -0.0568908 0.00237668 0.0243814 -0.0566504 0.0041245 0.0245236 -0.0549517 0.00129238 0.023737 -0.0569447 -0.00689178 0.0236686 -0.0501675 -0.00700533 0.0234558 -0.051402 -0.00690289 0.0234167 -0.052506 -0.00691667 0.0235695 -0.0525125 -0.00604331 0.0235394 -0.0546878 -0.00431904 0.0234297 -0.056404 -0.00161716 0.0235584 -0.0573706 0.00228848 0.024107 -0.0564868 0.00395191 0.0241014 -0.0548063 0.00227133 0.0239555 -0.0564449 9.253e-05 0.0238084 -0.0573152 -0.00225129 0.0236761 -0.057286 -0.00226768 0.023831 -0.0573301 -0.00440525 0.0235793 -0.0563636 -0.00696273 0.0237262 -0.0525251 0.00508866 0.0246512 -0.0527117 -0.00694402 0.0238352 -0.0501649 -0.00625106 0.0239786 -0.0548221 -0.00608352 0.0236965 -0.0547136 -0.00455349 0.0240167 -0.0565592 -0.0044355 0.0237356 -0.0564003 0.000112908 0.0242383 -0.0575506 9.27545e-05 0.0239615 -0.0573614 0.00398332 0.0242513 -0.0548375 0.00486584 0.0240874 -0.0526388 0.00167937 0.0199967 -0.0498521 0.00239468 0.0202967 -0.0514021 0.00193914 0.0202967 -0.0531021 0.000694637 0.0202967 -0.0543466 -0.00100536 0.0199967 -0.0545021 -0.00270536 0.0202967 -0.0543465 -0.00369002 0.0199967 -0.052952 -0.00440532 0.0202967 -0.051402 0.0677223 -2.83838e-06 0.00515201 0.0688385 -3.3303e-06 -0.00324676 0.0687092 4.31897e-05 -0.015407 0.0686102 -3.3303e-06 -0.0169024 -0.0497916 -2.98214e-06 -0.281428 -0.0492209 0.000113946 -0.281428 -0.0489673 0.000250878 -0.281428 -0.0489519 0.000262615 -0.281428 -0.0435488 -3.3303e-06 -0.281428 -0.049784 -2.80452e-06 -0.281428 -0.0497652 -2.1865e-06 -0.281428 0.0120004 0.0194967 -0.281429 -0.0324753 -3.3303e-06 -0.281428 -0.0381613 -3.3303e-06 -0.281428 0.00064485 -3.3303e-06 -0.281428 -0.036308 -3.3303e-06 9.09026e-05 -0.0366083 3.19275e-05 -0.00492338 -0.050525 -0.00841668 -0.282954 -0.0509659 -0.0117991 -0.28447 -0.0510138 -0.0116822 -0.284644 -0.0501678 -0.00662095 -0.282432 -0.0501866 -0.00671777 -0.282455 -0.0497313 -0.00425638 -0.281991 -0.0503093 -0.0068296 -0.282584 -0.0497864 -0.00458626 -0.282038 -0.0509476 -0.0105229 -0.284011 -0.0511485 -0.0115707 -0.284804 -0.0505546 -0.00673926 -0.28269 -0.0510849 -0.00919152 -0.283623 -0.051565 -0.011467 -0.284937 -0.0504246 -0.00678172 -0.282652 -0.0509201 -0.00925239 -0.283562 -0.0510838 -0.0104309 -0.284142 -0.0507878 -0.0093282 -0.283455 -0.00368998 -0.0190033 -0.049852 -0.00368998 -0.00900333 -0.049852 -0.00255529 -0.0190033 -0.0487174 -0.00100529 -0.00900333 -0.0483021 0.00054471 -0.0190033 -0.0487174 0.00054471 -0.00900333 -0.0487174 0.00167937 -0.00900333 -0.0498521 0.00167937 -0.0190033 -0.0498521 0.00209468 -0.00900333 -0.0514021 -0.00100536 -0.0190033 -0.0545021 -0.00369002 -0.0190033 -0.052952 -0.00369002 -0.00900333 -0.052952 -0.00410532 -0.00900333 -0.051402 -0.0462285 -0.000297329 -0.166089 -0.0483442 -0.000298835 -0.20437 -0.036705 -0.00900333 -0.0918518 -0.0391555 -0.00030333 -0.103508 -0.0373953 -0.00900333 -0.103399 -0.0363203 -0.00030333 -0.103062 -0.0349283 -0.00030333 -0.102242 -0.0332275 -0.00900333 -0.100113 -0.0332275 -0.00030333 -0.100113 -0.0326438 -0.00900333 -0.097451 -0.0326438 -0.00030333 -0.097451 -0.03287 -0.00030333 -0.0958961 -0.0332975 -0.00900333 -0.0948057 -0.0332975 -0.00030333 -0.0948057 -0.0400823 -0.00030333 -0.0868442 -0.0399212 -0.0119033 -0.0839261 -0.03846 -0.00900333 -0.0908133 -0.0397771 -0.00900333 -0.0888605 -0.0400899 -0.00900333 -0.087119 -0.0303023 -0.0229476 -0.0949402 -0.0303464 -0.0231547 -0.0949483 -0.030799 -0.0233863 -0.096759 -0.0306993 -0.0234384 -0.0950126 -0.0310717 -0.0222854 -0.111953 -0.0302332 -0.023105 -0.0967747 -0.0312174 -0.0224705 -0.111955 -0.030377 -0.0232893 -0.096777 -0.0314315 -0.0225686 -0.111948 -0.0305886 -0.0233884 -0.0967708 -0.0307723 -0.0230826 -0.0934635 -0.0316168 -0.0230954 -0.0921532 -0.0307248 -0.0228774 -0.0934631 -0.0315156 -0.022685 -0.0919659 -0.0314807 -0.0229128 -0.0920987 -0.0309076 -0.0234342 -0.0950505 -0.0318471 -0.0232276 -0.0925796 -0.0311111 -0.0233654 -0.0935722 -0.0309113 -0.0232665 -0.093502 -0.0304891 -0.0233399 -0.0949743 -0.0338402 -0.022462 -0.0901661 -0.0325615 -0.0228087 -0.0909836 -0.0324283 -0.0226298 -0.0909162 -0.0323624 -0.0224299 -0.0909209 -0.0337008 -0.0223688 -0.0900276 -0.0324875 -0.0227262 -0.0909404 -0.0336307 -0.0222896 -0.0899787 -0.0335223 -0.0221015 -0.0899449 -0.0334883 -0.022008 -0.0899565 -0.0303785 -0.0229415 -0.094572 -0.0318032 -0.0231933 -0.0922559 -0.0327297 -0.0229055 -0.0911128 -0.0339675 -0.0224693 -0.0903424 -0.0329341 -0.0220214 -0.116042 -0.0318851 -0.0223744 -0.114118 -0.0313669 -0.0223924 -0.113085 -0.0325931 -0.021644 -0.116203 -0.0319594 -0.0217375 -0.115237 -0.0320826 -0.0223729 -0.114045 -0.0331103 -0.0220261 -0.115911 -0.0312223 -0.0222082 -0.113098 -0.0315407 -0.0220927 -0.114207 -0.0316827 -0.0222757 -0.114179 -0.0320134 -0.0219398 -0.115245 -0.0321517 -0.0221213 -0.115203 -0.0357811 -0.0205165 -0.085812 -0.0359399 -0.0205542 -0.0857993 -0.0357019 -0.0205029 -0.0851546 -0.035911 -0.0207084 -0.0864982 -0.0356754 -0.0212584 -0.0879125 -0.0360598 -0.0207042 -0.0865148 -0.0361879 -0.0206634 -0.0865402 -0.0358605 -0.0205394 -0.0851258 -0.036013 -0.0205238 -0.0850931 -0.0354593 -0.0202326 -0.0865939 -0.0356273 -0.0205825 -0.0865066 -0.0355999 -0.0204459 -0.0851697 -0.0356434 -0.0204299 -0.0858301 -0.0355068 -0.0203588 -0.0851799 -0.0355458 -0.0203108 -0.0858506 -0.0354931 -0.0201815 -0.0858703 -0.0337058 -0.0218958 -0.089794 -0.0350633 -0.0208786 -0.088056 -0.0345501 -0.0216231 -0.089006 -0.0346264 -0.0217187 -0.089016 -0.0354774 -0.0203479 -0.0865613 -0.0354206 -0.0207189 -0.0871971 -0.035364 -0.0206046 -0.0872285 -0.0351596 -0.0209022 -0.0878639 -0.0352174 -0.0210108 -0.0878379 -0.0344947 -0.0215221 -0.0890156 -0.0335756 -0.0222072 -0.089953 -0.0361401 -0.0204688 -0.0850617 -0.0357594 -0.0206669 -0.086495 -0.0356173 -0.0214592 -0.0885397 -0.0363122 -0.0205272 -0.086325 -0.0357879 -0.0212419 -0.0879663 -0.0360419 -0.0205151 -0.0850864 -0.0355487 -0.0212436 -0.0878672 -0.035484 -0.0201005 -0.0861124 -0.0355316 -0.0204698 -0.0865305 -0.0353061 -0.0211125 -0.0878277 -0.0354036 -0.0211833 -0.0878335 -0.0264327 -0.0230314 -0.123415 -0.0302256 -0.0223734 -0.123859 -0.0282908 -0.0226149 -0.123834 -0.0301577 -0.0222675 -0.123685 -0.0318272 -0.0219185 -0.122848 -0.0337812 -0.0215739 -0.119698 -0.0327655 -0.021925 -0.116144 -0.0336733 -0.0216768 -0.117801 -0.0335668 -0.0216158 -0.117822 -0.0336717 -0.021513 -0.119683 -0.0332542 -0.0217325 -0.121547 -0.0324987 -0.0213368 -0.121928 -0.0330393 -0.0212004 -0.121067 -0.0328836 -0.0213456 -0.121382 -0.0334789 -0.0212143 -0.119659 -0.0335124 -0.021118 -0.119012 -0.0332693 -0.0212617 -0.11752 -0.0325731 -0.0215456 -0.116193 -0.0295096 -0.022017 -0.12366 -0.0300505 -0.0219048 -0.123546 -0.0316868 -0.021639 -0.122743 -0.0316159 -0.0215535 -0.122784 -0.0282497 -0.022263 -0.123678 -0.0300696 -0.0219985 -0.12355 -0.0255663 -0.0227457 -0.122411 -0.0265322 -0.0226642 -0.123131 -0.025103 -0.0230635 -0.121998 -0.0264987 -0.0229202 -0.123265 -0.0250523 -0.0231642 -0.122052 -0.0334775 -0.0215301 -0.117835 -0.0335158 -0.0213233 -0.119663 -0.0329202 -0.0214514 -0.121389 -0.0301244 -0.0221866 -0.123619 -0.0282762 -0.0224464 -0.123718 -0.0300944 -0.0220945 -0.123574 -0.0317202 -0.0217396 -0.122758 -0.0333744 -0.0213213 -0.117837 -0.0334126 -0.0214285 -0.11784 -0.0326369 -0.0217555 -0.116198 -0.0337867 -0.0217088 -0.117775 -0.0338631 -0.0217509 -0.117292 -0.0338984 -0.0216046 -0.119714 -0.0319639 -0.0220198 -0.122998 -0.031656 -0.0221191 -0.123456 -0.0291677 -0.0226 -0.124224 -0.0282884 -0.022724 -0.124008 -0.0265253 -0.0225756 -0.123118 -0.0275113 -0.0223994 -0.123528 -0.0282639 -0.0223536 -0.123689 -0.0265307 -0.0227547 -0.12316 -0.0282854 -0.0225355 -0.123767 -0.0317677 -0.0218356 -0.122793 -0.0329797 -0.0215518 -0.121411 -0.0330597 -0.021637 -0.121446 -0.0335808 -0.0214265 -0.119671 -0.0326902 -0.021842 -0.11618 -0.0302386 -0.0264494 -0.0802818 -0.0354951 -0.0210386 -0.0836726 -0.0358137 -0.0205344 -0.0851349 -0.0356037 -0.0210105 -0.0836022 -0.0346141 -0.0220008 -0.0826024 -0.0302557 -0.0267006 -0.0802436 -0.0303181 -0.0267682 -0.0802035 -0.0289342 -0.0278272 -0.0801604 -0.0302805 -0.0268999 -0.080139 -0.0304056 -0.0268012 -0.0801502 -0.0328741 -0.0244547 -0.0808672 -0.0344573 -0.021228 -0.08295 -0.0354065 -0.0201654 -0.085181 -0.0354471 -0.0202691 -0.0851831 -0.0349956 -0.0208154 -0.0837767 -0.034227 -0.0217259 -0.0826111 -0.0349261 -0.0207077 -0.0837433 -0.0351599 -0.0209579 -0.0837855 -0.0350981 -0.0209156 -0.0837892 -0.0352264 -0.0209927 -0.0837748 -0.034502 -0.0219547 -0.0826412 -0.0355055 -0.0206667 -0.0844385 -0.0350429 -0.0208674 -0.083786 -0.0343005 -0.0218095 -0.0826434 -0.0324381 -0.0241679 -0.0810495 -0.0273201 -0.0284163 -0.0805232 -0.0324971 -0.0242243 -0.0810605 -0.0301908 -0.0266271 -0.0802647 -0.0325616 -0.0242791 -0.0810587 -0.0343942 -0.0218886 -0.0826549 -0.0336304 -0.0231076 -0.0817445 -0.0353649 -0.0210347 -0.0837336 -0.0356563 -0.0207054 -0.0844007 -0.0348832 -0.0220063 -0.0823953 -0.0341738 -0.0229192 -0.0817137 -0.0347198 -0.0220235 -0.0825433 -0.0338034 -0.0231862 -0.0816606 -0.0326293 -0.0243299 -0.0810431 -0.0288747 -0.0277291 -0.0802119 -0.0281304 -0.0281404 -0.0803186 -0.0280587 -0.0280788 -0.080341 -0.0251216 -0.0230008 -0.121974 -0.0238903 -0.0231816 -0.120738 -0.0249823 -0.0232437 -0.122118 -0.0251351 -0.0229118 -0.121952 -0.0224224 -0.0233571 -0.119812 -0.022326 -0.0236364 -0.120076 -0.0238378 -0.0233476 -0.120833 -0.0190658 -0.0239502 -0.11952 -0.0190639 -0.0239217 -0.11933 -0.0207768 -0.0235137 -0.119232 -0.0223894 -0.0235256 -0.119919 -0.0207654 -0.0236844 -0.119347 -0.0190455 -0.0236398 -0.119035 0.0277482 -0.0286283 -0.0803587 0.0351964 -0.0285297 -0.0774129 0.0351925 -0.0285724 -0.0774042 0.0277584 -0.0284534 -0.0803886 0.025668 -0.0286299 -0.0810471 0.0122058 -0.0284527 -0.0841667 -0.0273219 -0.0283838 -0.0805308 -0.0273229 -0.0283508 -0.0805363 -0.0117518 -0.0284243 -0.0842326 -0.000119813 -0.0244089 -0.119334 -0.0190332 -0.0234518 -0.118998 -0.000119338 -0.0242996 -0.119154 -0.0190568 -0.0238122 -0.119152 -0.0145197 -0.0241853 -0.119521 0.0188032 -0.0237725 -0.118998 -0.000118587 -0.0241262 -0.119035 0.0188151 -0.024136 -0.119155 -0.000119933 -0.024436 -0.119525 0.0427308 -0.0256647 -0.0788405 0.0415904 -0.0260888 -0.0780222 0.0425781 -0.0255606 -0.0789243 0.0431522 -0.0247147 -0.0799937 0.036724 -0.0279834 -0.0769519 0.0378217 -0.0276072 -0.076852 0.0392388 -0.0268401 -0.0770414 0.0402976 -0.0263426 -0.0774044 0.0403627 -0.0264893 -0.0774053 0.0424551 -0.025402 -0.078954 0.0440865 -0.0247186 -0.0812411 0.0428763 -0.0256974 -0.0787269 0.0412148 -0.0265274 -0.0774203 0.0404145 -0.0268805 -0.077051 0.0405376 -0.0267334 -0.0772578 0.040377 -0.0268966 -0.077037 0.038895 -0.027505 -0.0766886 0.0377824 -0.0279312 -0.0766763 0.0379046 -0.0278022 -0.076748 0.0437498 -0.0244579 -0.0812669 0.0433555 -0.0250658 -0.0800168 0.0438921 -0.0246237 -0.0812728 0.0437045 -0.0243491 -0.0812482 0.0432177 -0.0248985 -0.0800292 0.0414857 -0.0259395 -0.0780652 0.040447 -0.0266278 -0.077355 0.0378618 -0.0276996 -0.0768181 0.0365168 -0.0281526 -0.0769852 0.0351986 -0.0284863 -0.0774181 0.0226961 -0.0240426 -0.120637 0.0218152 -0.0241148 -0.120168 0.0188195 -0.0242714 -0.119528 0.0225732 -0.0240317 -0.120349 0.0226543 -0.0239221 -0.120192 0.0188186 -0.0242451 -0.119336 0.0208003 -0.0240512 -0.119421 0.0243247 -0.0234063 -0.121289 0.0243109 -0.0235909 -0.121326 0.0227015 -0.0237504 -0.120085 0.0234535 -0.0234977 -0.120536 0.0208219 -0.0238779 -0.119303 0.0188094 -0.0239624 -0.119036 0.0208215 -0.0236883 -0.119264 0.0242416 -0.0237604 -0.121416 0.0255165 -0.0234785 -0.122956 0.0254533 -0.0235824 -0.123003 0.0433086 -0.024126 -0.0856766 0.043128 -0.0240318 -0.0855453 0.043694 -0.0238713 -0.0841455 0.0433995 -0.023837 -0.0848301 0.0424642 -0.0236775 -0.0859987 0.0438944 -0.0238379 -0.0828069 0.0438078 -0.0245425 -0.0812744 0.0440073 -0.0241748 -0.0827172 0.0440956 -0.0242593 -0.0827337 0.0442023 -0.02432 -0.0827459 0.0435357 -0.024026 -0.0849047 0.0438378 -0.0240602 -0.0842076 0.0442957 -0.0247245 -0.0811779 0.0425073 -0.0238864 -0.086021 0.0426208 -0.0240727 -0.0861186 0.043002 -0.0238438 -0.0854588 0.0437534 -0.023974 -0.0841729 0.0435658 -0.0241076 -0.085693 0.0442586 -0.0241341 -0.0843544 0.0440514 -0.0241523 -0.0842861 0.0443173 -0.0243526 -0.0827529 0.0439405 -0.0241211 -0.0842465 0.0439443 -0.0240748 -0.082698 0.0436615 -0.0237629 -0.0841266 0.0439087 -0.0239694 -0.0826781 0.0436533 -0.0236582 -0.0841162 0.0281447 -0.0233177 -0.125559 0.0305942 -0.0230219 -0.125717 0.031862 -0.022851 -0.125112 0.0341332 -0.0226577 -0.123357 0.0343728 -0.0226506 -0.122434 0.0349054 -0.0227107 -0.121077 0.0345631 -0.0229761 -0.118707 0.0345167 -0.0226439 -0.120596 0.0347234 -0.0227444 -0.120605 0.0341775 -0.0225511 -0.122356 0.0333717 -0.0226964 -0.12401 0.0332171 -0.0225955 -0.123874 0.0317676 -0.0227473 -0.124939 0.0300547 -0.0230631 -0.12559 0.0281968 -0.0232894 -0.125381 0.0282427 -0.0228215 -0.125047 0.0292413 -0.0226868 -0.125241 0.0299731 -0.0225895 -0.125245 0.0306242 -0.0225038 -0.125152 0.0267043 -0.0231313 -0.124244 0.0255398 -0.0234152 -0.122936 0.0266952 -0.0232244 -0.124271 0.0343187 -0.022226 -0.120931 0.0340594 -0.0226803 -0.118859 0.0340256 -0.022582 -0.118857 0.0340117 -0.0224852 -0.118848 0.0340144 -0.0222625 -0.122288 0.0336328 -0.0221671 -0.123026 0.0330797 -0.0223099 -0.123768 0.0325971 -0.0222585 -0.124205 0.0316714 -0.0224682 -0.124803 0.0320419 -0.0223233 -0.124593 0.0315266 -0.0223873 -0.124859 0.0253714 -0.02366 -0.123058 0.026639 -0.0233936 -0.12437 0.0265415 -0.0235038 -0.124511 0.0282373 -0.0231807 -0.125207 0.0300136 -0.0228748 -0.125333 0.0316942 -0.0225685 -0.124827 0.0317268 -0.0226642 -0.124873 0.033108 -0.022413 -0.123786 0.0341005 -0.0224662 -0.122325 0.0340455 -0.0223669 -0.122302 0.0344352 -0.0225596 -0.120588 0.034377 -0.0224616 -0.12058 0.0343437 -0.0223586 -0.120571 0.0299988 -0.0227817 -0.125282 0.029985 -0.0226844 -0.125253 0.0282528 -0.023009 -0.125089 0.0282505 -0.0229141 -0.125058 0.0300286 -0.0229565 -0.125405 0.0331544 -0.0225111 -0.123822 0.0391013 -0.0243286 -0.0913029 0.0410879 -0.0243491 -0.0876698 0.0420305 -0.0241426 -0.0866049 0.0409325 -0.0242504 -0.0875248 0.0393417 -0.0242779 -0.0898892 0.039177 -0.0238914 -0.0898093 0.0398663 -0.0239013 -0.0885358 0.039215 -0.0240949 -0.0898306 0.0399041 -0.0241064 -0.0885586 0.0407834 -0.0238597 -0.0874074 0.0418878 -0.0237528 -0.0864732 0.0401983 -0.0243903 -0.0887519 0.0403728 -0.0243899 -0.0888684 0.0421543 -0.0242381 -0.0867646 0.0389038 -0.0242262 -0.0912547 0.0408229 -0.0240658 -0.0874309 0.0400232 -0.0242904 -0.088636 0.0419353 -0.0239693 -0.0865009 0.0343754 -0.0229616 -0.118778 0.0341893 -0.0228573 -0.118835 0.0338751 -0.023216 -0.116634 0.0341158 -0.0227764 -0.118851 0.0340227 -0.0233648 -0.114442 0.0338276 -0.0232617 -0.114395 0.0336772 -0.0231122 -0.11664 0.0335438 -0.0229329 -0.116634 0.0335012 -0.0227348 -0.116619 0.0334775 -0.0227835 -0.116011 0.0386384 -0.0240179 -0.0918255 0.038772 -0.0240446 -0.0912173 0.0387696 -0.0241992 -0.0918611 0.0393025 -0.0243347 -0.0913473 0.0336976 -0.0230808 -0.114358 0.038966 -0.024302 -0.091908 -0.0482038 -0.0261117 -0.270721 -0.0527684 -0.0200033 -0.269831 -0.0528182 -0.0200033 -0.269575 -0.0512909 -0.0236651 -0.269906 -0.0519164 -0.0225844 -0.269497 -0.0488164 -0.026784 -0.270042 -0.0486801 -0.0266228 -0.270398 -0.0511174 -0.0235511 -0.270263 -0.0508332 -0.0233756 -0.270507 -0.0493444 -0.0272835 -0.280271 -0.0474376 -0.0287533 -0.280106 -0.0456383 -0.0295746 -0.278968 -0.0441337 -0.0303539 -0.277511 -0.0437781 -0.030264 -0.275364 -0.0435672 -0.0304871 -0.275366 -0.0441727 -0.0299926 -0.273317 -0.0453644 -0.0292863 -0.271669 -0.0452664 -0.0294952 -0.271441 -0.0470012 -0.028136 -0.270693 -0.0470161 -0.028325 -0.270388 -0.0444121 -0.0298576 -0.277293 -0.0439114 -0.0299874 -0.275367 -0.0453195 -0.0291749 -0.278445 -0.0449471 -0.0293536 -0.278037 -0.0456564 -0.0293058 -0.2788 -0.0444327 -0.0295693 -0.277238 -0.0465513 -0.028455 -0.279293 -0.0456404 -0.0291635 -0.278742 -0.0471553 -0.0280223 -0.279523 -0.0472301 -0.0281589 -0.279559 -0.0472982 -0.0282978 -0.279622 -0.0483304 -0.026244 -0.270697 -0.0453861 -0.0290198 -0.271853 -0.046906 -0.0278785 -0.270923 -0.0468349 -0.0277401 -0.270999 -0.0453682 -0.0288784 -0.27192 -0.0449806 -0.028984 -0.27235 -0.0447809 -0.0291175 -0.272611 -0.044295 -0.0294324 -0.27349 -0.0439547 -0.0296974 -0.275374 -0.0440928 -0.0296826 -0.276331 -0.0469153 -0.0291574 -0.280252 -0.0455537 -0.0297878 -0.279188 -0.0433252 -0.0306018 -0.274794 -0.0439914 -0.0302121 -0.273194 -0.0440199 -0.0302177 -0.27256 -0.048841 -0.026831 -0.269664 -0.0473996 -0.0285574 -0.279825 -0.0443095 -0.0301325 -0.277388 -0.0442768 -0.0297193 -0.27342 -0.0484533 -0.0263744 -0.270638 -0.0526361 -0.0200033 -0.279494 -0.0515358 -0.0237055 -0.279615 -0.0488194 -0.0267347 -0.279717 -0.0534567 -0.0200033 -0.279965 -0.0535087 -0.0200033 -0.280059 -0.0536061 -0.0200033 -0.28042 -0.0521423 -0.0240314 -0.280476 -0.052051 -0.0239896 -0.280122 -0.0518367 -0.0238747 -0.279809 -0.0491744 -0.0271141 -0.279956 -0.0489389 -0.0268648 -0.279758 -0.0453022 -0.00800333 -0.152002 -0.0456452 -0.00800333 -0.151659 -0.045787 -0.00800333 -0.151202 -0.0437233 -0.0138053 -0.151234 -0.0423528 -0.0157688 -0.151679 -0.0445089 -0.0120121 -0.15155 -0.0443181 -0.0119261 -0.151895 -0.0421934 -0.0156273 -0.152017 -0.0440167 -0.0117972 -0.152128 -0.0409922 -0.016121 -0.152413 -0.0410967 -0.0168827 -0.161502 -0.0429359 -0.0152154 -0.161921 -0.0393079 -0.0181749 -0.160737 -0.0411616 -0.0170625 -0.16181 -0.0370409 -0.0194818 -0.157192 -0.0375923 -0.0191539 -0.155035 -0.0387842 -0.0179125 -0.160049 -0.0379874 -0.0183739 -0.159012 -0.0400607 -0.017011 -0.160917 -0.0379933 -0.0185179 -0.159045 -0.0379792 -0.0186638 -0.15909 -0.039304 -0.0179069 -0.160544 -0.0392756 -0.0177643 -0.160477 -0.0408657 -0.0165032 -0.161209 -0.0423102 -0.0147501 -0.16132 -0.0403592 -0.0170192 -0.152581 -0.0418068 -0.0153075 -0.152301 -0.040433 -0.0171495 -0.152509 -0.0388295 -0.0181652 -0.153528 -0.0374568 -0.0186988 -0.156213 -0.0373846 -0.0189813 -0.157145 -0.0384463 -0.018234 -0.153952 -0.0377029 -0.0188796 -0.155118 -0.0411456 -0.0171492 -0.162138 -0.0424229 -0.0159431 -0.162305 -0.0392386 -0.0183827 -0.160985 -0.0397812 -0.0181139 -0.161642 -0.0378663 -0.0191295 -0.16006 -0.0377176 -0.0191592 -0.15936 -0.0374069 -0.0193753 -0.154931 -0.038718 -0.0187825 -0.153088 -0.0379877 -0.0191897 -0.15347 -0.0405705 -0.0175777 -0.152005 -0.0427413 -0.0150774 -0.16158 -0.0409555 -0.016636 -0.161278 -0.0378867 -0.0189396 -0.159211 -0.0372518 -0.0192585 -0.157167 -0.0388426 -0.0183056 -0.153468 -0.0388154 -0.0185711 -0.1533 -0.0405386 -0.0173931 -0.152292 -0.0419417 -0.0154173 -0.152244 -0.0453713 -0.00800333 -0.161145 -0.0440311 -0.0114855 -0.161208 -0.0449804 -0.0117257 -0.1618 -0.0430053 -0.0152537 -0.162297 -0.0447562 -0.0116361 -0.161464 -0.0444278 -0.011498 -0.161255 -0.0424564 -0.0148629 -0.161365 -0.0423664 -0.00800333 -0.0926998 -0.0427041 -0.00800333 -0.0923632 -0.0428487 -0.00800333 -0.0918967 -0.040636 -0.0166722 -0.0926368 -0.0418493 -0.013829 -0.0922321 -0.041648 -0.0137731 -0.0925757 -0.040344 -0.0165279 -0.0928648 -0.0413318 -0.0136897 -0.0928091 -0.0417727 -0.00915967 -0.0928505 -0.0390283 -0.0194297 -0.0924056 -0.0408234 -0.0167698 -0.0922997 -0.038652 -0.0190487 -0.0929565 -0.0388817 -0.0192754 -0.0927344 -0.0387529 -0.0194184 -0.0927373 -0.0390701 -0.0194873 -0.0920488 -0.0370931 -0.0205335 -0.0932389 -0.0372501 -0.0199976 -0.0932512 -0.0355977 -0.0219316 -0.0932694 -0.0355328 -0.0218982 -0.0937088 -0.0378353 -0.0199253 -0.0930318 -0.0385352 -0.0191884 -0.0929596 -0.0388892 -0.0195769 -0.0924117 -0.0371747 -0.020805 -0.093005 -0.0371756 -0.0210007 -0.0926939 -0.0388173 -0.0197461 -0.0920363 -0.0373216 -0.0209465 -0.092288 -0.0342262 -0.0216823 -0.0966699 -0.0346418 -0.0220931 -0.0950889 -0.0342474 -0.0224534 -0.094793 -0.033568 -0.0226287 -0.0964941 -0.0343078 -0.0221855 -0.0998935 -0.0335083 -0.0225762 -0.0983179 -0.0340685 -0.0223165 -0.100043 -0.038226 -0.0199782 -0.102604 -0.0377977 -0.0192623 -0.10195 -0.0355761 -0.0208624 -0.100823 -0.0367021 -0.0205194 -0.101653 -0.0365965 -0.0202271 -0.101538 -0.0373253 -0.0196788 -0.101833 -0.035635 -0.0216829 -0.0939249 -0.0344672 -0.0223156 -0.0949464 -0.0340489 -0.0222646 -0.0965997 -0.0338305 -0.0224898 -0.0965502 -0.0337777 -0.0224398 -0.0982692 -0.0353387 -0.0217175 -0.101234 -0.0381478 -0.0197971 -0.102281 -0.0367161 -0.0209985 -0.102154 -0.0394463 -0.0184922 -0.102298 -0.0396322 -0.0186393 -0.102646 -0.0356304 -0.0211216 -0.0941875 -0.035165 -0.0213488 -0.0946749 -0.0356673 -0.0214095 -0.0940913 -0.0347414 -0.0218131 -0.095198 -0.0341866 -0.0219805 -0.0966348 -0.0341424 -0.0219286 -0.0981755 -0.0340018 -0.0222145 -0.0982192 -0.0346086 -0.021677 -0.0996308 -0.0344994 -0.0219628 -0.0997483 -0.0355093 -0.0212181 -0.100831 -0.0354632 -0.0215008 -0.101008 -0.0367467 -0.0207941 -0.101869 -0.0379925 -0.0195393 -0.102051 -0.0413253 -0.0132696 -0.101889 -0.0417104 -0.0132648 -0.101937 -0.0420544 -0.0133601 -0.102146 -0.0422885 -0.013422 -0.102482 -0.0434063 -0.00800333 -0.10278 -0.0425222 -0.00800333 -0.101838 -0.0427132 -0.00800333 -0.10188 -0.0423716 -0.0134399 -0.102854 -0.0413482 -0.0161737 -0.102923 -0.0412724 -0.0161468 -0.102547 -0.0410529 -0.0160489 -0.102206 -0.0407287 -0.0158964 -0.101992 -0.0403946 -0.0157348 -0.10194 -0.0391723 -0.0182611 -0.102079 0.0483671 -0.00800333 -0.11436 0.0485587 -0.00800333 -0.114578 0.0475932 -0.0137256 -0.114368 0.0486469 -0.00800333 -0.114747 0.0487148 -0.00800333 -0.115231 0.0467601 -0.0167258 -0.114924 0.0477327 -0.0137805 -0.11475 0.0466542 -0.0166066 -0.114164 0.0473158 -0.0136418 -0.114078 0.0450232 -0.0194051 -0.114169 0.044943 -0.0192475 -0.113793 0.0467804 -0.0166983 -0.114546 0.0463955 -0.0164658 -0.113877 0.0451958 -0.0210516 -0.10427 0.0452688 -0.0212539 -0.10399 0.0432791 -0.021895 -0.104835 0.0417262 -0.0222857 -0.106166 0.0415468 -0.0225119 -0.106009 0.0406539 -0.0223337 -0.110162 0.0414092 -0.0217483 -0.107074 0.0410772 -0.0217379 -0.108053 0.0418327 -0.0219951 -0.106276 0.0432925 -0.0216091 -0.105006 0.0418558 -0.0216884 -0.106327 0.0428583 -0.0214383 -0.105339 0.0464406 -0.0191003 -0.104603 0.0432774 -0.0214569 -0.105059 0.0450031 -0.0206331 -0.104509 0.0450744 -0.0207792 -0.104458 0.0446372 -0.0188758 -0.113439 0.0445131 -0.0187459 -0.113394 0.0418359 -0.0211386 -0.111666 0.0414384 -0.0212305 -0.110984 0.0410754 -0.0215032 -0.109935 0.0410264 -0.0220475 -0.108055 0.0409768 -0.0216547 -0.108998 0.0410685 -0.0216577 -0.109962 0.0418301 -0.0212954 -0.111728 0.0431585 -0.0202658 -0.112873 0.0432027 -0.0204182 -0.112954 0.0473545 -0.0197933 -0.1038 0.0432075 -0.0221154 -0.104596 0.0406369 -0.0225677 -0.107994 0.040608 -0.022715 -0.107109 0.0410391 -0.0220749 -0.111877 0.0429305 -0.021055 -0.113744 0.0415676 -0.0218067 -0.112107 0.0431657 -0.0209017 -0.113497 0.0469915 -0.019583 -0.104434 0.0408741 -0.0223406 -0.108035 0.0410359 -0.0218145 -0.109995 0.0408902 -0.0221086 -0.110075 0.0417439 -0.0215879 -0.111899 0.044752 -0.0190038 -0.113517 0.0432294 -0.0207 -0.113193 0.0500538 -0.00800333 -0.105379 0.0510717 -0.00800333 -0.104595 0.0499586 -0.0139519 -0.104733 0.049301 -0.013817 -0.105161 0.0502442 -0.00800333 -0.105367 0.0504726 -0.00800333 -0.105305 0.0496721 -0.0138982 -0.105017 0.0506278 -0.00800333 -0.105225 0.0491405 -0.0169862 -0.104181 0.0489237 -0.0138185 -0.105147 0.0480344 -0.0165833 -0.104952 0.0489957 -0.0169564 -0.104525 0.0472223 -0.0197401 -0.104144 0.0487216 -0.0168654 -0.10481 0.0483701 -0.0167281 -0.104957 0.0469012 -0.0185581 -0.104704 0.0467064 -0.019348 -0.104593 0.0465709 -0.019225 -0.104615 0.033814 -0.0121294 -0.171836 0.0356991 -0.00800333 -0.172901 0.0344521 -0.0122324 -0.17228 0.0353578 -0.00800333 -0.172299 0.035707 -0.00800333 -0.173171 0.0345836 -0.0123071 -0.172666 0.0336562 -0.0144909 -0.172858 0.0336839 -0.0144623 -0.172476 0.0317958 -0.0158438 -0.171394 0.0341826 -0.0121172 -0.171988 0.0320614 -0.0161087 -0.171534 0.0323315 -0.0164753 -0.172173 0.031956 -0.0180054 -0.162571 0.0288714 -0.0184476 -0.169264 0.0287314 -0.0185502 -0.169004 0.0291374 -0.018257 -0.169668 0.030043 -0.0175942 -0.170586 0.03048 -0.0174425 -0.170896 0.0316426 -0.0160459 -0.171357 0.0319261 -0.0159694 -0.17144 0.0279738 -0.0196638 -0.168243 0.0281393 -0.0195043 -0.169504 0.0342666 -0.0169747 -0.162439 0.0344962 -0.0171329 -0.162156 0.0325116 -0.0186326 -0.162001 0.0288093 -0.0198826 -0.164058 0.0289843 -0.0196573 -0.164209 0.027921 -0.0199331 -0.166064 0.028151 -0.0197069 -0.1661 0.0289185 -0.0190626 -0.170176 0.0305685 -0.0178679 -0.171226 0.0305135 -0.018065 -0.171536 0.03225 -0.016331 -0.171809 0.0282596 -0.0190277 -0.166998 0.0283481 -0.019114 -0.16611 0.0282986 -0.0194183 -0.166115 0.0290879 -0.0193706 -0.164316 0.0291102 -0.0190685 -0.164365 0.032259 -0.0180099 -0.162512 0.0337234 -0.0164953 -0.162603 0.0305418 -0.0189751 -0.163026 0.0305268 -0.0188246 -0.163077 0.0283366 -0.0191519 -0.168064 0.029157 -0.0185606 -0.169784 0.0283666 -0.0189984 -0.168028 0.029158 -0.0184075 -0.169718 0.0305302 -0.0175918 -0.17098 0.0342432 -0.0175688 -0.161746 0.0317345 -0.0191078 -0.161825 0.0304581 -0.0194779 -0.162623 0.0294729 -0.0198419 -0.162957 0.0285934 -0.0200183 -0.163887 0.0279873 -0.0200858 -0.164934 0.027547 -0.019976 -0.167138 0.0339854 -0.0167411 -0.162594 0.0323271 -0.018156 -0.162462 0.0324426 -0.0184287 -0.162276 0.0305288 -0.019258 -0.162858 0.0281991 -0.0194403 -0.168149 0.0290824 -0.0188467 -0.169962 0.0371026 -0.00800333 -0.163328 0.0358616 -0.0124782 -0.163071 0.0338519 -0.0166192 -0.162614 0.0368909 -0.01264 -0.162666 0.0375278 -0.00800333 -0.163256 0.0365343 -0.0140721 -0.16222 0.0366091 -0.0125701 -0.162946 0.0359687 -0.0149716 -0.162471 0.0357003 -0.014869 -0.16275 0.0362475 -0.0124653 -0.163088 0.0350361 -0.0145556 -0.16289 0.0361153 -0.0150073 -0.162132 0.0353601 -0.0147163 -0.162895 0.0163498 -0.0165835 -0.224782 0.0159809 -0.017036 -0.222998 0.0161124 -0.017081 -0.221918 0.0160061 -0.0173973 -0.225282 0.0154754 -0.0178986 -0.22311 0.0158252 -0.0175603 -0.224189 0.0174128 -0.0154518 -0.22629 0.0182557 -0.0146149 -0.226924 0.0192219 -0.0133462 -0.227329 0.0160679 -0.01711 -0.224039 0.0160013 -0.0175499 -0.221881 0.0156947 -0.0179055 -0.221797 0.0166055 -0.0163254 -0.225285 0.0169488 -0.0161204 -0.225802 0.0183271 -0.0147295 -0.22701 0.0169491 -0.0164692 -0.226035 0.0169654 -0.0162403 -0.225869 0.0159777 -0.0173531 -0.224111 0.0168667 -0.0166606 -0.226227 0.0156342 -0.0177091 -0.224263 0.018524 -0.0159756 -0.218934 0.0184698 -0.0158501 -0.218972 0.0165403 -0.0169517 -0.220825 0.0179862 -0.0170034 -0.218535 0.0168721 -0.0174515 -0.219794 0.0200553 -0.0156676 -0.217765 0.0186268 -0.0165377 -0.21848 0.0186254 -0.0163432 -0.218705 0.0222336 -0.013524 -0.217789 0.0222819 -0.0132348 -0.218166 0.0205752 -0.0150931 -0.21801 0.0194319 -0.015462 -0.21857 0.0185701 -0.0161046 -0.218875 0.0160804 -0.0173403 -0.221905 0.0178528 -0.016263 -0.219345 0.0170182 -0.0168673 -0.22011 0.0170183 -0.0169988 -0.220066 0.0204516 -0.0149228 -0.218269 0.020275 -0.0147001 -0.218444 0.02105 -0.0138415 -0.218465 0.0169738 -0.0172446 -0.219947 0.0197149 -0.0148158 -0.218564 0.0207958 -0.013606 -0.218509 0.0214446 -0.0126689 -0.218602 0.0243354 -0.00800333 -0.219169 0.0246508 -0.00800333 -0.219077 0.0217317 -0.0128873 -0.218599 0.0220367 -0.0130949 -0.218448 0.0247354 -0.00800333 -0.219033 0.0122824 -0.0222357 -0.277516 0.0125573 -0.0209227 -0.277576 0.0126407 -0.0222177 -0.277663 0.012945 -0.0200795 -0.27773 0.013379 -0.0200801 -0.278401 0.0130527 -0.0223768 -0.278324 0.0133923 -0.0200797 -0.278564 0.0091175 -0.0278996 -0.277449 0.0121224 -0.024531 -0.278115 0.0117665 -0.0242399 -0.277471 0.0130423 -0.0223973 -0.278699 0.0120046 -0.0244147 -0.277746 0.0129134 -0.0223134 -0.277948 0.00536879 -0.0298589 -0.27099 0.0045 -0.030743 -0.27292 0.00689554 -0.0294496 -0.276863 0.00727521 -0.0290274 -0.276423 0.00905339 -0.0277199 -0.277096 0.00480013 -0.030583 -0.273099 0.00560438 -0.0294981 -0.274278 0.00516413 -0.0300724 -0.272994 0.00502406 -0.0303581 -0.273044 0.0054223 -0.0298967 -0.273977 0.00588198 -0.0296237 -0.274864 0.00589055 -0.0294743 -0.27481 0.00721763 -0.0286059 -0.276129 0.0088029 -0.0273114 -0.27677 0.0088978 -0.0274517 -0.276841 0.00725592 -0.028753 -0.276204 0.00579714 -0.0299046 -0.275011 0.00563042 -0.0301234 -0.275191 0.00721221 -0.0292318 -0.276702 0.00839601 -0.0281367 -0.268017 0.00844954 -0.0285075 -0.267931 0.00910075 -0.0276495 -0.26787 0.0101001 -0.0273675 -0.267774 0.00988264 -0.0270483 -0.26784 0.0106269 -0.0263908 -0.267939 0.00622985 -0.0296101 -0.269406 0.00709073 -0.0289504 -0.268642 0.00759961 -0.0288325 -0.268319 0.00754581 -0.0286768 -0.268364 0.00532689 -0.0301611 -0.270967 0.00471445 -0.0308107 -0.270754 0.0105199 -0.027856 -0.26679 0.0075165 -0.0295691 -0.267379 0.00760537 -0.0294935 -0.26771 0.00573629 -0.0304166 -0.268797 0.00496602 -0.03068 -0.270837 0.0114609 -0.0271749 -0.26693 0.0113557 -0.0271573 -0.267347 0.00526299 -0.0303249 -0.270941 0.00599725 -0.0302763 -0.268956 0.00766365 -0.029285 -0.268014 0.00948928 -0.0284529 -0.267179 0.00942027 -0.0282612 -0.267532 0.00548306 -0.029828 -0.270668 0.00564099 -0.0297598 -0.270317 0.011155 -0.0269975 -0.267693 0.00927746 -0.027968 -0.267777 0.0103072 -0.0276588 -0.267539 0.00853116 -0.0288013 -0.267688 0.00763966 -0.0289914 -0.268245 0.00622815 -0.0297659 -0.269345 0.00615528 -0.030057 -0.269172 0.0133262 -0.0233758 -0.268531 0.0145782 -0.0200033 -0.26878 0.013554 -0.0237626 -0.268502 0.0150475 -0.0200033 -0.268658 0.0153718 -0.0200033 -0.268376 0.0150677 -0.0221017 -0.268194 0.0154246 -0.0200033 -0.268297 0.0129916 -0.0257748 -0.267282 0.0142665 -0.0241066 -0.267584 0.0141681 -0.024068 -0.267975 0.0139076 -0.0239542 -0.268316 0.0126527 -0.0256131 -0.268032 0.0147856 -0.0220329 -0.268519 0.010896 -0.0267252 -0.267903 0.0128876 -0.0257587 -0.267677 -0.0451282 -0.0128632 -0.21856 -0.0451901 -0.0133963 -0.218627 -0.0454337 -0.013595 -0.218825 -0.0458956 -0.0129387 -0.218795 -0.0461865 -0.013121 -0.219459 -0.041057 -0.0169601 -0.216085 -0.0410492 -0.0172066 -0.21614 -0.045672 -0.0137999 -0.219459 -0.045548 -0.0136903 -0.219 -0.0439386 -0.0153228 -0.218619 -0.0452902 -0.0134775 -0.218689 -0.0436389 -0.0148867 -0.218325 -0.0449389 -0.0131948 -0.218559 -0.0438062 -0.0151073 -0.218427 -0.0440086 -0.0154944 -0.218878 -0.0422797 -0.0164519 -0.217632 -0.042214 -0.0162172 -0.217533 -0.0406181 -0.0178392 -0.216338 -0.0422564 -0.0168789 -0.217985 -0.0422962 -0.0166836 -0.217788 -0.0408501 -0.0176597 -0.216336 -0.040979 -0.0174507 -0.216227 -0.0416924 -0.0165879 -0.217027 -0.0407939 -0.0170826 -0.215444 -0.0477721 -0.00800333 -0.218419 -0.0479744 -0.00800333 -0.218425 -0.0456127 -0.0127434 -0.218602 -0.046685 -0.0103449 -0.218479 -0.0487855 -0.00800333 -0.218962 -0.0460983 -0.0130717 -0.219107 -0.0405781 -0.0171346 -0.214198 -0.0438618 -0.0149641 -0.209195 -0.0400871 -0.017962 -0.213504 -0.0408153 -0.0168821 -0.212613 -0.0414897 -0.0166029 -0.211276 -0.0421237 -0.0159293 -0.21065 -0.045529 -0.0130343 -0.208911 -0.0438096 -0.0147955 -0.209493 -0.042109 -0.0164916 -0.210163 -0.0404418 -0.0176377 -0.214186 -0.0408889 -0.0172614 -0.212032 -0.0407471 -0.0174698 -0.211905 -0.0402749 -0.0178511 -0.214184 -0.0406598 -0.0170215 -0.213196 -0.0405454 -0.0173875 -0.214191 -0.0409643 -0.0170123 -0.212142 -0.0421551 -0.0160563 -0.210579 -0.0435883 -0.0144509 -0.209799 -0.0432637 -0.0145981 -0.209942 -0.0449714 -0.0125857 -0.209543 -0.0451091 -0.0126923 -0.209486 -0.0436767 -0.0145711 -0.209722 -0.0421673 -0.016297 -0.210391 -0.0424809 -0.0162419 -0.209568 -0.0462259 -0.0103244 -0.20949 -0.0453672 -0.0128975 -0.209254 -0.0482774 -0.00800333 -0.208755 -0.0483239 -0.00800333 -0.208584 -0.0463245 -0.0120061 -0.2085 -0.0546973 -0.019629 -0.306522 -0.0545887 -0.0198033 -0.308294 -0.0520749 -0.0196309 -0.319256 -0.0496639 -0.0198033 -0.325198 -0.0520994 -0.0196253 -0.319172 0.00939918 -0.0197096 -0.296814 0.00807409 -0.0196253 -0.303291 -0.0124055 -0.0198033 -0.370549 0.00920752 -0.0195168 -0.296772 0.0162068 -0.0195168 -0.328146 0.0127145 -0.0195033 -0.320653 0.0145538 -0.0195033 -0.324713 0.0229876 -0.0196293 -0.356671 0.0220385 -0.0195033 -0.358692 0.0180466 -0.0195033 -0.36535 0.000478454 -0.0195033 -0.373692 -0.00937027 -0.0196293 -0.372036 -0.00680459 -0.0195033 -0.372702 -0.00624215 -0.0195383 -0.373009 -0.00666885 -0.0195033 -0.372743 -0.0174043 -0.0195158 -0.36622 -0.0257342 -0.0195168 -0.35615 -0.0256656 -0.0195033 -0.356094 -0.0340238 -0.0195168 -0.346049 -0.0339551 -0.0195033 -0.345993 -0.0422447 -0.0195033 -0.335891 -0.0423133 -0.0195168 -0.335948 -0.0443587 -0.0195168 -0.333396 -0.0445728 -0.0195033 -0.332963 -0.0493946 -0.0195033 -0.325066 -0.0506071 -0.0195033 -0.322408 -0.0518709 -0.0195033 -0.319094 -0.0540591 -0.0195033 -0.310059 0.0106338 -0.0195168 -0.290267 0.0130189 -0.0195146 -0.27936 0.013168 -0.0195516 -0.279057 0.013311 -0.0196242 -0.278766 0.00811818 -0.0197121 -0.303296 -0.0548228 -0.0198033 -0.299911 0.00800676 -0.0195588 -0.303284 0.00792213 -0.0195168 -0.303276 0.00929059 -0.0195588 -0.29679 0.00783367 -0.0195033 -0.303267 0.00787721 -0.0195033 -0.302869 0.0107169 -0.0195588 -0.290285 0.010783 -0.0196253 -0.2903 -0.0546335 -0.0195244 -0.299922 -0.0546313 -0.0195571 -0.30643 -0.0547351 -0.0195912 -0.299916 0.0108954 -0.0197096 -0.315948 0.011151 -0.0198033 -0.316475 0.0237574 -0.0198033 -0.346658 0.021876 -0.0197096 -0.340184 0.0184179 -0.0198033 -0.332514 0.0191248 -0.0198033 -0.334075 0.0218897 -0.0198033 -0.340177 0.022686 -0.0198033 -0.342194 0.021858 -0.0197096 -0.359851 0.0222108 -0.0198033 -0.359068 0.000484613 -0.0198033 -0.373992 0.008016 -0.0196253 -0.306549 0.0108558 -0.0196253 -0.315965 0.0163855 -0.0197096 -0.328065 0.00849693 -0.0196253 -0.30982 0.0085393 -0.0197096 -0.30981 0.00803393 -0.0196434 -0.306635 0.00813231 -0.0198033 -0.303297 0.000483411 -0.0196253 -0.373934 -0.0061929 -0.0196253 -0.373127 -0.00627236 -0.0196348 -0.373112 -0.0463312 -0.0196279 -0.330885 -0.0424313 -0.0196253 -0.336045 -0.0341754 -0.0197096 -0.346173 -0.0258523 -0.0196253 -0.356247 -0.0175501 -0.0197096 -0.366356 -0.0175183 -0.0196253 -0.366326 0.0237488 -0.0198033 -0.353395 -0.00617541 -0.0195588 -0.373061 0.000482021 -0.0195588 -0.373866 0.000484289 -0.019706 -0.373976 0.00777486 -0.0195033 -0.306565 0.00843102 -0.0195588 -0.309835 0.00826171 -0.0195033 -0.309875 0.0106358 -0.0195033 -0.316065 0.0162843 -0.0195588 -0.328111 0.0134162 -0.0197659 -0.278552 0.0133977 -0.019718 -0.27859 0.0113713 -0.0198033 -0.28789 0.0108255 -0.0197096 -0.290309 0.00935668 -0.0196253 -0.296804 0.0107941 -0.0195588 -0.315993 0.0163459 -0.0196253 -0.328083 0.0218363 -0.0196253 -0.340201 0.0217746 -0.0195588 -0.340229 0.0229963 -0.0196293 -0.343361 0.0216962 -0.0195165 -0.340264 0.0222972 -0.0195033 -0.341992 0.0234604 -0.0195033 -0.3467 0.0239865 -0.0198033 -0.35046 0.0234518 -0.0195033 -0.353353 0.0217567 -0.0195588 -0.359806 0.021673 -0.0195147 -0.359767 0.0218183 -0.0196253 -0.359833 0.0182635 -0.0197096 -0.365535 0.0182304 -0.0196253 -0.365507 0.0181789 -0.0195588 -0.365463 0.0158639 -0.0196293 -0.367924 0.0181086 -0.0195147 -0.365404 0.0173931 -0.0195033 -0.366087 0.0130671 -0.0195033 -0.369765 0.010413 -0.0195033 -0.371283 0.0103656 -0.0198033 -0.371639 0.00714125 -0.0198033 -0.372908 0.00384925 -0.0196293 -0.37363 0.000480513 -0.0195148 -0.373774 -0.0122505 -0.0195033 -0.370292 -0.0146587 -0.0198033 -0.369007 -0.017561 -0.0198033 -0.366366 -0.0207104 -0.0198033 -0.362605 -0.0258859 -0.0197096 -0.356274 -0.0286665 -0.0198033 -0.35291 -0.034187 -0.0198033 -0.346183 -0.04249 -0.019627 -0.335975 -0.0453251 -0.0198033 -0.332442 -0.0463782 -0.0196253 -0.330811 -0.0463217 -0.0195588 -0.330773 -0.0341418 -0.0196253 -0.346146 -0.042379 -0.0195588 -0.336002 -0.0340895 -0.0195588 -0.346103 -0.0258 -0.0195588 -0.356204 -0.0174688 -0.0195588 -0.36628 -0.0151142 -0.0196293 -0.368576 -0.0461767 -0.0195033 -0.330677 -0.0462508 -0.0195168 -0.330726 -0.0520354 -0.0195588 -0.31915 -0.0508732 -0.0195503 -0.32219 -0.0519552 -0.0195169 -0.319123 -0.0547012 -0.0196253 -0.306435 -0.0546151 -0.0195506 -0.306515 -0.0543315 -0.0195918 -0.309656 -0.0535767 -0.0195033 -0.312812 -0.0548018 -0.0196929 -0.299913 -0.0546049 -0.0193403 -0.296352 -0.054625 -0.0194492 -0.296329 -0.0544356 -0.018406 -0.292898 -0.0542611 -0.0167131 -0.289735 -0.0542427 -0.0166197 -0.289799 -0.0540909 -0.0143639 -0.287052 -0.0538896 -0.00851092 -0.283006 -0.053832 -0.0050711 -0.281962 -0.0538158 -0.00504889 -0.282075 -0.0545385 -0.0192401 -0.296375 -0.0544165 -0.0183028 -0.292942 -0.0541767 -0.016534 -0.28986 -0.0538999 -0.0115437 -0.284877 -0.0539657 -0.0116013 -0.284787 -0.0538731 -0.00846739 -0.283112 -0.0538075 -0.00842754 -0.283212 -0.0544364 -0.0191748 -0.296394 -0.0543502 -0.018208 -0.292985 -0.0542477 -0.0181467 -0.293016 -0.0540737 -0.016479 -0.289902 -0.054025 -0.0142907 -0.287129 -0.0539217 -0.014244 -0.287181 -0.0537502 -0.00502857 -0.282181 -0.0536461 -0.00501577 -0.282251 -0.0541361 -0.0181289 -0.293029 -0.0537963 -0.0115071 -0.284937 -0.0537036 -0.00840237 -0.283278 -0.0535901 -0.00839604 -0.2833 -0.0536317 -0.00150333 -0.281903 -0.0535131 -0.00150333 -0.281928 -0.0536317 -0.00030333 -0.281903 -0.053731 -0.00030333 -0.281834 -0.053731 -0.00150333 -0.281834 -0.0537729 -0.00030333 -0.281778 -0.0537947 -0.00150333 -0.281731 -0.0538126 -0.00150333 -0.281611 -0.0537729 -0.00022833 -0.281758 -0.0537729 -0.00015333 -0.281628 -0.0536891 -6.06252e-05 -0.281618 -0.0536631 -4.35227e-05 -0.281628 -0.0536056 -1.80133e-05 -0.281623 -0.0538131 -0.00030333 -0.281628 -0.0537979 -0.000210625 -0.281612 -0.0538117 -0.000280246 -0.281611 -0.0538055 -0.00023844 -0.281612 -0.0536631 -0.00030333 -0.281888 -0.0537729 -0.000173426 -0.281703 -0.0536631 -7.83303e-05 -0.281758 -0.0536631 -0.000173426 -0.281853 -0.0535131 -9.11983e-05 -0.28184 -0.0535131 -0.00015333 -0.281888 -0.0535131 -0.00030333 -0.281928 -0.0537947 -0.00030333 -0.281731 -0.0535131 -3.3303e-06 -0.281628 -0.0498555 -2.61664e-05 -0.281743 -0.0535131 -4.35227e-05 -0.281778 -0.0498555 -9.11983e-05 -0.28184 -0.0495198 -0.000188525 -0.281797 -0.0496991 -9.11983e-05 -0.281816 -0.0498555 -0.000188525 -0.281905 -0.0496793 -0.000188525 -0.281877 -0.0497288 -2.61664e-05 -0.281723 -0.0498555 -3.3303e-06 -0.281628 -0.0495299 -0.00015333 -0.281783 -0.0495938 -4.35227e-05 -0.281694 -0.0478634 -3.3303e-06 -0.280884 -0.0495577 -9.11983e-05 -0.281744 -0.048655 -0.00030333 -0.269217 -0.0486536 -0.00015333 -0.269258 -0.0520515 -3.3303e-06 -0.266037 -0.0511147 -3.3303e-06 -0.268528 -0.0486499 -4.35227e-05 -0.269367 -0.0499281 -4.35227e-05 -0.269143 -0.0498873 -0.00015333 -0.269041 -0.0510075 -4.35227e-05 -0.268423 -0.050929 -0.00015333 -0.268346 -0.0517048 -4.35227e-05 -0.267328 -0.0519017 -4.35227e-05 -0.266046 -0.0518397 -9.11983e-05 -0.266049 -0.0517921 -0.00015333 -0.266052 -0.0498723 -0.00030333 -0.269004 -0.051602 -0.00015333 -0.26729 -0.0517748 -0.000188525 -0.266053 -0.05169 -0.000188525 -0.264516 -0.0519369 -2.61664e-05 -0.266044 -0.0519667 -3.3303e-06 -0.264501 -0.0518521 -2.61664e-05 -0.264507 -0.0517549 -9.11983e-05 -0.264513 -0.0516672 -0.00030333 -0.264517 -0.0516051 -0.000188525 -0.26298 -0.0518819 -3.3303e-06 -0.262964 -0.0510095 -3.3303e-06 -0.252686 -0.0503479 -0.00030281 -0.248031 -0.0494211 -8.84989e-05 -0.223375 -0.0495229 -2.32459e-05 -0.223371 -0.0496303 -3.3303e-06 -0.223366 -0.0517672 -2.61664e-05 -0.262971 -0.0502515 -2.47877e-05 -0.243192 -0.0516701 -9.11983e-05 -0.262976 -0.0498954 -0.000301677 -0.238807 -0.0490119 -0.000189014 -0.222011 -0.0493533 -0.00018882 -0.223378 -0.0490731 -8.85925e-05 -0.221981 -0.0495639 -3.3303e-06 -0.222804 -0.0489915 -0.000298865 -0.22202 -0.0482104 -8.89102e-05 -0.220839 -0.0481656 -0.000189673 -0.22089 -0.0469483 -0.000190772 -0.220189 -0.0469697 -8.94397e-05 -0.220125 -0.048278 -2.33374e-05 -0.220763 -0.0455526 -0.000192237 -0.22002 -0.0455511 -0.00015333 -0.220001 -0.0455424 -4.35227e-05 -0.219892 -0.0470021 -2.34551e-05 -0.220028 -0.0464171 -3.3303e-06 -0.208025 -0.0463023 -0.000190704 -0.207771 -0.0449332 -0.000192107 -0.208084 -0.0462933 -0.000301389 -0.207751 -0.0474873 -8.87664e-05 -0.206999 -0.0463303 -8.92651e-05 -0.207833 -0.0481429 -0.000299092 -0.205748 -0.0481641 -0.000189048 -0.205756 -0.047421 -0.000299952 -0.206938 -0.0474374 -0.000189668 -0.206953 -0.0475625 -2.32009e-05 -0.207068 -0.0484335 -8.96148e-05 -0.204365 -0.0482281 -8.84685e-05 -0.205779 -0.0485344 -2.40321e-05 -0.20436 -0.0483242 -2.3135e-05 -0.205813 -0.0483109 -3.3303e-06 -0.206131 -0.0483665 -0.000189647 -0.204369 -0.0463196 -8.78621e-05 -0.166084 -0.0464213 -2.30022e-05 -0.166078 -0.0461445 -3.3303e-06 -0.164607 -0.0451528 -2.31243e-05 -0.163492 -0.0456558 -3.3303e-06 -0.163853 -0.0462516 -0.000187782 -0.166088 -0.045957 -8.79916e-05 -0.164699 -0.0441945 -3.3303e-06 -0.162774 -0.0424062 -3.3303e-06 -0.162496 -0.0424161 -2.61664e-05 -0.162611 -0.0438749 -2.32736e-05 -0.162771 -0.0438432 -8.9089e-05 -0.162868 -0.0424301 -0.000188525 -0.162773 -0.0450859 -8.84137e-05 -0.163569 -0.0438223 -0.000190334 -0.162933 -0.0458959 -0.000188052 -0.164729 -0.0458753 -0.000297704 -0.164739 -0.0450414 -0.00018893 -0.163621 -0.0431673 -8.8961e-05 -0.15059 -0.041772 -9.11983e-05 -0.150907 -0.0442742 -0.000188434 -0.14971 -0.0431393 -0.000190072 -0.150528 -0.0443242 -8.81737e-05 -0.149756 -0.0443992 -2.30699e-05 -0.149825 -0.0442574 -0.000298238 -0.149694 -0.0450651 -8.76745e-05 -0.148536 -0.044024 -3.3303e-06 -0.150315 -0.0451804 -0.000296347 -0.147127 -0.0452034 -0.000187853 -0.147126 -0.0452706 -8.87434e-05 -0.147122 -0.045001 -0.000187395 -0.148513 -0.0453711 -2.38328e-05 -0.147117 -0.0454799 -3.3303e-06 -0.147111 -0.0451609 -2.29594e-05 -0.14857 -0.0451471 -3.3303e-06 -0.148888 -0.0431445 -2.27215e-05 -0.106791 -0.0418759 -2.29275e-05 -0.104205 -0.042867 -3.3303e-06 -0.10532 -0.0430434 -8.65877e-05 -0.106797 -0.0426807 -8.68087e-05 -0.105412 -0.0418093 -8.75169e-05 -0.104282 -0.0405982 -2.31705e-05 -0.103484 -0.039148 -9.11983e-05 -0.103421 -0.0391535 -0.000188525 -0.103485 -0.0429752 -0.000185123 -0.106801 -0.0417646 -0.000187059 -0.104334 -0.0405665 -8.86151e-05 -0.103581 -0.0426194 -0.000185583 -0.105442 -0.0417493 -0.000296318 -0.104351 -0.0405455 -0.000189344 -0.103646 -0.0391536 -0.000192111 -0.103487 -0.0367535 -4.35227e-05 -0.0919937 -0.0386622 -3.3303e-06 -0.0910349 -0.0385611 -4.35227e-05 -0.0909241 -0.036705 -0.00030333 -0.0918518 -0.036718 -0.00015333 -0.0918898 -0.0384871 -0.00015333 -0.090843 -0.03846 -0.00030333 -0.0908133 -0.0399177 -4.35227e-05 -0.0889127 -0.0398148 -0.00015333 -0.0888745 -0.0401224 -0.00015333 -0.086842 -0.0397771 -0.00030333 -0.0888605 -0.040232 -4.35227e-05 -0.086836 -0.0403818 -3.3303e-06 -0.0868277 -0.038013 -0.00030333 -0.0493592 -0.0319799 -3.3303e-06 -0.030506 -0.0354611 -4.35227e-05 -0.0373422 -0.0373119 -4.35227e-05 -0.0432341 -0.0381628 -4.35227e-05 -0.0493509 -0.0383125 -3.3303e-06 -0.0493426 -0.0380531 -0.00015333 -0.0493569 -0.0372048 -0.00015333 -0.0432582 -0.0353595 -0.00015333 -0.0373837 -0.0326615 -4.35227e-05 -0.0318376 -0.0289901 -4.35227e-05 -0.0268717 -0.0289075 -0.00015333 -0.0269441 -0.0353223 -0.00030333 -0.0373989 -0.0325339 -0.00030333 -0.0319164 -0.0325681 -0.00015333 -0.0318953 0.0343314 -0.000188525 0.00244535 -0.0326473 -2.61664e-05 -0.0114255 0.0286324 -2.61664e-05 0.0193943 0.0327876 -3.3303e-06 0.0113494 0.0287275 -3.3303e-06 0.0194586 -0.034608 -3.3303e-06 -0.00258573 -0.0286663 -3.3303e-06 -0.019558 -0.00252169 -2.61664e-05 0.0344957 0.00650187 -2.61664e-05 0.0339698 0.00648356 -9.11983e-05 0.0338742 -0.0284517 -0.00015333 -0.0194115 -0.0325555 -9.11983e-05 -0.0113933 -0.0284911 -9.11983e-05 -0.0194384 -0.0343965 -9.11983e-05 -0.00256991 -0.0309868 -0.00030333 0.0149511 -0.0310053 -0.000194079 0.0149601 -0.0262824 -3.3303e-06 0.0226643 -0.0310659 -9.11983e-05 0.0149893 -0.0260708 -0.000194079 0.0224818 -0.0193559 -0.000194043 0.0284681 0.0325871 -9.11983e-05 0.01128 0.0285519 -9.11983e-05 0.0193397 0.0343487 -0.00015333 0.00244658 0.0326791 -2.61664e-05 0.0113118 0.0344582 -4.35227e-05 0.00245438 -0.032492 -0.000194079 -0.0113711 -0.0324725 -0.00030333 -0.0113643 -0.0344935 -2.61664e-05 -0.00257717 -0.0338021 -0.00030333 0.00641282 -0.0338223 -0.000194079 0.00641666 -0.0343294 -0.000194079 -0.0025649 -0.033984 -2.61664e-05 0.00644733 -0.0311535 -2.61664e-05 0.0150316 -0.0338884 -9.11983e-05 0.00642919 -0.0261955 -2.61664e-05 0.0225893 -0.0261218 -9.11983e-05 0.0225257 -0.0113125 -0.00030333 0.0324906 -0.01132 -0.000188525 0.0325121 -0.0194485 -2.61664e-05 0.0286042 -0.0113413 -9.11983e-05 0.0325735 -0.0193937 -9.11983e-05 0.0285237 -0.00250972 -0.000194079 0.0343315 -0.00250822 -0.00030333 0.034311 -0.0113733 -2.61664e-05 0.0326655 -0.00251461 -9.11983e-05 0.0343986 0.0227049 -3.3303e-06 0.0262389 0.015081 -2.61664e-05 0.0311239 0.0150386 -9.11983e-05 0.0310363 0.00647091 -0.000194079 0.0338082 0.00646703 -0.00030333 0.0337879 0.0226297 -2.61664e-05 0.0261521 0.0150092 -0.000194079 0.0309757 0.0346078 -3.3303e-06 0.00246502 0.022566 -9.11983e-05 0.0260785 0.022522 -0.000194079 0.0260277 0.0238404 -0.00030333 0.0247968 0.0325236 -0.000194043 0.011258 0.0325041 -0.00030333 0.0112513 0.0311484 -0.00030333 0.0145915 0.0284961 -0.000194079 0.019302 0.0284791 -0.00030333 0.0192904 0.0343086 -0.00030333 0.00244373 0.0382378 -0.000188525 -0.00527452 0.0355228 -0.00015333 -0.00180005 0.0356208 -4.35227e-05 -0.00175047 0.0384173 -3.3303e-06 -0.00506341 0.0343962 -9.11983e-05 0.00244997 0.058914 -3.3303e-06 -0.0619422 0.0584114 -3.3303e-06 -0.0647995 0.0571128 -0.00015333 -0.0706819 0.0586185 -0.00030333 -0.0618902 0.0571598 -9.11983e-05 -0.0706902 0.057221 -4.35227e-05 -0.070701 0.0572193 -4.35227e-05 -0.0707401 0.0572608 -2.61664e-05 -0.0707662 0.0571099 -0.00015333 -0.0707497 0.0570732 -0.00030333 -0.070675 0.0570699 -0.00030333 -0.0707532 0.0571246 -0.00015333 -0.0708159 0.0571694 -9.11983e-05 -0.0707996 0.0572761 -2.61664e-05 -0.0708081 0.0572278 -4.35227e-05 -0.0707783 0.0571847 -9.11983e-05 -0.0708415 0.0571083 -0.000188525 -0.0708218 0.0567681 -2.04739e-05 -0.0759215 0.0573214 -9.11983e-05 -0.0728241 0.0565897 -0.000202194 -0.0758829 0.0565726 -0.00030333 -0.0758792 0.0572355 -0.00030333 -0.0728057 0.0566589 -9.07579e-05 -0.0758978 0.0558445 -0.000307591 -0.0792823 0.0558863 -0.000199869 -0.0791746 0.0560517 -2.52261e-05 -0.0792099 0.0557425 -3.3303e-06 -0.0811282 0.0556366 -2.39705e-05 -0.0811026 0.0555384 -8.92236e-05 -0.0810801 0.0559509 -9.47151e-05 -0.0791884 0.055473 -0.000188631 -0.0810651 0.0556049 -3.3303e-06 -0.0817414 0.0553639 -2.38593e-05 -0.0823322 0.0552654 -8.88593e-05 -0.0823108 0.0551997 -0.000188092 -0.0822966 0.0551773 -0.000296678 -0.0822917 0.0554508 -0.000294701 -0.0810586 0.0516063 -8.89614e-05 -0.0991439 0.0518113 -3.3303e-06 -0.0991886 0.048471 -3.3303e-06 -0.10303 0.0517047 -2.38827e-05 -0.0991654 0.0508891 -8.9186e-05 -0.100851 0.0497346 -3.3303e-06 -0.102357 0.0479407 -9.03664e-05 -0.102977 0.0479668 -2.42039e-05 -0.103075 0.0460976 -9.11983e-05 -0.103119 0.0515406 -0.000188302 -0.0991296 0.0496113 -8.96703e-05 -0.102186 0.0495721 -0.000189761 -0.102132 0.0508329 -0.000188764 -0.100814 0.049559 -0.000298993 -0.102113 0.0479235 -0.000191193 -0.102912 0.0461068 -0.00030333 -0.103032 0.0426796 -4.35227e-05 -0.114136 0.0444011 -4.35227e-05 -0.114749 0.0426079 -0.00030333 -0.114268 0.0426271 -0.00015333 -0.114233 0.0405091 -0.00015333 -0.112291 0.0404756 -0.00030333 -0.112313 0.0395059 -0.00030333 -0.109588 0.0395459 -0.00015333 -0.109584 0.0442353 -0.00030333 -0.103128 0.0461046 -0.000192902 -0.103052 0.0442436 -0.00015333 -0.103168 0.0461026 -0.00015333 -0.103072 0.0443899 -8.99412e-05 -0.114808 0.0399612 -0.00015333 -0.106741 0.0400628 -4.35227e-05 -0.106782 0.0416587 -0.00015333 -0.104422 0.041729 -4.35227e-05 -0.104507 0.0442663 -4.35227e-05 -0.103275 0.0427513 -3.3303e-06 -0.114005 0.0407257 -3.3303e-06 -0.112147 0.0406007 -4.35227e-05 -0.11223 0.0396551 -4.35227e-05 -0.109573 0.0418251 -3.3303e-06 -0.104622 0.0442974 -3.3303e-06 -0.103422 0.0460911 -4.35227e-05 -0.103181 0.0460753 -3.3303e-06 -0.10333 0.0458324 -3.3303e-06 -0.115171 0.0449569 -3.3303e-06 -0.11474 0.0444287 -3.3303e-06 -0.114601 0.0443775 -0.000192107 -0.114875 0.0443809 -0.00015333 -0.114857 0.0456787 -0.000190382 -0.115402 0.0467246 -8.84367e-05 -0.116355 0.0457163 -8.91108e-05 -0.115346 0.0468098 -2.31283e-05 -0.116298 0.0471938 -0.000188085 -0.11769 0.0466679 -0.000188981 -0.116392 0.0472607 -8.80062e-05 -0.117677 0.0472374 -8.91003e-05 -0.119105 0.0473609 -2.30331e-05 -0.117658 0.0386879 -2.29549e-05 -0.158577 0.0471496 -0.000297367 -0.119086 0.0385884 -8.76475e-05 -0.158555 0.0471718 -0.000188588 -0.119091 0.0473359 -2.39145e-05 -0.119127 0.0444259 -3.3303e-06 -0.132909 0.0384992 -0.000296706 -0.158536 0.0385219 -0.000187335 -0.158541 0.0369206 -0.0002985 -0.160763 0.0379345 -0.000297129 -0.159812 0.0369325 -0.000188624 -0.160782 0.0369683 -8.82669e-05 -0.16084 0.0379534 -0.000187639 -0.159825 0.038009 -8.77936e-05 -0.159865 0.037022 -2.3092e-05 -0.160927 0.0381791 -3.3303e-06 -0.159985 0.0375764 -3.3303e-06 -0.160651 0.0356156 -0.000300658 -0.161245 0.0359614 -3.3303e-06 -0.161482 0.0342247 -0.00030333 -0.16118 0.035619 -0.000190179 -0.161267 0.0342149 -0.00015333 -0.161219 0.0356294 -8.90144e-05 -0.161334 0.0356451 -2.32573e-05 -0.161435 0.0316715 -8.99405e-05 -0.172808 0.0298333 -0.00015333 -0.17219 0.0267641 -0.00030333 -0.167231 0.0268043 -0.00015333 -0.167229 0.0274477 -0.00015333 -0.164296 0.027673 -0.00015333 -0.170104 0.026914 -4.35227e-05 -0.167225 0.0275455 -4.35227e-05 -0.164346 0.0294398 -0.00015333 -0.162049 0.029501 -4.35227e-05 -0.16214 0.0295845 -3.3303e-06 -0.162264 0.0270639 -3.3303e-06 -0.167219 0.0278948 -3.3303e-06 -0.169969 0.0277667 -4.35227e-05 -0.170047 0.0298873 -4.35227e-05 -0.172095 0.0317103 -3.3303e-06 -0.172601 0.0294174 -0.00030333 -0.162015 0.0305468 -3.3303e-06 -0.161745 0.0322839 -4.35227e-05 -0.161168 0.0322961 -3.3303e-06 -0.161317 0.0341881 -4.35227e-05 -0.161325 0.0342195 -0.000192109 -0.161201 0.0322749 -0.00015333 -0.161058 0.0316827 -4.35227e-05 -0.172748 0.032948 -0.000300222 -0.173421 0.0329603 -0.000189862 -0.173402 0.031659 -0.000192107 -0.172875 0.0316625 -0.00015333 -0.172856 0.0340064 -8.80028e-05 -0.174354 0.0329979 -8.886e-05 -0.173345 0.0331139 -3.3303e-06 -0.173171 0.0339497 -0.000188079 -0.174392 0.0345426 -8.74642e-05 -0.175677 0.0340914 -2.3032e-05 -0.174298 0.0337995 -3.3303e-06 -0.173754 0.0344528 -0.000189338 -0.177091 0.0344756 -0.000186958 -0.175689 0.0346426 -2.29127e-05 -0.175658 0.0346169 -2.40376e-05 -0.177127 0.0346797 -3.3303e-06 -0.175342 0.0262168 -0.000292443 -0.214535 0.0283526 -0.000293422 -0.204798 0.0262396 -0.000186976 -0.21454 0.0345183 -8.95444e-05 -0.177105 0.021906 -4.35227e-05 -0.217324 0.0264033 -2.3774e-05 -0.214576 0.0233629 -2.31171e-05 -0.217434 0.0256999 -2.26984e-05 -0.21607 0.025756 -2.2691e-05 -0.215997 0.0247958 -3.3303e-06 -0.217017 0.0247399 -2.28486e-05 -0.216926 0.0233473 -8.83679e-05 -0.217333 0.0255822 -2.27146e-05 -0.216212 0.0253249 -2.27525e-05 -0.216479 0.0233334 -0.000298777 -0.217243 0.0241288 -0.000296549 -0.217021 0.0246382 -0.000295262 -0.216762 0.0256521 -0.000293101 -0.215811 0.0246506 -0.000186303 -0.216782 0.0256719 -0.000184757 -0.215825 0.0263052 -8.83953e-05 -0.214554 0.0219425 -0.00030333 -0.217179 0.0219413 -0.000248344 -0.217184 0.0233343 -0.000244322 -0.217249 0.0233368 -0.000188827 -0.217266 0.0246865 -8.71556e-05 -0.21684 0.0252961 -3.3303e-06 -0.216648 0.0257276 -8.64137e-05 -0.215864 0.0257212 -2.26956e-05 -0.216043 0.0257141 -2.26965e-05 -0.216052 0.0257247 -2.26951e-05 -0.216038 0.0257282 -2.26947e-05 -0.216034 0.0258102 -2.2684e-05 -0.215923 0.0193394 -0.000192095 -0.228867 0.0193524 -8.99215e-05 -0.2288 0.0175771 -4.35227e-05 -0.228077 0.0193926 -3.3303e-06 -0.228593 0.0176515 -3.3303e-06 -0.227946 0.0149119 -3.3303e-06 -0.224213 0.0147843 -3.3303e-06 -0.223198 0.0175226 -0.00015333 -0.228172 0.0153445 -0.00030333 -0.226099 0.0144845 -0.00030333 -0.223208 0.0171456 -0.00030333 -0.21801 0.0199973 -0.00015333 -0.217058 0.0219327 -0.00015333 -0.217218 0.0154729 -4.35227e-05 -0.226022 0.0153789 -0.00015333 -0.226079 0.0145247 -0.00015333 -0.223207 0.0146344 -4.35227e-05 -0.223203 0.0151759 -0.00015333 -0.220282 0.0171679 -0.00015333 -0.218044 0.017229 -4.35227e-05 -0.218135 0.0200062 -4.35227e-05 -0.217167 0.0219208 -8.9949e-05 -0.217265 0.0152737 -4.35227e-05 -0.220332 0.0154072 -3.3303e-06 -0.2204 0.0173124 -3.3303e-06 -0.21826 0.022267 -2.34898e-05 -0.233156 0.0218571 -3.3303e-06 -0.230255 0.0208121 -2.30631e-05 -0.229316 0.0214868 -3.3303e-06 -0.229774 0.0223081 -2.26351e-05 -0.231683 0.0222084 -8.62542e-05 -0.231701 0.0221696 -8.72463e-05 -0.233134 0.0221039 -0.000184766 -0.233118 0.0200182 -0.000190306 -0.229071 0.0216256 -0.000186061 -0.230406 0.0218754 -0.00029386 -0.230919 0.0221411 -0.000184462 -0.231713 0.0206791 -8.82775e-05 -0.229348 0.020641 -0.000188678 -0.229405 0.019364 -4.35227e-05 -0.22874 0.0207363 -2.30832e-05 -0.229264 0.019343 -0.00015333 -0.228848 0.0216828 -8.7021e-05 -0.230369 0.021768 -2.28051e-05 -0.230313 0.0213052 -2.29317e-05 -0.229737 0.0210317 -2.30048e-05 -0.229485 0.0208866 -2.30433e-05 -0.229371 0.0208495 -2.30531e-05 -0.229343 0.0208681 -2.30482e-05 -0.229357 0.0208402 -2.30556e-05 -0.229337 0.0208309 -2.30581e-05 -0.22933 0.0152955 -2.35855e-05 -0.264227 0.0151946 -9.0027e-05 -0.264209 0.0151281 -0.00019199 -0.264196 0.0183861 -0.000299113 -0.248598 0.0186776 -3.3303e-06 -0.248668 0.0185711 -2.40544e-05 -0.248642 0.0184729 -8.97123e-05 -0.248619 0.0184077 -0.000189847 -0.248603 0.0147909 -2.3587e-05 -0.265524 0.0146551 -9.00346e-05 -0.265545 0.0150876 -2.35858e-05 -0.264943 0.0149304 -2.35864e-05 -0.265281 0.0148393 -2.35868e-05 -0.265444 0.0148153 -2.35869e-05 -0.265484 0.0148092 -2.35869e-05 -0.265494 0.0148031 -2.35869e-05 -0.265504 0.014797 -2.35869e-05 -0.265514 0.0147406 -2.35872e-05 -0.265601 0.0152513 -3.3303e-06 -0.264816 0.0145809 -0.00030301 -0.265495 0.0145987 -0.000192005 -0.265507 0.0136006 -0.000192058 -0.266502 0.0136942 -2.35929e-05 -0.266644 0.0123041 -9.00994e-05 -0.267092 0.0136378 -9.00601e-05 -0.266558 0.0122921 -0.00019214 -0.267025 0.0108773 -0.00015333 -0.267012 0.0108529 -4.35227e-05 -0.267119 0.0123224 -2.36016e-05 -0.267193 0.00428898 -9.11983e-05 -0.271695 0.00449962 -3.3303e-06 -0.27172 0.00435067 -4.35227e-05 -0.271702 0.0108815 -0.000192237 -0.266993 0.00498077 -0.00015333 -0.269527 0.00654006 -0.00015333 -0.267856 0.00507494 -4.35227e-05 -0.269583 0.00864639 -0.00015333 -0.26697 0.00520358 -3.3303e-06 -0.26966 0.00660287 -4.35227e-05 -0.267946 0.00866684 -4.35227e-05 -0.267078 0.0108195 -3.3303e-06 -0.267265 0.00329142 -2.61664e-05 -0.280891 0.00319478 -9.11983e-05 -0.28088 0.0031302 -0.000188525 -0.280872 0.00310752 -0.00030333 -0.280869 0.00424164 -0.00015333 -0.271689 0.0134174 -0.000259333 -0.278543 0.0133987 -0.000188488 -0.278536 0.0133712 -0.000134771 -0.278527 0.0131352 -3.3303e-06 -0.278444 0.0138262 -3.3303e-06 -0.275293 0.0139383 -2.61664e-05 -0.275317 0.0132599 -3.35334e-05 -0.278488 0.0133369 -9.11516e-05 -0.278515 0.0140969 -0.000188525 -0.275352 0.0148041 -0.000188525 -0.272127 0.0147406 -9.11983e-05 -0.272113 0.0140334 -9.11983e-05 -0.275338 0.0253748 -2.4513e-05 -0.223092 0.018254 -0.000305308 -0.254474 0.0206465 -0.000309823 -0.244363 0.0255419 -0.000200652 -0.223129 0.0254767 -9.42174e-05 -0.223114 0.0146455 -2.61664e-05 -0.272092 0.0195777 -3.3303e-06 -0.247504 0.0252666 -3.3303e-06 -0.223068 0.0324037 -3.3303e-06 -0.19053 0.0406829 -3.3303e-06 -0.15278 0.0502575 -3.3303e-06 -0.109108 0.0561663 -2.493e-05 -0.0825057 0.0416236 -0.000309583 -0.14989 0.0565604 -0.000198364 -0.0815051 0.0562667 -9.3552e-05 -0.0825275 0.0563315 -0.000197728 -0.0825415 0.0563954 -2.50007e-05 -0.081468 0.0565786 -0.000310818 -0.0815099 0.0564957 -9.38627e-05 -0.0814905 0.0627473 -8.67393e-05 -0.0520184 0.0599073 -0.000292388 -0.0660855 0.0596983 -0.000185392 -0.0669569 0.0581033 -0.00018533 -0.0744117 0.0582402 -0.000291609 -0.0738926 0.0573924 -0.000291805 -0.0778223 0.0644137 -0.000295239 -0.0442978 0.0596307 -8.59972e-05 -0.0669425 0.0595304 -2.20249e-05 -0.0669213 0.0626465 -2.21845e-05 -0.0519977 0.0686897 -8.76749e-05 -0.0221112 0.0628148 -0.00018695 -0.0520322 0.0667871 -0.000291924 0.0119497 0.0686773 -3.3303e-06 -0.0210355 0.0697001 -3.3303e-06 -0.0108844 0.06859 -2.30624e-05 -0.0220919 0.07 -0.000297606 -0.0108922 0.0698477 -0.000293398 -0.0140402 0.0687565 -0.000187108 -0.0221241 0.0693202 -0.000190722 0.00066418 0.0692243 -0.00030081 0.00147044 0.0690448 -3.3303e-06 0.000625495 0.0691471 -2.16876e-05 0.00063987 0.0695773 -0.000301907 -0.00118678 0.0699762 -0.0003019 -0.00649461 0.0699771 -0.000188194 -0.0108916 0.0692531 -8.94155e-05 0.000654757 0.0699034 -8.27821e-05 -0.0108897 0.0697202 -2.34511e-05 -0.00512956 0.069801 -2.07896e-05 -0.0108869 0.0667637 -0.000184037 0.0119424 0.0666931 -8.07386e-05 0.01192 0.068107 -2.31253e-05 0.00634011 0.0681069 -3.3303e-06 0.00584783 0.0623899 -0.000286284 0.0226528 0.0665959 -2.02323e-05 0.0118892 0.0621234 -3.3303e-06 0.0225162 0.0665012 -3.3303e-06 0.0118595 -0.0342611 -2.10269e-05 0.0153185 -0.0327371 -1.86689e-05 0.0193025 -0.0287886 -2.0596e-05 0.0267992 -0.028457 -3.3303e-06 0.0271299 -0.00287317 -1.96293e-05 0.0477769 0.0221459 -3.3303e-06 0.0505706 0.0221587 -2.04216e-05 0.0506695 0.0136919 -2.26577e-05 0.0510694 0.0053083 -3.3303e-06 0.0499959 0.0622168 -2.22961e-05 0.022564 0.0623668 -0.000180016 0.0226409 0.0623058 -8.42643e-05 0.0226096 0.0577476 -2.23217e-05 0.0297773 0.0578281 -8.43788e-05 0.0298367 0.0521649 -2.24869e-05 0.0361833 0.052235 -8.51181e-05 0.0362552 0.0491838 -3.3303e-06 0.0387384 0.0490104 -2.25872e-05 0.0390207 0.0457123 -8.60076e-05 0.0416636 0.0304441 -2.04788e-05 0.0489221 0.0304749 -8.70052e-05 0.0490255 0.026352 -2.28955e-05 0.0499669 0.0456507 -2.02835e-05 0.0415755 0.0383416 -2.28432e-05 0.045873 0.0304157 -3.3303e-06 0.0488262 0.0266699 -3.3303e-06 0.0497896 0.00528903 -1.9981e-05 0.0500925 0.00526845 -8.44668e-05 0.0501971 0.00114322 -2.2143e-05 0.0491014 -0.000244661 -3.3303e-06 0.048577 -0.00291023 -8.26174e-05 0.0478758 -0.0105305 -2.14662e-05 0.0441985 -0.0176722 -6.32536e-05 0.0394018 -0.0207124 -2.08383e-05 0.0366217 -0.0367145 -3.3303e-06 0.00286596 -0.035439 -1.89408e-05 0.0112473 -0.0368163 -2.12247e-05 0.00287418 -0.0236529 -1.85494e-05 0.0335762 -0.0201076 -3.3303e-06 0.0370511 0.0578833 -0.000180255 0.0298774 0.0457515 -0.000183652 0.0417195 0.0383856 -8.67148e-05 0.0459641 0.0221722 -8.67446e-05 0.0507765 0.0221808 -0.000185187 0.0508441 0.0136884 -8.5883e-05 0.0511701 0.0136861 -0.000183393 0.0512383 -0.0105791 -8.05625e-05 0.0442838 -0.0176464 -0.000168133 0.039536 -0.0176029 -7.85933e-05 0.0394823 -0.0237296 -7.71356e-05 0.0336445 -0.0288698 -7.67e-05 0.0268509 -0.0328318 -7.77519e-05 0.0193432 -0.0355398 -7.9076e-05 0.0112722 0.0579041 -0.000286621 0.0298928 0.0523005 -0.000288792 0.0363223 0.0522828 -0.000181798 0.0363041 0.0384152 -0.000185125 0.0460255 0.0304943 -0.000185729 0.0490908 0.0305011 -0.0002943 0.0491137 0.00525514 -0.000180439 0.0502643 0.00525012 -0.00028688 0.0502897 -0.00293426 -0.000176574 0.0479402 -0.0106133 -0.000172269 0.0443437 -0.0237812 -0.000165065 0.0336906 -0.0289282 -0.000164147 0.026888 -0.0328953 -0.000166363 0.0193704 -0.0356068 -0.000169147 0.0112888 -0.0375447 -3.3303e-06 -0.00761432 -0.0370116 -0.000269032 0.00288998 -0.0369822 -0.0001697 0.0028876 -0.0378198 -0.000184794 -0.00759396 -0.0369135 -7.94054e-05 0.00288205 -0.0423119 -3.3303e-06 -0.0787116 -0.0376493 -2.21672e-05 -0.0076067 -0.0387548 -3.3303e-06 -0.0231082 -0.0377511 -8.59375e-05 -0.00759911 -0.0407709 -0.000183745 -0.0481229 -0.0402006 -0.000291031 -0.0391242 -0.0406005 -2.20587e-05 -0.0481338 -0.0418362 -2.1709e-05 -0.0686592 -0.0407021 -8.54315e-05 -0.0481273 -0.0431693 -0.000205333 -0.089187 -0.0420061 -0.00018037 -0.0686493 -0.0431039 -9.73779e-05 -0.0891889 -0.0429998 -2.58259e-05 -0.0891919 -0.0419371 -8.3824e-05 -0.0686533 -0.042927 -3.3303e-06 -0.0901361 -0.0429033 -3.3303e-06 -0.0896656 -0.0430382 -2.47528e-05 -0.0901299 -0.0475459 -3.3303e-06 -0.173616 -0.0498232 -2.39292e-05 -0.21284 -0.0489793 -0.000308115 -0.194115 -0.0432091 -0.000202429 -0.0901203 -0.0431427 -9.51773e-05 -0.090124 -0.0463231 -3.3303e-06 -0.151491 -0.0513346 -3.3303e-06 -0.249206 -0.0499935 -0.000195199 -0.212831 -0.0499263 -9.15769e-05 -0.212834 -0.0526917 -9.01463e-05 -0.26292 -0.0513618 -0.000304778 -0.245066 -0.0511985 -0.000305142 -0.241693 -0.0527658 -0.000210625 -0.262916 -0.0500084 -3.3303e-06 -0.218528 -0.052657 -6.06252e-05 -0.262922 -0.0527805 -0.00030333 -0.262915 -0.053773 -0.000154191 -0.281613 -0.0527233 -0.000126995 -0.262918 -0.0537554 -0.000126995 -0.281614 -0.0536631 -4.36616e-05 -0.28162 -0.0525735 -1.80133e-05 -0.262926 -0.0498555 -0.00030333 -0.281928 -0.0496723 -0.00150333 -0.281899 -0.0496723 -0.00030333 -0.281899 -0.0495857 -0.00150333 -0.281864 -0.0495066 -0.00150333 -0.281816 -0.0524138 -0.0195033 -0.299902 -0.05217 -0.0189612 -0.295544 -0.0511301 -0.0152621 -0.287445 -0.0513359 -0.0178963 -0.291173 -0.0512212 -0.0166005 -0.289097 -0.0515726 -0.0195033 -0.295437 -0.0513485 -0.0114949 -0.284907 -0.051935 -0.0173675 -0.291423 -0.0519497 -0.0190049 -0.295545 -0.0521482 -0.0195033 -0.298781 -0.0518952 -0.0195033 -0.297622 -0.0517469 -0.0191366 -0.295523 -0.0517161 -0.0174091 -0.291413 -0.0515116 -0.0148545 -0.287794 -0.051686 -0.0195033 -0.296442 -0.0516135 -0.0193346 -0.29548 -0.0515145 -0.0175292 -0.29136 -0.0513109 -0.0149556 -0.287714 0.0471437 -0.000578241 -0.119085 0.046565 -0.00900333 -0.117671 0.0471712 -0.000297752 -0.117694 0.0464528 -0.00900333 -0.117184 0.0466491 -0.000298998 -0.116405 0.0450492 -0.00900333 -0.115296 0.0456665 -0.000300943 -0.115421 0.0443735 -0.00030333 -0.114896 0.0508139 -0.000297612 -0.100801 0.0499296 -0.00900333 -0.101154 0.0509308 -0.00900333 -0.099082 0.0480987 -0.00900333 -0.102562 0.0458097 -0.00900333 -0.103007 0.0479179 -0.000300973 -0.102891 -0.051752 -0.00465333 -0.266054 -0.051752 -0.00030333 -0.266054 -0.0515644 -0.00030333 -0.267275 -0.0509003 -0.00030333 -0.268318 0.0573054 -0.00030333 -0.0718292 0.0572355 -0.00650998 -0.0728057 0.0571021 -0.00900333 -0.0708716 0.0571021 -0.00030333 -0.0708716 0.0316551 -0.00030333 -0.172896 0.0339305 -0.000297744 -0.174404 0.0344526 -0.000296182 -0.175694 0.033628 -0.00495284 -0.17439 0.0328885 -0.00900333 -0.174198 0.0341241 -0.00505265 -0.175717 0.0341378 -0.00461566 -0.177038 0.033372 -0.00900333 -0.176879 -0.0422054 -0.00467263 -0.162811 -0.0438154 -0.000300874 -0.162954 -0.0450265 -0.000298925 -0.163638 -0.0446939 -0.00505128 -0.163713 -0.0455208 -0.00517081 -0.164857 -0.0449581 -0.00900333 -0.166173 -0.0447179 -0.00900333 -0.16506 -0.0458283 -0.00520894 -0.166129 -0.0434868 -0.0048697 -0.162994 0.0224359 -0.000301612 -0.217266 0.0228622 -0.00493345 -0.217103 0.0254816 -0.000293415 -0.216032 0.0240179 -0.00900333 -0.215312 0.0244584 -0.00900333 -0.214291 0.0250906 -0.00536207 -0.215604 0.0241226 -0.00518967 -0.216583 0.0232474 -0.00900333 -0.216152 0.0222264 -0.00900333 -0.216725 0.0209686 -0.00900333 -0.216991 0.021569 -0.00491366 -0.217098 0.0221589 -0.000292103 -0.232606 0.0221171 -0.000292712 -0.231717 0.0208532 -0.000297769 -0.229589 0.0200097 -0.000300855 -0.229091 0.0193354 -0.00030333 -0.228888 0.0216056 -0.000294948 -0.230419 0.0201237 -0.00498535 -0.229343 0.0192557 -0.00900333 -0.229282 0.0189917 -0.00470723 -0.22881 0.0180326 -0.00900333 -0.228476 0.020444 -0.00900333 -0.231733 0.020124 -0.00900333 -0.23047 0.0199124 -0.00900333 -0.230079 0.0215031 -0.00541651 -0.231633 0.0210406 -0.00524263 -0.230343 0.0203977 -0.00900333 -0.232494 -0.0455543 -0.00030333 -0.220041 -0.0464274 -0.00505442 -0.220272 -0.0469414 -0.000301304 -0.22021 -0.0481508 -0.000299781 -0.220907 -0.0486881 -0.00545144 -0.22335 -0.0493306 -0.000298595 -0.223379 -0.0483607 -0.00552808 -0.222127 -0.0472102 -0.00900333 -0.222146 -0.0475764 -0.00533779 -0.220999 -0.045328 -0.00900333 -0.220331 -0.0451944 -0.00474751 -0.220059 -0.0450652 -0.00900333 -0.207484 -0.0468127 -0.00538801 -0.206903 -0.045752 -0.00509552 -0.207743 -0.0445556 -0.00477923 -0.208083 -0.0456221 -0.00900333 -0.206951 -0.047473 -0.00558531 -0.205703 -0.0478844 -0.00458169 -0.204406 -0.0464645 -0.00900333 -0.204607 -0.0462823 -0.00900333 -0.205812 -0.0509659 -0.0195033 -0.28447 -0.0508768 -0.0106207 -0.283854 -0.0478325 -0.00907271 -0.281182 -0.0487778 -0.00939658 -0.281416 -0.0487986 -0.00944777 -0.281425 -0.0488061 -0.00950333 -0.281428 -0.0501866 -0.00672713 -0.282455 -0.0506914 -0.00933519 -0.283292 -0.0505388 -0.0195033 -0.282978 -0.0493024 -0.00030333 -0.281681 -0.0495677 -0.00289825 -0.281861 -0.0495066 -0.00030333 -0.281816 0.0377798 -0.0275069 -0.0768638 0.0420587 -0.0254242 -0.0785906 0.0425755 -0.0184033 -0.0791516 0.0436866 -0.0242529 -0.0812247 0.0436866 -0.0184033 -0.0812247 0.0433392 -0.0236232 -0.0848419 0.0431761 -0.0184033 -0.0851221 0.0418878 -0.0184033 -0.0864732 0.0387325 -0.0184033 -0.0911991 -0.0349399 -0.0205346 -0.0838064 -0.033729 -0.0222984 -0.0820591 -0.0324014 -0.0184033 -0.0810358 -0.0323865 -0.0241123 -0.0810272 -0.0296532 -0.0184033 -0.0802218 -0.0301883 -0.0228994 -0.0967658 -0.0314851 -0.0184033 -0.114183 -0.0310262 -0.0184033 -0.111945 -0.0314905 -0.0218886 -0.114198 -0.0310262 -0.0220785 -0.111945 -0.0207693 -0.0233278 -0.119194 -0.022421 -0.0231741 -0.119772 -0.0224203 -0.0184033 -0.119772 -0.0238962 -0.023002 -0.120699 -0.0251354 -0.0228246 -0.12194 0.0340052 -0.0221612 -0.122283 0.0340117 -0.0184033 -0.118848 0.0330683 -0.0222098 -0.123766 0.0339284 -0.0184033 -0.122466 0.0325981 -0.0184033 -0.124204 0.0306248 -0.0184033 -0.125152 0.0265079 -0.0184033 -0.124067 0.027109 -0.0229801 -0.124522 0.026702 -0.0230403 -0.124231 0.0255613 -0.0184033 -0.122904 0.0255613 -0.0232338 -0.122904 0.0224474 -0.0235834 -0.119902 0.0213445 -0.0184033 -0.119424 -0.0251354 -0.0184033 -0.12194 -0.0325731 -0.0184033 -0.116193 0.0398645 -0.0184033 -0.0885386 0.0351993 -0.0184033 -0.0774199 0.0403019 -0.0184033 -0.0774063 -0.0304499 -0.0184033 -0.0942886 -0.0301883 -0.0184033 -0.0967658 0.0438753 -0.0184033 -0.0830819 0.0374863 -0.0184033 -0.0768701 -0.0325009 -0.0184033 -0.121925 -0.0273229 -0.0184033 -0.0805411 0.0216267 -0.0184033 -0.082251 -0.0190332 -0.0184033 -0.118998 0.00423585 -0.0184033 -0.084942 -0.0133366 -0.0184033 -0.0839964 -0.0344898 -0.0184033 -0.0829988 -0.035389 -0.0184033 -0.0851722 -0.0346877 -0.0184033 -0.0887299 -0.0334883 -0.0184033 -0.0899565 -0.031706 -0.0184033 -0.0916968 0.0284365 -0.0184033 -0.125102 0.0239237 -0.0184033 -0.120915 0.0343272 -0.0184033 -0.120314 0.0387325 -0.0238431 -0.0911991 0.0386656 -0.0238293 -0.0915042 0.0385987 -0.023817 -0.0918093 0.0336585 -0.0228805 -0.11434 0.0361284 -0.023369 -0.103076 -0.0273229 -0.0282841 -0.0805411 -0.0196231 -0.0283913 -0.0827542 -0.0037765 -0.0284397 -0.0849641 0.0351993 -0.0284428 -0.0774199 0.0200705 -0.0284551 -0.0826446 0.00423194 -0.0284474 -0.0849422 0.0441769 -0.00250333 -0.106747 0.0473519 -0.00250333 -0.105751 0.0487245 -0.00250333 -0.107123 0.0492268 -0.00250333 -0.108998 0.0477285 -0.00250333 -0.110298 0.0487244 -0.00250333 -0.110873 0.0467768 -0.00250333 -0.11125 0.0473518 -0.00250333 -0.112246 0.0454768 -0.00250333 -0.112748 0.0432252 -0.00250333 -0.110298 0.0428768 -0.00250333 -0.108998 0.0422292 -0.00250333 -0.110873 -0.0473277 -0.00250333 -0.215361 -0.047676 -0.00250333 -0.214061 -0.0473277 -0.00250333 -0.212761 -0.048826 -0.00250333 -0.21406 -0.0483236 -0.00250333 -0.212185 -0.046951 -0.00250333 -0.210813 -0.045076 -0.00250333 -0.210311 -0.043201 -0.00250333 -0.210813 -0.0428243 -0.00250333 -0.212761 -0.042476 -0.00250333 -0.214061 -0.0428244 -0.00250333 -0.215361 -0.0418285 -0.00250333 -0.215936 -0.0450761 -0.00250333 -0.216661 -0.0432011 -0.00250333 -0.217308 -0.0469511 -0.00250333 -0.217308 0.0109631 -0.00250333 -0.270083 0.0115382 -0.00250333 -0.269087 0.0129107 -0.00250333 -0.27046 0.0134131 -0.00250333 -0.272335 0.0122631 -0.00250333 -0.272335 0.0129107 -0.00250333 -0.27421 0.0109631 -0.00250333 -0.274586 0.00966308 -0.00250333 -0.274935 0.00966306 -0.00250333 -0.276085 0.00836308 -0.00250333 -0.274586 0.00778807 -0.00250333 -0.275582 0.00741143 -0.00250333 -0.273635 0.00641549 -0.00250333 -0.27421 0.00741146 -0.00250333 -0.271035 0.00641554 -0.00250333 -0.27046 0.00836314 -0.00250333 -0.270083 0.00778815 -0.00250333 -0.269087 0.00966314 -0.00250333 -0.269735 -0.0462002 -0.00250333 -0.273914 -0.0458518 -0.00250333 -0.275214 -0.0447018 -0.00250333 -0.275214 -0.0452043 -0.00250333 -0.277089 -0.0471519 -0.00250333 -0.277466 -0.0507035 -0.00250333 -0.276514 -0.0516995 -0.00250333 -0.277089 -0.0522018 -0.00250333 -0.275214 -0.0507035 -0.00250333 -0.273914 -0.0471518 -0.00250333 -0.272962 -0.0418908 -0.00250333 -0.095655 -0.0399432 -0.00250333 -0.0952784 -0.0386432 -0.00250333 -0.0949301 -0.0367682 -0.00250333 -0.0942825 -0.0363916 -0.00250333 -0.0962301 -0.0353956 -0.00250333 -0.0956551 -0.0363916 -0.00250333 -0.0988301 -0.0348933 -0.00250333 -0.0975301 -0.0367683 -0.00250333 -0.100778 -0.0418909 -0.00250333 -0.099405 -0.0408949 -0.00250333 -0.0988301 0.0305079 -0.00250333 -0.168298 0.0301596 -0.00250333 -0.166998 0.029512 -0.00250333 -0.165123 0.0314596 -0.00250333 -0.164747 0.0327596 -0.00250333 -0.164398 0.0346346 -0.00250333 -0.163751 0.0350113 -0.00250333 -0.165698 0.0365096 -0.00250333 -0.166998 0.0360072 -0.00250333 -0.168873 0.0340596 -0.00250333 -0.16925 0.0327596 -0.00250333 -0.169598 0.0327595 -0.00250333 -0.170748 0.0314596 -0.00250333 -0.16925 -0.0445161 -0.00250333 -0.156817 -0.0456661 -0.00250333 -0.156817 -0.0441677 -0.00250333 -0.155517 -0.043216 -0.00250333 -0.154566 -0.041916 -0.00250333 -0.154217 -0.041916 -0.00250333 -0.153067 -0.040041 -0.00250333 -0.15357 -0.0396644 -0.00250333 -0.155518 -0.0393161 -0.00250333 -0.156818 -0.0406161 -0.00250333 -0.159069 -0.0419161 -0.00250333 -0.159418 -0.0419161 -0.00250333 -0.160568 -0.0432161 -0.00250333 -0.159069 -0.0437911 -0.00250333 -0.160065 0.0186058 -0.00250333 -0.226246 0.0182292 -0.00250333 -0.224298 0.0178809 -0.00250333 -0.222998 0.0182292 -0.00250333 -0.221698 0.0186059 -0.00250333 -0.21975 0.0204809 -0.00250333 -0.219248 0.0204809 -0.00250333 -0.220398 0.0217809 -0.00250333 -0.220746 0.0227325 -0.00250333 -0.221698 0.0223559 -0.00250333 -0.21975 0.0227325 -0.00250333 -0.224298 0.0237284 -0.00250333 -0.224873 0.0217808 -0.00250333 -0.22525 0.0621547 0.00239667 -0.0278986 0.0632047 0.00239667 -0.02818 0.0638672 0.00239667 -0.0270325 0.0639733 0.00239667 -0.0289486 0.0651208 0.00239667 -0.0282861 0.0655796 0.00239667 -0.0299986 0.0638671 0.00239667 -0.0329648 0.0611046 0.00239667 -0.0318172 0.0600546 0.00239667 -0.0299986 0.060336 0.00239667 -0.0289486 0.0591885 0.00239667 -0.0282861 0.0604422 0.00239667 -0.0270324 -0.0311105 0.00239667 -0.0219639 -0.032258 0.00239667 -0.0247264 -0.0311106 0.00239667 -0.0253889 -0.0340767 0.00239667 -0.0271014 -0.0351267 0.00239667 -0.025495 -0.0357892 0.00239667 -0.0266425 -0.0361767 0.00239667 -0.0236763 -0.0375017 0.00239667 -0.0236763 -0.0357891 0.00239667 -0.0207102 -0.0351267 0.00239667 -0.0218577 -0.00379787 0.00239667 0.0435407 -0.00313536 0.00239667 0.0446881 -0.00188173 0.00239667 0.0434345 -0.00188178 0.00239667 0.0400095 -0.00313543 0.00239667 0.0387559 -0.00589792 0.00239667 0.0399034 -0.00694789 0.00239667 0.041722 -0.00484787 0.00239667 0.043822 0.0563823 0.00239667 0.0289676 0.0564884 0.00239667 0.0270515 0.0564884 0.00239667 0.0249515 0.0580947 0.00239667 0.0260015 0.0576358 0.00239667 0.024289 0.0563822 0.00239667 0.0230353 0.0536197 0.00239667 0.0241829 0.0528511 0.00239667 0.0249515 0.0517036 0.00239667 0.024289 0.0512447 0.00239667 0.0260015 0.0517036 0.00239667 0.027714 0.0529573 0.00239667 0.0289677 0.0546697 0.00239667 0.0281015 -0.0511731 -0.023621 -0.279571 -0.0486999 -0.0266027 -0.279707 -0.0525394 -0.0200033 -0.279495 -0.0504457 -0.0233194 -0.270597 -0.0462946 -0.0280009 -0.271265 -0.045334 -0.0287389 -0.271969 -0.0440241 -0.0296156 -0.274411 -0.0440343 -0.0200033 -0.274357 -0.0441555 -0.0200033 -0.276552 -0.0453027 -0.0200033 -0.278428 -0.0456101 -0.0290232 -0.278703 -0.047202 -0.0200033 -0.279537 0.0143528 -0.0200033 -0.268756 0.0115081 -0.0256353 -0.268132 0.00869932 -0.027169 -0.27673 0.0114669 -0.0240783 -0.277337 -0.0388913 -0.00800333 -0.102023 -0.0406477 -0.0147999 -0.0929126 -0.0419002 -0.00800333 -0.0928434 -0.0383952 -0.018804 -0.0930369 -0.0382884 -0.0189404 -0.0930441 -0.0369488 -0.0202464 -0.0933613 -0.0341653 -0.0216869 -0.0970856 -0.0347717 -0.0215132 -0.0952364 -0.0351594 -0.00800333 -0.0946818 -0.0341853 -0.0216274 -0.0981439 -0.034428 -0.0214813 -0.0991053 -0.0346254 -0.0213754 -0.0995565 -0.0388913 -0.0180159 -0.102023 -0.0373934 -0.00800333 -0.101853 -0.0457317 -0.00800333 -0.151475 -0.0387669 -0.00800333 -0.160032 -0.0396644 -0.00800333 -0.158118 -0.0396644 -0.00800333 -0.155518 -0.041668 -0.00800333 -0.152324 -0.043216 -0.00800333 -0.154566 -0.0448196 -0.00800333 -0.15215 -0.04552 -0.00800333 -0.151825 -0.0441677 -0.00800333 -0.155517 -0.0445161 -0.00800333 -0.156817 -0.0461661 -0.00800333 -0.16164 -0.0441678 -0.00800333 -0.158117 -0.0459601 -0.00800333 -0.161393 -0.0458382 -0.00800333 -0.161303 -0.0455946 -0.00800333 -0.161189 -0.0452174 -0.00800333 -0.161142 -0.0419161 -0.00800333 -0.159418 -0.0406662 -0.00800333 -0.16114 -0.0421641 -0.00800333 -0.161311 -0.0436374 -0.0117884 -0.152216 -0.041668 -0.0151962 -0.152324 -0.0402769 -0.016891 -0.152627 -0.0394557 -0.0175835 -0.15305 -0.040198 -0.00800333 -0.152658 -0.0388007 -0.0180266 -0.15357 -0.0384322 -0.00800333 -0.153969 -0.0381469 -0.0183935 -0.154359 -0.0374268 -0.0186907 -0.157128 -0.0374985 -0.00800333 -0.15596 -0.0377291 -0.0185921 -0.155168 -0.0376197 -0.00800333 -0.158156 -0.0384929 -0.0180874 -0.159738 -0.0375809 -0.0185969 -0.158024 -0.0421641 -0.0146357 -0.161311 -0.0407701 -0.0163726 -0.161169 -0.0392328 -0.0176238 -0.16043 -0.044828 -0.0124761 -0.209567 -0.044828 -0.00800333 -0.209567 -0.0433579 -0.00800333 -0.209901 -0.0415922 -0.00800333 -0.211212 -0.0417531 -0.0160943 -0.211026 -0.0407797 -0.00800333 -0.215399 -0.0406585 -0.00800333 -0.213203 -0.041951 -0.0164113 -0.217298 -0.0453241 -0.00800333 -0.218554 -0.0453241 -0.0125382 -0.218554 -0.0449245 -0.0131834 -0.218558 -0.0432686 -0.0152814 -0.218182 -0.0438261 -0.00800333 -0.218383 0.0228724 -0.0104349 -0.218916 0.023949 -0.00800333 -0.219152 0.0179127 -0.0155953 -0.227042 0.0171555 -0.0164189 -0.226876 0.0210341 -0.0119723 -0.227726 0.0195171 -0.00800333 -0.227394 0.0195171 -0.0127586 -0.227394 0.0189204 -0.0139297 -0.227263 0.0183808 -0.0148891 -0.227145 0.0182674 -0.0150729 -0.22712 0.0369267 -0.00800333 -0.163305 0.0337234 -0.00800333 -0.162603 0.0487064 -0.00800333 -0.11496 0.0508577 -0.00800333 -0.105026 0.0498861 -0.00800333 -0.109967 0.0477285 -0.00800333 -0.107698 0.0467769 -0.00800333 -0.106747 0.0441769 -0.00800333 -0.106747 0.0432252 -0.00800333 -0.107698 0.04145 -0.00800333 -0.10699 0.0428768 -0.00800333 -0.108998 0.0432252 -0.00800333 -0.110298 0.040979 -0.00800333 -0.109138 0.0454768 -0.00800333 -0.111598 0.0431154 -0.00800333 -0.112829 0.0445131 -0.00800333 -0.113394 0.0467768 -0.00800333 -0.11125 0.0479284 -0.00800333 -0.114143 0.0498752 -0.00800333 -0.105356 0.0464406 -0.00800333 -0.104603 0.0464267 -0.0154523 -0.113814 0.0476835 -0.00988399 -0.114089 0.0122883 -0.000303196 -0.267004 0.0117961 -0.00900333 -0.267047 0.0135889 -0.000303083 -0.266484 0.0139421 -0.00900333 -0.266173 -0.0405385 -0.000299497 -0.103667 -0.0404852 -0.00900333 -0.103996 -0.0425979 -0.000294259 -0.105452 -0.0420069 -0.00900333 -0.105726 -0.044988 -0.00900333 -0.280113 -0.0478325 -0.00030333 -0.281182 -0.044988 -0.00030333 -0.280113 -0.043032 -0.00900333 -0.277788 -0.0434352 -0.00030333 -0.271923 -0.0430107 -0.00900333 -0.208427 -0.0405293 -0.00900333 -0.210145 -0.0405293 -0.00030333 -0.210145 -0.0391985 -0.00030333 -0.212854 -0.036202 -0.00900333 -0.158648 -0.036035 -0.00900333 -0.155629 -0.0360062 -0.00030333 -0.155781 -0.0370721 -0.00030333 -0.153277 -0.0373616 -0.00900333 -0.152912 -0.0391348 -0.00030333 -0.151501 -0.0410273 -0.00900333 -0.150884 -0.0545232 -0.0195033 -0.299928 -0.0543255 -0.019155 -0.296404 -0.0539615 -0.0164637 -0.289918 -0.0517291 -0.0148183 -0.287815 -0.051694 -0.0142313 -0.2872 -0.053809 -0.0142315 -0.2872 -0.0535324 -0.00501261 -0.282273 -0.0498555 -0.00150333 -0.281928 -0.0506883 -0.00670545 -0.282696 -0.0536831 -0.0114977 -0.284957 0.0121813 -0.00030333 -0.281061 0.0133166 -0.0196284 -0.278755 0.0128667 -0.0195033 -0.279669 0.0108788 -0.00465335 -0.266971 0.0108863 -0.00030333 -0.266973 0.00863891 -0.00900333 -0.266931 0.00863891 -0.00030333 -0.266931 0.00651707 -0.00030333 -0.267823 0.0049463 -0.00030333 -0.269506 0.0049463 -0.00900333 -0.269506 0.00420173 -0.00030333 -0.271684 -0.0288773 -0.00900333 -0.0269706 -0.0371655 -0.00030333 -0.043267 -0.038013 -0.00900333 -0.0493592 0.0343086 -0.00900333 0.00244373 0.0311484 -0.00900333 0.0145915 0.0133577 -0.00030333 0.0317009 0.0150002 -0.00030333 0.0309572 0.0133577 -0.00900333 0.0317009 0.0225085 -0.00030333 0.0260121 0.00109589 -0.00030333 0.0343846 -0.0113125 -0.00900333 0.0324906 -0.0193443 -0.00030333 0.028451 -0.0222153 -0.00030333 0.026271 -0.0301609 -0.00030333 0.0165539 -0.0260552 -0.00030333 0.0224684 -0.0340915 -0.00030333 0.00463316 -0.0343089 -0.00030333 -0.00256336 -0.0334838 -0.00030333 -0.00790418 -0.0334838 -0.00900333 -0.00790418 0.0354869 -0.00030333 -0.0018182 0.0558641 -0.000306154 -0.0791709 0.0565726 -0.00373609 -0.0758792 0.015107 -0.000302988 -0.264193 0.0186882 -0.00502961 -0.246312 0.015072 -0.00900333 -0.26415 0.0176661 -0.00900333 -0.249348 0.0197219 -0.00900333 -0.23645 0.0208205 -0.00479835 -0.236556 0.0214619 -0.00547934 -0.232912 0.0220803 -0.000292048 -0.233113 -0.0497086 -0.0049682 -0.238856 -0.0501957 -0.00900333 -0.24824 -0.0515823 -0.00900333 -0.262981 -0.0515823 -0.00465333 -0.262981 -0.0515823 -0.00030333 -0.262981 -0.0294859 -0.0350033 0.0684328 -0.0442731 -0.0350033 0.064233 -0.0380414 -0.0350033 -0.0757327 0.0838105 -0.0350033 1.12302e-06 0.0774191 -0.0350033 1.20485e-06 -0.0707071 -0.0350033 0.0442723 -0.0733998 -0.0350033 0.0423781 -0.081194 -0.0350033 0.0243098 -0.0707073 -0.0350033 0.0294853 -0.0262427 -0.0350033 0.0108707 -0.0294864 -0.0350033 0.0294847 -0.0284047 -0.0350033 2.55959e-06 -0.029487 -0.0350033 -0.0178665 -0.026243 -0.0350033 -0.0108657 -0.0200868 -0.0350033 -0.0200794 0.0200769 -0.0350033 -0.0200799 0.0283953 -0.0350033 1.83244e-06 0.0387905 -0.0350033 -0.0178674 0.0262334 -0.0350033 -0.0108663 -0.0645501 -0.0350033 0.0549245 -0.0653257 -0.0350033 0.0499149 -0.048473 -0.0350033 0.0684331 -0.0496331 -0.0350033 0.0687014 -0.046749 -0.0350033 0.0683916 -0.0467115 -0.0350033 0.0707202 -0.044273 -0.0350033 0.0707057 -0.032668 -0.0350033 0.0761698 -0.031618 -0.0350033 0.0722511 -0.033718 -0.0350033 0.0722511 -0.034768 -0.0350033 0.0740698 -0.00314176 -0.0350033 0.0807826 -0.00342312 -0.0350033 0.0797326 -0.00419179 -0.0350033 0.0789639 -0.030568 -0.0350033 0.0740698 -0.0294859 -0.0350033 0.0707055 -0.0289899 -0.0350033 0.0796415 -0.00984246 -0.0350033 0.0841793 -0.00629174 -0.0350033 0.0826013 -0.00524173 -0.0350033 0.0828826 0.0484654 -0.0350033 0.0684318 0.0486279 -0.0350033 0.0694099 0.0547734 -0.0350033 0.06467 0.0496255 -0.0350033 0.0687001 0.0565629 -0.0350033 0.0565683 0.0694347 -0.0350033 0.0449278 0.0706989 -0.0350033 0.0442705 0.0688749 -0.0350033 0.04938 0.0684262 -0.0350033 0.0484705 0.071024 -0.0350033 0.0462352 0.0706987 -0.0350033 0.0294834 0.0683847 -0.0350033 0.0467465 0.0730129 -0.0350033 0.0308469 0.0733915 -0.0350033 0.0423763 0.0758816 -0.0350033 0.0337155 0.0761629 -0.0350033 0.0326655 0.0828758 -0.0350033 0.00523926 0.0834576 -0.0350033 -0.0147156 0.0825944 -0.0350033 0.00418927 0.0818257 -0.0350033 0.00342062 0.0786757 -0.0350033 0.00523932 0.0774195 -0.0350033 0.0294834 0.0789571 -0.0350033 0.00628931 0.0797258 -0.0350033 0.00705796 0.0807758 -0.0350033 0.00733929 0.0793833 -0.0350033 0.029669 0.0774189 -0.0350033 -0.0178679 0.0710953 -0.0350033 -0.046121 0.0706978 -0.0350033 -0.0387941 0.0694286 -0.0350033 -0.048594 0.0684249 -0.0350033 -0.0484679 0.0671351 -0.0350033 -0.0488606 0.0565614 -0.0350033 -0.0565653 0.0642664 -0.0350033 -0.0496292 0.0484637 -0.0350033 -0.0684287 0.0467396 -0.0350033 -0.0683872 0.0487558 -0.0350033 -0.0693158 0.045971 -0.0350033 -0.0691558 0.044921 -0.0350033 -0.0694371 0.0387899 -0.0350033 -0.0684285 0.0316087 -0.0350033 -0.075884 0.0178634 -0.0350033 -0.0774218 0.03084 -0.0350033 -0.0730154 0.0316087 -0.0350033 -0.0722467 0.0326587 -0.0350033 -0.0719654 0.0344773 -0.0350033 -0.0751154 0.0380301 -0.0350033 -0.0757337 0.0347587 -0.0350033 -0.0740654 0.0344774 -0.0350033 -0.0730154 0.0387898 -0.0350033 -0.0707013 0.00628245 -0.0350033 -0.0789596 0.00418245 -0.0350033 -0.0789596 0.0337087 -0.0350033 -0.0758841 0.00341379 -0.0350033 -0.0797282 0.0052324 -0.0350033 -0.0828782 0.0041824 -0.0350033 -0.0825969 -0.0442748 -0.0350033 -0.0707002 -0.0460061 -0.0350033 -0.0711767 -0.0442748 -0.0350033 -0.0684275 -0.0484748 -0.0350033 -0.0684274 -0.0487669 -0.0350033 -0.0693145 -0.049636 -0.0350033 -0.0642689 -0.0565722 -0.0350033 -0.0565639 -0.0627698 -0.0350033 -0.0569461 -0.068394 -0.0350033 -0.0467421 -0.0684355 -0.0350033 -0.0484661 -0.0694391 -0.0350033 -0.0485922 -0.0679853 -0.0350033 -0.0506061 -0.0711058 -0.0350033 -0.0461192 -0.0752282 -0.0350033 -0.0390361 -0.0730223 -0.0350033 -0.0344798 -0.0740723 -0.0350033 -0.0347612 -0.0751223 -0.0350033 -0.0344798 -0.0778239 -0.0350033 -0.0335646 -0.0828299 -0.0350033 -0.0179575 -0.0828851 -0.0350033 -0.00523487 -0.0707079 -0.0350033 -0.017866 -0.0807851 -0.0350033 -0.0073349 -0.0847547 -0.0350033 3.28098e-06 -0.0484731 -0.0350033 0.064233 -0.0565708 -0.0350033 0.0484721 -0.0663758 -0.0350033 0.0459963 -0.0671444 -0.0350033 0.046765 -0.065244 -0.0350033 -0.0449235 -0.0642355 -0.0350033 -0.0484662 -0.0655253 -0.0350033 -0.0438735 -0.0484746 -0.0350033 -0.056564 -0.0457174 -0.0350033 -0.0653189 -0.0442746 -0.0350033 -0.056564 -0.0459988 -0.0350033 -0.0663689 -0.0478174 -0.0350033 -0.0674189 -0.0488674 -0.0350033 -0.0671375 0.043871 -0.0350033 -0.0691558 0.0431023 -0.0350033 -0.0683871 0.042821 -0.0350033 -0.0673371 0.047021 -0.0350033 -0.0673372 0.0634978 -0.0350033 -0.0488605 0.0634978 -0.0350033 -0.0467605 0.0632164 -0.0350033 -0.0478105 0.0652347 -0.0350033 0.0449279 0.0565628 -0.0350033 0.0484707 0.0673347 -0.0350033 0.0470279 0.065516 -0.0350033 0.0438779 0.0565627 -0.0350033 0.0442707 0.0662847 -0.0350033 0.0431092 0.0673347 -0.0350033 0.0428279 0.0684259 -0.0350033 0.0294835 0.0387916 -0.0350033 0.0642319 0.0459894 -0.0350033 0.0642733 0.0478081 -0.0350033 0.0674233 0.047808 -0.0350033 0.0632233 -0.0565721 -0.0350033 -0.0484663 -0.0294874 -0.0350033 -0.0484666 -5.16344e-06 -0.0350033 -0.0387932 -5.28728e-06 -0.0350033 -0.048467 -0.0294877 -0.0350033 -0.0684277 -5.54282e-06 -0.0350033 -0.068428 -0.0294877 -0.0350033 -0.0707004 -5.57192e-06 -0.0350033 -0.0707008 -0.0294878 -0.0350033 -0.0774212 -5.73978e-06 -0.0350033 -0.083813 -5.75174e-06 -0.0350033 -0.0847478 0.0108632 -0.0350033 -0.0262361 -5.39095e-06 -0.0350033 -0.0565646 0.0178635 -0.0350033 -0.0684283 0.0178635 -0.0350033 -0.070701 -5.65795e-06 -0.0350033 -0.0774216 0.0178639 -0.0350033 -0.0387934 0.0178638 -0.0350033 -0.0484672 0.0387901 -0.0350033 -0.0484675 0.0178637 -0.0350033 -0.0565648 0.03879 -0.0350033 -0.0565651 -0.0484744 -0.0350033 -0.0387926 -0.0442744 -0.0350033 -0.0387927 -0.0484745 -0.0350033 -0.0484664 -0.0478174 -0.0350033 -0.0632189 0.0706981 -0.0350033 -0.0178678 0.0684251 -0.0350033 -0.0387941 0.0565616 -0.0350033 -0.0387939 0.0565619 -0.0350033 -0.0178676 -0.0294868 -0.0350033 2.57344e-06 -0.0442741 -0.0350033 -0.0178663 -0.0442745 -0.0350033 -0.0484665 -0.0294873 -0.0350033 -0.0387928 -0.0294875 -0.0350033 -0.0565642 -0.0445714 -0.0350033 -0.0720837 0.0706983 -0.0350033 1.29088e-06 0.0684253 -0.0350033 -0.0178677 0.0684256 -0.0350033 1.31998e-06 -0.0692986 -0.0350033 0.0487968 -0.0684343 -0.0350033 0.0484723 -0.0710321 -0.0350033 0.046237 -0.0721841 -0.0350033 0.0444172 -0.0653258 -0.0350033 0.0457149 -0.0642343 -0.0350033 0.0442722 -0.0684343 -0.0350033 0.0442723 -0.0707076 -0.0350033 3.10115e-06 -0.0846112 -0.0350033 0.00493105 -0.0684349 -0.0350033 3.07205e-06 -0.0684345 -0.0350033 0.0294852 -0.0642345 -0.0350033 0.0294852 -4.10005e-06 -0.0350033 0.0442714 0.017865 -0.0350033 0.0442712 -4.28936e-06 -0.0350033 0.0294843 0.0178648 -0.0350033 0.0294841 -4.30321e-06 -0.0350033 0.0284022 0.0387911 -0.0350033 0.0294838 0.0200774 -0.0350033 0.0200838 0.0262337 -0.0350033 0.0108701 -0.0565707 -0.0350033 0.0565697 -0.0484732 -0.0350033 0.0565696 -0.056572 -0.0350033 -0.0387925 -0.0484741 -0.0350033 -0.0178662 -0.0442739 -0.0350033 2.76275e-06 -0.0442735 -0.0350033 0.0294849 0.017865 -0.0350033 0.0484712 0.0387915 -0.0350033 0.0565685 0.0484653 -0.0350033 0.0565684 0.0387914 -0.0350033 0.0484709 0.0387913 -0.0350033 0.0442709 0.0484649 -0.0350033 0.0294837 0.0387907 -0.0350033 1.69936e-06 0.0484645 -0.0350033 1.57552e-06 0.0387902 -0.0350033 -0.0387937 0.0484641 -0.0350033 -0.0387938 0.0484639 -0.0350033 -0.0484676 0.044921 -0.0350033 -0.0652371 0.0484652 -0.0350033 0.0484708 0.0484651 -0.0350033 0.0442708 0.0565625 -0.0350033 0.0294836 0.0565621 -0.0350033 1.47185e-06 0.0484643 -0.0350033 -0.0178675 0.0565615 -0.0350033 -0.0484677 0.0484638 -0.0350033 -0.0565652 0.0544708 -0.0350033 -0.0649208 -0.0438804 -0.0350033 0.0655229 -0.0547811 -0.0350033 0.0646714 -0.0568999 -0.0350033 0.0628153 -0.0428303 -0.0350033 0.0673415 -0.0484733 -0.0350033 0.048472 -0.0632258 -0.0350033 0.0478149 -0.0565709 -0.0350033 0.0442721 -0.068394 -0.0350033 -0.0431048 -0.067344 -0.0350033 -0.0428235 -0.0642354 -0.0350033 -0.0387924 -0.0565717 -0.0350033 -0.0178661 -0.0484739 -0.0350033 2.81651e-06 -0.0294863 -0.0350033 0.0442718 -0.0294862 -0.0350033 0.0484718 -4.04629e-06 -0.0350033 0.0484714 0.0178651 -0.0350033 0.0565688 -0.0431117 -0.0350033 0.0683915 -0.0684354 -0.0350033 -0.0387923 -0.0642351 -0.0350033 -0.017866 -0.0642349 -0.0350033 3.01828e-06 -0.0565715 -0.0350033 2.92018e-06 -0.0484735 -0.0350033 0.029485 -0.0442733 -0.0350033 0.044272 -0.0294861 -0.0350033 0.0565694 -3.94262e-06 -0.0350033 0.056569 0.0178652 -0.0350033 0.0642322 0.0387916 -0.0350033 0.0684319 -0.0449303 -0.0350033 0.0694415 -3.76165e-06 -0.0350033 0.0707052 -3.79075e-06 -0.0350033 0.0684324 0.0465671 -0.0350033 0.0708092 0.0387917 -0.0350033 0.0707047 0.0178653 -0.0350033 0.0707049 0.0178653 -0.0350033 0.0684322 -3.84452e-06 -0.0350033 0.0642324 -0.029486 -0.0350033 0.0642328 -0.0442732 -0.0350033 0.0565696 -0.0442733 -0.0350033 0.048472 -0.0484733 -0.0350033 0.044272 -0.0565711 -0.0350033 0.0294851 -0.0684351 -0.0350033 -0.017866 -0.0707081 -0.0350033 -0.0387923 -0.0463052 -0.00994435 -0.176197 0.0346307 -0.01719 -0.161818 0.0123584 -0.0194787 -0.221333 -0.0316431 -0.0225641 -0.111936 -0.0321077 -0.023148 -0.0946519 -0.031465 -0.0233074 -0.0948675 -0.0351615 -0.0218393 -0.101469 -0.0316094 -0.0214746 -0.142625 -0.0266794 -0.0230179 -0.123742 -0.024803 -0.0233207 -0.122271 -0.0222494 -0.0236716 -0.120243 0.00113256 -0.024441 -0.119525 -0.00291838 -0.0229668 -0.149265 0.0323549 -0.0228179 -0.125075 0.0259341 -0.0236076 -0.124204 0.0195104 -0.0224387 -0.150604 0.0251635 -0.0237315 -0.123186 0.0119912 -0.022789 -0.150451 0.0340775 -0.0232271 -0.11662 0.0342225 -0.0233733 -0.114486 0.0428278 -0.0237324 -0.0903046 0.0391665 -0.0243093 -0.0919522 0.0402615 -0.0225622 -0.109551 0.0420573 -0.0225084 -0.105047 0.0430931 -0.0222416 -0.10433 0.0451102 -0.0232317 -0.0891866 0.0442076 -0.0218555 -0.103878 0.0466283 -0.0204691 -0.103684 0.051344 -0.0201779 -0.0857498 0.0501065 -0.0139692 -0.104388 0.0504829 -0.0121743 -0.104469 0.0547737 -0.0137163 -0.0836001 0.0557887 -0.00824826 -0.0829261 0.0563502 -0.000309951 -0.0825456 0.0247028 -0.00623374 -0.223016 0.0255594 -0.000314869 -0.223133 0.0232676 -0.0120679 -0.218008 0.0224211 -0.0132842 -0.217826 0.0159836 -0.0195075 -0.204118 0.0156186 -0.0179543 -0.221777 0.0163897 -0.0177353 -0.220052 0.021952 -0.017006 -0.204511 -0.000882777 -0.0224334 -0.219528 -0.010061 -0.02194 -0.20171 -0.0122759 -0.0230033 -0.217974 -0.00444656 -0.0227488 -0.219042 -0.0172085 -0.0229012 -0.217302 -0.0247311 -0.0222866 -0.216276 -0.0293751 -0.0208533 -0.19835 -0.03175 -0.021049 -0.215319 -0.0347264 -0.0202487 -0.214914 -0.0438333 -0.0150526 -0.208889 -0.0420418 -0.0165811 -0.209894 -0.0413308 -0.01687 -0.19588 -0.0355877 -0.0194698 -0.197083 -0.0407741 -0.0174723 -0.211379 -0.0368678 -0.0195066 -0.214622 -0.0437564 -0.0148502 -0.195357 -0.0455694 -0.0130802 -0.208542 -0.0481858 -0.00645976 -0.194321 -0.047239 -0.00674372 -0.175761 -0.0432263 -0.000314468 -0.0901193 -0.0458756 -0.000310807 -0.137961 -0.0396963 -0.0186774 -0.103026 -0.0382193 -0.0200549 -0.102949 -0.0382986 -0.019268 -0.140714 -0.0366222 -0.0211037 -0.102454 -0.0341151 -0.021585 -0.119744 -0.0479448 -0.00030886 -0.175397 -0.0457873 -0.00800333 -0.151103 -0.0460461 -0.00800333 -0.156598 -0.0452893 -0.00734301 -0.138274 -0.0428488 -0.00800333 -0.0917934 -0.0427246 -0.00850392 -0.0903583 -0.0419043 -0.0138481 -0.0918642 -0.0408773 -0.0168048 -0.0919362 -0.0406924 -0.017165 -0.0912916 -0.0404128 -0.0175683 -0.1784 -0.0369372 -0.0195994 -0.155535 -0.0375115 -0.0189824 -0.17936 -0.0444908 -0.010888 -0.138651 -0.0445594 -0.0120411 -0.151182 -0.043168 -0.0142412 -0.139179 -0.0423954 -0.0158187 -0.151315 -0.0411211 -0.0171533 -0.13987 -0.0399919 -0.018073 -0.151923 -0.0350343 -0.0206009 -0.141651 -0.0331933 -0.0217797 -0.122031 0.0372874 -0.0176232 -0.150564 0.0403423 -0.0110092 -0.150219 0.0370401 -0.0126636 -0.162325 0.0356885 -0.00800333 -0.17328 0.0259582 -0.0178401 -0.187456 0.0345535 -0.0123547 -0.173045 0.0322927 -0.0165183 -0.172569 0.0298854 -0.0184773 -0.171526 0.0295971 -0.0186542 -0.171305 0.030664 -0.0208516 -0.150615 0.0342011 -0.0196602 -0.150605 0.0392376 -0.0145128 -0.150417 0.0449867 -0.01945 -0.114547 0.0477182 -0.0137973 -0.115129 0.0410465 -0.00739093 -0.150046 0.0486971 -0.00800333 -0.115337 0.0241445 -0.00800333 -0.22294 0.0251987 -0.00800333 -0.218415 0.0328728 -0.0067827 -0.186684 0.0306981 -0.0131386 -0.187098 0.0264547 -0.0124728 -0.204757 0.0287323 -0.0158746 -0.187304 0.0245049 -0.0150306 -0.204665 0.00958171 -0.0208396 -0.203666 0.00304977 -0.0215341 -0.203142 -0.0080703 -0.0219776 -0.18709 0.019485 -0.020082 -0.187723 0.0269915 -0.0216119 -0.150623 0.0126401 -0.0211738 -0.18794 0.00570895 -0.0216959 -0.187997 -0.0214791 -0.0217658 -0.184279 -0.036877 -0.0195768 -0.157889 -0.0230091 -0.0215675 -0.199585 -0.0174538 -0.0229007 -0.146427 -0.0280294 -0.0212026 -0.182383 -0.0245867 -0.022496 -0.144582 -0.0344306 -0.01998 -0.180363 -0.0429365 -0.0155451 -0.177528 -0.0457017 -0.012345 -0.194918 -0.044893 -0.0129314 -0.176789 -0.045061 -0.0117518 -0.162172 -0.0463017 -0.00800333 -0.162093 0.022983 -0.00800333 -0.228154 0.0251511 -0.00421534 -0.223077 0.0204067 -0.0045039 -0.244328 0.0175254 -0.0165317 -0.243934 0.0175352 -0.016796 -0.245992 0.0215978 -0.00850336 -0.234163 0.0182256 -0.015432 -0.22711 0.0197972 -0.00873125 -0.244239 0.0198914 -0.0122725 -0.233915 0.0187978 -0.0127699 -0.244095 0.017985 -0.00919513 -0.254444 0.0176736 -0.0136335 -0.254406 0.0165957 -0.00965371 -0.26234 0.0148264 -0.00030333 -0.272132 0.0177842 -0.0154884 -0.231615 0.0172851 -0.0179273 -0.254355 0.0151498 -0.0222363 -0.267805 0.015482 -0.020843 -0.267903 0.0156177 -0.0196454 -0.267678 0.00951454 -0.0284898 -0.266804 0.00637376 -0.0290963 -0.260897 0.00573184 -0.0301515 -0.266295 -5.11821e-06 -0.0318278 -0.270109 0.0023188 -0.0314483 -0.270426 0.00344582 -0.031182 -0.27058 -0.0348929 -0.0320017 -0.265353 -0.0466714 -0.0282916 -0.263748 -0.0444315 -0.0289065 -0.259465 -0.0470437 -0.0280106 -0.263697 -0.049887 -0.0251817 -0.26331 -0.0486118 -0.0256982 -0.258909 -0.0523688 -0.0166926 -0.258411 -0.0438734 -0.0157251 -0.219115 -0.0419816 -0.0171335 -0.218049 -0.0400652 -0.0180072 -0.214186 -0.0408238 -0.0194974 -0.225721 -0.023967 -0.0240436 -0.228031 -0.0221745 -0.0225667 -0.216625 -0.0441803 -0.016832 -0.225224 -0.0369272 -0.0214051 -0.226278 0.0176618 -0.0155754 -0.233627 0.0167735 -0.0181729 -0.243846 0.0153697 -0.02004 -0.243668 0.0112899 -0.0205742 -0.232845 0.00723998 -0.0221305 -0.232309 0.00256457 -0.0255736 -0.241919 0.00300995 -0.0231747 -0.23173 -0.0162786 -0.0262984 -0.239329 -0.0148639 -0.0245145 -0.229257 -0.0257084 -0.0260573 -0.238053 -0.0327505 -0.022683 -0.226856 0.00755174 -0.0212614 -0.226655 0.00344641 -0.0222712 -0.226095 0.0149776 -0.0183168 -0.23331 0.0151946 -0.0178525 -0.227652 0.0115023 -0.0198432 -0.227179 0.00904412 -0.0205829 -0.220881 0.00409659 -0.0217187 -0.220206 -0.00581466 -0.0242529 -0.2305 -0.0195407 -0.0313156 -0.262852 0.000594778 -0.031222 -0.265589 0.0111552 -0.0269598 -0.261566 0.0142452 -0.0241509 -0.267482 0.015327 -0.02174 -0.267636 0.0164037 -0.0189762 -0.262318 0.0160772 -0.0210265 -0.262271 0.0149493 -0.0233819 -0.262108 0.00125796 -0.0300635 -0.260191 -0.00790254 -0.0283026 -0.250861 -0.0507632 -0.0206101 -0.253161 -0.0514591 -0.0212889 -0.258532 -0.0478504 -0.0248778 -0.253541 -0.0436338 -0.0279352 -0.254094 -0.0387437 -0.0296764 -0.254744 -0.0395425 -0.0307808 -0.260121 -0.0344132 -0.0313594 -0.260818 -0.0286259 -0.0301135 -0.256123 -0.0293868 -0.0313398 -0.261507 -0.0494567 -0.0195318 -0.245262 -0.0336317 -0.0301626 -0.255435 -0.0177078 -0.0282817 -0.249525 -0.0188032 -0.0300587 -0.257466 -0.0088848 -0.0300943 -0.258816 -0.00959352 -0.0313308 -0.264206 -0.00304591 -0.0320009 -0.269695 0.0164981 -0.0188851 -0.261614 0.0168493 -0.0198668 -0.254296 0.0156292 -0.0220883 -0.254123 0.0117851 -0.025403 -0.253573 0.0115854 -0.0228561 -0.24316 0.00706871 -0.0273494 -0.252909 0.00718842 -0.0246122 -0.242558 0.00206284 -0.0282279 -0.252215 -0.00683838 -0.0261709 -0.240622 -0.0274378 -0.0283042 -0.248198 -0.032368 -0.0283132 -0.247521 -0.0304036 -0.0257743 -0.237419 -0.0373855 -0.0278823 -0.246846 -0.0422084 -0.0263155 -0.246209 -0.0350862 -0.0251589 -0.236793 -0.0396012 -0.0237413 -0.236185 -0.0464339 -0.0235142 -0.245658 -0.0436817 -0.021373 -0.235627 -0.0468726 -0.0180128 -0.235177 -0.0486346 -0.0143801 -0.235036 -0.0483107 -0.0142681 -0.233569 -0.0485455 -0.00800333 -0.21303 -0.049519 -0.00729851 -0.224669 -0.0518905 -0.00804179 -0.253063 -0.0500136 -0.000307402 -0.212829 -0.049618 -0.00422196 -0.212883 -0.0508041 -0.00381387 -0.234742 -0.0488968 -0.00800333 -0.219348 -0.0482439 -0.0107025 -0.224834 -0.0465293 -0.0138328 -0.224876 -0.0503338 -0.00741233 -0.234801 -0.0491413 -0.00622132 -0.212948 -0.0511668 -0.0077041 -0.245094 -0.0506337 -0.0152993 -0.245101 -0.0515507 -0.0159665 -0.251521 0.0134205 -0.0198033 -0.278544 0.0148264 -0.0200032 -0.272132 0.0141192 -0.00030333 -0.275357 0.0134205 -0.00030333 -0.278544 0.00843243 -0.0198033 -0.301305 0.00843242 -0.0211424 -0.301305 0.00836934 -0.0198033 -0.308923 0.00837037 -0.0216598 -0.308923 0.00854974 -0.0217215 -0.309787 0.00855392 -0.0198033 -0.309807 0.013847 -0.0229452 -0.322426 0.0234452 -0.0260051 -0.355086 0.0218717 -0.0198033 -0.359857 0.0218435 -0.0260039 -0.35992 0.018275 -0.0198033 -0.365545 0.0174583 -0.0198033 -0.366456 0.0163548 -0.0260038 -0.367553 0.0122902 -0.0260038 -0.370605 0.0132327 -0.0198033 -0.370015 0.0103654 -0.0260038 -0.371639 0.00271917 -0.0260038 -0.373841 0.00188559 -0.0198033 -0.373923 -0.00237494 -0.0260038 -0.373879 -0.00685167 -0.0198033 -0.373001 -0.00735635 -0.0260037 -0.372845 -0.0159272 -0.0260037 -0.367958 -0.0196086 -0.0260037 -0.363947 -0.0453254 -0.0254786 -0.33244 -0.0515812 -0.0198033 -0.320782 -0.0515813 -0.0241468 -0.320782 -0.0538706 -0.0198033 -0.312872 -0.0537932 -0.0231265 -0.313245 -0.0538126 -0.00030333 -0.281611 -0.0527805 -0.0170028 -0.262915 -0.0533383 -0.0174611 -0.273019 -0.0539826 -0.0116642 -0.284691 -0.0541085 -0.0144437 -0.286972 -0.0545886 -0.0224325 -0.308293 -0.0547674 -0.0210472 -0.298908 -0.054576 -0.0204984 -0.29544 0.0173905 -0.0320033 -0.354609 0.00475396 -0.0320033 -0.352748 0.00549085 -0.0320033 -0.349998 0.017824 -0.0320033 -0.348359 0.00573725 -0.0320033 -0.367055 0.0110169 -0.0320033 -0.364224 0.00274079 -0.0320033 -0.354761 0.0142861 -0.0320033 -0.360935 -0.00275921 -0.0320033 -0.354761 -0.0111408 -0.0320033 -0.363819 -9.21786e-06 -0.0320033 -0.355498 -0.00948949 -0.0320033 -0.365163 -0.00607554 -0.0320033 -0.366944 0.0177517 -0.0320033 -0.347887 0.0171309 -0.0320033 -0.34546 0.00475403 -0.0320033 -0.347248 0.0152225 -0.0320033 -0.34155 -0.0365977 -0.0320033 -0.28265 -9.07704e-06 -0.0320033 -0.344498 0.000833145 -0.0320033 -0.317869 -0.00275909 -0.0320033 -0.345235 -0.00127861 -0.0320033 -0.313638 -0.00314751 -0.0320033 -0.307685 -0.0399394 -0.0320033 -0.305544 -0.038437 -0.0320033 -0.319289 -0.00550915 -0.0320033 -0.349998 -0.0325918 -0.0320033 -0.33121 -0.024918 -0.0320033 -0.343297 -0.0142542 -0.0320033 -0.359877 -0.0114352 -0.0320033 -0.268552 -0.0190578 -0.0320033 -0.267512 -0.0399949 -0.0313793 -0.264657 -0.0413957 -0.0309768 -0.264467 -0.0513265 -0.0236984 -0.269528 -0.0512813 -0.0230137 -0.263119 -0.0519142 -0.0216139 -0.263033 -0.0525029 -0.0196327 -0.262953 -0.0528175 -0.0200033 -0.269453 -0.0491411 -0.0260712 -0.263411 -0.045023 -0.0293654 -0.263973 -0.0458388 -0.0291797 -0.270643 -0.0450835 -0.0312801 -0.301693 -0.0382662 -0.0320033 -0.294339 -0.0400297 -0.0320033 -0.30753 -0.0392326 -0.0320033 -0.316134 -0.0263968 -0.0315925 -0.346888 -0.0356766 -0.0320033 -0.326124 -0.000178606 -0.0320033 -0.367996 -0.00632432 -0.0320033 -0.366851 0.00119935 -0.0320033 -0.367957 0.00849675 -0.0320033 -0.365861 0.00952799 -0.0315925 -0.367783 0.0123535 -0.0315925 -0.365949 0.0150752 -0.0320033 -0.359818 0.017463 -0.0320033 -0.354326 0.0179337 -0.0320033 -0.351355 0.00652379 -0.0313481 -0.320593 -0.00385069 -0.0320033 -0.275532 0.00237116 -0.0311875 -0.276897 -0.00420481 -0.0320033 -0.283698 0.00152086 -0.0312053 -0.284926 -0.00389863 -0.0320033 -0.299081 0.000484694 -0.0312664 -0.30186 -0.00287249 -0.0320033 -0.308852 0.00526058 -0.0303286 -0.275137 0.00792153 -0.0233505 -0.306833 0.0080356 -0.02141 -0.305316 0.00799882 -0.0231273 -0.302792 0.00856508 -0.0211019 -0.300688 0.0126905 -0.0201577 -0.281873 0.00864517 -0.0235811 -0.310807 0.00880122 -0.0217923 -0.310762 0.0117796 -0.0241111 -0.318211 0.0100843 -0.0220475 -0.314121 0.0184317 -0.0256999 -0.332817 0.0144405 -0.0281853 -0.368642 0.017458 -0.0260038 -0.366456 0.0173421 -0.0281853 -0.365978 0.0196927 -0.0260038 -0.3637 0.0197585 -0.0281853 -0.362867 0.0216255 -0.0281853 -0.359399 0.0222107 -0.0260039 -0.359068 0.00188559 -0.0260038 -0.373922 0.00369724 -0.0281853 -0.373293 0.00768068 -0.0260038 -0.372731 -0.00685162 -0.0260038 -0.373001 -0.00415271 -0.0281853 -0.373219 -0.0201603 -0.0281853 -0.362533 -0.0115412 -0.0281853 -0.370569 -0.0146585 -0.0260037 -0.369007 -0.0120084 -0.0260037 -0.370781 -0.0307059 -0.0260036 -0.350425 -0.0375837 -0.0260008 -0.342044 -0.040759 -0.0269567 -0.337913 -0.0446768 -0.0255576 -0.333325 -0.0456916 -0.0265655 -0.331605 -0.0486693 -0.024925 -0.327114 -0.0517346 -0.0240934 -0.320372 -0.0542225 -0.0242453 -0.309433 -0.05276 -0.0236843 -0.3173 -0.0547708 -0.0221482 -0.306282 -0.0541503 -0.0192875 -0.287729 -0.043651 -0.0305732 -0.277064 -0.0424415 -0.0310376 -0.278035 -0.0449705 -0.0301109 -0.27904 -0.0441574 -0.0311938 -0.294014 -0.0470974 -0.030092 -0.293852 -0.0452722 -0.0313593 -0.308233 -0.0478885 -0.0304826 -0.308584 -0.0444485 -0.0314337 -0.314816 -0.046819 -0.0306584 -0.315524 -0.0446681 -0.0308145 -0.32228 -0.0502233 -0.0292481 -0.308897 -0.0465192 -0.0298494 -0.323169 -0.0480192 -0.0286584 -0.323889 -0.0451813 -0.0278076 -0.331253 -0.0494198 -0.0273454 -0.280625 -0.051847 -0.0266257 -0.293589 -0.0533567 -0.02448 -0.293506 -0.0523937 -0.0271989 -0.301518 -0.0521151 -0.0277246 -0.309151 -0.0538289 -0.0252819 -0.301484 -0.0506485 -0.0282193 -0.316669 -0.0518657 -0.0267094 -0.317033 -0.0542151 -0.0222528 -0.293459 -0.0546449 -0.0232921 -0.301464 -0.0534586 -0.0260173 -0.309331 -0.0525578 -0.0251423 -0.31724 -0.0490844 -0.0273237 -0.324401 -0.04969 -0.0259383 -0.324691 -0.0403194 -0.0281094 -0.337552 -0.0302422 -0.0281853 -0.350044 -0.030601 -0.027055 -0.350339 0.00480256 -0.0289304 -0.307073 0.00584891 -0.0290122 -0.311605 0.00943117 -0.0292005 -0.319275 0.0201036 -0.030031 -0.34087 0.0228887 -0.0281854 -0.355668 0.023986 -0.02597 -0.35046 0.0239903 -0.0259584 -0.350031 0.0234735 -0.0281018 -0.34784 0.0234627 -0.0257073 -0.344997 0.0226855 -0.0254808 -0.342192 0.0214386 -0.0277183 -0.340265 0.021893 -0.0252814 -0.340185 0.00811107 -0.0255049 -0.310959 0.00732578 -0.025327 -0.306879 0.00887046 -0.0248402 -0.294753 0.00960592 -0.0227196 -0.294914 0.0112958 -0.0223914 -0.287069 -0.0497211 -0.0285405 -0.293707 -0.0478785 -0.0302958 -0.301626 -0.0503727 -0.0289096 -0.301566 -0.0489344 -0.0295667 -0.316157 -0.0430203 -0.0300721 -0.329759 -0.0384577 -0.0302111 -0.336024 -0.018967 -0.030246 -0.361553 -0.0139155 -0.030246 -0.367261 -0.0147961 -0.0281853 -0.368354 -0.0108744 -0.030246 -0.36938 -0.00795949 -0.0281853 -0.372206 -0.00391596 -0.030246 -0.371893 -0.000230923 -0.0281853 -0.373585 0.010501 -0.030246 -0.3696 0.00752184 -0.0281853 -0.372351 0.0111369 -0.0281853 -0.370787 0.0203907 -0.030246 -0.358862 0.0215816 -0.030246 -0.355345 0.0235121 -0.02818 -0.351778 0.0214158 -0.0301342 -0.344326 0.0227758 -0.0279425 -0.343966 0.0174643 -0.0285269 -0.333256 0.0180811 -0.0271397 -0.332976 0.0105421 -0.0276506 -0.318772 0.011331 -0.0259139 -0.318415 0.0071717 -0.0273583 -0.311227 0.00627801 -0.0272311 -0.30696 0.00622963 -0.027108 -0.302573 0.00735753 -0.0251548 -0.302712 0.00757695 -0.0268832 -0.294469 0.0104615 -0.0245869 -0.286886 -0.0397131 -0.0315519 -0.327474 -0.0425936 -0.0314998 -0.321285 -0.0356086 -0.0315844 -0.333686 -0.0287225 -0.030246 -0.348797 -0.0171409 -0.0315925 -0.360055 -0.0125678 -0.0315925 -0.365589 -0.00985401 -0.0315925 -0.367561 -0.00750561 -0.030246 -0.370938 -0.00681102 -0.0315925 -0.368998 -0.00355365 -0.0315925 -0.369865 -0.00019903 -0.0315925 -0.370178 0.00316288 -0.0315925 -0.369928 -0.000218319 -0.030246 -0.372239 0.00348606 -0.030246 -0.371963 0.00643394 -0.0315925 -0.369123 0.0070919 -0.030246 -0.371075 0.0148367 -0.0315925 -0.363669 0.0136157 -0.030246 -0.367578 0.016352 -0.030246 -0.365065 0.0169035 -0.0315925 -0.361008 0.0186302 -0.030246 -0.362133 0.018501 -0.0315925 -0.35804 0.0195812 -0.0315925 -0.35485 0.0221681 -0.0302435 -0.351676 0.0201115 -0.031592 -0.35152 0.0200295 -0.0315835 -0.348156 0.0221125 -0.0302075 -0.347965 0.0193346 -0.0315664 -0.344877 0.0180604 -0.0315423 -0.341795 0.0143229 -0.03148 -0.334679 0.0165958 -0.0297647 -0.333649 0.00238703 -0.0313041 -0.312592 0.000941164 -0.031285 -0.30737 0.000988483 -0.0312326 -0.293024 0.00464136 -0.0288511 -0.302375 0.00575547 -0.0287063 -0.29407 0.00692814 -0.0285897 -0.286111 0.00899428 -0.0267021 -0.286564 0.00908592 -0.0279612 -0.277815 0.0121068 -0.0245696 -0.278487 0.0133691 -0.020078 -0.278778 0.0563518 -0.0262321 -0.0642677 0.0566142 -0.000312439 -0.081354 0.055956 -0.00929005 -0.0812562 -0.0381862 -0.0201244 -0.0910225 -0.0389114 -0.0196525 -0.0920549 -0.0389247 -0.019639 -0.092059 -0.041842 -0.0126404 -0.089368 -0.042501 -0.00845573 -0.0889751 -0.0418543 -0.013907 -0.0907648 -0.0431041 -0.00146647 -0.0877453 -0.0431855 -0.000317442 -0.0891869 -0.0429384 -0.00488306 -0.0848181 -0.0407989 -0.0128091 -0.0847898 -0.0390993 -0.0177161 -0.0813202 -0.0396707 -0.015993 -0.0824527 -0.0426987 -0.0112701 -0.0805954 -0.0424293 -0.0206432 -0.0758563 -0.0423556 -0.0241929 -0.0745621 -0.0423368 -0.0253427 -0.0742317 -0.0368773 -0.0262616 -0.0771271 -0.0366156 -0.0290033 -0.0766538 0.0532813 -0.0176323 -0.0845592 0.0536012 -0.0174499 -0.0829682 0.0435678 -0.0240103 -0.0863618 0.042282 -0.0242367 -0.0869478 0.0489188 -0.0218654 -0.0871559 0.0472062 -0.0231244 -0.0844299 0.0462 -0.0245956 -0.079145 0.0435751 -0.0252764 -0.0796373 0.0444625 -0.0242146 -0.0835517 0.0388384 -0.027898 -0.0761694 0.0453425 -0.0265892 -0.0742278 0.0450776 -0.02775 -0.0726512 0.0365729 -0.0283467 -0.07689 0.0351872 -0.028614 -0.0773922 0.0388026 -0.0290033 -0.0755657 0.0466752 -0.0290033 -0.0709731 0.00423027 -0.0286208 -0.0849112 0.00985635 -0.0290033 -0.0843735 0.0122012 -0.0286275 -0.0841355 0.020063 -0.0286307 -0.0826136 0.0256795 -0.0290033 -0.080972 -0.023342 -0.0290033 -0.0816793 -0.0164369 -0.0290033 -0.0833434 -0.0117483 -0.0285907 -0.0842043 -0.00946917 -0.0285976 -0.0844903 -0.00986784 -0.0290033 -0.0843733 -0.00377541 -0.0286106 -0.084934 -0.0234138 -0.0285038 -0.0817395 -0.0196183 -0.0285484 -0.0827293 -0.0305551 -0.0271451 -0.079851 -0.0283888 -0.0281179 -0.0802422 -0.0385466 -0.0194804 -0.0802486 -0.0367775 -0.0208306 -0.0894168 -0.0353806 -0.0220286 -0.0934779 -0.0310481 -0.0234172 -0.0944131 0.0581887 -0.00590112 -0.0739951 0.0581795 -0.00586029 -0.0740384 0.0582569 -0.00620448 -0.0736759 0.0585832 -0.00770756 -0.0721471 0.0561224 -0.0109582 -0.0786171 0.0550043 -0.014795 -0.0795708 0.0550781 -0.013462 -0.0819492 0.0575246 -0.0031544 -0.0771034 -0.0375906 -0.0191976 -0.0864151 -0.0362343 -0.0203923 -0.0850347 -0.0377938 -0.0185478 -0.0834222 -0.0358017 -0.0208179 -0.0837602 -0.039417 -0.0160536 -0.0855566 -0.0417896 -0.0102047 -0.087038 -0.0408353 -0.0140162 -0.0876065 -0.0393557 -0.017721 -0.0883316 -0.0406107 -0.0167042 -0.0899747 -0.0347148 -0.0222777 -0.092395 -0.0336328 -0.0226145 -0.0905889 -0.0333404 -0.022733 -0.0908284 -0.0375682 -0.0229953 -0.0783994 -0.0323375 -0.0250291 -0.0806247 -0.0302071 -0.0281046 -0.07955 0.050877 -0.0281284 -0.0682063 0.0508424 -0.0290033 -0.0680498 0.0563496 -0.0290033 -0.0635643 0.0611013 -0.0232381 -0.0603327 0.0612106 -0.0243413 -0.0598193 0.06128 -0.0251342 -0.0594932 0.0563518 -0.0230482 -0.0661499 0.0606133 -0.0192814 -0.0626241 0.0563037 -0.0163969 -0.0720807 0.0592426 -0.0110006 -0.0690556 0.0593466 -0.0115528 -0.0685678 0.0513191 -0.025305 -0.0702557 0.0489224 -0.0247858 -0.0745207 0.0518018 -0.0233794 -0.0725684 0.049499 -0.0235236 -0.0771656 0.0506338 -0.0214428 -0.0824632 0.045731 -0.0255334 -0.0764916 0.0484282 -0.0261452 -0.0722689 0.0388118 -0.0284306 -0.075723 0.0373289 -0.0280955 -0.0767297 0.0450051 -0.0283659 -0.0722137 0.0509742 -0.0272122 -0.0686508 0.0563393 -0.0196903 -0.0688684 0.0545208 -0.0190283 -0.0736353 0.0523467 -0.0215334 -0.0752924 0.0533219 -0.0184708 -0.0807887 0.0826525 -0.0260863 0.0164038 0.0840662 -0.0261401 0.00648556 0.0848015 -0.0290033 -0.00493829 0.0838355 -0.0290033 -0.0136844 0.0842883 -0.0261889 -0.00365232 0.0815233 -0.0290033 -0.0238659 0.0670926 -0.027519 0.0517683 0.0671229 -0.0290033 0.0520636 0.0237989 -0.0274243 0.0812584 0.0153425 -0.0274124 0.0832556 0.0195872 -0.0290033 0.0826621 -3.5793e-06 -0.0290033 0.0849524 -0.00186488 -0.0273912 0.0846113 -0.0106733 -0.0290033 0.0842796 -0.0189036 -0.0273724 0.0824687 -0.0195944 -0.0290033 0.0826626 -0.0271541 -0.0273634 0.0801194 -0.0274188 -0.0290033 0.0804072 -0.0381292 -0.0290033 0.0759168 -0.0498938 -0.027336 0.0682795 -0.0728598 -0.0272945 0.042864 -0.0681444 -0.0290033 0.0507317 -0.0681017 -0.0273056 0.0500935 -0.0629905 -0.0290033 0.0570047 -0.077257 -0.0290033 0.0353374 -0.073233 -0.0290033 0.0430617 -0.0847084 -0.0277265 -0.0012031 -0.080482 -0.0290033 0.0272032 -0.0800764 -0.0272727 0.0270387 -0.0824457 -0.0272633 0.0185916 -0.0836639 -0.0290033 0.0147547 -0.0844359 -0.0290033 0.00937567 -0.0848435 -0.0281597 -0.00118468 -0.0849465 -0.0290033 -0.00117061 -0.0376847 -0.00278979 0.00342764 -0.0367337 -0.0027696 0.00964767 -0.0356358 -0.00027083 0.011296 -0.035068 -0.00275513 0.0157502 -0.0329237 -0.000266827 0.0193825 -0.0289549 -0.00026363 0.026905 -0.0258636 -0.00271285 0.0324149 -0.0214872 -0.00268732 0.0371045 -0.0165654 -0.00265895 0.0412306 -0.0238045 -0.000264956 0.0337115 -0.0176654 -0.000269373 0.0395595 -0.0111772 -0.0026294 0.0447312 -0.0106276 -0.000275295 0.0443687 0.037953 -0.00245161 0.0466014 0.0384257 -0.000293456 0.0460472 0.0434782 -0.00243415 0.0435967 0.0648043 -0.000288272 0.0174158 0.0607736 -0.00234036 0.0260899 0.0572897 -0.00236805 0.0311571 0.0457656 -0.000291395 0.0417397 0.048587 -0.00241492 0.0399805 0.0673052 -0.000293386 0.0102331 0.0693287 -0.00390684 -0.0222034 0.0687795 -0.000296146 -0.0221285 0.0702287 -0.00395116 -0.0168421 0.0768194 -0.0157652 -0.0153245 0.0816974 -0.0229911 -0.0141854 0.0826193 -0.0229491 -0.00459614 0.0774755 -0.0157791 -0.0075064 0.0824083 -0.0228973 0.00497444 0.078794 -0.0227909 0.0233922 0.0755454 -0.0227432 0.0319602 0.0714546 -0.0226994 0.0399491 0.0692288 -0.0159786 0.0298239 0.0611666 -0.0226322 0.0539328 0.0550639 -0.0226045 0.0599052 0.0560589 -0.016057 0.0481431 0.0443064 -0.0160837 0.0574975 -0.0642147 -0.0193694 0.0292515 -0.0532845 -0.0164266 0.032503 -0.0515402 -0.0194012 0.0494583 -0.0459318 -0.0193933 0.055114 -0.0394051 -0.0163734 0.0503447 -0.0397538 -0.0193801 0.0601211 -0.0186035 -0.0193334 0.0708111 -0.00609178 -0.016181 0.0669244 0.00133729 -0.0161537 0.0679464 -0.00313077 -0.0193154 0.074025 0.0162952 -0.0161179 0.067592 0.0047732 -0.0193135 0.0744043 0.0236593 -0.0161074 0.0662194 0.020506 -0.0193228 0.0726791 0.0308368 -0.0160996 0.0640654 0.0377462 -0.0160923 0.0611485 -0.0689044 -0.0193626 0.0139378 -0.0700511 -0.0193395 0.00571189 -0.0669477 -0.0193602 0.021723 -0.0709292 -0.0223264 0.0323832 -0.060739 -0.0193892 0.0364469 -0.0671732 -0.0223513 0.0398528 -0.0564997 -0.0194007 0.0432118 -0.0330864 -0.0193642 0.064432 -0.0308388 -0.0224144 0.0727499 -0.0260091 -0.0193479 0.0680054 -0.0231351 -0.0224198 0.0757468 -0.0109504 -0.0193222 0.0728241 -0.0151647 -0.0224269 0.0779364 0.00125607 -0.0224488 0.0798126 0.0126796 -0.0193162 0.0739551 0.0281691 -0.0193323 0.0705859 0.0258539 -0.0225034 0.0762413 0.035586 -0.0193434 0.0676885 0.0337096 -0.0225264 0.0733591 0.0426737 -0.019355 0.0640113 0.083276 -0.0262277 -0.0138156 0.0811092 -0.0228427 0.0143548 0.0801264 -0.026032 0.025926 0.066632 -0.0226626 0.047286 0.0477323 -0.0258095 0.0690526 0.0483989 -0.0225772 0.0651619 0.040259 -0.0257848 0.0735963 0.0412529 -0.0225511 0.0696572 0.0323987 -0.0257619 0.0773162 0.0242372 -0.0257407 0.0801887 0.0177702 -0.0224825 0.0782831 0.0158602 -0.0257213 0.0821953 0.007353 -0.0257034 0.0833297 0.00954285 -0.0224642 0.0794756 -0.0097132 -0.0256722 0.0829745 -0.00700709 -0.0224364 0.079296 -0.0181064 -0.0256582 0.0815026 -0.0342074 -0.0256324 0.0760551 -0.0381973 -0.0224096 0.0689743 -0.0451327 -0.0224043 0.0644521 -0.0554956 -0.0255923 0.0620863 -0.0515705 -0.0223971 0.0592269 -0.0574366 -0.0223869 0.0533462 -0.0716492 -0.0255419 0.0422229 -0.0626591 -0.0223721 0.0468657 -0.0756024 -0.0255226 0.0345646 -0.0787643 -0.025505 0.0265066 -0.0739147 -0.0223074 0.0245416 -0.0830798 -0.0254981 -0.00142512 -0.0826097 -0.0254865 0.0089097 -0.0838475 -0.0262965 -0.00132046 -0.0840052 -0.0272621 0.00926571 -0.0810927 -0.0254905 0.0181254 -0.0768667 -0.0272833 0.0351551 -0.0669431 -0.0255603 0.0494065 -0.0615388 -0.025577 0.0560489 -0.0626483 -0.0273162 0.0567795 -0.0565576 -0.0273263 0.0628594 -0.0488796 -0.0256063 0.0674647 -0.04176 -0.0256196 0.072136 -0.0427248 -0.0273453 0.0729914 -0.03512 -0.0273544 0.0769497 -0.0262973 -0.0256451 0.0791876 -0.00119936 -0.0256871 0.083588 -0.0104466 -0.0273816 0.0839713 0.00675946 -0.0274015 0.0843743 0.0320432 -0.0274371 0.0783885 0.0399893 -0.027451 0.0746636 0.0475511 -0.0274661 0.0701066 0.0547334 -0.025836 0.0637138 0.0546431 -0.0274824 0.0647456 0.0611789 -0.0258637 0.0576228 0.0611814 -0.0274995 0.0586224 0.0669951 -0.025895 0.0508128 0.0721702 -0.0259336 0.0432304 0.0765918 -0.0259804 0.0349085 0.0768752 -0.0275725 0.0357076 0.0723635 -0.0275432 0.0441196 -0.0760912 -0.0222956 0.0164046 -0.06149 -0.0164124 0.00353833 -0.0774537 -0.0222829 0.00759561 -0.077049 -0.0219071 -0.00224733 0.0259611 -0.00248514 0.0505833 0.0196633 -0.00250335 0.051489 0.0132839 -0.00252365 0.0516415 0.0060669 -0.0049089 0.0520907 -0.000269854 -0.00495202 0.0507126 -0.0378436 -0.00029115 -0.00759231 -0.0393124 -0.00531521 0.0039372 -0.0365835 -0.00525796 0.0164349 -0.0327017 -0.00274703 0.0216468 -0.0296222 -0.0027334 0.0272342 -0.0227523 -0.00514651 0.0380701 -0.0177412 -0.00509867 0.0422296 -0.045244 -0.00963193 -0.000559239 -0.0447363 -0.00966798 0.00572474 -0.0507402 -0.0132584 0.0151915 -0.0457479 -0.0132344 0.0285187 -0.0357382 -0.00955773 0.0308822 -0.0378053 -0.0131803 0.0403823 -0.0217366 -0.0093931 0.0455259 -0.0272646 -0.0130727 0.0500271 -0.00812946 -0.0128923 0.0593736 0.0164452 -0.00904268 0.0564486 0.02309 -0.00900451 0.0556345 -0.0421583 -0.00756601 -0.00132764 -0.0417067 -0.00759766 0.00471816 -0.0435391 -0.00962421 0.012312 -0.0416433 -0.00959573 0.0187614 -0.0390669 -0.00958374 0.0249916 -0.0291908 -0.00744739 0.0346581 -0.0316866 -0.00951393 0.0363221 -0.0269898 -0.00945726 0.0412257 -0.0079447 -0.00721112 0.0501405 -0.0160164 -0.00932567 0.0491694 -0.00991934 -0.0092586 0.0521145 -0.00169463 -0.00715254 0.0522983 -0.00353569 -0.00919515 0.0543312 0.0113002 -0.00705157 0.0543665 0.00304521 -0.00913746 0.0557988 0.0178649 -0.00701015 0.0542625 0.00973479 -0.00908659 0.0565053 0.0243565 -0.00697366 0.053406 0.0679386 -0.00435691 0.0106841 0.0696968 -0.00209268 -0.000988134 0.0707862 -0.0078782 -0.0224021 0.0718818 -0.00793863 -0.0164674 0.072306 -0.00800207 -0.010435 0.0706048 -0.00400363 -0.0114018 0.0722132 -0.00808756 -0.00437169 0.0701057 -0.00415968 -0.000404458 0.037494 -0.00475154 0.0477431 0.0532109 -0.00239306 0.0358118 0.0608411 -0.00456937 0.027186 0.0676219 -0.00221187 0.00983395 0.0636229 -0.00230727 0.0207116 0.0637881 -0.00451474 0.0217513 0.0669348 -0.00855599 0.0196154 0.0690363 -0.00844472 0.013711 0.0705679 -0.0122921 0.0179819 0.0705845 -0.00831866 0.00772343 0.0724962 -0.0121892 0.0113866 0.071634 -0.00819445 0.00168799 0.0738317 -0.0120893 0.00464855 0.0745822 -0.0120065 -0.00218621 0.0741905 -0.0118968 -0.0159351 0.0565717 -0.0125531 0.0418099 0.0609534 -0.00871353 0.0310243 0.0515151 -0.0125919 0.0466808 0.052438 -0.00882113 0.0410108 0.0459361 -0.0126246 0.0509551 0.0473479 -0.00886487 0.0452232 0.0358454 -0.00893719 0.0518011 0.0268215 -0.0127015 0.0597402 -0.0054075 -0.00260006 0.0475557 -0.0064109 -0.0049991 0.0485918 0.000654358 -0.0025722 0.0496652 0.00691614 -0.00254661 0.0510324 -0.00294381 -0.000281419 0.0479657 0.0136852 -0.000291031 0.0512631 0.0221839 -0.000293542 0.050868 0.0320867 -0.00246823 0.0489439 0.0315396 -0.00477866 0.0500677 0.0295844 -0.00897015 0.0540775 0.0431151 -0.00472309 0.0447517 0.0417923 -0.00890285 0.0488361 0.048327 -0.00469174 0.0411409 0.0530592 -0.00465598 0.036966 0.0572485 -0.00461494 0.0322906 0.0569935 -0.0087704 0.0362557 0.0642552 -0.00864479 0.0254077 0.0680159 -0.0123824 0.0243801 0.0199214 -0.0127278 0.0612105 0.025333 -0.00480643 0.0516879 0.0189595 -0.00483655 0.0525756 0.0125073 -0.0048704 0.0527126 0.0047504 -0.00709906 0.0537111 -0.0139093 -0.00727293 0.0472596 -0.0122647 -0.00504871 0.0457525 -0.0194979 -0.00733513 0.0436877 -0.0246209 -0.00739452 0.0394687 -0.027214 -0.00518935 0.0333322 -0.0331221 -0.00748897 0.0293249 -0.031046 -0.00522349 0.0280868 -0.0363404 -0.00751489 0.023555 -0.0388162 -0.00752842 0.0174579 -0.0341796 -0.00524553 0.0224193 -0.0406103 -0.00755642 0.0111512 -0.0382994 -0.00528154 0.0102457 -0.0397351 -0.0052908 -0.0019237 -0.0402574 -0.00557988 -0.00726321 -0.0528583 -0.0132579 0.0013547 -0.0521766 -0.0132956 0.00823156 -0.0605827 -0.0164449 0.0110914 -0.0588829 -0.0164238 0.0184674 -0.0485898 -0.0132378 0.0219801 -0.0564409 -0.0164177 0.0256303 -0.0421425 -0.0132166 0.0346889 -0.0493619 -0.0164233 0.0389758 -0.0447098 -0.0164042 0.0449491 -0.032816 -0.0131305 0.0455163 -0.0335341 -0.0163356 0.0551024 -0.0212407 -0.0130112 0.0538648 -0.0148329 -0.01295 0.0569896 -0.0271824 -0.0162944 0.0591739 -0.020435 -0.0162531 0.0625193 -0.0133768 -0.0162146 0.0651102 -0.00121713 -0.0128405 0.0609963 0.00581863 -0.0127959 0.0618449 0.0128927 -0.0127587 0.0619155 0.00882708 -0.0161329 0.0681696 0.0335109 -0.0126772 0.0575228 0.0399088 -0.0126524 0.0545831 0.0504366 -0.0160723 0.053148 0.0610386 -0.0125086 0.0364033 0.0648448 -0.0124539 0.0305405 0.0611001 -0.0160379 0.0425379 0.0654852 -0.0160127 0.0363987 0.0723113 -0.0159342 0.022867 0.0746925 -0.0158827 0.0155805 0.0763656 -0.0158351 0.00803881 0.0773092 -0.0158009 0.000315406 0.0747153 -0.0119429 -0.0090693 -0.0419316 -0.00570988 -0.0384142 -0.0817113 -0.0243506 -0.00643211 -0.0404539 -0.00565777 -0.0130982 -0.083637 -0.0269773 -0.0127177 -0.0840406 -0.0290033 -0.0124263 -0.084811 -0.0290033 -0.00493612 -0.0845836 -0.0279842 -0.0066586 -0.0815288 -0.0285214 -0.0238324 -0.0828064 -0.0276301 -0.0183962 -0.0763543 -0.0248135 -0.035059 -0.0774295 -0.0276838 -0.0347548 -0.0813862 -0.0290033 -0.0243607 -0.0756162 -0.0290033 -0.0387198 -0.0652079 -0.0281536 -0.0544189 -0.0562365 -0.0264704 -0.0635873 -0.0517528 -0.0290033 -0.0673672 -0.0424232 -0.0209043 -0.0757494 -0.043658 -0.016485 -0.0765258 -0.0425488 -0.0160821 -0.0779582 -0.0432267 -0.0201584 -0.0754051 -0.0456507 -0.0187609 -0.0736546 -0.0424057 -0.0216824 -0.075441 -0.0426622 -0.0123744 -0.0799537 -0.0429055 -0.0101042 -0.0809563 -0.0427353 -0.0101976 -0.0812403 -0.042792 -0.00860702 -0.0822386 -0.0432601 -0.0064716 -0.0820355 -0.0428653 -0.00667178 -0.08353 -0.0431399 -0.000896256 -0.0883793 -0.0430982 -0.00149764 -0.0863426 -0.0430172 -0.00312935 -0.086209 -0.0430358 -0.00325269 -0.0858653 -0.0430113 -0.00325305 -0.0861051 -0.0431308 -0.00309701 -0.0828524 -0.0429618 -0.00434117 -0.0852314 -0.0436315 -0.00616852 -0.0791725 -0.0410298 -0.000288646 -0.0518189 -0.0414571 -0.00028707 -0.0588074 -0.0414378 -0.00294969 -0.051291 -0.0388456 -0.00307186 -0.0131134 -0.0382518 -0.000293528 -0.0126869 -0.0383256 -0.000293538 -0.0136199 -0.0458695 -0.00965707 -0.0142598 -0.042957 -0.00793339 -0.00689517 -0.0428712 -0.00781232 -0.0135216 -0.0422239 -0.00738189 -0.00699511 -0.0527622 -0.0130113 -0.0055584 -0.0452669 -0.00942785 -0.00658026 -0.0596887 -0.0155993 -0.00461409 -0.0597699 -0.0155991 -0.00598925 -0.0615933 -0.0162607 -0.00435443 -0.0702808 -0.0192536 -0.00317004 -0.0790169 -0.0225537 -0.0119874 -0.0749261 -0.0210058 -0.00253674 -0.0794178 -0.0230525 -0.00192437 -0.0815091 -0.0242848 -0.00163927 -0.0829927 -0.025389 -0.00668322 -0.084506 -0.0272744 -0.00123069 -0.0719911 -0.0275601 -0.0449513 -0.0797663 -0.0290033 -0.0292311 -0.0565781 -0.014483 -0.00503817 -0.0610127 -0.0153564 -0.0189204 -0.0677727 -0.0182189 -0.00855327 -0.076033 -0.0211213 -0.0235144 -0.0691945 -0.0180908 -0.0277102 -0.0726163 -0.0197097 -0.028678 -0.0708406 -0.0210766 -0.039973 -0.0729727 -0.0233832 -0.0402417 -0.0745061 -0.0223555 -0.0349442 -0.077793 -0.0238364 -0.0297101 -0.0792564 -0.0264996 -0.0296164 -0.0822913 -0.026183 -0.0185605 -0.0812021 -0.0269738 -0.0240988 -0.0829865 -0.0290033 -0.018178 -0.0463525 -0.00981955 -0.0267791 -0.0530205 -0.0127311 -0.0163621 -0.0615371 -0.0154968 -0.0314622 -0.0690319 -0.0179675 -0.0214933 -0.0727394 -0.019434 -0.022616 -0.0755547 -0.0209563 -0.0109976 -0.0760053 -0.0209261 -0.0173706 -0.0791261 -0.0227055 -0.0181753 -0.0818444 -0.0244896 -0.012633 -0.0511903 -0.0259276 -0.0678677 -0.0585846 -0.0215648 -0.0596184 -0.0553497 -0.0234997 -0.0639936 -0.0599511 -0.0242796 -0.0594721 -0.0609213 -0.0272058 -0.059111 -0.0617958 -0.0290033 -0.0582932 -0.0607976 -0.0163112 -0.0433188 -0.0599456 -0.0169755 -0.0489856 -0.0432497 -0.00475534 -0.0824734 -0.0435147 -0.00972684 -0.0797543 -0.0449363 -0.00870629 -0.072864 -0.0429074 -0.00300611 -0.0766026 -0.0428779 -0.000282328 -0.0833904 -0.0452281 -0.0120992 -0.0751996 -0.051536 -0.0187512 -0.0667647 -0.0456538 -0.0222028 -0.0727693 -0.045756 -0.0255918 -0.0719377 -0.0461996 -0.0287988 -0.0712912 -0.0423047 -0.0290033 -0.0736674 -0.0455515 -0.0153703 -0.0744879 -0.0450908 -0.00851888 -0.0698834 -0.0436492 -0.00584405 -0.069989 -0.0451149 -0.00829605 -0.0637677 -0.0433877 -0.00577348 -0.0637185 -0.0406064 -0.00297302 -0.0385828 -0.0388215 -0.00362802 -0.00745897 -0.0547315 -0.0167323 -0.0593038 -0.0610107 -0.0200611 -0.0548048 -0.0586735 -0.0178638 -0.0544248 -0.0627814 -0.0189069 -0.0496359 -0.0692129 -0.0221545 -0.0452194 -0.0709313 -0.0246818 -0.0452639 -0.070013 -0.0290033 -0.0481158 -0.0744224 -0.0260537 -0.0401405 -0.0466003 -0.0111575 -0.0698147 -0.0486874 -0.0133831 -0.0669946 -0.0491992 -0.0130052 -0.0642077 -0.0523528 -0.0145571 -0.0589014 -0.0472314 -0.010191 -0.0517705 -0.053075 -0.0139621 -0.0531641 -0.0460645 -0.0115482 -0.0725886 -0.0471323 -0.0106638 -0.0639743 -0.0472768 -0.0103768 -0.0579239 -0.0446988 -0.00809789 -0.0512847 -0.0536663 -0.0132267 -0.0412272 -0.082898 -0.0256495 -0.0127606 -0.081485 -0.0248912 -0.0185669 -0.0787237 -0.0231301 -0.0240859 -0.068883 -0.0184669 -0.0336701 -0.0536121 -0.0128356 -0.0289403 -0.046863 -0.00996739 -0.0393133 -0.044069 -0.00801368 -0.0386858 -0.042706 -0.005717 -0.0510914 -0.0422077 -0.00295921 -0.0639658 -0.0437436 -0.00600376 -0.0761689 -0.044605 -0.00898795 -0.0757488 -0.0528224 -0.0179603 -0.0643976 -0.0568343 -0.0190546 -0.0595566 -0.0629074 -0.0224933 -0.0549459 -0.0643131 -0.0251872 -0.0548209 -0.0651824 -0.0210701 -0.0500504 -0.0670583 -0.0235134 -0.0501802 -0.0683533 -0.0262664 -0.0499952 -0.0689646 -0.0290033 -0.0496066 -0.0567532 -0.0290033 -0.0632126 -0.0523313 -0.0290033 -0.0669189 -0.0542223 -0.0206574 -0.0642695 -0.050614 -0.0227914 -0.0684423 -0.0499537 -0.0197 -0.0689714 -0.0434908 -0.00629605 -0.0806284 -0.0439842 -0.00942397 -0.0784767 -0.0426203 -0.0136947 -0.0792153 -0.0439681 -0.0128761 -0.0775809 -0.0469583 -0.0145151 -0.0721861 -0.047589 -0.0176224 -0.0716409 -0.0490915 -0.0167162 -0.069391 -0.047969 -0.0138712 -0.0696696 -0.0502465 -0.0159953 -0.0669527 -0.051134 -0.0154171 -0.0643694 -0.0534774 -0.0135375 -0.0472535 -0.0613186 -0.0158234 -0.0374724 -0.0681108 -0.0190886 -0.0393802 -0.0668884 -0.0199504 -0.0448464 -0.0719768 -0.0202607 -0.0344601 -0.0755333 -0.0215978 -0.0293722 -0.0806139 -0.0255657 -0.0242235 -0.0839863 -0.026581 -0.00677834 -0.0840129 -0.0284986 -0.012478 0.067483 -0.0226386 -0.0515656 0.0635329 -0.0152486 -0.0586096 0.0614628 -0.0290033 -0.0586344 0.0719361 -0.0260665 -0.0449023 0.067629 -0.0290033 -0.0514 0.0785676 -0.0255302 -0.0307945 0.0735637 -0.0290033 -0.0424737 0.0806256 -0.0251948 -0.0237435 0.0813762 -0.0290033 -0.0243628 0.0789447 -0.0218233 -0.0235144 0.0704736 -0.00716851 -0.0223595 0.0728464 -0.0118467 -0.0226829 0.07458 -0.014739 -0.0229193 0.0731455 -0.0147678 -0.0286775 0.0752041 -0.0157389 -0.0230044 0.0765238 -0.0178317 -0.0231843 0.0635425 -0.00387484 -0.0504336 0.0602076 -0.00387661 -0.0660915 0.0631741 -0.00029466 -0.0503957 0.05837 -0.00390509 -0.0738405 0.0576688 -0.0037157 -0.0764291 0.0582359 -0.000291625 -0.0739125 0.0569991 -0.00132249 -0.0795586 0.056966 -0.00029898 -0.0797748 0.0574352 -0.00281727 -0.0775216 0.0605683 -0.00769867 -0.066117 0.0582834 -0.00585941 -0.0737277 0.0599375 -0.0148893 -0.0657958 0.0599945 -0.015232 -0.0655282 0.0607903 -0.0205986 -0.0617929 0.0634161 -0.0191481 -0.0584105 0.0629653 -0.0231017 -0.0580543 0.0671199 -0.0188169 -0.051539 0.0712991 -0.0222893 -0.044747 0.0675929 -0.0265014 -0.0514731 0.0625011 -0.0270576 -0.0576919 0.0770954 -0.0218883 -0.0302464 0.0745258 -0.0220355 -0.0376512 0.0721206 -0.0290033 -0.0448804 0.0643817 -0.0076193 -0.050684 0.0678388 -0.00759771 -0.0350836 0.0711665 -0.0148192 -0.0363599 0.0667612 -0.0038919 -0.0347211 0.0625696 -0.00764365 -0.058445 0.0605228 -0.0115866 -0.0659514 0.0600416 -0.0155183 -0.0653071 0.0632137 -0.0114198 -0.0586036 0.0664135 -0.0150509 -0.051351 0.065433 -0.0113294 -0.0510342 0.0689193 -0.0149141 -0.0439163 0.0702573 -0.0185777 -0.0444012 0.0755968 -0.0257424 -0.0380106 0.0148947 -3.3303e-06 -0.221865 -0.0114111 -3.3303e-06 0.0327739 0.00252721 -3.3303e-06 0.0493661 0.068485 -3.3303e-06 -0.0220716 0.0625805 -3.3303e-06 -0.0517985 0.057384 -3.3303e-06 -0.0707688 0.0573687 -3.3303e-06 -0.0707269 0.0126282 -3.3303e-06 -0.267236 0.0142248 -3.3303e-06 -0.266368 0.0145334 -3.3303e-06 -0.272068 0.0116881 -3.3303e-06 -0.275842 0.00966306 -3.3303e-06 -0.276385 0.00763807 -3.3303e-06 -0.275842 0.0119121 -3.3303e-06 -0.280929 0.00340401 -3.3303e-06 -0.280929 0.00340542 -3.3303e-06 -0.280905 0.00763816 -3.3303e-06 -0.268827 0.00668867 -3.3303e-06 -0.268069 0.00869477 -3.3303e-06 -0.267226 0.0239882 -3.3303e-06 -0.225023 0.0225058 -3.3303e-06 -0.226505 0.022349 -3.3303e-06 -0.231373 0.0204808 -3.3303e-06 -0.227048 0.0223723 -3.3303e-06 -0.23318 0.0169595 -3.3303e-06 -0.259255 0.0150959 -3.3303e-06 -0.269229 0.0154021 -3.3303e-06 -0.264247 0.0262621 -3.3303e-06 -0.21853 0.0199376 -3.3303e-06 -0.228742 0.0184558 -3.3303e-06 -0.226505 0.0156013 -3.3303e-06 -0.225944 0.0169734 -3.3303e-06 -0.225023 0.0200184 -3.3303e-06 -0.217317 0.0218695 -3.3303e-06 -0.21747 0.0236812 -3.3303e-06 -0.21748 0.0266201 -3.3303e-06 -0.216898 0.0263568 -3.3303e-06 -0.215117 0.0265097 -3.3303e-06 -0.214599 0.0347239 -3.3303e-06 -0.17715 0.0347846 -3.3303e-06 -0.163491 0.0347845 -3.3303e-06 -0.170506 0.0341515 -3.3303e-06 -0.161471 0.0322385 -3.3303e-06 -0.17274 0.0299609 -3.3303e-06 -0.171964 0.0287096 -3.3303e-06 -0.166998 0.0292522 -3.3303e-06 -0.164973 0.0276792 -3.3303e-06 -0.164414 0.0307346 -3.3303e-06 -0.163491 0.038681 -3.3303e-06 -0.161908 0.0474426 -3.3303e-06 -0.11915 0.0387921 -3.3303e-06 -0.1586 0.0386379 -3.3303e-06 -0.159122 0.0391181 -3.3303e-06 -0.159915 0.0489843 -3.3303e-06 -0.106973 0.0495268 -3.3303e-06 -0.108998 0.0434519 -3.3303e-06 -0.105491 0.0402017 -3.3303e-06 -0.106839 0.0398044 -3.3303e-06 -0.109558 0.0419695 -3.3303e-06 -0.106973 0.0414268 -3.3303e-06 -0.108998 0.0434518 -3.3303e-06 -0.112506 0.0454768 -3.3303e-06 -0.113048 0.0473983 -3.3303e-06 -0.117342 0.0465179 -3.3303e-06 -0.115754 0.0505601 -3.3303e-06 -0.101618 0.0510647 -3.3303e-06 -0.100966 0.0560571 -3.3303e-06 -0.0824821 0.0561707 -3.3303e-06 -0.0819622 0.0554705 -3.3303e-06 -0.0823553 0.0562864 -3.3303e-06 -0.0814427 0.0561577 -3.3303e-06 -0.0792323 0.0568658 -3.3303e-06 -0.0759426 0.0575288 -3.3303e-06 -0.0728687 0.0596106 -3.3303e-06 -0.0660398 0.0589306 -3.3303e-06 -0.0409569 0.0640171 -3.3303e-06 -0.0332246 0.0653806 -3.3303e-06 -0.0318611 0.0584118 -3.3303e-06 -0.030563 0.0653806 -3.3303e-06 -0.0281361 0.0640172 -3.3303e-06 -0.0267727 0.0697236 -3.3303e-06 -0.0090462 0.0584119 -3.3303e-06 -0.023113 0.0674238 -3.3303e-06 0.00867571 0.0580279 -3.3303e-06 0.0292146 0.0546698 -3.3303e-06 0.0297265 0.0509447 -3.3303e-06 0.0260015 0.0583947 -3.3303e-06 0.0260014 0.0514438 -3.3303e-06 0.024139 0.0458184 -3.3303e-06 -0.0125568 0.0528072 -3.3303e-06 0.0227756 0.0565323 -3.3303e-06 0.0292274 0.0540091 -3.3303e-06 0.0341366 0.0520913 -3.3303e-06 0.0361078 0.0502367 -3.3303e-06 0.0338614 0.0266233 -3.3303e-06 0.048318 0.0022472 -3.3303e-06 0.0483183 0.0137263 -3.3303e-06 0.0509646 -0.00162193 -3.3303e-06 0.0435845 -0.00298535 -3.3303e-06 0.0449479 -0.00283919 -3.3303e-06 0.0476854 0.00652347 -3.3303e-06 0.0340826 -0.00298543 -3.3303e-06 0.038496 -0.00954677 -3.3303e-06 0.0446289 -0.00807381 -3.3303e-06 0.0435846 -0.0195163 -3.3303e-06 0.0375901 -0.00857289 -3.3303e-06 0.0417221 -0.00807386 -3.3303e-06 0.0398596 -0.00253005 -3.3303e-06 0.0346102 -0.00484794 -3.3303e-06 0.037997 -0.019513 -3.3303e-06 0.0286991 -0.0235826 -3.3303e-06 0.0335132 -0.0353463 -3.3303e-06 0.0112242 -0.0340993 -3.3303e-06 0.0154805 -0.0312569 -3.3303e-06 0.0150815 -0.03265 -3.3303e-06 0.0192653 -0.0371357 -3.3303e-06 -0.0023737 -0.0340968 -3.3303e-06 0.00646873 -0.037833 -3.3303e-06 -0.0231118 -0.0393014 -3.3303e-06 -0.0305591 -0.0406682 -3.3303e-06 -0.0940227 -0.0421506 -3.3303e-06 -0.095505 -0.04238 -3.3303e-06 -0.104568 -0.0421507 -3.3303e-06 -0.099555 -0.0374582 -3.3303e-06 -0.0432012 -0.0398171 -3.3303e-06 -0.0379095 -0.0400583 -3.3303e-06 -0.0889649 -0.0428859 -3.3303e-06 -0.0891948 -0.0431823 -3.3303e-06 -0.106249 -0.0435505 -3.3303e-06 -0.101327 -0.0432505 -3.3303e-06 -0.106785 -0.0454235 -3.3303e-06 -0.158842 -0.0459661 -3.3303e-06 -0.156817 -0.043941 -3.3303e-06 -0.15331 -0.0468988 -3.3303e-06 -0.161907 -0.0464591 -3.3303e-06 -0.165532 -0.0484807 -3.3303e-06 -0.190529 -0.046528 -3.3303e-06 -0.166073 -0.0497141 -3.3303e-06 -0.212846 -0.0486437 -3.3303e-06 -0.204354 -0.0471878 -3.3303e-06 -0.207559 -0.0499839 -3.3303e-06 -0.269282 -0.0528559 -3.3303e-06 -0.269724 -0.052481 -3.3303e-06 -0.262931 -0.0503628 -3.3303e-06 -0.243187 -0.0502643 -3.3303e-06 -0.224145 -0.0518452 -3.3303e-06 -0.267381 -0.0525018 -3.3303e-06 -0.275214 -0.0530075 -3.3303e-06 -0.281628 -0.0519593 -3.3303e-06 -0.277239 -0.0497639 -3.3303e-06 -0.281614 -0.049681 -3.3303e-06 -0.281572 -0.0504769 -3.3303e-06 -0.278721 -0.0484519 -3.3303e-06 -0.279264 -0.0464269 -3.3303e-06 -0.278721 -0.0449445 -3.3303e-06 -0.277239 -0.0444018 -3.3303e-06 -0.275214 -0.0449444 -3.3303e-06 -0.273189 -0.0486448 -3.3303e-06 -0.269517 -0.0530074 -3.3303e-06 -0.272467 -0.0519592 -3.3303e-06 -0.273189 -0.0436784 -3.3303e-06 -0.219587 -0.0475465 -3.3303e-06 -0.218529 -0.0473166 -3.3303e-06 -0.220032 -0.0487714 -3.3303e-06 -0.22112 -0.0492621 -3.3303e-06 -0.221891 -0.0407567 -3.3303e-06 -0.210341 -0.041026 -3.3303e-06 -0.214061 -0.0415686 -3.3303e-06 -0.216086 -0.047101 -3.3303e-06 -0.210553 -0.045076 -3.3303e-06 -0.210011 -0.0454847 -3.3303e-06 -0.20831 -0.0449398 -3.3303e-06 -0.208362 -0.0398911 -3.3303e-06 -0.160325 -0.0384086 -3.3303e-06 -0.154793 -0.0392739 -3.3303e-06 -0.151767 -0.039891 -3.3303e-06 -0.15331 -0.0417772 -3.3303e-06 -0.151119 -0.041916 -3.3303e-06 -0.152768 -0.0423209 -3.3303e-06 -0.151067 -0.043254 -3.3303e-06 -0.150781 -0.0373143 -3.3303e-06 -0.153454 -0.0377132 -3.3303e-06 -0.160668 -0.0377588 -3.3303e-06 -0.152918 -0.0378661 -3.3303e-06 -0.156818 -0.0368019 -3.3303e-06 -0.0921357 -0.0345071 -3.3303e-06 -0.093608 -0.0351358 -3.3303e-06 -0.0955051 -0.0330652 -3.3303e-06 -0.0987027 -0.0351359 -3.3303e-06 -0.0995551 -0.0364364 -3.3303e-06 -0.102786 -0.0391299 -3.3303e-06 -0.103209 -0.0409191 -3.3303e-06 -0.103489 -0.0327891 -3.3303e-06 -0.0317587 -0.0356 -3.3303e-06 -0.0372856 -0.0378331 -3.3303e-06 -0.0305618 -0.0291029 -3.3303e-06 -0.0267729 -0.0308508 -3.3303e-06 -0.0255389 -0.0278697 -3.3303e-06 -0.0245153 -0.0303517 -3.3303e-06 -0.0236764 0.0151311 -3.3303e-06 0.0312272 0.0150756 -3.3303e-06 0.0338619 0.0391204 -3.3303e-06 0.0338616 0.0357546 -3.3303e-06 -0.00168275 0.0562311 -3.3303e-06 -0.0307766 -0.0430511 -3.3303e-06 -0.217568 -0.0485834 -3.3303e-06 -0.212035 -0.0308507 -3.3303e-06 -0.0218139 -0.0327557 -3.3303e-06 -0.0114634 -0.037853 -3.3303e-06 -0.0114546 -0.0378017 -3.3303e-06 -0.0236763 -0.0373026 -3.3303e-06 -0.0255388 -0.0359392 -3.3303e-06 -0.0269023 -0.0324721 -3.3303e-06 -0.0305619 -0.0340767 -3.3303e-06 -0.0274014 0.0455935 -3.3303e-06 0.0414942 0.0382953 -3.3303e-06 0.0457771 0.0150758 -3.3303e-06 0.0483182 0.0558619 -0.00125111 -0.0791614 0.0570953 -0.00589124 -0.0734571 0.0571112 -0.00595883 -0.0733839 0.057275 -0.00900333 -0.071551 0.0572812 -0.0068279 -0.0725454 0.0559736 -0.0016953 -0.0786292 0.0558538 -0.00132552 -0.0791849 0.0547735 -0.00900333 -0.0812266 0.0546208 -0.00813822 -0.0826733 -0.0349283 -0.00900333 -0.102242 -0.0428748 -0.00900333 -0.119828 0.0262334 -0.00900333 -0.0108663 -0.0350538 -0.00900333 -0.0927222 -0.00255536 -0.00900333 -0.0540867 0.0416329 -0.00900333 -0.104391 -0.0399212 -0.00900333 -0.0839261 -0.0353223 -0.00900333 -0.0373989 -0.0393717 -0.00900333 -0.10359 -0.038689 -0.00900333 -0.10353 -0.0399171 -0.00900333 -0.0860851 -0.0398568 -0.00900333 -0.0852757 -0.03988 -0.00900333 -0.0843218 -0.0434352 -0.00900333 -0.271923 0.000544641 -0.00900333 -0.0540868 0.0322717 -0.00900333 -0.161018 -0.00100536 -0.00900333 -0.0545021 0.0267641 -0.00900333 -0.167231 0.0171456 -0.00900333 -0.21801 0.0298136 -0.00900333 -0.172225 0.0108632 -0.00900333 -0.0262361 -5.03036e-06 -0.00900333 -0.0283978 -0.0200868 -0.00900333 -0.0200794 -0.00255529 -0.00900333 -0.0487174 -0.0398908 -0.00900333 -0.0842001 -0.0399049 -0.00900333 -0.0840629 -0.0413941 -0.00900333 -0.104735 -0.0411462 -0.00900333 -0.10448 -0.0399595 -0.00900333 -0.103752 0.0442353 -0.00900333 -0.103128 0.00167933 -0.00900333 -0.0529521 0.0586185 -0.00900333 -0.0618902 0.0570732 -0.00900333 -0.070675 0.0570868 -0.00900333 -0.0708297 -0.0284047 -0.00900333 2.55959e-06 -0.0340915 -0.00900333 0.00463316 -0.0262427 -0.00900333 0.0108707 -0.0301609 -0.00900333 0.0165539 -0.0200862 -0.00900333 0.0200843 -0.0222153 -0.00900333 0.026271 -0.0108725 -0.00900333 0.0262405 0.00109589 -0.00900333 0.0343846 0.0108639 -0.00900333 0.0262402 0.0200774 -0.00900333 0.0200838 0.0238404 -0.00900333 0.0247968 0.0262337 -0.00900333 0.0108701 0.0354869 -0.00900333 -0.0018182 -0.0398447 -0.00900333 -0.151186 0.0426079 -0.00900333 -0.114268 0.0336403 -0.00900333 -0.161063 0.0349045 -0.00900333 -0.16103 -0.0400396 -0.00900333 -0.0868721 -0.0399954 -0.00900333 -0.0866283 -0.0399524 -0.00900333 -0.0863573 -0.042466 -0.00900333 -0.274803 0.00310752 -0.00900333 -0.280869 0.0108611 -0.00900333 -0.266967 0.0218087 -0.00900333 -0.216858 0.0205912 -0.00900333 -0.216999 0.0466032 -0.00900333 -0.118353 0.0364191 -0.00900333 -0.160324 0.0410738 -0.00900333 -0.143268 0.00651707 -0.00900333 -0.267823 0.0153445 -0.00900333 -0.226099 0.00420173 -0.00900333 -0.271684 0.0490628 -0.00900333 -0.10199 0.0518632 -0.00900333 -0.0948397 -0.0441389 -0.00900333 -0.14753 0.0459151 -0.00900333 -0.116122 0.0439586 -0.00900333 -0.114803 0.0553556 -0.00900333 -0.078017 0.0457647 -0.00900333 -0.103005 -0.0404781 -0.00900333 -0.162643 -0.0378199 -0.00900333 -0.161202 -0.0391985 -0.00900333 -0.212854 -0.0393549 -0.00900333 -0.215869 -0.0427337 -0.00900333 -0.163091 0.0333704 -0.00900333 -0.175322 0.0320334 -0.00900333 -0.173285 0.0334377 -0.00900333 -0.176503 0.0292391 -0.00900333 -0.194415 -0.0420983 -0.00900333 -0.162891 -0.0414985 -0.00900333 -0.162803 -0.04347 -0.00900333 -0.208279 -0.044601 -0.00900333 -0.207802 -0.044125 -0.00900333 -0.164089 -0.0455249 -0.00900333 -0.180088 -0.0438824 -0.00900333 -0.163834 -0.0432335 -0.00900333 -0.163342 -0.0499051 -0.00900333 -0.245278 0.0146793 -0.00900333 -0.265258 0.0135697 -0.00900333 -0.26646 0.0129435 -0.00900333 -0.266792 0.0175026 -0.00900333 -0.228207 -0.0459237 -0.00900333 -0.206546 -0.0464048 -0.00900333 -0.205363 -0.0498723 -0.00900333 -0.269004 -0.040959 -0.00900333 -0.218425 -0.0436049 -0.00900333 -0.219877 -0.045691 -0.00900333 -0.269887 -0.044176 -0.00900333 -0.219993 -0.048655 -0.00900333 -0.269217 -0.051752 -0.00900333 -0.266054 -0.0509003 -0.00900333 -0.268318 -0.0515644 -0.00900333 -0.267275 -0.046564 -0.00900333 -0.2212 -0.0456268 -0.00900333 -0.22048 -0.0475035 -0.00900333 -0.223226 -0.0489816 -0.00900333 -0.236442 -0.0444069 -0.00900333 -0.220034 0.0531153 -0.00473794 -0.0909125 0.0545055 -0.00900333 -0.0827522 0.0515183 -0.00029697 -0.0991247 0.0522388 -0.00470003 -0.0949471 0.051334 -0.00465943 -0.0991067 0.0230809 -0.00800333 -0.222998 0.0250282 -0.00800333 -0.218776 0.0227325 -0.00800333 -0.221698 0.0214446 -0.00800333 -0.218602 0.0199388 -0.00800333 -0.218531 0.0204809 -0.00800333 -0.220398 0.0191809 -0.00800333 -0.220746 0.0182292 -0.00800333 -0.221698 0.0191808 -0.00800333 -0.22525 0.0204808 -0.00800333 -0.225598 0.0241481 -0.00800333 -0.219177 0.0217809 -0.00800333 -0.220746 -0.0437761 -0.00800333 -0.216312 -0.0428243 -0.00800333 -0.212761 -0.0473277 -0.00800333 -0.212761 -0.0473211 -0.00800333 -0.20943 -0.0478468 -0.00800333 -0.209268 -0.046376 -0.00800333 -0.211809 -0.0484402 -0.00800333 -0.210706 -0.0480537 -0.00800333 -0.209104 -0.0481744 -0.00800333 -0.208956 -0.0483365 -0.00800333 -0.208382 -0.0485365 -0.00800333 -0.218662 -0.04846 -0.00800333 -0.218605 -0.0481598 -0.00800333 -0.218464 -0.0473277 -0.00800333 -0.215361 -0.0463761 -0.00800333 -0.216312 -0.0419269 -0.00800333 -0.217275 0.038131 -0.00800333 -0.162553 0.0350112 -0.00800333 -0.168298 0.0350113 -0.00800333 -0.165698 0.0340596 -0.00800333 -0.164747 0.0372979 -0.00800333 -0.163318 0.0353596 -0.00800333 -0.166998 0.036912 -0.00800333 -0.167917 0.0379158 -0.00800333 -0.162979 0.037683 -0.00800333 -0.163177 0.0340596 -0.00800333 -0.16925 0.0355495 -0.00800333 -0.172516 0.0356406 -0.00800333 -0.17269 0.0314596 -0.00800333 -0.164747 0.0305079 -0.00800333 -0.165698 0.0314596 -0.00800333 -0.16925 0.0327596 -0.00800333 -0.169598 0.0317958 -0.00800333 -0.171394 0.0349087 -0.00800333 -0.172076 -0.0427958 -0.00800333 -0.0921662 -0.0363916 -0.00800333 -0.0988301 -0.0354941 -0.00800333 -0.100745 -0.0343469 -0.00800333 -0.0988685 -0.0342257 -0.00800333 -0.0966727 -0.0363916 -0.00800333 -0.0962301 -0.0369251 -0.00800333 -0.093371 -0.0383952 -0.00800333 -0.0930369 -0.0429321 -0.00800333 -0.101981 -0.0423451 -0.00800333 -0.101833 -0.0425885 -0.00800333 -0.0925175 -0.0432668 -0.00800333 -0.10232 -0.0430704 -0.00800333 -0.102084 0.0155578 -0.0200033 -0.26793 0.0147348 -0.0200033 -0.268766 0.0119148 -0.0200033 -0.271035 0.0119148 -0.0200033 -0.273635 0.0133826 -0.0200033 -0.278425 0.0122631 -0.0200033 -0.272335 0.0147881 -0.0200033 -0.272306 0.0151307 -0.0200033 -0.268607 0.0106269 -0.0200033 -0.267939 0.00966314 -0.0200033 -0.269735 0.00836314 -0.0200033 -0.270083 0.00912105 -0.0200033 -0.267868 0.00741146 -0.0200033 -0.271035 0.00563626 -0.0200033 -0.270326 0.00836308 -0.0200033 -0.274586 0.00730164 -0.0200033 -0.276165 0.00869932 -0.0200033 -0.27673 0.00966308 -0.0200033 -0.274935 0.0109631 -0.0200033 -0.274586 0.0129252 -0.0200033 -0.277718 -0.0526759 -0.0200033 -0.270029 -0.0525565 -0.0200033 -0.270187 -0.0533251 -0.0200033 -0.276607 -0.0462002 -0.0200033 -0.273914 -0.044968 -0.0200033 -0.272366 -0.0471518 -0.0200033 -0.272962 -0.0467337 -0.0200033 -0.271055 -0.0484518 -0.0200033 -0.272614 -0.0482038 -0.0200033 -0.270721 -0.0518456 -0.0200033 -0.27052 -0.0497518 -0.0200033 -0.272962 -0.0507035 -0.0200033 -0.273914 -0.0523335 -0.0200033 -0.27037 -0.0531155 -0.0200033 -0.279635 -0.0529048 -0.0200033 -0.279542 -0.0507035 -0.0200033 -0.276514 -0.0497519 -0.0200033 -0.277466 -0.0484519 -0.0200033 -0.277814 -0.0471519 -0.0200033 -0.277466 -0.0486999 -0.0200033 -0.279707 -0.03988 -0.0119033 -0.0843218 -0.0400214 -0.0114866 -0.0857424 -0.0399915 -0.0119033 -0.0866057 -0.0400823 -0.0117469 -0.0868442 -0.0399524 -0.0119033 -0.0863573 -0.0399954 -0.0119033 -0.0866283 -0.0400396 -0.0119033 -0.0868721 -0.0400899 -0.0119033 -0.087119 -0.000117767 -0.0239367 -0.118998 0.0188032 -0.0184033 -0.118998 0.0465232 -0.00900333 -0.118961 0.0344309 -0.000295703 -0.177086 0.030324 -0.000294258 -0.19581 0.025593 -0.00542313 -0.214421 -0.00250909 -0.0195033 -0.345668 -0.00433924 -0.0195033 -0.347498 -0.0025092 -0.0195033 -0.354328 -0.0145718 -0.0195033 -0.368695 -0.00433931 -0.0195033 -0.352498 -0.0173417 -0.0195033 -0.366161 -0.0204586 -0.0195033 -0.362438 0.0236908 -0.0195033 -0.350124 0.00432095 -0.0195033 -0.352498 0.0215982 -0.0195033 -0.359734 0.0121378 -0.0195033 -0.281149 0.0120272 -0.0195033 -0.281297 0.00705178 -0.0195033 -0.372621 0.00200569 -0.0195033 -0.373612 0.0118705 -0.0195033 -0.281395 -0.0524201 -0.0195033 -0.299928 -0.0515623 -0.0195033 -0.295275 -0.0493024 -0.0195033 -0.281681 0.0102585 -0.0195033 -0.291564 0.00853304 -0.0195033 -0.310916 0.00249091 -0.0195033 -0.345668 0.021616 -0.0195033 -0.3403 -0.0429511 -0.000293615 -0.106802 -0.0422575 -0.00900333 -0.106863 -0.0415801 -0.00470409 -0.150827 -0.0449791 -0.000296792 -0.148505 -0.0439763 -0.00496004 -0.149671 -0.0428448 -0.00481626 -0.150511 -0.0431301 -0.000300512 -0.150508 -0.0417699 -0.00030333 -0.150819 -0.0422275 -0.00900333 -0.150492 -0.0432288 -0.00900333 -0.149721 -0.0438861 -0.00900333 -0.148684 -0.0446838 -0.0050547 -0.148447 -0.0449159 -0.00459056 -0.147144 -0.0441384 -0.00900333 -0.147238 0.0342211 -0.00900333 -0.161103 0.0376392 -0.00900333 -0.158388 0.0371934 -0.00900333 -0.15946 0.0379196 -0.00739218 -0.158428 0.036165 -0.00900333 -0.160508 0.0353957 -0.00900333 -0.160893 0.0416329 -0.00030333 -0.104391 0.039924 -0.00030333 -0.106725 0.039924 -0.00900333 -0.106725 0.0395059 -0.00900333 -0.109588 0.0404756 -0.00900333 -0.112313 0.0617865 -0.0348033 0.0582976 0.0611823 -0.0290033 0.0589314 0.054601 -0.0290033 0.065077 0.0474948 -0.0290033 0.0704316 0.0381218 -0.0290033 0.0759158 0.0319334 -0.0290033 0.0787198 0.0836546 -0.0348033 -0.0147503 0.0848015 -0.0348033 -0.00493829 0.0846548 -0.0290033 0.00702167 0.0813769 -0.0348033 0.0243651 0.0836549 -0.0290033 0.0147525 0.0805995 -0.0290033 0.0268251 0.0779982 -0.0290033 0.0336482 0.0681363 -0.0348033 0.0507299 0.0724235 -0.0290033 0.0443944 0.0681363 -0.0290033 0.0507299 0.061785 -0.0290033 -0.0582948 0.0624405 -0.0290033 -0.0575921 0.068135 -0.0348033 -0.0507273 0.0791163 -0.0290033 -0.030923 0.0813762 -0.0348033 -0.0243628 0.061785 -0.0348033 -0.0582948 0.0290489 -0.0348033 -0.0798251 0.0290489 -0.0290033 -0.0798251 0.0381199 -0.0348033 -0.0759124 0.0466752 -0.0348033 -0.0709731 0.0545993 -0.0348033 -0.065074 -0.00986784 -0.0348033 -0.0843733 -5.7543e-06 -0.0290033 -0.0849478 0.0118394 -0.0290033 -0.0841181 -0.0290603 -0.0348033 -0.0798243 -0.0290603 -0.0290033 -0.0798243 -0.0582321 -0.0290033 -0.061853 -0.0546103 -0.0348033 -0.0650726 -0.0613018 -0.0290033 -0.0588124 -0.0466864 -0.0290033 -0.0709719 -0.0381311 -0.0348033 -0.0759114 -0.0722353 -0.0290033 -0.0447106 -0.0735741 -0.0290033 -0.0424719 -0.0653292 -0.0290033 -0.0543045 -0.0617958 -0.0348033 -0.0582932 -0.0640314 -0.0290033 -0.0558286 -0.0809237 -0.0290033 -0.0258552 -0.0735741 -0.0348033 -0.0424719 -0.0776078 -0.0290033 -0.0345557 -0.0751084 -0.0290033 -0.0396958 -0.0837301 -0.0290033 -0.0143701 -0.0836643 -0.0348033 -0.0147481 -0.081571 -0.0290033 -0.0237347 -0.0684595 -0.0290033 0.0503057 -0.073573 -0.0348033 0.0424781 -0.0780067 -0.0348033 0.0336502 -0.0780067 -0.0290033 0.0336502 -0.0836639 -0.0348033 0.0147547 -0.0848109 -0.0348033 0.00494268 0.0065761 -0.0290033 0.0846969 -0.00207044 -0.0290033 0.0849271 -0.00986568 -0.0348033 0.0843779 -0.0191499 -0.0290033 0.0827667 -0.0290583 -0.0348033 0.0798295 -0.0381292 -0.0348033 0.0759168 -0.0466845 -0.0348033 0.0709775 -0.0502071 -0.0290033 0.0685312 -0.0546086 -0.0348033 0.0650784 -0.0546086 -0.0290033 0.0650784 -0.0681444 -0.0348033 0.0507317 0.0593109 -0.00030333 -0.0462097 0.0586351 -0.00030333 -0.0410084 0.0559488 -0.00030333 -0.0308783 0.0593109 -0.00900333 -0.0462097 0.0559488 -0.00900333 -0.0308783 0.038223 -0.00900333 -0.00529191 0.038223 -0.00030333 -0.00529191 0.0487584 -0.00900333 -0.0169264 0.0455875 -0.00030333 -0.0127483 -0.0284185 -0.00900333 -0.0193889 -0.0284185 -0.00030333 -0.0193889 -0.0274181 -0.00030333 -0.0219001 -0.0274181 -0.00900333 -0.0219001 -0.0275814 -0.00900333 -0.0245983 -0.0108732 -0.0350033 -0.0262358 -0.0108732 -0.00900333 -0.0262358 -0.026243 -0.00900333 -0.0108657 -0.0200862 -0.0350033 0.0200843 -0.0108725 -0.0350033 0.0262405 0.0108639 -0.0350033 0.0262402 -4.30321e-06 -0.00900333 0.0284022 0.0283953 -0.00900333 1.83244e-06 0.0200769 -0.00900333 -0.0200799 -5.03036e-06 -0.0350033 -0.0283978 0.0322717 -0.00030333 -0.161018 0.0294174 -0.00900333 -0.162015 0.0274118 -0.00030333 -0.164278 0.0274118 -0.00900333 -0.164278 0.0276387 -0.00900333 -0.170125 0.0276387 -0.00030333 -0.170125 0.0298136 -0.00030333 -0.172225 0.0314508 -0.00468411 -0.172854 0.0309236 -0.00900333 -0.17271 0.0175026 -0.00030333 -0.228207 0.0144845 -0.00900333 -0.223208 0.0151401 -0.00030333 -0.220264 0.0151401 -0.00900333 -0.220264 0.019994 -0.00030333 -0.217018 0.019994 -0.00900333 -0.217018 0.0415879 -0.0211325 -0.111263 0.0415821 -0.00800333 -0.111253 0.0427326 -0.0203835 -0.112565 0.044607 -0.0206862 -0.104583 0.0449348 -0.00800333 -0.104531 0.0428826 -0.00800333 -0.105321 0.0415002 -0.0217402 -0.106892 0.0322175 -0.00800333 -0.162531 0.0303981 -0.00800333 -0.170829 0.0288649 -0.00800333 -0.169252 0.0282617 -0.00800333 -0.167138 0.0283721 -0.0188473 -0.167998 0.0301654 -0.00800333 -0.163321 0.0301329 -0.0188024 -0.163344 0.0287327 -0.00800333 -0.16499 0.0287575 -0.0191215 -0.164941 0.015983 -0.00800333 -0.223138 0.016454 -0.00800333 -0.220989 0.0170041 -0.0167399 -0.220141 0.0178866 -0.00800333 -0.219321 0.0165862 -0.00800333 -0.225252 0.0181194 -0.00800333 -0.226829 0.0181726 -0.0145018 -0.226861 0.0160894 -0.0168578 -0.22398 0.0169175 -0.0160018 -0.225746 0.00516311 -0.0298347 -0.272335 0.00642628 -0.0293356 -0.269209 0.00621088 -0.029457 -0.269448 0.00516527 -0.0200033 -0.272474 0.00706889 -0.0200033 -0.268658 0.00682324 -0.0287063 -0.275826 0.00544729 -0.0295978 -0.273909 0.00576841 -0.0200033 -0.274589 0.00577525 -0.0293915 -0.274601 0.0578957 -3.3303e-06 0.027864 0.0565323 0.00209667 0.0292274 0.0528073 0.00209667 0.0292275 0.0528073 -3.3303e-06 0.0292275 0.0514438 -3.3303e-06 0.027864 0.0514438 0.00209667 0.027864 0.0509447 0.00209667 0.0260015 0.0546697 -3.3303e-06 0.0222765 0.0565322 0.00209667 0.0227755 0.0565322 -3.3303e-06 0.0227755 0.0578956 -3.3303e-06 0.024139 0.0578956 0.00209667 0.024139 0.0583947 0.00209667 0.0260014 0.0578957 0.00209667 0.027864 -0.00112289 -3.3303e-06 0.041722 -0.00484785 -3.3303e-06 0.045447 -0.00484785 0.00209667 0.045447 -0.00671035 -3.3303e-06 0.044948 -0.00671035 0.00209667 0.044948 -0.00671043 -3.3303e-06 0.0384961 -0.00671043 0.00209667 0.0384961 -0.00298543 0.00209667 0.038496 -0.00162197 -3.3303e-06 0.0398595 -0.0308507 0.00209667 -0.0218139 -0.0322141 -3.3303e-06 -0.0204504 -0.0340766 -3.3303e-06 -0.0199514 -0.0359391 -3.3303e-06 -0.0204504 -0.0359391 0.00209667 -0.0204504 -0.0373026 -3.3303e-06 -0.0218138 -0.0373026 0.00209667 -0.0218138 -0.0340767 0.00209667 -0.0274014 -0.0322142 -3.3303e-06 -0.0269023 -0.0303517 0.00209667 -0.0236764 0.0653806 0.00209667 -0.0281361 0.0640172 0.00209667 -0.0267727 0.0621547 0.00209667 -0.0262736 0.0621547 -3.3303e-06 -0.0262736 0.0602922 -3.3303e-06 -0.0267726 0.0584296 0.00209667 -0.0299986 0.0589287 -3.3303e-06 -0.0281361 0.0584296 -3.3303e-06 -0.0299986 0.0589287 0.00209667 -0.0318611 0.0589287 -3.3303e-06 -0.0318611 0.0602921 -3.3303e-06 -0.0332245 0.0621546 0.00209667 -0.0337236 0.0621546 -3.3303e-06 -0.0337236 0.0653806 0.00209667 -0.0318611 0.0658796 -3.3303e-06 -0.0299986 0.0658796 0.00209667 -0.0299986 0.0172333 -0.00250333 -0.221123 0.0172333 -0.00030333 -0.221123 0.0186059 -0.00030333 -0.21975 0.0204809 -0.00030333 -0.219248 0.0237285 -0.00250333 -0.221123 0.0242309 -0.00250333 -0.222998 0.0237284 -0.00030333 -0.224873 0.0223558 -0.00250333 -0.226246 0.0204808 -0.00250333 -0.226748 0.0204808 -0.00030333 -0.226748 0.0186058 -0.00030333 -0.226246 0.0172332 -0.00250333 -0.224873 0.0167309 -0.00250333 -0.222998 0.0172332 -0.00030333 -0.224873 -0.0456661 -0.00030333 -0.156817 -0.0451636 -0.00250333 -0.154942 -0.043791 -0.00250333 -0.15357 -0.043791 -0.00030333 -0.15357 -0.041916 -0.00030333 -0.153067 -0.040041 -0.00030333 -0.15357 -0.0386684 -0.00250333 -0.154943 -0.0381661 -0.00250333 -0.156818 -0.0381661 -0.00030333 -0.156818 -0.0386685 -0.00250333 -0.158693 -0.0386685 -0.00030333 -0.158693 -0.0400411 -0.00250333 -0.160065 -0.0400411 -0.00030333 -0.160065 -0.0419161 -0.00030333 -0.160568 -0.0451637 -0.00250333 -0.158692 -0.0437911 -0.00030333 -0.160065 -0.0451637 -0.00030333 -0.158692 0.0308846 -0.00250333 -0.163751 0.0327596 -0.00250333 -0.163248 0.0308846 -0.00030333 -0.163751 0.0346346 -0.00030333 -0.163751 0.0360072 -0.00250333 -0.165123 0.0365096 -0.00030333 -0.166998 0.0360072 -0.00030333 -0.168873 0.0346345 -0.00250333 -0.170246 0.0346345 -0.00030333 -0.170246 0.0327595 -0.00030333 -0.170748 0.0308845 -0.00250333 -0.170246 0.029512 -0.00250333 -0.168873 0.029512 -0.00030333 -0.168873 0.0290096 -0.00250333 -0.166998 -0.0405182 -0.00250333 -0.0942825 -0.0418908 -0.00030333 -0.095655 -0.0386432 -0.00250333 -0.0937801 -0.0353957 -0.00250333 -0.0994051 -0.0353957 -0.00030333 -0.0994051 -0.0367683 -0.00030333 -0.100778 -0.0386433 -0.00250333 -0.10128 -0.0405183 -0.00250333 -0.100778 -0.0423933 -0.00250333 -0.09753 -0.0516994 -0.00250333 -0.273339 -0.0503268 -0.00250333 -0.271966 -0.0484518 -0.00250333 -0.271464 -0.0484518 -0.00030333 -0.271464 -0.0465768 -0.00250333 -0.271966 -0.0452042 -0.00250333 -0.273339 -0.0447018 -0.00030333 -0.275214 -0.0452043 -0.00030333 -0.277089 -0.0465769 -0.00250333 -0.278462 -0.0484519 -0.00250333 -0.278964 -0.0503269 -0.00250333 -0.278462 -0.0503269 -0.00030333 -0.278462 -0.0522018 -0.00030333 -0.275214 0.00591311 -0.00030333 -0.272335 0.00641554 -0.00030333 -0.27046 0.00966316 -0.00250333 -0.268585 0.00966316 -0.00030333 -0.268585 0.0115382 -0.00030333 -0.269087 0.0134131 -0.00030333 -0.272335 0.0129107 -0.00030333 -0.27421 0.0115381 -0.00250333 -0.275582 0.0115381 -0.00030333 -0.275582 0.00778807 -0.00030333 -0.275582 0.00591311 -0.00250333 -0.272335 -0.046951 -0.00030333 -0.210813 -0.045076 -0.00030333 -0.210311 -0.0418284 -0.00250333 -0.212186 -0.0418284 -0.00030333 -0.212186 -0.041326 -0.00250333 -0.214061 -0.041326 -0.00030333 -0.214061 -0.0418285 -0.00030333 -0.215936 -0.0450761 -0.00250333 -0.217811 -0.0450761 -0.00030333 -0.217811 -0.0469511 -0.00030333 -0.217308 -0.0483236 -0.00250333 -0.215935 -0.0483236 -0.00030333 -0.215935 0.0417268 -0.00250333 -0.108998 0.0422293 -0.00250333 -0.107123 0.0436019 -0.00250333 -0.105751 0.0454769 -0.00250333 -0.105248 0.0454769 -0.00030333 -0.105248 0.0473519 -0.00030333 -0.105751 0.0487245 -0.00030333 -0.107123 0.0492268 -0.00030333 -0.108998 0.0487244 -0.00030333 -0.110873 0.0436018 -0.00250333 -0.112246 0.0422292 -0.00030333 -0.110873 0.0191809 -0.00250333 -0.220746 0.0178809 -0.00800333 -0.222998 0.0182292 -0.00800333 -0.224298 0.0191808 -0.00250333 -0.22525 0.0204808 -0.00250333 -0.225598 0.0217808 -0.00800333 -0.22525 0.0230809 -0.00250333 -0.222998 0.0227325 -0.00800333 -0.224298 -0.043776 -0.00250333 -0.211809 -0.045076 -0.00250333 -0.211461 -0.043776 -0.00800333 -0.211809 -0.045076 -0.00800333 -0.211461 -0.046376 -0.00250333 -0.211809 -0.047676 -0.00800333 -0.214061 -0.0463761 -0.00250333 -0.216312 -0.0450761 -0.00800333 -0.216661 -0.0437761 -0.00250333 -0.216312 -0.0428244 -0.00800333 -0.215361 -0.042476 -0.00800333 -0.214061 0.0353596 -0.00250333 -0.166998 0.0340596 -0.00250333 -0.164747 0.0327596 -0.00800333 -0.164398 0.0305079 -0.00250333 -0.165698 0.0301596 -0.00800333 -0.166998 0.0305079 -0.00800333 -0.168298 0.0350112 -0.00250333 -0.168298 -0.0393161 -0.00800333 -0.156818 -0.040616 -0.00250333 -0.154566 -0.040616 -0.00800333 -0.154566 -0.041916 -0.00800333 -0.154217 -0.0441678 -0.00250333 -0.158117 -0.0432161 -0.00800333 -0.159069 -0.0406161 -0.00800333 -0.159069 -0.0396644 -0.00250333 -0.158118 0.0480768 -0.00250333 -0.108998 0.0480768 -0.00800333 -0.108998 0.0477285 -0.00250333 -0.107698 0.0467769 -0.00250333 -0.106747 0.0454769 -0.00800333 -0.106398 0.0454769 -0.00250333 -0.106398 0.0432252 -0.00250333 -0.107698 0.0441768 -0.00250333 -0.11125 0.0441768 -0.00800333 -0.11125 0.0454768 -0.00250333 -0.111598 0.0477285 -0.00800333 -0.110298 -0.0373432 -0.00250333 -0.0952784 -0.0373432 -0.00800333 -0.0952784 -0.0386432 -0.00800333 -0.0949301 -0.0399432 -0.00800333 -0.0952784 -0.0408949 -0.00250333 -0.0962301 -0.0408949 -0.00800333 -0.0962301 -0.0412433 -0.00250333 -0.0975301 -0.0412433 -0.00800333 -0.0975301 -0.0408949 -0.00800333 -0.0988301 -0.0399433 -0.00250333 -0.0997817 -0.0399433 -0.00800333 -0.0997817 -0.0386433 -0.00250333 -0.10013 -0.0373433 -0.00250333 -0.0997818 -0.0386433 -0.00800333 -0.10013 -0.0373433 -0.00800333 -0.0997818 -0.0360433 -0.00250333 -0.0975301 -0.0360433 -0.00800333 -0.0975301 0.0119148 -0.00250333 -0.271035 0.0109631 -0.0200033 -0.270083 0.00706311 -0.0200033 -0.272335 0.00706311 -0.00250333 -0.272335 0.00741143 -0.0200033 -0.273635 0.0119148 -0.00250333 -0.273635 -0.0484518 -0.00250333 -0.272614 -0.0497518 -0.00250333 -0.272962 -0.0510518 -0.00250333 -0.275214 -0.0510518 -0.0200033 -0.275214 -0.0497519 -0.00250333 -0.277466 -0.0484519 -0.00250333 -0.277814 -0.0462002 -0.00250333 -0.276514 -0.0462002 -0.0200033 -0.276514 -0.0458518 -0.0200033 -0.275214 -0.0358953 -0.0136033 -0.0226263 -0.032258 -0.0136033 -0.0226264 -0.0340766 -0.0136033 -0.0215764 -0.0330267 -0.0136033 -0.0218577 -0.032258 -0.0136033 -0.0247264 -0.0319767 -0.0136033 -0.0236764 -0.0340767 -0.0148651 -0.0236764 -0.0351267 -0.0136033 -0.025495 -0.0330267 -0.0136033 -0.025495 -0.0358953 0.00239667 -0.0226263 -0.0351267 -0.0136033 -0.0218577 -0.0340766 0.00239667 -0.0215764 -0.0330267 0.00239667 -0.0218577 -0.032258 0.00239667 -0.0226264 -0.0319767 0.00239667 -0.0236764 -0.0330267 0.00239667 -0.025495 -0.0340767 0.00239667 -0.0257764 -0.0340767 -0.0136033 -0.0257764 -0.0358953 0.00239667 -0.0247263 -0.0358953 -0.0136033 -0.0247263 -0.0361767 -0.0136033 -0.0236763 -0.00484789 -0.0148651 0.041722 -0.00379787 -0.0136033 0.0435407 -0.00666653 0.00239667 0.042772 -0.00666653 -0.0136033 0.042772 -0.00589787 -0.0136033 0.0435407 -0.00589787 0.00239667 0.0435407 -0.00484787 -0.0136033 0.043822 -0.00302923 -0.0136033 0.042772 -0.00302923 0.00239667 0.042772 -0.00274789 -0.0136033 0.041722 -0.00274789 0.00239667 0.041722 -0.00302925 -0.0136033 0.040672 -0.00302925 0.00239667 0.040672 -0.00379792 -0.0136033 0.0399033 -0.00379792 0.00239667 0.0399033 -0.00484792 -0.0136033 0.039622 -0.00589792 -0.0136033 0.0399034 -0.00484792 0.00239667 0.039622 -0.00666656 0.00239667 0.040672 -0.00666656 -0.0136033 0.040672 -0.00694789 -0.0136033 0.041722 0.0536197 -0.0136033 0.0278202 0.0564884 -0.0136033 0.0270515 0.0564884 -0.0136033 0.0249515 0.0567697 -0.0136033 0.0260015 0.0536197 -0.0136033 0.0241829 0.0546697 -0.0136033 0.0239015 0.0546697 -0.0148651 0.0260015 0.0525697 -0.0136033 0.0260015 0.0528511 -0.0136033 0.0270515 0.0525697 0.00239667 0.0260015 0.0528511 0.00239667 0.0270515 0.0536197 0.00239667 0.0278202 0.0546697 -0.0136033 0.0281015 0.0557197 -0.0136033 0.0278201 0.0557197 0.00239667 0.0278201 0.0567697 0.00239667 0.0260015 0.0557197 -0.0136033 0.0241828 0.0557197 0.00239667 0.0241828 0.0546697 0.00239667 0.0239015 0.0528511 -0.0136033 0.0249515 0.0639733 -0.0136033 -0.0289486 0.0621546 -0.0148651 -0.0299986 0.0642546 -0.0136033 -0.0299986 0.0632046 -0.0136033 -0.0318173 0.060336 -0.0136033 -0.0289486 0.0611047 -0.0136033 -0.0281799 0.0621547 -0.0136033 -0.0278986 0.0611047 0.00239667 -0.0281799 0.0632047 -0.0136033 -0.02818 0.0642546 0.00239667 -0.0299986 0.0639733 -0.0136033 -0.0310486 0.0639733 0.00239667 -0.0310486 0.0632046 0.00239667 -0.0318173 0.0621546 -0.0136033 -0.0320986 0.0621546 0.00239667 -0.0320986 0.0611046 -0.0136033 -0.0318172 0.060336 0.00239667 -0.0310486 0.060336 -0.0136033 -0.0310486 0.0600546 -0.0136033 -0.0299986 0.0499081 -0.0260033 0.0653233 0.0459894 -0.0260033 0.0663733 0.0478081 -0.0247415 0.0653233 0.0478081 -0.0260033 0.0674233 0.0457081 -0.0260033 0.0653233 0.0496267 -0.0260033 0.0642733 0.046758 -0.0260033 0.0635046 0.0496267 -0.0260033 0.0663733 0.0499081 -0.0350033 0.0653233 0.0496267 -0.0350033 0.0663733 0.0488581 -0.0350033 0.0671419 0.0488581 -0.0260033 0.0671419 0.0467581 -0.0260033 0.067142 0.0467581 -0.0350033 0.067142 0.0459894 -0.0350033 0.0663733 0.0457081 -0.0350033 0.0653233 0.0459894 -0.0260033 0.0642733 0.046758 -0.0350033 0.0635046 0.047808 -0.0260033 0.0632233 0.048858 -0.0260033 0.0635046 0.048858 -0.0350033 0.0635046 0.0496267 -0.0350033 0.0642733 0.0673347 -0.0247415 0.0449279 0.065516 -0.0260033 0.0438779 0.0652347 -0.0260033 0.0449279 0.0691533 -0.0260033 0.0459778 0.0683847 -0.0260033 0.0467465 0.0691533 -0.0350033 0.0459778 0.0673347 -0.0260033 0.0470279 0.0662847 -0.0350033 0.0467465 0.0662847 -0.0260033 0.0467465 0.065516 -0.0260033 0.0459779 0.065516 -0.0350033 0.0459779 0.0662847 -0.0260033 0.0431092 0.0673347 -0.0260033 0.0428279 0.0683847 -0.0260033 0.0431092 0.0683847 -0.0350033 0.0431092 0.0691533 -0.0260033 0.0438778 0.0694347 -0.0260033 0.0449278 0.0691533 -0.0350033 0.0438778 0.0758816 -0.0260033 0.0337155 0.0730129 -0.0260033 0.0344842 0.0740629 -0.0247415 0.0326655 0.0751129 -0.0260033 0.0344842 0.0730129 -0.0260033 0.0308469 0.0722443 -0.0260033 0.0337156 0.0719629 -0.0260033 0.0326656 0.0758816 -0.0260033 0.0316155 0.0740629 -0.0260033 0.0305655 0.0751129 -0.0260033 0.0308469 0.0761629 -0.0260033 0.0326655 0.0751129 -0.0350033 0.0344842 0.074063 -0.0260033 0.0347655 0.074063 -0.0350033 0.0347655 0.0730129 -0.0350033 0.0344842 0.0722443 -0.0350033 0.0337156 0.0719629 -0.0350033 0.0326656 0.0722443 -0.0260033 0.0316156 0.0722443 -0.0350033 0.0316156 0.0740629 -0.0350033 0.0305655 0.0751129 -0.0350033 0.0308469 0.0758816 -0.0350033 0.0316155 0.0825944 -0.0260033 0.00628927 0.0807757 -0.0247415 0.00523929 0.0818258 -0.0260033 0.00705793 0.0789571 -0.0260033 0.00418931 0.0786757 -0.0260033 0.00523932 0.0807757 -0.0260033 0.00313929 0.0828758 -0.0260033 0.00523926 0.0825944 -0.0350033 0.00628927 0.0818258 -0.0350033 0.00705793 0.0807758 -0.0260033 0.00733929 0.0797258 -0.0260033 0.00705796 0.0789571 -0.0260033 0.00628931 0.0789571 -0.0350033 0.00418931 0.0797257 -0.0260033 0.00342065 0.0797257 -0.0350033 0.00342065 0.0807757 -0.0350033 0.00313929 0.0818257 -0.0260033 0.00342062 0.0825944 -0.0260033 0.00418927 0.0653164 -0.0247415 -0.0478105 0.0653164 -0.0260033 -0.0457105 0.0642664 -0.0260033 -0.0459919 0.0642664 -0.0260033 -0.0496292 0.0634978 -0.0260033 -0.0467605 0.0632164 -0.0260033 -0.0478105 0.0663664 -0.0260033 -0.0496292 0.0653164 -0.0260033 -0.0499105 0.0671351 -0.0260033 -0.0467606 0.0671351 -0.0350033 -0.0467606 0.0663664 -0.0260033 -0.0459919 0.0663664 -0.0350033 -0.0459919 0.0653164 -0.0350033 -0.0457105 0.0642664 -0.0350033 -0.0459919 0.0634978 -0.0260033 -0.0488605 0.0653164 -0.0350033 -0.0499105 0.0663664 -0.0350033 -0.0496292 0.0671351 -0.0260033 -0.0488606 0.0674164 -0.0260033 -0.0478106 0.0674164 -0.0350033 -0.0478106 0.0467397 -0.0260033 -0.0662872 0.043871 -0.0260033 -0.0655185 0.043871 -0.0260033 -0.0691558 0.0431023 -0.0260033 -0.0683871 0.044921 -0.0247415 -0.0673371 0.045971 -0.0260033 -0.0691558 0.0467397 -0.0350033 -0.0662872 0.045971 -0.0260033 -0.0655185 0.045971 -0.0350033 -0.0655185 0.044921 -0.0260033 -0.0652371 0.043871 -0.0350033 -0.0655185 0.0431024 -0.0260033 -0.0662871 0.0431024 -0.0350033 -0.0662871 0.042821 -0.0260033 -0.0673371 0.044921 -0.0260033 -0.0694371 0.0467396 -0.0260033 -0.0683872 0.047021 -0.0260033 -0.0673372 0.0344774 -0.0260033 -0.0730154 0.0316087 -0.0260033 -0.0722467 0.0326587 -0.0247415 -0.0740654 0.03084 -0.0260033 -0.0730154 0.0305587 -0.0260033 -0.0740654 0.0344773 -0.0260033 -0.0751154 0.0326587 -0.0260033 -0.0761654 0.0337087 -0.0260033 -0.0758841 0.0337087 -0.0260033 -0.0722468 0.0337087 -0.0350033 -0.0722468 0.0326587 -0.0260033 -0.0719654 0.0305587 -0.0350033 -0.0740654 0.03084 -0.0260033 -0.0751154 0.03084 -0.0350033 -0.0751154 0.0316087 -0.0260033 -0.075884 0.0326587 -0.0350033 -0.0761654 0.0347587 -0.0260033 -0.0740654 0.00705109 -0.0260033 -0.0797282 0.00733243 -0.0260033 -0.0807782 0.00523243 -0.0247415 -0.0807782 0.00523246 -0.0260033 -0.0786782 0.0062824 -0.0260033 -0.0825969 0.0041824 -0.0260033 -0.0825969 0.00733243 -0.0350033 -0.0807782 0.00628245 -0.0260033 -0.0789596 0.00705109 -0.0350033 -0.0797282 0.00523246 -0.0350033 -0.0786782 0.00418245 -0.0260033 -0.0789596 0.00341379 -0.0260033 -0.0797282 0.00313243 -0.0260033 -0.0807782 0.00341376 -0.0260033 -0.0818282 0.00313243 -0.0350033 -0.0807782 0.00341376 -0.0350033 -0.0818282 0.0052324 -0.0260033 -0.0828782 0.0062824 -0.0350033 -0.0825969 0.00705107 -0.0260033 -0.0818282 0.00705107 -0.0350033 -0.0818282 -0.049636 -0.0260033 -0.0642689 -0.0488674 -0.0260033 -0.0635002 -0.0478174 -0.0247415 -0.0653189 -0.0499174 -0.0260033 -0.0653189 -0.0467674 -0.0260033 -0.0671376 -0.0459988 -0.0260033 -0.0663689 -0.0457174 -0.0260033 -0.0653189 -0.0459987 -0.0260033 -0.0642689 -0.0459987 -0.0350033 -0.0642689 -0.0467674 -0.0260033 -0.0635003 -0.0467674 -0.0350033 -0.0635003 -0.0478174 -0.0260033 -0.0632189 -0.0488674 -0.0350033 -0.0635002 -0.0496361 -0.0260033 -0.0663689 -0.0499174 -0.0350033 -0.0653189 -0.0496361 -0.0350033 -0.0663689 -0.0488674 -0.0260033 -0.0671375 -0.0478174 -0.0260033 -0.0674189 -0.0467674 -0.0350033 -0.0671376 -0.066294 -0.0260033 -0.0431048 -0.066294 -0.0260033 -0.0467421 -0.067344 -0.0260033 -0.0470235 -0.067344 -0.0247415 -0.0449235 -0.0655253 -0.0260033 -0.0438735 -0.066294 -0.0350033 -0.0431048 -0.067344 -0.0260033 -0.0428235 -0.068394 -0.0260033 -0.0431048 -0.0691627 -0.0260033 -0.0438734 -0.069444 -0.0260033 -0.0449234 -0.0691627 -0.0350033 -0.0438734 -0.069444 -0.0350033 -0.0449234 -0.0691627 -0.0260033 -0.0459734 -0.0691627 -0.0350033 -0.0459734 -0.068394 -0.0260033 -0.0467421 -0.067344 -0.0350033 -0.0470235 -0.0655254 -0.0260033 -0.0459735 -0.066294 -0.0350033 -0.0467421 -0.065244 -0.0260033 -0.0449235 -0.0655254 -0.0350033 -0.0459735 -0.0740723 -0.0247415 -0.0326612 -0.0722536 -0.0260033 -0.0316112 -0.0740722 -0.0260033 -0.0305612 -0.0751222 -0.0260033 -0.0308425 -0.0758909 -0.0260033 -0.0337111 -0.0758909 -0.0260033 -0.0316111 -0.0722536 -0.0260033 -0.0337112 -0.0740723 -0.0260033 -0.0347612 -0.0719723 -0.0260033 -0.0326612 -0.0719723 -0.0350033 -0.0326612 -0.0722536 -0.0350033 -0.0316112 -0.0730222 -0.0260033 -0.0308425 -0.0730222 -0.0350033 -0.0308425 -0.0740722 -0.0350033 -0.0305612 -0.0751222 -0.0350033 -0.0308425 -0.0761723 -0.0260033 -0.0326611 -0.0758909 -0.0350033 -0.0316111 -0.0761723 -0.0350033 -0.0326611 -0.0758909 -0.0350033 -0.0337111 -0.0751223 -0.0260033 -0.0344798 -0.0730223 -0.0260033 -0.0344798 -0.0722536 -0.0350033 -0.0337112 -0.0789664 -0.0260033 -0.00418492 -0.0807851 -0.0247415 -0.0052349 -0.0797351 -0.0260033 -0.00341626 -0.0826037 -0.0260033 -0.00628488 -0.0789664 -0.0260033 -0.00628492 -0.0786851 -0.0260033 -0.00523493 -0.0786851 -0.0350033 -0.00523493 -0.0789664 -0.0350033 -0.00418492 -0.0807851 -0.0260033 -0.0031349 -0.0797351 -0.0350033 -0.00341626 -0.0818351 -0.0260033 -0.00341623 -0.0807851 -0.0350033 -0.0031349 -0.0818351 -0.0350033 -0.00341623 -0.0826037 -0.0260033 -0.00418488 -0.0828851 -0.0260033 -0.00523487 -0.0826037 -0.0350033 -0.00418488 -0.0818351 -0.0260033 -0.00705354 -0.0826037 -0.0350033 -0.00628488 -0.0818351 -0.0350033 -0.00705354 -0.0807851 -0.0260033 -0.0073349 -0.0797351 -0.0260033 -0.00705357 -0.0797351 -0.0350033 -0.00705357 -0.0789664 -0.0350033 -0.00628492 -0.0632258 -0.0260033 0.0478149 -0.0663757 -0.0260033 0.0496336 -0.0642757 -0.0260033 0.0496336 -0.0653257 -0.0260033 0.0499149 -0.0653258 -0.0247415 0.0478149 -0.0635071 -0.0260033 0.0467649 -0.0635071 -0.0350033 0.0488649 -0.0635071 -0.0260033 0.0488649 -0.0642757 -0.0350033 0.0496336 -0.0671444 -0.0260033 0.048865 -0.0663757 -0.0350033 0.0496336 -0.0671444 -0.0350033 0.048865 -0.0674258 -0.0260033 0.047815 -0.0674258 -0.0350033 0.047815 -0.0671444 -0.0260033 0.046765 -0.0663758 -0.0260033 0.0459963 -0.0653258 -0.0260033 0.0457149 -0.0642758 -0.0260033 0.0459963 -0.0642758 -0.0350033 0.0459963 -0.0635071 -0.0350033 0.0467649 -0.0449303 -0.0247415 0.0673415 -0.0459803 -0.0260033 0.0691602 -0.046749 -0.0260033 0.0662916 -0.0428303 -0.0260033 0.0673415 -0.0431117 -0.0260033 0.0683915 -0.0438803 -0.0260033 0.0691602 -0.0438803 -0.0350033 0.0691602 -0.0449303 -0.0260033 0.0694415 -0.046749 -0.0260033 0.0683916 -0.0459803 -0.0350033 0.0691602 -0.0470303 -0.0260033 0.0673416 -0.0470303 -0.0350033 0.0673416 -0.046749 -0.0350033 0.0662916 -0.0459804 -0.0260033 0.0655229 -0.0459804 -0.0350033 0.0655229 -0.0449304 -0.0260033 0.0652415 -0.0449304 -0.0350033 0.0652415 -0.0438804 -0.0260033 0.0655229 -0.0431117 -0.0260033 0.0662915 -0.0431117 -0.0350033 0.0662915 -0.031618 -0.0260033 0.0722511 -0.030568 -0.0260033 0.0740698 -0.032668 -0.0247415 0.0740698 -0.0308494 -0.0260033 0.0751198 -0.031618 -0.0260033 0.0758884 -0.0308494 -0.0350033 0.0751198 -0.032668 -0.0260033 0.0761698 -0.031618 -0.0350033 0.0758884 -0.033718 -0.0350033 0.0758885 -0.033718 -0.0260033 0.0758885 -0.0344867 -0.0260033 0.0751198 -0.0344867 -0.0350033 0.0751198 -0.034768 -0.0260033 0.0740698 -0.0344867 -0.0260033 0.0730198 -0.0344867 -0.0350033 0.0730198 -0.033718 -0.0260033 0.0722511 -0.032668 -0.0350033 0.0719698 -0.032668 -0.0260033 0.0719698 -0.0308494 -0.0260033 0.0730198 -0.0308494 -0.0350033 0.0730198 -0.00314176 -0.0260033 0.0807826 -0.00342309 -0.0260033 0.0818326 -0.00629179 -0.0260033 0.078964 -0.0070604 -0.0260033 0.0818326 -0.00734176 -0.0260033 0.0807826 -0.00524179 -0.0260033 0.0786826 -0.00524176 -0.0247415 0.0807826 -0.00342309 -0.0350033 0.0818326 -0.00419174 -0.0260033 0.0826012 -0.00419174 -0.0350033 0.0826012 -0.00524173 -0.0260033 0.0828826 -0.00629174 -0.0260033 0.0826013 -0.0070604 -0.0350033 0.0818326 -0.00734176 -0.0350033 0.0807826 -0.00706043 -0.0260033 0.0797326 -0.00706043 -0.0350033 0.0797326 -0.00629179 -0.0350033 0.078964 -0.00524179 -0.0350033 0.0786826 -0.00419179 -0.0260033 0.0789639 -0.00342312 -0.0260033 0.0797326 -0.00500915 -0.0195033 -0.349998 -0.00250909 -0.0315033 -0.345668 -9.08344e-06 -0.0315033 -0.344998 -9.08344e-06 -0.0195033 -0.344998 0.00432101 -0.0195033 -0.347498 0.00432101 -0.0315033 -0.347498 0.00499085 -0.0195033 -0.349998 0.0024908 -0.0315033 -0.354328 0.0024908 -0.0195033 -0.354328 -9.21146e-06 -0.0195033 -0.354998 -0.00433931 -0.0315033 -0.352498 0.0336585 -0.0184033 -0.11434 0.0335013 -0.0184033 -0.11662 -0.0262963 -0.0184033 -0.122982 -0.0306995 -0.0217643 -0.123317 -0.0284564 -0.0184033 -0.123699 -0.0306999 -0.0184033 -0.123316 -0.0332887 -0.0184033 -0.117579 -0.033437 -0.0184033 -0.11985 -0.0334677 -0.021109 -0.119659 -0.035389 -0.0200426 -0.0851722 -0.0354604 -0.0200334 -0.0856422 -0.0354196 -0.0184033 -0.0868875 -0.0353402 -0.0204957 -0.087266 -0.0351309 -0.0207982 -0.0878998 -0.0344606 -0.0214246 -0.0890403 0.00249091 -0.0315033 -0.345668 0.00274091 -0.0320033 -0.345235 -0.00433924 -0.0315033 -0.347498 -0.00477225 -0.0320033 -0.347248 -0.00500915 -0.0315033 -0.349998 -0.00477232 -0.0320033 -0.352748 -0.0025092 -0.0315033 -0.354328 -9.21146e-06 -0.0315033 -0.354998 0.00432095 -0.0315033 -0.352498 0.00499085 -0.0315033 -0.349998 -0.0323641 0.00239667 -0.0207102 -0.0322141 0.00209667 -0.0204504 -0.0340766 0.00239667 -0.0202514 -0.0340766 0.00209667 -0.0199514 -0.0370428 0.00239667 -0.0219638 -0.0378017 0.00209667 -0.0236763 -0.0370428 0.00239667 -0.0253888 -0.0373026 0.00209667 -0.0255388 -0.0359392 0.00209667 -0.0269023 -0.0323642 0.00239667 -0.0266425 -0.0322142 0.00209667 -0.0269023 -0.0308508 0.00209667 -0.0255389 -0.0306517 0.00239667 -0.0236764 -0.00112289 0.00209667 0.041722 -0.00162193 0.00209667 0.0435845 -0.00298535 0.00209667 0.0449479 -0.00484785 0.00239667 0.045147 -0.00656036 0.00239667 0.0446882 -0.00781401 0.00239667 0.0434346 -0.00827289 0.00239667 0.0417221 -0.00807381 0.00209667 0.0435846 -0.00857289 0.00209667 0.0417221 -0.00807386 0.00209667 0.0398596 -0.00781405 0.00239667 0.0400096 -0.00656043 0.00239667 0.0387559 -0.00484794 0.00239667 0.038297 -0.00484794 0.00209667 0.037997 -0.00162197 0.00209667 0.0398595 -0.00142289 0.00239667 0.041722 0.0546698 0.00209667 0.0297265 0.0546698 0.00239667 0.0294265 0.0514438 0.00209667 0.024139 0.0529572 0.00239667 0.0230354 0.0528072 0.00209667 0.0227756 0.0546697 0.00209667 0.0222765 0.0546697 0.00239667 0.0225765 0.0576359 0.00239667 0.027714 0.0621547 0.00239667 -0.0265736 0.0602922 0.00209667 -0.0267726 0.0589287 0.00209667 -0.0281361 0.0587296 0.00239667 -0.0299986 0.0591885 0.00239667 -0.0317111 0.0604421 0.00239667 -0.0329647 0.0602921 0.00209667 -0.0332245 0.0621546 0.00239667 -0.0334236 0.0640171 0.00209667 -0.0332246 0.0651207 0.00239667 -0.0317111 -0.0451636 -0.00030333 -0.154942 -0.0386684 -0.00030333 -0.154943 -0.0384087 -3.3303e-06 -0.158843 -0.0419161 -3.3303e-06 -0.160867 -0.0439411 -3.3303e-06 -0.160325 -0.0454234 -3.3303e-06 -0.154792 -0.0405182 -0.00030333 -0.0942825 -0.0386432 -0.00030333 -0.0937801 -0.0386432 -3.3303e-06 -0.0934801 -0.0366182 -3.3303e-06 -0.0940227 -0.0367682 -0.00030333 -0.0942825 -0.0353956 -0.00030333 -0.0956551 -0.0348933 -0.00030333 -0.0975301 -0.0345933 -3.3303e-06 -0.0975301 -0.0386433 -0.00030333 -0.10128 -0.0366183 -3.3303e-06 -0.101038 -0.0405183 -0.00030333 -0.100778 -0.0386433 -3.3303e-06 -0.10158 -0.0406683 -3.3303e-06 -0.101037 -0.0418909 -0.00030333 -0.099405 -0.0423933 -0.00030333 -0.09753 -0.0426933 -3.3303e-06 -0.09753 0.0436019 -0.00030333 -0.105751 0.0454769 -3.3303e-06 -0.104948 0.0475019 -3.3303e-06 -0.105491 0.0473518 -0.00030333 -0.112246 0.0489842 -3.3303e-06 -0.111023 0.0475018 -3.3303e-06 -0.112506 0.0454768 -0.00030333 -0.112748 0.0436018 -0.00030333 -0.112246 0.0419694 -3.3303e-06 -0.111023 0.0417268 -0.00030333 -0.108998 0.0422293 -0.00030333 -0.107123 0.0327596 -0.00030333 -0.163248 0.0327596 -3.3303e-06 -0.162948 0.0360072 -0.00030333 -0.165123 0.036267 -3.3303e-06 -0.164973 0.0368096 -3.3303e-06 -0.166998 0.036267 -3.3303e-06 -0.169023 0.0327595 -3.3303e-06 -0.171048 0.0308845 -0.00030333 -0.170246 0.0307345 -3.3303e-06 -0.170506 0.0292522 -3.3303e-06 -0.169023 0.0290096 -0.00030333 -0.166998 0.029512 -0.00030333 -0.165123 -0.0483236 -0.00030333 -0.212185 -0.043051 -3.3303e-06 -0.210553 -0.043201 -0.00030333 -0.210813 -0.0415686 -3.3303e-06 -0.212036 -0.0432011 -0.00030333 -0.217308 -0.0450761 -3.3303e-06 -0.218111 -0.0471011 -3.3303e-06 -0.217568 -0.0485835 -3.3303e-06 -0.216085 -0.048826 -0.00030333 -0.21406 -0.049126 -3.3303e-06 -0.21406 -0.0504768 -3.3303e-06 -0.271707 -0.0503268 -0.00030333 -0.271966 -0.0484518 -3.3303e-06 -0.271164 -0.0464268 -3.3303e-06 -0.271707 -0.0465768 -0.00030333 -0.271966 -0.0452042 -0.00030333 -0.273339 -0.0465769 -0.00030333 -0.278462 -0.0484519 -0.00030333 -0.278964 -0.0516995 -0.00030333 -0.277089 -0.0516994 -0.00030333 -0.273339 0.0169735 -3.3303e-06 -0.220973 0.0184559 -3.3303e-06 -0.219491 0.0204809 -3.3303e-06 -0.218948 0.0223559 -0.00030333 -0.21975 0.0225059 -3.3303e-06 -0.219491 0.0237285 -0.00030333 -0.221123 0.0239883 -3.3303e-06 -0.220973 0.0242309 -0.00030333 -0.222998 0.0245309 -3.3303e-06 -0.222998 0.0223558 -0.00030333 -0.226246 0.0167309 -0.00030333 -0.222998 0.0164309 -3.3303e-06 -0.222998 0.00778815 -0.00030333 -0.269087 0.00966316 -3.3303e-06 -0.268285 0.0116882 -3.3303e-06 -0.268827 0.0129107 -0.00030333 -0.27046 0.0131705 -3.3303e-06 -0.27031 0.0137131 -3.3303e-06 -0.272335 0.0131705 -3.3303e-06 -0.27436 0.00966306 -0.00030333 -0.276085 0.00641549 -0.00030333 -0.27421 0.00615568 -3.3303e-06 -0.27436 0.00561311 -3.3303e-06 -0.272335 0.00615573 -3.3303e-06 -0.27031 0.057243 -4.35227e-05 -0.0708202 0.0571399 -0.00015333 -0.0708578 0.0576047 -3.3303e-06 -0.0718085 0.057455 -4.35227e-05 -0.0718189 0.0574165 -2.61664e-05 -0.0728446 0.0573821 -4.35227e-05 -0.0728372 0.0571236 -0.000188525 -0.0708637 0.0572578 -0.000188525 -0.0728105 0.0573455 -0.00015333 -0.0718264 0.0572748 -0.00015333 -0.0728141 0.0570699 -0.00900333 -0.0707532 0.0570868 -0.00030333 -0.0708297 0.0561506 -3.3303e-06 -0.0305546 0.0528249 -3.3303e-06 -0.023052 0.0518163 -3.3303e-06 -0.0212143 0.0457301 -2.61664e-05 -0.0126301 0.038343 -2.61664e-05 -0.00515085 0.0561231 -2.61664e-05 -0.0308155 0.0456552 -9.11983e-05 -0.0126922 0.0517166 -2.61664e-05 -0.0212713 0.0588175 -2.61664e-05 -0.0409766 0.038249 -0.00015333 -0.0052613 0.0382799 -9.11983e-05 -0.00522498 0.0383202 -4.35227e-05 -0.00517766 0.0516321 -9.11983e-05 -0.0213196 0.0560315 -9.11983e-05 -0.0308485 0.0587216 -9.11983e-05 -0.0409933 0.0559703 -0.000188525 -0.0308705 0.0515756 -0.000188525 -0.0213519 0.0515558 -0.00030333 -0.0213632 0.0456051 -0.000188525 -0.0127338 0.0487584 -0.00030333 -0.0169264 0.0598339 -3.3303e-06 -0.0514503 0.0586576 -0.000188525 -0.0410045 0.0597191 -2.61664e-05 -0.0514502 0.0588009 -2.61664e-05 -0.0619223 0.0596218 -9.11983e-05 -0.0514501 0.0595568 -0.000188525 -0.0514501 0.0587051 -9.11983e-05 -0.0619054 0.0595339 -0.00030333 -0.05145 0.058641 -0.000188525 -0.0618942 -0.0284374 -0.000188525 -0.0194017 -0.0274578 -0.00015333 -0.0219065 -0.0275662 -4.35227e-05 -0.0219239 -0.0285424 -4.35227e-05 -0.0194734 -0.0285715 -2.61664e-05 -0.0194933 -0.0275814 -0.00030333 -0.0245983 -0.02762 -0.00015333 -0.0245872 -0.0277143 -3.3303e-06 -0.0219477 -0.0288773 -0.00030333 -0.0269706 -0.0277256 -4.35227e-05 -0.0245568 -0.0367124 -0.000188525 -0.0918734 -0.0327939 -0.000188525 -0.0987597 -0.0342894 -0.00030333 -0.0934016 -0.0327716 -0.00030333 -0.0987644 -0.0340343 -0.000188525 -0.101336 -0.0340166 -0.00030333 -0.10135 -0.0343532 -9.11983e-05 -0.0934621 -0.0367334 -9.11983e-05 -0.0919349 -0.034306 -0.000188525 -0.0934173 -0.032892 -0.000188525 -0.0959023 -0.0363291 -0.000188525 -0.103041 -0.0340844 -9.11983e-05 -0.101294 -0.0344238 -2.61664e-05 -0.093529 -0.0329546 -9.11983e-05 -0.09592 -0.0328576 -9.11983e-05 -0.0987464 -0.0329528 -2.61664e-05 -0.0987263 -0.0363543 -9.11983e-05 -0.102981 -0.036392 -2.61664e-05 -0.102891 -0.0391397 -2.61664e-05 -0.103324 -0.0331587 -3.3303e-06 -0.0959778 -0.0330482 -2.61664e-05 -0.0959465 -0.0341595 -2.61664e-05 -0.101232 -0.034248 -3.3303e-06 -0.101159 -0.0391756 -9.11983e-05 -0.151579 -0.0371431 -9.11983e-05 -0.153329 -0.0424302 -0.000192109 -0.162774 -0.0417704 -0.000192107 -0.150841 -0.042432 -0.00030333 -0.162795 -0.0397379 -0.00030333 -0.162408 -0.0378199 -0.00030333 -0.161202 -0.0375088 -0.000188525 -0.160855 -0.037492 -0.00030333 -0.160871 -0.0361565 -0.00030333 -0.158499 -0.0360287 -0.000188525 -0.155785 -0.0370906 -0.000188525 -0.15329 -0.0373616 -0.00030333 -0.152912 -0.0360928 -9.11983e-05 -0.155796 -0.0361784 -0.000188525 -0.158493 -0.0397462 -0.000188525 -0.162387 -0.0362408 -9.11983e-05 -0.158474 -0.0375568 -9.11983e-05 -0.160811 -0.0376285 -2.61664e-05 -0.160745 -0.0397698 -9.11983e-05 -0.162326 -0.0424245 -9.11983e-05 -0.162708 -0.0417744 -2.61664e-05 -0.151004 -0.0391454 -0.000188525 -0.151521 -0.0417704 -0.000188525 -0.150842 -0.0392207 -2.61664e-05 -0.151665 -0.0372216 -2.61664e-05 -0.153386 -0.0361886 -2.61664e-05 -0.155813 -0.0363017 -3.3303e-06 -0.155833 -0.0363343 -2.61664e-05 -0.158447 -0.0364445 -3.3303e-06 -0.158415 -0.0398051 -2.61664e-05 -0.162236 -0.0398468 -3.3303e-06 -0.162129 -0.0449327 -0.00030333 -0.208062 -0.0430107 -0.00030333 -0.208427 -0.0430245 -0.00015333 -0.208465 -0.0449336 -0.00015333 -0.208102 -0.0430623 -4.35227e-05 -0.208568 -0.0449362 -4.35227e-05 -0.208212 -0.0436049 -0.00030333 -0.219877 -0.0393549 -0.00030333 -0.215869 -0.040959 -0.00030333 -0.218425 -0.0449348 -8.99404e-05 -0.208151 -0.0405598 -0.00015333 -0.210172 -0.040643 -4.35227e-05 -0.210243 -0.0393454 -4.35227e-05 -0.212885 -0.0392379 -0.00015333 -0.212862 -0.0394979 -4.35227e-05 -0.215823 -0.0393932 -0.00015333 -0.215856 -0.0409866 -0.00015333 -0.218396 -0.0436147 -0.00015333 -0.219838 -0.043114 -3.3303e-06 -0.208709 -0.0394924 -3.3303e-06 -0.212915 -0.039641 -3.3303e-06 -0.215778 -0.0410619 -4.35227e-05 -0.218316 -0.0411649 -3.3303e-06 -0.218207 -0.0436417 -4.35227e-05 -0.219732 -0.0455304 -3.3303e-06 -0.219742 -0.045691 -0.00030333 -0.269887 -0.0434688 -0.00015333 -0.271945 -0.0425061 -0.00015333 -0.274805 -0.042466 -0.00030333 -0.274803 -0.043032 -0.00030333 -0.277788 -0.0457095 -0.00015333 -0.269923 -0.0435606 -4.35227e-05 -0.272005 -0.0430683 -0.00015333 -0.277771 -0.0450112 -0.00015333 -0.28008 -0.0478366 -0.00015333 -0.281142 -0.047848 -4.35227e-05 -0.281033 -0.0457601 -4.35227e-05 -0.27002 -0.0458291 -3.3303e-06 -0.270153 -0.043686 -3.3303e-06 -0.272087 -0.0426156 -4.35227e-05 -0.274813 -0.0427653 -3.3303e-06 -0.274823 -0.0431675 -4.35227e-05 -0.277724 -0.043303 -3.3303e-06 -0.277659 -0.0450746 -4.35227e-05 -0.279991 -0.0451612 -3.3303e-06 -0.279868 0.0133691 -0.0200033 -0.278778 0.0132319 -0.0200033 -0.278021 0.0132317 -0.0200799 -0.27802 0.0126065 -0.0200033 -0.277587 0.0126065 -0.0200796 -0.277587 0.019539 -0.0350033 -0.0824636 0.0335387 -0.0350033 -0.0778271 0.0388454 -0.0350033 -0.0753187 0.0752178 -0.0350033 -0.039038 0.0735637 -0.0348033 -0.0424737 0.0779974 -0.0348033 -0.0336458 0.0685119 -0.0350033 -0.0498781 0.0679746 -0.0350033 -0.0506079 0.0494133 -0.0350033 -0.0688486 0.0459949 -0.0350033 -0.0711779 0.0774954 -0.0350033 -0.0342951 0.0778137 -0.0350033 -0.0335666 0.084602 -0.0350033 0.00492889 0.0842128 -0.0350033 0.0094883 0.0848017 -0.0348033 0.00494051 0.0836549 -0.0348033 0.0147525 0.0811853 -0.0350033 0.0243077 0.0629934 -0.0350033 0.0566926 0.0692905 -0.0350033 0.048795 0.0721759 -0.0350033 0.0444153 0.0735647 -0.0348033 0.0424763 0.0779451 -0.0350033 0.0332647 0.0779982 -0.0348033 0.0336482 0.046677 -0.0348033 0.0709763 0.054601 -0.0348033 0.065077 0.0568922 -0.0350033 0.0628139 0.061641 -0.0350033 0.0581604 0.0195872 -0.0348033 0.0826621 0.00983529 -0.0350033 0.084179 0.0467039 -0.0350033 0.070719 0.0381218 -0.0348033 0.0759158 0.0289826 -0.0350033 0.0796408 0.029051 -0.0348033 0.0798287 0.00985851 -0.0348033 0.0843777 -3.57926e-06 -0.0348033 0.0849522 -0.0617943 -0.0348033 0.0582992 -0.0616488 -0.0350033 0.058162 -0.0195944 -0.0348033 0.0826626 -0.0295141 -0.0350033 0.0794488 -0.0465746 -0.0350033 0.0708104 -0.0486355 -0.0350033 0.0694112 -0.0688829 -0.0350033 0.0493818 -0.0630013 -0.0350033 0.0566942 -0.0813856 -0.0348033 0.0243672 -0.0834673 -0.0350033 -0.0147134 -0.084811 -0.0348033 -0.00493612 -0.0813862 -0.0348033 -0.0243607 -0.0780076 -0.0348033 -0.0336438 -0.0685225 -0.0350033 -0.0498764 -0.0567908 -0.0350033 -0.0629096 -0.0645702 -0.0350033 -0.0548963 -0.0681457 -0.0348033 -0.0507256 -0.0494244 -0.0350033 -0.0688473 -0.0544817 -0.0350033 -0.0649194 -0.0466864 -0.0348033 -0.0709719 -0.0195504 -0.0350033 -0.0824631 -0.0195965 -0.0348033 -0.0826577 0.00805654 -0.0350033 -0.0843635 -5.7543e-06 -0.0348033 -0.0849478 0.00985635 -0.0348033 -0.0843735 0.0195851 -0.0348033 -0.0826582 -0.0399171 -0.0119034 -0.0860851 -0.0398568 -0.0119033 -0.0852757 -0.0398713 -0.0119033 -0.0844437 -0.0398713 -0.00900333 -0.0844436 -0.0398908 -0.0119033 -0.0842001 -0.0399049 -0.0119033 -0.0840629 0.00209468 -0.0190033 -0.0514021 0.00167933 -0.0190033 -0.0529521 -0.00100529 -0.0190033 -0.0483021 -0.00255536 -0.0190033 -0.0540867 -0.00410532 -0.0190033 -0.051402 -0.00100532 -0.0190033 -0.0514021 0.000544641 -0.0190033 -0.0540868 0.00360401 -0.00950333 -0.281429 -0.0488061 -0.0195033 -0.281428 0.0119658 -0.000392679 -0.281345 0.0118698 -0.000431109 -0.281395 0.0116892 -0.0195033 -0.281429 0.0118687 -5.47344e-05 -0.281149 0.0117654 -0.000312742 -0.281391 0.01199 -0.000106168 -0.281184 0.0119176 -0.000331648 -0.281364 0.0118609 -0.000274974 -0.281364 0.0121378 -0.000323892 -0.281149 0.0121452 -0.00015333 -0.281043 0.0121025 -9.11983e-05 -0.281022 0.0120864 -0.000202512 -0.281184 0.0120467 -4.35227e-05 -0.280995 0.00340408 -3.50596e-06 -0.280942 0.0118303 -0.000150611 -0.281283 0.0117999 -0.000226701 -0.281345 0.0116892 -0.00050333 -0.281429 0.00360401 -0.00050333 -0.281429 -0.0483729 -0.00914978 -0.281281 -0.046621 -0.00900333 -0.280928 0.00310401 -0.00900333 -0.280929 -0.0487099 -0.00931199 -0.28139 0.00339906 -0.00929838 -0.281385 0.00353687 -0.000335475 -0.2814 0.00346826 -0.000401444 -0.281407 0.00325401 -4.35227e-05 -0.280929 0.0032542 -4.37544e-05 -0.280945 0.00319188 -9.11983e-05 -0.280929 0.00314444 -0.000153514 -0.280945 0.00342125 -4.64141e-05 -0.281132 0.00329577 -9.66323e-05 -0.281165 0.00310419 -0.000303401 -0.280942 0.0031471 -0.000320564 -0.281132 0.00341703 -0.000254755 -0.281351 0.00335543 -0.000316346 -0.281351 0.00350212 -0.000367586 -0.281407 0.00348429 -0.000204026 -0.281329 0.00319731 -0.000195084 -0.281165 0.00314421 -0.00015333 -0.280929 0.00310401 -0.00030333 -0.280929 0.00312691 -0.00902622 -0.281078 0.00323088 -0.000354077 -0.281261 0.00323013 -0.00912945 -0.281261 0.0033047 -0.000383608 -0.281329 0.00343615 -0.000436188 -0.2814 0.0517832 -0.0190033 0.0240221 0.0484984 -0.0190033 0.02576 0.0493943 -0.0190033 0.0256551 0.0328823 -0.0190033 0.0136333 0.0355056 -0.0190033 0.0025289 0.0525498 -0.0190033 0.0232165 0.0535305 -0.0190033 0.0226921 0.0390005 -0.0190033 -0.00437792 0.051607 -0.0190033 -0.0183841 0.0559727 -0.0190033 -0.0177133 0.0567409 -0.0190033 -0.0163332 0.0513384 -0.00160525 0.0216251 0.0510393 -0.00270333 0.0235121 0.052247 -0.00420333 0.0228187 0.0528795 -0.00160525 0.020801 0.0520035 -0.00270333 0.0224989 0.046994 -0.00270333 0.0244761 0.0484492 -0.00270333 0.0248579 0.0475222 -0.00160525 0.0235134 0.0499127 -0.00270333 0.0245091 0.0494064 -0.00160525 0.0235347 0.0484616 -0.00160525 0.0237599 0.0482437 -0.00120333 0.0221984 0.0484786 -0.00120333 0.02226 0.0501337 -0.00160525 0.0228911 0.0487148 -0.00120333 0.0222037 0.0551899 -0.00120333 -0.00975319 0.0551952 -0.00120333 0.00972726 0.0537482 -0.00120333 -0.0157004 0.0356978 -0.00120333 0.0152481 0.0356178 -0.00120333 0.0150205 0.0488966 -0.00120333 0.0220428 0.0504299 -0.00120333 0.0204316 0.0529607 -0.00120333 -0.0156411 0.0531246 -0.00120333 -0.0157963 0.0536315 -0.00160525 0.0203353 0.054109 -0.00160525 0.0195907 0.0525792 -0.00120333 0.0192663 0.0532369 -0.00270333 0.0218393 0.0544018 -0.00270333 0.0211178 0.0523912 -0.00120333 0.0193827 0.052247 -0.0185033 0.0228187 0.0533677 -0.00420333 0.0222193 0.0546759 -0.00420333 -0.0186152 0.0545268 -0.00270333 -0.0182419 0.051607 -0.00420333 -0.0183841 0.0504599 -0.00420333 -0.0172983 0.0556747 -0.00270333 -0.0174436 0.0548605 -0.00160525 -0.0167069 0.0531449 -0.00270333 -0.0184543 0.0532273 -0.00160525 -0.0173593 0.0518103 -0.00270333 -0.0180374 0.0511924 -0.00208201 -0.0168129 0.0523658 -0.00160525 -0.0170902 0.0552994 -0.00160525 -0.0159182 0.053858 -0.00120333 -0.0155033 0.0541195 -0.00160525 -0.0172222 0.053563 -0.00120333 -0.0158293 0.0533399 -0.00120333 -0.0158635 0.0517103 -0.00160525 -0.0164697 0.033527 -0.00270333 0.0166755 0.0330933 -0.00305528 0.0137207 0.0330313 -0.00270333 0.0152653 0.0358751 -0.00120333 0.0154118 0.0344445 -0.00160525 0.0160722 0.0332536 -0.00270333 0.0137872 0.033694 -0.00208201 0.0139697 0.0341245 -0.00160525 0.0151619 0.0513708 -0.00420333 0.0237394 0.050098 -0.00420333 0.0248658 0.0484447 -0.00420333 0.0252598 0.0468006 -0.00420333 0.0248285 0.0484447 -0.0185033 0.0252598 0.0351535 -0.00160525 0.0167268 0.0346253 -0.00270333 0.0176895 0.0365576 -0.00420333 -0.00127639 0.039261 -0.00270333 -0.00407179 0.0395699 -0.00208201 -0.00370867 0.0369163 -0.00270333 -0.00109492 0.036382 -0.00208201 0.00259126 0.037896 -0.00160525 -0.000599138 0.0392345 -0.00120333 7.81184e-05 0.0402006 -0.00143169 -0.00296737 0.0399725 -0.00160525 -0.00323544 0.0409445 -0.00120333 -0.00209295 0.0474286 -0.00120333 -0.00844481 0.0458416 -0.00208201 -0.0098524 0.0465697 -0.00143169 -0.00920659 0.0453551 -0.00305528 -0.0102839 0.0391485 -0.00305528 -0.00420399 0.0390005 -0.00420333 -0.00437792 0.0451842 -0.00420333 -0.0104354 0.050795 -0.00270333 -0.0170763 0.0356537 -0.00120333 0.014782 0.038498 -0.00120333 0.00274182 0.0375613 -0.00120333 0.00887658 0.0345931 -0.00143169 0.0143424 0.034268 -0.00160525 0.0142076 0.036444 -0.00143169 0.00861264 0.0354968 -0.00208201 0.00838888 0.0370018 -0.00160525 0.00263536 0.034864 -0.00305528 0.00823937 0.0346417 -0.00420333 0.00818686 0.0359065 -0.00270333 0.00255743 0.0355056 -0.00420333 0.0025289 0.0526986 -0.00120333 0.0190801 0.0566725 -0.00160525 0.00998752 0.0559684 -0.00120333 0.00293797 0.0559097 -0.00120333 -0.00389495 0.0577539 -0.00270333 0.010178 0.0574663 -0.00160525 0.00301654 0.0574061 -0.00160525 -0.00399924 0.056667 -0.00160525 -0.0100143 0.0563547 -0.00270333 -0.016222 0.0581497 -0.00420333 0.0102478 0.0551416 -0.00270333 0.0199644 0.0589643 -0.00420333 0.00309511 0.0589024 -0.00420333 -0.00410354 0.0585629 -0.00270333 0.00307405 0.0585015 -0.00270333 -0.00407559 0.0577483 -0.00270333 -0.0102054 0.0546837 -0.00420333 0.0214042 0.0546904 -0.0185033 0.0213977 0.0533677 -0.0185033 0.0222193 0.034432 -0.00420333 0.0180419 0.034432 -0.0190033 0.0180419 0.0471567 -0.0186548 0.0250239 0.0476067 -0.0188268 0.0252707 0.0478488 -0.0189021 0.0254036 0.0451842 -0.0190033 -0.0104354 0.0504599 -0.0190033 -0.0172983 0.0365576 -0.0190033 -0.00127639 0.0331912 -0.0190033 0.0168964 0.0331912 -0.00420333 0.0168964 0.0326312 -0.00420333 0.0153032 0.0326312 -0.0190033 0.0153032 0.0328823 -0.00420333 0.0136333 0.0581441 -0.00420333 -0.0102753 0.0589024 -0.0190033 -0.00410354 0.0548083 -0.0190033 0.0219668 0.0549872 -0.0189587 0.021515 0.0581497 -0.0190033 0.0102478 0.0555195 -0.0185033 0.0201012 0.0555195 -0.00420333 0.0201012 0.0531147 -0.00420333 -0.0188551 0.0531147 -0.0190033 -0.0188551 0.0546759 -0.0190033 -0.0186152 0.0559727 -0.00420333 -0.0177133 0.0567409 -0.00420333 -0.0163332 0.050565 -0.0185033 0.0245744 0.0516405 -0.0189724 0.0239243 0.0507593 -0.0189724 0.0248373 0.050652 -0.0188569 0.0246921 0.0513963 -0.0186764 0.0237569 0.0513708 -0.0185033 0.0237394 0.0468006 -0.0185033 0.0248285 0.047866 -0.0185033 0.025205 0.0508622 -0.0190033 0.0249764 0.049355 -0.0189724 0.0254866 0.0493139 -0.0188569 0.0253108 0.0505834 -0.0186764 0.0245992 0.050098 -0.0185033 0.0248658 0.0480845 -0.0189586 0.0255329 0.0478605 -0.0186764 0.0252354 0.0492876 -0.0186764 0.0251983 0.0492806 -0.0185033 0.0251682 0.0514916 -0.0188569 0.0238222 0.0534682 -0.0189653 0.0225112 0.0534154 -0.0188569 0.0223578 0.0524339 -0.0189653 0.0230643 0.0523357 -0.0188569 0.0229352 0.05227 -0.0186947 0.022849 0.0533778 -0.0186764 0.0222486 0.0547934 -0.0188569 0.0215018 0.0551894 -0.0188271 0.0209908 0.0553753 -0.018655 0.0204951 0.0549301 -0.0189816 0.0216602 0.0533801 -0.0186947 0.0222553 0.0547121 -0.0186764 0.0214196 -0.0328979 -0.0190033 0.0136182 -0.0281238 -0.0190033 0.0491965 -0.0273056 -0.0190033 0.0481993 -0.0322875 -0.0190033 0.0494463 -0.0277698 -0.0190033 0.0222835 -0.0398976 -0.0108885 0.0228277 -0.0311206 -0.0147259 0.0479205 -0.0385038 -0.0152144 0.0422688 -0.0314222 -0.0147822 0.0478333 -0.0239906 -0.00414431 0.0336748 -0.0239065 -0.00395654 0.0336071 -0.028234 -0.00532989 0.029653 -0.0270003 -0.00760551 0.0346641 -0.0319517 -0.00766579 0.0280565 -0.0375749 -0.00757222 0.0153493 -0.0310694 -0.0146562 0.0477527 -0.0351468 -0.0135585 0.040242 -0.0307177 -0.0145296 0.047672 -0.0406153 -0.0136146 0.0331676 -0.0306794 -0.0107922 0.0371982 -0.0381199 -0.00794217 0.0150271 -0.0357637 -0.00769751 0.0207655 -0.0319413 -0.00632376 0.02536 -0.0533895 -0.0159679 0.0196167 -0.0532726 -0.0159403 0.0197348 -0.0449031 -0.0136395 0.0253416 -0.0496431 -0.0158369 0.028212 -0.0358719 -0.0108559 0.0303724 -0.0308928 -0.0175062 0.049977 -0.0318001 -0.0152247 0.0484583 -0.0311936 -0.0158213 0.0493778 -0.0320947 -0.0158862 0.0489785 -0.0296155 -0.016995 0.0498972 -0.0309852 -0.0170775 0.0499304 -0.0292011 -0.0164697 0.04965 -0.029323 -0.0154902 0.0491303 -0.0296181 -0.0146704 0.0482064 -0.0308898 -0.0146387 0.0478532 -0.0306583 -0.01504 0.0487433 -0.0313486 -0.0147748 0.0478744 -0.028572 -0.0152498 0.0484968 -0.0277553 -0.0161705 0.0484943 -0.0281457 -0.0163075 0.0489748 -0.0286439 -0.0163924 0.0493654 -0.0310687 -0.0166431 0.0498155 -0.0298052 -0.0165385 0.0498244 -0.0302311 -0.0156849 0.0494279 -0.0301115 -0.0148649 0.0485667 -0.0289206 -0.0153747 0.0488545 -0.0350599 -0.00721656 0.0133636 -0.0355944 -0.00742517 0.012867 -0.0349379 -0.00791206 0.0124864 -0.0343809 -0.00854394 0.0123004 -0.0354776 -0.0068418 0.0144144 -0.0376855 -0.00761968 0.0151702 -0.0356204 -0.00885719 0.0117288 -0.0366292 -0.00788451 0.0124549 -0.0370859 -0.00760034 0.0130611 -0.0353122 -0.0100292 0.0115542 -0.0357721 -0.00953056 0.0115223 -0.0362066 -0.00900585 0.0116571 -0.0366573 -0.00850936 0.0119652 -0.0371428 -0.00868012 0.0120273 -0.0374862 -0.00828307 0.0125107 -0.0370822 -0.00809406 0.0124419 -0.0377516 -0.007989 0.0131043 -0.0379206 -0.00781765 0.0137552 -0.0345657 -0.00932332 0.0118966 -0.0339702 -0.00922333 0.0122967 -0.0346168 -0.00709057 0.0140808 -0.0343456 -0.00772735 0.0130378 -0.033863 -0.00761603 0.0138168 -0.0333153 -0.00832422 0.0136548 -0.0330039 -0.00909075 0.0135959 -0.0334281 -0.00913938 0.0128662 -0.0337886 -0.00840627 0.0128754 -0.0348009 -0.00997448 0.0117197 -0.035008 -0.00870131 0.0119302 -0.0383017 -0.00810104 0.0139267 -0.0381756 -0.0086122 0.0128262 -0.0377347 -0.00939257 0.0119987 -0.0378492 -0.00845497 0.0126422 -0.0372618 -0.00927216 0.011806 -0.0378768 -0.00774637 0.015038 -0.0368726 -0.00713345 0.0140186 -0.0374476 -0.00749028 0.0137455 -0.0362681 -0.00715904 0.0134037 -0.0361223 -0.0083212 0.0119976 -0.0351708 -0.00942703 0.0116473 -0.0367526 -0.00914362 0.0116889 -0.054301 -0.0182541 0.0170024 -0.054202 -0.0187382 0.0168652 -0.053431 -0.0160315 0.0200662 -0.0532207 -0.0158913 0.0194506 -0.0549272 -0.0170925 0.0196184 -0.0554836 -0.0188402 0.0193521 -0.0551153 -0.0183396 0.0180819 -0.0553146 -0.0188183 0.0184814 -0.053376 -0.0171106 0.0168561 -0.0543422 -0.017761 0.0172153 -0.0534621 -0.0160179 0.0198455 -0.0541386 -0.0163368 0.0191703 -0.0547678 -0.0171292 0.0205908 -0.0551478 -0.0179698 0.0207501 -0.055352 -0.0179436 0.0194788 -0.0529702 -0.0186669 0.0162181 -0.0550653 -0.0178728 0.0182429 -0.0547361 -0.0169995 0.0186671 -0.0543158 -0.0172841 0.0175026 -0.0542178 -0.0168505 0.0178547 -0.0538276 -0.0162033 0.0186793 -0.0201761 -0.00520273 0.0345494 -0.0210517 -0.00985659 0.0368015 -0.0199477 -0.00756768 0.0347895 -0.0244307 -0.010801 0.0408263 -0.0270543 -0.0106385 0.0406493 -0.0260552 -0.00923225 0.0386599 -0.0256326 -0.0102607 0.040549 -0.0229558 -0.012718 0.0402717 -0.023463 -0.0117269 0.0407024 -0.0239635 -0.00752389 0.0372326 -0.0251118 -0.00759528 0.0367165 -0.0245593 -0.00746946 0.03696 -0.0233798 -0.00430029 0.0343711 -0.0227757 -0.00431611 0.0346749 -0.0233176 -0.00769584 0.0374157 -0.0220886 -0.00442344 0.0348641 -0.0226704 -0.00798545 0.0374822 -0.0220757 -0.00442626 0.0348662 -0.0215819 -0.00882294 0.0372448 -0.0213746 -0.00462525 0.0349026 -0.0206984 -0.00490734 0.0347799 -0.0412519 -0.0119757 0.0130235 -0.0414085 -0.0103543 0.0159837 -0.0450952 -0.0124086 0.0170597 -0.041615 -0.0105323 0.0148909 -0.0453189 -0.0125956 0.0159715 -0.0453275 -0.0131972 0.0149103 -0.0415695 -0.0111037 0.0138146 -0.0531133 -0.0158489 0.0194039 -0.0533561 -0.0160417 0.0183192 -0.0534231 -0.0166681 0.0172722 -0.0450922 -0.0141157 0.0141428 -0.0407623 -0.0129228 0.0126606 -0.0532756 -0.017626 0.0165281 -0.0531374 -0.0181492 0.0163201 -0.0350998 -0.0070578 0.0205395 -0.0346167 -0.00662336 0.0201864 -0.0370298 -0.0071602 0.015086 -0.0339628 -0.00632189 0.0197519 -0.0363159 -0.00688536 0.0147654 -0.0316061 -0.00700756 0.0184548 -0.0310566 -0.00771921 0.0182359 -0.0307319 -0.00849119 0.0181599 -0.0306052 -0.0092189 0.0181948 -0.0328979 -0.00981497 0.0136182 -0.0331741 -0.00625364 0.0192727 -0.032346 -0.00648654 0.0188156 -0.0287422 -0.0061252 0.0227246 -0.0281853 -0.00684133 0.0224439 -0.0278385 -0.00762081 0.0223482 -0.0276807 -0.0083529 0.0223941 -0.0244567 -0.00641476 0.026011 -0.0248449 -0.00562861 0.0261243 -0.0254244 -0.00490997 0.0264694 -0.0294674 -0.00561224 0.0231897 -0.0261403 -0.00441289 0.0270469 -0.0302535 -0.00540542 0.0237767 -0.0275031 -0.00441539 0.0285132 -0.0309744 -0.00551305 0.0243854 -0.0315446 -0.00585579 0.024928 -0.0242485 -0.00714889 0.0260713 -0.0212067 -0.00389063 0.0291975 -0.0218531 -0.0031854 0.0296065 -0.024103 -0.00392567 0.0333605 -0.027957 -0.00481721 0.0291567 -0.0237359 -0.00288694 0.0320783 -0.0232481 -0.00263184 0.0311954 -0.0268746 -0.0042481 0.0277727 -0.022931 -0.00263065 0.0307416 -0.0513032 -0.0186482 0.0292487 -0.0552664 -0.0188524 0.0208118 -0.054163 -0.0164563 0.0203501 -0.0512015 -0.0177716 0.0291626 -0.0459928 -0.0174934 0.0368374 -0.0508604 -0.0169361 0.0289413 -0.0457013 -0.0166651 0.0365646 -0.0503117 -0.0162649 0.028607 -0.0446385 -0.0155641 0.0356602 -0.0396701 -0.0179937 0.0437464 -0.0452249 -0.0159961 0.0361509 -0.0396152 -0.0171363 0.0436269 -0.0414755 -0.0180997 0.0420388 -0.046073 -0.0183617 0.0369428 -0.0322875 -0.0175374 0.0494463 -0.0322614 -0.0166936 0.0493182 -0.0393826 -0.0163171 0.043314 -0.038992 -0.0156513 0.0428374 -0.0214853 -0.00310287 0.0337046 -0.0211752 -0.00266178 0.0327527 -0.0224432 -0.003528 0.034156 -0.0230766 -0.002709 0.0326576 -0.0233785 -0.0033773 0.0335364 -0.0223099 -0.00238774 0.0319949 -0.0225808 -0.00272579 0.0303107 -0.0215164 -0.00347698 0.0341293 -0.0192554 -0.00449456 0.0328599 -0.0198625 -0.00457549 0.02981 -0.0192327 -0.00540464 0.030605 -0.0202179 -0.00303016 0.031207 -0.0201423 -0.00372138 0.0300729 -0.01972 -0.00377939 0.0306544 -0.0190532 -0.00545553 0.0311051 -0.018986 -0.00503262 0.0322691 -0.0206675 -0.0037661 0.0295642 -0.0207262 -0.0046679 0.0290782 -0.0212669 -0.00301153 0.0299995 -0.0206839 -0.00294874 0.0305626 -0.0205187 -0.00323645 0.033329 -0.0207051 -0.00275739 0.0324609 -0.0197254 -0.00363959 0.03278 -0.0199198 -0.00321338 0.031825 -0.0194389 -0.00391078 0.0312257 -0.0196683 -0.00559355 0.034144 -0.0209356 -0.00421003 0.0345278 -0.0190475 -0.00575692 0.0329409 -0.0190224 -0.00486009 0.0315852 -0.0192662 -0.00467911 0.0307508 -0.0192235 -0.00422246 0.0321636 -0.0209963 -0.00255061 0.0318725 -0.0240089 -0.0033652 0.0328172 -0.0239929 -0.00390809 0.0334698 -0.0238803 -0.00436048 0.0339911 -0.023853 -0.00411027 0.033798 -0.0232439 -0.00374158 0.0340003 -0.0227025 -0.00432332 0.0347024 -0.0217641 -0.00402193 0.0346045 -0.0193594 -0.00593419 0.0337173 -0.0192157 -0.00533088 0.033335 -0.0196031 -0.00491253 0.0338385 -0.0201884 -0.0045211 0.0342586 -0.0197955 -0.00399877 0.0334296 -0.0205845 -0.0036368 0.0338798 -0.0226049 -0.00290853 0.0333704 -0.0216649 -0.00266094 0.0330071 -0.0218827 -0.00236832 0.0316222 -0.0214538 -0.00245861 0.0312456 -0.0220215 -0.00252954 0.0306935 -0.0414757 -0.0190033 0.0420385 -0.0500241 -0.0190033 0.0313862 -0.0529702 -0.0190033 0.0162181 -0.0446919 -0.0151134 0.0138057 -0.0552664 -0.0190033 0.0208118 -0.0554273 -0.0188514 0.0202401 -0.0554908 -0.0190033 0.0195416 -0.0551216 -0.0190033 0.0180134 -0.0550943 -0.0187993 0.01796 -0.0544198 -0.018752 0.0170583 -0.0541209 -0.0190033 0.016801 -0.019602 -0.0190033 0.0299684 -0.0201259 -0.00536964 0.0293971 -0.0196948 -0.00536365 0.0298471 -0.0189278 -0.00558745 0.0320336 -0.0190193 -0.0190033 0.0312388 -0.01898 -0.0190033 0.0326358 -0.0204206 -0.0190033 0.0291664 -0.0204206 -0.00538697 0.0291664 -0.0273056 -0.0172773 0.0481993 -0.0193594 -0.0190033 0.0337173 -0.037111 -0.0102402 0.0115966 -0.037111 -0.0190033 0.0115966 -0.0346177 -0.0190033 0.0118013 -0.0353843 -0.0100371 0.0115376 -0.0359731 -0.0190033 0.0114604 -0.0359672 -0.0101029 0.0114607 -0.036545 -0.0101709 0.0114813 -0.0338488 -0.00988157 0.0123039 -0.0335037 -0.0190033 0.0126453 -0.0337103 -0.00986947 0.0124297 -0.0277194 -0.0173225 0.0487966 -0.0281989 -0.0173638 0.0492577 -0.029068 -0.0174228 0.0497628 -0.02945 -0.0174442 0.0498915 -0.0295242 -0.0190033 0.0499109 -0.031096 -0.0190033 0.0499404 -0.030728 -0.0175006 0.0499978 0.0499604 -0.0190033 0.0309519 0.0499041 -0.0190033 0.0295217 0.04928 -0.0190033 0.0282336 0.0494395 -0.0190033 0.032285 0.0320777 -0.0190033 0.0189257 0.0313793 -0.0190033 0.0500217 0.0122529 -0.0190033 0.0338987 0.0195347 -0.0190033 0.0554883 0.0167942 -0.0190033 0.0541184 0.0208049 -0.0190033 0.055264 0.0178735 -0.0014344 0.0488929 0.0272715 -0.00246153 0.048832 0.0179591 -0.0030749 0.0505157 0.0273675 -0.00328671 0.0492347 0.0363726 -0.0030749 0.0461196 0.0361106 -0.00209203 0.0455265 0.0271129 -0.00177261 0.0481664 0.0352493 -0.00120333 0.043577 0.0269116 -0.00133851 0.0473222 0.0162247 -0.00209203 0.0491615 0.0156011 -0.00375537 0.0497169 0.0160517 -0.00358615 0.050089 0.0167457 -0.0030749 0.0503067 0.0169867 -0.00335737 0.0504971 0.017925 -0.00209203 0.0498682 0.0173695 -0.0014344 0.048806 0.0169524 -0.0014344 0.04851 0.0178126 -0.00120333 0.0477399 0.015331 -0.00388964 0.0493962 0.0151439 -0.0030749 0.0485176 0.0157417 -0.0030749 0.049594 0.0169946 -0.00209203 0.049708 0.0163725 -0.00160525 0.0481596 0.019647 -0.0090251 0.0543738 0.0196187 -0.00916099 0.0545186 0.0193059 -0.00885013 0.0542311 0.0328526 -0.00542531 0.0485481 0.0304784 -0.0063876 0.0499276 0.0265917 -0.00633762 0.050935 0.0179623 -0.00323544 0.0505755 0.0364095 -0.00333248 0.0462029 0.0361928 -0.00160525 0.0447431 0.0357159 -0.0014344 0.0446331 0.0365898 -0.00209203 0.0452339 0.0369977 -0.0030749 0.045738 0.0371362 -0.00420333 0.0459092 0.0144699 -0.00120333 0.0362692 0.0317991 -0.00120333 0.0219802 0.0322673 -0.00120333 0.021987 0.0268898 -0.00120333 0.0276906 0.0469939 -0.00120333 0.0302501 0.0470019 -0.00120333 0.0304545 0.0267074 -0.00120333 0.0464555 0.0337104 -0.00420333 0.0193569 0.0336005 -0.00305528 0.0195571 0.0320777 -0.00420333 0.0189257 0.0320718 -0.00270333 0.0193276 0.0304331 -0.00420333 0.0193092 0.0294888 -0.00270333 0.0206487 0.0298793 -0.00208201 0.0209221 0.0311161 -0.00160525 0.0206447 0.032034 -0.00120333 0.0219254 0.0306161 -0.00270333 0.0196671 0.0320558 -0.00160525 0.0204256 0.0328195 -0.00143169 0.0209805 0.0136113 -0.00420333 0.0328954 0.0115224 -0.00420333 0.0354212 0.0125626 -0.00270333 0.0341548 0.011916 -0.00270333 0.0355025 0.0144603 -0.00120333 0.0360282 0.0129913 -0.00160525 0.0357247 0.0136987 -0.00305528 0.0331064 0.014185 -0.00160525 0.0342814 0.0134088 -0.00160525 0.0348547 0.0145647 -0.00120333 0.0358106 0.01675 -0.0111396 0.0540595 0.0177338 -0.0112789 0.0549672 0.016941 -0.0108076 0.0542663 0.0190353 -0.00952326 0.0548312 0.0178303 -0.00983436 0.0546308 0.0194183 -0.00902883 0.0544024 0.0193086 -0.0107688 0.0554175 0.0191743 -0.0113684 0.0554659 0.0180939 -0.010655 0.055085 0.0171879 -0.0104715 0.0544364 0.0185404 -0.0100505 0.0550408 0.0194548 -0.0101823 0.0552402 0.0197909 -0.00920571 0.0545465 0.0158413 -0.00728539 0.0511133 0.0185212 -0.00615875 0.0520252 0.0175237 -0.00635403 0.0520224 0.0166998 -0.00341417 0.0504118 0.0149324 -0.00420333 0.0485792 0.0165671 -0.00674888 0.0517079 0.0182853 -0.00907387 0.054301 0.0173055 -0.00956879 0.0540832 0.0165747 -0.0102593 0.0535938 0.016352 -0.0106159 0.0532961 0.0167042 -0.0014344 0.0480629 0.0130298 -0.00160525 0.0366889 0.0157664 -0.00209203 0.0483362 0.0119756 -0.00270333 0.0369961 0.0115897 -0.00420333 0.0371085 0.0153183 -0.00270333 0.0484668 0.0467493 -0.00120333 0.0299332 0.0473016 -0.00143169 0.0289267 0.0329888 -0.00160525 0.020672 0.0332877 -0.00208201 0.0201272 0.0479991 -0.00270333 0.0276555 0.0335171 -0.00270333 0.0197093 0.0480826 -0.00305528 0.0275033 0.0481925 -0.00420333 0.0273031 0.0260899 -0.00143169 0.0268671 0.0147587 -0.00120333 0.0356673 0.0143196 -0.00143169 0.0346066 0.0212027 -0.00120333 0.0322545 0.0316171 -0.00120333 0.0221386 0.0303883 -0.00160525 0.0212784 0.0196799 -0.00305528 0.0299386 0.0249587 -0.00305528 0.0257025 0.0293466 -0.00305528 0.0205491 0.0205719 -0.00143169 0.0312952 0.0139474 -0.00208201 0.0337073 0.0200372 -0.00208201 0.030482 0.013765 -0.00270333 0.0332668 0.0254118 -0.00208201 0.0261689 0.0247996 -0.00420333 0.0255386 0.0222766 -0.00420333 0.0277674 0.0195544 -0.00420333 0.0297478 0.0368834 -0.00270333 0.0455968 0.039896 -0.00120333 0.0393663 0.0481835 -0.00160525 0.031465 0.0491029 -0.00270333 0.0320653 0.0409639 -0.00160525 0.0404198 0.0494395 -0.00420333 0.032285 0.0417456 -0.00270333 0.041191 0.0420317 -0.00420333 0.0414733 0.0293044 -0.00777879 0.0510771 0.0335147 -0.00690447 0.0486165 0.0296723 -0.00869987 0.0510529 0.0208049 -0.0113663 0.055264 0.0368028 -0.00375936 0.0461047 0.0333097 -0.00609501 0.0486246 0.0277523 -0.00728853 0.0513459 0.0208872 -0.00901155 0.0542107 0.0250088 -0.00909421 0.0532578 0.0204573 -0.0101804 0.0551192 0.0199877 -0.00919857 0.0545164 0.0474709 -0.00160525 0.0286182 0.0480923 -0.00160525 0.0291499 0.0499604 -0.00420333 0.0309519 0.0499041 -0.00420333 0.0295217 0.04928 -0.00420333 0.0282336 0.0489618 -0.00270333 0.0284791 0.0484811 -0.00160525 0.0307032 0.049564 -0.00270333 0.0308852 0.0495142 -0.00270333 0.0296193 0.048449 -0.00160525 0.0298859 0.0477698 -0.00208201 0.0280734 0.0469275 -0.00120333 0.0306449 0.0469047 -0.00120333 0.0300661 0.0358363 -0.00537498 0.0469311 0.0420317 -0.0190033 0.0414733 0.0481925 -0.0190033 0.0273031 0.0337104 -0.0190033 0.0193569 0.0162113 -0.0109791 0.0529677 0.0154595 -0.00784217 0.050388 0.0115897 -0.0190033 0.0371085 0.0202156 -0.0113793 0.0554286 0.0185595 -0.0113419 0.055339 0.0180066 -0.0190033 0.0551191 0.0170797 -0.0111979 0.0544469 0.0162113 -0.0190033 0.0529677 0.0136113 -0.0190033 0.0328954 0.0222766 -0.0190033 0.0277674 0.0291595 -0.00420333 0.0204182 0.0122529 -0.00420333 0.0338987 0.0115224 -0.0190033 0.0354212 0.0291595 -0.0190033 0.0204182 0.0304331 -0.0190033 0.0193092 -0.0355376 -0.0190033 0.00864442 -0.0328917 -0.0190033 -0.0136289 -0.032823 -0.0190033 -0.0161297 -0.0344413 -0.0190033 -0.0180375 -0.0546735 -0.0190033 0.0149045 -0.0577943 -0.0190033 0.0121371 -0.0533898 -0.0190033 0.014778 -0.0590533 -0.0190033 0.000401913 -0.0575656 -0.0190033 -0.0131751 -0.0530557 -0.0190033 -0.025416 -0.0537952 -0.0190033 -0.0243592 -0.0395546 -0.00631522 -0.0160418 -0.0395514 -0.00653347 -0.0104547 -0.0383982 -0.00469228 -0.0149371 -0.0393216 -0.00602949 -0.0158731 -0.0382825 -0.00449435 -0.0147744 -0.0383073 -0.00455926 -0.0146194 -0.0514789 -0.0133334 -0.023381 -0.0513965 -0.0133035 -0.023344 -0.0463146 -0.0112705 -0.0118987 -0.0415254 -0.00832598 -0.0107559 -0.04097 -0.00776115 -0.0170299 -0.0552122 -0.0148919 -0.014147 -0.0520709 -0.013548 -0.0231079 -0.038349 -0.00458551 -0.0150804 -0.0554768 -0.0160361 0.0120933 -0.0555384 -0.0160447 0.0118951 -0.0552275 -0.0159478 0.0120877 -0.0402257 -0.00825366 0.00757301 -0.0458245 -0.0114095 0.00123966 -0.040537 -0.00788414 -0.000120331 -0.040077 -0.0080978 0.00728341 -0.0556065 -0.0154394 -0.00334109 -0.0568501 -0.0158604 -0.00496403 -0.0498717 -0.0130903 -0.00590694 -0.0460757 -0.0112834 -0.00489636 -0.0569502 -0.0161297 0.0033973 -0.0427716 -0.00929007 -0.00541892 -0.0402077 -0.00724854 -0.00581037 -0.0438016 -0.00994337 -0.00670579 -0.0460995 -0.0113776 -0.00245814 -0.0556215 -0.0155233 -0.00045199 -0.0552726 -0.0155492 0.00382313 -0.0558304 -0.0161389 0.011767 -0.0572608 -0.0172379 0.0120084 -0.0556975 -0.0179188 0.0144836 -0.0547795 -0.0188416 0.0148937 -0.0571948 -0.0189496 0.013483 -0.0548334 -0.0161358 0.0131993 -0.0568869 -0.017199 0.0129236 -0.0562156 -0.0170958 0.0136338 -0.0556896 -0.0161034 0.0119799 -0.0559818 -0.0164343 0.0128708 -0.0554483 -0.0162933 0.0131244 -0.054846 -0.0168443 0.0141254 -0.0540889 -0.0188069 0.0149066 -0.054457 -0.0177869 0.0147346 -0.0553351 -0.016939 0.014049 -0.0550923 -0.0178564 0.0146689 -0.0562589 -0.0179733 0.014184 -0.0571628 -0.0180515 0.0132881 -0.0576651 -0.0180813 0.0121014 -0.0519322 -0.0134975 -0.0232936 -0.0527941 -0.0139535 -0.0235029 -0.0534929 -0.0163576 -0.0248949 -0.0514164 -0.0135401 -0.0245254 -0.0521711 -0.0162892 -0.0260463 -0.0518272 -0.0157762 -0.0261523 -0.0519465 -0.0152788 -0.0259646 -0.05251 -0.0153421 -0.0256617 -0.0502784 -0.0161914 -0.0263998 -0.0504713 -0.0156683 -0.0263657 -0.0506795 -0.0151325 -0.0262174 -0.0493943 -0.0149169 -0.0259236 -0.051094 -0.0141612 -0.0255562 -0.0500462 -0.0139369 -0.025385 -0.0524767 -0.0138587 -0.0240212 -0.0519997 -0.0137164 -0.0243782 -0.0537233 -0.015476 -0.0241772 -0.0528562 -0.0145202 -0.0247224 -0.0534155 -0.0154421 -0.0247539 -0.0530069 -0.0153972 -0.0252529 -0.0517169 -0.0134197 -0.0233968 -0.0520664 -0.0143617 -0.0253084 -0.0508917 -0.0146179 -0.0259456 -0.0520288 -0.014798 -0.0256807 -0.0391185 -0.00886996 0.00961594 -0.0412301 -0.013195 0.0112346 -0.0375307 -0.0105921 0.0101565 -0.0451586 -0.0153159 0.0123794 -0.0456809 -0.0142888 0.0123 -0.0418438 -0.0122088 0.0111787 -0.0463003 -0.013348 0.0117433 -0.0449645 -0.0114158 0.00902657 -0.0431675 -0.0107415 0.0096865 -0.0425483 -0.0113068 0.010636 -0.0472545 -0.0126003 0.00971587 -0.0468667 -0.0127524 0.0107931 -0.0543435 -0.0167414 0.0141047 -0.0538355 -0.0176686 0.0146603 -0.037377 -0.00986127 -0.0196482 -0.0382184 -0.00885659 -0.0197801 -0.0349692 -0.00592814 -0.0182397 -0.0491101 -0.0155553 -0.0260184 -0.0393753 -0.00617794 -0.0166685 -0.04064 -0.00753729 -0.0175538 -0.0390569 -0.00614258 -0.017326 -0.0403052 -0.0075278 -0.0181797 -0.0398576 -0.00766129 -0.0187742 -0.0439625 -0.00992434 -0.0189635 -0.0433621 -0.00987685 -0.0201096 -0.0393263 -0.00794579 -0.0192708 -0.040965 -0.0124902 -0.021617 -0.0362872 -0.00518135 -0.0181607 -0.0387612 -0.00835972 -0.0196147 -0.0363086 -0.00517117 -0.0181533 -0.0370059 -0.00487717 -0.0177971 -0.0380234 -0.00463643 -0.0166916 -0.0383624 -0.00468845 -0.0159118 -0.0383636 -0.00468905 -0.0159078 -0.0466888 -0.0113709 -0.0206141 -0.0437046 -0.00983917 -0.0195268 -0.0429472 -0.0100616 -0.0206636 -0.050788 -0.0133497 -0.0244222 -0.0507578 -0.0133635 -0.0244682 -0.0424881 -0.0103962 -0.0211338 -0.0415968 -0.0113985 -0.0216608 -0.0496839 -0.0144175 -0.0257267 -0.034767 -0.00402391 -0.0126751 -0.0357908 -0.00470794 -0.0114758 -0.0387975 -0.00635799 -0.00682553 -0.038718 -0.005697 -0.0108449 -0.0391768 -0.00607678 -0.0113767 -0.0400138 -0.00704922 -0.0071871 -0.0360269 -0.00701618 -0.00642381 -0.0352818 -0.005956 -0.00990128 -0.0361541 -0.00546847 -0.00997279 -0.0377798 -0.00626562 -0.00661487 -0.0342265 -0.0073765 -0.0101457 -0.035094 -0.00848438 -0.00652398 -0.0349799 -0.00920472 -0.00663828 -0.0379391 -0.00413749 -0.014091 -0.0344842 -0.0041681 -0.0126863 -0.0331686 -0.00537781 -0.0132186 -0.0371129 -0.00527129 -0.0101863 -0.0355516 -0.00754018 -0.00643253 -0.0346239 -0.00663619 -0.00997186 -0.0353949 -0.00778154 -0.00644836 -0.0374591 -0.00385193 -0.0136378 -0.0380035 -0.00537249 -0.0104979 -0.0367725 -0.00454424 -0.0117344 -0.0361752 -0.00365778 -0.0129327 -0.035465 -0.00377327 -0.0127412 -0.039928 -0.00748753 -8.73151e-05 -0.0356038 -0.0101732 -0.000249558 -0.0404116 -0.00752856 -0.00361108 -0.0394418 -0.00662285 -0.00699788 -0.040537 -0.00788164 -0.000158452 -0.0399297 -0.00794029 0.00699567 -0.0386425 -0.0063201 -0.00678895 -0.0373004 -0.00634588 -0.00653901 -0.0373395 -0.00746017 -6.70228e-05 -0.0367009 -0.00656623 -0.00646679 -0.0365563 -0.00798713 -9.93728e-05 -0.0359981 -0.00869149 -0.000146073 -0.0356924 -0.00945282 -0.000198657 -0.0353676 -0.00891824 0.00621251 -0.0382481 -0.00720215 -5.49003e-05 -0.0391475 -0.00723018 -6.32835e-05 -0.0374178 -0.00729962 0.00653818 -0.0385635 -0.00728436 0.00674 -0.0569773 -0.0159428 -0.00310162 -0.0590547 -0.0188816 2.95197e-06 -0.0584007 -0.0172256 0.00346305 -0.0586891 -0.0177977 -0.00522391 -0.0577423 -0.0165515 0.00343634 -0.0576329 -0.0162838 -0.00505502 -0.0585933 -0.018994 0.00736905 -0.0588179 -0.0180709 0.00347257 -0.0566206 -0.0165642 0.0118675 -0.0558486 -0.0161411 0.0117014 -0.0537952 -0.0163734 -0.0243592 -0.0566161 -0.015973 -0.0146696 -0.0533788 -0.014624 -0.0238794 -0.0588181 -0.0186813 -0.00527869 -0.0582809 -0.0169564 -0.0051461 -0.0570026 -0.0168215 -0.0148912 -0.0559835 -0.0153022 -0.0144082 -0.0382951 -0.00450125 -0.0149227 -0.0384906 -0.00482431 -0.0152556 -0.0328917 -0.00596734 -0.0136289 -0.0345535 -0.00579661 -0.0180561 -0.03367 -0.00611303 -0.0174637 -0.0370791 -0.00325566 -0.0147786 -0.0364704 -0.00365168 -0.0130496 -0.0349845 -0.00300088 -0.0156108 -0.0351644 -0.00317759 -0.0162864 -0.0361242 -0.00294443 -0.015453 -0.0378225 -0.00383806 -0.014794 -0.0356998 -0.00548459 -0.0182878 -0.0339599 -0.00618445 -0.017719 -0.0360432 -0.00406954 -0.0175191 -0.0351242 -0.00443325 -0.017738 -0.0326283 -0.00587652 -0.0148153 -0.0326249 -0.00587304 -0.0149691 -0.0341328 -0.00565613 -0.0177946 -0.0337086 -0.00550245 -0.0174273 -0.033542 -0.00608149 -0.0173309 -0.0329142 -0.00515545 -0.0161078 -0.0329935 -0.00594774 -0.0165325 -0.0338603 -0.0034479 -0.0148814 -0.0341316 -0.00363753 -0.0163799 -0.0340667 -0.0037485 -0.0134927 -0.0343552 -0.00315712 -0.0148493 -0.034625 -0.00336407 -0.0163562 -0.0346361 -0.00406281 -0.017281 -0.0338311 -0.00466722 -0.01718 -0.0337059 -0.00397723 -0.0163596 -0.0333604 -0.0043587 -0.0163017 -0.0331187 -0.00422353 -0.0149508 -0.0350941 -0.00330234 -0.0134765 -0.0349559 -0.00308563 -0.0140702 -0.0361969 -0.00321878 -0.0136548 -0.0360945 -0.00302117 -0.0141519 -0.0371591 -0.00347931 -0.0139755 -0.0373266 -0.00380076 -0.0135373 -0.0335762 -0.00486149 -0.0129276 -0.0336444 -0.00407393 -0.0135696 -0.0336936 -0.00474536 -0.0128728 -0.0345569 -0.00348487 -0.0134599 -0.0349073 -0.00296339 -0.0148216 -0.0360608 -0.00291015 -0.0147858 -0.0372149 -0.00339782 -0.0156567 -0.0362655 -0.00310556 -0.0160228 -0.0355587 -0.00472614 -0.0179768 -0.0352004 -0.00536651 -0.0181823 -0.0347723 -0.00517291 -0.0179923 -0.0343163 -0.0049449 -0.0176861 -0.0332885 -0.00533078 -0.0168987 -0.0374383 -0.00372216 -0.0161654 -0.037616 -0.00469394 -0.0172552 -0.0366141 -0.00354461 -0.0167247 -0.0364045 -0.00439316 -0.0177013 -0.0371872 -0.00423261 -0.0171875 -0.0380062 -0.00409476 -0.0155717 -0.0356215 -0.00365603 -0.0171275 -0.0334445 -0.00381253 -0.014916 -0.033302 -0.00443844 -0.0136819 -0.032731 -0.00508231 -0.0150154 -0.0328607 -0.00519952 -0.0139707 -0.03524 -0.00958946 0.00780456 -0.035328 -0.0103028 0.00825416 -0.0360613 -0.0104078 0.00929717 -0.0351031 -0.00953027 0.00702257 -0.0350232 -0.0102348 0.00649159 -0.0361409 -0.00821749 0.00803684 -0.0359639 -0.00808467 0.00721708 -0.0354092 -0.00877969 0.00712837 -0.0362094 -0.00786918 0.00633766 -0.0359061 -0.00976852 0.00904459 -0.0399316 -0.00796966 0.00721568 -0.0386145 -0.00743067 0.00769897 -0.0400205 -0.00806933 0.0074228 -0.0401703 -0.00820673 0.00755074 -0.0367819 -0.00751458 0.00643077 -0.0377654 -0.00744349 0.00789918 -0.0387478 -0.00732504 0.00677342 -0.0368424 -0.00996282 0.00982139 -0.0378861 -0.0101476 0.0102035 -0.0372791 -0.00944302 0.00986353 -0.0383204 -0.00965231 0.0101249 -0.038351 -0.00853368 0.00949744 -0.0387042 -0.00925473 0.00994082 -0.0397911 -0.00837616 0.00871501 -0.0393929 -0.00807723 0.00859413 -0.0367402 -0.00756203 0.00727154 -0.0369011 -0.00771228 0.00801922 -0.0364705 -0.00839784 0.0086955 -0.0355766 -0.00887813 0.00795639 -0.0358999 -0.00901349 0.00864515 -0.0355224 -0.00967342 0.00848385 -0.0389666 -0.00775319 0.0083104 -0.0388998 -0.00823575 0.00909526 -0.0382852 -0.00784617 0.00872531 -0.037564 -0.00813271 0.00903148 -0.0377943 -0.00895004 0.00975914 -0.0368844 -0.00859078 0.00918709 -0.0363185 -0.00916076 0.00918332 -0.0589531 -0.0189595 0.00346474 -0.0571055 -0.0177145 -0.0150443 -0.0350631 -0.0102341 0.00618811 -0.0350631 -0.0190033 0.00618811 -0.0350099 -0.0102387 0.00679623 -0.0350514 -0.0190033 0.0073341 -0.0352174 -0.0102848 0.00798378 -0.0364977 -0.0190033 0.00966005 -0.0365023 -0.0104656 0.00966325 -0.0344413 -0.00630243 -0.0180375 -0.0335404 -0.0190033 -0.0173291 -0.0327417 -0.00589014 -0.0158656 -0.0329621 -0.00594027 -0.0164678 -0.0326469 -0.00588555 -0.0145778 -0.0327013 -0.00590595 -0.0142418 -0.0326321 -0.0190033 -0.0147452 -0.0339288 -0.00788203 -0.010792 -0.0351954 -0.0094418 -0.00538071 -0.0353929 -0.0190033 -0.00387549 -0.035447 -0.00978822 -0.00334467 -0.0489233 -0.0190033 -0.0259837 -0.0464292 -0.0151634 -0.0246152 -0.0387159 -0.0109745 -0.0203829 -0.0533898 -0.0187704 0.014778 -0.0375307 -0.0190033 0.0101565 -0.0517141 -0.0190033 -0.0262355 -0.0523336 -0.0162976 -0.0259597 -0.0529229 -0.016328 -0.0255394 -0.0534171 -0.0163536 -0.0250011 -0.0516812 -0.0162639 -0.0262463 -0.0505323 -0.0162045 -0.0264145 -0.0501492 -0.0190033 -0.0263852 -0.0489233 -0.0161211 -0.0259837 -0.0577943 -0.0189672 0.0121371 -0.057078 -0.0189451 0.013634 -0.0573012 -0.0190033 0.013329 -0.0561201 -0.0189047 0.0144483 -0.0561689 -0.0190033 0.0144196 -0.0557368 -0.0188873 0.0146394 -0.026392 -0.0190033 0.0501467 -0.00819143 -0.0190033 0.0406872 -0.00157891 -0.0190033 0.0404715 -0.0254229 -0.0190033 0.0530532 -0.00751823 -0.0190033 0.0439846 -0.013182 -0.0190033 0.0575631 -0.00276691 -0.0190033 0.0445362 0.00039505 -0.0190033 0.0590508 -0.0153057 -0.0190033 0.032638 0.00538981 -0.00120333 0.0468286 0.000662897 -0.00132767 0.0465218 0.000576366 -0.0014344 0.0468089 0.000294508 -0.00209203 0.0477441 0.00964431 -0.0030749 0.0502931 0.000107397 -0.0030749 0.0483649 -0.0127674 -0.00209203 0.0417043 -0.0172569 -0.00209203 0.0384442 -0.0117291 -0.0014344 0.0410628 -0.00892506 -0.0030749 0.0406322 -0.0128757 -0.00231469 0.0418719 -0.0125441 -0.00300854 0.0425029 -0.0118003 -0.00302356 0.0426661 -0.0104455 -0.00324306 0.0425068 -0.00980359 -0.00344971 0.0421875 -0.0106107 -0.0030749 0.042508 -0.00954291 -0.0030749 0.0417723 -0.0108439 -0.00209203 0.041903 -0.0111952 -0.0014344 0.0409916 -0.0100252 -0.00209203 0.0413389 -0.0107517 -0.0014344 0.040686 -0.0101613 -0.00160525 0.0403017 -0.0116105 -0.00120333 0.0399143 -0.0118295 -0.00209203 0.0420343 -0.0122372 -0.0014344 0.040884 -0.0018338 -0.0033059 0.0465212 -0.00137672 -0.0030749 0.0441224 -0.00200427 -0.00349891 0.0458194 -0.00107786 -0.00310155 0.0476621 -0.000564155 -0.00209203 0.0472431 -0.000469767 -0.00308821 0.048123 -0.00184512 -0.0030749 0.0453314 -0.00120257 -0.00209203 0.0454182 0.000909551 -0.00120333 0.0457034 -0.00101249 -0.0030749 0.0477115 -0.0011022 -0.00209203 0.0464072 0.000111206 -0.0014344 0.0465375 -0.000180267 -0.0014344 0.0460847 -0.00171422 -0.0030749 0.0466213 -0.000234638 -0.0014344 0.0455489 0.0128525 -0.00369718 0.0480356 0.0126598 -0.0030749 0.0480993 0.0126079 -0.0030749 0.0467514 0.0124336 -0.00270333 0.0468022 0.0115738 -0.00209203 0.0488968 0.012071 -0.0030749 0.0493129 0.00993923 -0.00120333 0.0475291 0.0110477 -0.0014344 0.0472061 0.0113793 -0.00160525 0.0471094 0.0108247 -0.0014344 0.04827 0.0103716 -0.0014344 0.0485996 0.00981673 -0.0014344 0.0486772 0.0107374 -0.00209203 0.0495053 0.0097131 -0.00209203 0.0496484 0.0109802 -0.0030749 0.0501065 0.00963972 -0.00318778 0.050336 0.0120252 -0.00209203 0.0479663 0.0110693 -0.0014344 0.0477659 -0.0184451 -0.0030749 0.0379363 -0.0185427 -0.00420333 0.0353472 -0.0183463 -0.00316256 0.0382024 -0.0186903 -0.0030749 0.0366834 -0.0187761 -0.00343461 0.0372484 -0.0166408 -0.0014344 0.0376863 -0.0169645 -0.0014344 0.0372663 -0.0170664 -0.0014344 0.0367459 -0.0183496 -0.0030749 0.0354532 -0.0178544 -0.00209203 0.037669 -0.0180424 -0.00209203 0.0367084 -0.0172277 -0.00160525 0.0360687 -0.0138052 -0.00120333 0.0384099 -0.0154142 -0.00120333 0.0358819 -0.0159126 -0.00120333 0.0367903 -0.0109114 -0.00120333 0.0370293 -0.0107094 -0.00120333 0.0371453 -0.010582 -0.00120333 0.0373403 -0.00758056 -0.00420333 0.0379497 -0.00775765 -0.00420333 0.0363288 -0.00813603 -0.00270333 0.0364643 -0.00864993 -0.00420333 0.0349639 -0.00892585 -0.00270333 0.0352562 -0.00797929 -0.00270333 0.0378991 -0.00906862 -0.00160525 0.0377608 -0.00967968 -0.00160525 0.0360546 -0.0104876 -0.00160525 0.0355904 -0.010639 -0.00120333 0.0377898 -0.0105567 -0.00120333 0.0375719 -0.00916981 -0.00160525 0.0368345 0.0017375 -0.00120333 0.0387704 0.00169008 -0.00120333 0.039221 -0.0241071 -0.0142059 0.0517534 -0.0239399 -0.0141682 0.0517662 -0.00831856 -0.0118233 0.0546535 -0.0022353 -0.0124125 0.057512 -0.0106307 -0.0132253 0.0564459 -0.0168953 -0.0137513 0.0548212 0.000899762 -0.0120693 0.0575999 0.0114761 -0.0106883 0.0566728 0.0117587 -0.0105714 0.0565257 0.00569292 -0.0061296 0.051413 0.0106012 -0.00697016 0.0526517 -0.0115731 -0.00801856 0.0474361 -0.0091614 -0.00873149 0.0495202 -0.00549804 -0.00920143 0.0516157 -0.0142643 -0.0093168 0.0477664 -0.017654 -0.00302976 0.0389328 0.00124334 -0.0117181 0.0571001 0.0116678 -0.0104631 0.0563842 0.00375834 -0.00909085 0.0539296 0.0118561 -0.0102357 0.0560999 0.0118619 -0.010434 0.0563506 -0.0173795 -0.011935 0.0506522 0.000602874 -0.00270333 0.0363624 0.000401242 -0.00420333 0.0360147 0.000168062 -0.00160525 0.0388331 -0.000923984 -0.00270333 0.0387181 0.00165982 -0.00120333 0.0389901 0.000289086 -0.00160525 0.039757 0.000478761 -0.00160525 0.0379546 0.00115374 -0.00160525 0.0373123 -0.0004427 -0.00270333 0.0373574 0.00190624 -0.00120333 0.0386099 0.00206596 -0.00143169 0.0373969 -0.00815712 -0.00420333 0.039475 -0.00871222 -0.00420333 0.0406891 -0.00848963 -0.00270333 0.0392492 -0.00910051 -0.00270333 0.0405853 -0.00939808 -0.00160525 0.0386324 -0.00955146 -0.00209203 0.0404647 -0.00862519 -0.00851897 0.0433174 -0.0086673 -0.00908192 0.0429104 -0.00562635 -0.0077724 0.0483213 -0.00560435 -0.00777903 0.0492072 0.000100944 -0.00313163 0.0483863 -0.00103726 -0.00556656 0.0494057 -0.00139316 -0.00515731 0.0489162 -0.00149299 -0.00316861 0.0471722 -0.00237658 -0.00519518 0.0477747 -0.00337054 -0.00755025 0.050404 -0.00308527 -0.00686628 0.0497055 -0.00192651 -0.00511734 0.0484142 -0.00348648 -0.00673452 0.0490487 -0.00380497 -0.00677635 0.0482664 -0.0100383 -0.00679563 0.0450435 -0.0104158 -0.00669508 0.045236 -0.0082234 -0.00837414 0.049314 -0.0118931 -0.00301756 0.0426555 -0.0125126 -0.00506617 0.0438037 -0.0119543 -0.00676626 0.0456615 -0.0117864 -0.00502893 0.0438695 -0.0111596 -0.00309581 0.0426657 -0.00828829 -0.00928371 0.0439454 -0.00792329 -0.010508 0.0442797 -0.00781516 -0.00985721 0.0445401 -0.00738633 -0.0108735 0.0448133 -0.00721537 -0.0102188 0.0450561 -0.00883359 -0.00758392 0.0426993 -0.0094375 -0.0065885 0.0437244 -0.00964688 -0.00565855 0.0431459 -0.0100421 -0.00620357 0.0441682 -0.0049795 -0.00991492 0.0458126 -0.0042293 -0.00935317 0.0457725 -0.00295869 -0.00763993 0.0453676 -0.00300518 -0.00884803 0.0452723 -0.00213868 -0.00693672 0.0446648 -0.00651529 -0.0103526 0.0454544 -0.00629499 -0.0110711 0.0454511 -0.00575577 -0.0102509 0.0457092 -0.00509738 -0.0107688 0.0457142 -0.00475843 -0.0105949 0.045721 -0.00267855 -0.00540197 0.0470468 -0.00328125 -0.00628172 0.0472793 -0.00398205 -0.00702074 0.0474374 -0.00302791 -0.00605219 0.0480575 -0.00475328 -0.00760687 0.047493 -0.00468307 -0.00735395 0.0483634 -0.00637292 -0.00828044 0.0472517 -0.00658874 -0.00802104 0.0481287 -0.00837874 -0.00862702 0.0443798 -0.0086846 -0.00801611 0.0449036 -0.00752779 -0.00878006 0.0458863 -0.0072929 -0.00947188 0.0453752 -0.00603129 -0.00913669 0.0462136 -0.00531608 -0.00885175 0.04636 -0.00592858 -0.00949903 0.0459839 -0.00520806 -0.0091976 0.0461163 -0.00392384 -0.00771362 0.0463321 -0.00699848 -0.00859257 0.0465811 -0.0062572 -0.0085131 0.0468551 -0.00614197 -0.00880299 0.0465057 -0.00541396 -0.00853266 0.0466648 -0.00473616 -0.00781875 0.0470867 -0.00468501 -0.00807784 0.0467184 -0.0040059 -0.00721509 0.0470381 -0.00279081 -0.00572198 0.0463059 -0.00277361 -0.00591266 0.0459558 -0.00200604 -0.0037012 0.0452062 -0.00183417 -0.00396968 0.0445129 -0.00814731 -0.00848758 0.045434 -0.00792021 -0.00825896 0.046556 -0.00685154 -0.00888593 0.0462455 -0.00672854 -0.00922386 0.0459619 -0.00460326 -0.0083731 0.0463984 -0.00398558 -0.00744914 0.0466662 -0.00322418 -0.00713336 0.0458659 -0.00247608 -0.00653453 0.0450762 -0.00271154 -0.00611571 0.0456305 -0.0038257 -0.00799815 0.0460432 -0.0035472 -0.00858704 0.0456126 -0.00449599 -0.0086921 0.0461332 -0.00663165 -0.00959089 0.0457356 -0.00788351 -0.00914678 0.0449156 -0.00876224 -0.00792898 0.0438005 -0.00903094 -0.00706997 0.043214 -0.0126066 -0.00700796 0.0456841 -0.0129686 -0.00617439 0.0446082 -0.0131148 -0.00305428 0.0422417 -0.006312 -0.00857566 0.05051 -0.00551418 -0.00800096 0.0499829 -0.00790098 -0.00812067 0.0486037 -0.0075331 -0.0080965 0.0477855 -0.00734567 -0.00819042 0.0473656 -0.00922262 -0.00772419 0.0466873 -0.0110773 -0.00827459 0.0480143 -0.0105299 -0.00792996 0.0477041 -0.00989229 -0.0077207 0.0472568 -0.0112027 -0.00664413 0.0455188 -0.010273 -0.00532785 0.0435393 -0.0110138 -0.00511253 0.0437866 -0.00919439 -0.00606435 0.0426545 -0.00275951 -0.00554987 0.0466728 -0.00549718 -0.00825445 0.0470253 -0.00556186 -0.00802962 0.0474313 -0.00716516 -0.00835742 0.0469589 -0.0086108 -0.00798606 0.0460513 -0.00890333 -0.00782228 0.0463726 -0.00920823 -0.00754475 0.0454629 -0.00968877 -0.00694621 0.0448223 -0.00911797 -0.00737833 0.0443222 -0.00893386 -0.00649576 0.0421262 -0.00933787 -0.00366624 0.0417976 -0.00892411 -0.00395335 0.0412262 -4.19913e-06 -0.00208201 0.0423052 -0.00089862 -0.00305528 0.0402113 -0.000736513 -0.00270333 0.0401493 -0.000291225 -0.00208201 0.0399789 -0.000649854 -0.00305528 0.0422275 -0.00155793 -0.00420333 0.0439971 -0.0013701 -0.00305528 0.044127 -0.000843421 -0.00209203 0.0444912 -0.000835218 -0.00208201 0.0444969 0.000962092 -0.00143169 0.0424216 -3.47116e-05 -0.00143169 0.0450505 0.00210191 -0.00120333 0.0425588 0.00901171 -0.00270333 0.0363488 0.00786593 -0.00420333 0.0351771 0.00618124 -0.00420333 0.0350606 0.00774231 -0.00270333 0.0355595 0.00633392 -0.00208201 0.035926 0.00822404 -0.00160525 0.0371139 0.00726944 -0.00120333 0.0383675 0.00714807 -0.00120333 0.038159 0.0069432 -0.00120333 0.0380316 0.00740457 -0.00160525 0.0366044 0.00644189 -0.00160525 0.0365378 0.00670253 -0.00120333 0.038015 -0.0153057 -0.00420333 0.032638 -0.0168988 -0.00420333 0.033198 -0.017692 -0.00270333 0.0346322 -0.0152678 -0.00270333 0.0330382 -0.016678 -0.00270333 0.0335339 -0.0167293 -0.00160525 0.0351604 -0.0151643 -0.00160525 0.0341314 -0.015023 -0.00120333 0.0356247 -0.0160747 -0.00160525 0.0344514 -0.0152506 -0.00120333 0.0357047 -0.0260664 -0.0160858 0.0518254 -0.0254066 -0.0161578 0.0528997 -0.0255648 -0.0169886 0.0528993 -0.025423 -0.0169919 0.0530532 -0.0262777 -0.0159634 0.050614 -0.0262023 -0.0165177 0.0517338 -0.0264014 -0.0168716 0.0502243 -0.0238139 -0.0142705 0.0521132 -0.0240005 -0.0142618 0.0519687 -0.0248963 -0.0146216 0.0519202 -0.0241051 -0.0141167 0.0515237 -0.0248554 -0.0169973 0.0535221 -0.0243479 -0.015881 0.0535645 -0.0250632 -0.0153621 0.0527336 -0.024272 -0.0153748 0.0533113 -0.026382 -0.0164213 0.0504129 -0.0260833 -0.0155189 0.0508194 -0.0258018 -0.0151101 0.0510196 -0.0255913 -0.0152697 0.0519321 -0.0250296 -0.0144758 0.0513667 -0.0240644 -0.0140655 0.0514185 0.00870954 -0.00160525 0.0379478 0.0119854 -0.00209203 0.0469328 0.00976377 -0.00270333 0.0376406 0.013199 -0.00599084 0.0490342 0.0136373 -0.00804586 0.0504918 0.0100642 -0.00515197 0.0513166 0.0120005 -0.00518117 0.0507047 0.0109724 -0.0031201 0.0501289 0.0110562 -0.00312348 0.0500955 0.012216 -0.00330737 0.049265 0.011358 -0.00508353 0.0510513 0.0130058 -0.00730369 0.0515556 0.0125555 -0.00537693 0.0502235 0.0130441 -0.0102571 0.0557368 0.0118547 -0.00692584 0.0523389 0.0131037 -0.0102698 0.0557093 0.0124721 -0.0070586 0.0520017 0.0147712 -0.0125787 0.0533874 0.0136394 -0.0088791 0.0495035 -0.021725 -0.0117889 0.0411469 -0.0221219 -0.0119988 0.0477716 -0.018834 -0.00380649 0.036235 -0.0188561 -0.00363576 0.0366735 -0.0184975 -0.00322428 0.0379565 -0.0201511 -0.00936496 0.0440074 -0.0186318 -0.00643274 0.0409989 -0.0194006 -0.00663744 0.0403203 -0.0209805 -0.00958899 0.0433678 -0.0216015 -0.0101407 0.0425725 -0.019933 -0.00709753 0.039451 -0.0249567 -0.0142843 0.0508129 -0.0256759 -0.0148961 0.0500941 -0.0259064 -0.0153253 0.0497402 -0.0200935 -0.0077437 0.0385523 -0.0218542 -0.0109345 0.0417799 -0.0260328 -0.0158033 0.0494176 -0.0260568 -0.0162991 0.0491417 -0.0177811 -0.00209203 0.0357651 -0.0169249 -0.0014344 0.0362349 -0.0181904 -0.00270333 0.0355405 -0.0147844 -0.00120333 0.0356606 -0.0142101 -0.00160525 0.0342749 -0.0101773 -0.00270333 0.034537 -0.0137896 -0.00270333 0.0332605 -0.00879551 -0.0185033 0.034834 -0.00815712 -0.0185033 0.039475 0.00198579 -0.00270333 0.0359491 0.00201215 -0.00208201 0.0364251 0.0020465 -0.00160525 0.0370454 0.00212943 -0.00120333 0.0385432 0.0019762 -0.00305528 0.0357758 0.00625108 -0.00270333 0.0354564 -0.0241546 -0.0149273 0.0529765 -0.0154916 -0.0140822 0.0559522 0.00260475 -0.0123484 0.0581574 0.00270921 -0.0129635 0.0586115 -0.0155704 -0.016307 0.0569637 -0.0113311 -0.0159352 0.057956 -0.00654003 -0.0133063 0.0577573 -0.00651976 -0.0128448 0.0571213 0.0118383 -0.0117367 0.0575211 0.00911576 -0.0135537 0.0583438 0.00281777 -0.0136743 0.0588917 -0.00652827 -0.0139408 0.0582687 -0.0155816 -0.0147294 0.0564921 -0.00648401 -0.0146877 0.0585921 -0.0156077 -0.0155024 0.0568387 0.0141208 -0.0107426 0.0550369 0.0136012 -0.0129962 0.0570966 0.0140728 -0.0109326 0.0554853 0.014735 -0.0117542 0.054773 0.0146307 -0.0118851 0.0553528 0.0139461 -0.0111037 0.0559017 0.0144273 -0.0120046 0.0558973 0.0145989 -0.0128523 0.055811 0.014349 -0.0124967 0.0562214 0.0134908 -0.0113931 0.0566314 0.0137512 -0.0112565 0.0562834 0.0129489 -0.0105716 0.0562228 0.0116587 -0.0111525 0.0571542 0.0115752 -0.010666 0.0566455 0.0119996 -0.0123965 0.0577374 0.0132412 -0.012292 0.057247 0.0126774 -0.0108331 0.056639 0.0134255 -0.012647 0.0572025 0.0141267 -0.0121136 0.0564038 0.0127826 -0.0116116 0.0571983 0.0147142 -0.0115643 0.0542106 -0.0013237 -0.00420333 0.0386761 -0.00076919 -0.0185033 0.0371222 -0.000779978 -0.00420333 0.0371388 0.00196357 -0.00420333 0.0355477 -0.0088056 -0.00574237 0.0411419 -0.00789971 -0.0185033 0.0443078 -0.00829002 -0.0100467 0.0437596 -0.00876705 -0.0185033 0.0425221 -0.00878037 -0.00843641 0.042454 -0.00883155 -0.00782636 0.042083 -0.00884789 -0.00713843 0.0417221 -0.00628069 -0.0185033 0.0454566 -0.00424823 -0.010251 0.0456768 -0.00430876 -0.0185033 0.0456855 -0.00353452 -0.00956746 0.0455003 -0.00230917 -0.00742612 0.0448131 -0.00111191 -0.0185033 0.0402929 -0.00111191 -0.00420333 0.0402929 -0.000876578 -0.00420333 0.0422002 -0.00121627 -0.0185033 0.0433987 -0.00121627 -0.00420333 0.0433987 -0.00114077 -0.0186764 0.0403039 -0.00134541 -0.0189363 0.0403822 -0.00135622 -0.0190033 0.0414807 -0.000857411 -0.0185033 0.0414462 -0.000924239 -0.0187533 0.0414509 -0.00127709 -0.0187533 0.0433706 -0.00246962 -0.0185033 0.0449382 -0.00250945 -0.0187533 0.0448843 -0.0062567 -0.0187533 0.0453941 -0.0078486 -0.0187533 0.0442645 -0.00870142 -0.0187533 0.0425087 -0.00866907 -0.0185033 0.0405394 -0.00813155 -0.0186764 0.0394924 -0.00860508 -0.0187533 0.0405592 -0.0081017 -0.0187533 0.0395126 -0.00110682 -0.0189363 0.0414635 -0.00144325 -0.0189363 0.0432939 -0.00261827 -0.0189363 0.0447372 -0.00431779 -0.0187533 0.0456191 -0.00434246 -0.0189363 0.0454378 -0.00619114 -0.0189363 0.0452232 -0.0085221 -0.0189363 0.0424721 -0.00843025 -0.0189363 0.0406133 -0.00167022 -0.0190033 0.0431891 -0.00437615 -0.0190033 0.0451901 -0.00610159 -0.0190033 0.0449898 -0.00770897 -0.0189363 0.0441462 -0.00827716 -0.0190033 0.0424221 0.00157731 -0.0186545 0.035567 0.00196357 -0.0185033 0.0355477 0.000506438 -0.0188569 0.0357909 0.00108846 -0.0188264 0.0355854 0.000116579 -0.0190033 0.035602 -0.00148273 -0.0188569 0.0388224 -0.00141727 -0.0189724 0.0404097 -0.00117447 -0.0187533 0.0403168 -0.00124869 -0.0188569 0.0403452 -0.00166289 -0.0189724 0.0388115 -0.00104254 -0.0189724 0.0369429 -0.00089163 -0.0188569 0.0370419 -0.00136739 -0.0186764 0.0388294 -0.000795028 -0.0186764 0.0371053 -0.00133655 -0.0185033 0.0388312 0.00057273 -0.0185033 0.0359215 0.000558741 -0.0186764 0.035894 0.000424733 -0.0189724 0.03563 -0.00118723 -0.0190033 0.0368479 -0.00183563 -0.0190033 0.0388011 0.000568346 -0.0189583 0.0355976 0.00618124 -0.0190033 0.0350606 0.000393669 -0.0189853 0.0356 0.0148977 -0.0190033 0.054671 0.014911 -0.0126897 0.0543665 0.0148761 -0.0126339 0.0538739 0.0147712 -0.0190033 0.0533874 0.014764 -0.0128028 0.0553703 0.0148938 -0.0127288 0.0547128 0.0144129 -0.0128921 0.0561661 0.0144127 -0.0190033 0.0561664 0.0133221 -0.0190033 0.0572987 0.0121302 -0.0130752 0.0577919 0.00292 -0.014409 0.0589797 0.0121302 -0.0190033 0.0577919 -0.024366 -0.0190033 0.0537928 -0.024366 -0.0169946 0.0537928 -0.0064136 -0.0154626 0.0587034 0.00232901 -0.0144831 0.0590061 0.0128194 -0.00420333 0.0466898 0.0101496 -0.0190033 0.0375282 -0.0180443 -0.0190033 0.0344388 -0.0180443 -0.00420333 0.0344388 -0.0259905 -0.0190033 0.0489209 -0.0198868 -0.0084364 0.0377967 -0.0260429 -0.0169668 0.052189 -0.0262424 -0.0190033 0.0517116 -0.0262424 -0.0169477 0.0517115 -0.0259905 -0.0167844 0.0489209 -0.0264217 -0.0168901 0.0505472 -0.0136357 -0.0190033 0.0328892 -0.0100637 -0.00420333 0.0341515 -0.0136357 -0.00420333 0.0328892 -0.0100637 -0.0185033 0.0341515 -0.0168988 -0.0190033 0.033198 0.00786593 -0.0190033 0.0351771 0.00930001 -0.0190033 0.0360688 0.00930001 -0.00420333 0.0360688 0.0101496 -0.00420333 0.0375282 -0.00711088 -0.0190033 0.0381887 -0.00774346 -0.0190033 0.0397559 -0.00854755 -0.0189853 0.034562 -0.00870107 -0.0188569 0.034722 -0.00871703 -0.0189583 0.0345197 -0.00877558 -0.0186764 0.0348103 -0.00922052 -0.0188264 0.0343886 -0.00969216 -0.0186545 0.0342588 -0.00795029 -0.0189363 0.0396154 -0.00728142 -0.0189724 0.0381592 -0.00803596 -0.0188569 0.0395573 -0.00745929 -0.0188569 0.0381286 -0.00757315 -0.0186764 0.0381089 -0.00827829 -0.0190033 0.0346274 -0.00858467 -0.0189724 0.0345841 -0.00745719 -0.0189724 0.0361982 -0.00773532 -0.0186764 0.0362996 -0.0072946 -0.0190033 0.0361389 -0.00762677 -0.0188569 0.03626 -0.00776436 -0.0185033 0.0363102 -0.0076036 -0.0185033 0.0381037 -0.0331716 -0.0190033 -0.0306785 -0.0491989 -0.0190033 -0.028117 -0.0499429 -0.0190033 -0.0310891 -0.0494488 -0.0190033 -0.0322806 -0.0355193 -0.0190033 -0.0268652 -0.0378241 -0.0190033 -0.0401647 -0.0405999 -0.0190033 -0.0414693 -0.0400854 -0.00813593 -0.0255552 -0.0399946 -0.0075881 -0.0264442 -0.0357777 -0.00671373 -0.0272967 -0.0367336 -0.00917808 -0.0266664 -0.0391572 -0.0061116 -0.027657 -0.0395982 -0.00692674 -0.0271209 -0.038548 -0.00632672 -0.0271921 -0.0382381 -0.00755592 -0.026428 -0.0379337 -0.00885465 -0.025834 -0.037816 -0.0101461 -0.0253381 -0.0372291 -0.00704364 -0.0267998 -0.0370679 -0.00855021 -0.0264833 -0.0408881 -0.00709027 -0.0288717 -0.0411975 -0.00764539 -0.027478 -0.0406603 -0.00752883 -0.026939 -0.0403066 -0.00808414 -0.0256468 -0.039157 -0.00506838 -0.0286347 -0.0396514 -0.00602081 -0.028239 -0.037882 -0.00665002 -0.0268995 -0.0375172 -0.00559672 -0.027261 -0.0366477 -0.00746137 -0.0268757 -0.0362539 -0.00622746 -0.0271557 -0.0357254 -0.00654039 -0.0273208 -0.0374729 -0.00945649 -0.0259686 -0.0375985 -0.00803713 -0.0263688 -0.038546 -0.00829246 -0.0258572 -0.0389304 -0.00716903 -0.0266848 -0.0392606 -0.00784932 -0.0260654 -0.0401698 -0.00684766 -0.0276787 -0.0410676 -0.00804588 -0.0260301 -0.038039 -0.0108429 -0.0249156 -0.0415839 -0.00843396 -0.0255673 -0.0410573 -0.0085627 -0.0250324 -0.0405451 -0.0101191 -0.0238468 -0.0376136 -0.010788 -0.0255446 -0.0378964 -0.0108247 -0.0250953 -0.0383154 -0.0102564 -0.024709 -0.0417804 -0.00897199 -0.0249045 -0.0409432 -0.00907475 -0.0244594 -0.0404685 -0.00885478 -0.0245982 -0.0404326 -0.00948655 -0.02413 -0.0399397 -0.00997201 -0.0239591 -0.0393356 -0.00981402 -0.0242025 -0.0397688 -0.0110527 -0.0238078 -0.042392 -0.0113471 -0.0241109 -0.0425915 -0.0109742 -0.0242586 -0.0427598 -0.0105962 -0.0244702 -0.0428872 -0.0102272 -0.0247438 -0.0422396 -0.0096124 -0.0246121 -0.0427269 -0.00893195 -0.0266349 -0.0389685 -0.00869167 -0.0252366 -0.0393095 -0.00907003 -0.0246601 -0.0380907 -0.00963351 -0.0252329 -0.0385604 -0.0109079 -0.0244159 -0.0395093 -0.00835717 -0.0253589 -0.0387409 -0.00964393 -0.0246094 -0.0398751 -0.00928842 -0.0243147 -0.0388918 -0.0103713 -0.0242483 -0.0412355 -0.00806867 -0.0261299 -0.0425571 -0.00907493 -0.0255655 -0.0420915 -0.0087808 -0.0254583 -0.0414001 -0.00927373 -0.0244277 -0.0419943 -0.00997712 -0.0242373 -0.0409774 -0.00966699 -0.0240676 -0.041709 -0.0103795 -0.0239575 -0.0414016 -0.0107958 -0.0237797 -0.0401345 -0.0105924 -0.023766 -0.0395018 -0.0104833 -0.0239413 -0.0391518 -0.0109796 -0.0240445 -0.0391409 -0.0109783 -0.02405 -0.0371921 -0.00297719 -0.0300197 -0.036913 -0.00352865 -0.0286174 -0.033668 -0.0058902 -0.0305097 -0.0338625 -0.00519723 -0.02967 -0.0338364 -0.00596387 -0.029437 -0.0358452 -0.00451408 -0.0278518 -0.0350265 -0.00500788 -0.0280324 -0.0345226 -0.00463553 -0.0287651 -0.0344413 -0.00554714 -0.0283968 -0.0340275 -0.00531914 -0.0291369 -0.033777 -0.0051056 -0.0303455 -0.0353255 -0.00401538 -0.028529 -0.0343006 -0.00441859 -0.0293696 -0.0350817 -0.00371507 -0.0291567 -0.0341756 -0.00424847 -0.030205 -0.0344851 -0.00543197 -0.0326623 -0.0339968 -0.00519078 -0.0317618 -0.0372505 -0.00296847 -0.0309384 -0.0363303 -0.00325554 -0.0319963 -0.035596 -0.00399898 -0.0326981 -0.0347691 -0.00462354 -0.0325737 -0.0352695 -0.00369859 -0.0320944 -0.0360153 -0.00300441 -0.0300132 -0.0360835 -0.00299471 -0.0310968 -0.0366082 -0.00293319 -0.0300068 -0.0374455 -0.00353042 -0.028771 -0.0363632 -0.00361175 -0.0285226 -0.0361446 -0.00327403 -0.0291103 -0.0338243 -0.00510237 -0.0310937 -0.0342357 -0.00424237 -0.031166 -0.0338092 -0.00591264 -0.0314938 -0.0339527 -0.00594792 -0.0318923 -0.0348456 -0.00628859 -0.0278911 -0.0359832 -0.0055202 -0.0273639 -0.0369381 -0.00586662 -0.0271308 -0.0367459 -0.00515345 -0.0273601 -0.0393928 -0.00466743 -0.0301944 -0.0389451 -0.00396137 -0.0302019 -0.0393941 -0.00463469 -0.030437 -0.0394383 -0.00470834 -0.0305739 -0.038156 -0.00533964 -0.0275777 -0.0387186 -0.0051592 -0.0280525 -0.0375486 -0.00486741 -0.0275914 -0.0391138 -0.00507426 -0.0285642 -0.0391109 -0.00440754 -0.0294844 -0.0383827 -0.00351876 -0.0312812 -0.0379458 -0.00332436 -0.0314982 -0.0374439 -0.00320533 -0.0316988 -0.0378771 -0.00379642 -0.0324502 -0.0375951 -0.00379795 -0.0326115 -0.0366271 -0.00359348 -0.0325646 -0.0344682 -0.00440678 -0.0319934 -0.0350073 -0.00346744 -0.0311754 -0.0349389 -0.00347605 -0.0300823 -0.0368121 -0.00416821 -0.0279382 -0.0355186 -0.00529089 -0.0276177 -0.0340898 -0.00605173 -0.0288439 -0.0382154 -0.00335404 -0.0300928 -0.0377354 -0.00312447 -0.0300496 -0.0383656 -0.00375644 -0.0292038 -0.0385613 -0.00414521 -0.0288557 -0.0377691 -0.00404457 -0.0282999 -0.0382896 -0.00470448 -0.0280431 -0.0363194 -0.00487448 -0.0275271 -0.0353383 -0.00591362 -0.0275635 -0.0348874 -0.00574144 -0.0279061 -0.042567 -0.00829971 -0.038106 -0.0425788 -0.00829829 -0.0383556 -0.0422237 -0.00796427 -0.0380101 -0.0425156 -0.00876637 -0.0266017 -0.0423226 -0.00860553 -0.0266927 -0.0422071 -0.00850226 -0.0268549 -0.0415855 -0.00788481 -0.0279994 -0.0479982 -0.0119442 -0.0299269 -0.0482426 -0.0120543 -0.0303416 -0.0481703 -0.012022 -0.0306413 -0.0480844 -0.011983 -0.0302842 -0.0427786 -0.00897099 -0.0266642 -0.0396027 -0.00512829 -0.0298752 -0.0402068 -0.00615945 -0.0294813 -0.0395178 -0.00491979 -0.0302234 -0.0393818 -0.00462591 -0.0303178 -0.0394506 -0.00481061 -0.0300324 -0.0395547 -0.00983739 -0.0412808 -0.0387514 -0.00967014 -0.04091 -0.0421864 -0.00990942 -0.0409454 -0.0422834 -0.00801755 -0.038146 -0.0411495 -0.00728953 -0.0385713 -0.0416754 -0.00781302 -0.0394572 -0.0433672 -0.00955183 -0.0394495 -0.0427917 -0.0100594 -0.0405397 -0.0418688 -0.00935288 -0.0409063 -0.0372362 -0.0100563 -0.0390953 -0.0376552 -0.00875526 -0.0393316 -0.0384429 -0.00884363 -0.0403786 -0.0379931 -0.00949811 -0.0402587 -0.0385919 -0.00773237 -0.0393112 -0.0411463 -0.0101433 -0.0413887 -0.0393744 -0.0103454 -0.0412663 -0.0403588 -0.00999498 -0.0414294 -0.0400428 -0.009344 -0.0412498 -0.0392451 -0.00910689 -0.0409686 -0.0390708 -0.00823596 -0.0403367 -0.0398251 -0.00777207 -0.0401043 -0.0427701 -0.0084804 -0.0383297 -0.0428147 -0.00870728 -0.0393173 -0.0424623 -0.00818691 -0.0383176 -0.0420033 -0.00807915 -0.0395548 -0.0416727 -0.00876601 -0.0406508 -0.0416066 -0.00821413 -0.0401626 -0.0422992 -0.00831322 -0.0395471 -0.042173 -0.00900631 -0.0405 -0.0426246 -0.00921599 -0.0402474 -0.0430239 -0.00939735 -0.0399004 -0.0427016 -0.0107981 -0.0407303 -0.0433219 -0.0101899 -0.0399752 -0.041319 -0.00751787 -0.0391893 -0.0406093 -0.00752679 -0.0397005 -0.0411315 -0.00789407 -0.0400492 -0.039845 -0.00857901 -0.0408493 -0.0404983 -0.00815612 -0.0405343 -0.040579 -0.00887716 -0.0410511 -0.0411176 -0.00848671 -0.0406795 -0.0412522 -0.00913169 -0.0410523 -0.0408025 -0.00955334 -0.041313 -0.0415185 -0.00974059 -0.0412052 -0.049221 -0.0130889 -0.0316412 -0.0495105 -0.013156 -0.0307397 -0.0494725 -0.0131462 -0.0297843 -0.0491132 -0.0130614 -0.0289107 -0.0482018 -0.0146762 -0.0272987 -0.0487854 -0.0147139 -0.0277001 -0.0493038 -0.0138818 -0.0284675 -0.0500023 -0.0147921 -0.0307006 -0.0499032 -0.0147857 -0.0294777 -0.0489173 -0.0124886 -0.0300078 -0.048201 -0.0120358 -0.0305816 -0.0487679 -0.0124363 -0.0311534 -0.0489099 -0.0138299 -0.0280001 -0.0484397 -0.013767 -0.0276163 -0.0494534 -0.0139026 -0.0320324 -0.049864 -0.0139554 -0.0308563 -0.0498106 -0.0139479 -0.0296009 -0.0481753 -0.0120241 -0.030111 -0.0376136 -0.0185033 -0.0255446 -0.0408018 -0.0111716 -0.0236806 -0.0383856 -0.0185033 -0.0245612 -0.042392 -0.0185033 -0.0241109 -0.0410898 -0.0112041 -0.0237002 -0.0483285 -0.0122748 -0.0290519 -0.0429679 -0.00931752 -0.0258442 -0.0484908 -0.0129122 -0.0282294 -0.0429664 -0.00988241 -0.0250724 -0.0391708 -0.00429376 -0.0311714 -0.038015 -0.00596688 -0.0356906 -0.0383806 -0.0048668 -0.0337773 -0.0397975 -0.00590411 -0.034903 -0.0404435 -0.00623776 -0.0344315 -0.038657 -0.00395584 -0.0318293 -0.038769 -0.00400631 -0.0317107 -0.0349513 -0.00493366 -0.0329254 -0.0359146 -0.00427313 -0.0330747 -0.0374246 -0.0050117 -0.0341697 -0.0362078 -0.00413493 -0.0330529 -0.0369069 -0.00390041 -0.0328996 -0.0408747 -0.0066832 -0.0340004 -0.0416984 -0.00753888 -0.0383123 -0.0389557 -0.00578771 -0.0353513 -0.039846 -0.0072063 -0.0390383 -0.039195 -0.0073973 -0.0392038 -0.0371288 -0.00643623 -0.0358533 -0.0364331 -0.00709843 -0.0358276 -0.0359854 -0.00782034 -0.0356567 -0.0377541 -0.00859631 -0.0393443 -0.0357648 -0.00849717 -0.0354047 -0.0373855 -0.00934797 -0.0392507 -0.0341374 -0.0185033 -0.0322605 -0.0340635 -0.00597653 -0.0321258 -0.0337729 -0.00594003 -0.0296592 -0.0337105 -0.0185033 -0.0310532 -0.0346504 -0.0185033 -0.0280782 -0.0346571 -0.00623174 -0.0280712 -0.0338306 -0.0185033 -0.0294552 -0.0344423 -0.00616539 -0.028314 -0.0463405 -0.0132013 -0.0366024 -0.0431049 -0.0108527 -0.0403621 -0.0463191 -0.011661 -0.0358318 -0.0460003 -0.011043 -0.0352776 -0.0455287 -0.0106284 -0.0347022 -0.0432258 -0.00901288 -0.0388372 -0.0429229 -0.00862589 -0.038209 -0.0494488 -0.0147566 -0.0322806 -0.0464329 -0.0124142 -0.0362903 -0.0420359 -0.0186548 -0.0239155 -0.041586 -0.0188268 -0.0236687 -0.041256 -0.0189253 -0.0234876 -0.0492616 -0.0147445 -0.0281938 -0.0482018 -0.0190033 -0.0272987 -0.0497583 -0.0147764 -0.029044 -0.0499134 -0.0190033 -0.0295173 -0.0499718 -0.0147901 -0.030935 -0.0341374 -0.00599596 -0.0322605 -0.0372362 -0.0190033 -0.0390953 -0.0431049 -0.0190033 -0.0403621 -0.0407756 -0.0105372 -0.0414623 -0.0410512 -0.0105747 -0.0414335 -0.0421282 -0.0190033 -0.0410937 -0.0415993 -0.010649 -0.0413087 -0.042386 -0.0107554 -0.0409495 -0.0390615 -0.0190033 -0.0411372 -0.0391434 -0.0103137 -0.0411744 -0.0380844 -0.0101686 -0.0404535 -0.0377219 -0.0101195 -0.0400312 -0.0373925 -0.0189363 -0.0254279 -0.0381686 -0.0189724 -0.0243166 -0.0395771 -0.0190033 -0.0233427 -0.0380538 -0.0190033 -0.0241872 -0.0383651 -0.0186764 -0.0245381 -0.0382884 -0.0188569 -0.0244516 -0.041239 -0.0185033 -0.0237198 -0.0406943 -0.0190033 -0.0231794 -0.0411081 -0.0189586 -0.0234065 -0.0412613 -0.0188569 -0.0235751 -0.0397097 -0.0186764 -0.0237926 -0.0397185 -0.0185033 -0.0238223 -0.0412437 -0.0186764 -0.0236893 -0.0396771 -0.0188569 -0.0236818 -0.039626 -0.0189724 -0.0235087 -0.0375862 -0.0186764 -0.0255302 -0.0374841 -0.0188569 -0.0254762 -0.0366461 -0.0189363 -0.0264078 -0.0373245 -0.0189724 -0.0253919 -0.0371715 -0.0190033 -0.0253111 -0.0368173 -0.0185033 -0.0265899 -0.0367714 -0.0187533 -0.0265411 -0.0375543 -0.0187533 -0.0255133 -0.0356223 -0.0189363 -0.027093 -0.0364748 -0.0190033 -0.0262257 -0.0344152 -0.0189724 -0.0278511 -0.0333538 -0.0190033 -0.0293046 -0.0335189 -0.0189724 -0.0293567 -0.0334147 -0.0189584 -0.0310608 -0.0334262 -0.0189543 -0.0310792 -0.0336891 -0.0188264 -0.0315047 -0.0336799 -0.0186764 -0.031058 -0.0339416 -0.0186545 -0.0319255 -0.035665 -0.0188569 -0.0271873 -0.0356978 -0.0187533 -0.0272597 -0.0345451 -0.0188569 -0.0279765 -0.0346282 -0.0186764 -0.0280568 -0.0357126 -0.0186764 -0.0272926 -0.0357254 -0.0185033 -0.0273208 -0.0335658 -0.0188569 -0.031076 -0.0342907 -0.0190033 -0.0277309 -0.033691 -0.0188569 -0.0294111 -0.0338011 -0.0186764 -0.0294459 0.0367311 -0.0816033 0.0112226 0.0367311 -0.0821033 0.0112226 0.0356204 -0.0821033 0.0112883 0.0345912 -0.0816033 0.0108657 0.0338473 -0.0816033 0.0100384 0.0338473 -0.0821033 0.0100384 0.033536 -0.0821033 0.00897021 0.0343601 -0.0816033 0.0069634 0.0343601 -0.0821033 0.0069634 0.0252408 -0.0821033 -0.0243301 0.0242116 -0.0821033 -0.0247527 0.0242116 -0.0816033 -0.0247527 0.0231564 -0.0816033 -0.0266482 0.0231564 -0.0821033 -0.0266482 0.0233394 -0.0816033 -0.0277457 0.0233394 -0.0821033 -0.0277457 0.0239804 -0.0816033 -0.028655 0.0249526 -0.0816033 -0.0291962 0.0239804 -0.0821033 -0.028655 0.00708665 -0.0816033 -0.0342283 0.00708665 -0.0821033 -0.0342283 0.00638722 -0.0821033 -0.0366284 0.00700973 -0.0816033 -0.037763 0.00700973 -0.0821033 -0.037763 -0.00968485 -0.0821033 -0.0332161 -0.0107955 -0.0816033 -0.0331503 -0.0107955 -0.0821033 -0.0331503 -0.0118247 -0.0816033 -0.0335729 -0.0125686 -0.0816033 -0.0344003 -0.0125686 -0.0821033 -0.0344003 -0.0128799 -0.0816033 -0.0354684 -0.0128799 -0.0821033 -0.0354684 -0.0120558 -0.0816033 -0.0374752 -0.0110837 -0.0821033 -0.0380164 -0.0285318 -0.0816033 -0.0238487 -0.0285318 -0.0821033 -0.0238487 -0.0286087 -0.0816033 -0.0273834 -0.0275023 -0.0816033 -0.0280546 -0.0286087 -0.0821033 -0.0273834 -0.0374814 -0.0816033 -0.00677469 -0.0364522 -0.0821033 -0.00635206 -0.0385366 -0.0816033 -0.0086702 -0.0377125 -0.0816033 -0.010677 -0.0383536 -0.0821033 -0.00976765 -0.0377125 -0.0821033 -0.010677 -0.0249619 -0.0816033 0.0292006 -0.0262557 -0.0816033 0.0292288 -0.0262557 -0.0821033 0.0292288 -0.0273902 -0.0816033 0.0286062 -0.0273902 -0.0821033 0.0286062 -0.0280615 -0.0821033 0.0274999 -0.0274671 -0.0821033 0.0250715 -0.0092361 -0.0816033 0.0385044 -0.0102653 -0.0816033 0.0380818 -0.0110092 -0.0816033 0.0372545 -0.0102653 -0.0821033 0.0380818 -0.0110092 -0.0821033 0.0372545 -0.0111375 -0.0816033 0.0350888 -0.0113205 -0.0821033 0.0361863 -0.0111375 -0.0821033 0.0350888 -0.0104964 -0.0816033 0.0341795 -0.0104964 -0.0821033 0.0341795 0.0110744 -0.0821033 0.0380208 0.00864607 -0.0821033 0.0374264 0.00864607 -0.0816033 0.0374264 0.00794663 -0.0816033 0.0350263 0.00856914 -0.0821033 0.0338918 0.00856914 -0.0816033 0.0338918 0.00967552 -0.0816033 0.0332205 0.0261992 -0.0816033 0.0280872 0.027493 -0.0821033 0.028059 0.0243934 -0.0816033 0.0263583 0.0243652 -0.0816033 0.0250645 0.0249878 -0.0821033 0.02393 0.0249878 -0.0816033 0.02393 0.0260941 -0.0816033 0.0232587 0.0352026 -0.0816033 -0.00791148 0.0363132 -0.0821033 -0.00797726 0.0352026 -0.0821033 -0.00791148 0.0341733 -0.0816033 -0.00833411 0.0334294 -0.0816033 -0.00916144 0.0341733 -0.0821033 -0.00833411 0.0334294 -0.0821033 -0.00916144 0.0331182 -0.0816033 -0.0102296 0.0331182 -0.0821033 -0.0102296 0.0333012 -0.0821033 -0.0113271 0.0333012 -0.0816033 -0.0113271 0.0339422 -0.0816033 -0.0122364 -0.034504 -0.0821033 0.0142221 -0.0365741 -0.0821033 0.0142671 -0.0383893 -0.0816033 0.0132711 -0.0394634 -0.0816033 0.0115009 -0.0394634 -0.0821033 0.0115009 -0.0395084 -0.0816033 0.00943085 -0.0385124 -0.0821033 0.0076156 -0.0367422 -0.0821033 0.00654155 0.056285 -0.081911 -0.0342217 0.0613211 -0.0816674 -0.0359185 0.0612182 -0.0821033 -0.0363462 0.0353322 -0.0821033 0.00642224 0.0377605 -0.0816033 0.00701659 0.036626 -0.0821033 0.00639408 0.0377605 -0.0821033 0.00701659 0.0384318 -0.0821033 0.00812297 0.0384599 -0.0816033 0.00941676 0.0384599 -0.0821033 0.00941676 0.0378374 -0.0816033 0.0105513 0.0262464 -0.0816033 -0.0292244 0.0273809 -0.0816033 -0.0286019 0.0262464 -0.0821033 -0.0292244 0.0280803 -0.0816033 -0.0262017 0.0280803 -0.0821033 -0.0262017 0.0274578 -0.0816033 -0.0250672 0.0274578 -0.0821033 -0.0250672 0.00922676 -0.0821033 -0.0385 0.010256 -0.0821033 -0.0380774 0.0109999 -0.0816033 -0.0372501 0.0113112 -0.0821033 -0.0361819 0.0111282 -0.0816033 -0.0350845 0.0104871 -0.0816033 -0.0341751 0.0111282 -0.0821033 -0.0350845 0.0104871 -0.0821033 -0.0341751 -0.0110837 -0.0816033 -0.0380164 -0.00978993 -0.0821033 -0.0380446 -0.00798412 -0.0821033 -0.0363157 -0.00857848 -0.0816033 -0.0338874 -0.00795597 -0.0821033 -0.0350219 -0.00857848 -0.0821033 -0.0338874 -0.0263917 -0.0821033 -0.0281204 -0.0253625 -0.0821033 -0.0276978 -0.0246186 -0.0816033 -0.0268705 -0.0246186 -0.0821033 -0.0268705 -0.0243073 -0.0816033 -0.0258023 -0.0244903 -0.0816033 -0.0247048 -0.0354466 -0.0816033 -0.0112463 -0.0367404 -0.0821033 -0.0112182 -0.0354466 -0.0821033 -0.0112463 -0.0336408 -0.0821033 -0.00951745 -0.0342351 -0.0821033 -0.00708912 -0.0353415 -0.0821033 -0.00641785 -0.0263608 -0.0816033 0.0244003 -0.023477 -0.0816033 0.0255844 -0.023477 -0.0821033 0.0255844 -0.0231657 -0.0816033 0.0266526 -0.0231657 -0.0821033 0.0266526 -0.0233487 -0.0816033 0.0277501 -0.0233487 -0.0821033 0.0277501 -0.0239898 -0.0821033 0.0286594 -0.00952431 -0.0821033 0.0336383 -0.00823052 -0.0816033 0.0336102 -0.00823052 -0.0821033 0.0336102 -0.00709599 -0.0816033 0.0342327 -0.00639655 -0.0816033 0.0366328 -0.00639655 -0.0821033 0.0366328 -0.00701906 -0.0816033 0.0377674 -0.00701906 -0.0821033 0.0377674 -0.00812544 -0.0816033 0.0384386 0.00967552 -0.0821033 0.0332205 0.0107862 -0.0821033 0.0331547 0.0118154 -0.0816033 0.0335773 0.0125593 -0.0816033 0.0344047 0.0128706 -0.0816033 0.0354728 0.0128706 -0.0821033 0.0354728 0.0126876 -0.0816033 0.0365703 0.0120465 -0.0821033 0.0374796 0.0272048 -0.0816033 0.0231929 0.0272048 -0.0821033 0.0231929 0.0289779 -0.0816033 0.0244429 0.028234 -0.0821033 0.0236155 0.0292892 -0.0821033 0.0255111 0.0284651 -0.0816033 0.0275179 0.0284651 -0.0821033 0.0275179 0.027493 -0.0816033 0.028059 0.0349143 -0.0816033 -0.0127776 0.0349143 -0.0821033 -0.0127776 0.0373427 -0.0816033 -0.0121832 0.0362081 -0.0821033 -0.0128057 0.0380421 -0.0816033 -0.00978307 0.0380421 -0.0821033 -0.00978307 0.0374196 -0.0821033 -0.00864854 -0.0346721 -0.0816033 0.0064965 -0.0328569 -0.0816033 0.00749252 -0.0328569 -0.0821033 0.00749252 -0.0317378 -0.0816033 0.0113328 -0.0317828 -0.0821033 0.00926272 -0.0327338 -0.0821033 0.013148 -0.0327338 -0.0816033 0.013148 -0.034504 -0.0816033 0.0142221 -0.0767633 -0.0710986 0.00415631 -0.0705378 -0.0711033 0.00292318 -0.0702154 -0.0708533 0.00235164 -0.0704639 -0.0706033 0.00239871 -0.0686361 -0.08056 0.00254504 -0.0696309 -0.0798953 0.00274286 -0.070301 -0.078893 0.0028761 -0.0674644 -0.0807932 0.00231205 -0.0675829 -0.0801033 0.00171609 -0.0681634 -0.0800312 0.00186031 -0.0594097 -0.0807932 0.00480937 -0.0631677 -0.0801033 0.00140054 -0.0561132 -0.0801033 0.0163529 -0.0544592 -0.0807932 0.0323232 -0.0540309 -0.0801033 0.0327541 -0.0525451 -0.0801033 0.0304997 -0.0520852 -0.0801033 0.0278392 -0.0565146 -0.0807932 0.0336597 -0.0579245 -0.0801033 0.0348599 -0.0602513 -0.0777033 0.0356442 -0.0599272 -0.078926 0.0355343 -0.0602019 -0.0798968 0.0350934 -0.0595625 -0.0794088 0.0354109 -0.0610652 -0.0711033 0.0354291 -0.0555349 -0.0805237 -0.00233852 -0.0559869 -0.0801033 -0.00140839 -0.0556496 -0.0801033 0.00629839 -0.0455852 -0.0805235 0.0318068 -0.0464653 -0.0801033 0.0312658 -0.0503226 -0.0806033 0.0234192 -0.0537684 -0.0801033 0.0156695 -0.0532883 -0.0806033 0.0155297 -0.0540064 -0.0806033 0.012811 -0.0554794 -0.0806033 0.0016783 -0.0604862 -0.0708533 0.035738 -0.0606656 -0.0706033 0.0359257 -0.0601933 -0.0711033 0.035742 0.076967 -0.0711033 -0.00419912 0.0699575 -0.0711033 -0.00230015 0.0705284 -0.0711033 -0.00291879 0.0705284 -0.0777033 -0.00291879 0.070206 -0.0708533 -0.00234725 0.0704582 -0.0706033 -0.00228531 0.0696216 -0.0798953 -0.00273847 0.0686268 -0.08056 -0.00254065 0.068154 -0.0800312 -0.00185591 0.0684701 -0.0799273 -0.00193419 0.0688822 -0.0797097 -0.00203597 0.0658582 -0.0801033 -0.00137059 0.0580102 -0.0801033 -0.00705358 0.0594004 -0.0807932 -0.00480498 0.0610505 -0.0807932 -0.00299166 0.0657397 -0.0807932 -0.00196655 0.0631583 -0.0801033 -0.00139615 0.0566872 -0.0807932 -0.0165185 0.0532667 -0.0807932 -0.0254745 0.0565052 -0.0807932 -0.0336554 0.0544499 -0.0807932 -0.0323188 0.0525358 -0.0801033 -0.0304953 0.0526831 -0.0807932 -0.0278558 0.0527185 -0.0801033 -0.0252124 0.0579151 -0.0801033 -0.0348555 0.0592463 -0.080561 -0.0347211 0.0601926 -0.0798968 -0.035089 0.0602419 -0.0777033 -0.0356398 0.0464559 -0.0801033 -0.0312614 0.0455759 -0.0805235 -0.0318024 0.0557752 -0.0802966 0.00173399 0.0555256 -0.0805237 0.00234291 0.0554139 -0.0806033 0.00300692 0.0503115 -0.0801033 -0.0245799 0.0556403 -0.0801033 -0.006294 0.0551434 -0.0806033 -0.00623778 0.0602419 -0.0711033 -0.0356398 0.0604769 -0.0708533 -0.0357336 0.0610558 -0.0711033 -0.0354247 0.0671743 -0.0711033 -0.0378036 0.0669693 -0.0710986 -0.037729 0.0667612 -0.0710843 -0.0376634 0.0658699 -0.0709233 -0.0374896 0.0717502 -0.0815076 -0.00242063 0.0718551 -0.0814055 -0.00233723 0.0710174 -0.0816674 -0.00264483 0.071377 -0.0813046 -0.00271721 0.0719425 -0.0727342 -0.00319998 0.0720881 -0.0742269 -0.00228684 0.0712493 -0.0737719 -0.00306215 0.0729716 -0.0720453 -0.00340463 0.0730308 -0.0729994 -0.00252848 0.0704643 -0.0821033 -0.00209037 0.0711604 -0.0821033 -0.0022288 0.0704582 -0.081911 -0.00228531 0.0657397 -0.0813033 -0.00196655 0.0658582 -0.081911 -0.00137059 0.064283 -0.0821033 -0.00105736 0.0597682 -0.0821033 -0.00303603 0.0833447 -0.0718033 -0.00528025 0.0831581 -0.0726033 -0.00450232 0.0841156 -0.0718033 -0.00490662 0.0836206 -0.0726033 -0.00427814 0.083947 -0.0726033 -0.00388097 0.0846595 -0.0718033 -0.00424468 0.0848765 -0.0718033 -0.00341589 0.0585252 -0.0826452 -0.00711621 0.0587125 -0.0825444 -0.00597709 0.060333 -0.0813033 -0.00360253 0.0531865 -0.0826452 -0.0254362 0.0566019 -0.0826452 -0.0164936 0.0522893 -0.08228 -0.0279217 0.0521706 -0.0821901 -0.0284789 0.052043 -0.0821033 -0.0295454 0.0526803 -0.0815513 -0.0279687 0.052961 -0.0821507 -0.0262472 0.0529499 -0.0826178 -0.0259585 0.0565052 -0.0813033 -0.0336554 0.0541288 -0.0813033 -0.0319735 0.0531008 -0.0813033 -0.0302716 0.0616633 -0.0813046 -0.0360506 0.0615081 -0.0811019 -0.0356005 0.0618187 -0.0815076 -0.0365012 0.0642399 -0.0726033 -0.037521 0.063452 -0.0727446 -0.0372609 0.0624011 -0.0727326 -0.0359477 0.0615081 -0.0750033 -0.0356005 0.0619061 -0.0750033 -0.0367546 0.0617419 -0.0737693 -0.0356915 0.061951 -0.0745355 -0.0367692 0.0727333 -0.0726033 -0.042311 0.073687 -0.0718033 -0.0418976 0.0735839 -0.0718033 -0.0410471 0.0728287 -0.0726033 -0.0413113 -0.0712394 -0.0820308 0.00232098 -0.0711697 -0.0821033 0.00223319 -0.0704675 -0.081911 0.0022897 -0.0628411 -0.0813033 0.00211286 -0.0658676 -0.081911 0.00137498 -0.0642924 -0.0821033 0.00106175 -0.0597775 -0.0821033 0.00304042 -0.0708135 -0.0813033 0.00297802 -0.0710268 -0.0816674 0.00264921 -0.0717595 -0.0815076 0.00242502 -0.0585345 -0.0826452 0.0071206 -0.0588641 -0.0820582 0.00602758 -0.0589443 -0.0819728 0.00579359 -0.0589235 -0.0823956 0.00515328 -0.0592809 -0.0822021 0.00408643 -0.0603424 -0.0813033 0.00360693 -0.0713864 -0.0813046 0.0027216 -0.0719693 -0.0813033 0.00225825 -0.0719693 -0.0742033 0.00225825 -0.0710137 -0.0742033 0.00301782 -0.0710137 -0.0811019 0.00301782 -0.0531958 -0.0826452 0.0254406 -0.0553535 -0.0826452 0.0203225 -0.057605 -0.0826452 0.0125966 -0.0586227 -0.0822787 0.00713133 -0.0717174 -0.0725014 0.00315776 -0.0722971 -0.0732293 0.00235185 -0.0711975 -0.0732797 0.00305437 -0.0726762 -0.0728717 0.0024596 -0.0724894 -0.0719848 0.00331127 -0.0522987 -0.08228 0.0279261 -0.0526896 -0.0815513 0.0279731 -0.0521799 -0.0821901 0.0284833 -0.0527988 -0.0813077 0.029211 -0.0529703 -0.0821507 0.0262516 -0.0529592 -0.0826178 0.0259629 -0.053276 -0.0822787 0.0254789 -0.0826534 -0.0726033 0.00451676 -0.0733989 -0.0718033 0.00349213 -0.0541381 -0.0813033 0.0319779 -0.0520524 -0.0821033 0.0295498 -0.084125 -0.0718033 0.00491101 -0.0831674 -0.0726033 0.00450671 -0.0846689 -0.0718033 0.00424907 -0.0839563 -0.0726033 0.00388537 -0.0606656 -0.081911 0.0359257 -0.0613304 -0.0816674 0.0359229 -0.0617374 -0.0742033 0.0356905 -0.0617374 -0.080869 0.0356905 -0.0630153 -0.0721829 0.0361873 -0.0638003 -0.0720184 0.0364925 -0.0619906 -0.0742033 0.036632 -0.0620343 -0.0738276 0.036646 -0.06355 -0.0726033 0.0371365 -0.0730062 -0.0726033 0.0418591 -0.0726544 -0.0726033 0.0408103 -0.0724302 -0.0720184 0.0398479 0.00906001 -0.0816033 0.0311083 0.0165426 -0.0821033 0.0272748 0.027962 -0.0821033 0.0153473 0.0309807 -0.0821033 0.00758615 0.027268 -0.0821033 -0.0165451 0.0311015 -0.0816033 -0.00906249 0.0220559 -0.0821033 -0.02304 0.0276954 -0.0816033 -0.0168045 0.0153405 -0.0821033 -0.0279645 0.015581 -0.0816033 -0.0284029 0.00769816 -0.0816033 -0.0314688 -0.00892946 -0.0821033 -0.0306239 -0.000709617 -0.0816033 -0.0323901 0.0734248 -0.0680033 -0.0427133 0.0658872 -0.0680033 -0.0536147 0.057834 -0.0680033 -0.0622167 0.0575616 -0.0676033 -0.0619238 0.0528654 -0.0676033 -0.0659785 0.0478357 -0.0676033 -0.0697115 0.048062 -0.0680033 -0.0700414 0.0462227 -0.0680033 -0.0712686 0.0372462 -0.0680033 -0.0763449 0.0372958 -0.0676033 -0.0758752 0.0255008 -0.0676033 -0.0806091 0.0256214 -0.0680033 -0.0809904 0.00905733 -0.0680033 -0.0844631 -0.0115274 -0.0680033 -0.0841627 -0.00419074 -0.0680033 -0.0848446 -0.0846689 -0.0680033 0.00424907 -0.084125 -0.0680033 0.00491101 -0.0838775 -0.0676033 0.00459677 -0.0824974 -0.0680033 0.0053014 0.0731343 -0.0680033 -0.0403178 0.0732063 -0.0676033 -0.0411792 0.073687 -0.0680033 -0.0418976 -0.0769763 -0.0680033 0.00420352 0.0670293 -0.0676033 -0.0381764 -0.0770543 -0.0676033 0.0038112 -0.0738382 -0.0676033 0.0013589 -0.0734805 -0.0680033 0.00153797 -0.0729517 -0.0680033 -0.000655396 0.0671743 -0.0680033 -0.0378036 0.0627938 -0.0680033 -0.0381739 -0.0721769 -0.0676033 -0.0130895 -0.0685351 -0.0680033 -0.0250036 -0.0633011 -0.0680033 -0.0362644 -0.056233 -0.0680033 -0.0464744 -0.0475356 -0.0680033 -0.0553377 -0.0264453 -0.0676033 -0.0684165 -0.0263011 -0.0680033 -0.0680434 -0.0205261 -0.0676033 -0.0704186 -0.00205191 -0.0676033 -0.0733192 -0.00204074 -0.0680033 -0.0729194 0.022577 -0.0676033 -0.0697853 0.0224539 -0.0680033 -0.0694047 0.0443643 -0.0680033 -0.0579037 0.0538363 -0.0676033 -0.0498112 0.0611695 -0.0680033 -0.0397398 -0.070388 -0.0676033 0.0468518 -0.0658965 -0.0680033 0.0536191 -0.0344211 -0.0676033 0.0772305 -0.0372555 -0.0680033 0.0763493 -0.0462321 -0.0680033 0.071273 -0.0480713 -0.0680033 0.0700457 -0.0219901 -0.0676033 0.0816437 -0.0220942 -0.0680033 0.08203 -0.0134495 -0.0680033 0.0838815 -0.00906667 -0.0680033 0.0844675 0.00416169 -0.0676033 0.0844495 0.017246 -0.0676033 0.0827737 0.0299103 -0.0676033 0.0790831 0.0418466 -0.0676033 0.0734677 0.0464473 -0.0680033 0.0711269 0.0626924 -0.0680033 0.0573222 0.0659599 -0.0676033 0.0528924 0.0814346 -0.0676033 0.0227256 0.0843751 -0.0680033 0.00982818 0.0839778 -0.0676033 0.00978192 0.0723056 -0.0676033 0.0438192 0.0724286 -0.0680033 0.0443861 0.0758121 -0.0676033 0.0374256 0.076909 -0.0676033 0.0351161 0.0781649 -0.0680033 0.0332591 0.0822037 -0.0680033 0.0214098 0.0844769 -0.0676033 -0.00339979 0.0843032 -0.0676033 -0.00406283 0.0841156 -0.0680033 -0.00490662 0.0838681 -0.0676033 -0.00459238 -0.0724302 -0.0680033 0.0398479 -0.0735932 -0.0680033 0.0410515 -0.072856 -0.0676033 0.0406002 -0.0732156 -0.0676033 0.0411836 -0.0736964 -0.0680033 0.041902 0.077045 -0.0676033 -0.0038068 -0.0670386 -0.0676033 0.0381808 0.0765433 -0.0680033 -0.00409547 -0.0615142 -0.0676033 0.0399621 -0.0628948 -0.0676033 0.0385919 0.0204049 -0.0680033 0.070039 0.0090515 -0.0676033 0.072791 0.00900211 -0.0680033 0.0723941 -0.00263008 -0.0680033 0.0729049 -0.0142732 -0.0676033 0.071951 -0.0141954 -0.0680033 0.0715586 -0.0253992 -0.0680033 0.0683895 -0.0359561 -0.0680033 0.0634782 -0.0420734 -0.0676033 0.0600892 -0.0458471 -0.0676033 0.0572621 -0.0540767 -0.0680033 0.0489708 0.0667612 -0.0680033 -0.0376634 0.0729424 -0.0680033 0.000659788 0.0729424 -0.0706033 0.000659788 0.076967 -0.0680033 -0.00419912 0.0758951 -0.0709767 -0.0038569 -0.0749362 -0.0706033 0.00328805 -0.0746937 -0.0706033 0.00309254 -0.0749198 -0.0680033 0.00327554 -0.0757074 -0.0709233 0.00376766 -0.0765526 -0.0710843 0.00409986 -0.0667705 -0.0680033 0.0376678 -0.0660957 -0.0709767 0.0375208 -0.0646615 -0.0680033 0.0375188 -0.0626795 -0.0680033 0.0382548 -0.0628031 -0.0706033 0.0381783 0.0833447 -0.0680033 -0.00528025 0.0846595 -0.0680033 -0.00424468 0.0734248 -0.0718033 -0.0427133 0.0735839 -0.0680033 -0.0410471 0.0731343 -0.0718033 -0.0403178 0.0724208 -0.0680033 -0.0398435 -0.083354 -0.0718033 0.00528464 -0.083354 -0.0680033 0.00528464 -0.0848859 -0.0718033 0.00342028 -0.0736118 -0.0718503 0.0423168 -0.0737025 -0.0720184 0.0418189 -0.0736041 -0.0720184 0.0410835 -0.0731436 -0.0680033 0.0403222 -0.0731553 -0.0720184 0.0403344 -0.065749 -0.0813033 0.00197094 -0.0705378 -0.0777033 0.00292318 -0.0769763 -0.0711033 0.00420352 -0.0824974 -0.0718033 0.0053014 -0.0608392 -0.0788955 0.0353412 -0.0610652 -0.0777033 0.0354291 -0.061897 -0.0733608 0.0357525 -0.0565146 -0.0813033 0.0336597 -0.0581447 -0.0807932 0.0342935 -0.0592557 -0.080561 0.0347255 -0.0613272 -0.0813033 0.035531 -0.062347 -0.0726529 0.0359275 -0.0671836 -0.0711033 0.037808 -0.0586227 -0.0807932 0.00713133 -0.0596675 -0.0814493 0.0044092 -0.0610598 -0.0807932 0.00299605 -0.0610598 -0.0813033 0.00299605 -0.0632975 -0.0807932 0.00199414 -0.065749 -0.0807932 0.00197094 -0.0531101 -0.0813033 0.030276 -0.0526925 -0.0807932 0.0278602 -0.0531101 -0.0807932 0.030276 -0.0528331 -0.0813033 0.0293754 -0.053276 -0.0807932 0.0254789 0.0608298 -0.0788955 -0.0353368 0.0610558 -0.0777033 -0.0354247 0.0581353 -0.0807932 -0.0342892 0.0613179 -0.0813033 -0.0355266 0.06338 -0.0720442 -0.0363284 0.0645298 -0.0718033 -0.0367754 0.0724208 -0.0718033 -0.0398435 0.0710043 -0.0811019 -0.00301343 0.0708042 -0.0813033 -0.00297363 0.0674551 -0.0807932 -0.00230765 0.0702916 -0.078893 -0.0028717 0.0710043 -0.0750033 -0.00301343 0.0824881 -0.0680033 -0.00529701 0.0824881 -0.0718033 -0.00529701 0.0741842 -0.0718033 -0.00364575 0.0527895 -0.0813077 -0.0292067 0.0531008 -0.0807932 -0.0302716 0.0528238 -0.0813033 -0.029371 0.0586134 -0.0822787 -0.00712694 0.0588548 -0.0820582 -0.00602318 0.058935 -0.0819728 -0.0057892 0.0596581 -0.0814493 -0.0044048 0.0632881 -0.0807932 -0.00198975 0.0610505 -0.0813033 -0.00299166 0.0628318 -0.0813033 -0.00210847 -0.0460121 -0.0696033 -0.0633112 -0.0461458 -0.0694033 -0.0634599 -0.0455048 -0.0694033 -0.0643693 -0.0454172 -0.0694033 -0.0660183 -0.0456331 -0.0694033 -0.0665349 -0.0460885 -0.0694033 -0.0671247 -0.0473733 -0.0696033 -0.0679821 -0.0485728 -0.0696033 -0.0679111 -0.0474062 -0.0694033 -0.0677848 -0.0472231 -0.0694033 -0.0677472 -0.046377 -0.0694033 -0.0673622 -0.0460885 -0.0678033 -0.0671247 -0.0456331 -0.0678033 -0.0665349 -0.0454172 -0.0678033 -0.0660183 -0.0453218 -0.0678033 -0.0654667 -0.0453218 -0.0694033 -0.0654667 -0.0453891 -0.0694033 -0.0647245 -0.0455048 -0.0678033 -0.0643693 -0.0460116 -0.0678033 -0.06359 -0.0460116 -0.0694033 -0.06359 -0.0461458 -0.0678033 -0.0634599 -0.0485168 -0.0678033 -0.0677191 -0.0474062 -0.0678033 -0.0677848 -0.0472231 -0.0678033 -0.0677472 -0.046377 -0.0678033 -0.0673622 -0.0462617 -0.0676033 -0.0675257 -0.0454583 -0.0676033 -0.0666322 -0.0451221 -0.0676033 -0.0654785 -0.0453198 -0.0676033 -0.0642933 -0.0453891 -0.0678033 -0.0647245 -0.0656724 -0.0694033 -0.0430645 -0.0655382 -0.0694033 -0.0431946 -0.0648464 -0.0696033 -0.0438979 -0.0657883 -0.0696033 -0.0471303 -0.0656151 -0.0694033 -0.0467293 -0.0669328 -0.0694033 -0.0473894 -0.0668999 -0.0696033 -0.0475867 -0.0656724 -0.0678033 -0.0430645 -0.0655382 -0.0678033 -0.0431946 -0.0650314 -0.0694033 -0.0439738 -0.0649157 -0.0694033 -0.0443291 -0.0649157 -0.0678033 -0.0443291 -0.0648484 -0.0694033 -0.0450713 -0.0649438 -0.0694033 -0.0456229 -0.0649438 -0.0678033 -0.0456229 -0.0651597 -0.0694033 -0.0461395 -0.0651597 -0.0678033 -0.0461395 -0.0659036 -0.0694033 -0.0469668 -0.0667497 -0.0694033 -0.0473518 -0.0659036 -0.0678033 -0.0469668 -0.0667497 -0.0678033 -0.0473518 -0.0669328 -0.0678033 -0.0473894 -0.0680434 -0.0694033 -0.0473236 -0.0680434 -0.0678033 -0.0473236 -0.0668999 -0.0676033 -0.0475867 -0.0657883 -0.0676033 -0.0471303 -0.0656151 -0.0678033 -0.0467293 -0.0648484 -0.0678033 -0.0450713 -0.0648464 -0.0676033 -0.0438979 -0.0650314 -0.0678033 -0.0439738 -0.073661 -0.0694033 -0.0351271 -0.0748276 -0.0696033 -0.0352533 -0.0736281 -0.0696033 -0.0353244 -0.0725166 -0.0696033 -0.0348679 -0.0726318 -0.0694033 -0.0347045 -0.0718879 -0.0694033 -0.0338771 -0.0717596 -0.0694033 -0.0317115 -0.0733728 -0.0694033 -0.030261 -0.0733169 -0.0696033 -0.030069 -0.073661 -0.0678033 -0.0351271 -0.0717596 -0.0678033 -0.0317115 -0.0715766 -0.0694033 -0.032809 -0.0724007 -0.0678033 -0.0308022 -0.0724007 -0.0694033 -0.0308022 -0.0733728 -0.0678033 -0.030261 -0.072267 -0.0676033 -0.0306534 -0.071377 -0.0676033 -0.0328208 -0.0715766 -0.0678033 -0.032809 -0.0718879 -0.0678033 -0.0338771 -0.0717132 -0.0676033 -0.0339744 -0.0726318 -0.0678033 -0.0347045 -0.0725166 -0.0676033 -0.0348679 -0.0736281 -0.0676033 -0.0353244 -0.0800297 -0.0696033 -0.00264272 -0.0791135 -0.0694033 -0.0033759 -0.0789798 -0.0696033 -0.00322718 -0.0782875 -0.0696033 -0.00420929 -0.0784725 -0.0694033 -0.00428526 -0.0783849 -0.0694033 -0.00593433 -0.0792294 -0.0696033 -0.00744168 -0.0790562 -0.0694033 -0.00704071 -0.080341 -0.0696033 -0.00789812 -0.0801907 -0.0694033 -0.00766322 -0.0793446 -0.0694033 -0.00727822 -0.0803739 -0.0694033 -0.00770085 -0.0786007 -0.0694033 -0.00645088 -0.0782895 -0.0694033 -0.00538271 -0.0783568 -0.0678033 -0.00464055 -0.0783568 -0.0694033 -0.00464055 -0.0789793 -0.0694033 -0.00350601 -0.0789793 -0.0678033 -0.00350601 -0.0781625 -0.0676033 -0.004593 -0.0781929 -0.0676033 -0.00599029 -0.0783849 -0.0678033 -0.00593433 -0.0790562 -0.0678033 -0.00704071 -0.0789179 -0.0676033 -0.00718518 -0.0801907 -0.0678033 -0.00766322 -0.0815405 -0.0676033 -0.00782708 -0.0452153 -0.0693033 -0.0719179 -0.0544734 -0.0696033 -0.0647958 -0.0671667 -0.0693033 -0.0520148 -0.0671388 -0.0694534 -0.0518054 -0.0751183 -0.0693033 -0.0396771 -0.0750548 -0.0694534 -0.0394757 -0.0797666 -0.0694534 -0.0287911 -0.0849532 -0.0693033 0.000504865 -0.0848038 -0.0694534 0.000355515 -0.0839195 -0.0696033 -0.0111299 -0.0840484 -0.0694534 -0.0112974 -0.0843845 -0.0693033 -0.00982379 -0.0837735 -0.0696033 -0.0109402 -0.0833765 -0.0726033 -0.0114155 -0.0836106 -0.0723971 -0.011224 -0.0811409 -0.0721033 0.000253579 -0.078349 -0.0721033 -0.000303825 -0.0770397 -0.0721033 -0.00120727 -0.0757939 -0.0726033 -0.00190502 -0.0762098 -0.0721033 -0.00218251 -0.0756302 -0.0721033 -0.00331728 -0.0747977 -0.0726033 -0.00484673 -0.0803969 -0.0726033 -0.0112223 -0.075854 -0.0721033 -0.00767098 -0.075318 -0.0721033 -0.00583545 -0.0843602 -0.0723971 0.000339233 -0.0841528 -0.0726033 0.000559362 -0.0811733 -0.0726033 0.000752531 -0.0849532 -0.0718033 0.000504865 -0.0846544 -0.0696033 0.000206078 -0.0845673 -0.0721906 0.00011893 -0.0844851 -0.0721033 3.67687e-05 -0.0738236 -0.0718033 -0.0420367 -0.0736196 -0.0694534 -0.0420914 -0.0731842 -0.0696033 -0.0422081 -0.0727355 -0.0721033 -0.0419087 -0.0706739 -0.0726033 -0.0399323 -0.0681785 -0.0726033 -0.0389818 -0.0703964 -0.0721033 -0.0403482 -0.0626088 -0.0721033 -0.0477212 -0.0613656 -0.0726033 -0.045432 -0.061737 -0.0726033 -0.0427877 -0.0635627 -0.0721033 -0.0409295 -0.0658052 -0.0721033 -0.0396431 -0.0665269 -0.0725833 -0.051567 -0.0670794 -0.0715653 -0.0513586 -0.0671636 -0.07182 -0.0519916 -0.067111 -0.0696033 -0.0515959 -0.0452204 -0.07182 -0.071895 -0.045261 -0.0694534 -0.0717117 -0.0450401 -0.0721033 -0.0708364 -0.0453587 -0.0715653 -0.0712717 -0.0433793 -0.0721033 -0.0685674 -0.0447394 -0.0726033 -0.0712721 -0.0447682 -0.0725833 -0.0712776 -0.0522555 -0.0721033 -0.0620703 -0.0502384 -0.0726033 -0.059829 -0.0500367 -0.0721033 -0.0602865 -0.0442735 -0.0726033 -0.0604773 -0.0423275 -0.0726033 -0.0628979 -0.0418525 -0.0726033 -0.0659672 -0.0426101 -0.0721033 -0.0635487 -0.054871 -0.07182 -0.0648312 -0.0548943 -0.0718033 -0.0648332 -0.0546839 -0.0694534 -0.0648145 -0.0542349 -0.0696033 -0.0647746 -0.0788643 -0.0721033 -0.0287633 -0.0799369 -0.07182 -0.028712 -0.079575 -0.0696033 -0.0288801 -0.0793578 -0.0715653 -0.028981 -0.0764933 -0.0726033 -0.0271713 -0.0762915 -0.0721033 -0.0276288 -0.0738715 -0.0726033 -0.0266645 -0.0738883 -0.0721033 -0.0271642 -0.0725335 -0.0721033 -0.0273808 -0.0692587 -0.0726033 -0.0290792 -0.0696599 -0.0721033 -0.0293777 -0.069509 -0.0726033 -0.0365569 -0.0686595 -0.0721033 -0.033637 -0.0744258 -0.0721033 -0.0388281 -0.0749193 -0.0715653 -0.0390458 -0.0837735 -0.0721033 -0.0109402 -0.0844851 -0.0696033 3.67687e-05 -0.0811409 -0.0696033 0.000253579 -0.0792463 -0.0721033 4.54632e-05 -0.0833773 -0.0696033 -0.00447951 -0.081427 -0.0696033 -0.00261231 -0.0792463 -0.0696033 4.54632e-05 -0.0756302 -0.0696033 -0.00331728 -0.075318 -0.0696033 -0.00583545 -0.0780898 -0.0696033 -0.00539454 -0.0761694 -0.0696033 -0.0082258 -0.078426 -0.0696033 -0.00654816 -0.0804293 -0.0696033 -0.0107234 -0.0815405 -0.0696033 -0.00782708 -0.0666307 -0.0721033 -0.0510592 -0.0642916 -0.0696033 -0.0494987 -0.0642916 -0.0721033 -0.0494987 -0.0731842 -0.0715653 -0.0422081 -0.0681789 -0.0696033 -0.0394872 -0.068109 -0.0721033 -0.0394769 -0.0734154 -0.0696033 -0.0421461 -0.0703964 -0.0696033 -0.0403482 -0.0699362 -0.0696033 -0.0441681 -0.0692112 -0.0696033 -0.0429732 -0.0679859 -0.0696033 -0.0423009 -0.062235 -0.0696033 -0.0428867 -0.0655387 -0.0696033 -0.0429158 -0.0646487 -0.0696033 -0.0450831 -0.0625945 -0.0696033 -0.0476969 -0.0649849 -0.0696033 -0.0462367 -0.0670794 -0.0696033 -0.0513586 -0.071853 -0.0696033 -0.0376935 -0.0762915 -0.0696033 -0.0276288 -0.0744344 -0.0696033 -0.0271731 -0.0749913 -0.0696033 -0.0392741 -0.0760225 -0.0696033 -0.0345284 -0.0749193 -0.0696033 -0.0390458 -0.0793578 -0.0696033 -0.028981 -0.0717132 -0.0696033 -0.0339744 -0.071377 -0.0696033 -0.0328208 -0.0715746 -0.0696033 -0.0316355 -0.0686595 -0.0696033 -0.033637 -0.072267 -0.0696033 -0.0306534 -0.0433793 -0.0696033 -0.0685674 -0.0542349 -0.0715653 -0.0647746 -0.0539163 -0.0721033 -0.0643393 -0.0522555 -0.0696033 -0.0620703 -0.0506047 -0.0696033 -0.0605775 -0.0484973 -0.0721033 -0.0598611 -0.0472231 -0.0721033 -0.0598511 -0.0453068 -0.0696033 -0.0715054 -0.0453587 -0.0696033 -0.0712717 -0.0497677 -0.0696033 -0.0671861 -0.0496846 -0.0696033 -0.0633686 -0.0484973 -0.0696033 -0.0598611 -0.0484593 -0.0696033 -0.0626963 -0.0426101 -0.0696033 -0.0635487 -0.0453198 -0.0696033 -0.0642933 -0.0451221 -0.0696033 -0.0654785 -0.0423809 -0.0696033 -0.0661521 -0.0454583 -0.0696033 -0.0666322 -0.0462617 -0.0696033 -0.0675257 0.0071827 -0.0696033 -0.078911 0.00754504 -0.0694033 -0.0798286 0.00785501 -0.0696033 -0.0801363 0.00766075 -0.0694033 -0.0801839 0.00772805 -0.0694033 -0.080926 0.00782461 -0.0696033 -0.0815336 0.00763259 -0.0694033 -0.0814777 0.00582678 -0.0694033 -0.0832065 0.00447704 -0.0696033 -0.0833704 0.00741678 -0.0694033 -0.0819942 0.00453299 -0.0678033 -0.0831784 0.00667286 -0.0694033 -0.0828215 0.00667286 -0.0678033 -0.0828215 0.00696131 -0.0694033 -0.082584 0.00772805 -0.0678033 -0.080926 0.00703824 -0.0694033 -0.0790493 0.00690399 -0.0678033 -0.0789192 0.00593186 -0.0694033 -0.0783781 0.00598782 -0.0676033 -0.078186 0.00703772 -0.0676033 -0.0787705 0.00754504 -0.0678033 -0.0798286 0.0079277 -0.0676033 -0.0809379 0.00741678 -0.0678033 -0.0819942 0.0067881 -0.0676033 -0.082985 0.00564365 -0.0678033 -0.0832442 0.00447704 -0.0676033 -0.0833704 0.0319033 -0.0696033 -0.0766576 0.0333006 -0.0696033 -0.076688 0.0352509 -0.0696033 -0.0748208 0.0352813 -0.0696033 -0.0734235 0.0344645 -0.0694033 -0.0723365 0.033253 -0.0694033 -0.0764937 0.0343876 -0.0678033 -0.0758712 0.0343876 -0.0694033 -0.0758712 0.0350588 -0.0694033 -0.0747648 0.035087 -0.0694033 -0.073471 0.0333581 -0.0678033 -0.0716652 0.0333581 -0.0694033 -0.0716652 0.0344645 -0.0678033 -0.0723365 0.035087 -0.0678033 -0.073471 0.0350588 -0.0678033 -0.0747648 0.033253 -0.0678033 -0.0764937 0.0345259 -0.0676033 -0.0760157 0.0319593 -0.0678033 -0.0764656 0.0455629 -0.0696033 -0.0699597 0.0455154 -0.0694033 -0.0697655 0.0467882 -0.0696033 -0.0692874 0.0466499 -0.0678033 -0.069143 0.0466499 -0.0694033 -0.069143 0.0473212 -0.0694033 -0.0680366 0.0473493 -0.0678033 -0.0667428 0.0473493 -0.0694033 -0.0667428 0.0467268 -0.0694033 -0.0656083 0.0456204 -0.0678033 -0.064937 0.0456764 -0.0676033 -0.064745 0.0467268 -0.0678033 -0.0656083 0.0473212 -0.0678033 -0.0680366 0.0475436 -0.0676033 -0.0666952 0.0455154 -0.0678033 -0.0697655 0.0455629 -0.0676033 -0.0699597 0.066988 -0.0694033 -0.0459515 0.0672667 -0.0696033 -0.0459433 0.0671222 -0.0694033 -0.0460817 0.067629 -0.0694033 -0.0468609 0.067939 -0.0696033 -0.0471686 0.0677447 -0.0694033 -0.0472162 0.0679086 -0.0696033 -0.0485659 0.0677166 -0.0694033 -0.04851 0.0671836 -0.0696033 -0.0497608 0.064561 -0.0696033 -0.0504027 0.0657276 -0.0694033 -0.0502765 0.0659108 -0.0694033 -0.0502389 0.0667569 -0.0694033 -0.0498539 0.0657276 -0.0678033 -0.0502765 0.064617 -0.0694033 -0.0502107 0.0670453 -0.0694033 -0.0496164 0.0675008 -0.0678033 -0.0490265 0.0677166 -0.0678033 -0.04851 0.0675008 -0.0694033 -0.0490265 0.067812 -0.0694033 -0.0479584 0.067629 -0.0678033 -0.0468609 0.0671222 -0.0678033 -0.0460817 0.0660159 -0.0694033 -0.0454104 0.064617 -0.0678033 -0.0502107 0.0659108 -0.0678033 -0.0502389 0.0659583 -0.0676033 -0.0504331 0.0667569 -0.0678033 -0.0498539 0.0670453 -0.0678033 -0.0496164 0.0671836 -0.0676033 -0.0497608 0.067812 -0.0678033 -0.0479584 0.0677447 -0.0678033 -0.0472162 0.0660159 -0.0678033 -0.0454104 0.066988 -0.0678033 -0.0459515 0.0672667 -0.0676033 -0.0459433 0.00905733 -0.0693033 -0.0844631 -0.000357986 -0.0694534 -0.084797 0.0345746 -0.0693033 -0.0775915 0.0394732 -0.0694534 -0.0750479 0.0286997 -0.0693033 -0.0799513 0.0420343 -0.0693033 -0.0738167 0.0462227 -0.0693033 -0.0712686 0.0421436 -0.0696033 -0.0734086 0.0420889 -0.0694534 -0.0736127 0.0658872 -0.0693033 -0.0536147 0.0647933 -0.0696033 -0.0544665 0.064812 -0.0694534 -0.054677 0.0648308 -0.0718033 -0.0548874 0.0647721 -0.0715653 -0.0542281 0.0643368 -0.0721033 -0.0539095 0.0648287 -0.07182 -0.0548641 0.0641819 -0.0726033 -0.0544157 0.0620679 -0.0721033 -0.0522487 0.060284 -0.0721033 -0.0500298 0.0593515 -0.0726033 -0.0471623 0.0598486 -0.0721033 -0.0472163 0.0603825 -0.0721033 -0.0453801 0.0619987 -0.0721033 -0.0434239 0.0628954 -0.0726033 -0.0423207 0.0630972 -0.0721033 -0.0427782 0.0659647 -0.0726033 -0.0418457 0.0712696 -0.0726033 -0.0447325 0.068565 -0.0721033 -0.0433724 0.0708339 -0.0721033 -0.0450332 0.0718926 -0.07182 -0.0452135 0.0712692 -0.0715653 -0.0453518 0.0717092 -0.0694534 -0.0452542 0.0719154 -0.0693033 -0.0452084 0.0392717 -0.0696033 -0.0749844 0.0396747 -0.0718033 -0.0751114 0.0388256 -0.0721033 -0.0744189 0.0390433 -0.0715653 -0.0749125 0.0381486 -0.0726033 -0.0716444 0.0376911 -0.0721033 -0.0718461 0.0393533 -0.0726033 -0.0743764 0.0271688 -0.0726033 -0.0764864 0.0278124 -0.0721033 -0.0714646 0.0304394 -0.0721033 -0.069033 0.0317261 -0.0721033 -0.068645 0.0302377 -0.0726033 -0.0685755 0.033307 -0.0726033 -0.0681005 0.0362026 -0.0726033 -0.0692238 0.033253 -0.0721033 -0.0685976 0.0289785 -0.0715653 -0.079351 0.0287609 -0.0721033 -0.0788574 0.0287886 -0.0694534 -0.0797598 0.0286997 -0.0718033 -0.0799513 -0.000507336 -0.0718033 -0.0849463 -0.000208548 -0.0696033 -0.0846476 -3.92395e-05 -0.0696033 -0.0844783 -3.92395e-05 -0.0715653 -0.0844783 -0.000540506 -0.0725833 -0.0841661 -0.00025605 -0.0721033 -0.081134 0.000133094 -0.0721033 -0.0787174 0.00119584 -0.0726033 -0.0763391 0.00153222 -0.0721033 -0.076709 0.00366422 -0.0721033 -0.0755065 0.00352166 -0.0726033 -0.0750273 0.00416016 -0.0721033 -0.0753838 0.0112199 -0.0726033 -0.08039 0.010023 -0.0721033 -0.0780763 0.00610683 -0.0721033 -0.0753482 0.0109028 -0.0721033 -0.0832283 0.0109377 -0.0715653 -0.0837666 0.0111275 -0.0696033 -0.0839126 0.0112949 -0.0694534 -0.0840415 0.0519891 -0.07182 -0.0671567 0.0515645 -0.0725833 -0.06652 0.0510568 -0.0721033 -0.0666238 0.0499122 -0.0726033 -0.0640073 0.0513561 -0.0696033 -0.0670725 0.0515935 -0.0696033 -0.0671041 0.0518029 -0.0694534 -0.067132 0.0520123 -0.0693033 -0.0671598 0.0399298 -0.0726033 -0.070667 0.0403457 -0.0721033 -0.0703895 0.0414051 -0.0721033 -0.0631076 0.0427852 -0.0726033 -0.0617301 0.0477188 -0.0721033 -0.0626019 0.0479731 -0.0726033 -0.0621714 0.0415869 -0.0726033 -0.0731508 0.0422056 -0.0715653 -0.0731773 0.0390433 -0.0696033 -0.0749125 0.0376911 -0.0696033 -0.0718461 0.0276263 -0.0696033 -0.0762846 0.0276263 -0.0721033 -0.0762846 0.0271628 -0.0696033 -0.0738532 0.0271909 -0.0721033 -0.0734711 0.0278124 -0.0696033 -0.0714646 0.0282206 -0.0721033 -0.0708168 0.0294437 -0.0696033 -0.0696029 0.0294437 -0.0721033 -0.0696029 0.0317261 -0.0696033 -0.068645 0.0341974 -0.0721033 -0.068785 0.0288777 -0.0696033 -0.0795681 0.0345259 -0.0696033 -0.0760157 0.0289785 -0.0696033 -0.079351 0.0301611 -0.0696033 -0.075091 0.0341974 -0.0696033 -0.068785 0.0362833 -0.0696033 -0.0699287 0.034609 -0.0696033 -0.0721982 0.0513561 -0.0715653 -0.0670725 0.0494962 -0.0696033 -0.0642848 0.0494962 -0.0721033 -0.0642848 0.0419063 -0.0721033 -0.0727286 0.0403457 -0.0696033 -0.0703895 0.0394484 -0.0696033 -0.0678851 0.0394745 -0.0721033 -0.0681021 0.0396819 -0.0721033 -0.0656632 0.0398314 -0.0721033 -0.0652525 0.0398314 -0.0696033 -0.0652525 0.040927 -0.0721033 -0.0635558 0.0429632 -0.0721033 -0.0621974 0.0414051 -0.0696033 -0.0631076 0.0438015 -0.0721033 -0.0619523 0.0453872 -0.0721033 -0.0618569 0.0464598 -0.0721033 -0.0620568 0.0422056 -0.0696033 -0.0731773 0.0441656 -0.0696033 -0.0699293 0.0438015 -0.0696033 -0.0619523 0.0433653 -0.0696033 -0.0651304 0.0444769 -0.0696033 -0.0646739 0.0464598 -0.0696033 -0.0620568 0.0481746 -0.0696033 -0.0629028 0.0468713 -0.0696033 -0.06547 0.0475436 -0.0696033 -0.0666952 0.0475132 -0.0696033 -0.0680925 -7.41379e-05 -0.0721033 -0.08394 0.00179125 -0.0696033 -0.0764877 0.00416016 -0.0696033 -0.0753838 0.00587433 -0.0696033 -0.0834008 0.00709962 -0.0696033 -0.0827285 0.0109377 -0.0696033 -0.0837666 0.0101305 -0.0696033 -0.0782764 0.00873787 -0.0696033 -0.0765401 0.00598782 -0.0696033 -0.078186 0.00478831 -0.0696033 -0.078115 0.00367676 -0.0696033 -0.0785714 0.000199362 -0.0696033 -0.0785605 -0.00025605 -0.0696033 -0.081134 0.0712692 -0.0696033 -0.0453518 0.068565 -0.0696033 -0.0433724 0.0620679 -0.0696033 -0.0522487 0.0647721 -0.0696033 -0.0542281 0.0715029 -0.0696033 -0.0453 0.0659583 -0.0696033 -0.0504331 0.0633661 -0.0696033 -0.0496777 0.0634492 -0.0696033 -0.0458603 0.064321 -0.0696033 -0.0424014 0.0619987 -0.0696033 -0.0434239 0.0627242 -0.0696033 -0.0470552 0.0626938 -0.0696033 -0.0484524 0.0604213 -0.0696033 -0.050318 0.0598166 -0.0721033 -0.0478537 0.0598166 -0.0696033 -0.0478537 0.0603825 -0.0696033 -0.0453801 0.0608783 -0.0721033 -0.044562 0.064321 -0.0721033 -0.0424014 0.0659107 -0.0721033 -0.0423427 0.0668552 -0.0721033 -0.0425302 -0.00599715 -0.0696033 0.0781904 -0.00479764 -0.0696033 0.0781194 -0.00483054 -0.0694033 0.0783167 -0.00305741 -0.0694033 0.0795666 -0.00274614 -0.0694033 0.0806348 -0.00288267 -0.0696033 0.0794693 -0.00254649 -0.0696033 0.080623 -0.00292915 -0.0694033 0.0817323 -0.0035702 -0.0694033 0.0826416 -0.00343648 -0.0696033 0.0827903 -0.00454233 -0.0694033 0.0831828 -0.00380133 -0.0694033 0.0787393 -0.00274614 -0.0678033 0.0806348 -0.0035702 -0.0678033 0.0826416 -0.00448637 -0.0676033 0.0833748 -0.00343648 -0.0676033 0.0827903 -0.00292915 -0.0678033 0.0817323 -0.00274414 -0.0676033 0.0818082 -0.00305741 -0.0678033 0.0795666 -0.00380133 -0.0678033 0.0787393 -0.00368609 -0.0676033 0.0785758 -0.00483054 -0.0678033 0.0783167 -0.00479764 -0.0676033 0.0781194 -0.00599715 -0.0676033 0.0781904 -0.0333675 -0.0694033 0.0716696 -0.0334234 -0.0696033 0.0714776 -0.0312276 -0.0694033 0.0720265 -0.0304837 -0.0694033 0.0728538 -0.0303089 -0.0696033 0.0727565 -0.0299727 -0.0696033 0.0739101 -0.0308627 -0.0696033 0.0760775 -0.0319126 -0.0696033 0.076662 -0.0322568 -0.0694033 0.0716038 -0.0304837 -0.0678033 0.0728538 -0.0301724 -0.0694033 0.073922 -0.0303554 -0.0694033 0.0750194 -0.0309965 -0.0678033 0.0759288 -0.0309965 -0.0694033 0.0759288 -0.0319686 -0.0678033 0.07647 -0.0301704 -0.0676033 0.0750954 -0.0303554 -0.0678033 0.0750194 -0.0301724 -0.0678033 0.073922 -0.0312276 -0.0678033 0.0720265 -0.0311124 -0.0676033 0.071863 -0.0322568 -0.0678033 0.0716038 -0.0333675 -0.0678033 0.0716696 -0.0334234 -0.0676033 0.0714776 -0.044336 -0.0694033 0.0649132 -0.0456857 -0.0696033 0.0647494 -0.0442884 -0.0696033 0.064719 -0.0425302 -0.0694033 0.0666421 -0.042502 -0.0694033 0.0679359 -0.0431245 -0.0694033 0.0690704 -0.0429801 -0.0696033 0.0692087 -0.0432014 -0.0694033 0.0655357 -0.042502 -0.0678033 0.0679359 -0.0431245 -0.0678033 0.0690704 -0.0441749 -0.0676033 0.0699337 -0.0429801 -0.0676033 0.0692087 -0.0425302 -0.0678033 0.0666421 -0.0423382 -0.0676033 0.0665862 -0.0432014 -0.0678033 0.0655357 -0.0430631 -0.0676033 0.0653913 -0.044336 -0.0678033 0.0649132 -0.0442884 -0.0676033 0.064719 -0.0660811 -0.0696033 0.0452228 -0.0638853 -0.0694033 0.0457716 -0.0631414 -0.0694033 0.0465989 -0.0628301 -0.0694033 0.0476671 -0.0630131 -0.0694033 0.0487646 -0.0636542 -0.0694033 0.0496739 -0.0649145 -0.0694033 0.045349 -0.0630131 -0.0678033 0.0487646 -0.0636542 -0.0678033 0.0496739 -0.0646263 -0.0694033 0.0502151 -0.0635205 -0.0676033 0.0498227 -0.0628301 -0.0678033 0.0476671 -0.0631414 -0.0678033 0.0465989 -0.0638853 -0.0678033 0.0457716 -0.0649145 -0.0678033 0.045349 -0.0648816 -0.0676033 0.0451517 0.000498002 -0.0693033 0.0849507 -0.0113043 -0.0694534 0.0840459 0.000199215 -0.0696033 0.0846519 -0.0372555 -0.0693033 0.0763493 -0.028887 -0.0696033 0.0795725 -0.028798 -0.0694534 0.0797642 -0.042153 -0.0696033 0.073413 -0.0420983 -0.0694534 0.0736171 -0.0480713 -0.0693033 0.0700457 -0.0663592 -0.0693033 0.0530453 -0.0648214 -0.0694534 0.0546814 -0.0648026 -0.0696033 0.0544709 -0.0648401 -0.0718033 0.0548918 -0.0648159 -0.0719971 0.0546201 -0.0647917 -0.0721906 0.0543482 -0.0647814 -0.0721033 0.0542325 -0.0641912 -0.0726033 0.0544201 -0.0688696 -0.0726033 0.0429733 -0.0685743 -0.0721033 0.0433768 -0.0712785 -0.0721033 0.0453562 -0.0717186 -0.0694534 0.0452586 -0.0719248 -0.0693033 0.0452128 -0.0716585 -0.0719971 0.0452719 -0.0719248 -0.0718033 0.0452128 -0.0715123 -0.0696033 0.0453044 -0.0396617 -0.07182 0.0751088 -0.039281 -0.0696033 0.0749888 -0.0394825 -0.0694534 0.0750523 -0.0393627 -0.0726033 0.0743807 -0.038835 -0.0721033 0.0744233 -0.0393531 -0.0725833 0.0744084 -0.0362926 -0.0721033 0.0699331 -0.0284099 -0.0725833 0.0792343 -0.0283829 -0.0726033 0.0792228 -0.0271781 -0.0726033 0.0764908 -0.0287702 -0.0721033 0.0788618 -0.0287189 -0.07182 0.0799345 -0.0289879 -0.0715653 0.0793554 0.000348652 -0.0694534 0.0848014 6.48043e-05 -0.0721033 0.0839444 2.99059e-05 -0.0715653 0.0844827 -0.0087472 -0.0721033 0.0765445 -0.0112292 -0.0726033 0.0803944 -0.0107302 -0.0721033 0.0804268 -0.0114038 -0.0725833 0.0833967 -0.0111368 -0.0696033 0.083917 -0.0114531 -0.07182 0.0841604 -0.0519984 -0.07182 0.0671611 -0.0510661 -0.0721033 0.0666282 -0.0513655 -0.0696033 0.0670769 -0.0516028 -0.0696033 0.0671085 -0.0518123 -0.0694534 0.0671364 -0.048184 -0.0721033 0.0629072 -0.046609 -0.0726033 0.0615811 -0.0419156 -0.0721033 0.072733 -0.0399392 -0.0726033 0.0706714 -0.0420436 -0.0718033 0.0738211 -0.042215 -0.0715653 0.0731817 -0.0620772 -0.0696033 0.0522531 -0.0620772 -0.0721033 0.0522531 -0.0604306 -0.0721033 0.0503224 -0.0598259 -0.0721033 0.0478581 -0.059858 -0.0696033 0.0472207 -0.0608876 -0.0721033 0.0445664 -0.062008 -0.0721033 0.0434283 -0.0631065 -0.0696033 0.0427825 -0.0631065 -0.0721033 0.0427825 -0.0643303 -0.0721033 0.0424058 -0.0668645 -0.0721033 0.0425346 -0.06592 -0.0696033 0.0423471 -0.0648816 -0.0696033 0.0451517 -0.0685743 -0.0696033 0.0433768 -0.0647814 -0.0696033 0.0542325 -0.0712785 -0.0696033 0.0453562 -0.0659677 -0.0696033 0.0504375 -0.0645704 -0.0696033 0.0504071 -0.0635205 -0.0696033 0.0498227 -0.0628281 -0.0696033 0.0488405 -0.0602934 -0.0696033 0.0500342 -0.0626305 -0.0696033 0.0476553 -0.0608876 -0.0696033 0.0445664 -0.0629667 -0.0696033 0.0465017 -0.0637701 -0.0696033 0.0456082 -0.0390526 -0.0715653 0.0749169 -0.0377004 -0.0721033 0.0718505 -0.0289879 -0.0696033 0.0793554 -0.0276356 -0.0721033 0.076289 -0.0272002 -0.0721033 0.0734755 -0.0272002 -0.0696033 0.0734755 -0.0282299 -0.0696033 0.0708212 -0.029453 -0.0721033 0.0696073 -0.0304488 -0.0721033 0.0690374 -0.0317355 -0.0721033 0.0686494 -0.0332623 -0.0721033 0.068602 -0.0332623 -0.0696033 0.068602 -0.0342068 -0.0721033 0.0687894 -0.0359166 -0.0721033 0.0696317 -0.0276356 -0.0696033 0.076289 -0.0301704 -0.0696033 0.0750954 -0.0304488 -0.0696033 0.0690374 -0.0311124 -0.0696033 0.071863 -0.0322239 -0.0696033 0.0714066 -0.0359166 -0.0696033 0.0696317 -0.0377004 -0.0696033 0.0718505 -0.0390526 -0.0696033 0.0749169 -0.0352906 -0.0696033 0.0734279 -0.0513655 -0.0715653 0.0670769 -0.042215 -0.0696033 0.0731817 -0.0403551 -0.0721033 0.0703939 -0.0394838 -0.0696033 0.0681065 -0.0394577 -0.0721033 0.0678895 -0.0396913 -0.0696033 0.0656676 -0.0398407 -0.0721033 0.0652569 -0.0409364 -0.0696033 0.0635602 -0.0409364 -0.0721033 0.0635602 -0.0438108 -0.0721033 0.0619567 -0.0429726 -0.0696033 0.0622018 -0.0464691 -0.0721033 0.0620612 -0.0453965 -0.0696033 0.0618613 -0.0477281 -0.0696033 0.0626063 -0.0495056 -0.0696033 0.0642891 -0.0495056 -0.0721033 0.0642891 -0.046486 -0.0696033 0.0695483 -0.0453745 -0.0696033 0.0700048 -0.0441749 -0.0696033 0.0699337 -0.0403551 -0.0696033 0.0703939 -0.0423077 -0.0696033 0.0679834 -0.0423382 -0.0696033 0.0665862 -0.0430631 -0.0696033 0.0653913 -0.0467356 -0.0696033 0.0653338 -0.0476256 -0.0696033 0.0675012 -0.010947 -0.0715653 0.083771 -0.0109122 -0.0721033 0.0832327 -0.000142428 -0.0696033 0.0787218 -0.00154156 -0.0696033 0.0767134 -0.00416949 -0.0721033 0.0753881 -0.00611616 -0.0721033 0.0753526 -0.00678052 -0.0721033 0.0755022 -0.0101398 -0.0721033 0.0782808 -0.00786435 -0.0696033 0.0801407 -0.0107302 -0.0696033 0.0804268 -0.00448637 -0.0696033 0.0833748 -0.00710896 -0.0696033 0.0827329 -0.010947 -0.0696033 0.083771 -0.00783394 -0.0696033 0.081538 -0.0100323 -0.0696033 0.0780807 -0.00719204 -0.0696033 0.0789154 -0.00838558 -0.0696033 0.0762697 -0.00611616 -0.0696033 0.0753526 -0.00368609 -0.0696033 0.0785758 -0.00367356 -0.0696033 0.0755109 0.000246716 -0.0696033 0.0811384 -0.00274414 -0.0696033 0.0818082 2.99059e-05 -0.0696033 0.0844827 0.0492485 -0.0694033 0.06328 0.0499924 -0.0694033 0.0641073 0.0493637 -0.0696033 0.0631165 0.0501672 -0.0696033 0.06401 0.0503037 -0.0694033 0.0651755 0.0501207 -0.0694033 0.0662729 0.0503057 -0.0696033 0.0663489 0.0494796 -0.0694033 0.0671823 0.0485075 -0.0694033 0.0677234 0.0482193 -0.0678033 0.0628573 0.0482193 -0.0694033 0.0628573 0.0501207 -0.0678033 0.0662729 0.0494796 -0.0678033 0.0671823 0.0505033 -0.0676033 0.0651636 0.0503037 -0.0678033 0.0651755 0.0499924 -0.0678033 0.0641073 0.0492485 -0.0678033 0.06328 0.0482522 -0.0676033 0.0626601 0.0665793 -0.0696033 0.0423357 0.067929 -0.0694033 0.0424995 0.0690636 -0.0694033 0.043122 0.0692019 -0.0696033 0.0429776 0.069763 -0.0694033 0.0455222 0.0699573 -0.0696033 0.0455698 0.069285 -0.0696033 0.0467951 0.0697348 -0.0678033 0.0442284 0.0697348 -0.0694033 0.0442284 0.0691405 -0.0694033 0.0466567 0.0691405 -0.0678033 0.0466567 0.0680341 -0.0694033 0.047328 0.0680901 -0.0676033 0.04752 0.069763 -0.0678033 0.0455222 0.069285 -0.0676033 0.0467951 0.0690636 -0.0678033 0.043122 0.067929 -0.0678033 0.0424995 0.0666352 -0.0678033 0.0425277 0.0744741 -0.0694033 0.0301996 0.0733075 -0.0696033 0.0300734 0.074507 -0.0696033 0.0300023 0.0755034 -0.0694033 0.0306222 0.0762473 -0.0694033 0.0314496 0.0767582 -0.0696033 0.0325059 0.0765605 -0.0696033 0.0336912 0.0763755 -0.0694033 0.0336152 0.0757345 -0.0694033 0.0345245 0.0733635 -0.0678033 0.0302654 0.0744741 -0.0678033 0.0301996 0.0755034 -0.0678033 0.0306222 0.0765586 -0.0678033 0.0325177 0.0765586 -0.0694033 0.0325177 0.0757345 -0.0678033 0.0345245 0.0747624 -0.0694033 0.0350657 0.0747624 -0.0678033 0.0350657 0.0748183 -0.0676033 0.0352577 0.0758682 -0.0676033 0.0346733 0.0763755 -0.0678033 0.0336152 0.0765605 -0.0676033 0.0336912 0.0762473 -0.0678033 0.0314496 0.076422 -0.0676033 0.0313523 0.0756186 -0.0676033 0.0304588 0.074507 -0.0676033 0.0300023 0.0800204 -0.0696033 0.00264711 0.0825046 -0.0694033 0.00343348 0.0833983 -0.0696033 0.00588119 0.0825816 -0.0694033 0.00696818 0.0800763 -0.0694033 0.00283913 0.0813701 -0.0678033 0.00281097 0.0813701 -0.0694033 0.00281097 0.0825046 -0.0678033 0.00343348 0.0831759 -0.0678033 0.00453986 0.0831759 -0.0694033 0.00453986 0.0832041 -0.0694033 0.00583364 0.0825816 -0.0678033 0.00696818 0.0832041 -0.0678033 0.00583364 0.0833983 -0.0676033 0.00588119 0.0814176 -0.0676033 0.0026167 0.0800204 -0.0676033 0.00264711 0.0546746 -0.0694534 0.0648189 0.0464473 -0.0693033 0.0711269 0.0452517 -0.0694534 0.0717161 0.0671016 -0.0696033 0.0516003 0.0736102 -0.0694534 0.0420958 0.0781649 -0.0693033 0.0332591 0.0751089 -0.0693033 0.0396815 0.0797573 -0.0694534 0.0287955 0.0841678 -0.0693033 0.0114692 0.084039 -0.0694534 0.0113018 0.0847945 -0.0694534 -0.000351123 0.0849438 -0.0693033 -0.000500473 0.0841536 -0.07182 0.0114506 0.0839102 -0.0696033 0.0111343 0.0832258 -0.0721033 0.0109097 0.0837641 -0.0715653 0.0109446 0.077741 -0.0726033 0.0104153 0.0761601 -0.0721033 0.00823019 0.0753086 -0.0721033 0.00583984 0.0757405 -0.0726033 0.00850209 0.0766898 -0.0726033 0.00084551 0.0839375 -0.0721033 -6.72751e-05 0.0846451 -0.0696033 -0.000201686 0.0738142 -0.0693033 0.0420411 0.0738142 -0.0718033 0.0420411 0.0737916 -0.07182 0.0420472 0.0731748 -0.0715653 0.0422125 0.0703871 -0.0721033 0.0403526 0.0706646 -0.0726033 0.0399367 0.0622257 -0.0721033 0.0428911 0.0633001 -0.0726033 0.0404869 0.0642823 -0.0721033 0.0495031 0.0671543 -0.07182 0.0519959 0.0665175 -0.0725833 0.0515714 0.0670701 -0.0715653 0.051363 0.0670701 -0.0696033 0.051363 0.0671574 -0.0718033 0.0520192 0.0671295 -0.0694534 0.0518098 0.0671574 -0.0693033 0.0520192 0.045211 -0.07182 0.0718994 0.0452975 -0.0696033 0.0715098 0.045206 -0.0718033 0.0719223 0.0453493 -0.0715653 0.0712761 0.0447588 -0.0725833 0.071282 0.0423716 -0.0721033 0.0661565 0.0429665 -0.0726033 0.0688672 0.0461294 -0.0726033 0.0595629 0.0462693 -0.0721033 0.0600429 0.0544098 -0.0725833 0.0642179 0.0522462 -0.0721033 0.0620747 0.0542256 -0.0715653 0.064779 0.053907 -0.0721033 0.0643437 0.0548616 -0.07182 0.0648356 0.0799276 -0.07182 0.0287164 0.0792275 -0.0725833 0.0284074 0.079216 -0.0726033 0.0283802 0.0762822 -0.0721033 0.0276332 0.0799488 -0.0693033 0.0287065 0.0795656 -0.0696033 0.0288845 0.0715121 -0.0721033 0.0277928 0.0696505 -0.0721033 0.0293821 0.0683492 -0.0726033 0.0308343 0.0716419 -0.0726033 0.0381554 0.0686502 -0.0721033 0.0336414 0.0743739 -0.0726033 0.0393602 0.0718437 -0.0721033 0.0376979 0.0744164 -0.0721033 0.0388325 0.07491 -0.0715653 0.0390502 0.07491 -0.0696033 0.0390502 0.0751019 -0.07182 0.0396592 0.074982 -0.0696033 0.0392785 0.0751089 -0.0718033 0.0396815 0.0750455 -0.0694534 0.0394801 0.0666213 -0.0721033 0.0510636 0.0727261 -0.0721033 0.0419131 0.0703871 -0.0696033 0.0403526 0.0680997 -0.0696033 0.0394813 0.0681696 -0.0721033 0.0394916 0.0657959 -0.0721033 0.0396475 0.0636363 -0.0721033 0.040857 0.0621949 -0.0696033 0.0429701 0.06185 -0.0721033 0.0453377 0.0618545 -0.0696033 0.045394 0.0625851 -0.0721033 0.0477013 0.0647425 -0.0696033 0.0456832 0.0642823 -0.0696033 0.0495031 0.0625994 -0.0696033 0.0477256 0.0699269 -0.0696033 0.0441725 0.0731748 -0.0696033 0.0422125 0.0679766 -0.0696033 0.0423053 0.0680901 -0.0696033 0.04752 0.0734061 -0.0696033 0.0421505 0.0653844 -0.0696033 0.0430607 0.0635534 -0.0696033 0.0409339 0.0656607 -0.0696033 0.0396888 0.0793485 -0.0715653 0.0289854 0.0788549 -0.0721033 0.0287677 0.0762822 -0.0696033 0.0276332 0.0738789 -0.0696033 0.0271686 0.0744251 -0.0721033 0.0271775 0.0725242 -0.0721033 0.0273852 0.0715121 -0.0696033 0.0277928 0.0702259 -0.0721033 0.0287251 0.0688254 -0.0721033 0.0309869 0.0686629 -0.0721033 0.0316218 0.0697414 -0.0721033 0.0360677 0.0718437 -0.0696033 0.0376979 0.0748183 -0.0696033 0.0352577 0.0758682 -0.0696033 0.0346733 0.076422 -0.0696033 0.0313523 0.0793485 -0.0696033 0.0289854 0.0756186 -0.0696033 0.0304588 0.0721126 -0.0696033 0.0307984 0.0696505 -0.0696033 0.0293821 0.0686629 -0.0696033 0.0316218 0.0687448 -0.0696033 0.0340681 0.06988 -0.0696033 0.0362367 0.0453493 -0.0696033 0.0712761 0.0450307 -0.0721033 0.0708408 0.0433699 -0.0721033 0.0685718 0.0542256 -0.0696033 0.064779 0.0522462 -0.0696033 0.0620747 0.0505953 -0.0721033 0.0605819 0.0503972 -0.0696033 0.0604708 0.048488 -0.0721033 0.0598655 0.0456285 -0.0696033 0.0602736 0.0456285 -0.0721033 0.0602736 0.0440057 -0.0721033 0.0613493 0.0426007 -0.0721033 0.0635531 0.0485635 -0.0696033 0.0679155 0.0544641 -0.0696033 0.0648002 0.0496134 -0.0696033 0.067331 0.0433699 -0.0696033 0.0685718 0.0424 -0.0696033 0.0663245 0.0425011 -0.0696033 0.0638789 0.0436534 -0.0696033 0.0617193 0.0470527 -0.0696033 0.0627311 0.0482522 -0.0696033 0.0626601 0.0480354 -0.0696033 0.059828 0.0505033 -0.0696033 0.0651636 0.0837641 -0.0696033 0.0109446 0.0844758 -0.0715653 -3.23767e-05 0.0844758 -0.0696033 -3.23767e-05 0.0811316 -0.0696033 -0.000249187 0.082726 -0.0696033 0.00710649 0.0833679 -0.0696033 0.0044839 0.0826429 -0.0696033 0.00328902 0.0814176 -0.0696033 0.0026167 0.0789705 -0.0696033 0.00323157 0.0755041 -0.0696033 0.00367109 0.0782781 -0.0696033 0.00421368 0.0762628 -0.0696033 0.00838311 0.0784167 -0.0696033 0.00655256 0.0780738 -0.0696033 0.0100299 0.0804199 -0.0696033 0.0107278 0.0811316 -0.0721033 -0.000249187 0.078715 -0.0696033 0.000139957 0.0767065 -0.0696033 0.00153909 0.0770303 -0.0721033 0.00121166 0.0756209 -0.0721033 0.00332167 0.0753457 -0.0696033 0.00611369 0.0779939 -0.0721033 0.00998393 0.0804199 -0.0721033 0.0107278 0.0534545 -0.0821033 -0.0649851 0.0539627 -0.0813033 -0.0656029 0.0584196 -0.0821033 -0.0605604 0.058975 -0.0813033 -0.0611362 0.058975 -0.0750033 -0.0611362 0.0552096 -0.0821033 -0.0495693 0.0539627 -0.0742033 -0.0656029 0.0527817 -0.0813033 -0.0654179 0.0615753 -0.0718033 -0.0585163 0.0601587 -0.0728802 -0.0590924 0.0594187 -0.0738357 -0.0600462 0.0597283 -0.0727573 -0.0604004 0.0591824 -0.0737564 -0.0609354 0.0592391 -0.0744376 -0.0602717 0.0591875 -0.0750033 -0.0603361 0.0559776 -0.0813033 -0.049345 0.0441743 -0.0821033 -0.0558338 0.0451387 -0.0821033 -0.055355 0.0467771 -0.0813033 -0.0563691 0.0472168 -0.0821033 -0.0557008 0.046083 -0.0813033 -0.0560972 0.0462143 -0.0821033 -0.055308 0.0535623 -0.0727255 -0.0659302 0.0538597 -0.0734208 -0.0656875 0.0527817 -0.0742033 -0.0654179 0.0823351 -0.0750033 0.0190965 0.0826226 -0.0740701 0.0197312 0.0828894 -0.0725278 0.0185783 0.0824307 -0.0732402 0.0181542 0.0825117 -0.0727639 0.017208 0.0831043 -0.0720181 0.017592 0.0737232 -0.0813033 0.0115504 0.0721064 -0.0813033 0.0092659 0.0689821 -0.0821033 0.0217211 0.0672535 -0.0821033 0.0233641 0.0683943 -0.0813033 0.0229884 0.0684695 -0.0813033 0.0229126 0.0807575 -0.0742033 0.0263455 0.079662 -0.0742033 0.026824 0.080475 -0.0723438 0.0271965 0.0795587 -0.0731547 0.0272074 0.0802405 -0.0719422 0.0278808 0.0793021 -0.0726302 0.0280983 0.0825856 -0.0750033 0.0198855 0.0818079 -0.0821033 0.0196982 0.079662 -0.0813033 0.026824 0.0707982 -0.0821033 0.0218561 0.079997 -0.0821033 0.0260975 0.0823351 -0.0813033 0.0190965 0.0807575 -0.0813033 0.0263455 0.0823395 -0.0746024 0.0190556 0.0823743 -0.0738361 0.018728 0.0741865 -0.0733063 0.0110217 0.0753049 -0.0726033 0.00974536 0.0825862 -0.0726033 0.0161256 0.0825081 -0.0727786 0.0172543 0.0717018 -0.0750033 0.00649655 0.0726801 -0.0740849 0.0100157 0.0737232 -0.0750033 0.0115504 0.0738436 -0.0740849 0.011413 0.0746996 -0.072786 0.0104361 0.0745848 -0.0726033 0.00888061 0.0721064 -0.0750033 0.0092659 0.0720048 -0.0740849 0.00832735 0.0725121 -0.0733063 0.00821202 0.073127 -0.0733063 0.00974935 0.0737959 -0.072786 0.00935077 0.0732714 -0.072786 0.00803941 0.0569427 -0.0729249 -0.0478969 0.0582813 -0.0726033 -0.0486722 0.0581412 -0.0726033 -0.0478384 0.0570203 -0.0729249 -0.0467723 0.0581995 -0.0726033 -0.046995 0.0573581 -0.0729249 -0.0456968 0.0584528 -0.0726033 -0.0461884 0.0579375 -0.0729249 -0.0447298 0.0561571 -0.0738033 -0.0466093 0.0560652 -0.0738033 -0.0479397 0.0557441 -0.0750033 -0.0479554 0.0565568 -0.0738033 -0.045337 0.0607353 -0.0726289 -0.0583213 0.0571294 -0.0729249 -0.0490086 0.0597216 -0.0733071 -0.0596605 0.0562862 -0.0738033 -0.0492549 0.0562634 -0.0750033 -0.0452053 0.0558412 -0.0750033 -0.0465496 0.0558412 -0.0813033 -0.0465496 0.0718267 -0.0750033 0.00836785 0.0725231 -0.0750033 0.0101092 0.0527642 -0.0739303 -0.065434 0.0526295 -0.0734222 -0.0655577 0.0471211 -0.0734033 -0.0570149 0.0523728 -0.0730002 -0.0657901 0.0520224 -0.0727169 -0.0661006 0.0515693 -0.0726033 -0.0664911 0.0462912 -0.0742033 -0.0561446 0.0447463 -0.073591 -0.0565567 0.0448037 -0.0734033 -0.0566293 0.0454659 -0.073591 -0.0562257 0.0461601 -0.073072 -0.0565946 0.0455323 -0.073072 -0.0565661 0.0456319 -0.0727251 -0.0570755 0.0457492 -0.0726033 -0.0576765 0.0449615 -0.073072 -0.0568287 0.0451671 -0.0728177 -0.0570885 0.069834 -0.073591 0.0225437 0.06924 -0.073591 0.0226061 0.0692659 -0.0734033 0.0226949 0.0694298 -0.0728177 0.0232572 0.0693371 -0.073072 0.022939 0.0697698 -0.0727251 0.0234072 0.069843 -0.0742033 0.0224222 0.070267 -0.073072 0.0230082 0.0698083 -0.073072 0.0228895 0.0697933 -0.0726033 0.0240356 0.0697244 -0.0726033 0.0240178 0.0700497 -0.0727251 0.0234796 0.0794462 -0.0728162 0.0276082 0.0796318 -0.0736055 0.0269377 0.0704122 -0.073591 0.0226932 0.0453384 -0.0813033 -0.0561297 0.0454425 -0.0742033 -0.0561061 0.0704632 -0.0742033 0.0225826 0.069843 -0.0813033 0.0224222 0.0697364 -0.0742033 0.0224174 0.069206 -0.0813033 0.0224891 0.0690049 -0.0813033 0.0225609 0.069206 -0.0742033 0.0224891 0.0690049 -0.0742033 0.0225609 0.0680092 -0.0813033 0.0236266 0.0591875 -0.0813033 -0.0603361 0.0559776 -0.0750033 -0.049345 0.0233986 -0.0816033 0.0224086 0.00797479 -0.0816033 0.0363201 0.0120465 -0.0816033 0.0374796 0.0155228 -0.0816033 0.0532859 0.00447903 -0.0816033 0.0553208 0.0110744 -0.0816033 0.0380208 0.0097806 -0.0816033 0.038049 0.0107862 -0.0816033 0.0331547 0.0182724 -0.0816033 0.0295695 -0.0176996 -0.0816033 0.0526058 -0.0220744 -0.0816033 0.041327 -0.0335526 -0.0816033 0.0202204 -0.0365741 -0.0816033 0.0142671 -0.0464938 -0.0816033 -0.030313 -0.0394397 -0.0816033 -0.0390507 -0.0347163 -0.0816033 -0.028541 -0.019293 -0.0816033 -0.0330355 -0.00978993 -0.0816033 -0.0380446 -0.0100618 -0.0816033 -0.054579 0.0229212 -0.0816033 -0.0505414 0.0312483 -0.0816033 -0.0124905 0.0522761 -0.0816033 -0.018625 0.0362081 -0.0816033 -0.0128057 0.0380139 -0.0816033 -0.0110769 0.0524241 -0.0816033 -0.0182041 0.0374196 -0.0816033 -0.00864854 0.0349623 -0.0816033 0.000254423 0.0363132 -0.0816033 -0.00797726 0.04153 -0.0816033 0.022792 0.043179 -0.0816033 0.0348651 0.0336956 -0.0816033 0.025075 0.0250647 -0.0816033 0.0274647 0.0259309 -0.0816033 0.0490695 0.0291062 -0.0816033 0.0266085 0.016802 -0.0816033 0.0277023 0.0292892 -0.0816033 0.0255111 0.039247 -0.0816033 0.0149576 0.0356204 -0.0816033 0.0112883 0.0284004 -0.0816033 0.0155879 0.033536 -0.0816033 0.00897021 0.0314664 -0.0816033 0.00770502 0.033719 -0.0816033 0.00787276 0.0323877 -0.0816033 -0.000702755 0.0353322 -0.0816033 0.00642224 0.055211 -0.0816033 -0.00560851 0.036626 -0.0816033 0.00639408 0.055355 -0.0816033 0.00394698 0.0384318 -0.0816033 0.00812297 0.0280522 -0.0816033 -0.0274955 0.0293528 -0.0816033 -0.0189949 0.0234677 -0.0816033 -0.0255801 0.0172338 -0.0816033 -0.0314151 0.0263514 -0.0816033 -0.0243959 0.0224017 -0.0816033 -0.0234011 0.0252408 -0.0816033 -0.0243301 0.00822119 -0.0816033 -0.0336058 0.00951498 -0.0816033 -0.0336339 0.0113112 -0.0816033 -0.0361819 -0.0261035 -0.0816033 -0.0232543 -0.0168113 -0.0816033 -0.0276979 -0.0367404 -0.0816033 -0.0112182 -0.0251313 -0.0816033 -0.0237955 -0.023408 -0.0816033 -0.0224042 -0.0284097 -0.0816033 -0.0155835 -0.0343121 -0.0816033 -0.0106238 -0.0336408 -0.0816033 -0.00951745 -0.00642471 -0.0816033 0.035339 0.000463156 -0.0816033 0.0347593 -0.00952431 -0.0816033 0.0336383 -0.00770749 -0.0816033 0.0314732 -0.0172431 -0.0816033 0.0314195 -0.0323561 -0.0816033 0.00604458 -0.0367422 -0.0816033 0.00654155 -0.0317828 -0.0816033 0.00926272 -0.0286421 -0.0816033 0.0187895 -0.0274671 -0.0816033 0.0250715 -0.0277048 -0.0816033 0.0168089 -0.0252501 -0.0816033 0.0243345 -0.022411 -0.0816033 0.0234055 -0.0242209 -0.0816033 0.0247571 -0.0243574 -0.0816033 0.0334926 -0.0239898 -0.0816033 0.0286594 -0.0292679 -0.0816033 0.0349236 -0.0280615 -0.0816033 0.0274999 -0.0280897 -0.0816033 0.0262061 -0.0336126 -0.0816033 -0.00822366 -0.032397 -0.0816033 0.000707147 -0.0342351 -0.0816033 -0.00708912 -0.0342516 -0.0816033 -0.000459861 -0.0353415 -0.0816033 -0.00641785 -0.0391621 -0.0816033 0.000971119 -0.0364522 -0.0816033 -0.00635206 -0.0554794 -0.0816033 0.0016783 -0.0385124 -0.0816033 0.0076156 -0.0382253 -0.0816033 -0.00760202 -0.0434468 -0.0816033 -0.0137321 -0.0383536 -0.0816033 -0.00976765 -0.0385362 -0.0816033 -0.0151631 -0.0292312 -0.0816033 -0.0262488 -0.0263917 -0.0816033 -0.0281204 -0.0182817 -0.0816033 -0.0295651 -0.0253625 -0.0816033 -0.0276978 -0.0086554 -0.0816033 -0.0374221 -0.00798412 -0.0816033 -0.0363157 -0.00795597 -0.0816033 -0.0350219 -0.00968485 -0.0816033 -0.0332161 -0.00047249 -0.0816033 -0.0347549 -0.0208431 -0.0816033 -0.0514372 -0.0126969 -0.0816033 -0.0365659 0.00641538 -0.0816033 -0.0353347 0.00638722 -0.0816033 -0.0366284 -0.00148381 -0.0816033 -0.0382253 0.0081161 -0.0816033 -0.0384343 0.0149507 -0.0816033 -0.0392494 0.00922676 -0.0816033 -0.0385 0.010256 -0.0816033 -0.0380774 -0.0516445 -0.0816033 -0.0203343 -0.0467411 -0.0816033 -0.0250368 -0.0457298 -0.0816033 -0.0215664 -0.0418306 -0.0816033 -0.0264678 -0.0337049 -0.0816033 -0.0250706 -0.0292031 -0.0816033 -0.024955 0.0250681 -0.0816033 -0.0336981 0.0227851 -0.0816033 -0.0415324 0.0217738 -0.0816033 -0.0450029 0.0139394 -0.0816033 -0.0427198 -0.0408193 -0.0816033 -0.0229974 -0.0314219 -0.0816033 -0.0172362 -0.0273973 -0.0816033 -0.0232261 0.028234 -0.0816033 0.0236155 0.0314126 -0.0816033 0.0172406 0.0493129 -0.0816033 0.0254587 -0.0269849 -0.0816033 0.042758 -0.0113205 -0.0816033 0.0361863 -0.0149601 -0.0816033 0.0392538 0.0547882 -0.0821033 -0.0336397 0.053522 -0.0821033 -0.0324949 -0.058726 -0.0821033 -0.0115659 -0.0626094 -0.0821033 0.00134715 -0.0597543 -0.0821033 -0.0034623 0.0550551 -0.0821033 -0.0464012 0.0305601 -0.0821033 -0.0514547 0.0479742 -0.0821033 -0.0564661 0.0232687 -0.0821033 -0.0551374 0.0100344 -0.0821033 -0.0704865 0.0155438 -0.0821033 -0.0577929 -0.0268387 -0.0821033 -0.0659476 -0.038255 -0.0821033 -0.0460297 -0.0564059 -0.0821033 -0.0434528 -0.070617 -0.0821033 -0.00912681 -0.0631422 -0.0821033 -0.0329082 -0.0534275 -0.0821033 -0.0269798 0.0833898 -0.0725833 0.0114013 0.0841678 -0.0718033 0.0114692 0.0833714 -0.0718033 0.0162789 0.0833671 -0.0726033 0.0114199 0.0520123 -0.0718033 -0.0671598 0.0799488 -0.0718033 0.0287065 0.0544132 -0.0726033 0.0641888 0.0613568 -0.0718033 0.0587497 0.0664886 -0.0726033 0.0515761 0.0744016 -0.0725833 0.0393506 0.0731551 -0.0725833 0.0416223 0.0731484 -0.0726033 0.0415938 0.04473 -0.0726033 0.0712765 0.0345625 -0.0726033 0.0767246 0.0237621 -0.0718033 0.0815598 -0.0420497 -0.07182 0.0737985 -0.0416248 -0.0725833 0.073162 -0.0256308 -0.0718033 0.0809948 -0.028709 -0.0718033 0.0799557 -0.0202008 -0.0718033 0.0825166 -0.0114224 -0.0726033 0.083374 -0.0583308 -0.0726033 0.0606593 -0.0515739 -0.0725833 0.0665244 -0.0644916 -0.0723971 0.0543843 -0.0515786 -0.0726033 0.0664955 -0.0578433 -0.0718033 0.0622211 0.064211 -0.0725833 -0.0544122 0.0396523 -0.07182 -0.0751044 0.0420343 -0.0718033 -0.0738167 0.0420403 -0.07182 -0.0737941 0.0393437 -0.0725833 -0.0744041 0.0416154 -0.0725833 -0.0731576 0.0114438 -0.07182 -0.084156 0.0114623 -0.0718033 -0.0841703 0.0113945 -0.0725833 -0.0833923 0.0201915 -0.0718033 -0.0825122 0.0220848 -0.0718033 -0.0820256 0.0287095 -0.07182 -0.0799301 0.0284005 -0.0725833 -0.0792299 -0.0452153 -0.0718033 -0.0719179 -0.0346358 -0.0726033 -0.0766914 -0.0237715 -0.0718033 -0.0815554 -0.0235477 -0.0726033 -0.0807873 -0.011995 -0.0726033 -0.0832892 -0.012109 -0.0718033 -0.084081 -0.000490778 -0.07182 -0.0849298 -0.0544191 -0.0725833 -0.0642135 -0.0544226 -0.0726033 -0.0641844 -0.0664979 -0.0726033 -0.0515717 -0.0627017 -0.0718033 -0.0573178 -0.0743832 -0.0726033 -0.0393558 -0.073801 -0.07182 -0.0420428 -0.0751112 -0.07182 -0.0396548 -0.0744109 -0.0725833 -0.0393462 -0.0731644 -0.0725833 -0.0416179 -0.0799582 -0.0718033 -0.0287021 -0.0792368 -0.0725833 -0.028403 -0.0817852 -0.0726033 -0.0198262 -0.0825627 -0.0718033 -0.0200147 -0.0838443 -0.0721906 -0.0110323 -0.0840108 -0.0719971 -0.0112486 0.0569876 -0.0813033 -0.0439965 0.0619061 -0.0813033 -0.0367546 0.0563544 -0.0821033 -0.0435076 0.0618624 -0.0814055 -0.0366279 0.0613242 -0.0820308 -0.0363096 0.0712301 -0.0820308 -0.00231658 0.0709051 -0.0821033 0.00642439 -0.0718644 -0.0814055 0.00234162 -0.0679285 -0.0821033 -0.0213472 -0.0686917 -0.0813033 -0.0215871 -0.068392 -0.0813033 -0.0225183 -0.0638516 -0.0813033 -0.033278 -0.0570396 -0.0813033 -0.0439411 -0.0479277 -0.0821033 -0.0526554 -0.0479377 -0.0813033 -0.0537233 -0.0379695 -0.0821033 -0.0602316 -0.0150463 -0.0813033 -0.0704091 -0.0148792 -0.0821033 -0.0696267 -0.00248789 -0.0813033 -0.071955 -0.0024603 -0.0821033 -0.0711554 -0.00213236 -0.0813033 -0.0719664 0.0222191 -0.0821033 -0.0676406 0.0224688 -0.0813033 -0.0684006 0.0337175 -0.0821033 -0.0627055 0.0634169 -0.0813033 0.034086 0.0627122 -0.0821033 0.0337073 0.0565923 -0.0821033 0.043202 0.0495989 -0.0813033 0.0521893 0.040721 -0.0813033 0.0593775 0.0199153 -0.0821033 0.0683589 0.0597169 -0.0750033 -0.0402139 0.0622332 -0.073779 -0.0368613 0.0603 -0.0733063 -0.0406065 0.0627537 -0.0731538 -0.0370316 0.0588873 -0.0726033 -0.0454631 0.0609458 -0.072786 -0.0410414 0.057544 -0.0733063 -0.044426 0.0572421 -0.0738033 -0.0441929 0.0598684 -0.0740849 -0.0403159 0.0740921 -0.0726033 0.00671303 0.0734301 -0.0727858 -0.00263029 0.073759 -0.072676 -0.0027139 0.0726746 -0.0733063 0.0018579 0.0724565 -0.0735365 -0.00238151 0.0719719 -0.0750033 0.00183995 0.07196 -0.0750033 -0.00225386 0.0743711 -0.0726033 0.00190121 0.0731774 -0.072786 0.00663019 0.0724019 -0.0733063 0.00655996 0.0734529 -0.072786 0.00187777 0.0718838 -0.0740849 0.00651303 0.0721545 -0.0740849 0.00184462 0.0226377 -0.0742033 -0.0683449 -0.068392 -0.0742033 -0.0225183 -0.0294001 -0.0728177 -0.0665992 -0.0214095 -0.0726033 -0.0704165 -0.0575603 -0.0726033 -0.0458705 -0.0714851 -0.0728177 -0.0137959 -0.0727626 -0.0728175 0.0024841 -0.0731594 -0.0726539 0.00259626 -0.0720541 -0.0736874 0.00228249 -0.0720415 -0.0734033 -0.0050581 -0.0721821 -0.0734029 0.00231906 -0.0626595 -0.0726033 -0.0386156 -0.0668491 -0.0726033 -0.0308001 -0.0693068 -0.0728177 -0.0222924 -0.0297231 -0.0726033 -0.0673311 0.0383905 -0.0726033 -0.0627893 0.0302279 -0.0728177 -0.0662234 0.0220438 -0.0728177 -0.0693787 0.0136885 -0.0726033 -0.0723128 0.00489212 -0.0726033 -0.0734347 0.00483889 -0.0728177 -0.0726365 -0.00397536 -0.0726033 -0.0734906 -0.0661225 -0.0728177 -0.0304653 -0.0614799 -0.0734033 -0.0378886 -0.0655907 -0.0734033 -0.0302202 -0.0687493 -0.0734033 -0.0221131 -0.0444532 -0.0728177 -0.0576534 -0.0516257 -0.0726033 -0.0524595 -0.0368974 -0.0734033 -0.0620771 -0.0291636 -0.0734033 -0.0660635 0.0135397 -0.0728177 -0.0715268 0.00479993 -0.0734033 -0.0720522 -0.00393221 -0.0728177 -0.0726918 -0.00390061 -0.0734033 -0.072107 -0.0706996 -0.0742033 -0.0136443 -0.0726257 -0.0728177 -0.00509914 -0.0709101 -0.0734033 -0.0136849 -0.0722706 -0.0726033 -0.0139476 -0.0634357 -0.0742033 -0.034064 -0.0612974 -0.0742033 -0.0377761 -0.0563091 -0.0742033 -0.0448733 -0.0619785 -0.0728177 -0.0381958 -0.0565476 -0.0742033 -0.0445724 -0.0510646 -0.0728177 -0.0518893 -0.0569347 -0.0728177 -0.0453719 -0.0564767 -0.0734033 -0.0450069 -0.0479377 -0.0742033 -0.0537233 -0.0506538 -0.0734033 -0.0514719 -0.0505035 -0.0742033 -0.0513191 -0.0440956 -0.0734033 -0.0571896 -0.0449416 -0.0726033 -0.058287 -0.0376053 -0.0726033 -0.0632683 -0.0371966 -0.0728177 -0.0625806 -0.0146112 -0.0742033 -0.0705006 -0.0211769 -0.0728177 -0.0696511 -0.0125446 -0.0734033 -0.0711151 -0.0210065 -0.0734033 -0.0690908 -0.0126463 -0.0728177 -0.0716918 -0.00388905 -0.0742033 -0.0718929 0.0218015 -0.0742033 -0.0686162 0.0133908 -0.0742033 -0.0707407 0.0134307 -0.0734033 -0.0709513 0.0104113 -0.0742033 -0.0712404 0.00478566 -0.0742033 -0.0718383 0.0379732 -0.0728177 -0.0621068 0.0218665 -0.0734033 -0.0688205 0.0299847 -0.0734033 -0.0656906 0.0376677 -0.0734033 -0.0616071 -0.0622434 -0.0733305 0.0367134 -0.0621096 -0.0735907 0.0366703 -0.0233354 -0.0726033 0.0698065 -0.0231413 -0.0727251 0.0692258 -0.014723 -0.0726033 0.0721155 -0.00589454 -0.0726033 0.0733662 -0.0630862 -0.0726759 0.0369859 -0.0589455 -0.0726033 0.0440809 -0.0584552 -0.0727251 0.0437142 -0.0394115 -0.0726033 0.0621637 0.0203629 -0.0728177 0.069895 0.0117919 -0.0727251 0.0720303 -0.0311196 -0.073072 0.0654511 -0.0313425 -0.0727251 0.0659199 -0.0626084 -0.0729283 0.0368312 -0.0523652 -0.073072 0.0501028 -0.0527403 -0.0727251 0.0504617 -0.0462514 -0.0727251 0.0564685 0.00295958 -0.073591 0.072063 0.011708 -0.073072 0.071518 0.0201731 -0.073591 0.0692439 0.00297384 -0.073072 0.0724096 0.00299517 -0.0727251 0.0729282 -0.0144274 -0.073591 0.0706672 -0.0580395 -0.073072 0.0434034 -0.0577617 -0.073591 0.0431957 -0.0459225 -0.073072 0.0560669 0.0116519 -0.073591 0.0711758 0.0116322 -0.0742033 0.0710556 0.0202702 -0.073072 0.0695769 -0.00577625 -0.073591 0.0718927 -0.00335849 -0.0742033 0.071924 -0.0228282 -0.0742033 0.068289 -0.0228668 -0.073591 0.0684045 -0.0144967 -0.073072 0.071007 -0.005804 -0.073072 0.0722384 -0.0151318 -0.0742033 0.0703952 -0.014403 -0.0742033 0.0705478 -0.0057665 -0.0742033 0.0717713 -0.00584554 -0.0727251 0.0727558 -0.0146005 -0.0727251 0.0715156 -0.0229768 -0.073072 0.0687335 -0.0264938 -0.0742033 0.0669524 -0.0316054 -0.0726033 0.0664729 -0.0388058 -0.073072 0.0612082 -0.0386201 -0.073591 0.0609153 -0.0309707 -0.073591 0.0651379 -0.0371356 -0.0742033 0.0616893 -0.0309184 -0.0742033 0.0650279 -0.0390837 -0.0727251 0.0616466 -0.0457027 -0.073591 0.0557986 -0.0467678 -0.0742033 0.054749 -0.0551286 -0.0742033 0.0463202 -0.0521146 -0.073591 0.049863 -0.0576642 -0.0742033 0.0431227 0.0601975 -0.0781707 -0.0356247 0.0597802 -0.0790701 -0.0355807 0.0599179 -0.078926 -0.0355299 0.0595531 -0.0794088 -0.0354065 0.0594014 -0.0795507 -0.0353553 0.0592558 -0.0796397 -0.0353767 0.0587685 -0.0799272 -0.0351873 0.0587042 -0.0799615 -0.0351203 0.0699076 -0.0782089 -0.00217582 0.0698288 -0.0784813 -0.00226865 0.0694583 -0.0791733 -0.00217776 0.0690728 -0.0795714 -0.00200983 0.0684717 -0.0799272 -0.00189029 -0.0602068 -0.0781707 0.0356291 -0.0601091 -0.078351 0.0357093 -0.0597896 -0.0790701 0.035585 -0.0594108 -0.0795507 0.0353597 -0.0587136 -0.0799615 0.0351247 -0.0696179 -0.0789588 0.00212074 -0.0698382 -0.0784813 0.00227304 -0.0694676 -0.0791733 0.00218215 -0.0692631 -0.0794087 0.0020502 -0.0688916 -0.0797097 0.00204037 -0.0690822 -0.0795714 0.00201422 -0.0684794 -0.0799273 0.00193858 0.0368283 -0.0831033 0.0459005 0.0376552 -0.0827206 0.0453235 0.052787 -0.0823962 0.0266654 0.0485302 -0.0821033 -0.0350176 0.0587392 -0.0827206 -0.00462888 0.0588603 -0.0824334 -0.00534766 0.0589141 -0.0823956 -0.00514889 0.0589553 -0.0823962 -0.00464592 0.0575956 -0.0826452 -0.0125922 0.0522223 -0.0823962 -0.0277508 0.0553442 -0.0826452 -0.0203181 0.0523394 -0.082316 -0.0277234 0.0370437 -0.0821794 -0.0465142 0.0427979 -0.0823962 -0.0408123 0.0372822 -0.0821033 -0.0468136 0.0430327 -0.0821794 -0.0410362 0.0433096 -0.0821033 -0.0413003 0.0530765 -0.0821794 0.0268117 0.0534181 -0.0821033 0.0269842 0.0492465 -0.0821033 0.0340073 0.0153038 -0.0827206 -0.0569007 0.00748104 -0.0821794 -0.0589921 0.0153601 -0.0823962 -0.05711 0.0229095 -0.0827206 -0.0542862 0.00752921 -0.0821033 -0.0593717 0.0154444 -0.0821794 -0.0574233 0.0229938 -0.0823962 -0.0544859 0.030199 -0.0823962 -0.0508468 0.0580229 -0.0823962 0.0114337 -0.00871302 -0.0821794 -0.058824 -0.00863377 -0.0827206 -0.0582887 -0.00876906 -0.0821033 -0.0592026 -0.000618374 -0.0823962 -0.0591375 -0.00866551 -0.0823962 -0.0585031 -0.00513043 -0.0831033 -0.0586242 0.015284 -0.0831033 -0.0568272 0.00640549 -0.0831033 -0.0584977 0.00741291 -0.0827206 -0.0584552 -0.000616124 -0.0827206 -0.0589208 -0.000625711 -0.0821033 -0.0598446 -0.00062174 -0.0821794 -0.0594619 0.0074402 -0.0823962 -0.0586702 0.0300883 -0.0827206 -0.0506604 0.0283045 -0.0831033 -0.0515916 0.0231199 -0.0821794 -0.0547848 0.0303647 -0.0821794 -0.0511257 0.0368416 -0.0823962 -0.0462604 0.0367066 -0.0827206 -0.0460909 0.042641 -0.0827206 -0.0406627 0.0425859 -0.0831033 -0.0406102 0.0482199 -0.0821794 -0.0347937 0.0479568 -0.0823962 -0.0346039 0.0520308 -0.0827206 -0.0276491 0.047781 -0.0827206 -0.0344771 0.0553114 -0.0827206 -0.0203061 0.0564952 -0.0831033 -0.0164625 0.0575614 -0.0827206 -0.0125847 0.0592715 -0.0822021 -0.00408203 0.0593629 -0.0821794 0.00344454 0.0590391 -0.0823962 0.00342576 0.0587467 -0.0831033 0.0034088 0.0586633 -0.0831033 -0.0046229 0.0583412 -0.0821794 0.0114964 0.0588226 -0.0827206 0.00341321 0.0556489 -0.0831033 0.0191334 0.0557209 -0.0827206 0.0191581 0.0561206 -0.0831033 0.0177019 0.0578103 -0.0827206 0.0113918 0.0577356 -0.0831033 0.011377 0.059745 -0.0821033 0.00346669 0.0559259 -0.0823962 0.0192286 0.0562327 -0.0821794 0.0193341 0.0484862 -0.0827206 0.0334824 0.0525935 -0.0827206 0.0265677 0.0515891 -0.0831033 0.0283113 0.0450749 -0.0831033 0.0378328 0.0489316 -0.0821794 0.0337899 0.0486646 -0.0823962 0.0336055 0.043875 -0.0821794 0.0401386 0.0377938 -0.0823962 0.0454902 0.0436356 -0.0823962 0.0399197 0.0434757 -0.0827206 0.0397734 0.0380011 -0.0821794 0.0457398 0.0312477 -0.0823962 0.0502134 0.0311332 -0.0827206 0.0500294 0.0240311 -0.0827206 0.0538034 0.0314192 -0.0821794 0.0504889 0.0241196 -0.0823962 0.0540013 0.0271663 -0.0831033 0.0522043 0.031093 -0.0831033 0.0499648 0.0242519 -0.0821794 0.0542975 0.016542 -0.0823962 0.0567833 0.0240001 -0.0831033 0.0537339 0.0565946 -0.0821033 0.0194585 0.0587167 -0.0821033 0.0115703 0.0626001 -0.0821033 -0.00134276 0.0679183 -0.0821033 0.0223327 -0.060566 -0.0821033 0.0360934 -0.0535314 -0.0821033 0.0324993 -0.0547975 -0.0821033 0.0336441 -0.0606656 -0.0821033 0.0359257 0.073196 -0.0821033 0.0121521 0.0699024 -0.0821033 0.0216244 0.0713637 -0.0821033 0.00956299 0.0441574 -0.0821033 0.0403969 -0.0548608 -0.0821033 0.0453921 -0.0465981 -0.0821033 0.0538399 -0.0372915 -0.0821033 0.046818 -0.0305695 -0.0821033 0.0514591 -0.0155531 -0.0821033 0.0577972 -0.00347485 -0.0821033 0.0711176 0.00875973 -0.0821033 0.059207 0.0304755 -0.0821033 0.0643482 0.0167398 -0.0821033 0.0574621 0.024408 -0.0821033 0.0546469 0.0402684 -0.0821033 0.0587178 0.0316214 -0.0821033 0.0508138 0.0490477 -0.0821033 0.0516094 0.0382457 -0.0821033 0.0460341 -0.0714104 -0.0813033 -0.00922938 -0.0718277 -0.0742033 -0.00504308 -0.0712657 -0.0813033 -0.0102867 -0.0712657 -0.0742033 -0.0102867 -0.0685453 -0.0742033 -0.0220474 -0.065396 -0.0742033 -0.0301305 -0.0634357 -0.0813033 -0.034064 -0.0565476 -0.0813033 -0.0445724 -0.0484662 -0.0813033 -0.053247 -0.0439647 -0.0742033 -0.0570198 -0.0383961 -0.0813033 -0.0609084 -0.037868 -0.0742033 -0.0612381 -0.037868 -0.0813033 -0.0612381 -0.0367879 -0.0742033 -0.0618928 -0.0271402 -0.0813033 -0.0666886 -0.0290771 -0.0742033 -0.0658673 -0.0266453 -0.0742033 -0.0668879 -0.0266453 -0.0813033 -0.0668879 -0.0209442 -0.0742033 -0.0688857 -0.0125074 -0.0742033 -0.070904 -0.0146112 -0.0813033 -0.0705006 -0.00213236 -0.0742033 -0.0719664 0.0101472 -0.0813033 -0.0712785 0.0340964 -0.0813033 -0.0634101 0.0298957 -0.0742033 -0.0654956 0.0446707 -0.0742033 -0.0564612 0.0446707 -0.0813033 -0.0564612 0.0375558 -0.0742033 -0.0614243 0.0341747 -0.0742033 -0.0633679 0.0634169 -0.0742033 0.034086 0.0647199 -0.0742033 0.0315416 0.0680092 -0.0742033 0.0236266 0.0572282 -0.0813033 0.0436874 0.0430458 -0.0742033 0.0577141 0.040721 -0.0742033 0.0593775 0.0358825 -0.0742033 0.062421 0.0201391 -0.0813033 0.0691269 0.0282107 -0.0742033 0.0662434 0.0308179 -0.0813033 0.0650711 0.0308179 -0.0742033 0.0650711 0.0535427 -0.0706033 -0.0495395 0.0535427 -0.0680033 -0.0495395 0.0339003 -0.0680033 -0.06459 -0.00204074 -0.0706033 -0.0729194 0.0103567 -0.0680033 -0.0722082 -0.0143792 -0.0680033 -0.0715176 -0.0263011 -0.0706033 -0.0680434 -0.037461 -0.0706033 -0.0625975 -0.037461 -0.0680033 -0.0625975 -0.056233 -0.0706033 -0.0464744 -0.0633011 -0.0706033 -0.0362644 -0.0717833 -0.0706033 -0.0130181 -0.0717833 -0.0680033 -0.0130181 -0.0611788 -0.0680033 0.0397442 -0.0540767 -0.0706033 0.0489708 -0.0455971 -0.0680033 0.0569498 -0.0253992 -0.0706033 0.0683895 -0.0141954 -0.0706033 0.0715586 -0.00263008 -0.0706033 0.0729049 0.0649618 -0.0706033 -0.0374798 0.0607118 -0.0706033 -0.0358274 0.0646522 -0.0706033 -0.0375144 0.0626701 -0.0706033 -0.0382505 0.0611695 -0.0706033 -0.0397398 0.0486507 -0.0706033 -0.0312534 -0.0685351 -0.0706033 -0.0250036 -0.0546812 -0.0706033 -0.00952299 0.0229212 -0.0706033 -0.0505414 0.0122776 -0.0706033 -0.0541217 0.0103567 -0.0706033 -0.0722082 0.00113113 -0.0706033 -0.0554862 -0.0100618 -0.0706033 -0.054579 -0.0208431 -0.0706033 -0.0514372 -0.0143792 -0.0706033 -0.0715176 -0.0307712 -0.0706033 -0.0461895 -0.0394397 -0.0706033 -0.0390507 -0.0475356 -0.0706033 -0.0553377 0.0461006 -0.0706033 -0.0314303 -0.0704675 -0.0706033 0.0022897 -0.0729517 -0.0706033 -0.000655396 -0.0734173 -0.0706033 0.00140699 0.0451242 -0.0706033 -0.0323032 0.0443643 -0.0706033 -0.0579037 0.0339003 -0.0706033 -0.06459 0.0224539 -0.0706033 -0.0694047 0.0749269 -0.0706033 -0.00328366 -0.0649711 -0.0706033 0.0374842 -0.0607211 -0.0706033 0.0358318 -0.0649505 -0.0706033 0.0374859 0.055355 -0.0706033 0.00394698 0.0581523 -0.0706033 0.0440416 0.0493129 -0.0706033 0.0254587 0.0644181 -0.0706033 0.034228 0.0534277 -0.0706033 0.01501 0.0690429 -0.0706033 0.0235424 0.0566266 -0.0706033 0.000756629 0.0704546 -0.0706033 -0.00239432 0.0734712 -0.0706033 -0.00153358 0.0749104 -0.0706033 -0.00327115 0.00900211 -0.0706033 0.0723941 0.0204049 -0.0706033 0.070039 0.0259309 -0.0706033 0.0490695 0.0413733 -0.0706033 0.0600818 -0.0473652 -0.0706033 0.031061 -0.0611788 -0.0706033 0.0397442 -0.0455971 -0.0706033 0.0569498 -0.0359561 -0.0706033 0.0634782 -0.0176996 -0.0706033 0.0526058 0.0699575 -0.0777033 -0.00230015 0.0540216 -0.0801033 -0.0327497 0.0566266 -0.0801033 0.000756629 0.0606941 -0.0801033 -0.00249952 0.0588769 -0.0801033 -0.00449647 0.0520759 -0.0801033 -0.0278348 0.0561039 -0.0801033 -0.0163485 0.053759 -0.0801033 -0.0156652 -0.0699668 -0.0777033 0.00230454 -0.0699668 -0.0711033 0.00230454 -0.0562944 -0.0801033 0.0342261 -0.0578338 -0.0801033 -0.00022256 -0.0566359 -0.0801033 -0.000752237 -0.0607034 -0.0801033 0.00250391 -0.04866 -0.0801033 0.0312577 -0.0473652 -0.0801033 0.031061 -0.0527279 -0.0801033 0.0252168 -0.0503209 -0.0801033 0.0245843 -0.0580196 -0.0801033 0.00705798 -0.0588863 -0.0801033 0.00450086 -0.0601933 -0.0777033 0.035742 -0.0602513 -0.0711033 0.0356442 0.0569876 -0.0750033 -0.0439965 0.0717018 -0.0813033 0.00649655 0.07196 -0.0813033 -0.00225386 0.0719154 -0.0718033 -0.0452084 0.0712752 -0.0725833 -0.0447613 0.0841636 -0.0725833 -0.000533643 0.0849273 -0.07182 -0.000483915 0.0849438 -0.0718033 -0.000500473 0.0609953 -0.0726033 -0.0579652 0.0617725 -0.0726033 -0.0526521 0.0598265 -0.0726033 -0.0502315 0.0617076 -0.0726033 -0.0415544 0.0604748 -0.0726033 -0.0442667 0.0721309 -0.0726033 -0.0405892 0.0688603 -0.0726033 -0.042969 0.0728906 -0.0726033 -0.0418216 0.072559 -0.0726033 -0.0408737 0.0841435 -0.0726033 -0.00055497 0.0826441 -0.0726033 -0.00451237 0.0790971 -0.0726033 -0.000521104 0.0743402 -0.0726033 -0.00286112 0.0751522 -0.0726033 0.00314734 0.0748116 -0.0726033 0.00589444 0.074167 -0.0726033 0.00783581 0.0803876 -0.0726033 0.0112267 0.0840772 -0.0726033 -0.0033837 -0.0781275 -0.0726033 0.000144454 -0.0735549 -0.0726033 0.0027075 -0.0734237 -0.0726033 -0.0051552 0.0459072 -0.0726033 -0.0577125 -0.0754057 -0.0726033 -0.00789245 -0.0471691 -0.0726033 -0.059354 -0.0127852 -0.0726033 -0.0724797 0.0278171 -0.0726033 -0.0705215 0.0305602 -0.0726033 -0.0669512 0.0222861 -0.0726033 -0.0701411 0.0459558 -0.0726033 -0.0577645 0.0389793 -0.0726033 -0.0681717 0.0392056 -0.0726033 -0.065511 -0.0840865 -0.0726033 0.00338809 -0.08363 -0.0726033 0.00428253 0.00866204 -0.0726033 -0.075855 0.0266938 -0.0726033 -0.0734171 0.0104585 -0.0726033 -0.0778306 0.0454295 -0.0726033 -0.0613587 0.0456635 -0.0726033 -0.0577159 0.040564 -0.0726033 -0.0632121 -0.0792252 -0.0726033 -0.0283761 -0.000755002 -0.0726033 -0.0811664 -0.000561833 -0.0726033 -0.084146 0.011413 -0.0726033 -0.0833696 0.0200013 -0.0726033 -0.0817351 0.0283736 -0.0726033 -0.0792184 -0.0655179 -0.0726033 -0.0392081 -0.0429758 -0.0726033 -0.0688628 -0.000330482 -0.0726033 -0.0785301 0.00618632 -0.0726033 -0.0748545 -0.0774552 -0.0726033 -0.0102261 -0.0731577 -0.0726033 -0.0415894 -0.0716513 -0.0726033 -0.038151 -0.0682706 -0.0726033 -0.0341912 -0.0681813 -0.0726033 -0.0315225 -0.0700684 -0.0726033 -0.0225374 -0.0712896 -0.0726033 -0.0273455 -0.0632189 -0.0726033 -0.0405664 -0.0621783 -0.0726033 -0.0479756 -0.0640141 -0.0726033 -0.0499147 -0.052659 -0.0726033 -0.061775 -0.0607883 -0.0726033 -0.0581921 -0.0593259 -0.0726033 0.047862 -0.0531827 -0.0726033 0.050885 -0.0599856 -0.0726033 0.0505504 -0.039378 -0.0726033 0.0650674 -0.071279 -0.0726033 0.0447369 -0.0729482 -0.0726033 0.0413006 -0.0721798 -0.0726033 0.0404919 -0.043709 -0.0726033 0.0614671 -0.0466393 -0.0726033 0.0569422 -0.0484798 -0.0726033 0.062504 -0.0499215 -0.0726033 0.0640117 0.0764839 -0.0726033 0.0271757 0.074458 -0.0726033 0.0266786 0.0723843 -0.0726033 0.0269052 0.0698771 -0.0726033 0.0283669 0.0421273 -0.0726033 0.0633921 0.03668 -0.0726033 0.0638081 0.0436601 -0.0726033 0.0609881 0.000552499 -0.0726033 0.0841504 0.0681581 -0.0726033 0.0337302 0.065656 -0.0726033 0.0391675 0.0693485 -0.0726033 0.036377 0.0118908 -0.0726033 0.0726345 0.000745669 -0.0726033 0.0811708 0.00302034 -0.0726033 0.07354 -0.00148775 -0.0726033 0.0761021 0.0566813 -0.0726033 0.0469454 0.0661582 -0.0726033 0.0322425 0.0640048 -0.0726033 0.049919 0.0621533 -0.0726033 0.0479534 0.0617613 -0.0726033 0.0427059 0.0613514 -0.0726033 0.0453749 0.0507012 -0.0726033 0.053349 0.0485498 -0.0726033 0.0593693 0.0418773 -0.0726033 0.0662323 0.0235383 -0.0726033 0.0807917 0.0288377 -0.0726033 0.0677154 0.0205867 -0.0726033 0.070663 -0.0316507 -0.0726033 0.0681567 -0.0366221 -0.0726033 0.069557 -0.0415962 -0.0726033 0.0731552 -0.0381579 -0.0726033 0.0716488 0.0526497 -0.0726033 0.0617794 0.0607789 -0.0726033 0.0581965 -0.00692041 -0.0726033 0.0750222 -0.0266725 -0.0726033 0.0738382 -0.00906588 -0.0726033 0.0761592 -0.0105851 -0.0726033 0.0780533 -0.0200106 -0.0726033 0.0817395 -0.0848859 -0.0680033 0.00342028 -0.0841772 -0.0693033 -0.0114648 -0.0799582 -0.0693033 -0.0287021 -0.0818292 -0.0680033 -0.0228287 -0.0818292 -0.0718033 -0.0228287 -0.082213 -0.0680033 -0.0214054 -0.0841772 -0.0718033 -0.0114648 -0.0738236 -0.0693033 -0.0420367 -0.0751183 -0.0718033 -0.0396771 -0.0708542 -0.0693033 -0.0468683 -0.0772822 -0.0680033 -0.0352779 -0.0772822 -0.0693033 -0.0352779 -0.0548943 -0.0693033 -0.0648332 -0.0627017 -0.0680033 -0.0573178 -0.0613661 -0.0718033 -0.0587453 -0.0671667 -0.0718033 -0.0520148 -0.0420539 -0.0718033 -0.0738109 -0.0420539 -0.0680033 -0.0738109 -0.056405 -0.0680033 -0.0635234 -0.0530231 -0.0693033 -0.0663721 -0.034965 -0.0718033 -0.0774205 -0.0300612 -0.0718033 -0.0794529 -0.0237715 -0.0680033 -0.0815554 -0.0173369 -0.0680033 -0.0831609 -0.0173369 -0.0718033 -0.0831609 -0.00419074 -0.0718033 -0.0848446 0.000966951 -0.0680033 -0.0849422 -0.000507336 -0.0693033 -0.0849463 0.0114623 -0.0693033 -0.0841703 0.0134402 -0.0680033 -0.0838771 0.0220848 -0.0680033 -0.0820256 0.0530984 -0.0721885 -0.0663044 0.0525113 -0.0718708 -0.0667704 0.0520598 -0.0718033 -0.067123 0.0567456 -0.0680033 -0.063211 0.0396747 -0.0693033 -0.0751114 0.0345746 -0.0680033 -0.0775915 0.0605957 -0.0720421 -0.0595301 0.0567456 -0.0813033 -0.063211 0.0589806 -0.0747954 -0.0611308 0.0663499 -0.0680033 -0.053041 0.0648308 -0.0693033 -0.0548874 0.0548849 -0.0693033 0.0648376 0.0548849 -0.0718033 0.0648376 0.0822037 -0.0813033 0.0214098 0.0825856 -0.0813033 0.0198855 0.0827265 -0.073232 0.0192909 0.0828506 -0.0726622 0.0187507 0.0848765 -0.0680033 -0.00341589 0.0844572 -0.0693033 0.00909571 0.0799691 -0.0718033 0.02865 0.0807415 -0.0737128 0.0263945 0.0806474 -0.0729601 0.0266807 0.0818199 -0.0680033 0.0228331 0.0708449 -0.0680033 0.0468727 0.0724286 -0.0693033 0.0443861 0.0772729 -0.0680033 0.0352823 0.0420446 -0.0680033 0.0738152 0.045206 -0.0693033 0.0719223 0.0530137 -0.0680033 0.0663765 0.0563957 -0.0680033 0.0635278 0.0563957 -0.0718033 0.0635278 0.0651192 -0.0718033 0.0545492 0.0651192 -0.0680033 0.0545492 0.0300519 -0.0680033 0.0794573 0.0354901 -0.0680033 0.0771814 0.0348911 -0.0718033 0.077454 -0.0847603 -0.0719971 0.00031197 -0.0734342 -0.0718033 0.0427177 -0.0713357 -0.0723971 0.045034 -0.071392 -0.0721906 0.045331 -0.0566966 -0.0822787 0.0165229 -0.0566966 -0.0807932 0.0165229 0.0532667 -0.0822787 -0.0254745 0.0566872 -0.0822787 -0.0165185 0.0586134 -0.0807932 -0.00712694 -0.0528787 -0.0676033 0.0659798 -0.0374563 -0.0676033 0.0758051 0.0623971 -0.0676033 0.0570523 0.0774193 -0.0676033 0.0189524 0.0723029 -0.0676033 0.0123244 -0.0189549 -0.0676033 0.0774262 -0.0732982 -0.0676033 0.041864 -0.0730884 -0.0676033 0.0425165 -0.0647183 -0.0676033 0.0379148 -0.0722852 -0.0676033 0.0402207 -0.0679483 -0.0676033 0.047173 -0.0629667 -0.0676033 0.0465017 -0.0596487 -0.0676033 0.0426966 -0.0637701 -0.0676033 0.0456082 -0.0712515 -0.0676033 0.0430598 -0.0660811 -0.0676033 0.0452228 -0.055128 -0.0676033 0.0575782 -0.0628281 -0.0676033 0.0488405 -0.0564878 -0.0676033 0.0629177 -0.0655862 -0.0676033 0.0533666 -0.0671929 -0.0676033 0.0497652 -0.0626305 -0.0676033 0.0476553 -0.0543732 -0.0676033 0.0492393 -0.0423077 -0.0676033 0.0679834 -0.0438486 -0.0676033 0.0722961 -0.0456857 -0.0676033 0.0647494 -0.0467356 -0.0676033 0.0653338 -0.0460144 -0.0676033 0.0709374 -0.0453745 -0.0676033 0.0700048 -0.0345352 -0.0676033 0.0760201 -0.0352602 -0.0676033 0.0748252 -0.0361532 -0.0676033 0.0638262 -0.0387992 -0.0676033 0.0707057 -0.0319126 -0.0676033 0.076662 -0.0346183 -0.0676033 0.0722026 -0.0322239 -0.0676033 0.0714066 -0.0255384 -0.0676033 0.0687645 -0.0303089 -0.0676033 0.0727565 -0.0211751 -0.0676033 0.0702306 -0.0299727 -0.0676033 0.0739101 -0.0308627 -0.0676033 0.0760775 -0.0175229 -0.0676033 0.0827174 -0.00710896 -0.0676033 0.0827329 -0.00783394 -0.0676033 0.081538 -0.00264447 -0.0676033 0.0733047 -0.009024 -0.0676033 0.0840698 -0.00288267 -0.0676033 0.0794693 -0.00254649 -0.0676033 0.080623 0.0459409 -0.0676033 0.0672736 0.0236502 -0.0676033 0.0811758 0.0205168 -0.0676033 0.070423 0.0458578 -0.0676033 0.0634561 0.0428777 -0.0676033 0.0595112 0.0470527 -0.0676033 0.0627311 0.0501672 -0.0676033 0.06401 0.0493637 -0.0676033 0.0631165 0.0503057 -0.0676033 0.0663489 0.0527641 -0.0676033 0.066064 0.0496134 -0.0676033 0.067331 0.0485635 -0.0676033 0.0679155 0.0471662 -0.0676033 0.0679459 0.0679766 -0.0676033 0.0423053 0.0692019 -0.0676033 0.0429776 0.0705113 -0.0676033 0.046652 0.0699269 -0.0676033 0.0441725 0.0699573 -0.0676033 0.0455698 0.0575714 -0.0676033 0.0551256 0.065779 -0.0676033 0.0471346 0.0649756 -0.0676033 0.0462411 0.0584712 -0.0676033 0.0442831 0.0655294 -0.0676033 0.0429201 0.0601234 -0.0676033 0.0420121 0.0706988 -0.0676033 0.0387967 0.073421 -0.0676033 0.0352881 0.0721957 -0.0676033 0.0346158 0.0767582 -0.0676033 0.0325059 0.0845138 -0.0676033 -0.00230617 0.0784167 -0.0676033 0.00655256 0.0826429 -0.0676033 0.00328902 0.0833679 -0.0676033 0.0044839 0.082726 -0.0676033 0.00710649 0.0827086 -0.0676033 0.01753 0.0815311 -0.0676033 0.00783147 0.0733424 -0.0676033 0.000663393 0.0825661 -0.0676033 -0.00490469 0.0832514 -0.0676033 -0.00489128 0.0387898 -0.0676033 -0.0707013 0.0175089 -0.0676033 -0.082714 -0.0228537 -0.0676033 -0.0784061 -0.0236596 -0.0676033 -0.0811714 -0.0758 -0.0676033 -0.0374646 -0.0425192 -0.0676033 -0.0597702 -0.0575807 -0.0676033 -0.0551212 0.0722759 -0.0676033 -0.0402164 0.0660718 -0.0676033 -0.0452184 0.0649748 -0.0676033 -0.0378801 0.0728467 -0.0676033 -0.0405958 0.0732888 -0.0676033 -0.0418596 0.067939 -0.0676033 -0.0471686 0.0730791 -0.0676033 -0.0425121 0.0679086 -0.0676033 -0.0485659 0.0596646 -0.0676033 -0.0426569 0.0637607 -0.0676033 -0.0456038 0.0615049 -0.0676033 -0.0399577 0.0629993 -0.0676033 -0.0385171 0.0626211 -0.0676033 -0.0476509 0.0635111 -0.0676033 -0.0498183 0.064561 -0.0676033 -0.0504027 0.0660374 -0.0676033 -0.0527912 0.0467882 -0.0676033 -0.0692874 0.0424234 -0.0676033 -0.0683628 0.0437978 -0.0676033 -0.0723168 0.0431157 -0.0676033 -0.0693449 0.0475132 -0.0676033 -0.0680925 0.0551187 -0.0676033 -0.0575738 0.0468713 -0.0676033 -0.06547 0.0446076 -0.0676033 -0.0582212 0.0444769 -0.0676033 -0.0646739 0.0352813 -0.0676033 -0.0734235 0.0352509 -0.0676033 -0.0748208 0.0370708 -0.0676033 -0.0759854 0.0333006 -0.0676033 -0.076688 0.0319033 -0.0676033 -0.0766576 0.0420365 -0.0676033 -0.0601041 0.0425619 -0.0676033 -0.0660239 0.0340862 -0.0676033 -0.0649442 0.0302996 -0.0676033 -0.0727521 0.0210952 -0.0676033 -0.0702475 0.0189456 -0.0676033 -0.0774218 0.0301611 -0.0676033 -0.075091 0.034609 -0.0676033 -0.0721982 0.0322146 -0.0676033 -0.0714022 0.00336523 -0.0676033 -0.0788279 -0.014458 -0.0676033 -0.0719097 0.00264025 -0.0676033 -0.0800228 0.00459053 -0.0676033 -0.0781556 0.000962376 -0.0676033 -0.0845423 0.00567655 -0.0676033 -0.0834414 0.0133769 -0.0676033 -0.0834822 0.00759152 -0.0676033 -0.0820915 0.00773005 -0.0676033 -0.0797526 0.0104135 -0.0676033 -0.0726042 -0.0504096 -0.0676033 -0.0645635 -0.047062 -0.0676033 -0.0627267 -0.0114731 -0.0676033 -0.0837664 -0.0473733 -0.0676033 -0.0679821 -0.0353323 -0.0676033 -0.0768136 -0.0376664 -0.0676033 -0.0629408 -0.0460121 -0.0676033 -0.0633112 -0.0720968 -0.0676033 -0.0441727 -0.0679859 -0.0676033 -0.0423009 -0.0707081 -0.0676033 -0.0387923 -0.0692112 -0.0676033 -0.0429732 -0.0692943 -0.0676033 -0.0467907 -0.0680994 -0.0676033 -0.0475156 -0.0477963 -0.0676033 -0.0556412 -0.0649849 -0.0676033 -0.0462367 -0.0565413 -0.0676033 -0.0467293 -0.0646487 -0.0676033 -0.0450831 -0.0655387 -0.0676033 -0.0429158 -0.0766948 -0.0676033 -0.0333031 -0.0748276 -0.0676033 -0.0352533 -0.0600619 -0.0676033 -0.0421089 -0.0665886 -0.0676033 -0.0423313 -0.0636481 -0.0676033 -0.0364633 -0.0715746 -0.0676033 -0.0316355 -0.0689108 -0.0676033 -0.0251407 -0.0702314 -0.0676033 -0.021174 -0.0818259 -0.0676033 -0.0213046 -0.0774287 -0.0676033 -0.018948 -0.0801432 -0.0676033 -0.00785749 -0.0733517 -0.0676033 -0.000659001 -0.0788348 -0.0676033 -0.0033677 -0.0800297 -0.0676033 -0.00264272 -0.0751623 -0.0676033 0.00295746 -0.0844862 -0.0676033 0.00340419 -0.0845361 -0.0676033 -0.00176947 -0.0825754 -0.0676033 0.00490908 -0.0843126 -0.0676033 0.00406722 -0.0832607 -0.0676033 0.00489568 0.0451242 -0.0806033 -0.0323032 -0.0451335 -0.0806033 0.0323076 -0.0451335 -0.0706033 0.0323076 -0.0503226 -0.0816033 0.0234192 -0.0498716 -0.0806033 0.0243648 -0.0540064 -0.0816033 0.012811 -0.0551528 -0.0806033 0.00624217 -0.0546812 -0.0816033 -0.00952299 -0.0554233 -0.0806033 -0.00300253 -0.0554233 -0.0706033 -0.00300253 0.0498623 -0.0806033 -0.0243604 0.047686 -0.0816033 -0.0283853 0.0554139 -0.0706033 0.00300692 0.0550158 -0.0816033 -0.00727759 0.0550158 -0.0806033 -0.00727759 0.053279 -0.0806033 -0.0155253 0.0524241 -0.0806033 -0.0182041 0.047686 -0.0806033 -0.0283853 0.0409954 -0.0816033 -0.0374042 0.0409954 -0.0706033 -0.0374042 0.0326263 -0.0816033 -0.0448918 0.0326263 -0.0706033 -0.0448918 0.0122776 -0.0816033 -0.0541217 0.00113113 -0.0816033 -0.0554862 -0.0307712 -0.0816033 -0.0461895 -0.0464938 -0.0706033 -0.030313 -0.0516445 -0.0706033 -0.0203343 -0.0445788 -0.0816033 0.0330688 -0.0370101 -0.0816033 0.0413646 -0.0445788 -0.0706033 0.0330688 -0.0370101 -0.0706033 0.0413646 -0.0279264 -0.0816033 0.0479671 -0.0279264 -0.0706033 0.0479671 -0.0067483 -0.0816033 0.055091 -0.0067483 -0.0706033 0.055091 0.00447903 -0.0706033 0.0553208 0.0155228 -0.0706033 0.0532859 0.0352771 -0.0816033 0.0428443 0.0352771 -0.0706033 0.0428443 0.043179 -0.0706033 0.0348651 0.0534277 -0.0816033 0.01501 -0.000976285 -0.0680033 0.0849466 -0.000976285 -0.0693033 0.0849466 -0.0114717 -0.0693033 0.0841747 -0.0256308 -0.0680033 0.0809948 -0.034584 -0.0680033 0.0775958 -0.0420436 -0.0693033 0.0738211 -0.039684 -0.0718033 0.0751158 -0.039684 -0.0693033 0.0751158 -0.0520216 -0.0693033 0.0671642 -0.0520216 -0.0718033 0.0671642 -0.056755 -0.0680033 0.0632154 -0.0588853 -0.0718033 0.0612359 -0.0578433 -0.0680033 0.0622211 -0.0734342 -0.0680033 0.0427177 -0.0648401 -0.0693033 0.0548918 0.0041814 -0.0680033 0.084849 0.000498002 -0.0718033 0.0849507 0.011518 -0.0680033 0.0841671 0.0173276 -0.0680033 0.0831653 0.0237621 -0.0680033 0.0815598 -0.028709 -0.0693033 0.0799557 -0.0134495 -0.0718033 0.0838815 -0.0114717 -0.0718033 0.0841747 0.0312877 -0.0706033 0.0658998 0.0504049 -0.0706033 0.0527334 0.0581523 -0.0680033 0.0440416 0.0719086 -0.0706033 0.0122572 0.0201391 -0.0742033 0.0691269 0.00850599 -0.0742033 0.0714974 0.00295458 -0.0742033 0.0719414 -0.00351384 -0.0813033 0.0719166 -0.0267828 -0.0813033 0.0668373 -0.0385549 -0.0742033 0.0608124 -0.0471216 -0.0813033 0.0544448 -0.0456255 -0.0742033 0.0557044 -0.0554772 -0.0813033 0.0459021 -0.0619906 -0.0813033 0.036632 -0.0520266 -0.0742033 0.0497788 -0.0522068 -0.0831033 0.0271731 -0.0527963 -0.0823962 -0.026661 -0.0244173 -0.0821033 -0.0546425 -0.0167491 -0.0821033 -0.0574577 -0.0242612 -0.0821794 -0.0542931 -0.0441667 -0.0821033 -0.0403925 -0.0485395 -0.0821033 0.035022 -0.0587218 -0.0825444 0.00598148 -0.0588696 -0.0824334 0.00535206 -0.0566112 -0.0826452 0.016498 -0.0575708 -0.0827206 0.0125891 -0.0520402 -0.0827206 0.0276535 -0.0522316 -0.0823962 0.0277552 -0.0523487 -0.082316 0.0277278 -0.0370531 -0.0821794 0.0465186 -0.0232781 -0.0821033 0.0551418 -0.0530859 -0.0821794 -0.0268073 -0.0566039 -0.0821033 -0.0194541 -0.036851 -0.0823962 0.0462648 -0.0433189 -0.0821033 0.0413047 -0.0486739 -0.0823962 -0.0336011 -0.0492558 -0.0821033 -0.0340029 -0.0152933 -0.0831033 0.0568316 -0.00744953 -0.0823962 0.0586746 -0.00742224 -0.0827206 0.0584596 -0.0154537 -0.0821794 0.0574277 -0.00749037 -0.0821794 0.0589965 -0.0153694 -0.0823962 0.0571144 -0.0229188 -0.0827206 0.0542906 -0.0230031 -0.0823962 0.0544903 -0.00753854 -0.0821033 0.0593761 -0.0231292 -0.0821794 0.0547892 -0.0300976 -0.0827206 0.0506648 -0.0302083 -0.0823962 0.0508512 -0.0580323 -0.0823962 -0.0114293 -0.0525348 -0.0831033 -0.026529 -0.0526028 -0.0827206 -0.0265633 0.0166328 -0.0821794 0.0570947 0.0164813 -0.0827206 0.0565752 0.01646 -0.0831033 0.0565021 0.000612407 -0.0821794 0.0594663 0.00870369 -0.0821794 0.0588284 0.00060904 -0.0823962 0.0591419 0.00865618 -0.0823962 0.0585075 0.00862444 -0.0827206 0.0582931 0.0051211 -0.0831033 0.0586285 0.000606791 -0.0827206 0.0589251 0.000616378 -0.0821033 0.059849 -0.0153131 -0.0827206 0.0569051 -0.0283138 -0.0831033 0.0515959 -0.0228892 -0.0831033 0.0542205 -0.030374 -0.0821794 0.0511301 -0.0367159 -0.0827206 0.0460953 -0.0426503 -0.0827206 0.0406671 -0.0477903 -0.0827206 0.0344814 -0.0482292 -0.0821794 0.0347981 -0.043042 -0.0821794 0.0410406 -0.0428072 -0.0823962 0.0408167 -0.0479661 -0.0823962 0.0346083 -0.051973 -0.0831033 0.0276178 -0.0552492 -0.0831033 0.0202842 -0.0553207 -0.0827206 0.0203104 -0.0565045 -0.0831033 0.0164669 -0.0574964 -0.0831033 0.0125728 -0.0593723 -0.0821794 -0.00344014 -0.0590484 -0.0823962 -0.00342136 -0.0589646 -0.0823962 0.00465031 -0.0587485 -0.0827206 0.00463327 -0.0586726 -0.0831033 0.00462729 -0.0583506 -0.0821794 -0.011492 -0.058832 -0.0827206 -0.00340882 -0.0585045 -0.0831033 -0.00640796 -0.058756 -0.0831033 -0.00340441 -0.0556582 -0.0831033 -0.019129 -0.0557302 -0.0827206 -0.0191537 -0.0578196 -0.0827206 -0.0113874 -0.0559352 -0.0823962 -0.0192242 -0.056242 -0.0821794 -0.0193297 -0.0484956 -0.0827206 -0.033478 -0.0489409 -0.0821794 -0.0337855 -0.0450842 -0.0831033 -0.0378284 -0.0380104 -0.0821794 -0.0457354 -0.0378031 -0.0823962 -0.0454858 -0.0438844 -0.0821794 -0.0401342 -0.043645 -0.0823962 -0.0399153 -0.0376159 -0.0831033 -0.0452606 -0.043485 -0.0827206 -0.039769 -0.0311425 -0.0827206 -0.050025 -0.0376645 -0.0827206 -0.0453191 -0.0316307 -0.0821033 -0.0508094 -0.0314285 -0.0821794 -0.0504845 -0.0312571 -0.0823962 -0.050209 -0.0240405 -0.0827206 -0.053799 -0.0271756 -0.0831033 -0.0521999 -0.0166421 -0.0821794 -0.0570903 -0.0241289 -0.0823962 -0.0539969 -0.0165513 -0.0823962 -0.0567789 -0.0164907 -0.0827206 -0.0565708 0.0611857 -0.0728177 0.0394431 0.0618581 -0.0726033 0.0398765 0.0204154 -0.0727251 0.0700752 0.0285242 -0.0728177 0.0669794 0.0440024 -0.0726033 0.0589966 0.0435241 -0.0728177 0.0583553 0.05015 -0.0728177 0.0527691 0.0682117 -0.0734033 0.023697 0.0362813 -0.0728177 0.0631146 0.0560651 -0.0728177 0.0464351 0.0497465 -0.0734033 0.0523446 0.0649126 -0.0734033 0.0316355 0.0606934 -0.0734033 0.0391258 0.065439 -0.0728177 0.0318921 0.0695206 -0.0726033 0.0241516 0.055449 -0.0742033 0.0459249 0.0572282 -0.0742033 0.0436874 0.0605133 -0.0742033 0.0390096 0.0495989 -0.0742033 0.0521893 0.0556141 -0.0734033 0.0460616 0.0431739 -0.0734033 0.0578859 0.020199 -0.0734033 0.0693327 0.0359894 -0.0734033 0.0626068 0.0282947 -0.0734033 0.0664406 -0.0612275 -0.0821033 0.0363505 -0.0619716 -0.0813557 0.0365612 -0.0613335 -0.0820308 0.036314 -0.0370519 -0.0821033 0.0608047 -0.0374682 -0.0813033 0.0614879 -0.0264852 -0.0821033 0.0660947 -0.0151892 -0.0821033 0.0695642 -0.0153598 -0.0813033 0.0703458 0.00842877 -0.0813033 0.0715066 0.00833506 -0.0821033 0.0707121 0.000481445 -0.07182 0.0849342 0.0121697 -0.0718033 0.0840753 0.000531172 -0.0725833 0.0841705 0.0120551 -0.0726033 0.0832836 -0.00641483 -0.0831033 0.058502 0.0051211 -0.0936033 0.0586285 0.000606001 -0.0831033 0.058849 0.00861329 -0.0831033 0.0582178 -0.00741266 -0.0831033 0.0583841 -0.0177044 -0.0831033 0.0561274 -0.0177044 -0.0936033 0.0561274 -0.0300588 -0.0831033 0.0505994 -0.0366685 -0.0831033 0.0460357 -0.0378353 -0.0936033 0.0450817 -0.0378353 -0.0831033 0.0450817 -0.0425952 -0.0831033 0.0406146 -0.045903 -0.0936033 0.0368352 -0.0522068 -0.0936033 0.0271731 -0.0477286 -0.0831033 0.0344369 -0.045903 -0.0831033 0.0368352 -0.058631 -0.0936033 0.00512796 -0.0585045 -0.0936033 -0.00640796 -0.058631 -0.0831033 0.00512796 -0.0577449 -0.0831033 -0.0113727 -0.0515984 -0.0936033 -0.0283069 -0.0561299 -0.0831033 -0.0176975 -0.0515984 -0.0831033 -0.0283069 -0.0484329 -0.0831033 -0.0334347 -0.0434289 -0.0831033 -0.0397176 -0.0450842 -0.0936033 -0.0378284 -0.0368376 -0.0831033 -0.0458961 -0.0311023 -0.0831033 -0.0499604 -0.0240094 -0.0831033 -0.0537295 -0.0271756 -0.0936033 -0.0521999 -0.0164694 -0.0831033 -0.0564977 -0.00862262 -0.0831033 -0.0582134 -0.000615335 -0.0831033 -0.0588446 0.00640549 -0.0936033 -0.0584977 0.00740333 -0.0831033 -0.0583797 0.0228799 -0.0831033 -0.0542161 0.0176951 -0.0936033 -0.056123 0.0176951 -0.0831033 -0.056123 0.0300494 -0.0831033 -0.050595 0.0283045 -0.0936033 -0.0515916 0.0366592 -0.0831033 -0.0460313 0.037826 -0.0831033 -0.0450774 0.037826 -0.0936033 -0.0450774 0.0458936 -0.0831033 -0.0368308 0.0477193 -0.0831033 -0.0344325 0.0519636 -0.0831033 -0.0276134 0.0521975 -0.0831033 -0.0271687 0.0552399 -0.0831033 -0.0202798 0.0521975 -0.0936033 -0.0271687 0.0574871 -0.0831033 -0.0125684 0.0586217 -0.0936033 -0.00512357 0.0586217 -0.0831033 -0.00512357 0.0584952 -0.0831033 0.00641236 0.0525255 -0.0831033 0.0265334 0.0561206 -0.0936033 0.0177019 0.0484236 -0.0831033 0.0334391 0.0450749 -0.0936033 0.0378328 0.0376066 -0.0831033 0.045265 0.0434195 -0.0831033 0.039722 0.0368283 -0.0936033 0.0459005 0.0271663 -0.0936033 0.0522043 0.01646 -0.0936033 0.0565021 0.0462912 -0.0813033 -0.0561446 0.0473014 -0.0813033 -0.0568989 0.0683943 -0.0742033 0.0229884 0.0684695 -0.0742033 0.0229126 0.0686171 -0.0734033 0.0230679 0.0690206 -0.0728177 0.0234924 0.0687649 -0.0728177 0.0238891 0.0696536 -0.0726033 0.0240252 0.0695718 -0.0726033 0.0240723 0.0694823 -0.0727251 0.0234374 0.0468645 -0.0742033 -0.0564304 0.0462571 -0.073591 -0.0562616 0.0467362 -0.0734033 -0.0566022 0.0462312 -0.0734033 -0.0563504 0.0473014 -0.0742033 -0.0568989 0.0463859 -0.0728177 -0.0570715 0.0466286 -0.0728177 -0.0573317 0.0458435 -0.0726033 -0.0576807 0.0460148 -0.0727251 -0.0570929 0.0460674 -0.0728177 -0.0569127 0.0704632 -0.0813033 0.0225826 0.0697364 -0.0813033 0.0224174 0.0738789 -0.0721033 0.0271686 0.0508487 -0.0726033 0.0601508 0.0682455 -0.0726033 0.0389974 0.079237 -0.0721033 -4.10712e-05 0.0811639 -0.0726033 -0.000748139 0.0791042 -0.0678033 0.00338029 0.0789705 -0.0676033 0.00323157 0.0782781 -0.0676033 0.00421368 0.0780805 -0.0676033 0.00539893 0.0793353 -0.0678033 0.00728261 0.0792201 -0.0676033 0.00744608 0.0803316 -0.0676033 0.00790251 0.0814752 -0.0678033 0.00763946 0.0803645 -0.0694033 0.00770524 0.0803645 -0.0678033 0.00770524 0.0793353 -0.0694033 0.00728261 0.0785914 -0.0678033 0.00645528 0.0782801 -0.0678033 0.0053871 0.0784631 -0.0678033 0.00428965 0.0800763 -0.0678033 0.00283913 0.0814752 -0.0694033 0.00763946 0.0815311 -0.0696033 0.00783147 0.0803316 -0.0696033 0.00790251 0.0792201 -0.0696033 0.00744608 0.0785914 -0.0694033 0.00645528 0.0782801 -0.0694033 0.0053871 0.0780805 -0.0696033 0.00539893 0.0784631 -0.0694033 0.00428965 0.0791042 -0.0694033 0.00338029 0.0733075 -0.0676033 0.0300734 0.0722571 -0.0678033 0.0309367 0.0721126 -0.0676033 0.0307984 0.0716346 -0.0678033 0.0320712 0.0714403 -0.0676033 0.0320236 0.0716628 -0.0678033 0.033365 0.072334 -0.0678033 0.0344714 0.0714707 -0.0676033 0.0334209 0.0734686 -0.0678033 0.0350939 0.072334 -0.0694033 0.0344714 0.0716628 -0.0694033 0.033365 0.0722571 -0.0694033 0.0309367 0.0734686 -0.0694033 0.0350939 0.073421 -0.0696033 0.0352881 0.0721957 -0.0696033 0.0346158 0.0714707 -0.0696033 0.0334209 0.0714403 -0.0696033 0.0320236 0.0716346 -0.0694033 0.0320712 0.0733635 -0.0694033 0.0302654 0.0665793 -0.0676033 0.0423357 0.0650221 -0.0678033 0.0439782 0.0648371 -0.0676033 0.0439023 0.0646394 -0.0676033 0.0450875 0.0651503 -0.0678033 0.0461438 0.0668906 -0.0676033 0.0475911 0.0680341 -0.0678033 0.047328 0.0669235 -0.0678033 0.0473938 0.0658942 -0.0678033 0.0469712 0.0648391 -0.0694033 0.0450757 0.0648391 -0.0678033 0.0450757 0.0649064 -0.0694033 0.0443335 0.0655289 -0.0694033 0.043199 0.0656631 -0.0678033 0.0430689 0.0666352 -0.0694033 0.0425277 0.0650221 -0.0694033 0.0439782 0.0647121 -0.0696033 0.044286 0.0649345 -0.0694033 0.0456273 0.0651503 -0.0694033 0.0461438 0.0667403 -0.0694033 0.0473562 0.0666928 -0.0696033 0.0475504 0.0658942 -0.0694033 0.0469712 0.0656058 -0.0694033 0.0467337 0.0654675 -0.0696033 0.0468781 0.0471086 -0.0678033 0.0629231 0.0460023 -0.0678033 0.0635944 0.0451855 -0.0676033 0.0646814 0.0453798 -0.0678033 0.0647289 0.0452159 -0.0676033 0.0660787 0.0472137 -0.0678033 0.0677516 0.0485075 -0.0678033 0.0677234 0.0472137 -0.0694033 0.0677516 0.0460792 -0.0678033 0.0671291 0.0460792 -0.0694033 0.0671291 0.0454079 -0.0678033 0.0660227 0.0453798 -0.0694033 0.0647289 0.0460023 -0.0694033 0.0635944 0.0471662 -0.0696033 0.0679459 0.0454079 -0.0694033 0.0660227 0.0459409 -0.0696033 0.0672736 0.0452159 -0.0696033 0.0660787 0.0451855 -0.0696033 0.0646814 0.0471086 -0.0694033 0.0629231 0.0458578 -0.0696033 0.0634561 -0.0389602 -0.0726033 0.0679393 -0.0410948 -0.0726033 0.0627275 -0.0414145 -0.0721033 0.063112 -0.0429726 -0.0721033 0.0622018 -0.0453965 -0.0721033 0.0618613 0.000246716 -0.0721033 0.0811384 0.000248856 -0.0726033 0.0783633 -0.000208696 -0.0721033 0.0785649 -0.00180058 -0.0721033 0.0764921 -0.00407201 -0.0726033 0.0748977 -0.0271721 -0.0721033 0.0738575 -0.0273812 -0.0726033 0.0712326 -0.0278218 -0.0721033 0.071469 -0.0282299 -0.0721033 0.0708212 -0.0291608 -0.0726033 0.0692016 -0.0343467 -0.0726033 0.0683094 -0.0617819 -0.0726033 0.0526565 -0.0602934 -0.0721033 0.0500342 -0.059858 -0.0721033 0.0472207 -0.0603919 -0.0721033 0.0453845 -0.0599434 -0.0726033 0.0451636 -0.0617064 -0.0726033 0.0430295 -0.0642398 -0.0726033 0.041914 -0.0670044 -0.0726033 0.0420545 -0.06592 -0.0721033 0.0423471 -0.0671316 -0.0678033 0.046086 -0.0677541 -0.0678033 0.0472206 -0.067276 -0.0676033 0.0459477 -0.0679179 -0.0676033 0.0485703 -0.0646263 -0.0678033 0.0502151 -0.0659677 -0.0676033 0.0504375 -0.0645704 -0.0676033 0.0504071 -0.0659201 -0.0678033 0.0502433 -0.0670546 -0.0678033 0.0496207 -0.0659201 -0.0694033 0.0502433 -0.0677259 -0.0678033 0.0485144 -0.0677541 -0.0694033 0.0472206 -0.0660252 -0.0678033 0.0454148 -0.0671929 -0.0696033 0.0497652 -0.0670546 -0.0694033 0.0496207 -0.0677259 -0.0694033 0.0485144 -0.0679179 -0.0696033 0.0485703 -0.0679483 -0.0696033 0.047173 -0.0671316 -0.0694033 0.046086 -0.067276 -0.0696033 0.0459477 -0.0660252 -0.0694033 0.0454148 -0.0466019 -0.0678033 0.0654825 -0.0472429 -0.0678033 0.0663919 -0.047428 -0.0676033 0.0663159 -0.047426 -0.0678033 0.0674893 -0.0476256 -0.0676033 0.0675012 -0.0463708 -0.0678033 0.0693849 -0.0472894 -0.0676033 0.0686548 -0.046486 -0.0676033 0.0695483 -0.0442309 -0.0678033 0.0697417 -0.0453416 -0.0678033 0.0698075 -0.0442309 -0.0694033 0.0697417 -0.0471147 -0.0678033 0.0685575 -0.0463708 -0.0694033 0.0693849 -0.0471147 -0.0694033 0.0685575 -0.047426 -0.0694033 0.0674893 -0.0472429 -0.0694033 0.0663919 -0.0456298 -0.0678033 0.0649414 -0.0456298 -0.0694033 0.0649414 -0.0453416 -0.0694033 0.0698075 -0.0472894 -0.0696033 0.0686548 -0.0466019 -0.0694033 0.0654825 -0.047428 -0.0696033 0.0663159 -0.0352906 -0.0676033 0.0734279 -0.0332624 -0.0678033 0.0764981 -0.0333099 -0.0676033 0.0766924 -0.0319686 -0.0694033 0.07647 -0.0343969 -0.0678033 0.0758756 -0.0332624 -0.0694033 0.0764981 -0.0350682 -0.0678033 0.0747692 -0.0350963 -0.0678033 0.0734754 -0.0344738 -0.0694033 0.0723409 -0.0344738 -0.0678033 0.0723409 -0.0333099 -0.0696033 0.0766924 -0.0343969 -0.0694033 0.0758756 -0.0345352 -0.0696033 0.0760201 -0.0350682 -0.0694033 0.0747692 -0.0352602 -0.0696033 0.0748252 -0.0350963 -0.0694033 0.0734754 -0.0346183 -0.0696033 0.0722026 -0.00704757 -0.0678033 0.0790537 -0.00719204 -0.0676033 0.0789154 -0.00786435 -0.0676033 0.0801407 -0.00697065 -0.0678033 0.0825884 -0.00588366 -0.0676033 0.0834052 -0.00454233 -0.0678033 0.0831828 -0.00583612 -0.0678033 0.0832109 -0.00764193 -0.0678033 0.081482 -0.00767008 -0.0678033 0.0801883 -0.00704757 -0.0694033 0.0790537 -0.0059412 -0.0678033 0.0783824 -0.0059412 -0.0694033 0.0783824 -0.00588366 -0.0696033 0.0834052 -0.00583612 -0.0694033 0.0832109 -0.00697065 -0.0694033 0.0825884 -0.00764193 -0.0694033 0.081482 -0.00767008 -0.0694033 0.0801883 0.0668552 -0.0696033 -0.0425302 0.00677119 -0.0721033 -0.0754979 0.00677119 -0.0696033 -0.0754979 0.00837624 -0.0721033 -0.0762653 0.0107209 -0.0696033 -0.0804224 0.0107209 -0.0721033 -0.0804224 0.0359072 -0.0721033 -0.0696273 0.0648723 -0.0676033 -0.0451473 0.0647221 -0.0678033 -0.0453822 0.063876 -0.0678033 -0.0457672 0.0629573 -0.0676033 -0.0464973 0.0629163 -0.0678033 -0.0471111 0.0628188 -0.0676033 -0.0488361 0.0649052 -0.0678033 -0.0453446 0.0647221 -0.0694033 -0.0453822 0.0635875 -0.0678033 -0.0460047 0.0631321 -0.0678033 -0.0465946 0.0629163 -0.0694033 -0.0471111 0.0628881 -0.0694033 -0.0484049 0.0628208 -0.0678033 -0.0476627 0.0628881 -0.0678033 -0.0484049 0.0630038 -0.0678033 -0.0487602 0.0635106 -0.0678033 -0.0495394 0.0636449 -0.0678033 -0.0496695 0.0660718 -0.0696033 -0.0452184 0.0646745 -0.0696033 -0.045188 0.0635875 -0.0694033 -0.0460047 0.0635106 -0.0694033 -0.0495394 0.0441656 -0.0676033 -0.0699293 0.0426084 -0.0678033 -0.0682868 0.0427366 -0.0678033 -0.0661212 0.0422257 -0.0676033 -0.0671775 0.0433653 -0.0676033 -0.0651304 0.0445098 -0.0678033 -0.0648712 0.0456204 -0.0694033 -0.064937 0.0434806 -0.0678033 -0.0652938 0.0424254 -0.0678033 -0.0671893 0.0427366 -0.0694033 -0.0661212 0.0426084 -0.0694033 -0.0682868 0.0432494 -0.0678033 -0.0691961 0.0442216 -0.0678033 -0.0697373 0.0445098 -0.0694033 -0.0648712 0.0456764 -0.0696033 -0.064745 0.0434806 -0.0694033 -0.0652938 0.0425619 -0.0696033 -0.0660239 0.0424254 -0.0694033 -0.0671893 0.0422257 -0.0696033 -0.0671775 0.0424234 -0.0696033 -0.0683628 0.0432494 -0.0694033 -0.0691961 0.0442216 -0.0694033 -0.0697373 0.0431157 -0.0696033 -0.0693449 0.0308534 -0.0676033 -0.0760731 0.0301631 -0.0678033 -0.0739176 0.0299634 -0.0676033 -0.0739058 0.031103 -0.0676033 -0.0718586 0.0322475 -0.0678033 -0.0715994 0.0334141 -0.0676033 -0.0714732 0.0322475 -0.0694033 -0.0715994 0.0312183 -0.0678033 -0.0720221 0.0304743 -0.0678033 -0.0728494 0.0304743 -0.0694033 -0.0728494 0.0303461 -0.0678033 -0.075015 0.0301631 -0.0694033 -0.0739176 0.0309871 -0.0678033 -0.0759244 0.0334141 -0.0696033 -0.0714732 0.0322146 -0.0696033 -0.0714022 0.0312183 -0.0694033 -0.0720221 0.031103 -0.0696033 -0.0718586 0.0302996 -0.0696033 -0.0727521 0.0303461 -0.0694033 -0.075015 0.0299634 -0.0696033 -0.0739058 0.0309871 -0.0694033 -0.0759244 0.0308534 -0.0696033 -0.0760731 0.0319593 -0.0694033 -0.0764656 0.00342662 -0.0678033 -0.0825071 0.00328215 -0.0676033 -0.0826454 0.00260984 -0.0676033 -0.0814201 0.00350354 -0.0678033 -0.0789724 0.00593186 -0.0678033 -0.0783781 0.00482121 -0.0694033 -0.0783123 0.00463807 -0.0678033 -0.0783499 0.00463807 -0.0694033 -0.0783499 0.00379199 -0.0694033 -0.0787349 0.00304808 -0.0694033 -0.0795622 0.00283226 -0.0694033 -0.0800788 0.00283226 -0.0678033 -0.0800788 0.00280411 -0.0678033 -0.0813726 0.00291981 -0.0694033 -0.0817279 0.00453299 -0.0694033 -0.0831784 0.00356087 -0.0694033 -0.0826372 0.00342714 -0.0696033 -0.0827859 0.00342662 -0.0694033 -0.0825071 0.0027348 -0.0696033 -0.0818038 0.00280411 -0.0694033 -0.0813726 0.0027368 -0.0694033 -0.0806304 0.00253715 -0.0696033 -0.0806186 0.00287333 -0.0696033 -0.079465 0.00350354 -0.0694033 -0.0789724 -0.0462786 -0.0721033 -0.0600385 -0.0462786 -0.0696033 -0.0600385 -0.0445689 -0.0721033 -0.0608808 -0.0440151 -0.0696033 -0.0613449 -0.0440151 -0.0721033 -0.0613449 -0.042785 -0.0721033 -0.0630996 -0.0423496 -0.0721033 -0.0659132 -0.0715215 -0.0721033 -0.0277884 -0.0725335 -0.0696033 -0.0273808 -0.0702352 -0.0721033 -0.0287207 -0.0702352 -0.0696033 -0.0287207 -0.0688347 -0.0721033 -0.0309825 -0.0686722 -0.0721033 -0.0316174 -0.0688347 -0.0696033 -0.0309825 -0.0687541 -0.0721033 -0.0340637 -0.0697507 -0.0696033 -0.0360633 -0.0698893 -0.0721033 -0.0362323 -0.071853 -0.0721033 -0.0376935 -0.0658052 -0.0696033 -0.0396431 -0.0656701 -0.0721033 -0.0396844 -0.0636456 -0.0696033 -0.0408526 -0.0622043 -0.0721033 -0.0429657 -0.0618593 -0.0696033 -0.0453333 -0.0618638 -0.0721033 -0.0453896 -0.0770397 -0.0696033 -0.00120727 -0.0752966 -0.0721033 -0.00487907 -0.0761694 -0.0721033 -0.0082258 -0.0780033 -0.0696033 -0.00997953 -0.0777327 -0.0721033 -0.00981015 -0.0804293 -0.0721033 -0.0107234 -0.0811963 -0.0678033 -0.00276895 -0.0812292 -0.0676033 -0.00257168 -0.0822255 -0.0678033 -0.00319158 -0.0823407 -0.0676033 -0.00302811 -0.082514 -0.0678033 -0.00342909 -0.0831442 -0.0676033 -0.00392163 -0.0829694 -0.0678033 -0.00401891 -0.0834804 -0.0676033 -0.00507526 -0.0831852 -0.0678033 -0.00453546 -0.0832827 -0.0676033 -0.00626051 -0.0830977 -0.0678033 -0.00618454 -0.0814845 -0.0678033 -0.00763506 -0.0824566 -0.0678033 -0.0070939 -0.0825904 -0.0676033 -0.00724262 -0.0825909 -0.0678033 -0.00696378 -0.0800856 -0.0678033 -0.00283473 -0.0813794 -0.0678033 -0.00280658 -0.0813794 -0.0694033 -0.00280658 -0.082514 -0.0694033 -0.00342909 -0.0832807 -0.0678033 -0.00508709 -0.0832134 -0.0678033 -0.00582925 -0.0832134 -0.0694033 -0.00582925 -0.0825909 -0.0694033 -0.00696378 -0.0800856 -0.0694033 -0.00283473 -0.0826523 -0.0696033 -0.00328462 -0.0831852 -0.0694033 -0.00453546 -0.0834077 -0.0696033 -0.0058768 -0.0827354 -0.0696033 -0.0071021 -0.0814845 -0.0694033 -0.00763506 -0.0758781 -0.0678033 -0.03439 -0.0760225 -0.0676033 -0.0345284 -0.0765006 -0.0678033 -0.0332555 -0.0758011 -0.0678033 -0.0308553 -0.0766644 -0.0676033 -0.0319058 -0.0759395 -0.0676033 -0.0307109 -0.0746666 -0.0678033 -0.0302328 -0.0747142 -0.0676033 -0.0300386 -0.0733169 -0.0676033 -0.030069 -0.0764724 -0.0678033 -0.0319617 -0.0747717 -0.0678033 -0.0350613 -0.0747142 -0.0696033 -0.0300386 -0.0746666 -0.0694033 -0.0302328 -0.0758011 -0.0694033 -0.0308553 -0.0759395 -0.0696033 -0.0307109 -0.0764724 -0.0694033 -0.0319617 -0.0766644 -0.0696033 -0.0319058 -0.0765006 -0.0694033 -0.0332555 -0.0766948 -0.0696033 -0.0333031 -0.0758781 -0.0694033 -0.03439 -0.0747717 -0.0694033 -0.0350613 -0.0691498 -0.0678033 -0.0466524 -0.0699666 -0.0676033 -0.0455654 -0.0697442 -0.0678033 -0.044224 -0.0699362 -0.0676033 -0.0441681 -0.0679384 -0.0678033 -0.0424951 -0.0666446 -0.0678033 -0.0425233 -0.0666446 -0.0694033 -0.0425233 -0.0690729 -0.0694033 -0.0431177 -0.0690729 -0.0678033 -0.0431177 -0.0697442 -0.0694033 -0.044224 -0.0697723 -0.0678033 -0.0455178 -0.0691498 -0.0694033 -0.0466524 -0.0665886 -0.0696033 -0.0423313 -0.0679384 -0.0694033 -0.0424951 -0.0697723 -0.0694033 -0.0455178 -0.0699666 -0.0696033 -0.0455654 -0.0692943 -0.0696033 -0.0467907 -0.0680994 -0.0696033 -0.0475156 -0.0482286 -0.0678033 -0.0628529 -0.0484593 -0.0676033 -0.0626963 -0.0496846 -0.0676033 -0.0633686 -0.0502457 -0.0678033 -0.0659132 -0.05044 -0.0676033 -0.0659608 -0.05013 -0.0678033 -0.0662685 -0.0485728 -0.0676033 -0.0679111 -0.0497677 -0.0676033 -0.0671861 -0.0496232 -0.0678033 -0.0670478 -0.047118 -0.0678033 -0.0629187 -0.0482286 -0.0694033 -0.0628529 -0.0484118 -0.0678033 -0.0628906 -0.0484118 -0.0694033 -0.0628906 -0.0492578 -0.0678033 -0.0632756 -0.0495463 -0.0678033 -0.0635131 -0.0500018 -0.0678033 -0.0641029 -0.0502176 -0.0678033 -0.0646195 -0.050313 -0.0678033 -0.0651711 -0.049489 -0.0678033 -0.0671779 -0.049489 -0.0694033 -0.0671779 -0.0485168 -0.0694033 -0.0677191 -0.05044 -0.0696033 -0.0659608 -0.0496232 -0.0694033 -0.0670478 -0.05013 -0.0694033 -0.0662685 -0.0502457 -0.0694033 -0.0659132 -0.050313 -0.0694033 -0.0651711 -0.0502176 -0.0694033 -0.0646195 -0.0504096 -0.0696033 -0.0645635 -0.0500018 -0.0694033 -0.0641029 -0.0495463 -0.0694033 -0.0635131 -0.0492578 -0.0694033 -0.0632756 -0.047118 -0.0694033 -0.0629187 -0.047062 -0.0696033 -0.0627267 -0.0765526 -0.0680033 0.00409986 0.0649412 -0.0680033 -0.0374815 0.0719086 -0.0680033 0.0122572 0.0702358 -0.0676033 0.0211327 0.0644181 -0.0680033 0.034228 0.0690429 -0.0680033 0.0235424 0.0647714 -0.0676033 0.0344156 0.0694215 -0.0676033 0.0236715 0.0504049 -0.0680033 0.0527334 0.0506813 -0.0676033 0.0530225 0.0312877 -0.0680033 0.0658998 0.0314593 -0.0676033 0.0662611 0.0413733 -0.0680033 0.0600818 0.0416002 -0.0676033 0.0604113 -0.0666586 -0.0676033 0.0380518 -0.0671836 -0.0680033 0.037808 0.0766552 -0.0676033 -0.00371144 0.0746844 -0.0680033 -0.00308815 0.074945 -0.0676033 -0.00278471 0.073408 -0.0680033 -0.0014026 0.0737707 -0.0676033 -0.001234 -0.0300612 -0.0680033 -0.0794529 -0.0530231 -0.0680033 -0.0663721 -0.0561394 -0.0676033 -0.0632243 -0.0354994 -0.0680033 -0.077177 -0.0462379 -0.0676033 -0.0707876 -0.0464566 -0.0680033 -0.0711225 -0.0648219 -0.0676033 -0.054288 -0.0660841 -0.0676033 -0.0527445 -0.0651286 -0.0680033 -0.0545448 -0.0708542 -0.0680033 -0.0468683 -0.0724379 -0.0680033 -0.0443817 -0.0722274 -0.0676033 -0.0439589 -0.0781742 -0.0680033 -0.0332547 -0.0778062 -0.0676033 -0.0330981 -0.0827239 -0.0676033 -0.0174973 -0.0843845 -0.0680033 -0.00982379 -0.0840688 -0.0676033 -0.0090485 -0.0844666 -0.0680033 -0.00909132 -0.00906935 -0.0816033 -0.0311039 -0.016552 -0.0821033 -0.0272704 -0.0230468 -0.0821033 -0.0220584 -0.0279714 -0.0821033 -0.0153429 -0.03099 -0.0821033 -0.00758176 -0.0314757 -0.0816033 -0.00770063 -0.0318971 -0.0821033 0.000696268 -0.0306308 -0.0821033 0.00892699 -0.0311108 -0.0816033 0.00906688 -0.0272773 -0.0821033 0.0165495 -0.0220653 -0.0821033 0.0230443 -0.0153498 -0.0821033 0.0279689 -0.0155903 -0.0816033 0.0284073 -0.00758862 -0.0821033 0.0309876 0.000700284 -0.0816033 0.0323945 -0.0658676 -0.0801033 0.00137498 -0.0699704 -0.0711033 0.00219085 -0.0683696 -0.0799694 0.00187253 -0.0699169 -0.0782089 0.00218021 -0.0699704 -0.0777033 0.00219085 -0.0684811 -0.0799272 0.00189469 0.0606563 -0.0706033 -0.0359213 0.0601839 -0.0711033 -0.0357376 0.056285 -0.0801033 -0.0342217 0.0585784 -0.0799986 -0.0351134 0.0595117 -0.0794087 -0.0354763 0.0601839 -0.0777033 -0.0357376 0.0600998 -0.078351 -0.0357049 -0.0704675 -0.0821033 0.0022897 -0.0704736 -0.0821033 0.00209477 0.0606563 -0.0821033 -0.0359213 0.0606563 -0.081911 -0.0359213 0.0605567 -0.0821033 -0.036089 -0.0585877 -0.0799986 0.0351178 -0.0587778 -0.0799272 0.0351917 -0.0592651 -0.0796397 0.0353811 -0.0595211 -0.0794087 0.0354807 0.0578244 -0.0801033 0.000226952 0.0578244 -0.0706033 0.000226952 0.0699611 -0.0711033 -0.00218646 0.0696085 -0.0789588 -0.00211635 0.0692538 -0.0794087 -0.00204581 0.0683603 -0.0799694 -0.00186814 0.0675736 -0.0801033 -0.0017117 0.0699611 -0.0777033 -0.00218646 -0.0562944 -0.081911 0.0342261 0.0704582 -0.0821033 -0.00228531 0.0557686 -0.0706033 0.00174615 0.0559776 -0.0801033 0.00141278 0.0461006 -0.0803028 -0.0314303 0.0473559 -0.0706033 -0.0310566 0.0473559 -0.0801033 -0.0310566 0.0486507 -0.0801033 -0.0312534 -0.04866 -0.0706033 0.0312577 -0.0461099 -0.0706033 0.0314347 -0.0461099 -0.0803028 0.0314347 -0.0566359 -0.0706033 -0.000752237 -0.0578338 -0.0706033 -0.00022256 -0.0557845 -0.0802966 -0.0017296 -0.0557779 -0.0706033 -0.00174176 0.000689405 -0.0821033 0.0318946 0.0318878 -0.0821033 -0.000691876 0.0306214 -0.0821033 -0.0089226 0.00757928 -0.0821033 -0.0309832 -0.000698738 -0.0821033 -0.0318903 0.00892013 -0.0821033 0.0306283 0.0230375 -0.0821033 0.0220628 -0.0395084 -0.0821033 0.00943085 -0.0346721 -0.0821033 0.0064965 -0.0317378 -0.0821033 0.0113328 -0.0383893 -0.0821033 0.0132711 0.0373427 -0.0821033 -0.0121832 0.0339422 -0.0821033 -0.0122364 0.0380139 -0.0821033 -0.0110769 0.0291062 -0.0821033 0.0266085 0.0260941 -0.0821033 0.0232587 0.0289779 -0.0821033 0.0244429 0.0250647 -0.0821033 0.0274647 0.0243934 -0.0821033 0.0263583 0.0261992 -0.0821033 0.0280872 0.0243652 -0.0821033 0.0250645 0.0125593 -0.0821033 0.0344047 0.0118154 -0.0821033 0.0335773 0.0097806 -0.0821033 0.038049 0.0126876 -0.0821033 0.0365703 0.00794663 -0.0821033 0.0350263 0.00797479 -0.0821033 0.0363201 -0.00812544 -0.0821033 0.0384386 -0.00642471 -0.0821033 0.035339 -0.0092361 -0.0821033 0.0385044 -0.00709599 -0.0821033 0.0342327 -0.0249619 -0.0821033 0.0292006 -0.0242209 -0.0821033 0.0247571 -0.0252501 -0.0821033 0.0243345 -0.0263608 -0.0821033 0.0244003 -0.0280897 -0.0821033 0.0262061 -0.0385366 -0.0821033 -0.0086702 -0.0382253 -0.0821033 -0.00760202 -0.0374814 -0.0821033 -0.00677469 -0.0343121 -0.0821033 -0.0106238 -0.0336126 -0.0821033 -0.00822366 -0.0244903 -0.0821033 -0.0247048 -0.0273973 -0.0821033 -0.0232261 -0.0292031 -0.0821033 -0.024955 -0.0261035 -0.0821033 -0.0232543 -0.0251313 -0.0821033 -0.0237955 -0.0243073 -0.0821033 -0.0258023 -0.0292312 -0.0821033 -0.0262488 -0.0275023 -0.0821033 -0.0280546 -0.0120558 -0.0821033 -0.0374752 -0.0118247 -0.0821033 -0.0335729 -0.0086554 -0.0821033 -0.0374221 -0.0126969 -0.0821033 -0.0365659 0.0081161 -0.0821033 -0.0384343 0.0109999 -0.0821033 -0.0372501 0.00822119 -0.0821033 -0.0336058 0.00951498 -0.0821033 -0.0336339 0.00641538 -0.0821033 -0.0353347 0.0280522 -0.0821033 -0.0274955 0.0234677 -0.0821033 -0.0255801 0.0263514 -0.0821033 -0.0243959 0.0249526 -0.0821033 -0.0291962 0.0273809 -0.0821033 -0.0286019 0.0378374 -0.0821033 0.0105513 0.0345912 -0.0821033 0.0108657 0.033719 -0.0821033 0.00787276 -0.0164694 -0.0936033 -0.0564977 -0.0368376 -0.0936033 -0.0458961 -0.0561299 -0.0936033 -0.0176975 -0.0565045 -0.0936033 0.0164669 -4.66678e-06 -0.0936033 2.19602e-06 -0.0283138 -0.0936033 0.0515959 -0.00641483 -0.0936033 0.058502 0.0584952 -0.0936033 0.00641236 0.0515891 -0.0936033 0.0283113 0.0564952 -0.0936033 -0.0164625 0.0458936 -0.0936033 -0.0368308 -0.00513043 -0.0936033 -0.0586242 + + + + + + + + + + 0.295681 0.707087 -0.64234 0.511032 0.704514 -0.492449 0.279234 0.704511 0.652451 0.503122 0.479654 0.718888 0.56025 -0.366063 0.743046 0.370635 0.69962 0.610869 0.356468 0.707104 0.610684 0.279233 0.704514 0.652449 0.738174 -0.306997 0.600709 0.513176 0.706753 0.486982 0.463624 0.70662 0.534547 0.885115 -0.204082 0.418236 0.730454 0.552993 0.400794 0.60695 0.707006 0.36298 0.568676 0.706075 0.421977 0.831274 0.551278 -0.0712417 0.705418 0.707089 0.0491046 0.695578 0.704513 0.140829 0.695576 0.704515 0.140829 0.663735 0.706923 0.244368 0.905231 -0.0474586 0.422261 0.923036 -0.382763 -0.0386957 0.999204 0.0334363 -0.0217432 0.765424 0.643217 0.0199651 0.699302 0.707072 -0.105006 0.68135 0.704513 -0.198553 0.68135 0.704513 -0.198553 0.582822 0.706773 -0.400988 0.854464 0.0334071 -0.518435 0.799326 -0.382759 -0.463221 0.739415 0.551273 -0.386476 0.646238 0.707072 -0.287098 0.316937 0.707009 -0.63221 0.400799 0.552987 -0.730456 0.521876 -0.204079 -0.82825 0.399609 0.705861 -0.58487 0.511036 0.70451 -0.492451 0.261119 0.339123 -0.903777 0.299913 -0.306992 -0.903221 0.324188 -0.0343257 -0.94537 0.292269 0.653577 -0.698152 -0.0273999 0.707103 -0.70658 -0.0155471 0.699616 -0.71435 0.0752964 0.296859 -0.951948 0.0679136 0.705189 -0.705759 0.165773 0.706862 -0.687652 -0.142802 0.705954 -0.693712 -0.156745 -0.252881 -0.954716 -0.08522 0.559058 -0.824738 -0.0442956 0.707028 -0.705797 0.294446 0 -0.955668 -0.0217578 0 -0.999763 -0.0217578 0 -0.999763 0.479339 0.0840388 -0.873597 0.479337 0.0840349 -0.873598 0.647877 0 -0.761745 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217577 0.999763 0 -0.0217577 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 0.732838 0 -0.680403 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217578 0 -0.999763 -0.0217578 0 -0.999763 0.851917 0.0840333 -0.51689 0.851918 0.0840347 -0.516889 0.941951 0 -0.335751 0.999763 0 -0.0217578 0.999763 0 -0.0217578 0.876699 0 0.481039 0.876699 0 0.481039 0.518724 0 0.854942 0.518724 0 0.854942 -0.0217578 0 -0.999763 -0.0217578 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.974856 0 -0.222834 0.996227 0.0840369 -0.0216808 0.996227 0.0840335 -0.0216784 0.983629 0 0.180206 0.876699 0 0.481039 0.876699 0 0.481039 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591246 0 -0.998251 -0.0217197 -0.0590893 -0.998016 0.201255 0 -0.979539 0.414178 0 -0.910196 0.478706 -0.09836 -0.872448 0.63564 0 -0.771986 0.854942 0 -0.518724 0.775184 -0.201917 -0.598597 0.486393 0 0.87374 0.517818 -0.0590916 0.853448 0.695967 0 0.718074 0.761743 0 0.647879 0.837104 0.053397 0.544432 0.876608 -0.0145066 0.480987 0.950825 0.00667448 0.309657 0.955665 0 0.294455 0.995913 0 0.0903194 0.992791 -0.117894 -0.021606 0.985353 0 -0.170525 0.922705 0 -0.385506 -0.0591246 0 -0.998251 -0.0217197 -0.0590893 -0.998016 0.201255 0 -0.979539 0.414178 0 -0.910196 0.478706 -0.0983606 -0.872448 0.635641 0 -0.771985 0.854942 0 -0.518724 0.775185 -0.201916 -0.598597 0.922705 0 -0.385508 0.985354 0 -0.170523 0.992791 -0.117892 -0.021606 0.995913 0 0.0903178 0.950846 0 0.309664 0.872448 -0.098361 0.478706 0.8383 0 0.545209 0.680405 0 0.732836 0.695932 -0.0089696 0.718051 0.518559 0.0251338 0.854673 0.485242 0.0687875 0.87167 0.335751 0 0.941951 0.486396 0 0.873738 0.517819 -0.0590885 0.853447 0.872448 -0.0983607 0.478706 0.8383 0 0.545209 0.695959 0 0.718082 0.922705 0 -0.385508 0.985354 0 -0.170522 0.992791 -0.117891 -0.021606 0.995913 0 0.0903169 0.950846 0 0.309664 0.775185 -0.201916 -0.598597 0.854942 0 -0.518724 0.635639 0 -0.771987 0.478706 -0.0983589 -0.872448 0.414179 0 -0.910195 0.201248 0 -0.97954 -0.0217197 -0.0590875 -0.998017 -0.0591235 0 -0.998251 0.486394 0 0.873739 0.486394 0 0.873739 0.817328 0 0.576173 0.817328 0 0.576173 0.986379 0 0.16449 0.986379 0 0.16449 0.960066 0 -0.279774 0.960066 0 -0.279774 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591246 0 -0.998251 -0.0591246 0 -0.998251 0.486395 0 0.873739 0.517818 0.0590882 0.853448 0.81633 -0.049396 0.57547 0.838301 0 0.545208 0.950845 0 0.309667 0.983297 -0.0789923 0.163975 0.995913 0 0.0903161 0.985354 0 -0.170521 0.95627 -0.0888327 -0.278668 0.922705 0 -0.385508 0.791487 0 -0.611186 0.741277 -0.0789904 -0.666535 0.635642 0 -0.771984 0.379855 0 -0.925046 0.413454 -0.059089 -0.908606 -0.0589855 0.0686868 -0.995893 -0.0217578 0 -0.999763 0.816329 -0.0493952 0.575471 0.517818 0.0590892 0.853448 0.486394 0 0.873739 0.985354 0 -0.170521 0.995913 0 0.0903161 0.983297 -0.0789911 0.163974 0.950846 0 0.309664 0.8383 0 0.54521 0.908542 -0.174531 -0.379593 0.960066 0 -0.279775 0.791487 0 -0.611186 0.741277 -0.0789897 -0.666535 0.635643 0 -0.771983 0.379855 0 -0.925046 0.413453 -0.0590891 -0.908606 -0.0589853 0.0686865 -0.995893 -0.0217577 0 -0.999763 0.486394 0 0.873739 0.517818 -0.0590905 0.853447 0.872448 -0.0983608 0.478706 0.8383 0 0.54521 0.695964 0 0.718077 0.922705 0 -0.385508 0.985354 0 -0.170523 0.992791 -0.117892 -0.021606 0.995913 0 0.0903178 0.950846 0 0.309664 0.775186 -0.201915 -0.598596 0.854942 0 -0.518724 0.63564 0 -0.771986 0.478706 -0.09836 -0.872448 0.414178 0 -0.910196 0.201255 0 -0.979539 -0.0217197 -0.0590893 -0.998016 -0.0591246 0 -0.998251 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217578 0.999763 0 -0.0217578 0.854941 0 -0.518724 0.854941 0 -0.518724 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217578 0 -0.999763 -0.0217578 0 -0.999763 0.908542 -0.17453 -0.379593 0.960066 0 -0.279774 0.791487 0 -0.611186 0.741277 -0.0789905 -0.666535 0.635643 0 -0.771984 0.379855 0 -0.925046 0.413456 -0.0590922 -0.908605 0.143297 0.0156365 -0.989556 -0.0216808 0.0840345 -0.996227 -0.0216818 0.084033 -0.996227 -0.222826 0 -0.974858 0.985354 0 -0.170521 0.995913 0 0.0903169 0.983297 -0.0789911 0.163975 0.950846 0 0.309664 0.838299 0 0.54521 0.81633 -0.0493929 0.57547 0.517819 0.0590916 0.853447 0.486394 0 0.873739 0.373093 0.69475 0.614918 0.373095 0.694747 0.614921 0.63057 0.694747 0.345989 0.63057 0.694747 0.34599 0.719086 0.694745 -0.0156494 0.719085 0.694746 -0.0156496 0.614919 0.694749 -0.373094 0.614922 0.694745 -0.373095 0.34599 0.694744 -0.630572 0.345992 0.694742 -0.630574 -0.0156495 0.694742 -0.719089 -0.0156503 0.694746 -0.719085 -0.31784 0.701412 -0.637965 -0.317841 0.701411 -0.637965 -0.354705 0.697261 -0.622906 -0.354705 0.697262 -0.622905 -0.597625 0.697262 -0.395815 -0.597626 0.697262 -0.395815 -0.711932 0.697262 -0.0835431 -0.711931 0.697262 -0.0835431 -0.289576 0.703802 -0.648698 -0.289574 0.703804 -0.648696 -0.345325 0.69843 -0.626854 -0.345325 0.69843 -0.626854 -0.579405 0.69843 -0.420102 -0.579405 0.69843 -0.420102 -0.703146 0.69843 -0.133348 -0.703147 0.698429 -0.133348 -0.334406 0.699691 -0.631352 -0.334405 0.699692 -0.631351 -0.320173 0.701181 -0.637051 -0.320173 0.701182 -0.637051 -0.526145 0.701182 -0.481161 -0.526145 0.701181 -0.481162 0.348272 0.698074 0.62562 0.348271 0.698074 0.625619 0.585226 0.698074 0.412556 0.585227 0.698074 0.412556 0.706273 0.698074 0.117778 0.706272 0.698074 0.117778 0.687432 0.698074 -0.200324 0.687432 0.698074 -0.200325 0.532437 0.698074 -0.478752 0.532437 0.698074 -0.478752 0.271986 0.698074 -0.662356 0.271986 0.698074 -0.662357 -0.0423348 0.698074 -0.714773 -0.0423352 0.698073 -0.714774 0.348271 0.698074 0.62562 0.348272 0.698073 0.62562 0.585228 0.698073 0.412556 0.585228 0.698073 0.412556 0.706274 0.698073 0.117776 0.706271 0.698076 0.117779 0.687431 0.698076 -0.200324 0.687431 0.698075 -0.200325 0.532437 0.698075 -0.478751 0.532437 0.698074 -0.478752 0.271985 0.698074 -0.662357 0.271985 0.698074 -0.662357 -0.0423349 0.698074 -0.714773 -0.0423346 0.698074 -0.714773 0.34827 0.698074 0.62562 0.348272 0.698073 0.62562 0.585227 0.698074 0.412556 0.585229 0.698073 0.412555 0.706274 0.698073 0.117778 0.706274 0.698073 0.117779 0.687432 0.698073 -0.200326 0.687432 0.698074 -0.200325 0.532436 0.698074 -0.478753 0.532436 0.698074 -0.478753 0.271986 0.698074 -0.662356 0.271986 0.698074 -0.662357 -0.0423348 0.698074 -0.714773 -0.0423339 0.698074 -0.714773 0.373093 0.694748 0.614921 0.373096 0.694745 0.614921 0.630571 0.694745 0.34599 0.630569 0.694747 0.345991 0.719084 0.694747 -0.0156495 0.719084 0.694747 -0.0156494 0.614921 0.694746 -0.373096 0.61492 0.694747 -0.373094 0.34599 0.694748 -0.630568 0.345989 0.694746 -0.630571 -0.0156512 0.694745 -0.719086 -0.0156488 0.694747 -0.719084 0.373096 0.694745 0.614922 0.373094 0.694747 0.614921 0.63057 0.694747 0.345989 0.63057 0.694747 0.345989 0.719084 0.694747 -0.0156492 0.719084 0.694747 -0.0156494 0.61492 0.694747 -0.373094 0.61492 0.694747 -0.373094 0.34599 0.694748 -0.630568 0.345989 0.694745 -0.630571 -0.0156512 0.694745 -0.719086 -0.0156488 0.694747 -0.719084 0.348271 0.698074 0.625619 0.348272 0.698073 0.62562 0.585228 0.698073 0.412556 0.585228 0.698073 0.412556 0.706274 0.698073 0.117776 0.706271 0.698075 0.117779 0.68743 0.698076 -0.200324 0.687431 0.698075 -0.200325 0.532437 0.698075 -0.478751 0.532437 0.698074 -0.478752 0.271985 0.698074 -0.662357 0.271985 0.698074 -0.662357 -0.0423349 0.698074 -0.714773 -0.042335 0.698074 -0.714773 -0.0423346 0.698074 -0.714773 -0.0423347 0.698074 -0.714773 0.142356 0.706859 -0.692881 0.277711 0.682273 -0.676299 0.295433 0.700862 -0.649239 0.450091 0.706117 -0.546642 0.550492 0.67227 -0.494987 0.562801 0.703124 -0.434594 0.687433 0.698073 -0.200326 0.722484 0.622012 -0.301859 0.698946 0.704873 -0.120952 0.706273 0.698073 0.117777 0.756657 0.650202 0.0686176 0.673292 0.706115 0.219269 0.585228 0.698073 0.412556 0.348272 0.698073 0.625621 0.348271 0.698073 0.625621 0.492297 0.706859 0.507932 0.618158 0.67546 0.402038 0.373094 0.694747 0.61492 0.373096 0.694746 0.614921 0.63057 0.694746 0.34599 0.63057 0.694747 0.34599 0.719084 0.694747 -0.0156496 0.719085 0.694746 -0.01565 0.614921 0.694746 -0.373095 0.614921 0.694746 -0.373095 0.345989 0.694746 -0.630571 0.34599 0.694747 -0.63057 -0.0156496 0.694747 -0.719084 -0.0156488 0.694747 -0.719084 0.348268 0.698075 0.62562 0.348273 0.698072 0.625621 0.58523 0.698072 0.412555 0.585227 0.698074 0.412556 0.706273 0.698074 0.117778 0.706273 0.698074 0.117778 0.687432 0.698074 -0.200325 0.687432 0.698074 -0.200325 0.532436 0.698074 -0.478753 0.532436 0.698074 -0.478753 0.271986 0.698074 -0.662356 0.271986 0.698075 -0.662356 -0.0423329 0.698075 -0.714772 -0.0423367 0.698072 -0.714775 0.373095 0.694745 0.614922 0.373095 0.694747 0.614921 0.630571 0.694745 0.34599 0.630569 0.694748 0.345988 0.719082 0.694749 -0.0156493 0.719085 0.694746 -0.0156489 0.61492 0.694747 -0.373094 0.614918 0.69475 -0.373094 0.345989 0.694749 -0.630568 0.345989 0.694748 -0.630569 -0.0156493 0.694749 -0.719082 -0.0156495 0.69475 -0.719081 0.373095 0.694746 0.614921 0.373095 0.694745 0.614922 0.630572 0.694744 0.345991 0.630569 0.694749 0.345988 0.719082 0.694749 -0.0156493 0.719085 0.694746 -0.0156489 0.614921 0.694747 -0.373095 0.614918 0.69475 -0.373093 0.345988 0.694749 -0.630568 0.34599 0.694745 -0.630571 -0.0156494 0.694748 -0.719083 -0.0156492 0.694747 -0.719084 0.348271 0.698073 0.625621 0.34827 0.698078 0.625617 0.492292 0.706863 0.50793 0.514444 0.777063 0.362657 0.597956 0.700863 0.388896 0.67329 0.706117 0.219271 0.575788 0.811941 0.0960184 0.708154 0.703131 0.0642226 0.698939 0.704879 -0.120958 0.54681 0.821954 -0.159347 0.654502 0.704877 -0.273451 0.532434 0.698077 -0.47875 0.423923 0.84447 -0.327353 0.450094 0.706115 -0.546641 0.271986 0.698073 -0.662358 0.255396 0.787251 -0.561257 0.142358 0.70686 -0.692881 -0.0423347 0.698074 -0.714773 -0.0423349 0.698075 -0.714772 0.348271 0.698073 0.625621 0.348272 0.69807 0.625624 0.492292 0.706857 0.507939 0.514446 0.777062 0.362657 0.597957 0.700861 0.388897 0.673291 0.706116 0.219272 0.575788 0.811941 0.0960185 0.708158 0.703127 0.0642217 0.698941 0.704876 -0.120957 0.54681 0.821954 -0.159346 0.654505 0.704873 -0.273454 0.532437 0.698074 -0.478753 0.423924 0.844469 -0.327354 0.450095 0.706117 -0.546639 0.271986 0.698075 -0.662356 0.255397 0.78725 -0.561258 0.142359 0.706858 -0.692882 -0.0423348 0.698072 -0.714775 -0.042335 0.698073 -0.714774 0.348269 0.698079 0.625615 0.348272 0.69807 0.625624 0.492291 0.706857 0.50794 0.514445 0.777063 0.362657 0.597957 0.700861 0.388896 0.67329 0.706116 0.219272 0.575788 0.811941 0.0960189 0.708161 0.703124 0.0642214 0.68743 0.698076 -0.200325 0.463804 0.882295 -0.0802643 0.654505 0.704873 -0.273454 0.532437 0.698074 -0.478752 0.423924 0.844469 -0.327354 0.450096 0.706112 -0.546644 0.271988 0.698068 -0.662362 0.255397 0.78725 -0.561257 0.142354 0.706855 -0.692886 -0.0423342 0.698069 -0.714778 -0.042335 0.698073 -0.714774 0.348271 0.698074 0.62562 0.348272 0.69807 0.625624 0.58523 0.698071 0.412556 0.585229 0.698073 0.412555 0.706273 0.698074 0.117779 0.706272 0.698075 0.117778 0.687431 0.698074 -0.200325 0.687431 0.698075 -0.200325 0.532435 0.698076 -0.478751 0.532436 0.698075 -0.478752 0.271986 0.698075 -0.662356 0.271985 0.698076 -0.662355 -0.0423346 0.698076 -0.714772 -0.0423342 0.698073 -0.714774 0.63057 0.694747 0.345989 0.373094 0.694747 0.614921 0.373093 0.69475 0.614918 0.431375 0.857441 0.280555 0.673288 0.706118 0.219273 0.719082 0.694749 -0.0156496 0.443041 0.895601 0.0401779 0.698942 0.704876 -0.120956 0.654503 0.704875 -0.273453 0.455325 0.84638 -0.276262 0.5628 0.703125 -0.434594 0.450095 0.706117 -0.546638 0.268709 0.829436 -0.489726 0.295431 0.700862 -0.64924 -0.0156494 0.694747 -0.719084 -0.0156492 0.694746 -0.719085 0.630567 0.69475 0.345988 0.373094 0.694749 0.614918 0.373095 0.694746 0.614921 0.431372 0.857443 0.280554 0.673289 0.706118 0.219271 0.719083 0.694748 -0.0156503 0.443039 0.895601 0.0401778 0.698938 0.704879 -0.120955 0.654499 0.704879 -0.273453 0.455326 0.846379 -0.276262 0.562802 0.703122 -0.434595 0.450098 0.706115 -0.546639 0.268709 0.829436 -0.489726 0.295432 0.70086 -0.649242 -0.0156493 0.694747 -0.719084 -0.0156494 0.694747 -0.719083 0.34827 0.698076 0.625618 0.34827 0.698074 0.62562 0.492292 0.70686 0.507934 0.514445 0.777063 0.362657 0.597957 0.700862 0.388896 0.67329 0.706116 0.219272 0.575789 0.811941 0.0960192 0.708161 0.703124 0.064222 0.687433 0.698073 -0.200326 0.463804 0.882294 -0.0802647 0.654505 0.704873 -0.273454 0.532437 0.698074 -0.478753 0.423922 0.844471 -0.327352 0.450093 0.706117 -0.54664 0.271986 0.698075 -0.662356 0.255397 0.78725 -0.561258 0.142359 0.706858 -0.692882 -0.0423348 0.698072 -0.714775 -0.042335 0.698073 -0.714774 0.373095 0.694747 0.61492 0.373095 0.694747 0.61492 0.63057 0.694747 0.345989 0.63057 0.694746 0.34599 0.719084 0.694747 -0.0156494 0.719085 0.694746 -0.0156492 0.61492 0.694747 -0.373095 0.614922 0.694745 -0.373095 0.34599 0.694744 -0.630572 0.345992 0.694742 -0.630574 -0.0156495 0.694742 -0.719089 -0.0156503 0.694746 -0.719085 0.630571 0.694745 0.34599 0.373096 0.694744 0.614923 0.373096 0.694746 0.61492 0.431371 0.857443 0.280554 0.673289 0.706118 0.219272 0.719084 0.694747 -0.0156493 0.443041 0.895601 0.0401783 0.698943 0.704875 -0.120956 0.654502 0.704876 -0.273454 0.455326 0.846379 -0.276263 0.562801 0.703123 -0.434595 0.450097 0.706114 -0.54664 0.26871 0.829435 -0.489727 0.295432 0.700864 -0.649238 -0.0156493 0.694749 -0.719082 -0.0156502 0.694753 -0.719078 -0.445932 0 -0.895067 -0.445932 0 -0.895067 0.10123 0 0.994863 0.108318 0.00100166 0.994116 -0.259889 -0.00104039 0.965638 -0.253 0 0.967466 -0.494834 0 -0.868988 -0.494834 0 -0.868988 -0.833722 0 -0.552185 -0.833722 0 -0.552185 -0.993185 0 -0.116547 -0.993185 0 -0.116547 0.26606 0 0.963956 0.0799341 0.00208073 0.996798 0.0657166 0 0.997838 -0.407626 0 -0.913149 -0.407626 0 -0.913149 -0.482514 0 -0.875888 -0.482514 0 -0.875888 -0.809588 0 -0.586999 -0.809588 0 -0.586999 -0.982488 0 -0.186324 -0.982488 0 -0.186324 0.486396 0 0.873739 0.486396 0 0.873739 0.817326 0 0.576175 0.817326 0 0.576175 0.986379 0 0.164488 0.986379 0 0.164488 0.960066 0 -0.279773 0.960066 0 -0.279773 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 0.486395 0 0.873739 0.486395 0 0.873739 0.817327 0 0.576175 0.817327 0 0.576175 0.986379 0 0.164486 0.986379 0 0.164486 0.960066 0 -0.279773 0.960066 0 -0.279773 0.743601 0 -0.668624 0.743601 0 -0.668624 0.379854 0 -0.925046 0.379854 0 -0.925046 -0.0591248 0 -0.998251 -0.0591248 0 -0.998251 0.486394 0 0.87374 0.518721 0.00363671 0.854936 0.817323 -0.00303832 0.576171 0.838299 0 0.545211 0.950847 0 0.30966 0.986367 -0.00486805 0.164487 0.995913 0 0.0903186 0.985354 0 -0.170524 0.960051 -0.00547918 -0.27977 0.922705 0 -0.385507 0.791487 0 -0.611186 0.74359 -0.00486822 -0.668618 0.635639 0 -0.771986 0.379855 0 -0.925046 0.414176 -0.00363679 -0.910189 -0.0591242 0.00422984 -0.998242 -0.021758 0 -0.999763 0.486391 0 0.873741 0.518719 -0.00363675 0.854937 0.695963 0 0.718078 0.838301 0 0.545208 0.876683 -0.00607229 0.48103 0.950845 0 0.309666 0.995913 0 0.0903164 0.999737 -0.00729365 -0.0217574 0.985354 0 -0.170521 0.922705 0 -0.385507 0.854918 -0.0072938 -0.518712 0.791484 0 -0.611189 0.635646 0 -0.771981 0.481032 -0.00607253 -0.876682 0.414179 0 -0.910196 0.201253 0 -0.979539 -0.0217601 -0.00363666 -0.999757 -0.0591272 0 -0.99825 0.486395 0 0.873739 0.518722 -0.00363668 0.854935 0.695963 0 0.718078 0.838301 0 0.545208 0.876683 -0.00607229 0.48103 0.950845 0 0.309666 0.995913 0 0.0903173 0.999737 -0.00729368 -0.0217569 0.985354 0 -0.170523 0.922704 0 -0.385508 0.854919 -0.00729363 -0.51871 0.791488 0 -0.611185 0.635645 0 -0.771982 0.481032 -0.0060725 -0.876682 0.414179 0 -0.910195 0.201252 0 -0.97954 -0.0217601 -0.00363666 -0.999757 -0.0591273 0 -0.99825 0.486395 0 0.873739 0.486395 0 0.873739 0.817327 0 0.576175 0.817327 0 0.576175 0.986379 0 0.164486 0.986379 0 0.164486 0.960066 0 -0.279772 0.960066 0 -0.279772 0.743601 0 -0.668624 0.743601 0 -0.668624 0.379854 0 -0.925046 0.379854 0 -0.925046 -0.0591248 0 -0.998251 -0.0591248 0 -0.998251 0.486395 0 0.873739 0.518722 0.00363676 0.854935 0.695969 0 0.718072 0.838298 0 0.545213 0.876682 0.0060726 0.481032 0.950847 0 0.30966 0.995913 0 0.0903147 0.999737 0.00729339 -0.0217553 0.985355 0 -0.170515 0.922703 0 -0.385512 0.854918 0.00729355 -0.518712 0.791487 0 -0.611185 0.635636 0 -0.771989 0.48103 0.0060722 -0.876683 -0.0591245 0 -0.998251 -0.0217578 0.00363663 -0.999757 0.201252 0 -0.97954 0.41418 0 -0.910195 0.486394 0 0.87374 0.518721 -0.00363671 0.854936 0.695963 0 0.718078 0.8383 0 0.545209 0.876683 -0.0060723 0.48103 0.950845 0 0.309667 0.995913 0 0.0903186 0.999737 -0.00729377 -0.0217574 0.985354 0 -0.170524 0.922705 0 -0.385507 0.854919 -0.0072937 -0.51871 0.791487 0 -0.611186 0.635639 0 -0.771986 0.481029 -0.00607235 -0.876683 0.414178 0 -0.910196 0.201255 0 -0.979539 -0.0217579 -0.00363663 -0.999757 -0.0591247 0 -0.998251 0.486391 0 0.873741 0.486391 0 0.873741 0.817329 0 0.576172 0.817329 0 0.576172 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279773 0.960066 0 -0.279773 0.743599 0 -0.668626 0.743599 0 -0.668626 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591222 0 -0.998251 -0.0591222 0 -0.998251 -0.0423347 0.698074 -0.714773 -0.0423348 0.698074 -0.714773 0.142357 0.70686 -0.69288 0.278674 0.679544 -0.678646 0.295432 0.700863 -0.649239 0.450094 0.706117 -0.546639 0.553549 0.667715 -0.497735 0.5628 0.703125 -0.434593 0.687432 0.698074 -0.200326 0.731269 0.609836 -0.305527 0.698944 0.704874 -0.120956 0.706272 0.698074 0.117778 0.762887 0.64282 0.069184 0.673289 0.706117 0.219273 0.585227 0.698075 0.412554 0.34827 0.698076 0.625618 0.34827 0.698076 0.625618 0.492291 0.706861 0.507934 0.620724 0.672104 0.403705 0.255198 0.851305 0.458426 0.503719 0.851305 -0.146789 0.517525 0.851305 0.0863023 0.428828 0.851305 0.302303 -0.031021 0.851305 -0.523754 0.199299 0.851305 -0.485345 0.390146 0.851305 -0.350808 0.255197 0.851305 0.458426 0.50372 0.851304 -0.146789 0.517525 0.851305 0.086301 0.428828 0.851305 0.302302 -0.0310211 0.851305 -0.523754 0.199299 0.851305 -0.485346 0.390146 0.851305 -0.350808 0.273991 0.849119 0.451582 0.490731 0.856529 0.159815 0.509849 0.855727 -0.0882337 0.411015 0.854595 -0.317386 -0.0114926 0.849119 -0.528077 0.21608 0.853125 -0.474855 0.328053 0.856529 -0.398422 0.477433 0.855727 -0.199472 0.517172 0.854595 0.0469019 0.437346 0.853125 0.28444 0.255195 0.851305 0.458427 0.437346 0.853126 0.284438 0.517172 0.854595 0.0469008 0.477433 0.855727 -0.199472 0.328056 0.856529 -0.398419 -0.0310224 0.851304 -0.523754 0.103707 0.857007 -0.504761 0.21608 0.853125 -0.474855 0.411014 0.854595 -0.317387 0.509849 0.855727 -0.0882324 0.49073 0.856529 0.159818 0.358632 0.857008 0.370028 0.255198 0.851305 0.458426 0.437347 0.853125 0.284439 0.517172 0.854596 0.0469013 0.477433 0.855727 -0.199473 0.328055 0.856529 -0.398419 -0.0310224 0.851305 -0.523753 0.103706 0.857008 -0.50476 0.216079 0.853126 -0.474854 0.411015 0.854596 -0.317385 0.509849 0.855727 -0.0882333 0.49073 0.856529 0.159818 0.358632 0.857008 0.370028 0.255198 0.851305 0.458426 0.50372 0.851305 -0.146789 0.517525 0.851305 0.0863012 0.428828 0.851305 0.302303 -0.0310211 0.851305 -0.523754 0.199299 0.851305 -0.485345 0.390146 0.851305 -0.350808 0.528077 0.849119 -0.0114915 0.463074 0.849119 0.254087 0.273992 0.849119 0.451581 -0.0114926 0.849119 -0.528077 0.254086 0.849119 -0.463074 0.451581 0.849119 -0.273992 0.255197 0.851305 0.458426 0.437346 0.853125 0.284439 0.517172 0.854596 0.0469019 0.477433 0.855727 -0.199472 0.328053 0.856529 -0.398421 -0.031021 0.851305 -0.523754 0.103707 0.857008 -0.50476 0.216079 0.853125 -0.474855 0.411014 0.854596 -0.317385 0.509849 0.855727 -0.0882336 0.49073 0.856529 0.159819 0.358632 0.857008 0.370028 0.255195 0.851305 0.458427 0.50372 0.851305 -0.146789 0.517525 0.851305 0.0863025 0.428829 0.851305 0.302301 -0.0310197 0.851305 -0.523754 0.199299 0.851305 -0.485346 0.390145 0.851305 -0.350809 0.348271 0.698074 0.62562 0.34827 0.698075 0.625619 0.585226 0.698075 0.412555 0.585227 0.698074 0.412555 0.706272 0.698074 0.117778 0.706272 0.698074 0.117779 0.687432 0.698074 -0.200326 0.687432 0.698074 -0.200326 0.532437 0.698074 -0.478753 0.532437 0.698074 -0.478752 0.271986 0.698075 -0.662356 0.271986 0.698074 -0.662357 -0.0423348 0.698074 -0.714773 -0.0423348 0.698074 -0.714773 0.373095 0.694746 0.614921 0.373095 0.694747 0.614921 0.630571 0.694746 0.345989 0.63057 0.694746 0.345989 0.719085 0.694746 -0.0156496 0.719085 0.694746 -0.0156496 0.614921 0.694746 -0.373095 0.61492 0.694748 -0.373093 0.345989 0.694748 -0.630569 0.345989 0.694747 -0.63057 -0.0156494 0.694747 -0.719084 -0.0156493 0.694747 -0.719084 0.373094 0.694748 0.61492 0.373095 0.694747 0.61492 0.630569 0.694747 0.34599 0.630569 0.694747 0.34599 0.719084 0.694747 -0.0156496 0.719084 0.694747 -0.0156496 0.61492 0.694747 -0.373095 0.61492 0.694747 -0.373095 0.345989 0.694747 -0.63057 0.345989 0.694748 -0.630569 -0.0156496 0.694747 -0.719084 -0.0156495 0.694747 -0.719084 0.373095 0.694747 0.61492 0.373095 0.694747 0.61492 0.63057 0.694747 0.345989 0.630569 0.694748 0.345989 0.719084 0.694747 -0.0156496 0.719084 0.694747 -0.0156496 0.614921 0.694747 -0.373094 0.614921 0.694746 -0.373095 0.345989 0.694746 -0.630571 0.345989 0.694746 -0.63057 -0.0156496 0.694746 -0.719085 -0.0156476 0.694748 -0.719083 0.373095 0.694746 0.614921 0.373096 0.694746 0.614921 0.63057 0.694746 0.345989 0.630569 0.694747 0.34599 0.719084 0.694747 -0.0156493 0.719084 0.694747 -0.0156493 0.61492 0.694748 -0.373094 0.61492 0.694748 -0.373094 0.345988 0.694748 -0.630569 0.345988 0.694748 -0.630569 -0.0156495 0.694749 -0.719082 -0.0156495 0.694749 -0.719082 0.373094 0.694748 0.61492 0.373095 0.694747 0.61492 0.630569 0.694747 0.34599 0.630569 0.694747 0.34599 0.719084 0.694747 -0.0156496 0.719084 0.694747 -0.0156495 0.61492 0.694748 -0.373095 0.61492 0.694747 -0.373095 0.345989 0.694747 -0.63057 0.34599 0.694748 -0.630568 -0.0156495 0.694749 -0.719082 -0.0156496 0.694749 -0.719082 0.348271 0.698074 0.62562 0.348272 0.698073 0.62562 0.585229 0.698073 0.412555 0.585227 0.698074 0.412555 0.706272 0.698074 0.11778 0.706273 0.698073 0.117779 0.687432 0.698073 -0.200326 0.687432 0.698073 -0.200326 0.532437 0.698074 -0.478753 0.532437 0.698074 -0.478752 0.271986 0.698074 -0.662357 0.271986 0.698074 -0.662357 -0.0423347 0.698074 -0.714773 -0.0423348 0.698074 -0.714773 0.34827 0.698075 0.625619 0.34827 0.698075 0.625619 0.585227 0.698075 0.412554 0.585228 0.698074 0.412553 0.706272 0.698074 0.11778 0.706273 0.698073 0.117779 0.687432 0.698073 -0.200326 0.687431 0.698075 -0.200324 0.532436 0.698075 -0.478751 0.532436 0.698074 -0.478753 0.271986 0.698074 -0.662357 0.271986 0.698074 -0.662357 -0.0423349 0.698074 -0.714773 -0.042335 0.698074 -0.714773 -0.0423347 0.698074 -0.714773 -0.0423348 0.698074 -0.714773 0.142357 0.70686 -0.69288 0.278675 0.679543 -0.678646 0.295432 0.700863 -0.649239 0.450094 0.706117 -0.54664 0.553548 0.667715 -0.497736 0.5628 0.703126 -0.434593 0.654503 0.704875 -0.273455 0.718174 0.663647 -0.209282 0.698945 0.704873 -0.120955 0.706273 0.698073 0.117779 0.762885 0.642821 0.069187 0.67329 0.706117 0.219271 0.585228 0.698074 0.412553 0.348269 0.698075 0.62562 0.34827 0.698074 0.62562 0.492294 0.70686 0.507932 0.620725 0.672104 0.403704 -0.0156486 0.694747 -0.719084 -0.0442135 0.663921 -0.746494 0.142358 0.706859 -0.692881 0.345989 0.694746 -0.63057 0.322081 0.628715 -0.7078 0.450094 0.706116 -0.54664 0.61492 0.694747 -0.373095 0.639875 0.588569 -0.494112 0.654504 0.704874 -0.273453 0.698944 0.704874 -0.120955 0.762091 0.647257 -0.0165845 0.70816 0.703125 0.0642218 0.67329 0.706117 0.219271 0.661854 0.655796 0.363155 0.34827 0.698076 0.625618 0.384094 0.672103 0.633047 0.492294 0.706861 0.507932 0.597956 0.700863 0.388896 -0.0156496 0.694746 -0.719085 -0.0442136 0.663921 -0.746494 0.142357 0.706859 -0.692881 0.345989 0.694746 -0.63057 0.322081 0.628715 -0.7078 0.450096 0.706118 -0.546636 0.61492 0.694748 -0.373094 0.639875 0.588569 -0.494112 0.654504 0.704874 -0.273453 0.698944 0.704874 -0.120957 0.762092 0.647257 -0.0165853 0.70816 0.703125 0.0642213 0.673289 0.706117 0.219273 0.661853 0.655796 0.363155 0.34827 0.698075 0.625619 0.384094 0.672103 0.633047 0.492284 0.706859 0.507944 0.597958 0.700862 0.388896 0.486394 0 0.87374 0.518721 0.00371761 0.854936 0.695963 0 0.718077 0.838299 0 0.54521 0.876682 0.00620745 0.48103 0.950845 0 0.309666 0.995913 0 0.0903164 0.999735 0.00745585 -0.0217574 0.985354 0 -0.170521 0.922704 0 -0.385509 0.854918 0.0074558 -0.51871 0.791488 0 -0.611185 0.63564 0 -0.771986 0.481029 0.00620744 -0.876683 -0.0591247 0 -0.998251 -0.0217579 0.00371752 -0.999756 0.201252 0 -0.979539 0.414178 0 -0.910196 0.486395 0 0.873739 0.51872 0.00371741 0.854936 0.817323 -0.00310609 0.576172 0.8383 0 0.545209 0.950846 0 0.309663 0.986367 -0.00497643 0.164487 0.995913 0 0.0903176 0.985354 0 -0.170524 0.960051 -0.00560107 -0.279771 0.922705 0 -0.385508 0.791488 0 -0.611185 0.743591 -0.00497652 -0.668616 0.63564 0 -0.771986 0.379856 0 -0.925046 0.414177 -0.00371767 -0.910189 -0.0591242 0.00432392 -0.998241 -0.021758 0 -0.999763 0.518724 0 0.854942 0.518724 0 0.854942 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.021758 0.999763 0 -0.021758 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217578 0 -0.999763 -0.0217578 0 -0.999763 0.518724 0 0.854942 0.518724 0 0.854942 0.876699 0 0.48104 0.876699 0 0.48104 0.999763 0 -0.021758 0.999763 0 -0.021758 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.518725 0 0.854941 0.518725 0 0.854941 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.021758 0.999763 0 -0.021758 0.854942 0 -0.518724 0.854942 0 -0.518724 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217577 0.999763 0 -0.0217577 0.854942 0 -0.518724 0.854942 0 -0.518724 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.486393 0 0.87374 0.51872 -0.00371768 0.854936 0.695966 0 0.718075 0.838299 0 0.545211 0.876682 -0.00620753 0.48103 0.950846 0 0.309663 0.995913 0 0.0903176 0.999735 -0.00745595 -0.0217574 0.985354 0 -0.170524 0.922705 0 -0.385508 0.854918 -0.00745594 -0.51871 0.791486 0 -0.611187 0.635644 0 -0.771983 0.481029 -0.00620762 -0.876683 0.414176 0 -0.910197 0.201255 0 -0.979539 -0.0217579 -0.00371752 -0.999756 -0.0591246 0 -0.998251 0.486394 0 0.87374 0.486394 0 0.87374 0.817328 0 0.576172 0.817328 0 0.576172 0.986379 0 0.164491 0.986379 0 0.164491 0.960066 0 -0.279775 0.960066 0 -0.279775 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591246 0 -0.998251 -0.0591246 0 -0.998251 0.486394 0 0.87374 0.518721 0.00371763 0.854936 0.817324 -0.00310588 0.57617 0.8383 0 0.545209 0.950846 0 0.309663 0.986366 -0.00497636 0.164489 0.995913 0 0.0903207 0.985354 0 -0.170519 0.960051 -0.00560128 -0.279771 0.922703 0 -0.385512 0.791488 0 -0.611185 0.743591 -0.00497651 -0.668616 0.635641 0 -0.771985 0.379855 0 -0.925046 0.414175 -0.00371751 -0.91019 -0.0591243 0.00432396 -0.998241 -0.0217578 0 -0.999763 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 0.201252 0 -0.979539 0.201252 0 -0.979539 0.414179 0 -0.910196 0.414179 0 -0.910196 0.63564 0 -0.771986 0.63564 0 -0.771986 0.791488 0 -0.611185 0.791488 0 -0.611185 0.922703 0 -0.385511 0.922703 0 -0.385511 0.985354 0 -0.17052 0.985354 0 -0.17052 0.995913 0 0.0903206 0.995913 0 0.0903206 0.950846 0 0.309663 0.950846 0 0.309663 0.8383 0 0.545209 0.8383 0 0.545209 0.695966 0 0.718075 0.695966 0 0.718075 0.486393 0 0.87374 0.486393 0 0.87374 0.486394 0 0.87374 0.486394 0 0.87374 0.695966 0 0.718075 0.695966 0 0.718075 0.838299 0 0.54521 0.838299 0 0.54521 0.950846 0 0.309663 0.950846 0 0.309663 0.995913 0 0.0903176 0.995913 0 0.0903176 0.985354 0 -0.17052 0.985354 0 -0.17052 0.922705 0 -0.385508 0.922705 0 -0.385508 0.791486 0 -0.611187 0.791486 0 -0.611187 0.63564 0 -0.771986 0.63564 0 -0.771986 0.41418 0 -0.910195 0.41418 0 -0.910195 0.201255 0 -0.979539 0.201255 0 -0.979539 -0.0591246 0 -0.998251 -0.0591246 0 -0.998251 0.486395 0 0.873739 0.486395 0 0.873739 0.69595 0 0.71809 0.69595 0 0.71809 0.838301 0 0.545208 0.838301 0 0.545208 0.950845 0 0.309666 0.950845 0 0.309666 0.995913 0 0.0903169 0.995913 0 0.0903169 0.985354 0 -0.170522 0.985354 0 -0.170522 0.922705 0 -0.385507 0.922705 0 -0.385507 0.791487 0 -0.611187 0.791487 0 -0.611187 0.635644 0 -0.771982 0.635644 0 -0.771982 0.41418 0 -0.910195 0.41418 0 -0.910195 0.201253 0 -0.979539 0.201253 0 -0.979539 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 0.839783 0 0.542923 0.988806 0 -0.149206 0.0152409 0.219459 -0.975503 0.0559995 0.704005 -0.707984 -0.162011 0 -0.986789 -0.162011 0 -0.986789 -0.040316 0 -0.999187 -0.0217544 0.00912769 -0.999722 0.446762 0 -0.894653 0.355289 0 -0.934757 0.218849 0.71952 -0.659087 0.240025 0 -0.970767 0.117622 0 -0.993059 0.465395 0.252948 -0.848189 0.379274 0.70273 -0.601932 0.428585 0.60904 -0.667372 0.678791 0.607969 -0.411846 0.572335 0.749949 -0.331676 0.860812 0.242494 -0.447436 0.823488 0.0912308 -0.559951 0.802683 0 -0.596406 0.720079 0 -0.693893 0.720079 0 -0.693893 0.607576 0 -0.794262 0.960066 0 -0.279774 0.960066 0 -0.279774 0.914165 0 -0.405343 0.966417 0.242499 -0.0850399 0.660913 0.74995 -0.0277072 0.793783 0.607956 -0.0172753 0.857433 0 0.514595 0.848191 0.252939 0.465397 0.643262 0.702727 0.303955 0.919996 0 0.391929 0.980114 0 0.198437 0.980114 0 0.198437 0.999313 0 0.0370677 0.661522 0.474185 0.580979 0.538654 0.719518 0.438344 0.626826 0.599329 0.497889 0.817578 0.111032 0.565012 0.518704 0.00912185 0.854905 0.536898 0.219455 0.814604 0.427562 0.704008 0.567066 0.632683 0 0.774411 0.722559 0 0.691309 0.393457 0 0.919343 0.393457 0 0.919343 0.502771 0 0.86442 0.592009 -0.805828 -0.0128834 0.373093 -0.69475 0.614918 0.373093 -0.694749 0.614919 0.630567 -0.69475 0.345988 0.630568 -0.694748 0.345989 0.694339 -0.70672 0.135795 0.592007 -0.80583 -0.012884 -0.0156492 -0.694747 -0.719084 -0.0156493 -0.694748 -0.719083 0.345988 -0.694749 -0.630568 0.345988 -0.694749 -0.630568 0.614918 -0.69475 -0.373094 0.614921 -0.694746 -0.373095 0.687777 -0.706717 -0.165874 0.348269 -0.698079 0.625615 0.34827 -0.698075 0.625619 0.49229 -0.706861 0.507935 0.533539 -0.681291 0.501178 0.519137 -0.805828 0.284847 0.857043 -0.450667 -0.249753 0.671407 -0.598778 0.436667 0.656129 -0.723764 0.213685 0.804387 -0.58361 0.111178 0.708154 -0.703131 0.0642192 0.698939 -0.704879 -0.120956 0.654502 -0.704877 -0.273452 0.562798 -0.703128 -0.434591 0.649553 -0.48678 -0.58406 0.450095 -0.706117 -0.546638 0.271986 -0.698074 -0.662356 -0.0423348 -0.698073 -0.714774 -0.0423349 -0.698074 -0.714773 0.14236 -0.70686 -0.69288 0.346643 -0.54729 -0.761782 0.229566 -0.706718 0.669215 0.307161 -0.805831 0.50625 0.334612 -0.725764 0.601084 0.467776 -0.707093 0.530288 0.492285 -0.706861 0.50794 0.665101 -0.581214 0.468861 0.597958 -0.700861 0.388896 0.673291 -0.706116 0.219272 0.861628 -0.486778 0.143686 0.708161 -0.703124 0.0642222 0.698945 -0.704872 -0.120957 0.857049 -0.450654 -0.249754 0.654504 -0.704874 -0.273455 0.5628 -0.703125 -0.434594 0.649554 -0.486778 -0.584061 0.450095 -0.706117 -0.546639 0.271986 -0.698074 -0.662356 -0.0423348 -0.698073 -0.714774 -0.0423346 -0.698072 -0.714775 0.142362 -0.706858 -0.692882 0.346643 -0.54729 -0.761782 -0.0423342 -0.69807 -0.714777 -0.0423352 -0.698076 -0.714772 0.271986 -0.698075 -0.662355 0.271986 -0.698075 -0.662356 0.532436 -0.698075 -0.478752 0.532437 -0.698074 -0.478753 0.687432 -0.698074 -0.200326 0.687432 -0.698074 -0.200326 0.706272 -0.698074 0.117778 0.706273 -0.698074 0.117779 0.585229 -0.698073 0.412555 0.58523 -0.698071 0.412556 0.348272 -0.69807 0.625624 0.348271 -0.698073 0.62562 -0.0423347 -0.698077 -0.71477 -0.0423345 -0.698076 -0.714772 0.271985 -0.698076 -0.662355 0.271985 -0.698075 -0.662356 0.532435 -0.698076 -0.478752 0.532436 -0.698075 -0.478752 0.68743 -0.698076 -0.200325 0.687432 -0.698074 -0.200325 0.706274 -0.698073 0.117779 0.706273 -0.698074 0.117779 0.585229 -0.698073 0.412555 0.58523 -0.698071 0.412556 0.348272 -0.69807 0.625624 0.348271 -0.698073 0.625621 -0.0156495 -0.694748 -0.719083 -0.0156494 -0.694747 -0.719084 0.34599 -0.694746 -0.63057 0.345989 -0.694747 -0.63057 0.61492 -0.694747 -0.373095 0.61492 -0.694747 -0.373094 0.719085 -0.694746 -0.0156496 0.719086 -0.694745 -0.0156494 0.630571 -0.694745 0.345991 0.63057 -0.694747 0.345989 0.373095 -0.694747 0.61492 0.373095 -0.694745 0.614922 -0.0156493 -0.694747 -0.719084 -0.0156493 -0.694747 -0.719084 0.345989 -0.694748 -0.630568 0.345988 -0.694749 -0.630568 0.614917 -0.69475 -0.373094 0.614921 -0.694746 -0.373095 0.719085 -0.694746 -0.0156489 0.719082 -0.694749 -0.0156493 0.630568 -0.694748 0.345989 0.630567 -0.69475 0.345988 0.373094 -0.694749 0.614918 0.373095 -0.694746 0.614921 -0.0156495 -0.69475 -0.719081 -0.0156493 -0.694749 -0.719082 0.345989 -0.694748 -0.630569 0.345989 -0.694747 -0.63057 0.61492 -0.694747 -0.373095 0.61492 -0.694747 -0.373094 0.719085 -0.694746 -0.0156489 0.719082 -0.694749 -0.0156493 0.630568 -0.69475 0.345988 0.63057 -0.694747 0.345989 0.373095 -0.694747 0.61492 0.373095 -0.694745 0.614922 -0.0156489 -0.694746 -0.719085 -0.0156493 -0.694749 -0.719082 0.345988 -0.694748 -0.630569 0.345991 -0.694744 -0.630572 0.614922 -0.694745 -0.373095 0.61492 -0.694747 -0.373095 0.719083 -0.694748 -0.0156496 0.719084 -0.694747 -0.0156494 0.630569 -0.694748 0.345989 0.63057 -0.694747 0.345989 0.373095 -0.694747 0.61492 0.373095 -0.694745 0.614922 -0.16588 -0.706717 -0.687775 -0.0128845 -0.805831 -0.592005 0.373096 -0.694744 0.614924 0.373094 -0.69475 0.614918 0.630568 -0.694749 0.345989 0.630568 -0.694749 0.345989 0.719084 -0.694747 -0.0156494 0.719084 -0.694747 -0.0156493 0.614921 -0.694746 -0.373095 0.614922 -0.694745 -0.373095 0.345991 -0.694744 -0.630572 0.345992 -0.694742 -0.630574 0.135796 -0.706713 -0.694346 -0.0128825 -0.805825 -0.592013 0.348271 -0.698075 0.625618 0.348271 -0.698073 0.625621 0.492292 -0.706859 0.507937 0.665098 -0.581218 0.468861 0.597957 -0.700861 0.388898 0.673291 -0.706116 0.21927 0.861625 -0.486782 0.143685 0.708161 -0.703124 0.0642222 0.698945 -0.704872 -0.120957 0.857048 -0.450657 -0.249753 0.654505 -0.704873 -0.273453 0.543997 -0.700204 -0.462366 -0.0423356 -0.698073 -0.714774 -0.042336 -0.698075 -0.714772 0.142356 -0.706861 -0.692879 0.180781 -0.681288 -0.709341 0.259854 -0.778702 -0.571051 0.368359 -0.64313 -0.671339 0.438621 -0.723764 -0.532707 0.670502 -0.531366 -0.517762 0.562468 -0.81041 -0.163909 0.694704 -0.702599 -0.154082 0.706274 -0.698073 0.117778 0.706272 -0.698074 0.117778 0.585227 -0.698075 0.412554 0.585225 -0.698077 0.412553 0.34827 -0.698076 0.625618 0.34827 -0.698076 0.625619 -0.0423348 -0.698073 -0.714774 -0.0423352 -0.698076 -0.714772 0.271985 -0.698076 -0.662355 0.271984 -0.698077 -0.662354 0.532433 -0.698079 -0.478749 0.319395 -0.879499 -0.352801 0.688854 -0.592281 -0.417951 -0.0423349 -0.698075 -0.714772 -0.0423349 -0.698074 -0.714773 0.271986 -0.698074 -0.662357 0.271986 -0.698075 -0.662356 0.532436 -0.698075 -0.478752 0.532436 -0.698074 -0.478752 0.687432 -0.698074 -0.200325 0.687431 -0.698075 -0.200325 0.706272 -0.698075 0.117778 0.706272 -0.698074 0.117778 0.585227 -0.698074 0.412555 0.585228 -0.698073 0.412555 0.348271 -0.698073 0.625621 0.34827 -0.698075 0.625619 0.104239 -0.703808 0.702701 0.104239 -0.703803 0.702705 0.0454827 -0.698435 0.714227 0.0454823 -0.698432 0.714229 -0.263019 -0.698433 0.665592 -0.263019 -0.698433 0.665591 -0.521434 -0.698433 0.490203 -0.521433 -0.698433 0.490203 0.0571084 -0.699695 0.712156 0.0571085 -0.699695 0.712155 0.0721748 -0.701184 0.709318 0.0721748 -0.701184 0.709318 -0.185296 -0.701184 0.688481 -0.185296 -0.701184 0.688481 0.0746331 -0.701412 0.708837 0.0746331 -0.701412 0.708838 0.0354491 -0.697264 0.715937 0.035449 -0.697263 0.715939 -0.291436 -0.697263 0.654897 -0.291434 -0.697266 0.654894 -0.555598 -0.697266 0.452914 -0.555599 -0.697265 0.452915 0.518725 0 0.854941 0.482991 -0.11807 0.867628 0.833954 0.101688 0.542383 0.817328 0 0.576172 0.950845 0 0.309667 0.977272 0.135575 0.162971 0.995913 0 0.0903168 0.985354 0 -0.170522 0.948878 0.152219 -0.276515 0.922704 0 -0.385509 0.743601 0 -0.668624 0.77547 0.200163 -0.598816 0.635643 0 -0.771983 0.414176 0 -0.910197 0.378478 0.0850857 -0.921691 -0.0216447 -0.1017 -0.99458 -0.0591279 0 -0.99825 0.486394 0 0.87374 0.486394 0 0.87374 0.817328 0 0.576173 0.817328 0 0.576173 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279774 0.960066 0 -0.279774 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379854 0 -0.925046 0.379854 0 -0.925046 -0.059124 0 -0.998251 -0.059124 0 -0.998251 0.486396 0 0.873739 0.486396 0 0.873739 0.817327 0 0.576174 0.817327 0 0.576174 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279774 0.960066 0 -0.279774 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591251 0 -0.998251 -0.0591251 0 -0.998251 0.486395 0 0.873739 0.516035 0.101688 0.85051 0.695957 0 0.718084 0.8767 0 0.481038 0.815589 0.23119 0.530439 0.950847 0 0.309661 0.999763 0 -0.0217575 0.938225 0.335403 0.0850868 0.985354 0 -0.170523 0.922705 0 -0.385507 0.837522 0.200839 -0.508154 0.791488 0 -0.611185 0.63564 0 -0.771986 0.47418 0.168253 -0.864201 -0.059124 0 -0.998251 -0.0216447 0.10169 -0.994581 0.201253 0 -0.979539 0.414178 0 -0.910196 0.518723 0 0.854943 0.482992 -0.118061 0.867629 0.833954 0.101693 0.542383 0.817327 0 0.576174 0.950846 0 0.309664 0.977272 0.135574 0.16297 0.995913 0 0.0903168 0.985354 0 -0.170522 0.948878 0.152219 -0.276515 0.922704 0 -0.385509 0.743601 0 -0.668624 0.77547 0.200163 -0.598816 0.635643 0 -0.771983 0.414176 0 -0.910197 0.378475 0.0850938 -0.921692 -0.0216447 -0.10169 -0.994581 -0.059124 0 -0.998251 0.518723 0 0.854943 0.518723 0 0.854943 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217575 0.999763 0 -0.0217575 0.854942 0 -0.518724 0.854942 0 -0.518724 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217575 0 -0.999763 -0.0217575 0 -0.999763 0.486396 0 0.873739 0.486396 0 0.873739 0.817328 0 0.576173 0.817328 0 0.576173 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279774 0.960066 0 -0.279774 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591251 0 -0.998251 -0.0591251 0 -0.998251 0.486394 0 0.87374 0.486394 0 0.87374 0.817327 0 0.576173 0.817327 0 0.576173 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279774 0.960066 0 -0.279774 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591251 0 -0.998251 -0.0591251 0 -0.998251 0.486394 0 0.87374 0.486394 0 0.87374 0.817328 0 0.576173 0.817328 0 0.576173 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279773 0.960066 0 -0.279773 0.743599 0 -0.668626 0.743599 0 -0.668626 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.059124 0 -0.998251 -0.059124 0 -0.998251 0.518724 0 0.854942 0.518724 0 0.854942 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217576 0 -0.999763 -0.0217576 0 -0.999763 -0.0591246 0 -0.998251 -0.0591246 0 -0.998251 0.201257 0 -0.979539 0.201257 0 -0.979539 0.414178 0 -0.910196 0.414178 0 -0.910196 0.635642 0 -0.771984 0.635642 0 -0.771984 0.791488 0 -0.611185 0.791488 0 -0.611185 0.922705 0 -0.385508 0.922705 0 -0.385508 0.985354 0 -0.170522 0.985354 0 -0.170522 0.995913 0 0.0903147 0.995913 0 0.0903147 0.950845 0 0.309667 0.950845 0 0.309667 0.8383 0 0.54521 0.8383 0 0.54521 0.695961 0 0.718079 0.695961 0 0.718079 0.486394 0 0.87374 0.486394 0 0.87374 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 0.20126 0 -0.979538 0.20126 0 -0.979538 0.414178 0 -0.910196 0.414178 0 -0.910196 0.635641 0 -0.771985 0.635641 0 -0.771985 0.791487 0 -0.611186 0.791487 0 -0.611186 0.922704 0 -0.385509 0.922704 0 -0.385509 0.985354 0 -0.170522 0.985354 0 -0.170522 0.995913 0 0.090318 0.995913 0 0.090318 0.950846 0 0.309664 0.950846 0 0.309664 0.8383 0 0.545209 0.8383 0 0.545209 0.695955 0 0.718086 0.695955 0 0.718086 0.486395 0 0.873739 0.486395 0 0.873739 0.486393 0 0.87374 0.486393 0 0.87374 0.817328 0 0.576173 0.817328 0 0.576173 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279775 0.960066 0 -0.279775 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379856 0 -0.925046 0.379856 0 -0.925046 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.518724 0 0.854942 0.486204 -0.0279055 0.8734 0.838059 0.0239938 0.545052 0.817328 0 0.576173 0.950846 0 0.309665 0.98587 0.0321122 0.164405 0.995913 0 0.0903172 0.985354 0 -0.170521 0.959439 0.0361382 -0.279592 0.922704 0 -0.385509 0.791488 0 -0.611185 0.743216 0.0321125 -0.66828 0.63564 0 -0.771986 0.414178 0 -0.910196 0.379778 0.0200487 -0.92486 -0.0217518 -0.0239937 -0.999475 -0.0591247 0 -0.998251 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217581 0.999763 0 -0.0217581 0.854942 0 -0.518724 0.854942 0 -0.518724 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217577 0 -0.999763 -0.0217577 0 -0.999763 0.518725 0 0.854941 0.518725 0 0.854941 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854942 0 -0.518724 0.854942 0 -0.518724 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.518724 0 0.854942 0.518724 0 0.854942 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217581 0.999763 0 -0.0217581 0.854942 0 -0.518724 0.854942 0 -0.518724 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217577 0.999763 0 -0.0217577 0.854942 0 -0.518724 0.854942 0 -0.518724 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.021759 0 -0.999763 -0.021759 0 -0.999763 0.486394 0 0.873739 0.518575 -0.0239941 0.854695 0.695961 0 0.718079 0.838299 0 0.54521 0.875996 -0.040045 0.480653 0.950847 0 0.309661 0.995913 0 0.090318 0.998607 -0.0480813 -0.0217319 0.985354 0 -0.170522 0.922705 0 -0.385508 0.853953 -0.0480813 -0.518124 0.791487 0 -0.611186 0.63564 0 -0.771986 0.480654 -0.0400438 -0.875996 0.414179 0 -0.910195 0.201252 0 -0.97954 -0.0217527 -0.0239938 -0.999475 -0.0591258 0 -0.998251 0.518724 0 0.854942 0.486205 -0.0279052 0.873399 0.838059 0.0239941 0.545052 0.817328 0 0.576173 0.950845 0 0.309667 0.98587 0.0321129 0.164404 0.995913 0 0.0903149 0.985354 0 -0.170521 0.959439 0.0361381 -0.279591 0.922704 0 -0.385508 0.791488 0 -0.611185 0.743217 0.0321126 -0.66828 0.63564 0 -0.771986 0.414178 0 -0.910196 0.379779 0.0200485 -0.92486 -0.0217518 -0.0239937 -0.999475 -0.0591247 0 -0.998251 0.486394 0 0.873739 0.486394 0 0.873739 0.817328 0 0.576173 0.817328 0 0.576173 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279774 0.960066 0 -0.279774 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.059125 0 -0.998251 -0.059125 0 -0.998251 -0.293432 0 -0.95598 -0.468052 -0.00686624 -0.883674 -0.480613 0 -0.876933 0.146735 0 0.989176 0.146735 0 0.989176 0.249904 0 0.968271 0.063539 0.0204793 0.997769 0.011959 -0.0136553 0.999835 -0.367474 0.0143921 0.929923 -0.396134 -0.00719694 0.918165 -0.728568 0.00756422 0.684931 -0.735623 0 0.677391 0.104711 0 0.994503 0.104711 0 0.994503 0.20867 0 0.977986 0.0494116 0.0412482 0.997926 -0.0238684 0 0.999715 -0.231391 0 0.972861 -0.406366 0.0316634 0.913162 -0.472366 -0.0158423 0.88126 -0.774971 0.0179042 0.631744 -0.790309 0 0.612708 -0.449061 0 -0.893501 -0.442679 -0.00330537 -0.896674 -0.737944 0.0034334 -0.674853 -0.733119 0 -0.6801 -0.0156496 0.694747 -0.719084 -0.0156492 0.694747 -0.719084 0.345989 0.694747 -0.63057 0.305946 0.67405 -0.67235 0.450097 0.706116 -0.546638 0.614921 0.694747 -0.373095 0.593046 0.662253 -0.457949 0.654505 0.704873 -0.273454 0.698944 0.704873 -0.120957 0.728874 0.684464 -0.0158624 0.373095 0.694747 0.61492 0.373095 0.694747 0.61492 0.597957 0.700862 0.388896 0.63771 0.686215 0.349907 0.67329 0.706116 0.219274 0.708161 0.703125 0.0642213 -0.170522 0 -0.985354 -0.170522 0 -0.985354 0.0530155 0 -0.998594 0.0530155 0 -0.998594 0.273894 0 -0.96176 0.273894 0 -0.96176 0.481039 0 -0.876699 0.481039 0 -0.876699 0.664062 0 -0.747677 0.664062 0 -0.747677 0.813787 0 -0.581164 0.813787 0 -0.581164 0.922704 0 -0.385508 0.922704 0 -0.385508 0.985354 0 -0.170522 0.985354 0 -0.170522 0.998594 0 0.0530155 0.998594 0 0.0530155 0.96176 0 0.273894 0.96176 0 0.273894 0.876699 0 0.481039 0.876699 0 0.481039 0.747677 0 0.664062 0.747677 0 0.664062 0.581164 0 0.813787 0.581164 0 0.813787 0.385508 0 0.922704 0.385508 0 0.922704 0.273455 0.704871 0.654507 0.273454 0.704874 0.654504 0.412238 0.704874 0.577245 0.412238 0.704874 0.577245 0.515355 0.705904 0.48591 0.713632 0.298321 0.633825 0.565683 0.706952 0.424525 0.599003 0.706618 0.376678 0.870145 0.122046 0.477443 0.865336 0.170088 0.471448 0.708334 0.704875 0.0376056 0.682207 0.704875 0.194282 0.682206 0.704876 0.194282 0.642036 0.706771 0.297095 0.8246 0.364614 0.432541 0.977898 0.122787 -0.169231 0.703198 0.706625 -0.0787054 0.708334 0.704875 0.0376056 0.471042 0.704873 -0.530353 0.577246 0.704873 -0.412239 0.577245 0.704874 -0.412238 0.635396 0.706624 -0.311376 0.915722 0.122787 -0.382591 0.666408 0.70647 -0.238329 0.690115 0.706469 -0.156978 0.463151 0.3646 -0.807811 0.381927 0.706769 -0.595491 0.471041 0.704874 -0.530352 0.475057 0.21993 -0.852028 0.477626 0.118908 -0.870479 0.471805 0.165251 -0.866079 0.302878 0.706618 -0.639497 0.194282 0.704876 -0.682206 0.194283 0.70487 -0.682211 0.0376058 0.704871 -0.708338 0.0376058 0.70487 -0.708339 -0.156978 0.70647 -0.690115 -0.169232 0.122775 -0.977899 -0.0846633 0.681907 -0.726523 -0.0450239 0.7071 -0.705678 0.348271 0.698074 0.62562 0.348271 0.698074 0.62562 0.585228 0.698074 0.412555 0.585228 0.698074 0.412555 0.706273 0.698074 0.117779 0.706273 0.698074 0.117779 0.687432 0.698074 -0.200326 0.687432 0.698074 -0.200326 0.532437 0.698074 -0.478752 0.532437 0.698074 -0.478753 0.271986 0.698073 -0.662357 0.271986 0.698074 -0.662357 -0.0423343 0.698074 -0.714773 -0.0423348 0.698074 -0.714773 0.348272 0.698073 0.62562 0.348271 0.698074 0.62562 0.585227 0.698074 0.412555 0.585228 0.698074 0.412555 0.706273 0.698074 0.117778 0.706273 0.698074 0.117779 0.687432 0.698074 -0.200326 0.687432 0.698074 -0.200326 0.532437 0.698074 -0.478752 0.532437 0.698074 -0.478753 0.271986 0.698074 -0.662357 0.271986 0.698074 -0.662357 -0.0423351 0.698074 -0.714773 -0.0423351 0.698074 -0.714773 -0.0423354 0.698074 -0.714773 -0.0423343 0.698074 -0.714773 0.142357 0.70686 -0.692881 0.273524 0.693898 -0.666101 0.295432 0.700862 -0.64924 0.450094 0.706116 -0.54664 0.537267 0.691348 -0.483096 0.562801 0.703125 -0.434593 0.687432 0.698074 -0.200326 0.684663 0.670381 -0.286053 0.698944 0.704873 -0.120958 0.706273 0.698074 0.117779 0.729792 0.680459 0.0661842 0.673291 0.706116 0.21927 0.585228 0.698074 0.412555 0.348271 0.698074 0.62562 0.348271 0.698074 0.62562 0.492288 0.706859 0.50794 0.607032 0.689672 0.394798 -0.015649 0.694747 -0.719084 -0.0156492 0.694747 -0.719084 0.345989 0.694747 -0.63057 0.305946 0.674049 -0.67235 0.450097 0.706116 -0.546638 0.614921 0.694747 -0.373095 0.593046 0.662253 -0.457949 0.654505 0.704873 -0.273454 0.698944 0.704873 -0.120957 0.728874 0.684464 -0.0158624 0.373094 0.694747 0.614921 0.373096 0.694746 0.614921 0.597957 0.700862 0.388897 0.63771 0.686215 0.349907 0.673291 0.706116 0.219272 0.708161 0.703125 0.0642213 0.373094 0.694747 0.614921 0.373095 0.694747 0.614921 0.63057 0.694747 0.345989 0.63057 0.694747 0.345989 0.719084 0.694747 -0.0156492 0.719084 0.694747 -0.0156494 0.614921 0.694747 -0.373095 0.614921 0.694747 -0.373095 0.345989 0.694747 -0.63057 0.345989 0.694747 -0.63057 -0.0156492 0.694747 -0.719084 -0.015649 0.694747 -0.719084 0.348272 0.698073 0.62562 0.348271 0.698074 0.62562 0.585228 0.698074 0.412555 0.585227 0.698074 0.412555 0.706273 0.698074 0.117778 0.706273 0.698074 0.117779 0.687432 0.698074 -0.200326 0.687432 0.698074 -0.200326 0.532437 0.698074 -0.478752 0.532437 0.698074 -0.478753 0.271986 0.698074 -0.662357 0.271986 0.698074 -0.662357 -0.0423351 0.698074 -0.714773 -0.042335 0.698074 -0.714773 -0.176919 0.70694 -0.684789 -0.0414096 0.713779 -0.699146 -0.059476 0.711487 -0.700177 -0.129478 0.708059 -0.694182 0.218647 0.70694 0.672629 0.263709 0.708059 0.655065 0.325972 0.711487 0.622517 0.340656 0.713779 0.611942 0.422274 0.70554 0.56912 0.585228 0.698074 0.412555 0.585227 0.698074 0.412555 0.706273 0.698074 0.117778 0.706273 0.698074 0.117778 0.687432 0.698074 -0.200326 0.687432 0.698074 -0.200326 0.532437 0.698074 -0.478752 0.532437 0.698074 -0.478752 0.271986 0.698074 -0.662357 0.271986 0.698074 -0.662357 0.0504353 0.70554 -0.706873 0.348271 0.698074 0.62562 0.348271 0.698074 0.62562 0.585228 0.698074 0.412555 0.585227 0.698074 0.412555 0.706273 0.698074 0.117778 0.706273 0.698074 0.117778 0.687432 0.698074 -0.200325 0.687432 0.698074 -0.200325 0.532436 0.698074 -0.478753 0.532437 0.698074 -0.478753 0.271986 0.698074 -0.662357 0.271986 0.698074 -0.662357 -0.0423343 0.698074 -0.714773 -0.0423348 0.698074 -0.714773 -0.345323 0.698433 -0.626852 -0.345323 0.698433 -0.626852 -0.579402 0.698433 -0.4201 -0.579403 0.698433 -0.420101 -0.703143 0.698433 -0.133347 -0.703143 0.698433 -0.133347 -0.334404 0.699695 -0.631348 -0.334404 0.699695 -0.631349 -0.320172 0.701185 -0.637048 -0.320171 0.701185 -0.637048 -0.526142 0.701185 -0.481159 -0.526143 0.701184 -0.48116 -0.31784 0.701414 -0.637963 -0.31784 0.701413 -0.637963 -0.711929 0.697265 -0.0835428 -0.711929 0.697264 -0.0835427 -0.597624 0.697264 -0.395814 -0.597624 0.697264 -0.395814 -0.354705 0.697263 -0.622903 -0.507241 0.413795 -0.755963 -0.247376 0.706156 -0.663437 -0.289574 0.703805 -0.648695 -0.289574 0.703806 -0.648694 0.373096 0.694745 0.614922 0.373095 0.694747 0.61492 0.630569 0.694747 0.34599 0.630571 0.694745 0.34599 0.719086 0.694745 -0.0156496 0.719085 0.694746 -0.0156494 0.61492 0.694747 -0.373094 0.61492 0.694747 -0.373095 0.345989 0.694747 -0.63057 0.345989 0.694746 -0.63057 -0.0156496 0.694747 -0.719084 -0.0156493 0.694748 -0.719083 -0.0156493 0.69475 -0.719081 0.809399 0.322029 -0.491092 -0.0156495 0.694749 -0.719082 0.295432 0.700863 -0.649239 0.439498 0.406514 -0.800991 0.450094 0.706116 -0.54664 0.5628 0.703125 -0.434593 0.654505 0.704874 -0.273454 0.698945 0.704873 -0.120957 0.946507 0.322026 -0.0205987 0.373095 0.694746 0.614922 0.373096 0.694744 0.614923 0.597958 0.70086 0.388897 0.800994 0.406508 0.4395 0.673291 0.706115 0.219273 0.708161 0.703125 0.0642216 0.34827 0.698074 0.625621 0.348273 0.69807 0.625623 0.58523 0.698071 0.412556 0.585228 0.698073 0.412556 0.706273 0.698074 0.117778 0.706272 0.698074 0.117778 0.687432 0.698074 -0.200326 0.687432 0.698074 -0.200326 0.532437 0.698074 -0.478753 0.532436 0.698075 -0.478752 0.271986 0.698075 -0.662356 0.271986 0.698075 -0.662355 -0.0423339 0.698076 -0.714771 -0.0423355 0.69807 -0.714777 -0.0423346 0.698073 -0.714774 -0.0423349 0.698072 -0.714775 0.142362 0.706858 -0.692882 0.309106 0.581219 -0.752754 0.85705 0.450654 -0.249754 0.295432 0.700863 -0.64924 0.450095 0.706117 -0.546639 0.649554 0.486778 -0.584061 0.5628 0.703125 -0.434594 0.654504 0.704873 -0.273455 0.698945 0.704872 -0.120957 0.708161 0.703124 0.0642222 0.861628 0.486777 0.143686 0.673291 0.706116 0.219272 0.585228 0.698073 0.412555 0.348271 0.698074 0.625619 0.34827 0.698076 0.625618 0.492285 0.706861 0.50794 0.701613 0.547284 0.456311 -0.042335 0.698073 -0.714774 -0.0423348 0.698074 -0.714773 0.14236 0.70686 -0.69288 0.309106 0.581219 -0.752754 0.295432 0.700863 -0.64924 0.450095 0.706117 -0.546638 0.649553 0.48678 -0.58406 0.562798 0.703128 -0.434591 0.654501 0.704877 -0.273452 0.857043 0.450667 -0.249753 0.698939 0.704879 -0.120956 0.708154 0.703131 0.0642192 0.86163 0.486773 0.143687 0.67329 0.706116 0.219274 0.585229 0.698073 0.412555 0.348268 0.698079 0.625616 0.348271 0.698075 0.625619 0.49229 0.706861 0.507935 0.701608 0.547292 0.456309 0.373093 0.69475 0.614918 0.373094 0.694749 0.614919 0.630567 0.69475 0.345988 0.630568 0.694748 0.345989 0.719082 0.694749 -0.0156488 0.719085 0.694746 -0.0156494 0.614921 0.694746 -0.373095 0.614918 0.69475 -0.373093 0.345988 0.694749 -0.630568 0.345988 0.694749 -0.630568 -0.0156492 0.694748 -0.719083 -0.0156493 0.694747 -0.719084 -0.0156494 0.694746 -0.719085 0.8094 0.322026 -0.491092 -0.0156496 0.694745 -0.719086 0.295432 0.700862 -0.64924 0.4395 0.406509 -0.800993 0.450095 0.706114 -0.546641 0.562802 0.703122 -0.434595 0.654506 0.704872 -0.273454 0.698945 0.704873 -0.120957 0.946507 0.322026 -0.0205987 0.373094 0.694749 0.614919 0.373096 0.694745 0.614922 0.597959 0.700859 0.388897 0.800994 0.406508 0.4395 0.673293 0.706112 0.219275 0.708165 0.70312 0.0642203 0.373094 0.694748 0.614919 0.373095 0.694747 0.61492 0.63057 0.694747 0.345989 0.630569 0.694748 0.345989 0.719082 0.694749 -0.0156488 0.719085 0.694746 -0.0156494 0.614922 0.694745 -0.373095 0.614922 0.694745 -0.373095 0.345991 0.694744 -0.630572 0.345992 0.694742 -0.630574 -0.0156504 0.694742 -0.719089 -0.0156494 0.694746 -0.719085 0.373097 0.694743 0.614923 0.373093 0.69475 0.614918 0.630568 0.694749 0.345989 0.630568 0.694748 0.345989 0.719084 0.694747 -0.0156493 0.719084 0.694747 -0.0156494 0.614921 0.694746 -0.373095 0.614922 0.694745 -0.373095 0.345991 0.694744 -0.630572 0.345991 0.694742 -0.630574 -0.0156504 0.694742 -0.719089 -0.0156494 0.694746 -0.719085 0.373095 0.694745 0.614922 0.373094 0.694747 0.614921 0.63057 0.694747 0.345989 0.630569 0.694748 0.345989 0.719084 0.694747 -0.0156496 0.719083 0.694748 -0.0156493 0.61492 0.694747 -0.373095 0.614922 0.694745 -0.373096 0.34599 0.694744 -0.630573 0.345989 0.694748 -0.630569 -0.0156488 0.694749 -0.719082 -0.0156494 0.694746 -0.719085 0.373096 0.694745 0.614922 0.373095 0.694747 0.61492 0.63057 0.694747 0.345989 0.630567 0.69475 0.345988 0.719082 0.694749 -0.0156489 0.719085 0.694746 -0.0156494 0.61492 0.694747 -0.373094 0.61492 0.694747 -0.373095 0.345989 0.694747 -0.63057 0.345989 0.694748 -0.630569 -0.0156495 0.694749 -0.719082 -0.0156493 0.69475 -0.719081 0.373096 0.694746 0.614921 0.373094 0.694749 0.614919 0.630567 0.69475 0.345988 0.630569 0.694748 0.345989 0.719082 0.694749 -0.0156488 0.719085 0.694746 -0.0156494 0.614921 0.694746 -0.373096 0.614918 0.69475 -0.373093 0.345988 0.694749 -0.630568 0.345988 0.694748 -0.630568 -0.0156493 0.694747 -0.719084 -0.0156494 0.694747 -0.719084 -0.130651 -0.705398 -0.696667 -0.130651 -0.705398 -0.696666 0.00777238 -0.705398 -0.708768 0.00777229 -0.705394 -0.708772 0.145898 -0.705394 -0.693637 0.145897 -0.705397 -0.693635 0.278415 -0.705397 -0.651844 0.278413 -0.705402 -0.651839 0.400231 -0.705402 -0.584999 0.400231 -0.705401 -0.584999 0.506669 -0.705401 -0.495677 0.506675 -0.705392 -0.495683 0.593642 -0.705393 -0.387311 0.593634 -0.705403 -0.387305 0.657787 -0.705403 -0.264052 0.657791 -0.705399 -0.264053 0.696666 -0.705398 -0.130651 0.696659 -0.705405 -0.13065 0.708762 -0.705405 0.00777231 0.708766 -0.705401 0.00777222 0.693631 -0.705401 0.145896 0.693635 -0.705396 0.145897 0.651844 -0.705397 0.278415 0.651845 -0.705396 0.278416 0.585003 -0.705396 0.400234 0.585003 -0.705397 0.400234 0.495681 -0.705397 0.506672 0.495676 -0.705403 0.506668 0.387306 -0.705402 0.593634 0.38731 -0.705396 0.593639 0.264054 -0.705395 0.657794 0.264054 -0.705397 0.657792 -0.184324 0 -0.982866 -0.184324 0 -0.982866 0.0109654 0 -0.99994 0.0109654 0 -0.99994 0.205833 0 -0.978587 0.205833 0 -0.978587 0.392791 0 -0.919628 0.392791 0 -0.919628 0.564654 0 -0.825328 0.564654 0 -0.825328 0.714818 0 -0.699311 0.714818 0 -0.699311 0.837511 0 -0.54642 0.837511 0 -0.54642 0.92802 0 -0.37253 0.92802 0 -0.37253 0.982866 0 -0.184324 0.982866 0 -0.184324 0.99994 0 0.0109654 0.99994 0 0.0109654 0.978587 0 0.205833 0.978587 0 0.205833 0.919628 0 0.392791 0.919628 0 0.392791 0.825328 0 0.564654 0.825328 0 0.564654 0.699311 0 0.714818 0.699311 0 0.714818 0.54642 0 0.837512 0.54642 0 0.837512 0.37253 0 0.92802 0.37253 0 0.92802 0.218624 0.809687 0.54462 0.218624 0.809687 0.54462 0.320673 0.809687 0.491504 0.320673 0.809687 0.491504 0.410399 0.809687 0.419499 0.410399 0.809687 0.4195 0.484354 0.809687 0.331374 0.484354 0.809687 0.331374 0.539695 0.809687 0.230514 0.539695 0.809687 0.230514 0.574296 0.809687 0.120796 0.574296 0.809687 0.120796 0.586827 0.809687 0.00643517 0.586827 0.809687 0.00643515 0.576807 0.809687 -0.108173 0.576807 0.809687 -0.108173 0.54462 0.809687 -0.218624 0.54462 0.809687 -0.218624 0.491504 0.809687 -0.320673 0.491504 0.809686 -0.320673 0.4195 0.809686 -0.410399 0.4195 0.809687 -0.410399 0.331374 0.809687 -0.484354 0.331374 0.809687 -0.484354 0.230514 0.809687 -0.539695 0.230515 0.809686 -0.539695 0.120796 0.809687 -0.574296 0.120796 0.809687 -0.574296 0.00643517 0.809687 -0.586827 0.00643515 0.809687 -0.586827 -0.108173 0.809687 -0.576807 -0.108173 0.809687 -0.576807 -0.184324 0 -0.982866 -0.184324 0 -0.982866 0.010965 0 -0.99994 0.010965 0 -0.99994 0.205833 0 -0.978587 0.205833 0 -0.978587 0.392791 0 -0.919628 0.392791 0 -0.919628 0.564654 0 -0.825328 0.564654 0 -0.825328 0.714818 0 -0.699311 0.714818 0 -0.699311 0.837512 0 -0.54642 0.837512 0 -0.54642 0.92802 0 -0.37253 0.92802 0 -0.37253 0.982866 0 -0.184324 0.982866 0 -0.184324 0.99994 0 0.0109653 0.99994 0 0.0109653 0.978587 0 0.205833 0.978587 0 0.205833 0.919628 0 0.392791 0.919628 0 0.392791 0.825328 0 0.564654 0.825328 0 0.564654 0.699311 0 0.714818 0.699311 0 0.714818 0.54642 0 0.837512 0.54642 0 0.837512 0.37253 0 0.92802 0.37253 0 0.92802 0.135559 -0.705637 0.695485 0.135559 -0.705637 0.695486 0.00735515 -0.705636 0.708536 0.0073552 -0.705636 0.708536 -0.121092 -0.705636 0.69815 -0.121092 -0.705637 0.69815 -0.245534 -0.705637 0.664672 -0.245534 -0.705637 0.664673 -0.361856 -0.705637 0.609211 -0.361856 -0.705636 0.609211 -0.466208 -0.705636 0.533599 -0.466208 -0.705637 0.533598 -0.55514 -0.705637 0.440337 -0.55514 -0.705637 0.440337 0.253646 0.705903 0.661336 0.253648 0.705897 0.661342 0.359041 0.705897 0.610573 0.359039 0.705902 0.610568 0.454638 0.705903 0.543145 0.454641 0.705898 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261301 0.658353 0.705899 0.261299 0.692382 0.7059 0.149374 0.692381 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680025 0.705901 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.408239 0.578839 0.705896 -0.408236 0.50375 0.705896 -0.497942 0.503748 0.705899 -0.49794 0.41492 0.705898 -0.574064 0.41492 0.705899 -0.574063 0.314773 0.705898 -0.634528 0.314776 0.705893 -0.634532 0.206042 0.705893 -0.677688 0.206044 0.705886 -0.677695 0.091689 0.705886 -0.702366 0.0916867 0.7059 -0.702352 -0.0251671 0.7059 -0.707864 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141336 0.705889 -0.694078 -0.141334 -0.705901 -0.694067 -0.141335 -0.705898 -0.69407 -0.0386994 -0.706395 -0.706759 -0.0306585 -0.505439 -0.862318 0.0187439 -0.70334 -0.710606 0.0321879 -0.707114 -0.706366 0.0916866 -0.705904 -0.702348 0.091687 -0.705897 -0.702355 0.162224 -0.707044 -0.688311 0.250693 -0.507218 -0.82455 0.218712 -0.70639 -0.673185 0.366235 -0.707112 -0.604867 0.340413 -0.706813 -0.620108 0.409768 -0.387016 -0.82602 0.288747 -0.705496 -0.647226 0.261019 -0.707108 -0.657166 0.461888 -0.707108 -0.535404 0.427316 -0.706466 -0.564187 0.51518 -0.47596 -0.712778 0.38439 -0.699812 -0.602086 0.36807 -0.706699 -0.604236 0.53876 -0.684623 -0.490948 0.654499 -0.391257 -0.646953 0.587704 -0.544822 -0.598141 0.480025 -0.697898 -0.531521 0.745629 -0.409268 -0.525868 0.556648 -0.706929 -0.436343 0.54006 -0.707107 -0.456438 0.680023 -0.705903 -0.198166 0.655697 -0.707059 -0.264818 0.769153 -0.520699 -0.370506 0.632213 -0.70636 -0.318374 0.591007 -0.706657 -0.389034 0.707131 -0.707021 -0.009349 0.704274 -0.706359 -0.0710936 0.847785 -0.520694 -0.100688 0.695315 -0.707055 -0.128882 0.680027 -0.705899 -0.198168 0.850751 -0.524606 0.0317985 0.911397 -0.409276 0.0429904 0.703907 -0.706933 0.0690012 0.817019 -0.54483 0.188786 0.899584 -0.391258 0.194075 0.718157 -0.684623 0.124668 0.700711 -0.707111 0.094857 0.633842 -0.707111 0.313432 0.635053 -0.706697 0.31191 0.647655 -0.699814 0.301337 0.81744 -0.475951 0.324441 0.663502 -0.706468 0.246308 0.681112 -0.70702 0.190287 0.620248 -0.706812 0.340162 0.789361 -0.387014 0.476581 0.590041 -0.706809 0.390222 0.554719 -0.706777 0.439038 0.699698 -0.388436 0.599616 0.516521 -0.706842 0.483302 0.478802 -0.706881 0.520642 0.589833 -0.394403 0.704659 0.434266 -0.706729 0.558522 0.396425 -0.707049 0.585601 0.43738 -0.505441 0.743793 0.34703 -0.706398 0.616905 0.253646 -0.705901 0.661337 0.253646 -0.705901 0.661337 0.253643 0.705909 0.66133 0.253645 0.705903 0.661336 0.359038 0.705903 0.610567 0.359035 0.705909 0.610562 0.454634 0.705909 0.54314 0.454637 0.705904 0.543143 0.537834 0.705905 0.460905 0.537834 0.705905 0.460904 0.606361 0.705905 0.366093 0.606366 0.705899 0.366097 0.658353 0.705899 0.261299 0.658347 0.705906 0.261296 0.692375 0.705907 0.149372 0.692375 0.705907 0.149372 0.707518 0.705907 0.0333734 0.707529 0.705895 0.0333743 0.703373 0.705896 -0.0835363 0.703361 0.705907 -0.0835353 0.680018 0.705908 -0.198165 0.680015 0.705911 -0.198164 0.638125 0.70591 -0.307389 0.638137 0.705897 -0.307394 0.578838 0.705897 -0.408236 0.578833 0.705902 -0.408233 0.503745 0.705903 -0.497937 0.503744 0.705905 -0.497936 0.414916 0.705904 -0.574059 0.414916 0.705905 -0.574058 0.31477 0.705905 -0.634522 0.314773 0.7059 -0.634526 0.20604 0.7059 -0.677682 0.206042 0.705893 -0.677689 0.0916881 0.705892 -0.70236 0.0916859 0.705907 -0.702346 -0.0251669 0.705907 -0.707857 -0.025167 0.705901 -0.707864 -0.141334 0.705901 -0.694067 -0.141335 0.705896 -0.694072 -0.141335 -0.705896 -0.694071 -0.141334 -0.705901 -0.694067 -0.0251671 -0.705901 -0.707864 -0.0251667 -0.705907 -0.707858 0.0916863 -0.705907 -0.702345 0.0916877 -0.705892 -0.70236 0.206042 -0.705893 -0.677689 0.20604 -0.7059 -0.677682 0.314773 -0.7059 -0.634526 0.31477 -0.705905 -0.634522 0.414916 -0.705905 -0.574058 0.414916 -0.705905 -0.574058 0.503744 -0.705904 -0.497936 0.503746 -0.705902 -0.497938 0.578833 -0.705903 -0.408232 0.578838 -0.705897 -0.408236 0.638136 -0.705897 -0.307395 0.638125 -0.70591 -0.307389 0.680016 -0.705911 -0.198164 0.680019 -0.705908 -0.198165 0.703361 -0.705907 -0.083535 0.703373 -0.705896 -0.0835367 0.707529 -0.705895 0.033374 0.707518 -0.705907 0.0333738 0.692375 -0.705907 0.149372 0.692375 -0.705907 0.149372 0.658347 -0.705907 0.261296 0.658354 -0.705899 0.261299 0.606366 -0.705899 0.366096 0.606361 -0.705905 0.366093 0.537834 -0.705905 0.460904 0.537835 -0.705904 0.460905 0.454637 -0.705904 0.543143 0.454634 -0.705909 0.54314 0.359035 -0.705909 0.610562 0.359038 -0.705903 0.610567 0.253645 -0.705904 0.661335 0.253643 -0.705909 0.66133 0.253646 0.705903 0.661336 0.253648 0.705897 0.661342 0.359041 0.705897 0.610573 0.359039 0.705902 0.610568 0.454638 0.705903 0.543145 0.454641 0.705898 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261301 0.658353 0.705899 0.261299 0.692382 0.7059 0.149374 0.692381 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680025 0.705901 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.408239 0.578839 0.705896 -0.408236 0.50375 0.705896 -0.497942 0.503748 0.705899 -0.49794 0.41492 0.705898 -0.574064 0.41492 0.705899 -0.574063 0.314773 0.705898 -0.634528 0.314776 0.705893 -0.634532 0.206042 0.705893 -0.677688 0.206044 0.705886 -0.677695 0.091689 0.705886 -0.702366 0.0916867 0.7059 -0.702352 -0.0251671 0.7059 -0.707864 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141336 0.705889 -0.694078 -0.141336 -0.70589 -0.694078 -0.141335 -0.705894 -0.694073 -0.0251674 -0.705894 -0.70787 -0.025167 -0.7059 -0.707864 0.0916871 -0.7059 -0.702352 0.0916886 -0.705886 -0.702366 0.206044 -0.705886 -0.677695 0.206042 -0.705894 -0.677688 0.314775 -0.705893 -0.634532 0.314773 -0.705899 -0.634527 0.41492 -0.705899 -0.574063 0.41492 -0.705899 -0.574063 0.503749 -0.705898 -0.497941 0.50375 -0.705896 -0.497942 0.578839 -0.705896 -0.408236 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680025 -0.705901 -0.198167 0.703368 -0.705901 -0.0835357 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692381 -0.705901 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.65836 -0.705892 0.261302 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454638 -0.705902 0.543145 0.359038 -0.705902 0.610568 0.359041 -0.705897 0.610573 0.253648 -0.705897 0.661341 0.253646 -0.705902 0.661336 0.253646 0.705903 0.661336 0.253648 0.705897 0.661342 0.359041 0.705897 0.610573 0.359039 0.705902 0.610568 0.454638 0.705903 0.543145 0.454641 0.705898 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261301 0.658353 0.705899 0.261299 0.692382 0.7059 0.149374 0.692381 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680025 0.705901 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.408239 0.578839 0.705896 -0.408236 0.50375 0.705896 -0.497942 0.503748 0.705899 -0.49794 0.41492 0.705898 -0.574064 0.41492 0.705899 -0.574063 0.314773 0.705898 -0.634528 0.314776 0.705893 -0.634532 0.206042 0.705893 -0.677688 0.206044 0.705886 -0.677695 0.091689 0.705886 -0.702366 0.0916867 0.7059 -0.702352 -0.0251671 0.7059 -0.707864 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141336 0.705889 -0.694078 -0.141336 -0.70589 -0.694078 -0.141335 -0.705894 -0.694073 -0.0251674 -0.705894 -0.70787 -0.025167 -0.7059 -0.707864 0.0916871 -0.7059 -0.702352 0.0916886 -0.705886 -0.702366 0.206044 -0.705886 -0.677695 0.206042 -0.705894 -0.677688 0.314775 -0.705893 -0.634532 0.314773 -0.705899 -0.634527 0.41492 -0.705899 -0.574063 0.41492 -0.705899 -0.574063 0.503749 -0.705898 -0.497941 0.50375 -0.705896 -0.497942 0.578839 -0.705896 -0.408236 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680025 -0.705901 -0.198167 0.703368 -0.705901 -0.0835357 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692381 -0.705901 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.65836 -0.705892 0.261302 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454638 -0.705902 0.543145 0.359038 -0.705902 0.610568 0.359041 -0.705897 0.610573 0.253648 -0.705897 0.661341 0.253646 -0.705902 0.661336 0.253646 0.705903 0.661336 0.253648 0.705897 0.661342 0.359041 0.705897 0.610573 0.359039 0.705902 0.610568 0.454638 0.705903 0.543145 0.454641 0.705898 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261301 0.658353 0.705899 0.261299 0.692382 0.7059 0.149374 0.692381 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680025 0.705901 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.408239 0.578839 0.705896 -0.408236 0.50375 0.705896 -0.497942 0.503748 0.705899 -0.49794 0.41492 0.705898 -0.574064 0.41492 0.705899 -0.574063 0.314773 0.705898 -0.634528 0.314776 0.705893 -0.634532 0.206042 0.705893 -0.677688 0.206044 0.705886 -0.677695 0.091689 0.705886 -0.702366 0.0916867 0.7059 -0.702352 -0.0251671 0.7059 -0.707864 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141336 0.705889 -0.694078 -0.141336 -0.70589 -0.694078 -0.141335 -0.705894 -0.694073 -0.0251674 -0.705894 -0.70787 -0.025167 -0.7059 -0.707864 0.0916871 -0.7059 -0.702352 0.0916886 -0.705886 -0.702366 0.206044 -0.705886 -0.677695 0.206042 -0.705894 -0.677688 0.314775 -0.705893 -0.634532 0.314773 -0.705899 -0.634527 0.41492 -0.705899 -0.574063 0.41492 -0.705899 -0.574063 0.503749 -0.705898 -0.497941 0.50375 -0.705896 -0.497942 0.578839 -0.705896 -0.408236 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680025 -0.705901 -0.198167 0.703368 -0.705901 -0.0835357 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692381 -0.705901 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.65836 -0.705892 0.261302 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454638 -0.705902 0.543145 0.359038 -0.705902 0.610568 0.359041 -0.705897 0.610573 0.253648 -0.705897 0.661341 0.253646 -0.705902 0.661336 0.253646 0.705903 0.661336 0.253648 0.705897 0.661342 0.359041 0.705897 0.610573 0.359039 0.705902 0.610568 0.454638 0.705903 0.543145 0.454641 0.705898 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261301 0.658353 0.705899 0.261299 0.692382 0.7059 0.149374 0.692381 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680025 0.705901 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.408239 0.578839 0.705896 -0.408236 0.50375 0.705896 -0.497942 0.503748 0.705899 -0.49794 0.41492 0.705898 -0.574064 0.41492 0.705899 -0.574063 0.314773 0.705898 -0.634528 0.314776 0.705893 -0.634532 0.206042 0.705893 -0.677688 0.206044 0.705886 -0.677695 0.091689 0.705886 -0.702366 0.0916867 0.7059 -0.702352 -0.0251671 0.7059 -0.707864 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141336 0.705889 -0.694078 -0.141336 -0.70589 -0.694078 -0.141335 -0.705894 -0.694073 -0.0251674 -0.705894 -0.70787 -0.025167 -0.7059 -0.707864 0.0916871 -0.7059 -0.702352 0.0916886 -0.705886 -0.702366 0.206044 -0.705886 -0.677695 0.206042 -0.705894 -0.677688 0.314775 -0.705893 -0.634532 0.314773 -0.705899 -0.634527 0.41492 -0.705899 -0.574063 0.41492 -0.705899 -0.574063 0.503749 -0.705898 -0.497941 0.50375 -0.705896 -0.497942 0.578839 -0.705896 -0.408236 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680025 -0.705901 -0.198167 0.703368 -0.705901 -0.0835357 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692381 -0.705901 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.65836 -0.705892 0.261302 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454638 -0.705902 0.543145 0.359038 -0.705902 0.610568 0.359041 -0.705897 0.610573 0.253648 -0.705897 0.661341 0.253646 -0.705902 0.661336 0.253646 0.705903 0.661336 0.253648 0.705897 0.661342 0.359041 0.705897 0.610573 0.359039 0.705902 0.610568 0.454638 0.705903 0.543145 0.454641 0.705898 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261301 0.658353 0.705899 0.261299 0.692382 0.7059 0.149374 0.692381 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680025 0.705901 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.408239 0.578839 0.705896 -0.408236 0.50375 0.705896 -0.497942 0.503748 0.705899 -0.49794 0.41492 0.705898 -0.574064 0.41492 0.705899 -0.574063 0.314773 0.705898 -0.634528 0.314776 0.705893 -0.634532 0.206042 0.705893 -0.677688 0.206044 0.705886 -0.677695 0.091689 0.705886 -0.702366 0.0916867 0.7059 -0.702352 -0.0251671 0.7059 -0.707864 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141336 0.705889 -0.694078 -0.141336 -0.70589 -0.694078 -0.141335 -0.705894 -0.694073 -0.0251674 -0.705894 -0.70787 -0.025167 -0.7059 -0.707864 0.0916871 -0.7059 -0.702352 0.0916886 -0.705886 -0.702366 0.206044 -0.705886 -0.677695 0.206042 -0.705894 -0.677688 0.314775 -0.705893 -0.634532 0.314773 -0.705899 -0.634527 0.41492 -0.705899 -0.574063 0.41492 -0.705899 -0.574063 0.503749 -0.705898 -0.497941 0.50375 -0.705896 -0.497942 0.578839 -0.705896 -0.408236 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680025 -0.705901 -0.198167 0.703368 -0.705901 -0.0835357 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692381 -0.705901 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.65836 -0.705892 0.261302 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454638 -0.705902 0.543145 0.359038 -0.705902 0.610568 0.359041 -0.705897 0.610573 0.253648 -0.705897 0.661341 0.253646 -0.705902 0.661336 0.253646 0.705903 0.661336 0.253648 0.705897 0.661342 0.359041 0.705897 0.610573 0.359039 0.705902 0.610568 0.454638 0.705903 0.543145 0.454641 0.705898 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261301 0.658353 0.705899 0.261299 0.692382 0.7059 0.149374 0.692381 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680025 0.705901 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.408239 0.578839 0.705896 -0.408236 0.50375 0.705896 -0.497942 0.503748 0.705899 -0.49794 0.41492 0.705898 -0.574064 0.41492 0.705899 -0.574063 0.314773 0.705898 -0.634528 0.314776 0.705893 -0.634532 0.206042 0.705893 -0.677688 0.206044 0.705886 -0.677695 0.091689 0.705886 -0.702366 0.0916867 0.7059 -0.702352 -0.0251671 0.7059 -0.707864 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141336 0.705889 -0.694078 -0.141336 -0.70589 -0.694078 -0.141335 -0.705894 -0.694073 -0.0251674 -0.705894 -0.70787 -0.025167 -0.7059 -0.707864 0.0916871 -0.7059 -0.702352 0.0916886 -0.705886 -0.702366 0.206044 -0.705886 -0.677695 0.206042 -0.705894 -0.677688 0.314775 -0.705893 -0.634532 0.314773 -0.705899 -0.634527 0.41492 -0.705899 -0.574063 0.41492 -0.705899 -0.574063 0.503749 -0.705898 -0.497941 0.50375 -0.705896 -0.497942 0.578839 -0.705896 -0.408236 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680025 -0.705901 -0.198167 0.703368 -0.705901 -0.0835357 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692381 -0.705901 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.65836 -0.705892 0.261302 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454638 -0.705902 0.543145 0.359038 -0.705902 0.610568 0.359041 -0.705897 0.610573 0.253648 -0.705897 0.661341 0.253646 -0.705902 0.661336 0.253646 0.705903 0.661336 0.253648 0.705897 0.661342 0.359041 0.705897 0.610573 0.359039 0.705902 0.610568 0.454638 0.705903 0.543145 0.454641 0.705898 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261301 0.658353 0.705899 0.261299 0.692382 0.7059 0.149374 0.692381 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680025 0.705901 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.408239 0.578839 0.705896 -0.408236 0.50375 0.705896 -0.497942 0.503748 0.705899 -0.49794 0.41492 0.705898 -0.574064 0.41492 0.705899 -0.574063 0.314773 0.705898 -0.634528 0.314776 0.705893 -0.634532 0.206042 0.705893 -0.677688 0.206044 0.705886 -0.677695 0.091689 0.705886 -0.702366 0.0916867 0.7059 -0.702352 -0.0251671 0.7059 -0.707864 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141336 0.705889 -0.694078 -0.141336 -0.70589 -0.694078 -0.141335 -0.705894 -0.694073 -0.0251674 -0.705894 -0.70787 -0.025167 -0.7059 -0.707864 0.0916871 -0.7059 -0.702352 0.0916886 -0.705886 -0.702366 0.206044 -0.705886 -0.677695 0.206042 -0.705894 -0.677688 0.314775 -0.705893 -0.634532 0.314773 -0.705899 -0.634527 0.41492 -0.705899 -0.574063 0.41492 -0.705899 -0.574063 0.503749 -0.705898 -0.497941 0.50375 -0.705896 -0.497942 0.578839 -0.705896 -0.408236 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680025 -0.705901 -0.198167 0.703368 -0.705901 -0.0835357 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692381 -0.705901 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.65836 -0.705892 0.261302 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454638 -0.705902 0.543145 0.359038 -0.705902 0.610568 0.359041 -0.705897 0.610573 0.253648 -0.705897 0.661341 0.253646 -0.705902 0.661336 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355306 0 -0.999369 -0.0355306 0 -0.999369 0.129444 0 -0.991587 0.129444 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444399 0 -0.895829 0.444399 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900923 0 -0.43398 0.900923 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.047118 0.998889 0 0.047118 0.977511 0 0.210886 0.977511 0 0.210886 0.929468 0 0.368904 0.929468 0 0.368904 0.856071 0 0.516858 0.856071 0 0.516858 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355306 0 -0.999369 -0.0355306 0 -0.999369 0.129444 0 -0.991587 0.129444 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444399 0 -0.895829 0.444399 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900923 0 -0.43398 0.900923 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.047118 0.998889 0 0.047118 0.977511 0 0.210886 0.977511 0 0.210886 0.929468 0 0.368904 0.929468 0 0.368904 0.856071 0 0.516858 0.856071 0 0.516858 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355306 0 -0.999369 -0.0355306 0 -0.999369 0.129444 0 -0.991587 0.129444 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444399 0 -0.895829 0.444399 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900923 0 -0.43398 0.900923 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.047118 0.998889 0 0.047118 0.977511 0 0.210886 0.977511 0 0.210886 0.929468 0 0.368904 0.929468 0 0.368904 0.856071 0 0.516858 0.856071 0 0.516858 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355306 0 -0.999369 -0.0355306 0 -0.999369 0.129444 0 -0.991587 0.129444 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444399 0 -0.895829 0.444399 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900923 0 -0.43398 0.900923 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.047118 0.998889 0 0.047118 0.977511 0 0.210886 0.977511 0 0.210886 0.929468 0 0.368904 0.929468 0 0.368904 0.856071 0 0.516858 0.856071 0 0.516858 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355306 0 -0.999369 -0.0355306 0 -0.999369 0.129444 0 -0.991587 0.129444 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444399 0 -0.895829 0.444399 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900923 0 -0.43398 0.900923 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.047118 0.998889 0 0.047118 0.977511 0 0.210886 0.977511 0 0.210886 0.929468 0 0.368904 0.929468 0 0.368904 0.856071 0 0.516858 0.856071 0 0.516858 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355306 0 -0.999369 -0.0355306 0 -0.999369 0.129444 0 -0.991587 0.129444 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444399 0 -0.895829 0.444399 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900923 0 -0.43398 0.900923 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.047118 0.998889 0 0.047118 0.977511 0 0.210886 0.977511 0 0.210886 0.929468 0 0.368904 0.929468 0 0.368904 0.856071 0 0.516858 0.856071 0 0.516858 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355306 0 -0.999369 -0.0355306 0 -0.999369 0.129444 0 -0.991587 0.129444 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444399 0 -0.895829 0.444399 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900923 0 -0.43398 0.900923 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.047118 0.998889 0 0.047118 0.977511 0 0.210886 0.977511 0 0.210886 0.929468 0 0.368904 0.929468 0 0.368904 0.856071 0 0.516858 0.856071 0 0.516858 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355306 0 -0.999369 -0.0355306 0 -0.999369 0.129444 0 -0.991587 0.129444 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444399 0 -0.895829 0.444399 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900923 0 -0.43398 0.900923 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.047118 0.998889 0 0.047118 0.977511 0 0.210886 0.977511 0 0.210886 0.929468 0 0.368904 0.929468 0 0.368904 0.856071 0 0.516858 0.856071 0 0.516858 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 0.253646 0.705903 0.661336 0.253648 0.705897 0.661342 0.359041 0.705897 0.610573 0.359039 0.705902 0.610568 0.454638 0.705903 0.543145 0.454641 0.705898 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261301 0.658353 0.705899 0.261299 0.692382 0.7059 0.149374 0.692381 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680025 0.705901 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.408239 0.578839 0.705896 -0.408236 0.50375 0.705896 -0.497942 0.503748 0.705899 -0.49794 0.41492 0.705898 -0.574064 0.41492 0.705899 -0.574063 0.314773 0.705898 -0.634528 0.314776 0.705893 -0.634532 0.206042 0.705893 -0.677688 0.206044 0.705886 -0.677695 0.091689 0.705886 -0.702366 0.0916867 0.7059 -0.702352 -0.0251671 0.7059 -0.707864 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141336 0.705889 -0.694078 -0.141336 -0.70589 -0.694078 -0.141335 -0.705894 -0.694073 -0.0251674 -0.705894 -0.70787 -0.025167 -0.7059 -0.707864 0.0916871 -0.7059 -0.702352 0.0916886 -0.705886 -0.702366 0.206044 -0.705886 -0.677695 0.206042 -0.705894 -0.677688 0.314775 -0.705893 -0.634532 0.314773 -0.705899 -0.634527 0.41492 -0.705899 -0.574063 0.41492 -0.705899 -0.574063 0.503749 -0.705898 -0.497941 0.50375 -0.705896 -0.497942 0.578839 -0.705896 -0.408236 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680025 -0.705901 -0.198167 0.703368 -0.705901 -0.0835357 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692381 -0.705901 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.65836 -0.705892 0.261302 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454638 -0.705902 0.543145 0.359038 -0.705902 0.610568 0.359041 -0.705897 0.610573 0.253648 -0.705897 0.661341 0.253646 -0.705902 0.661336 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355306 0 -0.999369 -0.0355306 0 -0.999369 0.129444 0 -0.991587 0.129444 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444399 0 -0.895829 0.444399 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900923 0 -0.43398 0.900923 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.047118 0.998889 0 0.047118 0.977511 0 0.210886 0.977511 0 0.210886 0.929468 0 0.368904 0.929468 0 0.368904 0.856071 0 0.516858 0.856071 0 0.516858 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.270241 -0.258819 -0.927352 -0.270241 -0.258821 -0.927352 -0.197829 -0.707112 -0.678864 -0.197829 -0.707112 -0.678864 -0.0724133 -0.965924 -0.248492 -0.0724133 -0.965924 -0.248492 0.0724133 -0.965924 0.248492 0.0724133 -0.965924 0.248492 0.197829 -0.707112 0.678864 0.197829 -0.707112 0.678864 0.270241 -0.258821 0.927352 0.270241 -0.258819 0.927352 -0.853459 -0.510202 0.106306 -0.919703 -0.3735 -0.121013 -0.957953 -0.136708 -0.252265 -0.672469 -0.136705 0.727391 -0.710718 -0.373498 0.596138 -0.776962 -0.510203 0.368814 -0.270241 -0.258818 -0.927353 -0.270241 -0.258818 -0.927353 -0.197829 -0.707111 -0.678865 -0.197829 -0.707111 -0.678865 -0.0724132 -0.965924 -0.248491 -0.0724131 -0.965924 -0.248491 0.0724133 -0.965924 0.248492 0.0724134 -0.965923 0.248492 0.197829 -0.707113 0.678863 0.197829 -0.707113 0.678863 0.270241 -0.258818 0.927353 0.270241 -0.258818 0.927353 -0.853459 -0.510202 0.106306 -0.919704 -0.373497 -0.121017 -0.957952 -0.136708 -0.252268 -0.672469 -0.136708 0.72739 -0.710717 -0.3735 0.596137 -0.77696 -0.510202 0.368819 0.270241 -0.258821 0.927352 0.270241 -0.258818 0.927353 0.197829 -0.707112 0.678864 0.197829 -0.707111 0.678865 0.0724132 -0.965924 0.248491 0.0724132 -0.965924 0.248491 -0.0724134 -0.965923 -0.248492 -0.0724134 -0.965923 -0.248492 -0.197828 -0.707114 -0.678863 -0.197828 -0.707114 -0.678863 -0.270241 -0.258818 -0.927353 -0.270241 -0.258818 -0.927353 0.853459 -0.510202 -0.106306 0.919703 -0.3735 0.121013 0.957953 -0.136708 0.252265 0.672469 -0.136708 -0.72739 0.710717 -0.373496 -0.59614 0.776962 -0.510202 -0.368814 0.270241 -0.258819 0.927352 0.270241 -0.258819 0.927352 0.197829 -0.707112 0.678864 0.197829 -0.707112 0.678864 0.0724133 -0.965924 0.248492 0.0724132 -0.965924 0.248491 -0.0724132 -0.965924 -0.248491 -0.0724133 -0.965924 -0.248492 -0.197829 -0.707112 -0.678864 -0.197829 -0.707112 -0.678864 -0.270241 -0.258819 -0.927352 -0.270241 -0.258819 -0.927352 0.853459 -0.510202 -0.106306 0.919704 -0.373497 0.121017 0.957952 -0.136708 0.252268 0.672469 -0.136709 -0.72739 0.710716 -0.373499 -0.596138 0.77696 -0.510202 -0.368818 0.373098 0.694746 0.61492 0.373095 0.694747 0.61492 0.630569 0.694747 0.345989 0.630572 0.694746 0.345988 0.719085 0.694746 -0.0156448 0.719087 0.694744 -0.0156479 0.614922 0.694744 -0.373097 0.614922 0.694745 -0.373096 0.34599 0.694746 -0.630571 0.345991 0.694746 -0.63057 -0.0156494 0.694746 -0.719085 -0.0156493 0.694746 -0.719085 0.518728 0 0.85494 0.518728 0 0.85494 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217513 0.999763 0 -0.0217513 0.85494 0 -0.518726 0.85494 0 -0.518726 0.48104 0 -0.876699 0.48104 0 -0.876699 -0.0217577 0 -0.999763 -0.0217577 0 -0.999763 -0.0156493 -0.694748 -0.719083 -0.0156492 -0.694748 -0.719083 0.345989 -0.694748 -0.630569 0.34599 -0.694748 -0.630569 0.614919 -0.694747 -0.373096 0.614921 -0.694746 -0.373095 0.719085 -0.694746 -0.0156448 0.719084 -0.694747 -0.0156478 0.630569 -0.694747 0.345989 0.630569 -0.694749 0.345986 0.373096 -0.694749 0.614917 0.373095 -0.694748 0.61492 -0.0156505 0.694746 -0.719085 -0.0156488 0.694747 -0.719084 0.345989 0.694746 -0.630571 0.311021 0.66038 -0.683494 0.450093 0.706116 -0.546641 0.614921 0.694746 -0.373094 0.607756 0.640617 -0.4693 0.654505 0.704875 -0.273451 0.69894 0.704875 -0.120969 0.739321 0.673161 -0.0160882 0.373092 0.694747 0.614922 0.373093 0.694746 0.614922 0.597957 0.700862 0.388896 0.645315 0.676903 0.354077 0.673291 0.706115 0.219272 0.708161 0.703124 0.0642245 0.51872 0 0.854944 0.48639 -0.00224012 0.873739 0.838299 0.00192594 0.545208 0.817329 0 0.576172 0.950846 0 0.309664 0.986375 0.00257819 0.164492 0.995913 0 0.0903212 0.985351 0 -0.17054 0.96006 0.00290155 -0.279781 0.922706 0 -0.385505 0.791493 0 -0.611179 0.7436 0.00257838 -0.668619 0.635639 0 -0.771987 0.41418 0 -0.910195 0.379854 0.00160923 -0.925045 -0.021757 -0.00192597 -0.999761 -0.0591236 0 -0.998251 -0.042334 -0.698075 -0.714772 -0.0423357 -0.698076 -0.714771 0.271985 -0.698076 -0.662355 0.271988 -0.698075 -0.662355 0.532439 -0.698073 -0.478751 0.532432 -0.698077 -0.478754 0.687427 -0.698078 -0.20033 0.687432 -0.698074 -0.200324 0.706272 -0.698074 0.117781 0.706272 -0.698074 0.11778 0.585228 -0.698074 0.412554 0.585228 -0.698075 0.412552 0.348268 -0.698075 0.62562 0.348268 -0.698075 0.62562 0.373096 0.694748 0.614919 0.373094 0.694749 0.614919 0.630569 0.694747 0.34599 0.630571 0.694746 0.345989 0.719086 0.694745 -0.015649 0.719086 0.694745 -0.0156505 0.614922 0.694745 -0.373096 0.614922 0.694746 -0.373093 0.34599 0.694747 -0.630569 0.345988 0.694745 -0.630572 -0.015653 0.694745 -0.719086 -0.0156478 0.694748 -0.719083 0.518727 0 0.85494 0.518727 0 0.85494 0.876699 0 0.48104 0.876699 0 0.48104 0.999763 0 -0.0217573 0.999763 0 -0.0217573 0.854941 0 -0.518725 0.854941 0 -0.518725 0.48104 0 -0.876699 0.48104 0 -0.876699 -0.0217628 0 -0.999763 -0.0217628 0 -0.999763 -0.0156529 -0.69475 -0.719081 -0.0156478 -0.694747 -0.719084 0.34599 -0.694746 -0.63057 0.345986 -0.694749 -0.63057 0.614919 -0.694748 -0.373094 0.614922 -0.694747 -0.373093 0.719085 -0.694746 -0.015649 0.719084 -0.694747 -0.0156505 0.630569 -0.694747 0.34599 0.630569 -0.694749 0.345987 0.373095 -0.694751 0.614916 0.373094 -0.69475 0.614918 -0.0423348 -0.698076 -0.714771 -0.0423351 -0.698077 -0.71477 0.271986 -0.698076 -0.662355 0.271985 -0.698077 -0.662354 0.532433 -0.698078 -0.478751 0.532437 -0.698074 -0.478752 0.687433 -0.698073 -0.200326 0.687428 -0.698077 -0.200326 0.706269 -0.698077 0.117781 0.706264 -0.698083 0.117777 0.585222 -0.698082 0.412548 0.585227 -0.698074 0.412556 0.34827 -0.698075 0.62562 0.34827 -0.698076 0.625619 -0.0591249 0 -0.998251 -0.0591249 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.743599 0 -0.668626 0.743599 0 -0.668626 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986378 0 0.164493 0.986378 0 0.164493 0.81733 0 0.57617 0.81733 0 0.57617 0.486393 0 0.87374 0.486393 0 0.87374 -0.0156488 -0.694751 -0.71908 -0.0156488 -0.694751 -0.71908 0.345988 -0.694752 -0.630565 0.345986 -0.694754 -0.630564 0.614913 -0.694754 -0.373093 0.614922 -0.694746 -0.373094 0.719085 -0.694746 -0.0156489 0.71908 -0.694751 -0.0156507 0.630567 -0.69475 0.345988 0.630566 -0.694752 0.345986 0.373094 -0.69475 0.614918 0.373094 -0.694746 0.614922 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.85494 0 -0.518727 0.85494 0 -0.518727 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 -0.0423341 -0.698073 -0.714774 -0.042336 -0.698078 -0.714769 0.271984 -0.698077 -0.662354 0.271984 -0.698077 -0.662354 0.532433 -0.698078 -0.47875 0.532437 -0.698075 -0.478751 0.687432 -0.698074 -0.200325 0.687432 -0.698074 -0.200325 0.706274 -0.698073 0.117779 0.706272 -0.698074 0.117778 0.585227 -0.698075 0.412555 0.585226 -0.698076 0.412553 0.348271 -0.698075 0.625619 0.348271 -0.698075 0.625619 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379854 0 -0.925046 0.379854 0 -0.925046 0.743599 0 -0.668625 0.743599 0 -0.668625 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.16449 0.986379 0 0.16449 0.817328 0 0.576173 0.817328 0 0.576173 0.486395 0 0.873739 0.486395 0 0.873739 -0.0156492 -0.694749 -0.719082 -0.0156493 -0.69475 -0.719081 0.345988 -0.694751 -0.630566 0.345988 -0.694751 -0.630566 0.614915 -0.694752 -0.373093 0.614921 -0.694747 -0.373094 0.719085 -0.694746 -0.0156489 0.71908 -0.694751 -0.0156507 0.630566 -0.694751 0.345988 0.630565 -0.694753 0.345986 0.373093 -0.694752 0.614916 0.373093 -0.694749 0.614919 -0.0156488 -0.694748 -0.719083 -0.0156497 -0.694751 -0.71908 0.345987 -0.694752 -0.630566 0.345989 -0.69475 -0.630567 0.614915 -0.694752 -0.373094 0.614922 -0.694746 -0.373095 0.719085 -0.694746 -0.0156489 0.71908 -0.694751 -0.0156507 0.630567 -0.69475 0.345988 0.630566 -0.694752 0.345986 0.373094 -0.69475 0.614918 0.373094 -0.694746 0.614922 0.348269 -0.698077 0.625618 0.348269 -0.698081 0.625613 0.492278 -0.706867 0.507937 0.619969 -0.651638 0.437043 0.597956 -0.700863 0.388895 0.673289 -0.706117 0.219274 0.774261 -0.619556 0.129116 0.708157 -0.703129 0.0642173 0.698941 -0.704878 -0.120949 0.762163 -0.608094 -0.222101 0.654494 -0.704882 -0.273457 0.532431 -0.698082 -0.478748 0.654979 -0.561424 -0.505773 0.450093 -0.70612 -0.546635 0.271986 -0.698078 -0.662353 -0.0423341 -0.698073 -0.714774 -0.0423359 -0.698077 -0.71477 0.142353 -0.706865 -0.692876 0.319133 -0.637419 -0.701321 0.373094 -0.694748 0.61492 0.373093 -0.694752 0.614916 0.630567 -0.69475 0.345988 0.711983 -0.527882 0.463056 0.673286 -0.706121 0.219268 0.71908 -0.694751 -0.0156488 0.908911 -0.408761 0.0824309 0.698938 -0.704879 -0.12096 0.654501 -0.70488 -0.273446 0.704408 -0.566698 -0.427391 -0.0156487 -0.694755 -0.719076 -0.015647 -0.694751 -0.71908 0.295431 -0.700865 -0.649237 0.387717 -0.591914 -0.706621 0.450088 -0.706116 -0.546645 0.562797 -0.703127 -0.434594 0.373097 0.694744 0.614922 0.373094 0.694747 0.614921 0.630568 0.694748 0.345989 0.63057 0.694746 0.345989 0.719085 0.694746 -0.0156489 0.719089 0.694742 -0.0156509 0.614924 0.694742 -0.373099 0.61492 0.694748 -0.373094 0.34599 0.694747 -0.63057 0.34599 0.694746 -0.63057 -0.0156493 0.694745 -0.719086 -0.0156494 0.694745 -0.719086 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.85494 0 -0.518726 0.85494 0 -0.518726 0.48104 0 -0.876699 0.48104 0 -0.876699 -0.0217576 0 -0.999763 -0.0217576 0 -0.999763 0.373098 0.694741 0.614925 0.373094 0.694745 0.614922 0.630569 0.694747 0.345989 0.630572 0.694745 0.345989 0.719085 0.694746 -0.0156489 0.719089 0.694742 -0.0156509 0.614924 0.694741 -0.373099 0.614921 0.694747 -0.373094 0.34599 0.694746 -0.630571 0.34599 0.694747 -0.630569 -0.0156488 0.694746 -0.719085 -0.0156499 0.694744 -0.719087 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.85494 0 -0.518726 0.85494 0 -0.518726 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.021757 0 -0.999763 -0.021757 0 -0.999763 0.373096 0.694745 0.614922 0.373096 0.694746 0.614921 0.630569 0.694747 0.345989 0.630569 0.694747 0.345989 0.719085 0.694746 -0.0156489 0.719089 0.694742 -0.0156509 0.614924 0.694741 -0.3731 0.61492 0.694747 -0.373094 0.345991 0.694746 -0.63057 0.345991 0.694743 -0.630573 -0.0156489 0.694742 -0.719089 -0.015649 0.694742 -0.719089 0.486397 0 0.873738 0.518724 -0.00161865 0.85494 0.695951 0 0.718089 0.8383 0 0.545209 0.876696 -0.00270291 0.481037 0.950845 0 0.309667 0.995914 0 0.0903117 0.999758 -0.00324638 -0.021757 0.985356 0 -0.170512 0.922701 0 -0.385517 0.854935 -0.00324644 -0.518724 0.791488 0 -0.611185 0.635643 0 -0.771984 0.481038 -0.00270292 -0.876695 0.41418 0 -0.910195 0.201248 0 -0.97954 -0.021757 -0.00161871 -0.999762 -0.0591236 0 -0.998251 0.348273 0.698071 0.625622 0.348273 0.69807 0.625623 0.58523 0.698071 0.412556 0.585231 0.69807 0.412557 0.706277 0.69807 0.11778 0.706277 0.69807 0.11778 0.687438 0.698067 -0.200327 0.687439 0.698067 -0.200327 0.532441 0.698064 -0.478762 0.532438 0.698074 -0.478752 0.27199 0.698074 -0.662355 0.271989 0.698064 -0.662366 -0.0423394 0.698064 -0.714783 -0.0423317 0.698078 -0.71477 0.486395 0 0.873739 0.518725 0.00161876 0.85494 0.817327 -0.00135245 0.576173 0.8383 0 0.545209 0.950847 0 0.309661 0.986376 -0.00216682 0.16449 0.995913 0 0.0903212 0.985353 0 -0.170527 0.960063 -0.00243876 -0.279773 0.922708 0 -0.385501 0.791485 0 -0.611188 0.743595 -0.00216699 -0.668627 0.635632 0 -0.771992 0.37986 0 -0.925044 0.414178 -0.00161851 -0.910195 -0.0591302 0.0018831 -0.998249 -0.0217571 0 -0.999763 0.348273 0.698073 0.62562 0.348271 0.698074 0.62562 0.585223 0.698074 0.41256 0.585228 0.698072 0.412558 0.706276 0.698072 0.117773 0.706271 0.698075 0.11778 0.687431 0.698077 -0.20032 0.687433 0.698072 -0.200331 0.53244 0.698072 -0.478752 0.53244 0.698072 -0.478752 0.271983 0.698072 -0.66236 0.271984 0.698073 -0.662359 -0.0423341 0.698073 -0.714775 -0.0423328 0.698073 -0.714774 0.486397 0 0.873738 0.518719 0.00192561 0.854942 0.817321 -0.00160956 0.57618 0.8383 0 0.545209 0.950844 0 0.30967 0.986377 -0.00257846 0.16448 0.995915 0 0.0903014 0.985356 0 -0.170512 0.960064 -0.00290193 -0.279766 0.922706 0 -0.385505 0.791483 0 -0.611191 0.7436 -0.00257786 -0.66862 0.635658 0 -0.771971 0.37985 0 -0.925048 0.414173 -0.00192607 -0.910196 -0.0591235 0.00224014 -0.998248 -0.021757 0 -0.999763 0.373095 -0.694748 0.614919 0.373092 -0.694746 0.614923 0.63057 -0.694746 0.345992 0.629506 -0.66038 0.409415 0.673289 -0.706116 0.219276 0.719084 -0.694747 -0.015653 0.764722 -0.640619 0.0693388 0.698946 -0.704873 -0.12095 0.654506 -0.704873 -0.273452 0.632225 -0.673162 -0.383595 -0.0156488 -0.694748 -0.719083 -0.0156478 -0.694747 -0.719084 0.295428 -0.700863 -0.64924 0.354081 -0.676902 -0.645314 0.450106 -0.706117 -0.546628 0.562797 -0.703126 -0.434597 0.373088 0.694749 0.614922 0.373095 0.694745 0.614922 0.630573 0.694745 0.345988 0.630571 0.694746 0.345989 0.719086 0.694745 -0.0156532 0.719085 0.694746 -0.0156505 0.614922 0.694747 -0.373092 0.614922 0.694744 -0.373096 0.345992 0.694744 -0.630572 0.345992 0.694745 -0.630571 -0.015653 0.694745 -0.719086 -0.0156478 0.694748 -0.719083 0.486394 0 0.87374 0.518715 -0.00192553 0.854945 0.695921 0 0.718119 0.838303 0 0.545205 0.876697 -0.00321597 0.481033 0.950846 0 0.309664 0.995913 0 0.0903131 0.999756 -0.00386278 -0.0217629 0.985353 0 -0.170525 0.922706 0 -0.385505 0.854938 -0.00386274 -0.518716 0.791492 0 -0.61118 0.635649 0 -0.771979 0.481038 -0.00321612 -0.876694 0.414177 0 -0.910197 0.201248 0 -0.97954 -0.0217627 -0.00192602 -0.999761 -0.0591303 0 -0.99825 0.348268 -0.698077 0.625618 0.348269 -0.698077 0.625617 0.49226 -0.706863 0.507962 0.592042 -0.689418 0.417359 0.597957 -0.700864 0.388892 0.673289 -0.706117 0.219271 0.719491 -0.684059 0.119984 0.708159 -0.703127 0.0642185 0.687429 -0.698076 -0.200327 0.74677 -0.652406 -0.129236 0.654505 -0.704874 -0.273451 0.532439 -0.698075 -0.478748 0.588269 -0.669024 -0.454254 0.4501 -0.706117 -0.546634 0.271983 -0.698075 -0.662357 -0.0423386 -0.698077 -0.714769 -0.0423328 -0.698074 -0.714773 0.142354 -0.70686 -0.692881 0.302053 -0.68421 -0.663793 -0.0156531 0.694745 -0.719086 -0.0434441 0.678372 -0.733433 0.142357 0.706858 -0.692882 0.345992 0.694745 -0.63057 0.311028 0.660382 -0.683489 0.450082 0.706113 -0.546654 0.614922 0.694745 -0.373096 0.607756 0.640615 -0.469303 0.654505 0.704872 -0.273455 0.698945 0.704872 -0.120956 0.73932 0.673162 -0.0160896 0.708161 0.703124 0.0642214 0.673289 0.706115 0.219278 0.645313 0.676904 0.35408 0.348272 0.698072 0.625622 0.378299 0.684208 0.623498 0.492297 0.706859 0.507932 0.59796 0.700861 0.388894 0.486395 0 0.873739 0.486395 0 0.873739 0.695969 0 0.718072 0.695969 0 0.718072 0.838302 0 0.545206 0.838302 0 0.545206 0.950843 0 0.309672 0.950843 0 0.309672 0.995913 0 0.0903169 0.995913 0 0.0903169 0.985354 0 -0.170521 0.985354 0 -0.170521 0.922704 0 -0.38551 0.922704 0 -0.38551 0.791491 0 -0.611181 0.791491 0 -0.611181 0.63562 0 -0.772002 0.63562 0 -0.772002 0.41419 0 -0.91019 0.41419 0 -0.91019 0.201253 0 -0.979539 0.201253 0 -0.979539 -0.0591303 0 -0.99825 -0.0591303 0 -0.99825 0.373095 -0.694746 0.614921 0.357362 -0.678374 0.64195 0.492296 -0.70686 0.50793 0.630569 -0.694748 0.34599 0.629505 -0.660383 0.409411 0.673288 -0.706117 0.219277 0.719083 -0.694748 -0.0156492 0.764725 -0.640614 0.069351 0.698943 -0.704874 -0.120956 0.654504 -0.704874 -0.273455 0.632223 -0.673164 -0.383594 0.562803 -0.703124 -0.434591 0.450081 -0.706115 -0.546652 0.35408 -0.676906 -0.645311 -0.0423388 -0.698074 -0.714773 -0.0158713 -0.684209 -0.729113 0.142357 -0.70686 -0.692881 0.295441 -0.700862 -0.649236 -0.0156488 -0.694746 -0.719085 -0.015649 -0.694746 -0.719085 0.345992 -0.694743 -0.630572 0.345986 -0.69475 -0.630568 0.614917 -0.694751 -0.373091 0.614915 -0.694754 -0.373091 0.719075 -0.694756 -0.0156528 0.719089 -0.694742 -0.0156472 0.630572 -0.694744 0.345991 0.630572 -0.694744 0.345991 0.373094 -0.694745 0.614923 0.373093 -0.694754 0.614913 -0.021757 0 -0.999763 -0.021757 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.854943 0 -0.518723 0.854943 0 -0.518723 0.999763 0 -0.0217628 0.999763 0 -0.0217628 0.876699 0 0.481039 0.876699 0 0.481039 0.518722 0 0.854943 0.518722 0 0.854943 0.373094 -0.694746 0.614922 0.373093 -0.694752 0.614916 0.630567 -0.69475 0.345988 0.711983 -0.527882 0.463056 0.673286 -0.706121 0.219268 0.71908 -0.694751 -0.0156488 0.908904 -0.408779 0.0824257 0.698941 -0.704877 -0.120954 0.654501 -0.704876 -0.273455 0.704405 -0.566701 -0.427391 -0.0156489 -0.694746 -0.719085 -0.0156507 -0.694751 -0.719081 0.295429 -0.700867 -0.649236 0.387725 -0.591904 -0.706625 0.450098 -0.706114 -0.54664 0.562802 -0.703123 -0.434594 -0.0217571 0 -0.999763 -0.0591232 0.00353186 -0.998244 0.414175 -0.00303654 -0.910192 0.379854 0 -0.925046 0.635644 0 -0.771983 0.743595 -0.00406489 -0.668618 0.791488 0 -0.611185 0.922703 0 -0.385511 0.960056 -0.00457528 -0.279771 0.985354 0 -0.170519 0.995913 0 0.0903162 0.986371 -0.00406484 0.164486 0.950847 0 0.309661 0.8383 0 0.545209 0.817325 -0.00253707 0.576172 0.518723 0.00303665 0.854937 0.486395 0 0.873739 -0.0423383 -0.698083 -0.714764 -0.0423323 -0.698069 -0.714778 0.271991 -0.698069 -0.66236 0.271984 -0.698077 -0.662354 0.532433 -0.698077 -0.478752 0.532439 -0.698071 -0.478754 0.687432 -0.698074 -0.200325 0.687431 -0.698075 -0.200325 0.706269 -0.698078 0.117777 0.706271 -0.698075 0.117779 0.585229 -0.698071 0.412558 0.585227 -0.698075 0.412554 0.348271 -0.698074 0.625619 0.348271 -0.698074 0.62562 -0.0591303 0 -0.99825 -0.0591303 0 -0.99825 0.379859 0 -0.925044 0.379859 0 -0.925044 0.743598 0 -0.668627 0.743598 0 -0.668627 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164488 0.986379 0 0.164488 0.817326 0 0.576175 0.817326 0 0.576175 0.486395 0 0.873739 0.486395 0 0.873739 -0.0156489 -0.694746 -0.719085 -0.015649 -0.694746 -0.719085 0.34599 -0.694748 -0.630569 0.345988 -0.69475 -0.630567 0.614915 -0.694752 -0.373094 0.614922 -0.694746 -0.373095 0.719085 -0.694746 -0.0156489 0.719081 -0.694751 -0.0156507 0.630566 -0.694752 0.345987 0.630566 -0.694752 0.345987 0.373094 -0.69475 0.614918 0.373094 -0.69475 0.614918 0.373095 -0.694746 0.614922 0.373094 -0.694752 0.614915 0.630567 -0.69475 0.345988 0.711984 -0.52788 0.463056 0.673287 -0.706118 0.219275 0.71908 -0.694751 -0.0156489 0.908904 -0.408779 0.0824257 0.698941 -0.704877 -0.120954 0.654501 -0.704876 -0.273455 0.704404 -0.566704 -0.427388 -0.0156489 -0.694746 -0.719085 -0.0156507 -0.694751 -0.719081 0.295429 -0.700867 -0.649236 0.387719 -0.591912 -0.706622 0.450094 -0.706121 -0.546634 0.562798 -0.703128 -0.434591 0.348271 -0.698073 0.625621 0.348271 -0.698074 0.62562 0.492298 -0.706859 0.507929 0.619969 -0.651637 0.437045 0.597955 -0.700865 0.388894 0.673286 -0.706119 0.219275 0.774259 -0.619558 0.129116 0.708159 -0.703126 0.0642207 0.698942 -0.704875 -0.120956 0.76216 -0.608097 -0.222102 0.654503 -0.704875 -0.273453 0.532435 -0.698077 -0.47875 0.654977 -0.561425 -0.505774 0.450094 -0.70612 -0.546635 0.271984 -0.698078 -0.662354 -0.0423341 -0.698073 -0.714774 -0.042336 -0.698078 -0.714769 0.142359 -0.706863 -0.692877 0.31913 -0.637421 -0.701321 0.348271 -0.698074 0.62562 0.348271 -0.698074 0.625619 0.492296 -0.70686 0.50793 0.619968 -0.651637 0.437045 0.597954 -0.700865 0.388895 0.673287 -0.706119 0.219273 0.774257 -0.61956 0.129115 0.708158 -0.703127 0.0642211 0.698941 -0.704876 -0.120955 0.76216 -0.608098 -0.222102 0.654501 -0.704877 -0.273454 0.532434 -0.698078 -0.47875 0.654979 -0.561423 -0.505774 0.450096 -0.706119 -0.546635 0.271984 -0.698077 -0.662354 -0.042334 -0.698073 -0.714774 -0.042336 -0.698078 -0.714769 0.142356 -0.706863 -0.692877 0.31913 -0.63742 -0.701322 -0.0423366 0.698069 -0.714778 -0.042334 0.698074 -0.714774 0.142359 0.706859 -0.692881 0.288134 0.651633 -0.701679 0.295434 0.700862 -0.64924 0.450096 0.706116 -0.546639 0.583687 0.619561 -0.524836 0.5628 0.703121 -0.4346 0.687436 0.698069 -0.200329 0.815731 0.467366 -0.340811 0.698944 0.704873 -0.120959 0.706274 0.698073 0.117779 0.824144 0.561427 0.0747435 0.673285 0.706121 0.219273 0.585224 0.698077 0.412554 0.348271 0.698072 0.625621 0.348272 0.698072 0.625622 0.4923 0.706857 0.507932 0.645927 0.637416 0.420094 0.486394 0 0.87374 0.518724 0.0016188 0.85494 0.695971 0 0.71807 0.8383 0 0.545209 0.876696 0.00270291 0.481037 0.950845 0 0.309667 0.995913 0 0.0903217 0.999758 0.00324667 -0.021757 0.985353 0 -0.170525 0.922706 0 -0.385505 0.854935 0.00324668 -0.518724 0.791483 0 -0.611191 0.635643 0 -0.771984 0.481038 0.00270292 -0.876695 -0.0591236 0 -0.998251 -0.0217571 0.00161871 -0.999762 0.201256 0 -0.979539 0.41418 0 -0.910195 0.348274 0.698068 0.625624 0.348272 0.69807 0.625623 0.585231 0.698071 0.412555 0.585228 0.698074 0.412554 0.706272 0.698074 0.117779 0.706274 0.698073 0.117779 0.687432 0.698074 -0.200325 0.687432 0.698073 -0.200326 0.532437 0.698074 -0.478752 0.532438 0.698074 -0.478752 0.271985 0.698073 -0.662358 0.271985 0.698074 -0.662357 -0.0423341 0.698073 -0.714774 -0.0423365 0.698069 -0.714778 0.486395 0 0.873739 0.518726 0.00161883 0.854939 0.817328 -0.00135235 0.576171 0.8383 0 0.545209 0.950844 0 0.30967 0.986376 -0.00216697 0.16449 0.995913 0 0.0903162 0.985354 0 -0.170519 0.960063 -0.00243898 -0.279773 0.922703 0 -0.385511 0.791488 0 -0.611185 0.743599 -0.0021669 -0.668622 0.635644 0 -0.771983 0.379853 0 -0.925047 0.414176 -0.00161876 -0.910195 -0.0591235 0.00188276 -0.998249 -0.0217571 0 -0.999763 0.373099 0.694741 0.614924 0.373093 0.694748 0.61492 0.630569 0.694748 0.34599 0.630575 0.694741 0.345991 0.719087 0.694744 -0.0156499 0.719085 0.694746 -0.015649 0.614922 0.694745 -0.373096 0.61492 0.694747 -0.373094 0.345989 0.694748 -0.630568 0.345989 0.694747 -0.630569 -0.0156489 0.694746 -0.719085 -0.0156509 0.694742 -0.719089 0.486395 0 0.873739 0.518726 -0.00161883 0.854939 0.695972 0 0.718069 0.8383 0 0.545209 0.876695 -0.00270286 0.481038 0.950844 0 0.30967 0.995913 0 0.0903162 0.999758 -0.00324657 -0.0217583 0.985354 0 -0.170522 0.922704 0 -0.385508 0.854937 -0.00324657 -0.518722 0.791487 0 -0.611186 0.635644 0 -0.771983 0.481037 -0.002703 -0.876696 0.414177 0 -0.910196 0.201256 0 -0.979539 -0.0217571 -0.00161871 -0.999762 -0.0591236 0 -0.998251 -0.0423365 0.698069 -0.714778 -0.042334 0.698074 -0.714774 0.142357 0.706859 -0.692882 0.288133 0.651633 -0.70168 0.295432 0.70086 -0.649242 0.450098 0.706115 -0.546638 0.583689 0.619559 -0.524837 0.562801 0.703124 -0.434594 0.687433 0.698073 -0.200326 0.815736 0.467352 -0.340818 0.698946 0.704872 -0.120956 0.706275 0.698072 0.117779 0.824152 0.561415 0.0747403 0.673291 0.706115 0.219274 0.585229 0.698072 0.412556 0.348274 0.698069 0.625624 0.348273 0.69807 0.625623 0.492299 0.706856 0.507934 0.645928 0.637414 0.420095 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.201253 0 -0.979539 0.201253 0 -0.979539 0.414177 0 -0.910196 0.414177 0 -0.910196 0.635645 0 -0.771982 0.635645 0 -0.771982 0.791487 0 -0.611186 0.791487 0 -0.611186 0.922704 0 -0.38551 0.922704 0 -0.38551 0.985354 0 -0.170521 0.985354 0 -0.170521 0.995913 0 0.0903169 0.995913 0 0.0903169 0.950845 0 0.309667 0.950845 0 0.309667 0.8383 0 0.545209 0.8383 0 0.545209 0.695969 0 0.718072 0.695969 0 0.718072 0.486395 0 0.873739 0.486395 0 0.873739 -0.0156505 0.694746 -0.719084 -0.0434441 0.678372 -0.733433 0.142391 0.706861 -0.692873 0.345988 0.694748 -0.63057 0.311017 0.660378 -0.683498 0.450086 0.706114 -0.546649 0.614922 0.694745 -0.373095 0.607757 0.640615 -0.469301 0.654506 0.704875 -0.273448 0.69894 0.704875 -0.120969 0.739321 0.673161 -0.0160882 0.708161 0.703124 0.0642245 0.673291 0.706115 0.219272 0.645314 0.676901 0.354082 0.348269 0.698074 0.625621 0.378299 0.684208 0.623498 0.492306 0.706859 0.507923 0.597957 0.70086 0.388899 0.486391 0 0.873741 0.486391 0 0.873741 0.695982 0 0.71806 0.695982 0 0.71806 0.838298 0 0.545213 0.838298 0 0.545213 0.950846 0 0.309664 0.950846 0 0.309664 0.995913 0 0.0903212 0.995913 0 0.0903212 0.985351 0 -0.17054 0.985351 0 -0.17054 0.922708 0 -0.385501 0.922708 0 -0.385501 0.791493 0 -0.611179 0.791493 0 -0.611179 0.635627 0 -0.771996 0.635627 0 -0.771996 0.414174 0 -0.910198 0.414174 0 -0.910198 0.201302 0 -0.979529 0.201302 0 -0.979529 -0.0591303 0 -0.99825 -0.0591303 0 -0.99825 0.373095 -0.694748 0.614919 0.35736 -0.678374 0.641953 0.492305 -0.70686 0.507922 0.630569 -0.694747 0.345991 0.629505 -0.660379 0.409418 0.67329 -0.706117 0.219272 0.719084 -0.694747 -0.0156478 0.764726 -0.640612 0.0693545 0.698938 -0.704877 -0.120969 0.654504 -0.704877 -0.273447 0.632223 -0.673165 -0.383592 0.562804 -0.703125 -0.434589 0.450085 -0.706116 -0.546648 0.354077 -0.676905 -0.645313 -0.0423387 -0.698076 -0.714771 -0.0158687 -0.68421 -0.729112 0.142391 -0.706863 -0.692871 0.295428 -0.700865 -0.649239 0.373098 0.694744 0.614921 0.373094 0.694746 0.614921 0.630569 0.694747 0.34599 0.630569 0.694747 0.34599 0.719084 0.694747 -0.0156488 0.719085 0.694746 -0.0156504 0.614921 0.694746 -0.373096 0.614921 0.694746 -0.373095 0.345988 0.694747 -0.63057 0.34599 0.694749 -0.630567 -0.0156447 0.69475 -0.719081 -0.0156531 0.694745 -0.719086 0.486394 0 0.87374 0.518726 -0.00192619 0.854938 0.695982 0 0.71806 0.838294 0 0.545218 0.876694 -0.00321637 0.481038 0.950852 0 0.309646 0.995913 0 0.0903212 0.999756 -0.00386293 -0.0217569 0.985353 0 -0.170525 0.922706 0 -0.385505 0.854935 -0.0038629 -0.518722 0.791484 0 -0.61119 0.635639 0 -0.771987 0.481035 -0.00321601 -0.876695 0.414177 0 -0.910197 0.201256 0 -0.979539 -0.0217513 -0.00192591 -0.999762 -0.0591169 0 -0.998251 0.34827 -0.698074 0.625621 0.34827 -0.698074 0.62562 0.492305 -0.70686 0.507922 0.592041 -0.68942 0.417358 0.597954 -0.700861 0.388903 0.673295 -0.706116 0.219259 0.719491 -0.68406 0.119981 0.70816 -0.703125 0.0642244 0.687432 -0.698074 -0.200325 0.74677 -0.652406 -0.129236 0.654505 -0.704874 -0.273451 0.532435 -0.698074 -0.478754 0.588263 -0.669025 -0.45426 0.450092 -0.706118 -0.54664 0.271989 -0.698076 -0.662354 -0.0423293 -0.698073 -0.714775 -0.0423386 -0.698077 -0.714769 0.142358 -0.706863 -0.692877 0.302051 -0.684214 -0.663789 0.348272 0.698072 0.625622 0.348271 0.698072 0.625622 0.585231 0.698072 0.412553 0.585227 0.698074 0.412555 0.706273 0.698073 0.11778 0.706274 0.698073 0.117778 0.687432 0.698073 -0.200325 0.687433 0.698073 -0.200326 0.53244 0.698073 -0.47875 0.532438 0.698071 -0.478755 0.271986 0.69807 -0.662361 0.27199 0.698072 -0.662357 -0.0423389 0.698072 -0.714775 -0.0423328 0.698075 -0.714772 0.486395 0 0.873739 0.518725 0.00192609 0.854939 0.81733 -0.0016091 0.576168 0.838302 0 0.545206 0.950843 0 0.309672 0.986375 -0.00257828 0.16449 0.995913 0 0.0903169 0.985354 0 -0.170521 0.960062 -0.00290188 -0.279773 0.922704 0 -0.385509 0.791491 0 -0.611181 0.743601 -0.00257826 -0.668618 0.635644 0 -0.771982 0.379854 0 -0.925047 0.414176 -0.00192601 -0.910195 -0.0591301 0.00224019 -0.998248 -0.0217628 0 -0.999763 0.373095 -0.694746 0.614921 0.373096 -0.694747 0.614919 0.63057 -0.694747 0.345988 0.629507 -0.660381 0.409412 0.673289 -0.706116 0.219278 0.719083 -0.694748 -0.0156494 0.764725 -0.640614 0.0693511 0.698943 -0.704874 -0.120956 0.654504 -0.704874 -0.273454 0.632223 -0.673164 -0.383594 -0.0156529 -0.69475 -0.719081 -0.0156478 -0.694747 -0.719084 0.295431 -0.700863 -0.64924 0.354082 -0.676902 -0.645313 0.450098 -0.706116 -0.546638 0.562803 -0.703124 -0.434591 -0.0156487 -0.694751 -0.71908 -0.0156489 -0.694751 -0.71908 0.34599 -0.694747 -0.630569 0.345985 -0.694754 -0.630565 0.614913 -0.694754 -0.373093 0.614922 -0.694746 -0.373094 0.719085 -0.694746 -0.0156489 0.71908 -0.694751 -0.0156507 0.630567 -0.69475 0.345988 0.630571 -0.694744 0.345993 0.373096 -0.694745 0.614921 0.373096 -0.694746 0.614921 -0.021757 0 -0.999763 -0.021757 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.85494 0 -0.518727 0.85494 0 -0.518727 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 -0.0156487 -0.694755 -0.719076 -0.015647 -0.694751 -0.71908 0.345987 -0.694752 -0.630566 0.345987 -0.694752 -0.630566 0.614918 -0.69475 -0.373094 0.614918 -0.69475 -0.373094 0.71908 -0.694751 -0.0156488 0.71908 -0.694751 -0.0156489 0.630566 -0.694752 0.345986 0.630567 -0.69475 0.345988 0.373094 -0.694746 0.614922 0.373094 -0.694746 0.614922 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.8767 0 0.481038 0.8767 0 0.481038 0.518723 0 0.854943 0.518723 0 0.854943 -0.0156528 -0.694756 -0.719075 -0.0156472 -0.694742 -0.719089 0.345992 -0.694743 -0.630573 0.34599 -0.694744 -0.630572 0.614922 -0.694746 -0.373094 0.614915 -0.694753 -0.373093 0.719081 -0.69475 -0.0156493 0.719082 -0.694749 -0.0156492 0.630566 -0.694751 0.345988 0.630566 -0.694751 0.345988 0.373094 -0.694752 0.614915 0.373094 -0.694747 0.614921 -0.0217628 0 -0.999763 -0.0217628 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854943 0 -0.518722 0.854943 0 -0.518722 0.999763 0 -0.0217578 0.999763 0 -0.0217578 0.876699 0 0.48104 0.876699 0 0.48104 0.518726 0 0.85494 0.518726 0 0.85494 0.373094 -0.694746 0.614922 0.373094 -0.69475 0.614918 0.630566 -0.694752 0.345986 0.711984 -0.52788 0.463056 0.673286 -0.706119 0.219273 0.71908 -0.694751 -0.0156507 0.908915 -0.408752 0.0824312 0.698944 -0.704873 -0.12096 0.654506 -0.704873 -0.273452 0.704411 -0.566695 -0.42739 -0.0156488 -0.694751 -0.71908 -0.0156489 -0.694751 -0.71908 0.295429 -0.700867 -0.649236 0.387719 -0.591912 -0.706622 0.450092 -0.706118 -0.54664 0.562801 -0.703125 -0.434593 -0.0423341 -0.698073 -0.714774 -0.042336 -0.698078 -0.714769 0.271984 -0.698077 -0.662354 0.271984 -0.698077 -0.662354 0.532433 -0.698078 -0.47875 0.532437 -0.698075 -0.478751 0.687432 -0.698074 -0.200325 0.687432 -0.698074 -0.200325 0.706274 -0.698073 0.117779 0.706272 -0.698074 0.117778 0.585226 -0.698074 0.412557 0.585222 -0.698081 0.41255 0.348267 -0.698083 0.625612 0.348267 -0.698083 0.625612 0.348267 -0.698081 0.625614 0.348267 -0.698083 0.625612 0.492278 -0.706868 0.507938 0.619967 -0.651639 0.437044 0.597955 -0.700862 0.388898 0.673292 -0.706116 0.219265 0.774255 -0.619563 0.129115 0.708157 -0.703128 0.0642212 0.69894 -0.704878 -0.120954 0.76216 -0.608097 -0.222102 0.6545 -0.704878 -0.273454 0.532434 -0.698078 -0.478749 0.654979 -0.561423 -0.505773 0.450094 -0.70612 -0.546635 0.271984 -0.698078 -0.662354 -0.0423341 -0.698073 -0.714774 -0.042336 -0.698077 -0.71477 0.142356 -0.706864 -0.692877 0.31913 -0.637421 -0.701321 0.373093 -0.694754 0.614913 0.373095 -0.694744 0.614924 0.63057 -0.694747 0.34599 0.711987 -0.527875 0.463059 0.673287 -0.70612 0.219268 0.719081 -0.69475 -0.0156494 0.908907 -0.40877 0.0824274 0.698942 -0.704876 -0.120956 0.654503 -0.704875 -0.273454 0.704406 -0.566702 -0.427388 -0.0156489 -0.694746 -0.719085 -0.0156507 -0.694751 -0.71908 0.295429 -0.700866 -0.649237 0.387718 -0.591912 -0.706622 0.450094 -0.706121 -0.546633 0.562797 -0.703129 -0.434591 0.348273 0.698068 0.625625 0.348273 0.698068 0.625625 0.585234 0.698067 0.412556 0.585223 0.698077 0.412555 0.706267 0.698079 0.11778 0.706273 0.698073 0.117779 0.687433 0.698073 -0.200326 0.687436 0.698069 -0.200329 0.532439 0.69807 -0.478755 0.532438 0.698074 -0.478752 0.271986 0.698073 -0.662358 0.271986 0.698073 -0.662358 -0.042334 0.698074 -0.714774 -0.0423342 0.698073 -0.714774 0.486394 0 0.87374 0.518724 0.0016188 0.85494 0.817329 -0.00135232 0.57617 0.8383 0 0.545209 0.950845 0 0.309667 0.986376 -0.0021669 0.164493 0.995913 0 0.0903212 0.985353 0 -0.170526 0.960063 -0.00243882 -0.279774 0.922706 0 -0.385505 0.791488 0 -0.611185 0.743598 -0.00216697 -0.668624 0.635639 0 -0.771987 0.379854 0 -0.925046 0.414176 -0.0016187 -0.910195 -0.0591235 0.00188275 -0.998249 -0.0217571 0 -0.999763 0.348269 0.698078 0.625616 0.348269 0.698078 0.625616 0.585224 0.698077 0.412555 0.585231 0.69807 0.412557 0.706277 0.69807 0.11778 0.706278 0.698068 0.117779 0.687436 0.69807 -0.200326 0.687436 0.698069 -0.200327 0.532439 0.69807 -0.478755 0.532438 0.698074 -0.478752 0.271986 0.698073 -0.662358 0.271986 0.698073 -0.662358 -0.042334 0.698074 -0.714774 -0.0423365 0.698069 -0.714778 0.486395 0 0.873739 0.486395 0 0.873739 0.817325 0 0.576176 0.817325 0 0.576176 0.986379 0 0.16449 0.986379 0 0.16449 0.960066 0 -0.279774 0.960066 0 -0.279774 0.743599 0 -0.668625 0.743599 0 -0.668625 0.379854 0 -0.925046 0.379854 0 -0.925046 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 -0.0423365 0.698069 -0.714778 -0.0423341 0.698073 -0.714774 0.142356 0.70686 -0.692881 0.288132 0.651634 -0.701679 0.295431 0.700861 -0.649241 0.450097 0.706116 -0.546638 0.58369 0.619559 -0.524836 0.562801 0.703125 -0.434593 0.687432 0.698073 -0.200326 0.815737 0.467349 -0.34082 0.698945 0.704873 -0.120954 0.706274 0.698073 0.117779 0.824151 0.561417 0.0747404 0.673296 0.706112 0.219267 0.585231 0.69807 0.412557 0.34827 0.698076 0.625618 0.348269 0.698078 0.625616 0.492281 0.706863 0.507941 0.645924 0.637418 0.420096 0.486395 0 0.873739 0.486395 0 0.873739 0.695951 0 0.718089 0.695951 0 0.718089 0.838298 0 0.545212 0.838298 0 0.545212 0.950849 0 0.309655 0.950849 0 0.309655 0.995913 0 0.0903171 0.995913 0 0.0903171 0.985354 0 -0.170519 0.985354 0 -0.170519 0.922703 0 -0.385511 0.922703 0 -0.385511 0.791488 0 -0.611185 0.791488 0 -0.611185 0.635644 0 -0.771983 0.635644 0 -0.771983 0.414177 0 -0.910196 0.414177 0 -0.910196 0.201252 0 -0.97954 0.201252 0 -0.97954 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.34827 0.698077 0.625617 0.348269 0.698078 0.625616 0.585225 0.698076 0.412555 0.585229 0.698072 0.412556 0.706274 0.698072 0.117779 0.706276 0.698071 0.117778 0.687433 0.698072 -0.200326 0.687433 0.698073 -0.200325 0.532438 0.698074 -0.478752 0.532438 0.698072 -0.478753 0.271986 0.698072 -0.662359 0.271986 0.698074 -0.662357 -0.042334 0.698073 -0.714774 -0.0423365 0.698069 -0.714778 0.486395 0 0.873739 0.518722 0.0016186 0.854942 0.817325 -0.00135251 0.576175 0.8383 0 0.54521 0.950847 0 0.309661 0.986377 -0.00216688 0.164489 0.995913 0 0.0903178 0.985354 0 -0.170521 0.960063 -0.00243894 -0.279773 0.922704 0 -0.38551 0.791487 0 -0.611186 0.743599 -0.00216688 -0.668622 0.635644 0 -0.771982 0.379854 0 -0.925047 0.414176 -0.00161875 -0.910195 -0.0591235 0.00188276 -0.998249 -0.0217571 0 -0.999763 0.348273 0.698073 0.62562 0.348272 0.698073 0.62562 0.58523 0.698073 0.412553 0.58523 0.698073 0.412553 0.706273 0.698073 0.117782 0.706274 0.698072 0.117781 0.687433 0.698072 -0.20033 0.687432 0.698075 -0.200324 0.532438 0.698075 -0.478751 0.532437 0.698074 -0.478751 0.271987 0.698074 -0.662357 0.271986 0.698073 -0.662358 -0.042335 0.698073 -0.714774 -0.042335 0.698073 -0.714774 0.486396 0 0.873738 0.486396 0 0.873738 0.81733 0 0.57617 0.81733 0 0.57617 0.986378 0 0.164493 0.986378 0 0.164493 0.960064 0 -0.27978 0.960064 0 -0.27978 0.743602 0 -0.668623 0.743602 0 -0.668623 0.379856 0 -0.925046 0.379856 0 -0.925046 -0.0591248 0 -0.998251 -0.0591248 0 -0.998251 -0.0423349 -0.698075 -0.714772 -0.0423349 -0.698075 -0.714772 0.271986 -0.698075 -0.662356 0.271985 -0.698075 -0.662356 0.532437 -0.698076 -0.47875 0.532436 -0.698076 -0.47875 0.687428 -0.698077 -0.200329 0.687432 -0.698074 -0.200324 0.706272 -0.698074 0.117781 0.706272 -0.698074 0.11778 0.585229 -0.698075 0.412552 0.585229 -0.698075 0.412552 0.348272 -0.698075 0.625618 0.348271 -0.698075 0.625619 0.373092 0.694747 0.614922 0.373096 0.694744 0.614922 0.630577 0.694743 0.345984 0.630567 0.694749 0.34599 0.719081 0.69475 -0.0156447 0.719086 0.694745 -0.0156531 0.614921 0.694744 -0.373098 0.614921 0.694745 -0.373096 0.345991 0.694746 -0.63057 0.345991 0.694746 -0.63057 -0.0156489 0.694745 -0.719085 -0.0156478 0.694746 -0.719085 0.51872 0 0.854944 0.51872 0 0.854944 0.876705 0 0.481029 0.876705 0 0.481029 0.999763 0 -0.0217514 0.999763 0 -0.0217514 0.85494 0 -0.518727 0.85494 0 -0.518727 0.48104 0 -0.876699 0.48104 0 -0.876699 -0.021757 0 -0.999763 -0.021757 0 -0.999763 -0.0156488 -0.694748 -0.719083 -0.0156478 -0.694747 -0.719084 0.34599 -0.694747 -0.630569 0.34599 -0.694747 -0.630569 0.614919 -0.694747 -0.373096 0.614921 -0.694746 -0.373095 0.719085 -0.694746 -0.0156448 0.719081 -0.69475 -0.0156529 0.630569 -0.694752 0.34598 0.63057 -0.694746 0.345992 0.373092 -0.694746 0.614923 0.373095 -0.694748 0.614919 0.348272 0.698072 0.625622 0.348271 0.698072 0.625622 0.585229 0.698072 0.412555 0.585228 0.698073 0.412555 0.706272 0.698074 0.117781 0.706275 0.698072 0.117777 0.687433 0.698073 -0.200326 0.687433 0.698073 -0.200325 0.532435 0.698072 -0.478756 0.532436 0.698073 -0.478754 0.271986 0.698073 -0.662358 0.271985 0.698073 -0.662359 -0.0423293 0.698073 -0.714774 -0.0423329 0.698071 -0.714776 0.486394 0 0.87374 0.486394 0 0.87374 0.817329 0 0.576172 0.817329 0 0.576172 0.986378 0 0.164492 0.986378 0 0.164492 0.960066 0 -0.279774 0.960066 0 -0.279774 0.743596 0 -0.668629 0.743596 0 -0.668629 0.379854 0 -0.925046 0.379854 0 -0.925046 -0.0591169 0 -0.998251 -0.0591169 0 -0.998251 -0.0423293 -0.698073 -0.714775 -0.0423328 -0.698074 -0.714773 0.271985 -0.698074 -0.662357 0.271984 -0.698075 -0.662357 0.532433 -0.698075 -0.478754 0.532435 -0.698074 -0.478754 0.687431 -0.698075 -0.200325 0.687432 -0.698074 -0.200325 0.706273 -0.698074 0.117781 0.706271 -0.698075 0.117777 0.585228 -0.698075 0.412553 0.585227 -0.698074 0.412555 0.34827 -0.698074 0.62562 0.34827 -0.698074 0.625621 -0.0423348 -0.698077 -0.71477 -0.0423346 -0.698077 -0.71477 0.271986 -0.698076 -0.662355 0.271985 -0.698077 -0.662354 0.532433 -0.698078 -0.478751 0.532437 -0.698074 -0.478752 0.687433 -0.698073 -0.200326 0.687428 -0.698077 -0.200326 0.706269 -0.698077 0.117781 0.706264 -0.698083 0.117777 0.585222 -0.698082 0.412548 0.585227 -0.698074 0.412556 0.34827 -0.698075 0.625619 0.34827 -0.698076 0.625618 -0.0591249 0 -0.998251 -0.0591249 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.743599 0 -0.668626 0.743599 0 -0.668626 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986378 0 0.164493 0.986378 0 0.164493 0.81733 0 0.57617 0.81733 0 0.57617 0.486393 0 0.87374 0.486393 0 0.87374 -0.0156489 -0.694746 -0.719085 -0.0156508 -0.694751 -0.719081 0.345986 -0.694752 -0.630566 0.345991 -0.694746 -0.63057 0.614924 -0.694744 -0.373095 0.614914 -0.694753 -0.373094 0.719076 -0.694755 -0.0156487 0.71908 -0.694751 -0.015647 0.630566 -0.694752 0.345987 0.630566 -0.694752 0.345987 0.373094 -0.69475 0.614918 0.373094 -0.69475 0.614918 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854943 0 -0.518723 0.854943 0 -0.518723 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 -0.0423341 -0.698073 -0.714774 -0.042336 -0.698077 -0.71477 0.271983 -0.698079 -0.662353 0.271984 -0.698077 -0.662354 0.532435 -0.698078 -0.478749 0.532434 -0.698078 -0.478749 0.687428 -0.698078 -0.200324 0.687428 -0.698078 -0.200324 0.70627 -0.698077 0.117779 0.706268 -0.698079 0.117778 0.585224 -0.698078 0.412553 0.585222 -0.698081 0.41255 0.348267 -0.698083 0.625612 0.348267 -0.698081 0.625614 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379853 0 -0.925047 0.379853 0 -0.925047 0.743601 0 -0.668624 0.743601 0 -0.668624 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.16449 0.986379 0 0.16449 0.817327 0 0.576174 0.817327 0 0.576174 0.486395 0 0.873739 0.486395 0 0.873739 -0.0591248 0 -0.998251 -0.0591248 0 -0.998251 0.379853 0 -0.925047 0.379853 0 -0.925047 0.743599 0 -0.668626 0.743599 0 -0.668626 0.960066 0 -0.279773 0.960066 0 -0.279773 0.986379 0 0.164491 0.986379 0 0.164491 0.817326 0 0.576175 0.817326 0 0.576175 0.486394 0 0.87374 0.486394 0 0.87374 -0.021756 0 -0.999763 -0.021756 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854939 0 -0.518729 0.854939 0 -0.518729 0.999763 0 -0.0217559 0.999763 0 -0.0217559 0.876701 0 0.481037 0.876701 0 0.481037 0.518723 0 0.854942 0.518723 0 0.854942 -0.0591223 0 -0.998251 -0.0591223 0 -0.998251 0.379854 0 -0.925046 0.379854 0 -0.925046 0.7436 0 -0.668624 0.7436 0 -0.668624 0.960065 0 -0.279777 0.960065 0 -0.279777 0.986379 0 0.164491 0.986379 0 0.164491 0.817326 0 0.576175 0.817326 0 0.576175 0.486396 0 0.873739 0.486396 0 0.873739 -0.0591222 0 -0.998251 -0.0591222 0 -0.998251 0.379855 0 -0.925046 0.379855 0 -0.925046 0.743599 0 -0.668626 0.743599 0 -0.668626 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164489 0.986379 0 0.164489 0.817328 0 0.576173 0.817328 0 0.576173 0.486392 0 0.873741 0.486392 0 0.873741 -0.059122 0 -0.998251 -0.059122 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.743598 0 -0.668627 0.743598 0 -0.668627 0.960066 0 -0.279772 0.960066 0 -0.279772 0.986379 0 0.164491 0.986379 0 0.164491 0.817329 0 0.576172 0.817329 0 0.576172 0.486396 0 0.873739 0.486396 0 0.873739 -0.0217559 0 -0.999763 -0.0217559 0 -0.999763 0.481036 0 -0.876701 0.481036 0 -0.876701 0.854943 0 -0.518722 0.854943 0 -0.518722 0.999763 0 -0.0217602 0.999763 0 -0.0217602 0.876698 0 0.481041 0.876698 0 0.481041 0.518727 0 0.85494 0.518727 0 0.85494 -0.0591248 0 -0.998251 -0.0591248 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.743599 0 -0.668626 0.743599 0 -0.668626 0.960066 0 -0.279773 0.960066 0 -0.279773 0.98638 0 0.164481 0.98638 0 0.164481 0.817327 0 0.576174 0.817327 0 0.576174 0.486394 0 0.87374 0.486394 0 0.87374 -0.0591242 0 -0.998251 -0.0591242 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.743599 0 -0.668626 0.743599 0 -0.668626 0.960066 0 -0.279773 0.960066 0 -0.279773 0.986379 0 0.164491 0.986379 0 0.164491 0.817326 0 0.576175 0.817326 0 0.576175 0.486394 0 0.87374 0.486394 0 0.87374 -0.0591274 0 -0.99825 -0.0591274 0 -0.99825 0.379854 0 -0.925046 0.379854 0 -0.925046 0.743603 0 -0.668622 0.743603 0 -0.668622 0.960065 0 -0.279778 0.960065 0 -0.279778 0.986379 0 0.16449 0.986379 0 0.16449 0.817326 0 0.576175 0.817326 0 0.576175 0.486396 0 0.873739 0.486396 0 0.873739 -0.0217646 0 -0.999763 -0.0217646 0 -0.999763 0.481043 0 -0.876697 0.481043 0 -0.876697 0.854942 0 -0.518723 0.854942 0 -0.518723 0.999763 0 -0.0217582 0.999763 0 -0.0217582 0.876699 0 0.481039 0.876699 0 0.481039 0.518729 0 0.854939 0.518729 0 0.854939 -0.0423348 -0.698077 -0.714771 -0.0423346 -0.698076 -0.714771 0.271986 -0.698075 -0.662355 0.271984 -0.698077 -0.662354 0.532432 -0.698078 -0.478751 0.532437 -0.698074 -0.478752 0.687433 -0.698073 -0.200326 0.687428 -0.698077 -0.200326 0.706269 -0.698078 0.117776 0.706272 -0.698074 0.117779 0.585227 -0.698074 0.412556 0.585227 -0.698074 0.412556 0.34827 -0.698075 0.62562 0.348269 -0.69808 0.625614 -0.0156489 -0.694746 -0.719085 -0.0156508 -0.694751 -0.719081 0.345986 -0.694752 -0.630566 0.345991 -0.694746 -0.63057 0.614924 -0.694744 -0.373095 0.614914 -0.694753 -0.373094 0.719076 -0.694755 -0.0156487 0.71908 -0.694751 -0.015647 0.630567 -0.694752 0.345984 0.630572 -0.694744 0.345991 0.373094 -0.694745 0.614923 0.373093 -0.694752 0.614915 -0.0423338 -0.698078 -0.71477 -0.042334 -0.698078 -0.714769 0.271984 -0.698077 -0.662354 0.271984 -0.698077 -0.662354 0.532433 -0.698078 -0.47875 0.532437 -0.698075 -0.478751 0.687432 -0.698074 -0.200326 0.687428 -0.698077 -0.200327 0.706269 -0.698078 0.117776 0.706272 -0.698074 0.117778 0.585226 -0.698074 0.412556 0.585227 -0.698072 0.412558 0.348271 -0.698072 0.625621 0.348271 -0.698077 0.625616 0.348271 -0.698073 0.625621 0.348271 -0.698075 0.625619 0.492297 -0.706861 0.507928 0.619967 -0.651639 0.437044 0.597953 -0.700867 0.388893 0.673284 -0.706121 0.219275 0.774256 -0.619562 0.129116 0.708156 -0.703129 0.0642205 0.698942 -0.704876 -0.120956 0.76216 -0.608097 -0.222102 0.654505 -0.704874 -0.273452 0.532439 -0.698072 -0.478753 0.654984 -0.561414 -0.505777 0.450085 -0.706121 -0.546641 0.271984 -0.698078 -0.662354 -0.0423383 -0.698083 -0.714764 -0.0423322 -0.698069 -0.714778 0.142357 -0.706855 -0.692885 0.319139 -0.637407 -0.701329 -0.0156495 0.694745 -0.719086 -0.0156495 0.694745 -0.719086 0.34599 0.694746 -0.63057 0.351771 0.527872 -0.773051 0.450094 0.70611 -0.546647 0.614925 0.69474 -0.373101 0.72234 0.408774 -0.557789 0.654503 0.704877 -0.27345 0.69894 0.704877 -0.120959 0.823732 0.566697 -0.0179242 0.373092 0.694749 0.614919 0.373098 0.694742 0.614924 0.597962 0.700855 0.388899 0.70663 0.5919 0.387723 0.673294 0.706116 0.219262 0.70816 0.703125 0.0642245 0.518722 0 0.854943 0.486392 -0.00188275 0.873738 0.838299 0.00161883 0.545208 0.817327 0 0.576175 0.950851 0 0.30965 0.986377 0.00216671 0.164486 0.995913 0 0.0903214 0.985353 0 -0.170526 0.960063 0.00243882 -0.279773 0.922706 0 -0.385504 0.791488 0 -0.611185 0.743597 0.00216701 -0.668625 0.635635 0 -0.77199 0.414178 0 -0.910196 0.379855 0.00135239 -0.925045 -0.0217578 -0.00161873 -0.999762 -0.0591249 0 -0.998251 -0.0423366 0.698069 -0.714778 -0.042334 0.698074 -0.714774 0.142359 0.706859 -0.692881 0.288132 0.651634 -0.701679 0.295431 0.700861 -0.649241 0.450093 0.706116 -0.546641 0.583692 0.619555 -0.524839 0.562803 0.703121 -0.434595 0.65451 0.704869 -0.273454 0.762161 0.608096 -0.222105 0.698944 0.704873 -0.120959 0.706274 0.698073 0.117779 0.824144 0.561427 0.0747435 0.673298 0.706112 0.219263 0.58523 0.69807 0.412559 0.34827 0.698075 0.625619 0.348274 0.69807 0.625622 0.492287 0.706855 0.507946 0.645934 0.637405 0.420099 0.486394 0 0.87374 0.518722 0.00161867 0.854942 0.695951 0 0.718089 0.8383 0 0.545209 0.876698 0.00270309 0.481033 0.950851 0 0.309649 0.995913 0 0.0903217 0.999758 0.00324667 -0.021757 0.985353 0 -0.170525 0.922706 0 -0.385505 0.854938 0.00324658 -0.51872 0.791488 0 -0.611185 0.635639 0 -0.771987 0.481036 0.00270295 -0.876697 -0.0591236 0 -0.998251 -0.0217571 0.00161871 -0.999762 0.201256 0 -0.979539 0.414177 0 -0.910196 0.348271 0.698073 0.625621 0.348275 0.698068 0.625624 0.585232 0.698068 0.412559 0.585229 0.69807 0.412559 0.706277 0.698069 0.117777 0.706273 0.698073 0.117779 0.687433 0.698073 -0.200326 0.687436 0.698069 -0.200329 0.532439 0.69807 -0.478755 0.532438 0.698074 -0.478752 0.271986 0.698073 -0.662358 0.271986 0.698073 -0.662358 -0.042334 0.698074 -0.714774 -0.0423342 0.698073 -0.714774 0.486394 0 0.87374 0.486394 0 0.87374 0.817326 0 0.576175 0.817326 0 0.576175 0.986379 0 0.164486 0.986379 0 0.164486 0.960066 0 -0.279775 0.960066 0 -0.279775 0.743599 0 -0.668625 0.743599 0 -0.668625 0.379854 0 -0.925046 0.379854 0 -0.925046 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 -0.0423317 0.698077 -0.71477 -0.0423394 0.698064 -0.714783 0.142358 0.706851 -0.69289 0.288135 0.651624 -0.701687 0.295436 0.700862 -0.649238 0.450088 0.706116 -0.546645 0.583694 0.619551 -0.52484 0.562805 0.703119 -0.434596 0.687435 0.698071 -0.200326 0.815735 0.467357 -0.340814 0.698946 0.704872 -0.120956 0.706272 0.698074 0.117779 0.824153 0.561415 0.0747398 0.673289 0.706117 0.219276 0.585228 0.698074 0.412554 0.348274 0.698068 0.625624 0.348272 0.69807 0.625623 0.4923 0.706856 0.507931 0.645927 0.637416 0.420094 0.486395 0 0.873739 0.486395 0 0.873739 0.695972 0 0.718069 0.695972 0 0.718069 0.8383 0 0.545209 0.8383 0 0.545209 0.950844 0 0.30967 0.950844 0 0.30967 0.995913 0 0.0903162 0.995913 0 0.0903162 0.985354 0 -0.170521 0.985354 0 -0.170521 0.922705 0 -0.385506 0.922705 0 -0.385506 0.791488 0 -0.611185 0.791488 0 -0.611185 0.635632 0 -0.771992 0.635632 0 -0.771992 0.414183 0 -0.910194 0.414183 0 -0.910194 0.201252 0 -0.97954 0.201252 0 -0.97954 -0.0591303 0 -0.99825 -0.0591303 0 -0.99825 0.191313 0 0.981529 0.191313 0 0.981529 0.0103802 0 0.999946 0.0103802 0 0.999946 -0.170896 0 0.985289 -0.170896 0 0.985289 -0.346519 0 0.938043 -0.346519 0 0.938043 -0.510681 0 0.85977 -0.510681 0 0.85977 -0.657952 0 0.75306 -0.657952 0 0.75306 -0.783461 0 0.621441 -0.783461 0 0.621441 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355312 0 -0.999369 -0.0355312 0 -0.999369 0.129445 0 -0.991587 0.129445 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444398 0 -0.895829 0.444398 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900922 0 -0.43398 0.900922 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.0471174 0.998889 0 0.0471174 0.977511 0 0.210887 0.977511 0 0.210887 0.929468 0 0.368904 0.929468 0 0.368904 0.856072 0 0.516857 0.856072 0 0.516857 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355312 0 -0.999369 -0.0355312 0 -0.999369 0.129445 0 -0.991587 0.129445 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444398 0 -0.895829 0.444398 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900922 0 -0.43398 0.900922 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.0471174 0.998889 0 0.0471174 0.977511 0 0.210887 0.977511 0 0.210887 0.929468 0 0.368904 0.929468 0 0.368904 0.856072 0 0.516857 0.856072 0 0.516857 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355312 0 -0.999369 -0.0355312 0 -0.999369 0.129445 0 -0.991587 0.129445 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444398 0 -0.895829 0.444398 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900922 0 -0.43398 0.900922 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.0471174 0.998889 0 0.0471174 0.977511 0 0.210887 0.977511 0 0.210887 0.929468 0 0.368904 0.929468 0 0.368904 0.856072 0 0.516857 0.856072 0 0.516857 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355312 0 -0.999369 -0.0355312 0 -0.999369 0.129445 0 -0.991587 0.129445 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444398 0 -0.895829 0.444398 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900922 0 -0.43398 0.900922 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.0471174 0.998889 0 0.0471174 0.977511 0 0.210887 0.977511 0 0.210887 0.929468 0 0.368904 0.929468 0 0.368904 0.856072 0 0.516857 0.856072 0 0.516857 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355312 0 -0.999369 -0.0355312 0 -0.999369 0.129445 0 -0.991587 0.129445 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444398 0 -0.895829 0.444398 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900922 0 -0.43398 0.900922 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.0471174 0.998889 0 0.0471174 0.977511 0 0.210887 0.977511 0 0.210887 0.929468 0 0.368904 0.929468 0 0.368904 0.856072 0 0.516857 0.856072 0 0.516857 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355312 0 -0.999369 -0.0355312 0 -0.999369 0.129445 0 -0.991587 0.129445 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444398 0 -0.895829 0.444398 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900922 0 -0.43398 0.900922 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.0471174 0.998889 0 0.0471174 0.977511 0 0.210887 0.977511 0 0.210887 0.929468 0 0.368904 0.929468 0 0.368904 0.856072 0 0.516857 0.856072 0 0.516857 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355312 0 -0.999369 -0.0355312 0 -0.999369 0.129445 0 -0.991587 0.129445 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444398 0 -0.895829 0.444398 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900922 0 -0.43398 0.900922 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.0471174 0.998889 0 0.0471174 0.977511 0 0.210887 0.977511 0 0.210887 0.929468 0 0.368904 0.929468 0 0.368904 0.856072 0 0.516857 0.856072 0 0.516857 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355312 0 -0.999369 -0.0355312 0 -0.999369 0.129445 0 -0.991587 0.129445 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444398 0 -0.895829 0.444398 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900922 0 -0.43398 0.900922 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.0471174 0.998889 0 0.0471174 0.977511 0 0.210887 0.977511 0 0.210887 0.929468 0 0.368904 0.929468 0 0.368904 0.856072 0 0.516857 0.856072 0 0.516857 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355312 0 -0.999369 -0.0355312 0 -0.999369 0.129445 0 -0.991587 0.129445 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444398 0 -0.895829 0.444398 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817204 0 -0.576348 0.817204 0 -0.576348 0.900922 0 -0.43398 0.900922 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.0471174 0.998889 0 0.0471174 0.977511 0 0.210887 0.977511 0 0.210887 0.929468 0 0.368904 0.929468 0 0.368904 0.856072 0 0.516857 0.856072 0 0.516857 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355312 0 -0.999369 -0.0355312 0 -0.999369 0.129445 0 -0.991587 0.129445 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444398 0 -0.895829 0.444398 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817205 0 -0.576348 0.817205 0 -0.576348 0.900922 0 -0.43398 0.900922 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.0471174 0.998889 0 0.0471174 0.977511 0 0.210887 0.977511 0 0.210887 0.929468 0 0.368904 0.929468 0 0.368904 0.856072 0 0.516857 0.856072 0 0.516857 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 -0.141336 -0.70589 -0.694078 -0.141335 -0.705894 -0.694073 -0.0251674 -0.705894 -0.70787 -0.025167 -0.7059 -0.707864 0.0916871 -0.7059 -0.702352 0.0916886 -0.705886 -0.702366 0.206044 -0.705886 -0.677695 0.206042 -0.705894 -0.677688 0.314775 -0.705893 -0.634532 0.314773 -0.705899 -0.634527 0.41492 -0.705899 -0.574063 0.41492 -0.705899 -0.574063 0.503749 -0.705898 -0.497941 0.50375 -0.705896 -0.497942 0.578839 -0.705896 -0.408236 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680025 -0.705901 -0.198167 0.703368 -0.705901 -0.0835357 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692381 -0.705901 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.65836 -0.705892 0.261302 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454638 -0.705902 0.543145 0.359038 -0.705902 0.610568 0.359041 -0.705897 0.610573 0.253648 -0.705897 0.661341 0.253646 -0.705902 0.661336 0.486394 0 0.87374 0.486394 0 0.87374 0.817326 0 0.576175 0.817326 0 0.576175 0.986379 0 0.164491 0.986379 0 0.164491 0.960066 0 -0.279773 0.960066 0 -0.279773 0.743599 0 -0.668626 0.743599 0 -0.668626 0.379853 0 -0.925047 0.379853 0 -0.925047 -0.0591248 0 -0.998251 -0.0591248 0 -0.998251 0.518723 0 0.854942 0.518723 0 0.854942 0.876701 0 0.481037 0.876701 0 0.481037 0.999763 0 -0.0217559 0.999763 0 -0.0217559 0.854939 0 -0.518729 0.854939 0 -0.518729 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.021756 0 -0.999763 -0.021756 0 -0.999763 0.518725 0 0.854941 0.518725 0 0.854941 0.8767 0 0.481037 0.8767 0 0.481037 0.999763 0 -0.0217559 0.999763 0 -0.0217559 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481037 0 -0.8767 0.481037 0 -0.8767 -0.0217559 0 -0.999763 -0.0217559 0 -0.999763 0.518723 0 0.854943 0.518723 0 0.854943 0.876701 0 0.481035 0.876701 0 0.481035 0.999763 0 -0.021756 0.999763 0 -0.021756 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481037 0 -0.8767 0.481037 0 -0.8767 -0.0217558 0 -0.999763 -0.0217558 0 -0.999763 0.518727 0 0.85494 0.518727 0 0.85494 0.876698 0 0.481041 0.876698 0 0.481041 0.999763 0 -0.0217602 0.999763 0 -0.0217602 0.854943 0 -0.518722 0.854943 0 -0.518722 0.481036 0 -0.876701 0.481036 0 -0.876701 -0.0217559 0 -0.999763 -0.0217559 0 -0.999763 0.486394 0 0.87374 0.518716 0.00572037 0.854927 0.817317 -0.00477864 0.576169 0.838297 0 0.545214 0.950844 0 0.309672 0.98635 -0.00765749 0.164486 0.995913 0 0.0903148 0.985352 0 -0.170534 0.960031 -0.00861713 -0.279762 0.92271 0 -0.385494 0.791485 0 -0.611189 0.743577 -0.00765688 -0.668606 0.635643 0 -0.771983 0.379856 0 -0.925046 0.414171 -0.00571996 -0.910181 -0.0591229 0.00665304 -0.998229 -0.021758 0 -0.999763 0.486394 0 0.87374 0.518716 0.00572037 0.854927 0.817318 -0.00477867 0.576167 0.838298 0 0.545213 0.950852 0 0.309647 0.986351 -0.00765651 0.164476 0.995913 0 0.0903148 0.985355 0 -0.170515 0.960031 -0.00861861 -0.279762 0.922703 0 -0.385512 0.791492 0 -0.61118 0.743577 -0.00765803 -0.668606 0.635628 0 -0.771995 0.379856 0 -0.925046 0.414176 -0.00572073 -0.910179 -0.0591235 0.00665315 -0.998228 -0.021758 0 -0.999763 0.486396 0 0.873739 0.518718 0.00572031 0.854926 0.817319 -0.00477874 0.576165 0.838299 0 0.54521 0.950844 0 0.309672 0.98635 -0.00765751 0.164485 0.995913 0 0.0903145 0.985353 0 -0.170525 0.96003 -0.00861782 -0.279763 0.922707 0 -0.385503 0.791488 0 -0.611184 0.743578 -0.00765728 -0.668605 0.63564 0 -0.771986 0.379856 0 -0.925046 0.414166 -0.00571911 -0.910183 -0.0591258 0.00665389 -0.998228 -0.0217559 0 -0.999763 0.4864 0 0.873737 0.4864 0 0.873737 0.817329 0 0.576171 0.817329 0 0.576171 0.986379 0 0.164491 0.986379 0 0.164491 0.960065 0 -0.279777 0.960065 0 -0.279777 0.743604 0 -0.668621 0.743604 0 -0.668621 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591323 0 -0.99825 -0.0591323 0 -0.99825 0.486396 0 0.873739 0.518716 0.00571997 0.854927 0.817317 -0.00477927 0.576169 0.838299 0 0.54521 0.950848 0 0.309658 0.98635 -0.00765675 0.164485 0.995913 0 0.090322 0.985353 0 -0.170525 0.960029 -0.00861819 -0.279768 0.922703 0 -0.385512 0.791488 0 -0.611184 0.743581 -0.0076569 -0.668602 0.635647 0 -0.77198 0.379854 0 -0.925046 0.414171 -0.00572027 -0.910181 -0.0591261 0.00665316 -0.998228 -0.0217602 0 -0.999763 0.264054 0.705397 0.657792 0.264054 0.705395 0.657794 0.38731 0.705396 0.59364 0.387306 0.705403 0.593634 0.495677 0.705402 0.506668 0.49568 0.705397 0.506672 0.585002 0.705397 0.400234 0.585003 0.705396 0.400234 0.651845 0.705396 0.278416 0.651844 0.705396 0.278415 0.693635 0.705396 0.145897 0.693631 0.7054 0.145896 0.708766 0.705401 0.00777235 0.708762 0.705405 0.00777218 0.69666 0.705405 -0.13065 0.696666 0.705398 -0.130651 0.657791 0.705398 -0.264053 0.657787 0.705403 -0.264052 0.593634 0.705403 -0.387306 0.593642 0.705393 -0.387311 0.506675 0.705393 -0.495683 0.506669 0.705401 -0.495677 0.400232 0.705401 -0.584999 0.400231 0.705401 -0.584999 0.278413 0.705402 -0.651839 0.278415 0.705396 -0.651844 0.145897 0.705396 -0.693635 0.145898 0.705395 -0.693637 0.00777243 0.705394 -0.708772 0.00777225 0.705398 -0.708769 -0.130651 0.705398 -0.696666 -0.130651 0.705397 -0.696667 0.253647 0.705898 0.66134 0.497328 0.707107 0.502658 0.454642 0.705896 0.543149 0.454641 0.705898 0.543148 0.397242 0.707052 0.585043 0.420597 0.558133 0.715252 0.347911 0.706363 0.616449 0.253647 0.705898 0.661341 0.572879 0.707109 0.414495 0.556463 0.704458 0.440555 0.674378 0.459592 0.577918 0.580338 0.623996 0.523294 0.506964 0.706204 0.494231 0.587282 0.706897 0.394205 0.756761 0.467501 0.456898 0.716931 0.554118 0.423039 0.677125 0.707109 0.203714 0.658353 0.7059 0.261299 0.658355 0.705897 0.2613 0.628215 0.70706 0.324672 0.656605 0.662731 0.360079 0.716129 0.686584 0.12555 0.867847 0.460203 0.187228 0.796734 0.57552 0.18437 0.688596 0.699969 0.189419 0.70716 0.707004 -0.00833346 0.829756 0.557276 0.0307841 0.881724 0.469929 0.0415907 0.704052 0.706905 0.0677993 0.700692 0.707102 0.0950596 0.704224 0.706328 -0.0718949 0.817261 0.568034 -0.0970624 0.695165 0.707059 -0.129668 0.680029 0.705896 -0.198168 0.680029 0.705896 -0.198168 0.655997 0.707059 -0.264075 0.741466 0.568031 -0.357169 0.632599 0.706332 -0.317671 0.591648 0.706685 -0.388007 0.721351 0.469925 -0.508746 0.557412 0.706905 -0.435405 0.479043 0.699967 -0.529683 0.572961 0.575522 -0.583515 0.63141 0.4602 -0.62413 0.536575 0.686584 -0.490602 0.539935 0.707102 -0.456592 0.439452 0.66122 -0.608005 0.417869 0.706048 -0.571736 0.461689 0.707107 -0.535577 0.381876 0.511456 -0.769794 0.360381 0.662724 -0.656447 0.355455 0.70706 -0.611325 0.368679 0.707103 -0.603392 0.258347 0.459591 -0.849725 0.232683 0.704459 -0.67052 0.260463 0.707105 -0.65739 0.298815 0.706508 -0.641526 0.0271457 0.707093 -0.706599 0.0916875 0.705896 -0.702356 0.0916879 0.705894 -0.702358 0.161583 0.707047 -0.688458 0.208372 0.623996 -0.753133 0.014915 0.691032 -0.72267 -0.0294821 0.55813 -0.82923 -0.0377115 0.706359 -0.706849 -0.141335 0.705894 -0.694073 -0.141335 0.705898 -0.694069 -0.0423349 0.698072 -0.714775 -0.0423351 0.698071 -0.714775 0.142356 0.706859 -0.692882 0.288133 0.651633 -0.701679 0.295432 0.700861 -0.649241 0.450098 0.706116 -0.546637 0.583688 0.619561 -0.524835 0.562799 0.703127 -0.434592 0.654499 0.704877 -0.273458 0.762167 0.60809 -0.222102 0.698946 0.704873 -0.120951 0.706273 0.698073 0.117779 0.82416 0.561404 0.0747365 0.673293 0.706112 0.219275 0.585232 0.69807 0.412555 0.348273 0.698071 0.625622 0.34827 0.698075 0.625619 0.492284 0.706862 0.50794 0.645927 0.637416 0.420094 0.486396 0 0.873738 0.518712 0.00717224 0.854919 0.695954 0 0.718086 0.8383 0 0.545209 0.876636 0.0119759 0.481005 0.950845 0 0.309667 0.995914 0 0.0903115 0.99966 0.0143834 -0.0217548 0.985355 0 -0.170513 0.922701 0 -0.385516 0.854852 0.0143838 -0.518673 0.791488 0 -0.611185 0.635645 0 -0.771981 0.481005 0.0119762 -0.876636 -0.0591248 0 -0.998251 -0.021757 0.00717254 -0.999738 0.201252 0 -0.97954 0.414178 0 -0.910196 -0.0156492 -0.694747 -0.719084 -0.0156493 -0.694747 -0.719084 0.345989 -0.694748 -0.630568 0.345989 -0.694749 -0.630568 0.614917 -0.69475 -0.373095 0.614926 -0.694741 -0.373097 0.719091 -0.694739 -0.015649 0.719083 -0.694748 -0.0156515 0.630568 -0.694749 0.345989 0.630567 -0.69475 0.345988 0.373094 -0.694749 0.614919 0.373095 -0.694747 0.61492 0.373098 0.694741 0.614925 0.373094 0.694745 0.614922 0.630569 0.694747 0.345989 0.630572 0.694745 0.345989 0.719085 0.694746 -0.0156489 0.719089 0.694742 -0.0156509 0.614924 0.694741 -0.373099 0.614921 0.694747 -0.373094 0.34599 0.694746 -0.630571 0.34599 0.694747 -0.630569 -0.0156488 0.694746 -0.719085 -0.0156499 0.694744 -0.719087 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.85494 0 -0.518726 0.85494 0 -0.518726 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.021757 0 -0.999763 -0.021757 0 -0.999763 -0.0156488 -0.694746 -0.719085 -0.0156495 -0.694749 -0.719082 0.345988 -0.69475 -0.630567 0.345989 -0.694749 -0.630568 0.614917 -0.69475 -0.373095 0.614927 -0.69474 -0.373097 0.719092 -0.694739 -0.015649 0.719083 -0.694748 -0.0156514 0.630567 -0.69475 0.345988 0.630568 -0.694749 0.345989 0.373096 -0.694746 0.614921 0.373096 -0.694745 0.614921 0.348273 0.698072 0.62562 0.348269 0.698076 0.625618 0.585224 0.698078 0.412554 0.585232 0.69807 0.412555 0.706277 0.698069 0.117778 0.706274 0.698073 0.117779 0.687432 0.698074 -0.200325 0.687429 0.698078 -0.200322 0.532435 0.698077 -0.478749 0.532436 0.698074 -0.478753 0.271986 0.698073 -0.662358 0.271986 0.698076 -0.662355 -0.0423341 0.698073 -0.714774 -0.0423364 0.698069 -0.714778 0.486397 0 0.873738 0.518712 0.0071721 0.854919 0.817312 -0.00599296 0.576165 0.8383 0 0.545209 0.950845 0 0.309667 0.986334 -0.0096016 0.164479 0.995914 0 0.0903117 0.985356 0 -0.170512 0.96001 -0.0108072 -0.279757 0.922701 0 -0.385517 0.791488 0 -0.611185 0.743567 -0.00960115 -0.668593 0.635643 0 -0.771984 0.379855 0 -0.925046 0.414169 -0.00717301 -0.910172 -0.0591215 0.00834234 -0.998216 -0.021757 0 -0.999763 0.373094 -0.694746 0.614922 0.373093 -0.694752 0.614916 0.630566 -0.694752 0.345987 0.761484 -0.418174 0.49525 0.673287 -0.706119 0.219273 0.708159 -0.703126 0.0642175 0.876469 -0.48108 -0.0190771 0.698953 -0.704866 -0.120951 0.654509 -0.704866 -0.273463 0.74951 -0.481075 -0.454755 -0.0156488 -0.694746 -0.719085 -0.0156495 -0.694749 -0.719082 0.295432 -0.700864 -0.649237 0.409095 -0.526079 -0.745575 0.450096 -0.706116 -0.546638 0.5628 -0.703126 -0.434593 0.373098 0.694744 0.614923 0.373094 0.694747 0.61492 0.630571 0.694745 0.345989 0.630569 0.694747 0.345989 0.719085 0.694746 -0.0156489 0.719085 0.694746 -0.0156489 0.614919 0.69475 -0.373092 0.614922 0.694745 -0.373096 0.34599 0.694741 -0.630576 0.345989 0.694745 -0.630571 -0.0156489 0.694746 -0.719085 -0.015647 0.694751 -0.71908 0.518726 0 0.854941 0.518726 0 0.854941 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854943 0 -0.518722 0.854943 0 -0.518722 0.481036 0 -0.876701 0.481036 0 -0.876701 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 -0.0156487 -0.694753 -0.719078 -0.0156476 -0.694749 -0.719082 0.345987 -0.694747 -0.630571 0.345992 -0.69474 -0.630576 0.614923 -0.694744 -0.373095 0.614922 -0.694746 -0.373094 0.719085 -0.694746 -0.0156489 0.719083 -0.694749 -0.0156496 0.630568 -0.69475 0.345987 0.63057 -0.694746 0.34599 0.373095 -0.694748 0.614919 0.373094 -0.694751 0.614916 -0.0423349 0.698074 -0.714773 -0.0423345 0.698075 -0.714772 0.14236 0.706859 -0.692881 0.301497 0.608289 -0.734223 0.295432 0.700865 -0.649237 0.45009 0.70612 -0.546638 0.626086 0.539528 -0.562961 0.562794 0.703133 -0.434587 0.654495 0.704883 -0.273453 0.823665 0.513775 -0.240025 0.698939 0.704879 -0.120954 0.706267 0.69808 0.117777 0.905907 0.415432 0.0821525 0.673283 0.706123 0.219272 0.585223 0.69808 0.412551 0.348271 0.698073 0.62562 0.348267 0.698079 0.625616 0.492278 0.706867 0.507938 0.681499 0.582331 0.443227 0.373096 0.694745 0.614921 0.373096 0.694746 0.614921 0.630567 0.694749 0.34599 0.630567 0.694749 0.34599 0.719083 0.694749 -0.0156496 0.719091 0.69474 -0.0156519 0.614924 0.694743 -0.373096 0.614926 0.69474 -0.373099 0.34599 0.694745 -0.630572 0.34599 0.694744 -0.630573 -0.0156497 0.694742 -0.719089 -0.0156485 0.694746 -0.719085 0.373093 0.694751 0.614917 0.373093 0.694752 0.614916 0.630565 0.694752 0.345988 0.630567 0.69475 0.345989 0.719083 0.694749 -0.0156496 0.719085 0.694746 -0.0156501 0.614921 0.694745 -0.373096 0.614917 0.694752 -0.373092 0.345989 0.694752 -0.630564 0.345991 0.694746 -0.63057 -0.0156495 0.694749 -0.719082 -0.0156519 0.69474 -0.719091 0.373094 0.694748 0.61492 0.373097 0.694745 0.614921 0.630573 0.694744 0.34599 0.630564 0.694752 0.34599 0.719078 0.694753 -0.0156489 0.719079 0.694752 -0.0156495 0.614918 0.694751 -0.37309 0.614924 0.69474 -0.373102 0.345992 0.694742 -0.630574 0.345992 0.694744 -0.630571 -0.0156492 0.694746 -0.719085 -0.0156494 0.694746 -0.719085 0.518725 0 0.854941 0.518725 0 0.854941 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.0217573 0.999763 0 -0.0217573 0.854943 0 -0.518721 0.854943 0 -0.518721 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217575 0 -0.999763 -0.0217575 0 -0.999763 -0.0156491 -0.694749 -0.719082 -0.0156493 -0.69475 -0.719081 0.34599 -0.694746 -0.63057 0.345993 -0.694742 -0.630573 0.614931 -0.694736 -0.373098 0.614913 -0.694754 -0.373094 0.719076 -0.694755 -0.0156488 0.719072 -0.69476 -0.0156503 0.63056 -0.694759 0.345983 0.63057 -0.694745 0.345994 0.373095 -0.694746 0.614921 0.373094 -0.694753 0.614914 0.373097 0.694742 0.614924 0.373097 0.694743 0.614924 0.630574 0.694743 0.345991 0.630576 0.694741 0.345991 0.719089 0.694742 -0.0156491 0.71909 0.694741 -0.0156497 0.614924 0.69474 -0.373101 0.61492 0.694747 -0.373094 0.345989 0.694745 -0.630571 0.345989 0.694751 -0.630566 -0.0156491 0.694747 -0.719084 -0.0156495 0.694746 -0.719085 0.518725 0 0.854941 0.518725 0 0.854941 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.0217572 0.999763 0 -0.0217572 0.854939 0 -0.518728 0.854939 0 -0.518728 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217574 0 -0.999763 -0.0217574 0 -0.999763 -0.0156491 -0.694746 -0.719085 -0.0156505 -0.69475 -0.719081 0.345984 -0.694756 -0.630562 0.345992 -0.694746 -0.630569 0.614916 -0.69475 -0.373096 0.614928 -0.694738 -0.373099 0.719094 -0.694737 -0.0156492 0.719089 -0.694742 -0.0156507 0.630576 -0.694739 0.345992 0.630572 -0.694746 0.345987 0.373094 -0.694749 0.614918 0.373096 -0.694741 0.614926 0.373101 0.69474 0.614924 0.373094 0.694747 0.61492 0.630571 0.694746 0.345989 0.630571 0.694746 0.345989 0.719084 0.694747 -0.0156489 0.719085 0.694746 -0.0156497 0.614924 0.694742 -0.373097 0.614921 0.694747 -0.373093 0.345989 0.694745 -0.630571 0.345989 0.694744 -0.630573 -0.0156491 0.694742 -0.719089 -0.0156497 0.694741 -0.71909 0.518728 0 0.854939 0.518728 0 0.854939 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.0217572 0.999763 0 -0.0217572 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217573 0 -0.999763 -0.0217573 0 -0.999763 -0.0156492 -0.694737 -0.719094 -0.0156507 -0.694741 -0.719089 0.34599 -0.694744 -0.630573 0.345989 -0.694746 -0.630571 0.614918 -0.694749 -0.373094 0.614919 -0.694749 -0.373094 0.719076 -0.694755 -0.0156488 0.71908 -0.694751 -0.0156475 0.63057 -0.694748 0.345988 0.630565 -0.694754 0.345984 0.373094 -0.694754 0.614913 0.373097 -0.694738 0.614929 0.486394 0 0.873739 0.51864 0.0178257 0.854807 0.695951 0 0.71809 0.838301 0 0.545207 0.876312 0.0297572 0.480825 0.950845 0 0.309667 0.995913 0 0.0903148 0.999125 0.0357353 -0.0217442 0.985354 0 -0.170519 0.922703 0 -0.385512 0.854396 0.0357351 -0.518393 0.791489 0 -0.611184 0.635638 0 -0.771988 0.480826 0.0297573 -0.876311 -0.0591244 0 -0.998251 -0.0217542 0.0178263 -0.999604 0.201257 0 -0.979539 0.41418 0 -0.910195 0.518725 0 0.854941 0.518725 0 0.854941 0.876698 0 0.481041 0.876698 0 0.481041 0.999763 0 -0.0217581 0.999763 0 -0.0217581 0.854942 0 -0.518724 0.854942 0 -0.518724 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217581 0 -0.999763 -0.0217581 0 -0.999763 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.48104 0.876699 0 0.48104 0.999763 0 -0.0217581 0.999763 0 -0.0217581 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481042 0 -0.876698 0.481042 0 -0.876698 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.373098 0.694741 0.614925 0.373094 0.694745 0.614922 0.630569 0.694747 0.345989 0.630572 0.694745 0.345989 0.719085 0.694746 -0.0156489 0.719089 0.694742 -0.0156509 0.614926 0.694741 -0.373096 0.614926 0.694741 -0.373096 0.345989 0.694745 -0.630572 0.345989 0.694747 -0.630569 -0.0156489 0.694746 -0.719085 -0.015649 0.694746 -0.719085 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854943 0 -0.518723 0.854943 0 -0.518723 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 -0.0156489 -0.694746 -0.719085 -0.0156496 -0.694749 -0.719083 0.345987 -0.69475 -0.630568 0.34599 -0.694745 -0.630571 0.614927 -0.69474 -0.373097 0.614916 -0.694751 -0.373094 0.719078 -0.694753 -0.0156487 0.719082 -0.694749 -0.0156476 0.63057 -0.694746 0.34599 0.630569 -0.694748 0.345988 0.373096 -0.694746 0.614921 0.373096 -0.694745 0.614921 -0.0156509 0.694742 -0.719089 -0.0156489 0.694746 -0.719085 0.345989 0.694745 -0.630572 0.35177 0.527877 -0.773048 0.450095 0.706119 -0.546636 0.614919 0.694749 -0.373092 0.722343 0.40876 -0.557796 0.654507 0.704872 -0.273452 0.698944 0.704873 -0.120959 0.823734 0.566693 -0.0179264 0.37309 0.694752 0.614918 0.373101 0.69474 0.614925 0.597962 0.700856 0.388899 0.706628 0.591903 0.387722 0.673292 0.706117 0.219265 0.70816 0.703125 0.064225 0.518722 0 0.854943 0.486378 -0.00834147 0.873708 0.838279 0.00717338 0.545195 0.817325 0 0.576176 0.950849 0 0.309655 0.986333 0.00960065 0.164483 0.995913 0 0.0903221 0.985353 0 -0.170525 0.96001 0.010806 -0.279757 0.922706 0 -0.385505 0.791485 0 -0.611188 0.743565 0.00960102 -0.668595 0.635644 0 -0.771983 0.414178 0 -0.910196 0.379848 0.00599266 -0.92503 -0.0217565 -0.00717239 -0.999738 -0.0591236 0 -0.998251 -0.0423336 -0.69808 -0.714767 -0.0423324 -0.698076 -0.714771 0.271985 -0.698076 -0.662355 0.271986 -0.698075 -0.662356 0.532436 -0.698074 -0.478753 0.532435 -0.698076 -0.478752 0.687433 -0.698073 -0.200326 0.687429 -0.698076 -0.200326 0.706275 -0.698071 0.11778 0.706274 -0.698073 0.117779 0.58523 -0.698069 0.41256 0.585225 -0.698078 0.412552 0.34827 -0.698078 0.625616 0.34827 -0.698078 0.625616 0.34827 0.698076 0.625618 0.348269 0.698078 0.625616 0.585224 0.698077 0.412555 0.585231 0.69807 0.412557 0.706277 0.698069 0.117778 0.706274 0.698073 0.117779 0.687432 0.698074 -0.200325 0.687432 0.698073 -0.200326 0.532437 0.698074 -0.478752 0.532438 0.698074 -0.478752 0.271985 0.698073 -0.662358 0.271985 0.698074 -0.662357 -0.0423341 0.698073 -0.714774 -0.0423365 0.698069 -0.714778 0.486395 0 0.873739 0.51871 0.00717197 0.854921 0.817311 -0.00599274 0.576166 0.838298 0 0.545212 0.950849 0 0.309655 0.986334 -0.00960086 0.164479 0.995913 0 0.0903172 0.985354 0 -0.170519 0.96001 -0.0108066 -0.279757 0.922703 0 -0.385511 0.791488 0 -0.611185 0.743567 -0.00960118 -0.668593 0.635644 0 -0.771983 0.379853 0 -0.925047 0.414166 -0.00717263 -0.910173 -0.0591215 0.0083423 -0.998216 -0.0217571 0 -0.999763 0.373094 -0.694751 0.614916 0.373097 -0.69474 0.614927 0.630571 -0.694745 0.34599 0.761492 -0.418149 0.495259 0.67329 -0.706119 0.219265 0.708158 -0.703127 0.0642213 0.876472 -0.481074 -0.0190749 0.698946 -0.704872 -0.120955 0.654505 -0.704872 -0.273456 0.74951 -0.481073 -0.454756 -0.0156487 -0.694753 -0.719078 -0.0156476 -0.694749 -0.719082 0.29543 -0.700865 -0.649238 0.409094 -0.526076 -0.745578 0.450096 -0.706117 -0.546637 0.562801 -0.703124 -0.434593 -0.0156509 0.694742 -0.719089 -0.0156489 0.694746 -0.719085 0.345989 0.694746 -0.63057 0.35177 0.527873 -0.773051 0.450097 0.706117 -0.546637 0.614921 0.694746 -0.373095 0.722341 0.408769 -0.557791 0.654507 0.704871 -0.273456 0.698946 0.704871 -0.120957 0.823732 0.566696 -0.0179269 0.373092 0.69475 0.614918 0.3731 0.69474 0.614925 0.597961 0.700857 0.388899 0.706627 0.591904 0.387722 0.673292 0.706116 0.21927 0.708162 0.703124 0.0642221 0.518722 0 0.854943 0.486378 -0.00834171 0.873709 0.838278 0.00717295 0.545196 0.817326 0 0.576175 0.950847 0 0.309661 0.986333 0.0096011 0.164482 0.995913 0 0.0903178 0.985354 0 -0.170521 0.96001 0.0108064 -0.279758 0.922704 0 -0.38551 0.791487 0 -0.611186 0.743567 0.00960111 -0.668593 0.635644 0 -0.771982 0.414177 0 -0.910196 0.379847 0.00599258 -0.92503 -0.0217565 -0.00717239 -0.999738 -0.0591236 0 -0.998251 -0.0423337 -0.69808 -0.714767 -0.0423325 -0.698076 -0.714771 0.271984 -0.698076 -0.662356 0.271985 -0.698075 -0.662356 0.532437 -0.698075 -0.478751 0.532433 -0.698079 -0.47875 0.687429 -0.698077 -0.200325 0.687429 -0.698077 -0.200325 0.706275 -0.698072 0.117779 0.706274 -0.698073 0.117779 0.585231 -0.698069 0.412559 0.585226 -0.698076 0.412553 0.34827 -0.698076 0.625618 0.34827 -0.698079 0.625615 -0.0423354 0.698073 -0.714774 -0.0423347 0.698075 -0.714772 0.142358 0.706863 -0.692878 0.301495 0.608297 -0.734218 0.29543 0.700865 -0.649237 0.450091 0.706121 -0.546637 0.626091 0.539524 -0.56296 0.562803 0.703122 -0.434594 0.654506 0.704871 -0.273458 0.823678 0.513751 -0.240029 0.698951 0.704867 -0.120956 0.706281 0.698066 0.117779 0.905899 0.415447 0.0821595 0.6733 0.706109 0.219266 0.585233 0.698067 0.412558 0.348268 0.698079 0.625616 0.348271 0.698074 0.625619 0.492297 0.706859 0.507931 0.681491 0.582339 0.443229 -0.0156483 0.694753 -0.719078 -0.0156496 0.694749 -0.719082 0.319896 0.698176 -0.640481 0.302061 0.778264 -0.550513 0.373093 0.694751 0.614917 0.373093 0.694752 0.614916 0.630565 0.694752 0.345988 0.630573 0.694744 0.34599 0.719089 0.694742 -0.0156497 0.719085 0.694746 -0.0156485 0.614916 0.694753 -0.373091 0.614926 0.694739 -0.373101 0.469104 0.706834 -0.529459 -0.120954 0.704879 -0.698939 -0.0347574 0.808958 -0.586838 0.348275 0.698067 0.625625 0.348269 0.698076 0.625619 0.585226 0.698075 0.412554 0.585225 0.698077 0.412554 0.706272 0.698075 0.117778 0.706272 0.698075 0.117778 0.687432 0.698074 -0.200326 0.68743 0.698076 -0.200325 0.532433 0.698078 -0.47875 0.532435 0.698075 -0.478753 0.271985 0.698075 -0.662356 0.271985 0.698075 -0.662355 0.0376066 0.704875 -0.708334 0.373091 0.694749 0.614921 0.373097 0.694743 0.614924 0.630574 0.694743 0.345991 0.630576 0.694741 0.345991 0.719089 0.694742 -0.0156491 0.71909 0.694741 -0.0156497 0.614924 0.69474 -0.373101 0.61492 0.694747 -0.373094 0.345989 0.694745 -0.630571 0.345989 0.694746 -0.630571 -0.0156489 0.694747 -0.719084 -0.0156497 0.694746 -0.719085 0.518721 0 0.854944 0.518721 0 0.854944 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.0217572 0.999763 0 -0.0217572 0.854939 0 -0.518728 0.854939 0 -0.518728 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217572 0 -0.999763 -0.0217572 0 -0.999763 -0.015649 -0.694746 -0.719085 -0.0156506 -0.694751 -0.71908 0.345988 -0.694748 -0.63057 0.34599 -0.694746 -0.630571 0.614916 -0.69475 -0.373096 0.614928 -0.694738 -0.373099 0.719094 -0.694737 -0.0156492 0.719089 -0.694742 -0.0156507 0.630576 -0.694739 0.345992 0.630575 -0.694741 0.345991 0.373095 -0.694741 0.614927 0.373093 -0.69475 0.614917 -0.0423345 0.698079 -0.714768 -0.042334 0.69808 -0.714768 0.142353 0.706866 -0.692876 0.283932 0.664301 -0.691438 0.295433 0.700861 -0.649241 0.450094 0.706115 -0.546642 0.570274 0.641756 -0.512773 0.562804 0.703116 -0.434602 0.654513 0.704866 -0.273453 0.742578 0.633837 -0.216398 0.698947 0.70487 -0.12096 0.706276 0.69807 0.117778 0.796969 0.59968 0.072277 0.673293 0.706114 0.219273 0.585231 0.698069 0.412558 0.348269 0.698077 0.625617 0.348276 0.698071 0.62562 0.492284 0.706856 0.507948 0.634728 0.653229 0.41281 0.486394 0 0.873739 0.518701 0.008893 0.854909 0.695948 0 0.718092 0.8383 0 0.545209 0.876603 0.0148496 0.480985 0.950846 0 0.309664 0.995913 0 0.0903191 0.999604 0.0178359 -0.0217537 0.985353 0 -0.170526 0.922706 0 -0.385504 0.854805 0.0178362 -0.518642 0.791484 0 -0.61119 0.635638 0 -0.771987 0.480985 0.0148494 -0.876603 -0.0591241 0 -0.998251 -0.0217564 0.00889366 -0.999724 0.201249 0 -0.97954 0.414178 0 -0.910196 -0.0156489 -0.694755 -0.719076 -0.0156503 -0.69476 -0.719072 0.345983 -0.69476 -0.630559 0.345993 -0.694746 -0.630568 0.614918 -0.694749 -0.373094 0.614917 -0.69475 -0.373094 0.719085 -0.694746 -0.015649 0.71908 -0.694751 -0.0156504 0.63057 -0.694748 0.345988 0.630571 -0.694746 0.34599 0.373092 -0.694749 0.61492 0.373091 -0.694754 0.614915 0.348273 0.698068 0.625625 0.34827 0.698072 0.625623 0.58523 0.698072 0.412554 0.585228 0.698074 0.412554 0.706273 0.698073 0.117779 0.706274 0.698073 0.117779 0.687432 0.698073 -0.200326 0.687432 0.698074 -0.200325 0.532437 0.698076 -0.478749 0.532438 0.698073 -0.478752 0.271986 0.698073 -0.662357 0.271985 0.698069 -0.662362 -0.0423422 0.698068 -0.714778 -0.0423345 0.698079 -0.714768 0.486394 0 0.873739 0.486394 0 0.873739 0.817329 0 0.576171 0.817329 0 0.576171 0.986379 0 0.16449 0.986379 0 0.16449 0.960066 0 -0.279774 0.960066 0 -0.279774 0.743602 0 -0.668622 0.743602 0 -0.668622 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591346 0 -0.99825 -0.0591346 0 -0.99825 -0.0423413 -0.698083 -0.714764 -0.0423363 -0.698069 -0.714778 0.271988 -0.698069 -0.662361 0.271982 -0.698077 -0.662356 0.532437 -0.698076 -0.478749 0.532441 -0.698072 -0.47875 0.687431 -0.698074 -0.200325 0.687431 -0.698075 -0.200326 0.706269 -0.698077 0.117778 0.706269 -0.698078 0.117778 0.585222 -0.698082 0.412549 0.585223 -0.69808 0.412551 0.348267 -0.698082 0.625613 0.348267 -0.698082 0.625613 0.486394 0 0.87374 0.518643 0.0178272 0.854805 0.69597 0 0.718071 0.838298 0 0.545213 0.876311 0.0297597 0.480825 0.95085 0 0.309652 0.995913 0 0.0903232 0.999125 0.0357365 -0.0217393 0.985354 0 -0.170519 0.922702 0 -0.385513 0.854395 0.0357349 -0.518394 0.791489 0 -0.611184 0.635639 0 -0.771986 0.480825 0.029758 -0.876311 -0.0591247 0 -0.998251 -0.0217546 0.0178262 -0.999604 0.201255 0 -0.979539 0.414177 0 -0.910196 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.48104 0.876699 0 0.48104 0.999763 0 -0.0217581 0.999763 0 -0.0217581 0.854943 0 -0.518723 0.854943 0 -0.518723 0.481037 0 -0.8767 0.481037 0 -0.8767 -0.0217581 0 -0.999763 -0.0217581 0 -0.999763 0.486396 0 0.873739 0.486396 0 0.873739 0.817327 0 0.576174 0.817327 0 0.576174 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279775 0.960066 0 -0.279775 0.743599 0 -0.668626 0.743599 0 -0.668626 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 -0.0423366 0.698069 -0.714778 -0.042334 0.698074 -0.714774 0.142359 0.706859 -0.692881 0.288134 0.651633 -0.701679 0.295434 0.700862 -0.64924 0.450096 0.706116 -0.546639 0.583687 0.619561 -0.524836 0.5628 0.703121 -0.4346 0.687436 0.698069 -0.200329 0.815731 0.467366 -0.340811 0.698944 0.704873 -0.120959 0.706274 0.698073 0.117779 0.824144 0.561427 0.0747435 0.673285 0.706121 0.219273 0.585224 0.698077 0.412554 0.348271 0.698072 0.625621 0.348272 0.698072 0.625622 0.4923 0.706857 0.507932 0.645927 0.637416 0.420094 0.486394 0 0.87374 0.518712 0.00717277 0.854919 0.695971 0 0.71807 0.8383 0 0.545209 0.876636 0.0119759 0.481005 0.950845 0 0.309667 0.995913 0 0.0903217 0.99966 0.0143847 -0.0217548 0.985353 0 -0.170525 0.922706 0 -0.385505 0.854851 0.0143848 -0.518673 0.791483 0 -0.611191 0.635643 0 -0.771984 0.481006 0.0119759 -0.876636 -0.0591236 0 -0.998251 -0.0217566 0.00717238 -0.999738 0.201256 0 -0.979539 0.41418 0 -0.910195 -0.0156489 -0.694746 -0.719085 -0.0156496 -0.694749 -0.719083 0.345989 -0.694749 -0.630567 0.345992 -0.694746 -0.630569 0.614918 -0.694748 -0.373096 0.614915 -0.694751 -0.373095 0.719078 -0.694753 -0.0156487 0.719082 -0.694749 -0.0156476 0.630567 -0.69475 0.345988 0.630566 -0.694752 0.345987 0.373093 -0.694752 0.614916 0.373094 -0.694746 0.614922 0.348274 0.698068 0.625624 0.348272 0.69807 0.625623 0.585231 0.698071 0.412555 0.585228 0.698074 0.412554 0.706272 0.698074 0.117779 0.706274 0.698073 0.117779 0.687432 0.698074 -0.200325 0.687432 0.698073 -0.200326 0.532437 0.698074 -0.478752 0.532438 0.698074 -0.478752 0.271985 0.698073 -0.662358 0.271985 0.698074 -0.662357 -0.0423341 0.698073 -0.714774 -0.0423365 0.698069 -0.714778 0.486395 0 0.873739 0.486395 0 0.873739 0.817329 0 0.576171 0.817329 0 0.576171 0.986379 0 0.16449 0.986379 0 0.16449 0.960066 0 -0.279774 0.960066 0 -0.279774 0.743601 0 -0.668624 0.743601 0 -0.668624 0.379853 0 -0.925047 0.379853 0 -0.925047 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 -0.0423345 -0.698066 -0.714781 -0.042337 -0.698075 -0.714772 0.271984 -0.698076 -0.662356 0.271985 -0.698074 -0.662357 0.532437 -0.698074 -0.478752 0.532439 -0.698072 -0.478752 0.687431 -0.698075 -0.200325 0.687433 -0.698073 -0.200325 0.706273 -0.698073 0.117779 0.706272 -0.698075 0.117779 0.585226 -0.698077 0.412552 0.585229 -0.698072 0.412555 0.348271 -0.698074 0.625619 0.348273 -0.698067 0.625627 0.373099 0.694741 0.614924 0.373093 0.694748 0.61492 0.630569 0.694748 0.34599 0.630575 0.694741 0.345991 0.719087 0.694744 -0.0156499 0.719085 0.694746 -0.015649 0.614922 0.694745 -0.373096 0.61492 0.694747 -0.373094 0.345989 0.694748 -0.630568 0.345989 0.694747 -0.630569 -0.0156489 0.694746 -0.719085 -0.0156509 0.694742 -0.719089 0.518726 0 0.85494 0.518726 0 0.85494 0.876699 0 0.48104 0.876699 0 0.48104 0.999763 0 -0.0217585 0.999763 0 -0.0217585 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 -0.0156491 -0.694739 -0.719091 -0.0156514 -0.694748 -0.719083 0.345988 -0.69475 -0.630567 0.345988 -0.69475 -0.630567 0.614919 -0.694749 -0.373094 0.614922 -0.694746 -0.373095 0.719085 -0.694746 -0.0156499 0.719086 -0.694745 -0.0156496 0.63057 -0.694746 0.34599 0.630568 -0.694749 0.345989 0.373095 -0.69475 0.614917 0.373097 -0.69474 0.614927 -0.0423365 0.698069 -0.714778 -0.042334 0.698074 -0.714774 0.142357 0.706859 -0.692882 0.288133 0.651633 -0.70168 0.295432 0.70086 -0.649242 0.450098 0.706115 -0.546638 0.583689 0.619559 -0.524837 0.562801 0.703124 -0.434594 0.687433 0.698073 -0.200326 0.815736 0.467352 -0.340818 0.698946 0.704872 -0.120956 0.706275 0.698072 0.117779 0.824152 0.561415 0.0747403 0.673291 0.706115 0.219274 0.585229 0.698072 0.412556 0.348274 0.698069 0.625624 0.348273 0.69807 0.625623 0.492299 0.706856 0.507934 0.645928 0.637414 0.420095 0.486395 0 0.873739 0.518713 0.00717285 0.854918 0.695969 0 0.718072 0.8383 0 0.545209 0.876636 0.0119758 0.481005 0.950845 0 0.309667 0.995913 0 0.0903169 0.99966 0.0143842 -0.0217553 0.985354 0 -0.170521 0.922704 0 -0.38551 0.854853 0.0143841 -0.518672 0.791487 0 -0.611186 0.635645 0 -0.771982 0.481005 0.0119763 -0.876636 -0.0591236 0 -0.998251 -0.0217565 0.00717239 -0.999738 0.201253 0 -0.979539 0.414177 0 -0.910196 -0.015649 -0.694739 -0.719091 -0.0156515 -0.694748 -0.719083 0.345989 -0.694748 -0.630568 0.345988 -0.69475 -0.630567 0.614918 -0.694749 -0.373094 0.614921 -0.694746 -0.373095 0.719084 -0.694747 -0.0156492 0.719084 -0.694747 -0.0156493 0.630568 -0.694748 0.345989 0.630568 -0.694749 0.345989 0.373095 -0.69475 0.614917 0.373097 -0.694741 0.614926 0.348271 0.698073 0.625621 0.348274 0.698068 0.625624 0.585234 0.698068 0.412555 0.585221 0.698082 0.41255 0.706264 0.698082 0.117781 0.70628 0.698067 0.117779 0.687439 0.698066 -0.200328 0.687435 0.698071 -0.200326 0.532438 0.698071 -0.478755 0.532439 0.698069 -0.478757 0.271986 0.698072 -0.662359 0.271986 0.698073 -0.662358 -0.0423347 0.698076 -0.714771 -0.0423334 0.69808 -0.714767 0.373099 0.694739 0.614926 0.373099 0.69474 0.614926 0.630572 0.694745 0.34599 0.630567 0.69475 0.345989 0.719083 0.694749 -0.0156496 0.719085 0.694746 -0.0156501 0.614921 0.694745 -0.373096 0.614921 0.694746 -0.373096 0.345988 0.694748 -0.630569 0.345989 0.694746 -0.630571 -0.0156461 0.694749 -0.719082 -0.0156487 0.694739 -0.719092 0.373098 0.69474 0.614926 0.373091 0.69475 0.614919 0.630568 0.694749 0.345989 0.630574 0.694742 0.34599 0.719083 0.694748 -0.0156493 0.719083 0.694748 -0.0156493 0.61492 0.694747 -0.373095 0.614919 0.694749 -0.373094 0.345987 0.69475 -0.630567 0.345987 0.694748 -0.630569 -0.0156495 0.694749 -0.719082 -0.0156484 0.694753 -0.719078 -0.042335 0.698073 -0.714774 -0.0423339 0.698075 -0.714773 0.142359 0.706859 -0.692881 0.283929 0.664297 -0.691443 0.295433 0.700865 -0.649236 0.450091 0.706121 -0.546636 0.570271 0.641764 -0.512767 0.562801 0.703124 -0.434593 0.654506 0.704873 -0.273451 0.742574 0.633843 -0.216395 0.698943 0.704874 -0.120959 0.70627 0.698076 0.11778 0.796968 0.599681 0.0722774 0.673298 0.706112 0.219263 0.58523 0.698071 0.412557 0.348269 0.698075 0.62562 0.348273 0.698071 0.625622 0.492308 0.706855 0.507926 0.634718 0.65324 0.412809 0.486392 0 0.873741 0.518704 0.00889461 0.854907 0.695981 0 0.71806 0.838297 0 0.545213 0.876603 0.0148508 0.480985 0.950851 0 0.30965 0.995913 0 0.0903198 0.999604 0.0178359 -0.0217538 0.985353 0 -0.170526 0.922706 0 -0.385504 0.854807 0.0178357 -0.518639 0.791488 0 -0.611185 0.63564 0 -0.771985 0.480989 0.0148496 -0.876601 -0.0591234 0 -0.998251 -0.0217563 0.00889363 -0.999724 0.201256 0 -0.979539 0.414181 0 -0.910195 -0.015649 -0.694746 -0.719085 -0.0156506 -0.694751 -0.71908 0.345991 -0.694747 -0.630569 0.345986 -0.694754 -0.630564 0.614916 -0.694754 -0.373089 0.614916 -0.694754 -0.373089 0.719076 -0.694755 -0.0156489 0.719072 -0.69476 -0.0156503 0.630559 -0.69476 0.345983 0.630558 -0.694762 0.345981 0.373089 -0.694759 0.61491 0.373091 -0.694751 0.614918 0.373101 0.69474 0.614924 0.373094 0.694747 0.61492 0.630571 0.694746 0.345989 0.630571 0.694746 0.345989 0.719084 0.694747 -0.0156491 0.719085 0.694746 -0.0156496 0.614921 0.694749 -0.373091 0.614921 0.694747 -0.373093 0.345989 0.694745 -0.630571 0.345989 0.694744 -0.630573 -0.0156491 0.694742 -0.719089 -0.0156496 0.694741 -0.71909 0.518728 0 0.854939 0.518728 0 0.854939 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.0217574 0.999763 0 -0.0217574 0.854944 0 -0.518721 0.854944 0 -0.518721 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217573 0 -0.999763 -0.0217573 0 -0.999763 -0.0156492 -0.694737 -0.719094 -0.0156507 -0.694741 -0.719089 0.34599 -0.694744 -0.630573 0.345989 -0.694746 -0.630571 0.61492 -0.694749 -0.373091 0.614911 -0.694758 -0.373089 0.719076 -0.694755 -0.0156489 0.71908 -0.694751 -0.0156474 0.630562 -0.694756 0.345984 0.630564 -0.694754 0.345986 0.373094 -0.694754 0.614913 0.373097 -0.694738 0.614929 0.373095 0.694742 0.614926 0.373098 0.694739 0.614927 0.630576 0.694742 0.345989 0.630567 0.69475 0.345989 0.719085 0.694746 -0.0156495 0.719085 0.694746 -0.0156494 0.61492 0.694748 -0.373094 0.614921 0.694745 -0.373097 0.34599 0.694744 -0.630573 0.34599 0.694752 -0.630564 -0.0156489 0.694753 -0.719078 -0.0156495 0.694752 -0.719079 0.518721 0 0.854943 0.518721 0 0.854943 0.876701 0 0.481035 0.876701 0 0.481035 0.999763 0 -0.021758 0.999763 0 -0.021758 0.854941 0 -0.518724 0.854941 0 -0.518724 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217573 0 -0.999763 -0.0217573 0 -0.999763 -0.0156488 -0.694755 -0.719076 -0.0156503 -0.69476 -0.719071 0.345983 -0.694759 -0.63056 0.345982 -0.69476 -0.630559 0.614913 -0.694756 -0.37309 0.614915 -0.694754 -0.373091 0.719081 -0.69475 -0.0156495 0.719082 -0.694749 -0.0156493 0.630564 -0.694756 0.345983 0.630573 -0.694742 0.345993 0.373098 -0.694736 0.614931 0.373094 -0.694754 0.614913 0.486394 0 0.87374 0.486394 0 0.87374 0.817331 0 0.576169 0.817331 0 0.576169 0.986378 0 0.164494 0.986378 0 0.164494 0.960066 0 -0.279775 0.960066 0 -0.279775 0.743599 0 -0.668626 0.743599 0 -0.668626 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 0.518725 0 0.854941 0.518725 0 0.854941 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.0217581 0.999763 0 -0.0217581 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217532 0 -0.999763 -0.0217532 0 -0.999763 0.518724 0 0.854942 0.518724 0 0.854942 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217577 0.999763 0 -0.0217577 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.348269 0.698076 0.625619 0.348274 0.69807 0.625622 0.585231 0.698069 0.412558 0.58523 0.69807 0.412558 0.706277 0.698069 0.117777 0.706273 0.698073 0.117779 0.687433 0.698073 -0.200326 0.687436 0.698069 -0.200329 0.532439 0.698069 -0.478757 0.532437 0.698074 -0.478752 0.271987 0.698073 -0.662357 0.271987 0.698071 -0.66236 -0.042335 0.698072 -0.714775 -0.0423348 0.698072 -0.714775 0.486393 0 0.87374 0.486393 0 0.87374 0.817327 0 0.576175 0.817327 0 0.576175 0.986379 0 0.164487 0.986379 0 0.164487 0.960066 0 -0.279774 0.960066 0 -0.279774 0.743598 0 -0.668626 0.743598 0 -0.668626 0.379856 0 -0.925046 0.379856 0 -0.925046 -0.0591248 0 -0.998251 -0.0591248 0 -0.998251 -0.0423349 -0.698075 -0.714772 -0.0423347 -0.698074 -0.714773 0.271985 -0.698077 -0.662353 0.271985 -0.698077 -0.662354 0.532432 -0.698079 -0.47875 0.532439 -0.698071 -0.478753 0.687435 -0.698071 -0.200326 0.687426 -0.698079 -0.200327 0.706267 -0.69808 0.117776 0.706278 -0.698068 0.117782 0.585231 -0.698069 0.412559 0.58523 -0.698071 0.412557 0.348271 -0.698072 0.625622 0.348271 -0.698073 0.625621 -0.0156509 0.694742 -0.719089 -0.0462966 0.621962 -0.781678 0.142359 0.70686 -0.692881 0.345991 0.694747 -0.630569 0.351772 0.527865 -0.773055 0.450097 0.70611 -0.546646 0.614925 0.69474 -0.373101 0.72234 0.408774 -0.557789 0.654503 0.704876 -0.273451 0.69894 0.704877 -0.120958 0.823731 0.566697 -0.0179242 0.70816 0.703125 0.0642247 0.673293 0.706117 0.219261 0.70663 0.5919 0.387723 0.34827 0.698075 0.625619 0.39969 0.637413 0.658751 0.492289 0.706853 0.507948 0.597963 0.700855 0.3889 0.486394 0 0.87374 0.486394 0 0.87374 0.695951 0 0.718089 0.695951 0 0.718089 0.8383 0 0.545209 0.8383 0 0.545209 0.950851 0 0.309649 0.950851 0 0.309649 0.995913 0 0.0903217 0.995913 0 0.0903217 0.985353 0 -0.170525 0.985353 0 -0.170525 0.922706 0 -0.385505 0.922706 0 -0.385505 0.791488 0 -0.611185 0.791488 0 -0.611185 0.635639 0 -0.771987 0.635639 0 -0.771987 0.414177 0 -0.910196 0.414177 0 -0.910196 0.201256 0 -0.979539 0.201256 0 -0.979539 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.373095 -0.694745 0.614922 0.395918 -0.580885 0.711211 0.492289 -0.706853 0.507948 0.630577 -0.694738 0.345993 0.761493 -0.41815 0.495256 0.673291 -0.706119 0.21926 0.708158 -0.703127 0.0642245 0.876475 -0.481069 -0.0190726 0.698938 -0.704879 -0.120958 0.654501 -0.704879 -0.27345 0.749509 -0.481078 -0.454753 0.562797 -0.70313 -0.43459 0.45009 -0.706121 -0.546637 0.40909 -0.526084 -0.745575 -0.0423341 -0.698073 -0.714774 -0.0173403 -0.604035 -0.796769 0.142359 -0.706862 -0.692878 0.29543 -0.700865 -0.649238 0.348271 0.698073 0.625621 0.348275 0.698068 0.625624 0.585232 0.698068 0.412559 0.585229 0.69807 0.412559 0.706277 0.698069 0.117777 0.706273 0.698073 0.117779 0.687433 0.698073 -0.200326 0.687436 0.698069 -0.200329 0.532439 0.69807 -0.478755 0.532438 0.698074 -0.478752 0.271986 0.698073 -0.662358 0.271986 0.698073 -0.662358 -0.042334 0.698074 -0.714774 -0.0423342 0.698073 -0.714774 0.486394 0 0.87374 0.486394 0 0.87374 0.817326 0 0.576175 0.817326 0 0.576175 0.986379 0 0.164486 0.986379 0 0.164486 0.960066 0 -0.279775 0.960066 0 -0.279775 0.743599 0 -0.668625 0.743599 0 -0.668625 0.379854 0 -0.925046 0.379854 0 -0.925046 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 -0.0423341 -0.698073 -0.714774 -0.0423346 -0.698075 -0.714772 0.271984 -0.698078 -0.662353 0.271985 -0.698077 -0.662354 0.532432 -0.698079 -0.478749 0.532436 -0.698076 -0.478751 0.687433 -0.698073 -0.200326 0.687426 -0.698079 -0.200326 0.706267 -0.69808 0.117775 0.706279 -0.698067 0.117782 0.585232 -0.698067 0.41256 0.585229 -0.698072 0.412555 0.34827 -0.698074 0.62562 0.348271 -0.698073 0.625621 -0.0423317 0.698077 -0.71477 -0.0423394 0.698064 -0.714783 0.142358 0.706851 -0.69289 0.288135 0.651624 -0.701687 0.295436 0.700862 -0.649238 0.450088 0.706116 -0.546645 0.583694 0.619551 -0.52484 0.562805 0.703119 -0.434596 0.687435 0.698071 -0.200326 0.815735 0.467357 -0.340814 0.698946 0.704872 -0.120956 0.706272 0.698074 0.117779 0.824153 0.561415 0.0747398 0.673289 0.706117 0.219276 0.585228 0.698074 0.412554 0.348274 0.698068 0.625624 0.348272 0.69807 0.625623 0.4923 0.706856 0.507931 0.645927 0.637416 0.420094 0.486395 0 0.873739 0.518714 0.00717291 0.854918 0.695972 0 0.718069 0.8383 0 0.545209 0.876636 0.0119757 0.481006 0.950844 0 0.30967 0.995913 0 0.0903162 0.99966 0.0143841 -0.0217549 0.985354 0 -0.170521 0.922705 0 -0.385506 0.854854 0.0143844 -0.518669 0.791488 0 -0.611185 0.635632 0 -0.771992 0.481005 0.0119752 -0.876636 -0.0591303 0 -0.99825 -0.0217623 0.00717257 -0.999737 0.201252 0 -0.97954 0.414183 0 -0.910194 -0.0156529 -0.694754 -0.719078 -0.0156479 -0.694735 -0.719096 0.345994 -0.694737 -0.630578 0.345995 -0.694736 -0.630578 0.614928 -0.694738 -0.373098 0.614915 -0.694752 -0.373094 0.719085 -0.694746 -0.0156489 0.719082 -0.694749 -0.0156495 0.630567 -0.694749 0.345989 0.630565 -0.694752 0.345987 0.373094 -0.694752 0.614915 0.373097 -0.69474 0.614927 0.373094 0.694746 0.614921 0.373097 0.694742 0.614925 0.630578 0.694738 0.345993 0.630568 0.694748 0.34599 0.719082 0.694749 -0.0156495 0.719091 0.69474 -0.0156519 0.614926 0.69474 -0.373098 0.614919 0.69475 -0.373091 0.345989 0.694749 -0.630568 0.34599 0.694742 -0.630575 -0.0156493 0.694748 -0.719083 -0.0156494 0.694747 -0.719084 -0.0423338 0.698073 -0.714774 -0.0423351 0.698069 -0.714778 0.142371 0.706853 -0.692885 0.301497 0.608289 -0.734223 0.295432 0.70086 -0.649242 0.450098 0.706113 -0.546641 0.626087 0.539525 -0.562963 0.562801 0.703122 -0.434598 0.65451 0.70487 -0.27345 0.823664 0.513776 -0.240024 0.698939 0.704879 -0.120954 0.706267 0.69808 0.117777 0.905906 0.415433 0.0821526 0.673282 0.706124 0.219272 0.585221 0.698082 0.41255 0.348274 0.698072 0.62562 0.348268 0.698081 0.625614 0.492273 0.706868 0.507941 0.681501 0.582328 0.443228 0.348265 0.698082 0.625614 0.348277 0.698066 0.625626 0.585232 0.69807 0.412556 0.585225 0.698077 0.412554 0.706272 0.698075 0.117779 0.706273 0.698073 0.117778 0.687433 0.698073 -0.200326 0.687431 0.698075 -0.200324 0.532439 0.698072 -0.478754 0.532437 0.698074 -0.478752 0.271985 0.698074 -0.662356 0.271985 0.698076 -0.662355 -0.0423347 0.698076 -0.714772 -0.0423376 0.698067 -0.71478 -0.0156493 0.694746 -0.719085 -0.0156495 0.694746 -0.719085 0.345989 0.69475 -0.630567 0.338662 0.575677 -0.744247 0.450094 0.70611 -0.546648 0.614927 0.694739 -0.373098 0.687175 0.496206 -0.530632 0.654511 0.704868 -0.273454 0.698949 0.704868 -0.12096 0.796364 0.604569 -0.0173314 0.373097 0.694742 0.614924 0.373095 0.694745 0.614923 0.597957 0.70086 0.3889 0.686717 0.621647 0.376795 0.673298 0.706112 0.219263 0.708165 0.70312 0.064224 0.518725 0 0.854941 0.486371 -0.0103438 0.873691 0.838265 0.00889459 0.545191 0.817324 0 0.576179 0.950851 0 0.30965 0.98631 0.0119042 0.164474 0.995913 0 0.0903201 0.985353 0 -0.170525 0.95998 0.013399 -0.279749 0.922705 0 -0.385506 0.79149 0 -0.611183 0.743547 0.011906 -0.668578 0.635634 0 -0.77199 0.414176 0 -0.910197 0.379844 0.00743042 -0.925021 -0.021757 -0.00889377 -0.999724 -0.0591251 0 -0.998251 -0.0423349 -0.698077 -0.71477 -0.0423346 -0.698076 -0.714771 0.271983 -0.698079 -0.662352 0.271985 -0.698077 -0.662354 0.532433 -0.698078 -0.47875 0.532431 -0.69808 -0.47875 0.687424 -0.698082 -0.200323 0.687438 -0.698069 -0.200322 0.706278 -0.698069 0.117777 0.706281 -0.698065 0.117779 0.585231 -0.698067 0.412563 0.585219 -0.698088 0.412544 0.348268 -0.698084 0.625611 0.348269 -0.698072 0.625623 0.348269 0.698075 0.62562 0.348273 0.698071 0.625622 0.585232 0.69807 0.412557 0.585234 0.698068 0.412557 0.706279 0.698068 0.117777 0.706271 0.698075 0.117781 0.68743 0.698076 -0.200325 0.687431 0.698074 -0.200327 0.532437 0.698073 -0.478754 0.532437 0.698072 -0.478755 0.271988 0.698073 -0.662357 0.271988 0.698073 -0.662357 -0.0423339 0.698075 -0.714773 -0.0423346 0.698074 -0.714774 0.486392 0 0.873741 0.518704 0.00889461 0.854907 0.817306 -0.00742949 0.576156 0.838297 0 0.545213 0.950851 0 0.30965 0.98631 -0.0119043 0.164474 0.995913 0 0.0903198 0.985353 0 -0.170526 0.95998 -0.0133988 -0.279749 0.922706 0 -0.385504 0.791488 0 -0.611185 0.743547 -0.0119055 -0.668578 0.63564 0 -0.771985 0.379858 0 -0.925045 0.414164 -0.0088938 -0.910159 -0.0591203 0.0103442 -0.998197 -0.0217572 0 -0.999763 0.373094 -0.69475 0.614917 0.373094 -0.694749 0.614918 0.630568 -0.694746 0.345993 0.736338 -0.477976 0.478901 0.673281 -0.70613 0.219258 0.719072 -0.69476 -0.0156503 0.945187 -0.315078 0.0857195 0.698934 -0.704883 -0.120958 0.654496 -0.704884 -0.273447 0.726269 -0.527597 -0.440653 -0.015649 -0.694746 -0.719085 -0.0156504 -0.694751 -0.71908 0.295434 -0.700863 -0.649238 0.398003 -0.561639 -0.725366 0.45009 -0.706123 -0.546634 0.562795 -0.703132 -0.434589 0.348269 0.698077 0.625617 0.348276 0.698071 0.62562 0.58523 0.69807 0.412558 0.585225 0.698075 0.412558 0.706272 0.698074 0.117779 0.706274 0.698072 0.117778 0.687438 0.698068 -0.200327 0.687438 0.698067 -0.200328 0.532441 0.698065 -0.478761 0.532439 0.698072 -0.478753 0.271986 0.698073 -0.662358 0.271987 0.698079 -0.66235 -0.042334 0.69808 -0.714768 -0.0423417 0.698069 -0.714778 0.486394 0 0.873739 0.486394 0 0.873739 0.817327 0 0.576175 0.817327 0 0.576175 0.986379 0 0.16449 0.986379 0 0.16449 0.960066 0 -0.279774 0.960066 0 -0.279774 0.743597 0 -0.668628 0.743597 0 -0.668628 0.379854 0 -0.925047 0.379854 0 -0.925047 -0.0591241 0 -0.998251 -0.0591241 0 -0.998251 -0.0423338 -0.698083 -0.714765 -0.0423351 -0.698086 -0.714761 0.27198 -0.698089 -0.662344 0.271988 -0.698078 -0.662352 0.532431 -0.698079 -0.478752 0.532441 -0.698069 -0.478755 0.687435 -0.698071 -0.200326 0.687438 -0.698067 -0.200326 0.706277 -0.69807 0.11778 0.706274 -0.698073 0.117778 0.585231 -0.698069 0.412559 0.585226 -0.698077 0.412551 0.348268 -0.69808 0.625614 0.348268 -0.698081 0.625614 0.518723 0 0.854942 0.518723 0 0.854942 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.021758 0.999763 0 -0.021758 0.854942 0 -0.518724 0.854942 0 -0.518724 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217577 0 -0.999763 -0.0217577 0 -0.999763 0.486398 0 0.873737 0.518643 0.0178247 0.854805 0.695945 0 0.718096 0.838302 0 0.545206 0.876312 0.0297572 0.480824 0.950845 0 0.309667 0.995913 0 0.0903149 0.999125 0.0357353 -0.0217442 0.985354 0 -0.17052 0.922707 0 -0.385502 0.854396 0.0357375 -0.518393 0.791485 0 -0.611189 0.635643 0 -0.771984 0.480825 0.029758 -0.876311 -0.0591247 0 -0.998251 -0.0217522 0.0178273 -0.999604 0.201271 0 -0.979536 0.414177 0 -0.910196 0.486391 0 0.873741 0.486391 0 0.873741 0.817329 0 0.576172 0.817329 0 0.576172 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279774 0.960066 0 -0.279774 0.7436 0 -0.668624 0.7436 0 -0.668624 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 -0.184324 0 -0.982866 -0.184324 0 -0.982866 0.0109654 0 -0.99994 0.0109654 0 -0.99994 0.205833 0 -0.978587 0.205833 0 -0.978587 0.392791 0 -0.919628 0.392791 0 -0.919628 0.564654 0 -0.825328 0.564654 0 -0.825328 0.714818 0 -0.699311 0.714818 0 -0.699311 0.837511 0 -0.54642 0.837511 0 -0.54642 0.92802 0 -0.37253 0.92802 0 -0.37253 0.982866 0 -0.184324 0.982866 0 -0.184324 0.99994 0 0.0109654 0.99994 0 0.0109654 0.978587 0 0.205833 0.978587 0 0.205833 0.919628 0 0.392791 0.919628 0 0.392791 0.825328 0 0.564654 0.825328 0 0.564654 0.699311 0 0.714818 0.699311 0 0.714818 0.54642 0 0.837512 0.54642 0 0.837512 0.37253 0 0.92802 0.37253 0 0.92802 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0355312 0 -0.999369 -0.0355312 0 -0.999369 0.129445 0 -0.991587 0.129445 0 -0.991587 0.290889 0 -0.956757 0.290889 0 -0.956757 0.444398 0 -0.895829 0.444398 0 -0.895829 0.585786 0 -0.810466 0.585786 0 -0.810466 0.711195 0 -0.702995 0.711195 0 -0.702995 0.817205 0 -0.576348 0.817205 0 -0.576348 0.900922 0 -0.43398 0.900922 0 -0.43398 0.960066 0 -0.279774 0.960066 0 -0.279774 0.993021 0 -0.117937 0.993021 0 -0.117937 0.998889 0 0.0471174 0.998889 0 0.0471174 0.977511 0 0.210887 0.977511 0 0.210887 0.929468 0 0.368904 0.929468 0 0.368904 0.856072 0 0.516857 0.856072 0 0.516857 0.759324 0 0.650713 0.759324 0 0.650713 0.641864 0 0.766819 0.641864 0 0.766819 0.506895 0 0.862008 0.506895 0 0.862008 0.3581 0 0.933683 0.3581 0 0.933683 0.255196 0.851304 0.458428 0.255198 0.851303 0.458429 0.428833 0.851303 0.302302 0.428828 0.851305 0.302303 0.517525 0.851305 0.0863016 0.517523 0.851306 0.0863033 0.503717 0.851306 -0.146786 0.503719 0.851305 -0.146789 0.390145 0.851305 -0.350809 0.390145 0.851305 -0.350809 0.1993 0.851305 -0.485344 0.199299 0.851303 -0.485348 -0.0310214 0.851305 -0.523754 -0.0310211 0.851305 -0.523754 0.273989 0.849119 0.451582 0.273991 0.849119 0.451582 0.463077 0.849118 0.254082 0.463073 0.84912 0.254083 0.528073 0.849121 -0.0114893 0.528075 0.84912 -0.0114915 0.45158 0.84912 -0.273992 0.45158 0.849119 -0.273994 0.254088 0.849118 -0.463074 0.254087 0.849117 -0.463077 -0.0114926 0.849118 -0.528078 -0.0114916 0.849119 -0.528077 0.273993 0.849118 0.451582 0.273991 0.849119 0.451582 0.463073 0.849119 0.254087 0.463077 0.849117 0.254086 0.52808 0.849117 -0.0114927 0.528078 0.849118 -0.0114915 0.451582 0.849118 -0.273993 0.451582 0.849119 -0.273991 0.254085 0.849119 -0.463075 0.254085 0.849119 -0.463075 -0.0114926 0.849119 -0.528077 -0.0114915 0.84912 -0.528075 0.273986 0.84912 0.451582 0.273991 0.849118 0.451583 0.463076 0.849118 0.254086 0.463078 0.849117 0.254085 0.528078 0.849118 -0.0114926 0.528077 0.849119 -0.0114916 0.451582 0.849118 -0.273993 0.451582 0.849119 -0.273991 0.254087 0.849119 -0.463073 0.254086 0.849118 -0.463076 -0.011496 0.849117 -0.52808 -0.0114914 0.84912 -0.528075 0.273995 0.849118 0.451581 0.273992 0.849119 0.451581 0.463073 0.849119 0.254087 0.463074 0.849118 0.254087 0.528077 0.849119 -0.0114926 0.528078 0.849118 -0.0114938 0.451583 0.849118 -0.27399 0.451583 0.849119 -0.27399 0.254084 0.849119 -0.463076 0.254084 0.849119 -0.463075 -0.0114926 0.849119 -0.528077 -0.0114915 0.84912 -0.528075 0.273992 0.849118 0.451583 -0.0114926 0.849119 -0.528077 -0.0114927 0.849119 -0.528077 0.216079 0.853126 -0.474854 0.237597 0.869504 -0.433025 0.416764 0.873135 -0.252868 0.411013 0.854595 -0.317387 0.328055 0.856529 -0.39842 0.487362 0.873135 -0.0106035 0.509852 0.855725 -0.0882399 0.477439 0.855725 -0.199467 0.273992 0.849118 0.451583 0.437345 0.853125 0.284442 0.433024 0.869504 0.237598 0.490727 0.85653 0.159821 0.517169 0.854597 0.0468997 0.273993 0.849118 0.451582 -0.0114926 0.849119 -0.528077 -0.0114926 0.849119 -0.528077 0.216081 0.853126 -0.474853 0.237598 0.869502 -0.433028 0.416768 0.873134 -0.252865 0.411018 0.854595 -0.317383 0.328048 0.856529 -0.398427 0.487364 0.873134 -0.0106097 0.509849 0.855728 -0.0882289 0.477431 0.855727 -0.199474 0.273991 0.849119 0.451582 0.437345 0.853125 0.284441 0.433024 0.869504 0.237599 0.490736 0.856528 0.159809 0.517175 0.854594 0.0469003 0.273995 0.849118 0.451581 -0.0114915 0.849118 -0.528078 -0.0114927 0.849117 -0.52808 0.216078 0.853124 -0.474858 0.237598 0.869503 -0.433025 0.416766 0.873135 -0.252866 0.411016 0.854595 -0.317385 0.328053 0.856529 -0.398421 0.487363 0.873135 -0.0106066 0.50985 0.855726 -0.0882348 0.477435 0.855726 -0.19947 0.273992 0.849119 0.451581 0.437346 0.853125 0.28444 0.433025 0.869503 0.2376 0.49073 0.856529 0.159822 0.517172 0.854595 0.0468998 0.255195 0.851306 0.458426 0.255202 0.851303 0.458427 0.428833 0.851303 0.302301 0.42883 0.851304 0.302301 0.517526 0.851304 0.0863034 0.517526 0.851304 0.0863039 0.50372 0.851304 -0.146792 0.50372 0.851304 -0.146791 0.390147 0.851303 -0.350812 0.390146 0.851306 -0.350805 0.199302 0.851307 -0.485341 0.199299 0.851305 -0.485345 -0.0310216 0.851304 -0.523754 -0.0310253 0.851303 -0.523757 0.273989 0.84912 0.451581 -0.0114938 0.849118 -0.528078 -0.0114926 0.849119 -0.528077 0.216079 0.853125 -0.474855 0.237599 0.869504 -0.433023 0.416766 0.873134 -0.252869 0.411016 0.854595 -0.317385 0.328057 0.856529 -0.398418 0.487363 0.873135 -0.0106066 0.50985 0.855726 -0.0882348 0.477433 0.855726 -0.199475 0.273991 0.849119 0.451582 0.437346 0.853125 0.28444 0.433025 0.869503 0.2376 0.490734 0.856527 0.159815 0.517174 0.854594 0.046904 0.27399 0.849119 0.451582 0.273991 0.849119 0.451581 0.463067 0.849121 0.254094 0.463073 0.849119 0.254086 0.528076 0.849119 -0.0114928 0.528076 0.849119 -0.0114927 0.451579 0.849119 -0.273996 0.451581 0.849119 -0.273991 0.254081 0.849119 -0.463077 0.254085 0.849119 -0.463074 -0.0114928 0.849119 -0.528076 -0.0114927 0.849119 -0.528076 0.273996 0.849119 0.451579 -0.0114926 0.84912 -0.528076 -0.0114941 0.849119 -0.528076 0.21608 0.853126 -0.474854 0.248636 0.856057 -0.453152 0.439995 0.857399 -0.266968 0.411014 0.854596 -0.317385 0.328053 0.856529 -0.398421 0.514531 0.857399 -0.011198 0.509849 0.855727 -0.0882337 0.477432 0.855727 -0.199472 0.27399 0.849119 0.451581 0.437346 0.853126 0.284438 0.453149 0.856057 0.248643 0.490731 0.856529 0.159817 0.517171 0.854596 0.0469015 0.273989 0.84912 0.451581 0.273991 0.849119 0.451581 0.463065 0.849121 0.254095 0.463074 0.849119 0.254085 0.528076 0.849119 -0.0114928 0.528076 0.849119 -0.0114927 0.451573 0.849117 -0.274013 0.451581 0.84912 -0.273991 0.254098 0.849121 -0.463063 0.254085 0.849119 -0.463074 -0.0114922 0.849119 -0.528076 -0.0114926 0.849119 -0.528076 0.273981 0.849121 0.451585 0.273991 0.849119 0.451581 0.463067 0.849121 0.254094 0.463074 0.849119 0.254086 0.528076 0.849119 -0.0114928 0.528076 0.849119 -0.0114927 0.451579 0.849119 -0.273996 0.451581 0.849119 -0.273991 0.254081 0.849119 -0.463077 0.254085 0.849119 -0.463074 -0.0114928 0.849119 -0.528076 -0.0114927 0.849119 -0.528076 0.273981 0.849121 0.451584 0.273991 0.849119 0.451581 0.463077 0.849119 0.254081 0.463074 0.849119 0.254085 0.528076 0.849119 -0.0114928 0.528076 0.849119 -0.0114927 0.451579 0.849119 -0.273996 0.451581 0.849119 -0.27399 0.254088 0.84912 -0.463071 0.254085 0.849119 -0.463074 -0.0114928 0.849119 -0.528076 -0.0114927 0.849119 -0.528076 0.273982 0.849121 0.451584 0.273991 0.84912 0.451581 0.463074 0.849119 0.254084 0.463073 0.849119 0.254085 0.528076 0.849119 -0.0114922 0.528076 0.849119 -0.0114925 0.451582 0.849119 -0.27399 0.451581 0.849119 -0.273991 0.254069 0.849117 -0.463087 0.254085 0.849119 -0.463074 -0.0114928 0.849119 -0.528076 -0.0114927 0.849119 -0.528076 0.255184 0.851306 0.45843 -0.031021 0.851305 -0.523753 -0.0310162 0.851305 -0.523753 0.103707 0.857008 -0.50476 0.197157 0.854762 -0.480116 0.38344 0.856792 -0.344792 0.328055 0.856529 -0.398419 0.216078 0.853126 -0.474855 0.494003 0.85746 -0.143955 0.477432 0.855727 -0.199472 0.411014 0.854596 -0.317386 0.508643 0.856791 0.0848053 0.517171 0.854596 0.0469014 0.509848 0.855727 -0.0882334 0.255196 0.851305 0.458426 0.358634 0.857008 0.370026 0.424209 0.854762 0.299045 0.437345 0.853126 0.28444 0.49073 0.856529 0.159817 0.255184 0.851307 0.45843 0.255197 0.851305 0.458426 0.42884 0.851303 0.302289 0.428828 0.851305 0.302301 0.517522 0.851306 0.0863106 0.517524 0.851305 0.0863038 0.503719 0.851306 -0.146786 0.503718 0.851305 -0.14679 0.390148 0.851306 -0.350804 0.390145 0.851305 -0.350808 0.199303 0.851306 -0.485342 0.199299 0.851305 -0.485345 -0.0310174 0.851305 -0.523753 -0.031021 0.851305 -0.523753 0.27399 0.849119 0.451582 -0.0114925 0.849119 -0.528076 -0.0114918 0.84912 -0.528076 0.216079 0.853126 -0.474854 0.24864 0.856057 -0.45315 0.440002 0.857399 -0.266956 0.411015 0.854596 -0.317384 0.328053 0.856529 -0.39842 0.514531 0.857399 -0.011198 0.509849 0.855728 -0.0882312 0.477431 0.855728 -0.199474 0.273991 0.849119 0.451581 0.437346 0.853125 0.284439 0.453158 0.856058 0.248622 0.49073 0.856529 0.159817 0.517171 0.854596 0.046903 0.255194 0.851305 0.458427 -0.031021 0.851305 -0.523753 -0.0310174 0.851305 -0.523753 0.103706 0.857008 -0.50476 0.197157 0.854762 -0.480115 0.38344 0.856792 -0.344792 0.328053 0.856529 -0.398421 0.216079 0.853126 -0.474854 0.494003 0.85746 -0.143955 0.477431 0.855727 -0.199474 0.411015 0.854596 -0.317385 0.508643 0.856791 0.0848053 0.517171 0.854596 0.0469028 0.509849 0.855728 -0.0882314 0.255196 0.851305 0.458426 0.358634 0.857008 0.370026 0.424209 0.854762 0.299045 0.437346 0.853126 0.284439 0.490731 0.856529 0.159817 -0.031021 0.851305 -0.523753 -0.0113433 0.853328 -0.521251 0.103707 0.857008 -0.504759 0.21608 0.853126 -0.474854 0.248636 0.856056 -0.453153 0.328053 0.856529 -0.398421 0.411014 0.854596 -0.317386 0.440003 0.857399 -0.266954 0.477432 0.855727 -0.199472 0.509849 0.855727 -0.0882315 0.514531 0.857399 -0.0111989 0.517172 0.854596 0.0469014 0.49073 0.856529 0.159817 0.453149 0.856057 0.248643 0.437345 0.853126 0.284439 0.358634 0.857008 0.370026 0.270453 0.853329 0.445741 0.255197 0.851305 0.458426 -0.031021 0.851305 -0.523753 -0.0113433 0.853328 -0.521251 0.103706 0.857008 -0.504759 0.21608 0.853126 -0.474853 0.248623 0.856056 -0.453161 0.328055 0.856529 -0.398419 0.411014 0.854596 -0.317385 0.439999 0.857398 -0.266962 0.477433 0.855727 -0.199472 0.509849 0.855727 -0.0882328 0.514531 0.857399 -0.0111989 0.517171 0.854596 0.046901 0.49073 0.856529 0.159818 0.453151 0.856057 0.24864 0.437346 0.853126 0.284438 0.358625 0.857008 0.370034 0.270443 0.853327 0.44575 0.255197 0.851305 0.458426 -0.255191 0.851306 -0.458427 0.031021 0.851305 0.523753 0.0310387 0.851303 0.523756 -0.103706 0.857008 0.50476 -0.197153 0.854763 0.480116 -0.383449 0.856791 0.344783 -0.328055 0.856529 0.398419 -0.216078 0.853126 0.474855 -0.494002 0.85746 0.143958 -0.477432 0.855727 0.199472 -0.411014 0.854596 0.317385 -0.508639 0.856791 -0.0848232 -0.517172 0.854596 -0.0469011 -0.509849 0.855727 0.0882329 -0.255197 0.851305 -0.458425 -0.358632 0.857008 -0.370028 -0.42421 0.854763 -0.299043 -0.437346 0.853126 -0.284438 -0.49073 0.856529 -0.159818 -0.273981 0.849121 -0.451584 -0.273991 0.849119 -0.451581 -0.463077 0.849119 -0.254081 -0.463074 0.849119 -0.254085 -0.528076 0.849119 0.0114928 -0.528076 0.849119 0.0114927 -0.451579 0.849119 0.273996 -0.451581 0.849119 0.27399 -0.254088 0.84912 0.463071 -0.254085 0.849119 0.463074 0.0114928 0.849119 0.528076 0.0114927 0.849119 0.528076 0.0310221 0.851305 0.523753 0.0113433 0.853328 0.521251 -0.103712 0.857008 0.504759 -0.216079 0.853126 0.474854 -0.248636 0.856056 0.453153 -0.328053 0.856529 0.398421 -0.411014 0.854596 0.317386 -0.439996 0.857398 0.266968 -0.477432 0.855727 0.199472 -0.509849 0.855727 0.0882335 -0.514531 0.857399 0.0111989 -0.517172 0.854596 -0.0469014 -0.49073 0.856529 -0.159817 -0.453146 0.856056 -0.24865 -0.437345 0.853126 -0.284439 -0.358632 0.857008 -0.370028 -0.270441 0.853327 -0.445752 -0.255197 0.851305 -0.458426 -0.2552 0.851305 -0.458425 0.0310212 0.851305 0.523753 0.031024 0.851305 0.523754 -0.103707 0.857008 0.50476 -0.197148 0.854763 0.480118 -0.383437 0.856792 0.344795 -0.328053 0.856529 0.39842 -0.216079 0.853126 0.474854 -0.494004 0.85746 0.143955 -0.477433 0.855727 0.199471 -0.411015 0.854596 0.317384 -0.508634 0.856792 -0.0848468 -0.517172 0.854596 -0.0469029 -0.509849 0.855727 0.0882354 -0.255197 0.851305 -0.458426 -0.358633 0.857008 -0.370027 -0.424219 0.854761 -0.299034 -0.437346 0.853126 -0.284439 -0.49073 0.856529 -0.159817 -0.273996 0.849119 -0.451579 -0.27399 0.849119 -0.451581 -0.463077 0.849119 -0.254081 -0.463074 0.849119 -0.254085 -0.528076 0.849119 0.0114932 -0.528076 0.849119 0.0114927 -0.451579 0.849119 0.273996 -0.451581 0.849119 0.27399 -0.254088 0.84912 0.463071 -0.254086 0.849119 0.463073 0.0114928 0.849119 0.528076 0.0114927 0.84912 0.528076 -0.27399 0.849119 -0.451581 0.0114926 0.849119 0.528076 0.0114941 0.849119 0.528076 -0.216079 0.853126 0.474854 -0.248636 0.856057 0.453152 -0.439995 0.857399 0.266968 -0.411014 0.854596 0.317385 -0.328054 0.856529 0.39842 -0.514531 0.857399 0.011198 -0.509849 0.855727 0.0882327 -0.477432 0.855727 0.199472 -0.273991 0.849119 -0.451581 -0.437345 0.853126 -0.284439 -0.453146 0.856056 -0.24865 -0.49073 0.856529 -0.159818 -0.517172 0.854596 -0.0469007 -0.255191 0.851306 -0.458428 -0.255197 0.851305 -0.458426 -0.42883 0.851305 -0.3023 -0.428828 0.851305 -0.302302 -0.517524 0.851305 -0.0863049 -0.517524 0.851305 -0.0863029 -0.503719 0.851305 0.14679 -0.503719 0.851305 0.146789 -0.390147 0.851305 0.350805 -0.390146 0.851305 0.350808 -0.199301 0.851305 0.485343 -0.199299 0.851305 0.485345 0.0310396 0.851303 0.523755 0.031021 0.851305 0.523753 -0.255184 0.851306 -0.45843 -0.255197 0.851305 -0.458426 -0.428841 0.851303 -0.302289 -0.428828 0.851305 -0.302301 -0.517523 0.851306 -0.0863072 -0.517525 0.851305 -0.0863026 -0.503719 0.851305 0.146786 -0.503719 0.851305 0.146789 -0.390148 0.851306 0.350804 -0.390145 0.851305 0.350809 -0.199303 0.851305 0.485343 -0.1993 0.851305 0.485345 0.0310389 0.851303 0.523755 0.031021 0.851305 0.523753 -0.255194 0.851305 -0.458427 -0.255197 0.851305 -0.458426 -0.428828 0.851305 -0.302302 -0.428828 0.851305 -0.302302 -0.517523 0.851306 -0.0863072 -0.517525 0.851305 -0.0863016 -0.503717 0.851303 0.146807 -0.503719 0.851305 0.146788 -0.39014 0.851304 0.350816 -0.390144 0.851305 0.350809 -0.199303 0.851306 0.485342 -0.199299 0.851305 0.485345 0.0310187 0.851305 0.523753 0.031021 0.851305 0.523753 -0.273989 0.84912 -0.451581 0.0114924 0.849119 0.528076 0.0114918 0.849119 0.528076 -0.216079 0.853126 0.474854 -0.248638 0.856057 0.453151 -0.440002 0.857399 0.266956 -0.411013 0.854596 0.317387 -0.328053 0.856529 0.39842 -0.514531 0.857398 0.0111981 -0.509849 0.855727 0.0882315 -0.477433 0.855727 0.199471 -0.273991 0.849119 -0.451581 -0.437345 0.853126 -0.284439 -0.453145 0.856056 -0.248651 -0.49073 0.856529 -0.159817 -0.517172 0.854596 -0.0469 -0.255184 0.851307 -0.45843 0.031021 0.851305 0.523753 0.0310162 0.851305 0.523753 -0.103707 0.857008 0.50476 -0.197157 0.854762 0.480116 -0.38345 0.856791 0.344782 -0.328053 0.856529 0.398421 -0.216079 0.853126 0.474854 -0.494003 0.85746 0.143955 -0.477431 0.855727 0.199475 -0.411015 0.854596 0.317384 -0.508637 0.856792 -0.0848288 -0.517172 0.854596 -0.0469 -0.509849 0.855727 0.0882311 -0.255197 0.851305 -0.458426 -0.358628 0.857008 -0.370032 -0.42422 0.854762 -0.299032 -0.437346 0.853126 -0.284438 -0.49073 0.856529 -0.159817 -0.255194 0.851305 -0.458427 0.031021 0.851305 0.523753 0.0310162 0.851305 0.523753 -0.103706 0.857008 0.50476 -0.197138 0.854764 0.480121 -0.38345 0.856791 0.344782 -0.328056 0.856529 0.398418 -0.216078 0.853126 0.474855 -0.494003 0.85746 0.143955 -0.477432 0.855727 0.199472 -0.411014 0.854596 0.317386 -0.508643 0.856791 -0.0848053 -0.517171 0.854596 -0.0469014 -0.509848 0.855727 0.0882334 -0.255196 0.851305 -0.458426 -0.358634 0.857008 -0.370026 -0.424209 0.854762 -0.299045 -0.437345 0.853126 -0.28444 -0.49073 0.856529 -0.159817 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.255199 0.851304 -0.458427 0.0310197 0.851305 0.523753 0.0310217 0.851304 0.523754 -0.103706 0.857007 0.504761 -0.192674 0.861806 0.46922 -0.369716 0.867638 0.332438 -0.328054 0.856528 0.398423 -0.21608 0.853124 0.474857 -0.474192 0.86951 0.138186 -0.477434 0.855726 0.199475 -0.411017 0.854594 0.317386 -0.490424 0.867638 -0.0817856 -0.517173 0.854595 -0.0469042 -0.50985 0.855726 0.0882339 -0.255199 0.851304 -0.458427 -0.358629 0.857007 -0.370033 -0.414579 0.861806 -0.292258 -0.437346 0.853125 -0.28444 -0.490732 0.856529 -0.159814 -0.273994 0.849117 -0.451584 -0.273991 0.849118 -0.451583 -0.463076 0.849118 -0.254086 -0.463074 0.849119 -0.254086 -0.528078 0.849118 0.0114927 -0.528077 0.849119 0.0114914 -0.451581 0.84912 0.273989 -0.451582 0.849119 0.273991 -0.254082 0.849118 0.463077 -0.254083 0.849121 0.463072 0.0114893 0.849121 0.528073 0.0114914 0.84912 0.528075 -0.255199 0.851304 -0.458427 0.0310197 0.851304 0.523755 0.0310176 0.851305 0.523754 -0.103706 0.857007 0.504761 -0.192674 0.861806 0.46922 -0.369716 0.867638 0.332438 -0.328051 0.856527 0.398428 -0.216082 0.853123 0.474857 -0.474192 0.86951 0.138182 -0.477434 0.855726 0.199475 -0.411017 0.854594 0.317386 -0.490424 0.867638 -0.081782 -0.517173 0.854595 -0.0469002 -0.509851 0.855727 0.0882287 -0.255199 0.851304 -0.458427 -0.358637 0.857007 -0.370025 -0.414581 0.861804 -0.29226 -0.437345 0.853125 -0.284442 -0.490732 0.856529 -0.159814 -0.255199 0.851304 -0.458427 0.0310211 0.851305 0.523754 0.0310215 0.851304 0.523754 -0.103709 0.857007 0.50476 -0.192679 0.861805 0.469219 -0.369712 0.867641 0.332435 -0.328047 0.856529 0.398426 -0.216079 0.853125 0.474854 -0.474189 0.86951 0.138189 -0.477431 0.855728 0.199474 -0.411016 0.854596 0.317381 -0.490427 0.867637 -0.0817827 -0.517176 0.854593 -0.0469003 -0.509853 0.855725 0.0882296 -0.255195 0.851306 -0.458426 -0.358635 0.857009 -0.370023 -0.414577 0.861806 -0.29226 -0.437351 0.853123 -0.284439 -0.490734 0.856526 -0.159823 -0.255194 0.851306 -0.458426 0.0310211 0.851305 0.523754 0.0310215 0.851304 0.523754 -0.103709 0.857007 0.50476 -0.192677 0.861805 0.46922 -0.369716 0.867638 0.332438 -0.328055 0.856528 0.398421 -0.21608 0.853125 0.474856 -0.474189 0.869512 0.138182 -0.477431 0.855728 0.199474 -0.411013 0.854596 0.317387 -0.490421 0.86764 -0.0817815 -0.51717 0.854597 -0.0468997 -0.509848 0.855728 0.0882286 -0.2552 0.851303 -0.458427 -0.358622 0.857006 -0.370041 -0.414581 0.861806 -0.292255 -0.437347 0.853126 -0.284437 -0.490729 0.856529 -0.159821 -0.255195 0.851306 -0.458426 -0.255198 0.851304 -0.458427 -0.42883 0.851304 -0.302302 -0.428827 0.851305 -0.302302 -0.517525 0.851305 -0.0863018 -0.517526 0.851304 -0.0863009 -0.50372 0.851305 0.146787 -0.503721 0.851304 0.14679 -0.390147 0.851304 0.350809 -0.390147 0.851304 0.35081 -0.199299 0.851304 0.485346 -0.1993 0.851305 0.485345 0.0310214 0.851304 0.523754 0.0310224 0.851304 0.523755 -0.255195 0.851306 -0.458426 -0.255195 0.851305 -0.458426 -0.428827 0.851305 -0.302302 -0.42883 0.851304 -0.302301 -0.517526 0.851304 -0.0863034 -0.517526 0.851304 -0.0863039 -0.50372 0.851304 0.146792 -0.503719 0.851305 0.14679 -0.390146 0.851306 0.350805 -0.390147 0.851304 0.35081 -0.199298 0.851303 0.485349 -0.199299 0.851305 0.485345 0.0310216 0.851304 0.523754 0.0310196 0.851306 0.523753 -0.255195 0.851306 -0.458426 -0.255198 0.851304 -0.458427 -0.42883 0.851304 -0.302302 -0.428827 0.851305 -0.302302 -0.517524 0.851305 -0.0863055 -0.517526 0.851304 -0.0863036 -0.503719 0.851305 0.14679 -0.50372 0.851304 0.146792 -0.390147 0.851304 0.350809 -0.390147 0.851305 0.350807 -0.199299 0.851305 0.485345 -0.199299 0.851305 0.485346 0.0310217 0.851304 0.523754 0.0310225 0.851304 0.523755 -0.255197 0.851304 -0.458428 -0.255198 0.851304 -0.458428 -0.428832 0.851303 -0.302302 -0.428829 0.851304 -0.302302 -0.517525 0.851305 -0.0863013 -0.517523 0.851306 -0.0863035 -0.503718 0.851306 0.146787 -0.503722 0.851302 0.146795 -0.390149 0.851302 0.350811 -0.390149 0.851304 0.350807 -0.199299 0.851304 0.485347 -0.199299 0.851303 0.485348 0.0310195 0.851305 0.523754 0.0310212 0.851304 0.523755 -0.273987 0.84912 -0.451581 -0.273992 0.849118 -0.451583 -0.463078 0.849118 -0.254082 -0.463072 0.849121 -0.254083 -0.528073 0.849121 0.0114893 -0.528075 0.84912 0.0114915 -0.45158 0.849119 0.273993 -0.45158 0.849119 0.273993 -0.254085 0.849119 0.463075 -0.254085 0.849119 0.463073 0.0114927 0.849119 0.528077 0.0114927 0.849119 0.528077 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.199537 0 0.97989 0.199537 0 0.97989 0.0355307 0 0.999369 0.0355307 0 0.999369 -0.129444 0 0.991587 -0.129444 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817205 0 0.576348 -0.817205 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506896 0 -0.862007 -0.506896 0 -0.862007 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0.184324 0 0.982866 0.184324 0 0.982866 -0.0109654 0 0.99994 -0.0109654 0 0.99994 -0.205833 0 0.978587 -0.205833 0 0.978587 -0.392791 0 0.919628 -0.392791 0 0.919628 -0.564654 0 0.825328 -0.564654 0 0.825328 -0.714818 0 0.699311 -0.714818 0 0.699311 -0.837512 0 0.54642 -0.837512 0 0.54642 -0.92802 0 0.37253 -0.92802 0 0.37253 -0.982866 0 0.184324 -0.982866 0 0.184324 -0.99994 0 -0.0109654 -0.99994 0 -0.0109654 -0.978587 0 -0.205833 -0.978587 0 -0.205833 -0.919628 0 -0.392791 -0.919628 0 -0.392791 -0.825328 0 -0.564654 -0.825328 0 -0.564654 -0.699311 0 -0.714818 -0.699311 0 -0.714818 -0.546419 0 -0.837512 -0.546419 0 -0.837512 -0.37253 0 -0.92802 -0.37253 0 -0.92802 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.0217556 -0.999763 0 0.0217556 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481037 0 0.8767 -0.481037 0 0.8767 0.0217581 0 0.999763 0.0217581 0 0.999763 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518723 0 -0.854943 -0.486291 -0.0207314 -0.873551 -0.838169 0.0178287 -0.54512 -0.817327 0 -0.576174 -0.950845 0 -0.309667 -0.986098 0.0238608 -0.164442 -0.995913 0 -0.0903149 -0.985354 0 0.170519 -0.959719 0.0268543 0.279674 -0.922702 0 0.385513 -0.791489 0 0.611184 -0.743389 0.0238609 0.668434 -0.635639 0 0.771986 -0.41418 0 0.910195 -0.379812 0.0148953 0.924944 0.0217545 -0.0178262 0.999604 0.0591247 0 0.998251 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217578 0 0.999763 0.0217578 0 0.999763 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0156488 -0.694755 0.719076 0.0156503 -0.69476 0.719071 -0.345985 -0.694756 0.630563 -0.34598 -0.694762 0.630559 -0.61491 -0.694759 0.373089 -0.614918 -0.694751 0.373091 -0.719085 -0.694746 0.0156491 -0.719081 -0.69475 0.0156505 -0.630563 -0.694757 -0.345981 -0.630576 -0.694737 -0.345996 -0.373098 -0.694733 -0.614934 -0.373093 -0.694758 -0.614909 -0.518719 0 -0.854945 -0.518719 0 -0.854945 -0.876702 0 -0.481034 -0.876702 0 -0.481034 -0.999763 0 0.0217574 -0.999763 0 0.0217574 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217572 0 0.999763 0.0217572 0 0.999763 -0.373093 0.694744 -0.614925 -0.373099 0.694738 -0.614928 -0.630578 0.69474 -0.345989 -0.630566 0.694751 -0.345989 -0.719084 0.694747 0.0156491 -0.719085 0.694746 0.0156495 -0.614919 0.694748 0.373095 -0.614922 0.694743 0.373099 -0.345991 0.694743 0.630574 -0.345991 0.69475 0.630566 0.0156488 0.694753 0.719078 0.0156495 0.694752 0.719079 -0.348269 -0.698077 -0.625617 -0.348269 -0.698082 -0.625612 -0.492274 -0.70687 -0.507937 -0.628525 -0.639251 -0.443073 -0.597961 -0.700855 -0.388903 -0.673302 -0.706108 -0.219264 -0.791096 -0.597297 -0.131922 -0.708166 -0.703119 -0.0642239 -0.687437 -0.69807 0.200322 -0.905537 -0.394263 0.156711 -0.654498 -0.704882 0.27345 -0.53243 -0.698081 0.478749 -0.675133 -0.521929 0.521331 -0.450085 -0.706121 0.546642 -0.271985 -0.698078 0.662353 0.0423344 -0.698074 0.714773 0.0423356 -0.698077 0.71477 -0.142349 -0.706865 0.692877 -0.324373 -0.62181 0.712835 -0.486397 0 -0.873738 -0.518704 -0.00889328 -0.854907 -0.695949 0 -0.718092 -0.838297 0 -0.545213 -0.876603 -0.0148508 -0.480985 -0.950851 0 -0.30965 -0.995913 0 -0.0903198 -0.999604 -0.0178359 0.0217537 -0.985354 0 0.170524 -0.922705 0 0.385508 -0.854807 -0.017835 0.518639 -0.791491 0 0.611181 -0.635631 0 0.771993 -0.480985 -0.0148488 0.876603 -0.414181 0 0.910195 -0.201243 0 0.979541 0.0217563 -0.00889368 0.999724 0.0591241 0 0.998251 -0.373095 0.694748 -0.614919 -0.373099 0.694743 -0.614922 -0.630574 0.694743 -0.345991 -0.630566 0.69475 -0.345991 -0.719078 0.694753 0.0156488 -0.719079 0.694752 0.0156495 -0.614919 0.69475 0.373091 -0.614925 0.694739 0.373102 -0.345992 0.69474 0.630576 -0.345992 0.694745 0.63057 0.0156489 0.694747 0.719084 0.0156495 0.694746 0.719085 0.0156493 -0.694749 0.719082 0.0156493 -0.694749 0.719082 -0.34599 -0.694746 0.63057 -0.345986 -0.694751 0.630567 -0.614918 -0.694752 0.37309 -0.614915 -0.694755 0.373089 -0.719076 -0.694755 0.0156488 -0.719072 -0.69476 0.0156503 -0.63056 -0.694759 -0.345983 -0.630559 -0.69476 -0.345982 -0.37309 -0.694756 -0.614913 -0.373091 -0.694753 -0.614915 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.0217573 -0.999763 0 0.0217573 -0.854943 0 0.518721 -0.854943 0 0.518721 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.373094 0.694748 -0.61492 -0.373097 0.694745 -0.614921 -0.630573 0.694744 -0.34599 -0.630564 0.694751 -0.34599 -0.719078 0.694753 0.0156489 -0.719079 0.694752 0.0156495 -0.614918 0.694751 0.37309 -0.61492 0.694748 0.373093 -0.345989 0.694747 0.630569 -0.345989 0.694745 0.630572 0.0156494 0.694746 0.719085 0.0156495 0.694746 0.719085 -0.373096 0.694743 -0.614924 -0.373093 0.694748 -0.61492 -0.630571 0.694746 -0.345989 -0.630567 0.69475 -0.345989 -0.719082 0.694749 0.0156478 -0.719085 0.694746 0.0156485 -0.614921 0.694745 0.373096 -0.614921 0.694746 0.373096 -0.345988 0.694748 0.630569 -0.345987 0.69475 0.630568 0.0156496 0.694749 0.719083 0.0156483 0.694753 0.719078 0.0156485 0.694746 0.719085 0.0156496 0.694742 0.719089 -0.34599 0.694744 0.630573 -0.389241 0.341758 0.85539 -0.450091 0.706121 0.546636 -0.562797 0.70313 0.434589 -0.77513 0.42189 0.4703 -0.654499 0.704878 0.273455 -0.698939 0.704879 0.120954 -0.906435 0.421885 0.0197255 -0.373094 0.694746 -0.614922 -0.373099 0.694739 -0.614927 -0.597967 0.700852 -0.3889 -0.768456 0.481339 -0.421649 -0.673287 0.706119 -0.219274 -0.708159 0.703127 -0.0642197 -0.373096 0.694746 -0.614921 -0.373094 0.694749 -0.614919 -0.630567 0.69475 -0.345987 -0.630569 0.694749 -0.345987 -0.719082 0.694749 0.0156495 -0.719078 0.694753 0.0156484 -0.614916 0.694753 0.373092 -0.614918 0.69475 0.373094 -0.345989 0.694749 0.630568 -0.345989 0.694748 0.630569 0.0156494 0.694747 0.719084 0.0156493 0.694747 0.719084 -0.373091 -0.694752 -0.614917 -0.395915 -0.580883 -0.711214 -0.492295 -0.706865 -0.507926 -0.630566 -0.694752 -0.345986 -0.761487 -0.418166 -0.495252 -0.673291 -0.706114 -0.219277 -0.70816 -0.703125 -0.0642208 -0.876472 -0.481074 0.0190749 -0.698946 -0.704872 0.120955 -0.654505 -0.704872 0.273456 -0.74951 -0.481073 0.454756 -0.562801 -0.703124 0.434593 -0.450096 -0.706117 0.546637 -0.409094 -0.526076 0.745578 0.0423345 -0.698066 0.714781 0.0173424 -0.604033 0.796771 -0.142356 -0.706862 0.692879 -0.29543 -0.700865 0.649238 -0.48639 0 -0.873742 -0.48639 0 -0.873742 -0.695972 0 -0.718069 -0.695972 0 -0.718069 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.950844 0 -0.30967 -0.950844 0 -0.30967 -0.995913 0 -0.0903162 -0.995913 0 -0.0903162 -0.985354 0 0.170519 -0.985354 0 0.170519 -0.922703 0 0.385511 -0.922703 0 0.385511 -0.791488 0 0.611185 -0.791488 0 0.611185 -0.635644 0 0.771983 -0.635644 0 0.771983 -0.414177 0 0.910196 -0.414177 0 0.910196 -0.201252 0 0.97954 -0.201252 0 0.97954 0.0591236 0 0.998251 0.0591236 0 0.998251 0.0156509 0.694742 0.719089 0.0462966 0.621961 0.781678 -0.142356 0.70686 0.692881 -0.345989 0.694747 0.630569 -0.35177 0.527872 0.773052 -0.450097 0.706116 0.546638 -0.614922 0.694745 0.373094 -0.722343 0.408767 0.557791 -0.654509 0.704868 0.273458 -0.69895 0.704868 0.120955 -0.823732 0.566696 0.0179285 -0.708162 0.703124 -0.064221 -0.673291 0.706114 -0.219277 -0.706624 0.591908 -0.38772 -0.348267 0.698077 -0.625619 -0.399689 0.637412 -0.658752 -0.492298 0.706859 -0.507929 -0.597958 0.700861 -0.388896 0.0156489 -0.694746 0.719085 0.0156496 -0.694749 0.719083 -0.345989 -0.694749 0.630567 -0.345987 -0.694752 0.630565 -0.614915 -0.694752 0.373094 -0.614916 -0.694751 0.373094 -0.719078 -0.694753 0.0156487 -0.719082 -0.694749 0.0156476 -0.630567 -0.69475 -0.345988 -0.630566 -0.694752 -0.345987 -0.373093 -0.694752 -0.614916 -0.373094 -0.694746 -0.614922 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373096 0.694745 -0.614922 -0.373096 0.694746 -0.614921 -0.630569 0.694747 -0.345989 -0.630569 0.694747 -0.345989 -0.719085 0.694746 0.0156489 -0.719089 0.694742 0.0156509 -0.614924 0.694741 0.3731 -0.61492 0.694747 0.373094 -0.345991 0.694746 0.63057 -0.345991 0.694743 0.630573 0.015649 0.694742 0.719089 0.015649 0.694742 0.719089 0.0156489 -0.694746 0.719085 0.0156496 -0.694749 0.719083 -0.345988 -0.69475 0.630567 -0.345989 -0.694749 0.630568 -0.614917 -0.69475 0.373095 -0.614916 -0.694751 0.373094 -0.719078 -0.694753 0.0156487 -0.719082 -0.694749 0.0156476 -0.630567 -0.69475 -0.345988 -0.630568 -0.694749 -0.345989 -0.373096 -0.694746 -0.614921 -0.373096 -0.694745 -0.614921 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.85494 0 0.518726 -0.85494 0 0.518726 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373098 0.694741 -0.614925 -0.373094 0.694745 -0.614922 -0.630569 0.694747 -0.345989 -0.630572 0.694745 -0.345989 -0.719085 0.694746 0.0156489 -0.719089 0.694742 0.0156509 -0.614924 0.694741 0.373099 -0.614921 0.694747 0.373094 -0.34599 0.694746 0.630571 -0.34599 0.694747 0.630569 0.0156489 0.694746 0.719085 0.0156499 0.694744 0.719087 0.0156494 -0.694747 0.719084 0.0156494 -0.694747 0.719084 -0.345989 -0.694748 0.630569 -0.345989 -0.694749 0.630568 -0.614917 -0.69475 0.373095 -0.614915 -0.694752 0.373094 -0.719078 -0.694753 0.0156488 -0.719082 -0.694749 0.0156476 -0.630568 -0.694748 -0.345989 -0.630567 -0.69475 -0.345988 -0.373094 -0.694749 -0.614919 -0.373095 -0.694747 -0.61492 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.85494 0 0.518726 -0.85494 0 0.518726 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217579 0 0.999763 0.0217579 0 0.999763 -0.373097 0.694744 -0.614922 -0.373095 0.694746 -0.614921 -0.630569 0.694748 -0.345989 -0.63057 0.694746 -0.345989 -0.719085 0.694746 0.0156489 -0.719089 0.694742 0.0156509 -0.614924 0.694742 0.373099 -0.61492 0.694748 0.373094 -0.34599 0.694747 0.63057 -0.34599 0.694746 0.63057 0.0156495 0.694745 0.719086 0.0156493 0.694745 0.719086 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.854943 0 0.518723 -0.854943 0 0.518723 -0.481038 0 0.8767 -0.481038 0 0.8767 0.021758 0 0.999763 0.021758 0 0.999763 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876701 0 -0.481036 -0.876701 0 -0.481036 -0.999763 0 0.0217581 -0.999763 0 0.0217581 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481042 0 0.876698 -0.481042 0 0.876698 0.021758 0 0.999763 0.021758 0 0.999763 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876698 0 -0.481042 -0.876698 0 -0.481042 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.48104 0 0.876699 -0.48104 0 0.876699 0.021758 0 0.999763 0.021758 0 0.999763 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0423337 -0.698082 0.714765 0.0423352 -0.698087 0.714761 -0.271981 -0.698086 0.662346 -0.271988 -0.698077 0.662352 -0.532433 -0.698077 0.478752 -0.532438 -0.698071 0.478754 -0.687432 -0.698074 0.200323 -0.687426 -0.69808 0.200324 -0.706272 -0.698075 -0.117779 -0.706272 -0.698075 -0.117778 -0.585228 -0.698071 -0.412559 -0.585223 -0.69808 -0.412551 -0.348267 -0.698082 -0.625613 -0.348267 -0.698082 -0.625613 -0.486394 0 -0.873739 -0.486394 0 -0.873739 -0.817325 0 -0.576176 -0.817325 0 -0.576176 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.960067 0 0.279771 -0.960067 0 0.279771 -0.743598 0 0.668627 -0.743598 0 0.668627 -0.379855 0 0.925046 -0.379855 0 0.925046 0.0591238 0 0.998251 0.0591238 0 0.998251 -0.348269 0.698078 -0.625616 -0.348275 0.698073 -0.625619 -0.585227 0.698073 -0.412558 -0.585226 0.698074 -0.412558 -0.706273 0.698073 -0.117779 -0.706274 0.698073 -0.117779 -0.687433 0.698074 0.200324 -0.687435 0.698071 0.200326 -0.53244 0.698068 0.478759 -0.532438 0.698073 0.478752 -0.271986 0.698073 0.662357 -0.271985 0.698069 0.662362 0.0423345 0.698069 0.714778 0.0423352 0.698068 0.714779 0.0423347 -0.698064 0.714783 0.0423363 -0.698069 0.714778 -0.271988 -0.698068 0.662362 -0.271982 -0.698077 0.662355 -0.532435 -0.698078 0.478749 -0.532426 -0.698088 0.478745 -0.687422 -0.698085 0.200323 -0.687425 -0.698081 0.200322 -0.706271 -0.698076 -0.117776 -0.706272 -0.698075 -0.117777 -0.585223 -0.69808 -0.412551 -0.585226 -0.698075 -0.412556 -0.348273 -0.698069 -0.625624 -0.348274 -0.698065 -0.625628 -0.486394 0 -0.873739 -0.486394 0 -0.873739 -0.817328 0 -0.576173 -0.817328 0 -0.576173 -0.986379 0 -0.164487 -0.986379 0 -0.164487 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743602 0 0.668623 -0.743602 0 0.668623 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591238 0 0.998251 0.0591238 0 0.998251 -0.348273 0.69807 -0.625623 -0.34827 0.698073 -0.625622 -0.585228 0.698074 -0.412555 -0.585231 0.698071 -0.412555 -0.706278 0.698069 -0.117777 -0.706271 0.698075 -0.117781 -0.68743 0.698076 0.200325 -0.68743 0.698076 0.200325 -0.532436 0.698077 0.478749 -0.532436 0.698076 0.47875 -0.271986 0.698075 0.662356 -0.271985 0.69807 0.662361 0.0423344 0.698069 0.714778 0.0423351 0.698068 0.714779 -0.373098 -0.694741 -0.614925 -0.388078 -0.602838 -0.697124 -0.492286 -0.706854 -0.507949 -0.630575 -0.694741 -0.345991 -0.736337 -0.477993 -0.478885 -0.673292 -0.706109 -0.219288 -0.719089 -0.694742 0.0156446 -0.945187 -0.315078 -0.0857195 -0.698936 -0.704881 0.120957 -0.654498 -0.704881 0.273451 -0.726272 -0.527586 0.440662 -0.562795 -0.703127 0.434596 -0.450098 -0.706117 0.546636 -0.398009 -0.56163 0.72537 0.0423344 -0.698074 0.714773 0.0170411 -0.621817 0.782977 -0.142358 -0.706866 0.692875 -0.295427 -0.700871 0.649233 -0.486397 0 -0.873738 -0.486397 0 -0.873738 -0.695949 0 -0.718092 -0.695949 0 -0.718092 -0.838305 0 -0.545201 -0.838305 0 -0.545201 -0.95084 0 -0.309683 -0.95084 0 -0.309683 -0.995913 0 -0.0903198 -0.995913 0 -0.0903198 -0.985354 0 0.170524 -0.985354 0 0.170524 -0.922705 0 0.385508 -0.922705 0 0.385508 -0.791483 0 0.611191 -0.791483 0 0.611191 -0.635646 0 0.77198 -0.635646 0 0.77198 -0.414176 0 0.910197 -0.414176 0 0.910197 -0.201256 0 0.979539 -0.201256 0 0.979539 0.0591241 0 0.998251 0.0591241 0 0.998251 0.0156495 0.694746 0.719085 0.0453703 0.641199 0.766033 -0.142359 0.706862 0.692879 -0.345989 0.694751 0.630566 -0.338662 0.575678 0.744247 -0.450099 0.706116 0.546636 -0.61492 0.694747 0.373094 -0.687174 0.496195 0.530643 -0.654511 0.704867 0.273456 -0.69895 0.704867 0.120959 -0.796364 0.604569 0.0173314 -0.708165 0.70312 -0.0642239 -0.673292 0.70611 -0.219287 -0.686707 0.621661 -0.376789 -0.348275 0.69807 -0.625623 -0.392755 0.653235 -0.647323 -0.492285 0.706855 -0.507948 -0.597964 0.700858 -0.388893 -0.373092 0.694752 -0.614916 -0.373094 0.69475 -0.614918 -0.630568 0.694749 -0.345989 -0.630568 0.694748 -0.345989 -0.719084 0.694747 0.0156494 -0.719084 0.694747 0.0156494 -0.614921 0.694747 0.373094 -0.614925 0.694742 0.373097 -0.345993 0.694738 0.630578 -0.34599 0.694748 0.630568 0.0156495 0.694749 0.719082 0.0156519 0.69474 0.719091 0.0156487 0.694739 0.719092 0.0156498 0.694735 0.719096 -0.194567 0.706831 0.680098 -0.302064 0.778264 0.550511 -0.373098 0.69474 -0.614927 -0.3731 0.694736 -0.614929 -0.630578 0.694739 -0.345991 -0.630567 0.69475 -0.345989 -0.719083 0.694749 0.0156496 -0.719085 0.694746 0.0156501 -0.614921 0.694745 0.373096 -0.614917 0.694752 0.373092 -0.368366 0.698178 0.613884 -0.373093 0.694751 -0.614917 -0.373093 0.694752 -0.614916 -0.630564 0.694752 -0.345989 -0.630567 0.694749 -0.34599 -0.719083 0.694749 0.0156495 -0.719091 0.69474 0.0156519 -0.614926 0.694739 0.373099 -0.614918 0.694751 0.37309 -0.345988 0.694752 0.630565 -0.34599 0.694743 0.630574 0.0156495 0.694749 0.719082 0.0156501 0.694746 0.719085 0.0423344 -0.698066 0.714781 0.0423369 -0.698075 0.714772 -0.271985 -0.698075 0.662356 -0.271993 -0.698063 0.662366 -0.532443 -0.698066 0.478757 -0.53244 -0.698069 0.478756 -0.687434 -0.698072 0.200326 -0.687432 -0.698074 0.200326 -0.706272 -0.698074 -0.117779 -0.706272 -0.698075 -0.117778 -0.585226 -0.698077 -0.412552 -0.585227 -0.698075 -0.412554 -0.34827 -0.698076 -0.625618 -0.348272 -0.698068 -0.625626 -0.518726 0 -0.85494 -0.486378 -0.00834283 -0.873709 -0.838278 0.00717226 -0.545195 -0.817329 0 -0.576172 -0.950845 0 -0.309667 -0.986333 0.00960131 -0.164482 -0.995913 0 -0.0903169 -0.985354 0 0.170521 -0.96001 0.0108064 0.279757 -0.922704 0 0.385509 -0.791487 0 0.611186 -0.743566 0.00960109 0.668593 -0.635644 0 0.771982 -0.414177 0 0.910196 -0.379847 0.00599258 0.92503 0.0217565 -0.00717239 0.999738 0.0591236 0 0.998251 0.0156509 0.694742 0.719089 0.0156489 0.694746 0.719085 -0.345992 0.694746 0.630569 -0.351774 0.52786 0.773059 -0.450101 0.706111 0.546642 -0.614923 0.694742 0.373098 -0.722342 0.408767 0.557792 -0.654507 0.704871 0.273455 -0.698946 0.704871 0.120957 -0.823732 0.566696 0.0179268 -0.373099 0.694742 -0.614924 -0.373094 0.694748 -0.61492 -0.597957 0.700862 -0.388896 -0.706623 0.591911 -0.38772 -0.67329 0.706115 -0.219274 -0.708162 0.703123 -0.0642214 0.0423345 -0.698066 0.714781 0.042337 -0.698075 0.714772 -0.271984 -0.698076 0.662356 -0.271993 -0.698062 0.662366 -0.532444 -0.698065 0.478758 -0.532442 -0.698067 0.478757 -0.687437 -0.698069 0.200327 -0.687433 -0.698073 0.200327 -0.706273 -0.698073 -0.117779 -0.706272 -0.698075 -0.117779 -0.585226 -0.698077 -0.412552 -0.585229 -0.698072 -0.412555 -0.34827 -0.698074 -0.62562 -0.348271 -0.69807 -0.625624 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.817329 0 -0.576171 -0.817329 0 -0.576171 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743601 0 0.668624 -0.743601 0 0.668624 -0.379853 0 0.925047 -0.379853 0 0.925047 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.348272 0.698071 -0.625623 -0.348274 0.698068 -0.625624 -0.585234 0.698067 -0.412557 -0.585227 0.698074 -0.412556 -0.706272 0.698074 -0.117779 -0.706274 0.698073 -0.117779 -0.687432 0.698074 0.200325 -0.687432 0.698073 0.200326 -0.532437 0.698074 0.478752 -0.532441 0.698065 0.478761 -0.271989 0.698063 0.662367 -0.27199 0.698072 0.662357 0.042334 0.698074 0.714774 0.0423366 0.698069 0.714778 0.015649 -0.694739 0.719092 0.0156514 -0.694748 0.719083 -0.345988 -0.69475 0.630567 -0.345989 -0.694749 0.630568 -0.614921 -0.694746 0.373096 -0.614921 -0.694745 0.373096 -0.719085 -0.694746 0.0156488 -0.719082 -0.694749 0.0156495 -0.630567 -0.694749 -0.345989 -0.630565 -0.694752 -0.345987 -0.373094 -0.694752 -0.614915 -0.373097 -0.69474 -0.614927 -0.518727 0 -0.85494 -0.518727 0 -0.85494 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.999763 0 0.021757 -0.999763 0 0.021757 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.3731 0.694741 -0.614924 -0.373094 0.694747 -0.61492 -0.63057 0.694746 -0.345991 -0.630569 0.694747 -0.345991 -0.719085 0.694746 0.0156488 -0.719089 0.694742 0.0156508 -0.614925 0.694741 0.373098 -0.614925 0.694741 0.373098 -0.345993 0.694739 0.630576 -0.345992 0.694747 0.630568 0.0156489 0.694746 0.719085 0.0156509 0.694742 0.719089 -0.348272 -0.698072 -0.625621 -0.348273 -0.698068 -0.625625 -0.492287 -0.706854 -0.507947 -0.637878 -0.625225 -0.449672 -0.597962 -0.700855 -0.388899 -0.6733 -0.706109 -0.219263 -0.809402 -0.571532 -0.134979 -0.708154 -0.703131 -0.0642238 -0.698938 -0.704879 0.120959 -0.80071 -0.551739 0.233339 -0.654506 -0.704873 0.273452 -0.532436 -0.698076 0.478751 -0.696478 -0.475046 0.537819 -0.45009 -0.706121 0.546637 -0.271985 -0.698077 0.662354 0.0423341 -0.698073 0.714774 0.0423346 -0.698075 0.714772 -0.142359 -0.706863 0.692878 -0.33008 -0.60404 0.725385 -0.486394 0 -0.87374 -0.518709 -0.0071722 -0.854921 -0.695951 0 -0.718089 -0.8383 0 -0.545209 -0.876639 -0.0119767 -0.481 -0.950851 0 -0.309649 -0.995913 0 -0.0903212 -0.99966 -0.0143847 0.0217548 -0.985353 0 0.170526 -0.922706 0 0.385505 -0.854854 -0.0143843 0.518669 -0.791488 0 0.611185 -0.635639 0 0.771987 -0.481003 -0.0119761 0.876637 -0.414177 0 0.910196 -0.201256 0 0.979539 0.0217566 -0.00717238 0.999738 0.0591236 0 0.998251 -0.373096 0.694741 -0.614926 -0.373097 0.694741 -0.614926 -0.630578 0.694739 -0.34599 -0.630572 0.694745 -0.345989 -0.719085 0.694746 0.0156489 -0.719081 0.694751 0.0156471 -0.614919 0.694749 0.373092 -0.614924 0.694742 0.373099 -0.345989 0.694745 0.630572 -0.345989 0.694747 0.630569 0.0156489 0.694746 0.719085 0.015649 0.694746 0.719085 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481042 0 0.876698 -0.481042 0 0.876698 0.021758 0 0.999763 0.021758 0 0.999763 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.486396 0 -0.873739 -0.518641 0.0178255 -0.854806 -0.695953 0 -0.718087 -0.8383 0 -0.545209 -0.876311 0.0297579 -0.480825 -0.950847 0 -0.309662 -0.995913 0 -0.090319 -0.999125 0.0357359 0.0217418 -0.985354 0 0.17052 -0.922704 0 0.385509 -0.854395 0.0357361 0.518393 -0.791487 0 0.611186 -0.635639 0 0.771987 -0.480825 0.0297574 0.876311 0.0591246 0 0.998251 0.0217546 0.0178262 0.999604 -0.201255 0 0.979539 -0.414179 0 0.910196 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876698 0 -0.481041 -0.876698 0 -0.481041 -0.999763 0 0.0217581 -0.999763 0 0.0217581 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481036 0 0.876701 -0.481036 0 0.876701 0.0217581 0 0.999763 0.0217581 0 0.999763 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0156488 -0.694755 0.719076 0.0156446 -0.694742 0.719089 -0.34599 -0.694743 0.630574 -0.345989 -0.694744 0.630573 -0.61492 -0.694747 0.373095 -0.614923 -0.694744 0.373096 -0.719082 -0.694749 0.0156493 -0.719082 -0.694749 0.0156493 -0.63057 -0.694746 -0.34599 -0.630567 -0.694751 -0.345986 -0.37309 -0.694752 -0.614918 -0.37309 -0.694755 -0.614915 -0.518721 0 -0.854943 -0.518721 0 -0.854943 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217573 0 0.999763 0.0217573 0 0.999763 -0.37309 0.694751 -0.614918 -0.373093 0.694748 -0.61492 -0.630569 0.694747 -0.345989 -0.630572 0.694745 -0.345989 -0.719085 0.694746 0.0156494 -0.719085 0.694746 0.0156495 -0.614924 0.694742 0.373097 -0.614923 0.694745 0.373095 -0.34599 0.694744 0.630573 -0.34599 0.694742 0.630574 0.0156491 0.694742 0.719089 0.0156497 0.694741 0.71909 0.0423337 -0.698082 0.714765 0.0423353 -0.698087 0.71476 -0.271981 -0.698086 0.662347 -0.271989 -0.698075 0.662355 -0.532438 -0.698071 0.478754 -0.532434 -0.698075 0.478753 -0.687426 -0.69808 0.200324 -0.68743 -0.698076 0.200324 -0.706268 -0.698079 -0.117775 -0.706274 -0.698073 -0.117778 -0.585229 -0.698069 -0.412561 -0.58522 -0.698085 -0.412547 -0.348266 -0.698085 -0.625611 -0.348266 -0.698085 -0.62561 -0.518722 0 -0.854943 -0.486368 -0.0103435 -0.873693 -0.838264 0.00889414 -0.545192 -0.817324 0 -0.576178 -0.950846 0 -0.309664 -0.98631 0.0119056 -0.164473 -0.995914 0 -0.0903111 -0.985355 0 0.170515 -0.95998 0.0134001 0.279749 -0.922702 0 0.385513 -0.791488 0 0.611185 -0.743547 0.0119054 0.668578 -0.635638 0 0.771987 -0.414178 0 0.910196 -0.379843 0.00743101 0.925021 0.0217563 -0.00889366 0.999724 0.0591238 0 0.998251 0.0156495 0.694752 0.719079 0.0156488 0.694753 0.719078 -0.345991 0.69475 0.630566 -0.338664 0.575679 0.744245 -0.450096 0.706112 0.546644 -0.614922 0.694743 0.373099 -0.687168 0.496219 0.530629 -0.654503 0.704874 0.273457 -0.698945 0.704873 0.120952 -0.796353 0.604584 0.0173311 -0.37309 0.694753 -0.614916 -0.373101 0.694741 -0.614923 -0.597957 0.70086 -0.3889 -0.68671 0.621655 -0.376796 -0.673291 0.706116 -0.219272 -0.708161 0.703125 -0.0642172 0.0423344 -0.698074 0.714773 0.0423356 -0.698077 0.71477 -0.271983 -0.698081 0.662351 -0.271985 -0.698078 0.662353 -0.532433 -0.698078 0.47875 -0.532443 -0.698068 0.478754 -0.68744 -0.698065 0.200328 -0.687438 -0.698067 0.200328 -0.706276 -0.698069 -0.117784 -0.706264 -0.698083 -0.117776 -0.585222 -0.698082 -0.412549 -0.585227 -0.698072 -0.412558 -0.348273 -0.698073 -0.62562 -0.348274 -0.698068 -0.625625 -0.518725 0 -0.854941 -0.486371 -0.0103439 -0.873691 -0.83827 0.00889494 -0.545183 -0.817328 0 -0.576172 -0.950841 0 -0.309679 -0.986308 0.011906 -0.164485 -0.995913 0 -0.0903198 -0.985353 0 0.170526 -0.95998 0.0133988 0.279749 -0.922706 0 0.385504 -0.79148 0 0.611195 -0.743547 0.0119036 0.668578 -0.635656 0 0.771973 -0.414176 0 0.910197 -0.379843 0.00743052 0.925021 0.0217565 -0.00889364 0.999724 0.0591241 0 0.998251 0.0156497 0.694746 0.719085 0.0156491 0.694747 0.719084 -0.345989 0.694746 0.630571 -0.338662 0.575678 0.744247 -0.450103 0.70612 0.546627 -0.614918 0.69475 0.373092 -0.687174 0.49619 0.530648 -0.65451 0.70487 0.273452 -0.698949 0.704868 0.12096 -0.796364 0.604569 0.0173314 -0.373097 0.694742 -0.614924 -0.373093 0.694747 -0.614921 -0.59796 0.700861 -0.388893 -0.686707 0.621661 -0.376789 -0.673291 0.706112 -0.219284 -0.708165 0.70312 -0.0642238 -0.373092 0.694752 -0.614916 -0.373094 0.69475 -0.614918 -0.630568 0.694749 -0.345989 -0.630569 0.694748 -0.345989 -0.719084 0.694747 0.0156494 -0.719084 0.694747 0.0156493 -0.614921 0.694746 0.373096 -0.614919 0.694749 0.373094 -0.345989 0.694751 0.630565 -0.34599 0.694748 0.630568 0.0156495 0.694749 0.719082 0.0156519 0.69474 0.719091 0.0423332 0.69808 0.714767 0.0423346 0.698076 0.714771 -0.142358 0.70686 0.69288 -0.301496 0.60829 0.734223 -0.295431 0.700866 0.649237 -0.45009 0.706121 0.546637 -0.626088 0.539528 0.56296 -0.562801 0.703123 0.434595 -0.654504 0.704874 0.273454 -0.823671 0.513764 0.240026 -0.698945 0.704872 0.120955 -0.706273 0.698073 -0.117778 -0.905903 0.41544 -0.0821561 -0.673289 0.706118 -0.21927 -0.585225 0.698077 -0.412554 -0.348268 0.698082 -0.625613 -0.348271 0.698078 -0.625616 -0.492282 0.706864 -0.507939 -0.681498 0.58233 -0.443229 -0.373096 0.694745 -0.614921 -0.373096 0.694746 -0.614921 -0.630567 0.694749 -0.34599 -0.630578 0.694738 -0.345993 -0.719096 0.694735 0.0156498 -0.719092 0.694739 0.0156487 -0.614927 0.69474 0.373098 -0.614929 0.694736 0.3731 -0.345991 0.694739 0.630578 -0.345989 0.69475 0.630567 0.0156496 0.694749 0.719083 0.0156484 0.694753 0.719078 0.0156487 -0.694753 0.719078 0.0156476 -0.694749 0.719082 -0.345989 -0.694748 0.630568 -0.345988 -0.69475 0.630567 -0.614918 -0.694749 0.373094 -0.614921 -0.694746 0.373095 -0.719084 -0.694747 0.0156494 -0.719084 -0.694747 0.0156495 -0.630569 -0.694749 -0.345987 -0.630573 -0.694742 -0.345992 -0.373098 -0.694738 -0.614929 -0.373094 -0.694752 -0.614915 -0.518722 0 -0.854943 -0.518722 0 -0.854943 -0.8767 0 -0.481037 -0.8767 0 -0.481037 -0.999763 0 0.0217579 -0.999763 0 0.0217579 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373095 0.694742 -0.614925 -0.373098 0.69474 -0.614927 -0.630575 0.694742 -0.345991 -0.63057 0.694746 -0.34599 -0.719086 0.694745 0.0156495 -0.719086 0.694745 0.0156494 -0.614922 0.694744 0.373097 -0.614921 0.694747 0.373094 -0.345989 0.694748 0.630569 -0.345989 0.694746 0.63057 0.0156489 0.694746 0.719085 0.015647 0.694751 0.719081 0.0156487 -0.694753 0.719078 0.0156476 -0.694749 0.719082 -0.345989 -0.69475 0.630567 -0.345988 -0.69475 0.630567 -0.614919 -0.694749 0.373094 -0.614919 -0.694748 0.373094 -0.719081 -0.69475 0.0156499 -0.719086 -0.694745 0.0156487 -0.63057 -0.694747 -0.345989 -0.630574 -0.694742 -0.345992 -0.373098 -0.694738 -0.614928 -0.373095 -0.694751 -0.614916 -0.518723 0 -0.854943 -0.518723 0 -0.854943 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.0217586 -0.999763 0 0.0217586 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373096 0.694741 -0.614926 -0.373097 0.69474 -0.614926 -0.630574 0.694743 -0.34599 -0.630571 0.694745 -0.34599 -0.719087 0.694744 0.01565 -0.719085 0.694746 0.015649 -0.614922 0.694745 0.373096 -0.61492 0.694747 0.373094 -0.345989 0.694749 0.630568 -0.345989 0.694745 0.630571 0.0156489 0.694746 0.719085 0.0156471 0.694751 0.719081 0.0156487 -0.694753 0.719078 0.0156476 -0.694749 0.719082 -0.345991 -0.694746 0.63057 -0.345987 -0.694752 0.630566 -0.614916 -0.694752 0.373093 -0.614922 -0.694746 0.373094 -0.719084 -0.694746 0.015651 -0.719089 -0.694742 0.0156497 -0.630573 -0.694744 -0.34599 -0.630576 -0.694739 -0.345993 -0.373098 -0.694736 -0.614931 -0.373093 -0.694755 -0.614913 -0.518722 0 -0.854943 -0.518722 0 -0.854943 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.02176 -0.999763 0 0.02176 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373094 0.694744 -0.614924 -0.373098 0.694739 -0.614927 -0.630575 0.694741 -0.345991 -0.630573 0.694743 -0.345991 -0.719089 0.694741 0.0156511 -0.719085 0.694746 0.015649 -0.614922 0.694745 0.373096 -0.614919 0.694749 0.373092 -0.345989 0.69475 0.630567 -0.345989 0.694745 0.630571 0.0156489 0.694746 0.719085 0.015647 0.694751 0.71908 -0.373094 -0.694746 -0.614922 -0.373093 -0.694752 -0.614916 -0.630566 -0.694752 -0.345987 -0.761494 -0.418139 -0.495264 -0.673291 -0.706119 -0.21926 -0.708158 -0.703127 -0.0642245 -0.876475 -0.481069 0.0190726 -0.698938 -0.704879 0.120958 -0.654501 -0.704879 0.27345 -0.749509 -0.481078 0.454753 0.0156489 -0.694746 0.719085 0.0156496 -0.694749 0.719083 -0.295432 -0.700864 0.649237 -0.409087 -0.526094 0.745569 -0.450086 -0.706121 0.546641 -0.562797 -0.70313 0.43459 -0.486394 0 -0.87374 -0.518712 0.00717277 -0.854919 -0.817312 -0.00599191 -0.576165 -0.838297 0 -0.545215 -0.950851 0 -0.309649 -0.986334 -0.00960033 -0.164479 -0.995913 0 -0.0903217 -0.985353 0 0.170525 -0.96001 -0.010806 0.279757 -0.922706 0 0.385505 -0.791488 0 0.611185 -0.743564 -0.00960179 0.668596 -0.635633 0 0.771992 -0.379857 0 0.925045 -0.414169 -0.00717247 0.910172 0.0591215 0.00834226 0.998216 0.0217571 0 0.999763 -0.348271 0.698072 -0.625621 -0.348272 0.698072 -0.625622 -0.58523 0.69807 -0.412558 -0.58523 0.69807 -0.412558 -0.706277 0.698069 -0.117778 -0.706274 0.698073 -0.117779 -0.687432 0.698074 0.200325 -0.687436 0.698069 0.200329 -0.532438 0.69807 0.478757 -0.532436 0.698074 0.478753 -0.271988 0.698073 0.662357 -0.271988 0.698072 0.662358 0.042334 0.698074 0.714774 0.0423366 0.698069 0.714778 -0.486396 0 -0.873739 -0.486396 0 -0.873739 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960065 0 0.279776 -0.960065 0 0.279776 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.379855 0 0.925046 -0.379855 0 0.925046 0.0591247 0 0.998251 0.0591247 0 0.998251 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.486396 0 -0.873739 -0.486396 0 -0.873739 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.379857 0 0.925045 -0.379857 0 0.925045 0.0591247 0 0.998251 0.0591247 0 0.998251 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217578 0 0.999763 0.0217578 0 0.999763 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0423347 -0.698064 0.714783 0.0423363 -0.698069 0.714778 -0.271988 -0.698068 0.662362 -0.271982 -0.698077 0.662355 -0.532435 -0.698078 0.478749 -0.532426 -0.698088 0.478745 -0.687422 -0.698085 0.200323 -0.687431 -0.698076 0.200322 -0.706268 -0.698079 -0.117776 -0.706271 -0.698076 -0.117778 -0.585223 -0.69808 -0.412551 -0.58523 -0.698067 -0.412563 -0.348275 -0.698065 -0.625628 -0.348275 -0.698065 -0.625628 -0.486394 0 -0.873739 -0.486394 0 -0.873739 -0.817328 0 -0.576173 -0.817328 0 -0.576173 -0.986379 0 -0.164487 -0.986379 0 -0.164487 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743602 0 0.668623 -0.743602 0 0.668623 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591238 0 0.998251 0.0591238 0 0.998251 -0.348274 0.698068 -0.625625 -0.348268 0.698073 -0.625623 -0.585228 0.698074 -0.412555 -0.585231 0.698071 -0.412555 -0.706278 0.698069 -0.117777 -0.706271 0.698075 -0.117781 -0.68743 0.698076 0.200325 -0.68743 0.698076 0.200325 -0.532436 0.698077 0.478749 -0.532436 0.698076 0.47875 -0.271986 0.698075 0.662356 -0.271985 0.69807 0.662361 0.0423344 0.698069 0.714778 0.0423351 0.698068 0.714779 0.042334 -0.698072 0.714775 0.042336 -0.698078 0.714769 -0.271985 -0.698074 0.662357 -0.271987 -0.698071 0.66236 -0.532447 -0.698064 0.478755 -0.53243 -0.698081 0.478749 -0.687424 -0.698082 0.200323 -0.687422 -0.698084 0.200324 -0.70626 -0.698088 -0.117774 -0.706264 -0.698083 -0.117776 -0.585222 -0.698082 -0.412549 -0.585227 -0.698072 -0.412558 -0.34827 -0.698072 -0.625622 -0.348269 -0.698077 -0.625617 -0.486392 0 -0.873741 -0.486392 0 -0.873741 -0.817328 0 -0.576172 -0.817328 0 -0.576172 -0.98638 0 -0.164486 -0.98638 0 -0.164486 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743605 0 0.668619 -0.743605 0 0.668619 -0.379854 0 0.925047 -0.379854 0 0.925047 0.0591234 0 0.998251 0.0591234 0 0.998251 -0.348269 0.698075 -0.62562 -0.348273 0.698071 -0.625622 -0.585232 0.69807 -0.412557 -0.585224 0.698076 -0.412556 -0.706269 0.698079 -0.117775 -0.706271 0.698076 -0.117774 -0.68743 0.698076 0.200325 -0.687431 0.698074 0.200327 -0.53244 0.698074 0.478749 -0.532441 0.698071 0.478751 -0.271986 0.698073 0.662358 -0.271986 0.698073 0.662358 0.0423339 0.698075 0.714773 0.042335 0.698073 0.714774 0.0423349 -0.698077 0.71477 0.0423346 -0.698076 0.714771 -0.271983 -0.698079 0.662352 -0.271985 -0.698077 0.662354 -0.532433 -0.698078 0.47875 -0.532431 -0.69808 0.47875 -0.687424 -0.698082 0.200323 -0.68742 -0.698086 0.200324 -0.706261 -0.698087 -0.117774 -0.70628 -0.698066 -0.117786 -0.585234 -0.698067 -0.412558 -0.58523 -0.698073 -0.412552 -0.348269 -0.698075 -0.62562 -0.348268 -0.69808 -0.625615 -0.486392 0 -0.873741 -0.486392 0 -0.873741 -0.817329 0 -0.576172 -0.817329 0 -0.576172 -0.986379 0 -0.164486 -0.986379 0 -0.164486 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743599 0 0.668625 -0.743599 0 0.668625 -0.379854 0 0.925046 -0.379854 0 0.925046 0.0591251 0 0.998251 0.0591251 0 0.998251 -0.348269 0.698075 -0.62562 -0.348272 0.698071 -0.625622 -0.585231 0.69807 -0.412556 -0.585232 0.69807 -0.412556 -0.706278 0.698068 -0.117777 -0.706271 0.698076 -0.117781 -0.68743 0.698076 0.200325 -0.687431 0.698075 0.200326 -0.532436 0.698074 0.478753 -0.532437 0.698072 0.478756 -0.271986 0.698072 0.662359 -0.271987 0.698076 0.662355 0.0423352 0.698072 0.714774 0.0423347 0.698073 0.714774 -0.348275 0.698066 -0.625626 -0.34827 0.698074 -0.62562 -0.585228 0.698073 -0.412556 -0.585224 0.698077 -0.412555 -0.706272 0.698075 -0.117778 -0.706273 0.698074 -0.117778 -0.687433 0.698073 0.200327 -0.687433 0.698073 0.200327 -0.532435 0.698076 0.478752 -0.532435 0.698074 0.478753 -0.271985 0.698074 0.662356 -0.271985 0.698076 0.662355 0.0423347 0.698076 0.714772 0.0423332 0.69808 0.714767 -0.348272 0.698072 -0.625621 -0.348271 0.698074 -0.625619 -0.585228 0.698073 -0.412556 -0.58523 0.698071 -0.412557 -0.706278 0.698068 -0.117779 -0.70628 0.698067 -0.117779 -0.687439 0.698066 0.200328 -0.687435 0.698071 0.200326 -0.532438 0.698071 0.478755 -0.532439 0.698069 0.478757 -0.271988 0.698072 0.662358 -0.271989 0.698067 0.662363 0.0423351 0.698069 0.714778 0.0423338 0.698073 0.714774 -0.373096 0.694746 -0.614921 -0.373094 0.694749 -0.614919 -0.630567 0.69475 -0.345987 -0.630569 0.694748 -0.345987 -0.719082 0.694749 0.0156495 -0.719078 0.694753 0.0156484 -0.614916 0.694752 0.373092 -0.614918 0.69475 0.373094 -0.345989 0.694749 0.630568 -0.345989 0.694748 0.630569 0.0156494 0.694747 0.719084 0.0156494 0.694747 0.719084 -0.37309 -0.694755 -0.614914 -0.373092 -0.694748 -0.614921 -0.630572 -0.694746 -0.345989 -0.761492 -0.418154 -0.495255 -0.673294 -0.706112 -0.219273 -0.708165 -0.70312 -0.0642219 -0.876479 -0.481062 0.019075 -0.698945 -0.704873 0.120959 -0.654507 -0.704872 0.273452 -0.749514 -0.481067 0.454756 0.0156487 -0.694753 0.719078 0.0156476 -0.694749 0.719082 -0.295432 -0.700862 0.64924 -0.409092 -0.52608 0.745576 -0.450094 -0.706121 0.546634 -0.562795 -0.70313 0.434592 -0.486394 0 -0.87374 -0.518708 0.00717202 -0.854921 -0.817312 -0.00599283 -0.576164 -0.8383 0 -0.545209 -0.950846 0 -0.309664 -0.986333 -0.00960128 -0.164483 -0.995913 0 -0.0903172 -0.985353 0 0.170525 -0.96001 -0.010806 0.279757 -0.922706 0 0.385505 -0.791485 0 0.611188 -0.743565 -0.00960103 0.668595 -0.635644 0 0.771983 -0.379854 0 0.925046 -0.414168 -0.00717268 0.910172 0.0591215 0.0083423 0.998216 0.0217571 0 0.999763 -0.348268 0.698079 -0.625616 -0.348271 0.698076 -0.625618 -0.585228 0.698073 -0.412556 -0.585231 0.69807 -0.412557 -0.706277 0.69807 -0.11778 -0.706278 0.698068 -0.117779 -0.687436 0.69807 0.200326 -0.687436 0.698069 0.200327 -0.532439 0.69807 0.478755 -0.532438 0.698074 0.478752 -0.271986 0.698073 0.662358 -0.271986 0.698073 0.662358 0.042334 0.698074 0.714774 0.0423365 0.698069 0.714778 -0.348274 -0.698072 -0.62562 -0.348275 -0.698068 -0.625624 -0.492287 -0.706854 -0.507947 -0.637878 -0.625225 -0.449672 -0.597962 -0.700855 -0.388899 -0.673296 -0.70611 -0.219276 -0.809416 -0.571512 -0.134982 -0.708154 -0.703131 -0.0642168 -0.698939 -0.704879 0.12095 -0.800718 -0.551728 0.233336 -0.654491 -0.704886 0.273455 -0.532426 -0.698086 0.478747 -0.696478 -0.475046 0.537819 -0.450103 -0.706112 0.546638 -0.271987 -0.698072 0.662359 0.0423341 -0.698073 0.714774 0.0423346 -0.698075 0.714772 -0.142353 -0.706863 0.692879 -0.330082 -0.604032 0.72539 -0.486397 0 -0.873738 -0.518712 -0.00717211 -0.854919 -0.695951 0 -0.718089 -0.8383 0 -0.545209 -0.876636 -0.0119759 -0.481004 -0.950845 0 -0.309667 -0.995914 0 -0.0903113 -0.99966 -0.0143834 0.0217548 -0.985355 0 0.170513 -0.922701 0 0.385517 -0.854851 -0.0143837 0.518673 -0.791488 0 0.611185 -0.635649 0 0.771979 -0.481006 -0.0119765 0.876636 -0.414177 0 0.910196 -0.201248 0 0.97954 0.0217565 -0.00717241 0.999738 0.0591236 0 0.998251 -0.373098 0.694741 -0.614925 -0.373098 0.694741 -0.614925 -0.630576 0.694739 -0.345993 -0.63057 0.694745 -0.345992 -0.719085 0.694746 0.0156489 -0.719089 0.694742 0.0156509 -0.614924 0.694741 0.3731 -0.614919 0.694749 0.373092 -0.345989 0.69475 0.630567 -0.34599 0.694743 0.630574 0.0156488 0.694747 0.719084 0.015649 0.694746 0.719085 0.0423341 -0.698073 0.714774 0.0423346 -0.698075 0.714772 -0.271982 -0.698079 0.662354 -0.271987 -0.698072 0.662359 -0.532442 -0.698069 0.478754 -0.532431 -0.698081 0.478749 -0.687423 -0.698084 0.200322 -0.687425 -0.698081 0.200322 -0.706268 -0.698079 -0.117776 -0.706279 -0.698067 -0.117782 -0.585232 -0.698067 -0.41256 -0.585229 -0.698072 -0.412555 -0.348272 -0.698074 -0.625619 -0.348273 -0.698072 -0.625621 -0.486397 0 -0.873738 -0.486397 0 -0.873738 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.986379 0 -0.164487 -0.986379 0 -0.164487 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743603 0 0.668622 -0.743603 0 0.668622 -0.379852 0 0.925047 -0.379852 0 0.925047 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.348274 0.69807 -0.625622 -0.34827 0.698074 -0.62562 -0.585225 0.698077 -0.412555 -0.585231 0.69807 -0.412555 -0.706277 0.698069 -0.117778 -0.706274 0.698073 -0.117779 -0.687432 0.698074 0.200325 -0.687429 0.698078 0.200322 -0.532436 0.698078 0.478748 -0.53244 0.698067 0.478759 -0.271985 0.698069 0.662362 -0.271986 0.698076 0.662355 0.0423341 0.698073 0.714774 0.0423364 0.698069 0.714778 -0.348273 -0.698073 -0.62562 -0.348273 -0.698073 -0.62562 -0.492287 -0.706858 -0.507942 -0.637875 -0.62523 -0.449669 -0.597961 -0.700857 -0.388899 -0.673295 -0.70611 -0.219276 -0.809416 -0.571512 -0.134981 -0.708155 -0.703131 -0.0642169 -0.698939 -0.70488 0.120949 -0.800719 -0.551728 0.233337 -0.654494 -0.704883 0.273455 -0.53243 -0.698082 0.478749 -0.69648 -0.475041 0.53782 -0.4501 -0.706112 0.54664 -0.271987 -0.698072 0.662358 0.0423349 -0.698075 0.714772 0.0423347 -0.698074 0.714773 -0.142355 -0.706862 0.692879 -0.330084 -0.604031 0.725391 -0.486396 0 -0.873738 -0.518712 -0.00717224 -0.854919 -0.695954 0 -0.718086 -0.8383 0 -0.545209 -0.876636 -0.0119758 -0.481005 -0.950845 0 -0.309668 -0.995914 0 -0.0903114 -0.99966 -0.0143834 0.0217548 -0.985355 0 0.170513 -0.922701 0 0.385516 -0.854852 -0.0143838 0.518673 -0.791488 0 0.611185 -0.635645 0 0.771982 -0.481005 -0.0119762 0.876636 -0.414178 0 0.910196 -0.201251 0 0.97954 0.0217572 -0.00717251 0.999738 0.0591248 0 0.998251 -0.373097 0.694744 -0.614923 -0.373098 0.694742 -0.614924 -0.630575 0.69474 -0.345993 -0.630569 0.694746 -0.345992 -0.719085 0.694746 0.0156489 -0.719089 0.694742 0.0156509 -0.614924 0.694742 0.373099 -0.61492 0.694748 0.373094 -0.34599 0.694747 0.63057 -0.34599 0.694742 0.630574 0.0156494 0.694745 0.719086 0.0156495 0.694745 0.719086 -0.253647 0.705898 -0.66134 -0.506128 0.70705 -0.493878 -0.454642 0.705896 -0.543149 -0.454642 0.705896 -0.543149 -0.402483 0.707094 -0.5814 -0.392902 0.63182 -0.668155 -0.353573 0.70614 -0.613476 -0.253647 0.705897 -0.661341 -0.580337 0.623998 -0.523294 -0.674379 0.45959 -0.577919 -0.55646 0.704461 -0.440552 -0.656605 0.662731 -0.360079 -0.705349 0.577957 -0.410425 -0.760605 0.45891 -0.459219 -0.589743 0.706815 -0.390661 -0.572851 0.707109 -0.414534 -0.628215 0.70706 -0.324672 -0.658355 0.705898 -0.261299 -0.658357 0.705896 -0.2613 -0.724046 0.674968 -0.14204 -0.837122 0.516344 -0.180599 -0.688601 0.699964 -0.189419 -0.677129 0.707105 -0.203715 -0.600931 0.707007 0.372857 -0.638137 0.705896 0.307395 -0.638137 0.705896 0.307395 -0.680029 0.705896 0.198168 -0.680025 0.7059 0.198167 -0.703368 0.7059 0.083536 -0.703371 0.705898 0.0835361 -0.707465 0.706686 -0.00943082 -0.881727 0.469923 -0.0415913 -0.704052 0.706905 -0.0678002 -0.700693 0.707102 -0.0950536 -0.683326 0.557271 0.471715 -0.721351 0.469925 0.508746 -0.557409 0.706908 0.435403 -0.609054 0.516343 0.602032 -0.534392 0.674973 0.50876 -0.539936 0.707106 0.456586 -0.355454 0.70706 0.611326 -0.414921 0.705897 0.574065 -0.414921 0.705897 0.574065 -0.46169 0.707106 0.535579 -0.479044 0.699966 0.529684 -0.283576 0.706897 0.647983 -0.37561 0.514194 0.771052 -0.39484 0.45891 0.795929 -0.374447 0.577958 0.725089 -0.360378 0.662741 0.656432 -0.162097 0.706205 0.689201 -0.208372 0.623996 0.753133 -0.258347 0.459591 0.849725 -0.232682 0.704459 0.670519 -0.260512 0.707109 0.657366 -0.149433 0.707109 0.691134 -0.0916869 0.705899 0.702354 -0.0916875 0.705896 0.702356 -0.00410216 0.706804 0.707397 0.0315696 0.458844 0.887956 0.0543289 0.706807 0.705317 0.141335 0.705898 0.694069 0.141335 0.705898 0.694069 -0.264054 0.705397 -0.657792 -0.264054 0.705395 -0.657794 -0.38731 0.705395 -0.59364 -0.387307 0.705401 -0.593635 -0.495677 0.705402 -0.506668 -0.495681 0.705396 -0.506673 -0.585002 0.705397 -0.400234 -0.584998 0.705402 -0.400231 -0.651839 0.705402 -0.278413 -0.651838 0.705403 -0.278413 -0.693629 0.705403 -0.145896 -0.693638 0.705394 -0.145898 -0.708772 0.705394 -0.00777243 -0.708769 0.705398 -0.00777225 -0.696666 0.705398 0.130651 -0.696666 0.705398 0.130651 -0.657791 0.705398 0.264053 -0.657793 0.705396 0.264054 -0.593638 0.705397 0.387309 -0.593637 0.705399 0.387308 -0.506672 0.705398 0.49568 -0.506669 0.7054 0.495678 -0.400231 0.705401 0.584999 -0.400231 0.705402 0.584998 -0.278413 0.705402 0.651839 -0.278415 0.705396 0.651844 -0.145897 0.705396 0.693635 -0.145898 0.705395 0.693637 -0.00777243 0.705394 0.708772 -0.00777225 0.705398 0.708769 0.130651 0.705398 0.696666 0.130651 0.705397 0.696667 -0.486396 0 -0.873739 -0.518716 -0.00571997 -0.854927 -0.695955 0 -0.718085 -0.838299 0 -0.54521 -0.87666 -0.00955139 -0.481016 -0.950848 0 -0.309658 -0.995913 0 -0.0903227 -0.999698 -0.0114722 0.0217545 -0.985354 0 0.170524 -0.922703 0 0.385512 -0.854885 -0.0114716 0.518691 -0.791488 0 0.611184 -0.635638 0 0.771987 -0.481016 -0.00955093 0.87666 -0.414178 0 0.910196 -0.201252 0 0.97954 0.0217555 -0.00572001 0.999747 0.0591223 0 0.998251 -0.518723 0 -0.854943 -0.518723 0 -0.854943 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217558 -0.999763 0 0.0217558 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481037 0 0.8767 -0.481037 0 0.8767 0.0217558 0 0.999763 0.0217558 0 0.999763 -0.486396 0 -0.873739 -0.518718 -0.00572031 -0.854926 -0.69597 0 -0.718071 -0.838297 0 -0.545214 -0.876658 -0.00955158 -0.481019 -0.950848 0 -0.309658 -0.995913 0 -0.0903152 -0.999698 -0.0114714 0.0217545 -0.985355 0 0.170514 -0.922703 0 0.385512 -0.854885 -0.0114716 0.518691 -0.791488 0 0.611184 -0.635631 0 0.771993 -0.481016 -0.00955056 0.87666 -0.41418 0 0.910195 -0.201252 0 0.97954 0.0217554 -0.00572 0.999747 0.059122 0 0.998251 -0.486392 0 -0.873741 -0.518715 -0.00572041 -0.854928 -0.69597 0 -0.718071 -0.838303 0 -0.545204 -0.876661 -0.00955066 -0.481015 -0.950844 0 -0.309672 -0.995913 0 -0.0903148 -0.999698 -0.0114714 0.0217545 -0.985355 0 0.170515 -0.922703 0 0.385512 -0.854887 -0.0114714 0.518687 -0.791492 0 0.61118 -0.635628 0 0.771995 -0.481014 -0.00955065 0.876661 -0.414178 0 0.910196 -0.201258 0 0.979538 0.0217578 -0.00572005 0.999747 0.0591248 0 0.998251 -0.486398 0 -0.873737 -0.518716 -0.00571956 -0.854927 -0.69594 0 -0.7181 -0.838302 0 -0.545206 -0.87666 -0.00955071 -0.481016 -0.950844 0 -0.309672 -0.995913 0 -0.0903148 -0.999698 -0.0114714 0.0217545 -0.985355 0 0.170515 -0.922703 0 0.385512 -0.854883 -0.0114719 0.518694 -0.791485 0 0.611189 -0.635643 0 0.771983 -0.481017 -0.00955118 0.876659 -0.414178 0 0.910196 -0.201258 0 0.979538 0.0217578 -0.00572005 0.999747 0.0591248 0 0.998251 -0.486396 0 -0.873739 -0.486396 0 -0.873739 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.98638 0 -0.164485 -0.98638 0 -0.164485 -0.960066 0 0.279773 -0.960066 0 0.279773 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591271 0 0.99825 0.0591271 0 0.99825 -0.486392 0 -0.873741 -0.486392 0 -0.873741 -0.817329 0 -0.576171 -0.817329 0 -0.576171 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.379855 0 0.925046 -0.379855 0 0.925046 0.0591222 0 0.998251 0.0591222 0 0.998251 -0.486396 0 -0.873739 -0.486396 0 -0.873739 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.960065 0 0.279778 -0.960065 0 0.279778 -0.743603 0 0.668622 -0.743603 0 0.668622 -0.379854 0 0.925046 -0.379854 0 0.925046 0.0591274 0 0.99825 0.0591274 0 0.99825 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.960064 0 0.279782 -0.960064 0 0.279782 -0.743604 0 0.66862 -0.743604 0 0.66862 -0.379853 0 0.925047 -0.379853 0 0.925047 0.0591248 0 0.998251 0.0591248 0 0.998251 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.8767 0 -0.481037 -0.8767 0 -0.481037 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.854939 0 0.518728 -0.854939 0 0.518728 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217582 0 0.999763 0.0217582 0 0.999763 0.141334 -0.705903 0.694065 0.141336 -0.705894 0.694073 0.025167 -0.705894 0.70787 0.0251674 -0.705887 0.707877 -0.0916884 -0.705887 0.702365 -0.0916873 -0.705899 0.702353 -0.20604 -0.705899 0.677683 -0.206038 -0.705908 0.677674 -0.314769 -0.705908 0.634519 -0.314774 -0.705895 0.634531 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.503751 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658365 -0.705886 -0.261304 -0.658359 -0.705893 -0.261301 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.454647 -0.705888 -0.543155 -0.359046 -0.705888 -0.61058 -0.359041 -0.705897 -0.610573 -0.253647 -0.705897 -0.661341 -0.25365 -0.705889 -0.661348 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.199537 0 0.97989 0.199537 0 0.97989 0.0355307 0 0.999369 0.0355307 0 0.999369 -0.129444 0 0.991587 -0.129444 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817205 0 0.576348 -0.817205 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506896 0 -0.862007 -0.506896 0 -0.862007 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0.199537 0 0.97989 0.199537 0 0.97989 0.0355307 0 0.999369 0.0355307 0 0.999369 -0.129444 0 0.991587 -0.129444 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506895 0 -0.862007 -0.506895 0 -0.862007 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0.199537 0 0.97989 0.199537 0 0.97989 0.0355307 0 0.999369 0.0355307 0 0.999369 -0.129444 0 0.991587 -0.129444 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506896 0 -0.862007 -0.506896 0 -0.862007 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0.199537 0 0.97989 0.199537 0 0.97989 0.0355307 0 0.999369 0.0355307 0 0.999369 -0.129444 0 0.991587 -0.129444 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506896 0 -0.862007 -0.506896 0 -0.862007 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0.199537 0 0.97989 0.199537 0 0.97989 0.0355307 0 0.999369 0.0355307 0 0.999369 -0.129444 0 0.991587 -0.129444 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506896 0 -0.862007 -0.506896 0 -0.862007 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0.199537 0 0.97989 0.199537 0 0.97989 0.0355307 0 0.999369 0.0355307 0 0.999369 -0.129444 0 0.991587 -0.129444 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506896 0 -0.862007 -0.506896 0 -0.862007 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0.199537 0 0.97989 0.199537 0 0.97989 0.0355307 0 0.999369 0.0355307 0 0.999369 -0.129444 0 0.991587 -0.129444 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506896 0 -0.862007 -0.506896 0 -0.862007 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0.199537 0 0.97989 0.199537 0 0.97989 0.0355307 0 0.999369 0.0355307 0 0.999369 -0.129444 0 0.991587 -0.129444 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506896 0 -0.862007 -0.506896 0 -0.862007 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0.199537 0 0.97989 0.199537 0 0.97989 0.0355307 0 0.999369 0.0355307 0 0.999369 -0.129444 0 0.991587 -0.129444 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506896 0 -0.862007 -0.506896 0 -0.862007 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0.199537 0 0.97989 0.199537 0 0.97989 0.0355307 0 0.999369 0.0355307 0 0.999369 -0.129444 0 0.991587 -0.129444 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506896 0 -0.862008 -0.506896 0 -0.862008 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0.994652 0 0.103279 0.994652 0 0.103279 0.959498 0 0.281717 0.959498 0 0.281717 0.892607 0 0.450836 0.892607 0 0.450836 0.796192 0 0.605044 0.796192 0 0.605044 0.673443 0 0.739239 0.673443 0 0.739239 0.528419 0 0.848984 0.528419 0 0.848984 0.365917 0 0.930647 0.365917 0 0.930647 -0.993905 0 -0.110244 -0.993905 0 -0.110244 -0.953366 0 -0.301816 -0.953366 0 -0.301816 -0.876273 0 -0.481815 -0.876273 0 -0.481815 -0.765581 0 -0.64334 -0.765581 0 -0.64334 -0.625534 0 -0.780197 -0.625534 0 -0.780197 -0.461502 0 -0.887139 -0.461502 0 -0.887139 -0.279774 0 -0.960066 -0.279774 0 -0.960066 -0.0873196 0 -0.99618 -0.0873196 0 -0.99618 0.108484 0 -0.994098 0.108484 0 -0.994098 0.300127 0 -0.953899 0.300127 0 -0.953899 0.480262 0 -0.877125 0.480262 0 -0.877125 0.641984 0 -0.766718 0.641984 0 -0.766718 0.779088 0 -0.626914 0.779088 0 -0.626914 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0.279774 0 0.960066 0.279774 0 0.960066 0 -1 0 0 -1 0 -0.279774 0 -0.960066 -0.279774 0 -0.960066 -0.279774 0 -0.960066 -0.279774 0 -0.960066 0 -1 0 0 -1 0 0.279774 0 0.960066 0.279774 0 0.960066 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.518723 0 -0.854943 -0.518723 0 -0.854943 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.999763 0 0.021757 -0.999763 0 0.021757 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373092 0.694749 -0.614919 -0.373094 0.694747 -0.61492 -0.63057 0.694746 -0.345991 -0.630573 0.694743 -0.345991 -0.719084 0.694747 0.0156488 -0.719089 0.694742 0.0156509 -0.614925 0.694741 0.373098 -0.614922 0.694745 0.373094 -0.345989 0.694747 0.630569 -0.345989 0.694747 0.630569 0.0156489 0.694746 0.719085 0.0156509 0.694742 0.719089 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373096 0.694745 -0.614922 -0.373096 0.694746 -0.614921 -0.630569 0.694747 -0.345989 -0.630569 0.694747 -0.345989 -0.719085 0.694746 0.0156489 -0.719089 0.694742 0.0156509 -0.614924 0.694741 0.3731 -0.61492 0.694747 0.373094 -0.345991 0.694746 0.63057 -0.345991 0.694743 0.630573 0.015649 0.694742 0.719089 0.015649 0.694742 0.719089 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.85494 0 0.518726 -0.85494 0 0.518726 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373098 0.694741 -0.614925 -0.373094 0.694745 -0.614922 -0.630569 0.694747 -0.345989 -0.630572 0.694745 -0.345989 -0.719085 0.694746 0.0156489 -0.719089 0.694742 0.0156509 -0.614924 0.694741 0.373099 -0.614921 0.694747 0.373094 -0.34599 0.694746 0.630571 -0.34599 0.694747 0.630569 0.0156489 0.694746 0.719085 0.0156499 0.694744 0.719087 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.85494 0 0.518726 -0.85494 0 0.518726 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217579 0 0.999763 0.0217579 0 0.999763 -0.373097 0.694744 -0.614922 -0.373095 0.694746 -0.614921 -0.630569 0.694748 -0.345989 -0.63057 0.694746 -0.345989 -0.719085 0.694746 0.0156489 -0.719089 0.694742 0.0156509 -0.614924 0.694742 0.373099 -0.61492 0.694748 0.373094 -0.34599 0.694747 0.63057 -0.34599 0.694746 0.63057 0.0156495 0.694745 0.719086 0.0156493 0.694745 0.719086 0.0156489 -0.694746 0.719085 0.0156507 -0.694751 0.719081 -0.345987 -0.694752 0.630566 -0.345987 -0.694752 0.630566 -0.614918 -0.69475 0.373094 -0.614922 -0.694746 0.373094 -0.719085 -0.694746 0.0156488 -0.71908 -0.694751 0.0156507 -0.630569 -0.694747 -0.34599 -0.630567 -0.69475 -0.345988 -0.373091 -0.694751 -0.614917 -0.373091 -0.694754 -0.614915 0.0156489 -0.694746 0.719085 0.0156489 -0.694746 0.719085 -0.34599 -0.694748 0.630569 -0.345988 -0.69475 0.630567 -0.614915 -0.694752 0.373094 -0.614922 -0.694746 0.373095 -0.719085 -0.694746 0.0156489 -0.719081 -0.694751 0.0156507 -0.630566 -0.694752 -0.345987 -0.630566 -0.694752 -0.345987 -0.373094 -0.69475 -0.614918 -0.373094 -0.69475 -0.614918 0.0156489 -0.694749 0.719082 0.0156497 -0.694751 0.71908 -0.345987 -0.694752 0.630566 -0.345989 -0.69475 0.630567 -0.614915 -0.694752 0.373094 -0.614922 -0.694746 0.373095 -0.719085 -0.694746 0.0156489 -0.71908 -0.694751 0.0156507 -0.630567 -0.69475 -0.345988 -0.630566 -0.694752 -0.345986 -0.373094 -0.69475 -0.614918 -0.373094 -0.694746 -0.614922 0.0156494 -0.69475 0.719081 0.0156492 -0.694749 0.719082 -0.345988 -0.69475 0.630566 -0.345988 -0.694751 0.630566 -0.614915 -0.694752 0.373093 -0.614921 -0.694747 0.373094 -0.719085 -0.694746 0.0156489 -0.71908 -0.694751 0.0156507 -0.630566 -0.694751 -0.345988 -0.630565 -0.694752 -0.345986 -0.373093 -0.694751 -0.614917 -0.373093 -0.694749 -0.614919 0.0591222 0 0.998251 0.0591222 0 0.998251 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817328 0 -0.576173 -0.817328 0 -0.576173 -0.486392 0 -0.873741 -0.486392 0 -0.873741 0.0217559 0 0.999763 0.0217559 0 0.999763 -0.481037 0 0.8767 -0.481037 0 0.8767 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.8767 0 -0.481037 -0.8767 0 -0.481037 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0217582 0 0.999763 0.0217582 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854939 0 0.518728 -0.854939 0 0.518728 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.8767 0 -0.481037 -0.8767 0 -0.481037 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0217582 0 0.999763 0.0217582 0 0.999763 -0.481035 0 0.876701 -0.481035 0 0.876701 -0.854943 0 0.518722 -0.854943 0 0.518722 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.876701 0 -0.481037 -0.876701 0 -0.481037 -0.518723 0 -0.854942 -0.518723 0 -0.854942 0.0217558 0 0.999763 0.0217558 0 0.999763 -0.481037 0 0.8767 -0.481037 0 0.8767 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.876698 0 -0.481041 -0.876698 0 -0.481041 -0.518727 0 -0.85494 -0.518727 0 -0.85494 0.0217602 0 0.999763 0.0217602 0 0.999763 -0.481041 0 0.876698 -0.481041 0 0.876698 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.876698 0 -0.481041 -0.876698 0 -0.481041 -0.518727 0 -0.85494 -0.518727 0 -0.85494 0.0217559 0 0.999763 0.0217559 0 0.999763 -0.481037 0 0.876701 -0.481037 0 0.876701 -0.854942 0 0.518723 -0.854942 0 0.518723 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518723 0 -0.854943 -0.518723 0 -0.854943 0.0217602 0 0.999763 0.0217602 0 0.999763 -0.481041 0 0.876698 -0.481041 0 0.876698 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.8767 0 -0.481037 -0.8767 0 -0.481037 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0591248 0 0.998251 0.0591248 0 0.998251 -0.379853 0 0.925047 -0.379853 0 0.925047 -0.743604 0 0.66862 -0.743604 0 0.66862 -0.960064 0 0.279782 -0.960064 0 0.279782 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0.0217582 0 0.999763 0.0217582 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854939 0 0.518728 -0.854939 0 0.518728 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.8767 0 -0.481037 -0.8767 0 -0.481037 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.481035 0 0.876702 -0.481035 0 0.876702 -0.854943 0 0.518722 -0.854943 0 0.518722 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.518727 0 -0.85494 -0.518727 0 -0.85494 0.0156487 -0.694755 0.719076 0.015647 -0.694751 0.71908 -0.345984 -0.694752 0.630567 -0.345991 -0.694744 0.630572 -0.614923 -0.694745 0.373094 -0.614922 -0.694746 0.373094 -0.719085 -0.694746 0.0156489 -0.71908 -0.694751 0.0156507 -0.630565 -0.694752 -0.345988 -0.630566 -0.69475 -0.345989 -0.373094 -0.694752 -0.614915 -0.373095 -0.694746 -0.614922 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.379854 0 0.925046 -0.379854 0 0.925046 -0.743599 0 0.668625 -0.743599 0 0.668625 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.986378 0 -0.164493 -0.986378 0 -0.164493 -0.81733 0 -0.57617 -0.81733 0 -0.57617 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0.0423338 -0.698078 0.71477 0.042334 -0.698078 0.714769 -0.271984 -0.698077 0.662354 -0.271984 -0.698077 0.662354 -0.532433 -0.698078 0.47875 -0.532437 -0.698075 0.478751 -0.687432 -0.698074 0.200326 -0.687428 -0.698077 0.200327 -0.706269 -0.698078 -0.117781 -0.706264 -0.698083 -0.117777 -0.585222 -0.698082 -0.412548 -0.585227 -0.698072 -0.412558 -0.348271 -0.698072 -0.625621 -0.348271 -0.698073 -0.625621 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0217579 0 0.999763 0.0217579 0 0.999763 -0.481037 0 0.8767 -0.481037 0 0.8767 -0.854943 0 0.518722 -0.854943 0 0.518722 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876701 0 -0.481035 -0.876701 0 -0.481035 -0.518722 0 -0.854943 -0.518722 0 -0.854943 0.0156494 -0.69475 0.719081 0.0156492 -0.694749 0.719082 -0.345987 -0.69475 0.630567 -0.34599 -0.694747 0.63057 -0.614924 -0.694744 0.373095 -0.614913 -0.694754 0.373093 -0.719076 -0.694755 0.0156487 -0.71908 -0.694751 0.015647 -0.630568 -0.694751 -0.345985 -0.630572 -0.694744 -0.34599 -0.373094 -0.694746 -0.614922 -0.373093 -0.694753 -0.614915 0.0156531 -0.694747 0.719084 0.015653 -0.694747 0.719084 -0.345988 -0.694748 0.63057 -0.345992 -0.694746 0.63057 -0.614923 -0.694746 0.373092 -0.614919 -0.694748 0.373095 -0.719083 -0.694748 0.0156488 -0.719084 -0.694747 0.0156478 -0.630569 -0.694747 -0.34599 -0.630569 -0.694747 -0.34599 -0.373096 -0.694747 -0.614919 -0.373095 -0.694746 -0.614921 -0.518727 0 -0.85494 -0.518727 0 -0.85494 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.999763 0 0.021757 -0.999763 0 0.021757 -0.854944 0 0.51872 -0.854944 0 0.51872 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217629 0 0.999763 0.0217629 0 0.999763 -0.373098 0.694744 -0.614921 -0.373096 0.694745 -0.614921 -0.63057 0.694746 -0.345991 -0.63057 0.694746 -0.345991 -0.719085 0.694745 0.0156489 -0.719085 0.694746 0.0156478 -0.614922 0.694747 0.373092 -0.614922 0.694744 0.373096 -0.34599 0.694744 0.630573 -0.345992 0.694745 0.63057 0.0156531 0.694745 0.719086 0.0156531 0.694745 0.719086 0.042334 -0.698075 0.714772 0.0423357 -0.698076 0.714771 -0.271985 -0.698076 0.662355 -0.271985 -0.698076 0.662355 -0.532432 -0.698077 0.478754 -0.532437 -0.698075 0.478752 -0.687434 -0.698073 0.200322 -0.687432 -0.698074 0.200324 -0.706272 -0.698074 -0.117781 -0.70627 -0.698077 -0.117774 -0.585225 -0.698077 -0.412552 -0.585225 -0.698076 -0.412556 -0.348272 -0.698076 -0.625617 -0.348271 -0.698075 -0.625619 -0.486397 0 -0.873738 -0.486397 0 -0.873738 -0.817329 0 -0.576172 -0.817329 0 -0.576172 -0.986378 0 -0.164492 -0.986378 0 -0.164492 -0.960067 0 0.279769 -0.960067 0 0.279769 -0.743596 0 0.668629 -0.743596 0 0.668629 -0.379854 0 0.925046 -0.379854 0 0.925046 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.348273 0.698073 -0.62562 -0.348271 0.698074 -0.62562 -0.585229 0.698074 -0.412554 -0.585225 0.698075 -0.412556 -0.70627 0.698076 -0.11778 -0.706274 0.698073 -0.117774 -0.687434 0.698072 0.200322 -0.687434 0.698072 0.200325 -0.532435 0.698072 0.478757 -0.532437 0.698075 0.478752 -0.271986 0.698074 0.662357 -0.271986 0.698074 0.662357 0.042334 0.698074 0.714773 0.0423359 0.698073 0.714774 0.0156493 -0.694748 0.719083 0.0156492 -0.694748 0.719083 -0.345989 -0.694748 0.630569 -0.34599 -0.694748 0.630569 -0.614919 -0.694747 0.373096 -0.614921 -0.694746 0.373095 -0.719084 -0.694747 0.015653 -0.719084 -0.694747 0.015653 -0.630569 -0.694747 -0.34599 -0.630569 -0.694746 -0.345992 -0.373094 -0.694746 -0.614922 -0.373095 -0.694748 -0.61492 -0.518722 0 -0.854943 -0.518722 0 -0.854943 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217628 -0.999763 0 0.0217628 -0.85494 0 0.518726 -0.85494 0 0.518726 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217577 0 0.999763 0.0217577 0 0.999763 -0.373094 0.694746 -0.614922 -0.373096 0.694745 -0.614922 -0.630572 0.694744 -0.345991 -0.63057 0.694745 -0.345992 -0.719086 0.694745 0.0156531 -0.719086 0.694745 0.0156531 -0.614922 0.694744 0.373097 -0.614922 0.694745 0.373096 -0.34599 0.694746 0.63057 -0.345991 0.694746 0.63057 0.0156494 0.694746 0.719085 0.0156493 0.694746 0.719085 -0.486395 0 -0.873739 -0.518722 -0.0016186 -0.854942 -0.695948 0 -0.718092 -0.8383 0 -0.545209 -0.876697 -0.002703 -0.481036 -0.950847 0 -0.309661 -0.995913 0 -0.0903169 -0.999758 -0.00324657 0.0217577 -0.985354 0 0.170523 -0.922704 0 0.385509 -0.854937 -0.00324655 0.518722 -0.791487 0 0.611186 -0.635644 0 0.771982 -0.481038 -0.002703 0.876696 -0.414177 0 0.910196 -0.201253 0 0.979539 0.0217571 -0.00161871 0.999762 0.0591236 0 0.998251 -0.373095 0.694742 -0.614925 -0.373098 0.69474 -0.614927 -0.630575 0.694742 -0.345991 -0.63057 0.694746 -0.34599 -0.719086 0.694745 0.0156495 -0.719086 0.694745 0.0156494 -0.614922 0.694744 0.373097 -0.614921 0.694747 0.373094 -0.345989 0.694748 0.630569 -0.345989 0.694746 0.63057 0.0156489 0.694746 0.719085 0.015647 0.694751 0.719081 -0.518723 0 -0.854943 -0.518723 0 -0.854943 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.0217586 -0.999763 0 0.0217586 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373096 0.694741 -0.614926 -0.373097 0.69474 -0.614926 -0.630574 0.694743 -0.34599 -0.630571 0.694745 -0.34599 -0.719087 0.694744 0.01565 -0.719085 0.694746 0.015649 -0.614922 0.694745 0.373096 -0.61492 0.694747 0.373094 -0.345989 0.694749 0.630568 -0.345989 0.694745 0.630571 0.0156489 0.694746 0.719085 0.0156471 0.694751 0.719081 -0.518722 0 -0.854943 -0.518722 0 -0.854943 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.02176 -0.999763 0 0.02176 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373094 0.694744 -0.614924 -0.373098 0.694739 -0.614927 -0.630575 0.694741 -0.345991 -0.630573 0.694743 -0.345991 -0.719089 0.694741 0.0156511 -0.719085 0.694746 0.015649 -0.614922 0.694745 0.373096 -0.614919 0.694749 0.373092 -0.345989 0.69475 0.630567 -0.345989 0.694745 0.630571 0.0156489 0.694746 0.719085 0.015647 0.694751 0.71908 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.854943 0 0.518723 -0.854943 0 0.518723 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373096 0.694745 -0.614922 -0.373096 0.694746 -0.614921 -0.630569 0.694747 -0.345989 -0.630569 0.694747 -0.345989 -0.719085 0.694746 0.0156489 -0.719081 0.694751 0.015647 -0.614919 0.694749 0.373092 -0.614925 0.69474 0.373101 -0.345991 0.694741 0.630575 -0.345991 0.694743 0.630573 0.015649 0.694742 0.719089 0.0156491 0.694742 0.719089 -0.348271 -0.698074 -0.62562 -0.348271 -0.698074 -0.625619 -0.492281 -0.706861 -0.507944 -0.61997 -0.651632 -0.43705 -0.597955 -0.700865 -0.388895 -0.673289 -0.706119 -0.219269 -0.774256 -0.619562 -0.129115 -0.708157 -0.703128 -0.064221 -0.698943 -0.704875 0.120958 -0.76216 -0.608098 0.222102 -0.654501 -0.704877 0.273453 -0.532434 -0.698078 0.47875 -0.654979 -0.561423 0.505774 -0.450095 -0.706119 0.546635 -0.271984 -0.698077 0.662354 0.0423335 -0.698082 0.714765 0.0423317 -0.698078 0.714769 -0.142356 -0.706863 0.692877 -0.31913 -0.63742 0.701322 0.0156487 -0.694755 0.719076 0.015647 -0.694751 0.71908 -0.345989 -0.69475 0.630567 -0.345986 -0.694753 0.630565 -0.614916 -0.694752 0.373093 -0.614918 -0.69475 0.373093 -0.71908 -0.694751 0.0156499 -0.719082 -0.694749 0.0156489 -0.630568 -0.69475 -0.345987 -0.630569 -0.694748 -0.345989 -0.373095 -0.694745 -0.614923 -0.373095 -0.694746 -0.614922 0.0156487 -0.694755 0.719076 0.015647 -0.694751 0.71908 -0.345989 -0.694749 0.630567 -0.345985 -0.694754 0.630564 -0.614914 -0.694754 0.373092 -0.614919 -0.69475 0.373092 -0.71908 -0.694751 0.0156509 -0.719085 -0.694746 0.015649 -0.630569 -0.694748 -0.345988 -0.630571 -0.694746 -0.34599 -0.373095 -0.694743 -0.614925 -0.373094 -0.694748 -0.61492 0.0156489 -0.694746 0.719085 0.015649 -0.694746 0.719085 -0.345988 -0.694748 0.630569 -0.34599 -0.694746 0.630571 -0.614924 -0.694744 0.373095 -0.614914 -0.694753 0.373094 -0.719076 -0.694755 0.0156487 -0.71908 -0.694751 0.015647 -0.630566 -0.694752 -0.345987 -0.630566 -0.694752 -0.345987 -0.373094 -0.69475 -0.614918 -0.373094 -0.69475 -0.614918 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0217571 0 0.999763 0.0591232 0.00353187 0.998244 -0.414175 -0.00303662 0.910192 -0.379854 0 0.925047 -0.635644 0 0.771982 -0.743595 -0.00406485 0.668618 -0.791487 0 0.611186 -0.922704 0 0.38551 -0.960056 -0.0045752 0.279771 -0.985354 0 0.170521 -0.995913 0 -0.0903169 -0.986371 -0.00406494 -0.164488 -0.950845 0 -0.309667 -0.8383 0 -0.54521 -0.817326 -0.00253692 -0.57617 -0.51872 0.00303681 -0.854939 -0.48639 0 -0.873742 -0.37309 -0.694755 -0.614914 -0.373091 -0.694752 -0.614917 -0.630567 -0.694751 -0.345986 -0.711987 -0.527874 -0.463059 -0.673289 -0.706117 -0.219273 -0.719082 -0.694749 0.0156492 -0.908907 -0.408772 -0.0824265 -0.698942 -0.704876 0.120956 -0.654503 -0.704875 0.273454 -0.704406 -0.566703 0.427388 0.0156489 -0.694746 0.719085 0.0156507 -0.694751 0.71908 -0.295429 -0.700866 0.649237 -0.387718 -0.591912 0.706622 -0.450094 -0.706122 0.546633 -0.562796 -0.703129 0.434591 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.379853 0 0.925047 -0.379853 0 0.925047 -0.743601 0 0.668624 -0.743601 0 0.668624 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486395 0 -0.873739 -0.486395 0 -0.873739 0.0423341 -0.698073 0.714774 0.042336 -0.698077 0.71477 -0.271983 -0.698079 0.662353 -0.271985 -0.698076 0.662355 -0.532437 -0.698075 0.478751 -0.532433 -0.698078 0.47875 -0.687428 -0.698078 0.200324 -0.687428 -0.698078 0.200324 -0.70627 -0.698077 -0.117779 -0.706268 -0.698079 -0.117778 -0.585224 -0.698078 -0.412553 -0.585222 -0.698081 -0.41255 -0.348267 -0.698083 -0.625612 -0.348267 -0.698081 -0.625614 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.743601 0 0.668623 -0.743601 0 0.668623 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164487 -0.986379 0 -0.164487 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.486397 0 -0.873738 -0.486397 0 -0.873738 0.0423341 -0.698073 0.714774 0.0423359 -0.698077 0.71477 -0.271983 -0.69808 0.662351 -0.271986 -0.698078 0.662353 -0.532435 -0.698078 0.478749 -0.532431 -0.698082 0.478748 -0.687424 -0.698082 0.200323 -0.687428 -0.698079 0.200322 -0.70627 -0.698077 -0.117776 -0.706272 -0.698074 -0.117778 -0.585226 -0.698074 -0.412556 -0.585223 -0.698082 -0.412549 -0.348269 -0.698081 -0.625613 -0.348269 -0.698077 -0.625618 0.0156448 -0.694746 0.719085 0.0156478 -0.694747 0.719084 -0.34599 -0.694747 0.630569 -0.345986 -0.694749 0.630569 -0.614917 -0.694749 0.373096 -0.614922 -0.694746 0.373093 -0.719083 -0.694748 0.0156491 -0.719083 -0.694748 0.0156494 -0.630569 -0.694748 -0.345989 -0.630569 -0.694749 -0.345987 -0.373094 -0.694751 -0.614916 -0.373093 -0.69475 -0.614918 -0.518726 0 -0.85494 -0.518726 0 -0.85494 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.999763 0 0.0217574 -0.999763 0 0.0217574 -0.854939 0 0.518728 -0.854939 0 0.518728 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217513 0 0.999763 0.0217513 0 0.999763 -0.373096 0.694748 -0.614919 -0.373094 0.694749 -0.614919 -0.630569 0.694748 -0.34599 -0.630571 0.694746 -0.345988 -0.719085 0.694746 0.0156491 -0.719085 0.694746 0.0156494 -0.614922 0.694744 0.373099 -0.614922 0.694746 0.373093 -0.345989 0.694747 0.630569 -0.345988 0.694746 0.630572 0.0156448 0.694746 0.719085 0.0156479 0.694744 0.719087 0.0156448 -0.694746 0.719085 0.0156478 -0.694747 0.719084 -0.345988 -0.694748 0.63057 -0.345986 -0.694749 0.63057 -0.614919 -0.694748 0.373095 -0.614919 -0.694748 0.373095 -0.719083 -0.694748 0.0156488 -0.719084 -0.694747 0.0156478 -0.630569 -0.694747 -0.34599 -0.630569 -0.694747 -0.34599 -0.373096 -0.694747 -0.614919 -0.373095 -0.694746 -0.614921 -0.486394 0 -0.87374 -0.518726 0.00192619 -0.854938 -0.695982 0 -0.71806 -0.838298 0 -0.545213 -0.876694 0.00321607 -0.481038 -0.950846 0 -0.309664 -0.995913 0 -0.0903212 -0.999756 0.00386293 0.0217569 -0.985353 0 0.170525 -0.922706 0 0.385505 -0.854935 0.0038629 0.518722 -0.791484 0 0.61119 -0.635639 0 0.771987 -0.481035 0.00321601 0.876695 0.0591169 0 0.998251 0.0217513 0.00192591 0.999762 -0.201256 0 0.979539 -0.414177 0 0.910197 0.0423389 0.698072 0.714775 0.0423291 0.698077 0.714771 -0.142359 0.706862 0.692879 -0.275156 0.68942 0.670067 -0.295431 0.700861 0.649241 -0.450094 0.706116 0.546641 -0.542401 0.684058 0.487715 -0.562799 0.703124 0.434597 -0.654507 0.704872 0.273452 -0.701929 0.682243 0.204549 -0.698945 0.704872 0.120959 -0.706275 0.698072 -0.117777 -0.740203 0.669024 -0.0671304 -0.67329 0.706116 -0.219272 -0.585228 0.698073 -0.412555 -0.348272 0.698072 -0.625622 -0.348271 0.698072 -0.625622 -0.492306 0.706858 -0.507924 -0.611358 0.68421 -0.397615 -0.348268 -0.698075 -0.62562 -0.348268 -0.698075 -0.62562 -0.492289 -0.706861 -0.507935 -0.592043 -0.68942 -0.417356 -0.597957 -0.700862 -0.388896 -0.67329 -0.706117 -0.219272 -0.719491 -0.684059 -0.119984 -0.70816 -0.703125 -0.064225 -0.698943 -0.704873 0.120968 -0.701926 -0.682246 0.204548 -0.654504 -0.704876 0.273451 -0.532434 -0.698076 0.478753 -0.588272 -0.66902 0.454255 -0.450093 -0.706116 0.54664 -0.271985 -0.698074 0.662357 0.042334 -0.698075 0.714772 0.0423328 -0.698074 0.714773 -0.142365 -0.70686 0.692879 -0.30205 -0.684212 0.663792 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.201264 0 0.979537 -0.201264 0 0.979537 -0.414174 0 0.910198 -0.414174 0 0.910198 -0.635639 0 0.771987 -0.635639 0 0.771987 -0.791493 0 0.611179 -0.791493 0 0.611179 -0.922706 0 0.385505 -0.922706 0 0.385505 -0.985351 0 0.170538 -0.985351 0 0.170538 -0.995913 0 -0.0903221 -0.995913 0 -0.0903221 -0.950846 0 -0.309664 -0.950846 0 -0.309664 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.695961 0 -0.71808 -0.695961 0 -0.71808 -0.486391 0 -0.873741 -0.486391 0 -0.873741 0.0423329 0.698073 0.714774 0.0423341 0.698073 0.714775 -0.142365 0.706858 0.692881 -0.275153 0.689418 0.67007 -0.295429 0.70086 0.649243 -0.450094 0.706115 0.546642 -0.542402 0.684056 0.487716 -0.562803 0.703126 0.434588 -0.687431 0.698075 0.200325 -0.699291 0.652405 0.292163 -0.698944 0.704871 0.120969 -0.706274 0.698072 -0.11778 -0.740204 0.669023 -0.0671312 -0.673292 0.706115 -0.219272 -0.58523 0.698073 -0.412553 -0.348269 0.698074 -0.625621 -0.348269 0.698074 -0.625621 -0.492291 0.70686 -0.507937 -0.61136 0.68421 -0.397613 -0.486395 0 -0.873739 -0.486395 0 -0.873739 -0.695969 0 -0.718072 -0.695969 0 -0.718072 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.950845 0 -0.309667 -0.950845 0 -0.309667 -0.995913 0 -0.0903169 -0.995913 0 -0.0903169 -0.985354 0 0.170521 -0.985354 0 0.170521 -0.922704 0 0.385509 -0.922704 0 0.385509 -0.791487 0 0.611186 -0.791487 0 0.611186 -0.635644 0 0.771982 -0.635644 0 0.771982 -0.414177 0 0.910196 -0.414177 0 0.910196 -0.201253 0 0.979539 -0.201253 0 0.979539 0.0591236 0 0.998251 0.0591236 0 0.998251 0.0156509 0.694742 0.719089 0.0462966 0.621962 0.781678 -0.142357 0.706859 0.692881 -0.345992 0.694746 0.630569 -0.351774 0.52786 0.773059 -0.450101 0.706111 0.546642 -0.614923 0.694742 0.373098 -0.722342 0.408767 0.557792 -0.654507 0.704871 0.273455 -0.698946 0.704871 0.120957 -0.823732 0.566696 0.0179268 -0.708162 0.703123 -0.0642214 -0.67329 0.706115 -0.219274 -0.706623 0.591911 -0.38772 -0.348274 0.698069 -0.625624 -0.399688 0.637413 -0.658752 -0.492296 0.70686 -0.507931 -0.597957 0.700862 -0.388896 -0.486394 0 -0.87374 -0.518725 0.00161884 -0.85494 -0.817328 -0.00135235 -0.576171 -0.8383 0 -0.545209 -0.950844 0 -0.30967 -0.986376 -0.00216697 -0.16449 -0.995913 0 -0.0903162 -0.985353 0 0.170525 -0.960063 -0.00243884 0.279773 -0.922706 0 0.385505 -0.791485 0 0.611188 -0.743599 -0.00216679 0.668622 -0.635649 0 0.771979 -0.379853 0 0.925047 -0.414176 -0.00161876 0.910195 0.0591235 0.00188276 0.998249 0.0217571 0 0.999763 -0.348272 0.698071 -0.625623 -0.348274 0.698068 -0.625624 -0.585234 0.698067 -0.412557 -0.585227 0.698074 -0.412556 -0.706272 0.698074 -0.117779 -0.706274 0.698073 -0.117779 -0.687432 0.698074 0.200325 -0.687432 0.698073 0.200326 -0.532437 0.698074 0.478752 -0.532441 0.698065 0.478761 -0.271989 0.698063 0.662367 -0.27199 0.698072 0.662357 0.042334 0.698074 0.714774 0.0423366 0.698069 0.714778 -0.486395 0 -0.873739 -0.518726 -0.00161883 -0.854939 -0.695972 0 -0.718069 -0.8383 0 -0.545209 -0.876695 -0.00270286 -0.481038 -0.950844 0 -0.30967 -0.995913 0 -0.0903162 -0.999758 -0.00324653 0.0217569 -0.985354 0 0.170519 -0.922703 0 0.385511 -0.854937 -0.00324651 0.518722 -0.791488 0 0.611185 -0.635644 0 0.771983 -0.481037 -0.002703 0.876696 -0.414177 0 0.910196 -0.201252 0 0.97954 0.021757 -0.00161871 0.999762 0.0591236 0 0.998251 -0.3731 0.694741 -0.614924 -0.373094 0.694747 -0.61492 -0.63057 0.694746 -0.345991 -0.630569 0.694747 -0.345991 -0.719085 0.694746 0.0156488 -0.719089 0.694742 0.0156508 -0.614925 0.694741 0.373098 -0.614925 0.694741 0.373098 -0.345993 0.694739 0.630576 -0.345992 0.694747 0.630568 0.0156489 0.694746 0.719085 0.0156509 0.694742 0.719089 -0.518722 0 -0.854943 -0.518722 0 -0.854943 -0.876702 0 -0.481035 -0.876702 0 -0.481035 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.854943 0 0.518723 -0.854943 0 0.518723 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373096 0.694741 -0.614926 -0.373097 0.694741 -0.614926 -0.630578 0.694739 -0.34599 -0.630572 0.694745 -0.345989 -0.719085 0.694746 0.0156489 -0.719081 0.694751 0.0156471 -0.614919 0.694749 0.373092 -0.614924 0.694742 0.373099 -0.345989 0.694745 0.630572 -0.345989 0.694747 0.630569 0.0156489 0.694746 0.719085 0.015649 0.694746 0.719085 -0.373094 -0.694747 -0.614921 -0.38087 -0.621963 -0.684178 -0.492293 -0.706865 -0.507927 -0.630566 -0.694751 -0.345988 -0.711982 -0.527884 -0.463055 -0.673286 -0.70612 -0.219273 -0.719081 -0.69475 0.0156493 -0.908907 -0.408772 -0.0824265 -0.698942 -0.704876 0.120956 -0.654503 -0.704875 0.273453 -0.704407 -0.566699 0.427391 -0.5628 -0.703124 0.434594 -0.450098 -0.706115 0.546638 -0.387724 -0.591905 0.706625 0.042334 -0.698073 0.714774 0.0167662 -0.63742 0.770334 -0.142356 -0.706863 0.692877 -0.29543 -0.700866 0.649237 -0.373094 -0.694748 -0.61492 -0.373093 -0.694752 -0.614916 -0.630567 -0.69475 -0.345988 -0.711983 -0.527882 -0.463056 -0.673289 -0.706116 -0.219276 -0.719085 -0.694746 0.0156489 -0.908908 -0.408769 -0.082426 -0.69894 -0.704877 0.120958 -0.654503 -0.704877 0.273451 -0.704408 -0.566698 0.427391 0.0156489 -0.694746 0.719085 0.0156507 -0.694751 0.71908 -0.29543 -0.700865 0.649238 -0.387724 -0.591903 0.706626 -0.4501 -0.706117 0.546634 -0.562797 -0.703127 0.434594 -0.348271 -0.698073 -0.625621 -0.348271 -0.698075 -0.625619 -0.492297 -0.706861 -0.507928 -0.619967 -0.651639 -0.437044 -0.597953 -0.700867 -0.388893 -0.673284 -0.706121 -0.219275 -0.774257 -0.619561 -0.129116 -0.708157 -0.703128 -0.0642205 -0.69894 -0.704878 0.120954 -0.76216 -0.608097 0.222102 -0.6545 -0.704878 0.273454 -0.532432 -0.698078 0.478751 -0.654984 -0.561414 0.505777 -0.450098 -0.706113 0.54664 -0.271991 -0.69807 0.662359 0.0423341 -0.698073 0.714774 0.042336 -0.698077 0.71477 -0.142356 -0.706864 0.692877 -0.31913 -0.637421 0.701321 0.0156488 -0.694751 0.71908 0.0156489 -0.694751 0.71908 -0.345986 -0.694752 0.630566 -0.345988 -0.69475 0.630567 -0.614922 -0.694746 0.373094 -0.614914 -0.694753 0.373093 -0.719076 -0.694755 0.0156487 -0.71908 -0.694751 0.015647 -0.630569 -0.69475 -0.345985 -0.630573 -0.694744 -0.34599 -0.373094 -0.694745 -0.614923 -0.373094 -0.694746 -0.614922 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.8767 0 -0.481037 -0.8767 0 -0.481037 -0.518722 0 -0.854943 -0.518722 0 -0.854943 0.0156489 -0.694746 0.719085 0.0156507 -0.694751 0.71908 -0.345988 -0.694751 0.630566 -0.345986 -0.694752 0.630565 -0.614917 -0.694751 0.373093 -0.614919 -0.694749 0.373093 -0.719082 -0.694749 0.0156493 -0.719082 -0.694749 0.0156493 -0.630567 -0.694751 -0.345986 -0.63057 -0.694747 -0.34599 -0.373095 -0.694744 -0.614924 -0.373093 -0.694754 -0.614913 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217599 -0.999763 0 0.0217599 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.518726 0 -0.854941 -0.518726 0 -0.854941 0.0156489 -0.694746 0.719085 0.0156507 -0.694751 0.71908 -0.345989 -0.694749 0.630567 -0.345985 -0.694754 0.630564 -0.614914 -0.694754 0.373092 -0.614919 -0.69475 0.373092 -0.71908 -0.694751 0.0156508 -0.719085 -0.694746 0.015649 -0.630572 -0.694743 -0.345992 -0.630568 -0.69475 -0.345986 -0.373093 -0.694752 -0.614916 -0.373094 -0.694748 -0.61492 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0591236 0 0.998251 0.021757 -0.00303655 0.999759 -0.201256 0 0.979539 -0.414177 0 0.910197 -0.481034 -0.00507064 0.876687 -0.635649 0 0.771979 -0.791483 0 0.611191 -0.854924 -0.00609041 0.518717 -0.922706 0 0.385505 -0.985353 0 0.170526 -0.999745 -0.0060904 0.0217567 -0.995913 0 -0.0903212 -0.950845 0 -0.309667 -0.876688 -0.00507038 -0.481033 -0.486397 0 -0.873738 -0.518723 -0.00303643 -0.854937 -0.695951 0 -0.718089 -0.8383 0 -0.545209 -0.348271 -0.698073 -0.625621 -0.348271 -0.698077 -0.625616 -0.492281 -0.706864 -0.50794 -0.61997 -0.651636 -0.437045 -0.597956 -0.700863 -0.388895 -0.673289 -0.706117 -0.219274 -0.774261 -0.619556 -0.129116 -0.708165 -0.70312 -0.0642248 -0.687437 -0.698069 0.200325 -0.871116 -0.467365 0.150756 -0.654506 -0.704873 0.273452 -0.532437 -0.698075 0.478751 -0.654969 -0.561436 0.505773 -0.450098 -0.70612 0.546632 -0.271984 -0.698078 0.662354 0.0423338 -0.698078 0.714769 0.0423337 -0.698078 0.714769 -0.142359 -0.706863 0.692877 -0.31913 -0.637421 0.701321 -0.348271 -0.698074 -0.62562 -0.348271 -0.698074 -0.62562 -0.492296 -0.70686 -0.507931 -0.592042 -0.689419 -0.417359 -0.597955 -0.700862 -0.388899 -0.673291 -0.706117 -0.219269 -0.719491 -0.684059 -0.119983 -0.70816 -0.703126 -0.0642212 -0.698943 -0.704875 0.120956 -0.701927 -0.682244 0.20455 -0.654504 -0.704874 0.273454 -0.532436 -0.698075 0.478753 -0.588261 -0.669026 0.45426 -0.450096 -0.706117 0.546636 -0.271984 -0.698075 0.662357 0.0423293 -0.698073 0.714775 0.0423328 -0.698074 0.714773 -0.142357 -0.70686 0.692881 -0.302053 -0.68421 0.663793 0.0591169 0 0.998251 0.0591169 0 0.998251 -0.201253 0 0.979539 -0.201253 0 0.979539 -0.414177 0 0.910196 -0.414177 0 0.910196 -0.635644 0 0.771982 -0.635644 0 0.771982 -0.791483 0 0.611191 -0.791483 0 0.611191 -0.922704 0 0.385509 -0.922704 0 0.385509 -0.985354 0 0.170521 -0.985354 0 0.170521 -0.995913 0 -0.0903169 -0.995913 0 -0.0903169 -0.950847 0 -0.309661 -0.950847 0 -0.309661 -0.838298 0 -0.545213 -0.838298 0 -0.545213 -0.695969 0 -0.718072 -0.695969 0 -0.718072 -0.486395 0 -0.873739 -0.486395 0 -0.873739 0.042333 0.698071 0.714776 0.0423293 0.698073 0.714774 -0.142357 0.706858 0.692882 -0.275152 0.689417 0.670072 -0.295431 0.700861 0.649241 -0.450098 0.706116 0.546638 -0.542402 0.684058 0.487714 -0.562798 0.703123 0.434598 -0.687433 0.698073 0.200326 -0.699292 0.652402 0.292167 -0.698945 0.704873 0.120956 -0.706274 0.698073 -0.117778 -0.740205 0.669023 -0.0671273 -0.673292 0.706115 -0.21927 -0.585229 0.698072 -0.412556 -0.348272 0.698072 -0.625622 -0.348271 0.698072 -0.625622 -0.492298 0.706858 -0.507932 -0.611358 0.684209 -0.397616 -0.373094 -0.69475 -0.614918 -0.373091 -0.694746 -0.614923 -0.63057 -0.694747 -0.345988 -0.629507 -0.660381 -0.409412 -0.67329 -0.706117 -0.219272 -0.719084 -0.694747 0.0156479 -0.764722 -0.640618 -0.0693464 -0.698944 -0.704874 0.120953 -0.654502 -0.704874 0.273459 -0.632223 -0.673166 0.38359 0.015653 -0.69475 0.719081 0.0156478 -0.694747 0.719084 -0.295431 -0.700863 0.64924 -0.354076 -0.676905 0.645314 -0.450098 -0.706119 0.546633 -0.562801 -0.703127 0.434588 -0.486397 0 -0.873738 -0.518718 0.00192551 -0.854943 -0.817324 -0.00160953 -0.576176 -0.838303 0 -0.545205 -0.950846 0 -0.309664 -0.986376 -0.00257831 -0.164485 -0.995914 0 -0.0903113 -0.985355 0 0.170517 -0.960061 -0.002902 0.279776 -0.922701 0 0.385517 -0.791492 0 0.61118 -0.743603 -0.0025782 0.668616 -0.635649 0 0.771979 -0.379854 0 0.925046 -0.414176 -0.00192596 0.910195 0.0591301 0.00224018 0.998248 0.0217629 0 0.999763 -0.348272 0.698075 -0.625618 -0.34827 0.698075 -0.625618 -0.585225 0.698075 -0.412557 -0.585228 0.698074 -0.412555 -0.706275 0.698072 -0.117776 -0.706272 0.698074 -0.11778 -0.687432 0.698073 0.200328 -0.687432 0.698074 0.200326 -0.532439 0.698076 0.478747 -0.532438 0.698073 0.478753 -0.271986 0.698073 0.662358 -0.271985 0.698073 0.662359 0.0423389 0.698072 0.714775 0.0423328 0.698075 0.714772 0.0156488 -0.694748 0.719083 0.0156504 -0.694749 0.719082 -0.345987 -0.694748 0.63057 -0.345988 -0.694747 0.63057 -0.61492 -0.694747 0.373095 -0.614921 -0.694747 0.373094 -0.719085 -0.694746 0.0156448 -0.719084 -0.694747 0.0156478 -0.630569 -0.694747 -0.34599 -0.630569 -0.694749 -0.345986 -0.373097 -0.69475 -0.614915 -0.373095 -0.694748 -0.614919 -0.51873 0 -0.854938 -0.51873 0 -0.854938 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.999763 0 0.0217514 -0.999763 0 0.0217514 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481036 0 0.876701 -0.481036 0 0.876701 0.021757 0 0.999763 0.021757 0 0.999763 -0.373099 0.694746 -0.614919 -0.373095 0.694748 -0.614919 -0.630568 0.694748 -0.34599 -0.630572 0.694746 -0.345988 -0.719085 0.694746 0.0156448 -0.719087 0.694744 0.0156479 -0.614922 0.694745 0.373096 -0.614922 0.694745 0.373095 -0.345988 0.694745 0.630572 -0.345989 0.694746 0.630571 0.0156488 0.694747 0.719084 0.0156505 0.694746 0.719085 -0.486394 0 -0.87374 -0.518721 -0.00161863 -0.854942 -0.695951 0 -0.718089 -0.8383 0 -0.545209 -0.876697 -0.00270296 -0.481036 -0.950846 0 -0.309664 -0.995913 0 -0.0903171 -0.999758 -0.00324661 0.0217599 -0.985353 0 0.170525 -0.922706 0 0.385505 -0.854937 -0.00324663 0.518722 -0.791485 0 0.611188 -0.635644 0 0.771983 -0.481038 -0.00270298 0.876695 -0.414178 0 0.910196 -0.201252 0 0.97954 0.021757 -0.00161871 0.999762 0.0591236 0 0.998251 -0.37309 0.694752 -0.614918 -0.373101 0.69474 -0.614925 -0.630575 0.694741 -0.345991 -0.630573 0.694743 -0.345991 -0.719089 0.694741 0.0156511 -0.719085 0.694746 0.015649 -0.614922 0.694745 0.373096 -0.614919 0.694749 0.373092 -0.345989 0.69475 0.630567 -0.345989 0.694745 0.630571 0.0156489 0.694746 0.719085 0.0156509 0.694742 0.719089 -0.486397 0 -0.873738 -0.518724 0.00161865 -0.85494 -0.817326 -0.00135252 -0.576174 -0.8383 0 -0.545209 -0.950845 0 -0.309667 -0.986377 -0.002167 -0.164486 -0.995914 0 -0.0903113 -0.985355 0 0.170513 -0.960063 -0.0024391 0.279774 -0.922701 0 0.385517 -0.791488 0 0.611185 -0.743601 -0.00216683 0.66862 -0.635649 0 0.771979 -0.379852 0 0.925047 -0.414176 -0.00161882 0.910195 0.0591235 0.00188277 0.998249 0.021757 0 0.999763 -0.348275 0.698068 -0.625624 -0.348271 0.698072 -0.625621 -0.585226 0.698075 -0.412555 -0.585231 0.69807 -0.412556 -0.706277 0.698069 -0.117777 -0.706273 0.698073 -0.117779 -0.687433 0.698073 0.200326 -0.687429 0.698078 0.200322 -0.532436 0.698078 0.478748 -0.53244 0.698067 0.478759 -0.271985 0.698069 0.662362 -0.271986 0.698076 0.662355 0.0423341 0.698073 0.714774 0.042334 0.698073 0.714774 -0.486397 0 -0.873738 -0.486397 0 -0.873738 -0.695951 0 -0.718089 -0.695951 0 -0.718089 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.950845 0 -0.309667 -0.950845 0 -0.309667 -0.995914 0 -0.0903117 -0.995914 0 -0.0903117 -0.985356 0 0.170512 -0.985356 0 0.170512 -0.922701 0 0.385517 -0.922701 0 0.385517 -0.791488 0 0.611185 -0.791488 0 0.611185 -0.635649 0 0.771979 -0.635649 0 0.771979 -0.414177 0 0.910196 -0.414177 0 0.910196 -0.201248 0 0.97954 -0.201248 0 0.97954 0.0591236 0 0.998251 0.0591236 0 0.998251 0.0423364 0.698069 0.714778 0.0423341 0.698073 0.714774 -0.142353 0.706861 0.692881 -0.288134 0.651633 0.701679 -0.295433 0.700858 0.649244 -0.450104 0.70611 0.54664 -0.583688 0.619558 0.52484 -0.562798 0.703128 0.434591 -0.654499 0.704878 0.273458 -0.762167 0.60809 0.222102 -0.698945 0.704874 0.12095 -0.706274 0.698073 -0.117779 -0.82416 0.561405 -0.0747367 -0.673293 0.706112 -0.219275 -0.585231 0.69807 -0.412555 -0.348274 0.69807 -0.625622 -0.34827 0.698074 -0.62562 -0.492283 0.706861 -0.507942 -0.645928 0.637415 -0.420095 -0.486396 0 -0.873738 -0.518725 0.00161868 -0.85494 -0.817326 -0.0013525 -0.576174 -0.8383 0 -0.545209 -0.950845 0 -0.309668 -0.986377 -0.002167 -0.164486 -0.995914 0 -0.0903115 -0.985355 0 0.170513 -0.960063 -0.0024391 0.279773 -0.922701 0 0.385516 -0.791488 0 0.611185 -0.7436 -0.00216687 0.668621 -0.635645 0 0.771982 -0.379853 0 0.925047 -0.414177 -0.00161882 0.910195 0.0591248 0.0018828 0.998249 0.0217577 0 0.999763 -0.348274 0.698071 -0.625622 -0.34827 0.698075 -0.625619 -0.585225 0.698077 -0.412554 -0.585232 0.69807 -0.412555 -0.706277 0.698069 -0.117777 -0.706273 0.698073 -0.117779 -0.687433 0.698073 0.200326 -0.687429 0.698077 0.200323 -0.532436 0.698076 0.47875 -0.53244 0.698067 0.478759 -0.271986 0.69807 0.662361 -0.271987 0.698075 0.662355 0.042335 0.698072 0.714775 0.0423351 0.698072 0.714775 -0.348267 -0.698083 -0.625612 -0.348267 -0.69808 -0.625615 -0.49228 -0.706865 -0.50794 -0.61997 -0.651635 -0.437046 -0.597956 -0.700863 -0.388895 -0.67329 -0.706117 -0.219272 -0.77426 -0.619557 -0.129116 -0.708161 -0.703124 -0.0642216 -0.687432 -0.698074 0.200325 -0.871117 -0.467364 0.150755 -0.654506 -0.704873 0.273452 -0.532437 -0.698075 0.478751 -0.654975 -0.561426 0.505774 -0.450094 -0.70612 0.546635 -0.271984 -0.698078 0.662354 0.0423341 -0.698073 0.714774 0.042336 -0.698078 0.714769 -0.142356 -0.706863 0.692878 -0.319132 -0.637418 0.701323 -0.373096 -0.694746 -0.614921 -0.373096 -0.694745 -0.614921 -0.630571 -0.694744 -0.345993 -0.711984 -0.52788 -0.463056 -0.673286 -0.706119 -0.219273 -0.71908 -0.694751 0.0156507 -0.9089 -0.408787 -0.0824207 -0.698946 -0.704872 0.120951 -0.654504 -0.704872 0.27346 -0.704404 -0.566707 0.427386 0.0156487 -0.694751 0.71908 0.0156489 -0.694751 0.71908 -0.29543 -0.700863 0.649239 -0.387718 -0.59191 0.706624 -0.450095 -0.706124 0.546629 -0.562795 -0.703132 0.434589 -0.34827 -0.698075 -0.625619 -0.34827 -0.698079 -0.625615 -0.492279 -0.706866 -0.507939 -0.619969 -0.651637 -0.437044 -0.597956 -0.700863 -0.388895 -0.673289 -0.706117 -0.219274 -0.774261 -0.619556 -0.129116 -0.708157 -0.703129 -0.0642173 -0.687428 -0.698079 0.200322 -0.871129 -0.467344 0.150746 -0.654494 -0.704882 0.273457 -0.53243 -0.698081 0.478749 -0.654982 -0.561418 0.505775 -0.450101 -0.706114 0.546636 -0.271987 -0.698074 0.662356 0.0423341 -0.698073 0.714774 0.0423359 -0.698077 0.71477 -0.142353 -0.706865 0.692876 -0.31913 -0.637421 0.701321 -0.373095 -0.694748 -0.614919 -0.373095 -0.694747 -0.61492 -0.63057 -0.694745 -0.345993 -0.711983 -0.527882 -0.463056 -0.673286 -0.70612 -0.219273 -0.71908 -0.694751 0.0156507 -0.908901 -0.408787 -0.0824209 -0.698946 -0.704873 0.120951 -0.654503 -0.704873 0.273459 -0.704404 -0.566705 0.427387 0.0156493 -0.69475 0.719082 0.0156494 -0.69475 0.719081 -0.295432 -0.700862 0.64924 -0.387718 -0.59191 0.706624 -0.450094 -0.706121 0.546633 -0.562797 -0.70313 0.43459 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.854943 0 0.518722 -0.854943 0 0.518722 -0.999763 0 0.02176 -0.999763 0 0.02176 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.518726 0 -0.854941 -0.518726 0 -0.854941 0.0156489 -0.694746 0.719085 0.0156472 -0.694742 0.719089 -0.345993 -0.694741 0.630574 -0.345989 -0.694746 0.630571 -0.61492 -0.694749 0.373092 -0.614914 -0.694754 0.373092 -0.71908 -0.694751 0.0156509 -0.719085 -0.694746 0.0156489 -0.630569 -0.694748 -0.34599 -0.630567 -0.69475 -0.345988 -0.373093 -0.694752 -0.614916 -0.373094 -0.694748 -0.61492 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.379852 0 0.925047 -0.379852 0 0.925047 -0.743603 0 0.668622 -0.743603 0 0.668622 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164487 -0.986379 0 -0.164487 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0.0423341 -0.698073 0.714774 0.0423361 -0.698078 0.714769 -0.271983 -0.698077 0.662355 -0.271985 -0.698074 0.662357 -0.532441 -0.698071 0.478752 -0.53243 -0.698081 0.478749 -0.687424 -0.698082 0.200323 -0.687428 -0.698079 0.200322 -0.70627 -0.698077 -0.117776 -0.706272 -0.698074 -0.117778 -0.585226 -0.698074 -0.412556 -0.585226 -0.698075 -0.412555 -0.348269 -0.698076 -0.625618 -0.348269 -0.698081 -0.625613 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.481037 0 0.8767 -0.481037 0 0.8767 -0.854943 0 0.518722 -0.854943 0 0.518722 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0156493 -0.694749 0.719082 0.0156493 -0.694749 0.719082 -0.345986 -0.694751 0.630567 -0.34599 -0.694747 0.63057 -0.614924 -0.694744 0.373095 -0.614913 -0.694754 0.373093 -0.719076 -0.694755 0.0156487 -0.71908 -0.694751 0.015647 -0.630566 -0.694751 -0.345988 -0.630565 -0.694752 -0.345986 -0.373093 -0.694751 -0.614916 -0.373093 -0.694748 -0.61492 -0.373094 -0.69475 -0.614918 -0.373091 -0.694746 -0.614923 -0.63057 -0.694747 -0.345988 -0.629507 -0.660381 -0.409412 -0.673288 -0.706116 -0.21928 -0.719084 -0.694747 0.0156505 -0.764724 -0.640615 -0.0693466 -0.698946 -0.704873 0.12095 -0.654503 -0.704873 0.27346 -0.632224 -0.673164 0.383594 0.0156529 -0.69475 0.719081 0.0156478 -0.694747 0.719084 -0.295431 -0.700863 0.64924 -0.354083 -0.676902 0.645313 -0.450101 -0.706116 0.546635 -0.562804 -0.703124 0.43459 -0.486386 0 -0.873744 -0.518718 0.0019261 -0.854943 -0.817329 -0.0016092 -0.576169 -0.838303 0 -0.545205 -0.950842 0 -0.309676 -0.986376 -0.00257838 -0.164487 -0.995914 0 -0.0903113 -0.985356 0 0.170512 -0.960062 -0.0029021 0.279773 -0.922701 0 0.385517 -0.791492 0 0.61118 -0.743603 -0.0025782 0.668616 -0.635649 0 0.771979 -0.379852 0 0.925047 -0.414176 -0.0019261 0.910195 0.0591301 0.0022402 0.998248 0.0217628 0 0.999763 -0.348264 0.698076 -0.625622 -0.348272 0.698072 -0.625621 -0.58523 0.698072 -0.412554 -0.585228 0.698074 -0.412555 -0.706274 0.698073 -0.117778 -0.706273 0.698074 -0.11778 -0.687432 0.698074 0.200325 -0.687432 0.698073 0.200328 -0.532441 0.698074 0.478748 -0.532441 0.698073 0.47875 -0.271984 0.698073 0.662358 -0.271985 0.698073 0.662358 0.0423389 0.698072 0.714775 0.0423326 0.698075 0.714772 0.015649 -0.694748 0.719083 0.0156479 -0.694747 0.719084 -0.34599 -0.694747 0.630569 -0.345987 -0.694749 0.630569 -0.614916 -0.694751 0.373095 -0.614918 -0.69475 0.373094 -0.719081 -0.69475 0.015653 -0.719084 -0.694747 0.0156478 -0.63057 -0.694748 -0.345988 -0.63057 -0.694746 -0.345992 -0.373092 -0.694746 -0.614923 -0.373095 -0.694748 -0.614919 -0.486397 0 -0.873738 -0.518719 0.00192561 -0.854942 -0.695921 0 -0.718118 -0.8383 0 -0.545209 -0.876695 0.00321602 -0.481035 -0.950846 0 -0.309664 -0.995913 0 -0.0903221 -0.999756 0.00386313 0.0217627 -0.985351 0 0.170538 -0.922706 0 0.385505 -0.854934 0.00386294 0.518723 -0.791483 0 0.611191 -0.635658 0 0.771971 -0.481038 0.00321629 0.876694 0.0591236 0 0.998251 0.0217572 0.00192596 0.999761 -0.201264 0 0.979537 -0.414174 0 0.910198 0.0423358 0.698073 0.714774 0.042334 0.698074 0.714773 -0.142365 0.70686 0.692879 -0.275155 0.689419 0.670068 -0.295429 0.70086 0.649243 -0.450109 0.706114 0.546631 -0.542404 0.684058 0.487712 -0.562799 0.703122 0.434599 -0.654508 0.704871 0.273453 -0.701928 0.682243 0.204555 -0.698944 0.704871 0.120969 -0.706274 0.698072 -0.11778 -0.740204 0.669023 -0.0671312 -0.673292 0.706115 -0.219272 -0.585228 0.698072 -0.412558 -0.348273 0.698073 -0.62562 -0.348271 0.698074 -0.62562 -0.492262 0.70686 -0.507963 -0.611363 0.684206 -0.397615 0.0423349 -0.698075 0.714772 0.0423349 -0.698075 0.714772 -0.271986 -0.698075 0.662356 -0.271985 -0.698075 0.662356 -0.532431 -0.698077 0.478755 -0.532438 -0.698074 0.478752 -0.687434 -0.698073 0.200321 -0.687432 -0.698074 0.200324 -0.706273 -0.698075 -0.117772 -0.706274 -0.698074 -0.117774 -0.585225 -0.698074 -0.412559 -0.585225 -0.698075 -0.412556 -0.348272 -0.698075 -0.625618 -0.348271 -0.698075 -0.625619 -0.486396 0 -0.873738 -0.486396 0 -0.873738 -0.817323 0 -0.576179 -0.817323 0 -0.576179 -0.98638 0 -0.16448 -0.98638 0 -0.16448 -0.960068 0 0.279768 -0.960068 0 0.279768 -0.743595 0 0.66863 -0.743595 0 0.66863 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591248 0 0.998251 0.0591248 0 0.998251 -0.348273 0.698073 -0.62562 -0.348272 0.698073 -0.62562 -0.585225 0.698074 -0.412559 -0.585228 0.698072 -0.412558 -0.706276 0.698072 -0.117772 -0.706274 0.698073 -0.117775 -0.687434 0.698073 0.200321 -0.687435 0.698071 0.200325 -0.532435 0.698071 0.478758 -0.532437 0.698074 0.478752 -0.271987 0.698074 0.662357 -0.271986 0.698073 0.662358 0.042335 0.698073 0.714774 0.042335 0.698073 0.714774 0.960066 2.80255e-07 -0.279773 0.960066 1.30952e-07 -0.279774 0.960065 0 -0.279776 0.960066 -1.14171e-07 -0.279774 0.960066 -2.30115e-07 -0.279773 0.960066 -7.74036e-07 -0.279774 0.960066 -4.40935e-06 -0.279774 0.960066 -7.49421e-07 -0.279774 0.960066 9.60022e-07 -0.279774 0.960066 5.73114e-07 -0.279774 0.960066 -5.87303e-07 -0.279774 0.960066 -3.01191e-07 -0.279774 0.960066 -2.98144e-07 -0.279773 0.960066 2.46349e-07 -0.279773 0.960067 1.08179e-05 -0.279769 0.960066 -1.01627e-06 -0.279775 0.960066 1.53568e-07 -0.279773 0.960066 4.60216e-07 -0.279772 0.960066 -2.2137e-07 -0.279773 0.960065 0 -0.279776 0.960066 1.91644e-07 -0.279773 0.960066 -3.42605e-07 -0.279773 0.960066 3.56031e-07 -0.279774 0.960066 9.15734e-08 -0.279774 0.960066 2.25508e-07 -0.279774 0.960066 1.03294e-06 -0.279775 0.960066 -7.94496e-07 -0.279773 0.960066 0 -0.279773 0.960066 1.64233e-07 -0.279773 0.960066 7.20983e-07 -0.279773 0.960066 6.14483e-07 -0.279773 0.960065 -5.79592e-06 -0.279776 0.960066 0 -0.279773 0.960066 6.21856e-07 -0.279773 0.960066 -4.53031e-08 -0.279773 0.960065 -3.36512e-06 -0.279776 0.960066 4.95656e-07 -0.279775 0.960066 5.60685e-07 -0.279774 0.960066 -1.49803e-07 -0.279773 0.960066 -3.75719e-07 -0.279772 0.960066 -3.19084e-07 -0.279773 0.960066 -5.97877e-07 -0.279773 0.960067 -2.91099e-06 -0.279772 0.960065 4.39039e-06 -0.279777 0.960066 -3.20028e-07 -0.279774 0.960066 2.83877e-07 -0.279773 0.960066 2.50125e-07 -0.279773 0.960066 -1.02199e-06 -0.279774 0.960066 6.32199e-07 -0.279774 0.960066 9.03866e-07 -0.279774 0.960066 1.54808e-06 -0.279774 0.960066 -1.32584e-06 -0.279775 0.776962 0.5102 -0.368818 0.710718 0.373498 -0.596138 0.672469 0.136707 -0.72739 0.957952 0.136707 0.252268 0.919704 0.373496 0.121016 0.85346 0.5102 -0.106307 -0.270241 0.258816 -0.927353 -0.270241 0.258817 -0.927353 -0.197829 0.707112 -0.678864 -0.197829 0.707112 -0.678864 -0.0724132 0.965924 -0.248491 -0.0724133 0.965924 -0.248492 0.0724133 0.965924 0.248492 0.0724132 0.965924 0.248491 0.197829 0.707112 0.678864 0.197829 0.707112 0.678864 0.270241 0.258816 0.927353 0.270241 0.258817 0.927353 0.776963 0.5102 -0.368814 0.710718 0.373495 -0.596139 0.672469 0.136706 -0.72739 0.957953 0.136707 0.252265 0.919704 0.373499 0.121011 0.85346 0.5102 -0.106307 -0.270241 0.258815 -0.927353 -0.270241 0.258815 -0.927353 -0.197828 0.707114 -0.678863 -0.197828 0.707114 -0.678863 -0.0724134 0.965923 -0.248492 -0.0724134 0.965923 -0.248492 0.0724132 0.965924 0.248491 0.0724132 0.965924 0.248491 0.197829 0.707112 0.678864 0.197829 0.707111 0.678865 0.270241 0.258818 0.927353 0.270241 0.258815 0.927353 -0.960066 -1.12812e-07 0.279774 -0.960065 0 0.279776 -0.960066 1.19015e-06 0.279773 -0.960066 2.20927e-07 0.279774 -0.960065 -8.69295e-07 0.279777 -0.960066 2.74293e-07 0.279773 -0.960066 1.30952e-07 0.279774 -0.960067 2.71256e-07 0.279771 -0.960068 0 0.279768 -0.960067 -2.37856e-07 0.279771 -0.960066 1.15182e-06 0.279774 -0.960066 -5.68895e-07 0.279774 -0.960066 1.04145e-06 0.279773 -0.960065 4.03762e-06 0.279778 -0.960065 4.52232e-06 0.279779 -0.960065 1.26413e-06 0.279779 -0.960066 -3.47719e-07 0.279773 -0.960066 2.91031e-07 0.279774 -0.960066 9.30629e-07 0.279773 -0.960066 3.30171e-07 0.279775 -0.960066 1.59433e-06 0.279774 -0.960066 5.86846e-08 0.279775 -0.960066 -5.44866e-06 0.279773 -0.960066 0 0.279773 -0.960066 -5.5119e-07 0.279773 -0.960066 -2.35118e-07 0.279773 -0.960065 7.1804e-07 0.279777 -0.960066 -9.58739e-07 0.279773 -0.960066 -3.16099e-07 0.279774 -0.960066 -1.57943e-06 0.279774 -0.960066 -8.3322e-07 0.279773 -0.960066 -1.38762e-06 0.279773 -0.960066 -8.13044e-08 0.279774 -0.960066 2.83877e-07 0.279773 -0.960064 -1.06053e-06 0.279779 -0.960066 2.50565e-07 0.279774 -0.960066 -1.44612e-06 0.279774 -0.960066 2.75584e-06 0.279774 -0.960066 6.19229e-06 0.279774 -0.960066 -7.23061e-07 0.279775 -0.960066 -6.45034e-07 0.279774 -0.960066 -1.44619e-06 0.279774 -0.960066 1.22385e-06 0.279775 -0.960066 -2.90648e-07 0.279774 -0.960067 3.79693e-06 0.279771 -0.960066 1.06289e-06 0.279773 -0.960066 -1.48389e-06 0.279775 -0.960065 5.40994e-07 0.279776 -0.960065 0 0.279776 -0.960065 -5.41001e-07 0.279776 -0.960065 -6.74155e-06 0.279778 -0.776961 0.5102 0.368818 -0.710718 0.373498 0.596137 -0.672469 0.136706 0.72739 -0.957952 0.136707 -0.252268 -0.919704 0.373496 -0.121016 -0.85346 0.5102 0.106307 0.270241 0.258815 0.927353 0.270241 0.258815 0.927353 0.197829 0.707113 0.678863 0.197829 0.707113 0.678863 0.0724133 0.965924 0.248492 0.0724134 0.965923 0.248492 -0.0724132 0.965924 -0.248491 -0.0724131 0.965924 -0.248491 -0.197829 0.707111 -0.678865 -0.197829 0.707111 -0.678865 -0.270241 0.258815 -0.927353 -0.270241 0.258815 -0.927353 -0.776963 0.5102 0.368814 -0.710719 0.373496 0.596137 -0.672469 0.136703 0.727391 -0.957953 0.136706 -0.252265 -0.919704 0.373499 -0.121011 -0.85346 0.5102 0.106307 0.270241 0.258818 0.927353 0.270241 0.258817 0.927353 0.197829 0.707112 0.678864 0.197829 0.707112 0.678864 0.0724133 0.965924 0.248492 0.0724133 0.965924 0.248492 -0.0724133 0.965924 -0.248492 -0.0724133 0.965924 -0.248492 -0.197829 0.707112 -0.678864 -0.197829 0.707112 -0.678864 -0.270241 0.258816 -0.927353 -0.270241 0.258818 -0.927353 -0.908323 0 0.41827 -0.908323 0 0.41827 -0.990823 0 0.135163 -0.990823 0 0.135163 0.990823 0 -0.135163 0.990823 0 -0.135163 0.908323 0 -0.41827 0.908323 0 -0.41827 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.199537 0 0.97989 0.199537 0 0.97989 0.0355311 0 0.999369 0.0355311 0 0.999369 -0.129445 0 0.991587 -0.129445 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.141334 -0.705903 0.694065 0.141336 -0.705894 0.694073 0.025167 -0.705894 0.70787 0.0251674 -0.705887 0.707877 -0.0916884 -0.705887 0.702365 -0.0916873 -0.705899 0.702353 -0.20604 -0.705899 0.677683 -0.206038 -0.705908 0.677674 -0.314769 -0.705908 0.634519 -0.314774 -0.705895 0.634531 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.503751 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658365 -0.705886 -0.261304 -0.658359 -0.705893 -0.261301 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.454647 -0.705888 -0.543155 -0.359046 -0.705888 -0.61058 -0.359041 -0.705897 -0.610573 -0.253647 -0.705897 -0.661341 -0.25365 -0.705889 -0.661348 -0.25365 0.70589 -0.661348 -0.253647 0.705898 -0.661341 -0.359042 0.705897 -0.610573 -0.359046 0.705887 -0.610581 -0.454647 0.705888 -0.543156 -0.454643 0.705894 -0.543151 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658366 0.705886 -0.261304 -0.692395 0.705886 -0.149376 -0.692394 0.705887 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503753 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314768 0.705909 0.634519 -0.206037 0.705908 0.677674 -0.20604 0.705899 0.677683 -0.0916869 0.705899 0.702354 -0.0916888 0.705887 0.702365 0.0251672 0.705887 0.707877 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141334 0.705902 0.694065 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.199537 0 0.97989 0.199537 0 0.97989 0.0355311 0 0.999369 0.0355311 0 0.999369 -0.129445 0 0.991587 -0.129445 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.97751 0 -0.210887 -0.97751 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.199537 0 0.97989 0.199537 0 0.97989 0.0355311 0 0.999369 0.0355311 0 0.999369 -0.129445 0 0.991587 -0.129445 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.199537 0 0.97989 0.199537 0 0.97989 0.0355311 0 0.999369 0.0355311 0 0.999369 -0.129445 0 0.991587 -0.129445 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.199537 0 0.97989 0.199537 0 0.97989 0.0355311 0 0.999369 0.0355311 0 0.999369 -0.129445 0 0.991587 -0.129445 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.97751 0 -0.210887 -0.97751 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.199537 0 0.97989 0.199537 0 0.97989 0.0355311 0 0.999369 0.0355311 0 0.999369 -0.129445 0 0.991587 -0.129445 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.199537 0 0.97989 0.199537 0 0.97989 0.0355311 0 0.999369 0.0355311 0 0.999369 -0.129445 0 0.991587 -0.129445 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.199537 0 0.97989 0.199537 0 0.97989 0.0355311 0 0.999369 0.0355311 0 0.999369 -0.129445 0 0.991587 -0.129445 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.97751 0 -0.210887 -0.97751 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.199537 0 0.97989 0.199537 0 0.97989 0.0355311 0 0.999369 0.0355311 0 0.999369 -0.129445 0 0.991587 -0.129445 0 0.991587 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.3581 0 -0.933683 -0.3581 0 -0.933683 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.141334 -0.705903 0.694065 0.141336 -0.705894 0.694073 0.025167 -0.705894 0.70787 0.0251674 -0.705887 0.707877 -0.0916884 -0.705887 0.702365 -0.0916873 -0.705899 0.702353 -0.20604 -0.705899 0.677683 -0.206038 -0.705908 0.677674 -0.314769 -0.705908 0.634519 -0.314774 -0.705895 0.634531 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.503751 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658365 -0.705886 -0.261304 -0.658359 -0.705893 -0.261301 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.454647 -0.705888 -0.543155 -0.359046 -0.705888 -0.61058 -0.359041 -0.705897 -0.610573 -0.253647 -0.705897 -0.661341 -0.25365 -0.705889 -0.661348 -0.25365 0.70589 -0.661348 -0.253647 0.705898 -0.661341 -0.359042 0.705897 -0.610573 -0.359046 0.705887 -0.610581 -0.454647 0.705888 -0.543156 -0.454643 0.705894 -0.543151 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658366 0.705886 -0.261304 -0.692395 0.705886 -0.149376 -0.692394 0.705887 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503753 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314768 0.705909 0.634519 -0.206037 0.705908 0.677674 -0.20604 0.705899 0.677683 -0.0916869 0.705899 0.702354 -0.0916888 0.705887 0.702365 0.0251672 0.705887 0.707877 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141334 0.705902 0.694065 0.141334 -0.705903 0.694065 0.141336 -0.705894 0.694073 0.025167 -0.705894 0.70787 0.0251674 -0.705887 0.707877 -0.0916884 -0.705887 0.702365 -0.0916873 -0.705899 0.702353 -0.20604 -0.705899 0.677683 -0.206038 -0.705908 0.677674 -0.314769 -0.705908 0.634519 -0.314774 -0.705895 0.634531 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.503751 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658365 -0.705886 -0.261304 -0.658359 -0.705893 -0.261301 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.454647 -0.705888 -0.543155 -0.359046 -0.705888 -0.61058 -0.359041 -0.705897 -0.610573 -0.253647 -0.705897 -0.661341 -0.25365 -0.705889 -0.661348 -0.25365 0.70589 -0.661348 -0.253647 0.705898 -0.661341 -0.359042 0.705897 -0.610573 -0.359046 0.705887 -0.610581 -0.454647 0.705888 -0.543156 -0.454643 0.705894 -0.543151 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658366 0.705886 -0.261304 -0.692395 0.705886 -0.149376 -0.692394 0.705887 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503753 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314768 0.705909 0.634519 -0.206037 0.705908 0.677674 -0.20604 0.705899 0.677683 -0.0916869 0.705899 0.702354 -0.0916888 0.705887 0.702365 0.0251672 0.705887 0.707877 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141334 0.705902 0.694065 0.141334 -0.705903 0.694065 0.141336 -0.705894 0.694073 0.025167 -0.705894 0.70787 0.0251674 -0.705887 0.707877 -0.0916884 -0.705887 0.702365 -0.0916873 -0.705899 0.702353 -0.20604 -0.705899 0.677683 -0.206038 -0.705908 0.677674 -0.314769 -0.705908 0.634519 -0.314774 -0.705895 0.634531 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.503751 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658365 -0.705886 -0.261304 -0.658359 -0.705893 -0.261301 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.454647 -0.705888 -0.543155 -0.359046 -0.705888 -0.61058 -0.359041 -0.705897 -0.610573 -0.253647 -0.705897 -0.661341 -0.25365 -0.705889 -0.661348 -0.25365 0.70589 -0.661348 -0.253647 0.705898 -0.661341 -0.359042 0.705897 -0.610573 -0.359046 0.705887 -0.610581 -0.454647 0.705888 -0.543156 -0.454643 0.705894 -0.543151 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658366 0.705886 -0.261304 -0.692395 0.705886 -0.149376 -0.692394 0.705887 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503753 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314768 0.705909 0.634519 -0.206037 0.705908 0.677674 -0.20604 0.705899 0.677683 -0.0916869 0.705899 0.702354 -0.0916888 0.705887 0.702365 0.0251672 0.705887 0.707877 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141334 0.705902 0.694065 0.141334 -0.705903 0.694065 0.141336 -0.705894 0.694073 0.025167 -0.705894 0.70787 0.0251674 -0.705887 0.707877 -0.0916884 -0.705887 0.702365 -0.0916873 -0.705899 0.702353 -0.20604 -0.705899 0.677683 -0.206038 -0.705908 0.677674 -0.314769 -0.705908 0.634519 -0.314774 -0.705895 0.634531 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.503751 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658365 -0.705886 -0.261304 -0.658359 -0.705893 -0.261301 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.454647 -0.705888 -0.543155 -0.359046 -0.705888 -0.61058 -0.359041 -0.705897 -0.610573 -0.253647 -0.705897 -0.661341 -0.25365 -0.705889 -0.661348 -0.25365 0.70589 -0.661348 -0.253647 0.705898 -0.661341 -0.359042 0.705897 -0.610573 -0.359046 0.705887 -0.610581 -0.454647 0.705888 -0.543156 -0.454643 0.705894 -0.543151 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658366 0.705886 -0.261304 -0.692395 0.705886 -0.149376 -0.692394 0.705887 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503753 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314768 0.705909 0.634519 -0.206037 0.705908 0.677674 -0.20604 0.705899 0.677683 -0.0916869 0.705899 0.702354 -0.0916888 0.705887 0.702365 0.0251672 0.705887 0.707877 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141334 0.705902 0.694065 0.141334 -0.705903 0.694065 0.141336 -0.705894 0.694073 0.025167 -0.705894 0.70787 0.0251674 -0.705887 0.707877 -0.0916884 -0.705887 0.702365 -0.0916873 -0.705899 0.702353 -0.20604 -0.705899 0.677683 -0.206038 -0.705908 0.677674 -0.314769 -0.705908 0.634519 -0.314774 -0.705895 0.634531 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.503751 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658365 -0.705886 -0.261304 -0.658359 -0.705893 -0.261301 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.454647 -0.705888 -0.543155 -0.359046 -0.705888 -0.61058 -0.359041 -0.705897 -0.610573 -0.253647 -0.705897 -0.661341 -0.25365 -0.705889 -0.661348 -0.25365 0.70589 -0.661348 -0.253647 0.705898 -0.661341 -0.359042 0.705897 -0.610573 -0.359046 0.705887 -0.610581 -0.454647 0.705888 -0.543156 -0.454643 0.705894 -0.543151 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658366 0.705886 -0.261304 -0.692395 0.705886 -0.149376 -0.692394 0.705887 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503753 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314768 0.705909 0.634519 -0.206037 0.705908 0.677674 -0.20604 0.705899 0.677683 -0.0916869 0.705899 0.702354 -0.0916888 0.705887 0.702365 0.0251672 0.705887 0.707877 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141334 0.705902 0.694065 0.141334 -0.705903 0.694065 0.141336 -0.705894 0.694073 0.025167 -0.705894 0.70787 0.0251674 -0.705887 0.707877 -0.0916884 -0.705887 0.702365 -0.0916873 -0.705899 0.702353 -0.20604 -0.705899 0.677683 -0.206038 -0.705908 0.677674 -0.314769 -0.705908 0.634519 -0.314774 -0.705895 0.634531 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.503751 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658365 -0.705886 -0.261304 -0.658359 -0.705893 -0.261301 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.454647 -0.705888 -0.543155 -0.359046 -0.705888 -0.61058 -0.359041 -0.705897 -0.610573 -0.253647 -0.705897 -0.661341 -0.25365 -0.705889 -0.661348 -0.25365 0.70589 -0.661348 -0.253647 0.705898 -0.661341 -0.359042 0.705897 -0.610573 -0.359046 0.705887 -0.610581 -0.454647 0.705888 -0.543156 -0.454643 0.705894 -0.543151 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658366 0.705886 -0.261304 -0.692395 0.705886 -0.149376 -0.692394 0.705887 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503753 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314768 0.705909 0.634519 -0.206037 0.705908 0.677674 -0.20604 0.705899 0.677683 -0.0916869 0.705899 0.702354 -0.0916888 0.705887 0.702365 0.0251672 0.705887 0.707877 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141334 0.705902 0.694065 0.141334 -0.705903 0.694065 0.141336 -0.705894 0.694073 0.025167 -0.705894 0.70787 0.0251674 -0.705887 0.707877 -0.0916884 -0.705887 0.702365 -0.0916873 -0.705899 0.702353 -0.20604 -0.705899 0.677683 -0.206038 -0.705908 0.677674 -0.314769 -0.705908 0.634519 -0.314774 -0.705895 0.634531 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.503751 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658365 -0.705886 -0.261304 -0.658359 -0.705893 -0.261301 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.454647 -0.705888 -0.543155 -0.359046 -0.705888 -0.61058 -0.359041 -0.705897 -0.610573 -0.253647 -0.705897 -0.661341 -0.25365 -0.705889 -0.661348 -0.25365 0.70589 -0.661348 -0.253647 0.705898 -0.661341 -0.359042 0.705897 -0.610573 -0.359046 0.705887 -0.610581 -0.454647 0.705888 -0.543156 -0.454643 0.705894 -0.543151 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658366 0.705886 -0.261304 -0.692395 0.705886 -0.149376 -0.692394 0.705887 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503753 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314768 0.705909 0.634519 -0.206037 0.705908 0.677674 -0.20604 0.705899 0.677683 -0.0916869 0.705899 0.702354 -0.0916888 0.705887 0.702365 0.0251672 0.705887 0.707877 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141334 0.705902 0.694065 0.141332 -0.705909 0.694059 0.141334 -0.705901 0.694067 0.0251668 -0.705901 0.707864 0.0251672 -0.705894 0.707871 -0.0916876 -0.705894 0.702358 -0.0916864 -0.705905 0.702347 -0.206038 -0.705905 0.677677 -0.206036 -0.705914 0.677668 -0.314766 -0.705915 0.634513 -0.314772 -0.705902 0.634525 -0.414918 -0.705901 0.574061 -0.414919 -0.705901 0.574062 -0.503748 -0.7059 0.49794 -0.503746 -0.705902 0.497938 -0.578833 -0.705903 0.408232 -0.578838 -0.705897 0.408236 -0.638136 -0.705897 0.307394 -0.638136 -0.705898 0.307394 -0.680028 -0.705898 0.198168 -0.680019 -0.705908 0.198165 -0.703361 -0.705907 0.083535 -0.70336 -0.705909 0.0835348 -0.707516 -0.705909 -0.0333738 -0.707531 -0.705894 -0.033374 -0.692388 -0.705894 -0.149375 -0.692389 -0.705893 -0.149375 -0.658359 -0.705893 -0.261301 -0.658353 -0.7059 -0.261299 -0.606366 -0.705899 -0.366096 -0.606361 -0.705905 -0.366093 -0.537834 -0.705905 -0.460904 -0.537838 -0.7059 -0.460908 -0.454639 -0.7059 -0.543146 -0.454643 -0.705895 -0.54315 -0.359043 -0.705894 -0.610575 -0.359038 -0.705903 -0.610567 -0.253645 -0.705904 -0.661335 -0.253648 -0.705896 -0.661342 -0.253647 0.705897 -0.661342 -0.253645 0.705904 -0.661335 -0.359038 0.705903 -0.610567 -0.359043 0.705894 -0.610575 -0.454643 0.705895 -0.543151 -0.454639 0.705901 -0.543146 -0.537838 0.7059 -0.460908 -0.537834 0.705905 -0.460904 -0.606361 0.705905 -0.366093 -0.606366 0.705899 -0.366097 -0.658353 0.705899 -0.261299 -0.65836 0.705892 -0.261302 -0.692389 0.705893 -0.149375 -0.692388 0.705894 -0.149375 -0.707531 0.705894 -0.0333744 -0.707516 0.705909 -0.0333733 -0.70336 0.705909 0.0835348 -0.703361 0.705907 0.0835349 -0.680018 0.705908 0.198165 -0.680028 0.705898 0.198168 -0.638136 0.705898 0.307394 -0.638137 0.705897 0.307394 -0.578838 0.705897 0.408236 -0.578833 0.705902 0.408233 -0.503745 0.705903 0.497937 -0.503748 0.7059 0.49794 -0.414919 0.7059 0.574062 -0.414919 0.705901 0.574062 -0.314772 0.705902 0.634525 -0.314765 0.705915 0.634513 -0.206035 0.705915 0.677668 -0.206038 0.705905 0.677677 -0.0916861 0.705905 0.702347 -0.0916879 0.705894 0.702359 0.025167 0.705894 0.707871 0.025167 0.705901 0.707864 0.141334 0.705901 0.694067 0.141333 0.705909 0.694059 0.0724107 -0.965926 0.248483 0.0686504 -0.98068 0.183179 0.159695 -0.793306 0.587506 0.155434 -0.831471 0.533382 0.22196 -0.60876 0.761673 0.225519 -0.555554 0.800313 0.280835 -0.258803 0.924204 0.274398 -0.19509 0.941619 0.274398 0.19509 0.941619 0.259615 0.258803 0.930388 0.250922 0.442289 0.861057 0.22196 0.60876 0.761673 0.183642 0.707029 0.682924 0.0545816 0.980785 0.187301 0.0617967 0.965867 0.251559 0.12374 0.896875 0.424621 0.170315 0.793354 0.58445 -0.0724107 0.965926 -0.248483 -0.0724108 0.965926 -0.248483 -0.19783 0.707106 -0.678869 -0.19783 0.707106 -0.678869 -0.270241 0.258818 -0.927353 -0.270241 0.258819 -0.927352 -0.270241 -0.258819 -0.927352 -0.260294 -0.195068 -0.945619 -0.232556 -0.608723 -0.758534 -0.232624 -0.555569 -0.798266 -0.170315 -0.793355 -0.58445 -0.162528 -0.831448 -0.531298 -0.0617967 -0.965867 -0.25156 -0.0545816 -0.980785 -0.187301 0.0545817 -0.980785 0.187301 0.084285 -0.965852 0.245002 0.12374 -0.896875 0.424621 0.170315 -0.793354 0.58445 0.213666 -0.70701 0.674155 0.22196 -0.60876 0.761673 0.250921 -0.442291 0.861056 0.282101 -0.2588 0.923819 0.274398 -0.19509 0.941619 0.274398 0.19509 0.941619 0.282101 0.2588 0.923819 0.250921 0.442291 0.861056 0.22196 0.60876 0.761673 0.213666 0.70701 0.674155 0.170315 0.793354 0.58445 0.12374 0.896875 0.424621 0.084285 0.965852 0.245002 0.0545817 0.980785 0.187301 -0.0724107 0.965926 -0.248483 -0.0724107 0.965926 -0.248483 -0.19783 0.707106 -0.67887 -0.19783 0.707106 -0.678869 -0.270241 0.258819 -0.927352 -0.270241 0.258819 -0.927352 -0.270241 -0.258819 -0.927352 -0.270241 -0.258819 -0.927352 -0.19783 -0.707106 -0.67887 -0.19783 -0.707106 -0.678869 -0.0724107 -0.965926 -0.248483 -0.0724107 -0.965926 -0.248483 0.0251667 -0.705903 0.707861 0.141333 -0.705903 0.694065 0.141334 -0.705901 0.694067 -0.206039 -0.705903 0.677679 -0.124156 -0.706884 0.696348 -0.118951 -0.394403 0.911206 -0.0662436 -0.706725 0.70438 0.0251671 -0.705899 0.707865 -0.318459 -0.645813 0.693909 -0.409768 -0.387017 0.82602 -0.268303 -0.706751 0.654612 -0.261017 -0.707114 0.657161 -0.206039 -0.705903 0.677679 -0.47484 -0.557289 0.681143 -0.539902 -0.387973 0.746983 -0.381579 -0.703567 0.599492 -0.366259 -0.707111 0.604855 -0.340414 -0.706812 0.62011 -0.54006 -0.707111 0.456432 -0.537455 -0.669698 0.51249 -0.626641 -0.472911 0.619416 -0.472261 -0.707022 0.526392 -0.438767 -0.706839 0.554854 -0.556645 -0.706933 0.43634 -0.745626 -0.409277 0.525866 -0.700486 -0.524607 0.483847 -0.703364 -0.705904 0.0835353 -0.680022 -0.705904 0.198166 -0.680027 -0.705898 0.198168 -0.638135 -0.705898 0.307394 -0.638135 -0.705899 0.307394 -0.609068 -0.707109 0.359211 -0.603893 -0.703572 0.374566 -0.700716 -0.707106 -0.0948578 -0.703912 -0.706928 -0.0690017 -0.911401 -0.409269 -0.042991 -0.707477 -0.706656 -0.0106415 -0.70337 -0.705898 0.0835365 -0.728634 -0.669693 -0.14354 -0.861299 -0.472902 -0.185815 -0.690417 -0.697894 -0.190443 -0.643894 -0.703566 -0.300658 -0.766412 -0.557297 -0.319425 -0.856666 -0.387966 -0.340008 -0.66815 -0.706837 -0.232287 -0.677197 -0.70711 -0.203469 -0.537835 -0.705903 -0.460906 -0.573184 -0.707114 -0.414066 -0.577961 -0.706751 -0.408001 -0.641375 -0.645814 -0.414201 -0.789357 -0.387025 -0.476578 -0.620248 -0.706811 -0.340162 -0.633851 -0.707111 -0.313413 -0.589834 -0.394397 -0.704661 -0.478802 -0.706881 -0.520642 -0.537838 -0.7059 -0.460907 -0.366176 -0.689417 -0.624995 -0.406601 -0.707108 -0.57851 -0.434269 -0.706724 -0.558526 -0.359039 -0.705901 -0.610569 -0.253646 -0.705901 -0.661337 -0.253646 -0.705901 -0.661338 -0.25365 0.70589 -0.661348 -0.253647 0.705898 -0.661341 -0.359042 0.705897 -0.610573 -0.359046 0.705887 -0.610581 -0.454647 0.705888 -0.543156 -0.454643 0.705894 -0.543151 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658366 0.705886 -0.261304 -0.692395 0.705886 -0.149376 -0.692394 0.705887 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503753 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314768 0.705909 0.634519 -0.206037 0.705908 0.677674 -0.20604 0.705899 0.677683 -0.0916869 0.705899 0.702354 -0.0916888 0.705887 0.702365 0.0251672 0.705887 0.707877 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141334 0.705902 0.694065 0.328364 0.939692 -0.095689 0.328363 0.939692 -0.0956887 0.0634789 0.244169 -0.967653 0.0634784 0.244169 -0.967653 0.13179 0.667082 -0.733235 0.131789 0.667082 -0.733235 0.250109 0.911252 -0.327209 0.250112 0.911249 -0.327213 0.581198 0.183734 0.792749 0.581198 0.183734 0.792749 0.563589 0.415722 0.713822 0.510348 0.529899 0.677312 0.534658 0.572618 0.621489 0.469157 0.783071 0.40828 0.374177 0.923695 0.0823387 0.374178 0.923694 0.0823384 0.444048 0.842998 0.303606 0.430068 0.762189 0.483848 0.0654602 0 -0.997855 0.0654602 0 -0.997855 0.591264 0 0.806478 0.591264 0 0.806478 0.250113 -0.91125 -0.32721 0.250113 -0.91125 -0.32721 0.131792 -0.667081 -0.733235 0.131793 -0.667081 -0.733235 0.0634794 -0.244169 -0.967653 0.0634789 -0.244168 -0.967653 0.374177 -0.923695 0.0823384 0.374178 -0.923694 0.0823386 0.444048 -0.842998 0.303605 0.436725 -0.793047 0.424674 0.48608 -0.746253 0.454789 0.541853 -0.523233 0.65774 0.581198 -0.183734 0.792749 0.581198 -0.183734 0.792749 0.563589 -0.415722 0.713822 0.479686 -0.584846 0.654107 0.328363 -0.939692 -0.0956888 0.328364 -0.939692 -0.0956889 -0.328363 -0.939692 0.0956887 -0.328363 -0.939692 0.0956887 -0.386736 -0.911251 -0.141625 -0.386737 -0.91125 -0.141625 -0.505057 -0.667081 -0.547649 -0.573368 -0.244168 -0.782068 -0.573368 -0.244168 -0.782068 -0.534662 -0.572618 -0.621487 -0.329049 -0.782098 -0.529196 -0.0634789 -0.244168 0.967653 -0.0634796 -0.244169 0.967653 -0.131793 -0.667081 0.733235 -0.250113 -0.91125 0.32721 -0.250113 -0.91125 0.32721 -0.165675 -0.746253 0.644716 0.0576607 -0.600123 0.797827 -0.591264 0 -0.806478 -0.591264 0 -0.806478 -0.0654602 0 0.997855 -0.0654602 0 0.997855 -0.386737 0.91125 -0.141625 -0.386735 0.911251 -0.141628 -0.505055 0.667082 -0.547651 -0.505055 0.667082 -0.547651 -0.573367 0.244168 -0.782069 -0.573368 0.244169 -0.782068 -0.271369 0.923695 0.270458 -0.271369 0.923694 0.270458 -0.211436 0.842998 0.494621 -0.140221 0.793047 0.592802 -0.165671 0.746254 0.644716 -0.103687 0.523233 0.845858 -0.0643458 0.183734 0.980868 -0.064346 0.183734 0.980868 -0.0918931 0.41572 0.904839 -0.0532036 0.584846 0.809398 -0.328363 0.939692 0.0956887 -0.328363 0.939692 0.0956887 -0.704488 -0.705401 -0.0781415 -0.704488 -0.705401 -0.0781416 -0.675754 -0.705401 -0.213929 -0.675754 -0.705401 -0.213929 -0.62111 -0.705401 -0.341514 -0.621109 -0.705402 -0.341514 -0.54265 -0.705402 -0.456004 -0.54265 -0.705401 -0.456004 -0.443383 -0.705402 -0.55301 -0.443383 -0.705401 -0.55301 -0.327116 -0.705401 -0.628811 -0.327116 -0.705401 -0.628812 -0.198306 -0.705401 -0.680503 -0.198306 -0.705401 -0.680503 -0.0618929 -0.705401 -0.706101 -0.0618924 -0.705402 -0.7061 0.0768941 -0.705402 -0.704624 0.076894 -0.705401 -0.704625 0.212732 -0.705401 -0.676132 0.212732 -0.705402 -0.676131 0.340414 -0.705402 -0.621713 0.340414 -0.705402 -0.621712 0.455043 -0.705402 -0.543456 0.455043 -0.705402 -0.543456 0.552224 -0.705402 -0.444362 0.552224 -0.705401 -0.444362 -0.704458 -0.70321 0.0960984 -0.704458 -0.70321 0.096098 0.645801 -0.70321 -0.297382 0.645801 -0.703211 -0.297382 -0.67887 -0.707106 0.19783 -0.67887 -0.707106 0.197831 0.678869 -0.707106 -0.19783 0.678869 -0.707106 -0.19783 -0.645801 -0.70321 0.297382 -0.645801 -0.70321 0.297383 0.704457 -0.703211 -0.0960983 0.704458 -0.70321 -0.0960993 0.704785 -0.705637 0.0731809 0.704785 -0.705637 0.0731809 0.679875 -0.705637 0.199617 0.679875 -0.705637 0.199617 0.632478 -0.705637 0.319451 0.632478 -0.705637 0.319451 0.564161 -0.705637 0.428718 0.564161 -0.705637 0.428718 0.477184 -0.705637 0.523805 0.477184 -0.705637 0.523805 0.374424 -0.705637 0.601568 0.374424 -0.705637 0.601567 0.259279 -0.705637 0.659432 0.259279 -0.705637 0.659432 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.960066 0 -0.279774 0.960066 3.26227e-07 -0.279774 0.960066 2.48324e-06 -0.279773 0.960066 3.7872e-07 -0.279774 0.960066 7.64482e-07 -0.279774 0.960066 2.43815e-07 -0.279774 0.960066 1.8936e-07 -0.279774 0.960066 -8.01881e-07 -0.279772 0.960065 -3.88006e-08 -0.279776 0.960066 -1.24978e-06 -0.279774 0.960066 0 -0.279775 0.960066 -7.28507e-07 -0.279774 0.960066 -6.90602e-07 -0.279774 0.960066 -1.18988e-06 -0.279774 -0.960066 2.48323e-06 0.279773 -0.960065 -1.51488e-06 0.279775 -0.960066 0 0.279774 -0.960065 2.36684e-06 0.279778 -0.960066 -2.37938e-06 0.279773 -0.960066 0 0.279774 -0.960066 -3.8622e-07 0.279775 -0.960066 1.46095e-06 0.279772 -0.960066 0 0.279774 -0.960066 -2.30809e-07 0.279774 -0.960066 5.42615e-07 0.279774 -0.960066 -1.8936e-08 0.279774 -0.960066 1.6723e-07 0.279774 -0.960066 0 0.279774 -0.960066 -5.01106e-07 0.279774 -0.960064 -3.06341e-06 0.27978 0.184324 0 0.982866 0.184324 0 0.982866 -0.010965 0 0.99994 -0.010965 0 0.99994 -0.205833 0 0.978587 -0.205833 0 0.978587 -0.392791 0 0.919628 -0.392791 0 0.919628 -0.564654 0 0.825328 -0.564654 0 0.825328 -0.714818 0 0.699311 -0.714818 0 0.699311 -0.837512 0 0.54642 -0.837512 0 0.54642 -0.92802 0 0.37253 -0.92802 0 0.37253 -0.982866 0 0.184324 -0.982866 0 0.184324 -0.99994 0 -0.0109653 -0.99994 0 -0.0109653 -0.978587 0 -0.205833 -0.978587 0 -0.205833 -0.919628 0 -0.392791 -0.919628 0 -0.392791 -0.825328 0 -0.564654 -0.825328 0 -0.564654 -0.699311 0 -0.714818 -0.699311 0 -0.714818 -0.54642 0 -0.837512 -0.54642 0 -0.837512 -0.37253 0 -0.92802 -0.37253 0 -0.92802 -0.218624 0.809687 -0.54462 -0.218624 0.809687 -0.54462 -0.320673 0.809687 -0.491504 -0.320673 0.809687 -0.491504 -0.410399 0.809687 -0.419499 -0.410399 0.809687 -0.4195 -0.484354 0.809687 -0.331374 -0.484354 0.809687 -0.331374 -0.539695 0.809687 -0.230514 -0.539695 0.809687 -0.230514 -0.574296 0.809687 -0.120796 -0.574296 0.809687 -0.120796 -0.586827 0.809687 -0.00643518 -0.586827 0.809687 -0.00643495 -0.576807 0.809687 0.108173 -0.576807 0.809687 0.108173 -0.54462 0.809687 0.218624 -0.54462 0.809687 0.218624 -0.491504 0.809687 0.320673 -0.491504 0.809687 0.320673 -0.4195 0.809687 0.410399 -0.419499 0.809687 0.410399 -0.331374 0.809687 0.484354 -0.331374 0.809687 0.484354 -0.230514 0.809687 0.539695 -0.230515 0.809686 0.539695 -0.120796 0.809687 0.574296 -0.120796 0.809687 0.574296 -0.00643517 0.809687 0.586827 -0.00643515 0.809687 0.586827 0.108173 0.809687 0.576807 0.108173 0.809687 0.576807 0.184324 0 0.982866 0.184324 0 0.982866 -0.0109654 0 0.99994 -0.0109654 0 0.99994 -0.205833 0 0.978587 -0.205833 0 0.978587 -0.392791 0 0.919628 -0.392791 0 0.919628 -0.564654 0 0.825328 -0.564654 0 0.825328 -0.714818 0 0.699311 -0.714818 0 0.699311 -0.837512 0 0.54642 -0.837512 0 0.54642 -0.92802 0 0.37253 -0.92802 0 0.37253 -0.982866 0 0.184324 -0.982866 0 0.184324 -0.99994 0 -0.0109654 -0.99994 0 -0.0109654 -0.978587 0 -0.205833 -0.978587 0 -0.205833 -0.919628 0 -0.392791 -0.919628 0 -0.392791 -0.825328 0 -0.564654 -0.825328 0 -0.564654 -0.699311 0 -0.714818 -0.699311 0 -0.714818 -0.546419 0 -0.837512 -0.546419 0 -0.837512 -0.37253 0 -0.92802 -0.37253 0 -0.92802 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.130651 -0.705398 0.696667 0.130651 -0.705398 0.696666 -0.00777238 -0.705398 0.708768 -0.00777229 -0.705394 0.708772 -0.145898 -0.705394 0.693637 -0.145897 -0.705397 0.693635 -0.278415 -0.705397 0.651844 -0.278413 -0.705402 0.651839 -0.400231 -0.705402 0.584999 -0.400231 -0.705401 0.584999 -0.506669 -0.705401 0.495677 -0.506671 -0.705398 0.495679 -0.593637 -0.705398 0.387308 -0.593638 -0.705397 0.387309 -0.657793 -0.705397 0.264054 -0.657791 -0.705399 0.264053 -0.696666 -0.705398 0.130651 -0.696666 -0.705399 0.130651 -0.708768 -0.705398 -0.00777238 -0.708772 -0.705394 -0.00777229 -0.693637 -0.705394 -0.145897 -0.693629 -0.705403 -0.145896 -0.651838 -0.705403 -0.278413 -0.651839 -0.705402 -0.278413 -0.584999 -0.705402 -0.400231 -0.585003 -0.705397 -0.400234 -0.495681 -0.705397 -0.506672 -0.495676 -0.705403 -0.506668 -0.387306 -0.705402 -0.593634 -0.38731 -0.705395 -0.59364 -0.264054 -0.705395 -0.657794 -0.264054 -0.705397 -0.657792 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.348271 0.698073 -0.62562 -0.348271 0.698073 -0.625621 -0.58523 0.698072 -0.412556 -0.585227 0.698074 -0.412555 -0.706273 0.698074 -0.117778 -0.706273 0.698073 -0.117778 -0.687433 0.698073 0.200326 -0.687429 0.698077 0.200324 -0.532434 0.698077 0.478751 -0.532436 0.698074 0.478753 -0.271986 0.698074 0.662357 -0.271986 0.698075 0.662356 0.0423348 0.698075 0.714772 0.042335 0.698074 0.714773 -0.34827 0.698076 -0.625619 -0.348273 0.698071 -0.625622 -0.58523 0.698071 -0.412557 -0.585228 0.698073 -0.412556 -0.706273 0.698074 -0.117778 -0.706273 0.698074 -0.117778 -0.687433 0.698073 0.200326 -0.687434 0.698071 0.200327 -0.532438 0.698072 0.478754 -0.532437 0.698074 0.478752 -0.271986 0.698075 0.662356 -0.271986 0.698074 0.662357 0.0423348 0.698074 0.714773 0.042335 0.698073 0.714774 -0.348271 0.698074 -0.625619 -0.34827 0.698076 -0.625618 -0.585226 0.698075 -0.412555 -0.585228 0.698073 -0.412555 -0.706273 0.698074 -0.117779 -0.706273 0.698073 -0.117779 -0.687433 0.698073 0.200326 -0.687432 0.698074 0.200325 -0.532437 0.698074 0.478753 -0.532436 0.698074 0.478753 -0.271986 0.698075 0.662356 -0.271986 0.698072 0.662358 0.0423349 0.698072 0.714775 0.0423346 0.698073 0.714774 0.0423355 0.69807 0.714777 0.0423339 0.698076 0.714771 -0.142357 0.706861 0.692879 -0.309107 0.581218 0.752754 -0.295432 0.700863 0.649239 -0.450094 0.706117 0.546639 -0.649554 0.486777 0.584062 -0.5628 0.703125 0.434593 -0.654504 0.704874 0.273454 -0.857049 0.450655 0.249754 -0.698944 0.704873 0.120957 -0.70816 0.703125 -0.0642211 -0.861629 0.486775 -0.143686 -0.67329 0.706116 -0.219273 -0.585228 0.698073 -0.412556 -0.34827 0.698074 -0.625621 -0.348273 0.69807 -0.625623 -0.492294 0.706857 -0.507938 -0.701612 0.547286 -0.456311 -0.348271 0.698073 -0.625621 -0.348273 0.69807 -0.625623 -0.58523 0.698071 -0.412556 -0.585227 0.698074 -0.412555 -0.706271 0.698075 -0.117778 -0.706272 0.698075 -0.117778 -0.687431 0.698074 0.200325 -0.687432 0.698074 0.200325 -0.532437 0.698074 0.478753 -0.532436 0.698074 0.478752 -0.271986 0.698074 0.662356 -0.271986 0.698074 0.662356 0.0423347 0.698076 0.714771 0.0423344 0.698077 0.714771 0.0423348 0.698075 0.714772 0.0423352 0.698074 0.714773 -0.14236 0.70686 0.69288 -0.309106 0.581219 0.752754 -0.295432 0.700863 0.64924 -0.450095 0.706117 0.546638 -0.649554 0.486779 0.58406 -0.5628 0.703125 0.434594 -0.654505 0.704873 0.273454 -0.857047 0.450658 0.249754 -0.698942 0.704876 0.120956 -0.708158 0.703128 -0.0642207 -0.861628 0.486777 -0.143686 -0.673289 0.706117 -0.219272 -0.585227 0.698075 -0.412554 -0.34827 0.698074 -0.62562 -0.348271 0.698073 -0.625621 -0.492294 0.706859 -0.507934 -0.701608 0.547293 -0.456309 -0.373093 0.69475 -0.614918 -0.373096 0.694745 -0.614921 -0.630572 0.694744 -0.345991 -0.630571 0.694745 -0.345991 -0.719086 0.694745 0.0156503 -0.719081 0.69475 0.0156493 -0.614919 0.694749 0.373093 -0.614923 0.694744 0.373097 -0.34599 0.694745 0.630571 -0.34599 0.694745 0.630571 0.0156494 0.694747 0.719084 0.0156493 0.694748 0.719083 -0.373096 0.694745 -0.614922 -0.373095 0.694747 -0.61492 -0.63057 0.694747 -0.345989 -0.630569 0.694748 -0.345989 -0.719082 0.694749 0.0156488 -0.719085 0.694746 0.0156494 -0.61492 0.694747 0.373094 -0.61492 0.694747 0.373095 -0.345989 0.694747 0.63057 -0.345989 0.694748 0.630569 0.0156495 0.694749 0.719082 0.0156493 0.69475 0.719081 -0.373095 0.694747 -0.61492 -0.373095 0.694747 -0.61492 -0.63057 0.694747 -0.345989 -0.630569 0.694748 -0.345989 -0.719084 0.694747 0.0156496 -0.719083 0.694748 0.0156493 -0.614919 0.694749 0.373094 -0.614922 0.694745 0.373096 -0.34599 0.694744 0.630573 -0.345989 0.694748 0.630569 0.0156488 0.694749 0.719082 0.0156494 0.694746 0.719085 -0.373097 0.694743 -0.614923 -0.373093 0.69475 -0.614918 -0.630568 0.694749 -0.345988 -0.630568 0.694748 -0.345989 -0.719084 0.694747 0.0156493 -0.719084 0.694747 0.0156494 -0.614921 0.694746 0.373095 -0.614922 0.694746 0.373095 -0.345991 0.694744 0.630572 -0.345991 0.694742 0.630574 0.0156504 0.694741 0.719089 0.0156494 0.694746 0.719085 -0.373094 0.694748 -0.614919 -0.373095 0.694747 -0.61492 -0.630569 0.694747 -0.34599 -0.630571 0.694745 -0.34599 -0.719086 0.694745 0.0156496 -0.719085 0.694746 0.0156494 -0.614922 0.694745 0.373095 -0.614922 0.694745 0.373095 -0.345991 0.694744 0.630572 -0.345992 0.694742 0.630574 0.0156504 0.694742 0.719089 0.0156494 0.694746 0.719085 -0.373095 0.694747 -0.61492 -0.373094 0.694749 -0.614919 -0.630567 0.69475 -0.345988 -0.630567 0.69475 -0.345988 -0.719082 0.694749 0.0156489 -0.719085 0.694746 0.0156494 -0.614921 0.694745 0.373096 -0.614918 0.69475 0.373093 -0.345989 0.694749 0.630568 -0.345989 0.694747 0.63057 0.0156496 0.694745 0.719086 0.0156494 0.694746 0.719085 0.688076 0.706222 -0.166736 0.688077 0.706222 -0.166737 0.65771 0.706222 -0.262045 0.65771 0.706222 -0.262045 0.555599 0.697264 -0.452916 0.555598 0.697266 -0.452914 0.291434 0.697266 -0.654894 0.291435 0.697264 -0.654896 0.0169866 0.702504 -0.711477 -0.0418669 0.532248 -0.845553 -0.14775 0.706154 -0.692471 -0.447286 0.70431 -0.551256 -0.447286 0.70431 -0.551256 -0.570193 0.70431 -0.42288 -0.570193 0.70431 -0.42288 -0.682325 0.699238 -0.213304 -0.682325 0.699238 -0.213304 -0.710061 0.699238 0.0829444 -0.710061 0.699238 0.0829446 -0.614793 0.699238 0.364824 -0.614792 0.699239 0.364823 -0.413023 0.699239 0.583504 -0.413023 0.699239 0.583504 -0.233183 0.706223 0.668487 -0.233183 0.706223 0.668487 -0.136644 0.706223 0.694678 -0.136644 0.706223 0.694678 0.0468854 0.700707 0.711906 0.0468854 0.700707 0.711906 0.306679 0.700707 0.644172 0.306679 0.700707 0.644172 0.523043 0.700707 0.485217 0.523044 0.700707 0.485217 0.599317 0.707107 0.375259 0.548971 0.700494 0.456003 0.716232 0.129603 0.685722 0.510933 0.616928 0.598622 0.419701 0.706913 0.56932 0.507512 0.700707 0.501439 0.507512 0.700707 0.501439 0.656904 0.700707 0.278364 0.656904 0.700707 0.278364 0.713273 0.700707 0.0158695 0.713272 0.700707 0.0158696 0.488436 0.706222 0.512523 0.488436 0.706223 0.512523 0.555793 0.706223 0.438571 0.555792 0.706223 0.438571 0.661826 0.699239 0.270281 0.661827 0.699238 0.270281 0.714533 0.699238 -0.0225573 0.714533 0.699238 -0.0225572 0.643461 0.699238 -0.311488 0.64346 0.699239 -0.311487 0.460921 0.699239 -0.546459 0.460922 0.699237 -0.54646 0.253759 0.704308 -0.662991 0.0585491 0.70555 -0.706237 0.0611885 0.844591 -0.531905 0.14621 0.706928 -0.692009 0.253759 0.704309 -0.66299 -0.10424 0.703805 -0.702704 -0.104238 0.703807 -0.702702 -0.695519 0.706222 0.132301 -0.695518 0.706223 0.132301 -0.669931 0.706223 0.229002 -0.669931 0.706222 0.229002 -0.593087 0.700707 0.396557 -0.593086 0.700707 0.396557 -0.40453 0.700707 0.587678 -0.40453 0.700708 0.587677 -0.158688 0.700708 0.695576 -0.158688 0.700707 0.695577 -0.169878 0.699585 0.694063 -0.169878 0.699585 0.694062 -0.180503 0.700707 0.690238 -0.180503 0.700707 0.690238 0.0873824 0.700707 0.708078 0.087382 0.700707 0.708077 0.342893 0.700707 0.625647 0.342893 0.700707 0.625647 -0.19964 0.706222 0.67926 -0.19964 0.706223 0.67926 -0.101917 0.706222 0.700616 -0.101917 0.706222 0.700616 0.703708 0.699238 0.125941 0.703709 0.699237 0.12594 0.591487 0.699237 0.40151 0.591486 0.699238 0.401509 0.376801 0.699238 0.607525 0.0746332 0.701412 0.708838 0.104924 0.632522 0.767403 0.218815 0.706937 0.672577 0.376802 0.699238 0.607525 0.701044 0.70431 -0.111733 0.701043 0.704311 -0.111733 0.65132 0.704311 -0.282361 0.651321 0.70431 -0.282362 0.521433 0.698433 -0.490203 0.521433 0.698433 -0.490202 0.263019 0.698434 -0.665591 0.263019 0.698432 -0.665593 -0.0454829 0.698432 -0.714229 -0.0454823 0.698434 -0.714228 -0.462335 0.706224 -0.536185 -0.462336 0.706222 -0.536187 -0.533288 0.706222 -0.465677 -0.533288 0.706222 -0.465677 -0.639973 0.700707 -0.315349 -0.639973 0.700707 -0.315349 -0.711209 0.700707 -0.0564942 -0.711208 0.700708 -0.0564948 -0.681731 0.700708 0.21036 -0.681731 0.700707 0.210361 -0.686014 0.699585 0.199912 -0.686014 0.699585 0.199912 -0.688014 0.700708 0.188799 -0.688015 0.700707 0.188799 -0.569522 0.700707 0.429714 -0.569522 0.700708 0.429714 -0.370379 0.700707 0.609777 -0.370379 0.700707 0.609777 -0.688076 0.706222 0.166736 -0.688076 0.706223 0.166736 -0.65771 0.706223 0.262045 -0.65771 0.706222 0.262045 0.242787 0.699239 0.672398 0.3627 0.456375 0.812509 0.14775 0.706155 0.69247 -0.0519745 0.699238 0.712997 -0.564984 0.699237 0.438019 -0.564983 0.699239 0.438017 -0.337731 0.69924 0.63008 -0.337731 0.699238 0.630082 -0.163716 0.706684 0.688328 -0.0198438 0.555698 0.831147 0.447286 0.704311 0.551255 0.447286 0.70431 0.551256 0.570193 0.70431 0.42288 0.570193 0.70431 0.42288 0.682325 0.699238 0.213304 0.682325 0.699238 0.213304 0.710061 0.699238 -0.0829444 0.710061 0.699238 -0.0829446 0.614793 0.699238 -0.364824 0.614792 0.699239 -0.364823 0.413023 0.699239 -0.583504 0.413023 0.699239 -0.583504 0.233183 0.706223 -0.668487 0.233183 0.706223 -0.668487 0.136644 0.706223 -0.694678 0.136644 0.706223 -0.694678 -0.0571084 0.699695 -0.712156 -0.0571084 0.699695 -0.712156 -0.516136 0.699585 -0.49415 -0.516137 0.699585 -0.49415 -0.507512 0.700707 -0.501439 -0.507512 0.700707 -0.501438 -0.656904 0.700707 -0.278364 -0.656904 0.700707 -0.278364 -0.713272 0.700708 -0.0158695 -0.713272 0.700707 -0.0158694 -0.488436 0.706222 -0.512523 -0.488436 0.706223 -0.512523 -0.555793 0.706223 -0.438571 -0.555792 0.706223 -0.438571 -0.661826 0.699239 -0.270281 -0.661827 0.699238 -0.270281 -0.714533 0.699238 0.0225573 -0.714531 0.69924 0.0225565 -0.643459 0.69924 0.311487 -0.64346 0.699239 0.311487 -0.460921 0.699239 0.546459 -0.460921 0.699239 0.546458 -0.253758 0.704311 0.662988 -0.253758 0.704309 0.66299 -0.0811286 0.704309 0.705242 -0.0811286 0.704309 0.705243 0.711841 0.699238 0.0659366 0.711841 0.699239 0.0659367 0.623342 0.699239 0.350014 0.623342 0.699239 0.350014 0.507858 0.706685 0.492622 0.477993 0.599305 0.64215 0.10424 0.703805 0.702704 0.180443 0.565719 0.804613 0.247376 0.706156 0.663437 0.396534 0.702506 0.590971 0.695519 0.706222 -0.132301 0.695519 0.706222 -0.132301 0.669931 0.706223 -0.229002 0.669931 0.706223 -0.229002 0.593086 0.700707 -0.396557 0.593086 0.700707 -0.396557 0.40453 0.700707 -0.587678 0.40453 0.700708 -0.587677 0.158688 0.700708 -0.695576 0.158688 0.700707 -0.695577 0.169878 0.699585 -0.694063 0.169878 0.699585 -0.694062 0.185296 0.701184 -0.688481 0.185296 0.701185 -0.68848 -0.0721747 0.701185 -0.709317 -0.0721747 0.701185 -0.709317 0.19964 0.706223 -0.679259 0.19964 0.706223 -0.679259 0.101917 0.706223 -0.700616 0.101917 0.706223 -0.700616 -0.074633 0.701412 -0.708837 -0.0746331 0.701412 -0.708838 -0.701044 0.70431 0.111733 -0.701043 0.704311 0.111733 -0.651321 0.704311 0.282361 -0.651321 0.70431 0.282362 0.298817 0.699239 0.64944 -0.525889 0.699238 0.484259 -0.525889 0.699238 0.484259 -0.283199 0.699238 0.656403 -0.283199 0.699239 0.656402 0.00855015 0.699239 0.714837 0.00855033 0.699238 0.714837 0.176751 0.706938 0.684835 0.351259 0.616062 0.705042 0.462335 0.706224 0.536185 0.462336 0.706222 0.536187 0.533288 0.706222 0.465677 0.533287 0.706223 0.465676 0.639971 0.700708 0.315349 0.639972 0.700707 0.315349 0.711209 0.700707 0.0564942 0.711209 0.700707 0.0564943 0.681732 0.700707 -0.210361 0.681731 0.700707 -0.21036 0.686014 0.699585 -0.199912 0.686014 0.699585 -0.199912 0.688014 0.700708 -0.188799 0.688015 0.700707 -0.188799 0.569522 0.700707 -0.429714 0.569522 0.700708 -0.429714 0.370379 0.700707 -0.609777 0.370379 0.700708 -0.609777 -0.373094 0.694747 -0.614921 -0.373095 0.694746 -0.614921 -0.63057 0.694746 -0.345989 -0.63057 0.694747 -0.345989 -0.719084 0.694747 0.0156492 -0.719084 0.694747 0.015649 -0.614921 0.694747 0.373094 -0.614921 0.694747 0.373095 -0.345989 0.694746 0.630571 -0.34599 0.694747 0.63057 0.0156492 0.694747 0.719084 0.0156496 0.694746 0.719084 -0.373095 0.694747 -0.614921 -0.373095 0.694747 -0.614921 -0.630571 0.694746 -0.345989 -0.630569 0.694747 -0.34599 -0.719084 0.694747 0.0156492 -0.719084 0.694747 0.0156496 -0.61492 0.694747 0.373095 -0.61492 0.694747 0.373095 -0.34599 0.694747 0.630569 -0.34599 0.694746 0.63057 0.0156495 0.694747 0.719084 0.0156493 0.694747 0.719084 -0.373095 0.694746 -0.614921 -0.373095 0.694746 -0.614921 -0.630571 0.694746 -0.345989 -0.63057 0.694746 -0.345989 -0.719085 0.694746 0.0156492 -0.719084 0.694747 0.0156485 -0.61492 0.694747 0.373095 -0.61492 0.694747 0.373095 -0.345989 0.694747 0.63057 -0.34599 0.694747 0.63057 0.0156492 0.694747 0.719084 0.0156496 0.694747 0.719084 -0.34827 0.698074 -0.62562 -0.348272 0.698074 -0.62562 -0.585229 0.698073 -0.412554 -0.585227 0.698074 -0.412555 -0.706273 0.698074 -0.117779 -0.706273 0.698074 -0.117778 -0.687432 0.698074 0.200326 -0.687432 0.698074 0.200325 -0.532438 0.698074 0.478752 -0.532437 0.698074 0.478753 -0.271987 0.698074 0.662357 -0.271986 0.698073 0.662357 0.0423372 0.698073 0.714774 0.0423348 0.698074 0.714773 -0.373094 0.694747 -0.614921 -0.373095 0.694746 -0.614921 -0.63057 0.694746 -0.345989 -0.63057 0.694746 -0.345989 -0.719084 0.694747 0.0156495 -0.719084 0.694747 0.0156494 -0.614921 0.694747 0.373094 -0.614921 0.694747 0.373095 -0.345989 0.694746 0.630571 -0.34599 0.694747 0.63057 0.0156492 0.694747 0.719084 0.0156496 0.694747 0.719084 0.0156496 0.694747 0.719084 0.0156491 0.694747 0.719084 -0.34599 0.694747 0.63057 -0.305948 0.67405 0.672349 -0.450093 0.706116 0.546642 -0.614921 0.694746 0.373095 -0.593046 0.662253 0.457949 -0.654505 0.704873 0.273453 -0.699051 0.704846 0.120496 -0.699039 0.704776 0.120974 -0.708025 0.703218 -0.0646857 -0.373094 0.694747 -0.614921 -0.373095 0.694746 -0.614921 -0.597957 0.700862 -0.388897 -0.63771 0.686215 -0.349907 -0.673291 0.706116 -0.21927 -0.70816 0.703125 -0.0642225 -0.373095 0.694747 -0.614921 -0.373095 0.694747 -0.614921 -0.630571 0.694746 -0.345989 -0.63057 0.694747 -0.34599 -0.719084 0.694747 0.0156492 -0.719084 0.694747 0.0156496 -0.61492 0.694746 0.373096 -0.614921 0.694747 0.373094 -0.345989 0.694747 0.63057 -0.345989 0.694747 0.63057 0.0156495 0.694747 0.719084 0.0156494 0.694747 0.719084 -0.373096 0.694746 -0.61492 -0.373095 0.694747 -0.61492 -0.630569 0.694747 -0.34599 -0.63057 0.694747 -0.34599 -0.719084 0.694747 0.0156492 -0.719084 0.694747 0.0156496 -0.614921 0.694746 0.373095 -0.614921 0.694747 0.373095 -0.34599 0.694747 0.63057 -0.345989 0.694746 0.63057 0.0156504 0.694746 0.719085 0.015649 0.694747 0.719084 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.273455 0.704871 -0.654507 -0.273454 0.704874 -0.654504 -0.412238 0.704874 -0.577245 -0.412238 0.704874 -0.577245 -0.486228 0.706991 -0.513563 -0.699742 0.352298 -0.621488 -0.541594 0.705782 -0.456671 -0.600496 0.706543 -0.374435 -0.87048 0.118904 -0.477626 -0.638631 0.706556 -0.304841 -0.68221 0.704872 -0.194283 -0.682207 0.704875 -0.194282 -0.699199 0.707068 -0.105716 -0.861949 0.504925 -0.045761 -0.708262 0.70544 -0.0268286 -0.698943 0.704875 0.120956 -0.698942 0.704875 0.120956 -0.654503 0.704875 0.273453 -0.654504 0.704874 0.273454 -0.577245 0.704874 0.412238 -0.577246 0.704873 0.412239 -0.471042 0.704873 0.530353 -0.471041 0.704874 0.530352 -0.378438 0.706671 0.59783 -0.476957 0.130003 0.869259 -0.309233 0.706418 0.63667 -0.24907 0.706953 0.661953 -0.261423 0.298316 0.917968 -0.173647 0.7059 0.686696 -0.0712104 0.706369 0.704253 -0.0525094 0.137841 0.989062 0.00808455 0.706701 0.707466 0.120957 0.704871 0.698947 0.120957 0.704871 0.698947 0.170522 0 0.985354 0.170522 0 0.985354 -0.0530155 0 0.998594 -0.0530155 0 0.998594 -0.273894 0 0.96176 -0.273894 0 0.96176 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.664062 0 0.747677 -0.664062 0 0.747677 -0.813787 0 0.581164 -0.813787 0 0.581164 -0.922704 0 0.385508 -0.922704 0 0.385508 -0.985354 0 0.170522 -0.985354 0 0.170522 -0.998594 0 -0.0530155 -0.998594 0 -0.0530155 -0.96176 0 -0.273894 -0.96176 0 -0.273894 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.747677 0 -0.664062 -0.747677 0 -0.664062 -0.581164 0 -0.813787 -0.581164 0 -0.813787 -0.385508 0 -0.922704 -0.385508 0 -0.922704 -0.373093 0.694747 -0.614921 -0.373095 0.694747 -0.614921 -0.63057 0.694747 -0.345989 -0.63057 0.694746 -0.345989 -0.719084 0.694747 0.0156495 -0.719084 0.694747 0.0156493 -0.614921 0.694747 0.373095 -0.61492 0.694747 0.373095 -0.345989 0.694747 0.63057 -0.345989 0.694747 0.63057 0.0156492 0.694747 0.719084 0.015649 0.694747 0.719084 -0.722324 0 -0.691554 -0.722324 0 -0.691554 -0.0657166 0 -0.997838 -0.0799324 -0.00686625 -0.996777 -0.26606 0 -0.963956 0.329359 0 -0.944205 0.329359 0 -0.944205 0.193002 0 -0.981198 0.193002 0 -0.981198 0.577745 0 -0.816217 0.577745 0 -0.816217 0.859983 0 -0.510322 0.859983 0 -0.510322 0.993246 0 -0.116024 0.993246 0 -0.116024 0.954449 0 0.298374 0.954449 0 0.298374 0.630076 0 0.776534 0.630076 0 0.776534 0.80321 0 0.595696 0.80321 0 0.595696 0.407626 0 0.913149 0.407626 0 0.913149 -0.971873 0 0.235507 -0.971873 0 0.235507 -0.928982 0 0.370125 -0.928982 0 0.370125 -0.711351 0 -0.702837 -0.711351 0 -0.702837 -0.920745 0 -0.390166 -0.920745 0 -0.390166 -0.999753 0 -0.0222434 -0.999753 0 -0.0222434 -0.653026 0 -0.757336 -0.653026 0 -0.757336 -0.753241 0 -0.657744 -0.753241 0 -0.657744 -0.417992 0 -0.908451 -0.445817 0.0226846 -0.894837 -0.0119561 -0.0259748 -0.999591 -0.0635428 0.0173209 -0.997829 0.396089 -0.0165917 -0.918062 0.367499 0.0082971 -0.929987 0.7356 -0.00793093 -0.677369 0.728589 0 -0.684951 0.987536 0 -0.157395 0.987536 0 -0.157395 0.917493 0 -0.397752 0.917493 0 -0.397752 0.982488 0 0.186324 0.984329 0.00793137 0.176162 0.80956 -0.00829685 0.586978 0.827268 0.0165918 0.561562 0.527028 -0.0136552 0.849738 0.482413 0.0204792 0.875705 0.309377 0 0.950939 -0.281981 0 0.95942 -0.281981 0 0.95942 -0.143953 0 0.989585 -0.143953 0 0.989585 -0.96435 0 0.264629 -0.96435 0 0.264629 -0.798266 0 0.602305 -0.798266 0 0.602305 -0.519139 0 0.85469 -0.519139 0 0.85469 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.897012 0 -0.442007 -0.897012 0 -0.442007 -0.99686 0 -0.0791846 -0.99686 0 -0.0791846 -0.955544 0 0.29485 -0.955544 0 0.29485 -0.982385 0 0.186869 -0.982385 0 0.186869 -0.946244 0 0.323454 -0.946244 0 0.323454 -0.995737 0 -0.0922334 -0.993026 -0.0179043 -0.116529 -0.871834 0.0158423 -0.489545 -0.833304 -0.0316633 -0.551908 -0.596876 0.0275255 -0.801861 -0.557181 0 -0.830391 -0.349374 0 -0.936983 -0.218692 0.0350249 -0.975165 -0.146735 0 -0.989176 0.35746 0 -0.933928 0.35746 0 -0.933928 0.114283 0 -0.993448 0.114283 0 -0.993448 0.644746 0 -0.764397 0.644746 0 -0.764397 0.900085 0 -0.435715 0.900085 0 -0.435715 0.999502 0 -0.0315536 0.999502 0 -0.0315536 0.925775 0 0.378074 0.925775 0 0.378074 0.689891 0 0.723913 0.689891 0 0.723913 0.785029 0 0.619459 0.785029 0 0.619459 -0.253 0 0.967466 -0.259888 -0.00343327 0.965633 0.122478 0.00356092 0.992465 0.101227 -0.00712156 0.994838 0.4806 0.00737643 0.876909 0.468063 0 0.883695 -0.237741 0 0.971328 -0.237741 0 0.971328 -0.831295 0 0.555831 -0.831295 0 0.555831 -0.567006 0 0.823714 -0.567006 0 0.823714 -0.222424 0 0.97495 -0.222424 0 0.97495 -0.329359 0 0.944205 -0.329359 0 0.944205 -0.193002 0 0.981198 -0.193002 0 0.981198 -0.577745 0 0.816217 -0.577745 0 0.816217 -0.859983 0 0.510322 -0.859983 0 0.510322 -0.993246 0 0.116024 -0.993246 0 0.116024 -0.954449 0 -0.298374 -0.954449 0 -0.298374 -0.630076 0 -0.776534 -0.630076 0 -0.776534 -0.80321 0 -0.595696 -0.80321 0 -0.595696 -0.407626 0 -0.913149 -0.339407 0.0350252 -0.939987 -0.20867 0 -0.977986 0.0727027 0 -0.997354 0.0238531 0.0357806 -0.999075 0.471969 -0.0439433 -0.880519 0.406471 0.0219941 -0.913399 0.790152 -0.0199553 -0.612586 0.775095 0 -0.631845 0.971873 0 -0.235507 0.971873 0 -0.235507 0.928982 0 -0.370125 0.928982 0 -0.370125 0.711351 0 0.702837 0.711351 0 0.702837 0.920745 0 0.390166 0.920745 0 0.390166 0.999753 0 0.0222434 0.999753 0 0.0222434 0.722324 0 0.691554 0.722324 0 0.691554 0.0657166 0 0.997838 0.0799324 0.00686625 0.996777 0.429845 -0.00635462 0.90288 0.449059 0.00317756 0.893496 0.733115 -0.0033053 0.680096 0.737948 0 0.674857 0.653026 0 0.757336 0.653026 0 0.757336 0.753242 0 0.657744 0.753242 0 0.657744 0.445932 0 0.895067 0.445932 0 0.895067 -0.987536 0 0.157395 -0.987536 0 0.157395 -0.917493 0 0.397752 -0.917493 0 0.397752 -0.98436 0 -0.176168 -0.98246 -0.00756464 -0.186318 -0.827361 0.00719671 -0.561625 -0.809504 -0.0143921 -0.586938 -0.527028 0.0136553 -0.849738 -0.482413 -0.0204792 -0.875705 -0.13544 0.0193726 -0.990596 -0.104711 0 -0.994503 0.281981 0 -0.95942 0.281981 0 -0.95942 0.143953 0 -0.989585 0.143953 0 -0.989585 0.96435 0 -0.264629 0.96435 0 -0.264629 0.798266 0 -0.602305 0.798266 0 -0.602305 0.519139 0 -0.85469 0.519139 0 -0.85469 0.960066 0 -0.279774 0.960066 0 -0.279774 0.897011 0 0.442007 0.897011 0 0.442007 0.99686 0 0.0791846 0.99686 0 0.0791846 0.955544 0 -0.29485 0.955544 0 -0.29485 0.982385 0 -0.186869 0.982385 0 -0.186869 0.946244 0 -0.323454 0.946244 0 -0.323454 0.995539 0.0199553 0.0922152 0.993185 0 0.116548 0.871834 -0.0158423 0.489545 0.833304 0.0316633 0.551908 0.717792 0 0.696258 0.557182 0 0.830391 0.494412 0.0412481 0.868248 0.349374 0 0.936983 -0.35746 0 0.933928 -0.35746 0 0.933928 -0.114283 0 0.993448 -0.114283 0 0.993448 -0.644746 0 0.764397 -0.644746 0 0.764397 -0.900085 0 0.435715 -0.900085 0 0.435715 -0.999502 0 0.0315536 -0.999502 0 0.0315536 -0.925775 0 -0.378074 -0.925775 0 -0.378074 -0.689891 0 -0.723913 -0.689891 0 -0.723913 -0.785029 0 -0.619459 -0.785029 0 -0.619459 0.259889 0 -0.965638 0.252999 0.00330544 -0.967461 -0.101229 -0.00317745 -0.994858 -0.108318 0 -0.994116 0.237741 0 -0.971328 0.237741 0 -0.971328 0.831295 0 -0.555831 0.831295 0 -0.555831 0.567006 0 -0.823714 0.567006 0 -0.823714 0.222424 0 -0.97495 0.222424 0 -0.97495 -0.486394 0 -0.873739 -0.486394 0 -0.873739 -0.817328 0 -0.576173 -0.817328 0 -0.576173 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.379855 0 0.925046 -0.379855 0 0.925046 0.059125 0 0.998251 0.059125 0 0.998251 -0.486394 0 -0.87374 -0.518575 0.0239944 -0.854695 -0.695965 0 -0.718076 -0.8383 0 -0.54521 -0.875996 0.0400442 -0.480654 -0.950846 0 -0.309665 -0.995913 0 -0.0903164 -0.998607 0.048081 0.0217329 -0.985354 0 0.170521 -0.922704 0 0.385508 -0.853953 0.0480811 0.518125 -0.791487 0 0.611186 -0.635642 0 0.771984 -0.480653 0.0400446 0.875996 0.0591253 0 0.998251 0.0217518 0.0239941 0.999475 -0.201257 0 0.979539 -0.414178 0 0.910196 -0.486393 0 -0.87374 -0.486393 0 -0.87374 -0.817328 0 -0.576173 -0.817328 0 -0.576173 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.379855 0 0.925046 -0.379855 0 0.925046 0.0591246 0 0.998251 0.0591246 0 0.998251 -0.486393 0 -0.87374 -0.518574 0.0239943 -0.854696 -0.695962 0 -0.718078 -0.8383 0 -0.545209 -0.875996 0.0400442 -0.480653 -0.950846 0 -0.309665 -0.995913 0 -0.0903167 -0.998607 0.0480811 0.0217326 -0.985354 0 0.170521 -0.922704 0 0.38551 -0.853952 0.0480808 0.518125 -0.791487 0 0.611186 -0.635641 0 0.771985 -0.480654 0.040044 0.875996 0.0591236 0 0.998251 0.0217508 0.0239936 0.999475 -0.201253 0 0.979539 -0.414179 0 0.910195 -0.486395 0 -0.873739 -0.486395 0 -0.873739 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591247 0 0.998251 0.0591247 0 0.998251 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.817327 0 -0.576173 -0.817327 0 -0.576173 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.379855 0 0.925046 -0.379855 0 0.925046 0.0591247 0 0.998251 0.0591247 0 0.998251 -0.486394 0 -0.873739 -0.518575 0.0239939 -0.854696 -0.817163 -0.0200484 -0.576057 -0.8383 0 -0.545209 -0.950847 0 -0.309661 -0.98587 -0.0321115 -0.164404 -0.995913 0 -0.0903181 -0.985354 0 0.170522 -0.959439 -0.036138 0.279591 -0.922705 0 0.385508 -0.791488 0 0.611185 -0.743216 -0.0321128 0.66828 -0.635639 0 0.771987 -0.379855 0 0.925046 -0.414058 -0.0239939 0.909934 0.0591017 0.0279051 0.997862 0.0217576 0 0.999763 -0.486394 0 -0.87374 -0.518576 -0.0239948 -0.854695 -0.695968 0 -0.718073 -0.838299 0 -0.545211 -0.875996 -0.0400452 -0.480653 -0.950847 0 -0.309661 -0.995913 0 -0.0903182 -0.998607 -0.0480813 0.0217319 -0.985354 0 0.170521 -0.922704 0 0.385508 -0.853952 -0.0480814 0.518125 -0.791486 0 0.611187 -0.635643 0 0.771983 -0.480654 -0.0400448 0.875996 -0.414178 0 0.910196 -0.201253 0 0.979539 0.0217518 -0.0239937 0.999475 0.0591247 0 0.998251 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217581 -0.999763 0 0.0217581 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481039 0 0.876699 -0.481039 0 0.876699 0.021759 0 0.999763 0.021759 0 0.999763 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217577 -0.999763 0 0.0217577 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481039 0 0.876699 -0.481039 0 0.876699 0.021759 0 0.999763 0.021759 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217581 -0.999763 0 0.0217581 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217581 0 0.999763 0.0217581 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.021759 -0.999763 0 0.021759 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.0217575 -0.999763 0 0.0217575 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217575 0 0.999763 0.0217575 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.0217575 -0.999763 0 0.0217575 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217579 0 0.999763 0.0217579 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.0217575 -0.999763 0 0.0217575 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217575 0 0.999763 0.0217575 0 0.999763 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.817328 0 -0.576172 -0.817328 0 -0.576172 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.743601 0 0.668624 -0.743601 0 0.668624 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591279 0 0.99825 0.0591279 0 0.99825 -0.518723 0 -0.854943 -0.518723 0 -0.854943 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217579 -0.999763 0 0.0217579 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217575 0 0.999763 0.0217575 0 0.999763 -0.518724 0 -0.854942 -0.482991 -0.118065 -0.867629 -0.833954 0.10169 -0.542383 -0.817328 0 -0.576173 -0.950847 0 -0.309661 -0.977272 0.135571 -0.16297 -0.995913 0 -0.0903185 -0.985354 0 0.170523 -0.948878 0.152218 0.276514 -0.922705 0 0.385507 -0.743599 0 0.668626 -0.775469 0.200171 0.598815 -0.635637 0 0.771988 -0.414178 0 0.910196 -0.378477 0.0850949 0.921691 0.0216447 -0.10169 0.994581 0.059124 0 0.998251 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.0217575 -0.999763 0 0.0217575 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217579 0 0.999763 0.0217579 0 0.999763 -0.518726 0 -0.854941 -0.518726 0 -0.854941 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.999763 0 0.0217575 -0.999763 0 0.0217575 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217592 0 0.999763 0.0217592 0 0.999763 -0.518723 0 -0.854943 -0.518723 0 -0.854943 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217579 -0.999763 0 0.0217579 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217575 0 0.999763 0.0217575 0 0.999763 -0.516137 -0.699584 -0.49415 -0.516137 -0.699585 -0.49415 -0.0468856 -0.700708 -0.711906 -0.523044 -0.700706 -0.485217 -0.523044 -0.700707 -0.485217 -0.315423 -0.701643 -0.63891 -0.319078 -0.670074 -0.670217 -0.188143 -0.707071 -0.681654 -0.0468854 -0.700707 -0.711907 0.136644 -0.706223 -0.694678 0.136644 -0.706223 -0.694678 0.233183 -0.706223 -0.668487 0.233183 -0.706223 -0.668487 0.413023 -0.699239 -0.583504 0.413024 -0.699238 -0.583505 0.614793 -0.699238 -0.364824 0.614791 -0.69924 -0.364823 0.710059 -0.69924 -0.0829442 0.710063 -0.699236 -0.0829438 0.682327 -0.699236 0.213305 0.682326 -0.699237 0.213304 0.570193 -0.704309 0.422881 0.570193 -0.70431 0.42288 0.447286 -0.70431 0.551256 0.447285 -0.704311 0.551255 0.289574 -0.703807 0.648693 0.289574 -0.703805 0.648695 -0.65771 -0.706222 0.262045 -0.65771 -0.706223 0.262045 -0.688076 -0.706223 0.166736 -0.688076 -0.706223 0.166736 -0.713272 -0.700707 -0.0158695 -0.713272 -0.700708 -0.0158695 -0.656904 -0.700707 -0.278364 -0.656904 -0.700707 -0.278364 -0.507512 -0.700707 -0.501438 -0.507512 -0.700707 -0.501439 -0.533288 -0.706222 -0.465676 -0.533288 -0.706222 -0.465677 -0.462336 -0.706222 -0.536187 -0.462334 -0.706225 -0.536184 -0.298817 -0.699241 -0.649439 -0.298817 -0.69924 -0.649439 -0.00855015 -0.69924 -0.714836 -0.00854982 -0.699238 -0.714838 0.283199 -0.699237 -0.656403 0.283198 -0.69924 -0.656401 0.525888 -0.699239 -0.484259 0.525889 -0.699239 -0.484259 0.651321 -0.70431 -0.282361 0.651322 -0.704309 -0.282362 0.701045 -0.704309 -0.111734 0.701045 -0.704309 -0.111734 0.703144 -0.698432 0.133348 0.703142 -0.698434 0.133347 0.579402 -0.698434 0.4201 0.579402 -0.698433 0.4201 0.345323 -0.698433 0.626852 0.345324 -0.698432 0.626852 -0.101917 -0.706222 0.700616 -0.101917 -0.706222 0.700616 -0.19964 -0.706223 0.679259 -0.19964 -0.706223 0.679259 -0.370379 -0.700709 0.609776 -0.37038 -0.700707 0.609777 -0.569522 -0.700708 0.429714 -0.569522 -0.700707 0.429714 -0.688015 -0.700707 0.188799 -0.688015 -0.700707 0.188799 -0.686015 -0.699584 0.199913 -0.686015 -0.699585 0.199913 -0.681732 -0.700706 0.21036 -0.68173 -0.700709 0.21036 -0.711207 -0.700709 -0.056494 -0.711209 -0.700707 -0.0564946 -0.639972 -0.700707 -0.315349 -0.639972 -0.700707 -0.315349 -0.669931 -0.706223 0.229002 -0.669931 -0.706223 0.229002 -0.695518 -0.706223 0.132301 -0.695519 -0.706223 0.132301 -0.711841 -0.699239 -0.0659365 -0.711842 -0.699238 -0.0659367 -0.623343 -0.699238 -0.350015 -0.623342 -0.699239 -0.350014 -0.426861 -0.699239 -0.573458 -0.426862 -0.699238 -0.573459 -0.156436 -0.699237 -0.697564 -0.156436 -0.699236 -0.697565 0.281989 -0.705927 -0.64973 0.157076 -0.89828 -0.410389 0.198205 -0.706764 -0.679116 0.135879 -0.706718 -0.694324 0.0496458 -0.900714 -0.431566 0.0479438 -0.706008 -0.70658 0.460922 -0.699237 -0.546459 0.460923 -0.699237 -0.54646 0.643461 -0.699238 -0.311488 0.643462 -0.699237 -0.311488 0.714533 -0.699238 -0.0225573 0.714533 -0.699238 -0.0225573 0.661827 -0.699238 0.270281 0.661825 -0.69924 0.27028 0.555791 -0.706224 0.43857 0.555793 -0.706222 0.438572 0.488437 -0.706222 0.512524 0.488436 -0.706223 0.512523 0.334404 -0.699696 0.631348 0.334404 -0.699694 0.63135 -0.169878 -0.699584 0.694063 -0.169878 -0.699585 0.694062 -0.158689 -0.700706 0.695578 -0.158687 -0.700709 0.695576 -0.404529 -0.700709 0.587677 -0.40453 -0.700707 0.587678 -0.593087 -0.700707 0.396557 -0.593086 -0.700708 0.396557 -0.136644 -0.706223 0.694678 -0.136644 -0.706223 0.694678 -0.233183 -0.706223 0.668487 -0.233183 -0.706223 0.668487 -0.413023 -0.699239 0.583504 -0.413023 -0.699239 0.583504 -0.614792 -0.699238 0.364823 -0.614791 -0.69924 0.364823 -0.710059 -0.69924 0.0829442 -0.710063 -0.699236 0.0829438 -0.682327 -0.699236 -0.213305 -0.682326 -0.699237 -0.213304 -0.420013 -0.706011 -0.570208 -0.273712 -0.900715 -0.337335 -0.456321 -0.744134 -0.487889 -0.570193 -0.704309 -0.422881 -0.570193 -0.70431 -0.42288 -0.506646 -0.707095 -0.493282 -0.242787 -0.69924 -0.672397 -0.242787 -0.699238 -0.672399 0.0519743 -0.699238 -0.712997 0.0519742 -0.699239 -0.712996 0.337731 -0.699239 -0.630081 0.33773 -0.699241 -0.63008 0.564982 -0.69924 -0.438017 0.564983 -0.699238 -0.438018 0.65771 -0.706222 -0.262045 0.657711 -0.706222 -0.262045 0.688077 -0.706222 -0.166737 0.688076 -0.706223 -0.166736 0.713272 -0.700707 0.0158695 0.713273 -0.700707 0.0158698 0.656904 -0.700707 0.278364 0.656904 -0.700707 0.278364 0.507512 -0.700707 0.501438 0.507512 -0.700707 0.501439 0.516137 -0.699585 0.49415 0.516137 -0.699585 0.49415 0.526142 -0.701184 0.48116 0.526141 -0.701186 0.481158 0.320171 -0.701186 0.637047 0.320171 -0.701185 0.637048 0.533287 -0.706223 0.465675 0.533288 -0.706222 0.465677 0.462336 -0.706222 0.536187 0.462335 -0.706223 0.536186 0.31784 -0.701413 0.637963 0.31784 -0.701414 0.637963 -0.651321 -0.70431 0.282361 -0.651319 -0.704312 0.282361 -0.701042 -0.704312 0.111733 -0.701045 -0.704309 0.111733 -0.703709 -0.699237 -0.12594 -0.703709 -0.699237 -0.12594 -0.591487 -0.699237 -0.40151 -0.591488 -0.699237 -0.401511 -0.376802 -0.699237 -0.607526 -0.376802 -0.699238 -0.607525 -0.096843 -0.699238 -0.708299 -0.0968431 -0.699239 -0.708298 0.101917 -0.706223 -0.700616 0.101917 -0.706223 -0.700616 0.19964 -0.706223 -0.679259 0.19964 -0.706223 -0.679259 0.370379 -0.700709 -0.609776 0.37038 -0.700708 -0.609777 0.569522 -0.700708 -0.429714 0.569522 -0.700707 -0.429714 0.688015 -0.700707 -0.188799 0.688015 -0.700707 -0.188799 0.686014 -0.699586 -0.199912 0.686015 -0.699585 -0.199913 0.681731 -0.700708 -0.21036 0.681732 -0.700707 -0.21036 0.711209 -0.700707 0.0564942 0.711209 -0.700707 0.0564941 0.639972 -0.700707 0.31535 0.639971 -0.700708 0.315349 0.669931 -0.706223 -0.229002 0.66993 -0.706223 -0.229002 0.695518 -0.706223 -0.132301 0.695519 -0.706223 -0.132301 0.711928 -0.697265 0.0835428 0.711929 -0.697265 0.0835429 0.597623 -0.697265 0.395813 0.597623 -0.697265 0.395813 0.354703 -0.697265 0.622902 0.354703 -0.697267 0.6229 -0.253759 -0.704309 0.66299 -0.253759 -0.704308 0.662991 -0.135879 -0.706718 0.694324 -0.0496458 -0.900714 0.431566 -0.0479438 -0.706008 0.70658 -0.460922 -0.699237 0.546459 -0.460923 -0.699237 0.54646 -0.643461 -0.699238 0.311488 -0.643462 -0.699237 0.311488 -0.714533 -0.699238 0.0225573 -0.714533 -0.699238 0.0225573 -0.661827 -0.699238 -0.270281 -0.661825 -0.69924 -0.27028 -0.555791 -0.706224 -0.43857 -0.555793 -0.706222 -0.438572 -0.488437 -0.706222 -0.512524 -0.488436 -0.706223 -0.512523 0.180503 -0.700707 -0.690238 0.180502 -0.700708 -0.690237 -0.0873824 -0.700708 -0.708077 -0.342893 -0.700708 -0.625646 -0.342893 -0.700707 -0.625647 -0.207498 -0.707071 -0.676014 -0.0807718 -0.666294 -0.741302 0.169878 -0.699584 -0.694063 0.169878 -0.699585 -0.694063 0.158689 -0.700706 -0.695578 0.158688 -0.700707 -0.695577 0.40453 -0.700707 -0.587678 0.40453 -0.700707 -0.587678 0.593087 -0.700707 -0.396557 0.593086 -0.700708 -0.396557 0.0423349 -0.698075 0.714772 0.0423349 -0.698074 0.714773 -0.271986 -0.698074 0.662357 -0.271986 -0.698075 0.662356 -0.532436 -0.698075 0.478752 -0.532436 -0.698074 0.478752 -0.687432 -0.698074 0.200325 -0.687433 -0.698073 0.200326 -0.706273 -0.698073 -0.117779 -0.706272 -0.698074 -0.117778 -0.585227 -0.698074 -0.412555 -0.585228 -0.698073 -0.412555 -0.348271 -0.698073 -0.625621 -0.34827 -0.698075 -0.625619 0.0156496 -0.694748 0.719083 0.0156494 -0.694747 0.719084 -0.34599 -0.694746 0.63057 -0.345989 -0.694747 0.63057 -0.61492 -0.694747 0.373095 -0.614922 -0.694745 0.373095 -0.719085 -0.694746 0.0156496 -0.719086 -0.694745 0.0156494 -0.630571 -0.694745 -0.345991 -0.63057 -0.694747 -0.345989 -0.373095 -0.694747 -0.61492 -0.373095 -0.694747 -0.61492 0.0423346 -0.698077 0.71477 0.0423345 -0.698076 0.714771 -0.271986 -0.698074 0.662356 -0.271986 -0.698074 0.662356 -0.532436 -0.698074 0.478752 -0.532437 -0.698074 0.478753 -0.687432 -0.698074 0.200325 -0.687431 -0.698074 0.200325 -0.706272 -0.698075 -0.117778 -0.706271 -0.698075 -0.117778 -0.585227 -0.698074 -0.412554 -0.585229 -0.698071 -0.412557 -0.348272 -0.69807 -0.625624 -0.348271 -0.698073 -0.625621 0.015649 -0.694743 0.719088 0.0156494 -0.694745 0.719086 -0.34599 -0.694745 0.630571 -0.345987 -0.69475 0.630567 -0.614918 -0.694749 0.373094 -0.614921 -0.694746 0.373095 -0.719084 -0.694747 0.0156494 -0.719084 -0.694747 0.0156494 -0.630571 -0.694745 -0.34599 -0.630571 -0.694745 -0.34599 -0.373096 -0.694744 -0.614923 -0.373095 -0.694746 -0.614921 -0.334612 -0.725764 -0.601084 -0.307161 -0.805831 -0.50625 -0.229566 -0.706718 -0.669215 0.0423349 -0.698073 0.714774 0.0423347 -0.698072 0.714775 -0.271987 -0.698072 0.662358 -0.271986 -0.698074 0.662356 -0.532436 -0.698074 0.478753 -0.532437 -0.698074 0.478753 -0.687432 -0.698074 0.200325 -0.687433 -0.698073 0.200325 -0.706273 -0.698073 -0.117779 -0.706273 -0.698074 -0.117779 -0.585228 -0.698073 -0.412556 -0.585226 -0.698075 -0.412554 -0.467776 -0.707093 -0.530288 -0.348272 -0.698071 -0.625622 -0.314869 -0.796862 -0.515624 -0.225086 -0.706822 -0.670625 0.0423349 -0.698073 0.714774 0.042335 -0.698074 0.714773 -0.271986 -0.698074 0.662357 -0.271986 -0.698074 0.662356 -0.532436 -0.698074 0.478752 -0.532438 -0.698072 0.478753 -0.687434 -0.698071 0.200326 -0.687433 -0.698073 0.200326 -0.706273 -0.698073 -0.117778 -0.62996 -0.771731 -0.0870686 -0.669616 -0.5734 -0.472045 -0.430479 -0.871147 -0.236201 -0.516302 -0.705845 -0.48499 -0.373095 -0.694746 -0.614921 -0.373095 -0.694745 -0.614922 -0.597959 -0.70086 -0.388897 -0.800994 -0.406507 -0.4395 -0.673289 -0.706118 -0.219269 -0.694339 -0.70672 -0.135795 -0.592007 -0.80583 0.012884 -0.911841 -0.402129 -0.0826937 -0.600563 -0.786349 0.14484 -0.698945 -0.704873 0.120957 -0.654505 -0.704873 0.273454 -0.8094 -0.322026 0.491092 0.0156492 -0.694747 0.719084 0.0156493 -0.694748 0.719083 -0.295431 -0.700864 0.649238 -0.439499 -0.406512 0.800992 -0.450094 -0.706114 0.546642 -0.562802 -0.703122 0.434595 -0.348271 -0.698074 -0.62562 -0.348272 -0.698071 -0.625622 -0.492298 -0.706856 -0.507934 -0.665096 -0.581222 -0.468859 -0.597955 -0.700863 -0.388897 -0.67329 -0.706117 -0.219269 -0.861625 -0.486782 -0.143685 -0.708161 -0.703124 -0.0642223 -0.694704 -0.702599 0.154082 -0.807119 -0.573628 0.139677 -0.6162 -0.744323 0.25745 -0.688855 -0.592277 0.417954 -0.512042 -0.762543 0.3954 -0.508539 -0.652571 0.561729 -0.450096 -0.706117 0.546638 -0.271986 -0.698074 0.662356 0.0423349 -0.698073 0.714774 0.0423352 -0.698076 0.714772 -0.142357 -0.706861 0.692879 -0.346643 -0.54729 0.761782 0.0156503 -0.694746 0.719085 -0.614922 -0.694745 0.373095 -0.614922 -0.694745 0.373095 -0.719085 -0.694746 0.0156496 -0.719086 -0.694745 0.0156494 -0.630571 -0.694745 -0.345991 -0.63057 -0.694747 -0.345989 -0.373095 -0.694747 -0.61492 -0.373094 -0.694748 -0.614919 0.0156495 -0.694742 0.719089 -0.200237 -0.706713 0.678574 -0.284848 -0.805827 0.519138 -0.284847 -0.805828 0.519137 -0.464775 -0.706716 0.53342 0.16588 -0.706717 0.687775 0.0128845 -0.805831 0.592005 -0.373096 -0.694744 -0.614924 -0.373094 -0.69475 -0.614918 -0.630568 -0.694749 -0.345988 -0.630568 -0.694749 -0.345989 -0.719084 -0.694747 0.0156494 -0.719084 -0.694747 0.0156493 -0.614921 -0.694746 0.373095 -0.614922 -0.694746 0.373095 -0.345991 -0.694744 0.630572 -0.345992 -0.694742 0.630574 -0.135796 -0.706713 0.694346 0.0128825 -0.805825 0.592013 0.0156489 -0.694746 0.719085 0.0156493 -0.694749 0.719082 -0.345988 -0.694748 0.630569 -0.345991 -0.694744 0.630572 -0.614922 -0.694745 0.373095 -0.614919 -0.694749 0.373094 -0.719083 -0.694748 0.0156496 -0.719084 -0.694747 0.0156493 -0.630569 -0.694748 -0.345989 -0.63057 -0.694747 -0.345989 -0.373095 -0.694747 -0.61492 -0.373095 -0.694747 -0.61492 0.0156495 -0.69475 0.719081 0.0156493 -0.694749 0.719082 -0.345989 -0.694748 0.630569 -0.345989 -0.694747 0.63057 -0.61492 -0.694747 0.373095 -0.61492 -0.694747 0.373094 -0.719085 -0.694746 0.0156489 -0.719082 -0.694749 0.0156493 -0.630569 -0.694748 -0.345988 -0.63057 -0.694747 -0.345989 -0.373095 -0.694747 -0.61492 -0.373095 -0.694745 -0.614922 0.0156494 -0.694748 0.719083 0.0156493 -0.694747 0.719084 -0.34599 -0.694745 0.630571 -0.34599 -0.694745 0.630571 -0.614923 -0.694744 0.373096 -0.614918 -0.694749 0.373094 -0.719081 -0.69475 0.0156502 -0.719086 -0.694745 0.0156494 -0.630571 -0.694745 -0.34599 -0.630572 -0.694744 -0.345991 -0.373096 -0.694745 -0.614922 -0.373094 -0.69475 -0.614918 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.988807 0 0.149203 -0.82296 0 0.568099 -0.720079 0 0.693893 0.195702 0 0.980664 0.119146 0.677614 0.725702 0.0760692 0 0.997103 -0.0559995 0.704005 0.707984 -0.0152409 0.219459 0.975503 0.0217544 0.0091277 0.999722 0.040316 0 0.999187 -0.416658 0 0.909063 -0.386063 0.111034 0.915766 -0.25731 0.609069 0.750218 -0.22144 0.711492 0.666891 -0.238071 0 0.971248 -0.117622 0 0.993059 -0.720079 0 0.693893 -0.565428 0 0.824798 -0.379274 0.70273 0.601932 -0.465395 0.252948 0.848189 -0.446762 0 0.894653 -0.678802 0.60795 0.411855 -0.572333 0.749951 0.331675 -0.860814 0.242489 0.447436 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.914165 0 0.405343 -0.966421 0.242486 0.0850402 -0.660916 0.749948 0.027707 -0.793783 0.607956 0.0172753 -0.939142 0 -0.343531 -0.954517 0 -0.298156 -0.851277 0.495603 -0.172352 -0.983497 0 -0.180926 -0.999313 0 -0.0370677 -0.720006 0.609039 -0.33266 -0.643258 0.702731 -0.303953 -0.848187 0.252955 -0.465395 -0.518704 0.00912185 -0.854905 -0.536898 0.219455 -0.814604 -0.456709 0.634164 -0.623902 -0.40138 0.745323 -0.532341 -0.654683 0 -0.755904 -0.775629 0 -0.631189 -0.775629 0 -0.631189 -0.857433 0 -0.514596 -0.393457 0 -0.919343 -0.393457 0 -0.919343 -0.502771 0 -0.86442 -0.486395 0 -0.873739 -0.518721 -0.0037176 -0.854935 -0.695963 0 -0.718078 -0.838301 0 -0.545208 -0.876682 -0.00620738 -0.48103 -0.950845 0 -0.309666 -0.995913 0 -0.0903169 -0.999735 -0.00745589 0.0217572 -0.985354 0 0.170522 -0.922705 0 0.385508 -0.854918 -0.00745592 0.51871 -0.791487 0 0.611186 -0.635644 0 0.771982 -0.481029 -0.00620763 0.876683 -0.414176 0 0.910197 -0.201253 0 0.979539 0.0217579 -0.00371752 0.999756 0.0591247 0 0.998251 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481038 0 0.8767 -0.481038 0 0.8767 0.021758 0 0.999763 0.021758 0 0.999763 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.695963 0 -0.718078 -0.695963 0 -0.718078 -0.838299 0 -0.545211 -0.838299 0 -0.545211 -0.950846 0 -0.309663 -0.950846 0 -0.309663 -0.995913 0 -0.0903176 -0.995913 0 -0.0903176 -0.985354 0 0.170524 -0.985354 0 0.170524 -0.922705 0 0.385508 -0.922705 0 0.385508 -0.791486 0 0.611187 -0.791486 0 0.611187 -0.63564 0 0.771986 -0.63564 0 0.771986 -0.414179 0 0.910196 -0.414179 0 0.910196 -0.201264 0 0.979537 -0.201264 0 0.979537 0.0591267 0 0.99825 0.0591267 0 0.99825 -0.486394 0 -0.87374 -0.518721 -0.00371762 -0.854936 -0.695965 0 -0.718076 -0.8383 0 -0.545209 -0.876683 -0.00620749 -0.481029 -0.950846 0 -0.309663 -0.995913 0 -0.0903207 -0.999735 -0.00745615 0.0217574 -0.985353 0 0.170527 -0.922706 0 0.385505 -0.854919 -0.00745593 0.518708 -0.791488 0 0.611185 -0.635641 0 0.771985 -0.481029 -0.00620747 0.876682 -0.414178 0 0.910196 -0.201254 0 0.979539 0.0217576 -0.00371758 0.999756 0.0591251 0 0.998251 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.48104 0 0.876699 -0.48104 0 0.876699 0.021758 0 0.999763 0.021758 0 0.999763 -0.486395 0 -0.873739 -0.518722 0.0037176 -0.854935 -0.817323 -0.00310591 -0.576171 -0.838299 0 -0.54521 -0.950845 0 -0.309666 -0.986367 -0.00497653 -0.164487 -0.995913 0 -0.0903161 -0.985354 0 0.170522 -0.960051 -0.00560112 0.27977 -0.922705 0 0.385508 -0.791487 0 0.611186 -0.743591 -0.00497644 0.668616 -0.635642 0 0.771984 -0.379856 0 0.925046 -0.414175 -0.00371746 0.91019 0.0591262 0.00432415 0.998241 0.021758 0 0.999763 -0.486395 0 -0.873739 -0.486395 0 -0.873739 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.7436 0 0.668624 -0.7436 0 0.668624 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591247 0 0.998251 0.0591247 0 0.998251 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.817328 0 -0.576173 -0.817328 0 -0.576173 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960066 0 0.279773 -0.960066 0 0.279773 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.379856 0 0.925045 -0.379856 0 0.925045 0.0591246 0 0.998251 0.0591246 0 0.998251 -0.486394 0 -0.873739 -0.486394 0 -0.873739 -0.817327 0 -0.576175 -0.817327 0 -0.576175 -0.986379 0 -0.164487 -0.986379 0 -0.164487 -0.960067 0 0.279771 -0.960067 0 0.279771 -0.743598 0 0.668627 -0.743598 0 0.668627 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591247 0 0.998251 0.0591247 0 0.998251 -0.486394 0 -0.87374 -0.518721 0.00371762 -0.854936 -0.817324 -0.00310588 -0.57617 -0.8383 0 -0.545209 -0.950846 0 -0.309663 -0.986367 -0.00497649 -0.164485 -0.995913 0 -0.0903148 -0.985354 0 0.170519 -0.960052 -0.00560109 0.279767 -0.922706 0 0.385505 -0.791485 0 0.611188 -0.743589 -0.00497641 0.668618 -0.635641 0 0.771985 -0.379855 0 0.925046 -0.414175 -0.00371751 0.91019 0.0591241 0.00432396 0.998241 0.0217576 0 0.999763 -0.486395 0 -0.873739 -0.518721 -0.00371747 -0.854936 -0.695954 0 -0.718086 -0.8383 0 -0.545209 -0.876683 -0.00620749 -0.481029 -0.950846 0 -0.309663 -0.995913 0 -0.0903149 -0.999735 -0.00745575 0.0217574 -0.985354 0 0.170519 -0.922703 0 0.385513 -0.854918 -0.00745567 0.51871 -0.791489 0 0.611184 -0.63564 0 0.771986 -0.481029 -0.00620745 0.876683 -0.414178 0 0.910196 -0.201255 0 0.979539 0.0217579 -0.00371752 0.999756 0.0591246 0 0.998251 -0.486393 0 -0.87374 -0.51872 -0.00371768 -0.854936 -0.695966 0 -0.718075 -0.838299 0 -0.545211 -0.876682 -0.00620753 -0.48103 -0.950846 0 -0.309663 -0.995913 0 -0.0903176 -0.999735 -0.00745595 0.0217574 -0.985354 0 0.170524 -0.922705 0 0.385508 -0.854918 -0.00745594 0.51871 -0.791486 0 0.611187 -0.635647 0 0.77198 -0.48103 -0.00620769 0.876682 -0.414176 0 0.910197 -0.201252 0 0.979539 0.0217579 -0.00371752 0.999756 0.0591247 0 0.998251 -0.373095 0.694746 -0.614921 -0.373096 0.694746 -0.614921 -0.63057 0.694746 -0.345989 -0.630569 0.694747 -0.34599 -0.719084 0.694747 0.0156494 -0.719084 0.694747 0.0156493 -0.61492 0.694748 0.373094 -0.61492 0.694748 0.373094 -0.345988 0.694748 0.630569 -0.345988 0.694748 0.630569 0.0156495 0.694749 0.719082 0.0156495 0.694749 0.719082 -0.373095 0.694747 -0.61492 -0.373095 0.694747 -0.61492 -0.63057 0.694747 -0.345989 -0.630569 0.694748 -0.345989 -0.719084 0.694747 0.0156496 -0.719084 0.694747 0.0156496 -0.614921 0.694747 0.373094 -0.614921 0.694746 0.373095 -0.345989 0.694746 0.630571 -0.345989 0.694746 0.63057 0.0156496 0.694746 0.719085 0.0156476 0.694748 0.719083 0.0156496 0.694747 0.719084 0.0442151 0.663921 0.746494 -0.142365 0.70686 0.692879 -0.345989 0.694747 0.63057 -0.32208 0.628715 0.707801 -0.450094 0.706117 0.546639 -0.614919 0.694748 0.373094 -0.639875 0.588569 0.494112 -0.654504 0.704874 0.273453 -0.698943 0.704874 0.120958 -0.762092 0.647256 0.0165855 -0.70816 0.703125 -0.0642218 -0.67329 0.706117 -0.219271 -0.661854 0.655796 -0.363155 -0.34827 0.698075 -0.625619 -0.384094 0.672102 -0.633048 -0.492292 0.70686 -0.507935 -0.597956 0.700862 -0.388897 -0.373094 0.694748 -0.61492 -0.373094 0.694748 -0.61492 -0.630569 0.694748 -0.345988 -0.630569 0.694748 -0.345988 -0.719082 0.694749 0.0156495 -0.719082 0.694749 0.0156496 -0.61492 0.694749 0.373092 -0.614921 0.694746 0.373096 -0.345989 0.694746 0.63057 -0.34599 0.694747 0.630569 0.0156493 0.694747 0.719084 0.0156493 0.694747 0.719084 -0.373094 0.694747 -0.614921 -0.373094 0.694747 -0.614921 -0.63057 0.694747 -0.345989 -0.630569 0.694748 -0.345989 -0.719084 0.694747 0.0156496 -0.719084 0.694747 0.0156495 -0.61492 0.694748 0.373094 -0.61492 0.694747 0.373095 -0.34599 0.694747 0.630569 -0.34599 0.694747 0.63057 0.0156496 0.694747 0.719084 0.0156496 0.694747 0.719084 -0.348271 0.698075 -0.625619 -0.34827 0.698076 -0.625618 -0.585226 0.698075 -0.412554 -0.585227 0.698075 -0.412554 -0.706272 0.698075 -0.117778 -0.706272 0.698074 -0.117778 -0.687432 0.698074 0.200325 -0.687431 0.698074 0.200325 -0.532437 0.698074 0.478752 -0.532437 0.698074 0.478752 -0.271986 0.698075 0.662356 -0.271986 0.698074 0.662357 0.0423363 0.698073 0.714774 0.0423347 0.698074 0.714773 -0.34827 0.698075 -0.625619 -0.34827 0.698076 -0.625618 -0.585226 0.698075 -0.412554 -0.585227 0.698074 -0.412554 -0.706272 0.698074 -0.117779 -0.706272 0.698074 -0.117779 -0.687431 0.698074 0.200325 -0.687431 0.698074 0.200326 -0.532437 0.698074 0.478752 -0.532437 0.698074 0.478751 -0.271986 0.698075 0.662356 -0.271985 0.698073 0.662357 0.0423348 0.698073 0.714774 0.0423348 0.698073 0.714774 -0.34827 0.698076 -0.625618 -0.348272 0.698074 -0.625619 -0.585228 0.698074 -0.412555 -0.585226 0.698075 -0.412555 -0.706271 0.698075 -0.117778 -0.706272 0.698074 -0.117778 -0.687432 0.698074 0.200325 -0.687432 0.698074 0.200325 -0.532436 0.698074 0.478754 -0.532436 0.698075 0.478751 -0.271987 0.698075 0.662355 -0.271986 0.698074 0.662357 0.0423347 0.698074 0.714773 0.0423348 0.698074 0.714773 -0.34827 0.698075 -0.625619 -0.348271 0.698074 -0.625619 -0.585226 0.698075 -0.412555 -0.585227 0.698074 -0.412555 -0.706273 0.698074 -0.117777 -0.706271 0.698076 -0.117778 -0.687431 0.698075 0.200323 -0.687433 0.698073 0.200326 -0.532436 0.698073 0.478755 -0.532436 0.698076 0.47875 -0.271986 0.698075 0.662355 -0.271985 0.698075 0.662356 0.0423348 0.698074 0.714773 0.0423347 0.698074 0.714773 -0.34827 0.698075 -0.625619 -0.348271 0.698074 -0.62562 -0.585229 0.698073 -0.412555 -0.585227 0.698074 -0.412555 -0.706273 0.698074 -0.117777 -0.706271 0.698075 -0.117778 -0.687431 0.698076 0.200323 -0.687432 0.698073 0.200326 -0.532436 0.698073 0.478754 -0.532436 0.698076 0.478751 -0.271986 0.698075 0.662356 -0.271985 0.698074 0.662356 0.0423347 0.698074 0.714773 0.0423348 0.698074 0.714773 -0.373094 0.694747 -0.61492 -0.373095 0.694746 -0.614921 -0.630571 0.694746 -0.345989 -0.63057 0.694746 -0.345989 -0.719085 0.694746 0.0156496 -0.719085 0.694746 0.0156496 -0.614921 0.694746 0.373096 -0.61492 0.694748 0.373093 -0.345989 0.694748 0.630569 -0.345989 0.694748 0.630569 0.0156496 0.694747 0.719084 0.0156496 0.694747 0.719084 -0.528076 0.849119 0.0114926 -0.463074 0.849119 -0.254086 -0.273991 0.849119 -0.451581 0.0114938 0.849119 0.528076 -0.254086 0.849119 0.463073 -0.451581 0.849119 0.273991 -0.528077 0.849119 0.0114915 -0.463074 0.849119 -0.254086 -0.273991 0.849119 -0.451582 0.0114926 0.849119 0.528077 -0.254086 0.849119 0.463074 -0.451581 0.849119 0.273992 -0.255197 0.851305 -0.458426 -0.437346 0.853125 -0.284439 -0.517172 0.854596 -0.0468999 -0.477433 0.855727 0.19947 -0.328051 0.856529 0.398422 0.0310213 0.851305 0.523754 -0.103711 0.857008 0.504759 -0.216079 0.853125 0.474855 -0.411015 0.854596 0.317384 -0.509849 0.855727 0.0882339 -0.490729 0.856529 -0.159822 -0.358636 0.857008 -0.370024 -0.528076 0.849119 0.0114938 -0.463073 0.849119 -0.254086 -0.273991 0.849119 -0.451582 0.0114926 0.849119 0.528077 -0.254086 0.849119 0.463074 -0.451581 0.849119 0.273992 -0.358632 0.857008 -0.370028 -0.490731 0.856529 -0.159816 -0.509849 0.855727 0.0882324 -0.411014 0.854595 0.317387 -0.103707 0.857007 0.504761 0.0310197 0.851305 0.523754 -0.21608 0.853125 0.474855 -0.328055 0.856529 0.39842 -0.477433 0.855727 0.199472 -0.517172 0.854595 -0.0469011 -0.437346 0.853126 -0.284438 -0.255195 0.851305 -0.458427 -0.528076 0.849119 0.0114926 -0.463074 0.849119 -0.254086 -0.27399 0.849119 -0.451583 0.0114938 0.849119 0.528076 -0.254086 0.849119 0.463073 -0.451581 0.849119 0.273992 -0.255197 0.851305 -0.458426 -0.437346 0.853125 -0.284439 -0.517172 0.854596 -0.0469019 -0.477433 0.855727 0.199472 -0.328053 0.856529 0.398421 0.031021 0.851305 0.523754 -0.103706 0.857008 0.50476 -0.21608 0.853125 0.474854 -0.411014 0.854596 0.317385 -0.509849 0.855727 0.0882336 -0.49073 0.856529 -0.159819 -0.358632 0.857008 -0.370028 -0.528076 0.849119 0.0114938 -0.463073 0.849119 -0.254086 -0.273991 0.849119 -0.451582 0.0114926 0.849119 0.528076 -0.254086 0.849119 0.463074 -0.451581 0.849119 0.273991 -0.528076 0.849119 0.0114926 -0.463074 0.849119 -0.254085 -0.27399 0.849119 -0.451582 0.0114926 0.849119 0.528076 -0.254085 0.849119 0.463074 -0.451582 0.849119 0.27399 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.373094 0.694748 -0.61492 -0.373095 0.694747 -0.61492 -0.630569 0.694747 -0.34599 -0.630569 0.694747 -0.34599 -0.719084 0.694747 0.0156496 -0.719084 0.694747 0.0156495 -0.61492 0.694748 0.373095 -0.614919 0.694748 0.373094 -0.345989 0.694749 0.630568 -0.345988 0.694748 0.630569 0.0156495 0.694749 0.719082 0.0156496 0.694749 0.719082 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.854941 0 0.518726 -0.854941 0 0.518726 -0.481041 0 0.876698 -0.481041 0 0.876698 0.0217602 0 0.999763 0.0217602 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217558 -0.999763 0 0.0217558 -0.854941 0 0.518726 -0.854941 0 0.518726 -0.481039 0 0.876699 -0.481039 0 0.876699 0.021758 0 0.999763 0.021758 0 0.999763 -0.486395 0 -0.873739 -0.518722 -0.0036368 -0.854935 -0.69597 0 -0.71807 -0.8383 0 -0.545209 -0.876682 -0.0060722 -0.481032 -0.950843 0 -0.309673 -0.995913 0 -0.0903148 -0.999737 -0.00729367 0.0217596 -0.985354 0 0.170524 -0.922706 0 0.385503 -0.85492 -0.00729376 0.518708 -0.791488 0 0.611185 -0.635637 0 0.771988 -0.481028 -0.00607232 0.876684 -0.414177 0 0.910196 -0.201261 0 0.979538 0.0217579 -0.00363668 0.999757 0.0591252 0 0.998251 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876698 0 -0.481041 -0.876698 0 -0.481041 -0.999763 0 0.0217602 -0.999763 0 0.0217602 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217581 0 0.999763 0.0217581 0 0.999763 -0.486391 0 -0.873741 -0.486391 0 -0.873741 -0.695963 0 -0.718078 -0.695963 0 -0.718078 -0.838301 0 -0.545208 -0.838301 0 -0.545208 -0.950847 0 -0.309662 -0.950847 0 -0.309662 -0.995913 0 -0.090317 -0.995913 0 -0.090317 -0.985354 0 0.170521 -0.985354 0 0.170521 -0.922705 0 0.385507 -0.922705 0 0.385507 -0.791485 0 0.611188 -0.791485 0 0.611188 -0.635644 0 0.771983 -0.635644 0 0.771983 -0.414179 0 0.910196 -0.414179 0 0.910196 -0.201253 0 0.979539 -0.201253 0 0.979539 0.0591222 0 0.998251 0.0591222 0 0.998251 -0.518722 0 -0.854943 -0.518722 0 -0.854943 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.854941 0 0.518726 -0.854941 0 0.518726 -0.481041 0 0.876698 -0.481041 0 0.876698 0.0217602 0 0.999763 0.0217602 0 0.999763 -0.486394 0 -0.87374 -0.518721 -0.00363671 -0.854936 -0.695963 0 -0.718078 -0.8383 0 -0.545209 -0.876683 -0.0060723 -0.48103 -0.950845 0 -0.309667 -0.995913 0 -0.0903186 -0.999737 -0.00729377 0.0217574 -0.985354 0 0.170524 -0.922705 0 0.385507 -0.854919 -0.0072937 0.51871 -0.791487 0 0.611186 -0.635639 0 0.771986 -0.48103 -0.00607232 0.876683 -0.414179 0 0.910195 -0.201252 0 0.97954 0.0217579 -0.00363663 0.999757 0.0591247 0 0.998251 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876698 0 -0.481041 -0.876698 0 -0.481041 -0.999763 0 0.0217602 -0.999763 0 0.0217602 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217581 0 0.999763 0.0217581 0 0.999763 -0.518723 0 -0.854942 -0.518723 0 -0.854942 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.0217581 -0.999763 0 0.0217581 -0.854942 0 0.518723 -0.854942 0 0.518723 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217581 0 0.999763 0.0217581 0 0.999763 -0.928982 0 0.370125 -0.928982 0 0.370125 -0.971873 0 0.235507 -0.971873 0 0.235507 -0.790309 0 0.612708 -0.790309 0 0.612708 -0.472426 0 0.881371 -0.472426 0 0.881371 -0.0727027 0 0.997354 -0.0727027 0 0.997354 0.339615 0 0.940564 0.339615 0 0.940564 0.80321 0 0.595696 0.80321 0 0.595696 0.630076 0 0.776534 0.630076 0 0.776534 0.954449 0 0.298374 0.954449 0 0.298374 0.993246 0 -0.116024 0.993246 0 -0.116024 0.859983 0 -0.510322 0.859983 0 -0.510322 0.577745 0 -0.816217 0.577745 0 -0.816217 0.193002 0 -0.981198 0.193002 0 -0.981198 0.329359 0 -0.944205 0.329359 0 -0.944205 -0.733119 0 -0.6801 -0.737948 0.00104044 -0.674857 -0.429854 -0.00107906 -0.902898 -0.44906 0.00215808 -0.893499 -0.0657164 -0.00223534 -0.997836 -0.0799343 0 -0.9968 -0.722324 0 -0.691554 -0.722324 0 -0.691554 -0.999753 0 -0.0222434 -0.999753 0 -0.0222434 -0.920745 0 -0.390166 -0.920745 0 -0.390166 -0.711351 0 -0.702837 -0.711351 0 -0.702837 -0.785029 0 -0.619459 -0.785029 0 -0.619459 -0.689891 0 -0.723913 -0.689891 0 -0.723913 -0.925775 0 -0.378074 -0.925775 0 -0.378074 -0.999502 0 0.0315536 -0.999502 0 0.0315536 -0.900085 0 0.435715 -0.900085 0 0.435715 -0.644746 0 0.764397 -0.644746 0 0.764397 -0.114283 0 0.993448 -0.114283 0 0.993448 -0.35746 0 0.933928 -0.35746 0 0.933928 0.218826 0 0.975764 0.218826 0 0.975764 0.597103 0 0.802165 0.597103 0 0.802165 0.871944 0 0.489606 0.871944 0 0.489606 0.995737 0 0.0922336 0.995737 0 0.0922336 0.946244 0 -0.323454 0.946244 0 -0.323454 0.982385 0 -0.186869 0.982385 0 -0.186869 0.222424 0 -0.97495 0.222424 0 -0.97495 0.567006 0 -0.823714 0.567006 0 -0.823714 0.831295 0 -0.555831 0.831295 0 -0.555831 0.237741 0 -0.971328 0.237741 0 -0.971328 -0.480613 0 -0.876933 -0.468062 -0.00208073 -0.883693 -0.122479 0.0019257 -0.992469 -0.10123 -0.000962871 -0.994863 0.253 0.00100165 -0.967466 0.259889 0 -0.965638 0.143953 0 -0.989585 0.143953 0 -0.989585 0.281981 0 -0.95942 0.281981 0 -0.95942 -0.104711 0 -0.994503 -0.104711 0 -0.994503 -0.917493 0 0.397752 -0.917493 0 0.397752 -0.987536 0 0.157395 -0.987536 0 0.157395 -0.735623 0 0.677391 -0.735623 0 0.677391 -0.396144 0 0.918188 -0.396144 0 0.918188 0.0119601 0 0.999928 0.0119601 0 0.999928 0.417992 0 0.908451 0.417992 0 0.908451 0.753242 0 0.657744 0.753242 0 0.657744 0.653026 0 0.757336 0.653026 0 0.757336 0.955544 0 -0.29485 0.955544 0 -0.29485 0.99686 0 0.0791846 0.99686 0 0.0791846 0.897011 0 0.442007 0.897011 0 0.442007 0.960066 0 -0.279774 0.960066 0 -0.279774 0.519139 0 -0.85469 0.519139 0 -0.85469 0.798266 0 -0.602305 0.798266 0 -0.602305 0.96435 0 -0.264629 0.96435 0 -0.264629 0.928982 0 -0.370125 0.928982 0 -0.370125 0.971873 0 -0.235507 0.971873 0 -0.235507 0.775095 0 -0.631845 0.775095 0 -0.631845 0.40657 0 -0.91362 0.40657 0 -0.91362 -0.0494537 0 -0.998776 -0.0494537 0 -0.998776 -0.80321 0 -0.595696 -0.80321 0 -0.595696 -0.630076 0 -0.776534 -0.630076 0 -0.776534 -0.954449 0 -0.298374 -0.954449 0 -0.298374 -0.993246 0 0.116024 -0.993246 0 0.116024 -0.859983 0 0.510322 -0.859983 0 0.510322 -0.577745 0 0.816217 -0.577745 0 0.816217 -0.193002 0 0.981198 -0.193002 0 0.981198 -0.329359 0 0.944205 -0.329359 0 0.944205 0.737948 0 0.674857 0.733119 -0.00100161 0.6801 0.449061 0.000962902 0.8935 0.442681 0 0.896679 0.722324 0 0.691554 0.722324 0 0.691554 0.999753 0 0.0222434 0.999753 0 0.0222434 0.920745 0 0.390166 0.920745 0 0.390166 0.711351 0 0.702837 0.711351 0 0.702837 0.785029 0 0.619459 0.785029 0 0.619459 0.689891 0 0.723913 0.689891 0 0.723913 0.925775 0 0.378074 0.925775 0 0.378074 0.999502 0 -0.0315536 0.999502 0 -0.0315536 0.900085 0 -0.435715 0.900085 0 -0.435715 0.644746 0 -0.764397 0.644746 0 -0.764397 0.114283 0 -0.993448 0.114283 0 -0.993448 0.35746 0 -0.933928 0.35746 0 -0.933928 -0.146735 0 -0.989176 -0.146735 0 -0.989176 -0.946244 0 0.323454 -0.946244 0 0.323454 -0.982385 0 0.186869 -0.982385 0 0.186869 -0.222424 0 0.97495 -0.222424 0 0.97495 -0.567006 0 0.823714 -0.567006 0 0.823714 -0.831295 0 0.555831 -0.831295 0 0.555831 -0.237741 0 0.971328 -0.237741 0 0.971328 0.480613 0 0.876933 0.468062 0.00208072 0.883693 0.293432 0 0.95598 -0.143953 0 0.989585 -0.143953 0 0.989585 -0.281981 0 0.95942 -0.281981 0 0.95942 0.135466 0 0.990782 0.135466 0 0.990782 0.527077 0 0.849818 0.527077 0 0.849818 0.827382 0 0.561639 0.827382 0 0.561639 0.98436 0 0.176168 0.98436 0 0.176168 0.917493 0 -0.397752 0.917493 0 -0.397752 0.987536 0 -0.157395 0.987536 0 -0.157395 0.728589 0 -0.684951 0.728589 0 -0.684951 0.367512 0 -0.930019 0.367512 0 -0.930019 -0.0635524 0 -0.997979 -0.0635524 0 -0.997979 -0.753241 0 -0.657744 -0.753241 0 -0.657744 -0.653026 0 -0.757336 -0.653026 0 -0.757336 -0.955544 0 0.29485 -0.955544 0 0.29485 -0.99686 0 -0.0791846 -0.99686 0 -0.0791846 -0.897012 0 -0.442007 -0.897012 0 -0.442007 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.519139 0 0.85469 -0.519139 0 0.85469 -0.798266 0 0.602305 -0.798266 0 0.602305 -0.96435 0 0.264629 -0.96435 0 0.264629 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.348269 0.698079 -0.625615 -0.348272 0.69807 -0.625624 -0.492292 0.706857 -0.507939 -0.514445 0.777063 -0.362657 -0.597957 0.700861 -0.388897 -0.67329 0.706116 -0.219272 -0.575788 0.811941 -0.0960187 -0.70816 0.703125 -0.0642213 -0.698942 0.704875 0.120957 -0.54681 0.821954 0.159346 -0.654505 0.704873 0.273454 -0.532437 0.698074 0.478753 -0.423924 0.844469 0.327354 -0.450096 0.706112 0.546644 -0.271988 0.698068 0.662362 -0.255397 0.78725 0.561257 -0.142354 0.706855 0.692886 0.0423342 0.698069 0.714778 0.042335 0.698073 0.714774 -0.348271 0.698073 -0.625621 -0.348272 0.69807 -0.625624 -0.58523 0.698071 -0.412556 -0.585229 0.698073 -0.412555 -0.706273 0.698074 -0.117779 -0.70627 0.698076 -0.117778 -0.687429 0.698077 0.200325 -0.687432 0.698074 0.200325 -0.532437 0.698074 0.478753 -0.532436 0.698074 0.478752 -0.271986 0.698075 0.662356 -0.271988 0.698071 0.662359 0.0423348 0.698072 0.714775 0.042335 0.698073 0.714774 -0.630567 0.69475 -0.345988 -0.373094 0.694749 -0.614918 -0.373096 0.694745 -0.614922 -0.431371 0.857443 -0.280553 -0.673288 0.706119 -0.219271 -0.719082 0.694749 0.0156488 -0.443042 0.8956 -0.0401781 -0.698945 0.704872 0.120956 -0.654505 0.704872 0.273456 -0.455327 0.846378 0.276264 -0.562802 0.703122 0.434595 -0.450098 0.706115 0.546639 -0.26871 0.829436 0.489726 -0.295432 0.700863 0.649239 0.0156493 0.694747 0.719084 0.0156496 0.694748 0.719083 -0.348271 0.698074 -0.62562 -0.348271 0.698073 -0.625621 -0.492291 0.706858 -0.507939 -0.514445 0.777063 -0.362657 -0.597956 0.700862 -0.388896 -0.67329 0.706116 -0.219271 -0.575788 0.811941 -0.0960185 -0.708161 0.703124 -0.0642208 -0.698945 0.704873 0.120956 -0.54681 0.821954 0.159346 -0.654507 0.704871 0.273456 -0.532439 0.698071 0.478754 -0.423926 0.844468 0.327355 -0.450097 0.706116 0.546638 -0.271986 0.698074 0.662357 -0.255396 0.787251 0.561257 -0.142358 0.706859 0.692881 0.0423349 0.698075 0.714772 0.0423347 0.698074 0.714773 -0.348271 0.698073 -0.625621 -0.34827 0.698076 -0.625618 -0.492292 0.706862 -0.507932 -0.514444 0.777063 -0.362656 -0.597956 0.700863 -0.388896 -0.673288 0.706117 -0.219276 -0.575784 0.811944 -0.0960192 -0.708161 0.703124 -0.0642208 -0.687433 0.698073 0.200326 -0.463803 0.882295 0.0802634 -0.654507 0.70487 0.273457 -0.532438 0.698071 0.478755 -0.423923 0.84447 0.327353 -0.450095 0.706121 0.546634 -0.271985 0.698077 0.662354 -0.255395 0.787252 0.561256 -0.142358 0.706861 0.692879 0.0423346 0.698076 0.714772 0.0423348 0.698077 0.71477 -0.373095 0.694747 -0.61492 -0.373095 0.694747 -0.61492 -0.63057 0.694747 -0.345989 -0.63057 0.694747 -0.34599 -0.719086 0.694745 0.0156494 -0.719085 0.694746 0.0156496 -0.614919 0.694749 0.373094 -0.614922 0.694745 0.373095 -0.34599 0.694744 0.630572 -0.345992 0.694742 0.630574 0.0156495 0.694742 0.719089 0.0156503 0.694746 0.719085 -0.630571 0.694745 -0.34599 -0.373096 0.694744 -0.614923 -0.373096 0.694746 -0.614921 -0.431371 0.857443 -0.280554 -0.673289 0.706118 -0.219271 -0.719084 0.694747 0.0156493 -0.44304 0.895601 -0.0401784 -0.698943 0.704875 0.120956 -0.654503 0.704876 0.273454 -0.455326 0.846379 0.276263 -0.562801 0.703123 0.434595 -0.450097 0.706114 0.54664 -0.26871 0.829435 0.489727 -0.295432 0.700864 0.649238 0.0156493 0.694749 0.719082 0.0156502 0.694753 0.719078 -0.373095 0.694747 -0.61492 -0.373095 0.694747 -0.61492 -0.63057 0.694747 -0.345989 -0.63057 0.694746 -0.34599 -0.719084 0.694747 0.0156494 -0.719085 0.694746 0.0156492 -0.61492 0.694747 0.373095 -0.614922 0.694745 0.373095 -0.34599 0.694744 0.630572 -0.345988 0.694748 0.630569 0.0156493 0.694749 0.719082 0.0156489 0.694746 0.719085 -0.630569 0.694747 -0.345989 -0.373095 0.694747 -0.61492 -0.373094 0.694749 -0.614919 -0.431372 0.857442 -0.280554 -0.673291 0.706116 -0.219272 -0.719086 0.694745 0.0156496 -0.44304 0.895601 -0.0401786 -0.698945 0.704873 0.120957 -0.654506 0.704872 0.273454 -0.455325 0.846379 0.276263 -0.562798 0.703128 0.434591 -0.450092 0.706119 0.546638 -0.26871 0.829435 0.489727 -0.295432 0.700863 0.649239 0.0156493 0.694749 0.719082 0.0156489 0.694746 0.719085 -0.373095 0.694746 -0.614921 -0.373095 0.694746 -0.614922 -0.630572 0.694744 -0.34599 -0.630569 0.694749 -0.345988 -0.719082 0.694749 0.0156493 -0.719085 0.694746 0.0156489 -0.614921 0.694746 0.373095 -0.614918 0.69475 0.373093 -0.345988 0.694749 0.630568 -0.345988 0.694749 0.630568 0.0156494 0.694747 0.719084 0.0156493 0.694747 0.719084 -0.373093 0.69475 -0.614918 -0.373095 0.694747 -0.614921 -0.630569 0.694747 -0.34599 -0.630569 0.694748 -0.345989 -0.719082 0.694749 0.0156493 -0.719081 0.69475 0.0156495 -0.614919 0.694748 0.373094 -0.614921 0.694747 0.373095 -0.345989 0.694747 0.63057 -0.345989 0.694746 0.63057 0.0156494 0.694747 0.719084 0.0156492 0.694746 0.719085 -0.373096 0.694745 -0.614921 -0.373094 0.694747 -0.614921 -0.63057 0.694747 -0.345989 -0.63057 0.694746 -0.345989 -0.719085 0.694746 0.0156495 -0.719084 0.694747 0.0156494 -0.614921 0.694745 0.373096 -0.614921 0.694747 0.373094 -0.34599 0.694748 0.630568 -0.345989 0.694746 0.630571 0.0156512 0.694745 0.719086 0.0156488 0.694747 0.719084 -0.373094 0.694747 -0.61492 -0.373095 0.694747 -0.61492 -0.630569 0.694747 -0.345989 -0.63057 0.694747 -0.345989 -0.719084 0.694747 0.015648 -0.719085 0.694746 0.0156488 -0.614921 0.694746 0.373096 -0.61492 0.694748 0.373094 -0.345989 0.694748 0.630569 -0.345989 0.694747 0.63057 0.0156496 0.694747 0.719084 0.0156488 0.694747 0.719084 -0.373096 0.694746 -0.614921 -0.373094 0.694747 -0.61492 -0.630568 0.694748 -0.34599 -0.630571 0.694746 -0.345989 -0.719086 0.694745 0.0156512 -0.719084 0.694747 0.0156488 -0.614921 0.694748 0.373093 -0.614921 0.694745 0.373096 -0.345989 0.694746 0.630572 -0.345989 0.694746 0.63057 0.0156496 0.694746 0.719085 0.0156494 0.694747 0.719084 -0.373094 0.694747 -0.61492 -0.373094 0.694747 -0.61492 -0.630568 0.694748 -0.34599 -0.630571 0.694746 -0.345989 -0.719086 0.694745 0.0156512 -0.719084 0.694747 0.0156488 -0.61492 0.694747 0.373095 -0.61492 0.694747 0.373095 -0.345989 0.694747 0.630569 -0.345989 0.694747 0.63057 0.0156496 0.694747 0.719084 0.0156494 0.694747 0.719084 0.0156488 0.694745 0.719086 0.0439997 0.667939 0.742914 -0.142357 0.706858 0.692882 -0.345989 0.694746 0.630571 -0.319042 0.637681 0.701124 -0.450096 0.706117 0.546637 -0.614921 0.694747 0.373094 -0.631063 0.603564 0.487309 -0.654506 0.704873 0.273453 -0.698945 0.704873 0.120956 -0.755834 0.654557 0.0164492 -0.70816 0.703125 -0.0642214 -0.673291 0.706116 -0.21927 -0.657313 0.661711 -0.360663 -0.348268 0.698075 -0.62562 -0.382507 0.675457 -0.630433 -0.492293 0.706858 -0.507936 -0.597958 0.700861 -0.388896 -0.373093 0.694748 -0.614921 -0.373096 0.694745 -0.614921 -0.630571 0.694745 -0.34599 -0.63057 0.694746 -0.345991 -0.719085 0.694746 0.0156495 -0.719084 0.694747 0.0156491 -0.614921 0.694746 0.373096 -0.61492 0.694747 0.373094 -0.34599 0.694748 0.630568 -0.345989 0.694746 0.630571 0.0156512 0.694745 0.719086 0.0156488 0.694747 0.719084 -0.373094 0.694747 -0.61492 -0.373096 0.694746 -0.614921 -0.63057 0.694746 -0.34599 -0.63057 0.694747 -0.34599 -0.719084 0.694747 0.0156496 -0.719084 0.694747 0.0156488 -0.61492 0.694747 0.373094 -0.614921 0.694746 0.373096 -0.34599 0.694746 0.63057 -0.34599 0.694747 0.63057 0.0156496 0.694747 0.719084 0.0156488 0.694747 0.719084 -0.373094 0.694747 -0.61492 -0.373094 0.694747 -0.61492 -0.630568 0.694748 -0.34599 -0.630571 0.694746 -0.345989 -0.719086 0.694745 0.0156512 -0.719084 0.694747 0.0156488 -0.61492 0.694747 0.373095 -0.61492 0.694747 0.373095 -0.34599 0.694747 0.63057 -0.345989 0.694746 0.63057 0.0156496 0.694746 0.719085 0.0156494 0.694747 0.719084 -0.373094 0.694747 -0.614921 -0.373095 0.694746 -0.614921 -0.630571 0.694746 -0.345989 -0.63057 0.694747 -0.34599 -0.719084 0.694747 0.0156496 -0.719085 0.694746 0.01565 -0.614921 0.694747 0.373094 -0.614921 0.694746 0.373095 -0.345989 0.694746 0.630571 -0.345989 0.694746 0.630571 0.0156496 0.694745 0.719085 0.0156488 0.694746 0.719085 -0.688079 0.706219 0.166737 -0.688079 0.706219 0.166737 -0.657713 0.706219 0.262046 -0.657713 0.706219 0.262046 -0.564986 0.699235 0.43802 -0.564985 0.699237 0.438019 -0.337732 0.699238 0.630082 -0.337733 0.699235 0.630085 -0.0519745 0.699235 0.713 -0.0519745 0.699235 0.713 0.242788 0.699235 0.672402 0.242787 0.699236 0.672401 0.447287 0.704308 0.551257 0.447288 0.704306 0.551258 0.570196 0.704306 0.422882 0.570196 0.704306 0.422882 0.682329 0.699234 0.213305 0.68233 0.699233 0.213305 0.710066 0.699233 -0.082945 0.710062 0.699237 -0.0829438 0.614794 0.699237 -0.364824 0.614796 0.699234 -0.364826 0.413026 0.699234 -0.583508 0.413025 0.699236 -0.583506 0.233184 0.706219 -0.66849 0.233184 0.70622 -0.66849 0.136644 0.70622 -0.694681 0.136644 0.70622 -0.694681 -0.0571086 0.699692 -0.712158 -0.0571089 0.699691 -0.712159 -0.516139 0.699581 -0.494152 -0.51614 0.699581 -0.494153 -0.507515 0.700704 -0.501441 -0.507514 0.700704 -0.501441 -0.656907 0.700704 -0.278365 -0.656907 0.700704 -0.278365 -0.713275 0.700704 -0.0158696 -0.713275 0.700704 -0.0158696 -0.488438 0.70622 -0.512525 -0.488439 0.706218 -0.512526 -0.555796 0.706218 -0.438573 -0.555794 0.706221 -0.438572 -0.661828 0.699236 -0.270282 -0.66183 0.699234 -0.270282 -0.714536 0.699235 0.0225574 -0.714536 0.699235 0.0225574 -0.643465 0.699234 0.311489 -0.643464 0.699234 0.311489 -0.460925 0.699234 0.546462 -0.460924 0.699234 0.546462 -0.25376 0.704305 0.662993 -0.25376 0.704305 0.662994 -0.0811291 0.704305 0.705247 -0.0811291 0.704304 0.705247 0.156437 0.699233 0.697568 0.156437 0.699234 0.697567 0.426864 0.699234 0.573462 0.426863 0.699236 0.573461 0.623345 0.699236 0.350015 0.623346 0.699234 0.350016 0.711845 0.699235 0.0659371 0.711844 0.699235 0.0659371 0.695522 0.706219 -0.132302 0.695521 0.70622 -0.132302 0.669933 0.70622 -0.229003 0.669934 0.706219 -0.229003 0.593089 0.700704 -0.396559 0.593089 0.700704 -0.396559 0.404532 0.700704 -0.587681 0.404532 0.700704 -0.58768 0.158689 0.700704 -0.69558 0.158689 0.700703 -0.695581 0.169879 0.699581 -0.694066 0.169879 0.699581 -0.694066 0.185297 0.701181 -0.688484 0.185297 0.701181 -0.688484 -0.0721752 0.701181 -0.709321 -0.0721752 0.701181 -0.709321 0.199641 0.70622 -0.679262 0.199641 0.70622 -0.679262 0.101918 0.70622 -0.700619 0.101918 0.706219 -0.700619 -0.0746334 0.701409 -0.708841 -0.0746334 0.701409 -0.708841 -0.701049 0.704306 0.111734 -0.701045 0.704309 0.111733 -0.651322 0.704309 0.282362 -0.651324 0.704307 0.282363 -0.525891 0.699235 0.484261 -0.525891 0.699236 0.484261 -0.2832 0.699236 0.656404 -0.2832 0.699234 0.656406 0.0085502 0.699235 0.714841 0.00854985 0.699236 0.71484 0.298819 0.699235 0.649444 0.298819 0.699236 0.649443 0.462337 0.70622 0.536188 0.462338 0.706218 0.536189 0.53329 0.706218 0.465679 0.533289 0.70622 0.465678 0.639974 0.700705 0.315351 0.639975 0.700704 0.315351 0.711212 0.700704 0.0564944 0.711212 0.700704 0.0564944 0.681735 0.700704 -0.210362 0.681734 0.700704 -0.210361 0.686018 0.699581 -0.199913 0.686017 0.699582 -0.199913 0.688018 0.700703 -0.1888 0.688018 0.700704 -0.1888 0.569525 0.700704 -0.429716 0.569524 0.700704 -0.429716 0.370381 0.700704 -0.60978 0.370381 0.700705 -0.609779 0.688079 0.706219 -0.166737 0.68808 0.706218 -0.166738 0.657714 0.706218 -0.262046 0.657713 0.706219 -0.262046 0.555601 0.697261 -0.452917 0.555601 0.697262 -0.452916 0.291436 0.697263 -0.654897 0.291436 0.69726 -0.6549 -0.0354493 0.697259 -0.715942 -0.0354491 0.697261 -0.715941 -0.586883 0.705925 -0.396533 -0.352952 0.898279 -0.261765 -0.532001 0.706763 -0.466327 -0.447287 0.704308 -0.551257 -0.376842 0.796441 -0.47294 -0.50642 0.70709 -0.493521 -0.682329 0.699234 -0.213305 -0.68233 0.699233 -0.213305 -0.710066 0.699233 0.082945 -0.710062 0.699237 0.0829438 -0.614794 0.699237 0.364824 -0.614795 0.699235 0.364825 -0.413025 0.699236 0.583506 -0.413025 0.699236 0.583506 -0.233184 0.706219 0.66849 -0.233184 0.70622 0.66849 -0.136644 0.70622 0.694681 -0.136644 0.70622 0.694681 0.523046 0.700704 0.485219 0.523045 0.700704 0.485219 0.30668 0.700704 0.644175 0.0468856 0.700704 0.711909 0.0468858 0.700704 0.71191 0.188143 0.707068 0.681657 0.330104 0.666291 0.668646 0.516139 0.699581 0.494152 0.516139 0.699581 0.494152 0.507515 0.700704 0.501441 0.507514 0.700704 0.501441 0.656907 0.700704 0.278365 0.656907 0.700704 0.278365 0.713276 0.700703 0.0158696 0.713275 0.700704 0.0158698 0.488438 0.70622 0.512525 0.488439 0.706218 0.512526 0.555796 0.706218 0.438573 0.555794 0.706221 0.438572 0.661828 0.699236 0.270282 0.66183 0.699234 0.270282 0.714536 0.699235 -0.0225574 0.714536 0.699235 -0.0225574 0.643465 0.699234 -0.311489 0.643464 0.699234 -0.311489 0.460925 0.699234 -0.546462 0.460924 0.699234 -0.546462 0.25376 0.704306 -0.662993 0.0748373 0.704687 -0.705561 0.0698386 0.791551 -0.607099 0.162021 0.707088 -0.688313 0.25376 0.704305 -0.662993 -0.104241 0.7038 -0.702709 -0.10424 0.703802 -0.702707 -0.695522 0.706219 0.132302 -0.695522 0.706219 0.132302 -0.669934 0.70622 0.229003 -0.669934 0.706219 0.229003 -0.593089 0.700704 0.396559 -0.593089 0.700704 0.39656 -0.404532 0.700704 0.587681 -0.404531 0.700705 0.587679 -0.158689 0.700705 0.695579 -0.158689 0.700703 0.695581 -0.169879 0.699581 0.694066 -0.169879 0.69958 0.694067 0.342894 0.700705 0.625649 -0.180504 0.700704 0.690241 -0.180504 0.700704 0.69024 0.0771802 0.70164 0.708339 0.0909158 0.67007 0.736709 0.207499 0.707068 0.676017 0.342895 0.700704 0.62565 -0.199641 0.70622 0.679262 -0.199641 0.706219 0.679263 -0.101918 0.706219 0.700619 -0.101918 0.706219 0.700619 0.0968435 0.699235 0.708302 0.0968435 0.699235 0.708302 0.376803 0.699235 0.607528 0.376804 0.699234 0.607529 0.59149 0.699233 0.401512 0.59149 0.699234 0.401512 0.703712 0.699234 0.125941 0.703712 0.699234 0.125941 0.701049 0.704306 -0.111734 0.701048 0.704306 -0.111734 0.651325 0.704306 -0.282363 0.651324 0.704307 -0.282363 0.521436 0.69843 -0.490205 0.521436 0.698429 -0.490205 0.26302 0.69843 -0.665594 0.26302 0.69843 -0.665595 -0.0454831 0.698429 -0.714233 -0.0454823 0.698432 -0.71423 -0.462336 0.706222 -0.536187 -0.462338 0.706218 -0.536189 -0.53329 0.706219 -0.465679 -0.53329 0.706219 -0.465679 -0.639975 0.700704 -0.315351 -0.639975 0.700704 -0.315351 -0.711212 0.700704 -0.0564944 -0.71121 0.700706 -0.0564948 -0.681733 0.700706 0.210361 -0.681735 0.700703 0.210362 -0.686018 0.699581 0.199914 -0.686019 0.699581 0.199914 -0.688018 0.700703 0.1888 -0.688018 0.700704 0.1888 -0.569525 0.700704 0.429716 -0.569524 0.700704 0.429716 -0.370381 0.700704 0.60978 -0.370381 0.700705 0.609779 -0.348271 0.698074 -0.62562 -0.348272 0.69807 -0.625624 -0.58523 0.698071 -0.412556 -0.585229 0.698073 -0.412555 -0.706273 0.698074 -0.117779 -0.706272 0.698075 -0.117778 -0.687431 0.698074 0.200325 -0.687431 0.698075 0.200325 -0.532435 0.698076 0.478751 -0.532436 0.698075 0.478752 -0.271986 0.698075 0.662356 -0.271985 0.698076 0.662355 0.0423346 0.698076 0.714772 0.0423348 0.698077 0.71477 -0.486396 0 -0.873739 -0.517819 -0.0590886 -0.853447 -0.872448 -0.0983607 -0.478706 -0.8383 0 -0.545209 -0.695959 0 -0.718081 -0.922705 0 0.385508 -0.985354 0 0.170522 -0.992791 -0.117891 0.021606 -0.995913 0 -0.0903169 -0.950846 0 -0.309664 -0.775185 -0.201916 0.598597 -0.854942 0 0.518724 -0.635639 0 0.771987 -0.478706 -0.0983589 0.872448 -0.414179 0 0.910195 -0.201248 0 0.97954 0.0217197 -0.0590875 0.998017 0.0591235 0 0.998251 -0.652533 0 -0.757761 -0.817328 0 -0.576173 -0.817328 0 -0.576173 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.379855 0 0.925046 -0.379855 0 0.925046 0.0591246 0 0.998251 0.0591246 0 0.998251 -0.518559 0.0251338 -0.854673 -0.485242 0.0687875 -0.87167 -0.335751 0 -0.941951 0.0217577 0 0.999763 0.058985 0.068686 0.995893 -0.413455 -0.0590915 0.908605 -0.379854 0 0.925046 -0.635644 0 0.771982 -0.741277 -0.0789896 0.666535 -0.791487 0 0.611186 -0.922704 0 0.38551 -0.95627 -0.0888339 0.278669 -0.985354 0 0.17052 -0.995913 0 -0.0903161 -0.986961 -0.0622378 -0.148442 -0.950825 0.00667448 -0.309657 -0.876606 -0.0145069 -0.48099 -0.837104 0.053394 -0.544432 -0.736898 -0.0156431 -0.675823 -0.517818 0.0590898 -0.853448 -0.486394 0 -0.873739 0.0591249 0 0.998251 0.0217197 -0.0590898 0.998016 -0.201254 0 0.979539 -0.414178 0 0.910196 -0.478707 -0.0983617 0.872448 -0.635644 0 0.771983 -0.854941 0 0.518725 -0.775185 -0.201914 0.598598 -0.922704 0 0.38551 -0.974858 0 0.222826 -0.985109 0.0223067 0.170478 -0.999173 -0.0343659 0.0217459 -0.995198 0.0378922 -0.0902512 -0.983629 0 -0.180206 -0.950846 0 -0.309664 -0.872448 -0.0983611 -0.478706 -0.486394 0 -0.873739 -0.517818 -0.0590892 -0.853448 -0.695959 0 -0.718082 -0.8383 0 -0.54521 0.0591246 0 0.998251 0.0217197 -0.0590893 0.998016 -0.201255 0 0.979539 -0.414178 0 0.910196 -0.478707 -0.0983626 0.872447 -0.635645 0 0.771982 -0.732834 0 0.680407 -0.851917 0.0840363 0.51689 -0.789183 -0.0762509 0.609407 -0.941102 0.0424442 0.335449 -0.922703 0 0.385511 -0.985354 0 0.17052 -0.992792 -0.11789 0.021606 -0.995913 0 -0.0903161 -0.950844 0 -0.30967 -0.872447 -0.0983589 -0.478708 -0.486394 0 -0.87374 -0.517818 -0.0590908 -0.853448 -0.695965 0 -0.718075 -0.8383 0 -0.54521 -0.294448 0 0.955668 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.479339 0.0840376 0.873597 -0.479337 0.0840349 0.873598 -0.647877 0 0.761745 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217577 -0.999763 0 0.0217577 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.222826 0 0.974858 0.0216808 0.0840334 0.996227 0.0216818 0.0840349 0.996227 -0.143297 0.0156365 0.989556 -0.413456 -0.0590922 0.908605 -0.379855 0 0.925046 -0.635643 0 0.771984 -0.741277 -0.0789905 0.666535 -0.791487 0 0.611186 -0.922704 0 0.385509 -0.95627 -0.0888331 0.278668 -0.985354 0 0.170521 -0.995913 0 -0.0903172 -0.983297 -0.0789909 -0.163975 -0.950846 0 -0.309664 -0.838299 0 -0.545211 -0.81633 -0.0493929 -0.57547 -0.517819 0.0590916 -0.853447 -0.486394 0 -0.873739 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.854941 0 0.518724 -0.854941 0 0.518724 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.81633 -0.0493935 -0.57547 -0.517818 0.0590905 -0.853447 -0.486394 0 -0.873739 -0.985354 0 0.170523 -0.995913 0 -0.0903178 -0.983297 -0.0789905 -0.163976 -0.950846 0 -0.309664 -0.8383 0 -0.54521 -0.908543 -0.174528 0.379591 -0.960066 0 0.279774 -0.791488 0 0.611185 -0.741276 -0.0789921 0.666535 -0.63564 0 0.771986 -0.379855 0 0.925046 -0.413455 -0.05909 0.908605 0.058985 0.0686858 0.995893 0.0217578 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217578 0 0.999763 0.0217578 0 0.999763 0.122094 0 0.992519 0.0216161 0.113948 0.993252 -0.13895 0 0.990299 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.486394 0 -0.873739 -0.486394 0 -0.873739 -0.817328 0 -0.576173 -0.817328 0 -0.576173 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.379855 0 0.925046 -0.379855 0 0.925046 0.0591246 0 0.998251 0.0591246 0 0.998251 -0.606945 0.707011 -0.362977 -0.252217 0.705954 -0.661827 -0.38067 -0.252869 -0.889465 -0.371172 0.559058 -0.741408 -0.341794 0.707029 -0.619101 -0.436418 0.70519 -0.558791 -0.574898 0.296861 -0.762473 -0.370635 0.69962 -0.61087 -0.356468 0.707104 -0.610684 -0.584897 0.706891 -0.397744 -0.781294 -0.0343143 -0.62322 -0.738174 -0.307 -0.600709 -0.705748 0.33914 -0.622016 -0.50923 0.706862 -0.490948 -0.730438 0.553019 -0.400788 -0.885115 -0.204082 -0.418236 -0.651241 0.705866 -0.278637 -0.695576 0.704515 -0.140829 -0.695578 0.704513 -0.140829 -0.831283 0.551265 0.0712417 -0.923039 -0.382755 0.0386962 -0.999206 0.0333779 0.0217467 -0.706996 0.706771 -0.0251209 -0.699301 0.707072 0.105008 -0.68135 0.704513 0.198553 -0.681351 0.704513 0.198553 -0.582822 0.706773 0.400988 -0.854464 0.0334007 0.518436 -0.799325 -0.382763 0.46322 -0.739416 0.551272 0.386476 -0.646238 0.707072 0.287099 -0.521349 0.705393 0.480226 -0.713373 0.136151 0.687431 -0.458614 0.707014 0.538335 -0.399608 0.705863 0.584868 -0.521876 -0.20408 0.828249 -0.400796 0.552994 0.730452 -0.299913 -0.306992 0.903221 -0.252963 0.706078 0.66141 -0.316938 0.707009 0.63221 0.0155471 0.699616 0.71435 -0.0381705 0.479652 0.876628 -0.0733777 -0.366068 0.927691 -0.103885 0.706615 0.699931 -0.171233 0.706748 0.686431 0.0273999 0.707103 0.70658 0.114978 0.704512 0.700316 0.114978 0.704511 0.700317 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.528073 0.849121 0.0114917 -0.463071 0.849121 -0.254083 -0.273989 0.849121 -0.451578 0.0114943 0.849121 0.528073 -0.254083 0.849121 0.463071 -0.451579 0.849121 0.273988 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.255196 0.851306 0.458424 0.503716 0.851306 -0.146789 0.517522 0.851306 0.086302 0.428827 0.851306 0.302299 -0.0310205 0.851307 -0.52375 0.199298 0.851307 -0.485342 0.390143 0.851307 -0.350807 -0.528073 0.849121 0.0114943 -0.463071 0.849121 -0.254084 -0.273989 0.849121 -0.451579 0.011493 0.849121 0.528073 -0.254085 0.849121 0.463071 -0.451579 0.849121 0.273989 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.528074 0.849121 -0.0114942 0.463071 0.849121 0.254084 0.273988 0.849121 0.451579 -0.011493 0.849121 -0.528073 0.254084 0.849121 -0.463071 0.451579 0.849121 -0.273989 0 -1 0 0 -1 0 -0.906605 0 0.421981 -0.906605 0 0.421981 -0.676286 0 0.73664 -0.676286 0 0.73664 0 1 0 0 1 0 0.800888 0 -0.598814 0.800888 0 -0.598814 0.812891 0 -0.582416 0.812891 0 -0.582416 0 1 0 0 1 0 0.406695 0 -0.913564 0.406695 0 -0.913564 0 -1 0 0 -1 0 -0.246181 0 0.969224 -0.246181 0 0.969224 -0.613201 0 0.789927 -0.613201 0 0.789927 -0.356697 0 0.93422 -0.356697 0 0.93422 0 1 0 0 1 0 0.552071 0 -0.833797 0.552071 0 -0.833797 0 -1 0 0 -1 0 -0.596351 0 0.802724 -0.596351 0 0.802724 -0.336853 0 0.941557 -0.336853 0 0.941557 -0.685248 0 0.728309 -0.685248 0 0.728309 0 1 0 0 1 0 0.0545523 0 -0.998511 0.0545523 0 -0.998511 0.0748301 0 -0.997196 0.0748301 0 -0.997196 0 -1 0 0 -1 0 -0.258015 0 0.966141 -0.258015 0 0.966141 0.131109 0 0.991368 0.131109 0 0.991368 0.421981 0 0.906605 0.421981 0 0.906605 0.736641 0 0.676284 0.736641 0 0.676284 0 1 0 0 1 0 -0.598814 0 -0.800888 -0.598814 0 -0.800888 -0.582418 0 -0.81289 -0.582418 0 -0.81289 0 -1 0 0 -1 0 0.969224 0 0.246181 0.969224 0 0.246181 0.789927 0 0.613201 0.789927 0 0.613201 0.93422 0 0.356697 0.93422 0 0.356697 0 1 0 0 1 0 -0.913564 0 -0.406695 -0.913564 0 -0.406695 0 -1 0 0 -1 0 0.802724 0 0.596351 0.802724 0 0.596351 0.941557 0 0.336853 0.941557 0 0.336853 0.728311 0 0.685247 0.728311 0 0.685247 0 1 0 0 1 0 -0.833797 0 -0.552071 -0.833797 0 -0.552071 0 -1 0 0 -1 0 0.96614 0 0.25802 0.96614 0 0.25802 0.991367 0 -0.131114 0.991367 0 -0.131114 0 1 0 0 1 0 0 -1 0 0 -1 0 -0.998511 0 -0.0545523 -0.998511 0 -0.0545523 -0.997196 0 -0.0748301 -0.997196 0 -0.0748301 -0.451581 -0.84912 0.27399 -0.254085 -0.84912 0.463073 0.0114923 -0.84912 0.528076 -0.273991 -0.84912 -0.451581 -0.463073 -0.84912 -0.254085 -0.528076 -0.84912 0.0114933 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0310207 -0.851305 -0.523753 0.503719 -0.851305 -0.146789 0.390145 -0.851305 -0.350808 0.199299 -0.851305 -0.485345 0.255197 -0.851305 0.458426 0.428828 -0.851305 0.302302 0.517524 -0.851305 0.0863025 0.0310207 -0.851305 0.523753 -0.503719 -0.851305 0.146789 -0.390145 -0.851305 0.350808 -0.199298 -0.851305 0.485345 -0.255197 -0.851305 -0.458425 -0.428828 -0.851305 -0.302302 -0.517524 -0.851305 -0.0863025 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.451581 -0.84912 -0.27399 0.254085 -0.84912 -0.463073 -0.0114919 -0.849119 -0.528076 0.27399 -0.84912 0.451581 0.463073 -0.84912 0.254085 0.528076 -0.84912 -0.0114933 0.982396 0 -0.186808 0.93765 -0.280679 -0.205018 0.970713 0 -0.240242 0.987239 0 -0.159247 0.976913 -0.00392336 -0.213603 0.976913 -0.00392485 -0.213603 0.963606 0 -0.267328 -0.784636 0 0.619957 -0.891969 0 -0.452096 -0.967808 -0.0628522 -0.243714 -0.971773 0 -0.235917 -0.621881 0 0.783112 -0.777778 -0.0628549 0.625389 -0.784635 0 0.619957 -0.97692 0 0.213605 -0.97692 0 0.213605 -0.971773 0 -0.235917 0 -1 0 0 -1 0 0 -1 0 -0.820902 0 0.57107 -0.820902 0 0.57107 -0.984329 0 -0.176341 -0.984329 0 -0.176341 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.998316 -0.00392204 0.0578858 0.999997 0 0.00260078 0.996367 0 0.0851661 0.993591 0 0.113034 0.998316 -0.00392486 0.0578853 0.958192 -0.280679 0.0555589 0.999533 0 0.0305622 -0.922802 0 0.385275 -0.7369 0 -0.676002 -0.866166 -0.0628608 -0.495788 -0.872088 0 -0.489349 -0.810086 0 0.58631 -0.917663 -0.062864 0.392356 -0.922802 0 0.385275 -0.998323 0 -0.0578863 -0.998323 0 -0.0578863 -0.872088 0 -0.489349 0 -1 0 0 -1 0 0 -1 0 -0.944532 0 0.328419 -0.944532 0 0.328419 -0.900239 0 -0.435396 -0.900239 0 -0.435396 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.749392 0 -0.662126 -0.749392 0 -0.662126 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.936441 0 0.350825 0.907668 -0.280686 0.312015 0.954222 0 0.299099 0.926249 0 0.376912 0.945678 -0.00392497 0.325082 0.945678 -0.00392322 0.325081 0.962217 0 0.272283 -0.992528 0 0.122018 -0.527197 0 -0.849743 -0.700284 -0.0628574 -0.711091 -0.707724 0 -0.706489 -0.938233 0 0.346004 -0.98949 -0.0628621 0.130223 -0.992528 0 0.122018 -0.945685 0 -0.325084 -0.945685 0 -0.325084 -0.707724 0 -0.706489 0 -1 0 0 -1 0 0 -1 0 -0.998112 0 0.0614136 -0.998112 0 0.0614136 0.807064 0 0.590464 0.789829 -0.280685 0.545331 0.838141 0 0.545454 0.790221 0 0.612822 0.822904 -0.00392396 0.568167 0.822904 -0.00392255 0.568167 0.853069 0 0.521799 -0.988643 0 -0.150285 -0.278373 0 -0.960473 -0.482466 -0.0628628 -0.873656 -0.490872 0 -0.871232 -0.996792 0 0.0800322 -0.987931 -0.0628585 -0.141566 -0.988643 0 -0.150285 -0.82291 0 -0.568172 -0.82291 0 -0.568172 -0.490872 0 -0.871232 0 -1 0 0 -1 0 0 -1 0 -0.977666 0 -0.210166 -0.977666 0 -0.210166 -0.542962 0 -0.839757 -0.542962 0 -0.839757 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.61783 0 0.786311 0.613412 -0.280685 0.738202 0.659899 0 0.751354 0.595582 0 0.803295 0.639099 -0.00392377 0.769115 0.639099 -0.00392174 0.769115 0.680647 0 0.732612 -0.911435 0 -0.411445 -0.00896006 0 -0.99996 -0.228865 -0.0628515 -0.971427 -0.237612 0 -0.97136 -0.981423 0 -0.191857 -0.913102 -0.0628622 -0.402856 -0.911435 0 -0.411445 -0.639102 0 -0.769122 -0.639102 0 -0.769122 -0.237612 0 -0.97136 0 -1 0 0 -1 0 0 -1 0 -0.884711 0 -0.466141 -0.884711 0 -0.466141 -0.296282 0 -0.955101 -0.296282 0 -0.955101 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.382775 0 0.923841 0.3915 -0.280682 0.876325 0.432715 0 0.901531 0.356754 0 0.934198 0.407894 -0.00392495 0.913021 0.407894 -0.00392444 0.913021 0.457785 0 0.889063 -0.766629 0 -0.642091 0.261194 0 -0.965286 0.0417093 -0.0628609 -0.99715 0.033267 0 -0.999447 -0.893267 0 -0.449526 -0.770551 -0.0628623 -0.63427 -0.766629 0 -0.642091 -0.407897 0 -0.913028 -0.407897 0 -0.913028 0.033267 0 -0.999447 0 -1 0 0 -1 0 0 -1 0 -0.726153 0 -0.687534 -0.726153 0 -0.687534 -0.0275885 0 -0.999619 -0.0275885 0 -0.999619 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.119331 0 0.992855 0.140552 -0.280688 0.949452 0.173439 0 0.984845 0.0915272 0 0.995803 0.146438 -0.00392166 0.989212 0.146438 -0.00392221 0.989212 0.200911 0 0.979609 -0.564966 0 -0.825114 0.511937 0 -0.859023 0.309192 -0.0628613 -0.94892 0.301682 0 -0.953409 -0.738851 0 -0.673869 -0.570853 -0.0628584 -0.818642 -0.564966 0 -0.825114 -0.14644 0 -0.98922 -0.14644 0 -0.98922 0.301682 0 -0.953409 0 -1 0 0 -1 0 0 -1 0 -0.513712 0 -0.857962 -0.513712 0 -0.857962 0.243111 0 -0.969998 0.243111 0 -0.969998 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.495789 0 -0.868443 0.495789 0 -0.868443 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.125878 -0.0039232 0.992038 -0.070821 0 0.997489 -0.152962 0 0.988232 -0.180553 0 0.983565 -0.125878 -0.00392328 0.992038 -0.120819 -0.280677 0.952168 -0.0987018 0 0.995117 -0.321402 0 -0.946943 0.724694 0 -0.689071 0.553741 -0.0628513 -0.830313 0.547722 0 -0.83666 -0.529646 0 -0.848219 -0.328817 -0.0628583 -0.9423 -0.321402 0 -0.946943 0.125878 0 -0.992046 0.125878 0 -0.992046 0.547722 0 -0.83666 0 -1 0 0 -1 0 0 -1 0 -0.263191 0 -0.964744 -0.263191 0 -0.964744 -0.413912 0 0.910317 -0.37323 -0.280684 0.88426 -0.36352 0 0.931586 -0.439233 0 0.898373 -0.388859 -0.00392425 0.921289 -0.388859 -0.00392376 0.921289 -0.337306 0 0.941395 -0.0540026 0 -0.998541 0.883745 0 -0.46797 0.757223 -0.0628611 -0.650125 0.753139 0 -0.657862 -0.281155 0 -0.959662 -0.0623949 -0.0628571 -0.99607 -0.0540026 0 -0.998541 0.388862 0 -0.921296 0.388862 0 -0.921296 0.753139 0 -0.657862 0 -1 0 0 -1 0 0 -1 0 0.00684823 0 -0.999977 0.00684823 0 -0.999977 0.711726 0 -0.702457 0.711726 0 -0.702457 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.276375 0 -0.96105 0.276375 0 -0.96105 0.874854 0 -0.484386 0.874854 0 -0.484386 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.623 -0.00392472 0.782212 -0.578771 0 0.81549 -0.644164 0 0.764887 -0.665326 0 0.746553 -0.623 -0.00392429 0.782212 -0.59796 -0.280687 0.750772 -0.601379 0 0.798964 0.217403 0 -0.976082 0.977225 0 -0.212208 0.904545 -0.062857 -0.42172 0.902699 0 -0.430272 -0.0118309 0 -0.99993 0.208655 -0.0628606 -0.975967 0.217403 0 -0.976082 0.623005 0 -0.782218 0.623005 0 -0.782218 0.902699 0 -0.430272 0 -1 0 0 -1 0 0 -1 0 -0.810936 -0.00392392 0.585122 -0.777333 0 0.629089 -0.826641 0 0.56273 -0.842068 0 0.539372 -0.810936 -0.00392393 0.585122 -0.778343 -0.280679 0.561606 -0.794637 0 0.607085 0.472686 0 -0.881231 0.998239 0 0.0593263 0.98478 -0.0628603 -0.162039 0.985311 0 -0.170772 0.258407 0 -0.966036 0.464232 -0.0628557 -0.883481 0.472686 0 -0.881231 0.810942 0 -0.585126 0.810942 0 -0.585126 0.985311 0 -0.170772 0 -1 0 0 -1 0 0 -1 0 0.525427 0 -0.850839 0.525427 0 -0.850839 0.973098 0 -0.230391 0.973098 0 -0.230391 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.938728 -0.00392551 0.344636 -0.918226 0 0.396058 -0.94781 0 0.318837 -0.956361 0 0.292187 -0.938728 -0.00392366 0.344636 -0.900999 -0.280682 0.330785 -0.928959 0 0.370183 0.69291 0 -0.721024 0.945207 0 0.326472 0.991979 -0.0628661 0.109662 0.994846 0 0.101396 0.509456 0 -0.860497 0.685377 -0.0628544 -0.725471 0.69291 0 -0.721024 0.938735 0 -0.34464 0.938735 0 -0.34464 0.994846 0 0.101396 0 -1 0 0 -1 0 0 -1 0 0.735495 0 -0.67753 0.735495 0 -0.67753 0.999171 0 0.0406977 0.999171 0 0.0406977 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.528073 0.849122 -0.0114942 0.46307 0.849122 0.254084 0.273988 0.849121 0.451579 -0.011493 0.849121 -0.528073 0.254083 0.849121 -0.463071 0.451579 0.849121 -0.273989 -0.528073 0.849121 0.0114917 -0.463071 0.849121 -0.254084 -0.273988 0.849121 -0.451579 0.0114929 0.849121 0.528073 -0.254085 0.849121 0.463071 -0.451578 0.849121 0.273991 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.528074 0.849121 0.0114943 -0.463071 0.849121 -0.254084 -0.273989 0.849121 -0.45158 0.0114917 0.849121 0.528073 -0.254084 0.849121 0.463071 -0.451579 0.849121 0.27399 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.255196 0.851307 0.458423 0.503716 0.851307 -0.146789 0.517521 0.851307 0.0863018 0.428825 0.851307 0.302301 -0.0310205 0.851306 -0.523751 0.199298 0.851307 -0.485343 0.390143 0.851307 -0.350806 -0.486396 0 -0.873739 -0.486396 0 -0.873739 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.960066 0 0.279773 -0.960066 0 0.279773 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591254 0 0.998251 0.0591254 0 0.998251 -0.255199 0.851303 -0.458428 -0.503721 0.851303 0.14679 -0.517527 0.851303 -0.0863037 -0.428831 0.851303 -0.302304 0.0310215 0.851304 0.523755 -0.1993 0.851304 0.485347 -0.390147 0.851304 0.35081 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.528079 0.849118 -0.0114925 0.463076 0.849118 0.254086 0.273992 0.849118 0.451583 -0.011493 0.849117 -0.52808 0.254085 0.849118 -0.463077 0.451585 0.849118 -0.273991 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217578 0.999763 0 -0.0217578 0.854943 0 -0.518722 0.854943 0 -0.518722 0.481036 0 -0.876701 0.481036 0 -0.876701 -0.0217586 0 -0.999763 -0.0217586 0 -0.999763 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.8767 0 -0.481039 -0.8767 0 -0.481039 -0.999763 0 0.0217587 -0.999763 0 0.0217587 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481041 0 0.876698 -0.481041 0 0.876698 0.0217586 0 0.999763 0.0217586 0 0.999763 -0.528079 0.849118 0.011493 -0.463076 0.849117 -0.254087 -0.273993 0.849117 -0.451584 0.011493 0.849118 0.528078 -0.254088 0.849118 0.463075 -0.451583 0.849118 0.273993 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.255199 0.851304 0.458427 0.503721 0.851303 -0.146792 0.517527 0.851303 0.0863031 0.42883 0.851304 0.302304 -0.0310215 0.851303 -0.523757 0.199301 0.851303 -0.485348 0.390148 0.851303 -0.35081 0.486397 0 0.873738 0.486397 0 0.873738 0.817327 0 0.576174 0.817327 0 0.576174 0.986379 0 0.164489 0.986379 0 0.164489 0.960065 0 -0.279777 0.960065 0 -0.279777 0.743601 0 -0.668624 0.743601 0 -0.668624 0.379856 0 -0.925046 0.379856 0 -0.925046 -0.0591253 0 -0.998251 -0.0591253 0 -0.998251 -0.258509 0 -0.966009 -0.258509 0 -0.966009 0 1 0 0 1 0 0.590645 0 0.806932 0.590645 0 0.806932 0 -1 0 0 -1 0 -0.451769 0 -0.892135 -0.451769 0 -0.892135 -0.744061 0 -0.668112 -0.744061 0 -0.668112 -0.969224 0 -0.246181 -0.969224 0 -0.246181 -0.789924 0 -0.613205 -0.789924 0 -0.613205 -0.934222 0 -0.356692 -0.934222 0 -0.356692 0 1 0 0 1 0 0.913564 0 0.406695 0.913564 0 0.406695 0 -1 0 0 -1 0 -0.802721 0 -0.596355 -0.802721 0 -0.596355 -0.941559 0 -0.336847 -0.941559 0 -0.336847 -0.728311 0 -0.685247 -0.728311 0 -0.685247 0 1 0 0 1 0 0.833797 0 0.552071 0.833797 0 0.552071 0 -1 0 0 -1 0 -0.96614 0 -0.25802 -0.96614 0 -0.25802 -0.991368 0 0.131109 -0.991368 0 0.131109 0 1 0 0 1 0 0.998511 0 0.054557 0.998511 0 0.054557 0.997196 0 0.0748301 0.997196 0 0.0748301 0 -1 0 0 -1 0 0 1 0 0 1 0 -0.800889 0 0.598812 -0.800889 0 0.598812 -0.812889 0 0.582419 -0.812889 0 0.582419 0 -1 0 0 -1 0 0.906605 0 -0.421981 0.906605 0 -0.421981 0.676284 0 -0.736641 0.676284 0 -0.736641 0 1 0 0 1 0 -0.406695 0 0.913564 -0.406695 0 0.913564 0 -1 0 0 -1 0 0.246175 0 -0.969225 0.246175 0 -0.969225 0.613205 0 -0.789924 0.613205 0 -0.789924 0.356697 0 -0.93422 0.356697 0 -0.93422 0 1 0 0 1 0 -0.552071 0 0.833797 -0.552071 0 0.833797 0 -1 0 0 -1 0 0.596355 0 -0.802721 0.596355 0 -0.802721 0.336846 0 -0.94156 0.336846 0 -0.94156 0.685248 0 -0.728309 0.685248 0 -0.728309 0.26867 0 -0.963232 0.26867 0 -0.963232 -0.0982117 0 -0.995166 -0.0982117 0 -0.995166 -0.30088 0 -0.953662 -0.30088 0 -0.953662 0 1 0 0 1 0 -0.0646969 0 0.997905 -0.0646969 0 0.997905 0 -1 0 0 -1 0 -0.451581 -0.84912 0.27399 -0.254085 -0.84912 0.463073 0.0114919 -0.84912 0.528075 -0.273991 -0.849119 -0.451581 -0.463073 -0.849119 -0.254085 -0.528076 -0.849119 0.0114926 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0310207 -0.851305 -0.523753 0.503718 -0.851305 -0.146789 0.390145 -0.851305 -0.350808 0.199299 -0.851305 -0.485345 0.255197 -0.851306 0.458425 0.428828 -0.851305 0.302301 0.517524 -0.851305 0.0863025 -0.0103769 0 -0.999946 -0.0103769 0 -0.999946 0.0449634 0 -0.998989 -0.0103766 -0.00392471 -0.999938 -0.0103768 -0.00392359 -0.999938 -0.0656696 0 -0.997841 0.640211 0 0.768199 0.466123 0 0.88472 0.466123 0 0.88472 0.472883 -0.0570001 0.87928 0 -1 0 0 -1 0 0.392108 0 0.919919 0.392108 0 0.919919 -0.372933 0 0.927858 -0.372933 0 0.927858 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.624122 0 0.781327 -0.425943 -0.0657708 0.902356 -0.419138 0 0.907923 0.0420178 0 0.999117 0.0420178 0 0.999117 -0.419138 0 0.907923 -0.609438 0 0.792834 -0.609438 0 0.792834 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.811794 0 0.583944 -0.679973 -0.0560787 0.731089 -0.674773 0 0.738025 0.0769341 0 0.997036 0.0769341 0 0.997036 -0.329798 0 0.944052 -0.329798 0 0.944052 -0.674773 0 0.738025 0.259788 -0.00392485 -0.965658 0.205963 0 -0.97856 0.31279 0 -0.949822 0.259789 -0.00392248 -0.965658 0.25979 0 -0.965665 0.25979 0 -0.965665 0.341312 0 0.93995 0.341312 0 0.93995 0.40416 -0.156579 0.901187 0.349317 0 0.937005 0 -1 0 0 -1 0 0 -1 0 0.129382 0 0.991595 0.129382 0 0.991595 0.534012 0 -0.845477 0.490161 -0.28068 -0.825203 0.486986 0 -0.87341 0.557444 0 -0.830215 0.510686 -0.00392215 -0.859758 0.510686 -0.00392498 -0.859758 0.462334 0 -0.886706 -0.082468 0 0.996594 -0.939238 0 0.343265 -0.838695 -0.0628642 0.54096 -0.835703 0 0.549182 0.147843 0 0.989011 -0.0738183 -0.0628512 0.995289 -0.082468 0 0.996594 -0.51069 0 0.859765 -0.51069 0 0.859765 -0.835703 0 0.549182 0 -1 0 0 -1 0 0 -1 0 -0.142955 0 0.989729 -0.142955 0 0.989729 -0.800739 0 0.599013 -0.800739 0 0.599013 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.742316 0 -0.67005 0.694621 -0.280684 -0.662358 0.70457 0 -0.709634 0.760787 0 -0.649002 0.723709 -0.00392463 -0.690095 0.723708 -0.00392228 -0.690095 0.684448 0 -0.729061 -0.348288 0 0.937388 -0.997019 0 0.0771622 -0.953544 -0.0628552 0.294624 -0.95288 0 0.303347 -0.124442 0 0.992227 -0.339606 -0.0628596 0.938465 -0.348288 0 0.937388 -0.723715 0 0.690099 -0.723715 0 0.690099 -0.95288 0 0.303347 0 -1 0 0 -1 0 0 -1 0 -0.404681 0 0.914458 -0.404681 0 0.914458 -0.93266 0 0.360757 -0.93266 0 0.360757 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.883057 -0.00392208 -0.46925 0.855767 0 -0.517361 0.895566 0 -0.444928 0.907674 0 -0.419677 0.883057 -0.00392477 -0.46925 0.847566 -0.280679 -0.450391 0.8699 0 -0.493228 -0.588277 0 0.808659 -0.980866 0 -0.194686 -0.997673 -0.0628541 0.0264345 -0.999387 0 0.0350128 -0.387513 0 0.921864 -0.580207 -0.0628655 0.812039 -0.588277 0 0.808659 -0.883063 0 0.469254 -0.883063 0 0.469254 -0.999387 0 0.0350128 0 -1 0 0 -1 0 0 -1 0 -0.63638 0 0.771375 -0.63638 0 0.771375 -0.995405 0 0.095752 -0.995405 0 0.095752 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.951142 0 0.308755 0.951142 0 0.308755 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.996899 -0.00392214 0.0785903 -0.991037 0 0.133591 -0.998683 0 0.0512978 -0.999728 0 0.023307 -0.996899 -0.00392526 0.0785908 -0.95683 -0.280688 0.0754319 -0.994385 0 0.105826 0.861745 0 -0.507341 0.822091 0 0.569356 0.925608 -0.0628575 0.373227 0.930598 0 0.366042 0.722719 0 -0.691142 0.855691 -0.062858 -0.513656 0.861745 0 -0.507341 0.996907 0 -0.0785918 0.996907 0 -0.0785918 0.930598 0 0.366042 0 -1 0 0 -1 0 0 -1 0 0.89102 0 -0.453965 0.89102 0 -0.453965 -0.981135 -0.00392221 -0.193284 -0.990329 0 -0.138741 -0.975489 0 -0.220046 -0.968946 0 -0.247272 -0.981135 -0.00392466 -0.193284 -0.941701 -0.280685 -0.185515 -0.986062 0 -0.16638 0.966668 0 -0.256032 0.637991 0 0.770044 0.790589 -0.0628592 0.609113 0.797333 0 0.60354 0.882382 0 -0.470534 0.962542 -0.0628605 -0.263746 0.966668 0 -0.256032 0.981142 0 0.193287 0.981142 0 0.193287 0.797333 0 0.60354 0 -1 0 0 -1 0 0 -1 0 0.980456 0 -0.196739 0.980456 0 -0.196739 0.832571 0 0.553918 0.832571 0 0.553918 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.892605 -0.00392313 -0.450823 -0.916178 0 -0.400772 -0.879948 0 -0.47507 -0.866313 0 -0.499502 -0.892605 -0.00392301 -0.450823 -0.856727 -0.28069 -0.432703 -0.904607 0 -0.426246 0.999898 0 0.0142672 0.406572 0 0.913619 0.596935 -0.062861 0.799824 0.604932 0 0.796277 0.976605 0 -0.215042 0.998006 -0.0628662 0.00572461 0.999898 0 0.0142672 0.892611 0 0.450828 0.892611 0 0.450828 0.604932 0 0.796277 0 -1 0 0 -1 0 0 -1 0 0.997179 0 0.0750617 0.997179 0 0.0750617 0.652255 0 0.757999 0.652255 0 0.757999 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.737879 0 -0.674933 -0.737879 0 -0.674933 -0.699413 0 -0.714718 -0.737874 -0.00392407 -0.674927 -0.737874 -0.00392336 -0.674927 -0.77408 0 -0.633088 0.965609 0 0.259997 0.470721 0 0.882282 0.470721 0 0.882282 0.785316 0 0.619095 0.785316 0 0.619095 0.965609 0 0.259997 0.966269 -0.0560702 0.251355 0.998405 0 0.0564577 0 -1 0 0 -1 0 0 -1 0 0.939942 0 0.341335 0.939942 0 0.341335 0.42356 0 0.905868 0.42356 0 0.905868 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0.145013 0 0.98943 0.208694 -0.0184696 0.977807 0.217065 0 0.976157 0.217065 0 0.976157 -0.528418 -0.00392208 -0.848975 -0.574553 0 -0.818468 -0.480645 0 -0.876915 -0.528418 -0.00392434 -0.848975 -0.528422 0 -0.848982 -0.528422 0 -0.848982 0.841263 0 0.540627 0.501288 0 0.86528 0.501288 0 0.86528 0.841262 0 0.540627 0.844012 -0.0657813 0.532275 0.946162 0 0.323695 0 -1 0 0 -1 0 0.812999 0 0.582265 0.812999 0 0.582265 0.163451 0 0.986551 0.163451 0 0.986551 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 -0.12731 0 0.991863 0.0734969 -0.0570009 0.995665 0.0821213 0 0.996622 0.0821213 0 0.996622 0 -1 0 -0.390197 0 0.920731 -0.233696 -0.0467583 0.971185 -0.22565 0 0.974209 0.110103 0 0.99392 0.110103 0 0.99392 -0.22565 0 0.974209 -0.279772 -0.00392353 -0.960059 -0.332446 0 -0.943122 -0.22622 0 -0.974076 -0.279772 -0.00392523 -0.960059 -0.279774 0 -0.960066 -0.279774 0 -0.960066 0.713672 0 0.70048 0.441072 0 0.897472 0.441072 0 0.897472 0.713672 0 0.70048 0.718834 -0.0467543 0.693607 0.823725 0 0.56699 0 -1 0 0 -1 0 0 -1 0 0.625753 0 0.780021 0.625753 0 0.780021 -0.108789 0 0.994065 -0.108789 0 0.994065 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0649182 -0.997876 -0.00541147 0.0649183 -0.997876 -0.00541993 0.156831 -0.987504 -0.0155009 -0.486333 -0.873743 -0.00731895 -0.176016 -0.984262 -0.0156925 -0.0876569 -0.996149 -0.00193869 -0.0873026 -0.996098 -0.0129221 -0.0873025 -0.996098 -0.0129211 -0.0431174 -0.999026 -0.00933572 -0.0346783 -0.999371 -0.00741131 -0.074268 -0.99715 -0.0132487 -0.0737928 -0.997207 -0.0114979 -0.152706 -0.988097 -0.0185893 -0.158029 -0.987406 -0.00750835 -0.170627 -0.985027 0.0246633 -0.218357 -0.975603 0.0227761 -0.265003 -0.962452 0.058819 -0.0926559 -0.992149 0.0839928 0.15197 -0.988311 -0.0121011 0.483429 -0.0707919 -0.872516 0.462 -0.228391 -0.856968 0.47082 -0.194854 -0.860442 0.449108 -0.439843 -0.777714 0.450195 -0.436333 -0.779062 0.419934 -0.549641 -0.722184 0.400492 -0.604042 -0.689013 0.379968 -0.703787 -0.600257 0.321389 -0.786502 -0.527374 0.29523 -0.838487 -0.458016 0.244346 -0.892742 -0.378559 0.167831 -0.972581 -0.160993 0.0319866 -0.970588 -0.238611 0.440333 -0.193908 -0.876645 0.440364 -0.193943 -0.876622 0.404467 -0.433727 -0.805163 0.328906 -0.556693 -0.762833 0.151662 -0.194082 -0.969191 0.151463 -0.193896 -0.969259 0.128555 -0.553798 -0.822667 0.128631 -0.553852 -0.822619 0.0857842 -0.831668 -0.548607 0.0856941 -0.831636 -0.54867 0.0299181 -0.981026 -0.191556 0.0053368 -0.979051 -0.203544 0.0225985 -0.969268 -0.244966 0.0957495 -0.976984 -0.190615 0.204019 -0.890738 -0.406155 0.168833 -0.834723 -0.524149 0.278867 -0.783678 -0.555051 0.358778 -0.601112 -0.714103 -1.64868e-06 -0.9949 -0.100864 0.00245634 -0.981462 -0.191641 -1.626e-05 -0.0666389 -0.997777 0.00228315 -0.196353 -0.980531 0.00253416 -0.55843 -0.829548 -0.000778681 -0.465077 -0.88527 0.000577583 -0.24227 -0.970209 0.000261848 -0.961713 -0.274059 -0.000331952 -0.916095 -0.400962 0.00169358 -0.834745 -0.550635 -0.000109307 -0.810336 -0.585966 4.54836e-05 -0.643359 -0.765564 -0.141181 -0.24058 -0.960307 -0.0975105 -0.641354 -0.761023 -0.0856296 -0.808256 -0.582572 -0.988966 -0.0135702 -0.147521 -0.988719 -0.135476 -0.0638837 -0.985343 -0.161521 -0.0548627 -0.987685 -0.109328 -0.111921 -0.851009 -0.313192 -0.421538 -0.841996 -0.470746 -0.263518 -0.845545 -0.46347 -0.265046 -0.558299 -0.65538 -0.508704 -0.0942534 -0.0664782 -0.993326 -0.238932 -0.194682 -0.95132 -0.28822 -0.192245 -0.938068 -0.844741 -0.112605 -0.523195 -0.564047 -0.172472 -0.80753 -0.562883 -0.173567 -0.808107 -0.284596 -0.191182 -0.939391 -0.276782 -0.538002 -0.796207 -0.0125822 -0.556581 -0.830698 -0.390418 -0.431707 -0.813144 -0.602282 -0.681332 -0.415986 -0.559641 -0.742099 -0.368905 -0.551912 -0.804118 -0.220876 -0.363235 -0.928758 -0.0739558 -0.54618 -0.835522 -0.0599244 -0.594202 -0.793836 -0.129419 -0.830015 -0.554199 -0.062753 -0.83541 -0.545342 -0.0685044 -0.981479 -0.190508 0.0201389 -0.98403 -0.177684 0.0106106 -0.1822 -0.978642 -0.0951945 -0.184048 -0.978112 -0.0970783 -0.193303 -0.944693 -0.264933 -0.198934 -0.941482 -0.272099 -0.185372 -0.901711 -0.390581 -0.209904 -0.870074 -0.445995 -0.157273 -0.817177 -0.554516 -0.278366 -0.753401 -0.595735 -0.285882 -0.539121 -0.792225 -0.561659 -0.469849 -0.681014 -0.555386 -0.476453 -0.681571 -0.848936 -0.312096 -0.426501 -0.854094 -0.124205 -0.505071 -0.993064 -0.0202212 -0.115822 -0.983206 -0.0842386 -0.161897 0.157762 -0.984669 -0.0744199 0.300248 -0.941109 -0.15545 0.110343 -0.992408 -0.054318 0.714377 -0.604423 -0.352615 0.645947 -0.69404 -0.317901 0.483627 -0.842072 -0.238787 0.531604 -0.803923 -0.266656 0.420077 -0.883319 -0.208043 0.819495 -0.39734 -0.412976 0.757086 -0.540177 -0.367464 0.881497 -0.180901 -0.436163 0.882271 -0.175608 -0.436761 0.895541 -0.0605202 -0.440845 0.91457 -0.0432468 -0.402108 0.882794 -0.179909 -0.433944 0.916055 -0.120103 -0.382646 0.926189 -0.0781971 -0.368863 0.956481 -0.0427658 -0.288643 0.969603 -0.113214 -0.216914 0.962263 -0.125039 -0.241692 0.966966 -0.128066 -0.2204 0.957965 -0.195083 -0.210348 0.870162 -0.434965 -0.231569 0.813571 -0.555581 -0.171556 0.526785 -0.829513 -0.18549 0.903151 -0.30994 -0.297079 0.708233 -0.443331 -0.549421 0.851795 -0.464507 -0.242236 0.710484 -0.571888 -0.410069 0.744256 -0.613308 -0.264454 0.804706 -0.574367 -0.150167 0.529224 -0.774765 -0.345919 0.570389 -0.80331 -0.171315 0.561029 -0.806974 -0.184496 0.292381 -0.943386 -0.156642 0.934024 -0.215809 -0.28465 0.926224 -0.225845 -0.301833 0.8392 -0.438388 -0.321808 0.848167 -0.449675 -0.280009 0.744204 -0.607633 -0.277384 0.765556 -0.621001 -0.168172 0.426748 -0.874179 -0.231726 0.0814848 -0.99503 -0.0572296 0.307714 -0.947562 -0.0862438 0.271463 -0.958284 -0.0894424 0.45177 -0.88351 -0.123755 0.665438 -0.738837 -0.106356 0.633684 -0.730299 -0.255162 0.900539 -0.385593 -0.200868 0.889273 -0.378132 -0.257314 0.947423 -0.177972 -0.265923 0.918851 -0.213216 -0.332042 0.922246 0 -0.386604 0.943886 0.000210581 -0.330272 0.962086 0 -0.272746 0.96466 0.110719 -0.239109 0.928034 0.0320713 -0.371112 0.940913 0.0591941 -0.333434 0.94901 0.0269725 -0.31409 0.943659 0.0219259 -0.330193 -0.908517 0.417798 -0.00637559 -0.835935 0.184331 -0.516947 -0.702821 0.178726 -0.688549 -0.169807 0.975336 -0.141014 -0.328896 0.94321 -0.0467143 -0.284811 0.95763 -0.0427411 -0.103173 0.988537 -0.110226 -0.162537 0.974136 -0.156973 -0.111204 0.975071 -0.192015 -0.0969748 0.984861 -0.14368 -0.0747645 0.943624 -0.322466 -0.05257 0.982145 -0.18063 0.0339962 0.965529 -0.258065 0.00504634 0.979625 -0.20077 0.0636721 0.984539 -0.163182 0.170613 0.953834 -0.247167 0.0637462 0.993612 -0.0931196 0.118046 0.987643 -0.103083 0.473722 0.842175 -0.257542 0.45682 0.854287 -0.248012 0.334535 0.840241 -0.42671 0.330209 0.844718 -0.421204 0.154701 0.83008 -0.535757 0.152877 0.834549 -0.529298 -0.0485267 0.822118 -0.567246 -0.0477998 0.826123 -0.561459 -0.246271 0.817931 -0.519941 -0.244105 0.820898 -0.516274 -0.411871 0.817911 -0.401727 -0.410394 0.819176 -0.400659 -0.522432 0.821321 -0.229119 0.0872406 0.0850625 -0.992549 0.277307 0.096728 -0.9559 0.345417 -0.575936 -0.740935 0.928344 0.086181 -0.361594 0.870832 -0.348795 -0.3464 0.786345 0.235296 -0.571224 0.655126 -0.431413 -0.620236 0.567476 0.392528 -0.723804 0.447381 -0.121027 -0.886117 -0.0498516 -0.0273158 -0.998383 0.052369 -0.366739 -0.928849 -0.0223569 0.25947 -0.965492 0.339512 0.281826 -0.897389 0.34433 0.261725 -0.90163 0.654514 0.287645 -0.699194 0.660973 0.266787 -0.701384 0.87233 0.291317 -0.392651 0.87584 0.280706 -0.392567 -0.972408 0.184205 0.14315 -0.997835 -0.0379093 0.0537356 -0.978041 -0.207349 0.0210183 -0.977386 0.187224 -0.098302 -0.912142 0.175944 -0.370189 -0.932636 -0.155033 -0.325813 -0.863408 0.138995 -0.484982 -0.191316 0.975567 -0.108014 -0.1562 0.984018 -0.0854995 -0.523658 0.820466 -0.229387 -0.562598 0.826495 -0.0197375 -0.627513 0.778251 -0.0235008 -0.702569 0.179884 -0.688505 -0.525989 0.183835 -0.830386 -0.388115 -0.0634462 -0.919424 -0.356748 0.176281 -0.917418 -0.160402 0.186417 -0.969288 0.748388 0.559575 -0.356077 0.744069 0.566982 -0.353401 0.557342 0.545324 -0.626092 0.551915 0.558989 -0.618807 0.280021 0.536267 -0.796245 0.277908 0.54954 -0.787892 -0.0366502 0.530109 -0.847137 -0.0355153 0.54079 -0.840408 -0.346477 0.527999 -0.775352 -0.344169 0.534432 -0.771965 -0.606323 0.529839 -0.592995 -0.6056 0.531146 -0.592564 -0.779696 0.534547 -0.326089 -0.782131 0.530818 -0.326348 -0.841414 0.540361 -0.00576477 -0.806272 0.591387 -0.013666 0.873943 0.239215 -0.423084 0.698321 0.0861864 -0.710577 0.697526 0.0857897 -0.711405 0.692929 0.124928 -0.710101 0.639066 0.0497347 -0.767542 0.740904 0.182584 -0.646316 0.92744 0.372169 -0.0366866 0.91879 0.393646 0.0294626 0.893891 0.415006 0.169497 0.839766 0.436846 0.322426 0.786908 0.449824 0.422415 0.748119 0.447258 0.490182 0.818916 0.298165 -0.490382 0.845311 0.341981 -0.410486 0.88644 0.262159 -0.38144 0.923988 0.321464 -0.207139 0.859591 0.401605 -0.315938 0.851519 0.523694 -0.0256747 0.850731 0.525283 -0.0182691 0.71414 0.604999 0.352109 0.711581 0.60488 0.357454 0.85385 0.130715 0.503839 0.940899 0.240442 -0.238532 -0.25175 0.179082 0.951079 0.549977 0.754959 0.357157 0.50812 0.773733 0.378353 0.615956 0.7081 0.345243 0.244715 0.708117 0.662333 0.25604 0.52088 0.814326 0.311288 0.558628 0.768788 0.339007 0.530251 0.777116 0.387806 0.59394 0.70487 0.456479 0.550923 0.698649 0.462262 0.624957 0.62908 0.594891 0.582122 0.554291 0.582259 0.608275 0.539423 0.684054 0.613821 0.394073 0.720151 0.571472 0.39345 0.739477 0.613286 0.277586 0.803386 0.550614 0.226706 0.787609 0.593094 0.167067 0.8304 0.550276 0.0873662 0.765684 0.126423 0.63067 0.551131 -0.485102 0.678919 0.437938 -0.645846 0.625374 -0.343903 -0.882407 0.321075 -0.160501 -0.692339 0.703496 0.460366 0.0736943 0.884665 0.576331 0.0370419 0.816377 -0.180541 -0.00717195 0.983541 -0.554251 -0.511404 0.656713 0.0727169 0.0825812 0.993928 0.15855 0.0305791 0.986877 -0.231075 0.0535008 0.971464 -0.292556 0.116713 0.949099 -0.46373 -0.00699398 0.885949 0.581998 0.169759 0.795274 0.375095 0.230227 0.897942 0.313018 0.101595 0.944298 0.0935231 0.236435 0.967136 -0.045652 0.103176 0.993615 -0.166367 0.22621 0.959766 -0.32995 0.118388 0.936546 0.963051 0.0831518 -0.256161 0.58236 -0.397025 -0.709386 0.872701 0.00309855 -0.488246 0.784877 0.136088 -0.604524 0.684723 -0.0171816 -0.728601 0.839301 0.267164 -0.473494 0.860217 0.368955 -0.351994 0.863696 0.395332 -0.312638 0.983003 0.0304832 -0.181039 0.363124 -0.795996 -0.484285 0.570266 -0.688446 -0.448151 0.988699 0.0760601 0.129189 0.964971 0.0302358 0.260607 0.852076 -0.452523 0.263038 0.756494 -0.636148 0.151765 0.945461 0.162014 0.282588 0.969802 0.236049 0.0613523 0.995365 0.0951976 -0.0136224 0.940881 0.248037 -0.230694 0.928417 0.104956 -0.356406 0.834333 0.254479 -0.489008 0.778663 0.126223 -0.614615 0.536631 0.645902 0.542991 0.723301 0.685893 0.0799131 0.479019 0.679447 0.555781 0.495361 0.735004 0.463019 0.47558 0.747054 0.464472 0.472872 0.767007 0.433696 0.46102 0.789469 0.405216 0.467953 0.787326 0.40142 0.458916 0.81174 0.361213 0.474801 0.797528 0.372174 0.488774 0.798224 0.352049 0.47469 0.807526 0.350101 0.537573 0.766964 0.350402 -0.0782096 0.302008 0.950092 0.0315082 0.394259 0.918459 0.131 0.292292 0.947314 0.218248 0.408178 0.88643 0.393295 0.299545 0.869248 0.418181 0.411634 0.809742 0.660727 0.334286 0.672081 0.651797 0.373276 0.66017 0.829367 0.382551 0.407191 0.858244 0.323476 0.398474 0.89847 0.406445 0.165993 0.948762 0.30367 0.0873774 0.9082 0.413084 -0.0673436 0.919075 0.377284 -0.113832 0.857578 0.474227 -0.199169 0.803578 0.593097 0.0499809 0.824453 0.564056 -0.0460205 0.660014 0.682561 0.313833 0.57132 0.593317 0.56707 -0.508182 0.0557852 0.859441 -0.357428 0.157806 0.920512 0.692381 0.451178 0.563069 0.558804 0.449598 0.69685 0.162035 0.388409 0.907129 0.429882 0.473505 0.768762 0.304442 0.442836 0.843334 0.253921 0.424665 0.869013 -0.071822 0.29243 0.953586 0.114788 0.38676 0.915008 -0.259183 0.189845 0.946986 -0.0882207 0.287647 0.953665 -0.0374319 0.311463 0.949521 -0.415928 0.0895537 0.904978 -0.0366301 0.0509617 -0.998029 0.928308 0.224533 -0.296361 0.906655 0.225147 -0.356772 -0.0475559 0.0277458 -0.998483 -0.0210097 0.0394848 -0.998999 0.0682024 0.0654605 -0.995522 0.284537 0.110941 -0.952224 0.353617 0.129051 -0.926445 0.856734 0.216725 -0.468015 0.767118 0.203602 -0.608338 0.69533 0.195107 -0.691701 0.625464 0.179163 -0.759405 0.489657 0.153451 -0.858306 -0.0360066 0.0780325 -0.9963 -0.0403985 0.0755302 -0.996325 0.322517 0.222185 -0.920118 0.323865 0.222928 -0.919464 0.648297 0.338173 -0.682166 0.649916 0.339045 -0.68019 0.852168 0.393288 -0.345158 0.853196 0.393841 -0.341975 0.755383 0.570933 -0.321608 0.755808 0.571215 -0.320105 0.566531 0.491827 -0.661173 0.566889 0.492101 -0.660662 0.269867 0.323924 -0.906777 0.26993 0.323975 -0.90674 0.0190038 0.162602 -0.986509 -0.0559372 0.104898 -0.992909 -0.138339 0.0542252 -0.988899 0.604953 0.741923 -0.289106 0.646553 0.753515 -0.119103 0.471037 0.865535 -0.170218 0.481654 0.850232 -0.212402 0.517678 0.833594 -0.192694 0.514718 0.790832 -0.331135 0.527417 0.800759 -0.283929 0.671259 0.60187 0.432624 0.668471 0.657829 0.346998 0.6999 0.635344 0.326311 0.664544 0.700156 0.261081 0.739191 0.656067 0.152226 0.698994 0.703153 0.130319 0.73409 0.676925 -0.0537089 0.722304 0.689599 -0.0522447 0.676736 0.694923 -0.243129 0.694413 0.671237 -0.259291 0.596003 0.703322 -0.387452 0.61138 0.653564 -0.446171 0.535415 0.688895 -0.488626 0.514686 0.63633 -0.574615 0.522204 0.631086 -0.573615 0.47358 0.601044 -0.643792 0.847921 -0.278247 0.451229 0.941302 0.150389 -0.302214 0.984202 0.144523 -0.102275 0.947918 -0.31851 0.00196043 0.985563 0.138366 0.0975745 0.943628 0.163912 0.287573 0.863537 0.0517558 0.501623 0.747639 0.112501 0.654507 0.421973 -0.447424 0.788511 0.614864 0.309683 0.725286 0.352603 -0.0141766 0.935666 0.857185 0.20639 0.471844 0.748099 0.260364 0.610376 0.71785 0.140199 0.681935 0.54946 0.257514 0.794846 0.449837 0.130089 0.883586 -0.124408 0.0388407 -0.991471 -0.366294 -0.308395 -0.877908 0.424838 0.102551 -0.899442 -0.162022 -0.624564 -0.763982 0.214886 0.030448 -0.976165 0.0951363 0.110026 -0.989365 0.541468 0.0519428 -0.839115 0.375187 -0.51454 -0.771028 0.209615 -0.741418 -0.637464 0.739462 0.0885498 -0.667349 0.848895 0.0546482 -0.525729 0.868145 -0.242001 -0.433313 0.822804 -0.347025 -0.450075 0.835503 0.205999 -0.509411 0.674747 0.249382 -0.69464 0.669087 0.151723 -0.727532 0.413388 0.26638 -0.870719 0.358301 0.132023 -0.924224 0.170373 0.259064 -0.950715 0.0530431 0.124307 -0.990825 0.647804 0.758255 0.0734768 0.548037 0.814589 -0.190002 0.571693 0.816798 0.0775156 0.485625 0.87406 -0.013707 0.489362 0.872044 -0.00796761 0.587074 0.809274 0.0204574 0.435991 0.897979 -0.0595432 0.623484 0.77332 -0.11508 0.43236 0.896 -0.101236 0.471957 0.869846 -0.143617 0.458344 0.874065 -0.161033 0.585869 0.341909 0.734749 0.621022 0.454817 0.638337 0.750344 0.363551 0.5521 0.737051 0.468435 0.48716 0.879785 0.385483 0.278173 0.85262 0.454559 0.25771 0.909968 0.412424 -0.0431936 0.901632 0.430487 -0.0417177 0.829094 0.438752 -0.346555 0.839826 0.404864 -0.361632 0.671034 0.458956 -0.5823 0.668778 0.382891 -0.637283 0.494399 0.462766 -0.735811 0.441336 0.369337 -0.81781 0.348751 0.43315 -0.831116 0.242022 0.356145 -0.902544 0.783476 0.619935 0.0429519 0.314086 0.022979 0.949116 0.377927 0.040222 0.924961 0.283474 0.0558791 0.957351 0.353024 0.107247 0.929447 0.55501 0.0779067 0.828188 0.789565 0.148664 0.595388 0.693971 0.110593 0.711459 0.934688 0.189897 0.300494 0.908548 0.174894 0.379411 0.977073 0.211391 -0.0253282 0.977982 0.208673 0.00256467 0.918688 0.394661 0.0159849 0.918655 0.394675 0.0174518 0.857896 0.332919 0.391381 0.857679 0.332847 0.391917 0.659714 0.216367 0.719696 0.659679 0.216355 0.719732 0.376349 0.0749225 0.923444 0.371989 0.0734419 0.925327 0.862028 0.505914 0.0309677 0.793315 0.565109 0.226505 0.757065 0.506845 0.412263 0.758057 0.507627 0.409469 0.594941 0.330117 0.732849 0.596059 0.330908 0.731583 0.414955 0.166274 0.89452 0.738544 0.169678 0.652505 0.84311 0.0597475 0.534411 0.787905 0.0935759 0.608645 0.487703 0.327116 0.809408 0.510625 0.314397 0.80026 0.587384 0.262884 0.765423 0.309675 0.413278 0.856331 0.41252 0.363589 0.835242 0.143546 0.470181 0.870818 0.118763 0.478806 0.86985 -0.052481 0.518632 0.853385 -0.402751 0.404633 0.821014 -0.214959 0.446243 0.868712 -0.194242 0.45466 0.869226 0.27264 0.422353 0.864457 -0.0666192 0.558453 0.826857 -0.224678 0.666977 0.710395 -0.969556 0.138393 -0.202012 -0.227784 0.718875 0.65676 -0.252864 0.75935 0.59954 -0.231946 0.737846 0.633865 -0.234619 0.739627 0.630798 -0.210621 0.698333 0.684083 -0.0576958 0.673333 0.737085 -0.0978425 0.625837 0.773793 -0.030171 0.591118 0.806021 -0.104039 0.541461 0.834264 -0.150436 0.598782 0.786657 -0.286885 0.557854 0.778779 -0.604025 0.544845 0.581633 -0.545589 0.602996 0.582003 -0.462594 0.549119 0.696042 -0.28801 0.582224 0.760307 -0.439856 0.589418 0.677579 -0.335063 0.722275 0.605023 -0.320911 0.75241 0.575235 -0.387769 0.721193 0.574035 -0.750752 -0.650521 -0.114861 -0.681227 -0.710625 -0.175905 -0.827089 0.0789179 0.556503 -0.535213 0.125751 0.835304 -0.64372 -0.496682 0.582178 -0.60517 -0.665138 0.437448 -0.95659 0.0333466 0.289525 -0.97697 0.101022 0.187945 -0.813327 -0.442856 -0.37733 -0.99813 0.0244456 -0.056035 -0.989221 0.081106 -0.121919 -0.941954 0.248035 0.226276 -0.891894 0.103025 0.440354 -0.830077 0.231068 0.507523 -0.713691 0.153883 0.683349 -0.742874 0.0262321 0.668917 -0.943298 0.268809 0.194759 0.808417 -0.00900196 0.588541 0.720408 0.094956 0.68702 0.634878 0.0600716 0.770274 0.368652 0.0844799 0.925721 0.291112 0.0331751 0.956114 0.230953 0.165316 0.958818 0.341631 -0.366238 0.865539 0.318499 -0.29169 0.901929 0.585769 0.00509309 0.810462 0.769054 -0.475333 0.427335 0.463303 0.103854 0.880094 0.350773 0.244571 0.90396 0.355702 0.239371 0.903425 0.712349 0.117772 0.691873 0.592029 0.253535 0.764998 0.585593 0.259281 0.76802 0.465979 0.368271 0.804512 0.427772 0.395838 0.812603 -0.0376156 0.134445 0.990207 -0.166229 0.0968552 0.981319 -0.095444 -0.691093 0.716436 -0.110311 -0.664275 0.739304 -0.392812 0.118986 0.911889 -0.439563 0.67227 0.595682 -0.934202 0.355275 0.0323492 -0.749248 0.569643 0.337839 -0.684677 0.614543 0.39186 -0.441173 0.695359 0.567311 -0.393235 0.707881 0.586746 -0.277994 0.783856 0.555238 -0.282244 0.770416 0.571661 -0.262029 0.769366 0.582594 -0.260539 0.786343 0.560165 -0.250291 0.760105 0.599662 -0.925987 0.369257 0.0787305 -0.855932 0.462824 0.230597 -0.866003 0.392271 0.3101 -0.693008 0.563796 0.449305 -0.627034 0.615648 0.477289 -0.389635 0.728559 0.56337 -0.354862 0.742264 0.568434 0.155109 0.562512 0.812109 0.321254 0.47386 0.81991 0.237798 0.375869 0.895642 0.198462 0.408299 0.891013 0.032316 0.297552 0.954158 -0.0368358 0.392972 0.918812 -0.289737 0.317817 0.902798 -0.294702 0.354915 0.887235 -0.560225 0.367371 0.74242 -0.581356 0.305841 0.75398 -0.732721 0.402977 0.548388 -0.796894 0.29796 0.525528 -0.837788 0.416015 0.353614 -0.987952 0.117984 0.10015 -0.967087 0.249184 -0.0514725 -0.83386 -0.185493 -0.519875 -0.933536 0.00581258 -0.358438 -0.913245 0.0597774 -0.403001 -0.947815 0.098882 -0.303098 -0.96416 0.255044 -0.0731237 -0.956705 0.175524 -0.232178 -0.445071 0.462101 0.767056 -0.489242 0.465338 0.737633 -0.794007 0.411677 0.447297 -0.7133 0.430007 0.553441 -0.605021 0.451059 0.656121 -0.9593 0.274571 0.0659801 -0.906471 0.340484 0.249761 -0.83996 0.385495 0.381918 -0.965641 0.239049 -0.101949 -0.965868 0.211552 -0.149485 -0.932122 0.361075 0.027803 -0.756031 0.535389 0.376532 -0.764019 0.530042 0.367874 -0.451923 0.612388 0.64865 -0.464122 0.610012 0.642243 -0.11283 0.0395348 0.992828 -0.116972 0.0407426 0.992299 -0.478966 0.121883 0.869331 -0.433011 0.115173 0.894001 -0.700765 0.169963 0.69285 -0.77341 0.190413 0.604633 -0.844364 0.202293 0.496111 -0.913387 0.216419 0.344801 -0.939707 0.224107 0.258316 -0.960096 0.224802 0.166372 -0.873075 0.415407 0.2553 -0.873115 0.415446 0.255098 -0.716929 0.35124 0.602198 -0.716831 0.351171 0.602356 -0.441152 0.228938 0.86774 -0.440914 0.228787 0.867901 -0.110737 0.0774198 0.99083 -0.115383 0.0802592 0.990073 -0.761437 0.598753 0.248411 -0.761372 0.59866 0.248836 -0.622883 0.506556 0.596169 -0.622752 0.506418 0.596424 -0.380103 0.33044 0.863904 -0.379989 0.330327 0.863998 -0.161211 0.166001 0.972859 -0.092803 0.107284 0.989888 -0.0168961 0.0556155 0.998309 -0.552698 0.25867 0.792222 -0.224861 -0.427625 -0.875542 -0.510891 0.289685 -0.809366 -0.189614 -0.0100072 -0.981808 -0.912473 -0.348292 -0.214677 -0.953517 0.0553165 -0.296218 -0.873411 0.0972503 -0.477175 -0.401782 -0.699017 -0.591563 -0.751569 0.0461985 -0.658034 -0.629368 0.11575 -0.768438 -0.898353 0.140686 0.416137 -0.933326 0.0618727 0.35366 -0.884985 -0.382483 0.265535 -0.961957 0.2327 0.143138 -0.992952 0.0339428 -0.113556 -0.406597 -0.136047 0.903421 -0.637163 0.731607 0.242434 -0.503885 0.854487 0.126306 -0.523306 0.835071 0.169728 -0.547939 0.822986 0.149856 -0.564474 0.780887 0.267552 -0.487972 0.750238 -0.446124 -0.446312 0.894511 0.025607 -0.526663 0.849949 0.014559 -0.511724 0.85886 -0.0223129 -0.640897 0.578899 -0.50411 -0.654763 0.630541 -0.416777 -0.676421 0.613454 -0.40759 -0.656569 0.679246 -0.327936 -0.732695 0.631927 -0.25264 -0.691632 0.690749 -0.210974 -0.756359 0.652247 -0.0499466 -0.732629 0.679068 -0.04607 -0.724186 0.672887 0.150923 -0.737023 0.657155 0.157938 -0.660191 0.684339 0.309562 -0.684063 0.634785 0.359313 -0.607632 0.672758 0.422114 -0.601023 0.616744 0.508329 -0.588601 0.625477 0.512178 -0.547293 0.589026 0.594575 -0.936942 0.204164 -0.283648 -0.844967 0.246557 -0.474596 -0.838905 0.144478 -0.524753 -0.648363 0.260406 -0.715412 -0.588234 0.131289 -0.797962 -0.434884 0.249911 -0.865113 -0.317545 0.13775 -0.938185 -0.0956772 -0.0254188 0.995088 -0.270045 0.18776 0.944363 -0.206477 0.118353 0.971267 -0.817992 0.163147 0.551609 -0.698249 -0.232158 0.677164 -0.696761 0.0903871 0.711586 -0.606517 0.237402 0.7588 -0.579621 0.310178 0.753545 -0.508345 0.124174 0.852154 -0.315202 0.2566 0.913676 -0.511328 0.8591 -0.0221425 -0.557582 0.82804 -0.0587552 -0.557027 0.828375 -0.0592921 -0.606275 0.785092 -0.126735 -0.46282 0.741995 0.485016 -0.682403 0.714288 -0.155301 -0.729061 0.672499 -0.127339 -0.501052 0.864771 0.0334307 -0.49971 0.863788 0.0644997 -0.462379 0.884068 0.0680467 -0.507068 0.855947 0.101183 -0.496025 0.859619 0.122535 -0.495756 0.344075 -0.797395 -0.547145 0.440302 -0.711876 -0.664849 0.348242 -0.660835 -0.672401 0.460801 -0.579258 -0.830535 0.363711 -0.421813 -0.805954 0.45269 -0.381458 -0.914697 0.388844 -0.110132 -0.897467 0.427988 -0.106676 -0.884049 0.418095 0.208933 -0.892104 0.397194 0.215377 -0.762401 0.442259 0.472391 -0.769958 0.369522 0.520209 -0.606679 0.449598 0.655593 -0.568961 0.35396 0.742291 -0.463397 0.427606 0.776155 -0.367338 0.344207 0.864051 -0.145916 0.0539279 -0.987826 -0.904941 0.409228 -0.116677 -0.969793 0.228471 -0.0854512 -0.968987 0.228644 -0.0937319 -0.891902 0.204236 -0.403483 -0.671017 0.149165 -0.726282 -0.586806 0.132261 -0.798853 -0.45767 0.0946166 -0.884073 -0.181943 0.0342028 -0.982714 -0.778791 0.176193 -0.60203 -0.853146 0.198445 -0.482454 -0.800192 0.351266 -0.486112 -0.90637 0.408808 -0.106626 -0.803828 0.584212 -0.112059 -0.70916 0.49918 -0.497907 -0.502707 0.335986 -0.796491 -0.496255 0.329161 -0.803358 -0.286551 0.172595 -0.94239 -0.138217 0.0466064 -0.989305 -0.802341 0.584207 -0.122276 -0.713761 0.501335 -0.489089 -0.800936 0.351415 -0.484777 -0.552949 0.23104 -0.800543 -0.552239 0.230545 -0.801175 -0.230782 0.0804742 -0.969672 -0.230843 0.0425829 -0.972059 -0.7387 -0.507408 0.443689 -0.992629 -0.0885952 0.082697 -0.991937 -0.0957791 0.0829927 -0.989769 -0.115332 0.0840049 -0.985911 -0.143486 0.0859773 -0.97904 -0.182688 0.0900343 -0.936419 -0.322197 0.138951 -0.985866 -0.140865 0.0906942 -0.732287 -0.645037 0.218365 -0.765867 0.622836 0.159758 -0.842771 -0.517905 0.146669 -0.663235 -0.644091 0.381137 -0.687956 0.643131 0.336303 -0.718809 -0.622717 0.309092 -0.933076 0.0860718 0.349229 -0.86296 -0.428497 0.26775 -0.275237 -0.609598 0.743394 -0.366269 0.541406 0.756787 -0.433416 -0.292481 0.852412 -0.506993 -0.101604 0.855941 -0.482284 -0.490079 0.726102 -0.563883 0.0456308 0.824593 -0.617971 -0.291532 0.730151 -0.594141 0.429196 0.680285 -0.627429 -0.510825 0.5877 -0.624947 0.553327 0.550701 -0.642627 -0.600725 0.475563 -0.782333 0.305706 0.542678 -0.794671 -0.378873 0.474292 -0.0918375 -0.658796 0.746695 -0.12401 0.688059 0.71498 -0.170854 -0.690224 0.703135 -0.272942 0.0324075 0.961485 -0.308663 -0.417507 0.854644 -0.0053204 -0.50118 0.865327 -0.0197832 0.0767308 0.996856 -0.0857843 -0.267334 0.959778 0.0925509 -0.546507 0.832325 0.108676 -0.184062 0.976888 0.0985532 0.267735 0.958439 0.0608599 -0.834708 0.547319 0.0207809 -0.98216 0.186893 0.0208237 -0.982097 0.187222 -0.00116285 -0.982097 0.188372 -0.0011541 -0.981965 0.189057 -0.0230659 -0.981966 0.187643 -0.0231705 -0.98177 0.188655 0.0927081 -0.544864 0.833384 -0.00516903 -0.544868 0.838506 -0.00510015 -0.541439 0.840725 -0.102564 -0.54145 0.834453 -0.102838 -0.536352 0.837706 -0.199169 -0.536343 0.820164 -0.199992 -0.529754 0.824235 -0.294428 -0.529753 0.795408 -0.295906 -0.52204 0.799946 -0.386701 -0.522043 0.76022 -0.388776 -0.513816 0.764753 -0.474677 -0.513813 0.714618 -0.477163 -0.505717 0.718725 -0.557422 -0.505711 0.658436 -0.559941 -0.498639 0.661684 -0.63262 -0.498651 0.59257 -0.634542 -0.493849 0.594534 -0.698965 -0.493841 0.517271 -0.699505 -0.492617 0.517708 -0.754558 -0.492619 0.433553 -0.752872 -0.496125 0.432486 -0.797666 -0.496135 0.342897 -0.793841 -0.503481 0.341061 -0.828008 -0.503461 0.246841 -0.825608 -0.507785 0.246018 -0.848726 -0.507787 0.147707 -0.850207 -0.505209 0.148029 0.0609842 -0.834096 0.548237 -0.00339965 -0.834099 0.551605 -0.00336479 -0.832817 0.553539 -0.0675264 -0.832825 0.549403 -0.0678019 -0.83094 0.552216 -0.131292 -0.830933 0.540659 -0.132058 -0.828501 0.544194 -0.194391 -0.828501 0.525165 -0.195745 -0.825657 0.529126 -0.255783 -0.825659 0.502855 -0.257688 -0.822618 0.50685 -0.314602 -0.822615 0.473635 -0.3169 -0.819611 0.477296 -0.370186 -0.819606 0.437274 -0.372524 -0.816983 0.440187 -0.420856 -0.816992 0.394215 -0.422645 -0.815211 0.395982 -0.465551 -0.815205 0.344533 -0.46605 -0.814755 0.344923 -0.502727 -0.814757 0.288855 -0.501164 -0.816056 0.287902 -0.530982 -0.816063 0.228253 -0.527486 -0.818774 0.226643 -0.550208 -0.81876 0.164023 -0.548031 -0.82036 0.163314 -0.563377 -0.820361 0.098048 -0.564702 -0.819418 0.0983137 -0.965208 0.246728 0.086599 -0.987636 -0.132165 0.0843047 -0.85954 -0.5057 0.0738832 -0.835128 -0.545407 0.0713658 -0.570589 -0.81977 0.0490471 -0.549028 -0.834484 0.0469482 -0.190688 -0.981514 0.0164069 -0.0441205 -0.981777 0.184844 -0.0553476 -0.972098 0.227951 -0.0550908 -0.981576 0.182959 -0.0664403 -0.981515 0.179482 -0.0669342 -0.981221 0.1809 -0.0874543 -0.981221 0.17192 -0.0881504 -0.980906 0.173359 -0.107611 -0.980905 0.162002 -0.108447 -0.980595 0.163316 -0.126675 -0.980594 0.149627 -0.127522 -0.980325 0.150669 -0.14406 -0.980326 0.134938 -0.144708 -0.980143 0.13557 -0.159395 -0.980142 0.11796 -0.159581 -0.980095 0.118103 -0.172137 -0.980095 0.0989078 -0.171568 -0.980229 0.0985659 -0.181775 -0.98023 0.0781439 -0.18051 -0.98051 0.0775702 -0.188291 -0.980508 0.0561341 -0.187503 -0.980673 0.0558825 -0.192756 -0.980673 0.033545 -0.193242 -0.980574 0.0336396 -0.195186 -0.980623 0.0167487 -0.00335058 -0.999994 0.000286962 0.872928 -0.152129 0.463522 0.696263 -0.589278 0.409841 0.732564 -0.526694 0.431211 0.484017 -0.827378 0.284908 0.165442 -0.9814 0.0973844 0.844549 -0.152417 0.513329 0.787796 -0.152309 0.596808 0.787207 -0.156639 0.596463 0.744454 -0.156893 0.648978 0.613824 -0.525847 0.588817 0.704886 -0.163098 0.690315 0.628492 -0.163015 0.760541 0.627652 -0.169905 0.759727 0.535532 -0.169901 0.827248 0.534824 -0.176273 0.826372 0.435622 -0.176279 0.8827 0.435149 -0.181153 0.881946 0.330777 -0.181158 0.926158 0.330557 -0.183902 0.925696 0.221515 -0.183897 0.95766 0.221505 -0.184066 0.95763 0.732423 -0.526953 0.431135 0.677448 -0.526951 0.513212 0.676066 -0.52966 0.512245 0.612111 -0.529669 0.587172 0.610277 -0.533575 0.585542 0.538753 -0.533581 0.651948 0.536956 -0.537835 0.649932 0.458145 -0.537824 0.707707 0.456699 -0.541749 0.705644 0.37198 -0.541758 0.753744 0.371067 -0.544726 0.752052 0.282059 -0.544733 0.789752 0.281655 -0.546407 0.788739 0.188744 -0.546396 0.815983 0.188723 -0.546517 0.815906 0.483882 -0.827483 0.284833 0.447563 -0.827481 0.33906 0.446386 -0.828463 0.338213 0.404151 -0.828469 0.387686 0.402552 -0.829929 0.386225 0.355365 -0.829934 0.43003 0.353833 -0.831499 0.428266 0.301896 -0.831492 0.466347 0.300664 -0.832949 0.46454 0.244881 -0.832956 0.496203 0.244111 -0.834055 0.494734 0.185551 -0.834059 0.519536 0.185214 -0.834678 0.51866 0.124116 -0.834671 0.536582 0.124099 -0.834715 0.536517 0.165402 -0.981409 0.0973619 0.152988 -0.981408 0.115897 0.152561 -0.981512 0.115586 0.138124 -0.981513 0.132494 0.137556 -0.981663 0.131969 0.12143 -0.981664 0.14694 0.120881 -0.981827 0.1463 0.103136 -0.981826 0.159314 0.102699 -0.981977 0.158665 0.0836424 -0.981978 0.169481 0.0833684 -0.982092 0.168951 0.063367 -0.982093 0.177422 0.0632479 -0.982157 0.177107 0.0423826 -0.982156 0.183229 0.0423761 -0.982161 0.183203 0.901664 -0.429198 -0.0528362 0.934525 -0.324194 -0.146836 0.968014 -0.184738 -0.169769 0.54263 -0.838444 -0.0506472 0.587765 -0.805693 -0.0734206 0.406265 -0.912713 -0.0436391 0.8328 -0.546333 -0.0892417 0.547828 -0.83452 -0.0588338 0.324039 -0.946033 0.00445741 0.186786 -0.9824 -0.00103617 0.186522 -0.982379 -0.0118986 0.980824 -0.192199 -0.0322984 0.979728 -0.191557 0.058637 0.977905 -0.200664 0.0586156 0.954526 -0.200677 0.220472 0.960233 -0.170037 0.221449 0.822706 -0.561619 -0.0879689 0.825941 -0.561586 0.0494299 0.829583 -0.556179 0.0495764 0.809724 -0.55621 0.187022 0.814777 -0.548419 0.188081 0.550646 -0.809871 0.202233 0.645566 -0.74939 0.147168 0.521793 -0.844538 0.120368 0.531778 -0.845125 0.0545436 0.404217 0.914356 0.0237035 0.536537 -0.843822 0.00962704 0.534536 -0.843204 -0.0572533 0.165297 0.986085 -0.0176822 0.185808 -0.982209 -0.0272134 0.910775 -0.170037 0.376266 0.913621 -0.15164 0.377231 0.772848 -0.548417 0.319289 0.786148 -0.526032 0.324442 0.405394 0.898862 0.166441 0.509582 -0.827595 0.2354 0.353791 -0.935308 0.00563589 0.387809 -0.921714 0.00694278 0.120123 -0.992733 0.00713834 0.389531 -0.920152 0.0398236 0.172735 -0.984738 0.0212914 0.169952 -0.984619 0.0405267 0.297189 -0.952404 0.0678664 0.240361 -0.966879 0.0858534 0.140794 -0.988677 0.0519113 0.223391 -0.969249 0.103217 0.173679 -0.981437 0.0813446 0.184288 -0.982231 -0.0354861 0.183549 -0.98219 -0.0401644 0.188794 -0.981144 -0.0414011 0.176895 -0.983467 -0.0387374 0.183221 -0.982254 -0.0400991 0.183532 -0.982193 -0.0401612 0.189012 -0.981098 -0.0414944 0.184673 -0.981992 -0.0398563 0.187652 -0.981558 -0.0364671 0.260931 -0.96397 -0.0517444 0.803999 0.571751 -0.163356 0.165743 -0.98555 -0.0349337 0.67941 0.720625 -0.138212 0.541561 -0.833412 -0.110163 0.538917 -0.835194 -0.109633 0.827599 -0.535484 -0.168333 0.820096 -0.547362 -0.166843 0.96512 -0.154819 -0.211128 0.177893 -0.983278 -0.0389757 0.173834 -0.984039 -0.0380733 0.558638 -0.820333 -0.122383 0.542493 -0.831615 -0.11882 0.846274 -0.499445 -0.185405 0.827473 -0.531453 -0.181235 0.975761 -0.046739 -0.213788 0.968447 -0.131066 -0.211972 0.963063 -0.184714 -0.195934 0.967191 -0.160761 -0.196714 0.964946 -0.160771 -0.207442 0.961878 -0.176347 -0.209028 0.975637 -0.049349 -0.213767 0.971619 -0.102545 -0.213169 0.971579 -0.102545 -0.213351 0.970775 -0.110866 -0.212849 0.920859 -0.334116 -0.200958 0.846414 -0.499444 -0.184768 0.825122 -0.535504 -0.180025 0.558729 -0.820333 -0.121968 0.539929 -0.833425 -0.11781 0.214388 -0.975627 -0.0467981 0.195549 -0.979767 -0.0426376 0.0241557 -0.999692 -0.00577553 0.0422195 -0.999064 -0.00939564 0.191762 -0.98077 -0.0363086 0.96254 -0.154811 -0.2226 0.183275 -0.982189 -0.0414148 0.10929 -0.993721 -0.0239641 0.542498 -0.831612 -0.118816 0.542717 -0.831462 -0.118864 0.827468 -0.531447 -0.181275 0.81221 -0.555592 -0.177856 0.417037 0.90426 -0.0916164 0.959939 -0.195083 -0.201146 0.958026 -0.195091 -0.210061 0.958028 -0.195083 -0.21006 0.958028 -0.19508 -0.210061 0.81216 -0.555594 -0.178077 0.81216 -0.555594 -0.178077 0.542689 -0.831462 -0.118992 0.54269 -0.831462 -0.118992 0.277837 -0.958695 -0.0609196 0.19078 -0.980785 -0.0407984 0.0897919 -0.995766 -0.0196881 -0.943318 -0.171443 -0.28418 -0.982362 -0.178801 0.0547232 -0.178767 -0.983841 0.00995153 -0.178176 -0.983949 0.00991549 -0.996366 -0.0651022 0.0549306 -0.996798 -0.058243 0.0547864 -0.538105 -0.842348 0.029881 -0.821676 -0.568132 0.0455448 -0.833684 -0.550306 0.0461907 -0.940687 -0.335238 0.0521937 -0.99782 -0.0361504 0.0552207 -0.998457 0.00475617 0.0553279 -0.99411 0.0882892 0.0628462 -0.270971 -0.962397 0.0191609 -0.731999 -0.67926 0.0527564 -0.549587 -0.834494 0.0396736 -0.256629 -0.966314 0.0194835 -0.219116 -0.975551 0.0169717 -0.190799 -0.981513 0.0151111 -0.00335229 -0.999994 0.000266292 -0.156406 -0.987655 0.00864361 -0.153325 -0.98814 0.00843272 -0.156746 -0.987601 0.00865773 -0.201781 -0.979365 0.0113424 -0.345886 -0.938069 0.0197332 -0.108861 -0.994035 0.00657059 -0.16841 -0.985653 0.0112264 -0.821833 -0.567849 0.0462463 -0.945193 -0.322033 0.0538929 -0.922205 -0.383112 0.0525636 -0.940601 -0.335243 0.0536886 -0.79832 -0.600511 0.0455051 -0.821602 -0.568129 0.0468915 -0.175977 -0.984346 0.00978231 -0.15448 -0.987959 0.00854058 -0.539303 -0.841579 0.0299455 -0.539258 -0.841578 0.0307752 -0.520263 -0.853492 0.0296337 -0.519759 -0.853484 0.0376386 -0.797527 -0.600509 0.0577916 -0.833531 -0.549148 0.0605215 -0.921286 -0.383125 0.066693 -0.9771 -0.200623 0.0708917 -0.774953 -0.629518 0.0561758 -0.980469 -0.182703 0.0728073 -0.939112 -0.341108 0.0413918 -0.980172 -0.190615 0.0541095 -0.980176 -0.190595 0.0541081 -0.982598 -0.178799 0.0503214 -0.180015 -0.983557 0.014537 -0.18044 -0.983555 0.00776586 -0.178892 -0.983839 0.00769428 -0.829577 -0.557251 0.0356916 -0.834209 -0.550277 0.0359207 -0.969801 -0.240302 0.0417256 -0.705473 -0.708196 0.0276719 0.0617613 0.0104621 0.998036 -0.178357 -0.983917 0.00983964 -0.210984 -0.977345 0.0168291 -0.535848 -0.843235 0.0426821 -0.537063 -0.843225 0.0231198 -0.538464 -0.842329 0.0231861 -0.992436 -0.0914723 0.0818795 -0.411993 -0.910763 0.0277844 -0.828393 -0.557355 0.0558641 -0.82832 -0.557464 0.0558587 -0.530916 0.846668 0.0358021 -0.534129 -0.844889 0.0294853 -0.17739 -0.984092 0.0097924 0.184967 -0.982015 -0.037878 0.751374 -0.640949 -0.156914 0.781048 -0.602741 -0.163299 0.663099 -0.73561 -0.138483 0.566239 -0.815758 -0.117951 0.495868 -0.862174 -0.103782 0.261105 -0.963766 -0.0545774 0.172352 -0.984344 -0.0368859 0.971678 -0.122349 -0.202168 0.975684 0.0787701 -0.204537 0.931643 -0.307387 -0.19379 0.971461 -0.122157 -0.203326 0.952806 -0.229143 -0.199135 0.863736 -0.470735 -0.179912 0.938473 -0.283771 -0.196832 0.879874 -0.438216 -0.183819 0.969456 -0.122354 -0.212565 0.965708 -0.1211 0.229658 -0.459112 -0.685328 -0.565281 -0.575521 -0.668158 -0.47153 -0.65084 -0.667173 -0.362336 -0.876351 -0.341302 -0.339884 -0.718165 -0.667178 -0.19777 -0.882279 -0.40995 -0.231354 -0.968596 -0.00580947 -0.248572 -0.586025 -0.706731 -0.396366 -0.112009 -0.993578 -0.0160033 -0.175021 -0.98429 -0.0232565 -0.159422 -0.984344 -0.0751774 -0.164426 -0.984291 -0.0643146 -0.662429 -0.706734 -0.248426 -0.877276 0.113955 -0.466263 -0.802441 -0.41001 -0.433567 -0.850714 -0.409989 -0.32893 -0.698072 -0.667159 -0.25999 -0.481813 -0.860934 -0.163244 -0.436773 -0.860935 -0.260807 -0.46619 -0.841087 -0.274298 -0.621144 -0.706625 -0.338912 -0.111838 -0.9893 -0.0936939 -0.136262 -0.984342 -0.111824 -0.136256 -0.984343 -0.11182 -0.135723 -0.984467 -0.111375 -0.147685 -0.981605 -0.121 -0.137633 -0.984346 -0.110095 -0.144804 -0.984293 -0.100987 -0.0776737 -0.987102 -0.139985 -0.100539 -0.9869 -0.126178 -0.108226 -0.984847 -0.135515 -0.136819 -0.983832 -0.11556 0.082247 -0.986399 -0.142313 0.115985 -0.973774 -0.195733 0.0841717 -0.990323 -0.110345 0.104966 -0.985242 -0.135207 0.629575 -0.704858 -0.326817 0.576418 -0.707009 -0.409733 0.619322 -0.610324 -0.493908 0.159947 -0.987091 -0.00825266 0.309722 -0.950803 -0.0067182 0.0953903 -0.995414 0.00724357 0.255949 -0.961926 0.0958549 0.113973 -0.993057 0.0291342 0.161361 -0.986141 0.0385908 0.159799 -0.98454 0.0717245 0.160536 -0.984346 0.0727357 0.15796 -0.984847 0.071592 0.155372 -0.985345 0.0703866 0.158775 -0.985316 0.0627887 0.172167 -0.984345 -0.0377306 0.705298 -0.694153 -0.143899 0.0469134 -0.998899 -0.000522884 -0.176409 -0.984308 -0.00411681 -0.188779 -0.982011 -0.00413708 -0.552634 -0.833319 -0.0132266 -0.984101 -0.12168 -0.129377 -0.964711 -0.23 -0.128189 -0.904117 -0.410048 -0.120137 -0.904118 -0.410047 -0.120137 -0.738082 -0.667544 -0.0980746 -0.738054 -0.667577 -0.0980714 -0.683347 -0.70665 -0.18353 -0.578428 -0.798409 -0.167227 -0.486266 -0.860934 -0.14946 -0.502849 -0.861788 -0.0668177 -0.502847 -0.861789 -0.0668175 -0.506963 -0.861901 -0.0107505 -0.744134 -0.667793 -0.0178123 -0.839471 -0.543096 -0.0183438 -0.911691 -0.410281 -0.0221382 -0.98281 -0.183303 -0.0220221 -0.992293 -0.121728 -0.0231628 -0.793245 -0.258865 -0.551136 -0.780491 -0.122197 -0.613108 -0.767734 -0.122182 -0.629012 -0.767215 -0.12231 -0.62962 -0.767214 -0.122306 -0.629622 -0.613664 -0.595557 -0.518391 -0.747987 -0.122345 -0.65234 -0.634795 -0.121895 -0.763005 -0.705313 -0.410609 -0.57787 -0.704847 -0.41061 -0.578438 -0.704804 -0.410731 -0.578404 -0.696515 -0.410702 -0.588379 -0.696866 -0.409718 -0.58865 -0.570145 -0.407894 -0.713132 -0.155412 -0.968368 -0.195218 -0.575464 -0.668239 -0.471485 -0.575084 -0.668239 -0.471948 -0.575079 -0.668246 -0.471944 -0.568341 -0.668212 -0.480084 -0.56893 -0.667367 -0.480562 -0.464978 -0.665321 -0.584075 -0.465043 -0.665206 -0.584154 -0.0383611 -0.994622 -0.096211 -0.140094 -0.953089 -0.268318 -0.228856 -0.870001 -0.436718 -0.308135 -0.868837 -0.387524 -0.317407 -0.8604 -0.398703 -0.387733 -0.861636 -0.327486 -0.387055 -0.862149 -0.326937 -0.391624 -0.862171 -0.321389 -0.391566 -0.862215 -0.321342 -0.391821 -0.862217 -0.321026 -0.391915 -0.862147 -0.321101 -0.430453 -0.860942 -0.271087 -0.61798 -0.667176 -0.415904 -0.750204 -0.409952 -0.518781 -0.70533 -0.41056 -0.577884 -0.767722 -0.122306 -0.629002 -0.767215 -0.122306 -0.629621 -0.26204 -0.126508 -0.956729 -0.0611356 -0.899091 -0.433472 -0.145207 -0.411936 -0.899568 -0.197534 0.0507316 -0.978983 -0.0594373 -0.861602 -0.504092 -0.110068 -0.664424 -0.739206 -0.390248 0.398713 -0.8299 -0.408561 -0.125562 -0.904053 -0.214915 0.870728 -0.442317 -0.369754 -0.41201 -0.832785 -0.303001 -0.66518 -0.682441 -0.30297 -0.665263 -0.682374 -0.189161 0.884706 -0.426044 -0.174301 -0.864541 -0.471368 -0.0596032 -0.985244 -0.160441 -0.0393607 -0.985256 -0.166496 -0.000955636 -0.999989 -0.00458811 -0.105421 -0.559321 -0.822221 -0.055131 -0.70683 -0.705232 0.0232924 -0.706262 -0.707568 0.0467415 -0.851754 -0.521852 0.112437 -0.706484 -0.698741 0.156543 -0.707049 -0.68962 0.259958 -0.652092 -0.712179 0.512836 -0.411646 -0.753357 0.55694 -0.0447464 -0.829347 0.553914 -0.125683 -0.823033 0.019291 -0.984539 -0.174098 0.146209 -0.865122 -0.479777 0.252347 -0.867895 -0.427877 0.260368 0.886521 -0.382478 0.308778 -0.864549 -0.396498 0.683362 -0.126582 -0.719022 0.246902 -0.947908 -0.201271 0.688002 -0.411605 -0.597691 0.00239379 -0.999995 -0.00220933 0.12074 -0.985255 -0.121223 0.727657 0.0529306 -0.683896 0.397 -0.861627 -0.316211 0.570089 -0.664509 -0.483143 0.420107 -0.665325 -0.617132 0.420196 -0.665143 -0.617268 0.240226 -0.66436 -0.707755 0.182531 -0.806605 -0.562202 0.277437 -0.527879 -0.802728 0.551296 0.0949089 -0.828894 0.891419 -0.410759 -0.191439 0.600008 -0.735227 -0.315329 0.446714 -0.858826 -0.250729 0.49831 -0.860365 -0.107047 0.463838 0.885704 0.0195572 0.493045 -0.869929 -0.0113942 0.484233 -0.868769 -0.103725 0.157787 -0.986881 -0.0341881 0.0984605 -0.994886 -0.0225306 0.93438 -0.126681 0.332995 0.346646 -0.93204 0.105541 0.969366 -0.122238 0.213041 0.991724 -0.121384 0.0418154 0.984205 -0.171949 0.0421167 0.97532 -0.0694867 -0.209576 0.970224 -0.124454 -0.207788 0.919814 -0.125375 -0.371784 0.16504 -0.986138 0.0171062 0.495161 -0.867193 0.0528415 0.484655 -0.867199 0.114343 0.453196 0.880667 0.137983 0.470268 -0.864695 0.176498 0.456907 -0.865093 0.207004 0.461476 -0.862172 0.209045 0.462167 -0.862171 0.207516 0.315347 -0.937838 0.144972 0.340506 -0.936749 0.0809763 0 -1 0 0.903504 -0.12703 0.409322 0.903252 -0.129052 0.409245 0.903848 -0.123996 0.409492 0.904014 -0.122455 0.409589 0.907826 0.098423 0.407634 0.910757 -0.122346 0.394402 0.965709 -0.121094 0.229658 0.892657 -0.407911 -0.191761 0.912219 -0.407894 0.0384631 0.912228 -0.407873 0.0384631 0.873443 -0.407894 0.265933 0.873407 -0.407976 0.265924 0.830533 -0.410646 0.376277 0.830545 -0.410617 0.376282 0.831801 -0.410618 0.373497 0.831901 -0.410378 0.373538 0.888655 -0.406978 0.211333 0.888644 -0.407002 0.211331 0.223737 -0.966565 -0.125272 0.813128 -0.410631 -0.412559 0.662253 -0.664455 -0.346295 0.729988 -0.665227 -0.156816 0.729956 -0.665264 -0.156808 0.745964 -0.665243 0.0314528 0.745966 -0.665241 0.0314528 0.714168 -0.665345 0.21744 0.714189 -0.66532 0.217447 0.677658 -0.668222 0.307016 0.677617 -0.668273 0.306997 0.678643 -0.668273 0.304722 0.678925 -0.667931 0.304842 0.72724 -0.664237 0.172947 0.456801 -0.882316 0.11336 0.989346 -0.121425 -0.0803138 0.969507 -0.122378 -0.212322 0.970052 -0.117497 -0.212588 0.929519 -0.307405 -0.203705 0.890493 -0.410657 -0.195916 0.861812 -0.470754 -0.188867 0.726684 -0.668258 -0.159253 0.749672 -0.640968 -0.164778 0.661688 -0.735623 -0.14501 0.990311 -0.12238 0.0656258 0.611572 0.790316 -0.0371472 0.911773 -0.406943 -0.0553816 0.911767 -0.406957 -0.055381 0.469251 -0.882605 -0.0285024 0.744018 -0.665329 -0.061433 0.508702 -0.860145 -0.0370528 0.494867 -0.862175 -0.108451 0.494851 -0.862184 -0.108447 -0.982468 -0.183584 0.0324673 -0.982523 -0.180122 0.0469429 -0.972838 -0.22817 0.039037 -0.838066 -0.544537 0.0335463 -0.838743 -0.543485 0.0336779 -0.551087 -0.834157 0.0220425 -0.551922 -0.833601 0.02216 -0.188125 -0.982116 0.0075135 -0.188491 -0.982046 0.00755701 -0.982901 -0.180104 0.0383094 -0.191926 -0.978576 -0.0745196 -0.184027 -0.980026 -0.0753809 -0.553179 -0.832009 -0.0418856 -0.548746 -0.834903 -0.0425943 -0.839098 -0.543979 -0.00109729 -0.837686 -0.54615 -0.00146687 -0.98204 -0.184803 0.0380194 -0.929174 -0.352914 -0.109946 -0.932425 -0.319498 -0.168833 -0.856736 -0.133418 -0.4982 -0.983752 -0.179396 0.0070893 -0.842506 -0.532808 -0.0793637 -0.555428 -0.819491 -0.141192 -0.988891 -0.0183294 -0.147509 -0.963072 -0.0331409 -0.267198 -0.99653 -0.0371503 -0.0744866 -0.849077 -0.0501772 -0.525881 -0.857053 -0.0496765 -0.512828 -0.571014 -0.0750178 -0.817505 -0.998479 1.67332e-05 0.055142 -0.935977 -0.226972 -0.269132 -0.937894 -0.167497 -0.303807 -0.190466 -0.571884 -0.797917 -0.195291 -0.42216 -0.885236 -0.191662 -0.422263 -0.885979 -0.194963 -0.259236 -0.945931 -0.19269 -0.259239 -0.946396 -0.194374 -0.0874192 -0.977024 -0.201016 -0.0875818 -0.975665 -0.998481 -2.47021e-05 0.0551012 -0.931717 -0.320925 -0.170033 -0.934617 -0.277417 -0.222558 -0.934011 -0.278615 -0.223601 -0.936465 -0.226308 -0.267989 -0.567483 -0.0750513 -0.819958 -0.567751 -0.182128 -0.8028 -0.844741 -0.151781 -0.513201 -0.841733 -0.261702 -0.472227 -0.566604 -0.363208 -0.739621 -0.56245 -0.492039 -0.66449 -0.565424 -0.491058 -0.662689 -0.560125 -0.604433 -0.566498 -0.563775 -0.602889 -0.564521 -0.55747 -0.697316 -0.45053 -0.561664 -0.695198 -0.44859 -0.557781 -0.749338 -0.356893 -0.834425 -0.51737 -0.189904 -0.829443 -0.549834 -0.0985245 -0.193002 -0.951421 -0.23989 -0.185308 -0.952826 -0.240384 -0.19396 -0.896361 -0.398644 -0.186397 -0.897423 -0.399861 -0.194661 -0.812377 -0.549683 -0.187713 -0.813166 -0.550931 -0.193843 -0.730813 -0.654475 0.372454 -0.649489 -0.662904 -0.191298 -0.670395 -0.716921 -0.195261 -0.571612 -0.796952 0.448852 0 -0.893606 0.448852 0 -0.893606 0.154602 0 -0.987977 0.154602 0 -0.987977 0.448762 -0.0200204 -0.893427 0.510016 -0.0839626 -0.856057 0.528077 -0.076328 -0.845759 0.704298 -0.00552532 -0.709883 0.722582 -0.0829243 -0.686294 0.837626 -0.179567 -0.515886 0.942791 -0.064871 -0.327011 0.84135 -0.125799 -0.525647 0.180094 -0.462724 -0.868017 0.531942 -0.364575 -0.764279 0.498773 -0.0180899 -0.866544 0.15435 -0.0570852 -0.986366 0.164455 -0.0567815 -0.984749 0.863681 -0.0102335 -0.503935 0.838938 -0.191948 -0.509254 0.877781 -0.0870504 -0.471088 0.987843 0.13688 0.0736875 0.988207 -0.0136151 -0.152517 0.118601 -0.289054 -0.949938 -0.144989 -0.379267 -0.913857 0.415621 -0.243687 -0.876285 0.443614 -0.388507 -0.807632 0.637338 -0.313778 -0.703806 0.752674 -0.246001 -0.610709 0.185369 -0.175468 -0.966876 0.0982845 -0.204186 -0.973986 0.318936 -0.139652 -0.937431 0.347993 -0.261795 -0.900202 0.554024 -0.187622 -0.811083 0.608371 -0.16025 -0.777306 0.719877 -0.101493 -0.686641 0.747332 -0.249241 -0.615933 0.865547 -0.156612 -0.475712 0.97978 -0.170885 -0.104065 0.980794 -0.15705 -0.115669 0.99848 7.555e-07 -0.0551187 0.847232 -0.510391 -0.147302 0.699568 -0.698599 -0.150216 0.553795 -0.821927 -0.13322 0.990703 -0.0585145 -0.122817 0.950861 -0.171058 -0.258076 0.87427 -0.281212 -0.395692 0.834358 -0.528849 -0.15545 0.829798 -0.511077 -0.224134 0.917431 -0.351289 -0.186861 0.912944 -0.307833 -0.267903 0.914056 -0.305568 -0.266701 0.90967 -0.238937 -0.339719 0.760789 -0.401678 -0.509759 0.549243 -0.814367 -0.187453 0.539092 -0.77516 -0.329402 0.545791 -0.770815 -0.328566 0.535947 -0.675368 -0.506596 0.541838 -0.671898 -0.504941 0.533603 -0.536432 -0.653842 0.538316 -0.534116 -0.651871 0.562099 -0.816309 -0.132986 0.190807 -0.967854 -0.163865 0.183783 -0.93611 -0.299869 -0.391194 -0.865714 -0.312261 0.188406 -0.89159 -0.41179 0.178409 -0.799061 -0.574171 0.187917 -0.797072 -0.573902 0.178154 -0.636389 -0.750513 0.185891 -0.634937 -0.749867 0.991858 0 -0.127352 0.972922 -0.0061734 -0.231053 0.954168 -0.0001513 -0.299271 0.859283 0.000183902 -0.5115 0.815421 -0.00551856 -0.578842 0.721093 0.000853153 -0.692838 0.484645 0 -0.874711 0.608213 -0.000744175 -0.793774 0.539082 -0.0028182 -0.842249 0.484645 0 -0.874711 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.62517e-05 -0.0739047 -0.997265 0.0111306 -0.0880822 -0.996051 -0.00913889 -0.220974 -0.975237 0.0216178 -0.261126 -0.965063 -7.7561e-06 -0.317524 -0.94825 -0.0642076 -0.652014 -0.755483 0.00016564 -0.452621 -0.891703 -0.0584147 -0.426681 -0.902514 0.029168 -0.576557 -0.816536 -1.23026e-06 -0.996225 -0.0868062 -0.0535121 -0.991387 -0.119532 0.029207 -0.966247 -0.255955 -0.00514284 -0.955461 -0.295074 0.00860657 -0.909349 -0.415946 0.0167245 -0.911503 -0.410954 -0.0205322 -0.823413 -0.567071 -0.0393288 -0.817129 -0.575111 0.00926709 -0.739157 -0.67347 -0.0260386 -0.678075 -0.734532 -1.62962e-05 0 -1 -1.62962e-05 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.99848 0 -0.0551179 0.99848 6.45741e-07 -0.0551188 0.99848 6.232e-07 -0.0551188 0.99848 -1.25527e-06 -0.0551183 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.214175 -1.77559e-07 0.976795 0.214175 1.01923e-07 0.976795 0.214175 0 0.976795 -0.214175 -1.35413e-06 -0.976795 -0.214176 5.00137e-07 -0.976795 -0.214176 0 -0.976795 -0.214175 -2.42061e-07 -0.976795 -0.214176 3.26418e-07 -0.976795 -0.170193 0 -0.985411 -0.0475305 0.0051884 -0.998856 -0.00692127 0.00049277 -0.999976 0.194054 -0.000318372 -0.980991 0.382764 0.0123197 -0.923764 0.359355 0.0087143 -0.93316 0.523832 0.000105858 -0.851822 0.616682 -8.43725e-05 -0.787213 0.758649 0.00756206 -0.651455 0.728592 0.0140541 -0.684804 0.995087 -0.000352846 -0.099 0.949249 0.020679 -0.313846 0.976785 0.00454229 -0.214174 0.907238 -1.10605e-05 -0.420617 0.845079 4.0227e-05 -0.534641 0.99328 0.000220576 0.115733 0.961607 0.00975284 0.274258 0.945125 0.00315941 0.326693 0.855664 -0.000871333 0.517531 0.716842 0.0068343 0.697202 0.717437 0.00696434 0.696589 0.37476 -0.0071426 0.927095 0.413687 0 0.910419 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0551189 0 -0.99848 -0.055119 -2.88144e-08 -0.99848 0.0551193 0 0.99848 0.0551186 -1.50933e-07 0.99848 0.0551187 -1.08526e-07 0.99848 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.88154 0 -0.47211 -0.88154 -2.70236e-07 -0.47211 0.88154 -1.03173e-07 0.47211 0.88154 0 0.47211 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.573129 0 0.819465 -0.573129 -7.78384e-08 0.819465 0.573129 -4.08478e-07 -0.819465 0.573128 0 -0.819466 0.699484 0 -0.714648 0.702297 0.00100343 -0.711883 0.87084 -0.000697084 -0.491567 0.929576 0.0197988 -0.368097 0.948383 0.0104113 -0.316955 0.979213 0.000411482 -0.202832 0.998784 -0.000545097 -0.0492989 0.993093 0.0150628 0.116362 0.994506 0.0173508 0.103233 0.68297 -4.28364e-05 0.730447 0.769357 0.00490806 0.6388 0.866154 0.0262488 0.499087 0.819442 0.00756116 0.573113 0.922034 -5.21711e-05 0.387108 0.96781 0.000160094 0.25168 0.139583 0.000480935 0.99021 0.302321 -0.000586119 0.953206 0.449978 0.015173 0.892911 0.443289 0.0163844 0.896229 0.569556 0.000115994 0.821953 -0.427765 0 0.90389 -0.434641 0.00269656 0.9006 -0.290513 0.000162702 0.956871 -0.0268765 -0.00386048 0.999631 -0.136522 0.0373183 0.989934 0.0171065 0.0112377 0.999791 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.676887 0.646842 -0.351311 -0.179069 0.983518 0.025044 -0.0767307 0.996982 0.011793 0.0831985 0.99652 -0.00518253 0.971488 0.122658 -0.202895 0.972061 0.132369 -0.193843 0.976916 0.045612 -0.208699 0.97781 0.088486 -0.189889 0.973969 0.105025 -0.200885 0.963364 0.189109 -0.190178 0.932692 0.317697 -0.170746 0.929967 0.327371 -0.167302 0.842171 0.521213 -0.138152 0.837541 0.529488 -0.134789 0.083577 0.996481 -0.00631057 0.0792725 0.996838 -0.00541682 0.0765414 0.997041 -0.00715137 0.0780905 0.996943 0.00253106 0.0745658 0.997215 0.00115688 0.0786942 0.996723 0.0187253 0.0749291 0.997052 0.0165425 0.0723168 0.997014 0.0270629 0.0664794 0.997302 0.0311218 0.0687691 0.99705 0.0340911 0.0649986 0.996984 0.042401 0.0649409 0.996992 0.0423074 0.0647932 0.996913 0.0443356 0.0642149 0.996972 0.0438563 -0.16962 0.979492 -0.108736 -0.167419 0.979678 -0.110462 -0.181128 0.975701 -0.123291 -0.180243 0.976075 -0.121619 -0.167966 0.985768 0.00692664 -0.160988 0.986933 -0.00680067 -0.17253 0.984827 -0.0187058 -0.16985 0.98508 -0.0277113 -0.172406 0.983956 -0.0458926 -0.177604 0.983153 -0.0432016 -0.167748 0.983764 -0.0637849 -0.0767678 0.996982 0.0115353 -0.0765082 0.997003 0.011443 -0.0756987 0.997065 0.0114925 -0.282277 0.958515 0.0396023 -0.234812 0.971569 0.0302721 -0.234753 0.971552 0.031263 -0.161118 0.986916 -0.00617964 -0.160634 0.986883 0.0160761 -0.979299 0.190426 0.0686451 -0.984232 0.160008 0.0753987 -0.99274 0.102897 0.062287 -0.992865 0.10089 0.0635605 -0.991225 0.118462 0.0586522 -0.992891 0.109375 0.0469438 -0.994148 0.103064 0.032372 -0.99413 0.0950561 -0.0516802 -0.989088 0.1426 -0.0370099 -0.925266 0.135444 -0.354314 -0.911086 0.192765 -0.364369 -0.945283 0.0967987 -0.31156 -0.973564 0.0964848 -0.207036 -0.953492 0.200294 -0.225247 -0.985396 0.086282 -0.146802 -0.762193 0.216632 -0.610026 -0.806211 0.172372 -0.56596 -0.840884 0.20117 -0.502439 -0.869054 0.0921587 -0.486058 -0.902934 0.0923027 -0.419749 -0.783164 0.158034 -0.601397 -0.771184 0.16894 -0.613788 -0.769581 0.148076 -0.621143 -0.774179 0.166351 -0.610716 -0.774222 0.169776 -0.609718 -0.76561 0.179331 -0.617804 -0.762186 0.174467 -0.623405 -0.677665 0.174307 -0.714414 -0.647686 0.100661 -0.755229 -0.541805 0.217046 -0.811997 -0.507402 0.182318 -0.842201 -0.395591 0.181947 -0.900224 -0.351986 0.0911214 -0.93156 -0.234403 0.218224 -0.94733 -0.187566 0.183735 -0.964915 -0.0739773 0.183208 -0.980287 -0.0193144 0.0830084 -0.996362 0.0904673 0.215883 -0.972219 0.14572 0.183762 -0.97211 0.252939 0.183203 -0.949978 0.31526 0.0730171 -0.946192 0.405706 0.212117 -0.88905 0.556219 0.132568 -0.820394 0.793702 0.147174 -0.590235 0.707105 0.192933 -0.680279 0.675273 0.214717 -0.705623 0.660867 0.183552 -0.727711 0.533342 0.182846 -0.825902 0.937925 0.183227 -0.29449 0.902008 0.183818 -0.390631 0.870686 0.210253 -0.444635 0.868896 0.199007 -0.453227 0.789332 0.158069 -0.59327 0.982317 0.183392 0.0376839 0.980764 0.184115 -0.0648303 0.969601 0.20595 -0.132128 0.969471 0.20708 -0.131313 0.947506 0.153908 -0.280258 0.910768 0.189484 0.366875 0.942033 0.190403 0.276261 0.956923 0.204285 0.206318 0.950346 0.222113 0.217964 0.98781 0.143916 0.0593298 0.882675 0.203449 0.423666 0.879917 0.207491 0.427426 0.876676 0.216908 0.429407 0.877148 0.218275 0.427747 0.877567 0.218281 0.426884 0.877139 0.218945 0.427423 0.903102 0.217772 0.37011 0.914532 0.200889 0.351104 0.955813 0.244296 0.163524 0.958729 0.216702 0.184059 0.975325 0.2184 -0.0322918 0.939885 0.317765 -0.125066 0.999714 0.0192782 -0.0141594 0.989048 0.104571 -0.104154 0.16389 0.982552 0.0879244 0.173203 0.983273 0.0563534 0.179748 0.982242 0.0537748 0.186677 0.982278 0.016804 0.189261 0.98181 0.0151516 0.187196 0.982014 -0.0246392 0.187089 0.982036 -0.0245407 0.182985 0.982022 -0.0463681 0.18548 0.980601 -0.0633906 0.180477 0.981942 -0.0567182 0.164301 0.981713 -0.0961523 0.149491 0.985812 -0.0763297 0.157962 0.978554 -0.132212 0.151823 0.981939 -0.112897 0.130808 0.981941 -0.136677 0.130809 0.981941 -0.136681 0.105235 0.981921 -0.157342 0.105232 0.982263 -0.155195 0.0781301 0.981609 -0.174185 0.0785371 0.981941 -0.172114 0.0417595 0.9818 -0.185269 0.0453336 0.984364 -0.17021 0.010781 0.979764 -0.199866 0.017518 0.981942 -0.188371 -0.0255158 0.981703 -0.188702 0.153799 0.983967 0.0903097 0.151276 0.983836 0.0958208 0.151149 0.983827 0.0961136 0.223902 0.968376 0.110073 0.211618 0.967733 0.136784 0.198727 0.971287 0.130803 0.201118 0.971477 0.125637 0.200357 0.971633 0.125641 0.212929 0.972122 0.098179 0.217004 0.971222 0.0981672 0.228317 0.972118 0.0534526 0.232279 0.971224 0.0526341 0.234412 0.972114 0.00667403 0.238072 0.971234 0.00505462 0.233927 0.972007 -0.0219054 0.237606 0.971089 -0.0230061 0.241124 0.97023 -0.0226399 0.72464 0.689123 0.0026658 0.72022 0.693715 0.00650503 0.709558 0.689102 0.147195 0.704444 0.693735 0.14997 0.665868 0.689161 0.285791 0.660209 0.693898 0.287452 0.631076 0.692793 0.348972 0.63243 0.691715 0.348657 0.629245 0.691421 0.354946 0.650244 0.668859 0.360292 0.67183 0.670023 0.315774 0.714703 0.691929 -0.102147 0.713795 0.692945 -0.101611 0.713962 0.692909 -0.100672 0.855704 0.517414 -0.00726585 0.853365 0.521295 -0.00441009 0.839992 0.517401 0.163432 0.83713 0.52131 0.165681 0.790525 0.517477 0.327547 0.787144 0.521577 0.329184 0.755322 0.521079 0.397448 0.756318 0.519929 0.39706 0.75404 0.519793 0.401546 0.768644 0.496425 0.403422 0.772557 0.496624 0.395626 0.883115 0.196864 0.425854 0.91056 0.18222 0.371048 0.713087 0.693873 -0.100235 0.842771 0.521128 -0.134768 0.842423 0.52175 -0.134537 0.933028 0.317677 -0.168937 0.932989 0.317814 -0.168895 0.975062 0.0962441 -0.199977 0.974914 0.104644 -0.196448 -0.725854 0.643818 -0.242148 -0.706197 0.664695 -0.243859 -0.739183 0.661947 -0.124238 -0.723555 0.678233 -0.12833 -0.73713 0.67569 -0.00904772 -0.726794 0.686719 -0.013716 -0.724196 0.685976 0.070549 -0.719723 0.690925 0.0679812 -0.719406 0.690839 0.0720883 -0.915869 0.395581 0.0685487 -0.946027 0.31563 0.0735596 -0.946546 0.31567 0.0663622 -0.94766 0.312082 0.0674146 -0.949275 0.31185 -0.0403329 -0.951693 0.304633 -0.0384713 -0.933114 0.305328 -0.189931 -0.936974 0.294604 -0.187849 -0.894515 0.295277 -0.335642 -0.899465 0.281887 -0.33392 -0.835889 0.282597 -0.470563 0.569666 0.818556 -0.073796 0.561315 0.824666 -0.0696468 0.561316 0.824666 -0.0696454 0.559985 0.825616 -0.0691008 0.569609 0.821888 0.00679465 0.564016 0.825696 0.0105558 0.556809 0.821861 0.120454 0.550531 0.825714 0.122928 0.521458 0.821891 0.229295 0.514762 0.825785 0.230432 0.489804 0.824493 0.283378 0.491221 0.823716 0.283185 0.487638 0.823321 0.290435 0.510526 0.806502 0.29819 0.514582 0.80692 0.289975 0.725504 0.56727 0.389677 0.751083 0.568143 0.336284 0.764191 0.554909 0.328768 0.806676 0.55747 0.196217 0.815467 0.547016 0.189177 0.834868 0.548698 0.0438826 0.839057 0.542626 0.0392563 0.832056 0.543272 -0.111974 0.832469 0.542506 -0.112619 0.80143 0.542542 -0.251711 0.801414 0.542582 -0.251674 0.748106 0.542586 -0.382017 0.748112 0.542562 -0.38204 0.67407 0.542561 -0.501256 0.674071 0.542546 -0.501271 0.580786 0.54257 -0.606883 0.580785 0.542563 -0.606889 0.471405 0.542561 -0.695274 0.4714 0.542543 -0.69529 0.348726 0.542566 -0.764207 0.348731 0.542576 -0.764197 0.216153 0.542574 -0.811722 0.216134 0.542541 -0.811748 0.077816 0.542558 -0.836406 0.0778284 0.542576 -0.836394 -0.0631861 0.542576 -0.837627 -0.0632127 0.542543 -0.837647 -0.201785 0.542552 -0.815426 -0.201762 0.542578 -0.815415 -0.341217 0.542334 -0.767754 -0.343429 0.539985 -0.768422 -0.474705 0.538964 -0.695826 -0.48042 0.533019 -0.696482 -0.594252 0.531152 -0.603939 -0.60161 0.523477 -0.603356 -0.674798 0.522542 -0.52115 -0.683375 0.513244 -0.51921 -0.688308 0.513094 -0.512803 -0.701077 0.490128 -0.517944 -0.696738 0.490272 -0.523632 -0.67871 0.520002 -0.518605 -0.693765 0.519458 -0.498853 -0.673424 0.543136 -0.501502 -0.725346 0.542098 -0.424268 -0.770699 0.473548 -0.426351 -0.831089 0.471817 -0.294414 -0.818977 0.491381 -0.296346 -0.85726 0.489641 -0.15924 -0.847601 0.505149 -0.162469 -0.863702 0.503448 -0.0236547 -0.857396 0.513949 -0.0269999 -0.854922 0.51374 0.0719671 -0.852066 0.518725 0.0700583 -0.85034 0.518367 0.0906489 -0.809668 0.581683 0.0779951 -0.409298 0.911007 0.0504099 -0.399192 0.915582 0.0485374 -0.399237 0.915598 0.0478604 -0.403968 0.913388 0.050321 -0.405282 0.914176 0.00540737 -0.417641 0.908549 0.010736 -0.409296 0.910617 -0.0570427 -0.427921 0.902286 -0.0525775 -0.407877 0.904743 -0.122789 -0.431843 0.893744 -0.121378 -0.402567 0.896521 -0.184905 -0.176181 0.98123 -0.0784037 -0.162388 0.982254 -0.0938473 -0.0125544 0.985951 -0.166565 -0.0465157 0.981079 -0.187937 -0.0703942 0.983227 -0.168255 -0.0788761 0.98172 -0.173219 -0.109485 0.981563 -0.156678 -0.113761 0.98085 -0.15809 -0.139094 0.98102 -0.135103 -0.144462 0.980132 -0.135908 -0.161193 0.979896 -0.117559 -0.166525 0.978953 -0.117981 -0.16587 0.978968 -0.118783 -0.16798 0.978836 -0.116888 0.406545 0.912558 -0.0442531 0.398949 0.916065 -0.0407903 0.398436 0.916171 -0.0433488 0.396989 0.916823 -0.0428457 0.404071 0.914701 0.00701816 0.398802 0.916984 0.00986769 0.394552 0.914678 0.0877063 0.388757 0.916995 0.0893793 0.368983 0.914685 0.164932 0.362938 0.917016 0.165403 0.343528 0.916005 0.207179 0.344708 0.915579 0.207101 0.341397 0.915225 0.214035 0.361134 0.905694 0.222037 0.36276 0.90587 0.218645 0.466199 0.848748 0.249572 0.471248 0.849039 0.238868 0.490932 0.83971 0.232107 0.518152 0.842815 0.14554 0.532669 0.835019 0.137863 0.545545 0.837178 0.0389108 0.55294 0.832555 0.0332974 0.547904 0.833397 -0.072465 0.548691 0.832804 -0.0733156 0.528029 0.832862 -0.16591 0.527997 0.832892 -0.165861 0.492899 0.832893 -0.251672 0.492913 0.832876 -0.251704 0.444127 0.832875 -0.330257 0.44413 0.83287 -0.330267 0.382659 0.832888 -0.399838 0.38266 0.832879 -0.399855 0.310607 0.832878 -0.45808 0.310604 0.832863 -0.458109 0.229758 0.832878 -0.503513 0.229761 0.832884 -0.503503 0.14244 0.832882 -0.534807 0.142423 0.832861 -0.534843 0.0512495 0.832873 -0.551087 0.0512684 0.83289 -0.551059 -0.041596 0.832891 -0.551872 -0.041633 0.832864 -0.55191 -0.132975 0.83287 -0.537258 -0.132945 0.832889 -0.537235 -0.226205 0.832664 -0.505472 -0.228692 0.831225 -0.506719 -0.317599 0.830258 -0.458042 -0.324338 0.826569 -0.459989 -0.4017 0.824733 -0.398062 -0.410646 0.819929 -0.398857 -0.459084 0.818775 -0.344746 -0.470825 0.812182 -0.344506 -0.474596 0.812006 -0.339713 -0.496431 0.794484 -0.349787 -0.496571 0.794476 -0.349608 -0.467142 0.816963 -0.338156 -0.482806 0.815965 -0.31796 -0.452873 0.833384 -0.316823 -0.483983 0.832131 -0.270774 -0.545946 0.790069 -0.27881 -0.58981 0.78669 -0.182327 -0.565419 0.80406 -0.183818 -0.592308 0.800986 -0.0871388 -0.573134 0.814313 -0.0917184 -0.584192 0.81161 0.00312443 -0.571476 0.820616 -0.00232495 -0.569389 0.819639 0.0631469 -0.564192 0.823434 0.0603612 -0.563685 0.823249 0.0672314 -0.578714 0.812461 0.0706927 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.000317427 0.999999 0.00107844 0 1 0 0 1 0 0 1 0 0 1 0 -0.000318258 1 0.000165864 -0.996182 0 0.0873048 -0.99653 0.0129253 0.0822196 -0.997214 0.0167663 0.0726884 -0.996449 0.0718519 0.0438846 -0.994244 0.072126 0.0792306 -0.981068 0.189804 0.0384599 -0.952253 0.296424 -0.0731187 -0.988945 0.139411 0.0505166 -0.849069 0.518703 0.100143 -0.798029 0.595984 0.0891811 -0.925273 0.34581 0.15584 -0.949792 0.2426 0.197589 -0.994441 0 0.105298 -0.995545 0.0303454 0.0892701 -0.988686 0.0593492 0.137761 -0.995549 0.0590909 0.0734133 -0.9722 0.172774 0.158039 -0.982089 0.17229 0.0762727 -0.900418 0.421483 0.107705 -0.949248 0.241058 0.202036 -0.950518 0.241145 0.195867 -0.962055 0.211114 0.17286 0.965039 0.137266 -0.223289 0.975378 0.072317 -0.208345 0.978015 0.160936 -0.13261 0.883066 0.433352 -0.180002 0.939654 0.285849 -0.187989 0.983231 0 -0.182362 0.986465 0.0477889 -0.156851 0.743286 0.664801 -0.0746057 0.793072 0.603797 -0.0804119 0.886271 0.442788 -0.135875 0.966651 0.246463 -0.0695804 0.965237 0.248083 -0.0822972 0.976172 0.0723486 -0.204581 0.979878 0.036093 -0.196309 0.968421 0.160077 -0.191146 0.986233 0.0470641 -0.158523 0.979072 0.165987 -0.117754 0.0341045 0.976164 0.21434 -0.905328 0.39601 0.153481 -0.971041 0.190806 0.143781 -0.965838 0.224693 0.129112 -0.958944 0.238545 0.153374 -0.53915 0.819907 0.192533 -0.555727 0.805886 0.204244 -0.384709 0.901398 0.1987 -0.282456 0.935313 0.21309 -0.256321 0.945327 0.201632 -0.153611 0.969147 0.192762 -0.0479221 0.98003 0.192988 -0.0493946 0.979795 0.193809 0.106064 0.979036 0.173896 0.25904 0.956638 0.1332 0.342069 0.929766 0.136106 0.420607 0.902582 0.0918449 0.582886 0.809912 0.0654717 0.582642 0.810071 0.0656835 0.724796 0.688944 -0.00515581 0.812551 0.5828 -0.0102292 0.8476 0.528429 -0.0483405 0.966814 0.220185 -0.129574 0.990516 0.105169 -0.0884174 0.938697 0.327561 -0.107482 0.674787 0.734907 -0.0676285 0.77686 0.628694 -0.0351047 0.775195 0.629392 -0.054205 0.893392 0.448194 0.0311737 0.591567 0.804137 0.0584049 0.708044 0.696583 0.115953 0.422461 0.895609 0.139324 0.503633 0.846389 0.173147 0.292904 0.937099 0.189873 0.118639 0.985333 0.12265 0.138423 0.983816 0.11378 0.18274 0.974746 0.12836 0.286339 0.951672 0.111038 0.262617 0.959063 0.105976 0.419333 0.903421 0.089385 0.374371 0.924117 0.0765099 0.589541 0.80734 0.0253654 0.516372 0.856295 0.0109118 0.592421 0.80562 0.00373484 0.320671 0.925755 0.20037 0.156001 0.964413 0.213475 0.15033 0.96461 0.216631 0.0560407 0.981203 0.18466 0.055752 0.981214 0.18469 0.0348317 0.984863 0.169801 -0.00697777 0.984467 0.17543 0.0144013 0.981679 0.189998 -0.0910738 0.974111 0.206912 -0.0394907 0.970016 0.23981 -0.213945 0.937557 0.274253 -0.235201 0.933967 0.269046 -0.3522 0.889296 0.291733 -0.431371 0.860722 0.270327 -0.542539 0.788061 0.29088 -0.52976 0.814619 0.236114 -0.494501 0.830293 0.257065 -0.276876 0.93004 0.241588 -0.256186 0.93325 0.251821 -0.0427487 0.97299 0.226855 -0.0432138 0.973018 0.226647 -0.650645 0.721638 0.236433 -0.660876 0.704392 0.258987 -0.663592 0.705693 0.248278 -0.744539 0.623852 0.237634 -0.726139 0.61594 0.305516 -0.488292 0.825737 0.282365 -0.422617 0.853306 0.305391 -0.250545 0.926934 0.279321 -0.231956 0.930109 0.284771 -0.0393889 0.967102 0.251321 -0.0376559 0.967051 0.251783 0.0257921 0.981602 0.189187 0.0205635 0.982076 0.187359 0.0252831 0.982553 0.184254 0.010635 0.983961 0.178068 0.10848 0.979037 0.17239 0.0302007 0.98264 0.183048 0.0343803 0.976251 0.213896 0.0243917 0.976253 0.215258 0.0248999 0.976136 0.215727 0.0160454 0.976071 0.216858 0.0174016 0.975911 0.217474 0.11228 0.972369 0.204673 0.119416 0.970821 0.207958 0.344519 0.923225 0.170183 0.333199 0.928331 0.164865 0.584779 0.803717 0.109877 0.559971 0.822832 0.0968539 0.814022 0.580383 0.0228855 0.786471 0.617618 0.00347518 0.96185 0.263617 -0.0731549 0.953739 0.283243 -0.100777 -0.848171 0.452766 0.27497 -0.770163 0.614983 0.169248 -0.776653 0.615912 0.132144 -0.668345 0.723848 0.171344 -0.575614 0.800954 0.164747 -0.572001 0.803663 0.164136 -0.49132 0.851096 0.185043 -0.376273 0.908698 0.180798 -0.30803 0.929588 0.202442 -0.232178 0.956273 0.177864 -0.192526 0.964562 0.180425 -0.0976129 0.98149 0.164769 -0.127371 0.980668 0.148549 -0.010765 0.988856 0.148488 -0.0287895 0.990281 0.136068 0.0479176 0.990948 0.1254 0.0359282 0.992319 0.118377 0.0777977 0.988746 0.127785 -0.794275 0.580548 0.179139 -0.787466 0.591558 0.173079 -0.780579 0.589716 0.2072 -0.940327 0.284097 0.187283 -0.928955 0.282548 0.239184 -0.918214 0.354122 0.177428 -0.8942 0.34988 0.279268 -0.878412 0.437598 0.192094 -0.87781 0.437498 0.195054 0.893229 0.445058 -0.0637557 0.959927 0.280245 -0.00172263 0.707506 0.704417 0.0568444 0.788015 0.607733 0.0984534 0.502973 0.851908 0.145847 0.561694 0.809719 0.169868 0.320746 0.925471 0.20156 0.335916 0.918819 0.207198 0.157395 0.961158 0.226719 0.120017 0.969606 0.213212 0.0605975 0.973819 0.219098 0.0154092 0.979005 0.203254 0.0389966 0.978866 0.200749 0.0210744 0.981972 0.187851 0.014232 0.981918 0.188773 0.0323419 0.97899 0.201327 0.0372919 0.978984 0.200497 0.0390519 0.976137 0.213616 0.041307 0.975831 0.214589 0.0368869 0.982672 0.181646 0.0239424 0.983738 0.178008 -0.934132 0.24906 0.255667 -0.865401 0.33924 0.368778 0.64291 0.253095 0.722917 0.205464 0.924606 0.320761 0.365182 0.89264 0.264264 0.705901 0.595962 0.382797 -0.575093 0.399068 0.714151 -0.521392 0.567839 0.636953 -0.43083 0.591617 0.68145 -0.345258 0.763367 0.545955 0.852772 0.0639736 0.51835 0.924232 0.00925678 0.381718 0.999373 0.0134968 -0.0327235 0.997681 0.0325612 0.0597732 0.997812 -0.0024603 0.0660741 0.996627 0.0483088 0.066341 0.712829 0.0661634 0.69821 0.751843 0.0708994 0.655519 -0.017852 0.0603443 0.998018 -0.0198064 0.0630166 0.997816 0.0989777 0.0514078 0.993761 0.102141 0.0469604 0.993661 0.213487 0.0602302 0.975087 0.225115 0.0462681 0.973233 0.324348 0.0609159 0.943974 0.335938 0.0468823 0.940717 0.429953 0.0635252 0.900614 0.441976 0.0484801 0.895716 0.529032 0.0682664 0.845851 0.542675 0.0504077 0.838429 -0.429073 0.176977 0.885763 -0.338153 0.0833358 0.937394 -0.249935 0.0760057 0.965275 -0.271403 0.109297 0.95624 -0.134454 0.0199136 0.99072 -0.170572 0.0930712 0.98094 -0.0887114 0.0634786 0.994033 -0.633559 0.269496 0.725241 -0.561125 0.108085 0.820644 -0.506864 0.101481 0.856032 -0.816514 0.111931 0.566371 -0.761962 0.219853 0.609162 -0.951269 0.090165 0.294886 -0.933291 0.083368 0.349311 -0.88343 0.201691 0.422933 -0.883975 0.177443 0.432553 -0.852532 0.12001 0.508711 -0.414154 0.125369 0.901532 -0.410706 0.199535 0.889666 -0.402685 0.168031 0.899784 0.0147459 0.628532 0.777644 -0.169922 0.59945 0.782168 0.725111 0.529326 0.440486 -0.278339 0.77377 0.569041 -0.0924154 0.851358 0.516381 -0.182322 0.851594 0.491474 -0.282871 0.845786 0.452361 -0.251196 0.877743 0.408004 -0.223798 0.904854 0.36215 -0.215063 0.877815 0.428006 -0.202452 0.864005 0.460986 -0.386626 0.721027 0.575013 -0.480855 0.262444 0.836601 -0.598737 0.256876 0.758636 -0.611844 0.10323 0.784214 -0.744177 0.12853 0.655501 0.775574 0.441017 0.451651 0.479795 0.841631 0.247898 0.537204 0.786638 0.304322 0.618602 0.700318 0.356212 0.620652 0.691281 0.370028 0.703874 0.59768 0.38385 0.387684 0.818234 0.424494 0.540213 0.599819 0.590243 0.466684 0.725638 0.505624 0.797402 0.212036 0.564969 0.809258 0.103876 0.578196 0.7838 0.181559 0.593881 0.993618 0.0668405 -0.0908641 0.99267 0.0731661 -0.0961931 0.985765 0.16706 -0.018908 0.985573 0.168175 -0.0190403 0.961991 0.265673 0.0631702 0.955173 0.289344 0.0626432 0.90536 0.395281 0.155164 0.877811 0.452279 0.157773 0.828711 0.516152 0.21639 0.744625 0.639898 0.189907 0.634658 0.725939 0.264996 0.943008 0.212925 0.255734 0.934411 0.276501 0.224553 0.962366 0.0679551 0.263124 0.961969 0.130212 0.240124 0.966162 -0.0442489 0.254113 0.971133 0.081907 0.224037 0.881111 0.0691856 0.467821 0.908205 0.102542 0.40577 0.897389 0.19462 0.396001 0.897299 0.148607 0.415658 0.841577 0.400599 0.362311 0.850104 0.352029 0.391662 0.770603 0.551354 0.319656 0.786347 0.503874 0.357449 0.710946 0.642052 0.286923 0.389239 0.887906 0.245186 0.414075 0.887754 0.201087 0.407208 0.885626 0.223269 0.498236 0.823076 0.272594 0.609729 0.763134 0.214144 0.730169 0.597895 0.330718 0.831048 0.507266 0.228124 0.862564 0.434314 0.259528 0.956698 0.157838 0.244575 0.921004 0.317044 0.226349 0.973696 0.211291 0.0852744 0.986397 0.137724 0.0897357 0.998346 -0.0166489 0.0550312 0.990627 0.126997 0.050297 0.995865 0.0550001 -0.0723019 0.997842 0.0308451 -0.0579656 0.205922 0.927958 0.310629 0.101819 0.937399 0.333041 0.102595 0.938575 0.329472 0.456798 0.734309 0.502122 0.322132 0.763785 0.559342 0.322781 0.769689 0.55081 0.170169 0.786614 0.593533 0.171055 0.788957 0.590158 0.851079 0.438744 0.288389 0.804164 0.287135 0.520456 0.831264 0.0947801 0.547738 0.76331 0.215417 0.60906 0.658943 0.25215 0.708671 0.717946 0.447346 0.533325 0.59048 0.484799 0.645216 0.549006 0.563359 0.61743 0.43992 0.58691 0.679711 0.377668 0.642152 0.667089 0.0742693 0.625128 0.77698 0.168438 0.623997 0.763057 0.204712 0.662262 0.720765 0.261262 0.615924 0.743223 0.350883 0.607041 0.713009 0.328834 0.904607 0.271208 0.300638 0.913855 0.272919 0.310694 0.894328 0.321942 0.311991 0.904957 0.289335 0.38881 0.817343 0.425179 0.274786 0.840842 0.466346 0.275359 0.84582 0.456909 0.142319 0.859945 0.490143 0.143171 0.861825 0.486579 0.00159273 0.938677 0.344793 -0.144739 0.76436 0.628334 -0.136548 0.777715 0.613607 -0.136379 0.801975 0.581581 -0.126862 0.850915 0.509755 -0.124954 0.848003 0.515051 -0.105055 0.930583 0.350682 -0.993778 0.0718117 0.0851407 -0.993915 0.0807701 0.074901 -0.969471 0.206735 0.131857 -0.969973 0.21269 0.117962 -0.891976 0.403904 0.203078 -0.894983 0.409333 0.177348 -0.745438 0.611445 0.265438 -0.756192 0.61464 0.224479 -0.593502 0.753068 0.283978 -0.611268 0.75319 0.243013 -0.432723 0.854742 0.286647 -0.102794 0.92833 0.357262 -0.215322 0.91014 0.353952 -0.225335 0.902511 0.367011 -0.346028 0.869726 0.351912 -0.3676 0.851404 0.37414 -0.46527 0.812345 0.351595 -0.56368 0.718899 0.406754 -0.994082 0.0696073 0.0833971 -0.994081 0.0703151 0.0828182 -0.975393 0.157179 0.154607 -0.975902 0.16607 0.141546 -0.919438 0.302166 0.251653 -0.922178 0.313419 0.226619 -0.818042 0.461326 0.343489 -0.826764 0.473495 0.30375 -0.704789 0.59007 0.393815 -0.557233 0.696044 0.452786 -0.438163 0.748517 0.49773 -0.419617 0.769878 0.480842 -0.341214 0.796026 0.499916 -0.320426 0.810143 0.490913 0.000787825 0.939206 0.343353 0.010834 0.862529 0.505891 0.0103455 0.863023 0.505059 0.0167121 0.790306 0.612485 0.0164694 0.790614 0.612093 0.0261594 0.623913 0.781056 -0.0214412 0.701053 0.712787 -0.29819 0.718316 0.628574 -0.117106 0.61173 0.782351 -0.165174 0.608216 0.776396 -0.199214 0.689391 0.696458 -0.117745 0.616165 0.778766 -0.330337 0.460541 0.823881 -0.232611 0.292942 0.927403 -0.243214 0.29286 0.924705 -0.243221 0.29287 0.9247 -0.132238 0.294829 0.946356 -0.131775 0.294256 0.946598 -0.0195606 0.295271 0.955213 -0.0187858 0.294363 0.955509 0.0931638 0.294429 0.951122 0.0941696 0.293288 0.951375 0.203923 0.292383 0.934306 0.205172 0.290983 0.93447 0.311221 0.289076 0.905305 0.312827 0.287255 0.905331 0.413628 0.284322 0.864912 0.415777 0.281804 0.864706 0.510028 0.277834 0.814051 0.512952 0.274219 0.813439 0.644747 0.265151 0.716936 0.662676 0.0880257 0.743715 0.626066 0.183728 0.757816 -0.4048 0.672359 0.619734 -0.430988 0.700595 0.568697 -0.475313 0.684382 0.5529 -0.475917 0.668173 0.571881 -0.647106 0.589344 0.483661 -0.662309 0.397698 0.634967 -0.691794 0.531951 0.488313 -0.616798 0.687224 0.383775 0.988606 0.0886894 -0.121626 0.989789 0.0830343 -0.115858 0.973846 0.221148 -0.0521288 0.974043 0.220339 -0.0518755 0.932471 0.36083 0.0173136 0.9237 0.382916 0.0124123 0.834227 0.542606 0.0981984 0.796684 0.597845 0.0887459 0.703995 0.694653 0.147814 0.641752 0.754366 0.138154 0.552131 0.813812 0.181276 0.468682 0.870616 0.149551 0.374539 0.908535 0.185162 0.322694 0.932162 0.16414 0.246719 0.950752 0.18762 0.219476 0.959869 0.174593 0.150336 0.969827 0.191923 0.137668 0.973124 0.184598 0.0691015 0.97779 0.197868 0.0653748 0.97858 0.195212 -0.00739412 0.978732 0.205008 -0.00539533 0.978366 0.206811 -0.0866647 0.973264 0.212712 -0.0805678 0.972181 0.219938 -0.176651 0.95922 0.220663 -0.167455 0.957213 0.236012 -0.288102 0.929923 0.228563 -0.277476 0.925545 0.25763 -0.399886 0.88427 0.241159 -0.446518 0.876802 0.178437 -0.600596 0.682268 0.416887 -0.718755 0.598577 0.35369 -0.769738 0.47766 0.42349 -0.860522 0.26498 0.435073 -0.994073 0.0706009 0.0826725 -0.994199 0.0649801 0.0857148 -0.980001 0.110825 0.165273 -0.980522 0.122278 0.153706 -0.946944 0.186642 0.261654 -0.946938 0.187253 0.261238 -0.860168 0.267329 0.434334 -0.855061 0.327162 0.402288 -0.70944 0.41083 0.572637 -0.706993 0.446311 0.548605 -0.552582 0.505554 0.662622 -0.560345 0.461874 0.687521 -0.993558 0.0778289 0.0823736 -0.994682 0.0511022 0.0894237 -0.981921 0.10475 0.157664 -0.977624 0.0518884 0.203862 -0.953567 0.119416 0.276496 -0.954919 0.123266 0.270066 -0.883939 0.137811 0.446834 -0.884161 0.196892 0.423666 -0.755776 0.21445 0.61872 -0.757665 0.247295 0.603977 -0.602219 0.26054 0.75462 -0.531834 -0.0507741 0.845325 -0.989531 0.111803 0.0912568 -0.993817 0.109049 0.0208892 -0.951558 0.278229 0.130866 -0.962392 0.253024 0.0988984 -0.183001 0.978452 0.0956208 -0.140936 0.983791 0.110873 -0.294169 0.949789 0.106613 -0.187978 0.964611 0.184906 -0.448724 0.888561 0.0954273 -0.318726 0.926405 0.200467 -0.64717 0.75056 0.133531 -0.625663 0.76498 0.152814 -0.859081 0.489452 0.14972 -0.865768 0.480079 0.141312 -0.928872 0.354313 0.10798 0.190983 0.980296 0.0504433 0.980472 0.0933499 -0.173093 0.97956 0.0953161 -0.177133 0.968641 0.238571 -0.0694192 0.962314 0.261633 -0.0741654 0.89541 0.443584 -0.0384091 0.911987 0.40951 -0.0241202 0.713329 0.699975 0.0345878 0.707981 0.705487 0.0324247 0.512583 0.853211 0.0963863 0.377681 0.923026 0.0733452 0.332832 0.937792 0.0988364 0.208709 0.975027 0.0759168 0.14057 0.985813 0.0917239 0.105892 0.99257 0.0599326 0.0830008 0.99437 0.0658804 0.118395 0.992298 0.0364398 0.0635634 0.996878 0.0468418 0.0711955 0.996442 0.045114 0.0468075 0.998148 0.0388515 0.0272111 0.998728 0.0424414 0.0251261 0.998808 0.0418461 -0.0151806 0.999062 0.0405598 -0.0050347 0.998954 0.0454573 -0.0590331 0.996826 0.0534063 -0.041104 0.99738 0.0595323 -0.111148 0.991888 0.061685 -0.0741253 0.994049 0.0798314 -0.110182 0.990766 0.0790091 -0.992715 0.0807558 0.0894131 -0.993799 0.0876367 0.0684286 -0.96236 0.243518 0.120676 -0.965998 0.237191 0.102899 -0.860534 0.47579 0.181949 -0.876933 0.456941 0.148975 -0.660403 0.713904 0.232827 -0.708547 0.681953 0.181389 -0.475156 0.847664 0.235994 -0.542901 0.8189 0.186176 -0.315232 0.922721 0.221846 -0.371182 0.914268 0.162291 -0.194164 0.96462 0.178352 -0.235765 0.960749 0.146209 -0.116853 0.981751 0.150032 -0.144185 0.980481 0.133668 -0.0576998 0.989627 0.131567 -0.0732444 0.989554 0.124167 -0.00721313 0.992883 0.118877 -0.0120799 0.993057 0.117012 0.039783 0.993128 0.11006 0.0466047 0.992593 0.11219 0.0871555 0.990676 0.104711 0.109363 0.987844 0.110473 0.141553 0.984553 0.103045 0.185826 0.976068 0.112964 0.214043 0.971136 0.10526 0.292139 0.948623 0.121528 0.336798 0.935421 0.107491 0.456191 0.879625 0.134719 0.518996 0.847465 0.111559 0.621965 0.774737 0.11376 0.72417 0.686459 0.0659656 0.784858 0.61562 0.0707829 0.902398 0.430778 -0.0103801 0.915022 0.40335 -0.00655835 0.968581 0.238721 -0.0697404 0.968013 0.24085 -0.0703053 0.988876 0.0771601 -0.127162 0.982366 0.105016 -0.154691 0.513745 0.857811 -0.0150447 0.185499 0.982643 0.00152344 0.879405 0.431281 -0.201604 -0.327839 0.940747 0.0866981 -0.337425 0.9409 0.0291893 -0.630075 0.774972 0.0492301 0.974924 0.0750022 -0.209519 0.969027 0.137474 -0.205153 -0.95124 0.301945 0.0630251 -0.988035 0.139571 0.0656183 -0.978935 0.198517 0.0477224 -0.972762 0.225515 0.0536411 -0.97265 0.225605 0.0552748 -0.974177 0.219248 0.0539407 0.962889 0.168593 -0.210763 0.963711 0.168695 -0.20689 0.959711 0.186526 -0.210148 0.959725 0.18653 -0.210084 0.959506 0.187454 -0.21026 0.959462 0.187443 -0.210471 0.961832 0.167688 -0.216242 0.963291 0.165388 -0.211466 0.964255 0.18098 -0.193543 0.979047 0.0533542 -0.196522 0.979453 0.0618293 -0.191962 0.979764 0.0649292 -0.189333 0.98732 0.0954023 -0.126878 0.951544 0.225349 -0.209243 0.947946 0.261702 -0.181412 0.905152 0.397778 -0.149911 0.901299 0.411512 -0.13534 0.801179 0.577657 -0.156285 0.639668 0.768066 0.0299858 0.695603 0.711303 -0.100916 0.517903 0.851222 -0.0848433 0.365586 0.930082 -0.0359855 0.426175 0.903238 0.050363 0.37413 0.927368 -0.00386681 0.341996 0.939346 -0.025836 0.31929 0.946945 -0.0367439 0.285964 0.957091 -0.0469196 0.33915 0.938212 -0.06882 0.425317 0.900391 -0.0916667 0.253145 0.965976 -0.0529822 0.225506 0.972874 -0.0516077 0.194011 0.980199 -0.039614 0.0549618 0.998346 -0.0168688 0.0715962 0.997246 -0.0193425 0.0940088 0.995146 -0.0290941 -0.0850862 0.996373 0.000890991 -0.0497703 0.998754 -0.00353719 -0.0330309 0.999406 -0.00985176 -0.0120602 0.999909 -0.00599581 0.0176888 0.999761 -0.0128423 -0.362431 0.931298 0.0364467 -0.390255 0.919962 0.0370179 -0.153949 0.987873 0.0201724 -0.240122 0.970277 0.0300673 -0.213448 0.976792 0.0178326 -0.263679 0.964144 0.0299904 -0.257382 0.965913 0.0276768 -0.318086 0.946684 0.0511012 -0.345233 0.936417 0.0627443 -0.371488 0.92531 0.0761424 -0.404466 0.909441 0.0965612 -0.343496 0.937819 0.0500529 -0.492093 0.868383 0.0612808 -0.635695 0.766694 0.0898524 -0.61518 0.78204 0.0998368 -0.969511 0.230482 0.0832258 -0.931344 0.354068 0.0850541 -0.906446 0.414735 0.0796936 -0.872526 0.480022 0.0909775 -0.803232 0.591212 0.0727089 -0.726222 0.682224 0.0846954 -0.0744496 0.996927 -0.0243788 -0.100801 0.994763 -0.0169029 -0.0966317 0.99532 -0.00079201 -0.119848 0.992743 0.00987932 -0.103769 0.993863 -0.0383142 -0.0968295 0.993951 -0.0518244 -0.0941985 0.994201 -0.0518766 -0.0811564 0.995271 -0.0533852 -0.0742717 0.995725 -0.0549071 -0.0669419 0.996079 -0.057848 -0.0452051 0.996274 -0.0734434 -0.0564113 0.994493 -0.0883278 -0.0346715 0.997187 -0.0664555 -0.019323 0.998177 -0.0571791 -0.00944347 0.999258 -0.0373436 -0.0157989 0.99948 -0.0281178 -0.0181219 0.999616 -0.0209551 -0.0196142 0.999739 -0.0116931 -0.0203631 0.999713 0.0126111 -0.016861 0.99714 0.0736747 -0.0469576 0.998897 0.000182218 -0.062145 0.997822 -0.022141 0.909407 0.375408 -0.17902 0.8954 0.403965 -0.187274 0.960226 0.213625 -0.179807 0.413939 0.905613 -0.0923022 0.57987 0.80775 -0.10626 0.700508 0.69688 -0.153775 0.759507 0.63372 -0.146792 0.840301 0.517791 -0.160585 -0.791661 0.610706 -0.0176362 -0.611996 0.787997 0.0672454 -0.471762 0.881349 0.0257821 -0.471766 0.881347 0.0257805 -0.424106 0.904929 0.0351957 -0.70151 0.707451 0.0860102 -0.906271 0.419676 0.0504549 -0.904204 0.424608 0.0460747 -0.973641 0.207626 0.0944211 -0.971469 0.226256 0.071104 -0.994908 0.069304 0.0731831 -0.994982 0.0648473 0.0761996 -0.994822 0.0697492 0.0739229 -0.993561 0.0809175 0.0793065 -0.988497 0.111847 0.101807 -0.958745 0.277571 0.06134 -0.29783 0.9546 -0.00596819 -0.34966 0.936767 -0.0143177 -0.42051 0.907246 -0.00876061 -0.980577 0.188414 0.0544892 -0.973676 0.219647 0.0609068 -0.886781 0.458996 0.0542496 -0.887481 0.45831 0.0482604 -0.884413 0.464143 0.048833 -0.885448 0.463081 0.0392266 -0.90789 0.417775 0.034646 -0.586711 0.803758 0.0987131 -0.679375 0.726081 0.106092 -0.623127 0.776779 0.0912489 -0.799281 0.595823 0.0783938 -0.851131 0.518474 0.0822256 -0.752937 0.657733 0.0217362 -0.749934 0.660249 0.0408729 -0.765732 0.641965 0.0391802 -0.762037 0.644713 0.0603659 -0.865826 0.498126 0.0470681 -0.861883 0.500153 0.0836912 -0.904536 0.420901 0.0682387 -0.591834 0.806059 0.0015699 -0.440621 0.897638 -0.00993555 -0.431099 0.901882 0.0276015 -0.378461 0.925335 0.0228461 -0.366633 0.928324 0.0616075 -0.275456 0.959909 0.0519539 -0.267442 0.959179 0.0919294 -0.223589 0.974602 -0.0126263 -0.264002 0.964432 0.0131456 -0.261622 0.96493 0.021538 -0.260594 0.965225 0.0207874 -0.249898 0.966655 0.0559275 -0.180164 0.983299 0.0257583 -0.170896 0.982456 0.0746591 -0.0986167 0.994271 0.0412188 -0.201831 0.971572 0.123745 -0.136673 0.986783 0.0870664 -0.502534 0.855713 0.123347 -0.403326 0.910719 0.0889914 -0.410068 0.910431 0.0543945 -0.542312 0.837504 0.0669773 -0.553892 0.832311 0.0215015 -0.575074 0.81767 0.0265654 -0.580151 0.814505 0.0024712 -0.782668 0.622172 0.0182515 0.183322 0.982764 -0.0238333 0.132066 0.991109 -0.0161793 0.13158 0.990725 -0.0339094 0.409977 0.90386 -0.122296 0.393806 0.915779 -0.079154 0.393756 0.913412 -0.103121 0.334943 0.93608 -0.10755 0.523633 0.846454 -0.0965642 0.523519 0.845792 -0.102779 0.470875 0.875528 -0.108295 0.469461 0.871341 -0.14273 0.503221 0.851974 -0.144602 0.0492388 0.998575 -0.0206027 0.0490989 0.998551 -0.0220322 0.0437018 0.998788 -0.0226226 0.0431004 0.99865 -0.0289866 0.0615598 0.997905 0.0198924 0.0698456 0.997526 0.00801821 0.0668132 0.997584 -0.0190058 0.252763 0.967362 0.0179378 0.17131 0.984693 0.0321514 0.106209 0.992563 0.0594903 0.11064 0.992118 0.0588236 0.0690039 0.994637 0.0770462 0.0713891 0.994374 0.0782572 0.0292858 0.997191 0.0689424 0.122765 0.991736 -0.0372572 0.226354 0.972568 -0.053617 0.226369 0.973093 -0.0429772 0.308988 0.949397 -0.0563128 0.308066 0.950959 -0.0277773 0.43918 0.897027 -0.0496391 0.44143 0.897081 -0.0196246 0.75467 0.634947 -0.165277 0.758307 0.636439 -0.141124 0.666577 0.732162 -0.14005 0.666059 0.731404 -0.146335 0.636665 0.75726 -0.145655 0.634114 0.75402 -0.171325 0.688519 0.704396 -0.172532 0.850642 0.484466 -0.204206 0.853064 0.486131 -0.189626 0.85833 0.47691 -0.189276 0.858818 0.477277 -0.186112 0.889233 0.418883 -0.183856 0.888371 0.41863 -0.188536 0.940812 0.285948 -0.18195 0.794281 0.603576 -0.0693849 0.743849 0.664705 -0.0696862 0.674617 0.734932 -0.0690464 0.586678 0.808148 -0.0520094 0.365767 0.93069 -0.00558887 0.290838 0.956623 0.0169042 0.28736 0.95734 -0.030407 0.216614 0.976067 -0.0192973 0.216985 0.975184 -0.0439712 0.142903 0.989197 -0.0326918 0.142785 0.989105 -0.0358163 0.04261 0.998869 -0.0211089 -0.000666113 0.998662 -0.0517038 0.00692225 0.998718 -0.05015 0.0244045 0.998322 -0.0525157 0.0273056 0.999486 -0.0168169 0.0395173 0.999108 -0.0149146 0.978944 0.0449159 -0.199125 0.975264 0.0752115 -0.207856 0.9618 0.179973 -0.206279 0.958914 0.192856 -0.208062 0.905892 0.373129 -0.200338 0.894147 0.399 -0.203223 0.698726 0.694905 -0.169965 0.675091 0.717595 -0.171201 0.423618 0.897247 -0.124484 0.40734 0.904759 -0.124442 0.224725 0.970325 -0.0892642 0.222266 0.970854 -0.0896714 0.0991613 0.992837 -0.0666482 0.0978 0.992143 -0.078019 0.0426998 0.996766 -0.0680753 0.970091 0.11714 -0.212608 0.960298 0.165164 -0.224829 0.92744 0.302249 -0.220231 0.87242 0.429811 -0.232691 0.806069 0.549073 -0.220842 0.67731 0.70007 -0.226173 0.579725 0.788416 -0.205719 0.492369 0.84641 -0.202886 0.381206 0.907191 -0.178006 0.400327 0.898705 -0.179073 0.249371 0.957465 -0.145175 0.330252 0.933779 -0.13781 0.259988 0.962392 -0.0787952 0.263496 0.963206 -0.0529527 0.141133 0.985124 -0.098044 0.136782 0.983348 -0.119654 0.249611 0.957567 -0.144081 0.214392 0.965365 -0.148681 0.379279 0.906368 -0.186131 0.397443 0.898429 -0.186719 0.574826 0.786829 -0.224668 0.664922 0.712878 -0.222898 0.798972 0.548036 -0.247588 0.887677 0.39739 -0.232618 0.923166 0.30217 -0.237611 0.955743 0.192432 -0.222541 0.967606 0.117165 -0.22363 0.974463 0.0749772 -0.21166 -0.103901 0.994355 -0.0214921 -0.110312 0.993469 -0.029152 -0.252118 0.96756 -0.0162523 -0.238297 0.971107 -0.0128696 -0.475789 0.879527 0.00751576 -0.478965 0.877804 0.00720511 -0.712151 0.701458 0.0282515 -0.716121 0.697425 0.0277114 -0.906656 0.419267 0.046808 -0.902876 0.427234 0.0478117 -0.977191 0.204689 0.0565665 -0.973739 0.219987 0.058631 -0.994876 0.0801721 0.0615948 -0.994526 0.0834523 0.0628717 -0.989429 0.133778 0.0559816 -0.995667 0.0831851 0.0415653 -0.949471 0.311941 0.0346221 -0.975517 0.218802 0.022207 -0.854115 0.520033 0.00733347 -0.90558 0.424145 -0.00502758 -0.660703 0.750118 -0.0281886 -0.721089 0.691839 -0.0372898 -0.447507 0.892459 -0.0570476 -0.486677 0.871374 -0.0620775 -0.254825 0.964042 -0.0754123 -0.246865 0.966291 -0.0730769 -0.144213 0.986371 -0.0792182 -0.0965947 0.994052 -0.0502967 -0.0623039 0.996622 -0.0535089 -0.0404559 0.998356 -0.040613 0.024843 0.998464 -0.0495314 0.0244566 0.998318 -0.0525681 0.0968209 0.993218 -0.0643766 0.0974796 0.994757 -0.0309105 0.124958 0.991754 -0.0284513 -0.0370042 0.996273 0.0779148 -0.046574 0.994999 0.0883578 -0.0555496 0.99814 0.0251291 -0.063512 0.997301 0.0368276 -0.0694969 0.997582 -0.000415342 -0.0881875 0.995999 0.0144349 -0.092124 0.995739 -0.0040454 -0.0999874 0.994988 0.00145847 -0.100318 0.994955 -0.000150501 -0.08925 0.995985 -0.00695002 0.888278 0.433925 -0.15057 0.611014 0.78588 -0.0951554 0.611965 0.786215 -0.0858132 0.421399 0.905395 -0.0518001 0.421927 0.903423 -0.0761878 0.307095 0.95 -0.0565113 0.307301 0.94862 -0.0754095 0.192814 0.979637 -0.0559817 0.19215 0.979474 -0.060897 0.121242 0.991432 -0.0486195 0.0511926 0.998569 -0.0154728 0.0432263 0.998928 -0.0165358 -0.0566615 0.998389 -0.00289819 -0.0906842 0.995729 -0.017342 -0.139037 0.990208 -0.0125474 -0.229226 0.971764 -0.0559533 -0.253566 0.96579 -0.054358 -0.305268 0.949905 -0.0670188 -0.447584 0.892294 -0.0589951 -0.425574 0.903152 -0.0565958 -0.660986 0.749237 -0.0417313 -0.594805 0.803175 -0.0334179 -0.854428 0.5194 -0.0133053 -0.783872 0.620922 -0.00077951 -0.950018 0.311823 0.0152573 -0.90824 0.417499 0.0281966 -0.983759 0.175724 0.0365881 -0.978594 0.19863 0.0538591 0.976795 0 -0.214176 0.976795 1.00028e-07 -0.214175 0.976795 0 -0.214176 0.976795 0 -0.214176 0.976796 3.6778e-07 -0.21417 0.976795 2.43331e-07 -0.214175 0.976785 0 -0.214223 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0848524 -0.996084 -0.0248503 0 -1 0 0 -1 0 0 -1 0 0.0720925 -0.99581 0.0562552 0 -1 0 0 -1 0 0 -1 0 0.210525 -0.977228 0.0265559 0.205048 -0.978027 -0.0376605 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.101578 -0.994698 -0.0160871 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.108831 -0.993822 -0.0217738 -0.314566 -0.947733 0.053386 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0199027 -0.998939 0.0415203 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.919359 0.392834 -0.0214603 -0.966561 -0.22274 -0.127071 -0.98848 7.7713e-06 -0.151352 -0.968612 3.56515e-05 -0.248576 -0.96756 -0.072649 -0.241971 -0.94839 0.0230397 -0.316267 -0.929341 -0.080075 -0.360436 -0.925037 0.000937032 -0.379877 -0.904973 0.000938496 -0.425467 -0.881819 -0.0523124 -0.468677 -0.870717 0.0490498 -0.489333 -0.820592 -0.0396765 -0.570136 -0.813694 4.10954e-05 -0.581293 -0.786384 4.07113e-05 -0.617738 -0.773528 0.00225292 -0.633758 -0.77404 -0.00366067 -0.633126 -0.773018 -7.64316e-07 -0.634384 -0.773019 -3.13686e-07 -0.634383 -0.773018 1.45693e-06 -0.634384 -0.773018 8.1074e-07 -0.634384 -0.753648 -0.000402655 -0.657278 -0.761655 -0.00685284 -0.647947 -0.639483 0.0159393 -0.76864 -0.645283 0.008106 -0.7639 -0.50809 -0.00281761 -0.8613 -0.425242 -0.0371458 -0.904317 -0.352528 0.0259122 -0.935443 -0.264161 0.00243072 -0.964476 -0.139652 -0.00620212 -0.990181 -0.190631 -0.0438877 -0.98068 0.0328388 0.0615795 -0.997562 -0.0193806 0.00880711 -0.999773 0.158869 -0.00302749 -0.987295 0.148241 -0.00701597 -0.988926 0.326585 0.0212465 -0.944929 0.31609 0.00953085 -0.948681 0.553774 -0.00885443 -0.83262 0.542352 -0.0223009 -0.839855 0.688868 0.0101852 -0.724815 0.67229 2.4526e-05 -0.740288 0.720645 2.43719e-05 -0.693305 0.775083 -0.0057158 -0.631834 0.799232 0.0194044 -0.60071 0.872479 -0.011832 -0.488509 0.886631 5.3314e-07 -0.462478 0.917645 5.5137e-07 -0.397402 0.927123 -0.00388415 -0.374738 0.958845 0.0145241 -0.283557 0.977377 -0.030321 -0.20932 0.990877 8.63582e-06 -0.134771 0.997681 -2.36601e-06 -0.0680628 0.998997 -0.0132861 0.0427497 0.99847 -0.00257251 0.0552298 0.97669 0.00148598 0.214651 0.977463 3.5825e-05 0.211107 0.963015 1.19574e-05 0.269448 0.941954 -0.00562146 0.335694 0.930964 0.0121546 0.364909 0.910883 -1.93738e-05 0.412665 0.910869 5.16427e-08 0.412696 0.910869 -4.75579e-07 0.412696 0.910869 3.35293e-07 0.412696 0.910869 2.17371e-06 0.412695 0.910869 1.32584e-06 0.412695 0.910869 5.43657e-07 0.412695 0.917651 -1.09957e-05 0.397387 0.935752 -0.0267354 0.351643 0.96795 0.100421 0.230191 0.985822 -0.0646522 0.154838 0.997808 -0.00276095 0.0661226 0.999867 0.00236524 -0.0161566 0.984503 0.156096 -0.0799207 0.990191 0.0911697 -0.10588 0.976144 -0.0379716 -0.213776 0.976051 -0.0390414 -0.214011 0.897824 0.000736632 -0.440354 0.897166 -3.43144e-05 -0.441694 0.897179 -1.72816e-05 -0.441667 0.897199 1.67308e-05 -0.441627 0.897178 -4.22178e-06 -0.441669 0.897182 0 -0.441662 0.897193 1.25159e-06 -0.441639 0.897185 0 -0.441654 0.897188 8.83452e-07 -0.44165 0.897178 -1.11447e-06 -0.441669 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.99848 -4.6015e-07 0.0551203 -0.99848 8.35154e-07 0.0551185 -0.99848 -1.52476e-06 0.0551185 -0.99848 3.34534e-06 0.0551181 -0.99848 -7.42935e-07 0.0551186 -0.99848 4.97856e-07 0.0551182 -0.99848 -7.66951e-07 0.0551192 -0.99848 8.90365e-07 0.0551171 -0.99848 -4.24814e-08 0.0551188 -0.99848 -8.03868e-08 0.0551184 -0.998479 3.76344e-05 0.0551249 -0.998481 6.76612e-06 0.0551018 -0.99848 0 0.0551184 -0.99848 2.66665e-05 0.0551216 -0.99848 4.50846e-06 0.0551202 -0.998479 1.45515e-05 0.0551303 -0.99848 -4.81568e-06 0.0551202 -0.99848 0 0.0551185 -0.99848 -1.21978e-07 0.0551182 -0.99848 -1.23949e-07 0.0551186 -0.99848 0 0.0551187 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258831 0 0.965923 0.258831 0 0.965923 0.707116 0 0.707098 0.707116 0 0.707098 0.965929 0 0.258806 0.965929 0 0.258806 0.998663 0 -0.0516979 0.987494 0.0204868 -0.156321 0.964143 0.0606729 -0.258355 0.706858 0.0269549 0.706841 0.734315 -0.00748158 0.678768 0.965898 0.00810213 0.258798 0.937524 0.0883031 0.336528 0.995723 0 0.0923862 0.0513207 -1.24941e-06 0.998682 0.103581 0.00984031 0.994572 0.25862 0.0404771 0.965131 0.309799 1.28336e-05 0.950802 0.526384 -8.53144e-07 0.850247 -0.442365 1.26545e-05 0.896835 -0.258552 0.044394 0.964977 -0.28827 0.0655293 0.955304 -0.0923371 5.40415e-06 0.995728 -0.643307 1.20789e-05 0.765609 -0.706218 0.0498723 0.706236 -0.819485 2.17589e-05 0.5731 -0.933912 8.65713e-06 0.357503 -0.964639 0.0515403 0.258488 -0.987939 0.0166444 0.153948 -0.873011 7.45332e-06 -0.487701 -0.942568 0.007276 -0.333937 -0.964817 0.0479648 -0.258509 -0.995705 0 -0.0925847 -0.998645 0 0.0520483 -0.706891 0.0252529 -0.706872 -0.713889 0.0186272 -0.700012 -0.851879 7.49874e-06 -0.523739 -0.0513917 -6.74067e-06 -0.998679 -0.154867 0.0167126 -0.987794 -0.258504 0.0503122 -0.964699 -0.356735 2.64297e-05 -0.934205 -0.532082 1.35605e-05 -0.846693 0.0930106 9.45758e-06 -0.995665 0.258482 0.0500667 -0.964718 0.282656 0.0366857 -0.95852 0.933826 -2.61269e-05 -0.357729 0.819554 9.11849e-06 -0.573002 0.70611 0.0528454 -0.706128 0.643291 1.59165e-05 -0.765622 0.442217 1.13265e-05 -0.896908 -0.948166 0 -0.317776 -0.936933 0.014146 -0.349224 0.312258 0.000397267 0.949997 0.793959 0 0.607971 0.790002 0.00169648 0.613101 0.682064 1.68941e-05 0.731293 0.475625 -0.000657816 0.879648 0.559676 0.0384388 0.82782 0.423961 0.010174 0.905623 0.165324 -0.000533807 0.986239 0.00199533 0.0159048 0.999872 0.00854306 0.0170897 0.999817 -0.392102 0.00420608 0.919912 -0.270704 -3.77916e-05 0.962663 -0.142657 0.000121251 0.989772 -0.833471 -0.00142073 0.552561 -0.905294 0.0452165 0.422373 -0.845665 0.0197862 0.533347 -0.749167 0.00020776 0.662381 -0.47211 -0.00048229 0.881539 -0.638944 0.0539426 0.76736 -0.549257 0.028484 0.835168 -0.978665 0.000148951 -0.205463 -0.996842 -0.000229571 -0.0794059 -0.995598 0.0197875 0.0916095 -0.993154 0.0135334 0.116028 -0.963806 0.000378291 0.266605 -0.119968 0 0.992778 -0.112912 -0.0010635 0.993604 -0.481014 0.00128978 0.876712 -0.504051 0.00564655 0.863655 -0.932392 1.21748e-05 0.361448 -0.897427 0.00439193 0.441141 -0.853092 0.0103957 0.521657 -0.803387 -0.000115922 0.595457 -0.674194 2.52582e-05 0.738554 -0.988584 -2.72297e-05 0.150668 -0.998423 0.0106528 0.0551157 -0.993051 -0.00156596 -0.117678 -0.951528 0.00162007 -0.307556 -0.905321 0.0110305 -0.424586 -0.861677 0.000628201 -0.507456 -0.22159 0 -0.97514 -0.251355 -0.00539375 -0.96788 -0.596047 0.00653497 -0.802923 -0.581251 0.00985428 -0.813664 -0.738206 -0.000257902 -0.674575 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707098 0.707115 0 0.707098 0.258831 0 0.965923 0.258831 0 0.965923 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.258831 0 -0.965923 -0.258831 0 -0.965923 0.258806 0 -0.965929 0.258806 0 -0.965929 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965923 0 -0.25883 0.965923 0 -0.25883 0.965929 0 0.258807 0.965929 0 0.258807 0.707116 0 0.707097 0.707116 0 0.707097 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965923 0 0.258829 -0.965923 0 0.258829 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707098 0.707115 0 0.707098 0.258831 0 0.965923 0.258831 0 0.965923 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258806 0.965929 0 0.258806 0.707116 0 0.707098 0.707116 0 0.707098 0.25883 0 0.965923 0.25883 0 0.965923 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.965922 0 0.258832 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258811 0 0.965928 -0.258811 0 0.965928 0.258826 0 0.965924 0.258826 0 0.965924 0.707122 0 0.707091 0.707122 0 0.707091 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.25883 0.965923 0 -0.25883 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258811 0 -0.965928 0.258811 0 -0.965928 -0.258841 0 -0.96592 -0.258841 0 -0.96592 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.965922 0 0.258832 -0.965923 0 0.258831 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.258796 0 0.965932 -0.258796 0 0.965932 0.258827 0 0.965924 0.258827 0 0.965924 0.707114 0 0.707099 0.707114 0 0.707099 0.965929 0 0.258808 0.965929 0 0.258808 0.965923 0 -0.258831 0.965923 0 -0.258831 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258811 0 -0.965928 0.258811 0 -0.965928 -0.258827 0 -0.965924 -0.258827 0 -0.965924 -0.707114 0 -0.707099 -0.707114 0 -0.707099 -0.96593 0 -0.258804 -0.96593 0 -0.258804 -0.965923 0 0.258831 -0.965923 0 0.25883 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258803 0 0.96593 -0.258803 0 0.96593 0.258827 0 0.965924 0.258827 0 0.965924 0.707118 0 0.707095 0.707118 0 0.707095 0.965929 0 0.258808 0.965929 0 0.258808 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258811 0 -0.965928 0.258811 0 -0.965928 -0.258834 0 -0.965922 -0.258834 0 -0.965922 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965923 0 0.25883 -0.965923 0 0.258831 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.258811 0 0.965928 -0.258811 0 0.965928 0.258834 0 0.965922 0.258834 0 0.965922 0.707114 0 0.7071 0.707114 0 0.7071 0.965929 0 0.258806 0.965929 0 0.258806 0.965923 0 -0.258831 0.965923 0 -0.258831 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258803 0 -0.96593 0.258803 0 -0.96593 -0.258827 0 -0.965924 -0.258827 0 -0.965924 -0.707118 0 -0.707096 -0.707118 0 -0.707096 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.965923 0 0.258831 -0.965922 0 0.258832 -0.707101 0 0.707113 -0.707101 0 0.707113 -0.258803 0 0.96593 -0.258803 0 0.96593 0.258834 0 0.965922 0.258834 0 0.965922 0.707115 0 0.707099 0.707115 0 0.707099 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258803 0 -0.96593 0.258803 0 -0.96593 -0.258834 0 -0.965922 -0.258834 0 -0.965922 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.258803 0 0.96593 -0.258803 0 0.96593 0.258827 0 0.965924 0.258827 0 0.965924 0.707118 0 0.707095 0.707118 0 0.707095 0.965929 0 0.258808 0.965929 0 0.258808 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258811 0 -0.965928 0.258811 0 -0.965928 -0.258834 0 -0.965922 -0.258834 0 -0.965922 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258832 -0.965922 0 0.258833 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258831 0 0.965923 0.258831 0 0.965923 0.707116 0 0.707097 0.707116 0 0.707097 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.25883 0.965923 0 -0.25883 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258833 -0.965922 0 0.258832 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.25883 0 0.965923 0.25883 0 0.965923 0.707116 0 0.707097 0.707116 0 0.707097 0.965929 0 0.258806 0.965929 0 0.258806 0.965923 0 -0.25883 0.965923 0 -0.25883 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.25883 0 -0.965923 -0.25883 0 -0.965923 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258832 -0.373497 -0.849121 -0.373488 -0.510205 -0.84912 -0.136699 0.373493 -0.849121 -0.373494 0.136701 -0.849122 -0.510201 -0.136716 -0.849122 -0.510197 0.3735 -0.849119 0.373491 0.510204 -0.84912 0.136703 0.510201 -0.84912 -0.136715 -0.373487 -0.849119 0.373502 -0.136703 -0.849119 0.510206 0.136717 -0.849118 0.510202 -0.510201 -0.84912 0.136715 -0.965931 0 -0.258802 -0.965931 0 -0.258802 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258835 0 -0.965922 -0.258835 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707106 0 -0.707108 0.707106 0 -0.707108 0.965923 0 -0.258832 0.965923 0 -0.258832 0.965929 0 0.258808 0.965929 0 0.258808 0.707115 0 0.707099 0.707115 0 0.707099 0.258835 0 0.965922 0.258835 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707093 0 0.707121 -0.707093 0 0.707121 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.3735 -0.849119 -0.373491 -0.510204 -0.84912 -0.136703 0.373487 -0.849119 -0.373502 0.136702 -0.849119 -0.510206 -0.136717 -0.849119 -0.510202 0.373497 -0.849121 0.373488 0.510203 -0.84912 0.136703 0.510203 -0.849119 -0.136712 -0.373492 -0.849121 0.373494 -0.136701 -0.849122 0.510201 0.136716 -0.849122 0.510197 -0.5102 -0.84912 0.136715 -0.965928 0 -0.258809 -0.965928 0 -0.258809 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258835 0 -0.965922 -0.258835 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707093 0 -0.707121 0.707093 0 -0.707121 0.965924 0 -0.258825 0.965924 0 -0.258825 0.965928 0 0.258809 0.965928 0 0.258809 0.707115 0 0.707098 0.707115 0 0.707098 0.258835 0 0.965922 0.258835 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707105 0 0.707108 -0.707105 0 0.707108 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.373498 -0.84912 -0.373489 -0.510204 -0.84912 -0.136701 0.37349 -0.84912 -0.373498 0.136702 -0.84912 -0.510203 -0.136716 -0.84912 -0.5102 0.373498 -0.84912 0.373489 0.510204 -0.84912 0.136701 0.510201 -0.84912 -0.136715 -0.37349 -0.84912 0.373498 -0.136702 -0.84912 0.510203 0.136716 -0.84912 0.5102 -0.510201 -0.84912 0.136715 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258834 0 -0.965922 -0.258834 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707099 0 -0.707114 0.707099 0 -0.707114 0.965923 0 -0.258832 0.965923 0 -0.258832 0.965929 0 0.258806 0.965929 0 0.258806 0.707115 0 0.707098 0.707115 0 0.707098 0.258834 0 0.965922 0.258834 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707099 0 0.707114 -0.707099 0 0.707114 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.373498 -0.84912 -0.37349 -0.510205 -0.84912 -0.1367 0.373489 -0.84912 -0.373498 0.136696 -0.849119 -0.510206 -0.13671 -0.849119 -0.510203 0.373498 -0.84912 0.373489 0.510204 -0.84912 0.136701 0.5102 -0.84912 -0.136715 -0.37349 -0.84912 0.373498 -0.136702 -0.84912 0.510203 0.136716 -0.84912 0.5102 -0.510201 -0.84912 0.136715 -0.96593 0 -0.258803 -0.96593 0 -0.258803 -0.707114 0 -0.7071 -0.707114 0 -0.7071 -0.258822 0 -0.965925 -0.258822 0 -0.965925 0.258795 0 -0.965932 0.258795 0 -0.965932 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965923 0 -0.258832 0.965923 0 -0.258832 0.965929 0 0.258806 0.965929 0 0.258806 0.707115 0 0.707098 0.707115 0 0.707098 0.258834 0 0.965922 0.258834 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.373499 -0.84912 -0.37349 -0.510205 -0.849119 -0.136701 0.37349 -0.84912 -0.373498 0.136702 -0.84912 -0.510203 -0.136716 -0.84912 -0.5102 0.373498 -0.84912 0.373489 0.510204 -0.84912 0.1367 0.510201 -0.84912 -0.136715 -0.37349 -0.84912 0.373498 -0.136702 -0.84912 0.510203 0.136716 -0.84912 0.5102 -0.510201 -0.84912 0.136715 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258835 0 -0.965922 -0.258835 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707099 0 -0.707114 0.707099 0 -0.707114 0.965923 0 -0.258832 0.965923 0 -0.258832 0.96593 0 0.258804 0.96593 0 0.258804 0.707115 0 0.707098 0.707115 0 0.707098 0.258834 0 0.965922 0.258834 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.373498 -0.84912 -0.37349 -0.510204 -0.84912 -0.136701 0.373489 -0.84912 -0.373498 0.136702 -0.84912 -0.510203 -0.136716 -0.84912 -0.5102 0.3735 -0.849119 0.373491 0.510204 -0.84912 0.136703 0.5102 -0.84912 -0.136715 -0.373492 -0.849119 0.373499 -0.136703 -0.849119 0.510206 0.136717 -0.849118 0.510202 -0.510202 -0.849119 0.136715 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707114 0 -0.7071 -0.707114 0 -0.7071 -0.258835 0 -0.965922 -0.258835 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965923 0 -0.258832 0.965923 0 -0.258832 0.965928 0 0.258809 0.965928 0 0.258809 0.707115 0 0.707098 0.707115 0 0.707098 0.258834 0 0.965922 0.258834 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.373498 -0.84912 -0.373489 -0.510204 -0.84912 -0.136702 0.37349 -0.84912 -0.373498 0.136699 -0.84912 -0.510205 -0.136713 -0.84912 -0.510201 0.373498 -0.849119 0.373491 0.510205 -0.84912 0.136701 0.510201 -0.84912 -0.136715 -0.373491 -0.849119 0.373498 -0.136702 -0.849119 0.510204 0.136717 -0.849119 0.510201 -0.510201 -0.84912 0.136717 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258828 0 -0.965924 -0.258828 0 -0.965924 0.258801 0 -0.965931 0.258801 0 -0.965931 0.7071 0 -0.707114 0.7071 0 -0.707114 0.965923 0 -0.258832 0.965923 0 -0.258832 0.96593 0 0.258804 0.96593 0 0.258804 0.707114 0 0.7071 0.707114 0 0.7071 0.258835 0 0.965922 0.258835 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.3735 -0.84912 -0.373488 -0.510204 -0.84912 -0.136702 0.373489 -0.84912 -0.3735 0.136702 -0.849119 -0.510205 -0.136713 -0.84912 -0.510201 0.373501 -0.849119 0.373488 0.510205 -0.849119 0.136702 0.510201 -0.84912 -0.136715 -0.373488 -0.84912 0.3735 -0.136702 -0.849119 0.510204 0.136713 -0.84912 0.510201 -0.5102 -0.84912 0.136715 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707119 0 -0.707095 -0.707119 0 -0.707095 -0.258828 0 -0.965923 -0.258828 0 -0.965923 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707097 0 -0.707117 0.707097 0 -0.707117 0.965923 0 -0.258832 0.965923 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707119 0 0.707095 0.707119 0 0.707095 0.258828 0 0.965923 0.258828 0 0.965923 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707095 0 0.707119 -0.707095 0 0.707119 -0.965923 0 0.258832 -0.965923 0 0.258832 0.965922 0 -0.258834 0.965922 0 -0.258834 0.707103 0 -0.707111 0.707103 0 -0.707111 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258839 0 -0.965921 -0.258839 0 -0.965921 -0.707112 0 -0.707102 -0.707112 0 -0.707102 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.965922 0 0.258834 -0.965922 0 0.258834 -0.707103 0 0.707111 -0.707103 0 0.707111 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258839 0 0.965921 0.258839 0 0.965921 0.707112 0 0.707102 0.707112 0 0.707102 0.96593 0 0.258805 0.96593 0 0.258805 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258806 0.965929 0 0.258806 0.707116 0 0.707098 0.707116 0 0.707098 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258831 0 -0.965923 -0.258831 0 -0.965923 0.258806 0 -0.965929 0.258806 0 -0.965929 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707098 0.707115 0 0.707098 0.258831 0 0.965923 0.258831 0 0.965923 -0.258806 0 0.965929 -0.258806 0 0.965929 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965923 0 -0.25883 0.965923 0 -0.25883 0.96593 0 0.258805 0.96593 0 0.258805 0.707115 0 0.707098 0.707115 0 0.707098 0.258832 0 0.965922 0.258832 0 0.965922 -0.258808 0 0.965929 -0.258808 0 0.965929 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258831 0 -0.965923 -0.258831 0 -0.965923 0.258806 0 -0.965929 0.258806 0 -0.965929 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707098 0.707115 0 0.707098 0.258832 0 0.965922 0.258832 0 0.965922 -0.258806 0 0.965929 -0.258806 0 0.965929 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.508597 -0.694747 -0.508583 -0.508597 -0.694746 -0.508584 -0.186166 -0.694746 -0.694745 -0.186166 -0.694748 -0.694743 0.186147 -0.694748 -0.694748 0.186148 -0.694746 -0.69475 0.508584 -0.694745 -0.508598 0.508584 -0.694746 -0.508597 0.694745 -0.694746 -0.186165 0.694743 -0.694748 -0.186165 0.694747 -0.694748 0.186148 0.694748 -0.694747 0.186148 0.508596 -0.694748 0.508582 0.508597 -0.694746 0.508584 0.186166 -0.694746 0.694745 0.186166 -0.694744 0.694747 -0.186149 -0.694744 0.694752 -0.186148 -0.694746 0.69475 -0.508585 -0.694745 0.508597 -0.508584 -0.694746 0.508597 -0.694749 -0.694743 0.186165 -0.694738 -0.694753 0.186165 -0.694743 -0.694753 -0.186145 -0.694749 -0.694746 -0.186149 -0.508597 -0.694745 -0.508585 -0.508596 -0.694747 -0.508583 -0.186166 -0.694748 -0.694743 -0.186166 -0.694746 -0.694745 0.186148 -0.694746 -0.694749 0.186149 -0.694746 -0.69475 0.508584 -0.694745 -0.508598 0.508582 -0.694747 -0.508596 0.694744 -0.694747 -0.186166 0.694747 -0.694744 -0.186166 0.694752 -0.694744 0.186149 0.69475 -0.694746 0.186147 0.508596 -0.694746 0.508584 0.508596 -0.694746 0.508584 0.186166 -0.694746 0.694745 0.186166 -0.694746 0.694745 -0.186148 -0.694746 0.694749 -0.186147 -0.694748 0.694748 -0.508583 -0.694747 0.508596 -0.508583 -0.694747 0.508596 -0.694744 -0.694747 0.186165 -0.694743 -0.694748 0.186165 -0.694748 -0.694748 -0.186146 -0.69475 -0.694746 -0.186148 -0.508597 -0.694745 -0.508584 -0.508597 -0.694746 -0.508583 -0.186166 -0.694746 -0.694744 -0.186166 -0.694744 -0.694747 0.186149 -0.694744 -0.694752 0.186148 -0.694746 -0.69475 0.508584 -0.694746 -0.508596 0.508582 -0.694749 -0.508595 0.694743 -0.694747 -0.186166 0.694745 -0.694746 -0.186166 0.69475 -0.694746 0.186148 0.69475 -0.694746 0.186148 0.508597 -0.694745 0.508584 0.508597 -0.694746 0.508583 0.186165 -0.694746 0.694745 0.186165 -0.694748 0.694743 -0.186148 -0.694748 0.694747 -0.186146 -0.694751 0.694745 -0.508581 -0.69475 0.508595 -0.508584 -0.694746 0.508596 -0.694744 -0.694746 0.186166 -0.694744 -0.694747 0.186166 -0.694749 -0.694747 -0.186148 -0.694749 -0.694746 -0.186148 -0.508597 -0.694745 -0.508585 -0.508596 -0.694747 -0.508583 -0.186166 -0.694748 -0.694743 -0.186166 -0.694746 -0.694745 0.186148 -0.694746 -0.694749 0.186149 -0.694746 -0.69475 0.508584 -0.694745 -0.508598 0.508582 -0.694747 -0.508596 0.694744 -0.694747 -0.186166 0.694747 -0.694744 -0.186166 0.694752 -0.694744 0.186149 0.69475 -0.694746 0.186147 0.508596 -0.694746 0.508584 0.508595 -0.694749 0.508582 0.186166 -0.694747 0.694744 0.186166 -0.694746 0.694745 -0.186148 -0.694746 0.69475 -0.186147 -0.694748 0.694748 -0.508584 -0.694746 0.508596 -0.508583 -0.694747 0.508596 -0.694744 -0.694747 0.186166 -0.694745 -0.694746 0.186166 -0.694749 -0.694746 -0.186148 -0.69475 -0.694746 -0.186148 -0.694744 -0.694746 0.186167 -0.508584 -0.694746 0.508597 -0.508582 -0.694748 0.508595 -0.186149 -0.694747 0.694748 -0.186149 -0.694744 0.694752 0.186168 -0.694744 0.694747 0.186164 -0.694751 0.694741 0.508594 -0.694749 0.508582 0.508598 -0.694745 0.508584 0.69475 -0.694746 0.186148 0.694746 -0.694749 0.186148 0.694744 -0.694747 -0.186164 0.694745 -0.694746 -0.186165 0.508584 -0.694746 -0.508597 0.508584 -0.694745 -0.508598 0.186146 -0.694745 -0.694751 0.186147 -0.694753 -0.694743 -0.186163 -0.694753 -0.694739 -0.186164 -0.694751 -0.694741 -0.508594 -0.694749 -0.508582 -0.508598 -0.694745 -0.508584 -0.69475 -0.694746 -0.186148 -0.694749 -0.694747 -0.186148 -0.694742 -0.694749 0.186165 -0.694745 -0.694746 0.186166 -0.508584 -0.694746 0.508597 -0.508582 -0.694748 0.508595 -0.186149 -0.694747 0.694748 -0.186149 -0.694744 0.694752 0.186168 -0.694744 0.694747 0.186163 -0.694752 0.69474 0.508591 -0.694753 0.50858 0.508598 -0.694745 0.508584 0.69475 -0.694746 0.186148 0.694751 -0.694745 0.186148 0.694748 -0.694743 -0.186167 0.694745 -0.694746 -0.186165 0.508584 -0.694746 -0.508597 0.508584 -0.694745 -0.508598 0.186149 -0.694746 -0.694749 0.186149 -0.694744 -0.694751 -0.186168 -0.694744 -0.694747 -0.186164 -0.69475 -0.694741 -0.508594 -0.694749 -0.508582 -0.508598 -0.694745 -0.508584 -0.69475 -0.694746 -0.186148 -0.694746 -0.694749 -0.186148 -0.694744 -0.694747 0.186166 -0.694747 -0.694744 0.186167 -0.508588 -0.694739 0.508602 -0.508583 -0.694751 0.508591 -0.186144 -0.694754 0.694742 -0.186144 -0.694753 0.694744 0.186163 -0.694753 0.694739 0.186169 -0.694742 0.694748 0.508599 -0.694743 0.508586 0.508597 -0.694745 0.508586 0.69475 -0.694746 0.186148 0.694751 -0.694745 0.186148 0.694739 -0.694752 -0.186164 0.694742 -0.694749 -0.186166 0.508579 -0.694752 -0.508593 0.508578 -0.694755 -0.508591 0.186144 -0.694756 -0.694741 0.186144 -0.694753 -0.694744 -0.186163 -0.694753 -0.694739 -0.186169 -0.694742 -0.694748 -0.508599 -0.694743 -0.508586 -0.508597 -0.694745 -0.508586 -0.694749 -0.694746 -0.18615 -0.694755 -0.69474 -0.186149 -0.694744 -0.694747 0.186165 -0.694742 -0.694749 0.186166 -0.508579 -0.694752 0.508593 -0.508579 -0.694753 0.508592 -0.186149 -0.694756 0.694739 -0.186148 -0.694735 0.69476 0.186167 -0.694735 0.694755 0.186164 -0.694741 0.69475 0.508602 -0.694742 0.508584 0.508599 -0.694745 0.508582 0.69475 -0.694746 0.186148 0.694746 -0.694749 0.186148 0.694744 -0.694747 -0.186165 0.694747 -0.694744 -0.186167 0.508588 -0.694739 -0.508602 0.508587 -0.694742 -0.508599 0.186149 -0.694738 -0.694758 0.186149 -0.694752 -0.694743 -0.186163 -0.694753 -0.694739 -0.186169 -0.694743 -0.694748 -0.5086 -0.694744 -0.508583 -0.508588 -0.694758 -0.508577 -0.694745 -0.694751 -0.186147 -0.694746 -0.69475 -0.186147 -0.694744 -0.694747 0.186166 -0.694747 -0.694744 0.186166 -0.508588 -0.694739 0.508602 -0.508588 -0.69474 0.508601 -0.186148 -0.694737 0.694758 -0.186149 -0.694752 0.694743 0.186163 -0.694753 0.694739 0.186169 -0.694742 0.694748 0.508602 -0.694742 0.508584 0.508586 -0.694759 0.508576 0.694743 -0.694753 0.186147 0.694748 -0.694747 0.186147 0.694746 -0.694745 -0.186167 0.694743 -0.694749 -0.186165 0.508579 -0.694752 -0.508593 0.508579 -0.694753 -0.508592 0.186149 -0.694756 -0.694739 0.186148 -0.694735 -0.69476 -0.186167 -0.694735 -0.694755 -0.186164 -0.694741 -0.69475 -0.508602 -0.694742 -0.508584 -0.508598 -0.694747 -0.508582 -0.694747 -0.694748 -0.186148 -0.694748 -0.694747 -0.186148 -0.694746 -0.694745 0.186165 -0.694743 -0.694748 0.186164 -0.508579 -0.694752 0.508593 -0.508579 -0.694752 0.508593 -0.186149 -0.694755 0.69474 -0.186148 -0.694735 0.69476 0.186173 -0.694734 0.694755 0.186159 -0.694759 0.694733 0.50859 -0.694756 0.508578 0.508599 -0.694745 0.508582 0.69475 -0.694746 0.186148 0.694746 -0.694749 0.186148 0.694744 -0.694747 -0.186165 0.694747 -0.694744 -0.186167 0.508588 -0.694739 -0.508602 0.508587 -0.694742 -0.508599 0.186149 -0.694738 -0.694758 0.186149 -0.694752 -0.694743 -0.186163 -0.694753 -0.694739 -0.186169 -0.694742 -0.694748 -0.508599 -0.694743 -0.508586 -0.508597 -0.694745 -0.508586 -0.69475 -0.694746 -0.186148 -0.69475 -0.694745 -0.186148 -0.694748 -0.694743 0.186168 -0.694738 -0.694754 0.186164 -0.508573 -0.694766 0.50858 -0.508579 -0.694753 0.508592 -0.186144 -0.694755 0.694742 -0.186143 -0.694736 0.694761 0.186161 -0.694736 0.694756 0.186168 -0.694724 0.694767 0.50861 -0.69473 0.508593 0.508596 -0.694745 0.508586 0.69475 -0.694746 0.186148 0.694747 -0.694748 0.186148 0.694745 -0.694746 -0.186165 0.694746 -0.694745 -0.186166 0.50859 -0.694741 -0.508597 0.508597 -0.694726 -0.50861 0.186153 -0.694719 -0.694775 0.186154 -0.694734 -0.69476 -0.186173 -0.694735 -0.694754 -0.186159 -0.694759 -0.694733 -0.508592 -0.694756 -0.508575 -0.508579 -0.694771 -0.508568 -0.694741 -0.694755 -0.186146 -0.694748 -0.694748 -0.186146 -0.694745 -0.694745 0.186168 -0.694747 -0.694744 0.186167 -0.508586 -0.694739 0.508605 -0.508578 -0.694755 0.508591 -0.186155 -0.694757 0.694736 -0.186154 -0.694735 0.694759 0.186173 -0.694734 0.694755 0.186159 -0.69476 0.694732 0.50859 -0.694758 0.508573 0.508601 -0.694746 0.508579 0.69475 -0.694746 0.186148 0.69475 -0.694745 0.186148 0.694748 -0.694743 -0.186166 0.694747 -0.694744 -0.186165 0.508586 -0.694739 -0.508605 0.508579 -0.694752 -0.508593 0.186144 -0.694754 -0.694742 0.186145 -0.69477 -0.694726 -0.186152 -0.694772 -0.694723 -0.186178 -0.694725 -0.694763 -0.508611 -0.694729 -0.508593 -0.508597 -0.694745 -0.508586 -0.69475 -0.694746 -0.186148 -0.694746 -0.694749 -0.186148 -0.694744 -0.694747 0.186165 0.508585 0.69475 -0.50859 0.508591 0.694736 -0.508603 0.18615 0.694733 -0.694762 0.186151 0.694741 -0.694754 -0.186173 0.69474 -0.694748 -0.186162 0.694759 -0.694733 -0.508587 0.694756 -0.50858 -0.508603 0.694739 -0.508587 -0.694753 0.694743 -0.186147 -0.694748 0.694747 -0.186148 -0.694746 0.694744 0.186168 -0.694743 0.694747 0.186166 -0.508585 0.69475 0.50859 -0.508591 0.694736 0.508603 -0.18615 0.694733 0.694762 -0.186151 0.694741 0.694754 0.186173 0.69474 0.694748 0.186162 0.694759 0.694733 0.508587 0.694756 0.50858 0.508603 0.694739 0.508587 0.694753 0.694743 0.186147 0.694748 0.694747 0.186148 0.694746 0.694744 -0.186168 0.694743 0.694747 -0.186166 -0.989057 0 -0.147534 -0.989057 0 -0.147534 -0.850148 0 -0.526544 -0.850148 0 -0.526544 -0.572628 0 -0.819815 -0.572628 0 -0.819815 -0.293699 0 -0.955898 -0.201788 0.00615412 -0.97941 -0.0944624 0 -0.995528 0.0677158 0.997596 0.0147465 0.237405 0.971072 -0.0256372 0.131809 0.990561 -0.0376097 0.00878957 0.999052 0.0426265 0.0806678 0.993962 0.0743739 0.103989 0.99383 0.0385748 0.0711609 0.993323 0.0908054 0.0151576 0.991512 0.12913 -0.000988389 0.99715 0.0754415 -0.0230761 0.964789 0.26201 -0.0490719 0.992105 0.115407 -0.129141 0.976164 0.174433 -0.106304 0.986195 0.126957 -0.16373 0.98249 0.0889153 -0.260936 0.950195 0.170415 -0.170861 0.98472 0.0336509 -0.265906 0.962787 0.0483261 0.519821 0.853352 -0.0397056 0.511414 0.858473 -0.038465 0.470832 0.864 0.178387 0.47281 0.862823 0.178853 0.352548 0.862391 0.363306 0.351905 0.862843 0.362858 0.172995 0.85704 0.48534 0.171044 0.8591 0.482381 -0.0366636 0.849606 0.526143 -0.0378905 0.853288 0.520062 -0.243407 0.841921 0.481584 -0.241896 0.846812 0.473704 -0.41611 0.834985 0.360073 -0.411572 0.840163 0.353178 -0.532349 0.828028 0.175993 0.0412744 -0.547143 0.836021 0.0665704 -0.320497 0.944907 -0.80442 0.236097 0.54513 -0.608336 -0.436593 0.662808 -0.0977316 0.0983817 0.990338 -0.289115 0.08772 0.953267 -0.274915 -0.558436 0.782669 -0.434247 -0.101722 0.895032 -0.614072 0.376457 0.693683 0.98235 0.0975328 -0.159611 0.952527 -0.302377 -0.0354924 0.847763 -0.530205 0.013412 0.991687 0.0932027 0.0887088 0.936661 0.0986962 0.336043 0.877643 -0.320088 0.356773 0.598893 0.567089 0.565453 0.69568 0.215819 0.685165 0.522958 0.0719821 0.849314 0.382088 -0.349355 0.855547 0.221124 0.600663 0.768315 0.109781 -0.117923 0.986936 -0.788274 0.279264 0.548302 -0.68114 0.283206 0.675161 -0.684771 0.265444 0.678696 -0.370846 0.286557 0.883379 -0.372881 0.268774 0.888099 -0.00330153 0.289128 0.957285 -0.00348032 0.273465 0.961876 0.366383 0.290432 0.883976 0.367367 0.27929 0.887152 0.681226 0.289619 0.672348 0.681992 0.285254 0.673437 0.89046 0.286139 0.353845 0.889535 0.289873 0.35313 0.959652 0.280438 -0.0205691 0.953883 0.299313 -0.0227732 -0.842523 0.433957 0.319118 -0.743224 0.605112 0.285409 -0.579567 0.788849 0.204498 0.816933 0.575899 -0.0309969 0.825252 0.563823 -0.0326004 0.763347 0.572417 0.2994 0.765235 0.569738 0.299691 0.581823 0.569046 0.581093 0.58024 0.571552 0.580216 0.305983 0.562602 0.768019 0.302716 0.56957 0.764168 -0.0179231 0.554888 0.831732 -0.0203282 0.565156 0.824733 -0.338838 0.547579 0.765079 -0.338384 0.559698 0.756462 -0.608173 0.541471 0.58046 -0.604472 0.553734 0.572706 -0.786575 0.536287 0.306099 -0.915512 -0.0632938 0.39728 -0.920384 0.191473 0.340928 0.508585 0.694744 -0.508598 0.508585 0.694745 -0.508598 0.186149 0.694745 -0.694751 0.186149 0.694742 -0.694753 -0.186166 0.694742 -0.694748 -0.186165 0.694745 -0.694746 -0.508598 0.694745 -0.508584 -0.508599 0.694744 -0.508585 -0.694751 0.694744 -0.186148 -0.694751 0.694745 -0.186148 -0.694746 0.694745 0.186166 -0.694746 0.694745 0.186166 -0.508585 0.694744 0.508598 -0.508585 0.694745 0.508598 -0.186149 0.694745 0.694751 -0.186149 0.694746 0.694749 0.186165 0.694747 0.694744 0.186166 0.694745 0.694746 0.508598 0.694745 0.508584 0.508599 0.694744 0.508585 0.694751 0.694745 0.186148 0.694751 0.694745 0.186148 0.694746 0.694745 -0.186166 0.694746 0.694744 -0.186167 0.00525722 -0.999986 0.000757261 0.0406709 -0.999158 0.00546374 0.149764 0.98861 0.014881 0.149763 0.98861 0.0148827 0.149763 0.98861 0.0148809 0.638833 0.766498 -0.0661352 -0.576518 -0.814613 0.0635069 -9.45096e-06 0.0017338 -0.999999 -9.92547e-06 2.81894e-05 -1 -1.01207e-05 1.87459e-05 -1 -1.03638e-05 1.35649e-05 -1 -1.05241e-05 1.0307e-05 -1 -9.52488e-06 0.000408531 -1 -9.53494e-06 0.000289325 -1 -9.57796e-06 5.55042e-05 -1 -1.27431e-05 -2.20897e-07 -1 -1.18552e-05 2.0306e-06 -1 -1.37451e-05 -8.1295e-07 -1 0 0 -1 -1.04827e-05 1.91927e-06 -1 -1.84998e-05 -2.45719e-06 -1 -1.31958e-05 0 -1 -1.57831e-05 -4.67451e-05 -1 -1.11817e-05 1.63741e-06 -1 -1.08666e-05 5.37195e-06 -1 0 0 -1 0 0 -1 0 0 -1 -1.20361e-05 3.43983e-07 -1 -1.76868e-05 2.658e-06 -1 -0.991294 0.0134332 0.13098 0.99131 -0.0108456 -0.131097 -0.998237 -0.000357115 0.0593528 -0.998229 -0.000355976 0.0594822 -0.997479 -0.0386723 0.0595021 0.982781 0.175869 -0.0566785 0.861371 0.0308542 -0.507039 0.970688 0.0496225 -0.235165 0.737044 -0.00741647 -0.675805 0.712663 0.02745 -0.700969 0.724793 0.000288512 -0.688966 0.592405 0.00586072 -0.805619 0.517131 0.00478012 -0.855893 0.519734 0.0475308 -0.853005 0.377686 0.0735216 -0.92301 0.743114 -0.0104666 -0.669083 0.651756 0.000542757 -0.758429 0.931978 0.131088 -0.337984 0.818733 0.238176 -0.522444 0.75857 0.294274 -0.581355 0.535156 0.401048 -0.743484 0.741834 0.259666 -0.618269 0.0807403 0.132928 -0.987831 0.127764 0.328667 -0.935764 0.967766 -0.0634741 -0.243721 0.180104 0.463039 -0.867846 0.667474 0.135884 -0.73213 0.551698 0.178473 -0.814725 0.901521 -0.0219403 -0.432179 0.693604 0.0725625 -0.716693 0.153444 0.122166 -0.980577 0.306145 0.0914541 -0.947582 0.348994 0.266601 -0.898403 0.414978 0.240122 -0.877573 0.436927 0.347885 -0.8295 0.688772 0.24111 -0.68371 0.74574 0.196477 -0.636607 0.857354 0.118423 -0.500919 0.919836 0.0380567 -0.390453 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258831 0 0.965923 0.258831 0 0.965923 0.707116 0 0.707098 0.707116 0 0.707098 0.965929 0 0.258806 0.965929 0 0.258806 0.951001 0.307032 -0.0364461 0.973825 0.22381 -0.0396677 0.966293 0.252975 -0.047759 0.995307 0.0815249 -0.0521271 0.992738 0.107055 -0.0548706 0.540007 0 0.84166 0.466134 0.0281016 0.884268 0.764472 -0.016837 0.644437 0.100773 0.00788808 -0.994878 0.155378 0.0190259 -0.987672 0.507563 -0.029391 -0.861113 0.424665 0 -0.905351 0.699087 0 -0.715037 0.781173 -0.0179229 -0.624057 0.843192 0 -0.537612 0.947302 0 -0.320341 0.976626 -0.0179873 -0.21419 0.995298 0 -0.0968598 0.989579 0 0.143994 0.970649 -0.0176252 0.239854 0.931029 0 0.364946 0.816725 0 0.577027 0.99848 0 -0.0551185 0.99848 2.23456e-07 -0.0551185 0.99848 0 -0.0551192 0.99848 -2.26556e-07 -0.0551201 0.99848 0 -0.0551178 0.999618 0 -0.0276489 0.509234 0 0.860628 0.509234 0 0.860628 0.829068 0 0.559147 0.829068 0 0.559147 0.984253 0 0.176767 0.988724 -0.00558963 0.149645 0.999618 0 -0.0276489 0.974949 -0.215467 0.0552055 0.976168 -0.209988 0.0547813 0.787924 -0.614935 0.0320973 0.789703 -0.61266 0.0319001 0.424004 -0.90566 0.000937527 0.423883 -0.905716 0.000945779 -0.0114743 -0.99951 -0.0291167 -0.0149762 -0.99947 -0.0289156 0.975154 -0.21169 -0.0652789 0.975443 -0.210369 -0.0652422 0.783852 -0.616208 -0.0765738 0.786657 -0.612619 -0.0766056 0.41361 -0.907613 -0.0718648 0.421137 -0.904117 -0.0722218 -0.0243068 -0.998321 -0.0525739 -0.0128173 -0.998492 -0.053382 0.662631 -0.619421 0.420997 0.0836204 -0.863665 0.497082 0.394799 -0.904957 0.158704 0.928428 -0.215833 0.302387 0.855686 -0.199306 0.477576 0.871487 -0.140596 0.469832 0.715914 -0.266681 0.64525 -0.0240965 -0.999484 0.0212222 0.0517588 -0.996525 0.0652564 -0.114944 -0.991984 0.0524916 -0.174218 -0.976454 0.12722 -0.0370415 -0.993195 0.110413 0.338586 -0.89354 0.294866 0.392902 -0.905932 0.157845 0.750936 -0.61288 0.245913 0.0965903 -0.853024 0.512855 0.213596 -0.894878 0.391879 0.462431 -0.699417 0.544953 0.559531 -0.59056 0.581519 0.600696 -0.521303 0.606142 0.732861 -0.22664 0.64152 0.300056 -0.679005 0.670014 0.327241 -0.651305 0.684628 0.426677 -0.517176 0.741941 0.458914 -0.471145 0.753273 0.533396 -0.328562 0.779446 0.602823 -0.180593 0.777168 0.617173 -0.127643 0.776405 0.956401 -0.211527 0.201376 0.896236 -0.348814 0.274026 0.748319 -0.616593 0.244604 0.675126 -0.599964 0.429241 0.319602 -0.904638 0.281931 0.235087 -0.880244 0.412195 -0.256119 -0.965988 0.0356461 -0.134196 -0.948523 0.286872 -0.174303 -0.950455 0.257399 -0.248604 -0.943639 0.218498 -0.0260773 -0.996051 -0.0848643 0.664026 -0.52208 -0.535259 0.825608 -0.113228 -0.552767 0.308514 -0.891497 -0.33174 0.0589002 -0.968872 -0.240455 0.346144 -0.891281 -0.292921 0.392239 -0.905294 -0.163068 0.137112 -0.980012 -0.14414 0.41068 -0.904261 -0.11685 0.76187 -0.323864 -0.560951 0.811024 -0.195975 -0.551212 0.875741 -0.217752 -0.430885 0.881964 -0.199364 -0.427076 0.931924 -0.217295 -0.290345 0.966794 0.177078 -0.184265 0.968072 -0.207041 -0.14132 -0.0374116 -0.995984 -0.0813385 -0.0622534 -0.986855 -0.149136 -0.0769612 -0.987273 -0.13917 0.778316 -0.611226 -0.143621 0.773348 -0.617185 -0.144967 0.746076 -0.605332 -0.277387 0.737697 -0.614942 -0.278655 0.692076 -0.598613 -0.403353 0.680341 -0.611615 -0.40381 0.622018 -0.592246 -0.51219 0.530445 -0.691657 -0.490141 -0.292643 -0.923111 0.249451 -0.605464 -0.786942 0.118891 0.0637421 -0.85647 0.512247 0.241726 -0.946002 0.215982 0.230364 -0.973074 -0.00768867 0.26696 -0.963457 -0.0219647 -0.0198011 -0.93293 0.359513 -0.0654319 -0.933639 0.352189 -0.272835 -0.917681 0.288829 -0.340723 -0.900622 0.269793 0.10831 -0.994076 0.0090798 -0.0945213 -0.994975 0.0330107 -0.287452 -0.957727 0.0114387 0.987633 -0.130702 0.0865931 0.974572 -0.0958953 0.202516 0.965522 -0.133747 0.223338 0.935874 -0.0865084 0.341549 0.921793 -0.128427 0.365792 0.979943 -0.129451 -0.151506 0.926524 -0.361619 0.103851 0.776578 -0.609698 0.158729 0.768974 -0.61943 0.158069 0.678438 -0.731987 -0.0625831 0.762333 -0.640873 -0.0901658 0.82785 -0.554044 -0.0877506 0.914379 -0.389395 -0.110829 0.926549 -0.360354 -0.107942 0.561155 -0.101729 0.821435 0.731555 0.168131 0.660726 0.687421 -0.0569292 0.724024 0.820378 -0.146837 0.552648 0.877505 0.143947 0.457455 0.894547 -0.0964999 0.436432 0.423805 -0.516017 0.744389 0.46684 -0.452739 0.759663 0.587696 -0.533479 0.608287 0.625694 -0.484437 0.611415 0.687974 -0.552955 0.470035 0.886981 -0.360023 0.289219 0.856083 -0.310715 0.413011 0.835885 -0.342227 0.429159 0.768285 -0.269913 0.580419 0.723862 -0.339499 0.600637 0.592568 -0.251858 0.765134 0.540867 -0.331826 0.772887 -0.404078 -0.909554 0.0971183 0.481139 -0.875038 -0.0530402 0.52767 -0.848197 -0.0461112 0.540597 -0.817802 0.197371 0.540242 -0.81805 0.197316 0.513905 -0.745604 0.424237 0.268321 -0.87267 0.407984 0.199111 -0.796917 0.570331 -0.0517408 -0.897796 0.437362 -0.273769 -0.9231 0.270068 -0.265607 -0.925075 0.271457 -0.923027 -0.358893 -0.138624 -0.599712 -0.785915 0.150611 -0.610004 -0.77979 0.140789 -0.32432 -0.937226 0.128158 0.443409 -0.889269 0.112205 -0.0511301 -0.97568 0.213155 0.25343 -0.94237 0.218431 0.233228 -0.88315 0.407002 0.985622 0.153211 -0.0712447 0.904972 -0.412561 -0.104016 0.999244 -0.0258989 0.0289827 0.918028 -0.38023 0.112472 0.902372 -0.332297 0.274415 0.751672 -0.566929 0.337018 0.91231 -0.251893 0.322862 0.515448 -0.744638 0.42406 0.448127 -0.666171 0.596153 0.592716 0.805022 0.0250489 0.279288 -0.671017 0.686829 -0.212088 -0.0774709 0.974175 -0.600009 -0.0708938 0.796846 -0.291067 -0.826002 0.482702 -0.29834 -0.810327 0.504345 -0.112043 -0.842409 0.527061 -0.110716 -0.829672 0.547162 0.0707578 -0.864468 0.497684 0.0760246 -0.857411 0.508986 0.236004 -0.891619 0.386415 0.23206 -0.961285 0.148591 0.261866 -0.962765 -0.0671573 0.413388 -0.839667 -0.352237 0.484946 -0.871331 -0.0748964 0.492016 -0.867296 -0.0756145 0.454567 -0.867058 0.20391 0.353335 -0.916602 0.18707 0.236773 -0.891083 0.387182 0.693618 0.520903 0.497549 0.770834 -0.341083 0.538031 0.875576 0.419744 0.239128 0.937822 -0.101864 0.331833 0.99207 -0.10629 0.0670714 0.88509 0.464828 -0.0234688 0.844782 -0.501761 -0.185954 0.842775 0.403972 -0.355722 0.883238 -0.135163 -0.449023 0.718569 -0.536198 -0.442888 0.188975 -0.0832251 0.978449 0.310851 -0.106473 0.944476 0.46389 0.576303 0.672816 0.502195 -0.000166106 0.864754 0.657782 -0.195535 0.727385 -0.00744595 -0.111684 0.993716 0.175024 0.580238 0.795419 0.0139399 -0.300296 0.953744 -0.742756 -0.094265 0.662894 -0.409676 0.664733 0.624736 -0.64788 -0.279065 0.708784 -0.649212 -0.239428 0.721941 -0.624468 -0.427897 0.65341 -0.607959 -0.505046 0.612629 -0.574037 -0.592303 0.565385 -0.460185 -0.79849 0.388129 -0.483069 -0.771566 0.413921 0.742775 -0.495968 -0.449779 0.838571 -0.539242 -0.0775691 0.846286 -0.526948 -0.078264 0.792865 -0.523651 0.311696 0.787107 -0.532616 0.311101 0.602647 -0.49111 0.628989 0.586443 -0.51769 0.622962 0.318319 -0.460076 0.828857 0.299849 -0.497448 0.814025 -0.011214 -0.437995 0.898908 -0.0234893 -0.47901 0.877495 0.0284285 -0.24776 0.968404 0.367637 -0.312585 0.875862 0.386523 -0.261956 0.884296 0.674764 -0.324078 0.663074 0.69038 -0.284798 0.66503 0.884544 -0.328936 0.33073 0.890363 -0.313145 0.330446 0.945687 -0.316814 -0.0728347 0.940128 -0.333046 -0.0723866 0.840637 -0.287805 -0.4588 0.821221 -0.342622 -0.456296 -0.0774883 -0.987133 -0.139874 -0.156378 -0.98152 -0.110295 0.0742278 -0.994422 -0.074939 0.322716 -0.894043 -0.310712 0.2044 -0.940865 -0.270174 0.257142 -0.964072 -0.0666504 -0.0833982 -0.995326 -0.0487009 -0.0951817 -0.994811 0.0359522 0.0441182 -0.993768 0.102368 -0.130183 -0.988267 0.0798784 -0.0513328 -0.982566 0.178686 -0.141383 -0.982876 0.118173 -0.0117251 -0.864251 0.502924 -0.167775 -0.978335 0.121293 -0.231733 -0.863971 0.44705 -0.195834 -0.974719 0.107573 -0.296 -0.937156 0.184721 -0.276216 -0.948742 0.153604 -0.397814 -0.103496 0.91161 -0.114678 0.672639 0.73103 -0.339907 -0.289043 0.89494 -0.333789 -0.241015 0.911316 -0.340856 -0.548871 0.763254 -0.328657 -0.427827 0.841991 -0.333498 -0.598036 0.728788 -0.0613801 -0.644653 0.762007 -0.0519452 -0.616217 0.785862 0.21571 -0.667371 0.712801 0.231072 -0.644055 0.729245 0.464779 -0.694043 0.549804 0.477298 -0.680221 0.556315 0.641567 -0.716721 0.273318 0.644072 -0.7143 0.273766 0.69248 -0.717056 -0.0793892 0.684258 -0.724992 -0.0785985 0.597971 -0.686426 -0.413824 0.582278 -0.70333 -0.407774 -0.279348 -0.0678606 -0.957789 0.414107 -0.262125 -0.871669 0.364392 -0.304705 -0.879985 0.428014 -0.848417 -0.311436 -0.12215 -0.127667 -0.984267 -0.328786 -0.91995 -0.21352 0.215391 -0.937454 -0.273473 -0.695641 -0.71838 -0.0037843 -0.638448 -0.768014 -0.0503825 -0.453194 -0.877123 -0.158965 -0.363594 -0.910578 -0.196588 -0.457516 -0.801562 -0.384938 -0.15674 -0.795136 -0.585825 -0.230034 -0.696954 -0.679219 -0.0715271 -0.649995 -0.756565 -0.231137 -0.338501 -0.912136 -0.119994 -0.423011 -0.898144 -0.227102 -0.333967 -0.914817 -0.350741 -0.490764 -0.797579 -0.312233 -0.488263 -0.814929 -0.287759 -0.527716 -0.799194 -0.459356 -0.673631 -0.578976 -0.288209 -0.544433 -0.787736 0.807916 -0.143584 -0.571537 0.932052 -0.108786 -0.345608 0.942154 -0.0455916 -0.332065 0.85308 -0.325439 -0.407853 0.74197 -0.509268 -0.436036 0.817134 -0.398039 -0.416963 0.706466 -0.250864 -0.661795 0.883347 0.0964665 -0.458686 0.548209 -0.282264 -0.78727 0.603285 -0.662159 -0.444513 0.491346 -0.75443 -0.435219 -0.329232 -0.914862 -0.23374 0.326635 -0.786798 -0.523697 0.47758 -0.499876 -0.722524 0.495526 -0.483046 -0.721887 0.358987 -0.586586 -0.725979 0.294901 -0.630062 -0.71837 0.231969 -0.663493 -0.711313 0.0325317 -0.751688 -0.658716 0.122028 -0.869637 -0.478372 0.104313 -0.872932 -0.476559 0.178393 -0.949173 -0.25932 0.0578415 -0.969493 -0.238197 0.586376 -0.678396 -0.442653 0.702099 -0.561137 -0.438386 0.580397 -0.401683 -0.708372 0.659795 -0.315899 -0.68182 0.531725 -0.144161 -0.834557 0.847487 0.391832 -0.358096 0.498687 -0.119277 -0.858536 -0.294688 -0.297823 -0.907998 0.363533 0.555378 0.74793 -0.327321 -0.369441 -0.869698 -0.307491 -0.232299 -0.92276 0.362625 0.0362597 -0.931229 0.326637 -0.0031159 -0.945145 0.253534 -0.0760422 -0.964333 0.135218 -0.192145 -0.972006 0.288133 -0.36911 -0.883593 -0.35513 -0.691956 -0.628553 0.200902 -0.502266 -0.841051 -0.0157219 -0.621245 -0.783459 0.0691525 -0.735489 -0.673998 -0.228677 -0.810016 -0.539983 -0.152256 -0.910998 -0.383275 0.494698 -0.743587 -0.449836 -0.138754 -0.973149 -0.183654 -0.477518 -0.796086 -0.371784 -0.44438 -0.802953 -0.397232 -0.49747 -0.732964 -0.463991 -0.460964 -0.737751 -0.493189 -0.400754 -0.678564 -0.615587 -0.120433 -0.588318 -0.799611 -0.2262 -0.617545 -0.753307 0.111602 -0.42424 -0.898647 0.0124797 -0.308279 -0.951214 0.0259156 -0.296637 -0.954638 -0.112329 -0.180968 -0.977053 -0.312857 -0.414581 -0.854543 -0.203841 -0.116818 -0.97201 -0.26923 -0.0372136 -0.962357 -0.297038 -0.166897 -0.940167 -0.701154 -0.274201 0.658177 -0.61449 -0.590224 0.523487 -0.505939 -0.770248 0.388257 -0.253195 -0.835809 0.48715 -0.710934 -0.0987538 0.696291 -0.706578 -0.170354 0.686824 -0.538238 -0.193513 0.820276 -0.540318 -0.173927 0.82329 -0.340315 -0.196286 0.919596 -0.341776 -0.178551 0.922664 -0.123691 -0.197651 0.972437 -0.124576 -0.183088 0.975172 -0.264121 -0.949702 0.168247 -0.222083 -0.969634 0.102416 -0.259083 -0.953557 0.153642 -0.372252 -0.822603 0.42983 -0.12029 -0.981108 0.151515 -0.11987 -0.981576 0.148793 -0.136752 -0.963673 0.229419 -0.122909 -0.842684 0.524191 -0.671782 -0.424678 0.606924 -0.637561 -0.524086 0.564668 -0.493431 -0.543678 0.678926 -0.497207 -0.533459 0.684256 -0.322995 -0.552872 0.768119 -0.325522 -0.543263 0.773887 -0.134064 -0.560014 0.817564 -0.135276 -0.551639 0.82304 -0.276478 -0.0679226 -0.958617 0.353742 -0.300879 -0.885629 0.370262 -0.0436234 -0.927902 0.367112 -0.130523 -0.920974 0.360714 -0.216555 -0.907188 0.364178 -0.177492 -0.91426 0.309294 -0.177701 -0.934216 0.273393 0.238659 -0.931825 0.26488 -0.178398 -0.947635 0.186938 -0.178294 -0.966057 0.186948 -0.177471 -0.966206 0.0951742 -0.177424 -0.979522 0.0951685 -0.176077 -0.979765 0.00258053 -0.176011 -0.984385 0.00252755 -0.173435 -0.984842 -0.0769158 -0.173414 -0.981841 -0.087323 0.273723 -0.957836 -0.29388 -0.232579 -0.927115 -0.296 -0.166919 -0.94049 -0.239086 0.48883 -0.838977 -0.250889 -0.158908 -0.954884 -0.182888 -0.159241 -0.970152 -0.182456 -0.168532 -0.968662 -0.123201 -0.168852 -0.977911 0.00952257 -0.990656 0.136054 -0.017201 -0.9899 0.140718 -0.00493561 -0.192993 0.981188 -0.00490426 -0.192124 0.981359 -0.0144841 -0.564744 0.825139 -0.0143832 -0.562169 0.826898 -0.0219197 -0.853778 0.520176 -0.0217776 -0.850765 0.525096 -0.0202441 -0.791786 0.610462 -0.0510244 -0.987518 0.149009 0.0016933 -0.193657 0.981068 0.00169441 -0.193023 0.981193 0.00492256 -0.566481 0.82406 0.00493047 -0.564854 0.825176 0.00742349 -0.855782 0.517284 0.0074466 -0.853994 0.52023 0.00846362 -0.975582 0.219472 -0.00393482 -0.99004 0.14073 0.366065 -0.752501 -0.547485 0.375747 -0.301067 -0.876455 0.371724 -0.216639 -0.902712 0.349615 -0.618229 -0.703962 0.278133 -0.460396 -0.843017 0.0539463 -0.548191 -0.834611 0.103378 -0.624117 -0.774462 -0.0747103 -0.709258 -0.700979 -0.575537 -0.0292041 -0.817254 -0.170498 -0.757481 -0.630201 -0.905922 -0.0663729 -0.418211 -0.866659 -0.22264 -0.446468 -0.745463 -0.139919 -0.651696 0.32168 -0.0435655 -0.945846 0.353231 -0.255518 -0.899966 0.0401536 0.145349 -0.988565 0.114031 -0.0695452 -0.99104 -0.056222 -0.140242 -0.98852 -0.409203 0.582566 -0.70226 -0.273184 -0.115355 -0.95502 -0.429048 -0.184891 -0.884157 -0.273156 -0.520808 -0.808792 -0.675786 -7.8742e-05 -0.737098 -0.55947 -0.524007 -0.642192 -0.25005 -0.802693 -0.541442 -0.803504 -0.235685 -0.546657 0.0730751 -0.941254 -0.329697 0.206888 -0.947776 -0.242732 0.0790104 -0.926515 -0.367869 0.130182 -0.895973 -0.4246 0.201671 -0.922392 -0.329426 0.13142 -0.84303 -0.521565 0.176518 -0.848616 -0.498691 0.244582 -0.856309 -0.45488 0.287382 -0.883952 -0.368836 0.233942 -0.631882 -0.738915 0.322508 -0.674299 -0.664312 -0.748321 -0.472341 -0.465735 -0.603068 -0.635925 -0.481568 -0.336031 -0.8342 -0.437257 -0.845067 -0.2722 -0.460184 -0.656121 -0.576308 -0.487211 -0.567121 -0.5145 -0.643167 -0.547644 -0.54377 -0.635924 -0.433835 -0.479214 -0.762982 -0.416218 -0.508758 -0.75361 -0.282853 -0.443234 -0.85061 -0.26945 -0.469353 -0.840895 -0.0425539 -0.363817 -0.930498 -0.0438936 -0.360798 -0.931611 0.204127 -0.25775 -0.944403 -0.336264 0.912298 0.23375 0.339009 -0.130344 -0.93171 0.738023 -0.434884 0.515944 0.789786 -0.19464 0.581682 0.130441 -0.987089 0.0929594 0.251986 -0.499725 0.828721 0.080681 -0.987428 0.135929 0.279528 -0.947548 0.154975 0.251316 -0.959409 0.127961 0.481383 -0.785243 0.38944 0.174722 -0.984349 0.0229855 0.384036 -0.83813 0.387369 0.18261 -0.847561 0.498291 0.100269 -0.992134 0.0749414 0.105264 -0.850194 0.515839 0.790601 -0.175284 0.586707 0.652996 -0.193856 0.732131 0.56431 -0.482529 0.669866 0.536678 -0.100259 0.83781 0.379287 -0.357077 0.853603 0.369272 -0.185987 0.91052 0.137133 -0.19879 0.9704 0.135885 -0.187637 0.972794 0.132116 -0.558696 0.818782 0.132821 -0.567865 0.812335 0.351221 -0.555359 0.753804 0.3505 -0.563574 0.74802 0.544522 -0.546897 0.635925 0.542112 -0.55654 0.629586 0.695027 -0.537935 0.477036 0.664311 -0.604679 0.43938 0.0628553 -0.997371 0.0360567 -0.600518 -0.229759 0.765891 -0.914011 -0.110877 0.390244 -0.205957 -0.901879 0.379731 -0.36371 -0.804918 0.468851 -0.262341 -0.917982 0.297466 -0.324226 -0.921289 0.21472 -0.884739 -0.323489 0.335546 -0.784499 -0.536761 0.310562 -0.897594 -0.232594 0.374467 -0.826416 -0.204142 0.52475 -0.693865 -0.468547 0.546822 -0.724188 -0.219226 0.653828 -0.610918 -0.207628 0.763983 -0.976102 -0.14117 -0.165215 -0.925729 -0.311232 -0.21485 -0.913341 -0.341864 -0.221215 -0.938721 -0.279046 -0.202325 -0.808081 -0.532276 -0.252363 -0.841524 -0.484107 -0.239745 -0.665346 -0.696216 -0.26944 -0.692426 -0.671488 -0.263914 -0.38569 -0.881162 -0.273491 -0.4999 -0.82692 -0.257496 -0.277879 -0.923087 -0.265883 0.0732029 -0.996933 0.0276618 0.0678932 -0.996172 -0.0550634 -0.508413 -0.822164 0.256052 -0.263107 -0.964504 0.0225023 -0.45919 -0.874511 0.156125 0.162677 -0.976803 -0.139258 -0.343488 -0.91296 -0.220272 0.0417888 -0.972517 -0.229051 -0.444902 -0.627753 0.63874 -0.456585 -0.615147 0.642747 -0.561388 -0.625897 0.541384 -0.561687 -0.625575 0.541446 -0.652849 -0.630632 0.419633 -0.649963 -0.633765 0.419391 -0.730928 -0.630049 0.262264 -0.642522 -0.72677 0.24284 0.0691132 -0.996065 -0.0554811 0.0418162 -0.989744 -0.136598 -0.294104 -0.952941 -0.0735295 -0.276262 -0.957847 -0.0787905 -0.516357 -0.856053 -0.0234165 -0.496879 -0.867292 -0.0302707 -0.708449 -0.705181 0.0286278 -0.689564 -0.723937 0.0204188 -0.853836 -0.514675 0.077936 -0.838148 -0.541076 0.0688855 -0.944938 -0.304195 0.120652 -0.934862 -0.337053 0.111485 -0.983599 -0.0929105 0.154599 -0.978208 0.0808465 0.191242 0.58803 -0.0967155 0.803036 0.13311 -0.984099 0.117606 0.131968 -0.959592 0.248531 0.0949696 -0.992175 0.0810554 0.0539182 -0.984829 0.164939 0.0630014 -0.996578 0.0535175 -0.237152 -0.913476 0.330637 0.0569589 -0.998351 -0.00712539 -0.363209 -0.926167 0.10146 0.0345122 -0.997733 -0.0577798 -0.165097 -0.977235 -0.133248 -0.0293995 -0.9919 -0.123574 -0.436212 -0.880036 -0.187768 -0.436148 -0.880071 -0.187751 -0.435749 -0.899292 0.0373709 -0.441352 -0.896538 0.0377993 -0.356616 -0.899419 0.252728 -0.360991 -0.897126 0.254658 -0.211935 -0.884962 0.41464 -0.212183 -0.884791 0.414877 -0.0312455 -0.864621 0.501452 -0.0282924 -0.868194 0.495418 0.160298 -0.845656 0.509088 -0.280459 0.549669 0.786897 -0.317148 0.0847515 0.944582 0.203349 -0.104907 0.97347 0.0115651 0.594794 0.803795 0.0170265 -0.0856361 0.996181 -0.12777 -0.103018 0.986439 0.761512 -0.0701982 0.644339 0.753083 -0.198225 0.627354 0.749207 -0.253477 0.611914 0.71042 -0.436257 0.552253 0.647422 -0.605249 0.463162 -0.91316 0.357877 0.195098 -0.925293 -0.313991 -0.212705 -0.97293 -0.121681 -0.196474 -0.733443 -0.652847 -0.189346 -0.970414 -0.0989654 0.220234 -0.889 -0.102479 0.446293 -0.730281 0.518693 0.444575 -0.787319 -0.105917 0.60738 -0.673796 -0.0963458 0.73261 -0.544258 0.515877 0.661554 -0.562504 0.35888 0.744845 -0.435383 -0.168221 0.884389 0.273618 -0.95757 0.0905174 0.192494 -0.980041 0.0496524 0.48668 -0.819036 0.303847 0.334857 -0.840638 0.425674 0.446679 -0.535232 0.716941 0.155432 -0.5706 0.806385 0.15637 -0.454295 0.87702 -0.16867 -0.493147 0.853438 -0.173074 -0.470181 0.865433 -0.476205 -0.504365 0.720309 -0.481265 -0.489993 0.726837 -0.720154 -0.510075 0.47032 -0.721223 -0.507815 0.471128 -0.852912 -0.503666 0.137338 -0.846669 -0.514797 0.134667 -0.847554 -0.484596 -0.216377 -0.834361 -0.506145 -0.218309 -0.935899 -0.283731 -0.20878 -0.934979 -0.315743 0.161619 -0.939331 -0.301131 0.164245 -0.800658 -0.305468 0.515399 -0.799363 -0.31059 0.514347 -0.545657 -0.289072 0.786572 -0.541187 -0.31062 0.781429 -0.215111 -0.273731 0.937443 -0.210804 -0.305097 0.928697 0.142099 -0.262905 0.9543 0.143402 -0.297915 0.94376 0.427812 -0.0768131 0.900598 0.334216 0.534041 0.776595 0.47854 -0.25653 0.839757 0.475928 -0.290822 0.830009 0.444754 -0.558627 0.700093 0.676932 -0.526582 0.514271 0.516385 -0.786318 0.33919 0.318387 -0.888913 0.329338 0.180679 -0.978162 0.102736 0.339294 -0.830895 0.441013 0.161473 -0.853037 0.49624 0.162685 -0.633172 0.756721 -0.117112 -0.666475 0.736272 -0.120829 -0.652344 0.74823 -0.385295 -0.682027 0.621601 -0.389275 -0.674752 0.627037 -0.600457 -0.692309 0.4002 -0.600185 -0.69266 0.4 -0.717694 -0.688849 0.101993 -0.710845 -0.696263 0.0995817 -0.71155 -0.669434 -0.213438 -0.700458 -0.680908 -0.21383 -0.0322101 -0.999446 -0.00836715 -0.436897 -0.893207 0.106315 -0.219751 -0.902831 0.369602 -0.224169 -0.900333 0.373027 -0.307986 -0.906846 0.287708 -0.319435 -0.900886 0.293879 -0.382804 -0.902111 0.199139 -0.933474 -0.209293 0.291242 -0.934493 -0.204952 0.291063 -0.860627 -0.209256 0.464256 -0.860497 -0.209766 0.464267 -0.755309 -0.207874 0.621527 -0.753351 -0.21486 0.621528 -0.620519 -0.20483 0.756968 -0.612144 -0.231074 0.756231 -0.224479 -0.971741 0.0730047 -0.0107099 -0.99975 -0.019604 0.0179543 -0.999568 0.0232876 0.11433 -0.992846 -0.0344407 0.0693404 -0.996767 0.0405805 -0.766621 -0.602124 0.223021 -0.76648 -0.602309 0.223008 -0.701698 -0.606009 0.374663 -0.69886 -0.609723 0.373943 -0.604694 -0.607923 0.514564 -0.598558 -0.616091 0.512016 -0.47807 -0.60699 0.634832 -0.462041 -0.629022 0.62518 -0.0284997 -0.991634 -0.125896 -0.0451554 -0.990735 -0.128084 -0.430481 -0.879068 -0.20476 -0.449766 -0.869092 -0.205887 -0.693009 -0.679585 -0.24063 -0.782183 -0.574009 -0.242286 -0.826958 -0.504167 -0.248908 -0.917591 -0.310723 -0.247947 -0.0501052 -0.996635 -0.0648663 -0.0562082 -0.996375 -0.0638606 -0.463679 -0.885531 -0.0289194 -0.472452 -0.880942 -0.0270136 -0.801857 -0.597354 0.013914 -0.810234 -0.585869 0.0166612 -0.979182 -0.195829 0.0534156 -0.965137 -0.116963 -0.234157 -0.953506 -0.187147 -0.236223 -0.977049 -0.205884 -0.0546469 -0.809789 -0.584248 0.0538167 -0.957684 -0.205334 0.201689 -0.957768 -0.205899 0.200716 -0.957819 -0.204929 0.201463 -0.786128 -0.600476 0.146398 -0.787285 -0.598663 0.147597 -0.447799 -0.892162 0.0593534 -0.451153 -0.890306 0.0617765 -0.0381328 -0.998648 -0.0353154 -0.0436821 -0.998534 -0.0319785 -0.957947 -0.204618 0.20117 -0.957657 -0.205339 0.201814 -0.953259 -0.226849 0.199592 -0.788549 -0.596875 0.148087 -0.787252 -0.598669 0.14775 -0.454628 -0.888469 0.0627421 -0.451118 -0.890312 0.0619362 -0.0489746 -0.998326 -0.0307755 -0.0436648 -0.998537 -0.0318997 -0.208545 -0.124438 -0.970064 -0.292543 -0.101341 -0.950867 -0.219097 -0.0579433 -0.973981 -0.555062 -0.214328 -0.803723 -0.61546 -0.233506 -0.752784 -0.761996 -0.296743 -0.575591 -0.807447 -0.322076 -0.494264 -0.853874 -0.336362 -0.397189 -0.878385 -0.461791 -0.123245 -0.913835 -0.365062 -0.177863 -0.830678 -0.304301 -0.466235 -0.944085 -0.329656 0.00547741 -0.77972 -0.613098 -0.127073 -0.779716 -0.61306 -0.127283 -0.688459 -0.524322 -0.501109 -0.68849 -0.524364 -0.501022 -0.478199 -0.344073 -0.808047 -0.478364 -0.344251 -0.807873 -0.270158 -0.172918 -0.947161 -0.134333 -0.0515928 -0.989592 -0.23212 0.0452389 -0.971635 -0.528709 -0.595342 0.605009 -0.54696 -0.650566 0.526875 -0.602602 -0.614444 0.509244 -0.587086 -0.682194 0.435823 -0.686436 -0.635944 0.352678 -0.649474 -0.691378 0.316511 -0.732436 -0.664285 0.149206 -0.718403 -0.679803 0.147532 -0.726032 -0.685911 -0.0490283 -0.751657 -0.65647 -0.0637095 -0.694305 -0.689378 -0.206635 -0.725419 -0.633826 -0.268388 -0.666186 -0.67024 -0.32707 -0.665148 -0.619349 -0.417115 -0.645974 -0.633947 -0.425239 -0.614245 -0.603409 -0.508528 -0.9279 0.26794 0.259248 -0.731084 0.0334358 0.681468 -0.703688 0.239526 0.668917 -0.849017 -0.157474 0.504353 -0.933564 -0.130798 0.333692 -0.67964 -0.0563083 0.731382 -0.571885 -0.102533 0.813901 -0.101817 0.525632 0.844597 -0.378184 -0.0357308 0.925041 -0.231229 -0.126551 0.964634 -0.0892977 0.0104728 0.99595 -0.667986 -0.213841 0.712789 -0.564464 -0.254798 0.785149 -0.50796 -0.133718 0.850938 -0.318619 -0.254602 0.91305 -0.196253 -0.131954 0.971634 -0.316311 -0.126308 -0.940209 -0.554025 -0.407164 -0.726137 -0.236866 0.408362 -0.881553 -0.640832 -0.108943 -0.759912 -0.747807 -0.0484181 -0.662148 -0.749978 0.213237 -0.626149 -0.415378 -0.261976 -0.871109 -0.596224 -0.126503 -0.792789 -0.639227 -0.262333 -0.72289 -0.751607 -0.202948 -0.627614 -0.775563 0.0668402 -0.627722 -0.887081 -0.162341 -0.432126 -0.958327 -0.123978 -0.257371 -0.94137 0.261885 -0.212692 -0.987164 -0.148606 -0.0585054 -0.979894 -0.143033 0.139102 -0.6035 -0.753842 0.259826 -0.592725 -0.799936 0.0936979 -0.553174 -0.799479 0.234161 -0.507385 -0.849244 0.1461 -0.506919 -0.850185 0.142192 -0.522205 -0.839108 0.152314 -0.46391 -0.883294 0.0676771 -0.556459 -0.827968 0.0694432 -0.467528 -0.883739 0.0205771 -0.561743 -0.826672 -0.0325309 -0.521922 -0.852431 -0.0309717 -0.533099 -0.844665 -0.0484309 -0.599909 -0.791407 -0.117408 -0.479674 -0.780296 0.401312 -0.659178 -0.739773 -0.134988 -0.367688 -0.338282 0.866239 -0.423912 -0.450062 0.785966 -0.581752 -0.348453 0.734946 -0.588419 -0.457 0.667019 -0.77832 -0.369857 0.50737 -0.756239 -0.446521 0.478248 -0.891946 -0.403151 0.2047 -0.882674 -0.423252 0.204317 -0.895028 -0.432643 -0.108376 -0.910981 -0.39355 -0.12342 -0.811238 -0.449862 -0.37352 -0.821172 -0.368109 -0.436088 -0.686979 -0.450035 -0.57055 -0.651176 -0.358813 -0.668747 -0.5528 -0.43362 -0.711608 -0.464789 -0.358025 -0.809808 -0.903114 -0.332001 0.272324 0.0083198 -0.0177043 0.999809 -0.106415 -0.0639463 0.992263 -0.0936012 -0.117064 0.988704 -0.0142915 -0.0575612 0.99824 -0.172942 -0.0833651 0.981398 -0.398519 -0.165216 0.902156 -0.454632 -0.189331 0.870324 -0.672941 -0.253552 0.694883 -0.739242 -0.28471 0.610296 -0.831036 -0.311206 0.461011 -0.909154 -0.336354 0.245571 -0.739385 -0.619339 0.264062 -0.739072 -0.619254 0.265136 -0.602343 -0.522197 0.603733 -0.601604 -0.521803 0.604809 -0.366672 -0.340542 0.865785 -0.365882 -0.340047 0.866313 -0.154302 -0.170973 0.973118 -0.894429 -0.41928 -0.155566 -0.29327 -0.0751673 -0.95307 -0.22285 -0.0430174 -0.973903 -0.560126 -0.162689 -0.812275 -0.620178 -0.176446 -0.76436 -0.777108 -0.227681 -0.586741 -0.820264 -0.246521 -0.516134 -0.874278 -0.258966 -0.410578 -0.940047 -0.283173 -0.190065 -0.945403 -0.288172 -0.152218 -0.956751 -0.290889 -0.0032113 -0.825698 -0.53774 -0.170462 -0.762277 -0.42067 -0.491904 -0.746178 -0.410321 -0.524267 -0.748986 -0.412902 -0.518201 -0.513194 -0.267751 -0.815439 -0.515412 -0.269457 -0.813476 -0.287761 -0.13467 -0.948187 -0.22105 -0.0915565 -0.970955 -0.133361 -0.0454833 -0.990023 -0.372769 -0.0904587 -0.923504 -0.60717 -0.775079 0.174919 -0.619246 -0.539676 0.570337 -0.646177 -0.591542 0.482217 -0.638886 -0.597732 0.484294 -0.629002 -0.672993 0.389148 -0.69933 -0.631615 0.334664 -0.65769 -0.698543 0.281924 -0.741882 -0.658248 0.127751 -0.714881 -0.688761 0.120636 -0.72903 -0.679414 -0.0831421 -0.742535 -0.663874 -0.0889585 -0.681448 -0.688147 -0.249165 -0.712421 -0.632895 -0.303152 -0.660236 -0.661543 -0.355596 -0.657093 -0.598993 -0.457642 -0.686994 -0.574359 -0.445142 -0.648462 -0.542844 -0.533683 -0.491238 0.476201 0.729327 -0.354436 0.65838 0.664012 -0.830616 0.417893 0.368025 -0.927394 -0.0469667 0.371126 -0.833852 -0.0904764 0.544522 -0.663606 -0.0454441 0.746701 -0.559638 -0.102172 0.822415 0.0171866 0.518099 0.855148 -0.35371 -0.0240515 0.935046 -0.241216 -0.115084 0.963624 -0.0683966 0.00692819 0.997634 -0.949511 -0.172362 0.262147 -0.782945 -0.250236 0.569544 -0.767579 -0.142819 0.62484 -0.565379 -0.258083 0.783415 -0.481633 -0.125143 0.867392 -0.352295 -0.23278 0.906477 -0.202102 -0.123432 0.971555 -0.426734 -0.238084 -0.872476 -0.309174 -0.1067 -0.945001 0.152381 0.283924 -0.946661 -0.154918 -0.0181343 -0.987761 -0.628246 -0.254884 -0.735079 -0.582526 -0.112641 -0.80497 -0.0139621 0.62566 -0.779971 -0.467916 -0.0151078 -0.883644 -0.94137 0.295574 -0.162664 -0.98931 -0.141889 -0.0336569 -0.976813 -0.1505 0.15227 -0.657649 -0.0939573 -0.747443 -0.745447 -0.0502367 -0.66467 -0.743063 -0.202609 -0.637814 -0.777042 0.119044 -0.618089 -0.746453 0.268338 -0.608935 -0.892787 -0.155955 -0.422621 -0.962668 -0.129603 -0.237641 -0.688953 -0.708406 0.153314 -0.696402 -0.650628 0.302833 -0.746847 -0.63336 0.202667 -0.612055 -0.767333 0.191281 -0.516099 -0.853054 0.0770702 -0.514116 -0.85462 0.0728607 -0.555922 -0.827089 0.0829137 -0.461924 -0.886835 0.0122438 -0.571294 -0.820437 -0.0224982 -0.465352 -0.884485 -0.0336817 -0.537027 -0.836734 -0.107134 -0.524233 -0.845573 -0.100928 -0.487478 -0.873134 -0.00126696 -0.617511 -0.756781 -0.214389 -0.654969 -0.739837 0.153808 -0.716853 -0.674526 -0.176452 -0.413907 -0.308363 0.856501 -0.491662 -0.415079 0.765492 -0.585956 -0.335674 0.737549 -0.608209 -0.458304 0.648104 -0.775205 -0.361869 0.517793 -0.753124 -0.459194 0.47111 -0.895629 -0.392232 0.209769 -0.876422 -0.436098 0.204214 -0.898983 -0.421211 -0.120047 -0.906571 -0.403098 -0.125067 -0.802201 -0.443404 -0.399833 -0.813808 -0.36756 -0.450129 -0.676294 -0.441532 -0.589641 -0.637148 -0.340307 -0.691545 -0.57529 -0.391061 -0.71841 -0.475675 -0.317847 -0.820187 -0.0160656 -0.0242729 0.999576 -0.116075 -0.0626158 0.991265 -0.114783 -0.0945162 0.988884 -0.0255903 -0.047832 0.998528 -0.766185 -0.269155 0.583537 -0.913078 -0.302601 0.273351 -0.924205 -0.310569 0.222244 -0.196463 -0.0838664 0.976918 -0.415853 -0.1556 0.896022 -0.473916 -0.179495 0.862082 -0.584548 -0.208971 0.783986 -0.741151 -0.257681 0.619917 -0.83843 -0.499954 0.216981 -0.841072 -0.499956 0.206499 -0.695017 -0.42733 0.578222 -0.699714 -0.428846 0.571394 -0.429359 -0.280186 0.858572 -0.433442 -0.281874 0.855964 -0.187984 -0.141842 0.971876 -0.294369 -0.0266397 -0.955321 -0.317521 -0.039555 -0.947426 -0.57619 -0.0892112 -0.812432 -0.631546 -0.0951795 -0.769475 -0.794257 -0.123464 -0.594906 -0.845087 -0.135632 -0.517138 -0.897505 -0.141087 -0.417826 -0.96935 -0.15533 -0.190352 -0.975285 -0.158441 -0.153999 -0.987195 -0.159514 -0.000783545 -0.932298 -0.319692 -0.169166 -0.933706 -0.322134 -0.156279 -0.806511 -0.269256 -0.526347 -0.81038 -0.271957 -0.518964 -0.550713 -0.175042 -0.816135 -0.553915 -0.176826 -0.813579 -0.26389 -0.072973 -0.961788 -0.193421 -0.0277813 -0.980722 -0.818782 -0.543909 -0.183737 -0.819425 -0.546059 -0.174246 -0.711333 -0.458851 -0.53241 -0.712586 -0.460336 -0.529445 -0.49231 -0.301133 -0.81667 -0.490743 -0.299624 -0.818166 -0.206445 -0.103178 -0.973003 -0.149836 -0.053632 -0.987255 -0.202515 -0.107422 -0.97337 -0.192493 -0.139429 -0.971342 -0.445326 -0.354265 -0.822303 -0.436357 -0.376642 -0.817149 -0.629823 -0.556483 -0.541895 -0.623965 -0.567334 -0.5374 -0.717197 -0.669849 -0.192172 -0.71509 -0.67259 -0.190444 -0.527219 -0.846269 -0.0766081 -0.668273 -0.718239 -0.193762 -0.55679 -0.439567 -0.704816 -0.361885 -0.127231 -0.923499 -0.447096 -0.151246 -0.881607 -0.672332 -0.714582 -0.19324 -0.512982 -0.846876 -0.140178 -0.541071 -0.82874 -0.142941 -0.620776 -0.662847 -0.418653 -0.620185 -0.682432 -0.386854 -0.626161 -0.392117 -0.673919 -0.645619 -0.451379 -0.615981 -0.547323 -0.0801783 -0.833072 -0.605825 -0.181292 -0.774667 -0.261306 -0.0680331 -0.962856 -0.366942 -0.26099 -0.892882 -0.457639 -0.354733 -0.815311 -0.463875 -0.372801 -0.803641 -0.605817 -0.585521 -0.538656 -0.620101 -0.663301 -0.418936 -0.645133 -0.735277 -0.207778 -0.633735 -0.763217 -0.126013 -0.818229 -0.166548 0.550238 -0.820247 -0.179247 0.543199 -0.82987 -0.15257 -0.536691 -0.931044 -0.137364 -0.338066 -0.926613 -0.163098 -0.338802 -0.97891 -0.146924 -0.141944 -0.999165 0.0301235 -0.0275954 -0.989805 -0.142023 0.0107617 -0.94736 -0.16367 0.275174 -0.94993 0.165676 0.264924 -0.918711 -0.141716 0.368628 -0.762015 -0.400128 -0.509147 -0.663101 -0.663086 -0.347295 -0.498141 -0.853376 -0.153637 -0.471169 -0.875089 -0.11054 -0.47972 -0.872189 -0.095687 -0.450916 -0.888166 -0.0885227 -0.460521 -0.886747 -0.0399933 -0.457233 -0.888421 -0.0405599 -0.450711 -0.89264 0.00733418 -0.470761 -0.882031 0.0201379 -0.459156 -0.887297 0.0433608 -0.487602 -0.869129 0.082818 -0.498745 -0.863782 0.0716501 -0.516662 -0.845522 0.134732 -0.577787 -0.80966 0.103015 -0.576753 -0.799741 0.166642 -0.684523 -0.714312 0.145553 -0.675332 -0.713734 0.18577 -0.254753 -0.1675 0.952389 -0.119088 -0.0881216 0.988965 -0.614278 -0.133642 0.777691 -0.609007 -0.0917618 0.787839 -0.422429 -0.197474 0.884623 -0.281746 0.13661 0.949714 -0.329371 -0.109705 0.937806 -0.645396 -0.700908 -0.303632 -0.704831 -0.680787 -0.199355 -0.682614 -0.70443 -0.194463 -0.712737 -0.700152 -0.0423479 -0.71284 -0.700048 -0.0423203 -0.692561 -0.713242 0.107915 -0.710922 -0.692321 0.123622 -0.65443 -0.7179 0.237363 -0.675473 -0.681539 0.281498 -0.618091 -0.709013 0.339505 -0.622267 -0.666311 0.410868 -0.604764 -0.676589 0.420105 -0.58213 -0.64123 0.499949 -0.620431 -0.610668 0.492087 -0.579981 -0.59145 0.560187 -0.745808 -0.1232 -0.654669 -0.759378 0.0388107 -0.649491 -0.758237 -0.452525 -0.469358 -0.862874 -0.417721 -0.284531 -0.849069 -0.446369 -0.282553 -0.897195 -0.439772 -0.0405124 -0.899048 -0.436055 -0.0396097 -0.867089 -0.456771 0.198789 -0.879087 -0.424862 0.216099 -0.783531 -0.467672 0.409099 -0.790169 -0.412808 0.453014 -0.670736 -0.469347 0.574305 -0.652159 -0.400208 0.643834 -0.558829 -0.454484 0.693654 -0.502291 -0.386821 0.773352 -0.467589 -0.414373 0.780805 -0.376477 -0.362999 0.852348 -0.031067 -0.0166998 0.999378 -0.12411 -0.0377722 0.991549 -0.795465 -0.161008 0.584219 -0.941591 -0.178498 0.285561 -0.957156 -0.185179 0.222624 -0.215244 -0.0515265 0.9752 -0.416888 -0.089198 0.904571 -0.494026 -0.107461 0.862781 -0.591991 -0.121483 0.796736 -0.760216 -0.151481 0.631764 -0.911674 -0.346891 0.220265 -0.914638 -0.346089 0.208948 -0.757031 -0.296291 0.582336 -0.762334 -0.296744 0.575144 -0.469265 -0.193958 0.861493 -0.473783 -0.194768 0.858834 -0.124282 -0.0671313 0.989973 -0.121563 -0.0665287 0.990352 -0.104494 -0.104848 0.988983 -0.10315 -0.104209 0.989192 -0.421973 -0.309023 0.852317 -0.418133 -0.307417 0.854786 -0.680917 -0.469107 0.562397 -0.676399 -0.467743 0.568947 -0.816169 -0.544768 0.192604 -0.813517 -0.545042 0.20278 0.32543 -0.0689386 0.94305 0.443369 -0.0321679 0.895762 0.468659 -0.0432968 0.882317 0.705222 -0.0963923 0.702403 0.746873 -0.101959 0.657103 0.878964 -0.131522 0.458392 0.922283 -0.146155 0.357818 0.95207 -0.150815 0.266117 0.98582 -0.165056 0.0302399 0.984981 -0.169958 -0.0304309 0.972302 -0.170065 -0.160332 0.949482 -0.312565 -0.02806 0.949924 -0.311648 -0.0227848 0.894047 -0.266563 0.360033 0.892777 -0.265224 0.364151 0.688019 -0.174406 0.704424 0.686227 -0.173259 0.706452 0.411884 -0.0694452 0.908586 0.342199 -0.0307596 0.939124 0.836944 -0.547056 -0.0159545 0.83842 -0.544999 -0.00526354 0.802373 -0.469604 0.368333 0.800578 -0.465739 0.377043 0.63173 -0.309454 0.710743 0.62853 -0.305717 0.715183 0.434488 -0.155716 0.887115 0.297908 -0.0439852 0.953581 0.561154 -0.75801 -0.332455 0.622851 -0.78166 0.0326175 0.432 -0.603451 -0.670241 0.462022 -0.656955 -0.595773 0.464234 -0.655696 -0.59544 0.454903 -0.718963 -0.525506 0.566263 -0.683928 -0.459987 0.538447 -0.725115 -0.429281 0.650602 -0.707553 -0.275836 0.639984 -0.718176 -0.273208 0.682424 -0.72686 -0.0772785 0.701645 -0.708981 -0.0709945 0.666334 -0.73879 0.100936 0.701509 -0.698733 0.140207 0.639098 -0.7339 0.230097 0.659872 -0.682512 0.31424 0.675705 -0.671686 0.303744 0.889381 0.204166 -0.409045 0.935682 -0.151297 -0.318761 0.890164 0.0750757 -0.449412 0.843198 -0.148621 -0.516652 0.671924 -0.169345 -0.720999 0.648335 0.246642 -0.720298 0.500748 -0.386136 -0.774694 0.124956 0.355626 -0.926238 0.210098 -0.254557 -0.943959 -0.0783582 0.0127387 -0.996844 0.534445 -0.225949 -0.814442 0.403434 -0.260413 -0.877169 0.353549 -0.149442 -0.923401 0.163104 -0.252879 -0.95365 0.0343843 -0.132653 -0.990566 0.465686 0.391895 0.793445 0.609885 -0.361728 0.705119 0.38406 0.0492794 0.921992 0.793938 -0.354425 0.494009 0.838652 0.181902 0.513395 0.693131 0.540503 0.476893 0.94809 -0.0951366 0.303439 0.993657 -0.0606185 0.0947189 0.980012 -0.160028 -0.118186 0.981344 0.190259 0.0276564 0.970783 -0.221189 0.0930401 0.905156 -0.258801 0.337215 0.916429 -0.177252 0.358802 0.732352 -0.275849 0.62255 0.719412 -0.152944 0.677535 0.537369 -0.270529 0.798779 0.458297 -0.129561 0.879305 0.500066 -0.637833 -0.585749 0.495164 -0.868366 0.0274533 0.443141 -0.839798 -0.313634 0.404286 -0.881379 -0.244383 0.413312 -0.878613 -0.23919 0.367227 -0.910167 -0.191677 0.474276 -0.844503 -0.24875 0.364792 -0.920296 -0.14136 0.507755 -0.85233 -0.125372 0.385073 -0.917876 -0.0960319 0.471077 -0.881672 -0.027227 0.439552 -0.897467 -0.0366914 0.434017 -0.899421 -0.0516773 0.517227 -0.855004 0.0380112 0.605879 -0.790837 -0.0865289 0.657813 -0.634089 0.406465 0.225551 -0.343194 -0.911781 0.293186 -0.452986 -0.84193 0.428424 -0.378017 -0.820705 0.435308 -0.477387 -0.763288 0.658013 -0.409265 -0.632077 0.640363 -0.466202 -0.610402 0.823429 -0.438393 -0.360245 0.817555 -0.449838 -0.359513 0.88466 -0.463403 -0.0513269 0.899715 -0.434422 -0.0423041 0.841942 -0.482654 0.241204 0.862169 -0.419791 0.283618 0.733554 -0.490845 0.470074 0.726144 -0.403428 0.55674 0.642408 -0.459412 0.613394 0.573204 -0.375308 0.72841 0.895814 -0.205608 -0.394007 -0.0555303 -0.0932088 -0.994097 -0.125624 -0.0150327 -0.991964 -0.0368033 -0.0325655 -0.998792 0.887029 -0.138562 -0.440432 0.799967 -0.149535 -0.581112 0.683324 -0.138594 -0.716841 0.0601332 -0.0450579 -0.997173 0.26279 -0.0766858 -0.961801 0.34313 -0.0922101 -0.934751 0.453025 -0.104724 -0.885325 0.648269 -0.131597 -0.749953 0.869753 -0.305161 -0.387823 0.868276 -0.305338 -0.390981 0.654428 -0.258909 -0.710415 0.653073 -0.258815 -0.711695 0.324735 -0.168901 -0.930602 0.324154 -0.168816 -0.93082 -0.0366637 -0.0581094 -0.997637 -0.0401499 -0.0574398 -0.997541 0.761853 -0.534399 -0.366057 0.758308 -0.534262 -0.373542 0.564728 -0.454138 -0.689087 0.561703 -0.453265 -0.692128 0.267962 -0.297262 -0.916423 0.266718 -0.296758 -0.916949 0.00192387 -0.138801 -0.990318 0.0238352 -0.14406 -0.989282 -0.146604 -0.0593902 -0.987411 0.87134 -0.331892 0.361405 0.381453 -0.0977453 0.919206 0.442481 -0.0653722 0.894392 0.381334 -0.0392208 0.923605 0.697816 -0.146415 0.701153 0.968002 -0.249349 0.0282267 0.937896 -0.228868 0.260711 0.909124 -0.221285 0.352883 0.868545 -0.200139 0.453403 0.74056 -0.155774 0.653686 0.952721 -0.257234 -0.16172 0.965348 -0.257173 -0.0443387 0.920929 -0.388975 -0.024239 0.920968 -0.387806 -0.0377305 0.828454 -0.559764 -0.0181243 0.300549 -0.0405543 0.952904 0.459423 -0.144499 0.876385 0.653769 -0.266928 0.70805 0.669627 -0.280638 0.687635 0.692317 -0.296242 0.657981 0.796531 -0.479819 0.367848 0.828465 -0.559671 -0.0203485 0.548128 -0.761267 -0.346451 0.499894 -0.395268 -0.770629 0.936097 0.335114 0.106874 0.846616 -0.0580787 0.529025 0.811109 0.24091 0.532978 0.653454 0.565162 0.503577 0.946032 -0.0948986 0.309867 0.99326 -0.0556053 0.101696 0.746764 -0.11324 0.655378 0.441928 0.384132 0.810643 0.617798 -0.270239 0.738442 0.251872 0.108168 0.961697 0.292496 -0.0496777 0.954975 0.661475 -0.749783 0.0166218 0.399698 -0.910852 -0.102906 0.521454 -0.85237 -0.0393783 0.458143 -0.88735 -0.0521069 0.467613 -0.883102 -0.0383179 0.545033 -0.838058 0.0244584 0.548676 -0.834684 0.0475112 0.519679 -0.799295 -0.301764 0.420239 -0.603201 -0.6779 0.45124 -0.659436 -0.601271 0.464642 -0.652028 -0.599139 0.455174 -0.713974 -0.532032 0.576614 -0.675576 -0.45947 0.549953 -0.71592 -0.430128 0.662008 -0.697821 -0.273478 0.653327 -0.70674 -0.271447 0.692996 -0.716818 -0.0769993 0.716855 -0.69386 -0.0683904 0.681234 -0.725979 0.0942063 0.717976 -0.682098 0.138756 0.66008 -0.71831 0.219829 0.678204 -0.668758 0.304635 0.698396 -0.653671 0.291475 0.679101 -0.617908 0.396246 0.980996 -0.157678 -0.113073 0.933371 -0.146423 -0.327688 0.897208 0.190102 -0.398597 0.849359 -0.145986 -0.507225 0.679345 -0.167428 -0.714463 0.656598 0.231127 -0.717955 0.185542 0.262267 -0.94699 0.180017 -0.231018 -0.956151 -0.0770306 0.0150918 -0.996915 0.537963 -0.224336 -0.81257 0.407466 -0.258948 -0.875738 0.359327 -0.149103 -0.921223 0.160111 -0.253373 -0.954026 0.0325614 -0.130486 -0.990915 0.981587 -0.190889 -0.00697182 0.903645 -0.257152 0.342488 0.914075 -0.166557 0.369765 0.734314 -0.274365 0.620893 0.715395 -0.145929 0.683312 0.545387 -0.266272 0.794765 0.466965 -0.135457 0.873839 0.464372 -0.599474 -0.651912 0.522773 -0.852449 0.00620301 0.441572 -0.839455 -0.316749 0.407782 -0.879868 -0.244022 0.400322 -0.892371 -0.208368 0.398028 -0.893729 -0.206934 0.426863 -0.888838 -0.166597 0.354266 -0.92375 -0.14554 0.511474 -0.847078 -0.144404 0.218713 -0.341493 -0.914082 0.286239 -0.453709 -0.843929 0.431453 -0.375944 -0.82007 0.437561 -0.473696 -0.764298 0.666236 -0.403063 -0.627432 0.64909 -0.459688 -0.606111 0.830438 -0.431135 -0.352839 0.825507 -0.440938 -0.352294 0.888515 -0.456624 -0.0451175 0.906029 -0.421876 -0.0336425 0.846522 -0.474986 0.240392 0.866857 -0.405908 0.289478 0.743614 -0.481895 0.463481 0.732127 -0.393636 0.555914 0.655211 -0.449768 0.606966 0.591649 -0.377374 0.712419 0.822515 -0.405914 -0.398376 -0.130424 -0.0206893 -0.991242 -0.0422201 -0.0455422 -0.99807 -0.140547 -0.0515975 -0.988729 -0.0610246 -0.0978494 -0.993329 0.665507 -0.195666 -0.720289 0.870554 -0.222033 -0.439132 0.0525401 -0.0636226 -0.99659 0.258558 -0.110224 -0.959687 0.330771 -0.130006 -0.934713 0.446069 -0.149648 -0.882399 0.637067 -0.187727 -0.747599 0.755337 -0.314349 -0.575023 0.886308 -0.22712 -0.403577 0.842837 -0.366382 -0.394195 0.629866 -0.308832 -0.712665 0.625915 -0.308494 -0.716283 0.30824 -0.201112 -0.929808 0.305676 -0.200661 -0.930751 -0.0413595 -0.0695289 -0.996722 -0.0464423 -0.0683785 -0.996578 0.739195 -0.557204 -0.378305 0.735081 -0.557102 -0.386385 0.542459 -0.470912 -0.695687 0.538635 -0.469843 -0.699371 0.252335 -0.307094 -0.917616 0.250346 -0.306295 -0.918428 0.0107145 -0.153931 -0.988024 0.954732 -0.141954 0.261411 0.675817 -0.327514 0.660307 0.69502 -0.310946 0.648275 0.983889 -0.127682 -0.125142 0.658229 -0.752712 0.0126217 0.655452 -0.755193 0.0081585 0.530446 -0.842682 -0.092272 0.705475 -0.0879342 0.703259 0.602537 -0.203375 0.771744 0.624424 -0.2384 0.743815 0.778069 -0.0853511 0.622354 0.0725725 0.55499 0.828686 0.60368 -0.00372911 0.797218 0.50381 -0.110543 0.856712 0.575714 -0.201902 0.792332 0.990328 -0.10535 0.090284 0.893703 0.446601 0.0429359 0.94079 -0.336398 -0.0418485 0.933155 -0.357085 -0.0413733 0.814339 -0.577326 -0.0595602 0.749909 -0.659311 -0.0542771 0.519939 -0.848993 -0.0942033 0.838261 -0.0330373 0.544267 0.85022 -0.163923 0.500255 0.763531 -0.233333 0.602143 0.805144 -0.38476 0.451334 0.77772 -0.309257 0.547276 0.790174 -0.568792 0.228257 0.788448 -0.477799 0.387372 0.741906 -0.665425 0.0823725 0.810803 0.238316 0.534607 0.757306 0.362186 0.543424 0.906819 -0.28795 0.307837 0.87833 -0.402044 0.258644 0.828971 -0.531434 0.174314 0.776127 -0.618327 0.123684 0.62133 -0.783044 -0.0281258 0.624398 -0.779968 -0.0421622 0.508671 -0.508844 -0.694501 0.531705 -0.030407 -0.846384 0.392199 -0.111299 -0.913122 0.708266 -0.0924232 -0.69987 0.832947 -0.0423653 -0.551728 0.513225 -0.849614 -0.121476 0.58472 -0.774342 -0.241861 0.584094 -0.775067 -0.24105 0.585741 -0.779625 -0.221569 0.688391 -0.701569 -0.184174 0.610091 -0.705764 -0.360121 0.583096 -0.613133 -0.53298 0.66249 -0.564938 -0.491887 0.700574 -0.606546 -0.375896 0.656413 -0.636668 -0.404691 0.547522 -0.555172 -0.626102 0.567131 -0.537648 -0.623936 0.374644 -0.204034 -0.90444 0.552946 -0.393308 -0.734547 0.703857 -0.66529 -0.248946 0.853599 -0.364992 -0.371685 0.862109 -0.338749 -0.376852 0.120029 0.711062 -0.692809 0.680378 -0.232028 -0.695161 0.827745 -0.177414 -0.532317 0.792325 0.38259 -0.475233 0.928203 -0.132412 -0.347716 0.422682 -0.328176 -0.844772 0.381202 -0.36477 -0.849487 0.245185 -0.302471 -0.921084 0.247508 -0.305579 -0.919435 0.557202 -0.818136 -0.142055 0.74622 -0.592024 -0.304407 0.656157 -0.629912 -0.415535 0.680487 -0.415595 -0.603505 0.684807 -0.309629 -0.659673 0.645711 -0.114945 -0.754881 0.468878 -0.223746 -0.854454 0.456309 -0.1912 -0.869036 0.225273 -0.0890013 -0.970222 0.239048 -0.170415 -0.955937 0.0811104 -0.0973664 -0.991938 0.048485 -0.132228 -0.990033 -0.0603714 -0.0960024 -0.993549 0.73077 -0.565525 -0.382305 -0.0627207 -0.0990819 -0.993101 0.817539 -0.427118 -0.386265 0.571396 -0.384521 -0.725017 0.589328 -0.391779 -0.706542 -0.127759 -0.0396353 -0.991013 0.0459385 -0.130692 -0.990358 0.176905 -0.206569 -0.962306 0.268473 -0.2516 -0.929849 0.281552 -0.258841 -0.923975 0.438071 -0.328419 -0.836801 0.605167 -0.399913 -0.688362 0.381451 -0.0374533 0.92363 0.390106 -0.0109912 0.920704 0.430268 -0.0328634 0.902103 0.706898 -0.0785029 0.702945 0.708769 -0.0783473 0.701076 0.924261 -0.120016 0.362405 0.925959 -0.11959 0.358187 0.987204 -0.137544 0.0806891 0.988769 -0.1482 -0.0193308 0.983941 -0.142301 -0.107757 0.750466 -0.659286 0.0462872 0.749378 -0.661087 0.0373691 0.718323 -0.558886 0.414317 0.719643 -0.562451 0.407139 0.571564 -0.365808 0.734506 0.573945 -0.369324 0.730881 0.403033 -0.184204 0.896456 0.348183 -0.123803 0.929215 0.279197 -0.061865 0.958239 0.918552 -0.395292 0.00267707 0.917907 -0.396778 -0.00376606 0.861761 -0.335158 0.380837 0.863009 -0.337093 0.376277 0.66491 -0.218972 0.714105 0.666591 -0.220476 0.712072 0.373347 -0.0734816 0.924777 0.38233 -0.0798866 0.920566 0.485291 -0.874353 0.000506369 0.986002 -0.143184 -0.0854361 0.917613 0.374344 -0.133613 0.468335 -0.883539 -0.00447189 0.436267 -0.897053 -0.0704755 0.44114 -0.894575 -0.0716401 0.564243 -0.825576 0.00741419 0.592871 -0.800928 0.0837792 0.625356 -0.690108 0.364254 0.634131 -0.636773 0.438632 0.557586 -0.378164 0.73898 0.727978 -0.670825 0.141568 0.691248 -0.714672 0.106866 0.716167 -0.693066 -0.0822495 0.753914 -0.652637 -0.0753602 0.937018 -0.328095 0.119799 0.964191 -0.133096 0.229394 0.923461 -0.157281 0.349975 0.894725 -0.0760292 0.440099 0.892144 -0.0919685 0.442291 0.804777 -0.244216 0.541011 0.800516 -0.25433 0.54267 0.922965 -0.374099 -0.0904753 0.90029 -0.424662 -0.0956023 0.877353 -0.456178 0.148838 0.933129 -0.119634 0.339054 0.851966 -0.420526 0.311949 0.750695 -0.469784 0.4645 0.753911 -0.263545 0.601799 0.743103 -0.142484 0.653832 0.478425 0.430974 0.765095 0.405519 0.0425316 0.913097 0.616705 -0.428097 0.660612 0.463117 -0.133246 0.876224 0.529159 -0.274688 0.802831 0.615378 -0.464835 0.636584 0.74677 -0.382027 0.544418 0.6904 -0.649052 0.319498 0.651769 -0.711626 0.26227 0.540588 -0.838265 0.0712461 0.487023 -0.873231 0.0166393 0.455004 -0.139128 -0.879554 0.313533 -0.172196 -0.933834 0.264665 -0.13361 -0.95504 0.178881 -0.184554 -0.966407 0.101801 -0.135155 -0.985581 0.0308117 -0.182919 -0.982645 -0.045404 -0.142833 -0.988705 0.431188 0.382541 -0.817153 0.544904 -0.0548319 -0.836703 0.434609 -0.109546 -0.893932 0.93562 -0.15388 -0.317706 0.842383 -0.0452991 -0.536972 0.762037 -0.0845238 -0.641993 0.590899 0.146572 -0.793319 0.446489 -0.893202 -0.0532712 0.530787 -0.839193 -0.11841 0.498006 -0.859085 -0.118162 0.496346 -0.86573 -0.0644337 0.475308 -0.876818 -0.072614 0.45789 -0.888402 -0.032844 0.447453 -0.892694 -0.0537008 0.706919 -0.663418 -0.245238 0.560029 -0.809691 -0.175406 0.54657 -0.813184 -0.199983 0.43895 -0.704374 -0.557835 0.436496 -0.693275 -0.573446 0.668062 -0.70774 -0.229779 0.607564 -0.734807 -0.301537 0.618733 -0.698547 -0.359448 0.556288 -0.731639 -0.394015 0.520893 -0.680504 -0.515349 0.514451 -0.707292 -0.484848 0.487929 -0.723437 -0.488431 0.91497 -0.0733097 -0.396806 0.783888 0.282335 -0.552998 0.877648 -0.182943 -0.44302 0.687987 -0.27095 -0.673246 0.662499 -0.172226 -0.728995 0.482938 -0.26641 -0.834144 0.225174 -0.45276 -0.862731 0.239767 -0.501229 -0.831433 0.326006 -0.442955 -0.835171 0.334899 -0.501327 -0.797819 0.434115 -0.442209 -0.784854 0.434218 -0.498846 -0.750072 0.541331 -0.440902 -0.715938 0.533941 -0.494578 -0.685785 0.689858 -0.411222 -0.595812 0.67429 -0.493663 -0.549209 0.832488 -0.421257 -0.359869 0.845551 -0.386908 -0.367893 0.818772 -0.166232 -0.549526 -0.0713014 -0.117378 -0.990524 0.0104501 -0.0697614 -0.997509 -0.0739575 -0.165254 -0.983474 -0.103685 -0.0452433 -0.993581 0.0893855 -0.0976641 -0.991197 0.321759 -0.1665 -0.932067 0.670143 -0.377858 -0.638852 0.660503 -0.370907 -0.652812 0.727219 -0.163115 -0.666743 0.683697 -0.147163 -0.714774 0.860982 -0.437333 -0.259712 0.845912 -0.423235 -0.324507 0.929454 -0.241203 -0.27917 0.857506 -0.169683 -0.485687 0.93595 -0.0953726 -0.338971 0.754498 -0.617057 -0.223547 0.750418 -0.612205 -0.249153 0.578547 -0.545071 -0.606779 0.572553 -0.53878 -0.61798 0.274031 -0.359786 -0.891886 0.340258 -0.251361 -0.906114 0.0991082 -0.0805261 -0.991813 0.517466 -0.124593 -0.846585 0.0241047 -0.218651 -0.975505 0.119525 -0.298486 -0.9469 0.223989 -0.453731 -0.862529 0.475323 -0.657522 -0.584579 0.476718 -0.659515 -0.581188 0.637251 -0.744816 -0.197889 0.637837 -0.74577 -0.192334 -0.105494 -0.0835316 0.990905 -0.033919 -0.0145565 0.999319 -0.185844 -0.101381 0.977335 -0.112048 -0.111229 0.987458 -0.34617 -0.259381 0.901603 -0.402463 -0.280511 0.871399 -0.466359 -0.365235 0.805675 -0.632408 -0.473246 0.613268 -0.621215 -0.440167 0.64834 -0.731451 -0.591963 0.338467 -0.76671 -0.580991 0.27314 -0.926679 -0.110338 0.359293 -0.216944 -0.0615489 0.974242 -0.732782 -0.646876 0.211147 -0.726958 -0.597421 0.338556 -0.66202 -0.52899 0.530942 -0.611978 -0.452189 0.648851 -0.541859 -0.348869 0.764643 -0.366078 -0.234111 0.900655 -0.493297 -0.330934 0.804451 -0.0958549 0.0635942 0.993362 -0.362639 -0.151597 0.919517 -0.436583 -0.0844503 0.895692 -0.332388 0.254723 0.908094 -0.713831 0.0295215 0.699695 -0.670423 -0.685438 0.28409 -0.656138 -0.742093 0.137045 -0.675781 -0.516201 0.526172 -0.694985 -0.575986 0.43039 -0.609979 -0.284628 0.739536 -0.668896 -0.382445 0.637428 -0.57287 -0.177119 0.800281 -0.702615 -0.100413 0.70445 -0.639639 -0.741075 0.204131 -0.604487 -0.783402 0.14449 -0.749481 -0.539707 0.3834 -0.726899 -0.611384 0.312773 -0.796791 -0.297947 0.525692 -0.797182 -0.391766 0.459369 -0.638487 0.331717 0.694477 -0.845877 -0.142681 0.513941 -0.978796 -0.122077 0.164488 -0.895662 0.357402 0.264676 -0.90672 -0.371352 0.199888 -0.917266 -0.338099 0.210503 -0.779347 -0.608517 0.149416 -0.799681 -0.578046 0.1624 -0.594392 -0.799368 0.0878027 -0.608521 -0.787852 0.0948228 -0.0317078 -0.0403121 0.998684 -0.261487 -0.165736 0.950871 -0.0976462 -0.09453 0.990722 -0.690691 -0.383717 0.612949 -0.853392 -0.4595 0.246133 -0.847013 -0.454579 0.275548 -0.201833 -0.136722 0.96983 -0.412082 -0.246996 0.87703 -0.421426 -0.252613 0.870969 -0.565359 -0.323075 0.758941 -0.707512 -0.394465 0.586366 -0.741199 -0.321019 -0.589551 -0.98932 -0.129997 -0.065931 -0.692575 -0.707602 -0.140142 -0.601608 -0.79804 -0.0346503 -0.653653 -0.755883 -0.0371171 -0.95642 0.0925561 -0.276936 -0.867213 -0.336211 -0.367293 -0.881952 -0.265405 -0.389513 -0.745079 -0.0596246 -0.664306 -0.739122 -0.181885 -0.64855 -0.755606 -0.644671 -0.116012 -0.758424 -0.631332 -0.161902 -0.71179 -0.550681 -0.436011 -0.689543 -0.499821 -0.524128 -0.492787 -0.301535 -0.816234 -0.652728 -0.752501 -0.0876868 -0.77281 -0.5666 -0.285885 -0.745206 -0.6335 -0.208195 -0.916058 -0.381572 -0.123453 -0.786129 -0.615556 -0.055612 -0.805141 -0.589141 -0.0682735 -0.596986 -0.802183 0.0104975 -0.535547 -0.843622 0.0386321 -0.870546 0.42087 -0.254985 -0.932019 -0.338867 -0.128487 -0.85442 -0.403019 -0.327937 -0.80058 -0.0441616 -0.597596 -0.799181 -0.344133 -0.49283 -0.716185 -0.406494 -0.567311 -0.646636 -0.24596 -0.722056 -0.572528 -0.098425 -0.813956 -0.301629 0.233533 -0.924382 -0.191883 0.031555 -0.98091 -0.480913 -0.241058 -0.842979 -0.313293 -0.102906 -0.944064 -0.442369 -0.228186 -0.867318 -0.600155 -0.368258 -0.71007 -0.658158 -0.309648 -0.686255 -0.725812 -0.536549 -0.430479 -0.717385 -0.609811 -0.336883 -0.692349 -0.708752 -0.135366 -0.649654 -0.754969 -0.0892808 -0.131292 -0.0497913 -0.990093 -0.438516 -0.223006 -0.870616 -0.291689 -0.112892 -0.949828 -0.29483 -0.128272 -0.946901 -0.51864 -0.265159 -0.812837 -0.592044 -0.302156 -0.747118 -0.71823 -0.376369 -0.585228 -0.755951 -0.402184 -0.516512 -0.805112 -0.427083 -0.411577 -0.810599 -0.563556 -0.159164 -0.856448 -0.460661 -0.232998 -0.769503 -0.394889 -0.501924 -0.892746 -0.447112 -0.0556275 -0.159617 0.986018 -0.0478608 -0.713013 0.692173 -0.111842 -0.682032 0.668678 -0.296145 0.966566 0.158096 0.20188 0.987923 0.153411 -0.0217652 -0.436535 0.894893 -0.0927533 -0.681041 0.711915 -0.171351 0.874543 0.453036 -0.173012 -0.401103 0.706537 -0.583029 0 1 0 0.14994 0.988691 -0.00267427 0.280243 0.958112 -0.0590284 0.146188 0.988737 -0.0320538 0.432982 0.896389 -0.0949372 0.136313 0.988739 0.0617603 0.136301 0.988741 0.061755 0.290143 0.953897 -0.0767961 0.482752 0.858462 -0.173185 0.126926 0.990461 -0.0536429 0.117657 0.990263 -0.074407 0.117912 0.990221 -0.0745638 -0.0192809 0.990109 -0.138971 0.00728607 0.990358 -0.13834 0.0518701 0.836406 -0.545651 0.0616853 0.947327 -0.31427 -0.138663 0.922756 -0.359575 -0.0715646 0.967726 -0.241628 -0.0218479 0.986148 -0.164422 -0.110786 0.989506 -0.0927556 -0.17022 0.975307 -0.140718 -0.115688 0.988738 -0.0949406 -0.115688 0.988738 -0.0949402 -0.115686 0.988738 -0.0949388 -0.115686 0.988738 -0.0949387 -0.115686 0.988738 -0.0949383 -0.116778 0.988737 -0.093608 -0.102378 0.99141 -0.0813938 -0.142619 0.984603 -0.101081 -0.122541 0.988731 -0.085993 -0.643452 0.706947 -0.293589 -0.336253 0.917516 -0.212365 -0.247724 0.964215 -0.0944592 -0.119147 0.992862 -0.00545865 0.146188 0.988737 -0.0320536 0.133075 0.990673 -0.0292934 0.432999 0.896389 -0.0948598 0.407335 0.908883 -0.0895027 0.667766 0.729865 -0.14624 0.977104 0.15362 -0.147203 0.749402 -0.645395 -0.147856 0.961682 0.175452 -0.210675 -0.946697 -0.321039 -0.0264394 -0.982274 0.186946 -0.0137161 -0.870971 -0.490985 -0.0185151 0.443667 0.896045 -0.0162065 0.436472 0.895571 -0.0862825 0.687769 0.713084 -0.135959 0.684733 0.713161 -0.150136 0.868028 0.45859 -0.190326 0.148596 0.988764 -0.0162638 0.106639 0.994074 -0.0210743 0.434933 0.896351 -0.0859527 0.432982 0.896389 -0.0949373 0.684771 0.713124 -0.150145 0.684767 0.713124 -0.150163 0.868031 0.45859 -0.190309 0.790422 0.587167 -0.174549 0.876997 0.440389 -0.192183 -0.187858 0.982186 -0.0044236 -0.396713 0.91793 -0.00475075 -0.549727 0.835333 -0.00438603 0.922045 0.156666 0.353962 0.834147 0.445721 0.324857 0.899412 0.158104 0.407505 0.274373 0.959366 0.06585 0.899416 0.158077 0.407507 0.899422 0.158037 0.40751 0.899282 0.159036 0.407431 0.899418 0.158142 0.407478 0.918413 0.157984 0.362711 0.548696 0.822681 -0.148755 0.907237 0.158105 -0.389774 0.834742 0.156617 -0.527898 0.834749 0.156572 -0.527901 0.735451 0.158043 -0.658889 0.289754 0.893114 -0.344079 -0.123415 0.162727 -0.978922 -0.131436 -0.188553 -0.973228 -0.0938876 0.986082 -0.13721 0.891149 0.453433 -0.0158863 0.7018 0.712367 -0.00303157 0.948664 0.283864 0.139489 0.857011 0.454689 0.242466 0.809474 0.458532 0.366743 0.809438 0.458608 0.366726 0.809433 0.458609 0.366737 0.809477 0.458516 0.366757 0.82997 0.457892 0.318568 0.831272 0.455139 0.319116 0.879652 0.457381 0.130441 0.956561 -0.245424 0.15735 0.556086 0.830795 0.0234287 -0.106499 0.460568 -0.881212 -0.120902 -0.387642 -0.913847 -0.174066 0.918079 -0.356134 -0.317507 0.618139 -0.719092 -0.267646 0.942147 -0.201803 -0.249912 0.949752 -0.188453 -0.639122 0.561465 -0.525623 -0.686957 0.458551 -0.563757 -0.686957 0.458551 -0.563757 -0.686957 0.458551 -0.563757 -0.684869 0.458548 -0.566293 -0.685123 0.457916 -0.566497 -0.557688 0.454845 -0.694334 0.680968 0.708668 -0.184587 0.595473 0.709647 -0.376581 0.59551 0.709604 -0.376604 -0.287598 0.708702 -0.644227 -0.0845382 0.709605 -0.69951 -0.0845319 0.709668 -0.699447 0.125923 0.708705 -0.694176 0.147219 0.460315 -0.875464 0.078684 0.909828 -0.407457 0.0489355 0.164345 -0.985188 0.301804 0.952336 0.0443887 0.286392 0.951789 0.1099 0.284407 0.952479 0.109072 0.277015 0.952633 0.125509 0.402938 0.896372 0.184817 0.403789 0.896374 0.182942 0.402571 0.897037 0.182378 0.419587 0.896301 0.143496 0.897355 0.000132281 -0.44131 0.966725 0.143221 -0.211967 0.964923 0.155284 -0.211685 0.964506 0.158129 -0.211481 0.868057 0.45853 -0.190333 0.871838 0.458455 -0.172388 0.689321 0.711519 -0.136299 0.702097 0.711971 -0.0125161 0.452243 0.891735 -0.0168858 0.447148 0.89204 0.0657476 0.689966 0.712733 0.126326 0.657658 0.709764 0.25243 0.65507 0.712526 0.251376 0.638541 0.713138 0.289309 0.638542 0.713137 0.28931 0.638545 0.713138 0.289301 0.638545 0.713137 0.289302 0.68133 0.708682 0.18319 0.186198 -0.977945 0.0946239 0.136279 0.988745 0.0617441 0.135119 0.988936 0.0612284 0.137709 0.988919 0.0554501 0.513318 0.83803 0.184963 0.328547 0.940993 0.0811771 0.69654 0.70681 0.123496 0.706523 0.706092 0.0475404 0.735867 0.675673 0.044344 0.682366 0.729263 -0.0505104 0.705461 0.706441 -0.0571471 0.696327 0.70689 -0.124242 0.186914 -0.977735 -0.0953772 0.410667 0.900815 -0.141016 0.368328 0.900043 -0.232933 0.368317 0.900049 -0.232926 0.8565 0.454704 -0.244239 0.752625 0.454985 -0.475966 0.752643 0.454946 -0.475976 0.587547 0.454722 -0.66934 0.458473 0.708673 -0.53627 0.16785 -0.977216 -0.129902 0.303069 0.900843 -0.310856 0.103258 0.990423 -0.0916565 0.344866 0.872244 -0.346781 0.19046 0.955794 -0.224013 0.410793 0.706839 -0.575872 0.351535 0.706307 -0.614454 0.356475 0.690751 -0.629117 0.255781 0.72244 -0.642384 0.259211 0.706116 -0.658946 0.186995 0.70681 -0.682241 -0.00575888 -0.977802 -0.209451 0.0491615 0.900589 -0.431883 -0.0523502 0.89979 -0.43317 -0.0509237 0.906349 -0.41945 -0.287229 0.709777 -0.643208 -0.0197715 -0.987568 -0.155943 -0.34345 0.706938 -0.618289 -0.113975 0.959523 -0.257539 -0.66466 0.157731 -0.730306 -0.757095 0.158004 -0.633911 -0.694047 0.434693 -0.573883 -0.763305 0.158027 -0.626413 -0.763301 0.158059 -0.626409 -0.763301 0.158058 -0.626409 -0.764684 0.158057 -0.624721 -0.770651 -0.126047 -0.624667 -0.633509 0.608458 -0.477959 -0.807172 -0.338745 -0.483451 -0.730297 -0.51919 -0.443969 -0.615622 0.711971 -0.337797 -0.560232 0.712508 -0.42246 -0.559899 0.712912 -0.422219 -0.541846 0.713212 -0.44467 -0.541846 0.713212 -0.44467 -0.541846 0.713212 -0.44467 -0.541852 0.713204 -0.444675 -0.540208 0.713202 -0.446674 -0.540751 0.712516 -0.447113 -0.434389 0.708822 -0.555767 -0.161994 -0.977355 -0.136147 -0.297639 0.824523 -0.481221 -0.614059 0.706369 -0.352099 -0.151298 0.987586 -0.0422144 -0.398641 0.8951 -0.199703 -0.36182 0.896284 -0.25644 -0.768793 -0.269911 -0.579746 -0.345903 0.896365 -0.277273 -0.342674 0.896377 -0.281218 -0.342674 0.896377 -0.281218 -0.342674 0.896377 -0.281218 -0.342669 0.89638 -0.281214 -0.341633 0.896379 -0.282475 -0.338271 0.898509 -0.27974 -0.292969 0.898087 -0.328038 -0.0800953 0.988857 -0.125487 -0.278716 0.910767 -0.304664 -0.922724 -0.277961 -0.267054 -0.955624 -0.113455 -0.271865 -0.307778 0.939216 -0.152139 -0.643535 0.711918 -0.281131 -0.913637 -0.20698 -0.349896 -0.415447 0.896083 -0.156327 -0.13833 0.988593 -0.0595753 -0.157517 0.987512 -0.00301114 -0.836288 0.548243 -0.00721436 -0.698201 0.715864 -0.00737511 -0.690224 0.715363 -0.108841 -0.841017 0.527652 -0.119474 -0.703599 -0.708525 -0.054229 -0.368905 0.928352 -0.0455025 -0.468563 0.874589 -0.124671 -0.696621 0.706978 -0.122073 -0.683094 0.706384 -0.185481 -0.981646 0.187346 0.0356687 -0.836296 0.548219 -0.00806099 -0.550791 0.83302 -0.0520202 -0.191445 0.977711 -0.0861978 -0.981431 0.188486 0.0355806 -0.983442 0.18122 -0.000814009 -0.983236 0.182332 -0.00112477 -0.985138 0.168044 -0.0355702 -0.98497 0.168929 -0.0360171 -0.98669 0.148102 -0.0671494 -0.986543 0.148825 -0.0677127 -0.988013 0.122164 -0.094373 -0.987901 0.122642 -0.0949245 -0.989065 0.0911439 -0.115948 -0.988979 0.0914311 -0.11645 -0.989781 0.0563266 -0.131001 -0.989728 0.0564446 -0.131352 -0.990139 0.0190406 -0.138788 -0.988856 0.0201793 -0.147504 -0.834173 0.55144 -0.00836522 -0.840072 0.530173 -0.11487 -0.838058 0.533159 -0.115757 -0.843633 0.491343 -0.216485 -0.841776 0.493924 -0.217834 -0.84682 0.43301 -0.308868 -0.845202 0.435019 -0.31047 -0.849495 0.357072 -0.388406 -0.848152 0.358471 -0.390046 -0.851557 0.266409 -0.451527 -0.85058 0.267191 -0.452905 -0.852911 0.1646 -0.495429 -0.852377 0.164879 -0.496255 -0.853573 0.05532 -0.518028 -0.848796 0.0563603 -0.525707 -0.545073 0.836745 -0.0524721 -0.553999 0.804509 -0.214129 -0.548479 0.807983 -0.215254 -0.556895 0.744635 -0.36795 -0.551823 0.747598 -0.369579 -0.559433 0.655413 -0.507414 -0.555032 0.657695 -0.509291 -0.561512 0.53983 -0.627127 -0.557945 0.541377 -0.628974 -0.563101 0.402332 -0.721835 -0.560342 0.403255 -0.723465 -0.563866 0.248396 -0.787626 -0.562236 0.24876 -0.788676 -0.564058 0.0839031 -0.821461 -0.570642 0.0832111 -0.816972 -0.182136 0.979453 -0.0865885 -0.192606 0.94171 -0.275836 -0.183602 0.943307 -0.276518 -0.193454 0.869328 -0.454801 -0.185079 0.870687 -0.455685 -0.193926 0.763313 -0.616236 -0.186783 0.764338 -0.617171 -0.194345 0.627336 -0.754109 -0.188172 0.628087 -0.755048 -0.19411 0.46677 -0.862813 -0.189987 0.467176 -0.863511 -0.194094 0.287761 -0.937828 -0.19125 0.28797 -0.938348 -0.193355 0.0974241 -0.97628 -0.200839 0.0970569 -0.974804 -0.201792 0 -0.979428 -0.201792 0 -0.979428 -0.448867 0 -0.893598 -0.572623 -0.00420623 -0.819808 -0.619492 0 -0.785003 -0.801706 0 -0.597719 -0.850137 -0.0050254 -0.526538 -0.90584 0 -0.42362 -0.984609 0 -0.174772 -0.989054 -0.0024112 -0.147534 -0.999617 0 0.0276921 -0.96361 0.189057 -0.188982 -0.963611 0.258197 -0.0691997 -0.998878 0.0384356 0.0276716 -0.545061 0.83829 0.0133179 -0.406955 0.913329 0.0147621 -0.839192 0.543181 0.0266822 -0.661364 0.638637 -0.393371 -0.839772 0.221109 -0.495876 -0.914149 0.404983 0.0178738 -0.82943 0.222244 -0.512497 -0.981852 0.144712 -0.12258 -0.436548 0.232678 -0.869073 -0.606247 0.205676 -0.76822 -0.592229 0.592224 -0.546385 -0.694751 0.694744 -0.18615 -0.694774 0.69471 -0.18619 -0.694804 0.508559 -0.508543 -0.694738 0.508697 -0.508495 -0.70418 0.273205 -0.655354 -0.791626 0.158071 -0.590205 -0.120201 0.448602 -0.885611 -0.250559 0.935114 -0.250565 -0.250549 0.935119 -0.250556 -0.25672 0.766791 -0.588325 -0.310758 0.672108 -0.672086 -0.256758 0.588416 -0.766708 -0.253434 0.296983 -0.920637 -0.195188 0.25373 -0.947377 -0.900066 0.112732 -0.42092 -0.96061 0.21944 -0.170512 -1.84423e-06 0.980793 -0.195052 0 0.965924 -0.258827 -0.00217136 0.967727 -0.251991 0.00139272 0.83141 -0.555658 -4.96004e-06 0.793381 -0.608726 -6.77502e-06 0.555552 -0.831482 0.00208996 0.608825 -0.793301 -0.00277988 0.195272 -0.980745 -1.57417e-05 0.258706 -0.965956 0.440434 0.192758 -0.876848 0.440479 0.192691 -0.87684 0.403518 0.438112 -0.803263 0.34753 0.552818 -0.757374 0.357718 0.604049 -0.712154 0.25145 0.82836 -0.500592 0.224674 0.783907 -0.578802 0.158152 0.97548 -0.153059 0.11751 0.965142 -0.233863 0.151705 0.192678 -0.969464 0.151473 0.19302 -0.969432 0.128834 0.550939 -0.824541 0.128851 0.55092 -0.824551 0.0864916 0.828359 -0.55348 0.0866124 0.828286 -0.553571 0.0305111 0.980327 -0.195007 0.0304456 0.980338 -0.194963 0.25462 0.695064 -0.672351 0.094586 0.963676 -0.249766 0.0946001 0.963667 -0.249795 0.220182 0.783258 -0.581401 0.29406 0.59701 -0.746397 0.342847 0.250693 -0.905323 0.317147 -0.158946 -0.934962 0.594167 0.440495 -0.673 0.542064 0.194904 -0.817422 0.167097 0.253655 0.952753 0.12347 0.69936 0.704024 0.196896 0.979958 0.0302264 0.263042 0.964168 0.0344901 0.222714 0.964502 0.141896 0.222732 0.964496 0.141911 0.146616 0.964496 0.219662 0.146618 0.964495 0.219666 0.0456217 0.964494 0.260134 0.0456195 0.964505 0.260094 0.12347 0.699381 0.704004 0.396796 0.699384 0.594487 0.396771 0.699447 0.594429 0.602755 0.699433 0.38403 0.602789 0.699388 0.38406 0.444828 0.893009 0.06829 0.609916 0.786915 0.0936343 0.708444 0.698542 0.100729 0.790409 0.600441 0.121344 0.890183 0.434624 0.136661 0.167096 0.253651 0.952754 0.537013 0.253649 0.804536 0.537017 0.253556 0.804563 0.815801 0.253573 0.519778 0.81579 0.253641 0.519761 0.957076 0.253314 0.140843 0.970209 0.191078 0.148945 0.979293 0.195096 -0.0540601 0.194791 0.980786 -0.0107531 0.194797 0.980785 -0.010753 0.441626 0.896868 -0.0243781 0.554896 0.831472 -0.0272976 0.979293 0.195096 -0.0540601 0.895509 0.442289 -0.0494349 0.830391 0.555558 -0.0425068 0.792157 0.608748 -0.0437296 0.607837 0.793353 -0.0335545 0.979299 0.195065 -0.0540581 0.979293 0.195096 -0.0540601 0.830197 0.555583 -0.0458295 0.830212 0.555561 -0.0458283 0.55473 0.831467 -0.0306215 0.554716 0.831476 -0.0306221 0.194794 0.980785 -0.0107532 0.194797 0.980785 -0.0107532 0.188715 0.981948 -0.0128473 0.977477 0.194994 -0.0807185 0.216404 0.976245 -0.0107367 0.538856 0.842164 -0.0198721 0.188991 0.981954 -0.00702308 0.182071 0.983262 -0.00672847 0.194474 0.980769 -0.0165063 0.5877 0.807821 -0.0450949 0.554034 0.831408 -0.0425165 0.21534 -0.976463 -0.0121627 0.830122 0.555582 -0.0471809 0.826887 0.560399 -0.0470147 0.319287 0.947484 -0.0181484 0.978664 0.202313 -0.0358648 0.9511 0.197587 -0.237418 0.950927 0.198394 -0.237442 0.808933 0.552133 -0.201932 0.808629 0.552589 -0.201904 0.372201 0.923493 -0.0928887 0.533333 0.839323 -0.105324 0.0869296 0.9958 -0.0287304 0.181416 0.983172 -0.0214559 0.782811 0.195031 -0.590906 0.782275 0.1976 -0.590762 0.666296 0.550536 -0.502951 0.665326 0.552185 -0.502428 0.437504 0.836375 -0.330254 0.299141 0.922332 -0.244578 0.0748227 0.99606 -0.0476019 0.490233 0.190709 -0.850472 0.489505 0.195033 -0.84991 0.417789 0.547839 -0.724793 0.416671 0.550528 -0.723398 0.274504 0.835378 -0.476226 0.273615 0.836377 -0.474983 0.0646787 0.991584 -0.112152 0.538245 0.438761 -0.71957 0.118979 0.184903 -0.975528 0.118382 0.190696 -0.974485 0.109188 0.429144 -0.896612 0.0972072 0.547468 -0.831161 0.0933635 0.699122 -0.70888 0.0624859 0.834999 -0.546693 0.0377196 0.964276 -0.262199 0.0630728 0.918828 -0.389585 0.0859841 0.922911 0.37529 0.0977366 0.792356 0.602179 0.0457566 0.987674 0.149686 0.0248399 0.965761 0.258241 0.218847 0.190654 0.956952 0.218631 0.185073 0.958096 0.186428 0.548324 0.815221 0.189798 0.430213 0.88255 0.177484 0.603423 0.777419 0.574215 0.194751 0.795204 0.574409 0.190674 0.796052 0.48857 0.55092 0.676599 0.489336 0.548378 0.678109 0.320371 0.836967 0.443676 0.239071 0.921716 0.305427 0.0454036 0.996145 0.0750627 0.838127 0.197225 0.508571 0.838443 0.194757 0.509001 0.712619 0.552441 0.432416 0.713405 0.550906 0.433078 0.467162 0.837496 0.283478 0.467829 0.836954 0.283979 0.109409 0.991779 0.0663708 0.718569 0.404818 0.565492 0.970184 0.196603 0.14174 0.970068 0.197224 0.141672 0.82686 0.549254 0.120922 0.824868 0.552374 0.120313 0.546431 0.833667 0.0800801 0.540806 0.837458 0.0786942 0.187436 0.981886 0.0277011 0.393235 0.916485 0.0736281 0.977021 0.206188 -0.0540059 0.978209 0.20046 -0.0540542 0.825022 0.563257 -0.0456086 0.829242 0.557009 -0.0458176 0.536155 0.843599 -0.029646 0.543663 0.838766 -0.0300322 0.180797 0.983469 -0.0100063 0.18547 0.982596 -0.0102507 0.0732749 0.99618 -0.0474989 0.546361 0.39195 -0.740179 0.0631496 0.991739 -0.111649 0.180065 0.983387 -0.0229683 0.0876863 0.995702 -0.0298068 0.529877 0.84079 -0.11092 0.804443 0.555473 -0.210525 0.947435 0.202205 -0.247952 0.369785 0.92407 -0.0967113 0.295624 0.922925 -0.24661 0.432727 0.837615 -0.33339 0.26863 0.837619 -0.475639 0.269788 0.836308 -0.477287 0.0616594 0.915898 -0.396648 0.0236228 0.97998 -0.197691 0.0614193 0.836216 -0.544949 0.06452 0.826187 -0.559689 0.094807 0.547865 -0.831177 0.804899 0.554793 -0.210573 0.658907 0.554853 -0.507917 0.660172 0.552705 -0.508616 0.409796 0.552695 -0.725669 0.411209 0.549275 -0.727465 0.0948425 0.549258 -0.830253 0.105647 0.372178 -0.922129 0.947661 0.201177 -0.247925 0.775793 0.201201 -0.598049 0.776529 0.197713 -0.598258 0.481983 0.197718 -0.853581 0.48293 0.192086 -0.854331 0.111451 0.192076 -0.975031 0.112167 0.185061 -0.976305 0.0865258 0.923235 0.374367 0.0959581 0.828613 0.551537 0.0302768 0.994629 0.0989788 0.0187882 0.980693 0.19465 0.219214 0.19315 0.956367 0.218901 0.185084 0.958032 0.186589 0.549989 0.814062 0.190382 0.372169 0.90843 0.18616 0.547851 0.8156 0.573881 0.199659 0.794227 0.574203 0.193169 0.795599 0.487575 0.554011 0.67479 0.488788 0.550016 0.677177 0.319506 0.838079 0.442198 0.238682 0.922006 0.304855 0.0451792 0.996185 0.0746646 0.837053 0.203808 0.507745 0.837605 0.199658 0.508483 0.710396 0.556457 0.430922 0.71168 0.553974 0.432001 0.465223 0.839005 0.282202 0.466389 0.838062 0.283077 0.108822 0.991869 0.06598 0.722707 0.392747 0.568721 0.968753 0.203717 0.141485 0.968739 0.203784 0.141478 0.823998 0.553639 0.120465 0.822207 0.556412 0.119921 0.543957 0.835321 0.0796906 0.538526 0.838958 0.0783563 0.186528 0.982063 0.0275555 0.393693 0.916282 0.073711 0.974691 0.216962 -0.0538992 0.976705 0.207685 -0.0539838 0.820572 0.569739 -0.0453809 0.82628 0.561405 -0.0456657 0.53245 0.845949 -0.0294526 0.541166 0.840384 -0.0299029 0.179502 0.983707 -0.00993807 0.184572 0.982766 -0.0102042 0.0725888 0.996253 -0.0470227 0.552931 0.366907 -0.748095 0.0628928 0.991821 -0.111066 0.17878 0.983627 -0.0227279 0.0870269 0.995768 -0.029543 0.526212 0.843159 -0.11038 0.800223 0.561932 -0.209465 0.945247 0.212793 -0.247441 0.367224 0.925163 -0.0960175 0.29362 0.924045 -0.244804 0.430726 0.839285 -0.331778 0.267413 0.839288 -0.473377 0.269259 0.837206 -0.476011 0.0622287 0.914983 -0.398666 0.0237439 0.97998 -0.197674 0.0614734 0.837124 -0.543548 0.0648561 0.826195 -0.559639 0.0950809 0.547909 -0.831117 0.800985 0.560814 -0.209548 0.65567 0.560867 -0.505495 0.657811 0.557273 -0.506687 0.408332 0.557274 -0.722987 0.410659 0.551674 -0.725958 0.0951775 0.551681 -0.828607 0.106144 0.370302 -0.922827 0.945665 0.21098 -0.247398 0.774104 0.211013 -0.596855 0.775379 0.205154 -0.597243 0.48126 0.205157 -0.852232 0.482804 0.196092 -0.853492 0.111666 0.196096 -0.974206 0.11278 0.185119 -0.976223 0.134434 0.964524 0.227201 0.134433 0.964525 0.227199 0.492569 0.253734 0.832463 0.495649 0.191343 0.847183 0.458607 0.434683 0.775068 0.363886 0.699558 0.614985 0.398554 0.601563 0.692298 0.314147 0.78704 0.530923 0.220359 0.964031 0.148616 0.220355 0.964032 0.148613 0.594546 0.696945 0.400977 0.594557 0.696931 0.400986 0.802311 0.252003 0.541102 0.802311 0.252003 0.541102 0.261015 0.964526 0.0395053 0.261019 0.964525 0.0395063 0.706535 0.699551 0.106937 0.706532 0.699555 0.106936 0.956383 0.253731 0.144752 0.956379 0.253744 0.14475 0.964456 0.258825 -0.0532403 0.964455 0.258827 -0.0532403 0.706038 0.707101 -0.038975 0.706037 0.707102 -0.038975 0.258426 0.965926 -0.0142657 0.258426 0.965926 -0.0142658 0.956932 0.257995 -0.133114 0.701577 0.70588 -0.0975922 0.205386 0.965796 -0.158286 0.13093 0.986654 -0.0968017 0.217447 0.965913 -0.140462 0.231441 0.965701 -0.11771 0.23144 0.965702 -0.117709 0.24772 0.965702 -0.0778136 0.247723 0.965701 -0.0778144 0.257181 0.965701 -0.0357749 0.257179 0.965701 -0.0357747 0.701567 0.705889 -0.0975912 0.675768 0.705888 -0.212272 0.675776 0.70588 -0.212274 0.631364 0.705881 -0.321109 0.631359 0.705887 -0.321107 0.569561 0.705887 -0.421098 0.569562 0.705886 -0.421099 0.956935 0.257986 -0.133114 0.921744 0.257986 -0.289537 0.921741 0.257997 -0.289537 0.861166 0.257996 -0.437986 0.861167 0.25799 -0.437986 0.776876 0.257989 -0.574374 0.776875 0.257991 -0.574374 -0.961113 0.19349 -0.197038 0.547092 0.829253 0.114151 -0.175896 0.980462 -0.0880663 -0.147073 0.980461 -0.130638 -0.1082 0.980461 -0.164283 0.196399 0.980461 -0.0110888 0.192565 0.980461 0.0401789 0.19257 0.98046 0.04018 0.175582 0.98046 0.0887043 0.175578 0.980461 0.0887021 -0.0619378 0.980461 -0.18671 -0.061937 0.980461 -0.186708 -0.175966 0.829254 -0.530447 -0.0114439 0.980461 -0.19638 -0.011444 0.980461 -0.196382 -0.0325127 0.829252 -0.557929 -0.0325126 0.829254 -0.557925 -0.0488167 0.543933 -0.837708 0.801047 0.43934 0.406576 0.710375 0.605451 0.358883 0.49883 0.829252 0.25201 0.545862 0.790862 0.276717 0.39751 0.895352 0.200823 0.837783 0.543951 -0.0473018 0.873561 0.18523 -0.45009 0.933534 0.183759 -0.307811 0.796913 0.543954 -0.262764 0.837782 0.543952 -0.0473018 0.557995 0.829246 -0.0315048 0.164477 0.980461 -0.107902 0.164478 0.980461 -0.107902 0.467293 0.829253 -0.306558 0.467296 0.82925 -0.30656 0.701617 0.543944 -0.460281 0.558391 0.543945 -0.626358 -0.499737 0.829253 -0.250205 -0.750305 0.543989 -0.375657 -0.750326 0.543954 -0.375667 -0.880112 0.439211 -0.180268 -0.822174 0.543947 -0.167783 -0.779669 0.605474 -0.15974 -0.547501 0.829252 -0.112173 -0.599714 0.790859 -0.122008 0.748915 0.543936 0.378498 0.877421 0.183762 0.44313 0.875697 0.193479 0.442404 0.196399 0.980461 -0.0110888 0.557994 0.829247 -0.0315048 0.547101 0.829247 0.114153 0.821429 0.543948 0.171392 0.82143 0.543947 0.171392 0.375858 -0.923353 0.0784231 0.943273 0.185046 0.275669 0.933534 0.183754 -0.307812 0.969948 0.185231 -0.157765 0.543705 -0.838715 -0.030698 0.982417 0.184329 -0.0296688 0.971261 0.184761 0.150051 0.186818 0.980461 -0.0615991 0.186818 0.980461 -0.0615991 0.530775 0.829246 -0.175011 0.530766 0.829252 -0.175008 0.796923 0.543937 -0.262767 0.701618 0.543942 -0.460282 0.455333 -0.838715 -0.298712 0.441653 0.183824 -0.878152 0.594307 0.185115 -0.782644 0.255554 -0.923322 -0.286653 0.691533 0.184738 -0.698322 0.807397 0.184311 -0.560482 0.130902 0.980461 -0.146835 0.130902 0.980461 -0.146835 0.371904 0.82925 -0.417171 0.371903 0.829251 -0.41717 0.558367 0.544001 -0.62633 0.376897 0.543992 -0.74968 0.440928 0.193493 -0.876438 0.198656 0.193499 -0.960778 0.0883854 0.980461 -0.175739 0.0883857 0.980461 -0.17574 0.251109 0.829251 -0.499286 0.251105 0.829257 -0.499279 0.37458 0.552249 -0.744789 0.168937 0.552256 -0.816378 0.198908 0.18376 -0.962636 0.0200675 0.185043 -0.982526 0.0398311 0.980461 -0.192639 0.0398309 0.980461 -0.192638 0.113161 0.829257 -0.547291 0.113162 0.829252 -0.547298 0.169908 0.543939 -0.821743 -0.0488162 0.543942 -0.837701 -0.0223365 -0.923353 -0.383302 -0.108502 0.184768 -0.976774 -0.405318 0.185238 -0.895212 -0.108201 0.980461 -0.164285 -0.307405 0.829249 -0.466743 -0.175969 0.829248 -0.530455 -0.264205 0.543945 -0.796442 -0.264207 0.543936 -0.796447 -0.171464 -0.838714 -0.516875 -0.28491 0.184335 -0.940663 -0.14707 0.980461 -0.130635 -0.417841 0.829251 -0.371148 -0.307403 0.829251 -0.46674 -0.461546 0.543952 -0.700779 -0.461548 0.543947 -0.700782 -0.540673 0.183746 -0.82092 -0.540671 0.183761 -0.820918 -0.255595 0.965365 -0.0523667 -0.192347 0.980489 -0.0405561 -0.1759 0.980461 -0.0880685 -0.499745 0.829247 -0.250209 -0.417846 0.829248 -0.371152 -0.627363 0.54395 -0.557256 -0.627361 0.543954 -0.557254 -0.407143 -0.838717 -0.361646 -0.662382 0.185218 -0.72591 -0.962953 0.18384 -0.197291 -0.910573 0.185128 -0.369573 -0.343392 -0.923321 -0.171932 -0.854535 0.184739 -0.48543 -0.751691 0.184312 -0.633238 -0.771061 0.19139 -0.607318 -0.946019 0.191406 -0.261556 -0.931737 0.254147 -0.259375 -0.760842 0.254146 -0.597101 -0.70727 0.435246 -0.557073 -0.62779 0.601147 -0.494472 -0.562229 0.700279 -0.439896 -0.484212 0.787455 -0.381384 -0.353029 0.893338 -0.278059 -0.207955 0.964704 -0.161555 -0.156216 0.980029 -0.123042 -0.867765 0.435226 -0.239921 -0.770237 0.601153 -0.212956 -0.687437 0.700279 -0.192457 -0.594087 0.787453 -0.164254 -0.254125 0.964616 -0.0702609 -0.254121 0.964617 -0.0702596 -0.254908 0.965925 0.0448397 -0.192139 0.980786 0.0337982 -0.21691 0.975486 0.0371099 -0.599411 0.79335 0.106311 -0.547169 0.83147 0.0962499 -0.781346 0.608776 0.137443 -0.818796 0.555572 0.144614 -0.951473 0.258802 0.166498 -0.965957 0.19508 0.169917 -0.693246 0.70406 -0.15398 -0.611487 0.790813 0.0264345 -0.260661 0.965365 0.0112683 -0.270723 0.942653 0.195226 -0.434744 0.895362 -0.0965673 -0.693245 0.704059 -0.153987 -0.656461 0.74122 0.140188 -0.965572 0.256758 0.0417875 -0.965582 0.256731 0.0417279 -0.795114 0.605486 0.0343611 -0.957756 0.193477 -0.212767 -0.960223 0.258777 -0.104911 -0.876986 0.439261 -0.194798 -0.776939 0.605461 -0.172575 -0.183294 0.980785 -0.066808 -0.183305 0.980784 -0.0667956 -0.415553 0.896876 -0.151426 -0.415558 0.896871 -0.151438 -0.571962 0.793356 -0.208435 -0.571965 0.793344 -0.208473 -0.74539 0.608755 -0.271683 -0.745391 0.608783 -0.271618 -0.842665 0.442298 -0.307064 -0.842667 0.442279 -0.307085 -0.921502 0.195095 -0.335814 -0.921511 0.195087 -0.335795 -0.43244 0.896874 0.0927992 -0.190526 0.980785 0.0419693 -0.165234 0.98561 0.0356397 -0.595904 0.793335 0.12457 -0.520485 0.846452 0.11231 -0.775522 0.608764 0.167248 -0.825723 0.535982 0.175798 -0.876791 0.442304 0.18869 -0.962917 0.171073 0.208625 -0.958738 0.195085 0.206793 -0.16525 0.98561 0.0355667 -0.193748 0.980203 0.0407923 -0.546405 0.82919 0.117838 -0.520761 0.846451 0.111031 -0.828157 0.531632 0.17755 -0.825512 0.535983 0.176782 -0.956662 0.207237 0.204575 -0.963232 0.171073 0.207168 -0.963981 0.207434 0.166467 -0.193417 0.980202 0.0423618 -0.181714 0.982517 0.0405022 -0.530747 0.839422 0.116951 -0.545641 0.829181 0.121389 -0.809614 0.559269 0.178167 -0.826774 0.531618 0.183921 -0.954335 0.212561 0.209913 -0.963631 0.159047 0.214756 -0.180693 0.982744 0.0395608 -0.181649 0.982518 0.0407733 -0.183846 0.982105 0.0408691 -0.529456 0.840158 0.117519 -0.530535 0.839426 0.11789 -0.808258 0.560837 0.17939 -0.809251 0.559274 0.179793 -0.955158 0.206701 0.212011 -0.954041 0.212579 0.211224 -0.956247 0.205878 0.20786 -0.956077 0.2067 0.207828 -0.809393 0.560293 0.175938 -0.80903 0.560841 0.175864 -0.530229 0.839984 0.115256 -0.529961 0.840161 0.1152 -0.180856 0.982724 0.0393126 -0.180752 0.982744 0.0392906 -0.0493657 0.994477 0.0926248 0 1 0 -0.173431 0.982148 0.0728499 -0.511905 0.837426 0.191496 -0.767645 0.553827 0.322486 -0.902829 0.202584 0.379287 -0.353848 0.923429 0.148562 -0.277315 0.923441 0.265241 -0.278198 0.922988 0.265893 -0.154869 0.922155 0.354467 -0.236936 0.83313 0.499755 -0.0933269 0.659483 0.745903 -0.0247629 0.964608 0.262522 -0.0397587 0.832874 0.552033 -0.0476443 0.788376 0.613346 -0.0616299 0.602371 0.795834 -0.768369 0.552699 0.322695 -0.602185 0.552731 0.576074 -0.6035 0.550257 0.577066 -0.357471 0.550248 0.754614 -0.358705 0.546733 0.756581 -0.061743 0.546485 0.835189 -0.0698931 0.429288 0.900459 -0.903218 0.200768 0.379328 -0.707873 0.200775 0.677204 -0.708625 0.196803 0.677583 -0.419709 0.196809 0.886065 -0.420503 0.191151 0.886926 -0.0757024 0.191153 0.978637 -0.0762226 0.184319 0.979906 -0.329254 0.186493 -0.925641 -0.266484 0.606409 -0.749169 -0.302224 0.432161 -0.849646 -0.087741 0.96512 -0.246668 -0.204815 0.79152 -0.575801 -0.328024 0.256017 -0.909316 -0.654024 0.251668 -0.713383 -0.65402 0.251699 -0.713376 -0.911805 0.251686 -0.324448 -0.911806 0.25168 -0.324449 -0.957646 0.251679 0.139901 -0.957645 0.251681 0.139901 -0.780883 0.251689 0.571729 -0.780887 0.251674 0.571731 -0.422613 0.251673 0.870666 -0.422611 0.251681 0.870664 -0.0507052 0.185115 0.981408 -0.0542355 0.25603 0.965146 -0.0465659 0.43084 0.901226 -0.0411227 0.604057 0.79588 -0.243471 0.703153 -0.668055 -0.484941 0.69645 -0.528952 -0.484949 0.696436 -0.528962 -0.676091 0.696438 -0.240574 -0.676079 0.696451 -0.240568 -0.710068 0.69645 0.103733 -0.710077 0.696441 0.103734 -0.579013 0.696441 0.423927 -0.579002 0.696454 0.42392 -0.313351 0.69646 0.645565 -0.313358 0.696446 0.645577 -0.0421851 0.70315 0.709789 -0.0316556 0.789698 0.612678 -0.0877428 0.965118 -0.246675 -0.179847 0.963936 -0.19617 -0.179843 0.963938 -0.196165 -0.25073 0.963937 -0.089217 -0.250736 0.963935 -0.0892197 -0.263343 0.963935 0.0384712 -0.263341 0.963936 0.038471 -0.214732 0.963936 0.157218 -0.214736 0.963935 0.15722 -0.116215 0.963935 0.239425 -0.116212 0.963936 0.239419 -0.0135093 0.965118 0.261465 -0.0135101 0.965117 0.261471 -0.144941 0.92306 -0.356304 -0.192968 0.792389 -0.578691 -0.0692074 0.987647 -0.140586 -0.0658851 0.96576 -0.250931 -0.369355 0.191992 -0.909239 -0.369319 0.185084 -0.910685 -0.314524 0.549135 -0.77429 -0.328738 0.430268 -0.840714 -0.299779 0.603386 -0.738957 -0.693805 0.197527 -0.692545 -0.694256 0.192 -0.693647 -0.589874 0.552591 -0.588805 -0.591215 0.549186 -0.590643 -0.386635 0.837594 -0.385941 -0.28463 0.921864 -0.262969 -0.0566573 0.996169 -0.0666181 -0.908008 0.20108 -0.367544 -0.90857 0.197513 -0.36809 -0.771214 0.554776 -0.312175 -0.772481 0.552582 -0.312932 -0.505267 0.838375 -0.204529 -0.506359 0.837577 -0.205101 -0.118238 0.991832 -0.0478366 -0.802638 0.39732 -0.444871 -0.979517 0.20078 0.0152806 -0.979458 0.201069 0.0153032 -0.833854 0.551835 0.0128917 -0.831934 0.554718 0.0131524 -0.550716 0.834651 0.00834843 -0.54509 0.838331 0.00880273 -0.188911 0.981991 0.00263574 -0.4004 0.916288 -0.00979952 -0.176657 0.98351 0.0387383 -0.955425 0.208013 0.209506 -0.956109 0.204705 0.209647 -0.806381 0.564341 0.176828 -0.809534 0.559597 0.177502 -0.52391 0.843989 0.114892 -0.530411 0.839726 0.116293 -0.179117 0.983043 0.0392886 -0.180925 0.982697 0.0396699 -0.89549 0.202796 0.396197 -0.895221 0.204001 0.396185 -0.760233 0.555798 0.336355 -0.759742 0.556549 0.336221 -0.349152 0.924251 0.154442 -0.504724 0.841183 0.194075 -0.0816752 0.995714 0.0433851 -0.173862 0.983427 0.0514068 -0.670667 0.198924 0.714588 -0.669888 0.202828 0.71422 -0.569967 0.553471 0.607295 -0.56871 0.555843 0.606307 -0.373561 0.83787 0.398028 -0.252087 0.92311 0.29038 -0.0646356 0.996192 0.0585161 -0.340024 0.192804 0.92044 -0.339139 0.198914 0.919466 -0.289493 0.549624 0.78365 -0.288243 0.553483 0.781391 -0.189895 0.836465 0.514068 -0.188954 0.837868 0.512126 -0.0444511 0.991752 0.120218 -0.421668 0.388396 0.819357 0.0453719 0.185077 0.981676 0.0459243 0.192795 0.980164 0.0419168 0.429586 0.902053 0.0427645 0.549269 0.834551 0.0261977 0.699208 0.714438 0.0295549 0.836089 0.547798 0.00649754 0.964275 0.264823 0.00255974 0.915773 0.401688 -0.336145 0.186297 -0.923201 -0.272179 0.605918 -0.747517 -0.308607 0.431741 -0.847562 -0.209237 0.791193 -0.574659 -0.334623 0.255757 -0.906982 -0.672407 0.251014 -0.69632 -0.672406 0.251024 -0.696317 -0.926597 0.251009 -0.280022 -0.926602 0.25099 -0.280024 -0.945508 0.251016 0.207379 -0.945509 0.25101 0.207379 -0.724343 0.251008 0.642123 -0.724344 0.251004 0.642124 -0.248357 0.702709 -0.666722 -0.49919 0.6954 -0.516942 -0.499181 0.695414 -0.516931 -0.687879 0.695419 -0.207881 -0.687875 0.695424 -0.207879 -0.701922 0.695417 0.153953 -0.701921 0.695417 0.153953 -0.537738 0.69541 0.4767 -0.53773 0.695421 0.476693 -0.123419 0.965625 0.22877 -0.19968 0.96374 0.177014 -0.19967 0.963743 0.177006 -0.260644 0.963741 0.0571671 -0.260642 0.963742 0.0571668 -0.255432 0.963741 -0.0771929 -0.255432 0.963741 -0.0771928 -0.185359 0.963741 -0.191951 -0.185354 0.963743 -0.191945 -0.0896685 0.965044 -0.246271 -0.0896679 0.965045 -0.246269 -0.319254 0.251 0.913825 -0.319245 0.251066 0.91381 -0.237002 0.695422 0.678395 -0.237014 0.69539 0.678423 -0.272002 -0.565543 0.778573 -0.0622629 0.965099 0.254377 0.0216359 0.965037 0.26122 0.021636 0.965041 0.261206 0.0587636 0.702312 0.709439 0.0587626 0.70228 0.709472 0.0744465 0.431926 0.898831 0.0756899 0.255798 0.963763 0.0811004 0.186281 0.979144 -0.144861 0.923302 -0.355709 -0.193044 0.79241 -0.578637 -0.0692284 0.987646 -0.140578 -0.0659305 0.965763 -0.250909 -0.369425 0.194009 -0.908782 -0.369378 0.185105 -0.910657 -0.314402 0.550392 -0.773447 -0.328784 0.430269 -0.840696 -0.299863 0.603353 -0.73895 -0.693381 0.201102 -0.69194 -0.693972 0.194026 -0.693366 -0.588887 0.554847 -0.58767 -0.590634 0.550436 -0.590061 -0.385803 0.8384 -0.385022 -0.284204 0.922105 -0.262584 -0.0564621 0.996196 -0.0663771 -0.907178 0.205516 -0.367139 -0.907893 0.201085 -0.367824 -0.769508 0.55756 -0.311424 -0.771111 0.554804 -0.312379 -0.50382 0.839397 -0.203905 -0.505205 0.838388 -0.204631 -0.117803 0.991893 -0.0476457 -0.805529 0.389682 -0.446398 -0.979235 0.202149 0.0153351 -0.978531 0.205508 0.015592 -0.835183 0.549826 0.0126718 -0.830095 0.557463 0.0133506 -0.552118 0.833726 0.00820559 -0.543523 0.839347 0.00889157 -0.189485 0.98188 0.00257185 -0.400439 0.916271 -0.00977359 -0.955809 0.206094 0.209655 -0.953804 0.215583 0.209241 -0.953962 0.214857 0.209267 -0.955196 0.209067 0.209503 -0.806998 0.563397 0.177023 -0.810825 0.557616 0.17784 -0.528488 0.840988 0.115929 -0.53174 0.838838 0.11663 -0.180302 0.982816 0.0395517 -0.181457 0.982593 0.0398013 0.0349073 0.789829 0.612333 -0.177471 0.982731 0.0523882 -0.0456634 0.992903 0.109813 0.00233304 0.914469 0.40465 0.0063739 0.964281 0.264805 -0.357955 0.890748 0.280065 -0.46754 0.809768 0.354518 -0.107378 0.983493 0.14564 -0.0637583 0.982949 0.172473 -0.189007 0.8377 0.512382 0.0248877 0.837715 0.54554 0.0370261 0.603429 0.796557 -0.413951 0.852575 0.319 -0.303696 0.906597 0.293003 -0.237693 0.93782 0.252975 -0.103643 0.99353 0.0464448 -0.494484 0.841291 0.218435 -0.501749 0.835906 0.222507 -0.893232 0.214234 0.395273 -0.893873 0.211467 0.395313 -0.331703 0.285144 0.899259 -0.0255209 0.10569 0.994072 -0.267287 0.105809 0.95779 -0.267565 -0.510287 0.817322 -0.444474 0.211553 0.870453 -0.668964 0.208182 0.713546 -0.627346 -0.282878 0.725546 -0.772679 0.218251 0.596099 -0.287437 0.55918 0.777623 -0.567363 0.559117 0.604556 -0.565343 0.562877 0.602957 -0.755679 0.562865 0.334861 -0.760448 0.555625 0.336154 0.17272 0.0915887 0.980704 0.0339022 -0.732913 0.679477 0.0429536 0.340596 0.939228 0.039775 0.285359 0.957595 0.0422731 0.552583 0.832385 -0.288269 0.552974 0.781742 -0.188117 0.839979 0.508967 -0.326261 0.843671 0.426349 -0.0997595 0.986455 0.130206 -0.141714 0.980431 0.136645 -0.244433 0.948255 0.202645 -0.385551 0.865527 0.319709 -0.408391 0.855049 0.319543 -0.411554 0.853626 0.319288 -0.38284 0.87477 0.297003 -0.404801 0.859549 0.311949 -0.410349 0.855531 0.315722 -0.414508 0.852333 0.318922 -0.419525 0.850184 0.318098 -0.43055 0.846239 0.313856 -0.690749 0.518886 0.503611 -0.736188 -0.444773 0.510103 -0.342196 0.186391 -0.920956 -0.277063 0.605973 -0.745676 -0.314152 0.431792 -0.845496 -0.0912784 0.96505 -0.245656 -0.213003 0.791211 -0.57325 -0.0912879 0.96504 -0.24569 -0.18641 0.963748 -0.190897 -0.186402 0.963751 -0.190888 -0.243504 0.965039 -0.0969822 -0.839633 -0.482338 -0.249732 -0.257772 0.965663 -0.0323714 -0.34058 0.255707 -0.904776 -0.676283 0.251001 -0.69256 -0.676279 0.251029 -0.692554 -0.927809 0.251034 -0.275958 -0.927803 0.251057 -0.275955 -0.94484 0.25103 0.210385 -0.944838 0.251035 0.210385 -0.723067 0.251027 0.643553 -0.723065 0.251033 0.643552 -0.31854 0.25103 0.914066 -0.318532 0.251094 0.914051 0.0820034 0.0906038 0.992505 0.0748934 0.255834 0.963815 0.0773533 0.342635 0.936279 0.0654986 0.605964 0.792791 -0.25271 0.7028 -0.664989 -0.501992 0.69551 -0.514072 -0.502008 0.695484 -0.514092 -0.688726 0.695481 -0.204847 -0.688741 0.695465 -0.204852 -0.701362 0.695487 0.156171 -0.701374 0.695475 0.156172 -0.536751 0.695469 0.477726 -0.536736 0.695487 0.477715 -0.236451 0.695493 0.678513 -0.236453 0.695487 0.678519 0.0533206 0.702772 0.709414 0.0503552 0.791176 0.609512 -0.259612 0.965474 0.0214882 -0.719777 -0.675452 0.16027 -0.24643 0.965315 0.0862505 -0.199304 0.963749 0.177387 -0.199293 0.963753 0.177379 -0.0877961 0.963753 0.251937 -0.0877994 0.96375 0.251945 0.0215791 0.965044 0.261199 0.0215791 0.965044 0.261197 -0.974899 0.2179 -0.0457391 -0.860227 0.212443 -0.463548 -0.724528 0.210514 -0.65631 -0.545179 0.83819 0.0147128 -0.0682851 0.965752 -0.250319 -0.108026 0.99301 -0.0475476 -0.394805 0.918751 -0.00510048 -0.186936 0.982361 0.00464162 -0.291114 0.873332 -0.390568 -0.400885 0.725293 -0.55968 -0.143215 0.983537 -0.110204 -0.170965 0.982976 -0.0672915 -0.502389 0.841667 -0.197993 -0.539805 0.841673 0.0140445 -0.827412 0.561164 0.0220321 -0.311899 0.84832 -0.427869 -0.28941 0.904134 -0.314298 -0.249327 0.937137 -0.244152 -0.284734 0.187879 -0.940015 -0.283243 0.194998 -0.939015 -0.498907 0.194119 -0.844636 -0.412182 0.492261 -0.766672 -0.698528 -0.198113 -0.687612 -0.93411 0.218118 -0.2826 -0.861433 -0.376991 -0.340311 -0.771127 0.559667 -0.303538 -0.591498 0.559751 -0.580352 -0.594087 0.553362 -0.583825 -0.392765 0.559164 -0.730117 -0.0695257 0.987171 -0.143731 -0.205618 0.837436 -0.506382 -0.235421 0.789151 -0.56729 -0.381607 -0.0389667 -0.923503 -0.218112 0.609687 -0.762042 -0.260691 0.434707 -0.862015 -0.964032 0.219597 0.149731 -0.93246 -0.360424 0.0247692 -0.825782 0.56357 0.0217447 -0.768519 0.56357 -0.302931 -0.504575 0.840211 -0.198621 -0.418353 0.84395 -0.335753 -0.127336 0.986597 -0.102034 -0.135857 0.979705 -0.147378 -0.206481 0.942941 -0.261206 -0.313889 0.86235 -0.397273 -0.313029 0.851828 -0.420002 -0.312487 0.849621 -0.424848 -0.320881 0.840656 -0.436271 -0.344911 0.810629 -0.473198 -0.364073 0.784044 -0.502719 -0.311401 0.847464 -0.429923 -0.310413 0.846123 -0.433266 -0.306613 0.842823 -0.44231 -0.527581 0.376571 -0.761481 -0.509793 -0.393317 -0.765123 -0.181956 0.982562 0.0382579 -0.179858 0.982965 0.0378324 -0.533298 0.838465 0.112115 -0.532087 0.839266 0.111872 -0.813181 0.556328 0.170986 -0.815646 0.552558 0.17147 -0.958915 0.199547 0.20165 -0.960883 0.189484 0.201992 -0.178304 0.983056 0.0425356 -0.180783 0.982578 0.0431085 -0.522966 0.843171 0.124776 -0.529919 0.83858 0.126371 -0.799918 0.568946 0.190869 -0.808182 0.556504 0.192729 -0.948824 0.220162 0.22641 -0.953143 0.199634 0.227298 -0.687991 0.58404 0.430774 -0.492113 0.818593 0.296193 -0.391631 0.901979 0.181823 -0.249092 0.965772 0.0723732 -0.456502 0.84405 0.281401 -0.177314 0.982805 0.051518 -0.15387 0.987249 0.0407946 -0.189252 0.97799 0.0878633 -0.313511 0.93324 0.175426 -0.446281 0.859345 0.249719 -0.455133 0.847239 0.273935 -0.456132 0.845059 0.278959 -0.560864 0.753508 0.343011 -0.600346 0.708965 0.370072 -0.64247 0.654171 0.399116 -0.456738 0.84314 0.283734 -0.456849 0.842298 0.286047 -0.45676 0.839333 0.294774 -0.831083 0.14707 0.53635 -0.911106 0.185799 0.367921 -0.911101 0.185822 0.367921 -0.777608 0.544724 0.314009 -0.777561 0.544797 0.313998 -0.511359 0.834189 0.206497 -0.693507 0.185603 0.696131 -0.693456 0.185874 0.696111 -0.59189 0.544674 0.594136 -0.591852 0.544746 0.594108 -0.389236 0.834172 0.390708 -0.389159 0.834237 0.390645 -0.079247 0.993676 0.079545 -0.784497 -0.339983 0.518628 -0.365091 0.185126 0.91238 -0.36502 0.185613 0.912309 -0.311611 0.544453 0.778762 -0.31154 0.544664 0.778643 -0.204905 0.834133 0.512091 -0.204878 0.83417 0.51204 -0.0485362 0.99143 0.121291 -0.416975 0.487287 0.767257 0.0221621 0.184919 0.982504 0.0221771 0.185113 0.982467 0.0203671 0.429002 0.903074 0.0229106 0.544056 0.838736 0.00910409 0.699067 0.714998 0.0164675 0.83374 0.551911 0.000259728 0.96426 0.264957 -0.00620571 0.921864 0.387463 -0.756882 0.600156 0.258732 -0.915335 0.253487 0.312901 -0.250073 0.964446 0.0854845 -0.584119 0.786725 0.199674 0.0181515 0.184768 0.982615 -0.915351 0.253425 0.312903 -0.707138 0.253386 0.660114 -0.707097 0.253557 0.660092 -0.375014 0.25359 0.89166 -0.375036 0.253455 0.891689 0.0142972 0.253887 0.967128 0.0166883 0.428708 0.903289 -0.674648 0.699618 0.23534 -0.522639 0.699147 0.487896 -0.52265 0.699132 0.487905 -0.277202 0.699126 0.659077 -0.277195 0.69914 0.659065 0.0132002 0.69952 0.714492 0.0131988 0.699501 0.71451 -0.250061 0.964449 0.0854813 -0.193172 0.964451 0.18033 -0.193193 0.964444 0.180347 -0.102465 0.964442 0.243624 -0.102459 0.964446 0.243611 0.00487625 0.964518 0.263974 0.00487623 0.964517 0.263974 -0.193724 0.980785 0.0230777 -0.256907 0.965925 0.0314379 -0.551726 0.831476 0.0651676 -0.604478 0.79336 0.0720095 -0.825633 0.555568 0.0983549 -0.787885 0.608756 0.0930247 -0.973772 0.195072 0.117108 -0.959142 0.258828 0.114259 0.894774 0.073306 -0.440461 0.865305 0.258846 -0.429238 0.863544 0.266643 -0.428012 0.789756 0.474961 -0.388198 0.711426 0.608811 -0.35103 0.691362 0.637332 -0.340333 0.546224 0.793307 -0.268892 0.520839 0.814592 -0.255279 0.231449 0.965925 -0.115846 0.201296 0.974505 -0.0990908 0.190565 0.980785 -0.0417838 0.218857 0.974521 -0.0490964 0.54286 0.831478 -0.118096 0.566497 0.814649 -0.124209 0.752722 0.637314 -0.165047 0.812561 0.555556 -0.176358 0.85967 0.474803 -0.188495 0.941383 0.266818 -0.206415 0.958381 0.195083 -0.208443 0.974153 0.0735043 -0.213597 0.958026 0.195091 -0.210061 0.958028 0.195084 -0.210061 0.81216 0.555594 -0.178077 0.812185 0.555557 -0.178081 0.54269 0.831462 -0.118991 0.542665 0.831479 -0.118987 0.190564 0.980785 -0.0417839 0.190565 0.980785 -0.0417839 0.183013 0.982187 -0.0426082 0.191408 0.980777 -0.0379313 0.962828 0.195037 -0.186876 0.148037 -0.988346 -0.0354695 0.962522 0.154781 -0.2227 0.425587 -0.900075 -0.0934891 0.827478 0.531455 -0.181208 0.812194 0.555592 -0.177927 0.542502 0.83161 -0.118817 0.542718 0.831462 -0.118864 0.0486448 0.998759 -0.0106852 0.160598 0.986464 -0.0331302 0 1 0 0.965006 0.154797 -0.211665 0.183529 0.98219 -0.0402578 0.18355 0.982186 -0.0402619 0.183626 0.982171 -0.0402771 0.184833 0.981934 -0.0405375 0.186604 0.981583 -0.0409226 0.186959 0.981512 -0.0409999 0.185391 0.981835 -0.0403804 0.193484 0.980186 -0.04242 0.252945 0.965893 -0.0553976 0.542502 0.83161 -0.118817 0.54274 0.831446 -0.118869 0.827474 0.531455 -0.181228 0.823964 0.537136 -0.180465 0.915839 0.347858 -0.200582 0.963026 0.168027 -0.210588 0.185505 0.981775 -0.04131 0.542586 0.83144 -0.119618 0.824639 0.535575 -0.182017 0.823719 0.537132 -0.181593 0.963033 0.165446 -0.212589 0.962669 0.168021 -0.21222 0.185363 0.981835 -0.0405126 0.183783 0.982132 -0.0405116 0.543417 0.830853 -0.119927 0.961861 0.16548 -0.217808 0.82499 0.535572 -0.180429 0.520189 0.847117 -0.108608 0.172619 0.984331 -0.0359986 0.177115 0.983495 -0.0369718 0.167374 0.985232 -0.0361224 0.957016 0.205822 -0.204345 0.951374 0.231206 -0.203548 0.803115 0.570511 -0.171824 0.747635 0.644184 -0.161459 0.543922 0.830846 -0.117661 0.953245 0.220982 -0.206134 0.952859 0.223163 -0.205567 0.935284 0.289208 -0.203966 0.946789 0.2459 -0.207664 0.961852 0.168253 -0.215711 0.952486 0.23513 -0.193609 0.965391 0.166218 -0.200977 0.950056 0.240924 -0.198365 0.806542 0.566696 -0.168362 0.803954 0.57051 -0.167859 0.518089 0.848462 -0.108149 0.517342 0.848462 -0.111666 0.185754 0.981772 -0.0402329 0.175758 0.983814 -0.0349099 0.17793 0.983409 -0.0353332 0.521222 0.847114 -0.103564 0.526547 0.843687 -0.104596 0.808136 0.566691 -0.160555 0.809517 0.564641 -0.16082 0.854052 0.49174 -0.169667 0.959367 0.209584 -0.188918 0.916773 0.22142 0.332416 0.170198 0.985261 -0.017149 0.164002 0.985664 0.0396201 0.178359 0.983408 -0.0331087 0.978763 0.204921 0.00549166 0.97764 0.204964 -0.0470181 0.586578 0.807395 -0.063556 0.515653 0.854972 -0.0559006 0.53498 0.842856 -0.0582312 0.815829 0.571483 -0.0884898 0.821409 0.563321 -0.0892031 0.443746 0.894859 -0.0481327 0.969434 0.209252 -0.128107 0.795898 0.579942 0.173821 0.986277 0.10049 0.130993 0.0739115 0.997251 0.00518753 0.17424 0.984556 0.0170062 0.53255 0.84476 0.0526399 0.684683 0.727022 0.0514555 0.412232 0.910772 0.0236336 0.830826 0.554514 0.0473517 0.819303 0.571474 0.0464841 0.405291 -0.913916 0.0223071 0.517717 0.855517 0.00765805 0.334815 0.94227 0.00513239 0.170579 0.985342 -0.00217785 0.493214 0.859548 0.133855 0.364302 0.926034 0.0987171 0.161245 0.985808 0.0467228 0.933609 0.221588 0.281556 0.570596 0.811059 0.128857 0.793365 0.581683 0.179489 0.811592 0.554491 0.184008 0.389079 -0.916883 0.0891249 0.526418 0.844758 0.0962708 0.21365 0.976122 0.0392319 0.172283 0.984561 0.0309398 0.882138 0.23774 0.406587 0.340719 0.929731 0.139681 0.753152 0.580591 0.309316 0.752399 0.58174 0.308991 0.488472 0.849171 0.200758 0.47366 0.858968 0.194475 0.164974 0.98396 0.0678676 0.155799 0.985713 0.0640032 -0.506631 0.858166 0.0829197 -0.159706 0.986818 0.0261427 -0.154919 0.986884 0.0453878 -0.152815 0.987242 0.0447207 -0.174385 0.98241 0.0667799 -0.149653 0.987114 0.056663 -0.141839 0.987047 0.0749591 -0.110333 0.992153 0.0588226 -0.20491 0.966431 0.154993 -0.126957 0.987159 0.0969466 -0.128434 0.981659 0.140891 -0.053579 0.986316 0.155916 -0.0685145 0.986255 0.150354 -0.236775 0.829249 0.506245 -0.048305 0.996487 0.0684183 -0.0877072 0.98865 0.121975 -0.22147 0.940817 0.256545 0.0287348 0.985629 0.166464 0.00791521 0.98556 0.169143 0.00842897 0.982893 0.183983 -0.0201248 0.984383 0.174884 -0.0189916 0.985932 0.166063 -0.036804 0.986018 0.162526 -0.063434 0.962644 0.263234 0.291111 -0.922444 0.253675 0.104981 0.990773 0.0857157 0.152101 0.98398 0.0929971 0.263801 0.950628 0.163449 0.448867 0.849219 0.278111 0.692063 0.580679 0.42879 0.825803 0.237196 0.511652 0.449158 0.849004 0.278298 0.398333 0.849005 0.347163 0.399958 0.84764 0.348626 0.354171 0.848229 0.393791 0.424818 -0.746428 0.512225 0.128113 0.983895 0.124647 0.119964 0.983884 0.13259 0.134296 0.979623 0.149342 0.0973853 0.987089 0.127171 0.316538 0.852751 0.415475 0.264954 0.852214 0.451144 0.270888 0.84469 0.461647 0.193005 0.844687 0.499253 0.189842 0.850435 0.490633 0.129455 0.850981 0.508992 0.138789 -0.739931 0.65821 0.102438 0.985747 0.133455 0.0853571 0.985677 0.145451 0.0914311 0.983502 0.156093 0.0652858 0.9835 0.168716 0.0613503 0.985509 0.158141 0.0421362 0.985588 0.16383 0.0498264 0.979053 0.197415 0.0269332 0.98719 0.157257 0.0871574 0.851449 0.517145 0.0245558 0.850911 0.524736 0.0247799 0.846226 0.532247 -0.0612637 0.846224 0.529294 -0.0594001 0.854948 0.515301 -0.120829 0.855479 0.503544 -0.176983 -0.761977 0.622951 -0.0409632 0.988744 0.143897 -0.0848045 0.962152 0.258984 -0.159996 0.858739 0.486795 -0.217475 0.858222 0.464931 -0.219034 0.856086 0.468126 -0.291611 0.856079 0.426722 -0.27595 0.872133 0.404025 -0.500562 0.662292 0.5575 -0.420896 -0.7924 0.44153 -0.170988 0.984879 0.027856 -0.495984 0.864513 0.0813451 -0.481856 0.865017 0.139862 -0.576852 -0.793557 0.193675 -0.464945 0.867396 0.177343 -0.440917 0.866896 0.232557 -0.446537 0.863243 0.235409 -0.402523 0.863241 0.304614 -0.395908 0.867985 0.299765 -0.356296 0.868485 0.344656 -0.114296 0.987216 0.111095 -0.0947811 0.991135 0.0930977 0.692409 0.580099 0.429016 0.614065 0.5801 0.535172 0.616035 0.576335 0.536972 0.521564 0.576347 0.629122 0.523528 0.571827 0.631611 0.415238 0.571821 0.707529 0.416447 0.56823 0.709709 0.296965 0.568236 0.767411 0.297313 0.566742 0.768381 0.170032 0.566742 0.806159 0.169863 0.568089 0.805247 0.0381987 0.568087 0.822082 0.0381332 0.572462 0.819044 -0.0940227 0.572468 0.814518 -0.0933172 0.57966 0.809498 -0.222372 0.579653 0.783934 -0.220362 0.589076 0.777451 -0.342624 0.589087 0.731837 -0.339179 0.599553 0.72491 -0.451555 0.599542 0.660793 -0.447115 0.609576 0.654603 -0.546764 0.60959 0.573977 -0.542691 0.617021 0.569887 -0.627546 0.617007 0.474856 -0.626132 0.619226 0.473833 -0.694476 0.619237 0.3664 -0.698226 0.613882 0.368278 -0.748425 0.613884 0.251011 -0.753386 0.607144 0.252558 -0.78416 0.607135 0.128371 -0.785293 0.605636 0.128531 0.826 0.236214 0.511789 0.732544 0.236219 0.63842 0.733616 0.229989 0.639462 0.621125 0.230003 0.749202 0.622163 0.222484 0.750609 0.493474 0.222483 0.840824 0.494084 0.216533 0.842018 0.352331 0.216536 0.910481 0.352494 0.214104 0.910992 0.201588 0.214105 0.955783 0.201518 0.216276 0.955309 0.045309 0.216274 0.975281 0.0453317 0.223526 0.973643 -0.111784 0.22353 0.968266 -0.111297 0.235503 0.96548 -0.265236 0.235498 0.934982 -0.263958 0.251149 0.931263 -0.41043 0.251156 0.876623 -0.408215 0.268657 0.872459 -0.543476 0.26865 0.795275 -0.540538 0.28554 0.791382 -0.661026 0.285548 0.693907 -0.658261 0.298108 0.691248 -0.76118 0.298098 0.575971 -0.760207 0.30186 0.575296 -0.84319 0.301866 0.444869 -0.845749 0.292769 0.446089 -0.906551 0.292772 0.304054 -0.909831 0.28139 0.305004 -0.94699 0.281383 0.155026 -0.946442 0.283257 0.154961 -0.1762 0.984258 0.0137526 -0.972723 0.218907 0.0767501 -0.955773 0.284127 0.0759674 -0.817938 0.571675 0.0645389 -0.792273 0.606912 0.0629385 -0.528085 0.848168 0.0416749 -0.51051 0.858918 0.0405006 -0.184692 0.982688 0.0145919 -0.172139 0.984976 0.0138356 -0.972638 0.218905 0.0778242 -0.193486 0.981046 0.0105943 -0.176172 0.984258 0.0141435 -0.196273 0.980432 0.0151888 -0.512599 0.857804 0.037599 -0.963051 0.258324 0.0761695 -0.953339 0.296207 0.0583637 -0.984593 0.162594 0.064345 -0.69552 0.716719 0.0506492 -0.526849 0.849092 0.038367 -0.528325 0.84817 0.0384797 -0.816651 0.57406 0.0594702 -0.818311 0.571678 0.0595996 -0.782344 0.620234 0.056982 -0.865476 0.496886 0.0636746 -0.273175 0.961773 0.0191682 -0.111921 0.993694 0.00675493 -0.527277 0.8491 0.0317581 -0.522526 0.852041 0.0315048 -0.817324 0.574072 0.0492198 -0.811511 0.582286 0.0489295 -0.92328 0.380078 0.0556222 -0.981031 0.185361 0.0567326 -0.988455 0.14246 0.0515897 -0.914597 0.401099 0.0513117 -0.854033 0.518024 0.0477395 -0.811696 0.582286 0.0457363 -0.565478 0.824158 0.0315866 -0.522645 0.852042 0.029449 -0.212097 0.977177 0.0118243 -0.131167 0.991328 0.00802002 -0.188721 0.981985 0.00951672 -0.193577 0.981059 0.00714422 -0.186108 0.982491 0.00873422 -0.557625 0.829753 0.0237514 -0.5657 0.82422 0.0254011 -0.849179 0.526845 0.0364582 -0.854465 0.518114 0.0380397 -0.98741 0.152344 0.042569 -0.988824 0.142507 0.0438069 -0.188665 0.981985 0.0105104 -0.197009 0.980341 0.010889 -0.185089 0.982668 0.0102296 -0.184959 0.982693 0.0102221 -0.185021 0.982681 0.0102258 -0.986814 0.152354 0.0546564 -0.9828 0.176501 0.0543239 -0.982766 0.176691 0.0543232 -0.982334 0.179084 0.0543063 -0.980439 0.189209 0.0542177 -0.837261 0.544838 0.0463226 -0.848645 0.526878 0.0469295 -0.547159 0.836481 0.0302721 -0.557244 0.829777 0.0308172 -0.190122 0.981704 0.010519 -0.196977 0.980348 0.0108873 -0.185056 0.982681 0.00958439 -0.155947 0.98768 0.0130245 -0.0224836 0.999747 0.000960285 -0.984593 0.156368 0.0782708 -0.98344 0.176676 0.0403847 -0.837265 0.544838 0.0462448 -0.168492 -0.98567 0.00805401 -0.249224 -0.968343 0.0140935 -0.889653 0.453989 0.049105 -0.757599 0.651356 0.0421768 -0.2684 0.96323 0.0122277 -0.106596 0.994285 0.00597091 -0.547166 0.836481 0.030145 -0.453297 0.891002 0.0252643 -0.646577 0.762012 0.0357222 -0.997741 0.0384627 0.0550777 -0.987631 0.14696 0.0546541 -0.986181 0.156414 0.0546074 -0.963336 0.262974 0.0531785 -0.912841 0.405194 0.050391 -0.889643 0.453989 0.0492888 -0.838267 0.543292 0.0462744 -0.757619 0.651356 0.0418224 -0.706038 0.707112 0.0387777 -0.646579 0.762012 0.0356927 -0.544218 0.838406 0.0300422 -0.453299 0.891002 0.025198 -0.406545 0.913355 0.0224422 -0.156192 0.987689 0.00862222 -0.156195 0.987689 0.00862234 -0.156194 0.987689 0.00862227 -0.156192 0.987689 0.00862217 0.154602 0 -0.987977 0.154602 0 -0.987977 0.37871 0 -0.925515 0.448844 0.00600392 -0.89359 0.517137 0 -0.855903 0.843824 0.515329 -0.149656 0.692623 0.705294 -0.151106 0.553791 0.821929 -0.13322 0.974637 0.11742 -0.190513 0.99848 -7.55499e-07 -0.0551187 0.980812 0.156961 -0.115635 0.973474 0.220269 -0.0618907 0.972027 0.207683 -0.10969 0.185647 0.617249 -0.764551 -0.203705 0.643811 -0.737571 0.183359 0.706038 -0.684025 0.187934 0.797354 -0.573504 0.178391 0.798781 -0.574566 0.190063 0.912175 -0.363059 0.179101 0.914102 -0.363786 0.190941 0.968334 -0.160846 0.561102 0.816989 -0.133015 0.549499 0.81558 -0.181326 0.539146 0.774957 -0.329791 0.545867 0.770938 -0.328152 0.535996 0.675114 -0.506881 0.541917 0.672081 -0.504611 0.533663 0.536175 -0.654003 0.538377 0.53432 -0.651654 0.834402 0.528729 -0.155624 0.827989 0.506022 -0.241614 0.917472 0.355786 -0.177939 0.912941 0.307659 -0.268114 0.914076 0.305713 -0.266468 0.910311 0.243835 -0.334483 0.823042 0.333184 -0.45999 -0.999661 0.0208913 0.0155439 -0.973671 0.0420184 -0.224054 -0.925025 0.0634546 -0.374569 -0.996035 0.0692201 -0.0558823 -0.997888 0.0646047 0.00669508 -0.988687 0.0747349 0.130047 -0.890549 0.0604479 -0.450854 -0.689983 0.0346985 -0.722994 -0.707024 0.0399884 -0.706058 -0.411455 0.0160684 -0.911288 -0.376048 0.00803518 -0.926566 -0.921211 0.0405252 0.386948 -0.897078 0.0857213 0.433477 -0.886878 0.0716116 0.456419 -0.721934 0.0453827 0.690472 -0.693277 0.0497427 0.718952 -0.427951 0.0372323 0.903035 -0.510154 0.0219404 0.859803 -0.190927 0.0331613 0.981044 -0.0773146 0.00542463 0.996992 0.0434695 0.00130553 0.999054 0.98842 0 0.151741 0.98842 0 0.151741 0.98842 0 0.151741 0.84337 0 0.537333 0.84337 0 0.537333 0.555159 0 0.831744 0.555159 0 0.831744 0.172746 0 0.984966 0.172746 0 0.984966 -0.997448 0 0.071399 -0.969124 0 -0.246574 -0.9782 -0.00322117 -0.20764 -0.999993 0.00353966 0.00145378 -0.987499 -0.0135855 0.157039 -0.376176 0.00867913 -0.926508 -0.706961 0.043753 -0.705898 -0.925289 0.0589652 -0.374651 -0.933 0.0661852 -0.353738 -0.997507 0.0688244 0.015574 -0.997624 0.0678277 0.0120839 -0.459885 0.0266701 -0.887578 -0.433371 0.0315544 -0.900663 -0.664166 0.0582212 -0.745315 -0.726183 0.100414 -0.680129 -0.922093 0.151504 -0.356078 -0.910687 0.134698 -0.39052 -0.981762 0.181696 -0.0559413 -0.98573 0.162604 0.0435585 -0.969837 0.175412 0.169255 0.140024 0.0107406 -0.99009 0.113822 0.0169351 -0.993357 0.506454 0.0440143 -0.861143 0.491343 0.0481657 -0.869633 0.805429 0.0657097 -0.589039 0.790028 0.0722187 -0.608802 0.968659 0.0761864 -0.23642 0.964281 0.0806416 -0.252307 0.953326 0.221014 -0.205723 0.948617 0.211208 -0.235622 0.835965 0.202123 -0.510205 0.7902 0.169672 -0.588893 0.713953 0.167343 -0.679903 0.597779 0.146791 -0.788107 0.497655 0.102917 -0.861247 0.445794 0.102098 -0.889294 0.300048 0.0769906 -0.950812 0.138348 0.021692 -0.990146 0.144453 0.0218268 -0.989271 0.173747 0.00328199 0.984785 0.00511485 0.0355116 0.999356 -0.0254188 0.0326937 0.999142 -0.268241 0.0562494 0.961708 -0.365907 0.0835426 0.926894 -0.453032 0.080156 0.887883 -0.651521 0.0961188 0.752517 -0.696401 0.113517 0.708619 -0.786716 0.111914 0.607086 -0.878106 0.292086 0.378967 -0.907916 0.119281 0.401822 -0.91186 0.117061 0.393457 -0.875638 0.289017 0.386946 -0.665446 0.25242 0.702471 -0.715775 0.238433 0.656365 -0.47879 0.206304 0.853346 -0.353303 0.141253 0.924784 -0.300172 0.134771 0.944316 -0.155981 0.0997658 0.982709 0.00496078 0.0253512 0.999666 -0.0217021 0.029257 0.999336 -0.980676 0.122793 0.152305 -0.990968 0.131661 0.0254484 -0.991908 0.118098 -0.046608 -0.951377 0.109299 -0.287986 -0.738549 0.0797307 -0.669469 -0.507846 0.0337679 -0.860786 -0.417376 0.0384964 -0.907918 -0.289267 0.00575491 -0.957231 -0.725975 0.0724482 -0.683895 -0.711033 0.143263 -0.68841 -0.409166 0.0747343 -0.909394 -0.549469 0.0577779 -0.833514 -0.941625 0.237586 -0.238527 -0.857086 0.224591 -0.463641 -0.758645 0.183732 -0.62506 -0.876406 0.092857 -0.472535 -0.929872 0.116247 -0.349035 -0.893076 0.273709 -0.357069 -0.959052 0.28272 0.0170008 -0.95376 0.294915 0.0580295 0.16586 0.0174247 -0.985995 0.120793 0.0260149 -0.992337 0.521393 0.06748 -0.850644 0.497968 0.0725498 -0.864155 0.808591 0.102763 -0.579328 0.793437 0.107963 -0.599 0.921052 0.29846 -0.250171 0.963358 0.118764 -0.240494 0.960725 0.120994 -0.249737 0.923913 0.307092 -0.228207 0.772183 0.258756 -0.580327 0.799295 0.250759 -0.546121 0.596017 0.207228 -0.775771 0.50265 0.146791 -0.851936 0.443639 0.136608 -0.885733 0.305245 0.0989852 -0.947115 0.16414 0.0244306 -0.986135 0.175326 0.0265124 -0.984153 0.558021 0.152035 0.815781 0.862485 0.113492 0.493192 0.850154 0.105106 0.515937 0.583983 0.0674096 0.808962 0.22267 0.0142073 0.97479 0.265742 0.0317575 0.963521 0.258077 0.0614498 0.964168 0.388451 0.0570852 0.9197 0.605442 0.0777114 0.792087 0.579361 0.180307 0.794878 0.681897 0.16695 0.71214 0.981657 0.12561 0.14343 0.968262 0.102038 0.228159 0.950821 0.302255 0.0676822 0.94963 0.304259 0.0750257 0.9168 0.311413 0.249998 0.823814 0.271108 0.497827 0.868586 0.255563 0.424553 0.777092 0.248278 0.578348 0.961399 0 -0.275157 0.983509 0.0196993 -0.179784 0.321231 0 -0.947001 0.184383 -0.0249597 -0.982538 0.310631 -0.0102469 -0.950475 0.369676 -0.00567454 -0.929143 0.385961 -0.00454206 -0.922504 0.402313 -0.00344507 -0.915496 0.453762 0 -0.891123 0.453762 0 -0.891123 0.703138 0.00575449 -0.71103 0.772301 0.000307139 -0.635257 0.746543 0.0113412 -0.665241 0.79692 0.0185518 -0.603799 0.723961 0.00062651 -0.68984 0.89762 -0.000138086 -0.440771 0.946716 0.00426651 -0.322042 0.644725 0.00257897 -0.76441 0.616039 0.00129785 -0.787715 0.5617 0 -0.827341 0.538673 0.00340663 -0.842508 0.552663 0 -0.833405 0.293435 0 -0.955979 0.233719 -0.0102988 -0.97225 -0.305355 -0.0441144 -0.951216 -0.11879 -0.00451527 -0.992909 0.0822258 0.00196367 -0.996612 -0.187074 -0.000135843 -0.982346 -0.608912 0.000135433 -0.793238 -0.548971 -0.0263461 -0.835426 -0.881384 0 -0.4724 -0.912861 -0.0290744 -0.407233 -0.791017 0.0093453 -0.611723 -0.991487 0 -0.130202 -0.994843 -0.00861141 -0.101064 -0.983305 0.00574915 0.181873 -0.91772 -0.0390296 0.395305 -0.945914 -0.0121555 0.324189 -0.797681 0.0074428 0.603034 -0.723628 -0.0170028 0.68998 -0.635589 0 0.772027 -0.645847 0 0.763467 -0.714128 0.0247595 0.699577 -0.776024 5.69535e-05 0.630704 -0.87942 -5.61176e-05 0.476046 -0.919897 0.0246168 0.391387 -0.95248 0 0.3046 0.949979 0 -0.312314 0.922884 -0.05023 -0.381787 0.871731 0.00157164 -0.489982 0.773014 -0.0020588 -0.634386 0.684283 -0.041977 -0.728007 0.60973 0.000406362 -0.792609 0.28398 -0.000690344 -0.95883 0.312569 -0.0156568 -0.949766 -0.0204613 0.00894564 -0.999751 -0.135728 -0.0101623 -0.990694 -0.262362 0 -0.96497 0.650518 0 0.759491 0.698413 0.0239786 0.715293 0.998055 0 0.0623415 0.994322 0.0172367 0.105012 0.776307 -0.00508941 0.630334 0.884721 0.0100597 0.466013 0.899603 0.0251803 0.435981 0.954482 -0.00360481 0.298245 0.979266 0.0027608 0.202558 0.841511 0 -0.54024 0.879107 0.0253515 -0.47595 0.91147 0.000335132 -0.411366 0.979633 -0.000673179 -0.200795 0.979428 0 -0.201794 -0.111979 0 0.993711 -0.222528 0.0397516 0.974116 -0.330529 -1.72657e-05 0.943796 -0.532206 1.63635e-05 0.846615 -0.623385 0.0425632 0.780756 -0.707364 0 0.706849 -0.989308 0 -0.14584 -0.894034 0.00355943 0.447984 -0.974219 -0.00892629 0.225429 -0.982895 -0.0271966 0.182147 -0.976972 0.0361089 -0.210288 -0.793655 -0.0280937 0.60772 -0.793794 -0.0280017 0.607542 -0.682315 1.47896e-05 0.731059 -0.572908 -3.09338e-05 0.81962 -0.432551 -0.028037 0.901173 -0.454484 -0.0375626 0.889963 0.19027 0.00399233 0.981724 0.00971466 -0.0305071 0.999487 0.0224991 -0.0258119 0.999414 -0.141825 -1.77303e-05 0.989892 -0.308376 9.46125e-06 0.951265 0.421026 -0.00707113 0.907021 0.472714 -0.0253824 0.88085 0.581749 -0.00435719 0.813357 0.775636 0.0101931 0.631098 0.758345 0 0.651853 0.793942 0 0.607993 0.771987 0.0142982 0.635477 0.654082 -0.00420533 0.756412 0.50028 0.018104 0.865674 0.530813 0.0348709 0.846772 0.365716 -0.0080227 0.930692 0.165173 0.013504 0.986172 0.130507 0 0.991447 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.976794 0 0.21418 -0.976795 3.39859e-07 0.214174 -0.976795 0 0.214176 -0.976795 2.87792e-07 0.214176 -0.976795 1.70382e-07 0.214176 0.99848 0 -0.0551185 0.99848 0 -0.0551185 -0.276242 0 -0.961088 -0.23973 0.0302037 -0.97037 -0.18462 -0.00602769 -0.982791 -0.091315 0.00903437 -0.995781 -0.0536808 0.0450523 -0.997541 0.00273521 1.8963e-05 -0.999996 0.335335 0 -0.942099 0.369958 0.0538388 -0.927487 0.281573 -0.00602156 -0.959521 0.152901 0.0150199 -0.988127 0.189505 0.0747615 -0.979029 0.0967983 -1.77629e-05 -0.995304 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0551146 -2.70502e-06 0.99848 0.0551192 0 0.99848 -0.0551214 -1.55329e-06 -0.99848 -0.0551237 0 -0.99848 -0.274057 0 -0.961713 -0.221567 0.0134383 -0.975053 -0.597071 -0.0117231 -0.802103 -0.596027 -0.0114742 -0.802882 -0.733379 -0.000134066 -0.67982 -0.79411 7.37433e-05 -0.607774 -0.905352 -0.00714622 -0.424601 -0.878014 -0.019656 -0.478231 -0.998382 -0.0139794 0.0551135 -0.997418 -0.000653227 -0.0718094 -0.959285 0.000579095 -0.28244 -0.853136 0.00063113 0.521689 -0.747264 -0.0420043 0.663198 -0.842345 -0.014201 0.538752 -0.936266 0.00195589 0.351286 -0.989763 -0.00315448 0.142688 -0.379818 -0.0384258 0.924263 -0.534224 -0.00753893 0.845309 -0.664464 -0.000116771 0.74732 -0.504062 -0.00144978 0.863667 -0.112918 0.00104906 0.993604 -0.11829 0 0.992979 -0.214171 2.39059e-06 -0.976796 -0.214173 3.31405e-07 -0.976796 -0.214175 0 -0.976795 0.214174 -2.61571e-06 0.976795 0.214174 -3.14953e-06 0.976795 0.214177 0 0.976795 0.214174 -1.89855e-06 0.976795 0.214175 -1.04399e-06 0.976795 0.0551188 4.07219e-07 0.99848 0.055119 2.9938e-07 0.99848 0.0551206 0 0.99848 -0.0551162 0 -0.99848 -0.0551184 7.41865e-07 -0.99848 -0.0551172 -2.8008e-06 -0.99848 -0.0669969 0 -0.997753 -0.221591 -0.00152518 -0.975138 -0.199863 -0.00437316 -0.979814 -0.596036 -0.00885066 -0.802909 -0.530864 0.000354758 -0.847457 -0.343343 -8.0206e-05 -0.93921 -0.989412 9.87284e-06 -0.145131 -0.934627 -3.62627e-05 -0.35563 -0.905343 -0.0085521 -0.424595 -0.819015 4.9741e-05 -0.573772 -0.723276 -5.00966e-05 -0.690559 -0.999813 -0.00497749 0.0186636 -0.99844 -0.00890977 0.0551166 -0.969538 0.00152769 0.244935 -0.916303 -0.00152565 0.400482 -0.853103 -0.0090771 0.521664 -0.799424 0.00143809 0.600766 -0.112913 0 0.993605 -0.0736295 -0.0059393 0.997268 -0.240526 0.000282739 0.970643 -0.504059 -0.00143983 0.863668 -0.39092 -0.024444 0.9201 -0.574289 -0.00132446 0.818651 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0551159 0 0.99848 0.055117 -5.85867e-07 0.99848 -0.0551183 -2.15417e-06 -0.99848 -0.0551224 0 -0.99848 -0.130589 0 -0.991437 -0.22158 -0.00775464 -0.975111 -0.286628 -0.000875024 -0.958042 -0.457339 0.000885955 -0.889292 -0.629151 -0.0170084 -0.777097 -0.596032 -0.0100444 -0.802898 -0.732949 -0.000130521 -0.680284 -0.805576 0.000116052 -0.592493 -0.90534 -0.00892644 -0.424594 -0.889949 -0.0146989 -0.455824 -0.998399 -0.01272 0.0551128 -0.999458 -0.00312008 -0.0327669 -0.967625 0.00220316 -0.252384 -0.853139 0.000596588 0.521684 -0.740119 -0.0412488 0.67121 -0.823947 -0.0175415 0.566395 -0.924618 0.00134181 0.380893 -0.985552 -0.00150515 0.169364 -0.112908 0 0.993605 -0.103612 -0.00212551 0.994616 -0.33393 0.000913717 0.942597 -0.504019 -0.0124781 0.863603 -0.51302 -0.0106651 0.85831 -0.64752 -0.0001693 0.762049 0.0551198 0 0.99848 0.0551194 2.35155e-07 0.99848 -0.0551141 1.42224e-06 -0.99848 -0.0551118 0 -0.99848 -0.232686 0 -0.972552 -0.221595 0.00277746 -0.975135 -0.596054 -0.00362434 -0.802936 -0.905309 -0.0122461 -0.424576 -0.859691 0.0053426 -0.510786 -0.587677 -0.00692847 -0.809066 -0.998371 -0.0147876 0.0551112 -0.996696 8.45443e-05 -0.0812195 -0.96629 -5.18043e-05 -0.257455 -0.853137 0.000991669 0.521687 -0.738674 -0.0489767 0.672281 -0.832085 -0.0166847 0.554397 -0.925118 -0.000427186 0.379679 -0.985316 0.000703463 0.17074 -0.112909 0 0.993605 -0.018642 -0.0313522 0.999335 -0.0479326 -0.0234772 0.998575 -0.173714 0.003657 0.984789 -0.362646 -0.00193249 0.931925 -0.504008 -0.0146581 0.863575 -0.529047 -0.00817098 0.848553 -0.66581 -0.000171082 0.746121 -0.214174 0 -0.976796 -0.214171 1.73244e-06 -0.976796 0.214206 -2.53621e-05 0.976788 0.214175 6.53877e-07 0.976795 0.214174 0 0.976796 0.214177 -7.15675e-06 0.976795 0.214176 -5.95791e-06 0.976795 0.214169 2.05697e-06 0.976797 0.214163 7.64545e-06 0.976798 0.214153 1.0788e-05 0.9768 0.214191 6.19042e-06 0.976792 -0.214176 -4.49318e-07 -0.976795 -0.214177 -7.02935e-07 -0.976795 -0.214174 0 -0.976796 0.214175 -2.45113e-06 0.976795 0.21418 0 0.976794 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.214176 -1.83486e-07 -0.976795 -0.214174 8.39538e-07 -0.976796 -0.214176 4.23867e-07 -0.976795 -0.214186 0 -0.976793 0.214177 0 0.976795 0.214175 -4.27169e-07 0.976795 0.214177 1.79803e-06 0.976795 0.0850193 0.000562874 0.996379 0.022569 0.000351646 0.999745 0.0468641 -0.00752684 0.998873 -0.216254 0.00746734 0.976308 -0.371493 -0.00538986 0.92842 -0.468972 0.00344478 0.883207 -0.610591 0.00350772 0.791938 -0.705759 -0.00334001 0.708444 -0.77874 0.00833656 0.627291 -0.9425 -0.00152625 0.334202 -0.927236 0.00555713 0.374437 0.0876041 0.00718516 -0.996129 0.114263 0.00649719 -0.993429 0.264938 0.026959 -0.963889 0.420943 0.0367814 -0.906341 0.49172 0.0358441 -0.870015 0.590092 0.0527571 -0.80561 0.715367 0.0598208 -0.696184 0.790711 0.0590718 -0.609334 0.848213 0.074015 -0.524459 0.973988 0.0728314 -0.214576 0.964434 0.0785821 -0.252374 0.205257 0 -0.978708 0.446124 0.0360061 -0.894247 0.351723 0 -0.936104 0.765245 0 -0.643739 0.765245 0 -0.643739 0.982498 0 -0.186273 0.982498 0 -0.186273 0.947766 0 0.318966 0.947766 0 0.318966 0.669953 0 0.742403 0.669953 0 0.742403 0.220325 0 0.975426 0.220325 0 0.975426 0.0838577 0.0108265 -0.996419 0.30602 0.0344284 0.951402 0.186543 0.011128 0.982384 0.217381 0 0.976087 0.569303 0 0.822128 0.569303 0 0.822128 0.897537 0 0.440939 0.897537 0 0.440939 0.998656 0 -0.0518237 0.998656 0 -0.0518237 0.847074 0 -0.531475 0.847074 0 -0.531475 0.481146 0 -0.87664 0.481146 0 -0.87664 0.197859 0 -0.98023 0.094484 0.00698823 -0.995502 0.142219 0.0108534 -0.989776 0.250469 0.00912688 0.968082 0.127884 0.0191179 -0.991605 0.155191 0.0134188 -0.987793 0.532304 -0.0224827 -0.846255 0.476549 0 -0.879148 0.710555 0 -0.703642 0.844719 -0.0114742 -0.535087 0.871342 0.00382554 -0.49066 0.998466 -0.0042765 -0.0552039 0.998466 -0.0042764 -0.0552042 0.920123 0.00382584 0.39161 0.898559 -0.0114744 0.438703 0.783794 0 0.621021 0.622506 0 0.782615 0.570478 -0.0168502 0.82114 0.239632 0.0155559 0.970739 0.247924 0.0190825 0.968592 -0.992979 0 0.11829 -0.992979 0 0.11829 -1.73888e-06 0.992442 -0.122714 -0.0513143 0.994117 -0.0953793 0.0613545 0.929724 -0.363111 -0.123064 0.951379 -0.28237 0.0409669 0.879936 -0.473322 -0.0616549 0.816805 -0.573609 0.0297767 0.77166 -0.635338 -4.26546e-05 0.723551 -0.690271 -2.77977e-05 0.633467 -0.77377 -0.00174531 0.634301 -0.773085 0.00254824 0.42546 -0.904974 -1.62179e-05 0.0979541 -0.995191 -0.0547202 0.154416 -0.98649 0.0302652 0.289744 -0.956626 -0.0921733 0.471477 -0.877048 -1.62962e-05 0 -1 -1.62962e-05 0 -1 0.897127 0 -0.441773 0.897309 4.12897e-05 -0.441403 0.897141 -1.53259e-05 -0.441744 0.897188 -6.79531e-08 -0.441649 0.897165 -6.51209e-06 -0.441695 0.897531 0.000107791 -0.440951 0.897177 -2.32875e-06 -0.441671 0.897193 2.06792e-06 -0.441639 0.897177 -1.75897e-06 -0.441672 0.897186 0 -0.441653 0.99848 1.25527e-06 -0.0551183 0.99848 -6.27921e-07 -0.0551188 0.99848 -6.40575e-07 -0.0551188 0.99848 0 -0.0551179 0.0184695 0.00035872 0.999829 0.019389 0.000832345 0.999812 0.0161313 0 0.99987 -0.387687 0 0.921791 -0.387687 0 0.921791 -0.730994 0 0.682384 -0.730994 0 0.682384 -0.94624 0 0.323466 -0.94624 0 0.323466 -0.984879 0 0.173245 -0.984879 0 0.173245 -0.939564 0 -0.342374 -0.939564 0 -0.342374 0.804096 0 -0.594499 0.849192 0.058562 -0.524827 0.891341 0 -0.453333 0.954039 0 -0.299682 0.973941 0.0585621 -0.21911 0.990463 0 -0.137778 0.888944 0 -0.458016 -0.97965 0 -0.200712 -0.966372 0.0540664 -0.251398 -0.92659 0 -0.376074 -0.412456 0 -0.910977 -0.549748 0.0324405 -0.8347 -0.549748 0.0324405 -0.8347 -0.674044 0 -0.738691 -0.813038 0 -0.582211 -0.759929 0.112607 -0.640178 -0.869501 0 -0.493932 -0.289877 0 -0.957064 -0.213355 0.0648674 -0.974819 -0.110403 0 -0.993887 0.0204202 0 -0.999792 0.150673 0.0540664 -0.987104 0.202483 0 -0.979286 0.44931 0 -0.893376 0.494778 0.0540663 -0.867336 0.604759 0 -0.796409 0.774139 0 -0.633016 0.816245 0.112607 -0.566625 0.703644 0 -0.710552 0.949206 0.0324405 -0.312979 0.949206 0.0324405 -0.312979 0.987029 0 -0.160543 0.999544 0 -0.030186 0.996723 0.0648674 0.0483185 0.988276 0 0.15268 0.95985 0 0.280514 0.913625 0.0540665 0.402948 0.892562 0 0.450924 -0.785583 0 -0.618756 -0.785583 0 -0.618756 -0.963839 0 -0.266483 -0.963839 0 -0.266483 -0.977613 0 0.21041 -0.976654 0.004385 0.214773 -0.980264 0.00490738 0.19763 -0.977938 0.0368827 0.205616 -0.976347 0.0402736 0.212424 -0.968382 0.0942516 0.230982 -0.939459 0.30276 0.160477 -0.977798 0.120622 0.171352 -0.978814 0.132595 0.15602 -0.946557 0.252337 0.200887 -0.943942 0.251965 0.213277 -0.973113 0.123519 0.194406 0.987842 0.116233 -0.103242 0.989571 0.10639 -0.0971108 0.996776 0.0406151 -0.0692011 0.995605 0 -0.0936538 0.998625 0.0186481 -0.0489953 0.995936 0.0195342 -0.0879206 0.996608 0 -0.0822914 0.998517 0.0403445 -0.0365592 0.990488 0.123166 -0.0613515 0.988043 0.141768 -0.0606109 0.944429 0.311286 -0.105621 0.99848 0 -0.0551181 0.99848 0 -0.0551193 0.99848 0 -0.0551181 0.99848 -4.26722e-07 -0.0551181 0.99848 0 -0.0551169 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.957379 -0.285391 0.0444736 0.6689 -0.719806 -0.185614 -0.971316 -0.233136 0.0468359 0.200551 -0.9787 -0.0438713 -0.0779341 -0.99613 -0.040633 -0.234697 -0.971157 -0.0420872 -0.267818 -0.962955 -0.0314794 -0.30846 -0.950244 -0.0434539 -0.307217 -0.951321 -0.0246195 -0.310862 -0.949661 0.03883 -0.292905 -0.955421 -0.0371192 -0.294313 -0.955011 -0.0365176 -0.252856 -0.966714 -0.0390903 -0.24776 -0.968013 -0.0395679 -0.228851 -0.972641 -0.0399666 -0.427701 -0.903029 -0.0401395 -0.294889 -0.955075 -0.0295323 -0.357058 -0.933282 -0.0386443 -0.324433 -0.945189 -0.0368921 -0.202664 -0.978259 -0.043998 -0.253891 -0.966898 -0.0254496 -0.158072 -0.986642 -0.0393714 -0.154791 -0.987126 -0.0402675 -0.130168 -0.990768 -0.0378862 -0.106557 -0.993589 -0.0377616 0.0400157 -0.997591 -0.056657 0.00957131 -0.998704 -0.0499878 0.00788143 -0.998689 -0.0505803 -0.00399461 -0.998792 -0.0489678 -0.0139193 -0.998749 -0.0480318 -0.017402 -0.9988 -0.0457908 0.114856 -0.990595 -0.0743636 0.109393 -0.991391 -0.071949 0.142192 -0.986883 -0.0764384 0.0899233 -0.993767 -0.0658793 0.0770105 -0.995051 -0.0627941 0.0453178 -0.997381 -0.0563696 0.0600626 -0.996176 -0.0634513 0.0499141 -0.996959 -0.0598404 0.169219 -0.982424 -0.0787954 0.178073 -0.980926 -0.07794 0.191278 -0.978055 -0.0825964 0.167291 -0.982533 -0.0815021 0.202085 -0.975193 -0.090334 0.198334 -0.976002 -0.0899102 0.281811 -0.953642 -0.105592 0.369805 -0.920236 -0.128104 0.191628 -0.978052 -0.0818078 0.251536 -0.963002 -0.0967313 0.179994 -0.98015 -0.0831214 0.220972 -0.970922 -0.0920925 0.269863 -0.958332 -0.0936715 0.309336 -0.946223 -0.094729 0.25853 -0.961094 -0.0972708 0.364518 -0.924793 -0.109015 0.386858 -0.915611 -0.109528 0.500547 -0.854064 -0.14152 0.622135 -0.768188 -0.151116 0.658426 -0.735182 -0.161194 0.816007 -0.545232 -0.191976 0.928054 -0.311232 -0.204574 0.930087 -0.303946 -0.206288 0.82212 -0.536264 -0.191154 0.95456 -0.209697 -0.21176 0.967321 -0.142903 -0.209448 0.965245 -0.153051 -0.211844 0.97529 -0.0587782 -0.212965 0.975166 -0.0521694 -0.215241 0.975145 -0.0498636 -0.215883 0.973031 -0.0745055 -0.21831 0.951477 -0.217924 -0.217256 0.971319 -0.104716 -0.213479 0.971666 -0.102231 -0.213108 0.871649 -0.436466 -0.222993 0.597357 -0.784875 -0.164729 0.686267 -0.699576 -0.199075 0.775208 -0.598255 -0.202836 0.75759 -0.622878 -0.195143 0.788221 -0.579428 -0.207295 0.411996 -0.9069 -0.0882777 0.448511 -0.889484 -0.0875006 0.379687 -0.920459 -0.0926999 0.525314 -0.837815 -0.1487 0.577276 -0.800036 -0.163386 0.0924824 -0.995186 0.0324208 0.144654 -0.989289 0.0195761 0.107092 -0.994098 0.0173239 0.220933 -0.975053 -0.0214395 0.313059 -0.949432 -0.0239344 0.0405662 -0.997393 0.0596829 -0.0115409 -0.9977 0.0667988 -0.017302 -0.997437 0.0694236 -0.0595671 -0.996679 0.0555286 -0.101564 -0.993401 0.0532794 -0.101126 -0.993448 0.0532363 -0.168914 -0.985009 0.0349998 -0.253454 -0.966224 0.0466148 -0.210933 -0.976961 0.032485 -0.324205 -0.945639 0.025645 -0.745257 -0.664863 0.0504795 -0.65449 -0.755797 0.0203157 -0.604634 -0.796376 0.0142645 -0.412038 -0.911164 0.00212653 -0.518413 -0.852344 0.068981 -0.439307 -0.897695 0.0339452 -0.409393 -0.909092 0.0771307 -0.418915 -0.906831 0.0465654 -0.892729 -0.449614 0.0297131 -0.817443 -0.575546 0.0231185 -0.787413 -0.615894 0.0255877 -0.641686 -0.766827 -0.0147091 -0.992778 -0.101215 0.0643956 -0.990065 -0.129532 0.054715 -0.990407 -0.129369 0.0485456 -0.992203 -0.111926 0.0548321 -0.994824 -0.085394 0.0550818 -0.981271 -0.187368 0.044734 -0.928311 -0.370708 0.0285293 -0.935913 -0.351095 0.0282633 -0.816921 -0.576658 0.0102684 -0.834488 -0.550944 0.0094787 -0.681923 -0.731413 -0.00388608 -0.602486 -0.797981 -0.0153608 -0.545314 -0.838073 -0.0163162 -0.37246 -0.92762 -0.0281866 -0.359582 -0.932746 -0.0261765 -0.994829 -0.0853901 0.0549832 -0.992494 -0.111676 0.0498355 -0.980287 -0.191678 0.0479216 -0.973407 -0.22445 0.0458424 -0.973234 -0.224458 0.049335 -0.973366 -0.224288 0.0474641 -0.996745 -0.0618413 0.0517264 -0.996917 -0.0599702 0.0505926 -0.995949 -0.0628988 0.0642617 -0.986703 -0.159803 0.0296609 -0.986199 -0.161564 0.0361846 -0.944149 -0.328545 0.0253285 -0.935317 -0.345726 0.0751986 -0.828571 -0.555175 -0.0724661 -0.571998 -0.586545 0.573396 -0.861487 -0.506833 0.0309972 -0.799452 -0.600678 0.00787788 -0.763804 -0.645387 0.00889435 -0.686818 -0.726818 0.00416828 -0.6272 -0.778815 -0.00818861 -0.576143 -0.817334 -0.00489496 -0.38639 -0.922236 -0.0135644 -0.47806 -0.878206 0.0146004 -0.461077 -0.887285 -0.0115087 -0.442066 -0.896858 -0.0149633 -0.386047 -0.922371 -0.0141278 -0.956073 -0.291372 0.0320461 -0.90225 -0.428922 0.0444088 -0.928244 -0.370811 0.0293513 -0.834315 -0.550978 0.018508 -0.81528 -0.578598 0.0233099 -0.685227 -0.728279 -0.0086259 -0.598646 -0.800998 0.00503421 -0.387452 -0.921036 -0.0396688 -0.382753 -0.923643 -0.0195771 -0.24637 -0.968541 -0.0350721 0.926827 -0.302651 -0.222247 0.831797 -0.511312 -0.216044 0.799133 -0.570705 -0.188898 0.882896 -0.416028 -0.217752 0.933008 -0.281474 -0.224205 0.916625 -0.344399 -0.202947 0.955724 -0.17469 -0.236803 0.949652 -0.232515 -0.209994 0.964804 -0.147532 -0.217687 0.959696 -0.177274 -0.218078 0.957193 -0.189996 -0.218367 0.329323 -0.93638 -0.121406 0.361359 -0.921484 -0.142433 0.205476 -0.97455 -0.0896255 0.520666 -0.84121 -0.145848 0.54518 -0.822839 -0.160358 0.36244 -0.923567 -0.125145 0.935513 -0.257102 -0.242311 0.891705 -0.394065 -0.222653 0.800112 -0.558355 -0.219229 0.795455 -0.565858 -0.216923 0.575594 -0.799013 -0.173983 0.575188 -0.79935 -0.17378 0.435899 -0.888561 -0.143009 0.254219 -0.9634 -0.0850447 0.278021 -0.957118 -0.0814154 0.201933 -0.974363 -0.0991981 0.317634 -0.942074 -0.107722 0.317534 -0.941748 -0.110833 0.545189 -0.822855 -0.160248 0.566996 -0.807599 -0.162168 0.833698 -0.513062 -0.20424 0.806914 -0.553751 -0.205548 0.934701 -0.282489 -0.215719 0.922711 -0.317138 -0.219151 0.960318 -0.176586 -0.215888 0.961666 -0.170239 -0.214981 0.973558 -0.074601 -0.215915 0.975089 -0.0611256 -0.213227 0.928377 -0.302212 -0.216295 0.931223 -0.295101 -0.213867 0.905694 -0.371199 -0.204765 0.924546 -0.301137 -0.233519 0.774152 -0.597656 -0.208559 0.799721 -0.557876 -0.221858 0.594707 -0.782867 -0.182874 0.575574 -0.798963 -0.174277 0.375644 -0.917157 -0.133094 0.329325 -0.938557 -0.103224 0.197939 -0.977223 -0.0765184 0.158899 -0.985932 -0.0518532 0.10239 -0.993898 -0.0410325 0.0752991 -0.996875 -0.0238716 0.0195076 -0.99971 -0.014106 0.301531 -0.946711 -0.113214 0.237078 -0.967509 -0.0878649 0.159339 -0.984533 -0.0728381 0.109564 -0.992523 -0.0537891 0.0754293 -0.996013 -0.0476261 0.0457589 -0.998277 -0.0367198 0.018312 -0.999315 -0.0321575 0.00973122 -0.999575 -0.0274649 -0.0206797 -0.999514 -0.0233212 -0.0101849 -0.999531 -0.028885 -0.0914173 -0.995609 -0.020129 -0.35874 -0.933261 -0.0181489 -0.388433 -0.92137 -0.0140296 -0.253731 -0.966956 -0.024835 -0.312233 -0.949898 -0.0142782 -0.151457 -0.988073 -0.0278095 0.0372836 -0.997583 0.0586284 0.0302112 -0.999521 -0.00668566 -0.0285421 -0.999592 0.00131429 -0.01813 -0.999774 -0.0111404 -0.111811 -0.993728 -0.00169746 -0.0897312 -0.995864 -0.014226 -0.217943 -0.975957 -0.00298499 -0.946945 -0.318517 0.0429172 -0.946731 -0.319239 0.0422763 -0.948385 -0.313967 0.044625 -0.918061 -0.392885 0.0529633 -0.920356 -0.390549 0.020414 -0.0516132 -0.997783 -0.0420115 -0.0676608 -0.996784 -0.042934 -0.063921 -0.997553 -0.0283082 -0.192474 -0.981171 -0.0160398 -0.192643 -0.981128 -0.0166031 -0.31027 -0.950619 -0.00753173 -0.415821 -0.909224 -0.0201271 -0.441465 -0.897189 -0.0126597 -0.639512 -0.768776 0.00287156 -0.625839 -0.77995 -0.00161585 -0.78874 -0.614604 0.0123209 -0.798249 -0.602112 0.0161317 -0.901729 -0.431504 0.0262659 -0.901913 -0.431227 0.0244313 -0.957085 -0.285794 0.0480683 -0.948512 -0.314684 0.0360478 -0.971518 -0.232619 0.0451879 0.930362 -0.302449 -0.207246 0.945694 -0.217379 -0.241679 0.971515 -0.0574658 -0.229904 0.99079 -0.0908239 -0.100428 0.991279 -0.0908098 -0.0954916 0.989137 -0.0218895 -0.145355 0.991267 -0.0207234 -0.130233 0.980219 -0.0206521 -0.196836 0.989272 0.00687079 -0.145924 0.984581 -2.32733e-07 -0.174929 0.947363 -0.319704 0.0171293 0.946892 -0.31833 0.0454081 0.952379 -0.304651 0.0127246 0.878156 -0.448989 -0.16508 0.953042 -0.226655 -0.200844 0.942569 -0.262236 -0.206874 0.974522 -0.0575289 -0.216788 0.968903 -0.104617 -0.224238 0.768727 -0.636021 -0.0673582 0.79037 -0.601402 -0.116751 0.89767 -0.415936 -0.145557 0.896813 -0.415895 -0.150853 0.974686 -0.144138 -0.170915 0.975422 -0.144154 -0.166645 0.975164 -0.0302361 -0.21941 0.827481 -0.560885 -0.0261277 0.824789 -0.562126 -0.0611405 0.965846 -0.242262 -0.0919226 0.966492 -0.24218 -0.0851017 0.982699 -0.0704574 -0.171287 0.983111 -0.0704656 -0.168902 0.984714 -0.0303639 -0.171514 0.981582 -0.0138005 -0.19054 0.205094 -0.964868 0.164213 -0.939608 -0.269301 0.211219 0.908786 -0.413292 0.0574198 0.63206 -0.740003 -0.229991 0.603096 -0.795864 -0.0536264 0.41288 -0.907057 -0.0823301 0.435439 -0.899497 -0.0360296 0.610781 -0.790476 -0.0457624 0.575246 -0.817001 -0.0400309 0.628835 -0.775805 -0.0519 0.699909 -0.713529 0.031698 0.713702 -0.700326 -0.0131748 0.895569 -0.443681 0.0332313 0.898015 -0.389939 0.203756 0.932294 -0.241204 -0.269536 0.983615 -0.134145 0.120449 0.990276 -0.0927816 -0.103655 0.984226 -0.0441646 -0.171317 0.366249 -0.170041 0.914849 0.780978 -0.615757 -0.104483 0.904388 -0.426695 0.00364579 0.419652 -0.898195 0.130911 0.413208 -0.90172 0.127124 0.416795 -0.884073 0.211414 0.24204 -0.964794 0.102902 0.0730653 -0.989718 0.122962 0.174586 -0.9787 0.108009 0.362431 -0.926751 0.0988797 0.242404 -0.964725 0.102691 0.286064 -0.957227 0.0434003 0.0193386 -0.989593 0.14259 0.022744 -0.990196 0.137819 -0.0908291 -0.98465 0.149044 -0.524452 -0.837383 0.154081 -0.385397 -0.911542 0.143385 -0.330491 -0.925961 0.182681 -0.253994 -0.955285 0.151383 -0.101037 -0.984976 0.140048 -0.575468 -0.796235 0.186674 -0.581407 -0.790755 0.191501 -0.66207 -0.736465 0.138864 -0.901661 -0.415125 0.121151 -0.820598 -0.544689 0.173011 -0.821189 -0.543419 0.174195 -0.750486 -0.645512 0.141723 -0.975271 -0.195728 0.102646 -0.975913 -0.105792 0.190795 -0.950709 -0.287215 0.116876 -0.773818 -0.620702 0.126236 -0.735512 -0.659212 0.156403 -0.647677 -0.743336 0.167233 -0.595844 -0.789077 0.149428 -0.600776 -0.784856 0.151883 -0.728449 -0.67173 0.134689 -0.404125 -0.90341 0.143291 -0.417694 -0.896431 0.148133 -0.304612 -0.939842 0.154627 -0.270367 -0.951135 0.149144 -0.236542 -0.958961 0.156336 -0.15158 -0.976767 0.15149 -0.133556 -0.981386 0.138001 -0.0887064 -0.985942 0.141597 -0.0332712 -0.990494 0.133474 -0.0498575 -0.991034 0.123958 0.0457718 -0.991145 0.124649 0.0488107 -0.991379 0.121591 -0.00233985 -0.991075 0.133283 -0.762678 -0.619067 0.187292 -0.848599 -0.447222 0.282617 -0.579469 -0.77608 0.248829 -0.665321 -0.674655 0.31967 -0.389865 -0.877702 0.278647 -0.443216 -0.83837 0.317326 -0.244254 -0.927029 0.284531 0.909346 -0.415196 0.0264923 0.716462 -0.68846 0.112714 0.798548 -0.588147 0.128075 0.603083 -0.782854 0.153068 0.387298 -0.89779 0.209697 0.375048 -0.9014 0.216371 0.228317 -0.946506 0.22803 0.261344 -0.942044 0.210364 0.0925718 -0.970103 0.224347 0.142859 -0.974982 0.170296 0.0382393 -0.982499 0.182302 0.0514229 -0.984588 0.167161 -0.00156093 -0.984636 0.174611 -0.0236227 -0.979331 0.200878 -0.031678 -0.978836 0.202179 -0.114516 -0.960002 0.255504 -0.0913953 -0.961019 0.260938 -0.251109 -0.923749 0.289193 0.368839 -0.923507 0.10532 0.349768 -0.928665 0.123467 0.254674 -0.957811 0.133191 0.253882 -0.957917 0.133939 0.140026 -0.979297 0.146187 0.529789 -0.824783 0.197629 0.525977 -0.849057 0.0494907 0.481771 -0.871204 0.0943386 0.473083 -0.880901 -0.0143484 0.338924 -0.940771 0.00903053 0.319481 -0.947157 0.0287302 0.245028 -0.968203 0.0504472 0.231752 -0.97057 0.0654665 0.175497 -0.98179 0.0727304 0.153971 -0.983603 0.0939036 0.103394 -0.987698 0.117316 0.0182789 -0.989211 0.145354 0.0289317 -0.974295 0.223408 0.0358451 -0.974283 0.222459 0.218664 -0.967989 0.123219 0.224153 -0.958145 0.178085 0.030906 -0.978044 0.206095 0.0322192 -0.975899 0.215829 0.0274066 -0.975914 0.216427 0.530765 -0.843716 0.0801983 0.591475 -0.803623 0.0659362 0.689611 -0.72096 0.068216 0.73571 -0.677297 0.000518319 0.899021 -0.434358 -0.055638 0.908246 -0.412162 -0.0721884 0.980476 -0.15879 -0.115984 0.982177 -0.138847 -0.126692 0.981057 -0.158769 -0.11099 0.982663 -0.171602 -0.0701864 0.901004 -0.433132 -0.0242473 0.876607 -0.481196 0.00331622 0.689297 -0.72213 0.0582959 0.65781 -0.747331 0.0937155 0.420281 -0.896302 0.141448 0.395898 -0.903679 0.163183 0.207815 -0.959202 0.191689 0.196287 -0.959708 0.201077 0.03728 -0.97466 0.220564 -0.967463 -0.212547 0.137256 -0.96907 -0.195754 0.150278 -0.805731 -0.565573 0.175855 -0.81549 -0.543587 0.198719 -0.557365 -0.805295 0.202101 -0.573644 -0.786882 0.227485 -0.302526 -0.929053 0.212929 -0.320106 -0.91752 0.235987 -0.0643852 -0.975596 0.209923 -0.078631 -0.970659 0.227242 0.0386464 -0.976606 0.211535 0.0336041 -0.975492 0.217456 0.0321342 -0.975495 0.217664 0.0226862 -0.98869 0.148248 0.0201769 -0.988781 0.148001 -0.94884 -0.270063 0.163611 -0.954925 -0.22876 0.189173 -0.768684 -0.604301 0.20963 -0.791873 -0.561775 0.23947 -0.51554 -0.823962 0.235171 -0.543705 -0.79731 0.262072 -0.271037 -0.932051 0.240457 -0.293183 -0.920176 0.259462 -0.0525509 -0.971815 0.229812 -0.0602737 -0.969821 0.236252 0.0323278 -0.974389 0.222534 0.0393563 -0.975426 0.216785 0.031983 -0.975448 0.217896 0.0346593 -0.976285 0.213699 0.0257525 -0.97629 0.214929 0.0264747 -0.975095 0.220202 0.0400579 -0.975036 0.218403 0.0296509 -0.989623 0.140598 0.0229947 -0.985755 0.16661 0.972335 -0.220782 -0.076289 0.97507 -0.217813 0.0423803 0.876191 -0.474709 0.0833052 0.798137 -0.58719 0.134853 0.65763 -0.736039 0.160528 0.602027 -0.772869 0.200593 0.398585 -0.889075 0.225115 0.388013 -0.892127 0.23142 0.200715 -0.947668 0.248273 0.228693 -0.945316 0.232543 0.040896 -0.968013 0.247545 0.088841 -0.97694 0.194151 0.0253284 -0.979217 0.201226 0.038677 -0.981872 0.185559 0.027796 -0.981948 0.187099 0.00418781 -0.97648 0.215567 0.0307691 -0.97697 0.211144 -0.0248322 -0.968388 0.248209 -0.0490436 -0.966376 0.252412 -0.0883115 -0.95616 0.27921 -0.257135 -0.916306 0.307026 -0.248539 -0.920648 0.301057 -0.49008 -0.805067 0.334197 -0.447219 -0.841753 0.302402 -0.736366 -0.591576 0.328334 -0.678132 -0.681011 0.276336 -0.85826 -0.427291 0.284275 -0.873062 -0.432205 0.225747 -0.790381 -0.598939 0.128725 -0.906301 -0.41962 0.0503841 -0.995903 0.000585255 0.0904271 -0.994048 -0.101018 0.0407984 -0.998523 -0.00508035 0.0540873 -0.971234 -0.233166 0.0483483 -0.882599 -0.468321 0.0411626 -0.858281 -0.47279 0.199558 -0.870263 -0.478265 0.117924 -0.915937 -0.352391 0.192044 -0.923262 -0.353157 0.151222 -0.959846 -0.268818 0.0802086 -0.944455 -0.237956 0.226673 -0.94589 -0.318933 0.0597918 -0.975824 -0.212532 0.0509779 -0.98814 -0.130497 0.0809301 -0.991544 -0.129451 -0.00908975 -0.995771 -0.0418609 0.081775 -0.998478 -0.0265066 0.0483542 -0.996504 -0.0265731 0.0792028 -0.948193 -0.238309 0.210093 -0.994145 -0.0698535 0.0824369 -0.986531 -0.0693755 0.148136 -0.995497 -0.0248859 0.0914697 -0.992603 -0.0192349 0.119872 -0.995971 -0.000379146 0.0896758 -0.995847 0 0.0910442 0.976795 -3.8023e-06 -0.214175 0.976795 -3.47467e-06 -0.214176 0.976795 -2.30892e-07 -0.214176 0.976798 1.80953e-06 -0.214165 0.976795 -9.19815e-08 -0.214176 0.976795 0 -0.214176 0.976795 0 -0.214175 0.976795 8.11453e-06 -0.214175 0.976795 1.43898e-06 -0.214176 0.976833 -0.001866 -0.213994 0.977649 -8.41011e-07 -0.210243 0.988841 -3.68517e-06 -0.148972 0.992274 0.0694544 -0.102801 0.992791 -0.112322 0.0418278 0.995724 0.000558874 0.0923756 0.978877 0.000558539 0.204452 0.97911 2.04768e-06 0.203331 0.96837 0.000510524 0.249516 0.930237 -0.0584159 0.362279 0.910873 -3.02293e-05 0.412687 0.910869 2.07138e-06 0.412696 0.910869 2.15582e-06 0.412696 0.930585 -0.0642332 0.360397 0.972387 -2.67996e-05 0.233375 0.930093 1.21893e-05 0.367324 0.93014 6.11922e-05 0.367205 0.91088 -1.16733e-05 0.412671 0.910869 -4.55543e-05 0.412697 0.963892 0.0264334 0.264978 0.994251 -0.0200335 0.105182 0.998178 0.00479667 0.0601511 0.99995 -8.78311e-05 -0.00997853 0.996735 -8.92594e-05 -0.0807422 0.99311 -0.0169849 -0.115948 0.964879 0.0241158 -0.261585 0.955144 -8.59653e-06 -0.296142 0.918793 -8.79743e-06 -0.394739 0.918252 -0.000198471 -0.395996 0.845171 0.00152109 -0.534494 0.868042 0.0515993 -0.493802 0.744516 -0.0281626 -0.66701 0.776691 -6.66886e-05 -0.629882 0.705212 -6.64719e-05 -0.708996 0.644002 0.0206907 -0.764744 0.600355 -0.0151204 -0.799591 0.492972 0.00790582 -0.870009 0.473198 -5.80912e-05 -0.880956 0.366068 -5.81086e-05 -0.930588 0.376873 0.00644957 -0.926242 0.218315 -0.00875504 -0.975839 0.189592 0.0126246 -0.981782 0.0966485 -4.78761e-05 -0.995319 0.04961 -4.80242e-05 -0.998769 -0.0100784 -0.0135468 -0.999857 -0.133709 0.0436484 -0.990059 -0.192506 -4.40658e-05 -0.981296 -0.295474 -4.38124e-05 -0.955351 -0.403898 0.00980522 -0.914751 -0.405529 0.00821583 -0.914045 -0.564704 -0.00529937 -0.825276 -0.556236 -3.57619e-05 -0.831024 -0.637238 -3.57213e-05 -0.770667 -0.673033 0.01256 -0.739506 -0.736577 -0.0204822 -0.676043 -0.766723 0.00276435 -0.641972 -0.773018 2.50722e-06 -0.634384 -0.773018 3.7427e-07 -0.634384 -0.773019 1.2175e-06 -0.634383 -0.773018 -6.07099e-07 -0.634384 -0.776837 0.00523306 -0.62968 -0.775461 0.00949861 -0.631324 -0.806359 -0.000103556 -0.591426 -0.857892 -8.10875e-05 -0.51383 -0.844739 0.0356986 -0.533987 -0.916873 -0.0291343 -0.398115 -0.908529 -2.82268e-05 -0.417822 -0.93647 -1.92238e-05 -0.350747 -0.948397 0.00362397 -0.317065 -0.959717 0.0423245 -0.277761 -0.968869 0.00519716 -0.247521 -0.987905 -0.00563675 -0.154961 -0.99848 0 0.0551185 -0.99848 0 0.0551185 -0.99848 3.8272e-07 0.0551188 -0.99848 2.32928e-08 0.0551186 -0.99848 1.62483e-07 0.0551187 -0.99848 1.45013e-07 0.0551187 -0.99848 -3.18215e-07 0.0551184 -0.99848 -2.46955e-07 0.0551184 -0.987341 -5.87341e-05 -0.158614 -0.995924 -4.26361e-05 -0.0901918 -0.998174 0.0535961 -0.0278771 -0.999205 -0.0393639 0.00633192 -0.99848 1.00295e-05 0.0551127 -0.99848 -1.44398e-07 0.055119 -0.99848 -7.89831e-07 0.0551183 -0.99848 -1.52583e-06 0.0551189 -0.99848 4.18106e-07 0.0551192 -0.99848 -2.4078e-07 0.0551184 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.00034037 -1 0.000369803 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.000142146 -1 -0.000269527 -5.30094e-05 -1 2.29907e-06 3.11031e-06 -1 9.61813e-05 0 -1 0 0 -1 0 -0.27294 -0.961697 0.025347 -0.991103 -0.118755 0.0600983 -0.881659 -0.46852 0.0562717 -0.907958 -0.41437 0.0625354 -0.942693 -0.329915 0.0498652 -0.956005 -0.286594 0.0626052 -0.992937 -0.105601 0.0540723 -0.610393 -0.791626 0.0273564 -0.673584 -0.736893 0.0572059 -0.781999 -0.622117 0.0380554 -0.76473 -0.643925 0.0234246 -0.836788 -0.543774 0.0639959 -0.403141 -0.914827 0.0238325 -0.541221 -0.83979 0.0428122 -0.599466 -0.799814 0.0306302 -0.445671 -0.893133 0.0607443 -0.385638 -0.921843 0.0385858 -0.348143 -0.936928 0.0310327 -0.119476 -0.992766 0.0118715 -0.159952 -0.987117 0.00403357 -0.143672 -0.989307 0.0251042 -0.135059 -0.99065 0.0192786 -0.134595 -0.990523 0.0273625 -0.125432 -0.991925 0.0187295 -0.12768 -0.991692 0.0156828 -0.122674 -0.992431 0.00557781 -0.121415 -0.992594 -0.00396341 -0.111126 -0.993753 -0.0102943 -0.114175 -0.993204 -0.0225914 -0.107388 -0.993848 -0.0270829 -0.104623 -0.984031 -0.144001 -0.142969 -0.983265 -0.112917 -0.133369 -0.984921 -0.110202 -0.135105 -0.987013 -0.0868977 -0.101813 -0.992225 -0.0715751 -0.108383 -0.991725 -0.0688129 -0.0881259 -0.994248 -0.0608746 -0.0921869 -0.994171 -0.0559131 -0.0924951 -0.994142 -0.0559143 -0.0979879 -0.994401 -0.0395718 -0.0329591 -0.982259 -0.184611 -0.0647604 -0.982734 -0.173321 -0.0801669 -0.982224 -0.169732 -0.0831706 -0.984253 -0.155978 -0.121775 -0.981221 -0.14959 -0.0390583 -0.988403 -0.146747 -0.0172549 -0.982615 -0.184854 0.00531994 -0.982709 -0.185083 0.0141678 -0.981595 -0.190447 0.0340322 -0.984632 -0.171294 0.0443823 -0.982614 -0.18028 0.0737505 -0.982614 -0.170384 0.0737572 -0.982613 -0.170388 0.101104 -0.982613 -0.155721 0.101107 -0.982613 -0.155722 0.132314 -0.982447 -0.131496 0.114765 -0.985499 -0.124982 0.150786 -0.981602 -0.117141 0.151248 -0.982706 -0.106833 0.171174 -0.982298 -0.0760915 0.186129 -0.9825 0.00699114 0.183412 -0.982607 -0.0290501 0.183394 -0.982611 -0.029032 0.179237 -0.982733 -0.0459398 0.177587 -0.982266 -0.0601433 0.137245 -0.98778 -0.0738612 0.186484 -0.981299 0.0477016 0.184401 -0.982444 0.0282948 0.186374 -0.982455 0.00682464 0.183096 -0.982113 0.0439327 0.173591 -0.981607 0.0794588 0.16667 -0.982652 0.0813457 0.154059 -0.984392 0.0850739 0.159502 -0.982429 0.0969187 0.155373 -0.983255 0.0952307 0.167739 -0.981079 0.0966841 0.128809 -0.991654 -0.00558655 0.0558411 -0.998413 -0.00728252 0.118618 -0.991577 -0.0520146 0.155916 -0.987019 -0.0385279 0.224944 -0.973653 -0.0374305 0.358565 -0.932814 -0.0358972 0.135471 -0.990707 -0.012142 0.136842 -0.990577 -0.00566247 0.15212 -0.988357 0.00302763 0.162403 -0.986709 -0.00547977 0.175187 -0.984416 0.0152936 0.171708 -0.984992 0.0175359 0.169913 -0.984645 0.0400579 0.166229 -0.984837 0.0496371 0.171336 -0.983559 0.0570575 0.164141 -0.983029 0.0819241 0.273227 -0.960255 -0.0570748 0.290246 -0.955719 -0.0485567 0.321236 -0.94467 -0.0663838 0.35622 -0.924816 -0.133503 0.985436 -0.136844 0.100939 0.994825 0.0194854 -0.09972 0.97805 -0.208246 -0.00720543 0.97674 -0.0588869 -0.206182 0.978124 -0.0699422 -0.195912 0.971536 -0.114707 -0.207266 0.970079 -0.132544 -0.203417 0.978967 -0.00790255 0.203866 0.982117 -0.0493007 0.181703 0.9628 -0.0903305 0.254668 0.914863 -0.0896091 0.393695 0.933595 0.070648 0.351295 0.903721 -0.0880346 0.418973 0.903562 -0.0823326 0.420473 0.903916 -0.0803336 0.420099 0.663508 -0.193726 -0.722653 0.764487 -0.176576 -0.619985 0.772762 -0.206008 -0.600332 0.857924 -0.160549 -0.488047 0.863242 -0.197219 -0.464671 0.902717 -0.183168 -0.389297 0.927788 -0.201282 -0.314157 -0.0928313 -0.0635176 -0.993654 0.0938149 -0.24035 -0.966142 0.0725259 -0.212537 -0.974458 0.215985 -0.145948 -0.965427 0.234942 -0.183361 -0.954558 0.37034 -0.185491 -0.910187 0.388125 -0.213101 -0.896631 0.465963 -0.174188 -0.867489 0.53203 -0.213113 -0.819467 0.595572 -0.12686 -0.793222 0.681666 -0.256245 -0.685325 -0.411172 -0.149606 -0.899197 -0.289846 -0.194262 -0.937151 -0.250937 -0.216341 -0.943519 -0.19064 -0.138926 -0.97178 -0.00966941 -0.28259 -0.959192 -0.761392 -0.206037 -0.614679 -0.714372 -0.244499 -0.655662 -0.712004 -0.250175 -0.656097 -0.625965 -0.187264 -0.757033 -0.550289 -0.207531 -0.808772 -0.545424 -0.196216 -0.814869 -0.399409 -0.173268 -0.90025 -0.766688 -0.127935 -0.629144 -0.765323 -0.156222 -0.6244 -0.772902 -0.122885 -0.622513 -0.773648 -0.228929 -0.590813 -0.801796 -0.17003 -0.572898 -0.86578 -0.0869466 -0.492813 -0.816436 -0.322486 -0.478994 -0.90962 -0.0646266 -0.410384 -0.910962 -0.256285 -0.323211 -0.922341 -0.221513 -0.316575 -0.955695 -0.235398 -0.176735 -0.96362 -0.143008 -0.2258 -0.944338 -0.14325 -0.296151 -0.946246 -0.319838 0.0481901 -0.98534 -0.156866 -0.0670684 -0.983742 -0.108938 -0.142776 -0.998533 0.00667753 -0.0537334 -0.988442 -0.134209 0.0704999 -0.989982 -0.120435 0.0737033 -0.989974 -0.120569 0.073583 -0.992741 -0.101869 0.0639373 -0.994119 -0.0861751 0.0655771 -0.99143 -0.108291 0.0730768 -0.99203 -0.104506 0.0703928 -0.332904 -0.942277 0.0359083 -0.348797 -0.937099 0.0136333 -0.360366 -0.931585 0.0478093 -0.348142 -0.936171 0.0488047 -0.347899 -0.936062 0.0524749 -0.330397 -0.942066 0.0578794 -0.331667 -0.943163 0.0209817 -0.320723 -0.946819 0.0258875 -0.314135 -0.948948 -0.0285718 -0.304608 -0.952205 -0.0228159 -0.290117 -0.954169 -0.0734406 -0.283339 -0.956598 -0.0681136 -0.244944 -0.95801 -0.149062 -0.663795 -0.742492 0.089901 -0.6415 -0.760679 0.0992287 -0.645607 -0.76335 0.0220932 -0.6294 -0.776482 0.0305072 -0.619244 -0.781546 -0.0756439 -0.604447 -0.793934 -0.0656691 -0.578009 -0.798786 -0.166872 -0.566722 -0.808774 -0.157197 -0.506351 -0.81245 -0.289021 -0.592423 -0.800935 0.0868198 -0.768788 -0.635004 0.0757228 -0.65941 -0.740178 0.131582 -0.812364 -0.575275 0.0955143 -0.812162 -0.575213 0.0975875 -0.794986 -0.597103 0.10708 -0.800347 -0.599415 0.0120736 -0.78675 -0.616924 0.0206913 -0.77537 -0.621793 -0.110337 -0.762637 -0.639003 -0.100298 -0.730746 -0.643817 -0.226959 -0.720677 -0.658378 -0.217171 -0.669802 -0.662816 -0.334725 -0.934816 -0.341094 0.0988651 -0.927154 -0.359571 0.105332 -0.928563 -0.359812 0.0911336 -0.920374 -0.378417 0.0985506 -0.925216 -0.379355 -0.00810738 -0.918289 -0.395907 -0.0013287 -0.904548 -0.398647 -0.151243 -0.898118 -0.415596 -0.143753 -0.860712 -0.418389 -0.290043 -0.855601 -0.433439 -0.282979 -0.794856 -0.436054 -0.421972 -0.792447 -0.444189 -0.417999 -0.718551 -0.446535 -0.533189 -0.719709 -0.441981 -0.535417 -0.699341 -0.442364 -0.561459 -0.717653 -0.379886 -0.583662 -0.705046 -0.379842 -0.598857 -0.766666 -0.127936 -0.62917 0.658861 -0.745445 -0.101064 0.694301 -0.713799 -0.0918513 0.69365 -0.713951 -0.0955163 0.731525 -0.676327 -0.0863322 0.740411 -0.671612 0.0270111 0.753335 -0.656599 0.036931 0.73778 -0.65225 0.173928 0.746722 -0.639189 0.18397 0.696742 -0.63386 0.335814 0.706219 -0.618257 0.344984 0.694386 -0.617652 0.369234 0.699763 -0.609436 0.37272 0.703885 -0.609696 0.36444 0.942421 -0.162585 -0.292247 0.969607 -0.217694 -0.11168 0.980685 -0.116674 -0.156986 0.978268 -0.207301 -0.00416325 0.975205 -0.220867 0.0139297 0.986001 -0.125673 0.109587 0.960382 -0.211353 0.18165 0.947165 -0.163893 0.275714 0.914527 -0.213837 0.343385 0.90835 -0.181731 0.376661 0.888024 -0.179476 0.423322 0.879941 -0.258307 0.398725 0.868023 -0.258205 0.424107 0.86679 -0.263416 0.423423 0.88024 -0.263517 0.394636 0.87821 -0.274816 0.391437 0.941345 -0.276647 0.193224 0.939221 -0.287455 0.187707 0.957412 -0.28869 0.00463918 0.953422 -0.301637 -0.00157577 0.938261 -0.303306 -0.166348 0.926641 -0.334437 -0.171721 0.925732 -0.334482 -0.176468 0.914103 -0.362474 -0.181739 -0.472441 -0.878833 0.0667277 -0.505216 -0.860473 0.0659048 -0.504655 -0.860209 0.0732407 -0.482697 -0.872036 0.0809713 -0.485189 -0.874075 0.0241719 -0.470457 -0.881874 0.0311351 -0.461756 -0.885668 -0.0487174 -0.448665 -0.892783 -0.0404791 -0.428049 -0.896335 -0.115578 -0.418429 -0.901835 -0.107755 -0.387671 -0.904987 -0.175245 -0.590672 -0.753712 -0.28814 -0.535682 -0.757413 -0.373323 -0.538239 -0.752587 -0.379357 -0.52413 -0.753222 -0.397422 -0.565213 -0.690255 -0.451755 -0.574893 -0.690072 -0.439658 -0.622741 -0.599534 -0.502745 -0.599486 -0.59928 -0.530546 -0.609927 -0.558664 -0.562035 -0.472837 -0.561943 -0.678708 -0.469729 -0.550221 -0.690371 -0.350537 -0.550484 -0.757688 -0.348484 -0.54567 -0.762104 -0.215433 -0.545714 -0.809805 -0.215391 -0.545641 -0.809866 -0.0779303 -0.545626 -0.834397 -0.0779509 -0.545656 -0.834376 0.0621906 -0.54566 -0.835696 0.0621987 -0.545651 -0.835701 0.2003 -0.54563 -0.813737 0.20028 -0.545653 -0.813727 0.332901 -0.545658 -0.769048 0.332897 -0.545661 -0.769047 0.456339 -0.545637 -0.702876 0.456334 -0.545642 -0.702875 0.566778 -0.545644 -0.61728 0.56676 -0.545662 -0.617281 0.661785 -0.54564 -0.514118 0.661786 -0.545639 -0.514118 0.737922 -0.545636 -0.397181 0.737887 -0.545673 -0.397194 0.793726 -0.545671 -0.268778 0.793731 -0.545666 -0.268775 0.827556 -0.545658 -0.131942 0.827641 -0.545547 -0.131869 0.838223 -0.545035 0.0178646 0.839169 -0.543538 0.0190079 0.823239 -0.542109 0.16851 0.82444 -0.539604 0.170663 0.783002 -0.53733 0.313343 0.783734 -0.534948 0.315582 0.759846 -0.535155 0.369112 0.80262 -0.438356 0.404531 0.80038 -0.438268 0.40904 0.797175 -0.445881 0.407065 0.81052 -0.446244 0.379372 0.804776 -0.461807 0.372921 0.86328 -0.465682 0.19465 0.857493 -0.479721 0.18594 0.875468 -0.482719 0.0231998 0.866341 -0.499256 0.0140372 0.854845 -0.502803 -0.128176 0.828404 -0.543375 -0.135979 0.828385 -0.543377 -0.136088 0.802767 -0.57871 -0.143735 -0.101705 -0.994051 -0.038973 -0.321134 -0.93639 -0.141584 -0.290583 -0.938382 -0.187083 -0.293187 -0.936423 -0.192752 -0.287408 -0.936703 -0.199958 -0.326325 -0.912626 -0.246223 -0.334967 -0.912329 -0.235483 -0.393536 -0.868649 -0.300963 -0.381749 -0.868773 -0.315438 -0.401854 -0.84382 -0.355642 -0.312523 -0.846937 -0.430149 -0.311084 -0.838951 -0.446528 -0.232042 -0.83952 -0.491288 -0.23031 -0.836144 -0.497816 -0.141029 -0.836273 -0.529866 -0.140986 -0.836221 -0.529961 -0.0509688 -0.836211 -0.546034 -0.0509945 -0.836234 -0.545996 0.0406821 -0.836238 -0.546856 0.040697 -0.836227 -0.546872 0.131095 -0.836213 -0.532506 0.131071 -0.836228 -0.532488 0.217846 -0.836231 -0.503251 0.217844 -0.836232 -0.50325 0.298638 -0.836216 -0.459954 0.29862 -0.836226 -0.459949 0.370906 -0.836226 -0.403926 0.370875 -0.836241 -0.403921 0.43306 -0.836225 -0.336432 0.433063 -0.836224 -0.336432 0.482904 -0.83622 -0.259885 0.482857 -0.836244 -0.259894 0.519385 -0.836242 -0.175893 0.519396 -0.836236 -0.175888 0.541591 -0.836222 -0.0860942 0.541683 -0.836168 -0.0860401 0.549048 -0.835648 0.0154626 0.550079 -0.834953 0.0163538 0.539691 -0.83345 0.118722 0.540957 -0.832399 0.120323 0.513216 -0.829929 0.218695 0.513806 -0.829259 0.219849 0.492509 -0.828684 0.265929 0.497978 -0.823333 0.272288 0.493717 -0.822952 0.281058 0.487318 -0.828649 0.275432 0.494599 -0.829225 0.260303 0.484928 -0.838933 0.247054 0.516764 -0.843556 0.146179 0.508542 -0.850735 0.132796 0.51751 -0.854454 0.045742 0.505116 -0.862462 0.0318873 0.499921 -0.865705 -0.025188 0.459834 -0.886801 -0.0462197 0.463378 -0.885735 -0.0274806 0.426092 -0.903322 -0.0495543 0.419233 -0.904115 -0.0825888 0.66495 -0.743892 -0.0668248 0.519138 -0.845194 -0.127059 0.81165 -0.57693 -0.0915203 0.725293 -0.673911 -0.14069 0.914761 -0.362449 -0.178446 0.89545 -0.403914 -0.187146 0.969986 -0.134599 -0.202509 0.967467 -0.143395 -0.208437 0.704507 -0.121898 -0.69915 -0.730949 -0.66278 0.162591 0.232889 -0.962481 -0.139256 0.191902 -0.977807 -0.0840704 0.972112 -0.0737017 -0.222634 -0.614159 -0.784059 0.0897742 -0.429574 -0.862673 0.266948 -0.710918 -0.677154 0.18989 -0.752226 -0.609756 0.249706 -0.722038 -0.625209 0.296269 -0.745373 -0.613482 0.260881 -0.936601 -0.308564 0.166036 -0.867906 -0.36415 0.337837 -0.972481 -0.16827 0.16114 -0.972074 -0.168831 0.162995 -0.996315 -0.0777432 -0.0362223 -0.996274 -0.0805478 -0.0308142 -0.996402 -0.0827819 -0.0181794 -0.982119 -0.0957807 0.162074 -0.998195 -0.0582782 0.0145307 -0.997104 -0.0623643 0.0435164 -0.978054 -0.151444 -0.143088 -0.977442 -0.148246 -0.150436 -0.944594 -0.325961 0.0386159 -0.917382 -0.244388 -0.314143 -0.858288 -0.464401 -0.21834 -0.915462 -0.229856 -0.330296 -0.915512 -0.236761 -0.325242 -0.711053 -0.514082 -0.479713 -0.73427 -0.33336 -0.59137 -0.786956 -0.499278 -0.362521 -0.802027 -0.310792 -0.51006 -0.804229 -0.318213 -0.501952 -0.555962 -0.317115 -0.768339 -0.557185 -0.325583 -0.763898 -0.555196 -0.284664 -0.781488 -0.508553 -0.403794 -0.760476 -0.486153 -0.248667 -0.837747 -0.484902 -0.193527 -0.852887 -0.460265 -0.139198 -0.876801 0.935431 -0.319407 -0.151482 0.793798 -0.601385 -0.0906758 0.806348 -0.589106 -0.0525027 0.576861 -0.816708 -0.0148046 0.364103 -0.929585 -0.057447 0.232539 -0.962688 -0.138408 0.260549 -0.960073 -0.10185 0.193733 -0.974308 -0.114853 0.198161 -0.974282 -0.10727 0.33624 -0.917485 -0.212518 0.315727 -0.934175 -0.166235 0.232299 -0.962621 -0.139278 0.258493 -0.929834 -0.261897 0.270597 -0.921694 -0.277953 0.282803 -0.934716 -0.21524 0.281477 -0.93759 -0.204194 0.283936 -0.936326 -0.206577 0.313499 -0.932693 -0.178331 0.315147 -0.93303 -0.173601 0.327763 -0.697657 -0.63706 0.291791 -0.777646 -0.556888 0.18919 -0.792727 -0.579476 0.263927 -0.915492 -0.303673 0.264588 -0.89059 -0.369921 0.25437 -0.901165 -0.350995 0.342217 -0.783159 -0.519182 0.282743 -0.838298 -0.466169 0.377683 -0.525476 -0.762385 0.314096 -0.223493 -0.922711 0.370216 -0.0366759 -0.928221 0.345724 -0.503712 -0.791675 0.415617 -0.24713 -0.875322 0.489371 -0.238301 -0.838885 -0.051534 -0.463569 -0.884561 0.0029246 0.063157 -0.997999 0.0509767 -0.480736 -0.875382 0.0968478 0.0258693 -0.994963 0.125975 -0.166659 -0.977934 0.185193 -0.222701 -0.957135 0.160312 -0.690601 -0.705245 0.264697 -0.182135 -0.946976 0.309267 -0.178174 -0.934135 -0.222736 -0.310058 -0.924258 -0.183862 0.0399038 -0.982142 -0.148298 -0.28858 -0.945901 -0.123337 -0.161202 -0.979184 -0.0764978 -0.206174 -0.975521 -0.301504 -0.212761 -0.929424 -0.296826 -0.156134 -0.942081 -0.251108 -0.151248 -0.956069 -0.308029 -0.544681 -0.780026 -0.345386 -0.525982 -0.777207 -0.457261 -0.412935 -0.787653 -0.311459 -0.432614 -0.846072 -0.331631 -0.379174 -0.863856 -0.60058 -0.496781 -0.626508 -0.578909 -0.500003 -0.644097 -0.66322 -0.327505 -0.672963 -0.551342 -0.783388 -0.286923 -0.495313 -0.868083 0.0331333 -0.600635 -0.7593 0.250401 -0.721578 -0.6894 0.0636622 -0.719984 -0.684383 0.115076 -0.449085 -0.887631 0.10215 -0.38695 -0.921736 0.0259264 -0.315757 -0.948536 -0.0240028 -0.32227 -0.946639 0.00414629 -0.244912 -0.969524 -0.00646181 -0.244033 -0.969709 -0.0105714 -0.229431 -0.97301 -0.0247657 0.946345 -0.108447 -0.304419 0.946879 -0.110987 -0.30183 0.946273 -0.108102 -0.304764 0.945956 -0.106272 -0.306387 0.940259 -0.248434 -0.232795 0.855042 -0.357323 -0.375798 0.863684 -0.440958 -0.244145 0.950994 -0.224208 -0.212935 0.961175 -0.252362 -0.111611 0.969355 -0.175401 -0.172004 0.964568 -0.169361 -0.202301 0.986901 -0.0725089 -0.144112 0.974831 -0.0586438 -0.215093 0.965855 -0.0735239 -0.248432 0.96342 -0.0710813 -0.258399 0.979195 -0.137866 -0.148899 0.948942 -0.113413 -0.294357 0.948289 -0.112847 -0.296672 -0.890382 -0.398611 0.21984 -0.784223 -0.539348 0.306754 -0.857103 -0.512407 0.0530407 -0.713947 -0.692744 0.101909 -0.748768 -0.662006 0.0330782 -0.958206 -0.258267 0.123038 -0.885574 -0.4227 0.192573 -0.92359 -0.37728 -0.0681278 -0.814558 -0.57744 -0.0553124 -0.817624 -0.480076 -0.317834 -0.749406 -0.625176 -0.218048 -0.76721 -0.490979 -0.412708 -0.63683 -0.740164 -0.215884 -0.649545 -0.709254 -0.273952 -0.978702 -0.153749 -0.136027 -0.964533 -0.19359 0.179439 -0.958789 -0.257857 0.119306 -0.90784 -0.178582 0.379389 -0.895379 -0.397042 0.201627 -0.837981 -0.319904 0.442097 -0.734331 -0.661687 0.151422 -0.708765 -0.610653 0.353208 -0.482266 -0.875194 0.0381411 -0.485246 -0.86475 0.129401 -0.350358 -0.93595 0.035312 -0.314459 -0.949271 -5.55143e-05 -0.490317 -0.700712 -0.518258 -0.493916 -0.686679 -0.533403 -0.486683 -0.40454 -0.774266 -0.388168 -0.586809 -0.71062 -0.41087 -0.193043 -0.891022 -0.333209 -0.390123 -0.858356 -0.378514 -0.207694 -0.901993 -0.351803 -0.167837 -0.920905 -0.302876 -0.209142 -0.929799 0.462139 -0.363477 -0.808896 0.563059 -0.116955 -0.818099 0.566245 -0.166729 -0.807198 0.612695 -0.162525 -0.773428 0.619574 -0.19358 -0.760694 0.682713 -0.180281 -0.708097 0.718833 -0.353781 -0.59843 0.704713 -0.240723 -0.667407 0.703761 -0.216686 -0.676585 0.808198 -0.270836 -0.522938 0.80497 -0.258489 -0.534047 0.76787 -0.401342 -0.4993 0.746764 -0.280246 -0.603162 0.74527 -0.253394 -0.616737 0.871179 -0.23184 -0.432779 0.868649 -0.225892 -0.440933 0.888166 -0.315912 -0.333708 0.811961 -0.281179 -0.511524 0.808711 -0.272502 -0.521276 0.570648 -0.586711 -0.57457 0.487647 -0.790634 -0.370268 0.613517 -0.665101 -0.425721 0.558442 -0.78939 -0.254962 0.674498 -0.666785 -0.316938 0.634368 -0.756062 -0.161081 0.779413 -0.595813 -0.193705 0.77808 -0.601246 -0.181922 0.52345 -0.826983 -0.205182 0.5255 -0.824175 -0.211155 0.397654 -0.900691 -0.175007 0.453396 -0.838789 -0.30144 0.365566 -0.895999 -0.252086 0.433286 -0.810484 -0.394182 0.345808 -0.871714 -0.347178 0.437497 -0.731149 -0.523468 0.406724 -0.766924 -0.49639 0.35175 -0.600583 -0.718034 0.344169 -0.613151 -0.711051 0.398883 -0.600666 -0.692887 0.417461 -0.558434 -0.716853 0.488269 -0.542907 -0.683261 0.536667 -0.413714 -0.735411 0.622758 -0.394011 -0.675964 0.573548 -0.585684 -0.572727 0.681199 -0.372566 -0.630208 0.63164 -0.6555 -0.413945 0.753172 -0.412209 -0.512655 0.731734 -0.623224 -0.275966 0.808668 -0.455878 -0.371795 0.798525 -0.574846 -0.178631 0.915559 -0.358939 -0.181423 0.915534 -0.396391 -0.0683493 0.939336 -0.310818 -0.145051 0.940393 -0.316424 -0.124644 0.974608 -0.161824 -0.154768 0.840238 0.516971 -0.163528 0.930078 0.333812 -0.153378 -0.54002 0.841097 0.0305606 -0.779285 0.623905 0.0588023 -0.672893 0.739056 0.031796 -0.433418 0.901041 0.0165822 -0.608772 0.792893 0.0268093 -0.306518 0.945203 0.112422 0.950242 0.184455 0.251031 0.957885 0.259051 0.123889 0.965023 0.223927 0.136334 0.978997 0.203522 0.0120103 0.985195 0.170175 0.0207671 0.968362 0.225465 -0.106956 0.976453 0.192191 -0.0979861 0.95871 0.182952 -0.217725 0.945899 0.230289 -0.228564 0.89636 0.270608 0.351156 0.905079 0.248524 0.345061 0.945055 0.222854 0.239182 0.810301 0.179541 0.557833 0.788876 0.135357 0.59946 0.749603 0.143831 0.646072 0.749529 0.133676 0.648334 0.676165 0.148683 0.721591 0.67587 0.138974 0.7238 0.595944 0.155154 0.787894 0.595415 0.145253 0.790179 0.509731 0.160053 0.845315 0.503035 0.0883645 0.859737 0.414904 0.214199 0.884292 0.407291 0.161614 0.898885 0.323991 0.174018 0.929918 0.303991 0.0354619 0.952015 0.223249 0.243554 0.943844 0.129177 -0.0251459 0.991303 0.152034 0.178371 0.972147 0.0380738 0.193086 0.980443 0.0269611 0.236674 0.971215 -0.0120338 0.193718 0.980983 -0.0726266 0.200657 0.976966 -0.0735903 0.196174 0.977804 -0.170928 0.207016 0.96329 -0.172078 0.202137 0.964121 -0.223002 0.20769 0.952436 -0.266654 0.22438 0.93731 -0.270879 0.208654 0.939728 -0.360659 0.217402 0.907007 -0.383528 0.126875 0.914773 -0.443605 0.27527 0.852902 -0.520777 0.0591432 0.851642 -0.701711 0.11486 0.703142 -0.587197 0.308021 0.748547 -0.61396 0.229401 0.755267 -0.535151 0.223556 0.814639 -0.861247 0.239888 0.448003 -0.810839 0.238861 0.534307 -0.811209 0.237709 0.534261 -0.781106 0.2368 0.577754 -0.750308 0.249043 0.612385 -0.751078 0.23472 0.617081 -0.675063 0.230482 0.700833 -0.892916 0.291826 0.34284 -0.886484 0.242901 0.393885 -0.860345 0.242728 0.448207 -0.827207 0.560555 0.0388135 -0.910911 0.410358 0.0429834 -0.952802 0.299324 0.0507227 -0.901425 0.245222 0.35679 -0.933716 0.243797 0.262178 -0.960496 0.131055 0.245504 -0.937531 0.31056 0.156807 -0.959424 0.246056 0.137706 -0.968325 0.243149 0.0567929 -0.99138 0.121911 0.0479973 -0.959246 0.272279 0.0755678 -0.947983 0.283873 0.144025 -0.937981 0.310812 0.153582 -0.935919 0.243077 0.254891 -0.89405 0.332962 0.299686 -0.899049 0.248589 0.360437 -0.823939 0.340079 0.453289 -0.846927 0.288377 0.446713 -0.77645 0.284729 0.562187 -0.752373 0.331285 0.569373 -0.709175 0.246702 0.660461 -0.586029 0.414573 0.696203 -0.677676 0.18563 0.711545 -0.517894 0.317177 0.794471 -0.546046 0.250583 0.799401 -0.428396 0.234396 0.87266 -0.407005 0.278632 0.869891 0.205826 0.0739141 0.975793 0.363332 0.193834 0.911273 0.35631 0.158441 0.920837 0.473979 0.1202 0.872294 0.495564 0.202923 0.844534 0.94004 0.00661712 0.341 0.897854 0.150245 0.413866 0.879956 0.0885482 0.46673 0.831504 0.207779 0.515198 0.819587 0.100695 0.564037 0.742345 0.173921 0.647051 0.741603 0.162968 0.650743 0.63566 0.088969 0.766825 0.645297 0.263285 0.717128 0.575146 0.0906496 0.813013 0.952817 0.0975115 0.287458 0.98808 0.0804646 0.131241 0.994408 0.0746183 0.0747309 0.974994 0.151676 -0.162424 0.971448 0.199523 -0.12837 0.985855 0.153765 -0.0666749 0.984775 0.167241 -0.0474137 0.828374 0.531164 -0.177938 0.836557 0.521316 -0.16853 0.82652 0.535984 -0.172009 0.831977 0.548659 -0.0823852 0.823538 0.563157 -0.0681144 0.809618 0.586773 0.0146716 0.806058 0.591538 0.0187961 0.774243 0.624352 0.103599 0.780822 0.616999 0.0981299 0.72958 0.658921 0.183127 0.750549 0.638433 0.170528 0.678558 0.689441 0.253436 0.714712 0.657601 0.238217 0.622672 0.716315 0.314917 0.671316 0.676957 0.301769 0.564015 0.739719 0.367018 0.623523 0.694695 0.358634 0.503976 0.7597 0.41093 0.569038 0.713162 0.409385 0.441471 0.777723 0.447493 0.500829 0.737573 0.452942 0.377544 0.795144 0.47456 0.429852 0.761454 0.485196 0.347145 0.798775 0.491375 -0.295286 0.945561 0.136825 -0.297537 0.943431 0.14632 -0.284073 0.943308 0.171676 -0.285495 0.941227 0.180513 -0.269528 0.940502 0.206908 -0.270173 0.938598 0.21457 -0.251488 0.937142 0.241906 -0.251533 0.935503 0.248126 -0.22989 0.933179 0.276273 -0.229571 0.931903 0.280809 -0.204578 0.928549 0.309749 -0.204185 0.927755 0.312377 -0.175287 0.923155 0.342139 -0.175157 0.922972 0.3427 -0.141934 0.916899 0.373031 -0.142481 0.917512 0.371309 -0.104305 0.909671 0.402019 -0.105991 0.911286 0.3979 -0.0622813 0.901344 0.428604 -0.0656064 0.904185 0.422073 -0.0159556 0.891809 0.452131 -0.0214816 0.89616 0.443211 0.0347415 0.880918 0.471992 0.0264922 0.887049 0.460915 0.0896262 0.868523 0.487477 0.0781097 0.876758 0.474547 0.148458 0.85449 0.497803 0.133118 0.86521 0.483416 0.211102 0.838624 0.502141 0.191477 0.852216 0.486892 0.276936 0.820843 0.499524 0.252503 0.837819 0.484047 0.351115 0.798489 0.489013 -0.309136 0.948546 0.0685273 -0.31623 0.94753 0.046749 -0.357423 0.932469 0.0524491 -0.354528 0.930085 0.0961832 -0.342962 0.93091 0.125634 -0.346342 0.928472 0.134117 -0.332833 0.928734 0.163329 -0.335488 0.92625 0.171783 -0.319447 0.925876 0.201763 -0.321236 0.923534 0.209504 -0.30247 0.922394 0.240211 -0.30343 0.920381 0.246635 -0.281682 0.918338 0.278047 -0.282017 0.916747 0.282915 -0.2571 0.913666 0.314824 -0.257062 0.912588 0.317964 -0.228642 0.908312 0.350275 -0.228524 0.907854 0.351537 -0.19608 0.902173 0.384235 -0.196204 0.902445 0.383532 -0.159457 0.895167 0.416233 -0.160197 0.896336 0.413423 -0.118584 0.887188 0.445909 -0.120346 0.889431 0.440941 -0.0733733 0.878115 0.47279 -0.0765845 0.881622 0.4657 -0.0240177 0.867868 0.496214 -0.0291432 0.872877 0.487069 0.0295911 0.856289 0.515648 0.0221302 0.863014 0.504694 0.0871857 0.843257 0.530392 0.0769659 0.851955 0.517927 0.148446 0.82867 0.539694 0.135048 0.839641 0.526084 0.213255 0.812341 0.542794 0.196339 0.825885 0.528549 0.280819 0.794278 0.538761 0.260007 0.810797 0.524408 0.334119 0.781708 0.526591 0.87408 0.448475 -0.186691 0.88787 0.408966 -0.210791 0.899113 0.428115 -0.0911824 0.895733 0.435791 -0.0880207 0.886796 0.461842 0.0172052 0.887015 0.461426 0.017057 0.860202 0.495652 0.11992 0.866045 0.486055 0.117117 0.822153 0.527065 0.215099 0.834985 0.508215 0.210993 0.775316 0.554749 0.301892 0.794687 0.528632 0.298363 0.721226 0.579197 0.379954 0.745198 0.548964 0.378575 0.661418 0.601241 0.448369 0.688887 0.568308 0.449958 0.597539 0.620812 0.507483 0.626393 0.587455 0.512375 0.529825 0.638904 0.557753 0.555984 0.609373 0.565285 0.458352 0.657682 0.597803 0.48163 0.631762 0.607379 0.384095 0.676767 0.628058 0.40443 0.654205 0.639102 0.309075 0.695347 0.648818 0.326488 0.675856 0.660776 0.234393 0.7131 0.660718 0.248993 0.696378 0.673098 0.160852 0.729831 0.664434 0.172796 0.715606 0.676793 0.0896733 0.745237 0.660742 0.0991259 0.733303 0.672637 0.0210886 0.759426 0.650252 0.0282891 0.749561 0.66133 -0.0443043 0.772343 0.633658 -0.039092 0.764361 0.643603 -0.105968 0.783985 0.611668 -0.102455 0.777726 0.620197 -0.163975 0.794525 0.584673 -0.16183 0.789806 0.591622 -0.217849 0.803934 0.553382 -0.216742 0.800617 0.558602 -0.267534 0.81232 0.518229 -0.267125 0.810274 0.521633 -0.31309 0.819789 0.4795 -0.313042 0.818896 0.481054 -0.35417 0.826357 0.437833 -0.354148 0.826563 0.437462 -0.390865 0.832175 0.393332 -0.390524 0.833429 0.391008 -0.423025 0.837337 0.34629 -0.422009 0.839605 0.342011 -0.450342 0.841948 0.297179 -0.448319 0.845155 0.291073 -0.472763 0.846102 0.246184 -0.469676 0.849872 0.239003 -0.490369 0.849589 0.19426 -0.486683 0.853249 0.187366 -0.504304 0.85184 0.141586 -0.500001 0.85544 0.134986 -0.515388 0.852711 0.0851996 -0.718369 0.69493 0.031905 -0.781004 0.622889 0.0451875 -0.767415 0.62853 0.126588 -0.771614 0.622852 0.129103 -0.749958 0.627452 0.209444 -0.753112 0.622819 0.21194 -0.726109 0.625151 0.286272 -0.729031 0.620428 0.289108 -0.696007 0.620774 0.360852 -0.698716 0.615832 0.36407 -0.659438 0.614128 0.433576 -0.66113 0.610543 0.436056 -0.61587 0.606699 0.502615 -0.616533 0.60501 0.503836 -0.56523 0.59893 0.567272 -0.565199 0.599031 0.567197 -0.508232 0.590684 0.626731 -0.507841 0.592381 0.625446 -0.445444 0.581749 0.680549 -0.444973 0.584899 0.678154 -0.377065 0.571904 0.728524 -0.376752 0.576378 0.725153 -0.303993 0.56108 0.769921 -0.304032 0.566831 0.765681 -0.22648 0.549173 0.804435 -0.227038 0.556172 0.799454 -0.144949 0.536115 0.831607 -0.146168 0.54437 0.826012 -0.0603912 0.522018 0.850794 -0.0623933 0.531569 0.844714 0.0269911 0.506818 0.86163 0.0241078 0.5177 0.855223 0.116187 0.490652 0.863575 0.112347 0.502925 0.856998 0.206195 0.473701 0.856207 0.201337 0.487458 0.849617 0.296515 0.456015 0.839124 0.290613 0.471326 0.832704 0.385595 0.437976 0.812092 0.378627 0.45497 0.806005 0.47252 0.419842 0.774892 0.46448 0.438669 0.769304 0.556191 0.401962 0.727378 0.547102 0.422753 0.722468 0.634759 0.385033 0.669948 0.624681 0.407876 0.665891 0.7075 0.369293 0.602549 0.696393 0.394552 0.599471 0.772783 0.355697 0.52563 0.761899 0.380921 0.523841 0.83048 0.342475 0.439333 0.820537 0.366286 0.438809 0.909135 0.304465 0.284207 0.88121 0.0114043 0.472588 0.881017 0.122165 0.45704 0.820266 0.138119 0.555055 -0.303473 0.947294 0.10266 -0.312993 0.946516 0.0783767 -0.35041 0.932473 0.0877857 -0.360374 0.93106 0.0570761 -0.511212 0.855695 0.0802978 -0.520297 0.853122 0.0383807 -0.502498 0.863358 0.045924 -0.313723 0.948596 0.0417645 -0.319502 0.947425 0.0174296 -0.365363 0.930682 0.0184536 -0.349073 0.936584 0.0309683 -0.388497 0.92125 0.0192009 0.124664 0.398661 0.908586 0.130228 0.38604 0.913244 0.0170834 0.417885 0.908339 0.0204981 0.409496 0.912082 -0.0890034 0.437784 0.894664 -0.0873705 0.433286 0.897012 -0.1919 0.457889 0.868051 -0.191541 0.456727 0.868742 -0.29006 0.477628 0.829299 -0.955874 0.283231 0.0780024 -0.835531 0.547591 0.0450815 -0.822493 0.555103 0.123958 -0.827275 0.546568 0.129922 -0.804047 0.553096 0.21816 -0.806152 0.548727 0.221401 -0.773465 0.55307 0.309623 -0.773414 0.553194 0.309525 -0.729053 0.555074 0.400468 -0.729286 0.554326 0.401079 -0.675345 0.553162 0.487771 -0.675978 0.550187 0.490254 -0.614012 0.545948 0.570026 -0.614514 0.54142 0.573792 -0.544929 0.534114 0.646355 -0.544989 0.529021 0.65048 -0.46783 0.518549 0.715711 -0.467442 0.513804 0.719377 -0.382824 0.500011 0.776811 -0.427521 0.90343 0.0322459 -0.424376 0.905102 0.026386 -0.421549 0.905956 0.0392523 -0.424904 0.904013 0.0470858 -0.418036 0.905733 0.0699594 -0.422565 0.902581 0.0823813 -0.409954 0.904634 0.116509 -0.413285 0.901536 0.128176 -0.397925 0.902854 0.162818 -0.40015 0.899885 0.173457 -0.380549 0.900352 0.211067 -0.381755 0.897581 0.220482 -0.358145 0.896873 0.259522 -0.358504 0.894411 0.267401 -0.331095 0.892322 0.306818 -0.33087 0.890288 0.312909 -0.299389 0.886622 0.352518 -0.298907 0.885184 0.356517 -0.262819 0.879682 0.396339 -0.262488 0.879056 0.397945 -0.221129 0.871384 0.437941 -0.221423 0.871808 0.436947 -0.174148 0.861566 0.476839 -0.175651 0.863373 0.473005 -0.121718 0.850081 0.512394 -0.125086 0.853647 0.50561 -0.0638008 0.836762 0.543838 -0.069759 0.842523 0.534124 -0.000554292 0.821468 0.570254 -0.00993205 0.829979 0.557706 0.0677418 0.804116 0.5906 -0.597982 0.800833 0.0329361 -0.552018 0.833481 0.0241882 -0.54796 0.835277 0.0453122 -0.552273 0.832199 0.0493897 -0.542183 0.83574 0.087042 -0.548993 0.830495 0.0942609 -0.530844 0.834569 0.147308 -0.53602 0.83006 0.153894 -0.513627 0.832741 0.206712 -0.517247 0.829085 0.212304 -0.488398 0.830223 0.268694 -0.490991 0.82702 0.2738 -0.456682 0.826084 0.330192 -0.458431 0.823252 0.334808 -0.419389 0.820052 0.389393 -0.420388 0.817717 0.393208 -0.376521 0.812109 0.44577 -0.376916 0.810496 0.448364 -0.327815 0.802249 0.498933 -0.32786 0.80163 0.499897 -0.273039 0.790426 0.548339 -0.273095 0.791092 0.54735 -0.21211 0.776554 0.593274 -0.212633 0.778878 0.590031 -0.145037 0.760568 0.632851 -0.14657 0.764954 0.627186 -0.0720329 0.742413 0.666059 -0.0751863 0.749313 0.657934 0.0064121 0.722099 0.691761 0.000969194 0.732053 0.681247 0.0895735 0.699747 0.708753 0.0811984 0.713269 0.696171 0.958636 0.215313 0.186166 0.982111 0.000598332 0.188302 0.970271 0.116007 0.212405 0.880319 0.411347 0.236287 0.874692 0.450429 0.178962 0.951448 0.241972 0.190255 0.97726 0.206707 0.0472845 0.994733 0.0712757 0.0736603 0.987047 0.160337 0.0054929 0.89944 0.405946 -0.161915 0.915691 0.363527 -0.171344 0.924054 0.377362 -0.0610032 0.923673 0.378423 -0.0602091 0.918284 0.395434 0.0196282 0.899202 0.435005 0.0469813 0.913812 0.395035 0.0943156 0.891434 0.422547 0.163708 0.3476 0.342297 0.87293 0.337333 0.363689 0.868295 0.451364 0.322859 0.831885 0.438998 0.348273 0.828243 0.549404 0.305295 0.777786 0.535396 0.334161 0.775685 0.640175 0.289525 0.711584 0.625201 0.320953 0.711416 0.722321 0.275186 0.634449 0.707197 0.308049 0.636379 0.794636 0.261742 0.547763 0.780162 0.294911 0.551701 0.855092 0.249409 0.454547 0.842812 0.279666 0.459842 0.938148 0.0275716 0.345136 0.913336 0.227445 0.337768 0.90071 0.268367 0.341614 0.822348 0.473731 0.315155 0.837652 0.451997 0.306656 0.769416 0.571827 0.284628 0.725751 0.619962 0.298217 0.798888 0.560439 0.21837 0.76594 0.599093 0.233289 0.82027 0.550861 0.153974 0.798988 0.577714 0.166926 0.83677 0.540189 0.0895122 0.826713 0.554113 0.0974942 0.850529 0.525531 0.0204255 0.849684 0.526862 0.0213051 0.860275 0.506839 -0.0551572 0.865753 0.49651 -0.0628458 0.862352 0.482228 -0.154291 0.86968 0.463496 -0.16979 0.629748 0.656667 0.414977 0.687384 0.598535 0.411411 0.562797 0.679581 0.470563 0.617522 0.627495 0.474254 0.491168 0.702149 0.5155 0.54076 0.657173 0.525074 0.416718 0.724189 0.549451 0.460348 0.686053 0.563392 0.341392 0.745167 0.572867 0.378538 0.713514 0.589582 0.266475 0.764933 0.586403 0.297062 0.739231 0.604394 0.192994 0.783394 0.590803 0.217345 0.762972 0.608798 0.122008 0.800387 0.586936 -0.382231 0.49646 0.779376 -0.290437 0.479182 0.82827 -0.32403 0.180057 0.928754 -0.20033 0.361025 0.910785 -0.270999 0.114314 0.955768 -0.0931321 0.248226 0.964215 -0.112552 0.185684 0.976142 0.0230578 0.163039 0.98635 0.0453473 0.222007 0.97399 0.141078 0.115414 0.983248 0.245544 0.303597 0.920618 0.23991 0.363479 0.900181 0.231993 0.380506 0.895206 0.193615 0.629537 0.752461 0.292269 0.586391 0.755463 0.266682 0.614661 0.742342 0.387494 0.558466 0.733461 0.356599 0.592782 0.722113 0.480654 0.530324 0.698375 0.444912 0.570749 0.690145 0.569871 0.502411 0.650254 0.530227 0.548653 0.646405 0.653275 0.475068 0.589528 0.6111 0.526495 0.591067 0.728969 0.44863 0.517045 0.685792 0.504471 0.524593 0.794195 0.424367 0.434933 0.752698 0.48208 0.44838 0.81587 0.432273 0.384051 0.733876 0.583113 0.348433 0.681296 0.63843 0.35811 0.0541555 0.815933 0.575605 0.140604 0.78462 0.603823 0.167671 0.679349 0.714403 0.119487 0.583154 0.803526 0.102426 0.589207 0.801464 0.110289 0.574089 0.811331 0.0087085 0.610323 0.792105 0.0138413 0.59929 0.800412 -0.0818056 0.630549 0.771827 -0.07886 0.623124 0.778137 -0.167937 0.649575 0.741519 -0.166556 0.64518 0.745656 -0.248706 0.667085 0.702242 -0.248291 0.665182 0.704191 -0.323454 0.682877 0.655024 -0.323461 0.682943 0.654952 -0.391772 0.696784 0.600838 -0.391752 0.698293 0.599097 -0.453431 0.708614 0.540617 -0.453069 0.711101 0.537647 -0.508421 0.718191 0.475089 -0.507564 0.721188 0.471451 -0.556882 0.725251 0.404838 -0.555558 0.728324 0.401122 -0.598775 0.729449 0.330714 -0.597111 0.732346 0.327305 -0.633123 0.730681 0.255461 -0.630869 0.733863 0.251891 -0.658132 0.730077 0.183982 -0.653861 0.735265 0.17847 -0.674945 0.72957 0.110349 -0.668424 0.736558 0.1034 -0.679581 0.731565 0.0546028 -0.67675 0.734384 0.0518675 -0.680701 0.732065 0.0269559 -0.802425 0.594955 0.0462867 -0.335296 0.941903 0.019865 -0.325238 0.945366 0.0224325 -0.322901 0.946167 0.0224174 -0.35634 0.933926 0.02836 -0.339361 0.940499 0.0172209 -0.334438 0.941638 0.0383245 -0.337156 0.940394 0.044544 -0.331166 0.941446 0.0633101 -0.335125 0.93922 0.0745431 -0.32524 0.940311 0.100168 -0.32827 0.938025 0.111122 -0.316462 0.938651 0.137064 -0.318599 0.93634 0.14752 -0.304108 0.936426 0.174999 -0.305339 0.934186 0.184568 -0.287944 0.933568 0.2134 -0.28837 0.931521 0.221611 -0.267977 0.930046 0.251402 -0.267807 0.928286 0.258001 -0.244152 0.925794 0.288609 -0.243659 0.924438 0.293335 -0.21629 0.920733 0.324761 -0.21581 0.919925 0.327359 -0.184124 0.914752 0.359621 -0.184046 0.914653 0.359912 -0.147506 0.907721 0.392791 -0.148313 0.908564 0.390532 -0.106222 0.89951 0.42379 -0.10846 0.901554 0.418853 -0.0601601 0.889967 0.45204 -0.0644255 0.893509 0.4444 -0.00938191 0.878953 0.476817 -0.016363 0.884374 0.466492 0.0460847 0.866325 0.49735 0.0357306 0.874005 0.484601 0.106016 0.851929 0.512813 0.0915971 0.862323 0.498005 0.170093 0.835635 0.522286 0.150901 0.849275 0.505926 0.237957 0.817301 0.524782 0.21343 0.834712 0.507645 0.308881 0.796852 0.519249 0.278438 0.818687 0.502218 0.382015 0.774277 0.504539 0.345273 0.801198 0.488743 0.456129 0.749681 0.479504 0.412956 0.782337 0.466279 0.529206 0.72356 0.443173 0.479626 0.762653 0.433958 0.59842 0.697034 0.395015 0.543821 0.742288 0.391493 0.648962 0.679649 0.341944 0.598435 0.723324 0.344497 0.690932 0.664389 0.284957 0.649053 0.702443 0.292068 0.728369 0.647858 0.223065 0.696876 0.678447 0.232536 0.758211 0.632161 0.159651 0.739192 0.65218 0.168095 0.783355 0.614508 0.0934649 0.776539 0.622459 0.0976309 0.805229 0.59259 0.0210527 0.807921 0.58899 0.0188286 0.821543 0.567086 -0.0589925 0.830137 0.553313 -0.0686856 0.827195 0.535066 -0.171619 0.828915 0.532104 -0.172526 -0.73497 0.676637 0.0445137 -0.755206 -0.162641 -0.63499 -0.629148 0.777276 -0.00391446 -0.668555 0.742717 0.0374944 -0.958368 0.205617 -0.198124 -0.986767 0.0379507 -0.15764 -0.986464 0.16009 -0.0355055 -0.991779 0.120439 -0.0432203 -0.968471 0.0346249 -0.246709 -0.966352 0.0883185 -0.241586 -0.955065 0.15852 -0.250443 -0.879024 0.289081 -0.379143 -0.923802 0.132892 -0.359069 -0.937295 0.141907 -0.318339 -0.935352 0.149236 -0.320694 -0.938155 0.143851 -0.314916 -0.954502 0.0411922 -0.295347 -0.958754 0.0264101 -0.283009 -0.878924 0.135471 -0.457319 -0.72294 0.126026 -0.67932 -0.761218 0.0213071 -0.648146 -0.790491 0.0303901 -0.611719 -0.676487 0.02914 -0.735878 -0.706077 0.115215 -0.698699 -0.715322 0.0890256 -0.693101 -0.664225 0.12937 -0.736253 -0.70339 0.0309275 -0.710131 -0.723938 0.0388251 -0.688772 -0.576398 0.10703 -0.81013 -0.552412 -0.182899 -0.813259 -0.52827 -0.242454 -0.813724 -0.545566 -0.132355 -0.827551 -0.612072 -0.34415 -0.71199 -0.604839 -0.313633 -0.731987 -0.688714 -0.353829 -0.632833 -0.719884 -0.278486 -0.635777 -0.664273 -0.288385 -0.68962 -0.678585 -0.470705 -0.563879 -0.621678 -0.194588 -0.758717 -0.572855 -0.313185 -0.757465 -0.583022 -0.278789 -0.763127 -0.845297 -0.28902 -0.449378 -0.860839 -0.283488 -0.422599 -0.85951 -0.293337 -0.418564 -0.939855 -0.178294 -0.291349 -0.955555 -0.187832 -0.227229 -0.998226 -0.0594673 0.00289392 -0.998778 -0.0493243 0.00312162 -0.998583 -0.00461029 0.053018 -0.996161 0.0762834 0.0429361 -0.9967 -0.0136887 0.0800145 -0.995735 -0.0554694 -0.0737266 -0.986278 -0.131088 -0.100355 -0.994877 0.0514739 -0.0870095 -0.994123 0.0492763 -0.0963881 -0.982972 -0.136416 -0.123109 -0.982899 0.172337 0.064879 -0.984268 0.162785 0.0686775 -0.984694 0.161977 0.0643515 -0.984374 0.16377 0.064705 -0.984792 0.162952 0.0602571 -0.98508 0.161408 0.0597109 -0.977308 0.196855 0.0782087 -0.977351 0.197003 0.0773011 -0.977937 0.196131 0.0719126 -0.395832 0.918316 0.00365371 -0.541458 0.840548 0.0174035 -0.525563 0.85071 0.00873901 -0.60057 0.799543 0.0068333 -0.666935 0.744922 0.0170178 -0.674584 0.738086 0.0128684 -0.804444 0.59372 0.0191693 -0.324527 0.944842 0.0442237 -0.355772 0.933999 0.0327299 -0.427345 0.903462 0.0336489 -0.325635 0.945298 0.0193494 -0.318973 0.947362 0.0276154 -0.321643 0.946319 0.0320309 -0.338234 0.940775 0.0232351 -0.349015 0.936591 0.0314091 -0.563922 0.825803 -0.00640294 -0.386616 0.92161 0.0341154 -0.424862 0.904891 0.0257678 -0.432109 0.901403 0.0274636 -0.523883 0.851523 0.0213352 -0.506698 0.862071 0.00955423 -0.609945 0.792304 0.0148668 -0.630274 0.776352 0.00565424 -0.720668 0.693277 0.00243315 -0.954466 0.296163 -0.0358161 -0.912912 0.406186 -0.0400637 -0.920622 0.388635 -0.0376583 -0.829841 0.251468 -0.498125 -0.741543 0.511825 -0.433762 -0.79908 0.417389 -0.432732 -0.807867 0.423006 -0.410386 -0.904238 0.179321 -0.387553 -0.840593 0.264787 -0.472537 -0.900673 0.0567486 -0.430776 -0.924578 0.0684261 -0.374798 -0.335289 0.941905 0.0199192 -0.343042 0.937958 0.0505714 -0.324868 0.944492 0.0489473 -0.32364 0.944866 0.0498514 -0.345846 0.936857 0.0518567 -0.490193 0.871241 -0.0254719 -0.450089 0.892595 -0.0263314 -0.444611 0.894344 -0.0496982 -0.415617 0.908179 -0.0497385 -0.408066 0.909551 -0.078732 -0.353655 0.932175 -0.0773157 -0.618546 0.70949 -0.337675 -0.66952 0.658817 -0.343078 -0.675615 0.662232 -0.324027 -0.747499 0.577417 -0.328382 -0.753234 0.58081 -0.308703 -0.838428 0.449848 -0.307693 -0.842876 0.452893 -0.290599 -0.89315 0.347878 -0.285068 -0.905223 0.357873 -0.229123 -0.925645 0.303909 -0.225434 -0.933984 0.312878 -0.172575 -0.982317 0.104071 -0.155637 -0.962145 0.197432 -0.187876 -0.7345 0.677966 0.0295363 -0.554788 0.831757 0.0197517 -0.52565 0.850651 0.00923994 -0.384388 0.923167 0.00284888 -0.39765 0.91747 0.0110768 -0.32038 0.947262 0.00719474 -0.312789 0.94982 0.00244494 -0.319626 0.94754 0.00275634 -0.306428 0.951832 -0.0108643 -0.365494 0.930771 -0.00890171 -0.375605 0.926283 0.0303513 -0.373959 0.926932 0.0308351 -0.426794 0.903692 0.0344602 -0.492816 0.870042 -0.01265 -0.563292 0.826193 -0.0103309 -0.581497 -0.0419978 -0.812464 -0.57619 -0.0275431 -0.816851 -0.612486 -0.0165856 -0.790307 -0.73197 0.228015 -0.642051 -0.692076 0.313317 -0.65028 -0.724378 0.332061 -0.604163 -0.786615 0.188238 -0.588051 -0.666142 0.316259 -0.675452 -0.763366 0.0797296 -0.641026 -0.735165 0.121831 -0.666851 -0.462481 0.861685 -0.208832 -0.526062 0.831902 -0.176627 -0.50435 0.825666 -0.252798 -0.983882 -0.129202 -0.123623 -0.967121 -0.0574015 -0.247754 -0.986913 -0.0342719 -0.157572 -0.97995 -0.13827 -0.143456 -0.899867 -0.101795 -0.424118 -0.891866 -0.259237 -0.370637 -0.879862 -0.252988 -0.402294 -0.83817 0.525079 -0.147525 -0.963867 0.261588 -0.0503133 -0.959939 0.275316 0.052133 -0.987849 0.145678 0.0541597 -0.984381 0.166594 0.0569225 -0.976475 0.17278 -0.129011 -0.958716 0.14927 -0.242038 -0.893102 -0.116882 -0.434405 -0.849209 0.371798 -0.37498 -0.794338 0.146592 -0.589523 -0.695362 -0.119198 -0.708705 -0.658122 0.0117261 -0.75282 -0.637083 -0.165513 -0.752815 -0.610387 -0.0745495 -0.788588 -0.522039 -0.0985879 -0.847205 -0.522187 -0.0823753 -0.848844 -0.885629 -0.0134344 -0.464198 -0.950356 0.0265074 -0.310033 -0.882018 0.316289 -0.349294 -0.929438 0.362091 -0.0709558 -0.879039 0.470785 -0.075177 -0.880446 0.473693 -0.0207187 -0.82506 0.564347 0.0280589 -0.825157 0.564599 0.0185397 -0.906226 0.419236 0.0547277 -0.906196 0.41925 0.0551171 -0.896998 0.438013 0.0594917 -0.897593 0.437808 0.0514909 -0.84743 0.527433 0.0606326 -0.847697 0.527569 0.0555 -0.958813 0.282248 0.0318439 -0.758918 0.508341 -0.40698 -0.657183 0.638667 -0.400269 -0.662391 0.641864 -0.386327 -0.600544 0.704258 -0.378639 -0.60541 0.707129 -0.365304 -0.588375 0.72257 -0.362916 -0.592834 0.725114 -0.350367 -0.729398 0.579351 -0.363774 -0.579811 0.685907 -0.439716 -0.818271 0.354502 -0.452505 -0.692531 0.480337 -0.538216 -0.843515 0.159269 -0.512949 -0.777826 0.222586 -0.587743 -0.836364 0.0504818 -0.545845 -0.881099 0.0711116 -0.467554 -0.847631 0.156847 -0.506873 -0.867842 0.129525 -0.47966 -0.816229 0.388818 -0.427307 -0.85655 0.415647 -0.305874 -0.796726 0.591775 -0.122595 -0.720044 0.657662 -0.221398 -0.746346 0.663729 -0.0493031 -0.613781 0.777425 -0.137417 -0.633457 0.773553 -0.0186865 -0.510079 0.846588 -0.152015 -0.52336 0.846635 -0.0964539 -0.811871 0.16877 -0.558912 -0.942264 0.254321 -0.21785 -0.847092 0.478591 -0.231056 -0.86306 0.490618 -0.120087 -0.759743 0.649677 -0.0266563 -0.758138 0.650254 -0.0489453 -0.677918 0.735057 0.0109261 -0.634814 0.77244 -0.0186428 -0.637617 0.770337 0.00503166 -0.473282 0.880909 -0.00181299 -0.417544 0.906685 -0.0598337 -0.829799 0.558005 -0.00797989 -0.767478 0.640924 -0.0138871 -0.76595 0.641689 -0.0394406 -0.737425 0.67422 -0.0403906 -0.732288 0.675016 -0.0900447 -0.668752 0.737962 -0.0904572 -0.667512 0.73806 -0.0984646 -0.581986 0.807319 -0.0976169 -0.578466 0.807556 -0.115025 -0.520741 0.846171 -0.113242 -0.514919 0.846126 -0.137585 -0.470938 0.87175 -0.135162 -0.464867 0.871218 -0.157727 -0.332655 0.931612 -0.146424 -0.417612 0.906338 -0.0644272 -0.299742 0.951963 -0.06262 -0.333724 0.942239 -0.0285212 -0.376445 0.926021 -0.0278165 -0.433655 0.901052 0.00703242 -0.575077 0.817983 0.0137715 -0.576417 0.816822 0.0233547 -0.767745 0.639847 0.0341016 -0.767799 0.639527 0.0385949 -0.919639 0.389833 0.0479102 -0.920603 0.389016 0.0340166 -0.896378 0.443284 0.00222648 -0.960465 0.2783 0.00746856 -0.961416 0.270385 -0.0507044 -0.971558 0.0560851 -0.230066 -0.699786 0.470532 -0.537493 -0.759484 0.368741 -0.535924 -0.755441 0.366294 -0.543265 -0.681852 0.488845 -0.544158 -0.700033 0.500662 -0.509206 -0.66538 0.54828 -0.506615 -0.679149 0.557336 -0.477633 -0.787243 0.388576 -0.478809 -0.639139 0.520795 -0.565928 -0.819109 0.172974 -0.546937 -0.715327 0.29388 -0.633989 -0.792725 0.0914809 -0.602676 -0.813846 0.100507 -0.572323 -0.642266 0.0176623 -0.766278 -0.617585 0.07731 -0.782696 -0.674338 0.0224703 -0.738081 -0.616682 0.170001 -0.768637 -0.751879 0.0174167 -0.659071 -0.719922 0.119568 -0.683678 -0.796843 0.0674392 -0.600411 -0.713992 0.290656 -0.636973 -0.865923 0.18482 -0.464779 -0.98699 -0.125548 -0.100436 -0.996142 -0.0834673 -0.0271088 -0.995938 0.0826716 -0.0356871 -0.995714 0.0809084 -0.0448064 -0.993387 0.0549487 -0.100812 -0.995359 -0.0172 -0.0946828 -0.93624 0.0265479 -0.350356 -0.926988 -0.247273 -0.282046 -0.798822 -0.154576 -0.581369 -0.804191 -0.229414 -0.548311 -0.773036 -0.23831 -0.587897 -0.761407 -0.133619 -0.634354 -0.864771 -0.095842 -0.492935 -0.713994 0.0221465 -0.699802 -0.911163 0.115552 -0.395511 -0.759641 0.240579 -0.604207 -0.896996 0.324546 -0.300113 -0.753229 0.441739 -0.487353 -0.838925 0.49715 -0.221464 -0.709945 0.594816 -0.377056 -0.744009 0.614456 -0.262478 -0.628514 0.734592 -0.255627 -0.651483 0.741826 -0.158948 -0.520966 0.821922 -0.230301 -0.554258 0.826659 -0.0971227 -0.405121 0.882506 -0.238874 -0.455919 0.887992 -0.0600726 -0.351647 0.922186 -0.160986 -0.367278 0.923609 -0.10979 -0.487937 0.865182 -0.115666 -0.370143 0.901345 -0.22488 -0.534819 0.80806 -0.246998 -0.539478 0.80969 -0.231009 -0.592626 0.770097 -0.236103 -0.598142 0.77194 -0.215255 -0.669753 0.709267 -0.219934 -0.674128 0.710795 -0.200805 -0.767904 0.607433 -0.203343 -0.770176 0.608509 -0.191171 -0.833256 0.519132 -0.190228 -0.840726 0.524064 -0.136148 -0.867653 0.478553 -0.134778 -0.871875 0.48256 -0.083487 -0.970847 0.228518 -0.0723578 -0.916833 0.3797 -0.123474 -0.993871 0.0441026 -0.101368 -0.993559 0.0489536 -0.102196 0.81666 -0.146975 -0.558091 0.928907 -0.0465835 -0.367371 0.762955 -0.209041 -0.61172 0.724399 -0.0536347 -0.687292 0.834349 -0.0040585 -0.551221 0.766465 -0.00769453 -0.64224 0.933388 0.159377 -0.321537 0.890166 0.156485 -0.427922 0.933429 0.228882 -0.276267 0.931326 0.229523 -0.282757 0.876395 0.395617 -0.274624 0.8619 0.4461 -0.241087 0.892482 0.405076 -0.198467 0.831034 0.51522 -0.2096 0.82183 0.530648 -0.207384 0.833128 0.509541 -0.215097 0.811658 0.532473 -0.240176 0.823273 0.518439 -0.231175 0.974805 0.10241 -0.198159 0.972927 0.102313 -0.207231 0.975705 0.0820711 -0.203137 0.976939 0.032051 -0.211098 0.965326 0.0306605 -0.259239 0.977006 -0.00514737 -0.213152 0.977483 -0.00781013 -0.210869 0.975998 -0.0143309 -0.217306 0.976897 -0.0134526 -0.213286 0.97641 -0.00914687 -0.215732 0.976304 -0.00920526 -0.216207 0.940851 -0.126394 -0.314363 0.962518 -0.057926 -0.26496 0.971518 -0.0563172 -0.230178 0.972503 0.0316082 -0.230735 0.97466 0.0819919 -0.208125 0.94417 -0.0995818 -0.314049 0.94488 -0.102665 -0.310905 0.945843 0.0913488 -0.311508 0.970346 -0.0329155 -0.239468 0.970344 -0.107139 -0.216686 0.941606 -0.119649 -0.314741 0.94156 -0.120336 -0.314617 0.891239 -0.177585 -0.41732 0.926098 -0.173107 -0.335227 0.924288 -0.126103 -0.360263 0.813778 -0.204985 -0.543825 0.801686 -0.147166 -0.579346 0.722704 -0.117049 -0.681175 0.759613 -0.189415 -0.622182 0.861287 0.185184 -0.473172 0.929271 0.190127 -0.316713 0.849175 0.361117 -0.385353 0.770118 -0.143776 -0.621487 0.874242 -0.141498 -0.464413 0.815223 0.0814376 -0.573393 0.910703 0.0893273 -0.403287 0.832021 0.278258 -0.47991 0.857109 0.164603 -0.488128 0.833866 0.0105133 -0.551866 0.773414 0.00682952 -0.633864 0.774967 -0.0564129 -0.629479 0.730018 -0.0576553 -0.680991 0.822571 0.526283 -0.215413 0.832326 0.509695 -0.217815 0.842693 0.446192 -0.301298 0.865016 0.396047 -0.308048 0.881707 0.290776 -0.37154 0.923756 -0.0577705 -0.378599 0.845636 0.166741 -0.507048 0.969834 0.151483 -0.190982 0.974303 0.104165 -0.19971 0.974285 0.104788 -0.199472 0.954153 0.226901 -0.195215 0.952514 0.227047 -0.202898 0.963199 0.146495 -0.22536 0.963302 0.0926001 -0.251942 0.866672 0.440689 -0.233824 0.877422 0.438643 -0.194224 0.862373 0.462293 -0.206395 0.923681 0.333274 -0.189054 0.934646 0.291678 -0.203373 0.933739 0.291801 -0.207327 0.935807 0.284772 -0.207775 0.933201 0.285073 -0.21879 0.944604 0.172845 -0.279013 0.952728 0.173001 -0.249761 0.93889 -0.0256238 -0.343261 0.911589 -0.0281526 -0.410138 0.896662 -0.177983 -0.405364 0.814052 -0.227736 -0.534281 0.808805 -0.25497 -0.529929 0.886468 -0.0500458 -0.460075 0.88307 0.0743449 -0.463314 0.925939 0.0777742 -0.369578 0.923966 0.26677 -0.274083 0.911773 0.266805 -0.312227 0.901591 0.336101 -0.272341 0.892395 0.361622 -0.269927 0.841802 0.446215 -0.303745 0.869558 0.281863 -0.405489 0.867286 0.289828 -0.40474 0.867703 0.165591 -0.468692 0.880943 0.051845 -0.470375 0.822562 0.047459 -0.566692 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 5.44761e-11 1 -5.02869e-11 -4.62663e-11 1 4.47494e-10 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -2.01449e-10 1 4.93414e-10 -7.70493e-11 1 -1.16616e-11 4.73056e-10 1 -5.00431e-10 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.984954 0.00398239 0.172773 -0.97493 0.0131672 0.222124 -0.958997 0.0834915 0.27084 -0.972313 0.0328444 0.231365 -0.96105 0.0176197 0.275814 -0.976216 0.0118036 0.216477 -0.97752 0 0.210844 -0.977506 -6.10834e-05 0.210909 -0.977319 -0.000166406 0.211773 -0.977655 0 0.210217 -0.95031 0.131671 0.28209 -0.950394 0.103362 0.293374 -0.950134 0.0966957 0.29647 -0.950202 0.0974367 0.296009 -0.95089 0.104799 0.291247 -0.979243 0.0976768 0.177602 -0.964936 0.0683796 0.253422 -0.966546 0.0704102 0.246639 -0.973804 0.0715687 0.215832 -0.987836 0.063196 0.142075 -0.978412 0.114728 0.171894 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 5.5625e-06 1 -1.20004e-06 -2.98026e-06 1 9.93995e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -5.24341e-06 1 -3.90646e-06 9.35703e-07 1 -9.4829e-08 1.80967e-06 1 -1.62196e-06 6.46484e-07 1 -8.887e-07 -1.06988e-06 1 3.04631e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 3.42936e-06 1 3.18185e-06 8.36591e-08 1 3.26841e-07 -2.38059e-07 1 -2.30026e-08 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.47814e-05 1 9.79958e-06 6.57078e-07 1 1.50313e-06 -1.26577e-06 1 3.2769e-08 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1.06045e-05 1 -6.47212e-06 4.04238e-06 1 -3.84959e-06 -5.54826e-06 1 5.60638e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 6.66068e-06 1 -6.81737e-07 -5.28446e-07 1 -2.75956e-08 -1.207e-06 1 1.26147e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.69739e-05 1 4.73227e-06 -0.968948 0.108901 0.221991 -0.973165 0.0888843 0.212247 -0.972944 0.0902474 0.212687 -0.977344 0.0594801 0.20313 -0.976344 0.0413493 0.212231 -0.97627 0.0418354 0.212479 -0.976193 0.0421276 0.212774 -0.972975 0.0902465 0.212544 -0.972595 0.0914815 0.213754 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.58862e-05 -1 6.05169e-07 0.000110751 -1 -4.01104e-05 4.4321e-05 -1 -2.97464e-05 2.58932e-05 -1 -2.70702e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -5.67788e-06 -1 -1.73997e-06 -7.39914e-06 -1 1.98268e-06 -1.43015e-05 -1 0.000611798 3.34435e-05 -1 8.96066e-06 2.00581e-05 -1 -2.65664e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.818712 0.568013 0.0840959 0.792567 0.602426 0.0944487 0.840141 0.537299 0.073982 0.86169 0.503638 0.0619639 0.92359 0.383043 0.0161166 0.936571 0.317839 -0.147693 0.926502 0.351555 -0.134174 0.934794 0.333856 -0.121248 0.952281 0.296865 -0.0709431 0.939801 0.302479 -0.158997 0.942463 0.287174 -0.171159 0.93799 0.289449 -0.190771 1.26008e-05 0 1 1.27995e-05 -6.79601e-07 1 1.29983e-05 0 1 -0.976573 0.0212005 0.21414 -0.97335 0.0827547 0.213873 -0.96053 0.172552 0.218193 -0.965268 0.146386 0.216398 -0.97367 0.0748871 0.215311 -0.958239 0.175444 0.225828 -0.96941 0.122567 0.212655 -0.96941 0.122582 0.212647 -0.974487 0.0684884 0.213741 -0.970627 0.0979611 0.219742 -0.952022 0.219878 0.212856 -0.926912 0.301871 0.222953 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.996578 0.0616209 -0.0550987 0.995195 0.0796501 -0.0569517 0.985124 0.165321 -0.0469018 0.983654 0.174266 -0.045347 0.986194 0.0601419 0.15429 0.240526 0.0181064 0.970474 0.987527 0.0630587 0.144274 0.862197 0.059664 0.503048 0.853664 0.0540888 0.518008 0.592657 0.0397822 0.804472 0.585064 0.0363774 0.810171 0.24084 0.0145102 0.970456 0.223043 0.00793286 0.974776 0.309657 0.0499764 0.949534 0.586557 0.0901428 0.804876 0.606921 0.10235 0.788144 0.850718 0.150978 0.503473 0.836611 0.137101 0.530363 0.96065 0.181406 0.210341 0.979808 0.16232 0.11674 0.984825 0.173545 -0.00156892 -0.911503 0.0805789 0.403324 0.0677035 0.00882823 0.997666 0.0465118 0.00884787 0.998879 -0.106147 0.0332277 0.993795 -0.268237 0.0456931 0.962269 -0.345931 0.0466383 0.9371 -0.9102 0.167783 0.378661 -0.877112 0.0937149 0.471055 -0.741648 0.0900159 0.664722 -0.682273 0.0760107 0.727136 -0.58663 0.0745026 0.806421 -0.445908 0.0648121 0.892729 -0.0801318 0.0061595 0.996765 -0.0515969 0 0.998668 -0.436668 0 0.899623 -0.436668 0 0.899623 -0.806858 0 0.590746 -0.806858 0 0.590746 -0.989497 0 0.144554 -0.989497 0 0.144554 -0.942133 0 -0.335239 -0.942133 0 -0.335239 -0.675775 0 -0.737108 -0.675775 0 -0.737108 -0.335134 0 -0.942171 -0.368297 0.00763226 -0.929677 0.765978 -0.0139471 0.642715 0.756297 0.00729065 0.654188 0.686229 -0.00800139 0.727342 0.682493 0 0.730892 0.597169 0 0.802115 0.601768 -0.00984903 0.79861 0.499982 0.0108271 0.865968 0.505011 0 0.863113 0.396091 0 0.918211 0.412519 -0.030946 0.910423 0.286579 0.0405848 0.957197 0.304182 0 0.952614 0.173661 0 0.984806 0.154428 0.0330434 0.987451 0.0581436 -0.0220312 0.998065 0.97303 -0.00491492 -0.230625 0.975118 0.0102708 -0.221451 0.993191 -0.00965439 -0.1161 0.993956 0 -0.109783 1 0 -1.28214e-05 0.999706 0.020911 0.0122643 0.993105 -0.0165017 0.116064 0.99174 0 0.128268 0.973048 0 0.230604 0.96911 0.0258534 0.24527 0.939525 -0.0191149 0.341945 0.934395 0 0.356238 0.893639 0 0.448787 0.887443 0.0223707 0.460374 0.835369 -0.0173237 0.549416 0.828204 0 0.560427 0.796204 0 0.605029 0.731235 0 -0.682126 0.766007 -0.00869848 -0.642773 0.766465 -0.00761939 -0.642241 0.823475 0.00604467 -0.567321 0.835311 -0.0201461 -0.549408 0.857642 0 -0.514247 0.893627 0 -0.448811 0.900877 0.0294987 -0.433071 0.939487 -0.0207225 -0.341959 0.945473 0 -0.3257 0.958882 0 -0.283804 0.686124 -0.0177538 -0.727268 0.694081 -0.00359228 -0.719888 0.725443 0 -0.688283 0.173613 -0.0159909 -0.984684 0.221376 0.0505141 -0.973879 0.286716 -0.0228335 -0.957743 0.322247 0 -0.946656 0.396068 0 -0.918221 0.400191 0.00767657 -0.9164 0.499977 -0.00708187 -0.86601 0.503887 0 -0.86377 0.597148 0 -0.802131 0.573622 -0.0479904 -0.817713 0.631479 0.0112418 -0.775311 -0.173619 -0.0218116 -0.984571 -0.154888 0 -0.987932 -0.0581577 0 -0.998307 -0.0581608 -5.12962e-06 -0.998307 0.0581321 -5.12965e-06 -0.998309 0.0581351 0 -0.998309 0.127762 0 -0.991805 -0.396053 -0.01403 -0.918121 -0.386952 0 -0.9221 -0.286816 0 -0.957986 -0.308337 -0.0387793 -0.950486 -0.234263 0.0127002 -0.97209 -0.676708 -0.0139519 -0.736119 -0.703014 -0.0450156 -0.70975 -0.686236 -0.00666424 -0.727349 -0.724484 0 -0.689292 -0.642344 0.0084455 -0.76637 -0.612534 -0.0109072 -0.790369 -0.597009 -0.0231183 -0.801901 -0.579728 0 -0.81481 -0.500011 0 -0.866019 -0.523377 -0.047445 -0.850779 -0.464775 0.00811607 -0.885392 -0.837197 -0.0236791 -0.546388 -0.83534 -0.0192505 -0.549396 -0.858254 0 -0.513225 -0.875215 0 -0.483734 -0.817979 -0.00451454 -0.57523 -0.79084 0.00640888 -0.611989 -0.76582 -0.0246193 -0.642583 -0.761268 -0.0179914 -0.648188 -0.740682 0 -0.671855 -0.955312 0 -0.295598 -0.939615 -0.0132029 -0.341978 -0.945186 -0.0400575 -0.324066 -0.92674 0.00479945 -0.375674 -0.893602 -0.0089771 -0.44877 -0.901458 -0.0384864 -0.431152 -0.887018 -0.0137498 -0.461531 -0.99324 0 -0.11608 -0.994475 -0.0235732 -0.10229 -0.987478 -0.000916242 -0.157753 -0.981463 0.00136145 -0.191648 -0.972798 -0.0226528 -0.230545 -0.969043 -0.00423022 -0.246855 -0.959088 0 -0.283108 -0.83547 -0.00502784 0.549513 -0.834993 -0.00640833 0.550223 -0.886854 0.00550601 0.462017 -0.893526 -0.0150531 0.44876 -0.913853 0 0.406046 -0.939688 0 0.342032 -0.933136 -0.029827 0.358283 -0.97231 0.03878 0.230455 -0.968852 0 0.24764 -0.993237 0 0.116106 -0.988873 -0.0445558 0.141933 -0.997918 0.0644997 1.27947e-05 -0.997337 -0.0546543 0.048286 -0.999353 0 -0.0359701 0.038804 -3.97939e-05 0.999247 -0.0122661 -3.98191e-05 0.999925 -0.0581243 -0.0163892 0.998175 -0.075047 0.00645117 0.997159 -0.1757 -0.00777963 0.984413 -0.173634 -0.00436496 0.984801 -0.227973 0 0.973667 -0.286792 0 0.957993 -0.276933 -0.0174232 0.960731 -0.395985 0.0204818 0.918029 -0.386653 0 0.922225 -0.499988 0 0.866032 -0.521208 0.0429543 0.852348 -0.596972 -0.0243397 0.801893 -0.617206 0 0.786802 -0.686232 0 0.727382 -0.693633 0.0176666 0.720112 -0.765955 -0.0145203 0.64273 -0.772664 0 0.634816 -0.803972 0 0.594667 -0.996178 0 0.0873467 -0.997669 0.052113 0.0440508 -0.999095 0 -0.0425283 -0.991664 0 -0.128847 -0.963655 0.0779157 -0.255534 -0.97679 0 -0.2142 -0.907905 0 -0.419175 -0.887687 0.0521129 -0.457489 -0.845905 0 -0.533333 -0.741249 0 -0.67123 -0.709313 0.0779153 -0.700575 -0.796567 0 -0.604551 0.929002 0 0.370075 0.929002 0 0.370075 0.998175 0 -0.0603951 0.998175 0 -0.0603951 0.877605 0 -0.479384 0.877605 0 -0.479384 0.195103 0 0.980783 0.195103 0 0.980783 0.555581 0 0.831463 0.555581 0 0.831463 0.831477 0 0.55556 0.831477 0 0.55556 0.980788 0 0.195078 0.980788 0 0.195078 0.980783 0 -0.195103 0.980783 0 -0.195103 0.831462 0 -0.555581 0.831462 0 -0.555581 0.55556 0 -0.831477 0.55556 0 -0.831477 0.195078 0 -0.980788 0.195078 0 -0.980788 -0.195103 0 -0.980783 -0.195103 0 -0.980783 -0.555581 0 -0.831463 -0.555581 0 -0.831463 -0.831477 0 -0.55556 -0.831477 0 -0.55556 -0.980788 0 -0.195078 -0.980788 0 -0.195078 -0.980783 0 0.195103 -0.980783 0 0.195103 -0.831462 0 0.555581 -0.831462 0 0.555581 -0.55556 0 0.831477 -0.55556 0 0.831477 -0.195078 0 0.980788 -0.195078 0 0.980788 -0.342126 0.00696556 -0.939628 0.0329483 0.0111861 0.999394 0.0825452 0 0.996587 -0.329813 0 0.944046 -0.329813 0 0.944046 -0.7483 0 0.663361 -0.7483 0 0.663361 -0.976781 0 0.214239 -0.976781 0 0.214239 -0.957244 0 -0.289283 -0.957244 0 -0.289283 -0.694647 0 -0.719351 -0.694647 0 -0.719351 -0.358433 0 -0.933555 -0.400474 0.0184724 -0.916122 0.0823372 0.0108958 0.996545 -0.45256 0.0316524 -0.891172 -0.34828 0.0107093 -0.937329 -0.375666 0 -0.926755 -0.698649 0 -0.715464 -0.698649 0 -0.715464 -0.958502 0 -0.285087 -0.958502 0 -0.285087 -0.976095 0 0.217344 -0.976095 0 0.217344 -0.746985 0 0.664841 -0.746985 0 0.664841 -0.329078 0 0.944303 -0.329078 0 0.944303 -0.0314247 0 0.999506 0.0710694 0.00703088 0.997447 -0.0475286 0 -0.99887 0.422175 0 0.906514 0.374756 0.00819772 0.927087 0.716839 -0.00728603 0.697201 0.994497 0.000912846 0.104762 0.945909 -0.0123885 0.324196 0.961641 -0.00487499 0.274266 0.881386 2.75172e-05 0.472397 0.751136 -0.000171528 0.660147 0.994393 -0.00123815 -0.105738 0.976747 -0.00992779 -0.214165 0.947072 -0.000850034 -0.321019 -0.0145497 0.0044818 -0.999884 0.398953 -0.00654414 -0.916948 0.359369 0.000550504 -0.933195 0.701974 -0.000355483 -0.712202 0.758639 -0.00907003 -0.651448 0.84655 -0.000690471 -0.53231 0.894037 8.25276e-05 -0.447994 -0.0475337 0 -0.99887 0.231223 0 0.972901 0.374763 -0.00294101 0.927116 0.428968 0.00701237 0.903293 0.71477 -0.00874039 0.699305 0.71683 -0.00923328 0.697187 0.835715 -6.81793e-05 0.549163 0.880061 3.87437e-05 0.474861 0.961637 -0.00571465 0.274267 0.94316 -0.0167403 0.331919 0.976722 -0.0122155 -0.214159 0.995057 -0.00145154 -0.0992969 0.993707 0.00122253 0.112002 -0.0220347 0.00452903 -0.999747 0.393173 -0.00664421 -0.919441 0.359372 0.000916593 -0.933194 0.706587 -0.000610188 -0.707626 0.758625 -0.0108741 -0.651437 0.852578 -0.00039942 -0.5226 0.943837 0.000647946 -0.33041 0.992654 -0.00210577 -0.120969 0.976688 -0.0148499 -0.214151 0.93109 0.00227648 -0.364783 0.827977 -0.00231841 -0.560758 0.75858 -0.0154888 -0.651396 0.684258 -0.000674334 -0.72924 -0.0475337 0 -0.99887 -0.11255 -0.0210683 -0.993423 0.0468057 0.00328606 -0.998899 0.359356 -0.00730326 -0.933172 0.325188 -0.0178416 -0.945481 0.516927 0.000381215 -0.856029 0.368338 0 0.929692 0.374764 -0.00154033 0.927119 0.716796 -0.0133651 0.697155 0.750813 -0.0234914 0.660097 0.599959 0.000936955 0.80003 0.993925 0.00146194 0.110051 0.952723 -0.0174296 0.30334 0.961589 -0.0114742 0.274253 0.891316 0.000268855 0.453382 0.828199 -0.00030484 0.560435 0.988498 -0.00236299 -0.151218 0.659526 -0.0340977 -0.750908 0.75867 0.000732036 -0.651475 0.521994 -0.000191938 -0.852949 0.747766 -0.0161914 -0.663765 0.836089 -0.00012705 -0.548593 0.976795 0.00026609 -0.214176 0.914478 -0.0443511 -0.402199 0.942754 -0.0305485 -0.332086 -0.0475435 0 -0.998869 -0.117527 -0.0165652 -0.992932 0.0380634 0.000229997 -0.999275 0.359378 -0.000645039 -0.933192 0.229623 -0.0391742 -0.972491 0.383559 -0.0101927 -0.92346 0.434399 0 0.90072 0.374727 0.0155961 0.927004 0.716807 -0.0121822 0.697165 0.984023 0.00230989 0.178027 0.922854 -0.0302746 0.383958 0.961624 -0.00763941 0.274265 0.883625 5.32697e-05 0.468195 0.75989 -0.000266003 0.650052 0.965929 0 0.258807 0.707116 0 0.707098 0.707116 0 0.707098 0.258831 0 0.965923 0.258831 0 0.965923 -0.258806 0 0.965929 -0.258806 0 0.965929 -0.707099 0 0.707115 -0.707099 0 0.707115 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.258831 0 -0.965923 -0.258831 0 -0.965923 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707098 0.707115 0 0.707098 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.25883 0 -0.965923 -0.25883 0 -0.965923 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707099 0 -0.707115 0.707099 0 -0.707115 0.965923 0 -0.258832 0.965923 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707116 0 0.707098 0.707116 0 0.707098 0.258832 0 0.965923 0.258832 0 0.965923 -0.258806 0 0.965929 -0.258806 0 0.965929 -0.707099 0 0.707115 -0.707099 0 0.707115 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.258831 0 -0.965923 -0.258831 0 -0.965923 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965923 0 -0.258832 0.965923 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707116 0 0.707098 0.707116 0 0.707098 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.25883 0.965923 0 -0.25883 0.965929 0 0.258807 0.965923 0 -0.25883 0.965923 0 -0.25883 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258829 0 -0.965923 -0.258829 0 -0.965923 -0.707118 0 -0.707096 -0.707118 0 -0.707096 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258829 0 0.965923 0.258829 0 0.965923 0.707118 0 0.707096 0.707118 0 0.707096 0.965929 0 0.258808 0.965929 0 0.258808 0.965922 0 -0.258833 0.965922 0 -0.258833 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258813 0 -0.965928 0.258813 0 -0.965928 -0.258835 0 -0.965921 -0.258835 0 -0.965921 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.965922 0 0.258833 -0.965922 0 0.258833 -0.707101 0 0.707113 -0.707101 0 0.707113 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258835 0 0.965921 0.258835 0 0.965921 0.707115 0 0.707099 0.707115 0 0.707099 0.965929 0 0.258806 0.965929 0 0.258806 0.965923 0 -0.25883 0.965923 0 -0.25883 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258829 0 -0.965923 -0.258829 0 -0.965923 -0.707117 0 -0.707096 -0.707117 0 -0.707096 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258828 0 0.965923 0.258828 0 0.965923 0.707118 0 0.707096 0.707118 0 0.707096 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.258831 0.965923 0 -0.258831 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258828 0 0.965923 0.258828 0 0.965923 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.258829 0.965923 0 -0.258829 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258835 0 -0.965921 -0.258835 0 -0.965921 -0.707114 0 -0.7071 -0.707114 0 -0.7071 -0.96593 0 -0.258804 -0.96593 0 -0.258804 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258836 0 0.965921 0.258836 0 0.965921 0.707114 0 0.7071 0.707114 0 0.7071 0.965929 0 0.258806 0.965929 0 0.258806 0.965922 0 -0.258833 0.965922 0 -0.258833 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258821 0 -0.965925 -0.258821 0 -0.965925 -0.707122 0 -0.707092 -0.707122 0 -0.707092 -0.965928 0 -0.25881 -0.965928 0 -0.25881 -0.965923 0 0.258829 -0.965923 0 0.258829 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258836 0 0.965921 0.258836 0 0.965921 0.707114 0 0.7071 0.707114 0 0.7071 0.965929 0 0.258806 0.965929 0 0.258806 0.965923 0 -0.258831 0.965923 0 -0.258831 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.707118 0 -0.707095 -0.707118 0 -0.707095 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258828 0 0.965923 0.258828 0 0.965923 0.707118 0 0.707095 0.707118 0 0.707095 0.965929 0 0.258808 0.965929 0 0.258808 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258809 0 -0.965929 0.258809 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258832 0 0.965922 0.258832 0 0.965922 0.707116 0 0.707097 0.707116 0 0.707097 0.965929 0 0.258807 0.965929 0 0.258807 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.258827 0 -0.965924 -0.258827 0 -0.965924 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707096 0 -0.707118 0.707096 0 -0.707118 0.965923 0 -0.258829 0.965923 0 -0.258829 0.965929 0 0.258808 0.965929 0 0.258808 0.707121 0 0.707092 0.707121 0 0.707092 0.258827 0 0.965924 0.258827 0 0.965924 -0.258805 0 0.96593 -0.258805 0 0.96593 -0.707101 0 0.707112 -0.707101 0 0.707112 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965928 0 -0.25881 -0.965928 0 -0.25881 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.258837 0 -0.965921 -0.258837 0 -0.965921 0.258805 0 -0.96593 0.258805 0 -0.96593 0.7071 0 -0.707114 0.7071 0 -0.707114 0.965923 0 -0.25883 0.965923 0 -0.25883 0.96593 0 0.258804 0.96593 0 0.258804 0.707115 0 0.707099 0.707115 0 0.707099 0.258827 0 0.965924 0.258827 0 0.965924 -0.258805 0 0.96593 -0.258805 0 0.96593 -0.707096 0 0.707118 -0.707096 0 0.707118 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.258827 0 -0.965924 -0.258827 0 -0.965924 0.258804 0 -0.96593 0.258804 0 -0.96593 0.707102 0 -0.707112 0.707102 0 -0.707112 0.965922 0 -0.258833 0.965922 0 -0.258833 0.965929 0 0.258807 0.965929 0 0.258807 0.707116 0 0.707098 0.707116 0 0.707098 0.258827 0 0.965924 0.258827 0 0.965924 -0.258805 0 0.96593 -0.258805 0 0.96593 -0.707096 0 0.707118 -0.707096 0 0.707118 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.258837 0 -0.965921 -0.258837 0 -0.965921 0.258815 0 -0.965927 0.258815 0 -0.965927 0.707094 0 -0.707119 0.707094 0 -0.707119 0.965923 0 -0.25883 0.965923 0 -0.25883 0.96593 0 0.258804 0.96593 0 0.258804 0.707115 0 0.707099 0.707115 0 0.707099 0.258837 0 0.965921 0.258837 0 0.965921 -0.258815 0 0.965927 -0.258815 0 0.965927 -0.707096 0 0.707118 -0.707096 0 0.707118 -0.965922 0 0.258833 -0.965922 0 0.258833 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707118 0 -0.707096 -0.707118 0 -0.707096 -0.258827 0 -0.965924 -0.258827 0 -0.965924 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707099 0 -0.707115 0.707099 0 -0.707115 0.965922 0 -0.258833 0.965922 0 -0.258833 0.965929 0 0.258807 0.965929 0 0.258807 0.707116 0 0.707097 0.707116 0 0.707097 0.258832 0 0.965922 0.258832 0 0.965922 -0.25881 0 0.965928 -0.25881 0 0.965928 -0.707094 0 0.707119 -0.707094 0 0.707119 -0.965923 0 0.258829 -0.965923 0 0.258829 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707099 0 -0.707115 0.707099 0 -0.707115 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258808 0.965929 0 0.258808 0.707115 0 0.707099 0.707115 0 0.707099 0.258833 0 0.965922 0.258833 0 0.965922 -0.258804 0 0.96593 -0.258804 0 0.96593 -0.707099 0 0.707115 -0.707099 0 0.707115 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258837 0 -0.965921 -0.258837 0 -0.965921 0.258815 0 -0.965927 0.258815 0 -0.965927 0.707096 0 -0.707118 0.707096 0 -0.707118 0.965923 0 -0.258829 0.965923 0 -0.258829 0.965929 0 0.258806 0.965929 0 0.258806 0.707116 0 0.707098 0.707116 0 0.707098 0.258817 0 0.965926 0.258817 0 0.965926 -0.258795 0 0.965932 -0.258795 0 0.965932 -0.707095 0 0.707118 -0.707095 0 0.707118 -0.965923 0 0.258829 -0.965923 0 0.258829 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.258837 0 -0.965921 -0.258837 0 -0.965921 0.258795 0 -0.965932 0.258795 0 -0.965932 0.707107 0 -0.707107 0.707107 0 -0.707107 0.965921 0 -0.258836 0.965921 0 -0.258836 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707099 0.707115 0 0.707099 0.258838 0 0.965921 0.258838 0 0.965921 -0.258815 0 0.965927 -0.258815 0 0.965927 -0.707096 0 0.707118 -0.707096 0 0.707118 -0.965921 0 0.258836 -0.965921 0 0.258836 0.37349 0.84912 -0.373499 0.510201 0.849119 -0.136715 -0.373499 0.84912 -0.373489 -0.136715 0.84912 -0.510201 0.136702 0.84912 -0.510204 -0.373489 0.84912 0.3735 -0.5102 0.84912 0.136715 -0.510204 0.84912 -0.136702 0.373499 0.84912 0.373489 0.136715 0.84912 0.510201 -0.136702 0.84912 0.510204 0.510204 0.849119 0.136702 0.965923 0 -0.258831 0.965923 0 -0.258831 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707097 0 0.707117 -0.707097 0 0.707117 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707116 0 0.707097 0.707116 0 0.707097 0.965929 0 0.258807 0.965929 0 0.258807 0.373489 0.849119 -0.373499 0.510201 0.84912 -0.136715 -0.373499 0.84912 -0.37349 -0.136715 0.84912 -0.510201 0.136702 0.849119 -0.510205 -0.373489 0.84912 0.373499 -0.510201 0.84912 0.136715 -0.510204 0.84912 -0.136701 0.373499 0.84912 0.373489 0.136715 0.84912 0.5102 -0.136702 0.84912 0.510204 0.510204 0.84912 0.136702 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258831 0 0.965923 0.258831 0 0.965923 0.707117 0 0.707097 0.707117 0 0.707097 0.965929 0 0.258807 0.965929 0 0.258807 0.37349 0.84912 -0.373499 0.510201 0.849119 -0.136715 -0.373499 0.84912 -0.373489 -0.136715 0.84912 -0.510201 0.136702 0.84912 -0.510204 -0.373489 0.84912 0.3735 -0.5102 0.84912 0.136715 -0.510204 0.84912 -0.136702 0.373499 0.84912 0.373489 0.136715 0.84912 0.510201 -0.136702 0.84912 0.510204 0.510204 0.849119 0.136702 0.965923 0 -0.258831 0.965923 0 -0.258831 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707097 0 0.707117 -0.707097 0 0.707117 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707116 0 0.707097 0.707116 0 0.707097 0.965929 0 0.258807 0.965929 0 0.258807 0.373489 0.84912 -0.373499 0.5102 0.84912 -0.136715 -0.3735 0.84912 -0.373488 -0.136715 0.84912 -0.510201 0.136701 0.84912 -0.510204 -0.373488 0.84912 0.373501 -0.510201 0.84912 0.136713 -0.510204 0.849119 -0.136702 0.373499 0.84912 0.37349 0.136715 0.84912 0.510201 -0.136703 0.849119 0.510204 0.510204 0.84912 0.136702 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707118 0 -0.707096 -0.707118 0 -0.707096 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965923 0 0.258828 -0.965923 0 0.258828 -0.707094 0 0.70712 -0.707094 0 0.70712 -0.258808 0 0.965929 -0.258808 0 0.965929 0.258831 0 0.965923 0.258831 0 0.965923 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 -0.373499 -0.849119 -0.37349 -0.510204 -0.84912 -0.136702 0.373488 -0.849119 -0.373501 0.136702 -0.849119 -0.510205 -0.136717 -0.849119 -0.510201 0.373499 -0.84912 0.37349 0.510205 -0.849119 0.136702 0.510202 -0.849119 -0.136714 -0.373489 -0.84912 0.373498 -0.136699 -0.84912 0.510205 0.136713 -0.849119 0.510202 -0.510201 -0.84912 0.136715 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258835 0 -0.965922 -0.258835 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707095 0 -0.707119 0.707095 0 -0.707119 0.965923 0 -0.25883 0.965923 0 -0.25883 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707098 0.707115 0 0.707098 0.258828 0 0.965923 0.258828 0 0.965923 -0.258801 0 0.965931 -0.258801 0 0.965931 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.373498 -0.84912 -0.37349 -0.510204 -0.84912 -0.136702 0.37349 -0.849119 -0.3735 0.136702 -0.849119 -0.510205 -0.136715 -0.849119 -0.510201 0.373499 -0.849119 0.37349 0.510205 -0.849119 0.136702 0.510201 -0.849119 -0.136717 -0.373489 -0.84912 0.373498 -0.136702 -0.84912 0.510204 0.136715 -0.84912 0.510201 -0.5102 -0.84912 0.136716 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707114 0 -0.7071 -0.707114 0 -0.7071 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965922 0 -0.258835 0.965922 0 -0.258835 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707098 0.707115 0 0.707098 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.373498 -0.84912 -0.373489 -0.510203 -0.84912 -0.136702 0.37349 -0.849119 -0.373499 0.136702 -0.84912 -0.510204 -0.136715 -0.84912 -0.510201 0.373498 -0.849119 0.373491 0.510205 -0.849119 0.136702 0.510201 -0.849119 -0.136717 -0.37349 -0.84912 0.373499 -0.136702 -0.849119 0.510205 0.136715 -0.849119 0.510202 -0.5102 -0.84912 0.136717 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965922 0 -0.258835 0.965922 0 -0.258835 0.965929 0 0.258807 0.965929 0 0.258807 0.707114 0 0.7071 0.707114 0 0.7071 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.373498 -0.84912 -0.37349 -0.510203 -0.84912 -0.136702 0.37349 -0.849119 -0.373499 0.136702 -0.849119 -0.510205 -0.136715 -0.84912 -0.510201 0.373499 -0.849119 0.373491 0.510205 -0.849119 0.136702 0.510201 -0.849119 -0.136717 -0.37349 -0.84912 0.373498 -0.136702 -0.84912 0.510204 0.136715 -0.849119 0.510201 -0.5102 -0.84912 0.136716 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707114 0 -0.707099 -0.707114 0 -0.707099 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965922 0 -0.258834 0.965922 0 -0.258834 0.965929 0 0.258807 0.965929 0 0.258807 0.707114 0 0.707099 0.707114 0 0.707099 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707099 0 0.707115 -0.707099 0 0.707115 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.373499 -0.849119 -0.37349 -0.510205 -0.849119 -0.136702 0.373489 -0.84912 -0.373498 0.136702 -0.84912 -0.510204 -0.136715 -0.84912 -0.510201 0.373498 -0.84912 0.37349 0.510203 -0.84912 0.136702 0.5102 -0.84912 -0.136716 -0.37349 -0.849119 0.3735 -0.136702 -0.849119 0.510205 0.136715 -0.849119 0.510201 -0.510201 -0.849119 0.136717 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965922 0 -0.258834 0.965922 0 -0.258834 0.965929 0 0.258807 0.965929 0 0.258807 0.707114 0 0.7071 0.707114 0 0.7071 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.373498 -0.84912 -0.373489 -0.510204 -0.84912 -0.136701 0.373488 -0.849119 -0.373501 0.136702 -0.849119 -0.510205 -0.136713 -0.84912 -0.510201 0.373501 -0.849119 0.373488 0.510205 -0.849119 0.136702 0.510201 -0.849119 -0.136715 -0.373488 -0.84912 0.373501 -0.136702 -0.849119 0.510205 0.136713 -0.849119 0.510202 -0.510201 -0.84912 0.136715 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258828 0 -0.965923 -0.258828 0 -0.965923 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707095 0 -0.707119 0.707095 0 -0.707119 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707119 0 0.707095 0.707119 0 0.707095 0.258828 0 0.965923 0.258828 0 0.965923 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707095 0 0.707119 -0.707095 0 0.707119 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.373498 -0.84912 -0.373489 -0.510204 -0.84912 -0.136701 0.373489 -0.849119 -0.3735 0.136702 -0.849119 -0.510205 -0.136713 -0.84912 -0.510202 0.3735 -0.849119 0.373489 0.510205 -0.849119 0.136702 0.510201 -0.84912 -0.136716 -0.373488 -0.84912 0.373501 -0.136702 -0.849119 0.510205 0.136713 -0.849119 0.510202 -0.510201 -0.84912 0.136715 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258827 0 -0.965924 -0.258827 0 -0.965924 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707097 0 -0.707117 0.707097 0 -0.707117 0.965922 0 -0.258833 0.965922 0 -0.258833 0.965929 0 0.258807 0.965929 0 0.258807 0.707118 0 0.707096 0.707118 0 0.707096 0.258828 0 0.965923 0.258828 0 0.965923 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707095 0 0.707119 -0.707095 0 0.707119 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.373498 -0.84912 -0.37349 -0.510205 -0.84912 -0.136701 0.373489 -0.84912 -0.3735 0.136702 -0.849119 -0.510205 -0.136713 -0.84912 -0.510201 0.373501 -0.849119 0.373488 0.510205 -0.849119 0.136702 0.510201 -0.84912 -0.136715 -0.373489 -0.84912 0.3735 -0.136702 -0.849119 0.510205 0.136713 -0.84912 0.510201 -0.510201 -0.84912 0.136715 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258828 0 -0.965923 -0.258828 0 -0.965923 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707096 0 -0.707118 0.707096 0 -0.707118 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707119 0 0.707095 0.707119 0 0.707095 0.258828 0 0.965923 0.258828 0 0.965923 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707096 0 0.707118 -0.707096 0 0.707118 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.373499 -0.849119 -0.37349 -0.510204 -0.84912 -0.136702 0.373491 -0.849119 -0.373498 0.136702 -0.849119 -0.510205 -0.136716 -0.849119 -0.510201 0.373498 -0.84912 0.373491 0.510205 -0.84912 0.136701 0.510202 -0.849119 -0.136715 -0.37349 -0.84912 0.373498 -0.136702 -0.84912 0.510203 0.136717 -0.84912 0.5102 -0.5102 -0.84912 0.136717 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258834 0 -0.965922 -0.258834 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.7071 0 -0.707114 0.7071 0 -0.707114 0.965922 0 -0.258832 0.965922 0 -0.258832 0.96593 0 0.258804 0.96593 0 0.258804 0.707114 0 0.7071 0.707114 0 0.7071 0.258835 0 0.965922 0.258835 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.373501 -0.84912 -0.373488 -0.510205 -0.849119 -0.136702 0.373489 -0.84912 -0.373498 0.136701 -0.84912 -0.510204 -0.136715 -0.84912 -0.510201 0.3735 -0.849119 0.373489 0.510205 -0.849119 0.136702 0.510202 -0.84912 -0.136713 -0.373488 -0.849119 0.373501 -0.136702 -0.849119 0.510205 0.136715 -0.849119 0.510201 -0.510202 -0.849119 0.136713 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707119 0 -0.707095 -0.707119 0 -0.707095 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258806 0 -0.965929 0.258806 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965924 0 -0.258827 0.965924 0 -0.258827 0.965929 0 0.258807 0.965929 0 0.258807 0.707117 0 0.707097 0.707117 0 0.707097 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707095 0 0.707119 -0.707095 0 0.707119 -0.965923 0 0.258828 -0.965923 0 0.258828 -0.3735 -0.849119 -0.373489 -0.510205 -0.849119 -0.136702 0.37349 -0.84912 -0.373499 0.136701 -0.849119 -0.510205 -0.136715 -0.849119 -0.510201 0.373501 -0.84912 0.373488 0.510205 -0.849119 0.136702 0.510202 -0.849119 -0.136713 -0.373488 -0.84912 0.373501 -0.136702 -0.84912 0.510204 0.136715 -0.84912 0.510201 -0.510201 -0.84912 0.136713 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707117 0 -0.707097 -0.707117 0 -0.707097 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258806 0 -0.965929 0.258806 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965923 0 -0.258828 0.965923 0 -0.258828 0.965929 0 0.258807 0.965929 0 0.258807 0.707119 0 0.707095 0.707119 0 0.707095 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707095 0 0.707119 -0.707095 0 0.707119 -0.965923 0 0.258828 -0.965923 0 0.258828 -0.3735 -0.84912 -0.373489 -0.510205 -0.849119 -0.136702 0.37349 -0.84912 -0.373498 0.136701 -0.84912 -0.510205 -0.136715 -0.84912 -0.510201 0.3735 -0.849119 0.373489 0.510205 -0.849119 0.136702 0.510201 -0.84912 -0.136713 -0.373488 -0.849119 0.373501 -0.136702 -0.849119 0.510205 0.136715 -0.84912 0.510201 -0.510201 -0.84912 0.136713 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707118 0 -0.707096 -0.707118 0 -0.707096 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707099 0 -0.707115 0.707099 0 -0.707115 0.965923 0 -0.258828 0.965923 0 -0.258828 0.965929 0 0.258807 0.965929 0 0.258807 0.707118 0 0.707096 0.707118 0 0.707096 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707095 0 0.707119 -0.707095 0 0.707119 -0.965923 0 0.258828 -0.965923 0 0.258828 -0.373498 -0.849119 -0.373491 -0.510205 -0.849119 -0.136702 0.37349 -0.84912 -0.373499 0.136702 -0.849119 -0.510205 -0.136715 -0.849119 -0.510202 0.373498 -0.84912 0.373489 0.510203 -0.84912 0.136702 0.5102 -0.84912 -0.136717 -0.37349 -0.849119 0.373499 -0.136702 -0.84912 0.510204 0.136715 -0.84912 0.510201 -0.510201 -0.849119 0.136717 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707114 0 -0.7071 -0.707114 0 -0.7071 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965922 0 -0.258835 0.965922 0 -0.258835 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707098 0.707115 0 0.707098 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.373498 -0.84912 -0.373489 -0.510204 -0.84912 -0.136702 0.37349 -0.84912 -0.373498 0.136702 -0.84912 -0.510203 -0.136716 -0.84912 -0.5102 0.373498 -0.849119 0.373491 0.510205 -0.849119 0.136701 0.510201 -0.849119 -0.136715 -0.373491 -0.849119 0.373498 -0.136702 -0.849119 0.510205 0.136717 -0.849119 0.510201 -0.510201 -0.849119 0.136717 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258834 0 -0.965922 -0.258834 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.7071 0 -0.707114 0.7071 0 -0.707114 0.965922 0 -0.258832 0.965922 0 -0.258832 0.96593 0 0.258804 0.96593 0 0.258804 0.707114 0 0.7071 0.707114 0 0.7071 0.258835 0 0.965922 0.258835 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.373498 -0.84912 -0.373489 -0.510204 -0.84912 -0.136702 0.37349 -0.84912 -0.373498 0.136702 -0.84912 -0.510204 -0.136716 -0.84912 -0.5102 0.3735 -0.849119 0.37349 0.510205 -0.849119 0.136702 0.510201 -0.849119 -0.136715 -0.37349 -0.849119 0.373499 -0.136702 -0.849119 0.510205 0.136717 -0.849119 0.510201 -0.510201 -0.84912 0.136715 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258835 0 -0.965922 -0.258835 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.7071 0 -0.707114 0.7071 0 -0.707114 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707098 0.707115 0 0.707098 0.258835 0 0.965922 0.258835 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.373498 -0.84912 -0.37349 -0.510204 -0.84912 -0.136702 0.37349 -0.84912 -0.373498 0.136702 -0.84912 -0.510203 -0.136716 -0.84912 -0.5102 0.373499 -0.849119 0.37349 0.510205 -0.849119 0.136702 0.510201 -0.84912 -0.136715 -0.373491 -0.849119 0.373499 -0.136702 -0.849119 0.510205 0.136717 -0.849119 0.510201 -0.510201 -0.849119 0.136715 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.258835 0 -0.965922 -0.258835 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707099 0 -0.707114 0.707099 0 -0.707114 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707098 0.707115 0 0.707098 0.258834 0 0.965922 0.258834 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707099 0 0.707115 -0.707099 0 0.707115 -0.965922 0 0.258832 -0.965922 0 0.258832 0.965922 0 -0.258834 0.965922 0 -0.258834 0.707103 0 -0.707111 0.707103 0 -0.707111 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258839 0 -0.965921 -0.258839 0 -0.965921 -0.707112 0 -0.707102 -0.707112 0 -0.707102 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.965922 0 0.258834 -0.965922 0 0.258834 -0.707103 0 0.707111 -0.707103 0 0.707111 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258839 0 0.965921 0.258839 0 0.965921 0.707112 0 0.707102 0.707112 0 0.707102 0.96593 0 0.258805 0.96593 0 0.258805 -0.974745 0 -0.223322 -0.994181 0 0.107721 -0.99752 0.0149951 0.0687633 -0.999239 9.122e-06 -0.0390141 -0.974758 -3.3472e-05 -0.223264 -0.738237 0 0.674541 -0.668029 -0.0145078 0.743994 -0.314733 -0.0340289 0.94857 -0.385517 -0.00896275 0.922657 -0.592662 0.00623666 0.805427 0.167927 -4.60127e-05 0.985799 0.312114 -0.100951 0.944666 0.196695 -0.0468934 0.979343 0.0156475 0.00609519 0.999859 -0.199943 -0.00555153 0.979792 0.911339 0.0188218 0.411226 0.950927 -0.0924381 0.295286 0.846903 0.000120236 0.531748 0.611398 -0.000310585 0.791323 0.684574 -0.0766222 0.724906 0.502226 1.01894e-05 0.864737 0.888605 0 -0.458673 0.885206 -0.00364723 -0.465185 0.99786 0.00539867 -0.0651715 0.982662 -0.0790746 -0.167695 0.997607 -0.00643772 0.0688379 0.988642 0 -0.15029 0.999094 -0.0386331 -0.0178673 0.997499 -0.0569369 -0.0418791 0.998416 -0.0128287 0.054782 0.928638 0.0391017 0.368921 0.963623 -0.142186 0.226305 0.939597 -0.0568814 0.337523 0.912346 -0.0272324 0.408514 0.855505 0.0111132 0.517676 0.714876 -0.0180887 0.699017 0.703187 -0.0107164 0.710925 0.598486 0 0.801133 -0.508599 -0.694739 -0.508592 -0.508592 -0.694755 -0.508576 -0.186168 -0.69476 -0.69473 -0.186166 -0.694741 -0.694749 0.186148 -0.694741 -0.694754 0.186153 -0.694733 -0.694761 0.508595 -0.694736 -0.5086 0.508582 -0.694749 -0.508594 0.694743 -0.694747 -0.186167 0.694746 -0.694745 -0.186167 0.694749 -0.694747 0.186146 0.694752 -0.694743 0.186149 0.508599 -0.694739 0.508592 0.508592 -0.694755 0.508576 0.186168 -0.69476 0.69473 0.186166 -0.694741 0.694749 -0.186148 -0.694741 0.694754 -0.186153 -0.694733 0.694761 -0.508595 -0.694736 0.5086 -0.508582 -0.694749 0.508594 -0.694743 -0.694747 0.186167 -0.694746 -0.694745 0.186167 -0.694749 -0.694747 -0.186146 -0.694752 -0.694743 -0.186149 0.694749 0.694746 0.186148 0.508596 0.694747 0.508583 0.508597 0.694746 0.508584 0.186166 0.694746 0.694745 0.186166 0.694746 0.694745 -0.186149 0.694746 0.694749 -0.186147 0.694749 0.694747 -0.508581 0.69475 0.508594 -0.508584 0.694746 0.508596 -0.694745 0.694746 0.186166 -0.694742 0.694749 0.186166 -0.694748 0.694748 -0.186147 -0.694749 0.694746 -0.186148 -0.508597 0.694747 -0.508583 -0.508597 0.694746 -0.508584 -0.186165 0.694746 -0.694745 -0.186166 0.694746 -0.694745 0.186148 0.694746 -0.694749 0.186148 0.694746 -0.69475 0.508584 0.694745 -0.508597 0.508584 0.694746 -0.508597 0.694745 0.694746 -0.186166 0.694745 0.694746 -0.186166 0.694749 0.694746 0.186148 0.694748 0.694747 0.186148 0.508595 0.694749 0.508582 0.508596 0.694747 0.508584 0.186166 0.694746 0.694744 0.186166 0.694748 0.694743 -0.186147 0.694748 0.694747 -0.186148 0.694746 0.694749 -0.508583 0.694747 0.508597 -0.508584 0.694746 0.508597 -0.694745 0.694746 0.186165 -0.694745 0.694746 0.186166 -0.694749 0.694746 -0.186148 -0.69475 0.694746 -0.186148 -0.508598 0.694745 -0.508584 -0.508597 0.694746 -0.508583 -0.186166 0.694746 -0.694744 -0.186166 0.694744 -0.694747 0.186148 0.694744 -0.694752 0.186147 0.694746 -0.69475 0.508584 0.694746 -0.508596 0.508584 0.694746 -0.508596 0.694744 0.694746 -0.186166 0.694744 0.694747 -0.186166 0.694749 0.694747 0.186148 0.694749 0.694746 0.186148 0.508596 0.694747 0.508584 0.508595 0.694749 0.508582 0.186166 0.694747 0.694744 0.186166 0.694746 0.694745 -0.186149 0.694746 0.694749 -0.186147 0.694749 0.694747 -0.508581 0.69475 0.508594 -0.508584 0.694746 0.508596 -0.694745 0.694746 0.186166 -0.694742 0.694749 0.186166 -0.694748 0.694748 -0.186147 -0.694749 0.694746 -0.186148 -0.508596 0.694747 -0.508584 -0.508595 0.694749 -0.508582 -0.186166 0.694747 -0.694744 -0.186166 0.694746 -0.694745 0.186148 0.694746 -0.694749 0.186148 0.694746 -0.69475 0.508584 0.694745 -0.508597 0.508584 0.694746 -0.508597 0.694745 0.694746 -0.186166 0.694743 0.694748 -0.186166 0.694747 0.694748 0.186147 0.694749 0.694746 0.186148 0.508597 0.694747 0.508583 0.508597 0.694746 0.508584 0.186166 0.694746 0.694745 0.186166 0.694748 0.694743 -0.186147 0.694748 0.694748 -0.186148 0.694746 0.69475 -0.508584 0.694745 0.508597 -0.508582 0.694747 0.508596 -0.694744 0.694747 0.186166 -0.694747 0.694744 0.186166 -0.694751 0.694744 -0.18615 -0.694745 0.694751 -0.186146 -0.508593 0.694752 -0.50858 -0.508596 0.694746 -0.508585 -0.186166 0.694746 -0.694745 -0.186166 0.694748 -0.694743 0.186147 0.694748 -0.694748 0.186148 0.694746 -0.69475 0.508585 0.694745 -0.508597 0.508581 0.694749 -0.508595 0.69474 0.694751 -0.186166 0.694747 0.694744 -0.186166 0.694751 0.694744 0.18615 0.508579 0.694752 -0.508593 0.508578 0.694755 -0.508591 0.18615 0.694756 -0.694739 0.186149 0.694735 -0.69476 -0.186172 0.694734 -0.694755 -0.186159 0.694759 -0.694734 -0.508589 0.694756 -0.508578 -0.508599 0.694745 -0.508583 -0.69475 0.694746 -0.186148 -0.694746 0.694749 -0.186148 -0.694744 0.694747 0.186167 -0.694742 0.694749 0.186166 -0.508582 0.694753 0.50859 -0.508587 0.694742 0.5086 -0.186149 0.694738 0.694757 -0.186149 0.694735 0.69476 0.186172 0.694734 0.694755 0.186159 0.694759 0.694734 0.508589 0.694756 0.508578 0.508599 0.694745 0.508583 0.69475 0.694746 0.186148 0.694746 0.694749 0.186148 0.694744 0.694747 -0.186167 0.694742 0.694749 -0.186166 0.508584 0.694746 -0.508597 0.508584 0.694745 -0.508598 0.186147 0.694746 -0.69475 0.186147 0.694753 -0.694743 -0.186162 0.694753 -0.694739 -0.186168 0.694742 -0.694749 -0.508599 0.694743 -0.508586 -0.508597 0.694745 -0.508585 -0.69475 0.694746 -0.186147 -0.694749 0.694747 -0.186147 -0.694742 0.69475 0.186164 -0.694745 0.694746 0.186165 -0.508584 0.694746 0.508597 -0.508584 0.694745 0.508598 -0.186147 0.694746 0.69475 -0.186147 0.694751 0.694744 0.186162 0.694754 0.694738 0.186168 0.694742 0.694748 0.508599 0.694743 0.508586 0.508597 0.694745 0.508585 0.69475 0.694746 0.186148 0.694753 0.694743 0.186148 0.694746 0.694745 -0.186166 0.694745 0.694746 -0.186165 0.508584 0.694746 -0.508597 0.508582 0.694748 -0.508595 0.186149 0.694747 -0.694748 0.186149 0.694744 -0.694752 -0.186167 0.694744 -0.694747 -0.186168 0.694742 -0.694749 -0.5086 0.694742 -0.508586 -0.508597 0.694745 -0.508585 -0.69475 0.694746 -0.186148 -0.694748 0.694747 -0.186148 -0.694742 0.694749 0.186165 -0.694744 0.694746 0.186167 -0.508584 0.694746 0.508597 -0.508582 0.694748 0.508595 -0.186147 0.694747 0.694749 -0.186147 0.694753 0.694743 0.186165 0.694753 0.694739 0.186166 0.694751 0.69474 0.508595 0.694749 0.508581 0.508593 0.694751 0.50858 0.694747 0.694748 0.186148 0.694746 0.694749 0.186148 0.694744 0.694747 -0.186166 0.694744 0.694746 -0.186167 0.508588 0.694739 -0.508602 0.508588 0.69474 -0.508601 0.186149 0.694737 -0.694758 0.18615 0.694752 -0.694743 -0.186162 0.694753 -0.694739 -0.186167 0.694743 -0.694747 -0.508598 0.694745 -0.508583 -0.508599 0.694745 -0.508583 -0.694749 0.694746 -0.186149 -0.694755 0.69474 -0.186149 -0.694744 0.694747 0.186165 -0.694743 0.694748 0.186165 -0.508579 0.694752 0.508593 -0.508578 0.694755 0.508591 -0.186145 0.694756 0.694741 -0.186145 0.694753 0.694744 0.186162 0.694753 0.694739 0.186168 0.694742 0.694749 0.508601 0.694742 0.508585 0.508587 0.694758 0.508578 0.694745 0.69475 0.186147 0.694746 0.694749 0.186147 0.694744 0.694747 -0.186165 0.694747 0.694744 -0.186167 0.508588 0.694739 -0.508602 0.508587 0.694742 -0.5086 0.186149 0.694738 -0.694757 0.18615 0.694752 -0.694743 -0.186162 0.694753 -0.694739 -0.186168 0.694742 -0.694749 -0.508601 0.694742 -0.508585 -0.508599 0.694745 -0.508583 -0.694749 0.694746 -0.186149 -0.694755 0.69474 -0.186149 -0.694744 0.694747 0.186165 -0.694743 0.694748 0.186165 -0.508579 0.694752 0.508593 -0.508578 0.694755 0.508591 -0.186145 0.694756 0.694741 -0.186145 0.694753 0.694744 0.186162 0.694753 0.694739 0.186168 0.694742 0.694749 0.508601 0.694742 0.508585 0.508587 0.694758 0.508577 0.694745 0.694751 0.186148 0.694746 0.694749 0.186148 0.694744 0.694747 -0.186166 0.694747 0.694744 -0.186167 0.508588 0.694739 -0.508602 0.508594 0.694726 -0.508614 0.186154 0.694719 -0.694775 0.186154 0.694734 -0.694759 -0.186172 0.694734 -0.694755 -0.186159 0.694759 -0.694734 -0.508588 0.694756 -0.508579 -0.508598 0.694745 -0.508584 -0.694751 0.694745 -0.186147 -0.694746 0.69475 -0.186147 -0.694744 0.694747 0.186166 -0.694739 0.694753 0.186162 -0.50857 0.694765 0.508584 -0.508577 0.694752 0.508596 -0.186155 0.694756 0.694738 -0.186154 0.694734 0.69476 0.186172 0.694734 0.694755 0.186177 0.694725 0.694763 0.508606 0.69473 0.508597 0.508593 0.694744 0.50859 0.69475 0.694746 0.186148 0.694751 0.694745 0.186148 0.694748 0.694743 -0.186165 0.694748 0.694743 -0.186165 0.508579 0.694752 -0.508593 0.508579 0.694752 -0.508593 0.186145 0.694754 -0.694742 0.186145 0.694753 -0.694744 -0.186162 0.694753 -0.694739 -0.186168 0.694742 -0.694748 -0.5086 0.694744 -0.508584 -0.508586 0.694759 -0.508576 -0.694743 0.694753 -0.186147 -0.694749 0.694747 -0.186147 -0.694746 0.694745 0.186165 -0.694747 0.694744 0.186166 -0.508588 0.694739 0.508602 -0.508588 0.69474 0.508601 -0.186149 0.694737 0.694758 -0.18615 0.694752 0.694743 0.186162 0.694753 0.694739 0.186168 0.694742 0.694748 0.5086 0.694744 0.508584 0.508599 0.694745 0.508583 0.694749 0.694746 0.186149 0.694753 0.694742 0.186149 0.694742 0.69475 -0.186164 0.694743 0.694748 -0.186165 0.508588 0.694739 -0.508602 0.508582 0.694753 -0.50859 0.186145 0.694755 -0.694741 0.186145 0.69477 -0.694726 -0.186152 0.694772 -0.694723 -0.186177 0.694725 -0.694763 -0.508612 0.694729 -0.508591 -0.508598 0.694746 -0.508583 -0.694748 0.694747 -0.18615 -0.694756 0.694739 -0.18615 -0.694736 0.694756 0.186161 -0.694746 0.694744 0.186168 -0.508588 0.694739 0.508602 -0.508582 0.694753 0.50859 -0.186145 0.694755 0.694741 -0.186144 0.694736 0.694761 0.186172 0.694734 0.694755 0.186159 0.694759 0.694734 0.508588 0.694757 0.508578 0.508598 0.694745 0.508583 0.69475 0.694746 0.186147 0.694748 0.694748 0.186147 0.694745 0.694745 -0.186167 0.694746 0.694744 -0.186168 -0.599203 0.790429 -0.127191 -0.192659 0.980413 -0.0408952 -0.426851 0.896361 -0.11973 -0.773616 0.606224 -0.184421 -0.945491 0.256453 -0.200697 -0.95755 0.193516 -0.213658 -0.196451 0.980413 0.0140629 -0.25552 0.965281 -0.0542383 -0.260983 0.96499 0.0261211 -0.444658 0.895135 0.0318308 -0.610999 0.790422 0.0437382 -0.708728 0.70285 0.0608834 -0.695107 0.703602 -0.14755 -0.879017 0.438764 -0.186588 -0.978647 0.193241 0.0700533 -0.963583 0.256178 0.0766863 -0.896296 0.43879 0.0641602 -0.79421 0.604978 0.0568525 -0.999065 0 0.043237 -0.999065 0 0.043237 -0.976202 0 -0.216865 -0.976202 0 -0.216865 -0.697905 0.194383 -0.689307 -0.457874 0.8305 -0.317209 -0.157125 0.98512 -0.0696495 -0.0794921 0.99616 -0.0367011 -0.171049 0.980779 -0.0938836 -0.160948 0.980644 -0.111503 -0.160944 0.980645 -0.1115 -0.139303 0.980645 -0.137587 -0.139306 0.980644 -0.137589 -0.183408 0.980785 -0.0664937 -0.189255 0.980645 -0.050185 -0.189251 0.980645 -0.050184 -0.457873 0.8305 -0.317209 -0.505719 0.830501 -0.233488 -0.505727 0.830495 -0.233492 -0.538419 0.830494 -0.142773 -0.538407 0.830503 -0.14277 -0.637534 0.440999 -0.63172 -0.565233 0.607328 -0.55827 -0.396305 0.8305 -0.391423 -0.433607 0.792273 -0.429288 -0.315629 0.896212 -0.311741 -0.592259 0.55412 -0.584963 -0.684269 0.55412 -0.474053 -0.684269 0.554122 -0.474052 -0.755773 0.554121 -0.348937 -0.755757 0.554148 -0.348929 -0.80461 0.554148 -0.213359 -0.804633 0.554112 -0.213365 -0.972645 0.194912 -0.126376 -0.948157 0.194382 -0.251424 -0.948157 0.194383 -0.251424 -0.890588 0.194383 -0.41118 -0.890588 0.194383 -0.41118 -0.829681 0.194915 -0.523104 -0.402454 -0.871948 -0.278815 -0.781288 0.194918 -0.592955 -0.697904 0.19439 -0.689306 -0.195071 0.980645 -0.0167927 -0.195074 0.980645 -0.016793 -0.554963 0.830502 -0.0477742 -0.554963 0.830502 -0.0477741 -0.829375 0.554112 -0.071397 -0.829378 0.554107 -0.0713973 -0.487797 -0.871947 -0.0419922 -0.979933 0.194913 -0.0417126 -0.195047 0.980645 0.0171021 -0.195047 0.980645 0.0171021 -0.554886 0.830503 0.0486533 -0.554885 0.830503 0.0486533 -0.829263 0.554108 0.0727112 -0.82925 0.554128 0.0727103 -0.977176 0.194385 0.0856807 -0.977178 0.194376 0.0856808 0.911976 0.190571 0.363293 0.899766 0.253152 0.355436 0.837086 0.433694 0.33346 0.74361 0.599413 0.296223 0.665864 0.698867 0.261171 0.574196 0.786117 0.228735 0.418975 0.892527 0.166902 0.246475 0.964477 0.0950472 0.185529 0.979856 0.0739068 0.9657 0.252999 -0.0584302 0.965703 0.25299 -0.0584298 0.714353 0.69845 -0.0432219 0.714351 0.698452 -0.0432219 0.264274 0.964315 -0.0159899 0.264272 0.964316 -0.0159899 0.849056 0.25299 -0.463789 0.849052 0.253003 -0.463788 0.628064 0.698452 -0.343075 0.628066 0.698449 -0.343076 0.232351 0.964316 -0.12692 0.232352 0.964315 -0.12692 0.487072 0.431793 0.759155 0.14454 0.367347 -0.918784 0.530208 0.189647 0.826386 0.50711 0.861706 0.0174042 0.530209 0.189634 0.826389 0.801346 0.19315 0.566161 0.449554 0.855842 0.255804 0.9133 0.19422 0.357997 0.970877 0.193497 0.141273 0.976397 0.193957 -0.0950205 0.929347 0.193777 -0.314269 0.454921 0.863175 -0.219032 0.152768 0.183478 -0.971081 0.152831 0.189646 -0.969885 0.498198 0.193377 -0.845224 0.303929 0.860429 -0.409009 0.685798 0.194051 -0.701445 0.827223 0.193699 -0.52743 0.433022 0.597483 0.674912 0.454429 0.544472 0.705014 0.729134 0.54427 0.41489 0.729133 0.544271 0.41489 0.838415 0.544272 0.0287748 0.838422 0.544262 0.0287755 0.755862 0.54427 -0.363927 0.755866 0.544263 -0.363928 0.500367 0.544255 -0.673364 0.500353 0.544289 -0.673348 0.13037 0.544287 -0.828707 0.130369 0.54429 -0.828706 0.337339 0.784241 0.520738 0.306118 0.823803 0.477118 0.492703 0.823798 0.280357 0.492711 0.823792 0.280362 0.566566 0.823787 0.0194451 0.566546 0.823801 0.0194434 0.510768 0.823796 -0.24592 0.510776 0.82379 -0.245924 0.338122 0.823787 -0.455027 0.338121 0.823788 -0.455025 0.0880994 0.823786 -0.560013 0.0880996 0.823786 -0.560014 0.143653 0.963968 0.223897 0.105788 0.979472 0.171593 0.174429 0.979655 0.0992532 0.17443 0.979654 0.099254 0.200572 0.979655 0.00688346 0.200575 0.979654 0.00688375 0.180825 0.979654 -0.0870622 0.180821 0.979655 -0.0870602 0.119695 0.979656 -0.161079 0.119702 0.979654 -0.161088 0.0311887 0.979654 -0.198254 0.0311873 0.979656 -0.198247 0.369112 0.82458 0.428747 0.54684 0.545438 0.635188 0.132122 0.370201 -0.919508 0.246204 0.183976 0.951597 0.246163 0.190217 0.95038 0.610957 0.191728 0.768096 0.470568 0.692677 0.546593 0.139801 0.18396 -0.972941 0.139894 0.190212 -0.971725 0.522561 0.191726 -0.830766 0.407461 0.692644 -0.595164 0.696925 0.19493 -0.690144 0.855448 0.190179 -0.481707 0.855436 0.19024 -0.481703 0.980246 0.190214 -0.0541975 0.98025 0.190192 -0.0541967 0.903331 0.19021 0.384464 0.903329 0.190226 0.384463 0.768747 0.195 0.6091 0.546846 0.545424 0.635195 0.771207 0.54544 0.328231 0.771217 0.545423 0.328236 0.836864 0.545453 -0.0462699 0.836878 0.54543 -0.0462696 0.730327 0.545431 -0.411251 0.730322 0.545439 -0.411249 0.473484 0.545435 -0.691602 0.473499 0.545398 -0.691621 0.119212 0.545395 -0.829658 0.119206 0.545435 -0.829633 0.369107 0.824586 0.42874 0.520546 0.82459 0.221549 0.520544 0.824591 0.221548 0.564866 0.824592 -0.0312305 0.564863 0.824594 -0.0312304 0.492953 0.824587 -0.277585 0.492944 0.824594 -0.27758 0.319588 0.824593 -0.466809 0.31958 0.824602 -0.466798 0.0804588 0.824601 -0.559964 0.0804638 0.824583 -0.55999 0.0501201 0.979776 0.193719 0.050117 0.979779 0.193705 0.141709 0.824579 0.547712 0.141711 0.824572 0.547722 0.20994 0.545437 0.811433 0.209939 0.545449 0.811425 0.2328 0.369043 0.899784 0.119625 0.980252 0.157468 0.640567 -0.189877 0.744057 0.150439 0.980717 0.124747 0.184116 0.979776 0.0783615 0.184116 0.979776 0.0783615 0.199798 0.979775 -0.0110465 0.199799 0.979775 -0.0110465 0.174361 0.979775 -0.0981841 0.174368 0.979773 -0.0981875 0.113048 0.979772 -0.165125 0.113039 0.979776 -0.165113 0.0284596 0.979776 -0.198065 0.02846 0.979775 -0.198068 0.183289 0.186284 0.965248 0.148394 0.606024 0.781482 0.168274 0.43172 0.886173 0.048892 0.965047 0.257475 0.1141 0.791158 0.600874 0.0823969 0.186139 -0.979062 0.184402 0.255713 0.949003 0.551078 0.251001 0.795809 0.551075 0.251035 0.795801 0.868796 0.251037 0.426819 0.868802 0.251006 0.426824 0.966683 0.251014 -0.0501645 0.966677 0.251038 -0.0501655 0.819956 0.251002 -0.51446 0.819951 0.251024 -0.514458 0.46574 0.251022 -0.848572 0.465738 0.251033 -0.848569 0.0851887 0.255756 -0.962981 0.0756497 0.431552 -0.89891 0.137889 0.702766 0.69793 0.409076 0.695471 0.590743 0.40909 0.695443 0.590766 0.644948 0.695448 0.31685 0.644938 0.69546 0.316844 0.717591 0.695469 -0.0372392 0.717597 0.695462 -0.0372391 0.608667 0.695473 -0.381893 0.608686 0.69545 -0.381903 0.345744 0.695439 -0.629941 0.345735 0.695456 -0.629927 0.0596969 0.702323 -0.709351 0.0597016 0.702298 -0.709375 0.0488936 0.965043 0.257491 0.151897 0.963748 0.219355 0.151891 0.963752 0.219344 0.239469 0.96375 0.117646 0.239472 0.963749 0.117647 0.266457 0.963748 -0.0138276 0.266453 0.963749 -0.0138276 0.226013 0.963748 -0.141806 0.226005 0.96375 -0.141801 0.128372 0.96375 -0.233893 0.128376 0.963748 -0.233899 0.02198 0.965043 -0.261167 0.0219769 0.965049 -0.261148 0.0588017 0.963727 0.260332 0.158358 0.695256 0.7011 0.213275 0.250949 0.944213 0.213275 0.250854 0.944238 0.648529 0.250866 0.718663 0.648518 0.250951 0.718643 0.917441 0.250938 0.30876 0.917436 0.25096 0.308757 0.951067 0.250914 -0.180314 0.95106 0.250942 -0.180314 0.740751 0.250978 -0.623135 0.740768 0.250909 -0.623144 0.340473 0.250893 -0.906163 0.340478 0.250853 -0.906172 0.158356 0.695268 0.701089 0.481527 0.695275 0.533596 0.481524 0.69528 0.533592 0.68119 0.695287 0.22925 0.681199 0.695278 0.229254 0.706128 0.695313 -0.133877 0.706156 0.695284 -0.13388 0.550031 0.695256 -0.462693 0.549979 0.695322 -0.462656 0.252778 0.695339 -0.672761 0.25279 0.695309 -0.672787 0.058805 0.963721 0.260352 0.17882 0.963721 0.198156 0.178829 0.963717 0.198168 0.252985 0.963717 0.0851409 0.252989 0.963715 0.0851426 0.262256 0.963717 -0.0497211 0.262257 0.963716 -0.0497212 0.204268 0.963715 -0.171835 0.204279 0.963711 -0.171844 0.0938971 0.963708 -0.249902 0.0938884 0.963714 -0.249882 0.994181 0 -0.107723 0.980451 0.193185 -0.0373493 0.996413 -0.021918 0.0817414 0.935098 0.0629533 0.348754 0.932677 -0.000926231 0.360712 0.70276 0.000842658 0.711426 0.709465 0.0666152 0.701585 0.378573 -0.0570862 0.923809 0.390128 -4.81512e-06 0.920761 0.119837 -0.924504 -0.361845 0.381258 -0.270904 -0.883886 0.298793 -0.706963 -0.641036 0.320745 -0.707109 -0.630175 0.39865 -0.603561 -0.690502 0.387781 -0.633515 -0.66954 0.711548 -0.513517 -0.479583 0.802447 -0.278413 -0.527793 0.480954 -0.830857 -0.279928 0.851391 -0.303797 -0.427599 0.684429 -0.650797 -0.328664 0.594986 -0.682343 -0.424735 0.569438 -0.707099 -0.419228 0.54213 -0.706505 -0.454913 0.182182 -0.968125 -0.171884 0.485647 -0.706513 -0.514769 0.433875 -0.70686 -0.55866 0.564404 -0.32659 -0.758147 0.468003 -0.58922 -0.65863 0.385025 -0.725167 -0.570866 0.647955 -0.707103 -0.283124 0.665022 -0.706508 -0.242058 0.239946 -0.968125 -0.0718384 0.688634 -0.7065 -0.163218 0.702927 -0.7065 -0.0821696 0.250045 -0.968125 -0.0145667 0.707707 -0.706507 -9.07466e-06 0.704674 -0.706976 0.0601598 0.955178 -0.274176 0.111632 0.359441 -0.930274 0.0734312 0.688642 -0.706497 0.163202 0.670456 -0.706899 0.22535 0.900816 -0.284677 0.327857 0.463216 -0.804133 0.372561 0.675351 -0.472 0.566672 0.606218 -0.668571 0.430712 0.695377 -0.542866 0.470901 0.803249 -0.275137 0.528291 0.698012 -0.563541 0.441815 0.607388 -0.70708 0.362102 0.632425 -0.706516 0.317605 0.603313 -0.738312 0.301511 0.67027 -0.692004 0.268083 0.4002 -0.702768 0.588181 0.469066 -0.58767 0.659258 0.567937 -0.309042 0.762851 0.420746 -0.730843 0.53744 0.474764 -0.693459 0.541954 0.643896 -0.345873 0.682473 0.4951 -0.706831 0.505238 0.520035 -0.707079 0.479169 0.0577653 -0.968125 0.243717 0.389149 -0.707104 0.590396 0.353862 -0.706505 0.612889 0.112413 -0.968125 0.223826 0.280318 -0.706502 0.649828 0.202983 -0.706502 0.677977 0.122901 -0.706508 0.696951 0.0411585 -0.706509 0.706507 3.22438e-06 -0.968125 0.250468 -0.643875 -0.345888 0.682485 -0.495084 -0.706836 0.505248 -0.474747 -0.693464 0.541963 -0.420729 -0.730847 0.537447 -0.567918 -0.30904 0.762866 -0.469034 -0.5877 0.659253 -0.0411404 -0.706507 0.706509 -0.122883 -0.706507 0.696956 -0.0577587 -0.968125 0.243717 -0.202963 -0.70651 0.677974 -0.244025 -0.707107 0.663665 -0.302507 -0.645484 0.701313 -0.117768 -0.965419 0.232588 -0.353842 -0.706513 0.612891 -0.389115 -0.707111 0.590409 -0.400186 -0.702768 0.588191 -0.695363 -0.542869 0.470918 -0.80324 -0.275118 0.528314 -0.698027 -0.563494 0.441851 -0.606206 -0.668572 0.430727 -0.492755 -0.780264 0.385203 -0.735447 -0.279767 0.617129 -0.603954 -0.596569 0.52853 -0.520019 -0.707083 0.47918 -0.607387 -0.707072 0.36212 -0.632424 -0.706508 0.317626 -0.229984 -0.968125 0.0992088 -0.665031 -0.706499 0.242061 -0.688636 -0.706499 0.163219 -0.246664 -0.968124 0.0434967 -0.70292 -0.706507 0.0821688 -0.706958 -0.706956 0.0205793 -0.962616 -0.270871 1.2342e-05 -0.378736 -0.924912 -0.0331302 -0.702918 -0.706511 -0.0821502 -0.693901 -0.707043 -0.136351 -0.915758 -0.338063 -0.217027 -0.30994 -0.945544 -0.0994128 -0.665031 -0.706505 -0.242042 -0.639066 -0.706879 -0.30318 -0.851407 -0.303781 -0.427579 -0.480969 -0.830852 -0.279919 -0.802467 -0.278387 -0.527776 -0.711551 -0.513535 -0.47956 -0.594991 -0.68235 -0.424716 -0.640542 -0.358857 -0.678917 -0.424375 -0.7993 -0.425471 -0.590514 -0.618253 -0.518707 -0.735652 -0.278915 -0.61727 -0.553373 -0.706932 -0.440484 -0.569436 -0.707112 -0.419208 -0.385039 -0.725168 -0.570855 -0.468028 -0.589205 -0.658626 -0.564423 -0.326594 -0.758131 -0.433893 -0.706854 -0.558654 -0.464273 -0.707049 -0.533416 -0.387004 -0.689535 -0.612184 -0.451901 -0.427991 -0.782693 -0.345104 -0.70676 -0.617571 -0.280317 -0.706506 -0.649824 -0.0856684 -0.968125 -0.235363 -0.20298 -0.70651 -0.677969 -0.1229 -0.70651 -0.69695 -0.029081 -0.968124 -0.248776 -0.0411589 -0.706501 -0.706514 0.0336825 -0.706699 -0.706712 0.0504402 -0.49712 -0.866214 0.0897941 -0.835128 -0.542676 0.122883 -0.706508 -0.696955 0.202963 -0.706508 -0.677977 -0.979938 0 0.199303 -0.979938 0 0.199303 -0.983905 0 0.178694 -0.983935 -1.43622e-05 0.178528 -0.991689 9.91644e-07 0.128661 -0.991687 0 0.128671 -0.987795 0 0.15576 -0.987625 -9.4334e-05 0.156835 -0.985987 -1.4361e-05 0.166824 -0.997237 5.72528e-07 0.0742827 -0.997237 0 0.0742806 -0.999848 0 -0.0174506 -0.999848 3.01703e-06 -0.01744 -0.997419 4.40699e-06 -0.0717978 -0.997427 0 -0.0716935 -0.996144 0 -0.0877389 -0.996144 0 -0.0877389 -0.994768 0 -0.102161 -0.994768 0 -0.102161 -0.992974 0 -0.118331 -0.992974 0 -0.118331 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.47441e-05 0 -1 -1.47441e-05 0 -1 -1.251e-05 1.80634e-06 -1 -1.28086e-05 0 -1 0.800332 0 -0.599557 0.751023 0.000751908 -0.660276 0.528367 -0.000436966 -0.849016 0.459963 4.90201e-06 -0.887938 0.18447 -7.82725e-06 -0.982838 0.183671 0 -0.982988 0.158672 0.779953 -0.605389 0.156697 0.156698 -0.975137 0.438533 0.0645329 -0.896395 0.0762876 0.259051 -0.962846 0.229467 0.100025 -0.968163 0.349513 0.504579 -0.789456 0.725769 0.115031 -0.678254 0.612511 0.248089 -0.750521 0.45999 0.459991 -0.759485 0.459988 0.459992 -0.759486 0.24809 0.612512 -0.75052 0.071563 0.445783 -0.892276 0.308649 0.911185 -0.272907 0.841447 0.258472 -0.47451 0.862884 0.23929 -0.445165 0.639079 0.602216 -0.47845 0.617618 0.617618 -0.486925 0.473022 0.784123 -0.401748 0.110162 0.933106 -0.342312 -1.85569e-07 0.999912 -0.0132443 0.000330243 0.973941 -0.226801 0.000493987 0.97539 -0.220484 -0.000550991 0.781487 -0.623922 -0.00198822 0.812659 -0.582736 0.000224789 0.632282 -0.774738 -0.000417504 0.472421 -0.881373 -0.000369955 0.46957 -0.882895 0.00049395 0.194153 -0.980971 -1.45292e-05 0.170227 -0.985405 9.31218e-05 0.591996 -0.805941 -6.35001e-05 0.79062 -0.612307 0.000209581 0.870367 -0.492404 -0.000346618 0.965094 -0.261905 -1.90428e-06 0.988488 -0.1513 -1.24906e-05 0.0557035 -0.998447 0.000101612 0.162533 -0.986703 0.000199961 0.209772 -0.97775 1.73904e-05 0.299165 -0.954201 -6.18751e-05 0.555674 -0.8314 0.0380466 0.184867 -0.982027 -0.090183 0.0901834 -0.991834 -0.965758 0.259057 -0.0141566 -0.258793 0.965829 -0.0141604 -0.259 0.965731 -0.0167964 -0.60866 0.793221 -0.0182931 -0.592593 0.592593 -0.545589 -0.793221 0.608659 -0.0182889 -0.96579 0.258783 -0.0167814 -0.247853 0.939885 -0.234913 -0.293151 0.915645 -0.275057 -0.676704 0.676704 -0.290074 -0.676704 0.676704 -0.290074 -0.93129 0.244873 -0.269695 -0.557503 0.340999 -0.756909 -0.806741 0.172235 -0.565247 -0.922223 0.306142 -0.236182 -0.0513278 0.455904 -0.888548 -0.132837 0.356584 -0.924771 -0.261591 0.261592 -0.929053 -0.261591 0.261592 -0.929053 -0.130336 0.754202 -0.643578 -0.253788 0.649401 -0.716847 -0.484961 0.484961 -0.727754 -0.484961 0.484962 -0.727753 -0.649403 0.253789 -0.716845 -0.427527 0.0249495 -0.903658 -0.405972 0.184815 -0.895003 -0.184868 -0.0380465 -0.982027 -0.979129 0.194752 0.0581304 -0.962978 0.258029 -0.0780627 -0.819511 0.55501 0.14271 -0.792476 0.608088 0.047032 -0.555264 0.831021 0.032954 -0.591707 0.771127 0.235043 -0.21703 0.94992 -0.224833 -0.258789 0.965812 0.0153568 -0.998242 0 0.0592651 -0.998242 0 0.0592651 -0.999912 0 -0.0132362 -0.97539 -0.000316424 -0.220487 -0.988458 0.00136195 -0.151487 -0.840318 -0.00138048 -0.542092 -0.870314 2.71295e-05 -0.492498 -0.675765 -1.26653e-05 -0.737117 -0.592754 -0.00125526 -0.805383 -0.4724 0.000492206 -0.881384 -0.1706 -0.000946074 -0.98534 -0.209582 0 -0.977791 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.123518 -0.965089 -0.230968 -0.189738 -0.965089 -0.180561 -0.189738 -0.965089 -0.180561 -0.515496 -0.702574 -0.490564 -0.515496 -0.702574 -0.490565 -0.700316 -0.255749 -0.666446 -0.700315 -0.255747 -0.666448 -0.123518 -0.965089 -0.230968 -0.335584 -0.702573 -0.627515 -0.335585 -0.702574 -0.627513 -0.455901 -0.255749 -0.852494 -0.455901 -0.255749 -0.852494 0.245611 -0.25157 -0.936156 0.245611 -0.25157 -0.936156 -0.224356 -0.251571 -0.941476 -0.224357 -0.251572 -0.941475 -0.641418 -0.251571 -0.724773 -0.641417 -0.25157 -0.724774 0.182149 -0.696286 -0.694268 0.182151 -0.696285 -0.694268 -0.166387 -0.696285 -0.698214 -0.166387 -0.696285 -0.698214 -0.475685 -0.696285 -0.537504 -0.475685 -0.696286 -0.537503 0.0675665 -0.963905 -0.257529 0.0675666 -0.963905 -0.257529 -0.0617188 -0.963905 -0.258993 -0.0617183 -0.963905 -0.258993 -0.176449 -0.963905 -0.19938 -0.176449 -0.963905 -0.199381 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.509434 -0.252826 -0.82253 -0.814394 -0.252825 -0.522343 -0.814393 -0.252825 -0.522344 -0.602612 -0.69819 -0.38651 -0.602612 -0.69819 -0.38651 -0.223005 -0.964267 -0.143033 -0.223005 -0.964267 -0.143033 -0.509434 -0.252825 -0.822531 -0.376957 -0.698188 -0.608635 -0.376959 -0.69819 -0.608633 -0.139499 -0.964267 -0.225233 -0.139499 -0.964267 -0.225232 -0.724406 0 -0.689373 -0.724406 0 -0.689373 -0.471584 0 -0.881821 -0.471584 0 -0.881821 0.550608 -0.598736 0.581675 -0.845438 -0.252575 0.470574 -0.845437 -0.252576 0.470575 -0.552452 -0.252576 0.794357 -0.552453 -0.252574 0.794356 -0.146951 -0.252574 0.956353 -0.146951 -0.252575 0.956353 0.28848 -0.252574 0.923572 0.288481 -0.252575 0.923572 0.665158 -0.252575 0.702689 0.665158 -0.252576 0.702688 -0.625865 -0.69781 0.34836 -0.625867 -0.697809 0.348358 -0.408973 -0.697809 0.58805 -0.408973 -0.697809 0.58805 -0.108785 -0.697809 0.707974 -0.108784 -0.69781 0.707974 0.213558 -0.69781 0.683706 0.213558 -0.69781 0.683706 0.421267 -0.705123 0.570382 0.425362 -0.785583 0.449364 -0.231719 -0.964195 0.128975 -0.231718 -0.964195 0.128976 -0.151417 -0.964195 0.217718 -0.151417 -0.964195 0.217718 -0.040276 -0.964195 0.262119 -0.040275 -0.964195 0.262118 0.0790674 -0.964195 0.253134 0.0790661 -0.964195 0.253135 0.182307 -0.964195 0.192594 0.182308 -0.964195 0.192593 0.677018 -0.696429 -0.237976 0.970953 -0.189539 0.14603 0.962304 -0.254262 0.0965499 0.913051 -0.251665 -0.320941 0.91305 -0.251666 -0.320943 0.656497 -0.251666 -0.711109 0.656498 -0.251666 -0.711108 0.486786 -0.69643 -0.527281 0.180534 -0.963933 -0.195553 0.180534 -0.963933 -0.195553 0.251086 -0.963933 -0.0882585 0.891989 -0.431692 0.134157 0.79313 -0.597257 0.119288 0.709647 -0.704101 0.0253467 0.613329 -0.784422 0.0922462 0.447981 -0.891501 0.0673774 0.486787 -0.696429 -0.52728 0.677018 -0.69643 -0.237976 0.251086 -0.963933 -0.0882583 0.254227 -0.965339 -0.0590656 0.198559 -0.979634 0.0298623 -0.719567 0 -0.694424 -0.662718 -0.00638105 -0.748842 -0.529419 0 -0.84836 -0.346993 0 -0.937868 -0.231805 -0.00732193 -0.972735 0.333215 0 -0.942851 0.253767 -0.00656112 -0.967243 0.0943072 0 -0.995543 -0.108885 0 -0.994054 0.124502 -0.965926 -0.226906 0.124502 -0.965926 -0.226907 0.340146 -0.707107 -0.61992 0.340145 -0.707108 -0.619919 0.464648 -0.258819 -0.846826 0.464648 -0.258818 -0.846827 0.77106 -0.191392 0.607318 0.771559 -0.254978 0.582824 0.932215 -0.254059 0.257739 0.932215 -0.254057 0.25774 0.707268 -0.43525 0.557072 0.627795 -0.601138 0.494476 0.576022 -0.702601 0.417793 0.770248 -0.601138 0.212959 0.677798 -0.702601 0.216662 0.594079 -0.787459 0.164252 0.254122 -0.964617 0.0702601 0.254122 -0.964617 0.07026 0.156215 -0.980029 0.123041 0.218281 -0.965552 0.141645 0.35303 -0.893338 0.27806 0.484208 -0.787459 0.381381 0.136844 -0.980693 0.139695 0.155038 -0.980693 0.119182 0.136845 -0.980693 0.139695 0.310118 -0.896441 0.316577 0.385506 -0.830635 0.401783 0.200875 -0.965579 0.165245 0.444946 -0.830635 0.334765 0.483383 -0.792629 0.371592 0.659702 -0.554625 0.507134 0.634715 -0.608092 0.476824 0.627916 -0.441415 0.640995 0.578176 -0.554425 0.598603 0.55568 -0.607817 0.567255 0.42666 -0.792628 0.435547 0.6864 -0.194628 0.700697 0.686399 -0.194629 0.700696 0.770483 -0.194772 0.606976 0.765926 -0.258226 0.588793 0.186224 -0.980664 0.0601574 0.193458 -0.980664 0.0295367 0.186224 -0.980664 0.0601572 0.421972 -0.896303 0.136312 0.527654 -0.830286 0.179463 0.255635 -0.96538 0.0518843 0.552182 -0.830286 0.0756314 0.603015 -0.792399 0.0920669 0.822766 -0.554325 0.125618 0.78675 -0.607981 0.106692 0.853987 -0.441138 0.275869 0.789467 -0.553975 0.264299 0.755847 -0.607519 0.244166 0.580468 -0.792399 0.187512 0.933412 -0.194484 0.301526 0.933412 -0.194485 0.301526 0.966824 -0.194725 0.165329 0.955068 -0.258036 0.145818 -0.250938 -0.965683 -0.0669838 -0.250938 -0.965683 -0.0669838 -0.257604 -0.965805 -0.0293369 -0.257604 -0.965805 -0.029337 -0.25926 -0.965805 0.00222753 -0.259259 -0.965805 0.00222763 -0.25722 -0.965836 0.0316059 -0.25722 -0.965836 0.031606 -0.25247 -0.965836 0.0584796 -0.25247 -0.965836 0.0584796 -0.684462 -0.705783 -0.182706 -0.684464 -0.705781 -0.182707 -0.70322 -0.706447 -0.0800857 -0.703219 -0.706449 -0.0800853 -0.707738 -0.706448 0.00608092 -0.707739 -0.706448 0.00608083 -0.702316 -0.706616 0.0862974 -0.702316 -0.706615 0.0862973 -0.689347 -0.706615 0.159673 -0.689346 -0.706617 0.159673 -0.933483 -0.257916 -0.249178 -0.933482 -0.257918 -0.249177 -0.959841 -0.258372 -0.109311 -0.959841 -0.258371 -0.109311 -0.96601 -0.258371 0.0083005 -0.966011 -0.258369 0.0083 -0.958805 -0.258483 0.117813 -0.958804 -0.258484 0.117814 -0.941099 -0.258484 0.217986 -0.941099 -0.258484 0.217986 -0.842461 0 -0.538757 -0.84174 -0.000143914 -0.539883 -0.527678 0.000144871 -0.849445 -0.52654 0 -0.85015 0.481039 -3.16649e-06 -0.876699 0.481039 0 -0.876699 0.481039 0 -0.876699 0.481039 1.68282e-05 -0.876699 0.481039 -8.45158e-06 -0.876699 0.481039 1.63207e-05 -0.876699 0.481039 -3.69956e-05 -0.876699 0.951582 0 0.307396 0.972743 -0.0310724 0.229796 0.988545 0 0.15093 0.699781 0 0.714357 0.699781 0 0.714357 0.792815 0 0.609463 0.792815 0 0.609463 0.96384 0 0.266483 0.96384 0 0.266483 0.785583 0 0.618756 0.785583 0 0.618756 0.67833 0 -0.734757 0.67833 0 -0.734757 0.943415 0 -0.331614 0.943415 0 -0.331614 0.988878 0 0.148726 0.988878 0 0.148726 -0.974207 0 0.225655 -0.984496 0.0221164 0.174005 -0.992535 0 0.121958 -0.800891 0.55412 -0.226992 -0.526753 0.836644 -0.150192 -0.894669 0.368471 -0.252579 -0.931088 0.255111 -0.260755 -0.941056 0.213873 -0.262052 -0.999963 0 0.00859224 -0.998189 0.0296368 -0.0523546 -0.993578 0 -0.113153 -0.966171 0 -0.257904 -0.966171 0 -0.257904 0.687446 0 0.726235 0.687446 0 0.726235 0.298147 0 0.95452 0.298147 0 0.95452 -0.151875 0 0.9884 -0.151875 0 0.9884 -0.570964 0 0.820975 -0.570964 0 0.820975 -0.873768 0 0.486343 -0.873768 0 0.486343 -0.521224 -0.175268 -0.835229 -0.0205646 -0.984232 -0.175684 -0.128213 -0.983998 -0.123733 -0.12821 -0.983998 -0.123731 -0.391784 -0.838778 -0.378097 -0.391785 -0.838777 -0.378098 -0.608463 -0.533819 -0.587205 -0.608466 -0.533814 -0.587207 -0.708659 -0.173447 -0.683899 -0.708661 -0.173438 -0.683899 0.0928485 -0.1752 -0.980145 0.305806 -0.397173 -0.865296 0.278499 -0.174772 -0.944401 0.222215 -0.562168 -0.79661 0.24092 -0.587995 -0.772152 -0.0752782 -0.983781 -0.162816 -0.0752795 -0.98378 -0.162818 -0.229613 -0.837047 -0.496619 -0.229614 -0.837046 -0.49662 -0.355569 -0.531174 -0.769042 -0.355567 -0.531179 -0.769039 -0.409766 0.215933 -0.886265 -0.341671 -0.174462 -0.923485 -0.0167252 -0.986336 -0.163893 -0.02342 -0.931045 -0.364152 -0.00888422 -0.836529 -0.54785 -0.0324043 -0.596207 -0.802176 -0.0220027 -0.531177 -0.846975 -0.0253162 0.222843 -0.974526 -0.107214 -0.174556 -0.978793 -0.710829 -0.192703 -0.676453 -0.711339 -0.173558 -0.681083 -0.607076 -0.550413 -0.573152 -0.612358 -0.534259 -0.58274 -0.406019 -0.828166 -0.386381 -0.396076 -0.839298 -0.372427 -0.1407 -0.980391 -0.137976 -0.128932 -0.984034 -0.122696 -0.0931372 -0.980303 -0.174159 -0.0931371 -0.980303 -0.174159 -0.264314 -0.828166 -0.494246 -0.264315 -0.828165 -0.494247 -0.393643 -0.550667 -0.736079 -0.393645 -0.550662 -0.736081 -0.439898 -0.360375 -0.822569 -0.46512 -0.192786 -0.864 -0.464421 -0.173637 -0.868426 -0.427158 -0.852122 -0.302366 -0.0515617 -0.99453 -0.0908429 -0.412642 -0.833095 -0.368347 -0.651278 -0.537147 -0.536012 -0.612494 -0.6469 -0.454281 -0.798353 -0.173473 -0.576663 -0.722997 -0.513322 -0.462359 -0.109071 -0.979643 -0.168535 -0.290652 -0.825713 -0.483445 -0.272646 -0.856173 -0.438899 -0.442137 -0.545838 -0.711742 -0.445701 -0.529204 -0.722007 -0.493019 -0.356443 -0.79365 -0.519859 -0.171519 -0.836856 -0.519857 -0.171528 -0.836855 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.617619 -0.754664 -0.221425 0.629707 -0.753451 -0.189157 0.353868 -0.923905 -0.145526 0.450012 -0.881743 -0.141489 0.412052 -0.89683 -0.160962 0.324777 -0.940118 -0.103432 0.300195 -0.946677 -0.116985 0.327966 -0.939398 -0.0998501 0.258794 -0.917517 -0.301973 0.331132 -0.924537 -0.188632 0.305854 -0.924105 -0.229094 0.309765 -0.920324 -0.238852 0.279607 -0.916603 -0.285759 0.268417 -0.924761 -0.269759 0.258462 -0.91757 -0.302097 0.257847 -0.918673 -0.299258 0.41117 -0.785694 -0.462196 0.402016 -0.830624 -0.385288 0.337711 -0.886892 -0.315236 0.651005 -0.493883 -0.57643 0.672044 -0.473221 -0.569578 0.610067 -0.524823 -0.593616 0.644047 -0.497796 -0.580864 0.654669 -0.498126 -0.568577 0.669495 -0.483609 -0.563825 0.595739 -0.665907 -0.449069 0.605609 -0.657798 -0.447816 0.656714 -0.716203 -0.236177 0.633875 -0.738738 -0.22906 0.611609 -0.736656 -0.28857 0.259985 -0.916413 -0.304293 0.267558 -0.921961 -0.280001 0.33475 -0.887884 -0.315601 0.364128 -0.890006 -0.27441 0.362027 -0.89309 -0.267072 0.545902 -0.817327 -0.184305 0.540189 -0.820545 -0.186823 0.505144 -0.822774 -0.260523 0.649669 -0.681589 -0.336699 0.601817 -0.715908 -0.353965 0.325414 -0.940024 -0.102276 0.325879 -0.939807 -0.102788 0.300262 -0.946652 -0.117014 0.347834 -0.927672 -0.135781 0.324871 -0.929419 -0.175038 0.387948 -0.897509 -0.209699 0.397214 -0.893824 -0.208084 0.508125 -0.81866 -0.267589 0.462072 -0.817455 -0.343884 0.468402 -0.813975 -0.343575 0.431968 -0.811554 -0.393427 0.562442 -0.647422 -0.514299 0.356009 -0.0248682 -0.934152 0.127122 -0.080128 -0.988645 0.276245 -0.712738 -0.644743 -0.750481 -0.132392 -0.647496 -0.791059 -0.233007 -0.565626 -0.600954 -0.11356 -0.791175 -0.665053 -0.225771 -0.711851 -0.350213 -0.158145 -0.923223 -0.312401 -0.103127 -0.944336 -0.0820657 -0.0176082 -0.996471 0.340401 -0.670233 -0.659481 0.396992 -0.383773 -0.833736 0.363736 -0.424042 -0.829388 -0.0139401 -0.165456 -0.986119 -0.0140866 -0.163177 -0.986496 -0.242126 -0.250113 -0.937453 -0.1898 -0.489923 -0.850853 -0.179126 -0.478408 -0.859674 0.100257 -0.891811 -0.44116 0.0833129 -0.920114 -0.382688 0.186246 -0.859608 -0.4758 0.148782 -0.893119 -0.424502 0.275528 -0.836298 -0.474015 0.252577 -0.851078 -0.460295 0.315299 -0.853931 -0.413991 -0.540221 -0.477338 -0.693044 -0.565229 -0.548938 -0.615779 -0.414963 -0.446892 -0.792523 -0.46376 -0.533369 -0.707421 -0.347972 -0.472822 -0.80954 -0.441103 -0.10327 -0.891495 -0.486579 -0.169347 -0.857066 0.390571 -0.149963 -0.908276 0.385462 -0.165981 -0.907672 0.0275545 -0.250645 -0.967687 0.0446688 -0.464375 -0.884511 0.101413 -0.377016 -0.920638 0.13379 -0.678298 -0.722504 -0.0582649 -0.744528 -0.665044 -0.017944 -0.681853 -0.731269 -0.187934 -0.777744 -0.59983 -0.168239 -0.752548 -0.636685 -0.282721 -0.785982 -0.549819 -0.23828 -0.776863 0.582844 -0.495592 -0.303978 0.813625 -0.0295452 -0.909793 0.41401 -0.0342543 -0.945574 0.323598 0.149718 -0.970768 0.187603 0.558173 -0.819886 -0.127394 0.578216 -0.813311 0.0647442 0.371349 -0.927962 0.0314127 0.140678 -0.966186 0.216088 0.0244396 -0.511014 0.859225 0.080034 -0.385932 0.919049 0.185227 -0.653207 0.734174 0.235632 -0.559054 0.794944 0.324597 -0.738639 0.590804 -0.21237 -0.100438 0.972014 -0.18386 -0.111244 0.976637 -0.123328 -0.0644954 0.990268 0.255626 -0.141612 0.956348 0.298186 -0.386247 0.872868 0.531532 -0.388275 0.752806 0.488932 -0.47108 0.734186 0.5116 -0.656689 0.554099 0.171816 -0.482443 0.858911 0.238099 -0.346834 0.907202 0.309241 -0.615357 0.725056 0.371118 -0.510594 0.775607 0.429364 -0.718072 0.54774 0.444496 -0.699137 0.560028 0.490684 -0.802797 0.338743 0.527309 -0.749991 0.399323 0.569341 -0.821683 0.0262317 -0.554519 -0.0256426 0.831776 -0.514991 -0.0855916 0.852912 -0.662308 -0.113992 0.74051 -0.43328 -0.814955 0.384859 -0.621645 -0.623467 0.474179 -0.649303 -0.607019 0.458185 -0.770293 -0.385086 0.508289 -0.795662 -0.36066 0.486669 -0.819014 -0.102445 0.564553 -0.864972 0.0350345 0.500596 -0.706546 -0.141482 0.69338 -0.658285 -0.332118 0.675543 -0.602265 -0.367895 0.708471 -0.501667 -0.567738 0.65269 -0.299764 -0.0766635 0.950928 -0.360379 -0.121066 0.924916 -0.324472 -0.27948 0.903664 -0.413479 -0.339603 0.844811 -0.331836 -0.523566 0.784706 -0.44393 -0.589917 0.674481 -0.290275 -0.769077 0.569439 -0.407591 -0.822703 0.396271 -0.168942 -0.947691 0.270815 0.626491 -0.779121 0.0219165 0.601171 -0.79896 0.0160058 0.655085 -0.671262 0.346802 0.682491 -0.629865 0.370776 0.589152 -0.627849 0.508631 0.589432 -0.406955 0.697824 0.43313 -0.473479 0.766952 0.402925 -0.133064 0.905508 0.217005 -0.173931 0.96055 0.53962 -0.84152 0.0255887 0.525274 -0.850913 0.00580748 0.350541 -0.85588 0.380252 0.34137 -0.882901 0.322417 0.16993 -0.781229 0.600671 0.165988 -0.838925 0.518317 -0.0247197 -0.636137 0.77118 -0.0245827 -0.736508 0.675982 -0.142321 -0.561747 0.814976 -0.134742 -0.542098 0.829442 -0.224947 -0.309673 0.923852 -0.0701781 -0.195342 0.978221 -0.132887 -0.348393 0.927881 0.0998497 -0.169151 0.980519 0.110479 -0.143484 0.983467 0.0569077 -0.1867 0.980767 0.466512 -0.151602 0.871426 0.486875 -0.762942 0.42529 0.431023 -0.902071 0.0220928 0.463438 -0.878082 -0.119151 0.390765 -0.918268 0.0639311 0.429792 -0.902529 0.0268507 0.643269 -0.737125 0.207005 0.711774 -0.698426 0.0746944 0.901743 -0.408558 0.141212 0.988608 -0.136034 -0.0644187 0.962256 -0.171161 0.211583 0.952289 -0.24747 0.178616 0.920241 -0.060534 0.386643 0.797973 -0.12022 0.590582 0.578166 -0.525411 0.624234 0.524036 -0.605102 0.599364 0.573213 -0.357554 0.73728 0.521042 -0.461443 0.718043 0.548779 -0.179663 0.816433 0.869127 -0.462551 0.175113 0.961039 -0.176352 0.212848 0.777337 -0.277932 0.564359 0.796882 -0.123852 0.591304 0.66409 -0.075038 0.743877 0.46342 -0.884921 -0.046438 0.48769 -0.869523 -0.0780253 0.672389 -0.737693 -0.0608374 0.710265 -0.689378 -0.142413 0.893265 -0.419236 -0.162232 0.889577 -0.430822 -0.151809 0.963866 -0.213533 -0.159267 0.952112 -0.146777 -0.268215 0.506251 -0.00627396 0.862364 0.501841 -0.307214 0.808564 0.814403 -0.171337 0.554429 0.783009 -0.352236 0.512667 0.776833 -0.486858 0.399374 0.769448 -0.498335 0.399514 0.632504 -0.725813 0.270435 0.532627 -0.76964 0.352084 0.377045 -0.922763 0.0796544 -0.784776 -0.144069 -0.602802 -0.70061 -0.199697 -0.68503 -0.84979 -0.0512869 -0.52462 -0.831529 -0.0627988 -0.55192 -0.166617 -0.71769 -0.676136 0.188913 -0.844086 -0.501828 0.333715 -0.794557 -0.507262 0.392742 -0.77916 -0.488532 0.18658 -0.801767 -0.567766 -0.801313 -0.16438 -0.575219 -0.803288 -0.162053 -0.57312 -0.526956 -0.487536 -0.696151 -0.545134 -0.477559 -0.689033 -0.2329 -0.680063 -0.695178 -0.00551924 -0.738529 -0.674199 0.0510874 -0.631662 -0.773558 0.421255 -0.672785 -0.608197 0.50732 -0.65052 -0.565199 0.258783 -0.667032 -0.698642 0.323556 -0.660244 -0.677783 0.208477 -0.655766 -0.725609 0.0983244 -0.634628 -0.766537 -0.00559931 -0.61359 -0.789605 -0.169901 -0.565039 -0.807381 -0.121107 -0.574662 -0.809381 -0.483096 -0.408315 -0.77453 -0.336559 -0.446106 -0.829288 -0.539034 -0.358248 -0.7623 0.10049 -0.891577 -0.441578 0.208123 -0.890538 -0.404508 -0.264942 -0.769537 -0.58105 -0.220976 -0.787135 -0.575837 -0.588223 -0.52012 -0.619248 -0.582205 -0.525491 -0.6204 -0.813176 -0.1832 -0.552434 -0.815756 -0.178393 -0.550198 0.312354 -0.0853656 0.946122 0.615926 -0.68516 0.388833 0.616059 -0.684641 0.389536 0.538333 -0.45085 0.711991 0.538271 -0.450278 0.7124 0.378979 -0.154001 0.912501 0.496688 -0.866641 0.0472631 0.594982 -0.803528 0.0184031 0.594713 -0.803742 0.0177632 0.496519 -0.866759 0.0468898 0.532173 -0.738344 0.414296 0.532129 -0.738282 0.414462 0.482908 -0.485387 0.728834 0.482896 -0.485372 0.728852 0.41092 -0.908846 0.0717161 0.41027 -0.909287 0.0698225 0.459183 -0.774372 0.435314 0.458997 -0.775045 0.434313 0.434974 -0.509202 0.742638 0.436004 -0.591392 0.678348 0.417422 -0.428625 0.801273 0.378905 -0.153767 0.912571 0.359933 -0.16571 0.918144 0.359931 -0.165702 0.918146 0.343588 -0.173862 0.922886 0.360407 -0.260926 0.895558 0.61684 -0.693573 -0.372109 0.5734 -0.795838 -0.194562 0.540961 -0.823847 -0.169229 0.373401 -0.924267 -0.0793816 0.337847 -0.939694 -0.0532397 0.119561 -0.991269 0.0555935 0.0850612 -0.993166 0.0799067 -0.164317 -0.966947 0.194969 -0.193396 -0.9573 0.214882 -0.437714 -0.841281 0.317259 -0.458675 -0.824507 0.331368 -0.659677 -0.63364 0.404138 -0.672405 -0.614473 0.412668 -0.807165 -0.383686 0.448631 -0.813339 -0.365244 0.452855 -0.804436 -0.112169 0.583353 -0.880436 -0.13154 0.455554 -0.882071 -0.114986 0.456869 0.553151 -0.801072 -0.228709 0.367938 -0.925625 -0.0885469 0.426338 -0.896778 -0.118429 0.136584 -0.987043 0.0842109 0.19508 -0.979077 0.0578887 -0.124958 -0.957139 0.261286 -0.0738461 -0.967467 0.24198 -0.379717 -0.826724 0.415141 -0.341115 -0.848693 0.404179 -0.58949 -0.615893 0.522663 -0.564226 -0.642133 0.518955 -0.732011 -0.364577 0.575537 -0.717649 -0.390158 0.576851 -0.801606 -0.136327 0.582102 -0.708614 -0.109059 0.697117 -0.703447 -0.142326 0.696352 -0.604949 -0.398073 0.689619 -0.627028 -0.3636 0.688935 -0.441886 -0.65216 0.615974 -0.478815 -0.617071 0.624467 -0.216015 -0.856239 0.469246 -0.270781 -0.827994 0.491023 0.0431511 -0.963963 0.262514 -0.0273803 -0.953743 0.299374 0.290952 -0.956238 0.0309202 0.212895 -0.973801 0.0799177 0.490305 -0.851496 -0.185892 0.415674 -0.899938 -0.13163 0.573554 -0.762523 -0.299324 0.593942 -0.756416 -0.273985 -0.596066 -0.103685 0.796212 -0.584748 -0.150786 0.797078 -0.488392 -0.355945 0.796729 -0.466925 -0.408972 0.784043 -0.322227 -0.608221 0.725423 -0.286625 -0.663545 0.691053 -0.106619 -0.815086 0.569444 -0.0550596 -0.861233 0.505218 0.128387 -0.931147 0.341295 0.642308 -0.586345 -0.4936 0.608506 -0.696671 -0.379961 0.558742 -0.775023 -0.295207 0.505445 -0.845633 -0.171552 0.406999 -0.912603 -0.0388143 0.342493 -0.936177 0.0791946 0.256607 -0.950204 0.176818 0.141657 -0.936137 0.321839 0.820983 -0.143006 -0.552754 0.896878 -0.145122 -0.41779 0.896489 -0.149703 -0.417008 0.819623 -0.433761 -0.374258 0.817261 -0.439907 -0.372246 0.662926 -0.688423 -0.294284 0.657601 -0.69506 -0.290608 0.414852 -0.875815 -0.246671 0.44792 -0.873943 -0.188658 0.439342 -0.879421 -0.183295 0.820652 -0.149418 -0.551547 0.751298 -0.437588 -0.494032 0.755118 -0.428955 -0.495777 0.609511 -0.691394 -0.387906 0.617384 -0.682038 -0.391997 0.425349 -0.868104 -0.25588 0.382652 -0.870637 -0.309141 0.684484 -0.143464 -0.714772 0.393979 -0.860541 -0.322876 0.557391 -0.673989 -0.484823 0.548399 -0.686108 -0.478032 0.672279 -0.422961 -0.607573 0.6679 -0.434096 -0.604542 0.704143 -0.294934 -0.645908 0.738068 -0.14815 -0.658261 0.61064 -0.137281 -0.779918 0.610885 -0.147547 -0.777849 0.572198 -0.415602 -0.707011 0.569912 -0.429418 -0.700571 0.482952 -0.663999 -0.570844 0.476585 -0.679139 -0.558244 0.354001 -0.850795 -0.38837 0.342871 -0.863768 -0.369248 -0.926347 -0.0177569 -0.376252 -0.246893 -0.846045 -0.472495 -0.300361 -0.824332 -0.479854 -0.342437 -0.692404 -0.635069 0.311664 -0.701331 -0.641093 0.470904 -0.77264 -0.425766 0.504964 -0.797675 -0.329738 0.331208 -0.939405 -0.0884311 0.300292 -0.717967 -0.627971 0.379808 -0.79456 -0.473731 0.105591 -0.937271 -0.332225 0.319866 -0.943431 -0.0873131 0.151132 -0.980939 0.122139 0.156194 -0.98196 0.106575 0.117169 -0.981281 0.152836 0.121169 -0.94399 0.306921 -0.048178 -0.8585 0.510546 -0.286767 -0.758286 -0.585464 -0.641591 -0.581954 -0.499691 -0.570349 -0.691214 -0.443763 -0.858104 -0.404501 -0.316286 -0.786189 -0.562531 -0.255864 -0.595708 -0.205999 0.776335 -0.716129 -0.119914 0.687589 -0.847029 -0.15621 0.508074 -0.616921 -0.689641 0.379214 -0.758387 -0.40554 0.51028 -0.806486 -0.356221 0.471898 -0.843004 -0.143145 0.518511 -0.960826 -0.0966022 0.259773 -0.927908 -0.203723 0.312224 -0.998459 0.00730841 0.055004 -0.982352 -0.150299 0.111335 -0.989303 -0.044829 -0.138814 -0.463523 -0.68936 0.556713 -0.318469 -0.650661 0.689361 -0.450093 -0.400713 0.798026 -0.40194 -0.89836 0.177181 -0.415702 -0.893035 0.17228 -0.251723 -0.898063 0.360719 -0.632784 -0.679222 0.371808 -0.476612 -0.68407 0.552168 -0.616673 -0.409064 0.672593 -0.581522 -0.356249 0.731382 -0.625872 -0.172736 0.760557 -0.402376 -0.835325 -0.374601 -0.635304 -0.7257 -0.264099 -0.565624 -0.789773 -0.237336 -0.846317 -0.528852 -0.0637504 -0.774032 -0.632319 -0.0323708 -0.709362 -0.23084 -0.665971 -0.568974 -0.491578 -0.659257 -0.643907 -0.159625 -0.748267 -0.363618 -0.542201 -0.757496 -0.433128 -0.306891 -0.847478 -0.125512 -0.58826 -0.798872 -0.179994 -0.433009 -0.883235 -0.957306 -0.148715 -0.24789 -0.947113 -0.191336 -0.257621 -0.914782 -0.400544 -0.0523264 -0.972927 -0.196647 -0.121422 -0.887299 -0.43032 0.165906 -0.949551 -0.288878 0.122073 -0.85653 -0.396636 0.330206 -0.717914 -0.666822 0.19987 -0.754725 -0.631809 0.176656 -0.508299 -0.861121 -0.0101825 -0.541197 -0.840447 -0.0274622 -0.301877 -0.936279 -0.179586 -0.0217558 -0.991326 -0.129611 0.608595 -0.602607 -0.516214 0.588008 -0.61468 -0.525753 0.572209 -0.591019 -0.568572 0.547619 -0.573562 -0.609213 0.54821 -0.56964 -0.612353 0.546512 -0.548281 -0.633019 0.543989 -0.551825 -0.632111 0.355394 -0.57533 -0.736675 0.304873 -0.610157 -0.731274 0.229013 -0.600891 -0.765822 0.10435 -0.58611 -0.803484 0.110389 -0.60104 -0.791559 0.0153002 -0.551616 -0.833958 -0.848181 -0.124235 -0.514932 -0.840469 -0.152761 -0.51988 -0.859258 -0.282931 -0.426175 -0.698836 -0.533672 -0.476259 -0.802471 -0.253694 -0.540074 -0.481377 -0.620526 -0.61905 -0.587526 -0.421259 -0.690908 -0.217689 -0.669538 -0.710163 -0.302773 -0.544503 -0.782205 0.0147562 -0.660966 -0.750271 0.0223157 -0.750972 -0.659957 0.0513086 -0.77904 -0.624871 0.0142134 -0.842965 -0.537781 0.11959 -0.936722 -0.329015 -0.103949 -0.9749 -0.19689 -0.114354 -0.976638 -0.18194 -0.271409 -0.959205 -0.0791401 -0.0504675 -0.982709 0.178148 -0.240784 -0.900045 0.363239 -0.0838911 -0.858887 0.505248 -0.274565 -0.658234 0.700958 0.611124 0 -0.791535 0.61611 0.190846 -0.76419 0.68716 2.44032e-05 -0.726506 0.742486 -3.55739e-06 -0.669862 0.663603 0.525393 -0.532535 0.790063 -0.316019 -0.525292 0.783845 0.484337 -0.388594 0.905113 0 -0.425172 0.279774 0 0.960066 0.279774 -2.26464e-07 0.960066 0.279774 8.21372e-08 0.960066 0.279774 0 0.960066 0.96261 0 -0.270892 0.918 0.361923 -0.162134 0.990921 -0.118055 -0.0643398 0.964671 0.180622 0.191795 0.896158 0.38734 0.21649 0.921209 -0.0214856 0.388474 0.798474 0.0503703 0.599918 0.745322 0.256904 0.61522 0.662387 0.0215235 0.748852 0.450543 -0.0773123 0.889401 0.465029 0 0.885296 -0.61647 0 0.787378 -0.699865 0.00304025 0.714268 -0.722146 0.00124003 0.691739 -0.853805 -0.00117821 0.520592 -0.908906 0.00516898 0.416968 -0.941208 0.000973581 0.337825 -0.991022 -0.00116525 0.133695 -0.999592 0.00514976 0.0280897 -0.991368 -0.00202787 -0.131092 -0.943622 0.0028204 -0.331013 -0.927903 0 -0.372822 -0.89408 0 0.447908 -0.860018 -0.0365349 0.508953 -0.820702 0.000934711 0.571356 -0.730878 -0.000972222 0.682507 -0.68326 -0.0301492 0.729552 -0.628749 0 0.777609 -0.876699 0 -0.481039 -0.876699 1.20036e-07 -0.481039 -0.876699 3.93112e-08 -0.481039 -0.876699 1.91798e-07 -0.481039 -0.8767 0 -0.481038 0.199647 0 0.979868 0.118814 0.00535005 0.992902 -0.308334 0.00233445 0.951275 -0.22498 0.00941994 0.974318 -0.243882 0.00767015 0.969775 -0.130765 5.58451e-05 0.991413 0.0356009 -5.37203e-05 0.999366 -0.522783 -0.00291048 0.852461 -0.603892 0.00698003 0.797035 -0.672276 0.00226913 0.740297 -0.84886 -0.00672526 0.528574 -0.825553 0 0.564325 -0.822028 0 -0.569447 -0.694429 0.0830495 -0.714752 -0.772992 -0.0116861 -0.634308 -0.502896 0.00926459 -0.864298 -0.453959 0.0476187 -0.889749 -0.319476 0.00338849 -0.947588 -0.0824745 -0.00850005 -0.996557 -0.018734 0.0426987 -0.998912 0.124572 0.00735609 -0.992183 0.382879 -0.0293868 -0.923331 0.355633 0 -0.934626 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.028158 -0.980399 -0.195001 -0.0156662 -0.988487 -0.150493 -0.087443 -0.828098 -0.553721 -0.0517266 -0.893092 -0.44689 -0.105731 -0.703435 -0.702851 -0.113498 -0.549323 -0.827866 -0.130554 -0.447036 -0.884938 -0.134159 -0.348265 -0.927746 -0.301351 -0.332334 -0.893723 -0.283032 -0.447024 -0.848565 -0.272456 -0.549312 -0.789952 -0.222984 -0.703423 -0.674889 -0.184471 -0.828667 -0.528471 -0.139911 -0.893743 -0.426203 -0.0671417 -0.980468 -0.184863 -0.0481399 -0.988573 -0.142853 0.486771 -0.541025 -0.685818 0.909112 -0.190638 -0.370367 0.789397 -0.263197 -0.554598 0.67115 -0.263743 -0.692819 0.530073 -0.401588 -0.746827 0.488914 -0.317803 -0.812382 0.159538 -0.34188 -0.926102 0.129411 -0.476006 -0.869868 0.327762 -0.319715 -0.889019 0.142777 -0.541026 -0.828798 0.03413 -0.979582 -0.198125 0.0964557 -0.822908 -0.559928 0.0964588 -0.822907 -0.559929 0.32886 -0.822906 -0.463332 0.116364 -0.979582 -0.163945 0.175764 -0.979582 -0.0975987 0.831998 -0.307154 -0.461991 0.789203 -0.43025 -0.438228 0.70969 -0.545167 -0.446243 0.701212 -0.597239 -0.389367 0.542255 -0.784409 -0.301102 0.142775 -0.541027 -0.828798 0.486769 -0.541027 -0.685818 0.328856 -0.822907 -0.463332 0.447492 -0.828554 -0.336524 0.39547 -0.891841 -0.219597 -0.0790869 -0.72121 -0.688187 -0.08209 -0.724215 -0.68467 -0.0623359 -0.710714 -0.700714 -0.0751942 -0.719867 -0.690027 -0.0802412 -0.719083 -0.690276 -0.0825109 -0.721354 -0.687634 -0.0756744 -0.645199 -0.760257 -0.135764 -0.671017 -0.728906 -0.208555 -0.596518 -0.77503 -0.270618 -0.415233 -0.868532 -0.284459 -0.459437 -0.841428 -0.209366 -0.591837 -0.778392 -0.125721 -0.51879 -0.845607 -0.128981 -0.457526 -0.879792 -0.127764 -0.460128 -0.878612 -0.547657 -0.327495 -0.769947 -0.32355 -0.94407 -0.0636188 -0.119585 -0.75159 -0.648701 -0.292782 -0.827226 -0.479558 -0.415481 -0.603535 -0.68053 -0.367117 -0.550367 -0.749881 -0.468947 -0.436014 -0.768102 -0.497863 -0.295218 -0.815462 -0.673203 -0.191098 -0.714339 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.162976 -0.69643 0.698874 0.526684 -0.597258 0.604886 0.644769 -0.189538 0.740505 -0.250704 -0.189539 0.949327 -0.200576 -0.254263 0.946108 0.219795 -0.251665 0.942526 0.219795 -0.251666 0.942526 0.598387 -0.254263 0.759791 0.592334 -0.431688 0.680284 0.407286 -0.784423 0.46776 0.174771 -0.963933 0.200721 0.174771 -0.963933 0.200721 0.0604426 -0.963933 0.259192 -0.230316 -0.431687 0.872124 -0.204789 -0.597258 0.775464 -0.102331 -0.704102 0.702687 -0.158365 -0.784423 0.599668 -0.115672 -0.8915 0.438005 0.402602 -0.704102 0.584938 0.162976 -0.69643 0.698873 0.0604431 -0.963933 0.259192 0.0310831 -0.965339 0.259141 -0.0512688 -0.979634 0.194136 0.646998 -0.69643 0.31045 0.583309 -0.18954 0.789826 0.612181 -0.254263 0.748722 0.872564 -0.251666 0.418685 0.872564 -0.251666 0.418684 0.967043 -0.251666 -0.0386168 0.967044 -0.251666 -0.0386165 0.717054 -0.69643 -0.0286334 0.265934 -0.963933 -0.0106189 0.265934 -0.963933 -0.0106193 0.239953 -0.963933 0.115135 0.53587 -0.431689 0.725595 0.476479 -0.597256 0.645177 0.483875 -0.704102 0.519717 0.368462 -0.784423 0.498915 0.26913 -0.8915 0.364414 0.717053 -0.69643 -0.0286337 0.646998 -0.69643 0.310451 0.239952 -0.963933 0.115137 0.221532 -0.965339 0.138 0.119285 -0.979634 0.161519 0.863683 -0.211923 -0.457319 0.180431 -0.2036 -0.962285 0.585076 -0.188724 -0.788713 0.604493 -0.147359 -0.782862 0.75884 -0.0312591 -0.650527 0.00396477 -0.656942 -0.753931 -0.0343205 -0.620656 -0.783331 0.807127 -0.0110128 -0.590275 0.720953 -0.331903 -0.608332 0.579449 -0.361302 -0.730547 0.440723 -0.565879 -0.69681 0.26819 -0.513841 -0.814887 0.100578 -0.684278 -0.722251 0.047742 -0.675297 -0.735999 -0.241671 -0.375302 -0.894843 -0.036442 -0.0722666 -0.996719 0.249995 -0.133387 -0.959015 0.187567 -0.226243 -0.955841 0.405795 -0.0620253 -0.911857 0.219945 -0.332138 -0.917229 -0.115203 -0.261035 -0.958431 -0.166571 -0.167468 -0.971704 0.859049 0.117541 -0.498216 0.785988 -0.305529 -0.537471 0.580192 -0.0142649 -0.814355 0.520986 -0.279146 -0.80663 0.387031 -0.348262 -0.853768 0.275526 -0.567262 -0.776079 0.124064 -0.465022 -0.876563 -0.0754923 -0.560056 -0.825008 -0.0988109 -0.553446 -0.827003 -0.105839 -0.556524 -0.824063 0.905305 -0.076545 -0.417807 0.124878 -0.421531 -0.898175 0.0884501 -0.439216 -0.894017 0.332051 -0.379952 -0.863353 0.418225 -0.343495 -0.840892 0.907114 -0.0732596 -0.41446 0.788201 -0.179253 -0.588734 0.709613 -0.216896 -0.670377 0.670543 -0.248539 -0.698999 0.489662 -0.332746 -0.805923 0.121168 -0.60787 -0.784737 0.084159 -0.625951 -0.775308 0.449135 -0.496517 -0.742798 0.425596 -0.515188 -0.743941 0.730373 -0.317958 -0.604531 0.720556 -0.330676 -0.609469 0.911295 -0.106946 -0.397623 0.878985 -0.18009 -0.441534 0.938459 -0.0554542 -0.34091 0.188409 -0.980555 -0.0549045 0.250249 -0.965907 -0.0663326 0.42564 -0.896351 -0.124036 0.586244 -0.791917 -0.170838 0.681237 -0.707081 -0.189612 0.942275 -0.191623 -0.27459 0.929188 -0.258813 -0.263867 0.862552 -0.439116 -0.251358 0.763046 -0.606891 -0.22236 -0.0938459 -0.980785 0.171035 -0.093846 -0.980785 0.171036 -0.212759 -0.896872 0.387756 -0.212759 -0.896872 0.387756 -0.292838 -0.793354 0.5337 -0.292838 -0.793354 0.5337 -0.381634 -0.608761 0.695533 -0.381633 -0.608763 0.695531 -0.431431 -0.442288 0.786288 -0.431432 -0.442285 0.78629 -0.471796 -0.195091 0.859854 -0.471796 -0.195091 0.859854 0.45912 -0.194253 0.866877 0.348797 -0.830317 0.434642 0.0917033 -0.980617 0.173148 0.12263 -0.980617 0.152812 0.12263 -0.980617 0.152812 0.149181 -0.980617 0.127023 0.191593 -0.96532 0.177339 0.60505 -0.607045 0.515181 0.46481 -0.792034 0.395771 0.521117 -0.553849 0.649375 0.633944 -0.553849 0.539784 0.697332 -0.441417 0.564694 0.0917033 -0.980617 0.173148 0.207754 -0.896083 0.392267 0.254601 -0.829975 0.496307 0.285724 -0.792035 0.539484 0.371933 -0.607042 0.702257 0.429396 -0.829974 0.356036 0.348797 -0.830317 0.434643 0.521117 -0.553849 0.649375 0.383154 -0.553506 0.739476 0.420135 -0.440696 0.793268 0.746884 -0.194251 0.635949 0.746884 -0.194252 0.635948 0.64936 -0.194881 0.735087 0.624778 -0.0592819 0.778549 0.577025 -0.19488 0.793136 0.45912 -0.194251 0.866877 -0.174045 -0.965824 -0.192072 -0.174045 -0.965824 -0.192072 -0.410426 -0.791454 -0.452936 -0.486455 -0.706905 -0.513466 -0.533987 -0.606291 -0.589295 -0.603459 -0.438555 -0.665963 -0.657502 -0.258591 -0.707687 -0.659071 -0.191335 -0.727335 -0.202435 -0.9656 -0.163209 -0.202436 -0.9656 -0.163209 -0.551862 -0.705329 -0.444926 -0.551861 -0.70533 -0.444925 -0.752224 -0.25761 -0.606462 -0.752224 -0.25761 -0.606462 -0.574904 -0.0729518 -0.814962 -0.531059 -0.111938 -0.839908 -0.527518 -0.125207 -0.840267 -0.483562 -0.1138 -0.867881 -0.4717 -0.165745 -0.866041 -0.413309 -0.14154 -0.899523 -0.426793 -0.00881951 -0.904306 -0.327193 -0.208445 -0.921681 -0.447597 -0.212619 -0.868591 -0.378431 -0.355907 -0.854471 -0.36245 -0.346237 -0.865303 -0.34722 -0.40559 -0.845538 -0.289116 -0.452863 -0.843403 -0.289209 -0.453308 -0.843131 -0.197962 -0.554825 -0.808072 -0.197926 -0.555098 -0.807893 -0.155715 -0.56983 -0.806875 -0.292509 -0.893068 0.341859 -0.519829 -0.60057 0.60753 -0.638151 -0.191121 0.745813 -0.900945 -0.253707 -0.352037 -0.900945 -0.253708 -0.352036 -0.966532 -0.253708 0.0380483 -0.966533 -0.253707 0.0380469 -0.870483 -0.253707 0.421771 -0.870485 -0.253706 0.42177 -0.670394 -0.256202 0.696371 -0.585487 -0.434726 0.684265 -0.665609 -0.699517 -0.26008 -0.665608 -0.699517 -0.260079 -0.714063 -0.699517 0.0281086 -0.714062 -0.699518 0.0281097 -0.643103 -0.699518 0.311598 -0.643103 -0.699517 0.311598 -0.528476 -0.706214 0.471142 -0.401088 -0.787017 0.468757 -0.245913 -0.964517 -0.0960879 -0.245913 -0.964517 -0.096089 -0.263815 -0.964517 0.0103853 -0.263815 -0.964517 0.0103853 -0.237599 -0.964517 0.115122 -0.237598 -0.964517 0.115123 -0.242319 -0.964076 0.10881 -0.129465 -0.979972 0.151307 -0.650135 0 0.759819 -0.650135 0 0.759819 -0.899928 0 0.436038 -0.899928 0 0.436038 -0.999226 0 0.0393353 -0.999226 0 0.0393353 -0.93142 0 -0.363945 -0.93142 0 -0.363945 -0.778499 0 -0.627646 -0.778499 0 -0.627646 -0.668231 0.0982003 -0.737444 -0.661035 0 -0.750355 -0.605371 0.043094 -0.794776 -0.562733 0.0890789 -0.821825 -0.625673 -0.0256201 -0.779664 -0.44411 0.0160864 -0.895828 -0.428975 0 -0.903316 -0.481039 0 0.876699 -0.481039 0 0.876699 0.960066 0 -0.279774 0.960066 2.9598e-08 -0.279774 0.960066 -6.37262e-08 -0.279774 0.960066 0 -0.279774 -0.269077 0 -0.963119 -0.0355706 0.018828 -0.99919 -0.173911 -0.0111019 -0.984699 0.202446 0.00668116 -0.979271 0.234805 0.0109421 -0.971981 0.4103 -0.00344628 -0.911944 0.636569 0.00731149 -0.771185 0.623265 0.0101123 -0.781946 0.761498 -0.000574996 -0.648168 0.89207 0.00162752 -0.451895 0.896772 0 -0.442493 0.468035 0 0.88371 0.509176 -0.0214796 0.860394 0.588304 0 0.80864 0.662054 0 0.749456 0.729715 -0.0214795 0.683414 0.761387 0 0.648298 0.999204 0 -0.039901 0.999204 0 -0.039901 0.901582 0 0.432609 0.901582 0 0.432609 0.594077 0 0.804408 0.594077 0 0.804408 0.656673 0 0.754176 0.656673 0 0.754176 0.227104 0 0.97387 0.227104 0 0.97387 -0.255333 0 0.966853 -0.255333 0 0.966853 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.781888 -0.622926 -0.0247806 0.876182 -0.478749 -0.0557097 0.824309 -0.566122 -0.00444866 0.883296 -0.465771 -0.053346 0.594102 -0.804146 -0.0198061 0.521772 -0.853012 0.0111871 0.473479 -0.880746 -0.0101766 0.382616 -0.923889 -0.0057782 0.340698 -0.940172 0.00155511 0.337317 -0.94122 -0.0179326 0.349085 -0.936897 -0.0190752 0.420672 -0.906849 -0.0257023 0.460658 -0.887569 0.00389184 0.530263 -0.84688 -0.0401907 0.663926 -0.743922 0.076043 0.672827 -0.739766 -0.00704161 0.723614 -0.689663 -0.0273542 0.364878 -0.930469 -0.0330534 0.346198 -0.937963 -0.0193086 0.322617 -0.946393 -0.0160694 0.880437 -0.47163 -0.0489449 0.880357 -0.47117 -0.0544971 0.821663 -0.569962 0.003647 0.835491 -0.548532 -0.0326705 0.741319 -0.670441 -0.0309206 0.786701 -0.617177 0.0139034 0.603399 -0.796419 -0.0403243 0.330762 -0.941671 -0.0620718 0.332107 -0.941168 -0.0625113 0.323868 -0.944918 -0.0473323 0.374851 -0.925909 -0.0466934 0.385706 -0.920383 -0.0642292 0.446938 -0.893163 -0.0500747 0.544037 -0.837245 -0.0551818 0.631556 -0.768973 -0.0990829 0.626807 -0.773201 -0.0962933 0.619211 -0.778679 -0.101176 0.541144 -0.838755 -0.0604353 0.542549 -0.837718 -0.0621941 0.661424 -0.74739 -0.0626668 0.668986 -0.740605 -0.0629409 0.632208 -0.768685 -0.0971391 0.341854 -0.939576 -0.0182371 0.364266 -0.930529 -0.0377575 0.409832 -0.90824 0.0844885 0.448324 -0.88883 -0.0948037 0.518665 -0.85477 0.0188279 0.345714 -0.93791 -0.0284149 0.340675 -0.939834 -0.0255315 0.394707 -0.918477 -0.0246306 0.395175 -0.918063 -0.0315765 0.556533 -0.8304 -0.0266139 0.527186 -0.839745 0.130016 0.618349 -0.784749 -0.0425797 0.611814 -0.785779 -0.0907478 0.604438 -0.796083 -0.0301276 0.550155 -0.832518 -0.0651472 0.545605 -0.836677 -0.0478188 0.392333 -0.919074 -0.0371307 0.392395 -0.919028 -0.0375981 0.334272 -0.941899 -0.0329932 0.337171 -0.940289 -0.0466102 0.321348 -0.945942 -0.0439248 0.33102 -0.941613 -0.0615707 0.328452 -0.942615 -0.059969 0.316607 -0.91042 -0.266261 0.0289823 -0.21355 -0.976502 0.385801 -0.752332 -0.533998 0.676186 -0.694174 -0.24677 0.301929 -0.119874 -0.945764 0.260527 -0.163615 -0.951502 0.476912 -0.158402 -0.86456 0.90413 -0.148007 -0.400803 0.915677 -0.116205 -0.384748 0.783317 -0.158453 -0.601089 0.698427 -0.199845 -0.687213 0.646022 -0.117777 -0.754178 0.445347 -0.182419 -0.876578 0.403419 -0.885146 -0.231884 0.268111 -0.932993 -0.240084 0.267429 -0.767081 -0.583154 0.136409 -0.787726 -0.600733 0.0637066 -0.487048 -0.871049 0.461824 -0.881433 -0.0989617 0.449664 -0.876307 -0.172883 0.607433 -0.739107 -0.291111 0.566583 -0.700602 -0.433751 0.471209 -0.866033 -0.167178 0.347431 -0.910488 -0.224285 0.447521 -0.706507 -0.548246 0.241287 -0.781499 -0.57536 0.223618 -0.462229 -0.858102 0.00267662 -0.541974 -0.840391 -0.0907727 -0.142067 -0.985686 -0.165134 -0.221658 -0.96104 0.115438 -0.12453 -0.985478 0.144211 -0.52756 -0.837188 0.301895 -0.477633 -0.825061 0.441135 -0.495171 -0.748469 0.446881 -0.490924 -0.747858 0.692512 -0.40741 -0.595353 0.642372 -0.467504 -0.607287 0.848228 -0.415109 -0.328929 0.832323 -0.436663 -0.341415 0.447816 -0.889278 0.0929856 -0.0532392 -0.0843839 0.99501 0.806601 -0.156004 0.570139 0.26007 -0.947226 0.187419 0.256907 -0.948498 0.18534 0.204707 -0.892981 0.40085 0.172165 -0.819016 0.547332 0.379997 -0.0641387 0.922761 0.471495 -0.136097 0.871304 0.579534 -0.14318 0.802271 0.500137 -0.17229 0.848634 0.481081 -0.206168 0.852089 0.469743 -0.387805 0.793063 0.637147 -0.173679 0.750919 0.584332 -0.494372 0.643547 0.583721 -0.491311 0.646438 -0.281649 -0.165357 0.945162 -0.245493 -0.0215099 0.96916 -0.206768 -0.334881 0.919294 -0.181535 -0.223118 0.957739 -0.112465 -0.49988 0.858762 -0.0957192 -0.412531 0.9059 -0.0279363 -0.655728 0.75448 -0.00781002 -0.583371 0.812169 0.0810027 -0.815562 0.572973 0.578477 -0.500055 0.644445 0.495711 -0.729824 0.470774 0.529807 -0.741132 0.412344 0.391087 -0.906115 0.161267 0.399131 -0.904485 0.150335 0.860831 -0.166503 0.480882 0.876416 -0.144827 0.459261 0.794298 -0.45995 0.396909 0.4439 -0.889381 0.109336 0.647568 -0.714034 0.266105 0.642639 -0.699683 0.312185 0.770219 -0.481575 0.418148 0.710508 -0.449555 0.541368 0.77001 -0.168226 0.615454 0.732808 -0.138938 0.666099 0.324039 -0.927728 0.185256 0.326989 -0.92656 0.185917 0.365981 -0.742074 0.56159 0.298657 -0.794034 0.529447 0.310505 -0.533383 0.786822 0.270132 -0.611425 0.743766 0.265535 -0.362311 0.893433 0.22458 -0.466605 0.855478 0.212657 -0.18308 0.959822 0.17191 -0.311444 0.934585 0.162959 -0.107688 0.980738 0.150591 -0.143481 0.978129 0.317792 -0.711192 -0.627068 -0.172642 -0.162512 -0.971486 -0.0881802 -0.231083 -0.96893 -0.22719 -0.0791151 -0.970632 -0.188737 -0.172262 -0.966801 -0.189735 -0.171195 -0.966795 0.0205768 -0.503591 -0.863697 0.0170529 -0.500828 -0.865379 0.230988 -0.75651 -0.611831 0.475492 -0.83703 -0.270718 0.446806 -0.801249 -0.397949 0.405336 -0.894193 -0.190055 0.397389 -0.877937 -0.267038 0.232831 -0.761291 -0.605167 0.317012 -0.709587 -0.629277 0.0735272 -0.47136 -0.87887 0.165855 -0.525841 -0.834256 0.0197869 -0.404207 -0.914453 0.305847 -0.914973 -0.263216 0.315991 -0.917048 -0.243254 0.149743 -0.782461 -0.604427 0.160076 -0.790654 -0.590967 -0.0281686 -0.525114 -0.850566 -0.0295681 -0.523367 -0.851594 -0.201942 -0.184483 -0.961866 -0.205365 -0.178788 -0.962216 -0.0552316 -0.369297 0.927669 -0.355822 -0.177557 0.917532 -0.216865 -0.255045 0.942296 -0.316607 -0.142044 0.937861 -0.404733 -0.0784966 0.91106 -0.400804 -0.196014 0.89495 -0.366296 -0.294236 0.882753 -0.455239 -0.0653712 0.887966 -0.450831 -0.0942793 0.887617 0.751922 -0.65536 0.0715212 0.698894 -0.7139 0.0435273 0.684717 -0.718101 0.124476 0.61727 -0.742921 0.258933 0.602632 -0.734841 0.311196 0.459312 -0.727777 0.509287 0.578844 -0.815276 0.0162607 0.543908 -0.830002 0.123535 0.477829 -0.844238 0.24278 0.444857 -0.838165 0.315567 0.349524 -0.822889 0.447981 0.315801 -0.803601 0.504476 0.192934 -0.748115 0.634902 0.162929 -0.721691 0.672768 0.020743 -0.621896 0.782825 -0.0692831 -0.511906 0.856243 -0.147634 -0.453929 0.878722 -0.372348 -0.178913 0.910685 -0.38483 -0.167912 0.907586 -0.0128682 -0.407656 0.913045 0.0820492 -0.466698 0.880603 0.148398 -0.504077 0.850814 0.191776 -0.538937 0.820225 0.345716 -0.605634 0.71672 0.395803 -0.637416 0.661091 0.65832 -0.671471 0.340208 0.602137 -0.623343 0.498872 0.716291 -0.623513 0.313303 0.725247 -0.63197 0.273184 0.812931 -0.579914 0.053317 0.80548 -0.571607 0.156418 0.813464 -0.580375 0.0379659 0.437007 -0.897147 0.0644372 0.527017 -0.767106 -0.36579 0.299426 -0.924547 0.235706 0.308998 -0.92664 0.214146 0.169893 -0.889642 0.423878 0.189165 -0.89999 0.392726 0.0409416 -0.794692 0.605631 0.0667323 -0.821827 0.565815 -0.17784 -0.577269 0.796953 -0.139686 -0.641585 0.754226 -0.2468 -0.475833 0.8442 -0.356745 -0.647216 -0.67368 -0.864854 -0.390072 -0.316024 0.183732 -0.959513 -0.21349 0.408336 -0.901992 -0.140256 0.803359 -0.58865 -0.0900298 0.716564 -0.685548 -0.128681 0.671549 -0.739165 -0.0515486 0.609538 -0.790354 -0.0616839 -0.698999 -0.628392 -0.341356 -0.504863 -0.78955 -0.34889 -0.439747 -0.835256 -0.330106 -0.291083 -0.899109 -0.326915 -0.131405 -0.949064 -0.286373 -0.113987 -0.951378 -0.286159 0.110701 -0.962589 -0.247322 -0.883777 -0.344187 -0.316977 -0.939753 -0.190995 -0.283524 -0.955132 -0.107582 -0.27595 0.636052 -0.743974 -0.204795 0.511647 -0.804741 -0.301013 0.463288 -0.875884 -0.134876 0.275784 -0.941632 -0.193061 -0.568088 -0.594143 -0.569448 -0.708345 -0.465526 -0.530597 -0.813822 -0.323527 -0.482725 -0.794605 -0.34621 -0.49874 -0.926759 -0.0753071 -0.368031 -0.899029 -0.131753 -0.417597 0.232051 -0.899086 -0.371209 -0.0366685 -0.901416 -0.431398 -0.0777995 -0.88187 -0.465029 -0.0633761 -0.884228 -0.462736 -0.362814 -0.733489 -0.574769 -0.632964 -0.556317 -0.538394 -0.692625 -0.634238 -0.34353 -0.799673 -0.497221 -0.336592 0.529956 -0.79564 -0.293432 0.357529 -0.859651 -0.36493 -0.00954298 -0.826382 -0.563028 0.189272 -0.832135 -0.521275 0.0201094 -0.80852 -0.588125 0.0275949 -0.807431 -0.589316 -0.214135 -0.75854 -0.615438 -0.97385 -0.124142 -0.190278 -0.915442 -0.376569 -0.141996 0.314348 -0.943437 -0.105412 -0.990982 -0.117291 -0.0647872 -0.988479 -0.127343 0.0818122 -0.971712 -0.226143 0.0680744 0.550011 -0.832612 -0.0651621 0.585503 -0.809204 -0.0487389 0.603786 -0.79657 -0.0302899 0.401682 -0.909952 -0.10315 0.546602 -0.835991 -0.0484361 0.546959 -0.835347 -0.0550575 0.546944 -0.835473 -0.0532732 0.260516 -0.959157 -0.110226 0.0880399 -0.987978 -0.127077 0.0321366 -0.989769 -0.139011 -0.140157 -0.978742 -0.149734 -0.271479 -0.948213 -0.164896 -0.323094 -0.932316 -0.16247 -0.554976 -0.814487 -0.169151 -0.5394 -0.824357 -0.171708 -0.778935 -0.606782 -0.158354 -0.730953 -0.660181 -0.172825 -0.833017 -0.530693 -0.15636 -0.990001 -0.0518654 -0.131181 -0.994408 0.063559 -0.084335 -0.921871 -0.36039 -0.142382 -0.923249 -0.376174 0.0781297 -0.780759 -0.622388 0.0552214 -0.775718 -0.628823 0.0533229 -0.556365 -0.829709 0.0451839 -0.52178 -0.852249 0.037642 -0.272961 -0.961902 0.0153705 -0.316209 -0.948339 0.0258008 0.0313135 -0.999334 -0.018717 -0.014504 -0.999872 -0.0067175 0.313939 -0.948816 -0.0345063 0.213226 -0.976909 -0.0135426 0.452577 -0.889916 -0.0567761 0.468825 -0.882868 -0.0273456 0.984553 -0.148952 -0.092029 0.988421 -0.146712 0.038715 0.988152 -0.150025 -0.0323793 0.954241 -0.299001 0.00474477 0.896702 -0.442634 -0.000619116 0.89974 -0.436426 -0.00112882 0.715125 -0.698895 -0.0119079 0.720949 -0.692874 -0.0125574 0.508919 -0.860569 -0.0205783 0.476323 -0.879247 -0.00637942 0.975402 -0.14882 -0.162612 0.944146 -0.304281 -0.1265 0.890081 -0.439875 -0.119441 0.889765 -0.440546 -0.119318 0.711466 -0.696146 -0.0959011 0.710244 -0.697442 -0.0955402 0.469087 -0.880849 -0.0637331 0.466689 -0.882167 -0.0631182 0.937045 -0.161159 0.309798 0.939969 -0.138574 0.311858 0.859051 -0.45337 0.237671 0.867476 -0.435101 0.241189 0.692607 -0.707637 0.139804 0.704418 -0.695034 0.143954 0.461456 -0.886644 0.0303349 0.474414 -0.87963 0.0343878 0.975952 -0.15217 0.156084 0.977771 -0.139557 0.156484 0.890119 -0.442094 0.110642 0.893135 -0.435846 0.111125 0.715532 -0.696554 0.0531581 0.716052 -0.696014 0.0532306 0.476484 -0.879145 -0.00823507 0.471996 -0.881557 -0.00878941 0.827599 -0.561066 0.0169012 0.842083 -0.536919 0.0511232 -0.925288 -0.219436 -0.309339 -0.600523 -0.262838 0.755174 0.484898 -0.72899 0.483164 0.616014 -0.787077 0.0321813 0.392163 -0.806809 -0.441891 0.366023 -0.827245 -0.426254 0.186455 -0.837024 -0.514417 0.0193292 -0.854085 -0.519773 0.00747238 -0.843793 -0.536617 -0.218746 -0.767867 -0.602106 -0.27428 -0.909956 0.311048 -0.0124159 -0.966563 0.25613 0.00207468 -0.962393 0.271652 0.812593 -0.572477 -0.109377 0.812444 -0.572727 -0.109172 0.638486 -0.740566 -0.209518 0.606862 -0.769252 -0.199925 -0.202685 -0.0175929 0.979086 -0.278363 -0.362066 0.889619 -0.431867 0.116335 0.894403 -0.492807 -0.243631 0.835336 0.0607395 -0.540276 0.839293 -0.0428824 -0.592459 0.804458 -0.0740208 -0.644826 0.760736 -0.165208 -0.672378 0.721536 -0.985484 -0.148307 -0.0826236 -0.969896 -0.170339 0.17403 -0.983619 -0.124351 0.130505 -0.990617 -0.1344 -0.0248113 -0.403136 -0.359419 0.841605 -0.541216 0.0593238 0.838788 -0.634196 -0.0858688 0.768389 -0.70689 -0.0865197 0.702012 -0.75989 -0.112034 0.640325 -0.819005 -0.052371 0.571391 -0.879654 -0.153266 0.450243 -0.881908 -0.151067 0.446562 -0.931251 -0.103474 0.349377 -0.743631 -0.627003 -0.232121 -0.651628 -0.720679 -0.236652 -0.63489 -0.743783 0.209051 -0.468424 -0.86197 0.193875 -0.619069 -0.743501 -0.252904 -0.502247 -0.826714 -0.25356 -0.486123 -0.849808 0.203744 -0.31714 -0.930252 0.184535 -0.601218 -0.793238 0.096495 -0.0444429 -0.997671 0.0517474 -0.0417699 -0.9976 0.0552265 -0.213803 -0.407074 0.88802 -0.335065 -0.444982 0.830495 -0.36377 -0.494469 0.789412 -0.468976 -0.503366 0.72573 -0.530196 -0.607319 0.591655 -0.663777 -0.519445 0.538124 -0.741395 -0.641537 0.196886 -0.385112 -0.709334 -0.590367 -0.242613 -0.768106 -0.592581 -0.285929 -0.876788 -0.386636 -0.0151382 -0.938117 -0.345988 -0.0256443 -0.927132 -0.373858 0.338219 -0.896343 -0.286666 0.35512 -0.909093 -0.217804 0.847625 -0.526917 -0.0623702 0.512037 -0.819391 -0.257714 -0.919025 -0.0577235 -0.38995 -0.811151 -0.399776 -0.426865 -0.828959 -0.302001 -0.470767 -0.710399 -0.471352 -0.522648 -0.695572 -0.492194 -0.523378 -0.56083 -0.576056 -0.594667 -0.556972 -0.582798 -0.591717 -0.415637 -0.700705 -0.579878 -0.47025 -0.841267 -0.266709 -0.447078 -0.853926 -0.266331 -0.333806 -0.926758 -0.17232 -0.0440846 -0.985611 -0.163179 -0.0508273 -0.983268 -0.174929 0.316872 -0.936963 -0.14728 0.321364 -0.946782 0.0181211 0.367311 -0.925433 0.0930368 0.350235 -0.920465 0.173435 0.0039762 -0.380028 0.924967 -0.110801 -0.359338 0.926607 -0.212135 -0.404197 0.889732 -0.36415 -0.103284 0.925596 -0.451808 -0.247284 0.857158 -0.574041 -0.266178 0.774355 -0.597261 -0.30698 0.740974 -0.698906 -0.295348 0.651383 -0.750085 -0.385545 0.537333 -0.81664 -0.344744 0.462872 -0.874736 -0.441089 0.200694 -0.891921 -0.415941 0.1774 0.842322 -0.536392 0.0527062 0.804963 -0.572409 0.156148 0.726406 -0.613398 0.309963 0.729796 -0.625662 0.275583 0.59428 -0.651629 0.471393 0.598247 -0.62886 0.496624 0.465143 -0.535685 0.704758 0.167904 -0.762671 0.624613 0.290664 -0.688868 0.664059 0.289875 -0.694409 0.658611 0.356642 -0.587034 0.726772 0.152454 -0.370848 0.916095 0.15978 -0.584696 0.795362 0.0761723 -0.475873 0.876209 0.817531 -0.574299 -0.0427139 0.814461 -0.580217 -0.000940129 0.663674 -0.742786 0.0883531 0.66126 -0.729517 0.174757 0.398941 -0.842511 0.361968 0.407486 -0.851419 0.330214 0.064827 -0.860177 0.505858 0.0860314 -0.885382 0.456833 -0.20319 -0.799561 0.56517 -0.228444 -0.775429 0.588662 -0.380804 -0.735529 0.560344 -0.522663 -0.61995 0.585223 -0.617116 -0.761396 0.198604 -0.757846 -0.618463 0.207779 -0.774372 -0.595878 -0.212784 -0.899194 -0.391126 -0.19614 -0.879087 -0.449184 -0.159499 -0.973735 -0.178836 -0.140916 -0.973578 -0.155505 -0.167223 -0.981917 -0.0734814 -0.174472 -0.914959 -0.128331 -0.382598 -0.815388 -0.0412074 -0.577446 0.123813 -0.90534 -0.406238 0.0795359 -0.91485 -0.395882 -0.128766 -0.857092 -0.498811 -0.988814 -0.143327 0.0412857 -0.964016 -0.220887 0.147925 -0.965884 -0.225881 0.126673 -0.908604 -0.136711 -0.394651 -0.859447 -0.321953 -0.397112 -0.898218 -0.376728 -0.226452 -0.754155 -0.616642 -0.225839 -0.770489 -0.581759 -0.260583 -0.981027 -0.0776535 -0.177641 -0.91855 -0.348181 -0.18718 -0.925099 -0.379413 0.0154433 -0.776424 -0.627377 0.0596965 -0.774806 -0.62914 0.0621207 -0.699313 -0.329726 -0.634225 -0.570769 -0.562705 -0.597984 -0.572049 -0.475579 -0.66827 -0.356453 -0.727875 -0.585781 -0.352102 -0.760028 -0.546244 -0.197971 -0.852533 -0.483731 -0.257097 -0.935258 -0.243297 0.439549 -0.868448 -0.229336 0.438177 -0.874295 -0.208829 0.495109 -0.816487 -0.297013 -0.325636 -0.944765 -0.0371559 -0.20652 -0.96611 -0.154859 -0.0332123 -0.992989 -0.113446 0.0203889 -0.988515 -0.149739 0.189547 -0.972092 -0.138236 0.424262 -0.890794 -0.162753 0.441587 -0.889823 -0.114964 -0.431618 -0.00830846 -0.902018 -0.31563 -0.153461 -0.936391 -0.309023 -0.183953 -0.933095 -0.174563 -0.301793 -0.937256 -0.158338 -0.360162 -0.919354 -0.0302273 -0.443776 -0.895628 0.00634783 -0.526049 -0.85043 0.119868 -0.561979 -0.81842 0.176562 -0.660221 -0.730024 0.379991 -0.661676 -0.646368 0.364364 -0.722832 -0.587156 0.518994 -0.806231 -0.283967 -0.529001 -0.848346 -0.0216216 -0.560143 -0.827101 -0.0463076 -0.549978 -0.78799 -0.276759 -0.532479 -0.809858 -0.246163 -0.487324 -0.748979 -0.448938 -0.691031 -0.530434 -0.491035 -0.677947 -0.592841 -0.434657 -0.816939 -0.3564 -0.45342 -0.763888 -0.296821 -0.573038 -0.823112 -0.0243656 -0.567356 0.540955 -0.783485 -0.305807 0.475342 -0.843697 -0.249449 0.26905 -0.810065 -0.520967 0.207119 -0.825427 -0.52514 0.0771803 -0.747874 -0.659338 -0.0138996 -0.746186 -0.665593 -0.122589 -0.64044 -0.758162 -0.236341 -0.608113 -0.757853 -0.312232 -0.497677 -0.809215 -0.435547 -0.427175 -0.792351 -0.477019 -0.334848 -0.812607 -0.593633 -0.226525 -0.772196 -0.608586 -0.167826 -0.775537 -0.619107 -0.15397 -0.770064 0.986249 0 -0.165267 0.0324388 0.999468 -0.00348009 0.362867 0.9315 -0.0252044 0.995321 -0.091419 -0.0312705 0.982859 0.177235 0.0507524 0.637916 0.766927 0.0699001 0.980063 -0.117473 0.16024 0.940282 0.124053 0.316986 0.942269 0 0.334857 -0.991444 0 0.130536 -0.999044 0.00304337 0.0436045 -0.999934 0.00536761 0.0101838 -0.985012 -0.00590706 -0.172385 -0.937517 0.00807221 -0.347846 -0.925746 0.00534686 -0.378108 -0.726626 -0.0133022 -0.686904 -0.818737 0.0173407 -0.573907 -0.638736 -5.2939e-05 -0.769426 -0.433182 0.000106377 -0.901306 -0.432464 0 -0.901651 -0.996962 -0.000128326 -0.0778895 -0.551669 0 0.834063 -0.618078 0.00368537 0.786108 -0.661201 0.00118216 0.750208 -0.858201 0.00462511 0.513293 -0.82425 -2.66853e-05 0.566226 -0.719943 5.12736e-06 0.694033 -0.999759 0.000171233 -0.0219618 -0.991625 0.0027432 0.129123 -0.990624 0.00338833 0.136575 -0.939072 -0.00110212 0.343718 -0.899284 0.00174551 0.437362 -0.98713 0.000929272 -0.15992 -0.974009 0.00355685 -0.226483 -0.955005 0 -0.29659 -0.939204 0 -0.34336 -0.967149 -0.0256785 -0.25291 -0.980025 -0.0784913 -0.18273 -0.968479 -0.0190935 -0.248361 -0.992473 0.00122282 -0.122455 -0.999464 0 0.0327481 -0.994869 -0.0578494 0.0830065 -0.998697 -0.00293231 -0.0509547 -0.481039 0 0.876699 -0.481039 -1.02823e-07 0.876699 -0.48104 0 0.876699 -0.481039 -4.5883e-07 0.876699 -0.481039 6.01447e-08 0.876699 -0.481039 9.74905e-08 0.876699 -0.279774 0 -0.960066 -0.279774 0 -0.960066 -0.279774 3.07979e-07 -0.960066 -0.279774 -5.69503e-08 -0.960066 0.870896 0 0.491467 0.819105 0.0224703 0.573203 0.813327 0.0198878 0.581467 0.377978 -0.000892498 0.925814 0.469631 0.0175459 0.882688 0.521019 0.0323457 0.852932 0.580302 0.00877391 0.814354 0.736788 -0.00537166 0.676102 0.144721 0.00215946 0.98947 0.0951655 0.0234501 0.995185 -0.0579308 0.00252538 0.998317 -0.311237 -0.0093659 0.950286 -0.29354 0 0.955947 0.92403 0 -0.382321 0.258244 0.54706 -0.796263 0.250971 0.0996545 -0.962851 -0.0972376 -0.13009 -0.986723 -0.0102459 0.521815 -0.852997 -0.180846 0 -0.983511 0.761884 -0.556093 -0.332104 0.772237 0.199918 -0.603061 0.463153 0.744489 -0.480858 0.646848 -0.100034 -0.756029 0.444341 0.0408615 -0.894925 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0298963 -0.980514 -0.194161 0.0351001 -0.989562 -0.139767 0.039745 -0.97534 -0.2171 0.0667151 -0.94163 -0.329974 0.111012 -0.828373 -0.549067 0.111013 -0.828371 -0.54907 0.165639 -0.548995 -0.819249 0.165639 -0.548994 -0.819249 0.185188 -0.35604 -0.915937 0.184355 -0.365332 -0.91244 0.119625 -0.980541 -0.155659 0.504529 -0.51103 -0.695915 0.49399 -0.557049 -0.667585 0.43781 -0.666945 -0.602916 0.328501 -0.829118 -0.452384 0.328498 -0.82912 -0.452382 0.122865 -0.977894 -0.169199 0.110996 -0.980541 -0.161925 -0.026626 -0.97947 -0.199823 -0.114379 -0.97947 -0.166 -0.794072 -0.42926 -0.430332 0.391529 -0.509628 -0.766149 0.244624 -0.585773 -0.772676 -0.109408 -0.560255 -0.821063 0.0580328 -0.559083 -0.827078 0.182293 -0.556546 -0.810571 -0.258844 -0.247481 -0.933677 -0.509436 -0.495336 -0.703646 -0.503871 -0.459718 -0.731282 -0.688599 -0.267699 -0.673921 -0.837267 -0.309665 -0.450658 -0.836596 -0.307502 -0.453377 -0.940179 -0.19154 -0.281737 -0.0995695 -0.880581 -0.463317 -0.133624 -0.542298 -0.829492 -0.477564 -0.539946 -0.693102 -0.477564 -0.539945 -0.693103 -0.716063 -0.544145 -0.437219 -0.70588 -0.596153 -0.382538 -0.0751904 -0.822156 -0.564275 -0.0751885 -0.822155 -0.564276 -0.322989 -0.822155 -0.468764 -0.32299 -0.822156 -0.468761 -0.500493 -0.822156 -0.271232 -0.494318 -0.760404 -0.42123 -0.27038 -0.962671 0.0126333 0.250236 -0.657091 -0.711065 0.188973 -0.822156 -0.536981 0.188973 -0.822156 -0.536981 0.06692 -0.97947 -0.190158 0.873593 -0.279502 -0.398389 0.826475 -0.191508 0.5294 0.891328 -0.443387 -0.0945696 0.960914 -0.263721 0.084237 0.893679 -0.296852 0.336476 0.532323 -0.772931 -0.345269 0.367091 -0.364706 -0.855707 0.286858 -0.822158 -0.4917 0.424143 -0.539951 -0.727019 0.424144 -0.539949 -0.727019 0.0808742 -0.987037 -0.138625 0.604053 -0.00319775 -0.796938 0.888339 -0.303965 0.34418 0.866142 -0.370383 0.33558 0.785764 -0.540285 0.30111 0.783085 -0.542888 0.3034 0.670011 -0.695484 0.25959 0.531387 -0.822463 0.202935 0.526774 -0.824465 0.206801 0.188349 -0.979589 0.0702153 0.186604 -0.978084 -0.0923598 0.173223 -0.93906 -0.296918 0.28686 -0.822157 -0.4917 0.577489 -0.726871 -0.371706 0.70776 -0.539949 -0.455555 0.70776 -0.539949 -0.455556 0.478674 -0.822159 -0.308102 0.478675 -0.822158 -0.308102 0.169509 -0.979471 -0.109106 0.899971 -0.426277 -0.09133 0.837397 -0.539949 -0.0849799 0.837397 -0.539949 -0.0849797 0.56635 -0.822158 -0.0574737 0.56635 -0.822158 -0.0574736 0.200557 -0.979471 -0.0203527 -0.891439 -0.236507 -0.386524 -0.977495 -0.188409 0.094894 -0.953526 -0.299067 0.0367068 -0.902905 -0.428433 0.0347581 -0.839502 -0.543279 -0.0092002 -0.802951 -0.595244 0.0309103 -0.621763 -0.78284 0.0239353 -0.512991 -0.821525 -0.248872 -0.757809 -0.53904 -0.367643 -0.757809 -0.539041 -0.367641 -0.813875 -0.426272 -0.394841 -0.591028 -0.208007 -0.779371 -0.201898 -0.979376 0.00777226 -0.453882 -0.890891 0.0174727 -0.118863 -0.979376 -0.163385 -0.335429 -0.821524 -0.46107 -0.335429 -0.821525 -0.461068 -0.495508 -0.539043 -0.681106 -0.495506 -0.53904 -0.681109 -0.473626 -0.593157 -0.651033 -0.357958 -0.364863 -0.8595 -0.0279508 -0.979376 -0.200105 -0.0788763 -0.821525 -0.56469 -0.0788748 -0.821525 -0.564691 -0.116517 -0.539039 -0.834183 -0.116519 -0.539041 -0.834181 -0.125308 -0.423673 -0.897106 -0.126659 -0.348271 -0.928797 -0.559149 -0.827635 -0.0487077 -0.512991 -0.821525 -0.248871 -0.181785 -0.979376 -0.0881904 0.825819 -0.540285 -0.161599 0.904334 -0.190658 0.381877 0.946145 -0.282627 0.157895 0.595064 -0.671227 -0.441987 0.834598 -0.350227 -0.42519 0.920374 -0.347095 -0.180102 0.848366 -0.495433 -0.186604 0.958535 -0.282874 -0.0345464 0.663027 -0.54705 -0.51101 0.159533 -0.979505 -0.122956 0.450614 -0.822392 -0.347301 0.450616 -0.822392 -0.3473 0.558332 -0.822392 -0.109257 0.197669 -0.979505 -0.0386806 0.194113 -0.979505 0.0537527 0.908806 -0.332773 0.251661 0.870282 -0.429571 0.240993 0.818976 -0.544468 0.181199 0.773508 -0.596495 0.214195 0.598461 -0.783825 0.165722 0.670445 -0.541036 -0.507724 0.825819 -0.540285 -0.161599 0.558332 -0.822392 -0.109256 0.555112 -0.82823 0.0767161 0.436615 -0.891487 0.120905 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.905177 -0.252158 -0.342156 -0.905177 -0.252158 -0.342155 -0.961963 -0.252158 0.105089 -0.961963 -0.252157 0.105089 -0.809951 -0.252157 0.529524 -0.809951 -0.252157 0.529524 -0.482138 -0.252157 0.839023 -0.482138 -0.252158 0.839023 -0.67059 -0.697177 -0.253482 -0.67059 -0.697177 -0.253481 -0.712659 -0.697177 0.0778538 -0.712659 -0.697177 0.0778544 -0.600042 -0.697178 0.392292 -0.600043 -0.697177 0.392291 -0.357186 -0.697177 0.62158 -0.357187 -0.697177 0.62158 -0.248472 -0.964075 -0.0939217 -0.248472 -0.964075 -0.0939204 -0.26406 -0.964075 0.0288472 -0.264059 -0.964075 0.0288476 -0.222332 -0.964075 0.145355 -0.222333 -0.964075 0.145354 -0.132347 -0.964075 0.230312 -0.13235 -0.964075 0.230312 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0982307 -0.680942 -0.72572 0.192328 -0.891282 -0.410642 0.236989 -0.906304 -0.349929 0.231571 -0.907278 -0.35103 0.231578 -0.907552 -0.350316 0.241543 -0.893806 -0.377845 0.233705 -0.881154 -0.411035 0.203322 -0.916794 -0.343729 0.203505 -0.916584 -0.344179 0.229542 -0.907791 -0.351036 0.110371 -0.90054 -0.420531 0.130514 -0.878837 -0.458925 0.158031 -0.866333 -0.473807 0.188414 -0.876656 -0.44269 0.0108612 -0.79309 -0.609008 0.0613766 -0.836035 -0.545233 0.0563503 -0.804944 -0.59067 0.00875792 -0.791175 -0.611527 0.0124085 -0.790004 -0.612977 0.0768162 -0.432009 -0.898592 0.108875 -0.56725 -0.816317 0.0533618 -0.715278 -0.6968 0.292734 -0.755816 -0.585704 0.290939 -0.747643 -0.596979 0.312539 -0.650463 -0.692256 0.253212 -0.75013 -0.610892 0.2421 -0.75717 -0.606697 0.286693 -0.746914 -0.599939 0.357958 -0.753883 -0.550933 0.354837 -0.677496 -0.644274 0.378858 -0.751071 -0.540702 0.465517 -0.5532 -0.690842 0.506322 -0.505928 -0.698337 0.138319 -0.852576 -0.503967 0.151426 -0.816775 -0.556731 0.0529885 -0.789142 -0.61192 0.0493273 -0.795642 -0.603756 0.0102385 -0.784159 -0.620475 0.176388 -0.449136 -0.875879 0.194373 -0.556489 -0.807799 0.181054 -0.603695 -0.776384 0.186637 -0.704156 -0.685077 0.176404 -0.719913 -0.671273 0.150276 -0.813167 -0.562295 0.231907 -0.832486 -0.503176 0.232672 -0.831984 -0.503653 0.293527 -0.844011 -0.448873 0.282496 -0.849146 -0.446258 0.494215 -0.697177 0.519323 0.973483 -0.189919 -0.12752 0.794663 -0.598059 -0.104096 0.894033 -0.432422 -0.117113 0.281144 -0.189921 0.940685 0.323911 -0.254738 0.911148 0.667102 -0.252158 0.700993 0.667101 -0.252157 0.700994 0.912304 -0.252157 0.322672 0.614184 -0.785051 -0.0804545 0.709485 -0.704666 -0.00881115 0.67587 -0.697177 0.239047 0.26338 -0.964075 -0.0345014 0.263381 -0.964075 -0.0345013 0.250428 -0.964075 0.0885735 0.250428 -0.964075 0.0885735 0.183119 -0.964075 0.192424 0.258198 -0.432422 0.863913 0.2295 -0.598057 0.767892 0.281693 -0.704665 0.651226 0.177378 -0.78505 0.593492 0.129509 -0.891883 0.433327 0.963986 -0.254738 -0.0764191 0.912304 -0.252158 0.322672 0.67587 -0.697177 0.239048 0.494215 -0.697177 0.519323 0.18312 -0.964075 0.192423 0.164769 -0.965133 0.203393 0.0573829 -0.979716 0.191999 -0.2385 -0.965001 -0.10905 -0.2385 -0.965001 -0.10905 -0.879276 -0.255429 -0.402032 -0.920463 -0.190814 -0.341084 -0.819275 -0.434126 -0.374598 -0.647598 -0.702097 -0.296102 -0.762371 -0.606763 -0.225008 -0.560246 -0.787722 -0.256162 -0.895714 -0.405182 -0.183093 -0.936958 -0.156026 0.312676 -0.0584524 -0.513966 -0.855817 0.252651 -0.967463 -0.0135101 0.528288 -0.831747 -0.170611 -0.0436731 -0.930821 0.362856 0.665863 -0.635189 -0.391358 0.33348 -0.492443 -0.803922 0.458308 -0.489053 -0.742146 0.530253 -0.49933 -0.685202 0.578769 -0.487552 -0.653697 0.697345 -0.489066 -0.523951 0.749053 -0.466471 -0.470451 0.82342 -0.458438 -0.334385 0.235568 -0.740749 -0.629125 0.351816 -0.849321 -0.393548 0.353648 -0.851615 -0.386893 0.40484 -0.865589 -0.294722 0.444104 -0.895336 0.0338393 0.406077 -0.913682 -0.0169166 0.243894 -0.649381 -0.720292 0.488501 -0.714805 -0.500421 0.458005 -0.70411 -0.542642 0.536731 -0.701634 -0.468646 0.670067 -0.718908 -0.184882 0.633311 -0.742517 -0.21814 -0.500041 -0.837596 -0.219982 -0.313949 -0.87699 -0.363765 0.218401 -0.821296 -0.527042 0.202288 -0.830513 -0.518968 0.0628063 -0.935365 -0.348062 0.0293029 -0.945562 -0.324121 -0.112541 -0.985589 -0.126291 -0.153074 -0.983356 -0.0978753 0.0642789 -0.513158 -0.855884 0.103512 -0.509921 -0.85397 0.187675 -0.522801 -0.831539 -0.00784522 -0.738885 -0.673786 0.100219 -0.692912 -0.714023 -0.1505 -0.732433 -0.663997 -0.145188 -0.488643 -0.860319 -0.283847 -0.481407 -0.829264 -0.940977 -0.0780671 0.329346 -0.858272 -0.119586 0.499067 -0.819859 -0.0900064 0.565447 -0.743827 -0.138053 0.653959 -0.68062 -0.0917811 0.726865 -0.297132 -0.779564 0.551356 -0.940996 -0.109717 -0.320137 -0.993786 0.0286571 -0.107554 -0.987298 -0.0345419 -0.155081 -0.993247 -0.110362 -0.035774 -0.999764 -0.0211247 0.00500073 -0.982288 -0.175459 0.0657629 -0.983438 0.0265479 0.179292 -0.983794 -0.0507661 0.171963 -0.812803 -0.428522 -0.394615 -0.69673 -0.485448 -0.528117 -0.632613 -0.554842 -0.540326 -0.6921 -0.532463 -0.48732 -0.746638 -0.647276 -0.153511 0.133357 -0.107862 0.985181 0.334008 -0.106901 0.936489 0.335217 -0.102988 0.936495 0.497165 -0.0924389 0.862718 0.499271 -0.0871916 0.862047 0.662853 -0.084178 0.744002 0.66418 -0.0945023 0.741575 0.743741 -0.0573079 0.666007 0.769567 -0.00753022 0.638522 -0.51214 -0.177828 0.840292 -0.519665 -0.163208 0.838637 -0.304639 -0.0977819 0.947435 -0.162606 -0.197243 0.966775 -0.0878838 -0.102015 0.990893 0.0417103 -0.120022 0.991895 0.143479 -0.0861304 0.985898 0.944679 -0.312283 0.100305 0.94514 -0.319265 0.0691469 0.805312 -0.560179 0.194093 0.911498 -0.395587 -0.112616 0.876174 -0.414707 -0.245636 0.793453 -0.586534 -0.162512 0.782446 -0.618508 -0.0722953 0.721933 -0.691262 -0.0311392 0.689645 -0.721198 0.0652994 0.606561 -0.788357 0.102845 0.554074 -0.810313 0.190773 0.439088 -0.871628 0.217866 0.378494 -0.881541 0.282184 0.224885 -0.931613 0.285525 0.17674 -0.931159 0.318914 -0.0573212 -0.961105 0.27017 -0.833333 -0.552567 0.0150074 -0.884955 -0.464975 0.0255601 -0.765259 -0.594596 0.246646 -0.816173 -0.521787 0.248193 -0.63227 -0.619197 0.465649 -0.676098 -0.57235 0.464012 -0.411136 -0.62784 0.660896 -0.473928 -0.54941 0.688143 -0.220765 -0.553458 0.803086 -0.208139 -0.565127 0.798317 0.0365826 -0.527673 0.848659 0.0810802 -0.556952 0.826578 0.285176 -0.490856 0.823246 0.35403 -0.524599 0.774247 0.504468 -0.445322 0.73973 0.579497 -0.473642 0.663209 0.707448 -0.368478 0.60311 -0.144091 -0.77544 0.614761 -0.131039 -0.783738 0.607111 0.10747 -0.747396 0.655629 0.147825 -0.766185 0.625387 0.350875 -0.700432 0.621515 0.407478 -0.719346 0.562587 0.562176 -0.637675 0.52662 0.617435 -0.650126 0.442844 0.803409 -0.483183 0.347947 0.8109 -0.496256 0.310115 0.945659 -0.263785 0.190125 0.925513 -0.215734 0.311264 0.925111 -0.215362 0.312712 -0.63112 -0.773297 0.0608303 -0.692849 -0.718294 0.0633593 -0.518168 -0.81147 0.27022 -0.566442 -0.777542 0.273078 -0.35931 -0.826806 0.432767 -0.428172 -0.66729 0.60942 -0.185148 -0.670401 0.718528 -0.17209 -0.680496 0.712257 0.0722554 -0.643225 0.76226 0.115385 -0.667441 0.735669 0.321094 -0.600863 0.732026 0.384676 -0.627293 0.677147 0.538727 -0.546063 0.641551 0.604491 -0.566432 0.56013 0.786626 -0.405028 0.466017 0.68956 -0.302956 0.657819 0.858685 -0.344865 0.379115 0.856571 -0.103336 0.505577 0.878631 -0.118292 0.462617 0.82497 -0.223322 0.519184 0.743193 -0.22895 0.628686 0.707719 -0.270944 0.652475 0.602817 -0.265072 0.752561 0.538422 -0.316347 0.781042 0.422428 -0.296849 0.856408 0.312613 -0.354669 0.881182 0.208333 -0.324328 0.922718 0.0406474 -0.378586 0.924673 -0.0264306 -0.348454 0.936953 -0.247409 -0.382209 0.89034 -0.266242 -0.36928 0.890364 -0.512164 -0.365155 0.7774 -0.494163 -0.384436 0.779752 -0.722283 -0.333766 0.605729 -0.689514 -0.389199 0.610815 -0.865863 -0.296351 0.403059 -0.833286 -0.380246 0.401308 -0.946537 -0.258258 0.193314 -0.917118 -0.35746 0.1764 -0.975154 -0.221443 -0.00620483 -0.945539 -0.323046 -0.0399626 -0.965106 -0.186006 -0.184314 0.261568 -0.761237 -0.59338 0.246148 -0.724343 -0.644002 0.341334 -0.64009 -0.688314 0.0565567 -0.601648 -0.796757 0.395571 -0.486432 -0.779042 0.230655 -0.811956 -0.536214 0.22992 -0.863073 -0.449714 0.200696 -0.935443 -0.290977 0.205324 -0.947549 -0.244933 0.116521 -0.986507 0.115011 0.0776701 -0.996964 0.00547456 -0.00117069 -0.975997 0.217782 -0.27157 -0.95791 0.0930487 -0.255189 -0.965971 0.0421782 -0.474384 -0.85359 -0.215277 -0.39506 -0.858851 -0.326042 -0.451412 -0.740002 -0.498623 -0.579264 -0.676334 -0.455001 -0.675394 -0.641581 -0.363617 0.207901 -0.81588 -0.539553 0.218266 -0.774643 -0.593538 -0.0422573 -0.880497 -0.472165 0.0329309 -0.838351 -0.544135 -0.202031 -0.893469 -0.401119 -0.280224 -0.703781 -0.652814 -0.401038 -0.696504 -0.595022 -0.396152 -0.43363 -0.809338 -0.628379 -0.386394 -0.675159 -0.506684 -0.373152 -0.777193 -0.810306 -0.280679 -0.514416 -0.689412 -0.279958 -0.668083 0.929041 -0.365631 -0.0565321 0.829284 -0.55733 0.0408726 0.79481 -0.605081 -0.0464053 0.727386 -0.63312 0.264707 0.617198 -0.721339 0.314224 0.573143 -0.716431 0.397786 0.421217 -0.79677 0.433283 0.372859 -0.785274 0.494288 0.17721 -0.848728 0.498255 0.140794 -0.83552 0.531115 -0.0860674 -0.870134 0.485241 -0.0986806 -0.863808 0.494062 -0.322294 -0.860923 0.393623 -0.262237 -0.927997 0.264676 -0.60335 -0.635337 0.481991 -0.329627 -0.928129 0.172981 -0.546018 -0.834705 -0.0716383 -0.829646 -0.547111 0.111159 -0.680371 -0.715582 -0.158233 -0.741813 -0.568859 -0.355124 -0.843926 -0.496033 -0.204306 -0.865251 -0.343701 -0.364979 -0.931828 -0.279943 -0.230931 -0.931824 -0.170264 -0.320491 -0.837452 -0.179513 -0.516187 0.199231 -0.979644 -0.0245819 0.273484 -0.961855 -0.00642296 0.563467 -0.821351 -0.0888161 0.61546 -0.784501 -0.0759379 0.832661 -0.54417 -0.102737 0.882472 -0.437083 -0.173788 0.795939 -0.597358 -0.0982061 0.974475 -0.189586 -0.120234 0.974475 -0.189586 -0.120235 0.944052 -0.1928 0.26757 0.852449 -0.190937 0.486696 0.602662 -0.368327 0.707908 0.930434 -0.0991344 0.352796 0.785658 -0.542215 0.2979 0.784149 -0.544041 0.298548 0.672436 -0.694853 0.254969 0.530164 -0.823721 0.201023 0.530164 -0.823721 0.201024 0.187701 -0.979644 0.0711712 0.187701 -0.979644 0.0711713 -0.0552984 -0.597259 0.80014 -0.8364 -0.251666 0.486928 -0.8364 -0.251666 0.486928 -0.511048 -0.251667 0.821885 -0.511047 -0.251667 0.821885 -0.0667251 -0.251667 0.965511 -0.0667274 -0.251665 0.965511 -0.620183 -0.69643 0.361053 -0.620183 -0.696429 0.361052 -0.378937 -0.696429 0.60942 -0.378937 -0.696429 0.60942 -0.128931 -0.704101 0.698297 -0.0427614 -0.784422 0.618752 -0.230007 -0.963933 0.133904 -0.230007 -0.963933 0.133904 -0.140536 -0.963933 0.226016 -0.140536 -0.963933 0.226016 -0.0183493 -0.963933 0.265512 -0.0183503 -0.963933 0.265513 -0.143939 -0.251667 0.95705 -0.14394 -0.251667 0.95705 0.320941 -0.251667 0.91305 0.32094 -0.251666 0.913051 0.711109 -0.251666 0.656497 0.711109 -0.251666 0.656497 -0.10673 -0.696429 0.709644 -0.106729 -0.69643 0.709644 0.237974 -0.69643 0.677019 0.237974 -0.696429 0.677019 0.527281 -0.69643 0.486786 0.52728 -0.696429 0.486787 -0.0395827 -0.963933 0.263186 -0.0395858 -0.963933 0.263186 0.0882575 -0.963933 0.251086 0.0882584 -0.963933 0.251086 0.195553 -0.963933 0.180535 0.195553 -0.963933 0.180534 0.944351 -0.160902 0.286901 0.68778 -0.722188 -0.0735118 0.577648 -0.58069 -0.573692 0.628645 -0.152643 -0.762565 0.755859 -0.369351 -0.540608 0.756427 -0.42944 -0.493355 0.836479 -0.159064 -0.524406 0.726707 -0.138079 -0.672927 0.919768 -0.0656874 -0.386927 0.984258 -0.08372 -0.155654 0.877985 -0.47861 0.00868739 0.816221 -0.576945 0.0302832 0.943756 -0.315774 0.0980356 0.887453 -0.444429 0.122104 0.972754 -0.146853 0.179396 0.8089 -0.205748 -0.550771 0.86448 -0.171909 -0.472358 0.95183 -0.267988 -0.149003 0.981985 -0.123987 -0.142596 0.99599 -0.0675097 0.0587011 0.336118 -0.808748 -0.482651 0.349419 -0.805562 -0.478514 0.360403 -0.843829 -0.397569 0.383902 -0.86187 -0.331361 0.389769 -0.863083 -0.321199 0.38843 -0.878628 -0.277733 0.476478 -0.183995 -0.859718 0.559613 -0.224138 -0.797869 0.557504 -0.436781 -0.705982 0.539232 -0.388693 -0.747092 0.404054 -0.716134 -0.569115 0.598052 -0.649901 -0.469002 0.639263 -0.691648 -0.336103 0.968207 0.0187349 0.249449 0.929735 -0.303421 0.208634 0.972805 -0.140836 -0.183893 0.928598 -0.316392 -0.193912 0.846682 -0.457349 -0.271959 0.849453 -0.450512 -0.274716 0.681126 -0.678266 -0.27572 0.668953 -0.72526 -0.162788 0.389878 -0.884939 -0.254711 -0.188409 -0.980555 0.0549045 -0.246258 -0.965896 0.0800169 -0.42564 -0.896351 0.124036 -0.586244 -0.791917 0.170838 -0.675834 -0.707066 0.208099 -0.763047 -0.60689 0.22236 -0.862552 -0.439116 0.251358 -0.924997 -0.258811 0.278205 -0.942275 -0.191623 0.274589 -0.113077 -0.463259 -0.878979 -0.174651 -0.595264 -0.78432 -0.988477 -0.142331 0.0515301 -0.985126 -0.132396 0.109537 -0.887837 -0.376743 -0.264218 -0.127843 -0.611256 -0.781039 -0.157259 -0.44504 -0.881595 -0.476119 -0.44877 -0.756251 -0.352386 -0.410705 -0.84092 -0.665959 -0.475748 -0.574598 -0.571379 -0.42023 -0.704935 -0.880832 -0.310163 -0.357679 -0.482019 -0.585513 -0.651792 -0.453038 -0.580924 -0.676228 -0.674355 -0.526803 -0.51742 -0.655124 -0.527214 -0.541163 -0.878199 -0.39334 -0.272122 -0.897077 -0.283204 -0.339187 -0.990419 -0.119461 0.0692815 -0.206667 -0.746848 -0.632065 -0.140714 -0.731142 -0.667556 -0.411468 -0.718664 -0.560549 -0.448341 -0.71206 -0.540334 -0.605699 -0.649635 -0.45946 -0.645261 -0.636673 -0.422239 -0.872592 -0.457134 -0.17208 -0.864974 -0.464769 -0.189233 -0.978223 -0.16112 0.130846 -0.978168 -0.159898 0.132738 0.894362 -0.0782502 0.440448 0.403161 -0.87152 -0.279132 0.799583 -0.470256 -0.373532 0.85325 -0.430057 -0.294985 0.932849 -0.0936702 0.347878 0.96403 -0.227551 0.137357 0.960548 -0.276751 0.0274899 0.949342 -0.313433 -0.0225745 0.882401 -0.41359 -0.224304 0.558754 -0.717048 -0.416696 0.63519 -0.533252 -0.558727 0.666027 -0.517527 -0.537191 0.530147 -0.729683 -0.431865 0.774301 -0.605244 -0.184763 0.784435 -0.598173 -0.163863 0.913133 -0.394243 0.103732 0.914491 -0.38776 0.115533 0.472408 -0.818984 -0.325723 0.265034 -0.873149 -0.409107 0.70812 -0.703075 -0.0652135 0.690987 -0.718436 -0.0799137 0.870068 -0.458268 0.181581 0.82935 -0.545392 0.121352 0.888624 -0.393759 0.235165 0.93375 -0.0971278 0.344494 0.919046 -0.131171 0.371682 0.919372 -0.134782 0.369579 0.905049 -0.156212 0.39558 0.90378 -0.240641 0.353939 0.434963 -0.777693 0.453873 0.619921 -0.707107 0.340146 0.388681 -0.896351 0.213266 0.191287 -0.963363 0.187992 0.172048 -0.980555 0.0944019 0.860452 -0.191623 0.472125 0.807673 -0.258066 0.530157 0.787653 -0.439116 0.432181 0.696787 -0.606891 0.382323 -0.0863521 -0.965834 0.244352 -0.0863523 -0.965834 0.244352 -0.235774 -0.706605 0.667173 -0.235774 -0.706605 0.667173 -0.321875 -0.258478 0.910816 -0.321876 -0.258477 0.910816 -0.473872 0 0.880594 -0.498236 -0.00280778 0.867037 -0.8198 0.00314166 0.572642 -0.836998 -0.000317959 0.547206 -0.996007 0.000351476 0.0892742 -0.994082 0.00277069 0.108598 -0.927306 -0.00253587 -0.374295 -0.935404 0 -0.353581 0.091081 -0.608078 0.788635 0.09108 -0.608081 0.788633 0.0699206 -0.792829 0.60542 0.0699205 -0.792829 0.60542 0.0508155 -0.896561 0.439995 0.0128307 -0.965412 0.260413 0.0224209 -0.980719 0.194134 0.102933 -0.441655 0.891261 0.0890106 -0.194973 0.976761 0.110833 -0.258389 0.959662 0.0556756 -0.814257 -0.577829 0.26321 -0.815022 -0.516198 0.308244 -0.620381 -0.721188 0.306779 -0.634564 -0.709377 0.204498 -0.643728 -0.737424 0.203271 -0.612167 -0.764155 0.0992315 -0.623342 -0.775627 0.103982 -0.695842 -0.710627 0.0992383 -0.734606 -0.671198 0.0688738 -0.356763 -0.931652 0.346087 -0.193813 -0.917965 0.352782 -0.127633 -0.92696 0.23722 -0.138362 -0.961552 0.206559 -0.333587 -0.919811 0.269658 -0.781067 -0.563222 0.199364 -0.845764 -0.494912 0.195255 -0.730669 -0.654216 0.168608 -0.800309 -0.575392 0.133943 -0.804081 -0.579234 -0.0729652 -0.326846 -0.942257 -0.0602735 -0.374045 -0.92545 -0.0283678 -0.53782 -0.842582 -0.162112 -0.109841 -0.98064 -0.0427244 -0.3781 -0.924778 -0.105412 -0.132768 -0.985526 -0.0288056 -0.122886 -0.992003 0.0501675 -0.169511 -0.984251 0.0496603 -0.13754 -0.989251 0.160874 -0.12595 -0.978906 0.0173497 -0.716421 -0.697452 -0.0104464 -0.595039 -0.803629 0.091505 -0.581328 -0.808507 0.075535 -0.392449 -0.916667 0.209867 -0.378008 -0.901702 0.207306 -0.405996 -0.890052 0.341581 -0.39403 -0.853266 0.328676 -0.4615 -0.824009 -0.887503 -0.382426 -0.257078 -0.129923 -0.741198 -0.658594 -0.733234 -0.16909 -0.658618 -0.58126 -0.724986 -0.369503 -0.556774 -0.631807 -0.53928 -0.408923 -0.727486 -0.550949 -0.933391 -0.318588 0.165175 -0.977894 -0.203969 0.0460415 -0.975439 -0.0977274 -0.197402 -0.966794 -0.244153 -0.0754902 -0.934867 -0.0227121 -0.35427 -0.773378 -0.493926 -0.397396 -0.78682 -0.317694 -0.529136 -0.80973 -0.524146 -0.263835 -0.942581 -0.255645 -0.21491 -0.920356 -0.149571 -0.36135 -0.894416 -0.137788 -0.425481 -0.879653 -0.0767485 -0.469382 -0.726371 -0.0215402 -0.686966 -0.718533 -0.0884718 -0.689843 -0.817141 -0.220606 -0.532554 -0.713961 -0.464624 -0.523817 -0.702471 -0.30245 -0.64425 -0.1696 -0.780845 -0.601263 -0.169743 -0.774843 -0.608938 -0.18551 -0.807968 -0.559261 -0.0264896 -0.724575 -0.688687 -0.353321 -0.142144 -0.92464 -0.31546 -0.364448 -0.876163 -0.282066 -0.256196 -0.924555 -0.199072 -0.564315 -0.801199 -0.209996 -0.589052 -0.780333 -0.114316 -0.727231 -0.676807 -0.109228 -0.692251 -0.713343 -0.429157 0.0575253 -0.901396 -0.388625 -0.0869454 -0.917285 -0.64285 -0.242831 -0.726483 -0.573049 -0.435836 -0.694019 -0.559317 -0.243278 -0.792452 -0.399119 -0.569967 -0.718221 -0.457498 -0.656361 -0.599905 -0.453872 -0.590685 -0.667151 -0.52538 -0.662642 -0.533743 -0.528768 -0.716376 -0.455203 -0.851471 -0.340382 -0.398921 -0.829547 -0.537634 -0.151001 -0.997625 -0.0674272 0.0140509 0.988395 0 -0.151903 0.991526 -0.00229983 -0.129884 0.949063 0.00256577 0.315076 0.942769 0.000325443 0.333447 0.666814 -0.000359128 0.745224 0.689374 0.00354776 0.724397 0.259529 -0.00317925 0.96573 0.286356 0 0.958123 -0.909444 0 -0.415826 -0.901175 0.00181746 -0.433452 -0.97884 -0.000811626 -0.204625 -0.996079 -0.0064918 -0.0882249 -0.899505 -0.00111815 0.436908 -0.830918 -0.0343887 0.555331 -0.916679 -0.00675841 0.399567 -0.97053 0.000346346 0.240979 -0.99878 -0.00165533 -0.0493544 -0.995466 -0.0282781 0.090817 -0.999773 -0.017058 0.012753 0.0860434 0.000420386 0.996291 -0.0172171 -0.00546691 0.999837 -0.115301 -0.0154431 0.993211 -0.214649 0.000306537 0.976691 -0.578677 -0.000512781 0.815556 -0.507525 -0.0229173 0.861332 -0.704736 0.000413861 0.709469 0.240762 -0.000741615 0.970584 0.376417 -0.0134121 0.926353 0.405935 -0.00910825 0.913857 0.775471 -0.00726657 0.631341 0.657916 -0.00102573 0.753091 0.548585 0.00149521 0.836093 0.97651 0 -0.215473 0.992444 0.00778626 -0.122451 0.962021 -0.0130862 0.272662 0.983525 0 0.18077 0.868426 0 0.495818 0.770943 -0.00823084 0.636851 0.961626 -0.173929 -0.212189 0.777863 -0.60454 -0.171641 0.885858 -0.420769 -0.195471 0.418378 -0.903569 -0.0923182 0.598586 -0.790095 -0.132082 0.173502 -0.984089 -0.0382845 0.946453 -0.256614 -0.195899 0.951978 -0.251244 0.174972 0.951978 -0.251241 0.174972 0.750618 -0.251238 0.611107 0.750617 -0.251241 0.611107 0.364376 -0.25124 0.896721 0.364374 -0.251246 0.89672 -0.111616 -0.251246 0.961466 -0.111616 -0.251247 0.961466 -0.560115 -0.251246 0.789396 -0.560116 -0.251238 0.789398 -0.870654 -0.25124 0.422895 -0.870654 -0.251241 0.422894 -0.966745 -0.251241 -0.0477714 -0.966745 -0.25124 -0.0477712 -0.887441 -0.173928 -0.426846 -0.876403 -0.256612 -0.407514 -0.817519 -0.420765 -0.393216 -0.717852 -0.604544 -0.345277 0.69635 -0.704235 -0.138385 0.706417 -0.695786 0.129838 0.706416 -0.695786 0.129838 0.556996 -0.695786 0.453472 0.556998 -0.695784 0.453473 0.270386 -0.695783 0.665416 0.270384 -0.695787 0.665412 -0.0828245 -0.695787 0.713457 -0.0828243 -0.695784 0.71346 -0.415635 -0.695784 0.585775 -0.415635 -0.695784 0.585775 -0.646071 -0.695785 0.31381 -0.64607 -0.695786 0.313809 -0.717374 -0.695786 -0.0354487 -0.717373 -0.695787 -0.0354488 -0.646126 -0.704237 -0.294231 -0.55241 -0.790093 -0.265701 0.256418 -0.965632 -0.0424783 0.262195 -0.963811 0.048191 0.262194 -0.963811 0.0481909 0.206735 -0.963811 0.168311 0.206735 -0.963811 0.168311 0.100356 -0.963811 0.246975 0.100357 -0.96381 0.246977 -0.0307413 -0.96381 0.26481 -0.0307414 -0.963811 0.264808 -0.154267 -0.963811 0.217416 -0.154267 -0.963811 0.217416 -0.239796 -0.963811 0.116474 -0.239796 -0.963811 0.116474 -0.266262 -0.963811 -0.0131573 -0.266262 -0.963811 -0.0131573 -0.235647 -0.965207 -0.113343 -0.235646 -0.965207 -0.113343 0.268581 -0.53504 0.800997 0.262111 -0.57032 0.778481 0.255656 -0.172144 0.951318 0.196258 -0.841022 0.504148 0.222974 -0.832012 0.507975 0.27051 -0.698621 0.662385 0.0907825 -0.991329 0.0949979 0.0636575 -0.939574 0.336375 0.150839 -0.955622 0.253049 0.541526 -0.836554 -0.0832253 0.607119 -0.787694 -0.104621 0.427564 -0.901594 -0.0657108 0.973674 -0.171949 -0.149641 0.973674 -0.171948 -0.149641 0.837896 -0.530422 -0.128773 0.894976 -0.418087 -0.155634 0.79071 -0.600008 -0.121522 0.524131 -0.833672 0.174004 0.524131 -0.833672 0.174004 0.807117 -0.526083 0.267951 0.807118 -0.526082 0.267952 0.935243 -0.170051 0.310487 0.935243 -0.170053 0.310487 0.657102 -0.170051 0.73437 0.657102 -0.170051 0.73437 0.567082 -0.526081 0.633764 0.56708 -0.526085 0.633763 0.368254 -0.833673 0.411557 0.368254 -0.833672 0.411557 0.12117 -0.983351 0.135419 0.172458 -0.983351 0.0572537 0.172457 -0.983352 0.0572534 0.177634 -0.983718 -0.0272999 0.177633 -0.983718 -0.0272998 0.114729 0 0.993397 0.114729 0 0.993397 0.0989447 -0.126883 0.98697 0.0953547 -0.166267 0.98146 0.0897165 -0.265053 0.960051 0.0814824 -0.449712 0.889449 0.0554515 -0.781674 0.621218 -0.995179 -0.00126949 0.0980709 -0.998504 0.0292677 -0.0461885 -0.997363 0.0109527 0.0717443 -0.97752 0 0.210844 -0.886972 0.0421537 -0.459895 -0.937051 0.0191081 -0.348668 -0.98107 0.000678422 -0.193653 -0.951224 1.99923e-05 -0.3085 -0.720242 -1.03831e-05 -0.693723 -0.754191 0.0129427 -0.656528 -0.382286 -0.0133306 -0.923948 -0.427341 0 -0.904091 -0.180099 0 -0.983648 -0.107624 0.0410711 -0.993343 -0.10657 0.0431913 -0.993367 -0.0457433 0.00967662 -0.998906 0.319454 0 -0.947602 0.332005 0.0852394 -0.939419 0.229027 -0.0135175 -0.973326 0.108718 0.0614703 -0.99217 0.133241 0.160236 -0.978045 0.0374928 -0.0259362 -0.99896 -0.960066 -8.15337e-08 0.279774 -0.960066 0 0.279774 -0.960066 -7.30906e-08 0.279774 -0.960066 0 0.279774 0.876699 0 0.48104 0.876699 0 0.481039 0.876699 -3.05265e-08 0.481039 0.876699 1.70892e-08 0.481039 0.876699 7.95399e-08 0.481039 0.735251 2.087e-05 -0.677795 0.573348 7.1221e-06 -0.819312 0.636419 0.0514181 -0.769628 0.483973 0 -0.875083 0.829707 0.0158323 -0.557974 0.852743 0.0385772 -0.520904 0.922695 -1.49614e-06 -0.385531 0.995459 2.74549e-05 -0.0951917 0.987787 0.0422782 -0.149963 0.950328 0 0.311251 0.95385 -0.00673735 0.300209 0.998022 0.00209266 0.0628283 -0.202023 -0.755971 0.622652 -0.282198 -0.419271 0.862888 -0.303278 -0.242248 0.921596 -0.333199 0 0.942857 -0.333199 0 0.942857 -0.317216 -0.111463 0.94178 -0.312629 -0.148965 0.938122 0.734757 0 0.67833 0.734757 0 0.67833 0.331615 0 0.943415 0.331615 0 0.943415 -0.148726 0 0.988878 -0.148726 0 0.988878 -0.0689441 0 0.997621 -0.0689441 0 0.997621 -0.528043 0 0.849217 -0.528043 0 0.849217 -0.864216 0 0.503121 -0.864216 0 0.503121 -0.151104 -0.983614 0.0983391 -0.166655 -0.983718 -0.0672681 -0.204792 -0.955636 0.211709 -0.306552 -0.841021 0.445769 -0.333413 -0.832018 0.443375 -0.477672 -0.53727 0.695104 -0.411094 -0.630779 0.658118 -0.510816 -0.173752 0.841949 -0.416983 -0.475068 0.774878 -0.250319 -0.963868 -0.0910953 -0.567006 -0.787692 -0.240925 -0.508059 -0.836553 -0.205071 -0.74184 -0.600011 -0.299434 -0.78379 -0.529707 -0.324165 -0.84297 -0.416687 -0.340254 -0.913498 -0.171948 -0.368721 -0.913498 -0.171947 -0.368721 -0.139019 -0.93959 0.3128 -0.110898 -0.990808 0.0774633 -0.452745 -0.833672 0.316248 -0.452744 -0.833673 0.316247 -0.697191 -0.52608 0.486996 -0.697192 -0.526077 0.486997 -0.807863 -0.170064 0.564302 -0.807863 -0.170053 0.564304 -0.180988 -0.983352 0.0162223 -0.180987 -0.983352 0.0162223 -0.550054 -0.833673 0.0493024 -0.550055 -0.833672 0.0493027 -0.84704 -0.526079 0.0759221 -0.847039 -0.526081 0.0759219 -0.9815 -0.170054 0.0879739 -0.9815 -0.170054 0.087974 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.140745 -0.836379 -0.529774 0.508746 -0.842299 -0.178072 0.693451 -0.69278 -0.197943 0.290198 -0.915331 -0.279203 -0.366707 -0.0944493 -0.92553 -0.577472 -0.070233 -0.813384 -0.283998 -0.226136 -0.931777 0.463534 -0.677527 -0.571046 0.528224 -0.647246 -0.549593 0.255767 -0.624009 -0.738374 0.344788 -0.594172 -0.726692 0.0233673 -0.523529 -0.851688 0.134339 -0.498496 -0.85642 -0.207367 -0.386239 -0.898787 0.0103909 -0.813658 -0.581252 -0.273018 -0.733004 -0.62303 -0.288497 -0.703813 -0.649166 -0.480531 -0.551461 -0.681895 -0.496352 -0.465534 -0.732743 -0.763771 -0.290857 -0.576244 -0.0823546 -0.370744 -0.925077 -0.412101 -0.229346 -0.881801 -0.452461 -0.278844 -0.847069 -0.653974 -0.130867 -0.745112 -0.641661 -0.170372 -0.747827 0.656409 -0.739566 -0.148894 0.436299 -0.865031 -0.247718 0.459127 -0.844786 -0.274844 0.22205 -0.886922 -0.405047 0.190117 -0.865273 -0.463852 0.0171396 -0.851994 -0.523272 0.806683 -0.528581 -0.26432 0.689315 -0.552513 -0.468588 0.596827 -0.542186 -0.591467 0.628057 -0.526973 -0.572576 0.404829 -0.503386 -0.763359 0.47238 -0.477109 -0.741097 0.185937 -0.420732 -0.887925 0.274989 -0.395997 -0.876109 -0.042705 -0.311128 -0.949408 0.0802597 -0.288169 -0.95421 -0.266241 -0.199375 -0.943062 -0.130202 -0.179722 -0.975063 -0.368268 -0.0924007 -0.925117 -0.317349 -0.0360101 -0.947625 -0.832324 -0.0864436 -0.547507 -0.632449 -0.327212 -0.702097 -0.576272 -0.268596 -0.771859 -0.345059 -0.410596 -0.844006 -0.302407 -0.501684 -0.810471 -0.121488 -0.575802 -0.808512 -0.0820422 -0.648908 -0.756431 0.115586 -0.698831 -0.705886 0.149285 -0.749453 -0.645007 0.339374 -0.764369 -0.548238 0.365929 -0.79282 -0.487373 0.644677 -0.725591 -0.240642 0.706866 -0.642944 -0.294897 0.702228 -0.670618 -0.239054 0.776051 -0.563081 -0.284052 0.332403 -0.871659 -0.360166 0.0818879 -0.129859 -0.988145 -0.768268 -0.142198 -0.624135 -0.685838 -0.067979 -0.724573 0.0360364 -0.805915 -0.590934 0.244838 -0.859868 -0.447976 0.184612 -0.871883 -0.453583 0.0478413 -0.815485 -0.576797 -0.224037 -0.224801 -0.9483 -0.113948 -0.262453 -0.958193 -0.073339 -0.396603 -0.915056 0.0327059 -0.413209 -0.910049 0.0883901 -0.553096 -0.828415 0.182785 -0.549735 -0.815096 0.262308 -0.707103 -0.656658 -0.839271 -0.0923997 -0.535804 -0.764427 -0.135114 -0.630393 -0.732551 -0.263584 -0.627608 0.414626 -0.762782 -0.496235 0.345969 -0.776024 -0.527344 0.271909 -0.69002 -0.670774 0.138429 -0.724624 -0.675098 0.0399878 -0.593465 -0.803866 -0.0533395 -0.596514 -0.800828 -0.133989 -0.447348 -0.884266 -0.238173 -0.430411 -0.870643 -0.293709 -0.283245 -0.912966 -0.0728707 -0.36144 -0.929544 0.29647 0.0406697 -0.954176 0.388511 -0.15193 -0.908832 0.384966 -0.107184 -0.916686 0.466424 -0.264896 -0.843966 0.466126 -0.258056 -0.846247 0.534643 -0.376522 -0.756563 0.53435 -0.403752 -0.742599 0.65135 -0.741091 -0.16287 0.589542 -0.482133 -0.648065 0.55899 -0.668579 -0.490442 0.667618 -0.531097 -0.521749 0.594784 -0.778973 -0.198577 0.623682 -0.755647 -0.200047 -0.294305 -0.709829 -0.639943 -0.547758 -0.513159 -0.66078 -0.550316 -0.596786 -0.583951 -0.648126 -0.339502 -0.681668 -0.568265 -0.268373 -0.77785 -0.603761 -0.126932 -0.786995 -0.527082 -0.0606296 -0.847649 -0.0878886 -0.779249 -0.620521 -0.168873 -0.713718 -0.679771 -0.165568 -0.688294 -0.706285 -0.349319 -0.420062 -0.837571 -0.365943 -0.537813 -0.759502 -0.474796 -0.310437 -0.823527 -0.399373 -0.245448 -0.883322 -0.429269 -0.116445 -0.895639 0.507528 -0.84353 -0.175703 0.519682 -0.826839 -0.2151 0.551956 -0.798402 -0.240621 0.52201 -0.828164 -0.204083 0.556547 -0.802094 -0.216565 0.536989 -0.657436 -0.528602 0.545934 -0.638901 -0.541998 0.395042 -0.600614 -0.69513 0.379561 -0.526503 -0.760742 0.281881 -0.465201 -0.839125 0.270959 -0.412693 -0.869636 0.157969 -0.307305 -0.938408 0.154537 -0.289293 -0.944684 0.0331965 -0.140163 -0.989572 -0.00334558 0.0878441 -0.996129 -0.247867 -0.109502 -0.962586 -0.352077 -0.0540238 -0.93441 -0.431684 -0.118521 -0.894204 -0.453259 -0.4932 0.742503 -0.624033 -0.634026 -0.456721 -0.877438 -0.246683 -0.411399 0.262861 -0.964487 -0.0258745 0.192763 -0.726112 -0.660003 0.169286 -0.704892 -0.688818 0.431199 -0.900153 0.0615753 0.64309 -0.732626 -0.222924 0.628206 -0.772067 0.0962831 0.839697 -0.526435 -0.133321 0.689 -0.67606 -0.261193 0.688384 -0.644511 -0.332766 0.621286 -0.734001 0.27431 -0.984396 -0.107663 -0.139189 -0.984348 -0.12064 -0.128469 -0.940656 -0.118133 -0.318137 -0.946707 -0.147262 -0.28646 -0.464681 -0.504213 -0.727902 -0.575428 -0.497979 -0.648768 -0.696029 -0.32149 -0.642019 -0.868889 -0.0274882 -0.494244 -0.795977 -0.286456 -0.533258 -0.838296 -0.414474 -0.354218 -0.849213 -0.313997 -0.424551 -0.885419 -0.432311 -0.170707 -0.264315 -0.668529 -0.69513 -0.315287 -0.80256 -0.50645 -0.645871 -0.560063 -0.518825 -0.684936 -0.687088 -0.242433 -0.898903 -0.38313 -0.212566 -0.901917 -0.428381 0.0551032 -0.986757 -0.150031 0.0616603 -0.98563 -0.0891655 0.143469 -0.84812 -0.163949 0.503799 -0.856377 -0.155445 0.492397 -0.889951 -0.127355 0.437913 0.412356 -0.908666 0.065487 0.304787 -0.928585 0.211742 0.0341562 -0.956629 0.289301 0.0874239 -0.875624 0.475016 -0.230678 -0.778656 0.583508 -0.491755 -0.510689 0.705247 -0.541041 -0.598783 0.590536 -0.279819 -0.790566 0.544708 -0.334187 -0.876717 0.345957 0.0156578 -0.961454 0.274519 -0.0158336 -0.998686 0.0487409 0.0754586 -0.997047 -0.0142632 -0.596887 -0.599373 0.533364 -0.643914 -0.678109 0.354321 -0.360757 -0.874936 0.32302 -0.401074 -0.915887 0.0170467 -0.11926 -0.992862 -0.00137855 -0.113007 -0.904039 -0.412242 0.0778908 -0.922421 -0.378249 0.113533 -0.916705 -0.383096 0.263177 -0.900707 -0.345636 -0.338201 -0.75607 -0.560338 -0.377906 -0.880664 -0.285688 -0.705027 -0.652727 -0.277281 -0.707525 -0.705568 0.0397836 -0.902545 -0.427229 0.0537482 -0.875346 -0.395327 0.278362 -0.952493 -0.148904 0.265679 -0.931507 -0.113836 0.345452 -0.728329 -0.114533 -0.675588 -0.546638 0.0133714 -0.837262 -0.365512 -0.131118 -0.921525 -0.365373 -0.131523 -0.921523 -0.153426 -0.22464 -0.962288 -0.13473 -0.270156 -0.953343 0.0629993 -0.320787 -0.945054 0.116695 -0.405626 -0.906559 0.831269 -0.528927 -0.170959 0.839364 -0.533362 -0.104853 0.838479 -0.542933 -0.0466506 0.825404 -0.563343 0.0367774 0.835971 -0.548735 -0.00656175 0.663838 -0.741225 0.0995213 0.280353 -0.386042 -0.878848 0.420798 -0.56188 -0.712194 0.419562 -0.378822 -0.824901 0.607276 -0.561348 -0.562231 0.60903 -0.543444 -0.577712 0.687462 -0.55556 -0.467706 0.72434 -0.562742 -0.398314 0.85653 -0.428907 -0.287045 0.854246 -0.492119 -0.167579 0.522012 -0.774834 0.35656 0.487924 -0.767495 0.415791 0.36839 -0.822039 0.434213 0.276212 -0.826357 0.490755 0.152261 -0.84028 0.520333 0.136403 -0.784599 0.604813 -0.162661 -0.656175 0.736869 -0.148018 -0.811069 0.565914 -0.260201 -0.662504 0.702413 -0.699406 -0.315916 0.641115 -0.788413 -0.333566 0.516855 -0.787939 -0.317963 0.527305 -0.850426 -0.416276 0.321699 -0.67295 -0.666175 0.321482 -0.708325 -0.704823 0.0387369 -0.400332 -0.916197 0.0178142 -0.397881 -0.861897 -0.314363 0.146812 -0.953377 -0.263665 -0.0420382 -0.859409 -0.509557 0.00835637 -0.727426 -0.686135 -0.165291 -0.647781 -0.743679 -0.129106 -0.564508 -0.815268 -0.373935 -0.29886 -0.877984 -0.357187 -0.517928 -0.777283 -0.600053 -0.116357 -0.791453 -0.598597 -0.391125 -0.699073 -0.750391 0.0605089 -0.658219 -0.776118 -0.263525 -0.572883 0.795291 -0.605581 -0.028021 0.425812 -0.902463 0.065146 0.432783 -0.846512 -0.310026 0.377746 -0.854361 -0.356897 0.434315 -0.712318 -0.551339 0.446284 -0.740839 -0.501985 0.499349 -0.626652 -0.598296 0.244675 -0.513099 -0.822717 0.286027 -0.650304 -0.703771 0.0430498 -0.479914 -0.876259 0.040133 -0.557773 -0.829023 -0.224214 -0.225054 -0.948198 -0.231402 -0.472281 -0.850532 -0.453124 -0.0656862 -0.889024 -0.471029 -0.364731 -0.803183 -0.601648 -0.0135938 -0.798645 -0.64414 -0.201601 -0.737863 0.613269 -0.789255 -0.0312571 0.702273 -0.711276 -0.0300056 0.680809 -0.731571 -0.0360831 0.679214 -0.733536 -0.0243514 0.686414 -0.726282 -0.0367514 0.696769 -0.716331 -0.0371875 0.702952 -0.710559 -0.0310521 0.703914 -0.7092 -0.0392453 0.751824 -0.65798 -0.0427061 0.62168 -0.78084 -0.0616637 0.625216 -0.779828 -0.0312101 0.640807 -0.767033 -0.0320454 0.67179 -0.739948 -0.0342935 0.411371 -0.911468 -0.000418771 0.508558 -0.860526 -0.0293869 0.411617 -0.911357 0.000898402 0.411178 -0.911555 -0.000540376 0.410814 -0.911719 0.000665796 0.508001 -0.860893 -0.0282657 0.484173 -0.874848 0.0147433 0.581992 -0.812582 -0.0315635 0.837095 -0.534632 -0.115937 0.889838 -0.453044 -0.054214 0.898292 -0.435178 -0.0607619 0.897099 -0.436691 -0.0671868 0.897116 -0.43683 -0.0660478 0.899544 -0.433066 -0.0572171 0.827333 -0.543872 -0.140438 0.859471 -0.506598 -0.0683257 0.791342 -0.609617 -0.0463157 0.720993 -0.690916 -0.0529526 -0.418566 0 -0.908187 -0.54912 -0.000726996 -0.835743 -0.556223 -0.00182561 -0.831031 -0.795496 0.00217017 -0.605954 -0.786817 0 -0.617186 -0.368232 -0.228999 0.901091 -0.862481 -0.207565 0.461566 0.424688 -0.104598 0.899277 0.636833 -0.770686 0.0220481 0.54393 -0.67093 0.503977 0.485566 -0.847915 0.212758 0.782881 -0.522616 0.337594 0.726945 -0.590006 0.351346 0.799689 -0.346958 0.490019 0.57763 -0.13717 0.804691 0.574964 -0.139601 0.806181 0.578957 -0.367029 0.728079 0.569256 -0.376161 0.731061 0.576615 -0.356092 0.735333 0.373796 -0.548712 0.747791 0.433157 -0.392595 0.811322 0.3045 -0.523479 0.79577 -0.850338 -0.0646126 0.522256 -0.799254 -0.291941 0.525322 -0.71988 -0.389466 0.574534 -0.715813 -0.400014 0.572364 -0.594448 -0.597062 0.538655 -0.563072 0.00347629 0.826401 -0.391903 -0.135119 0.91003 -0.355743 -0.0995934 0.929262 -0.691938 -0.34507 0.634152 -0.650794 -0.00621218 0.759229 -0.543501 -0.399556 0.738215 -0.531782 -0.215392 0.819032 -0.412417 -0.47949 0.774598 -0.556159 -0.613275 0.560875 -0.334734 -0.774559 0.536667 0.114123 -0.0778763 0.99041 -0.0970254 -0.270528 0.95781 -0.0218241 0.370948 0.928397 -0.175186 -0.0339553 0.98395 -0.140114 -0.199585 0.969811 -0.238686 -0.294309 0.925425 -0.189582 -0.416501 0.889149 -0.298882 -0.520518 0.799832 -0.185262 -0.664111 0.724317 -0.312204 -0.779619 0.542884 -0.0654725 -0.904182 0.422101 -0.1105 -0.838721 0.533233 0.174434 -0.95007 0.258727 0.719259 -0.690292 0.0785046 0.686777 -0.714571 0.133137 0.692827 -0.708996 0.131584 0.643538 -0.748411 0.160436 0.653464 -0.739276 0.162652 0.614915 -0.772004 0.160899 0.597907 -0.786769 0.153303 0.358183 -0.642312 0.677599 0.588268 -0.574178 0.569438 0.490203 -0.672723 0.554206 0.655586 -0.566737 0.499015 0.57575 -0.662049 0.479795 0.665665 -0.589001 0.458222 0.699868 -0.353722 0.620536 0.724955 -0.329693 0.604766 0.735888 -0.0836112 0.671922 0.675664 -0.193874 0.71126 0.167731 -0.938801 0.300863 0.563652 -0.813044 0.145795 0.327239 -0.820564 0.468604 0.322897 -0.851445 0.413254 0.0978657 -0.75482 0.64859 0.100194 -0.814852 0.570944 -0.0833004 -0.674857 0.733232 0.0137783 -0.583525 0.811979 -0.0619775 -0.450319 0.890714 0.0240813 -0.367994 0.929516 -0.00796267 -0.262394 0.964928 0.170575 -0.0873907 0.981462 0.110017 -0.325983 0.938952 0.653429 -0.733108 0.188634 0.59503 -0.789039 0.15283 0.445461 -0.735819 0.510034 0.422404 -0.786606 0.450362 0.271274 -0.653197 0.706926 0.248399 -0.739891 0.625187 0.125983 -0.587189 0.799585 0.195523 -0.521016 0.830851 0.149534 -0.399722 0.904357 0.305261 -0.243669 0.920566 0.245604 -0.442831 0.862311 0.410218 -0.294669 0.863071 0.377326 -0.0718645 0.923288 0.353448 -0.171163 0.919662 0.228343 -0.050791 0.972255 0.73554 -0.650946 0.187751 0.711983 -0.69955 0.0609114 0.759958 -0.649544 -0.0235791 0.608972 -0.68064 -0.407286 0.637133 -0.100252 -0.764206 0.564507 -0.192829 -0.802589 0.766061 -0.107147 -0.633775 0.71352 -0.179882 -0.677149 0.859522 -0.115829 -0.4978 0.928318 -0.0991149 0.358333 0.935394 -0.150909 0.319787 0.982199 -0.138725 0.126652 0.984546 -0.170278 -0.0409105 0.989449 -0.121136 -0.0794836 0.938727 -0.149499 -0.310549 0.525901 -0.849501 -0.042155 0.551832 -0.83337 0.0312351 0.553446 -0.832183 0.0341857 0.524833 -0.848014 0.0736436 0.897902 -0.205131 -0.389478 0.848885 -0.390013 -0.356769 0.704461 -0.457046 -0.542995 0.704173 -0.457305 -0.54315 0.602084 -0.441231 -0.66544 0.875227 -0.388545 0.288115 0.871905 -0.421879 0.248596 0.9159 -0.399734 -0.0366163 0.918237 -0.394695 -0.0324966 0.849453 -0.428651 -0.307713 0.705555 -0.672021 -0.224898 0.662583 -0.705935 -0.250279 0.513606 -0.848635 -0.1266 0.513996 -0.848415 -0.126492 -0.53367 0.00388752 -0.845684 -0.69173 -0.00211334 -0.722153 -0.786562 0.0070196 -0.617472 -0.783621 0.00748867 -0.621195 -0.846314 0 -0.532685 0.0646419 0.0288229 -0.997492 -0.122361 0.00109564 -0.992485 -0.484864 -0.00158063 -0.874588 -0.360865 0.0272671 -0.932219 -0.447697 0.0158025 -0.894046 -0.0672066 0.00405707 -0.997731 0.321228 -0.00402395 -0.946993 0.300785 0 -0.953692 0.542845 -0.832645 -0.109646 0.564716 -0.798835 -0.207264 0.615128 -0.677343 -0.403515 0.615152 -0.63563 -0.466436 0.614628 -0.435114 -0.657957 0.621534 -0.460882 -0.633468 0.593204 -0.337319 -0.730975 0.541032 -0.147661 -0.827937 0.564556 -0.197407 -0.80144 0.509266 -0.0671827 -0.857983 0.493442 -0.758917 0.424924 0.825806 -0.563549 -0.0213897 0.757576 -0.64654 0.0898014 -0.291925 -0.754837 0.587367 0.0785489 -0.857683 0.508145 0.0157525 -0.865508 0.500647 0.32504 -0.86321 0.386287 0.276948 -0.854734 0.439011 0.588422 -0.76365 0.265702 0.604453 -0.756823 0.248709 0.697645 -0.701425 0.145924 -0.854426 -0.0878261 0.512096 -0.836789 -0.138499 0.529719 -0.72941 -0.30777 0.610933 -0.710647 -0.339614 0.616151 -0.528108 -0.52904 0.664243 -0.492405 -0.569305 0.658354 -0.0847561 -0.767959 0.634866 -0.237528 -0.621356 0.746657 -0.0961533 -0.729322 0.67738 0.137358 -0.772506 0.619974 0.14212 -0.775445 0.615213 0.297857 -0.795096 0.528303 0.711216 -0.702819 -0.0147193 0.644915 -0.762796 0.047199 0.520929 -0.845801 0.115121 0.468524 -0.869612 0.155757 0.263967 -0.930453 0.254125 0.173104 -0.9325 0.316984 -0.0441469 -0.928774 0.368008 -0.156616 -0.895259 0.417113 -0.351315 -0.819998 0.451865 -0.367681 -0.808909 0.458777 -0.610013 -0.6218 0.491172 -0.615041 -0.615284 0.493102 -0.797893 -0.385106 0.463746 -0.769018 -0.441931 0.461854 -0.890377 -0.127499 0.437004 -0.843454 -0.325413 0.427423 -0.908353 -0.102471 0.405455 -0.543995 0 -0.839088 -0.876663 0 0.481105 -0.942782 0.00197817 0.333403 -0.903915 0.0111365 0.427568 -0.940994 0.0044613 0.338395 -0.919604 0.000144264 -0.392848 -0.961475 -4.63323e-05 -0.274892 -0.99718 0.00336416 -0.0749736 -0.992505 0.00859447 -0.121902 -0.989848 -0.00279109 0.142105 -0.575995 0.0033154 -0.817446 -0.690793 3.51185e-05 -0.723052 -0.859244 -0.000176818 -0.511565 -0.751987 0.0236462 -0.658754 -0.833499 0.00977144 -0.552435 0.792423 -0.142112 0.593186 0.78846 -0.0963672 0.60749 0.805881 -0.391944 0.443774 0.816395 -0.331592 0.472807 0.748352 -0.613084 0.253176 0.782936 -0.545437 0.299184 0.62749 -0.777277 0.0457899 0.691916 -0.714102 0.106354 0.827538 -0.152548 0.540287 0.828997 -0.11926 0.546389 0.800593 -0.429554 0.417773 0.814659 -0.386392 0.432472 0.695917 -0.672123 0.252883 0.729098 -0.625409 0.277993 0.528133 -0.846396 0.0684831 0.583105 -0.805871 0.102769 0.481039 0 -0.876699 0.481039 0 -0.876699 0.481039 -7.5345e-06 -0.876699 0.481039 6.55106e-06 -0.876699 0.481039 1.20785e-05 -0.876699 0.481039 -3.93913e-05 -0.876699 0.481039 0 -0.876699 0.811832 0 0.583891 0.786009 0.0385078 0.617015 0.757959 0 0.652302 0.566718 0 -0.823912 0.718308 0.0326921 -0.694957 0.634345 -0.00461176 -0.773036 0.863386 0.00360048 -0.504531 0.890612 0.018198 -0.4544 0.948423 0.000692398 -0.317007 0.996737 -0.00164299 -0.0807002 0.999699 0.0158276 -0.0187488 0.991637 0.00208117 0.129041 0.923702 -0.00767383 0.383035 0.932076 0 0.362262 -0.928891 0 0.370353 -0.584736 -0.76049 0.282381 -0.770666 -0.519201 0.369466 -0.832054 -0.386543 0.397832 -0.888097 0 0.459657 -0.910122 -0.0179438 0.413951 -0.882176 -0.220513 0.4161 -0.870509 -0.267621 0.41303 0.674265 0 0.738489 0.599538 0.00644703 0.800321 0.103783 0.00134256 0.994599 0.221082 0.00770578 0.975225 0.238605 0.00988201 0.971066 0.41562 -0.00290818 0.909534 0.57027 0.00346576 0.82145 -0.138098 -0.00367616 0.990412 -0.210989 0.00694444 0.977464 -0.36948 0.000497235 0.929238 -0.617941 -0.00245546 0.786221 -0.563693 0.0103932 0.825919 -0.758661 -0.00105288 0.651485 -0.876293 0.0028505 0.481769 -0.887614 0 0.460587 -0.338438 -0.902703 -0.265682 -0.0872612 -0.983672 -0.1574 -0.0872608 -0.983672 -0.1574 -0.14046 -0.983927 -0.110264 -0.140461 -0.983927 -0.110265 -0.774712 -0.173068 -0.608169 -0.774715 -0.173053 -0.608169 -0.665568 -0.532942 -0.522486 -0.726643 -0.420358 -0.543406 -0.627756 -0.602549 -0.492805 0.291136 -0.422605 -0.85828 0.266013 -0.174546 -0.948035 0.208575 -0.582295 -0.785767 0.187003 -0.538161 -0.821835 -0.0256713 -0.984119 -0.175645 -0.0201114 -0.98725 -0.157901 -0.0417867 -0.871868 -0.487954 0.162658 -0.772579 -0.61373 0.105349 -0.780383 -0.616364 -0.411204 -0.529866 -0.741723 -0.411204 -0.529866 -0.741723 -0.477662 -0.171716 -0.861599 -0.477663 -0.171711 -0.861599 -0.066209 -0.171707 -0.982921 -0.0662094 -0.171704 -0.982921 -0.0569973 -0.52987 -0.846162 -0.056997 -0.529871 -0.846161 -0.0368593 -0.836188 -0.547202 -0.26592 -0.836188 -0.479662 -0.265919 -0.836189 -0.479661 -0.428959 -0.838211 -0.336744 -0.490696 -0.789643 -0.368349 -0.783437 -0.173479 -0.596768 -0.634288 -0.603522 -0.483157 -0.557299 -0.703306 -0.441338 -0.48844 -0.789302 -0.37206 -0.341567 -0.903126 -0.260182 -0.199484 -0.965477 -0.167512 -0.141704 -0.984006 -0.107941 -0.547791 -0.173471 -0.818433 -0.547073 -0.255986 -0.796983 -0.762072 -0.255988 -0.594741 -0.721985 -0.419861 -0.549958 -0.504828 -0.419844 -0.754241 -0.443502 -0.603527 -0.662617 -0.406467 -0.703306 -0.58322 -0.341524 -0.789303 -0.510256 -0.145805 -0.965032 -0.217842 -0.145806 -0.965031 -0.217843 -0.103031 -0.983872 -0.146221 -0.151262 -0.98829 -0.0200681 -0.178228 -0.983805 -0.0190188 -0.548099 -0.835437 -0.0404007 -0.567616 -0.816542 0.10522 -0.819555 -0.537896 0.197479 -0.770195 -0.599681 0.217216 -0.943945 -0.174291 0.280339 -0.849212 -0.434339 0.300314 -0.161127 -0.964188 -0.210664 -0.34342 -0.789129 -0.509252 -0.314508 -0.83777 -0.446347 -0.459984 -0.601881 -0.652805 -0.48119 -0.531555 -0.697069 -0.523168 -0.418361 -0.742475 -0.567337 -0.172757 -0.805161 -0.567339 -0.172751 -0.805161 -0.56096 -0.809319 0.174147 -0.554148 -0.831375 -0.0416634 -0.846319 -0.528862 -0.0636302 -0.846314 -0.52887 -0.0636311 -0.982452 -0.171264 -0.0738668 -0.982453 -0.171259 -0.0738664 -0.155034 -0.983588 -0.0923022 -0.155033 -0.983588 -0.0923019 -0.472114 -0.835524 -0.281082 -0.472117 -0.835523 -0.281083 -0.729243 -0.528869 -0.434168 -0.729246 -0.528866 -0.434169 -0.846549 -0.171262 -0.504007 -0.84655 -0.171261 -0.504007 -0.0591242 0 -0.998251 -0.0591242 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.7436 0 -0.668625 0.7436 0 -0.668625 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164487 0.986379 0 0.164487 0.817327 0 0.576175 0.817327 0 0.576175 0.486395 0 0.873739 0.486395 0 0.873739 -0.0591253 0 -0.998251 -0.0591253 0 -0.998251 0.379855 0 -0.925046 0.379855 0 -0.925046 0.743599 0 -0.668625 0.743599 0 -0.668625 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.16449 0.986379 0 0.16449 0.817329 0 0.576172 0.817329 0 0.576172 0.486393 0 0.87374 0.486393 0 0.87374 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217574 0.999763 0 -0.0217574 0.8767 0 0.481038 0.8767 0 0.481038 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591235 0 -0.998251 -0.0591235 0 -0.998251 0.379854 0 -0.925047 0.379854 0 -0.925047 0.743601 0 -0.668624 0.743601 0 -0.668624 0.960066 0 -0.279775 0.960066 0 -0.279775 0.986379 0 0.164489 0.986379 0 0.164489 0.817327 0 0.576174 0.817327 0 0.576174 0.486395 0 0.873739 0.486395 0 0.873739 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.8767 0 0.481038 0.8767 0 0.481038 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591249 0 -0.998251 -0.0591249 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.7436 0 -0.668624 0.7436 0 -0.668624 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164487 0.986379 0 0.164487 0.817327 0 0.576174 0.817327 0 0.576174 0.486395 0 0.873739 0.486395 0 0.873739 -0.0217585 0 -0.999763 -0.0217585 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.8767 0 0.481038 0.8767 0 0.481038 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379854 0 -0.925047 0.379854 0 -0.925047 0.743601 0 -0.668624 0.743601 0 -0.668624 0.960066 0 -0.279775 0.960066 0 -0.279775 0.986379 0 0.164489 0.986379 0 0.164489 0.817328 0 0.576173 0.817328 0 0.576173 0.486395 0 0.873739 0.486395 0 0.873739 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.8767 0 0.481038 0.8767 0 0.481038 0.518724 0 0.854942 0.518724 0 0.854942 -0.0217585 0 -0.999763 -0.0217585 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217585 0.999763 0 -0.0217585 0.876699 0 0.481039 0.876699 0 0.481039 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591242 0 -0.998251 -0.0591242 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.7436 0 -0.668624 0.7436 0 -0.668624 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164487 0.986379 0 0.164487 0.817327 0 0.576174 0.817327 0 0.576174 0.486395 0 0.873739 0.486395 0 0.873739 -0.0217575 0 -0.999763 -0.0217575 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217575 0.999763 0 -0.0217575 0.876699 0 0.481039 0.876699 0 0.481039 0.518724 0 0.854942 0.518724 0 0.854942 0.256248 -0.70711 0.659039 0.256245 -0.707105 0.659045 0.256244 -0.707107 0.659044 0.256241 -0.707106 0.659046 0.256244 -0.707112 0.659038 0.256242 -0.70711 0.659041 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0217585 0 0.999763 0.0217585 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.379854 0 0.925047 -0.379854 0 0.925047 -0.743601 0 0.668624 -0.743601 0 0.668624 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817328 0 -0.576173 -0.817328 0 -0.576173 -0.486395 0 -0.873739 -0.486395 0 -0.873739 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0591252 0 0.998251 0.0591252 0 0.998251 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.7436 0 0.668624 -0.7436 0 0.668624 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164488 -0.986379 0 -0.164488 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486395 0 -0.873739 -0.486395 0 -0.873739 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.85494 0 0.518726 -0.85494 0 0.518726 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.0591253 0 0.998251 0.0591253 0 0.998251 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.7436 0 0.668624 -0.7436 0 0.668624 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.817329 0 -0.576172 -0.817329 0 -0.576172 -0.486393 0 -0.87374 -0.486393 0 -0.87374 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.379854 0 0.925047 -0.379854 0 0.925047 -0.743601 0 0.668624 -0.743601 0 0.668624 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486395 0 -0.873739 -0.486395 0 -0.873739 0.0591253 0 0.998251 0.0591253 0 0.998251 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.7436 0 0.668624 -0.7436 0 0.668624 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164488 -0.986379 0 -0.164488 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0217577 0 0.999763 0.0217577 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.0217575 -0.999763 0 0.0217575 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.137909 0.707111 0.693523 0.137909 0.707111 0.693524 0.13791 0.707102 0.693532 0.137909 0.707108 0.693527 0.137834 0.707497 0.693145 0.629322 0.516332 0.580822 0.62933 0.516323 0.580823 0.73486 0 0.678219 0.73486 0 0.678219 0.706798 0.707051 -0.0226971 0.706686 0.707153 -0.0230261 0.706734 0.70709 -0.0234756 0.465699 0.474694 0.746853 0.728453 0.309804 0.611046 0.628885 0.326618 0.705567 0.755746 0.0987452 0.647377 0.729675 0.118586 0.673433 0.270644 0.655544 0.704992 0.25623 0.671384 0.695406 0.371716 0.592791 0.714441 0.462581 0.551135 0.694456 0.631022 0.52729 0.569014 0.146355 0.660977 0.735996 0.146355 0.660977 0.735996 -0.717264 0.653017 0.243106 -0.717266 0.653015 0.243107 -0.560143 0.653015 0.509717 -0.560143 0.653017 0.509715 -0.309494 0.653016 0.691219 -0.309493 0.653016 0.691219 -0.00716851 0.653016 0.75731 -0.00716852 0.653016 0.75731 -0.736164 0.659747 0.150986 -0.736165 0.659745 0.150986 -0.702031 0.659745 0.268121 -0.702031 0.659746 0.268121 -0.412876 0.653017 -0.634904 -0.412876 0.653017 -0.634904 -0.632368 0.653016 -0.41675 -0.632368 0.653017 -0.41675 -0.746274 0.653017 -0.129012 -0.746275 0.653016 -0.129011 -0.735577 0.653016 0.180269 -0.735577 0.653016 0.180268 -0.271935 0.660977 -0.6994 -0.271937 0.660975 -0.699402 -0.150734 0.655567 -0.73994 -0.141226 0.633917 -0.760398 0.0407337 0.527928 -0.848311 0.0413386 0.548106 -0.835387 0.253673 0.11885 -0.959961 0.352146 0.0636375 -0.933779 0.209407 0.197651 -0.957644 0.204969 0.356024 -0.911721 0.174791 0.365679 -0.914181 0.108563 0.438214 -0.892291 0.255484 0 -0.966813 0.255484 0 -0.966813 0.608776 0.793309 0.00729368 0.679883 0.733303 0.00512048 0.692985 0.720947 0.00283496 0.801464 0.597013 -0.0350781 0.57791 0.74234 -0.339044 0.554035 0.765445 -0.327323 0.446019 0.854562 -0.266065 0.613179 0.706265 -0.353839 0.638255 0.70709 -0.304392 0.715128 0.641958 -0.276552 0.662844 0.706083 -0.249167 0.683773 0.706993 -0.180598 0.818845 0.549974 -0.164381 0.69721 0.706465 -0.121677 0.705606 0.706804 -0.0504922 0.218794 0.516328 -0.82797 0.218795 0.516327 -0.82797 -0.256243 0.707111 -0.65904 -0.256242 0.707113 -0.659038 -0.256245 0.707108 -0.659043 0.608729 0.70708 -0.359842 0.608412 0.707151 -0.36024 0.608334 0.707054 -0.360563 -0.137909 0.707111 -0.693523 -0.137909 0.70711 -0.693524 -0.137909 0.707115 -0.69352 -0.629333 0.516325 -0.580817 -0.629323 0.516337 -0.580817 -0.73486 0 -0.678219 -0.73486 0 -0.678219 -0.706788 0.707061 0.0226967 -0.706692 0.707149 0.022979 -0.706745 0.707079 0.0234759 -0.465699 0.474694 -0.746853 -0.728453 0.309804 -0.611046 -0.62888 0.326619 -0.705571 -0.755741 0.0987443 -0.647383 -0.729675 0.118582 -0.673434 -0.270645 0.655542 -0.704993 -0.256227 0.671388 -0.695404 -0.371724 0.592788 -0.71444 -0.462581 0.551135 -0.694456 -0.631022 0.52729 -0.569014 -0.146355 0.660976 -0.735997 -0.146355 0.660976 -0.735997 0.717266 0.653015 -0.243106 0.717266 0.653015 -0.243106 0.560143 0.653015 -0.509716 0.560143 0.653015 -0.509717 0.309493 0.653015 -0.69122 0.309493 0.653018 -0.691218 0.00716851 0.653016 -0.75731 0.00716853 0.653016 -0.75731 0.736166 0.659744 -0.150986 0.736165 0.659745 -0.150986 0.702031 0.659745 -0.268121 0.70203 0.659746 -0.268121 0.412877 0.653015 0.634905 0.412875 0.653018 0.634903 0.632366 0.653018 0.41675 0.63237 0.653015 0.41675 0.746276 0.653014 0.129011 0.746275 0.653016 0.129011 0.735577 0.653016 -0.180269 0.735577 0.653017 -0.180268 0.271937 0.660976 0.699401 0.271936 0.660977 0.6994 0.150734 0.655569 0.739938 0.141223 0.633916 0.760399 -0.0407336 0.527929 0.848311 -0.0413385 0.548106 0.835387 -0.253673 0.11885 0.959961 -0.352146 0.0636375 0.933779 -0.209407 0.197651 0.957644 -0.204969 0.356023 0.911721 -0.174792 0.365678 0.914181 -0.108562 0.438215 0.89229 -0.255484 0 0.966813 -0.255484 0 0.966813 -0.576963 0.745832 0.33294 -0.548936 0.774286 0.314883 -0.787128 0.368414 0.494672 -0.509673 0.793201 0.333265 -0.665775 0.745583 0.029139 -0.70743 0.706193 0.0288909 -0.64363 0.765033 0.0215706 -0.518892 0.854705 0.015183 -0.622269 0.706805 0.336465 -0.653428 0.706466 0.271915 -0.778963 0.549975 0.301238 -0.673748 0.706993 0.214999 -0.694542 0.705813 0.139428 -0.757899 0.632547 0.159603 -0.701857 0.707091 0.0861302 -0.218794 0.516328 0.82797 -0.218794 0.516329 0.82797 0.256243 0.707111 0.65904 0.256243 0.707112 0.659039 0.256192 0.707253 0.658908 0.256216 0.707186 0.658969 0.256248 0.7071 0.65905 -0.608725 0.707085 0.35984 -0.608415 0.707154 0.360229 -0.608334 0.707054 0.360563 0.622229 2.85625e-05 -0.782835 0.622211 0 -0.78285 0.622225 -3.91209e-07 -0.782838 0.622226 -4.72947e-07 -0.782838 0.622231 0 -0.782834 0.351823 -0.505444 -0.787875 0.351429 -0.505531 -0.787995 0.351666 -0.50572 -0.787768 0.351168 -0.505736 -0.78798 0.25534 -0.605403 -0.753849 0.551987 -0.395296 -0.734202 0.480611 -0.423029 -0.768153 0.631466 -0.136597 -0.763277 0.614905 -0.152948 -0.773627 -0.0021491 -0.700431 -0.713717 -0.0636043 -0.771994 -0.632439 0.0555835 -0.704939 -0.707086 0.167158 -0.661212 -0.731339 0.392878 -0.608651 -0.689341 -0.13791 -0.707105 -0.693529 -0.137909 -0.707111 -0.693523 -0.137906 -0.707109 -0.693527 -0.137908 -0.707109 -0.693526 -0.137912 -0.707105 -0.693529 -0.13791 -0.707106 -0.693529 -0.13791 -0.707108 -0.693527 -0.13791 -0.707108 -0.693527 0.0349889 -0.696303 -0.716895 -0.0185178 -0.807761 -0.589219 0.118693 -0.704295 -0.699915 0.316276 -0.702169 -0.637909 0.405633 -0.612556 -0.678408 0.459122 -0.706014 -0.539214 0.0139936 -0.698758 -0.715221 0.0139936 -0.698758 -0.715221 0.311977 -0.698758 -0.643745 0.311977 -0.698759 -0.643744 0.552713 -0.698758 -0.454143 0.552713 -0.698758 -0.454143 0.692026 -0.698758 -0.181209 0.692027 -0.698757 -0.181211 0.958199 -0.235451 -0.162534 0.948148 -0.289912 -0.130256 0.941362 -0.291659 -0.169625 0.922013 -0.335236 -0.193673 0.925082 -0.330091 -0.187786 0.848739 -0.453602 -0.271822 0.838516 -0.511361 -0.18815 0.683763 -0.554562 -0.474267 0.689922 -0.674049 -0.263943 0.895554 -0.235455 -0.37755 0.900593 0.265755 -0.343956 0.92322 -0.23557 -0.303598 0.941786 -0.23557 -0.239887 0.94438 0.265762 -0.19369 0.95818 -0.23545 -0.162649 0.844873 -0.469763 -0.255952 0.798904 -0.599581 -0.0474889 0.751355 -0.644385 -0.142246 0.696004 -0.706824 0.12641 0.833934 -0.466409 -0.294986 0.832525 -0.466835 -0.298272 0.904 -0.240073 -0.353765 0.881287 -0.26339 -0.392375 0.880513 -0.235693 -0.411273 0.333991 -0.704583 0.62611 0.36551 -0.774381 0.516465 0.476108 -0.704295 0.526583 0.641605 -0.696304 0.321719 0.713632 -0.552184 0.431072 0.676916 -0.706013 0.208158 0.719569 -0.505902 0.475693 0.719711 -0.505476 0.475931 0.719767 -0.505615 0.475698 0.719931 -0.505281 0.475805 0.945361 0 0.326025 0.945361 1.53351e-07 0.326026 0.945361 1.19375e-07 0.326026 0.945358 4.81751e-07 0.326034 0.945366 0 0.326012 0.381317 -0.700463 0.603282 0.32603 -0.743661 0.583671 0.619605 -0.603918 0.501371 0.556853 -0.696854 0.452006 0.808587 -0.4097 0.422295 0.768129 -0.550432 0.327114 0.934189 -0.153287 0.322172 0.96517 -0.0848261 0.24749 0.883174 -0.284083 0.37323 0.256244 -0.707108 0.659042 0.256244 -0.707108 0.659042 0.681038 -0.698759 -0.218915 0.681038 -0.698757 -0.21892 0.710155 -0.698757 0.0861316 0.710155 -0.698757 0.0861319 0.608961 -0.698757 0.375372 0.608961 -0.698758 0.375373 0.396022 -0.698758 0.595738 0.396017 -0.69876 0.595739 0.13791 -0.707106 0.693529 0.137909 -0.707111 0.693523 0.137906 -0.70711 0.693526 0.137909 -0.70711 0.693525 0.137914 -0.707105 0.693529 0.13791 -0.707106 0.693529 -0.034989 -0.696302 0.716895 0.0185178 -0.807761 0.589219 -0.118693 -0.704295 0.699915 -0.316276 -0.70217 0.637908 -0.405633 -0.612556 0.678407 -0.459122 -0.706013 0.539216 -0.35183 -0.505439 0.787875 -0.351432 -0.505527 0.787997 -0.35167 -0.505718 0.787767 -0.35117 -0.505734 0.78798 -0.958197 -0.23546 0.162532 -0.948146 -0.289919 0.130255 -0.94136 -0.291666 0.169624 -0.922011 -0.335241 0.193671 -0.925073 -0.330108 0.187797 -0.848739 -0.453602 0.271822 -0.838516 -0.511363 0.188147 -0.683764 -0.554564 0.474264 -0.689922 -0.674048 0.263946 -0.622224 -7.95977e-06 0.78284 -0.622212 0 0.782849 -0.622225 -3.09228e-07 0.782839 -0.622223 -7.54085e-08 0.78284 -0.622224 0 0.782839 -0.895554 -0.235454 0.377551 -0.900592 0.265759 0.343956 -0.92322 -0.23557 0.303598 -0.941786 -0.23557 0.239886 -0.944383 0.265753 0.193691 -0.958178 -0.235459 0.162648 -0.326469 -0.572592 0.752035 -0.6149 -0.152965 0.773628 -0.625651 -0.138829 0.767651 -0.499245 -0.433183 0.750404 -0.491676 -0.464915 0.73628 -0.534969 -0.340183 0.773359 -0.235355 -0.686932 0.687555 -0.277173 -0.629799 0.725623 -0.0804952 -0.689008 0.72027 -0.00819039 -0.726259 0.687373 0.106291 -0.706742 0.699442 -0.844875 -0.46976 0.255952 -0.798906 -0.599579 0.0474882 -0.751355 -0.644384 0.142249 -0.696004 -0.706824 -0.12641 -0.83394 -0.466407 0.294971 -0.832525 -0.466835 0.298274 -0.903998 -0.24008 0.353765 -0.881288 -0.263394 0.392372 -0.880514 -0.235691 0.411273 0.13791 -0.707108 0.693527 0.13791 -0.707107 0.693528 -0.333991 -0.704584 -0.626109 -0.36551 -0.774381 -0.516465 -0.476108 -0.704295 -0.526583 -0.641605 -0.696304 -0.32172 -0.71363 -0.552186 -0.431071 -0.676915 -0.706013 -0.208161 -0.0139933 -0.698758 0.715221 -0.0139936 -0.698758 0.715221 -0.311974 -0.698758 0.643746 -0.311973 -0.698758 0.643747 -0.552713 -0.698758 0.454143 -0.552713 -0.698758 0.454143 -0.692026 -0.698758 0.181209 -0.692027 -0.698757 0.181211 -0.256257 -0.707108 -0.659037 -0.256245 -0.707106 -0.659044 -0.256244 -0.707108 -0.659043 -0.256242 -0.707107 -0.659045 -0.256243 -0.70711 -0.659042 -0.256243 -0.707109 -0.659042 -0.719908 -0.505168 -0.47596 -0.719612 -0.505737 -0.475803 -0.719575 -0.505897 -0.475688 -0.965688 0 -0.259706 -0.965688 0 -0.259706 -0.965689 1.14195e-05 -0.259701 -0.822834 -0.431648 -0.369626 -0.525465 -0.759476 -0.383514 -0.624165 -0.638803 -0.449832 -0.294531 -0.801234 -0.520841 -0.368977 -0.754873 -0.542238 -0.952988 -0.161648 -0.25629 -0.973144 -0.105466 -0.204615 -0.922742 -0.264766 -0.280084 -0.867612 -0.396346 -0.300264 -0.752167 -0.608904 -0.251955 -0.234155 -0.76321 -0.602231 -0.234155 -0.76321 -0.602231 -0.639527 -0.765891 -0.0664542 -0.646951 -0.757595 -0.0866246 -0.562149 -0.755359 -0.33678 -0.562154 -0.755357 -0.336778 -0.365083 -0.755358 -0.544196 -0.365078 -0.75536 -0.544196 -0.285967 0.704066 -0.650011 -0.285966 0.704068 -0.650009 -0.444457 0.704068 -0.553847 -0.444458 0.704067 -0.553848 -0.572659 0.704067 -0.419942 -0.572659 0.704067 -0.419941 -0.661835 0.704067 -0.257417 -0.661835 0.704067 -0.257417 -0.705908 0.704067 -0.0773503 -0.705908 0.704067 -0.0773503 -0.701875 0.704067 0.107988 -0.701874 0.704067 0.107988 -0.650009 0.704067 0.285967 -0.65001 0.704066 0.285967 -0.553848 0.704067 0.444458 -0.553848 0.704067 0.444458 -0.419942 0.704067 0.572659 -0.419942 0.704067 0.572659 -0.257417 0.704067 0.661835 -0.257417 0.704067 0.661835 -0.0773503 0.704067 0.705908 -0.0773503 0.704067 0.705908 0.107988 0.704067 0.701875 0.107988 0.704066 0.701876 0.584143 0.706148 -0.400165 0.584146 0.706144 -0.400167 0.550405 0.707104 -0.443912 0.486938 0.747434 -0.451921 0.516818 0.706255 -0.483842 0.476935 0.707094 -0.522064 0.43904 0.740728 -0.508494 0.539619 0.488027 -0.686033 0.421566 0.706861 -0.568005 0.392495 0.707074 -0.588213 0.367477 0.735248 -0.569536 0.402685 0.575135 -0.712084 0.344504 0.696454 -0.629499 0.311014 0.707106 -0.635036 0.299018 0.707053 -0.640831 0.2144 0.816209 -0.536502 0.251167 0.706544 -0.661597 0.198658 0.707024 -0.678714 0.159162 0.780716 -0.604277 0.170536 0.580476 -0.79622 0.129249 0.707002 -0.695301 0.0937183 0.706991 -0.700985 0.0466646 0.836182 -0.546464 0.0418299 0.706701 -0.706275 -0.0133869 0.706941 -0.707146 -0.0336579 0.841342 -0.539455 -0.171246 0.706837 -0.686336 -0.111759 0.843838 -0.524831 -0.1202 0.706895 -0.69703 -0.0654709 0.706775 -0.704402 -0.692024 0.698761 0.181208 -0.692027 0.698758 0.181206 -0.552713 0.698758 0.454143 -0.552713 0.698758 0.454143 -0.311975 0.698758 0.643746 -0.311976 0.698757 0.643747 -0.0139933 0.698758 0.715221 -0.0139937 0.698758 0.715221 0.396023 0.698757 0.595739 0.396023 0.698758 0.595737 0.608959 0.69876 0.375371 0.60896 0.698758 0.375373 0.710155 0.698757 0.0861316 0.710155 0.698757 0.0861317 0.68104 0.698757 -0.218915 0.681032 0.698763 -0.218919 0.13791 0.707107 0.693527 0.13791 0.707108 0.693527 0.256244 0.707107 0.659044 0.256246 0.707104 0.659046 0.16811 0.706771 0.687178 0.266741 0.76118 0.591146 0.321365 0.701067 0.636577 0.551625 0.697813 0.45691 0.551624 0.697815 0.456908 0.696323 0.697816 0.16789 0.696326 0.697813 0.167892 0.227363 0.706767 0.669915 0.0925817 0.761178 0.641901 0.0709155 0.701068 0.709559 -0.219816 0.697813 0.681717 -0.219817 0.697813 0.681717 -0.497125 0.697814 0.515677 -0.497127 0.697812 0.515678 0.705247 0.705822 0.0666525 0.705248 0.705821 0.0666525 0.688033 0.706538 0.165573 0.514128 0.84632 0.139337 0.671037 0.706967 0.223397 0.642388 0.705824 0.298579 0.64239 0.705823 0.298579 0.597178 0.706741 0.379336 0.424556 0.856371 0.293907 0.562654 0.70683 0.428733 0.505619 0.705821 0.496152 0.505619 0.70582 0.496152 0.435966 0.706737 0.557186 0.301903 0.856345 0.41896 0.386908 0.706833 0.592191 0.310667 0.705822 0.636633 0.310667 0.705822 0.636633 0.226669 0.706788 0.670129 0.144254 0.856823 0.49502 0.168812 0.706783 0.686994 0.0799692 0.705818 0.703865 0.0799688 0.70582 0.703863 -0.0405688 0.70582 0.707229 -0.0405689 0.705822 0.707226 -0.152556 0.706122 0.691461 -0.138607 0.789354 0.598087 -0.210564 0.70709 0.675045 -0.274658 0.705824 0.652974 -0.27466 0.705819 0.652979 -0.368075 0.706392 0.604592 -0.298418 0.832368 0.467022 -0.417824 0.707026 0.570559 -0.477145 0.705823 0.523591 -0.477145 0.705822 0.523591 -0.548757 0.706407 0.447051 -0.435717 0.833762 0.339104 -0.58431 0.707019 0.398379 -0.600332 0.706944 0.373939 -0.767389 0.359964 0.530603 -0.569526 0.706704 0.419774 -0.512764 0.706029 0.488463 -0.297878 0.713411 0.634282 -0.348684 0.68916 0.6352 -0.401994 0.577128 0.710861 -0.375795 0.707068 0.599026 -0.39249 0.707079 0.58821 -0.37415 0.769184 0.518043 -0.539596 0.488095 0.686002 -0.457555 0.706969 0.539294 -0.476933 0.707094 0.522066 -0.448617 0.788891 0.419993 -0.0151738 0.849793 0.526898 -0.299017 0.707054 0.640831 -0.251168 0.706545 0.661596 -0.184199 0.834791 0.51884 -0.198657 0.707022 0.678716 -0.165281 0.706975 0.687655 -0.170539 0.580457 0.796233 -0.0970337 0.786564 0.609837 -0.0937186 0.706989 0.700987 -0.0418302 0.706706 0.70627 0.0133879 0.706945 0.707142 0.0654702 0.706775 0.704402 0.0662516 0.853249 0.517278 0.1202 0.706896 0.69703 0.171245 0.706839 0.686333 0.171246 0.706837 0.686336 0.224264 0.706837 0.670886 0.224264 0.706835 0.670887 0.273065 0.706892 0.652487 0.222005 0.853247 0.471893 0.323186 0.706775 0.629301 0.368588 0.706944 0.603633 0.295852 0.849791 0.436265 0.571599 0.706739 0.416886 0.414695 0.7067 0.573238 0.455623 0.706983 0.540908 0.366649 0.843776 0.391931 0.496681 0.706626 0.503972 0.537199 0.70692 0.460089 0.494675 0.753568 0.432934 0.628467 0.620728 0.468749 0.658505 0.73505 0.161469 0.862341 0.47982 0.16168 0.69818 0.706728 0.114373 0.597415 0.707039 0.378407 0.590304 0.714283 0.375954 0.635334 0.689154 0.34845 0.720942 0.577124 0.383627 0.638766 0.707066 0.303374 0.647038 0.707076 0.28528 0.557393 0.804902 0.203584 0.667997 0.706359 0.234174 0.682726 0.707095 0.184126 0.707316 0.706201 0.0313625 0.77985 0.62527 0.0295236 0.706714 0.707096 -0.0238759 0.69203 0.698754 -0.18121 0.692025 0.698759 -0.181213 0.552713 0.698758 -0.454143 0.552713 0.698758 -0.454143 0.311976 0.698759 -0.643745 0.311975 0.69876 -0.643744 0.0139936 0.698758 -0.715221 0.0139937 0.698758 -0.715221 -0.396024 0.698761 -0.595734 -0.396022 0.698754 -0.595743 -0.608961 0.698754 -0.375378 -0.608961 0.698756 -0.375376 -0.710155 0.698757 -0.0861316 -0.710155 0.698757 -0.0861312 -0.681038 0.698756 0.218921 -0.681038 0.698757 0.218921 -0.13791 0.707108 -0.693527 -0.13791 0.707108 -0.693527 -0.256243 0.707109 -0.659041 -0.256245 0.707106 -0.659044 -0.16811 0.706771 -0.687178 -0.168109 0.70677 -0.687179 0.50377 0.698979 -0.507586 0.503775 0.698975 -0.507588 0.248949 0.698976 -0.670415 0.248946 0.69898 -0.670412 -0.0503918 0.698979 -0.713365 -0.0503911 0.698977 -0.713367 -0.14325 0.705983 -0.693591 -0.143252 0.705975 -0.693598 -0.0310759 0.705975 -0.707555 -0.0310758 0.705975 -0.707555 0.0818908 0.705975 -0.703486 0.0818906 0.70598 -0.703481 0.17112 0.706694 -0.686514 0.147238 0.841057 -0.520523 0.225285 0.706932 -0.670443 0.298742 0.705976 -0.642146 0.298743 0.705973 -0.642148 0.37766 0.706701 -0.598286 0.302671 0.841781 -0.446984 0.424069 0.706924 -0.566061 0.485344 0.705976 -0.515789 0.485343 0.705979 -0.515787 0.550905 0.706528 -0.44421 0.445519 0.826986 -0.342938 0.584192 0.707019 -0.398552 0.341982 0 0.939707 0.321385 0.00153858 0.946947 0.300637 0 0.953739 -0.975448 0 -0.22023 -0.972073 -0.011828 -0.23438 -0.797167 0.0110283 -0.603658 -0.769938 -0.0220542 -0.637738 -0.23763 0 -0.971356 -0.305197 -0.00987401 -0.952238 -0.476172 0.0332955 -0.878722 -0.504266 0.0178851 -0.863363 -0.604842 0.0034633 -0.796338 0.627613 -0.00023168 0.778525 0.796929 0.0268101 0.603477 0.770056 -0.0134115 0.637836 0.97537 0.0126191 0.220213 0.972142 0 0.234393 0.527894 0.000740601 0.84931 0.450474 0.0288731 0.892323 0.365805 0 0.930692 -0.321386 0 -0.946948 -0.254129 -0.00987364 -0.96712 -0.0704249 0.0332964 -0.996961 -0.0384749 0.0178844 -0.999099 0.0821209 0.00349147 -0.996616 0.347985 -0.0268114 -0.937117 0.30686 0.0134114 -0.95166 0.704378 -0.0126189 -0.709713 0.694038 0 -0.719939 0.0195617 0 -0.999809 0.0195617 0 -0.999809 0.436113 0 -0.899892 0.436113 0 -0.899892 0.772638 0 -0.634847 0.772638 0 -0.634847 0.967385 0 -0.253312 0.967385 0 -0.253312 0.952025 0 -0.306022 0.952025 0 -0.306022 0.992725 0 0.120403 0.992725 0 0.120403 0.851267 0 0.524733 0.851267 0 0.524733 0.5536 0 0.832783 0.5536 0 0.832783 -0.0195613 0 0.999809 -0.0195613 0 0.999809 -0.43611 0 0.899894 -0.43611 0 0.899894 -0.772638 0 0.634847 -0.772638 0 0.634847 -0.967385 0 0.253312 -0.967385 0 0.253312 -0.91429 0 0.40506 -0.951953 0.0120611 0.306007 -0.98365 -0.00221254 0.180076 -0.992717 0.00402437 -0.120402 -0.991153 0.00162917 -0.132712 -0.851262 -0.00186957 -0.524738 -0.857835 0.000934709 -0.513924 -0.553604 -0.00091765 -0.83278 -0.557113 0 -0.830437 0.195034 0 0.980796 0.195034 5.48124e-07 0.980797 0.195037 -2.19784e-06 0.980796 0.195034 4.04398e-08 0.980797 0.195034 -7.76819e-07 0.980797 0.195034 0 0.980796 0.195035 2.62655e-07 0.980796 0.195034 5.04049e-07 0.980797 0.195037 0 0.980796 0.195037 0 0.980796 0.195033 5.93463e-07 0.980797 0.195035 -2.0325e-07 0.980796 0.195034 0 0.980796 0.195034 -1.40058e-07 0.980796 0.195034 4.94799e-07 0.980796 0.195035 -1.06121e-06 0.980796 0.195034 8.91397e-07 0.980797 -0.362382 -1.04754e-07 -0.93203 -0.362388 1.36903e-06 -0.932027 -0.362384 -7.11613e-07 -0.932029 -0.362387 0 -0.932028 -0.362387 0 -0.932028 -0.362381 -1.43541e-06 -0.93203 -0.362386 6.93359e-07 -0.932028 -0.362385 0 -0.932028 -0.362384 3.8841e-06 -0.932029 -0.362384 8.92793e-07 -0.932029 -0.362384 2.03932e-06 -0.932029 -0.362387 1.11579e-06 -0.932028 -0.362382 -8.70736e-06 -0.93203 -0.362385 1.43835e-06 -0.932028 -0.362385 3.11298e-06 -0.932029 -0.362384 0 -0.932029 -0.362384 0 -0.932029 -0.976908 0 0.213659 -0.951479 -0.0781178 0.297631 -0.897416 -0.200817 0.392832 -0.932702 0.173585 0.316125 -0.770004 -0.0833147 0.632576 -0.720125 -0.228052 0.655296 -0.648295 0 0.76139 -0.408657 0 0.912688 -0.436489 -0.185546 0.88037 -0.00923599 0.218797 0.975727 -0.0487483 0 0.998811 -0.545163 0 -0.83833 -0.56765 0.185546 -0.802089 -0.82536 -0.151368 -0.543938 -0.855958 0 -0.517045 -0.996274 -0.0163457 -0.084683 -0.957409 -0.236588 -0.165511 -0.964461 -0.176565 -0.196572 -0.955827 0 -0.29393 -0.987828 0.019281 0.154348 -0.967909 -0.0829811 0.237206 -0.929851 0 0.367936 0.362383 2.22603e-07 0.932029 0.362393 2.45221e-06 0.932025 0.362384 -6.71205e-07 0.932029 0.362388 0 0.932027 0.362388 0 0.932027 0.362388 -8.10881e-08 0.932027 0.362382 -1.83495e-06 0.93203 0.362385 0 0.932029 0.362384 1.2947e-06 0.932029 0.362385 3.0842e-06 0.932029 0.362384 6.88269e-07 0.932029 0.362386 1.91242e-06 0.932028 0.362383 -5.1632e-06 0.932029 0.362385 4.75006e-06 0.932028 0.362385 5.67803e-06 0.932029 0.362384 0 0.932029 0.362384 0 0.932029 -0.195034 0 -0.980796 -0.195034 6.50101e-07 -0.980797 -0.195033 1.71535e-06 -0.980797 -0.195035 -2.06244e-06 -0.980796 -0.195034 3.45253e-07 -0.980796 -0.195034 0 -0.980796 -0.195034 2.66764e-07 -0.980797 -0.195036 -2.79579e-07 -0.980796 -0.195034 0 -0.980797 -0.195034 0 -0.980797 -0.195034 -1.10759e-07 -0.980796 -0.195034 -7.24323e-08 -0.980796 -0.195034 0 -0.980796 -0.195034 -1.5346e-07 -0.980796 -0.195034 -4.94799e-08 -0.980796 -0.195034 3.8595e-07 -0.980796 -0.195034 -2.10185e-07 -0.980796 0.545164 0 0.83833 0.567651 0.185542 0.802089 0.825359 -0.151373 0.543938 0.855958 0 0.517045 0.996274 -0.0163457 0.084683 0.95741 -0.236585 0.16551 0.964462 -0.176558 0.196572 0.955828 0 0.293926 0.987829 0.0192807 -0.154346 0.967908 -0.0829836 -0.237207 0.92985 0 -0.36794 0.976908 0 -0.213659 0.951479 -0.0781178 -0.297631 0.897416 -0.200817 -0.392832 0.932702 0.173585 -0.316125 0.770003 -0.0833169 -0.632577 0.720125 -0.228047 -0.655297 0.648297 0 -0.761388 0.408656 0 -0.912689 0.436488 -0.185552 -0.880368 0.00923599 0.218797 -0.975727 0.0487482 0 -0.998811 -0.348272 -0.698075 -0.625618 -0.348274 -0.698068 -0.625626 -0.492289 -0.706853 -0.507948 -0.637877 -0.625226 -0.449673 -0.59796 -0.700858 -0.388898 -0.673295 -0.706111 -0.219273 -0.809414 -0.571515 -0.134979 -0.708167 -0.703118 -0.0642221 -0.698951 -0.704866 0.12096 -0.80072 -0.551725 0.233339 -0.654512 -0.704866 0.273455 -0.532441 -0.698069 0.478755 -0.696472 -0.475055 0.537819 -0.450098 -0.706114 0.546639 -0.271986 -0.69807 0.66236 0.0423341 -0.698073 0.714774 0.0423329 -0.698069 0.714778 -0.142357 -0.706855 0.692886 -0.330086 -0.604024 0.725395 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.201252 0 0.97954 -0.201252 0 0.97954 -0.414178 0 0.910196 -0.414178 0 0.910196 -0.635644 0 0.771983 -0.635644 0 0.771983 -0.791485 0 0.611188 -0.791485 0 0.611188 -0.922706 0 0.385505 -0.922706 0 0.385505 -0.985353 0 0.170525 -0.985353 0 0.170525 -0.995913 0 -0.0903171 -0.995913 0 -0.0903171 -0.950846 0 -0.309664 -0.950846 0 -0.309664 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.695951 0 -0.718089 -0.695951 0 -0.718089 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0.0423327 0.698073 0.714774 0.0423343 0.698069 0.714778 -0.142357 0.706855 0.692886 -0.296453 0.625232 0.721942 -0.295433 0.700859 0.649243 -0.450098 0.706114 0.546639 -0.610187 0.571524 0.548663 -0.562803 0.703119 0.434599 -0.654512 0.704866 0.273455 -0.80072 0.551725 0.233339 -0.698951 0.704866 0.12096 -0.70628 0.698067 -0.11778 -0.87637 0.475036 -0.0794761 -0.673295 0.706111 -0.219273 -0.58523 0.69807 -0.412559 -0.34827 0.698075 -0.625619 -0.348276 0.698068 -0.625624 -0.492289 0.706853 -0.507948 -0.668101 0.604017 -0.434516 -0.348278 -0.698066 -0.625625 -0.348278 -0.698062 -0.625629 -0.492292 -0.706848 -0.507951 -0.637883 -0.625218 -0.449675 -0.597968 -0.700849 -0.388903 -0.673302 -0.706103 -0.219278 -0.809421 -0.571505 -0.134982 -0.708161 -0.703125 -0.0642173 -0.698946 -0.704873 0.120951 -0.800723 -0.551721 0.233338 -0.654497 -0.704879 0.273458 -0.532431 -0.698079 0.478751 -0.696481 -0.475039 0.537821 -0.450107 -0.706106 0.546643 -0.271989 -0.698065 0.662365 0.0423345 -0.698066 0.71478 0.042335 -0.698068 0.714778 -0.142354 -0.706856 0.692885 -0.330085 -0.604025 0.725395 -0.486397 0 -0.873738 -0.486397 0 -0.873738 -0.695951 0 -0.718089 -0.695951 0 -0.718089 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.950845 0 -0.309667 -0.950845 0 -0.309667 -0.995914 0 -0.0903113 -0.995914 0 -0.0903113 -0.985355 0 0.170513 -0.985355 0 0.170513 -0.922701 0 0.385517 -0.922701 0 0.385517 -0.791488 0 0.611185 -0.791488 0 0.611185 -0.635649 0 0.771979 -0.635649 0 0.771979 -0.414177 0 0.910197 -0.414177 0 0.910197 -0.201248 0 0.97954 -0.201248 0 0.97954 0.0591236 0 0.998251 0.0591236 0 0.998251 0.0423351 0.698067 0.71478 0.0423343 0.698069 0.714778 -0.142354 0.706856 0.692885 -0.296454 0.625231 0.721943 -0.295435 0.700853 0.649248 -0.450107 0.706106 0.546643 -0.610186 0.571522 0.548667 -0.562796 0.70313 0.43459 -0.654497 0.704879 0.273458 -0.800723 0.551721 0.233338 -0.698946 0.704873 0.120951 -0.706273 0.698073 -0.117781 -0.876383 0.475013 -0.079472 -0.673302 0.706103 -0.219278 -0.585238 0.698061 -0.412563 -0.348276 0.698066 -0.625626 -0.348279 0.698062 -0.625629 -0.492292 0.706848 -0.507951 -0.668106 0.604009 -0.434519 0.0423345 -0.698066 0.71478 0.042335 -0.698068 0.714778 -0.271985 -0.698072 0.66236 -0.271989 -0.698065 0.662365 -0.532447 -0.698062 0.478758 -0.532435 -0.698075 0.478753 -0.687429 -0.698077 0.200324 -0.687431 -0.698075 0.200324 -0.706274 -0.698073 -0.117777 -0.706285 -0.698061 -0.117783 -0.585238 -0.698061 -0.412564 -0.585234 -0.698066 -0.412559 -0.348275 -0.698068 -0.625624 -0.348276 -0.698066 -0.625626 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.379852 0 0.925047 -0.379852 0 0.925047 -0.743603 0 0.668622 -0.743603 0 0.668622 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164487 -0.986379 0 -0.164487 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.486397 0 -0.873738 -0.486397 0 -0.873738 -0.348276 0.698066 -0.625626 -0.348275 0.698068 -0.625625 -0.585233 0.698066 -0.41256 -0.585238 0.698061 -0.412562 -0.706286 0.69806 -0.117779 -0.706274 0.698072 -0.117781 -0.687431 0.698075 0.200325 -0.687429 0.698077 0.200324 -0.532438 0.698075 0.47875 -0.532444 0.698063 0.478761 -0.271987 0.698065 0.662366 -0.271987 0.698072 0.662359 0.0423343 0.698069 0.714778 0.0423351 0.698067 0.71478 -0.348276 -0.698066 -0.625625 -0.348276 -0.698066 -0.625626 -0.492291 -0.706851 -0.507947 -0.63788 -0.625223 -0.449673 -0.597967 -0.70085 -0.388902 -0.673301 -0.706104 -0.219278 -0.809421 -0.571505 -0.134982 -0.708161 -0.703125 -0.0642175 -0.698946 -0.704873 0.120951 -0.800723 -0.551721 0.233338 -0.6545 -0.704877 0.273458 -0.532434 -0.698075 0.478754 -0.696483 -0.475034 0.537823 -0.450104 -0.706106 0.546645 -0.27199 -0.698065 0.662364 0.0423352 -0.698068 0.714779 0.0423351 -0.698068 0.714779 -0.142356 -0.706855 0.692886 -0.330086 -0.604024 0.725395 0.0591248 0 0.998251 0.0217504 -0.0259923 0.999425 -0.201251 0 0.97954 -0.414178 0 0.910196 -0.480587 -0.043376 0.875874 -0.635645 0 0.771982 -0.791488 0 0.611185 -0.85378 -0.0520758 0.518023 -0.922701 0 0.385516 -0.985355 0 0.170513 -0.998407 -0.0520747 0.0217276 -0.995914 0 -0.0903114 -0.950845 0 -0.309668 -0.875874 -0.0433747 -0.480587 -0.486396 0 -0.873738 -0.51855 -0.0259913 -0.854652 -0.695954 0 -0.718086 -0.8383 0 -0.545209 -0.373099 0.694739 -0.614926 -0.373097 0.694742 -0.614924 -0.630572 0.694744 -0.345991 -0.630574 0.694742 -0.345992 -0.719089 0.694742 0.015649 -0.719098 0.694733 0.0156518 -0.614931 0.694733 0.373103 -0.614924 0.694743 0.373096 -0.345992 0.694742 0.630573 -0.345992 0.694741 0.630574 0.0156495 0.69474 0.719091 0.0156492 0.694741 0.71909 -0.452143 -0.702359 -0.54978 -0.421192 -0.686268 -0.592987 -0.420863 -0.686899 -0.592491 -0.345823 -0.810673 -0.472458 -0.451733 -0.702923 -0.549396 -0.61236 -0.695257 -0.37634 -0.585431 -0.693768 -0.419471 -0.584963 -0.694387 -0.4191 -0.434272 -0.852916 -0.289726 -0.61184 -0.695868 -0.376058 -0.643464 -0.696975 -0.316513 -0.642975 -0.697553 -0.316233 -0.482286 -0.849803 -0.212685 -0.668072 -0.692642 -0.271895 -0.668623 -0.692032 -0.272093 -0.727953 -0.684454 -0.0400816 -0.730686 -0.681068 -0.0473711 -0.61287 -0.789323 -0.0368866 -0.704096 -0.704525 -0.0888394 -0.704614 -0.703986 -0.0890123 -0.792511 0 0.609858 -0.792521 -1.68368e-05 0.609845 -0.792518 0 0.609848 -0.792516 -5.46267e-07 0.609851 -0.792514 -1.67268e-06 0.609854 -0.792527 2.36734e-06 0.609837 -0.0457464 -0.70711 0.705622 -0.0457461 -0.707106 0.705626 -0.0457467 -0.707104 0.705628 -0.0457468 -0.707102 0.70563 -0.14082 -0.694745 -0.705336 -0.0999027 -0.403597 -0.909467 -0.256991 -0.705745 -0.660212 -0.403701 -0.703359 -0.585074 -0.566949 -0.511688 -0.645558 -0.540368 -0.704693 -0.459794 -0.631836 -0.704717 -0.322734 -0.813638 -0.511924 -0.275549 -0.695182 -0.703329 -0.148494 -0.708273 -0.705761 0.0158194 -0.828471 -0.53505 0.165402 -0.230714 -0.694746 0.681248 -0.230714 -0.694746 0.681249 -0.508568 -0.699678 0.501807 -0.61333 -0.577655 0.538647 -0.615239 -0.706514 0.349741 -0.683937 -0.701666 0.199736 0.045753 -0.707102 -0.70563 0.0457468 -0.707103 -0.705629 0.0457477 -0.70711 -0.705622 0.0457466 -0.707106 -0.705626 -0.707132 0 -0.707082 -0.707144 1.47285e-06 -0.70707 -0.707133 -1.32834e-06 -0.70708 -0.707142 -5.54782e-07 -0.707071 -0.70714 -9.26222e-07 -0.707073 -0.707155 0 -0.707059 -0.258878 0 -0.96591 -0.258853 -2.26643e-06 -0.965917 -0.258957 1.82884e-05 -0.965889 -0.258873 2.67761e-06 -0.965911 -0.258864 0 -0.965914 -0.0246485 -0.501821 -0.864621 -0.0245802 -0.50162 -0.864739 0.392466 -0.707114 -0.588183 0.39243 -0.707106 -0.588217 0.39243 -0.707106 -0.588217 0.254877 -0.698073 -0.669128 0.254877 -0.698072 -0.669128 -0.0606882 -0.698073 -0.71345 -0.519959 -0.698073 0.492277 -0.51996 -0.698072 0.492278 -0.682061 -0.69807 0.217924 -0.682057 -0.698074 0.217925 -0.709066 -0.698074 -0.0995908 -0.709066 -0.698074 -0.0995907 -0.595636 -0.698074 -0.39738 -0.595636 -0.698073 -0.39738 -0.364232 -0.698074 -0.616464 -0.364232 -0.698075 -0.616463 -0.206563 -0.707079 -0.676292 -0.0532365 -0.672669 -0.738026 -0.392431 -0.707106 0.588217 -0.392428 -0.707109 0.588215 -0.392484 -0.707099 0.58819 -0.807795 -0.501741 0.309393 -0.807891 -0.501741 0.309141 -0.991265 0 0.131885 -0.991266 1.27188e-06 0.13188 -0.991281 2.26316e-05 0.131763 -0.991264 -2.37739e-06 0.131892 -0.991268 0 0.131866 -0.97626 0 -0.216601 -0.97626 4.15038e-07 -0.216603 -0.976272 -9.38292e-06 -0.21655 -0.976262 -7.90209e-07 -0.216593 -0.97626 0 -0.216602 -0.864873 -0.501822 0.0129861 -0.864989 -0.501621 0.0130597 -0.570585 -0.707109 0.417648 -0.570588 -0.707106 0.417649 -0.570625 -0.707097 0.417613 0.45066 -0.694747 -0.560564 0.450662 -0.694745 -0.560565 0.189362 -0.703329 -0.685179 0.131378 -0.511923 -0.848926 0.00556312 -0.704714 -0.70947 -0.137908 -0.705745 -0.694914 -0.305698 -0.534389 -0.788021 -0.314839 -0.701696 -0.63914 -0.454722 -0.70634 -0.542505 -0.643164 -0.564786 -0.517066 -0.670564 -0.694748 0.260133 -0.670566 -0.694746 0.260133 -0.71122 -0.69859 -0.0783464 -0.787746 -0.603816 -0.12191 -0.659184 -0.706767 -0.256821 -0.584584 -0.700234 -0.409798 0.570572 -0.707103 -0.417675 0.570586 -0.707108 -0.417648 0.570586 -0.707107 -0.417649 0.273953 -0.501738 -0.820493 0.273708 -0.501738 -0.820575 0.0886495 0 -0.996063 0.0886355 1.25764e-06 -0.996064 0.0887558 -2.19268e-05 -0.996053 0.0886249 1.73041e-06 -0.996065 0.0886308 0 -0.996065 -0.172992 -0.501737 -0.847546 -0.173247 -0.501738 -0.847493 0.285305 -0.707105 -0.646995 0.285318 -0.707108 -0.646987 0.285318 -0.707105 -0.64699 -0.421276 0 -0.906932 -0.42127 -5.85103e-07 -0.906935 -0.421312 8.2073e-06 -0.906916 -0.421269 -3.61476e-07 -0.906936 -0.42127 0 -0.906935 0.135889 -0.698073 -0.703014 0.135889 -0.698074 -0.703013 -0.182594 -0.698074 -0.692353 -0.143266 -0.419764 -0.896255 -0.264843 -0.705357 -0.657517 -0.464913 -0.698074 -0.544563 -0.510839 -0.492238 -0.704801 -0.532814 -0.705986 -0.466576 -0.65515 -0.698072 -0.288918 -0.739399 -0.555638 -0.380205 -0.685638 -0.706476 -0.175478 -0.715627 -0.698071 0.0239545 -0.427459 -0.698071 0.574436 -0.427459 -0.698071 0.574436 -0.634367 -0.698069 0.332081 -0.634364 -0.698072 0.33208 -0.690627 -0.706826 0.153075 -0.792 -0.610501 -0.00497268 -0.285319 -0.707104 0.646991 -0.285318 -0.707106 0.646989 -0.285407 -0.70709 0.646967 -0.742477 -0.501737 0.443833 -0.742614 -0.501738 0.443603 -0.953763 0 0.300559 -0.953759 -3.74866e-06 0.300571 -0.953812 2.78524e-05 0.300404 -0.953772 2.06471e-06 0.300532 -0.953765 0 0.300554 -0.0646954 0 0.997905 -0.0646954 0 0.997905 0.0646954 0 -0.997905 0.0646954 0 -0.997905 -0.109191 0 -0.994021 -0.109191 0 -0.994021 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.55498 0 0.831864 -0.554982 2.7016e-06 0.831863 -0.55498 0 0.831864 0.554984 0 -0.831861 0.55498 -9.22728e-07 -0.831864 0.55498 0 -0.831864 0.361955 0 -0.932195 0.355954 0.0061115 -0.934484 -0.0655349 -0.0059366 -0.997833 -0.0719467 0 -0.997409 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.403501 0 0.914979 -0.403502 2.62214e-06 0.914979 -0.4035 0 0.91498 0.403499 0 -0.91498 0.4035 3.66377e-07 -0.91498 0.403501 0 -0.914979 0.238301 0 -0.971191 0.189645 0.0379531 -0.981119 -0.108579 -0.027239 -0.993715 -0.157845 0 -0.987464 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.806932 0 0.590645 -0.806931 -1.43026e-06 0.590646 -0.806932 0 0.590645 0.80693 0 -0.590647 0.806931 3.32453e-07 -0.590645 0.806931 0 -0.590645 0.670727 0 -0.741704 0.625732 0.0515839 -0.778331 0.321635 -0.0370378 -0.946139 0.266382 0 -0.963868 0.00784099 0 -0.999969 -0.0796446 -0.0445728 -0.995826 -0.194658 0 -0.980871 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.3731 -0.694734 -0.614932 -0.373098 -0.694744 -0.614922 -0.630574 -0.694742 -0.345992 -0.761487 -0.418167 -0.495252 -0.673295 -0.70611 -0.219275 -0.708167 -0.703119 -0.0642219 -0.876478 -0.481064 0.0190743 -0.69895 -0.704868 0.120957 -0.65451 -0.704867 0.273457 -0.749514 -0.481066 0.454758 0.0156492 -0.694733 0.719098 0.0156516 -0.694742 0.719089 -0.295433 -0.700857 0.649245 -0.409095 -0.52607 0.745581 -0.450099 -0.706113 0.54664 -0.562803 -0.70312 0.434597 0.0217571 0 0.999763 0.0590966 0.0302281 0.997795 -0.414037 -0.0259925 0.909889 -0.379854 0 0.925047 -0.635644 0 0.771982 -0.743151 -0.0347845 0.668219 -0.791487 0 0.611186 -0.922704 0 0.385509 -0.95933 -0.0391455 0.279559 -0.985354 0 0.170521 -0.995913 0 -0.0903169 -0.985782 -0.0347853 -0.16439 -0.950845 0 -0.309667 -0.8383 0 -0.545209 -0.817136 -0.0217174 -0.576036 -0.518551 0.0259935 -0.854651 -0.486395 0 -0.873739 -0.348278 0.698061 -0.625631 -0.348271 0.698069 -0.625625 -0.585233 0.698068 -0.412557 -0.585231 0.69807 -0.412556 -0.706278 0.698068 -0.11778 -0.706279 0.698068 -0.117779 -0.687439 0.698067 0.200327 -0.68744 0.698065 0.200328 -0.532445 0.698063 0.478759 -0.532447 0.698059 0.478763 -0.271992 0.698055 0.662374 -0.271991 0.698068 0.662361 0.0423343 0.698069 0.714778 0.0423378 0.69806 0.714786 0.0156492 -0.694732 0.719098 0.0156516 -0.694742 0.719089 -0.345994 -0.694739 0.630575 -0.34599 -0.694745 0.630572 -0.614922 -0.694745 0.373096 -0.614922 -0.694745 0.373096 -0.719084 -0.694747 0.0156509 -0.719089 -0.694742 0.0156496 -0.630573 -0.694743 -0.345992 -0.630575 -0.694739 -0.345995 -0.373098 -0.694742 -0.614924 -0.3731 -0.694736 -0.614929 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217599 -0.999763 0 0.0217599 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.518726 0 -0.854941 -0.518726 0 -0.854941 -0.373101 0.694736 -0.614929 -0.373097 0.694741 -0.614925 -0.630576 0.694739 -0.345994 -0.630572 0.694743 -0.345993 -0.719089 0.694742 0.015651 -0.719085 0.694746 0.0156495 -0.614922 0.694745 0.373096 -0.614922 0.694745 0.373096 -0.345991 0.694745 0.630571 -0.345992 0.69474 0.630576 0.015649 0.694742 0.719089 0.0156518 0.694733 0.719098 0.0156492 -0.694732 0.719098 0.0156516 -0.694742 0.719089 -0.345991 -0.694743 0.630573 -0.345992 -0.694742 0.630574 -0.614927 -0.694739 0.373099 -0.614927 -0.694739 0.373099 -0.719091 -0.694739 0.015649 -0.719089 -0.694742 0.0156496 -0.630573 -0.694743 -0.345992 -0.630571 -0.694745 -0.34599 -0.373097 -0.694745 -0.61492 -0.373101 -0.694733 -0.614933 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.021757 -0.999763 0 0.021757 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.518727 0 -0.85494 -0.518727 0 -0.85494 -0.373104 0.694732 -0.614931 -0.373095 0.694745 -0.614923 -0.630571 0.694745 -0.345991 -0.630573 0.694743 -0.345991 -0.719089 0.694742 0.0156489 -0.719091 0.69474 0.0156497 -0.614927 0.694739 0.373099 -0.614927 0.694739 0.373099 -0.345992 0.694742 0.630574 -0.345991 0.694743 0.630573 0.015649 0.694742 0.719089 0.0156518 0.694733 0.719098 -0.373099 -0.694739 -0.614927 -0.395922 -0.580874 -0.711219 -0.492295 -0.706844 -0.507954 -0.630585 -0.69473 -0.345997 -0.761499 -0.418136 -0.495259 -0.673299 -0.70611 -0.219263 -0.708165 -0.70312 -0.0642248 -0.876479 -0.481062 0.0190727 -0.698944 -0.704873 0.12096 -0.654507 -0.704872 0.273452 -0.749512 -0.481071 0.454755 -0.562802 -0.703123 0.434594 -0.450094 -0.706115 0.546642 -0.409092 -0.526076 0.745579 0.0423345 -0.698066 0.71478 0.0173404 -0.604028 0.796775 -0.14236 -0.706855 0.692885 -0.295433 -0.700858 0.649244 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.201256 0 0.979539 -0.201256 0 0.979539 -0.414177 0 0.910197 -0.414177 0 0.910197 -0.635639 0 0.771987 -0.635639 0 0.771987 -0.791488 0 0.611185 -0.791488 0 0.611185 -0.922706 0 0.385505 -0.922706 0 0.385505 -0.985353 0 0.170526 -0.985353 0 0.170526 -0.995913 0 -0.0903212 -0.995913 0 -0.0903212 -0.950851 0 -0.309649 -0.950851 0 -0.309649 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.695951 0 -0.718089 -0.695951 0 -0.718089 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0.0156498 0.69474 0.719091 0.0481258 0.580885 0.812562 -0.14236 0.706855 0.692885 -0.34599 0.694743 0.630574 -0.376226 0.418164 0.826796 -0.450094 0.706115 0.546642 -0.562802 0.703123 0.434594 -0.749512 0.481071 0.454755 -0.654507 0.704872 0.273452 -0.698944 0.704873 0.12096 -0.876479 0.481062 0.0190727 -0.708165 0.70312 -0.0642248 -0.673299 0.70611 -0.219263 -0.745591 0.526053 -0.4091 -0.348274 0.698066 -0.625627 -0.413408 0.604019 -0.681363 -0.492295 0.706844 -0.507954 -0.597971 0.700845 -0.388905 0.0860184 -0.702358 -0.706608 0.0858797 -0.702915 -0.70607 0.0378792 -0.81067 -0.584276 0.0366899 -0.686885 -0.725839 0.0367005 -0.686282 -0.726409 0.314324 -0.695263 -0.646382 0.314048 -0.695849 -0.645886 0.210647 -0.852915 -0.477665 0.268249 -0.694381 -0.66774 0.268439 -0.693777 -0.668291 0.372703 -0.69697 -0.612638 0.417787 -0.692025 -0.58869 0.417421 -0.692646 -0.588218 0.292529 -0.849804 -0.438474 0.372432 -0.697567 -0.612123 0.546503 -0.703969 -0.453611 0.592469 -0.684446 -0.42487 0.591996 -0.685052 -0.424552 0.500407 -0.784494 -0.36628 0.546144 -0.704533 -0.453168 0.996066 0 0.088616 0.996064 -1.57709e-06 0.0886335 0.996077 2.64126e-05 0.0884883 0.996062 -3.84906e-06 0.0886557 0.996064 0 0.0886424 0.820488 -0.501823 0.273813 0.820579 -0.501615 0.273921 0.417674 -0.707101 0.570575 0.41765 -0.707106 0.570587 0.417648 -0.707109 0.570585 0.560563 -0.694749 0.450658 0.560565 -0.694745 0.450662 0.710795 -0.694745 0.110001 0.831346 -0.526283 0.178577 0.706811 -0.70651 -0.0355188 0.670566 -0.694746 -0.260133 0.877427 -0.406232 -0.255144 0.605893 -0.705762 -0.367143 0.506583 -0.703329 -0.4987 0.538242 -0.511919 -0.669504 0.359549 -0.704717 -0.611636 0.208771 -0.704692 -0.678103 0.131399 -0.511689 -0.849063 -0.314839 -0.701695 -0.639141 -0.305698 -0.53439 -0.78802 -0.137909 -0.705745 -0.694914 0.0261996 -0.70336 -0.710351 -0.417652 -0.707103 -0.570589 -0.417651 -0.707104 -0.570589 -0.417616 -0.707095 -0.570625 -0.0131232 -0.501739 -0.86492 -0.0128724 -0.501739 -0.864923 0.216601 0 -0.97626 0.216596 -1.52622e-06 -0.976261 0.21655 -1.00277e-05 -0.976272 0.216615 2.76413e-06 -0.976257 0.216585 0 -0.976264 -0.300559 0 -0.953763 -0.300567 -2.40982e-06 -0.953761 -0.300404 2.83e-05 -0.953812 -0.300532 2.51195e-06 -0.953772 -0.300559 0 -0.953763 -0.443688 -0.501823 -0.742506 -0.443812 -0.501617 -0.742571 -0.646988 -0.707106 -0.285318 -0.646989 -0.707106 -0.285319 -0.646988 -0.707105 -0.285324 0.710794 -0.694746 0.110001 0.710794 -0.694746 0.110001 0.670566 -0.694746 -0.260133 0.837244 -0.481412 -0.259356 0.598999 -0.706248 -0.377378 0.450659 -0.694748 -0.560564 0.666986 -0.321713 -0.672034 0.352203 -0.705169 -0.615378 0.204902 -0.704441 -0.679542 0.131566 -0.509849 -0.850143 -0.560566 -0.694746 -0.45066 -0.560566 -0.694745 -0.450661 -0.314838 -0.701696 -0.63914 -0.305697 -0.534393 -0.788019 -0.137911 -0.705745 -0.694913 0.0220655 -0.703655 -0.710199 0.647019 -0.707097 0.285271 0.646988 -0.707107 0.285318 0.64699 -0.707105 0.285318 0.847545 -0.501738 -0.172991 0.847493 -0.501739 -0.173245 0.906936 0 -0.421269 0.906932 7.66684e-07 -0.421277 0.906916 8.2073e-06 -0.421312 0.906936 -3.61476e-07 -0.421269 0.906935 0 -0.42127 0.707081 0 -0.707132 0.70707 1.44595e-06 -0.707144 0.707057 4.96825e-06 -0.707157 0.707072 1.28526e-06 -0.707142 0.707075 0 -0.707139 0.736458 -0.501822 -0.453657 0.736596 -0.501619 -0.453657 0.705638 -0.707097 0.045697 0.705626 -0.707106 0.0457467 0.705626 -0.707106 0.0457467 0.70692 -0.698073 -0.113835 0.70692 -0.698073 -0.113835 0.587521 -0.698074 -0.409282 0.587522 -0.698073 -0.409283 0.351758 -0.698073 -0.623666 0.351759 -0.698072 -0.623667 0.170011 -0.706724 -0.686759 0.0506639 -0.621857 -0.781491 -0.686304 -0.698073 -0.204159 -0.686303 -0.698074 -0.204159 -0.529756 -0.698076 -0.481714 -0.529757 -0.698073 -0.481717 -0.307036 -0.702405 -0.642149 -0.29908 -0.602368 -0.74007 -0.155574 -0.706425 -0.690478 0.0130258 -0.701455 -0.712594 -0.705626 -0.707106 -0.0457467 -0.705626 -0.707106 -0.0457466 -0.705631 -0.707098 -0.0457972 -0.671839 -0.501738 -0.544878 -0.671678 -0.501738 -0.545076 -0.609846 0 -0.79252 -0.609852 -2.08853e-06 -0.792515 -0.609927 -1.90596e-05 -0.792458 -0.609837 2.596e-06 -0.792527 -0.60986 0 -0.792509 -0.309393 -0.501741 -0.807795 -0.309154 -0.501741 -0.807886 -0.588216 -0.707106 -0.392432 -0.588216 -0.707106 -0.392432 -0.588194 -0.707097 -0.392482 -0.131885 0 -0.991265 -0.13188 1.27188e-06 -0.991266 -0.131763 2.26316e-05 -0.991281 -0.131892 -2.37739e-06 -0.991264 -0.131866 0 -0.991268 0.66913 -0.698071 0.254877 0.669129 -0.698073 0.254875 0.71345 -0.698073 -0.0606884 0.713451 -0.698072 -0.0606882 0.664744 -0.706826 -0.241894 0.667564 -0.631496 -0.394424 0.599086 -0.701017 -0.386874 0.484038 -0.706476 -0.516332 0.441871 -0.605043 -0.662324 0.359116 -0.702266 -0.614702 0.198756 -0.705986 -0.679765 0.112732 -0.585731 -0.802627 -0.492278 -0.698073 -0.519958 -0.492278 -0.698073 -0.519958 -0.282056 -0.704329 -0.651433 -0.249011 -0.574979 -0.779354 -0.12984 -0.705354 -0.696862 0.0426674 -0.703369 -0.709544 0.588237 -0.707101 0.39241 0.588217 -0.707106 0.392431 0.588219 -0.707104 0.392431 0.864671 -0.50174 -0.0245176 0.864663 -0.50174 -0.0247751 0.965915 0 -0.258861 0.965913 6.12001e-07 -0.258868 0.965924 -7.67509e-06 -0.258826 0.965911 1.04427e-06 -0.258873 0.965912 0 -0.258869 -0.914979 0 -0.403501 -0.91498 -1.3508e-06 -0.4035 -0.914979 0 -0.403501 0.914979 0 0.403502 0.914979 -2.10328e-07 0.403501 0.914979 0 0.403501 0.982311 0 0.187258 0.987649 0.0344581 0.152846 0.964531 -0.0292468 -0.262346 0.955218 0 -0.295902 0.846086 0 -0.533046 0.751266 -0.0479237 -0.658257 0.704436 0 -0.709767 0.496733 0 -0.867903 0.38637 -0.0559805 -0.920644 0.288691 0 -0.957422 0.0310545 0 -0.999518 -0.05648 -0.0534119 -0.996974 -0.194661 0 -0.980871 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.831863 0 -0.554981 -0.831864 -2.70159e-06 -0.55498 -0.831863 0 -0.554982 0.831861 0 0.554984 0.831863 -7.19185e-07 0.554981 0.831863 0 0.554981 0.934293 -0.0211379 0.355878 0.94139 0 0.337321 0.996245 0.017753 -0.0847435 0.988959 -0.0354826 -0.143876 0.939717 0 -0.341954 0.840062 0 -0.54249 0.805319 -0.0480747 -0.590889 0.683923 0 -0.729554 0.504436 0 -0.863449 0.433578 -0.0572142 -0.899298 0.280639 0 -0.959814 0.0600252 0 -0.998197 -0.0392011 -0.0629003 -0.99725 -0.183169 0 -0.983081 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.997905 0 -0.0646954 -0.997905 7.94588e-08 -0.0646954 -0.997905 0 -0.0646954 0.997905 0 0.0646954 0.997905 1.35695e-08 0.0646954 0.997905 0 0.0646954 0.984701 0 -0.174252 0.987152 -0.0161879 -0.158961 0.792979 0.017211 -0.609006 0.820045 -0.0344022 -0.571264 0.491097 0.0261842 -0.870711 0.422086 -0.0392529 -0.905706 0.240301 0 -0.970698 0.0182764 0 -0.999833 -0.0436091 -0.0481605 -0.997887 -0.219804 0 -0.975544 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.590647 0 -0.80693 -0.590648 -3.49619e-06 -0.806929 -0.590646 0 -0.806931 0.590647 0 0.80693 0.590646 1.89974e-07 0.806931 0.590646 0 0.806931 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.760857 0 0.64892 0.77903 0.0294425 0.626295 0.970868 -0.0258293 0.23822 0.977698 0 0.210014 0.99874 0 -0.0501889 0.973851 -0.0443324 -0.222822 0.960227 0 -0.279221 0.855239 0 -0.518234 0.769752 -0.0554681 -0.635929 0.71263 0 -0.70154 0.506772 0 -0.86208 0.402267 -0.059228 -0.913605 0.294246 0 -0.95573 0.0368576 0 -0.999321 -0.0506831 -0.0556149 -0.997165 -0.194658 0 -0.980871 0.042334 -0.698073 0.714774 0.0423329 -0.698069 0.714778 -0.271987 -0.698069 0.662362 -0.271987 -0.698068 0.662362 -0.532442 -0.698068 0.478756 -0.532438 -0.698072 0.478754 -0.687436 -0.698069 0.200328 -0.687438 -0.698067 0.200328 -0.706278 -0.698068 -0.117779 -0.70628 -0.698066 -0.11778 -0.585236 -0.698062 -0.412563 -0.585232 -0.698069 -0.412558 -0.348273 -0.698069 -0.625624 -0.348273 -0.698073 -0.62562 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.379854 0 0.925047 -0.379854 0 0.925047 -0.743601 0 0.668624 -0.743601 0 0.668624 -0.960065 0 0.279776 -0.960065 0 0.279776 -0.986379 0 -0.164488 -0.986379 0 -0.164488 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.486395 0 -0.873739 -0.486395 0 -0.873739 -0.348272 0.698073 -0.625621 -0.348274 0.698069 -0.625623 -0.585231 0.698069 -0.412559 -0.585237 0.698062 -0.412561 -0.70628 0.698066 -0.117779 -0.706278 0.698068 -0.11778 -0.687438 0.698067 0.200328 -0.687436 0.698069 0.200327 -0.532439 0.698072 0.478753 -0.532441 0.698068 0.478757 -0.271987 0.698068 0.662363 -0.271987 0.698069 0.662362 0.0423343 0.698069 0.714778 0.0423326 0.698073 0.714774 0.0423341 -0.698073 0.714774 0.0423329 -0.698069 0.714778 -0.271986 -0.698069 0.662362 -0.271987 -0.698068 0.662363 -0.532442 -0.698067 0.478756 -0.532438 -0.698072 0.478754 -0.687436 -0.698069 0.200328 -0.687439 -0.698066 0.200328 -0.70628 -0.698067 -0.11778 -0.706277 -0.698069 -0.117778 -0.585234 -0.698065 -0.412561 -0.585232 -0.698069 -0.412558 -0.348274 -0.698069 -0.625623 -0.348273 -0.698072 -0.625621 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.379853 0 0.925047 -0.379853 0 0.925047 -0.743601 0 0.668624 -0.743601 0 0.668624 -0.960065 0 0.279776 -0.960065 0 0.279776 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486395 0 -0.873739 -0.486395 0 -0.873739 -0.348273 0.698072 -0.625621 -0.348274 0.698069 -0.625623 -0.585231 0.698069 -0.412558 -0.585235 0.698065 -0.41256 -0.706277 0.698069 -0.117779 -0.70628 0.698067 -0.117779 -0.687439 0.698066 0.200329 -0.687436 0.698069 0.200327 -0.532439 0.698072 0.478753 -0.532441 0.698068 0.478757 -0.271987 0.698068 0.662363 -0.271987 0.698069 0.662362 0.0423343 0.698069 0.714778 0.0423327 0.698073 0.714774 0.0156489 -0.694746 0.719085 0.0156478 -0.694742 0.719089 -0.345994 -0.694739 0.630575 -0.34599 -0.694745 0.630572 -0.614922 -0.694745 0.373096 -0.614928 -0.694739 0.373098 -0.719091 -0.69474 0.0156511 -0.719096 -0.694735 0.0156498 -0.630579 -0.694737 -0.345993 -0.630582 -0.694732 -0.345996 -0.373102 -0.694729 -0.614936 -0.373097 -0.694748 -0.614918 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.02176 -0.999763 0 0.02176 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518722 0 -0.854943 -0.518722 0 -0.854943 -0.373092 0.694749 -0.61492 -0.373106 0.69473 -0.614933 -0.630583 0.694732 -0.345995 -0.630578 0.694737 -0.345994 -0.719096 0.694735 0.0156512 -0.719091 0.69474 0.0156498 -0.614927 0.694739 0.373099 -0.614923 0.694745 0.373095 -0.345991 0.694745 0.630571 -0.345992 0.69474 0.630576 0.015649 0.694742 0.719089 0.0156477 0.694746 0.719085 0.0423345 -0.698066 0.71478 0.0423352 -0.698069 0.714778 -0.27199 -0.698066 0.662363 -0.271987 -0.698071 0.66236 -0.532436 -0.698073 0.478755 -0.532444 -0.698065 0.478758 -0.687441 -0.698064 0.200328 -0.687431 -0.698074 0.200328 -0.706274 -0.698073 -0.117777 -0.706285 -0.698061 -0.117783 -0.585238 -0.698061 -0.412564 -0.585234 -0.698066 -0.412559 -0.348274 -0.698068 -0.625626 -0.348274 -0.698066 -0.625627 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.379857 0 0.925045 -0.379857 0 0.925045 -0.743598 0 0.668627 -0.743598 0 0.668627 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164487 -0.986379 0 -0.164487 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.348274 0.698066 -0.625627 -0.348273 0.698067 -0.625626 -0.585233 0.698066 -0.41256 -0.585238 0.698061 -0.412562 -0.706286 0.69806 -0.117779 -0.706274 0.698072 -0.117781 -0.687431 0.698075 0.200325 -0.68744 0.698064 0.200331 -0.532442 0.698064 0.47876 -0.532438 0.698073 0.478753 -0.271989 0.698071 0.662359 -0.271989 0.698066 0.662363 0.0423343 0.698069 0.714778 0.0423354 0.698067 0.71478 -0.0019587 -0.704346 0.709854 -0.0535088 -0.684006 0.727511 -0.0534478 -0.684641 0.726918 -0.0407367 -0.776862 0.628352 -0.00208555 -0.704917 0.709287 -0.322643 -0.701709 0.635222 -0.322323 -0.702291 0.63474 -0.231773 -0.81857 0.52557 -0.282308 -0.687597 0.668964 -0.282516 -0.686984 0.669506 -0.422578 -0.697008 0.579317 -0.422213 -0.697594 0.578877 -0.292604 -0.849721 0.438585 -0.3829 -0.692613 0.61129 -0.383195 -0.691991 0.611809 -0.549648 -0.702421 0.452207 -0.592961 -0.686199 0.42134 -0.592486 -0.686803 0.421025 -0.473464 -0.809771 0.346559 -0.549262 -0.702991 0.451792 -0.996063 0 -0.088651 -0.996064 1.39046e-06 -0.0886356 -0.996064 1.84797e-06 -0.0886332 -0.996065 2.37254e-06 -0.0886249 -0.996063 -1.09806e-06 -0.0886461 -0.996065 0 -0.0886218 -0.417644 -0.707104 -0.570594 -0.41765 -0.707106 -0.570587 -0.417651 -0.707104 -0.570588 -0.417649 -0.707107 -0.570587 0.314839 -0.701697 0.639138 0.314839 -0.701697 0.639139 0.417645 -0.707114 0.570581 0.41765 -0.707106 0.570586 0.417653 -0.707101 0.570591 0.417653 -0.707101 0.570591 -0.216585 0 0.976264 -0.216606 -1.60506e-05 0.976259 -0.216602 0 0.97626 -0.216596 -1.05596e-06 0.976261 -0.216596 -9.57736e-07 0.976261 -0.216615 2.76413e-06 0.976257 0.300548 0 0.953767 0.300543 1.5932e-06 0.953768 0.300661 -2.0588e-05 0.953731 0.300558 1.17692e-07 0.953764 0.300559 0 0.953763 0.443683 -0.501821 0.74251 0.443805 -0.501619 0.742573 0.646991 -0.707104 0.285319 0.646987 -0.707108 0.285316 0.646983 -0.707105 0.285335 0.344002 -0.698589 0.627404 0.576763 -0.698587 0.423462 0.576762 -0.69859 0.423459 0.442455 -0.706767 0.552008 0.352244 -0.603821 0.71507 -0.64702 -0.707095 -0.285275 -0.646991 -0.707104 -0.285318 -0.646988 -0.707107 -0.285318 -0.847544 -0.501739 0.172993 -0.847492 -0.50174 0.173246 -0.906936 0 0.421269 -0.906932 7.66684e-07 0.421277 -0.906916 8.2073e-06 0.421312 -0.90693 1.99487e-06 0.42128 -0.906933 0 0.421274 -0.707064 0 0.70715 -0.707085 -2.74388e-06 0.707128 -0.707058 4.82414e-06 0.707156 -0.707072 1.28526e-06 0.707142 -0.707075 0 0.707139 -0.736458 -0.501822 0.453657 -0.736596 -0.501619 0.453657 -0.705635 -0.707099 -0.0457083 -0.705626 -0.707106 -0.0457466 -0.705626 -0.707106 -0.0457466 0.688862 -0.699677 0.189529 0.688861 -0.699678 0.189528 0.55734 -0.699679 0.447014 0.557341 -0.699677 0.447015 0.334546 -0.699677 0.631293 0.334545 -0.699678 0.631292 0.705626 -0.707106 0.0457467 0.705626 -0.707106 0.0457466 0.70563 -0.707099 0.0457855 0.67184 -0.501737 0.544877 0.671679 -0.501738 0.545075 0.609847 0 0.792519 0.609854 -2.51695e-06 0.792514 0.60991 -1.51836e-05 0.792471 0.609857 -2.35384e-06 0.792512 0.609836 0 0.792528 0.309392 -0.501736 0.807798 0.309149 -0.501737 0.807891 0.588217 -0.707106 0.39243 0.588217 -0.707107 0.39243 0.588194 -0.707097 0.392482 0.131885 0 0.991265 0.131878 1.86093e-06 0.991266 0.132022 -2.41672e-05 0.991247 0.131896 1.84948e-07 0.991264 0.131898 0 0.991263 0.514947 -0.701661 0.492444 0.514949 -0.701658 0.492447 0.315222 -0.701657 0.638993 0.315222 -0.701659 0.638991 -0.588255 -0.707096 -0.392391 -0.588217 -0.707106 -0.392431 -0.588217 -0.707106 -0.392431 -0.864673 -0.501737 0.0245138 -0.864665 -0.501738 0.0247709 -0.965912 0 0.25887 -0.965913 -1.61407e-07 0.258868 -0.965905 5.47341e-06 0.258897 -0.965915 -1.66013e-06 0.258858 -0.965914 0 0.258864 0.590646 0 0.806931 0.590646 0 0.806931 -0.590645 0 -0.806931 -0.590645 0 -0.806931 -0.760857 0 -0.64892 -0.779031 -0.0294435 -0.626294 -0.902887 0 -0.429878 -0.977698 0 -0.210015 -0.98692 -0.0515847 -0.152734 -0.99874 0 0.0501889 -0.960226 0 0.279222 -0.93025 -0.0663708 0.360873 -0.85524 0 0.518232 -0.712629 0 0.701542 -0.624857 -0.0737976 0.777244 -0.506774 0 0.862079 -0.294244 0 0.95573 -0.15252 -0.0738703 0.985536 -0.0368577 0 0.999321 0.194657 0 0.980871 0.360867 -0.0665903 0.930237 0.441894 0 0.897067 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.91498 0 0.4035 0.914979 3.17835e-06 0.403502 0.91498 0 0.403499 -0.914979 0 -0.403502 -0.91498 -4.003e-07 -0.4035 -0.91498 0 -0.4035 -0.982311 0 -0.187258 -0.987649 -0.0344581 -0.152846 -0.997305 0 0.0733625 -0.955218 0 0.295902 -0.930715 -0.0583832 0.361055 -0.846083 0 0.533051 -0.704439 0 0.709765 -0.624953 -0.0717119 0.777362 -0.496728 0 0.867906 -0.288691 0 0.957422 -0.152512 -0.0744441 0.985494 -0.0310546 0 0.999518 0.194653 0 0.980872 0.360867 -0.0665917 0.930237 0.441896 0 0.897066 0.625426 0 0.780283 0.778691 -0.0416512 0.626023 0.80607 0 0.59182 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.831864 0 0.55498 0.831863 2.7016e-06 0.554982 0.831864 0 0.55498 -0.831865 0 -0.554978 -0.831864 7.32755e-07 -0.55498 -0.831863 0 -0.554981 -0.934502 0 -0.355959 -0.941211 0.0194496 -0.337258 -0.996245 -0.0177531 0.0847447 -0.988959 0.0354828 0.143877 -0.860509 -0.0320802 0.508425 -0.840062 0 0.54249 -0.683923 0 0.729554 -0.554469 -0.0429602 0.831095 -0.504439 0 0.863447 -0.280639 0 0.959814 -0.138912 -0.0503853 0.989022 -0.0600252 0 0.998197 0.183169 0 0.983081 0.303904 -0.0543521 0.951151 0.442244 0.0272382 0.896481 0.687016 -0.0379536 0.72565 0.722722 0 0.691139 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.997905 0 0.0646954 0.997905 7.94588e-08 0.0646954 0.997905 0 0.0646954 -0.997905 0 -0.0646954 -0.997905 1.01771e-08 -0.0646954 -0.997905 0 -0.0646954 -0.987282 0 0.158982 -0.984588 0.0151613 0.174232 -0.820449 -0.0141312 0.571546 -0.79278 0.0282502 0.608853 -0.491095 -0.0261845 0.870713 -0.422084 0.0392524 0.905707 -0.0646522 -0.0361481 0.997253 -0.0182764 0 0.999833 0.219793 0 0.975546 0.374323 -0.0440166 0.926253 0.468048 0.0293692 0.883215 0.739452 -0.0330599 0.672397 0.779982 0.0165407 0.625583 0.958327 -0.0183802 0.28508 0.964172 0 0.265276 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0423348 -0.69806 0.714787 0.0423374 -0.698069 0.714778 -0.271986 -0.698069 0.662362 -0.271987 -0.698068 0.662363 -0.532442 -0.698067 0.478756 -0.532436 -0.698074 0.478753 -0.687433 -0.698072 0.200326 -0.68744 -0.698066 0.200325 -0.70628 -0.698067 -0.11778 -0.706278 -0.698068 -0.11778 -0.585231 -0.69807 -0.412555 -0.585239 -0.698058 -0.412566 -0.348277 -0.698055 -0.625637 -0.348274 -0.698072 -0.625621 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.379853 0 0.925047 -0.379853 0 0.925047 -0.743601 0 0.668624 -0.743601 0 0.668624 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.817329 0 -0.576171 -0.817329 0 -0.576171 -0.48639 0 -0.873742 -0.48639 0 -0.873742 -0.348269 0.698072 -0.625623 -0.348281 0.698056 -0.625634 -0.585242 0.698058 -0.412562 -0.58523 0.69807 -0.412559 -0.706278 0.698068 -0.11778 -0.70628 0.698067 -0.11778 -0.687439 0.698066 0.200327 -0.687434 0.698072 0.200324 -0.532437 0.698074 0.478751 -0.532441 0.698068 0.478757 -0.271987 0.698068 0.662363 -0.271987 0.698069 0.662362 0.0423343 0.698069 0.714778 0.0423379 0.69806 0.714787 0.0156491 -0.694739 0.719091 0.0156497 -0.694742 0.719089 -0.345992 -0.694743 0.630573 -0.34599 -0.694745 0.630571 -0.61492 -0.694745 0.373097 -0.614921 -0.694744 0.373098 -0.719085 -0.694746 0.0156489 -0.719089 -0.694742 0.0156477 -0.630573 -0.694743 -0.345991 -0.630572 -0.694745 -0.34599 -0.373096 -0.694745 -0.614922 -0.373098 -0.694739 -0.614928 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.373099 0.694739 -0.614927 -0.373095 0.694745 -0.614923 -0.630571 0.694745 -0.34599 -0.630573 0.694743 -0.345991 -0.719089 0.694742 0.015649 -0.719085 0.694746 0.0156477 -0.614921 0.694744 0.373098 -0.614921 0.694745 0.373097 -0.345991 0.694745 0.630571 -0.345991 0.694743 0.630573 0.015649 0.694742 0.719089 0.0156498 0.69474 0.719091 0.0423356 -0.698067 0.71478 0.0423354 -0.698066 0.714781 -0.271991 -0.698063 0.662366 -0.271988 -0.698067 0.662363 -0.532439 -0.69807 0.478755 -0.532444 -0.698065 0.478758 -0.687441 -0.698064 0.200329 -0.687446 -0.69806 0.200328 -0.706286 -0.69806 -0.117783 -0.706273 -0.698074 -0.117777 -0.58523 -0.698072 -0.412554 -0.585234 -0.698066 -0.412559 -0.348274 -0.698068 -0.625626 -0.348274 -0.698066 -0.625627 0.0591253 0 0.998251 0.0591253 0 0.998251 -0.379856 0 0.925046 -0.379856 0 0.925046 -0.743599 0 0.668625 -0.743599 0 0.668625 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.986378 0 -0.164493 -0.986378 0 -0.164493 -0.81733 0 -0.57617 -0.81733 0 -0.57617 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.348274 0.698066 -0.625627 -0.348273 0.698067 -0.625626 -0.585236 0.698066 -0.412558 -0.585229 0.698072 -0.412556 -0.706272 0.698074 -0.117781 -0.706286 0.69806 -0.117779 -0.687445 0.698059 0.20033 -0.687442 0.698064 0.200327 -0.532443 0.698064 0.478759 -0.53244 0.69807 0.478754 -0.271989 0.698067 0.662362 -0.271989 0.698063 0.662367 0.0423357 0.698066 0.714781 0.0423354 0.698067 0.71478 0.0156496 -0.69474 0.71909 0.0156495 -0.69474 0.719091 -0.345993 -0.694741 0.630574 -0.345992 -0.694742 0.630574 -0.614922 -0.694744 0.373098 -0.614921 -0.694745 0.373097 -0.719085 -0.694746 0.0156489 -0.719089 -0.694742 0.0156478 -0.630574 -0.694742 -0.345992 -0.630573 -0.694743 -0.345991 -0.373098 -0.694742 -0.614924 -0.373098 -0.69474 -0.614926 0.0217579 0 0.999763 0.0217579 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.85494 0 0.518726 -0.85494 0 0.518726 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.373099 0.69474 -0.614926 -0.373097 0.694742 -0.614924 -0.630572 0.694744 -0.345991 -0.630574 0.694742 -0.345992 -0.719089 0.694742 0.015649 -0.719085 0.694746 0.0156477 -0.614921 0.694745 0.373097 -0.614922 0.694744 0.373098 -0.345992 0.694742 0.630573 -0.345992 0.694741 0.630574 0.0156496 0.69474 0.719091 0.0156495 0.69474 0.71909 0.435954 -0.684005 0.584877 0.432481 -0.681071 0.590849 0.371116 -0.780803 0.502614 0.382795 -0.7049 0.597147 0.382985 -0.704351 0.597672 0.613382 -0.701703 0.362457 0.597946 -0.686989 0.412925 0.597479 -0.687603 0.41258 0.477831 -0.818567 0.318787 0.612862 -0.702276 0.362226 0.667647 -0.696995 0.26162 0.651873 -0.69199 0.310179 0.651344 -0.692614 0.309899 0.482408 -0.84972 0.212739 0.66709 -0.697596 0.261441 0.706543 -0.702407 0.0861435 0.705974 -0.702997 0.0859955 0.585521 -0.809768 0.0379599 0.725886 -0.686828 0.0368293 0.726491 -0.686188 0.0368407 0.792519 0 -0.609847 0.792514 -2.51695e-06 -0.609854 0.792471 -1.51836e-05 -0.60991 0.792512 -2.35384e-06 -0.609857 0.792528 0 -0.609836 0.544952 -0.50182 -0.671718 0.544969 -0.501621 -0.671852 0.0457467 -0.707106 -0.705626 0.0457466 -0.707106 -0.705626 0.0457855 -0.707099 -0.70563 0.210099 -0.697374 -0.685221 0.210099 -0.697374 -0.685221 0.495346 -0.697373 -0.51798 0.495343 -0.697377 -0.517978 0.675153 -0.697377 -0.240486 0.675153 -0.697377 -0.240486 0.711257 -0.697378 0.0881918 0.711258 -0.697377 0.0881922 0.595972 -0.697376 0.398099 0.595974 -0.697375 0.398101 0.353834 -0.697375 0.623274 0.353833 -0.697377 0.623271 -0.0457084 -0.707099 0.705635 -0.0457466 -0.707106 0.705626 -0.0457466 -0.707106 0.705626 0.453565 -0.501738 0.736571 0.453786 -0.501739 0.736435 0.70715 0 0.707064 0.707128 -2.76405e-06 0.707086 0.707157 4.96825e-06 0.707057 0.707142 1.28526e-06 0.707072 0.707139 0 0.707075 0.258878 0 0.96591 0.258862 -1.49643e-06 0.965914 0.259027 3.14472e-05 0.96587 0.258873 2.67761e-06 0.965911 0.258864 0 0.965914 0.0246483 -0.50182 0.864621 0.02458 -0.50162 0.864739 -0.392391 -0.707096 0.588255 -0.39243 -0.707106 0.588217 -0.392429 -0.707109 0.588214 0.521373 -0.697862 -0.49108 0.521371 -0.697863 -0.491079 0.683913 -0.697863 -0.21272 0.683913 -0.697863 -0.21272 0.707931 -0.697863 0.108724 0.707932 -0.697862 0.108724 0.58856 -0.697863 0.408148 0.588562 -0.69786 0.40815 0.349979 -0.697861 0.624904 0.349978 -0.697864 0.624901 0.39243 -0.707106 -0.588217 0.39243 -0.707107 -0.588217 0.392482 -0.707097 -0.588194 0.807798 -0.501736 -0.309392 0.807891 -0.501737 -0.309149 0.991265 0 -0.131885 0.991266 1.27188e-06 -0.13188 0.991244 -2.77167e-05 -0.13204 0.991264 5.78375e-07 -0.131894 0.991263 0 -0.1319 0.976261 0 0.216596 0.976261 1.07103e-07 0.216596 0.976242 1.62167e-05 0.216683 0.97626 -1.47959e-07 0.2166 0.97626 0 0.216602 0.864875 -0.50182 -0.01299 0.86499 -0.501618 -0.0130636 0.57059 -0.707103 -0.417651 0.570587 -0.707106 -0.41765 0.570571 -0.70711 -0.417666 0.662903 -0.696759 -0.274018 0.6629 -0.696763 -0.274018 0.714539 -0.696763 0.0629002 0.714539 -0.696762 0.0629006 0.604835 -0.696761 0.385615 0.604835 -0.696761 0.385615 0.393794 -0.701457 0.594041 0.403682 -0.589762 0.699444 0.239711 -0.706427 0.665958 -0.570575 -0.707101 0.417674 -0.570587 -0.707106 0.41765 -0.570588 -0.707105 0.417651 -0.273955 -0.501741 0.82049 -0.273715 -0.501742 0.82057 -0.088616 0 0.996066 -0.0886335 -1.57709e-06 0.996064 -0.088476 2.87915e-05 0.996078 -0.0886249 1.88102e-06 0.996065 -0.0886314 0 0.996064 0.172994 -0.501738 0.847545 0.173248 -0.501739 0.847493 -0.290619 -0.708388 0.643216 -0.285241 -0.707295 0.646816 -0.28526 -0.707107 0.647013 0.421276 0 0.906932 0.42127 -5.85103e-07 0.906935 0.421312 8.2073e-06 0.906916 0.42128 1.99487e-06 0.90693 0.421274 0 0.906933 0.264841 -0.705358 0.657518 0.421288 -0.548037 0.722614 0.417156 -0.703368 0.575547 0.532816 -0.705984 0.466577 0.70182 -0.564436 0.43458 0.439802 -0.696371 -0.567135 0.439801 -0.696372 -0.567134 0.65453 -0.696371 -0.294377 0.654528 -0.696373 -0.294377 0.71313 -0.701018 0.00448011 0.80606 -0.589439 0.0531881 0.685637 -0.706479 0.17547 0.633114 -0.702269 0.325552 0.285319 -0.707104 -0.646991 0.285316 -0.707108 -0.646987 0.285335 -0.707105 -0.646983 0.742482 -0.501739 -0.443823 0.742612 -0.501739 -0.443605 0.953767 0 -0.300547 0.95377 2.43662e-06 -0.300539 0.953799 2.02208e-05 -0.300444 0.953763 -3.17101e-06 -0.300561 0.953773 0 -0.300527 0.55498 0 -0.831864 0.554982 2.7016e-06 -0.831863 0.55498 0 -0.831864 -0.554978 0 0.831865 -0.554979 4.68148e-07 0.831864 -0.55498 0 0.831864 -0.35596 0 0.934501 -0.361949 -0.00628972 0.932177 0.0847563 0.00646843 0.996381 0.0655306 -0.0129346 0.997767 0.508642 0.0132866 0.860876 0.488611 -0.0106312 0.872437 0.831817 0.010515 0.554951 0.82172 -0.00788817 0.569837 0.99025 0.00780268 0.139084 0.988398 -0.0052013 0.151798 0.952546 0.00514662 -0.30435 0.954875 -0.00257385 -0.296998 0.726172 0.00254358 -0.687509 0.727938 0 -0.685643 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.403499 0 -0.91498 0.403499 -1.58918e-07 -0.91498 0.403499 0 -0.91498 -0.403499 0 0.91498 -0.403499 1.69619e-07 0.91498 -0.4035 0 0.91498 -0.238301 0 0.971191 -0.189645 -0.0379531 0.981119 -0.0162121 0 0.999869 0.157846 0 0.987464 0.254634 -0.0543518 0.965509 0.37362 0 0.927582 0.586861 0 0.809688 0.648471 -0.0503865 0.75957 0.752322 0 0.658795 0.889316 0 0.457293 0.914135 -0.042962 0.403126 0.968778 0 0.247932 0.99944 0 -0.0334522 0.999225 -0.0388702 0.00627745 0.885028 0.0455922 -0.463301 0.911768 -0.0228198 -0.410071 0.596855 0.0211367 -0.802071 0.612809 0 -0.790231 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.806931 0 -0.590646 0.806931 -6.35672e-07 -0.590646 0.806931 0 -0.590646 -0.806935 0 0.59064 -0.806932 -1.2891e-06 0.590645 -0.806931 0 0.590646 -0.655269 0 0.755396 -0.67059 -0.0202128 0.741553 -0.262559 0.0220366 0.964664 -0.321544 -0.0440305 0.945871 0.0796893 0.0293701 0.996387 0.181862 -0.0440155 0.982338 0.338677 0 0.940903 0.590646 0 0.806931 0.551959 -0.0454284 0.832633 0.880951 0.0545972 0.470047 0.842647 -0.0364354 0.537233 0.998554 0.0344027 0.0413037 0.996 -0.0172104 0.087677 0.918011 0.0161876 -0.396225 0.924158 0 -0.38201 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0646954 0 -0.997905 0.0646954 7.94588e-08 -0.997905 0.0646954 0 -0.997905 -0.0646954 0 0.997905 -0.0646954 1.35695e-08 0.997905 -0.0646954 0 0.997905 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.158982 0 0.987282 0.109059 -0.049119 0.992821 0.570579 0.0598317 0.819061 0.493079 -0.0498941 0.868553 0.86999 0.048411 0.490687 0.83092 -0.0387501 0.55504 0.997201 0.0375605 0.0646488 0.992006 -0.0281818 0.123003 0.926807 0.0272859 -0.374546 0.941868 -0.0181959 -0.335489 0.672661 0.0175972 -0.739742 0.691113 -0.00880119 -0.722693 0.285118 0.00849956 -0.958455 0.293145 0 -0.956068 0.470627 -0.706829 -0.528113 0.427963 -0.754264 -0.497929 0.481773 -0.707051 -0.517662 0.73431 -0.650191 -0.195038 -0.128888 -0.553538 -0.82279 0.966489 0 -0.256707 0.966489 0 -0.256707 0.67875 -0.707109 0.198229 0.678752 -0.707107 0.19823 -0.594683 -0.707106 -0.382562 -0.594682 -0.707108 -0.38256 -0.15476 0 -0.987952 -0.15476 0 -0.987952 0.599072 -0.700912 -0.387085 0.590691 -0.696985 -0.406566 0.734987 -0.572778 -0.362932 0.812934 -0.539016 -0.220455 0.782646 -0.503018 -0.366657 0.907452 -0.341147 -0.245253 0.898444 -0.346563 -0.269615 0.94619 -0.181949 -0.267619 0.962554 -0.14377 -0.229828 0.962346 -0.0575542 -0.265666 0.966312 -0.0191864 -0.256659 0.654014 -0.697154 -0.293669 0.654016 -0.697152 -0.293669 0.716072 -0.697151 0.0349367 0.716071 -0.697152 0.0349362 0.317853 -0.699321 -0.64025 0.317855 -0.69932 -0.64025 0.0312094 -0.69932 -0.714127 -0.50806 -0.69932 -0.502819 -0.508059 -0.699319 -0.502821 -0.298213 -0.703144 -0.64549 -0.266004 -0.68439 -0.678861 -0.157362 -0.706485 -0.690012 0.0312087 -0.69932 -0.714127 0.368247 -0.704791 -0.606353 0.358964 -0.697941 -0.619696 0.197576 -0.676066 -0.709858 0.0914677 -0.514925 -0.852341 0.0755135 -0.692756 -0.717207 -0.0317566 -0.341473 -0.939355 -0.0889415 -0.521477 -0.848617 -0.153523 -0.12617 -0.980057 -0.193653 -0.070363 -0.978544 -0.101015 -0.26044 -0.960191 0.949435 -0.0874875 -0.301527 0.933856 -0.0465945 -0.354601 0.948983 -0.1593 -0.272131 0.919356 -0.266167 -0.289723 0.918992 -0.315149 -0.236928 0.884258 -0.407993 -0.227222 0.870989 -0.462874 -0.1647 0.870824 -0.463793 -0.162978 0.806766 -0.577948 -0.122903 0.806528 -0.578747 -0.120684 0.791366 -0.610279 -0.0360459 0.710541 -0.703036 0.0295258 0.585204 -0.697153 -0.414143 0.585206 -0.69715 -0.414144 0.709394 -0.69715 -0.103643 0.709393 -0.697151 -0.103643 0.237945 -0.706485 0.666529 0.366033 -0.678754 0.636642 0.612037 -0.69932 0.369271 0.611171 -0.686499 0.393939 0.502258 -0.706951 0.497953 0.391289 -0.701397 0.595765 0.398974 -0.0781799 0.913623 0.423106 -0.148632 0.893806 0.399714 -0.281668 0.872292 0.487698 -0.476069 0.731785 0.387186 -0.426473 0.81744 0.55536 -0.620028 0.554203 0.453803 -0.613862 0.645938 0.621988 -0.702319 0.346236 0.609448 -0.749782 0.257682 0.59624 -0.676631 0.432052 0.95309 0 -0.302688 0.95309 0 -0.302688 0.466006 -0.707107 -0.531825 0.466006 -0.707107 -0.531825 -0.296074 -0.707107 0.642137 -0.296073 -0.707108 0.642136 0.400199 0 0.916428 0.400199 0 0.916428 0.724129 -0.650192 -0.229973 0.333294 -0.553543 0.76322 0.678733 -0.706946 0.198871 0.660723 -0.72697 0.186975 0.685918 -0.707093 0.171859 0.656713 -0.0838187 -0.749468 0.649335 -0.195091 -0.735054 0.619567 -0.332078 -0.711239 0.55052 -0.555566 -0.623116 0.51686 -0.618674 -0.591691 0.367295 -0.831467 -0.416841 0.352568 -0.844628 -0.402865 0.128571 -0.980785 -0.14673 0.121935 -0.982973 -0.137462 0.242148 -0.930062 -0.276314 0.979066 -0.192781 -0.0653137 0.936508 -0.194512 -0.29175 0.754065 -0.192784 -0.627869 0.879398 -0.194514 -0.434538 0.754065 -0.192785 -0.627869 0.641392 -0.550821 -0.534053 0.641392 -0.550822 -0.534053 0.430599 -0.828272 -0.358537 0.430596 -0.828274 -0.358537 0.151715 -0.980319 -0.126326 0.151716 -0.980318 -0.126326 0.894852 -0.266726 -0.357906 0.774937 -0.550824 -0.309944 0.77494 -0.550821 -0.309943 0.520256 -0.828273 -0.20808 0.520258 -0.828272 -0.20808 0.183306 -0.980318 -0.0733142 0.183304 -0.980319 -0.0733146 0.979065 -0.192782 -0.0653142 0.83277 -0.550825 -0.0555547 0.832771 -0.550824 -0.0555542 0.559083 -0.828273 -0.0372964 0.559081 -0.828274 -0.0372972 0.196984 -0.980319 -0.0131411 0.196986 -0.980318 -0.0131397 0.682314 -0.606105 -0.40876 0.256899 -0.965474 0.0431596 0.256898 -0.965474 0.0431594 0.25988 -0.965474 -0.0179461 0.25988 -0.965474 -0.0179459 0.248527 -0.965474 -0.0780635 0.248528 -0.965474 -0.0780628 0.223467 -0.965474 -0.133874 0.223466 -0.965474 -0.133875 0.524507 -0.791301 -0.31422 0.637827 -0.707 -0.305495 0.676947 -0.704649 -0.212632 0.676949 -0.704647 -0.212631 0.707872 -0.704647 -0.0488824 0.707871 -0.704648 -0.0488838 0.69975 -0.704648 0.11756 0.699751 -0.704648 0.117561 0.953016 -0.257148 0.160109 0.953017 -0.257146 0.16011 0.964076 -0.257146 -0.0665755 0.964076 -0.257148 -0.0665767 0.921961 -0.257147 -0.289591 0.921962 -0.257146 -0.28959 0.828994 -0.257145 -0.496634 0.828994 -0.257145 -0.496634 0.0700569 -0.997333 0.0204601 0.250286 -0.965905 0.0662135 0.299464 -0.950246 0.085753 0.568921 -0.805186 0.167344 0.680827 -0.707087 0.191057 0.765956 -0.602552 0.224148 0.894062 -0.364322 0.26062 0.929163 -0.258813 0.263954 0.953116 -0.118684 0.278358 0.98618 0 0.16568 0.998468 0.0262556 0.0487145 0.857841 0 -0.513915 0.911939 0.026256 -0.409485 0.954044 0 -0.299668 0.997624 0 -0.0688922 0.997782 0 -0.0665622 0.989226 0.0233274 -0.144527 0.768481 0 -0.639872 0.81605 0.0233276 -0.577511 0.896522 0 -0.443 0.954743 0 -0.297431 -0.837917 -0.0856522 -0.539035 -0.80978 -0.258816 -0.526565 -0.792446 -0.334209 -0.510228 -0.594989 -0.707108 -0.382082 -0.648817 -0.629827 -0.42703 -0.440568 -0.852674 -0.280797 -0.21538 -0.965917 -0.143584 -0.158375 -0.982109 -0.101877 0.410309 -0.189785 -0.89198 -0.0444871 -0.189783 -0.980818 -0.0444879 -0.189784 -0.980817 -0.0408619 -0.432152 -0.900874 -0.00187739 -0.548211 -0.836338 -0.0363251 -0.597765 -0.800848 0.41031 -0.189783 -0.89198 0.376868 -0.432147 -0.81928 0.316461 -0.548211 -0.774156 -0.0280803 -0.784827 -0.619079 0.0324605 -0.829122 -0.558125 -0.0205048 -0.891745 -0.452073 -0.00908651 -0.979686 -0.200332 -0.00908551 -0.979686 -0.200332 0.33502 -0.597763 -0.728314 0.258979 -0.784828 -0.563005 0.179953 -0.829122 -0.529314 0.197035 -0.964872 -0.173779 0.0838048 -0.979686 -0.182188 -0.245773 -0.192092 0.950103 -0.0436916 -0.19501 0.979828 0.131406 -0.193005 0.972359 0.101994 -0.216416 0.970959 0.0939882 -0.43658 0.894743 0.0390139 -0.552745 0.832437 -0.117086 -0.869117 0.480548 0.0642425 -0.788593 0.611551 0.0833751 -0.602592 0.793682 0.0586863 -0.827308 0.558674 0.0206992 -0.980175 0.19705 0.0207034 -0.980175 0.197048 -0.245768 -0.192096 0.950104 -0.209252 -0.549393 0.808938 -0.209258 -0.549389 0.808939 -0.140683 -0.827309 0.543846 -0.140685 -0.827308 0.543846 -0.049621 -0.980175 0.19182 -0.0496248 -0.980175 0.19182 -0.0383788 -0.99579 0.0832375 -0.0789981 -0.98078 0.178407 -0.146626 -0.938363 0.313011 -0.230221 -0.83147 0.505624 -0.267558 -0.771817 0.576812 -0.346531 -0.555568 0.755818 -0.357449 -0.521659 0.774663 -0.410401 -0.195089 0.890793 -0.411059 -0.190309 0.891523 0.444668 -0.00354953 -0.895688 0.417904 0 -0.908491 0.04366 0.00267607 -0.999043 -0.0453099 -0.00535034 -0.998959 -0.222348 0 -0.974967 -0.250436 0 0.968133 -0.250436 0 0.968133 -0.0445468 0 0.999007 -0.0445468 0 0.999007 0.133924 0 0.990992 0.133924 0 0.990992 0.336209 0 0.941787 0.336209 0 0.941787 0.548968 0 0.835843 0.548968 0 0.835843 0.710144 0 0.704057 0.710144 0 0.704057 0.856226 0 0.516602 0.856226 0 0.516602 0.659032 0 -0.752115 0.659032 0 -0.752115 -0.418712 0 0.908119 -0.418712 0 0.908119 -0.841008 0 -0.541023 -0.841008 0 -0.541023 0.959901 0 0.28034 0.959901 0 0.28034 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.700651 -0.707117 0.0952557 0.698231 -0.706474 0.115617 0.707351 -0.697571 0.114228 0.697706 -0.706966 0.115783 0.433057 -0.707109 -0.55898 0.433171 -0.707106 -0.558895 0.433253 -0.707107 -0.55883 0.665652 -0.707109 0.238547 0.665574 -0.707106 0.238774 0.665491 -0.70721 0.238696 0.559123 -0.707115 0.432862 0.550963 -0.706719 0.443833 0.460547 -0.711148 0.531192 0.463359 -0.706795 0.534546 0.463496 -0.704023 0.538073 0.461108 -0.747098 0.478773 0.484996 -0.706629 0.515222 0.526854 -0.706912 0.47191 0.501617 -0.749151 0.432613 0.556769 -0.701323 0.445145 0.615185 -0.712467 0.337547 0.615193 -0.712458 0.337552 0.620305 -0.706667 0.340357 0.620304 -0.706668 0.340357 0.62499 -0.701276 0.342928 0.625005 -0.701259 0.342936 0.376313 -0.70711 0.598651 0.335143 -0.705082 0.62493 0.34902 -0.680734 0.644039 0.334362 -0.706276 0.624001 0.245043 -0.706244 0.664208 0.245043 -0.706245 0.664208 -0.337464 -0.712641 0.61503 -0.337533 -0.712496 0.615159 -0.340357 -0.706667 0.620305 -0.340357 -0.706668 0.620304 -0.342928 -0.701276 0.62499 -0.342936 -0.701259 0.625005 -0.0952557 -0.707117 0.700651 -0.10372 -0.706886 0.699681 -0.224054 -0.713631 0.663725 -0.226401 -0.706569 0.670449 -0.230478 -0.701319 0.674561 -0.172365 -0.769419 0.615049 -0.203696 -0.706631 0.677629 -0.140183 -0.706818 0.693367 -0.125958 -0.739008 0.661817 -0.101854 -0.703979 0.702879 -0.530375 -0.685948 0.498175 -0.432788 -0.707118 0.559176 -0.458397 -0.705983 0.539871 -0.541171 -0.707138 0.455071 -0.502727 -0.724294 0.471873 -0.517477 -0.705294 0.484539 -0.516386 -0.706626 0.483762 -0.4858 -0.707095 0.513824 -0.444603 -0.733303 0.514389 -0.465528 -0.691016 0.552974 0.534407 -0.695874 -0.479759 0.526346 -0.706963 -0.472401 0.527031 -0.706249 -0.472705 0.519088 -0.716723 -0.465677 0.337529 -0.712504 -0.615152 0.337469 -0.71263 -0.615039 0.340357 -0.70667 -0.620302 0.340357 -0.706668 -0.620304 0.342999 -0.701125 -0.62512 0.343007 -0.701108 -0.625135 0.0952607 -0.707117 -0.700651 0.132217 -0.705729 -0.696036 0.132395 -0.688 -0.713532 0.132293 -0.706628 -0.695109 0.176005 -0.707082 -0.684878 0.193888 -0.739178 -0.644999 0.207439 -0.720665 -0.661521 0.212038 -0.705793 -0.675941 0.218657 -0.692733 -0.687248 -0.376379 -0.707113 -0.598606 -0.363484 -0.706657 -0.607055 -0.368999 -0.70035 -0.611023 -0.301137 -0.770785 -0.561433 -0.0193127 -0.714502 -0.699367 -0.321033 -0.70672 -0.630464 -0.270791 -0.706935 -0.653387 -0.215777 -0.782453 -0.58413 -0.224264 -0.706837 -0.670886 -0.171246 -0.706837 -0.686336 -0.131799 -0.782453 -0.608602 -0.122602 -0.706933 -0.696574 -0.0529017 -0.706283 -0.705951 -0.0583922 -0.793684 -0.605521 -0.0170345 -0.700411 -0.713537 -0.0194629 -0.706487 -0.707458 -0.498757 -0.685939 -0.529839 -0.55898 -0.707109 -0.433057 -0.541668 -0.706116 -0.456066 -0.472384 -0.724342 -0.502177 -0.485663 -0.70531 -0.516401 -0.484932 -0.706627 -0.515285 -0.51637 -0.707084 -0.483109 -0.510031 -0.739177 -0.43987 -0.553618 -0.692733 -0.462199 -0.615151 -0.712505 -0.337529 -0.625107 -0.701141 -0.342992 -0.615072 -0.712593 -0.337487 -0.620304 -0.706668 -0.340358 -0.620302 -0.70667 -0.340356 -0.625092 -0.701157 -0.342984 -0.661995 -0.71923 -0.210882 -0.674808 -0.705968 -0.21504 -0.684566 -0.694588 -0.221171 -0.635122 -0.748636 -0.190167 -0.684292 -0.707056 -0.178368 -0.69523 -0.70665 -0.131534 -0.713703 -0.687985 -0.131546 -0.714674 -0.686968 -0.131593 -0.676687 -0.725091 -0.127817 -0.677515 -0.724297 -0.127936 0.585491 -0.706454 -0.397648 0.573192 -0.723039 -0.385572 0.572931 -0.723375 -0.385329 0.588742 -0.702746 -0.399414 0.607052 -0.67934 -0.412292 0.706721 -0.707106 -0.0233947 0.689276 -0.724214 0.0203339 0.70748 -0.706438 0.0204441 0.70749 -0.706427 0.020446 0.733505 -0.679339 0.021638 -0.683682 -0.729022 -0.0332639 -0.706719 -0.707106 0.0234551 -0.707453 -0.705943 -0.033995 -0.741717 -0.669742 -0.0360873 -0.707437 -0.705958 -0.0339924 -0.700588 -0.707098 -0.0958606 -0.655821 -0.741 -0.144283 -0.690564 -0.705959 -0.1573 -0.673119 -0.707101 -0.216608 -0.62297 -0.738505 -0.257912 -0.652549 -0.705942 -0.275365 -0.625009 -0.707102 -0.330711 -0.570562 -0.735936 -0.364495 -0.594522 -0.705921 -0.384992 -0.557732 -0.707101 -0.434675 -0.500051 -0.733289 -0.46069 -0.518256 -0.705904 -0.482815 -0.47335 -0.707103 -0.525305 -0.413451 -0.730568 -0.543442 -0.426092 -0.705886 -0.565836 -0.37445 -0.707104 -0.599825 -0.313295 -0.727767 -0.610083 -0.320855 -0.705869 -0.631507 -0.264064 -0.707106 -0.65595 -0.202552 -0.724884 -0.658419 -0.205773 -0.70585 -0.677816 -0.145593 -0.707106 -0.691956 -0.0845412 -0.721919 -0.686794 -0.0843735 -0.70583 -0.703339 -0.0226453 -0.707105 -0.706746 0.0371638 -0.718863 -0.694158 0.0396196 -0.70581 -0.707292 0.161139 -0.705734 -0.689908 0.161139 -0.705737 -0.689905 0.279425 -0.705737 -0.651043 0.279426 -0.705735 -0.651045 0.389083 -0.705735 -0.592075 0.389082 -0.705737 -0.592073 0.648469 -0.705992 0.284718 0.648471 -0.70599 0.284718 0.59528 -0.70599 0.383694 0.595279 -0.705991 0.383693 0.527104 -0.705991 0.47301 0.527104 -0.70599 0.47301 0.445662 -0.70599 0.550421 0.445662 -0.70599 0.550421 0.353002 -0.70599 0.613978 0.353003 -0.705988 0.613979 0.251456 -0.705988 0.662081 0.251455 -0.70599 0.662079 0.158286 -0.980766 -0.114211 0.841002 -0.0972908 -0.532212 0.834782 -0.19494 -0.514915 0.78584 -0.354853 -0.506493 0.708402 -0.555245 -0.435741 0.641541 -0.646574 -0.412756 0.474266 -0.831222 -0.290073 0.419745 -0.866936 -0.268768 0.167598 -0.980733 -0.100369 0.146316 -0.984963 -0.0918622 0.217812 -0.965708 -0.141301 0.445785 -0.831172 -0.332308 0.493836 -0.793194 -0.356327 0.67438 -0.555369 -0.486598 0.635637 -0.608718 -0.474794 0.805382 -0.19507 -0.559739 0.783334 -0.25869 -0.565214 0.19486 -0.980766 0.0112997 0.678774 -0.733755 -0.0295004 0.471096 -0.882079 -0.00241758 0.195175 -0.980768 -0.00102499 0.310537 -0.9502 -0.0262107 0.123955 -0.992288 -0.000803626 0.555329 -0.831465 0.0165957 0.831589 -0.555249 -0.0126167 0.88232 -0.470646 0.00198624 0.980766 -0.194976 -0.00906963 0.98664 -0.162892 -0.00286765 0.19486 -0.980766 0.0112998 0.554843 -0.831332 0.032175 0.554843 -0.831333 0.0321749 0.830209 -0.55537 0.0481431 0.830212 -0.555365 0.0481445 0.97916 -0.19499 0.0567821 0.97916 -0.194991 0.056782 0.298158 -0.258819 -0.918757 0.236585 -0.258385 -0.936624 -0.918493 -0.258823 -0.298968 -0.246253 -0.706462 -0.663529 0.148328 -0.965808 -0.212637 -0.0603195 -0.965808 -0.252145 -0.19264 -0.965808 -0.173509 -0.212109 -0.965808 -0.149082 -0.257058 -0.965808 -0.0337141 -0.532735 -0.846228 -0.00960039 -0.259108 -0.965837 -0.00465902 -0.379471 -0.925178 0.00689806 -0.127525 -0.991833 -0.00212777 -0.965827 -0.258508 -0.0187357 -0.986805 -0.161719 -0.00794544 -0.912589 -0.408509 -0.0173681 -0.70744 -0.706645 -0.0134402 -0.833051 -0.553162 0.0061789 -0.687699 -0.72593 -0.00977531 -0.2285 -0.965807 -0.122491 -0.228498 -0.965808 -0.12249 -0.241571 -0.965808 -0.0941204 -0.24157 -0.965808 -0.0941201 -0.251136 -0.965808 -0.0643843 -0.090206 -0.965808 -0.243061 -0.0902059 -0.965808 -0.24306 -0.118783 -0.965808 -0.230448 0.121678 -0.965808 -0.228932 0.121678 -0.965808 -0.228931 0.0932622 -0.965808 -0.241903 0.0932628 -0.965808 -0.241905 0.0634932 -0.965808 -0.251365 0.0634935 -0.965807 -0.251366 0.0328018 -0.965807 -0.257178 0.0328016 -0.965807 -0.257177 0.00163416 -0.965807 -0.259255 0.00163405 -0.965808 -0.259254 -0.0295572 -0.965808 -0.257569 -0.623775 -0.706465 -0.334384 -0.623776 -0.706463 -0.334385 -0.659464 -0.706463 -0.256939 -0.659464 -0.706462 -0.256939 -0.397569 -0.706464 -0.585532 -0.170375 -0.965808 -0.195418 -0.145636 -0.965808 -0.214489 -0.397567 -0.706468 -0.585529 -0.324263 -0.706467 -0.629093 -0.442604 -0.258388 -0.858683 -0.373779 -0.258786 -0.890684 0.332168 -0.706464 -0.624958 0.332167 -0.706466 -0.624956 0.254596 -0.706466 -0.660369 0.254597 -0.706462 -0.660372 0.173329 -0.706462 -0.686198 0.173328 -0.706466 -0.686195 0.0895443 -0.706465 -0.70206 0.0895445 -0.706465 -0.702061 0.00446078 -0.706465 -0.707734 0.00446058 -0.706466 -0.707733 -0.9525 -0.258749 -0.160602 -0.257059 -0.965807 -0.0337142 -0.701736 -0.706467 -0.0920353 -0.701739 -0.706465 -0.092036 -0.985393 -0.1109 -0.129238 -0.960469 -0.258657 -0.102933 -0.251138 -0.965808 -0.0643848 -0.685579 -0.706462 -0.175764 -0.685574 -0.706467 -0.175762 -0.935779 -0.258385 -0.239907 -0.93578 -0.258378 -0.239908 -0.90682 -0.224261 -0.356909 -0.900135 -0.258381 -0.350709 -0.864546 -0.258707 -0.430848 -0.87662 -0.103471 -0.469926 -0.837019 -0.258714 -0.482148 -0.756966 -0.258815 -0.600014 -0.21211 -0.965807 -0.149082 -0.579031 -0.706467 -0.406974 -0.579032 -0.706465 -0.406976 -0.795574 -0.233212 -0.559173 -0.791822 -0.25842 -0.553387 -0.19264 -0.965808 -0.173509 -0.525884 -0.706464 -0.47366 -0.525883 -0.706467 -0.473658 -0.717807 -0.258382 -0.646522 -0.717808 -0.258378 -0.646524 -0.170375 -0.965808 -0.195418 -0.465103 -0.706464 -0.533468 -0.465103 -0.706464 -0.533468 -0.653226 -0.109234 -0.749242 -0.660473 -0.258749 -0.704858 -0.442605 -0.258382 -0.858685 -0.500735 -0.258811 -0.826003 -0.552248 -0.183031 -0.81334 -0.549634 -0.258503 -0.794405 -0.616824 -0.258668 -0.743383 -0.145637 -0.965807 -0.214491 -0.118784 -0.965807 -0.230449 -0.324264 -0.706463 -0.629097 -0.246252 -0.706463 -0.663529 -0.34507 -0.128109 -0.929793 -0.319458 -0.258613 -0.911628 -0.181864 -0.258795 -0.948657 -0.0603195 -0.965808 -0.252145 -0.164665 -0.706464 -0.688326 -0.164665 -0.706462 -0.688329 -0.230222 -0.144402 -0.962365 -0.238699 -0.258577 -0.936034 -0.0295572 -0.965808 -0.257569 -0.0806876 -0.706466 -0.703133 -0.0806876 -0.706464 -0.703134 -0.110135 -0.258382 -0.959744 -0.110135 -0.258383 -0.959744 0.236585 -0.258385 -0.936624 0.159761 -0.25877 -0.952636 0.125632 -0.118265 -0.985002 0.102086 -0.258632 -0.960566 0.00608849 -0.25838 -0.966024 0.0183452 -0.133641 -0.99086 -0.0403302 -0.258802 -0.965088 0.148328 -0.965808 -0.212636 0.348681 -0.792823 -0.499853 0.410133 -0.706262 -0.577048 0.454203 -0.608059 -0.651125 0.513305 -0.441634 -0.735852 0.35824 -0.197211 -0.912563 0.347513 -0.258376 -0.901375 0.430089 -0.258682 -0.864932 0.466731 -0.105098 -0.878132 0.481405 -0.258733 -0.83744 0.556544 -0.25831 -0.789642 0.561167 -0.194752 -0.804465 -0.629264 -0.19508 0.75231 0.175533 -0.608059 0.774243 -0.144053 -0.830999 0.537298 -0.094451 -0.980716 0.1711 -0.738438 -0.461134 0.492 -0.792283 -0.305978 0.527887 -0.0506105 -0.980716 0.18877 -0.0506106 -0.980716 0.188771 -0.0274119 -0.980716 0.193506 -0.127205 -0.988284 0.0843418 -0.164359 -0.980694 0.105947 -0.149134 -0.980716 0.126313 -0.149135 -0.980716 0.126313 -0.132766 -0.980716 0.143421 -0.132766 -0.980716 0.14342 -0.114448 -0.980716 0.158423 0.139215 -0.792945 0.593176 0.0979378 -0.896548 0.431984 0.0432124 -0.980716 0.190601 -0.311031 -0.554866 0.771611 -0.207969 -0.831 0.515935 -0.207971 -0.830997 0.515938 -0.0730666 -0.980716 0.181265 -0.0730663 -0.980716 0.181264 -0.384658 -0.886192 0.258267 -0.465108 -0.830987 0.305181 -0.42448 -0.831 0.359522 -0.424478 -0.831001 0.359521 -0.377888 -0.831001 0.408214 -0.377889 -0.831 0.408215 0.0844825 -0.554856 0.827646 0.183948 -0.554857 0.811355 0.207384 -0.441835 0.872797 0.0432125 -0.980716 0.190602 0.0198465 -0.980716 0.194429 0.0564886 -0.830999 0.553399 -0.0108463 -0.830999 0.556168 -0.0162213 -0.554867 0.831781 -0.116687 -0.554867 0.823715 -0.612033 -0.675819 0.410712 -0.694565 -0.554893 0.4579 -0.634837 -0.554862 0.537689 -0.634837 -0.554862 0.53769 -0.565158 -0.554862 0.610512 -0.565156 -0.554864 0.610511 -0.00269013 -0.194912 0.980817 0.0781814 -0.194952 0.977692 0.101548 0.000881296 0.99483 0.13726 -0.195049 0.971142 0.216872 -0.194749 0.956577 0.216872 -0.194748 0.956577 0.122993 -0.831003 0.542501 0.0564885 -0.831003 0.553392 0.0844827 -0.554867 0.827638 -0.0162213 -0.554867 0.831781 -0.0194917 -0.0257772 0.999478 -0.335996 -0.195027 0.92145 -0.254002 -0.194751 0.947394 -0.215441 -0.554859 0.803565 -0.116688 -0.554859 0.823721 -0.0780222 -0.831001 0.550772 -0.010846 -0.831001 0.556165 -0.00381061 -0.980716 0.195402 0.0198465 -0.980716 0.194429 -0.26192 -0.123852 0.95711 -0.201101 -0.195083 0.959949 -0.137573 -0.194741 0.971159 -0.137573 -0.194743 0.971158 -0.0620945 -0.195062 0.978823 -0.00381059 -0.980716 0.195401 -0.0274121 -0.980716 0.193507 -0.0780225 -0.831 0.550773 -0.144052 -0.831 0.537296 -0.21544 -0.554862 0.803563 -0.311032 -0.554862 0.771613 -0.37382 0.0149652 0.92738 -0.391199 -0.194984 0.899413 -0.5155 -0.195083 0.834388 -0.0944498 -0.980716 0.171099 -0.268832 -0.831002 0.486997 -0.268835 -0.830997 0.487002 -0.40206 -0.554858 0.728341 -0.402056 -0.554866 0.728337 -0.482257 -0.0648855 0.873623 -0.464032 -0.194864 0.86412 -0.114448 -0.980716 0.158423 -0.325751 -0.831 0.450916 -0.32575 -0.831002 0.450914 -0.487182 -0.554864 0.674374 -0.487185 -0.554858 0.674377 -0.574385 -0.194746 0.795082 -0.574384 -0.19475 0.795082 -0.685981 -0.0510243 0.725829 -0.666316 -0.19475 0.719789 -0.730166 -0.194997 0.654855 -0.762975 0.0164767 0.646218 -0.768489 -0.195017 0.60942 -0.818273 -0.194776 0.540825 -0.826412 -0.11666 0.550849 -0.281723 0.887819 -0.363882 -0.856123 0.0978245 0.507429 -0.762438 0.131036 0.633654 -0.891986 0.363836 0.268299 -0.656238 0.401932 0.638594 -0.742807 0.623477 0.243955 -0.658296 0.64279 0.391749 -0.577077 0.740864 0.343662 -0.518904 0.750912 0.408497 -0.51678 0.855258 -0.0383706 -0.527842 0.846149 -0.0735925 -0.263866 0.93759 0.226494 -0.993861 0.105931 0.0319154 -0.937772 0.167376 0.304252 -0.908653 0.34349 -0.237411 -0.816214 0.479414 0.322422 -0.787341 0.596313 -0.15654 -0.571702 0.71863 0.395888 -0.57767 0.725299 0.374485 -0.529071 0.788441 -0.313759 -0.464249 0.885595 0.0139438 -0.352666 0.935699 0.00965501 -0.275949 0.949972 0.146304 -0.25167 0.709908 -0.657794 0.281723 0.887819 0.363881 0.856123 0.0978245 -0.507429 0.762427 0.13104 -0.633667 0.891977 0.363836 -0.268328 0.656223 0.401929 -0.638612 0.742798 0.62348 -0.243974 0.658313 0.642788 -0.391723 0.577094 0.74086 -0.343641 0.518894 0.750913 -0.408508 0.516774 0.855263 0.0383436 0.527846 0.846145 0.0735984 0.263866 0.93759 -0.226494 0.993861 0.105931 -0.0319155 0.937772 0.167376 -0.304253 0.908653 0.34349 0.237412 0.816214 0.479414 -0.322423 0.787341 0.596313 0.15654 0.571702 0.71863 -0.395888 0.577671 0.725299 -0.374483 0.529066 0.788438 0.313776 0.464265 0.885588 -0.0138656 0.352697 0.935688 -0.00959635 0.275938 0.949973 -0.146322 0.251669 0.709941 0.657759 0.620363 -0.195084 0.759666 0.868053 -0.195088 -0.456535 0.512672 -0.830869 0.21639 0.316171 -0.830867 -0.457925 0.0673884 -0.980697 0.183554 0.0917547 -0.980697 0.172668 0.114412 -0.980697 0.158566 0.134939 -0.980697 0.141512 0.152949 -0.980697 0.121818 0.150389 -0.980697 -0.124966 -0.0417671 -0.980697 -0.191022 0.195371 -0.980729 0.00069673 0.831498 -0.548484 -0.088182 0.438552 -0.896358 -0.064921 0.815725 -0.571262 -0.0908479 0.79777 -0.5941 -0.102998 0.828638 -0.555574 -0.0685294 0.584443 -0.809961 -0.0488792 0.384938 -0.9161 -0.112175 0.879183 -0.420579 -0.223941 0.894544 -0.420396 -0.151847 0.744294 -0.555441 -0.370826 0.728495 -0.582466 -0.360594 0.404779 -0.896355 -0.180836 0.836085 -0.420382 -0.352479 0.861858 -0.420564 -0.283419 0.629321 -0.734885 -0.252781 0.58631 -0.758122 -0.285467 0.584984 -0.741262 -0.329126 0.15311 -0.983309 -0.0982865 0.111097 -0.980697 -0.160907 0.111097 -0.980697 -0.160907 0.088152 -0.980697 -0.174536 0.180145 -0.980697 0.0760358 0.180145 -0.980697 0.076036 0.188821 -0.980697 0.0507979 0.561589 -0.554677 -0.613964 0.37558 -0.830867 -0.410608 0.375579 -0.830869 -0.410607 0.131972 -0.980697 -0.14428 0.131972 -0.980697 -0.144281 0.715379 -0.55468 0.424926 0.478432 -0.830869 0.284183 0.478432 -0.830868 0.284183 0.168113 -0.980697 0.0998572 0.168113 -0.980697 0.0998572 0.0481655 -0.554675 -0.830672 0.274955 -0.195049 -0.941465 0.189588 -0.194654 -0.962375 0.160826 -0.55468 -0.816374 0.048165 -0.55468 -0.830669 0.0322119 -0.830868 -0.555537 0.0113187 -0.980697 -0.195206 0.0377938 -0.980697 -0.191846 0.107558 -0.830866 -0.545979 0.1809 -0.830866 -0.526248 0.270493 -0.554672 -0.786875 0.375119 -0.554672 -0.742714 0.0377938 -0.980697 -0.191846 0.0635649 -0.980697 -0.184913 0.180899 -0.830869 -0.526244 0.250871 -0.830869 -0.49671 0.375116 -0.554682 -0.742709 0.472754 -0.554682 -0.684713 0.557304 -0.194648 -0.80717 0.620811 -0.195071 -0.759303 0.803497 -0.554676 0.216163 0.867788 -0.195062 0.45705 0.903674 -0.194652 0.381424 0.766578 -0.554678 0.323558 0.803497 -0.554678 0.216163 0.537362 -0.830869 0.144565 -0.0417669 -0.980697 -0.19102 -0.118865 -0.830868 -0.543627 -0.118865 -0.830868 -0.543626 -0.177733 -0.554682 -0.812858 -0.177734 -0.554672 -0.812865 -0.209519 -0.194651 -0.958234 -0.209519 -0.194658 -0.958233 -0.0153672 -0.980697 -0.19493 -0.0437335 -0.830868 -0.554749 -0.0437335 -0.830868 -0.554749 -0.065393 -0.554675 -0.829494 -0.065393 -0.554682 -0.829489 -0.0776705 0.152644 -0.985224 -0.114579 -0.195005 -0.974087 0.189589 -0.194645 -0.962377 0.115148 -0.195075 -0.974006 0.0578364 -0.0416006 -0.997459 0.0484168 -0.194752 -0.979657 -0.0478381 -0.194948 -0.979646 -0.0153672 -0.980697 -0.194928 0.0113186 -0.980697 -0.195205 0.0322119 -0.830868 -0.555537 0.107557 -0.830868 -0.545977 0.160826 -0.55468 -0.816373 0.270491 -0.55468 -0.786871 0.323148 0.108965 -0.940054 0.557304 -0.194652 -0.80717 0.486411 -0.195062 -0.851678 0.449714 0.0702317 -0.890407 0.427174 -0.194851 -0.882925 0.338573 -0.19489 -0.920536 0.063565 -0.980697 -0.184914 0.0881519 -0.980697 -0.174536 0.250872 -0.830868 -0.496712 0.316171 -0.830868 -0.457925 0.472757 -0.554677 -0.684715 0.561589 -0.554676 -0.613964 0.674798 0.0199776 -0.737732 0.671216 -0.1948 -0.715207 0.780413 -0.195025 -0.594071 0.150389 -0.980697 -0.124967 0.427993 -0.830868 -0.355642 0.427991 -0.830869 -0.355641 0.639958 -0.55468 -0.531775 0.63996 -0.554676 -0.531776 0.761938 0.13635 -0.633134 0.738069 -0.194919 -0.645957 0.164924 -0.98072 -0.104829 0.435285 -0.857659 -0.273765 0.472433 -0.830867 -0.294051 0.706409 -0.554677 -0.439682 0.706407 -0.55468 -0.439681 0.832743 -0.194652 -0.518315 0.832743 -0.194649 -0.518315 0.909394 -0.108161 -0.401626 0.895563 -0.194655 -0.400095 0.931721 -0.194984 -0.306393 0.948 0.158042 -0.276258 0.950459 -0.194982 -0.242096 0.969666 -0.194707 -0.147777 0.982805 -0.113699 -0.145489 0.977415 -0.195086 -0.0812491 0.193799 -0.981041 0.000594755 0.556387 -0.830912 -0.00425993 0.530318 -0.847781 -0.00550334 0.832021 -0.554678 -0.00863423 0.832019 -0.55468 -0.00863437 0.980818 -0.19466 -0.0101786 0.98082 -0.19465 -0.0101781 0.193978 -0.980697 0.0246135 0.552041 -0.830869 0.0700477 0.552047 -0.830866 0.0700486 0.825448 -0.554676 0.10474 0.825447 -0.554678 0.10474 0.98278 0.136352 0.124704 0.977377 -0.195036 0.0818295 0.903674 -0.194649 0.381424 0.931525 -0.195071 0.306935 0.965472 0.0199768 0.259739 0.950351 -0.1948 0.242664 0.969537 -0.194918 0.148341 0.19398 -0.980697 0.0246139 0.188822 -0.980697 0.0507982 0.537362 -0.830869 0.144565 0.512672 -0.830869 0.21639 0.766582 -0.554672 0.32356 0.715384 -0.554672 0.424929 0.857642 0.070224 0.509429 0.834613 -0.194838 0.515227 0.73767 -0.195043 0.646375 0.15295 -0.980697 0.121819 0.435281 -0.830867 0.346684 0.43528 -0.830868 0.346683 0.650856 -0.554678 0.51838 0.650855 -0.55468 0.518379 0.77756 0.108972 0.619294 0.780087 -0.194878 0.594548 0.134937 -0.980697 0.14151 0.384019 -0.830868 0.402724 0.38402 -0.830867 0.402726 0.574208 -0.554677 0.602177 0.574208 -0.554678 0.602177 0.6769 -0.194653 0.709871 0.6769 -0.194649 0.709872 0.114413 -0.980697 0.158568 0.325606 -0.830867 0.451265 0.325604 -0.830869 0.451264 0.486863 -0.55468 0.674756 0.486864 -0.554677 0.674757 0.573935 -0.194645 0.795432 0.578077 -0.0191398 0.815758 0.426641 -0.195005 0.883148 0.0917548 -0.980697 0.172668 0.261127 -0.830866 0.4914 0.261126 -0.830867 0.491399 0.39045 -0.554678 0.734766 0.390449 -0.554679 0.734765 0.463755 0.152642 0.872715 0.48592 -0.194944 0.851985 0.0673884 -0.980697 0.183554 0.191781 -0.830867 0.522378 0.191782 -0.830866 0.52238 0.286763 -0.554673 0.781092 0.286762 -0.554679 0.781088 0.338047 -0.194658 0.920778 0.338047 -0.194651 0.92078 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.998819 0 -0.0485966 -0.998694 -0.0472729 -0.0193732 -0.994297 0.00439151 -0.106558 -0.990768 0 -0.135566 -0.986081 0 -0.166264 -0.974662 -0.0272749 -0.222013 -0.968665 0.00387141 -0.248339 -0.951926 -0.000233583 -0.306328 -0.950895 0 -0.309514 -0.930521 0 -0.366238 -0.920966 -0.0280418 -0.388632 -0.895012 0.00304969 -0.446031 -0.883891 0 -0.467694 -0.86652 0 -0.499142 -0.838963 -0.0313774 -0.543283 -0.819649 0.00586535 -0.572836 -0.788747 0 -0.614719 -0.783668 0 -0.621179 -0.743034 -0.00340211 -0.669245 -0.731456 -0.0248428 -0.681436 -0.683757 0.00195195 -0.729707 -0.669414 0 -0.74289 -0.638557 0 -0.769575 -0.601195 -0.0342751 -0.798367 -0.568968 0.00413548 -0.822349 -0.529551 0 -0.848278 -0.518398 0 -0.85514 -0.458128 -0.0122732 -0.888802 -0.452871 -0.0204386 -0.891342 -0.386961 0.00109844 -0.922095 -0.373442 0 -0.927653 -0.330708 0 -0.943733 -0.290303 -0.0359685 -0.956259 -0.247102 0.00264869 -0.968986 -0.2059 0 -0.978573 -0.188278 0 -0.982116 -0.113977 -0.0226479 -0.993225 -0.119094 -0.0148308 -0.992772 -0.0417527 0.000487683 -0.999128 -0.0320253 0 -0.999487 0.0559282 0 -0.998435 0.0184724 -0.0647126 -0.997733 0.105681 0.00140613 -0.994399 0.165394 -0.000858482 -0.986227 0.24472 -0.0384157 -0.968832 0.227437 -0.00819946 -0.973758 0.308675 0.000121842 -0.951167 0.394403 -0.00217054 -0.918935 0.364819 -0.0571362 -0.929324 0.572121 0 -0.820169 0.548868 -0.0338259 -0.835224 0.498376 -0.000346749 -0.866961 0.445244 0.000408153 -0.895409 0.859619 -0.0637349 0.506945 0.840527 0 0.54177 0.890078 0 0.455808 0.915369 -0.0239589 0.401903 0.923432 0 0.383762 0.818359 0 0.574708 0.782699 0 0.6224 0.744051 -0.0239579 0.667693 0.73086 0 0.682528 0.644573 0 0.764543 0.629088 -0.0239583 0.776965 0.581892 0 0.813266 0.498433 0 0.866928 0.531371 -0.0637359 0.844738 0.336424 0 0.941711 0.35495 -0.023958 0.934578 0.410067 0 0.912056 0.463627 0 0.88603 -0.789166 0 0.61418 -0.789166 0 0.61418 -0.673563 0 0.739129 -0.673563 0 0.739129 -0.538445 0 0.842661 -0.538445 0 0.842661 -0.387723 0 0.921776 -0.387723 0 0.921776 -0.225767 0 0.974181 -0.225767 0 0.974181 -0.0572692 0 0.998359 -0.0572692 0 0.998359 0.112888 0 0.993608 0.112888 0 0.993608 0.279774 0 0.960066 0.279774 0 0.960066 0.438554 0 0.898705 0.438554 0 0.898705 0.584625 0 0.811304 0.584625 0 0.811304 0.713757 0 0.700393 0.713757 0 0.700393 0.822207 0 0.569188 0.822207 0 0.569188 0.906833 0 0.421491 0.906833 0 0.421491 0.965182 0 0.26158 0.965182 0 0.26158 0.995564 0 0.0940901 0.995564 0 0.0940901 0.792426 0 -0.609969 0.792426 0 -0.609969 0.685287 0 -0.728273 0.685287 0 -0.728273 0.560691 0 -0.828025 0.560691 0 -0.828025 0.421811 0 -0.906684 0.421811 0 -0.906684 0.272185 0 -0.962245 0.272185 0 -0.962245 0.115627 0 -0.993293 0.115627 0 -0.993293 -0.0438778 0 -0.999037 -0.0438778 0 -0.999037 -0.202265 0 -0.979331 -0.202265 0 -0.979331 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.999485 0 0.032096 -0.999485 0 0.032096 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.860249 0 0.509874 -0.860249 0 0.509874 0.999485 0 -0.032096 0.999485 0 -0.032096 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.860249 0 -0.509874 0.860249 0 -0.509874 0.827246 0 -0.56184 0.810306 -0.039474 -0.584675 0.845011 0 -0.534749 0.998323 0 0.0578933 0.999344 -0.0210445 0.029481 0.999996 0 -0.00290646 0.598606 -0.707113 -0.376379 0.605311 -0.706765 -0.366171 0.607983 -0.70206 -0.370768 0.60519 -0.707058 -0.365806 0.713508 -0.700447 -0.0167239 0.706966 -0.707056 -0.0164792 0.707394 -0.706632 -0.0162585 0.700981 -0.712996 -0.0161836 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.027604 0 -0.999619 -0.952823 0 -0.303526 -0.999734 0 0.023081 -0.999734 0 0.023081 -0.983542 0.172371 -0.0541545 -0.998463 -0.0441835 -0.0334629 -0.993781 0 -0.111356 -0.992115 0 -0.125332 -0.980056 0.0756663 -0.183751 -0.915011 0 -0.40343 -0.925134 -0.0488908 -0.376478 -0.935027 0.135209 -0.327784 -0.952823 0 -0.303526 -0.965504 0 -0.260389 -0.967661 -0.00327331 -0.252231 -0.981333 0.0203052 -0.191243 -0.982634 0 -0.185552 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.798135 0.0927254 -0.5953 -0.812875 0 -0.582438 -0.843463 0 -0.537187 -0.851404 -0.0363318 -0.52325 -0.878954 0.0932196 -0.467708 -0.864509 0.166184 -0.47435 -0.89732 0 -0.441381 -0.655077 0 -0.755562 -0.685014 -0.021327 -0.728217 -0.701784 0.0208514 -0.712085 -0.730234 0 -0.683197 -0.752508 0 -0.658584 -0.764832 -0.0185405 -0.643963 -0.778753 0 -0.62733 -0.513717 0 -0.85796 -0.513717 0 -0.85796 -0.634683 0.039997 -0.771737 -0.644236 0 -0.764826 -0.579078 0 -0.815272 -0.584937 -0.0637935 -0.808566 -0.520985 0.0245881 -0.853212 -0.453762 0 -0.891123 -0.456827 -0.00723588 -0.889526 -0.382858 0.00536331 -0.923792 -0.386055 0 -0.922476 -0.317036 0 -0.948413 -0.317036 0 -0.948413 -0.242086 0 -0.970255 -0.242086 0 -0.970255 -0.173343 0 -0.984862 -0.169935 0.00482909 -0.985443 -0.0959855 -0.0067023 -0.99536 -0.0925465 0 -0.995708 -0.027604 0 -0.999619 -0.0189218 0.024592 -0.999519 0.0503851 -0.0540134 -0.997268 0.0591225 0 -0.998251 0.120842 0 -0.992672 0.132484 0.0219271 -0.990943 0.146637 0 -0.98919 0.186577 -0.0213271 -0.982209 0.209387 0.0208499 -0.977611 0.248899 0 -0.968529 0.280912 0 -0.959733 0.299161 -0.0185396 -0.954023 0.481038 0 -0.8767 0.481038 0 -0.8767 0.651815 0 -0.758378 0.651815 0 -0.758378 0.648015 0.00295718 -0.761622 0.642929 0.00761686 -0.765888 0.622404 0.00224243 -0.782693 0.615548 8.98633e-05 -0.7881 0.612596 0 -0.790396 0.637465 0.0138713 -0.770354 0.638571 0.0122506 -0.769465 0.612564 0.135208 -0.778771 0.578062 -0.0488892 -0.814527 0.555045 0 -0.83182 0.519736 0 -0.854327 0.488728 0.119328 -0.864237 0.47997 0.0666221 -0.874752 0.421814 -0.0697618 -0.903995 0.437317 0 -0.899308 0.354922 0 -0.934896 0.36909 0.139491 -0.918866 0.319837 0 -0.947473 0.700731 0.0179954 -0.713199 0.674174 -0.029894 -0.737967 0.715924 0.0254303 -0.697715 0.692464 0.00795422 -0.721409 0.686682 0.00331367 -0.72695 0.681309 0 -0.731996 0.680192 0.000714723 -0.733033 0.681276 0 -0.732027 0.855626 0 -0.517594 0.855626 0 -0.517594 0.818426 0.125852 -0.56066 0.812226 -0.0320456 -0.582462 0.778387 0 -0.627784 0.769472 0 -0.638681 0.72792 0.0756625 -0.681475 0.723325 0 -0.690508 0.741838 0.082308 -0.665508 0.655077 0 0.755562 0.986566 0 0.163362 0.970016 0 0.24304 0.970016 0 0.24304 0.971074 0.00098636 0.238776 0.972241 0.00239706 0.233969 0.973511 0.00470297 0.228592 0.97437 0.00696199 0.224844 0.975798 0.011219 0.218387 0.999734 0 -0.023081 0.999734 0 -0.023081 0.985348 0.163075 0.0499675 0.998413 0.0417378 0.0377979 0.992634 -0.00551988 0.121024 0.980056 0.0756655 0.183751 0.981072 0.0482579 0.187535 0.978751 0.0261558 0.203376 0.941284 0 0.337617 0.954341 0.0174696 0.298208 0.964829 -0.0373697 0.260207 0.949463 0.0206645 0.313199 0.959654 0 0.281182 0.959654 0 0.281182 0.958678 0.00285314 0.28448 0.956701 0.00899425 0.290934 0.8767 0 0.481038 0.8767 0 0.481038 0.915011 0 0.40343 0.931069 0 0.364843 0.935027 0.135207 0.327785 0.952767 0.000860307 0.3037 0.944505 0.0392418 0.326145 0.778753 0 0.62733 0.798136 0.0927269 0.595299 0.819937 -0.0842057 0.566227 0.843463 0 0.537187 0.860924 0 0.508734 0.878954 0.0932196 0.467708 0.864509 0.16618 0.47435 0.901902 -0.0490219 0.42915 0.47212 -0.0457579 0.880346 0.513717 0 0.85796 0.520984 0.024587 0.853212 0.539529 0 0.841967 0.586131 0 0.810216 0.595278 -0.08855 0.798626 0.644082 0.0219268 0.764643 0.655077 0 0.755562 0.701936 0 0.71224 0.693446 0.0267603 0.720012 0.752397 -0.0170708 0.658489 0.74488 0 0.667199 0.778753 0 0.62733 0.317036 0 0.948413 0.345622 -0.0537214 0.936835 0.38605 0.00534015 0.922462 0.456824 -0.00817939 0.889519 -0.707076 -0.707135 0.00183341 -0.713879 -0.700069 0.0167326 -0.706992 -0.707049 0.0156422 -0.707457 -0.706587 0.0154739 -0.700592 -0.713379 0.0161747 -0.599611 -0.713372 0.362721 -0.614146 -0.707002 0.350675 -0.611979 -0.707249 0.353949 -0.613312 -0.698822 0.368098 -0.601841 -0.711411 0.36288 -0.608707 -0.700886 0.371799 -0.598933 -0.714213 0.362186 -0.934186 0 0.356786 -0.934186 0 0.356786 -0.979609 0 0.200915 -0.979609 0 0.200915 0.934186 0 -0.356786 0.934186 0 -0.356786 0.979609 0 -0.200915 0.979609 0 -0.200915 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.777296 0 0.629135 0.808164 0 -0.588958 0.902607 0 -0.430465 0.855348 0.0957038 -0.509138 0.93605 0 -0.351867 0.923839 0.208811 -0.32081 0.966845 0 -0.255364 0.985111 0 -0.171921 0.955908 0.265037 -0.126476 0.997449 0 -0.0713762 0.999928 0 0.01198 0.961333 0.266733 0.068502 0.993586 0 0.11308 -0.943338 0 0.331834 -0.922962 -0.0250073 0.384077 -0.87655 0.248458 0.412225 -0.998038 0 -0.0626089 -0.997224 0.0729311 0.0150243 -0.998368 -0.0490764 0.0292127 -0.993215 0.00597255 0.116141 -0.992554 0 0.121804 -0.973004 0 0.230789 -0.941195 0.273621 0.198202 -0.95267 0 0.304005 -0.879646 0 0.47563 -0.836957 0 0.547269 -0.774039 0.266733 0.574209 -0.777296 0 0.629135 -0.666764 0 0.745269 -0.666764 0 0.745269 -0.503094 0 0.864232 -0.503094 0 0.864232 -0.318827 0 0.947813 -0.318827 0 0.947813 -0.121507 0 0.992591 -0.121507 0 0.992591 0.0807873 0 0.996731 0.0807873 0 0.996731 0.279774 0 0.960066 0.279774 0 0.960066 0.467307 0 0.884095 0.467307 0 0.884095 0.635708 0 0.77193 0.635708 0 0.77193 0.778084 0 0.628161 0.778084 0 0.628161 0.888604 0 0.458675 0.888604 0 0.458675 0.962745 0 0.270412 0.962745 0 0.270412 0.993586 0 0.11308 0.855613 0.0861205 -0.510401 0.808164 0 -0.588958 0.738741 0 -0.67399 0.738741 0 -0.67399 0.587945 0 -0.808901 0.587945 0 -0.808901 0.41308 0 -0.910695 0.41308 0 -0.910695 0.221302 0 -0.975205 0.221302 0 -0.975205 0.0204648 0 -0.999791 0.0204648 0 -0.999791 -0.18121 0 -0.983444 -0.18121 0 -0.983444 -0.375467 0 -0.926836 -0.375467 0 -0.926836 -0.554352 0 -0.832282 -0.554352 0 -0.832282 -0.710541 0 -0.703655 -0.710541 0 -0.703655 -0.837641 0 -0.54622 -0.837641 0 -0.54622 -0.930448 0 -0.366423 -0.930448 0 -0.366423 -0.985162 0 -0.171625 -0.985162 0 -0.171625 -0.998038 0 -0.0626089 -0.319839 0 0.947472 0.018929 0 0.999821 -0.146637 0 0.98919 -0.0733523 0 0.997306 -0.0587334 -0.114674 0.991665 -0.132484 0.0219271 0.990943 -0.35007 -0.164804 0.922112 -0.422842 0 0.906204 -0.452854 0 0.891585 -0.481041 0 0.876698 -0.481041 0 0.876698 -0.479972 0.0666286 0.87475 -0.488728 0.119326 0.864237 -0.530172 -0.0490191 0.846472 -0.555043 0 0.831822 -0.589318 0 0.807901 -0.612565 0.135211 0.77877 -0.640606 0 0.76787 -0.72792 0.0756625 0.681475 -0.64718 -0.0140721 0.762207 -0.674473 0 0.738299 -0.687013 0 0.726645 -0.724972 0.0203037 0.688479 -0.729127 0 0.684379 -0.855627 0 0.517592 -0.855627 0 0.517592 -0.81496 0.135322 0.563496 -0.814678 0.0344968 0.578886 -0.772225 -0.00552162 0.635326 0.212061 0 0.977256 -0.00274914 0.085743 0.996314 0.027604 0 0.999619 0.092362 -0.0629284 0.993735 0.0747875 -0.0112607 0.997136 0.169935 0.00533916 0.985441 0.240973 -0.0957877 0.965793 -0.382352 0.181092 0.906098 -0.319839 0 0.947472 -0.28091 0 0.959734 -0.269833 -0.0111563 0.962843 -0.209387 0.0208519 0.977611 -0.198167 0 0.980168 -0.146637 0 0.98919 -0.355499 0 -0.934677 -0.355499 0 -0.934677 -0.499677 0 -0.866212 -0.499677 0 -0.866212 -0.631126 0 -0.775681 -0.631126 0 -0.775681 -0.746497 0 -0.665389 -0.746497 0 -0.665389 -0.842851 0 -0.538147 -0.842851 0 -0.538147 -0.917734 0 -0.397196 -0.917734 0 -0.397196 -0.969238 0 -0.246126 -0.969238 0 -0.246126 -0.996051 0 -0.0887864 -0.996051 0 -0.0887864 0.221105 0 0.97525 0.199064 -0.0275899 0.979598 0.139948 -0.000246206 0.990159 0.0797109 0.000417547 0.996818 0.0342942 -0.0347212 0.998809 -0.00274274 -0.000983064 0.999996 -0.0633106 0.000344277 0.997994 -0.131426 -0.0214083 0.991095 -0.140252 -0.00927666 0.990072 -0.20504 -0.000223983 0.978754 -0.293603 0.00277889 0.955923 -0.263621 -0.0501298 0.963323 -0.342574 -0.00128114 0.93949 -0.398854 0.00137387 0.917013 -0.447425 -0.0328544 0.893718 -0.473099 -0.00283119 0.881005 -0.525598 0.000486796 0.850733 -0.589344 -0.0133573 0.807772 -0.585475 -0.0204138 0.810434 -0.641591 -0.000892344 0.767047 -0.714881 0.00566553 0.699223 -0.685515 -0.0628944 0.725336 -0.832093 0 0.554636 -0.817923 -0.0269731 0.574696 -0.783532 0.0018832 0.621349 -0.744453 -0.00276301 0.667669 -0.620363 -0.195084 -0.759666 -0.868053 -0.195088 0.456535 -0.512672 -0.830869 -0.216389 -0.316171 -0.830867 0.457925 -0.0673884 -0.980697 -0.183554 -0.0917547 -0.980697 -0.172668 -0.114411 -0.980697 -0.158566 -0.134938 -0.980697 -0.141511 -0.152951 -0.980697 -0.121819 -0.150389 -0.980697 0.124966 0.0417671 -0.980697 0.191022 -0.195373 -0.980729 -0.000696849 -0.831503 -0.548477 0.0881835 -0.438558 -0.896355 0.0649221 -0.815728 -0.571257 0.0908495 -0.797761 -0.594111 0.103008 -0.828643 -0.555567 0.0685237 -0.584437 -0.809966 0.0488744 -0.384935 -0.916102 0.112174 -0.879184 -0.420579 0.22394 -0.894544 -0.420396 0.151847 -0.744294 -0.555441 0.370826 -0.728495 -0.582466 0.360594 -0.404781 -0.896354 0.180837 -0.836085 -0.420382 0.352479 -0.861858 -0.420564 0.283419 -0.629308 -0.734897 0.25278 -0.586311 -0.758126 0.285456 -0.584984 -0.741262 0.329126 -0.153111 -0.983309 0.0982871 -0.111097 -0.980697 0.160907 -0.111097 -0.980697 0.160907 -0.088152 -0.980697 0.174536 -0.180145 -0.980697 -0.0760359 -0.180144 -0.980697 -0.0760352 -0.188819 -0.980697 -0.0507975 -0.561587 -0.554681 0.613962 -0.37558 -0.830867 0.410608 -0.375579 -0.830869 0.410607 -0.131972 -0.980697 0.14428 -0.131972 -0.980697 0.144281 -0.715379 -0.55468 -0.424926 -0.478431 -0.830869 -0.284182 -0.478436 -0.830866 -0.284185 -0.168114 -0.980697 -0.0998575 -0.168113 -0.980697 -0.0998573 -0.0481655 -0.554675 0.830672 -0.274955 -0.195049 0.941465 -0.189588 -0.194654 0.962375 -0.160826 -0.55468 0.816374 -0.048165 -0.55468 0.830669 -0.0322119 -0.830868 0.555537 -0.0113187 -0.980697 0.195206 -0.0377938 -0.980697 0.191846 -0.107557 -0.830869 0.545975 -0.180899 -0.830869 0.526244 -0.270492 -0.554672 0.786876 -0.375119 -0.554672 0.742714 -0.0377938 -0.980697 0.191846 -0.0635648 -0.980697 0.184913 -0.180899 -0.830869 0.526244 -0.250871 -0.830869 0.49671 -0.375116 -0.554682 0.742709 -0.472755 -0.554682 0.684713 -0.557305 -0.194648 0.80717 -0.620809 -0.195071 0.759304 -0.803498 -0.554676 -0.216163 -0.867789 -0.195062 -0.457049 -0.903674 -0.194652 -0.381424 -0.766578 -0.554678 -0.323559 -0.803497 -0.554678 -0.216163 -0.537366 -0.830866 -0.144566 0.0417669 -0.980697 0.19102 0.118865 -0.830868 0.543627 0.118865 -0.830868 0.543627 0.177733 -0.554682 0.812858 0.177734 -0.554672 0.812865 0.209519 -0.194651 0.958234 0.209519 -0.194658 0.958233 0.0153672 -0.980697 0.19493 0.0437335 -0.830868 0.554749 0.0437335 -0.830868 0.554749 0.065393 -0.554675 0.829494 0.065393 -0.554682 0.829489 0.0776705 0.152644 0.985224 0.114579 -0.195005 0.974087 -0.189588 -0.194654 0.962375 -0.115151 -0.195084 0.974003 -0.0578364 -0.0416006 0.997459 -0.0484168 -0.194752 0.979657 0.0478381 -0.194948 0.979646 0.0153672 -0.980697 0.194928 -0.0113186 -0.980697 0.195205 -0.0322119 -0.830868 0.555537 -0.107558 -0.830868 0.545977 -0.160827 -0.554674 0.816377 -0.270492 -0.554673 0.786874 -0.323148 0.108965 0.940054 -0.557304 -0.194652 0.80717 -0.486411 -0.195062 0.851678 -0.449714 0.0702317 0.890407 -0.427174 -0.194851 0.882925 -0.338573 -0.19489 0.920536 -0.063565 -0.980697 0.184914 -0.0881519 -0.980697 0.174536 -0.250872 -0.830868 0.496712 -0.316171 -0.830868 0.457925 -0.472755 -0.55468 0.684713 -0.561587 -0.554681 0.613962 -0.674798 0.0199841 0.737732 -0.671217 -0.1948 0.715207 -0.780413 -0.195025 0.594071 -0.15039 -0.980697 0.124967 -0.427993 -0.830867 0.355642 -0.427992 -0.830869 0.355641 -0.63996 -0.554675 0.531777 -0.639957 -0.554681 0.531774 -0.761937 0.136353 0.633134 -0.738069 -0.194919 0.645957 -0.164923 -0.98072 0.104829 -0.435282 -0.857662 0.273763 -0.472433 -0.830867 0.294051 -0.706409 -0.554677 0.439682 -0.70641 -0.554675 0.439683 -0.832743 -0.194652 0.518314 -0.832743 -0.194649 0.518315 -0.909394 -0.108162 0.401626 -0.895563 -0.194655 0.400095 -0.931722 -0.194984 0.306392 -0.948001 0.158037 0.276258 -0.950459 -0.194982 0.242096 -0.969666 -0.194707 0.147777 -0.982804 -0.113708 0.14549 -0.977414 -0.195086 0.0812563 -0.193798 -0.981041 -0.000594674 -0.556382 -0.830915 0.00426015 -0.530318 -0.847781 0.00550334 -0.832021 -0.554678 0.00863423 -0.832023 -0.554674 0.00863403 -0.98082 -0.194651 0.0101781 -0.98082 -0.19465 0.0101781 -0.19398 -0.980697 -0.0246139 -0.552046 -0.830866 -0.0700485 -0.552042 -0.830869 -0.0700478 -0.825448 -0.554676 -0.10474 -0.825447 -0.554678 -0.10474 -0.982781 0.136349 -0.124703 -0.977378 -0.195027 -0.0818308 -0.903673 -0.194656 -0.381424 -0.931523 -0.195078 -0.306936 -0.965472 0.0199766 -0.259739 -0.950351 -0.1948 -0.242664 -0.969537 -0.194918 -0.148341 -0.193978 -0.980697 -0.0246136 -0.18882 -0.980697 -0.0507977 -0.537366 -0.830866 -0.144566 -0.512676 -0.830866 -0.216391 -0.766578 -0.554679 -0.323559 -0.71538 -0.554678 -0.424927 -0.857642 0.0702304 -0.509429 -0.834612 -0.194846 -0.515227 -0.73767 -0.195043 -0.646375 -0.15295 -0.980697 -0.121819 -0.435279 -0.830869 -0.346682 -0.435283 -0.830866 -0.346685 -0.650856 -0.554678 -0.518381 -0.650855 -0.55468 -0.51838 -0.77756 0.10897 -0.619295 -0.780086 -0.194886 -0.594547 -0.134938 -0.980697 -0.141511 -0.384019 -0.830869 -0.402724 -0.384018 -0.830869 -0.402723 -0.574211 -0.554673 -0.60218 -0.574208 -0.554678 -0.602177 -0.6769 -0.194653 -0.709871 -0.676901 -0.194649 -0.709871 -0.114412 -0.980697 -0.158567 -0.325606 -0.830866 -0.451266 -0.325605 -0.830869 -0.451264 -0.486863 -0.554679 -0.674756 -0.486865 -0.554673 -0.67476 -0.573935 -0.194648 -0.795431 -0.578076 -0.019139 -0.815758 -0.426641 -0.195005 -0.883148 -0.0917544 -0.980697 -0.172668 -0.261127 -0.830866 -0.491401 -0.261126 -0.830867 -0.4914 -0.39045 -0.554678 -0.734766 -0.390449 -0.554679 -0.734765 -0.463755 0.152642 -0.872715 -0.48592 -0.194947 -0.851984 -0.0673884 -0.980697 -0.183554 -0.191781 -0.830868 -0.522378 -0.191782 -0.830866 -0.52238 -0.286763 -0.554671 -0.781093 -0.286762 -0.554679 -0.781088 -0.338047 -0.194658 -0.920778 -0.338047 -0.194651 -0.92078 0.616635 -0.706482 0.34734 0.22588 -0.96581 0.127234 0.22588 -0.96581 0.127234 0.2394 -0.96581 0.0994904 0.0657461 -0.980718 0.184035 0.0828803 -0.96573 0.245962 0.115611 -0.965811 0.232043 0.115611 -0.965811 0.232043 0.142367 -0.965811 0.21666 0.142367 -0.965811 0.21666 0.167105 -0.965811 0.198207 0.167105 -0.96581 0.198207 0.189475 -0.96581 0.176945 0.189475 -0.965811 0.176945 0.209159 -0.96581 0.153175 0.653541 -0.706482 0.271601 0.315612 -0.706479 0.633464 0.315612 -0.706479 0.633464 0.388653 -0.706479 0.591469 0.388653 -0.706479 0.591469 0.456186 -0.706479 0.541093 0.456186 -0.70648 0.541092 0.517253 -0.70648 0.483047 0.517253 -0.706481 0.483047 0.892072 -0.258391 0.37073 0.892073 -0.258387 0.370731 0.859761 -0.258768 0.440284 0.832063 -0.258629 0.490695 0.864488 -0.124657 0.486951 0.616635 -0.706482 0.34734 0.653541 -0.706482 0.271601 0.2394 -0.96581 0.0994907 0.756039 -0.258772 0.6012 0.209159 -0.96581 0.153175 0.57099 -0.706481 0.418157 0.570989 -0.706482 0.418156 0.800496 -0.124653 0.586232 0.790515 -0.25863 0.555154 0.70604 -0.258391 0.659349 0.70604 -0.258394 0.659349 0.622683 -0.258394 0.738578 0.622683 -0.258394 0.738579 0.562072 -0.258774 0.785564 0.544868 -0.124659 0.829204 0.514338 -0.258629 0.81766 0.14901 -0.896559 0.417106 0.205028 -0.792837 0.57391 0.232213 -0.706277 0.668768 0.267078 -0.608084 0.747599 0.301835 -0.441654 0.844889 0.447853 -0.25863 0.855884 0.442469 -0.124658 0.888078 0.396099 -0.258775 0.880989 0.320532 -0.258321 0.911334 0.329982 -0.19476 0.923678 -0.606338 -0.670865 0.426959 -0.557515 -0.731935 0.391726 -0.58339 -0.701377 0.409544 -0.579283 -0.706021 0.407388 -0.506377 -0.705885 0.495286 -0.506377 -0.705885 0.495286 -0.417486 -0.705885 0.572217 -0.417485 -0.705885 0.572217 -0.317094 -0.705885 0.633386 -0.317094 -0.705886 0.633385 -0.207967 -0.705886 0.677108 -0.207968 -0.705885 0.677109 -0.0931135 -0.705885 0.70218 -0.0931135 -0.705886 0.702178 0.0243059 -0.705886 0.707908 0.0243061 -0.705885 0.70791 0.141056 -0.705885 0.69414 0.141056 -0.705884 0.694141 0.0551994 -0.678514 0.732511 0.0511764 -0.729249 0.682332 0.0530044 -0.704533 0.707689 0.0531067 -0.706272 0.705946 0.150133 -0.706244 0.691867 0.150132 -0.706245 0.691866 0.184276 -0.0228471 0.982609 -0.049362 0 0.998781 -0.0109618 -0.0257037 0.99961 0.0487739 0 0.99881 0.116822 0 0.993153 -0.117407 0 0.993084 -0.19328 -0.00734483 0.981116 -0.205799 -0.0183587 0.978422 -0.435521 0 0.900178 -0.392648 -0.0269275 0.919294 -0.345192 0 0.938532 -0.28034 0 0.959901 -0.495937 0 0.868358 -0.568096 -0.0163159 0.822801 -0.564612 -0.0122379 0.825266 -0.632969 0 0.774177 -0.684326 0 0.729176 -0.714567 -0.0265195 0.699065 -0.848977 -0.00346897 0.528419 -0.83733 -0.0208072 0.546301 -0.795692 0 0.605702 -0.752502 0 0.658589 -0.885059 0 0.465479 -0.914761 0 0.403996 -0.927742 -0.0244796 0.372418 -0.949955 0 0.312388 -0.969058 0 0.246833 -0.982571 -0.0244794 0.184269 -0.999584 -0.0269069 0.0103728 -0.99993 -0.00448664 -0.0109653 -0.996562 0 0.0828481 -0.988586 0 0.150661 -0.996513 0 -0.0834329 -0.988497 0 -0.151242 -0.978243 -0.0265198 -0.205761 -0.921173 -0.0163159 -0.38881 -0.919559 -0.0122379 -0.392762 -0.94977 0 -0.312949 -0.968912 0 -0.247404 -0.884784 0 -0.466 -0.85092 0 -0.525294 -0.825028 -0.0269276 -0.564449 -0.690082 -0.00734482 -0.723694 -0.699193 -0.0183587 -0.714697 -0.752115 0 -0.659032 -0.795335 0 -0.60617 -0.632515 0 -0.774548 -0.578182 0 -0.815908 -0.546239 -0.0257035 -0.837235 -0.495425 0 -0.86865 -0.434992 0 -0.900434 -0.372433 -0.0228473 -0.927778 -0.344639 0 -0.938735 -0.213605 0 -0.97692 -0.184276 -0.0228471 -0.982609 -0.116822 0 -0.993153 -0.0487739 0 -0.99881 0.0109618 -0.0257037 -0.99961 0.193241 -0.0214095 -0.980918 0.205826 -0.00856624 -0.978551 0.117403 0 -0.993084 0.049362 0 -0.998781 0.435521 0 -0.900178 0.392648 -0.0269275 -0.919294 0.345192 0 -0.938532 0.28034 0 -0.959901 0.495937 0 -0.868358 0.568096 -0.0163158 -0.822801 0.564612 -0.0122381 -0.825266 0.752503 0 -0.658589 0.714567 -0.0265197 -0.699065 0.684326 0 -0.729176 0.632971 0 -0.774176 0.795692 0 -0.605702 0.848674 -0.0269069 -0.528231 0.837503 -0.00448658 -0.546414 0.885059 0 -0.465479 0.914761 0 -0.403996 0.927742 -0.0244792 -0.372418 0.988586 0 -0.150661 0.982571 -0.0244794 -0.184269 0.969058 0 -0.246833 0.949954 0 -0.312389 0.996563 0 -0.0828407 0.99994 -0.00346869 -0.0103765 0.999723 -0.0208067 0.010963 0.968912 0 0.247404 0.978243 -0.0265196 0.205761 0.988497 0 0.151242 0.996513 0 0.0834317 0.949771 0 0.312947 0.921234 -0.0116277 0.388836 0.919517 -0.0155025 0.392744 0.884784 0 0.466002 0.850921 0 0.525294 0.825028 -0.0269277 0.564449 0.690081 -0.00734479 0.723695 0.699193 -0.0183587 0.714697 0.752115 0 0.659032 0.795335 0 0.60617 0.632515 0 0.774548 0.578183 0 0.815907 0.546239 -0.0257036 0.837235 0.495425 0 0.868651 0.434992 0 0.900434 0.372433 -0.0228473 0.927778 0.344639 0 0.938735 0.213605 0 0.97692 -0.446148 0 -0.894959 -0.419398 -0.00267683 -0.907799 -0.731311 0.00311387 -0.682037 -0.710763 0 -0.703431 0.828241 -0.253575 0.499717 0.329771 -0.194761 0.923753 0.523106 -0.260721 0.811409 0.530826 -0.254959 0.80822 0.685967 -0.258712 0.680087 0.449486 -0.432154 0.781796 0.399578 -0.597768 0.69499 0.425959 -0.704718 0.567389 0.807694 -0.276766 0.520606 0.602792 -0.696909 0.388535 0.602793 -0.69691 0.388533 0.223428 -0.964023 0.144012 0.223428 -0.964023 0.144014 0.0999493 -0.979686 0.173854 0.211958 -0.964872 0.155228 0.225559 -0.891747 0.392314 0.308888 -0.784826 0.537249 -0.437839 -0.192095 -0.878292 -0.490889 -0.257395 -0.832332 -0.707146 -0.254955 -0.659501 -0.401381 -0.436574 -0.805168 -0.356046 -0.602589 -0.714225 -0.414261 -0.707067 -0.573101 -0.707149 -0.254959 -0.659497 -0.521261 -0.701399 -0.486135 -0.521259 -0.701397 -0.48614 -0.192139 -0.964869 -0.179194 -0.192142 -0.96487 -0.179188 -0.0883919 -0.980175 -0.177323 -0.231273 -0.961438 -0.148827 -0.199888 -0.894019 -0.400967 -0.274344 -0.788593 -0.550323 -0.178503 -0.701397 0.690057 0.0952265 -0.703145 0.704641 0.0752061 -0.694103 0.715937 -0.0315063 -0.706952 0.70656 -0.178504 -0.701397 0.690058 -0.169791 -0.701662 0.691984 0.112051 -0.70433 0.700974 0.0828216 -0.646996 0.757982 -0.0114707 -0.70667 0.707451 -0.169792 -0.701662 0.691984 0.0569593 -0.699678 0.712184 0.05696 -0.69968 0.712182 -0.229952 -0.69968 0.676439 -0.229954 -0.699677 0.676441 -0.479207 -0.699677 0.529917 -0.479207 -0.699677 0.529917 0.0468925 -0.69859 0.713984 0.046893 -0.698592 0.713982 -0.258987 -0.698591 0.667005 -0.258987 -0.698592 0.667005 0.077796 -0.701698 0.708215 0.0777957 -0.701697 0.708216 0.348273 0.698067 0.625626 0.348274 0.698066 0.625627 0.585234 0.698065 0.412561 0.585237 0.698062 0.412562 0.706286 0.698061 0.117779 0.706273 0.698073 0.117781 0.687433 0.698073 -0.200326 0.68744 0.698064 -0.200331 0.532443 0.698064 -0.47876 0.532439 0.698073 -0.478753 0.271988 0.698071 -0.66236 0.271988 0.698071 -0.662359 -0.0423353 0.698068 -0.714779 -0.042335 0.698068 -0.714779 -0.0591248 0 -0.998251 -0.0591248 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.743598 0 -0.668626 0.743598 0 -0.668626 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164487 0.986379 0 0.164487 0.817327 0 0.576175 0.817327 0 0.576175 0.486393 0 0.87374 0.486393 0 0.87374 -0.0423352 -0.698068 -0.714779 -0.0423351 -0.698068 -0.714779 0.271988 -0.698071 -0.662359 0.271988 -0.698071 -0.66236 0.532436 -0.698073 -0.478754 0.532444 -0.698065 -0.478758 0.687441 -0.698064 -0.200328 0.687432 -0.698073 -0.200328 0.706273 -0.698073 0.117777 0.706285 -0.698061 0.117783 0.585236 -0.698062 0.412563 0.585235 -0.698065 0.41256 0.348274 -0.698066 0.625627 0.348274 -0.698067 0.625626 0.373097 0.694739 0.614928 0.3731 0.694735 0.614931 0.630585 0.694731 0.345994 0.630573 0.694743 0.345991 0.719089 0.694742 -0.015649 0.719085 0.694746 -0.0156477 0.614923 0.694745 -0.373095 0.614923 0.694745 -0.373095 0.345989 0.694745 -0.630572 0.34599 0.694743 -0.630574 -0.015649 0.694742 -0.719089 -0.0156498 0.69474 -0.719091 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854943 0 -0.518723 0.854943 0 -0.518723 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876702 0 0.481035 0.876702 0 0.481035 0.518722 0 0.854943 0.518722 0 0.854943 -0.0156491 -0.694739 -0.719091 -0.0156497 -0.694742 -0.719089 0.34599 -0.694743 -0.630573 0.345989 -0.694745 -0.630572 0.614923 -0.694745 -0.373095 0.614923 -0.694745 -0.373095 0.719085 -0.694746 -0.0156489 0.719089 -0.694742 -0.0156477 0.630574 -0.694743 0.345988 0.630583 -0.694731 0.345996 0.3731 -0.694735 0.614931 0.373098 -0.694739 0.614927 0.348274 0.698066 0.625627 0.348273 0.698067 0.625626 0.585233 0.698066 0.41256 0.585238 0.698061 0.412562 0.706286 0.69806 0.117779 0.706273 0.698073 0.117781 0.687433 0.698073 -0.200326 0.687438 0.698066 -0.20033 0.53244 0.698069 -0.478756 0.532438 0.698073 -0.478753 0.271987 0.69807 -0.66236 0.271987 0.698072 -0.662359 -0.0423343 0.698069 -0.714778 -0.0423351 0.698067 -0.71478 -0.0217571 0 -0.999763 -0.0590966 0.030228 -0.997795 0.414037 -0.0259917 -0.909889 0.379854 0 -0.925046 0.635639 0 -0.771987 0.743149 -0.034786 -0.668221 0.791488 0 -0.611185 0.922706 0 -0.385505 0.95933 -0.0391438 -0.27956 0.985353 0 -0.170526 0.995913 0 0.0903212 0.985783 -0.0347819 0.164387 0.950851 0 0.309649 0.8383 0 0.545209 0.817134 -0.0217197 0.576039 0.518547 0.0259911 0.854654 0.486394 0 0.87374 0.373099 -0.694739 0.614927 0.373101 -0.694732 0.614934 0.630585 -0.69473 0.345997 0.761499 -0.418136 0.495259 0.673299 -0.70611 0.219263 0.708165 -0.70312 0.0642248 0.876479 -0.481062 -0.0190727 0.698944 -0.704873 -0.12096 0.654507 -0.704872 -0.273452 0.749512 -0.481071 -0.454755 -0.0156491 -0.694739 -0.719091 -0.0156497 -0.694742 -0.719089 0.295433 -0.700858 -0.649244 0.409092 -0.526077 -0.745579 0.450094 -0.706115 -0.546642 0.562802 -0.703123 -0.434594 0.373104 0.694732 0.614931 0.373095 0.694745 0.614923 0.630571 0.694745 0.345991 0.630573 0.694743 0.345991 0.719089 0.694742 -0.015649 0.719091 0.69474 -0.0156497 0.614922 0.694746 -0.373094 0.614931 0.694732 -0.373104 0.345997 0.69473 -0.630584 0.345997 0.694731 -0.630583 -0.0156534 0.694727 -0.719103 -0.0156477 0.694746 -0.719085 -0.0217628 0 -0.999763 -0.0217628 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854943 0 -0.518722 0.854943 0 -0.518722 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876699 0 0.48104 0.876699 0 0.48104 0.518727 0 0.85494 0.518727 0 0.85494 -0.015653 -0.694747 -0.719084 -0.015648 -0.694728 -0.719102 0.345997 -0.694731 -0.630583 0.345998 -0.69473 -0.630584 0.614934 -0.694732 -0.373101 0.61492 -0.694746 -0.373097 0.719091 -0.69474 -0.0156491 0.719089 -0.694742 -0.0156496 0.630573 -0.694743 0.345992 0.630571 -0.694745 0.34599 0.373097 -0.694745 0.61492 0.373101 -0.694733 0.614933 -0.675616 -0.696374 -0.242088 -0.675619 -0.69637 -0.24209 -0.710205 -0.696371 0.103322 -0.710201 -0.696375 0.103322 -0.578629 -0.696376 0.424559 -0.708457 -0.537383 0.457503 -0.484036 -0.706479 0.51633 -0.31168 -0.696375 0.646465 -0.446519 -0.465251 0.764305 -0.198755 -0.705987 0.679764 0.0281905 -0.696374 0.717125 -0.0554643 -0.382354 0.92235 0.12984 -0.705354 0.696862 -0.706329 -0.696761 0.124992 -0.706329 -0.696762 0.124992 -0.568889 -0.696763 0.436906 -0.56889 -0.696762 0.436906 -0.302995 -0.696762 0.650167 -0.302996 -0.696761 0.650168 0.0313149 -0.696761 0.71662 -0.0154552 -0.53376 0.845495 0.155567 -0.706427 0.690478 -0.703562 -0.697862 -0.13412 -0.703562 -0.697863 -0.13412 -0.705416 -0.706892 0.0518909 -0.743216 -0.637781 0.20215 -0.681686 -0.700509 0.211168 -0.598999 -0.706246 0.377382 -0.606195 -0.591955 0.531147 -0.5012 -0.702697 0.50499 -0.352201 -0.705167 0.615381 -0.317914 -0.570156 0.757531 -0.204901 -0.704442 0.679541 0.0405082 -0.697861 0.715087 -0.0275796 -0.45965 0.887672 0.137905 -0.705745 0.694915 -0.54531 -0.697376 -0.465084 -0.545311 -0.697375 -0.465085 -0.638574 -0.706956 -0.304034 -0.74224 -0.644912 -0.182122 -0.698526 -0.699676 -0.150047 -0.706813 -0.706508 0.0355189 -0.779419 -0.600585 0.178336 -0.684173 -0.70166 0.198949 -0.605894 -0.705762 0.367141 -0.632986 -0.570845 0.522939 -0.506581 -0.703331 0.4987 -0.359552 -0.704714 0.611637 -0.333794 -0.56025 0.758091 -0.20877 -0.704692 0.678103 0.0363818 -0.697378 0.71578 -0.0329024 -0.450679 0.89208 0.137908 -0.705745 0.694914 0.373099 0.694739 0.614927 0.373099 0.694739 0.614927 0.630574 0.694742 0.345992 0.630576 0.69474 0.345992 0.719089 0.694742 -0.015649 0.719085 0.694746 -0.0156477 0.614923 0.694745 -0.373095 0.614931 0.694734 -0.373103 0.345992 0.694738 -0.630577 0.345991 0.694743 -0.630573 -0.015649 0.694742 -0.719089 -0.0156498 0.69474 -0.719091 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854943 0 -0.518723 0.854943 0 -0.518723 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 -0.0156491 -0.694739 -0.719091 -0.0156497 -0.694742 -0.719089 0.34599 -0.694743 -0.630573 0.345994 -0.694738 -0.630577 0.614933 -0.694733 -0.373101 0.614921 -0.694744 -0.373098 0.719085 -0.694746 -0.0156489 0.719089 -0.694742 -0.0156478 0.630576 -0.69474 0.345993 0.630574 -0.694742 0.345991 0.373099 -0.694739 0.614927 0.373099 -0.694739 0.614927 0.348273 0.698072 0.625621 0.348273 0.698071 0.625622 0.585228 0.698072 0.412558 0.585237 0.698062 0.412561 0.70628 0.698066 0.11778 0.706282 0.698064 0.11778 0.687436 0.69807 -0.200326 0.687439 0.698066 -0.200329 0.53244 0.698069 -0.478756 0.532441 0.698068 -0.478757 0.271988 0.698068 -0.662362 0.271988 0.698069 -0.662361 -0.0423343 0.698069 -0.714778 -0.0423325 0.698074 -0.714774 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379854 0 -0.925046 0.379854 0 -0.925046 0.743599 0 -0.668625 0.743599 0 -0.668625 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.16449 0.986379 0 0.16449 0.817325 0 0.576176 0.817325 0 0.576176 0.486395 0 0.873739 0.486395 0 0.873739 -0.042334 -0.698074 -0.714773 -0.0423328 -0.698069 -0.714778 0.271987 -0.698069 -0.662361 0.271988 -0.698068 -0.662362 0.532441 -0.698068 -0.478757 0.53244 -0.698069 -0.478757 0.68744 -0.698066 -0.200327 0.687436 -0.69807 -0.200328 0.706282 -0.698064 0.117781 0.70628 -0.698066 0.11778 0.585235 -0.698062 0.412564 0.58523 -0.698071 0.412556 0.348273 -0.698071 0.625622 0.348273 -0.698072 0.625621 0.373095 0.694745 0.614923 0.373103 0.694733 0.61493 0.630577 0.694738 0.345992 0.630573 0.694743 0.345991 0.719089 0.694742 -0.015649 0.719091 0.69474 -0.0156498 0.614927 0.694739 -0.373099 0.614927 0.694739 -0.373099 0.345992 0.694742 -0.630574 0.345991 0.694743 -0.630573 -0.015649 0.694742 -0.719089 -0.0156477 0.694746 -0.719085 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.8767 0 0.481038 0.8767 0 0.481038 0.518723 0 0.854943 0.518723 0 0.854943 -0.0156489 -0.694746 -0.719085 -0.0156477 -0.694742 -0.719089 0.345991 -0.694743 -0.630573 0.345992 -0.694742 -0.630574 0.614927 -0.694739 -0.373099 0.614927 -0.694739 -0.373099 0.719091 -0.694739 -0.0156491 0.719089 -0.694742 -0.0156497 0.630573 -0.694743 0.34599 0.630577 -0.694738 0.345994 0.373101 -0.694733 0.614933 0.373098 -0.694744 0.614921 0.373094 0.694746 0.614922 0.373104 0.694732 0.614932 0.63058 0.694735 0.345994 0.630574 0.694741 0.345992 0.719091 0.69474 -0.0156496 0.71909 0.694741 -0.0156492 0.614926 0.69474 -0.373099 0.614924 0.694742 -0.373097 0.345991 0.694744 -0.630572 0.345992 0.694742 -0.630574 -0.015649 0.694742 -0.719089 -0.0156477 0.694746 -0.719085 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217579 0.999763 0 -0.0217579 0.8767 0 0.481038 0.8767 0 0.481038 0.518722 0 0.854943 0.518722 0 0.854943 -0.0156489 -0.694746 -0.719085 -0.0156478 -0.694742 -0.719089 0.345992 -0.694742 -0.630574 0.345991 -0.694743 -0.630573 0.614924 -0.694742 -0.373098 0.614926 -0.69474 -0.373098 0.71909 -0.694741 -0.0156496 0.719091 -0.69474 -0.0156493 0.630575 -0.694742 0.345991 0.630579 -0.694735 0.345995 0.373101 -0.694731 0.614934 0.373098 -0.694745 0.614921 -0.441893 0 -0.897068 -0.441893 0 -0.897068 -0.468247 0 -0.883597 -0.431074 -0.0367348 -0.901568 -0.779332 0.0440308 -0.625062 -0.739678 -0.0220346 -0.6726 -0.963976 0.0202133 -0.265221 -0.958489 0 -0.285128 -0.442411 0 -0.896813 -0.397047 -0.0379536 -0.917013 -0.72187 0.0485582 -0.690323 -0.687513 0 -0.726172 -0.480769 0 -0.876847 -0.441508 -0.0416506 -0.89629 -0.80507 0.0498301 -0.591083 -0.779369 0 -0.626565 -0.0423354 0.698067 -0.71478 -0.0423343 0.698069 -0.714778 0.14236 0.706853 -0.692887 0.296454 0.625231 -0.721943 0.295435 0.700859 -0.649242 0.450097 0.706114 -0.54664 0.610187 0.571525 -0.548663 0.562805 0.703115 -0.434603 0.654515 0.704864 -0.273456 0.800724 0.55172 -0.233339 0.698957 0.70486 -0.120961 0.706287 0.698059 0.117779 0.876361 0.475053 0.0794792 0.67329 0.706116 0.219274 0.585229 0.698072 0.412556 0.348274 0.698066 0.625627 0.348273 0.698067 0.625626 0.492303 0.706852 0.507935 0.668093 0.60403 0.434511 -0.0591236 0 -0.998251 -0.0217498 0.0259918 -0.999426 0.201256 0 -0.979539 0.41418 0 -0.910195 0.480588 0.0433751 -0.875873 0.635643 0 -0.771983 0.791483 0 -0.611191 0.85378 0.0520795 -0.518023 0.922706 0 -0.385505 0.985353 0 -0.170525 0.998407 0.0520793 -0.0217275 0.995913 0 0.0903217 0.950845 0 0.309667 0.875874 0.0433749 0.480586 0.8383 0 0.545209 0.695971 0 0.71807 0.51855 0.0259932 0.854652 0.486394 0 0.87374 -0.0156491 -0.694739 -0.719091 -0.0156497 -0.694742 -0.719089 0.345992 -0.694743 -0.630573 0.345995 -0.694739 -0.630575 0.614923 -0.694742 -0.373099 0.614921 -0.694744 -0.373099 0.719085 -0.694746 -0.0156489 0.719089 -0.694742 -0.0156477 0.630573 -0.694743 0.345991 0.630572 -0.694745 0.34599 0.373096 -0.694745 0.614922 0.373098 -0.694739 0.614928 0.348278 0.69806 0.625632 0.348272 0.698067 0.625626 0.585235 0.698066 0.412558 0.585231 0.69807 0.412557 0.706278 0.698068 0.11778 0.70628 0.698067 0.11778 0.687439 0.698066 -0.200327 0.687437 0.698068 -0.200326 0.532444 0.698065 -0.478757 0.532443 0.698067 -0.478755 0.271987 0.698068 -0.662363 0.271987 0.698069 -0.662362 -0.0423343 0.698069 -0.714778 -0.0423379 0.69806 -0.714787 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379853 0 -0.925047 0.379853 0 -0.925047 0.743601 0 -0.668624 0.743601 0 -0.668624 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.16449 0.986379 0 0.16449 0.817329 0 0.576171 0.817329 0 0.576171 0.486395 0 0.873739 0.486395 0 0.873739 -0.0423348 -0.69806 -0.714787 -0.0423374 -0.698069 -0.714778 0.271986 -0.698069 -0.662362 0.271987 -0.698068 -0.662363 0.532442 -0.698067 -0.478756 0.532444 -0.698065 -0.478757 0.687437 -0.698069 -0.200327 0.687439 -0.698066 -0.200327 0.70628 -0.698067 0.11778 0.706278 -0.698068 0.11778 0.585231 -0.69807 0.412555 0.585234 -0.698066 0.412559 0.348274 -0.698068 0.625625 0.348276 -0.69806 0.625632 0.348278 0.69806 0.625632 0.348271 0.698069 0.625626 0.585233 0.698068 0.412556 0.585231 0.69807 0.412556 0.706278 0.698068 0.11778 0.70628 0.698067 0.11778 0.687439 0.698066 -0.200327 0.68744 0.698065 -0.200328 0.532445 0.698062 -0.47876 0.532442 0.69807 -0.478753 0.271987 0.698069 -0.662361 0.271987 0.698069 -0.662361 -0.0423343 0.698069 -0.714778 -0.0423377 0.69806 -0.714786 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379854 0 -0.925046 0.379854 0 -0.925046 0.7436 0 -0.668624 0.7436 0 -0.668624 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.16449 0.986379 0 0.16449 0.817329 0 0.576171 0.817329 0 0.576171 0.486395 0 0.873739 0.486395 0 0.873739 -0.0423348 -0.69806 -0.714787 -0.0423372 -0.698069 -0.714778 0.271987 -0.698069 -0.662361 0.271987 -0.698069 -0.662361 0.53244 -0.69807 -0.478755 0.532447 -0.698063 -0.478758 0.68744 -0.698065 -0.200328 0.687439 -0.698066 -0.200328 0.70628 -0.698067 0.11778 0.706278 -0.698068 0.11778 0.585231 -0.69807 0.412555 0.585233 -0.698068 0.412557 0.348273 -0.698069 0.625624 0.348275 -0.69806 0.625633 0.373103 0.694734 0.614931 0.373096 0.694743 0.614924 0.630573 0.694742 0.345992 0.630574 0.694742 0.345992 0.71909 0.694741 -0.0156493 0.71909 0.69474 -0.0156494 0.614926 0.694739 -0.373099 0.614924 0.694742 -0.373097 0.345991 0.694744 -0.630572 0.345992 0.694742 -0.630574 -0.015649 0.694742 -0.719089 -0.0156518 0.694733 -0.719098 -0.0591236 0 -0.998251 -0.0217497 -0.0259918 -0.999426 0.201253 0 -0.979539 0.414177 0 -0.910196 0.480587 -0.0433764 -0.875874 0.635645 0 -0.771982 0.791487 0 -0.611186 0.853781 -0.0520772 -0.518021 0.922704 0 -0.38551 0.985354 0 -0.170521 0.998407 -0.0520775 -0.021728 0.995913 0 0.0903169 0.950845 0 0.309667 0.875874 -0.0433747 0.480587 0.486395 0 0.873739 0.518551 -0.0259935 0.854651 0.695969 0 0.718072 0.8383 0 0.545209 0.348275 -0.698061 0.625632 0.348273 -0.698069 0.625624 0.4923 -0.706855 0.507935 0.637872 -0.625236 0.449666 0.59796 -0.700859 0.388898 0.673294 -0.706112 0.219275 0.809414 -0.571515 0.134978 0.708166 -0.703119 0.0642218 0.698951 -0.704867 -0.120957 0.800724 -0.551718 -0.233341 0.654512 -0.704865 -0.273458 0.532446 -0.698063 -0.478758 0.696479 -0.475044 -0.53782 0.450101 -0.70611 -0.546642 0.271987 -0.698068 -0.662362 -0.0423348 -0.69806 -0.714787 -0.0423373 -0.698069 -0.714778 0.142358 -0.706855 -0.692886 0.330085 -0.604025 -0.725395 -0.441893 0 -0.897068 -0.499242 -0.0500192 -0.865018 -0.642378 0 -0.766388 -0.818844 0 -0.574016 -0.842612 -0.0375269 -0.537211 -0.931779 0 -0.363026 -0.996148 0 -0.0876902 -0.993727 -0.0228995 -0.109467 -0.92387 0.0249442 0.381893 -0.932306 0 0.361671 -0.373623 0 -0.927581 -0.502661 -0.0628988 -0.862192 -0.586861 0 -0.809688 -0.752322 0 -0.658795 -0.848809 -0.0572136 -0.525595 -0.889316 0 -0.457293 -0.968775 0 -0.247942 -0.996676 -0.0480759 -0.0657667 -0.99998 0 -0.00627851 -0.976306 0 0.216394 -0.911431 -0.0354828 0.409919 -0.885811 0.0177517 0.463707 -0.612693 -0.0194512 0.790082 -0.596986 0 0.802252 -0.292113 0 -0.956384 -0.488604 -0.012011 -0.872423 -0.508662 0.00961027 -0.860913 -0.821707 -0.00972465 -0.569828 -0.831842 0.00729341 -0.554965 -0.988384 -0.00737787 -0.151797 -0.990268 0.00491959 -0.139087 -0.954866 -0.00497525 0.296997 -0.952557 0.00248606 0.30435 -0.727936 -0.00251743 0.685641 -0.726173 0 0.687512 -0.362743 0 -0.931889 -0.492931 -0.0556145 -0.868289 -0.567925 0 -0.82308 -0.761604 0 -0.648042 -0.830085 -0.0592283 -0.554482 -0.890552 0 -0.454882 -0.977939 0 -0.208892 -0.990872 -0.0554685 -0.122865 -0.999751 0 0.0223296 -0.959904 0 0.280329 -0.941097 -0.0443324 0.335217 -0.869351 0 0.494195 -0.69114 0 0.722721 -0.711514 -0.0294424 0.702055 -0.292985 0.0330315 0.955546 -0.320768 0 0.947158 -0.0423352 0.698067 -0.714779 -0.0423353 0.698067 -0.71478 0.142357 0.706855 -0.692886 0.296455 0.625231 -0.721943 0.295435 0.700853 -0.649248 0.450105 0.706106 -0.546645 0.610189 0.571517 -0.548669 0.562799 0.703127 -0.434592 0.6545 0.704877 -0.273458 0.800723 0.551721 -0.233338 0.698946 0.704873 -0.120951 0.706273 0.698073 0.117781 0.876383 0.475013 0.0794722 0.673301 0.706104 0.219278 0.585239 0.698063 0.412559 0.348275 0.698067 0.625625 0.348271 0.698073 0.625621 0.492285 0.706861 0.507941 0.668093 0.60403 0.434511 -0.0591248 0 -0.998251 -0.0217502 0.0259924 -0.999425 0.201252 0 -0.97954 0.414178 0 -0.910196 0.480587 0.0433761 -0.875874 0.635645 0 -0.771981 0.791488 0 -0.611185 0.85378 0.0520758 -0.518023 0.922701 0 -0.385516 0.985355 0 -0.170513 0.998407 0.0520747 -0.0217276 0.995914 0 0.0903115 0.950845 0 0.309667 0.875874 0.0433748 0.480587 0.8383 0 0.545209 0.695954 0 0.718086 0.51855 0.0259913 0.854652 0.486396 0 0.873738 -0.0156494 -0.69474 -0.71909 -0.0156494 -0.694741 -0.71909 0.345992 -0.694742 -0.630574 0.345992 -0.694742 -0.630574 0.614922 -0.694744 -0.373098 0.614932 -0.694734 -0.3731 0.719098 -0.694733 -0.0156492 0.719089 -0.694742 -0.0156516 0.630574 -0.694742 0.345992 0.630573 -0.694743 0.345991 0.373098 -0.694742 0.614924 0.373098 -0.69474 0.614926 0.373099 0.694739 0.614927 0.373099 0.694739 0.614927 0.630574 0.694742 0.345992 0.630573 0.694743 0.345991 0.719089 0.694742 -0.015649 0.719098 0.694733 -0.0156518 0.614931 0.694733 -0.373103 0.614924 0.694743 -0.373096 0.345992 0.694742 -0.630574 0.345991 0.694743 -0.630573 -0.0156489 0.694742 -0.719089 -0.0156497 0.69474 -0.719091 -0.021757 0 -0.999763 -0.021757 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.85494 0 -0.518726 0.85494 0 -0.518726 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 -0.015649 -0.694739 -0.719091 -0.0156496 -0.694742 -0.719089 0.345991 -0.694743 -0.630573 0.345992 -0.694742 -0.630574 0.614922 -0.694744 -0.373098 0.614933 -0.694733 -0.373101 0.719098 -0.694732 -0.0156492 0.719089 -0.694742 -0.0156516 0.630573 -0.694743 0.345991 0.630574 -0.694742 0.345992 0.373099 -0.694739 0.614927 0.373099 -0.694739 0.614927 0.373099 0.694739 0.614927 0.373095 0.694745 0.614923 0.630571 0.694745 0.34599 0.630573 0.694743 0.345991 0.719089 0.694742 -0.015649 0.719098 0.694733 -0.0156518 0.614931 0.694732 -0.373104 0.614925 0.694741 -0.373097 0.345994 0.694739 -0.630576 0.345993 0.694743 -0.630572 -0.0156489 0.694742 -0.719089 -0.0156497 0.69474 -0.719091 -0.021757 0 -0.999763 -0.021757 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.85494 0 -0.518727 0.85494 0 -0.518727 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 -0.015649 -0.694739 -0.719091 -0.0156496 -0.694742 -0.719089 0.345992 -0.694743 -0.630573 0.345995 -0.694739 -0.630575 0.614923 -0.694742 -0.373099 0.614932 -0.694733 -0.373102 0.719098 -0.694732 -0.0156492 0.719089 -0.694742 -0.0156516 0.630573 -0.694743 0.345991 0.630572 -0.694745 0.34599 0.373096 -0.694745 0.614922 0.373098 -0.694739 0.614928 -0.0156477 0.694746 -0.719085 -0.0481322 0.580861 -0.812579 0.142384 0.706854 -0.692881 0.345992 0.69474 -0.630576 0.376228 0.418161 -0.826797 0.450096 0.706104 -0.546654 0.562806 0.703115 -0.434601 0.749524 0.481047 -0.454762 0.654514 0.704866 -0.273451 0.698951 0.704866 -0.120962 0.876483 0.481054 -0.0190751 0.708165 0.70312 0.0642248 0.673295 0.706112 0.219271 0.74558 0.526072 0.409095 0.348273 0.698072 0.625621 0.413407 0.604025 0.681358 0.492295 0.706853 0.50794 0.597963 0.700855 0.3889 -0.0591303 0 -0.99825 -0.0591303 0 -0.99825 0.20129 0 -0.979532 0.20129 0 -0.979532 0.414178 0 -0.910196 0.414178 0 -0.910196 0.635632 0 -0.771992 0.635632 0 -0.771992 0.791485 0 -0.611188 0.791485 0 -0.611188 0.922708 0 -0.385501 0.922708 0 -0.385501 0.985353 0 -0.170527 0.985353 0 -0.170527 0.995913 0 0.0903212 0.995913 0 0.0903212 0.950847 0 0.309661 0.950847 0 0.309661 0.8383 0 0.545209 0.8383 0 0.545209 0.695962 0 0.718079 0.695962 0 0.718079 0.486395 0 0.873739 0.486395 0 0.873739 0.373098 -0.694744 0.614921 0.395921 -0.58088 0.711214 0.492296 -0.706853 0.50794 0.630576 -0.694739 0.345993 0.761488 -0.418163 0.495253 0.673295 -0.706112 0.219271 0.708165 -0.70312 0.0642248 0.876483 -0.481054 -0.0190751 0.698951 -0.704866 -0.120962 0.654514 -0.704866 -0.273451 0.749524 -0.481047 -0.454762 0.562806 -0.703115 -0.434601 0.450096 -0.706104 -0.546654 0.409094 -0.526073 -0.74558 -0.0423388 -0.698074 -0.714773 -0.0173385 -0.60401 -0.796788 0.142385 -0.706854 -0.692881 0.295435 -0.700855 -0.649246 0.258765 0 0.96594 0.23763 0.00153755 0.971355 0.216383 0 0.976309 0.191432 0 0.981506 0.0994062 0.0288728 0.994628 0.0110001 0.000740507 0.999939 -0.111131 -0.000231543 0.993806 -0.306812 0.0220529 0.951515 -0.348088 -0.0110305 0.937397 -0.69399 0.0118253 0.719888 -0.704435 0 0.709768 -0.705437 0.705978 -0.0628816 -0.705438 0.705976 -0.0628817 -0.68906 0.706433 -0.161706 -0.561257 0.815277 -0.142524 -0.484603 0.818184 -0.309411 -0.603719 0.706452 -0.369389 -0.649974 0.705974 -0.281309 -0.649972 0.705976 -0.281308 -0.673372 0.707048 -0.215993 -0.390992 0.784984 -0.480546 -0.452633 0.706257 -0.544356 -0.528696 0.705976 -0.471253 -0.528696 0.705976 -0.471253 -0.571839 0.707041 -0.416044 -0.251775 0.705982 -0.661966 -0.251777 0.705978 -0.66197 -0.353888 0.705978 -0.613481 -0.353887 0.705979 -0.61348 -0.40727 0.707089 -0.578063 -0.227363 0.706769 -0.669913 -0.227363 0.706769 -0.669913 -0.34072 0.698977 -0.628762 -0.34072 0.698977 -0.628761 -0.570124 0.698977 -0.431728 -0.570121 0.698982 -0.431724 -0.69758 0.698983 -0.157495 -0.697584 0.698978 -0.157498 -0.187678 0.843837 -0.50271 -0.224264 0.706837 -0.670885 -0.332922 0.836181 -0.435849 -0.273064 0.706894 -0.652485 -0.323186 0.706774 -0.629302 -0.261408 0.841343 -0.473084 -0.368587 0.706946 -0.603631 -0.414692 0.706707 -0.573234 -0.45562 0.706988 -0.540905 -0.496679 0.706629 -0.50397 -0.402165 0.828 -0.390742 -0.532166 0.707023 -0.465744 -0.547413 0.707082 -0.447631 -0.633238 0.613135 -0.472309 -0.492763 0.798567 -0.345652 -0.596461 0.707056 -0.379876 -0.603459 0.707109 -0.368557 -0.628743 0.696452 -0.345885 -0.722183 0.575131 -0.384287 -0.615906 0.735248 -0.282966 -0.647036 0.707078 -0.28528 -0.670205 0.706145 -0.228438 -0.584336 0.785232 -0.204845 -0.682729 0.707091 -0.184127 -0.688319 0.70701 -0.162338 -0.862956 0.478675 -0.161796 -0.669633 0.735002 -0.106598 -0.702709 0.707107 -0.0787407 -0.70598 0.706781 -0.0453182 -0.915022 0.402236 -0.0306664 -0.707236 0.706944 0.00682287 0.285967 0.704066 0.65001 0.285966 0.704068 0.650009 0.444457 0.704068 0.553847 0.444458 0.704067 0.553848 0.572659 0.704067 0.419942 0.572659 0.704067 0.419941 0.661835 0.704067 0.257417 0.661836 0.704066 0.257417 0.705909 0.704066 0.0773506 0.705908 0.704067 0.0773506 0.701875 0.704067 -0.107988 0.701874 0.704068 -0.107988 0.650009 0.704068 -0.285966 0.65001 0.704066 -0.285967 0.553848 0.704067 -0.444458 0.553848 0.704067 -0.444458 0.419942 0.704067 -0.572659 0.419942 0.704067 -0.572659 0.257417 0.704067 -0.661835 0.257417 0.704067 -0.661835 0.0773503 0.704067 -0.705908 0.0773503 0.704067 -0.705908 -0.107988 0.704067 -0.701875 -0.107988 0.704066 -0.701876 0.195034 -2.8243e-07 0.980796 0.195034 0 0.980796 0.195034 4.40878e-08 0.980796 0.195034 0 0.980796 0.195035 4.23936e-07 0.980796 0.19504 4.25886e-06 0.980795 0.195034 -7.10992e-08 0.980797 0.195034 2.70843e-07 0.980796 0.195034 3.1081e-07 0.980796 0.19504 2.80891e-06 0.980795 0.195032 -1.38195e-06 0.980797 0.362385 1.27094e-06 0.932029 0.362385 0 0.932029 0.362385 0 0.932029 0.362385 0 0.932029 0.362385 -1.30005e-06 0.932028 0.362383 1.76061e-06 0.932029 0.362392 -5.43315e-06 0.932026 0.362379 3.75767e-06 0.932031 0.362387 -8.71403e-07 0.932028 0.362382 1.40906e-06 0.93203 0.362382 1.59959e-06 0.93203 0.195034 0 0.980796 0.195034 -3.56679e-06 0.980796 -0.999518 0 0.031058 0.362385 -4.69314e-06 0.932029 0.362385 0 0.932029 0.859726 0 -0.510755 -0.362385 3.98933e-06 -0.932029 -0.362385 0 -0.932029 -0.362385 -1.48046e-07 -0.932029 -0.362384 0 -0.932029 -0.362384 1.62506e-06 -0.932029 -0.362386 -7.82486e-07 -0.932028 -0.362392 -5.43315e-06 -0.932026 -0.362383 9.39427e-07 -0.932029 -0.36238 2.33154e-06 -0.93203 -0.362391 -2.53062e-06 -0.932026 -0.362388 -1.34526e-06 -0.932028 -0.195034 -2.8243e-07 -0.980796 -0.195034 0 -0.980796 -0.195034 5.21038e-08 -0.980796 -0.195034 0 -0.980796 -0.195035 4.23936e-07 -0.980796 -0.195021 -9.25184e-06 -0.980799 -0.195034 -7.10992e-08 -0.980797 -0.195034 2.70843e-07 -0.980796 -0.195034 3.1081e-07 -0.980796 -0.195038 1.94463e-06 -0.980796 -0.195036 6.56436e-07 -0.980796 -0.859735 0 0.510741 -0.362385 3.75452e-07 -0.932029 -0.362385 0 -0.932029 0.999518 0 -0.031058 -0.195034 0 -0.980796 -0.195034 -3.66065e-06 -0.980796 -0.710914 0.00904003 -0.703221 -0.755528 0 -0.655117 -0.404425 0 -0.914571 -0.404425 0 -0.914571 -0.98615 0 -0.165856 -0.962611 0.00728864 -0.270791 -0.925273 -0.000153472 -0.379303 -0.846109 9.32481e-05 -0.53301 0.1502 0 0.988656 -0.742549 0 0.669792 -0.666448 0.00728817 0.745516 -0.578441 0 0.815724 -0.429355 0 0.903136 -0.285318 0.00637054 0.958412 -0.22186 0 0.975079 0.1502 0 0.988656 -0.1502 0 -0.988656 0.742549 0 -0.669792 0.666446 0.0072883 -0.745518 0.578439 0 -0.815726 0.429359 0 -0.903134 0.285318 0.00637066 -0.958412 0.221859 0 -0.975079 -0.1502 0 -0.988656 0.710916 0.00903992 0.703219 0.755529 0 0.655115 0.404424 0 0.914572 0.404424 0 0.914572 0.98615 0 0.165856 0.962611 0.00728865 0.270791 0.925275 -0.000153118 0.379298 0.846104 9.35912e-05 0.533017 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + + + + + + + + + + + + + + +

21 0 0 0 17 0 18 1 1 1 10750 1 11900 2 12012 2 10763 2 2 3 10763 3 3 3 3 4 10763 4 6 4 2 5 11898 5 10763 5 10763 6 11898 6 4 6 10763 7 4 7 11900 7 10761 8 5 8 6 8 6 9 5 9 11816 9 6 10 11816 10 3 10 11711 11 10761 11 10758 11 11711 12 7 12 10761 12 10761 13 7 13 8 13 10761 14 8 14 5 14 11 15 11879 15 12 15 9 16 11882 16 10759 16 10759 17 11882 17 11886 17 10759 18 11886 18 10758 18 10758 19 11886 19 10 19 10758 20 10 20 11711 20 11 21 12 21 10759 21 10759 22 12 22 44 22 10759 23 44 23 9 23 11879 24 11 24 11861 24 11861 25 11 25 13 25 11861 26 13 26 11862 26 18 27 14 27 1 27 1 28 14 28 15 28 1 29 15 29 13 29 13 30 15 30 16 30 13 31 16 31 11862 31 0 32 11972 32 17 32 17 33 11972 33 25 33 17 34 25 34 10750 34 10750 35 25 35 11974 35 10750 36 11974 36 18 36 11713 37 19 37 10748 37 10748 38 19 38 17 38 17 39 19 39 20 39 17 40 20 40 21 40 11956 41 11954 41 23 41 23 42 11954 42 126 42 23 43 126 43 10748 43 10748 44 126 44 22 44 10748 45 22 45 11713 45 633 46 11992 46 11958 46 633 47 11958 47 23 47 23 48 11958 48 11957 48 23 49 11957 49 11956 49 11972 50 11971 50 24 50 24 51 11971 51 11970 51 24 52 11970 52 132 52 11972 53 24 53 25 53 25 54 24 54 26 54 25 55 26 55 11973 55 11973 56 26 56 27 56 11973 57 27 57 11975 57 11975 58 27 58 29 58 11975 59 29 59 28 59 28 60 29 60 129 60 28 61 129 61 30 61 30 62 129 62 11991 62 30 63 11991 63 11978 63 14 64 11980 64 31 64 31 65 11980 65 32 65 31 66 32 66 209 66 209 67 32 67 11979 67 209 68 11979 68 11708 68 14 69 31 69 15 69 15 70 31 70 33 70 15 71 33 71 34 71 34 72 33 72 208 72 34 73 208 73 35 73 35 74 208 74 36 74 35 75 36 75 11876 75 11876 76 36 76 37 76 11876 77 37 77 38 77 11873 78 214 78 213 78 11873 79 213 79 11878 79 11878 80 213 80 40 80 11878 81 40 81 39 81 39 82 40 82 41 82 39 83 41 83 42 83 42 84 41 84 12 84 12 85 41 85 43 85 12 86 43 86 44 86 44 87 43 87 11880 87 11880 88 43 88 45 88 11880 89 45 89 46 89 46 90 45 90 47 90 46 91 47 91 48 91 11689 92 50 92 11890 92 11890 93 50 93 49 93 50 94 51 94 49 94 49 95 51 95 52 95 49 96 52 96 11887 96 11887 97 52 97 219 97 11887 98 219 98 11888 98 11888 99 219 99 57 99 11697 100 11896 100 53 100 53 101 11896 101 11895 101 53 102 11895 102 216 102 216 103 11895 103 7 103 216 104 7 104 217 104 217 105 7 105 11711 105 217 106 11711 106 218 106 218 107 11711 107 54 107 218 108 54 108 55 108 55 109 54 109 11888 109 55 110 11888 110 56 110 56 111 11888 111 57 111 11422 112 225 112 58 112 58 113 225 113 60 113 225 114 59 114 60 114 60 115 59 115 61 115 60 116 61 116 11814 116 11814 117 61 117 62 117 11814 118 62 118 63 118 63 119 62 119 64 119 64 120 65 120 63 120 63 121 65 121 224 121 63 122 224 122 11813 122 224 123 66 123 11813 123 11813 124 66 124 222 124 11813 125 222 125 11812 125 11812 126 222 126 67 126 11812 127 67 127 2 127 2 128 67 128 221 128 2 129 221 129 11898 129 11898 130 221 130 68 130 11898 131 68 131 11897 131 11676 132 11899 132 71 132 71 133 11899 133 11901 133 75 134 69 134 11901 134 11901 135 69 135 70 135 11901 136 70 136 71 136 72 137 73 137 11842 137 11842 138 73 138 74 138 11842 139 74 139 75 139 75 140 74 140 76 140 75 141 76 141 69 141 72 142 11842 142 77 142 77 143 11842 143 11844 143 77 144 11844 144 78 144 78 145 11844 145 81 145 78 146 81 146 79 146 79 147 81 147 80 147 80 148 81 148 11681 148 80 149 11681 149 230 149 82 150 11903 150 11906 150 82 151 11906 151 84 151 84 152 11906 152 83 152 84 153 83 153 233 153 233 154 83 154 11905 154 233 155 11905 155 235 155 235 156 11905 156 85 156 235 157 85 157 86 157 86 158 85 158 87 158 86 159 87 159 237 159 237 160 87 160 88 160 237 161 88 161 89 161 89 162 88 162 11741 162 89 163 11741 163 11675 163 11404 164 11913 164 11912 164 11404 165 11912 165 90 165 90 166 11912 166 11909 166 90 167 11909 167 91 167 91 168 11909 168 241 168 241 169 11909 169 11855 169 241 170 11855 170 92 170 92 171 11855 171 242 171 242 172 11855 172 93 172 242 173 93 173 243 173 243 174 93 174 245 174 245 175 93 175 94 175 245 176 94 176 95 176 95 177 94 177 11851 177 95 178 11851 178 247 178 247 179 11851 179 96 179 247 180 96 180 248 180 11918 181 249 181 11923 181 11923 182 249 182 97 182 11923 183 97 183 11922 183 98 184 99 184 11916 184 11916 185 99 185 251 185 11916 186 251 186 11918 186 11918 187 251 187 100 187 11918 188 100 188 249 188 98 189 11916 189 101 189 101 190 11916 190 102 190 101 191 102 191 253 191 253 192 102 192 11938 192 253 193 11938 193 103 193 103 194 11938 194 11937 194 103 195 11937 195 104 195 104 196 11937 196 11941 196 104 197 11941 197 105 197 11640 198 11641 198 106 198 106 199 11641 199 107 199 11757 200 258 200 107 200 107 201 258 201 256 201 107 202 256 202 106 202 261 203 108 203 11756 203 11756 204 108 204 260 204 11756 205 260 205 11757 205 11757 206 260 206 109 206 11757 207 109 207 258 207 261 208 11756 208 110 208 110 209 11756 209 11755 209 110 210 11755 210 263 210 263 211 11755 211 11754 211 263 212 11754 212 264 212 264 213 11754 213 111 213 111 214 11754 214 112 214 111 215 112 215 11655 215 113 216 11637 216 114 216 113 217 114 217 115 217 115 218 114 218 11949 218 115 219 11949 219 116 219 116 220 11949 220 117 220 116 221 117 221 268 221 268 222 117 222 11719 222 268 223 11719 223 118 223 118 224 11719 224 11717 224 118 225 11717 225 119 225 119 226 11717 226 11639 226 119 227 11639 227 270 227 127 228 120 228 121 228 121 229 120 229 123 229 121 230 123 230 122 230 122 231 123 231 11967 231 122 232 11967 232 124 232 124 233 11967 233 11966 233 124 234 11966 234 125 234 125 235 11966 235 126 235 125 236 126 236 11623 236 11623 237 126 237 11954 237 11623 238 11954 238 11955 238 127 239 277 239 120 239 120 240 277 240 276 240 120 241 276 241 128 241 276 242 275 242 128 242 128 243 275 243 273 243 128 244 273 244 11782 244 11782 245 273 245 274 245 11782 246 274 246 11785 246 11355 247 11991 247 129 247 11355 248 129 248 11357 248 11357 249 129 249 29 249 11357 250 29 250 11358 250 11358 251 29 251 27 251 11358 252 27 252 130 252 130 253 27 253 26 253 130 254 26 254 131 254 131 255 26 255 24 255 131 256 24 256 11361 256 11361 257 24 257 132 257 11361 258 132 258 11616 258 11338 259 11853 259 11342 259 11342 260 11853 260 11605 260 11319 261 11843 261 133 261 133 262 11843 262 134 262 133 263 134 263 287 263 287 264 134 264 135 264 287 265 135 265 11586 265 11586 266 135 266 136 266 11560 267 11808 267 137 267 137 268 11808 268 11811 268 11280 269 138 269 139 269 139 270 138 270 11866 270 139 271 11866 271 140 271 140 272 11866 272 11868 272 140 273 11868 273 141 273 141 274 11868 274 142 274 11275 275 11539 275 11255 275 11255 276 11539 276 11772 276 11251 277 11770 277 11249 277 11249 278 11770 278 143 278 11249 279 143 279 11248 279 11248 280 143 280 11747 280 11506 281 144 281 293 281 293 282 144 282 11735 282 293 283 11735 283 145 283 145 284 11735 284 11743 284 145 285 11743 285 296 285 296 286 11743 286 146 286 296 287 146 287 298 287 298 288 146 288 11744 288 298 289 11744 289 147 289 147 290 11744 290 11746 290 147 291 11746 291 300 291 300 292 11746 292 148 292 300 293 148 293 301 293 301 294 148 294 11501 294 11499 295 149 295 302 295 302 296 149 296 11934 296 302 297 11934 297 150 297 150 298 11934 298 11925 298 150 299 11925 299 305 299 305 300 11925 300 11927 300 305 301 11927 301 151 301 151 302 11927 302 153 302 151 303 153 303 152 303 152 304 153 304 154 304 152 305 154 305 307 305 307 306 154 306 155 306 307 307 155 307 308 307 308 308 155 308 11931 308 11226 309 11727 309 310 309 310 310 11727 310 11764 310 310 311 11764 311 312 311 312 312 11764 312 156 312 312 313 156 313 314 313 314 314 156 314 157 314 314 315 157 315 316 315 316 316 157 316 11733 316 316 317 11733 317 317 317 317 318 11733 318 158 318 317 319 158 319 318 319 318 320 158 320 11732 320 318 321 11732 321 11215 321 11215 322 11732 322 159 322 319 323 11490 323 320 323 320 324 11490 324 160 324 320 325 160 325 321 325 321 326 160 326 161 326 321 327 161 327 323 327 323 328 161 328 11720 328 323 329 11720 329 325 329 325 330 11720 330 162 330 325 331 162 331 327 331 327 332 162 332 11718 332 327 333 11718 333 329 333 329 334 11718 334 11487 334 11479 335 11478 335 332 335 332 336 11478 336 163 336 332 337 163 337 164 337 164 338 163 338 165 338 164 339 165 339 166 339 166 340 165 340 11712 340 166 341 11712 341 167 341 167 342 11712 342 11716 342 167 343 11716 343 168 343 168 344 11716 344 11715 344 168 345 11715 345 11485 345 11485 346 11715 346 11714 346 11191 347 11477 347 338 347 338 348 11477 348 169 348 338 349 169 349 339 349 339 350 169 350 170 350 339 351 170 351 341 351 341 352 170 352 171 352 341 353 171 353 172 353 172 354 171 354 173 354 172 355 173 355 342 355 342 356 173 356 11859 356 342 357 11859 357 344 357 344 358 11859 358 11872 358 344 359 11872 359 11470 359 11470 360 11872 360 11874 360 175 361 11885 361 174 361 174 362 352 362 175 362 175 363 352 363 353 363 175 364 353 364 178 364 353 365 176 365 178 365 178 366 176 366 177 366 178 367 177 367 11889 367 11889 368 177 368 179 368 11889 369 179 369 180 369 179 370 349 370 180 370 180 371 349 371 346 371 180 372 346 372 181 372 346 373 182 373 181 373 181 374 182 374 183 374 181 375 183 375 11884 375 184 376 186 376 185 376 185 377 186 377 11884 377 185 378 11884 378 187 378 187 379 11884 379 183 379 11462 380 188 380 356 380 356 381 188 381 189 381 356 382 189 382 190 382 190 383 189 383 11819 383 190 384 11819 384 191 384 191 385 11819 385 192 385 191 386 192 386 194 386 194 387 192 387 193 387 194 388 193 388 360 388 360 389 193 389 195 389 360 390 195 390 11172 390 11172 391 195 391 11456 391 196 392 197 392 198 392 198 393 197 393 11835 393 198 394 11835 394 366 394 366 395 11835 395 200 395 366 396 200 396 199 396 199 397 200 397 11836 397 199 398 11836 398 201 398 201 399 11836 399 11837 399 201 400 11837 400 368 400 368 401 11837 401 203 401 368 402 203 402 202 402 202 403 203 403 205 403 202 404 205 404 204 404 204 405 205 405 206 405 11163 406 37 406 36 406 11163 407 36 407 11162 407 11162 408 36 408 208 408 11162 409 208 409 207 409 207 410 208 410 33 410 207 411 33 411 11161 411 11161 412 33 412 31 412 11161 413 31 413 11159 413 11159 414 31 414 209 414 11159 415 209 415 210 415 210 416 209 416 11708 416 210 417 11708 417 11445 417 11146 418 47 418 45 418 11146 419 45 419 211 419 211 420 45 420 43 420 211 421 43 421 212 421 212 422 43 422 41 422 212 423 41 423 11141 423 11141 424 41 424 40 424 11141 425 40 425 11154 425 11154 426 40 426 213 426 11154 427 213 427 11152 427 11152 428 213 428 214 428 11152 429 214 429 11151 429 11437 430 11697 430 53 430 11437 431 53 431 215 431 215 432 53 432 216 432 215 433 216 433 11139 433 216 434 217 434 11139 434 11139 435 217 435 218 435 11139 436 218 436 11127 436 218 437 55 437 11127 437 11127 438 55 438 56 438 11127 439 56 439 11128 439 11128 440 56 440 57 440 11128 441 57 441 11129 441 57 442 219 442 11129 442 11129 443 219 443 52 443 11129 444 52 444 11130 444 11130 445 52 445 51 445 51 446 50 446 11130 446 11130 447 50 447 11689 447 11130 448 11689 448 11132 448 220 449 68 449 221 449 220 450 221 450 11114 450 11114 451 221 451 67 451 11114 452 67 452 11116 452 67 453 222 453 11116 453 11116 454 222 454 66 454 11116 455 66 455 223 455 66 456 224 456 223 456 223 457 224 457 65 457 223 458 65 458 11117 458 11117 459 65 459 64 459 11117 460 64 460 11118 460 64 461 62 461 11118 461 11118 462 62 462 61 462 11118 463 61 463 11119 463 11119 464 61 464 59 464 59 465 225 465 11119 465 11119 466 225 466 11422 466 11119 467 11422 467 11120 467 11421 468 11676 468 71 468 11421 469 71 469 226 469 226 470 71 470 70 470 226 471 70 471 11110 471 70 472 69 472 11110 472 11110 473 69 473 76 473 11110 474 76 474 11112 474 11112 475 76 475 74 475 11112 476 74 476 227 476 74 477 73 477 227 477 227 478 73 478 72 478 227 479 72 479 228 479 72 480 77 480 228 480 228 481 77 481 78 481 228 482 78 482 229 482 229 483 78 483 79 483 79 484 80 484 229 484 229 485 80 485 230 485 229 486 230 486 11412 486 231 487 82 487 84 487 231 488 84 488 232 488 232 489 84 489 233 489 232 490 233 490 234 490 234 491 233 491 235 491 234 492 235 492 236 492 236 493 235 493 86 493 236 494 86 494 11096 494 11096 495 86 495 237 495 11096 496 237 496 238 496 238 497 237 497 89 497 238 498 89 498 239 498 239 499 89 499 11675 499 239 500 11675 500 11098 500 11088 501 240 501 90 501 90 502 240 502 11086 502 90 503 11086 503 11404 503 90 504 91 504 11088 504 11088 505 91 505 241 505 11088 506 241 506 244 506 244 507 241 507 92 507 92 508 242 508 244 508 244 509 242 509 243 509 244 510 243 510 246 510 243 511 245 511 246 511 246 512 245 512 95 512 246 513 95 513 11090 513 95 514 247 514 11090 514 11090 515 247 515 248 515 11090 516 248 516 11091 516 11078 517 11077 517 249 517 249 518 11077 518 250 518 249 519 250 519 97 519 249 520 100 520 11078 520 11078 521 100 521 251 521 11078 522 251 522 252 522 252 523 251 523 99 523 99 524 98 524 252 524 252 525 98 525 101 525 252 526 101 526 254 526 101 527 253 527 254 527 254 528 253 528 103 528 254 529 103 529 11082 529 103 530 104 530 11082 530 11082 531 104 531 105 531 11082 532 105 532 11385 532 255 533 11640 533 106 533 255 534 106 534 11062 534 11062 535 106 535 256 535 11062 536 256 536 257 536 256 537 258 537 257 537 257 538 258 538 109 538 257 539 109 539 259 539 259 540 109 540 260 540 259 541 260 541 11064 541 260 542 108 542 11064 542 11064 543 108 543 261 543 11064 544 261 544 262 544 261 545 110 545 262 545 262 546 110 546 263 546 262 547 263 547 265 547 265 548 263 548 264 548 264 549 111 549 265 549 265 550 111 550 11655 550 265 551 11655 551 11067 551 11055 552 113 552 115 552 11055 553 115 553 266 553 266 554 115 554 116 554 266 555 116 555 267 555 267 556 116 556 268 556 267 557 268 557 11057 557 11057 558 268 558 118 558 11057 559 118 559 11058 559 11058 560 118 560 119 560 11058 561 119 561 269 561 269 562 119 562 270 562 269 563 270 563 11374 563 271 564 272 564 273 564 273 565 272 565 11046 565 273 566 11046 566 274 566 273 567 275 567 271 567 271 568 275 568 276 568 271 569 276 569 278 569 278 570 276 570 277 570 277 571 127 571 278 571 278 572 127 572 121 572 278 573 121 573 11048 573 121 574 122 574 11048 574 11048 575 122 575 124 575 11048 576 124 576 279 576 124 577 125 577 279 577 279 578 125 578 11623 578 279 579 11623 579 11049 579 280 580 11338 580 281 580 281 581 11338 581 11342 581 283 582 11329 582 282 582 283 583 282 583 284 583 284 584 282 584 285 584 284 585 285 585 11325 585 11318 586 11319 586 286 586 286 587 11319 587 133 587 286 588 133 588 11024 588 11024 589 133 589 287 589 11024 590 287 590 11026 590 11026 591 287 591 11586 591 288 592 11309 592 289 592 289 593 11309 593 11304 593 289 594 11304 594 11573 594 11012 595 11560 595 11013 595 11013 596 11560 596 137 596 11001 597 11280 597 290 597 290 598 11280 598 139 598 290 599 139 599 291 599 291 600 139 600 140 600 291 601 140 601 292 601 292 602 140 602 141 602 383 603 11506 603 384 603 384 604 11506 604 293 604 384 605 293 605 294 605 294 606 293 606 145 606 294 607 145 607 295 607 295 608 145 608 296 608 295 609 296 609 385 609 385 610 296 610 298 610 385 611 298 611 297 611 297 612 298 612 147 612 297 613 147 613 299 613 299 614 147 614 300 614 299 615 300 615 10972 615 10972 616 300 616 301 616 387 617 11499 617 303 617 303 618 11499 618 302 618 303 619 302 619 388 619 388 620 302 620 150 620 388 621 150 621 304 621 304 622 150 622 305 622 304 623 305 623 306 623 306 624 305 624 151 624 306 625 151 625 392 625 392 626 151 626 152 626 392 627 152 627 390 627 390 628 152 628 307 628 390 629 307 629 391 629 391 630 307 630 308 630 309 631 11226 631 310 631 309 632 310 632 311 632 311 633 310 633 312 633 311 634 312 634 398 634 398 635 312 635 313 635 313 636 312 636 314 636 313 637 314 637 397 637 397 638 314 638 393 638 393 639 314 639 316 639 393 640 316 640 315 640 315 641 316 641 395 641 395 642 316 642 317 642 395 643 317 643 396 643 396 644 317 644 318 644 396 645 318 645 394 645 394 646 318 646 11215 646 394 647 11215 647 11214 647 400 648 319 648 406 648 406 649 319 649 320 649 406 650 320 650 407 650 407 651 320 651 404 651 404 652 320 652 321 652 404 653 321 653 405 653 405 654 321 654 322 654 322 655 321 655 323 655 322 656 323 656 401 656 401 657 323 657 402 657 402 658 323 658 325 658 402 659 325 659 324 659 324 660 325 660 326 660 326 661 325 661 327 661 326 662 327 662 403 662 403 663 327 663 328 663 328 664 327 664 329 664 328 665 329 665 330 665 10953 666 11479 666 414 666 414 667 11479 667 332 667 414 668 332 668 331 668 331 669 332 669 412 669 412 670 332 670 164 670 412 671 164 671 408 671 408 672 164 672 333 672 333 673 164 673 166 673 333 674 166 674 409 674 409 675 166 675 334 675 334 676 166 676 167 676 334 677 167 677 411 677 411 678 167 678 335 678 335 679 167 679 168 679 335 680 168 680 410 680 410 681 168 681 336 681 336 682 168 682 11485 682 336 683 11485 683 10957 683 11190 684 11191 684 337 684 337 685 11191 685 338 685 337 686 338 686 416 686 416 687 338 687 339 687 416 688 339 688 340 688 340 689 339 689 341 689 340 690 341 690 415 690 415 691 341 691 172 691 415 692 172 692 418 692 418 693 172 693 342 693 418 694 342 694 343 694 343 695 342 695 344 695 343 696 344 696 10949 696 10949 697 344 697 11470 697 184 698 185 698 11188 698 11188 699 185 699 345 699 185 700 187 700 345 700 345 701 187 701 183 701 345 702 183 702 347 702 183 703 182 703 347 703 347 704 182 704 346 704 347 705 346 705 348 705 346 706 349 706 348 706 348 707 349 707 179 707 348 708 179 708 350 708 179 709 177 709 350 709 350 710 177 710 176 710 350 711 176 711 351 711 174 712 419 712 352 712 352 713 419 713 351 713 352 714 351 714 353 714 353 715 351 715 176 715 11179 716 11462 716 354 716 354 717 11462 717 356 717 354 718 356 718 355 718 355 719 356 719 423 719 423 720 356 720 190 720 423 721 190 721 357 721 357 722 190 722 358 722 358 723 190 723 191 723 358 724 191 724 422 724 422 725 191 725 421 725 421 726 191 726 194 726 421 727 194 727 420 727 420 728 194 728 359 728 359 729 194 729 360 729 359 730 360 730 361 730 361 731 360 731 362 731 362 732 360 732 11172 732 362 733 11172 733 11171 733 363 734 196 734 364 734 364 735 196 735 198 735 364 736 198 736 365 736 365 737 198 737 366 737 365 738 366 738 424 738 424 739 366 739 199 739 424 740 199 740 367 740 367 741 199 741 201 741 367 742 201 742 425 742 425 743 201 743 368 743 425 744 368 744 369 744 369 745 368 745 202 745 369 746 202 746 370 746 370 747 202 747 204 747 372 748 11039 748 11037 748 11037 749 371 749 372 749 372 750 371 750 373 750 372 751 373 751 374 751 373 752 511 752 374 752 374 753 511 753 375 753 374 754 375 754 11352 754 11352 755 375 755 376 755 11352 756 376 756 377 756 376 757 510 757 377 757 377 758 510 758 378 758 377 759 378 759 379 759 378 760 508 760 379 760 379 761 508 761 380 761 379 762 380 762 382 762 10864 763 11360 763 381 763 381 764 11360 764 382 764 381 765 382 765 507 765 507 766 382 766 380 766 386 767 383 767 384 767 386 768 295 768 385 768 294 769 295 769 386 769 384 770 294 770 386 770 386 771 299 771 10972 771 297 772 299 772 386 772 385 773 297 773 386 773 389 774 387 774 303 774 389 775 304 775 306 775 388 776 304 776 389 776 303 777 388 777 389 777 389 778 390 778 391 778 392 779 390 779 389 779 306 780 392 780 389 780 399 781 309 781 311 781 398 782 313 782 399 782 397 783 393 783 399 783 315 784 395 784 399 784 399 785 394 785 11214 785 396 786 394 786 399 786 395 787 396 787 399 787 393 788 315 788 399 788 313 789 397 789 399 789 311 790 398 790 399 790 10959 791 400 791 406 791 407 792 404 792 10959 792 405 793 322 793 10959 793 401 794 402 794 10959 794 324 795 326 795 10959 795 10959 796 328 796 330 796 403 797 328 797 10959 797 326 798 403 798 10959 798 402 799 324 799 10959 799 322 800 401 800 10959 800 404 801 405 801 10959 801 406 802 407 802 10959 802 413 803 10953 803 414 803 331 804 412 804 413 804 408 805 333 805 413 805 409 806 334 806 413 806 411 807 335 807 413 807 413 808 336 808 10957 808 410 809 336 809 413 809 335 810 410 810 413 810 334 811 411 811 413 811 333 812 409 812 413 812 412 813 408 813 413 813 414 814 331 814 413 814 417 815 11190 815 337 815 417 816 340 816 415 816 416 817 340 817 417 817 337 818 416 818 417 818 417 819 343 819 10949 819 418 820 343 820 417 820 415 821 418 821 417 821 10943 822 347 822 348 822 345 823 347 823 10943 823 11188 824 345 824 10943 824 10943 825 351 825 419 825 350 826 351 826 10943 826 348 827 350 827 10943 827 10940 828 11179 828 354 828 355 829 423 829 10940 829 357 830 358 830 10940 830 422 831 421 831 10940 831 420 832 359 832 10940 832 10940 833 362 833 11171 833 361 834 362 834 10940 834 359 835 361 835 10940 835 421 836 420 836 10940 836 358 837 422 837 10940 837 423 838 357 838 10940 838 354 839 355 839 10940 839 10939 840 363 840 364 840 10939 841 424 841 367 841 365 842 424 842 10939 842 364 843 365 843 10939 843 10939 844 369 844 370 844 425 845 369 845 10939 845 367 846 425 846 10939 846 516 847 426 847 517 847 517 848 426 848 11158 848 517 849 11158 849 427 849 427 850 11158 850 11156 850 427 851 11156 851 428 851 428 852 11156 852 429 852 428 853 429 853 430 853 430 854 429 854 11166 854 430 855 11166 855 520 855 520 856 11166 856 431 856 520 857 431 857 522 857 522 858 431 858 432 858 522 859 432 859 10846 859 10846 860 432 860 433 860 10844 861 11150 861 434 861 434 862 11150 862 435 862 434 863 435 863 525 863 525 864 435 864 436 864 525 865 436 865 526 865 526 866 436 866 437 866 526 867 437 867 529 867 529 868 437 868 11149 868 529 869 11149 869 438 869 438 870 11149 870 11148 870 438 871 11148 871 439 871 439 872 11148 872 11147 872 531 873 11131 873 532 873 532 874 11131 874 11133 874 532 875 11133 875 440 875 440 876 11133 876 11134 876 440 877 11134 877 535 877 535 878 11134 878 11135 878 535 879 11135 879 441 879 441 880 11135 880 442 880 441 881 442 881 537 881 537 882 442 882 443 882 537 883 443 883 10829 883 10829 884 443 884 10923 884 539 885 10922 885 444 885 444 886 10922 886 11122 886 444 887 11122 887 445 887 445 888 11122 888 446 888 445 889 446 889 541 889 541 890 446 890 11123 890 541 891 11123 891 447 891 447 892 11123 892 448 892 447 893 448 893 449 893 449 894 448 894 11125 894 449 895 11125 895 450 895 450 896 11125 896 11126 896 10821 897 11101 897 451 897 451 898 11101 898 11102 898 451 899 11102 899 543 899 543 900 11102 900 11104 900 543 901 11104 901 452 901 452 902 11104 902 454 902 452 903 454 903 453 903 453 904 454 904 11106 904 453 905 11106 905 546 905 546 906 11106 906 455 906 546 907 455 907 10810 907 10810 908 455 908 10911 908 456 909 11097 909 457 909 457 910 11097 910 458 910 457 911 458 911 549 911 549 912 458 912 459 912 549 913 459 913 550 913 550 914 459 914 460 914 550 915 460 915 461 915 461 916 460 916 462 916 461 917 462 917 556 917 556 918 462 918 463 918 556 919 463 919 10802 919 10802 920 463 920 10903 920 10902 921 464 921 465 921 465 922 464 922 466 922 465 923 466 923 559 923 559 924 466 924 467 924 559 925 467 925 560 925 560 926 467 926 468 926 560 927 468 927 561 927 561 928 468 928 11094 928 561 929 11094 929 564 929 564 930 11094 930 469 930 564 931 469 931 565 931 565 932 469 932 470 932 565 933 470 933 566 933 566 934 470 934 471 934 10896 935 472 935 473 935 473 936 472 936 474 936 473 937 474 937 567 937 567 938 474 938 475 938 567 939 475 939 570 939 570 940 475 940 11071 940 570 941 11071 941 571 941 571 942 11071 942 476 942 571 943 476 943 574 943 574 944 476 944 11073 944 574 945 11073 945 576 945 576 946 11073 946 11074 946 576 947 11074 947 477 947 477 948 11074 948 10892 948 478 949 11060 949 10777 949 10777 950 479 950 478 950 478 951 479 951 578 951 478 952 578 952 480 952 578 953 579 953 480 953 480 954 579 954 481 954 480 955 481 955 482 955 481 956 483 956 482 956 482 957 483 957 485 957 482 958 485 958 484 958 484 959 485 959 582 959 484 960 582 960 11069 960 582 961 583 961 11069 961 11069 962 583 962 584 962 11069 963 584 963 11068 963 588 964 11066 964 587 964 587 965 11066 965 11068 965 587 966 11068 966 586 966 586 967 11068 967 584 967 11053 968 10873 968 10872 968 10872 969 486 969 11053 969 11053 970 486 970 599 970 11053 971 599 971 11052 971 599 972 487 972 11052 972 11052 973 487 973 596 973 11052 974 596 974 11051 974 11051 975 596 975 595 975 595 976 488 976 11051 976 11051 977 488 977 593 977 11051 978 593 978 489 978 593 979 490 979 489 979 489 980 490 980 491 980 489 981 491 981 493 981 492 982 10881 982 589 982 589 983 10881 983 493 983 589 984 493 984 591 984 591 985 493 985 491 985 11044 986 10866 986 10764 986 10764 987 608 987 11044 987 11044 988 608 988 607 988 11044 989 607 989 495 989 607 990 494 990 495 990 495 991 494 991 605 991 495 992 605 992 496 992 496 993 605 993 497 993 497 994 603 994 496 994 496 995 603 995 498 995 496 996 498 996 499 996 498 997 500 997 499 997 499 998 500 998 506 998 499 999 506 999 501 999 502 1000 504 1000 503 1000 503 1001 504 1001 501 1001 503 1002 501 1002 505 1002 505 1003 501 1003 506 1003 10864 1004 381 1004 10865 1004 10865 1005 381 1005 3973 1005 381 1006 507 1006 3973 1006 3973 1007 507 1007 380 1007 3973 1008 380 1008 509 1008 380 1009 508 1009 509 1009 509 1010 508 1010 378 1010 509 1011 378 1011 3976 1011 378 1012 510 1012 3976 1012 3976 1013 510 1013 376 1013 3976 1014 376 1014 512 1014 376 1015 375 1015 512 1015 512 1016 375 1016 511 1016 512 1017 511 1017 513 1017 11037 1018 514 1018 371 1018 371 1019 514 1019 513 1019 371 1020 513 1020 373 1020 373 1021 513 1021 511 1021 515 1022 516 1022 517 1022 515 1023 517 1023 3984 1023 3984 1024 517 1024 427 1024 3984 1025 427 1025 3985 1025 3985 1026 427 1026 3987 1026 3987 1027 427 1027 428 1027 3987 1028 428 1028 3982 1028 3982 1029 428 1029 518 1029 518 1030 428 1030 430 1030 518 1031 430 1031 3983 1031 3983 1032 430 1032 519 1032 519 1033 430 1033 520 1033 519 1034 520 1034 521 1034 521 1035 520 1035 522 1035 521 1036 522 1036 523 1036 523 1037 522 1037 10846 1037 523 1038 10846 1038 10845 1038 4136 1039 10844 1039 524 1039 524 1040 10844 1040 434 1040 524 1041 434 1041 3988 1041 3988 1042 434 1042 525 1042 3988 1043 525 1043 3989 1043 3989 1044 525 1044 526 1044 3989 1045 526 1045 527 1045 527 1046 526 1046 529 1046 527 1047 529 1047 528 1047 528 1048 529 1048 438 1048 528 1049 438 1049 530 1049 530 1050 438 1050 439 1050 4135 1051 531 1051 3991 1051 3991 1052 531 1052 532 1052 3991 1053 532 1053 533 1053 533 1054 532 1054 440 1054 533 1055 440 1055 534 1055 534 1056 440 1056 535 1056 534 1057 535 1057 3993 1057 3993 1058 535 1058 441 1058 3993 1059 441 1059 536 1059 536 1060 441 1060 537 1060 536 1061 537 1061 4129 1061 4129 1062 537 1062 10829 1062 10827 1063 539 1063 538 1063 538 1064 539 1064 444 1064 538 1065 444 1065 3996 1065 3996 1066 444 1066 445 1066 3996 1067 445 1067 540 1067 540 1068 445 1068 541 1068 540 1069 541 1069 3999 1069 3999 1070 541 1070 447 1070 3999 1071 447 1071 4000 1071 4000 1072 447 1072 449 1072 4000 1073 449 1073 4120 1073 4120 1074 449 1074 450 1074 4001 1075 10821 1075 542 1075 542 1076 10821 1076 451 1076 542 1077 451 1077 4003 1077 4003 1078 451 1078 543 1078 4003 1079 543 1079 4004 1079 4004 1080 543 1080 452 1080 4004 1081 452 1081 544 1081 544 1082 452 1082 453 1082 544 1083 453 1083 4006 1083 4006 1084 453 1084 546 1084 4006 1085 546 1085 545 1085 545 1086 546 1086 10810 1086 10809 1087 456 1087 4011 1087 4011 1088 456 1088 457 1088 4011 1089 457 1089 4013 1089 4013 1090 457 1090 547 1090 547 1091 457 1091 549 1091 547 1092 549 1092 548 1092 548 1093 549 1093 4010 1093 4010 1094 549 1094 550 1094 4010 1095 550 1095 4009 1095 4009 1096 550 1096 551 1096 551 1097 550 1097 461 1097 551 1098 461 1098 552 1098 552 1099 461 1099 553 1099 553 1100 461 1100 556 1100 553 1101 556 1101 554 1101 554 1102 556 1102 555 1102 555 1103 556 1103 10802 1103 555 1104 10802 1104 4109 1104 4014 1105 10902 1105 4015 1105 4015 1106 10902 1106 465 1106 4015 1107 465 1107 557 1107 557 1108 465 1108 559 1108 557 1109 559 1109 558 1109 558 1110 559 1110 560 1110 558 1111 560 1111 4019 1111 4019 1112 560 1112 561 1112 4019 1113 561 1113 562 1113 562 1114 561 1114 564 1114 562 1115 564 1115 563 1115 563 1116 564 1116 565 1116 563 1117 565 1117 4097 1117 4097 1118 565 1118 566 1118 4022 1119 10896 1119 473 1119 4022 1120 473 1120 4028 1120 4028 1121 473 1121 567 1121 4028 1122 567 1122 568 1122 568 1123 567 1123 569 1123 569 1124 567 1124 570 1124 569 1125 570 1125 4025 1125 4025 1126 570 1126 4027 1126 4027 1127 570 1127 571 1127 4027 1128 571 1128 572 1128 572 1129 571 1129 4024 1129 4024 1130 571 1130 574 1130 4024 1131 574 1131 573 1131 573 1132 574 1132 576 1132 573 1133 576 1133 575 1133 575 1134 576 1134 477 1134 575 1135 477 1135 10787 1135 10777 1136 10776 1136 479 1136 479 1137 10776 1137 577 1137 479 1138 577 1138 578 1138 578 1139 577 1139 4033 1139 578 1140 4033 1140 579 1140 579 1141 4033 1141 4032 1141 579 1142 4032 1142 481 1142 481 1143 4032 1143 4031 1143 481 1144 4031 1144 483 1144 483 1145 4031 1145 4035 1145 483 1146 4035 1146 485 1146 485 1147 4035 1147 580 1147 485 1148 580 1148 582 1148 582 1149 580 1149 581 1149 582 1150 581 1150 583 1150 583 1151 581 1151 585 1151 583 1152 585 1152 584 1152 584 1153 585 1153 4039 1153 584 1154 4039 1154 586 1154 586 1155 4039 1155 4038 1155 586 1156 4038 1156 587 1156 587 1157 4038 1157 4037 1157 587 1158 4037 1158 588 1158 588 1159 4037 1159 4077 1159 10774 1160 492 1160 4049 1160 4049 1161 492 1161 589 1161 4049 1162 589 1162 590 1162 590 1163 589 1163 591 1163 590 1164 591 1164 4047 1164 4047 1165 591 1165 491 1165 4047 1166 491 1166 592 1166 592 1167 491 1167 490 1167 592 1168 490 1168 594 1168 594 1169 490 1169 593 1169 594 1170 593 1170 4044 1170 4044 1171 593 1171 488 1171 4044 1172 488 1172 4042 1172 4042 1173 488 1173 595 1173 4042 1174 595 1174 597 1174 597 1175 595 1175 596 1175 597 1176 596 1176 598 1176 598 1177 596 1177 487 1177 598 1178 487 1178 4041 1178 4041 1179 487 1179 599 1179 4041 1180 599 1180 600 1180 600 1181 599 1181 486 1181 600 1182 486 1182 4040 1182 4040 1183 486 1183 10872 1183 4062 1184 502 1184 4060 1184 4060 1185 502 1185 503 1185 4060 1186 503 1186 4059 1186 4059 1187 503 1187 505 1187 4059 1188 505 1188 4057 1188 4057 1189 505 1189 506 1189 4057 1190 506 1190 4056 1190 4056 1191 506 1191 500 1191 4056 1192 500 1192 601 1192 601 1193 500 1193 498 1193 601 1194 498 1194 602 1194 602 1195 498 1195 603 1195 602 1196 603 1196 4054 1196 4054 1197 603 1197 497 1197 4054 1198 497 1198 604 1198 604 1199 497 1199 605 1199 604 1200 605 1200 606 1200 606 1201 605 1201 494 1201 606 1202 494 1202 4052 1202 4052 1203 494 1203 607 1203 4052 1204 607 1204 4050 1204 4050 1205 607 1205 608 1205 4050 1206 608 1206 609 1206 609 1207 608 1207 10764 1207 610 1208 10701 1208 628 1208 611 1209 10718 1209 12000 1209 612 1210 615 1210 613 1210 613 1211 615 1211 617 1211 10561 1212 12012 1212 614 1212 614 1213 12012 1213 615 1213 614 1214 615 1214 704 1214 704 1215 615 1215 612 1215 722 1216 616 1216 620 1216 620 1217 616 1217 618 1217 620 1218 618 1218 617 1218 617 1219 618 1219 619 1219 617 1220 619 1220 613 1220 722 1221 620 1221 723 1221 723 1222 620 1222 12006 1222 723 1223 12006 1223 10724 1223 732 1224 12005 1224 733 1224 733 1225 12005 1225 12004 1225 733 1226 12004 1226 621 1226 732 1227 10729 1227 12005 1227 12005 1228 10729 1228 10730 1228 12005 1229 10730 1229 12006 1229 12006 1230 10730 1230 10737 1230 12006 1231 10737 1231 10724 1231 12000 1232 10718 1232 12004 1232 12004 1233 10718 1233 10713 1233 12004 1234 10713 1234 621 1234 611 1235 12000 1235 638 1235 638 1236 12000 1236 11997 1236 638 1237 11997 1237 637 1237 10701 1238 622 1238 628 1238 628 1239 622 1239 646 1239 628 1240 646 1240 623 1240 623 1241 646 1241 624 1241 623 1242 624 1242 11997 1242 11997 1243 624 1243 625 1243 11997 1244 625 1244 637 1244 627 1245 626 1245 629 1245 627 1246 629 1246 628 1246 628 1247 629 1247 630 1247 628 1248 630 1248 610 1248 631 1249 652 1249 634 1249 634 1250 652 1250 10698 1250 634 1251 10698 1251 627 1251 627 1252 10698 1252 632 1252 627 1253 632 1253 626 1253 633 1254 10515 1254 634 1254 634 1255 10515 1255 635 1255 634 1256 635 1256 631 1256 636 1257 834 1257 638 1257 10495 1258 830 1258 10708 1258 10708 1259 830 1259 831 1259 10708 1260 831 1260 10709 1260 10709 1261 831 1261 636 1261 10709 1262 636 1262 637 1262 637 1263 636 1263 638 1263 837 1264 639 1264 640 1264 640 1265 639 1265 10710 1265 640 1266 10710 1266 641 1266 641 1267 10710 1267 10719 1267 641 1268 10719 1268 834 1268 834 1269 10719 1269 10717 1269 834 1270 10717 1270 638 1270 642 1271 643 1271 10208 1271 10208 1272 848 1272 642 1272 642 1273 848 1273 846 1273 642 1274 846 1274 622 1274 622 1275 846 1275 646 1275 644 1276 10703 1276 10702 1276 846 1277 645 1277 646 1277 646 1278 645 1278 845 1278 646 1279 845 1279 10702 1279 10702 1280 845 1280 647 1280 10702 1281 647 1281 644 1281 644 1282 842 1282 10703 1282 10703 1283 842 1283 840 1283 10703 1284 840 1284 648 1284 648 1285 840 1285 651 1285 648 1286 651 1286 10704 1286 10493 1287 649 1287 650 1287 650 1288 649 1288 10704 1288 650 1289 10704 1289 839 1289 839 1290 10704 1290 651 1290 631 1291 10483 1291 10203 1291 631 1292 10203 1292 652 1292 652 1293 10203 1293 653 1293 652 1294 653 1294 10699 1294 10699 1295 653 1295 861 1295 10699 1296 861 1296 655 1296 861 1297 654 1297 655 1297 655 1298 654 1298 656 1298 655 1299 656 1299 657 1299 656 1300 858 1300 657 1300 657 1301 858 1301 856 1301 657 1302 856 1302 658 1302 856 1303 855 1303 658 1303 658 1304 855 1304 853 1304 658 1305 853 1305 10524 1305 10524 1306 853 1306 852 1306 10524 1307 852 1307 660 1307 10488 1308 10536 1308 659 1308 659 1309 10536 1309 660 1309 659 1310 660 1310 661 1310 661 1311 660 1311 852 1311 662 1312 663 1312 871 1312 871 1313 663 1313 664 1313 871 1314 664 1314 665 1314 665 1315 664 1315 10518 1315 665 1316 10518 1316 666 1316 666 1317 10518 1317 667 1317 666 1318 667 1318 868 1318 868 1319 667 1319 668 1319 868 1320 668 1320 866 1320 866 1321 668 1321 669 1321 866 1322 669 1322 864 1322 864 1323 669 1323 670 1323 864 1324 670 1324 10196 1324 10196 1325 670 1325 10692 1325 10471 1326 671 1326 672 1326 672 1327 671 1327 673 1327 672 1328 673 1328 879 1328 879 1329 673 1329 10678 1329 879 1330 10678 1330 878 1330 878 1331 10678 1331 10505 1331 878 1332 10505 1332 876 1332 876 1333 10505 1333 674 1333 876 1334 674 1334 675 1334 675 1335 674 1335 10509 1335 675 1336 10509 1336 676 1336 676 1337 10509 1337 10508 1337 676 1338 10508 1338 873 1338 873 1339 10508 1339 10472 1339 10457 1340 10456 1340 677 1340 677 1341 10456 1341 10651 1341 677 1342 10651 1342 887 1342 887 1343 10651 1343 10605 1343 887 1344 10605 1344 678 1344 678 1345 10605 1345 10610 1345 678 1346 10610 1346 886 1346 886 1347 10610 1347 679 1347 886 1348 679 1348 884 1348 884 1349 679 1349 680 1349 884 1350 680 1350 681 1350 681 1351 680 1351 10676 1351 10171 1352 10656 1352 894 1352 894 1353 10656 1353 10655 1353 894 1354 10655 1354 682 1354 682 1355 10655 1355 683 1355 682 1356 683 1356 684 1356 684 1357 683 1357 685 1357 684 1358 685 1358 686 1358 686 1359 685 1359 687 1359 686 1360 687 1360 688 1360 688 1361 687 1361 689 1361 688 1362 689 1362 890 1362 890 1363 689 1363 690 1363 10436 1364 10638 1364 902 1364 902 1365 10638 1365 691 1365 902 1366 691 1366 901 1366 901 1367 691 1367 692 1367 901 1368 692 1368 693 1368 693 1369 692 1369 10580 1369 693 1370 10580 1370 694 1370 694 1371 10580 1371 695 1371 694 1372 695 1372 898 1372 898 1373 695 1373 10581 1373 898 1374 10581 1374 896 1374 896 1375 10581 1375 10582 1375 10160 1376 10631 1376 908 1376 908 1377 10631 1377 696 1377 908 1378 696 1378 697 1378 697 1379 696 1379 10593 1379 697 1380 10593 1380 698 1380 698 1381 10593 1381 699 1381 698 1382 699 1382 700 1382 700 1383 699 1383 10591 1383 700 1384 10591 1384 905 1384 905 1385 10591 1385 701 1385 905 1386 701 1386 702 1386 702 1387 701 1387 10590 1387 703 1388 10560 1388 704 1388 703 1389 704 1389 712 1389 705 1390 10157 1390 706 1390 706 1391 10157 1391 707 1391 706 1392 707 1392 708 1392 708 1393 707 1393 911 1393 708 1394 911 1394 709 1394 709 1395 911 1395 914 1395 709 1396 914 1396 10569 1396 10569 1397 914 1397 710 1397 10569 1398 710 1398 711 1398 711 1399 710 1399 712 1399 711 1400 712 1400 612 1400 612 1401 712 1401 704 1401 714 1402 10417 1402 713 1402 713 1403 917 1403 714 1403 714 1404 917 1404 716 1404 714 1405 716 1405 715 1405 716 1406 717 1406 715 1406 715 1407 717 1407 718 1407 715 1408 718 1408 719 1408 718 1409 920 1409 719 1409 719 1410 920 1410 922 1410 719 1411 922 1411 10725 1411 10725 1412 922 1412 923 1412 10725 1413 923 1413 723 1413 928 1414 10745 1414 720 1414 720 1415 10745 1415 721 1415 720 1416 721 1416 925 1416 925 1417 721 1417 722 1417 925 1418 722 1418 924 1418 924 1419 722 1419 723 1419 924 1420 723 1420 724 1420 724 1421 723 1421 923 1421 725 1422 733 1422 935 1422 935 1423 733 1423 10497 1423 935 1424 10497 1424 726 1424 726 1425 10497 1425 728 1425 726 1426 728 1426 727 1426 727 1427 728 1427 10722 1427 727 1428 10722 1428 929 1428 929 1429 10722 1429 10715 1429 10135 1430 729 1430 938 1430 938 1431 729 1431 730 1431 938 1432 730 1432 731 1432 731 1433 730 1433 10723 1433 731 1434 10723 1434 725 1434 725 1435 10723 1435 732 1435 725 1436 732 1436 733 1436 10411 1437 10600 1437 734 1437 734 1438 10600 1438 10598 1438 734 1439 10598 1439 944 1439 944 1440 10598 1440 735 1440 944 1441 735 1441 736 1441 736 1442 735 1442 10626 1442 736 1443 10626 1443 737 1443 737 1444 10626 1444 738 1444 737 1445 738 1445 942 1445 942 1446 738 1446 10627 1446 942 1447 10627 1447 941 1447 941 1448 10627 1448 10526 1448 941 1449 10526 1449 739 1449 739 1450 10526 1450 740 1450 10389 1451 10687 1451 741 1451 741 1452 10687 1452 742 1452 743 1453 744 1453 951 1453 951 1454 744 1454 745 1454 951 1455 745 1455 952 1455 952 1456 745 1456 10611 1456 952 1457 10611 1457 746 1457 746 1458 10611 1458 10367 1458 10087 1459 10602 1459 747 1459 747 1460 10602 1460 748 1460 10338 1461 749 1461 750 1461 750 1462 749 1462 10578 1462 750 1463 10578 1463 10059 1463 10059 1464 10578 1464 10579 1464 10308 1465 751 1465 955 1465 955 1466 751 1466 752 1466 753 1467 10291 1467 754 1467 754 1468 10291 1468 755 1468 754 1469 755 1469 756 1469 756 1470 755 1470 10533 1470 756 1471 10533 1471 959 1471 959 1472 10533 1472 10540 1472 10280 1473 10281 1473 757 1473 10280 1474 757 1474 758 1474 758 1475 757 1475 972 1475 758 1476 972 1476 759 1476 759 1477 972 1477 760 1477 759 1478 760 1478 761 1478 760 1479 973 1479 761 1479 761 1480 973 1480 968 1480 761 1481 968 1481 762 1481 762 1482 968 1482 967 1482 762 1483 967 1483 765 1483 765 1484 967 1484 763 1484 763 1485 964 1485 765 1485 765 1486 964 1486 764 1486 765 1487 764 1487 766 1487 766 1488 764 1488 10274 1488 766 1489 10274 1489 10574 1489 767 1490 768 1490 10731 1490 10731 1491 768 1491 1005 1491 10731 1492 1005 1492 10735 1492 10735 1493 1005 1493 769 1493 10735 1494 769 1494 10736 1494 10736 1495 769 1495 1007 1495 10736 1496 1007 1496 10738 1496 10738 1497 1007 1497 770 1497 10738 1498 770 1498 10739 1498 10739 1499 770 1499 771 1499 10739 1500 771 1500 10734 1500 10734 1501 771 1501 1009 1501 10734 1502 1009 1502 772 1502 772 1503 1009 1503 1010 1503 773 1504 774 1504 775 1504 775 1505 774 1505 776 1505 775 1506 776 1506 10716 1506 10716 1507 776 1507 1013 1507 10716 1508 1013 1508 10720 1508 10720 1509 1013 1509 1014 1509 10720 1510 1014 1510 10714 1510 10714 1511 1014 1511 1016 1511 10714 1512 1016 1512 10712 1512 10712 1513 1016 1513 1017 1513 10712 1514 1017 1514 10721 1514 10721 1515 1017 1515 777 1515 10721 1516 777 1516 778 1516 778 1517 777 1517 1019 1517 10697 1518 779 1518 1026 1518 10697 1519 1026 1519 10522 1519 10522 1520 1026 1520 1028 1520 10522 1521 1028 1521 781 1521 1028 1522 780 1522 781 1522 781 1523 780 1523 782 1523 781 1524 782 1524 10519 1524 10519 1525 782 1525 783 1525 783 1526 1024 1526 10519 1526 10519 1527 1024 1527 784 1527 10519 1528 784 1528 785 1528 784 1529 786 1529 785 1529 785 1530 786 1530 787 1530 785 1531 787 1531 790 1531 788 1532 10521 1532 789 1532 789 1533 10521 1533 790 1533 789 1534 790 1534 1021 1534 1021 1535 790 1535 787 1535 791 1536 9700 1536 792 1536 791 1537 792 1537 793 1537 793 1538 792 1538 1036 1538 793 1539 1036 1539 794 1539 794 1540 1036 1540 795 1540 794 1541 795 1541 10514 1541 795 1542 1033 1542 10514 1542 10514 1543 1033 1543 1032 1543 10514 1544 1032 1544 796 1544 796 1545 1032 1545 1031 1545 796 1546 1031 1546 797 1546 797 1547 1031 1547 1030 1547 1030 1548 1029 1548 797 1548 797 1549 1029 1549 798 1549 797 1550 798 1550 10696 1550 10696 1551 798 1551 10243 1551 10696 1552 10243 1552 10517 1552 799 1553 9693 1553 10511 1553 10511 1554 9693 1554 1037 1554 10511 1555 1037 1555 10504 1555 10504 1556 1037 1556 1039 1556 10504 1557 1039 1557 10506 1557 10506 1558 1039 1558 800 1558 10506 1559 800 1559 802 1559 802 1560 800 1560 801 1560 802 1561 801 1561 10507 1561 10507 1562 801 1562 803 1562 10507 1563 803 1563 804 1563 804 1564 803 1564 10236 1564 10666 1565 9683 1565 10668 1565 10668 1566 9683 1566 1043 1566 10668 1567 1043 1567 10669 1567 10669 1568 1043 1568 806 1568 10669 1569 806 1569 805 1569 805 1570 806 1570 807 1570 805 1571 807 1571 10665 1571 10665 1572 807 1572 808 1572 10665 1573 808 1573 809 1573 809 1574 808 1574 810 1574 809 1575 810 1575 811 1575 811 1576 810 1576 812 1576 811 1577 812 1577 10659 1577 10659 1578 812 1578 10230 1578 813 1579 1048 1579 814 1579 814 1580 1048 1580 815 1580 814 1581 815 1581 10646 1581 10646 1582 815 1582 816 1582 10646 1583 816 1583 817 1583 817 1584 816 1584 1050 1584 817 1585 1050 1585 10647 1585 10647 1586 1050 1586 818 1586 10647 1587 818 1587 10648 1587 10648 1588 818 1588 1052 1588 10648 1589 1052 1589 10650 1589 10650 1590 1052 1590 819 1590 10650 1591 819 1591 10643 1591 10643 1592 819 1592 9672 1592 10222 1593 821 1593 820 1593 820 1594 821 1594 822 1594 820 1595 822 1595 823 1595 823 1596 822 1596 824 1596 823 1597 824 1597 825 1597 825 1598 824 1598 1055 1598 825 1599 1055 1599 826 1599 826 1600 1055 1600 1057 1600 826 1601 1057 1601 827 1601 827 1602 1057 1602 828 1602 827 1603 828 1603 829 1603 829 1604 828 1604 1060 1604 829 1605 1060 1605 10216 1605 10216 1606 1060 1606 10217 1606 830 1607 9511 1607 831 1607 831 1608 9511 1608 832 1608 831 1609 832 1609 636 1609 636 1610 832 1610 833 1610 636 1611 833 1611 834 1611 834 1612 833 1612 835 1612 834 1613 835 1613 641 1613 641 1614 835 1614 1104 1614 641 1615 1104 1615 640 1615 640 1616 1104 1616 836 1616 640 1617 836 1617 837 1617 837 1618 836 1618 10209 1618 838 1619 10493 1619 1093 1619 1093 1620 10493 1620 650 1620 1093 1621 650 1621 1094 1621 1094 1622 650 1622 839 1622 1094 1623 839 1623 1095 1623 1095 1624 839 1624 651 1624 1095 1625 651 1625 1096 1625 1096 1626 651 1626 840 1626 1096 1627 840 1627 841 1627 841 1628 840 1628 842 1628 841 1629 842 1629 1098 1629 1098 1630 842 1630 644 1630 1098 1631 644 1631 843 1631 843 1632 644 1632 647 1632 843 1633 647 1633 844 1633 844 1634 647 1634 845 1634 844 1635 845 1635 1099 1635 1099 1636 845 1636 645 1636 1099 1637 645 1637 847 1637 847 1638 645 1638 846 1638 847 1639 846 1639 1100 1639 1100 1640 846 1640 848 1640 1100 1641 848 1641 849 1641 849 1642 848 1642 10208 1642 1085 1643 10488 1643 850 1643 850 1644 10488 1644 659 1644 850 1645 659 1645 851 1645 851 1646 659 1646 661 1646 851 1647 661 1647 1087 1647 1087 1648 661 1648 852 1648 1087 1649 852 1649 1088 1649 1088 1650 852 1650 853 1650 1088 1651 853 1651 854 1651 854 1652 853 1652 855 1652 854 1653 855 1653 857 1653 857 1654 855 1654 856 1654 857 1655 856 1655 1090 1655 1090 1656 856 1656 858 1656 1090 1657 858 1657 859 1657 859 1658 858 1658 656 1658 859 1659 656 1659 1091 1659 1091 1660 656 1660 654 1660 1091 1661 654 1661 860 1661 860 1662 654 1662 861 1662 860 1663 861 1663 862 1663 862 1664 861 1664 653 1664 862 1665 653 1665 863 1665 863 1666 653 1666 10203 1666 10196 1667 10197 1667 864 1667 864 1668 10197 1668 865 1668 864 1669 865 1669 866 1669 866 1670 865 1670 867 1670 866 1671 867 1671 868 1671 868 1672 867 1672 869 1672 868 1673 869 1673 666 1673 666 1674 869 1674 1083 1674 666 1675 1083 1675 665 1675 665 1676 1083 1676 870 1676 665 1677 870 1677 871 1677 871 1678 870 1678 872 1678 871 1679 872 1679 662 1679 662 1680 872 1680 10192 1680 873 1681 9544 1681 1077 1681 873 1682 1077 1682 676 1682 676 1683 1077 1683 874 1683 676 1684 874 1684 675 1684 675 1685 874 1685 875 1685 675 1686 875 1686 876 1686 875 1687 1079 1687 876 1687 876 1688 1079 1688 877 1688 876 1689 877 1689 878 1689 877 1690 1076 1690 878 1690 878 1691 1076 1691 1074 1691 878 1692 1074 1692 879 1692 1074 1693 880 1693 879 1693 879 1694 880 1694 881 1694 879 1695 881 1695 672 1695 672 1696 881 1696 882 1696 672 1697 882 1697 10471 1697 681 1698 883 1698 884 1698 884 1699 883 1699 885 1699 884 1700 885 1700 886 1700 886 1701 885 1701 1068 1701 886 1702 1068 1702 678 1702 678 1703 1068 1703 1070 1703 678 1704 1070 1704 887 1704 887 1705 1070 1705 888 1705 887 1706 888 1706 677 1706 677 1707 888 1707 889 1707 677 1708 889 1708 10457 1708 10457 1709 889 1709 10179 1709 890 1710 10177 1710 688 1710 688 1711 10177 1711 891 1711 688 1712 891 1712 686 1712 686 1713 891 1713 892 1713 686 1714 892 1714 684 1714 684 1715 892 1715 1134 1715 684 1716 1134 1716 682 1716 682 1717 1134 1717 893 1717 682 1718 893 1718 894 1718 894 1719 893 1719 895 1719 894 1720 895 1720 10171 1720 10171 1721 895 1721 1137 1721 896 1722 897 1722 898 1722 898 1723 897 1723 899 1723 898 1724 899 1724 694 1724 694 1725 899 1725 900 1725 694 1726 900 1726 693 1726 693 1727 900 1727 1130 1727 693 1728 1130 1728 901 1728 901 1729 1130 1729 1131 1729 901 1730 1131 1730 902 1730 902 1731 1131 1731 903 1731 902 1732 903 1732 10436 1732 10436 1733 903 1733 904 1733 702 1734 1120 1734 905 1734 905 1735 1120 1735 1122 1735 905 1736 1122 1736 700 1736 700 1737 1122 1737 906 1737 700 1738 906 1738 698 1738 698 1739 906 1739 907 1739 698 1740 907 1740 697 1740 697 1741 907 1741 1125 1741 697 1742 1125 1742 908 1742 908 1743 1125 1743 1128 1743 908 1744 1128 1744 10160 1744 10160 1745 1128 1745 909 1745 10157 1746 9476 1746 707 1746 707 1747 9476 1747 910 1747 707 1748 910 1748 911 1748 911 1749 910 1749 912 1749 911 1750 912 1750 914 1750 914 1751 912 1751 913 1751 914 1752 913 1752 710 1752 710 1753 913 1753 1116 1753 710 1754 1116 1754 712 1754 712 1755 1116 1755 915 1755 712 1756 915 1756 703 1756 703 1757 915 1757 10149 1757 713 1758 916 1758 917 1758 917 1759 916 1759 918 1759 917 1760 918 1760 716 1760 716 1761 918 1761 717 1761 717 1762 918 1762 919 1762 717 1763 919 1763 718 1763 718 1764 919 1764 920 1764 920 1765 919 1765 921 1765 920 1766 921 1766 922 1766 922 1767 921 1767 923 1767 923 1768 921 1768 1112 1768 923 1769 1112 1769 724 1769 724 1770 1112 1770 924 1770 924 1771 1112 1771 926 1771 924 1772 926 1772 925 1772 925 1773 926 1773 720 1773 720 1774 926 1774 927 1774 720 1775 927 1775 928 1775 929 1776 1108 1776 930 1776 929 1777 930 1777 727 1777 727 1778 930 1778 931 1778 727 1779 931 1779 726 1779 726 1780 931 1780 932 1780 726 1781 932 1781 935 1781 932 1782 933 1782 935 1782 935 1783 933 1783 934 1783 935 1784 934 1784 725 1784 934 1785 936 1785 725 1785 725 1786 936 1786 937 1786 725 1787 937 1787 731 1787 937 1788 1107 1788 731 1788 731 1789 1107 1789 939 1789 731 1790 939 1790 938 1790 938 1791 939 1791 1106 1791 938 1792 1106 1792 10135 1792 739 1793 9452 1793 941 1793 941 1794 9452 1794 940 1794 941 1795 940 1795 942 1795 942 1796 940 1796 943 1796 942 1797 943 1797 737 1797 737 1798 943 1798 9453 1798 737 1799 9453 1799 736 1799 736 1800 9453 1800 9454 1800 736 1801 9454 1801 944 1801 944 1802 9454 1802 945 1802 944 1803 945 1803 734 1803 734 1804 945 1804 946 1804 734 1805 946 1805 10411 1805 10411 1806 946 1806 947 1806 10118 1807 9647 1807 948 1807 948 1808 9647 1808 1063 1808 948 1809 1063 1809 10398 1809 9642 1810 10389 1810 949 1810 949 1811 10389 1811 741 1811 9658 1812 743 1812 950 1812 950 1813 743 1813 951 1813 950 1814 951 1814 9656 1814 9656 1815 951 1815 952 1815 9656 1816 952 1816 953 1816 953 1817 952 1817 746 1817 953 1818 746 1818 9654 1818 954 1819 10308 1819 9595 1819 9595 1820 10308 1820 955 1820 956 1821 753 1821 957 1821 957 1822 753 1822 754 1822 957 1823 754 1823 9614 1823 9614 1824 754 1824 958 1824 958 1825 754 1825 756 1825 958 1826 756 1826 9613 1826 9613 1827 756 1827 959 1827 9613 1828 959 1828 10023 1828 960 1829 961 1829 1064 1829 960 1830 1064 1830 10282 1830 10282 1831 1064 1831 962 1831 10282 1832 962 1832 10006 1832 9721 1833 10274 1833 963 1833 963 1834 10274 1834 764 1834 963 1835 764 1835 965 1835 764 1836 964 1836 965 1836 965 1837 964 1837 763 1837 965 1838 763 1838 966 1838 966 1839 763 1839 967 1839 967 1840 968 1840 966 1840 966 1841 968 1841 973 1841 966 1842 973 1842 969 1842 10281 1843 970 1843 757 1843 757 1844 970 1844 971 1844 757 1845 971 1845 972 1845 972 1846 971 1846 969 1846 972 1847 969 1847 760 1847 760 1848 969 1848 973 1848 9429 1849 10002 1849 1002 1849 9429 1850 1002 1850 9428 1850 9428 1851 1002 1851 975 1851 9428 1852 975 1852 974 1852 974 1853 975 1853 999 1853 974 1854 999 1854 976 1854 976 1855 999 1855 997 1855 976 1856 997 1856 9426 1856 9426 1857 997 1857 977 1857 9426 1858 977 1858 9436 1858 9436 1859 977 1859 991 1859 9436 1860 991 1860 9435 1860 9435 1861 991 1861 992 1861 9435 1862 992 1862 9434 1862 9434 1863 992 1863 978 1863 9434 1864 978 1864 979 1864 979 1865 978 1865 980 1865 979 1866 980 1866 9433 1866 9433 1867 980 1867 982 1867 9433 1868 982 1868 981 1868 981 1869 982 1869 988 1869 981 1870 988 1870 9443 1870 9443 1871 988 1871 987 1871 9443 1872 987 1872 983 1872 983 1873 987 1873 985 1873 983 1874 985 1874 984 1874 984 1875 985 1875 9986 1875 984 1876 9986 1876 9440 1876 986 1877 9986 1877 985 1877 986 1878 985 1878 9830 1878 9830 1879 985 1879 987 1879 9830 1880 987 1880 9837 1880 9837 1881 987 1881 9816 1881 9816 1882 987 1882 988 1882 9816 1883 988 1883 989 1883 989 1884 988 1884 9814 1884 9814 1885 988 1885 982 1885 9814 1886 982 1886 9770 1886 978 1887 9808 1887 980 1887 980 1888 9808 1888 9755 1888 980 1889 9755 1889 982 1889 982 1890 9755 1890 9768 1890 982 1891 9768 1891 9770 1891 992 1892 994 1892 978 1892 978 1893 994 1893 990 1893 978 1894 990 1894 9808 1894 997 1895 9884 1895 977 1895 977 1896 9884 1896 9885 1896 977 1897 9885 1897 991 1897 991 1898 9885 1898 9940 1898 991 1899 9940 1899 992 1899 992 1900 9940 1900 993 1900 992 1901 993 1901 994 1901 996 1902 9938 1902 997 1902 997 1903 9938 1903 995 1903 997 1904 995 1904 9884 1904 996 1905 997 1905 998 1905 998 1906 997 1906 999 1906 998 1907 999 1907 9935 1907 9935 1908 999 1908 1000 1908 1000 1909 999 1909 975 1909 1000 1910 975 1910 9866 1910 9866 1911 975 1911 1002 1911 9866 1912 1002 1912 1004 1912 10002 1913 9971 1913 1001 1913 10002 1914 1001 1914 1002 1914 1002 1915 1001 1915 1003 1915 1002 1916 1003 1916 1004 1916 768 1917 9718 1917 1005 1917 1005 1918 9718 1918 9852 1918 1005 1919 9852 1919 769 1919 769 1920 9852 1920 1006 1920 769 1921 1006 1921 1007 1921 1007 1922 1006 1922 9850 1922 1007 1923 9850 1923 770 1923 770 1924 9850 1924 1008 1924 770 1925 1008 1925 771 1925 771 1926 1008 1926 9796 1926 771 1927 9796 1927 1009 1927 1009 1928 9796 1928 1011 1928 1009 1929 1011 1929 1010 1929 1010 1930 1011 1930 9713 1930 774 1931 9748 1931 776 1931 776 1932 9748 1932 1012 1932 776 1933 1012 1933 1013 1933 1013 1934 1012 1934 1015 1934 1013 1935 1015 1935 1014 1935 1014 1936 1015 1936 9747 1936 1014 1937 9747 1937 1016 1937 1016 1938 9747 1938 1018 1938 1016 1939 1018 1939 1017 1939 1017 1940 1018 1940 9745 1940 1017 1941 9745 1941 777 1941 777 1942 9745 1942 1020 1942 777 1943 1020 1943 1019 1943 1019 1944 1020 1944 9709 1944 9859 1945 9706 1945 788 1945 788 1946 789 1946 9859 1946 9859 1947 789 1947 1021 1947 9859 1948 1021 1948 1022 1948 1021 1949 787 1949 1022 1949 1022 1950 787 1950 786 1950 1022 1951 786 1951 9788 1951 9788 1952 786 1952 784 1952 9788 1953 784 1953 1023 1953 784 1954 1024 1954 1023 1954 1023 1955 1024 1955 783 1955 1023 1956 783 1956 9791 1956 783 1957 782 1957 9791 1957 9791 1958 782 1958 780 1958 9791 1959 780 1959 1027 1959 779 1960 1025 1960 1026 1960 1026 1961 1025 1961 1027 1961 1026 1962 1027 1962 1028 1962 1028 1963 1027 1963 780 1963 9781 1964 10243 1964 9780 1964 9780 1965 10243 1965 798 1965 9780 1966 798 1966 9772 1966 798 1967 1029 1967 9772 1967 9772 1968 1029 1968 1030 1968 9772 1969 1030 1969 1034 1969 1034 1970 1030 1970 1031 1970 1031 1971 1032 1971 1034 1971 1034 1972 1032 1972 1033 1972 1034 1973 1033 1973 9773 1973 9700 1974 1035 1974 792 1974 792 1975 1035 1975 9784 1975 792 1976 9784 1976 1036 1976 1036 1977 9784 1977 9773 1977 1036 1978 9773 1978 795 1978 795 1979 9773 1979 1033 1979 9693 1980 9752 1980 1037 1980 1037 1981 9752 1981 1038 1981 1037 1982 1038 1982 1039 1982 1039 1983 1038 1983 1040 1983 1039 1984 1040 1984 800 1984 800 1985 1040 1985 9751 1985 800 1986 9751 1986 801 1986 801 1987 9751 1987 9869 1987 801 1988 9869 1988 803 1988 803 1989 9869 1989 1041 1989 803 1990 1041 1990 10236 1990 10236 1991 1041 1991 1042 1991 9683 1992 9943 1992 1043 1992 1043 1993 9943 1993 9941 1993 1043 1994 9941 1994 806 1994 806 1995 9941 1995 1044 1995 806 1996 1044 1996 807 1996 807 1997 1044 1997 1045 1997 807 1998 1045 1998 808 1998 808 1999 1045 1999 9957 1999 808 2000 9957 2000 810 2000 810 2001 9957 2001 9946 2001 810 2002 9946 2002 812 2002 812 2003 9946 2003 1046 2003 812 2004 1046 2004 10230 2004 10230 2005 1046 2005 9945 2005 1047 2006 9754 2006 9672 2006 819 2007 9812 2007 9672 2007 9672 2008 9812 2008 9769 2008 9672 2009 9769 2009 1047 2009 1048 2010 9760 2010 9759 2010 9759 2011 9757 2011 1048 2011 1048 2012 9757 2012 1049 2012 1048 2013 1049 2013 815 2013 815 2014 1049 2014 9767 2014 815 2015 9767 2015 816 2015 816 2016 9767 2016 9765 2016 816 2017 9765 2017 1050 2017 1050 2018 9765 2018 9761 2018 1050 2019 9761 2019 818 2019 818 2020 9761 2020 1051 2020 818 2021 1051 2021 1052 2021 1052 2022 1051 2022 9762 2022 1052 2023 9762 2023 819 2023 819 2024 9762 2024 9764 2024 819 2025 9764 2025 9812 2025 821 2026 1053 2026 822 2026 822 2027 1053 2027 1054 2027 822 2028 1054 2028 824 2028 824 2029 1054 2029 9824 2029 824 2030 9824 2030 1055 2030 1055 2031 9824 2031 1056 2031 1055 2032 1056 2032 1057 2032 1057 2033 1056 2033 1058 2033 1057 2034 1058 2034 828 2034 828 2035 1058 2035 1059 2035 828 2036 1059 2036 1060 2036 1060 2037 1059 2037 9833 2037 1060 2038 9833 2038 10217 2038 10217 2039 9833 2039 9835 2039 10097 2040 9651 2040 10096 2040 10096 2041 9651 2041 1061 2041 10096 2042 1061 2042 10094 2042 10094 2043 1061 2043 9933 2043 10094 2044 9933 2044 1062 2044 1062 2045 9933 2045 9652 2045 9647 2046 9921 2046 1063 2046 1063 2047 9921 2047 9627 2047 961 2048 9963 2048 1064 2048 1064 2049 9963 2049 9917 2049 1064 2050 9917 2050 962 2050 962 2051 9917 2051 9625 2051 10029 2052 9903 2052 10028 2052 10028 2053 9903 2053 9605 2053 9584 2054 9583 2054 1065 2054 1065 2055 9583 2055 10050 2055 1065 2056 10050 2056 9735 2056 9735 2057 10050 2057 10051 2057 9735 2058 10051 2058 9733 2058 9733 2059 10051 2059 1066 2059 9733 2060 1066 2060 10052 2060 10072 2061 9841 2061 10067 2061 10067 2062 9841 2062 9831 2062 883 2063 1067 2063 885 2063 885 2064 1067 2064 9882 2064 885 2065 9882 2065 1068 2065 1068 2066 9882 2066 1069 2066 1068 2067 1069 2067 1070 2067 1070 2068 1069 2068 1071 2068 1070 2069 1071 2069 888 2069 888 2070 1071 2070 1072 2070 888 2071 1072 2071 889 2071 889 2072 1072 2072 9950 2072 889 2073 9950 2073 10179 2073 10179 2074 9950 2074 9546 2074 9873 2075 9538 2075 882 2075 1076 2076 1073 2076 1075 2076 882 2077 881 2077 9873 2077 9873 2078 881 2078 880 2078 9873 2079 880 2079 1075 2079 1075 2080 880 2080 1074 2080 1075 2081 1074 2081 1076 2081 1076 2082 877 2082 1073 2082 1073 2083 877 2083 1079 2083 1073 2084 1079 2084 9876 2084 9544 2085 9877 2085 1077 2085 1077 2086 9877 2086 1078 2086 1077 2087 1078 2087 874 2087 874 2088 1078 2088 9876 2088 874 2089 9876 2089 875 2089 875 2090 9876 2090 1079 2090 10197 2091 1080 2091 865 2091 865 2092 1080 2092 1081 2092 865 2093 1081 2093 867 2093 867 2094 1081 2094 9872 2094 867 2095 9872 2095 869 2095 869 2096 9872 2096 1082 2096 869 2097 1082 2097 1083 2097 1083 2098 1082 2098 9871 2098 1083 2099 9871 2099 870 2099 870 2100 9871 2100 1084 2100 870 2101 1084 2101 872 2101 872 2102 1084 2102 9867 2102 872 2103 9867 2103 10192 2103 10192 2104 9867 2104 9868 2104 9776 2105 9520 2105 1085 2105 1085 2106 850 2106 9776 2106 9776 2107 850 2107 851 2107 9776 2108 851 2108 1086 2108 857 2109 1089 2109 9778 2109 851 2110 1087 2110 1086 2110 1086 2111 1087 2111 1088 2111 1086 2112 1088 2112 9778 2112 9778 2113 1088 2113 854 2113 9778 2114 854 2114 857 2114 857 2115 1090 2115 1089 2115 1089 2116 1090 2116 859 2116 1089 2117 859 2117 9775 2117 9775 2118 859 2118 1091 2118 9775 2119 1091 2119 9782 2119 863 2120 9528 2120 862 2120 862 2121 9528 2121 9782 2121 862 2122 9782 2122 860 2122 860 2123 9782 2123 1091 2123 1092 2124 9864 2124 838 2124 838 2125 1093 2125 1092 2125 1092 2126 1093 2126 1094 2126 1092 2127 1094 2127 9948 2127 1094 2128 1095 2128 9948 2128 9948 2129 1095 2129 1096 2129 9948 2130 1096 2130 1097 2130 1096 2131 841 2131 1097 2131 1097 2132 841 2132 1098 2132 1097 2133 1098 2133 9865 2133 1098 2134 843 2134 9865 2134 9865 2135 843 2135 844 2135 9865 2136 844 2136 9863 2136 9863 2137 844 2137 1099 2137 9863 2138 1099 2138 9862 2138 849 2139 9861 2139 1100 2139 1100 2140 9861 2140 9862 2140 1100 2141 9862 2141 847 2141 847 2142 9862 2142 1099 2142 9511 2143 9855 2143 832 2143 832 2144 9855 2144 9854 2144 832 2145 9854 2145 833 2145 833 2146 9854 2146 1101 2146 833 2147 1101 2147 835 2147 835 2148 1101 2148 1102 2148 835 2149 1102 2149 1104 2149 1104 2150 1102 2150 1103 2150 1104 2151 1103 2151 836 2151 836 2152 1103 2152 1105 2152 836 2153 1105 2153 10209 2153 10209 2154 1105 2154 9504 2154 9849 2155 9851 2155 1106 2155 936 2156 9847 2156 9848 2156 1106 2157 939 2157 9849 2157 9849 2158 939 2158 1107 2158 9849 2159 1107 2159 9848 2159 9848 2160 1107 2160 937 2160 9848 2161 937 2161 936 2161 936 2162 934 2162 9847 2162 9847 2163 934 2163 933 2163 9847 2164 933 2164 1110 2164 1108 2165 1109 2165 930 2165 930 2166 1109 2166 9844 2166 930 2167 9844 2167 931 2167 931 2168 9844 2168 1110 2168 931 2169 1110 2169 932 2169 932 2170 1110 2170 933 2170 916 2171 9799 2171 918 2171 918 2172 9799 2172 9802 2172 918 2173 9802 2173 919 2173 919 2174 9802 2174 9804 2174 919 2175 9804 2175 921 2175 921 2176 9804 2176 1111 2176 921 2177 1111 2177 1112 2177 1112 2178 1111 2178 9801 2178 1112 2179 9801 2179 926 2179 926 2180 9801 2180 1113 2180 926 2181 1113 2181 927 2181 927 2182 1113 2182 9800 2182 9476 2183 9734 2183 910 2183 910 2184 9734 2184 9732 2184 910 2185 9732 2185 912 2185 912 2186 9732 2186 1114 2186 912 2187 1114 2187 913 2187 913 2188 1114 2188 1115 2188 913 2189 1115 2189 1116 2189 1116 2190 1115 2190 1117 2190 1116 2191 1117 2191 915 2191 915 2192 1117 2192 1118 2192 915 2193 1118 2193 10149 2193 10149 2194 1118 2194 1119 2194 1120 2195 1121 2195 1122 2195 1122 2196 1121 2196 1123 2196 1122 2197 1123 2197 906 2197 906 2198 1123 2198 1124 2198 906 2199 1124 2199 907 2199 907 2200 1124 2200 1126 2200 907 2201 1126 2201 1125 2201 1125 2202 1126 2202 1127 2202 1125 2203 1127 2203 1128 2203 1128 2204 1127 2204 9840 2204 1128 2205 9840 2205 909 2205 909 2206 9840 2206 9829 2206 897 2207 9822 2207 899 2207 899 2208 9822 2208 9823 2208 899 2209 9823 2209 900 2209 900 2210 9823 2210 1129 2210 900 2211 1129 2211 1130 2211 1130 2212 1129 2212 9828 2212 1130 2213 9828 2213 1131 2213 1131 2214 9828 2214 1132 2214 1131 2215 1132 2215 903 2215 903 2216 1132 2216 9827 2216 903 2217 9827 2217 904 2217 904 2218 9827 2218 9465 2218 10177 2219 1133 2219 891 2219 891 2220 1133 2220 9806 2220 891 2221 9806 2221 892 2221 892 2222 9806 2222 9807 2222 892 2223 9807 2223 1134 2223 1134 2224 9807 2224 9965 2224 1134 2225 9965 2225 893 2225 893 2226 9965 2226 1135 2226 893 2227 1135 2227 895 2227 895 2228 1135 2228 1136 2228 895 2229 1136 2229 1137 2229 1137 2230 1136 2230 9455 2230 1138 2231 9425 2231 1140 2231 1138 2232 1140 2232 1139 2232 1139 2233 1140 2233 1157 2233 1139 2234 1157 2234 9403 2234 9403 2235 1157 2235 1159 2235 9403 2236 1159 2236 9404 2236 9404 2237 1159 2237 1160 2237 9404 2238 1160 2238 1141 2238 1141 2239 1160 2239 1142 2239 1141 2240 1142 2240 9405 2240 9405 2241 1142 2241 1162 2241 9405 2242 1162 2242 1143 2242 1143 2243 1162 2243 1144 2243 1143 2244 1144 2244 1145 2244 1145 2245 1144 2245 1164 2245 1145 2246 1164 2246 9407 2246 9407 2247 1164 2247 1147 2247 9407 2248 1147 2248 1146 2248 1146 2249 1147 2249 1148 2249 1146 2250 1148 2250 9409 2250 9409 2251 1148 2251 1165 2251 9409 2252 1165 2252 1149 2252 1149 2253 1165 2253 1166 2253 1149 2254 1166 2254 9381 2254 9381 2255 1166 2255 1150 2255 9381 2256 1150 2256 1151 2256 1151 2257 1150 2257 1153 2257 1151 2258 1153 2258 1152 2258 1152 2259 1153 2259 1154 2259 1152 2260 1154 2260 1155 2260 1155 2261 1154 2261 1170 2261 1155 2262 1170 2262 9384 2262 9425 2263 9348 2263 1156 2263 9425 2264 1156 2264 1140 2264 1140 2265 1156 2265 1189 2265 1140 2266 1189 2266 1157 2266 1157 2267 1189 2267 1158 2267 1157 2268 1158 2268 1159 2268 1159 2269 1158 2269 1188 2269 1159 2270 1188 2270 1160 2270 1160 2271 1188 2271 1186 2271 1160 2272 1186 2272 1142 2272 1142 2273 1186 2273 1161 2273 1142 2274 1161 2274 1162 2274 1162 2275 1161 2275 1163 2275 1162 2276 1163 2276 1144 2276 1144 2277 1163 2277 1182 2277 1144 2278 1182 2278 1164 2278 1164 2279 1182 2279 1179 2279 1164 2280 1179 2280 1147 2280 1147 2281 1179 2281 1177 2281 1147 2282 1177 2282 1148 2282 1148 2283 1177 2283 1175 2283 1148 2284 1175 2284 1165 2284 1165 2285 1175 2285 1174 2285 1165 2286 1174 2286 1166 2286 1166 2287 1174 2287 1172 2287 1166 2288 1172 2288 1150 2288 1150 2289 1172 2289 1167 2289 1150 2290 1167 2290 1153 2290 1153 2291 1167 2291 1168 2291 1153 2292 1168 2292 1154 2292 1154 2293 1168 2293 1169 2293 1154 2294 1169 2294 1170 2294 1171 2295 1169 2295 1168 2295 1171 2296 1168 2296 9441 2296 9441 2297 1168 2297 1167 2297 9441 2298 1167 2298 9442 2298 9442 2299 1167 2299 1172 2299 9442 2300 1172 2300 1173 2300 1173 2301 1172 2301 1174 2301 1173 2302 1174 2302 1176 2302 1176 2303 1174 2303 1175 2303 1176 2304 1175 2304 1178 2304 1178 2305 1175 2305 1177 2305 1178 2306 1177 2306 1180 2306 1180 2307 1177 2307 1179 2307 1180 2308 1179 2308 1181 2308 1181 2309 1179 2309 1182 2309 1181 2310 1182 2310 1183 2310 1183 2311 1182 2311 1163 2311 1183 2312 1163 2312 1184 2312 1184 2313 1163 2313 1161 2313 1184 2314 1161 2314 1185 2314 1185 2315 1161 2315 1186 2315 1185 2316 1186 2316 1187 2316 1187 2317 1186 2317 1188 2317 1187 2318 1188 2318 9437 2318 9437 2319 1188 2319 1158 2319 9437 2320 1158 2320 9427 2320 9427 2321 1158 2321 1189 2321 9427 2322 1189 2322 1190 2322 1190 2323 1189 2323 1156 2323 1190 2324 1156 2324 1191 2324 1191 2325 1156 2325 9348 2325 1191 2326 9348 2326 9347 2326 9346 2327 9345 2327 9400 2327 9346 2328 9400 2328 1192 2328 1192 2329 9400 2329 9401 2329 1192 2330 9401 2330 4174 2330 4174 2331 9401 2331 9402 2331 4174 2332 9402 2332 4172 2332 4172 2333 9402 2333 1193 2333 4172 2334 1193 2334 4170 2334 4170 2335 1193 2335 1194 2335 4170 2336 1194 2336 1195 2336 1195 2337 1194 2337 9406 2337 1195 2338 9406 2338 1196 2338 1196 2339 9406 2339 1197 2339 1196 2340 1197 2340 1198 2340 1198 2341 1197 2341 1200 2341 1198 2342 1200 2342 1199 2342 1199 2343 1200 2343 9408 2343 1199 2344 9408 2344 4168 2344 4168 2345 9408 2345 9380 2345 4168 2346 9380 2346 4195 2346 4195 2347 9380 2347 1201 2347 4195 2348 1201 2348 1203 2348 1203 2349 1201 2349 1202 2349 1203 2350 1202 2350 4194 2350 4194 2351 1202 2351 9382 2351 4194 2352 9382 2352 4193 2352 4193 2353 9382 2353 1204 2353 4193 2354 1204 2354 4192 2354 4192 2355 1204 2355 1205 2355 4192 2356 1205 2356 4191 2356 4191 2357 1205 2357 9383 2357 4191 2358 9383 2358 4190 2358 6394 2359 2733 2359 1206 2359 6394 2360 1206 2360 6398 2360 6398 2361 1206 2361 1207 2361 6398 2362 1207 2362 6399 2362 6399 2363 1207 2363 1208 2363 6399 2364 1208 2364 1210 2364 1210 2365 1208 2365 1209 2365 1210 2366 1209 2366 1211 2366 1211 2367 1209 2367 2736 2367 1211 2368 2736 2368 6401 2368 6401 2369 2736 2369 1212 2369 6401 2370 1212 2370 6402 2370 6402 2371 1212 2371 7925 2371 6402 2372 7925 2372 6403 2372 1213 2373 9196 2373 1214 2373 1213 2374 1214 2374 1216 2374 1216 2375 1214 2375 1215 2375 1216 2376 1215 2376 2945 2376 2945 2377 1215 2377 2754 2377 2945 2378 2754 2378 1217 2378 1217 2379 2754 2379 2753 2379 1217 2380 2753 2380 1218 2380 1218 2381 2753 2381 1219 2381 1218 2382 1219 2382 2943 2382 2943 2383 1219 2383 1221 2383 2943 2384 1221 2384 1220 2384 1220 2385 1221 2385 1222 2385 1220 2386 1222 2386 1223 2386 1223 2387 1222 2387 2750 2387 1223 2388 2750 2388 2942 2388 2942 2389 2750 2389 1224 2389 2942 2390 1224 2390 1225 2390 1225 2391 1224 2391 2748 2391 1225 2392 2748 2392 1226 2392 1226 2393 2748 2393 1227 2393 1226 2394 1227 2394 2941 2394 2941 2395 1227 2395 1228 2395 2941 2396 1228 2396 2939 2396 2939 2397 1228 2397 1229 2397 2939 2398 1229 2398 2937 2398 2937 2399 1229 2399 2744 2399 2937 2400 2744 2400 2936 2400 2936 2401 2744 2401 1230 2401 2936 2402 1230 2402 1231 2402 1231 2403 1230 2403 1232 2403 1231 2404 1232 2404 1233 2404 1233 2405 1232 2405 2741 2405 1233 2406 2741 2406 2934 2406 2934 2407 2741 2407 2740 2407 2934 2408 2740 2408 2933 2408 2933 2409 2740 2409 2738 2409 2933 2410 2738 2410 1234 2410 1235 2411 1236 2411 1237 2411 1237 2412 1236 2412 1238 2412 1238 2413 1236 2413 6421 2413 6421 2414 1236 2414 1239 2414 6421 2415 1239 2415 6710 2415 6710 2416 1239 2416 1240 2416 1240 2417 1239 2417 2894 2417 1240 2418 2894 2418 6707 2418 6707 2419 2894 2419 6700 2419 6700 2420 2894 2420 2896 2420 6700 2421 2896 2421 6698 2421 1241 2422 6460 2422 1242 2422 1242 2423 6460 2423 6448 2423 1242 2424 6448 2424 2896 2424 2896 2425 6448 2425 6422 2425 2896 2426 6422 2426 6698 2426 1243 2427 6468 2427 2898 2427 2898 2428 6468 2428 1244 2428 2898 2429 1244 2429 1242 2429 1242 2430 1244 2430 6457 2430 1242 2431 6457 2431 1241 2431 6690 2432 6691 2432 1245 2432 1245 2433 6691 2433 2898 2433 2898 2434 6691 2434 6693 2434 2898 2435 6693 2435 1243 2435 2899 2436 6440 2436 1245 2436 1245 2437 6440 2437 6430 2437 1245 2438 6430 2438 6690 2438 2901 2439 1249 2439 2900 2439 2900 2440 1249 2440 1246 2440 2900 2441 1246 2441 2899 2441 2899 2442 1246 2442 6441 2442 2899 2443 6441 2443 6440 2443 6482 2444 6480 2444 1247 2444 1247 2445 6480 2445 1248 2445 1247 2446 1248 2446 2901 2446 2901 2447 1248 2447 6681 2447 2901 2448 6681 2448 1249 2448 6482 2449 1247 2449 1250 2449 1250 2450 1247 2450 2902 2450 1250 2451 2902 2451 1252 2451 1253 2452 1251 2452 6674 2452 1253 2453 6674 2453 2902 2453 2902 2454 6674 2454 6504 2454 2902 2455 6504 2455 1252 2455 2904 2456 6486 2456 6484 2456 6484 2457 6522 2457 2904 2457 2904 2458 6522 2458 1254 2458 2904 2459 1254 2459 1253 2459 1253 2460 1254 2460 6521 2460 1253 2461 6521 2461 1251 2461 6486 2462 2904 2462 6492 2462 6492 2463 2904 2463 2906 2463 6492 2464 2906 2464 6490 2464 6490 2465 2906 2465 1255 2465 1255 2466 2906 2466 2908 2466 1255 2467 2908 2467 6667 2467 6667 2468 2908 2468 1256 2468 1256 2469 2908 2469 1257 2469 1256 2470 1257 2470 1258 2470 1258 2471 1257 2471 6656 2471 6656 2472 1257 2472 2909 2472 6656 2473 2909 2473 1259 2473 1259 2474 2909 2474 6203 2474 1259 2475 6203 2475 1260 2475 8812 2476 9122 2476 1261 2476 8812 2477 1261 2477 1262 2477 1262 2478 1261 2478 2907 2478 1262 2479 2907 2479 8814 2479 8814 2480 2907 2480 1263 2480 8814 2481 1263 2481 1264 2481 1264 2482 1263 2482 2905 2482 1264 2483 2905 2483 1265 2483 1265 2484 2905 2484 2903 2484 1265 2485 2903 2485 1266 2485 1266 2486 2903 2486 1267 2486 1266 2487 1267 2487 8817 2487 8817 2488 1267 2488 1268 2488 8817 2489 1268 2489 8819 2489 8819 2490 1268 2490 1269 2490 8819 2491 1269 2491 8820 2491 8820 2492 1269 2492 1270 2492 8820 2493 1270 2493 8821 2493 8821 2494 1270 2494 1271 2494 8821 2495 1271 2495 8789 2495 8789 2496 1271 2496 1272 2496 8789 2497 1272 2497 8791 2497 8791 2498 1272 2498 2897 2498 8791 2499 2897 2499 8792 2499 8792 2500 2897 2500 1273 2500 8792 2501 1273 2501 1274 2501 1274 2502 1273 2502 1275 2502 1274 2503 1275 2503 8794 2503 8794 2504 1275 2504 2895 2504 8794 2505 2895 2505 8795 2505 8795 2506 2895 2506 1276 2506 8795 2507 1276 2507 8796 2507 8796 2508 1276 2508 2893 2508 8796 2509 2893 2509 1277 2509 1277 2510 2893 2510 2892 2510 1277 2511 2892 2511 1278 2511 1278 2512 2892 2512 1279 2512 1278 2513 1279 2513 8798 2513 1280 2514 2910 2514 2912 2514 1280 2515 2912 2515 1281 2515 1281 2516 2912 2516 2913 2516 1281 2517 2913 2517 8733 2517 8733 2518 2913 2518 2916 2518 8733 2519 2916 2519 8735 2519 8735 2520 2916 2520 1282 2520 8735 2521 1282 2521 8736 2521 8736 2522 1282 2522 2919 2522 8736 2523 2919 2523 8737 2523 8737 2524 2919 2524 2920 2524 8737 2525 2920 2525 1283 2525 1283 2526 2920 2526 1284 2526 1283 2527 1284 2527 1285 2527 1285 2528 1284 2528 2922 2528 1285 2529 2922 2529 8739 2529 8739 2530 2922 2530 1286 2530 8739 2531 1286 2531 8741 2531 8741 2532 1286 2532 1287 2532 8741 2533 1287 2533 8742 2533 8742 2534 1287 2534 2924 2534 8742 2535 2924 2535 1288 2535 1288 2536 2924 2536 2927 2536 1288 2537 2927 2537 8744 2537 8744 2538 2927 2538 1289 2538 8744 2539 1289 2539 8745 2539 8745 2540 1289 2540 2929 2540 8745 2541 2929 2541 1290 2541 1290 2542 2929 2542 1291 2542 1290 2543 1291 2543 1292 2543 1292 2544 1291 2544 1294 2544 1292 2545 1294 2545 1293 2545 1293 2546 1294 2546 1295 2546 1293 2547 1295 2547 8749 2547 8749 2548 1295 2548 2931 2548 8749 2549 2931 2549 1296 2549 1296 2550 2931 2550 9084 2550 1296 2551 9084 2551 1297 2551 1298 2552 2932 2552 2930 2552 1298 2553 2930 2553 8719 2553 8719 2554 2930 2554 1299 2554 8719 2555 1299 2555 8720 2555 8720 2556 1299 2556 1300 2556 8720 2557 1300 2557 8722 2557 8722 2558 1300 2558 1301 2558 8722 2559 1301 2559 8725 2559 8725 2560 1301 2560 2928 2560 8725 2561 2928 2561 1302 2561 1302 2562 2928 2562 2926 2562 1302 2563 2926 2563 1303 2563 1303 2564 2926 2564 2925 2564 1303 2565 2925 2565 8726 2565 8726 2566 2925 2566 2923 2566 8726 2567 2923 2567 8728 2567 8728 2568 2923 2568 1304 2568 8728 2569 1304 2569 8685 2569 8685 2570 1304 2570 1305 2570 8685 2571 1305 2571 8686 2571 8686 2572 1305 2572 2921 2572 8686 2573 2921 2573 8687 2573 8687 2574 2921 2574 1306 2574 8687 2575 1306 2575 8689 2575 8689 2576 1306 2576 1307 2576 8689 2577 1307 2577 8691 2577 8691 2578 1307 2578 2918 2578 8691 2579 2918 2579 8693 2579 8693 2580 2918 2580 2917 2580 8693 2581 2917 2581 1308 2581 1308 2582 2917 2582 2915 2582 1308 2583 2915 2583 1309 2583 1309 2584 2915 2584 2914 2584 1309 2585 2914 2585 1310 2585 1310 2586 2914 2586 2911 2586 1310 2587 2911 2587 8694 2587 8694 2588 2911 2588 1311 2588 8694 2589 1311 2589 8696 2589 9068 2590 6248 2590 2870 2590 9068 2591 2870 2591 1312 2591 1312 2592 2870 2592 2872 2592 1312 2593 2872 2593 1313 2593 1313 2594 2872 2594 2873 2594 1313 2595 2873 2595 1314 2595 1314 2596 2873 2596 1316 2596 1314 2597 1316 2597 1315 2597 1315 2598 1316 2598 2875 2598 1315 2599 2875 2599 1317 2599 1317 2600 2875 2600 2876 2600 1317 2601 2876 2601 8640 2601 8640 2602 2876 2602 2878 2602 8640 2603 2878 2603 1318 2603 1318 2604 2878 2604 1319 2604 1318 2605 1319 2605 8641 2605 8641 2606 1319 2606 1320 2606 8641 2607 1320 2607 1321 2607 1321 2608 1320 2608 1322 2608 1321 2609 1322 2609 1323 2609 1323 2610 1322 2610 2881 2610 1323 2611 2881 2611 1324 2611 1324 2612 2881 2612 1325 2612 1324 2613 1325 2613 8642 2613 8642 2614 1325 2614 2883 2614 8642 2615 2883 2615 8643 2615 8643 2616 2883 2616 2885 2616 8643 2617 2885 2617 1326 2617 1326 2618 2885 2618 2887 2618 1326 2619 2887 2619 1327 2619 1327 2620 2887 2620 2888 2620 1327 2621 2888 2621 8648 2621 8648 2622 2888 2622 1328 2622 8648 2623 1328 2623 1329 2623 1329 2624 1328 2624 2891 2624 1329 2625 2891 2625 1330 2625 1330 2626 2891 2626 1331 2626 1330 2627 1331 2627 1332 2627 1333 2628 2890 2628 2889 2628 1333 2629 2889 2629 8591 2629 8591 2630 2889 2630 1334 2630 8591 2631 1334 2631 8593 2631 8593 2632 1334 2632 2886 2632 8593 2633 2886 2633 1335 2633 1335 2634 2886 2634 1336 2634 1335 2635 1336 2635 1337 2635 1337 2636 1336 2636 2884 2636 1337 2637 2884 2637 8595 2637 8595 2638 2884 2638 1338 2638 8595 2639 1338 2639 8596 2639 8596 2640 1338 2640 2882 2640 8596 2641 2882 2641 8599 2641 8599 2642 2882 2642 1339 2642 8599 2643 1339 2643 8600 2643 8600 2644 1339 2644 1340 2644 8600 2645 1340 2645 8602 2645 8602 2646 1340 2646 2880 2646 8602 2647 2880 2647 1341 2647 1341 2648 2880 2648 2879 2648 1341 2649 2879 2649 8603 2649 8603 2650 2879 2650 2877 2650 8603 2651 2877 2651 1342 2651 1342 2652 2877 2652 2874 2652 1342 2653 2874 2653 8606 2653 8606 2654 2874 2654 1343 2654 8606 2655 1343 2655 8607 2655 8607 2656 1343 2656 1344 2656 8607 2657 1344 2657 1345 2657 1345 2658 1344 2658 1346 2658 1345 2659 1346 2659 8608 2659 8608 2660 1346 2660 2871 2660 8608 2661 2871 2661 8610 2661 8610 2662 2871 2662 1347 2662 8610 2663 1347 2663 8611 2663 8611 2664 1347 2664 1348 2664 8611 2665 1348 2665 1349 2665 1350 2666 9040 2666 1351 2666 1350 2667 1351 2667 1352 2667 1352 2668 1351 2668 2850 2668 1352 2669 2850 2669 1353 2669 1353 2670 2850 2670 2852 2670 1353 2671 2852 2671 1354 2671 1354 2672 2852 2672 1356 2672 1354 2673 1356 2673 1355 2673 1355 2674 1356 2674 2854 2674 1355 2675 2854 2675 8546 2675 8546 2676 2854 2676 1357 2676 8546 2677 1357 2677 8547 2677 8547 2678 1357 2678 2856 2678 8547 2679 2856 2679 1358 2679 1358 2680 2856 2680 1359 2680 1358 2681 1359 2681 8548 2681 8548 2682 1359 2682 2857 2682 8548 2683 2857 2683 1360 2683 1360 2684 2857 2684 1361 2684 1360 2685 1361 2685 8552 2685 8552 2686 1361 2686 2859 2686 8552 2687 2859 2687 8553 2687 8553 2688 2859 2688 2862 2688 8553 2689 2862 2689 8555 2689 8555 2690 2862 2690 2863 2690 8555 2691 2863 2691 8556 2691 8556 2692 2863 2692 2864 2692 8556 2693 2864 2693 1363 2693 1363 2694 2864 2694 1362 2694 1363 2695 1362 2695 1364 2695 1364 2696 1362 2696 2867 2696 1364 2697 2867 2697 1365 2697 1365 2698 2867 2698 1366 2698 1365 2699 1366 2699 8559 2699 8559 2700 1366 2700 1367 2700 8559 2701 1367 2701 8561 2701 8561 2702 1367 2702 1368 2702 8561 2703 1368 2703 9019 2703 1369 2704 2869 2704 2868 2704 1369 2705 2868 2705 1371 2705 1371 2706 2868 2706 1370 2706 1371 2707 1370 2707 8522 2707 8522 2708 1370 2708 2866 2708 8522 2709 2866 2709 8523 2709 8523 2710 2866 2710 2865 2710 8523 2711 2865 2711 8524 2711 8524 2712 2865 2712 1372 2712 8524 2713 1372 2713 8527 2713 8527 2714 1372 2714 1373 2714 8527 2715 1373 2715 8528 2715 8528 2716 1373 2716 2861 2716 8528 2717 2861 2717 1374 2717 1374 2718 2861 2718 2860 2718 1374 2719 2860 2719 8530 2719 8530 2720 2860 2720 2858 2720 8530 2721 2858 2721 1376 2721 1376 2722 2858 2722 1375 2722 1376 2723 1375 2723 8532 2723 8532 2724 1375 2724 1377 2724 8532 2725 1377 2725 1378 2725 1378 2726 1377 2726 2855 2726 1378 2727 2855 2727 8534 2727 8534 2728 2855 2728 1379 2728 8534 2729 1379 2729 1380 2729 1380 2730 1379 2730 2853 2730 1380 2731 2853 2731 1381 2731 1381 2732 2853 2732 1382 2732 1381 2733 1382 2733 8500 2733 8500 2734 1382 2734 2851 2734 8500 2735 2851 2735 8502 2735 8502 2736 2851 2736 2849 2736 8502 2737 2849 2737 1383 2737 1383 2738 2849 2738 1384 2738 1383 2739 1384 2739 8505 2739 8505 2740 1384 2740 6265 2740 8505 2741 6265 2741 8506 2741 1385 2742 2828 2742 2830 2742 1385 2743 2830 2743 1386 2743 1386 2744 2830 2744 1387 2744 1386 2745 1387 2745 1388 2745 1388 2746 1387 2746 1389 2746 1388 2747 1389 2747 8450 2747 8450 2748 1389 2748 2831 2748 8450 2749 2831 2749 1390 2749 1390 2750 2831 2750 2832 2750 1390 2751 2832 2751 8451 2751 8451 2752 2832 2752 1391 2752 8451 2753 1391 2753 8452 2753 8452 2754 1391 2754 2835 2754 8452 2755 2835 2755 8454 2755 8454 2756 2835 2756 1392 2756 8454 2757 1392 2757 8456 2757 8456 2758 1392 2758 2836 2758 8456 2759 2836 2759 8457 2759 8457 2760 2836 2760 2837 2760 8457 2761 2837 2761 1393 2761 1393 2762 2837 2762 1394 2762 1393 2763 1394 2763 1395 2763 1395 2764 1394 2764 2839 2764 1395 2765 2839 2765 8458 2765 8458 2766 2839 2766 2842 2766 8458 2767 2842 2767 1396 2767 1396 2768 2842 2768 1397 2768 1396 2769 1397 2769 1398 2769 1398 2770 1397 2770 1399 2770 1398 2771 1399 2771 8461 2771 8461 2772 1399 2772 2845 2772 8461 2773 2845 2773 1400 2773 1400 2774 2845 2774 2846 2774 1400 2775 2846 2775 1401 2775 1401 2776 2846 2776 2848 2776 1401 2777 2848 2777 1402 2777 1402 2778 2848 2778 1403 2778 1402 2779 1403 2779 8982 2779 1404 2780 2847 2780 1405 2780 1404 2781 1405 2781 1406 2781 1406 2782 1405 2782 2844 2782 1406 2783 2844 2783 1407 2783 1407 2784 2844 2784 1408 2784 1407 2785 1408 2785 1409 2785 1409 2786 1408 2786 2843 2786 1409 2787 2843 2787 1410 2787 1410 2788 2843 2788 1411 2788 1410 2789 1411 2789 8436 2789 8436 2790 1411 2790 2841 2790 8436 2791 2841 2791 1412 2791 1412 2792 2841 2792 2840 2792 1412 2793 2840 2793 8438 2793 8438 2794 2840 2794 2838 2794 8438 2795 2838 2795 1413 2795 1413 2796 2838 2796 1414 2796 1413 2797 1414 2797 8409 2797 8409 2798 1414 2798 1415 2798 8409 2799 1415 2799 8412 2799 8412 2800 1415 2800 2834 2800 8412 2801 2834 2801 8413 2801 8413 2802 2834 2802 2833 2802 8413 2803 2833 2803 1416 2803 1416 2804 2833 2804 1417 2804 1416 2805 1417 2805 1418 2805 1418 2806 1417 2806 1419 2806 1418 2807 1419 2807 1421 2807 1421 2808 1419 2808 1420 2808 1421 2809 1420 2809 1422 2809 1422 2810 1420 2810 1423 2810 1422 2811 1423 2811 1425 2811 1425 2812 1423 2812 1424 2812 1425 2813 1424 2813 1426 2813 1426 2814 1424 2814 2829 2814 1426 2815 2829 2815 1427 2815 1427 2816 2829 2816 8968 2816 1427 2817 8968 2817 8418 2817 1428 2818 8966 2818 1429 2818 1428 2819 1429 2819 1430 2819 1430 2820 1429 2820 1431 2820 1430 2821 1431 2821 8374 2821 8374 2822 1431 2822 2815 2822 8374 2823 2815 2823 1432 2823 1432 2824 2815 2824 1433 2824 1432 2825 1433 2825 1434 2825 1434 2826 1433 2826 2818 2826 1434 2827 2818 2827 1435 2827 1435 2828 2818 2828 1436 2828 1435 2829 1436 2829 8376 2829 8376 2830 1436 2830 1438 2830 8376 2831 1438 2831 1437 2831 1437 2832 1438 2832 2821 2832 1437 2833 2821 2833 1439 2833 1439 2834 2821 2834 1441 2834 1439 2835 1441 2835 1440 2835 1440 2836 1441 2836 1442 2836 1440 2837 1442 2837 1443 2837 1443 2838 1442 2838 1444 2838 1443 2839 1444 2839 1445 2839 1445 2840 1444 2840 2822 2840 1445 2841 2822 2841 8381 2841 8381 2842 2822 2842 2824 2842 8381 2843 2824 2843 1446 2843 1446 2844 2824 2844 1447 2844 1446 2845 1447 2845 8382 2845 8382 2846 1447 2846 1448 2846 8382 2847 1448 2847 1450 2847 1450 2848 1448 2848 1449 2848 1450 2849 1449 2849 1451 2849 1451 2850 1449 2850 2826 2850 1451 2851 2826 2851 1452 2851 1452 2852 2826 2852 1453 2852 1452 2853 1453 2853 8384 2853 8384 2854 1453 2854 8942 2854 8384 2855 8942 2855 8386 2855 8346 2856 2827 2856 1454 2856 8346 2857 1454 2857 1455 2857 1455 2858 1454 2858 1456 2858 1455 2859 1456 2859 8349 2859 8349 2860 1456 2860 1457 2860 8349 2861 1457 2861 8350 2861 8350 2862 1457 2862 1458 2862 8350 2863 1458 2863 1459 2863 1459 2864 1458 2864 1460 2864 1459 2865 1460 2865 1461 2865 1461 2866 1460 2866 2825 2866 1461 2867 2825 2867 1462 2867 1462 2868 2825 2868 2823 2868 1462 2869 2823 2869 1463 2869 1463 2870 2823 2870 1465 2870 1463 2871 1465 2871 1464 2871 1464 2872 1465 2872 1466 2872 1464 2873 1466 2873 8318 2873 8318 2874 1466 2874 1467 2874 8318 2875 1467 2875 8319 2875 8319 2876 1467 2876 2820 2876 8319 2877 2820 2877 8321 2877 8321 2878 2820 2878 1468 2878 8321 2879 1468 2879 8322 2879 8322 2880 1468 2880 2819 2880 8322 2881 2819 2881 8323 2881 8323 2882 2819 2882 2817 2882 8323 2883 2817 2883 8325 2883 8325 2884 2817 2884 2816 2884 8325 2885 2816 2885 8326 2885 8326 2886 2816 2886 1469 2886 8326 2887 1469 2887 1470 2887 1470 2888 1469 2888 1472 2888 1470 2889 1472 2889 1471 2889 1471 2890 1472 2890 1473 2890 1471 2891 1473 2891 8329 2891 8329 2892 1473 2892 1474 2892 8329 2893 1474 2893 8330 2893 8272 2894 8920 2894 2797 2894 8272 2895 2797 2895 1475 2895 1475 2896 2797 2896 2799 2896 1475 2897 2799 2897 8275 2897 8275 2898 2799 2898 1476 2898 8275 2899 1476 2899 1477 2899 1477 2900 1476 2900 2801 2900 1477 2901 2801 2901 1478 2901 1478 2902 2801 2902 1479 2902 1478 2903 1479 2903 1480 2903 1480 2904 1479 2904 1481 2904 1480 2905 1481 2905 8279 2905 8279 2906 1481 2906 1482 2906 8279 2907 1482 2907 1483 2907 1483 2908 1482 2908 2803 2908 1483 2909 2803 2909 8282 2909 8282 2910 2803 2910 1484 2910 8282 2911 1484 2911 1485 2911 1485 2912 1484 2912 2806 2912 1485 2913 2806 2913 1486 2913 1486 2914 2806 2914 2807 2914 1486 2915 2807 2915 1487 2915 1487 2916 2807 2916 2808 2916 1487 2917 2808 2917 8284 2917 8284 2918 2808 2918 2810 2918 8284 2919 2810 2919 8287 2919 8287 2920 2810 2920 1488 2920 8287 2921 1488 2921 8288 2921 8288 2922 1488 2922 1489 2922 8288 2923 1489 2923 1490 2923 1490 2924 1489 2924 1491 2924 1490 2925 1491 2925 1492 2925 1492 2926 1491 2926 2812 2926 1492 2927 2812 2927 8290 2927 8290 2928 2812 2928 2814 2928 8290 2929 2814 2929 1493 2929 1493 2930 2814 2930 8903 2930 1493 2931 8903 2931 8292 2931 8244 2932 6301 2932 2813 2932 8244 2933 2813 2933 1495 2933 1495 2934 2813 2934 1494 2934 1495 2935 1494 2935 1496 2935 1496 2936 1494 2936 1497 2936 1496 2937 1497 2937 1498 2937 1498 2938 1497 2938 1499 2938 1498 2939 1499 2939 8247 2939 8247 2940 1499 2940 2811 2940 8247 2941 2811 2941 8248 2941 8248 2942 2811 2942 2809 2942 8248 2943 2809 2943 1500 2943 1500 2944 2809 2944 1502 2944 1500 2945 1502 2945 1501 2945 1501 2946 1502 2946 1503 2946 1501 2947 1503 2947 8250 2947 8250 2948 1503 2948 2805 2948 8250 2949 2805 2949 1504 2949 1504 2950 2805 2950 2804 2950 1504 2951 2804 2951 8253 2951 8253 2952 2804 2952 1505 2952 8253 2953 1505 2953 1506 2953 1506 2954 1505 2954 1507 2954 1506 2955 1507 2955 8254 2955 8254 2956 1507 2956 1508 2956 8254 2957 1508 2957 1509 2957 1509 2958 1508 2958 2802 2958 1509 2959 2802 2959 1510 2959 1510 2960 2802 2960 1511 2960 1510 2961 1511 2961 1512 2961 1512 2962 1511 2962 2800 2962 1512 2963 2800 2963 1513 2963 1513 2964 2800 2964 2798 2964 1513 2965 2798 2965 8225 2965 8225 2966 2798 2966 1514 2966 8225 2967 1514 2967 1515 2967 1515 2968 1514 2968 6320 2968 1515 2969 6320 2969 8227 2969 8882 2970 2781 2970 1516 2970 8882 2971 1516 2971 8168 2971 8168 2972 1516 2972 1517 2972 8168 2973 1517 2973 8170 2973 8170 2974 1517 2974 2784 2974 8170 2975 2784 2975 8171 2975 8171 2976 2784 2976 1518 2976 8171 2977 1518 2977 1519 2977 1519 2978 1518 2978 2786 2978 1519 2979 2786 2979 1520 2979 1520 2980 2786 2980 2788 2980 1520 2981 2788 2981 8174 2981 8174 2982 2788 2982 1521 2982 8174 2983 1521 2983 8175 2983 8175 2984 1521 2984 1522 2984 8175 2985 1522 2985 8177 2985 8177 2986 1522 2986 2791 2986 8177 2987 2791 2987 1523 2987 1523 2988 2791 2988 1524 2988 1523 2989 1524 2989 1525 2989 1525 2990 1524 2990 2793 2990 1525 2991 2793 2991 8180 2991 8180 2992 2793 2992 2794 2992 8180 2993 2794 2993 1526 2993 1526 2994 2794 2994 1527 2994 1526 2995 1527 2995 1528 2995 1528 2996 1527 2996 1529 2996 1528 2997 1529 2997 1530 2997 1530 2998 1529 2998 1531 2998 1530 2999 1531 2999 1532 2999 1532 3000 1531 3000 1533 3000 1532 3001 1533 3001 8184 3001 8184 3002 1533 3002 1534 3002 8184 3003 1534 3003 1535 3003 1535 3004 1534 3004 1536 3004 1535 3005 1536 3005 1537 3005 1537 3006 1536 3006 6322 3006 1537 3007 6322 3007 8860 3007 8152 3008 8859 3008 2796 3008 8152 3009 2796 3009 1538 3009 1538 3010 2796 3010 2795 3010 1538 3011 2795 3011 8155 3011 8155 3012 2795 3012 1539 3012 8155 3013 1539 3013 8156 3013 8156 3014 1539 3014 1540 3014 8156 3015 1540 3015 8157 3015 8157 3016 1540 3016 1541 3016 8157 3017 1541 3017 8159 3017 8159 3018 1541 3018 1542 3018 8159 3019 1542 3019 8160 3019 8160 3020 1542 3020 1543 3020 8160 3021 1543 3021 1544 3021 1544 3022 1543 3022 1545 3022 1544 3023 1545 3023 8161 3023 8161 3024 1545 3024 2792 3024 8161 3025 2792 3025 8162 3025 8162 3026 2792 3026 1546 3026 8162 3027 1546 3027 8163 3027 8163 3028 1546 3028 2790 3028 8163 3029 2790 3029 8164 3029 8164 3030 2790 3030 2789 3030 8164 3031 2789 3031 1547 3031 1547 3032 2789 3032 2787 3032 1547 3033 2787 3033 8125 3033 8125 3034 2787 3034 2785 3034 8125 3035 2785 3035 1548 3035 1548 3036 2785 3036 1549 3036 1548 3037 1549 3037 8126 3037 8126 3038 1549 3038 2783 3038 8126 3039 2783 3039 1550 3039 1550 3040 2783 3040 2782 3040 1550 3041 2782 3041 1551 3041 1551 3042 2782 3042 2780 3042 1551 3043 2780 3043 8130 3043 8130 3044 2780 3044 1552 3044 8130 3045 1552 3045 8844 3045 1553 3046 8843 3046 2759 3046 1553 3047 2759 3047 8086 3047 8086 3048 2759 3048 2760 3048 8086 3049 2760 3049 8089 3049 8089 3050 2760 3050 1554 3050 8089 3051 1554 3051 1555 3051 1555 3052 1554 3052 2763 3052 1555 3053 2763 3053 1556 3053 1556 3054 2763 3054 2764 3054 1556 3055 2764 3055 8092 3055 8092 3056 2764 3056 2766 3056 8092 3057 2766 3057 1557 3057 1557 3058 2766 3058 1558 3058 1557 3059 1558 3059 1559 3059 1559 3060 1558 3060 1561 3060 1559 3061 1561 3061 1560 3061 1560 3062 1561 3062 2769 3062 1560 3063 2769 3063 1562 3063 1562 3064 2769 3064 2771 3064 1562 3065 2771 3065 8095 3065 8095 3066 2771 3066 1563 3066 8095 3067 1563 3067 8096 3067 8096 3068 1563 3068 2773 3068 8096 3069 2773 3069 1564 3069 1564 3070 2773 3070 1565 3070 1564 3071 1565 3071 8100 3071 8100 3072 1565 3072 2775 3072 8100 3073 2775 3073 8061 3073 8061 3074 2775 3074 2776 3074 8061 3075 2776 3075 1566 3075 1566 3076 2776 3076 2777 3076 1566 3077 2777 3077 1567 3077 1567 3078 2777 3078 1568 3078 1567 3079 1568 3079 8064 3079 8064 3080 1568 3080 1569 3080 8064 3081 1569 3081 8066 3081 8066 3082 1569 3082 1570 3082 8066 3083 1570 3083 8822 3083 8787 3084 8786 3084 1571 3084 8787 3085 1571 3085 8797 3085 8797 3086 1571 3086 8732 3086 8797 3087 8732 3087 1572 3087 1572 3088 8732 3088 1573 3088 1572 3089 1573 3089 1574 3089 1574 3090 1573 3090 8734 3090 1574 3091 8734 3091 1576 3091 1576 3092 8734 3092 1575 3092 1576 3093 1575 3093 1577 3093 1577 3094 1575 3094 1578 3094 1577 3095 1578 3095 8793 3095 8793 3096 1578 3096 8738 3096 8793 3097 8738 3097 1579 3097 1579 3098 8738 3098 1580 3098 1579 3099 1580 3099 8790 3099 8790 3100 1580 3100 8740 3100 8790 3101 8740 3101 1581 3101 1581 3102 8740 3102 1582 3102 1581 3103 1582 3103 8788 3103 8788 3104 1582 3104 1583 3104 8788 3105 1583 3105 8818 3105 8818 3106 1583 3106 1585 3106 8818 3107 1585 3107 1584 3107 1584 3108 1585 3108 8743 3108 1584 3109 8743 3109 1586 3109 1586 3110 8743 3110 8746 3110 1586 3111 8746 3111 8816 3111 8816 3112 8746 3112 8747 3112 8816 3113 8747 3113 8815 3113 8815 3114 8747 3114 1587 3114 8815 3115 1587 3115 8813 3115 8813 3116 1587 3116 8748 3116 8813 3117 8748 3117 1588 3117 1588 3118 8748 3118 1589 3118 1588 3119 1589 3119 1590 3119 1590 3120 1589 3120 8769 3120 1590 3121 8769 3121 1591 3121 8695 3122 8635 3122 8636 3122 8695 3123 8636 3123 1593 3123 1593 3124 8636 3124 1592 3124 1593 3125 1592 3125 1594 3125 1594 3126 1592 3126 8637 3126 1594 3127 8637 3127 1595 3127 1595 3128 8637 3128 8638 3128 1595 3129 8638 3129 8692 3129 8692 3130 8638 3130 8639 3130 8692 3131 8639 3131 8690 3131 8690 3132 8639 3132 1596 3132 8690 3133 1596 3133 8688 3133 8688 3134 1596 3134 1598 3134 8688 3135 1598 3135 1597 3135 1597 3136 1598 3136 1599 3136 1597 3137 1599 3137 1601 3137 1601 3138 1599 3138 1600 3138 1601 3139 1600 3139 8684 3139 8684 3140 1600 3140 1602 3140 8684 3141 1602 3141 1603 3141 1603 3142 1602 3142 1604 3142 1603 3143 1604 3143 8727 3143 8727 3144 1604 3144 1605 3144 8727 3145 1605 3145 1606 3145 1606 3146 1605 3146 8644 3146 1606 3147 8644 3147 1607 3147 1607 3148 8644 3148 8645 3148 1607 3149 8645 3149 8724 3149 8724 3150 8645 3150 8646 3150 8724 3151 8646 3151 8723 3151 8723 3152 8646 3152 8647 3152 8723 3153 8647 3153 8721 3153 8721 3154 8647 3154 1608 3154 8721 3155 1608 3155 1610 3155 1610 3156 1608 3156 1609 3156 1610 3157 1609 3157 8718 3157 8718 3158 1609 3158 8649 3158 8718 3159 8649 3159 8717 3159 8613 3160 8588 3160 8544 3160 8613 3161 8544 3161 8612 3161 8612 3162 8544 3162 1611 3162 8612 3163 1611 3163 8609 3163 8609 3164 1611 3164 8545 3164 8609 3165 8545 3165 1612 3165 1612 3166 8545 3166 1614 3166 1612 3167 1614 3167 1613 3167 1613 3168 1614 3168 1615 3168 1613 3169 1615 3169 8605 3169 8605 3170 1615 3170 1616 3170 8605 3171 1616 3171 8604 3171 8604 3172 1616 3172 1617 3172 8604 3173 1617 3173 1618 3173 1618 3174 1617 3174 8549 3174 1618 3175 8549 3175 1619 3175 1619 3176 8549 3176 8550 3176 1619 3177 8550 3177 1620 3177 1620 3178 8550 3178 8551 3178 1620 3179 8551 3179 8601 3179 8601 3180 8551 3180 1622 3180 8601 3181 1622 3181 1621 3181 1621 3182 1622 3182 8554 3182 1621 3183 8554 3183 8598 3183 8598 3184 8554 3184 1623 3184 8598 3185 1623 3185 8597 3185 8597 3186 1623 3186 8557 3186 8597 3187 8557 3187 8594 3187 8594 3188 8557 3188 1624 3188 8594 3189 1624 3189 1625 3189 1625 3190 1624 3190 8558 3190 1625 3191 8558 3191 1626 3191 1626 3192 8558 3192 1627 3192 1626 3193 1627 3193 8592 3193 8592 3194 1627 3194 8560 3194 8592 3195 8560 3195 8590 3195 8590 3196 8560 3196 1628 3196 8590 3197 1628 3197 1629 3197 8504 3198 8446 3198 8447 3198 8504 3199 8447 3199 8503 3199 8503 3200 8447 3200 1630 3200 8503 3201 1630 3201 1631 3201 1631 3202 1630 3202 8448 3202 1631 3203 8448 3203 8501 3203 8501 3204 8448 3204 8449 3204 8501 3205 8449 3205 1633 3205 1633 3206 8449 3206 1632 3206 1633 3207 1632 3207 1634 3207 1634 3208 1632 3208 1635 3208 1634 3209 1635 3209 8499 3209 8499 3210 1635 3210 8453 3210 8499 3211 8453 3211 8533 3211 8533 3212 8453 3212 8455 3212 8533 3213 8455 3213 1637 3213 1637 3214 8455 3214 1636 3214 1637 3215 1636 3215 8531 3215 8531 3216 1636 3216 1638 3216 8531 3217 1638 3217 1639 3217 1639 3218 1638 3218 1641 3218 1639 3219 1641 3219 1640 3219 1640 3220 1641 3220 1642 3220 1640 3221 1642 3221 8529 3221 8529 3222 1642 3222 8459 3222 8529 3223 8459 3223 8526 3223 8526 3224 8459 3224 8460 3224 8526 3225 8460 3225 8525 3225 8525 3226 8460 3226 1643 3226 8525 3227 1643 3227 1644 3227 1644 3228 1643 3228 8462 3228 1644 3229 8462 3229 1645 3229 1645 3230 8462 3230 1646 3230 1645 3231 1646 3231 8521 3231 8521 3232 1646 3232 1647 3232 8521 3233 1647 3233 1648 3233 1648 3234 1647 3234 8480 3234 1648 3235 8480 3235 8479 3235 1649 3236 8371 3236 8372 3236 1649 3237 8372 3237 8417 3237 8417 3238 8372 3238 1650 3238 8417 3239 1650 3239 8416 3239 8416 3240 1650 3240 8373 3240 8416 3241 8373 3241 1651 3241 1651 3242 8373 3242 1652 3242 1651 3243 1652 3243 1653 3243 1653 3244 1652 3244 8375 3244 1653 3245 8375 3245 8415 3245 8415 3246 8375 3246 1654 3246 8415 3247 1654 3247 8414 3247 8414 3248 1654 3248 8377 3248 8414 3249 8377 3249 1655 3249 1655 3250 8377 3250 1656 3250 1655 3251 1656 3251 8411 3251 8411 3252 1656 3252 1657 3252 8411 3253 1657 3253 8410 3253 8410 3254 1657 3254 8378 3254 8410 3255 8378 3255 8439 3255 8439 3256 8378 3256 8379 3256 8439 3257 8379 3257 1658 3257 1658 3258 8379 3258 8380 3258 1658 3259 8380 3259 8437 3259 8437 3260 8380 3260 1659 3260 8437 3261 1659 3261 1661 3261 1661 3262 1659 3262 1660 3262 1661 3263 1660 3263 8435 3263 8435 3264 1660 3264 1662 3264 8435 3265 1662 3265 1663 3265 1663 3266 1662 3266 1665 3266 1663 3267 1665 3267 1664 3267 1664 3268 1665 3268 8383 3268 1664 3269 8383 3269 8434 3269 8434 3270 8383 3270 8385 3270 8434 3271 8385 3271 1667 3271 1667 3272 8385 3272 1666 3272 1667 3273 1666 3273 8433 3273 8316 3274 1668 3274 1669 3274 8316 3275 1669 3275 8328 3275 8328 3276 1669 3276 8273 3276 8328 3277 8273 3277 8327 3277 8327 3278 8273 3278 8274 3278 8327 3279 8274 3279 1670 3279 1670 3280 8274 3280 8276 3280 1670 3281 8276 3281 1671 3281 1671 3282 8276 3282 8277 3282 1671 3283 8277 3283 8324 3283 8324 3284 8277 3284 8278 3284 8324 3285 8278 3285 1672 3285 1672 3286 8278 3286 8280 3286 1672 3287 8280 3287 1673 3287 1673 3288 8280 3288 8281 3288 1673 3289 8281 3289 8320 3289 8320 3290 8281 3290 1675 3290 8320 3291 1675 3291 1674 3291 1674 3292 1675 3292 1676 3292 1674 3293 1676 3293 8317 3293 8317 3294 1676 3294 8283 3294 8317 3295 8283 3295 8355 3295 8355 3296 8283 3296 1677 3296 8355 3297 1677 3297 8354 3297 8354 3298 1677 3298 8285 3298 8354 3299 8285 3299 8353 3299 8353 3300 8285 3300 8286 3300 8353 3301 8286 3301 8352 3301 8352 3302 8286 3302 1678 3302 8352 3303 1678 3303 8351 3303 8351 3304 1678 3304 1679 3304 8351 3305 1679 3305 1681 3305 1681 3306 1679 3306 1680 3306 1681 3307 1680 3307 8348 3307 8348 3308 1680 3308 8289 3308 8348 3309 8289 3309 8347 3309 8347 3310 8289 3310 8291 3310 8347 3311 8291 3311 1682 3311 8226 3312 1683 3312 1684 3312 8226 3313 1684 3313 1685 3313 1685 3314 1684 3314 8169 3314 1685 3315 8169 3315 1686 3315 1686 3316 8169 3316 1687 3316 1686 3317 1687 3317 1688 3317 1688 3318 1687 3318 8172 3318 1688 3319 8172 3319 8224 3319 8224 3320 8172 3320 1689 3320 8224 3321 1689 3321 1690 3321 1690 3322 1689 3322 8173 3322 1690 3323 8173 3323 8223 3323 8223 3324 8173 3324 1691 3324 8223 3325 1691 3325 8222 3325 8222 3326 1691 3326 8176 3326 8222 3327 8176 3327 1692 3327 1692 3328 8176 3328 8178 3328 1692 3329 8178 3329 8252 3329 8252 3330 8178 3330 8179 3330 8252 3331 8179 3331 8251 3331 8251 3332 8179 3332 1693 3332 8251 3333 1693 3333 8249 3333 8249 3334 1693 3334 1694 3334 8249 3335 1694 3335 1695 3335 1695 3336 1694 3336 8181 3336 1695 3337 8181 3337 1696 3337 1696 3338 8181 3338 1697 3338 1696 3339 1697 3339 8246 3339 8246 3340 1697 3340 8182 3340 8246 3341 8182 3341 1698 3341 1698 3342 8182 3342 8183 3342 1698 3343 8183 3343 8245 3343 8245 3344 8183 3344 8185 3344 8245 3345 8185 3345 1699 3345 1699 3346 8185 3346 1701 3346 1699 3347 1701 3347 1700 3347 1700 3348 1701 3348 8203 3348 1700 3349 8203 3349 8243 3349 8123 3350 8084 3350 8087 3350 8123 3351 8087 3351 8129 3351 8129 3352 8087 3352 1702 3352 8129 3353 1702 3353 8128 3353 8128 3354 1702 3354 8088 3354 8128 3355 8088 3355 8127 3355 8127 3356 8088 3356 8090 3356 8127 3357 8090 3357 1703 3357 1703 3358 8090 3358 8091 3358 1703 3359 8091 3359 1704 3359 1704 3360 8091 3360 1705 3360 1704 3361 1705 3361 8124 3361 8124 3362 1705 3362 8093 3362 8124 3363 8093 3363 1706 3363 1706 3364 8093 3364 1708 3364 1706 3365 1708 3365 1707 3365 1707 3366 1708 3366 8094 3366 1707 3367 8094 3367 1709 3367 1709 3368 8094 3368 1711 3368 1709 3369 1711 3369 1710 3369 1710 3370 1711 3370 8097 3370 1710 3371 8097 3371 1712 3371 1712 3372 8097 3372 8098 3372 1712 3373 8098 3373 1713 3373 1713 3374 8098 3374 8099 3374 1713 3375 8099 3375 1714 3375 1714 3376 8099 3376 1715 3376 1714 3377 1715 3377 8158 3377 8158 3378 1715 3378 1716 3378 8158 3379 1716 3379 1717 3379 1717 3380 1716 3380 8062 3380 1717 3381 8062 3381 8154 3381 8154 3382 8062 3382 8063 3382 8154 3383 8063 3383 1718 3383 1718 3384 8063 3384 8065 3384 1718 3385 8065 3385 8153 3385 8153 3386 8065 3386 8102 3386 8153 3387 8102 3387 8101 3387 7990 3388 2779 3388 2778 3388 7990 3389 2778 3389 7991 3389 7991 3390 2778 3390 1719 3390 7991 3391 1719 3391 1720 3391 1720 3392 1719 3392 1721 3392 1720 3393 1721 3393 7993 3393 7993 3394 1721 3394 1722 3394 7993 3395 1722 3395 7994 3395 7994 3396 1722 3396 2774 3396 7994 3397 2774 3397 1723 3397 1723 3398 2774 3398 1724 3398 1723 3399 1724 3399 7996 3399 7996 3400 1724 3400 2772 3400 7996 3401 2772 3401 1725 3401 1725 3402 2772 3402 1726 3402 1725 3403 1726 3403 7997 3403 7997 3404 1726 3404 2770 3404 7997 3405 2770 3405 7998 3405 7998 3406 2770 3406 1727 3406 7998 3407 1727 3407 7999 3407 7999 3408 1727 3408 2768 3408 7999 3409 2768 3409 1728 3409 1728 3410 2768 3410 2767 3410 1728 3411 2767 3411 1729 3411 1729 3412 2767 3412 2765 3412 1729 3413 2765 3413 8000 3413 8000 3414 2765 3414 1731 3414 8000 3415 1731 3415 1730 3415 1730 3416 1731 3416 2762 3416 1730 3417 2762 3417 1732 3417 1732 3418 2762 3418 2761 3418 1732 3419 2761 3419 1733 3419 1733 3420 2761 3420 2758 3420 1733 3421 2758 3421 8001 3421 8001 3422 2758 3422 1734 3422 8001 3423 1734 3423 1735 3423 1735 3424 1734 3424 8038 3424 1735 3425 8038 3425 8003 3425 7950 3426 8037 3426 2739 3426 7950 3427 2739 3427 7951 3427 7951 3428 2739 3428 2742 3428 7951 3429 2742 3429 7952 3429 7952 3430 2742 3430 2743 3430 7952 3431 2743 3431 1736 3431 1736 3432 2743 3432 1737 3432 1736 3433 1737 3433 7955 3433 7955 3434 1737 3434 2745 3434 7955 3435 2745 3435 7957 3435 7957 3436 2745 3436 2746 3436 7957 3437 2746 3437 7958 3437 7958 3438 2746 3438 2747 3438 7958 3439 2747 3439 7959 3439 7959 3440 2747 3440 2749 3440 7959 3441 2749 3441 7961 3441 7961 3442 2749 3442 1738 3442 7961 3443 1738 3443 1739 3443 1739 3444 1738 3444 1740 3444 1739 3445 1740 3445 7962 3445 7962 3446 1740 3446 2751 3446 7962 3447 2751 3447 7963 3447 7963 3448 2751 3448 1742 3448 7963 3449 1742 3449 1741 3449 1741 3450 1742 3450 1743 3450 1741 3451 1743 3451 1744 3451 1744 3452 1743 3452 2752 3452 1744 3453 2752 3453 7965 3453 7965 3454 2752 3454 1745 3454 7965 3455 1745 3455 7966 3455 7966 3456 1745 3456 2755 3456 7966 3457 2755 3457 1746 3457 1746 3458 2755 3458 2756 3458 1746 3459 2756 3459 7931 3459 7931 3460 2756 3460 2757 3460 7931 3461 2757 3461 1747 3461 1747 3462 2757 3462 8017 3462 1747 3463 8017 3463 8018 3463 7987 3464 7986 3464 1748 3464 7987 3465 1748 3465 8002 3465 8002 3466 1748 3466 7953 3466 8002 3467 7953 3467 1749 3467 1749 3468 7953 3468 7954 3468 1749 3469 7954 3469 1750 3469 1750 3470 7954 3470 1751 3470 1750 3471 1751 3471 1753 3471 1753 3472 1751 3472 1752 3472 1753 3473 1752 3473 1754 3473 1754 3474 1752 3474 7956 3474 1754 3475 7956 3475 1755 3475 1755 3476 7956 3476 1756 3476 1755 3477 1756 3477 1757 3477 1757 3478 1756 3478 7960 3478 1757 3479 7960 3479 1758 3479 1758 3480 7960 3480 1760 3480 1758 3481 1760 3481 1759 3481 1759 3482 1760 3482 1761 3482 1759 3483 1761 3483 1762 3483 1762 3484 1761 3484 1763 3484 1762 3485 1763 3485 1764 3485 1764 3486 1763 3486 1765 3486 1764 3487 1765 3487 7995 3487 7995 3488 1765 3488 1766 3488 7995 3489 1766 3489 1767 3489 1767 3490 1766 3490 7964 3490 1767 3491 7964 3491 1768 3491 1768 3492 7964 3492 1769 3492 1768 3493 1769 3493 1770 3493 1770 3494 1769 3494 7967 3494 1770 3495 7967 3495 7992 3495 7992 3496 7967 3496 7929 3496 7992 3497 7929 3497 1771 3497 1771 3498 7929 3498 7930 3498 1771 3499 7930 3499 1772 3499 1772 3500 7930 3500 1773 3500 1772 3501 1773 3501 7968 3501 7915 3502 7890 3502 1774 3502 1774 3503 7890 3503 1775 3503 1774 3504 1775 3504 1781 3504 1781 3505 1775 3505 1776 3505 1781 3506 1776 3506 1782 3506 1782 3507 1776 3507 1777 3507 1782 3508 1777 3508 1783 3508 1783 3509 1777 3509 1778 3509 1783 3510 1778 3510 1779 3510 1779 3511 1778 3511 1780 3511 1779 3512 1780 3512 7912 3512 7912 3513 1780 3513 7916 3513 7913 3514 1781 3514 1782 3514 1774 3515 1781 3515 7913 3515 7915 3516 1774 3516 7913 3516 7913 3517 1779 3517 7912 3517 1783 3518 1779 3518 7913 3518 1782 3519 1783 3519 7913 3519 1791 3520 7884 3520 1792 3520 1792 3521 7884 3521 7883 3521 1792 3522 7883 3522 1784 3522 1784 3523 7883 3523 1785 3523 1784 3524 1785 3524 1786 3524 1786 3525 1785 3525 1787 3525 1786 3526 1787 3526 1794 3526 1794 3527 1787 3527 1788 3527 1794 3528 1788 3528 1793 3528 1793 3529 1788 3529 1790 3529 1793 3530 1790 3530 1789 3530 1789 3531 1790 3531 7903 3531 1795 3532 1784 3532 1786 3532 1792 3533 1784 3533 1795 3533 1791 3534 1792 3534 1795 3534 1795 3535 1793 3535 1789 3535 1794 3536 1793 3536 1795 3536 1786 3537 1794 3537 1795 3537 1806 3538 7882 3538 1796 3538 1796 3539 7882 3539 1797 3539 1796 3540 1797 3540 1798 3540 1798 3541 1797 3541 1799 3541 1798 3542 1799 3542 1805 3542 1805 3543 1799 3543 1800 3543 1805 3544 1800 3544 1801 3544 1801 3545 1800 3545 7846 3545 1801 3546 7846 3546 1802 3546 1802 3547 7846 3547 1803 3547 1802 3548 1803 3548 1804 3548 1804 3549 1803 3549 7878 3549 1807 3550 1798 3550 1805 3550 1796 3551 1798 3551 1807 3551 1806 3552 1796 3552 1807 3552 1807 3553 1802 3553 1804 3553 1801 3554 1802 3554 1807 3554 1805 3555 1801 3555 1807 3555 7874 3556 7851 3556 1808 3556 1808 3557 7851 3557 7852 3557 1808 3558 7852 3558 1809 3558 1809 3559 7852 3559 7854 3559 1809 3560 7854 3560 1813 3560 1813 3561 7854 3561 7849 3561 1813 3562 7849 3562 1810 3562 1810 3563 7849 3563 1811 3563 1810 3564 1811 3564 1815 3564 1815 3565 1811 3565 7847 3565 1815 3566 7847 3566 7867 3566 7867 3567 7847 3567 1812 3567 1814 3568 1809 3568 1813 3568 1808 3569 1809 3569 1814 3569 7874 3570 1808 3570 1814 3570 1814 3571 1815 3571 7867 3571 1810 3572 1815 3572 1814 3572 1813 3573 1810 3573 1814 3573 1816 3574 7838 3574 1820 3574 1820 3575 7838 3575 4550 3575 1820 3576 4550 3576 1822 3576 1822 3577 4550 3577 4549 3577 1822 3578 4549 3578 1824 3578 1824 3579 4549 3579 4548 3579 1824 3580 4548 3580 1827 3580 1827 3581 4548 3581 4546 3581 1827 3582 4546 3582 1828 3582 1828 3583 4546 3583 1818 3583 1828 3584 1818 3584 1817 3584 1817 3585 1818 3585 4544 3585 7817 3586 1816 3586 1819 3586 1819 3587 1816 3587 1820 3587 1819 3588 1820 3588 1821 3588 1821 3589 1820 3589 1822 3589 1821 3590 1822 3590 1823 3590 1823 3591 1822 3591 1824 3591 1823 3592 1824 3592 1825 3592 1825 3593 1824 3593 1827 3593 1825 3594 1827 3594 1826 3594 1826 3595 1827 3595 1828 3595 1826 3596 1828 3596 7826 3596 7826 3597 1828 3597 1817 3597 7826 3598 7757 3598 1826 3598 1826 3599 7757 3599 7758 3599 1826 3600 7758 3600 1825 3600 1825 3601 7758 3601 1829 3601 1825 3602 1829 3602 1823 3602 1823 3603 1829 3603 1830 3603 1823 3604 1830 3604 1821 3604 1821 3605 1830 3605 7749 3605 1821 3606 7749 3606 1819 3606 1819 3607 7749 3607 7751 3607 1819 3608 7751 3608 7817 3608 7817 3609 7751 3609 7818 3609 4527 3610 1831 3610 1832 3610 1832 3611 1831 3611 1833 3611 1832 3612 1833 3612 1834 3612 1833 3613 1848 3613 1834 3613 1834 3614 1848 3614 1835 3614 1834 3615 1835 3615 4530 3615 4530 3616 1835 3616 1847 3616 1847 3617 1836 3617 4530 3617 4530 3618 1836 3618 1840 3618 4530 3619 1840 3619 1837 3619 7805 3620 1838 3620 1841 3620 1841 3621 1838 3621 1839 3621 1841 3622 1839 3622 1843 3622 1843 3623 1839 3623 1837 3623 1843 3624 1837 3624 1844 3624 1844 3625 1837 3625 1840 3625 7792 3626 7805 3626 1841 3626 7792 3627 1841 3627 1853 3627 1853 3628 1841 3628 1843 3628 1853 3629 1843 3629 1842 3629 1842 3630 1843 3630 1844 3630 1842 3631 1844 3631 1845 3631 1844 3632 1840 3632 1845 3632 1845 3633 1840 3633 1836 3633 1845 3634 1836 3634 1846 3634 1836 3635 1847 3635 1846 3635 1846 3636 1847 3636 1835 3636 1846 3637 1835 3637 1849 3637 1835 3638 1848 3638 1849 3638 1849 3639 1848 3639 1833 3639 1849 3640 1833 3640 1850 3640 1850 3641 1833 3641 1831 3641 1850 3642 1831 3642 7798 3642 7798 3643 7797 3643 1850 3643 1850 3644 7797 3644 1851 3644 1850 3645 1851 3645 1849 3645 1849 3646 1851 3646 1852 3646 1849 3647 1852 3647 1846 3647 1846 3648 1852 3648 7732 3648 1846 3649 7732 3649 1845 3649 1845 3650 7732 3650 7734 3650 1845 3651 7734 3651 1842 3651 1842 3652 7734 3652 7735 3652 1842 3653 7735 3653 1853 3653 1853 3654 7735 3654 7725 3654 1853 3655 7725 3655 7792 3655 7792 3656 7725 3656 7724 3656 1859 3657 4524 3657 1855 3657 1855 3658 4524 3658 1854 3658 1855 3659 1854 3659 1861 3659 1861 3660 1854 3660 1857 3660 1861 3661 1857 3661 1856 3661 1856 3662 1857 3662 1858 3662 1856 3663 1858 3663 1863 3663 1863 3664 1858 3664 4522 3664 1863 3665 4522 3665 1865 3665 1865 3666 4522 3666 4521 3666 1865 3667 4521 3667 7777 3667 7777 3668 4521 3668 4519 3668 7775 3669 1859 3669 1870 3669 1870 3670 1859 3670 1855 3670 1870 3671 1855 3671 1860 3671 1860 3672 1855 3672 1861 3672 1860 3673 1861 3673 1867 3673 1867 3674 1861 3674 1856 3674 1867 3675 1856 3675 1862 3675 1862 3676 1856 3676 1863 3676 1862 3677 1863 3677 1864 3677 1864 3678 1863 3678 1865 3678 1864 3679 1865 3679 1866 3679 1866 3680 1865 3680 7777 3680 1866 3681 7705 3681 1864 3681 1864 3682 7705 3682 7706 3682 1864 3683 7706 3683 1862 3683 1862 3684 7706 3684 7708 3684 1862 3685 7708 3685 1867 3685 1867 3686 7708 3686 1868 3686 1867 3687 1868 3687 1860 3687 1860 3688 1868 3688 1869 3688 1860 3689 1869 3689 1870 3689 1870 3690 1869 3690 1871 3690 1870 3691 1871 3691 7775 3691 7775 3692 1871 3692 7697 3692 7770 3693 1872 3693 1873 3693 1873 3694 1872 3694 1874 3694 1873 3695 1874 3695 1881 3695 1881 3696 1874 3696 6581 3696 1881 3697 6581 3697 1884 3697 1884 3698 6581 3698 1875 3698 1884 3699 1875 3699 1886 3699 1886 3700 1875 3700 6582 3700 1886 3701 6582 3701 1887 3701 1887 3702 6582 3702 1876 3702 1887 3703 1876 3703 1877 3703 1877 3704 1876 3704 6574 3704 1877 3705 6574 3705 7765 3705 7765 3706 6574 3706 7766 3706 1878 3707 7770 3707 1879 3707 1879 3708 7770 3708 1873 3708 1879 3709 1873 3709 1880 3709 1880 3710 1873 3710 1881 3710 1880 3711 1881 3711 1882 3711 1882 3712 1881 3712 1884 3712 1882 3713 1884 3713 1883 3713 1883 3714 1884 3714 1886 3714 1883 3715 1886 3715 1885 3715 1885 3716 1886 3716 1887 3716 1885 3717 1887 3717 7750 3717 7750 3718 1887 3718 1877 3718 7750 3719 1877 3719 1888 3719 1888 3720 1877 3720 7765 3720 7747 3721 7748 3721 1889 3721 1889 3722 7748 3722 1890 3722 1889 3723 1890 3723 1891 3723 1891 3724 1890 3724 1892 3724 1891 3725 1892 3725 1896 3725 1896 3726 1892 3726 6624 3726 1896 3727 6624 3727 1897 3727 1897 3728 6624 3728 1893 3728 1897 3729 1893 3729 1901 3729 1901 3730 1893 3730 1894 3730 1901 3731 1894 3731 1902 3731 1902 3732 1894 3732 6627 3732 7730 3733 7747 3733 7731 3733 7731 3734 7747 3734 1889 3734 7731 3735 1889 3735 7733 3735 7733 3736 1889 3736 1891 3736 7733 3737 1891 3737 1895 3737 1895 3738 1891 3738 1896 3738 1895 3739 1896 3739 1898 3739 1898 3740 1896 3740 1897 3740 1898 3741 1897 3741 1899 3741 1899 3742 1897 3742 1901 3742 1899 3743 1901 3743 1900 3743 1900 3744 1901 3744 1902 3744 1911 3745 7721 3745 1912 3745 1912 3746 7721 3746 6533 3746 1912 3747 6533 3747 1903 3747 1903 3748 6533 3748 1904 3748 1903 3749 1904 3749 1914 3749 1914 3750 1904 3750 6531 3750 1914 3751 6531 3751 1905 3751 1905 3752 6531 3752 6530 3752 1905 3753 6530 3753 1917 3753 1917 3754 6530 3754 1906 3754 1917 3755 1906 3755 1920 3755 1920 3756 1906 3756 1907 3756 1920 3757 1907 3757 1908 3757 1908 3758 1907 3758 1909 3758 1910 3759 1911 3759 7707 3759 7707 3760 1911 3760 1912 3760 7707 3761 1912 3761 7709 3761 7709 3762 1912 3762 1903 3762 7709 3763 1903 3763 1913 3763 1913 3764 1903 3764 1914 3764 1913 3765 1914 3765 1915 3765 1915 3766 1914 3766 1905 3766 1915 3767 1905 3767 1916 3767 1916 3768 1905 3768 1917 3768 1916 3769 1917 3769 1918 3769 1918 3770 1917 3770 1920 3770 1918 3771 1920 3771 1919 3771 1919 3772 1920 3772 1908 3772 1968 3773 6579 3773 1967 3773 1967 3774 6579 3774 1921 3774 1967 3775 1921 3775 1966 3775 1966 3776 1921 3776 6573 3776 1966 3777 6573 3777 1963 3777 1963 3778 6573 3778 6572 3778 1963 3779 6572 3779 1922 3779 1922 3780 6572 3780 1924 3780 1922 3781 1924 3781 1923 3781 1923 3782 1924 3782 1926 3782 1923 3783 1926 3783 1925 3783 1925 3784 1926 3784 7694 3784 1981 3785 6618 3785 1980 3785 1980 3786 6618 3786 6617 3786 1980 3787 6617 3787 1979 3787 1979 3788 6617 3788 1927 3788 1979 3789 1927 3789 1929 3789 1929 3790 1927 3790 1928 3790 1929 3791 1928 3791 1930 3791 1930 3792 1928 3792 1931 3792 1930 3793 1931 3793 1977 3793 1977 3794 1931 3794 6622 3794 1977 3795 6622 3795 7685 3795 7685 3796 6622 3796 6630 3796 6655 3797 6654 3797 1932 3797 1932 3798 1933 3798 6655 3798 6655 3799 1933 3799 1991 3799 6655 3800 1991 3800 1934 3800 1991 3801 1992 3801 1934 3801 1934 3802 1992 3802 1993 3802 1934 3803 1993 3803 6628 3803 1993 3804 1935 3804 6628 3804 6628 3805 1935 3805 1994 3805 6628 3806 1994 3806 1936 3806 1936 3807 1994 3807 1937 3807 1936 3808 1937 3808 6625 3808 1937 3809 1938 3809 6625 3809 6625 3810 1938 3810 1939 3810 6625 3811 1939 3811 1943 3811 1940 3812 7670 3812 1941 3812 1941 3813 7670 3813 1943 3813 1941 3814 1943 3814 1942 3814 1942 3815 1943 3815 1939 3815 7666 3816 2005 3816 6529 3816 6529 3817 2005 3817 2006 3817 6529 3818 2006 3818 1944 3818 2006 3819 1945 3819 1944 3819 1944 3820 1945 3820 1946 3820 1944 3821 1946 3821 6527 3821 6527 3822 1946 3822 2007 3822 2007 3823 2008 3823 6527 3823 6527 3824 2008 3824 1947 3824 6527 3825 1947 3825 6526 3825 1948 3826 1949 3826 1951 3826 1951 3827 1949 3827 1950 3827 1951 3828 1950 3828 1952 3828 1952 3829 1950 3829 6526 3829 1952 3830 6526 3830 2010 3830 2010 3831 6526 3831 1947 3831 7649 3832 1953 3832 1962 3832 1962 3833 1953 3833 1954 3833 1962 3834 1954 3834 1955 3834 1955 3835 1954 3835 1956 3835 1955 3836 1956 3836 1964 3836 1964 3837 1956 3837 1957 3837 1964 3838 1957 3838 1965 3838 1965 3839 1957 3839 1958 3839 1965 3840 1958 3840 1959 3840 1959 3841 1958 3841 1960 3841 1959 3842 1960 3842 7643 3842 7643 3843 1960 3843 1961 3843 1925 3844 7649 3844 1923 3844 1923 3845 7649 3845 1962 3845 1923 3846 1962 3846 1922 3846 1922 3847 1962 3847 1955 3847 1922 3848 1955 3848 1963 3848 1963 3849 1955 3849 1964 3849 1963 3850 1964 3850 1966 3850 1966 3851 1964 3851 1965 3851 1966 3852 1965 3852 1967 3852 1967 3853 1965 3853 1959 3853 1967 3854 1959 3854 1968 3854 1968 3855 1959 3855 7643 3855 1976 3856 7636 3856 1978 3856 1978 3857 7636 3857 4495 3857 1978 3858 4495 3858 1969 3858 1969 3859 4495 3859 1971 3859 1969 3860 1971 3860 1970 3860 1970 3861 1971 3861 4493 3861 1970 3862 4493 3862 1972 3862 1972 3863 4493 3863 4492 3863 1972 3864 4492 3864 1973 3864 1973 3865 4492 3865 4491 3865 1973 3866 4491 3866 1974 3866 1974 3867 4491 3867 1975 3867 7685 3868 1976 3868 1977 3868 1977 3869 1976 3869 1978 3869 1977 3870 1978 3870 1930 3870 1930 3871 1978 3871 1969 3871 1930 3872 1969 3872 1929 3872 1929 3873 1969 3873 1970 3873 1929 3874 1970 3874 1979 3874 1979 3875 1970 3875 1972 3875 1979 3876 1972 3876 1980 3876 1980 3877 1972 3877 1973 3877 1980 3878 1973 3878 1981 3878 1981 3879 1973 3879 1974 3879 1982 3880 1983 3880 1984 3880 1984 3881 1983 3881 1985 3881 1984 3882 1985 3882 1986 3882 1986 3883 1985 3883 4487 3883 1986 3884 4487 3884 1987 3884 1987 3885 4487 3885 4484 3885 1987 3886 4484 3886 1988 3886 1988 3887 4484 3887 1989 3887 1988 3888 1989 3888 1995 3888 1995 3889 1989 3889 4482 3889 1995 3890 4482 3890 1990 3890 1990 3891 4482 3891 4481 3891 1932 3892 1982 3892 1933 3892 1933 3893 1982 3893 1984 3893 1933 3894 1984 3894 1991 3894 1991 3895 1984 3895 1992 3895 1992 3896 1984 3896 1986 3896 1992 3897 1986 3897 1993 3897 1993 3898 1986 3898 1935 3898 1935 3899 1986 3899 1987 3899 1935 3900 1987 3900 1994 3900 1994 3901 1987 3901 1937 3901 1937 3902 1987 3902 1988 3902 1937 3903 1988 3903 1938 3903 1938 3904 1988 3904 1939 3904 1939 3905 1988 3905 1995 3905 1939 3906 1995 3906 1942 3906 1942 3907 1995 3907 1941 3907 1941 3908 1995 3908 1990 3908 1941 3909 1990 3909 1940 3909 7607 3910 1996 3910 1997 3910 1997 3911 1996 3911 4465 3911 1997 3912 4465 3912 1998 3912 1998 3913 4465 3913 4462 3913 1998 3914 4462 3914 1999 3914 1999 3915 4462 3915 4461 3915 1999 3916 4461 3916 2009 3916 2009 3917 4461 3917 2000 3917 2009 3918 2000 3918 2001 3918 2001 3919 2000 3919 2002 3919 2001 3920 2002 3920 2003 3920 2003 3921 2002 3921 2004 3921 2003 3922 2004 3922 2011 3922 2011 3923 2004 3923 4471 3923 2005 3924 7607 3924 1997 3924 2005 3925 1997 3925 2006 3925 2006 3926 1997 3926 1998 3926 2006 3927 1998 3927 1945 3927 1945 3928 1998 3928 1946 3928 1946 3929 1998 3929 1999 3929 1946 3930 1999 3930 2007 3930 2007 3931 1999 3931 2008 3931 2008 3932 1999 3932 2009 3932 2008 3933 2009 3933 1947 3933 1947 3934 2009 3934 2010 3934 2010 3935 2009 3935 2001 3935 2010 3936 2001 3936 1952 3936 1952 3937 2001 3937 2003 3937 1952 3938 2003 3938 1951 3938 1951 3939 2003 3939 2011 3939 1951 3940 2011 3940 1948 3940 2012 3941 7597 3941 2020 3941 2020 3942 7597 3942 4449 3942 2020 3943 4449 3943 2013 3943 2013 3944 4449 3944 4447 3944 2013 3945 4447 3945 2014 3945 2014 3946 4447 3946 2016 3946 2014 3947 2016 3947 2015 3947 2015 3948 2016 3948 4445 3948 2015 3949 4445 3949 2017 3949 2017 3950 4445 3950 4458 3950 2017 3951 4458 3951 2024 3951 2024 3952 4458 3952 2018 3952 2024 3953 2018 3953 2019 3953 2019 3954 2018 3954 4456 3954 7579 3955 2012 3955 2020 3955 7579 3956 2020 3956 2021 3956 2021 3957 2020 3957 2013 3957 2021 3958 2013 3958 2025 3958 2025 3959 2013 3959 2026 3959 2026 3960 2013 3960 2014 3960 2026 3961 2014 3961 2027 3961 2027 3962 2014 3962 2028 3962 2028 3963 2014 3963 2015 3963 2028 3964 2015 3964 2022 3964 2022 3965 2015 3965 2023 3965 2023 3966 2015 3966 2017 3966 2023 3967 2017 3967 2030 3967 2030 3968 2017 3968 2024 3968 2030 3969 2024 3969 2029 3969 2029 3970 2024 3970 2019 3970 2029 3971 2019 3971 7587 3971 7491 3972 7579 3972 7490 3972 7490 3973 7579 3973 2021 3973 7490 3974 2021 3974 7489 3974 2021 3975 2025 3975 7489 3975 7489 3976 2025 3976 2026 3976 7489 3977 2026 3977 7488 3977 7488 3978 2026 3978 2027 3978 2027 3979 2028 3979 7488 3979 7488 3980 2028 3980 2022 3980 7488 3981 2022 3981 7498 3981 7587 3982 7588 3982 2029 3982 2029 3983 7588 3983 7497 3983 2029 3984 7497 3984 2030 3984 2030 3985 7497 3985 7498 3985 2030 3986 7498 3986 2023 3986 2023 3987 7498 3987 2022 3987 2038 3988 4444 3988 2039 3988 2039 3989 4444 3989 2032 3989 2039 3990 2032 3990 2031 3990 2031 3991 2032 3991 2034 3991 2031 3992 2034 3992 2033 3992 2033 3993 2034 3993 4439 3993 2033 3994 4439 3994 2035 3994 2035 3995 4439 3995 4437 3995 2035 3996 4437 3996 2036 3996 2036 3997 4437 3997 4436 3997 2036 3998 4436 3998 7571 3998 7571 3999 4436 3999 2037 3999 7570 4000 2038 4000 2042 4000 2042 4001 2038 4001 2039 4001 2042 4002 2039 4002 2044 4002 2044 4003 2039 4003 2045 4003 2045 4004 2039 4004 2031 4004 2045 4005 2031 4005 2046 4005 2046 4006 2031 4006 2047 4006 2047 4007 2031 4007 2033 4007 2047 4008 2033 4008 2049 4008 2049 4009 2033 4009 2050 4009 2050 4010 2033 4010 2035 4010 2050 4011 2035 4011 2051 4011 2051 4012 2035 4012 2052 4012 2052 4013 2035 4013 2036 4013 2052 4014 2036 4014 2053 4014 2053 4015 2036 4015 2040 4015 2040 4016 2036 4016 7571 4016 2040 4017 7571 4017 2041 4017 2043 4018 7467 4018 7570 4018 7570 4019 2042 4019 2043 4019 2043 4020 2042 4020 2044 4020 2043 4021 2044 4021 7466 4021 2044 4022 2045 4022 7466 4022 7466 4023 2045 4023 2046 4023 7466 4024 2046 4024 7477 4024 7477 4025 2046 4025 2047 4025 7477 4026 2047 4026 2048 4026 2047 4027 2049 4027 2048 4027 2048 4028 2049 4028 2050 4028 2048 4029 2050 4029 7476 4029 2050 4030 2051 4030 7476 4030 7476 4031 2051 4031 2052 4031 7476 4032 2052 4032 7473 4032 2041 4033 7554 4033 2040 4033 2040 4034 7554 4034 7473 4034 2040 4035 7473 4035 2053 4035 2053 4036 7473 4036 2052 4036 2054 4037 7551 4037 7544 4037 7544 4038 2055 4038 2054 4038 2054 4039 2055 4039 2057 4039 2054 4040 2057 4040 2056 4040 2057 4041 2058 4041 2056 4041 2056 4042 2058 4042 2076 4042 2056 4043 2076 4043 2060 4043 2060 4044 2076 4044 2059 4044 2059 4045 2074 4045 2060 4045 2060 4046 2074 4046 2072 4046 2060 4047 2072 4047 4423 4047 2072 4048 2070 4048 4423 4048 4423 4049 2070 4049 2061 4049 4423 4050 2061 4050 2062 4050 2065 4051 2063 4051 2064 4051 2064 4052 2063 4052 2062 4052 2064 4053 2062 4053 2068 4053 2068 4054 2062 4054 2061 4054 2077 4055 2065 4055 2066 4055 2066 4056 2065 4056 2064 4056 2066 4057 2064 4057 2067 4057 2067 4058 2064 4058 2068 4058 2067 4059 2068 4059 2080 4059 2080 4060 2068 4060 2061 4060 2080 4061 2061 4061 2069 4061 2069 4062 2061 4062 2070 4062 2069 4063 2070 4063 2071 4063 2071 4064 2070 4064 2072 4064 2071 4065 2072 4065 2073 4065 2073 4066 2072 4066 2074 4066 2073 4067 2074 4067 2081 4067 2081 4068 2074 4068 2059 4068 2081 4069 2059 4069 2082 4069 2082 4070 2059 4070 2076 4070 2082 4071 2076 4071 2075 4071 2075 4072 2076 4072 2058 4072 2075 4073 2058 4073 2087 4073 2087 4074 2058 4074 2057 4074 2087 4075 2057 4075 2086 4075 2086 4076 2057 4076 2055 4076 2086 4077 2055 4077 2084 4077 2084 4078 2055 4078 7544 4078 2078 4079 7445 4079 2077 4079 2077 4080 2066 4080 2078 4080 2078 4081 2066 4081 2067 4081 2078 4082 2067 4082 2079 4082 2067 4083 2080 4083 2079 4083 2079 4084 2080 4084 2069 4084 2079 4085 2069 4085 7442 4085 7442 4086 2069 4086 2071 4086 2071 4087 2073 4087 7442 4087 7442 4088 2073 4088 2081 4088 7442 4089 2081 4089 2083 4089 2081 4090 2082 4090 2083 4090 2083 4091 2082 4091 2075 4091 2083 4092 2075 4092 2088 4092 2084 4093 2085 4093 2086 4093 2086 4094 2085 4094 2088 4094 2086 4095 2088 4095 2087 4095 2087 4096 2088 4096 2075 4096 7509 4097 6437 4097 2095 4097 2095 4098 6437 4098 2089 4098 2095 4099 2089 4099 2096 4099 2096 4100 2089 4100 6436 4100 2096 4101 6436 4101 2090 4101 2090 4102 6436 4102 2091 4102 2090 4103 2091 4103 2099 4103 2099 4104 2091 4104 2092 4104 2099 4105 2092 4105 2101 4105 2101 4106 2092 4106 2093 4106 2101 4107 2093 4107 7518 4107 7518 4108 2093 4108 7519 4108 7496 4109 7509 4109 2094 4109 2094 4110 7509 4110 2095 4110 2094 4111 2095 4111 7487 4111 7487 4112 2095 4112 2096 4112 7487 4113 2096 4113 2097 4113 2097 4114 2096 4114 2090 4114 2097 4115 2090 4115 2098 4115 2098 4116 2090 4116 2099 4116 2098 4117 2099 4117 2100 4117 2100 4118 2099 4118 2101 4118 2100 4119 2101 4119 7492 4119 7492 4120 2101 4120 7518 4120 2102 4121 2121 4121 2103 4121 2103 4122 2121 4122 2104 4122 2103 4123 2104 4123 6453 4123 2104 4124 2118 4124 6453 4124 6453 4125 2118 4125 2106 4125 6453 4126 2106 4126 2105 4126 2105 4127 2106 4127 2116 4127 2116 4128 2115 4128 2105 4128 2105 4129 2115 4129 2113 4129 2105 4130 2113 4130 6455 4130 7486 4131 2107 4131 2108 4131 2108 4132 2107 4132 2109 4132 2108 4133 2109 4133 2110 4133 2110 4134 2109 4134 6455 4134 2110 4135 6455 4135 2111 4135 2111 4136 6455 4136 2113 4136 7474 4137 7486 4137 2108 4137 7474 4138 2108 4138 7475 4138 7475 4139 2108 4139 2110 4139 7475 4140 2110 4140 2112 4140 2112 4141 2110 4141 2111 4141 2112 4142 2111 4142 2114 4142 2111 4143 2113 4143 2114 4143 2114 4144 2113 4144 2115 4144 2114 4145 2115 4145 2117 4145 2115 4146 2116 4146 2117 4146 2117 4147 2116 4147 2106 4147 2117 4148 2106 4148 2119 4148 2106 4149 2118 4149 2119 4149 2119 4150 2118 4150 2104 4150 2119 4151 2104 4151 2120 4151 2120 4152 2104 4152 2121 4152 2120 4153 2121 4153 7478 4153 2124 4154 6558 4154 2126 4154 2126 4155 6558 4155 6559 4155 2126 4156 6559 4156 2127 4156 2127 4157 6559 4157 2122 4157 2127 4158 2122 4158 2128 4158 2128 4159 2122 4159 6568 4159 2128 4160 6568 4160 2130 4160 2130 4161 6568 4161 6566 4161 2130 4162 6566 4162 2131 4162 2131 4163 6566 4163 6565 4163 2131 4164 6565 4164 2123 4164 2123 4165 6565 4165 6564 4165 2123 4166 6564 4166 7459 4166 7459 4167 6564 4167 7460 4167 7451 4168 2124 4168 2125 4168 2125 4169 2124 4169 2126 4169 2125 4170 2126 4170 7452 4170 7452 4171 2126 4171 2127 4171 7452 4172 2127 4172 7453 4172 7453 4173 2127 4173 2128 4173 7453 4174 2128 4174 7443 4174 7443 4175 2128 4175 2130 4175 7443 4176 2130 4176 2129 4176 2129 4177 2130 4177 2131 4177 2129 4178 2131 4178 7444 4178 7444 4179 2131 4179 2123 4179 7444 4180 2123 4180 7446 4180 7446 4181 2123 4181 7459 4181 7441 4182 6433 4182 2175 4182 2175 4183 6433 4183 6432 4183 2175 4184 6432 4184 2173 4184 2173 4185 6432 4185 6462 4185 2173 4186 6462 4186 2172 4186 2172 4187 6462 4187 6465 4187 2172 4188 6465 4188 2169 4188 2169 4189 6465 4189 6461 4189 2169 4190 6461 4190 2167 4190 2167 4191 6461 4191 6429 4191 2167 4192 6429 4192 7403 4192 7403 4193 6429 4193 2132 4193 2133 4194 2187 4194 6443 4194 6443 4195 2187 4195 2134 4195 6443 4196 2134 4196 2136 4196 2134 4197 2135 4197 2136 4197 2136 4198 2135 4198 2189 4198 2136 4199 2189 4199 2137 4199 2137 4200 2189 4200 2138 4200 2138 4201 2139 4201 2137 4201 2137 4202 2139 4202 2191 4202 2137 4203 2191 4203 2142 4203 7382 4204 6470 4204 2194 4204 2194 4205 6470 4205 2141 4205 2194 4206 2141 4206 2140 4206 2140 4207 2141 4207 2142 4207 2140 4208 2142 4208 2192 4208 2192 4209 2142 4209 2191 4209 2145 4210 6450 4210 2143 4210 2143 4211 2144 4211 2145 4211 2145 4212 2144 4212 2202 4212 2145 4213 2202 4213 6452 4213 2202 4214 2204 4214 6452 4214 6452 4215 2204 4215 2146 4215 6452 4216 2146 4216 6446 4216 2146 4217 2205 4217 6446 4217 6446 4218 2205 4218 2147 4218 6446 4219 2147 4219 6456 4219 6456 4220 2147 4220 2208 4220 6456 4221 2208 4221 2149 4221 2208 4222 2148 4222 2149 4222 2149 4223 2148 4223 2150 4223 2149 4224 2150 4224 6454 4224 7419 4225 2151 4225 2152 4225 2152 4226 2151 4226 6454 4226 2152 4227 6454 4227 2209 4227 2209 4228 6454 4228 2150 4228 2153 4229 7416 4229 7355 4229 7355 4230 2236 4230 2153 4230 2153 4231 2236 4231 2234 4231 2153 4232 2234 4232 2154 4232 2234 4233 2232 4233 2154 4233 2154 4234 2232 4234 2155 4234 2154 4235 2155 4235 6715 4235 2155 4236 2156 4236 6715 4236 6715 4237 2156 4237 2230 4237 6715 4238 2230 4238 6716 4238 6716 4239 2230 4239 2228 4239 6716 4240 2228 4240 6711 4240 2228 4241 2227 4241 6711 4241 6711 4242 2227 4242 2226 4242 6711 4243 2226 4243 6712 4243 2221 4244 6714 4244 2223 4244 2223 4245 6714 4245 6712 4245 2223 4246 6712 4246 2224 4246 2224 4247 6712 4247 2226 4247 2158 4248 2157 4248 7397 4248 7397 4249 2159 4249 2158 4249 2158 4250 2159 4250 2176 4250 2158 4251 2176 4251 2160 4251 2176 4252 2174 4252 2160 4252 2160 4253 2174 4253 2161 4253 2160 4254 2161 4254 4407 4254 4407 4255 2161 4255 2162 4255 4407 4256 2162 4256 2163 4256 2162 4257 2171 4257 2163 4257 2163 4258 2171 4258 2164 4258 2163 4259 2164 4259 4409 4259 2164 4260 2170 4260 4409 4260 4409 4261 2170 4261 2168 4261 4409 4262 2168 4262 4411 4262 7407 4263 7409 4263 2165 4263 2165 4264 7409 4264 4411 4264 2165 4265 4411 4265 2166 4265 2166 4266 4411 4266 2168 4266 7407 4267 2165 4267 7403 4267 7403 4268 2165 4268 2167 4268 2165 4269 2166 4269 2167 4269 2167 4270 2166 4270 2168 4270 2167 4271 2168 4271 2169 4271 2168 4272 2170 4272 2169 4272 2169 4273 2170 4273 2164 4273 2169 4274 2164 4274 2172 4274 2164 4275 2171 4275 2172 4275 2172 4276 2171 4276 2162 4276 2172 4277 2162 4277 2173 4277 2162 4278 2161 4278 2173 4278 2173 4279 2161 4279 2174 4279 2173 4280 2174 4280 2175 4280 7397 4281 7441 4281 2159 4281 2159 4282 7441 4282 2175 4282 2159 4283 2175 4283 2176 4283 2176 4284 2175 4284 2174 4284 7394 4285 4397 4285 2188 4285 2188 4286 4397 4286 2177 4286 2188 4287 2177 4287 2178 4287 2178 4288 2177 4288 2179 4288 2178 4289 2179 4289 2190 4289 2190 4290 2179 4290 2180 4290 2190 4291 2180 4291 2181 4291 2181 4292 2180 4292 2182 4292 2181 4293 2182 4293 2184 4293 2184 4294 2182 4294 2183 4294 2184 4295 2183 4295 2193 4295 2193 4296 2183 4296 2186 4296 2193 4297 2186 4297 2185 4297 2185 4298 2186 4298 4402 4298 2187 4299 7394 4299 2188 4299 2187 4300 2188 4300 2134 4300 2134 4301 2188 4301 2178 4301 2134 4302 2178 4302 2135 4302 2135 4303 2178 4303 2189 4303 2189 4304 2178 4304 2190 4304 2189 4305 2190 4305 2138 4305 2138 4306 2190 4306 2139 4306 2139 4307 2190 4307 2181 4307 2139 4308 2181 4308 2191 4308 2191 4309 2181 4309 2192 4309 2192 4310 2181 4310 2184 4310 2192 4311 2184 4311 2140 4311 2140 4312 2184 4312 2193 4312 2140 4313 2193 4313 2194 4313 2194 4314 2193 4314 2185 4314 2194 4315 2185 4315 7382 4315 2201 4316 4393 4316 2203 4316 2203 4317 4393 4317 2195 4317 2203 4318 2195 4318 2206 4318 2206 4319 2195 4319 2196 4319 2206 4320 2196 4320 2207 4320 2207 4321 2196 4321 2197 4321 2207 4322 2197 4322 2198 4322 2198 4323 2197 4323 4390 4323 2198 4324 4390 4324 2210 4324 2210 4325 4390 4325 2199 4325 2210 4326 2199 4326 7365 4326 7365 4327 2199 4327 2200 4327 2143 4328 2201 4328 2144 4328 2144 4329 2201 4329 2203 4329 2144 4330 2203 4330 2202 4330 2202 4331 2203 4331 2204 4331 2204 4332 2203 4332 2206 4332 2204 4333 2206 4333 2146 4333 2146 4334 2206 4334 2205 4334 2205 4335 2206 4335 2207 4335 2205 4336 2207 4336 2147 4336 2147 4337 2207 4337 2208 4337 2208 4338 2207 4338 2198 4338 2208 4339 2198 4339 2148 4339 2148 4340 2198 4340 2150 4340 2150 4341 2198 4341 2210 4341 2150 4342 2210 4342 2209 4342 2209 4343 2210 4343 2152 4343 2152 4344 2210 4344 7365 4344 2152 4345 7365 4345 7419 4345 4385 4346 4376 4346 7362 4346 7362 4347 2220 4347 4385 4347 4385 4348 2220 4348 2222 4348 4385 4349 2222 4349 2211 4349 2222 4350 2212 4350 2211 4350 2211 4351 2212 4351 2225 4351 2211 4352 2225 4352 2213 4352 2213 4353 2225 4353 2214 4353 2213 4354 2214 4354 2215 4354 2214 4355 2229 4355 2215 4355 2215 4356 2229 4356 2216 4356 2215 4357 2216 4357 2218 4357 2216 4358 2217 4358 2218 4358 2218 4359 2217 4359 2231 4359 2218 4360 2231 4360 2219 4360 7356 4361 4383 4361 2235 4361 2235 4362 4383 4362 2219 4362 2235 4363 2219 4363 2233 4363 2233 4364 2219 4364 2231 4364 7362 4365 2221 4365 2220 4365 2220 4366 2221 4366 2223 4366 2220 4367 2223 4367 2222 4367 2222 4368 2223 4368 2224 4368 2222 4369 2224 4369 2212 4369 2212 4370 2224 4370 2226 4370 2212 4371 2226 4371 2225 4371 2225 4372 2226 4372 2227 4372 2225 4373 2227 4373 2214 4373 2214 4374 2227 4374 2228 4374 2214 4375 2228 4375 2229 4375 2229 4376 2228 4376 2230 4376 2229 4377 2230 4377 2216 4377 2216 4378 2230 4378 2156 4378 2216 4379 2156 4379 2217 4379 2217 4380 2156 4380 2155 4380 2217 4381 2155 4381 2231 4381 2231 4382 2155 4382 2232 4382 2231 4383 2232 4383 2233 4383 2233 4384 2232 4384 2234 4384 2233 4385 2234 4385 2235 4385 2235 4386 2234 4386 2236 4386 2235 4387 2236 4387 7356 4387 7356 4388 2236 4388 7355 4388 4365 4389 4364 4389 7332 4389 7332 4390 2237 4390 4365 4390 4365 4391 2237 4391 2255 4391 4365 4392 2255 4392 4367 4392 2255 4393 2238 4393 4367 4393 4367 4394 2238 4394 2254 4394 4367 4395 2254 4395 2239 4395 2239 4396 2254 4396 2240 4396 2240 4397 2252 4397 2239 4397 2239 4398 2252 4398 2250 4398 2239 4399 2250 4399 4368 4399 2250 4400 2248 4400 4368 4400 4368 4401 2248 4401 2242 4401 4368 4402 2242 4402 4369 4402 2241 4403 4370 4403 2244 4403 2244 4404 4370 4404 4369 4404 2244 4405 4369 4405 2245 4405 2245 4406 4369 4406 2242 4406 7321 4407 2241 4407 2243 4407 2243 4408 2241 4408 2244 4408 2243 4409 2244 4409 2258 4409 2258 4410 2244 4410 2245 4410 2258 4411 2245 4411 2246 4411 2246 4412 2245 4412 2242 4412 2246 4413 2242 4413 2247 4413 2247 4414 2242 4414 2248 4414 2247 4415 2248 4415 2249 4415 2249 4416 2248 4416 2250 4416 2249 4417 2250 4417 2260 4417 2260 4418 2250 4418 2252 4418 2260 4419 2252 4419 2251 4419 2251 4420 2252 4420 2240 4420 2251 4421 2240 4421 2261 4421 2261 4422 2240 4422 2254 4422 2261 4423 2254 4423 2253 4423 2253 4424 2254 4424 2238 4424 2253 4425 2238 4425 2264 4425 2264 4426 2238 4426 2255 4426 2264 4427 2255 4427 2256 4427 2256 4428 2255 4428 2237 4428 2256 4429 2237 4429 7309 4429 7309 4430 2237 4430 7332 4430 2257 4431 7319 4431 7321 4431 7321 4432 2243 4432 2257 4432 2257 4433 2243 4433 2258 4433 2257 4434 2258 4434 2259 4434 2258 4435 2246 4435 2259 4435 2259 4436 2246 4436 2247 4436 2259 4437 2247 4437 7245 4437 7245 4438 2247 4438 2249 4438 2249 4439 2260 4439 7245 4439 7245 4440 2260 4440 2251 4440 7245 4441 2251 4441 7244 4441 2251 4442 2261 4442 7244 4442 7244 4443 2261 4443 2253 4443 7244 4444 2253 4444 2263 4444 7309 4445 2262 4445 2256 4445 2256 4446 2262 4446 2263 4446 2256 4447 2263 4447 2264 4447 2264 4448 2263 4448 2253 4448 7296 4449 4354 4449 2269 4449 2269 4450 4354 4450 2265 4450 2269 4451 2265 4451 2272 4451 2272 4452 2265 4452 2266 4452 2272 4453 2266 4453 2273 4453 2273 4454 2266 4454 4351 4454 2273 4455 4351 4455 2274 4455 2274 4456 4351 4456 4349 4456 2274 4457 4349 4457 2267 4457 2267 4458 4349 4458 4348 4458 2267 4459 4348 4459 2278 4459 2278 4460 4348 4460 4346 4460 7284 4461 7296 4461 2268 4461 2268 4462 7296 4462 2269 4462 2268 4463 2269 4463 2270 4463 2270 4464 2269 4464 2271 4464 2271 4465 2269 4465 2272 4465 2271 4466 2272 4466 2281 4466 2281 4467 2272 4467 2283 4467 2283 4468 2272 4468 2273 4468 2283 4469 2273 4469 2284 4469 2284 4470 2273 4470 2285 4470 2285 4471 2273 4471 2274 4471 2285 4472 2274 4472 2286 4472 2286 4473 2274 4473 2275 4473 2275 4474 2274 4474 2267 4474 2275 4475 2267 4475 2276 4475 2276 4476 2267 4476 2277 4476 2277 4477 2267 4477 2278 4477 2277 4478 2278 4478 7290 4478 2280 4479 2279 4479 7284 4479 7284 4480 2268 4480 2280 4480 2280 4481 2268 4481 2270 4481 2280 4482 2270 4482 7226 4482 2270 4483 2271 4483 7226 4483 7226 4484 2271 4484 2281 4484 7226 4485 2281 4485 2282 4485 2282 4486 2281 4486 2283 4486 2282 4487 2283 4487 7225 4487 2283 4488 2284 4488 7225 4488 7225 4489 2284 4489 2285 4489 7225 4490 2285 4490 7224 4490 2285 4491 2286 4491 7224 4491 7224 4492 2286 4492 2275 4492 7224 4493 2275 4493 2287 4493 7290 4494 7222 4494 2277 4494 2277 4495 7222 4495 2287 4495 2277 4496 2287 4496 2276 4496 2276 4497 2287 4497 2275 4497 2288 4498 7283 4498 2289 4498 2289 4499 7283 4499 4336 4499 2289 4500 4336 4500 2297 4500 2297 4501 4336 4501 4335 4501 2297 4502 4335 4502 2290 4502 2290 4503 4335 4503 4334 4503 2290 4504 4334 4504 2291 4504 2291 4505 4334 4505 2292 4505 2291 4506 2292 4506 2299 4506 2299 4507 2292 4507 4332 4507 2299 4508 4332 4508 2301 4508 2301 4509 4332 4509 2293 4509 2301 4510 2293 4510 2302 4510 2302 4511 2293 4511 2294 4511 7274 4512 2288 4512 2289 4512 7274 4513 2289 4513 2295 4513 2295 4514 2289 4514 2297 4514 2295 4515 2297 4515 2296 4515 2296 4516 2297 4516 2305 4516 2305 4517 2297 4517 2290 4517 2305 4518 2290 4518 2306 4518 2306 4519 2290 4519 2298 4519 2298 4520 2290 4520 2291 4520 2298 4521 2291 4521 2310 4521 2310 4522 2291 4522 2309 4522 2309 4523 2291 4523 2299 4523 2309 4524 2299 4524 2300 4524 2300 4525 2299 4525 2301 4525 2300 4526 2301 4526 2308 4526 2308 4527 2301 4527 2302 4527 2308 4528 2302 4528 7269 4528 2303 4529 7274 4529 2304 4529 2304 4530 7274 4530 2295 4530 2304 4531 2295 4531 7194 4531 2295 4532 2296 4532 7194 4532 7194 4533 2296 4533 2305 4533 7194 4534 2305 4534 7193 4534 7193 4535 2305 4535 2306 4535 2306 4536 2298 4536 7193 4536 7193 4537 2298 4537 2310 4537 7193 4538 2310 4538 7191 4538 7269 4539 2307 4539 2308 4539 2308 4540 2307 4540 7189 4540 2308 4541 7189 4541 2300 4541 2300 4542 7189 4542 7191 4542 2300 4543 7191 4543 2309 4543 2309 4544 7191 4544 2310 4544 2318 4545 2311 4545 2319 4545 2319 4546 2311 4546 2312 4546 2319 4547 2312 4547 2322 4547 2322 4548 2312 4548 2313 4548 2322 4549 2313 4549 2323 4549 2323 4550 2313 4550 2314 4550 2323 4551 2314 4551 2315 4551 2315 4552 2314 4552 2316 4552 2315 4553 2316 4553 2325 4553 2325 4554 2316 4554 2317 4554 2325 4555 2317 4555 7252 4555 7252 4556 2317 4556 7262 4556 7242 4557 2318 4557 7243 4557 7243 4558 2318 4558 2319 4558 7243 4559 2319 4559 2320 4559 2320 4560 2319 4560 2322 4560 2320 4561 2322 4561 2321 4561 2321 4562 2322 4562 2323 4562 2321 4563 2323 4563 2324 4563 2324 4564 2323 4564 2315 4564 2324 4565 2315 4565 7246 4565 7246 4566 2315 4566 2325 4566 7246 4567 2325 4567 7251 4567 7251 4568 2325 4568 7252 4568 2329 4569 7241 4569 2331 4569 2331 4570 7241 4570 2326 4570 2331 4571 2326 4571 2332 4571 2332 4572 2326 4572 6591 4572 2332 4573 6591 4573 2327 4573 2327 4574 6591 4574 6589 4574 2327 4575 6589 4575 2335 4575 2335 4576 6589 4576 6592 4576 2335 4577 6592 4577 2328 4577 2328 4578 6592 4578 6611 4578 2328 4579 6611 4579 2336 4579 2336 4580 6611 4580 6610 4580 7223 4581 2329 4581 2330 4581 2330 4582 2329 4582 2331 4582 2330 4583 2331 4583 2333 4583 2333 4584 2331 4584 2332 4584 2333 4585 2332 4585 7218 4585 7218 4586 2332 4586 2327 4586 7218 4587 2327 4587 7217 4587 7217 4588 2327 4588 2335 4588 7217 4589 2335 4589 2334 4589 2334 4590 2335 4590 2328 4590 2334 4591 2328 4591 7227 4591 7227 4592 2328 4592 2336 4592 2337 4593 6542 4593 2343 4593 2343 4594 6542 4594 2338 4594 2343 4595 2338 4595 2339 4595 2339 4596 2338 4596 6553 4596 2339 4597 6553 4597 2344 4597 2344 4598 6553 4598 6551 4598 2344 4599 6551 4599 2347 4599 2347 4600 6551 4600 2340 4600 2347 4601 2340 4601 2349 4601 2349 4602 2340 4602 6549 4602 2349 4603 6549 4603 2341 4603 2341 4604 6549 4604 6548 4604 7190 4605 2337 4605 2342 4605 2342 4606 2337 4606 2343 4606 2342 4607 2343 4607 7192 4607 7192 4608 2343 4608 2339 4608 7192 4609 2339 4609 2345 4609 2345 4610 2339 4610 2344 4610 2345 4611 2344 4611 2346 4611 2346 4612 2344 4612 2347 4612 2346 4613 2347 4613 2348 4613 2348 4614 2347 4614 2349 4614 2348 4615 2349 4615 7196 4615 7196 4616 2349 4616 2341 4616 2350 4617 2388 4617 6737 4617 6737 4618 2388 4618 2351 4618 6737 4619 2351 4619 2352 4619 2351 4620 2391 4620 2352 4620 2352 4621 2391 4621 2353 4621 2352 4622 2353 4622 6738 4622 6738 4623 2353 4623 2392 4623 2392 4624 2394 4624 6738 4624 6738 4625 2394 4625 2354 4625 6738 4626 2354 4626 2355 4626 7185 4627 2356 4627 2398 4627 2398 4628 2356 4628 6739 4628 2398 4629 6739 4629 2396 4629 2396 4630 6739 4630 2355 4630 2396 4631 2355 4631 2357 4631 2357 4632 2355 4632 2354 4632 2358 4633 6593 4633 2414 4633 2414 4634 6593 4634 6595 4634 2414 4635 6595 4635 2359 4635 2359 4636 6595 4636 6615 4636 2359 4637 6615 4637 2360 4637 2360 4638 6615 4638 6614 4638 2360 4639 6614 4639 2413 4639 2413 4640 6614 4640 6613 4640 2413 4641 6613 4641 2411 4641 2411 4642 6613 4642 6741 4642 2411 4643 6741 4643 2409 4643 2409 4644 6741 4644 2361 4644 2409 4645 2361 4645 2408 4645 2408 4646 2361 4646 6612 4646 6634 4647 7169 4647 2428 4647 2428 4648 2430 4648 6634 4648 6634 4649 2430 4649 2362 4649 6634 4650 2362 4650 2364 4650 2362 4651 2363 4651 2364 4651 2364 4652 2363 4652 2366 4652 2364 4653 2366 4653 2365 4653 2366 4654 2432 4654 2365 4654 2365 4655 2432 4655 2433 4655 2365 4656 2433 4656 2367 4656 2367 4657 2433 4657 2434 4657 2367 4658 2434 4658 2368 4658 2434 4659 2369 4659 2368 4659 2368 4660 2369 4660 2370 4660 2368 4661 2370 4661 2372 4661 7174 4662 7175 4662 2371 4662 2371 4663 7175 4663 2372 4663 2371 4664 2372 4664 2373 4664 2373 4665 2372 4665 2370 4665 6792 4666 7166 4666 2374 4666 2374 4667 7166 4667 2450 4667 2374 4668 2450 4668 6541 4668 2450 4669 2451 4669 6541 4669 6541 4670 2451 4670 2452 4670 6541 4671 2452 4671 2377 4671 2377 4672 2452 4672 2375 4672 2375 4673 2376 4673 2377 4673 2377 4674 2376 4674 2379 4674 2377 4675 2379 4675 6556 4675 2458 4676 2378 4676 2457 4676 2457 4677 2378 4677 6555 4677 2457 4678 6555 4678 2455 4678 2455 4679 6555 4679 6556 4679 2455 4680 6556 4680 2453 4680 2453 4681 6556 4681 2379 4681 2389 4682 4327 4682 2380 4682 2380 4683 4327 4683 4326 4683 2380 4684 4326 4684 2390 4684 2390 4685 4326 4685 4325 4685 2390 4686 4325 4686 2393 4686 2393 4687 4325 4687 2381 4687 2393 4688 2381 4688 2382 4688 2382 4689 2381 4689 2383 4689 2382 4690 2383 4690 2395 4690 2395 4691 2383 4691 2384 4691 2395 4692 2384 4692 2385 4692 2385 4693 2384 4693 2386 4693 2385 4694 2386 4694 2397 4694 2397 4695 2386 4695 2387 4695 2388 4696 2389 4696 2380 4696 2388 4697 2380 4697 2351 4697 2351 4698 2380 4698 2390 4698 2351 4699 2390 4699 2391 4699 2391 4700 2390 4700 2353 4700 2353 4701 2390 4701 2393 4701 2353 4702 2393 4702 2392 4702 2392 4703 2393 4703 2394 4703 2394 4704 2393 4704 2382 4704 2394 4705 2382 4705 2354 4705 2354 4706 2382 4706 2357 4706 2357 4707 2382 4707 2395 4707 2357 4708 2395 4708 2396 4708 2396 4709 2395 4709 2385 4709 2396 4710 2385 4710 2398 4710 2398 4711 2385 4711 2397 4711 2398 4712 2397 4712 7185 4712 2410 4713 2400 4713 2399 4713 2399 4714 2400 4714 2401 4714 2399 4715 2401 4715 2412 4715 2412 4716 2401 4716 2402 4716 2412 4717 2402 4717 2403 4717 2403 4718 2402 4718 4314 4718 2403 4719 4314 4719 2404 4719 2404 4720 4314 4720 2405 4720 2404 4721 2405 4721 2406 4721 2406 4722 2405 4722 4322 4722 2406 4723 4322 4723 2415 4723 2415 4724 4322 4724 2407 4724 2415 4725 2407 4725 7138 4725 7138 4726 2407 4726 4320 4726 2408 4727 2410 4727 2409 4727 2409 4728 2410 4728 2399 4728 2409 4729 2399 4729 2411 4729 2411 4730 2399 4730 2412 4730 2411 4731 2412 4731 2413 4731 2413 4732 2412 4732 2403 4732 2413 4733 2403 4733 2360 4733 2360 4734 2403 4734 2404 4734 2360 4735 2404 4735 2359 4735 2359 4736 2404 4736 2406 4736 2359 4737 2406 4737 2414 4737 2414 4738 2406 4738 2415 4738 2414 4739 2415 4739 2358 4739 2358 4740 2415 4740 7138 4740 4302 4741 4313 4741 7128 4741 7128 4742 2416 4742 4302 4742 4302 4743 2416 4743 2417 4743 4302 4744 2417 4744 2418 4744 2417 4745 2419 4745 2418 4745 2418 4746 2419 4746 2437 4746 2418 4747 2437 4747 2420 4747 2420 4748 2437 4748 2436 4748 2420 4749 2436 4749 2421 4749 2436 4750 2435 4750 2421 4750 2421 4751 2435 4751 2422 4751 2421 4752 2422 4752 2423 4752 2422 4753 2431 4753 2423 4753 2423 4754 2431 4754 2427 4754 2423 4755 2427 4755 2424 4755 7136 4756 2425 4756 2429 4756 2429 4757 2425 4757 2424 4757 2429 4758 2424 4758 2426 4758 2426 4759 2424 4759 2427 4759 2428 4760 7136 4760 2430 4760 2430 4761 7136 4761 2429 4761 2430 4762 2429 4762 2362 4762 2362 4763 2429 4763 2426 4763 2362 4764 2426 4764 2363 4764 2363 4765 2426 4765 2427 4765 2363 4766 2427 4766 2366 4766 2366 4767 2427 4767 2431 4767 2366 4768 2431 4768 2432 4768 2432 4769 2431 4769 2422 4769 2432 4770 2422 4770 2433 4770 2433 4771 2422 4771 2435 4771 2433 4772 2435 4772 2434 4772 2434 4773 2435 4773 2436 4773 2434 4774 2436 4774 2369 4774 2369 4775 2436 4775 2437 4775 2369 4776 2437 4776 2370 4776 2370 4777 2437 4777 2419 4777 2370 4778 2419 4778 2373 4778 2373 4779 2419 4779 2417 4779 2373 4780 2417 4780 2371 4780 2371 4781 2417 4781 2416 4781 2371 4782 2416 4782 7174 4782 7174 4783 2416 4783 7128 4783 2448 4784 2438 4784 2449 4784 2449 4785 2438 4785 4292 4785 2449 4786 4292 4786 2439 4786 2439 4787 4292 4787 2440 4787 2439 4788 2440 4788 2442 4788 2442 4789 2440 4789 2441 4789 2442 4790 2441 4790 2454 4790 2454 4791 2441 4791 2444 4791 2454 4792 2444 4792 2443 4792 2443 4793 2444 4793 2445 4793 2443 4794 2445 4794 2456 4794 2456 4795 2445 4795 2446 4795 2456 4796 2446 4796 2447 4796 2447 4797 2446 4797 4299 4797 7166 4798 2448 4798 2449 4798 7166 4799 2449 4799 2450 4799 2450 4800 2449 4800 2439 4800 2450 4801 2439 4801 2451 4801 2451 4802 2439 4802 2452 4802 2452 4803 2439 4803 2442 4803 2452 4804 2442 4804 2375 4804 2375 4805 2442 4805 2376 4805 2376 4806 2442 4806 2454 4806 2376 4807 2454 4807 2379 4807 2379 4808 2454 4808 2453 4808 2453 4809 2454 4809 2443 4809 2453 4810 2443 4810 2455 4810 2455 4811 2443 4811 2456 4811 2455 4812 2456 4812 2457 4812 2457 4813 2456 4813 2447 4813 2457 4814 2447 4814 2458 4814 7111 4815 4205 4815 2459 4815 2459 4816 4205 4816 4204 4816 2459 4817 4204 4817 2460 4817 2460 4818 4204 4818 4203 4818 2460 4819 4203 4819 2464 4819 2464 4820 4203 4820 4202 4820 2464 4821 4202 4821 2466 4821 2466 4822 4202 4822 4201 4822 2466 4823 4201 4823 2468 4823 2468 4824 4201 4824 4198 4824 2468 4825 4198 4825 2461 4825 2461 4826 4198 4826 4213 4826 2461 4827 4213 4827 7099 4827 7099 4828 4213 4828 4212 4828 2462 4829 7111 4829 2463 4829 2463 4830 7111 4830 2459 4830 2463 4831 2459 4831 2474 4831 2474 4832 2459 4832 2460 4832 2474 4833 2460 4833 2472 4833 2472 4834 2460 4834 2464 4834 2472 4835 2464 4835 2465 4835 2465 4836 2464 4836 2466 4836 2465 4837 2466 4837 2467 4837 2467 4838 2466 4838 2468 4838 2467 4839 2468 4839 2470 4839 2470 4840 2468 4840 2461 4840 2470 4841 2461 4841 2469 4841 2469 4842 2461 4842 7099 4842 2469 4843 7045 4843 2470 4843 2470 4844 7045 4844 7047 4844 2470 4845 7047 4845 2467 4845 2467 4846 7047 4846 7032 4846 2467 4847 7032 4847 2465 4847 2465 4848 7032 4848 2471 4848 2465 4849 2471 4849 2472 4849 2472 4850 2471 4850 2473 4850 2472 4851 2473 4851 2474 4851 2474 4852 2473 4852 7036 4852 2474 4853 7036 4853 2463 4853 2463 4854 7036 4854 2475 4854 2463 4855 2475 4855 2462 4855 2462 4856 2475 4856 7038 4856 7086 4857 4226 4857 2476 4857 2476 4858 4226 4858 4224 4858 2476 4859 4224 4859 2483 4859 2483 4860 4224 4860 4223 4860 2483 4861 4223 4861 2484 4861 2484 4862 4223 4862 2477 4862 2484 4863 2477 4863 2478 4863 2478 4864 2477 4864 4220 4864 2478 4865 4220 4865 2485 4865 2485 4866 4220 4866 2480 4866 2485 4867 2480 4867 2479 4867 2479 4868 2480 4868 7087 4868 2481 4869 7086 4869 2482 4869 2482 4870 7086 4870 2476 4870 2482 4871 2476 4871 2490 4871 2490 4872 2476 4872 2483 4872 2490 4873 2483 4873 2489 4873 2489 4874 2483 4874 2484 4874 2489 4875 2484 4875 2488 4875 2488 4876 2484 4876 2478 4876 2488 4877 2478 4877 2487 4877 2487 4878 2478 4878 2485 4878 2487 4879 2485 4879 7079 4879 7079 4880 2485 4880 2479 4880 7079 4881 2486 4881 2487 4881 2487 4882 2486 4882 7006 4882 2487 4883 7006 4883 2488 4883 2488 4884 7006 4884 7008 4884 2488 4885 7008 4885 2489 4885 2489 4886 7008 4886 7009 4886 2489 4887 7009 4887 2490 4887 2490 4888 7009 4888 7011 4888 2490 4889 7011 4889 2482 4889 2482 4890 7011 4890 2491 4890 2482 4891 2491 4891 2481 4891 2481 4892 2491 4892 7072 4892 2498 4893 4281 4893 2499 4893 2499 4894 4281 4894 4279 4894 2499 4895 4279 4895 2492 4895 2492 4896 4279 4896 2493 4896 2492 4897 2493 4897 2502 4897 2502 4898 2493 4898 4278 4898 2502 4899 4278 4899 2503 4899 2503 4900 4278 4900 2494 4900 2503 4901 2494 4901 2495 4901 2495 4902 2494 4902 4289 4902 2495 4903 4289 4903 2496 4903 2496 4904 4289 4904 4287 4904 2496 4905 4287 4905 7064 4905 7064 4906 4287 4906 7065 4906 2497 4907 2498 4907 2500 4907 2500 4908 2498 4908 2499 4908 2500 4909 2499 4909 2501 4909 2501 4910 2499 4910 2492 4910 2501 4911 2492 4911 2509 4911 2509 4912 2492 4912 2502 4912 2509 4913 2502 4913 2507 4913 2507 4914 2502 4914 2503 4914 2507 4915 2503 4915 2505 4915 2505 4916 2503 4916 2495 4916 2505 4917 2495 4917 2504 4917 2504 4918 2495 4918 2496 4918 2504 4919 2496 4919 7059 4919 7059 4920 2496 4920 7064 4920 7059 4921 6985 4921 2504 4921 2504 4922 6985 4922 6986 4922 2504 4923 6986 4923 2505 4923 2505 4924 6986 4924 2506 4924 2505 4925 2506 4925 2507 4925 2507 4926 2506 4926 2508 4926 2507 4927 2508 4927 2509 4927 2509 4928 2508 4928 6975 4928 2509 4929 6975 4929 2501 4929 2501 4930 6975 4930 6976 4930 2501 4931 6976 4931 2500 4931 2500 4932 6976 4932 2510 4932 2500 4933 2510 4933 2497 4933 2497 4934 2510 4934 6977 4934 2520 4935 6506 4935 2511 4935 2511 4936 6506 4936 2512 4936 2511 4937 2512 4937 2513 4937 2513 4938 2512 4938 2514 4938 2513 4939 2514 4939 2522 4939 2522 4940 2514 4940 6479 4940 2522 4941 6479 4941 2515 4941 2515 4942 6479 4942 6477 4942 2515 4943 6477 4943 2517 4943 2517 4944 6477 4944 2516 4944 2517 4945 2516 4945 2524 4945 2524 4946 2516 4946 2518 4946 2524 4947 2518 4947 2519 4947 2519 4948 2518 4948 6475 4948 7054 4949 2520 4949 7033 4949 7033 4950 2520 4950 2511 4950 7033 4951 2511 4951 2521 4951 2521 4952 2511 4952 2513 4952 2521 4953 2513 4953 7034 4953 7034 4954 2513 4954 2522 4954 7034 4955 2522 4955 2523 4955 2523 4956 2522 4956 2515 4956 2523 4957 2515 4957 7035 4957 7035 4958 2515 4958 2517 4958 7035 4959 2517 4959 7037 4959 7037 4960 2517 4960 2524 4960 7037 4961 2524 4961 2525 4961 2525 4962 2524 4962 2519 4962 2534 4963 6488 4963 2526 4963 2526 4964 6488 4964 2527 4964 2526 4965 2527 4965 2528 4965 2528 4966 2527 4966 2529 4966 2528 4967 2529 4967 2536 4967 2536 4968 2529 4968 2530 4968 2536 4969 2530 4969 2531 4969 2531 4970 2530 4970 6497 4970 2531 4971 6497 4971 2532 4971 2532 4972 6497 4972 2533 4972 2532 4973 2533 4973 7027 4973 7027 4974 2533 4974 7028 4974 7026 4975 2534 4975 7007 4975 7007 4976 2534 4976 2526 4976 7007 4977 2526 4977 2535 4977 2535 4978 2526 4978 2528 4978 2535 4979 2528 4979 7010 4979 7010 4980 2528 4980 2536 4980 7010 4981 2536 4981 2537 4981 2537 4982 2536 4982 2531 4982 2537 4983 2531 4983 7012 4983 7012 4984 2531 4984 2532 4984 7012 4985 2532 4985 7014 4985 7014 4986 2532 4986 7027 4986 6995 4987 7002 4987 2543 4987 2543 4988 7002 4988 6662 4988 2543 4989 6662 4989 2545 4989 2545 4990 6662 4990 2538 4990 2545 4991 2538 4991 2546 4991 2546 4992 2538 4992 6661 4992 2546 4993 6661 4993 2540 4993 2540 4994 6661 4994 2539 4994 2540 4995 2539 4995 2549 4995 2549 4996 2539 4996 6660 4996 2549 4997 6660 4997 2542 4997 2542 4998 6660 4998 2541 4998 2542 4999 2541 4999 2552 4999 2552 5000 2541 5000 6996 5000 6994 5001 6995 5001 6987 5001 6987 5002 6995 5002 2543 5002 6987 5003 2543 5003 2544 5003 2544 5004 2543 5004 2545 5004 2544 5005 2545 5005 6988 5005 6988 5006 2545 5006 2546 5006 6988 5007 2546 5007 2547 5007 2547 5008 2546 5008 2540 5008 2547 5009 2540 5009 2548 5009 2548 5010 2540 5010 2549 5010 2548 5011 2549 5011 2550 5011 2550 5012 2549 5012 2542 5012 2550 5013 2542 5013 2551 5013 2551 5014 2542 5014 2552 5014 6973 5015 6689 5015 2553 5015 2553 5016 6689 5016 6687 5016 2553 5017 6687 5017 2554 5017 2554 5018 6687 5018 2555 5018 2554 5019 2555 5019 2557 5019 2557 5020 2555 5020 2556 5020 2557 5021 2556 5021 2558 5021 2558 5022 2556 5022 6686 5022 2558 5023 6686 5023 2559 5023 2559 5024 6686 5024 2560 5024 2559 5025 2560 5025 2561 5025 2561 5026 2560 5026 2562 5026 2561 5027 2562 5027 9262 5027 9262 5028 2562 5028 6685 5028 9264 5029 6520 5029 9265 5029 9265 5030 6520 5030 6519 5030 9265 5031 6519 5031 9268 5031 9268 5032 6519 5032 2563 5032 9268 5033 2563 5033 2564 5033 2564 5034 2563 5034 2565 5034 2564 5035 2565 5035 2566 5035 2566 5036 2565 5036 2567 5036 2566 5037 2567 5037 9269 5037 9269 5038 2567 5038 6513 5038 9269 5039 6513 5039 2568 5039 2568 5040 6513 5040 6514 5040 6961 5041 2569 5041 2570 5041 2570 5042 2569 5042 2571 5042 2570 5043 2571 5043 2572 5043 2572 5044 2571 5044 2573 5044 2572 5045 2573 5045 2574 5045 2574 5046 2573 5046 6670 5046 2574 5047 6670 5047 9271 5047 9271 5048 6670 5048 6793 5048 9271 5049 6793 5049 9275 5049 9275 5050 6793 5050 6673 5050 9275 5051 6673 5051 9274 5051 9274 5052 6673 5052 6672 5052 9274 5053 6672 5053 9273 5053 9273 5054 6672 5054 2575 5054 6954 5055 6955 5055 2576 5055 2576 5056 6955 5056 6705 5056 2576 5057 6705 5057 2577 5057 2577 5058 6705 5058 2578 5058 2577 5059 2578 5059 9277 5059 9277 5060 2578 5060 2579 5060 9277 5061 2579 5061 9278 5061 9278 5062 2579 5062 2580 5062 9278 5063 2580 5063 2581 5063 2581 5064 2580 5064 2582 5064 2581 5065 2582 5065 9276 5065 9276 5066 2582 5066 6704 5066 9276 5067 6704 5067 2583 5067 2583 5068 6704 5068 6706 5068 6949 5069 2584 5069 2585 5069 2585 5070 2584 5070 2586 5070 2585 5071 2586 5071 9283 5071 9283 5072 2586 5072 2587 5072 9283 5073 2587 5073 9284 5073 9284 5074 2587 5074 2588 5074 9284 5075 2588 5075 9282 5075 9282 5076 2588 5076 6832 5076 9282 5077 6832 5077 2589 5077 2589 5078 6832 5078 2590 5078 2589 5079 2590 5079 2591 5079 2591 5080 2590 5080 6697 5080 2591 5081 6697 5081 2592 5081 2592 5082 6697 5082 2593 5082 6940 5083 6941 5083 9287 5083 9287 5084 6941 5084 6723 5084 9287 5085 6723 5085 2594 5085 2594 5086 6723 5086 2595 5086 2594 5087 2595 5087 2596 5087 2596 5088 2595 5088 6722 5088 2596 5089 6722 5089 9286 5089 9286 5090 6722 5090 6721 5090 9286 5091 6721 5091 2597 5091 2597 5092 6721 5092 6720 5092 2597 5093 6720 5093 6934 5093 6934 5094 6720 5094 6719 5094 9295 5095 6729 5095 2598 5095 2598 5096 6729 5096 2600 5096 2598 5097 2600 5097 2599 5097 2599 5098 2600 5098 2601 5098 2599 5099 2601 5099 2602 5099 2602 5100 2601 5100 2603 5100 2602 5101 2603 5101 9291 5101 9291 5102 2603 5102 2604 5102 9291 5103 2604 5103 9293 5103 9293 5104 2604 5104 2606 5104 9293 5105 2606 5105 2605 5105 2605 5106 2606 5106 2607 5106 2605 5107 2607 5107 9292 5107 9292 5108 2607 5108 6927 5108 6925 5109 2608 5109 9302 5109 9302 5110 2608 5110 6601 5110 9302 5111 6601 5111 2609 5111 2609 5112 6601 5112 6733 5112 2609 5113 6733 5113 2610 5113 2610 5114 6733 5114 6606 5114 2610 5115 6606 5115 9296 5115 9296 5116 6606 5116 2611 5116 9296 5117 2611 5117 9301 5117 9301 5118 2611 5118 2612 5118 9301 5119 2612 5119 2613 5119 2613 5120 2612 5120 6604 5120 2613 5121 6604 5121 9300 5121 9300 5122 6604 5122 6920 5122 6919 5123 6747 5123 9305 5123 9305 5124 6747 5124 2615 5124 9305 5125 2615 5125 2614 5125 2614 5126 2615 5126 2616 5126 2614 5127 2616 5127 9307 5127 9307 5128 2616 5128 2617 5128 9307 5129 2617 5129 9308 5129 9308 5130 2617 5130 6749 5130 9308 5131 6749 5131 9303 5131 9303 5132 6749 5132 2618 5132 9303 5133 2618 5133 2619 5133 2619 5134 2618 5134 2620 5134 2619 5135 2620 5135 9310 5135 9310 5136 2620 5136 6746 5136 9313 5137 2621 5137 2623 5137 2623 5138 2621 5138 2622 5138 2623 5139 2622 5139 2624 5139 2624 5140 2622 5140 6750 5140 2624 5141 6750 5141 9312 5141 9312 5142 6750 5142 6754 5142 9312 5143 6754 5143 9314 5143 9314 5144 6754 5144 2626 5144 9314 5145 2626 5145 2625 5145 2625 5146 2626 5146 6751 5146 2625 5147 6751 5147 2627 5147 2627 5148 6751 5148 6909 5148 2628 5149 6503 5149 2675 5149 2675 5150 6503 5150 2629 5150 2675 5151 2629 5151 2672 5151 2672 5152 2629 5152 2631 5152 2672 5153 2631 5153 2630 5153 2630 5154 2631 5154 6834 5154 2630 5155 6834 5155 2668 5155 2668 5156 6834 5156 2632 5156 2668 5157 2632 5157 2667 5157 2667 5158 2632 5158 2633 5158 2667 5159 2633 5159 2665 5159 2665 5160 2633 5160 6508 5160 2665 5161 6508 5161 2634 5161 2634 5162 6508 5162 6903 5162 6867 5163 2635 5163 2693 5163 2693 5164 2635 5164 6502 5164 2693 5165 6502 5165 2636 5165 2636 5166 6502 5166 6511 5166 2636 5167 6511 5167 2689 5167 2689 5168 6511 5168 2637 5168 2689 5169 2637 5169 2687 5169 2687 5170 2637 5170 2638 5170 2687 5171 2638 5171 2684 5171 2684 5172 2638 5172 2639 5172 2684 5173 2639 5173 2640 5173 2640 5174 2639 5174 6899 5174 6897 5175 2641 5175 2707 5175 2707 5176 2641 5176 6666 5176 2707 5177 6666 5177 2706 5177 2706 5178 6666 5178 2642 5178 2706 5179 2642 5179 2705 5179 2705 5180 2642 5180 2643 5180 2705 5181 2643 5181 2644 5181 2644 5182 2643 5182 6499 5182 2644 5183 6499 5183 2703 5183 2703 5184 6499 5184 2645 5184 2703 5185 2645 5185 2701 5185 2701 5186 2645 5186 2646 5186 2701 5187 2646 5187 2647 5187 2647 5188 2646 5188 6496 5188 2649 5189 6539 5189 2648 5189 2648 5190 2719 5190 2649 5190 2649 5191 2719 5191 2650 5191 2649 5192 2650 5192 6425 5192 2650 5193 2721 5193 6425 5193 6425 5194 2721 5194 2722 5194 6425 5195 2722 5195 2651 5195 2722 5196 2725 5196 2651 5196 2651 5197 2725 5197 2726 5197 2651 5198 2726 5198 6537 5198 6537 5199 2726 5199 2728 5199 6537 5200 2728 5200 6538 5200 2728 5201 2730 5201 6538 5201 6538 5202 2730 5202 2657 5202 6538 5203 2657 5203 2656 5203 2652 5204 2654 5204 2653 5204 2653 5205 2654 5205 2656 5205 2653 5206 2656 5206 2655 5206 2655 5207 2656 5207 2657 5207 4237 5208 2658 5208 2659 5208 2659 5209 2658 5209 2674 5209 2659 5210 2674 5210 2660 5210 2674 5211 2673 5211 2660 5211 2660 5212 2673 5212 2661 5212 2660 5213 2661 5213 4233 5213 4233 5214 2661 5214 2671 5214 2671 5215 2670 5215 4233 5215 4233 5216 2670 5216 2662 5216 4233 5217 2662 5217 2664 5217 6890 5218 4229 5218 2663 5218 2663 5219 4229 5219 4232 5219 2663 5220 4232 5220 2666 5220 2666 5221 4232 5221 2664 5221 2666 5222 2664 5222 2669 5222 2669 5223 2664 5223 2662 5223 2634 5224 6890 5224 2663 5224 2634 5225 2663 5225 2665 5225 2665 5226 2663 5226 2666 5226 2665 5227 2666 5227 2667 5227 2667 5228 2666 5228 2669 5228 2667 5229 2669 5229 2668 5229 2669 5230 2662 5230 2668 5230 2668 5231 2662 5231 2670 5231 2668 5232 2670 5232 2630 5232 2670 5233 2671 5233 2630 5233 2630 5234 2671 5234 2661 5234 2630 5235 2661 5235 2672 5235 2661 5236 2673 5236 2672 5236 2672 5237 2673 5237 2674 5237 2672 5238 2674 5238 2675 5238 2675 5239 2674 5239 2658 5239 2675 5240 2658 5240 2628 5240 4242 5241 6875 5241 2676 5241 2676 5242 2692 5242 4242 5242 4242 5243 2692 5243 2694 5243 4242 5244 2694 5244 2677 5244 2694 5245 2695 5245 2677 5245 2677 5246 2695 5246 2691 5246 2677 5247 2691 5247 2678 5247 2691 5248 2690 5248 2678 5248 2678 5249 2690 5249 2679 5249 2678 5250 2679 5250 4245 5250 4245 5251 2679 5251 2680 5251 4245 5252 2680 5252 4246 5252 2680 5253 2688 5253 4246 5253 4246 5254 2688 5254 2686 5254 4246 5255 2686 5255 2681 5255 6874 5256 2683 5256 2682 5256 2682 5257 2683 5257 2681 5257 2682 5258 2681 5258 2685 5258 2685 5259 2681 5259 2686 5259 6874 5260 2682 5260 2640 5260 2640 5261 2682 5261 2684 5261 2682 5262 2685 5262 2684 5262 2684 5263 2685 5263 2686 5263 2684 5264 2686 5264 2687 5264 2686 5265 2688 5265 2687 5265 2687 5266 2688 5266 2680 5266 2687 5267 2680 5267 2689 5267 2680 5268 2679 5268 2689 5268 2689 5269 2679 5269 2690 5269 2689 5270 2690 5270 2636 5270 2690 5271 2691 5271 2636 5271 2636 5272 2691 5272 2695 5272 2636 5273 2695 5273 2693 5273 2676 5274 6867 5274 2692 5274 2692 5275 6867 5275 2693 5275 2692 5276 2693 5276 2694 5276 2694 5277 2693 5277 2695 5277 6865 5278 6866 5278 2702 5278 2702 5279 6866 5279 4257 5279 2702 5280 4257 5280 2696 5280 2696 5281 4257 5281 4256 5281 2696 5282 4256 5282 2704 5282 2704 5283 4256 5283 4255 5283 2704 5284 4255 5284 2697 5284 2697 5285 4255 5285 4254 5285 2697 5286 4254 5286 2698 5286 2698 5287 4254 5287 4266 5287 2698 5288 4266 5288 2699 5288 2699 5289 4266 5289 2700 5289 2699 5290 2700 5290 6861 5290 6861 5291 2700 5291 4265 5291 2647 5292 6865 5292 2701 5292 2701 5293 6865 5293 2702 5293 2701 5294 2702 5294 2703 5294 2703 5295 2702 5295 2696 5295 2703 5296 2696 5296 2644 5296 2644 5297 2696 5297 2704 5297 2644 5298 2704 5298 2705 5298 2705 5299 2704 5299 2697 5299 2705 5300 2697 5300 2706 5300 2706 5301 2697 5301 2698 5301 2706 5302 2698 5302 2707 5302 2707 5303 2698 5303 2699 5303 2707 5304 2699 5304 6897 5304 6897 5305 2699 5305 6861 5305 2710 5306 2708 5306 6845 5306 6845 5307 2709 5307 2710 5307 2710 5308 2709 5308 2732 5308 2710 5309 2732 5309 2711 5309 2732 5310 2712 5310 2711 5310 2711 5311 2712 5311 2731 5311 2711 5312 2731 5312 2713 5312 2713 5313 2731 5313 2729 5313 2713 5314 2729 5314 2715 5314 2729 5315 2727 5315 2715 5315 2715 5316 2727 5316 2714 5316 2715 5317 2714 5317 2716 5317 2714 5318 2724 5318 2716 5318 2716 5319 2724 5319 2723 5319 2716 5320 2723 5320 4269 5320 2717 5321 4270 5321 2718 5321 2718 5322 4270 5322 4269 5322 2718 5323 4269 5323 2720 5323 2720 5324 4269 5324 2723 5324 2648 5325 2717 5325 2719 5325 2719 5326 2717 5326 2718 5326 2719 5327 2718 5327 2650 5327 2650 5328 2718 5328 2720 5328 2650 5329 2720 5329 2721 5329 2721 5330 2720 5330 2723 5330 2721 5331 2723 5331 2722 5331 2722 5332 2723 5332 2724 5332 2722 5333 2724 5333 2725 5333 2725 5334 2724 5334 2714 5334 2725 5335 2714 5335 2726 5335 2726 5336 2714 5336 2727 5336 2726 5337 2727 5337 2728 5337 2728 5338 2727 5338 2729 5338 2728 5339 2729 5339 2730 5339 2730 5340 2729 5340 2731 5340 2730 5341 2731 5341 2657 5341 2657 5342 2731 5342 2712 5342 2657 5343 2712 5343 2655 5343 2655 5344 2712 5344 2732 5344 2655 5345 2732 5345 2653 5345 2653 5346 2732 5346 2709 5346 2653 5347 2709 5347 2652 5347 2652 5348 2709 5348 6845 5348 2733 5349 6378 5349 6640 5349 2733 5350 6640 5350 1206 5350 1206 5351 6640 5351 2734 5351 1206 5352 2734 5352 1207 5352 1207 5353 2734 5353 2735 5353 1207 5354 2735 5354 1208 5354 1208 5355 2735 5355 6779 5355 1208 5356 6779 5356 1209 5356 1209 5357 6779 5357 6643 5357 1209 5358 6643 5358 2736 5358 2736 5359 6643 5359 6762 5359 2736 5360 6762 5360 1212 5360 1212 5361 6762 5361 2737 5361 1212 5362 2737 5362 7925 5362 8037 5363 2738 5363 2740 5363 8037 5364 2740 5364 2739 5364 2739 5365 2740 5365 2741 5365 2739 5366 2741 5366 2742 5366 2742 5367 2741 5367 1232 5367 2742 5368 1232 5368 2743 5368 2743 5369 1232 5369 1230 5369 2743 5370 1230 5370 1737 5370 1737 5371 1230 5371 2744 5371 1737 5372 2744 5372 2745 5372 2745 5373 2744 5373 1229 5373 2745 5374 1229 5374 2746 5374 2746 5375 1229 5375 1228 5375 2746 5376 1228 5376 2747 5376 2747 5377 1228 5377 1227 5377 2747 5378 1227 5378 2749 5378 2749 5379 1227 5379 2748 5379 2749 5380 2748 5380 1738 5380 1738 5381 2748 5381 1224 5381 1738 5382 1224 5382 1740 5382 1740 5383 1224 5383 2750 5383 1740 5384 2750 5384 2751 5384 2751 5385 2750 5385 1222 5385 2751 5386 1222 5386 1742 5386 1742 5387 1222 5387 1221 5387 1742 5388 1221 5388 1743 5388 1743 5389 1221 5389 1219 5389 1743 5390 1219 5390 2752 5390 2752 5391 1219 5391 2753 5391 2752 5392 2753 5392 1745 5392 1745 5393 2753 5393 2754 5393 1745 5394 2754 5394 2755 5394 2755 5395 2754 5395 1215 5395 2755 5396 1215 5396 2756 5396 2756 5397 1215 5397 1214 5397 2756 5398 1214 5398 2757 5398 2757 5399 1214 5399 9196 5399 2757 5400 9196 5400 8017 5400 8843 5401 8038 5401 1734 5401 8843 5402 1734 5402 2759 5402 2759 5403 1734 5403 2758 5403 2759 5404 2758 5404 2760 5404 2760 5405 2758 5405 2761 5405 2760 5406 2761 5406 1554 5406 1554 5407 2761 5407 2762 5407 1554 5408 2762 5408 2763 5408 2763 5409 2762 5409 1731 5409 2763 5410 1731 5410 2764 5410 2764 5411 1731 5411 2765 5411 2764 5412 2765 5412 2766 5412 2766 5413 2765 5413 2767 5413 2766 5414 2767 5414 1558 5414 1558 5415 2767 5415 2768 5415 1558 5416 2768 5416 1561 5416 1561 5417 2768 5417 1727 5417 1561 5418 1727 5418 2769 5418 2769 5419 1727 5419 2770 5419 2769 5420 2770 5420 2771 5420 2771 5421 2770 5421 1726 5421 2771 5422 1726 5422 1563 5422 1563 5423 1726 5423 2772 5423 1563 5424 2772 5424 2773 5424 2773 5425 2772 5425 1724 5425 2773 5426 1724 5426 1565 5426 1565 5427 1724 5427 2774 5427 1565 5428 2774 5428 2775 5428 2775 5429 2774 5429 1722 5429 2775 5430 1722 5430 2776 5430 2776 5431 1722 5431 1721 5431 2776 5432 1721 5432 2777 5432 2777 5433 1721 5433 1719 5433 2777 5434 1719 5434 1568 5434 1568 5435 1719 5435 2778 5435 1568 5436 2778 5436 1569 5436 1569 5437 2778 5437 2779 5437 1569 5438 2779 5438 1570 5438 2781 5439 1552 5439 2780 5439 2781 5440 2780 5440 1516 5440 1516 5441 2780 5441 2782 5441 1516 5442 2782 5442 1517 5442 1517 5443 2782 5443 2783 5443 1517 5444 2783 5444 2784 5444 2784 5445 2783 5445 1549 5445 2784 5446 1549 5446 1518 5446 1518 5447 1549 5447 2785 5447 1518 5448 2785 5448 2786 5448 2786 5449 2785 5449 2787 5449 2786 5450 2787 5450 2788 5450 2788 5451 2787 5451 2789 5451 2788 5452 2789 5452 1521 5452 1521 5453 2789 5453 2790 5453 1521 5454 2790 5454 1522 5454 1522 5455 2790 5455 1546 5455 1522 5456 1546 5456 2791 5456 2791 5457 1546 5457 2792 5457 2791 5458 2792 5458 1524 5458 1524 5459 2792 5459 1545 5459 1524 5460 1545 5460 2793 5460 2793 5461 1545 5461 1543 5461 2793 5462 1543 5462 2794 5462 2794 5463 1543 5463 1542 5463 2794 5464 1542 5464 1527 5464 1527 5465 1542 5465 1541 5465 1527 5466 1541 5466 1529 5466 1529 5467 1541 5467 1540 5467 1529 5468 1540 5468 1531 5468 1531 5469 1540 5469 1539 5469 1531 5470 1539 5470 1533 5470 1533 5471 1539 5471 2795 5471 1533 5472 2795 5472 1534 5472 1534 5473 2795 5473 2796 5473 1534 5474 2796 5474 1536 5474 1536 5475 2796 5475 8859 5475 1536 5476 8859 5476 6322 5476 8920 5477 6320 5477 1514 5477 8920 5478 1514 5478 2797 5478 2797 5479 1514 5479 2798 5479 2797 5480 2798 5480 2799 5480 2799 5481 2798 5481 2800 5481 2799 5482 2800 5482 1476 5482 1476 5483 2800 5483 1511 5483 1476 5484 1511 5484 2801 5484 2801 5485 1511 5485 2802 5485 2801 5486 2802 5486 1479 5486 1479 5487 2802 5487 1508 5487 1479 5488 1508 5488 1481 5488 1481 5489 1508 5489 1507 5489 1481 5490 1507 5490 1482 5490 1482 5491 1507 5491 1505 5491 1482 5492 1505 5492 2803 5492 2803 5493 1505 5493 2804 5493 2803 5494 2804 5494 1484 5494 1484 5495 2804 5495 2805 5495 1484 5496 2805 5496 2806 5496 2806 5497 2805 5497 1503 5497 2806 5498 1503 5498 2807 5498 2807 5499 1503 5499 1502 5499 2807 5500 1502 5500 2808 5500 2808 5501 1502 5501 2809 5501 2808 5502 2809 5502 2810 5502 2810 5503 2809 5503 2811 5503 2810 5504 2811 5504 1488 5504 1488 5505 2811 5505 1499 5505 1488 5506 1499 5506 1489 5506 1489 5507 1499 5507 1497 5507 1489 5508 1497 5508 1491 5508 1491 5509 1497 5509 1494 5509 1491 5510 1494 5510 2812 5510 2812 5511 1494 5511 2813 5511 2812 5512 2813 5512 2814 5512 2814 5513 2813 5513 6301 5513 2814 5514 6301 5514 8903 5514 8966 5515 1474 5515 1473 5515 8966 5516 1473 5516 1429 5516 1429 5517 1473 5517 1472 5517 1429 5518 1472 5518 1431 5518 1431 5519 1472 5519 1469 5519 1431 5520 1469 5520 2815 5520 2815 5521 1469 5521 2816 5521 2815 5522 2816 5522 1433 5522 1433 5523 2816 5523 2817 5523 1433 5524 2817 5524 2818 5524 2818 5525 2817 5525 2819 5525 2818 5526 2819 5526 1436 5526 1436 5527 2819 5527 1468 5527 1436 5528 1468 5528 1438 5528 1438 5529 1468 5529 2820 5529 1438 5530 2820 5530 2821 5530 2821 5531 2820 5531 1467 5531 2821 5532 1467 5532 1441 5532 1441 5533 1467 5533 1466 5533 1441 5534 1466 5534 1442 5534 1442 5535 1466 5535 1465 5535 1442 5536 1465 5536 1444 5536 1444 5537 1465 5537 2823 5537 1444 5538 2823 5538 2822 5538 2822 5539 2823 5539 2825 5539 2822 5540 2825 5540 2824 5540 2824 5541 2825 5541 1460 5541 2824 5542 1460 5542 1447 5542 1447 5543 1460 5543 1458 5543 1447 5544 1458 5544 1448 5544 1448 5545 1458 5545 1457 5545 1448 5546 1457 5546 1449 5546 1449 5547 1457 5547 1456 5547 1449 5548 1456 5548 2826 5548 2826 5549 1456 5549 1454 5549 2826 5550 1454 5550 1453 5550 1453 5551 1454 5551 2827 5551 1453 5552 2827 5552 8942 5552 2828 5553 8968 5553 2829 5553 2828 5554 2829 5554 2830 5554 2830 5555 2829 5555 1424 5555 2830 5556 1424 5556 1387 5556 1387 5557 1424 5557 1423 5557 1387 5558 1423 5558 1389 5558 1389 5559 1423 5559 1420 5559 1389 5560 1420 5560 2831 5560 2831 5561 1420 5561 1419 5561 2831 5562 1419 5562 2832 5562 2832 5563 1419 5563 1417 5563 2832 5564 1417 5564 1391 5564 1391 5565 1417 5565 2833 5565 1391 5566 2833 5566 2835 5566 2835 5567 2833 5567 2834 5567 2835 5568 2834 5568 1392 5568 1392 5569 2834 5569 1415 5569 1392 5570 1415 5570 2836 5570 2836 5571 1415 5571 1414 5571 2836 5572 1414 5572 2837 5572 2837 5573 1414 5573 2838 5573 2837 5574 2838 5574 1394 5574 1394 5575 2838 5575 2840 5575 1394 5576 2840 5576 2839 5576 2839 5577 2840 5577 2841 5577 2839 5578 2841 5578 2842 5578 2842 5579 2841 5579 1411 5579 2842 5580 1411 5580 1397 5580 1397 5581 1411 5581 2843 5581 1397 5582 2843 5582 1399 5582 1399 5583 2843 5583 1408 5583 1399 5584 1408 5584 2845 5584 2845 5585 1408 5585 2844 5585 2845 5586 2844 5586 2846 5586 2846 5587 2844 5587 1405 5587 2846 5588 1405 5588 2848 5588 2848 5589 1405 5589 2847 5589 2848 5590 2847 5590 1403 5590 9040 5591 6265 5591 1384 5591 9040 5592 1384 5592 1351 5592 1351 5593 1384 5593 2849 5593 1351 5594 2849 5594 2850 5594 2850 5595 2849 5595 2851 5595 2850 5596 2851 5596 2852 5596 2852 5597 2851 5597 1382 5597 2852 5598 1382 5598 1356 5598 1356 5599 1382 5599 2853 5599 1356 5600 2853 5600 2854 5600 2854 5601 2853 5601 1379 5601 2854 5602 1379 5602 1357 5602 1357 5603 1379 5603 2855 5603 1357 5604 2855 5604 2856 5604 2856 5605 2855 5605 1377 5605 2856 5606 1377 5606 1359 5606 1359 5607 1377 5607 1375 5607 1359 5608 1375 5608 2857 5608 2857 5609 1375 5609 2858 5609 2857 5610 2858 5610 1361 5610 1361 5611 2858 5611 2860 5611 1361 5612 2860 5612 2859 5612 2859 5613 2860 5613 2861 5613 2859 5614 2861 5614 2862 5614 2862 5615 2861 5615 1373 5615 2862 5616 1373 5616 2863 5616 2863 5617 1373 5617 1372 5617 2863 5618 1372 5618 2864 5618 2864 5619 1372 5619 2865 5619 2864 5620 2865 5620 1362 5620 1362 5621 2865 5621 2866 5621 1362 5622 2866 5622 2867 5622 2867 5623 2866 5623 1370 5623 2867 5624 1370 5624 1366 5624 1366 5625 1370 5625 2868 5625 1366 5626 2868 5626 1367 5626 1367 5627 2868 5627 2869 5627 1367 5628 2869 5628 1368 5628 6248 5629 1348 5629 1347 5629 6248 5630 1347 5630 2870 5630 2870 5631 1347 5631 2871 5631 2870 5632 2871 5632 2872 5632 2872 5633 2871 5633 1346 5633 2872 5634 1346 5634 2873 5634 2873 5635 1346 5635 1344 5635 2873 5636 1344 5636 1316 5636 1316 5637 1344 5637 1343 5637 1316 5638 1343 5638 2875 5638 2875 5639 1343 5639 2874 5639 2875 5640 2874 5640 2876 5640 2876 5641 2874 5641 2877 5641 2876 5642 2877 5642 2878 5642 2878 5643 2877 5643 2879 5643 2878 5644 2879 5644 1319 5644 1319 5645 2879 5645 2880 5645 1319 5646 2880 5646 1320 5646 1320 5647 2880 5647 1340 5647 1320 5648 1340 5648 1322 5648 1322 5649 1340 5649 1339 5649 1322 5650 1339 5650 2881 5650 2881 5651 1339 5651 2882 5651 2881 5652 2882 5652 1325 5652 1325 5653 2882 5653 1338 5653 1325 5654 1338 5654 2883 5654 2883 5655 1338 5655 2884 5655 2883 5656 2884 5656 2885 5656 2885 5657 2884 5657 1336 5657 2885 5658 1336 5658 2887 5658 2887 5659 1336 5659 2886 5659 2887 5660 2886 5660 2888 5660 2888 5661 2886 5661 1334 5661 2888 5662 1334 5662 1328 5662 1328 5663 1334 5663 2889 5663 1328 5664 2889 5664 2891 5664 2891 5665 2889 5665 2890 5665 2891 5666 2890 5666 1331 5666 1235 5667 1279 5667 2892 5667 1235 5668 2892 5668 1236 5668 1236 5669 2892 5669 2893 5669 1236 5670 2893 5670 1239 5670 1239 5671 2893 5671 1276 5671 1239 5672 1276 5672 2894 5672 2894 5673 1276 5673 2895 5673 2894 5674 2895 5674 2896 5674 2896 5675 2895 5675 1275 5675 2896 5676 1275 5676 1242 5676 1242 5677 1275 5677 1273 5677 1242 5678 1273 5678 2898 5678 2898 5679 1273 5679 2897 5679 2898 5680 2897 5680 1245 5680 1245 5681 2897 5681 1272 5681 1245 5682 1272 5682 2899 5682 2899 5683 1272 5683 1271 5683 2899 5684 1271 5684 2900 5684 2900 5685 1271 5685 1270 5685 2900 5686 1270 5686 2901 5686 2901 5687 1270 5687 1269 5687 2901 5688 1269 5688 1247 5688 1247 5689 1269 5689 1268 5689 1247 5690 1268 5690 2902 5690 2902 5691 1268 5691 1267 5691 2902 5692 1267 5692 1253 5692 1253 5693 1267 5693 2903 5693 1253 5694 2903 5694 2904 5694 2904 5695 2903 5695 2905 5695 2904 5696 2905 5696 2906 5696 2906 5697 2905 5697 1263 5697 2906 5698 1263 5698 2908 5698 2908 5699 1263 5699 2907 5699 2908 5700 2907 5700 1257 5700 1257 5701 2907 5701 1261 5701 1257 5702 1261 5702 2909 5702 2909 5703 1261 5703 9122 5703 2909 5704 9122 5704 6203 5704 2910 5705 1311 5705 2911 5705 2910 5706 2911 5706 2912 5706 2912 5707 2911 5707 2914 5707 2912 5708 2914 5708 2913 5708 2913 5709 2914 5709 2915 5709 2913 5710 2915 5710 2916 5710 2916 5711 2915 5711 2917 5711 2916 5712 2917 5712 1282 5712 1282 5713 2917 5713 2918 5713 1282 5714 2918 5714 2919 5714 2919 5715 2918 5715 1307 5715 2919 5716 1307 5716 2920 5716 2920 5717 1307 5717 1306 5717 2920 5718 1306 5718 1284 5718 1284 5719 1306 5719 2921 5719 1284 5720 2921 5720 2922 5720 2922 5721 2921 5721 1305 5721 2922 5722 1305 5722 1286 5722 1286 5723 1305 5723 1304 5723 1286 5724 1304 5724 1287 5724 1287 5725 1304 5725 2923 5725 1287 5726 2923 5726 2924 5726 2924 5727 2923 5727 2925 5727 2924 5728 2925 5728 2927 5728 2927 5729 2925 5729 2926 5729 2927 5730 2926 5730 1289 5730 1289 5731 2926 5731 2928 5731 1289 5732 2928 5732 2929 5732 2929 5733 2928 5733 1301 5733 2929 5734 1301 5734 1291 5734 1291 5735 1301 5735 1300 5735 1291 5736 1300 5736 1294 5736 1294 5737 1300 5737 1299 5737 1294 5738 1299 5738 1295 5738 1295 5739 1299 5739 2930 5739 1295 5740 2930 5740 2931 5740 2931 5741 2930 5741 2932 5741 2931 5742 2932 5742 9084 5742 1234 5743 3880 5743 3881 5743 1234 5744 3881 5744 2933 5744 2933 5745 3881 5745 3883 5745 2933 5746 3883 5746 2934 5746 2934 5747 3883 5747 2935 5747 2934 5748 2935 5748 1233 5748 1233 5749 2935 5749 3884 5749 1233 5750 3884 5750 1231 5750 1231 5751 3884 5751 3886 5751 1231 5752 3886 5752 2936 5752 2936 5753 3886 5753 3888 5753 2936 5754 3888 5754 2937 5754 2937 5755 3888 5755 3889 5755 2937 5756 3889 5756 2939 5756 2939 5757 3889 5757 2938 5757 2939 5758 2938 5758 2941 5758 2941 5759 2938 5759 2940 5759 2941 5760 2940 5760 1226 5760 1226 5761 2940 5761 3891 5761 1226 5762 3891 5762 1225 5762 1225 5763 3891 5763 3892 5763 1225 5764 3892 5764 2942 5764 2942 5765 3892 5765 3893 5765 2942 5766 3893 5766 1223 5766 1223 5767 3893 5767 3894 5767 1223 5768 3894 5768 1220 5768 1220 5769 3894 5769 3897 5769 1220 5770 3897 5770 2943 5770 2943 5771 3897 5771 2944 5771 2943 5772 2944 5772 1218 5772 1218 5773 2944 5773 3898 5773 1218 5774 3898 5774 1217 5774 1217 5775 3898 5775 2946 5775 1217 5776 2946 5776 2945 5776 2945 5777 2946 5777 2947 5777 2945 5778 2947 5778 1216 5778 1216 5779 2947 5779 2948 5779 1216 5780 2948 5780 1213 5780 4637 5781 2949 5781 3901 5781 3901 5782 2949 5782 2950 5782 3901 5783 2950 5783 3902 5783 3902 5784 2950 5784 2951 5784 3902 5785 2951 5785 3903 5785 3903 5786 2951 5786 2952 5786 3903 5787 2952 5787 2953 5787 2953 5788 2952 5788 2954 5788 2953 5789 2954 5789 2955 5789 2955 5790 2954 5790 2956 5790 2955 5791 2956 5791 3906 5791 3906 5792 2956 5792 4894 5792 3906 5793 4894 5793 4631 5793 4631 5794 4894 5794 6105 5794 3907 5795 4899 5795 2957 5795 2957 5796 4899 5796 2958 5796 2957 5797 2958 5797 2959 5797 2959 5798 2958 5798 4896 5798 2959 5799 4896 5799 3908 5799 3908 5800 4896 5800 4897 5800 3908 5801 4897 5801 2960 5801 2960 5802 4897 5802 2961 5802 2960 5803 2961 5803 2962 5803 2962 5804 2961 5804 4902 5804 2962 5805 4902 5805 4618 5805 4618 5806 4902 5806 2963 5806 3910 5807 6098 5807 2964 5807 2964 5808 6098 5808 2965 5808 2964 5809 2965 5809 3912 5809 3912 5810 2965 5810 2966 5810 3912 5811 2966 5811 2968 5811 2968 5812 2966 5812 2967 5812 2968 5813 2967 5813 2969 5813 2969 5814 2967 5814 2970 5814 2969 5815 2970 5815 3913 5815 3913 5816 2970 5816 4907 5816 3913 5817 4907 5817 6087 5817 6087 5818 4907 5818 6088 5818 4611 5819 4870 5819 3915 5819 3915 5820 4870 5820 4869 5820 3915 5821 4869 5821 3918 5821 3918 5822 4869 5822 2972 5822 3918 5823 2972 5823 2971 5823 2971 5824 2972 5824 2973 5824 2971 5825 2973 5825 2974 5825 2974 5826 2973 5826 2975 5826 2974 5827 2975 5827 3920 5827 3920 5828 2975 5828 4969 5828 3920 5829 4969 5829 3922 5829 3922 5830 4969 5830 4968 5830 2976 5831 4881 5831 3923 5831 3923 5832 4881 5832 4878 5832 3923 5833 4878 5833 3925 5833 3925 5834 4878 5834 4877 5834 3925 5835 4877 5835 2977 5835 2977 5836 4877 5836 2978 5836 2977 5837 2978 5837 3926 5837 3926 5838 2978 5838 4876 5838 3926 5839 4876 5839 3928 5839 3928 5840 4876 5840 2979 5840 3928 5841 2979 5841 6070 5841 6070 5842 2979 5842 6071 5842 4590 5843 4853 5843 2980 5843 4590 5844 2980 5844 3936 5844 3936 5845 2980 5845 2981 5845 3936 5846 2981 5846 3937 5846 3937 5847 2981 5847 3938 5847 3938 5848 2981 5848 2982 5848 3938 5849 2982 5849 3934 5849 3934 5850 2982 5850 2983 5850 2983 5851 2982 5851 2985 5851 2983 5852 2985 5852 2984 5852 2984 5853 2985 5853 2986 5853 2986 5854 2985 5854 4857 5854 2986 5855 4857 5855 3931 5855 3931 5856 4857 5856 4856 5856 3931 5857 4856 5857 2987 5857 2987 5858 4856 5858 2988 5858 2987 5859 2988 5859 6061 5859 2989 5860 6060 5860 2990 5860 2989 5861 2990 5861 3947 5861 3947 5862 2990 5862 4946 5862 3947 5863 4946 5863 3948 5863 3948 5864 4946 5864 2991 5864 2991 5865 4946 5865 2993 5865 2991 5866 2993 5866 2992 5866 2992 5867 2993 5867 3946 5867 3946 5868 2993 5868 4952 5868 3946 5869 4952 5869 3944 5869 3944 5870 4952 5870 3945 5870 3945 5871 4952 5871 2995 5871 3945 5872 2995 5872 2994 5872 2994 5873 2995 5873 4951 5873 2994 5874 4951 5874 3940 5874 3940 5875 4951 5875 6048 5875 3940 5876 6048 5876 2996 5876 3950 5877 6046 5877 2998 5877 3950 5878 2998 5878 2997 5878 2997 5879 2998 5879 3000 5879 2997 5880 3000 5880 2999 5880 2999 5881 3000 5881 3001 5881 3001 5882 3000 5882 4957 5882 3001 5883 4957 5883 3002 5883 3002 5884 4957 5884 3003 5884 3003 5885 4957 5885 4955 5885 3003 5886 4955 5886 3953 5886 3953 5887 4955 5887 3004 5887 3004 5888 4955 5888 3005 5888 3004 5889 3005 5889 3006 5889 3006 5890 3005 5890 3007 5890 3006 5891 3007 5891 3008 5891 3008 5892 3007 5892 4959 5892 3008 5893 4959 5893 4577 5893 6034 5894 3009 5894 3010 5894 3010 5895 3009 5895 3011 5895 3010 5896 3011 5896 3012 5896 3012 5897 3011 5897 4923 5897 3012 5898 4923 5898 3958 5898 3958 5899 4923 5899 3013 5899 3958 5900 3013 5900 3959 5900 3959 5901 3013 5901 4930 5901 3959 5902 4930 5902 3961 5902 3961 5903 4930 5903 4929 5903 3961 5904 4929 5904 3963 5904 3963 5905 4929 5905 4928 5905 3963 5906 4928 5906 4564 5906 4564 5907 4928 5907 4927 5907 4554 5908 4931 5908 3014 5908 4554 5909 3014 5909 3969 5909 3969 5910 3014 5910 4933 5910 3969 5911 4933 5911 3015 5911 3015 5912 4933 5912 3971 5912 3971 5913 4933 5913 3016 5913 3971 5914 3016 5914 3972 5914 3972 5915 3016 5915 3017 5915 3017 5916 3016 5916 3018 5916 3017 5917 3018 5917 3967 5917 3967 5918 3018 5918 3020 5918 3020 5919 3018 5919 3019 5919 3020 5920 3019 5920 3021 5920 3021 5921 3019 5921 3022 5921 3021 5922 3022 5922 3023 5922 3023 5923 3022 5923 6017 5923 3023 5924 6017 5924 3965 5924 3026 5925 3024 5925 3025 5925 3026 5926 3025 5926 3027 5926 3027 5927 3025 5927 3878 5927 3027 5928 3878 5928 3028 5928 3028 5929 3878 5929 3876 5929 3028 5930 3876 5930 3029 5930 3029 5931 3876 5931 3874 5931 3029 5932 3874 5932 3031 5932 3031 5933 3874 5933 3030 5933 3031 5934 3030 5934 4196 5934 4196 5935 3030 5935 3871 5935 4196 5936 3871 5936 3032 5936 3032 5937 3871 5937 3870 5937 3032 5938 3870 5938 3033 5938 3033 5939 3870 5939 3868 5939 3033 5940 3868 5940 3034 5940 3034 5941 3868 5941 3035 5941 3034 5942 3035 5942 3036 5942 3036 5943 3035 5943 3866 5943 3036 5944 3866 5944 3037 5944 3037 5945 3866 5945 3864 5945 3037 5946 3864 5946 4169 5946 4169 5947 3864 5947 3862 5947 4169 5948 3862 5948 4171 5948 4171 5949 3862 5949 3038 5949 4171 5950 3038 5950 4173 5950 4173 5951 3038 5951 3861 5951 4173 5952 3861 5952 3039 5952 3039 5953 3861 5953 3860 5953 3039 5954 3860 5954 4175 5954 4175 5955 3860 5955 5074 5955 4175 5956 5074 5956 3040 5956 4920 5957 3899 5957 3042 5957 3046 5958 4741 5958 3045 5958 3045 5959 4741 5959 4743 5959 3045 5960 4743 5960 3041 5960 3041 5961 4743 5961 4745 5961 3041 5962 4745 5962 3042 5962 3042 5963 4745 5963 4919 5963 3042 5964 4919 5964 4920 5964 4728 5965 3044 5965 3043 5965 3043 5966 3044 5966 4909 5966 3043 5967 4909 5967 3045 5967 3045 5968 4909 5968 4910 5968 3045 5969 4910 5969 3046 5969 4728 5970 3043 5970 3047 5970 3047 5971 3043 5971 3896 5971 3047 5972 3896 5972 4724 5972 4721 5973 3048 5973 3895 5973 3895 5974 3048 5974 4646 5974 3895 5975 4646 5975 3896 5975 3896 5976 4646 5976 3049 5976 3896 5977 3049 5977 4724 5977 4905 5978 3050 5978 3051 5978 3051 5979 3050 5979 3895 5979 3895 5980 3050 5980 4906 5980 3895 5981 4906 5981 4721 5981 4754 5982 4755 5982 3052 5982 3052 5983 4755 5983 3053 5983 3052 5984 3053 5984 3051 5984 3051 5985 3053 5985 4714 5985 3051 5986 4714 5986 4905 5986 4754 5987 3052 5987 4892 5987 4892 5988 3052 5988 3054 5988 4892 5989 3054 5989 4890 5989 4890 5990 3054 5990 3055 5990 4890 5991 3055 5991 4889 5991 4889 5992 3055 5992 4707 5992 4707 5993 3055 5993 3058 5993 4707 5994 3058 5994 3056 5994 3056 5995 3058 5995 3057 5995 3057 5996 3058 5996 3890 5996 3057 5997 3890 5997 3059 5997 4879 5998 4884 5998 3887 5998 3887 5999 4884 5999 3060 5999 3887 6000 3060 6000 3890 6000 3890 6001 3060 6001 3061 6001 3890 6002 3061 6002 3059 6002 3885 6003 3062 6003 3887 6003 3887 6004 3062 6004 3063 6004 3887 6005 3063 6005 4879 6005 4694 6006 3885 6006 3067 6006 4694 6007 3064 6007 3885 6007 3885 6008 3064 6008 3065 6008 3885 6009 3065 6009 3062 6009 4873 6010 3067 6010 3066 6010 4873 6011 4701 6011 3067 6011 3067 6012 4701 6012 4695 6012 3067 6013 4695 6013 4694 6013 4644 6014 3068 6014 3882 6014 3882 6015 3068 6015 3069 6015 3882 6016 3069 6016 3066 6016 3066 6017 3069 6017 4872 6017 3066 6018 4872 6018 4873 6018 4644 6019 3882 6019 3070 6019 3070 6020 3882 6020 3071 6020 3070 6021 3071 6021 3072 6021 3072 6022 3071 6022 5969 6022 3072 6023 5969 6023 4848 6023 3073 6024 5962 6024 3086 6024 3086 6025 3088 6025 3073 6025 3073 6026 3088 6026 3074 6026 3073 6027 3074 6027 4810 6027 3074 6028 3085 6028 4810 6028 4810 6029 3085 6029 3075 6029 4810 6030 3075 6030 4812 6030 3075 6031 3076 6031 4812 6031 4812 6032 3076 6032 3077 6032 4812 6033 3077 6033 4813 6033 4813 6034 3077 6034 3078 6034 4813 6035 3078 6035 4806 6035 3078 6036 3083 6036 4806 6036 4806 6037 3083 6037 3082 6037 4806 6038 3082 6038 4948 6038 3079 6039 5968 6039 3080 6039 3080 6040 5968 6040 4948 6040 3080 6041 4948 6041 3081 6041 3081 6042 4948 6042 3082 6042 3079 6043 3080 6043 3096 6043 3096 6044 3080 6044 3095 6044 3080 6045 3081 6045 3095 6045 3095 6046 3081 6046 3082 6046 3095 6047 3082 6047 3084 6047 3082 6048 3083 6048 3084 6048 3084 6049 3083 6049 3078 6049 3084 6050 3078 6050 3093 6050 3078 6051 3077 6051 3093 6051 3093 6052 3077 6052 3076 6052 3093 6053 3076 6053 3090 6053 3076 6054 3075 6054 3090 6054 3090 6055 3075 6055 3085 6055 3090 6056 3085 6056 3089 6056 3086 6057 3087 6057 3088 6057 3088 6058 3087 6058 3089 6058 3088 6059 3089 6059 3074 6059 3074 6060 3089 6060 3085 6060 3087 6061 4502 6061 3089 6061 3089 6062 4502 6062 3091 6062 3089 6063 3091 6063 3090 6063 3090 6064 3091 6064 3092 6064 3090 6065 3092 6065 3093 6065 3093 6066 3092 6066 3094 6066 3093 6067 3094 6067 3084 6067 3084 6068 3094 6068 4503 6068 3084 6069 4503 6069 3095 6069 3095 6070 4503 6070 4504 6070 3095 6071 4504 6071 3096 6071 3096 6072 4504 6072 4505 6072 5944 6073 5945 6073 3097 6073 3097 6074 5945 6074 4838 6074 3097 6075 4838 6075 3104 6075 3104 6076 4838 6076 3099 6076 3104 6077 3099 6077 3098 6077 3098 6078 3099 6078 3100 6078 3098 6079 3100 6079 3101 6079 3101 6080 3100 6080 4945 6080 3101 6081 4945 6081 3102 6081 3102 6082 4945 6082 3103 6082 3102 6083 3103 6083 5938 6083 5938 6084 3103 6084 5016 6084 5937 6085 5944 6085 3112 6085 3112 6086 5944 6086 3097 6086 3112 6087 3097 6087 3111 6087 3111 6088 3097 6088 3104 6088 3111 6089 3104 6089 3108 6089 3108 6090 3104 6090 3098 6090 3108 6091 3098 6091 3107 6091 3107 6092 3098 6092 3101 6092 3107 6093 3101 6093 3105 6093 3105 6094 3101 6094 3102 6094 3105 6095 3102 6095 3106 6095 3106 6096 3102 6096 5938 6096 3106 6097 4489 6097 3105 6097 3105 6098 4489 6098 4490 6098 3105 6099 4490 6099 3107 6099 3107 6100 4490 6100 3109 6100 3107 6101 3109 6101 3108 6101 3108 6102 3109 6102 3110 6102 3108 6103 3110 6103 3111 6103 3111 6104 3110 6104 3113 6104 3111 6105 3113 6105 3112 6105 3112 6106 3113 6106 4494 6106 3112 6107 4494 6107 5937 6107 5937 6108 4494 6108 3114 6108 3120 6109 5924 6109 3121 6109 3121 6110 5924 6110 3115 6110 3121 6111 3115 6111 3116 6111 3116 6112 3115 6112 3117 6112 3116 6113 3117 6113 3123 6113 3123 6114 3117 6114 4822 6114 3123 6115 4822 6115 3126 6115 3126 6116 4822 6116 3118 6116 3126 6117 3118 6117 3128 6117 3128 6118 3118 6118 4831 6118 3128 6119 4831 6119 3119 6119 3119 6120 4831 6120 4829 6120 3119 6121 4829 6121 3129 6121 3129 6122 4829 6122 4828 6122 5920 6123 3120 6123 3121 6123 5920 6124 3121 6124 3132 6124 3132 6125 3121 6125 3116 6125 3132 6126 3116 6126 3122 6126 3122 6127 3116 6127 3133 6127 3133 6128 3116 6128 3123 6128 3133 6129 3123 6129 3134 6129 3134 6130 3123 6130 3124 6130 3124 6131 3123 6131 3126 6131 3124 6132 3126 6132 3125 6132 3125 6133 3126 6133 3137 6133 3137 6134 3126 6134 3128 6134 3137 6135 3128 6135 3127 6135 3127 6136 3128 6136 3119 6136 3127 6137 3119 6137 3136 6137 3136 6138 3119 6138 3129 6138 3136 6139 3129 6139 3130 6139 4488 6140 5920 6140 3131 6140 3131 6141 5920 6141 3132 6141 3131 6142 3132 6142 4486 6142 4486 6143 3132 6143 3122 6143 3122 6144 3133 6144 4486 6144 4486 6145 3133 6145 3134 6145 4486 6146 3134 6146 4485 6146 3134 6147 3124 6147 4485 6147 4485 6148 3124 6148 3125 6148 4485 6149 3125 6149 4483 6149 3130 6150 4479 6150 3136 6150 3136 6151 4479 6151 3135 6151 3136 6152 3135 6152 3127 6152 3127 6153 3135 6153 4483 6153 3127 6154 4483 6154 3137 6154 3137 6155 4483 6155 3125 6155 5893 6156 4843 6156 3145 6156 3145 6157 4843 6157 3138 6157 3145 6158 3138 6158 3146 6158 3146 6159 3138 6159 3139 6159 3146 6160 3139 6160 3147 6160 3147 6161 3139 6161 4954 6161 3147 6162 4954 6162 3148 6162 3148 6163 4954 6163 3140 6163 3148 6164 3140 6164 3141 6164 3141 6165 3140 6165 3142 6165 3141 6166 3142 6166 5880 6166 5880 6167 3142 6167 3143 6167 5894 6168 5893 6168 3144 6168 3144 6169 5893 6169 3145 6169 3144 6170 3145 6170 3153 6170 3153 6171 3145 6171 3146 6171 3153 6172 3146 6172 3152 6172 3152 6173 3146 6173 3147 6173 3152 6174 3147 6174 3151 6174 3151 6175 3147 6175 3148 6175 3151 6176 3148 6176 3149 6176 3149 6177 3148 6177 3141 6177 3149 6178 3141 6178 5882 6178 5882 6179 3141 6179 5880 6179 5882 6180 3150 6180 3149 6180 3149 6181 3150 6181 4472 6181 3149 6182 4472 6182 3151 6182 3151 6183 4472 6183 4459 6183 3151 6184 4459 6184 3152 6184 3152 6185 4459 6185 4460 6185 3152 6186 4460 6186 3153 6186 3153 6187 4460 6187 4463 6187 3153 6188 4463 6188 3144 6188 3144 6189 4463 6189 4464 6189 3144 6190 4464 6190 5894 6190 5894 6191 4464 6191 4466 6191 3158 6192 3154 6192 3155 6192 3155 6193 3156 6193 3158 6193 3158 6194 3156 6194 3157 6194 3158 6195 3157 6195 4815 6195 3157 6196 3237 6196 4815 6196 4815 6197 3237 6197 3233 6197 4815 6198 3233 6198 4817 6198 3233 6199 3232 6199 4817 6199 4817 6200 3232 6200 3231 6200 4817 6201 3231 6201 4819 6201 4819 6202 3231 6202 3229 6202 4819 6203 3229 6203 4821 6203 3229 6204 3159 6204 4821 6204 4821 6205 3159 6205 3228 6205 4821 6206 3228 6206 4811 6206 3160 6207 3161 6207 3227 6207 3227 6208 3161 6208 4811 6208 3227 6209 4811 6209 3162 6209 3162 6210 4811 6210 3228 6210 3163 6211 4832 6211 3239 6211 3239 6212 4832 6212 3164 6212 3239 6213 3164 6213 3165 6213 3165 6214 3164 6214 3166 6214 3165 6215 3166 6215 3240 6215 3240 6216 3166 6216 4836 6216 3240 6217 4836 6217 3167 6217 3167 6218 4836 6218 4839 6218 3167 6219 4839 6219 3241 6219 3241 6220 4839 6220 4841 6220 3241 6221 4841 6221 5750 6221 5750 6222 4841 6222 5861 6222 3168 6223 5859 6223 3243 6223 3243 6224 5859 6224 3169 6224 3243 6225 3169 6225 3245 6225 3245 6226 3169 6226 3170 6226 3245 6227 3170 6227 3246 6227 3246 6228 3170 6228 3171 6228 3246 6229 3171 6229 3172 6229 3172 6230 3171 6230 4845 6230 3172 6231 4845 6231 3249 6231 3249 6232 4845 6232 3174 6232 3249 6233 3174 6233 3173 6233 3173 6234 3174 6234 5851 6234 3180 6235 5785 6235 3181 6235 3181 6236 5785 6236 3175 6236 3181 6237 3175 6237 3176 6237 3176 6238 3175 6238 5784 6238 3176 6239 5784 6239 3177 6239 3177 6240 5784 6240 5782 6240 3177 6241 5782 6241 3182 6241 3182 6242 5782 6242 5781 6242 3182 6243 5781 6243 3178 6243 3178 6244 5781 6244 5780 6244 3178 6245 5780 6245 5837 6245 5837 6246 5780 6246 5779 6246 3179 6247 3180 6247 3189 6247 3189 6248 3180 6248 3181 6248 3189 6249 3181 6249 3188 6249 3188 6250 3181 6250 3176 6250 3188 6251 3176 6251 3186 6251 3186 6252 3176 6252 3177 6252 3186 6253 3177 6253 3183 6253 3183 6254 3177 6254 3182 6254 3183 6255 3182 6255 3185 6255 3185 6256 3182 6256 3178 6256 3185 6257 3178 6257 3184 6257 3184 6258 3178 6258 5837 6258 3184 6259 4542 6259 3185 6259 3185 6260 4542 6260 4543 6260 3185 6261 4543 6261 3183 6261 3183 6262 4543 6262 3187 6262 3183 6263 3187 6263 3186 6263 3186 6264 3187 6264 4545 6264 3186 6265 4545 6265 3188 6265 3188 6266 4545 6266 4547 6266 3188 6267 4547 6267 3189 6267 3189 6268 4547 6268 3190 6268 3189 6269 3190 6269 3179 6269 3179 6270 3190 6270 4551 6270 5826 6271 5764 6271 3191 6271 3191 6272 5764 6272 3192 6272 3191 6273 3192 6273 3200 6273 3200 6274 3192 6274 5765 6274 3200 6275 5765 6275 3193 6275 3193 6276 5765 6276 3195 6276 3193 6277 3195 6277 3194 6277 3194 6278 3195 6278 5767 6278 3194 6279 5767 6279 3196 6279 3196 6280 5767 6280 5770 6280 3196 6281 5770 6281 3197 6281 3197 6282 5770 6282 5819 6282 3206 6283 5826 6283 3198 6283 3198 6284 5826 6284 3191 6284 3198 6285 3191 6285 3199 6285 3199 6286 3191 6286 3200 6286 3199 6287 3200 6287 3204 6287 3204 6288 3200 6288 3193 6288 3204 6289 3193 6289 3202 6289 3202 6290 3193 6290 3194 6290 3202 6291 3194 6291 3201 6291 3201 6292 3194 6292 3196 6292 3201 6293 3196 6293 5812 6293 5812 6294 3196 6294 3197 6294 5812 6295 5811 6295 3201 6295 3201 6296 5811 6296 4528 6296 3201 6297 4528 6297 3202 6297 3202 6298 4528 6298 4529 6298 3202 6299 4529 6299 3204 6299 3204 6300 4529 6300 3203 6300 3204 6301 3203 6301 3199 6301 3199 6302 3203 6302 3205 6302 3199 6303 3205 6303 3198 6303 3198 6304 3205 6304 4531 6304 3198 6305 4531 6305 3206 6305 3206 6306 4531 6306 4532 6306 3214 6307 5743 6307 3207 6307 3207 6308 5743 6308 3208 6308 3207 6309 3208 6309 3209 6309 3209 6310 3208 6310 3210 6310 3209 6311 3210 6311 3215 6311 3215 6312 3210 6312 5747 6312 3215 6313 5747 6313 3211 6313 3211 6314 5747 6314 3212 6314 3211 6315 3212 6315 3218 6315 3218 6316 3212 6316 3213 6316 3218 6317 3213 6317 5796 6317 5796 6318 3213 6318 5802 6318 3225 6319 3214 6319 3223 6319 3223 6320 3214 6320 3207 6320 3223 6321 3207 6321 3222 6321 3222 6322 3207 6322 3209 6322 3222 6323 3209 6323 3220 6323 3220 6324 3209 6324 3215 6324 3220 6325 3215 6325 3216 6325 3216 6326 3215 6326 3211 6326 3216 6327 3211 6327 3217 6327 3217 6328 3211 6328 3218 6328 3217 6329 3218 6329 5795 6329 5795 6330 3218 6330 5796 6330 5795 6331 4518 6331 3217 6331 3217 6332 4518 6332 3219 6332 3217 6333 3219 6333 3216 6333 3216 6334 3219 6334 4520 6334 3216 6335 4520 6335 3220 6335 3220 6336 4520 6336 3221 6336 3220 6337 3221 6337 3222 6337 3222 6338 3221 6338 3224 6338 3222 6339 3224 6339 3223 6339 3223 6340 3224 6340 4523 6340 3223 6341 4523 6341 3225 6341 3225 6342 4523 6342 5788 6342 3160 6343 3227 6343 5776 6343 5776 6344 3227 6344 3226 6344 3227 6345 3162 6345 3226 6345 3226 6346 3162 6346 3228 6346 3226 6347 3228 6347 5783 6347 3228 6348 3159 6348 5783 6348 5783 6349 3159 6349 3229 6349 5783 6350 3229 6350 3230 6350 3229 6351 3231 6351 3230 6351 3230 6352 3231 6352 3232 6352 3230 6353 3232 6353 3234 6353 3232 6354 3233 6354 3234 6354 3234 6355 3233 6355 3237 6355 3234 6356 3237 6356 3236 6356 3155 6357 3235 6357 3156 6357 3156 6358 3235 6358 3236 6358 3156 6359 3236 6359 3157 6359 3157 6360 3236 6360 3237 6360 5758 6361 3163 6361 3238 6361 3238 6362 3163 6362 3239 6362 3238 6363 3239 6363 5766 6363 5766 6364 3239 6364 3165 6364 5766 6365 3165 6365 5768 6365 5768 6366 3165 6366 3240 6366 5768 6367 3240 6367 5769 6367 5769 6368 3240 6368 3167 6368 5769 6369 3167 6369 5771 6369 5771 6370 3167 6370 3241 6370 5771 6371 3241 6371 3242 6371 3242 6372 3241 6372 5750 6372 5744 6373 3168 6373 5745 6373 5745 6374 3168 6374 3243 6374 5745 6375 3243 6375 5746 6375 5746 6376 3243 6376 3245 6376 5746 6377 3245 6377 3244 6377 3244 6378 3245 6378 3246 6378 3244 6379 3246 6379 3247 6379 3247 6380 3246 6380 3172 6380 3247 6381 3172 6381 3248 6381 3248 6382 3172 6382 3249 6382 3248 6383 3249 6383 3250 6383 3250 6384 3249 6384 3173 6384 3257 6385 3252 6385 3251 6385 3251 6386 3252 6386 4939 6386 3251 6387 4939 6387 3259 6387 3259 6388 4939 6388 4938 6388 3259 6389 4938 6389 3253 6389 3253 6390 4938 6390 4935 6390 3253 6391 4935 6391 3260 6391 3260 6392 4935 6392 3254 6392 3260 6393 3254 6393 3261 6393 3261 6394 3254 6394 3255 6394 3261 6395 3255 6395 3256 6395 3256 6396 3255 6396 4941 6396 5712 6397 3257 6397 3258 6397 3258 6398 3257 6398 3251 6398 3258 6399 3251 6399 3267 6399 3267 6400 3251 6400 3259 6400 3267 6401 3259 6401 3266 6401 3266 6402 3259 6402 3253 6402 3266 6403 3253 6403 3264 6403 3264 6404 3253 6404 3260 6404 3264 6405 3260 6405 3263 6405 3263 6406 3260 6406 3261 6406 3263 6407 3261 6407 5706 6407 5706 6408 3261 6408 3256 6408 5706 6409 3262 6409 3263 6409 3263 6410 3262 6410 4323 6410 3263 6411 4323 6411 3264 6411 3264 6412 4323 6412 4324 6412 3264 6413 4324 6413 3266 6413 3266 6414 4324 6414 3265 6414 3266 6415 3265 6415 3267 6415 3267 6416 3265 6416 3268 6416 3267 6417 3268 6417 3258 6417 3258 6418 3268 6418 3269 6418 3258 6419 3269 6419 5712 6419 5712 6420 3269 6420 5713 6420 4657 6421 5690 6421 3270 6421 3270 6422 5690 6422 3271 6422 3270 6423 3271 6423 3272 6423 3271 6424 3286 6424 3272 6424 3272 6425 3286 6425 3285 6425 3272 6426 3285 6426 3273 6426 3273 6427 3285 6427 3282 6427 3282 6428 3274 6428 3273 6428 3273 6429 3274 6429 3279 6429 3273 6430 3279 6430 3278 6430 5705 6431 3276 6431 3275 6431 3275 6432 3276 6432 4652 6432 3275 6433 4652 6433 3277 6433 3277 6434 4652 6434 3278 6434 3277 6435 3278 6435 3281 6435 3281 6436 3278 6436 3279 6436 5699 6437 5705 6437 3275 6437 5699 6438 3275 6438 3292 6438 3292 6439 3275 6439 3277 6439 3292 6440 3277 6440 3280 6440 3280 6441 3277 6441 3281 6441 3280 6442 3281 6442 3290 6442 3281 6443 3279 6443 3290 6443 3290 6444 3279 6444 3274 6444 3290 6445 3274 6445 3283 6445 3274 6446 3282 6446 3283 6446 3283 6447 3282 6447 3285 6447 3283 6448 3285 6448 3284 6448 3285 6449 3286 6449 3284 6449 3284 6450 3286 6450 3271 6450 3284 6451 3271 6451 3287 6451 3287 6452 3271 6452 5690 6452 3287 6453 5690 6453 5688 6453 5688 6454 4319 6454 3287 6454 3287 6455 4319 6455 4321 6455 3287 6456 4321 6456 3284 6456 3284 6457 4321 6457 3288 6457 3284 6458 3288 6458 3283 6458 3283 6459 3288 6459 3289 6459 3283 6460 3289 6460 3290 6460 3290 6461 3289 6461 3291 6461 3290 6462 3291 6462 3280 6462 3280 6463 3291 6463 3293 6463 3280 6464 3293 6464 3292 6464 3292 6465 3293 6465 3294 6465 3292 6466 3294 6466 5699 6466 5699 6467 3294 6467 4315 6467 5683 6468 3295 6468 3300 6468 3300 6469 3295 6469 4648 6469 3300 6470 4648 6470 3296 6470 3296 6471 4648 6471 4649 6471 3296 6472 4649 6472 3303 6472 3303 6473 4649 6473 3297 6473 3303 6474 3297 6474 3305 6474 3305 6475 3297 6475 4803 6475 3305 6476 4803 6476 3308 6476 3308 6477 4803 6477 4802 6477 3308 6478 4802 6478 3309 6478 3309 6479 4802 6479 3298 6479 3309 6480 3298 6480 5677 6480 5677 6481 3298 6481 4801 6481 3299 6482 5683 6482 3300 6482 3299 6483 3300 6483 3301 6483 3301 6484 3300 6484 3296 6484 3301 6485 3296 6485 3313 6485 3313 6486 3296 6486 3302 6486 3302 6487 3296 6487 3303 6487 3302 6488 3303 6488 3304 6488 3304 6489 3303 6489 3306 6489 3306 6490 3303 6490 3305 6490 3306 6491 3305 6491 3314 6491 3314 6492 3305 6492 3307 6492 3307 6493 3305 6493 3308 6493 3307 6494 3308 6494 3315 6494 3315 6495 3308 6495 3309 6495 3315 6496 3309 6496 3310 6496 3310 6497 3309 6497 5677 6497 3310 6498 5677 6498 3311 6498 5666 6499 3299 6499 3312 6499 3312 6500 3299 6500 3301 6500 3312 6501 3301 6501 4306 6501 4306 6502 3301 6502 3313 6502 3313 6503 3302 6503 4306 6503 4306 6504 3302 6504 3304 6504 4306 6505 3304 6505 4305 6505 3304 6506 3306 6506 4305 6506 4305 6507 3306 6507 3314 6507 4305 6508 3314 6508 4304 6508 3311 6509 4312 6509 3310 6509 3310 6510 4312 6510 4303 6510 3310 6511 4303 6511 3315 6511 3315 6512 4303 6512 4304 6512 3315 6513 4304 6513 3307 6513 3307 6514 4304 6514 3314 6514 4793 6515 5654 6515 4781 6515 4781 6516 5654 6516 3316 6516 4781 6517 3316 6517 3318 6517 3316 6518 3331 6518 3318 6518 3318 6519 3331 6519 3317 6519 3318 6520 3317 6520 3320 6520 3320 6521 3317 6521 3319 6521 3319 6522 3330 6522 3320 6522 3320 6523 3330 6523 3321 6523 3320 6524 3321 6524 3322 6524 3326 6525 4780 6525 3323 6525 3323 6526 4780 6526 3324 6526 3323 6527 3324 6527 3327 6527 3327 6528 3324 6528 3322 6528 3327 6529 3322 6529 3325 6529 3325 6530 3322 6530 3321 6530 5659 6531 3326 6531 3323 6531 5659 6532 3323 6532 3338 6532 3338 6533 3323 6533 3327 6533 3338 6534 3327 6534 3328 6534 3328 6535 3327 6535 3325 6535 3328 6536 3325 6536 3329 6536 3325 6537 3321 6537 3329 6537 3329 6538 3321 6538 3330 6538 3329 6539 3330 6539 3337 6539 3330 6540 3319 6540 3337 6540 3337 6541 3319 6541 3317 6541 3337 6542 3317 6542 3336 6542 3317 6543 3331 6543 3336 6543 3336 6544 3331 6544 3316 6544 3336 6545 3316 6545 3332 6545 3332 6546 3316 6546 5654 6546 3332 6547 5654 6547 5653 6547 5653 6548 3333 6548 3332 6548 3332 6549 3333 6549 3334 6549 3332 6550 3334 6550 3336 6550 3336 6551 3334 6551 3335 6551 3336 6552 3335 6552 3337 6552 3337 6553 3335 6553 4300 6553 3337 6554 4300 6554 3329 6554 3329 6555 4300 6555 4301 6555 3329 6556 4301 6556 3328 6556 3328 6557 4301 6557 4290 6557 3328 6558 4290 6558 3338 6558 3338 6559 4290 6559 4291 6559 3338 6560 4291 6560 5659 6560 5659 6561 4291 6561 4293 6561 3339 6562 5643 6562 3340 6562 3340 6563 3434 6563 3339 6563 3339 6564 3434 6564 3341 6564 3339 6565 3341 6565 4670 6565 3341 6566 3432 6566 4670 6566 4670 6567 3432 6567 3430 6567 4670 6568 3430 6568 4669 6568 3430 6569 3429 6569 4669 6569 4669 6570 3429 6570 3342 6570 4669 6571 3342 6571 4666 6571 4666 6572 3342 6572 3427 6572 4666 6573 3427 6573 3343 6573 3427 6574 3426 6574 3343 6574 3343 6575 3426 6575 3344 6575 3343 6576 3344 6576 3345 6576 3422 6577 4982 6577 3423 6577 3423 6578 4982 6578 3345 6578 3423 6579 3345 6579 3346 6579 3346 6580 3345 6580 3344 6580 4804 6581 5639 6581 4658 6581 4658 6582 5639 6582 3440 6582 4658 6583 3440 6583 3347 6583 3347 6584 3440 6584 3348 6584 3436 6585 4651 6585 3349 6585 3349 6586 4651 6586 4654 6586 3349 6587 4654 6587 3350 6587 3350 6588 4654 6588 4655 6588 3350 6589 4655 6589 3351 6589 3351 6590 4655 6590 4661 6590 3351 6591 4661 6591 3348 6591 3348 6592 4661 6592 3352 6592 3348 6593 3352 6593 3347 6593 5620 6594 3448 6594 4792 6594 4792 6595 3448 6595 3356 6595 5628 6596 5629 6596 3353 6596 3353 6597 5629 6597 4788 6597 3353 6598 4788 6598 3442 6598 3442 6599 4788 6599 4786 6599 3442 6600 4786 6600 3444 6600 3444 6601 4786 6601 3355 6601 3444 6602 3355 6602 3354 6602 3354 6603 3355 6603 4784 6603 3354 6604 4784 6604 3447 6604 3447 6605 4784 6605 4783 6605 3447 6606 4783 6606 3356 6606 3356 6607 4783 6607 3357 6607 3356 6608 3357 6608 4792 6608 5615 6609 5553 6609 3362 6609 3362 6610 5553 6610 5556 6610 3362 6611 5556 6611 3363 6611 3363 6612 5556 6612 5543 6612 3363 6613 5543 6613 3358 6613 3358 6614 5543 6614 5544 6614 3358 6615 5544 6615 3364 6615 3364 6616 5544 6616 5545 6616 3364 6617 5545 6617 3359 6617 3359 6618 5545 6618 3361 6618 3359 6619 3361 6619 3360 6619 3360 6620 3361 6620 5546 6620 3375 6621 5615 6621 3373 6621 3373 6622 5615 6622 3362 6622 3373 6623 3362 6623 3372 6623 3372 6624 3362 6624 3363 6624 3372 6625 3363 6625 3369 6625 3369 6626 3363 6626 3358 6626 3369 6627 3358 6627 3367 6627 3367 6628 3358 6628 3364 6628 3367 6629 3364 6629 3365 6629 3365 6630 3364 6630 3359 6630 3365 6631 3359 6631 3366 6631 3366 6632 3359 6632 3360 6632 3366 6633 4363 6633 3365 6633 3365 6634 4363 6634 4366 6634 3365 6635 4366 6635 3367 6635 3367 6636 4366 6636 3368 6636 3367 6637 3368 6637 3369 6637 3369 6638 3368 6638 3370 6638 3369 6639 3370 6639 3372 6639 3372 6640 3370 6640 3371 6640 3372 6641 3371 6641 3373 6641 3373 6642 3371 6642 3374 6642 3373 6643 3374 6643 3375 6643 3375 6644 3374 6644 5598 6644 5040 6645 5595 6645 5594 6645 5594 6646 3376 6646 5040 6646 5040 6647 3376 6647 3377 6647 5040 6648 3377 6648 3378 6648 3377 6649 3394 6649 3378 6649 3378 6650 3394 6650 3393 6650 3378 6651 3393 6651 3379 6651 3393 6652 3392 6652 3379 6652 3379 6653 3392 6653 3380 6653 3379 6654 3380 6654 3382 6654 3382 6655 3380 6655 3381 6655 3382 6656 3381 6656 3383 6656 3381 6657 3389 6657 3383 6657 3383 6658 3389 6658 3384 6658 3383 6659 3384 6659 5035 6659 5587 6660 3385 6660 3386 6660 3386 6661 3385 6661 5035 6661 3386 6662 5035 6662 3387 6662 3387 6663 5035 6663 3384 6663 5587 6664 3386 6664 5573 6664 5573 6665 3386 6665 3388 6665 3386 6666 3387 6666 3388 6666 3388 6667 3387 6667 3384 6667 3388 6668 3384 6668 3390 6668 3384 6669 3389 6669 3390 6669 3390 6670 3389 6670 3381 6670 3390 6671 3381 6671 3398 6671 3381 6672 3380 6672 3398 6672 3398 6673 3380 6673 3392 6673 3398 6674 3392 6674 3391 6674 3392 6675 3393 6675 3391 6675 3391 6676 3393 6676 3394 6676 3391 6677 3394 6677 3396 6677 5594 6678 3395 6678 3376 6678 3376 6679 3395 6679 3396 6679 3376 6680 3396 6680 3377 6680 3377 6681 3396 6681 3394 6681 3395 6682 4345 6682 3396 6682 3396 6683 4345 6683 4347 6683 3396 6684 4347 6684 3391 6684 3391 6685 4347 6685 3397 6685 3391 6686 3397 6686 3398 6686 3398 6687 3397 6687 4350 6687 3398 6688 4350 6688 3390 6688 3390 6689 4350 6689 3399 6689 3390 6690 3399 6690 3388 6690 3388 6691 3399 6691 4352 6691 3388 6692 4352 6692 5573 6692 5573 6693 4352 6693 4353 6693 3400 6694 5524 6694 3402 6694 3402 6695 5524 6695 3401 6695 3402 6696 3401 6696 3410 6696 3410 6697 3401 6697 5527 6697 3410 6698 5527 6698 3411 6698 3411 6699 5527 6699 5528 6699 3411 6700 5528 6700 3403 6700 3403 6701 5528 6701 5529 6701 3403 6702 5529 6702 3404 6702 3404 6703 5529 6703 3406 6703 3404 6704 3406 6704 3405 6704 3405 6705 3406 6705 3407 6705 3405 6706 3407 6706 3414 6706 3414 6707 3407 6707 5567 6707 3408 6708 3400 6708 3409 6708 3409 6709 3400 6709 3402 6709 3409 6710 3402 6710 3420 6710 3420 6711 3402 6711 3410 6711 3420 6712 3410 6712 3419 6712 3419 6713 3410 6713 3411 6713 3419 6714 3411 6714 3417 6714 3417 6715 3411 6715 3403 6715 3417 6716 3403 6716 3412 6716 3412 6717 3403 6717 3404 6717 3412 6718 3404 6718 3413 6718 3413 6719 3404 6719 3405 6719 3413 6720 3405 6720 5561 6720 5561 6721 3405 6721 3414 6721 5561 6722 4343 6722 3413 6722 3413 6723 4343 6723 3415 6723 3413 6724 3415 6724 3412 6724 3412 6725 3415 6725 3416 6725 3412 6726 3416 6726 3417 6726 3417 6727 3416 6727 3418 6727 3417 6728 3418 6728 3419 6728 3419 6729 3418 6729 4333 6729 3419 6730 4333 6730 3420 6730 3420 6731 4333 6731 3421 6731 3420 6732 3421 6732 3409 6732 3409 6733 3421 6733 4337 6733 3409 6734 4337 6734 3408 6734 3408 6735 4337 6735 4338 6735 3422 6736 3423 6736 5555 6736 5555 6737 3423 6737 3424 6737 3423 6738 3346 6738 3424 6738 3424 6739 3346 6739 3344 6739 3424 6740 3344 6740 3425 6740 3344 6741 3426 6741 3425 6741 3425 6742 3426 6742 3427 6742 3425 6743 3427 6743 3428 6743 3427 6744 3342 6744 3428 6744 3428 6745 3342 6745 3429 6745 3428 6746 3429 6746 3431 6746 3429 6747 3430 6747 3431 6747 3431 6748 3430 6748 3432 6748 3431 6749 3432 6749 3435 6749 3340 6750 3433 6750 3434 6750 3434 6751 3433 6751 3435 6751 3434 6752 3435 6752 3341 6752 3341 6753 3435 6753 3432 6753 5034 6754 3436 6754 3437 6754 3437 6755 3436 6755 3349 6755 3437 6756 3349 6756 3438 6756 3438 6757 3349 6757 3350 6757 3438 6758 3350 6758 5041 6758 5041 6759 3350 6759 3351 6759 5041 6760 3351 6760 5039 6760 5039 6761 3351 6761 3348 6761 5039 6762 3348 6762 3439 6762 3439 6763 3348 6763 3440 6763 3439 6764 3440 6764 5530 6764 5530 6765 3440 6765 5639 6765 5525 6766 5628 6766 5526 6766 5526 6767 5628 6767 3353 6767 5526 6768 3353 6768 3441 6768 3441 6769 3353 6769 3442 6769 3441 6770 3442 6770 3443 6770 3443 6771 3442 6771 3444 6771 3443 6772 3444 6772 3445 6772 3445 6773 3444 6773 3354 6773 3445 6774 3354 6774 5517 6774 5517 6775 3354 6775 3447 6775 5517 6776 3447 6776 3446 6776 3446 6777 3447 6777 3356 6777 3446 6778 3356 6778 5518 6778 5518 6779 3356 6779 3448 6779 3449 6780 4678 6780 3467 6780 3467 6781 3468 6781 3449 6781 3449 6782 3468 6782 3470 6782 3449 6783 3470 6783 3450 6783 3470 6784 3451 6784 3450 6784 3450 6785 3451 6785 3466 6785 3450 6786 3466 6786 4679 6786 4679 6787 3466 6787 3465 6787 4679 6788 3465 6788 3452 6788 3465 6789 3453 6789 3452 6789 3452 6790 3453 6790 3463 6790 3452 6791 3463 6791 3454 6791 3463 6792 3455 6792 3454 6792 3454 6793 3455 6793 3456 6793 3454 6794 3456 6794 3459 6794 5512 6795 3458 6795 3457 6795 3457 6796 3458 6796 3459 6796 3457 6797 3459 6797 3461 6797 3461 6798 3459 6798 3456 6798 5512 6799 3457 6799 3460 6799 3460 6800 3457 6800 3472 6800 3457 6801 3461 6801 3472 6801 3472 6802 3461 6802 3456 6802 3472 6803 3456 6803 3462 6803 3456 6804 3455 6804 3462 6804 3462 6805 3455 6805 3463 6805 3462 6806 3463 6806 3464 6806 3463 6807 3453 6807 3464 6807 3464 6808 3453 6808 3465 6808 3464 6809 3465 6809 3471 6809 3465 6810 3466 6810 3471 6810 3471 6811 3466 6811 3451 6811 3471 6812 3451 6812 3469 6812 3467 6813 5488 6813 3468 6813 3468 6814 5488 6814 3469 6814 3468 6815 3469 6815 3470 6815 3470 6816 3469 6816 3451 6816 5488 6817 5487 6817 3469 6817 3469 6818 5487 6818 4405 6818 3469 6819 4405 6819 3471 6819 3471 6820 4405 6820 4406 6820 3471 6821 4406 6821 3464 6821 3464 6822 4406 6822 4408 6822 3464 6823 4408 6823 3462 6823 3462 6824 4408 6824 3473 6824 3462 6825 3473 6825 3472 6825 3472 6826 3473 6826 4410 6826 3472 6827 4410 6827 3460 6827 3460 6828 4410 6828 4412 6828 5485 6829 5486 6829 3481 6829 3481 6830 5486 6830 3474 6830 3481 6831 3474 6831 3482 6831 3482 6832 3474 6832 4682 6832 3482 6833 4682 6833 3475 6833 3475 6834 4682 6834 3476 6834 3475 6835 3476 6835 3484 6835 3484 6836 3476 6836 4681 6836 3484 6837 4681 6837 3477 6837 3477 6838 4681 6838 4680 6838 3477 6839 4680 6839 3478 6839 3478 6840 4680 6840 3479 6840 3478 6841 3479 6841 5474 6841 5474 6842 3479 6842 4647 6842 3494 6843 5485 6843 3480 6843 3480 6844 5485 6844 3481 6844 3480 6845 3481 6845 3491 6845 3491 6846 3481 6846 3482 6846 3491 6847 3482 6847 3483 6847 3483 6848 3482 6848 3475 6848 3483 6849 3475 6849 3489 6849 3489 6850 3475 6850 3484 6850 3489 6851 3484 6851 3488 6851 3488 6852 3484 6852 3477 6852 3488 6853 3477 6853 3485 6853 3485 6854 3477 6854 3478 6854 3485 6855 3478 6855 3486 6855 3486 6856 3478 6856 5474 6856 3486 6857 3487 6857 3485 6857 3485 6858 3487 6858 4403 6858 3485 6859 4403 6859 3488 6859 3488 6860 4403 6860 4404 6860 3488 6861 4404 6861 3489 6861 3489 6862 4404 6862 3490 6862 3489 6863 3490 6863 3483 6863 3483 6864 3490 6864 4395 6864 3483 6865 4395 6865 3491 6865 3491 6866 4395 6866 3492 6866 3491 6867 3492 6867 3480 6867 3480 6868 3492 6868 3493 6868 3480 6869 3493 6869 3494 6869 3494 6870 3493 6870 4396 6870 3499 6871 3495 6871 3502 6871 3502 6872 3495 6872 4700 6872 3502 6873 4700 6873 3503 6873 3503 6874 4700 6874 4699 6874 3503 6875 4699 6875 3505 6875 3505 6876 4699 6876 4698 6876 3505 6877 4698 6877 3496 6877 3496 6878 4698 6878 3497 6878 3496 6879 3497 6879 3506 6879 3506 6880 3497 6880 4697 6880 3506 6881 4697 6881 3508 6881 3508 6882 4697 6882 3498 6882 5464 6883 3499 6883 3500 6883 3500 6884 3499 6884 3502 6884 3500 6885 3502 6885 3501 6885 3501 6886 3502 6886 3503 6886 3501 6887 3503 6887 3504 6887 3504 6888 3503 6888 3505 6888 3504 6889 3505 6889 3510 6889 3510 6890 3505 6890 3496 6890 3510 6891 3496 6891 3509 6891 3509 6892 3496 6892 3506 6892 3509 6893 3506 6893 3507 6893 3507 6894 3506 6894 3508 6894 3507 6895 5457 6895 3509 6895 3509 6896 5457 6896 4389 6896 3509 6897 4389 6897 3510 6897 3510 6898 4389 6898 4391 6898 3510 6899 4391 6899 3504 6899 3504 6900 4391 6900 3511 6900 3504 6901 3511 6901 3501 6901 3501 6902 3511 6902 3512 6902 3501 6903 3512 6903 3500 6903 3500 6904 3512 6904 3513 6904 3500 6905 3513 6905 5464 6905 5464 6906 3513 6906 4392 6906 3515 6907 4862 6907 3514 6907 3514 6908 3516 6908 3515 6908 3515 6909 3516 6909 3517 6909 3515 6910 3517 6910 4864 6910 3517 6911 3533 6911 4864 6911 4864 6912 3533 6912 3518 6912 4864 6913 3518 6913 4865 6913 4865 6914 3518 6914 3519 6914 4865 6915 3519 6915 4866 6915 3519 6916 3531 6916 4866 6916 4866 6917 3531 6917 3530 6917 4866 6918 3530 6918 4868 6918 3530 6919 3529 6919 4868 6919 4868 6920 3529 6920 3520 6920 4868 6921 3520 6921 3521 6921 3524 6922 3522 6922 3523 6922 3523 6923 3522 6923 3521 6923 3523 6924 3521 6924 3527 6924 3527 6925 3521 6925 3520 6925 3524 6926 3523 6926 3525 6926 3525 6927 3523 6927 3526 6927 3523 6928 3527 6928 3526 6928 3526 6929 3527 6929 3520 6929 3526 6930 3520 6930 3528 6930 3520 6931 3529 6931 3528 6931 3528 6932 3529 6932 3530 6932 3528 6933 3530 6933 3532 6933 3530 6934 3531 6934 3532 6934 3532 6935 3531 6935 3519 6935 3532 6936 3519 6936 3537 6936 3519 6937 3518 6937 3537 6937 3537 6938 3518 6938 3533 6938 3537 6939 3533 6939 3534 6939 3514 6940 3535 6940 3516 6940 3516 6941 3535 6941 3534 6941 3516 6942 3534 6942 3517 6942 3517 6943 3534 6943 3533 6943 3535 6944 4375 6944 3534 6944 3534 6945 4375 6945 3536 6945 3534 6946 3536 6946 3537 6946 3537 6947 3536 6947 4384 6947 3537 6948 4384 6948 3532 6948 3532 6949 4384 6949 3538 6949 3532 6950 3538 6950 3528 6950 3528 6951 3538 6951 3539 6951 3528 6952 3539 6952 3526 6952 3526 6953 3539 6953 3540 6953 3526 6954 3540 6954 3525 6954 3525 6955 3540 6955 5433 6955 3624 6956 4675 6956 3625 6956 3625 6957 4675 6957 3541 6957 3625 6958 3541 6958 3628 6958 3628 6959 3541 6959 3542 6959 3628 6960 3542 6960 3543 6960 3543 6961 3542 6961 4677 6961 3543 6962 4677 6962 3630 6962 3630 6963 4677 6963 4676 6963 3630 6964 4676 6964 3544 6964 3544 6965 4676 6965 4672 6965 3544 6966 4672 6966 3545 6966 3545 6967 4672 6967 4981 6967 3545 6968 4981 6968 5429 6968 5429 6969 4981 6969 4980 6969 3632 6970 5424 6970 3546 6970 3546 6971 5424 6971 3547 6971 3546 6972 3547 6972 3635 6972 3635 6973 3547 6973 3548 6973 3635 6974 3548 6974 3549 6974 3549 6975 3548 6975 3550 6975 3549 6976 3550 6976 3636 6976 3636 6977 3550 6977 4965 6977 3636 6978 4965 6978 3551 6978 3551 6979 4965 6979 3552 6979 3551 6980 3552 6980 3553 6980 3553 6981 3552 6981 4691 6981 3637 6982 3554 6982 3639 6982 3639 6983 3554 6983 4689 6983 3639 6984 4689 6984 3642 6984 3642 6985 4689 6985 3555 6985 3642 6986 3555 6986 3643 6986 3643 6987 3555 6987 3556 6987 3643 6988 3556 6988 3557 6988 3557 6989 3556 6989 3559 6989 3557 6990 3559 6990 3558 6990 3558 6991 3559 6991 4686 6991 3558 6992 4686 6992 3560 6992 3560 6993 4686 6993 4961 6993 5341 6994 5418 6994 5398 6994 5398 6995 3575 6995 5341 6995 5341 6996 3575 6996 3561 6996 5341 6997 3561 6997 3562 6997 3561 6998 3576 6998 3562 6998 3562 6999 3576 6999 3563 6999 3562 7000 3563 7000 3564 7000 3563 7001 3565 7001 3564 7001 3564 7002 3565 7002 3566 7002 3564 7003 3566 7003 5347 7003 5347 7004 3566 7004 3574 7004 5347 7005 3574 7005 3567 7005 3574 7006 3573 7006 3567 7006 3567 7007 3573 7007 3572 7007 3567 7008 3572 7008 3568 7008 3570 7009 5408 7009 3571 7009 3571 7010 5408 7010 3568 7010 3571 7011 3568 7011 3569 7011 3569 7012 3568 7012 3572 7012 3570 7013 3571 7013 5395 7013 5395 7014 3571 7014 3583 7014 3571 7015 3569 7015 3583 7015 3583 7016 3569 7016 3572 7016 3583 7017 3572 7017 3582 7017 3572 7018 3573 7018 3582 7018 3582 7019 3573 7019 3574 7019 3582 7020 3574 7020 3580 7020 3574 7021 3566 7021 3580 7021 3580 7022 3566 7022 3565 7022 3580 7023 3565 7023 3579 7023 3565 7024 3563 7024 3579 7024 3579 7025 3563 7025 3576 7025 3579 7026 3576 7026 3577 7026 5398 7027 5397 7027 3575 7027 3575 7028 5397 7028 3577 7028 3575 7029 3577 7029 3561 7029 3561 7030 3577 7030 3576 7030 5397 7031 4455 7031 3577 7031 3577 7032 4455 7032 4457 7032 3577 7033 4457 7033 3579 7033 3579 7034 4457 7034 3578 7034 3579 7035 3578 7035 3580 7035 3580 7036 3578 7036 3581 7036 3580 7037 3581 7037 3582 7037 3582 7038 3581 7038 4446 7038 3582 7039 4446 7039 3583 7039 3583 7040 4446 7040 4448 7040 3583 7041 4448 7041 5395 7041 5395 7042 4448 7042 5396 7042 3592 7043 5329 7043 3593 7043 3593 7044 5329 7044 3584 7044 3593 7045 3584 7045 3585 7045 3585 7046 3584 7046 5327 7046 3585 7047 5327 7047 3595 7047 3595 7048 5327 7048 3586 7048 3595 7049 3586 7049 3587 7049 3587 7050 3586 7050 3588 7050 3587 7051 3588 7051 3597 7051 3597 7052 3588 7052 3589 7052 3597 7053 3589 7053 5374 7053 5374 7054 3589 7054 3590 7054 5382 7055 3592 7055 3591 7055 3591 7056 3592 7056 3593 7056 3591 7057 3593 7057 3601 7057 3601 7058 3593 7058 3585 7058 3601 7059 3585 7059 3600 7059 3600 7060 3585 7060 3595 7060 3600 7061 3595 7061 3594 7061 3594 7062 3595 7062 3587 7062 3594 7063 3587 7063 3596 7063 3596 7064 3587 7064 3597 7064 3596 7065 3597 7065 3598 7065 3598 7066 3597 7066 5374 7066 3598 7067 5373 7067 3596 7067 3596 7068 5373 7068 4435 7068 3596 7069 4435 7069 3594 7069 3594 7070 4435 7070 3599 7070 3594 7071 3599 7071 3600 7071 3600 7072 3599 7072 4438 7072 3600 7073 4438 7073 3601 7073 3601 7074 4438 7074 4440 7074 3601 7075 4440 7075 3591 7075 3591 7076 4440 7076 4441 7076 3591 7077 4441 7077 5382 7077 5382 7078 4441 7078 4442 7078 5360 7079 5312 7079 3613 7079 3613 7080 5312 7080 3602 7080 3613 7081 3602 7081 3603 7081 3603 7082 3602 7082 3604 7082 3603 7083 3604 7083 3605 7083 3605 7084 3604 7084 3606 7084 3605 7085 3606 7085 3616 7085 3616 7086 3606 7086 3608 7086 3616 7087 3608 7087 3607 7087 3607 7088 3608 7088 3609 7088 3607 7089 3609 7089 3610 7089 3610 7090 3609 7090 3611 7090 3612 7091 5360 7091 3622 7091 3622 7092 5360 7092 3613 7092 3622 7093 3613 7093 3621 7093 3621 7094 3613 7094 3603 7094 3621 7095 3603 7095 3614 7095 3614 7096 3603 7096 3605 7096 3614 7097 3605 7097 3615 7097 3615 7098 3605 7098 3616 7098 3615 7099 3616 7099 3618 7099 3618 7100 3616 7100 3607 7100 3618 7101 3607 7101 3617 7101 3617 7102 3607 7102 3610 7102 3617 7103 4421 7103 3618 7103 3618 7104 4421 7104 3619 7104 3618 7105 3619 7105 3615 7105 3615 7106 3619 7106 4422 7106 3615 7107 4422 7107 3614 7107 3614 7108 4422 7108 3620 7108 3614 7109 3620 7109 3621 7109 3621 7110 3620 7110 4424 7110 3621 7111 4424 7111 3622 7111 3622 7112 4424 7112 4425 7112 3622 7113 4425 7113 3612 7113 3612 7114 4425 7114 4426 7114 3623 7115 3624 7115 3626 7115 3626 7116 3624 7116 3625 7116 3626 7117 3625 7117 5348 7117 5348 7118 3625 7118 3628 7118 5348 7119 3628 7119 3627 7119 3627 7120 3628 7120 3543 7120 3627 7121 3543 7121 3629 7121 3629 7122 3543 7122 3630 7122 3629 7123 3630 7123 5340 7123 5340 7124 3630 7124 3544 7124 5340 7125 3544 7125 3631 7125 3631 7126 3544 7126 3545 7126 3631 7127 3545 7127 5342 7127 5342 7128 3545 7128 5429 7128 5328 7129 3632 7129 3633 7129 3633 7130 3632 7130 3546 7130 3633 7131 3546 7131 3634 7131 3634 7132 3546 7132 3635 7132 3634 7133 3635 7133 5326 7133 5326 7134 3635 7134 3549 7134 5326 7135 3549 7135 5325 7135 5325 7136 3549 7136 3636 7136 5325 7137 3636 7137 5324 7137 5324 7138 3636 7138 3551 7138 5324 7139 3551 7139 5323 7139 5323 7140 3551 7140 3553 7140 5311 7141 3637 7141 3638 7141 3638 7142 3637 7142 3639 7142 3638 7143 3639 7143 3640 7143 3640 7144 3639 7144 3642 7144 3640 7145 3642 7145 3641 7145 3641 7146 3642 7146 3643 7146 3641 7147 3643 7147 3644 7147 3644 7148 3643 7148 3557 7148 3644 7149 3557 7149 3645 7149 3645 7150 3557 7150 3558 7150 3645 7151 3558 7151 5299 7151 5299 7152 3558 7152 3560 7152 3646 7153 4710 7153 3647 7153 3647 7154 4710 7154 4711 7154 3647 7155 4711 7155 3648 7155 3648 7156 4711 7156 4712 7156 3648 7157 4712 7157 3654 7157 3654 7158 4712 7158 3649 7158 3654 7159 3649 7159 3656 7159 3656 7160 3649 7160 3650 7160 3656 7161 3650 7161 3657 7161 3657 7162 3650 7162 3651 7162 3657 7163 3651 7163 3659 7163 3659 7164 3651 7164 4715 7164 3659 7165 4715 7165 5293 7165 5293 7166 4715 7166 4903 7166 3664 7167 3646 7167 3663 7167 3663 7168 3646 7168 3647 7168 3663 7169 3647 7169 3652 7169 3652 7170 3647 7170 3648 7170 3652 7171 3648 7171 3653 7171 3653 7172 3648 7172 3654 7172 3653 7173 3654 7173 3655 7173 3655 7174 3654 7174 3656 7174 3655 7175 3656 7175 3658 7175 3658 7176 3656 7176 3657 7176 3658 7177 3657 7177 3660 7177 3660 7178 3657 7178 3659 7178 3660 7179 3659 7179 5284 7179 5284 7180 3659 7180 5293 7180 5284 7181 4238 7181 3660 7181 3660 7182 4238 7182 4236 7182 3660 7183 4236 7183 3658 7183 3658 7184 4236 7184 4235 7184 3658 7185 4235 7185 3655 7185 3655 7186 4235 7186 4234 7186 3655 7187 4234 7187 3653 7187 3653 7188 4234 7188 3661 7188 3653 7189 3661 7189 3652 7189 3652 7190 3661 7190 3662 7190 3652 7191 3662 7191 3663 7191 3663 7192 3662 7192 4231 7192 3663 7193 4231 7193 3664 7193 3664 7194 4231 7194 4230 7194 3665 7195 5272 7195 3684 7195 3684 7196 3683 7196 3665 7196 3665 7197 3683 7197 3682 7197 3665 7198 3682 7198 3666 7198 3682 7199 3681 7199 3666 7199 3666 7200 3681 7200 3679 7200 3666 7201 3679 7201 3667 7201 3667 7202 3679 7202 3668 7202 3668 7203 3669 7203 3667 7203 3667 7204 3669 7204 3676 7204 3667 7205 3676 7205 4717 7205 3676 7206 3675 7206 4717 7206 4717 7207 3675 7207 3673 7207 4717 7208 3673 7208 4718 7208 5271 7209 4720 7209 3670 7209 3670 7210 4720 7210 4718 7210 3670 7211 4718 7211 3672 7211 3672 7212 4718 7212 3673 7212 5270 7213 5271 7213 3671 7213 3671 7214 5271 7214 3670 7214 3671 7215 3670 7215 3687 7215 3687 7216 3670 7216 3672 7216 3687 7217 3672 7217 3688 7217 3688 7218 3672 7218 3673 7218 3688 7219 3673 7219 3674 7219 3674 7220 3673 7220 3675 7220 3674 7221 3675 7221 3689 7221 3689 7222 3675 7222 3676 7222 3689 7223 3676 7223 3677 7223 3677 7224 3676 7224 3669 7224 3677 7225 3669 7225 3678 7225 3678 7226 3669 7226 3668 7226 3678 7227 3668 7227 3691 7227 3691 7228 3668 7228 3679 7228 3691 7229 3679 7229 3680 7229 3680 7230 3679 7230 3681 7230 3680 7231 3681 7231 3694 7231 3694 7232 3681 7232 3682 7232 3694 7233 3682 7233 3693 7233 3693 7234 3682 7234 3683 7234 3693 7235 3683 7235 5264 7235 5264 7236 3683 7236 3684 7236 3686 7237 3685 7237 5270 7237 5270 7238 3671 7238 3686 7238 3686 7239 3671 7239 3687 7239 3686 7240 3687 7240 4244 7240 4244 7241 3687 7241 3688 7241 3688 7242 3674 7242 4244 7242 4244 7243 3674 7243 3689 7243 4244 7244 3689 7244 3690 7244 3689 7245 3677 7245 3690 7245 3690 7246 3677 7246 3678 7246 3690 7247 3678 7247 3692 7247 3678 7248 3691 7248 3692 7248 3692 7249 3691 7249 3680 7249 3692 7250 3680 7250 4243 7250 5264 7251 4252 7251 3693 7251 3693 7252 4252 7252 4243 7252 3693 7253 4243 7253 3694 7253 3694 7254 4243 7254 3680 7254 5255 7255 3695 7255 3696 7255 3696 7256 3695 7256 3697 7256 3696 7257 3697 7257 3698 7257 3698 7258 3697 7258 4732 7258 3698 7259 4732 7259 3706 7259 3706 7260 4732 7260 4731 7260 3706 7261 4731 7261 3699 7261 3699 7262 4731 7262 3700 7262 3699 7263 3700 7263 3707 7263 3707 7264 3700 7264 4730 7264 3707 7265 4730 7265 3709 7265 3709 7266 4730 7266 3701 7266 3709 7267 3701 7267 5256 7267 5256 7268 3701 7268 4729 7268 3702 7269 5255 7269 3716 7269 3716 7270 5255 7270 3696 7270 3716 7271 3696 7271 3703 7271 3703 7272 3696 7272 3698 7272 3703 7273 3698 7273 3704 7273 3704 7274 3698 7274 3706 7274 3704 7275 3706 7275 3705 7275 3705 7276 3706 7276 3699 7276 3705 7277 3699 7277 3712 7277 3712 7278 3699 7278 3707 7278 3712 7279 3707 7279 3708 7279 3708 7280 3707 7280 3709 7280 3708 7281 3709 7281 3710 7281 3710 7282 3709 7282 5256 7282 3710 7283 5246 7283 3708 7283 3708 7284 5246 7284 3711 7284 3708 7285 3711 7285 3712 7285 3712 7286 3711 7286 3713 7286 3712 7287 3713 7287 3705 7287 3705 7288 3713 7288 4253 7288 3705 7289 4253 7289 3704 7289 3704 7290 4253 7290 3714 7290 3704 7291 3714 7291 3703 7291 3703 7292 3714 7292 3715 7292 3703 7293 3715 7293 3716 7293 3716 7294 3715 7294 3717 7294 3716 7295 3717 7295 3702 7295 3702 7296 3717 7296 3718 7296 4746 7297 4744 7297 5219 7297 5219 7298 3719 7298 4746 7298 4746 7299 3719 7299 3720 7299 4746 7300 3720 7300 3723 7300 3720 7301 3721 7301 3723 7301 3723 7302 3721 7302 3722 7302 3723 7303 3722 7303 3724 7303 3724 7304 3722 7304 3734 7304 3724 7305 3734 7305 4737 7305 3734 7306 3725 7306 4737 7306 4737 7307 3725 7307 3733 7307 4737 7308 3733 7308 4739 7308 3733 7309 3732 7309 4739 7309 4739 7310 3732 7310 3731 7310 4739 7311 3731 7311 3726 7311 5234 7312 4740 7312 3728 7312 3728 7313 4740 7313 3726 7313 3728 7314 3726 7314 3729 7314 3729 7315 3726 7315 3731 7315 5234 7316 3728 7316 3727 7316 3727 7317 3728 7317 3730 7317 3728 7318 3729 7318 3730 7318 3730 7319 3729 7319 3731 7319 3730 7320 3731 7320 3740 7320 3731 7321 3732 7321 3740 7321 3740 7322 3732 7322 3733 7322 3740 7323 3733 7323 3735 7323 3733 7324 3725 7324 3735 7324 3735 7325 3725 7325 3734 7325 3735 7326 3734 7326 3738 7326 3734 7327 3722 7327 3738 7327 3738 7328 3722 7328 3721 7328 3738 7329 3721 7329 3736 7329 5219 7330 5211 7330 3719 7330 3719 7331 5211 7331 3736 7331 3719 7332 3736 7332 3720 7332 3720 7333 3736 7333 3721 7333 5211 7334 4275 7334 3736 7334 3736 7335 4275 7335 3737 7335 3736 7336 3737 7336 3738 7336 3738 7337 3737 7337 3739 7337 3738 7338 3739 7338 3735 7338 3735 7339 3739 7339 4267 7339 3735 7340 4267 7340 3740 7340 3740 7341 4267 7341 4268 7341 3740 7342 4268 7342 3730 7342 3730 7343 4268 7343 3741 7343 3730 7344 3741 7344 3727 7344 3727 7345 3741 7345 5217 7345 5123 7346 5210 7346 3835 7346 3835 7347 5210 7347 4751 7347 3835 7348 4751 7348 3742 7348 3742 7349 4751 7349 3743 7349 3742 7350 3743 7350 3744 7350 3744 7351 3743 7351 3745 7351 3744 7352 3745 7352 3837 7352 3837 7353 3745 7353 4753 7353 3837 7354 4753 7354 3839 7354 3839 7355 4753 7355 4760 7355 3839 7356 4760 7356 5117 7356 5117 7357 4760 7357 4758 7357 3747 7358 4726 7358 3746 7358 3746 7359 3851 7359 3747 7359 3747 7360 3851 7360 3748 7360 3747 7361 3748 7361 3749 7361 3748 7362 3850 7362 3749 7362 3749 7363 3850 7363 3849 7363 3749 7364 3849 7364 4749 7364 3849 7365 3847 7365 4749 7365 4749 7366 3847 7366 3750 7366 4749 7367 3750 7367 3751 7367 3751 7368 3750 7368 3846 7368 3751 7369 3846 7369 3752 7369 3846 7370 3844 7370 3752 7370 3752 7371 3844 7371 3753 7371 3752 7372 3753 7372 4747 7372 5105 7373 5197 7373 3842 7373 3842 7374 5197 7374 4747 7374 3842 7375 4747 7375 3843 7375 3843 7376 4747 7376 3753 7376 3852 7377 5196 7377 3754 7377 3754 7378 5196 7378 3755 7378 3754 7379 3755 7379 3854 7379 3854 7380 3755 7380 3756 7380 3854 7381 3756 7381 3757 7381 3757 7382 3756 7382 3758 7382 3757 7383 3758 7383 3759 7383 3759 7384 3758 7384 3760 7384 3759 7385 3760 7385 3856 7385 3856 7386 3760 7386 3761 7386 3856 7387 3761 7387 3762 7387 3762 7388 3761 7388 4918 7388 3762 7389 4918 7389 3763 7389 3763 7390 4918 7390 4917 7390 5126 7391 3780 7391 5125 7391 5125 7392 3780 7392 3764 7392 5125 7393 3764 7393 3765 7393 3764 7394 3778 7394 3765 7394 3765 7395 3778 7395 3777 7395 3765 7396 3777 7396 3768 7396 3768 7397 3777 7397 3766 7397 3766 7398 3767 7398 3768 7398 3768 7399 3767 7399 3769 7399 3768 7400 3769 7400 3772 7400 3770 7401 5132 7401 3774 7401 3774 7402 5132 7402 3771 7402 3774 7403 3771 7403 3775 7403 3775 7404 3771 7404 3772 7404 3775 7405 3772 7405 3773 7405 3773 7406 3772 7406 3769 7406 5175 7407 3770 7407 3774 7407 5175 7408 3774 7408 3786 7408 3786 7409 3774 7409 3775 7409 3786 7410 3775 7410 3776 7410 3776 7411 3775 7411 3773 7411 3776 7412 3773 7412 3784 7412 3773 7413 3769 7413 3784 7413 3784 7414 3769 7414 3767 7414 3784 7415 3767 7415 3783 7415 3767 7416 3766 7416 3783 7416 3783 7417 3766 7417 3777 7417 3783 7418 3777 7418 3782 7418 3777 7419 3778 7419 3782 7419 3782 7420 3778 7420 3764 7420 3782 7421 3764 7421 3779 7421 3779 7422 3764 7422 3780 7422 3779 7423 3780 7423 3781 7423 3781 7424 4210 7424 3779 7424 3779 7425 4210 7425 4211 7425 3779 7426 4211 7426 3782 7426 3782 7427 4211 7427 4197 7427 3782 7428 4197 7428 3783 7428 3783 7429 4197 7429 4199 7429 3783 7430 4199 7430 3784 7430 3784 7431 4199 7431 4200 7431 3784 7432 4200 7432 3776 7432 3776 7433 4200 7433 3785 7433 3776 7434 3785 7434 3786 7434 3786 7435 3785 7435 3787 7435 3786 7436 3787 7436 5175 7436 5175 7437 3787 7437 5176 7437 5174 7438 3788 7438 3789 7438 3789 7439 3788 7439 3790 7439 3789 7440 3790 7440 3797 7440 3797 7441 3790 7441 3791 7441 3797 7442 3791 7442 3801 7442 3801 7443 3791 7443 3792 7443 3801 7444 3792 7444 3803 7444 3803 7445 3792 7445 5111 7445 3803 7446 5111 7446 3794 7446 3794 7447 5111 7447 3793 7447 3794 7448 3793 7448 3804 7448 3804 7449 3793 7449 3795 7449 3804 7450 3795 7450 5161 7450 5161 7451 3795 7451 5169 7451 3796 7452 5174 7452 3789 7452 3796 7453 3789 7453 3798 7453 3798 7454 3789 7454 3797 7454 3798 7455 3797 7455 3799 7455 3799 7456 3797 7456 3800 7456 3800 7457 3797 7457 3801 7457 3800 7458 3801 7458 3802 7458 3802 7459 3801 7459 3806 7459 3806 7460 3801 7460 3803 7460 3806 7461 3803 7461 3811 7461 3811 7462 3803 7462 3809 7462 3809 7463 3803 7463 3794 7463 3809 7464 3794 7464 3808 7464 3808 7465 3794 7465 3804 7465 3808 7466 3804 7466 3807 7466 3807 7467 3804 7467 5161 7467 3807 7468 5161 7468 5160 7468 4225 7469 3796 7469 3805 7469 3805 7470 3796 7470 3798 7470 3805 7471 3798 7471 4222 7471 3798 7472 3799 7472 4222 7472 4222 7473 3799 7473 3800 7473 4222 7474 3800 7474 4221 7474 4221 7475 3800 7475 3802 7475 3802 7476 3806 7476 4221 7476 4221 7477 3806 7477 3811 7477 4221 7478 3811 7478 3810 7478 5160 7479 4218 7479 3807 7479 3807 7480 4218 7480 4219 7480 3807 7481 4219 7481 3808 7481 3808 7482 4219 7482 3810 7482 3808 7483 3810 7483 3809 7483 3809 7484 3810 7484 3811 7484 3816 7485 5091 7485 3817 7485 3817 7486 5091 7486 5093 7486 3817 7487 5093 7487 3818 7487 3818 7488 5093 7488 5095 7488 3818 7489 5095 7489 3819 7489 3819 7490 5095 7490 3812 7490 3819 7491 3812 7491 3813 7491 3813 7492 3812 7492 5081 7492 3813 7493 5081 7493 3814 7493 3814 7494 5081 7494 5082 7494 3814 7495 5082 7495 3822 7495 3822 7496 5082 7496 3815 7496 3822 7497 3815 7497 5140 7497 5140 7498 3815 7498 5085 7498 5133 7499 3816 7499 3831 7499 3831 7500 3816 7500 3817 7500 3831 7501 3817 7501 3829 7501 3829 7502 3817 7502 3818 7502 3829 7503 3818 7503 3827 7503 3827 7504 3818 7504 3819 7504 3827 7505 3819 7505 3826 7505 3826 7506 3819 7506 3813 7506 3826 7507 3813 7507 3820 7507 3820 7508 3813 7508 3814 7508 3820 7509 3814 7509 3821 7509 3821 7510 3814 7510 3822 7510 3821 7511 3822 7511 3823 7511 3823 7512 3822 7512 5140 7512 3823 7513 3824 7513 3821 7513 3821 7514 3824 7514 4288 7514 3821 7515 4288 7515 3820 7515 3820 7516 4288 7516 3825 7516 3820 7517 3825 7517 3826 7517 3826 7518 3825 7518 4277 7518 3826 7519 4277 7519 3827 7519 3827 7520 4277 7520 3828 7520 3827 7521 3828 7521 3829 7521 3829 7522 3828 7522 3830 7522 3829 7523 3830 7523 3831 7523 3831 7524 3830 7524 3832 7524 3831 7525 3832 7525 5133 7525 5133 7526 3832 7526 4280 7526 5122 7527 5123 7527 3833 7527 3833 7528 5123 7528 3835 7528 3833 7529 3835 7529 3834 7529 3834 7530 3835 7530 3742 7530 3834 7531 3742 7531 3836 7531 3836 7532 3742 7532 3744 7532 3836 7533 3744 7533 5124 7533 5124 7534 3744 7534 3837 7534 5124 7535 3837 7535 3838 7535 3838 7536 3837 7536 3839 7536 3838 7537 3839 7537 5127 7537 5127 7538 3839 7538 5117 7538 5105 7539 3842 7539 3840 7539 3840 7540 3842 7540 3841 7540 3842 7541 3843 7541 3841 7541 3841 7542 3843 7542 3753 7542 3841 7543 3753 7543 3845 7543 3753 7544 3844 7544 3845 7544 3845 7545 3844 7545 3846 7545 3845 7546 3846 7546 5112 7546 3846 7547 3750 7547 5112 7547 5112 7548 3750 7548 3847 7548 5112 7549 3847 7549 3848 7549 3847 7550 3849 7550 3848 7550 3848 7551 3849 7551 3850 7551 3848 7552 3850 7552 5106 7552 3746 7553 5107 7553 3851 7553 3851 7554 5107 7554 5106 7554 3851 7555 5106 7555 3748 7555 3748 7556 5106 7556 3850 7556 5092 7557 3852 7557 5094 7557 5094 7558 3852 7558 3754 7558 5094 7559 3754 7559 5096 7559 5096 7560 3754 7560 3854 7560 5096 7561 3854 7561 3853 7561 3853 7562 3854 7562 3757 7562 3853 7563 3757 7563 3855 7563 3855 7564 3757 7564 3759 7564 3855 7565 3759 7565 5083 7565 5083 7566 3759 7566 3856 7566 5083 7567 3856 7567 5084 7567 5084 7568 3856 7568 3762 7568 5084 7569 3762 7569 3857 7569 3857 7570 3762 7570 3763 7570 3858 7571 5074 7571 3860 7571 3858 7572 3860 7572 3859 7572 3859 7573 3860 7573 3861 7573 3859 7574 3861 7574 4775 7574 4775 7575 3861 7575 3038 7575 4775 7576 3038 7576 4776 7576 4776 7577 3038 7577 3862 7577 4776 7578 3862 7578 3863 7578 3863 7579 3862 7579 3864 7579 3863 7580 3864 7580 3865 7580 3865 7581 3864 7581 3866 7581 3865 7582 3866 7582 4773 7582 4773 7583 3866 7583 3035 7583 4773 7584 3035 7584 3867 7584 3867 7585 3035 7585 3868 7585 3867 7586 3868 7586 3869 7586 3869 7587 3868 7587 3870 7587 3869 7588 3870 7588 4771 7588 4771 7589 3870 7589 3871 7589 4771 7590 3871 7590 3872 7590 3872 7591 3871 7591 3030 7591 3872 7592 3030 7592 3873 7592 3873 7593 3030 7593 3874 7593 3873 7594 3874 7594 3875 7594 3875 7595 3874 7595 3876 7595 3875 7596 3876 7596 3877 7596 3877 7597 3876 7597 3878 7597 3877 7598 3878 7598 5029 7598 5029 7599 3878 7599 3025 7599 5029 7600 3025 7600 3879 7600 3879 7601 3025 7601 3024 7601 3879 7602 3024 7602 5058 7602 3880 7603 5969 7603 3071 7603 3880 7604 3071 7604 3881 7604 3881 7605 3071 7605 3882 7605 3881 7606 3882 7606 3883 7606 3883 7607 3882 7607 3066 7607 3883 7608 3066 7608 2935 7608 2935 7609 3066 7609 3067 7609 2935 7610 3067 7610 3884 7610 3884 7611 3067 7611 3885 7611 3884 7612 3885 7612 3886 7612 3886 7613 3885 7613 3887 7613 3886 7614 3887 7614 3888 7614 3888 7615 3887 7615 3890 7615 3888 7616 3890 7616 3889 7616 3889 7617 3890 7617 3058 7617 3889 7618 3058 7618 2938 7618 2938 7619 3058 7619 3055 7619 2938 7620 3055 7620 2940 7620 2940 7621 3055 7621 3054 7621 2940 7622 3054 7622 3891 7622 3891 7623 3054 7623 3052 7623 3891 7624 3052 7624 3892 7624 3892 7625 3052 7625 3051 7625 3892 7626 3051 7626 3893 7626 3893 7627 3051 7627 3895 7627 3893 7628 3895 7628 3894 7628 3894 7629 3895 7629 3896 7629 3894 7630 3896 7630 3897 7630 3897 7631 3896 7631 3043 7631 3897 7632 3043 7632 2944 7632 2944 7633 3043 7633 3045 7633 2944 7634 3045 7634 3898 7634 3898 7635 3045 7635 3041 7635 3898 7636 3041 7636 2946 7636 2946 7637 3041 7637 3042 7637 2946 7638 3042 7638 2947 7638 2947 7639 3042 7639 3899 7639 2947 7640 3899 7640 2948 7640 4636 7641 4637 7641 3900 7641 3900 7642 4637 7642 3901 7642 3900 7643 3901 7643 6132 7643 6132 7644 3901 7644 3902 7644 6132 7645 3902 7645 6133 7645 6133 7646 3902 7646 3903 7646 6133 7647 3903 7647 3904 7647 3904 7648 3903 7648 2953 7648 3904 7649 2953 7649 6135 7649 6135 7650 2953 7650 2955 7650 6135 7651 2955 7651 3905 7651 3905 7652 2955 7652 3906 7652 3905 7653 3906 7653 4630 7653 4630 7654 3906 7654 4631 7654 4629 7655 3907 7655 6140 7655 6140 7656 3907 7656 2957 7656 6140 7657 2957 7657 6141 7657 6141 7658 2957 7658 2959 7658 6141 7659 2959 7659 6137 7659 6137 7660 2959 7660 3908 7660 6137 7661 3908 7661 6139 7661 6139 7662 3908 7662 2960 7662 6139 7663 2960 7663 3909 7663 3909 7664 2960 7664 2962 7664 3909 7665 2962 7665 6138 7665 6138 7666 2962 7666 4618 7666 6148 7667 3910 7667 3911 7667 3911 7668 3910 7668 2964 7668 3911 7669 2964 7669 6147 7669 6147 7670 2964 7670 3912 7670 6147 7671 3912 7671 6146 7671 6146 7672 3912 7672 2968 7672 6146 7673 2968 7673 6143 7673 6143 7674 2968 7674 2969 7674 6143 7675 2969 7675 6144 7675 6144 7676 2969 7676 3913 7676 6144 7677 3913 7677 6145 7677 6145 7678 3913 7678 6087 7678 3914 7679 4611 7679 6151 7679 6151 7680 4611 7680 3915 7680 6151 7681 3915 7681 3916 7681 3916 7682 3915 7682 3918 7682 3916 7683 3918 7683 3917 7683 3917 7684 3918 7684 2971 7684 3917 7685 2971 7685 3919 7685 3919 7686 2971 7686 2974 7686 3919 7687 2974 7687 3921 7687 3921 7688 2974 7688 3920 7688 3921 7689 3920 7689 4603 7689 4603 7690 3920 7690 3922 7690 4602 7691 2976 7691 6156 7691 6156 7692 2976 7692 3923 7692 6156 7693 3923 7693 3924 7693 3924 7694 3923 7694 3925 7694 3924 7695 3925 7695 6161 7695 6161 7696 3925 7696 2977 7696 6161 7697 2977 7697 6160 7697 6160 7698 2977 7698 3926 7698 6160 7699 3926 7699 3927 7699 3927 7700 3926 7700 3928 7700 3927 7701 3928 7701 6153 7701 6153 7702 3928 7702 6070 7702 3929 7703 6165 7703 4590 7703 6061 7704 6162 7704 2987 7704 2987 7705 6162 7705 3930 7705 2987 7706 3930 7706 3931 7706 3931 7707 3930 7707 3932 7707 3935 7708 2984 7708 3932 7708 3932 7709 2984 7709 2986 7709 3932 7710 2986 7710 3931 7710 3933 7711 3934 7711 3935 7711 3935 7712 3934 7712 2983 7712 3935 7713 2983 7713 2984 7713 4590 7714 3936 7714 3929 7714 3929 7715 3936 7715 3937 7715 3929 7716 3937 7716 3933 7716 3933 7717 3937 7717 3938 7717 3933 7718 3938 7718 3934 7718 6167 7719 3939 7719 2989 7719 2996 7720 3941 7720 3940 7720 3940 7721 3941 7721 3942 7721 3940 7722 3942 7722 2994 7722 2994 7723 3942 7723 6166 7723 3943 7724 3944 7724 6166 7724 6166 7725 3944 7725 3945 7725 6166 7726 3945 7726 2994 7726 3949 7727 2992 7727 3943 7727 3943 7728 2992 7728 3946 7728 3943 7729 3946 7729 3944 7729 2989 7730 3947 7730 6167 7730 6167 7731 3947 7731 3948 7731 6167 7732 3948 7732 3949 7732 3949 7733 3948 7733 2991 7733 3949 7734 2991 7734 2992 7734 3954 7735 6171 7735 3950 7735 4577 7736 6170 7736 3008 7736 3008 7737 6170 7737 3951 7737 3008 7738 3951 7738 3006 7738 3006 7739 3951 7739 6172 7739 3952 7740 3953 7740 6172 7740 6172 7741 3953 7741 3004 7741 6172 7742 3004 7742 3006 7742 3955 7743 3002 7743 3952 7743 3952 7744 3002 7744 3003 7744 3952 7745 3003 7745 3953 7745 3950 7746 2997 7746 3954 7746 3954 7747 2997 7747 2999 7747 3954 7748 2999 7748 3955 7748 3955 7749 2999 7749 3001 7749 3955 7750 3001 7750 3002 7750 6177 7751 6034 7751 6175 7751 6175 7752 6034 7752 3010 7752 6175 7753 3010 7753 3956 7753 3956 7754 3010 7754 3012 7754 3956 7755 3012 7755 3957 7755 3957 7756 3012 7756 3958 7756 3957 7757 3958 7757 3960 7757 3960 7758 3958 7758 3959 7758 3960 7759 3959 7759 6174 7759 6174 7760 3959 7760 3961 7760 6174 7761 3961 7761 3962 7761 3962 7762 3961 7762 3963 7762 3962 7763 3963 7763 3964 7763 3964 7764 3963 7764 4564 7764 3968 7765 6182 7765 4554 7765 3965 7766 6181 7766 3023 7766 3023 7767 6181 7767 3966 7767 3023 7768 3966 7768 3021 7768 3021 7769 3966 7769 6180 7769 6179 7770 3967 7770 6180 7770 6180 7771 3967 7771 3020 7771 6180 7772 3020 7772 3021 7772 3970 7773 3972 7773 6179 7773 6179 7774 3972 7774 3017 7774 6179 7775 3017 7775 3967 7775 4554 7776 3969 7776 3968 7776 3968 7777 3969 7777 3015 7777 3968 7778 3015 7778 3970 7778 3970 7779 3015 7779 3971 7779 3970 7780 3971 7780 3972 7780 12019 7781 10865 7781 12015 7781 12015 7782 10865 7782 3973 7782 12015 7783 3973 7783 3974 7783 3974 7784 3973 7784 509 7784 3974 7785 509 7785 3975 7785 3975 7786 509 7786 3976 7786 3975 7787 3976 7787 12017 7787 12017 7788 3976 7788 512 7788 12017 7789 512 7789 12016 7789 12016 7790 512 7790 513 7790 12016 7791 513 7791 3977 7791 3977 7792 513 7792 514 7792 3978 7793 4146 7793 515 7793 10845 7794 3979 7794 523 7794 523 7795 3979 7795 3980 7795 523 7796 3980 7796 521 7796 521 7797 3980 7797 3981 7797 12020 7798 3983 7798 3981 7798 3981 7799 3983 7799 519 7799 3981 7800 519 7800 521 7800 3986 7801 3982 7801 12020 7801 12020 7802 3982 7802 518 7802 12020 7803 518 7803 3983 7803 515 7804 3984 7804 3978 7804 3978 7805 3984 7805 3985 7805 3978 7806 3985 7806 3986 7806 3986 7807 3985 7807 3987 7807 3986 7808 3987 7808 3982 7808 4137 7809 4136 7809 12027 7809 12027 7810 4136 7810 524 7810 12027 7811 524 7811 12022 7811 12022 7812 524 7812 3988 7812 12022 7813 3988 7813 12023 7813 12023 7814 3988 7814 3989 7814 12023 7815 3989 7815 12024 7815 12024 7816 3989 7816 527 7816 12024 7817 527 7817 3990 7817 3990 7818 527 7818 528 7818 3990 7819 528 7819 12028 7819 12028 7820 528 7820 530 7820 4134 7821 4135 7821 12030 7821 12030 7822 4135 7822 3991 7822 12030 7823 3991 7823 12035 7823 12035 7824 3991 7824 533 7824 12035 7825 533 7825 12034 7825 12034 7826 533 7826 534 7826 12034 7827 534 7827 3992 7827 3992 7828 534 7828 3993 7828 3992 7829 3993 7829 12033 7829 12033 7830 3993 7830 536 7830 12033 7831 536 7831 12029 7831 12029 7832 536 7832 4129 7832 3994 7833 10827 7833 12043 7833 12043 7834 10827 7834 538 7834 12043 7835 538 7835 3995 7835 3995 7836 538 7836 3996 7836 3995 7837 3996 7837 3997 7837 3997 7838 3996 7838 540 7838 3997 7839 540 7839 3998 7839 3998 7840 540 7840 3999 7840 3998 7841 3999 7841 12042 7841 12042 7842 3999 7842 4000 7842 12042 7843 4000 7843 12039 7843 12039 7844 4000 7844 4120 7844 4119 7845 4001 7845 12049 7845 12049 7846 4001 7846 542 7846 12049 7847 542 7847 4002 7847 4002 7848 542 7848 4003 7848 4002 7849 4003 7849 4005 7849 4005 7850 4003 7850 4004 7850 4005 7851 4004 7851 12048 7851 12048 7852 4004 7852 544 7852 12048 7853 544 7853 12047 7853 12047 7854 544 7854 4006 7854 12047 7855 4006 7855 12044 7855 12044 7856 4006 7856 545 7856 12051 7857 12052 7857 10809 7857 4109 7858 12055 7858 555 7858 555 7859 12055 7859 12057 7859 555 7860 12057 7860 554 7860 554 7861 12057 7861 4007 7861 4008 7862 552 7862 4007 7862 4007 7863 552 7863 553 7863 4007 7864 553 7864 554 7864 12050 7865 4009 7865 4008 7865 4008 7866 4009 7866 551 7866 4008 7867 551 7867 552 7867 4012 7868 548 7868 12050 7868 12050 7869 548 7869 4010 7869 12050 7870 4010 7870 4009 7870 10809 7871 4011 7871 12051 7871 12051 7872 4011 7872 4013 7872 12051 7873 4013 7873 4012 7873 4012 7874 4013 7874 547 7874 4012 7875 547 7875 548 7875 12060 7876 4014 7876 12058 7876 12058 7877 4014 7877 4015 7877 12058 7878 4015 7878 4016 7878 4016 7879 4015 7879 557 7879 4016 7880 557 7880 4017 7880 4017 7881 557 7881 558 7881 4017 7882 558 7882 4018 7882 4018 7883 558 7883 4019 7883 4018 7884 4019 7884 12061 7884 12061 7885 4019 7885 562 7885 12061 7886 562 7886 4020 7886 4020 7887 562 7887 563 7887 4020 7888 563 7888 4021 7888 4021 7889 563 7889 4097 7889 12063 7890 4089 7890 4022 7890 10787 7891 12067 7891 575 7891 575 7892 12067 7892 12066 7892 575 7893 12066 7893 573 7893 573 7894 12066 7894 4023 7894 4026 7895 572 7895 4023 7895 4023 7896 572 7896 4024 7896 4023 7897 4024 7897 573 7897 12068 7898 4025 7898 4026 7898 4026 7899 4025 7899 4027 7899 4026 7900 4027 7900 572 7900 4022 7901 4028 7901 12063 7901 12063 7902 4028 7902 568 7902 12063 7903 568 7903 12068 7903 12068 7904 568 7904 569 7904 12068 7905 569 7905 4025 7905 12071 7906 4079 7906 4077 7906 10776 7907 4029 7907 577 7907 577 7908 4029 7908 4030 7908 577 7909 4030 7909 4033 7909 4033 7910 4030 7910 12073 7910 4034 7911 4031 7911 12073 7911 12073 7912 4031 7912 4032 7912 12073 7913 4032 7913 4033 7913 4036 7914 580 7914 4034 7914 4034 7915 580 7915 4035 7915 4034 7916 4035 7916 4031 7916 12072 7917 585 7917 4036 7917 4036 7918 585 7918 581 7918 4036 7919 581 7919 580 7919 4077 7920 4037 7920 12071 7920 12071 7921 4037 7921 4038 7921 12071 7922 4038 7922 12072 7922 12072 7923 4038 7923 4039 7923 12072 7924 4039 7924 585 7924 4040 7925 12075 7925 600 7925 600 7926 12075 7926 12080 7926 600 7927 12080 7927 4041 7927 4041 7928 12080 7928 598 7928 598 7929 12080 7929 4043 7929 598 7930 4043 7930 597 7930 597 7931 4043 7931 4042 7931 4042 7932 4043 7932 4045 7932 4042 7933 4045 7933 4044 7933 4044 7934 4045 7934 594 7934 594 7935 4045 7935 4046 7935 594 7936 4046 7936 592 7936 592 7937 4046 7937 4047 7937 4047 7938 4046 7938 4048 7938 4047 7939 4048 7939 590 7939 590 7940 4048 7940 4049 7940 4049 7941 4048 7941 12074 7941 4049 7942 12074 7942 10774 7942 609 7943 12084 7943 4050 7943 4050 7944 12084 7944 4051 7944 4050 7945 4051 7945 4052 7945 4052 7946 4051 7946 606 7946 606 7947 4051 7947 4053 7947 606 7948 4053 7948 604 7948 604 7949 4053 7949 4054 7949 4054 7950 4053 7950 4055 7950 4054 7951 4055 7951 602 7951 602 7952 4055 7952 601 7952 601 7953 4055 7953 12081 7953 601 7954 12081 7954 4056 7954 4056 7955 12081 7955 4057 7955 4057 7956 12081 7956 4058 7956 4057 7957 4058 7957 4059 7957 4059 7958 4058 7958 4060 7958 4060 7959 4058 7959 4061 7959 4060 7960 4061 7960 4062 7960 12083 7961 12084 7961 609 7961 4062 7962 4061 7962 4063 7962 4063 7963 4061 7963 12085 7963 4063 7964 12085 7964 4064 7964 4064 7965 12085 7965 4066 7965 4065 7966 10770 7966 4066 7966 4066 7967 10770 7967 10771 7967 4066 7968 10771 7968 4064 7968 12082 7969 4069 7969 4065 7969 4065 7970 4069 7970 4067 7970 4065 7971 4067 7971 10770 7971 4070 7972 4071 7972 12082 7972 12082 7973 4071 7973 4068 7973 12082 7974 4068 7974 4069 7974 609 7975 10766 7975 12083 7975 12083 7976 10766 7976 10767 7976 12083 7977 10767 7977 4070 7977 4070 7978 10767 7978 10769 7978 4070 7979 10769 7979 4071 7979 12075 7980 4040 7980 12076 7980 12076 7981 4040 7981 4072 7981 12076 7982 4072 7982 4073 7982 4073 7983 4072 7983 4074 7983 4073 7984 4074 7984 12079 7984 12079 7985 4074 7985 10773 7985 12079 7986 10773 7986 12077 7986 12077 7987 10773 7987 4075 7987 12077 7988 4075 7988 12078 7988 12078 7989 4075 7989 4076 7989 12078 7990 4076 7990 12074 7990 12074 7991 4076 7991 10774 7991 4077 7992 4079 7992 4078 7992 4078 7993 4079 7993 12070 7993 4078 7994 12070 7994 10785 7994 10785 7995 12070 7995 10783 7995 10783 7996 12070 7996 12069 7996 10783 7997 12069 7997 4080 7997 4080 7998 12069 7998 4081 7998 4081 7999 12069 7999 4082 7999 4081 8000 4082 8000 4083 8000 4083 8001 4082 8001 4085 8001 4085 8002 4082 8002 4084 8002 4085 8003 4084 8003 4086 8003 4086 8004 4084 8004 10781 8004 10781 8005 4084 8005 4087 8005 10781 8006 4087 8006 10779 8006 10779 8007 4087 8007 10778 8007 10778 8008 4087 8008 4029 8008 10778 8009 4029 8009 10776 8009 4088 8010 12067 8010 10787 8010 4022 8011 4089 8011 10797 8011 10797 8012 4089 8012 4090 8012 10797 8013 4090 8013 10796 8013 10796 8014 4090 8014 12064 8014 4092 8015 4093 8015 12064 8015 12064 8016 4093 8016 10795 8016 12064 8017 10795 8017 10796 8017 12065 8018 4091 8018 4092 8018 4092 8019 4091 8019 10793 8019 4092 8020 10793 8020 4093 8020 4094 8021 4095 8021 12065 8021 12065 8022 4095 8022 10792 8022 12065 8023 10792 8023 4091 8023 10787 8024 10788 8024 4088 8024 4088 8025 10788 8025 4096 8025 4088 8026 4096 8026 4094 8026 4094 8027 4096 8027 10790 8027 4094 8028 10790 8028 4095 8028 4021 8029 4097 8029 12062 8029 12062 8030 4097 8030 10798 8030 12062 8031 10798 8031 4098 8031 4098 8032 10798 8032 4099 8032 4098 8033 4099 8033 12059 8033 12059 8034 4099 8034 4101 8034 12059 8035 4101 8035 4100 8035 4100 8036 4101 8036 4102 8036 4100 8037 4102 8037 4103 8037 4103 8038 4102 8038 4104 8038 4103 8039 4104 8039 12060 8039 12060 8040 4104 8040 4014 8040 4110 8041 12055 8041 4109 8041 10809 8042 12052 8042 10808 8042 10808 8043 12052 8043 12056 8043 10808 8044 12056 8044 4105 8044 4105 8045 12056 8045 12054 8045 4106 8046 4108 8046 12054 8046 12054 8047 4108 8047 10806 8047 12054 8048 10806 8048 4105 8048 12053 8049 4107 8049 4106 8049 4106 8050 4107 8050 10805 8050 4106 8051 10805 8051 4108 8051 4109 8052 4111 8052 4110 8052 4110 8053 4111 8053 4112 8053 4110 8054 4112 8054 12053 8054 12053 8055 4112 8055 4113 8055 12053 8056 4113 8056 4107 8056 12044 8057 545 8057 4114 8057 4114 8058 545 8058 10811 8058 4114 8059 10811 8059 4115 8059 4115 8060 10811 8060 4116 8060 4115 8061 4116 8061 4117 8061 4117 8062 4116 8062 10814 8062 4117 8063 10814 8063 4118 8063 4118 8064 10814 8064 10816 8064 4118 8065 10816 8065 12046 8065 12046 8066 10816 8066 10818 8066 12046 8067 10818 8067 12045 8067 12045 8068 10818 8068 10819 8068 12045 8069 10819 8069 4119 8069 4119 8070 10819 8070 4001 8070 12039 8071 4120 8071 4121 8071 4121 8072 4120 8072 10822 8072 4121 8073 10822 8073 4122 8073 4122 8074 10822 8074 4123 8074 4122 8075 4123 8075 12041 8075 12041 8076 4123 8076 10823 8076 12041 8077 10823 8077 4124 8077 4124 8078 10823 8078 4125 8078 4124 8079 4125 8079 12040 8079 12040 8080 4125 8080 4126 8080 12040 8081 4126 8081 4127 8081 4127 8082 4126 8082 4128 8082 4127 8083 4128 8083 3994 8083 3994 8084 4128 8084 10827 8084 12029 8085 4129 8085 4130 8085 4130 8086 4129 8086 4131 8086 4130 8087 4131 8087 12038 8087 12038 8088 4131 8088 10831 8088 12038 8089 10831 8089 12031 8089 12031 8090 10831 8090 4132 8090 12031 8091 4132 8091 12032 8091 12032 8092 4132 8092 10832 8092 12032 8093 10832 8093 12037 8093 12037 8094 10832 8094 10834 8094 12037 8095 10834 8095 12036 8095 12036 8096 10834 8096 4133 8096 12036 8097 4133 8097 4134 8097 4134 8098 4133 8098 4135 8098 4144 8099 12028 8099 530 8099 4136 8100 4137 8100 4138 8100 4138 8101 4137 8101 12026 8101 4138 8102 12026 8102 4142 8102 4142 8103 12026 8103 4139 8103 12021 8104 4140 8104 4139 8104 4139 8105 4140 8105 4141 8105 4139 8106 4141 8106 4142 8106 12025 8107 4143 8107 12021 8107 12021 8108 4143 8108 10841 8108 12021 8109 10841 8109 4140 8109 530 8110 10837 8110 4144 8110 4144 8111 10837 8111 10839 8111 4144 8112 10839 8112 12025 8112 12025 8113 10839 8113 4145 8113 12025 8114 4145 8114 4143 8114 4153 8115 3979 8115 10845 8115 515 8116 4146 8116 10855 8116 10855 8117 4146 8117 4147 8117 10855 8118 4147 8118 10854 8118 10854 8119 4147 8119 4148 8119 4149 8120 10851 8120 4148 8120 4148 8121 10851 8121 10852 8121 4148 8122 10852 8122 10854 8122 4151 8123 10848 8123 4149 8123 4149 8124 10848 8124 10849 8124 4149 8125 10849 8125 10851 8125 4150 8126 4156 8126 4151 8126 4151 8127 4156 8127 4152 8127 4151 8128 4152 8128 10848 8128 10845 8129 10847 8129 4153 8129 4153 8130 10847 8130 4154 8130 4153 8131 4154 8131 4150 8131 4150 8132 4154 8132 4155 8132 4150 8133 4155 8133 4156 8133 12018 8134 3977 8134 514 8134 10865 8135 12019 8135 4157 8135 4157 8136 12019 8136 4158 8136 4157 8137 4158 8137 4159 8137 4159 8138 4158 8138 4160 8138 4161 8139 4163 8139 4160 8139 4160 8140 4163 8140 10862 8140 4160 8141 10862 8141 4159 8141 12013 8142 10860 8142 4161 8142 4161 8143 10860 8143 4162 8143 4161 8144 4162 8144 4163 8144 12014 8145 4164 8145 12013 8145 12013 8146 4164 8146 4165 8146 12013 8147 4165 8147 10860 8147 514 8148 10857 8148 12018 8148 12018 8149 10857 8149 4166 8149 12018 8150 4166 8150 12014 8150 12014 8151 4166 8151 4167 8151 12014 8152 4167 8152 4164 8152 4195 8153 3032 8153 4168 8153 4168 8154 3032 8154 3033 8154 4168 8155 3033 8155 1199 8155 1199 8156 3033 8156 3034 8156 1199 8157 3034 8157 1198 8157 1198 8158 3034 8158 3036 8158 1198 8159 3036 8159 1196 8159 1196 8160 3036 8160 3037 8160 1196 8161 3037 8161 1195 8161 1195 8162 3037 8162 4169 8162 1195 8163 4169 8163 4170 8163 4170 8164 4169 8164 4171 8164 4170 8165 4171 8165 4172 8165 4172 8166 4171 8166 4173 8166 4172 8167 4173 8167 4174 8167 4174 8168 4173 8168 3039 8168 4174 8169 3039 8169 1192 8169 1192 8170 3039 8170 4175 8170 1192 8171 4175 8171 9346 8171 9346 8172 4175 8172 3040 8172 9346 8173 3040 8173 4176 8173 4176 8174 3040 8174 4177 8174 4176 8175 4177 8175 9343 8175 9343 8176 4177 8176 6003 8176 9343 8177 6003 8177 9341 8177 9341 8178 6003 8178 4178 8178 9341 8179 4178 8179 9340 8179 9340 8180 4178 8180 6004 8180 9340 8181 6004 8181 4179 8181 4179 8182 6004 8182 6006 8182 4179 8183 6006 8183 4180 8183 4180 8184 6006 8184 6007 8184 4180 8185 6007 8185 4182 8185 4182 8186 6007 8186 4181 8186 4182 8187 4181 8187 9338 8187 9338 8188 4181 8188 4183 8188 9338 8189 4183 8189 4184 8189 4184 8190 4183 8190 6009 8190 4184 8191 6009 8191 4185 8191 4185 8192 6009 8192 6011 8192 4185 8193 6011 8193 9335 8193 9335 8194 6011 8194 4187 8194 9335 8195 4187 8195 4186 8195 4186 8196 4187 8196 4188 8196 4186 8197 4188 8197 4189 8197 4189 8198 4188 8198 6013 8198 4189 8199 6013 8199 9334 8199 9334 8200 6013 8200 6015 8200 9334 8201 6015 8201 9332 8201 9332 8202 6015 8202 6016 8202 9332 8203 6016 8203 4190 8203 4190 8204 6016 8204 3026 8204 4190 8205 3026 8205 4191 8205 4191 8206 3026 8206 3027 8206 4191 8207 3027 8207 4192 8207 4192 8208 3027 8208 3028 8208 4192 8209 3028 8209 4193 8209 4193 8210 3028 8210 3029 8210 4193 8211 3029 8211 4194 8211 4194 8212 3029 8212 3031 8212 4194 8213 3031 8213 1203 8213 1203 8214 3031 8214 4196 8214 1203 8215 4196 8215 4195 8215 4195 8216 4196 8216 3032 8216 4211 8217 4213 8217 4197 8217 4197 8218 4213 8218 4198 8218 4197 8219 4198 8219 4199 8219 4199 8220 4198 8220 4201 8220 4199 8221 4201 8221 4200 8221 4200 8222 4201 8222 4202 8222 4200 8223 4202 8223 3785 8223 3785 8224 4202 8224 4203 8224 3785 8225 4203 8225 3787 8225 3787 8226 4203 8226 4204 8226 3787 8227 4204 8227 5176 8227 5176 8228 4204 8228 4205 8228 5176 8229 4205 8229 4206 8229 4206 8230 4205 8230 7110 8230 4206 8231 7110 8231 4207 8231 4207 8232 7110 8232 7109 8232 4207 8233 7109 8233 5179 8233 5179 8234 7109 8234 4208 8234 5179 8235 4208 8235 5181 8235 5181 8236 4208 8236 7108 8236 5181 8237 7108 8237 4209 8237 4209 8238 7108 8238 7107 8238 4209 8239 7107 8239 4210 8239 4210 8240 7107 8240 4212 8240 4210 8241 4212 8241 4211 8241 4211 8242 4212 8242 4213 8242 4228 8243 7094 8243 5153 8243 5153 8244 7094 8244 7092 8244 5153 8245 7092 8245 4214 8245 4214 8246 7092 8246 4215 8246 4214 8247 4215 8247 4216 8247 4216 8248 4215 8248 7091 8248 4216 8249 7091 8249 4217 8249 4217 8250 7091 8250 7090 8250 4217 8251 7090 8251 4218 8251 4218 8252 7090 8252 7087 8252 4218 8253 7087 8253 4219 8253 4219 8254 7087 8254 2480 8254 4219 8255 2480 8255 3810 8255 3810 8256 2480 8256 4220 8256 3810 8257 4220 8257 4221 8257 4221 8258 4220 8258 2477 8258 4221 8259 2477 8259 4222 8259 4222 8260 2477 8260 4223 8260 4222 8261 4223 8261 3805 8261 3805 8262 4223 8262 4224 8262 3805 8263 4224 8263 4225 8263 4225 8264 4224 8264 4226 8264 4225 8265 4226 8265 5159 8265 5159 8266 4226 8266 4227 8266 5159 8267 4227 8267 4228 8267 4228 8268 4227 8268 7094 8268 5279 8269 4230 8269 4229 8269 4229 8270 4230 8270 4231 8270 4229 8271 4231 8271 4232 8271 4232 8272 4231 8272 3662 8272 4232 8273 3662 8273 2664 8273 2664 8274 3662 8274 3661 8274 2664 8275 3661 8275 4233 8275 4233 8276 3661 8276 4234 8276 4233 8277 4234 8277 2660 8277 2660 8278 4234 8278 4235 8278 2660 8279 4235 8279 2659 8279 2659 8280 4235 8280 4236 8280 2659 8281 4236 8281 4237 8281 4237 8282 4236 8282 4238 8282 4237 8283 4238 8283 6885 8283 6885 8284 4238 8284 5283 8284 6885 8285 5283 8285 6887 8285 6887 8286 5283 8286 5282 8286 6887 8287 5282 8287 4239 8287 4239 8288 5282 8288 5281 8288 4239 8289 5281 8289 4240 8289 4240 8290 5281 8290 5280 8290 4240 8291 5280 8291 4241 8291 4241 8292 5280 8292 5279 8292 4241 8293 5279 8293 4229 8293 6875 8294 4242 8294 4243 8294 4243 8295 4242 8295 2677 8295 4243 8296 2677 8296 3692 8296 3692 8297 2677 8297 2678 8297 3692 8298 2678 8298 3690 8298 3690 8299 2678 8299 4245 8299 3690 8300 4245 8300 4244 8300 4244 8301 4245 8301 4246 8301 4244 8302 4246 8302 3686 8302 3686 8303 4246 8303 2681 8303 3686 8304 2681 8304 3685 8304 3685 8305 2681 8305 2683 8305 3685 8306 2683 8306 4247 8306 4247 8307 2683 8307 6877 8307 4247 8308 6877 8308 5260 8308 5260 8309 6877 8309 4248 8309 5260 8310 4248 8310 4249 8310 4249 8311 4248 8311 4250 8311 4249 8312 4250 8312 5262 8312 5262 8313 4250 8313 6876 8313 5262 8314 6876 8314 5263 8314 5263 8315 6876 8315 4251 8315 5263 8316 4251 8316 4252 8316 4252 8317 4251 8317 6875 8317 4252 8318 6875 8318 4243 8318 3713 8319 4266 8319 4253 8319 4253 8320 4266 8320 4254 8320 4253 8321 4254 8321 3714 8321 3714 8322 4254 8322 4255 8322 3714 8323 4255 8323 3715 8323 3715 8324 4255 8324 4256 8324 3715 8325 4256 8325 3717 8325 3717 8326 4256 8326 4257 8326 3717 8327 4257 8327 3718 8327 3718 8328 4257 8328 6866 8328 3718 8329 6866 8329 4258 8329 4258 8330 6866 8330 4259 8330 4258 8331 4259 8331 5242 8331 5242 8332 4259 8332 4260 8332 5242 8333 4260 8333 5243 8333 5243 8334 4260 8334 4261 8334 5243 8335 4261 8335 5244 8335 5244 8336 4261 8336 4262 8336 5244 8337 4262 8337 4263 8337 4263 8338 4262 8338 4264 8338 4263 8339 4264 8339 5246 8339 5246 8340 4264 8340 4265 8340 5246 8341 4265 8341 3711 8341 3711 8342 4265 8342 2700 8342 3711 8343 2700 8343 3713 8343 3713 8344 2700 8344 4266 8344 2708 8345 2710 8345 3737 8345 3737 8346 2710 8346 2711 8346 3737 8347 2711 8347 3739 8347 3739 8348 2711 8348 2713 8348 3739 8349 2713 8349 4267 8349 4267 8350 2713 8350 2715 8350 4267 8351 2715 8351 4268 8351 4268 8352 2715 8352 2716 8352 4268 8353 2716 8353 3741 8353 3741 8354 2716 8354 4269 8354 3741 8355 4269 8355 5217 8355 5217 8356 4269 8356 4270 8356 5217 8357 4270 8357 5218 8357 5218 8358 4270 8358 4271 8358 5218 8359 4271 8359 4272 8359 4272 8360 4271 8360 6856 8360 4272 8361 6856 8361 5214 8361 5214 8362 6856 8362 6854 8362 5214 8363 6854 8363 4273 8363 4273 8364 6854 8364 4274 8364 4273 8365 4274 8365 5213 8365 5213 8366 4274 8366 4276 8366 5213 8367 4276 8367 4275 8367 4275 8368 4276 8368 2708 8368 4275 8369 2708 8369 3737 8369 4277 8370 2494 8370 3828 8370 3828 8371 2494 8371 4278 8371 3828 8372 4278 8372 3830 8372 3830 8373 4278 8373 2493 8373 3830 8374 2493 8374 3832 8374 3832 8375 2493 8375 4279 8375 3832 8376 4279 8376 4280 8376 4280 8377 4279 8377 4281 8377 4280 8378 4281 8378 5135 8378 5135 8379 4281 8379 4282 8379 5135 8380 4282 8380 5137 8380 5137 8381 4282 8381 4283 8381 5137 8382 4283 8382 5138 8382 5138 8383 4283 8383 7070 8383 5138 8384 7070 8384 4284 8384 4284 8385 7070 8385 4285 8385 4284 8386 4285 8386 5139 8386 5139 8387 4285 8387 4286 8387 5139 8388 4286 8388 3824 8388 3824 8389 4286 8389 7065 8389 3824 8390 7065 8390 4288 8390 4288 8391 7065 8391 4287 8391 4288 8392 4287 8392 3825 8392 3825 8393 4287 8393 4289 8393 3825 8394 4289 8394 4277 8394 4277 8395 4289 8395 2494 8395 4301 8396 2441 8396 4290 8396 4290 8397 2441 8397 2440 8397 4290 8398 2440 8398 4291 8398 4291 8399 2440 8399 4292 8399 4291 8400 4292 8400 4293 8400 4293 8401 4292 8401 2438 8401 4293 8402 2438 8402 4294 8402 4294 8403 2438 8403 4295 8403 4294 8404 4295 8404 4296 8404 4296 8405 4295 8405 7127 8405 4296 8406 7127 8406 4297 8406 4297 8407 7127 8407 7125 8407 4297 8408 7125 8408 5650 8408 5650 8409 7125 8409 4298 8409 5650 8410 4298 8410 5651 8410 5651 8411 4298 8411 7124 8411 5651 8412 7124 8412 3333 8412 3333 8413 7124 8413 4299 8413 3333 8414 4299 8414 3334 8414 3334 8415 4299 8415 2446 8415 3334 8416 2446 8416 3335 8416 3335 8417 2446 8417 2445 8417 3335 8418 2445 8418 4300 8418 4300 8419 2445 8419 2444 8419 4300 8420 2444 8420 4301 8420 4301 8421 2444 8421 2441 8421 4313 8422 4302 8422 4303 8422 4303 8423 4302 8423 2418 8423 4303 8424 2418 8424 4304 8424 4304 8425 2418 8425 2420 8425 4304 8426 2420 8426 4305 8426 4305 8427 2420 8427 2421 8427 4305 8428 2421 8428 4306 8428 4306 8429 2421 8429 2423 8429 4306 8430 2423 8430 3312 8430 3312 8431 2423 8431 2424 8431 3312 8432 2424 8432 5666 8432 5666 8433 2424 8433 2425 8433 5666 8434 2425 8434 5667 8434 5667 8435 2425 8435 4307 8435 5667 8436 4307 8436 5670 8436 5670 8437 4307 8437 4308 8437 5670 8438 4308 8438 5671 8438 5671 8439 4308 8439 4309 8439 5671 8440 4309 8440 4310 8440 4310 8441 4309 8441 7132 8441 4310 8442 7132 8442 5673 8442 5673 8443 7132 8443 4311 8443 5673 8444 4311 8444 4312 8444 4312 8445 4311 8445 4313 8445 4312 8446 4313 8446 4303 8446 3289 8447 2405 8447 3291 8447 3291 8448 2405 8448 4314 8448 3291 8449 4314 8449 3293 8449 3293 8450 4314 8450 2402 8450 3293 8451 2402 8451 3294 8451 3294 8452 2402 8452 2401 8452 3294 8453 2401 8453 4315 8453 4315 8454 2401 8454 2400 8454 4315 8455 2400 8455 5685 8455 5685 8456 2400 8456 7150 8456 5685 8457 7150 8457 4316 8457 4316 8458 7150 8458 7149 8458 4316 8459 7149 8459 5686 8459 5686 8460 7149 8460 7147 8460 5686 8461 7147 8461 5687 8461 5687 8462 7147 8462 4317 8462 5687 8463 4317 8463 4318 8463 4318 8464 4317 8464 7145 8464 4318 8465 7145 8465 4319 8465 4319 8466 7145 8466 4320 8466 4319 8467 4320 8467 4321 8467 4321 8468 4320 8468 2407 8468 4321 8469 2407 8469 3288 8469 3288 8470 2407 8470 4322 8470 3288 8471 4322 8471 3289 8471 3289 8472 4322 8472 2405 8472 2387 8473 2386 8473 4323 8473 4323 8474 2386 8474 2384 8474 4323 8475 2384 8475 4324 8475 4324 8476 2384 8476 2383 8476 4324 8477 2383 8477 3265 8477 3265 8478 2383 8478 2381 8478 3265 8479 2381 8479 3268 8479 3268 8480 2381 8480 4325 8480 3268 8481 4325 8481 3269 8481 3269 8482 4325 8482 4326 8482 3269 8483 4326 8483 5713 8483 5713 8484 4326 8484 4327 8484 5713 8485 4327 8485 5714 8485 5714 8486 4327 8486 7160 8486 5714 8487 7160 8487 4328 8487 4328 8488 7160 8488 7159 8488 4328 8489 7159 8489 5711 8489 5711 8490 7159 8490 4329 8490 5711 8491 4329 8491 4330 8491 4330 8492 4329 8492 4331 8492 4330 8493 4331 8493 5707 8493 5707 8494 4331 8494 7158 8494 5707 8495 7158 8495 3262 8495 3262 8496 7158 8496 2387 8496 3262 8497 2387 8497 4323 8497 3415 8498 2293 8498 3416 8498 3416 8499 2293 8499 4332 8499 3416 8500 4332 8500 3418 8500 3418 8501 4332 8501 2292 8501 3418 8502 2292 8502 4333 8502 4333 8503 2292 8503 4334 8503 4333 8504 4334 8504 3421 8504 3421 8505 4334 8505 4335 8505 3421 8506 4335 8506 4337 8506 4337 8507 4335 8507 4336 8507 4337 8508 4336 8508 4338 8508 4338 8509 4336 8509 7283 8509 4338 8510 7283 8510 4339 8510 4339 8511 7283 8511 7281 8511 4339 8512 7281 8512 5558 8512 5558 8513 7281 8513 7280 8513 5558 8514 7280 8514 4340 8514 4340 8515 7280 8515 7279 8515 4340 8516 7279 8516 4341 8516 4341 8517 7279 8517 7277 8517 4341 8518 7277 8518 4342 8518 4342 8519 7277 8519 7276 8519 4342 8520 7276 8520 4343 8520 4343 8521 7276 8521 2294 8521 4343 8522 2294 8522 3415 8522 3415 8523 2294 8523 2293 8523 4360 8524 4344 8524 5579 8524 5579 8525 4344 8525 7307 8525 5579 8526 7307 8526 4345 8526 4345 8527 7307 8527 4346 8527 4345 8528 4346 8528 4347 8528 4347 8529 4346 8529 4348 8529 4347 8530 4348 8530 3397 8530 3397 8531 4348 8531 4349 8531 3397 8532 4349 8532 4350 8532 4350 8533 4349 8533 4351 8533 4350 8534 4351 8534 3399 8534 3399 8535 4351 8535 2266 8535 3399 8536 2266 8536 4352 8536 4352 8537 2266 8537 2265 8537 4352 8538 2265 8538 4353 8538 4353 8539 2265 8539 4354 8539 4353 8540 4354 8540 4355 8540 4355 8541 4354 8541 7300 8541 4355 8542 7300 8542 4356 8542 4356 8543 7300 8543 7302 8543 4356 8544 7302 8544 4358 8544 4358 8545 7302 8545 4357 8545 4358 8546 4357 8546 5576 8546 5576 8547 4357 8547 4359 8547 5576 8548 4359 8548 4360 8548 4360 8549 4359 8549 4344 8549 4361 8550 4362 8550 4363 8550 4363 8551 4362 8551 4364 8551 4363 8552 4364 8552 4366 8552 4366 8553 4364 8553 4365 8553 4366 8554 4365 8554 3368 8554 3368 8555 4365 8555 4367 8555 3368 8556 4367 8556 3370 8556 3370 8557 4367 8557 2239 8557 3370 8558 2239 8558 3371 8558 3371 8559 2239 8559 4368 8559 3371 8560 4368 8560 3374 8560 3374 8561 4368 8561 4369 8561 3374 8562 4369 8562 5598 8562 5598 8563 4369 8563 4370 8563 5598 8564 4370 8564 5599 8564 5599 8565 4370 8565 4371 8565 5599 8566 4371 8566 4372 8566 4372 8567 4371 8567 7334 8567 4372 8568 7334 8568 5602 8568 5602 8569 7334 8569 4373 8569 5602 8570 4373 8570 5603 8570 5603 8571 4373 8571 4374 8571 5603 8572 4374 8572 5606 8572 5606 8573 4374 8573 7338 8573 5606 8574 7338 8574 4361 8574 4361 8575 7338 8575 4362 8575 3536 8576 4375 8576 4376 8576 4376 8577 4375 8577 4377 8577 4376 8578 4377 8578 7363 8578 7363 8579 4377 8579 4378 8579 7363 8580 4378 8580 7361 8580 7361 8581 4378 8581 4379 8581 7361 8582 4379 8582 4380 8582 4380 8583 4379 8583 4381 8583 4380 8584 4381 8584 7359 8584 7359 8585 4381 8585 4382 8585 7359 8586 4382 8586 7357 8586 7357 8587 4382 8587 5435 8587 7357 8588 5435 8588 4383 8588 4383 8589 5435 8589 5433 8589 4383 8590 5433 8590 2219 8590 2219 8591 5433 8591 3540 8591 2219 8592 3540 8592 2218 8592 2218 8593 3540 8593 3539 8593 2218 8594 3539 8594 2215 8594 2215 8595 3539 8595 3538 8595 2215 8596 3538 8596 2213 8596 2213 8597 3538 8597 4384 8597 2213 8598 4384 8598 2211 8598 2211 8599 4384 8599 3536 8599 2211 8600 3536 8600 4385 8600 4385 8601 3536 8601 4376 8601 4394 8602 7379 8602 4386 8602 4386 8603 7379 8603 4387 8603 4386 8604 4387 8604 5454 8604 5454 8605 4387 8605 7378 8605 5454 8606 7378 8606 5456 8606 5456 8607 7378 8607 7377 8607 5456 8608 7377 8608 4388 8608 4388 8609 7377 8609 7376 8609 4388 8610 7376 8610 5457 8610 5457 8611 7376 8611 2200 8611 5457 8612 2200 8612 4389 8612 4389 8613 2200 8613 2199 8613 4389 8614 2199 8614 4391 8614 4391 8615 2199 8615 4390 8615 4391 8616 4390 8616 3511 8616 3511 8617 4390 8617 2197 8617 3511 8618 2197 8618 3512 8618 3512 8619 2197 8619 2196 8619 3512 8620 2196 8620 3513 8620 3513 8621 2196 8621 2195 8621 3513 8622 2195 8622 4392 8622 4392 8623 2195 8623 4393 8623 4392 8624 4393 8624 5451 8624 5451 8625 4393 8625 7381 8625 5451 8626 7381 8626 4394 8626 4394 8627 7381 8627 7379 8627 3490 8628 2182 8628 4395 8628 4395 8629 2182 8629 2180 8629 4395 8630 2180 8630 3492 8630 3492 8631 2180 8631 2179 8631 3492 8632 2179 8632 3493 8632 3493 8633 2179 8633 2177 8633 3493 8634 2177 8634 4396 8634 4396 8635 2177 8635 4397 8635 4396 8636 4397 8636 5471 8636 5471 8637 4397 8637 7395 8637 5471 8638 7395 8638 5472 8638 5472 8639 7395 8639 7393 8639 5472 8640 7393 8640 4398 8640 4398 8641 7393 8641 7390 8641 4398 8642 7390 8642 4399 8642 4399 8643 7390 8643 4401 8643 4399 8644 4401 8644 4400 8644 4400 8645 4401 8645 7389 8645 4400 8646 7389 8646 3487 8646 3487 8647 7389 8647 4402 8647 3487 8648 4402 8648 4403 8648 4403 8649 4402 8649 2186 8649 4403 8650 2186 8650 4404 8650 4404 8651 2186 8651 2183 8651 4404 8652 2183 8652 3490 8652 3490 8653 2183 8653 2182 8653 2157 8654 2158 8654 4405 8654 4405 8655 2158 8655 2160 8655 4405 8656 2160 8656 4406 8656 4406 8657 2160 8657 4407 8657 4406 8658 4407 8658 4408 8658 4408 8659 4407 8659 2163 8659 4408 8660 2163 8660 3473 8660 3473 8661 2163 8661 4409 8661 3473 8662 4409 8662 4410 8662 4410 8663 4409 8663 4411 8663 4410 8664 4411 8664 4412 8664 4412 8665 4411 8665 7409 8665 4412 8666 7409 8666 4413 8666 4413 8667 7409 8667 7408 8667 4413 8668 7408 8668 4414 8668 4414 8669 7408 8669 7406 8669 4414 8670 7406 8670 5494 8670 5494 8671 7406 8671 4415 8671 5494 8672 4415 8672 5492 8672 5492 8673 4415 8673 4416 8673 5492 8674 4416 8674 4417 8674 4417 8675 4416 8675 4418 8675 4417 8676 4418 8676 5489 8676 5489 8677 4418 8677 2157 8677 5489 8678 2157 8678 5487 8678 5487 8679 2157 8679 4405 8679 4430 8680 4419 8680 4420 8680 4420 8681 4419 8681 7552 8681 4420 8682 7552 8682 4421 8682 4421 8683 7552 8683 7551 8683 4421 8684 7551 8684 3619 8684 3619 8685 7551 8685 2054 8685 3619 8686 2054 8686 4422 8686 4422 8687 2054 8687 2056 8687 4422 8688 2056 8688 3620 8688 3620 8689 2056 8689 2060 8689 3620 8690 2060 8690 4424 8690 4424 8691 2060 8691 4423 8691 4424 8692 4423 8692 4425 8692 4425 8693 4423 8693 2062 8693 4425 8694 2062 8694 4426 8694 4426 8695 2062 8695 2063 8695 4426 8696 2063 8696 5351 8696 5351 8697 2063 8697 4428 8697 5351 8698 4428 8698 4427 8698 4427 8699 4428 8699 7547 8699 4427 8700 7547 8700 5353 8700 5353 8701 7547 8701 7549 8701 5353 8702 7549 8702 4429 8702 4429 8703 7549 8703 7550 8703 4429 8704 7550 8704 4430 8704 4430 8705 7550 8705 4419 8705 4443 8706 4431 8706 5366 8706 5366 8707 4431 8707 7577 8707 5366 8708 7577 8708 5367 8708 5367 8709 7577 8709 7576 8709 5367 8710 7576 8710 4432 8710 4432 8711 7576 8711 7574 8711 4432 8712 7574 8712 5370 8712 5370 8713 7574 8713 4433 8713 5370 8714 4433 8714 5371 8714 5371 8715 4433 8715 4434 8715 5371 8716 4434 8716 5373 8716 5373 8717 4434 8717 2037 8717 5373 8718 2037 8718 4435 8718 4435 8719 2037 8719 4436 8719 4435 8720 4436 8720 3599 8720 3599 8721 4436 8721 4437 8721 3599 8722 4437 8722 4438 8722 4438 8723 4437 8723 4439 8723 4438 8724 4439 8724 4440 8724 4440 8725 4439 8725 2034 8725 4440 8726 2034 8726 4441 8726 4441 8727 2034 8727 2032 8727 4441 8728 2032 8728 4442 8728 4442 8729 2032 8729 4444 8729 4442 8730 4444 8730 4443 8730 4443 8731 4444 8731 4431 8731 4458 8732 4445 8732 3581 8732 3581 8733 4445 8733 2016 8733 3581 8734 2016 8734 4446 8734 4446 8735 2016 8735 4447 8735 4446 8736 4447 8736 4448 8736 4448 8737 4447 8737 4449 8737 4448 8738 4449 8738 5396 8738 5396 8739 4449 8739 7597 8739 5396 8740 7597 8740 4450 8740 4450 8741 7597 8741 7596 8741 4450 8742 7596 8742 5392 8742 5392 8743 7596 8743 7595 8743 5392 8744 7595 8744 4451 8744 4451 8745 7595 8745 4452 8745 4451 8746 4452 8746 5389 8746 5389 8747 4452 8747 4453 8747 5389 8748 4453 8748 4454 8748 4454 8749 4453 8749 7592 8749 4454 8750 7592 8750 4455 8750 4455 8751 7592 8751 4456 8751 4455 8752 4456 8752 4457 8752 4457 8753 4456 8753 2018 8753 4457 8754 2018 8754 3578 8754 3578 8755 2018 8755 4458 8755 3578 8756 4458 8756 3581 8756 4471 8757 2004 8757 4472 8757 4472 8758 2004 8758 2002 8758 4472 8759 2002 8759 4459 8759 4459 8760 2002 8760 2000 8760 4459 8761 2000 8761 4460 8761 4460 8762 2000 8762 4461 8762 4460 8763 4461 8763 4463 8763 4463 8764 4461 8764 4462 8764 4463 8765 4462 8765 4464 8765 4464 8766 4462 8766 4465 8766 4464 8767 4465 8767 4466 8767 4466 8768 4465 8768 1996 8768 4466 8769 1996 8769 5877 8769 5877 8770 1996 8770 4467 8770 5877 8771 4467 8771 5879 8771 5879 8772 4467 8772 4468 8772 5879 8773 4468 8773 5875 8773 5875 8774 4468 8774 4469 8774 5875 8775 4469 8775 5874 8775 5874 8776 4469 8776 7605 8776 5874 8777 7605 8777 5873 8777 5873 8778 7605 8778 4470 8778 5873 8779 4470 8779 3150 8779 3150 8780 4470 8780 4471 8780 3150 8781 4471 8781 4472 8781 5910 8782 4473 8782 5908 8782 5908 8783 4473 8783 4475 8783 5908 8784 4475 8784 4474 8784 4474 8785 4475 8785 4476 8785 4474 8786 4476 8786 5904 8786 5904 8787 4476 8787 7619 8787 5904 8788 7619 8788 4477 8788 4477 8789 7619 8789 4478 8789 4477 8790 4478 8790 5901 8790 5901 8791 4478 8791 4480 8791 5901 8792 4480 8792 4479 8792 4479 8793 4480 8793 4481 8793 4479 8794 4481 8794 3135 8794 3135 8795 4481 8795 4482 8795 3135 8796 4482 8796 4483 8796 4483 8797 4482 8797 1989 8797 4483 8798 1989 8798 4485 8798 4485 8799 1989 8799 4484 8799 4485 8800 4484 8800 4486 8800 4486 8801 4484 8801 4487 8801 4486 8802 4487 8802 3131 8802 3131 8803 4487 8803 1985 8803 3131 8804 1985 8804 4488 8804 4488 8805 1985 8805 1983 8805 4488 8806 1983 8806 5910 8806 5910 8807 1983 8807 4473 8807 4501 8808 7642 8808 4489 8808 4489 8809 7642 8809 1975 8809 4489 8810 1975 8810 4490 8810 4490 8811 1975 8811 4491 8811 4490 8812 4491 8812 3109 8812 3109 8813 4491 8813 4492 8813 3109 8814 4492 8814 3110 8814 3110 8815 4492 8815 4493 8815 3110 8816 4493 8816 3113 8816 3113 8817 4493 8817 1971 8817 3113 8818 1971 8818 4494 8818 4494 8819 1971 8819 4495 8819 4494 8820 4495 8820 3114 8820 3114 8821 4495 8821 7636 8821 3114 8822 7636 8822 4496 8822 4496 8823 7636 8823 7635 8823 4496 8824 7635 8824 4497 8824 4497 8825 7635 8825 4498 8825 4497 8826 4498 8826 5928 8826 5928 8827 4498 8827 4499 8827 5928 8828 4499 8828 4500 8828 4500 8829 4499 8829 7639 8829 4500 8830 7639 8830 5931 8830 5931 8831 7639 8831 7641 8831 5931 8832 7641 8832 4501 8832 4501 8833 7641 8833 7642 8833 5946 8834 7650 8834 4502 8834 4502 8835 7650 8835 1961 8835 4502 8836 1961 8836 3091 8836 3091 8837 1961 8837 1960 8837 3091 8838 1960 8838 3092 8838 3092 8839 1960 8839 1958 8839 3092 8840 1958 8840 3094 8840 3094 8841 1958 8841 1957 8841 3094 8842 1957 8842 4503 8842 4503 8843 1957 8843 1956 8843 4503 8844 1956 8844 4504 8844 4504 8845 1956 8845 1954 8845 4504 8846 1954 8846 4505 8846 4505 8847 1954 8847 1953 8847 4505 8848 1953 8848 4506 8848 4506 8849 1953 8849 7655 8849 4506 8850 7655 8850 4507 8850 4507 8851 7655 8851 4509 8851 4507 8852 4509 8852 4508 8852 4508 8853 4509 8853 7654 8853 4508 8854 7654 8854 5949 8854 5949 8855 7654 8855 7652 8855 5949 8856 7652 8856 4510 8856 4510 8857 7652 8857 4511 8857 4510 8858 4511 8858 5946 8858 5946 8859 4511 8859 7650 8859 4512 8860 4525 8860 4513 8860 4513 8861 4525 8861 7790 8861 4513 8862 7790 8862 4514 8862 4514 8863 7790 8863 4515 8863 4514 8864 4515 8864 5791 8864 5791 8865 4515 8865 4516 8865 5791 8866 4516 8866 5794 8866 5794 8867 4516 8867 7788 8867 5794 8868 7788 8868 4517 8868 4517 8869 7788 8869 7787 8869 4517 8870 7787 8870 4518 8870 4518 8871 7787 8871 4519 8871 4518 8872 4519 8872 3219 8872 3219 8873 4519 8873 4521 8873 3219 8874 4521 8874 4520 8874 4520 8875 4521 8875 4522 8875 4520 8876 4522 8876 3221 8876 3221 8877 4522 8877 1858 8877 3221 8878 1858 8878 3224 8878 3224 8879 1858 8879 1857 8879 3224 8880 1857 8880 4523 8880 4523 8881 1857 8881 1854 8881 4523 8882 1854 8882 5788 8882 5788 8883 1854 8883 4524 8883 5788 8884 4524 8884 4512 8884 4512 8885 4524 8885 4525 8885 4536 8886 4538 8886 4526 8886 4526 8887 4538 8887 7814 8887 4526 8888 7814 8888 5811 8888 5811 8889 7814 8889 4527 8889 5811 8890 4527 8890 4528 8890 4528 8891 4527 8891 1832 8891 4528 8892 1832 8892 4529 8892 4529 8893 1832 8893 1834 8893 4529 8894 1834 8894 3203 8894 3203 8895 1834 8895 4530 8895 3203 8896 4530 8896 3205 8896 3205 8897 4530 8897 1837 8897 3205 8898 1837 8898 4531 8898 4531 8899 1837 8899 1839 8899 4531 8900 1839 8900 4532 8900 4532 8901 1839 8901 1838 8901 4532 8902 1838 8902 4533 8902 4533 8903 1838 8903 7808 8903 4533 8904 7808 8904 5808 8904 5808 8905 7808 8905 4534 8905 5808 8906 4534 8906 5809 8906 5809 8907 4534 8907 7811 8907 5809 8908 7811 8908 4535 8908 4535 8909 7811 8909 4537 8909 4535 8910 4537 8910 4536 8910 4536 8911 4537 8911 4538 8911 5832 8912 7837 8912 5833 8912 5833 8913 7837 8913 4539 8913 5833 8914 4539 8914 5834 8914 5834 8915 4539 8915 7834 8915 5834 8916 7834 8916 5835 8916 5835 8917 7834 8917 4540 8917 5835 8918 4540 8918 4541 8918 4541 8919 4540 8919 7833 8919 4541 8920 7833 8920 4542 8920 4542 8921 7833 8921 4544 8921 4542 8922 4544 8922 4543 8922 4543 8923 4544 8923 1818 8923 4543 8924 1818 8924 3187 8924 3187 8925 1818 8925 4546 8925 3187 8926 4546 8926 4545 8926 4545 8927 4546 8927 4548 8927 4545 8928 4548 8928 4547 8928 4547 8929 4548 8929 4549 8929 4547 8930 4549 8930 3190 8930 3190 8931 4549 8931 4550 8931 3190 8932 4550 8932 4551 8932 4551 8933 4550 8933 7838 8933 4551 8934 7838 8934 5828 8934 5828 8935 7838 8935 4552 8935 5828 8936 4552 8936 5832 8936 5832 8937 4552 8937 7837 8937 4553 8938 6181 8938 3965 8938 4554 8939 6182 8939 6027 8939 6027 8940 6182 8940 6183 8940 6027 8941 6183 8941 4555 8941 4555 8942 6183 8942 4556 8942 6178 8943 4557 8943 4556 8943 4556 8944 4557 8944 6025 8944 4556 8945 6025 8945 4555 8945 4558 8946 6022 8946 6178 8946 6178 8947 6022 8947 4559 8947 6178 8948 4559 8948 4557 8948 4560 8949 4561 8949 4558 8949 4558 8950 4561 8950 6021 8950 4558 8951 6021 8951 6022 8951 3965 8952 4562 8952 4553 8952 4553 8953 4562 8953 4563 8953 4553 8954 4563 8954 4560 8954 4560 8955 4563 8955 6019 8955 4560 8956 6019 8956 4561 8956 3964 8957 4564 8957 6176 8957 6176 8958 4564 8958 6028 8958 6176 8959 6028 8959 4565 8959 4565 8960 6028 8960 6030 8960 4565 8961 6030 8961 6173 8961 6173 8962 6030 8962 6031 8962 6173 8963 6031 8963 4566 8963 4566 8964 6031 8964 4567 8964 4566 8965 4567 8965 4568 8965 4568 8966 4567 8966 6033 8966 4568 8967 6033 8967 6177 8967 6177 8968 6033 8968 6034 8968 4578 8969 6170 8969 4577 8969 3950 8970 6171 8970 4569 8970 4569 8971 6171 8971 6169 8971 4569 8972 6169 8972 6045 8972 6045 8973 6169 8973 4571 8973 4570 8974 6042 8974 4571 8974 4571 8975 6042 8975 4572 8975 4571 8976 4572 8976 6045 8976 4575 8977 6041 8977 4570 8977 4570 8978 6041 8978 4573 8978 4570 8979 4573 8979 6042 8979 4579 8980 4574 8980 4575 8980 4575 8981 4574 8981 4576 8981 4575 8982 4576 8982 6041 8982 4577 8983 6035 8983 4578 8983 4578 8984 6035 8984 6036 8984 4578 8985 6036 8985 4579 8985 4579 8986 6036 8986 6039 8986 4579 8987 6039 8987 4574 8987 4588 8988 3941 8988 2996 8988 2989 8989 3939 8989 6059 8989 6059 8990 3939 8990 4580 8990 6059 8991 4580 8991 6057 8991 6057 8992 4580 8992 4581 8992 4585 8993 4582 8993 4581 8993 4581 8994 4582 8994 4583 8994 4581 8995 4583 8995 6057 8995 4584 8996 6054 8996 4585 8996 4585 8997 6054 8997 4586 8997 4585 8998 4586 8998 4582 8998 6168 8999 4587 8999 4584 8999 4584 9000 4587 9000 6053 9000 4584 9001 6053 9001 6054 9001 2996 9002 6047 9002 4588 9002 4588 9003 6047 9003 6050 9003 4588 9004 6050 9004 6168 9004 6168 9005 6050 9005 6051 9005 6168 9006 6051 9006 4587 9006 4589 9007 6162 9007 6061 9007 4590 9008 6165 9008 4591 9008 4591 9009 6165 9009 6164 9009 4591 9010 6164 9010 4594 9010 4594 9011 6164 9011 4592 9011 4596 9012 6069 9012 4592 9012 4592 9013 6069 9013 4593 9013 4592 9014 4593 9014 4594 9014 4598 9015 4595 9015 4596 9015 4596 9016 4595 9016 6066 9016 4596 9017 6066 9017 6069 9017 6163 9018 4597 9018 4598 9018 4598 9019 4597 9019 6065 9019 4598 9020 6065 9020 4595 9020 6061 9021 4599 9021 4589 9021 4589 9022 4599 9022 6063 9022 4589 9023 6063 9023 6163 9023 6163 9024 6063 9024 6064 9024 6163 9025 6064 9025 4597 9025 6153 9026 6070 9026 6154 9026 6154 9027 6070 9027 6072 9027 6154 9028 6072 9028 6155 9028 6155 9029 6072 9029 6074 9029 6155 9030 6074 9030 6157 9030 6157 9031 6074 9031 6075 9031 6157 9032 6075 9032 4600 9032 4600 9033 6075 9033 6076 9033 4600 9034 6076 9034 6158 9034 6158 9035 6076 9035 4601 9035 6158 9036 4601 9036 6159 9036 6159 9037 4601 9037 6078 9037 6159 9038 6078 9038 4602 9038 4602 9039 6078 9039 2976 9039 4603 9040 3922 9040 4604 9040 4604 9041 3922 9041 6079 9041 4604 9042 6079 9042 4605 9042 4605 9043 6079 9043 6081 9043 4605 9044 6081 9044 4606 9044 4606 9045 6081 9045 6082 9045 4606 9046 6082 9046 4607 9046 4607 9047 6082 9047 4608 9047 4607 9048 4608 9048 6152 9048 6152 9049 4608 9049 4609 9049 6152 9050 4609 9050 4610 9050 4610 9051 4609 9051 6085 9051 4610 9052 6085 9052 3914 9052 3914 9053 6085 9053 4611 9053 6145 9054 6087 9054 4612 9054 4612 9055 6087 9055 4613 9055 4612 9056 4613 9056 4614 9056 4614 9057 4613 9057 6090 9057 4614 9058 6090 9058 6142 9058 6142 9059 6090 9059 6092 9059 6142 9060 6092 9060 4615 9060 4615 9061 6092 9061 4616 9061 4615 9062 4616 9062 6150 9062 6150 9063 4616 9063 6095 9063 6150 9064 6095 9064 6149 9064 6149 9065 6095 9065 6096 9065 6149 9066 6096 9066 6148 9066 6148 9067 6096 9067 3910 9067 6138 9068 4618 9068 4617 9068 4617 9069 4618 9069 4619 9069 4617 9070 4619 9070 4620 9070 4620 9071 4619 9071 4621 9071 4620 9072 4621 9072 4622 9072 4622 9073 4621 9073 4624 9073 4622 9074 4624 9074 4623 9074 4623 9075 4624 9075 4626 9075 4623 9076 4626 9076 4625 9076 4625 9077 4626 9077 6103 9077 4625 9078 6103 9078 4627 9078 4627 9079 6103 9079 4628 9079 4627 9080 4628 9080 4629 9080 4629 9081 4628 9081 3907 9081 4630 9082 4631 9082 6134 9082 6134 9083 4631 9083 6106 9083 6134 9084 6106 9084 4633 9084 4633 9085 6106 9085 4632 9085 4633 9086 4632 9086 4634 9086 4634 9087 4632 9087 6107 9087 4634 9088 6107 9088 4635 9088 4635 9089 6107 9089 6109 9089 4635 9090 6109 9090 6136 9090 6136 9091 6109 9091 6112 9091 6136 9092 6112 9092 4636 9092 4636 9093 6112 9093 4637 9093 5006 9094 4638 9094 5015 9094 4958 9095 4639 9095 4964 9095 5978 9096 4639 9096 5974 9096 4668 9097 4667 9097 5982 9097 4936 9098 4934 9098 4640 9098 5992 9099 4641 9099 5989 9099 5999 9100 4642 9100 4778 9100 3044 9101 5017 9101 4909 9101 4755 9102 4643 9102 3053 9102 3070 9103 4867 9103 4644 9103 3154 9104 3158 9104 4645 9104 3865 9105 4970 9105 3863 9105 4766 9106 5021 9106 4767 9106 5210 9107 5209 9107 4750 9107 5197 9108 5198 9108 4994 9108 5203 9109 4724 9109 3049 9109 5273 9110 5272 9110 4646 9110 4718 9111 4720 9111 4898 9111 4880 9112 4647 9112 4998 9112 3449 9113 3450 9113 4985 9113 4659 9114 5995 9114 4804 9114 4648 9115 5635 9115 4649 9115 4649 9116 5635 9116 5636 9116 4649 9117 5636 9117 3297 9117 3297 9118 5636 9118 5638 9118 3297 9119 5638 9119 4803 9119 4648 9120 3295 9120 5635 9120 5635 9121 3295 9121 4794 9121 5635 9122 4794 9122 5633 9122 5633 9123 4794 9123 4650 9123 5009 9124 4654 9124 4651 9124 3278 9125 4652 9125 4932 9125 3276 9126 5704 9126 5009 9126 3276 9127 5009 9127 4652 9127 5704 9128 4653 9128 5009 9128 5009 9129 4653 9129 5702 9129 5009 9130 5702 9130 4654 9130 4654 9131 5702 9131 5701 9131 4654 9132 5701 9132 4655 9132 3273 9133 4656 9133 3272 9133 3272 9134 4656 9134 4660 9134 5701 9135 5700 9135 4655 9135 4655 9136 5700 9136 4657 9136 4655 9137 4657 9137 4660 9137 4660 9138 4657 9138 3270 9138 4660 9139 3270 9139 3272 9139 4804 9140 4658 9140 4659 9140 4659 9141 4658 9141 3347 9141 4659 9142 3347 9142 5990 9142 5990 9143 3347 9143 3352 9143 5990 9144 3352 9144 4660 9144 4660 9145 3352 9145 4661 9145 4660 9146 4661 9146 4655 9146 3343 9147 3345 9147 4662 9147 4662 9148 3345 9148 4982 9148 4982 9149 4663 9149 4983 9149 4983 9150 4663 9150 5647 9150 4983 9151 5647 9151 4942 9151 4942 9152 5647 9152 5646 9152 4942 9153 5646 9153 4664 9153 4664 9154 4665 9154 4942 9154 4942 9155 4665 9155 5643 9155 4942 9156 5643 9156 4934 9156 4934 9157 5643 9157 3339 9157 4934 9158 3339 9158 4640 9158 3343 9159 4667 9159 4666 9159 4666 9160 4667 9160 4668 9160 4666 9161 4668 9161 4669 9161 4669 9162 4668 9162 4640 9162 4669 9163 4640 9163 4670 9163 4670 9164 4640 9164 3339 9164 4671 9165 5431 9165 4895 9165 4895 9166 5431 9166 4980 9166 5509 9167 3057 9167 5511 9167 5511 9168 3057 9168 3059 9168 4981 9169 4672 9169 4985 9169 4673 9170 3459 9170 3061 9170 3061 9171 3459 9171 3458 9171 3061 9172 3458 9172 3059 9172 3059 9173 3458 9173 4674 9173 3059 9174 4674 9174 5511 9174 4708 9175 5508 9175 4675 9175 4675 9176 5508 9176 5506 9176 4675 9177 5506 9177 3541 9177 3541 9178 5506 9178 4678 9178 3541 9179 4678 9179 3542 9179 3542 9180 4678 9180 4677 9180 4672 9181 4676 9181 4985 9181 4985 9182 4676 9182 4677 9182 4985 9183 4677 9183 3449 9183 3449 9184 4677 9184 4678 9184 4988 9185 4679 9185 4883 9185 4883 9186 4679 9186 3452 9186 4883 9187 3452 9187 4673 9187 4673 9188 3452 9188 3454 9188 4673 9189 3454 9189 3459 9189 5486 9190 3062 9190 3065 9190 3479 9191 4680 9191 4999 9191 4999 9192 4680 9192 4681 9192 3474 9193 4692 9193 4682 9193 4682 9194 4692 9194 4683 9194 4682 9195 4683 9195 3476 9195 5486 9196 5484 9196 3062 9196 3062 9197 5484 9197 4684 9197 3062 9198 4684 9198 3063 9198 4684 9199 5481 9199 3063 9199 3063 9200 5481 9200 4685 9200 3063 9201 4685 9201 4879 9201 4867 9202 4690 9202 5422 9202 4961 9203 4686 9203 4962 9203 4962 9204 4686 9204 3559 9204 4962 9205 3559 9205 4849 9205 4867 9206 5422 9206 4863 9206 4863 9207 5422 9207 4687 9207 4863 9208 4687 9208 4688 9208 3559 9209 3556 9209 4849 9209 4849 9210 3556 9210 3555 9210 4849 9211 3555 9211 4689 9211 4690 9212 4867 9212 5423 9212 5423 9213 4867 9213 3070 9213 5423 9214 3070 9214 3554 9214 3554 9215 3070 9215 3072 9215 3554 9216 3072 9216 4689 9216 4691 9217 4999 9217 4683 9217 4683 9218 4999 9218 4681 9218 4683 9219 4681 9219 3476 9219 4691 9220 3552 9220 4970 9220 3474 9221 5486 9221 4692 9221 4692 9222 5486 9222 3065 9222 4692 9223 3065 9223 4693 9223 4693 9224 3065 9224 3064 9224 4693 9225 3064 9225 5428 9225 5428 9226 3064 9226 4694 9226 5428 9227 4694 9227 5425 9227 4695 9228 5424 9228 4694 9228 4694 9229 5424 9229 4696 9229 4694 9230 4696 9230 5425 9230 4697 9231 3497 9231 4706 9231 4706 9232 3497 9232 4698 9232 4706 9233 4698 9233 4874 9233 4874 9234 4698 9234 4699 9234 4874 9235 4699 9235 4700 9235 3495 9236 4695 9236 4700 9236 4700 9237 4695 9237 4701 9237 4700 9238 4701 9238 4874 9238 4874 9239 4701 9239 4873 9239 3547 9240 4705 9240 3548 9240 3548 9241 4705 9241 4702 9241 3548 9242 4702 9242 3498 9242 3495 9243 5469 9243 4695 9243 4695 9244 5469 9244 4703 9244 4695 9245 4703 9245 5424 9245 5424 9246 4703 9246 4704 9246 5424 9247 4704 9247 3547 9247 3547 9248 4704 9248 5467 9248 3547 9249 5467 9249 4705 9249 4965 9250 3550 9250 4966 9250 4966 9251 3550 9251 3548 9251 4966 9252 3548 9252 4706 9252 4706 9253 3548 9253 3498 9253 4706 9254 3498 9254 4697 9254 4707 9255 3056 9255 4888 9255 4888 9256 3056 9256 5432 9256 5432 9257 3056 9257 3057 9257 5432 9258 3057 9258 4708 9258 4708 9259 3057 9259 5509 9259 4708 9260 5509 9260 5508 9260 4709 9261 4643 9261 4710 9261 4710 9262 4643 9262 4759 9262 4710 9263 4759 9263 4711 9263 4711 9264 4759 9264 4712 9264 4709 9265 5298 9265 4643 9265 4643 9266 5298 9266 4713 9266 4643 9267 4713 9267 3053 9267 3053 9268 4713 9268 5296 9268 3053 9269 5296 9269 4714 9269 4714 9270 5296 9270 5295 9270 4714 9271 5295 9271 4905 9271 4903 9272 4715 9272 4904 9272 4904 9273 4715 9273 3651 9273 4904 9274 3651 9274 4900 9274 4900 9275 3651 9275 3650 9275 4900 9276 3650 9276 4716 9276 4716 9277 3650 9277 3649 9277 4716 9278 3649 9278 4712 9278 5272 9279 3665 9279 5201 9279 5201 9280 3665 9280 5198 9280 3665 9281 3666 9281 5198 9281 5198 9282 3666 9282 3667 9282 5198 9283 3667 9283 4994 9283 4994 9284 3667 9284 4717 9284 4994 9285 4717 9285 4718 9285 5273 9286 4646 9286 4719 9286 4719 9287 4646 9287 3048 9287 4719 9288 3048 9288 4722 9288 4898 9289 4720 9289 4721 9289 4721 9290 4720 9290 5277 9290 4721 9291 5277 9291 3048 9291 3048 9292 5277 9292 5276 9292 3048 9293 5276 9293 4722 9293 3695 9294 4723 9294 4749 9294 4724 9295 5203 9295 3047 9295 4725 9296 3747 9296 4723 9296 4723 9297 3747 9297 3749 9297 4723 9298 3749 9298 4749 9298 4725 9299 5258 9299 3747 9299 3747 9300 5258 9300 3047 9300 3747 9301 3047 9301 4726 9301 4726 9302 3047 9302 5203 9302 5019 9303 4732 9303 3697 9303 5258 9304 5257 9304 3047 9304 3047 9305 5257 9305 4727 9305 3047 9306 4727 9306 4728 9306 4728 9307 4727 9307 4729 9307 4728 9308 4729 9308 3044 9308 3044 9309 4729 9309 3701 9309 3044 9310 3701 9310 5017 9310 5017 9311 3701 9311 4730 9311 5017 9312 4730 9312 5018 9312 5018 9313 4730 9313 3700 9313 5018 9314 3700 9314 5019 9314 5019 9315 3700 9315 4731 9315 5019 9316 4731 9316 4732 9316 4735 9317 4911 9317 4733 9317 4733 9318 4911 9318 4740 9318 4733 9319 4734 9319 4735 9319 4735 9320 4734 9320 4736 9320 4735 9321 4736 9321 4741 9321 3724 9322 4737 9322 4913 9322 4913 9323 4737 9323 4739 9323 4913 9324 4739 9324 4738 9324 4738 9325 4739 9325 3726 9325 4738 9326 3726 9326 4740 9326 4736 9327 5238 9327 4741 9327 4741 9328 5238 9328 4742 9328 4741 9329 4742 9329 4743 9329 4743 9330 4742 9330 4744 9330 4743 9331 4744 9331 4745 9331 4745 9332 4744 9332 4746 9332 4745 9333 4746 9333 3723 9333 5272 9334 5201 9334 4646 9334 4646 9335 5201 9335 5202 9335 4646 9336 5202 9336 3049 9336 3049 9337 5202 9337 5205 9337 3049 9338 5205 9338 5203 9338 3752 9339 4747 9339 4748 9339 3752 9340 4748 9340 3751 9340 3751 9341 4748 9341 5019 9341 3751 9342 5019 9342 4749 9342 4749 9343 5019 9343 3697 9343 4749 9344 3697 9344 3695 9344 3743 9345 4751 9345 4752 9345 5210 9346 4750 9346 4751 9346 3743 9347 4752 9347 3745 9347 3745 9348 4752 9348 4759 9348 3745 9349 4759 9349 4753 9349 4754 9350 4756 9350 4755 9350 4755 9351 4756 9351 4757 9351 4755 9352 4757 9352 4643 9352 4643 9353 4757 9353 4758 9353 4643 9354 4758 9354 4759 9354 4759 9355 4758 9355 4760 9355 4759 9356 4760 9356 4753 9356 4892 9357 4761 9357 4754 9357 4754 9358 4761 9358 4762 9358 4754 9359 4762 9359 4756 9359 4977 9360 4763 9360 4764 9360 4764 9361 4763 9361 5072 9361 5005 9362 5068 9362 4765 9362 4765 9363 5068 9363 5070 9363 4765 9364 5070 9364 5007 9364 5003 9365 5002 9365 5065 9365 5065 9366 5002 9366 5001 9366 5065 9367 5001 9367 4766 9367 4766 9368 5001 9368 5000 9368 4766 9369 5000 9369 5021 9369 4767 9370 5021 9370 4768 9370 4768 9371 5021 9371 5022 9371 4768 9372 5022 9372 5061 9372 5033 9373 5058 9373 5060 9373 3873 9374 3875 9374 4748 9374 4748 9375 3875 9375 3877 9375 4748 9376 3877 9376 5019 9376 4772 9377 3872 9377 4769 9377 4769 9378 3872 9378 3873 9378 4769 9379 3873 9379 4995 9379 4995 9380 3873 9380 4748 9380 4995 9381 4748 9381 4994 9381 4994 9382 4748 9382 4747 9382 4994 9383 4747 9383 5197 9383 4770 9384 3869 9384 4772 9384 4772 9385 3869 9385 4771 9385 4772 9386 4771 9386 3872 9386 4691 9387 4970 9387 4999 9387 4999 9388 4970 9388 3865 9388 4999 9389 3865 9389 4774 9389 4774 9390 3865 9390 4773 9390 4774 9391 4773 9391 4770 9391 4770 9392 4773 9392 3867 9392 4770 9393 3867 9393 3869 9393 4971 9394 4775 9394 4776 9394 4775 9395 4971 9395 3859 9395 3859 9396 4971 9396 4777 9396 3859 9397 4777 9397 4979 9397 4778 9398 4642 9398 4779 9398 4779 9399 4642 9399 3324 9399 4779 9400 3324 9400 4780 9400 4782 9401 4780 9401 5665 9401 4781 9402 5999 9402 6000 9402 5629 9403 5627 9403 4921 9403 3357 9404 5661 9404 4793 9404 4782 9405 5665 9405 4921 9405 4921 9406 5665 9406 4787 9406 4921 9407 4787 9407 5629 9407 4789 9408 4920 9408 4921 9408 4781 9409 3318 9409 5999 9409 5999 9410 3318 9410 3320 9410 5999 9411 3320 9411 4642 9411 4642 9412 3320 9412 3322 9412 4642 9413 3322 9413 3324 9413 5627 9414 5626 9414 4921 9414 4921 9415 5626 9415 5625 9415 4921 9416 5625 9416 4789 9416 3357 9417 4783 9417 5661 9417 5661 9418 4783 9418 4784 9418 5661 9419 4784 9419 5662 9419 5662 9420 4784 9420 3355 9420 5662 9421 3355 9421 4785 9421 4785 9422 3355 9422 4786 9422 4785 9423 4786 9423 4787 9423 4787 9424 4786 9424 4788 9424 4787 9425 4788 9425 5629 9425 5625 9426 5624 9426 4789 9426 4789 9427 5624 9427 4790 9427 4789 9428 4790 9428 4791 9428 4791 9429 4790 9429 5620 9429 5620 9430 4792 9430 4791 9430 4791 9431 4792 9431 3357 9431 4791 9432 3357 9432 6000 9432 6000 9433 3357 9433 4793 9433 6000 9434 4793 9434 4781 9434 3295 9435 5684 9435 4794 9435 4794 9436 5684 9436 4795 9436 4794 9437 4795 9437 4796 9437 4796 9438 4795 9438 5681 9438 4796 9439 5681 9439 4797 9439 4797 9440 5681 9440 4798 9440 4797 9441 4798 9441 4800 9441 4801 9442 4799 9442 4800 9442 4800 9443 4799 9443 5997 9443 4800 9444 5997 9444 4797 9444 4797 9445 5997 9445 5996 9445 4801 9446 3298 9446 4799 9446 4799 9447 3298 9447 4802 9447 4799 9448 4802 9448 5993 9448 5993 9449 4802 9449 4803 9449 5993 9450 4803 9450 5995 9450 5995 9451 4803 9451 5638 9451 5995 9452 5638 9452 4804 9452 5968 9453 5967 9453 4950 9453 4805 9454 5869 9454 4807 9454 4820 9455 4806 9455 5986 9455 5986 9456 4806 9456 4948 9456 5986 9457 4948 9457 4949 9457 5965 9458 4807 9458 4808 9458 4808 9459 4807 9459 4950 9459 4808 9460 4950 9460 4809 9460 4809 9461 4950 9461 5967 9461 3161 9462 4810 9462 4811 9462 4811 9463 4810 9463 4812 9463 4811 9464 4812 9464 4820 9464 4820 9465 4812 9465 4813 9465 4820 9466 4813 9466 4806 9466 4805 9467 4807 9467 5870 9467 5870 9468 4807 9468 5965 9468 5870 9469 5965 9469 5872 9469 5872 9470 5965 9470 5964 9470 5872 9471 5964 9471 4814 9471 4814 9472 5964 9472 5962 9472 4814 9473 5962 9473 3161 9473 3161 9474 5962 9474 3073 9474 3161 9475 3073 9475 4810 9475 3158 9476 4815 9476 4816 9476 4816 9477 4815 9477 4818 9477 4816 9478 4818 9478 5985 9478 4815 9479 4817 9479 4818 9479 4818 9480 4817 9480 4819 9480 4818 9481 4819 9481 4820 9481 4820 9482 4819 9482 4821 9482 4820 9483 4821 9483 4811 9483 4964 9484 4827 9484 5864 9484 3118 9485 4822 9485 4833 9485 4833 9486 4822 9486 3117 9486 4833 9487 3117 9487 4823 9487 3117 9488 3115 9488 4823 9488 4823 9489 3115 9489 5924 9489 4823 9490 5924 9490 5978 9490 5978 9491 5924 9491 5923 9491 5978 9492 5923 9492 4639 9492 4639 9493 5923 9493 5921 9493 4639 9494 5921 9494 4964 9494 4964 9495 5921 9495 4824 9495 4964 9496 4824 9496 4825 9496 4825 9497 4826 9497 4964 9497 4964 9498 4826 9498 4828 9498 4964 9499 4828 9499 4827 9499 4827 9500 4828 9500 4829 9500 4827 9501 4829 9501 4830 9501 4830 9502 4829 9502 4831 9502 4830 9503 4831 9503 5866 9503 5866 9504 4831 9504 3118 9504 5866 9505 3118 9505 4832 9505 3118 9506 4833 9506 4832 9506 4832 9507 4833 9507 4834 9507 4832 9508 4834 9508 3164 9508 3164 9509 4834 9509 5976 9509 3164 9510 5976 9510 3166 9510 3166 9511 5976 9511 4835 9511 3166 9512 4835 9512 4836 9512 4839 9513 4836 9513 4838 9513 4838 9514 4836 9514 4835 9514 4838 9515 4835 9515 3099 9515 3099 9516 4835 9516 5980 9516 3099 9517 5980 9517 3100 9517 3100 9518 5980 9518 4945 9518 4837 9519 5941 9519 4638 9519 4638 9520 5941 9520 5940 9520 4638 9521 5940 9521 5016 9521 4838 9522 5945 9522 4839 9522 4839 9523 5945 9523 4840 9523 4839 9524 4840 9524 4841 9524 4841 9525 4840 9525 5943 9525 4841 9526 5943 9526 4842 9526 4842 9527 4837 9527 4841 9527 4841 9528 4837 9528 4638 9528 4841 9529 4638 9529 5861 9529 5861 9530 4638 9530 5006 9530 5861 9531 5006 9531 5008 9531 3142 9532 3140 9532 4953 9532 3142 9533 4953 9533 3143 9533 3174 9534 4845 9534 5897 9534 4954 9535 3139 9535 5970 9535 5970 9536 3139 9536 3138 9536 5970 9537 3138 9537 5972 9537 5972 9538 3138 9538 4843 9538 5972 9539 4843 9539 4847 9539 4847 9540 4843 9540 3171 9540 4847 9541 3171 9541 3170 9541 4843 9542 5900 9542 3171 9542 3171 9543 5900 9543 4844 9543 3171 9544 4844 9544 4845 9544 4845 9545 4844 9545 5898 9545 4845 9546 5898 9546 5897 9546 5853 9547 5852 9547 4962 9547 4962 9548 5852 9548 5851 9548 4962 9549 5851 9549 5895 9549 5895 9550 5851 9550 3174 9550 5895 9551 3174 9551 4846 9551 4846 9552 3174 9552 5897 9552 3170 9553 3169 9553 4847 9553 4847 9554 3169 9554 5859 9554 4847 9555 5859 9555 4850 9555 4689 9556 3072 9556 4849 9556 4849 9557 3072 9557 4848 9557 4849 9558 4848 9558 4850 9558 5859 9559 5858 9559 4850 9559 4850 9560 5858 9560 5856 9560 4850 9561 5856 9561 4849 9561 4849 9562 5856 9562 4851 9562 4849 9563 4851 9563 4962 9563 4962 9564 4851 9564 4852 9564 4962 9565 4852 9565 5853 9565 2980 9566 4853 9566 4816 9566 3158 9567 4816 9567 4645 9567 4645 9568 4816 9568 4853 9568 4645 9569 4853 9569 4854 9569 3343 9570 4662 9570 4667 9570 4667 9571 4662 9571 6062 9571 4667 9572 6062 9572 2988 9572 4854 9573 6068 9573 4645 9573 4645 9574 6068 9574 6067 9574 4645 9575 6067 9575 4662 9575 4662 9576 6067 9576 4855 9576 4662 9577 4855 9577 6062 9577 2988 9578 4856 9578 4667 9578 4667 9579 4856 9579 4857 9579 4667 9580 4857 9580 5982 9580 5982 9581 4857 9581 2985 9581 5982 9582 2985 9582 5985 9582 5985 9583 2985 9583 2982 9583 5985 9584 2982 9584 4816 9584 4816 9585 2982 9585 2981 9585 4816 9586 2981 9586 2980 9586 4858 9587 3069 9587 3068 9587 4858 9588 4859 9588 3069 9588 3069 9589 4859 9589 4860 9589 3069 9590 4860 9590 4974 9590 4860 9591 5449 9591 4974 9591 4974 9592 5449 9592 4861 9592 4974 9593 4861 9593 4862 9593 4863 9594 3515 9594 4864 9594 4864 9595 4865 9595 4863 9595 4863 9596 4865 9596 4866 9596 4863 9597 4866 9597 4867 9597 4867 9598 4866 9598 4868 9598 4867 9599 4868 9599 4644 9599 4644 9600 4868 9600 3521 9600 4644 9601 3521 9601 3068 9601 3068 9602 3521 9602 3522 9602 3068 9603 3522 9603 4858 9603 4969 9604 2975 9604 4973 9604 4974 9605 2972 9605 4869 9605 4973 9606 2975 9606 4974 9606 4974 9607 2975 9607 2973 9607 4974 9608 2973 9608 2972 9608 4869 9609 4870 9609 4974 9609 4974 9610 4870 9610 4872 9610 4974 9611 4872 9611 3069 9611 4871 9612 6080 9612 4874 9612 4874 9613 6080 9613 4968 9613 4870 9614 6086 9614 4872 9614 4872 9615 6086 9615 6084 9615 4872 9616 6084 9616 4873 9616 4873 9617 6084 9617 6083 9617 4873 9618 6083 9618 4874 9618 4874 9619 6083 9619 4875 9619 4874 9620 4875 9620 4871 9620 2979 9621 4876 9621 4989 9621 4989 9622 4876 9622 4998 9622 4998 9623 4876 9623 2978 9623 4998 9624 2978 9624 4877 9624 4877 9625 4878 9625 4998 9625 4998 9626 4878 9626 4879 9626 4998 9627 4879 9627 4880 9627 4880 9628 4879 9628 4685 9628 4878 9629 4881 9629 4879 9629 4879 9630 4881 9630 4882 9630 4879 9631 4882 9631 4884 9631 6071 9632 4883 9632 6073 9632 6073 9633 4883 9633 4887 9633 4882 9634 4885 9634 4884 9634 4884 9635 4885 9635 6077 9635 4884 9636 6077 9636 4886 9636 3061 9637 3060 9637 4673 9637 4673 9638 3060 9638 4884 9638 4673 9639 4884 9639 4883 9639 4883 9640 4884 9640 4886 9640 4883 9641 4886 9641 4887 9641 2950 9642 2949 9642 4895 9642 2950 9643 4895 9643 2951 9643 4888 9644 4671 9644 4707 9644 4707 9645 4671 9645 4895 9645 4707 9646 4895 9646 4889 9646 4889 9647 4895 9647 2949 9647 4889 9648 2949 9648 6111 9648 6111 9649 6110 9649 4889 9649 4889 9650 6110 9650 4891 9650 4889 9651 4891 9651 4890 9651 4890 9652 4891 9652 6108 9652 4890 9653 4750 9653 4892 9653 4892 9654 4750 9654 5209 9654 4892 9655 5209 9655 4761 9655 6108 9656 4893 9656 4890 9656 4890 9657 4893 9657 6105 9657 4890 9658 6105 9658 4750 9658 4750 9659 6105 9659 4894 9659 4894 9660 2956 9660 4750 9660 4750 9661 2956 9661 2954 9661 4750 9662 2954 9662 4895 9662 4895 9663 2954 9663 2952 9663 4895 9664 2952 9664 2951 9664 4986 9665 4896 9665 2958 9665 4896 9666 4986 9666 4897 9666 4897 9667 4986 9667 4898 9667 4897 9668 4898 9668 2961 9668 2958 9669 4899 9669 4900 9669 6101 9670 6100 9670 4906 9670 4906 9671 6100 9671 4721 9671 4899 9672 6104 9672 4900 9672 4900 9673 6104 9673 4901 9673 4900 9674 4901 9674 6102 9674 6100 9675 6099 9675 4721 9675 4721 9676 6099 9676 2963 9676 4721 9677 2963 9677 4898 9677 4898 9678 2963 9678 4902 9678 4898 9679 4902 9679 2961 9679 5295 9680 4903 9680 4905 9680 4905 9681 4903 9681 4904 9681 4905 9682 4904 9682 3050 9682 3050 9683 4904 9683 4900 9683 3050 9684 4900 9684 4906 9684 4906 9685 4900 9685 6102 9685 4906 9686 6102 9686 6101 9686 5024 9687 2965 9687 6098 9687 6089 9688 6088 9688 4910 9688 4907 9689 2970 9689 4911 9689 4911 9690 2970 9690 2967 9690 4911 9691 2967 9691 5024 9691 5024 9692 2967 9692 2966 9692 5024 9693 2966 9693 2965 9693 6098 9694 6097 9694 5017 9694 6097 9695 4908 9695 5017 9695 5017 9696 4908 9696 6094 9696 5017 9697 6094 9697 4909 9697 4909 9698 6094 9698 6093 9698 4909 9699 6093 9699 4910 9699 4910 9700 6093 9700 6091 9700 4910 9701 6091 9701 6089 9701 4741 9702 3046 9702 4735 9702 4735 9703 3046 9703 4910 9703 4735 9704 4910 9704 4911 9704 4911 9705 4910 9705 6088 9705 4911 9706 6088 9706 4907 9706 4914 9707 5193 9707 4745 9707 5196 9708 4912 9708 4913 9708 4913 9709 4912 9709 4915 9709 3756 9710 3755 9710 4921 9710 4921 9711 3755 9711 5196 9711 3723 9712 3724 9712 4745 9712 4745 9713 3724 9713 4913 9713 4745 9714 4913 9714 4914 9714 4914 9715 4913 9715 4915 9715 5193 9716 4916 9716 4745 9716 4745 9717 4916 9717 4917 9717 4745 9718 4917 9718 4919 9718 4917 9719 4918 9719 4919 9719 4919 9720 4918 9720 3761 9720 4919 9721 3761 9721 4920 9721 4920 9722 3761 9722 3760 9722 4920 9723 3760 9723 4921 9723 4921 9724 3760 9724 3758 9724 4921 9725 3758 9725 3756 9725 4924 9726 4922 9726 4779 9726 4779 9727 4922 9727 6029 9727 4923 9728 3011 9728 4797 9728 4797 9729 3011 9729 3009 9729 4924 9730 4779 9730 6032 9730 6032 9731 4779 9731 5023 9731 6032 9732 5023 9732 4925 9732 6029 9733 4927 9733 4779 9733 4779 9734 4927 9734 4926 9734 4779 9735 4926 9735 4778 9735 4927 9736 4928 9736 4926 9736 4926 9737 4928 9737 4929 9737 4926 9738 4929 9738 5996 9738 5996 9739 4929 9739 4930 9739 5996 9740 4930 9740 4797 9740 4797 9741 4930 9741 3013 9741 4797 9742 3013 9742 4923 9742 4931 9743 6026 9743 4990 9743 3014 9744 4931 9744 4641 9744 6026 9745 6024 9745 4990 9745 4990 9746 6024 9746 6023 9746 4990 9747 6023 9747 4932 9747 4932 9748 6023 9748 6020 9748 4932 9749 6020 9749 6018 9749 3273 9750 3278 9750 4656 9750 4656 9751 3278 9751 4932 9751 4656 9752 4932 9752 5991 9752 5991 9753 4932 9753 6018 9753 3019 9754 5992 9754 3022 9754 3022 9755 5992 9755 5991 9755 3022 9756 5991 9756 6017 9756 6017 9757 5991 9757 6018 9757 3019 9758 3018 9758 5992 9758 5992 9759 3018 9759 3016 9759 5992 9760 3016 9760 4641 9760 4641 9761 3016 9761 4933 9761 4641 9762 4933 9762 3014 9762 4938 9763 4934 9763 4935 9763 4935 9764 4934 9764 4936 9764 4935 9765 4936 9765 3254 9765 3254 9766 4936 9766 4937 9766 4938 9767 4939 9767 4934 9767 4934 9768 4939 9768 3252 9768 4934 9769 3252 9769 4942 9769 4942 9770 3252 9770 5730 9770 4942 9771 5730 9771 5729 9771 4641 9772 4940 9772 5989 9772 5989 9773 4940 9773 4941 9773 5989 9774 4941 9774 4937 9774 4937 9775 4941 9775 3255 9775 4937 9776 3255 9776 3254 9776 5729 9777 5727 9777 4942 9777 4942 9778 5727 9778 4943 9778 4942 9779 4943 9779 4641 9779 4641 9780 4943 9780 5725 9780 4641 9781 5725 9781 4940 9781 6060 9782 6058 9782 4944 9782 2990 9783 6060 9783 5981 9783 5981 9784 6060 9784 4944 9784 5981 9785 4944 9785 5980 9785 5980 9786 4944 9786 3103 9786 5980 9787 3103 9787 4945 9787 6058 9788 6056 9788 4944 9788 4944 9789 6056 9789 6055 9789 4944 9790 6055 9790 4993 9790 4993 9791 6055 9791 6052 9791 4993 9792 6052 9792 6049 9792 2990 9793 5981 9793 4946 9793 4946 9794 5981 9794 4947 9794 4946 9795 4947 9795 2993 9795 4948 9796 5968 9796 4949 9796 4949 9797 5968 9797 4950 9797 4949 9798 4950 9798 4947 9798 4947 9799 4950 9799 4952 9799 4947 9800 4952 9800 2993 9800 6048 9801 4951 9801 4950 9801 4950 9802 4951 9802 2995 9802 4950 9803 2995 9803 4952 9803 6046 9804 6044 9804 4953 9804 4953 9805 6044 9805 6043 9805 4953 9806 6043 9806 6040 9806 5895 9807 3143 9807 4962 9807 4962 9808 3143 9808 4953 9808 4962 9809 4953 9809 4958 9809 4958 9810 4953 9810 6040 9810 4958 9811 6040 9811 6038 9811 3005 9812 4955 9812 4639 9812 2998 9813 6046 9813 4956 9813 4956 9814 6046 9814 4953 9814 4956 9815 4953 9815 5970 9815 5970 9816 4953 9816 3140 9816 5970 9817 3140 9817 4954 9817 4639 9818 4955 9818 5974 9818 5974 9819 4955 9819 4957 9819 5974 9820 4957 9820 4956 9820 4956 9821 4957 9821 3000 9821 4956 9822 3000 9822 2998 9822 6038 9823 6037 9823 4958 9823 4958 9824 6037 9824 4959 9824 4958 9825 4959 9825 4639 9825 4639 9826 4959 9826 3007 9826 4639 9827 3007 9827 3005 9827 4963 9828 4960 9828 4863 9828 4777 9829 4960 9829 4979 9829 4979 9830 4960 9830 4963 9830 4979 9831 4963 9831 4978 9831 4688 9832 4961 9832 4863 9832 4863 9833 4961 9833 4962 9833 4863 9834 4962 9834 4963 9834 4963 9835 4962 9835 4958 9835 4963 9836 4958 9836 4978 9836 4978 9837 4958 9837 4964 9837 4978 9838 4964 9838 4976 9838 4976 9839 4964 9839 5864 9839 4976 9840 5864 9840 5007 9840 5007 9841 5864 9841 5862 9841 3552 9842 4965 9842 4970 9842 4970 9843 4965 9843 4966 9843 4970 9844 4966 9844 4972 9844 4972 9845 4966 9845 4706 9845 4972 9846 4706 9846 4967 9846 4967 9847 4706 9847 4874 9847 4967 9848 4874 9848 4973 9848 4973 9849 4874 9849 4968 9849 4973 9850 4968 9850 4969 9850 3863 9851 4970 9851 4776 9851 4776 9852 4970 9852 4972 9852 4776 9853 4972 9853 4971 9853 4971 9854 4972 9854 4967 9854 4971 9855 4967 9855 4777 9855 4777 9856 4967 9856 4973 9856 4777 9857 4973 9857 4960 9857 4960 9858 4973 9858 4974 9858 4960 9859 4974 9859 4863 9859 4863 9860 4974 9860 4862 9860 4863 9861 4862 9861 3515 9861 5070 9862 4975 9862 5007 9862 5007 9863 4975 9863 5072 9863 5007 9864 5072 9864 4976 9864 4976 9865 5072 9865 4763 9865 4976 9866 4763 9866 4978 9866 4978 9867 4763 9867 4977 9867 4978 9868 4977 9868 4979 9868 4979 9869 4977 9869 3858 9869 4979 9870 3858 9870 3859 9870 4751 9871 4750 9871 4752 9871 4752 9872 4750 9872 4895 9872 4752 9873 4895 9873 4985 9873 4985 9874 4895 9874 4980 9874 4985 9875 4980 9875 4981 9875 4982 9876 4983 9876 4662 9876 4662 9877 4983 9877 4807 9877 4662 9878 4807 9878 4645 9878 4645 9879 4807 9879 5869 9879 4645 9880 5869 9880 3154 9880 4712 9881 4759 9881 4716 9881 4716 9882 4759 9882 4752 9882 4716 9883 4752 9883 4984 9883 4984 9884 4752 9884 4985 9884 4984 9885 4985 9885 4988 9885 4988 9886 4985 9886 3450 9886 4988 9887 3450 9887 4679 9887 2958 9888 4900 9888 4986 9888 4986 9889 4900 9889 4716 9889 4986 9890 4716 9890 4987 9890 4987 9891 4716 9891 4984 9891 4987 9892 4984 9892 4996 9892 4996 9893 4984 9893 4988 9893 4996 9894 4988 9894 4997 9894 4997 9895 4988 9895 4883 9895 4997 9896 4883 9896 4989 9896 4989 9897 4883 9897 6071 9897 4989 9898 6071 9898 2979 9898 4931 9899 4990 9899 4641 9899 4641 9900 4990 9900 4991 9900 4641 9901 4991 9901 4942 9901 4942 9902 4991 9902 4992 9902 4942 9903 4992 9903 4983 9903 4983 9904 4992 9904 5014 9904 4983 9905 5014 9905 4807 9905 4807 9906 5014 9906 4993 9906 4807 9907 4993 9907 4950 9907 4950 9908 4993 9908 6049 9908 4950 9909 6049 9909 6048 9909 4718 9910 4898 9910 4994 9910 4994 9911 4898 9911 4986 9911 4994 9912 4986 9912 4995 9912 4995 9913 4986 9913 4987 9913 4995 9914 4987 9914 4769 9914 4769 9915 4987 9915 4996 9915 4769 9916 4996 9916 4772 9916 4772 9917 4996 9917 4997 9917 4772 9918 4997 9918 4770 9918 4770 9919 4997 9919 4989 9919 4770 9920 4989 9920 4774 9920 4774 9921 4989 9921 4998 9921 4774 9922 4998 9922 4999 9922 4999 9923 4998 9923 4647 9923 4999 9924 4647 9924 3479 9924 5630 9925 5021 9925 4651 9925 4651 9926 5021 9926 5000 9926 4651 9927 5000 9927 5009 9927 5009 9928 5000 9928 5001 9928 5009 9929 5001 9929 5010 9929 5010 9930 5001 9930 5002 9930 5010 9931 5002 9931 5011 9931 5011 9932 5002 9932 5003 9932 5011 9933 5003 9933 5012 9933 5012 9934 5003 9934 5004 9934 5012 9935 5004 9935 5013 9935 5013 9936 5004 9936 5005 9936 5013 9937 5005 9937 5015 9937 5015 9938 5005 9938 4765 9938 5015 9939 4765 9939 5006 9939 5006 9940 4765 9940 5007 9940 5006 9941 5007 9941 5008 9941 5008 9942 5007 9942 5862 9942 4652 9943 5009 9943 4932 9943 4932 9944 5009 9944 5010 9944 4932 9945 5010 9945 4990 9945 4990 9946 5010 9946 5011 9946 4990 9947 5011 9947 4991 9947 4991 9948 5011 9948 5012 9948 4991 9949 5012 9949 4992 9949 4992 9950 5012 9950 5013 9950 4992 9951 5013 9951 5014 9951 5014 9952 5013 9952 5015 9952 5014 9953 5015 9953 4993 9953 4993 9954 5015 9954 4638 9954 4993 9955 4638 9955 4944 9955 4944 9956 4638 9956 5016 9956 4944 9957 5016 9957 3103 9957 6098 9958 5017 9958 5024 9958 5024 9959 5017 9959 5018 9959 5024 9960 5018 9960 5026 9960 5026 9961 5018 9961 5019 9961 5026 9962 5019 9962 5020 9962 5020 9963 5019 9963 3877 9963 5020 9964 3877 9964 5029 9964 5630 9965 4650 9965 5021 9965 5021 9966 4650 9966 4794 9966 5021 9967 4794 9967 5022 9967 5022 9968 4794 9968 4796 9968 5022 9969 4796 9969 5031 9969 5031 9970 4796 9970 4797 9970 5031 9971 4797 9971 5023 9971 5023 9972 4797 9972 3009 9972 5023 9973 3009 9973 4925 9973 4740 9974 4911 9974 4738 9974 4738 9975 4911 9975 5024 9975 4738 9976 5024 9976 5025 9976 5025 9977 5024 9977 5026 9977 5025 9978 5026 9978 5027 9978 5027 9979 5026 9979 5020 9979 5027 9980 5020 9980 5028 9980 5028 9981 5020 9981 5029 9981 5028 9982 5029 9982 3879 9982 4780 9983 4782 9983 4779 9983 4779 9984 4782 9984 5030 9984 4779 9985 5030 9985 5023 9985 5023 9986 5030 9986 5032 9986 5023 9987 5032 9987 5031 9987 5031 9988 5032 9988 5033 9988 5031 9989 5033 9989 5022 9989 5022 9990 5033 9990 5060 9990 5022 9991 5060 9991 5061 9991 5196 9992 4913 9992 4921 9992 4921 9993 4913 9993 4738 9993 4921 9994 4738 9994 4782 9994 4782 9995 4738 9995 5025 9995 4782 9996 5025 9996 5030 9996 5030 9997 5025 9997 5027 9997 5030 9998 5027 9998 5032 9998 5032 9999 5027 9999 5028 9999 5032 10000 5028 10000 5033 10000 5033 10001 5028 10001 3879 10001 5033 10002 3879 10002 5058 10002 5041 10003 3382 10003 3438 10003 3438 10004 3382 10004 3383 10004 3438 10005 3383 10005 3437 10005 3437 10006 3383 10006 5035 10006 3437 10007 5035 10007 5034 10007 5034 10008 5035 10008 3385 10008 5034 10009 3385 10009 5538 10009 5538 10010 3385 10010 5588 10010 5538 10011 5588 10011 5536 10011 5536 10012 5588 10012 5589 10012 5536 10013 5589 10013 5534 10013 5534 10014 5589 10014 5590 10014 5534 10015 5590 10015 5036 10015 5036 10016 5590 10016 5037 10016 5036 10017 5037 10017 5531 10017 5531 10018 5037 10018 5038 10018 5531 10019 5038 10019 5530 10019 5530 10020 5038 10020 5595 10020 5530 10021 5595 10021 3439 10021 3439 10022 5595 10022 5040 10022 3439 10023 5040 10023 5039 10023 5039 10024 5040 10024 3378 10024 5039 10025 3378 10025 5041 10025 5041 10026 3378 10026 3379 10026 5041 10027 3379 10027 3382 10027 2948 10028 3899 10028 6001 10028 2948 10029 6001 10029 5042 10029 5042 10030 6001 10030 5043 10030 5042 10031 5043 10031 5044 10031 5044 10032 5043 10032 5998 10032 5044 10033 5998 10033 6114 10033 6114 10034 5998 10034 5045 10034 6114 10035 5045 10035 5046 10035 5046 10036 5045 10036 5994 10036 5046 10037 5994 10037 6118 10037 6118 10038 5994 10038 5988 10038 6118 10039 5988 10039 6119 10039 6119 10040 5988 10040 5987 10040 6119 10041 5987 10041 5047 10041 5047 10042 5987 10042 5049 10042 5047 10043 5049 10043 5048 10043 5048 10044 5049 10044 5983 10044 5048 10045 5983 10045 5050 10045 5050 10046 5983 10046 5984 10046 5050 10047 5984 10047 5051 10047 5051 10048 5984 10048 5052 10048 5051 10049 5052 10049 5053 10049 5053 10050 5052 10050 5054 10050 5053 10051 5054 10051 5056 10051 5056 10052 5054 10052 5055 10052 5056 10053 5055 10053 6125 10053 6125 10054 5055 10054 5979 10054 6125 10055 5979 10055 6126 10055 6126 10056 5979 10056 5977 10056 6126 10057 5977 10057 6128 10057 6128 10058 5977 10058 5975 10058 6128 10059 5975 10059 5057 10059 5057 10060 5975 10060 5971 10060 5057 10061 5971 10061 6130 10061 6130 10062 5971 10062 5973 10062 6130 10063 5973 10063 6131 10063 6131 10064 5973 10064 5969 10064 6131 10065 5969 10065 3880 10065 5058 10066 3024 10066 5059 10066 5058 10067 5059 10067 5060 10067 5060 10068 5059 10068 5062 10068 5060 10069 5062 10069 5061 10069 5061 10070 5062 10070 6014 10070 5061 10071 6014 10071 4768 10071 4768 10072 6014 10072 5063 10072 4768 10073 5063 10073 4767 10073 4767 10074 5063 10074 6012 10074 4767 10075 6012 10075 4766 10075 4766 10076 6012 10076 6010 10076 4766 10077 6010 10077 5065 10077 5065 10078 6010 10078 5064 10078 5065 10079 5064 10079 5003 10079 5003 10080 5064 10080 5066 10080 5003 10081 5066 10081 5004 10081 5004 10082 5066 10082 5067 10082 5004 10083 5067 10083 5005 10083 5005 10084 5067 10084 6008 10084 5005 10085 6008 10085 5068 10085 5068 10086 6008 10086 5069 10086 5068 10087 5069 10087 5070 10087 5070 10088 5069 10088 6005 10088 5070 10089 6005 10089 4975 10089 4975 10090 6005 10090 5071 10090 4975 10091 5071 10091 5072 10091 5072 10092 5071 10092 6002 10092 5072 10093 6002 10093 4764 10093 4764 10094 6002 10094 5073 10094 4764 10095 5073 10095 4977 10095 4977 10096 5073 10096 5074 10096 4977 10097 5074 10097 3858 10097 3857 10098 3763 10098 5075 10098 5075 10099 3763 10099 5076 10099 5075 10100 5076 10100 5077 10100 5077 10101 5076 10101 5078 10101 5077 10102 5078 10102 5089 10102 5089 10103 5078 10103 5194 10103 5089 10104 5194 10104 5090 10104 5090 10105 5194 10105 5079 10105 5090 10106 5079 10106 5080 10106 5080 10107 5079 10107 5195 10107 5080 10108 5195 10108 5092 10108 5092 10109 5195 10109 3852 10109 5081 10110 3855 10110 5082 10110 5082 10111 3855 10111 5083 10111 5082 10112 5083 10112 3815 10112 3815 10113 5083 10113 5084 10113 3815 10114 5084 10114 5085 10114 5085 10115 5084 10115 3857 10115 5085 10116 3857 10116 5086 10116 5086 10117 3857 10117 5075 10117 5086 10118 5075 10118 5087 10118 5087 10119 5075 10119 5077 10119 5087 10120 5077 10120 5148 10120 5148 10121 5077 10121 5089 10121 5148 10122 5089 10122 5088 10122 5088 10123 5089 10123 5090 10123 5088 10124 5090 10124 5150 10124 5150 10125 5090 10125 5080 10125 5150 10126 5080 10126 5091 10126 5091 10127 5080 10127 5092 10127 5091 10128 5092 10128 5093 10128 5093 10129 5092 10129 5094 10129 5093 10130 5094 10130 5095 10130 5095 10131 5094 10131 5096 10131 5095 10132 5096 10132 3812 10132 3812 10133 5096 10133 3853 10133 3812 10134 3853 10134 5081 10134 5081 10135 3853 10135 3855 10135 5107 10136 3746 10136 5097 10136 5107 10137 5097 10137 5109 10137 5109 10138 5097 10138 5204 10138 5109 10139 5204 10139 5098 10139 5098 10140 5204 10140 5099 10140 5098 10141 5099 10141 5116 10141 5099 10142 5100 10142 5116 10142 5116 10143 5100 10143 5101 10143 5116 10144 5101 10144 5103 10144 5101 10145 5102 10145 5103 10145 5103 10146 5102 10146 5104 10146 5103 10147 5104 10147 5114 10147 5104 10148 5200 10148 5114 10148 5114 10149 5200 10149 5199 10149 5114 10150 5199 10150 5113 10150 5113 10151 5199 10151 5105 10151 5113 10152 5105 10152 3840 10152 5112 10153 3848 10153 3793 10153 3793 10154 3848 10154 3795 10154 3795 10155 3848 10155 5106 10155 3795 10156 5106 10156 5169 10156 5169 10157 5106 10157 5107 10157 5169 10158 5107 10158 5108 10158 5108 10159 5107 10159 5109 10159 5108 10160 5109 10160 5110 10160 5110 10161 5109 10161 5098 10161 5110 10162 5098 10162 5171 10162 3793 10163 5111 10163 5112 10163 5112 10164 5111 10164 3792 10164 5112 10165 3792 10165 3845 10165 3845 10166 3792 10166 3791 10166 3845 10167 3791 10167 3841 10167 3841 10168 3791 10168 3790 10168 3841 10169 3790 10169 3840 10169 3840 10170 3790 10170 3788 10170 3840 10171 3788 10171 5113 10171 5113 10172 3788 10172 5172 10172 5113 10173 5172 10173 5114 10173 5114 10174 5172 10174 5115 10174 5114 10175 5115 10175 5103 10175 5103 10176 5115 10176 5171 10176 5103 10177 5171 10177 5116 10177 5116 10178 5171 10178 5098 10178 5127 10179 5117 10179 5128 10179 5128 10180 5117 10180 5118 10180 5128 10181 5118 10181 5130 10181 5130 10182 5118 10182 5206 10182 5130 10183 5206 10183 5119 10183 5119 10184 5206 10184 5207 10184 5119 10185 5207 10185 5131 10185 5131 10186 5207 10186 5208 10186 5131 10187 5208 10187 5120 10187 5120 10188 5208 10188 5121 10188 5120 10189 5121 10189 5122 10189 5122 10190 5121 10190 5123 10190 5132 10191 5122 10191 3771 10191 3771 10192 5122 10192 3833 10192 3771 10193 3833 10193 3772 10193 3772 10194 3833 10194 3834 10194 3772 10195 3834 10195 3768 10195 3768 10196 3834 10196 3836 10196 3768 10197 3836 10197 3765 10197 3765 10198 3836 10198 5124 10198 3765 10199 5124 10199 5125 10199 5125 10200 5124 10200 3838 10200 5125 10201 3838 10201 5126 10201 5126 10202 3838 10202 5127 10202 5126 10203 5127 10203 5129 10203 5129 10204 5127 10204 5128 10204 5129 10205 5128 10205 5188 10205 5188 10206 5128 10206 5130 10206 5188 10207 5130 10207 5190 10207 5190 10208 5130 10208 5119 10208 5190 10209 5119 10209 5191 10209 5191 10210 5119 10210 5131 10210 5191 10211 5131 10211 5192 10211 5192 10212 5131 10212 5120 10212 5192 10213 5120 10213 5132 10213 5132 10214 5120 10214 5122 10214 5133 10215 4280 10215 5134 10215 5134 10216 4280 10216 5135 10216 5134 10217 5135 10217 5144 10217 5144 10218 5135 10218 5137 10218 5144 10219 5137 10219 5136 10219 5136 10220 5137 10220 5138 10220 5136 10221 5138 10221 5142 10221 5142 10222 5138 10222 4284 10222 5142 10223 4284 10223 5141 10223 5141 10224 4284 10224 5139 10224 5141 10225 5139 10225 3823 10225 3823 10226 5139 10226 3824 10226 3823 10227 5140 10227 5141 10227 5141 10228 5140 10228 5147 10228 5141 10229 5147 10229 5142 10229 5142 10230 5147 10230 5143 10230 5142 10231 5143 10231 5136 10231 5136 10232 5143 10232 5145 10232 5136 10233 5145 10233 5144 10233 5144 10234 5145 10234 5149 10234 5144 10235 5149 10235 5134 10235 5134 10236 5149 10236 5146 10236 5134 10237 5146 10237 5133 10237 5133 10238 5146 10238 3816 10238 5140 10239 5085 10239 5147 10239 5147 10240 5085 10240 5086 10240 5147 10241 5086 10241 5143 10241 5143 10242 5086 10242 5087 10242 5143 10243 5087 10243 5145 10243 5145 10244 5087 10244 5148 10244 5145 10245 5148 10245 5149 10245 5149 10246 5148 10246 5088 10246 5149 10247 5088 10247 5146 10247 5146 10248 5088 10248 5150 10248 5146 10249 5150 10249 3816 10249 3816 10250 5150 10250 5091 10250 4217 10251 4218 10251 5160 10251 5160 10252 5151 10252 4217 10252 4217 10253 5151 10253 5162 10253 4217 10254 5162 10254 4216 10254 5162 10255 5152 10255 4216 10255 4216 10256 5152 10256 5164 10256 4216 10257 5164 10257 4214 10257 4214 10258 5164 10258 5165 10258 4214 10259 5165 10259 5153 10259 5165 10260 5154 10260 5153 10260 5153 10261 5154 10261 5155 10261 5153 10262 5155 10262 4228 10262 5155 10263 5156 10263 4228 10263 4228 10264 5156 10264 5168 10264 4228 10265 5168 10265 5159 10265 3796 10266 4225 10266 5157 10266 5157 10267 4225 10267 5159 10267 5157 10268 5159 10268 5158 10268 5158 10269 5159 10269 5168 10269 5160 10270 5161 10270 5151 10270 5151 10271 5161 10271 5170 10271 5151 10272 5170 10272 5162 10272 5162 10273 5170 10273 5152 10273 5152 10274 5170 10274 5163 10274 5152 10275 5163 10275 5164 10275 5164 10276 5163 10276 5165 10276 5165 10277 5163 10277 5166 10277 5165 10278 5166 10278 5154 10278 5154 10279 5166 10279 5155 10279 5155 10280 5166 10280 5167 10280 5155 10281 5167 10281 5156 10281 5156 10282 5167 10282 5168 10282 5168 10283 5167 10283 5173 10283 5168 10284 5173 10284 5158 10284 5158 10285 5173 10285 5157 10285 5157 10286 5173 10286 5174 10286 5157 10287 5174 10287 3796 10287 5161 10288 5169 10288 5170 10288 5170 10289 5169 10289 5108 10289 5170 10290 5108 10290 5163 10290 5163 10291 5108 10291 5110 10291 5163 10292 5110 10292 5166 10292 5166 10293 5110 10293 5171 10293 5166 10294 5171 10294 5167 10294 5167 10295 5171 10295 5115 10295 5167 10296 5115 10296 5173 10296 5173 10297 5115 10297 5172 10297 5173 10298 5172 10298 5174 10298 5174 10299 5172 10299 3788 10299 5175 10300 5176 10300 5177 10300 5177 10301 5176 10301 4206 10301 5177 10302 4206 10302 5184 10302 5184 10303 4206 10303 4207 10303 5184 10304 4207 10304 5183 10304 5183 10305 4207 10305 5179 10305 5183 10306 5179 10306 5178 10306 5178 10307 5179 10307 5181 10307 5178 10308 5181 10308 5180 10308 5180 10309 5181 10309 4209 10309 5180 10310 4209 10310 3781 10310 3781 10311 4209 10311 4210 10311 3781 10312 3780 10312 5180 10312 5180 10313 3780 10313 5182 10313 5180 10314 5182 10314 5178 10314 5178 10315 5182 10315 5187 10315 5178 10316 5187 10316 5183 10316 5183 10317 5187 10317 5185 10317 5183 10318 5185 10318 5184 10318 5184 10319 5185 10319 5189 10319 5184 10320 5189 10320 5177 10320 5177 10321 5189 10321 5186 10321 5177 10322 5186 10322 5175 10322 5175 10323 5186 10323 3770 10323 3780 10324 5126 10324 5182 10324 5182 10325 5126 10325 5129 10325 5182 10326 5129 10326 5187 10326 5187 10327 5129 10327 5188 10327 5187 10328 5188 10328 5185 10328 5185 10329 5188 10329 5190 10329 5185 10330 5190 10330 5189 10330 5189 10331 5190 10331 5191 10331 5189 10332 5191 10332 5186 10332 5186 10333 5191 10333 5192 10333 5186 10334 5192 10334 3770 10334 3770 10335 5192 10335 5132 10335 3763 10336 4917 10336 5076 10336 5076 10337 4917 10337 4916 10337 5076 10338 4916 10338 5078 10338 5078 10339 4916 10339 5193 10339 5078 10340 5193 10340 5194 10340 5194 10341 5193 10341 4914 10341 5194 10342 4914 10342 5079 10342 5079 10343 4914 10343 4915 10343 5079 10344 4915 10344 5195 10344 5195 10345 4915 10345 4912 10345 5195 10346 4912 10346 3852 10346 3852 10347 4912 10347 5196 10347 5197 10348 5105 10348 5198 10348 5198 10349 5105 10349 5199 10349 5198 10350 5199 10350 5201 10350 5201 10351 5199 10351 5200 10351 5200 10352 5104 10352 5201 10352 5201 10353 5104 10353 5102 10353 5201 10354 5102 10354 5202 10354 5102 10355 5101 10355 5202 10355 5202 10356 5101 10356 5100 10356 5202 10357 5100 10357 5205 10357 3746 10358 4726 10358 5097 10358 5097 10359 4726 10359 5203 10359 5097 10360 5203 10360 5204 10360 5204 10361 5203 10361 5205 10361 5204 10362 5205 10362 5099 10362 5099 10363 5205 10363 5100 10363 5117 10364 4758 10364 5118 10364 5118 10365 4758 10365 4757 10365 5118 10366 4757 10366 5206 10366 5206 10367 4757 10367 4756 10367 5206 10368 4756 10368 5207 10368 5207 10369 4756 10369 4762 10369 5207 10370 4762 10370 5208 10370 5208 10371 4762 10371 4761 10371 5208 10372 4761 10372 5121 10372 5121 10373 4761 10373 5209 10373 5121 10374 5209 10374 5123 10374 5123 10375 5209 10375 5210 10375 5213 10376 4275 10376 5211 10376 5211 10377 5212 10377 5213 10377 5213 10378 5212 10378 5220 10378 5213 10379 5220 10379 4273 10379 4273 10380 5220 10380 5222 10380 5222 10381 5223 10381 4273 10381 4273 10382 5223 10382 5225 10382 4273 10383 5225 10383 5214 10383 5225 10384 5227 10384 5214 10384 5214 10385 5227 10385 5229 10385 5214 10386 5229 10386 4272 10386 5229 10387 5230 10387 4272 10387 4272 10388 5230 10388 5215 10388 4272 10389 5215 10389 5218 10389 3727 10390 5217 10390 5216 10390 5216 10391 5217 10391 5218 10391 5216 10392 5218 10392 5232 10392 5232 10393 5218 10393 5215 10393 5211 10394 5219 10394 5212 10394 5212 10395 5219 10395 5240 10395 5212 10396 5240 10396 5220 10396 5220 10397 5240 10397 5221 10397 5220 10398 5221 10398 5222 10398 5222 10399 5221 10399 5239 10399 5222 10400 5239 10400 5223 10400 5223 10401 5239 10401 5224 10401 5223 10402 5224 10402 5225 10402 5225 10403 5224 10403 5226 10403 5225 10404 5226 10404 5227 10404 5227 10405 5226 10405 5237 10405 5227 10406 5237 10406 5229 10406 5229 10407 5237 10407 5228 10407 5229 10408 5228 10408 5230 10408 5230 10409 5228 10409 5231 10409 5230 10410 5231 10410 5215 10410 5215 10411 5231 10411 5236 10411 5215 10412 5236 10412 5232 10412 5232 10413 5236 10413 5235 10413 5232 10414 5235 10414 5216 10414 5216 10415 5235 10415 5233 10415 5216 10416 5233 10416 3727 10416 3727 10417 5233 10417 5234 10417 4733 10418 4740 10418 5234 10418 5234 10419 5233 10419 4733 10419 4733 10420 5233 10420 5235 10420 4733 10421 5235 10421 4734 10421 5235 10422 5236 10422 4734 10422 4734 10423 5236 10423 5231 10423 4734 10424 5231 10424 4736 10424 4736 10425 5231 10425 5228 10425 5228 10426 5237 10426 4736 10426 4736 10427 5237 10427 5226 10427 4736 10428 5226 10428 5238 10428 5226 10429 5224 10429 5238 10429 5238 10430 5224 10430 5239 10430 5238 10431 5239 10431 4742 10431 5219 10432 4744 10432 5240 10432 5240 10433 4744 10433 4742 10433 5240 10434 4742 10434 5221 10434 5221 10435 4742 10435 5239 10435 3702 10436 3718 10436 5241 10436 5241 10437 3718 10437 4258 10437 5241 10438 4258 10438 5252 10438 5252 10439 4258 10439 5242 10439 5252 10440 5242 10440 5250 10440 5250 10441 5242 10441 5243 10441 5250 10442 5243 10442 5248 10442 5248 10443 5243 10443 5244 10443 5248 10444 5244 10444 5245 10444 5245 10445 5244 10445 4263 10445 5245 10446 4263 10446 3710 10446 3710 10447 4263 10447 5246 10447 3710 10448 5256 10448 5245 10448 5245 10449 5256 10449 5247 10449 5245 10450 5247 10450 5248 10450 5248 10451 5247 10451 5249 10451 5248 10452 5249 10452 5250 10452 5250 10453 5249 10453 5251 10453 5250 10454 5251 10454 5252 10454 5252 10455 5251 10455 5253 10455 5252 10456 5253 10456 5241 10456 5241 10457 5253 10457 5254 10457 5241 10458 5254 10458 3702 10458 3702 10459 5254 10459 5255 10459 5256 10460 4729 10460 5247 10460 5247 10461 4729 10461 4727 10461 5247 10462 4727 10462 5249 10462 5249 10463 4727 10463 5257 10463 5249 10464 5257 10464 5251 10464 5251 10465 5257 10465 5258 10465 5251 10466 5258 10466 5253 10466 5253 10467 5258 10467 4725 10467 5253 10468 4725 10468 5254 10468 5254 10469 4725 10469 4723 10469 5254 10470 4723 10470 5255 10470 5255 10471 4723 10471 3695 10471 5270 10472 3685 10472 5268 10472 5268 10473 3685 10473 4247 10473 5268 10474 4247 10474 5259 10474 5259 10475 4247 10475 5260 10475 5259 10476 5260 10476 5266 10476 5266 10477 5260 10477 4249 10477 5266 10478 4249 10478 5261 10478 5261 10479 4249 10479 5262 10479 5261 10480 5262 10480 5265 10480 5265 10481 5262 10481 5263 10481 5265 10482 5263 10482 5264 10482 5264 10483 5263 10483 4252 10483 5264 10484 3684 10484 5265 10484 5265 10485 3684 10485 5274 10485 5265 10486 5274 10486 5261 10486 5261 10487 5274 10487 5275 10487 5261 10488 5275 10488 5266 10488 5266 10489 5275 10489 5267 10489 5266 10490 5267 10490 5259 10490 5259 10491 5267 10491 5269 10491 5259 10492 5269 10492 5268 10492 5268 10493 5269 10493 5278 10493 5268 10494 5278 10494 5270 10494 5270 10495 5278 10495 5271 10495 3684 10496 5272 10496 5274 10496 5274 10497 5272 10497 5273 10497 5274 10498 5273 10498 5275 10498 5275 10499 5273 10499 4719 10499 5275 10500 4719 10500 5267 10500 5267 10501 4719 10501 4722 10501 5267 10502 4722 10502 5269 10502 5269 10503 4722 10503 5276 10503 5269 10504 5276 10504 5278 10504 5278 10505 5276 10505 5277 10505 5278 10506 5277 10506 5271 10506 5271 10507 5277 10507 4720 10507 3664 10508 4230 10508 5291 10508 5291 10509 4230 10509 5279 10509 5291 10510 5279 10510 5290 10510 5290 10511 5279 10511 5280 10511 5290 10512 5280 10512 5288 10512 5288 10513 5280 10513 5281 10513 5288 10514 5281 10514 5287 10514 5287 10515 5281 10515 5282 10515 5287 10516 5282 10516 5285 10516 5285 10517 5282 10517 5283 10517 5285 10518 5283 10518 5284 10518 5284 10519 5283 10519 4238 10519 5284 10520 5293 10520 5285 10520 5285 10521 5293 10521 5286 10521 5285 10522 5286 10522 5287 10522 5287 10523 5286 10523 5294 10523 5287 10524 5294 10524 5288 10524 5288 10525 5294 10525 5289 10525 5288 10526 5289 10526 5290 10526 5290 10527 5289 10527 5297 10527 5290 10528 5297 10528 5291 10528 5291 10529 5297 10529 5292 10529 5291 10530 5292 10530 3664 10530 3664 10531 5292 10531 3646 10531 5293 10532 4903 10532 5286 10532 5286 10533 4903 10533 5295 10533 5286 10534 5295 10534 5294 10534 5294 10535 5295 10535 5296 10535 5294 10536 5296 10536 5289 10536 5289 10537 5296 10537 4713 10537 5289 10538 4713 10538 5297 10538 5297 10539 4713 10539 5298 10539 5297 10540 5298 10540 5292 10540 5292 10541 5298 10541 4709 10541 5292 10542 4709 10542 3646 10542 3646 10543 4709 10543 4710 10543 5299 10544 3560 10544 5301 10544 5301 10545 3560 10545 5300 10545 5301 10546 5300 10546 5308 10546 5308 10547 5300 10547 5421 10547 5308 10548 5421 10548 5306 10548 5306 10549 5421 10549 5302 10549 5306 10550 5302 10550 5313 10550 5313 10551 5302 10551 5304 10551 5313 10552 5304 10552 5303 10552 5303 10553 5304 10553 5305 10553 5303 10554 5305 10554 5311 10554 5311 10555 5305 10555 3637 10555 5314 10556 5363 10556 5306 10556 5306 10557 5363 10557 5307 10557 5306 10558 5307 10558 5308 10558 5308 10559 5307 10559 5309 10559 5308 10560 5309 10560 5301 10560 5301 10561 5309 10561 5310 10561 5301 10562 5310 10562 5299 10562 5299 10563 5310 10563 3611 10563 5299 10564 3611 10564 3645 10564 3645 10565 3611 10565 3609 10565 3645 10566 3609 10566 3644 10566 3644 10567 3609 10567 3608 10567 3644 10568 3608 10568 3641 10568 3641 10569 3608 10569 3606 10569 3641 10570 3606 10570 3640 10570 3640 10571 3606 10571 3604 10571 3640 10572 3604 10572 3638 10572 3638 10573 3604 10573 3602 10573 3638 10574 3602 10574 5311 10574 5311 10575 3602 10575 5312 10575 5311 10576 5312 10576 5303 10576 5303 10577 5312 10577 5365 10577 5303 10578 5365 10578 5313 10578 5313 10579 5365 10579 5314 10579 5313 10580 5314 10580 5306 10580 5323 10581 3553 10581 5315 10581 5315 10582 3553 10582 5316 10582 5315 10583 5316 10583 5321 10583 5321 10584 5316 10584 5317 10584 5321 10585 5317 10585 5318 10585 5318 10586 5317 10586 5319 10586 5318 10587 5319 10587 5332 10587 5332 10588 5319 10588 5427 10588 5332 10589 5427 10589 5331 10589 5331 10590 5427 10590 5426 10590 5331 10591 5426 10591 5328 10591 5328 10592 5426 10592 3632 10592 5387 10593 5320 10593 5318 10593 5318 10594 5320 10594 5322 10594 5318 10595 5322 10595 5321 10595 5321 10596 5322 10596 5386 10596 5321 10597 5386 10597 5315 10597 5315 10598 5386 10598 5385 10598 5315 10599 5385 10599 5323 10599 5323 10600 5385 10600 3590 10600 5323 10601 3590 10601 5324 10601 5324 10602 3590 10602 3589 10602 5324 10603 3589 10603 5325 10603 5325 10604 3589 10604 3588 10604 5325 10605 3588 10605 5326 10605 5326 10606 3588 10606 3586 10606 5326 10607 3586 10607 3634 10607 3634 10608 3586 10608 5327 10608 3634 10609 5327 10609 3633 10609 3633 10610 5327 10610 3584 10610 3633 10611 3584 10611 5328 10611 5328 10612 3584 10612 5329 10612 5328 10613 5329 10613 5331 10613 5331 10614 5329 10614 5330 10614 5331 10615 5330 10615 5332 10615 5332 10616 5330 10616 5387 10616 5332 10617 5387 10617 5318 10617 5342 10618 5429 10618 5344 10618 5344 10619 5429 10619 5333 10619 5344 10620 5333 10620 5334 10620 5334 10621 5333 10621 5430 10621 5334 10622 5430 10622 5336 10622 5336 10623 5430 10623 5335 10623 5336 10624 5335 10624 5345 10624 5345 10625 5335 10625 5337 10625 5345 10626 5337 10626 5339 10626 5339 10627 5337 10627 5338 10627 5339 10628 5338 10628 3623 10628 3623 10629 5338 10629 3624 10629 3564 10630 3629 10630 3562 10630 3562 10631 3629 10631 5340 10631 3562 10632 5340 10632 5341 10632 5341 10633 5340 10633 3631 10633 5341 10634 3631 10634 5418 10634 5418 10635 3631 10635 5342 10635 5418 10636 5342 10636 5343 10636 5343 10637 5342 10637 5344 10637 5343 10638 5344 10638 5416 10638 5416 10639 5344 10639 5334 10639 5416 10640 5334 10640 5414 10640 5414 10641 5334 10641 5336 10641 5414 10642 5336 10642 5412 10642 5412 10643 5336 10643 5345 10643 5412 10644 5345 10644 5346 10644 5346 10645 5345 10645 5339 10645 5346 10646 5339 10646 5408 10646 5408 10647 5339 10647 3623 10647 5408 10648 3623 10648 3568 10648 3568 10649 3623 10649 3626 10649 3568 10650 3626 10650 3567 10650 3567 10651 3626 10651 5348 10651 3567 10652 5348 10652 5347 10652 5347 10653 5348 10653 3627 10653 5347 10654 3627 10654 3564 10654 3564 10655 3627 10655 3629 10655 3612 10656 4426 10656 5349 10656 5349 10657 4426 10657 5351 10657 5349 10658 5351 10658 5350 10658 5350 10659 5351 10659 4427 10659 5350 10660 4427 10660 5352 10660 5352 10661 4427 10661 5353 10661 5352 10662 5353 10662 5354 10662 5354 10663 5353 10663 4429 10663 5354 10664 4429 10664 5357 10664 5357 10665 4429 10665 4430 10665 5357 10666 4430 10666 5355 10666 5355 10667 4430 10667 4420 10667 5355 10668 4420 10668 3617 10668 3617 10669 4420 10669 4421 10669 3617 10670 3610 10670 5355 10670 5355 10671 3610 10671 5356 10671 5355 10672 5356 10672 5357 10672 5357 10673 5356 10673 5361 10673 5357 10674 5361 10674 5354 10674 5354 10675 5361 10675 5362 10675 5354 10676 5362 10676 5352 10676 5352 10677 5362 10677 5358 10677 5352 10678 5358 10678 5350 10678 5350 10679 5358 10679 5364 10679 5350 10680 5364 10680 5349 10680 5349 10681 5364 10681 5359 10681 5349 10682 5359 10682 3612 10682 3612 10683 5359 10683 5360 10683 3610 10684 3611 10684 5356 10684 5356 10685 3611 10685 5310 10685 5356 10686 5310 10686 5361 10686 5361 10687 5310 10687 5309 10687 5361 10688 5309 10688 5362 10688 5362 10689 5309 10689 5307 10689 5362 10690 5307 10690 5358 10690 5358 10691 5307 10691 5363 10691 5358 10692 5363 10692 5364 10692 5364 10693 5363 10693 5314 10693 5364 10694 5314 10694 5359 10694 5359 10695 5314 10695 5365 10695 5359 10696 5365 10696 5360 10696 5360 10697 5365 10697 5312 10697 5382 10698 4442 10698 5381 10698 5381 10699 4442 10699 4443 10699 5381 10700 4443 10700 5380 10700 5380 10701 4443 10701 5366 10701 5380 10702 5366 10702 5377 10702 5377 10703 5366 10703 5367 10703 5377 10704 5367 10704 5368 10704 5368 10705 5367 10705 4432 10705 5368 10706 4432 10706 5369 10706 5369 10707 4432 10707 5370 10707 5369 10708 5370 10708 5372 10708 5372 10709 5370 10709 5371 10709 5372 10710 5371 10710 3598 10710 3598 10711 5371 10711 5373 10711 3598 10712 5374 10712 5372 10712 5372 10713 5374 10713 5384 10713 5372 10714 5384 10714 5369 10714 5369 10715 5384 10715 5375 10715 5369 10716 5375 10716 5368 10716 5368 10717 5375 10717 5376 10717 5368 10718 5376 10718 5377 10718 5377 10719 5376 10719 5378 10719 5377 10720 5378 10720 5380 10720 5380 10721 5378 10721 5379 10721 5380 10722 5379 10722 5381 10722 5381 10723 5379 10723 5383 10723 5381 10724 5383 10724 5382 10724 5382 10725 5383 10725 3592 10725 5374 10726 3590 10726 5384 10726 5384 10727 3590 10727 5385 10727 5384 10728 5385 10728 5375 10728 5375 10729 5385 10729 5386 10729 5375 10730 5386 10730 5376 10730 5376 10731 5386 10731 5322 10731 5376 10732 5322 10732 5378 10732 5378 10733 5322 10733 5320 10733 5378 10734 5320 10734 5379 10734 5379 10735 5320 10735 5387 10735 5379 10736 5387 10736 5383 10736 5383 10737 5387 10737 5330 10737 5383 10738 5330 10738 3592 10738 3592 10739 5330 10739 5329 10739 4454 10740 4455 10740 5397 10740 5397 10741 5399 10741 4454 10741 4454 10742 5399 10742 5388 10742 4454 10743 5388 10743 5389 10743 5388 10744 5400 10744 5389 10744 5389 10745 5400 10745 5390 10745 5389 10746 5390 10746 4451 10746 4451 10747 5390 10747 5402 10747 5402 10748 5403 10748 4451 10748 4451 10749 5403 10749 5391 10749 4451 10750 5391 10750 5392 10750 5391 10751 5393 10751 5392 10751 5392 10752 5393 10752 5394 10752 5392 10753 5394 10753 4450 10753 5395 10754 5396 10754 5407 10754 5407 10755 5396 10755 4450 10755 5407 10756 4450 10756 5406 10756 5406 10757 4450 10757 5394 10757 5397 10758 5398 10758 5399 10758 5399 10759 5398 10759 5419 10759 5399 10760 5419 10760 5388 10760 5388 10761 5419 10761 5420 10761 5388 10762 5420 10762 5400 10762 5400 10763 5420 10763 5417 10763 5400 10764 5417 10764 5390 10764 5390 10765 5417 10765 5401 10765 5390 10766 5401 10766 5402 10766 5402 10767 5401 10767 5415 10767 5402 10768 5415 10768 5403 10768 5403 10769 5415 10769 5404 10769 5403 10770 5404 10770 5391 10770 5391 10771 5404 10771 5413 10771 5391 10772 5413 10772 5393 10772 5393 10773 5413 10773 5405 10773 5393 10774 5405 10774 5394 10774 5394 10775 5405 10775 5411 10775 5394 10776 5411 10776 5406 10776 5406 10777 5411 10777 5410 10777 5406 10778 5410 10778 5407 10778 5407 10779 5410 10779 5409 10779 5407 10780 5409 10780 5395 10780 5395 10781 5409 10781 3570 10781 5346 10782 5408 10782 3570 10782 3570 10783 5409 10783 5346 10783 5346 10784 5409 10784 5410 10784 5346 10785 5410 10785 5412 10785 5410 10786 5411 10786 5412 10786 5412 10787 5411 10787 5405 10787 5412 10788 5405 10788 5414 10788 5414 10789 5405 10789 5413 10789 5413 10790 5404 10790 5414 10790 5414 10791 5404 10791 5415 10791 5414 10792 5415 10792 5416 10792 5415 10793 5401 10793 5416 10793 5416 10794 5401 10794 5417 10794 5416 10795 5417 10795 5343 10795 5398 10796 5418 10796 5419 10796 5419 10797 5418 10797 5343 10797 5419 10798 5343 10798 5420 10798 5420 10799 5343 10799 5417 10799 3560 10800 4961 10800 5300 10800 5300 10801 4961 10801 4688 10801 5300 10802 4688 10802 5421 10802 5421 10803 4688 10803 4687 10803 5421 10804 4687 10804 5302 10804 5302 10805 4687 10805 5422 10805 5302 10806 5422 10806 5304 10806 5304 10807 5422 10807 4690 10807 5304 10808 4690 10808 5305 10808 5305 10809 4690 10809 5423 10809 5305 10810 5423 10810 3637 10810 3637 10811 5423 10811 3554 10811 5424 10812 3632 10812 4696 10812 4696 10813 3632 10813 5426 10813 4696 10814 5426 10814 5425 10814 5425 10815 5426 10815 5427 10815 3553 10816 4691 10816 5316 10816 5316 10817 4691 10817 4683 10817 5316 10818 4683 10818 5317 10818 5317 10819 4683 10819 4692 10819 5317 10820 4692 10820 5319 10820 5319 10821 4692 10821 4693 10821 5319 10822 4693 10822 5427 10822 5427 10823 4693 10823 5428 10823 5427 10824 5428 10824 5425 10824 5429 10825 4980 10825 5333 10825 5333 10826 4980 10826 5431 10826 5333 10827 5431 10827 5430 10827 5430 10828 5431 10828 4671 10828 5430 10829 4671 10829 5335 10829 5335 10830 4671 10830 4888 10830 5335 10831 4888 10831 5337 10831 5337 10832 4888 10832 5432 10832 5337 10833 5432 10833 5338 10833 5338 10834 5432 10834 4708 10834 5338 10835 4708 10835 3624 10835 3624 10836 4708 10836 4675 10836 3525 10837 5433 10837 5434 10837 5434 10838 5433 10838 5435 10838 5434 10839 5435 10839 5445 10839 5445 10840 5435 10840 4382 10840 5445 10841 4382 10841 5444 10841 5444 10842 4382 10842 4381 10842 5444 10843 4381 10843 5436 10843 5436 10844 4381 10844 4379 10844 5436 10845 4379 10845 5437 10845 5437 10846 4379 10846 4378 10846 5437 10847 4378 10847 5438 10847 5438 10848 4378 10848 4377 10848 5438 10849 4377 10849 3535 10849 3535 10850 4377 10850 4375 10850 3535 10851 3514 10851 5439 10851 3535 10852 5439 10852 5438 10852 5438 10853 5439 10853 5450 10853 5438 10854 5450 10854 5437 10854 5437 10855 5450 10855 5440 10855 5437 10856 5440 10856 5436 10856 5440 10857 5441 10857 5436 10857 5436 10858 5441 10858 5448 10858 5436 10859 5448 10859 5444 10859 5448 10860 5442 10860 5444 10860 5444 10861 5442 10861 5443 10861 5444 10862 5443 10862 5445 10862 5443 10863 5447 10863 5445 10863 5445 10864 5447 10864 5446 10864 5445 10865 5446 10865 5434 10865 5434 10866 5446 10866 3524 10866 5434 10867 3524 10867 3525 10867 3522 10868 3524 10868 4858 10868 4858 10869 3524 10869 5446 10869 4858 10870 5446 10870 4859 10870 5446 10871 5447 10871 4859 10871 4859 10872 5447 10872 5443 10872 4859 10873 5443 10873 4860 10873 4860 10874 5443 10874 5442 10874 5442 10875 5448 10875 4860 10875 4860 10876 5448 10876 5441 10876 4860 10877 5441 10877 5449 10877 3514 10878 4862 10878 5439 10878 5439 10879 4862 10879 4861 10879 5439 10880 4861 10880 5450 10880 5450 10881 4861 10881 5449 10881 5450 10882 5449 10882 5440 10882 5440 10883 5449 10883 5441 10883 5464 10884 4392 10884 5463 10884 5463 10885 4392 10885 5451 10885 5463 10886 5451 10886 5461 10886 5461 10887 5451 10887 4394 10887 5461 10888 4394 10888 5452 10888 5452 10889 4394 10889 4386 10889 5452 10890 4386 10890 5453 10890 5453 10891 4386 10891 5454 10891 5453 10892 5454 10892 5455 10892 5455 10893 5454 10893 5456 10893 5455 10894 5456 10894 5458 10894 5458 10895 5456 10895 4388 10895 5458 10896 4388 10896 3507 10896 3507 10897 4388 10897 5457 10897 3507 10898 3508 10898 5458 10898 5458 10899 3508 10899 5459 10899 5458 10900 5459 10900 5455 10900 5455 10901 5459 10901 5465 10901 5455 10902 5465 10902 5453 10902 5453 10903 5465 10903 5466 10903 5453 10904 5466 10904 5452 10904 5452 10905 5466 10905 5460 10905 5452 10906 5460 10906 5461 10906 5461 10907 5460 10907 5462 10907 5461 10908 5462 10908 5463 10908 5463 10909 5462 10909 5468 10909 5463 10910 5468 10910 5464 10910 5464 10911 5468 10911 3499 10911 3508 10912 3498 10912 5459 10912 5459 10913 3498 10913 4702 10913 5459 10914 4702 10914 5465 10914 5465 10915 4702 10915 4705 10915 5465 10916 4705 10916 5466 10916 5466 10917 4705 10917 5467 10917 5466 10918 5467 10918 5460 10918 5460 10919 5467 10919 4704 10919 5460 10920 4704 10920 5462 10920 5462 10921 4704 10921 4703 10921 5462 10922 4703 10922 5468 10922 5468 10923 4703 10923 5469 10923 5468 10924 5469 10924 3499 10924 3499 10925 5469 10925 3495 10925 3494 10926 4396 10926 5470 10926 5470 10927 4396 10927 5471 10927 5470 10928 5471 10928 5479 10928 5479 10929 5471 10929 5472 10929 5479 10930 5472 10930 5477 10930 5477 10931 5472 10931 4398 10931 5477 10932 4398 10932 5473 10932 5473 10933 4398 10933 4399 10933 5473 10934 4399 10934 5475 10934 5475 10935 4399 10935 4400 10935 5475 10936 4400 10936 3486 10936 3486 10937 4400 10937 3487 10937 3486 10938 5474 10938 5475 10938 5475 10939 5474 10939 5476 10939 5475 10940 5476 10940 5473 10940 5473 10941 5476 10941 5480 10941 5473 10942 5480 10942 5477 10942 5477 10943 5480 10943 5478 10943 5477 10944 5478 10944 5479 10944 5479 10945 5478 10945 5482 10945 5479 10946 5482 10946 5470 10946 5470 10947 5482 10947 5483 10947 5470 10948 5483 10948 3494 10948 3494 10949 5483 10949 5485 10949 5474 10950 4647 10950 5476 10950 5476 10951 4647 10951 4880 10951 5476 10952 4880 10952 5480 10952 5480 10953 4880 10953 4685 10953 5480 10954 4685 10954 5478 10954 5478 10955 4685 10955 5481 10955 5478 10956 5481 10956 5482 10956 5482 10957 5481 10957 4684 10957 5482 10958 4684 10958 5483 10958 5483 10959 4684 10959 5484 10959 5483 10960 5484 10960 5485 10960 5485 10961 5484 10961 5486 10961 5489 10962 5487 10962 5488 10962 5488 10963 5497 10963 5489 10963 5489 10964 5497 10964 5498 10964 5489 10965 5498 10965 4417 10965 5498 10966 5490 10966 4417 10966 4417 10967 5490 10967 5491 10967 4417 10968 5491 10968 5492 10968 5491 10969 5500 10969 5492 10969 5492 10970 5500 10970 5493 10970 5492 10971 5493 10971 5494 10971 5494 10972 5493 10972 5501 10972 5494 10973 5501 10973 4414 10973 5501 10974 5503 10974 4414 10974 4414 10975 5503 10975 5495 10975 4414 10976 5495 10976 4413 10976 3460 10977 4412 10977 5504 10977 5504 10978 4412 10978 4413 10978 5504 10979 4413 10979 5496 10979 5496 10980 4413 10980 5495 10980 5488 10981 3467 10981 5497 10981 5497 10982 3467 10982 5507 10982 5497 10983 5507 10983 5498 10983 5498 10984 5507 10984 5490 10984 5490 10985 5507 10985 5499 10985 5490 10986 5499 10986 5491 10986 5491 10987 5499 10987 5500 10987 5500 10988 5499 10988 5510 10988 5500 10989 5510 10989 5493 10989 5493 10990 5510 10990 5501 10990 5501 10991 5510 10991 5502 10991 5501 10992 5502 10992 5503 10992 5503 10993 5502 10993 5495 10993 5495 10994 5502 10994 5505 10994 5495 10995 5505 10995 5496 10995 5496 10996 5505 10996 5504 10996 5504 10997 5505 10997 5512 10997 5504 10998 5512 10998 3460 10998 3467 10999 4678 10999 5507 10999 5507 11000 4678 11000 5506 11000 5507 11001 5506 11001 5499 11001 5499 11002 5506 11002 5508 11002 5499 11003 5508 11003 5510 11003 5510 11004 5508 11004 5509 11004 5510 11005 5509 11005 5502 11005 5502 11006 5509 11006 5511 11006 5502 11007 5511 11007 5505 11007 5505 11008 5511 11008 4674 11008 5505 11009 4674 11009 5512 11009 5512 11010 4674 11010 3458 11010 5518 11011 3448 11011 5520 11011 5520 11012 3448 11012 5621 11012 5520 11013 5621 11013 5521 11013 5521 11014 5621 11014 5622 11014 5521 11015 5622 11015 5513 11015 5513 11016 5622 11016 5623 11016 5513 11017 5623 11017 5523 11017 5523 11018 5623 11018 5514 11018 5523 11019 5514 11019 5515 11019 5515 11020 5514 11020 5516 11020 5515 11021 5516 11021 5525 11021 5525 11022 5516 11022 5628 11022 5529 11023 3445 11023 3406 11023 3406 11024 3445 11024 5517 11024 3406 11025 5517 11025 3407 11025 3407 11026 5517 11026 3446 11026 3407 11027 3446 11027 5567 11027 5567 11028 3446 11028 5518 11028 5567 11029 5518 11029 5519 11029 5519 11030 5518 11030 5520 11030 5519 11031 5520 11031 5568 11031 5568 11032 5520 11032 5521 11032 5568 11033 5521 11033 5570 11033 5570 11034 5521 11034 5513 11034 5570 11035 5513 11035 5522 11035 5522 11036 5513 11036 5523 11036 5522 11037 5523 11037 5572 11037 5572 11038 5523 11038 5515 11038 5572 11039 5515 11039 5524 11039 5524 11040 5515 11040 5525 11040 5524 11041 5525 11041 3401 11041 3401 11042 5525 11042 5526 11042 3401 11043 5526 11043 5527 11043 5527 11044 5526 11044 3441 11044 5527 11045 3441 11045 5528 11045 5528 11046 3441 11046 3443 11046 5528 11047 3443 11047 5529 11047 5529 11048 3443 11048 3445 11048 5639 11049 5640 11049 5530 11049 5530 11050 5640 11050 5531 11050 5640 11051 5641 11051 5531 11051 5531 11052 5641 11052 5637 11052 5531 11053 5637 11053 5036 11053 5637 11054 5532 11054 5036 11054 5036 11055 5532 11055 5533 11055 5036 11056 5533 11056 5534 11056 5533 11057 5535 11057 5534 11057 5534 11058 5535 11058 5634 11058 5534 11059 5634 11059 5536 11059 5634 11060 5632 11060 5536 11060 5536 11061 5632 11061 5537 11061 5536 11062 5537 11062 5538 11062 3436 11063 5034 11063 5631 11063 5631 11064 5034 11064 5538 11064 5631 11065 5538 11065 5539 11065 5539 11066 5538 11066 5537 11066 3433 11067 3340 11067 5540 11067 5540 11068 3340 11068 5642 11068 5540 11069 5642 11069 5548 11069 5548 11070 5642 11070 5644 11070 5548 11071 5644 11071 5550 11071 5550 11072 5644 11072 5645 11072 5550 11073 5645 11073 5551 11073 5551 11074 5645 11074 5541 11074 5551 11075 5541 11075 5554 11075 5554 11076 5541 11076 5542 11076 5554 11077 5542 11077 5555 11077 5555 11078 5542 11078 3422 11078 5556 11079 3424 11079 5543 11079 5543 11080 3424 11080 3425 11080 5543 11081 3425 11081 5544 11081 5544 11082 3425 11082 3428 11082 5544 11083 3428 11083 5545 11083 5545 11084 3428 11084 3431 11084 5545 11085 3431 11085 3361 11085 3361 11086 3431 11086 3435 11086 3361 11087 3435 11087 5546 11087 5546 11088 3435 11088 3433 11088 5546 11089 3433 11089 5618 11089 5618 11090 3433 11090 5540 11090 5618 11091 5540 11091 5619 11091 5619 11092 5540 11092 5548 11092 5619 11093 5548 11093 5547 11093 5547 11094 5548 11094 5550 11094 5547 11095 5550 11095 5549 11095 5549 11096 5550 11096 5551 11096 5549 11097 5551 11097 5552 11097 5552 11098 5551 11098 5554 11098 5552 11099 5554 11099 5553 11099 5553 11100 5554 11100 5555 11100 5553 11101 5555 11101 5556 11101 5556 11102 5555 11102 3424 11102 3408 11103 4338 11103 5566 11103 5566 11104 4338 11104 4339 11104 5566 11105 4339 11105 5557 11105 5557 11106 4339 11106 5558 11106 5557 11107 5558 11107 5564 11107 5564 11108 5558 11108 4340 11108 5564 11109 4340 11109 5559 11109 5559 11110 4340 11110 4341 11110 5559 11111 4341 11111 5560 11111 5560 11112 4341 11112 4342 11112 5560 11113 4342 11113 5561 11113 5561 11114 4342 11114 4343 11114 5561 11115 3414 11115 5560 11115 5560 11116 3414 11116 5562 11116 5560 11117 5562 11117 5559 11117 5559 11118 5562 11118 5563 11118 5559 11119 5563 11119 5564 11119 5564 11120 5563 11120 5569 11120 5564 11121 5569 11121 5557 11121 5557 11122 5569 11122 5571 11122 5557 11123 5571 11123 5566 11123 5566 11124 5571 11124 5565 11124 5566 11125 5565 11125 3408 11125 3408 11126 5565 11126 3400 11126 3414 11127 5567 11127 5562 11127 5562 11128 5567 11128 5519 11128 5562 11129 5519 11129 5563 11129 5563 11130 5519 11130 5568 11130 5563 11131 5568 11131 5569 11131 5569 11132 5568 11132 5570 11132 5569 11133 5570 11133 5571 11133 5571 11134 5570 11134 5522 11134 5571 11135 5522 11135 5565 11135 5565 11136 5522 11136 5572 11136 5565 11137 5572 11137 3400 11137 3400 11138 5572 11138 5524 11138 5573 11139 4353 11139 5574 11139 5574 11140 4353 11140 4355 11140 5574 11141 4355 11141 5584 11141 5584 11142 4355 11142 4356 11142 5584 11143 4356 11143 5575 11143 5575 11144 4356 11144 4358 11144 5575 11145 4358 11145 5577 11145 5577 11146 4358 11146 5576 11146 5577 11147 5576 11147 5581 11147 5581 11148 5576 11148 4360 11148 5581 11149 4360 11149 5578 11149 5578 11150 4360 11150 5579 11150 5578 11151 5579 11151 3395 11151 3395 11152 5579 11152 4345 11152 3395 11153 5594 11153 5580 11153 3395 11154 5580 11154 5578 11154 5578 11155 5580 11155 5596 11155 5578 11156 5596 11156 5581 11156 5581 11157 5596 11157 5582 11157 5581 11158 5582 11158 5577 11158 5582 11159 5593 11159 5577 11159 5577 11160 5593 11160 5592 11160 5577 11161 5592 11161 5575 11161 5592 11162 5591 11162 5575 11162 5575 11163 5591 11163 5583 11163 5575 11164 5583 11164 5584 11164 5583 11165 5585 11165 5584 11165 5584 11166 5585 11166 5586 11166 5584 11167 5586 11167 5574 11167 5574 11168 5586 11168 5587 11168 5574 11169 5587 11169 5573 11169 3385 11170 5587 11170 5588 11170 5588 11171 5587 11171 5586 11171 5588 11172 5586 11172 5589 11172 5586 11173 5585 11173 5589 11173 5589 11174 5585 11174 5583 11174 5589 11175 5583 11175 5590 11175 5590 11176 5583 11176 5591 11176 5591 11177 5592 11177 5590 11177 5590 11178 5592 11178 5593 11178 5590 11179 5593 11179 5037 11179 5594 11180 5595 11180 5580 11180 5580 11181 5595 11181 5038 11181 5580 11182 5038 11182 5596 11182 5596 11183 5038 11183 5037 11183 5596 11184 5037 11184 5582 11184 5582 11185 5037 11185 5593 11185 3375 11186 5598 11186 5597 11186 5597 11187 5598 11187 5599 11187 5597 11188 5599 11188 5600 11188 5600 11189 5599 11189 4372 11189 5600 11190 4372 11190 5601 11190 5601 11191 4372 11191 5602 11191 5601 11192 5602 11192 5604 11192 5604 11193 5602 11193 5603 11193 5604 11194 5603 11194 5605 11194 5605 11195 5603 11195 5606 11195 5605 11196 5606 11196 5608 11196 5608 11197 5606 11197 4361 11197 5608 11198 4361 11198 3366 11198 3366 11199 4361 11199 4363 11199 3366 11200 3360 11200 5607 11200 3366 11201 5607 11201 5608 11201 5608 11202 5607 11202 5609 11202 5608 11203 5609 11203 5605 11203 5605 11204 5609 11204 5610 11204 5605 11205 5610 11205 5604 11205 5610 11206 5611 11206 5604 11206 5604 11207 5611 11207 5612 11207 5604 11208 5612 11208 5601 11208 5612 11209 5617 11209 5601 11209 5601 11210 5617 11210 5613 11210 5601 11211 5613 11211 5600 11211 5613 11212 5614 11212 5600 11212 5600 11213 5614 11213 5616 11213 5600 11214 5616 11214 5597 11214 5597 11215 5616 11215 5615 11215 5597 11216 5615 11216 3375 11216 5553 11217 5615 11217 5552 11217 5552 11218 5615 11218 5616 11218 5552 11219 5616 11219 5549 11219 5616 11220 5614 11220 5549 11220 5549 11221 5614 11221 5613 11221 5549 11222 5613 11222 5547 11222 5547 11223 5613 11223 5617 11223 5617 11224 5612 11224 5547 11224 5547 11225 5612 11225 5611 11225 5547 11226 5611 11226 5619 11226 3360 11227 5546 11227 5607 11227 5607 11228 5546 11228 5618 11228 5607 11229 5618 11229 5609 11229 5609 11230 5618 11230 5619 11230 5609 11231 5619 11231 5610 11231 5610 11232 5619 11232 5611 11232 3448 11233 5620 11233 5621 11233 5621 11234 5620 11234 4790 11234 5621 11235 4790 11235 5622 11235 5622 11236 4790 11236 5624 11236 5622 11237 5624 11237 5623 11237 5623 11238 5624 11238 5625 11238 5623 11239 5625 11239 5514 11239 5514 11240 5625 11240 5626 11240 5514 11241 5626 11241 5516 11241 5516 11242 5626 11242 5627 11242 5516 11243 5627 11243 5628 11243 5628 11244 5627 11244 5629 11244 5630 11245 4651 11245 3436 11245 3436 11246 5631 11246 5630 11246 5630 11247 5631 11247 5539 11247 5630 11248 5539 11248 4650 11248 5539 11249 5537 11249 4650 11249 4650 11250 5537 11250 5632 11250 4650 11251 5632 11251 5633 11251 5632 11252 5634 11252 5633 11252 5633 11253 5634 11253 5535 11253 5633 11254 5535 11254 5635 11254 5635 11255 5535 11255 5533 11255 5635 11256 5533 11256 5636 11256 5533 11257 5532 11257 5636 11257 5636 11258 5532 11258 5637 11258 5636 11259 5637 11259 5638 11259 5639 11260 4804 11260 5640 11260 5640 11261 4804 11261 5638 11261 5640 11262 5638 11262 5641 11262 5641 11263 5638 11263 5637 11263 3340 11264 5643 11264 5642 11264 5642 11265 5643 11265 4665 11265 5642 11266 4665 11266 5644 11266 5644 11267 4665 11267 4664 11267 5644 11268 4664 11268 5645 11268 5645 11269 4664 11269 5646 11269 5645 11270 5646 11270 5541 11270 5541 11271 5646 11271 5647 11271 5541 11272 5647 11272 5542 11272 5542 11273 5647 11273 4663 11273 5542 11274 4663 11274 3422 11274 3422 11275 4663 11275 4982 11275 5659 11276 4293 11276 5658 11276 5658 11277 4293 11277 4294 11277 5658 11278 4294 11278 5648 11278 5648 11279 4294 11279 4296 11279 5648 11280 4296 11280 5657 11280 5657 11281 4296 11281 4297 11281 5657 11282 4297 11282 5649 11282 5649 11283 4297 11283 5650 11283 5649 11284 5650 11284 5652 11284 5652 11285 5650 11285 5651 11285 5652 11286 5651 11286 5653 11286 5653 11287 5651 11287 3333 11287 5653 11288 5654 11288 5652 11288 5652 11289 5654 11289 5655 11289 5652 11290 5655 11290 5649 11290 5649 11291 5655 11291 5656 11291 5649 11292 5656 11292 5657 11292 5657 11293 5656 11293 5663 11293 5657 11294 5663 11294 5648 11294 5648 11295 5663 11295 5664 11295 5648 11296 5664 11296 5658 11296 5658 11297 5664 11297 5660 11297 5658 11298 5660 11298 5659 11298 5659 11299 5660 11299 3326 11299 5654 11300 4793 11300 5655 11300 5655 11301 4793 11301 5661 11301 5655 11302 5661 11302 5656 11302 5656 11303 5661 11303 5662 11303 5656 11304 5662 11304 5663 11304 5663 11305 5662 11305 4785 11305 5663 11306 4785 11306 5664 11306 5664 11307 4785 11307 4787 11307 5664 11308 4787 11308 5660 11308 5660 11309 4787 11309 5665 11309 5660 11310 5665 11310 3326 11310 3326 11311 5665 11311 4780 11311 3299 11312 5666 11312 5675 11312 5675 11313 5666 11313 5667 11313 5675 11314 5667 11314 5668 11314 5668 11315 5667 11315 5670 11315 5668 11316 5670 11316 5669 11316 5669 11317 5670 11317 5671 11317 5669 11318 5671 11318 5672 11318 5672 11319 5671 11319 4310 11319 5672 11320 4310 11320 5674 11320 5674 11321 4310 11321 5673 11321 5674 11322 5673 11322 3311 11322 3311 11323 5673 11323 4312 11323 3311 11324 5677 11324 5674 11324 5674 11325 5677 11325 5678 11325 5674 11326 5678 11326 5672 11326 5672 11327 5678 11327 5679 11327 5672 11328 5679 11328 5669 11328 5669 11329 5679 11329 5680 11329 5669 11330 5680 11330 5668 11330 5668 11331 5680 11331 5676 11331 5668 11332 5676 11332 5675 11332 5675 11333 5676 11333 5682 11333 5675 11334 5682 11334 3299 11334 3299 11335 5682 11335 5683 11335 5677 11336 4801 11336 5678 11336 5678 11337 4801 11337 4800 11337 5678 11338 4800 11338 5679 11338 5679 11339 4800 11339 4798 11339 5679 11340 4798 11340 5680 11340 5680 11341 4798 11341 5681 11341 5680 11342 5681 11342 5676 11342 5676 11343 5681 11343 4795 11343 5676 11344 4795 11344 5682 11344 5682 11345 4795 11345 5684 11345 5682 11346 5684 11346 5683 11346 5683 11347 5684 11347 3295 11347 5699 11348 4315 11348 5698 11348 5698 11349 4315 11349 5685 11349 5698 11350 5685 11350 5695 11350 5695 11351 5685 11351 4316 11351 5695 11352 4316 11352 5694 11352 5694 11353 4316 11353 5686 11353 5694 11354 5686 11354 5691 11354 5691 11355 5686 11355 5687 11355 5691 11356 5687 11356 5689 11356 5689 11357 5687 11357 4318 11357 5689 11358 4318 11358 5688 11358 5688 11359 4318 11359 4319 11359 5688 11360 5690 11360 5689 11360 5689 11361 5690 11361 5692 11361 5689 11362 5692 11362 5691 11362 5691 11363 5692 11363 5693 11363 5691 11364 5693 11364 5694 11364 5694 11365 5693 11365 5696 11365 5694 11366 5696 11366 5695 11366 5695 11367 5696 11367 5697 11367 5695 11368 5697 11368 5698 11368 5698 11369 5697 11369 5703 11369 5698 11370 5703 11370 5699 11370 5699 11371 5703 11371 5705 11371 5690 11372 4657 11372 5692 11372 5692 11373 4657 11373 5700 11373 5692 11374 5700 11374 5693 11374 5693 11375 5700 11375 5701 11375 5693 11376 5701 11376 5696 11376 5696 11377 5701 11377 5702 11377 5696 11378 5702 11378 5697 11378 5697 11379 5702 11379 4653 11379 5697 11380 4653 11380 5703 11380 5703 11381 4653 11381 5704 11381 5703 11382 5704 11382 5705 11382 5705 11383 5704 11383 3276 11383 3262 11384 5706 11384 5707 11384 5707 11385 5706 11385 5708 11385 5707 11386 5708 11386 4330 11386 4330 11387 5708 11387 5709 11387 5709 11388 5710 11388 4330 11388 4330 11389 5710 11389 5718 11389 4330 11390 5718 11390 5711 11390 5718 11391 5719 11391 5711 11391 5711 11392 5719 11392 5717 11392 5711 11393 5717 11393 4328 11393 5712 11394 5713 11394 5715 11394 5715 11395 5713 11395 5714 11395 5715 11396 5714 11396 5721 11396 5721 11397 5714 11397 4328 11397 5721 11398 4328 11398 5716 11398 5716 11399 4328 11399 5717 11399 5706 11400 3256 11400 5723 11400 5706 11401 5723 11401 5708 11401 5708 11402 5723 11402 5724 11402 5708 11403 5724 11403 5709 11403 5709 11404 5724 11404 5710 11404 5710 11405 5724 11405 5726 11405 5710 11406 5726 11406 5718 11406 5718 11407 5726 11407 5719 11407 5719 11408 5726 11408 5720 11408 5719 11409 5720 11409 5717 11409 5717 11410 5720 11410 5716 11410 5716 11411 5720 11411 5728 11411 5716 11412 5728 11412 5721 11412 5721 11413 5728 11413 5722 11413 5721 11414 5722 11414 5715 11414 5715 11415 5722 11415 3257 11415 5715 11416 3257 11416 5712 11416 3256 11417 4941 11417 5723 11417 5723 11418 4941 11418 4940 11418 5723 11419 4940 11419 5724 11419 5724 11420 4940 11420 5725 11420 5724 11421 5725 11421 5726 11421 5726 11422 5725 11422 4943 11422 5726 11423 4943 11423 5720 11423 5720 11424 4943 11424 5727 11424 5720 11425 5727 11425 5728 11425 5728 11426 5727 11426 5729 11426 5728 11427 5729 11427 5722 11427 5722 11428 5729 11428 5730 11428 5722 11429 5730 11429 3257 11429 3257 11430 5730 11430 3252 11430 3250 11431 3173 11431 5731 11431 5731 11432 3173 11432 5732 11432 5731 11433 5732 11433 5733 11433 5733 11434 5732 11434 5734 11434 5733 11435 5734 11435 5735 11435 5735 11436 5734 11436 5736 11436 5735 11437 5736 11437 5740 11437 5740 11438 5736 11438 5854 11438 5740 11439 5854 11439 5741 11439 5741 11440 5854 11440 5855 11440 5741 11441 5855 11441 5737 11441 5737 11442 5855 11442 5857 11442 5737 11443 5857 11443 5744 11443 5744 11444 5857 11444 3168 11444 5804 11445 5735 11445 5738 11445 5738 11446 5735 11446 5740 11446 5738 11447 5740 11447 5739 11447 5739 11448 5740 11448 5741 11448 5739 11449 5741 11449 5742 11449 5742 11450 5741 11450 5737 11450 5742 11451 5737 11451 5743 11451 5743 11452 5737 11452 5744 11452 5743 11453 5744 11453 3208 11453 3208 11454 5744 11454 5745 11454 3208 11455 5745 11455 3210 11455 3210 11456 5745 11456 5746 11456 3210 11457 5746 11457 5747 11457 5747 11458 5746 11458 3244 11458 5747 11459 3244 11459 3212 11459 3212 11460 3244 11460 3247 11460 3212 11461 3247 11461 3213 11461 3213 11462 3247 11462 3248 11462 3213 11463 3248 11463 5802 11463 5802 11464 3248 11464 3250 11464 5802 11465 3250 11465 5748 11465 5748 11466 3250 11466 5731 11466 5748 11467 5731 11467 5749 11467 5749 11468 5731 11468 5733 11468 5749 11469 5733 11469 5804 11469 5804 11470 5733 11470 5735 11470 3242 11471 5750 11471 5751 11471 5751 11472 5750 11472 5860 11472 5751 11473 5860 11473 5753 11473 5753 11474 5860 11474 5752 11474 5753 11475 5752 11475 5754 11475 5754 11476 5752 11476 5863 11476 5754 11477 5863 11477 5755 11477 5755 11478 5863 11478 5756 11478 5755 11479 5756 11479 5757 11479 5757 11480 5756 11480 5865 11480 5757 11481 5865 11481 5763 11481 5763 11482 5865 11482 5759 11482 5763 11483 5759 11483 5758 11483 5758 11484 5759 11484 3163 11484 5821 11485 5751 11485 5760 11485 5760 11486 5751 11486 5753 11486 5760 11487 5753 11487 5761 11487 5761 11488 5753 11488 5754 11488 5761 11489 5754 11489 5762 11489 5762 11490 5754 11490 5755 11490 5762 11491 5755 11491 5824 11491 5824 11492 5755 11492 5757 11492 5824 11493 5757 11493 5827 11493 5827 11494 5757 11494 5763 11494 5827 11495 5763 11495 5764 11495 5764 11496 5763 11496 5758 11496 5764 11497 5758 11497 3192 11497 3192 11498 5758 11498 3238 11498 3192 11499 3238 11499 5765 11499 5765 11500 3238 11500 5766 11500 5765 11501 5766 11501 3195 11501 3195 11502 5766 11502 5768 11502 3195 11503 5768 11503 5767 11503 5767 11504 5768 11504 5769 11504 5767 11505 5769 11505 5770 11505 5770 11506 5769 11506 5771 11506 5770 11507 5771 11507 5819 11507 5819 11508 5771 11508 3242 11508 5819 11509 3242 11509 5821 11509 5821 11510 3242 11510 5751 11510 3235 11511 3155 11511 5772 11511 5772 11512 3155 11512 5867 11512 5772 11513 5867 11513 5773 11513 5773 11514 5867 11514 5868 11514 5773 11515 5868 11515 5777 11515 5777 11516 5868 11516 5774 11516 5777 11517 5774 11517 5787 11517 5787 11518 5774 11518 5775 11518 5787 11519 5775 11519 5786 11519 5786 11520 5775 11520 5871 11520 5786 11521 5871 11521 5776 11521 5776 11522 5871 11522 3160 11522 5849 11523 5848 11523 5777 11523 5777 11524 5848 11524 5846 11524 5777 11525 5846 11525 5773 11525 5773 11526 5846 11526 5778 11526 5773 11527 5778 11527 5772 11527 5772 11528 5778 11528 5844 11528 5772 11529 5844 11529 3235 11529 3235 11530 5844 11530 5779 11530 3235 11531 5779 11531 3236 11531 3236 11532 5779 11532 5780 11532 3236 11533 5780 11533 3234 11533 3234 11534 5780 11534 5781 11534 3234 11535 5781 11535 3230 11535 3230 11536 5781 11536 5782 11536 3230 11537 5782 11537 5783 11537 5783 11538 5782 11538 5784 11538 5783 11539 5784 11539 3226 11539 3226 11540 5784 11540 3175 11540 3226 11541 3175 11541 5776 11541 5776 11542 3175 11542 5785 11542 5776 11543 5785 11543 5786 11543 5786 11544 5785 11544 5850 11544 5786 11545 5850 11545 5787 11545 5787 11546 5850 11546 5849 11546 5787 11547 5849 11547 5777 11547 3225 11548 5788 11548 5789 11548 5789 11549 5788 11549 4512 11549 5789 11550 4512 11550 5801 11550 5801 11551 4512 11551 4513 11551 5801 11552 4513 11552 5790 11552 5790 11553 4513 11553 4514 11553 5790 11554 4514 11554 5799 11554 5799 11555 4514 11555 5791 11555 5799 11556 5791 11556 5792 11556 5792 11557 5791 11557 5794 11557 5792 11558 5794 11558 5793 11558 5793 11559 5794 11559 4517 11559 5793 11560 4517 11560 5795 11560 5795 11561 4517 11561 4518 11561 5795 11562 5796 11562 5793 11562 5793 11563 5796 11563 5797 11563 5793 11564 5797 11564 5792 11564 5792 11565 5797 11565 5798 11565 5792 11566 5798 11566 5799 11566 5799 11567 5798 11567 5803 11567 5799 11568 5803 11568 5790 11568 5790 11569 5803 11569 5800 11569 5790 11570 5800 11570 5801 11570 5801 11571 5800 11571 5805 11571 5801 11572 5805 11572 5789 11572 5789 11573 5805 11573 5806 11573 5789 11574 5806 11574 3225 11574 3225 11575 5806 11575 3214 11575 5796 11576 5802 11576 5797 11576 5797 11577 5802 11577 5748 11577 5797 11578 5748 11578 5798 11578 5798 11579 5748 11579 5749 11579 5798 11580 5749 11580 5803 11580 5803 11581 5749 11581 5804 11581 5803 11582 5804 11582 5800 11582 5800 11583 5804 11583 5738 11583 5800 11584 5738 11584 5805 11584 5805 11585 5738 11585 5739 11585 5805 11586 5739 11586 5806 11586 5806 11587 5739 11587 5742 11587 5806 11588 5742 11588 3214 11588 3214 11589 5742 11589 5743 11589 3206 11590 4532 11590 5807 11590 5807 11591 4532 11591 4533 11591 5807 11592 4533 11592 5818 11592 5818 11593 4533 11593 5808 11593 5818 11594 5808 11594 5817 11594 5817 11595 5808 11595 5809 11595 5817 11596 5809 11596 5814 11596 5814 11597 5809 11597 4535 11597 5814 11598 4535 11598 5810 11598 5810 11599 4535 11599 4536 11599 5810 11600 4536 11600 5813 11600 5813 11601 4536 11601 4526 11601 5813 11602 4526 11602 5812 11602 5812 11603 4526 11603 5811 11603 5812 11604 3197 11604 5813 11604 5813 11605 3197 11605 5820 11605 5813 11606 5820 11606 5810 11606 5810 11607 5820 11607 5815 11607 5810 11608 5815 11608 5814 11608 5814 11609 5815 11609 5816 11609 5814 11610 5816 11610 5817 11610 5817 11611 5816 11611 5822 11611 5817 11612 5822 11612 5818 11612 5818 11613 5822 11613 5823 11613 5818 11614 5823 11614 5807 11614 5807 11615 5823 11615 5825 11615 5807 11616 5825 11616 3206 11616 3206 11617 5825 11617 5826 11617 3197 11618 5819 11618 5820 11618 5820 11619 5819 11619 5821 11619 5820 11620 5821 11620 5815 11620 5815 11621 5821 11621 5760 11621 5815 11622 5760 11622 5816 11622 5816 11623 5760 11623 5761 11623 5816 11624 5761 11624 5822 11624 5822 11625 5761 11625 5762 11625 5822 11626 5762 11626 5823 11626 5823 11627 5762 11627 5824 11627 5823 11628 5824 11628 5825 11628 5825 11629 5824 11629 5827 11629 5825 11630 5827 11630 5826 11630 5826 11631 5827 11631 5764 11631 3179 11632 4551 11632 5829 11632 5829 11633 4551 11633 5828 11633 5829 11634 5828 11634 5830 11634 5830 11635 5828 11635 5832 11635 5830 11636 5832 11636 5831 11636 5831 11637 5832 11637 5833 11637 5831 11638 5833 11638 5841 11638 5841 11639 5833 11639 5834 11639 5841 11640 5834 11640 5839 11640 5839 11641 5834 11641 5835 11641 5839 11642 5835 11642 5836 11642 5836 11643 5835 11643 4541 11643 5836 11644 4541 11644 3184 11644 3184 11645 4541 11645 4542 11645 3184 11646 5837 11646 5836 11646 5836 11647 5837 11647 5838 11647 5836 11648 5838 11648 5839 11648 5839 11649 5838 11649 5840 11649 5839 11650 5840 11650 5841 11650 5841 11651 5840 11651 5845 11651 5841 11652 5845 11652 5831 11652 5831 11653 5845 11653 5847 11653 5831 11654 5847 11654 5830 11654 5830 11655 5847 11655 5842 11655 5830 11656 5842 11656 5829 11656 5829 11657 5842 11657 5843 11657 5829 11658 5843 11658 3179 11658 3179 11659 5843 11659 3180 11659 5837 11660 5779 11660 5838 11660 5838 11661 5779 11661 5844 11661 5838 11662 5844 11662 5840 11662 5840 11663 5844 11663 5778 11663 5840 11664 5778 11664 5845 11664 5845 11665 5778 11665 5846 11665 5845 11666 5846 11666 5847 11666 5847 11667 5846 11667 5848 11667 5847 11668 5848 11668 5842 11668 5842 11669 5848 11669 5849 11669 5842 11670 5849 11670 5843 11670 5843 11671 5849 11671 5850 11671 5843 11672 5850 11672 3180 11672 3180 11673 5850 11673 5785 11673 3173 11674 5851 11674 5732 11674 5732 11675 5851 11675 5852 11675 5732 11676 5852 11676 5734 11676 5734 11677 5852 11677 5853 11677 5734 11678 5853 11678 5736 11678 5736 11679 5853 11679 4852 11679 5736 11680 4852 11680 5854 11680 5854 11681 4852 11681 4851 11681 5854 11682 4851 11682 5855 11682 5855 11683 4851 11683 5856 11683 5855 11684 5856 11684 5857 11684 5857 11685 5856 11685 5858 11685 5857 11686 5858 11686 3168 11686 3168 11687 5858 11687 5859 11687 5750 11688 5861 11688 5860 11688 5860 11689 5861 11689 5008 11689 5860 11690 5008 11690 5752 11690 5752 11691 5008 11691 5862 11691 5752 11692 5862 11692 5863 11692 5863 11693 5862 11693 5864 11693 5863 11694 5864 11694 5756 11694 5756 11695 5864 11695 4827 11695 5756 11696 4827 11696 5865 11696 5865 11697 4827 11697 4830 11697 5865 11698 4830 11698 5759 11698 5759 11699 4830 11699 5866 11699 5759 11700 5866 11700 3163 11700 3163 11701 5866 11701 4832 11701 3155 11702 3154 11702 5867 11702 5867 11703 3154 11703 5869 11703 5867 11704 5869 11704 5868 11704 5868 11705 5869 11705 4805 11705 5868 11706 4805 11706 5774 11706 5774 11707 4805 11707 5870 11707 5774 11708 5870 11708 5775 11708 5775 11709 5870 11709 5872 11709 5775 11710 5872 11710 5871 11710 5871 11711 5872 11711 4814 11711 5871 11712 4814 11712 3160 11712 3160 11713 4814 11713 3161 11713 3150 11714 5882 11714 5873 11714 5873 11715 5882 11715 5883 11715 5873 11716 5883 11716 5874 11716 5874 11717 5883 11717 5884 11717 5884 11718 5885 11718 5874 11718 5874 11719 5885 11719 5887 11719 5874 11720 5887 11720 5875 11720 5887 11721 5876 11721 5875 11721 5875 11722 5876 11722 5889 11722 5875 11723 5889 11723 5879 11723 5894 11724 4466 11724 5892 11724 5892 11725 4466 11725 5877 11725 5892 11726 5877 11726 5890 11726 5890 11727 5877 11727 5879 11727 5890 11728 5879 11728 5878 11728 5878 11729 5879 11729 5889 11729 5882 11730 5880 11730 5881 11730 5882 11731 5881 11731 5883 11731 5883 11732 5881 11732 5896 11732 5883 11733 5896 11733 5884 11733 5884 11734 5896 11734 5885 11734 5885 11735 5896 11735 5886 11735 5885 11736 5886 11736 5887 11736 5887 11737 5886 11737 5876 11737 5876 11738 5886 11738 5888 11738 5876 11739 5888 11739 5889 11739 5889 11740 5888 11740 5878 11740 5878 11741 5888 11741 5891 11741 5878 11742 5891 11742 5890 11742 5890 11743 5891 11743 5899 11743 5890 11744 5899 11744 5892 11744 5892 11745 5899 11745 5893 11745 5892 11746 5893 11746 5894 11746 5880 11747 3143 11747 5881 11747 5881 11748 3143 11748 5895 11748 5881 11749 5895 11749 5896 11749 5896 11750 5895 11750 4846 11750 5896 11751 4846 11751 5886 11751 5886 11752 4846 11752 5897 11752 5886 11753 5897 11753 5888 11753 5888 11754 5897 11754 5898 11754 5888 11755 5898 11755 5891 11755 5891 11756 5898 11756 4844 11756 5891 11757 4844 11757 5899 11757 5899 11758 4844 11758 5900 11758 5899 11759 5900 11759 5893 11759 5893 11760 5900 11760 4843 11760 5901 11761 4479 11761 3130 11761 3130 11762 5911 11762 5901 11762 5901 11763 5911 11763 5902 11763 5901 11764 5902 11764 4477 11764 5902 11765 5903 11765 4477 11765 4477 11766 5903 11766 5914 11766 4477 11767 5914 11767 5904 11767 5914 11768 5915 11768 5904 11768 5904 11769 5915 11769 5905 11769 5904 11770 5905 11770 4474 11770 4474 11771 5905 11771 5906 11771 4474 11772 5906 11772 5908 11772 5906 11773 5907 11773 5908 11773 5908 11774 5907 11774 5918 11774 5908 11775 5918 11775 5910 11775 5920 11776 4488 11776 5909 11776 5909 11777 4488 11777 5910 11777 5909 11778 5910 11778 5919 11778 5919 11779 5910 11779 5918 11779 3130 11780 3129 11780 5911 11780 5911 11781 3129 11781 5912 11781 5911 11782 5912 11782 5902 11782 5902 11783 5912 11783 5903 11783 5903 11784 5912 11784 5913 11784 5903 11785 5913 11785 5914 11785 5914 11786 5913 11786 5915 11786 5915 11787 5913 11787 5916 11787 5915 11788 5916 11788 5905 11788 5905 11789 5916 11789 5906 11789 5906 11790 5916 11790 5917 11790 5906 11791 5917 11791 5907 11791 5907 11792 5917 11792 5918 11792 5918 11793 5917 11793 5922 11793 5918 11794 5922 11794 5919 11794 5919 11795 5922 11795 5909 11795 5909 11796 5922 11796 3120 11796 5909 11797 3120 11797 5920 11797 3129 11798 4828 11798 5912 11798 5912 11799 4828 11799 4826 11799 5912 11800 4826 11800 5913 11800 5913 11801 4826 11801 4825 11801 5913 11802 4825 11802 5916 11802 5916 11803 4825 11803 4824 11803 5916 11804 4824 11804 5917 11804 5917 11805 4824 11805 5921 11805 5917 11806 5921 11806 5922 11806 5922 11807 5921 11807 5923 11807 5922 11808 5923 11808 3120 11808 3120 11809 5923 11809 5924 11809 5937 11810 3114 11810 5925 11810 5925 11811 3114 11811 4496 11811 5925 11812 4496 11812 5926 11812 5926 11813 4496 11813 4497 11813 5926 11814 4497 11814 5927 11814 5927 11815 4497 11815 5928 11815 5927 11816 5928 11816 5929 11816 5929 11817 5928 11817 4500 11817 5929 11818 4500 11818 5932 11818 5932 11819 4500 11819 5931 11819 5932 11820 5931 11820 5930 11820 5930 11821 5931 11821 4501 11821 5930 11822 4501 11822 3106 11822 3106 11823 4501 11823 4489 11823 3106 11824 5938 11824 5930 11824 5930 11825 5938 11825 5933 11825 5930 11826 5933 11826 5932 11826 5932 11827 5933 11827 5939 11827 5932 11828 5939 11828 5929 11828 5929 11829 5939 11829 5942 11829 5929 11830 5942 11830 5927 11830 5927 11831 5942 11831 5934 11831 5927 11832 5934 11832 5926 11832 5926 11833 5934 11833 5935 11833 5926 11834 5935 11834 5925 11834 5925 11835 5935 11835 5936 11835 5925 11836 5936 11836 5937 11836 5937 11837 5936 11837 5944 11837 5938 11838 5016 11838 5933 11838 5933 11839 5016 11839 5940 11839 5933 11840 5940 11840 5939 11840 5939 11841 5940 11841 5941 11841 5939 11842 5941 11842 5942 11842 5942 11843 5941 11843 4837 11843 5942 11844 4837 11844 5934 11844 5934 11845 4837 11845 4842 11845 5934 11846 4842 11846 5935 11846 5935 11847 4842 11847 5943 11847 5935 11848 5943 11848 5936 11848 5936 11849 5943 11849 4840 11849 5936 11850 4840 11850 5944 11850 5944 11851 4840 11851 5945 11851 5946 11852 4502 11852 3087 11852 3087 11853 5953 11853 5946 11853 5946 11854 5953 11854 5947 11854 5946 11855 5947 11855 4510 11855 5947 11856 5954 11856 4510 11856 4510 11857 5954 11857 5948 11857 4510 11858 5948 11858 5949 11858 5948 11859 5956 11859 5949 11859 5949 11860 5956 11860 5950 11860 5949 11861 5950 11861 4508 11861 4508 11862 5950 11862 5958 11862 4508 11863 5958 11863 4507 11863 5958 11864 5951 11864 4507 11864 4507 11865 5951 11865 5960 11865 4507 11866 5960 11866 4506 11866 3096 11867 4505 11867 5952 11867 5952 11868 4505 11868 4506 11868 5952 11869 4506 11869 5961 11869 5961 11870 4506 11870 5960 11870 3087 11871 3086 11871 5953 11871 5953 11872 3086 11872 5963 11872 5953 11873 5963 11873 5947 11873 5947 11874 5963 11874 5954 11874 5954 11875 5963 11875 5955 11875 5954 11876 5955 11876 5948 11876 5948 11877 5955 11877 5956 11877 5956 11878 5955 11878 5957 11878 5956 11879 5957 11879 5950 11879 5950 11880 5957 11880 5958 11880 5958 11881 5957 11881 5966 11881 5958 11882 5966 11882 5951 11882 5951 11883 5966 11883 5960 11883 5960 11884 5966 11884 5959 11884 5960 11885 5959 11885 5961 11885 5961 11886 5959 11886 5952 11886 5952 11887 5959 11887 3079 11887 5952 11888 3079 11888 3096 11888 3086 11889 5962 11889 5963 11889 5963 11890 5962 11890 5964 11890 5963 11891 5964 11891 5955 11891 5955 11892 5964 11892 5965 11892 5955 11893 5965 11893 5957 11893 5957 11894 5965 11894 4808 11894 5957 11895 4808 11895 5966 11895 5966 11896 4808 11896 4809 11896 5966 11897 4809 11897 5959 11897 5959 11898 4809 11898 5967 11898 5959 11899 5967 11899 3079 11899 3079 11900 5967 11900 5968 11900 4848 11901 5969 11901 5973 11901 4956 11902 5970 11902 5975 11902 5975 11903 5970 11903 5972 11903 5975 11904 5972 11904 5971 11904 5971 11905 5972 11905 4847 11905 5971 11906 4847 11906 5973 11906 5973 11907 4847 11907 4850 11907 5973 11908 4850 11908 4848 11908 4956 11909 5975 11909 5974 11909 5974 11910 5975 11910 5977 11910 5974 11911 5977 11911 5978 11911 5976 11912 4834 11912 5979 11912 5979 11913 4834 11913 4833 11913 5979 11914 4833 11914 5977 11914 5977 11915 4833 11915 4823 11915 5977 11916 4823 11916 5978 11916 5976 11917 5979 11917 4835 11917 4835 11918 5979 11918 5055 11918 4835 11919 5055 11919 5980 11919 5054 11920 4949 11920 4947 11920 5054 11921 4947 11921 5055 11921 5055 11922 4947 11922 5981 11922 5055 11923 5981 11923 5980 11923 4640 11924 4668 11924 5049 11924 5049 11925 4668 11925 5982 11925 5049 11926 5982 11926 5983 11926 5983 11927 5982 11927 5985 11927 5983 11928 5985 11928 5984 11928 5984 11929 5985 11929 4818 11929 5984 11930 4818 11930 5052 11930 5052 11931 4818 11931 4820 11931 5052 11932 4820 11932 5054 11932 5054 11933 4820 11933 5986 11933 5054 11934 5986 11934 4949 11934 4640 11935 5049 11935 4936 11935 4936 11936 5049 11936 5987 11936 4936 11937 5987 11937 4937 11937 5988 11938 5992 11938 5987 11938 5987 11939 5992 11939 5989 11939 5987 11940 5989 11940 4937 11940 5990 11941 4660 11941 5994 11941 5994 11942 4660 11942 4656 11942 5994 11943 4656 11943 5988 11943 5988 11944 4656 11944 5991 11944 5988 11945 5991 11945 5992 11945 4799 11946 5993 11946 5045 11946 5045 11947 5993 11947 5995 11947 5045 11948 5995 11948 5994 11948 5994 11949 5995 11949 4659 11949 5994 11950 4659 11950 5990 11950 4778 11951 4926 11951 5998 11951 5998 11952 4926 11952 5996 11952 5998 11953 5996 11953 5045 11953 5045 11954 5996 11954 5997 11954 5045 11955 5997 11955 4799 11955 4778 11956 5998 11956 5999 11956 5999 11957 5998 11957 5043 11957 5999 11958 5043 11958 6000 11958 6000 11959 5043 11959 4791 11959 4791 11960 5043 11960 6001 11960 4791 11961 6001 11961 4789 11961 4789 11962 6001 11962 3899 11962 4789 11963 3899 11963 4920 11963 3040 11964 5074 11964 5073 11964 3040 11965 5073 11965 4177 11965 4177 11966 5073 11966 6002 11966 4177 11967 6002 11967 6003 11967 6003 11968 6002 11968 5071 11968 6003 11969 5071 11969 4178 11969 4178 11970 5071 11970 6005 11970 4178 11971 6005 11971 6004 11971 6004 11972 6005 11972 5069 11972 6004 11973 5069 11973 6006 11973 6006 11974 5069 11974 6008 11974 6006 11975 6008 11975 6007 11975 6007 11976 6008 11976 5067 11976 6007 11977 5067 11977 4181 11977 4181 11978 5067 11978 5066 11978 4181 11979 5066 11979 4183 11979 4183 11980 5066 11980 5064 11980 4183 11981 5064 11981 6009 11981 6009 11982 5064 11982 6010 11982 6009 11983 6010 11983 6011 11983 6011 11984 6010 11984 6012 11984 6011 11985 6012 11985 4187 11985 4187 11986 6012 11986 5063 11986 4187 11987 5063 11987 4188 11987 4188 11988 5063 11988 6014 11988 4188 11989 6014 11989 6013 11989 6013 11990 6014 11990 5062 11990 6013 11991 5062 11991 6015 11991 6015 11992 5062 11992 5059 11992 6015 11993 5059 11993 6016 11993 6016 11994 5059 11994 3024 11994 6016 11995 3024 11995 3026 11995 3965 11996 6017 11996 4562 11996 4562 11997 6017 11997 6018 11997 4562 11998 6018 11998 4563 11998 4563 11999 6018 11999 6019 11999 6019 12000 6018 12000 6020 12000 6019 12001 6020 12001 4561 12001 4561 12002 6020 12002 6021 12002 6021 12003 6020 12003 6023 12003 6021 12004 6023 12004 6022 12004 6022 12005 6023 12005 4559 12005 4559 12006 6023 12006 6024 12006 4559 12007 6024 12007 4557 12007 4557 12008 6024 12008 6025 12008 6025 12009 6024 12009 6026 12009 6025 12010 6026 12010 4555 12010 4555 12011 6026 12011 6027 12011 6027 12012 6026 12012 4931 12012 6027 12013 4931 12013 4554 12013 4564 12014 4927 12014 6028 12014 6028 12015 4927 12015 6029 12015 6028 12016 6029 12016 6030 12016 6030 12017 6029 12017 4922 12017 6030 12018 4922 12018 6031 12018 6031 12019 4922 12019 4924 12019 6031 12020 4924 12020 4567 12020 4567 12021 4924 12021 6032 12021 4567 12022 6032 12022 6033 12022 6033 12023 6032 12023 4925 12023 6033 12024 4925 12024 6034 12024 6034 12025 4925 12025 3009 12025 4577 12026 4959 12026 6035 12026 6035 12027 4959 12027 6037 12027 6035 12028 6037 12028 6036 12028 6036 12029 6037 12029 6039 12029 6039 12030 6037 12030 6038 12030 6039 12031 6038 12031 4574 12031 4574 12032 6038 12032 4576 12032 4576 12033 6038 12033 6040 12033 4576 12034 6040 12034 6041 12034 6041 12035 6040 12035 4573 12035 4573 12036 6040 12036 6043 12036 4573 12037 6043 12037 6042 12037 6042 12038 6043 12038 4572 12038 4572 12039 6043 12039 6044 12039 4572 12040 6044 12040 6045 12040 6045 12041 6044 12041 4569 12041 4569 12042 6044 12042 6046 12042 4569 12043 6046 12043 3950 12043 2996 12044 6048 12044 6047 12044 6047 12045 6048 12045 6049 12045 6047 12046 6049 12046 6050 12046 6050 12047 6049 12047 6051 12047 6051 12048 6049 12048 6052 12048 6051 12049 6052 12049 4587 12049 4587 12050 6052 12050 6053 12050 6053 12051 6052 12051 6055 12051 6053 12052 6055 12052 6054 12052 6054 12053 6055 12053 4586 12053 4586 12054 6055 12054 6056 12054 4586 12055 6056 12055 4582 12055 4582 12056 6056 12056 4583 12056 4583 12057 6056 12057 6058 12057 4583 12058 6058 12058 6057 12058 6057 12059 6058 12059 6059 12059 6059 12060 6058 12060 6060 12060 6059 12061 6060 12061 2989 12061 6061 12062 2988 12062 4599 12062 4599 12063 2988 12063 6062 12063 4599 12064 6062 12064 6063 12064 6063 12065 6062 12065 6064 12065 6064 12066 6062 12066 4855 12066 6064 12067 4855 12067 4597 12067 4597 12068 4855 12068 6065 12068 6065 12069 4855 12069 6067 12069 6065 12070 6067 12070 4595 12070 4595 12071 6067 12071 6066 12071 6066 12072 6067 12072 6068 12072 6066 12073 6068 12073 6069 12073 6069 12074 6068 12074 4593 12074 4593 12075 6068 12075 4854 12075 4593 12076 4854 12076 4594 12076 4594 12077 4854 12077 4591 12077 4591 12078 4854 12078 4853 12078 4591 12079 4853 12079 4590 12079 6070 12080 6071 12080 6072 12080 6072 12081 6071 12081 6073 12081 6072 12082 6073 12082 6074 12082 6074 12083 6073 12083 4887 12083 6074 12084 4887 12084 6075 12084 6075 12085 4887 12085 4886 12085 6075 12086 4886 12086 6076 12086 6076 12087 4886 12087 6077 12087 6076 12088 6077 12088 4601 12088 4601 12089 6077 12089 4885 12089 4601 12090 4885 12090 6078 12090 6078 12091 4885 12091 4882 12091 6078 12092 4882 12092 2976 12092 2976 12093 4882 12093 4881 12093 3922 12094 4968 12094 6079 12094 6079 12095 4968 12095 6080 12095 6079 12096 6080 12096 6081 12096 6081 12097 6080 12097 4871 12097 6081 12098 4871 12098 6082 12098 6082 12099 4871 12099 4875 12099 6082 12100 4875 12100 4608 12100 4608 12101 4875 12101 6083 12101 4608 12102 6083 12102 4609 12102 4609 12103 6083 12103 6084 12103 4609 12104 6084 12104 6085 12104 6085 12105 6084 12105 6086 12105 6085 12106 6086 12106 4611 12106 4611 12107 6086 12107 4870 12107 6087 12108 6088 12108 4613 12108 4613 12109 6088 12109 6089 12109 4613 12110 6089 12110 6090 12110 6090 12111 6089 12111 6091 12111 6090 12112 6091 12112 6092 12112 6092 12113 6091 12113 6093 12113 6092 12114 6093 12114 4616 12114 4616 12115 6093 12115 6094 12115 4616 12116 6094 12116 6095 12116 6095 12117 6094 12117 4908 12117 6095 12118 4908 12118 6096 12118 6096 12119 4908 12119 6097 12119 6096 12120 6097 12120 3910 12120 3910 12121 6097 12121 6098 12121 4618 12122 2963 12122 4619 12122 4619 12123 2963 12123 6099 12123 4619 12124 6099 12124 4621 12124 4621 12125 6099 12125 6100 12125 4621 12126 6100 12126 4624 12126 4624 12127 6100 12127 6101 12127 4624 12128 6101 12128 4626 12128 4626 12129 6101 12129 6102 12129 4626 12130 6102 12130 6103 12130 6103 12131 6102 12131 4901 12131 6103 12132 4901 12132 4628 12132 4628 12133 4901 12133 6104 12133 4628 12134 6104 12134 3907 12134 3907 12135 6104 12135 4899 12135 4631 12136 6105 12136 6106 12136 6106 12137 6105 12137 4893 12137 6106 12138 4893 12138 4632 12138 4632 12139 4893 12139 6108 12139 4632 12140 6108 12140 6107 12140 6107 12141 6108 12141 4891 12141 6107 12142 4891 12142 6109 12142 6109 12143 4891 12143 6110 12143 6109 12144 6110 12144 6112 12144 6112 12145 6110 12145 6111 12145 6112 12146 6111 12146 4637 12146 4637 12147 6111 12147 2949 12147 1213 12148 2948 12148 5042 12148 1213 12149 5042 12149 6113 12149 6113 12150 5042 12150 5044 12150 6113 12151 5044 12151 9194 12151 9194 12152 5044 12152 6114 12152 9194 12153 6114 12153 6115 12153 6115 12154 6114 12154 5046 12154 6115 12155 5046 12155 6116 12155 6116 12156 5046 12156 6118 12156 6116 12157 6118 12157 6117 12157 6117 12158 6118 12158 6119 12158 6117 12159 6119 12159 9193 12159 9193 12160 6119 12160 5047 12160 9193 12161 5047 12161 6120 12161 6120 12162 5047 12162 5048 12162 6120 12163 5048 12163 6121 12163 6121 12164 5048 12164 5050 12164 6121 12165 5050 12165 6122 12165 6122 12166 5050 12166 5051 12166 6122 12167 5051 12167 9191 12167 9191 12168 5051 12168 5053 12168 9191 12169 5053 12169 6123 12169 6123 12170 5053 12170 5056 12170 6123 12171 5056 12171 6124 12171 6124 12172 5056 12172 6125 12172 6124 12173 6125 12173 9187 12173 9187 12174 6125 12174 6126 12174 9187 12175 6126 12175 6127 12175 6127 12176 6126 12176 6128 12176 6127 12177 6128 12177 6129 12177 6129 12178 6128 12178 5057 12178 6129 12179 5057 12179 9185 12179 9185 12180 5057 12180 6130 12180 9185 12181 6130 12181 9184 12181 9184 12182 6130 12182 6131 12182 9184 12183 6131 12183 9182 12183 9182 12184 6131 12184 3880 12184 9182 12185 3880 12185 1234 12185 4636 12186 3900 12186 6134 12186 6134 12187 4633 12187 4634 12187 6132 12188 6133 12188 3900 12188 3900 12189 6133 12189 3904 12189 4630 12190 6134 12190 3905 12190 3905 12191 6134 12191 3900 12191 3905 12192 3900 12192 6135 12192 6135 12193 3900 12193 3904 12193 4636 12194 6134 12194 6136 12194 6136 12195 6134 12195 4634 12195 6136 12196 4634 12196 4635 12196 4617 12197 4620 12197 6141 12197 6141 12198 4620 12198 4622 12198 6141 12199 4622 12199 4623 12199 6141 12200 6137 12200 6139 12200 4617 12201 6141 12201 6138 12201 6138 12202 6141 12202 6139 12202 6138 12203 6139 12203 3909 12203 4629 12204 6140 12204 4627 12204 4627 12205 6140 12205 6141 12205 4627 12206 6141 12206 4625 12206 4625 12207 6141 12207 4623 12207 6146 12208 4615 12208 6150 12208 6142 12209 4615 12209 4614 12209 4614 12210 4615 12210 6146 12210 4614 12211 6146 12211 4612 12211 6143 12212 6144 12212 6146 12212 6146 12213 6144 12213 6145 12213 6146 12214 6145 12214 4612 12214 3911 12215 6147 12215 6148 12215 6148 12216 6147 12216 6146 12216 6148 12217 6146 12217 6149 12217 6149 12218 6146 12218 6150 12218 4610 12219 3914 12219 6151 12219 3916 12220 3917 12220 6151 12220 6151 12221 3917 12221 3919 12221 4605 12222 4606 12222 4604 12222 4604 12223 4606 12223 4607 12223 4604 12224 4607 12224 6152 12224 6152 12225 4610 12225 4604 12225 4604 12226 4610 12226 6151 12226 4604 12227 6151 12227 4603 12227 4603 12228 6151 12228 3919 12228 4603 12229 3919 12229 3921 12229 3927 12230 6153 12230 6159 12230 6159 12231 6153 12231 6154 12231 6159 12232 6154 12232 6155 12232 6156 12233 3924 12233 6161 12233 6155 12234 6157 12234 6159 12234 6159 12235 6157 12235 4600 12235 6159 12236 4600 12236 6158 12236 6159 12237 4602 12237 3927 12237 3927 12238 4602 12238 6156 12238 3927 12239 6156 12239 6160 12239 6160 12240 6156 12240 6161 12240 6162 12241 4589 12241 3929 12241 3930 12242 6162 12242 3932 12242 3932 12243 6162 12243 3929 12243 3932 12244 3929 12244 3935 12244 3935 12245 3929 12245 3933 12245 4598 12246 4596 12246 6163 12246 6163 12247 4596 12247 4592 12247 6163 12248 4592 12248 4589 12248 4589 12249 4592 12249 6164 12249 4589 12250 6164 12250 3929 12250 3929 12251 6164 12251 6165 12251 4580 12252 3939 12252 6167 12252 6168 12253 4584 12253 4585 12253 3943 12254 6166 12254 3949 12254 3949 12255 6166 12255 3942 12255 3949 12256 3942 12256 6167 12256 3942 12257 3941 12257 6167 12257 6167 12258 3941 12258 4588 12258 6167 12259 4588 12259 4580 12259 4580 12260 4588 12260 6168 12260 4580 12261 6168 12261 4581 12261 4581 12262 6168 12262 4585 12262 6170 12263 4578 12263 6169 12263 4570 12264 4571 12264 4575 12264 4575 12265 4571 12265 6169 12265 4575 12266 6169 12266 4579 12266 4579 12267 6169 12267 4578 12267 6171 12268 3954 12268 3955 12268 6170 12269 6169 12269 3951 12269 3951 12270 6169 12270 6171 12270 3951 12271 6171 12271 6172 12271 6172 12272 6171 12272 3955 12272 6172 12273 3955 12273 3952 12273 3962 12274 3964 12274 6176 12274 3956 12275 3957 12275 3960 12275 4566 12276 4568 12276 6173 12276 6173 12277 4568 12277 6177 12277 3960 12278 6174 12278 3956 12278 3956 12279 6174 12279 3962 12279 3956 12280 3962 12280 6175 12280 6175 12281 3962 12281 6176 12281 6175 12282 6176 12282 6177 12282 6177 12283 6176 12283 4565 12283 6177 12284 4565 12284 6173 12284 4553 12285 4560 12285 6179 12285 4560 12286 4558 12286 6179 12286 6179 12287 4558 12287 6178 12287 6179 12288 6178 12288 4556 12288 6180 12289 3966 12289 6179 12289 6179 12290 3966 12290 6181 12290 6179 12291 6181 12291 4553 12291 3968 12292 3970 12292 6182 12292 6182 12293 3970 12293 6179 12293 6182 12294 6179 12294 6183 12294 6183 12295 6179 12295 4556 12295 9084 12296 2932 12296 9082 12296 9084 12297 9082 12297 6184 12297 6184 12298 9082 12298 9081 12298 6184 12299 9081 12299 6185 12299 6185 12300 9081 12300 6186 12300 6185 12301 6186 12301 9087 12301 9087 12302 6186 12302 6187 12302 9087 12303 6187 12303 9089 12303 9089 12304 6187 12304 9078 12304 9089 12305 9078 12305 6188 12305 6188 12306 9078 12306 6190 12306 6188 12307 6190 12307 6189 12307 6189 12308 6190 12308 6191 12308 6189 12309 6191 12309 9091 12309 9091 12310 6191 12310 6192 12310 9091 12311 6192 12311 9092 12311 9092 12312 6192 12312 6193 12312 9092 12313 6193 12313 6194 12313 6194 12314 6193 12314 9075 12314 6194 12315 9075 12315 6195 12315 6195 12316 9075 12316 9074 12316 6195 12317 9074 12317 9094 12317 9094 12318 9074 12318 6196 12318 9094 12319 6196 12319 9095 12319 9095 12320 6196 12320 9071 12320 9095 12321 9071 12321 9097 12321 9097 12322 9071 12322 6197 12322 9097 12323 6197 12323 9098 12323 9098 12324 6197 12324 6199 12324 9098 12325 6199 12325 6198 12325 6198 12326 6199 12326 6200 12326 6198 12327 6200 12327 9101 12327 9101 12328 6200 12328 9069 12328 9101 12329 9069 12329 9102 12329 9102 12330 9069 12330 6201 12330 9102 12331 6201 12331 6202 12331 6202 12332 6201 12332 1311 12332 6202 12333 1311 12333 2910 12333 6203 12334 9122 12334 6204 12334 6203 12335 6204 12335 6205 12335 6205 12336 6204 12336 9120 12336 6205 12337 9120 12337 9155 12337 9155 12338 9120 12338 9118 12338 9155 12339 9118 12339 6206 12339 6206 12340 9118 12340 6207 12340 6206 12341 6207 12341 9157 12341 9157 12342 6207 12342 6208 12342 9157 12343 6208 12343 6209 12343 6209 12344 6208 12344 6210 12344 6209 12345 6210 12345 9158 12345 9158 12346 6210 12346 6211 12346 9158 12347 6211 12347 9159 12347 9159 12348 6211 12348 6213 12348 9159 12349 6213 12349 6212 12349 6212 12350 6213 12350 6214 12350 6212 12351 6214 12351 9165 12351 9165 12352 6214 12352 6215 12352 9165 12353 6215 12353 6216 12353 6216 12354 6215 12354 6217 12354 6216 12355 6217 12355 6218 12355 6218 12356 6217 12356 6219 12356 6218 12357 6219 12357 9167 12357 9167 12358 6219 12358 9110 12358 9167 12359 9110 12359 9170 12359 9170 12360 9110 12360 9108 12360 9170 12361 9108 12361 9175 12361 9175 12362 9108 12362 6220 12362 9175 12363 6220 12363 9174 12363 9174 12364 6220 12364 9106 12364 9174 12365 9106 12365 9176 12365 9176 12366 9106 12366 9104 12366 9176 12367 9104 12367 6221 12367 6221 12368 9104 12368 6222 12368 6221 12369 6222 12369 9180 12369 9180 12370 6222 12370 1279 12370 9180 12371 1279 12371 1235 12371 1331 12372 2890 12372 6223 12372 1331 12373 6223 12373 9054 12373 9054 12374 6223 12374 9053 12374 9054 12375 9053 12375 6224 12375 6224 12376 9053 12376 6225 12376 6224 12377 6225 12377 6226 12377 6226 12378 6225 12378 9050 12378 6226 12379 9050 12379 6227 12379 6227 12380 9050 12380 9049 12380 6227 12381 9049 12381 6228 12381 6228 12382 9049 12382 6229 12382 6228 12383 6229 12383 9056 12383 9056 12384 6229 12384 9046 12384 9056 12385 9046 12385 6230 12385 6230 12386 9046 12386 6231 12386 6230 12387 6231 12387 9059 12387 9059 12388 6231 12388 6232 12388 9059 12389 6232 12389 6233 12389 6233 12390 6232 12390 6234 12390 6233 12391 6234 12391 6235 12391 6235 12392 6234 12392 6237 12392 6235 12393 6237 12393 6236 12393 6236 12394 6237 12394 9043 12394 6236 12395 9043 12395 6238 12395 6238 12396 9043 12396 6240 12396 6238 12397 6240 12397 6239 12397 6239 12398 6240 12398 6241 12398 6239 12399 6241 12399 9061 12399 9061 12400 6241 12400 6242 12400 9061 12401 6242 12401 9063 12401 9063 12402 6242 12402 6243 12402 9063 12403 6243 12403 6244 12403 6244 12404 6243 12404 6245 12404 6244 12405 6245 12405 9065 12405 9065 12406 6245 12406 6247 12406 9065 12407 6247 12407 6246 12407 6246 12408 6247 12408 1348 12408 6246 12409 1348 12409 6248 12409 1368 12410 2869 12410 9018 12410 1368 12411 9018 12411 9020 12411 9020 12412 9018 12412 9015 12412 9020 12413 9015 12413 9021 12413 9021 12414 9015 12414 6249 12414 9021 12415 6249 12415 9022 12415 9022 12416 6249 12416 6250 12416 9022 12417 6250 12417 9024 12417 9024 12418 6250 12418 6252 12418 9024 12419 6252 12419 6251 12419 6251 12420 6252 12420 9011 12420 6251 12421 9011 12421 9027 12421 9027 12422 9011 12422 9009 12422 9027 12423 9009 12423 9028 12423 9028 12424 9009 12424 6253 12424 9028 12425 6253 12425 9030 12425 9030 12426 6253 12426 9006 12426 9030 12427 9006 12427 9031 12427 9031 12428 9006 12428 6254 12428 9031 12429 6254 12429 9033 12429 9033 12430 6254 12430 6255 12430 9033 12431 6255 12431 6256 12431 6256 12432 6255 12432 9003 12432 6256 12433 9003 12433 9036 12433 9036 12434 9003 12434 9001 12434 9036 12435 9001 12435 9037 12435 9037 12436 9001 12436 6257 12436 9037 12437 6257 12437 6258 12437 6258 12438 6257 12438 8999 12438 6258 12439 8999 12439 6259 12439 6259 12440 8999 12440 6260 12440 6259 12441 6260 12441 6261 12441 6261 12442 6260 12442 8996 12442 6261 12443 8996 12443 6262 12443 6262 12444 8996 12444 6263 12444 6262 12445 6263 12445 6264 12445 6264 12446 6263 12446 6265 12446 6264 12447 6265 12447 9040 12447 1403 12448 2847 12448 8980 12448 1403 12449 8980 12449 6266 12449 6266 12450 8980 12450 6267 12450 6266 12451 6267 12451 8983 12451 8983 12452 6267 12452 6268 12452 8983 12453 6268 12453 6269 12453 6269 12454 6268 12454 6270 12454 6269 12455 6270 12455 6271 12455 6271 12456 6270 12456 6272 12456 6271 12457 6272 12457 8985 12457 8985 12458 6272 12458 6273 12458 8985 12459 6273 12459 8986 12459 8986 12460 6273 12460 8976 12460 8986 12461 8976 12461 6275 12461 6275 12462 8976 12462 6274 12462 6275 12463 6274 12463 8988 12463 8988 12464 6274 12464 6276 12464 8988 12465 6276 12465 8989 12465 8989 12466 6276 12466 8974 12466 8989 12467 8974 12467 8990 12467 8990 12468 8974 12468 6277 12468 8990 12469 6277 12469 6278 12469 6278 12470 6277 12470 6279 12470 6278 12471 6279 12471 6280 12471 6280 12472 6279 12472 6281 12472 6280 12473 6281 12473 6283 12473 6283 12474 6281 12474 6282 12474 6283 12475 6282 12475 6285 12475 6285 12476 6282 12476 6284 12476 6285 12477 6284 12477 8993 12477 8993 12478 6284 12478 8972 12478 8993 12479 8972 12479 8994 12479 8994 12480 8972 12480 6287 12480 8994 12481 6287 12481 6286 12481 6286 12482 6287 12482 8969 12482 6286 12483 8969 12483 8995 12483 8995 12484 8969 12484 8968 12484 8995 12485 8968 12485 2828 12485 8942 12486 2827 12486 8941 12486 8942 12487 8941 12487 8943 12487 8943 12488 8941 12488 6288 12488 8943 12489 6288 12489 8946 12489 8946 12490 6288 12490 8938 12490 8946 12491 8938 12491 8947 12491 8947 12492 8938 12492 8937 12492 8947 12493 8937 12493 6289 12493 6289 12494 8937 12494 6290 12494 6289 12495 6290 12495 8949 12495 8949 12496 6290 12496 8936 12496 8949 12497 8936 12497 6291 12497 6291 12498 8936 12498 8935 12498 6291 12499 8935 12499 8951 12499 8951 12500 8935 12500 8932 12500 8951 12501 8932 12501 6293 12501 6293 12502 8932 12502 6292 12502 6293 12503 6292 12503 8954 12503 8954 12504 6292 12504 8931 12504 8954 12505 8931 12505 8956 12505 8956 12506 8931 12506 8929 12506 8956 12507 8929 12507 8957 12507 8957 12508 8929 12508 6294 12508 8957 12509 6294 12509 8959 12509 8959 12510 6294 12510 8926 12510 8959 12511 8926 12511 6295 12511 6295 12512 8926 12512 6296 12512 6295 12513 6296 12513 8961 12513 8961 12514 6296 12514 8924 12514 8961 12515 8924 12515 6297 12515 6297 12516 8924 12516 6298 12516 6297 12517 6298 12517 8964 12517 8964 12518 6298 12518 8922 12518 8964 12519 8922 12519 6299 12519 6299 12520 8922 12520 8921 12520 6299 12521 8921 12521 6300 12521 6300 12522 8921 12522 1474 12522 6300 12523 1474 12523 8966 12523 8903 12524 6301 12524 8901 12524 8903 12525 8901 12525 6302 12525 6302 12526 8901 12526 8899 12526 6302 12527 8899 12527 8905 12527 8905 12528 8899 12528 8897 12528 8905 12529 8897 12529 8906 12529 8906 12530 8897 12530 6303 12530 8906 12531 6303 12531 6305 12531 6305 12532 6303 12532 6304 12532 6305 12533 6304 12533 6306 12533 6306 12534 6304 12534 8895 12534 6306 12535 8895 12535 6307 12535 6307 12536 8895 12536 6309 12536 6307 12537 6309 12537 6308 12537 6308 12538 6309 12538 6310 12538 6308 12539 6310 12539 6311 12539 6311 12540 6310 12540 6312 12540 6311 12541 6312 12541 6313 12541 6313 12542 6312 12542 8892 12542 6313 12543 8892 12543 8910 12543 8910 12544 8892 12544 8890 12544 8910 12545 8890 12545 8911 12545 8911 12546 8890 12546 6314 12546 8911 12547 6314 12547 8912 12547 8912 12548 6314 12548 8887 12548 8912 12549 8887 12549 8914 12549 8914 12550 8887 12550 8886 12550 8914 12551 8886 12551 6315 12551 6315 12552 8886 12552 8884 12552 6315 12553 8884 12553 6316 12553 6316 12554 8884 12554 6317 12554 6316 12555 6317 12555 8917 12555 8917 12556 6317 12556 6318 12556 8917 12557 6318 12557 8918 12557 8918 12558 6318 12558 6319 12558 8918 12559 6319 12559 6321 12559 6321 12560 6319 12560 6320 12560 6321 12561 6320 12561 8920 12561 6322 12562 8859 12562 8858 12562 6322 12563 8858 12563 8861 12563 8861 12564 8858 12564 6323 12564 8861 12565 6323 12565 6324 12565 6324 12566 6323 12566 8857 12566 6324 12567 8857 12567 8863 12567 8863 12568 8857 12568 8856 12568 8863 12569 8856 12569 8864 12569 8864 12570 8856 12570 6325 12570 8864 12571 6325 12571 8866 12571 8866 12572 6325 12572 8855 12572 8866 12573 8855 12573 8867 12573 8867 12574 8855 12574 6326 12574 8867 12575 6326 12575 8869 12575 8869 12576 6326 12576 6327 12576 8869 12577 6327 12577 8870 12577 8870 12578 6327 12578 6328 12578 8870 12579 6328 12579 8872 12579 8872 12580 6328 12580 6329 12580 8872 12581 6329 12581 6330 12581 6330 12582 6329 12582 6331 12582 6330 12583 6331 12583 8873 12583 8873 12584 6331 12584 8851 12584 8873 12585 8851 12585 8874 12585 8874 12586 8851 12586 6332 12586 8874 12587 6332 12587 8876 12587 8876 12588 6332 12588 8849 12588 8876 12589 8849 12589 6333 12589 6333 12590 8849 12590 6334 12590 6333 12591 6334 12591 6335 12591 6335 12592 6334 12592 8847 12592 6335 12593 8847 12593 8878 12593 8878 12594 8847 12594 6336 12594 8878 12595 6336 12595 6337 12595 6337 12596 6336 12596 8845 12596 6337 12597 8845 12597 8880 12597 8880 12598 8845 12598 1552 12598 8880 12599 1552 12599 2781 12599 1570 12600 2779 12600 8059 12600 1570 12601 8059 12601 8823 12601 8823 12602 8059 12602 8058 12602 8823 12603 8058 12603 8824 12603 8824 12604 8058 12604 8056 12604 8824 12605 8056 12605 6338 12605 6338 12606 8056 12606 6340 12606 6338 12607 6340 12607 6339 12607 6339 12608 6340 12608 6341 12608 6339 12609 6341 12609 8826 12609 8826 12610 6341 12610 8052 12610 8826 12611 8052 12611 8827 12611 8827 12612 8052 12612 8050 12612 8827 12613 8050 12613 6342 12613 6342 12614 8050 12614 8049 12614 6342 12615 8049 12615 8830 12615 8830 12616 8049 12616 8048 12616 8830 12617 8048 12617 6343 12617 6343 12618 8048 12618 6344 12618 6343 12619 6344 12619 8831 12619 8831 12620 6344 12620 6345 12620 8831 12621 6345 12621 8833 12621 8833 12622 6345 12622 6346 12622 8833 12623 6346 12623 8834 12623 8834 12624 6346 12624 6347 12624 8834 12625 6347 12625 6348 12625 6348 12626 6347 12626 6349 12626 6348 12627 6349 12627 8836 12627 8836 12628 6349 12628 6350 12628 8836 12629 6350 12629 8838 12629 8838 12630 6350 12630 8041 12630 8838 12631 8041 12631 8840 12631 8840 12632 8041 12632 6351 12632 8840 12633 6351 12633 8841 12633 8841 12634 6351 12634 6352 12634 8841 12635 6352 12635 8842 12635 8842 12636 6352 12636 8038 12636 8842 12637 8038 12637 8843 12637 8017 12638 9196 12638 6353 12638 8017 12639 6353 12639 8019 12639 8019 12640 6353 12640 9195 12640 8019 12641 9195 12641 8020 12641 8020 12642 9195 12642 6354 12642 8020 12643 6354 12643 8021 12643 8021 12644 6354 12644 6355 12644 8021 12645 6355 12645 8022 12645 8022 12646 6355 12646 6356 12646 8022 12647 6356 12647 6357 12647 6357 12648 6356 12648 6358 12648 6357 12649 6358 12649 6359 12649 6359 12650 6358 12650 6360 12650 6359 12651 6360 12651 8025 12651 8025 12652 6360 12652 9192 12652 8025 12653 9192 12653 6361 12653 6361 12654 9192 12654 6362 12654 6361 12655 6362 12655 8026 12655 8026 12656 6362 12656 9190 12656 8026 12657 9190 12657 6363 12657 6363 12658 9190 12658 9189 12658 6363 12659 9189 12659 6364 12659 6364 12660 9189 12660 9188 12660 6364 12661 9188 12661 8029 12661 8029 12662 9188 12662 6365 12662 8029 12663 6365 12663 8031 12663 8031 12664 6365 12664 9186 12664 8031 12665 9186 12665 8033 12665 8033 12666 9186 12666 6366 12666 8033 12667 6366 12667 6367 12667 6367 12668 6366 12668 6368 12668 6367 12669 6368 12669 6369 12669 6369 12670 6368 12670 9183 12670 6369 12671 9183 12671 8036 12671 8036 12672 9183 12672 9181 12672 8036 12673 9181 12673 6370 12673 6370 12674 9181 12674 2738 12674 6370 12675 2738 12675 8037 12675 9253 12676 6842 12676 6836 12676 9253 12677 6836 12677 9255 12677 9255 12678 6836 12678 6371 12678 9255 12679 6371 12679 6372 12679 6372 12680 6371 12680 6373 12680 6372 12681 6373 12681 6374 12681 6374 12682 6373 12682 6375 12682 6374 12683 6375 12683 9259 12683 9259 12684 6375 12684 6376 12684 9259 12685 6376 12685 6377 12685 6377 12686 6376 12686 6639 12686 6377 12687 6639 12687 9260 12687 9260 12688 6639 12688 6378 12688 9260 12689 6378 12689 2733 12689 9238 12690 7927 12690 6644 12690 9238 12691 6644 12691 6379 12691 6379 12692 6644 12692 6380 12692 6379 12693 6380 12693 6381 12693 6381 12694 6380 12694 6645 12694 6381 12695 6645 12695 6382 12695 6382 12696 6645 12696 6383 12696 6382 12697 6383 12697 9241 12697 9241 12698 6383 12698 6384 12698 9241 12699 6384 12699 9243 12699 9243 12700 6384 12700 6385 12700 9243 12701 6385 12701 9244 12701 9244 12702 6385 12702 6386 12702 9244 12703 6386 12703 9247 12703 9247 12704 6386 12704 6831 12704 9247 12705 6831 12705 9248 12705 9248 12706 6831 12706 6387 12706 9248 12707 6387 12707 9249 12707 9249 12708 6387 12708 6388 12708 9249 12709 6388 12709 6389 12709 6389 12710 6388 12710 6390 12710 6389 12711 6390 12711 9250 12711 9250 12712 6390 12712 6648 12712 9250 12713 6648 12713 9251 12713 9251 12714 6648 12714 6391 12714 9251 12715 6391 12715 7928 12715 9237 12716 6392 12716 6404 12716 6394 12717 6400 12717 9254 12717 9254 12718 9256 12718 6394 12718 6394 12719 9256 12719 6393 12719 6394 12720 6393 12720 9257 12720 9257 12721 9258 12721 6394 12721 6394 12722 9258 12722 6395 12722 6394 12723 6395 12723 6396 12723 6392 12724 9239 12724 6404 12724 6404 12725 9239 12725 9240 12725 6404 12726 9240 12726 6397 12726 6394 12727 6398 12727 6400 12727 6400 12728 6398 12728 6399 12728 6400 12729 6399 12729 1210 12729 1210 12730 1211 12730 6400 12730 6400 12731 1211 12731 6401 12731 6400 12732 6401 12732 6402 12732 6397 12733 9242 12733 6404 12733 6404 12734 9242 12734 9245 12734 6404 12735 9245 12735 9246 12735 6402 12736 6403 12736 6400 12736 6400 12737 6403 12737 6405 12737 6400 12738 6405 12738 6404 12738 6404 12739 6405 12739 6406 12739 6404 12740 6406 12740 9237 12740 9246 12741 6407 12741 6404 12741 6404 12742 6407 12742 6408 12742 6404 12743 6408 12743 6409 12743 6409 12744 6410 12744 6404 12744 6404 12745 6410 12745 6411 12745 6404 12746 6411 12746 9252 12746 9329 12747 9232 12747 9327 12747 9327 12748 9232 12748 6412 12748 9330 12749 9222 12749 9324 12749 9324 12750 9222 12750 9228 12750 9325 12751 9219 12751 6413 12751 6413 12752 9219 12752 9216 12752 6414 12753 9226 12753 9134 12753 9134 12754 9226 12754 6415 12754 9317 12755 6416 12755 9319 12755 9319 12756 6416 12756 9206 12756 9138 12757 6417 12757 6418 12757 6418 12758 6417 12758 9154 12758 9316 12759 9146 12759 9144 12759 9144 12760 9146 12760 9145 12760 9320 12761 9197 12761 9321 12761 9321 12762 9197 12762 9201 12762 6758 12763 6796 12763 6756 12763 9156 12764 6752 12764 6753 12764 6419 12765 6745 12765 9160 12765 9163 12766 6585 12766 6420 12766 9178 12767 6826 12767 6653 12767 9177 12768 6799 12768 6718 12768 6710 12769 6561 12769 6421 12769 6702 12770 6953 12770 6451 12770 6422 12771 6451 12771 6698 12771 1250 12772 6507 12772 6482 12772 6644 12773 6784 12773 6380 12773 7887 12774 7888 12774 6769 12774 2737 12775 6762 12775 6423 12775 7848 12776 6424 12776 6844 12776 7681 12777 7684 12777 6631 12777 2649 12778 6425 12778 6657 12778 6671 12779 6426 12779 6427 12779 7716 12780 6428 12780 6567 12780 2533 12781 6497 12781 6498 12781 2132 12782 6429 12782 6692 12782 6438 12783 7439 12783 6440 12783 6440 12784 7439 12784 6430 12784 6430 12785 7439 12785 6431 12785 6430 12786 6431 12786 6690 12786 2092 12787 6432 12787 2093 12787 2093 12788 6432 12788 6433 12788 2093 12789 6433 12789 7519 12789 7519 12790 6433 12790 6434 12790 7519 12791 6434 12791 6439 12791 6439 12792 6434 12792 6435 12792 2091 12793 6436 12793 6463 12793 6463 12794 6436 12794 2089 12794 6463 12795 2089 12795 6683 12795 6683 12796 2089 12796 6437 12796 6683 12797 6437 12797 6684 12797 6435 12798 6438 12798 6439 12798 6439 12799 6438 12799 6440 12799 6439 12800 6440 12800 7517 12800 7517 12801 6440 12801 6441 12801 7517 12802 6441 12802 7515 12802 1246 12803 7514 12803 6441 12803 6441 12804 7514 12804 6442 12804 6441 12805 6442 12805 7515 12805 2136 12806 6444 12806 6443 12806 6443 12807 6444 12807 6445 12807 2107 12808 6467 12808 2109 12808 2109 12809 6467 12809 6830 12809 2109 12810 6830 12810 6455 12810 7420 12811 7421 12811 2103 12811 7421 12812 7424 12812 2103 12812 2103 12813 7424 12813 6448 12813 2103 12814 6448 12814 2102 12814 6451 12815 6452 12815 6446 12815 7424 12816 6447 12816 6448 12816 6448 12817 6447 12817 6449 12817 6448 12818 6449 12818 6422 12818 6422 12819 6449 12819 6450 12819 6422 12820 6450 12820 6451 12820 6451 12821 6450 12821 2145 12821 6451 12822 2145 12822 6452 12822 6446 12823 6456 12823 6822 12823 2103 12824 6453 12824 7420 12824 7420 12825 6453 12825 2105 12825 7420 12826 2105 12826 2151 12826 2151 12827 2105 12827 6455 12827 2151 12828 6455 12828 6454 12828 6454 12829 6455 12829 6822 12829 6454 12830 6822 12830 2149 12830 2149 12831 6822 12831 6456 12831 6460 12832 1241 12832 6445 12832 6445 12833 1241 12833 6457 12833 6445 12834 6457 12834 6443 12834 6445 12835 6458 12835 6460 12835 6460 12836 6458 12836 6459 12836 6460 12837 6459 12837 6448 12837 6448 12838 6459 12838 7482 12838 6448 12839 7482 12839 2102 12839 6692 12840 6429 12840 6694 12840 6694 12841 6429 12841 6461 12841 6694 12842 6461 12842 6465 12842 2092 12843 2091 12843 6432 12843 6432 12844 2091 12844 6463 12844 6432 12845 6463 12845 6462 12845 6462 12846 6463 12846 6464 12846 6462 12847 6464 12847 6465 12847 2137 12848 2142 12848 6466 12848 6466 12849 2142 12849 2141 12849 6466 12850 2141 12850 6469 12850 2137 12851 6467 12851 2136 12851 2136 12852 6467 12852 2107 12852 2136 12853 2107 12853 6444 12853 1244 12854 7437 12854 6457 12854 6457 12855 7437 12855 2133 12855 6457 12856 2133 12856 6443 12856 6468 12857 6473 12857 1244 12857 1244 12858 6473 12858 7435 12858 1244 12859 7435 12859 7437 12859 2141 12860 6470 12860 6469 12860 6469 12861 6470 12861 6471 12861 6469 12862 6471 12862 1243 12862 1243 12863 6471 12863 7429 12863 1243 12864 7429 12864 6468 12864 6468 12865 7429 12865 6472 12865 6468 12866 6472 12866 6473 12866 2516 12867 6477 12867 6476 12867 6678 12868 6474 12868 6688 12868 6688 12869 6474 12869 6475 12869 6688 12870 6475 12870 6476 12870 6476 12871 6475 12871 2518 12871 6476 12872 2518 12872 2516 12872 6477 12873 6479 12873 6478 12873 6478 12874 6479 12874 2514 12874 6478 12875 2514 12875 2512 12875 1248 12876 6480 12876 6677 12876 6677 12877 6480 12877 6481 12877 6481 12878 6480 12878 6482 12878 6481 12879 6482 12879 6483 12879 6483 12880 6482 12880 6507 12880 6483 12881 6507 12881 6506 12881 6501 12882 6484 12882 6485 12882 6485 12883 6484 12883 6486 12883 6485 12884 6486 12884 7031 12884 7031 12885 6486 12885 6492 12885 2641 12886 6487 12886 6490 12886 2527 12887 6488 12887 6492 12887 6492 12888 6488 12888 6489 12888 6492 12889 6489 12889 7031 12889 6490 12890 6487 12890 6492 12890 6487 12891 6491 12891 6492 12891 6492 12892 6491 12892 6493 12892 6492 12893 6493 12893 2527 12893 2527 12894 6493 12894 6494 12894 2527 12895 6494 12895 2529 12895 2529 12896 6494 12896 6495 12896 2529 12897 6495 12897 2530 12897 2530 12898 6495 12898 6496 12898 2530 12899 6496 12899 6497 12899 6498 12900 2645 12900 6499 12900 6499 12901 2643 12901 6665 12901 6665 12902 2643 12902 2642 12902 6665 12903 2642 12903 6666 12903 6497 12904 6496 12904 6498 12904 6498 12905 6496 12905 2646 12905 6498 12906 2646 12906 2645 12906 7028 12907 2533 12907 6827 12907 6500 12908 6511 12908 7029 12908 7029 12909 6511 12909 7030 12909 7030 12910 6511 12910 6502 12910 7030 12911 6502 12911 6501 12911 6501 12912 6502 12912 6522 12912 6501 12913 6522 12913 6484 12913 1250 12914 1252 12914 6908 12914 6908 12915 1252 12915 6503 12915 6503 12916 1252 12916 6504 12916 6503 12917 6504 12917 2629 12917 2629 12918 6504 12918 6675 12918 2629 12919 6675 12919 2631 12919 6908 12920 6907 12920 1250 12920 1250 12921 6907 12921 6906 12921 1250 12922 6906 12922 6507 12922 6507 12923 6906 12923 6505 12923 6507 12924 6505 12924 6904 12924 2512 12925 6506 12925 6478 12925 6478 12926 6506 12926 6507 12926 6478 12927 6507 12927 6903 12927 6903 12928 6507 12928 6904 12928 6903 12929 6508 12929 6478 12929 6478 12930 6508 12930 2633 12930 6478 12931 2633 12931 6509 12931 6509 12932 2633 12932 2632 12932 6509 12933 2632 12933 6834 12933 2639 12934 2638 12934 6510 12934 6510 12935 2638 12935 6500 12935 6500 12936 2638 12936 2637 12936 6500 12937 2637 12937 6511 12937 2639 12938 6510 12938 6899 12938 6899 12939 6510 12939 6512 12939 6899 12940 6512 12940 6518 12940 6513 12941 6512 12941 6514 12941 6514 12942 6512 12942 6515 12942 6514 12943 6515 12943 6516 12943 6516 12944 6515 12944 6517 12944 1251 12945 6965 12945 6676 12945 6513 12946 2567 12946 6512 12946 6512 12947 2567 12947 2565 12947 6512 12948 2565 12948 6518 12948 6518 12949 2565 12949 2563 12949 6518 12950 2563 12950 6525 12950 2563 12951 6519 12951 6525 12951 6525 12952 6519 12952 6520 12952 6525 12953 6520 12953 6521 12953 6521 12954 6520 12954 6967 12954 6521 12955 6967 12955 1251 12955 1251 12956 6967 12956 6966 12956 1251 12957 6966 12957 6965 12957 6502 12958 2635 12958 6522 12958 6522 12959 2635 12959 6523 12959 6522 12960 6523 12960 1254 12960 1254 12961 6523 12961 6902 12961 1254 12962 6902 12962 6521 12962 6521 12963 6902 12963 6524 12963 6521 12964 6524 12964 6525 12964 7659 12965 7662 12965 6560 12965 6529 12966 9177 12966 9179 12966 6560 12967 7662 12967 7721 12967 7721 12968 7720 12968 6560 12968 6560 12969 7720 12969 7719 12969 6560 12970 7719 12970 6567 12970 6567 12971 7719 12971 7717 12971 6567 12972 7717 12972 7716 12972 6526 12973 6799 12973 6527 12973 6527 12974 6799 12974 9177 12974 6527 12975 9177 12975 1944 12975 1944 12976 9177 12976 6529 12976 6526 12977 1950 12977 6799 12977 6799 12978 1950 12978 1949 12978 6799 12979 1949 12979 6560 12979 6560 12980 1949 12980 7657 12980 6560 12981 7657 12981 7659 12981 6528 12982 7667 12982 9179 12982 9179 12983 7667 12983 7666 12983 9179 12984 7666 12984 6529 12984 1906 12985 6530 12985 6535 12985 6535 12986 6530 12986 6531 12986 6535 12987 6531 12987 6532 12987 6532 12988 6531 12988 1904 12988 6532 12989 1904 12989 7662 12989 7662 12990 1904 12990 6533 12990 7662 12991 6533 12991 7721 12991 6428 12992 1909 12992 6534 12992 6534 12993 1909 12993 1907 12993 6534 12994 1907 12994 6528 12994 6528 12995 1907 12995 1906 12995 6528 12996 1906 12996 7667 12996 7667 12997 1906 12997 6535 12997 1258 12998 6536 12998 1256 12998 1256 12999 6536 12999 6892 12999 6425 13000 2651 13000 6657 13000 6657 13001 2651 13001 6537 13001 6657 13002 6537 13002 6656 13002 6537 13003 6538 13003 6656 13003 6656 13004 6538 13004 2656 13004 6656 13005 2656 13005 1258 13005 1258 13006 2656 13006 2654 13006 1258 13007 2654 13007 6536 13007 6427 13008 6426 13008 6794 13008 6426 13009 6891 13009 6794 13009 6794 13010 6891 13010 6539 13010 6794 13011 6539 13011 6790 13011 6790 13012 6539 13012 2649 13012 6659 13013 1260 13013 6540 13013 6541 13014 2377 13014 6554 13014 6553 13015 2338 13015 6543 13015 6543 13016 2338 13016 6542 13016 6543 13017 6542 13017 6540 13017 6540 13018 6542 13018 7208 13018 6544 13019 6659 13019 6545 13019 6545 13020 6659 13020 6540 13020 6545 13021 6540 13021 7209 13021 7209 13022 6540 13022 7208 13022 6549 13023 2340 13023 6546 13023 6544 13024 6547 13024 6659 13024 6659 13025 6547 13025 6548 13025 6659 13026 6548 13026 7167 13026 7167 13027 6548 13027 6549 13027 7167 13028 6549 13028 7165 13028 7165 13029 6549 13029 6546 13029 2378 13030 6550 13030 6551 13030 6551 13031 6550 13031 7162 13031 6551 13032 7162 13032 2340 13032 2340 13033 7162 13033 6552 13033 2340 13034 6552 13034 6546 13034 6551 13035 6553 13035 2378 13035 2378 13036 6553 13036 6543 13036 2378 13037 6543 13037 6555 13037 6555 13038 6543 13038 6554 13038 6555 13039 6554 13039 6556 13039 6556 13040 6554 13040 2377 13040 6791 13041 6792 13041 6756 13041 6756 13042 6792 13042 2374 13042 6756 13043 2374 13043 6557 13043 6557 13044 2374 13044 6541 13044 6558 13045 7465 13045 6713 13045 6558 13046 6713 13046 6559 13046 6559 13047 6713 13047 6560 13047 6559 13048 6560 13048 2122 13048 7460 13049 1238 13049 6421 13049 7465 13050 7464 13050 6713 13050 6713 13051 7464 13051 6562 13051 6713 13052 6562 13052 6561 13052 6561 13053 6562 13053 6563 13053 6561 13054 6563 13054 6421 13054 6421 13055 6563 13055 7461 13055 6421 13056 7461 13056 7460 13056 6428 13057 6534 13057 6567 13057 6567 13058 6534 13058 1237 13058 6567 13059 1237 13059 1238 13059 7460 13060 6564 13060 1238 13060 1238 13061 6564 13061 6565 13061 1238 13062 6565 13062 6567 13062 6567 13063 6565 13063 6566 13063 6567 13064 6566 13064 6560 13064 6560 13065 6566 13065 6568 13065 6560 13066 6568 13066 2122 13066 7693 13067 6569 13067 6728 13067 6774 13068 1874 13068 1872 13068 6778 13069 6570 13069 7688 13069 6732 13070 7694 13070 6571 13070 6571 13071 7694 13071 1926 13071 6571 13072 1926 13072 6583 13072 6583 13073 1926 13073 1924 13073 6583 13074 1924 13074 6572 13074 6579 13075 7767 13075 1921 13075 1921 13076 7767 13076 7766 13076 1921 13077 7766 13077 6573 13077 6573 13078 7766 13078 6574 13078 6774 13079 1872 13079 6778 13079 1872 13080 6575 13080 6778 13080 6778 13081 6575 13081 6576 13081 6778 13082 6576 13082 6578 13082 6570 13083 6778 13083 6577 13083 6577 13084 6778 13084 6578 13084 6577 13085 6578 13085 6579 13085 6579 13086 6578 13086 6580 13086 6579 13087 6580 13087 7767 13087 1874 13088 6774 13088 6581 13088 6581 13089 6774 13089 6603 13089 6581 13090 6603 13090 1875 13090 6582 13091 6605 13091 1876 13091 1876 13092 6605 13092 6583 13092 1876 13093 6583 13093 6574 13093 6574 13094 6583 13094 6572 13094 6574 13095 6572 13095 6573 13095 6773 13096 6768 13096 6588 13096 6773 13097 6588 13097 6584 13097 7264 13098 6736 13098 2311 13098 2311 13099 6736 13099 6585 13099 2311 13100 6585 13100 2312 13100 2312 13101 6585 13101 9163 13101 7264 13102 6586 13102 6736 13102 6736 13103 6586 13103 6587 13103 6736 13104 6587 13104 6767 13104 6588 13105 7262 13105 6584 13105 6584 13106 7262 13106 2317 13106 6584 13107 2317 13107 6602 13107 6602 13108 2317 13108 2316 13108 6602 13109 2316 13109 9166 13109 9166 13110 2316 13110 2314 13110 9166 13111 2314 13111 9163 13111 9163 13112 2314 13112 2313 13112 9163 13113 2313 13113 2312 13113 6590 13114 6594 13114 6592 13114 6592 13115 6589 13115 6590 13115 6590 13116 6589 13116 6591 13116 6590 13117 6591 13117 6598 13117 6609 13118 6611 13118 7178 13118 7178 13119 6611 13119 6592 13119 7178 13120 6592 13120 6593 13120 6593 13121 6592 13121 6594 13121 6593 13122 6594 13122 6595 13122 6595 13123 6594 13123 6616 13123 6610 13124 6782 13124 7235 13124 7235 13125 6782 13125 6780 13125 7235 13126 6780 13126 7236 13126 6596 13127 6810 13127 7238 13127 7238 13128 6810 13128 6634 13128 7238 13129 6634 13129 6597 13129 6597 13130 6634 13130 2364 13130 6597 13131 2364 13131 7240 13131 7240 13132 2364 13132 2365 13132 7240 13133 2365 13133 7241 13133 7241 13134 2365 13134 6598 13134 7241 13135 6598 13135 2326 13135 2326 13136 6598 13136 6591 13136 6924 13137 6923 13137 6584 13137 6599 13138 6600 13138 6774 13138 6733 13139 6601 13139 6602 13139 6602 13140 6601 13140 2608 13140 6602 13141 2608 13141 6584 13141 6584 13142 2608 13142 6926 13142 6584 13143 6926 13143 6924 13143 6774 13144 6600 13144 6603 13144 6603 13145 6600 13145 6920 13145 6603 13146 6920 13146 6604 13146 6582 13147 1875 13147 6605 13147 6605 13148 1875 13148 6603 13148 6605 13149 6603 13149 9164 13149 9164 13150 6603 13150 6604 13150 9164 13151 6604 13151 2612 13151 2612 13152 2611 13152 9164 13152 9164 13153 2611 13153 6606 13153 9164 13154 6606 13154 6607 13154 6608 13155 6782 13155 6609 13155 6609 13156 6782 13156 6610 13156 6609 13157 6610 13157 6611 13157 6783 13158 7177 13158 6763 13158 6763 13159 7177 13159 6612 13159 6763 13160 6612 13160 6742 13160 6742 13161 6612 13161 2361 13161 6741 13162 6613 13162 6743 13162 6743 13163 6613 13163 6614 13163 6743 13164 6614 13164 6616 13164 6616 13165 6614 13165 6615 13165 6616 13166 6615 13166 6595 13166 7678 13167 7680 13167 6620 13167 1927 13168 6617 13168 6786 13168 6786 13169 6617 13169 6618 13169 6786 13170 6618 13170 6620 13170 6620 13171 6618 13171 6619 13171 6620 13172 6619 13172 7678 13172 1927 13173 6786 13173 1928 13173 1928 13174 6786 13174 6621 13174 1928 13175 6621 13175 1931 13175 1931 13176 6621 13176 9169 13176 1931 13177 9169 13177 6622 13177 6622 13178 9169 13178 9168 13178 6622 13179 9168 13179 6630 13179 6627 13180 1894 13180 9173 13180 9173 13181 1894 13181 1893 13181 9173 13182 1893 13182 6623 13182 6623 13183 1893 13183 6624 13183 6623 13184 6624 13184 9168 13184 9168 13185 6624 13185 1892 13185 1943 13186 6626 13186 6625 13186 6625 13187 6626 13187 6629 13187 6625 13188 6629 13188 1936 13188 9172 13189 1934 13189 9173 13189 9173 13190 1934 13190 6628 13190 9173 13191 6628 13191 6627 13191 6627 13192 6628 13192 1936 13192 6627 13193 1936 13193 7743 13193 7743 13194 1936 13194 6629 13194 6630 13195 9168 13195 7686 13195 7686 13196 9168 13196 1892 13196 7686 13197 1892 13197 7684 13197 7684 13198 1892 13198 1890 13198 7684 13199 1890 13199 6631 13199 6631 13200 1890 13200 7748 13200 6631 13201 7748 13201 6632 13201 6632 13202 7748 13202 7746 13202 6632 13203 7746 13203 6820 13203 6805 13204 6633 13204 6803 13204 7172 13205 6804 13205 6752 13205 6803 13206 6633 13206 6810 13206 6810 13207 6633 13207 7169 13207 6810 13208 7169 13208 6634 13208 2365 13209 2367 13209 6598 13209 6598 13210 2367 13210 2368 13210 6598 13211 2368 13211 6635 13211 6635 13212 2368 13212 2372 13212 6635 13213 2372 13213 9156 13213 9156 13214 2372 13214 7175 13214 9156 13215 7175 13215 6752 13215 6752 13216 7175 13216 6636 13216 6752 13217 6636 13217 7172 13217 6371 13218 6637 13218 6373 13218 6373 13219 6637 13219 6827 13219 6827 13220 6807 13220 6373 13220 6373 13221 6807 13221 6638 13221 6373 13222 6638 13222 6375 13222 6641 13223 6639 13223 6638 13223 6638 13224 6639 13224 6376 13224 6638 13225 6376 13225 6375 13225 2735 13226 2734 13226 6809 13226 6809 13227 2734 13227 6640 13227 6809 13228 6640 13228 6641 13228 6641 13229 6640 13229 6378 13229 6641 13230 6378 13230 6639 13230 6642 13231 6643 13231 6779 13231 2737 13232 6423 13232 7924 13232 6764 13233 7895 13233 7924 13233 7895 13234 6764 13234 7888 13234 6784 13235 6644 13235 6775 13235 6775 13236 6644 13236 7927 13236 6775 13237 7927 13237 7887 13237 6380 13238 6785 13238 6645 13238 6645 13239 6785 13239 6788 13239 6645 13240 6788 13240 6383 13240 6813 13241 6386 13241 6815 13241 6815 13242 6386 13242 6385 13242 6815 13243 6385 13243 6646 13243 6646 13244 6385 13244 6384 13244 6646 13245 6384 13245 6383 13245 6843 13246 7843 13246 7839 13246 6390 13247 6647 13247 6648 13247 6648 13248 6647 13248 6838 13248 6648 13249 6838 13249 6391 13249 6650 13250 6649 13250 7671 13250 6649 13251 6650 13251 7670 13251 7670 13252 6650 13252 6819 13252 7670 13253 6819 13253 1943 13253 1943 13254 6819 13254 6821 13254 1943 13255 6821 13255 6626 13255 6651 13256 7675 13256 6826 13256 6826 13257 7675 13257 6652 13257 6826 13258 6652 13258 6653 13258 6653 13259 6652 13259 6654 13259 6653 13260 6654 13260 9172 13260 9172 13261 6654 13261 6655 13261 9172 13262 6655 13262 1934 13262 6658 13263 6657 13263 6999 13263 6999 13264 6657 13264 6656 13264 6999 13265 6656 13265 7000 13265 7000 13266 6656 13266 7001 13266 7001 13267 6656 13267 7002 13267 7002 13268 6656 13268 1259 13268 7002 13269 1259 13269 6662 13269 2541 13270 6659 13270 6996 13270 6996 13271 6659 13271 6657 13271 6996 13272 6657 13272 6997 13272 6997 13273 6657 13273 6658 13273 2541 13274 6660 13274 6659 13274 6659 13275 6660 13275 2539 13275 6659 13276 2539 13276 1260 13276 1260 13277 2539 13277 6661 13277 1260 13278 6661 13278 1259 13278 1259 13279 6661 13279 2538 13279 1259 13280 2538 13280 6662 13280 6957 13281 6663 13281 6665 13281 6959 13282 1255 13282 6664 13282 6664 13283 1255 13283 6667 13283 6959 13284 6957 13284 1255 13284 1255 13285 6957 13285 6665 13285 1255 13286 6665 13286 6490 13286 6490 13287 6665 13287 6666 13287 6490 13288 6666 13288 2641 13288 2573 13289 2571 13289 6667 13289 6667 13290 2571 13290 2569 13290 6667 13291 2569 13291 6664 13291 6663 13292 6668 13292 6665 13292 6665 13293 6668 13293 2575 13293 6665 13294 2575 13294 6669 13294 6793 13295 6670 13295 6794 13295 6670 13296 2573 13296 6794 13296 6794 13297 2573 13297 6667 13297 6794 13298 6667 13298 6427 13298 6427 13299 6667 13299 1256 13299 6427 13300 1256 13300 6671 13300 6671 13301 1256 13301 6892 13301 2575 13302 6672 13302 6669 13302 6669 13303 6672 13303 6673 13303 6669 13304 6673 13304 6793 13304 6504 13305 6674 13305 6675 13305 6675 13306 6674 13306 1251 13306 6675 13307 1251 13307 6515 13307 6515 13308 1251 13308 6676 13308 6515 13309 6676 13309 6517 13309 6677 13310 6678 13310 1248 13310 1248 13311 6678 13311 6688 13311 1248 13312 6688 13312 6681 13312 6679 13313 1249 13313 6680 13313 6680 13314 1249 13314 6681 13314 6680 13315 6681 13315 6682 13315 1249 13316 6683 13316 1246 13316 1246 13317 6683 13317 6684 13317 1246 13318 6684 13318 7514 13318 6679 13319 6970 13319 1249 13319 1249 13320 6970 13320 6685 13320 1249 13321 6685 13321 6683 13321 6683 13322 6685 13322 2562 13322 6688 13323 2556 13323 2555 13323 2562 13324 2560 13324 6683 13324 6683 13325 2560 13325 6686 13325 6683 13326 6686 13326 2556 13326 2555 13327 6687 13327 6688 13327 6688 13328 6687 13328 6689 13328 6688 13329 6689 13329 6681 13329 6681 13330 6689 13330 6974 13330 6681 13331 6974 13331 6682 13331 6431 13332 2132 13332 6690 13332 6690 13333 2132 13333 6692 13333 6690 13334 6692 13334 6691 13334 6691 13335 6692 13335 6694 13335 6691 13336 6694 13336 6693 13336 6948 13337 6947 13337 6694 13337 6694 13338 6947 13338 6944 13338 6694 13339 6944 13339 6693 13339 6693 13340 6944 13340 6695 13340 6693 13341 6695 13341 1243 13341 6832 13342 2588 13342 6833 13342 2588 13343 2587 13343 6833 13343 6833 13344 2587 13344 2586 13344 6833 13345 2586 13345 6694 13345 6694 13346 2586 13346 2584 13346 6694 13347 2584 13347 6948 13347 6469 13348 2590 13348 6832 13348 6695 13349 6696 13349 1243 13349 1243 13350 6696 13350 2593 13350 1243 13351 2593 13351 6469 13351 6469 13352 2593 13352 6697 13352 6469 13353 6697 13353 2590 13353 6451 13354 6953 13354 6698 13354 6698 13355 6953 13355 6699 13355 6698 13356 6699 13356 6700 13356 6700 13357 6699 13357 6951 13357 6700 13358 6951 13358 6701 13358 6702 13359 6451 13359 6955 13359 6955 13360 6451 13360 6703 13360 6955 13361 6703 13361 6705 13361 6706 13362 6704 13362 6708 13362 6708 13363 6704 13363 2582 13363 6708 13364 2582 13364 2580 13364 2580 13365 2579 13365 6703 13365 6703 13366 2579 13366 2578 13366 6703 13367 2578 13367 6705 13367 6701 13368 6706 13368 6700 13368 6700 13369 6706 13369 6708 13369 6700 13370 6708 13370 6707 13370 6707 13371 6708 13371 7413 13371 6707 13372 7413 13372 6709 13372 6709 13373 7415 13373 6707 13373 6707 13374 7415 13374 7417 13374 6707 13375 7417 13375 1240 13375 1240 13376 7417 13376 7416 13376 1240 13377 7416 13377 6710 13377 6710 13378 7416 13378 2153 13378 6710 13379 2153 13379 6561 13379 6711 13380 6712 13380 6713 13380 6713 13381 6712 13381 6714 13381 6713 13382 6714 13382 6708 13382 6708 13383 6714 13383 7410 13383 6708 13384 7410 13384 7413 13384 2153 13385 2154 13385 6561 13385 6561 13386 2154 13386 6715 13386 6561 13387 6715 13387 6713 13387 6713 13388 6715 13388 6716 13388 6713 13389 6716 13389 6711 13389 6719 13390 6720 13390 6718 13390 6937 13391 6717 13391 6799 13391 6718 13392 6720 13392 9178 13392 6799 13393 6717 13393 6718 13393 6718 13394 6717 13394 6935 13394 6718 13395 6935 13395 6719 13395 6720 13396 6721 13396 9178 13396 9178 13397 6721 13397 6722 13397 9178 13398 6722 13398 6826 13398 6826 13399 6722 13399 2595 13399 2595 13400 6723 13400 6826 13400 6826 13401 6723 13401 6941 13401 6826 13402 6941 13402 6798 13402 6798 13403 6941 13403 6724 13403 6798 13404 6724 13404 6939 13404 6730 13405 6933 13405 6931 13405 6787 13406 6725 13406 6786 13406 6725 13407 6726 13407 6786 13407 6786 13408 6726 13408 9171 13408 6786 13409 9171 13409 6621 13409 2603 13410 2601 13410 6728 13410 6725 13411 6927 13411 6726 13411 6726 13412 6927 13412 2607 13412 6726 13413 2607 13413 6727 13413 6727 13414 2607 13414 2606 13414 6727 13415 2606 13415 2604 13415 2601 13416 2600 13416 6728 13416 6728 13417 2600 13417 6729 13417 6728 13418 6729 13418 6730 13418 6730 13419 6729 13419 6731 13419 6730 13420 6731 13420 6933 13420 2604 13421 2603 13421 6727 13421 6727 13422 2603 13422 6728 13422 6727 13423 6728 13423 6732 13423 6732 13424 6728 13424 6569 13424 6732 13425 6569 13425 7694 13425 6606 13426 6733 13426 6607 13426 6607 13427 6733 13427 6602 13427 6607 13428 6602 13428 6734 13428 6734 13429 6602 13429 9166 13429 6745 13430 6735 13430 7182 13430 7181 13431 7180 13431 6736 13431 6736 13432 7180 13432 2350 13432 6736 13433 2350 13433 6585 13433 6585 13434 2350 13434 6737 13434 6737 13435 2352 13435 6585 13435 6585 13436 2352 13436 6738 13436 6585 13437 6738 13437 6420 13437 6420 13438 6738 13438 2355 13438 6420 13439 2355 13439 9162 13439 9162 13440 2355 13440 6739 13440 9162 13441 6739 13441 6419 13441 6419 13442 6739 13442 2356 13442 6419 13443 2356 13443 6745 13443 6745 13444 2356 13444 6740 13444 6745 13445 6740 13445 6735 13445 2361 13446 6741 13446 6742 13446 6742 13447 6741 13447 6743 13447 6742 13448 6743 13448 6916 13448 6916 13449 6743 13449 6918 13449 9161 13450 9160 13450 2616 13450 6916 13451 6915 13451 6742 13451 6742 13452 6915 13452 6744 13452 6742 13453 6744 13453 6745 13453 6745 13454 6744 13454 6746 13454 6745 13455 6746 13455 2620 13455 2616 13456 2615 13456 9161 13456 9161 13457 2615 13457 6747 13457 9161 13458 6747 13458 6743 13458 6743 13459 6747 13459 6748 13459 6743 13460 6748 13460 6918 13460 2620 13461 2618 13461 6745 13461 6745 13462 2618 13462 6749 13462 6745 13463 6749 13463 9160 13463 9160 13464 6749 13464 2617 13464 9160 13465 2617 13465 2616 13465 6909 13466 6752 13466 6797 13466 6755 13467 6753 13467 6750 13467 6750 13468 2622 13468 6755 13468 6755 13469 2622 13469 2621 13469 6755 13470 2621 13470 6757 13470 6909 13471 6751 13471 6752 13471 6752 13472 6751 13472 2626 13472 6752 13473 2626 13473 6753 13473 6753 13474 2626 13474 6754 13474 6753 13475 6754 13475 6750 13475 6541 13476 6554 13476 6557 13476 6557 13477 6554 13477 6755 13477 6557 13478 6755 13478 6756 13478 6756 13479 6755 13479 6757 13479 6756 13480 6757 13480 6758 13480 6759 13481 6760 13481 6797 13481 6797 13482 6760 13482 6761 13482 6797 13483 6761 13483 6909 13483 6643 13484 6642 13484 6762 13484 6762 13485 6642 13485 6781 13485 6762 13486 6781 13486 6423 13486 6423 13487 6781 13487 6763 13487 6423 13488 6763 13488 6765 13488 6765 13489 6763 13489 6742 13489 6765 13490 6742 13490 6766 13490 6766 13491 6742 13491 6745 13491 6766 13492 6745 13492 6736 13492 6736 13493 6745 13493 7182 13493 6736 13494 7182 13494 7181 13494 7924 13495 6423 13495 6764 13495 6764 13496 6423 13496 6765 13496 6764 13497 6765 13497 6771 13497 6771 13498 6765 13498 6766 13498 6771 13499 6766 13499 6772 13499 6772 13500 6766 13500 6736 13500 6772 13501 6736 13501 6773 13501 6773 13502 6736 13502 6767 13502 6773 13503 6767 13503 6768 13503 7888 13504 6764 13504 6769 13504 6769 13505 6764 13505 6771 13505 6769 13506 6771 13506 6770 13506 6770 13507 6771 13507 6772 13507 6770 13508 6772 13508 6777 13508 6777 13509 6772 13509 6773 13509 6777 13510 6773 13510 6778 13510 6778 13511 6773 13511 6584 13511 6778 13512 6584 13512 6774 13512 6774 13513 6584 13513 6923 13513 6774 13514 6923 13514 6599 13514 7887 13515 6769 13515 6775 13515 6775 13516 6769 13516 6770 13516 6775 13517 6770 13517 6776 13517 6776 13518 6770 13518 6777 13518 6776 13519 6777 13519 6730 13519 6730 13520 6777 13520 6778 13520 6730 13521 6778 13521 6728 13521 6728 13522 6778 13522 7688 13522 6728 13523 7688 13523 7693 13523 2735 13524 6809 13524 6779 13524 6779 13525 6809 13525 6811 13525 6779 13526 6811 13526 6642 13526 6642 13527 6811 13527 6780 13527 6642 13528 6780 13528 6781 13528 6781 13529 6780 13529 6782 13529 6781 13530 6782 13530 6763 13530 6763 13531 6782 13531 6608 13531 6763 13532 6608 13532 6783 13532 6380 13533 6784 13533 6785 13533 6785 13534 6784 13534 6775 13534 6785 13535 6775 13535 6789 13535 6789 13536 6775 13536 6776 13536 6789 13537 6776 13537 6620 13537 6620 13538 6776 13538 6730 13538 6620 13539 6730 13539 6786 13539 6786 13540 6730 13540 6931 13540 6786 13541 6931 13541 6787 13541 6383 13542 6788 13542 6646 13542 6646 13543 6788 13543 6785 13543 6646 13544 6785 13544 6818 13544 6818 13545 6785 13545 6789 13545 6818 13546 6789 13546 6632 13546 6632 13547 6789 13547 6620 13547 6632 13548 6620 13548 6631 13548 6631 13549 6620 13549 7680 13549 6631 13550 7680 13550 7681 13550 2649 13551 6657 13551 6790 13551 6790 13552 6657 13552 6659 13552 6790 13553 6659 13553 6791 13553 6791 13554 6659 13554 7167 13554 6791 13555 7167 13555 6792 13555 6793 13556 6794 13556 6669 13556 6669 13557 6794 13557 6790 13557 6669 13558 6790 13558 6800 13558 6800 13559 6790 13559 6791 13559 6800 13560 6791 13560 6795 13560 6795 13561 6791 13561 6756 13561 6795 13562 6756 13562 6797 13562 6797 13563 6756 13563 6796 13563 6797 13564 6796 13564 6759 13564 2580 13565 6703 13565 6708 13565 6708 13566 6703 13566 6824 13566 6708 13567 6824 13567 6713 13567 6713 13568 6824 13568 6825 13568 6713 13569 6825 13569 6560 13569 6560 13570 6825 13570 6798 13570 6560 13571 6798 13571 6799 13571 6799 13572 6798 13572 6939 13572 6799 13573 6939 13573 6937 13573 6499 13574 6665 13574 6498 13574 6498 13575 6665 13575 6669 13575 6498 13576 6669 13576 6806 13576 6806 13577 6669 13577 6800 13577 6806 13578 6800 13578 6801 13578 6801 13579 6800 13579 6795 13579 6801 13580 6795 13580 6802 13580 6802 13581 6795 13581 6797 13581 6802 13582 6797 13582 6808 13582 6808 13583 6797 13583 6752 13583 6808 13584 6752 13584 6803 13584 6803 13585 6752 13585 6804 13585 6803 13586 6804 13586 6805 13586 2533 13587 6498 13587 6827 13587 6827 13588 6498 13588 6806 13588 6827 13589 6806 13589 6807 13589 6807 13590 6806 13590 6801 13590 6807 13591 6801 13591 6638 13591 6638 13592 6801 13592 6802 13592 6638 13593 6802 13593 6641 13593 6641 13594 6802 13594 6808 13594 6641 13595 6808 13595 6809 13595 6809 13596 6808 13596 6803 13596 6809 13597 6803 13597 6811 13597 6811 13598 6803 13598 6810 13598 6811 13599 6810 13599 6780 13599 6780 13600 6810 13600 6596 13600 6780 13601 6596 13601 7236 13601 6455 13602 6830 13602 6822 13602 6822 13603 6830 13603 6812 13603 6822 13604 6812 13604 6823 13604 6823 13605 6812 13605 6813 13605 6823 13606 6813 13606 6814 13606 6814 13607 6813 13607 6815 13607 6814 13608 6815 13608 6816 13608 6816 13609 6815 13609 6646 13609 6816 13610 6646 13610 6817 13610 6817 13611 6646 13611 6818 13611 6817 13612 6818 13612 6650 13612 6650 13613 6818 13613 6632 13613 6650 13614 6632 13614 6819 13614 6819 13615 6632 13615 6820 13615 6819 13616 6820 13616 6821 13616 6446 13617 6822 13617 6451 13617 6451 13618 6822 13618 6823 13618 6451 13619 6823 13619 6703 13619 6703 13620 6823 13620 6814 13620 6703 13621 6814 13621 6824 13621 6824 13622 6814 13622 6816 13622 6824 13623 6816 13623 6825 13623 6825 13624 6816 13624 6817 13624 6825 13625 6817 13625 6798 13625 6798 13626 6817 13626 6650 13626 6798 13627 6650 13627 6826 13627 6826 13628 6650 13628 7671 13628 6826 13629 7671 13629 6651 13629 6371 13630 6836 13630 6637 13630 6637 13631 6836 13631 6510 13631 6637 13632 6510 13632 6827 13632 6827 13633 6510 13633 6500 13633 6827 13634 6500 13634 7028 13634 7028 13635 6500 13635 7029 13635 2137 13636 6466 13636 6467 13636 6467 13637 6466 13637 6828 13637 6467 13638 6828 13638 6830 13638 6830 13639 6828 13639 6829 13639 6830 13640 6829 13640 6812 13640 6812 13641 6829 13641 6387 13641 6812 13642 6387 13642 6813 13642 6813 13643 6387 13643 6831 13643 6813 13644 6831 13644 6386 13644 6832 13645 6833 13645 6469 13645 6469 13646 6833 13646 6838 13646 6469 13647 6838 13647 6466 13647 6466 13648 6838 13648 6647 13648 6466 13649 6647 13649 6828 13649 6828 13650 6647 13650 6390 13650 6828 13651 6390 13651 6829 13651 6829 13652 6390 13652 6388 13652 6829 13653 6388 13653 6387 13653 2631 13654 6675 13654 6834 13654 6834 13655 6675 13655 6515 13655 6834 13656 6515 13656 6509 13656 6509 13657 6515 13657 6512 13657 6509 13658 6512 13658 6835 13658 6835 13659 6512 13659 6510 13659 6835 13660 6510 13660 6841 13660 6841 13661 6510 13661 6836 13661 6841 13662 6836 13662 6842 13662 6465 13663 6464 13663 6694 13663 6694 13664 6464 13664 6837 13664 6694 13665 6837 13665 6833 13665 6833 13666 6837 13666 6843 13666 6833 13667 6843 13667 6838 13667 6838 13668 6843 13668 7839 13668 6838 13669 7839 13669 6391 13669 6477 13670 6478 13670 6476 13670 6476 13671 6478 13671 6509 13671 6476 13672 6509 13672 6839 13672 6839 13673 6509 13673 6835 13673 6839 13674 6835 13674 6840 13674 6840 13675 6835 13675 6841 13675 6840 13676 6841 13676 6844 13676 6844 13677 6841 13677 6842 13677 6844 13678 6842 13678 7848 13678 2556 13679 6688 13679 6683 13679 6683 13680 6688 13680 6476 13680 6683 13681 6476 13681 6463 13681 6463 13682 6476 13682 6839 13682 6463 13683 6839 13683 6464 13683 6464 13684 6839 13684 6840 13684 6464 13685 6840 13685 6837 13685 6837 13686 6840 13686 6844 13686 6837 13687 6844 13687 6843 13687 6843 13688 6844 13688 6424 13688 6843 13689 6424 13689 7843 13689 2652 13690 6845 13690 6893 13690 6893 13691 6845 13691 6847 13691 6893 13692 6847 13692 6846 13692 6846 13693 6847 13693 6848 13693 6846 13694 6848 13694 6849 13694 6849 13695 6848 13695 6853 13695 6849 13696 6853 13696 6850 13696 6850 13697 6853 13697 6855 13697 6850 13698 6855 13698 6851 13698 6851 13699 6855 13699 6852 13699 6851 13700 6852 13700 2648 13700 2648 13701 6852 13701 2717 13701 6845 13702 2708 13702 6847 13702 6847 13703 2708 13703 4276 13703 6847 13704 4276 13704 6848 13704 6848 13705 4276 13705 4274 13705 6848 13706 4274 13706 6853 13706 6853 13707 4274 13707 6854 13707 6853 13708 6854 13708 6855 13708 6855 13709 6854 13709 6856 13709 6855 13710 6856 13710 6852 13710 6852 13711 6856 13711 4271 13711 6852 13712 4271 13712 2717 13712 2717 13713 4271 13713 4270 13713 6897 13714 6861 13714 6857 13714 6857 13715 6861 13715 6858 13715 6857 13716 6858 13716 6896 13716 6896 13717 6858 13717 6862 13717 6896 13718 6862 13718 6859 13718 6859 13719 6862 13719 6860 13719 6859 13720 6860 13720 6895 13720 6895 13721 6860 13721 6863 13721 6895 13722 6863 13722 6894 13722 6894 13723 6863 13723 6864 13723 6894 13724 6864 13724 2647 13724 2647 13725 6864 13725 6865 13725 6861 13726 4265 13726 6858 13726 6858 13727 4265 13727 4264 13727 6858 13728 4264 13728 6862 13728 6862 13729 4264 13729 4262 13729 6862 13730 4262 13730 6860 13730 6860 13731 4262 13731 4261 13731 6860 13732 4261 13732 6863 13732 6863 13733 4261 13733 4260 13733 6863 13734 4260 13734 6864 13734 6864 13735 4260 13735 4259 13735 6864 13736 4259 13736 6865 13736 6865 13737 4259 13737 6866 13737 6867 13738 2676 13738 6868 13738 6868 13739 2676 13739 6869 13739 6868 13740 6869 13740 6901 13740 6901 13741 6869 13741 6870 13741 6901 13742 6870 13742 6900 13742 6900 13743 6870 13743 6871 13743 6900 13744 6871 13744 6872 13744 6872 13745 6871 13745 6873 13745 6872 13746 6873 13746 6898 13746 6898 13747 6873 13747 6878 13747 6898 13748 6878 13748 2640 13748 2640 13749 6878 13749 6874 13749 2676 13750 6875 13750 6869 13750 6869 13751 6875 13751 4251 13751 6869 13752 4251 13752 6870 13752 6870 13753 4251 13753 6876 13753 6870 13754 6876 13754 6871 13754 6871 13755 6876 13755 4250 13755 6871 13756 4250 13756 6873 13756 6873 13757 4250 13757 4248 13757 6873 13758 4248 13758 6878 13758 6878 13759 4248 13759 6877 13759 6878 13760 6877 13760 6874 13760 6874 13761 6877 13761 2683 13761 2628 13762 2658 13762 6879 13762 6879 13763 2658 13763 6880 13763 6879 13764 6880 13764 6905 13764 6905 13765 6880 13765 6886 13765 6905 13766 6886 13766 6881 13766 6881 13767 6886 13767 6888 13767 6881 13768 6888 13768 6882 13768 6882 13769 6888 13769 6889 13769 6882 13770 6889 13770 6883 13770 6883 13771 6889 13771 6884 13771 6883 13772 6884 13772 2634 13772 2634 13773 6884 13773 6890 13773 2658 13774 4237 13774 6880 13774 6880 13775 4237 13775 6885 13775 6880 13776 6885 13776 6886 13776 6886 13777 6885 13777 6887 13777 6886 13778 6887 13778 6888 13778 6888 13779 6887 13779 4239 13779 6888 13780 4239 13780 6889 13780 6889 13781 4239 13781 4240 13781 6889 13782 4240 13782 6884 13782 6884 13783 4240 13783 4241 13783 6884 13784 4241 13784 6890 13784 6890 13785 4241 13785 4229 13785 2648 13786 6539 13786 6851 13786 6851 13787 6539 13787 6891 13787 6851 13788 6891 13788 6850 13788 6850 13789 6891 13789 6426 13789 6850 13790 6426 13790 6849 13790 6849 13791 6426 13791 6671 13791 6849 13792 6671 13792 6846 13792 6846 13793 6671 13793 6892 13793 6846 13794 6892 13794 6893 13794 6893 13795 6892 13795 6536 13795 6893 13796 6536 13796 2652 13796 2652 13797 6536 13797 2654 13797 2647 13798 6496 13798 6894 13798 6894 13799 6496 13799 6495 13799 6894 13800 6495 13800 6895 13800 6895 13801 6495 13801 6494 13801 6895 13802 6494 13802 6859 13802 6859 13803 6494 13803 6493 13803 6859 13804 6493 13804 6896 13804 6896 13805 6493 13805 6491 13805 6896 13806 6491 13806 6857 13806 6857 13807 6491 13807 6487 13807 6857 13808 6487 13808 6897 13808 6897 13809 6487 13809 2641 13809 2640 13810 6899 13810 6898 13810 6898 13811 6899 13811 6518 13811 6898 13812 6518 13812 6872 13812 6872 13813 6518 13813 6525 13813 6872 13814 6525 13814 6900 13814 6900 13815 6525 13815 6524 13815 6900 13816 6524 13816 6901 13816 6901 13817 6524 13817 6902 13817 6901 13818 6902 13818 6868 13818 6868 13819 6902 13819 6523 13819 6868 13820 6523 13820 6867 13820 6867 13821 6523 13821 2635 13821 2634 13822 6903 13822 6883 13822 6883 13823 6903 13823 6904 13823 6883 13824 6904 13824 6882 13824 6882 13825 6904 13825 6505 13825 6882 13826 6505 13826 6881 13826 6881 13827 6505 13827 6906 13827 6881 13828 6906 13828 6905 13828 6905 13829 6906 13829 6907 13829 6905 13830 6907 13830 6879 13830 6879 13831 6907 13831 6908 13831 6879 13832 6908 13832 2628 13832 2628 13833 6908 13833 6503 13833 2627 13834 6909 13834 9311 13834 9311 13835 6909 13835 6761 13835 9311 13836 6761 13836 6910 13836 6910 13837 6761 13837 6760 13837 6910 13838 6760 13838 6911 13838 6911 13839 6760 13839 6759 13839 6911 13840 6759 13840 6912 13840 6912 13841 6759 13841 6796 13841 6912 13842 6796 13842 6913 13842 6913 13843 6796 13843 6758 13843 6913 13844 6758 13844 9315 13844 9315 13845 6758 13845 6757 13845 9315 13846 6757 13846 9313 13846 9313 13847 6757 13847 2621 13847 9310 13848 6746 13848 6914 13848 6914 13849 6746 13849 6744 13849 6914 13850 6744 13850 9309 13850 9309 13851 6744 13851 6915 13851 9309 13852 6915 13852 9306 13852 9306 13853 6915 13853 6916 13853 9306 13854 6916 13854 6917 13854 6917 13855 6916 13855 6918 13855 6917 13856 6918 13856 9304 13856 9304 13857 6918 13857 6748 13857 9304 13858 6748 13858 6919 13858 6919 13859 6748 13859 6747 13859 9300 13860 6920 13860 6921 13860 6921 13861 6920 13861 6600 13861 6921 13862 6600 13862 9299 13862 9299 13863 6600 13863 6599 13863 9299 13864 6599 13864 6922 13864 6922 13865 6599 13865 6923 13865 6922 13866 6923 13866 9297 13866 9297 13867 6923 13867 6924 13867 9297 13868 6924 13868 9298 13868 9298 13869 6924 13869 6926 13869 9298 13870 6926 13870 6925 13870 6925 13871 6926 13871 2608 13871 9292 13872 6927 13872 6928 13872 6928 13873 6927 13873 6725 13873 6928 13874 6725 13874 6929 13874 6929 13875 6725 13875 6787 13875 6929 13876 6787 13876 6930 13876 6930 13877 6787 13877 6931 13877 6930 13878 6931 13878 6932 13878 6932 13879 6931 13879 6933 13879 6932 13880 6933 13880 9294 13880 9294 13881 6933 13881 6731 13881 9294 13882 6731 13882 9295 13882 9295 13883 6731 13883 6729 13883 6934 13884 6719 13884 9289 13884 9289 13885 6719 13885 6935 13885 9289 13886 6935 13886 6936 13886 6936 13887 6935 13887 6717 13887 6936 13888 6717 13888 9290 13888 9290 13889 6717 13889 6937 13889 9290 13890 6937 13890 6938 13890 6938 13891 6937 13891 6939 13891 6938 13892 6939 13892 9288 13892 9288 13893 6939 13893 6724 13893 9288 13894 6724 13894 6940 13894 6940 13895 6724 13895 6941 13895 2592 13896 2593 13896 6942 13896 6942 13897 2593 13897 6696 13897 6942 13898 6696 13898 6943 13898 6943 13899 6696 13899 6695 13899 6943 13900 6695 13900 9285 13900 9285 13901 6695 13901 6944 13901 9285 13902 6944 13902 6945 13902 6945 13903 6944 13903 6947 13903 6945 13904 6947 13904 6946 13904 6946 13905 6947 13905 6948 13905 6946 13906 6948 13906 6949 13906 6949 13907 6948 13907 2584 13907 2583 13908 6706 13908 9280 13908 9280 13909 6706 13909 6701 13909 9280 13910 6701 13910 9279 13910 9279 13911 6701 13911 6951 13911 9279 13912 6951 13912 6950 13912 6950 13913 6951 13913 6699 13913 6950 13914 6699 13914 6952 13914 6952 13915 6699 13915 6953 13915 6952 13916 6953 13916 9281 13916 9281 13917 6953 13917 6702 13917 9281 13918 6702 13918 6954 13918 6954 13919 6702 13919 6955 13919 9273 13920 2575 13920 9272 13920 9272 13921 2575 13921 6668 13921 9272 13922 6668 13922 6956 13922 6956 13923 6668 13923 6663 13923 6956 13924 6663 13924 9270 13924 9270 13925 6663 13925 6957 13925 9270 13926 6957 13926 6958 13926 6958 13927 6957 13927 6959 13927 6958 13928 6959 13928 6960 13928 6960 13929 6959 13929 6664 13929 6960 13930 6664 13930 6961 13930 6961 13931 6664 13931 2569 13931 2568 13932 6514 13932 9263 13932 9263 13933 6514 13933 6516 13933 9263 13934 6516 13934 6962 13934 6962 13935 6516 13935 6517 13935 6962 13936 6517 13936 9267 13936 9267 13937 6517 13937 6676 13937 9267 13938 6676 13938 6963 13938 6963 13939 6676 13939 6965 13939 6963 13940 6965 13940 6964 13940 6964 13941 6965 13941 6966 13941 6964 13942 6966 13942 9266 13942 9266 13943 6966 13943 6967 13943 9266 13944 6967 13944 9264 13944 9264 13945 6967 13945 6520 13945 9262 13946 6685 13946 6968 13946 6968 13947 6685 13947 6970 13947 6968 13948 6970 13948 6969 13948 6969 13949 6970 13949 6679 13949 6969 13950 6679 13950 9261 13950 9261 13951 6679 13951 6680 13951 9261 13952 6680 13952 6971 13952 6971 13953 6680 13953 6682 13953 6971 13954 6682 13954 6972 13954 6972 13955 6682 13955 6974 13955 6972 13956 6974 13956 6973 13956 6973 13957 6974 13957 6689 13957 6975 13958 2547 13958 6976 13958 6976 13959 2547 13959 2548 13959 6976 13960 2548 13960 2510 13960 2510 13961 2548 13961 2550 13961 2510 13962 2550 13962 6977 13962 6977 13963 2550 13963 2551 13963 6977 13964 2551 13964 6978 13964 6978 13965 2551 13965 6979 13965 6978 13966 6979 13966 7057 13966 7057 13967 6979 13967 6989 13967 7057 13968 6989 13968 6980 13968 6980 13969 6989 13969 6981 13969 6980 13970 6981 13970 6982 13970 6982 13971 6981 13971 6983 13971 6982 13972 6983 13972 7060 13972 7060 13973 6983 13973 6984 13973 7060 13974 6984 13974 6985 13974 6985 13975 6984 13975 6994 13975 6985 13976 6994 13976 6986 13976 6986 13977 6994 13977 6987 13977 6986 13978 6987 13978 2506 13978 2506 13979 6987 13979 2544 13979 2506 13980 2544 13980 2508 13980 2508 13981 2544 13981 6988 13981 2508 13982 6988 13982 6975 13982 6975 13983 6988 13983 2547 13983 2551 13984 2552 13984 6979 13984 6979 13985 2552 13985 6990 13985 6979 13986 6990 13986 6989 13986 6989 13987 6990 13987 6991 13987 6989 13988 6991 13988 6981 13988 6981 13989 6991 13989 6998 13989 6981 13990 6998 13990 6983 13990 6983 13991 6998 13991 6992 13991 6983 13992 6992 13992 6984 13992 6984 13993 6992 13993 6993 13993 6984 13994 6993 13994 6994 13994 6994 13995 6993 13995 6995 13995 2552 13996 6996 13996 6990 13996 6990 13997 6996 13997 6997 13997 6990 13998 6997 13998 6991 13998 6991 13999 6997 13999 6658 13999 6991 14000 6658 14000 6998 14000 6998 14001 6658 14001 6999 14001 6998 14002 6999 14002 6992 14002 6992 14003 6999 14003 7000 14003 6992 14004 7000 14004 6993 14004 6993 14005 7000 14005 7001 14005 6993 14006 7001 14006 6995 14006 6995 14007 7001 14007 7002 14007 7015 14008 7017 14008 7074 14008 7074 14009 7017 14009 7004 14009 7074 14010 7004 14010 7003 14010 7003 14011 7004 14011 7021 14011 7003 14012 7021 14012 7077 14012 7077 14013 7021 14013 7023 14013 7077 14014 7023 14014 7078 14014 7078 14015 7023 14015 7005 14015 7078 14016 7005 14016 2486 14016 2486 14017 7005 14017 7026 14017 2486 14018 7026 14018 7006 14018 7006 14019 7026 14019 7007 14019 7006 14020 7007 14020 7008 14020 7008 14021 7007 14021 2535 14021 7008 14022 2535 14022 7009 14022 7009 14023 2535 14023 7010 14023 7009 14024 7010 14024 7011 14024 7011 14025 7010 14025 2537 14025 7011 14026 2537 14026 2491 14026 2491 14027 2537 14027 7012 14027 2491 14028 7012 14028 7072 14028 7072 14029 7012 14029 7014 14029 7072 14030 7014 14030 7013 14030 7013 14031 7014 14031 7016 14031 7013 14032 7016 14032 7015 14032 7015 14033 7016 14033 7017 14033 7014 14034 7027 14034 7016 14034 7016 14035 7027 14035 7018 14035 7016 14036 7018 14036 7017 14036 7017 14037 7018 14037 7019 14037 7017 14038 7019 14038 7004 14038 7004 14039 7019 14039 7020 14039 7004 14040 7020 14040 7021 14040 7021 14041 7020 14041 7022 14041 7021 14042 7022 14042 7023 14042 7023 14043 7022 14043 7024 14043 7023 14044 7024 14044 7005 14044 7005 14045 7024 14045 7025 14045 7005 14046 7025 14046 7026 14046 7026 14047 7025 14047 2534 14047 7027 14048 7028 14048 7018 14048 7018 14049 7028 14049 7029 14049 7018 14050 7029 14050 7019 14050 7019 14051 7029 14051 7030 14051 7019 14052 7030 14052 7020 14052 7020 14053 7030 14053 6501 14053 7020 14054 6501 14054 7022 14054 7022 14055 6501 14055 6485 14055 7022 14056 6485 14056 7024 14056 7024 14057 6485 14057 7031 14057 7024 14058 7031 14058 7025 14058 7025 14059 7031 14059 6489 14059 7025 14060 6489 14060 2534 14060 2534 14061 6489 14061 6488 14061 7047 14062 7033 14062 7032 14062 7032 14063 7033 14063 2521 14063 7032 14064 2521 14064 2471 14064 2471 14065 2521 14065 7034 14065 2471 14066 7034 14066 2473 14066 2473 14067 7034 14067 2523 14067 2473 14068 2523 14068 7036 14068 7036 14069 2523 14069 7035 14069 7036 14070 7035 14070 2475 14070 2475 14071 7035 14071 7037 14071 2475 14072 7037 14072 7038 14072 7038 14073 7037 14073 2525 14073 7038 14074 2525 14074 7096 14074 7096 14075 2525 14075 7048 14075 7096 14076 7048 14076 7039 14076 7039 14077 7048 14077 7049 14077 7039 14078 7049 14078 7040 14078 7040 14079 7049 14079 7042 14079 7040 14080 7042 14080 7041 14080 7041 14081 7042 14081 7043 14081 7041 14082 7043 14082 7044 14082 7044 14083 7043 14083 7046 14083 7044 14084 7046 14084 7045 14084 7045 14085 7046 14085 7054 14085 7045 14086 7054 14086 7047 14086 7047 14087 7054 14087 7033 14087 2525 14088 2519 14088 7048 14088 7048 14089 2519 14089 7050 14089 7048 14090 7050 14090 7049 14090 7049 14091 7050 14091 7051 14091 7049 14092 7051 14092 7042 14092 7042 14093 7051 14093 7052 14093 7042 14094 7052 14094 7043 14094 7043 14095 7052 14095 7053 14095 7043 14096 7053 14096 7046 14096 7046 14097 7053 14097 7055 14097 7046 14098 7055 14098 7054 14098 7054 14099 7055 14099 2520 14099 2519 14100 6475 14100 7050 14100 7050 14101 6475 14101 6474 14101 7050 14102 6474 14102 7051 14102 7051 14103 6474 14103 6678 14103 7051 14104 6678 14104 7052 14104 7052 14105 6678 14105 6677 14105 7052 14106 6677 14106 7053 14106 7053 14107 6677 14107 6481 14107 7053 14108 6481 14108 7055 14108 7055 14109 6481 14109 6483 14109 7055 14110 6483 14110 2520 14110 2520 14111 6483 14111 6506 14111 2497 14112 6977 14112 7063 14112 7063 14113 6977 14113 6978 14113 7063 14114 6978 14114 7056 14114 7056 14115 6978 14115 7057 14115 7056 14116 7057 14116 7062 14116 7062 14117 7057 14117 6980 14117 7062 14118 6980 14118 7061 14118 7061 14119 6980 14119 6982 14119 7061 14120 6982 14120 7058 14120 7058 14121 6982 14121 7060 14121 7058 14122 7060 14122 7059 14122 7059 14123 7060 14123 6985 14123 7059 14124 7064 14124 7058 14124 7058 14125 7064 14125 7066 14125 7058 14126 7066 14126 7061 14126 7061 14127 7066 14127 7067 14127 7061 14128 7067 14128 7062 14128 7062 14129 7067 14129 7068 14129 7062 14130 7068 14130 7056 14130 7056 14131 7068 14131 7069 14131 7056 14132 7069 14132 7063 14132 7063 14133 7069 14133 7071 14133 7063 14134 7071 14134 2497 14134 2497 14135 7071 14135 2498 14135 7064 14136 7065 14136 7066 14136 7066 14137 7065 14137 4286 14137 7066 14138 4286 14138 7067 14138 7067 14139 4286 14139 4285 14139 7067 14140 4285 14140 7068 14140 7068 14141 4285 14141 7070 14141 7068 14142 7070 14142 7069 14142 7069 14143 7070 14143 4283 14143 7069 14144 4283 14144 7071 14144 7071 14145 4283 14145 4282 14145 7071 14146 4282 14146 2498 14146 2498 14147 4282 14147 4281 14147 2481 14148 7072 14148 7084 14148 7084 14149 7072 14149 7013 14149 7084 14150 7013 14150 7073 14150 7073 14151 7013 14151 7015 14151 7073 14152 7015 14152 7082 14152 7082 14153 7015 14153 7074 14153 7082 14154 7074 14154 7075 14154 7075 14155 7074 14155 7003 14155 7075 14156 7003 14156 7076 14156 7076 14157 7003 14157 7077 14157 7076 14158 7077 14158 7080 14158 7080 14159 7077 14159 7078 14159 7080 14160 7078 14160 7079 14160 7079 14161 7078 14161 2486 14161 7079 14162 2479 14162 7080 14162 7080 14163 2479 14163 7088 14163 7080 14164 7088 14164 7076 14164 7076 14165 7088 14165 7089 14165 7076 14166 7089 14166 7075 14166 7075 14167 7089 14167 7081 14167 7075 14168 7081 14168 7082 14168 7082 14169 7081 14169 7083 14169 7082 14170 7083 14170 7073 14170 7073 14171 7083 14171 7093 14171 7073 14172 7093 14172 7084 14172 7084 14173 7093 14173 7085 14173 7084 14174 7085 14174 2481 14174 2481 14175 7085 14175 7086 14175 2479 14176 7087 14176 7088 14176 7088 14177 7087 14177 7090 14177 7088 14178 7090 14178 7089 14178 7089 14179 7090 14179 7091 14179 7089 14180 7091 14180 7081 14180 7081 14181 7091 14181 4215 14181 7081 14182 4215 14182 7083 14182 7083 14183 4215 14183 7092 14183 7083 14184 7092 14184 7093 14184 7093 14185 7092 14185 7094 14185 7093 14186 7094 14186 7085 14186 7085 14187 7094 14187 4227 14187 7085 14188 4227 14188 7086 14188 7086 14189 4227 14189 4226 14189 2462 14190 7038 14190 7104 14190 7104 14191 7038 14191 7096 14191 7104 14192 7096 14192 7095 14192 7095 14193 7096 14193 7039 14193 7095 14194 7039 14194 7101 14194 7101 14195 7039 14195 7040 14195 7101 14196 7040 14196 7097 14196 7097 14197 7040 14197 7041 14197 7097 14198 7041 14198 7098 14198 7098 14199 7041 14199 7044 14199 7098 14200 7044 14200 2469 14200 2469 14201 7044 14201 7045 14201 2469 14202 7099 14202 7098 14202 7098 14203 7099 14203 7100 14203 7098 14204 7100 14204 7097 14204 7097 14205 7100 14205 7106 14205 7097 14206 7106 14206 7101 14206 7101 14207 7106 14207 7102 14207 7101 14208 7102 14208 7095 14208 7095 14209 7102 14209 7103 14209 7095 14210 7103 14210 7104 14210 7104 14211 7103 14211 7105 14211 7104 14212 7105 14212 2462 14212 2462 14213 7105 14213 7111 14213 7099 14214 4212 14214 7100 14214 7100 14215 4212 14215 7107 14215 7100 14216 7107 14216 7106 14216 7106 14217 7107 14217 7108 14217 7106 14218 7108 14218 7102 14218 7102 14219 7108 14219 4208 14219 7102 14220 4208 14220 7103 14220 7103 14221 4208 14221 7109 14221 7103 14222 7109 14222 7105 14222 7105 14223 7109 14223 7110 14223 7105 14224 7110 14224 7111 14224 7111 14225 7110 14225 4205 14225 2458 14226 2447 14226 7113 14226 7113 14227 2447 14227 7112 14227 7113 14228 7112 14228 7161 14228 7161 14229 7112 14229 7114 14229 7114 14230 7112 14230 7116 14230 7114 14231 7116 14231 7115 14231 7115 14232 7116 14232 7163 14232 7163 14233 7116 14233 7117 14233 7163 14234 7117 14234 7164 14234 7164 14235 7117 14235 7118 14235 7118 14236 7117 14236 7119 14236 7118 14237 7119 14237 7120 14237 7120 14238 7119 14238 7121 14238 7121 14239 7119 14239 7126 14239 7121 14240 7126 14240 7122 14240 7122 14241 7126 14241 7123 14241 7123 14242 7126 14242 2448 14242 7123 14243 2448 14243 7166 14243 2447 14244 4299 14244 7112 14244 7112 14245 4299 14245 7124 14245 7112 14246 7124 14246 7116 14246 7116 14247 7124 14247 4298 14247 7116 14248 4298 14248 7117 14248 7117 14249 4298 14249 7125 14249 7117 14250 7125 14250 7119 14250 7119 14251 7125 14251 7127 14251 7119 14252 7127 14252 7126 14252 7126 14253 7127 14253 4295 14253 7126 14254 4295 14254 2448 14254 2448 14255 4295 14255 2438 14255 7174 14256 7128 14256 7173 14256 7173 14257 7128 14257 7129 14257 7173 14258 7129 14258 7130 14258 7130 14259 7129 14259 7131 14259 7130 14260 7131 14260 7171 14260 7171 14261 7131 14261 7133 14261 7171 14262 7133 14262 7170 14262 7170 14263 7133 14263 7134 14263 7170 14264 7134 14264 7168 14264 7168 14265 7134 14265 7135 14265 7168 14266 7135 14266 2428 14266 2428 14267 7135 14267 7136 14267 7128 14268 4313 14268 7129 14268 7129 14269 4313 14269 4311 14269 7129 14270 4311 14270 7131 14270 7131 14271 4311 14271 7132 14271 7131 14272 7132 14272 7133 14272 7133 14273 7132 14273 4309 14273 7133 14274 4309 14274 7134 14274 7134 14275 4309 14275 4308 14275 7134 14276 4308 14276 7135 14276 7135 14277 4308 14277 4307 14277 7135 14278 4307 14278 7136 14278 7136 14279 4307 14279 2425 14279 2358 14280 7138 14280 7137 14280 7137 14281 7138 14281 7144 14281 7137 14282 7144 14282 7139 14282 7139 14283 7144 14283 7141 14283 7139 14284 7141 14284 7140 14284 7140 14285 7141 14285 7146 14285 7140 14286 7146 14286 7176 14286 7176 14287 7146 14287 7148 14287 7176 14288 7148 14288 7142 14288 7142 14289 7148 14289 7143 14289 7142 14290 7143 14290 2408 14290 2408 14291 7143 14291 2410 14291 7138 14292 4320 14292 7144 14292 7144 14293 4320 14293 7145 14293 7144 14294 7145 14294 7141 14294 7141 14295 7145 14295 4317 14295 7141 14296 4317 14296 7146 14296 7146 14297 4317 14297 7147 14297 7146 14298 7147 14298 7148 14298 7148 14299 7147 14299 7149 14299 7148 14300 7149 14300 7143 14300 7143 14301 7149 14301 7150 14301 7143 14302 7150 14302 2410 14302 2410 14303 7150 14303 2400 14303 7185 14304 2397 14304 7184 14304 7184 14305 2397 14305 7156 14305 7184 14306 7156 14306 7183 14306 7183 14307 7156 14307 7157 14307 7183 14308 7157 14308 7152 14308 7152 14309 7157 14309 7151 14309 7152 14310 7151 14310 7154 14310 7154 14311 7151 14311 7153 14311 7154 14312 7153 14312 7179 14312 7179 14313 7153 14313 7155 14313 7179 14314 7155 14314 2388 14314 2388 14315 7155 14315 2389 14315 2397 14316 2387 14316 7156 14316 7156 14317 2387 14317 7158 14317 7156 14318 7158 14318 7157 14318 7157 14319 7158 14319 4331 14319 7157 14320 4331 14320 7151 14320 7151 14321 4331 14321 4329 14321 7151 14322 4329 14322 7153 14322 7153 14323 4329 14323 7159 14323 7153 14324 7159 14324 7155 14324 7155 14325 7159 14325 7160 14325 7155 14326 7160 14326 2389 14326 2389 14327 7160 14327 4327 14327 6550 14328 2378 14328 2458 14328 2458 14329 7113 14329 6550 14329 6550 14330 7113 14330 7161 14330 6550 14331 7161 14331 7162 14331 7161 14332 7114 14332 7162 14332 7162 14333 7114 14333 7115 14333 7162 14334 7115 14334 6552 14334 7115 14335 7163 14335 6552 14335 6552 14336 7163 14336 7164 14336 6552 14337 7164 14337 6546 14337 6546 14338 7164 14338 7118 14338 6546 14339 7118 14339 7165 14339 7118 14340 7120 14340 7165 14340 7165 14341 7120 14341 7121 14341 7165 14342 7121 14342 7167 14342 7166 14343 6792 14343 7123 14343 7123 14344 6792 14344 7167 14344 7123 14345 7167 14345 7122 14345 7122 14346 7167 14346 7121 14346 2428 14347 7169 14347 7168 14347 7168 14348 7169 14348 6633 14348 7168 14349 6633 14349 7170 14349 7170 14350 6633 14350 6805 14350 7170 14351 6805 14351 7171 14351 7171 14352 6805 14352 6804 14352 7171 14353 6804 14353 7130 14353 7130 14354 6804 14354 7172 14354 7130 14355 7172 14355 7173 14355 7173 14356 7172 14356 6636 14356 7173 14357 6636 14357 7174 14357 7174 14358 6636 14358 7175 14358 2408 14359 6612 14359 7142 14359 7142 14360 6612 14360 7177 14360 7142 14361 7177 14361 7176 14361 7176 14362 7177 14362 6783 14362 7176 14363 6783 14363 7140 14363 7140 14364 6783 14364 6608 14364 7140 14365 6608 14365 7139 14365 7139 14366 6608 14366 6609 14366 7139 14367 6609 14367 7137 14367 7137 14368 6609 14368 7178 14368 7137 14369 7178 14369 2358 14369 2358 14370 7178 14370 6593 14370 2388 14371 2350 14371 7179 14371 7179 14372 2350 14372 7180 14372 7179 14373 7180 14373 7154 14373 7154 14374 7180 14374 7181 14374 7154 14375 7181 14375 7152 14375 7152 14376 7181 14376 7182 14376 7152 14377 7182 14377 7183 14377 7183 14378 7182 14378 6735 14378 7183 14379 6735 14379 7184 14379 7184 14380 6735 14380 6740 14380 7184 14381 6740 14381 7185 14381 7185 14382 6740 14382 2356 14382 7197 14383 7202 14383 7186 14383 7186 14384 7202 14384 7203 14384 7186 14385 7203 14385 7187 14385 7187 14386 7203 14386 7205 14386 7187 14387 7205 14387 7188 14387 7188 14388 7205 14388 7207 14388 7188 14389 7207 14389 2307 14389 2307 14390 7207 14390 7190 14390 2307 14391 7190 14391 7189 14391 7189 14392 7190 14392 2342 14392 7189 14393 2342 14393 7191 14393 7191 14394 2342 14394 7192 14394 7191 14395 7192 14395 7193 14395 7193 14396 7192 14396 2345 14396 7193 14397 2345 14397 7194 14397 7194 14398 2345 14398 2346 14398 7194 14399 2346 14399 2304 14399 2304 14400 2346 14400 2348 14400 2304 14401 2348 14401 2303 14401 2303 14402 2348 14402 7196 14402 2303 14403 7196 14403 7195 14403 7195 14404 7196 14404 7198 14404 7195 14405 7198 14405 7267 14405 7267 14406 7198 14406 7197 14406 7267 14407 7197 14407 7186 14407 7196 14408 2341 14408 7213 14408 7196 14409 7213 14409 7198 14409 7198 14410 7213 14410 7199 14410 7198 14411 7199 14411 7197 14411 7197 14412 7199 14412 7200 14412 7197 14413 7200 14413 7202 14413 7200 14414 7201 14414 7202 14414 7202 14415 7201 14415 7204 14415 7202 14416 7204 14416 7203 14416 7204 14417 7212 14417 7203 14417 7203 14418 7212 14418 7206 14418 7203 14419 7206 14419 7205 14419 7206 14420 7211 14420 7205 14420 7205 14421 7211 14421 7210 14421 7205 14422 7210 14422 7207 14422 7207 14423 7210 14423 2337 14423 7207 14424 2337 14424 7190 14424 6542 14425 2337 14425 7208 14425 7208 14426 2337 14426 7210 14426 7208 14427 7210 14427 7209 14427 7210 14428 7211 14428 7209 14428 7209 14429 7211 14429 7206 14429 7209 14430 7206 14430 6545 14430 6545 14431 7206 14431 7212 14431 7212 14432 7204 14432 6545 14432 6545 14433 7204 14433 7201 14433 6545 14434 7201 14434 6544 14434 2341 14435 6548 14435 7213 14435 7213 14436 6548 14436 6547 14436 7213 14437 6547 14437 7199 14437 7199 14438 6547 14438 6544 14438 7199 14439 6544 14439 7200 14439 7200 14440 6544 14440 7201 14440 7286 14441 7215 14441 7214 14441 7214 14442 7215 14442 7228 14442 7228 14443 7215 14443 7216 14443 7228 14444 7216 14444 7227 14444 7227 14445 7216 14445 2279 14445 7227 14446 2279 14446 2334 14446 2334 14447 2279 14447 2280 14447 2334 14448 2280 14448 7217 14448 7217 14449 2280 14449 7226 14449 7217 14450 7226 14450 7218 14450 7214 14451 7230 14451 7286 14451 7286 14452 7230 14452 7232 14452 7286 14453 7232 14453 7219 14453 7219 14454 7232 14454 7220 14454 7219 14455 7220 14455 7288 14455 7288 14456 7220 14456 7221 14456 7288 14457 7221 14457 7222 14457 7222 14458 7221 14458 7223 14458 7222 14459 7223 14459 2287 14459 2287 14460 7223 14460 2330 14460 2287 14461 2330 14461 7224 14461 7224 14462 2330 14462 2333 14462 7224 14463 2333 14463 7225 14463 7225 14464 2333 14464 7218 14464 7225 14465 7218 14465 2282 14465 2282 14466 7218 14466 7226 14466 7227 14467 2336 14467 7228 14467 7228 14468 2336 14468 7234 14468 7228 14469 7234 14469 7214 14469 7214 14470 7234 14470 7229 14470 7214 14471 7229 14471 7230 14471 7230 14472 7229 14472 7231 14472 7230 14473 7231 14473 7232 14473 7232 14474 7231 14474 7237 14474 7232 14475 7237 14475 7220 14475 7220 14476 7237 14476 7233 14476 7220 14477 7233 14477 7221 14477 7221 14478 7233 14478 7239 14478 7221 14479 7239 14479 7223 14479 7223 14480 7239 14480 2329 14480 2336 14481 6610 14481 7234 14481 7234 14482 6610 14482 7235 14482 7234 14483 7235 14483 7229 14483 7229 14484 7235 14484 7236 14484 7229 14485 7236 14485 7231 14485 7231 14486 7236 14486 6596 14486 7231 14487 6596 14487 7237 14487 7237 14488 6596 14488 7238 14488 7237 14489 7238 14489 7233 14489 7233 14490 7238 14490 6597 14490 7233 14491 6597 14491 7239 14491 7239 14492 6597 14492 7240 14492 7239 14493 7240 14493 2329 14493 2329 14494 7240 14494 7241 14494 7308 14495 7260 14495 2262 14495 2262 14496 7260 14496 7242 14496 2262 14497 7242 14497 2263 14497 2263 14498 7242 14498 7243 14498 2263 14499 7243 14499 7244 14499 7244 14500 7243 14500 2320 14500 7244 14501 2320 14501 7245 14501 7245 14502 2320 14502 2321 14502 7245 14503 2321 14503 2259 14503 2259 14504 2321 14504 2324 14504 2259 14505 2324 14505 2257 14505 2257 14506 2324 14506 7246 14506 2257 14507 7246 14507 7319 14507 7319 14508 7246 14508 7251 14508 7319 14509 7251 14509 7247 14509 7247 14510 7251 14510 7254 14510 7247 14511 7254 14511 7316 14511 7316 14512 7254 14512 7255 14512 7316 14513 7255 14513 7315 14513 7315 14514 7255 14514 7248 14514 7315 14515 7248 14515 7249 14515 7249 14516 7248 14516 7258 14516 7249 14517 7258 14517 7312 14517 7312 14518 7258 14518 7250 14518 7312 14519 7250 14519 7308 14519 7308 14520 7250 14520 7260 14520 7251 14521 7252 14521 7254 14521 7254 14522 7252 14522 7253 14522 7254 14523 7253 14523 7255 14523 7255 14524 7253 14524 7256 14524 7255 14525 7256 14525 7248 14525 7248 14526 7256 14526 7257 14526 7248 14527 7257 14527 7258 14527 7258 14528 7257 14528 7263 14528 7258 14529 7263 14529 7250 14529 7250 14530 7263 14530 7259 14530 7250 14531 7259 14531 7260 14531 7260 14532 7259 14532 7261 14532 7260 14533 7261 14533 7242 14533 7242 14534 7261 14534 2318 14534 7252 14535 7262 14535 7253 14535 7253 14536 7262 14536 6588 14536 7253 14537 6588 14537 7256 14537 7256 14538 6588 14538 6768 14538 7256 14539 6768 14539 7257 14539 7257 14540 6768 14540 6767 14540 7257 14541 6767 14541 7263 14541 7263 14542 6767 14542 6587 14542 7263 14543 6587 14543 7259 14543 7259 14544 6587 14544 6586 14544 7259 14545 6586 14545 7261 14545 7261 14546 6586 14546 7264 14546 7261 14547 7264 14547 2318 14547 2318 14548 7264 14548 2311 14548 7274 14549 2303 14549 7265 14549 7265 14550 2303 14550 7195 14550 7265 14551 7195 14551 7271 14551 7271 14552 7195 14552 7267 14552 7271 14553 7267 14553 7266 14553 7266 14554 7267 14554 7186 14554 7266 14555 7186 14555 7268 14555 7268 14556 7186 14556 7187 14556 7268 14557 7187 14557 7270 14557 7270 14558 7187 14558 7188 14558 7270 14559 7188 14559 7269 14559 7269 14560 7188 14560 2307 14560 7269 14561 2302 14561 7270 14561 7270 14562 2302 14562 7275 14562 7270 14563 7275 14563 7268 14563 7268 14564 7275 14564 7278 14564 7268 14565 7278 14565 7266 14565 7266 14566 7278 14566 7272 14566 7266 14567 7272 14567 7271 14567 7271 14568 7272 14568 7273 14568 7271 14569 7273 14569 7265 14569 7265 14570 7273 14570 7282 14570 7265 14571 7282 14571 7274 14571 7274 14572 7282 14572 2288 14572 2302 14573 2294 14573 7275 14573 7275 14574 2294 14574 7276 14574 7275 14575 7276 14575 7278 14575 7278 14576 7276 14576 7277 14576 7278 14577 7277 14577 7272 14577 7272 14578 7277 14578 7279 14578 7272 14579 7279 14579 7273 14579 7273 14580 7279 14580 7280 14580 7273 14581 7280 14581 7282 14581 7282 14582 7280 14582 7281 14582 7282 14583 7281 14583 2288 14583 2288 14584 7281 14584 7283 14584 7284 14585 2279 14585 7297 14585 7297 14586 2279 14586 7216 14586 7297 14587 7216 14587 7285 14587 7285 14588 7216 14588 7215 14588 7285 14589 7215 14589 7293 14589 7293 14590 7215 14590 7286 14590 7293 14591 7286 14591 7287 14591 7287 14592 7286 14592 7219 14592 7287 14593 7219 14593 7289 14593 7289 14594 7219 14594 7288 14594 7289 14595 7288 14595 7290 14595 7290 14596 7288 14596 7222 14596 2278 14597 7291 14597 7290 14597 7290 14598 7291 14598 7289 14598 7291 14599 7292 14599 7289 14599 7289 14600 7292 14600 7306 14600 7289 14601 7306 14601 7287 14601 7306 14602 7305 14602 7287 14602 7287 14603 7305 14603 7304 14603 7287 14604 7304 14604 7293 14604 7304 14605 7294 14605 7293 14605 7293 14606 7294 14606 7295 14606 7293 14607 7295 14607 7285 14607 7295 14608 7303 14608 7285 14608 7285 14609 7303 14609 7299 14609 7285 14610 7299 14610 7297 14610 7296 14611 7284 14611 7298 14611 7298 14612 7284 14612 7297 14612 7298 14613 7297 14613 7301 14613 7301 14614 7297 14614 7299 14614 7300 14615 4354 14615 7296 14615 7296 14616 7298 14616 7300 14616 7300 14617 7298 14617 7301 14617 7300 14618 7301 14618 7302 14618 7301 14619 7299 14619 7302 14619 7302 14620 7299 14620 7303 14620 7302 14621 7303 14621 4357 14621 7303 14622 7295 14622 4357 14622 4357 14623 7295 14623 7294 14623 4357 14624 7294 14624 4359 14624 4359 14625 7294 14625 7304 14625 4359 14626 7304 14626 4344 14626 7304 14627 7305 14627 4344 14627 4344 14628 7305 14628 7306 14628 4344 14629 7306 14629 7307 14629 2278 14630 4346 14630 7291 14630 7291 14631 4346 14631 7307 14631 7291 14632 7307 14632 7292 14632 7292 14633 7307 14633 7306 14633 7308 14634 2262 14634 7309 14634 7309 14635 7331 14635 7308 14635 7308 14636 7331 14636 7310 14636 7308 14637 7310 14637 7312 14637 7310 14638 7311 14638 7312 14638 7312 14639 7311 14639 7313 14639 7312 14640 7313 14640 7249 14640 7313 14641 7328 14641 7249 14641 7249 14642 7328 14642 7314 14642 7249 14643 7314 14643 7315 14643 7315 14644 7314 14644 7326 14644 7315 14645 7326 14645 7316 14645 7326 14646 7317 14646 7316 14646 7316 14647 7317 14647 7318 14647 7316 14648 7318 14648 7247 14648 7321 14649 7319 14649 7323 14649 7323 14650 7319 14650 7247 14650 7323 14651 7247 14651 7320 14651 7320 14652 7247 14652 7318 14652 2241 14653 7321 14653 7322 14653 7322 14654 7321 14654 7323 14654 7322 14655 7323 14655 7333 14655 7333 14656 7323 14656 7320 14656 7333 14657 7320 14657 7324 14657 7324 14658 7320 14658 7318 14658 7324 14659 7318 14659 7335 14659 7335 14660 7318 14660 7317 14660 7335 14661 7317 14661 7325 14661 7325 14662 7317 14662 7326 14662 7325 14663 7326 14663 7336 14663 7336 14664 7326 14664 7314 14664 7336 14665 7314 14665 7337 14665 7337 14666 7314 14666 7328 14666 7337 14667 7328 14667 7327 14667 7327 14668 7328 14668 7313 14668 7327 14669 7313 14669 7329 14669 7329 14670 7313 14670 7311 14670 7329 14671 7311 14671 7339 14671 7339 14672 7311 14672 7310 14672 7339 14673 7310 14673 7330 14673 7330 14674 7310 14674 7331 14674 7330 14675 7331 14675 7332 14675 7332 14676 7331 14676 7309 14676 4371 14677 4370 14677 2241 14677 2241 14678 7322 14678 4371 14678 4371 14679 7322 14679 7333 14679 4371 14680 7333 14680 7334 14680 7333 14681 7324 14681 7334 14681 7334 14682 7324 14682 7335 14682 7334 14683 7335 14683 4373 14683 4373 14684 7335 14684 7325 14684 4373 14685 7325 14685 4374 14685 7325 14686 7336 14686 4374 14686 4374 14687 7336 14687 7337 14687 4374 14688 7337 14688 7338 14688 7337 14689 7327 14689 7338 14689 7338 14690 7327 14690 7329 14690 7338 14691 7329 14691 4362 14691 7332 14692 4364 14692 7330 14692 7330 14693 4364 14693 4362 14693 7330 14694 4362 14694 7339 14694 7339 14695 4362 14695 7329 14695 2221 14696 7362 14696 7340 14696 7340 14697 7362 14697 7341 14697 7340 14698 7341 14698 7411 14698 7411 14699 7341 14699 7364 14699 7411 14700 7364 14700 7412 14700 7412 14701 7364 14701 7342 14701 7412 14702 7342 14702 7414 14702 7414 14703 7342 14703 7360 14703 7414 14704 7360 14704 7343 14704 7343 14705 7360 14705 7345 14705 7343 14706 7345 14706 7344 14706 7344 14707 7345 14707 7347 14707 7344 14708 7347 14708 7346 14708 7346 14709 7347 14709 7348 14709 7346 14710 7348 14710 7349 14710 7349 14711 7348 14711 7350 14711 7349 14712 7350 14712 7351 14712 7351 14713 7350 14713 7352 14713 7351 14714 7352 14714 7353 14714 7353 14715 7352 14715 7358 14715 7353 14716 7358 14716 7418 14716 7418 14717 7358 14717 7354 14717 7418 14718 7354 14718 7355 14718 7355 14719 7354 14719 7356 14719 7357 14720 4383 14720 7356 14720 7356 14721 7354 14721 7357 14721 7357 14722 7354 14722 7358 14722 7357 14723 7358 14723 7359 14723 7358 14724 7352 14724 7359 14724 7359 14725 7352 14725 7350 14725 7359 14726 7350 14726 4380 14726 4380 14727 7350 14727 7348 14727 7348 14728 7347 14728 4380 14728 4380 14729 7347 14729 7345 14729 4380 14730 7345 14730 7361 14730 7345 14731 7360 14731 7361 14731 7361 14732 7360 14732 7342 14732 7361 14733 7342 14733 7363 14733 7362 14734 4376 14734 7341 14734 7341 14735 4376 14735 7363 14735 7341 14736 7363 14736 7364 14736 7364 14737 7363 14737 7342 14737 7419 14738 7365 14738 7367 14738 7419 14739 7367 14739 7366 14739 7366 14740 7367 14740 7375 14740 7366 14741 7375 14741 7422 14741 7422 14742 7375 14742 7368 14742 7368 14743 7375 14743 7369 14743 7368 14744 7369 14744 7423 14744 7423 14745 7369 14745 7370 14745 7370 14746 7369 14746 7371 14746 7370 14747 7371 14747 7426 14747 7426 14748 7371 14748 7425 14748 7425 14749 7371 14749 7372 14749 7425 14750 7372 14750 7373 14750 7373 14751 7372 14751 7380 14751 7373 14752 7380 14752 7374 14752 7374 14753 7380 14753 2201 14753 7374 14754 2201 14754 2143 14754 7365 14755 2200 14755 7367 14755 7367 14756 2200 14756 7376 14756 7367 14757 7376 14757 7375 14757 7375 14758 7376 14758 7377 14758 7375 14759 7377 14759 7369 14759 7369 14760 7377 14760 7378 14760 7369 14761 7378 14761 7371 14761 7371 14762 7378 14762 4387 14762 7371 14763 4387 14763 7372 14763 7372 14764 4387 14764 7379 14764 7372 14765 7379 14765 7380 14765 7380 14766 7379 14766 7381 14766 7380 14767 7381 14767 2201 14767 2201 14768 7381 14768 4393 14768 7382 14769 2185 14769 7427 14769 7427 14770 2185 14770 7383 14770 7427 14771 7383 14771 7428 14771 7428 14772 7383 14772 7430 14772 7430 14773 7383 14773 7384 14773 7430 14774 7384 14774 7431 14774 7431 14775 7384 14775 7432 14775 7432 14776 7384 14776 7391 14776 7432 14777 7391 14777 7433 14777 7433 14778 7391 14778 7434 14778 7434 14779 7391 14779 7392 14779 7434 14780 7392 14780 7436 14780 7436 14781 7392 14781 7385 14781 7385 14782 7392 14782 7387 14782 7385 14783 7387 14783 7386 14783 7386 14784 7387 14784 7388 14784 7388 14785 7387 14785 7394 14785 7388 14786 7394 14786 2187 14786 2185 14787 4402 14787 7383 14787 7383 14788 4402 14788 7389 14788 7383 14789 7389 14789 7384 14789 7384 14790 7389 14790 4401 14790 7384 14791 4401 14791 7391 14791 7391 14792 4401 14792 7390 14792 7391 14793 7390 14793 7392 14793 7392 14794 7390 14794 7393 14794 7392 14795 7393 14795 7387 14795 7387 14796 7393 14796 7395 14796 7387 14797 7395 14797 7394 14797 7394 14798 7395 14798 4397 14798 7441 14799 7397 14799 7396 14799 7396 14800 7397 14800 7405 14800 7396 14801 7405 14801 7398 14801 7398 14802 7405 14802 7399 14802 7398 14803 7399 14803 7440 14803 7440 14804 7399 14804 7400 14804 7440 14805 7400 14805 7438 14805 7438 14806 7400 14806 7401 14806 7438 14807 7401 14807 7402 14807 7402 14808 7401 14808 7404 14808 7402 14809 7404 14809 7403 14809 7403 14810 7404 14810 7407 14810 7397 14811 2157 14811 7405 14811 7405 14812 2157 14812 4418 14812 7405 14813 4418 14813 7399 14813 7399 14814 4418 14814 4416 14814 7399 14815 4416 14815 7400 14815 7400 14816 4416 14816 4415 14816 7400 14817 4415 14817 7401 14817 7401 14818 4415 14818 7406 14818 7401 14819 7406 14819 7404 14819 7404 14820 7406 14820 7408 14820 7404 14821 7408 14821 7407 14821 7407 14822 7408 14822 7409 14822 7410 14823 6714 14823 2221 14823 2221 14824 7340 14824 7410 14824 7410 14825 7340 14825 7411 14825 7410 14826 7411 14826 7413 14826 7411 14827 7412 14827 7413 14827 7413 14828 7412 14828 7414 14828 7413 14829 7414 14829 6709 14829 6709 14830 7414 14830 7343 14830 7343 14831 7344 14831 6709 14831 6709 14832 7344 14832 7346 14832 6709 14833 7346 14833 7415 14833 7346 14834 7349 14834 7415 14834 7415 14835 7349 14835 7351 14835 7415 14836 7351 14836 7417 14836 7355 14837 7416 14837 7418 14837 7418 14838 7416 14838 7417 14838 7418 14839 7417 14839 7353 14839 7353 14840 7417 14840 7351 14840 2151 14841 7419 14841 7420 14841 7420 14842 7419 14842 7366 14842 7420 14843 7366 14843 7421 14843 7366 14844 7422 14844 7421 14844 7421 14845 7422 14845 7368 14845 7421 14846 7368 14846 7424 14846 7424 14847 7368 14847 7423 14847 7423 14848 7370 14848 7424 14848 7424 14849 7370 14849 7426 14849 7424 14850 7426 14850 6447 14850 2143 14851 6450 14851 7374 14851 7374 14852 6450 14852 6449 14852 7374 14853 6449 14853 7373 14853 7373 14854 6449 14854 6447 14854 7373 14855 6447 14855 7425 14855 7425 14856 6447 14856 7426 14856 6471 14857 6470 14857 7382 14857 7382 14858 7427 14858 6471 14858 6471 14859 7427 14859 7428 14859 6471 14860 7428 14860 7429 14860 7428 14861 7430 14861 7429 14861 7429 14862 7430 14862 7431 14862 7429 14863 7431 14863 6472 14863 7431 14864 7432 14864 6472 14864 6472 14865 7432 14865 7433 14865 6472 14866 7433 14866 6473 14866 6473 14867 7433 14867 7434 14867 6473 14868 7434 14868 7435 14868 7434 14869 7436 14869 7435 14869 7435 14870 7436 14870 7385 14870 7435 14871 7385 14871 7437 14871 2187 14872 2133 14872 7388 14872 7388 14873 2133 14873 7437 14873 7388 14874 7437 14874 7386 14874 7386 14875 7437 14875 7385 14875 7403 14876 2132 14876 7402 14876 7402 14877 2132 14877 6431 14877 7402 14878 6431 14878 7438 14878 7438 14879 6431 14879 7439 14879 7438 14880 7439 14880 7440 14880 7440 14881 7439 14881 6438 14881 7440 14882 6438 14882 7398 14882 7398 14883 6438 14883 6435 14883 7398 14884 6435 14884 7396 14884 7396 14885 6435 14885 6434 14885 7396 14886 6434 14886 7441 14886 7441 14887 6434 14887 6433 14887 7442 14888 7443 14888 2079 14888 2079 14889 7443 14889 2129 14889 2079 14890 2129 14890 2078 14890 2078 14891 2129 14891 7444 14891 2078 14892 7444 14892 7445 14892 7445 14893 7444 14893 7446 14893 7445 14894 7446 14894 7528 14894 7528 14895 7446 14895 7454 14895 7528 14896 7454 14896 7447 14896 7447 14897 7454 14897 7455 14897 7447 14898 7455 14898 7525 14898 7525 14899 7455 14899 7448 14899 7525 14900 7448 14900 7524 14900 7524 14901 7448 14901 7523 14901 7523 14902 7448 14902 7449 14902 7523 14903 7449 14903 7522 14903 7522 14904 7449 14904 7450 14904 7522 14905 7450 14905 2085 14905 2085 14906 7450 14906 7451 14906 2085 14907 7451 14907 2088 14907 2088 14908 7451 14908 2125 14908 2088 14909 2125 14909 2083 14909 2083 14910 2125 14910 7452 14910 2083 14911 7452 14911 7442 14911 7442 14912 7452 14912 7453 14912 7442 14913 7453 14913 7443 14913 7446 14914 7459 14914 7454 14914 7454 14915 7459 14915 7462 14915 7454 14916 7462 14916 7455 14916 7455 14917 7462 14917 7463 14917 7455 14918 7463 14918 7448 14918 7448 14919 7463 14919 7456 14919 7448 14920 7456 14920 7449 14920 7449 14921 7456 14921 7457 14921 7449 14922 7457 14922 7450 14922 7450 14923 7457 14923 7458 14923 7450 14924 7458 14924 7451 14924 7451 14925 7458 14925 2124 14925 7459 14926 7460 14926 7462 14926 7462 14927 7460 14927 7461 14927 7462 14928 7461 14928 7463 14928 7463 14929 7461 14929 6563 14929 7463 14930 6563 14930 7456 14930 7456 14931 6563 14931 6562 14931 7456 14932 6562 14932 7457 14932 7457 14933 6562 14933 7464 14933 7457 14934 7464 14934 7458 14934 7458 14935 7464 14935 7465 14935 7458 14936 7465 14936 2124 14936 2124 14937 7465 14937 6558 14937 7477 14938 2117 14938 7466 14938 7466 14939 2117 14939 2119 14939 7466 14940 2119 14940 2043 14940 2043 14941 2119 14941 2120 14941 2043 14942 2120 14942 7467 14942 7467 14943 2120 14943 7478 14943 7467 14944 7478 14944 7561 14944 7561 14945 7478 14945 7468 14945 7561 14946 7468 14946 7562 14946 7562 14947 7468 14947 7469 14947 7562 14948 7469 14948 7470 14948 7470 14949 7469 14949 7471 14949 7470 14950 7471 14950 7558 14950 7558 14951 7471 14951 7480 14951 7558 14952 7480 14952 7555 14952 7555 14953 7480 14953 7472 14953 7555 14954 7472 14954 7554 14954 7554 14955 7472 14955 7474 14955 7554 14956 7474 14956 7473 14956 7473 14957 7474 14957 7475 14957 7473 14958 7475 14958 7476 14958 7476 14959 7475 14959 2112 14959 7476 14960 2112 14960 2048 14960 2048 14961 2112 14961 2114 14961 2048 14962 2114 14962 7477 14962 7477 14963 2114 14963 2117 14963 7478 14964 2121 14964 7468 14964 7468 14965 2121 14965 7483 14965 7468 14966 7483 14966 7469 14966 7469 14967 7483 14967 7479 14967 7469 14968 7479 14968 7471 14968 7471 14969 7479 14969 7484 14969 7471 14970 7484 14970 7480 14970 7480 14971 7484 14971 7481 14971 7480 14972 7481 14972 7472 14972 7472 14973 7481 14973 7485 14973 7472 14974 7485 14974 7474 14974 7474 14975 7485 14975 7486 14975 2121 14976 2102 14976 7483 14976 7483 14977 2102 14977 7482 14977 7483 14978 7482 14978 7479 14978 7479 14979 7482 14979 6459 14979 7479 14980 6459 14980 7484 14980 7484 14981 6459 14981 6458 14981 7484 14982 6458 14982 7481 14982 7481 14983 6458 14983 6445 14983 7481 14984 6445 14984 7485 14984 7485 14985 6445 14985 6444 14985 7485 14986 6444 14986 7486 14986 7486 14987 6444 14987 2107 14987 7498 14988 7487 14988 7488 14988 7488 14989 7487 14989 2097 14989 7488 14990 2097 14990 7489 14990 7489 14991 2097 14991 2098 14991 7489 14992 2098 14992 7490 14992 7490 14993 2098 14993 2100 14993 7490 14994 2100 14994 7491 14994 7491 14995 2100 14995 7492 14995 7491 14996 7492 14996 7582 14996 7582 14997 7492 14997 7500 14997 7582 14998 7500 14998 7493 14998 7493 14999 7500 14999 7502 14999 7493 15000 7502 15000 7494 15000 7494 15001 7502 15001 7504 15001 7494 15002 7504 15002 7586 15002 7586 15003 7504 15003 7508 15003 7586 15004 7508 15004 7495 15004 7495 15005 7508 15005 7512 15005 7495 15006 7512 15006 7588 15006 7588 15007 7512 15007 7496 15007 7588 15008 7496 15008 7497 15008 7497 15009 7496 15009 2094 15009 7497 15010 2094 15010 7498 15010 7498 15011 2094 15011 7487 15011 7518 15012 7520 15012 7492 15012 7492 15013 7520 15013 7500 15013 7520 15014 7499 15014 7500 15014 7500 15015 7499 15015 7501 15015 7500 15016 7501 15016 7502 15016 7501 15017 7516 15017 7502 15017 7502 15018 7516 15018 7503 15018 7502 15019 7503 15019 7504 15019 7503 15020 7505 15020 7504 15020 7504 15021 7505 15021 7506 15021 7504 15022 7506 15022 7508 15022 7506 15023 7507 15023 7508 15023 7508 15024 7507 15024 7513 15024 7508 15025 7513 15025 7512 15025 7509 15026 7496 15026 7510 15026 7510 15027 7496 15027 7512 15027 7510 15028 7512 15028 7511 15028 7511 15029 7512 15029 7513 15029 6684 15030 6437 15030 7509 15030 7509 15031 7510 15031 6684 15031 6684 15032 7510 15032 7511 15032 6684 15033 7511 15033 7514 15033 7511 15034 7513 15034 7514 15034 7514 15035 7513 15035 7507 15035 7514 15036 7507 15036 6442 15036 6442 15037 7507 15037 7506 15037 6442 15038 7506 15038 7515 15038 7506 15039 7505 15039 7515 15039 7515 15040 7505 15040 7503 15040 7515 15041 7503 15041 7517 15041 7503 15042 7516 15042 7517 15042 7517 15043 7516 15043 7501 15043 7517 15044 7501 15044 6439 15044 7518 15045 7519 15045 7520 15045 7520 15046 7519 15046 6439 15046 7520 15047 6439 15047 7499 15047 7499 15048 6439 15048 7501 15048 7522 15049 2085 15049 2084 15049 2084 15050 7521 15050 7522 15050 7522 15051 7521 15051 7542 15051 7522 15052 7542 15052 7523 15052 7542 15053 7541 15053 7523 15053 7523 15054 7541 15054 7539 15054 7523 15055 7539 15055 7524 15055 7539 15056 7538 15056 7524 15056 7524 15057 7538 15057 7534 15057 7524 15058 7534 15058 7525 15058 7525 15059 7534 15059 7526 15059 7525 15060 7526 15060 7447 15060 7526 15061 7533 15061 7447 15061 7447 15062 7533 15062 7529 15062 7447 15063 7529 15063 7528 15063 2077 15064 7445 15064 7527 15064 7527 15065 7445 15065 7528 15065 7527 15066 7528 15066 7531 15066 7531 15067 7528 15067 7529 15067 2065 15068 2077 15068 7530 15068 7530 15069 2077 15069 7527 15069 7530 15070 7527 15070 7545 15070 7545 15071 7527 15071 7531 15071 7545 15072 7531 15072 7546 15072 7546 15073 7531 15073 7529 15073 7546 15074 7529 15074 7548 15074 7548 15075 7529 15075 7533 15075 7548 15076 7533 15076 7532 15076 7532 15077 7533 15077 7526 15077 7532 15078 7526 15078 7535 15078 7535 15079 7526 15079 7534 15079 7535 15080 7534 15080 7536 15080 7536 15081 7534 15081 7538 15081 7536 15082 7538 15082 7537 15082 7537 15083 7538 15083 7539 15083 7537 15084 7539 15084 7540 15084 7540 15085 7539 15085 7541 15085 7540 15086 7541 15086 7553 15086 7553 15087 7541 15087 7542 15087 7553 15088 7542 15088 7543 15088 7543 15089 7542 15089 7521 15089 7543 15090 7521 15090 7544 15090 7544 15091 7521 15091 2084 15091 4428 15092 2063 15092 2065 15092 2065 15093 7530 15093 4428 15093 4428 15094 7530 15094 7545 15094 4428 15095 7545 15095 7547 15095 7545 15096 7546 15096 7547 15096 7547 15097 7546 15097 7548 15097 7547 15098 7548 15098 7549 15098 7549 15099 7548 15099 7532 15099 7549 15100 7532 15100 7550 15100 7532 15101 7535 15101 7550 15101 7550 15102 7535 15102 7536 15102 7550 15103 7536 15103 4419 15103 7536 15104 7537 15104 4419 15104 4419 15105 7537 15105 7540 15105 4419 15106 7540 15106 7552 15106 7544 15107 7551 15107 7543 15107 7543 15108 7551 15108 7552 15108 7543 15109 7552 15109 7553 15109 7553 15110 7552 15110 7540 15110 7554 15111 2041 15111 7555 15111 7555 15112 2041 15112 7556 15112 7555 15113 7556 15113 7558 15113 7556 15114 7557 15114 7558 15114 7558 15115 7557 15115 7563 15115 7558 15116 7563 15116 7470 15116 7470 15117 7563 15117 7565 15117 7565 15118 7566 15118 7470 15118 7470 15119 7566 15119 7567 15119 7470 15120 7567 15120 7562 15120 7570 15121 7467 15121 7559 15121 7559 15122 7467 15122 7561 15122 7559 15123 7561 15123 7560 15123 7560 15124 7561 15124 7562 15124 7560 15125 7562 15125 7568 15125 7568 15126 7562 15126 7567 15126 2041 15127 7571 15127 7572 15127 2041 15128 7572 15128 7556 15128 7556 15129 7572 15129 7573 15129 7556 15130 7573 15130 7557 15130 7557 15131 7573 15131 7563 15131 7563 15132 7573 15132 7564 15132 7563 15133 7564 15133 7565 15133 7565 15134 7564 15134 7566 15134 7566 15135 7564 15135 7575 15135 7566 15136 7575 15136 7567 15136 7567 15137 7575 15137 7568 15137 7568 15138 7575 15138 7569 15138 7568 15139 7569 15139 7560 15139 7560 15140 7569 15140 7578 15140 7560 15141 7578 15141 7559 15141 7559 15142 7578 15142 2038 15142 7559 15143 2038 15143 7570 15143 7571 15144 2037 15144 7572 15144 7572 15145 2037 15145 4434 15145 7572 15146 4434 15146 7573 15146 7573 15147 4434 15147 4433 15147 7573 15148 4433 15148 7564 15148 7564 15149 4433 15149 7574 15149 7564 15150 7574 15150 7575 15150 7575 15151 7574 15151 7576 15151 7575 15152 7576 15152 7569 15152 7569 15153 7576 15153 7577 15153 7569 15154 7577 15154 7578 15154 7578 15155 7577 15155 4431 15155 7578 15156 4431 15156 2038 15156 2038 15157 4431 15157 4444 15157 7579 15158 7491 15158 7580 15158 7580 15159 7491 15159 7582 15159 7580 15160 7582 15160 7581 15160 7581 15161 7582 15161 7493 15161 7581 15162 7493 15162 7583 15162 7583 15163 7493 15163 7494 15163 7583 15164 7494 15164 7584 15164 7584 15165 7494 15165 7586 15165 7584 15166 7586 15166 7585 15166 7585 15167 7586 15167 7495 15167 7585 15168 7495 15168 7587 15168 7587 15169 7495 15169 7588 15169 7587 15170 2019 15170 7585 15170 7585 15171 2019 15171 7589 15171 7585 15172 7589 15172 7584 15172 7584 15173 7589 15173 7593 15173 7584 15174 7593 15174 7583 15174 7583 15175 7593 15175 7590 15175 7583 15176 7590 15176 7581 15176 7581 15177 7590 15177 7594 15177 7581 15178 7594 15178 7580 15178 7580 15179 7594 15179 7591 15179 7580 15180 7591 15180 7579 15180 7579 15181 7591 15181 2012 15181 2019 15182 4456 15182 7589 15182 7589 15183 4456 15183 7592 15183 7589 15184 7592 15184 7593 15184 7593 15185 7592 15185 4453 15185 7593 15186 4453 15186 7590 15186 7590 15187 4453 15187 4452 15187 7590 15188 4452 15188 7594 15188 7594 15189 4452 15189 7595 15189 7594 15190 7595 15190 7591 15190 7591 15191 7595 15191 7596 15191 7591 15192 7596 15192 2012 15192 2012 15193 7596 15193 7597 15193 1948 15194 2011 15194 7598 15194 7598 15195 2011 15195 7599 15195 7598 15196 7599 15196 7658 15196 7658 15197 7599 15197 7660 15197 7660 15198 7599 15198 7600 15198 7660 15199 7600 15199 7661 15199 7661 15200 7600 15200 7601 15200 7601 15201 7600 15201 7604 15201 7601 15202 7604 15202 7663 15202 7663 15203 7604 15203 7664 15203 7664 15204 7604 15204 7606 15204 7664 15205 7606 15205 7665 15205 7665 15206 7606 15206 7669 15206 7669 15207 7606 15207 7602 15207 7669 15208 7602 15208 7668 15208 7668 15209 7602 15209 7603 15209 7603 15210 7602 15210 7607 15210 7603 15211 7607 15211 2005 15211 2011 15212 4471 15212 7599 15212 7599 15213 4471 15213 4470 15213 7599 15214 4470 15214 7600 15214 7600 15215 4470 15215 7605 15215 7600 15216 7605 15216 7604 15216 7604 15217 7605 15217 4469 15217 7604 15218 4469 15218 7606 15218 7606 15219 4469 15219 4468 15219 7606 15220 4468 15220 7602 15220 7602 15221 4468 15221 4467 15221 7602 15222 4467 15222 7607 15222 7607 15223 4467 15223 1996 15223 1940 15224 1990 15224 7608 15224 1940 15225 7608 15225 7609 15225 7609 15226 7608 15226 7618 15226 7609 15227 7618 15227 7610 15227 7610 15228 7618 15228 7672 15228 7672 15229 7618 15229 7611 15229 7672 15230 7611 15230 7612 15230 7612 15231 7611 15231 7613 15231 7613 15232 7611 15232 7614 15232 7613 15233 7614 15233 7673 15233 7673 15234 7614 15234 7676 15234 7676 15235 7614 15235 7615 15235 7676 15236 7615 15236 7674 15236 7674 15237 7615 15237 7616 15237 7674 15238 7616 15238 7617 15238 7617 15239 7616 15239 1982 15239 7617 15240 1982 15240 1932 15240 1990 15241 4481 15241 7608 15241 7608 15242 4481 15242 4480 15242 7608 15243 4480 15243 7618 15243 7618 15244 4480 15244 4478 15244 7618 15245 4478 15245 7611 15245 7611 15246 4478 15246 7619 15246 7611 15247 7619 15247 7614 15247 7614 15248 7619 15248 4476 15248 7614 15249 4476 15249 7615 15249 7615 15250 4476 15250 4475 15250 7615 15251 4475 15251 7616 15251 7616 15252 4475 15252 4473 15252 7616 15253 4473 15253 1982 15253 1982 15254 4473 15254 1983 15254 1981 15255 1974 15255 7621 15255 7621 15256 1974 15256 7620 15256 7621 15257 7620 15257 7677 15257 7677 15258 7620 15258 7622 15258 7677 15259 7622 15259 7623 15259 7623 15260 7622 15260 7624 15260 7623 15261 7624 15261 7679 15261 7679 15262 7624 15262 7625 15262 7679 15263 7625 15263 7626 15263 7626 15264 7625 15264 7627 15264 7626 15265 7627 15265 7682 15265 7682 15266 7627 15266 7640 15266 7682 15267 7640 15267 7628 15267 7628 15268 7640 15268 7638 15268 7628 15269 7638 15269 7629 15269 7629 15270 7638 15270 7637 15270 7629 15271 7637 15271 7683 15271 7683 15272 7637 15272 7630 15272 7683 15273 7630 15273 7631 15273 7631 15274 7630 15274 7632 15274 7631 15275 7632 15275 7634 15275 7634 15276 7632 15276 7633 15276 7634 15277 7633 15277 7685 15277 7685 15278 7633 15278 1976 15278 7635 15279 7636 15279 1976 15279 1976 15280 7633 15280 7635 15280 7635 15281 7633 15281 7632 15281 7635 15282 7632 15282 4498 15282 7632 15283 7630 15283 4498 15283 4498 15284 7630 15284 7637 15284 4498 15285 7637 15285 4499 15285 7637 15286 7638 15286 4499 15286 4499 15287 7638 15287 7640 15287 4499 15288 7640 15288 7639 15288 7639 15289 7640 15289 7627 15289 7639 15290 7627 15290 7641 15290 7627 15291 7625 15291 7641 15291 7641 15292 7625 15292 7624 15292 7641 15293 7624 15293 7642 15293 1974 15294 1975 15294 7620 15294 7620 15295 1975 15295 7642 15295 7620 15296 7642 15296 7622 15296 7622 15297 7642 15297 7624 15297 1968 15298 7643 15298 7644 15298 1968 15299 7644 15299 7687 15299 7687 15300 7644 15300 7651 15300 7687 15301 7651 15301 7645 15301 7645 15302 7651 15302 7689 15302 7689 15303 7651 15303 7653 15303 7689 15304 7653 15304 7690 15304 7690 15305 7653 15305 7691 15305 7691 15306 7653 15306 7646 15306 7691 15307 7646 15307 7692 15307 7692 15308 7646 15308 7696 15308 7696 15309 7646 15309 7647 15309 7696 15310 7647 15310 7648 15310 7648 15311 7647 15311 7656 15311 7648 15312 7656 15312 7695 15312 7695 15313 7656 15313 7649 15313 7695 15314 7649 15314 1925 15314 7643 15315 1961 15315 7644 15315 7644 15316 1961 15316 7650 15316 7644 15317 7650 15317 7651 15317 7651 15318 7650 15318 4511 15318 7651 15319 4511 15319 7653 15319 7653 15320 4511 15320 7652 15320 7653 15321 7652 15321 7646 15321 7646 15322 7652 15322 7654 15322 7646 15323 7654 15323 7647 15323 7647 15324 7654 15324 4509 15324 7647 15325 4509 15325 7656 15325 7656 15326 4509 15326 7655 15326 7656 15327 7655 15327 7649 15327 7649 15328 7655 15328 1953 15328 7657 15329 1949 15329 1948 15329 1948 15330 7598 15330 7657 15330 7657 15331 7598 15331 7658 15331 7657 15332 7658 15332 7659 15332 7658 15333 7660 15333 7659 15333 7659 15334 7660 15334 7661 15334 7659 15335 7661 15335 7662 15335 7662 15336 7661 15336 7601 15336 7662 15337 7601 15337 6532 15337 7601 15338 7663 15338 6532 15338 6532 15339 7663 15339 7664 15339 6532 15340 7664 15340 6535 15340 7664 15341 7665 15341 6535 15341 6535 15342 7665 15342 7669 15342 6535 15343 7669 15343 7667 15343 2005 15344 7666 15344 7603 15344 7603 15345 7666 15345 7667 15345 7603 15346 7667 15346 7668 15346 7668 15347 7667 15347 7669 15347 7670 15348 1940 15348 6649 15348 6649 15349 1940 15349 7609 15349 6649 15350 7609 15350 7671 15350 7609 15351 7610 15351 7671 15351 7671 15352 7610 15352 7672 15352 7671 15353 7672 15353 6651 15353 6651 15354 7672 15354 7612 15354 7612 15355 7613 15355 6651 15355 6651 15356 7613 15356 7673 15356 6651 15357 7673 15357 7675 15357 1932 15358 6654 15358 7617 15358 7617 15359 6654 15359 6652 15359 7617 15360 6652 15360 7674 15360 7674 15361 6652 15361 7675 15361 7674 15362 7675 15362 7676 15362 7676 15363 7675 15363 7673 15363 6619 15364 6618 15364 1981 15364 1981 15365 7621 15365 6619 15365 6619 15366 7621 15366 7677 15366 6619 15367 7677 15367 7678 15367 7677 15368 7623 15368 7678 15368 7678 15369 7623 15369 7679 15369 7678 15370 7679 15370 7680 15370 7680 15371 7679 15371 7626 15371 7680 15372 7626 15372 7681 15372 7626 15373 7682 15373 7681 15373 7681 15374 7682 15374 7628 15374 7681 15375 7628 15375 7684 15375 7628 15376 7629 15376 7684 15376 7684 15377 7629 15377 7683 15377 7684 15378 7683 15378 7686 15378 7685 15379 6630 15379 7634 15379 7634 15380 6630 15380 7686 15380 7634 15381 7686 15381 7631 15381 7631 15382 7686 15382 7683 15382 6579 15383 1968 15383 6577 15383 6577 15384 1968 15384 7687 15384 6577 15385 7687 15385 6570 15385 7687 15386 7645 15386 6570 15386 6570 15387 7645 15387 7689 15387 6570 15388 7689 15388 7688 15388 7688 15389 7689 15389 7690 15389 7690 15390 7691 15390 7688 15390 7688 15391 7691 15391 7692 15391 7688 15392 7692 15392 7693 15392 1925 15393 7694 15393 7695 15393 7695 15394 7694 15394 6569 15394 7695 15395 6569 15395 7648 15395 7648 15396 6569 15396 7693 15396 7648 15397 7693 15397 7696 15397 7696 15398 7693 15398 7692 15398 7709 15399 1913 15399 1868 15399 1868 15400 1913 15400 1915 15400 1868 15401 1915 15401 1869 15401 1869 15402 1915 15402 1916 15402 1869 15403 1916 15403 1871 15403 1871 15404 1916 15404 1918 15404 1871 15405 1918 15405 7697 15405 7697 15406 1918 15406 1919 15406 7697 15407 1919 15407 7698 15407 7698 15408 1919 15408 7699 15408 7698 15409 7699 15409 7701 15409 7701 15410 7699 15410 7700 15410 7701 15411 7700 15411 7702 15411 7702 15412 7700 15412 7710 15412 7702 15413 7710 15413 7703 15413 7703 15414 7710 15414 7704 15414 7703 15415 7704 15415 7771 15415 7771 15416 7704 15416 7713 15416 7771 15417 7713 15417 7705 15417 7705 15418 7713 15418 1910 15418 7705 15419 1910 15419 7706 15419 7706 15420 1910 15420 7707 15420 7706 15421 7707 15421 7708 15421 7708 15422 7707 15422 7709 15422 7708 15423 7709 15423 1868 15423 1919 15424 1908 15424 7699 15424 7699 15425 1908 15425 7714 15425 7699 15426 7714 15426 7700 15426 7700 15427 7714 15427 7715 15427 7700 15428 7715 15428 7710 15428 7710 15429 7715 15429 7711 15429 7710 15430 7711 15430 7704 15430 7704 15431 7711 15431 7712 15431 7704 15432 7712 15432 7713 15432 7713 15433 7712 15433 7718 15433 7713 15434 7718 15434 1910 15434 1910 15435 7718 15435 1911 15435 1908 15436 1909 15436 7714 15436 7714 15437 1909 15437 6428 15437 7714 15438 6428 15438 7715 15438 7715 15439 6428 15439 7716 15439 7715 15440 7716 15440 7711 15440 7711 15441 7716 15441 7717 15441 7711 15442 7717 15442 7712 15442 7712 15443 7717 15443 7719 15443 7712 15444 7719 15444 7718 15444 7718 15445 7719 15445 7720 15445 7718 15446 7720 15446 1911 15446 1911 15447 7720 15447 7721 15447 7794 15448 7722 15448 7736 15448 7736 15449 7722 15449 7723 15449 7723 15450 7722 15450 7793 15450 7723 15451 7793 15451 1900 15451 1900 15452 7793 15452 7724 15452 1900 15453 7724 15453 1899 15453 1899 15454 7724 15454 7725 15454 1899 15455 7725 15455 1898 15455 1898 15456 7725 15456 7735 15456 1898 15457 7735 15457 1895 15457 7736 15458 7738 15458 7794 15458 7794 15459 7738 15459 7726 15459 7794 15460 7726 15460 7727 15460 7727 15461 7726 15461 7740 15461 7727 15462 7740 15462 7728 15462 7728 15463 7740 15463 7729 15463 7728 15464 7729 15464 7797 15464 7797 15465 7729 15465 7730 15465 7797 15466 7730 15466 1851 15466 1851 15467 7730 15467 7731 15467 1851 15468 7731 15468 1852 15468 1852 15469 7731 15469 7733 15469 1852 15470 7733 15470 7732 15470 7732 15471 7733 15471 1895 15471 7732 15472 1895 15472 7734 15472 7734 15473 1895 15473 7735 15473 1900 15474 1902 15474 7723 15474 7723 15475 1902 15475 7742 15475 7723 15476 7742 15476 7736 15476 7736 15477 7742 15477 7737 15477 7736 15478 7737 15478 7738 15478 7738 15479 7737 15479 7744 15479 7738 15480 7744 15480 7726 15480 7726 15481 7744 15481 7739 15481 7726 15482 7739 15482 7740 15482 7740 15483 7739 15483 7745 15483 7740 15484 7745 15484 7729 15484 7729 15485 7745 15485 7741 15485 7729 15486 7741 15486 7730 15486 7730 15487 7741 15487 7747 15487 1902 15488 6627 15488 7742 15488 7742 15489 6627 15489 7743 15489 7742 15490 7743 15490 7737 15490 7737 15491 7743 15491 6629 15491 7737 15492 6629 15492 7744 15492 7744 15493 6629 15493 6626 15493 7744 15494 6626 15494 7739 15494 7739 15495 6626 15495 6821 15495 7739 15496 6821 15496 7745 15496 7745 15497 6821 15497 6820 15497 7745 15498 6820 15498 7741 15498 7741 15499 6820 15499 7746 15499 7741 15500 7746 15500 7747 15500 7747 15501 7746 15501 7748 15501 1830 15502 1883 15502 7749 15502 7749 15503 1883 15503 1885 15503 7749 15504 1885 15504 7751 15504 7751 15505 1885 15505 7750 15505 7751 15506 7750 15506 7818 15506 7818 15507 7750 15507 1888 15507 7818 15508 1888 15508 7819 15508 7819 15509 1888 15509 7759 15509 7819 15510 7759 15510 7820 15510 7820 15511 7759 15511 7753 15511 7820 15512 7753 15512 7752 15512 7752 15513 7753 15513 7762 15513 7752 15514 7762 15514 7754 15514 7754 15515 7762 15515 7824 15515 7824 15516 7762 15516 7755 15516 7824 15517 7755 15517 7756 15517 7756 15518 7755 15518 7763 15518 7756 15519 7763 15519 7757 15519 7757 15520 7763 15520 1878 15520 7757 15521 1878 15521 7758 15521 7758 15522 1878 15522 1879 15522 7758 15523 1879 15523 1829 15523 1829 15524 1879 15524 1880 15524 1829 15525 1880 15525 1830 15525 1830 15526 1880 15526 1882 15526 1830 15527 1882 15527 1883 15527 1888 15528 7765 15528 7759 15528 7759 15529 7765 15529 7760 15529 7759 15530 7760 15530 7753 15530 7753 15531 7760 15531 7761 15531 7753 15532 7761 15532 7762 15532 7762 15533 7761 15533 7768 15533 7762 15534 7768 15534 7755 15534 7755 15535 7768 15535 7769 15535 7755 15536 7769 15536 7763 15536 7763 15537 7769 15537 7764 15537 7763 15538 7764 15538 1878 15538 1878 15539 7764 15539 7770 15539 7765 15540 7766 15540 7760 15540 7760 15541 7766 15541 7767 15541 7760 15542 7767 15542 7761 15542 7761 15543 7767 15543 6580 15543 7761 15544 6580 15544 7768 15544 7768 15545 6580 15545 6578 15545 7768 15546 6578 15546 7769 15546 7769 15547 6578 15547 6576 15547 7769 15548 6576 15548 7764 15548 7764 15549 6576 15549 6575 15549 7764 15550 6575 15550 7770 15550 7770 15551 6575 15551 1872 15551 7705 15552 1866 15552 7771 15552 7771 15553 1866 15553 7772 15553 7771 15554 7772 15554 7703 15554 7772 15555 7773 15555 7703 15555 7703 15556 7773 15556 7779 15556 7703 15557 7779 15557 7702 15557 7702 15558 7779 15558 7780 15558 7780 15559 7774 15559 7702 15559 7702 15560 7774 15560 7781 15560 7702 15561 7781 15561 7701 15561 7775 15562 7697 15562 7785 15562 7785 15563 7697 15563 7698 15563 7785 15564 7698 15564 7784 15564 7784 15565 7698 15565 7701 15565 7784 15566 7701 15566 7776 15566 7776 15567 7701 15567 7781 15567 1866 15568 7777 15568 7778 15568 1866 15569 7778 15569 7772 15569 7772 15570 7778 15570 7786 15570 7772 15571 7786 15571 7773 15571 7773 15572 7786 15572 7779 15572 7779 15573 7786 15573 7789 15573 7779 15574 7789 15574 7780 15574 7780 15575 7789 15575 7774 15575 7774 15576 7789 15576 7782 15576 7774 15577 7782 15577 7781 15577 7781 15578 7782 15578 7776 15578 7776 15579 7782 15579 7783 15579 7776 15580 7783 15580 7784 15580 7784 15581 7783 15581 7791 15581 7784 15582 7791 15582 7785 15582 7785 15583 7791 15583 1859 15583 7785 15584 1859 15584 7775 15584 7777 15585 4519 15585 7778 15585 7778 15586 4519 15586 7787 15586 7778 15587 7787 15587 7786 15587 7786 15588 7787 15588 7788 15588 7786 15589 7788 15589 7789 15589 7789 15590 7788 15590 4516 15590 7789 15591 4516 15591 7782 15591 7782 15592 4516 15592 4515 15592 7782 15593 4515 15593 7783 15593 7783 15594 4515 15594 7790 15594 7783 15595 7790 15595 7791 15595 7791 15596 7790 15596 4525 15596 7791 15597 4525 15597 1859 15597 1859 15598 4525 15598 4524 15598 7792 15599 7724 15599 7804 15599 7804 15600 7724 15600 7793 15600 7804 15601 7793 15601 7802 15601 7802 15602 7793 15602 7722 15602 7802 15603 7722 15603 7801 15603 7801 15604 7722 15604 7794 15604 7801 15605 7794 15605 7795 15605 7795 15606 7794 15606 7727 15606 7795 15607 7727 15607 7796 15607 7796 15608 7727 15608 7728 15608 7796 15609 7728 15609 7798 15609 7798 15610 7728 15610 7797 15610 1831 15611 7815 15611 7798 15611 7798 15612 7815 15612 7796 15612 7815 15613 7816 15613 7796 15613 7796 15614 7816 15614 7799 15614 7796 15615 7799 15615 7795 15615 7799 15616 7813 15616 7795 15616 7795 15617 7813 15617 7800 15617 7795 15618 7800 15618 7801 15618 7800 15619 7812 15619 7801 15619 7801 15620 7812 15620 7810 15620 7801 15621 7810 15621 7802 15621 7810 15622 7803 15622 7802 15622 7802 15623 7803 15623 7809 15623 7802 15624 7809 15624 7804 15624 7805 15625 7792 15625 7806 15625 7806 15626 7792 15626 7804 15626 7806 15627 7804 15627 7807 15627 7807 15628 7804 15628 7809 15628 7808 15629 1838 15629 7805 15629 7805 15630 7806 15630 7808 15630 7808 15631 7806 15631 7807 15631 7808 15632 7807 15632 4534 15632 7807 15633 7809 15633 4534 15633 4534 15634 7809 15634 7803 15634 4534 15635 7803 15635 7811 15635 7803 15636 7810 15636 7811 15636 7811 15637 7810 15637 7812 15637 7811 15638 7812 15638 4537 15638 4537 15639 7812 15639 7800 15639 4537 15640 7800 15640 4538 15640 7800 15641 7813 15641 4538 15641 4538 15642 7813 15642 7799 15642 4538 15643 7799 15643 7814 15643 1831 15644 4527 15644 7815 15644 7815 15645 4527 15645 7814 15645 7815 15646 7814 15646 7816 15646 7816 15647 7814 15647 7799 15647 7817 15648 7818 15648 7830 15648 7830 15649 7818 15649 7819 15649 7830 15650 7819 15650 7821 15650 7821 15651 7819 15651 7820 15651 7821 15652 7820 15652 7829 15652 7829 15653 7820 15653 7752 15653 7829 15654 7752 15654 7822 15654 7822 15655 7752 15655 7754 15655 7822 15656 7754 15656 7823 15656 7823 15657 7754 15657 7824 15657 7823 15658 7824 15658 7825 15658 7825 15659 7824 15659 7756 15659 7825 15660 7756 15660 7826 15660 7826 15661 7756 15661 7757 15661 7826 15662 1817 15662 7825 15662 7825 15663 1817 15663 7832 15663 7825 15664 7832 15664 7823 15664 7823 15665 7832 15665 7827 15665 7823 15666 7827 15666 7822 15666 7822 15667 7827 15667 7828 15667 7822 15668 7828 15668 7829 15668 7829 15669 7828 15669 7835 15669 7829 15670 7835 15670 7821 15670 7821 15671 7835 15671 7836 15671 7821 15672 7836 15672 7830 15672 7830 15673 7836 15673 7831 15673 7830 15674 7831 15674 7817 15674 7817 15675 7831 15675 1816 15675 1817 15676 4544 15676 7832 15676 7832 15677 4544 15677 7833 15677 7832 15678 7833 15678 7827 15678 7827 15679 7833 15679 4540 15679 7827 15680 4540 15680 7828 15680 7828 15681 4540 15681 7834 15681 7828 15682 7834 15682 7835 15682 7835 15683 7834 15683 4539 15683 7835 15684 4539 15684 7836 15684 7836 15685 4539 15685 7837 15685 7836 15686 7837 15686 7831 15686 7831 15687 7837 15687 4552 15687 7831 15688 4552 15688 1816 15688 1816 15689 4552 15689 7838 15689 1799 15690 1797 15690 7839 15690 7839 15691 1797 15691 7882 15691 7839 15692 7882 15692 7841 15692 7841 15693 7882 15693 7840 15693 7841 15694 7840 15694 7842 15694 9215 15695 7843 15695 9207 15695 9207 15696 7843 15696 6424 15696 9215 15697 9211 15697 7843 15697 7843 15698 9211 15698 9213 15698 7843 15699 9213 15699 7839 15699 7839 15700 9213 15700 7844 15700 7839 15701 7844 15701 7845 15701 7848 15702 7847 15702 1811 15702 7878 15703 1803 15703 7845 15703 7845 15704 1803 15704 7846 15704 7845 15705 7846 15705 7839 15705 7839 15706 7846 15706 1800 15706 7839 15707 1800 15707 1799 15707 7847 15708 7848 15708 1812 15708 1812 15709 7848 15709 7861 15709 1812 15710 7861 15710 7868 15710 1811 15711 7849 15711 7848 15711 7848 15712 7849 15712 7853 15712 7848 15713 7853 15713 6424 15713 6424 15714 7853 15714 9208 15714 6424 15715 9208 15715 9207 15715 9198 15716 7850 15716 7851 15716 7851 15717 7850 15717 9205 15717 7851 15718 9205 15718 7852 15718 7852 15719 9205 15719 7853 15719 7852 15720 7853 15720 7854 15720 7854 15721 7853 15721 7849 15721 7845 15722 9199 15722 7878 15722 7878 15723 9199 15723 7856 15723 7878 15724 7856 15724 7855 15724 7855 15725 7856 15725 7858 15725 7856 15726 7857 15726 7858 15726 7858 15727 7857 15727 7841 15727 7858 15728 7841 15728 7859 15728 7859 15729 7841 15729 7842 15729 7851 15730 7875 15730 9198 15730 9198 15731 7875 15731 7873 15731 9198 15732 7873 15732 7860 15732 7860 15733 7873 15733 7870 15733 7860 15734 7870 15734 7861 15734 7861 15735 7870 15735 7869 15735 7861 15736 7869 15736 7868 15736 7857 15737 9203 15737 7841 15737 7841 15738 9203 15738 7862 15738 7841 15739 7862 15739 7861 15739 7861 15740 7862 15740 7863 15740 7861 15741 7863 15741 7860 15741 1814 15742 7866 15742 7864 15742 7865 15743 7866 15743 1814 15743 7867 15744 7865 15744 1814 15744 1814 15745 7872 15745 7874 15745 7871 15746 7872 15746 1814 15746 7864 15747 7871 15747 1814 15747 7867 15748 1812 15748 7865 15748 7865 15749 1812 15749 7868 15749 7865 15750 7868 15750 7866 15750 7866 15751 7868 15751 7869 15751 7866 15752 7869 15752 7864 15752 7864 15753 7869 15753 7870 15753 7864 15754 7870 15754 7871 15754 7871 15755 7870 15755 7873 15755 7871 15756 7873 15756 7872 15756 7872 15757 7873 15757 7875 15757 7872 15758 7875 15758 7874 15758 7874 15759 7875 15759 7851 15759 1807 15760 7876 15760 7880 15760 7879 15761 7876 15761 1807 15761 1804 15762 7879 15762 1807 15762 1807 15763 7877 15763 1806 15763 7881 15764 7877 15764 1807 15764 7880 15765 7881 15765 1807 15765 1804 15766 7878 15766 7879 15766 7879 15767 7878 15767 7855 15767 7879 15768 7855 15768 7876 15768 7876 15769 7855 15769 7858 15769 7876 15770 7858 15770 7880 15770 7880 15771 7858 15771 7859 15771 7880 15772 7859 15772 7881 15772 7881 15773 7859 15773 7842 15773 7881 15774 7842 15774 7877 15774 7877 15775 7842 15775 7840 15775 7877 15776 7840 15776 1806 15776 1806 15777 7840 15777 7882 15777 7911 15778 7926 15778 7884 15778 7884 15779 7926 15779 7924 15779 1787 15780 7924 15780 1788 15780 1788 15781 7924 15781 7900 15781 1787 15782 1785 15782 7924 15782 7924 15783 1785 15783 7883 15783 7924 15784 7883 15784 7884 15784 1780 15785 7887 15785 7916 15785 7916 15786 7887 15786 7892 15786 7916 15787 7892 15787 7894 15787 7895 15788 9218 15788 7924 15788 7924 15789 9218 15789 7885 15789 7924 15790 7885 15790 7900 15790 7890 15791 7923 15791 7886 15791 7886 15792 7923 15792 7891 15792 1780 15793 1778 15793 7887 15793 7887 15794 1778 15794 1777 15794 7887 15795 1777 15795 7888 15795 7888 15796 1777 15796 1776 15796 7888 15797 1776 15797 7889 15797 7889 15798 1776 15798 1775 15798 7889 15799 1775 15799 9229 15799 9229 15800 1775 15800 7890 15800 9229 15801 7890 15801 9227 15801 9227 15802 7890 15802 7886 15802 7911 15803 7909 15803 7926 15803 7926 15804 7909 15804 7908 15804 7926 15805 7908 15805 7907 15805 9236 15806 9233 15806 7892 15806 7892 15807 9233 15807 7891 15807 7923 15808 7922 15808 7891 15808 7891 15809 7922 15809 7919 15809 7891 15810 7919 15810 7892 15810 7892 15811 7919 15811 7893 15811 7892 15812 7893 15812 7894 15812 7889 15813 9224 15813 7888 15813 7888 15814 9224 15814 9217 15814 7888 15815 9217 15815 7895 15815 7895 15816 9217 15816 7896 15816 7895 15817 7896 15817 9218 15817 9236 15818 7892 15818 7897 15818 7897 15819 7892 15819 7926 15819 7897 15820 7926 15820 9231 15820 9231 15821 7926 15821 7907 15821 9231 15822 7907 15822 7898 15822 7898 15823 7907 15823 7904 15823 7898 15824 7904 15824 7899 15824 7899 15825 7904 15825 7903 15825 7899 15826 7903 15826 7900 15826 7900 15827 7903 15827 1790 15827 7900 15828 1790 15828 1788 15828 1795 15829 7906 15829 7901 15829 7905 15830 7906 15830 1795 15830 1789 15831 7905 15831 1795 15831 1795 15832 7910 15832 1791 15832 7902 15833 7910 15833 1795 15833 7901 15834 7902 15834 1795 15834 1789 15835 7903 15835 7905 15835 7905 15836 7903 15836 7904 15836 7905 15837 7904 15837 7906 15837 7906 15838 7904 15838 7907 15838 7906 15839 7907 15839 7901 15839 7901 15840 7907 15840 7908 15840 7901 15841 7908 15841 7902 15841 7902 15842 7908 15842 7909 15842 7902 15843 7909 15843 7910 15843 7910 15844 7909 15844 7911 15844 7910 15845 7911 15845 1791 15845 1791 15846 7911 15846 7884 15846 7913 15847 7918 15847 7920 15847 7917 15848 7918 15848 7913 15848 7912 15849 7917 15849 7913 15849 7913 15850 7914 15850 7915 15850 7921 15851 7914 15851 7913 15851 7920 15852 7921 15852 7913 15852 7912 15853 7916 15853 7917 15853 7917 15854 7916 15854 7894 15854 7917 15855 7894 15855 7918 15855 7918 15856 7894 15856 7893 15856 7918 15857 7893 15857 7920 15857 7920 15858 7893 15858 7919 15858 7920 15859 7919 15859 7921 15859 7921 15860 7919 15860 7922 15860 7921 15861 7922 15861 7914 15861 7914 15862 7922 15862 7923 15862 7914 15863 7923 15863 7915 15863 7915 15864 7923 15864 7890 15864 2737 15865 7924 15865 7925 15865 7925 15866 7924 15866 7926 15866 7887 15867 7927 15867 7892 15867 7892 15868 7927 15868 9238 15868 7848 15869 6842 15869 7861 15869 7861 15870 6842 15870 9253 15870 6391 15871 7839 15871 7928 15871 7928 15872 7839 15872 7841 15872 7967 15873 1746 15873 7929 15873 7929 15874 1746 15874 7931 15874 7929 15875 7931 15875 7930 15875 7930 15876 7931 15876 1747 15876 7930 15877 1747 15877 1773 15877 1773 15878 1747 15878 8018 15878 1773 15879 8018 15879 7969 15879 7969 15880 8018 15880 7932 15880 7969 15881 7932 15881 7933 15881 7933 15882 7932 15882 7934 15882 7933 15883 7934 15883 7971 15883 7971 15884 7934 15884 8023 15884 7971 15885 8023 15885 7936 15885 7936 15886 8023 15886 7935 15886 7936 15887 7935 15887 7973 15887 7973 15888 7935 15888 8024 15888 7973 15889 8024 15889 7937 15889 7937 15890 8024 15890 7938 15890 7937 15891 7938 15891 7939 15891 7939 15892 7938 15892 7940 15892 7939 15893 7940 15893 7941 15893 7941 15894 7940 15894 7942 15894 7941 15895 7942 15895 7975 15895 7975 15896 7942 15896 7943 15896 7975 15897 7943 15897 7976 15897 7976 15898 7943 15898 8027 15898 7976 15899 8027 15899 7944 15899 7944 15900 8027 15900 8028 15900 7944 15901 8028 15901 7945 15901 7945 15902 8028 15902 8030 15902 7945 15903 8030 15903 7946 15903 7946 15904 8030 15904 8032 15904 7946 15905 8032 15905 7978 15905 7978 15906 8032 15906 8034 15906 7978 15907 8034 15907 7981 15907 7981 15908 8034 15908 8035 15908 7981 15909 8035 15909 7982 15909 7982 15910 8035 15910 7947 15910 7982 15911 7947 15911 7983 15911 7983 15912 7947 15912 7948 15912 7983 15913 7948 15913 7985 15913 7985 15914 7948 15914 7949 15914 7985 15915 7949 15915 7986 15915 7986 15916 7949 15916 7950 15916 7986 15917 7950 15917 1748 15917 1748 15918 7950 15918 7951 15918 1748 15919 7951 15919 7953 15919 7953 15920 7951 15920 7952 15920 7953 15921 7952 15921 7954 15921 7954 15922 7952 15922 1736 15922 7954 15923 1736 15923 1751 15923 1751 15924 1736 15924 7955 15924 1751 15925 7955 15925 1752 15925 1752 15926 7955 15926 7957 15926 1752 15927 7957 15927 7956 15927 7956 15928 7957 15928 7958 15928 7956 15929 7958 15929 1756 15929 1756 15930 7958 15930 7959 15930 1756 15931 7959 15931 7960 15931 7960 15932 7959 15932 7961 15932 7960 15933 7961 15933 1760 15933 1760 15934 7961 15934 1739 15934 1760 15935 1739 15935 1761 15935 1761 15936 1739 15936 7962 15936 1761 15937 7962 15937 1763 15937 1763 15938 7962 15938 7963 15938 1763 15939 7963 15939 1765 15939 1765 15940 7963 15940 1741 15940 1765 15941 1741 15941 1766 15941 1766 15942 1741 15942 1744 15942 1766 15943 1744 15943 7964 15943 7964 15944 1744 15944 7965 15944 7964 15945 7965 15945 1769 15945 1769 15946 7965 15946 7966 15946 1769 15947 7966 15947 7967 15947 7967 15948 7966 15948 1746 15948 7968 15949 1773 15949 7969 15949 7968 15950 7969 15950 7988 15950 7988 15951 7969 15951 7933 15951 7988 15952 7933 15952 7970 15952 7970 15953 7933 15953 7971 15953 7970 15954 7971 15954 8016 15954 8016 15955 7971 15955 7936 15955 8016 15956 7936 15956 7972 15956 7972 15957 7936 15957 7973 15957 7972 15958 7973 15958 8015 15958 8015 15959 7973 15959 7937 15959 8015 15960 7937 15960 8014 15960 8014 15961 7937 15961 7939 15961 8014 15962 7939 15962 7974 15962 7974 15963 7939 15963 7941 15963 7974 15964 7941 15964 8012 15964 8012 15965 7941 15965 7975 15965 8012 15966 7975 15966 8011 15966 8011 15967 7975 15967 7976 15967 8011 15968 7976 15968 8009 15968 8009 15969 7976 15969 7944 15969 8009 15970 7944 15970 7977 15970 7977 15971 7944 15971 7945 15971 7977 15972 7945 15972 8008 15972 8008 15973 7945 15973 7946 15973 8008 15974 7946 15974 8007 15974 8007 15975 7946 15975 7978 15975 8007 15976 7978 15976 7979 15976 7979 15977 7978 15977 7981 15977 7979 15978 7981 15978 7980 15978 7980 15979 7981 15979 7982 15979 7980 15980 7982 15980 8005 15980 8005 15981 7982 15981 7983 15981 8005 15982 7983 15982 7984 15982 7984 15983 7983 15983 7985 15983 7984 15984 7985 15984 8004 15984 8004 15985 7985 15985 7986 15985 8004 15986 7986 15986 7987 15986 8016 15987 8057 15987 7970 15987 7970 15988 8057 15988 8060 15988 7970 15989 8060 15989 7988 15989 7988 15990 8060 15990 7989 15990 7988 15991 7989 15991 7968 15991 7968 15992 7989 15992 7990 15992 7968 15993 7990 15993 1772 15993 1772 15994 7990 15994 7991 15994 1772 15995 7991 15995 1771 15995 1771 15996 7991 15996 1720 15996 1771 15997 1720 15997 7992 15997 7992 15998 1720 15998 7993 15998 7992 15999 7993 15999 1770 15999 1770 16000 7993 16000 7994 16000 1770 16001 7994 16001 1768 16001 1768 16002 7994 16002 1723 16002 1768 16003 1723 16003 1767 16003 1767 16004 1723 16004 7996 16004 1767 16005 7996 16005 7995 16005 7995 16006 7996 16006 1725 16006 7995 16007 1725 16007 1764 16007 1764 16008 1725 16008 7997 16008 1764 16009 7997 16009 1762 16009 1762 16010 7997 16010 7998 16010 1762 16011 7998 16011 1759 16011 1759 16012 7998 16012 7999 16012 1759 16013 7999 16013 1758 16013 1758 16014 7999 16014 1728 16014 1758 16015 1728 16015 1757 16015 1757 16016 1728 16016 1729 16016 1757 16017 1729 16017 1755 16017 1755 16018 1729 16018 8000 16018 1755 16019 8000 16019 1754 16019 1754 16020 8000 16020 1730 16020 1754 16021 1730 16021 1753 16021 1753 16022 1730 16022 1732 16022 1753 16023 1732 16023 1750 16023 1750 16024 1732 16024 1733 16024 1750 16025 1733 16025 1749 16025 1749 16026 1733 16026 8001 16026 1749 16027 8001 16027 8002 16027 8002 16028 8001 16028 1735 16028 8002 16029 1735 16029 7987 16029 7987 16030 1735 16030 8003 16030 7987 16031 8003 16031 8004 16031 8004 16032 8003 16032 8039 16032 8004 16033 8039 16033 7984 16033 7984 16034 8039 16034 8040 16034 7984 16035 8040 16035 8005 16035 8005 16036 8040 16036 8006 16036 8005 16037 8006 16037 7980 16037 7980 16038 8006 16038 8042 16038 7980 16039 8042 16039 7979 16039 7979 16040 8042 16040 8043 16040 7979 16041 8043 16041 8007 16041 8007 16042 8043 16042 8044 16042 8007 16043 8044 16043 8008 16043 8008 16044 8044 16044 8045 16044 8008 16045 8045 16045 7977 16045 7977 16046 8045 16046 8046 16046 7977 16047 8046 16047 8009 16047 8009 16048 8046 16048 8047 16048 8009 16049 8047 16049 8011 16049 8011 16050 8047 16050 8010 16050 8011 16051 8010 16051 8012 16051 8012 16052 8010 16052 8013 16052 8012 16053 8013 16053 7974 16053 7974 16054 8013 16054 8051 16054 7974 16055 8051 16055 8014 16055 8014 16056 8051 16056 8053 16056 8014 16057 8053 16057 8015 16057 8015 16058 8053 16058 8054 16058 8015 16059 8054 16059 7972 16059 7972 16060 8054 16060 8055 16060 7972 16061 8055 16061 8016 16061 8016 16062 8055 16062 8057 16062 8018 16063 8017 16063 8019 16063 8018 16064 8019 16064 7932 16064 7932 16065 8019 16065 8020 16065 7932 16066 8020 16066 7934 16066 7934 16067 8020 16067 8021 16067 7934 16068 8021 16068 8023 16068 8023 16069 8021 16069 8022 16069 8023 16070 8022 16070 7935 16070 7935 16071 8022 16071 6357 16071 7935 16072 6357 16072 8024 16072 8024 16073 6357 16073 6359 16073 8024 16074 6359 16074 7938 16074 7938 16075 6359 16075 8025 16075 7938 16076 8025 16076 7940 16076 7940 16077 8025 16077 6361 16077 7940 16078 6361 16078 7942 16078 7942 16079 6361 16079 8026 16079 7942 16080 8026 16080 7943 16080 7943 16081 8026 16081 6363 16081 7943 16082 6363 16082 8027 16082 8027 16083 6363 16083 6364 16083 8027 16084 6364 16084 8028 16084 8028 16085 6364 16085 8029 16085 8028 16086 8029 16086 8030 16086 8030 16087 8029 16087 8031 16087 8030 16088 8031 16088 8032 16088 8032 16089 8031 16089 8033 16089 8032 16090 8033 16090 8034 16090 8034 16091 8033 16091 6367 16091 8034 16092 6367 16092 8035 16092 8035 16093 6367 16093 6369 16093 8035 16094 6369 16094 7947 16094 7947 16095 6369 16095 8036 16095 7947 16096 8036 16096 7948 16096 7948 16097 8036 16097 6370 16097 7948 16098 6370 16098 7949 16098 7949 16099 6370 16099 8037 16099 7949 16100 8037 16100 7950 16100 8003 16101 8038 16101 6352 16101 8003 16102 6352 16102 8039 16102 8039 16103 6352 16103 6351 16103 8039 16104 6351 16104 8040 16104 8040 16105 6351 16105 8041 16105 8040 16106 8041 16106 8006 16106 8006 16107 8041 16107 6350 16107 8006 16108 6350 16108 8042 16108 8042 16109 6350 16109 6349 16109 8042 16110 6349 16110 8043 16110 8043 16111 6349 16111 6347 16111 8043 16112 6347 16112 8044 16112 8044 16113 6347 16113 6346 16113 8044 16114 6346 16114 8045 16114 8045 16115 6346 16115 6345 16115 8045 16116 6345 16116 8046 16116 8046 16117 6345 16117 6344 16117 8046 16118 6344 16118 8047 16118 8047 16119 6344 16119 8048 16119 8047 16120 8048 16120 8010 16120 8010 16121 8048 16121 8049 16121 8010 16122 8049 16122 8013 16122 8013 16123 8049 16123 8050 16123 8013 16124 8050 16124 8051 16124 8051 16125 8050 16125 8052 16125 8051 16126 8052 16126 8053 16126 8053 16127 8052 16127 6341 16127 8053 16128 6341 16128 8054 16128 8054 16129 6341 16129 6340 16129 8054 16130 6340 16130 8055 16130 8055 16131 6340 16131 8056 16131 8055 16132 8056 16132 8057 16132 8057 16133 8056 16133 8058 16133 8057 16134 8058 16134 8060 16134 8060 16135 8058 16135 8059 16135 8060 16136 8059 16136 7989 16136 7989 16137 8059 16137 2779 16137 7989 16138 2779 16138 7990 16138 8099 16139 8100 16139 1715 16139 1715 16140 8100 16140 8061 16140 1715 16141 8061 16141 1716 16141 1716 16142 8061 16142 1566 16142 1716 16143 1566 16143 8062 16143 8062 16144 1566 16144 1567 16144 8062 16145 1567 16145 8063 16145 8063 16146 1567 16146 8064 16146 8063 16147 8064 16147 8065 16147 8065 16148 8064 16148 8066 16148 8065 16149 8066 16149 8102 16149 8102 16150 8066 16150 8822 16150 8102 16151 8822 16151 8103 16151 8103 16152 8822 16152 8067 16152 8103 16153 8067 16153 8105 16153 8105 16154 8067 16154 8825 16154 8105 16155 8825 16155 8107 16155 8107 16156 8825 16156 8068 16156 8107 16157 8068 16157 8109 16157 8109 16158 8068 16158 8069 16158 8109 16159 8069 16159 8110 16159 8110 16160 8069 16160 8070 16160 8110 16161 8070 16161 8071 16161 8071 16162 8070 16162 8828 16162 8071 16163 8828 16163 8111 16163 8111 16164 8828 16164 8072 16164 8111 16165 8072 16165 8073 16165 8073 16166 8072 16166 8829 16166 8073 16167 8829 16167 8112 16167 8112 16168 8829 16168 8074 16168 8112 16169 8074 16169 8114 16169 8114 16170 8074 16170 8075 16170 8114 16171 8075 16171 8076 16171 8076 16172 8075 16172 8832 16172 8076 16173 8832 16173 8118 16173 8118 16174 8832 16174 8077 16174 8118 16175 8077 16175 8119 16175 8119 16176 8077 16176 8835 16176 8119 16177 8835 16177 8078 16177 8078 16178 8835 16178 8837 16178 8078 16179 8837 16179 8079 16179 8079 16180 8837 16180 8080 16180 8079 16181 8080 16181 8121 16181 8121 16182 8080 16182 8839 16182 8121 16183 8839 16183 8082 16183 8082 16184 8839 16184 8081 16184 8082 16185 8081 16185 8083 16185 8083 16186 8081 16186 8085 16186 8083 16187 8085 16187 8084 16187 8084 16188 8085 16188 1553 16188 8084 16189 1553 16189 8087 16189 8087 16190 1553 16190 8086 16190 8087 16191 8086 16191 1702 16191 1702 16192 8086 16192 8089 16192 1702 16193 8089 16193 8088 16193 8088 16194 8089 16194 1555 16194 8088 16195 1555 16195 8090 16195 8090 16196 1555 16196 1556 16196 8090 16197 1556 16197 8091 16197 8091 16198 1556 16198 8092 16198 8091 16199 8092 16199 1705 16199 1705 16200 8092 16200 1557 16200 1705 16201 1557 16201 8093 16201 8093 16202 1557 16202 1559 16202 8093 16203 1559 16203 1708 16203 1708 16204 1559 16204 1560 16204 1708 16205 1560 16205 8094 16205 8094 16206 1560 16206 1562 16206 8094 16207 1562 16207 1711 16207 1711 16208 1562 16208 8095 16208 1711 16209 8095 16209 8097 16209 8097 16210 8095 16210 8096 16210 8097 16211 8096 16211 8098 16211 8098 16212 8096 16212 1564 16212 8098 16213 1564 16213 8099 16213 8099 16214 1564 16214 8100 16214 8101 16215 8102 16215 8103 16215 8101 16216 8103 16216 8104 16216 8104 16217 8103 16217 8105 16217 8104 16218 8105 16218 8106 16218 8106 16219 8105 16219 8107 16219 8106 16220 8107 16220 8108 16220 8108 16221 8107 16221 8109 16221 8108 16222 8109 16222 8147 16222 8147 16223 8109 16223 8110 16223 8147 16224 8110 16224 8145 16224 8145 16225 8110 16225 8071 16225 8145 16226 8071 16226 8143 16226 8143 16227 8071 16227 8111 16227 8143 16228 8111 16228 8142 16228 8142 16229 8111 16229 8073 16229 8142 16230 8073 16230 8140 16230 8140 16231 8073 16231 8112 16231 8140 16232 8112 16232 8113 16232 8113 16233 8112 16233 8114 16233 8113 16234 8114 16234 8115 16234 8115 16235 8114 16235 8076 16235 8115 16236 8076 16236 8116 16236 8116 16237 8076 16237 8118 16237 8116 16238 8118 16238 8117 16238 8117 16239 8118 16239 8119 16239 8117 16240 8119 16240 8137 16240 8137 16241 8119 16241 8078 16241 8137 16242 8078 16242 8136 16242 8136 16243 8078 16243 8079 16243 8136 16244 8079 16244 8133 16244 8133 16245 8079 16245 8121 16245 8133 16246 8121 16246 8120 16246 8120 16247 8121 16247 8082 16247 8120 16248 8082 16248 8132 16248 8132 16249 8082 16249 8083 16249 8132 16250 8083 16250 8122 16250 8122 16251 8083 16251 8084 16251 8122 16252 8084 16252 8123 16252 1706 16253 1547 16253 8124 16253 8124 16254 1547 16254 8125 16254 8124 16255 8125 16255 1704 16255 1704 16256 8125 16256 1548 16256 1704 16257 1548 16257 1703 16257 1703 16258 1548 16258 8126 16258 1703 16259 8126 16259 8127 16259 8127 16260 8126 16260 1550 16260 8127 16261 1550 16261 8128 16261 8128 16262 1550 16262 1551 16262 8128 16263 1551 16263 8129 16263 8129 16264 1551 16264 8130 16264 8129 16265 8130 16265 8123 16265 8123 16266 8130 16266 8844 16266 8123 16267 8844 16267 8122 16267 8122 16268 8844 16268 8131 16268 8122 16269 8131 16269 8132 16269 8132 16270 8131 16270 8846 16270 8132 16271 8846 16271 8120 16271 8120 16272 8846 16272 8134 16272 8120 16273 8134 16273 8133 16273 8133 16274 8134 16274 8848 16274 8133 16275 8848 16275 8136 16275 8136 16276 8848 16276 8135 16276 8136 16277 8135 16277 8137 16277 8137 16278 8135 16278 8850 16278 8137 16279 8850 16279 8117 16279 8117 16280 8850 16280 8138 16280 8117 16281 8138 16281 8116 16281 8116 16282 8138 16282 8852 16282 8116 16283 8852 16283 8115 16283 8115 16284 8852 16284 8139 16284 8115 16285 8139 16285 8113 16285 8113 16286 8139 16286 8853 16286 8113 16287 8853 16287 8140 16287 8140 16288 8853 16288 8141 16288 8140 16289 8141 16289 8142 16289 8142 16290 8141 16290 8854 16290 8142 16291 8854 16291 8143 16291 8143 16292 8854 16292 8144 16292 8143 16293 8144 16293 8145 16293 8145 16294 8144 16294 8146 16294 8145 16295 8146 16295 8147 16295 8147 16296 8146 16296 8148 16296 8147 16297 8148 16297 8108 16297 8108 16298 8148 16298 8149 16298 8108 16299 8149 16299 8106 16299 8106 16300 8149 16300 8150 16300 8106 16301 8150 16301 8104 16301 8104 16302 8150 16302 8151 16302 8104 16303 8151 16303 8101 16303 8101 16304 8151 16304 8152 16304 8101 16305 8152 16305 8153 16305 8153 16306 8152 16306 1538 16306 8153 16307 1538 16307 1718 16307 1718 16308 1538 16308 8155 16308 1718 16309 8155 16309 8154 16309 8154 16310 8155 16310 8156 16310 8154 16311 8156 16311 1717 16311 1717 16312 8156 16312 8157 16312 1717 16313 8157 16313 8158 16313 8158 16314 8157 16314 8159 16314 8158 16315 8159 16315 1714 16315 1714 16316 8159 16316 8160 16316 1714 16317 8160 16317 1713 16317 1713 16318 8160 16318 1544 16318 1713 16319 1544 16319 1712 16319 1712 16320 1544 16320 8161 16320 1712 16321 8161 16321 1710 16321 1710 16322 8161 16322 8162 16322 1710 16323 8162 16323 1709 16323 1709 16324 8162 16324 8163 16324 1709 16325 8163 16325 1707 16325 1707 16326 8163 16326 8164 16326 1707 16327 8164 16327 1706 16327 1706 16328 8164 16328 1547 16328 8216 16329 8879 16329 8165 16329 8165 16330 8879 16330 8166 16330 8165 16331 8166 16331 8219 16331 8219 16332 8166 16332 8167 16332 8219 16333 8167 16333 8221 16333 8221 16334 8167 16334 8881 16334 8221 16335 8881 16335 1683 16335 1683 16336 8881 16336 8882 16336 1683 16337 8882 16337 1684 16337 1684 16338 8882 16338 8168 16338 1684 16339 8168 16339 8169 16339 8169 16340 8168 16340 8170 16340 8169 16341 8170 16341 1687 16341 1687 16342 8170 16342 8171 16342 1687 16343 8171 16343 8172 16343 8172 16344 8171 16344 1519 16344 8172 16345 1519 16345 1689 16345 1689 16346 1519 16346 1520 16346 1689 16347 1520 16347 8173 16347 8173 16348 1520 16348 8174 16348 8173 16349 8174 16349 1691 16349 1691 16350 8174 16350 8175 16350 1691 16351 8175 16351 8176 16351 8176 16352 8175 16352 8177 16352 8176 16353 8177 16353 8178 16353 8178 16354 8177 16354 1523 16354 8178 16355 1523 16355 8179 16355 8179 16356 1523 16356 1525 16356 8179 16357 1525 16357 1693 16357 1693 16358 1525 16358 8180 16358 1693 16359 8180 16359 1694 16359 1694 16360 8180 16360 1526 16360 1694 16361 1526 16361 8181 16361 8181 16362 1526 16362 1528 16362 8181 16363 1528 16363 1697 16363 1697 16364 1528 16364 1530 16364 1697 16365 1530 16365 8182 16365 8182 16366 1530 16366 1532 16366 8182 16367 1532 16367 8183 16367 8183 16368 1532 16368 8184 16368 8183 16369 8184 16369 8185 16369 8185 16370 8184 16370 1535 16370 8185 16371 1535 16371 1701 16371 1701 16372 1535 16372 1537 16372 1701 16373 1537 16373 8203 16373 8203 16374 1537 16374 8860 16374 8203 16375 8860 16375 8186 16375 8186 16376 8860 16376 8188 16376 8186 16377 8188 16377 8187 16377 8187 16378 8188 16378 8862 16378 8187 16379 8862 16379 8189 16379 8189 16380 8862 16380 8190 16380 8189 16381 8190 16381 8205 16381 8205 16382 8190 16382 8865 16382 8205 16383 8865 16383 8191 16383 8191 16384 8865 16384 8868 16384 8191 16385 8868 16385 8207 16385 8207 16386 8868 16386 8192 16386 8207 16387 8192 16387 8193 16387 8193 16388 8192 16388 8195 16388 8193 16389 8195 16389 8194 16389 8194 16390 8195 16390 8196 16390 8194 16391 8196 16391 8211 16391 8211 16392 8196 16392 8871 16392 8211 16393 8871 16393 8198 16393 8198 16394 8871 16394 8197 16394 8198 16395 8197 16395 8213 16395 8213 16396 8197 16396 8875 16396 8213 16397 8875 16397 8214 16397 8214 16398 8875 16398 8199 16398 8214 16399 8199 16399 8201 16399 8201 16400 8199 16400 8200 16400 8201 16401 8200 16401 8202 16401 8202 16402 8200 16402 8877 16402 8202 16403 8877 16403 8216 16403 8216 16404 8877 16404 8879 16404 8243 16405 8203 16405 8186 16405 8243 16406 8186 16406 8242 16406 8242 16407 8186 16407 8187 16407 8242 16408 8187 16408 8204 16408 8204 16409 8187 16409 8189 16409 8204 16410 8189 16410 8241 16410 8241 16411 8189 16411 8205 16411 8241 16412 8205 16412 8206 16412 8206 16413 8205 16413 8191 16413 8206 16414 8191 16414 8208 16414 8208 16415 8191 16415 8207 16415 8208 16416 8207 16416 8238 16416 8238 16417 8207 16417 8193 16417 8238 16418 8193 16418 8209 16418 8209 16419 8193 16419 8194 16419 8209 16420 8194 16420 8210 16420 8210 16421 8194 16421 8211 16421 8210 16422 8211 16422 8235 16422 8235 16423 8211 16423 8198 16423 8235 16424 8198 16424 8212 16424 8212 16425 8198 16425 8213 16425 8212 16426 8213 16426 8234 16426 8234 16427 8213 16427 8214 16427 8234 16428 8214 16428 8215 16428 8215 16429 8214 16429 8201 16429 8215 16430 8201 16430 8232 16430 8232 16431 8201 16431 8202 16431 8232 16432 8202 16432 8231 16432 8231 16433 8202 16433 8216 16433 8231 16434 8216 16434 8217 16434 8217 16435 8216 16435 8165 16435 8217 16436 8165 16436 8218 16436 8218 16437 8165 16437 8219 16437 8218 16438 8219 16438 8229 16438 8229 16439 8219 16439 8221 16439 8229 16440 8221 16440 8220 16440 8220 16441 8221 16441 1683 16441 8220 16442 1683 16442 8226 16442 8222 16443 8254 16443 8223 16443 8223 16444 8254 16444 1509 16444 8223 16445 1509 16445 1690 16445 1690 16446 1509 16446 1510 16446 1690 16447 1510 16447 8224 16447 8224 16448 1510 16448 1512 16448 8224 16449 1512 16449 1688 16449 1688 16450 1512 16450 1513 16450 1688 16451 1513 16451 1686 16451 1686 16452 1513 16452 8225 16452 1686 16453 8225 16453 1685 16453 1685 16454 8225 16454 1515 16454 1685 16455 1515 16455 8226 16455 8226 16456 1515 16456 8227 16456 8226 16457 8227 16457 8220 16457 8220 16458 8227 16458 8228 16458 8220 16459 8228 16459 8229 16459 8229 16460 8228 16460 8883 16460 8229 16461 8883 16461 8218 16461 8218 16462 8883 16462 8230 16462 8218 16463 8230 16463 8217 16463 8217 16464 8230 16464 8885 16464 8217 16465 8885 16465 8231 16465 8231 16466 8885 16466 8888 16466 8231 16467 8888 16467 8232 16467 8232 16468 8888 16468 8233 16468 8232 16469 8233 16469 8215 16469 8215 16470 8233 16470 8889 16470 8215 16471 8889 16471 8234 16471 8234 16472 8889 16472 8891 16472 8234 16473 8891 16473 8212 16473 8212 16474 8891 16474 8893 16474 8212 16475 8893 16475 8235 16475 8235 16476 8893 16476 8894 16476 8235 16477 8894 16477 8210 16477 8210 16478 8894 16478 8236 16478 8210 16479 8236 16479 8209 16479 8209 16480 8236 16480 8237 16480 8209 16481 8237 16481 8238 16481 8238 16482 8237 16482 8239 16482 8238 16483 8239 16483 8208 16483 8208 16484 8239 16484 8896 16484 8208 16485 8896 16485 8206 16485 8206 16486 8896 16486 8240 16486 8206 16487 8240 16487 8241 16487 8241 16488 8240 16488 8898 16488 8241 16489 8898 16489 8204 16489 8204 16490 8898 16490 8900 16490 8204 16491 8900 16491 8242 16491 8242 16492 8900 16492 8902 16492 8242 16493 8902 16493 8243 16493 8243 16494 8902 16494 8244 16494 8243 16495 8244 16495 1700 16495 1700 16496 8244 16496 1495 16496 1700 16497 1495 16497 1699 16497 1699 16498 1495 16498 1496 16498 1699 16499 1496 16499 8245 16499 8245 16500 1496 16500 1498 16500 8245 16501 1498 16501 1698 16501 1698 16502 1498 16502 8247 16502 1698 16503 8247 16503 8246 16503 8246 16504 8247 16504 8248 16504 8246 16505 8248 16505 1696 16505 1696 16506 8248 16506 1500 16506 1696 16507 1500 16507 1695 16507 1695 16508 1500 16508 1501 16508 1695 16509 1501 16509 8249 16509 8249 16510 1501 16510 8250 16510 8249 16511 8250 16511 8251 16511 8251 16512 8250 16512 1504 16512 8251 16513 1504 16513 8252 16513 8252 16514 1504 16514 8253 16514 8252 16515 8253 16515 1692 16515 1692 16516 8253 16516 1506 16516 1692 16517 1506 16517 8222 16517 8222 16518 1506 16518 8254 16518 8293 16519 8255 16519 8256 16519 8256 16520 8255 16520 8904 16520 8256 16521 8904 16521 8295 16521 8295 16522 8904 16522 8258 16522 8295 16523 8258 16523 8257 16523 8257 16524 8258 16524 8259 16524 8257 16525 8259 16525 8297 16525 8297 16526 8259 16526 8907 16526 8297 16527 8907 16527 8299 16527 8299 16528 8907 16528 8260 16528 8299 16529 8260 16529 8262 16529 8262 16530 8260 16530 8261 16530 8262 16531 8261 16531 8302 16531 8302 16532 8261 16532 8908 16532 8302 16533 8908 16533 8263 16533 8263 16534 8908 16534 8909 16534 8263 16535 8909 16535 8303 16535 8303 16536 8909 16536 8264 16536 8303 16537 8264 16537 8305 16537 8305 16538 8264 16538 8265 16538 8305 16539 8265 16539 8308 16539 8308 16540 8265 16540 8266 16540 8308 16541 8266 16541 8267 16541 8267 16542 8266 16542 8913 16542 8267 16543 8913 16543 8310 16543 8310 16544 8913 16544 8915 16544 8310 16545 8915 16545 8268 16545 8268 16546 8915 16546 8916 16546 8268 16547 8916 16547 8311 16547 8311 16548 8916 16548 8919 16548 8311 16549 8919 16549 8313 16549 8313 16550 8919 16550 8269 16550 8313 16551 8269 16551 8270 16551 8270 16552 8269 16552 8271 16552 8270 16553 8271 16553 1668 16553 1668 16554 8271 16554 8272 16554 1668 16555 8272 16555 1669 16555 1669 16556 8272 16556 1475 16556 1669 16557 1475 16557 8273 16557 8273 16558 1475 16558 8275 16558 8273 16559 8275 16559 8274 16559 8274 16560 8275 16560 1477 16560 8274 16561 1477 16561 8276 16561 8276 16562 1477 16562 1478 16562 8276 16563 1478 16563 8277 16563 8277 16564 1478 16564 1480 16564 8277 16565 1480 16565 8278 16565 8278 16566 1480 16566 8279 16566 8278 16567 8279 16567 8280 16567 8280 16568 8279 16568 1483 16568 8280 16569 1483 16569 8281 16569 8281 16570 1483 16570 8282 16570 8281 16571 8282 16571 1675 16571 1675 16572 8282 16572 1485 16572 1675 16573 1485 16573 1676 16573 1676 16574 1485 16574 1486 16574 1676 16575 1486 16575 8283 16575 8283 16576 1486 16576 1487 16576 8283 16577 1487 16577 1677 16577 1677 16578 1487 16578 8284 16578 1677 16579 8284 16579 8285 16579 8285 16580 8284 16580 8287 16580 8285 16581 8287 16581 8286 16581 8286 16582 8287 16582 8288 16582 8286 16583 8288 16583 1678 16583 1678 16584 8288 16584 1490 16584 1678 16585 1490 16585 1679 16585 1679 16586 1490 16586 1492 16586 1679 16587 1492 16587 1680 16587 1680 16588 1492 16588 8290 16588 1680 16589 8290 16589 8289 16589 8289 16590 8290 16590 1493 16590 8289 16591 1493 16591 8291 16591 8291 16592 1493 16592 8292 16592 8291 16593 8292 16593 8293 16593 8293 16594 8292 16594 8255 16594 1682 16595 8291 16595 8293 16595 1682 16596 8293 16596 8344 16596 8344 16597 8293 16597 8256 16597 8344 16598 8256 16598 8294 16598 8294 16599 8256 16599 8295 16599 8294 16600 8295 16600 8343 16600 8343 16601 8295 16601 8257 16601 8343 16602 8257 16602 8296 16602 8296 16603 8257 16603 8297 16603 8296 16604 8297 16604 8298 16604 8298 16605 8297 16605 8299 16605 8298 16606 8299 16606 8339 16606 8339 16607 8299 16607 8262 16607 8339 16608 8262 16608 8300 16608 8300 16609 8262 16609 8302 16609 8300 16610 8302 16610 8301 16610 8301 16611 8302 16611 8263 16611 8301 16612 8263 16612 8337 16612 8337 16613 8263 16613 8303 16613 8337 16614 8303 16614 8304 16614 8304 16615 8303 16615 8305 16615 8304 16616 8305 16616 8306 16616 8306 16617 8305 16617 8308 16617 8306 16618 8308 16618 8307 16618 8307 16619 8308 16619 8267 16619 8307 16620 8267 16620 8309 16620 8309 16621 8267 16621 8310 16621 8309 16622 8310 16622 8335 16622 8335 16623 8310 16623 8268 16623 8335 16624 8268 16624 8334 16624 8334 16625 8268 16625 8311 16625 8334 16626 8311 16626 8312 16626 8312 16627 8311 16627 8313 16627 8312 16628 8313 16628 8314 16628 8314 16629 8313 16629 8270 16629 8314 16630 8270 16630 8315 16630 8315 16631 8270 16631 1668 16631 8315 16632 1668 16632 8316 16632 8317 16633 8318 16633 1674 16633 1674 16634 8318 16634 8319 16634 1674 16635 8319 16635 8320 16635 8320 16636 8319 16636 8321 16636 8320 16637 8321 16637 1673 16637 1673 16638 8321 16638 8322 16638 1673 16639 8322 16639 1672 16639 1672 16640 8322 16640 8323 16640 1672 16641 8323 16641 8324 16641 8324 16642 8323 16642 8325 16642 8324 16643 8325 16643 1671 16643 1671 16644 8325 16644 8326 16644 1671 16645 8326 16645 1670 16645 1670 16646 8326 16646 1470 16646 1670 16647 1470 16647 8327 16647 8327 16648 1470 16648 1471 16648 8327 16649 1471 16649 8328 16649 8328 16650 1471 16650 8329 16650 8328 16651 8329 16651 8316 16651 8316 16652 8329 16652 8330 16652 8316 16653 8330 16653 8315 16653 8315 16654 8330 16654 8331 16654 8315 16655 8331 16655 8314 16655 8314 16656 8331 16656 8332 16656 8314 16657 8332 16657 8312 16657 8312 16658 8332 16658 8333 16658 8312 16659 8333 16659 8334 16659 8334 16660 8333 16660 8923 16660 8334 16661 8923 16661 8335 16661 8335 16662 8923 16662 8925 16662 8335 16663 8925 16663 8309 16663 8309 16664 8925 16664 8336 16664 8309 16665 8336 16665 8307 16665 8307 16666 8336 16666 8927 16666 8307 16667 8927 16667 8306 16667 8306 16668 8927 16668 8928 16668 8306 16669 8928 16669 8304 16669 8304 16670 8928 16670 8930 16670 8304 16671 8930 16671 8337 16671 8337 16672 8930 16672 8338 16672 8337 16673 8338 16673 8301 16673 8301 16674 8338 16674 8933 16674 8301 16675 8933 16675 8300 16675 8300 16676 8933 16676 8934 16676 8300 16677 8934 16677 8339 16677 8339 16678 8934 16678 8340 16678 8339 16679 8340 16679 8298 16679 8298 16680 8340 16680 8341 16680 8298 16681 8341 16681 8296 16681 8296 16682 8341 16682 8342 16682 8296 16683 8342 16683 8343 16683 8343 16684 8342 16684 8939 16684 8343 16685 8939 16685 8294 16685 8294 16686 8939 16686 8940 16686 8294 16687 8940 16687 8344 16687 8344 16688 8940 16688 8345 16688 8344 16689 8345 16689 1682 16689 1682 16690 8345 16690 8346 16690 1682 16691 8346 16691 8347 16691 8347 16692 8346 16692 1455 16692 8347 16693 1455 16693 8348 16693 8348 16694 1455 16694 8349 16694 8348 16695 8349 16695 1681 16695 1681 16696 8349 16696 8350 16696 1681 16697 8350 16697 8351 16697 8351 16698 8350 16698 1459 16698 8351 16699 1459 16699 8352 16699 8352 16700 1459 16700 1461 16700 8352 16701 1461 16701 8353 16701 8353 16702 1461 16702 1462 16702 8353 16703 1462 16703 8354 16703 8354 16704 1462 16704 1463 16704 8354 16705 1463 16705 8355 16705 8355 16706 1463 16706 1464 16706 8355 16707 1464 16707 8317 16707 8317 16708 1464 16708 8318 16708 8387 16709 8944 16709 8356 16709 8356 16710 8944 16710 8945 16710 8356 16711 8945 16711 8357 16711 8357 16712 8945 16712 8358 16712 8357 16713 8358 16713 8359 16713 8359 16714 8358 16714 8948 16714 8359 16715 8948 16715 8390 16715 8390 16716 8948 16716 8361 16716 8390 16717 8361 16717 8360 16717 8360 16718 8361 16718 8950 16718 8360 16719 8950 16719 8362 16719 8362 16720 8950 16720 8952 16720 8362 16721 8952 16721 8363 16721 8363 16722 8952 16722 8953 16722 8363 16723 8953 16723 8396 16723 8396 16724 8953 16724 8955 16724 8396 16725 8955 16725 8398 16725 8398 16726 8955 16726 8364 16726 8398 16727 8364 16727 8365 16727 8365 16728 8364 16728 8958 16728 8365 16729 8958 16729 8399 16729 8399 16730 8958 16730 8960 16730 8399 16731 8960 16731 8401 16731 8401 16732 8960 16732 8367 16732 8401 16733 8367 16733 8366 16733 8366 16734 8367 16734 8962 16734 8366 16735 8962 16735 8403 16735 8403 16736 8962 16736 8963 16736 8403 16737 8963 16737 8368 16737 8368 16738 8963 16738 8370 16738 8368 16739 8370 16739 8369 16739 8369 16740 8370 16740 8965 16740 8369 16741 8965 16741 8407 16741 8407 16742 8965 16742 8967 16742 8407 16743 8967 16743 8371 16743 8371 16744 8967 16744 1428 16744 8371 16745 1428 16745 8372 16745 8372 16746 1428 16746 1430 16746 8372 16747 1430 16747 1650 16747 1650 16748 1430 16748 8374 16748 1650 16749 8374 16749 8373 16749 8373 16750 8374 16750 1432 16750 8373 16751 1432 16751 1652 16751 1652 16752 1432 16752 1434 16752 1652 16753 1434 16753 8375 16753 8375 16754 1434 16754 1435 16754 8375 16755 1435 16755 1654 16755 1654 16756 1435 16756 8376 16756 1654 16757 8376 16757 8377 16757 8377 16758 8376 16758 1437 16758 8377 16759 1437 16759 1656 16759 1656 16760 1437 16760 1439 16760 1656 16761 1439 16761 1657 16761 1657 16762 1439 16762 1440 16762 1657 16763 1440 16763 8378 16763 8378 16764 1440 16764 1443 16764 8378 16765 1443 16765 8379 16765 8379 16766 1443 16766 1445 16766 8379 16767 1445 16767 8380 16767 8380 16768 1445 16768 8381 16768 8380 16769 8381 16769 1659 16769 1659 16770 8381 16770 1446 16770 1659 16771 1446 16771 1660 16771 1660 16772 1446 16772 8382 16772 1660 16773 8382 16773 1662 16773 1662 16774 8382 16774 1450 16774 1662 16775 1450 16775 1665 16775 1665 16776 1450 16776 1451 16776 1665 16777 1451 16777 8383 16777 8383 16778 1451 16778 1452 16778 8383 16779 1452 16779 8385 16779 8385 16780 1452 16780 8384 16780 8385 16781 8384 16781 1666 16781 1666 16782 8384 16782 8386 16782 1666 16783 8386 16783 8387 16783 8387 16784 8386 16784 8944 16784 8433 16785 1666 16785 8387 16785 8433 16786 8387 16786 8388 16786 8388 16787 8387 16787 8356 16787 8388 16788 8356 16788 8389 16788 8389 16789 8356 16789 8357 16789 8389 16790 8357 16790 8431 16790 8431 16791 8357 16791 8359 16791 8431 16792 8359 16792 8391 16792 8391 16793 8359 16793 8390 16793 8391 16794 8390 16794 8392 16794 8392 16795 8390 16795 8360 16795 8392 16796 8360 16796 8393 16796 8393 16797 8360 16797 8362 16797 8393 16798 8362 16798 8394 16798 8394 16799 8362 16799 8363 16799 8394 16800 8363 16800 8395 16800 8395 16801 8363 16801 8396 16801 8395 16802 8396 16802 8426 16802 8426 16803 8396 16803 8398 16803 8426 16804 8398 16804 8397 16804 8397 16805 8398 16805 8365 16805 8397 16806 8365 16806 8424 16806 8424 16807 8365 16807 8399 16807 8424 16808 8399 16808 8400 16808 8400 16809 8399 16809 8401 16809 8400 16810 8401 16810 8402 16810 8402 16811 8401 16811 8366 16811 8402 16812 8366 16812 8421 16812 8421 16813 8366 16813 8403 16813 8421 16814 8403 16814 8404 16814 8404 16815 8403 16815 8368 16815 8404 16816 8368 16816 8405 16816 8405 16817 8368 16817 8369 16817 8405 16818 8369 16818 8406 16818 8406 16819 8369 16819 8407 16819 8406 16820 8407 16820 8408 16820 8408 16821 8407 16821 8371 16821 8408 16822 8371 16822 1649 16822 8439 16823 8409 16823 8410 16823 8410 16824 8409 16824 8412 16824 8410 16825 8412 16825 8411 16825 8411 16826 8412 16826 8413 16826 8411 16827 8413 16827 1655 16827 1655 16828 8413 16828 1416 16828 1655 16829 1416 16829 8414 16829 8414 16830 1416 16830 1418 16830 8414 16831 1418 16831 8415 16831 8415 16832 1418 16832 1421 16832 8415 16833 1421 16833 1653 16833 1653 16834 1421 16834 1422 16834 1653 16835 1422 16835 1651 16835 1651 16836 1422 16836 1425 16836 1651 16837 1425 16837 8416 16837 8416 16838 1425 16838 1426 16838 8416 16839 1426 16839 8417 16839 8417 16840 1426 16840 1427 16840 8417 16841 1427 16841 1649 16841 1649 16842 1427 16842 8418 16842 1649 16843 8418 16843 8408 16843 8408 16844 8418 16844 8970 16844 8408 16845 8970 16845 8406 16845 8406 16846 8970 16846 8971 16846 8406 16847 8971 16847 8405 16847 8405 16848 8971 16848 8419 16848 8405 16849 8419 16849 8404 16849 8404 16850 8419 16850 8420 16850 8404 16851 8420 16851 8421 16851 8421 16852 8420 16852 8973 16852 8421 16853 8973 16853 8402 16853 8402 16854 8973 16854 8422 16854 8402 16855 8422 16855 8400 16855 8400 16856 8422 16856 8423 16856 8400 16857 8423 16857 8424 16857 8424 16858 8423 16858 8425 16858 8424 16859 8425 16859 8397 16859 8397 16860 8425 16860 8427 16860 8397 16861 8427 16861 8426 16861 8426 16862 8427 16862 8975 16862 8426 16863 8975 16863 8395 16863 8395 16864 8975 16864 8428 16864 8395 16865 8428 16865 8394 16865 8394 16866 8428 16866 8429 16866 8394 16867 8429 16867 8393 16867 8393 16868 8429 16868 8977 16868 8393 16869 8977 16869 8392 16869 8392 16870 8977 16870 8430 16870 8392 16871 8430 16871 8391 16871 8391 16872 8430 16872 8978 16872 8391 16873 8978 16873 8431 16873 8431 16874 8978 16874 8432 16874 8431 16875 8432 16875 8389 16875 8389 16876 8432 16876 8979 16876 8389 16877 8979 16877 8388 16877 8388 16878 8979 16878 8981 16878 8388 16879 8981 16879 8433 16879 8433 16880 8981 16880 1404 16880 8433 16881 1404 16881 1667 16881 1667 16882 1404 16882 1406 16882 1667 16883 1406 16883 8434 16883 8434 16884 1406 16884 1407 16884 8434 16885 1407 16885 1664 16885 1664 16886 1407 16886 1409 16886 1664 16887 1409 16887 1663 16887 1663 16888 1409 16888 1410 16888 1663 16889 1410 16889 8435 16889 8435 16890 1410 16890 8436 16890 8435 16891 8436 16891 1661 16891 1661 16892 8436 16892 1412 16892 1661 16893 1412 16893 8437 16893 8437 16894 1412 16894 8438 16894 8437 16895 8438 16895 1658 16895 1658 16896 8438 16896 1413 16896 1658 16897 1413 16897 8439 16897 8439 16898 1413 16898 8409 16898 8496 16899 8440 16899 8497 16899 8497 16900 8440 16900 8441 16900 8497 16901 8441 16901 8442 16901 8442 16902 8441 16902 8443 16902 8442 16903 8443 16903 8445 16903 8445 16904 8443 16904 8444 16904 8445 16905 8444 16905 8446 16905 8446 16906 8444 16906 1385 16906 8446 16907 1385 16907 8447 16907 8447 16908 1385 16908 1386 16908 8447 16909 1386 16909 1630 16909 1630 16910 1386 16910 1388 16910 1630 16911 1388 16911 8448 16911 8448 16912 1388 16912 8450 16912 8448 16913 8450 16913 8449 16913 8449 16914 8450 16914 1390 16914 8449 16915 1390 16915 1632 16915 1632 16916 1390 16916 8451 16916 1632 16917 8451 16917 1635 16917 1635 16918 8451 16918 8452 16918 1635 16919 8452 16919 8453 16919 8453 16920 8452 16920 8454 16920 8453 16921 8454 16921 8455 16921 8455 16922 8454 16922 8456 16922 8455 16923 8456 16923 1636 16923 1636 16924 8456 16924 8457 16924 1636 16925 8457 16925 1638 16925 1638 16926 8457 16926 1393 16926 1638 16927 1393 16927 1641 16927 1641 16928 1393 16928 1395 16928 1641 16929 1395 16929 1642 16929 1642 16930 1395 16930 8458 16930 1642 16931 8458 16931 8459 16931 8459 16932 8458 16932 1396 16932 8459 16933 1396 16933 8460 16933 8460 16934 1396 16934 1398 16934 8460 16935 1398 16935 1643 16935 1643 16936 1398 16936 8461 16936 1643 16937 8461 16937 8462 16937 8462 16938 8461 16938 1400 16938 8462 16939 1400 16939 1646 16939 1646 16940 1400 16940 1401 16940 1646 16941 1401 16941 1647 16941 1647 16942 1401 16942 1402 16942 1647 16943 1402 16943 8480 16943 8480 16944 1402 16944 8982 16944 8480 16945 8982 16945 8463 16945 8463 16946 8982 16946 8464 16946 8463 16947 8464 16947 8481 16947 8481 16948 8464 16948 8465 16948 8481 16949 8465 16949 8466 16949 8466 16950 8465 16950 8467 16950 8466 16951 8467 16951 8483 16951 8483 16952 8467 16952 8984 16952 8483 16953 8984 16953 8468 16953 8468 16954 8984 16954 8469 16954 8468 16955 8469 16955 8471 16955 8471 16956 8469 16956 8470 16956 8471 16957 8470 16957 8485 16957 8485 16958 8470 16958 8987 16958 8485 16959 8987 16959 8488 16959 8488 16960 8987 16960 8472 16960 8488 16961 8472 16961 8473 16961 8473 16962 8472 16962 8991 16962 8473 16963 8991 16963 8489 16963 8489 16964 8991 16964 8474 16964 8489 16965 8474 16965 8490 16965 8490 16966 8474 16966 8476 16966 8490 16967 8476 16967 8475 16967 8475 16968 8476 16968 8477 16968 8475 16969 8477 16969 8494 16969 8494 16970 8477 16970 8478 16970 8494 16971 8478 16971 8495 16971 8495 16972 8478 16972 8992 16972 8495 16973 8992 16973 8496 16973 8496 16974 8992 16974 8440 16974 8479 16975 8480 16975 8463 16975 8479 16976 8463 16976 8520 16976 8520 16977 8463 16977 8481 16977 8520 16978 8481 16978 8482 16978 8482 16979 8481 16979 8466 16979 8482 16980 8466 16980 8519 16980 8519 16981 8466 16981 8483 16981 8519 16982 8483 16982 8517 16982 8517 16983 8483 16983 8468 16983 8517 16984 8468 16984 8516 16984 8516 16985 8468 16985 8471 16985 8516 16986 8471 16986 8484 16986 8484 16987 8471 16987 8485 16987 8484 16988 8485 16988 8486 16988 8486 16989 8485 16989 8488 16989 8486 16990 8488 16990 8487 16990 8487 16991 8488 16991 8473 16991 8487 16992 8473 16992 8515 16992 8515 16993 8473 16993 8489 16993 8515 16994 8489 16994 8491 16994 8491 16995 8489 16995 8490 16995 8491 16996 8490 16996 8514 16996 8514 16997 8490 16997 8475 16997 8514 16998 8475 16998 8492 16998 8492 16999 8475 16999 8494 16999 8492 17000 8494 17000 8493 17000 8493 17001 8494 17001 8495 17001 8493 17002 8495 17002 8511 17002 8511 17003 8495 17003 8496 17003 8511 17004 8496 17004 8510 17004 8510 17005 8496 17005 8497 17005 8510 17006 8497 17006 8508 17006 8508 17007 8497 17007 8442 17007 8508 17008 8442 17008 8507 17008 8507 17009 8442 17009 8445 17009 8507 17010 8445 17010 8498 17010 8498 17011 8445 17011 8446 17011 8498 17012 8446 17012 8504 17012 8533 17013 8534 17013 8499 17013 8499 17014 8534 17014 1380 17014 8499 17015 1380 17015 1634 17015 1634 17016 1380 17016 1381 17016 1634 17017 1381 17017 1633 17017 1633 17018 1381 17018 8500 17018 1633 17019 8500 17019 8501 17019 8501 17020 8500 17020 8502 17020 8501 17021 8502 17021 1631 17021 1631 17022 8502 17022 1383 17022 1631 17023 1383 17023 8503 17023 8503 17024 1383 17024 8505 17024 8503 17025 8505 17025 8504 17025 8504 17026 8505 17026 8506 17026 8504 17027 8506 17027 8498 17027 8498 17028 8506 17028 8997 17028 8498 17029 8997 17029 8507 17029 8507 17030 8997 17030 8509 17030 8507 17031 8509 17031 8508 17031 8508 17032 8509 17032 8998 17032 8508 17033 8998 17033 8510 17033 8510 17034 8998 17034 9000 17034 8510 17035 9000 17035 8511 17035 8511 17036 9000 17036 8512 17036 8511 17037 8512 17037 8493 17037 8493 17038 8512 17038 9002 17038 8493 17039 9002 17039 8492 17039 8492 17040 9002 17040 8513 17040 8492 17041 8513 17041 8514 17041 8514 17042 8513 17042 9004 17042 8514 17043 9004 17043 8491 17043 8491 17044 9004 17044 9005 17044 8491 17045 9005 17045 8515 17045 8515 17046 9005 17046 9007 17046 8515 17047 9007 17047 8487 17047 8487 17048 9007 17048 9008 17048 8487 17049 9008 17049 8486 17049 8486 17050 9008 17050 9010 17050 8486 17051 9010 17051 8484 17051 8484 17052 9010 17052 9012 17052 8484 17053 9012 17053 8516 17053 8516 17054 9012 17054 9013 17054 8516 17055 9013 17055 8517 17055 8517 17056 9013 17056 9014 17056 8517 17057 9014 17057 8519 17057 8519 17058 9014 17058 8518 17058 8519 17059 8518 17059 8482 17059 8482 17060 8518 17060 9016 17060 8482 17061 9016 17061 8520 17061 8520 17062 9016 17062 9017 17062 8520 17063 9017 17063 8479 17063 8479 17064 9017 17064 1369 17064 8479 17065 1369 17065 1648 17065 1648 17066 1369 17066 1371 17066 1648 17067 1371 17067 8521 17067 8521 17068 1371 17068 8522 17068 8521 17069 8522 17069 1645 17069 1645 17070 8522 17070 8523 17070 1645 17071 8523 17071 1644 17071 1644 17072 8523 17072 8524 17072 1644 17073 8524 17073 8525 17073 8525 17074 8524 17074 8527 17074 8525 17075 8527 17075 8526 17075 8526 17076 8527 17076 8528 17076 8526 17077 8528 17077 8529 17077 8529 17078 8528 17078 1374 17078 8529 17079 1374 17079 1640 17079 1640 17080 1374 17080 8530 17080 1640 17081 8530 17081 1639 17081 1639 17082 8530 17082 1376 17082 1639 17083 1376 17083 8531 17083 8531 17084 1376 17084 8532 17084 8531 17085 8532 17085 1637 17085 1637 17086 8532 17086 1378 17086 1637 17087 1378 17087 8533 17087 8533 17088 1378 17088 8534 17088 8573 17089 9034 17089 8580 17089 8580 17090 9034 17090 9035 17090 8580 17091 9035 17091 8535 17091 8535 17092 9035 17092 8536 17092 8535 17093 8536 17093 8582 17093 8582 17094 8536 17094 8537 17094 8582 17095 8537 17095 8584 17095 8584 17096 8537 17096 8538 17096 8584 17097 8538 17097 8539 17097 8539 17098 8538 17098 8540 17098 8539 17099 8540 17099 8585 17099 8585 17100 8540 17100 9038 17100 8585 17101 9038 17101 8541 17101 8541 17102 9038 17102 9039 17102 8541 17103 9039 17103 8542 17103 8542 17104 9039 17104 8543 17104 8542 17105 8543 17105 8588 17105 8588 17106 8543 17106 1350 17106 8588 17107 1350 17107 8544 17107 8544 17108 1350 17108 1352 17108 8544 17109 1352 17109 1611 17109 1611 17110 1352 17110 1353 17110 1611 17111 1353 17111 8545 17111 8545 17112 1353 17112 1354 17112 8545 17113 1354 17113 1614 17113 1614 17114 1354 17114 1355 17114 1614 17115 1355 17115 1615 17115 1615 17116 1355 17116 8546 17116 1615 17117 8546 17117 1616 17117 1616 17118 8546 17118 8547 17118 1616 17119 8547 17119 1617 17119 1617 17120 8547 17120 1358 17120 1617 17121 1358 17121 8549 17121 8549 17122 1358 17122 8548 17122 8549 17123 8548 17123 8550 17123 8550 17124 8548 17124 1360 17124 8550 17125 1360 17125 8551 17125 8551 17126 1360 17126 8552 17126 8551 17127 8552 17127 1622 17127 1622 17128 8552 17128 8553 17128 1622 17129 8553 17129 8554 17129 8554 17130 8553 17130 8555 17130 8554 17131 8555 17131 1623 17131 1623 17132 8555 17132 8556 17132 1623 17133 8556 17133 8557 17133 8557 17134 8556 17134 1363 17134 8557 17135 1363 17135 1624 17135 1624 17136 1363 17136 1364 17136 1624 17137 1364 17137 8558 17137 8558 17138 1364 17138 1365 17138 8558 17139 1365 17139 1627 17139 1627 17140 1365 17140 8559 17140 1627 17141 8559 17141 8560 17141 8560 17142 8559 17142 8561 17142 8560 17143 8561 17143 1628 17143 1628 17144 8561 17144 9019 17144 1628 17145 9019 17145 8562 17145 8562 17146 9019 17146 8563 17146 8562 17147 8563 17147 8564 17147 8564 17148 8563 17148 8565 17148 8564 17149 8565 17149 8566 17149 8566 17150 8565 17150 9023 17150 8566 17151 9023 17151 8576 17151 8576 17152 9023 17152 9025 17152 8576 17153 9025 17153 8577 17153 8577 17154 9025 17154 9026 17154 8577 17155 9026 17155 8567 17155 8567 17156 9026 17156 8568 17156 8567 17157 8568 17157 8569 17157 8569 17158 8568 17158 9029 17158 8569 17159 9029 17159 8570 17159 8570 17160 9029 17160 8572 17160 8570 17161 8572 17161 8571 17161 8571 17162 8572 17162 9032 17162 8571 17163 9032 17163 8573 17163 8573 17164 9032 17164 9034 17164 1629 17165 1628 17165 8562 17165 1629 17166 8562 17166 8632 17166 8632 17167 8562 17167 8564 17167 8632 17168 8564 17168 8574 17168 8574 17169 8564 17169 8566 17169 8574 17170 8566 17170 8575 17170 8575 17171 8566 17171 8576 17171 8575 17172 8576 17172 8630 17172 8630 17173 8576 17173 8577 17173 8630 17174 8577 17174 8628 17174 8628 17175 8577 17175 8567 17175 8628 17176 8567 17176 8578 17176 8578 17177 8567 17177 8569 17177 8578 17178 8569 17178 8627 17178 8627 17179 8569 17179 8570 17179 8627 17180 8570 17180 8625 17180 8625 17181 8570 17181 8571 17181 8625 17182 8571 17182 8623 17182 8623 17183 8571 17183 8573 17183 8623 17184 8573 17184 8579 17184 8579 17185 8573 17185 8580 17185 8579 17186 8580 17186 8622 17186 8622 17187 8580 17187 8535 17187 8622 17188 8535 17188 8581 17188 8581 17189 8535 17189 8582 17189 8581 17190 8582 17190 8583 17190 8583 17191 8582 17191 8584 17191 8583 17192 8584 17192 8619 17192 8619 17193 8584 17193 8539 17193 8619 17194 8539 17194 8586 17194 8586 17195 8539 17195 8585 17195 8586 17196 8585 17196 8616 17196 8616 17197 8585 17197 8541 17197 8616 17198 8541 17198 8587 17198 8587 17199 8541 17199 8542 17199 8587 17200 8542 17200 8614 17200 8614 17201 8542 17201 8588 17201 8614 17202 8588 17202 8613 17202 8632 17203 8589 17203 1629 17203 1629 17204 8589 17204 1333 17204 1629 17205 1333 17205 8590 17205 8590 17206 1333 17206 8591 17206 8590 17207 8591 17207 8592 17207 8592 17208 8591 17208 8593 17208 8592 17209 8593 17209 1626 17209 1626 17210 8593 17210 1335 17210 1626 17211 1335 17211 1625 17211 1625 17212 1335 17212 1337 17212 1625 17213 1337 17213 8594 17213 8594 17214 1337 17214 8595 17214 8594 17215 8595 17215 8597 17215 8597 17216 8595 17216 8596 17216 8597 17217 8596 17217 8598 17217 8598 17218 8596 17218 8599 17218 8598 17219 8599 17219 1621 17219 1621 17220 8599 17220 8600 17220 1621 17221 8600 17221 8601 17221 8601 17222 8600 17222 8602 17222 8601 17223 8602 17223 1620 17223 1620 17224 8602 17224 1341 17224 1620 17225 1341 17225 1619 17225 1619 17226 1341 17226 8603 17226 1619 17227 8603 17227 1618 17227 1618 17228 8603 17228 1342 17228 1618 17229 1342 17229 8604 17229 8604 17230 1342 17230 8606 17230 8604 17231 8606 17231 8605 17231 8605 17232 8606 17232 8607 17232 8605 17233 8607 17233 1613 17233 1613 17234 8607 17234 1345 17234 1613 17235 1345 17235 1612 17235 1612 17236 1345 17236 8608 17236 1612 17237 8608 17237 8609 17237 8609 17238 8608 17238 8610 17238 8609 17239 8610 17239 8612 17239 8612 17240 8610 17240 8611 17240 8612 17241 8611 17241 8613 17241 8613 17242 8611 17242 1349 17242 8613 17243 1349 17243 8614 17243 8614 17244 1349 17244 9041 17244 8614 17245 9041 17245 8587 17245 8587 17246 9041 17246 8615 17246 8587 17247 8615 17247 8616 17247 8616 17248 8615 17248 8617 17248 8616 17249 8617 17249 8586 17249 8586 17250 8617 17250 8618 17250 8586 17251 8618 17251 8619 17251 8619 17252 8618 17252 9042 17252 8619 17253 9042 17253 8583 17253 8583 17254 9042 17254 8620 17254 8583 17255 8620 17255 8581 17255 8581 17256 8620 17256 8621 17256 8581 17257 8621 17257 8622 17257 8622 17258 8621 17258 9044 17258 8622 17259 9044 17259 8579 17259 8579 17260 9044 17260 8624 17260 8579 17261 8624 17261 8623 17261 8623 17262 8624 17262 8626 17262 8623 17263 8626 17263 8625 17263 8625 17264 8626 17264 9045 17264 8625 17265 9045 17265 8627 17265 8627 17266 9045 17266 9047 17266 8627 17267 9047 17267 8578 17267 8578 17268 9047 17268 9048 17268 8578 17269 9048 17269 8628 17269 8628 17270 9048 17270 8629 17270 8628 17271 8629 17271 8630 17271 8630 17272 8629 17272 8631 17272 8630 17273 8631 17273 8575 17273 8575 17274 8631 17274 9051 17274 8575 17275 9051 17275 8574 17275 8574 17276 9051 17276 9052 17276 8574 17277 9052 17277 8632 17277 8632 17278 9052 17278 8589 17278 8680 17279 8661 17279 8633 17279 8633 17280 8661 17280 9064 17280 8633 17281 9064 17281 8634 17281 8634 17282 9064 17282 9066 17282 8634 17283 9066 17283 8683 17283 8683 17284 9066 17284 9067 17284 8683 17285 9067 17285 8635 17285 8635 17286 9067 17286 9068 17286 8635 17287 9068 17287 8636 17287 8636 17288 9068 17288 1312 17288 8636 17289 1312 17289 1592 17289 1592 17290 1312 17290 1313 17290 1592 17291 1313 17291 8637 17291 8637 17292 1313 17292 1314 17292 8637 17293 1314 17293 8638 17293 8638 17294 1314 17294 1315 17294 8638 17295 1315 17295 8639 17295 8639 17296 1315 17296 1317 17296 8639 17297 1317 17297 1596 17297 1596 17298 1317 17298 8640 17298 1596 17299 8640 17299 1598 17299 1598 17300 8640 17300 1318 17300 1598 17301 1318 17301 1599 17301 1599 17302 1318 17302 8641 17302 1599 17303 8641 17303 1600 17303 1600 17304 8641 17304 1321 17304 1600 17305 1321 17305 1602 17305 1602 17306 1321 17306 1323 17306 1602 17307 1323 17307 1604 17307 1604 17308 1323 17308 1324 17308 1604 17309 1324 17309 1605 17309 1605 17310 1324 17310 8642 17310 1605 17311 8642 17311 8644 17311 8644 17312 8642 17312 8643 17312 8644 17313 8643 17313 8645 17313 8645 17314 8643 17314 1326 17314 8645 17315 1326 17315 8646 17315 8646 17316 1326 17316 1327 17316 8646 17317 1327 17317 8647 17317 8647 17318 1327 17318 8648 17318 8647 17319 8648 17319 1608 17319 1608 17320 8648 17320 1329 17320 1608 17321 1329 17321 1609 17321 1609 17322 1329 17322 1330 17322 1609 17323 1330 17323 8649 17323 8649 17324 1330 17324 1332 17324 8649 17325 1332 17325 8662 17325 8662 17326 1332 17326 8650 17326 8662 17327 8650 17327 8663 17327 8663 17328 8650 17328 8651 17328 8663 17329 8651 17329 8664 17329 8664 17330 8651 17330 8652 17330 8664 17331 8652 17331 8665 17331 8665 17332 8652 17332 9055 17332 8665 17333 9055 17333 8667 17333 8667 17334 9055 17334 9057 17334 8667 17335 9057 17335 8668 17335 8668 17336 9057 17336 8653 17336 8668 17337 8653 17337 8669 17337 8669 17338 8653 17338 9058 17338 8669 17339 9058 17339 8654 17339 8654 17340 9058 17340 8655 17340 8654 17341 8655 17341 8672 17341 8672 17342 8655 17342 8656 17342 8672 17343 8656 17343 8673 17343 8673 17344 8656 17344 8657 17344 8673 17345 8657 17345 8674 17345 8674 17346 8657 17346 9060 17346 8674 17347 9060 17347 8658 17347 8658 17348 9060 17348 8659 17348 8658 17349 8659 17349 8676 17349 8676 17350 8659 17350 8660 17350 8676 17351 8660 17351 8678 17351 8678 17352 8660 17352 9062 17352 8678 17353 9062 17353 8680 17353 8680 17354 9062 17354 8661 17354 8717 17355 8649 17355 8662 17355 8717 17356 8662 17356 8715 17356 8715 17357 8662 17357 8663 17357 8715 17358 8663 17358 8714 17358 8714 17359 8663 17359 8664 17359 8714 17360 8664 17360 8666 17360 8666 17361 8664 17361 8665 17361 8666 17362 8665 17362 8712 17362 8712 17363 8665 17363 8667 17363 8712 17364 8667 17364 8710 17364 8710 17365 8667 17365 8668 17365 8710 17366 8668 17366 8709 17366 8709 17367 8668 17367 8669 17367 8709 17368 8669 17368 8670 17368 8670 17369 8669 17369 8654 17369 8670 17370 8654 17370 8671 17370 8671 17371 8654 17371 8672 17371 8671 17372 8672 17372 8706 17372 8706 17373 8672 17373 8673 17373 8706 17374 8673 17374 8705 17374 8705 17375 8673 17375 8674 17375 8705 17376 8674 17376 8675 17376 8675 17377 8674 17377 8658 17377 8675 17378 8658 17378 8703 17378 8703 17379 8658 17379 8676 17379 8703 17380 8676 17380 8677 17380 8677 17381 8676 17381 8678 17381 8677 17382 8678 17382 8679 17382 8679 17383 8678 17383 8680 17383 8679 17384 8680 17384 8702 17384 8702 17385 8680 17385 8633 17385 8702 17386 8633 17386 8681 17386 8681 17387 8633 17387 8634 17387 8681 17388 8634 17388 8682 17388 8682 17389 8634 17389 8683 17389 8682 17390 8683 17390 8697 17390 8697 17391 8683 17391 8635 17391 8697 17392 8635 17392 8695 17392 1603 17393 8685 17393 8684 17393 8684 17394 8685 17394 8686 17394 8684 17395 8686 17395 1601 17395 1601 17396 8686 17396 8687 17396 1601 17397 8687 17397 1597 17397 1597 17398 8687 17398 8689 17398 1597 17399 8689 17399 8688 17399 8688 17400 8689 17400 8691 17400 8688 17401 8691 17401 8690 17401 8690 17402 8691 17402 8693 17402 8690 17403 8693 17403 8692 17403 8692 17404 8693 17404 1308 17404 8692 17405 1308 17405 1595 17405 1595 17406 1308 17406 1309 17406 1595 17407 1309 17407 1594 17407 1594 17408 1309 17408 1310 17408 1594 17409 1310 17409 1593 17409 1593 17410 1310 17410 8694 17410 1593 17411 8694 17411 8695 17411 8695 17412 8694 17412 8696 17412 8695 17413 8696 17413 8697 17413 8697 17414 8696 17414 8698 17414 8697 17415 8698 17415 8682 17415 8682 17416 8698 17416 8699 17416 8682 17417 8699 17417 8681 17417 8681 17418 8699 17418 8700 17418 8681 17419 8700 17419 8702 17419 8702 17420 8700 17420 8701 17420 8702 17421 8701 17421 8679 17421 8679 17422 8701 17422 9070 17422 8679 17423 9070 17423 8677 17423 8677 17424 9070 17424 9072 17424 8677 17425 9072 17425 8703 17425 8703 17426 9072 17426 9073 17426 8703 17427 9073 17427 8675 17427 8675 17428 9073 17428 8704 17428 8675 17429 8704 17429 8705 17429 8705 17430 8704 17430 9076 17430 8705 17431 9076 17431 8706 17431 8706 17432 9076 17432 9077 17432 8706 17433 9077 17433 8671 17433 8671 17434 9077 17434 8707 17434 8671 17435 8707 17435 8670 17435 8670 17436 8707 17436 8708 17436 8670 17437 8708 17437 8709 17437 8709 17438 8708 17438 8711 17438 8709 17439 8711 17439 8710 17439 8710 17440 8711 17440 9079 17440 8710 17441 9079 17441 8712 17441 8712 17442 9079 17442 9080 17442 8712 17443 9080 17443 8666 17443 8666 17444 9080 17444 8713 17444 8666 17445 8713 17445 8714 17445 8714 17446 8713 17446 9083 17446 8714 17447 9083 17447 8715 17447 8715 17448 9083 17448 8716 17448 8715 17449 8716 17449 8717 17449 8717 17450 8716 17450 1298 17450 8717 17451 1298 17451 8718 17451 8718 17452 1298 17452 8719 17452 8718 17453 8719 17453 1610 17453 1610 17454 8719 17454 8720 17454 1610 17455 8720 17455 8721 17455 8721 17456 8720 17456 8722 17456 8721 17457 8722 17457 8723 17457 8723 17458 8722 17458 8725 17458 8723 17459 8725 17459 8724 17459 8724 17460 8725 17460 1302 17460 8724 17461 1302 17461 1607 17461 1607 17462 1302 17462 1303 17462 1607 17463 1303 17463 1606 17463 1606 17464 1303 17464 8726 17464 1606 17465 8726 17465 8727 17465 8727 17466 8726 17466 8728 17466 8727 17467 8728 17467 1603 17467 1603 17468 8728 17468 8685 17468 8768 17469 9100 17469 8782 17469 8782 17470 9100 17470 8729 17470 8782 17471 8729 17471 8730 17471 8730 17472 8729 17472 9103 17472 8730 17473 9103 17473 8784 17473 8784 17474 9103 17474 8731 17474 8784 17475 8731 17475 8786 17475 8786 17476 8731 17476 1280 17476 8786 17477 1280 17477 1571 17477 1571 17478 1280 17478 1281 17478 1571 17479 1281 17479 8732 17479 8732 17480 1281 17480 8733 17480 8732 17481 8733 17481 1573 17481 1573 17482 8733 17482 8735 17482 1573 17483 8735 17483 8734 17483 8734 17484 8735 17484 8736 17484 8734 17485 8736 17485 1575 17485 1575 17486 8736 17486 8737 17486 1575 17487 8737 17487 1578 17487 1578 17488 8737 17488 1283 17488 1578 17489 1283 17489 8738 17489 8738 17490 1283 17490 1285 17490 8738 17491 1285 17491 1580 17491 1580 17492 1285 17492 8739 17492 1580 17493 8739 17493 8740 17493 8740 17494 8739 17494 8741 17494 8740 17495 8741 17495 1582 17495 1582 17496 8741 17496 8742 17496 1582 17497 8742 17497 1583 17497 1583 17498 8742 17498 1288 17498 1583 17499 1288 17499 1585 17499 1585 17500 1288 17500 8744 17500 1585 17501 8744 17501 8743 17501 8743 17502 8744 17502 8745 17502 8743 17503 8745 17503 8746 17503 8746 17504 8745 17504 1290 17504 8746 17505 1290 17505 8747 17505 8747 17506 1290 17506 1292 17506 8747 17507 1292 17507 1587 17507 1587 17508 1292 17508 1293 17508 1587 17509 1293 17509 8748 17509 8748 17510 1293 17510 8749 17510 8748 17511 8749 17511 1589 17511 1589 17512 8749 17512 1296 17512 1589 17513 1296 17513 8769 17513 8769 17514 1296 17514 1297 17514 8769 17515 1297 17515 8750 17515 8750 17516 1297 17516 9085 17516 8750 17517 9085 17517 8751 17517 8751 17518 9085 17518 9086 17518 8751 17519 9086 17519 8771 17519 8771 17520 9086 17520 9088 17520 8771 17521 9088 17521 8752 17521 8752 17522 9088 17522 8754 17522 8752 17523 8754 17523 8753 17523 8753 17524 8754 17524 8755 17524 8753 17525 8755 17525 8756 17525 8756 17526 8755 17526 9090 17526 8756 17527 9090 17527 8757 17527 8757 17528 9090 17528 8758 17528 8757 17529 8758 17529 8759 17529 8759 17530 8758 17530 8760 17530 8759 17531 8760 17531 8761 17531 8761 17532 8760 17532 8762 17532 8761 17533 8762 17533 8763 17533 8763 17534 8762 17534 8764 17534 8763 17535 8764 17535 8776 17535 8776 17536 8764 17536 9093 17536 8776 17537 9093 17537 8765 17537 8765 17538 9093 17538 9096 17538 8765 17539 9096 17539 8779 17539 8779 17540 9096 17540 8766 17540 8779 17541 8766 17541 8767 17541 8767 17542 8766 17542 9099 17542 8767 17543 9099 17543 8768 17543 8768 17544 9099 17544 9100 17544 1591 17545 8769 17545 8750 17545 1591 17546 8750 17546 8810 17546 8810 17547 8750 17547 8751 17547 8810 17548 8751 17548 8770 17548 8770 17549 8751 17549 8771 17549 8770 17550 8771 17550 8809 17550 8809 17551 8771 17551 8752 17551 8809 17552 8752 17552 8772 17552 8772 17553 8752 17553 8753 17553 8772 17554 8753 17554 8773 17554 8773 17555 8753 17555 8756 17555 8773 17556 8756 17556 8774 17556 8774 17557 8756 17557 8757 17557 8774 17558 8757 17558 8775 17558 8775 17559 8757 17559 8759 17559 8775 17560 8759 17560 8807 17560 8807 17561 8759 17561 8761 17561 8807 17562 8761 17562 8806 17562 8806 17563 8761 17563 8763 17563 8806 17564 8763 17564 8804 17564 8804 17565 8763 17565 8776 17565 8804 17566 8776 17566 8777 17566 8777 17567 8776 17567 8765 17567 8777 17568 8765 17568 8778 17568 8778 17569 8765 17569 8779 17569 8778 17570 8779 17570 8802 17570 8802 17571 8779 17571 8767 17571 8802 17572 8767 17572 8780 17572 8780 17573 8767 17573 8768 17573 8780 17574 8768 17574 8781 17574 8781 17575 8768 17575 8782 17575 8781 17576 8782 17576 8783 17576 8783 17577 8782 17577 8730 17577 8783 17578 8730 17578 8799 17578 8799 17579 8730 17579 8784 17579 8799 17580 8784 17580 8785 17580 8785 17581 8784 17581 8786 17581 8785 17582 8786 17582 8787 17582 8788 17583 8821 17583 1581 17583 1581 17584 8821 17584 8789 17584 1581 17585 8789 17585 8790 17585 8790 17586 8789 17586 8791 17586 8790 17587 8791 17587 1579 17587 1579 17588 8791 17588 8792 17588 1579 17589 8792 17589 8793 17589 8793 17590 8792 17590 1274 17590 8793 17591 1274 17591 1577 17591 1577 17592 1274 17592 8794 17592 1577 17593 8794 17593 1576 17593 1576 17594 8794 17594 8795 17594 1576 17595 8795 17595 1574 17595 1574 17596 8795 17596 8796 17596 1574 17597 8796 17597 1572 17597 1572 17598 8796 17598 1277 17598 1572 17599 1277 17599 8797 17599 8797 17600 1277 17600 1278 17600 8797 17601 1278 17601 8787 17601 8787 17602 1278 17602 8798 17602 8787 17603 8798 17603 8785 17603 8785 17604 8798 17604 8800 17604 8785 17605 8800 17605 8799 17605 8799 17606 8800 17606 9105 17606 8799 17607 9105 17607 8783 17607 8783 17608 9105 17608 9107 17608 8783 17609 9107 17609 8781 17609 8781 17610 9107 17610 8801 17610 8781 17611 8801 17611 8780 17611 8780 17612 8801 17612 9109 17612 8780 17613 9109 17613 8802 17613 8802 17614 9109 17614 8803 17614 8802 17615 8803 17615 8778 17615 8778 17616 8803 17616 9111 17616 8778 17617 9111 17617 8777 17617 8777 17618 9111 17618 9112 17618 8777 17619 9112 17619 8804 17619 8804 17620 9112 17620 8805 17620 8804 17621 8805 17621 8806 17621 8806 17622 8805 17622 9113 17622 8806 17623 9113 17623 8807 17623 8807 17624 9113 17624 9114 17624 8807 17625 9114 17625 8775 17625 8775 17626 9114 17626 8808 17626 8775 17627 8808 17627 8774 17627 8774 17628 8808 17628 9115 17628 8774 17629 9115 17629 8773 17629 8773 17630 9115 17630 9116 17630 8773 17631 9116 17631 8772 17631 8772 17632 9116 17632 9117 17632 8772 17633 9117 17633 8809 17633 8809 17634 9117 17634 9119 17634 8809 17635 9119 17635 8770 17635 8770 17636 9119 17636 8811 17636 8770 17637 8811 17637 8810 17637 8810 17638 8811 17638 9121 17638 8810 17639 9121 17639 1591 17639 1591 17640 9121 17640 8812 17640 1591 17641 8812 17641 1590 17641 1590 17642 8812 17642 1262 17642 1590 17643 1262 17643 1588 17643 1588 17644 1262 17644 8814 17644 1588 17645 8814 17645 8813 17645 8813 17646 8814 17646 1264 17646 8813 17647 1264 17647 8815 17647 8815 17648 1264 17648 1265 17648 8815 17649 1265 17649 8816 17649 8816 17650 1265 17650 1266 17650 8816 17651 1266 17651 1586 17651 1586 17652 1266 17652 8817 17652 1586 17653 8817 17653 1584 17653 1584 17654 8817 17654 8819 17654 1584 17655 8819 17655 8818 17655 8818 17656 8819 17656 8820 17656 8818 17657 8820 17657 8788 17657 8788 17658 8820 17658 8821 17658 8822 17659 1570 17659 8823 17659 8822 17660 8823 17660 8067 17660 8067 17661 8823 17661 8824 17661 8067 17662 8824 17662 8825 17662 8825 17663 8824 17663 6338 17663 8825 17664 6338 17664 8068 17664 8068 17665 6338 17665 6339 17665 8068 17666 6339 17666 8069 17666 8069 17667 6339 17667 8826 17667 8069 17668 8826 17668 8070 17668 8070 17669 8826 17669 8827 17669 8070 17670 8827 17670 8828 17670 8828 17671 8827 17671 6342 17671 8828 17672 6342 17672 8072 17672 8072 17673 6342 17673 8830 17673 8072 17674 8830 17674 8829 17674 8829 17675 8830 17675 6343 17675 8829 17676 6343 17676 8074 17676 8074 17677 6343 17677 8831 17677 8074 17678 8831 17678 8075 17678 8075 17679 8831 17679 8833 17679 8075 17680 8833 17680 8832 17680 8832 17681 8833 17681 8834 17681 8832 17682 8834 17682 8077 17682 8077 17683 8834 17683 6348 17683 8077 17684 6348 17684 8835 17684 8835 17685 6348 17685 8836 17685 8835 17686 8836 17686 8837 17686 8837 17687 8836 17687 8838 17687 8837 17688 8838 17688 8080 17688 8080 17689 8838 17689 8840 17689 8080 17690 8840 17690 8839 17690 8839 17691 8840 17691 8841 17691 8839 17692 8841 17692 8081 17692 8081 17693 8841 17693 8842 17693 8081 17694 8842 17694 8085 17694 8085 17695 8842 17695 8843 17695 8085 17696 8843 17696 1553 17696 8844 17697 1552 17697 8845 17697 8844 17698 8845 17698 8131 17698 8131 17699 8845 17699 6336 17699 8131 17700 6336 17700 8846 17700 8846 17701 6336 17701 8847 17701 8846 17702 8847 17702 8134 17702 8134 17703 8847 17703 6334 17703 8134 17704 6334 17704 8848 17704 8848 17705 6334 17705 8849 17705 8848 17706 8849 17706 8135 17706 8135 17707 8849 17707 6332 17707 8135 17708 6332 17708 8850 17708 8850 17709 6332 17709 8851 17709 8850 17710 8851 17710 8138 17710 8138 17711 8851 17711 6331 17711 8138 17712 6331 17712 8852 17712 8852 17713 6331 17713 6329 17713 8852 17714 6329 17714 8139 17714 8139 17715 6329 17715 6328 17715 8139 17716 6328 17716 8853 17716 8853 17717 6328 17717 6327 17717 8853 17718 6327 17718 8141 17718 8141 17719 6327 17719 6326 17719 8141 17720 6326 17720 8854 17720 8854 17721 6326 17721 8855 17721 8854 17722 8855 17722 8144 17722 8144 17723 8855 17723 6325 17723 8144 17724 6325 17724 8146 17724 8146 17725 6325 17725 8856 17725 8146 17726 8856 17726 8148 17726 8148 17727 8856 17727 8857 17727 8148 17728 8857 17728 8149 17728 8149 17729 8857 17729 6323 17729 8149 17730 6323 17730 8150 17730 8150 17731 6323 17731 8858 17731 8150 17732 8858 17732 8151 17732 8151 17733 8858 17733 8859 17733 8151 17734 8859 17734 8152 17734 8860 17735 6322 17735 8861 17735 8860 17736 8861 17736 8188 17736 8188 17737 8861 17737 6324 17737 8188 17738 6324 17738 8862 17738 8862 17739 6324 17739 8863 17739 8862 17740 8863 17740 8190 17740 8190 17741 8863 17741 8864 17741 8190 17742 8864 17742 8865 17742 8865 17743 8864 17743 8866 17743 8865 17744 8866 17744 8868 17744 8868 17745 8866 17745 8867 17745 8868 17746 8867 17746 8192 17746 8192 17747 8867 17747 8869 17747 8192 17748 8869 17748 8195 17748 8195 17749 8869 17749 8870 17749 8195 17750 8870 17750 8196 17750 8196 17751 8870 17751 8872 17751 8196 17752 8872 17752 8871 17752 8871 17753 8872 17753 6330 17753 8871 17754 6330 17754 8197 17754 8197 17755 6330 17755 8873 17755 8197 17756 8873 17756 8875 17756 8875 17757 8873 17757 8874 17757 8875 17758 8874 17758 8199 17758 8199 17759 8874 17759 8876 17759 8199 17760 8876 17760 8200 17760 8200 17761 8876 17761 6333 17761 8200 17762 6333 17762 8877 17762 8877 17763 6333 17763 6335 17763 8877 17764 6335 17764 8879 17764 8879 17765 6335 17765 8878 17765 8879 17766 8878 17766 8166 17766 8166 17767 8878 17767 6337 17767 8166 17768 6337 17768 8167 17768 8167 17769 6337 17769 8880 17769 8167 17770 8880 17770 8881 17770 8881 17771 8880 17771 2781 17771 8881 17772 2781 17772 8882 17772 8227 17773 6320 17773 6319 17773 8227 17774 6319 17774 8228 17774 8228 17775 6319 17775 6318 17775 8228 17776 6318 17776 8883 17776 8883 17777 6318 17777 6317 17777 8883 17778 6317 17778 8230 17778 8230 17779 6317 17779 8884 17779 8230 17780 8884 17780 8885 17780 8885 17781 8884 17781 8886 17781 8885 17782 8886 17782 8888 17782 8888 17783 8886 17783 8887 17783 8888 17784 8887 17784 8233 17784 8233 17785 8887 17785 6314 17785 8233 17786 6314 17786 8889 17786 8889 17787 6314 17787 8890 17787 8889 17788 8890 17788 8891 17788 8891 17789 8890 17789 8892 17789 8891 17790 8892 17790 8893 17790 8893 17791 8892 17791 6312 17791 8893 17792 6312 17792 8894 17792 8894 17793 6312 17793 6310 17793 8894 17794 6310 17794 8236 17794 8236 17795 6310 17795 6309 17795 8236 17796 6309 17796 8237 17796 8237 17797 6309 17797 8895 17797 8237 17798 8895 17798 8239 17798 8239 17799 8895 17799 6304 17799 8239 17800 6304 17800 8896 17800 8896 17801 6304 17801 6303 17801 8896 17802 6303 17802 8240 17802 8240 17803 6303 17803 8897 17803 8240 17804 8897 17804 8898 17804 8898 17805 8897 17805 8899 17805 8898 17806 8899 17806 8900 17806 8900 17807 8899 17807 8901 17807 8900 17808 8901 17808 8902 17808 8902 17809 8901 17809 6301 17809 8902 17810 6301 17810 8244 17810 8292 17811 8903 17811 6302 17811 8292 17812 6302 17812 8255 17812 8255 17813 6302 17813 8905 17813 8255 17814 8905 17814 8904 17814 8904 17815 8905 17815 8906 17815 8904 17816 8906 17816 8258 17816 8258 17817 8906 17817 6305 17817 8258 17818 6305 17818 8259 17818 8259 17819 6305 17819 6306 17819 8259 17820 6306 17820 8907 17820 8907 17821 6306 17821 6307 17821 8907 17822 6307 17822 8260 17822 8260 17823 6307 17823 6308 17823 8260 17824 6308 17824 8261 17824 8261 17825 6308 17825 6311 17825 8261 17826 6311 17826 8908 17826 8908 17827 6311 17827 6313 17827 8908 17828 6313 17828 8909 17828 8909 17829 6313 17829 8910 17829 8909 17830 8910 17830 8264 17830 8264 17831 8910 17831 8911 17831 8264 17832 8911 17832 8265 17832 8265 17833 8911 17833 8912 17833 8265 17834 8912 17834 8266 17834 8266 17835 8912 17835 8914 17835 8266 17836 8914 17836 8913 17836 8913 17837 8914 17837 6315 17837 8913 17838 6315 17838 8915 17838 8915 17839 6315 17839 6316 17839 8915 17840 6316 17840 8916 17840 8916 17841 6316 17841 8917 17841 8916 17842 8917 17842 8919 17842 8919 17843 8917 17843 8918 17843 8919 17844 8918 17844 8269 17844 8269 17845 8918 17845 6321 17845 8269 17846 6321 17846 8271 17846 8271 17847 6321 17847 8920 17847 8271 17848 8920 17848 8272 17848 8330 17849 1474 17849 8921 17849 8330 17850 8921 17850 8331 17850 8331 17851 8921 17851 8922 17851 8331 17852 8922 17852 8332 17852 8332 17853 8922 17853 6298 17853 8332 17854 6298 17854 8333 17854 8333 17855 6298 17855 8924 17855 8333 17856 8924 17856 8923 17856 8923 17857 8924 17857 6296 17857 8923 17858 6296 17858 8925 17858 8925 17859 6296 17859 8926 17859 8925 17860 8926 17860 8336 17860 8336 17861 8926 17861 6294 17861 8336 17862 6294 17862 8927 17862 8927 17863 6294 17863 8929 17863 8927 17864 8929 17864 8928 17864 8928 17865 8929 17865 8931 17865 8928 17866 8931 17866 8930 17866 8930 17867 8931 17867 6292 17867 8930 17868 6292 17868 8338 17868 8338 17869 6292 17869 8932 17869 8338 17870 8932 17870 8933 17870 8933 17871 8932 17871 8935 17871 8933 17872 8935 17872 8934 17872 8934 17873 8935 17873 8936 17873 8934 17874 8936 17874 8340 17874 8340 17875 8936 17875 6290 17875 8340 17876 6290 17876 8341 17876 8341 17877 6290 17877 8937 17877 8341 17878 8937 17878 8342 17878 8342 17879 8937 17879 8938 17879 8342 17880 8938 17880 8939 17880 8939 17881 8938 17881 6288 17881 8939 17882 6288 17882 8940 17882 8940 17883 6288 17883 8941 17883 8940 17884 8941 17884 8345 17884 8345 17885 8941 17885 2827 17885 8345 17886 2827 17886 8346 17886 8386 17887 8942 17887 8943 17887 8386 17888 8943 17888 8944 17888 8944 17889 8943 17889 8946 17889 8944 17890 8946 17890 8945 17890 8945 17891 8946 17891 8947 17891 8945 17892 8947 17892 8358 17892 8358 17893 8947 17893 6289 17893 8358 17894 6289 17894 8948 17894 8948 17895 6289 17895 8949 17895 8948 17896 8949 17896 8361 17896 8361 17897 8949 17897 6291 17897 8361 17898 6291 17898 8950 17898 8950 17899 6291 17899 8951 17899 8950 17900 8951 17900 8952 17900 8952 17901 8951 17901 6293 17901 8952 17902 6293 17902 8953 17902 8953 17903 6293 17903 8954 17903 8953 17904 8954 17904 8955 17904 8955 17905 8954 17905 8956 17905 8955 17906 8956 17906 8364 17906 8364 17907 8956 17907 8957 17907 8364 17908 8957 17908 8958 17908 8958 17909 8957 17909 8959 17909 8958 17910 8959 17910 8960 17910 8960 17911 8959 17911 6295 17911 8960 17912 6295 17912 8367 17912 8367 17913 6295 17913 8961 17913 8367 17914 8961 17914 8962 17914 8962 17915 8961 17915 6297 17915 8962 17916 6297 17916 8963 17916 8963 17917 6297 17917 8964 17917 8963 17918 8964 17918 8370 17918 8370 17919 8964 17919 6299 17919 8370 17920 6299 17920 8965 17920 8965 17921 6299 17921 6300 17921 8965 17922 6300 17922 8967 17922 8967 17923 6300 17923 8966 17923 8967 17924 8966 17924 1428 17924 8418 17925 8968 17925 8969 17925 8418 17926 8969 17926 8970 17926 8970 17927 8969 17927 6287 17927 8970 17928 6287 17928 8971 17928 8971 17929 6287 17929 8972 17929 8971 17930 8972 17930 8419 17930 8419 17931 8972 17931 6284 17931 8419 17932 6284 17932 8420 17932 8420 17933 6284 17933 6282 17933 8420 17934 6282 17934 8973 17934 8973 17935 6282 17935 6281 17935 8973 17936 6281 17936 8422 17936 8422 17937 6281 17937 6279 17937 8422 17938 6279 17938 8423 17938 8423 17939 6279 17939 6277 17939 8423 17940 6277 17940 8425 17940 8425 17941 6277 17941 8974 17941 8425 17942 8974 17942 8427 17942 8427 17943 8974 17943 6276 17943 8427 17944 6276 17944 8975 17944 8975 17945 6276 17945 6274 17945 8975 17946 6274 17946 8428 17946 8428 17947 6274 17947 8976 17947 8428 17948 8976 17948 8429 17948 8429 17949 8976 17949 6273 17949 8429 17950 6273 17950 8977 17950 8977 17951 6273 17951 6272 17951 8977 17952 6272 17952 8430 17952 8430 17953 6272 17953 6270 17953 8430 17954 6270 17954 8978 17954 8978 17955 6270 17955 6268 17955 8978 17956 6268 17956 8432 17956 8432 17957 6268 17957 6267 17957 8432 17958 6267 17958 8979 17958 8979 17959 6267 17959 8980 17959 8979 17960 8980 17960 8981 17960 8981 17961 8980 17961 2847 17961 8981 17962 2847 17962 1404 17962 8982 17963 1403 17963 6266 17963 8982 17964 6266 17964 8464 17964 8464 17965 6266 17965 8983 17965 8464 17966 8983 17966 8465 17966 8465 17967 8983 17967 6269 17967 8465 17968 6269 17968 8467 17968 8467 17969 6269 17969 6271 17969 8467 17970 6271 17970 8984 17970 8984 17971 6271 17971 8985 17971 8984 17972 8985 17972 8469 17972 8469 17973 8985 17973 8986 17973 8469 17974 8986 17974 8470 17974 8470 17975 8986 17975 6275 17975 8470 17976 6275 17976 8987 17976 8987 17977 6275 17977 8988 17977 8987 17978 8988 17978 8472 17978 8472 17979 8988 17979 8989 17979 8472 17980 8989 17980 8991 17980 8991 17981 8989 17981 8990 17981 8991 17982 8990 17982 8474 17982 8474 17983 8990 17983 6278 17983 8474 17984 6278 17984 8476 17984 8476 17985 6278 17985 6280 17985 8476 17986 6280 17986 8477 17986 8477 17987 6280 17987 6283 17987 8477 17988 6283 17988 8478 17988 8478 17989 6283 17989 6285 17989 8478 17990 6285 17990 8992 17990 8992 17991 6285 17991 8993 17991 8992 17992 8993 17992 8440 17992 8440 17993 8993 17993 8994 17993 8440 17994 8994 17994 8441 17994 8441 17995 8994 17995 6286 17995 8441 17996 6286 17996 8443 17996 8443 17997 6286 17997 8995 17997 8443 17998 8995 17998 8444 17998 8444 17999 8995 17999 2828 17999 8444 18000 2828 18000 1385 18000 8506 18001 6265 18001 6263 18001 8506 18002 6263 18002 8997 18002 8997 18003 6263 18003 8996 18003 8997 18004 8996 18004 8509 18004 8509 18005 8996 18005 6260 18005 8509 18006 6260 18006 8998 18006 8998 18007 6260 18007 8999 18007 8998 18008 8999 18008 9000 18008 9000 18009 8999 18009 6257 18009 9000 18010 6257 18010 8512 18010 8512 18011 6257 18011 9001 18011 8512 18012 9001 18012 9002 18012 9002 18013 9001 18013 9003 18013 9002 18014 9003 18014 8513 18014 8513 18015 9003 18015 6255 18015 8513 18016 6255 18016 9004 18016 9004 18017 6255 18017 6254 18017 9004 18018 6254 18018 9005 18018 9005 18019 6254 18019 9006 18019 9005 18020 9006 18020 9007 18020 9007 18021 9006 18021 6253 18021 9007 18022 6253 18022 9008 18022 9008 18023 6253 18023 9009 18023 9008 18024 9009 18024 9010 18024 9010 18025 9009 18025 9011 18025 9010 18026 9011 18026 9012 18026 9012 18027 9011 18027 6252 18027 9012 18028 6252 18028 9013 18028 9013 18029 6252 18029 6250 18029 9013 18030 6250 18030 9014 18030 9014 18031 6250 18031 6249 18031 9014 18032 6249 18032 8518 18032 8518 18033 6249 18033 9015 18033 8518 18034 9015 18034 9016 18034 9016 18035 9015 18035 9018 18035 9016 18036 9018 18036 9017 18036 9017 18037 9018 18037 2869 18037 9017 18038 2869 18038 1369 18038 9019 18039 1368 18039 9020 18039 9019 18040 9020 18040 8563 18040 8563 18041 9020 18041 9021 18041 8563 18042 9021 18042 8565 18042 8565 18043 9021 18043 9022 18043 8565 18044 9022 18044 9023 18044 9023 18045 9022 18045 9024 18045 9023 18046 9024 18046 9025 18046 9025 18047 9024 18047 6251 18047 9025 18048 6251 18048 9026 18048 9026 18049 6251 18049 9027 18049 9026 18050 9027 18050 8568 18050 8568 18051 9027 18051 9028 18051 8568 18052 9028 18052 9029 18052 9029 18053 9028 18053 9030 18053 9029 18054 9030 18054 8572 18054 8572 18055 9030 18055 9031 18055 8572 18056 9031 18056 9032 18056 9032 18057 9031 18057 9033 18057 9032 18058 9033 18058 9034 18058 9034 18059 9033 18059 6256 18059 9034 18060 6256 18060 9035 18060 9035 18061 6256 18061 9036 18061 9035 18062 9036 18062 8536 18062 8536 18063 9036 18063 9037 18063 8536 18064 9037 18064 8537 18064 8537 18065 9037 18065 6258 18065 8537 18066 6258 18066 8538 18066 8538 18067 6258 18067 6259 18067 8538 18068 6259 18068 8540 18068 8540 18069 6259 18069 6261 18069 8540 18070 6261 18070 9038 18070 9038 18071 6261 18071 6262 18071 9038 18072 6262 18072 9039 18072 9039 18073 6262 18073 6264 18073 9039 18074 6264 18074 8543 18074 8543 18075 6264 18075 9040 18075 8543 18076 9040 18076 1350 18076 1349 18077 1348 18077 6247 18077 1349 18078 6247 18078 9041 18078 9041 18079 6247 18079 6245 18079 9041 18080 6245 18080 8615 18080 8615 18081 6245 18081 6243 18081 8615 18082 6243 18082 8617 18082 8617 18083 6243 18083 6242 18083 8617 18084 6242 18084 8618 18084 8618 18085 6242 18085 6241 18085 8618 18086 6241 18086 9042 18086 9042 18087 6241 18087 6240 18087 9042 18088 6240 18088 8620 18088 8620 18089 6240 18089 9043 18089 8620 18090 9043 18090 8621 18090 8621 18091 9043 18091 6237 18091 8621 18092 6237 18092 9044 18092 9044 18093 6237 18093 6234 18093 9044 18094 6234 18094 8624 18094 8624 18095 6234 18095 6232 18095 8624 18096 6232 18096 8626 18096 8626 18097 6232 18097 6231 18097 8626 18098 6231 18098 9045 18098 9045 18099 6231 18099 9046 18099 9045 18100 9046 18100 9047 18100 9047 18101 9046 18101 6229 18101 9047 18102 6229 18102 9048 18102 9048 18103 6229 18103 9049 18103 9048 18104 9049 18104 8629 18104 8629 18105 9049 18105 9050 18105 8629 18106 9050 18106 8631 18106 8631 18107 9050 18107 6225 18107 8631 18108 6225 18108 9051 18108 9051 18109 6225 18109 9053 18109 9051 18110 9053 18110 9052 18110 9052 18111 9053 18111 6223 18111 9052 18112 6223 18112 8589 18112 8589 18113 6223 18113 2890 18113 8589 18114 2890 18114 1333 18114 1332 18115 1331 18115 9054 18115 1332 18116 9054 18116 8650 18116 8650 18117 9054 18117 6224 18117 8650 18118 6224 18118 8651 18118 8651 18119 6224 18119 6226 18119 8651 18120 6226 18120 8652 18120 8652 18121 6226 18121 6227 18121 8652 18122 6227 18122 9055 18122 9055 18123 6227 18123 6228 18123 9055 18124 6228 18124 9057 18124 9057 18125 6228 18125 9056 18125 9057 18126 9056 18126 8653 18126 8653 18127 9056 18127 6230 18127 8653 18128 6230 18128 9058 18128 9058 18129 6230 18129 9059 18129 9058 18130 9059 18130 8655 18130 8655 18131 9059 18131 6233 18131 8655 18132 6233 18132 8656 18132 8656 18133 6233 18133 6235 18133 8656 18134 6235 18134 8657 18134 8657 18135 6235 18135 6236 18135 8657 18136 6236 18136 9060 18136 9060 18137 6236 18137 6238 18137 9060 18138 6238 18138 8659 18138 8659 18139 6238 18139 6239 18139 8659 18140 6239 18140 8660 18140 8660 18141 6239 18141 9061 18141 8660 18142 9061 18142 9062 18142 9062 18143 9061 18143 9063 18143 9062 18144 9063 18144 8661 18144 8661 18145 9063 18145 6244 18145 8661 18146 6244 18146 9064 18146 9064 18147 6244 18147 9065 18147 9064 18148 9065 18148 9066 18148 9066 18149 9065 18149 6246 18149 9066 18150 6246 18150 9067 18150 9067 18151 6246 18151 6248 18151 9067 18152 6248 18152 9068 18152 8696 18153 1311 18153 6201 18153 8696 18154 6201 18154 8698 18154 8698 18155 6201 18155 9069 18155 8698 18156 9069 18156 8699 18156 8699 18157 9069 18157 6200 18157 8699 18158 6200 18158 8700 18158 8700 18159 6200 18159 6199 18159 8700 18160 6199 18160 8701 18160 8701 18161 6199 18161 6197 18161 8701 18162 6197 18162 9070 18162 9070 18163 6197 18163 9071 18163 9070 18164 9071 18164 9072 18164 9072 18165 9071 18165 6196 18165 9072 18166 6196 18166 9073 18166 9073 18167 6196 18167 9074 18167 9073 18168 9074 18168 8704 18168 8704 18169 9074 18169 9075 18169 8704 18170 9075 18170 9076 18170 9076 18171 9075 18171 6193 18171 9076 18172 6193 18172 9077 18172 9077 18173 6193 18173 6192 18173 9077 18174 6192 18174 8707 18174 8707 18175 6192 18175 6191 18175 8707 18176 6191 18176 8708 18176 8708 18177 6191 18177 6190 18177 8708 18178 6190 18178 8711 18178 8711 18179 6190 18179 9078 18179 8711 18180 9078 18180 9079 18180 9079 18181 9078 18181 6187 18181 9079 18182 6187 18182 9080 18182 9080 18183 6187 18183 6186 18183 9080 18184 6186 18184 8713 18184 8713 18185 6186 18185 9081 18185 8713 18186 9081 18186 9083 18186 9083 18187 9081 18187 9082 18187 9083 18188 9082 18188 8716 18188 8716 18189 9082 18189 2932 18189 8716 18190 2932 18190 1298 18190 1297 18191 9084 18191 6184 18191 1297 18192 6184 18192 9085 18192 9085 18193 6184 18193 6185 18193 9085 18194 6185 18194 9086 18194 9086 18195 6185 18195 9087 18195 9086 18196 9087 18196 9088 18196 9088 18197 9087 18197 9089 18197 9088 18198 9089 18198 8754 18198 8754 18199 9089 18199 6188 18199 8754 18200 6188 18200 8755 18200 8755 18201 6188 18201 6189 18201 8755 18202 6189 18202 9090 18202 9090 18203 6189 18203 9091 18203 9090 18204 9091 18204 8758 18204 8758 18205 9091 18205 9092 18205 8758 18206 9092 18206 8760 18206 8760 18207 9092 18207 6194 18207 8760 18208 6194 18208 8762 18208 8762 18209 6194 18209 6195 18209 8762 18210 6195 18210 8764 18210 8764 18211 6195 18211 9094 18211 8764 18212 9094 18212 9093 18212 9093 18213 9094 18213 9095 18213 9093 18214 9095 18214 9096 18214 9096 18215 9095 18215 9097 18215 9096 18216 9097 18216 8766 18216 8766 18217 9097 18217 9098 18217 8766 18218 9098 18218 9099 18218 9099 18219 9098 18219 6198 18219 9099 18220 6198 18220 9100 18220 9100 18221 6198 18221 9101 18221 9100 18222 9101 18222 8729 18222 8729 18223 9101 18223 9102 18223 8729 18224 9102 18224 9103 18224 9103 18225 9102 18225 6202 18225 9103 18226 6202 18226 8731 18226 8731 18227 6202 18227 2910 18227 8731 18228 2910 18228 1280 18228 8798 18229 1279 18229 6222 18229 8798 18230 6222 18230 8800 18230 8800 18231 6222 18231 9104 18231 8800 18232 9104 18232 9105 18232 9105 18233 9104 18233 9106 18233 9105 18234 9106 18234 9107 18234 9107 18235 9106 18235 6220 18235 9107 18236 6220 18236 8801 18236 8801 18237 6220 18237 9108 18237 8801 18238 9108 18238 9109 18238 9109 18239 9108 18239 9110 18239 9109 18240 9110 18240 8803 18240 8803 18241 9110 18241 6219 18241 8803 18242 6219 18242 9111 18242 9111 18243 6219 18243 6217 18243 9111 18244 6217 18244 9112 18244 9112 18245 6217 18245 6215 18245 9112 18246 6215 18246 8805 18246 8805 18247 6215 18247 6214 18247 8805 18248 6214 18248 9113 18248 9113 18249 6214 18249 6213 18249 9113 18250 6213 18250 9114 18250 9114 18251 6213 18251 6211 18251 9114 18252 6211 18252 8808 18252 8808 18253 6211 18253 6210 18253 8808 18254 6210 18254 9115 18254 9115 18255 6210 18255 6208 18255 9115 18256 6208 18256 9116 18256 9116 18257 6208 18257 6207 18257 9116 18258 6207 18258 9117 18258 9117 18259 6207 18259 9118 18259 9117 18260 9118 18260 9119 18260 9119 18261 9118 18261 9120 18261 9119 18262 9120 18262 8811 18262 8811 18263 9120 18263 6204 18263 8811 18264 6204 18264 9121 18264 9121 18265 6204 18265 9122 18265 9121 18266 9122 18266 8812 18266 6413 18267 9216 18267 9223 18267 6413 18268 9223 18268 9123 18268 9123 18269 9223 18269 9225 18269 9123 18270 9225 18270 9328 18270 9328 18271 9225 18271 9124 18271 9328 18272 9124 18272 9125 18272 9125 18273 9124 18273 9222 18273 9125 18274 9222 18274 9330 18274 9228 18275 9126 18275 9324 18275 9324 18276 9126 18276 9127 18276 9126 18277 9234 18277 9127 18277 9127 18278 9234 18278 9235 18278 9127 18279 9235 18279 9130 18279 9232 18280 9329 18280 9128 18280 9128 18281 9329 18281 9130 18281 9128 18282 9130 18282 9129 18282 9129 18283 9130 18283 9235 18283 9327 18284 6412 18284 9131 18284 9131 18285 6412 18285 9230 18285 9131 18286 9230 18286 9132 18286 9132 18287 9230 18287 9133 18287 9132 18288 9133 18288 6414 18288 6414 18289 9133 18289 9226 18289 9134 18290 6415 18290 9220 18290 9134 18291 9220 18291 9326 18291 9326 18292 9220 18292 9221 18292 9326 18293 9221 18293 9135 18293 9135 18294 9221 18294 9136 18294 9135 18295 9136 18295 9137 18295 9137 18296 9136 18296 9219 18296 9137 18297 9219 18297 9325 18297 6417 18298 9138 18298 9139 18298 9139 18299 9138 18299 9140 18299 9139 18300 9140 18300 9212 18300 9212 18301 9140 18301 9214 18301 9214 18302 9140 18302 9141 18302 9214 18303 9141 18303 9142 18303 9142 18304 9141 18304 9143 18304 9143 18305 9141 18305 9144 18305 9143 18306 9144 18306 9145 18306 9146 18307 9316 18307 9200 18307 9200 18308 9316 18308 9322 18308 9200 18309 9322 18309 9147 18309 9147 18310 9322 18310 9204 18310 9204 18311 9322 18311 9323 18311 9204 18312 9323 18312 9148 18312 9148 18313 9323 18313 9202 18313 9202 18314 9323 18314 9321 18314 9202 18315 9321 18315 9201 18315 9197 18316 9320 18316 9149 18316 9149 18317 9320 18317 9318 18317 9149 18318 9318 18318 9151 18318 9151 18319 9318 18319 9150 18319 9151 18320 9150 18320 9206 18320 9206 18321 9150 18321 9319 18321 6416 18322 9317 18322 9210 18322 9210 18323 9317 18323 9152 18323 9210 18324 9152 18324 9209 18324 9209 18325 9152 18325 9153 18325 9209 18326 9153 18326 9154 18326 9154 18327 9153 18327 6418 18327 9155 18328 6540 18328 6205 18328 6205 18329 6540 18329 1260 18329 6205 18330 1260 18330 6203 18330 9157 18331 6755 18331 6206 18331 6206 18332 6755 18332 6554 18332 6206 18333 6554 18333 9155 18333 9155 18334 6554 18334 6543 18334 9155 18335 6543 18335 6540 18335 6635 18336 9157 18336 6598 18336 6598 18337 9157 18337 6209 18337 6635 18338 9156 18338 9157 18338 9157 18339 9156 18339 6753 18339 9157 18340 6753 18340 6755 18340 6616 18341 6209 18341 6743 18341 6743 18342 6209 18342 9158 18342 6616 18343 6594 18343 6209 18343 6209 18344 6594 18344 6590 18344 6209 18345 6590 18345 6598 18345 9162 18346 6419 18346 9159 18346 9159 18347 6419 18347 9160 18347 9159 18348 9160 18348 9158 18348 9158 18349 9160 18349 9161 18349 9158 18350 9161 18350 6743 18350 9162 18351 9159 18351 6420 18351 6420 18352 9159 18352 6212 18352 6420 18353 6212 18353 9163 18353 6218 18354 9164 18354 6216 18354 6216 18355 9164 18355 6607 18355 6216 18356 6607 18356 9165 18356 9165 18357 6607 18357 6734 18357 9165 18358 6734 18358 6212 18358 6212 18359 6734 18359 9166 18359 6212 18360 9166 18360 9163 18360 6732 18361 6571 18361 9167 18361 9167 18362 6571 18362 6583 18362 9167 18363 6583 18363 6218 18363 6218 18364 6583 18364 6605 18364 6218 18365 6605 18365 9164 18365 6732 18366 9167 18366 6727 18366 6727 18367 9167 18367 9170 18367 6727 18368 9170 18368 6726 18368 9168 18369 9169 18369 9175 18369 9175 18370 9169 18370 6621 18370 9175 18371 6621 18371 9170 18371 9170 18372 6621 18372 9171 18372 9170 18373 9171 18373 6726 18373 9176 18374 9178 18374 9174 18374 9174 18375 9178 18375 6653 18375 6653 18376 9172 18376 9174 18376 9174 18377 9172 18377 9173 18377 9174 18378 9173 18378 9175 18378 9175 18379 9173 18379 6623 18379 9175 18380 6623 18380 9168 18380 6221 18381 9177 18381 9176 18381 9176 18382 9177 18382 6718 18382 9176 18383 6718 18383 9178 18383 6534 18384 6528 18384 6221 18384 6221 18385 6528 18385 9179 18385 6221 18386 9179 18386 9177 18386 6221 18387 9180 18387 6534 18387 6534 18388 9180 18388 1235 18388 6534 18389 1235 18389 1237 18389 1234 18390 2738 18390 9181 18390 1234 18391 9181 18391 9182 18391 9182 18392 9181 18392 9183 18392 9182 18393 9183 18393 9184 18393 9184 18394 9183 18394 6368 18394 9184 18395 6368 18395 9185 18395 9185 18396 6368 18396 6366 18396 9185 18397 6366 18397 6129 18397 6129 18398 6366 18398 9186 18398 6129 18399 9186 18399 6127 18399 6127 18400 9186 18400 6365 18400 6127 18401 6365 18401 9187 18401 9187 18402 6365 18402 9188 18402 9187 18403 9188 18403 6124 18403 6124 18404 9188 18404 9189 18404 6124 18405 9189 18405 6123 18405 6123 18406 9189 18406 9190 18406 6123 18407 9190 18407 9191 18407 9191 18408 9190 18408 6362 18408 9191 18409 6362 18409 6122 18409 6122 18410 6362 18410 9192 18410 6122 18411 9192 18411 6121 18411 6121 18412 9192 18412 6360 18412 6121 18413 6360 18413 6120 18413 6120 18414 6360 18414 6358 18414 6120 18415 6358 18415 9193 18415 9193 18416 6358 18416 6356 18416 9193 18417 6356 18417 6117 18417 6117 18418 6356 18418 6355 18418 6117 18419 6355 18419 6116 18419 6116 18420 6355 18420 6354 18420 6116 18421 6354 18421 6115 18421 6115 18422 6354 18422 9195 18422 6115 18423 9195 18423 9194 18423 9194 18424 9195 18424 6353 18424 9194 18425 6353 18425 6113 18425 6113 18426 6353 18426 9196 18426 6113 18427 9196 18427 1213 18427 9197 18428 7863 18428 9201 18428 9201 18429 7863 18429 7862 18429 9206 18430 7850 18430 9151 18430 9151 18431 7850 18431 9198 18431 9151 18432 9198 18432 9149 18432 9149 18433 9198 18433 7860 18433 9149 18434 7860 18434 9197 18434 9197 18435 7860 18435 7863 18435 7856 18436 9199 18436 9146 18436 9146 18437 9200 18437 7856 18437 7856 18438 9200 18438 9147 18438 7856 18439 9147 18439 7857 18439 7857 18440 9147 18440 9204 18440 7857 18441 9204 18441 9203 18441 9201 18442 7862 18442 9202 18442 9202 18443 7862 18443 9203 18443 9202 18444 9203 18444 9148 18444 9148 18445 9203 18445 9204 18445 6416 18446 9205 18446 9206 18446 9206 18447 9205 18447 7850 18447 7845 18448 9145 18448 9199 18448 9199 18449 9145 18449 9146 18449 9154 18450 9207 18450 9209 18450 9209 18451 9207 18451 9208 18451 9209 18452 9208 18452 9210 18452 9210 18453 9208 18453 7853 18453 9210 18454 7853 18454 6416 18454 6416 18455 7853 18455 9205 18455 9211 18456 9215 18456 6417 18456 6417 18457 9139 18457 9211 18457 9211 18458 9139 18458 9212 18458 9211 18459 9212 18459 9213 18459 9213 18460 9212 18460 9214 18460 9213 18461 9214 18461 7844 18461 9145 18462 7845 18462 9143 18462 9143 18463 7845 18463 7844 18463 9143 18464 7844 18464 9142 18464 9142 18465 7844 18465 9214 18465 6417 18466 9215 18466 9154 18466 9154 18467 9215 18467 9207 18467 9219 18468 7896 18468 9216 18468 9216 18469 7896 18469 9217 18469 7896 18470 9219 18470 9218 18470 9218 18471 9219 18471 9136 18471 9218 18472 9136 18472 7885 18472 6415 18473 7900 18473 9220 18473 9220 18474 7900 18474 7885 18474 9220 18475 7885 18475 9221 18475 9221 18476 7885 18476 9136 18476 9229 18477 9222 18477 7889 18477 7889 18478 9222 18478 9124 18478 7889 18479 9124 18479 9224 18479 9216 18480 9217 18480 9223 18480 9223 18481 9217 18481 9224 18481 9223 18482 9224 18482 9225 18482 9225 18483 9224 18483 9124 18483 9226 18484 7899 18484 6415 18484 6415 18485 7899 18485 7900 18485 9227 18486 9228 18486 9229 18486 9229 18487 9228 18487 9222 18487 6412 18488 7897 18488 9230 18488 9230 18489 7897 18489 9231 18489 9230 18490 9231 18490 9133 18490 9133 18491 9231 18491 7898 18491 9133 18492 7898 18492 9226 18492 9226 18493 7898 18493 7899 18493 9233 18494 9236 18494 9232 18494 9232 18495 9128 18495 9233 18495 9233 18496 9128 18496 9129 18496 9233 18497 9129 18497 7891 18497 7891 18498 9129 18498 9235 18498 7891 18499 9235 18499 7886 18499 9228 18500 9227 18500 9126 18500 9126 18501 9227 18501 7886 18501 9126 18502 7886 18502 9234 18502 9234 18503 7886 18503 9235 18503 9232 18504 9236 18504 6412 18504 6412 18505 9236 18505 7897 18505 9237 18506 9238 18506 6379 18506 9237 18507 6379 18507 6392 18507 6392 18508 6379 18508 6381 18508 6392 18509 6381 18509 9239 18509 9239 18510 6381 18510 6382 18510 9239 18511 6382 18511 9240 18511 9240 18512 6382 18512 9241 18512 9240 18513 9241 18513 6397 18513 6397 18514 9241 18514 9243 18514 6397 18515 9243 18515 9242 18515 9242 18516 9243 18516 9244 18516 9242 18517 9244 18517 9245 18517 9245 18518 9244 18518 9247 18518 9245 18519 9247 18519 9246 18519 9246 18520 9247 18520 9248 18520 9246 18521 9248 18521 6407 18521 6407 18522 9248 18522 9249 18522 6407 18523 9249 18523 6408 18523 6408 18524 9249 18524 6389 18524 6408 18525 6389 18525 6409 18525 6409 18526 6389 18526 9250 18526 6409 18527 9250 18527 6410 18527 6410 18528 9250 18528 9251 18528 6410 18529 9251 18529 6411 18529 6411 18530 9251 18530 7928 18530 6411 18531 7928 18531 9252 18531 7892 18532 9238 18532 6406 18532 6406 18533 9238 18533 9237 18533 7928 18534 7841 18534 9252 18534 9252 18535 7841 18535 6404 18535 6405 18536 7926 18536 6406 18536 6406 18537 7926 18537 7892 18537 7861 18538 6400 18538 7841 18538 7841 18539 6400 18539 6404 18539 7925 18540 7926 18540 6403 18540 6403 18541 7926 18541 6405 18541 7861 18542 9253 18542 6400 18542 6400 18543 9253 18543 9254 18543 9254 18544 9253 18544 9255 18544 9254 18545 9255 18545 9256 18545 9256 18546 9255 18546 6372 18546 9256 18547 6372 18547 6393 18547 6393 18548 6372 18548 6374 18548 6393 18549 6374 18549 9257 18549 9257 18550 6374 18550 9259 18550 9257 18551 9259 18551 9258 18551 9258 18552 9259 18552 6377 18552 9258 18553 6377 18553 6395 18553 6395 18554 6377 18554 9260 18554 6395 18555 9260 18555 6396 18555 6396 18556 9260 18556 2733 18556 6396 18557 2733 18557 6394 18557 9261 18558 2558 18558 2559 18558 2557 18559 2558 18559 2554 18559 2554 18560 2558 18560 9261 18560 2554 18561 9261 18561 2553 18561 6968 18562 6969 18562 9262 18562 9262 18563 6969 18563 9261 18563 9262 18564 9261 18564 2561 18564 2561 18565 9261 18565 2559 18565 6971 18566 6972 18566 9261 18566 9261 18567 6972 18567 6973 18567 9261 18568 6973 18568 2553 18568 9263 18569 6962 18569 9268 18569 9268 18570 6962 18570 9267 18570 9268 18571 2564 18571 2566 18571 9264 18572 9265 18572 9266 18572 9266 18573 9265 18573 9268 18573 9266 18574 9268 18574 6964 18574 6964 18575 9268 18575 9267 18575 6964 18576 9267 18576 6963 18576 9263 18577 9268 18577 2568 18577 2568 18578 9268 18578 2566 18578 2568 18579 2566 18579 9269 18579 2570 18580 2572 18580 9270 18580 2572 18581 2574 18581 9270 18581 9270 18582 2574 18582 9271 18582 9270 18583 9271 18583 9275 18583 6958 18584 6960 18584 9270 18584 9270 18585 6960 18585 6961 18585 9270 18586 6961 18586 2570 18586 9272 18587 6956 18587 9273 18587 9273 18588 6956 18588 9270 18588 9273 18589 9270 18589 9274 18589 9274 18590 9270 18590 9275 18590 6950 18591 6952 18591 9281 18591 2581 18592 9276 18592 9278 18592 9278 18593 9276 18593 9281 18593 2577 18594 9277 18594 2576 18594 2576 18595 9277 18595 9278 18595 2576 18596 9278 18596 6954 18596 6954 18597 9278 18597 9281 18597 9279 18598 6950 18598 9280 18598 9280 18599 6950 18599 9281 18599 9280 18600 9281 18600 2583 18600 2583 18601 9281 18601 9276 18601 9285 18602 6945 18602 6946 18602 9284 18603 9282 18603 9285 18603 9285 18604 9282 18604 2589 18604 9283 18605 9284 18605 2585 18605 2585 18606 9284 18606 9285 18606 2585 18607 9285 18607 6949 18607 6949 18608 9285 18608 6946 18608 6942 18609 6943 18609 2592 18609 2592 18610 6943 18610 9285 18610 2592 18611 9285 18611 2591 18611 2591 18612 9285 18612 2589 18612 9290 18613 6938 18613 9286 18613 9286 18614 6938 18614 9288 18614 2594 18615 2596 18615 9287 18615 9287 18616 2596 18616 9286 18616 9287 18617 9286 18617 6940 18617 6940 18618 9286 18618 9288 18618 6936 18619 9290 18619 9289 18619 9289 18620 9290 18620 9286 18620 9289 18621 9286 18621 6934 18621 6934 18622 9286 18622 2597 18622 6930 18623 9291 18623 9293 18623 2598 18624 2599 18624 6930 18624 6930 18625 2599 18625 2602 18625 6930 18626 2602 18626 9291 18626 6928 18627 6929 18627 9292 18627 9292 18628 6929 18628 6930 18628 9292 18629 6930 18629 2605 18629 2605 18630 6930 18630 9293 18630 6932 18631 9294 18631 6930 18631 6930 18632 9294 18632 9295 18632 6930 18633 9295 18633 2598 18633 2610 18634 9296 18634 6922 18634 6922 18635 9296 18635 9301 18635 6922 18636 9297 18636 9298 18636 6921 18637 9299 18637 9300 18637 9300 18638 9299 18638 6922 18638 9300 18639 6922 18639 2613 18639 2613 18640 6922 18640 9301 18640 2609 18641 2610 18641 9302 18641 9302 18642 2610 18642 6922 18642 9302 18643 6922 18643 6925 18643 6925 18644 6922 18644 9298 18644 9306 18645 9308 18645 9303 18645 6917 18646 9304 18646 9306 18646 9306 18647 9304 18647 6919 18647 9306 18648 6919 18648 9305 18648 9305 18649 2614 18649 9306 18649 9306 18650 2614 18650 9307 18650 9306 18651 9307 18651 9308 18651 6914 18652 9309 18652 9310 18652 9310 18653 9309 18653 9306 18653 9310 18654 9306 18654 2619 18654 2619 18655 9306 18655 9303 18655 9314 18656 6913 18656 9315 18656 2625 18657 2627 18657 9314 18657 9314 18658 2627 18658 9311 18658 6912 18659 6913 18659 6911 18659 6911 18660 6913 18660 9314 18660 6911 18661 9314 18661 6910 18661 6910 18662 9314 18662 9311 18662 2624 18663 9312 18663 2623 18663 2623 18664 9312 18664 9314 18664 2623 18665 9314 18665 9313 18665 9313 18666 9314 18666 9315 18666 9144 18667 9317 18667 9316 18667 9316 18668 9317 18668 9322 18668 9153 18669 9152 18669 6418 18669 6418 18670 9152 18670 9317 18670 6418 18671 9317 18671 9138 18671 9138 18672 9317 18672 9144 18672 9138 18673 9144 18673 9140 18673 9140 18674 9144 18674 9141 18674 9150 18675 9318 18675 9319 18675 9319 18676 9318 18676 9320 18676 9319 18677 9320 18677 9317 18677 9317 18678 9320 18678 9321 18678 9317 18679 9321 18679 9322 18679 9322 18680 9321 18680 9323 18680 9131 18681 9132 18681 9327 18681 9327 18682 9132 18682 6414 18682 9327 18683 6414 18683 9134 18683 9324 18684 9127 18684 9130 18684 9137 18685 9325 18685 9135 18685 9135 18686 9325 18686 9327 18686 9135 18687 9327 18687 9326 18687 9326 18688 9327 18688 9134 18688 9325 18689 6413 18689 9327 18689 9327 18690 6413 18690 9123 18690 9327 18691 9123 18691 9328 18691 9130 18692 9329 18692 9324 18692 9324 18693 9329 18693 9327 18693 9324 18694 9327 18694 9330 18694 9330 18695 9327 18695 9328 18695 9330 18696 9328 18696 9125 18696 4190 18697 9383 18697 9331 18697 4190 18698 9331 18698 9332 18698 9332 18699 9331 18699 9385 18699 9332 18700 9385 18700 9334 18700 9334 18701 9385 18701 9333 18701 9334 18702 9333 18702 4189 18702 4189 18703 9333 18703 9386 18703 4189 18704 9386 18704 4186 18704 4186 18705 9386 18705 9388 18705 4186 18706 9388 18706 9335 18706 9335 18707 9388 18707 9389 18707 9335 18708 9389 18708 4185 18708 4185 18709 9389 18709 9336 18709 4185 18710 9336 18710 4184 18710 4184 18711 9336 18711 9392 18711 4184 18712 9392 18712 9338 18712 9338 18713 9392 18713 9337 18713 9338 18714 9337 18714 4182 18714 4182 18715 9337 18715 9394 18715 4182 18716 9394 18716 4180 18716 4180 18717 9394 18717 9339 18717 4180 18718 9339 18718 4179 18718 4179 18719 9339 18719 9397 18719 4179 18720 9397 18720 9340 18720 9340 18721 9397 18721 9342 18721 9340 18722 9342 18722 9341 18722 9341 18723 9342 18723 9399 18723 9341 18724 9399 18724 9343 18724 9343 18725 9399 18725 9344 18725 9343 18726 9344 18726 4176 18726 4176 18727 9344 18727 9345 18727 4176 18728 9345 18728 9346 18728 9347 18729 9348 18729 9379 18729 9347 18730 9379 18730 9430 18730 9430 18731 9379 18731 9349 18731 9430 18732 9349 18732 9432 18732 9432 18733 9349 18733 9377 18733 9432 18734 9377 18734 9350 18734 9350 18735 9377 18735 9351 18735 9350 18736 9351 18736 9444 18736 9444 18737 9351 18737 9375 18737 9444 18738 9375 18738 9352 18738 9352 18739 9375 18739 9373 18739 9352 18740 9373 18740 9445 18740 9445 18741 9373 18741 9353 18741 9445 18742 9353 18742 9447 18742 9447 18743 9353 18743 9371 18743 9447 18744 9371 18744 9354 18744 9354 18745 9371 18745 9370 18745 9354 18746 9370 18746 9355 18746 9355 18747 9370 18747 9356 18747 9355 18748 9356 18748 9449 18748 9449 18749 9356 18749 9358 18749 9449 18750 9358 18750 9357 18750 9357 18751 9358 18751 9368 18751 9357 18752 9368 18752 9359 18752 9359 18753 9368 18753 9366 18753 9359 18754 9366 18754 9438 18754 9438 18755 9366 18755 9360 18755 9438 18756 9360 18756 9361 18756 9361 18757 9360 18757 9363 18757 9361 18758 9363 18758 9362 18758 9362 18759 9363 18759 1169 18759 9362 18760 1169 18760 1171 18760 1170 18761 1169 18761 9363 18761 1170 18762 9363 18762 9364 18762 9364 18763 9363 18763 9360 18763 9364 18764 9360 18764 9365 18764 9365 18765 9360 18765 9366 18765 9365 18766 9366 18766 9367 18766 9367 18767 9366 18767 9368 18767 9367 18768 9368 18768 9412 18768 9412 18769 9368 18769 9358 18769 9412 18770 9358 18770 9415 18770 9415 18771 9358 18771 9356 18771 9415 18772 9356 18772 9416 18772 9416 18773 9356 18773 9370 18773 9416 18774 9370 18774 9369 18774 9369 18775 9370 18775 9371 18775 9369 18776 9371 18776 9418 18776 9418 18777 9371 18777 9353 18777 9418 18778 9353 18778 9372 18778 9372 18779 9353 18779 9373 18779 9372 18780 9373 18780 9374 18780 9374 18781 9373 18781 9375 18781 9374 18782 9375 18782 9419 18782 9419 18783 9375 18783 9351 18783 9419 18784 9351 18784 9420 18784 9420 18785 9351 18785 9377 18785 9420 18786 9377 18786 9376 18786 9376 18787 9377 18787 9349 18787 9376 18788 9349 18788 9423 18788 9423 18789 9349 18789 9379 18789 9423 18790 9379 18790 9378 18790 9378 18791 9379 18791 9348 18791 9378 18792 9348 18792 9425 18792 9380 18793 9409 18793 1201 18793 1201 18794 9409 18794 1149 18794 1201 18795 1149 18795 1202 18795 1202 18796 1149 18796 9381 18796 1202 18797 9381 18797 9382 18797 9382 18798 9381 18798 1151 18798 9382 18799 1151 18799 1204 18799 1204 18800 1151 18800 1152 18800 1204 18801 1152 18801 1205 18801 1205 18802 1152 18802 1155 18802 1205 18803 1155 18803 9383 18803 9383 18804 1155 18804 9384 18804 9383 18805 9384 18805 9331 18805 9331 18806 9384 18806 9410 18806 9331 18807 9410 18807 9385 18807 9385 18808 9410 18808 9411 18808 9385 18809 9411 18809 9333 18809 9333 18810 9411 18810 9387 18810 9333 18811 9387 18811 9386 18811 9386 18812 9387 18812 9413 18812 9386 18813 9413 18813 9388 18813 9388 18814 9413 18814 9414 18814 9388 18815 9414 18815 9389 18815 9389 18816 9414 18816 9390 18816 9389 18817 9390 18817 9336 18817 9336 18818 9390 18818 9417 18818 9336 18819 9417 18819 9392 18819 9392 18820 9417 18820 9391 18820 9392 18821 9391 18821 9337 18821 9337 18822 9391 18822 9393 18822 9337 18823 9393 18823 9394 18823 9394 18824 9393 18824 9395 18824 9394 18825 9395 18825 9339 18825 9339 18826 9395 18826 9396 18826 9339 18827 9396 18827 9397 18827 9397 18828 9396 18828 9421 18828 9397 18829 9421 18829 9342 18829 9342 18830 9421 18830 9398 18830 9342 18831 9398 18831 9399 18831 9399 18832 9398 18832 9422 18832 9399 18833 9422 18833 9344 18833 9344 18834 9422 18834 9424 18834 9344 18835 9424 18835 9345 18835 9345 18836 9424 18836 1138 18836 9345 18837 1138 18837 9400 18837 9400 18838 1138 18838 1139 18838 9400 18839 1139 18839 9401 18839 9401 18840 1139 18840 9403 18840 9401 18841 9403 18841 9402 18841 9402 18842 9403 18842 9404 18842 9402 18843 9404 18843 1193 18843 1193 18844 9404 18844 1141 18844 1193 18845 1141 18845 1194 18845 1194 18846 1141 18846 9405 18846 1194 18847 9405 18847 9406 18847 9406 18848 9405 18848 1143 18848 9406 18849 1143 18849 1197 18849 1197 18850 1143 18850 1145 18850 1197 18851 1145 18851 1200 18851 1200 18852 1145 18852 9407 18852 1200 18853 9407 18853 9408 18853 9408 18854 9407 18854 1146 18854 9408 18855 1146 18855 9380 18855 9380 18856 1146 18856 9409 18856 9384 18857 1170 18857 9364 18857 9384 18858 9364 18858 9410 18858 9410 18859 9364 18859 9365 18859 9410 18860 9365 18860 9411 18860 9411 18861 9365 18861 9367 18861 9411 18862 9367 18862 9387 18862 9387 18863 9367 18863 9412 18863 9387 18864 9412 18864 9413 18864 9413 18865 9412 18865 9415 18865 9413 18866 9415 18866 9414 18866 9414 18867 9415 18867 9416 18867 9414 18868 9416 18868 9390 18868 9390 18869 9416 18869 9369 18869 9390 18870 9369 18870 9417 18870 9417 18871 9369 18871 9418 18871 9417 18872 9418 18872 9391 18872 9391 18873 9418 18873 9372 18873 9391 18874 9372 18874 9393 18874 9393 18875 9372 18875 9374 18875 9393 18876 9374 18876 9395 18876 9395 18877 9374 18877 9419 18877 9395 18878 9419 18878 9396 18878 9396 18879 9419 18879 9420 18879 9396 18880 9420 18880 9421 18880 9421 18881 9420 18881 9376 18881 9421 18882 9376 18882 9398 18882 9398 18883 9376 18883 9423 18883 9398 18884 9423 18884 9422 18884 9422 18885 9423 18885 9378 18885 9422 18886 9378 18886 9424 18886 9424 18887 9378 18887 9425 18887 9424 18888 9425 18888 1138 18888 9426 18889 9437 18889 976 18889 976 18890 9437 18890 9427 18890 976 18891 9427 18891 974 18891 974 18892 9427 18892 1190 18892 974 18893 1190 18893 9428 18893 9428 18894 1190 18894 1191 18894 9428 18895 1191 18895 9429 18895 9429 18896 1191 18896 9347 18896 9429 18897 9347 18897 10001 18897 10001 18898 9347 18898 9430 18898 10001 18899 9430 18899 9431 18899 9431 18900 9430 18900 9432 18900 9431 18901 9432 18901 9999 18901 9443 18902 1176 18902 981 18902 981 18903 1176 18903 1178 18903 981 18904 1178 18904 9433 18904 9433 18905 1178 18905 1180 18905 9433 18906 1180 18906 979 18906 979 18907 1180 18907 1181 18907 979 18908 1181 18908 9434 18908 9434 18909 1181 18909 1183 18909 9434 18910 1183 18910 9435 18910 9435 18911 1183 18911 1184 18911 9435 18912 1184 18912 9436 18912 9436 18913 1184 18913 1185 18913 9436 18914 1185 18914 9426 18914 9426 18915 1185 18915 1187 18915 9426 18916 1187 18916 9437 18916 9450 18917 9359 18917 9990 18917 9990 18918 9359 18918 9438 18918 9990 18919 9438 18919 9988 18919 9988 18920 9438 18920 9361 18920 9988 18921 9361 18921 9439 18921 9439 18922 9361 18922 9362 18922 9439 18923 9362 18923 9440 18923 9440 18924 9362 18924 1171 18924 9440 18925 1171 18925 984 18925 984 18926 1171 18926 9441 18926 984 18927 9441 18927 983 18927 983 18928 9441 18928 9442 18928 983 18929 9442 18929 9443 18929 9443 18930 9442 18930 1173 18930 9443 18931 1173 18931 1176 18931 9432 18932 9350 18932 9999 18932 9999 18933 9350 18933 9444 18933 9999 18934 9444 18934 9997 18934 9997 18935 9444 18935 9352 18935 9997 18936 9352 18936 9996 18936 9996 18937 9352 18937 9445 18937 9996 18938 9445 18938 9446 18938 9446 18939 9445 18939 9447 18939 9446 18940 9447 18940 9995 18940 9995 18941 9447 18941 9354 18941 9995 18942 9354 18942 9994 18942 9994 18943 9354 18943 9355 18943 9994 18944 9355 18944 9448 18944 9448 18945 9355 18945 9449 18945 9448 18946 9449 18946 9450 18946 9450 18947 9449 18947 9357 18947 9450 18948 9357 18948 9359 18948 9454 18949 10130 18949 10129 18949 943 18950 940 18950 9452 18950 9451 18951 947 18951 946 18951 10132 18952 10130 18952 10134 18952 10134 18953 10130 18953 9454 18953 10134 18954 9454 18954 9452 18954 9452 18955 9454 18955 9453 18955 9452 18956 9453 18956 943 18956 10129 18957 10127 18957 9454 18957 9454 18958 10127 18958 9451 18958 9454 18959 9451 18959 945 18959 945 18960 9451 18960 946 18960 1137 18961 9455 18961 9456 18961 9456 18962 9455 18962 9810 18962 9456 18963 9810 18963 9457 18963 9457 18964 9810 18964 9458 18964 9457 18965 9458 18965 10174 18965 10174 18966 9458 18966 9459 18966 10174 18967 9459 18967 10176 18967 10176 18968 9459 18968 9460 18968 10176 18969 9460 18969 9461 18969 9461 18970 9460 18970 9463 18970 9461 18971 9463 18971 9462 18971 9462 18972 9463 18972 9464 18972 9462 18973 9464 18973 10177 18973 10177 18974 9464 18974 1133 18974 904 18975 9465 18975 10166 18975 10166 18976 9465 18976 9466 18976 10166 18977 9466 18977 10167 18977 10167 18978 9466 18978 9815 18978 10167 18979 9815 18979 9467 18979 9467 18980 9815 18980 9813 18980 9467 18981 9813 18981 10168 18981 10168 18982 9813 18982 9468 18982 10168 18983 9468 18983 9469 18983 9469 18984 9468 18984 9811 18984 9469 18985 9811 18985 10170 18985 10170 18986 9811 18986 9763 18986 10170 18987 9763 18987 897 18987 897 18988 9763 18988 9822 18988 909 18989 9829 18989 10162 18989 10162 18990 9829 18990 9470 18990 10162 18991 9470 18991 9471 18991 9471 18992 9470 18992 9834 18992 9471 18993 9834 18993 9473 18993 9473 18994 9834 18994 9472 18994 9473 18995 9472 18995 9474 18995 9474 18996 9472 18996 9832 18996 9474 18997 9832 18997 10163 18997 10163 18998 9832 18998 9839 18998 10163 18999 9839 18999 10164 18999 10164 19000 9839 19000 9475 19000 10164 19001 9475 19001 1120 19001 1120 19002 9475 19002 1121 19002 9739 19003 9734 19003 9476 19003 9476 19004 10158 19004 9739 19004 9739 19005 10158 19005 9477 19005 9739 19006 9477 19006 9478 19006 9477 19007 10156 19007 9478 19007 9478 19008 10156 19008 10155 19008 9478 19009 10155 19009 9740 19009 10155 19010 9479 19010 9740 19010 9740 19011 9479 19011 10153 19011 9740 19012 10153 19012 9481 19012 10153 19013 9480 19013 9481 19013 9481 19014 9480 19014 10152 19014 9481 19015 10152 19015 9482 19015 9482 19016 10152 19016 10151 19016 9482 19017 10151 19017 9483 19017 10149 19018 1119 19018 9484 19018 9484 19019 1119 19019 9483 19019 9484 19020 9483 19020 9485 19020 9485 19021 9483 19021 10151 19021 927 19022 9800 19022 9486 19022 9486 19023 9800 19023 9726 19023 9486 19024 9726 19024 9487 19024 9487 19025 9726 19025 9488 19025 9487 19026 9488 19026 9489 19026 9489 19027 9488 19027 9724 19027 9489 19028 9724 19028 10146 19028 10146 19029 9724 19029 9490 19029 10146 19030 9490 19030 9491 19030 9491 19031 9490 19031 9492 19031 9491 19032 9492 19032 10148 19032 10148 19033 9492 19033 9725 19033 10148 19034 9725 19034 916 19034 916 19035 9725 19035 9799 19035 9493 19036 1109 19036 1108 19036 1108 19037 9494 19037 9493 19037 9493 19038 9494 19038 10142 19038 9493 19039 10142 19039 9843 19039 10142 19040 9495 19040 9843 19040 9843 19041 9495 19041 10141 19041 9843 19042 10141 19042 9497 19042 10141 19043 9496 19043 9497 19043 9497 19044 9496 19044 9498 19044 9497 19045 9498 19045 9499 19045 9498 19046 10139 19046 9499 19046 9499 19047 10139 19047 9501 19047 9499 19048 9501 19048 9500 19048 9500 19049 9501 19049 10137 19049 9500 19050 10137 19050 9503 19050 1106 19051 9851 19051 9502 19051 9502 19052 9851 19052 9503 19052 9502 19053 9503 19053 10136 19053 10136 19054 9503 19054 10137 19054 10209 19055 9504 19055 10212 19055 10212 19056 9504 19056 9505 19056 10212 19057 9505 19057 10214 19057 10214 19058 9505 19058 9506 19058 10214 19059 9506 19059 9507 19059 9507 19060 9506 19060 9508 19060 9507 19061 9508 19061 10215 19061 10215 19062 9508 19062 9509 19062 10215 19063 9509 19063 9510 19063 9510 19064 9509 19064 9512 19064 9510 19065 9512 19065 9511 19065 9511 19066 9512 19066 9855 19066 838 19067 9864 19067 9513 19067 9513 19068 9864 19068 9515 19068 9513 19069 9515 19069 9514 19069 9514 19070 9515 19070 9898 19070 9514 19071 9898 19071 9516 19071 9516 19072 9898 19072 9517 19072 9516 19073 9517 19073 9518 19073 9518 19074 9517 19074 9860 19074 9518 19075 9860 19075 10207 19075 10207 19076 9860 19076 9519 19076 10207 19077 9519 19077 849 19077 849 19078 9519 19078 9861 19078 1085 19079 9520 19079 9521 19079 9521 19080 9520 19080 9522 19080 9521 19081 9522 19081 10201 19081 10201 19082 9522 19082 9523 19082 10201 19083 9523 19083 10202 19083 10202 19084 9523 19084 9524 19084 10202 19085 9524 19085 9525 19085 9525 19086 9524 19086 9527 19086 9525 19087 9527 19087 9526 19087 9526 19088 9527 19088 9774 19088 9526 19089 9774 19089 863 19089 863 19090 9774 19090 9528 19090 10192 19091 9868 19091 9529 19091 9529 19092 9868 19092 9530 19092 9529 19093 9530 19093 10193 19093 10193 19094 9530 19094 9532 19094 10193 19095 9532 19095 9531 19095 9531 19096 9532 19096 9533 19096 9531 19097 9533 19097 9534 19097 9534 19098 9533 19098 9535 19098 9534 19099 9535 19099 9537 19099 9537 19100 9535 19100 9536 19100 9537 19101 9536 19101 10197 19101 10197 19102 9536 19102 1080 19102 882 19103 9538 19103 10189 19103 10189 19104 9538 19104 9539 19104 10189 19105 9539 19105 10190 19105 10190 19106 9539 19106 9540 19106 10190 19107 9540 19107 9541 19107 9541 19108 9540 19108 9937 19108 9541 19109 9937 19109 9542 19109 9542 19110 9937 19110 9879 19110 9542 19111 9879 19111 9543 19111 9543 19112 9879 19112 9545 19112 9543 19113 9545 19113 9544 19113 9544 19114 9545 19114 9877 19114 10179 19115 9546 19115 10180 19115 10180 19116 9546 19116 9547 19116 10180 19117 9547 19117 9548 19117 9548 19118 9547 19118 9886 19118 9548 19119 9886 19119 9549 19119 9549 19120 9886 19120 9550 19120 9549 19121 9550 19121 9552 19121 9552 19122 9550 19122 9551 19122 9552 19123 9551 19123 10186 19123 10186 19124 9551 19124 9883 19124 10186 19125 9883 19125 883 19125 883 19126 9883 19126 1067 19126 9553 19127 9554 19127 9555 19127 9555 19128 9554 19128 9556 19128 9555 19129 9556 19129 10079 19129 10079 19130 9556 19130 9887 19130 10079 19131 9887 19131 9557 19131 9557 19132 9887 19132 9558 19132 9557 19133 9558 19133 10077 19133 10077 19134 9558 19134 9842 19134 10077 19135 9842 19135 10074 19135 10074 19136 9842 19136 9841 19136 10074 19137 9841 19137 10072 19137 10067 19138 9831 19138 10069 19138 10069 19139 9831 19139 9825 19139 10069 19140 9825 19140 10071 19140 10071 19141 9825 19141 9559 19141 10071 19142 9559 19142 10065 19142 10065 19143 9559 19143 9560 19143 10065 19144 9560 19144 9561 19144 9561 19145 9560 19145 9821 19145 9561 19146 9821 19146 9562 19146 9562 19147 9821 19147 9820 19147 9562 19148 9820 19148 9563 19148 9563 19149 9820 19149 9819 19149 9563 19150 9819 19150 10064 19150 10064 19151 9819 19151 9892 19151 10064 19152 9892 19152 9564 19152 9564 19153 9892 19153 9891 19153 9564 19154 9891 19154 10086 19154 10086 19155 9891 19155 9565 19155 10086 19156 9565 19156 10088 19156 10088 19157 9565 19157 9889 19157 10088 19158 9889 19158 10084 19158 10084 19159 9889 19159 9566 19159 9566 19160 9567 19160 10084 19160 10084 19161 9567 19161 9959 19161 10084 19162 9959 19162 10085 19162 10085 19163 9959 19163 9568 19163 10085 19164 9568 19164 9958 19164 10085 19165 9958 19165 10082 19165 10082 19166 9958 19166 9569 19166 10082 19167 9569 19167 10083 19167 10083 19168 9569 19168 9570 19168 10083 19169 9570 19169 9553 19169 9553 19170 9570 19170 9554 19170 10057 19171 9571 19171 9572 19171 9572 19172 9571 19172 9900 19172 9572 19173 9900 19173 10058 19173 10058 19174 9900 19174 9573 19174 10058 19175 9573 19175 10055 19175 10055 19176 9573 19176 9574 19176 10055 19177 9574 19177 9575 19177 9575 19178 9574 19178 9576 19178 9575 19179 9576 19179 9577 19179 9577 19180 9576 19180 9578 19180 9577 19181 9578 19181 9579 19181 9579 19182 9578 19182 9722 19182 9582 19183 9579 19183 9722 19183 9580 19184 10053 19184 9581 19184 9581 19185 10053 19185 9582 19185 9581 19186 9582 19186 9723 19186 9723 19187 9582 19187 9722 19187 10053 19188 9580 19188 10052 19188 10052 19189 9580 19189 9733 19189 9583 19190 9584 19190 10048 19190 10048 19191 9584 19191 9738 19191 10048 19192 9738 19192 9585 19192 9585 19193 9738 19193 9586 19193 9585 19194 9586 19194 9587 19194 9587 19195 9586 19195 9737 19195 9587 19196 9737 19196 10063 19196 10063 19197 9737 19197 9736 19197 10063 19198 9736 19198 9588 19198 9588 19199 9736 19199 9589 19199 10060 19200 9588 19200 9590 19200 9590 19201 9588 19201 9589 19201 10060 19202 9590 19202 10061 19202 10061 19203 9590 19203 9894 19203 10061 19204 9894 19204 9591 19204 9591 19205 9894 19205 9592 19205 9591 19206 9592 19206 10057 19206 10057 19207 9592 19207 9571 19207 10041 19208 9594 19208 9593 19208 9593 19209 9594 19209 9596 19209 9593 19210 9596 19210 9595 19210 9595 19211 9596 19211 9597 19211 9600 19212 10036 19212 9906 19212 9906 19213 10036 19213 10037 19213 9906 19214 10037 19214 9907 19214 9907 19215 10037 19215 10038 19215 9907 19216 10038 19216 9598 19216 9595 19217 9597 19217 954 19217 954 19218 9597 19218 9598 19218 954 19219 9598 19219 9599 19219 9599 19220 9598 19220 10038 19220 10036 19221 9600 19221 10035 19221 10035 19222 9600 19222 9601 19222 10035 19223 9601 19223 10033 19223 10033 19224 9601 19224 9905 19224 10033 19225 9905 19225 9603 19225 9603 19226 9905 19226 9602 19226 9603 19227 9602 19227 10031 19227 10031 19228 9602 19228 9904 19228 10031 19229 9904 19229 10029 19229 10029 19230 9904 19230 9903 19230 10028 19231 9605 19231 9604 19231 9604 19232 9605 19232 9901 19232 9604 19233 9901 19233 10044 19233 10044 19234 9901 19234 9899 19234 10044 19235 9899 19235 9606 19235 9606 19236 9899 19236 9720 19236 9606 19237 9720 19237 10045 19237 10045 19238 9720 19238 9910 19238 10045 19239 9910 19239 10046 19239 10046 19240 9910 19240 9607 19240 9608 19241 10046 19241 9609 19241 9609 19242 10046 19242 9607 19242 9608 19243 9609 19243 9610 19243 9610 19244 9609 19244 9909 19244 9610 19245 9909 19245 10040 19245 10040 19246 9909 19246 9908 19246 10040 19247 9908 19247 10041 19247 10041 19248 9908 19248 9594 19248 10020 19249 9913 19249 10022 19249 10022 19250 9913 19250 9912 19250 10022 19251 9912 19251 10023 19251 10023 19252 9912 19252 9911 19252 9611 19253 9616 19253 10017 19253 10017 19254 956 19254 9611 19254 9611 19255 956 19255 957 19255 9611 19256 957 19256 9612 19256 10023 19257 9911 19257 9613 19257 9613 19258 9911 19258 9794 19258 9613 19259 9794 19259 958 19259 958 19260 9794 19260 9612 19260 958 19261 9612 19261 9614 19261 9614 19262 9612 19262 957 19262 10017 19263 9616 19263 9615 19263 9615 19264 9616 19264 9793 19264 9615 19265 9793 19265 9617 19265 9617 19266 9793 19266 9618 19266 9617 19267 9618 19267 10015 19267 10015 19268 9618 19268 9619 19268 10015 19269 9619 19269 10012 19269 10012 19270 9619 19270 9620 19270 10012 19271 9620 19271 9621 19271 9621 19272 9620 19272 9622 19272 9621 19273 9622 19273 10009 19273 10009 19274 9622 19274 9896 19274 10009 19275 9896 19275 10010 19275 10010 19276 9896 19276 9623 19276 10010 19277 9623 19277 10011 19277 10011 19278 9623 19278 9895 19278 10011 19279 9895 19279 961 19279 961 19280 9895 19280 9963 19280 10024 19281 962 19281 9624 19281 9624 19282 962 19282 9625 19282 10024 19283 9624 19283 9626 19283 9626 19284 9624 19284 9915 19284 9626 19285 9915 19285 10026 19285 10026 19286 9915 19286 9914 19286 10026 19287 9914 19287 10020 19287 10020 19288 9914 19288 9913 19288 1063 19289 9627 19289 10113 19289 10113 19290 9627 19290 9924 19290 10113 19291 9924 19291 10115 19291 10115 19292 9924 19292 9919 19292 10115 19293 9919 19293 9628 19293 9628 19294 9919 19294 9629 19294 9628 19295 9629 19295 9630 19295 9630 19296 9629 19296 9631 19296 9630 19297 9631 19297 10110 19297 10110 19298 9631 19298 9874 19298 10110 19299 9874 19299 9632 19299 9632 19300 9874 19300 9633 19300 9632 19301 9633 19301 9634 19301 9634 19302 9633 19302 9635 19302 9634 19303 9635 19303 949 19303 949 19304 9635 19304 9928 19304 9925 19305 9637 19305 9636 19305 9636 19306 9637 19306 9638 19306 9636 19307 9638 19307 9640 19307 9638 19308 9639 19308 9640 19308 9640 19309 9639 19309 9641 19309 9640 19310 9641 19310 9927 19310 949 19311 9928 19311 9642 19311 9642 19312 9928 19312 9927 19312 9642 19313 9927 19313 10109 19313 10109 19314 9927 19314 9641 19314 9637 19315 9925 19315 10105 19315 10105 19316 9925 19316 9643 19316 10105 19317 9643 19317 10121 19317 10121 19318 9643 19318 9644 19318 10121 19319 9644 19319 10123 19319 10123 19320 9644 19320 9645 19320 10123 19321 9645 19321 10124 19321 10124 19322 9645 19322 9931 19322 10124 19323 9931 19323 10119 19323 10119 19324 9931 19324 9970 19324 10120 19325 10119 19325 9922 19325 9922 19326 10119 19326 9970 19326 10120 19327 9922 19327 10117 19327 10117 19328 9922 19328 9646 19328 10117 19329 9646 19329 9647 19329 9647 19330 9646 19330 9921 19330 9667 19331 9668 19331 9648 19331 9648 19332 9668 19332 9890 19332 9648 19333 9890 19333 9650 19333 9650 19334 9890 19334 9649 19334 9650 19335 9649 19335 10097 19335 10097 19336 9649 19336 9651 19336 1062 19337 9652 19337 10093 19337 10093 19338 9652 19338 9954 19338 10093 19339 9954 19339 9654 19339 9654 19340 9954 19340 9951 19340 9918 19341 9653 19341 9659 19341 9654 19342 9951 19342 953 19342 953 19343 9951 19343 9655 19343 953 19344 9655 19344 9656 19344 9656 19345 9655 19345 9657 19345 9656 19346 9657 19346 950 19346 950 19347 9657 19347 9918 19347 950 19348 9918 19348 9658 19348 9658 19349 9918 19349 9659 19349 9659 19350 9653 19350 10090 19350 10090 19351 9653 19351 9923 19351 10090 19352 9923 19352 10091 19352 10091 19353 9923 19353 9660 19353 10091 19354 9660 19354 9661 19354 9661 19355 9660 19355 9662 19355 9661 19356 9662 19356 10103 19356 10103 19357 9662 19357 9719 19357 10103 19358 9719 19358 10101 19358 10101 19359 9719 19359 9961 19359 9663 19360 10101 19360 9664 19360 9664 19361 10101 19361 9961 19361 9663 19362 9664 19362 10100 19362 10100 19363 9664 19363 9665 19363 10100 19364 9665 19364 9666 19364 9666 19365 9665 19365 9934 19365 9666 19366 9934 19366 9667 19366 9667 19367 9934 19367 9668 19367 10217 19368 9835 19368 9669 19368 9669 19369 9835 19369 9836 19369 9669 19370 9836 19370 9670 19370 9670 19371 9836 19371 9838 19371 9670 19372 9838 19372 9671 19372 9671 19373 9838 19373 9817 19373 9671 19374 9817 19374 10221 19374 10221 19375 9817 19375 9826 19375 10221 19376 9826 19376 10223 19376 10223 19377 9826 19377 9818 19377 10223 19378 9818 19378 821 19378 821 19379 9818 19379 1053 19379 9672 19380 9754 19380 9673 19380 9673 19381 9754 19381 9674 19381 9673 19382 9674 19382 9675 19382 9675 19383 9674 19383 9676 19383 9675 19384 9676 19384 10226 19384 10226 19385 9676 19385 9677 19385 10226 19386 9677 19386 10228 19386 10228 19387 9677 19387 9809 19387 10228 19388 9809 19388 10229 19388 10229 19389 9809 19389 9678 19389 10229 19390 9678 19390 1048 19390 1048 19391 9678 19391 9760 19391 10230 19392 9945 19392 10231 19392 10231 19393 9945 19393 9944 19393 10231 19394 9944 19394 9679 19394 9679 19395 9944 19395 9680 19395 9679 19396 9680 19396 10233 19396 10233 19397 9680 19397 9942 19397 10233 19398 9942 19398 10234 19398 10234 19399 9942 19399 9681 19399 10234 19400 9681 19400 10235 19400 10235 19401 9681 19401 9682 19401 10235 19402 9682 19402 9683 19402 9683 19403 9682 19403 9943 19403 10236 19404 1042 19404 9684 19404 9684 19405 1042 19405 9685 19405 9684 19406 9685 19406 9686 19406 9686 19407 9685 19407 9687 19407 9686 19408 9687 19408 9688 19408 9688 19409 9687 19409 9689 19409 9688 19410 9689 19410 10239 19410 10239 19411 9689 19411 9690 19411 10239 19412 9690 19412 9691 19412 9691 19413 9690 19413 9692 19413 9691 19414 9692 19414 10242 19414 10242 19415 9692 19415 9753 19415 10242 19416 9753 19416 9693 19416 9693 19417 9753 19417 9752 19417 10243 19418 9781 19418 10244 19418 10244 19419 9781 19419 9694 19419 10244 19420 9694 19420 9695 19420 9695 19421 9694 19421 9696 19421 9695 19422 9696 19422 10247 19422 10247 19423 9696 19423 9697 19423 10247 19424 9697 19424 9698 19424 9698 19425 9697 19425 9699 19425 9698 19426 9699 19426 10248 19426 10248 19427 9699 19427 9701 19427 10248 19428 9701 19428 9700 19428 9700 19429 9701 19429 1035 19429 1025 19430 779 19430 9702 19430 9702 19431 779 19431 10257 19431 9702 19432 10257 19432 9777 19432 10257 19433 10256 19433 9777 19433 9777 19434 10256 19434 9703 19434 9777 19435 9703 19435 9704 19435 9703 19436 10255 19436 9704 19436 9704 19437 10255 19437 9705 19437 9704 19438 9705 19438 9779 19438 9779 19439 9705 19439 10254 19439 9779 19440 10254 19440 9792 19440 788 19441 9706 19441 10249 19441 10249 19442 9706 19442 9707 19442 10249 19443 9707 19443 9708 19443 9708 19444 9707 19444 9792 19444 9708 19445 9792 19445 10251 19445 10251 19446 9792 19446 10254 19446 1019 19447 9709 19447 9710 19447 9710 19448 9709 19448 9744 19448 9710 19449 9744 19449 10260 19449 10260 19450 9744 19450 9711 19450 10260 19451 9711 19451 10262 19451 10262 19452 9711 19452 9712 19452 10262 19453 9712 19453 10265 19453 10265 19454 9712 19454 9750 19454 10265 19455 9750 19455 10267 19455 10267 19456 9750 19456 9749 19456 10267 19457 9749 19457 774 19457 774 19458 9749 19458 9748 19458 1010 19459 9713 19459 10268 19459 10268 19460 9713 19460 9803 19460 10268 19461 9803 19461 10269 19461 10269 19462 9803 19462 9714 19462 10269 19463 9714 19463 9715 19463 9715 19464 9714 19464 9716 19464 9715 19465 9716 19465 10271 19465 10271 19466 9716 19466 9717 19466 10271 19467 9717 19467 10272 19467 10272 19468 9717 19468 9797 19468 10272 19469 9797 19469 768 19469 768 19470 9797 19470 9718 19470 9980 19471 9846 19471 9978 19471 996 19472 998 19472 9878 19472 9719 19473 9662 19473 9920 19473 9954 19474 9964 19474 9956 19474 9910 19475 9720 19475 9893 19475 9907 19476 9598 19476 9897 19476 9959 19477 9567 19477 9888 19477 9727 19478 9721 19478 963 19478 9902 19479 9799 19479 9725 19479 9722 19480 970 19480 9723 19480 9723 19481 970 19481 10005 19481 9723 19482 10005 19482 9581 19482 9573 19483 9900 19483 9902 19483 9727 19484 963 19484 9984 19484 9725 19485 9492 19485 9722 19485 9722 19486 9492 19486 970 19486 970 19487 9492 19487 9490 19487 970 19488 9490 19488 971 19488 971 19489 9490 19489 9724 19489 971 19490 9724 19490 969 19490 9722 19491 9578 19491 9725 19491 9725 19492 9578 19492 9576 19492 9725 19493 9576 19493 9902 19493 9902 19494 9576 19494 9574 19494 9902 19495 9574 19495 9573 19495 9724 19496 9488 19496 969 19496 969 19497 9488 19497 9726 19497 969 19498 9726 19498 966 19498 966 19499 9726 19499 9800 19499 966 19500 9800 19500 965 19500 9729 19501 1117 19501 1115 19501 9721 19502 9727 19502 9728 19502 9728 19503 9727 19503 9729 19503 9728 19504 9729 19504 10004 19504 10004 19505 9729 19505 1115 19505 10004 19506 1115 19506 9730 19506 1115 19507 1114 19507 9730 19507 9730 19508 1114 19508 9732 19508 9730 19509 9732 19509 9731 19509 10005 19510 9731 19510 9581 19510 9581 19511 9731 19511 9732 19511 9581 19512 9732 19512 9580 19512 9580 19513 9732 19513 9734 19513 9580 19514 9734 19514 9733 19514 9733 19515 9734 19515 9735 19515 9590 19516 9589 19516 9967 19516 9967 19517 9589 19517 9736 19517 9967 19518 9736 19518 9737 19518 9737 19519 9586 19519 9967 19519 9967 19520 9586 19520 9738 19520 9967 19521 9738 19521 986 19521 986 19522 9738 19522 9584 19522 986 19523 9584 19523 1065 19523 9734 19524 9739 19524 9735 19524 9735 19525 9739 19525 9478 19525 9735 19526 9478 19526 1065 19526 1065 19527 9478 19527 9740 19527 1065 19528 9740 19528 986 19528 986 19529 9740 19529 9481 19529 9481 19530 9482 19530 986 19530 986 19531 9482 19531 9483 19531 986 19532 9483 19532 9741 19532 9741 19533 9483 19533 1119 19533 9741 19534 1119 19534 9729 19534 9729 19535 1119 19535 1118 19535 9729 19536 1118 19536 1117 19536 9743 19537 9742 19537 9712 19537 9712 19538 9742 19538 9750 19538 9712 19539 9711 19539 9743 19539 9743 19540 9711 19540 9744 19540 9743 19541 9744 19541 9709 19541 9745 19542 1018 19542 9846 19542 9745 19543 9846 19543 1020 19543 1020 19544 9846 19544 9845 19544 1020 19545 9845 19545 9709 19545 9858 19546 9978 19546 9746 19546 9746 19547 9978 19547 9846 19547 9746 19548 9846 19548 9747 19548 9747 19549 9846 19549 1018 19549 9747 19550 1015 19550 9746 19550 9746 19551 1015 19551 1012 19551 9746 19552 1012 19552 9857 19552 9857 19553 1012 19553 9748 19553 9857 19554 9748 19554 9742 19554 9742 19555 9748 19555 9749 19555 9742 19556 9749 19556 9750 19556 9866 19557 9533 19557 1038 19557 1038 19558 9533 19558 1040 19558 1040 19559 9533 19559 9751 19559 9751 19560 9533 19560 9532 19560 9751 19561 9532 19561 9530 19561 1038 19562 9752 19562 9866 19562 9866 19563 9752 19563 9753 19563 9866 19564 9753 19564 1000 19564 1000 19565 9753 19565 9692 19565 1000 19566 9692 19566 9690 19566 9687 19567 9685 19567 9876 19567 9876 19568 9685 19568 1073 19568 9754 19569 9768 19569 9674 19569 9674 19570 9768 19570 9755 19570 9674 19571 9755 19571 9676 19571 9676 19572 9755 19572 9808 19572 9676 19573 9808 19573 9677 19573 9677 19574 9808 19574 9809 19574 9756 19575 9757 19575 9758 19575 9758 19576 9757 19576 9759 19576 9758 19577 9759 19577 9966 19577 9966 19578 9759 19578 9760 19578 9966 19579 9760 19579 1136 19579 1136 19580 9760 19580 9678 19580 9761 19581 9766 19581 1051 19581 1051 19582 9766 19582 9822 19582 1051 19583 9822 19583 9762 19583 9762 19584 9822 19584 9763 19584 9762 19585 9763 19585 9764 19585 9764 19586 9763 19586 9811 19586 9764 19587 9811 19587 9812 19587 9761 19588 9765 19588 9766 19588 9766 19589 9765 19589 9767 19589 9766 19590 9767 19590 9756 19590 9756 19591 9767 19591 1049 19591 9756 19592 1049 19592 9757 19592 9754 19593 1047 19593 9768 19593 9768 19594 1047 19594 9769 19594 9768 19595 9769 19595 9770 19595 9770 19596 9769 19596 9812 19596 9770 19597 9812 19597 9814 19597 9782 19598 9783 19598 9786 19598 9786 19599 9783 19599 9771 19599 9786 19600 9771 19600 9790 19600 9772 19601 1034 19601 9527 19601 9527 19602 1034 19602 9773 19602 9527 19603 9773 19603 9774 19603 9774 19604 9773 19604 9784 19604 9774 19605 9784 19605 9528 19605 9522 19606 9780 19606 9523 19606 9523 19607 9780 19607 9772 19607 9523 19608 9772 19608 9524 19608 9524 19609 9772 19609 9527 19609 9777 19610 1089 19610 9786 19610 9786 19611 1089 19611 9775 19611 9786 19612 9775 19612 9782 19612 9779 19613 9520 19613 9776 19613 9779 19614 9776 19614 9704 19614 9704 19615 9776 19615 1086 19615 9704 19616 1086 19616 9777 19616 9777 19617 1086 19617 9778 19617 9777 19618 9778 19618 1089 19618 9522 19619 9520 19619 9780 19619 9780 19620 9520 19620 9779 19620 9780 19621 9779 19621 9781 19621 9781 19622 9779 19622 9929 19622 9781 19623 9929 19623 9694 19623 9694 19624 9929 19624 9870 19624 9782 19625 9528 19625 9783 19625 9783 19626 9528 19626 9784 19626 9783 19627 9784 19627 9971 19627 9971 19628 9784 19628 1035 19628 9971 19629 1035 19629 1001 19629 1035 19630 9701 19630 1001 19630 1001 19631 9701 19631 9699 19631 1001 19632 9699 19632 9785 19632 9785 19633 9699 19633 9697 19633 9785 19634 9697 19634 9870 19634 9870 19635 9697 19635 9696 19635 9870 19636 9696 19636 9694 19636 9790 19637 1025 19637 9786 19637 9786 19638 1025 19638 9702 19638 9786 19639 9702 19639 9777 19639 9972 19640 9787 19640 9789 19640 9789 19641 9787 19641 9788 19641 9788 19642 1023 19642 9789 19642 9789 19643 1023 19643 9791 19643 9789 19644 9791 19644 9790 19644 9790 19645 9791 19645 1027 19645 9790 19646 1027 19646 1025 19646 9793 19647 9616 19647 9792 19647 9793 19648 9517 19648 9618 19648 9618 19649 9517 19649 9898 19649 9618 19650 9898 19650 9619 19650 9929 19651 9794 19651 9911 19651 9929 19652 9911 19652 9930 19652 9792 19653 9616 19653 9779 19653 9779 19654 9616 19654 9611 19654 9779 19655 9611 19655 9929 19655 9929 19656 9611 19656 9612 19656 9929 19657 9612 19657 9794 19657 9795 19658 9982 19658 9713 19658 9500 19659 9503 19659 9718 19659 9713 19660 1011 19660 9795 19660 9795 19661 1011 19661 9796 19661 9795 19662 9796 19662 9981 19662 9981 19663 9796 19663 1008 19663 9981 19664 1008 19664 9850 19664 9797 19665 9902 19665 9718 19665 9718 19666 9902 19666 9798 19666 9718 19667 9798 19667 9500 19667 9797 19668 9717 19668 9902 19668 9902 19669 9717 19669 9716 19669 9902 19670 9716 19670 9799 19670 9799 19671 9716 19671 9714 19671 9799 19672 9714 19672 9802 19672 963 19673 965 19673 9984 19673 9984 19674 965 19674 9800 19674 9984 19675 9800 19675 9983 19675 9983 19676 9800 19676 1113 19676 9983 19677 1113 19677 9982 19677 9982 19678 1113 19678 9801 19678 9982 19679 9801 19679 9713 19679 9713 19680 9801 19680 1111 19680 9713 19681 1111 19681 9804 19681 9802 19682 9714 19682 9804 19682 9804 19683 9714 19683 9803 19683 9804 19684 9803 19684 9713 19684 9956 19685 9965 19685 9805 19685 9805 19686 9965 19686 9807 19686 9464 19687 994 19687 1133 19687 1133 19688 994 19688 9805 19688 1133 19689 9805 19689 9806 19689 9806 19690 9805 19690 9807 19690 9464 19691 9463 19691 994 19691 994 19692 9463 19692 9460 19692 994 19693 9460 19693 990 19693 990 19694 9460 19694 9459 19694 990 19695 9459 19695 9808 19695 9808 19696 9459 19696 9458 19696 9808 19697 9458 19697 9809 19697 9809 19698 9458 19698 9810 19698 9809 19699 9810 19699 9678 19699 9678 19700 9810 19700 9455 19700 9678 19701 9455 19701 1136 19701 9811 19702 9468 19702 9812 19702 9812 19703 9468 19703 9813 19703 9812 19704 9813 19704 9814 19704 9814 19705 9813 19705 9815 19705 9814 19706 9815 19706 989 19706 989 19707 9815 19707 9466 19707 989 19708 9466 19708 9816 19708 9816 19709 9466 19709 9465 19709 9816 19710 9465 19710 9817 19710 9817 19711 9465 19711 9827 19711 9817 19712 9827 19712 9826 19712 1053 19713 9818 19713 9559 19713 9559 19714 9818 19714 9560 19714 9831 19715 1123 19715 1121 19715 9892 19716 9819 19716 9766 19716 9766 19717 9819 19717 9820 19717 9766 19718 9820 19718 9822 19718 9822 19719 9820 19719 9821 19719 9822 19720 9821 19720 9823 19720 9823 19721 9821 19721 9560 19721 9823 19722 9560 19722 1129 19722 1129 19723 9560 19723 9818 19723 1129 19724 9818 19724 9828 19724 1053 19725 9559 19725 1054 19725 1054 19726 9559 19726 9825 19726 1054 19727 9825 19727 9824 19727 9824 19728 9825 19728 9831 19728 9824 19729 9831 19729 1056 19729 9826 19730 9827 19730 9818 19730 9818 19731 9827 19731 1132 19731 9818 19732 1132 19732 9828 19732 9834 19733 9470 19733 9830 19733 9830 19734 9470 19734 9829 19734 9830 19735 9829 19735 986 19735 9831 19736 1121 19736 1056 19736 1056 19737 1121 19737 9475 19737 1056 19738 9475 19738 9839 19738 9832 19739 9472 19739 1059 19739 1059 19740 9472 19740 9833 19740 9472 19741 9834 19741 9833 19741 9833 19742 9834 19742 9830 19742 9833 19743 9830 19743 9835 19743 9835 19744 9830 19744 9837 19744 9835 19745 9837 19745 9836 19745 9836 19746 9837 19746 9816 19746 9836 19747 9816 19747 9838 19747 9838 19748 9816 19748 9817 19748 9832 19749 1059 19749 9839 19749 9839 19750 1059 19750 1058 19750 9839 19751 1058 19751 1056 19751 9829 19752 9840 19752 986 19752 986 19753 9840 19753 1127 19753 986 19754 1127 19754 1126 19754 1123 19755 9831 19755 1124 19755 1124 19756 9831 19756 9841 19756 1124 19757 9841 19757 9842 19757 9845 19758 9844 19758 1109 19758 9709 19759 9845 19759 9743 19759 9743 19760 9845 19760 1109 19760 9743 19761 1109 19761 9493 19761 9493 19762 9843 19762 9743 19762 9743 19763 9843 19763 9497 19763 9743 19764 9497 19764 9798 19764 9798 19765 9497 19765 9499 19765 9798 19766 9499 19766 9500 19766 9844 19767 9845 19767 1110 19767 1110 19768 9845 19768 9846 19768 1110 19769 9846 19769 9847 19769 9847 19770 9846 19770 9980 19770 9847 19771 9980 19771 9848 19771 9848 19772 9980 19772 9981 19772 9848 19773 9981 19773 9849 19773 9849 19774 9981 19774 9850 19774 9849 19775 9850 19775 9851 19775 9851 19776 9850 19776 1006 19776 9851 19777 1006 19777 9503 19777 9503 19778 1006 19778 9852 19778 9503 19779 9852 19779 9718 19779 1101 19780 9854 19780 9853 19780 9853 19781 9854 19781 9855 19781 9853 19782 9855 19782 9856 19782 9856 19783 9855 19783 9512 19783 9512 19784 9509 19784 9856 19784 9856 19785 9509 19785 9508 19785 9856 19786 9508 19786 9742 19786 9742 19787 9508 19787 9506 19787 9506 19788 9505 19788 9742 19788 9742 19789 9505 19789 9504 19789 9742 19790 9504 19790 9857 19790 9857 19791 9504 19791 1105 19791 9857 19792 1105 19792 9746 19792 9746 19793 1105 19793 1103 19793 9746 19794 1103 19794 9858 19794 9858 19795 1103 19795 1102 19795 9858 19796 1102 19796 9976 19796 1092 19797 9948 19797 9856 19797 9792 19798 9707 19798 9793 19798 9793 19799 9707 19799 9706 19799 9793 19800 9706 19800 9517 19800 9517 19801 9706 19801 9859 19801 9517 19802 9859 19802 9860 19802 9860 19803 9859 19803 1022 19803 9860 19804 1022 19804 9519 19804 9519 19805 1022 19805 9788 19805 9519 19806 9788 19806 9861 19806 9861 19807 9788 19807 9787 19807 9861 19808 9787 19808 9862 19808 9862 19809 9787 19809 9972 19809 9862 19810 9972 19810 9863 19810 1092 19811 9856 19811 9864 19811 9863 19812 9972 19812 9865 19812 9865 19813 9972 19813 9949 19813 9865 19814 9949 19814 1097 19814 9785 19815 9872 19815 1001 19815 1001 19816 9872 19816 1081 19816 1001 19817 1081 19817 1003 19817 1003 19818 1081 19818 1080 19818 1003 19819 1080 19819 1004 19819 1004 19820 1080 19820 9536 19820 1004 19821 9536 19821 9866 19821 9866 19822 9536 19822 9535 19822 9866 19823 9535 19823 9533 19823 9867 19824 9870 19824 9868 19824 9868 19825 9870 19825 9926 19825 9868 19826 9926 19826 9530 19826 9530 19827 9926 19827 9869 19827 9530 19828 9869 19828 9751 19828 9867 19829 1084 19829 9870 19829 9870 19830 1084 19830 9871 19830 9870 19831 9871 19831 9785 19831 9785 19832 9871 19832 1082 19832 9785 19833 1082 19833 9872 19833 9685 19834 1042 19834 1073 19834 1073 19835 1042 19835 9635 19835 1073 19836 9635 19836 1075 19836 1075 19837 9635 19837 9633 19837 1075 19838 9633 19838 9873 19838 9873 19839 9633 19839 9874 19839 9873 19840 9874 19840 9538 19840 9538 19841 9874 19841 9875 19841 9538 19842 9875 19842 9539 19842 9539 19843 9875 19843 9952 19843 9539 19844 9952 19844 9540 19844 9540 19845 9952 19845 9937 19845 9687 19846 9876 19846 9689 19846 9689 19847 9876 19847 1078 19847 9689 19848 1078 19848 9936 19848 9936 19849 1078 19849 9877 19849 9936 19850 9877 19850 9878 19850 9878 19851 9877 19851 9545 19851 9878 19852 9545 19852 9879 19852 9546 19853 9950 19853 9880 19853 1071 19854 1069 19854 9881 19854 9881 19855 1069 19855 9882 19855 9882 19856 1067 19856 9884 19856 1067 19857 9883 19857 9884 19857 9884 19858 9883 19858 9551 19858 9884 19859 9551 19859 9885 19859 9885 19860 9551 19860 9550 19860 9885 19861 9550 19861 9940 19861 9940 19862 9550 19862 9886 19862 9940 19863 9886 19863 9547 19863 9558 19864 986 19864 9842 19864 9842 19865 986 19865 1126 19865 9842 19866 1126 19866 1124 19866 9570 19867 9569 19867 9967 19867 9967 19868 9569 19868 9958 19868 9558 19869 9887 19869 986 19869 986 19870 9887 19870 9556 19870 986 19871 9556 19871 9967 19871 9967 19872 9556 19872 9554 19872 9967 19873 9554 19873 9570 19873 9567 19874 9566 19874 9888 19874 9888 19875 9566 19875 9889 19875 9888 19876 9889 19876 9934 19876 9934 19877 9889 19877 9565 19877 9934 19878 9565 19878 9668 19878 9668 19879 9565 19879 9891 19879 9668 19880 9891 19880 9890 19880 9890 19881 9891 19881 9892 19881 9893 19882 9571 19882 9592 19882 9590 19883 9967 19883 9894 19883 9894 19884 9967 19884 9969 19884 9894 19885 9969 19885 9592 19885 9893 19886 9720 19886 9571 19886 9571 19887 9720 19887 9899 19887 9571 19888 9899 19888 9900 19888 9594 19889 9908 19889 9895 19889 9895 19890 9908 19890 9962 19890 9895 19891 9962 19891 9963 19891 9594 19892 9895 19892 9596 19892 9596 19893 9895 19893 9623 19893 9596 19894 9623 19894 9597 19894 9597 19895 9623 19895 9896 19895 9597 19896 9896 19896 9598 19896 9598 19897 9896 19897 9622 19897 9598 19898 9622 19898 9897 19898 9897 19899 9622 19899 9620 19899 9897 19900 9620 19900 9619 19900 9898 19901 9515 19901 9619 19901 9619 19902 9515 19902 9864 19902 9619 19903 9864 19903 9897 19903 9897 19904 9864 19904 9856 19904 9897 19905 9856 19905 9907 19905 9899 19906 9901 19906 9900 19906 9900 19907 9901 19907 9605 19907 9900 19908 9605 19908 9902 19908 9902 19909 9605 19909 9903 19909 9902 19910 9903 19910 9798 19910 9798 19911 9903 19911 9904 19911 9904 19912 9602 19912 9798 19912 9798 19913 9602 19913 9905 19913 9798 19914 9905 19914 9743 19914 9743 19915 9905 19915 9601 19915 9743 19916 9601 19916 9742 19916 9742 19917 9601 19917 9600 19917 9742 19918 9600 19918 9856 19918 9856 19919 9600 19919 9906 19919 9856 19920 9906 19920 9907 19920 9908 19921 9909 19921 9962 19921 9962 19922 9909 19922 9609 19922 9962 19923 9609 19923 9893 19923 9893 19924 9609 19924 9607 19924 9893 19925 9607 19925 9910 19925 9911 19926 9912 19926 9930 19926 9930 19927 9912 19927 9913 19927 9930 19928 9913 19928 9916 19928 9916 19929 9913 19929 9914 19929 9916 19930 9914 19930 9915 19930 9915 19931 9624 19931 9916 19931 9916 19932 9624 19932 9625 19932 9916 19933 9625 19933 9917 19933 9631 19934 9629 19934 9918 19934 9918 19935 9629 19935 9919 19935 9627 19936 9921 19936 9920 19936 9920 19937 9921 19937 9646 19937 9920 19938 9646 19938 9922 19938 9920 19939 9662 19939 9627 19939 9627 19940 9662 19940 9660 19940 9627 19941 9660 19941 9924 19941 9924 19942 9660 19942 9923 19942 9924 19943 9923 19943 9919 19943 9919 19944 9923 19944 9653 19944 9919 19945 9653 19945 9918 19945 9925 19946 9636 19946 9929 19946 9929 19947 9636 19947 9640 19947 9929 19948 9640 19948 9870 19948 9870 19949 9640 19949 9927 19949 9870 19950 9927 19950 9926 19950 9926 19951 9927 19951 9928 19951 9926 19952 9928 19952 9869 19952 9869 19953 9928 19953 9635 19953 9869 19954 9635 19954 1041 19954 1041 19955 9635 19955 1042 19955 9925 19956 9929 19956 9643 19956 9643 19957 9929 19957 9930 19957 9643 19958 9930 19958 9644 19958 9644 19959 9930 19959 9645 19959 9645 19960 9930 19960 9916 19960 9645 19961 9916 19961 9931 19961 9922 19962 9970 19962 9920 19962 9920 19963 9970 19963 9932 19963 9920 19964 9932 19964 9968 19964 9652 19965 9933 19965 9756 19965 9756 19966 9933 19966 1061 19966 9756 19967 1061 19967 9766 19967 9766 19968 1061 19968 9651 19968 9766 19969 9651 19969 9892 19969 9892 19970 9651 19970 9649 19970 9892 19971 9649 19971 9890 19971 9874 19972 9631 19972 9875 19972 9875 19973 9631 19973 9918 19973 9875 19974 9918 19974 9952 19974 9952 19975 9918 19975 9657 19975 9934 19976 9665 19976 9888 19976 9888 19977 9665 19977 9664 19977 9888 19978 9664 19978 9961 19978 998 19979 9935 19979 9878 19979 9878 19980 9935 19980 1000 19980 9878 19981 1000 19981 9936 19981 9936 19982 1000 19982 9690 19982 9936 19983 9690 19983 9689 19983 9939 19984 996 19984 9952 19984 9952 19985 996 19985 9878 19985 9952 19986 9878 19986 9937 19986 9937 19987 9878 19987 9879 19987 9938 19988 996 19988 9881 19988 9881 19989 996 19989 9939 19989 9881 19990 9939 19990 1071 19990 9882 19991 9884 19991 9881 19991 9881 19992 9884 19992 995 19992 9881 19993 995 19993 9938 19993 9957 19994 1045 19994 9880 19994 9880 19995 1045 19995 1044 19995 9880 19996 1044 19996 9941 19996 9547 19997 9546 19997 9940 19997 9940 19998 9546 19998 9880 19998 9940 19999 9880 19999 9943 19999 9943 20000 9880 20000 9941 20000 9680 20001 994 20001 9942 20001 9942 20002 994 20002 993 20002 9942 20003 993 20003 9681 20003 9681 20004 993 20004 9940 20004 9681 20005 9940 20005 9682 20005 9682 20006 9940 20006 9943 20006 9680 20007 9944 20007 994 20007 994 20008 9944 20008 9945 20008 994 20009 9945 20009 9805 20009 9805 20010 9945 20010 1046 20010 9805 20011 1046 20011 9946 20011 1102 20012 1101 20012 9976 20012 9976 20013 1101 20013 9853 20013 9976 20014 9853 20014 9947 20014 9947 20015 9853 20015 9856 20015 9947 20016 9856 20016 9949 20016 9949 20017 9856 20017 9948 20017 9949 20018 9948 20018 1097 20018 9952 20019 9953 20019 9939 20019 9939 20020 9953 20020 9955 20020 9939 20021 9955 20021 1071 20021 1071 20022 9955 20022 9880 20022 1071 20023 9880 20023 1072 20023 1072 20024 9880 20024 9950 20024 9657 20025 9655 20025 9952 20025 9952 20026 9655 20026 9951 20026 9952 20027 9951 20027 9953 20027 9953 20028 9951 20028 9954 20028 9953 20029 9954 20029 9955 20029 9955 20030 9954 20030 9956 20030 9955 20031 9956 20031 9880 20031 9880 20032 9956 20032 9805 20032 9880 20033 9805 20033 9957 20033 9957 20034 9805 20034 9946 20034 9958 20035 9568 20035 9960 20035 9960 20036 9568 20036 9959 20036 9960 20037 9959 20037 9968 20037 9968 20038 9959 20038 9888 20038 9968 20039 9888 20039 9920 20039 9920 20040 9888 20040 9961 20040 9920 20041 9961 20041 9719 20041 9592 20042 9969 20042 9893 20042 9893 20043 9969 20043 9916 20043 9893 20044 9916 20044 9962 20044 9962 20045 9916 20045 9917 20045 9962 20046 9917 20046 9963 20046 9954 20047 9652 20047 9964 20047 9964 20048 9652 20048 9756 20048 9964 20049 9756 20049 9956 20049 9956 20050 9756 20050 9758 20050 9956 20051 9758 20051 9965 20051 9965 20052 9758 20052 9966 20052 9965 20053 9966 20053 1135 20053 1135 20054 9966 20054 1136 20054 9958 20055 9960 20055 9967 20055 9967 20056 9960 20056 9968 20056 9967 20057 9968 20057 9969 20057 9969 20058 9968 20058 9932 20058 9969 20059 9932 20059 9916 20059 9916 20060 9932 20060 9970 20060 9916 20061 9970 20061 9931 20061 9971 20062 10002 20062 10000 20062 9971 20063 10000 20063 9783 20063 9783 20064 10000 20064 9998 20064 9783 20065 9998 20065 9771 20065 9771 20066 9998 20066 9790 20066 9790 20067 9998 20067 9973 20067 9790 20068 9973 20068 9789 20068 9789 20069 9973 20069 9972 20069 9972 20070 9973 20070 9974 20070 9972 20071 9974 20071 9949 20071 9949 20072 9974 20072 9975 20072 9949 20073 9975 20073 9947 20073 9947 20074 9975 20074 9976 20074 9976 20075 9975 20075 9977 20075 9976 20076 9977 20076 9858 20076 9858 20077 9977 20077 9993 20077 9858 20078 9993 20078 9978 20078 9978 20079 9993 20079 9979 20079 9978 20080 9979 20080 9980 20080 9980 20081 9979 20081 9992 20081 9980 20082 9992 20082 9981 20082 9981 20083 9992 20083 9991 20083 9981 20084 9991 20084 9795 20084 9795 20085 9991 20085 9982 20085 9982 20086 9991 20086 9989 20086 9982 20087 9989 20087 9983 20087 9983 20088 9989 20088 9984 20088 9984 20089 9989 20089 9985 20089 9984 20090 9985 20090 9727 20090 9727 20091 9985 20091 9729 20091 9729 20092 9985 20092 9987 20092 9729 20093 9987 20093 9741 20093 9741 20094 9987 20094 9986 20094 9741 20095 9986 20095 986 20095 9440 20096 9986 20096 9987 20096 9440 20097 9987 20097 9439 20097 9439 20098 9987 20098 9985 20098 9439 20099 9985 20099 9988 20099 9988 20100 9985 20100 9989 20100 9988 20101 9989 20101 9990 20101 9990 20102 9989 20102 9991 20102 9990 20103 9991 20103 9450 20103 9450 20104 9991 20104 9992 20104 9450 20105 9992 20105 9448 20105 9448 20106 9992 20106 9979 20106 9448 20107 9979 20107 9994 20107 9994 20108 9979 20108 9993 20108 9994 20109 9993 20109 9995 20109 9995 20110 9993 20110 9977 20110 9995 20111 9977 20111 9446 20111 9446 20112 9977 20112 9975 20112 9446 20113 9975 20113 9996 20113 9996 20114 9975 20114 9974 20114 9996 20115 9974 20115 9997 20115 9997 20116 9974 20116 9973 20116 9997 20117 9973 20117 9999 20117 9999 20118 9973 20118 9998 20118 9999 20119 9998 20119 9431 20119 9431 20120 9998 20120 10000 20120 9431 20121 10000 20121 10001 20121 10001 20122 10000 20122 10002 20122 10001 20123 10002 20123 9429 20123 10274 20124 9721 20124 10003 20124 10003 20125 9721 20125 9728 20125 10003 20126 9728 20126 10275 20126 10275 20127 9728 20127 10004 20127 10275 20128 10004 20128 10276 20128 10276 20129 10004 20129 9730 20129 10276 20130 9730 20130 10278 20130 10278 20131 9730 20131 9731 20131 10278 20132 9731 20132 10279 20132 10279 20133 9731 20133 10005 20133 10279 20134 10005 20134 10281 20134 10281 20135 10005 20135 970 20135 962 20136 10024 20136 10006 20136 10006 20137 10024 20137 10007 20137 10284 20138 10011 20138 10008 20138 10008 20139 10011 20139 961 20139 10008 20140 961 20140 960 20140 10287 20141 10009 20141 10286 20141 10286 20142 10009 20142 10010 20142 10286 20143 10010 20143 10284 20143 10284 20144 10010 20144 10011 20144 10009 20145 10287 20145 9621 20145 9621 20146 10287 20146 10013 20146 9621 20147 10013 20147 10012 20147 10012 20148 10013 20148 10014 20148 10012 20149 10014 20149 10015 20149 10015 20150 10014 20150 10016 20150 10015 20151 10016 20151 9617 20151 9617 20152 10016 20152 10018 20152 10290 20153 10017 20153 10289 20153 10289 20154 10017 20154 9615 20154 10289 20155 9615 20155 10018 20155 10018 20156 9615 20156 9617 20156 10017 20157 10290 20157 956 20157 956 20158 10290 20158 753 20158 10019 20159 10020 20159 10021 20159 10021 20160 10020 20160 10022 20160 10021 20161 10022 20161 959 20161 959 20162 10022 20162 10023 20162 10007 20163 10024 20163 10025 20163 10025 20164 10024 20164 9626 20164 10025 20165 9626 20165 10293 20165 10293 20166 9626 20166 10026 20166 10293 20167 10026 20167 10019 20167 10019 20168 10026 20168 10020 20168 10027 20169 10028 20169 10297 20169 10297 20170 10028 20170 9604 20170 10297 20171 9604 20171 10319 20171 10319 20172 9604 20172 10044 20172 10028 20173 10027 20173 10030 20173 10028 20174 10030 20174 10029 20174 10029 20175 10030 20175 10032 20175 10029 20176 10032 20176 10031 20176 10031 20177 10032 20177 10300 20177 10031 20178 10300 20178 9603 20178 9603 20179 10300 20179 10301 20179 9603 20180 10301 20180 10033 20180 10303 20181 10036 20181 10034 20181 10034 20182 10036 20182 10035 20182 10034 20183 10035 20183 10301 20183 10301 20184 10035 20184 10033 20184 10036 20185 10303 20185 10306 20185 10036 20186 10306 20186 10037 20186 10037 20187 10306 20187 10307 20187 10037 20188 10307 20188 10038 20188 10038 20189 10307 20189 9599 20189 9599 20190 10307 20190 10308 20190 9599 20191 10308 20191 954 20191 10310 20192 10041 20192 10309 20192 10309 20193 10041 20193 9593 20193 10309 20194 9593 20194 955 20194 955 20195 9593 20195 9595 20195 10316 20196 9608 20196 10314 20196 10314 20197 9608 20197 9610 20197 10314 20198 9610 20198 10039 20198 10039 20199 9610 20199 10040 20199 10039 20200 10040 20200 10310 20200 10310 20201 10040 20201 10041 20201 10046 20202 9608 20202 10042 20202 10042 20203 9608 20203 10316 20203 10319 20204 10044 20204 10043 20204 10043 20205 10044 20205 9606 20205 10043 20206 9606 20206 10317 20206 10317 20207 9606 20207 10045 20207 10317 20208 10045 20208 10042 20208 10042 20209 10045 20209 10046 20209 10049 20210 9583 20210 10047 20210 10047 20211 9583 20211 10048 20211 10047 20212 10048 20212 10321 20212 10321 20213 10048 20213 9585 20213 9583 20214 10049 20214 10322 20214 9583 20215 10322 20215 10050 20215 10050 20216 10322 20216 10324 20216 10050 20217 10324 20217 10051 20217 10051 20218 10324 20218 10326 20218 10051 20219 10326 20219 1066 20219 1066 20220 10326 20220 10052 20220 10052 20221 10326 20221 10327 20221 10052 20222 10327 20222 10053 20222 10328 20223 9579 20223 10329 20223 10329 20224 9579 20224 9582 20224 10329 20225 9582 20225 10327 20225 10327 20226 9582 20226 10053 20226 9579 20227 10328 20227 9577 20227 9577 20228 10328 20228 10331 20228 9577 20229 10331 20229 9575 20229 9575 20230 10331 20230 10054 20230 9575 20231 10054 20231 10055 20231 10055 20232 10054 20232 10334 20232 10055 20233 10334 20233 10058 20233 10058 20234 10334 20234 10335 20234 10056 20235 10057 20235 10336 20235 10336 20236 10057 20236 9572 20236 10336 20237 9572 20237 10335 20237 10335 20238 9572 20238 10058 20238 10059 20239 10060 20239 10061 20239 10059 20240 10061 20240 750 20240 750 20241 10061 20241 9591 20241 750 20242 9591 20242 10338 20242 10338 20243 9591 20243 10057 20243 10338 20244 10057 20244 10056 20244 9588 20245 10060 20245 10062 20245 10062 20246 10060 20246 10059 20246 10321 20247 9585 20247 10341 20247 10341 20248 9585 20248 9587 20248 10341 20249 9587 20249 10340 20249 10340 20250 9587 20250 10063 20250 10340 20251 10063 20251 10062 20251 10062 20252 10063 20252 9588 20252 10343 20253 9563 20253 10342 20253 10342 20254 9563 20254 10064 20254 10342 20255 10064 20255 747 20255 747 20256 10064 20256 9564 20256 9563 20257 10343 20257 9562 20257 9562 20258 10343 20258 10344 20258 9562 20259 10344 20259 9561 20259 9561 20260 10344 20260 10346 20260 9561 20261 10346 20261 10065 20261 10065 20262 10346 20262 10066 20262 10065 20263 10066 20263 10071 20263 10071 20264 10066 20264 10070 20264 10073 20265 10067 20265 10068 20265 10068 20266 10067 20266 10069 20266 10068 20267 10069 20267 10070 20267 10070 20268 10069 20268 10071 20268 10067 20269 10073 20269 10072 20269 10072 20270 10073 20270 10075 20270 10072 20271 10075 20271 10074 20271 10074 20272 10075 20272 10076 20272 10074 20273 10076 20273 10077 20273 10077 20274 10076 20274 10352 20274 10077 20275 10352 20275 9557 20275 9557 20276 10352 20276 10078 20276 9557 20277 10078 20277 10079 20277 10355 20278 9553 20278 10354 20278 10354 20279 9553 20279 9555 20279 10354 20280 9555 20280 10078 20280 10078 20281 9555 20281 10079 20281 10359 20282 10085 20282 10080 20282 10080 20283 10085 20283 10082 20283 10080 20284 10082 20284 10081 20284 10081 20285 10082 20285 10083 20285 10081 20286 10083 20286 10355 20286 10355 20287 10083 20287 9553 20287 10084 20288 10085 20288 10089 20288 10089 20289 10085 20289 10359 20289 747 20290 9564 20290 10086 20290 747 20291 10086 20291 10087 20291 10087 20292 10086 20292 10088 20292 10087 20293 10088 20293 10361 20293 10361 20294 10088 20294 10084 20294 10361 20295 10084 20295 10089 20295 10365 20296 9659 20296 10364 20296 10364 20297 9659 20297 10090 20297 10364 20298 10090 20298 10385 20298 10385 20299 10090 20299 10091 20299 9659 20300 10365 20300 9658 20300 9658 20301 10365 20301 743 20301 10092 20302 1062 20302 10368 20302 10368 20303 1062 20303 10093 20303 10368 20304 10093 20304 746 20304 746 20305 10093 20305 9654 20305 1062 20306 10092 20306 10370 20306 1062 20307 10370 20307 10094 20307 10094 20308 10370 20308 10095 20308 10094 20309 10095 20309 10096 20309 10096 20310 10095 20310 10372 20310 10096 20311 10372 20311 10097 20311 10097 20312 10372 20312 10373 20312 10097 20313 10373 20313 9650 20313 10098 20314 9667 20314 10374 20314 10374 20315 9667 20315 9648 20315 10374 20316 9648 20316 10373 20316 10373 20317 9648 20317 9650 20317 10102 20318 9663 20318 10378 20318 10378 20319 9663 20319 10100 20319 10378 20320 10100 20320 10099 20320 10099 20321 10100 20321 9666 20321 10099 20322 9666 20322 10098 20322 10098 20323 9666 20323 9667 20323 10101 20324 9663 20324 10104 20324 10104 20325 9663 20325 10102 20325 10385 20326 10091 20326 10383 20326 10383 20327 10091 20327 9661 20327 10383 20328 9661 20328 10382 20328 10382 20329 9661 20329 10103 20329 10382 20330 10103 20330 10104 20330 10104 20331 10103 20331 10101 20331 10387 20332 9637 20332 10106 20332 10106 20333 9637 20333 10105 20333 10106 20334 10105 20334 10405 20334 10405 20335 10105 20335 10121 20335 9638 20336 9637 20336 10107 20336 10107 20337 9637 20337 10387 20337 9638 20338 10107 20338 9639 20338 9639 20339 10107 20339 10108 20339 9639 20340 10108 20340 9641 20340 9641 20341 10108 20341 10109 20341 10109 20342 10108 20342 10389 20342 10109 20343 10389 20343 9642 20343 10390 20344 9632 20344 10392 20344 10392 20345 9632 20345 9634 20345 10392 20346 9634 20346 741 20346 741 20347 9634 20347 949 20347 9632 20348 10390 20348 10110 20348 10110 20349 10390 20349 10393 20349 10110 20350 10393 20350 9630 20350 9630 20351 10393 20351 10111 20351 9630 20352 10111 20352 9628 20352 9628 20353 10111 20353 10112 20353 9628 20354 10112 20354 10115 20354 10115 20355 10112 20355 10114 20355 10398 20356 1063 20356 10397 20356 10397 20357 1063 20357 10113 20357 10397 20358 10113 20358 10114 20358 10114 20359 10113 20359 10115 20359 10402 20360 10120 20360 10117 20360 10402 20361 10117 20361 10116 20361 10116 20362 10117 20362 9647 20362 10116 20363 9647 20363 10118 20363 10119 20364 10120 20364 10401 20364 10401 20365 10120 20365 10402 20365 10405 20366 10121 20366 10122 20366 10122 20367 10121 20367 10123 20367 10122 20368 10123 20368 10125 20368 10125 20369 10123 20369 10124 20369 10125 20370 10124 20370 10401 20370 10401 20371 10124 20371 10119 20371 10411 20372 947 20372 10409 20372 10409 20373 947 20373 9451 20373 10409 20374 9451 20374 10126 20374 10126 20375 9451 20375 10127 20375 10126 20376 10127 20376 10128 20376 10128 20377 10127 20377 10129 20377 10128 20378 10129 20378 10407 20378 10407 20379 10129 20379 10130 20379 10407 20380 10130 20380 10131 20380 10131 20381 10130 20381 10132 20381 10131 20382 10132 20382 10133 20382 10133 20383 10132 20383 10134 20383 10133 20384 10134 20384 739 20384 739 20385 10134 20385 9452 20385 1106 20386 9502 20386 10135 20386 10135 20387 9502 20387 10416 20387 9502 20388 10136 20388 10416 20388 10416 20389 10136 20389 10137 20389 10416 20390 10137 20390 10138 20390 10137 20391 9501 20391 10138 20391 10138 20392 9501 20392 10139 20392 10138 20393 10139 20393 10140 20393 10139 20394 9498 20394 10140 20394 10140 20395 9498 20395 9496 20395 10140 20396 9496 20396 10413 20396 9496 20397 10141 20397 10413 20397 10413 20398 10141 20398 9495 20398 10413 20399 9495 20399 10412 20399 1108 20400 929 20400 9494 20400 9494 20401 929 20401 10412 20401 9494 20402 10412 20402 10142 20402 10142 20403 10412 20403 9495 20403 928 20404 927 20404 10422 20404 10422 20405 927 20405 9486 20405 10422 20406 9486 20406 10143 20406 10143 20407 9486 20407 9487 20407 10143 20408 9487 20408 10144 20408 10144 20409 9487 20409 9489 20409 10144 20410 9489 20410 10145 20410 10145 20411 9489 20411 10146 20411 10145 20412 10146 20412 10419 20412 10419 20413 10146 20413 9491 20413 10419 20414 9491 20414 10147 20414 10147 20415 9491 20415 10148 20415 10147 20416 10148 20416 713 20416 713 20417 10148 20417 916 20417 10149 20418 9484 20418 703 20418 703 20419 9484 20419 10150 20419 9484 20420 9485 20420 10150 20420 10150 20421 9485 20421 10151 20421 10150 20422 10151 20422 10425 20422 10151 20423 10152 20423 10425 20423 10425 20424 10152 20424 9480 20424 10425 20425 9480 20425 10424 20425 9480 20426 10153 20426 10424 20426 10424 20427 10153 20427 9479 20427 10424 20428 9479 20428 10154 20428 9479 20429 10155 20429 10154 20429 10154 20430 10155 20430 10156 20430 10154 20431 10156 20431 10159 20431 9476 20432 10157 20432 10158 20432 10158 20433 10157 20433 10159 20433 10158 20434 10159 20434 9477 20434 9477 20435 10159 20435 10156 20435 10160 20436 909 20436 10434 20436 10434 20437 909 20437 10162 20437 10434 20438 10162 20438 10161 20438 10161 20439 10162 20439 9471 20439 10161 20440 9471 20440 10433 20440 10433 20441 9471 20441 9473 20441 10433 20442 9473 20442 10432 20442 10432 20443 9473 20443 9474 20443 10432 20444 9474 20444 10429 20444 10429 20445 9474 20445 10163 20445 10429 20446 10163 20446 10165 20446 10165 20447 10163 20447 10164 20447 10165 20448 10164 20448 702 20448 702 20449 10164 20449 1120 20449 10436 20450 904 20450 10445 20450 10445 20451 904 20451 10166 20451 10445 20452 10166 20452 10444 20452 10444 20453 10166 20453 10167 20453 10444 20454 10167 20454 10440 20454 10440 20455 10167 20455 9467 20455 10440 20456 9467 20456 10439 20456 10439 20457 9467 20457 10168 20457 10439 20458 10168 20458 10438 20458 10438 20459 10168 20459 9469 20459 10438 20460 9469 20460 10169 20460 10169 20461 9469 20461 10170 20461 10169 20462 10170 20462 896 20462 896 20463 10170 20463 897 20463 10171 20464 1137 20464 9456 20464 10171 20465 9456 20465 10448 20465 10448 20466 9456 20466 9457 20466 10448 20467 9457 20467 10172 20467 10172 20468 9457 20468 10173 20468 10173 20469 9457 20469 10174 20469 10173 20470 10174 20470 10452 20470 10452 20471 10174 20471 10175 20471 10175 20472 10174 20472 10176 20472 10175 20473 10176 20473 10453 20473 10453 20474 10176 20474 10455 20474 10455 20475 10176 20475 9461 20475 10455 20476 9461 20476 10454 20476 10454 20477 9461 20477 9462 20477 10454 20478 9462 20478 10178 20478 10178 20479 9462 20479 10177 20479 10178 20480 10177 20480 890 20480 10457 20481 10179 20481 10181 20481 10181 20482 10179 20482 10180 20482 10181 20483 10180 20483 10458 20483 10458 20484 10180 20484 10182 20484 10182 20485 10180 20485 9548 20485 10182 20486 9548 20486 10460 20486 10460 20487 9548 20487 10461 20487 10461 20488 9548 20488 9549 20488 10461 20489 9549 20489 10462 20489 10462 20490 9549 20490 10183 20490 10183 20491 9549 20491 9552 20491 10183 20492 9552 20492 10184 20492 10184 20493 9552 20493 10185 20493 10185 20494 9552 20494 10186 20494 10185 20495 10186 20495 10187 20495 10187 20496 10186 20496 10465 20496 10465 20497 10186 20497 883 20497 10465 20498 883 20498 681 20498 10471 20499 882 20499 10188 20499 10188 20500 882 20500 10189 20500 10188 20501 10189 20501 10469 20501 10469 20502 10189 20502 10190 20502 10469 20503 10190 20503 10467 20503 10467 20504 10190 20504 9541 20504 10467 20505 9541 20505 10191 20505 10191 20506 9541 20506 9542 20506 10191 20507 9542 20507 10473 20507 10473 20508 9542 20508 9543 20508 10473 20509 9543 20509 873 20509 873 20510 9543 20510 9544 20510 662 20511 10192 20511 10478 20511 10478 20512 10192 20512 9529 20512 10478 20513 9529 20513 10194 20513 10194 20514 9529 20514 10193 20514 10194 20515 10193 20515 10195 20515 10195 20516 10193 20516 9531 20516 10195 20517 9531 20517 10480 20517 10480 20518 9531 20518 9534 20518 10480 20519 9534 20519 10475 20519 10475 20520 9534 20520 9537 20520 10475 20521 9537 20521 10196 20521 10196 20522 9537 20522 10197 20522 10488 20523 1085 20523 10198 20523 10198 20524 1085 20524 9521 20524 10198 20525 9521 20525 10199 20525 10199 20526 9521 20526 10201 20526 10199 20527 10201 20527 10200 20527 10200 20528 10201 20528 10202 20528 10200 20529 10202 20529 10485 20529 10485 20530 10202 20530 9525 20530 10485 20531 9525 20531 10482 20531 10482 20532 9525 20532 9526 20532 10482 20533 9526 20533 10203 20533 10203 20534 9526 20534 863 20534 10493 20535 838 20535 10492 20535 10492 20536 838 20536 9513 20536 10492 20537 9513 20537 10204 20537 10204 20538 9513 20538 9514 20538 10204 20539 9514 20539 10491 20539 10491 20540 9514 20540 9516 20540 10491 20541 9516 20541 10205 20541 10205 20542 9516 20542 9518 20542 10205 20543 9518 20543 10206 20543 10206 20544 9518 20544 10207 20544 10206 20545 10207 20545 10208 20545 10208 20546 10207 20546 849 20546 837 20547 10209 20547 10210 20547 10210 20548 10209 20548 10212 20548 10210 20549 10212 20549 10211 20549 10211 20550 10212 20550 10214 20550 10211 20551 10214 20551 10213 20551 10213 20552 10214 20552 9507 20552 10213 20553 9507 20553 10496 20553 10496 20554 9507 20554 10215 20554 10496 20555 10215 20555 10494 20555 10494 20556 10215 20556 9510 20556 10494 20557 9510 20557 830 20557 830 20558 9510 20558 9511 20558 10216 20559 10217 20559 10586 20559 10586 20560 10217 20560 9669 20560 10586 20561 9669 20561 10218 20561 10218 20562 9669 20562 9670 20562 10218 20563 9670 20563 10219 20563 10219 20564 9670 20564 9671 20564 10219 20565 9671 20565 10220 20565 10220 20566 9671 20566 10221 20566 10220 20567 10221 20567 10637 20567 10637 20568 10221 20568 10223 20568 10637 20569 10223 20569 10222 20569 10222 20570 10223 20570 821 20570 10643 20571 9672 20571 10224 20571 10224 20572 9672 20572 9673 20572 10224 20573 9673 20573 10225 20573 10225 20574 9673 20574 9675 20574 10225 20575 9675 20575 10640 20575 10640 20576 9675 20576 10226 20576 10640 20577 10226 20577 10227 20577 10227 20578 10226 20578 10228 20578 10227 20579 10228 20579 10641 20579 10641 20580 10228 20580 10229 20580 10641 20581 10229 20581 813 20581 813 20582 10229 20582 1048 20582 10659 20583 10230 20583 10657 20583 10657 20584 10230 20584 10231 20584 10657 20585 10231 20585 10232 20585 10232 20586 10231 20586 9679 20586 10232 20587 9679 20587 10664 20587 10664 20588 9679 20588 10233 20588 10664 20589 10233 20589 10661 20589 10661 20590 10233 20590 10234 20590 10661 20591 10234 20591 10660 20591 10660 20592 10234 20592 10235 20592 10660 20593 10235 20593 10666 20593 10666 20594 10235 20594 9683 20594 804 20595 10236 20595 10510 20595 10510 20596 10236 20596 9684 20596 10510 20597 9684 20597 10237 20597 10237 20598 9684 20598 9686 20598 10237 20599 9686 20599 10238 20599 10238 20600 9686 20600 9688 20600 10238 20601 9688 20601 10682 20601 10682 20602 9688 20602 10239 20602 10682 20603 10239 20603 10240 20603 10240 20604 10239 20604 9691 20604 10240 20605 9691 20605 10241 20605 10241 20606 9691 20606 10242 20606 10241 20607 10242 20607 799 20607 799 20608 10242 20608 9693 20608 10517 20609 10243 20609 10245 20609 10245 20610 10243 20610 10244 20610 10245 20611 10244 20611 10689 20611 10689 20612 10244 20612 9695 20612 10689 20613 9695 20613 10246 20613 10246 20614 9695 20614 10247 20614 10246 20615 10247 20615 10690 20615 10690 20616 10247 20616 9698 20616 10690 20617 9698 20617 10516 20617 10516 20618 9698 20618 10248 20618 10516 20619 10248 20619 791 20619 791 20620 10248 20620 9700 20620 10521 20621 788 20621 10249 20621 10521 20622 10249 20622 10250 20622 10250 20623 10249 20623 9708 20623 10250 20624 9708 20624 10252 20624 10252 20625 9708 20625 10251 20625 10252 20626 10251 20626 10253 20626 10251 20627 10254 20627 10253 20627 10253 20628 10254 20628 9705 20628 10253 20629 9705 20629 10523 20629 10523 20630 9705 20630 10255 20630 10523 20631 10255 20631 10525 20631 10525 20632 10255 20632 9703 20632 9703 20633 10256 20633 10525 20633 10525 20634 10256 20634 10257 20634 10525 20635 10257 20635 10258 20635 10258 20636 10257 20636 779 20636 10258 20637 779 20637 10697 20637 778 20638 1019 20638 10259 20638 10259 20639 1019 20639 9710 20639 10259 20640 9710 20640 10261 20640 10261 20641 9710 20641 10260 20641 10261 20642 10260 20642 10263 20642 10263 20643 10260 20643 10262 20643 10263 20644 10262 20644 10264 20644 10264 20645 10262 20645 10265 20645 10264 20646 10265 20646 10266 20646 10266 20647 10265 20647 10267 20647 10266 20648 10267 20648 773 20648 773 20649 10267 20649 774 20649 772 20650 1010 20650 10733 20650 10733 20651 1010 20651 10268 20651 10733 20652 10268 20652 10732 20652 10732 20653 10268 20653 10269 20653 10732 20654 10269 20654 10726 20654 10726 20655 10269 20655 9715 20655 10726 20656 9715 20656 10727 20656 10727 20657 9715 20657 10271 20657 10727 20658 10271 20658 10270 20658 10270 20659 10271 20659 10272 20659 10270 20660 10272 20660 767 20660 767 20661 10272 20661 768 20661 10574 20662 10274 20662 10273 20662 10273 20663 10274 20663 10003 20663 10273 20664 10003 20664 10570 20664 10570 20665 10003 20665 10275 20665 10570 20666 10275 20666 10573 20666 10573 20667 10275 20667 10276 20667 10573 20668 10276 20668 10277 20668 10277 20669 10276 20669 10278 20669 10277 20670 10278 20670 10571 20670 10571 20671 10278 20671 10279 20671 10571 20672 10279 20672 10280 20672 10280 20673 10279 20673 10281 20673 10006 20674 10007 20674 10527 20674 10527 20675 10007 20675 10295 20675 10629 20676 10285 20676 10284 20676 10006 20677 10527 20677 10282 20677 10282 20678 10527 20678 10283 20678 10282 20679 10283 20679 960 20679 960 20680 10283 20680 10629 20680 960 20681 10629 20681 10008 20681 10008 20682 10629 20682 10284 20682 10284 20683 10285 20683 10286 20683 10286 20684 10285 20684 10529 20684 10286 20685 10529 20685 10287 20685 10287 20686 10529 20686 10530 20686 10287 20687 10530 20687 10013 20687 10013 20688 10530 20688 10554 20688 10013 20689 10554 20689 10014 20689 10014 20690 10554 20690 10553 20690 10014 20691 10553 20691 10016 20691 10016 20692 10553 20692 10528 20692 10016 20693 10528 20693 10018 20693 10018 20694 10528 20694 10520 20694 10018 20695 10520 20695 10289 20695 10289 20696 10520 20696 10288 20696 10289 20697 10288 20697 10290 20697 10290 20698 10288 20698 10535 20698 10290 20699 10535 20699 753 20699 753 20700 10535 20700 10291 20700 959 20701 10540 20701 10021 20701 10021 20702 10540 20702 10292 20702 10021 20703 10292 20703 10019 20703 10019 20704 10292 20704 10538 20704 10019 20705 10538 20705 10293 20705 10293 20706 10538 20706 10537 20706 10293 20707 10537 20707 10025 20707 10025 20708 10537 20708 10294 20708 10025 20709 10294 20709 10007 20709 10007 20710 10294 20710 10295 20710 10319 20711 10296 20711 10297 20711 10297 20712 10296 20712 10298 20712 10297 20713 10298 20713 10027 20713 10027 20714 10298 20714 10299 20714 10027 20715 10299 20715 10030 20715 10030 20716 10299 20716 10545 20716 10030 20717 10545 20717 10032 20717 10032 20718 10545 20718 10543 20718 10032 20719 10543 20719 10300 20719 10300 20720 10543 20720 10542 20720 10300 20721 10542 20721 10301 20721 10301 20722 10542 20722 10302 20722 10301 20723 10302 20723 10034 20723 10034 20724 10302 20724 10304 20724 10034 20725 10304 20725 10303 20725 10303 20726 10304 20726 10305 20726 10303 20727 10305 20727 10306 20727 10306 20728 10305 20728 10550 20728 10306 20729 10550 20729 10307 20729 10307 20730 10550 20730 10531 20730 10307 20731 10531 20731 10308 20731 10308 20732 10531 20732 751 20732 955 20733 752 20733 10309 20733 10309 20734 752 20734 10311 20734 10309 20735 10311 20735 10310 20735 10310 20736 10311 20736 10312 20736 10310 20737 10312 20737 10039 20737 10039 20738 10312 20738 10313 20738 10039 20739 10313 20739 10314 20739 10314 20740 10313 20740 10315 20740 10314 20741 10315 20741 10316 20741 10316 20742 10315 20742 10556 20742 10042 20743 10316 20743 10555 20743 10555 20744 10316 20744 10556 20744 10042 20745 10555 20745 10317 20745 10317 20746 10555 20746 10318 20746 10317 20747 10318 20747 10043 20747 10043 20748 10318 20748 10320 20748 10043 20749 10320 20749 10319 20749 10319 20750 10320 20750 10296 20750 10321 20751 10558 20751 10047 20751 10047 20752 10558 20752 10557 20752 10047 20753 10557 20753 10049 20753 10049 20754 10557 20754 10323 20754 10049 20755 10323 20755 10322 20755 10322 20756 10323 20756 10564 20756 10322 20757 10564 20757 10324 20757 10324 20758 10564 20758 10568 20758 10324 20759 10568 20759 10326 20759 10326 20760 10568 20760 10325 20760 10326 20761 10325 20761 10327 20761 10327 20762 10325 20762 10565 20762 10741 20763 10328 20763 10503 20763 10503 20764 10328 20764 10329 20764 10503 20765 10329 20765 10572 20765 10572 20766 10329 20766 10330 20766 10330 20767 10329 20767 10327 20767 10330 20768 10327 20768 10565 20768 10328 20769 10741 20769 10331 20769 10331 20770 10741 20770 10332 20770 10331 20771 10332 20771 10054 20771 10054 20772 10332 20772 10740 20772 10054 20773 10740 20773 10334 20773 10334 20774 10740 20774 10333 20774 10334 20775 10333 20775 10335 20775 10335 20776 10333 20776 10575 20776 10335 20777 10575 20777 10336 20777 10336 20778 10575 20778 10337 20778 10336 20779 10337 20779 10056 20779 10056 20780 10337 20780 10577 20780 10056 20781 10577 20781 10338 20781 10338 20782 10577 20782 749 20782 10062 20783 10059 20783 10339 20783 10339 20784 10059 20784 10579 20784 10062 20785 10339 20785 10340 20785 10340 20786 10339 20786 10599 20786 10340 20787 10599 20787 10341 20787 10341 20788 10599 20788 10559 20788 10341 20789 10559 20789 10321 20789 10321 20790 10559 20790 10558 20790 747 20791 748 20791 10342 20791 10342 20792 748 20792 10606 20792 10342 20793 10606 20793 10343 20793 10343 20794 10606 20794 10583 20794 10343 20795 10583 20795 10344 20795 10344 20796 10583 20796 10345 20796 10344 20797 10345 20797 10346 20797 10346 20798 10345 20798 10347 20798 10346 20799 10347 20799 10066 20799 10066 20800 10347 20800 10348 20800 10066 20801 10348 20801 10070 20801 10070 20802 10348 20802 10350 20802 10589 20803 10073 20803 10349 20803 10349 20804 10073 20804 10068 20804 10349 20805 10068 20805 10587 20805 10070 20806 10350 20806 10068 20806 10068 20807 10350 20807 10636 20807 10068 20808 10636 20808 10587 20808 10073 20809 10589 20809 10075 20809 10075 20810 10589 20810 10351 20810 10075 20811 10351 20811 10076 20811 10076 20812 10351 20812 10353 20812 10076 20813 10353 20813 10352 20813 10352 20814 10353 20814 10592 20814 10352 20815 10592 20815 10078 20815 10078 20816 10592 20816 10596 20816 10078 20817 10596 20817 10354 20817 10354 20818 10596 20818 10595 20818 10354 20819 10595 20819 10355 20819 10355 20820 10595 20820 10356 20820 10355 20821 10356 20821 10081 20821 10081 20822 10356 20822 10357 20822 10081 20823 10357 20823 10080 20823 10080 20824 10357 20824 10358 20824 10080 20825 10358 20825 10359 20825 10359 20826 10358 20826 10597 20826 10089 20827 10359 20827 10360 20827 10360 20828 10359 20828 10597 20828 10089 20829 10360 20829 10361 20829 10361 20830 10360 20830 10362 20830 10361 20831 10362 20831 10087 20831 10087 20832 10362 20832 10602 20832 10385 20833 10363 20833 10364 20833 10364 20834 10363 20834 10613 20834 10364 20835 10613 20835 10365 20835 10365 20836 10613 20836 10366 20836 10365 20837 10366 20837 743 20837 743 20838 10366 20838 744 20838 746 20839 10367 20839 10368 20839 10368 20840 10367 20840 10369 20840 10368 20841 10369 20841 10092 20841 10092 20842 10369 20842 10652 20842 10092 20843 10652 20843 10370 20843 10370 20844 10652 20844 10653 20844 10370 20845 10653 20845 10095 20845 10095 20846 10653 20846 10371 20846 10095 20847 10371 20847 10372 20847 10372 20848 10371 20848 10608 20848 10372 20849 10608 20849 10373 20849 10373 20850 10608 20850 10607 20850 10373 20851 10607 20851 10374 20851 10374 20852 10607 20852 10375 20852 10374 20853 10375 20853 10098 20853 10098 20854 10375 20854 10376 20854 10098 20855 10376 20855 10099 20855 10099 20856 10376 20856 10377 20856 10099 20857 10377 20857 10378 20857 10378 20858 10377 20858 10379 20858 10378 20859 10379 20859 10102 20859 10102 20860 10379 20860 10380 20860 10104 20861 10102 20861 10381 20861 10381 20862 10102 20862 10380 20862 10104 20863 10381 20863 10382 20863 10382 20864 10381 20864 10384 20864 10382 20865 10384 20865 10383 20865 10383 20866 10384 20866 10502 20866 10383 20867 10502 20867 10385 20867 10385 20868 10502 20868 10363 20868 10405 20869 10386 20869 10106 20869 10106 20870 10386 20870 10617 20870 10106 20871 10617 20871 10387 20871 10387 20872 10617 20872 10615 20872 10387 20873 10615 20873 10107 20873 10107 20874 10615 20874 10388 20874 10107 20875 10388 20875 10108 20875 10108 20876 10388 20876 10614 20876 10108 20877 10614 20877 10389 20877 10389 20878 10614 20878 10687 20878 10677 20879 10390 20879 10391 20879 10391 20880 10390 20880 10392 20880 10391 20881 10392 20881 10618 20881 10618 20882 10392 20882 741 20882 10618 20883 741 20883 742 20883 10390 20884 10677 20884 10393 20884 10393 20885 10677 20885 10394 20885 10393 20886 10394 20886 10111 20886 10111 20887 10394 20887 10603 20887 10111 20888 10603 20888 10112 20888 10112 20889 10603 20889 10395 20889 10112 20890 10395 20890 10114 20890 10114 20891 10395 20891 10396 20891 10114 20892 10396 20892 10397 20892 10397 20893 10396 20893 10612 20893 10397 20894 10612 20894 10398 20894 10398 20895 10612 20895 10623 20895 10399 20896 10402 20896 10622 20896 10622 20897 10402 20897 10116 20897 10622 20898 10116 20898 10400 20898 10398 20899 10623 20899 948 20899 948 20900 10623 20900 10400 20900 948 20901 10400 20901 10118 20901 10118 20902 10400 20902 10116 20902 10401 20903 10402 20903 10621 20903 10621 20904 10402 20904 10399 20904 10401 20905 10621 20905 10125 20905 10125 20906 10621 20906 10403 20906 10125 20907 10403 20907 10122 20907 10122 20908 10403 20908 10404 20908 10122 20909 10404 20909 10405 20909 10405 20910 10404 20910 10386 20910 739 20911 740 20911 10133 20911 10133 20912 740 20912 10620 20912 10133 20913 10620 20913 10131 20913 10131 20914 10620 20914 10406 20914 10131 20915 10406 20915 10407 20915 10407 20916 10406 20916 10408 20916 10407 20917 10408 20917 10128 20917 10128 20918 10408 20918 10625 20918 10128 20919 10625 20919 10126 20919 10126 20920 10625 20920 10601 20920 10126 20921 10601 20921 10409 20921 10409 20922 10601 20922 10410 20922 10409 20923 10410 20923 10411 20923 10411 20924 10410 20924 10600 20924 929 20925 10715 20925 10412 20925 10412 20926 10715 20926 10711 20926 10412 20927 10711 20927 10413 20927 10413 20928 10711 20928 10549 20928 10413 20929 10549 20929 10140 20929 10140 20930 10549 20930 10541 20930 10140 20931 10541 20931 10138 20931 10138 20932 10541 20932 10414 20932 10138 20933 10414 20933 10416 20933 10416 20934 10414 20934 10415 20934 10416 20935 10415 20935 10135 20935 10135 20936 10415 20936 729 20936 713 20937 10417 20937 10147 20937 10147 20938 10417 20938 10418 20938 10147 20939 10418 20939 10419 20939 10419 20940 10418 20940 10420 20940 10419 20941 10420 20941 10145 20941 10145 20942 10420 20942 10742 20942 10145 20943 10742 20943 10144 20943 10144 20944 10742 20944 10421 20944 10144 20945 10421 20945 10143 20945 10143 20946 10421 20946 10744 20946 10143 20947 10744 20947 10422 20947 10422 20948 10744 20948 10423 20948 10422 20949 10423 20949 928 20949 928 20950 10423 20950 10745 20950 10157 20951 705 20951 10159 20951 10159 20952 705 20952 10566 20952 10159 20953 10566 20953 10154 20953 10154 20954 10566 20954 10567 20954 10154 20955 10567 20955 10424 20955 10424 20956 10567 20956 10562 20956 10424 20957 10562 20957 10425 20957 10425 20958 10562 20958 10426 20958 10425 20959 10426 20959 10150 20959 10150 20960 10426 20960 10427 20960 10150 20961 10427 20961 703 20961 703 20962 10427 20962 10560 20962 10434 20963 10632 20963 10160 20963 10160 20964 10632 20964 10428 20964 10160 20965 10428 20965 10631 20965 702 20966 10590 20966 10165 20966 10165 20967 10590 20967 10430 20967 10165 20968 10430 20968 10429 20968 10429 20969 10430 20969 10588 20969 10429 20970 10588 20970 10432 20970 10432 20971 10588 20971 10431 20971 10432 20972 10431 20972 10433 20972 10433 20973 10431 20973 10635 20973 10433 20974 10635 20974 10161 20974 10161 20975 10635 20975 10634 20975 10161 20976 10634 20976 10434 20976 10434 20977 10634 20977 10435 20977 10434 20978 10435 20978 10632 20978 10445 20979 10447 20979 10436 20979 10436 20980 10447 20980 10639 20980 10436 20981 10639 20981 10638 20981 896 20982 10582 20982 10169 20982 10169 20983 10582 20983 10437 20983 10169 20984 10437 20984 10438 20984 10438 20985 10437 20985 10649 20985 10438 20986 10649 20986 10439 20986 10439 20987 10649 20987 10441 20987 10439 20988 10441 20988 10440 20988 10440 20989 10441 20989 10442 20989 10440 20990 10442 20990 10444 20990 10444 20991 10442 20991 10443 20991 10444 20992 10443 20992 10445 20992 10445 20993 10443 20993 10446 20993 10445 20994 10446 20994 10447 20994 10449 20995 10656 20995 10171 20995 10171 20996 10448 20996 10449 20996 10449 20997 10448 20997 10172 20997 10449 20998 10172 20998 10450 20998 10450 20999 10172 20999 10173 20999 10450 21000 10173 21000 10756 21000 10756 21001 10173 21001 10451 21001 10451 21002 10173 21002 10452 21002 10451 21003 10452 21003 10670 21003 10452 21004 10175 21004 10670 21004 10670 21005 10175 21005 10453 21005 10670 21006 10453 21006 10672 21006 890 21007 690 21007 10178 21007 10178 21008 690 21008 10658 21008 10178 21009 10658 21009 10454 21009 10454 21010 10658 21010 10672 21010 10454 21011 10672 21011 10455 21011 10455 21012 10672 21012 10453 21012 10667 21013 10456 21013 10457 21013 10457 21014 10181 21014 10667 21014 10667 21015 10181 21015 10458 21015 10667 21016 10458 21016 10459 21016 10458 21017 10182 21017 10459 21017 10459 21018 10182 21018 10460 21018 10459 21019 10460 21019 10673 21019 10673 21020 10460 21020 10461 21020 10673 21021 10461 21021 10754 21021 10461 21022 10462 21022 10754 21022 10754 21023 10462 21023 10183 21023 10754 21024 10183 21024 10463 21024 10463 21025 10183 21025 10184 21025 10463 21026 10184 21026 10464 21026 10464 21027 10184 21027 10185 21027 10464 21028 10185 21028 10675 21028 681 21029 10676 21029 10465 21029 10465 21030 10676 21030 10675 21030 10465 21031 10675 21031 10187 21031 10187 21032 10675 21032 10185 21032 10473 21033 873 21033 10472 21033 10191 21034 10466 21034 10467 21034 10467 21035 10466 21035 10468 21035 10467 21036 10468 21036 10469 21036 10469 21037 10468 21037 10680 21037 10469 21038 10680 21038 10188 21038 10188 21039 10680 21039 10470 21039 10188 21040 10470 21040 10471 21040 10471 21041 10470 21041 671 21041 10472 21042 10474 21042 10473 21042 10473 21043 10474 21043 10753 21043 10473 21044 10753 21044 10191 21044 10191 21045 10753 21045 10752 21045 10191 21046 10752 21046 10466 21046 10196 21047 10692 21047 10694 21047 10196 21048 10694 21048 10475 21048 663 21049 662 21049 10476 21049 10476 21050 662 21050 10478 21050 10476 21051 10478 21051 10477 21051 10477 21052 10478 21052 10194 21052 10477 21053 10194 21053 10479 21053 10479 21054 10194 21054 10195 21054 10479 21055 10195 21055 10481 21055 10481 21056 10195 21056 10480 21056 10481 21057 10480 21057 10684 21057 10684 21058 10480 21058 10475 21058 10684 21059 10475 21059 10685 21059 10685 21060 10475 21060 10694 21060 10203 21061 10483 21061 10482 21061 10482 21062 10483 21062 10484 21062 10482 21063 10484 21063 10485 21063 10485 21064 10484 21064 10513 21064 10485 21065 10513 21065 10200 21065 10200 21066 10513 21066 10486 21066 10200 21067 10486 21067 10199 21067 10199 21068 10486 21068 10695 21068 10199 21069 10695 21069 10198 21069 10198 21070 10695 21070 10487 21070 10198 21071 10487 21071 10488 21071 10488 21072 10487 21072 10536 21072 10208 21073 643 21073 10206 21073 10206 21074 643 21074 10700 21074 10206 21075 10700 21075 10205 21075 10205 21076 10700 21076 10489 21076 10205 21077 10489 21077 10491 21077 10491 21078 10489 21078 10490 21078 10491 21079 10490 21079 10204 21079 10204 21080 10490 21080 10706 21080 10204 21081 10706 21081 10492 21081 10492 21082 10706 21082 10705 21082 10492 21083 10705 21083 10493 21083 10493 21084 10705 21084 649 21084 830 21085 10495 21085 10494 21085 10494 21086 10495 21086 10707 21086 10494 21087 10707 21087 10496 21087 10496 21088 10707 21088 10551 21088 10496 21089 10551 21089 10213 21089 10213 21090 10551 21090 10546 21090 10213 21091 10546 21091 10211 21091 10211 21092 10546 21092 10547 21092 10211 21093 10547 21093 10210 21093 10210 21094 10547 21094 10548 21094 10210 21095 10548 21095 837 21095 837 21096 10548 21096 639 21096 10497 21097 733 21097 621 21097 10709 21098 637 21098 625 21098 624 21099 10498 21099 625 21099 660 21100 10534 21100 10524 21100 664 21101 10499 21101 10518 21101 10500 21102 10512 21102 10683 21102 10466 21103 10752 21103 10751 21103 10674 21104 10679 21104 10751 21104 10673 21105 10754 21105 10662 21105 10450 21106 10756 21106 10760 21106 10442 21107 10644 21107 10443 21107 10447 21108 10446 21108 10584 21108 10626 21109 735 21109 10501 21109 10502 21110 10609 21110 10623 21110 10379 21111 10377 21111 10624 21111 10603 21112 10394 21112 10604 21112 10503 21113 10743 21113 10741 21113 10559 21114 10599 21114 10594 21114 10315 21115 10313 21115 10628 21115 10296 21116 10320 21116 10501 21116 781 21117 10519 21117 10532 21117 10504 21118 10506 21118 10619 21118 10505 21119 10678 21119 10510 21119 10506 21120 802 21120 10391 21120 10391 21121 802 21121 10507 21121 10391 21122 10507 21122 10677 21122 10677 21123 10507 21123 804 21123 10238 21124 10508 21124 10237 21124 10237 21125 10508 21125 10509 21125 10237 21126 10509 21126 10510 21126 10510 21127 10509 21127 674 21127 10510 21128 674 21128 10505 21128 10747 21129 10682 21129 10500 21129 10500 21130 10682 21130 10240 21130 10511 21131 10512 21131 799 21131 799 21132 10512 21132 10500 21132 799 21133 10500 21133 10241 21133 10241 21134 10500 21134 10240 21134 631 21135 635 21135 10483 21135 10483 21136 635 21136 10515 21136 10486 21137 797 21137 10695 21137 10695 21138 797 21138 10696 21138 10515 21139 791 21139 793 21139 793 21140 10513 21140 10515 21140 10515 21141 10513 21141 10484 21141 10515 21142 10484 21142 10483 21142 793 21143 794 21143 10513 21143 10513 21144 794 21144 10514 21144 10513 21145 10514 21145 10486 21145 10486 21146 10514 21146 796 21146 10486 21147 796 21147 797 21147 791 21148 10515 21148 10516 21148 10516 21149 10515 21149 10691 21149 10516 21150 10691 21150 10690 21150 10517 21151 10245 21151 10518 21151 10518 21152 10245 21152 10689 21152 10518 21153 10689 21153 667 21153 10519 21154 785 21154 10520 21154 785 21155 790 21155 10520 21155 10520 21156 790 21156 10521 21156 10520 21157 10521 21157 10288 21157 10288 21158 10521 21158 10250 21158 10288 21159 10250 21159 10252 21159 10697 21160 10522 21160 626 21160 626 21161 10522 21161 629 21161 10252 21162 10253 21162 10534 21162 10534 21163 10253 21163 10523 21163 10534 21164 10523 21164 10524 21164 10524 21165 10523 21165 10525 21165 10524 21166 10525 21166 658 21166 658 21167 10525 21167 10258 21167 10628 21168 10285 21168 10629 21168 10294 21169 740 21169 10295 21169 10295 21170 740 21170 10526 21170 10295 21171 10526 21171 10527 21171 10527 21172 10526 21172 10627 21172 10527 21173 10627 21173 10283 21173 10552 21174 10528 21174 10553 21174 10628 21175 10313 21175 10285 21175 10285 21176 10313 21176 10312 21176 10285 21177 10312 21177 10529 21177 10529 21178 10312 21178 10311 21178 10529 21179 10311 21179 10530 21179 10530 21180 10311 21180 752 21180 10530 21181 752 21181 10554 21181 10554 21182 752 21182 751 21182 10554 21183 751 21183 10531 21183 10489 21184 10700 21184 10532 21184 10519 21185 10520 21185 10532 21185 10532 21186 10520 21186 10490 21186 10532 21187 10490 21187 10489 21187 10533 21188 755 21188 10539 21188 10252 21189 10534 21189 10288 21189 10288 21190 10534 21190 660 21190 10288 21191 660 21191 10535 21191 10535 21192 660 21192 10536 21192 10535 21193 10536 21193 10291 21193 10291 21194 10536 21194 10487 21194 10291 21195 10487 21195 755 21195 10294 21196 10537 21196 740 21196 740 21197 10537 21197 10538 21197 740 21198 10538 21198 10616 21198 10616 21199 10538 21199 10292 21199 10616 21200 10292 21200 10539 21200 10539 21201 10292 21201 10540 21201 10539 21202 10540 21202 10533 21202 10577 21203 10337 21203 10298 21203 10298 21204 10337 21204 10576 21204 10298 21205 10576 21205 10299 21205 10299 21206 10576 21206 10544 21206 10304 21207 10302 21207 10549 21207 10414 21208 10544 21208 10415 21208 10415 21209 10544 21209 10728 21209 10415 21210 10728 21210 729 21210 10549 21211 10302 21211 10541 21211 10541 21212 10302 21212 10542 21212 10541 21213 10542 21213 10414 21213 10414 21214 10542 21214 10543 21214 10414 21215 10543 21215 10544 21215 10544 21216 10543 21216 10545 21216 10544 21217 10545 21217 10299 21217 10546 21218 10550 21218 10547 21218 10547 21219 10550 21219 10305 21219 10547 21220 10305 21220 10548 21220 10548 21221 10305 21221 10304 21221 10548 21222 10304 21222 10711 21222 10711 21223 10304 21223 10549 21223 10498 21224 10552 21224 10551 21224 10546 21225 10551 21225 10550 21225 10550 21226 10551 21226 10552 21226 10550 21227 10552 21227 10531 21227 10531 21228 10552 21228 10553 21228 10531 21229 10553 21229 10554 21229 10320 21230 10318 21230 10501 21230 10501 21231 10318 21231 10555 21231 10501 21232 10555 21232 10628 21232 10628 21233 10555 21233 10556 21233 10628 21234 10556 21234 10315 21234 10564 21235 10323 21235 10563 21235 10563 21236 10323 21236 10557 21236 10563 21237 10557 21237 10594 21237 10594 21238 10557 21238 10558 21238 10594 21239 10558 21239 10559 21239 10427 21240 10561 21240 10560 21240 10560 21241 10561 21241 614 21241 10560 21242 614 21242 704 21242 10427 21243 10426 21243 10561 21243 10561 21244 10426 21244 10562 21244 10561 21245 10562 21245 10563 21245 10563 21246 10562 21246 10567 21246 10563 21247 10567 21247 10564 21247 706 21248 10330 21248 705 21248 705 21249 10330 21249 10565 21249 705 21250 10565 21250 10566 21250 10566 21251 10565 21251 10325 21251 10566 21252 10325 21252 10567 21252 10567 21253 10325 21253 10568 21253 10567 21254 10568 21254 10564 21254 619 21255 10569 21255 613 21255 613 21256 10569 21256 711 21256 613 21257 711 21257 612 21257 10573 21258 708 21258 10570 21258 10570 21259 708 21259 709 21259 10570 21260 709 21260 10273 21260 10273 21261 709 21261 10569 21261 10273 21262 10569 21262 10574 21262 10574 21263 10569 21263 619 21263 758 21264 10743 21264 10280 21264 10280 21265 10743 21265 10503 21265 10280 21266 10503 21266 10571 21266 10571 21267 10503 21267 10572 21267 10571 21268 10572 21268 10277 21268 10277 21269 10572 21269 10330 21269 10277 21270 10330 21270 10573 21270 10573 21271 10330 21271 706 21271 10573 21272 706 21272 708 21272 758 21273 759 21273 10743 21273 10743 21274 759 21274 761 21274 10743 21275 761 21275 618 21275 761 21276 762 21276 618 21276 618 21277 762 21277 765 21277 618 21278 765 21278 619 21278 619 21279 765 21279 766 21279 619 21280 766 21280 10574 21280 10337 21281 10575 21281 10576 21281 10576 21282 10575 21282 10333 21282 10576 21283 10333 21283 10544 21283 10544 21284 10333 21284 10740 21284 10298 21285 10296 21285 10577 21285 10577 21286 10296 21286 10501 21286 10577 21287 10501 21287 749 21287 749 21288 10501 21288 10578 21288 10578 21289 10501 21289 735 21289 10578 21290 735 21290 10579 21290 10580 21291 10636 21291 695 21291 695 21292 10636 21292 10350 21292 695 21293 10350 21293 10581 21293 10581 21294 10350 21294 10348 21294 10581 21295 10348 21295 10582 21295 10582 21296 10348 21296 10347 21296 10582 21297 10347 21297 10642 21297 10642 21298 10347 21298 10345 21298 10642 21299 10345 21299 10583 21299 10762 21300 10586 21300 10584 21300 10584 21301 10586 21301 10218 21301 10584 21302 10218 21302 10219 21302 826 21303 827 21303 10585 21303 10585 21304 827 21304 829 21304 10585 21305 829 21305 10762 21305 10762 21306 829 21306 10216 21306 10762 21307 10216 21307 10586 21307 823 21308 825 21308 10587 21308 10587 21309 825 21309 826 21309 826 21310 10585 21310 10587 21310 10587 21311 10585 21311 10431 21311 10587 21312 10431 21312 10349 21312 10431 21313 10588 21313 10349 21313 10349 21314 10588 21314 10430 21314 10349 21315 10430 21315 10589 21315 10589 21316 10430 21316 10590 21316 10589 21317 10590 21317 10351 21317 10351 21318 10590 21318 701 21318 10351 21319 701 21319 10353 21319 10353 21320 701 21320 10591 21320 10353 21321 10591 21321 10592 21321 10596 21322 10592 21322 10563 21322 10563 21323 10592 21323 10591 21323 10563 21324 10591 21324 10561 21324 10561 21325 10591 21325 699 21325 10561 21326 699 21326 10593 21326 10358 21327 10357 21327 10594 21327 10594 21328 10357 21328 10356 21328 10594 21329 10356 21329 10563 21329 10563 21330 10356 21330 10595 21330 10563 21331 10595 21331 10596 21331 10360 21332 10597 21332 10410 21332 10410 21333 10597 21333 10600 21333 10579 21334 735 21334 10339 21334 10339 21335 735 21335 10598 21335 10339 21336 10598 21336 10599 21336 10599 21337 10598 21337 10600 21337 10599 21338 10600 21338 10594 21338 10594 21339 10600 21339 10597 21339 10594 21340 10597 21340 10358 21340 10624 21341 748 21341 10602 21341 10360 21342 10410 21342 10362 21342 10362 21343 10410 21343 10601 21343 10362 21344 10601 21344 10602 21344 10603 21345 10604 21345 10395 21345 10679 21346 680 21346 10604 21346 10604 21347 680 21347 679 21347 10604 21348 679 21348 10610 21348 10369 21349 10367 21349 10605 21349 10624 21350 10377 21350 748 21350 748 21351 10377 21351 10376 21351 748 21352 10376 21352 10606 21352 10606 21353 10376 21353 10375 21353 10606 21354 10375 21354 10583 21354 10583 21355 10375 21355 10607 21355 10583 21356 10607 21356 10642 21356 10642 21357 10607 21357 10608 21357 10642 21358 10608 21358 10371 21358 10502 21359 10384 21359 10609 21359 10609 21360 10384 21360 10381 21360 10609 21361 10381 21361 10624 21361 10624 21362 10381 21362 10380 21362 10624 21363 10380 21363 10379 21363 10605 21364 10367 21364 10610 21364 10610 21365 10367 21365 10611 21365 10610 21366 10611 21366 10604 21366 10604 21367 10611 21367 745 21367 10604 21368 745 21368 10395 21368 10395 21369 745 21369 744 21369 10395 21370 744 21370 10396 21370 10396 21371 744 21371 10366 21371 10396 21372 10366 21372 10612 21372 10612 21373 10366 21373 10613 21373 10612 21374 10613 21374 10623 21374 10623 21375 10613 21375 10363 21375 10623 21376 10363 21376 10502 21376 10687 21377 10614 21377 10539 21377 10614 21378 10388 21378 10539 21378 10539 21379 10388 21379 10615 21379 10539 21380 10615 21380 10616 21380 10616 21381 10615 21381 10617 21381 10616 21382 10617 21382 740 21382 740 21383 10617 21383 10386 21383 740 21384 10386 21384 10404 21384 10506 21385 10391 21385 10619 21385 10619 21386 10391 21386 10618 21386 10619 21387 10618 21387 10686 21387 10404 21388 10403 21388 740 21388 740 21389 10403 21389 10621 21389 740 21390 10621 21390 10620 21390 10620 21391 10621 21391 10399 21391 10620 21392 10399 21392 10406 21392 10406 21393 10399 21393 10622 21393 10406 21394 10622 21394 10609 21394 10609 21395 10622 21395 10400 21395 10609 21396 10400 21396 10623 21396 10602 21397 10601 21397 10624 21397 10624 21398 10601 21398 10625 21398 10624 21399 10625 21399 10609 21399 10609 21400 10625 21400 10408 21400 10609 21401 10408 21401 10406 21401 10626 21402 10501 21402 738 21402 738 21403 10501 21403 10628 21403 738 21404 10628 21404 10627 21404 10627 21405 10628 21405 10629 21405 10627 21406 10629 21406 10283 21406 10428 21407 10630 21407 10631 21407 10631 21408 10630 21408 10561 21408 10631 21409 10561 21409 696 21409 696 21410 10561 21410 10593 21410 10632 21411 10435 21411 10633 21411 10633 21412 10435 21412 10634 21412 10633 21413 10634 21413 10585 21413 10585 21414 10634 21414 10635 21414 10585 21415 10635 21415 10431 21415 823 21416 10587 21416 820 21416 820 21417 10587 21417 10636 21417 820 21418 10636 21418 10222 21418 10222 21419 10636 21419 10580 21419 10222 21420 10580 21420 10637 21420 10637 21421 10580 21421 692 21421 10637 21422 692 21422 10220 21422 10220 21423 692 21423 691 21423 10220 21424 691 21424 10219 21424 10219 21425 691 21425 10638 21425 10219 21426 10638 21426 10584 21426 10584 21427 10638 21427 10639 21427 10584 21428 10639 21428 10447 21428 10760 21429 10645 21429 10654 21429 10654 21430 10645 21430 10640 21430 10654 21431 10640 21431 10227 21431 10441 21432 10649 21432 10643 21432 10227 21433 10641 21433 10654 21433 10654 21434 10641 21434 813 21434 10654 21435 813 21435 10642 21435 10642 21436 813 21436 814 21436 10442 21437 10441 21437 10644 21437 10644 21438 10441 21438 10643 21438 10644 21439 10643 21439 10757 21439 10757 21440 10643 21440 10224 21440 10757 21441 10224 21441 10645 21441 10645 21442 10224 21442 10225 21442 10645 21443 10225 21443 10640 21443 814 21444 10646 21444 10642 21444 10642 21445 10646 21445 817 21445 10642 21446 817 21446 10582 21446 10582 21447 817 21447 10647 21447 10582 21448 10647 21448 10437 21448 10437 21449 10647 21449 10648 21449 10437 21450 10648 21450 10649 21450 10649 21451 10648 21451 10650 21451 10649 21452 10650 21452 10643 21452 10605 21453 10651 21453 10369 21453 10369 21454 10651 21454 689 21454 10369 21455 689 21455 10652 21455 10652 21456 689 21456 687 21456 10652 21457 687 21457 10653 21457 10653 21458 687 21458 685 21458 10653 21459 685 21459 10371 21459 10371 21460 685 21460 683 21460 10371 21461 683 21461 10642 21461 10642 21462 683 21462 10655 21462 10642 21463 10655 21463 10654 21463 10654 21464 10655 21464 10656 21464 10654 21465 10656 21465 10760 21465 10760 21466 10656 21466 10449 21466 10760 21467 10449 21467 10450 21467 10663 21468 10671 21468 10657 21468 10657 21469 10671 21469 10658 21469 10657 21470 10658 21470 10659 21470 10659 21471 10658 21471 811 21471 10660 21472 10662 21472 10661 21472 10661 21473 10662 21473 10755 21473 10661 21474 10755 21474 10664 21474 10664 21475 10755 21475 10663 21475 10664 21476 10663 21476 10232 21476 10232 21477 10663 21477 10657 21477 811 21478 10658 21478 809 21478 809 21479 10658 21479 690 21479 809 21480 690 21480 10665 21480 10668 21481 10456 21481 10666 21481 10666 21482 10456 21482 10667 21482 10666 21483 10667 21483 10660 21483 10668 21484 10669 21484 10456 21484 10456 21485 10669 21485 805 21485 10456 21486 805 21486 10651 21486 10651 21487 805 21487 10665 21487 10651 21488 10665 21488 689 21488 689 21489 10665 21489 690 21489 10451 21490 10670 21490 10671 21490 10671 21491 10670 21491 10672 21491 10671 21492 10672 21492 10658 21492 10660 21493 10667 21493 10662 21493 10662 21494 10667 21494 10459 21494 10662 21495 10459 21495 10673 21495 10463 21496 10464 21496 10674 21496 10674 21497 10464 21497 10675 21497 10674 21498 10675 21498 10679 21498 10679 21499 10675 21499 10676 21499 10679 21500 10676 21500 680 21500 804 21501 10510 21501 10677 21501 10677 21502 10510 21502 10678 21502 10677 21503 10678 21503 10394 21503 10394 21504 10678 21504 673 21504 10394 21505 673 21505 10604 21505 10604 21506 673 21506 671 21506 10604 21507 671 21507 10679 21507 671 21508 10470 21508 10679 21508 10679 21509 10470 21509 10680 21509 10679 21510 10680 21510 10751 21510 10751 21511 10680 21511 10468 21511 10751 21512 10468 21512 10466 21512 10472 21513 10681 21513 10474 21513 10474 21514 10681 21514 10753 21514 10238 21515 10682 21515 10508 21515 10508 21516 10682 21516 10747 21516 10508 21517 10747 21517 10472 21517 10472 21518 10747 21518 10746 21518 10472 21519 10746 21519 10681 21519 10512 21520 10477 21520 10479 21520 10512 21521 10479 21521 10683 21521 10683 21522 10479 21522 10481 21522 10683 21523 10481 21523 10749 21523 10749 21524 10481 21524 10684 21524 10749 21525 10684 21525 10685 21525 10511 21526 10504 21526 10512 21526 10512 21527 10504 21527 10619 21527 10512 21528 10619 21528 10477 21528 10477 21529 10619 21529 10686 21529 10477 21530 10686 21530 10476 21530 10476 21531 10686 21531 10618 21531 10476 21532 10618 21532 663 21532 663 21533 10618 21533 742 21533 663 21534 742 21534 664 21534 664 21535 742 21535 10687 21535 664 21536 10687 21536 10499 21536 10499 21537 10687 21537 10539 21537 10499 21538 10539 21538 10518 21538 10518 21539 10539 21539 10688 21539 10518 21540 10688 21540 10517 21540 667 21541 10689 21541 668 21541 668 21542 10689 21542 10246 21542 668 21543 10246 21543 669 21543 669 21544 10246 21544 10690 21544 669 21545 10690 21545 670 21545 670 21546 10690 21546 10691 21546 670 21547 10691 21547 10692 21547 10692 21548 10691 21548 10693 21548 10692 21549 10693 21549 10694 21549 755 21550 10487 21550 10539 21550 10539 21551 10487 21551 10695 21551 10539 21552 10695 21552 10688 21552 10688 21553 10695 21553 10696 21553 10688 21554 10696 21554 10517 21554 10258 21555 10697 21555 658 21555 658 21556 10697 21556 626 21556 658 21557 626 21557 657 21557 657 21558 626 21558 632 21558 657 21559 632 21559 655 21559 655 21560 632 21560 10698 21560 655 21561 10698 21561 10699 21561 10699 21562 10698 21562 652 21562 10522 21563 781 21563 629 21563 629 21564 781 21564 10532 21564 629 21565 10532 21565 630 21565 630 21566 10532 21566 10700 21566 630 21567 10700 21567 610 21567 610 21568 10700 21568 643 21568 610 21569 643 21569 10701 21569 10701 21570 643 21570 642 21570 10701 21571 642 21571 622 21571 646 21572 10702 21572 624 21572 624 21573 10702 21573 10703 21573 624 21574 10703 21574 10498 21574 10703 21575 648 21575 10498 21575 10498 21576 648 21576 10704 21576 10498 21577 10704 21577 10552 21577 10552 21578 10704 21578 649 21578 10552 21579 649 21579 10528 21579 10528 21580 649 21580 10705 21580 10528 21581 10705 21581 10520 21581 10520 21582 10705 21582 10706 21582 10520 21583 10706 21583 10490 21583 10551 21584 10707 21584 10498 21584 10498 21585 10707 21585 10495 21585 10498 21586 10495 21586 625 21586 625 21587 10495 21587 10708 21587 625 21588 10708 21588 10709 21588 773 21589 10710 21589 10266 21589 10266 21590 10710 21590 639 21590 10266 21591 639 21591 10264 21591 10264 21592 639 21592 10548 21592 10264 21593 10548 21593 10263 21593 10263 21594 10548 21594 10711 21594 10263 21595 10711 21595 10261 21595 10721 21596 621 21596 10712 21596 10712 21597 621 21597 10713 21597 10712 21598 10713 21598 10714 21598 10261 21599 10711 21599 10259 21599 10259 21600 10711 21600 10715 21600 10259 21601 10715 21601 778 21601 778 21602 10715 21602 10722 21602 778 21603 10722 21603 10721 21603 773 21604 775 21604 10710 21604 10710 21605 775 21605 10716 21605 10710 21606 10716 21606 10720 21606 638 21607 10717 21607 611 21607 611 21608 10717 21608 10719 21608 611 21609 10719 21609 10718 21609 10718 21610 10719 21610 10710 21610 10718 21611 10710 21611 10713 21611 10713 21612 10710 21612 10720 21612 10713 21613 10720 21613 10714 21613 10721 21614 10722 21614 621 21614 621 21615 10722 21615 728 21615 621 21616 728 21616 10497 21616 730 21617 10729 21617 10723 21617 10723 21618 10729 21618 732 21618 715 21619 719 21619 10724 21619 10724 21620 719 21620 10725 21620 10724 21621 10725 21621 723 21621 10726 21622 10727 21622 10544 21622 10544 21623 10727 21623 10270 21623 10544 21624 10270 21624 10728 21624 10728 21625 10270 21625 767 21625 10728 21626 767 21626 10731 21626 730 21627 729 21627 10729 21627 10729 21628 729 21628 10728 21628 10729 21629 10728 21629 10730 21629 10730 21630 10728 21630 10731 21630 10730 21631 10731 21631 10735 21631 10726 21632 10417 21632 10732 21632 10732 21633 10417 21633 714 21633 10732 21634 714 21634 10733 21634 10733 21635 714 21635 715 21635 10733 21636 715 21636 772 21636 772 21637 715 21637 10724 21637 772 21638 10724 21638 10734 21638 10734 21639 10724 21639 10737 21639 10735 21640 10736 21640 10730 21640 10730 21641 10736 21641 10738 21641 10730 21642 10738 21642 10737 21642 10737 21643 10738 21643 10739 21643 10737 21644 10739 21644 10734 21644 10726 21645 10544 21645 10417 21645 10417 21646 10544 21646 10740 21646 10417 21647 10740 21647 10418 21647 10418 21648 10740 21648 10332 21648 10418 21649 10332 21649 10420 21649 10420 21650 10332 21650 10741 21650 10420 21651 10741 21651 10742 21651 10742 21652 10741 21652 10743 21652 10742 21653 10743 21653 10421 21653 10421 21654 10743 21654 618 21654 10421 21655 618 21655 10744 21655 722 21656 721 21656 616 21656 616 21657 721 21657 10745 21657 616 21658 10745 21658 618 21658 618 21659 10745 21659 10423 21659 618 21660 10423 21660 10744 21660 10671 21661 10663 21661 11 21661 10463 21662 10674 21662 1 21662 1 21663 10674 21663 10750 21663 10515 21664 633 21664 10691 21664 10691 21665 633 21665 23 21665 10691 21666 23 21666 10693 21666 10749 21667 23 21667 10748 21667 10749 21668 10685 21668 23 21668 23 21669 10685 21669 10694 21669 23 21670 10694 21670 10693 21670 17 21671 10681 21671 10746 21671 10746 21672 10747 21672 17 21672 17 21673 10747 21673 10500 21673 17 21674 10500 21674 10748 21674 10748 21675 10500 21675 10683 21675 10748 21676 10683 21676 10749 21676 10674 21677 10751 21677 10750 21677 10750 21678 10751 21678 10752 21678 10750 21679 10752 21679 17 21679 17 21680 10752 21680 10753 21680 17 21681 10753 21681 10681 21681 10463 21682 1 21682 10754 21682 10754 21683 1 21683 13 21683 10754 21684 13 21684 10662 21684 11 21685 10663 21685 13 21685 13 21686 10663 21686 10755 21686 13 21687 10755 21687 10662 21687 10671 21688 11 21688 10451 21688 10451 21689 11 21689 10759 21689 10451 21690 10759 21690 10756 21690 10644 21691 10757 21691 10758 21691 10758 21692 10757 21692 10645 21692 10758 21693 10645 21693 10759 21693 10759 21694 10645 21694 10760 21694 10759 21695 10760 21695 10756 21695 10644 21696 10758 21696 10443 21696 10443 21697 10758 21697 10761 21697 10443 21698 10761 21698 10446 21698 10428 21699 10632 21699 10763 21699 10632 21700 10633 21700 10763 21700 10763 21701 10633 21701 10585 21701 10763 21702 10585 21702 6 21702 6 21703 10585 21703 10762 21703 6 21704 10762 21704 10761 21704 10761 21705 10762 21705 10584 21705 10761 21706 10584 21706 10446 21706 12012 21707 10561 21707 10763 21707 10763 21708 10561 21708 10630 21708 10763 21709 10630 21709 10428 21709 609 21710 10764 21710 10766 21710 10766 21711 10764 21711 10765 21711 10766 21712 10765 21712 10767 21712 10767 21713 10765 21713 10769 21713 10769 21714 10765 21714 10768 21714 10769 21715 10768 21715 4071 21715 4071 21716 10768 21716 4068 21716 4068 21717 10768 21717 10867 21717 4068 21718 10867 21718 4069 21718 4069 21719 10867 21719 4067 21719 4067 21720 10867 21720 10869 21720 4067 21721 10869 21721 10770 21721 10770 21722 10869 21722 10771 21722 10771 21723 10869 21723 10772 21723 10771 21724 10772 21724 4064 21724 4064 21725 10772 21725 4063 21725 4063 21726 10772 21726 502 21726 4063 21727 502 21727 4062 21727 4040 21728 10872 21728 4072 21728 4072 21729 10872 21729 10874 21729 4072 21730 10874 21730 4074 21730 4074 21731 10874 21731 10875 21731 4074 21732 10875 21732 10773 21732 10773 21733 10875 21733 10877 21733 10773 21734 10877 21734 4075 21734 4075 21735 10877 21735 10879 21735 4075 21736 10879 21736 4076 21736 4076 21737 10879 21737 10775 21737 4076 21738 10775 21738 10774 21738 10774 21739 10775 21739 492 21739 10776 21740 10777 21740 10778 21740 10778 21741 10777 21741 10889 21741 10778 21742 10889 21742 10779 21742 10779 21743 10889 21743 10891 21743 10779 21744 10891 21744 10781 21744 10781 21745 10891 21745 10780 21745 10781 21746 10780 21746 4086 21746 4086 21747 10780 21747 10887 21747 4086 21748 10887 21748 4085 21748 4085 21749 10887 21749 10886 21749 4085 21750 10886 21750 4083 21750 4083 21751 10886 21751 10782 21751 4083 21752 10782 21752 4081 21752 4081 21753 10782 21753 10885 21753 4081 21754 10885 21754 4080 21754 4080 21755 10885 21755 10883 21755 4080 21756 10883 21756 10783 21756 10783 21757 10883 21757 10784 21757 10783 21758 10784 21758 10785 21758 10785 21759 10784 21759 10786 21759 10785 21760 10786 21760 4078 21760 4078 21761 10786 21761 10882 21761 4078 21762 10882 21762 4077 21762 4077 21763 10882 21763 588 21763 10787 21764 477 21764 10788 21764 10788 21765 477 21765 10789 21765 10788 21766 10789 21766 4096 21766 4096 21767 10789 21767 10790 21767 10790 21768 10789 21768 10791 21768 10790 21769 10791 21769 4095 21769 4095 21770 10791 21770 10792 21770 10792 21771 10791 21771 10794 21771 10792 21772 10794 21772 4091 21772 4091 21773 10794 21773 10793 21773 10793 21774 10794 21774 10894 21774 10793 21775 10894 21775 4093 21775 4093 21776 10894 21776 10795 21776 10795 21777 10894 21777 10895 21777 10795 21778 10895 21778 10796 21778 10796 21779 10895 21779 10797 21779 10797 21780 10895 21780 10896 21780 10797 21781 10896 21781 4022 21781 4097 21782 566 21782 10798 21782 10798 21783 566 21783 10897 21783 10798 21784 10897 21784 4099 21784 4099 21785 10897 21785 10899 21785 4099 21786 10899 21786 4101 21786 4101 21787 10899 21787 10799 21787 4101 21788 10799 21788 4102 21788 4102 21789 10799 21789 10800 21789 4102 21790 10800 21790 4104 21790 4104 21791 10800 21791 10801 21791 4104 21792 10801 21792 4014 21792 4014 21793 10801 21793 10902 21793 4109 21794 10802 21794 10904 21794 4109 21795 10904 21795 4111 21795 4111 21796 10904 21796 10803 21796 4111 21797 10803 21797 4112 21797 4112 21798 10803 21798 4113 21798 4113 21799 10803 21799 10804 21799 4113 21800 10804 21800 4107 21800 4107 21801 10804 21801 10805 21801 10805 21802 10804 21802 10907 21802 10805 21803 10907 21803 4108 21803 4108 21804 10907 21804 10806 21804 10806 21805 10907 21805 10807 21805 10806 21806 10807 21806 4105 21806 4105 21807 10807 21807 10910 21807 4105 21808 10910 21808 10808 21808 10808 21809 10910 21809 456 21809 10808 21810 456 21810 10809 21810 545 21811 10810 21811 10811 21811 10811 21812 10810 21812 10812 21812 10811 21813 10812 21813 4116 21813 4116 21814 10812 21814 10813 21814 4116 21815 10813 21815 10814 21815 10814 21816 10813 21816 10815 21816 10814 21817 10815 21817 10816 21817 10816 21818 10815 21818 10817 21818 10816 21819 10817 21819 10818 21819 10818 21820 10817 21820 10913 21820 10818 21821 10913 21821 10819 21821 10819 21822 10913 21822 10820 21822 10819 21823 10820 21823 4001 21823 4001 21824 10820 21824 10821 21824 4120 21825 450 21825 10822 21825 10822 21826 450 21826 10915 21826 10822 21827 10915 21827 4123 21827 4123 21828 10915 21828 10917 21828 4123 21829 10917 21829 10823 21829 10823 21830 10917 21830 10824 21830 10823 21831 10824 21831 4125 21831 4125 21832 10824 21832 10825 21832 4125 21833 10825 21833 4126 21833 4126 21834 10825 21834 10826 21834 4126 21835 10826 21835 4128 21835 4128 21836 10826 21836 10828 21836 4128 21837 10828 21837 10827 21837 10827 21838 10828 21838 539 21838 4129 21839 10829 21839 4131 21839 4131 21840 10829 21840 10830 21840 4131 21841 10830 21841 10831 21841 10831 21842 10830 21842 10924 21842 10831 21843 10924 21843 4132 21843 4132 21844 10924 21844 10833 21844 4132 21845 10833 21845 10832 21845 10832 21846 10833 21846 10925 21846 10832 21847 10925 21847 10834 21847 10834 21848 10925 21848 10835 21848 10834 21849 10835 21849 4133 21849 4133 21850 10835 21850 10928 21850 4133 21851 10928 21851 4135 21851 4135 21852 10928 21852 531 21852 530 21853 439 21853 10836 21853 530 21854 10836 21854 10837 21854 10837 21855 10836 21855 10838 21855 10837 21856 10838 21856 10839 21856 10839 21857 10838 21857 4145 21857 4145 21858 10838 21858 10840 21858 4145 21859 10840 21859 4143 21859 4143 21860 10840 21860 10841 21860 10841 21861 10840 21861 10930 21861 10841 21862 10930 21862 4140 21862 4140 21863 10930 21863 4141 21863 4141 21864 10930 21864 10842 21864 4141 21865 10842 21865 4142 21865 4142 21866 10842 21866 10843 21866 4142 21867 10843 21867 4138 21867 4138 21868 10843 21868 10844 21868 4138 21869 10844 21869 4136 21869 10845 21870 10846 21870 10847 21870 10847 21871 10846 21871 10931 21871 10847 21872 10931 21872 4154 21872 4154 21873 10931 21873 4155 21873 4155 21874 10931 21874 10933 21874 4155 21875 10933 21875 4156 21875 4156 21876 10933 21876 4152 21876 4152 21877 10933 21877 10850 21877 4152 21878 10850 21878 10848 21878 10848 21879 10850 21879 10849 21879 10849 21880 10850 21880 10853 21880 10849 21881 10853 21881 10851 21881 10851 21882 10853 21882 10852 21882 10852 21883 10853 21883 10856 21883 10852 21884 10856 21884 10854 21884 10854 21885 10856 21885 10855 21885 10855 21886 10856 21886 516 21886 10855 21887 516 21887 515 21887 514 21888 11037 21888 10857 21888 10857 21889 11037 21889 11038 21889 10857 21890 11038 21890 4166 21890 4166 21891 11038 21891 4167 21891 4167 21892 11038 21892 10858 21892 4167 21893 10858 21893 4164 21893 4164 21894 10858 21894 4165 21894 4165 21895 10858 21895 10859 21895 4165 21896 10859 21896 10860 21896 10860 21897 10859 21897 4162 21897 4162 21898 10859 21898 10861 21898 4162 21899 10861 21899 4163 21899 4163 21900 10861 21900 10862 21900 10862 21901 10861 21901 10863 21901 10862 21902 10863 21902 4159 21902 4159 21903 10863 21903 4157 21903 4157 21904 10863 21904 10864 21904 4157 21905 10864 21905 10865 21905 10764 21906 10866 21906 10765 21906 10765 21907 10866 21907 11045 21907 10765 21908 11045 21908 10768 21908 10768 21909 11045 21909 11047 21909 10768 21910 11047 21910 10867 21910 10867 21911 11047 21911 10868 21911 10867 21912 10868 21912 10869 21912 10869 21913 10868 21913 10870 21913 10869 21914 10870 21914 10772 21914 10772 21915 10870 21915 10871 21915 10772 21916 10871 21916 502 21916 502 21917 10871 21917 504 21917 10872 21918 10873 21918 10874 21918 10874 21919 10873 21919 10876 21919 10874 21920 10876 21920 10875 21920 10875 21921 10876 21921 11056 21921 10875 21922 11056 21922 10877 21922 10877 21923 11056 21923 10878 21923 10877 21924 10878 21924 10879 21924 10879 21925 10878 21925 10880 21925 10879 21926 10880 21926 10775 21926 10775 21927 10880 21927 11059 21927 10775 21928 11059 21928 492 21928 492 21929 11059 21929 10881 21929 11065 21930 11066 21930 588 21930 588 21931 10882 21931 11065 21931 11065 21932 10882 21932 10786 21932 11065 21933 10786 21933 10884 21933 10786 21934 10784 21934 10884 21934 10884 21935 10784 21935 10883 21935 10884 21936 10883 21936 11063 21936 11063 21937 10883 21937 10885 21937 10885 21938 10782 21938 11063 21938 11063 21939 10782 21939 10886 21939 11063 21940 10886 21940 10888 21940 10886 21941 10887 21941 10888 21941 10888 21942 10887 21942 10780 21942 10888 21943 10780 21943 10890 21943 10777 21944 11060 21944 10889 21944 10889 21945 11060 21945 10890 21945 10889 21946 10890 21946 10891 21946 10891 21947 10890 21947 10780 21947 477 21948 10892 21948 10789 21948 10789 21949 10892 21949 10893 21949 10789 21950 10893 21950 10791 21950 10791 21951 10893 21951 11076 21951 10791 21952 11076 21952 10794 21952 10794 21953 11076 21953 11079 21953 10794 21954 11079 21954 10894 21954 10894 21955 11079 21955 11080 21955 10894 21956 11080 21956 10895 21956 10895 21957 11080 21957 11081 21957 10895 21958 11081 21958 10896 21958 10896 21959 11081 21959 472 21959 566 21960 471 21960 10897 21960 10897 21961 471 21961 10898 21961 10897 21962 10898 21962 10899 21962 10899 21963 10898 21963 11087 21963 10899 21964 11087 21964 10799 21964 10799 21965 11087 21965 10900 21965 10799 21966 10900 21966 10800 21966 10800 21967 10900 21967 10901 21967 10800 21968 10901 21968 10801 21968 10801 21969 10901 21969 11089 21969 10801 21970 11089 21970 10902 21970 10902 21971 11089 21971 464 21971 10802 21972 10903 21972 10904 21972 10904 21973 10903 21973 10905 21973 10904 21974 10905 21974 10803 21974 10803 21975 10905 21975 10906 21975 10803 21976 10906 21976 10804 21976 10804 21977 10906 21977 11100 21977 10804 21978 11100 21978 10907 21978 10907 21979 11100 21979 11095 21979 10907 21980 11095 21980 10807 21980 10807 21981 11095 21981 10908 21981 10807 21982 10908 21982 10910 21982 10910 21983 10908 21983 10909 21983 10910 21984 10909 21984 456 21984 456 21985 10909 21985 11097 21985 10810 21986 10911 21986 10812 21986 10812 21987 10911 21987 11108 21987 10812 21988 11108 21988 10813 21988 10813 21989 11108 21989 11109 21989 10813 21990 11109 21990 10815 21990 10815 21991 11109 21991 11111 21991 10815 21992 11111 21992 10817 21992 10817 21993 11111 21993 10912 21993 10817 21994 10912 21994 10913 21994 10913 21995 10912 21995 10914 21995 10913 21996 10914 21996 10820 21996 10820 21997 10914 21997 11113 21997 10820 21998 11113 21998 10821 21998 10821 21999 11113 21999 11101 21999 450 22000 11126 22000 10915 22000 10915 22001 11126 22001 10916 22001 10915 22002 10916 22002 10917 22002 10917 22003 10916 22003 11115 22003 10917 22004 11115 22004 10824 22004 10824 22005 11115 22005 10918 22005 10824 22006 10918 22006 10825 22006 10825 22007 10918 22007 10919 22007 10825 22008 10919 22008 10826 22008 10826 22009 10919 22009 10920 22009 10826 22010 10920 22010 10828 22010 10828 22011 10920 22011 10921 22011 10828 22012 10921 22012 539 22012 539 22013 10921 22013 10922 22013 10829 22014 10923 22014 10830 22014 10830 22015 10923 22015 11137 22015 10830 22016 11137 22016 10924 22016 10924 22017 11137 22017 11138 22017 10924 22018 11138 22018 10833 22018 10833 22019 11138 22019 11140 22019 10833 22020 11140 22020 10925 22020 10925 22021 11140 22021 10926 22021 10925 22022 10926 22022 10835 22022 10835 22023 10926 22023 10927 22023 10835 22024 10927 22024 10928 22024 10928 22025 10927 22025 10929 22025 10928 22026 10929 22026 531 22026 531 22027 10929 22027 11131 22027 439 22028 11147 22028 10836 22028 10836 22029 11147 22029 11145 22029 10836 22030 11145 22030 10838 22030 10838 22031 11145 22031 11144 22031 10838 22032 11144 22032 10840 22032 10840 22033 11144 22033 11143 22033 10840 22034 11143 22034 10930 22034 10930 22035 11143 22035 11142 22035 10930 22036 11142 22036 10842 22036 10842 22037 11142 22037 11155 22037 10842 22038 11155 22038 10843 22038 10843 22039 11155 22039 11153 22039 10843 22040 11153 22040 10844 22040 10844 22041 11153 22041 11150 22041 10846 22042 433 22042 10931 22042 10931 22043 433 22043 10932 22043 10931 22044 10932 22044 10933 22044 10933 22045 10932 22045 10934 22045 10933 22046 10934 22046 10850 22046 10850 22047 10934 22047 10935 22047 10850 22048 10935 22048 10853 22048 10853 22049 10935 22049 11160 22049 10853 22050 11160 22050 10856 22050 10856 22051 11160 22051 10936 22051 10856 22052 10936 22052 516 22052 516 22053 10936 22053 426 22053 10939 22054 11167 22054 10938 22054 10937 22055 11167 22055 10939 22055 370 22056 10937 22056 10939 22056 10939 22057 11170 22057 363 22057 11168 22058 11170 22058 10939 22058 10938 22059 11168 22059 10939 22059 10940 22060 10941 22060 11174 22060 11173 22061 10941 22061 10940 22061 11171 22062 11173 22062 10940 22062 10940 22063 11178 22063 11179 22063 11176 22064 11178 22064 10940 22064 11174 22065 11176 22065 10940 22065 10943 22066 419 22066 10942 22066 11181 22067 11182 22067 10943 22067 11183 22068 11184 22068 10943 22068 10947 22069 10944 22069 10943 22069 10945 22070 11186 22070 10943 22070 10943 22071 11187 22071 11188 22071 10946 22072 11187 22072 10943 22072 11186 22073 10946 22073 10943 22073 10944 22074 10945 22074 10943 22074 11184 22075 10947 22075 10943 22075 11182 22076 11183 22076 10943 22076 10942 22077 11181 22077 10943 22077 417 22078 10948 22078 11189 22078 10950 22079 10948 22079 417 22079 10949 22080 10950 22080 417 22080 417 22081 10951 22081 11190 22081 10952 22082 10951 22082 417 22082 11189 22083 10952 22083 417 22083 11192 22084 10956 22084 413 22084 11194 22085 11196 22085 413 22085 10955 22086 11198 22086 413 22086 10954 22087 11200 22087 413 22087 413 22088 11205 22088 11206 22088 10953 22089 413 22089 11206 22089 11202 22090 11205 22090 413 22090 11200 22091 11202 22091 413 22091 11198 22092 10954 22092 413 22092 11196 22093 10955 22093 413 22093 10956 22094 11194 22094 413 22094 10957 22095 11192 22095 413 22095 10959 22096 11209 22096 10960 22096 10958 22097 11209 22097 10959 22097 330 22098 10958 22098 10959 22098 10959 22099 11212 22099 400 22099 10961 22100 11212 22100 10959 22100 10960 22101 10961 22101 10959 22101 399 22102 11214 22102 11216 22102 10966 22103 11217 22103 399 22103 10962 22104 10963 22104 399 22104 11219 22105 11221 22105 399 22105 11222 22106 10965 22106 399 22106 399 22107 10964 22107 309 22107 11224 22108 10964 22108 399 22108 10965 22109 11224 22109 399 22109 11221 22110 11222 22110 399 22110 10963 22111 11219 22111 399 22111 11217 22112 10962 22112 399 22112 11216 22113 10966 22113 399 22113 389 22114 10967 22114 10968 22114 10969 22115 10967 22115 389 22115 391 22116 10969 22116 389 22116 389 22117 11227 22117 387 22117 10970 22118 11227 22118 389 22118 10968 22119 10970 22119 389 22119 386 22120 10971 22120 10974 22120 11228 22121 10971 22121 386 22121 10972 22122 11228 22122 386 22122 386 22123 10973 22123 383 22123 11231 22124 10973 22124 386 22124 10974 22125 11231 22125 386 22125 10984 22126 10976 22126 11252 22126 10978 22127 10984 22127 11243 22127 11243 22128 10984 22128 10975 22128 11247 22129 10976 22129 11250 22129 11250 22130 10976 22130 10984 22130 11250 22131 10984 22131 10977 22131 10977 22132 10984 22132 10978 22132 10975 22133 10979 22133 11243 22133 11243 22134 10979 22134 11242 22134 11243 22135 11242 22135 10980 22135 11252 22136 10981 22136 10984 22136 10984 22137 10981 22137 11254 22137 10984 22138 11254 22138 10986 22138 11238 22139 11240 22139 11237 22139 11237 22140 11240 22140 10982 22140 11237 22141 10982 22141 10983 22141 10983 22142 10982 22142 10984 22142 10983 22143 10984 22143 10985 22143 10985 22144 10984 22144 10986 22144 11273 22145 11272 22145 11265 22145 10994 22146 10987 22146 11265 22146 11265 22147 10987 22147 10988 22147 11260 22148 11261 22148 11266 22148 11272 22149 11276 22149 11265 22149 11265 22150 11276 22150 11274 22150 11265 22151 11274 22151 11256 22151 10988 22152 10989 22152 11265 22152 11265 22153 10989 22153 11271 22153 11265 22154 11271 22154 11273 22154 11256 22155 10990 22155 11265 22155 11265 22156 10990 22156 10991 22156 11265 22157 10991 22157 11266 22157 11266 22158 10991 22158 11258 22158 11266 22159 11258 22159 11260 22159 11267 22160 11268 22160 10992 22160 10992 22161 11268 22161 10994 22161 10992 22162 10994 22162 10993 22162 10993 22163 10994 22163 11265 22163 11284 22164 11292 22164 11291 22164 11282 22165 10995 22165 10998 22165 11287 22166 10996 22166 11284 22166 11284 22167 10996 22167 10997 22167 11284 22168 10997 22168 11292 22168 10998 22169 10999 22169 11282 22169 11282 22170 10999 22170 11000 22170 11282 22171 11000 22171 11284 22171 11284 22172 11000 22172 11288 22172 11284 22173 11288 22173 11287 22173 11291 22174 11297 22174 11284 22174 11284 22175 11297 22175 11296 22175 11284 22176 11296 22176 11294 22176 290 22177 291 22177 11001 22177 11001 22178 291 22178 292 22178 11001 22179 292 22179 11002 22179 11002 22180 292 22180 11284 22180 11002 22181 11284 22181 11278 22181 11278 22182 11284 22182 11294 22182 11006 22183 11003 22183 11004 22183 11304 22184 11309 22184 11009 22184 11009 22185 11309 22185 11308 22185 11308 22186 11005 22186 11009 22186 11009 22187 11005 22187 11310 22187 11009 22188 11310 22188 11313 22188 11004 22189 11007 22189 11006 22189 11006 22190 11007 22190 11008 22190 11006 22191 11008 22191 11009 22191 11009 22192 11008 22192 11305 22192 11009 22193 11305 22193 11304 22193 11299 22194 11010 22194 11011 22194 11011 22195 11012 22195 11299 22195 11299 22196 11012 22196 11013 22196 11299 22197 11013 22197 11014 22197 11014 22198 11013 22198 11009 22198 11014 22199 11009 22199 11015 22199 11015 22200 11009 22200 11313 22200 11015 22201 11313 22201 11016 22201 11329 22202 11328 22202 282 22202 282 22203 11328 22203 11027 22203 282 22204 11027 22204 285 22204 11028 22205 11017 22205 11027 22205 11027 22206 11017 22206 11018 22206 11027 22207 11018 22207 285 22207 11019 22208 11021 22208 11020 22208 11020 22209 11021 22209 11022 22209 11020 22210 11022 22210 11315 22210 11315 22211 11022 22211 11027 22211 11315 22212 11027 22212 11023 22212 11023 22213 11027 22213 11328 22213 286 22214 11024 22214 11318 22214 11318 22215 11024 22215 11026 22215 11318 22216 11026 22216 11025 22216 11025 22217 11026 22217 11323 22217 11025 22218 11323 22218 11027 22218 11027 22219 11323 22219 11321 22219 11027 22220 11321 22220 11028 22220 11032 22221 11029 22221 11335 22221 11335 22222 11029 22222 11034 22222 11335 22223 11034 22223 11030 22223 11031 22224 11032 22224 11350 22224 11350 22225 11032 22225 11335 22225 11350 22226 11335 22226 11351 22226 11351 22227 11335 22227 11343 22227 11036 22228 11337 22228 11033 22228 11339 22229 11346 22229 11335 22229 11335 22230 11346 22230 11344 22230 11335 22231 11344 22231 11343 22231 11331 22232 11332 22232 11034 22232 11034 22233 11332 22233 11035 22233 11034 22234 11035 22234 11030 22234 11033 22235 280 22235 11036 22235 11036 22236 280 22236 281 22236 11036 22237 281 22237 11335 22237 11335 22238 281 22238 11341 22238 11335 22239 11341 22239 11339 22239 11037 22240 11039 22240 11038 22240 11038 22241 11039 22241 11040 22241 11038 22242 11040 22242 10858 22242 10858 22243 11040 22243 11356 22243 10858 22244 11356 22244 10859 22244 10859 22245 11356 22245 11041 22245 10859 22246 11041 22246 10861 22246 10861 22247 11041 22247 11359 22247 10861 22248 11359 22248 10863 22248 10863 22249 11359 22249 11042 22249 10863 22250 11042 22250 10864 22250 10864 22251 11042 22251 11360 22251 11367 22252 11369 22252 496 22252 496 22253 11369 22253 11371 22253 496 22254 11371 22254 495 22254 495 22255 11371 22255 11043 22255 495 22256 11043 22256 11044 22256 11044 22257 11043 22257 11373 22257 11044 22258 11373 22258 10866 22258 10866 22259 11373 22259 11046 22259 10866 22260 11046 22260 11045 22260 11045 22261 11046 22261 272 22261 11045 22262 272 22262 11047 22262 11047 22263 272 22263 271 22263 11047 22264 271 22264 10868 22264 10868 22265 271 22265 278 22265 10868 22266 278 22266 10870 22266 10870 22267 278 22267 11048 22267 10870 22268 11048 22268 10871 22268 10871 22269 11048 22269 279 22269 10871 22270 279 22270 504 22270 504 22271 279 22271 11049 22271 504 22272 11049 22272 501 22272 501 22273 11049 22273 11363 22273 501 22274 11363 22274 499 22274 499 22275 11363 22275 11367 22275 499 22276 11367 22276 496 22276 11050 22277 11377 22277 11051 22277 11051 22278 11377 22278 11378 22278 11051 22279 11378 22279 11052 22279 11052 22280 11378 22280 11379 22280 11052 22281 11379 22281 11053 22281 11053 22282 11379 22282 11054 22282 11053 22283 11054 22283 10873 22283 10873 22284 11054 22284 11055 22284 10873 22285 11055 22285 10876 22285 10876 22286 11055 22286 266 22286 10876 22287 266 22287 11056 22287 11056 22288 266 22288 267 22288 11056 22289 267 22289 10878 22289 10878 22290 267 22290 11057 22290 10878 22291 11057 22291 10880 22291 10880 22292 11057 22292 11058 22292 10880 22293 11058 22293 11059 22293 11059 22294 11058 22294 269 22294 11059 22295 269 22295 10881 22295 10881 22296 269 22296 11374 22296 10881 22297 11374 22297 493 22297 493 22298 11374 22298 11375 22298 493 22299 11375 22299 489 22299 489 22300 11375 22300 11050 22300 489 22301 11050 22301 11051 22301 11070 22302 11384 22302 480 22302 480 22303 11384 22303 478 22303 478 22304 11384 22304 11061 22304 478 22305 11061 22305 11060 22305 11060 22306 11061 22306 255 22306 11060 22307 255 22307 10890 22307 10890 22308 255 22308 11062 22308 10890 22309 11062 22309 10888 22309 10888 22310 11062 22310 257 22310 10888 22311 257 22311 11063 22311 257 22312 259 22312 11063 22312 11063 22313 259 22313 11064 22313 11063 22314 11064 22314 10884 22314 10884 22315 11064 22315 262 22315 10884 22316 262 22316 11065 22316 11065 22317 262 22317 265 22317 11065 22318 265 22318 11066 22318 11066 22319 265 22319 11067 22319 11066 22320 11067 22320 11068 22320 11068 22321 11067 22321 11380 22321 11068 22322 11380 22322 11069 22322 11069 22323 11380 22323 11381 22323 11069 22324 11381 22324 484 22324 484 22325 11381 22325 11070 22325 484 22326 11070 22326 482 22326 482 22327 11070 22327 480 22327 474 22328 11083 22328 475 22328 475 22329 11083 22329 11387 22329 475 22330 11387 22330 11071 22330 11071 22331 11387 22331 11390 22331 11071 22332 11390 22332 476 22332 476 22333 11390 22333 11072 22333 476 22334 11072 22334 11073 22334 11073 22335 11072 22335 11391 22335 11073 22336 11391 22336 11074 22336 11074 22337 11391 22337 11075 22337 11074 22338 11075 22338 10892 22338 10892 22339 11075 22339 250 22339 10892 22340 250 22340 10893 22340 10893 22341 250 22341 11077 22341 10893 22342 11077 22342 11076 22342 11076 22343 11077 22343 11078 22343 11076 22344 11078 22344 11079 22344 11079 22345 11078 22345 252 22345 11079 22346 252 22346 11080 22346 11080 22347 252 22347 254 22347 11080 22348 254 22348 11081 22348 11081 22349 254 22349 11082 22349 11081 22350 11082 22350 472 22350 472 22351 11082 22351 11385 22351 472 22352 11385 22352 474 22352 474 22353 11385 22353 11083 22353 469 22354 11084 22354 470 22354 470 22355 11084 22355 11085 22355 470 22356 11085 22356 471 22356 471 22357 11085 22357 11086 22357 471 22358 11086 22358 10898 22358 10898 22359 11086 22359 240 22359 10898 22360 240 22360 11087 22360 11087 22361 240 22361 11088 22361 11087 22362 11088 22362 10900 22362 10900 22363 11088 22363 244 22363 10900 22364 244 22364 10901 22364 10901 22365 244 22365 246 22365 10901 22366 246 22366 11089 22366 11089 22367 246 22367 11090 22367 11089 22368 11090 22368 464 22368 464 22369 11090 22369 11091 22369 464 22370 11091 22370 466 22370 466 22371 11091 22371 11395 22371 466 22372 11395 22372 467 22372 467 22373 11395 22373 11092 22373 467 22374 11092 22374 468 22374 468 22375 11092 22375 11093 22375 468 22376 11093 22376 11094 22376 11094 22377 11093 22377 11400 22377 11094 22378 11400 22378 469 22378 469 22379 11400 22379 11084 22379 11095 22380 11096 22380 10908 22380 10908 22381 11096 22381 238 22381 10908 22382 238 22382 10909 22382 10909 22383 238 22383 239 22383 10909 22384 239 22384 11097 22384 11097 22385 239 22385 11098 22385 11097 22386 11098 22386 458 22386 458 22387 11098 22387 11099 22387 458 22388 11099 22388 459 22388 459 22389 11099 22389 11406 22389 459 22390 11406 22390 460 22390 460 22391 11406 22391 11407 22391 460 22392 11407 22392 462 22392 462 22393 11407 22393 11409 22393 462 22394 11409 22394 463 22394 463 22395 11409 22395 11410 22395 463 22396 11410 22396 10903 22396 10903 22397 11410 22397 231 22397 10903 22398 231 22398 10905 22398 10905 22399 231 22399 232 22399 10905 22400 232 22400 10906 22400 10906 22401 232 22401 234 22401 10906 22402 234 22402 11100 22402 11100 22403 234 22403 236 22403 11100 22404 236 22404 11095 22404 11095 22405 236 22405 11096 22405 11113 22406 229 22406 11101 22406 11101 22407 229 22407 11412 22407 11101 22408 11412 22408 11102 22408 11102 22409 11412 22409 11103 22409 11102 22410 11103 22410 11104 22410 11104 22411 11103 22411 11105 22411 11104 22412 11105 22412 454 22412 454 22413 11105 22413 11414 22413 454 22414 11414 22414 11106 22414 11106 22415 11414 22415 11107 22415 11106 22416 11107 22416 455 22416 455 22417 11107 22417 11420 22417 455 22418 11420 22418 10911 22418 10911 22419 11420 22419 11421 22419 10911 22420 11421 22420 11108 22420 11108 22421 11421 22421 226 22421 11108 22422 226 22422 11109 22422 11109 22423 226 22423 11110 22423 11109 22424 11110 22424 11111 22424 11111 22425 11110 22425 11112 22425 11111 22426 11112 22426 10912 22426 10912 22427 11112 22427 227 22427 10912 22428 227 22428 10914 22428 10914 22429 227 22429 228 22429 10914 22430 228 22430 11113 22430 11113 22431 228 22431 229 22431 10916 22432 11114 22432 11115 22432 11115 22433 11114 22433 11116 22433 11115 22434 11116 22434 10918 22434 10918 22435 11116 22435 223 22435 10918 22436 223 22436 10919 22436 10919 22437 223 22437 11117 22437 10919 22438 11117 22438 10920 22438 10920 22439 11117 22439 11118 22439 10920 22440 11118 22440 10921 22440 10921 22441 11118 22441 11119 22441 10921 22442 11119 22442 10922 22442 10922 22443 11119 22443 11120 22443 10922 22444 11120 22444 11122 22444 11122 22445 11120 22445 11121 22445 11122 22446 11121 22446 446 22446 446 22447 11121 22447 11424 22447 446 22448 11424 22448 11123 22448 11123 22449 11424 22449 11426 22449 11123 22450 11426 22450 448 22450 448 22451 11426 22451 11124 22451 448 22452 11124 22452 11125 22452 11125 22453 11124 22453 11427 22453 11125 22454 11427 22454 11126 22454 11126 22455 11427 22455 220 22455 11126 22456 220 22456 10916 22456 10916 22457 220 22457 11114 22457 11140 22458 11127 22458 10926 22458 10926 22459 11127 22459 11128 22459 10926 22460 11128 22460 10927 22460 10927 22461 11128 22461 11129 22461 10927 22462 11129 22462 10929 22462 10929 22463 11129 22463 11130 22463 10929 22464 11130 22464 11131 22464 11131 22465 11130 22465 11132 22465 11131 22466 11132 22466 11133 22466 11133 22467 11132 22467 11430 22467 11133 22468 11430 22468 11134 22468 11134 22469 11430 22469 11428 22469 11134 22470 11428 22470 11135 22470 11135 22471 11428 22471 11136 22471 11135 22472 11136 22472 442 22472 442 22473 11136 22473 11433 22473 442 22474 11433 22474 443 22474 443 22475 11433 22475 11436 22475 443 22476 11436 22476 10923 22476 10923 22477 11436 22477 11437 22477 10923 22478 11437 22478 11137 22478 11137 22479 11437 22479 215 22479 11137 22480 215 22480 11138 22480 11138 22481 215 22481 11139 22481 11138 22482 11139 22482 11140 22482 11140 22483 11139 22483 11127 22483 11155 22484 11142 22484 11141 22484 11141 22485 11142 22485 11143 22485 11141 22486 11143 22486 212 22486 212 22487 11143 22487 11144 22487 212 22488 11144 22488 211 22488 211 22489 11144 22489 11145 22489 211 22490 11145 22490 11146 22490 11146 22491 11145 22491 11147 22491 11146 22492 11147 22492 11443 22492 11443 22493 11147 22493 11148 22493 11443 22494 11148 22494 11442 22494 11442 22495 11148 22495 11149 22495 11442 22496 11149 22496 11441 22496 11441 22497 11149 22497 437 22497 11441 22498 437 22498 11439 22498 11439 22499 437 22499 436 22499 11439 22500 436 22500 11438 22500 11438 22501 436 22501 435 22501 11438 22502 435 22502 11151 22502 11151 22503 435 22503 11150 22503 11151 22504 11150 22504 11152 22504 11152 22505 11150 22505 11153 22505 11152 22506 11153 22506 11154 22506 11154 22507 11153 22507 11155 22507 11154 22508 11155 22508 11141 22508 11165 22509 429 22509 11448 22509 11448 22510 429 22510 11156 22510 11448 22511 11156 22511 11157 22511 11157 22512 11156 22512 11158 22512 11157 22513 11158 22513 11445 22513 11445 22514 11158 22514 426 22514 11445 22515 426 22515 210 22515 210 22516 426 22516 10936 22516 210 22517 10936 22517 11159 22517 11159 22518 10936 22518 11160 22518 11159 22519 11160 22519 11161 22519 11161 22520 11160 22520 10935 22520 11161 22521 10935 22521 207 22521 207 22522 10935 22522 10934 22522 207 22523 10934 22523 11162 22523 11162 22524 10934 22524 10932 22524 11162 22525 10932 22525 11163 22525 11163 22526 10932 22526 433 22526 11163 22527 433 22527 11449 22527 11449 22528 433 22528 432 22528 11449 22529 432 22529 11164 22529 11164 22530 432 22530 431 22530 11164 22531 431 22531 11165 22531 11165 22532 431 22532 11166 22532 11165 22533 11166 22533 429 22533 370 22534 204 22534 10937 22534 10937 22535 204 22535 11450 22535 10937 22536 11450 22536 11167 22536 11167 22537 11450 22537 11451 22537 11167 22538 11451 22538 10938 22538 10938 22539 11451 22539 11452 22539 10938 22540 11452 22540 11168 22540 11168 22541 11452 22541 11169 22541 11168 22542 11169 22542 11170 22542 11170 22543 11169 22543 11454 22543 11170 22544 11454 22544 363 22544 363 22545 11454 22545 196 22545 11171 22546 11172 22546 11173 22546 11173 22547 11172 22547 11457 22547 11173 22548 11457 22548 10941 22548 10941 22549 11457 22549 11458 22549 10941 22550 11458 22550 11174 22550 11174 22551 11458 22551 11175 22551 11174 22552 11175 22552 11176 22552 11176 22553 11175 22553 11177 22553 11176 22554 11177 22554 11178 22554 11178 22555 11177 22555 11460 22555 11178 22556 11460 22556 11179 22556 11179 22557 11460 22557 11462 22557 419 22558 174 22558 10942 22558 10942 22559 174 22559 11180 22559 10942 22560 11180 22560 11181 22560 11181 22561 11180 22561 11182 22561 11182 22562 11180 22562 11463 22562 11182 22563 11463 22563 11183 22563 11183 22564 11463 22564 11184 22564 11184 22565 11463 22565 11185 22565 11184 22566 11185 22566 10947 22566 10947 22567 11185 22567 10944 22567 10944 22568 11185 22568 11466 22568 10944 22569 11466 22569 10945 22569 10945 22570 11466 22570 11186 22570 11186 22571 11466 22571 11468 22571 11186 22572 11468 22572 10946 22572 10946 22573 11468 22573 11187 22573 11187 22574 11468 22574 184 22574 11187 22575 184 22575 11188 22575 10949 22576 11470 22576 10950 22576 10950 22577 11470 22577 11471 22577 10950 22578 11471 22578 10948 22578 10948 22579 11471 22579 11472 22579 10948 22580 11472 22580 11189 22580 11189 22581 11472 22581 11473 22581 11189 22582 11473 22582 10952 22582 10952 22583 11473 22583 11474 22583 10952 22584 11474 22584 10951 22584 10951 22585 11474 22585 11475 22585 10951 22586 11475 22586 11190 22586 11190 22587 11475 22587 11191 22587 10957 22588 11485 22588 11192 22588 11192 22589 11485 22589 11193 22589 11192 22590 11193 22590 10956 22590 10956 22591 11193 22591 11195 22591 10956 22592 11195 22592 11194 22592 11194 22593 11195 22593 11484 22593 11194 22594 11484 22594 11196 22594 11196 22595 11484 22595 11483 22595 11196 22596 11483 22596 10955 22596 10955 22597 11483 22597 11197 22597 10955 22598 11197 22598 11198 22598 11198 22599 11197 22599 11481 22599 11198 22600 11481 22600 10954 22600 10954 22601 11481 22601 11199 22601 10954 22602 11199 22602 11200 22602 11200 22603 11199 22603 11201 22603 11200 22604 11201 22604 11202 22604 11202 22605 11201 22605 11203 22605 11202 22606 11203 22606 11205 22606 11205 22607 11203 22607 11204 22607 11205 22608 11204 22608 11206 22608 11206 22609 11204 22609 11207 22609 11206 22610 11207 22610 10953 22610 10953 22611 11207 22611 11479 22611 330 22612 329 22612 10958 22612 10958 22613 329 22613 11208 22613 10958 22614 11208 22614 11209 22614 11209 22615 11208 22615 11488 22615 11209 22616 11488 22616 10960 22616 10960 22617 11488 22617 11210 22617 10960 22618 11210 22618 10961 22618 10961 22619 11210 22619 11211 22619 10961 22620 11211 22620 11212 22620 11212 22621 11211 22621 11213 22621 11212 22622 11213 22622 400 22622 400 22623 11213 22623 319 22623 11214 22624 11215 22624 11216 22624 11216 22625 11215 22625 11218 22625 11216 22626 11218 22626 10966 22626 10966 22627 11218 22627 11217 22627 11217 22628 11218 22628 11491 22628 11217 22629 11491 22629 10962 22629 10962 22630 11491 22630 10963 22630 10963 22631 11491 22631 11220 22631 10963 22632 11220 22632 11219 22632 11219 22633 11220 22633 11221 22633 11221 22634 11220 22634 11223 22634 11221 22635 11223 22635 11222 22635 11222 22636 11223 22636 10965 22636 10965 22637 11223 22637 11225 22637 10965 22638 11225 22638 11224 22638 11224 22639 11225 22639 10964 22639 10964 22640 11225 22640 11226 22640 10964 22641 11226 22641 309 22641 391 22642 308 22642 10969 22642 10969 22643 308 22643 11493 22643 10969 22644 11493 22644 10967 22644 10967 22645 11493 22645 11494 22645 10967 22646 11494 22646 10968 22646 10968 22647 11494 22647 11495 22647 10968 22648 11495 22648 10970 22648 10970 22649 11495 22649 11496 22649 10970 22650 11496 22650 11227 22650 11227 22651 11496 22651 11498 22651 11227 22652 11498 22652 387 22652 387 22653 11498 22653 11499 22653 10972 22654 301 22654 11228 22654 11228 22655 301 22655 11502 22655 11228 22656 11502 22656 10971 22656 10971 22657 11502 22657 11229 22657 10971 22658 11229 22658 10974 22658 10974 22659 11229 22659 11230 22659 10974 22660 11230 22660 11231 22660 11231 22661 11230 22661 11232 22661 11231 22662 11232 22662 10973 22662 10973 22663 11232 22663 11233 22663 10973 22664 11233 22664 383 22664 383 22665 11233 22665 11506 22665 11234 22666 10983 22666 11235 22666 11235 22667 10983 22667 10985 22667 11235 22668 10985 22668 11236 22668 11236 22669 10985 22669 10986 22669 10983 22670 11234 22670 11237 22670 11237 22671 11234 22671 11508 22671 11237 22672 11508 22672 11238 22672 11238 22673 11508 22673 11239 22673 11238 22674 11239 22674 11240 22674 11240 22675 11239 22675 11241 22675 11240 22676 11241 22676 10982 22676 10982 22677 11241 22677 11510 22677 11512 22678 10975 22678 11511 22678 11511 22679 10975 22679 10984 22679 11511 22680 10984 22680 11510 22680 11510 22681 10984 22681 10982 22681 10975 22682 11512 22682 10979 22682 10979 22683 11512 22683 11513 22683 10979 22684 11513 22684 11242 22684 11242 22685 11513 22685 11515 22685 11242 22686 11515 22686 10980 22686 10980 22687 11515 22687 11244 22687 10980 22688 11244 22688 11243 22688 11243 22689 11244 22689 11246 22689 11245 22690 10977 22690 11516 22690 11516 22691 10977 22691 10978 22691 11516 22692 10978 22692 11246 22692 11246 22693 10978 22693 11243 22693 11248 22694 10976 22694 11247 22694 11248 22695 11247 22695 11249 22695 11249 22696 11247 22696 11250 22696 11249 22697 11250 22697 11251 22697 11251 22698 11250 22698 10977 22698 11251 22699 10977 22699 11245 22699 11252 22700 10976 22700 11519 22700 11519 22701 10976 22701 11248 22701 11236 22702 10986 22702 11253 22702 11253 22703 10986 22703 11254 22703 11253 22704 11254 22704 11520 22704 11520 22705 11254 22705 10981 22705 11520 22706 10981 22706 11519 22706 11519 22707 10981 22707 11252 22707 11257 22708 10991 22708 11522 22708 11522 22709 10991 22709 10990 22709 11522 22710 10990 22710 11255 22710 11255 22711 10990 22711 11256 22711 10991 22712 11257 22712 11258 22712 11258 22713 11257 22713 11259 22713 11258 22714 11259 22714 11260 22714 11260 22715 11259 22715 11523 22715 11260 22716 11523 22716 11261 22716 11261 22717 11523 22717 11262 22717 11261 22718 11262 22718 11266 22718 11266 22719 11262 22719 11263 22719 11264 22720 10993 22720 11525 22720 11525 22721 10993 22721 11265 22721 11525 22722 11265 22722 11263 22722 11263 22723 11265 22723 11266 22723 10993 22724 11264 22724 10992 22724 10992 22725 11264 22725 11526 22725 10992 22726 11526 22726 11267 22726 11267 22727 11526 22727 11269 22727 11267 22728 11269 22728 11268 22728 11268 22729 11269 22729 11527 22729 11268 22730 11527 22730 10994 22730 10994 22731 11527 22731 11529 22731 11532 22732 10988 22732 11530 22732 11530 22733 10988 22733 10987 22733 11530 22734 10987 22734 11529 22734 11529 22735 10987 22735 10994 22735 11535 22736 11273 22736 11270 22736 11270 22737 11273 22737 11271 22737 11270 22738 11271 22738 11533 22738 11533 22739 11271 22739 10989 22739 11533 22740 10989 22740 11532 22740 11532 22741 10989 22741 10988 22741 11272 22742 11273 22742 11277 22742 11277 22743 11273 22743 11535 22743 11255 22744 11256 22744 11274 22744 11255 22745 11274 22745 11275 22745 11275 22746 11274 22746 11276 22746 11275 22747 11276 22747 11537 22747 11537 22748 11276 22748 11272 22748 11537 22749 11272 22749 11277 22749 11279 22750 11002 22750 11542 22750 11542 22751 11002 22751 11278 22751 11542 22752 11278 22752 11540 22752 11540 22753 11278 22753 11294 22753 11002 22754 11279 22754 11001 22754 11001 22755 11279 22755 11280 22755 11281 22756 11282 22756 11283 22756 11283 22757 11282 22757 11284 22757 11283 22758 11284 22758 141 22758 141 22759 11284 22759 292 22759 11282 22760 11281 22760 10995 22760 10995 22761 11281 22761 11285 22761 10995 22762 11285 22762 10998 22762 10998 22763 11285 22763 11548 22763 10998 22764 11548 22764 10999 22764 10999 22765 11548 22765 11286 22765 10999 22766 11286 22766 11000 22766 11000 22767 11286 22767 11289 22767 11552 22768 11287 22768 11550 22768 11550 22769 11287 22769 11288 22769 11550 22770 11288 22770 11289 22770 11289 22771 11288 22771 11000 22771 11293 22772 11292 22772 11290 22772 11290 22773 11292 22773 10997 22773 11290 22774 10997 22774 11553 22774 11553 22775 10997 22775 10996 22775 11553 22776 10996 22776 11552 22776 11552 22777 10996 22777 11287 22777 11291 22778 11292 22778 11298 22778 11298 22779 11292 22779 11293 22779 11540 22780 11294 22780 11295 22780 11295 22781 11294 22781 11296 22781 11295 22782 11296 22782 11555 22782 11555 22783 11296 22783 11297 22783 11555 22784 11297 22784 11298 22784 11298 22785 11297 22785 11291 22785 11559 22786 11299 22786 11300 22786 11300 22787 11299 22787 11014 22787 11300 22788 11014 22788 11556 22788 11556 22789 11014 22789 11015 22789 11299 22790 11559 22790 11010 22790 11010 22791 11559 22791 11301 22791 11010 22792 11301 22792 11011 22792 11011 22793 11301 22793 11302 22793 11011 22794 11302 22794 11012 22794 11012 22795 11302 22795 11560 22795 11563 22796 11006 22796 11303 22796 11303 22797 11006 22797 11009 22797 11303 22798 11009 22798 137 22798 137 22799 11009 22799 11013 22799 11006 22800 11563 22800 11003 22800 11003 22801 11563 22801 11565 22801 11003 22802 11565 22802 11004 22802 11004 22803 11565 22803 11567 22803 11004 22804 11567 22804 11007 22804 11007 22805 11567 22805 11568 22805 11007 22806 11568 22806 11008 22806 11008 22807 11568 22807 11306 22807 11573 22808 11304 22808 11570 22808 11570 22809 11304 22809 11305 22809 11570 22810 11305 22810 11306 22810 11306 22811 11305 22811 11008 22811 11307 22812 11005 22812 11308 22812 11307 22813 11308 22813 11574 22813 11574 22814 11308 22814 11309 22814 11574 22815 11309 22815 288 22815 11310 22816 11005 22816 11311 22816 11311 22817 11005 22817 11307 22817 11556 22818 11015 22818 11312 22818 11312 22819 11015 22819 11016 22819 11312 22820 11016 22820 11576 22820 11576 22821 11016 22821 11313 22821 11576 22822 11313 22822 11311 22822 11311 22823 11313 22823 11310 22823 11314 22824 11315 22824 11577 22824 11577 22825 11315 22825 11023 22825 11577 22826 11023 22826 11326 22826 11326 22827 11023 22827 11328 22827 11315 22828 11314 22828 11020 22828 11020 22829 11314 22829 11579 22829 11020 22830 11579 22830 11019 22830 11019 22831 11579 22831 11580 22831 11019 22832 11580 22832 11021 22832 11021 22833 11580 22833 11582 22833 11021 22834 11582 22834 11022 22834 11022 22835 11582 22835 11316 22835 11585 22836 11025 22836 11317 22836 11317 22837 11025 22837 11027 22837 11317 22838 11027 22838 11316 22838 11316 22839 11027 22839 11022 22839 11025 22840 11585 22840 11318 22840 11318 22841 11585 22841 11319 22841 11320 22842 11321 22842 11322 22842 11322 22843 11321 22843 11323 22843 11322 22844 11323 22844 11586 22844 11586 22845 11323 22845 11026 22845 11590 22846 11018 22846 11324 22846 11324 22847 11018 22847 11017 22847 11324 22848 11017 22848 11589 22848 11589 22849 11017 22849 11028 22849 11589 22850 11028 22850 11320 22850 11320 22851 11028 22851 11321 22851 285 22852 11018 22852 11325 22852 11325 22853 11018 22853 11590 22853 11326 22854 11328 22854 11327 22854 11327 22855 11328 22855 11329 22855 11327 22856 11329 22856 283 22856 11594 22857 11034 22857 11330 22857 11330 22858 11034 22858 11029 22858 11330 22859 11029 22859 11347 22859 11347 22860 11029 22860 11032 22860 11034 22861 11594 22861 11331 22861 11331 22862 11594 22862 11333 22862 11331 22863 11333 22863 11332 22863 11332 22864 11333 22864 11596 22864 11332 22865 11596 22865 11035 22865 11035 22866 11596 22866 11598 22866 11035 22867 11598 22867 11030 22867 11030 22868 11598 22868 11334 22868 11336 22869 11036 22869 11599 22869 11599 22870 11036 22870 11335 22870 11599 22871 11335 22871 11334 22871 11334 22872 11335 22872 11030 22872 11036 22873 11336 22873 11337 22873 11337 22874 11336 22874 11602 22874 11337 22875 11602 22875 11033 22875 11033 22876 11602 22876 11603 22876 11033 22877 11603 22877 280 22877 280 22878 11603 22878 11338 22878 11606 22879 11339 22879 11340 22879 11340 22880 11339 22880 11341 22880 11340 22881 11341 22881 11342 22881 11342 22882 11341 22882 281 22882 11612 22883 11343 22883 11345 22883 11345 22884 11343 22884 11344 22884 11345 22885 11344 22885 11608 22885 11608 22886 11344 22886 11346 22886 11608 22887 11346 22887 11606 22887 11606 22888 11346 22888 11339 22888 11351 22889 11343 22889 11611 22889 11611 22890 11343 22890 11612 22890 11347 22891 11032 22891 11348 22891 11348 22892 11032 22892 11031 22892 11348 22893 11031 22893 11349 22893 11349 22894 11031 22894 11350 22894 11349 22895 11350 22895 11611 22895 11611 22896 11350 22896 11351 22896 379 22897 11618 22897 377 22897 377 22898 11618 22898 11620 22898 377 22899 11620 22899 11352 22899 11352 22900 11620 22900 11353 22900 11352 22901 11353 22901 374 22901 374 22902 11353 22902 11354 22902 374 22903 11354 22903 372 22903 372 22904 11354 22904 11622 22904 372 22905 11622 22905 11039 22905 11039 22906 11622 22906 11355 22906 11039 22907 11355 22907 11040 22907 11040 22908 11355 22908 11357 22908 11040 22909 11357 22909 11356 22909 11356 22910 11357 22910 11358 22910 11356 22911 11358 22911 11041 22911 11041 22912 11358 22912 130 22912 11041 22913 130 22913 11359 22913 11359 22914 130 22914 131 22914 11359 22915 131 22915 11042 22915 11042 22916 131 22916 11361 22916 11042 22917 11361 22917 11360 22917 11360 22918 11361 22918 11616 22918 11360 22919 11616 22919 382 22919 382 22920 11616 22920 11362 22920 382 22921 11362 22921 379 22921 379 22922 11362 22922 11618 22922 11049 22923 11623 22923 11364 22923 11049 22924 11364 22924 11363 22924 11363 22925 11364 22925 11365 22925 11363 22926 11365 22926 11367 22926 11365 22927 11366 22927 11367 22927 11367 22928 11366 22928 11368 22928 11367 22929 11368 22929 11369 22929 11368 22930 11370 22930 11369 22930 11369 22931 11370 22931 11626 22931 11369 22932 11626 22932 11371 22932 11371 22933 11626 22933 11625 22933 11371 22934 11625 22934 11043 22934 11625 22935 11627 22935 11043 22935 11043 22936 11627 22936 11372 22936 11043 22937 11372 22937 11373 22937 11373 22938 11372 22938 11628 22938 11628 22939 11629 22939 11373 22939 11373 22940 11629 22940 274 22940 11373 22941 274 22941 11046 22941 11374 22942 270 22942 11630 22942 11374 22943 11630 22943 11375 22943 11375 22944 11630 22944 11631 22944 11375 22945 11631 22945 11050 22945 11050 22946 11631 22946 11376 22946 11050 22947 11376 22947 11377 22947 11377 22948 11376 22948 11634 22948 11377 22949 11634 22949 11378 22949 11378 22950 11634 22950 11635 22950 11378 22951 11635 22951 11379 22951 11379 22952 11635 22952 11638 22952 11379 22953 11638 22953 11054 22953 11054 22954 11638 22954 113 22954 11054 22955 113 22955 11055 22955 11381 22956 11380 22956 11653 22956 11653 22957 11380 22957 11067 22957 11653 22958 11067 22958 11655 22958 11653 22959 11651 22959 11381 22959 11381 22960 11651 22960 11649 22960 11381 22961 11649 22961 11070 22961 11070 22962 11649 22962 11382 22962 11382 22963 11647 22963 11070 22963 11070 22964 11647 22964 11383 22964 11070 22965 11383 22965 11384 22965 11383 22966 11646 22966 11384 22966 11384 22967 11646 22967 11644 22967 11384 22968 11644 22968 11061 22968 11644 22969 11642 22969 11061 22969 11061 22970 11642 22970 11640 22970 11061 22971 11640 22971 255 22971 11385 22972 105 22972 11386 22972 11385 22973 11386 22973 11083 22973 11083 22974 11386 22974 11660 22974 11083 22975 11660 22975 11387 22975 11660 22976 11661 22976 11387 22976 11387 22977 11661 22977 11388 22977 11387 22978 11388 22978 11390 22978 11388 22979 11389 22979 11390 22979 11390 22980 11389 22980 11658 22980 11390 22981 11658 22981 11072 22981 11072 22982 11658 22982 11657 22982 11072 22983 11657 22983 11391 22983 11657 22984 11392 22984 11391 22984 11391 22985 11392 22985 11656 22985 11391 22986 11656 22986 11075 22986 11075 22987 11656 22987 11393 22987 11393 22988 11394 22988 11075 22988 11075 22989 11394 22989 97 22989 11075 22990 97 22990 250 22990 11091 22991 248 22991 11396 22991 11091 22992 11396 22992 11395 22992 11395 22993 11396 22993 11397 22993 11395 22994 11397 22994 11092 22994 11397 22995 11667 22995 11092 22995 11092 22996 11667 22996 11666 22996 11092 22997 11666 22997 11093 22997 11093 22998 11666 22998 11665 22998 11093 22999 11665 22999 11400 22999 11665 23000 11398 23000 11400 23000 11400 23001 11398 23001 11399 23001 11400 23002 11399 23002 11084 23002 11399 23003 11401 23003 11084 23003 11084 23004 11401 23004 11402 23004 11084 23005 11402 23005 11085 23005 11085 23006 11402 23006 11663 23006 11663 23007 11403 23007 11085 23007 11085 23008 11403 23008 11404 23008 11085 23009 11404 23009 11086 23009 11098 23010 11675 23010 11405 23010 11098 23011 11405 23011 11099 23011 11099 23012 11405 23012 11674 23012 11099 23013 11674 23013 11406 23013 11406 23014 11674 23014 11671 23014 11406 23015 11671 23015 11407 23015 11407 23016 11671 23016 11408 23016 11407 23017 11408 23017 11409 23017 11409 23018 11408 23018 11669 23018 11409 23019 11669 23019 11410 23019 11410 23020 11669 23020 82 23020 11410 23021 82 23021 231 23021 11105 23022 11103 23022 11411 23022 11411 23023 11103 23023 11412 23023 11411 23024 11412 23024 230 23024 11411 23025 11679 23025 11105 23025 11105 23026 11679 23026 11413 23026 11105 23027 11413 23027 11414 23027 11414 23028 11413 23028 11677 23028 11677 23029 11415 23029 11414 23029 11414 23030 11415 23030 11416 23030 11414 23031 11416 23031 11107 23031 11416 23032 11417 23032 11107 23032 11107 23033 11417 23033 11418 23033 11107 23034 11418 23034 11420 23034 11418 23035 11419 23035 11420 23035 11420 23036 11419 23036 11676 23036 11420 23037 11676 23037 11421 23037 11120 23038 11422 23038 11683 23038 11120 23039 11683 23039 11121 23039 11121 23040 11683 23040 11423 23040 11121 23041 11423 23041 11424 23041 11424 23042 11423 23042 11425 23042 11424 23043 11425 23043 11426 23043 11426 23044 11425 23044 11686 23044 11426 23045 11686 23045 11124 23045 11124 23046 11686 23046 11688 23046 11124 23047 11688 23047 11427 23047 11427 23048 11688 23048 68 23048 11427 23049 68 23049 220 23049 11428 23050 11430 23050 11429 23050 11429 23051 11430 23051 11132 23051 11429 23052 11132 23052 11689 23052 11429 23053 11431 23053 11428 23053 11428 23054 11431 23054 11692 23054 11428 23055 11692 23055 11136 23055 11136 23056 11692 23056 11691 23056 11691 23057 11432 23057 11136 23057 11136 23058 11432 23058 11434 23058 11136 23059 11434 23059 11433 23059 11434 23060 11694 23060 11433 23060 11433 23061 11694 23061 11435 23061 11433 23062 11435 23062 11436 23062 11435 23063 11696 23063 11436 23063 11436 23064 11696 23064 11697 23064 11436 23065 11697 23065 11437 23065 11151 23066 214 23066 11698 23066 11151 23067 11698 23067 11438 23067 11438 23068 11698 23068 11699 23068 11438 23069 11699 23069 11439 23069 11439 23070 11699 23070 11440 23070 11439 23071 11440 23071 11441 23071 11441 23072 11440 23072 11701 23072 11441 23073 11701 23073 11442 23073 11442 23074 11701 23074 11444 23074 11442 23075 11444 23075 11443 23075 11443 23076 11444 23076 47 23076 11443 23077 47 23077 11146 23077 11445 23078 11708 23078 11446 23078 11445 23079 11446 23079 11157 23079 11157 23080 11446 23080 11447 23080 11157 23081 11447 23081 11448 23081 11448 23082 11447 23082 11705 23082 11448 23083 11705 23083 11165 23083 11165 23084 11705 23084 11704 23084 11165 23085 11704 23085 11164 23085 11164 23086 11704 23086 11703 23086 11164 23087 11703 23087 11449 23087 11449 23088 11703 23088 37 23088 11449 23089 37 23089 11163 23089 204 23090 206 23090 11450 23090 11450 23091 206 23091 11830 23091 11450 23092 11830 23092 11451 23092 11451 23093 11830 23093 11829 23093 11451 23094 11829 23094 11452 23094 11452 23095 11829 23095 11828 23095 11452 23096 11828 23096 11169 23096 11169 23097 11828 23097 11453 23097 11169 23098 11453 23098 11454 23098 11454 23099 11453 23099 11455 23099 11454 23100 11455 23100 196 23100 196 23101 11455 23101 197 23101 11172 23102 11456 23102 11457 23102 11457 23103 11456 23103 11815 23103 11457 23104 11815 23104 11458 23104 11458 23105 11815 23105 11817 23105 11458 23106 11817 23106 11175 23106 11175 23107 11817 23107 11459 23107 11175 23108 11459 23108 11177 23108 11177 23109 11459 23109 11822 23109 11177 23110 11822 23110 11460 23110 11460 23111 11822 23111 11461 23111 11460 23112 11461 23112 11462 23112 11462 23113 11461 23113 188 23113 174 23114 11885 23114 11180 23114 11180 23115 11885 23115 11883 23115 11180 23116 11883 23116 11463 23116 11463 23117 11883 23117 11464 23117 11463 23118 11464 23118 11185 23118 11185 23119 11464 23119 11465 23119 11185 23120 11465 23120 11466 23120 11466 23121 11465 23121 11467 23121 11466 23122 11467 23122 11468 23122 11468 23123 11467 23123 11469 23123 11468 23124 11469 23124 184 23124 184 23125 11469 23125 186 23125 11470 23126 11874 23126 11471 23126 11471 23127 11874 23127 11877 23127 11471 23128 11877 23128 11472 23128 11472 23129 11877 23129 11860 23129 11472 23130 11860 23130 11473 23130 11473 23131 11860 23131 11863 23131 11473 23132 11863 23132 11474 23132 11474 23133 11863 23133 11875 23133 11474 23134 11875 23134 11475 23134 11475 23135 11875 23135 11476 23135 11475 23136 11476 23136 11191 23136 11191 23137 11476 23137 11477 23137 11480 23138 11478 23138 11479 23138 11479 23139 11207 23139 11480 23139 11480 23140 11207 23140 11204 23140 11480 23141 11204 23141 11968 23141 11204 23142 11203 23142 11968 23142 11968 23143 11203 23143 11201 23143 11968 23144 11201 23144 11778 23144 11778 23145 11201 23145 11199 23145 11199 23146 11481 23146 11778 23146 11778 23147 11481 23147 11197 23147 11778 23148 11197 23148 11482 23148 11197 23149 11483 23149 11482 23149 11482 23150 11483 23150 11484 23150 11482 23151 11484 23151 11486 23151 11485 23152 11714 23152 11193 23152 11193 23153 11714 23153 11486 23153 11193 23154 11486 23154 11195 23154 11195 23155 11486 23155 11484 23155 329 23156 11487 23156 11208 23156 11208 23157 11487 23157 11962 23157 11208 23158 11962 23158 11488 23158 11488 23159 11962 23159 11723 23159 11488 23160 11723 23160 11210 23160 11210 23161 11723 23161 11725 23161 11210 23162 11725 23162 11211 23162 11211 23163 11725 23163 11960 23163 11211 23164 11960 23164 11213 23164 11213 23165 11960 23165 11489 23165 11213 23166 11489 23166 319 23166 319 23167 11489 23167 11490 23167 11215 23168 159 23168 11218 23168 11218 23169 159 23169 11492 23169 11218 23170 11492 23170 11491 23170 11491 23171 11492 23171 11731 23171 11491 23172 11731 23172 11220 23172 11220 23173 11731 23173 11730 23173 11220 23174 11730 23174 11223 23174 11223 23175 11730 23175 11729 23175 11223 23176 11729 23176 11225 23176 11225 23177 11729 23177 11728 23177 11225 23178 11728 23178 11226 23178 11226 23179 11728 23179 11727 23179 308 23180 11931 23180 11493 23180 11493 23181 11931 23181 11928 23181 11493 23182 11928 23182 11494 23182 11494 23183 11928 23183 11920 23183 11494 23184 11920 23184 11495 23184 11495 23185 11920 23185 11924 23185 11495 23186 11924 23186 11496 23186 11496 23187 11924 23187 11497 23187 11496 23188 11497 23188 11498 23188 11498 23189 11497 23189 11500 23189 11498 23190 11500 23190 11499 23190 11499 23191 11500 23191 149 23191 301 23192 11501 23192 11502 23192 11502 23193 11501 23193 11503 23193 11502 23194 11503 23194 11229 23194 11229 23195 11503 23195 11504 23195 11229 23196 11504 23196 11230 23196 11230 23197 11504 23197 11505 23197 11230 23198 11505 23198 11232 23198 11232 23199 11505 23199 11736 23199 11232 23200 11736 23200 11233 23200 11233 23201 11736 23201 11734 23201 11233 23202 11734 23202 11506 23202 11506 23203 11734 23203 144 23203 11236 23204 11507 23204 11235 23204 11235 23205 11507 23205 11753 23205 11235 23206 11753 23206 11234 23206 11234 23207 11753 23207 11752 23207 11234 23208 11752 23208 11508 23208 11508 23209 11752 23209 11509 23209 11508 23210 11509 23210 11239 23210 11239 23211 11509 23211 11751 23211 11239 23212 11751 23212 11241 23212 11241 23213 11751 23213 11950 23213 11241 23214 11950 23214 11510 23214 11510 23215 11950 23215 11945 23215 11510 23216 11945 23216 11511 23216 11511 23217 11945 23217 11946 23217 11511 23218 11946 23218 11512 23218 11512 23219 11946 23219 11514 23219 11512 23220 11514 23220 11513 23220 11513 23221 11514 23221 11758 23221 11513 23222 11758 23222 11515 23222 11515 23223 11758 23223 11765 23223 11515 23224 11765 23224 11244 23224 11244 23225 11765 23225 11767 23225 11244 23226 11767 23226 11246 23226 11246 23227 11767 23227 11769 23227 11246 23228 11769 23228 11516 23228 11516 23229 11769 23229 11517 23229 11516 23230 11517 23230 11245 23230 11245 23231 11517 23231 11518 23231 11245 23232 11518 23232 11251 23232 11251 23233 11518 23233 11770 23233 11519 23234 11248 23234 11749 23234 11749 23235 11248 23235 11747 23235 11519 23236 11749 23236 11520 23236 11520 23237 11749 23237 11750 23237 11520 23238 11750 23238 11253 23238 11253 23239 11750 23239 11521 23239 11253 23240 11521 23240 11236 23240 11236 23241 11521 23241 11507 23241 11255 23242 11772 23242 11522 23242 11522 23243 11772 23243 11773 23243 11522 23244 11773 23244 11257 23244 11257 23245 11773 23245 11774 23245 11257 23246 11774 23246 11259 23246 11259 23247 11774 23247 11776 23247 11259 23248 11776 23248 11523 23248 11523 23249 11776 23249 11777 23249 11523 23250 11777 23250 11262 23250 11262 23251 11777 23251 11524 23251 11262 23252 11524 23252 11263 23252 11263 23253 11524 23253 11780 23253 11263 23254 11780 23254 11525 23254 11525 23255 11780 23255 11781 23255 11525 23256 11781 23256 11264 23256 11264 23257 11781 23257 11783 23257 11264 23258 11783 23258 11526 23258 11526 23259 11783 23259 11784 23259 11526 23260 11784 23260 11269 23260 11269 23261 11784 23261 11786 23261 11269 23262 11786 23262 11527 23262 11527 23263 11786 23263 11528 23263 11527 23264 11528 23264 11529 23264 11529 23265 11528 23265 11531 23265 11529 23266 11531 23266 11530 23266 11530 23267 11531 23267 11790 23267 11530 23268 11790 23268 11532 23268 11532 23269 11790 23269 11789 23269 11532 23270 11789 23270 11533 23270 11533 23271 11789 23271 11534 23271 11533 23272 11534 23272 11270 23272 11270 23273 11534 23273 11788 23273 11270 23274 11788 23274 11535 23274 11535 23275 11788 23275 11787 23275 11277 23276 11535 23276 11536 23276 11536 23277 11535 23277 11787 23277 11277 23278 11536 23278 11537 23278 11537 23279 11536 23279 11538 23279 11537 23280 11538 23280 11275 23280 11275 23281 11538 23281 11539 23281 11540 23282 11541 23282 11542 23282 11542 23283 11541 23283 11543 23283 11542 23284 11543 23284 11279 23284 11279 23285 11543 23285 11544 23285 11279 23286 11544 23286 11280 23286 11280 23287 11544 23287 138 23287 141 23288 142 23288 11283 23288 11283 23289 142 23289 11545 23289 11283 23290 11545 23290 11281 23290 11281 23291 11545 23291 11546 23291 11281 23292 11546 23292 11285 23292 11285 23293 11546 23293 11547 23293 11285 23294 11547 23294 11548 23294 11548 23295 11547 23295 11796 23295 11548 23296 11796 23296 11286 23296 11286 23297 11796 23297 11549 23297 11286 23298 11549 23298 11289 23298 11289 23299 11549 23299 11775 23299 11289 23300 11775 23300 11550 23300 11550 23301 11775 23301 11551 23301 11550 23302 11551 23302 11552 23302 11552 23303 11551 23303 11771 23303 11552 23304 11771 23304 11553 23304 11553 23305 11771 23305 11797 23305 11553 23306 11797 23306 11290 23306 11290 23307 11797 23307 11798 23307 11290 23308 11798 23308 11293 23308 11293 23309 11798 23309 11982 23309 11298 23310 11293 23310 11554 23310 11554 23311 11293 23311 11982 23311 11298 23312 11554 23312 11555 23312 11555 23313 11554 23313 11800 23313 11555 23314 11800 23314 11295 23314 11295 23315 11800 23315 11801 23315 11295 23316 11801 23316 11540 23316 11540 23317 11801 23317 11541 23317 11556 23318 11557 23318 11300 23318 11300 23319 11557 23319 11806 23319 11300 23320 11806 23320 11559 23320 11559 23321 11806 23321 11558 23321 11559 23322 11558 23322 11301 23322 11301 23323 11558 23323 11810 23323 11301 23324 11810 23324 11302 23324 11302 23325 11810 23325 11561 23325 11302 23326 11561 23326 11560 23326 11560 23327 11561 23327 11808 23327 11562 23328 11563 23328 11821 23328 11821 23329 11563 23329 11303 23329 11821 23330 11303 23330 11820 23330 137 23331 11811 23331 11303 23331 11303 23332 11811 23332 11564 23332 11303 23333 11564 23333 11820 23333 11563 23334 11562 23334 11565 23334 11565 23335 11562 23335 11566 23335 11565 23336 11566 23336 11567 23336 11567 23337 11566 23337 11891 23337 11567 23338 11891 23338 11568 23338 11568 23339 11891 23339 11569 23339 11568 23340 11569 23340 11306 23340 11306 23341 11569 23341 11823 23341 11306 23342 11823 23342 11570 23342 11570 23343 11823 23343 11571 23343 11570 23344 11571 23344 11573 23344 11573 23345 11571 23345 11803 23345 11572 23346 11307 23346 11825 23346 11825 23347 11307 23347 11574 23347 11825 23348 11574 23348 11802 23348 11573 23349 11803 23349 289 23349 289 23350 11803 23350 11802 23350 289 23351 11802 23351 288 23351 288 23352 11802 23352 11574 23352 11311 23353 11307 23353 11575 23353 11575 23354 11307 23354 11572 23354 11311 23355 11575 23355 11576 23355 11576 23356 11575 23356 11805 23356 11576 23357 11805 23357 11312 23357 11312 23358 11805 23358 11804 23358 11312 23359 11804 23359 11556 23359 11556 23360 11804 23360 11557 23360 11326 23361 11827 23361 11577 23361 11577 23362 11827 23362 11578 23362 11577 23363 11578 23363 11314 23363 11314 23364 11578 23364 11738 23364 11314 23365 11738 23365 11579 23365 11579 23366 11738 23366 11737 23366 11579 23367 11737 23367 11580 23367 11580 23368 11737 23368 11581 23368 11580 23369 11581 23369 11582 23369 11582 23370 11581 23370 11742 23370 11582 23371 11742 23371 11316 23371 11316 23372 11742 23372 11833 23372 11317 23373 11316 23373 11833 23373 11583 23374 11585 23374 11584 23374 11584 23375 11585 23375 11317 23375 11584 23376 11317 23376 11832 23376 11832 23377 11317 23377 11833 23377 11585 23378 11583 23378 11319 23378 11319 23379 11583 23379 11843 23379 11586 23380 136 23380 11322 23380 11322 23381 136 23381 11847 23381 11322 23382 11847 23382 11320 23382 11320 23383 11847 23383 11587 23383 11320 23384 11587 23384 11589 23384 11589 23385 11587 23385 11588 23385 11589 23386 11588 23386 11324 23386 11324 23387 11588 23387 11845 23387 11324 23388 11845 23388 11590 23388 11590 23389 11845 23389 11848 23389 11325 23390 11590 23390 11849 23390 11849 23391 11590 23391 11848 23391 11826 23392 11827 23392 11326 23392 11325 23393 11849 23393 284 23393 284 23394 11849 23394 11591 23394 284 23395 11591 23395 283 23395 283 23396 11591 23396 11826 23396 283 23397 11826 23397 11327 23397 11327 23398 11826 23398 11326 23398 11347 23399 11592 23399 11330 23399 11330 23400 11592 23400 11593 23400 11330 23401 11593 23401 11594 23401 11594 23402 11593 23402 11595 23402 11594 23403 11595 23403 11333 23403 11333 23404 11595 23404 11768 23404 11333 23405 11768 23405 11596 23405 11596 23406 11768 23406 11597 23406 11596 23407 11597 23407 11598 23407 11598 23408 11597 23408 11766 23408 11598 23409 11766 23409 11334 23409 11334 23410 11766 23410 11917 23410 11334 23411 11917 23411 11599 23411 11599 23412 11917 23412 11854 23412 11599 23413 11854 23413 11336 23413 11336 23414 11854 23414 11600 23414 11336 23415 11600 23415 11602 23415 11602 23416 11600 23416 11601 23416 11602 23417 11601 23417 11603 23417 11603 23418 11601 23418 11604 23418 11603 23419 11604 23419 11338 23419 11338 23420 11604 23420 11853 23420 11342 23421 11605 23421 11340 23421 11340 23422 11605 23422 11852 23422 11340 23423 11852 23423 11606 23423 11606 23424 11852 23424 11607 23424 11606 23425 11607 23425 11608 23425 11608 23426 11607 23426 11609 23426 11608 23427 11609 23427 11345 23427 11345 23428 11609 23428 11610 23428 11345 23429 11610 23429 11612 23429 11612 23430 11610 23430 11857 23430 11611 23431 11612 23431 11613 23431 11613 23432 11612 23432 11857 23432 11611 23433 11613 23433 11349 23433 11349 23434 11613 23434 11614 23434 11349 23435 11614 23435 11348 23435 11348 23436 11614 23436 11615 23436 11348 23437 11615 23437 11347 23437 11347 23438 11615 23438 11592 23438 11616 23439 132 23439 11617 23439 11616 23440 11617 23440 11362 23440 11362 23441 11617 23441 11984 23441 11362 23442 11984 23442 11618 23442 11618 23443 11984 23443 11619 23443 11618 23444 11619 23444 11620 23444 11620 23445 11619 23445 11987 23445 11620 23446 11987 23446 11353 23446 11353 23447 11987 23447 11621 23447 11353 23448 11621 23448 11354 23448 11354 23449 11621 23449 11990 23449 11354 23450 11990 23450 11622 23450 11622 23451 11990 23451 11991 23451 11622 23452 11991 23452 11355 23452 11623 23453 11955 23453 11364 23453 11364 23454 11955 23454 11624 23454 11959 23455 11366 23455 11624 23455 11624 23456 11366 23456 11365 23456 11624 23457 11365 23457 11364 23457 11625 23458 11626 23458 11724 23458 11724 23459 11626 23459 11370 23459 11724 23460 11370 23460 11959 23460 11959 23461 11370 23461 11368 23461 11959 23462 11368 23462 11366 23462 11625 23463 11724 23463 11627 23463 11627 23464 11724 23464 11722 23464 11627 23465 11722 23465 11372 23465 11372 23466 11722 23466 11961 23466 11372 23467 11961 23467 11628 23467 11628 23468 11961 23468 11629 23468 11629 23469 11961 23469 11785 23469 11629 23470 11785 23470 274 23470 11993 23471 11942 23471 11630 23471 11630 23472 11942 23472 11944 23472 11630 23473 11944 23473 11631 23473 11631 23474 11944 23474 11632 23474 11631 23475 11632 23475 11376 23475 11376 23476 11632 23476 11633 23476 11376 23477 11633 23477 11634 23477 11634 23478 11633 23478 11636 23478 11634 23479 11636 23479 11635 23479 11635 23480 11636 23480 11947 23480 11635 23481 11947 23481 11638 23481 11638 23482 11947 23482 11637 23482 11638 23483 11637 23483 113 23483 11993 23484 11630 23484 11953 23484 11953 23485 11630 23485 270 23485 11953 23486 270 23486 11639 23486 11641 23487 11640 23487 11642 23487 11641 23488 11642 23488 11643 23488 11643 23489 11642 23489 11644 23489 11643 23490 11644 23490 11645 23490 11645 23491 11644 23491 11646 23491 11645 23492 11646 23492 11760 23492 11646 23493 11383 23493 11760 23493 11760 23494 11383 23494 11647 23494 11760 23495 11647 23495 11648 23495 11647 23496 11382 23496 11648 23496 11648 23497 11382 23497 11649 23497 11648 23498 11649 23498 11650 23498 11650 23499 11649 23499 11651 23499 11650 23500 11651 23500 11652 23500 11652 23501 11651 23501 11653 23501 11652 23502 11653 23502 11654 23502 11654 23503 11653 23503 11655 23503 11654 23504 11655 23504 112 23504 97 23505 11394 23505 11922 23505 11922 23506 11394 23506 11921 23506 11394 23507 11393 23507 11921 23507 11921 23508 11393 23508 11656 23508 11921 23509 11656 23509 11935 23509 11935 23510 11656 23510 11392 23510 11935 23511 11392 23511 11710 23511 11392 23512 11657 23512 11710 23512 11710 23513 11657 23513 11658 23513 11710 23514 11658 23514 11999 23514 11999 23515 11658 23515 11389 23515 11999 23516 11389 23516 12001 23516 12001 23517 11389 23517 11388 23517 12001 23518 11388 23518 11659 23518 11659 23519 11388 23519 11661 23519 11659 23520 11661 23520 11940 23520 105 23521 11941 23521 11386 23521 11386 23522 11941 23522 11940 23522 11386 23523 11940 23523 11660 23523 11660 23524 11940 23524 11661 23524 11404 23525 11403 23525 11913 23525 11913 23526 11403 23526 11662 23526 11403 23527 11663 23527 11662 23527 11662 23528 11663 23528 11402 23528 11662 23529 11402 23529 11915 23529 11915 23530 11402 23530 11401 23530 11915 23531 11401 23531 11664 23531 11664 23532 11401 23532 12003 23532 12003 23533 11401 23533 11399 23533 12003 23534 11399 23534 11932 23534 11399 23535 11398 23535 11932 23535 11932 23536 11398 23536 11665 23536 11932 23537 11665 23537 11933 23537 11665 23538 11666 23538 11933 23538 11933 23539 11666 23539 11667 23539 11933 23540 11667 23540 11929 23540 248 23541 96 23541 11396 23541 11396 23542 96 23542 11929 23542 11396 23543 11929 23543 11397 23543 11397 23544 11929 23544 11667 23544 11668 23545 11904 23545 11669 23545 11669 23546 11904 23546 11903 23546 11669 23547 11903 23547 82 23547 11668 23548 11669 23548 11670 23548 11670 23549 11669 23549 11408 23549 11670 23550 11408 23550 11908 23550 11908 23551 11408 23551 11671 23551 11908 23552 11671 23552 11672 23552 11672 23553 11671 23553 11674 23553 11672 23554 11674 23554 11673 23554 11673 23555 11674 23555 11405 23555 11673 23556 11405 23556 11740 23556 11740 23557 11405 23557 11675 23557 11740 23558 11675 23558 11741 23558 11899 23559 11676 23559 12010 23559 12010 23560 11676 23560 11419 23560 12010 23561 11419 23561 12007 23561 12007 23562 11419 23562 11838 23562 11838 23563 11419 23563 11418 23563 11838 23564 11418 23564 11839 23564 11839 23565 11418 23565 11417 23565 11839 23566 11417 23566 11840 23566 11417 23567 11416 23567 11840 23567 11840 23568 11416 23568 11415 23568 11840 23569 11415 23569 11678 23569 11415 23570 11677 23570 11678 23570 11678 23571 11677 23571 11413 23571 11678 23572 11413 23572 11680 23572 11413 23573 11679 23573 11680 23573 11680 23574 11679 23574 11411 23574 11680 23575 11411 23575 11841 23575 11841 23576 11411 23576 230 23576 11841 23577 230 23577 11681 23577 11422 23578 58 23578 11682 23578 11422 23579 11682 23579 11683 23579 11683 23580 11682 23580 11807 23580 11683 23581 11807 23581 11423 23581 11423 23582 11807 23582 11684 23582 11423 23583 11684 23583 11425 23583 11425 23584 11684 23584 11685 23584 11425 23585 11685 23585 11686 23585 11686 23586 11685 23586 11687 23586 11686 23587 11687 23587 11688 23587 11688 23588 11687 23588 11897 23588 11688 23589 11897 23589 68 23589 11893 23590 11429 23590 11892 23590 11892 23591 11429 23591 11689 23591 11892 23592 11689 23592 11890 23592 11432 23593 11691 23593 11690 23593 11690 23594 11691 23594 11692 23594 11690 23595 11692 23595 11893 23595 11893 23596 11692 23596 11431 23596 11893 23597 11431 23597 11429 23597 11432 23598 11690 23598 11434 23598 11434 23599 11690 23599 11693 23599 11434 23600 11693 23600 11694 23600 11694 23601 11693 23601 11894 23601 11694 23602 11894 23602 11435 23602 11435 23603 11894 23603 11695 23603 11435 23604 11695 23604 11696 23604 11696 23605 11695 23605 11896 23605 11696 23606 11896 23606 11697 23606 214 23607 11873 23607 11871 23607 214 23608 11871 23608 11698 23608 11698 23609 11871 23609 11869 23609 11698 23610 11869 23610 11699 23610 11699 23611 11869 23611 11700 23611 11699 23612 11700 23612 11440 23612 11440 23613 11700 23613 11867 23613 11440 23614 11867 23614 11701 23614 11701 23615 11867 23615 11702 23615 11701 23616 11702 23616 11444 23616 11444 23617 11702 23617 48 23617 11444 23618 48 23618 47 23618 38 23619 37 23619 11870 23619 11870 23620 37 23620 11703 23620 11870 23621 11703 23621 11795 23621 11795 23622 11703 23622 11704 23622 11795 23623 11704 23623 11794 23623 11794 23624 11704 23624 11705 23624 11794 23625 11705 23625 11706 23625 11706 23626 11705 23626 11447 23626 11706 23627 11447 23627 11793 23627 11793 23628 11447 23628 11446 23628 11793 23629 11446 23629 11707 23629 11707 23630 11446 23630 11708 23630 11707 23631 11708 23631 11979 23631 11980 23632 14 23632 18 23632 11974 23633 11976 23633 18 23633 22 23634 11964 23634 11713 23634 11992 23635 11721 23635 11958 23635 11721 23636 11992 23636 11951 23636 11709 23637 11939 23637 11998 23637 11710 23638 11999 23638 11936 23638 11915 23639 11664 23639 11914 23639 11745 23640 11911 23640 11914 23640 54 23641 11711 23641 10 23641 42 23642 12 23642 11879 23642 11742 23643 11834 23643 11833 23643 11821 23644 11818 23644 11562 23644 11864 23645 11544 23645 11543 23645 11501 23646 148 23646 11907 23646 165 23647 11964 23647 11712 23647 11712 23648 11964 23648 11965 23648 11712 23649 11965 23649 11716 23649 165 23650 163 23650 11964 23650 11964 23651 163 23651 11478 23651 11964 23652 11478 23652 11713 23652 11713 23653 11478 23653 11480 23653 11713 23654 11480 23654 19 23654 11778 23655 11482 23655 11780 23655 11482 23656 11486 23656 11780 23656 11780 23657 11486 23657 11714 23657 11780 23658 11714 23658 11781 23658 11781 23659 11714 23659 11715 23659 11781 23660 11715 23660 11716 23660 11487 23661 11718 23661 11949 23661 11717 23662 11719 23662 161 23662 11951 23663 161 23663 160 23663 11949 23664 11718 23664 117 23664 117 23665 11718 23665 162 23665 117 23666 162 23666 11719 23666 11719 23667 162 23667 11720 23667 11719 23668 11720 23668 161 23668 11951 23669 160 23669 11721 23669 11721 23670 160 23670 11490 23670 11721 23671 11490 23671 11958 23671 11958 23672 11490 23672 11489 23672 11958 23673 11489 23673 11960 23673 11962 23674 11722 23674 11723 23674 11723 23675 11722 23675 11724 23675 11723 23676 11724 23676 11725 23676 11725 23677 11724 23677 11959 23677 11764 23678 11727 23678 11996 23678 11996 23679 11727 23679 11726 23679 11996 23680 11726 23680 11943 23680 11727 23681 11728 23681 11726 23681 11726 23682 11728 23682 11729 23682 11726 23683 11729 23683 11948 23683 11948 23684 11729 23684 11730 23684 11948 23685 11730 23685 11946 23685 11730 23686 11731 23686 11946 23686 11946 23687 11731 23687 11492 23687 11946 23688 11492 23688 11514 23688 11514 23689 11492 23689 159 23689 159 23690 11732 23690 11514 23690 11514 23691 11732 23691 158 23691 11514 23692 158 23692 11762 23692 11762 23693 158 23693 11733 23693 11762 23694 11733 23694 157 23694 11734 23695 11736 23695 11739 23695 11672 23696 11673 23696 11503 23696 11734 23697 11739 23697 144 23697 144 23698 11739 23698 11910 23698 144 23699 11910 23699 11735 23699 11505 23700 11581 23700 11736 23700 11736 23701 11581 23701 11737 23701 11736 23702 11737 23702 11739 23702 11739 23703 11737 23703 11738 23703 11739 23704 11738 23704 11578 23704 11503 23705 11673 23705 11504 23705 11504 23706 11673 23706 11740 23706 11504 23707 11740 23707 11505 23707 11505 23708 11740 23708 11741 23708 11505 23709 11741 23709 11581 23709 11581 23710 11741 23710 88 23710 11581 23711 88 23711 11742 23711 11742 23712 88 23712 87 23712 11742 23713 87 23713 11834 23713 11735 23714 11910 23714 11743 23714 11743 23715 11910 23715 11911 23715 11743 23716 11911 23716 146 23716 146 23717 11911 23717 11745 23717 146 23718 11745 23718 11744 23718 11907 23719 148 23719 11745 23719 11745 23720 148 23720 11746 23720 11745 23721 11746 23721 11744 23721 11521 23722 11748 23722 11507 23722 11507 23723 11748 23723 11791 23723 11747 23724 11858 23724 11749 23724 11749 23725 11858 23725 11748 23725 11749 23726 11748 23726 11750 23726 11750 23727 11748 23727 11521 23727 11751 23728 11509 23728 11792 23728 11792 23729 11509 23729 11752 23729 11792 23730 11752 23730 11791 23730 11791 23731 11752 23731 11753 23731 11791 23732 11753 23732 11507 23732 112 23733 11754 23733 11762 23733 11754 23734 11755 23734 11762 23734 11762 23735 11755 23735 11756 23735 11762 23736 11756 23736 11514 23736 11514 23737 11756 23737 11757 23737 11514 23738 11757 23738 11758 23738 11757 23739 107 23739 11758 23739 11758 23740 107 23740 11641 23740 11758 23741 11641 23741 11759 23741 11759 23742 11641 23742 11643 23742 11759 23743 11643 23743 11645 23743 11650 23744 11998 23744 11648 23744 11648 23745 11998 23745 11760 23745 11652 23746 11654 23746 11761 23746 11761 23747 11654 23747 112 23747 11761 23748 112 23748 11995 23748 11995 23749 112 23749 11762 23749 11995 23750 11762 23750 11763 23750 11763 23751 11762 23751 157 23751 11763 23752 157 23752 11996 23752 11996 23753 157 23753 156 23753 11996 23754 156 23754 11764 23754 11938 23755 11767 23755 11759 23755 11759 23756 11767 23756 11765 23756 11759 23757 11765 23757 11758 23757 11917 23758 11766 23758 102 23758 102 23759 11766 23759 11597 23759 102 23760 11597 23760 11768 23760 11938 23761 102 23761 11767 23761 11767 23762 102 23762 11768 23762 11767 23763 11768 23763 11769 23763 11769 23764 11768 23764 11595 23764 11769 23765 11595 23765 11517 23765 11517 23766 11595 23766 11593 23766 11517 23767 11593 23767 11518 23767 11518 23768 11593 23768 11592 23768 11518 23769 11592 23769 11770 23769 11770 23770 11592 23770 11858 23770 11770 23771 11858 23771 143 23771 143 23772 11858 23772 11747 23772 11797 23773 11771 23773 11772 23773 11539 23774 11538 23774 11799 23774 11772 23775 11771 23775 11773 23775 11773 23776 11771 23776 11551 23776 11773 23777 11551 23777 11774 23777 11774 23778 11551 23778 11775 23778 11774 23779 11775 23779 11776 23779 11776 23780 11775 23780 11549 23780 11776 23781 11549 23781 11777 23781 11777 23782 11549 23782 11977 23782 11777 23783 11977 23783 11524 23783 11983 23784 11969 23784 11779 23784 11983 23785 11779 23785 11985 23785 11968 23786 11778 23786 11779 23786 11779 23787 11778 23787 11780 23787 11779 23788 11780 23788 11985 23788 11985 23789 11780 23789 11986 23789 11716 23790 11965 23790 11781 23790 11781 23791 11965 23791 11782 23791 11781 23792 11782 23792 11783 23792 11783 23793 11782 23793 11785 23793 11783 23794 11785 23794 11784 23794 11784 23795 11785 23795 11961 23795 11784 23796 11961 23796 11786 23796 11792 23797 11528 23797 11786 23797 11788 23798 11748 23798 11787 23798 11787 23799 11748 23799 11799 23799 11787 23800 11799 23800 11536 23800 11536 23801 11799 23801 11538 23801 11788 23802 11534 23802 11748 23802 11748 23803 11534 23803 11789 23803 11748 23804 11789 23804 11791 23804 11791 23805 11789 23805 11790 23805 11791 23806 11790 23806 11792 23806 11792 23807 11790 23807 11531 23807 11792 23808 11531 23808 11528 23808 11867 23809 11865 23809 11702 23809 11702 23810 11865 23810 11881 23810 11702 23811 11881 23811 48 23811 11976 23812 11977 23812 11793 23812 11706 23813 11547 23813 11794 23813 11794 23814 11547 23814 11546 23814 11794 23815 11546 23815 11795 23815 11795 23816 11546 23816 11545 23816 11795 23817 11545 23817 11870 23817 11706 23818 11793 23818 11547 23818 11547 23819 11793 23819 11977 23819 11547 23820 11977 23820 11796 23820 11796 23821 11977 23821 11549 23821 11772 23822 11539 23822 11797 23822 11797 23823 11539 23823 11799 23823 11797 23824 11799 23824 11798 23824 11798 23825 11799 23825 11982 23825 11824 23826 11800 23826 11554 23826 11825 23827 11541 23827 11824 23827 11824 23828 11541 23828 11801 23828 11824 23829 11801 23829 11800 23829 11825 23830 11802 23830 11541 23830 11541 23831 11802 23831 11803 23831 11541 23832 11803 23832 11543 23832 11543 23833 11803 23833 11571 23833 11543 23834 11571 23834 11864 23834 11804 23835 11805 23835 11846 23835 11810 23836 11558 23836 11809 23836 11809 23837 11558 23837 11806 23837 11809 23838 11806 23838 11846 23838 11846 23839 11806 23839 11557 23839 11846 23840 11557 23840 11804 23840 11808 23841 11561 23841 11807 23841 11808 23842 11807 23842 11811 23842 11687 23843 11685 23843 11900 23843 11900 23844 11685 23844 11684 23844 11900 23845 11684 23845 11809 23845 11809 23846 11684 23846 11807 23846 11809 23847 11807 23847 11810 23847 11810 23848 11807 23848 11561 23848 11807 23849 11682 23849 11811 23849 11811 23850 11682 23850 58 23850 11811 23851 58 23851 11564 23851 2 23852 3 23852 11812 23852 11812 23853 3 23853 11813 23853 58 23854 60 23854 11564 23854 11564 23855 60 23855 11814 23855 11564 23856 11814 23856 3 23856 3 23857 11814 23857 63 23857 3 23858 63 23858 11813 23858 195 23859 3 23859 11456 23859 11456 23860 3 23860 11816 23860 11456 23861 11816 23861 11815 23861 11815 23862 11816 23862 11817 23862 11817 23863 11816 23863 5 23863 11817 23864 5 23864 11459 23864 11459 23865 5 23865 11818 23865 11459 23866 11818 23866 11822 23866 195 23867 193 23867 3 23867 3 23868 193 23868 192 23868 3 23869 192 23869 11564 23869 11564 23870 192 23870 11819 23870 11564 23871 11819 23871 11820 23871 11820 23872 11819 23872 189 23872 11820 23873 189 23873 11821 23873 11821 23874 189 23874 188 23874 11821 23875 188 23875 11818 23875 11818 23876 188 23876 11461 23876 11818 23877 11461 23877 11822 23877 11571 23878 11823 23878 11864 23878 11864 23879 11823 23879 11569 23879 11864 23880 11569 23880 11865 23880 11865 23881 11569 23881 11891 23881 11981 23882 11575 23882 11824 23882 11824 23883 11575 23883 11572 23883 11824 23884 11572 23884 11825 23884 11826 23885 11591 23885 11856 23885 11609 23886 11607 23886 11827 23886 11453 23887 11828 23887 11584 23887 11584 23888 11828 23888 12008 23888 11828 23889 11829 23889 12008 23889 12008 23890 11829 23890 11830 23890 12008 23891 11830 23891 11831 23891 11453 23892 11584 23892 11455 23892 11455 23893 11584 23893 11832 23893 11455 23894 11832 23894 197 23894 197 23895 11832 23895 11833 23895 197 23896 11833 23896 11835 23896 11835 23897 11833 23897 11834 23897 11835 23898 11834 23898 200 23898 200 23899 11834 23899 11836 23899 11836 23900 11834 23900 12009 23900 11836 23901 12009 23901 11837 23901 11830 23902 206 23902 11831 23902 11831 23903 206 23903 205 23903 11831 23904 205 23904 12009 23904 12009 23905 205 23905 203 23905 12009 23906 203 23906 11837 23906 11839 23907 12008 23907 11838 23907 11838 23908 12008 23908 12007 23908 11583 23909 11584 23909 11841 23909 11839 23910 11840 23910 12008 23910 12008 23911 11840 23911 11678 23911 12008 23912 11678 23912 11584 23912 11584 23913 11678 23913 11680 23913 11584 23914 11680 23914 11841 23914 136 23915 135 23915 11809 23915 11809 23916 135 23916 11844 23916 11809 23917 11844 23917 11900 23917 11900 23918 11844 23918 11842 23918 11900 23919 11842 23919 75 23919 11841 23920 11681 23920 11583 23920 11583 23921 11681 23921 81 23921 11583 23922 81 23922 11843 23922 11843 23923 81 23923 11844 23923 11843 23924 11844 23924 134 23924 134 23925 11844 23925 135 23925 11846 23926 11848 23926 11845 23926 11845 23927 11588 23927 11846 23927 11846 23928 11588 23928 11587 23928 11846 23929 11587 23929 11809 23929 11809 23930 11587 23930 11847 23930 11809 23931 11847 23931 136 23931 11805 23932 11575 23932 11846 23932 11846 23933 11575 23933 11981 23933 11846 23934 11981 23934 11848 23934 11848 23935 11981 23935 11856 23935 11848 23936 11856 23936 11849 23936 11849 23937 11856 23937 11591 23937 11919 23938 11851 23938 11850 23938 11850 23939 11851 23939 94 23939 11850 23940 94 23940 93 23940 11827 23941 11607 23941 11578 23941 11578 23942 11607 23942 11852 23942 11578 23943 11852 23943 11739 23943 11739 23944 11852 23944 11605 23944 11739 23945 11605 23945 11853 23945 11917 23946 11919 23946 11854 23946 11854 23947 11919 23947 11850 23947 11854 23948 11850 23948 11600 23948 11600 23949 11850 23949 93 23949 11600 23950 93 23950 11601 23950 11601 23951 93 23951 11855 23951 11601 23952 11855 23952 11604 23952 11604 23953 11855 23953 11853 23953 11827 23954 11826 23954 11609 23954 11609 23955 11826 23955 11856 23955 11609 23956 11856 23956 11610 23956 11610 23957 11856 23957 11857 23957 11592 23958 11615 23958 11858 23958 11858 23959 11615 23959 11614 23959 11858 23960 11614 23960 11613 23960 15 23961 34 23961 16 23961 16 23962 34 23962 35 23962 16 23963 35 23963 11876 23963 170 23964 169 23964 11870 23964 11859 23965 173 23965 11871 23965 11871 23966 173 23966 171 23966 11877 23967 11879 23967 11860 23967 11860 23968 11879 23968 11861 23968 11860 23969 11861 23969 11863 23969 11863 23970 11861 23970 11862 23970 11863 23971 11862 23971 11875 23971 11544 23972 11864 23972 138 23972 138 23973 11864 23973 11865 23973 138 23974 11865 23974 11866 23974 11866 23975 11865 23975 11867 23975 11866 23976 11867 23976 11868 23976 11868 23977 11867 23977 11700 23977 11868 23978 11700 23978 142 23978 142 23979 11700 23979 11869 23979 142 23980 11869 23980 11545 23980 11545 23981 11869 23981 11871 23981 11545 23982 11871 23982 11870 23982 11870 23983 11871 23983 171 23983 11870 23984 171 23984 170 23984 11859 23985 11871 23985 11872 23985 11872 23986 11871 23986 11873 23986 11872 23987 11873 23987 11874 23987 11874 23988 11873 23988 11878 23988 11874 23989 11878 23989 11877 23989 11875 23990 11862 23990 11476 23990 11476 23991 11862 23991 16 23991 11476 23992 16 23992 11477 23992 11477 23993 16 23993 11876 23993 11477 23994 11876 23994 169 23994 169 23995 11876 23995 38 23995 169 23996 38 23996 11870 23996 11877 23997 11878 23997 11879 23997 11879 23998 11878 23998 39 23998 11879 23999 39 23999 42 23999 46 24000 9 24000 11880 24000 11880 24001 9 24001 44 24001 11889 24002 180 24002 11865 24002 46 24003 48 24003 9 24003 9 24004 48 24004 11881 24004 9 24005 11881 24005 11882 24005 11882 24006 11881 24006 11469 24006 11882 24007 11469 24007 11467 24007 11887 24008 11464 24008 11883 24008 180 24009 181 24009 11865 24009 11865 24010 181 24010 11884 24010 11865 24011 11884 24011 11881 24011 11881 24012 11884 24012 186 24012 11881 24013 186 24013 11469 24013 175 24014 178 24014 49 24014 11887 24015 11883 24015 49 24015 49 24016 11883 24016 11885 24016 49 24017 11885 24017 175 24017 11467 24018 11465 24018 11882 24018 11882 24019 11465 24019 11464 24019 11882 24020 11464 24020 11886 24020 11886 24021 11464 24021 11887 24021 11886 24022 11887 24022 10 24022 10 24023 11887 24023 11888 24023 10 24024 11888 24024 54 24024 178 24025 11889 24025 49 24025 49 24026 11889 24026 11865 24026 49 24027 11865 24027 11890 24027 11890 24028 11865 24028 11891 24028 11890 24029 11891 24029 11892 24029 11892 24030 11891 24030 11566 24030 11892 24031 11566 24031 11893 24031 11893 24032 11566 24032 11562 24032 11893 24033 11562 24033 11690 24033 11690 24034 11562 24034 11818 24034 11690 24035 11818 24035 11693 24035 11693 24036 11818 24036 5 24036 11693 24037 5 24037 11894 24037 7 24038 11895 24038 8 24038 8 24039 11895 24039 11896 24039 8 24040 11896 24040 5 24040 5 24041 11896 24041 11695 24041 5 24042 11695 24042 11894 24042 11687 24043 11900 24043 11897 24043 11897 24044 11900 24044 4 24044 11897 24045 4 24045 11898 24045 12010 24046 12011 24046 11899 24046 11899 24047 12011 24047 11900 24047 11899 24048 11900 24048 11901 24048 11901 24049 11900 24049 75 24049 11906 24050 11903 24050 12009 24050 12009 24051 11903 24051 11902 24051 11902 24052 11903 24052 11904 24052 11902 24053 11904 24053 11668 24053 87 24054 85 24054 11834 24054 11834 24055 85 24055 11905 24055 11834 24056 11905 24056 12009 24056 12009 24057 11905 24057 83 24057 12009 24058 83 24058 11906 24058 11503 24059 11501 24059 11672 24059 11672 24060 11501 24060 11907 24060 11672 24061 11907 24061 11908 24061 11908 24062 11907 24062 11670 24062 11853 24063 11855 24063 11739 24063 11739 24064 11855 24064 11909 24064 11739 24065 11909 24065 11910 24065 11910 24066 11909 24066 11912 24066 11910 24067 11912 24067 11911 24067 11911 24068 11912 24068 11913 24068 11911 24069 11913 24069 11914 24069 11914 24070 11913 24070 11662 24070 11914 24071 11662 24071 11915 24071 102 24072 11916 24072 11917 24072 11917 24073 11916 24073 11918 24073 11917 24074 11918 24074 11919 24074 11919 24075 11918 24075 11923 24075 11919 24076 11923 24076 11851 24076 11851 24077 11923 24077 11924 24077 11934 24078 149 24078 11921 24078 11924 24079 11920 24079 11851 24079 11851 24080 11920 24080 11928 24080 11851 24081 11928 24081 96 24081 11921 24082 149 24082 11922 24082 11922 24083 149 24083 11500 24083 11922 24084 11500 24084 11923 24084 11923 24085 11500 24085 11497 24085 11923 24086 11497 24086 11924 24086 11934 24087 11936 24087 11925 24087 11925 24088 11936 24088 11926 24088 11925 24089 11926 24089 11927 24089 11927 24090 11926 24090 12002 24090 11927 24091 12002 24091 153 24091 96 24092 11928 24092 11929 24092 11929 24093 11928 24093 11931 24093 11929 24094 11931 24094 11930 24094 11930 24095 11931 24095 155 24095 11930 24096 155 24096 12002 24096 12002 24097 155 24097 154 24097 12002 24098 154 24098 153 24098 12003 24099 11932 24099 11930 24099 11930 24100 11932 24100 11933 24100 11930 24101 11933 24101 11929 24101 11934 24102 11921 24102 11936 24102 11936 24103 11921 24103 11935 24103 11936 24104 11935 24104 11710 24104 11937 24105 11938 24105 11939 24105 11939 24106 11938 24106 11759 24106 11939 24107 11759 24107 11998 24107 11998 24108 11759 24108 11645 24108 11998 24109 11645 24109 11760 24109 12001 24110 11659 24110 11709 24110 11709 24111 11659 24111 11940 24111 11709 24112 11940 24112 11939 24112 11939 24113 11940 24113 11941 24113 11939 24114 11941 24114 11937 24114 11993 24115 11943 24115 11942 24115 11942 24116 11943 24116 11944 24116 11950 24117 114 24117 11945 24117 11945 24118 114 24118 11637 24118 11945 24119 11637 24119 11946 24119 11946 24120 11637 24120 11947 24120 11946 24121 11947 24121 11948 24121 11948 24122 11947 24122 11636 24122 11948 24123 11636 24123 11726 24123 11726 24124 11636 24124 11633 24124 11726 24125 11633 24125 11943 24125 11943 24126 11633 24126 11632 24126 11943 24127 11632 24127 11944 24127 11487 24128 11949 24128 11963 24128 11963 24129 11949 24129 114 24129 11963 24130 114 24130 11792 24130 11792 24131 114 24131 11950 24131 11792 24132 11950 24132 11751 24132 161 24133 11951 24133 11717 24133 11717 24134 11951 24134 11952 24134 11717 24135 11952 24135 11639 24135 11639 24136 11952 24136 11994 24136 11639 24137 11994 24137 11953 24137 11954 24138 11956 24138 11955 24138 11955 24139 11956 24139 11957 24139 11955 24140 11957 24140 11624 24140 11624 24141 11957 24141 11958 24141 11624 24142 11958 24142 11959 24142 11959 24143 11958 24143 11960 24143 11959 24144 11960 24144 11725 24144 11786 24145 11961 24145 11792 24145 11792 24146 11961 24146 11722 24146 11792 24147 11722 24147 11963 24147 11963 24148 11722 24148 11962 24148 11963 24149 11962 24149 11487 24149 22 24150 123 24150 11964 24150 11964 24151 123 24151 120 24151 11964 24152 120 24152 11965 24152 11965 24153 120 24153 128 24153 11965 24154 128 24154 11782 24154 126 24155 11966 24155 22 24155 22 24156 11966 24156 11967 24156 22 24157 11967 24157 123 24157 11480 24158 11968 24158 19 24158 19 24159 11968 24159 11779 24159 19 24160 11779 24160 20 24160 20 24161 11779 24161 11969 24161 20 24162 11969 24162 21 24162 21 24163 11969 24163 11970 24163 21 24164 11970 24164 0 24164 0 24165 11970 24165 11971 24165 0 24166 11971 24166 11972 24166 25 24167 11973 24167 11974 24167 11974 24168 11973 24168 11975 24168 11974 24169 11975 24169 11976 24169 11975 24170 28 24170 11976 24170 11976 24171 28 24171 30 24171 11976 24172 30 24172 11977 24172 11977 24173 30 24173 11978 24173 11977 24174 11978 24174 11524 24174 11524 24175 11978 24175 11989 24175 11524 24176 11989 24176 11780 24176 11780 24177 11989 24177 11988 24177 11780 24178 11988 24178 11986 24178 11793 24179 11707 24179 11976 24179 11976 24180 11707 24180 11979 24180 11976 24181 11979 24181 18 24181 18 24182 11979 24182 32 24182 18 24183 32 24183 11980 24183 11613 24184 11857 24184 11858 24184 11858 24185 11857 24185 11856 24185 11858 24186 11856 24186 11748 24186 11748 24187 11856 24187 11981 24187 11748 24188 11981 24188 11799 24188 11799 24189 11981 24189 11824 24189 11799 24190 11824 24190 11982 24190 11982 24191 11824 24191 11554 24191 132 24192 11970 24192 11969 24192 132 24193 11969 24193 11617 24193 11617 24194 11969 24194 11983 24194 11617 24195 11983 24195 11984 24195 11984 24196 11983 24196 11985 24196 11984 24197 11985 24197 11619 24197 11619 24198 11985 24198 11986 24198 11619 24199 11986 24199 11987 24199 11987 24200 11986 24200 11988 24200 11987 24201 11988 24201 11621 24201 11621 24202 11988 24202 11989 24202 11621 24203 11989 24203 11990 24203 11990 24204 11989 24204 11978 24204 11990 24205 11978 24205 11991 24205 11652 24206 11761 24206 628 24206 11992 24207 633 24207 11951 24207 11951 24208 633 24208 634 24208 11951 24209 634 24209 11952 24209 11952 24210 634 24210 11994 24210 627 24211 11943 24211 11993 24211 627 24212 11993 24212 634 24212 634 24213 11993 24213 11953 24213 634 24214 11953 24214 11994 24214 11761 24215 11995 24215 628 24215 628 24216 11995 24216 11763 24216 628 24217 11763 24217 627 24217 627 24218 11763 24218 11996 24218 627 24219 11996 24219 11943 24219 11652 24220 628 24220 11650 24220 11650 24221 628 24221 623 24221 11650 24222 623 24222 11998 24222 11998 24223 623 24223 11997 24223 11998 24224 11997 24224 11709 24224 11936 24225 11999 24225 12000 24225 12000 24226 11999 24226 11997 24226 11997 24227 11999 24227 12001 24227 11997 24228 12001 24228 11709 24228 11936 24229 12000 24229 11926 24229 11926 24230 12000 24230 12004 24230 11926 24231 12004 24231 12002 24231 11914 24232 11664 24232 12005 24232 12005 24233 11664 24233 12003 24233 12005 24234 12003 24234 12004 24234 12004 24235 12003 24235 11930 24235 12004 24236 11930 24236 12002 24236 11914 24237 12005 24237 11745 24237 11745 24238 12005 24238 12006 24238 11745 24239 12006 24239 11907 24239 11907 24240 12006 24240 11670 24240 11670 24241 12006 24241 620 24241 11670 24242 620 24242 11668 24242 617 24243 12009 24243 620 24243 620 24244 12009 24244 11902 24244 620 24245 11902 24245 11668 24245 12010 24246 12007 24246 615 24246 615 24247 12007 24247 12008 24247 615 24248 12008 24248 617 24248 617 24249 12008 24249 11831 24249 617 24250 11831 24250 12009 24250 12010 24251 615 24251 12011 24251 12011 24252 615 24252 12012 24252 12011 24253 12012 24253 11900 24253 4161 24254 4160 24254 12013 24254 12013 24255 4160 24255 12017 24255 12013 24256 12017 24256 12014 24256 12019 24257 12015 24257 3974 24257 12016 24258 3977 24258 12017 24258 12017 24259 3977 24259 12018 24259 12017 24260 12018 24260 12014 24260 4160 24261 4158 24261 12017 24261 12017 24262 4158 24262 12019 24262 12017 24263 12019 24263 3975 24263 3975 24264 12019 24264 3974 24264 12020 24265 4149 24265 4148 24265 4151 24266 4149 24266 4150 24266 4150 24267 4149 24267 12020 24267 4150 24268 12020 24268 4153 24268 3981 24269 3980 24269 12020 24269 12020 24270 3980 24270 3979 24270 12020 24271 3979 24271 4153 24271 3978 24272 3986 24272 4146 24272 4146 24273 3986 24273 12020 24273 4146 24274 12020 24274 4147 24274 4147 24275 12020 24275 4148 24275 12025 24276 12021 24276 4139 24276 12022 24277 12023 24277 12024 24277 4144 24278 12025 24278 12028 24278 12028 24279 12025 24279 4139 24279 12028 24280 4139 24280 4137 24280 4137 24281 4139 24281 12026 24281 4137 24282 12027 24282 12028 24282 12028 24283 12027 24283 12022 24283 12028 24284 12022 24284 3990 24284 3990 24285 12022 24285 12024 24285 12029 24286 4130 24286 12030 24286 12031 24287 12032 24287 12037 24287 12033 24288 12029 24288 3992 24288 3992 24289 12029 24289 12030 24289 3992 24290 12030 24290 12034 24290 12034 24291 12030 24291 12035 24291 4134 24292 12030 24292 12036 24292 12036 24293 12030 24293 4130 24293 12036 24294 4130 24294 12037 24294 12037 24295 4130 24295 12038 24295 12037 24296 12038 24296 12031 24296 3994 24297 12042 24297 4127 24297 4127 24298 12042 24298 12039 24298 4127 24299 12039 24299 4121 24299 4124 24300 12040 24300 12041 24300 12041 24301 12040 24301 4127 24301 12041 24302 4127 24302 4122 24302 4122 24303 4127 24303 4121 24303 3997 24304 3998 24304 3995 24304 3995 24305 3998 24305 12042 24305 3995 24306 12042 24306 12043 24306 12043 24307 12042 24307 3994 24307 12047 24308 12044 24308 12045 24308 12045 24309 12044 24309 4114 24309 12046 24310 12045 24310 4118 24310 4118 24311 12045 24311 4114 24311 4118 24312 4114 24312 4117 24312 4117 24313 4114 24313 4115 24313 12049 24314 4002 24314 4005 24314 12045 24315 4119 24315 12047 24315 12047 24316 4119 24316 12049 24316 12047 24317 12049 24317 12048 24317 12048 24318 12049 24318 4005 24318 12056 24319 12050 24319 4008 24319 4012 24320 12050 24320 12051 24320 12051 24321 12050 24321 12056 24321 12051 24322 12056 24322 12052 24322 12053 24323 4106 24323 4110 24323 4110 24324 4106 24324 12054 24324 4110 24325 12054 24325 12055 24325 12055 24326 12054 24326 12056 24326 12055 24327 12056 24327 12057 24327 12057 24328 12056 24328 4008 24328 12057 24329 4008 24329 4007 24329 12060 24330 12058 24330 12062 24330 12058 24331 4016 24331 12062 24331 12062 24332 4016 24332 4017 24332 12062 24333 4017 24333 4018 24333 4100 24334 4103 24334 12059 24334 12059 24335 4103 24335 12060 24335 12059 24336 12060 24336 4098 24336 4098 24337 12060 24337 12062 24337 4018 24338 12061 24338 12062 24338 12062 24339 12061 24339 4020 24339 12062 24340 4020 24340 4021 24340 12067 24341 4088 24341 12063 24341 12063 24342 4088 24342 4090 24342 12063 24343 4090 24343 4089 24343 12064 24344 4090 24344 4092 24344 4092 24345 4090 24345 4088 24345 4092 24346 4088 24346 12065 24346 12065 24347 4088 24347 4094 24347 4023 24348 12066 24348 4026 24348 4026 24349 12066 24349 12067 24349 4026 24350 12067 24350 12068 24350 12068 24351 12067 24351 12063 24351 4082 24352 4034 24352 12073 24352 12069 24353 12070 24353 4082 24353 4082 24354 12070 24354 4079 24354 4082 24355 4079 24355 12071 24355 12071 24356 12072 24356 4082 24356 4082 24357 12072 24357 4036 24357 4082 24358 4036 24358 4034 24358 4087 24359 4084 24359 4029 24359 4029 24360 4084 24360 4082 24360 4029 24361 4082 24361 4030 24361 4030 24362 4082 24362 12073 24362 12074 24363 12075 24363 12076 24363 4046 24364 4045 24364 4043 24364 12077 24365 12078 24365 12079 24365 12079 24366 12078 24366 12074 24366 12079 24367 12074 24367 4073 24367 4073 24368 12074 24368 12076 24368 12074 24369 4048 24369 12075 24369 12075 24370 4048 24370 4046 24370 12075 24371 4046 24371 12080 24371 12080 24372 4046 24372 4043 24372 4053 24373 4051 24373 12084 24373 12083 24374 4070 24374 12081 24374 12081 24375 4070 24375 12082 24375 12081 24376 12082 24376 4065 24376 12083 24377 12081 24377 12084 24377 12084 24378 12081 24378 4055 24378 12084 24379 4055 24379 4053 24379 4061 24380 4058 24380 12085 24380 12085 24381 4058 24381 12081 24381 12085 24382 12081 24382 4066 24382 4066 24383 12081 24383 4065 24383 12097 24384 12094 24384 12093 24384 12091 24385 12094 24385 12097 24385 12086 24386 12091 24386 12097 24386 12097 24387 12092 24387 12087 24387 12088 24388 12092 24388 12097 24388 12093 24389 12088 24389 12097 24389 12096 24390 12089 24390 12090 24390 12090 24391 12089 24391 12091 24391 12095 24392 12090 24392 12099 24392 12099 24393 12090 24393 12091 24393 12099 24394 12091 24394 12098 24394 12098 24395 12091 24395 12086 24395 12092 24396 12088 24396 12093 24396 12089 24397 12087 24397 12091 24397 12091 24398 12087 24398 12092 24398 12091 24399 12092 24399 12094 24399 12094 24400 12092 24400 12093 24400 12097 24401 12087 24401 12089 24401 12097 24402 12090 24402 12095 24402 12096 24403 12090 24403 12097 24403 12089 24404 12096 24404 12097 24404 12097 24405 12098 24405 12086 24405 12099 24406 12098 24406 12097 24406 12095 24407 12099 24407 12097 24407 12110 24408 12105 24408 12107 24408 12100 24409 12105 24409 12110 24409 12104 24410 12100 24410 12110 24410 12110 24411 12109 24411 12111 24411 12101 24412 12109 24412 12110 24412 12107 24413 12101 24413 12110 24413 12106 24414 12109 24414 12101 24414 12102 24415 12103 24415 12112 24415 12100 24416 12104 24416 12105 24416 12105 24417 12104 24417 12106 24417 12105 24418 12106 24418 12107 24418 12107 24419 12106 24419 12101 24419 12106 24420 12108 24420 12109 24420 12109 24421 12108 24421 12102 24421 12109 24422 12102 24422 12111 24422 12111 24423 12102 24423 12112 24423 12110 24424 12103 24424 12102 24424 12112 24425 12103 24425 12110 24425 12111 24426 12112 24426 12110 24426 12110 24427 12106 24427 12104 24427 12108 24428 12106 24428 12110 24428 12102 24429 12108 24429 12110 24429 12119 24430 12115 24430 12117 24430 12117 24431 12115 24431 12114 24431 12113 24432 12114 24432 12116 24432 12116 24433 12114 24433 12115 24433 12116 24434 12115 24434 12120 24434 12120 24435 12115 24435 12119 24435 12113 24436 12116 24436 12118 24436 12118 24437 12116 24437 12120 24437 12114 24438 12113 24438 12117 24438 12117 24439 12113 24439 12118 24439 12117 24440 12118 24440 12119 24440 12119 24441 12118 24441 12120 24441 12123 24442 12128 24442 12121 24442 12121 24443 12128 24443 12122 24443 12123 24444 12127 24444 12128 24444 12128 24445 12127 24445 12125 24445 12124 24446 12125 24446 12126 24446 12126 24447 12125 24447 12127 24447 12126 24448 12127 24448 12121 24448 12121 24449 12127 24449 12123 24449 12128 24450 12125 24450 12122 24450 12122 24451 12125 24451 12124 24451 12122 24452 12124 24452 12121 24452 12121 24453 12124 24453 12126 24453 12131 24454 12133 24454 12130 24454 12130 24455 12133 24455 12136 24455 12133 24456 12134 24456 12136 24456 12136 24457 12134 24457 12135 24457 12135 24458 12134 24458 12129 24458 12129 24459 12134 24459 12132 24459 12130 24460 12129 24460 12131 24460 12131 24461 12129 24461 12132 24461 12131 24462 12132 24462 12133 24462 12133 24463 12132 24463 12134 24463 12135 24464 12129 24464 12136 24464 12136 24465 12129 24465 12130 24465 12139 24466 12142 24466 12141 24466 12141 24467 12142 24467 12137 24467 12138 24468 12139 24468 12140 24468 12140 24469 12139 24469 12141 24469 12140 24470 12141 24470 12144 24470 12144 24471 12141 24471 12137 24471 12144 24472 12143 24472 12140 24472 12140 24473 12143 24473 12138 24473 12139 24474 12138 24474 12142 24474 12142 24475 12138 24475 12143 24475 12142 24476 12143 24476 12137 24476 12137 24477 12143 24477 12144 24477 12146 24478 12145 24478 12147 24478 12147 24479 12145 24479 12152 24479 12147 24480 12152 24480 12150 24480 12150 24481 12152 24481 12151 24481 12146 24482 12147 24482 12149 24482 12149 24483 12147 24483 12150 24483 12145 24484 12146 24484 12148 24484 12148 24485 12146 24485 12149 24485 12148 24486 12149 24486 12151 24486 12151 24487 12149 24487 12150 24487 12151 24488 12152 24488 12148 24488 12148 24489 12152 24489 12145 24489 12158 24490 12159 24490 12157 24490 12157 24491 12159 24491 12153 24491 12154 24492 12160 24492 12156 24492 12156 24493 12160 24493 12155 24493 12156 24494 12155 24494 12157 24494 12157 24495 12155 24495 12158 24495 12153 24496 12154 24496 12157 24496 12157 24497 12154 24497 12156 24497 12153 24498 12159 24498 12154 24498 12154 24499 12159 24499 12160 24499 12155 24500 12160 24500 12158 24500 12158 24501 12160 24501 12159 24501 12165 24502 12164 24502 12161 24502 12161 24503 12164 24503 12162 24503 12161 24504 12162 24504 12166 24504 12166 24505 12162 24505 12168 24505 12167 24506 12164 24506 12163 24506 12163 24507 12164 24507 12165 24507 12161 24508 12166 24508 12165 24508 12165 24509 12166 24509 12163 24509 12166 24510 12168 24510 12163 24510 12163 24511 12168 24511 12167 24511 12167 24512 12168 24512 12164 24512 12164 24513 12168 24513 12162 24513 12174 24514 12169 24514 12170 24514 12170 24515 12169 24515 12172 24515 12170 24516 12172 24516 12171 24516 12171 24517 12172 24517 12176 24517 12174 24518 12170 24518 12175 24518 12175 24519 12170 24519 12171 24519 12176 24520 12172 24520 12173 24520 12173 24521 12172 24521 12169 24521 12169 24522 12174 24522 12173 24522 12173 24523 12174 24523 12175 24523 12173 24524 12175 24524 12176 24524 12176 24525 12175 24525 12171 24525 12180 24526 12177 24526 12183 24526 12178 24527 12177 24527 12180 24527 12184 24528 12178 24528 12180 24528 12180 24529 12186 24529 12179 24529 12185 24530 12186 24530 12180 24530 12183 24531 12185 24531 12180 24531 12184 24532 12188 24532 12186 24532 12181 24533 12182 24533 12190 24533 12177 24534 12178 24534 12183 24534 12183 24535 12178 24535 12184 24535 12183 24536 12184 24536 12185 24536 12185 24537 12184 24537 12186 24537 12179 24538 12186 24538 12187 24538 12187 24539 12186 24539 12188 24539 12187 24540 12188 24540 12190 24540 12190 24541 12188 24541 12189 24541 12190 24542 12189 24542 12181 24542 12180 24543 12179 24543 12187 24543 12180 24544 12182 24544 12181 24544 12190 24545 12182 24545 12180 24545 12187 24546 12190 24546 12180 24546 12180 24547 12188 24547 12184 24547 12189 24548 12188 24548 12180 24548 12181 24549 12189 24549 12180 24549 12191 24550 12203 24550 12197 24550 12191 24551 12192 24551 12196 24551 12193 24552 12192 24552 12191 24552 12197 24553 12193 24553 12191 24553 12191 24554 12194 24554 12199 24554 12195 24555 12194 24555 12191 24555 12196 24556 12195 24556 12191 24556 12199 24557 12202 24557 12204 24557 12199 24558 12194 24558 12202 24558 12202 24559 12194 24559 12197 24559 12202 24560 12197 24560 12203 24560 12192 24561 12193 24561 12196 24561 12196 24562 12193 24562 12197 24562 12196 24563 12197 24563 12195 24563 12195 24564 12197 24564 12194 24564 12204 24565 12198 24565 12199 24565 12199 24566 12198 24566 12200 24566 12199 24567 12200 24567 12201 24567 12191 24568 12200 24568 12198 24568 12201 24569 12200 24569 12191 24569 12199 24570 12201 24570 12191 24570 12191 24571 12202 24571 12203 24571 12204 24572 12202 24572 12191 24572 12198 24573 12204 24573 12191 24573 12210 24574 12205 24574 12217 24574 12217 24575 12205 24575 12211 24575 12217 24576 12211 24576 12213 24576 12218 24577 12219 24577 12205 24577 12205 24578 12219 24578 12206 24578 12205 24579 12206 24579 12211 24579 12211 24580 12206 24580 12207 24580 12212 24581 12221 24581 12208 24581 12205 24582 12210 24582 12209 24582 12209 24583 12210 24583 12215 24583 12209 24584 12215 24584 12220 24584 12213 24585 12211 24585 12212 24585 12213 24586 12212 24586 12214 24586 12214 24587 12212 24587 12208 24587 12214 24588 12208 24588 12215 24588 12215 24589 12208 24589 12216 24589 12215 24590 12216 24590 12220 24590 12213 24591 12214 24591 12217 24591 12217 24592 12214 24592 12215 24592 12217 24593 12215 24593 12210 24593 12206 24594 12221 24594 12207 24594 12207 24595 12221 24595 12212 24595 12218 24596 12209 24596 12219 24596 12219 24597 12209 24597 12220 24597 12209 24598 12218 24598 12205 24598 12216 24599 12208 24599 12220 24599 12220 24600 12208 24600 12221 24600 12220 24601 12221 24601 12219 24601 12219 24602 12221 24602 12206 24602 12212 24603 12211 24603 12207 24603 12224 24604 12222 24604 12225 24604 12225 24605 12222 24605 12223 24605 12232 24606 12231 24606 12236 24606 12235 24607 12224 24607 12236 24607 12236 24608 12224 24608 12225 24608 12236 24609 12225 24609 12232 24609 12232 24610 12225 24610 12228 24610 12234 24611 12238 24611 12229 24611 12236 24612 12231 24612 12227 24612 12227 24613 12231 24613 12226 24613 12227 24614 12226 24614 12237 24614 12228 24615 12225 24615 12234 24615 12228 24616 12234 24616 12233 24616 12233 24617 12234 24617 12229 24617 12233 24618 12229 24618 12226 24618 12226 24619 12229 24619 12230 24619 12226 24620 12230 24620 12237 24620 12226 24621 12231 24621 12233 24621 12233 24622 12231 24622 12232 24622 12233 24623 12232 24623 12228 24623 12222 24624 12238 24624 12223 24624 12223 24625 12238 24625 12234 24625 12235 24626 12227 24626 12224 24626 12224 24627 12227 24627 12237 24627 12227 24628 12235 24628 12236 24628 12230 24629 12229 24629 12237 24629 12237 24630 12229 24630 12238 24630 12237 24631 12238 24631 12224 24631 12224 24632 12238 24632 12222 24632 12234 24633 12225 24633 12223 24633 12244 24634 12248 24634 12245 24634 12245 24635 12248 24635 12239 24635 12248 24636 12244 24636 12243 24636 12246 24637 12245 24637 12239 24637 12240 24638 12241 24638 12239 24638 12239 24639 12241 24639 12242 24639 12239 24640 12242 24640 12246 24640 12253 24641 12251 24641 12247 24641 12249 24642 12243 24642 12255 24642 12255 24643 12243 24643 12251 24643 12255 24644 12251 24644 12250 24644 12244 24645 12245 24645 12243 24645 12243 24646 12245 24646 12246 24646 12243 24647 12246 24647 12251 24647 12251 24648 12246 24648 12247 24648 12253 24649 12242 24649 12241 24649 12243 24650 12249 24650 12248 24650 12248 24651 12249 24651 12254 24651 12248 24652 12254 24652 12239 24652 12250 24653 12251 24653 12253 24653 12250 24654 12253 24654 12252 24654 12252 24655 12253 24655 12241 24655 12252 24656 12241 24656 12254 24656 12254 24657 12241 24657 12240 24657 12254 24658 12240 24658 12239 24658 12250 24659 12252 24659 12255 24659 12255 24660 12252 24660 12254 24660 12255 24661 12254 24661 12249 24661 12246 24662 12242 24662 12247 24662 12247 24663 12242 24663 12253 24663 12262 24664 12260 24664 12256 24664 12256 24665 12260 24665 12257 24665 12256 24666 12257 24666 12263 24666 12269 24667 12258 24667 12260 24667 12260 24668 12258 24668 12272 24668 12260 24669 12272 24669 12257 24669 12257 24670 12272 24670 12259 24670 12264 24671 12271 24671 12265 24671 12260 24672 12262 24672 12261 24672 12261 24673 12262 24673 12266 24673 12261 24674 12266 24674 12270 24674 12263 24675 12257 24675 12264 24675 12263 24676 12264 24676 12268 24676 12268 24677 12264 24677 12265 24677 12268 24678 12265 24678 12266 24678 12266 24679 12265 24679 12267 24679 12266 24680 12267 24680 12270 24680 12266 24681 12262 24681 12268 24681 12268 24682 12262 24682 12256 24682 12268 24683 12256 24683 12263 24683 12272 24684 12271 24684 12259 24684 12259 24685 12271 24685 12264 24685 12269 24686 12261 24686 12258 24686 12258 24687 12261 24687 12270 24687 12261 24688 12269 24688 12260 24688 12272 24689 12258 24689 12270 24689 12267 24690 12265 24690 12270 24690 12270 24691 12265 24691 12271 24691 12270 24692 12271 24692 12272 24692 12264 24693 12257 24693 12259 24693 12283 24694 12287 24694 12282 24694 12282 24695 12287 24695 12276 24695 12282 24696 12276 24696 12280 24696 12286 24697 12284 24697 12287 24697 12287 24698 12284 24698 12273 24698 12287 24699 12273 24699 12276 24699 12276 24700 12273 24700 12289 24700 12274 24701 12288 24701 12277 24701 12287 24702 12283 24702 12285 24702 12285 24703 12283 24703 12278 24703 12285 24704 12278 24704 12275 24704 12280 24705 12276 24705 12274 24705 12280 24706 12274 24706 12281 24706 12281 24707 12274 24707 12277 24707 12281 24708 12277 24708 12278 24708 12278 24709 12277 24709 12279 24709 12278 24710 12279 24710 12275 24710 12280 24711 12281 24711 12282 24711 12282 24712 12281 24712 12278 24712 12282 24713 12278 24713 12283 24713 12273 24714 12288 24714 12289 24714 12289 24715 12288 24715 12274 24715 12286 24716 12285 24716 12284 24716 12284 24717 12285 24717 12275 24717 12285 24718 12286 24718 12287 24718 12279 24719 12277 24719 12275 24719 12275 24720 12277 24720 12288 24720 12275 24721 12288 24721 12284 24721 12284 24722 12288 24722 12273 24722 12274 24723 12276 24723 12289 24723 12300 24724 12293 24724 12290 24724 12290 24725 12293 24725 12295 24725 12290 24726 12295 24726 12291 24726 12301 24727 12292 24727 12293 24727 12293 24728 12292 24728 12305 24728 12293 24729 12305 24729 12295 24729 12295 24730 12305 24730 12306 24730 12297 24731 12304 24731 12298 24731 12293 24732 12300 24732 12294 24732 12294 24733 12300 24733 12299 24733 12294 24734 12299 24734 12303 24734 12291 24735 12295 24735 12297 24735 12291 24736 12297 24736 12296 24736 12296 24737 12297 24737 12298 24737 12296 24738 12298 24738 12299 24738 12299 24739 12298 24739 12302 24739 12299 24740 12302 24740 12303 24740 12291 24741 12296 24741 12290 24741 12290 24742 12296 24742 12299 24742 12290 24743 12299 24743 12300 24743 12305 24744 12304 24744 12306 24744 12306 24745 12304 24745 12297 24745 12301 24746 12294 24746 12292 24746 12292 24747 12294 24747 12303 24747 12294 24748 12301 24748 12293 24748 12305 24749 12292 24749 12303 24749 12302 24750 12298 24750 12303 24750 12303 24751 12298 24751 12304 24751 12303 24752 12304 24752 12305 24752 12297 24753 12295 24753 12306 24753 12307 24754 12312 24754 12308 24754 12308 24755 12312 24755 12309 24755 12308 24756 12309 24756 12310 24756 12311 24757 12313 24757 12312 24757 12312 24758 12313 24758 12319 24758 12312 24759 12319 24759 12309 24759 12309 24760 12319 24760 12320 24760 12316 24761 12321 24761 12323 24761 12312 24762 12307 24762 12314 24762 12314 24763 12307 24763 12315 24763 12314 24764 12315 24764 12318 24764 12310 24765 12309 24765 12316 24765 12310 24766 12316 24766 12317 24766 12317 24767 12316 24767 12323 24767 12317 24768 12323 24768 12315 24768 12315 24769 12323 24769 12322 24769 12315 24770 12322 24770 12318 24770 12315 24771 12307 24771 12317 24771 12317 24772 12307 24772 12308 24772 12317 24773 12308 24773 12310 24773 12319 24774 12321 24774 12320 24774 12320 24775 12321 24775 12316 24775 12311 24776 12314 24776 12313 24776 12313 24777 12314 24777 12318 24777 12314 24778 12311 24778 12312 24778 12319 24779 12313 24779 12318 24779 12322 24780 12323 24780 12318 24780 12318 24781 12323 24781 12321 24781 12318 24782 12321 24782 12319 24782 12316 24783 12309 24783 12320 24783 12328 24784 12325 24784 12330 24784 12330 24785 12325 24785 12324 24785 12325 24786 12328 24786 12329 24786 12326 24787 12330 24787 12324 24787 12335 24788 12333 24788 12324 24788 12324 24789 12333 24789 12339 24789 12324 24790 12339 24790 12326 24790 12340 24791 12331 24791 12327 24791 12330 24792 12326 24792 12331 24792 12331 24793 12326 24793 12327 24793 12332 24794 12338 24794 12329 24794 12328 24795 12330 24795 12329 24795 12329 24796 12330 24796 12331 24796 12329 24797 12331 24797 12332 24797 12332 24798 12331 24798 12336 24798 12340 24799 12339 24799 12333 24799 12329 24800 12338 24800 12325 24800 12325 24801 12338 24801 12337 24801 12325 24802 12337 24802 12324 24802 12336 24803 12331 24803 12340 24803 12336 24804 12340 24804 12334 24804 12334 24805 12340 24805 12333 24805 12334 24806 12333 24806 12337 24806 12337 24807 12333 24807 12335 24807 12337 24808 12335 24808 12324 24808 12336 24809 12334 24809 12332 24809 12332 24810 12334 24810 12337 24810 12332 24811 12337 24811 12338 24811 12326 24812 12339 24812 12327 24812 12327 24813 12339 24813 12340 24813 12347 24814 12343 24814 12355 24814 12355 24815 12343 24815 12341 24815 12355 24816 12341 24816 12342 24816 12356 24817 12357 24817 12343 24817 12343 24818 12357 24818 12344 24818 12343 24819 12344 24819 12341 24819 12341 24820 12344 24820 12345 24820 12350 24821 12346 24821 12352 24821 12343 24822 12347 24822 12348 24822 12348 24823 12347 24823 12354 24823 12348 24824 12354 24824 12349 24824 12342 24825 12341 24825 12350 24825 12342 24826 12350 24826 12351 24826 12351 24827 12350 24827 12352 24827 12351 24828 12352 24828 12354 24828 12354 24829 12352 24829 12353 24829 12354 24830 12353 24830 12349 24830 12354 24831 12347 24831 12351 24831 12351 24832 12347 24832 12355 24832 12351 24833 12355 24833 12342 24833 12344 24834 12346 24834 12345 24834 12345 24835 12346 24835 12350 24835 12356 24836 12348 24836 12357 24836 12357 24837 12348 24837 12349 24837 12348 24838 12356 24838 12343 24838 12344 24839 12357 24839 12349 24839 12353 24840 12352 24840 12349 24840 12349 24841 12352 24841 12346 24841 12349 24842 12346 24842 12344 24842 12350 24843 12341 24843 12345 24843 12366 24844 12365 24844 12368 24844 12368 24845 12365 24845 12358 24845 12359 24846 12360 24846 12361 24846 12361 24847 12360 24847 12364 24847 12360 24848 12359 24848 12369 24848 12366 24849 12361 24849 12364 24849 12362 24850 12363 24850 12364 24850 12364 24851 12363 24851 12365 24851 12364 24852 12365 24852 12366 24852 12358 24853 12367 24853 12368 24853 12361 24854 12366 24854 12367 24854 12367 24855 12366 24855 12368 24855 12373 24856 12374 24856 12369 24856 12359 24857 12361 24857 12369 24857 12369 24858 12361 24858 12367 24858 12369 24859 12367 24859 12373 24859 12373 24860 12367 24860 12370 24860 12358 24861 12365 24861 12363 24861 12369 24862 12374 24862 12360 24862 12360 24863 12374 24863 12371 24863 12360 24864 12371 24864 12364 24864 12370 24865 12367 24865 12358 24865 12370 24866 12358 24866 12372 24866 12372 24867 12358 24867 12363 24867 12372 24868 12363 24868 12371 24868 12371 24869 12363 24869 12362 24869 12371 24870 12362 24870 12364 24870 12370 24871 12372 24871 12373 24871 12373 24872 12372 24872 12371 24872 12373 24873 12371 24873 12374 24873 12375 24874 12391 24874 12376 24874 12376 24875 12391 24875 12388 24875 12387 24876 12380 24876 12379 24876 12377 24877 12375 24877 12379 24877 12379 24878 12375 24878 12376 24878 12379 24879 12376 24879 12387 24879 12387 24880 12376 24880 12378 24880 12382 24881 12390 24881 12389 24881 12379 24882 12380 24882 12381 24882 12381 24883 12380 24883 12384 24883 12381 24884 12384 24884 12386 24884 12378 24885 12376 24885 12382 24885 12378 24886 12382 24886 12383 24886 12383 24887 12382 24887 12389 24887 12383 24888 12389 24888 12384 24888 12384 24889 12389 24889 12385 24889 12384 24890 12385 24890 12386 24890 12384 24891 12380 24891 12383 24891 12383 24892 12380 24892 12387 24892 12383 24893 12387 24893 12378 24893 12391 24894 12390 24894 12388 24894 12388 24895 12390 24895 12382 24895 12377 24896 12381 24896 12375 24896 12375 24897 12381 24897 12386 24897 12381 24898 12377 24898 12379 24898 12391 24899 12375 24899 12386 24899 12385 24900 12389 24900 12386 24900 12386 24901 12389 24901 12390 24901 12386 24902 12390 24902 12391 24902 12382 24903 12376 24903 12388 24903 12404 24904 12407 24904 12392 24904 12392 24905 12407 24905 12408 24905 12402 24906 12403 24906 12405 24906 12393 24907 12404 24907 12405 24907 12405 24908 12404 24908 12392 24908 12405 24909 12392 24909 12402 24909 12402 24910 12392 24910 12396 24910 12397 24911 12394 24911 12406 24911 12405 24912 12403 24912 12395 24912 12395 24913 12403 24913 12399 24913 12395 24914 12399 24914 12401 24914 12396 24915 12392 24915 12397 24915 12396 24916 12397 24916 12398 24916 12398 24917 12397 24917 12406 24917 12398 24918 12406 24918 12399 24918 12399 24919 12406 24919 12400 24919 12399 24920 12400 24920 12401 24920 12396 24921 12398 24921 12402 24921 12402 24922 12398 24922 12399 24922 12402 24923 12399 24923 12403 24923 12407 24924 12394 24924 12408 24924 12408 24925 12394 24925 12397 24925 12393 24926 12395 24926 12404 24926 12404 24927 12395 24927 12401 24927 12395 24928 12393 24928 12405 24928 12407 24929 12404 24929 12401 24929 12400 24930 12406 24930 12401 24930 12401 24931 12406 24931 12394 24931 12401 24932 12394 24932 12407 24932 12397 24933 12392 24933 12408 24933 12413 24934 12409 24934 12410 24934 12411 24935 12409 24935 12413 24935 12415 24936 12411 24936 12413 24936 12413 24937 12412 24937 12419 24937 12416 24938 12412 24938 12413 24938 12410 24939 12416 24939 12413 24939 12413 24940 12417 24940 12420 24940 12418 24941 12417 24941 12413 24941 12419 24942 12418 24942 12413 24942 12413 24943 12421 24943 12415 24943 12414 24944 12421 24944 12413 24944 12420 24945 12414 24945 12413 24945 12409 24946 12411 24946 12415 24946 12416 24947 12410 24947 12412 24947 12412 24948 12410 24948 12409 24948 12412 24949 12409 24949 12419 24949 12419 24950 12409 24950 12415 24950 12419 24951 12415 24951 12421 24951 12417 24952 12418 24952 12420 24952 12420 24953 12418 24953 12419 24953 12420 24954 12419 24954 12414 24954 12414 24955 12419 24955 12421 24955 12425 24956 12422 24956 12430 24956 12424 24957 12422 24957 12425 24957 12423 24958 12424 24958 12425 24958 12425 24959 12426 24959 12427 24959 12428 24960 12426 24960 12425 24960 12430 24961 12428 24961 12425 24961 12430 24962 12433 24962 12432 24962 12431 24963 12435 24963 12430 24963 12430 24964 12435 24964 12429 24964 12430 24965 12429 24965 12433 24965 12426 24966 12428 24966 12427 24966 12427 24967 12428 24967 12430 24967 12427 24968 12430 24968 12434 24968 12434 24969 12430 24969 12432 24969 12422 24970 12424 24970 12430 24970 12430 24971 12424 24971 12423 24971 12430 24972 12423 24972 12431 24972 12425 24973 12427 24973 12434 24973 12425 24974 12433 24974 12429 24974 12432 24975 12433 24975 12425 24975 12434 24976 12432 24976 12425 24976 12425 24977 12431 24977 12423 24977 12435 24978 12431 24978 12425 24978 12429 24979 12435 24979 12425 24979 12436 24980 12462 24980 12437 24980 12437 24981 12462 24981 12438 24981 12437 24982 12438 24982 12439 24982 12439 24983 12438 24983 12440 24983 12439 24984 12440 24984 12441 24984 12441 24985 12440 24985 12442 24985 12441 24986 12442 24986 12448 24986 12448 24987 12442 24987 12444 24987 12448 24988 12444 24988 12443 24988 12443 24989 12444 24989 12449 24989 12443 24990 12449 24990 12447 24990 12447 24991 12449 24991 12445 24991 12447 24992 12445 24992 12446 24992 12446 24993 12445 24993 12458 24993 12453 24994 12436 24994 12437 24994 12453 24995 12441 24995 12448 24995 12439 24996 12441 24996 12453 24996 12437 24997 12439 24997 12453 24997 12453 24998 12447 24998 12446 24998 12443 24999 12447 24999 12453 24999 12448 25000 12443 25000 12453 25000 12438 25001 12450 25001 12440 25001 12440 25002 12450 25002 12444 25002 12440 25003 12444 25003 12442 25003 12449 25004 12444 25004 12445 25004 12445 25005 12444 25005 12450 25005 12445 25006 12450 25006 12458 25006 12458 25007 12450 25007 12459 25007 12451 25008 12452 25008 12461 25008 12461 25009 12452 25009 12450 25009 12461 25010 12450 25010 12462 25010 12462 25011 12450 25011 12438 25011 12453 25012 12454 25012 12455 25012 12456 25013 12454 25013 12453 25013 12446 25014 12456 25014 12453 25014 12453 25015 12460 25015 12436 25015 12457 25016 12460 25016 12453 25016 12455 25017 12457 25017 12453 25017 12446 25018 12458 25018 12456 25018 12456 25019 12458 25019 12459 25019 12456 25020 12459 25020 12454 25020 12454 25021 12459 25021 12450 25021 12454 25022 12450 25022 12455 25022 12455 25023 12450 25023 12452 25023 12455 25024 12452 25024 12457 25024 12457 25025 12452 25025 12451 25025 12457 25026 12451 25026 12460 25026 12460 25027 12451 25027 12461 25027 12460 25028 12461 25028 12436 25028 12436 25029 12461 25029 12462 25029 12489 25030 12463 25030 12471 25030 12471 25031 12463 25031 12479 25031 12471 25032 12479 25032 12464 25032 12464 25033 12479 25033 12477 25033 12464 25034 12477 25034 12469 25034 12469 25035 12477 25035 12478 25035 12469 25036 12478 25036 12473 25036 12473 25037 12478 25037 12465 25037 12473 25038 12465 25038 12466 25038 12466 25039 12465 25039 12467 25039 12466 25040 12467 25040 12472 25040 12472 25041 12467 25041 12468 25041 12470 25042 12464 25042 12469 25042 12471 25043 12464 25043 12470 25043 12489 25044 12471 25044 12470 25044 12470 25045 12466 25045 12472 25045 12473 25046 12466 25046 12470 25046 12469 25047 12473 25047 12470 25047 12478 25048 12476 25048 12474 25048 12475 25049 12488 25049 12478 25049 12478 25050 12488 25050 12486 25050 12478 25051 12486 25051 12476 25051 12467 25052 12465 25052 12468 25052 12468 25053 12465 25053 12478 25053 12468 25054 12478 25054 12483 25054 12483 25055 12478 25055 12474 25055 12477 25056 12479 25056 12478 25056 12478 25057 12479 25057 12463 25057 12478 25058 12463 25058 12475 25058 12470 25059 12472 25059 12481 25059 12470 25060 12484 25060 12485 25060 12482 25061 12484 25061 12470 25061 12481 25062 12482 25062 12470 25062 12470 25063 12480 25063 12489 25063 12487 25064 12480 25064 12470 25064 12485 25065 12487 25065 12470 25065 12472 25066 12468 25066 12481 25066 12481 25067 12468 25067 12483 25067 12481 25068 12483 25068 12482 25068 12482 25069 12483 25069 12474 25069 12482 25070 12474 25070 12484 25070 12484 25071 12474 25071 12476 25071 12484 25072 12476 25072 12485 25072 12485 25073 12476 25073 12486 25073 12485 25074 12486 25074 12487 25074 12487 25075 12486 25075 12488 25075 12487 25076 12488 25076 12480 25076 12480 25077 12488 25077 12475 25077 12480 25078 12475 25078 12489 25078 12489 25079 12475 25079 12463 25079 12494 25080 12490 25080 12493 25080 12493 25081 12490 25081 12496 25081 12491 25082 12492 25082 12493 25082 12493 25083 12492 25083 12494 25083 12492 25084 12495 25084 12494 25084 12494 25085 12495 25085 12490 25085 12490 25086 12495 25086 12496 25086 12496 25087 12495 25087 12497 25087 12493 25088 12496 25088 12491 25088 12491 25089 12496 25089 12497 25089 12491 25090 12497 25090 12492 25090 12492 25091 12497 25091 12495 25091 12504 25092 12505 25092 12498 25092 12498 25093 12505 25093 12502 25093 12503 25094 12500 25094 12499 25094 12499 25095 12500 25095 12501 25095 12499 25096 12501 25096 12498 25096 12498 25097 12501 25097 12504 25097 12502 25098 12503 25098 12498 25098 12498 25099 12503 25099 12499 25099 12502 25100 12505 25100 12503 25100 12503 25101 12505 25101 12500 25101 12501 25102 12500 25102 12504 25102 12504 25103 12500 25103 12505 25103 12510 25104 12506 25104 12507 25104 12507 25105 12506 25105 12508 25105 12507 25106 12508 25106 12509 25106 12509 25107 12508 25107 12513 25107 12512 25108 12506 25108 12511 25108 12511 25109 12506 25109 12510 25109 12507 25110 12509 25110 12510 25110 12510 25111 12509 25111 12511 25111 12509 25112 12513 25112 12511 25112 12511 25113 12513 25113 12512 25113 12512 25114 12513 25114 12506 25114 12506 25115 12513 25115 12508 25115 12514 25116 12521 25116 12515 25116 12515 25117 12521 25117 12520 25117 12515 25118 12520 25118 12516 25118 12516 25119 12520 25119 12519 25119 12514 25120 12515 25120 12518 25120 12518 25121 12515 25121 12516 25121 12521 25122 12514 25122 12517 25122 12517 25123 12514 25123 12518 25123 12517 25124 12518 25124 12519 25124 12519 25125 12518 25125 12516 25125 12519 25126 12520 25126 12517 25126 12517 25127 12520 25127 12521 25127 12522 25128 12523 25128 12524 25128 12524 25129 12523 25129 12525 25129 12526 25130 12522 25130 12527 25130 12527 25131 12522 25131 12524 25131 12527 25132 12524 25132 12528 25132 12528 25133 12524 25133 12525 25133 12528 25134 12529 25134 12527 25134 12527 25135 12529 25135 12526 25135 12522 25136 12526 25136 12523 25136 12523 25137 12526 25137 12529 25137 12523 25138 12529 25138 12525 25138 12525 25139 12529 25139 12528 25139 12535 25140 12530 25140 12537 25140 12537 25141 12530 25141 12536 25141 12535 25142 12531 25142 12530 25142 12530 25143 12531 25143 12533 25143 12532 25144 12533 25144 12534 25144 12534 25145 12533 25145 12531 25145 12534 25146 12531 25146 12537 25146 12537 25147 12531 25147 12535 25147 12530 25148 12533 25148 12536 25148 12536 25149 12533 25149 12532 25149 12536 25150 12532 25150 12537 25150 12537 25151 12532 25151 12534 25151 12542 25152 12543 25152 12545 25152 12545 25153 12543 25153 12538 25153 12543 25154 12544 25154 12538 25154 12538 25155 12544 25155 12539 25155 12539 25156 12544 25156 12540 25156 12540 25157 12544 25157 12541 25157 12545 25158 12540 25158 12542 25158 12542 25159 12540 25159 12541 25159 12542 25160 12541 25160 12543 25160 12543 25161 12541 25161 12544 25161 12539 25162 12540 25162 12538 25162 12538 25163 12540 25163 12545 25163 12550 25164 12552 25164 12546 25164 12546 25165 12552 25165 12551 25165 12546 25166 12551 25166 12547 25166 12547 25167 12551 25167 12549 25167 12547 25168 12549 25168 12548 25168 12548 25169 12549 25169 12553 25169 12548 25170 12550 25170 12547 25170 12547 25171 12550 25171 12546 25171 12548 25172 12553 25172 12550 25172 12550 25173 12553 25173 12552 25173 12551 25174 12552 25174 12549 25174 12549 25175 12552 25175 12553 25175 12555 25176 12560 25176 12557 25176 12554 25177 12560 25177 12555 25177 12556 25178 12554 25178 12555 25178 12555 25179 12562 25179 12563 25179 12561 25180 12562 25180 12555 25180 12557 25181 12561 25181 12555 25181 12563 25182 12554 25182 12564 25182 12564 25183 12554 25183 12556 25183 12564 25184 12556 25184 12566 25184 12558 25185 12565 25185 12567 25185 12567 25186 12565 25186 12564 25186 12567 25187 12564 25187 12559 25187 12559 25188 12564 25188 12566 25188 12557 25189 12560 25189 12561 25189 12561 25190 12560 25190 12554 25190 12561 25191 12554 25191 12562 25191 12562 25192 12554 25192 12563 25192 12555 25193 12563 25193 12564 25193 12555 25194 12558 25194 12567 25194 12565 25195 12558 25195 12555 25195 12564 25196 12565 25196 12555 25196 12555 25197 12566 25197 12556 25197 12559 25198 12566 25198 12555 25198 12567 25199 12559 25199 12555 25199 12568 25200 12569 25200 12570 25200 12570 25201 12569 25201 12571 25201 12579 25202 12580 25202 12571 25202 12571 25203 12580 25203 12572 25203 12571 25204 12572 25204 12570 25204 12570 25205 12572 25205 12573 25205 12568 25206 12570 25206 12581 25206 12576 25207 12582 25207 12581 25207 12581 25208 12582 25208 12574 25208 12581 25209 12574 25209 12568 25209 12569 25210 12568 25210 12575 25210 12575 25211 12568 25211 12574 25211 12572 25212 12576 25212 12573 25212 12573 25213 12576 25213 12581 25213 12579 25214 12577 25214 12580 25214 12580 25215 12577 25215 12578 25215 12577 25216 12579 25216 12571 25216 12583 25217 12582 25217 12578 25217 12578 25218 12582 25218 12576 25218 12578 25219 12576 25219 12580 25219 12580 25220 12576 25220 12572 25220 12581 25221 12570 25221 12573 25221 12571 25222 12569 25222 12577 25222 12577 25223 12569 25223 12575 25223 12577 25224 12575 25224 12578 25224 12574 25225 12582 25225 12575 25225 12575 25226 12582 25226 12583 25226 12575 25227 12583 25227 12578 25227 12596 25228 12585 25228 12584 25228 12584 25229 12585 25229 12587 25229 12585 25230 12596 25230 12586 25230 12587 25231 12592 25231 12588 25231 12593 25232 12584 25232 12598 25232 12598 25233 12584 25233 12587 25233 12598 25234 12587 25234 12589 25234 12589 25235 12587 25235 12588 25235 12601 25236 12594 25236 12595 25236 12586 25237 12600 25237 12585 25237 12585 25238 12600 25238 12591 25238 12585 25239 12591 25239 12587 25239 12599 25240 12589 25240 12590 25240 12590 25241 12589 25241 12588 25241 12590 25242 12588 25242 12591 25242 12591 25243 12588 25243 12592 25243 12591 25244 12592 25244 12587 25244 12584 25245 12593 25245 12594 25245 12594 25246 12593 25246 12595 25246 12596 25247 12584 25247 12586 25247 12586 25248 12584 25248 12594 25248 12586 25249 12594 25249 12600 25249 12600 25250 12594 25250 12597 25250 12598 25251 12589 25251 12601 25251 12601 25252 12589 25252 12599 25252 12601 25253 12599 25253 12594 25253 12594 25254 12599 25254 12597 25254 12590 25255 12591 25255 12599 25255 12599 25256 12591 25256 12600 25256 12599 25257 12600 25257 12597 25257 12593 25258 12598 25258 12595 25258 12595 25259 12598 25259 12601 25259 12611 25260 12604 25260 12602 25260 12602 25261 12604 25261 12618 25261 12602 25262 12618 25262 12603 25262 12613 25263 12605 25263 12604 25263 12604 25264 12605 25264 12606 25264 12604 25265 12606 25265 12618 25265 12618 25266 12606 25266 12607 25266 12608 25267 12617 25267 12615 25267 12604 25268 12611 25268 12612 25268 12612 25269 12611 25269 12610 25269 12612 25270 12610 25270 12616 25270 12603 25271 12618 25271 12608 25271 12603 25272 12608 25272 12609 25272 12609 25273 12608 25273 12615 25273 12609 25274 12615 25274 12610 25274 12610 25275 12615 25275 12614 25275 12610 25276 12614 25276 12616 25276 12603 25277 12609 25277 12602 25277 12602 25278 12609 25278 12610 25278 12602 25279 12610 25279 12611 25279 12606 25280 12617 25280 12607 25280 12607 25281 12617 25281 12608 25281 12613 25282 12612 25282 12605 25282 12605 25283 12612 25283 12616 25283 12612 25284 12613 25284 12604 25284 12606 25285 12605 25285 12616 25285 12614 25286 12615 25286 12616 25286 12616 25287 12615 25287 12617 25287 12616 25288 12617 25288 12606 25288 12608 25289 12618 25289 12607 25289 12629 25290 12619 25290 12620 25290 12620 25291 12619 25291 12622 25291 12620 25292 12622 25292 12627 25292 12621 25293 12632 25293 12619 25293 12619 25294 12632 25294 12630 25294 12619 25295 12630 25295 12622 25295 12622 25296 12630 25296 12631 25296 12623 25297 12624 25297 12625 25297 12619 25298 12629 25298 12633 25298 12633 25299 12629 25299 12626 25299 12633 25300 12626 25300 12634 25300 12627 25301 12622 25301 12623 25301 12627 25302 12623 25302 12628 25302 12628 25303 12623 25303 12625 25303 12628 25304 12625 25304 12626 25304 12626 25305 12625 25305 12635 25305 12626 25306 12635 25306 12634 25306 12627 25307 12628 25307 12620 25307 12620 25308 12628 25308 12626 25308 12620 25309 12626 25309 12629 25309 12630 25310 12624 25310 12631 25310 12631 25311 12624 25311 12623 25311 12621 25312 12633 25312 12632 25312 12632 25313 12633 25313 12634 25313 12633 25314 12621 25314 12619 25314 12635 25315 12625 25315 12634 25315 12634 25316 12625 25316 12624 25316 12634 25317 12624 25317 12632 25317 12632 25318 12624 25318 12630 25318 12623 25319 12622 25319 12631 25319 12638 25320 12649 25320 12641 25320 12641 25321 12649 25321 12650 25321 12647 25322 12646 25322 12637 25322 12636 25323 12638 25323 12637 25323 12637 25324 12638 25324 12641 25324 12637 25325 12641 25325 12647 25325 12647 25326 12641 25326 12639 25326 12642 25327 12651 25327 12652 25327 12637 25328 12646 25328 12640 25328 12640 25329 12646 25329 12643 25329 12640 25330 12643 25330 12645 25330 12639 25331 12641 25331 12642 25331 12639 25332 12642 25332 12648 25332 12648 25333 12642 25333 12652 25333 12648 25334 12652 25334 12643 25334 12643 25335 12652 25335 12644 25335 12643 25336 12644 25336 12645 25336 12643 25337 12646 25337 12648 25337 12648 25338 12646 25338 12647 25338 12648 25339 12647 25339 12639 25339 12649 25340 12651 25340 12650 25340 12650 25341 12651 25341 12642 25341 12636 25342 12640 25342 12638 25342 12638 25343 12640 25343 12645 25343 12640 25344 12636 25344 12637 25344 12649 25345 12638 25345 12645 25345 12644 25346 12652 25346 12645 25346 12645 25347 12652 25347 12651 25347 12645 25348 12651 25348 12649 25348 12642 25349 12641 25349 12650 25349 12653 25350 12662 25350 12660 25350 12660 25351 12662 25351 12663 25351 12662 25352 12653 25352 12659 25352 12654 25353 12660 25353 12663 25353 12666 25354 12665 25354 12663 25354 12663 25355 12665 25355 12669 25355 12663 25356 12669 25356 12654 25356 12661 25357 12655 25357 12656 25357 12660 25358 12654 25358 12655 25358 12655 25359 12654 25359 12656 25359 12657 25360 12658 25360 12659 25360 12653 25361 12660 25361 12659 25361 12659 25362 12660 25362 12655 25362 12659 25363 12655 25363 12657 25363 12657 25364 12655 25364 12664 25364 12661 25365 12669 25365 12665 25365 12659 25366 12658 25366 12662 25366 12662 25367 12658 25367 12667 25367 12662 25368 12667 25368 12663 25368 12664 25369 12655 25369 12661 25369 12664 25370 12661 25370 12668 25370 12668 25371 12661 25371 12665 25371 12668 25372 12665 25372 12667 25372 12667 25373 12665 25373 12666 25373 12667 25374 12666 25374 12663 25374 12667 25375 12658 25375 12668 25375 12668 25376 12658 25376 12657 25376 12668 25377 12657 25377 12664 25377 12654 25378 12669 25378 12656 25378 12656 25379 12669 25379 12661 25379 12673 25380 12683 25380 12678 25380 12678 25381 12683 25381 12670 25381 12675 25382 12671 25382 12674 25382 12672 25383 12673 25383 12674 25383 12674 25384 12673 25384 12678 25384 12674 25385 12678 25385 12675 25385 12675 25386 12678 25386 12677 25386 12679 25387 12686 25387 12685 25387 12674 25388 12671 25388 12684 25388 12684 25389 12671 25389 12676 25389 12684 25390 12676 25390 12681 25390 12677 25391 12678 25391 12679 25391 12677 25392 12679 25392 12682 25392 12682 25393 12679 25393 12685 25393 12682 25394 12685 25394 12676 25394 12676 25395 12685 25395 12680 25395 12676 25396 12680 25396 12681 25396 12676 25397 12671 25397 12682 25397 12682 25398 12671 25398 12675 25398 12682 25399 12675 25399 12677 25399 12683 25400 12686 25400 12670 25400 12670 25401 12686 25401 12679 25401 12672 25402 12684 25402 12673 25402 12673 25403 12684 25403 12681 25403 12684 25404 12672 25404 12674 25404 12683 25405 12673 25405 12681 25405 12680 25406 12685 25406 12681 25406 12681 25407 12685 25407 12686 25407 12681 25408 12686 25408 12683 25408 12679 25409 12678 25409 12670 25409 12689 25410 12687 25410 12691 25410 12691 25411 12687 25411 12703 25411 12692 25412 12693 25412 12690 25412 12688 25413 12689 25413 12690 25413 12690 25414 12689 25414 12691 25414 12690 25415 12691 25415 12692 25415 12692 25416 12691 25416 12695 25416 12694 25417 12702 25417 12701 25417 12690 25418 12693 25418 12699 25418 12699 25419 12693 25419 12698 25419 12699 25420 12698 25420 12700 25420 12695 25421 12691 25421 12694 25421 12695 25422 12694 25422 12697 25422 12697 25423 12694 25423 12701 25423 12697 25424 12701 25424 12698 25424 12698 25425 12701 25425 12696 25425 12698 25426 12696 25426 12700 25426 12695 25427 12697 25427 12692 25427 12692 25428 12697 25428 12698 25428 12692 25429 12698 25429 12693 25429 12687 25430 12702 25430 12703 25430 12703 25431 12702 25431 12694 25431 12688 25432 12699 25432 12689 25432 12689 25433 12699 25433 12700 25433 12699 25434 12688 25434 12690 25434 12687 25435 12689 25435 12700 25435 12696 25436 12701 25436 12700 25436 12700 25437 12701 25437 12702 25437 12700 25438 12702 25438 12687 25438 12694 25439 12691 25439 12703 25439 12710 25440 12719 25440 12705 25440 12705 25441 12719 25441 12715 25441 12704 25442 12714 25442 12715 25442 12715 25443 12714 25443 12712 25443 12715 25444 12712 25444 12705 25444 12705 25445 12712 25445 12718 25445 12717 25446 12713 25446 12707 25446 12706 25447 12711 25447 12716 25447 12716 25448 12711 25448 12708 25448 12716 25449 12708 25449 12707 25449 12707 25450 12708 25450 12709 25450 12707 25451 12709 25451 12717 25451 12717 25452 12709 25452 12710 25452 12717 25453 12710 25453 12705 25453 12709 25454 12708 25454 12710 25454 12710 25455 12708 25455 12711 25455 12710 25456 12711 25456 12719 25456 12712 25457 12713 25457 12718 25457 12718 25458 12713 25458 12717 25458 12704 25459 12720 25459 12714 25459 12714 25460 12720 25460 12721 25460 12720 25461 12704 25461 12715 25461 12716 25462 12707 25462 12706 25462 12706 25463 12707 25463 12713 25463 12706 25464 12713 25464 12721 25464 12721 25465 12713 25465 12712 25465 12721 25466 12712 25466 12714 25466 12717 25467 12705 25467 12718 25467 12715 25468 12719 25468 12720 25468 12720 25469 12719 25469 12711 25469 12720 25470 12711 25470 12721 25470 12721 25471 12711 25471 12706 25471 12735 25472 12734 25472 12736 25472 12736 25473 12734 25473 12722 25473 12723 25474 12735 25474 12724 25474 12724 25475 12735 25475 12736 25475 12724 25476 12736 25476 12731 25476 12731 25477 12736 25477 12729 25477 12725 25478 12726 25478 12728 25478 12727 25479 12737 25479 12728 25479 12728 25480 12737 25480 12730 25480 12728 25481 12730 25481 12725 25481 12725 25482 12730 25482 12729 25482 12725 25483 12729 25483 12736 25483 12729 25484 12730 25484 12731 25484 12731 25485 12730 25485 12737 25485 12734 25486 12726 25486 12722 25486 12722 25487 12726 25487 12725 25487 12723 25488 12733 25488 12735 25488 12735 25489 12733 25489 12732 25489 12733 25490 12723 25490 12724 25490 12734 25491 12735 25491 12732 25491 12727 25492 12728 25492 12732 25492 12732 25493 12728 25493 12726 25493 12732 25494 12726 25494 12734 25494 12725 25495 12736 25495 12722 25495 12724 25496 12731 25496 12733 25496 12733 25497 12731 25497 12737 25497 12733 25498 12737 25498 12732 25498 12732 25499 12737 25499 12727 25499 12749 25500 12746 25500 12738 25500 12742 25501 12747 25501 12751 25501 12751 25502 12747 25502 12739 25502 12751 25503 12739 25503 12755 25503 12744 25504 12752 25504 12739 25504 12739 25505 12752 25505 12754 25505 12739 25506 12754 25506 12755 25506 12740 25507 12741 25507 12746 25507 12746 25508 12741 25508 12738 25508 12750 25509 12740 25509 12742 25509 12742 25510 12740 25510 12746 25510 12742 25511 12746 25511 12747 25511 12747 25512 12746 25512 12748 25512 12749 25513 12743 25513 12753 25513 12752 25514 12744 25514 12753 25514 12753 25515 12744 25515 12745 25515 12753 25516 12745 25516 12749 25516 12749 25517 12745 25517 12748 25517 12749 25518 12748 25518 12746 25518 12744 25519 12739 25519 12745 25519 12745 25520 12739 25520 12747 25520 12745 25521 12747 25521 12748 25521 12741 25522 12743 25522 12738 25522 12738 25523 12743 25523 12749 25523 12750 25524 12751 25524 12740 25524 12740 25525 12751 25525 12755 25525 12751 25526 12750 25526 12742 25526 12752 25527 12753 25527 12754 25527 12754 25528 12753 25528 12743 25528 12754 25529 12743 25529 12755 25529 12755 25530 12743 25530 12741 25530 12755 25531 12741 25531 12740 25531 14569 25532 14573 25532 12756 25532 12756 25533 14573 25533 12757 25533 12756 25534 12757 25534 15448 25534 15448 25535 12757 25535 12766 25535 14606 25536 12763 25536 12758 25536 12758 25537 12763 25537 12762 25537 12758 25538 12762 25538 12759 25538 12759 25539 12762 25539 12761 25539 14601 25540 15432 25540 12760 25540 12760 25541 15432 25541 12761 25541 12760 25542 12761 25542 14600 25542 14600 25543 12761 25543 12762 25543 14600 25544 12762 25544 14599 25544 14599 25545 12762 25545 12763 25545 12764 25546 12765 25546 15434 25546 15434 25547 12765 25547 14604 25547 15434 25548 14604 25548 14606 25548 12766 25549 14571 25549 12767 25549 12767 25550 14571 25550 14567 25550 13553 25551 12768 25551 12776 25551 12776 25552 12768 25552 12769 25552 12776 25553 12769 25553 12770 25553 12770 25554 12769 25554 15439 25554 12770 25555 15439 25555 12771 25555 12771 25556 15439 25556 15438 25556 12771 25557 15438 25557 12772 25557 12772 25558 15438 25558 15437 25558 12772 25559 15437 25559 12773 25559 12773 25560 15437 25560 12774 25560 12773 25561 12774 25561 12779 25561 12779 25562 12774 25562 15442 25562 12779 25563 15442 25563 15441 25563 12775 25564 13513 25564 12776 25564 12776 25565 12770 25565 12775 25565 12775 25566 12770 25566 12771 25566 12775 25567 12771 25567 12781 25567 13515 25568 13513 25568 12783 25568 12783 25569 13513 25569 12775 25569 12783 25570 12775 25570 12777 25570 12777 25571 12775 25571 12781 25571 12777 25572 12781 25572 12778 25572 12778 25573 12781 25573 12780 25573 12778 25574 12780 25574 14560 25574 14560 25575 12780 25575 15436 25575 15441 25576 15436 25576 12779 25576 12779 25577 15436 25577 12780 25577 12779 25578 12780 25578 12773 25578 12773 25579 12780 25579 12781 25579 12773 25580 12781 25580 12772 25580 12772 25581 12781 25581 12771 25581 12782 25582 12803 25582 14560 25582 14560 25583 12803 25583 12778 25583 15378 25584 13515 25584 12789 25584 12789 25585 13515 25585 12783 25585 12777 25586 12784 25586 12783 25586 12783 25587 12784 25587 12785 25587 12783 25588 12785 25588 12789 25588 12803 25589 12786 25589 12778 25589 12778 25590 12786 25590 12787 25590 12778 25591 12787 25591 12777 25591 12777 25592 12787 25592 12788 25592 12777 25593 12788 25593 12784 25593 12789 25594 12785 25594 12790 25594 12784 25595 12788 25595 12807 25595 12807 25596 12788 25596 12787 25596 14785 25597 12791 25597 12809 25597 14788 25598 12792 25598 14789 25598 14789 25599 12792 25599 12802 25599 14788 25600 12810 25600 12792 25600 12792 25601 12810 25601 12808 25601 12792 25602 12808 25602 12802 25602 12802 25603 12808 25603 12793 25603 12808 25604 12806 25604 12805 25604 15378 25605 12789 25605 12794 25605 12794 25606 12789 25606 12790 25606 12794 25607 12790 25607 12795 25607 12809 25608 12796 25608 12797 25608 12797 25609 12796 25609 12795 25609 12797 25610 12795 25610 12798 25610 12798 25611 12795 25611 12790 25611 12798 25612 12790 25612 12807 25612 12807 25613 12790 25613 12785 25613 12807 25614 12785 25614 12784 25614 12808 25615 12805 25615 12793 25615 12793 25616 12805 25616 12804 25616 12793 25617 12804 25617 12801 25617 12799 25618 12800 25618 12801 25618 12801 25619 12800 25619 13337 25619 12801 25620 13337 25620 12793 25620 12793 25621 13337 25621 13341 25621 12793 25622 13341 25622 12802 25622 12802 25623 13341 25623 13330 25623 12802 25624 13330 25624 14789 25624 12782 25625 12799 25625 12803 25625 12803 25626 12799 25626 12801 25626 12803 25627 12801 25627 12786 25627 12786 25628 12801 25628 12804 25628 12786 25629 12804 25629 12787 25629 12787 25630 12804 25630 12805 25630 12787 25631 12805 25631 12807 25631 12807 25632 12805 25632 12806 25632 12807 25633 12806 25633 12798 25633 12798 25634 12806 25634 12808 25634 12798 25635 12808 25635 12797 25635 12797 25636 12808 25636 12810 25636 12797 25637 12810 25637 12809 25637 12809 25638 12810 25638 14788 25638 12809 25639 14788 25639 14785 25639 12816 25640 12811 25640 12812 25640 12812 25641 12811 25641 12838 25641 12812 25642 12838 25642 14637 25642 12813 25643 12814 25643 12815 25643 12815 25644 12814 25644 12830 25644 12815 25645 12830 25645 12816 25645 12816 25646 12830 25646 12817 25646 12816 25647 12817 25647 12811 25647 12813 25648 12815 25648 12828 25648 12828 25649 12815 25649 12818 25649 12828 25650 12818 25650 12821 25650 12821 25651 12818 25651 12819 25651 12821 25652 12819 25652 12820 25652 12844 25653 12821 25653 12820 25653 12829 25654 12828 25654 12821 25654 12829 25655 12821 25655 12835 25655 12835 25656 12821 25656 12844 25656 12835 25657 12844 25657 12822 25657 12836 25658 12835 25658 12822 25658 12823 25659 14506 25659 12825 25659 14506 25660 14505 25660 12825 25660 12825 25661 14505 25661 12824 25661 12825 25662 12824 25662 12826 25662 12826 25663 12824 25663 12827 25663 12826 25664 12827 25664 12840 25664 12828 25665 12829 25665 12813 25665 12813 25666 12829 25666 12834 25666 12813 25667 12834 25667 12814 25667 12814 25668 12834 25668 12831 25668 12814 25669 12831 25669 12830 25669 12830 25670 12831 25670 12817 25670 12817 25671 12831 25671 12832 25671 12817 25672 12832 25672 12811 25672 12811 25673 12832 25673 12833 25673 12811 25674 12833 25674 12838 25674 12829 25675 12835 25675 12834 25675 12834 25676 12835 25676 12836 25676 12834 25677 12836 25677 12831 25677 12831 25678 12836 25678 12837 25678 12831 25679 12837 25679 12832 25679 12832 25680 12837 25680 12841 25680 12832 25681 12841 25681 12833 25681 14637 25682 12838 25682 12839 25682 12839 25683 12838 25683 12833 25683 12839 25684 12833 25684 12840 25684 12840 25685 12833 25685 12841 25685 12840 25686 12841 25686 12826 25686 12826 25687 12841 25687 12837 25687 12826 25688 12837 25688 12825 25688 12825 25689 12837 25689 12836 25689 12825 25690 12836 25690 12823 25690 12823 25691 12836 25691 12822 25691 12820 25692 12842 25692 12844 25692 12844 25693 12842 25693 12843 25693 12844 25694 12843 25694 12822 25694 12845 25695 13849 25695 13851 25695 12845 25696 13851 25696 13350 25696 13350 25697 13851 25697 12846 25697 12846 25698 13851 25698 12843 25698 12846 25699 12843 25699 12842 25699 12847 25700 12870 25700 12872 25700 12848 25701 14821 25701 12873 25701 12873 25702 14821 25702 12849 25702 12850 25703 12851 25703 12875 25703 12874 25704 14449 25704 12876 25704 12876 25705 14449 25705 15389 25705 12850 25706 12875 25706 12853 25706 12875 25707 12852 25707 12853 25707 12853 25708 12852 25708 12854 25708 12853 25709 12854 25709 14373 25709 14373 25710 12854 25710 12855 25710 12854 25711 12860 25711 12855 25711 12855 25712 12860 25712 12859 25712 12855 25713 12859 25713 12856 25713 12856 25714 12859 25714 12857 25714 12856 25715 12857 25715 12858 25715 12858 25716 12857 25716 15382 25716 12858 25717 15382 25717 15381 25717 15390 25718 15382 25718 12880 25718 12880 25719 15382 25719 12857 25719 12880 25720 12857 25720 12882 25720 12882 25721 12857 25721 12859 25721 12882 25722 12859 25722 12884 25722 12884 25723 12859 25723 12860 25723 12884 25724 12860 25724 12885 25724 12885 25725 12860 25725 12854 25725 12885 25726 12854 25726 12886 25726 12886 25727 12854 25727 12852 25727 12886 25728 12852 25728 12861 25728 12861 25729 12852 25729 12875 25729 12861 25730 12875 25730 12887 25730 14824 25731 14826 25731 12866 25731 12866 25732 14826 25732 12864 25732 12866 25733 12864 25733 12862 25733 14827 25734 15399 25734 14828 25734 14828 25735 15399 25735 12867 25735 14828 25736 12867 25736 14829 25736 14829 25737 12867 25737 12862 25737 14829 25738 12862 25738 12863 25738 12863 25739 12862 25739 12864 25739 12865 25740 14824 25740 12878 25740 12878 25741 14824 25741 12866 25741 12878 25742 12866 25742 12883 25742 12883 25743 12866 25743 12862 25743 12883 25744 12862 25744 12881 25744 12881 25745 12862 25745 12867 25745 12881 25746 12867 25746 12868 25746 12868 25747 12867 25747 15399 25747 12868 25748 15399 25748 15415 25748 15423 25749 12869 25749 12870 25749 12870 25750 12869 25750 12871 25750 12870 25751 12871 25751 12872 25751 12872 25752 12871 25752 14819 25752 12872 25753 14819 25753 12873 25753 12873 25754 14819 25754 14818 25754 12873 25755 14818 25755 12848 25755 12851 25756 12874 25756 12875 25756 12875 25757 12874 25757 12876 25757 12875 25758 12876 25758 12887 25758 12887 25759 12876 25759 15389 25759 12887 25760 15389 25760 15414 25760 14821 25761 14823 25761 12849 25761 12849 25762 14823 25762 12877 25762 12849 25763 12877 25763 12878 25763 12878 25764 12877 25764 12879 25764 12878 25765 12879 25765 12865 25765 15415 25766 15390 25766 12868 25766 12868 25767 15390 25767 12880 25767 12868 25768 12880 25768 12881 25768 12881 25769 12880 25769 12882 25769 12881 25770 12882 25770 12883 25770 12883 25771 12882 25771 12884 25771 12883 25772 12884 25772 12878 25772 12878 25773 12884 25773 12885 25773 12878 25774 12885 25774 12849 25774 12849 25775 12885 25775 12886 25775 12849 25776 12886 25776 12873 25776 12873 25777 12886 25777 12861 25777 12873 25778 12861 25778 12872 25778 12872 25779 12861 25779 12887 25779 12872 25780 12887 25780 12847 25780 12847 25781 12887 25781 15414 25781 13808 25782 12888 25782 12893 25782 12893 25783 12888 25783 12889 25783 12893 25784 12889 25784 13819 25784 13819 25785 12919 25785 12893 25785 12893 25786 12919 25786 12917 25786 12893 25787 12917 25787 12890 25787 13809 25788 12894 25788 13810 25788 13810 25789 12894 25789 12891 25789 13810 25790 12891 25790 13811 25790 13811 25791 12891 25791 12892 25791 12892 25792 12891 25792 14182 25792 12892 25793 14182 25793 14208 25793 12890 25794 12921 25794 12893 25794 12893 25795 12921 25795 12894 25795 12893 25796 12894 25796 13808 25796 13808 25797 12894 25797 13809 25797 12921 25798 12922 25798 12894 25798 12894 25799 12922 25799 12941 25799 12894 25800 12941 25800 12891 25800 12891 25801 12941 25801 12943 25801 12891 25802 12943 25802 14182 25802 13827 25803 13826 25803 12926 25803 12920 25804 12929 25804 12895 25804 12914 25805 12948 25805 12913 25805 12935 25806 14215 25806 12896 25806 12896 25807 14215 25807 12897 25807 12896 25808 12897 25808 12942 25808 12942 25809 12897 25809 12943 25809 12898 25810 12899 25810 12938 25810 12938 25811 12899 25811 12900 25811 12938 25812 12900 25812 12901 25812 12901 25813 12900 25813 12930 25813 12901 25814 12930 25814 12939 25814 12939 25815 12930 25815 12933 25815 12939 25816 12933 25816 12902 25816 12902 25817 12933 25817 12934 25817 12902 25818 12934 25818 12903 25818 12903 25819 12934 25819 12935 25819 12903 25820 12935 25820 12904 25820 12904 25821 12935 25821 12896 25821 12904 25822 12896 25822 12940 25822 12940 25823 12896 25823 12942 25823 13826 25824 13825 25824 12926 25824 12926 25825 13825 25825 13832 25825 12926 25826 13832 25826 12909 25826 12905 25827 12908 25827 12906 25827 12906 25828 12908 25828 12910 25828 12906 25829 12910 25829 13831 25829 13831 25830 12910 25830 13832 25830 12907 25831 12912 25831 13836 25831 13836 25832 12912 25832 12908 25832 13836 25833 12908 25833 13829 25833 13829 25834 12908 25834 12905 25834 12907 25835 13835 25835 12912 25835 12912 25836 13835 25836 13833 25836 12912 25837 13833 25837 12945 25837 13832 25838 12910 25838 12909 25838 12909 25839 12910 25839 12908 25839 12909 25840 12908 25840 12911 25840 12911 25841 12908 25841 12912 25841 12911 25842 12912 25842 12913 25842 12913 25843 12912 25843 12945 25843 12913 25844 12945 25844 12914 25844 12923 25845 12925 25845 12915 25845 12915 25846 12925 25846 12916 25846 12915 25847 12916 25847 12918 25847 12918 25848 12916 25848 12917 25848 12918 25849 12917 25849 12919 25849 12890 25850 12929 25850 12921 25850 12921 25851 12929 25851 12920 25851 12921 25852 12920 25852 12922 25852 12923 25853 13822 25853 12925 25853 12925 25854 13822 25854 12924 25854 12925 25855 12924 25855 12928 25855 12928 25856 12924 25856 13823 25856 12928 25857 13823 25857 13828 25857 13827 25858 12926 25858 13828 25858 13828 25859 12926 25859 12927 25859 13828 25860 12927 25860 12928 25860 12928 25861 12927 25861 12895 25861 12928 25862 12895 25862 12925 25862 12925 25863 12895 25863 12929 25863 12925 25864 12929 25864 12916 25864 12916 25865 12929 25865 12890 25865 12916 25866 12890 25866 12917 25866 12899 25867 12944 25867 12900 25867 12900 25868 12944 25868 14180 25868 12900 25869 14180 25869 12930 25869 12930 25870 14180 25870 12931 25870 12930 25871 12931 25871 12933 25871 12933 25872 12931 25872 12932 25872 12932 25873 14193 25873 12933 25873 12933 25874 14193 25874 14153 25874 12933 25875 14153 25875 12934 25875 12934 25876 14153 25876 12936 25876 12934 25877 12936 25877 12935 25877 12935 25878 12936 25878 12937 25878 12935 25879 12937 25879 14215 25879 12948 25880 12898 25880 12913 25880 12913 25881 12898 25881 12938 25881 12913 25882 12938 25882 12911 25882 12911 25883 12938 25883 12901 25883 12911 25884 12901 25884 12909 25884 12909 25885 12901 25885 12939 25885 12909 25886 12939 25886 12926 25886 12926 25887 12939 25887 12902 25887 12926 25888 12902 25888 12927 25888 12927 25889 12902 25889 12903 25889 12927 25890 12903 25890 12895 25890 12895 25891 12903 25891 12904 25891 12895 25892 12904 25892 12920 25892 12920 25893 12904 25893 12940 25893 12920 25894 12940 25894 12922 25894 12922 25895 12940 25895 12942 25895 12922 25896 12942 25896 12941 25896 12941 25897 12942 25897 12943 25897 14207 25898 12944 25898 12899 25898 13833 25899 13816 25899 12945 25899 12945 25900 13816 25900 12914 25900 12946 25901 13807 25901 14207 25901 12946 25902 14207 25902 12947 25902 12947 25903 14207 25903 12899 25903 12947 25904 12899 25904 13814 25904 13814 25905 12899 25905 12898 25905 13814 25906 12898 25906 12949 25906 12949 25907 12898 25907 12948 25907 12949 25908 12948 25908 12950 25908 12950 25909 12948 25909 12914 25909 12950 25910 12914 25910 12951 25910 12951 25911 12914 25911 13816 25911 12951 25912 13816 25912 13817 25912 13748 25913 13747 25913 12952 25913 14338 25914 13722 25914 13742 25914 14338 25915 13742 25915 12953 25915 13727 25916 13726 25916 13746 25916 13746 25917 13748 25917 13727 25917 13727 25918 13748 25918 12952 25918 13727 25919 12952 25919 12956 25919 12956 25920 12952 25920 12955 25920 13742 25921 13741 25921 12953 25921 12953 25922 13741 25922 13739 25922 12953 25923 13739 25923 12955 25923 12955 25924 13739 25924 12954 25924 12955 25925 12954 25925 12956 25925 13747 25926 12963 25926 12952 25926 12952 25927 12963 25927 12957 25927 12952 25928 12957 25928 12955 25928 12955 25929 12957 25929 12961 25929 12955 25930 12961 25930 12953 25930 12953 25931 12961 25931 12958 25931 12953 25932 12958 25932 14338 25932 14338 25933 12958 25933 12959 25933 12965 25934 12959 25934 12966 25934 12966 25935 12959 25935 12958 25935 12966 25936 12958 25936 12960 25936 12960 25937 12958 25937 12961 25937 12960 25938 12961 25938 12994 25938 12994 25939 12961 25939 12957 25939 12994 25940 12957 25940 12962 25940 12962 25941 12957 25941 12963 25941 12962 25942 12963 25942 12964 25942 12965 25943 12966 25943 12967 25943 12967 25944 12966 25944 12976 25944 12972 25945 13000 25945 12975 25945 12975 25946 13000 25946 14342 25946 12975 25947 14342 25947 12976 25947 12976 25948 14342 25948 14341 25948 12976 25949 14341 25949 12967 25949 13020 25950 13019 25950 13001 25950 13001 25951 13019 25951 12968 25951 13001 25952 12968 25952 13003 25952 13003 25953 12968 25953 12969 25953 13003 25954 12969 25954 13006 25954 13006 25955 12969 25955 12997 25955 13006 25956 12997 25956 13007 25956 13007 25957 12997 25957 12970 25957 13007 25958 12970 25958 12971 25958 12971 25959 12970 25959 12972 25959 12971 25960 12972 25960 12973 25960 12973 25961 12972 25961 12975 25961 12973 25962 12975 25962 12974 25962 12974 25963 12975 25963 12976 25963 12974 25964 12976 25964 12960 25964 12960 25965 12976 25965 12966 25965 12980 25966 12985 25966 13004 25966 13755 25967 12977 25967 13005 25967 13005 25968 12977 25968 12978 25968 13005 25969 12978 25969 13004 25969 13004 25970 12978 25970 12979 25970 13004 25971 12979 25971 12980 25971 12980 25972 12981 25972 12982 25972 12982 25973 12981 25973 12983 25973 12982 25974 12983 25974 12986 25974 12986 25975 12983 25975 12984 25975 12986 25976 12984 25976 13021 25976 12980 25977 12982 25977 12985 25977 12985 25978 12982 25978 12986 25978 12985 25979 12986 25979 13002 25979 13002 25980 12986 25980 13021 25980 13002 25981 13021 25981 12987 25981 12962 25982 12964 25982 13749 25982 12962 25983 13749 25983 12989 25983 13752 25984 12990 25984 13751 25984 13751 25985 12990 25985 12989 25985 13751 25986 12989 25986 12988 25986 12988 25987 12989 25987 13749 25987 13752 25988 13753 25988 12990 25988 12990 25989 13753 25989 13754 25989 12990 25990 13754 25990 12993 25990 12993 25991 13754 25991 12991 25991 12993 25992 12991 25992 12992 25992 13755 25993 13005 25993 12992 25993 12992 25994 13005 25994 13008 25994 12992 25995 13008 25995 12993 25995 12993 25996 13008 25996 13009 25996 12993 25997 13009 25997 12990 25997 12990 25998 13009 25998 13010 25998 12990 25999 13010 25999 12989 25999 12989 26000 13010 26000 12994 26000 12989 26001 12994 26001 12962 26001 13019 26002 12995 26002 12968 26002 12968 26003 12995 26003 12996 26003 12968 26004 12996 26004 12969 26004 12969 26005 12996 26005 12998 26005 12969 26006 12998 26006 12997 26006 12997 26007 12998 26007 14344 26007 12997 26008 14344 26008 12970 26008 12970 26009 14344 26009 12999 26009 12970 26010 12999 26010 12972 26010 12972 26011 12999 26011 14343 26011 12972 26012 14343 26012 13000 26012 12987 26013 13020 26013 13002 26013 13002 26014 13020 26014 13001 26014 13002 26015 13001 26015 12985 26015 12985 26016 13001 26016 13003 26016 12985 26017 13003 26017 13004 26017 13004 26018 13003 26018 13006 26018 13004 26019 13006 26019 13005 26019 13005 26020 13006 26020 13007 26020 13005 26021 13007 26021 13008 26021 13008 26022 13007 26022 12971 26022 13008 26023 12971 26023 13009 26023 13009 26024 12971 26024 12973 26024 13009 26025 12973 26025 13010 26025 13010 26026 12973 26026 12974 26026 13010 26027 12974 26027 12994 26027 12994 26028 12974 26028 12960 26028 14378 26029 12995 26029 13019 26029 13730 26030 13729 26030 13744 26030 13744 26031 13729 26031 13011 26031 12984 26032 13745 26032 13021 26032 13021 26033 13745 26033 13018 26033 13729 26034 13728 26034 13011 26034 13011 26035 13728 26035 13013 26035 13011 26036 13013 26036 13012 26036 13012 26037 13013 26037 13724 26037 13012 26038 13724 26038 13014 26038 13014 26039 13724 26039 13723 26039 13014 26040 13723 26040 13015 26040 13015 26041 14374 26041 13014 26041 13014 26042 14374 26042 13016 26042 13014 26043 13016 26043 13012 26043 13012 26044 13016 26044 13017 26044 13012 26045 13017 26045 13011 26045 13011 26046 13017 26046 13018 26046 13011 26047 13018 26047 13744 26047 13744 26048 13018 26048 13745 26048 14374 26049 14378 26049 13016 26049 13016 26050 14378 26050 13019 26050 13016 26051 13019 26051 13017 26051 13017 26052 13019 26052 13020 26052 13017 26053 13020 26053 13018 26053 13018 26054 13020 26054 12987 26054 13018 26055 12987 26055 13021 26055 13051 26056 13022 26056 13049 26056 13049 26057 13022 26057 13800 26057 13776 26058 13022 26058 13778 26058 13778 26059 13022 26059 13051 26059 13778 26060 13051 26060 13779 26060 13779 26061 13051 26061 13023 26061 13779 26062 13023 26062 13024 26062 13024 26063 13023 26063 13069 26063 13024 26064 13069 26064 13025 26064 13025 26065 13069 26065 13068 26065 13025 26066 13068 26066 13780 26066 14155 26067 13781 26067 13026 26067 13026 26068 13781 26068 13780 26068 13026 26069 13780 26069 14156 26069 14156 26070 13780 26070 13068 26070 14156 26071 13068 26071 13027 26071 13027 26072 13068 26072 14252 26072 13077 26073 13063 26073 13062 26073 13028 26074 13030 26074 13031 26074 13029 26075 13061 26075 13030 26075 13030 26076 13061 26076 14174 26076 13030 26077 14174 26077 13031 26077 14252 26078 13068 26078 13028 26078 13028 26079 13068 26079 13032 26079 13028 26080 13032 26080 13030 26080 13030 26081 13032 26081 13070 26081 13030 26082 13070 26082 13029 26082 13029 26083 13070 26083 13072 26083 13029 26084 13072 26084 13033 26084 13075 26085 13067 26085 13034 26085 13034 26086 13067 26086 13035 26086 13034 26087 13035 26087 13073 26087 13072 26088 13073 26088 13033 26088 13033 26089 13073 26089 13035 26089 13033 26090 13035 26090 13036 26090 13036 26091 13035 26091 13067 26091 13036 26092 13067 26092 14173 26092 14840 26093 13039 26093 14841 26093 14841 26094 13039 26094 13042 26094 14841 26095 13042 26095 13043 26095 13037 26096 14843 26096 13038 26096 13038 26097 14843 26097 14842 26097 13038 26098 14842 26098 13074 26098 14840 26099 14846 26099 13039 26099 13039 26100 14846 26100 13041 26100 13039 26101 13041 26101 13040 26101 13040 26102 13041 26102 14845 26102 13040 26103 14845 26103 14844 26103 13040 26104 13076 26104 13039 26104 13039 26105 13076 26105 13074 26105 13039 26106 13074 26106 13042 26106 13042 26107 13074 26107 14842 26107 13042 26108 14842 26108 13043 26108 13062 26109 13065 26109 13075 26109 13049 26110 13800 26110 13044 26110 13044 26111 13800 26111 14831 26111 13044 26112 14831 26112 13047 26112 13045 26113 14830 26113 13046 26113 13046 26114 14830 26114 14834 26114 13046 26115 14834 26115 13071 26115 13071 26116 14834 26116 14835 26116 13071 26117 14835 26117 13053 26117 13047 26118 13045 26118 13044 26118 13044 26119 13045 26119 13046 26119 13044 26120 13046 26120 13050 26120 13050 26121 13046 26121 13071 26121 13050 26122 13071 26122 13048 26122 13049 26123 13044 26123 13051 26123 13051 26124 13044 26124 13050 26124 13051 26125 13050 26125 13023 26125 13023 26126 13050 26126 13048 26126 13023 26127 13048 26127 13069 26127 14835 26128 13052 26128 13053 26128 13053 26129 13052 26129 14837 26129 13053 26130 14837 26130 13038 26130 13038 26131 14837 26131 13054 26131 13038 26132 13054 26132 13037 26132 13055 26133 13056 26133 14239 26133 13063 26134 13057 26134 13064 26134 13064 26135 13057 26135 13055 26135 13064 26136 13055 26136 13066 26136 13066 26137 13055 26137 14239 26137 13066 26138 14239 26138 14238 26138 13036 26139 13058 26139 13033 26139 13033 26140 13058 26140 13059 26140 13033 26141 13059 26141 13029 26141 13029 26142 13059 26142 13060 26142 13029 26143 13060 26143 13061 26143 13062 26144 13063 26144 13065 26144 13065 26145 13063 26145 13064 26145 13065 26146 13064 26146 13075 26146 13075 26147 13064 26147 13066 26147 13075 26148 13066 26148 13067 26148 13067 26149 13066 26149 14238 26149 13067 26150 14238 26150 14173 26150 13068 26151 13069 26151 13032 26151 13032 26152 13069 26152 13048 26152 13032 26153 13048 26153 13070 26153 13070 26154 13048 26154 13071 26154 13070 26155 13071 26155 13072 26155 13072 26156 13071 26156 13053 26156 13072 26157 13053 26157 13073 26157 13073 26158 13053 26158 13038 26158 13073 26159 13038 26159 13034 26159 13034 26160 13038 26160 13074 26160 13034 26161 13074 26161 13075 26161 13075 26162 13074 26162 13076 26162 13075 26163 13076 26163 13062 26163 13062 26164 13076 26164 13040 26164 13062 26165 13040 26165 13077 26165 13077 26166 13040 26166 14844 26166 13077 26167 14844 26167 13796 26167 13077 26168 13796 26168 13797 26168 13799 26169 13784 26169 13797 26169 13797 26170 13784 26170 13063 26170 13797 26171 13063 26171 13077 26171 13078 26172 13083 26172 13794 26172 13794 26173 13083 26173 13079 26173 13082 26174 13790 26174 13079 26174 13079 26175 13790 26175 13080 26175 13079 26176 13080 26176 13794 26176 13782 26177 13081 26177 13082 26177 13082 26178 13081 26178 13791 26178 13082 26179 13791 26179 13790 26179 13784 26180 13782 26180 13063 26180 13063 26181 13782 26181 13082 26181 13063 26182 13082 26182 13057 26182 13057 26183 13082 26183 13079 26183 13057 26184 13079 26184 13055 26184 13055 26185 13079 26185 13083 26185 13055 26186 13083 26186 13056 26186 13084 26187 13769 26187 13773 26187 13773 26188 13085 26188 13084 26188 13084 26189 13085 26189 13090 26189 13084 26190 13090 26190 13086 26190 13086 26191 13090 26191 13770 26191 13770 26192 13090 26192 13089 26192 13770 26193 13089 26193 13087 26193 13087 26194 13089 26194 13088 26194 13088 26195 13089 26195 14381 26195 13088 26196 14381 26196 14382 26196 13092 26197 14381 26197 13094 26197 13094 26198 14381 26198 13089 26198 13094 26199 13089 26199 13096 26199 13096 26200 13089 26200 13090 26200 13096 26201 13090 26201 13099 26201 13099 26202 13090 26202 13085 26202 13099 26203 13085 26203 13091 26203 13091 26204 13085 26204 13773 26204 13111 26205 13092 26205 13093 26205 13093 26206 13092 26206 13094 26206 13093 26207 13094 26207 13095 26207 13095 26208 13094 26208 13096 26208 13095 26209 13096 26209 13097 26209 13097 26210 13096 26210 13099 26210 13097 26211 13099 26211 13098 26211 13098 26212 13099 26212 13091 26212 13098 26213 13091 26213 14847 26213 13100 26214 13129 26214 13101 26214 13102 26215 13103 26215 13104 26215 13104 26216 13103 26216 14857 26216 13104 26217 14857 26217 13126 26217 13105 26218 13140 26218 13110 26218 13105 26219 13106 26219 13107 26219 13107 26220 13106 26220 13108 26220 13107 26221 13108 26221 13102 26221 13102 26222 13108 26222 13109 26222 13102 26223 13109 26223 13103 26223 13127 26224 14851 26224 13128 26224 13128 26225 14851 26225 14850 26225 13128 26226 14850 26226 13110 26226 13110 26227 14850 26227 14854 26227 13110 26228 14854 26228 13105 26228 13131 26229 14849 26229 13130 26229 13111 26230 13093 26230 13123 26230 13137 26231 13112 26231 13113 26231 13113 26232 13112 26232 13114 26232 13113 26233 13114 26233 13123 26233 13123 26234 13114 26234 14379 26234 13123 26235 14379 26235 13111 26235 13135 26236 13136 26236 13115 26236 13115 26237 13136 26237 13120 26237 13115 26238 13120 26238 13116 26238 13138 26239 13148 26239 13139 26239 13139 26240 13148 26240 13133 26240 13139 26241 13133 26241 13117 26241 13117 26242 13133 26242 13118 26242 13117 26243 13118 26243 13119 26243 13119 26244 13118 26244 13120 26244 13119 26245 13120 26245 13141 26245 13141 26246 13120 26246 13136 26246 13141 26247 13136 26247 13121 26247 13121 26248 13136 26248 13137 26248 13121 26249 13137 26249 13142 26249 13142 26250 13137 26250 13113 26250 13142 26251 13113 26251 13122 26251 13122 26252 13113 26252 13123 26252 13122 26253 13123 26253 13095 26253 13095 26254 13123 26254 13093 26254 13105 26255 13107 26255 13140 26255 13140 26256 13107 26256 13102 26256 13140 26257 13102 26257 13124 26257 13124 26258 13102 26258 13104 26258 13124 26259 13104 26259 13125 26259 13125 26260 13104 26260 13126 26260 13125 26261 13126 26261 13149 26261 14847 26262 14849 26262 13098 26262 13098 26263 14849 26263 13131 26263 13098 26264 13131 26264 13097 26264 13127 26265 13128 26265 14852 26265 14852 26266 13128 26266 13129 26266 14852 26267 13129 26267 13130 26267 13130 26268 13129 26268 13100 26268 13130 26269 13100 26269 13131 26269 13131 26270 13100 26270 13101 26270 13131 26271 13101 26271 13097 26271 13116 26272 13120 26272 13132 26272 13132 26273 13120 26273 13118 26273 13132 26274 13118 26274 14358 26274 14358 26275 13118 26275 13133 26275 14358 26276 13133 26276 13134 26276 13134 26277 13133 26277 13148 26277 13134 26278 13148 26278 14363 26278 13135 26279 14356 26279 13136 26279 13136 26280 14356 26280 14355 26280 13136 26281 14355 26281 13137 26281 13137 26282 14355 26282 14353 26282 13137 26283 14353 26283 13112 26283 13149 26284 13138 26284 13125 26284 13125 26285 13138 26285 13139 26285 13125 26286 13139 26286 13124 26286 13124 26287 13139 26287 13117 26287 13124 26288 13117 26288 13140 26288 13140 26289 13117 26289 13119 26289 13140 26290 13119 26290 13110 26290 13110 26291 13119 26291 13141 26291 13110 26292 13141 26292 13128 26292 13128 26293 13141 26293 13121 26293 13128 26294 13121 26294 13129 26294 13129 26295 13121 26295 13142 26295 13129 26296 13142 26296 13101 26296 13101 26297 13142 26297 13122 26297 13101 26298 13122 26298 13097 26298 13097 26299 13122 26299 13095 26299 14857 26300 13771 26300 13150 26300 13143 26301 14360 26301 14362 26301 14383 26302 14360 26302 13757 26302 13757 26303 14360 26303 13143 26303 13757 26304 13143 26304 13763 26304 13146 26305 13152 26305 13144 26305 13144 26306 13152 26306 13145 26306 13144 26307 13145 26307 13764 26307 13764 26308 13145 26308 13765 26308 13146 26309 13763 26309 13152 26309 13152 26310 13763 26310 13143 26310 13152 26311 13143 26311 13147 26311 13147 26312 13143 26312 14362 26312 13147 26313 14362 26313 14363 26313 13148 26314 13138 26314 13151 26314 13151 26315 13138 26315 13149 26315 13151 26316 13149 26316 13150 26316 13150 26317 13149 26317 13126 26317 13150 26318 13126 26318 14857 26318 14363 26319 13148 26319 13147 26319 13147 26320 13148 26320 13151 26320 13147 26321 13151 26321 13152 26321 13152 26322 13151 26322 13150 26322 13152 26323 13150 26323 13145 26323 13145 26324 13150 26324 13771 26324 13145 26325 13771 26325 13765 26325 13325 26326 13209 26326 13208 26326 14284 26327 13153 26327 13208 26327 13208 26328 13153 26328 13154 26328 13208 26329 13154 26329 14223 26329 14223 26330 14222 26330 13208 26330 13208 26331 14222 26331 14290 26331 13208 26332 14290 26332 13155 26332 13155 26333 14290 26333 14384 26333 13190 26334 13156 26334 13157 26334 13157 26335 13156 26335 13206 26335 13157 26336 13206 26336 13207 26336 13188 26337 13158 26337 13159 26337 13159 26338 13158 26338 13160 26338 13159 26339 13160 26339 13190 26339 13190 26340 13160 26340 13161 26340 13190 26341 13161 26341 13156 26341 13170 26342 13162 26342 13182 26342 13182 26343 13162 26343 13163 26343 13182 26344 13163 26344 13164 26344 13164 26345 13163 26345 13165 26345 13164 26346 13165 26346 13185 26346 13185 26347 13165 26347 13166 26347 13185 26348 13166 26348 13186 26348 13186 26349 13166 26349 13167 26349 13186 26350 13167 26350 13187 26350 13187 26351 13167 26351 14178 26351 13187 26352 14178 26352 13188 26352 13188 26353 14178 26353 13168 26353 13188 26354 13168 26354 13158 26354 13171 26355 13173 26355 13169 26355 13169 26356 13173 26356 14171 26356 13169 26357 14171 26357 13170 26357 13170 26358 14171 26358 14170 26358 13170 26359 14170 26359 13162 26359 13175 26360 14163 26360 13171 26360 13171 26361 14163 26361 13172 26361 13171 26362 13172 26362 13173 26362 13174 26363 13236 26363 13175 26363 13175 26364 13236 26364 13235 26364 13175 26365 13235 26365 14163 26365 13258 26366 13174 26366 13193 26366 13176 26367 13258 26367 13192 26367 13176 26368 13192 26368 13177 26368 13177 26369 13192 26369 13178 26369 13177 26370 13178 26370 14583 26370 14583 26371 13178 26371 13179 26371 14583 26372 13179 26372 14584 26372 13174 26373 13175 26373 13193 26373 13193 26374 13175 26374 13171 26374 13193 26375 13171 26375 13180 26375 13180 26376 13171 26376 13169 26376 13180 26377 13169 26377 13181 26377 13181 26378 13169 26378 13170 26378 13181 26379 13170 26379 13194 26379 13194 26380 13170 26380 13182 26380 13194 26381 13182 26381 13195 26381 13195 26382 13182 26382 13164 26382 13195 26383 13164 26383 13183 26383 13183 26384 13164 26384 13185 26384 13183 26385 13185 26385 13184 26385 13184 26386 13185 26386 13186 26386 13184 26387 13186 26387 13198 26387 13198 26388 13186 26388 13187 26388 13198 26389 13187 26389 13199 26389 13199 26390 13187 26390 13188 26390 13199 26391 13188 26391 13201 26391 13201 26392 13188 26392 13159 26392 13201 26393 13159 26393 13189 26393 13189 26394 13159 26394 13190 26394 13189 26395 13190 26395 13191 26395 13191 26396 13190 26396 13157 26396 13191 26397 13157 26397 13204 26397 13204 26398 13157 26398 13207 26398 13204 26399 13207 26399 13205 26399 13258 26400 13193 26400 13192 26400 13192 26401 13193 26401 13180 26401 13192 26402 13180 26402 13178 26402 13178 26403 13180 26403 13181 26403 13178 26404 13181 26404 13179 26404 13179 26405 13181 26405 13194 26405 13179 26406 13194 26406 13212 26406 13212 26407 13194 26407 13195 26407 13212 26408 13195 26408 13213 26408 13213 26409 13195 26409 13183 26409 13213 26410 13183 26410 13196 26410 13196 26411 13183 26411 13184 26411 13196 26412 13184 26412 13197 26412 13197 26413 13184 26413 13198 26413 13197 26414 13198 26414 13216 26414 13216 26415 13198 26415 13199 26415 13216 26416 13199 26416 13200 26416 13200 26417 13199 26417 13201 26417 13200 26418 13201 26418 13220 26418 13220 26419 13201 26419 13189 26419 13220 26420 13189 26420 13202 26420 13202 26421 13189 26421 13191 26421 13202 26422 13191 26422 13203 26422 13203 26423 13191 26423 13204 26423 13203 26424 13204 26424 13223 26424 13223 26425 13204 26425 13205 26425 13223 26426 13205 26426 13224 26426 13206 26427 14284 26427 13207 26427 13207 26428 14284 26428 13208 26428 13207 26429 13208 26429 13205 26429 13205 26430 13208 26430 13209 26430 13205 26431 13209 26431 13224 26431 13224 26432 13209 26432 13316 26432 13224 26433 13316 26433 13210 26433 14584 26434 13179 26434 13211 26434 13211 26435 13179 26435 13212 26435 13211 26436 13212 26436 14578 26436 14578 26437 13212 26437 13213 26437 14578 26438 13213 26438 13214 26438 13214 26439 13213 26439 13196 26439 13214 26440 13196 26440 14582 26440 14582 26441 13196 26441 13197 26441 14582 26442 13197 26442 13215 26442 13215 26443 13197 26443 13216 26443 13215 26444 13216 26444 13217 26444 13217 26445 13216 26445 13200 26445 13217 26446 13200 26446 13218 26446 13218 26447 13200 26447 13220 26447 13218 26448 13220 26448 13219 26448 13219 26449 13220 26449 13202 26449 13219 26450 13202 26450 13221 26450 13221 26451 13202 26451 13203 26451 13221 26452 13203 26452 13222 26452 13222 26453 13203 26453 13223 26453 13222 26454 13223 26454 14575 26454 14575 26455 13223 26455 13224 26455 14575 26456 13224 26456 14574 26456 14574 26457 13224 26457 13210 26457 14574 26458 13210 26458 14572 26458 14158 26459 13227 26459 13225 26459 13225 26460 13227 26460 13226 26460 13225 26461 13226 26461 13237 26461 13278 26462 13237 26462 13246 26462 14597 26463 13278 26463 13247 26463 13227 26464 14157 26464 13226 26464 13226 26465 14157 26465 13229 26465 13226 26466 13229 26466 13228 26466 13228 26467 13229 26467 14162 26467 13228 26468 14162 26468 13238 26468 14162 26469 14251 26469 13238 26469 13238 26470 14251 26470 13230 26470 13238 26471 13230 26471 13242 26471 13242 26472 13230 26472 14168 26472 13242 26473 14168 26473 13231 26473 13231 26474 14168 26474 13233 26474 13231 26475 13233 26475 13232 26475 13232 26476 13233 26476 14165 26476 13232 26477 14165 26477 13234 26477 13234 26478 14165 26478 13235 26478 13234 26479 13235 26479 13236 26479 13237 26480 13226 26480 13246 26480 13246 26481 13226 26481 13228 26481 13246 26482 13228 26482 13239 26482 13239 26483 13228 26483 13238 26483 13239 26484 13238 26484 13240 26484 13240 26485 13238 26485 13242 26485 13240 26486 13242 26486 13241 26486 13241 26487 13242 26487 13231 26487 13241 26488 13231 26488 13243 26488 13243 26489 13231 26489 13232 26489 13243 26490 13232 26490 13244 26490 13244 26491 13232 26491 13234 26491 13244 26492 13234 26492 13245 26492 13245 26493 13234 26493 13236 26493 13245 26494 13236 26494 13174 26494 13278 26495 13246 26495 13247 26495 13247 26496 13246 26496 13239 26496 13247 26497 13239 26497 13252 26497 13252 26498 13239 26498 13240 26498 13252 26499 13240 26499 13253 26499 13253 26500 13240 26500 13241 26500 13253 26501 13241 26501 13255 26501 13255 26502 13241 26502 13243 26502 13255 26503 13243 26503 13248 26503 13248 26504 13243 26504 13244 26504 13248 26505 13244 26505 13249 26505 13249 26506 13244 26506 13245 26506 13249 26507 13245 26507 13250 26507 13250 26508 13245 26508 13174 26508 13250 26509 13174 26509 13258 26509 14597 26510 13247 26510 13251 26510 13251 26511 13247 26511 13252 26511 13251 26512 13252 26512 14594 26512 14594 26513 13252 26513 13253 26513 14594 26514 13253 26514 13254 26514 13254 26515 13253 26515 13255 26515 13254 26516 13255 26516 14590 26516 14590 26517 13255 26517 13248 26517 14590 26518 13248 26518 14715 26518 14715 26519 13248 26519 13249 26519 14715 26520 13249 26520 13256 26520 13256 26521 13249 26521 13250 26521 13256 26522 13250 26522 13257 26522 13257 26523 13250 26523 13258 26523 13257 26524 13258 26524 13176 26524 13260 26525 14201 26525 13259 26525 14258 26526 13261 26526 14297 26526 14297 26527 13261 26527 14298 26527 13260 26528 13259 26528 14183 26528 14258 26529 14183 26529 13261 26529 13261 26530 14183 26530 13259 26530 13261 26531 13259 26531 13288 26531 13284 26532 13288 26532 13262 26532 14507 26533 13263 26533 13264 26533 13264 26534 13263 26534 13265 26534 13264 26535 13265 26535 13273 26535 14201 26536 13266 26536 13259 26536 13259 26537 13266 26537 14160 26537 13259 26538 14160 26538 13267 26538 13267 26539 14160 26539 13268 26539 13267 26540 13268 26540 13274 26540 13288 26541 13259 26541 13262 26541 13262 26542 13259 26542 13267 26542 13262 26543 13267 26543 13271 26543 13271 26544 13267 26544 13274 26544 13271 26545 13274 26545 13269 26545 13277 26546 13276 26546 13269 26546 13269 26547 13276 26547 13270 26547 13269 26548 13270 26548 13271 26548 13271 26549 13270 26549 13272 26549 13271 26550 13272 26550 13262 26550 13262 26551 13272 26551 13264 26551 13262 26552 13264 26552 13284 26552 13284 26553 13264 26553 13273 26553 13284 26554 13273 26554 13279 26554 13268 26555 14158 26555 13274 26555 13274 26556 14158 26556 13225 26556 13274 26557 13225 26557 13269 26557 13269 26558 13225 26558 13237 26558 13269 26559 13237 26559 13277 26559 13277 26560 13237 26560 13278 26560 14507 26561 13264 26561 14598 26561 14598 26562 13264 26562 13272 26562 14598 26563 13272 26563 13275 26563 13275 26564 13272 26564 13270 26564 13275 26565 13270 26565 14602 26565 14602 26566 13270 26566 13276 26566 14602 26567 13276 26567 14603 26567 14603 26568 13276 26568 13277 26568 14603 26569 13277 26569 14587 26569 14587 26570 13277 26570 13278 26570 14587 26571 13278 26571 14597 26571 13284 26572 13279 26572 13280 26572 14628 26573 14625 26573 13289 26573 13301 26574 14612 26574 14706 26574 14622 26575 13281 26575 13289 26575 13289 26576 13281 26576 14705 26576 13289 26577 14705 26577 14628 26577 14612 26578 13301 26578 14609 26578 13300 26579 13282 26579 13283 26579 13280 26580 14525 26580 13284 26580 13284 26581 14525 26581 13285 26581 13284 26582 13285 26582 13286 26582 13282 26583 13300 26583 13286 26583 13286 26584 13300 26584 13284 26584 13284 26585 13300 26585 13287 26585 13284 26586 13287 26586 13288 26586 13288 26587 13287 26587 13298 26587 13288 26588 13298 26588 13261 26588 13292 26589 14082 26589 13293 26589 14706 26590 14622 26590 13301 26590 13301 26591 14622 26591 13289 26591 13301 26592 13289 26592 13299 26592 13299 26593 13289 26593 13304 26593 13299 26594 13304 26594 13290 26594 13290 26595 13304 26595 13292 26595 13290 26596 13292 26596 13291 26596 13291 26597 13292 26597 13293 26597 14298 26598 13261 26598 13294 26598 13294 26599 13261 26599 13298 26599 13294 26600 13298 26600 13295 26600 13295 26601 13298 26601 13296 26601 13291 26602 14334 26602 13290 26602 13290 26603 14334 26603 14336 26603 13290 26604 14336 26604 13297 26604 13297 26605 13296 26605 13290 26605 13290 26606 13296 26606 13298 26606 13290 26607 13298 26607 13299 26607 13299 26608 13298 26608 13287 26608 13299 26609 13287 26609 13301 26609 13301 26610 13287 26610 13300 26610 13301 26611 13300 26611 14609 26611 14609 26612 13300 26612 13283 26612 14631 26613 14632 26613 13303 26613 13303 26614 14632 26614 13302 26614 13303 26615 13302 26615 19250 26615 14083 26616 14082 26616 13292 26616 14625 26617 14631 26617 13289 26617 13289 26618 14631 26618 13303 26618 13289 26619 13303 26619 13304 26619 13304 26620 13303 26620 13307 26620 13304 26621 13307 26621 13292 26621 13292 26622 13307 26622 13306 26622 13292 26623 13306 26623 14083 26623 14083 26624 13306 26624 13305 26624 14504 26625 13305 26625 13306 26625 12824 26626 14505 26626 14504 26626 14504 26627 13306 26627 12824 26627 12824 26628 13306 26628 13307 26628 12824 26629 13307 26629 12827 26629 12827 26630 13307 26630 13303 26630 12827 26631 13303 26631 12840 26631 12840 26632 13303 26632 12839 26632 12839 26633 13303 26633 19250 26633 12839 26634 19250 26634 14637 26634 13325 26635 13208 26635 13328 26635 13308 26636 13309 26636 13336 26636 13333 26637 14551 26637 13334 26637 13334 26638 14551 26638 14563 26638 13313 26639 13310 26639 14332 26639 14332 26640 13310 26640 13323 26640 13334 26641 13311 26641 13340 26641 13340 26642 13311 26642 13312 26642 13340 26643 13312 26643 13336 26643 13336 26644 13312 26644 13310 26644 13336 26645 13310 26645 13308 26645 13308 26646 13310 26646 13313 26646 13327 26647 14473 26647 14474 26647 14566 26648 13314 26648 13315 26648 13315 26649 13314 26649 13316 26649 13315 26650 13316 26650 13209 26650 13314 26651 14532 26651 13316 26651 13316 26652 14532 26652 14531 26652 13316 26653 14531 26653 13210 26653 13210 26654 14531 26654 14572 26654 14542 26655 13317 26655 13320 26655 13320 26656 13317 26656 13318 26656 13318 26657 13319 26657 13320 26657 13320 26658 13319 26658 13321 26658 13320 26659 13321 26659 13315 26659 13315 26660 13321 26660 13322 26660 13315 26661 13322 26661 14566 26661 14474 26662 13323 26662 13327 26662 13327 26663 13323 26663 13310 26663 13327 26664 13310 26664 13326 26664 13326 26665 13310 26665 13312 26665 13326 26666 13312 26666 13324 26666 13324 26667 13312 26667 13311 26667 14563 26668 14542 26668 13334 26668 13334 26669 14542 26669 13320 26669 13334 26670 13320 26670 13311 26670 13311 26671 13320 26671 13315 26671 13311 26672 13315 26672 13324 26672 13324 26673 13315 26673 13209 26673 13324 26674 13209 26674 13326 26674 13326 26675 13209 26675 13325 26675 13326 26676 13325 26676 13327 26676 13327 26677 13325 26677 13328 26677 13327 26678 13328 26678 14473 26678 14473 26679 13328 26679 14384 26679 13329 26680 14070 26680 13335 26680 14786 26681 13330 26681 13341 26681 14786 26682 13341 26682 14069 26682 13336 26683 13309 26683 14074 26683 13338 26684 13331 26684 13332 26684 13332 26685 13331 26685 13333 26685 13332 26686 13333 26686 13334 26686 13342 26687 13340 26687 13335 26687 13335 26688 13340 26688 13336 26688 13335 26689 13336 26689 13329 26689 13329 26690 13336 26690 14074 26690 13337 26691 12800 26691 12799 26691 12782 26692 13338 26692 13339 26692 13339 26693 13338 26693 13332 26693 13339 26694 13332 26694 13342 26694 13342 26695 13332 26695 13334 26695 13342 26696 13334 26696 13340 26696 14070 26697 14069 26697 13335 26697 13335 26698 14069 26698 13341 26698 13335 26699 13341 26699 13342 26699 13342 26700 13341 26700 13337 26700 13342 26701 13337 26701 13339 26701 13339 26702 13337 26702 12799 26702 13339 26703 12799 26703 12782 26703 13343 26704 13344 26704 13349 26704 13345 26705 13352 26705 13346 26705 13346 26706 13352 26706 14764 26706 13346 26707 14764 26707 13347 26707 13347 26708 14764 26708 13343 26708 13347 26709 13343 26709 13348 26709 13348 26710 13343 26710 13349 26710 13348 26711 13349 26711 13700 26711 13354 26712 13849 26712 13475 26712 13475 26713 13849 26713 12845 26713 13475 26714 12845 26714 13476 26714 12845 26715 13350 26715 13476 26715 13476 26716 13350 26716 13351 26716 13476 26717 13351 26717 13345 26717 13345 26718 13351 26718 14763 26718 13345 26719 14763 26719 13352 26719 13353 26720 13354 26720 13475 26720 14759 26721 13479 26721 13467 26721 14737 26722 13419 26722 13400 26722 13412 26723 13355 26723 13402 26723 13363 26724 13361 26724 13360 26724 14726 26725 13359 26725 13362 26725 13390 26726 13389 26726 13362 26726 13362 26727 13389 26727 13388 26727 13362 26728 13388 26728 13386 26728 13371 26729 13363 26729 13368 26729 13710 26730 13709 26730 13356 26730 13356 26731 13709 26731 13391 26731 13364 26732 13357 26732 13358 26732 13358 26733 13357 26733 13711 26733 13358 26734 13711 26734 13362 26734 14726 26735 13363 26735 13359 26735 13359 26736 13363 26736 13360 26736 13359 26737 13360 26737 13362 26737 13362 26738 13360 26738 13361 26738 13362 26739 13361 26739 13358 26739 13358 26740 13361 26740 13363 26740 13358 26741 13363 26741 13364 26741 13364 26742 13363 26742 13371 26742 13365 26743 13366 26743 13408 26743 13408 26744 13366 26744 13367 26744 13408 26745 13367 26745 13410 26745 13410 26746 13367 26746 13369 26746 13410 26747 13369 26747 13368 26747 13368 26748 13369 26748 13370 26748 13368 26749 13370 26749 13371 26749 13405 26750 13372 26750 13407 26750 13407 26751 13372 26751 13365 26751 13407 26752 13365 26752 13373 26752 13373 26753 13365 26753 13408 26753 13712 26754 13374 26754 13713 26754 13713 26755 13374 26755 13429 26755 13713 26756 13429 26756 13714 26756 13714 26757 13429 26757 13430 26757 13441 26758 13716 26758 14746 26758 14746 26759 13716 26759 13715 26759 14746 26760 13715 26760 13433 26760 13445 26761 13375 26761 13376 26761 13376 26762 13375 26762 13444 26762 13376 26763 13444 26763 13703 26763 13455 26764 13377 26764 13452 26764 13452 26765 13377 26765 13703 26765 13452 26766 13703 26766 13451 26766 13457 26767 13378 26767 13456 26767 13456 26768 13378 26768 13379 26768 13456 26769 13379 26769 13455 26769 13455 26770 13379 26770 13380 26770 13455 26771 13380 26771 13377 26771 13348 26772 13700 26772 13381 26772 13381 26773 13700 26773 13699 26773 13381 26774 13699 26774 13382 26774 13709 26775 13383 26775 13391 26775 13391 26776 13383 26776 13384 26776 13391 26777 13384 26777 13485 26777 13385 26778 13386 26778 13387 26778 13387 26779 13386 26779 13388 26779 13387 26780 13388 26780 13394 26780 13394 26781 13388 26781 13389 26781 13394 26782 13389 26782 13392 26782 13392 26783 13389 26783 13390 26783 13711 26784 13710 26784 13362 26784 13362 26785 13710 26785 13356 26785 13362 26786 13356 26786 13390 26786 13390 26787 13356 26787 13391 26787 13390 26788 13391 26788 13392 26788 13392 26789 13391 26789 13485 26789 13392 26790 13485 26790 13394 26790 13394 26791 13485 26791 13393 26791 13394 26792 13393 26792 13387 26792 13387 26793 13393 26793 13875 26793 13387 26794 13875 26794 13385 26794 13363 26795 14730 26795 13413 26795 13413 26796 14730 26796 13395 26796 13413 26797 13395 26797 13414 26797 13396 26798 14732 26798 13398 26798 13398 26799 14732 26799 14734 26799 13398 26800 14734 26800 13400 26800 13400 26801 14734 26801 13397 26801 13400 26802 13397 26802 14737 26802 13355 26803 13396 26803 13402 26803 13402 26804 13396 26804 13398 26804 13402 26805 13398 26805 13399 26805 13399 26806 13398 26806 13400 26806 13399 26807 13400 26807 13403 26807 13403 26808 13400 26808 13419 26808 13403 26809 13419 26809 13401 26809 13412 26810 13402 26810 13411 26810 13411 26811 13402 26811 13399 26811 13411 26812 13399 26812 13409 26812 13409 26813 13399 26813 13403 26813 13409 26814 13403 26814 13404 26814 13404 26815 13403 26815 13401 26815 13404 26816 13401 26816 13420 26816 13422 26817 13405 26817 13406 26817 13406 26818 13405 26818 13407 26818 13406 26819 13407 26819 13420 26819 13420 26820 13407 26820 13373 26820 13420 26821 13373 26821 13404 26821 13404 26822 13373 26822 13408 26822 13404 26823 13408 26823 13409 26823 13409 26824 13408 26824 13410 26824 13409 26825 13410 26825 13411 26825 13411 26826 13410 26826 13368 26826 13411 26827 13368 26827 13412 26827 13412 26828 13368 26828 13363 26828 13412 26829 13363 26829 13355 26829 13355 26830 13363 26830 13413 26830 13355 26831 13413 26831 13396 26831 13396 26832 13413 26832 13414 26832 13396 26833 13414 26833 14732 26833 13418 26834 14738 26834 13415 26834 13415 26835 14738 26835 13424 26835 13415 26836 13424 26836 13416 26836 13417 26837 13423 26837 13424 26837 13424 26838 13423 26838 13421 26838 13424 26839 13421 26839 13416 26839 14737 26840 13418 26840 13419 26840 13419 26841 13418 26841 13415 26841 13419 26842 13415 26842 13401 26842 13401 26843 13415 26843 13416 26843 13401 26844 13416 26844 13420 26844 13420 26845 13416 26845 13421 26845 13420 26846 13421 26846 13406 26846 13406 26847 13421 26847 13423 26847 13406 26848 13423 26848 13422 26848 13422 26849 13423 26849 13417 26849 13422 26850 13417 26850 13701 26850 13701 26851 13417 26851 13424 26851 13701 26852 13424 26852 13425 26852 13425 26853 13424 26853 13427 26853 13425 26854 13427 26854 13426 26854 13426 26855 13427 26855 14742 26855 13426 26856 14742 26856 13428 26856 13428 26857 14742 26857 13712 26857 13435 26858 13437 26858 13432 26858 13432 26859 13437 26859 13439 26859 13432 26860 13439 26860 14744 26860 13712 26861 14742 26861 13374 26861 13374 26862 14742 26862 13436 26862 13374 26863 13436 26863 13429 26863 13429 26864 13436 26864 13434 26864 13429 26865 13434 26865 13430 26865 14744 26866 13431 26866 13432 26866 13432 26867 13431 26867 14746 26867 13432 26868 14746 26868 13435 26868 13715 26869 13714 26869 13433 26869 13433 26870 13714 26870 13430 26870 13433 26871 13430 26871 14746 26871 14746 26872 13430 26872 13434 26872 14746 26873 13434 26873 13435 26873 13435 26874 13434 26874 13436 26874 13435 26875 13436 26875 13437 26875 13437 26876 13436 26876 14742 26876 13437 26877 14742 26877 13439 26877 13439 26878 14742 26878 13438 26878 13439 26879 13438 26879 14744 26879 13463 26880 13449 26880 13440 26880 13441 26881 14746 26881 13442 26881 13442 26882 14746 26882 13468 26882 13442 26883 13468 26883 13443 26883 13453 26884 13444 26884 13443 26884 13443 26885 13444 26885 13375 26885 13443 26886 13375 26886 13442 26886 13442 26887 13375 26887 13445 26887 13442 26888 13445 26888 13441 26888 13459 26889 13464 26889 13447 26889 13447 26890 13464 26890 13446 26890 13447 26891 13446 26891 13448 26891 13448 26892 13446 26892 13440 26892 13448 26893 13440 26893 14750 26893 14750 26894 13440 26894 13449 26894 14750 26895 13449 26895 14748 26895 14748 26896 13449 26896 13450 26896 13703 26897 13444 26897 13451 26897 13451 26898 13444 26898 13453 26898 13451 26899 13453 26899 13452 26899 13452 26900 13453 26900 13454 26900 13452 26901 13454 26901 13455 26901 13455 26902 13454 26902 13471 26902 13455 26903 13471 26903 13456 26903 13456 26904 13471 26904 13474 26904 13456 26905 13474 26905 13457 26905 13457 26906 13474 26906 13382 26906 13457 26907 13382 26907 13458 26907 13459 26908 13460 26908 13464 26908 13464 26909 13460 26909 13461 26909 13464 26910 13461 26910 13466 26910 13466 26911 13461 26911 14757 26911 13466 26912 14757 26912 13467 26912 13467 26913 14757 26913 13462 26913 13467 26914 13462 26914 14759 26914 13463 26915 13440 26915 13469 26915 13469 26916 13440 26916 13446 26916 13469 26917 13446 26917 13470 26917 13470 26918 13446 26918 13464 26918 13470 26919 13464 26919 13465 26919 13465 26920 13464 26920 13466 26920 13465 26921 13466 26921 13472 26921 13472 26922 13466 26922 13467 26922 13472 26923 13467 26923 13473 26923 13473 26924 13467 26924 13479 26924 13473 26925 13479 26925 13480 26925 13450 26926 13449 26926 14746 26926 14746 26927 13449 26927 13463 26927 14746 26928 13463 26928 13468 26928 13468 26929 13463 26929 13469 26929 13468 26930 13469 26930 13443 26930 13443 26931 13469 26931 13470 26931 13443 26932 13470 26932 13453 26932 13453 26933 13470 26933 13465 26933 13453 26934 13465 26934 13454 26934 13454 26935 13465 26935 13472 26935 13454 26936 13472 26936 13471 26936 13471 26937 13472 26937 13473 26937 13471 26938 13473 26938 13474 26938 13474 26939 13473 26939 13480 26939 13474 26940 13480 26940 13382 26940 13478 26941 14762 26941 13481 26941 13481 26942 14762 26942 13353 26942 13353 26943 13475 26943 13481 26943 13481 26944 13475 26944 13476 26944 13481 26945 13476 26945 13482 26945 13482 26946 13476 26946 13345 26946 13482 26947 13345 26947 13477 26947 13477 26948 13345 26948 13346 26948 13477 26949 13346 26949 13347 26949 14759 26950 13478 26950 13479 26950 13479 26951 13478 26951 13481 26951 13479 26952 13481 26952 13480 26952 13480 26953 13481 26953 13482 26953 13480 26954 13482 26954 13382 26954 13382 26955 13482 26955 13477 26955 13382 26956 13477 26956 13381 26956 13381 26957 13477 26957 13347 26957 13381 26958 13347 26958 13348 26958 13874 26959 13875 26959 13393 26959 13873 26960 13874 26960 13483 26960 13483 26961 13874 26961 13393 26961 13483 26962 13393 26962 13484 26962 13484 26963 13393 26963 13485 26963 13484 26964 13485 26964 13488 26964 13488 26965 13485 26965 13384 26965 13488 26966 13384 26966 13486 26966 13486 26967 13384 26967 13383 26967 13871 26968 13873 26968 13483 26968 13486 26969 13487 26969 13488 26969 13488 26970 13487 26970 13510 26970 13488 26971 13510 26971 13484 26971 13484 26972 13510 26972 13492 26972 13484 26973 13492 26973 13483 26973 13483 26974 13492 26974 13490 26974 13483 26975 13490 26975 13871 26975 13491 26976 13507 26976 14777 26976 14777 26977 13507 26977 13506 26977 13489 26978 13500 26978 13494 26978 13871 26979 13490 26979 13491 26979 13491 26980 13490 26980 13492 26980 13491 26981 13492 26981 13510 26981 13493 26982 14784 26982 13494 26982 13494 26983 14784 26983 14783 26983 13494 26984 14783 26984 13489 26984 13493 26985 13494 26985 13495 26985 13495 26986 13494 26986 13500 26986 13495 26987 13500 26987 15377 26987 14781 26988 14780 26988 14782 26988 14782 26989 14780 26989 13499 26989 14782 26990 13499 26990 13489 26990 13504 26991 13496 26991 13502 26991 13502 26992 13496 26992 13693 26992 13502 26993 13693 26993 13497 26993 13497 26994 13693 26994 13692 26994 13497 26995 13692 26995 13501 26995 13501 26996 13692 26996 13498 26996 13501 26997 13498 26997 15377 26997 14778 26998 14777 26998 14779 26998 14779 26999 14777 26999 13506 26999 14779 27000 13506 27000 14780 27000 14780 27001 13506 27001 13503 27001 14780 27002 13503 27002 13499 27002 15377 27003 13500 27003 13501 27003 13501 27004 13500 27004 13489 27004 13501 27005 13489 27005 13497 27005 13497 27006 13489 27006 13499 27006 13497 27007 13499 27007 13502 27007 13502 27008 13499 27008 13503 27008 13502 27009 13503 27009 13504 27009 13504 27010 13503 27010 13506 27010 13504 27011 13506 27011 13505 27011 13505 27012 13506 27012 13507 27012 13505 27013 13507 27013 13508 27013 13508 27014 13507 27014 13491 27014 13508 27015 13491 27015 13509 27015 13509 27016 13491 27016 13510 27016 13509 27017 13510 27017 13487 27017 13487 27018 13511 27018 13509 27018 13509 27019 13511 27019 13512 27019 13509 27020 13512 27020 13508 27020 13508 27021 13512 27021 13696 27021 13508 27022 13696 27022 13505 27022 13505 27023 13696 27023 13698 27023 13505 27024 13698 27024 13504 27024 13504 27025 13698 27025 13694 27025 13504 27026 13694 27026 13496 27026 13555 27027 12776 27027 13513 27027 13555 27028 13513 27028 13514 27028 13514 27029 13513 27029 13515 27029 13514 27030 13515 27030 13691 27030 13554 27031 13555 27031 13514 27031 13520 27032 13528 27032 13554 27032 13554 27033 13528 27033 13529 27033 13554 27034 13529 27034 13552 27034 13552 27035 13529 27035 13521 27035 13531 27036 13536 27036 13516 27036 13516 27037 13536 27037 13535 27037 13523 27038 13517 27038 13518 27038 13518 27039 13517 27039 13519 27039 13518 27040 13519 27040 13525 27040 13554 27041 13514 27041 13520 27041 13520 27042 13514 27042 13691 27042 13520 27043 13691 27043 13526 27043 13529 27044 13531 27044 13521 27044 13521 27045 13531 27045 13516 27045 13521 27046 13516 27046 13550 27046 13550 27047 13516 27047 13535 27047 13550 27048 13535 27048 13720 27048 13522 27049 13523 27049 13527 27049 13527 27050 13523 27050 13518 27050 13527 27051 13518 27051 13524 27051 13524 27052 13518 27052 13525 27052 13524 27053 13525 27053 13530 27053 13530 27054 13525 27054 13532 27054 13526 27055 13522 27055 13520 27055 13520 27056 13522 27056 13527 27056 13520 27057 13527 27057 13528 27057 13528 27058 13527 27058 13524 27058 13528 27059 13524 27059 13529 27059 13529 27060 13524 27060 13530 27060 13529 27061 13530 27061 13531 27061 13531 27062 13530 27062 13532 27062 13531 27063 13532 27063 13536 27063 13707 27064 13537 27064 13708 27064 13537 27065 13707 27065 13540 27065 13721 27066 13540 27066 13533 27066 13538 27067 13541 27067 13708 27067 13542 27068 13546 27068 13541 27068 13695 27069 13534 27069 13718 27069 13720 27070 13535 27070 13721 27070 13721 27071 13535 27071 13536 27071 13721 27072 13536 27072 13532 27072 13708 27073 13537 27073 13538 27073 13538 27074 13537 27074 13540 27074 13538 27075 13540 27075 13539 27075 13539 27076 13540 27076 13721 27076 13539 27077 13721 27077 13544 27077 13544 27078 13721 27078 13532 27078 13544 27079 13532 27079 13525 27079 13541 27080 13538 27080 13542 27080 13542 27081 13538 27081 13539 27081 13542 27082 13539 27082 13543 27082 13543 27083 13539 27083 13544 27083 13543 27084 13544 27084 13545 27084 13545 27085 13544 27085 13525 27085 13545 27086 13525 27086 13519 27086 13718 27087 13546 27087 13695 27087 13695 27088 13546 27088 13542 27088 13695 27089 13542 27089 13547 27089 13547 27090 13542 27090 13543 27090 13547 27091 13543 27091 13548 27091 13548 27092 13543 27092 13545 27092 13548 27093 13545 27093 13697 27093 13697 27094 13545 27094 13519 27094 13697 27095 13519 27095 13517 27095 13720 27096 13549 27096 13550 27096 13550 27097 13549 27097 13551 27097 13550 27098 13551 27098 13521 27098 13521 27099 13551 27099 13552 27099 13552 27100 13551 27100 13717 27100 13552 27101 13717 27101 13554 27101 13553 27102 12776 27102 13555 27102 13554 27103 13717 27103 13555 27103 13555 27104 13717 27104 13556 27104 13555 27105 13556 27105 13553 27105 15152 27106 13557 27106 13558 27106 13558 27107 13557 27107 15289 27107 13558 27108 15289 27108 13559 27108 13559 27109 15289 27109 15288 27109 13559 27110 15288 27110 15154 27110 15154 27111 15288 27111 15286 27111 15154 27112 15286 27112 15156 27112 15156 27113 15286 27113 15285 27113 15156 27114 15285 27114 13560 27114 13560 27115 15285 27115 13561 27115 13560 27116 13561 27116 13562 27116 13562 27117 13561 27117 15282 27117 13562 27118 15282 27118 13563 27118 13563 27119 15282 27119 15280 27119 13563 27120 15280 27120 15149 27120 15149 27121 15280 27121 13564 27121 15149 27122 13564 27122 13565 27122 13565 27123 13564 27123 13566 27123 13565 27124 13566 27124 13568 27124 13568 27125 13566 27125 13567 27125 13568 27126 13567 27126 13569 27126 13569 27127 13567 27127 13570 27127 13569 27128 13570 27128 15152 27128 15152 27129 13570 27129 13557 27129 15135 27130 15271 27130 13571 27130 13571 27131 15271 27131 15269 27131 13571 27132 15269 27132 15137 27132 15137 27133 15269 27133 15268 27133 15137 27134 15268 27134 15139 27134 15139 27135 15268 27135 13572 27135 15139 27136 13572 27136 13573 27136 13573 27137 13572 27137 15265 27137 13573 27138 15265 27138 15128 27138 15128 27139 15265 27139 13574 27139 15128 27140 13574 27140 13575 27140 13575 27141 13574 27141 13576 27141 13575 27142 13576 27142 15130 27142 15130 27143 13576 27143 15263 27143 15130 27144 15263 27144 15131 27144 15131 27145 15263 27145 15262 27145 15131 27146 15262 27146 13577 27146 13577 27147 15262 27147 15276 27147 13577 27148 15276 27148 13578 27148 13578 27149 15276 27149 15275 27149 13578 27150 15275 27150 13579 27150 13579 27151 15275 27151 15274 27151 13579 27152 15274 27152 15135 27152 15135 27153 15274 27153 15271 27153 15096 27154 13581 27154 13580 27154 13580 27155 13581 27155 15304 27155 13580 27156 15304 27156 15098 27156 15098 27157 15304 27157 13583 27157 15098 27158 13583 27158 13582 27158 13582 27159 13583 27159 13584 27159 13582 27160 13584 27160 13586 27160 13586 27161 13584 27161 13585 27161 13586 27162 13585 27162 13587 27162 13587 27163 13585 27163 13588 27163 13587 27164 13588 27164 13589 27164 13589 27165 13588 27165 15308 27165 13589 27166 15308 27166 13590 27166 13590 27167 15308 27167 13591 27167 13590 27168 13591 27168 15101 27168 15101 27169 13591 27169 15306 27169 15101 27170 15306 27170 13592 27170 13592 27171 15306 27171 13593 27171 13592 27172 13593 27172 15095 27172 15095 27173 13593 27173 13594 27173 15095 27174 13594 27174 13595 27174 13595 27175 13594 27175 13596 27175 13595 27176 13596 27176 15096 27176 15096 27177 13596 27177 13581 27177 15112 27178 15294 27178 15113 27178 15113 27179 15294 27179 15293 27179 15113 27180 15293 27180 15114 27180 15114 27181 15293 27181 13597 27181 15114 27182 13597 27182 13598 27182 13598 27183 13597 27183 15302 27183 13598 27184 15302 27184 13599 27184 13599 27185 15302 27185 15300 27185 13599 27186 15300 27186 13600 27186 13600 27187 15300 27187 15299 27187 13600 27188 15299 27188 13601 27188 13601 27189 15299 27189 13602 27189 13601 27190 13602 27190 15117 27190 15117 27191 13602 27191 13603 27191 15117 27192 13603 27192 15120 27192 15120 27193 13603 27193 15297 27193 15120 27194 15297 27194 15111 27194 15111 27195 15297 27195 15296 27195 15111 27196 15296 27196 13604 27196 13604 27197 15296 27197 13605 27197 13604 27198 13605 27198 13606 27198 13606 27199 13605 27199 13607 27199 13606 27200 13607 27200 15112 27200 15112 27201 13607 27201 15294 27201 13608 27202 13609 27202 13610 27202 13610 27203 13609 27203 13611 27203 13610 27204 13611 27204 15061 27204 15061 27205 13611 27205 13612 27205 15061 27206 13612 27206 15063 27206 15063 27207 13612 27207 13613 27207 15063 27208 13613 27208 13614 27208 13614 27209 13613 27209 15320 27209 13614 27210 15320 27210 15066 27210 15066 27211 15320 27211 15319 27211 15066 27212 15319 27212 13615 27212 13615 27213 15319 27213 13617 27213 13615 27214 13617 27214 13616 27214 13616 27215 13617 27215 15316 27215 13616 27216 15316 27216 15055 27216 15055 27217 15316 27217 13618 27217 15055 27218 13618 27218 15056 27218 15056 27219 13618 27219 15314 27219 15056 27220 15314 27220 15058 27220 15058 27221 15314 27221 15313 27221 15058 27222 15313 27222 13619 27222 13619 27223 15313 27223 15311 27223 13619 27224 15311 27224 13608 27224 13608 27225 15311 27225 13609 27225 15019 27226 15343 27226 15021 27226 15021 27227 15343 27227 15342 27227 15021 27228 15342 27228 15023 27228 15023 27229 15342 27229 15340 27229 15023 27230 15340 27230 15025 27230 15025 27231 15340 27231 15351 27231 15025 27232 15351 27232 13620 27232 13620 27233 15351 27233 15350 27233 13620 27234 15350 27234 13621 27234 13621 27235 15350 27235 15348 27235 13621 27236 15348 27236 15028 27236 15028 27237 15348 27237 13622 27237 15028 27238 13622 27238 13623 27238 13623 27239 13622 27239 15346 27239 13623 27240 15346 27240 15031 27240 15031 27241 15346 27241 15345 27241 15031 27242 15345 27242 13624 27242 13624 27243 15345 27243 13625 27243 13624 27244 13625 27244 13626 27244 13626 27245 13625 27245 13627 27245 13626 27246 13627 27246 13628 27246 13628 27247 13627 27247 13629 27247 13628 27248 13629 27248 15019 27248 15019 27249 13629 27249 15343 27249 13642 27250 15365 27250 13630 27250 13630 27251 15365 27251 13631 27251 13630 27252 13631 27252 13632 27252 13632 27253 13631 27253 15364 27253 13632 27254 15364 27254 15045 27254 15045 27255 15364 27255 15362 27255 15045 27256 15362 27256 15047 27256 15047 27257 15362 27257 15360 27257 15047 27258 15360 27258 13633 27258 13633 27259 15360 27259 15357 27259 13633 27260 15357 27260 13634 27260 13634 27261 15357 27261 15355 27261 13634 27262 15355 27262 13635 27262 13635 27263 15355 27263 15354 27263 13635 27264 15354 27264 13636 27264 13636 27265 15354 27265 13638 27265 13636 27266 13638 27266 13637 27266 13637 27267 13638 27267 15353 27267 13637 27268 15353 27268 13639 27268 13639 27269 15353 27269 13640 27269 13639 27270 13640 27270 13641 27270 13641 27271 13640 27271 15366 27271 13641 27272 15366 27272 13642 27272 13642 27273 15366 27273 15365 27273 15171 27274 13657 27274 13643 27274 13643 27275 13657 27275 13644 27275 13643 27276 13644 27276 13645 27276 13645 27277 13644 27277 13646 27277 13645 27278 13646 27278 15173 27278 15173 27279 13646 27279 14905 27279 15173 27280 14905 27280 15174 27280 15174 27281 14905 27281 13647 27281 15174 27282 13647 27282 13648 27282 13648 27283 13647 27283 13649 27283 13648 27284 13649 27284 15176 27284 15176 27285 13649 27285 13650 27285 15176 27286 13650 27286 15178 27286 15178 27287 13650 27287 13651 27287 15178 27288 13651 27288 15179 27288 15179 27289 13651 27289 13652 27289 15179 27290 13652 27290 13653 27290 13653 27291 13652 27291 13655 27291 13653 27292 13655 27292 13654 27292 13654 27293 13655 27293 14898 27293 13654 27294 14898 27294 13656 27294 13656 27295 14898 27295 14900 27295 13656 27296 14900 27296 15171 27296 15171 27297 14900 27297 13657 27297 13672 27298 13659 27298 13658 27298 13658 27299 13659 27299 13660 27299 13658 27300 13660 27300 13661 27300 13661 27301 13660 27301 14891 27301 13661 27302 14891 27302 13662 27302 13662 27303 14891 27303 13663 27303 13662 27304 13663 27304 15187 27304 15187 27305 13663 27305 14893 27305 15187 27306 14893 27306 13664 27306 13664 27307 14893 27307 14896 27307 13664 27308 14896 27308 15188 27308 15188 27309 14896 27309 13666 27309 15188 27310 13666 27310 13665 27310 13665 27311 13666 27311 14897 27311 13665 27312 14897 27312 15181 27312 15181 27313 14897 27313 13667 27313 15181 27314 13667 27314 15183 27314 15183 27315 13667 27315 13669 27315 15183 27316 13669 27316 13668 27316 13668 27317 13669 27317 13671 27317 13668 27318 13671 27318 13670 27318 13670 27319 13671 27319 14889 27319 13670 27320 14889 27320 13672 27320 13672 27321 14889 27321 13659 27321 15198 27322 14879 27322 13673 27322 13673 27323 14879 27323 14881 27323 13673 27324 14881 27324 13674 27324 13674 27325 14881 27325 13675 27325 13674 27326 13675 27326 13676 27326 13676 27327 13675 27327 13677 27327 13676 27328 13677 27328 13678 27328 13678 27329 13677 27329 13679 27329 13678 27330 13679 27330 15201 27330 15201 27331 13679 27331 14883 27331 15201 27332 14883 27332 13680 27332 13680 27333 14883 27333 14884 27333 13680 27334 14884 27334 13681 27334 13681 27335 14884 27335 14886 27335 13681 27336 14886 27336 15192 27336 15192 27337 14886 27337 13682 27337 15192 27338 13682 27338 13684 27338 13684 27339 13682 27339 13683 27339 13684 27340 13683 27340 15194 27340 15194 27341 13683 27341 14876 27341 15194 27342 14876 27342 15196 27342 15196 27343 14876 27343 13685 27343 15196 27344 13685 27344 15198 27344 15198 27345 13685 27345 14879 27345 15214 27346 13690 27346 15215 27346 15215 27347 13690 27347 13686 27347 15215 27348 13686 27348 15216 27348 15216 27349 13686 27349 14869 27349 15216 27350 14869 27350 15219 27350 15219 27351 14869 27351 14871 27351 15219 27352 14871 27352 15220 27352 15220 27353 14871 27353 14872 27353 15220 27354 14872 27354 15205 27354 15205 27355 14872 27355 14858 27355 15205 27356 14858 27356 15206 27356 15206 27357 14858 27357 14860 27357 15206 27358 14860 27358 15208 27358 15208 27359 14860 27359 14861 27359 15208 27360 14861 27360 13687 27360 13687 27361 14861 27361 14863 27361 13687 27362 14863 27362 15211 27362 15211 27363 14863 27363 14865 27363 15211 27364 14865 27364 15213 27364 15213 27365 14865 27365 14866 27365 15213 27366 14866 27366 13688 27366 13688 27367 14866 27367 13689 27367 13688 27368 13689 27368 15214 27368 15214 27369 13689 27369 13690 27369 13691 27370 13498 27370 13526 27370 13526 27371 13498 27371 13692 27371 13526 27372 13692 27372 13522 27372 13522 27373 13692 27373 13693 27373 13522 27374 13693 27374 13523 27374 13697 27375 13517 27375 13694 27375 13523 27376 13693 27376 13517 27376 13517 27377 13693 27377 13496 27377 13517 27378 13496 27378 13694 27378 13486 27379 13534 27379 13487 27379 13487 27380 13534 27380 13695 27380 13487 27381 13695 27381 13511 27381 13511 27382 13695 27382 13547 27382 13511 27383 13547 27383 13512 27383 13512 27384 13547 27384 13548 27384 13512 27385 13548 27385 13696 27385 13696 27386 13548 27386 13697 27386 13696 27387 13697 27387 13698 27387 13698 27388 13697 27388 13694 27388 15378 27389 13498 27389 13515 27389 13515 27390 13498 27390 13691 27390 13349 27391 13344 27391 15443 27391 13369 27392 13367 27392 13428 27392 13428 27393 13367 27393 13366 27393 13556 27394 13699 27394 15443 27394 15443 27395 13699 27395 13700 27395 15443 27396 13700 27396 13349 27396 13357 27397 13364 27397 13534 27397 13534 27398 13364 27398 13371 27398 13534 27399 13371 27399 13370 27399 13366 27400 13365 27400 13428 27400 13428 27401 13365 27401 13372 27401 13428 27402 13372 27402 13405 27402 13405 27403 13422 27403 13428 27403 13428 27404 13422 27404 13701 27404 13428 27405 13701 27405 13426 27405 13426 27406 13701 27406 13425 27406 13370 27407 13369 27407 13534 27407 13534 27408 13369 27408 13428 27408 13534 27409 13428 27409 13702 27409 13702 27410 13428 27410 15169 27410 13458 27411 13382 27411 15160 27411 13377 27412 15164 27412 13703 27412 13703 27413 15164 27413 13705 27413 13703 27414 13705 27414 13376 27414 13376 27415 13705 27415 13445 27415 13712 27416 15165 27416 13428 27416 13428 27417 15165 27417 13704 27417 13428 27418 13704 27418 15169 27418 13486 27419 13383 27419 13534 27419 13534 27420 13383 27420 13709 27420 13445 27421 13705 27421 13441 27421 13441 27422 13705 27422 13706 27422 13441 27423 13706 27423 13716 27423 13549 27424 13707 27424 13719 27424 13719 27425 13707 27425 13708 27425 13719 27426 13708 27426 13541 27426 13709 27427 13710 27427 13534 27427 13534 27428 13710 27428 13711 27428 13534 27429 13711 27429 13357 27429 13712 27430 13713 27430 15165 27430 15165 27431 13713 27431 13714 27431 15165 27432 13714 27432 13706 27432 13706 27433 13714 27433 13715 27433 13706 27434 13715 27434 13716 27434 13377 27435 13380 27435 15164 27435 15164 27436 13380 27436 13379 27436 15164 27437 13379 27437 15162 27437 15162 27438 13379 27438 13378 27438 15162 27439 13378 27439 15160 27439 15160 27440 13378 27440 13457 27440 15160 27441 13457 27441 13458 27441 13551 27442 13549 27442 13717 27442 13717 27443 13549 27443 13719 27443 13717 27444 13719 27444 13556 27444 13556 27445 13719 27445 15160 27445 13556 27446 15160 27446 13699 27446 13699 27447 15160 27447 13382 27447 13702 27448 15157 27448 13534 27448 13534 27449 15157 27449 15159 27449 13534 27450 15159 27450 13718 27450 13718 27451 15159 27451 13719 27451 13718 27452 13719 27452 13546 27452 13546 27453 13719 27453 13541 27453 13549 27454 13720 27454 13721 27454 13721 27455 13533 27455 13549 27455 13549 27456 13533 27456 13540 27456 13549 27457 13540 27457 13707 27457 13742 27458 13722 27458 13740 27458 13723 27459 13724 27459 13740 27459 13740 27460 13724 27460 13013 27460 13728 27461 13725 27461 13013 27461 13013 27462 13725 27462 15202 27462 13013 27463 15202 27463 13740 27463 13740 27464 15202 27464 15190 27464 13740 27465 15190 27465 15191 27465 13737 27466 13726 27466 15191 27466 15191 27467 13726 27467 13727 27467 15191 27468 13727 27468 12956 27468 13728 27469 13729 27469 13725 27469 13725 27470 13729 27470 13730 27470 13725 27471 13730 27471 13731 27471 13731 27472 13730 27472 13743 27472 13731 27473 13743 27473 15200 27473 15200 27474 13743 27474 13733 27474 15200 27475 13733 27475 13732 27475 13732 27476 13733 27476 13756 27476 13732 27477 13756 27477 15199 27477 15199 27478 13756 27478 13734 27478 15199 27479 13734 27479 15197 27479 15197 27480 13734 27480 13735 27480 15197 27481 13735 27481 15195 27481 15195 27482 13735 27482 13736 27482 15195 27483 13736 27483 15193 27483 15193 27484 13736 27484 13750 27484 15193 27485 13750 27485 13737 27485 13737 27486 13750 27486 13738 27486 13737 27487 13738 27487 13726 27487 12956 27488 12954 27488 15191 27488 15191 27489 12954 27489 13739 27489 15191 27490 13739 27490 13740 27490 13740 27491 13739 27491 13741 27491 13740 27492 13741 27492 13742 27492 13730 27493 13744 27493 13743 27493 13743 27494 13744 27494 13745 27494 13743 27495 13745 27495 12984 27495 13746 27496 13726 27496 13738 27496 13746 27497 13738 27497 13748 27497 12964 27498 12963 27498 13738 27498 13738 27499 12963 27499 13747 27499 13738 27500 13747 27500 13748 27500 12964 27501 13738 27501 13749 27501 13749 27502 13738 27502 13750 27502 13749 27503 13750 27503 12988 27503 12988 27504 13750 27504 13751 27504 13751 27505 13750 27505 13752 27505 13752 27506 13750 27506 13736 27506 13752 27507 13736 27507 13753 27507 13753 27508 13736 27508 13754 27508 13754 27509 13736 27509 13735 27509 13754 27510 13735 27510 12991 27510 12978 27511 12977 27511 13734 27511 13734 27512 12977 27512 13755 27512 13734 27513 13755 27513 13735 27513 13735 27514 13755 27514 12992 27514 13735 27515 12992 27515 12991 27515 12978 27516 13734 27516 12979 27516 12979 27517 13734 27517 13756 27517 12979 27518 13756 27518 12980 27518 12980 27519 13756 27519 12981 27519 12981 27520 13756 27520 13733 27520 12981 27521 13733 27521 12983 27521 12983 27522 13733 27522 13743 27522 12983 27523 13743 27523 12984 27523 13761 27524 14383 27524 13757 27524 13758 27525 13760 27525 13761 27525 13759 27526 14848 27526 15217 27526 15217 27527 14848 27527 13768 27527 15217 27528 13768 27528 13760 27528 13758 27529 13761 27529 15212 27529 15212 27530 13761 27530 13757 27530 15212 27531 13757 27531 13762 27531 13762 27532 13757 27532 13763 27532 13762 27533 13763 27533 13146 27533 13084 27534 13086 27534 13761 27534 13761 27535 13086 27535 13770 27535 13146 27536 13144 27536 13762 27536 13762 27537 13144 27537 13764 27537 13762 27538 13764 27538 15210 27538 15210 27539 13764 27539 13765 27539 15210 27540 13765 27540 15209 27540 15209 27541 13765 27541 13772 27541 15209 27542 13772 27542 15207 27542 15207 27543 13772 27543 14856 27543 15207 27544 14856 27544 15204 27544 15204 27545 14856 27545 13766 27545 15204 27546 13766 27546 15203 27546 15203 27547 13766 27547 14855 27547 15203 27548 14855 27548 15218 27548 15218 27549 14855 27549 14853 27549 15218 27550 14853 27550 13759 27550 13759 27551 14853 27551 13767 27551 13759 27552 13767 27552 14848 27552 13760 27553 13768 27553 13761 27553 13761 27554 13768 27554 13769 27554 13761 27555 13769 27555 13084 27555 13770 27556 13087 27556 13761 27556 13761 27557 13087 27557 13088 27557 13761 27558 13088 27558 14382 27558 14857 27559 13772 27559 13771 27559 13771 27560 13772 27560 13765 27560 14847 27561 13091 27561 13768 27561 13768 27562 13091 27562 13773 27562 13768 27563 13773 27563 13769 27563 13024 27564 13025 27564 13792 27564 13788 27565 14833 27565 15175 27565 15175 27566 14833 27566 13774 27566 15175 27567 13774 27567 15172 27567 15172 27568 13774 27568 14832 27568 15172 27569 14832 27569 13775 27569 13775 27570 14832 27570 13776 27570 13775 27571 13776 27571 13777 27571 13777 27572 13776 27572 13778 27572 13777 27573 13778 27573 13779 27573 13794 27574 13789 27574 13793 27574 13025 27575 13780 27575 13792 27575 13792 27576 13780 27576 13781 27576 13792 27577 13781 27577 14155 27577 13783 27578 13081 27578 13782 27578 13782 27579 13784 27579 13783 27579 13783 27580 13784 27580 13799 27580 13783 27581 13799 27581 15170 27581 15170 27582 13799 27582 13798 27582 15170 27583 13798 27583 13785 27583 13785 27584 13798 27584 13786 27584 13785 27585 13786 27585 13787 27585 13787 27586 13786 27586 14838 27586 13787 27587 14838 27587 15177 27587 15177 27588 14838 27588 14839 27588 15177 27589 14839 27589 13788 27589 13788 27590 14839 27590 14836 27590 13788 27591 14836 27591 14833 27591 13794 27592 13080 27592 13789 27592 13789 27593 13080 27593 13790 27593 13789 27594 13790 27594 13783 27594 13783 27595 13790 27595 13791 27595 13783 27596 13791 27596 13081 27596 13779 27597 13024 27597 13777 27597 13777 27598 13024 27598 13792 27598 13777 27599 13792 27599 13793 27599 13793 27600 13792 27600 13795 27600 13793 27601 13795 27601 13794 27601 13794 27602 13795 27602 13078 27602 13796 27603 13798 27603 13797 27603 13797 27604 13798 27604 13799 27604 13776 27605 14832 27605 13022 27605 13022 27606 14832 27606 13800 27606 12892 27607 14208 27607 13806 27607 13805 27608 12888 27608 13808 27608 13812 27609 13834 27609 15186 27609 15186 27610 13834 27610 13830 27610 15186 27611 13830 27611 13801 27611 13801 27612 13830 27612 13824 27612 13801 27613 13824 27613 13802 27613 13802 27614 13824 27614 13803 27614 13802 27615 13803 27615 15185 27615 15185 27616 13803 27616 13821 27616 15185 27617 13821 27617 13804 27617 13804 27618 13821 27618 13820 27618 13804 27619 13820 27619 15184 27619 15184 27620 13820 27620 13818 27620 15184 27621 13818 27621 13805 27621 13805 27622 13818 27622 12889 27622 13805 27623 12889 27623 12888 27623 15180 27624 15182 27624 13806 27624 13806 27625 15182 27625 13805 27625 13806 27626 13807 27626 12946 27626 13808 27627 13809 27627 13805 27627 13805 27628 13809 27628 13810 27628 13805 27629 13810 27629 13806 27629 13806 27630 13810 27630 13811 27630 13806 27631 13811 27631 12892 27631 12949 27632 12950 27632 13813 27632 13813 27633 12950 27633 12951 27633 13813 27634 12951 27634 15189 27634 15189 27635 12951 27635 13817 27635 15189 27636 13817 27636 13812 27636 13812 27637 13817 27637 13815 27637 13812 27638 13815 27638 13834 27638 13806 27639 12946 27639 15180 27639 15180 27640 12946 27640 12947 27640 15180 27641 12947 27641 13813 27641 13813 27642 12947 27642 13814 27642 13813 27643 13814 27643 12949 27643 13833 27644 13815 27644 13816 27644 13816 27645 13815 27645 13817 27645 12889 27646 13818 27646 13819 27646 13819 27647 13818 27647 12919 27647 12919 27648 13818 27648 12918 27648 12918 27649 13818 27649 13820 27649 12918 27650 13820 27650 12915 27650 12915 27651 13820 27651 13821 27651 12915 27652 13821 27652 12923 27652 12923 27653 13821 27653 13822 27653 13822 27654 13821 27654 12924 27654 12924 27655 13821 27655 13803 27655 12924 27656 13803 27656 13823 27656 13824 27657 13832 27657 13825 27657 13825 27658 13826 27658 13824 27658 13824 27659 13826 27659 13827 27659 13824 27660 13827 27660 13803 27660 13803 27661 13827 27661 13828 27661 13803 27662 13828 27662 13823 27662 13829 27663 12905 27663 13830 27663 13830 27664 12905 27664 12906 27664 13830 27665 12906 27665 13824 27665 13824 27666 12906 27666 13831 27666 13824 27667 13831 27667 13832 27667 13834 27668 13815 27668 13833 27668 13833 27669 13835 27669 13834 27669 13834 27670 13835 27670 12907 27670 13834 27671 12907 27671 13830 27671 13830 27672 12907 27672 13836 27672 13830 27673 13836 27673 13829 27673 13847 27674 14822 27674 13837 27674 13837 27675 14822 27675 14820 27675 13837 27676 14820 27676 15425 27676 15425 27677 14820 27677 14817 27677 15425 27678 14817 27678 15426 27678 15426 27679 14817 27679 13838 27679 15426 27680 13838 27680 15427 27680 15427 27681 13838 27681 14812 27681 15427 27682 14812 27682 13839 27682 13839 27683 14812 27683 14809 27683 13839 27684 14809 27684 15429 27684 15429 27685 14809 27685 14805 27685 15429 27686 14805 27686 13840 27686 13840 27687 14805 27687 13841 27687 13840 27688 13841 27688 15431 27688 15431 27689 13841 27689 14807 27689 15431 27690 14807 27690 13842 27690 13842 27691 14807 27691 13843 27691 13842 27692 13843 27692 13844 27692 13844 27693 13843 27693 13845 27693 13844 27694 13845 27694 13846 27694 13846 27695 13845 27695 14825 27695 13846 27696 14825 27696 13847 27696 13847 27697 14825 27697 14822 27697 13991 27698 14037 27698 14035 27698 13865 27699 14094 27699 13867 27699 13867 27700 13864 27700 13869 27700 14064 27701 14095 27701 13848 27701 13849 27702 13354 27702 13850 27702 13851 27703 13849 27703 13852 27703 12843 27704 13851 27704 14503 27704 14503 27705 13851 27705 13852 27705 14503 27706 13852 27706 14502 27706 13849 27707 13850 27707 13852 27707 13852 27708 13850 27708 13853 27708 13852 27709 13853 27709 14098 27709 14098 27710 13853 27710 13950 27710 14098 27711 13950 27711 14097 27711 14064 27712 13848 27712 14065 27712 14065 27713 13848 27713 13854 27713 14065 27714 13854 27714 13855 27714 13855 27715 13854 27715 13856 27715 13855 27716 13856 27716 14047 27716 14047 27717 13856 27717 13933 27717 14047 27718 13933 27718 14059 27718 14059 27719 13933 27719 13857 27719 13857 27720 13933 27720 13932 27720 13857 27721 13932 27721 13858 27721 13858 27722 13932 27722 13931 27722 13858 27723 13931 27723 13859 27723 13859 27724 13931 27724 13930 27724 13859 27725 13930 27725 13928 27725 14001 27726 14002 27726 14034 27726 14034 27727 14002 27727 14062 27727 14034 27728 14062 27728 14032 27728 14032 27729 14062 27729 14031 27729 13868 27730 14054 27730 13860 27730 13860 27731 14054 27731 14050 27731 13860 27732 14050 27732 14000 27732 14000 27733 14050 27733 13861 27733 14000 27734 13861 27734 13862 27734 13862 27735 13861 27735 14049 27735 13862 27736 14049 27736 13863 27736 13864 27737 13867 27737 14048 27737 14048 27738 13867 27738 14094 27738 14048 27739 14094 27739 14067 27739 14093 27740 13865 27740 13866 27740 13866 27741 13865 27741 13867 27741 13866 27742 13867 27742 13868 27742 13868 27743 13867 27743 13869 27743 13868 27744 13869 27744 14054 27744 14790 27745 13870 27745 14776 27745 14776 27746 13870 27746 13872 27746 14776 27747 13872 27747 13871 27747 13871 27748 13872 27748 13873 27748 13873 27749 13872 27749 13958 27749 13873 27750 13958 27750 13874 27750 13874 27751 13958 27751 13875 27751 13875 27752 13958 27752 13876 27752 13875 27753 13876 27753 14724 27753 13877 27754 13878 27754 14727 27754 14727 27755 13879 27755 13877 27755 13877 27756 13879 27756 14725 27756 13877 27757 14725 27757 13876 27757 13876 27758 14725 27758 13880 27758 13876 27759 13880 27759 14724 27759 13883 27760 14731 27760 13881 27760 13881 27761 14731 27761 14729 27761 13881 27762 14729 27762 13878 27762 13878 27763 14729 27763 14728 27763 13878 27764 14728 27764 14727 27764 13881 27765 13882 27765 13883 27765 13883 27766 13882 27766 13989 27766 13883 27767 13989 27767 14733 27767 14733 27768 13989 27768 13884 27768 14733 27769 13884 27769 14735 27769 14735 27770 13884 27770 13987 27770 14735 27771 13987 27771 13885 27771 13885 27772 13987 27772 13887 27772 13885 27773 13887 27773 13886 27773 13886 27774 13887 27774 13985 27774 13886 27775 13985 27775 14736 27775 14736 27776 13985 27776 13888 27776 14736 27777 13888 27777 14739 27777 14739 27778 13888 27778 13889 27778 14739 27779 13889 27779 14740 27779 14740 27780 13889 27780 13890 27780 14740 27781 13890 27781 14741 27781 14741 27782 13890 27782 13981 27782 14741 27783 13981 27783 14743 27783 14743 27784 13981 27784 13980 27784 14743 27785 13980 27785 13891 27785 13891 27786 13980 27786 13892 27786 13891 27787 13892 27787 13979 27787 13976 27788 14745 27788 13978 27788 13978 27789 14745 27789 13893 27789 13978 27790 13893 27790 13979 27790 13979 27791 13893 27791 13894 27791 13979 27792 13894 27792 13891 27792 13972 27793 14747 27793 13975 27793 13975 27794 14747 27794 13895 27794 13975 27795 13895 27795 13976 27795 13976 27796 13895 27796 13896 27796 13976 27797 13896 27797 14745 27797 13900 27798 14751 27798 13897 27798 13897 27799 14751 27799 14749 27799 13897 27800 14749 27800 13972 27800 13972 27801 14749 27801 13898 27801 13972 27802 13898 27802 14747 27802 13967 27803 14753 27803 13968 27803 13968 27804 14753 27804 13899 27804 13968 27805 13899 27805 13900 27805 13900 27806 13899 27806 14752 27806 13900 27807 14752 27807 14751 27807 13902 27808 13901 27808 14754 27808 13901 27809 13902 27809 14755 27809 14755 27810 13902 27810 13903 27810 14755 27811 13903 27811 14756 27811 14756 27812 13903 27812 14758 27812 14758 27813 13903 27813 13904 27813 14758 27814 13904 27814 13905 27814 13904 27815 13946 27815 13905 27815 13905 27816 13946 27816 13906 27816 13905 27817 13906 27817 14760 27817 13906 27818 13907 27818 14760 27818 14760 27819 13907 27819 13908 27819 14760 27820 13908 27820 13909 27820 13909 27821 13908 27821 14761 27821 14017 27822 14018 27822 13926 27822 13926 27823 14018 27823 14057 27823 14057 27824 14018 27824 14020 27824 14057 27825 14020 27825 14058 27825 14058 27826 14020 27826 13910 27826 14058 27827 13910 27827 13911 27827 13911 27828 13910 27828 13912 27828 13911 27829 13912 27829 14053 27829 14053 27830 13912 27830 13914 27830 13914 27831 13912 27831 13913 27831 13914 27832 13913 27832 13915 27832 13915 27833 13913 27833 13916 27833 13915 27834 13916 27834 13918 27834 13918 27835 13916 27835 13917 27835 13918 27836 13917 27836 13919 27836 13919 27837 13917 27837 13920 27837 13919 27838 13920 27838 13921 27838 13921 27839 13920 27839 13922 27839 13921 27840 13922 27840 14044 27840 14044 27841 13922 27841 14023 27841 14044 27842 14023 27842 13924 27842 13924 27843 14023 27843 13923 27843 13924 27844 13923 27844 13925 27844 13925 27845 13923 27845 14026 27845 13925 27846 14026 27846 14004 27846 13926 27847 13927 27847 14017 27847 14017 27848 13927 27848 13928 27848 14017 27849 13928 27849 14015 27849 14015 27850 13928 27850 13930 27850 14015 27851 13930 27851 13929 27851 13929 27852 13930 27852 13931 27852 13929 27853 13931 27853 14013 27853 14013 27854 13931 27854 13932 27854 14013 27855 13932 27855 14012 27855 14012 27856 13932 27856 13933 27856 14012 27857 13933 27857 13934 27857 13934 27858 13933 27858 13856 27858 13934 27859 13856 27859 13935 27859 13935 27860 13856 27860 13854 27860 13935 27861 13854 27861 14011 27861 14011 27862 13854 27862 13848 27862 14011 27863 13848 27863 13936 27863 13937 27864 13949 27864 13938 27864 13938 27865 13949 27865 13944 27865 13938 27866 13944 27866 13939 27866 13939 27867 13944 27867 13945 27867 13939 27868 13945 27868 13964 27868 13964 27869 13945 27869 13947 27869 13964 27870 13947 27870 13940 27870 13940 27871 13947 27871 13942 27871 13940 27872 13942 27872 13941 27872 13941 27873 13942 27873 13948 27873 13941 27874 13948 27874 13967 27874 13943 27875 14097 27875 13960 27875 13960 27876 14097 27876 13950 27876 13960 27877 13950 27877 13937 27877 13949 27878 13907 27878 13944 27878 13944 27879 13907 27879 13906 27879 13944 27880 13906 27880 13945 27880 13945 27881 13906 27881 13946 27881 13945 27882 13946 27882 13947 27882 13947 27883 13946 27883 13904 27883 13947 27884 13904 27884 13942 27884 13942 27885 13904 27885 13903 27885 13942 27886 13903 27886 13948 27886 13948 27887 13903 27887 13902 27887 13948 27888 13902 27888 13967 27888 13967 27889 13902 27889 14754 27889 13967 27890 14754 27890 14753 27890 13937 27891 13950 27891 13949 27891 13949 27892 13950 27892 13853 27892 13949 27893 13853 27893 13907 27893 13907 27894 13853 27894 13850 27894 13907 27895 13850 27895 13908 27895 13908 27896 13850 27896 13354 27896 13908 27897 13354 27897 14761 27897 14037 27898 13991 27898 13952 27898 13952 27899 13991 27899 13951 27899 13952 27900 13951 27900 13953 27900 13953 27901 13951 27901 13954 27901 13953 27902 13954 27902 13955 27902 13955 27903 13954 27903 13956 27903 13955 27904 13956 27904 14041 27904 14041 27905 13956 27905 13996 27905 14041 27906 13996 27906 14042 27906 13870 27907 13957 27907 13872 27907 13872 27908 13957 27908 13997 27908 13872 27909 13997 27909 13958 27909 13958 27910 13997 27910 13995 27910 13958 27911 13995 27911 13876 27911 13876 27912 13995 27912 13994 27912 13876 27913 13994 27913 13877 27913 13877 27914 13994 27914 13993 27914 13877 27915 13993 27915 13878 27915 13878 27916 13993 27916 13992 27916 13878 27917 13992 27917 13881 27917 14010 27918 13943 27918 13959 27918 13959 27919 13943 27919 13960 27919 13959 27920 13960 27920 13961 27920 13961 27921 13960 27921 13937 27921 13961 27922 13937 27922 13962 27922 13962 27923 13937 27923 13938 27923 13962 27924 13938 27924 13963 27924 13963 27925 13938 27925 13939 27925 13963 27926 13939 27926 14014 27926 14014 27927 13939 27927 13964 27927 14014 27928 13964 27928 13965 27928 13965 27929 13964 27929 13940 27929 13965 27930 13940 27930 14016 27930 14016 27931 13940 27931 13941 27931 14016 27932 13941 27932 13966 27932 13966 27933 13941 27933 13967 27933 13966 27934 13967 27934 14019 27934 14019 27935 13967 27935 13968 27935 14019 27936 13968 27936 13969 27936 13969 27937 13968 27937 13900 27937 13969 27938 13900 27938 13970 27938 13970 27939 13900 27939 13897 27939 13970 27940 13897 27940 13971 27940 13971 27941 13897 27941 13972 27941 13971 27942 13972 27942 13973 27942 13973 27943 13972 27943 13975 27943 13973 27944 13975 27944 13974 27944 13974 27945 13975 27945 13976 27945 13974 27946 13976 27946 13977 27946 13977 27947 13976 27947 13978 27947 13977 27948 13978 27948 14021 27948 14021 27949 13978 27949 13979 27949 14021 27950 13979 27950 14022 27950 14022 27951 13979 27951 13892 27951 14022 27952 13892 27952 14024 27952 14024 27953 13892 27953 13980 27953 14024 27954 13980 27954 14025 27954 14025 27955 13980 27955 13981 27955 14025 27956 13981 27956 13982 27956 13982 27957 13981 27957 13890 27957 13982 27958 13890 27958 14028 27958 14028 27959 13890 27959 13889 27959 14028 27960 13889 27960 13983 27960 13983 27961 13889 27961 13888 27961 13983 27962 13888 27962 14029 27962 14029 27963 13888 27963 13985 27963 14029 27964 13985 27964 13984 27964 13984 27965 13985 27965 13887 27965 13984 27966 13887 27966 13986 27966 13986 27967 13887 27967 13987 27967 13986 27968 13987 27968 13988 27968 13988 27969 13987 27969 13884 27969 13988 27970 13884 27970 14033 27970 14033 27971 13884 27971 13989 27971 14033 27972 13989 27972 13990 27972 13990 27973 13989 27973 13882 27973 13990 27974 13882 27974 14035 27974 14035 27975 13882 27975 13881 27975 14035 27976 13881 27976 13991 27976 13991 27977 13881 27977 13992 27977 13991 27978 13992 27978 13951 27978 13951 27979 13992 27979 13993 27979 13951 27980 13993 27980 13954 27980 13954 27981 13993 27981 13994 27981 13954 27982 13994 27982 13956 27982 13956 27983 13994 27983 13995 27983 13956 27984 13995 27984 13996 27984 13996 27985 13995 27985 13997 27985 13996 27986 13997 27986 14042 27986 14042 27987 13997 27987 13957 27987 14040 27988 14093 27988 14039 27988 14039 27989 14093 27989 13866 27989 14039 27990 13866 27990 13998 27990 13998 27991 13866 27991 13868 27991 13998 27992 13868 27992 13999 27992 13999 27993 13868 27993 13860 27993 13999 27994 13860 27994 14038 27994 14038 27995 13860 27995 14000 27995 14038 27996 14000 27996 14036 27996 14036 27997 14000 27997 13862 27997 14036 27998 13862 27998 14001 27998 14001 27999 13862 27999 13863 27999 14001 28000 13863 28000 14002 28000 14026 28001 14003 28001 14004 28001 14004 28002 14003 28002 14027 28002 14004 28003 14027 28003 14043 28003 14043 28004 14027 28004 14005 28004 14043 28005 14005 28005 14006 28005 14006 28006 14005 28006 14007 28006 14006 28007 14007 28007 14008 28007 14008 28008 14007 28008 14030 28008 14008 28009 14030 28009 14060 28009 14060 28010 14030 28010 14031 28010 14060 28011 14031 28011 14009 28011 14009 28012 14031 28012 14062 28012 13936 28013 14010 28013 14011 28013 14011 28014 14010 28014 13959 28014 14011 28015 13959 28015 13935 28015 13935 28016 13959 28016 13961 28016 13935 28017 13961 28017 13934 28017 13934 28018 13961 28018 13962 28018 13934 28019 13962 28019 14012 28019 14012 28020 13962 28020 13963 28020 14012 28021 13963 28021 14013 28021 14013 28022 13963 28022 14014 28022 14013 28023 14014 28023 13929 28023 13929 28024 14014 28024 13965 28024 13929 28025 13965 28025 14015 28025 14015 28026 13965 28026 14016 28026 14015 28027 14016 28027 14017 28027 14017 28028 14016 28028 13966 28028 14017 28029 13966 28029 14018 28029 14018 28030 13966 28030 14019 28030 14018 28031 14019 28031 14020 28031 14020 28032 14019 28032 13969 28032 14020 28033 13969 28033 13910 28033 13910 28034 13969 28034 13970 28034 13910 28035 13970 28035 13912 28035 13912 28036 13970 28036 13971 28036 13912 28037 13971 28037 13913 28037 13913 28038 13971 28038 13973 28038 13913 28039 13973 28039 13916 28039 13916 28040 13973 28040 13974 28040 13916 28041 13974 28041 13917 28041 13917 28042 13974 28042 13977 28042 13917 28043 13977 28043 13920 28043 13920 28044 13977 28044 14021 28044 13920 28045 14021 28045 13922 28045 13922 28046 14021 28046 14022 28046 13922 28047 14022 28047 14023 28047 14023 28048 14022 28048 14024 28048 14023 28049 14024 28049 13923 28049 13923 28050 14024 28050 14025 28050 13923 28051 14025 28051 14026 28051 14026 28052 14025 28052 13982 28052 14026 28053 13982 28053 14003 28053 14003 28054 13982 28054 14028 28054 14003 28055 14028 28055 14027 28055 14027 28056 14028 28056 13983 28056 14027 28057 13983 28057 14005 28057 14005 28058 13983 28058 14029 28058 14005 28059 14029 28059 14007 28059 14007 28060 14029 28060 13984 28060 14007 28061 13984 28061 14030 28061 14030 28062 13984 28062 13986 28062 14030 28063 13986 28063 14031 28063 14031 28064 13986 28064 13988 28064 14031 28065 13988 28065 14032 28065 14032 28066 13988 28066 14033 28066 14032 28067 14033 28067 14034 28067 14034 28068 14033 28068 13990 28068 14034 28069 13990 28069 14001 28069 14001 28070 13990 28070 14035 28070 14001 28071 14035 28071 14036 28071 14036 28072 14035 28072 14037 28072 14036 28073 14037 28073 14038 28073 14038 28074 14037 28074 13952 28074 14038 28075 13952 28075 13999 28075 13999 28076 13952 28076 13953 28076 13999 28077 13953 28077 13998 28077 13998 28078 13953 28078 13955 28078 13998 28079 13955 28079 14039 28079 14039 28080 13955 28080 14041 28080 14039 28081 14041 28081 14040 28081 14040 28082 14041 28082 14042 28082 13864 28083 14048 28083 14055 28083 14043 28084 14006 28084 15374 28084 15374 28085 14006 28085 14008 28085 15374 28086 14008 28086 15375 28086 14043 28087 15374 28087 14004 28087 14004 28088 15374 28088 14045 28088 14004 28089 14045 28089 13925 28089 14052 28090 14044 28090 14045 28090 14045 28091 14044 28091 13924 28091 14045 28092 13924 28092 13925 28092 14046 28093 14055 28093 14047 28093 14047 28094 14055 28094 14048 28094 14047 28095 14048 28095 13855 28095 14049 28096 13861 28096 14055 28096 14055 28097 13861 28097 14050 28097 14051 28098 13914 28098 13915 28098 13915 28099 13918 28099 14051 28099 14051 28100 13918 28100 13919 28100 14051 28101 13919 28101 14052 28101 14052 28102 13919 28102 13921 28102 14052 28103 13921 28103 14044 28103 13914 28104 14051 28104 14053 28104 14053 28105 14051 28105 14056 28105 14053 28106 14056 28106 13911 28106 14050 28107 14054 28107 14055 28107 14055 28108 14054 28108 13869 28108 14055 28109 13869 28109 13864 28109 13926 28110 14057 28110 14056 28110 14056 28111 14057 28111 14058 28111 14056 28112 14058 28112 13911 28112 14046 28113 14047 28113 15369 28113 15369 28114 14047 28114 14059 28114 15369 28115 14059 28115 15371 28115 15371 28116 14059 28116 13857 28116 15371 28117 13857 28117 13858 28117 13858 28118 13859 28118 15371 28118 15371 28119 13859 28119 13928 28119 15371 28120 13928 28120 14056 28120 14056 28121 13928 28121 13927 28121 14056 28122 13927 28122 13926 28122 14008 28123 14060 28123 15375 28123 15375 28124 14060 28124 14009 28124 15375 28125 14009 28125 14061 28125 14061 28126 14009 28126 14062 28126 14061 28127 14062 28127 14063 28127 14063 28128 14062 28128 14002 28128 14063 28129 14002 28129 14055 28129 14055 28130 14002 28130 13863 28130 14055 28131 13863 28131 14049 28131 14066 28132 14095 28132 14064 28132 14064 28133 14065 28133 14066 28133 14066 28134 14065 28134 13855 28134 14066 28135 13855 28135 14152 28135 14152 28136 13855 28136 14048 28136 14152 28137 14048 28137 14067 28137 14068 28138 14069 28138 14077 28138 14077 28139 14069 28139 14070 28139 14077 28140 14070 28140 14071 28140 14071 28141 14070 28141 13329 28141 14071 28142 13329 28142 14072 28142 14072 28143 13329 28143 14074 28143 14072 28144 14074 28144 14073 28144 14073 28145 14074 28145 13309 28145 14079 28146 14080 28146 14394 28146 14394 28147 14393 28147 14079 28147 14079 28148 14393 28148 14075 28148 14079 28149 14075 28149 14076 28149 14790 28150 14068 28150 14091 28150 14091 28151 14068 28151 14077 28151 14091 28152 14077 28152 14078 28152 14078 28153 14077 28153 14071 28153 14078 28154 14071 28154 14079 28154 14079 28155 14071 28155 14072 28155 14079 28156 14072 28156 14080 28156 14076 28157 14143 28157 14079 28157 14079 28158 14143 28158 14081 28158 14079 28159 14081 28159 14078 28159 14082 28160 14083 28160 14440 28160 14440 28161 14083 28161 14088 28161 14085 28162 14442 28162 14088 28162 14088 28163 14442 28163 14435 28163 14088 28164 14435 28164 14440 28164 13305 28165 14502 28165 14084 28165 14084 28166 14502 28166 14133 28166 14099 28167 14444 28167 14443 28167 14443 28168 14442 28168 14099 28168 14099 28169 14442 28169 14085 28169 14099 28170 14085 28170 14086 28170 14086 28171 14085 28171 14087 28171 14083 28172 13305 28172 14088 28172 14088 28173 13305 28173 14084 28173 14088 28174 14084 28174 14085 28174 14085 28175 14084 28175 14133 28175 14085 28176 14133 28176 14087 28176 14127 28177 14089 28177 14090 28177 13957 28178 13870 28178 14140 28178 13870 28179 14790 28179 14140 28179 14140 28180 14790 28180 14091 28180 14140 28181 14091 28181 14078 28181 14139 28182 14092 28182 14042 28182 14042 28183 14092 28183 14040 28183 14040 28184 14092 28184 14093 28184 14093 28185 14092 28185 14116 28185 14093 28186 14116 28186 13865 28186 13865 28187 14116 28187 14094 28187 14094 28188 14116 28188 14117 28188 14094 28189 14117 28189 14067 28189 14129 28190 13848 28190 14095 28190 13848 28191 14129 28191 13936 28191 13936 28192 14129 28192 14131 28192 13936 28193 14131 28193 14010 28193 14010 28194 14131 28194 14096 28194 14010 28195 14096 28195 13943 28195 13943 28196 14096 28196 14097 28196 14097 28197 14096 28197 14132 28197 14097 28198 14132 28198 14098 28198 14133 28199 14502 28199 14132 28199 14132 28200 14502 28200 13852 28200 14132 28201 13852 28201 14098 28201 14444 28202 14099 28202 14108 28202 14108 28203 14099 28203 14100 28203 14099 28204 14086 28204 14100 28204 14100 28205 14086 28205 14101 28205 14100 28206 14101 28206 14102 28206 14102 28207 14101 28207 14103 28207 14102 28208 14103 28208 14106 28208 14106 28209 14103 28209 14109 28209 14106 28210 14109 28210 14104 28210 14111 28211 14428 28211 14426 28211 14111 28212 14426 28212 14104 28212 14104 28213 14426 28213 14105 28213 14104 28214 14105 28214 14106 28214 14106 28215 14105 28215 14447 28215 14106 28216 14447 28216 14102 28216 14102 28217 14447 28217 14107 28217 14102 28218 14107 28218 14100 28218 14100 28219 14107 28219 14445 28219 14100 28220 14445 28220 14108 28220 14109 28221 14147 28221 14104 28221 14104 28222 14147 28222 14110 28222 14104 28223 14110 28223 14111 28223 14111 28224 14110 28224 14149 28224 14111 28225 14149 28225 14137 28225 14137 28226 14149 28226 14150 28226 14137 28227 14150 28227 14112 28227 14112 28228 14150 28228 14124 28228 14112 28229 14124 28229 14136 28229 14136 28230 14124 28230 14123 28230 14136 28231 14123 28231 14135 28231 14135 28232 14123 28232 14121 28232 14135 28233 14121 28233 14113 28233 14113 28234 14121 28234 14119 28234 14113 28235 14119 28235 14134 28235 14139 28236 14114 28236 14092 28236 14092 28237 14114 28237 14115 28237 14092 28238 14115 28238 14116 28238 14116 28239 14115 28239 14120 28239 14116 28240 14120 28240 14117 28240 14117 28241 14120 28241 14122 28241 14118 28242 14141 28242 14119 28242 14119 28243 14141 28243 14142 28243 14119 28244 14142 28244 14134 28244 14139 28245 14118 28245 14114 28245 14114 28246 14118 28246 14119 28246 14114 28247 14119 28247 14115 28247 14115 28248 14119 28248 14121 28248 14115 28249 14121 28249 14120 28249 14120 28250 14121 28250 14123 28250 14120 28251 14123 28251 14122 28251 14122 28252 14123 28252 14124 28252 14152 28253 14125 28253 14066 28253 14066 28254 14125 28254 14128 28254 14066 28255 14128 28255 14095 28255 14095 28256 14128 28256 14126 28256 14095 28257 14126 28257 14129 28257 14152 28258 14127 28258 14125 28258 14125 28259 14127 28259 14090 28259 14125 28260 14090 28260 14128 28260 14128 28261 14090 28261 14151 28261 14128 28262 14151 28262 14126 28262 14126 28263 14151 28263 14130 28263 14126 28264 14130 28264 14129 28264 14129 28265 14130 28265 14148 28265 14129 28266 14148 28266 14131 28266 14131 28267 14148 28267 14146 28267 14131 28268 14146 28268 14096 28268 14096 28269 14146 28269 14145 28269 14096 28270 14145 28270 14132 28270 14132 28271 14145 28271 14144 28271 14132 28272 14144 28272 14133 28272 14133 28273 14144 28273 14087 28273 14142 28274 14076 28274 14134 28274 14134 28275 14076 28275 14075 28275 14134 28276 14075 28276 14393 28276 14393 28277 14391 28277 14134 28277 14134 28278 14391 28278 14409 28278 14134 28279 14409 28279 14113 28279 14113 28280 14409 28280 14408 28280 14113 28281 14408 28281 14135 28281 14135 28282 14408 28282 14401 28282 14135 28283 14401 28283 14136 28283 14136 28284 14401 28284 14406 28284 14136 28285 14406 28285 14112 28285 14112 28286 14406 28286 14407 28286 14112 28287 14407 28287 14137 28287 14137 28288 14407 28288 14138 28288 14137 28289 14138 28289 14111 28289 14111 28290 14138 28290 14429 28290 14111 28291 14429 28291 14428 28291 14042 28292 13957 28292 14139 28292 14139 28293 13957 28293 14140 28293 14139 28294 14140 28294 14118 28294 14118 28295 14140 28295 14078 28295 14118 28296 14078 28296 14141 28296 14141 28297 14078 28297 14081 28297 14141 28298 14081 28298 14142 28298 14142 28299 14081 28299 14143 28299 14142 28300 14143 28300 14076 28300 14086 28301 14087 28301 14101 28301 14101 28302 14087 28302 14144 28302 14101 28303 14144 28303 14103 28303 14103 28304 14144 28304 14145 28304 14103 28305 14145 28305 14109 28305 14109 28306 14145 28306 14146 28306 14109 28307 14146 28307 14147 28307 14147 28308 14146 28308 14148 28308 14147 28309 14148 28309 14110 28309 14110 28310 14148 28310 14130 28310 14110 28311 14130 28311 14149 28311 14149 28312 14130 28312 14151 28312 14149 28313 14151 28313 14150 28313 14150 28314 14151 28314 14090 28314 14150 28315 14090 28315 14124 28315 14124 28316 14090 28316 14089 28316 14124 28317 14089 28317 14122 28317 14122 28318 14089 28318 14127 28318 14122 28319 14127 28319 14117 28319 14117 28320 14127 28320 14152 28320 14117 28321 14152 28321 14067 28321 14276 28322 14232 28322 14278 28322 14232 28323 14276 28323 14275 28323 14250 28324 14209 28324 14210 28324 14214 28325 14213 28325 14202 28325 12936 28326 14153 28326 14154 28326 14207 28327 14191 28327 14181 28327 14155 28328 13026 28328 14282 28328 14156 28329 14253 28329 14283 28329 14253 28330 14156 28330 13027 28330 13028 28331 13031 28331 14176 28331 14157 28332 13227 28332 14188 28332 14158 28333 13268 28333 14159 28333 14201 28334 14200 28334 13266 28334 14160 28335 13266 28335 14161 28335 14161 28336 13266 28336 14200 28336 14161 28337 14200 28337 14198 28337 14251 28338 14162 28338 14250 28338 14250 28339 14162 28339 13229 28339 14172 28340 13172 28340 14244 28340 14244 28341 13172 28341 14163 28341 14244 28342 14163 28342 14247 28342 14247 28343 14163 28343 13235 28343 14247 28344 13235 28344 14248 28344 14248 28345 13235 28345 14165 28345 14248 28346 14165 28346 14164 28346 14164 28347 14165 28347 13233 28347 14164 28348 13233 28348 14166 28348 14166 28349 13233 28349 14168 28349 14166 28350 14168 28350 14167 28350 14167 28351 14168 28351 13230 28351 13163 28352 13162 28352 14169 28352 14169 28353 13162 28353 14170 28353 14169 28354 14170 28354 14243 28354 14243 28355 14170 28355 14171 28355 14243 28356 14171 28356 14172 28356 14172 28357 14171 28357 13173 28357 14172 28358 13173 28358 13172 28358 13167 28359 13166 28359 14177 28359 14177 28360 13166 28360 13165 28360 14177 28361 13165 28361 13163 28361 14288 28362 13168 28362 14178 28362 14288 28363 14178 28363 14289 28363 13156 28364 13161 28364 14287 28364 14287 28365 13161 28365 13160 28365 14287 28366 13160 28366 14288 28366 14288 28367 13160 28367 13158 28367 14288 28368 13158 28368 13168 28368 13163 28369 14169 28369 14177 28369 14177 28370 14169 28370 13078 28370 14177 28371 13078 28371 13795 28371 14239 28372 13056 28372 14240 28372 14240 28373 13056 28373 13083 28373 14219 28374 14173 28374 14238 28374 14173 28375 14221 28375 13036 28375 13036 28376 14221 28376 14229 28376 13036 28377 14229 28377 13058 28377 14174 28378 13061 28378 14175 28378 14175 28379 13061 28379 13060 28379 14175 28380 13060 28380 14229 28380 14229 28381 13060 28381 13059 28381 14229 28382 13059 28382 13058 28382 13028 28383 14176 28383 14252 28383 13795 28384 13792 28384 14177 28384 14177 28385 13792 28385 14289 28385 14177 28386 14289 28386 13167 28386 13167 28387 14289 28387 14178 28387 14191 28388 14207 28388 14190 28388 12932 28389 12931 28389 14179 28389 14179 28390 12931 28390 14180 28390 14179 28391 14180 28391 14181 28391 14181 28392 14180 28392 12944 28392 14181 28393 12944 28393 14207 28393 14203 28394 12897 28394 14215 28394 14182 28395 12943 28395 14204 28395 14204 28396 12943 28396 12897 28396 14190 28397 14250 28397 14188 28397 14188 28398 14250 28398 13229 28398 14188 28399 13229 28399 14157 28399 13260 28400 14183 28400 14199 28400 14199 28401 14183 28401 14257 28401 14199 28402 14257 28402 14197 28402 14197 28403 14257 28403 14260 28403 14197 28404 14260 28404 14185 28404 14185 28405 14260 28405 14184 28405 14185 28406 14184 28406 14196 28406 14196 28407 14184 28407 14262 28407 14196 28408 14262 28408 14194 28408 14194 28409 14262 28409 14186 28409 14194 28410 14186 28410 14263 28410 14187 28411 14192 28411 14198 28411 14198 28412 14192 28412 14189 28412 14198 28413 14189 28413 14161 28413 14161 28414 14189 28414 14159 28414 14161 28415 14159 28415 14160 28415 14160 28416 14159 28416 13268 28416 13227 28417 14158 28417 14188 28417 14188 28418 14158 28418 14159 28418 14188 28419 14159 28419 14190 28419 14190 28420 14159 28420 14189 28420 14190 28421 14189 28421 14191 28421 14191 28422 14189 28422 14192 28422 14191 28423 14192 28423 14181 28423 14181 28424 14192 28424 14195 28424 14181 28425 14195 28425 14179 28425 14153 28426 14193 28426 14154 28426 14154 28427 14193 28427 12932 28427 14154 28428 12932 28428 14263 28428 14263 28429 12932 28429 14179 28429 14263 28430 14179 28430 14194 28430 14194 28431 14179 28431 14195 28431 14194 28432 14195 28432 14196 28432 14196 28433 14195 28433 14192 28433 14196 28434 14192 28434 14185 28434 14185 28435 14192 28435 14187 28435 14185 28436 14187 28436 14197 28436 14197 28437 14187 28437 14198 28437 14197 28438 14198 28438 14199 28438 14199 28439 14198 28439 14200 28439 14199 28440 14200 28440 13260 28440 13260 28441 14200 28441 14201 28441 14214 28442 14202 28442 14216 28442 14216 28443 14202 28443 14217 28443 14216 28444 14217 28444 14234 28444 12897 28445 14203 28445 14204 28445 14204 28446 14203 28446 14206 28446 14204 28447 14206 28447 14205 28447 14205 28448 14206 28448 14235 28448 14205 28449 14235 28449 14237 28449 14207 28450 13807 28450 14190 28450 14190 28451 13807 28451 13806 28451 14190 28452 13806 28452 14250 28452 14250 28453 13806 28453 14208 28453 14250 28454 14208 28454 14209 28454 14209 28455 14208 28455 14182 28455 14209 28456 14182 28456 14210 28456 14210 28457 14182 28457 14204 28457 14210 28458 14204 28458 14249 28458 14249 28459 14204 28459 14205 28459 14245 28460 14246 28460 14237 28460 14237 28461 14246 28461 14211 28461 14237 28462 14211 28462 14205 28462 14205 28463 14211 28463 14212 28463 14205 28464 14212 28464 14249 28464 12936 28465 14154 28465 12937 28465 12937 28466 14154 28466 14213 28466 12937 28467 14213 28467 14215 28467 14215 28468 14213 28468 14214 28468 14215 28469 14214 28469 14203 28469 14203 28470 14214 28470 14216 28470 14203 28471 14216 28471 14206 28471 14206 28472 14216 28472 14234 28472 14206 28473 14234 28473 14235 28473 14217 28474 14268 28474 14218 28474 14219 28475 14236 28475 14173 28475 14173 28476 14236 28476 14220 28476 14173 28477 14220 28477 14221 28477 14221 28478 14220 28478 14218 28478 14221 28479 14218 28479 14229 28479 14229 28480 14218 28480 14268 28480 14222 28481 14223 28481 14224 28481 14224 28482 14223 28482 14225 28482 14224 28483 14225 28483 14226 28483 14226 28484 14225 28484 14227 28484 14226 28485 14227 28485 14314 28485 14314 28486 14227 28486 14231 28486 14314 28487 14231 28487 14316 28487 14316 28488 14231 28488 14233 28488 14316 28489 14233 28489 14228 28489 14228 28490 14233 28490 14273 28490 14228 28491 14273 28491 14317 28491 14268 28492 14270 28492 14229 28492 14229 28493 14270 28493 14271 28493 14229 28494 14271 28494 14175 28494 14175 28495 14271 28495 14272 28495 14175 28496 14272 28496 14230 28496 14230 28497 14272 28497 14256 28497 14230 28498 14256 28498 14255 28498 14223 28499 13154 28499 14225 28499 14225 28500 13154 28500 14277 28500 14225 28501 14277 28501 14227 28501 14227 28502 14277 28502 14278 28502 14227 28503 14278 28503 14231 28503 14231 28504 14278 28504 14232 28504 14231 28505 14232 28505 14233 28505 14233 28506 14232 28506 14275 28506 14233 28507 14275 28507 14273 28507 14255 28508 14254 28508 14230 28508 14230 28509 14254 28509 14176 28509 14230 28510 14176 28510 14175 28510 14175 28511 14176 28511 13031 28511 14175 28512 13031 28512 14174 28512 14217 28513 14218 28513 14234 28513 14234 28514 14218 28514 14220 28514 14234 28515 14220 28515 14235 28515 14235 28516 14220 28516 14236 28516 14235 28517 14236 28517 14237 28517 14237 28518 14236 28518 14242 28518 14237 28519 14242 28519 14245 28519 14238 28520 14239 28520 14219 28520 14219 28521 14239 28521 14240 28521 14219 28522 14240 28522 14236 28522 14236 28523 14240 28523 14241 28523 14236 28524 14241 28524 14242 28524 13083 28525 13078 28525 14240 28525 14240 28526 13078 28526 14169 28526 14240 28527 14169 28527 14241 28527 14241 28528 14169 28528 14243 28528 14241 28529 14243 28529 14242 28529 14242 28530 14243 28530 14172 28530 14242 28531 14172 28531 14245 28531 14245 28532 14172 28532 14244 28532 14245 28533 14244 28533 14246 28533 14246 28534 14244 28534 14247 28534 14246 28535 14247 28535 14211 28535 14211 28536 14247 28536 14248 28536 14211 28537 14248 28537 14212 28537 14212 28538 14248 28538 14164 28538 14212 28539 14164 28539 14249 28539 14249 28540 14164 28540 14166 28540 14249 28541 14166 28541 14210 28541 14210 28542 14166 28542 14167 28542 14210 28543 14167 28543 14250 28543 14250 28544 14167 28544 13230 28544 14250 28545 13230 28545 14251 28545 13027 28546 14252 28546 14253 28546 14253 28547 14252 28547 14176 28547 14253 28548 14176 28548 14283 28548 14283 28549 14176 28549 14254 28549 14283 28550 14254 28550 14279 28550 14279 28551 14254 28551 14255 28551 14279 28552 14255 28552 14274 28552 14274 28553 14255 28553 14256 28553 14183 28554 14258 28554 14257 28554 14257 28555 14258 28555 14259 28555 14257 28556 14259 28556 14260 28556 14260 28557 14259 28557 14261 28557 14260 28558 14261 28558 14184 28558 14184 28559 14261 28559 14329 28559 14184 28560 14329 28560 14262 28560 14262 28561 14329 28561 14328 28561 14262 28562 14328 28562 14186 28562 14186 28563 14328 28563 14264 28563 14186 28564 14264 28564 14263 28564 14263 28565 14264 28565 14265 28565 14263 28566 14265 28566 14154 28566 14154 28567 14265 28567 14266 28567 14154 28568 14266 28568 14213 28568 14213 28569 14266 28569 14324 28569 14213 28570 14324 28570 14202 28570 14202 28571 14324 28571 14267 28571 14202 28572 14267 28572 14217 28572 14217 28573 14267 28573 14321 28573 14217 28574 14321 28574 14268 28574 14268 28575 14321 28575 14269 28575 14268 28576 14269 28576 14270 28576 14270 28577 14269 28577 14320 28577 14270 28578 14320 28578 14271 28578 14271 28579 14320 28579 14319 28579 14271 28580 14319 28580 14272 28580 14272 28581 14319 28581 14317 28581 14272 28582 14317 28582 14256 28582 14256 28583 14317 28583 14273 28583 14256 28584 14273 28584 14274 28584 14274 28585 14273 28585 14275 28585 14274 28586 14275 28586 14279 28586 14279 28587 14275 28587 14276 28587 13154 28588 13153 28588 14277 28588 14277 28589 13153 28589 14285 28589 14277 28590 14285 28590 14278 28590 14278 28591 14285 28591 14286 28591 14278 28592 14286 28592 14276 28592 14276 28593 14286 28593 14280 28593 14276 28594 14280 28594 14279 28594 14279 28595 14280 28595 14281 28595 14279 28596 14281 28596 14283 28596 14283 28597 14281 28597 14282 28597 14283 28598 14282 28598 14156 28598 14156 28599 14282 28599 13026 28599 13153 28600 14284 28600 14285 28600 14285 28601 14284 28601 13206 28601 14285 28602 13206 28602 14286 28602 14286 28603 13206 28603 13156 28603 14286 28604 13156 28604 14280 28604 14280 28605 13156 28605 14287 28605 14280 28606 14287 28606 14281 28606 14281 28607 14287 28607 14288 28607 14281 28608 14288 28608 14282 28608 14282 28609 14288 28609 14289 28609 14282 28610 14289 28610 14155 28610 14155 28611 14289 28611 13792 28611 14384 28612 14290 28612 14385 28612 14385 28613 14290 28613 14312 28613 14385 28614 14312 28614 14296 28614 14296 28615 14312 28615 14313 28615 14318 28616 14291 28616 14292 28616 14292 28617 14291 28617 14354 28617 14292 28618 14354 28618 14315 28618 14315 28619 14354 28619 14357 28619 14315 28620 14357 28620 14293 28620 14293 28621 14357 28621 14295 28621 14293 28622 14295 28622 14294 28622 14294 28623 14295 28623 14359 28623 14294 28624 14359 28624 14313 28624 14313 28625 14359 28625 14361 28625 14313 28626 14361 28626 14296 28626 14304 28627 14325 28627 14326 28627 14297 28628 14298 28628 14299 28628 14299 28629 14298 28629 14300 28629 14299 28630 14300 28630 14330 28630 14330 28631 14300 28631 14339 28631 14330 28632 14339 28632 14301 28632 14301 28633 14339 28633 14302 28633 14301 28634 14302 28634 14303 28634 14303 28635 14302 28635 14340 28635 14303 28636 14340 28636 14327 28636 14327 28637 14340 28637 14345 28637 14327 28638 14345 28638 14326 28638 14326 28639 14345 28639 14346 28639 14326 28640 14346 28640 14304 28640 14304 28641 14305 28641 14325 28641 14325 28642 14305 28642 14306 28642 14325 28643 14306 28643 14323 28643 14323 28644 14306 28644 14347 28644 14323 28645 14347 28645 14322 28645 14322 28646 14347 28646 14352 28646 14322 28647 14352 28647 14307 28647 14307 28648 14352 28648 14351 28648 14307 28649 14351 28649 14308 28649 14308 28650 14351 28650 14350 28650 14308 28651 14350 28651 14309 28651 14309 28652 14350 28652 14310 28652 14309 28653 14310 28653 14318 28653 14318 28654 14310 28654 14311 28654 14318 28655 14311 28655 14291 28655 14290 28656 14222 28656 14312 28656 14312 28657 14222 28657 14224 28657 14312 28658 14224 28658 14313 28658 14313 28659 14224 28659 14226 28659 14313 28660 14226 28660 14294 28660 14294 28661 14226 28661 14314 28661 14294 28662 14314 28662 14293 28662 14293 28663 14314 28663 14316 28663 14293 28664 14316 28664 14315 28664 14315 28665 14316 28665 14228 28665 14315 28666 14228 28666 14292 28666 14292 28667 14228 28667 14317 28667 14292 28668 14317 28668 14318 28668 14318 28669 14317 28669 14319 28669 14318 28670 14319 28670 14309 28670 14309 28671 14319 28671 14320 28671 14309 28672 14320 28672 14308 28672 14308 28673 14320 28673 14269 28673 14308 28674 14269 28674 14307 28674 14307 28675 14269 28675 14321 28675 14307 28676 14321 28676 14322 28676 14322 28677 14321 28677 14267 28677 14322 28678 14267 28678 14323 28678 14323 28679 14267 28679 14324 28679 14323 28680 14324 28680 14325 28680 14325 28681 14324 28681 14266 28681 14325 28682 14266 28682 14326 28682 14326 28683 14266 28683 14265 28683 14326 28684 14265 28684 14327 28684 14327 28685 14265 28685 14264 28685 14327 28686 14264 28686 14303 28686 14303 28687 14264 28687 14328 28687 14303 28688 14328 28688 14301 28688 14301 28689 14328 28689 14329 28689 14301 28690 14329 28690 14330 28690 14330 28691 14329 28691 14261 28691 14330 28692 14261 28692 14299 28692 14299 28693 14261 28693 14259 28693 14299 28694 14259 28694 14297 28694 14297 28695 14259 28695 14258 28695 14445 28696 14107 28696 14446 28696 14427 28697 14413 28697 14425 28697 14331 28698 14457 28698 14335 28698 14401 28699 14408 28699 14410 28699 14387 28700 14386 28700 14403 28700 14390 28701 14392 28701 14396 28701 13294 28702 13295 28702 14450 28702 14082 28703 14440 28703 14439 28703 14072 28704 14073 28704 14397 28704 14397 28705 14073 28705 13309 28705 14332 28706 14501 28706 14333 28706 14332 28707 14333 28707 13313 28707 13313 28708 14333 28708 14388 28708 13313 28709 14388 28709 13308 28709 14082 28710 14439 28710 13293 28710 13293 28711 14439 28711 14437 28711 13293 28712 14437 28712 13291 28712 13291 28713 14437 28713 14335 28713 13291 28714 14335 28714 14334 28714 14334 28715 14335 28715 14336 28715 14336 28716 14335 28716 14457 28716 14336 28717 14457 28717 13297 28717 14375 28718 13723 28718 14337 28718 14337 28719 13723 28719 14298 28719 13723 28720 13740 28720 14298 28720 14298 28721 13740 28721 13722 28721 14298 28722 13722 28722 14300 28722 14300 28723 13722 28723 14338 28723 14300 28724 14338 28724 14339 28724 14339 28725 14338 28725 12959 28725 14339 28726 12959 28726 14302 28726 12959 28727 12965 28727 14302 28727 14302 28728 12965 28728 12967 28728 14302 28729 12967 28729 14340 28729 14340 28730 12967 28730 14341 28730 14340 28731 14341 28731 14345 28731 14345 28732 14341 28732 14342 28732 14345 28733 14342 28733 13000 28733 13000 28734 14343 28734 14345 28734 14345 28735 14343 28735 12999 28735 14345 28736 12999 28736 14344 28736 14453 28737 14344 28737 12998 28737 14453 28738 12998 28738 14376 28738 14344 28739 14453 28739 14345 28739 14345 28740 14453 28740 14483 28740 14345 28741 14483 28741 14346 28741 14347 28742 14306 28742 14348 28742 14348 28743 14306 28743 14305 28743 14348 28744 14305 28744 14304 28744 14311 28745 14310 28745 14349 28745 14349 28746 14310 28746 14350 28746 14349 28747 14350 28747 14372 28747 14372 28748 14350 28748 14351 28748 14372 28749 14351 28749 14352 28749 14353 28750 14355 28750 14468 28750 14353 28751 14468 28751 13112 28751 14291 28752 14364 28752 14354 28752 14354 28753 14364 28753 14468 28753 14354 28754 14468 28754 14357 28754 14357 28755 14468 28755 14355 28755 14355 28756 14356 28756 14357 28756 14357 28757 14356 28757 13135 28757 14357 28758 13135 28758 13115 28758 13115 28759 13116 28759 14357 28759 14357 28760 13116 28760 13132 28760 14357 28761 13132 28761 14295 28761 14295 28762 13132 28762 14358 28762 14295 28763 14358 28763 14359 28763 14359 28764 14358 28764 13134 28764 14383 28765 14296 28765 14360 28765 14360 28766 14296 28766 14361 28766 14360 28767 14361 28767 14362 28767 14362 28768 14361 28768 14359 28768 14362 28769 14359 28769 14363 28769 14363 28770 14359 28770 13134 28770 12856 28771 12858 28771 14349 28771 14349 28772 12858 28772 14364 28772 14349 28773 14364 28773 14311 28773 14311 28774 14364 28774 14291 28774 15381 28775 15380 28775 14365 28775 14365 28776 15380 28776 14369 28776 14369 28777 15380 28777 15383 28777 14369 28778 15383 28778 14366 28778 14366 28779 14367 28779 14369 28779 14369 28780 14367 28780 14368 28780 14369 28781 14368 28781 14370 28781 14368 28782 15385 28782 14370 28782 14370 28783 15385 28783 14371 28783 14370 28784 14371 28784 15388 28784 14449 28785 12874 28785 14372 28785 14372 28786 12874 28786 12851 28786 14372 28787 12851 28787 12850 28787 12850 28788 12853 28788 14372 28788 14372 28789 12853 28789 14373 28789 14372 28790 14373 28790 14349 28790 14349 28791 14373 28791 12855 28791 14349 28792 12855 28792 12856 28792 14377 28793 14374 28793 14375 28793 14375 28794 14374 28794 13015 28794 14375 28795 13015 28795 13723 28795 12998 28796 12996 28796 14376 28796 14376 28797 12996 28797 12995 28797 14376 28798 12995 28798 14377 28798 14377 28799 12995 28799 14378 28799 14377 28800 14378 28800 14374 28800 13092 28801 13111 28801 14469 28801 14469 28802 13111 28802 14379 28802 14469 28803 14379 28803 14468 28803 14468 28804 14379 28804 13114 28804 14468 28805 13114 28805 13112 28805 14469 28806 14471 28806 13092 28806 13092 28807 14471 28807 14380 28807 13092 28808 14380 28808 14381 28808 14381 28809 14380 28809 14472 28809 14381 28810 14472 28810 14382 28810 14382 28811 14472 28811 14473 28811 14382 28812 14473 28812 13761 28812 13761 28813 14473 28813 14384 28813 13761 28814 14384 28814 14383 28814 14383 28815 14384 28815 14385 28815 14383 28816 14385 28816 14296 28816 14402 28817 14386 28817 14495 28817 14495 28818 14386 28818 14387 28818 14495 28819 14387 28819 14497 28819 13309 28820 13308 28820 14397 28820 14397 28821 13308 28821 14388 28821 14397 28822 14388 28822 14389 28822 14389 28823 14388 28823 14333 28823 14389 28824 14333 28824 14395 28824 14395 28825 14333 28825 14501 28825 14395 28826 14501 28826 14500 28826 14409 28827 14391 28827 14390 28827 14390 28828 14391 28828 14393 28828 14390 28829 14393 28829 14392 28829 14392 28830 14393 28830 14394 28830 14392 28831 14394 28831 14080 28831 14500 28832 14412 28832 14395 28832 14395 28833 14412 28833 14396 28833 14395 28834 14396 28834 14389 28834 14389 28835 14396 28835 14392 28835 14389 28836 14392 28836 14397 28836 14397 28837 14392 28837 14080 28837 14397 28838 14080 28838 14072 28838 14398 28839 14497 28839 14411 28839 14411 28840 14497 28840 14387 28840 14411 28841 14387 28841 14399 28841 14399 28842 14387 28842 14403 28842 14399 28843 14403 28843 14410 28843 14410 28844 14403 28844 14400 28844 14410 28845 14400 28845 14401 28845 14402 28846 14488 28846 14386 28846 14386 28847 14488 28847 14487 28847 14386 28848 14487 28848 14403 28848 14403 28849 14487 28849 14404 28849 14403 28850 14404 28850 14400 28850 14400 28851 14404 28851 14405 28851 14400 28852 14405 28852 14401 28852 14401 28853 14405 28853 14484 28853 14401 28854 14484 28854 14406 28854 14406 28855 14484 28855 14407 28855 14408 28856 14409 28856 14410 28856 14410 28857 14409 28857 14390 28857 14410 28858 14390 28858 14399 28858 14399 28859 14390 28859 14396 28859 14399 28860 14396 28860 14411 28860 14411 28861 14396 28861 14412 28861 14411 28862 14412 28862 14398 28862 14398 28863 14412 28863 14500 28863 14425 28864 14413 28864 14448 28864 14448 28865 14413 28865 14414 28865 14448 28866 14414 28866 14415 28866 14421 28867 14416 28867 14417 28867 14418 28868 14492 28868 14421 28868 14421 28869 14492 28869 14460 28869 14421 28870 14460 28870 14416 28870 14490 28871 14418 28871 14419 28871 14419 28872 14418 28872 14421 28872 14419 28873 14421 28873 14420 28873 14420 28874 14421 28874 14417 28874 14420 28875 14417 28875 14459 28875 14486 28876 14415 28876 14422 28876 14422 28877 14415 28877 14414 28877 14422 28878 14414 28878 14424 28878 14424 28879 14414 28879 14413 28879 14427 28880 14423 28880 14413 28880 14413 28881 14423 28881 14485 28881 14413 28882 14485 28882 14424 28882 14447 28883 14105 28883 14425 28883 14425 28884 14105 28884 14426 28884 14425 28885 14426 28885 14427 28885 14427 28886 14426 28886 14428 28886 14427 28887 14428 28887 14423 28887 14423 28888 14428 28888 14429 28888 14423 28889 14429 28889 14138 28889 14430 28890 14432 28890 14431 28890 14431 28891 14432 28891 14433 28891 14431 28892 14433 28892 14434 28892 14434 28893 14433 28893 14491 28893 14434 28894 14491 28894 14446 28894 14446 28895 14491 28895 14489 28895 14446 28896 14489 28896 14445 28896 14435 28897 14490 28897 14441 28897 14441 28898 14490 28898 14419 28898 14441 28899 14419 28899 14438 28899 14438 28900 14419 28900 14420 28900 14438 28901 14420 28901 14436 28901 14436 28902 14420 28902 14459 28902 14436 28903 14459 28903 14331 28903 14331 28904 14335 28904 14436 28904 14436 28905 14335 28905 14437 28905 14436 28906 14437 28906 14438 28906 14438 28907 14437 28907 14439 28907 14438 28908 14439 28908 14441 28908 14441 28909 14439 28909 14440 28909 14441 28910 14440 28910 14435 28910 14442 28911 14443 28911 14489 28911 14443 28912 14444 28912 14489 28912 14489 28913 14444 28913 14108 28913 14489 28914 14108 28914 14445 28914 14107 28915 14447 28915 14446 28915 14446 28916 14447 28916 14425 28916 14446 28917 14425 28917 14434 28917 14434 28918 14425 28918 14448 28918 14434 28919 14448 28919 14431 28919 14431 28920 14448 28920 14415 28920 14431 28921 14415 28921 14430 28921 14430 28922 14415 28922 14486 28922 15388 28923 14449 28923 14370 28923 14370 28924 14449 28924 14372 28924 14370 28925 14372 28925 14348 28925 14348 28926 14372 28926 14352 28926 14348 28927 14352 28927 14347 28927 14298 28928 13294 28928 14337 28928 14337 28929 13294 28929 14450 28929 14337 28930 14450 28930 14375 28930 14375 28931 14450 28931 14451 28931 14375 28932 14451 28932 14377 28932 14377 28933 14451 28933 14466 28933 14377 28934 14466 28934 14376 28934 14376 28935 14466 28935 14452 28935 14376 28936 14452 28936 14453 28936 14453 28937 14452 28937 14454 28937 14453 28938 14454 28938 14483 28938 14483 28939 14454 28939 14455 28939 14483 28940 14455 28940 14482 28940 14482 28941 14455 28941 14463 28941 14482 28942 14463 28942 14493 28942 13296 28943 13297 28943 14456 28943 14456 28944 13297 28944 14457 28944 14456 28945 14457 28945 14467 28945 14467 28946 14457 28946 14331 28946 14467 28947 14331 28947 14458 28947 14458 28948 14331 28948 14459 28948 14458 28949 14459 28949 14465 28949 14465 28950 14459 28950 14417 28950 14465 28951 14417 28951 14464 28951 14464 28952 14417 28952 14416 28952 14464 28953 14416 28953 14462 28953 14462 28954 14416 28954 14460 28954 14492 28955 14461 28955 14460 28955 14460 28956 14461 28956 14463 28956 14460 28957 14463 28957 14462 28957 14462 28958 14463 28958 14455 28958 14462 28959 14455 28959 14464 28959 14464 28960 14455 28960 14454 28960 14464 28961 14454 28961 14465 28961 14465 28962 14454 28962 14452 28962 14465 28963 14452 28963 14458 28963 14458 28964 14452 28964 14466 28964 14458 28965 14466 28965 14467 28965 14467 28966 14466 28966 14451 28966 14467 28967 14451 28967 14456 28967 14456 28968 14451 28968 14450 28968 14456 28969 14450 28969 13296 28969 13296 28970 14450 28970 13295 28970 12858 28971 15381 28971 14364 28971 14364 28972 15381 28972 14365 28972 14364 28973 14365 28973 14468 28973 14468 28974 14365 28974 14470 28974 14468 28975 14470 28975 14469 28975 14469 28976 14470 28976 14480 28976 14469 28977 14480 28977 14471 28977 14471 28978 14480 28978 14478 28978 14471 28979 14478 28979 14380 28979 14380 28980 14478 28980 14477 28980 14380 28981 14477 28981 14472 28981 14472 28982 14477 28982 14475 28982 14472 28983 14475 28983 14473 28983 14473 28984 14475 28984 14474 28984 13323 28985 14474 28985 14476 28985 14476 28986 14474 28986 14475 28986 14476 28987 14475 28987 14499 28987 14499 28988 14475 28988 14477 28988 14499 28989 14477 28989 14498 28989 14498 28990 14477 28990 14478 28990 14498 28991 14478 28991 14496 28991 14496 28992 14478 28992 14480 28992 14496 28993 14480 28993 14479 28993 14479 28994 14480 28994 14470 28994 14479 28995 14470 28995 14481 28995 14481 28996 14470 28996 14365 28996 14481 28997 14365 28997 14494 28997 14494 28998 14365 28998 14369 28998 14494 28999 14369 28999 14493 28999 14493 29000 14369 29000 14370 29000 14493 29001 14370 29001 14482 29001 14482 29002 14370 29002 14348 29002 14482 29003 14348 29003 14483 29003 14483 29004 14348 29004 14304 29004 14483 29005 14304 29005 14346 29005 14138 29006 14407 29006 14423 29006 14423 29007 14407 29007 14484 29007 14423 29008 14484 29008 14485 29008 14485 29009 14484 29009 14405 29009 14485 29010 14405 29010 14424 29010 14424 29011 14405 29011 14404 29011 14424 29012 14404 29012 14422 29012 14422 29013 14404 29013 14487 29013 14422 29014 14487 29014 14486 29014 14486 29015 14487 29015 14488 29015 14435 29016 14442 29016 14490 29016 14490 29017 14442 29017 14489 29017 14490 29018 14489 29018 14418 29018 14418 29019 14489 29019 14491 29019 14418 29020 14491 29020 14492 29020 14492 29021 14491 29021 14433 29021 14492 29022 14433 29022 14461 29022 14461 29023 14433 29023 14432 29023 14461 29024 14432 29024 14463 29024 14463 29025 14432 29025 14430 29025 14463 29026 14430 29026 14493 29026 14493 29027 14430 29027 14486 29027 14493 29028 14486 29028 14494 29028 14494 29029 14486 29029 14488 29029 14494 29030 14488 29030 14481 29030 14481 29031 14488 29031 14402 29031 14481 29032 14402 29032 14479 29032 14479 29033 14402 29033 14495 29033 14479 29034 14495 29034 14496 29034 14496 29035 14495 29035 14497 29035 14496 29036 14497 29036 14498 29036 14498 29037 14497 29037 14398 29037 14498 29038 14398 29038 14499 29038 14499 29039 14398 29039 14500 29039 14499 29040 14500 29040 14476 29040 14476 29041 14500 29041 14501 29041 14476 29042 14501 29042 13323 29042 13323 29043 14501 29043 14332 29043 14502 29044 13305 29044 14504 29044 14505 29045 12843 29045 14504 29045 14504 29046 12843 29046 14503 29046 14504 29047 14503 29047 14502 29047 14505 29048 14506 29048 12843 29048 12843 29049 14506 29049 12823 29049 12843 29050 12823 29050 12822 29050 14538 29051 14536 29051 14673 29051 13285 29052 14527 29052 13286 29052 14598 29053 13263 29053 14507 29053 13219 29054 13221 29054 14681 29054 13314 29055 14565 29055 14532 29055 13331 29056 14557 29056 14548 29056 14508 29057 14948 29057 14562 29057 14974 29058 14642 29058 14643 29058 14509 29059 14977 29059 14510 29059 14967 29060 14511 29060 14539 29060 14512 29061 14682 29061 14530 29061 14513 29062 14514 29062 14673 29062 14795 29063 14515 29063 14691 29063 14665 29064 14702 29064 14516 29064 14516 29065 14702 29065 14701 29065 14516 29066 14701 29066 14695 29066 14517 29067 14518 29067 14520 29067 14665 29068 14800 29068 14666 29068 14666 29069 14800 29069 14654 29069 14654 29070 14803 29070 14655 29070 14655 29071 14803 29071 14519 29071 14655 29072 14519 29072 14520 29072 14520 29073 14519 29073 14791 29073 14520 29074 14791 29074 14517 29074 15225 29075 15224 29075 14718 29075 14521 29076 14522 29076 14719 29076 14719 29077 14522 29077 15227 29077 14719 29078 15227 29078 14718 29078 14718 29079 15227 29079 14523 29079 14718 29080 14523 29080 15225 29080 14680 29081 15222 29081 14524 29081 14680 29082 14524 29082 14525 29082 14524 29083 15232 29083 14525 29083 14525 29084 15232 29084 15231 29084 14525 29085 15231 29085 13285 29085 13285 29086 15231 29086 14526 29086 13285 29087 14526 29087 14527 29087 15256 29088 14564 29088 14672 29088 15256 29089 14672 29089 15258 29089 14513 29090 14520 29090 14528 29090 14528 29091 14520 29091 14688 29091 14528 29092 14688 29092 14683 29092 14683 29093 14688 29093 14529 29093 14512 29094 14530 29094 15254 29094 14530 29095 14531 29095 15254 29095 15254 29096 14531 29096 14532 29096 15254 29097 14532 29097 14533 29097 14533 29098 14532 29098 14565 29098 14533 29099 14565 29099 14534 29099 13318 29100 14535 29100 15013 29100 13318 29101 15013 29101 13319 29101 15006 29102 15007 29102 14536 29102 15007 29103 15009 29103 14536 29103 14536 29104 15009 29104 14537 29104 14536 29105 14537 29105 14647 29105 14647 29106 14537 29106 15010 29106 14647 29107 15010 29107 14646 29107 14536 29108 14538 29108 15006 29108 15006 29109 14538 29109 14671 29109 15006 29110 14671 29110 14670 29110 14541 29111 14967 29111 13317 29111 13317 29112 14967 29112 14539 29112 13317 29113 14539 29113 13318 29113 13318 29114 14539 29114 14540 29114 13318 29115 14540 29115 14535 29115 14541 29116 13317 29116 14980 29116 14980 29117 13317 29117 14542 29117 14980 29118 14542 29118 14978 29118 14509 29119 14510 29119 14642 29119 14543 29120 14547 29120 14544 29120 14544 29121 14970 29121 14543 29121 14543 29122 14970 29122 14972 29122 14543 29123 14972 29123 14545 29123 14545 29124 14972 29124 14974 29124 14646 29125 14546 29125 14543 29125 14543 29126 14546 29126 14540 29126 14543 29127 14540 29127 14547 29127 14547 29128 14540 29128 14539 29128 14547 29129 14539 29129 14544 29129 14544 29130 14539 29130 14511 29130 13333 29131 13331 29131 14550 29131 14552 29132 14949 29132 14548 29132 14548 29133 14949 29133 14549 29133 14548 29134 14549 29134 13331 29134 13331 29135 14549 29135 14952 29135 13331 29136 14952 29136 14550 29136 14945 29137 14551 29137 14943 29137 14943 29138 14551 29138 13333 29138 14943 29139 13333 29139 14953 29139 14953 29140 13333 29140 14550 29140 14552 29141 14638 29141 14553 29141 14553 29142 14638 29142 14554 29142 14553 29143 14554 29143 14555 29143 12782 29144 14924 29144 14926 29144 12782 29145 14926 29145 13338 29145 14926 29146 14913 29146 13338 29146 13338 29147 14913 29147 14556 29147 13338 29148 14556 29148 13331 29148 13331 29149 14556 29149 14915 29149 13331 29150 14915 29150 14557 29150 14557 29151 14915 29151 14916 29151 14916 29152 14558 29152 14557 29152 14557 29153 14558 29153 14918 29153 14557 29154 14918 29154 14559 29154 14559 29155 14918 29155 14919 29155 14559 29156 14919 29156 15440 29156 15440 29157 14919 29157 14561 29157 15440 29158 14561 29158 14560 29158 14560 29159 14561 29159 14920 29159 14560 29160 14920 29160 12782 29160 12782 29161 14920 29161 14922 29161 12782 29162 14922 29162 14924 29162 14945 29163 14508 29163 14551 29163 14551 29164 14508 29164 14562 29164 14551 29165 14562 29165 14563 29165 14563 29166 14562 29166 14510 29166 14563 29167 14510 29167 14542 29167 14542 29168 14510 29168 14977 29168 14542 29169 14977 29169 14978 29169 14672 29170 14566 29170 13322 29170 14564 29171 14534 29171 14672 29171 14672 29172 14534 29172 14565 29172 14672 29173 14565 29173 14566 29173 14566 29174 14565 29174 13314 29174 14567 29175 14571 29175 14572 29175 14570 29176 12766 29176 14530 29176 14572 29177 14531 29177 14567 29177 14567 29178 14531 29178 14530 29178 14567 29179 14530 29179 14568 29179 14568 29180 14530 29180 12766 29180 14681 29181 14569 29181 14530 29181 14530 29182 14569 29182 15447 29182 14530 29183 15447 29183 14570 29183 14571 29184 12766 29184 14572 29184 14572 29185 12766 29185 12757 29185 14572 29186 12757 29186 14574 29186 12757 29187 14573 29187 14574 29187 14574 29188 14573 29188 14569 29188 14574 29189 14569 29189 14575 29189 14575 29190 14569 29190 14681 29190 14575 29191 14681 29191 13222 29191 13222 29192 14681 29192 13221 29192 13219 29193 14686 29193 13218 29193 13218 29194 14686 29194 14580 29194 13218 29195 14580 29195 13217 29195 15252 29196 15250 29196 14692 29196 14692 29197 15250 29197 14576 29197 14692 29198 14576 29198 15249 29198 14582 29199 15246 29199 13214 29199 13214 29200 15246 29200 14577 29200 13214 29201 14577 29201 14578 29201 14578 29202 14577 29202 15245 29202 14578 29203 15245 29203 13211 29203 13211 29204 15245 29204 15244 29204 15249 29205 14579 29205 14580 29205 14580 29206 14579 29206 15248 29206 14580 29207 15248 29207 14581 29207 13217 29208 14580 29208 13215 29208 13215 29209 14580 29209 14581 29209 13215 29210 14581 29210 14582 29210 14582 29211 14581 29211 15247 29211 14582 29212 15247 29212 15246 29212 13177 29213 14583 29213 14693 29213 14693 29214 14583 29214 14584 29214 14693 29215 14584 29215 13211 29215 13256 29216 13257 29216 14714 29216 14714 29217 13257 29217 13176 29217 14714 29218 13176 29218 13177 29218 14585 29219 15237 29219 14588 29219 15240 29220 14586 29220 14597 29220 14597 29221 14586 29221 14684 29221 14597 29222 14684 29222 14587 29222 14585 29223 14588 29223 14586 29223 15237 29224 15236 29224 14588 29224 14588 29225 15236 29225 14589 29225 14588 29226 14589 29226 14593 29226 14593 29227 14589 29227 14591 29227 14594 29228 13254 29228 14593 29228 14593 29229 13254 29229 14590 29229 14593 29230 14590 29230 14715 29230 14591 29231 14592 29231 14593 29231 14593 29232 14592 29232 14595 29232 14593 29233 14595 29233 14594 29233 14594 29234 14595 29234 14596 29234 14594 29235 14596 29235 13251 29235 13251 29236 14596 29236 15233 29236 13251 29237 15233 29237 14597 29237 14597 29238 15233 29238 15241 29238 14597 29239 15241 29239 15240 29239 14601 29240 14605 29240 15433 29240 15433 29241 14605 29241 14606 29241 13265 29242 13263 29242 12763 29242 12763 29243 13263 29243 14598 29243 12763 29244 14598 29244 14599 29244 14599 29245 14598 29245 13275 29245 14599 29246 13275 29246 14600 29246 14600 29247 13275 29247 14602 29247 14600 29248 14602 29248 12760 29248 12760 29249 14602 29249 14601 29249 14601 29250 14602 29250 14603 29250 14601 29251 14603 29251 14605 29251 13273 29252 12764 29252 13279 29252 13279 29253 12764 29253 13280 29253 12763 29254 14606 29254 13265 29254 13265 29255 14606 29255 14604 29255 13265 29256 14604 29256 13273 29256 13273 29257 14604 29257 12765 29257 13273 29258 12765 29258 12764 29258 14525 29259 13280 29259 14680 29259 14680 29260 13280 29260 12764 29260 14680 29261 12764 29261 14605 29261 14605 29262 12764 29262 15435 29262 14605 29263 15435 29263 14606 29263 14526 29264 14521 29264 14527 29264 14527 29265 14521 29265 14719 29265 14527 29266 14719 29266 13286 29266 13286 29267 14719 29267 14720 29267 13286 29268 14720 29268 13282 29268 13282 29269 14720 29269 13283 29269 13283 29270 14720 29270 14722 29270 13283 29271 14722 29271 14609 29271 14607 29272 14608 29272 14722 29272 14722 29273 14608 29273 14999 29273 14722 29274 14999 29274 14609 29274 14609 29275 14999 29275 14610 29275 14609 29276 14610 29276 14612 29276 14610 29277 14611 29277 14612 29277 14612 29278 14611 29278 15000 29278 14612 29279 15000 29279 14706 29279 14706 29280 15000 29280 14613 29280 14706 29281 14613 29281 15002 29281 15004 29282 14996 29282 14721 29282 14721 29283 14996 29283 14614 29283 14721 29284 14614 29284 14723 29284 14621 29285 14622 29285 14706 29285 14621 29286 14706 29286 14707 29286 14988 29287 14615 29287 14622 29287 14622 29288 14615 29288 14616 29288 14622 29289 14616 29289 13281 29289 14993 29290 14619 29290 14992 29290 14992 29291 14619 29291 13281 29291 14992 29292 13281 29292 14617 29292 14617 29293 13281 29293 14616 29293 14993 29294 14618 29294 14619 29294 14619 29295 14618 29295 14620 29295 14619 29296 14620 29296 14621 29296 14621 29297 14620 29297 14982 29297 14982 29298 14983 29298 14621 29298 14621 29299 14983 29299 14984 29299 14621 29300 14984 29300 14622 29300 14622 29301 14984 29301 14987 29301 14622 29302 14987 29302 14988 29302 14623 29303 14628 29303 14705 29303 14623 29304 14705 29304 14704 29304 14625 29305 14628 29305 14959 29305 14959 29306 14961 29306 14625 29306 14625 29307 14961 29307 14624 29307 14625 29308 14624 29308 14631 29308 14630 29309 14626 29309 14668 29309 14668 29310 14626 29310 14964 29310 14668 29311 14964 29311 14623 29311 14623 29312 14964 29312 14627 29312 14623 29313 14627 29313 14954 29313 14954 29314 14956 29314 14623 29314 14623 29315 14956 29315 14957 29315 14623 29316 14957 29316 14628 29316 14628 29317 14957 29317 14958 29317 14628 29318 14958 29318 14959 29318 14637 29319 14937 29319 14633 29319 14624 29320 14629 29320 14631 29320 14631 29321 14629 29321 14630 29321 14631 29322 14630 29322 14632 29322 14632 29323 14630 29323 14668 29323 14632 29324 14668 29324 13302 29324 14633 29325 14940 29325 14669 29325 14927 29326 14634 29326 14668 29326 14668 29327 14634 29327 14931 29327 14668 29328 14931 29328 13302 29328 13302 29329 14931 29329 14933 29329 13302 29330 14933 29330 19250 29330 19250 29331 14933 29331 14934 29331 19250 29332 14934 29332 14637 29332 14637 29333 14934 29333 14936 29333 14637 29334 14936 29334 14937 29334 14940 29335 14941 29335 14669 29335 14669 29336 14941 29336 14942 29336 14669 29337 14942 29337 14668 29337 14668 29338 14942 29338 14635 29338 14668 29339 14635 29339 14927 29339 14633 29340 14669 29340 14637 29340 14637 29341 14669 29341 14636 29341 14637 29342 14636 29342 12812 29342 14552 29343 14548 29343 14638 29343 14638 29344 14548 29344 14557 29344 14638 29345 14557 29345 14639 29345 14639 29346 14557 29346 14559 29346 14639 29347 14559 29347 14640 29347 14640 29348 14559 29348 15440 29348 14640 29349 15440 29349 14641 29349 14642 29350 14510 29350 14643 29350 14643 29351 14510 29351 14562 29351 14643 29352 14562 29352 14554 29352 14554 29353 14562 29353 14948 29353 14554 29354 14948 29354 14555 29354 14974 29355 14643 29355 14545 29355 14545 29356 14643 29356 14554 29356 14545 29357 14554 29357 14644 29357 14644 29358 14554 29358 14638 29358 14644 29359 14638 29359 14645 29359 14645 29360 14638 29360 14639 29360 14645 29361 14639 29361 14650 29361 14650 29362 14639 29362 14640 29362 14650 29363 14640 29363 14652 29363 14652 29364 14640 29364 14641 29364 14652 29365 14641 29365 15445 29365 14646 29366 14543 29366 14647 29366 14647 29367 14543 29367 14545 29367 14647 29368 14545 29368 14675 29368 14675 29369 14545 29369 14644 29369 14675 29370 14644 29370 14648 29370 14648 29371 14644 29371 14645 29371 14648 29372 14645 29372 14649 29372 14649 29373 14645 29373 14650 29373 14649 29374 14650 29374 14651 29374 14651 29375 14650 29375 14652 29375 14651 29376 14652 29376 14653 29376 14653 29377 14652 29377 15445 29377 14653 29378 15445 29378 15444 29378 14654 29379 14655 29379 14666 29379 14666 29380 14655 29380 14674 29380 14666 29381 14674 29381 14656 29381 14656 29382 14674 29382 14676 29382 14656 29383 14676 29383 14657 29383 14657 29384 14676 29384 14658 29384 14657 29385 14658 29385 14659 29385 14659 29386 14658 29386 14677 29386 14659 29387 14677 29387 14660 29387 14660 29388 14677 29388 14661 29388 14660 29389 14661 29389 14663 29389 14663 29390 14661 29390 14662 29390 14663 29391 14662 29391 14664 29391 14664 29392 14662 29392 14678 29392 14664 29393 14678 29393 15446 29393 14665 29394 14666 29394 14702 29394 14702 29395 14666 29395 14656 29395 14702 29396 14656 29396 14667 29396 14667 29397 14656 29397 14657 29397 14667 29398 14657 29398 14703 29398 14703 29399 14657 29399 14659 29399 14703 29400 14659 29400 14704 29400 14704 29401 14659 29401 14660 29401 14704 29402 14660 29402 14623 29402 14623 29403 14660 29403 14663 29403 14623 29404 14663 29404 14668 29404 14668 29405 14663 29405 14664 29405 14668 29406 14664 29406 14669 29406 14669 29407 14664 29407 15446 29407 14669 29408 15446 29408 14636 29408 15013 29409 15005 29409 13319 29409 13319 29410 15005 29410 14670 29410 13319 29411 14670 29411 13321 29411 13321 29412 14670 29412 14671 29412 13321 29413 14671 29413 13322 29413 13322 29414 14671 29414 14538 29414 13322 29415 14538 29415 14672 29415 14672 29416 14538 29416 14673 29416 14672 29417 14673 29417 15258 29417 15258 29418 14673 29418 14514 29418 14513 29419 14673 29419 14520 29419 14520 29420 14673 29420 14536 29420 14520 29421 14536 29421 14655 29421 14655 29422 14536 29422 14647 29422 14655 29423 14647 29423 14674 29423 14674 29424 14647 29424 14675 29424 14674 29425 14675 29425 14676 29425 14676 29426 14675 29426 14648 29426 14676 29427 14648 29427 14658 29427 14658 29428 14648 29428 14649 29428 14658 29429 14649 29429 14677 29429 14677 29430 14649 29430 14651 29430 14677 29431 14651 29431 14661 29431 14661 29432 14651 29432 14653 29432 14661 29433 14653 29433 14662 29433 14662 29434 14653 29434 15444 29434 14662 29435 15444 29435 14678 29435 14587 29436 14684 29436 14603 29436 14603 29437 14684 29437 14685 29437 14603 29438 14685 29438 14605 29438 14605 29439 14685 29439 14679 29439 14605 29440 14679 29440 14680 29440 14680 29441 14679 29441 15223 29441 14680 29442 15223 29442 15222 29442 13219 29443 14681 29443 14686 29443 14686 29444 14681 29444 14530 29444 14686 29445 14530 29445 14529 29445 14529 29446 14530 29446 14682 29446 14529 29447 14682 29447 14683 29447 14586 29448 14588 29448 14684 29448 14684 29449 14588 29449 14717 29449 14684 29450 14717 29450 14685 29450 14685 29451 14717 29451 14718 29451 14685 29452 14718 29452 14679 29452 14679 29453 14718 29453 15224 29453 14679 29454 15224 29454 15223 29454 15249 29455 14580 29455 14692 29455 14692 29456 14580 29456 14686 29456 14692 29457 14686 29457 14687 29457 14687 29458 14686 29458 14529 29458 14687 29459 14529 29459 14689 29459 14689 29460 14529 29460 14688 29460 14689 29461 14688 29461 14690 29461 14690 29462 14688 29462 14520 29462 14690 29463 14520 29463 14691 29463 14691 29464 14520 29464 14518 29464 14691 29465 14518 29465 14795 29465 15244 29466 15252 29466 13211 29466 13211 29467 15252 29467 14692 29467 13211 29468 14692 29468 14693 29468 14693 29469 14692 29469 14687 29469 14693 29470 14687 29470 14696 29470 14696 29471 14687 29471 14689 29471 14696 29472 14689 29472 14694 29472 14694 29473 14689 29473 14690 29473 14694 29474 14690 29474 14699 29474 14699 29475 14690 29475 14691 29475 14699 29476 14691 29476 14701 29476 14701 29477 14691 29477 14515 29477 14701 29478 14515 29478 14695 29478 13177 29479 14693 29479 14714 29479 14714 29480 14693 29480 14696 29480 14714 29481 14696 29481 14697 29481 14697 29482 14696 29482 14694 29482 14697 29483 14694 29483 14698 29483 14698 29484 14694 29484 14699 29484 14698 29485 14699 29485 14711 29485 14711 29486 14699 29486 14701 29486 14711 29487 14701 29487 14700 29487 14700 29488 14701 29488 14702 29488 14700 29489 14702 29489 14709 29489 14709 29490 14702 29490 14667 29490 14709 29491 14667 29491 14707 29491 14707 29492 14667 29492 14703 29492 14707 29493 14703 29493 14621 29493 14621 29494 14703 29494 14704 29494 14621 29495 14704 29495 14619 29495 14619 29496 14704 29496 14705 29496 14619 29497 14705 29497 13281 29497 15002 29498 15004 29498 14706 29498 14706 29499 15004 29499 14721 29499 14706 29500 14721 29500 14707 29500 14707 29501 14721 29501 14708 29501 14707 29502 14708 29502 14709 29502 14709 29503 14708 29503 14710 29503 14709 29504 14710 29504 14700 29504 14700 29505 14710 29505 14712 29505 14700 29506 14712 29506 14711 29506 14711 29507 14712 29507 14713 29507 14711 29508 14713 29508 14698 29508 14698 29509 14713 29509 14716 29509 14698 29510 14716 29510 14697 29510 14697 29511 14716 29511 19442 29511 14697 29512 19442 29512 14714 29512 13256 29513 14714 29513 14715 29513 14715 29514 14714 29514 19442 29514 14715 29515 19442 29515 14593 29515 14593 29516 19442 29516 14716 29516 14593 29517 14716 29517 14588 29517 14588 29518 14716 29518 14713 29518 14588 29519 14713 29519 14717 29519 14717 29520 14713 29520 14712 29520 14717 29521 14712 29521 14718 29521 14718 29522 14712 29522 14710 29522 14718 29523 14710 29523 14719 29523 14719 29524 14710 29524 14708 29524 14719 29525 14708 29525 14720 29525 14720 29526 14708 29526 14721 29526 14720 29527 14721 29527 14722 29527 14722 29528 14721 29528 14723 29528 14722 29529 14723 29529 14607 29529 13385 29530 13875 29530 14724 29530 13385 29531 14724 29531 13386 29531 13386 29532 14724 29532 13880 29532 13386 29533 13880 29533 13362 29533 13880 29534 14725 29534 13362 29534 13362 29535 14725 29535 13879 29535 13362 29536 13879 29536 14726 29536 13879 29537 14727 29537 14726 29537 14726 29538 14727 29538 14728 29538 14726 29539 14728 29539 13363 29539 13363 29540 14728 29540 14729 29540 13363 29541 14729 29541 14730 29541 14730 29542 14729 29542 14731 29542 14730 29543 14731 29543 13395 29543 13395 29544 14731 29544 13414 29544 14731 29545 13883 29545 13414 29545 13414 29546 13883 29546 14733 29546 13414 29547 14733 29547 14732 29547 14732 29548 14733 29548 14735 29548 14732 29549 14735 29549 14734 29549 14734 29550 14735 29550 13397 29550 13397 29551 14735 29551 13885 29551 13397 29552 13885 29552 14737 29552 13885 29553 13886 29553 14737 29553 14737 29554 13886 29554 14736 29554 14737 29555 14736 29555 13418 29555 13418 29556 14736 29556 14739 29556 13418 29557 14739 29557 14738 29557 14738 29558 14739 29558 13424 29558 13424 29559 14739 29559 14740 29559 13424 29560 14740 29560 13427 29560 13427 29561 14740 29561 14741 29561 13427 29562 14741 29562 14742 29562 14742 29563 14741 29563 14743 29563 14742 29564 14743 29564 13438 29564 13438 29565 14743 29565 13891 29565 13438 29566 13891 29566 14744 29566 14744 29567 13891 29567 13894 29567 14744 29568 13894 29568 13431 29568 13894 29569 13893 29569 13431 29569 13431 29570 13893 29570 14745 29570 13431 29571 14745 29571 14746 29571 14746 29572 14745 29572 13896 29572 14746 29573 13896 29573 13450 29573 13896 29574 13895 29574 13450 29574 13450 29575 13895 29575 14747 29575 13450 29576 14747 29576 14748 29576 14748 29577 14747 29577 13898 29577 14748 29578 13898 29578 14750 29578 13898 29579 14749 29579 14750 29579 14750 29580 14749 29580 14751 29580 14750 29581 14751 29581 13448 29581 13448 29582 14751 29582 14752 29582 13448 29583 14752 29583 13447 29583 14752 29584 13899 29584 13447 29584 13447 29585 13899 29585 14753 29585 13447 29586 14753 29586 13459 29586 13459 29587 14753 29587 14754 29587 13459 29588 14754 29588 13460 29588 13460 29589 14754 29589 13901 29589 13460 29590 13901 29590 13461 29590 13901 29591 14755 29591 13461 29591 13461 29592 14755 29592 14756 29592 13461 29593 14756 29593 14757 29593 14757 29594 14756 29594 14758 29594 14757 29595 14758 29595 13462 29595 13462 29596 14758 29596 13905 29596 13462 29597 13905 29597 14759 29597 14759 29598 13905 29598 14760 29598 14759 29599 14760 29599 13478 29599 13478 29600 14760 29600 13909 29600 13478 29601 13909 29601 14762 29601 14762 29602 13909 29602 14761 29602 14762 29603 14761 29603 13353 29603 13353 29604 14761 29604 13354 29604 13350 29605 12846 29605 13351 29605 13351 29606 12846 29606 14763 29606 14763 29607 12846 29607 13352 29607 13352 29608 12846 29608 12842 29608 13352 29609 12842 29609 14764 29609 14764 29610 12842 29610 12820 29610 14764 29611 12820 29611 13343 29611 12819 29612 15443 29612 12820 29612 12820 29613 15443 29613 13344 29613 12820 29614 13344 29614 13343 29614 15077 29615 14765 29615 15078 29615 15078 29616 14765 29616 15324 29616 15078 29617 15324 29617 14766 29617 14766 29618 15324 29618 14768 29618 14766 29619 14768 29619 14767 29619 14767 29620 14768 29620 15337 29620 14767 29621 15337 29621 14769 29621 14769 29622 15337 29622 14770 29622 14769 29623 14770 29623 14771 29623 14771 29624 14770 29624 15335 29624 14771 29625 15335 29625 14772 29625 14772 29626 15335 29626 15334 29626 14772 29627 15334 29627 15083 29627 15083 29628 15334 29628 15331 29628 15083 29629 15331 29629 14773 29629 14773 29630 15331 29630 15330 29630 14773 29631 15330 29631 15074 29631 15074 29632 15330 29632 15328 29632 15074 29633 15328 29633 15076 29633 15076 29634 15328 29634 14774 29634 15076 29635 14774 29635 14775 29635 14775 29636 14774 29636 15327 29636 14775 29637 15327 29637 15077 29637 15077 29638 15327 29638 14765 29638 13489 29639 14783 29639 14776 29639 13871 29640 13491 29640 14776 29640 14776 29641 13491 29641 14777 29641 14777 29642 14778 29642 14776 29642 14776 29643 14778 29643 14779 29643 14776 29644 14779 29644 14780 29644 14780 29645 14781 29645 14776 29645 14776 29646 14781 29646 14782 29646 14776 29647 14782 29647 13489 29647 14783 29648 14784 29648 14786 29648 14788 29649 14787 29649 14785 29649 14785 29650 14787 29650 12791 29650 14784 29651 12791 29651 14786 29651 14786 29652 12791 29652 14787 29652 14786 29653 14787 29653 13330 29653 13330 29654 14787 29654 14788 29654 13330 29655 14788 29655 14789 29655 14786 29656 14069 29656 14068 29656 14783 29657 14786 29657 14776 29657 14776 29658 14786 29658 14068 29658 14776 29659 14068 29659 14790 29659 14791 29660 14792 29660 14517 29660 14517 29661 14792 29661 14793 29661 14517 29662 14793 29662 14518 29662 14518 29663 14793 29663 14794 29663 14518 29664 14794 29664 14795 29664 14795 29665 14794 29665 14796 29665 14795 29666 14796 29666 14515 29666 14515 29667 14796 29667 14797 29667 14515 29668 14797 29668 14695 29668 14695 29669 14797 29669 15424 29669 14695 29670 15424 29670 14516 29670 14516 29671 15424 29671 14798 29671 14516 29672 14798 29672 14665 29672 14665 29673 14798 29673 14799 29673 14665 29674 14799 29674 14800 29674 14800 29675 14799 29675 14801 29675 14800 29676 14801 29676 14654 29676 14654 29677 14801 29677 15428 29677 14654 29678 15428 29678 14803 29678 14803 29679 15428 29679 14802 29679 14803 29680 14802 29680 14519 29680 14519 29681 14802 29681 15430 29681 14519 29682 15430 29682 14791 29682 14791 29683 15430 29683 14792 29683 15400 29684 14804 29684 14807 29684 14807 29685 14804 29685 14827 29685 14807 29686 14827 29686 13843 29686 14805 29687 15404 29687 13841 29687 13841 29688 15404 29688 14806 29688 13841 29689 14806 29689 14807 29689 14807 29690 14806 29690 15401 29690 14807 29691 15401 29691 15400 29691 14808 29692 15405 29692 14809 29692 14809 29693 15405 29693 14810 29693 14809 29694 14810 29694 14805 29694 14805 29695 14810 29695 14811 29695 14805 29696 14811 29696 15404 29696 14812 29697 14813 29697 15398 29697 14812 29698 15398 29698 14809 29698 14809 29699 15398 29699 14814 29699 14809 29700 14814 29700 14808 29700 14813 29701 14812 29701 14815 29701 14815 29702 14812 29702 13838 29702 14815 29703 13838 29703 14816 29703 14816 29704 13838 29704 15423 29704 15423 29705 13838 29705 14817 29705 15423 29706 14817 29706 12869 29706 12848 29707 14818 29707 14820 29707 14820 29708 14818 29708 14819 29708 14820 29709 14819 29709 14817 29709 14817 29710 14819 29710 12871 29710 14817 29711 12871 29711 12869 29711 14822 29712 14823 29712 14820 29712 14820 29713 14823 29713 14821 29713 14820 29714 14821 29714 12848 29714 14824 29715 12865 29715 14825 29715 14825 29716 12865 29716 12879 29716 14825 29717 12879 29717 14822 29717 14822 29718 12879 29718 12877 29718 14822 29719 12877 29719 14823 29719 14824 29720 14825 29720 14826 29720 14826 29721 14825 29721 13845 29721 14826 29722 13845 29722 12864 29722 14827 29723 14828 29723 13843 29723 13843 29724 14828 29724 14829 29724 13843 29725 14829 29725 13845 29725 13845 29726 14829 29726 12863 29726 13845 29727 12863 29727 12864 29727 13798 29728 13796 29728 13786 29728 13786 29729 13796 29729 14844 29729 14833 29730 14834 29730 14830 29730 13800 29731 14832 29731 14831 29731 14831 29732 14832 29732 13774 29732 14831 29733 13774 29733 13047 29733 13047 29734 13774 29734 14833 29734 13047 29735 14833 29735 13045 29735 13045 29736 14833 29736 14830 29736 14834 29737 14833 29737 14835 29737 14835 29738 14833 29738 14836 29738 14835 29739 14836 29739 13052 29739 13037 29740 13054 29740 14836 29740 14836 29741 13054 29741 14837 29741 14836 29742 14837 29742 13052 29742 14838 29743 14840 29743 14839 29743 14839 29744 14840 29744 14841 29744 14841 29745 13043 29745 14839 29745 14839 29746 13043 29746 14842 29746 14839 29747 14842 29747 14836 29747 14836 29748 14842 29748 14843 29748 14836 29749 14843 29749 13037 29749 14844 29750 14845 29750 13786 29750 13786 29751 14845 29751 13041 29751 13786 29752 13041 29752 14838 29752 14838 29753 13041 29753 14846 29753 14838 29754 14846 29754 14840 29754 14847 29755 13768 29755 14849 29755 14849 29756 13768 29756 14848 29756 14849 29757 14848 29757 13130 29757 13130 29758 14848 29758 13767 29758 14850 29759 14851 29759 14853 29759 14853 29760 14851 29760 13127 29760 14853 29761 13127 29761 13767 29761 13767 29762 13127 29762 14852 29762 13767 29763 14852 29763 13130 29763 14850 29764 14853 29764 14854 29764 14854 29765 14853 29765 14855 29765 14854 29766 14855 29766 13105 29766 13105 29767 14855 29767 13106 29767 13106 29768 14855 29768 13766 29768 13106 29769 13766 29769 13108 29769 13772 29770 14857 29770 14856 29770 14856 29771 14857 29771 13103 29771 14856 29772 13103 29772 13766 29772 13766 29773 13103 29773 13109 29773 13766 29774 13109 29774 13108 29774 14858 29775 14859 29775 14860 29775 14860 29776 14859 29776 15260 29776 14860 29777 15260 29777 14861 29777 14861 29778 15260 29778 14862 29778 14861 29779 14862 29779 14863 29779 14863 29780 14862 29780 14864 29780 14863 29781 14864 29781 14865 29781 14865 29782 14864 29782 15253 29782 14865 29783 15253 29783 14866 29783 14866 29784 15253 29784 14867 29784 14866 29785 14867 29785 13689 29785 13689 29786 14867 29786 14868 29786 13689 29787 14868 29787 13690 29787 13690 29788 14868 29788 15255 29788 13690 29789 15255 29789 13686 29789 13686 29790 15255 29790 14870 29790 13686 29791 14870 29791 14869 29791 14869 29792 14870 29792 15257 29792 14869 29793 15257 29793 14871 29793 14871 29794 15257 29794 15259 29794 14871 29795 15259 29795 14872 29795 14872 29796 15259 29796 14873 29796 14872 29797 14873 29797 14858 29797 14858 29798 14873 29798 14859 29798 14886 29799 14874 29799 13682 29799 13682 29800 14874 29800 14875 29800 13682 29801 14875 29801 13683 29801 13683 29802 14875 29802 15221 29802 13683 29803 15221 29803 14876 29803 14876 29804 15221 29804 14877 29804 14876 29805 14877 29805 13685 29805 13685 29806 14877 29806 14878 29806 13685 29807 14878 29807 14879 29807 14879 29808 14878 29808 14880 29808 14879 29809 14880 29809 14881 29809 14881 29810 14880 29810 15226 29810 14881 29811 15226 29811 13675 29811 13675 29812 15226 29812 14882 29812 13675 29813 14882 29813 13677 29813 13677 29814 14882 29814 15228 29814 13677 29815 15228 29815 13679 29815 13679 29816 15228 29816 15229 29816 13679 29817 15229 29817 14883 29817 14883 29818 15229 29818 14885 29818 14883 29819 14885 29819 14884 29819 14884 29820 14885 29820 15230 29820 14884 29821 15230 29821 14886 29821 14886 29822 15230 29822 14874 29822 14897 29823 15242 29823 13667 29823 13667 29824 15242 29824 15243 29824 13667 29825 15243 29825 13669 29825 13669 29826 15243 29826 14887 29826 13669 29827 14887 29827 13671 29827 13671 29828 14887 29828 15234 29828 13671 29829 15234 29829 14889 29829 14889 29830 15234 29830 14888 29830 14889 29831 14888 29831 13659 29831 13659 29832 14888 29832 14890 29832 13659 29833 14890 29833 13660 29833 13660 29834 14890 29834 15235 29834 13660 29835 15235 29835 14891 29835 14891 29836 15235 29836 14892 29836 14891 29837 14892 29837 13663 29837 13663 29838 14892 29838 14894 29838 13663 29839 14894 29839 14893 29839 14893 29840 14894 29840 14895 29840 14893 29841 14895 29841 14896 29841 14896 29842 14895 29842 15238 29842 14896 29843 15238 29843 13666 29843 13666 29844 15238 29844 15239 29844 13666 29845 15239 29845 14897 29845 14897 29846 15239 29846 15242 29846 13655 29847 15251 29847 14898 29847 14898 29848 15251 29848 14899 29848 14898 29849 14899 29849 14900 29849 14900 29850 14899 29850 14901 29850 14900 29851 14901 29851 13657 29851 13657 29852 14901 29852 14902 29852 13657 29853 14902 29853 13644 29853 13644 29854 14902 29854 14903 29854 13644 29855 14903 29855 13646 29855 13646 29856 14903 29856 14904 29856 13646 29857 14904 29857 14905 29857 14905 29858 14904 29858 14906 29858 14905 29859 14906 29859 13647 29859 13647 29860 14906 29860 14907 29860 13647 29861 14907 29861 13649 29861 13649 29862 14907 29862 14908 29862 13649 29863 14908 29863 13650 29863 13650 29864 14908 29864 14909 29864 13650 29865 14909 29865 13651 29865 13651 29866 14909 29866 14910 29866 13651 29867 14910 29867 13652 29867 13652 29868 14910 29868 14911 29868 13652 29869 14911 29869 13655 29869 13655 29870 14911 29870 15251 29870 14926 29871 14912 29871 14913 29871 14913 29872 14912 29872 15352 29872 14913 29873 15352 29873 14556 29873 14556 29874 15352 29874 14914 29874 14556 29875 14914 29875 14915 29875 14915 29876 14914 29876 15356 29876 14915 29877 15356 29877 14916 29877 14916 29878 15356 29878 15358 29878 14916 29879 15358 29879 14558 29879 14558 29880 15358 29880 15359 29880 14558 29881 15359 29881 14918 29881 14918 29882 15359 29882 14917 29882 14918 29883 14917 29883 14919 29883 14919 29884 14917 29884 15361 29884 14919 29885 15361 29885 14561 29885 14561 29886 15361 29886 15363 29886 14561 29887 15363 29887 14920 29887 14920 29888 15363 29888 14921 29888 14920 29889 14921 29889 14922 29889 14922 29890 14921 29890 14923 29890 14922 29891 14923 29891 14924 29891 14924 29892 14923 29892 14925 29892 14924 29893 14925 29893 14926 29893 14926 29894 14925 29894 14912 29894 14942 29895 15341 29895 14635 29895 14635 29896 15341 29896 14928 29896 14635 29897 14928 29897 14927 29897 14927 29898 14928 29898 14929 29898 14927 29899 14929 29899 14634 29899 14634 29900 14929 29900 14930 29900 14634 29901 14930 29901 14931 29901 14931 29902 14930 29902 15344 29902 14931 29903 15344 29903 14933 29903 14933 29904 15344 29904 14932 29904 14933 29905 14932 29905 14934 29905 14934 29906 14932 29906 14935 29906 14934 29907 14935 29907 14936 29907 14936 29908 14935 29908 14938 29908 14936 29909 14938 29909 14937 29909 14937 29910 14938 29910 15347 29910 14937 29911 15347 29911 14633 29911 14633 29912 15347 29912 14939 29912 14633 29913 14939 29913 14940 29913 14940 29914 14939 29914 15349 29914 14940 29915 15349 29915 14941 29915 14941 29916 15349 29916 15339 29916 14941 29917 15339 29917 14942 29917 14942 29918 15339 29918 15341 29918 14953 29919 15325 29919 14943 29919 14943 29920 15325 29920 14944 29920 14943 29921 14944 29921 14945 29921 14945 29922 14944 29922 15326 29922 14945 29923 15326 29923 14508 29923 14508 29924 15326 29924 14946 29924 14508 29925 14946 29925 14948 29925 14948 29926 14946 29926 14947 29926 14948 29927 14947 29927 14555 29927 14555 29928 14947 29928 15329 29928 14555 29929 15329 29929 14553 29929 14553 29930 15329 29930 15332 29930 14553 29931 15332 29931 14552 29931 14552 29932 15332 29932 14950 29932 14552 29933 14950 29933 14949 29933 14949 29934 14950 29934 15333 29934 14949 29935 15333 29935 14549 29935 14549 29936 15333 29936 14951 29936 14549 29937 14951 29937 14952 29937 14952 29938 14951 29938 15336 29938 14952 29939 15336 29939 14550 29939 14550 29940 15336 29940 15338 29940 14550 29941 15338 29941 14953 29941 14953 29942 15338 29942 15325 29942 14627 29943 14965 29943 14954 29943 14954 29944 14965 29944 14955 29944 14954 29945 14955 29945 14956 29945 14956 29946 14955 29946 15312 29946 14956 29947 15312 29947 14957 29947 14957 29948 15312 29948 15315 29948 14957 29949 15315 29949 14958 29949 14958 29950 15315 29950 15317 29950 14958 29951 15317 29951 14959 29951 14959 29952 15317 29952 14960 29952 14959 29953 14960 29953 14961 29953 14961 29954 14960 29954 15318 29954 14961 29955 15318 29955 14624 29955 14624 29956 15318 29956 14962 29956 14624 29957 14962 29957 14629 29957 14629 29958 14962 29958 15321 29958 14629 29959 15321 29959 14630 29959 14630 29960 15321 29960 14963 29960 14630 29961 14963 29961 14626 29961 14626 29962 14963 29962 15322 29962 14626 29963 15322 29963 14964 29963 14964 29964 15322 29964 15323 29964 14964 29965 15323 29965 14627 29965 14627 29966 15323 29966 14965 29966 14980 29967 15292 29967 14541 29967 14541 29968 15292 29968 14966 29968 14541 29969 14966 29969 14967 29969 14967 29970 14966 29970 14968 29970 14967 29971 14968 29971 14511 29971 14511 29972 14968 29972 14969 29972 14511 29973 14969 29973 14544 29973 14544 29974 14969 29974 15295 29974 14544 29975 15295 29975 14970 29975 14970 29976 15295 29976 14971 29976 14970 29977 14971 29977 14972 29977 14972 29978 14971 29978 14973 29978 14972 29979 14973 29979 14974 29979 14974 29980 14973 29980 15298 29980 14974 29981 15298 29981 14642 29981 14642 29982 15298 29982 14975 29982 14642 29983 14975 29983 14509 29983 14509 29984 14975 29984 14976 29984 14509 29985 14976 29985 14977 29985 14977 29986 14976 29986 15301 29986 14977 29987 15301 29987 14978 29987 14978 29988 15301 29988 14979 29988 14978 29989 14979 29989 14980 29989 14980 29990 14979 29990 15292 29990 14620 29991 15303 29991 14982 29991 14982 29992 15303 29992 14981 29992 14982 29993 14981 29993 14983 29993 14983 29994 14981 29994 15305 29994 14983 29995 15305 29995 14984 29995 14984 29996 15305 29996 14985 29996 14984 29997 14985 29997 14987 29997 14987 29998 14985 29998 14986 29998 14987 29999 14986 29999 14988 29999 14988 30000 14986 30000 14989 30000 14988 30001 14989 30001 14615 30001 14615 30002 14989 30002 14990 30002 14615 30003 14990 30003 14616 30003 14616 30004 14990 30004 15307 30004 14616 30005 15307 30005 14617 30005 14617 30006 15307 30006 14991 30006 14617 30007 14991 30007 14992 30007 14992 30008 14991 30008 15309 30008 14992 30009 15309 30009 14993 30009 14993 30010 15309 30010 14994 30010 14993 30011 14994 30011 14618 30011 14618 30012 14994 30012 15310 30012 14618 30013 15310 30013 14620 30013 14620 30014 15310 30014 15303 30014 15004 30015 14995 30015 14996 30015 14996 30016 14995 30016 15261 30016 14996 30017 15261 30017 14614 30017 14614 30018 15261 30018 14997 30018 14614 30019 14997 30019 14723 30019 14723 30020 14997 30020 15264 30020 14723 30021 15264 30021 14607 30021 14607 30022 15264 30022 14998 30022 14607 30023 14998 30023 14608 30023 14608 30024 14998 30024 15266 30024 14608 30025 15266 30025 14999 30025 14999 30026 15266 30026 15267 30026 14999 30027 15267 30027 14610 30027 14610 30028 15267 30028 15270 30028 14610 30029 15270 30029 14611 30029 14611 30030 15270 30030 15272 30030 14611 30031 15272 30031 15000 30031 15000 30032 15272 30032 15273 30032 15000 30033 15273 30033 14613 30033 14613 30034 15273 30034 15001 30034 14613 30035 15001 30035 15002 30035 15002 30036 15001 30036 15003 30036 15002 30037 15003 30037 15004 30037 15004 30038 15003 30038 14995 30038 15013 30039 15278 30039 15005 30039 15005 30040 15278 30040 15279 30040 15005 30041 15279 30041 14670 30041 14670 30042 15279 30042 15281 30042 14670 30043 15281 30043 15006 30043 15006 30044 15281 30044 15283 30044 15006 30045 15283 30045 15007 30045 15007 30046 15283 30046 15008 30046 15007 30047 15008 30047 15009 30047 15009 30048 15008 30048 15284 30048 15009 30049 15284 30049 14537 30049 14537 30050 15284 30050 15287 30050 14537 30051 15287 30051 15010 30051 15010 30052 15287 30052 15011 30052 15010 30053 15011 30053 14646 30053 14646 30054 15011 30054 15012 30054 14646 30055 15012 30055 14546 30055 14546 30056 15012 30056 15290 30056 14546 30057 15290 30057 14540 30057 14540 30058 15290 30058 15291 30058 14540 30059 15291 30059 14535 30059 14535 30060 15291 30060 15277 30060 14535 30061 15277 30061 15013 30061 15013 30062 15277 30062 15278 30062 15016 30063 15014 30063 15015 30063 15032 30064 15014 30064 15016 30064 15016 30065 15020 30065 15022 30065 15018 30066 15020 30066 15016 30066 15015 30067 15018 30067 15016 30067 15016 30068 15017 30068 15026 30068 15024 30069 15017 30069 15016 30069 15022 30070 15024 30070 15016 30070 15016 30071 15029 30071 15030 30071 15027 30072 15029 30072 15016 30072 15026 30073 15027 30073 15016 30073 15030 30074 15032 30074 15016 30074 15032 30075 13624 30075 15014 30075 15014 30076 13624 30076 13626 30076 15014 30077 13626 30077 15015 30077 15015 30078 13626 30078 13628 30078 15015 30079 13628 30079 15018 30079 15018 30080 13628 30080 15019 30080 15018 30081 15019 30081 15020 30081 15020 30082 15019 30082 15021 30082 15020 30083 15021 30083 15022 30083 15022 30084 15021 30084 15023 30084 15022 30085 15023 30085 15024 30085 15024 30086 15023 30086 15025 30086 15024 30087 15025 30087 15017 30087 15017 30088 15025 30088 13620 30088 15017 30089 13620 30089 15026 30089 15026 30090 13620 30090 13621 30090 15026 30091 13621 30091 15027 30091 15027 30092 13621 30092 15028 30092 15027 30093 15028 30093 15029 30093 15029 30094 15028 30094 13623 30094 15029 30095 13623 30095 15030 30095 15030 30096 13623 30096 15031 30096 15030 30097 15031 30097 15032 30097 15032 30098 15031 30098 13624 30098 15035 30099 15039 30099 15034 30099 15038 30100 15039 30100 15035 30100 15035 30101 15040 30101 15041 30101 15033 30102 15040 30102 15035 30102 15034 30103 15033 30103 15035 30103 15035 30104 15043 30104 15037 30104 15042 30105 15043 30105 15035 30105 15041 30106 15042 30106 15035 30106 15035 30107 15044 30107 15046 30107 15036 30108 15044 30108 15035 30108 15037 30109 15036 30109 15035 30109 15046 30110 15038 30110 15035 30110 15038 30111 13633 30111 15039 30111 15039 30112 13633 30112 13634 30112 15039 30113 13634 30113 15034 30113 15034 30114 13634 30114 13635 30114 15034 30115 13635 30115 15033 30115 15033 30116 13635 30116 13636 30116 15033 30117 13636 30117 15040 30117 15040 30118 13636 30118 13637 30118 15040 30119 13637 30119 15041 30119 15041 30120 13637 30120 13639 30120 15041 30121 13639 30121 15042 30121 15042 30122 13639 30122 13641 30122 15042 30123 13641 30123 15043 30123 15043 30124 13641 30124 13642 30124 15043 30125 13642 30125 15037 30125 15037 30126 13642 30126 13630 30126 15037 30127 13630 30127 15036 30127 15036 30128 13630 30128 13632 30128 15036 30129 13632 30129 15044 30129 15044 30130 13632 30130 15045 30130 15044 30131 15045 30131 15046 30131 15046 30132 15045 30132 15047 30132 15046 30133 15047 30133 15038 30133 15038 30134 15047 30134 13633 30134 15052 30135 15048 30135 15054 30135 15053 30136 15048 30136 15052 30136 15052 30137 15059 30137 15060 30137 15057 30138 15059 30138 15052 30138 15054 30139 15057 30139 15052 30139 15052 30140 15062 30140 15064 30140 15049 30141 15062 30141 15052 30141 15060 30142 15049 30142 15052 30142 15052 30143 15051 30143 15050 30143 15065 30144 15051 30144 15052 30144 15064 30145 15065 30145 15052 30145 15050 30146 15053 30146 15052 30146 15053 30147 13616 30147 15048 30147 15048 30148 13616 30148 15055 30148 15048 30149 15055 30149 15054 30149 15054 30150 15055 30150 15056 30150 15054 30151 15056 30151 15057 30151 15057 30152 15056 30152 15058 30152 15057 30153 15058 30153 15059 30153 15059 30154 15058 30154 13619 30154 15059 30155 13619 30155 15060 30155 15060 30156 13619 30156 13608 30156 15060 30157 13608 30157 15049 30157 15049 30158 13608 30158 13610 30158 15049 30159 13610 30159 15062 30159 15062 30160 13610 30160 15061 30160 15062 30161 15061 30161 15064 30161 15064 30162 15061 30162 15063 30162 15064 30163 15063 30163 15065 30163 15065 30164 15063 30164 13614 30164 15065 30165 13614 30165 15051 30165 15051 30166 13614 30166 15066 30166 15051 30167 15066 30167 15050 30167 15050 30168 15066 30168 13615 30168 15050 30169 13615 30169 15053 30169 15053 30170 13615 30170 13616 30170 15068 30171 15067 30171 15075 30171 15084 30172 15067 30172 15068 30172 15068 30173 15069 30173 15079 30173 15070 30174 15069 30174 15068 30174 15075 30175 15070 30175 15068 30175 15068 30176 15072 30176 15071 30176 15080 30177 15072 30177 15068 30177 15079 30178 15080 30178 15068 30178 15068 30179 15082 30179 15073 30179 15081 30180 15082 30180 15068 30180 15071 30181 15081 30181 15068 30181 15073 30182 15084 30182 15068 30182 15084 30183 15074 30183 15067 30183 15067 30184 15074 30184 15076 30184 15067 30185 15076 30185 15075 30185 15075 30186 15076 30186 14775 30186 15075 30187 14775 30187 15070 30187 15070 30188 14775 30188 15077 30188 15070 30189 15077 30189 15069 30189 15069 30190 15077 30190 15078 30190 15069 30191 15078 30191 15079 30191 15079 30192 15078 30192 14766 30192 15079 30193 14766 30193 15080 30193 15080 30194 14766 30194 14767 30194 15080 30195 14767 30195 15072 30195 15072 30196 14767 30196 14769 30196 15072 30197 14769 30197 15071 30197 15071 30198 14769 30198 14771 30198 15071 30199 14771 30199 15081 30199 15081 30200 14771 30200 14772 30200 15081 30201 14772 30201 15082 30201 15082 30202 14772 30202 15083 30202 15082 30203 15083 30203 15073 30203 15073 30204 15083 30204 14773 30204 15073 30205 14773 30205 15084 30205 15084 30206 14773 30206 15074 30206 15088 30207 15086 30207 15085 30207 15100 30208 15086 30208 15088 30208 15088 30209 15097 30209 15090 30209 15087 30210 15097 30210 15088 30210 15085 30211 15087 30211 15088 30211 15088 30212 15099 30212 15089 30212 15091 30213 15099 30213 15088 30213 15090 30214 15091 30214 15088 30214 15088 30215 15092 30215 15093 30215 15094 30216 15092 30216 15088 30216 15089 30217 15094 30217 15088 30217 15093 30218 15100 30218 15088 30218 15100 30219 13592 30219 15086 30219 15086 30220 13592 30220 15095 30220 15086 30221 15095 30221 15085 30221 15085 30222 15095 30222 13595 30222 15085 30223 13595 30223 15087 30223 15087 30224 13595 30224 15096 30224 15087 30225 15096 30225 15097 30225 15097 30226 15096 30226 13580 30226 15097 30227 13580 30227 15090 30227 15090 30228 13580 30228 15098 30228 15090 30229 15098 30229 15091 30229 15091 30230 15098 30230 13582 30230 15091 30231 13582 30231 15099 30231 15099 30232 13582 30232 13586 30232 15099 30233 13586 30233 15089 30233 15089 30234 13586 30234 13587 30234 15089 30235 13587 30235 15094 30235 15094 30236 13587 30236 13589 30236 15094 30237 13589 30237 15092 30237 15092 30238 13589 30238 13590 30238 15092 30239 13590 30239 15093 30239 15093 30240 13590 30240 15101 30240 15093 30241 15101 30241 15100 30241 15100 30242 15101 30242 13592 30242 15102 30243 15104 30243 15103 30243 15119 30244 15104 30244 15102 30244 15102 30245 15106 30245 15105 30245 15107 30246 15106 30246 15102 30246 15103 30247 15107 30247 15102 30247 15102 30248 15109 30248 15115 30248 15108 30249 15109 30249 15102 30249 15105 30250 15108 30250 15102 30250 15102 30251 15110 30251 15118 30251 15116 30252 15110 30252 15102 30252 15115 30253 15116 30253 15102 30253 15118 30254 15119 30254 15102 30254 15119 30255 15111 30255 15104 30255 15104 30256 15111 30256 13604 30256 15104 30257 13604 30257 15103 30257 15103 30258 13604 30258 13606 30258 15103 30259 13606 30259 15107 30259 15107 30260 13606 30260 15112 30260 15107 30261 15112 30261 15106 30261 15106 30262 15112 30262 15113 30262 15106 30263 15113 30263 15105 30263 15105 30264 15113 30264 15114 30264 15105 30265 15114 30265 15108 30265 15108 30266 15114 30266 13598 30266 15108 30267 13598 30267 15109 30267 15109 30268 13598 30268 13599 30268 15109 30269 13599 30269 15115 30269 15115 30270 13599 30270 13600 30270 15115 30271 13600 30271 15116 30271 15116 30272 13600 30272 13601 30272 15116 30273 13601 30273 15110 30273 15110 30274 13601 30274 15117 30274 15110 30275 15117 30275 15118 30275 15118 30276 15117 30276 15120 30276 15118 30277 15120 30277 15119 30277 15119 30278 15120 30278 15111 30278 15125 30279 15127 30279 15121 30279 15126 30280 15127 30280 15125 30280 15125 30281 15122 30281 15132 30281 15129 30282 15122 30282 15125 30282 15121 30283 15129 30283 15125 30283 15125 30284 15134 30284 15123 30284 15133 30285 15134 30285 15125 30285 15132 30286 15133 30286 15125 30286 15125 30287 15136 30287 15138 30287 15124 30288 15136 30288 15125 30288 15123 30289 15124 30289 15125 30289 15138 30290 15126 30290 15125 30290 15126 30291 13573 30291 15127 30291 15127 30292 13573 30292 15128 30292 15127 30293 15128 30293 15121 30293 15121 30294 15128 30294 13575 30294 15121 30295 13575 30295 15129 30295 15129 30296 13575 30296 15130 30296 15129 30297 15130 30297 15122 30297 15122 30298 15130 30298 15131 30298 15122 30299 15131 30299 15132 30299 15132 30300 15131 30300 13577 30300 15132 30301 13577 30301 15133 30301 15133 30302 13577 30302 13578 30302 15133 30303 13578 30303 15134 30303 15134 30304 13578 30304 13579 30304 15134 30305 13579 30305 15123 30305 15123 30306 13579 30306 15135 30306 15123 30307 15135 30307 15124 30307 15124 30308 15135 30308 13571 30308 15124 30309 13571 30309 15136 30309 15136 30310 13571 30310 15137 30310 15136 30311 15137 30311 15138 30311 15138 30312 15137 30312 15139 30312 15138 30313 15139 30313 15126 30313 15126 30314 15139 30314 13573 30314 15140 30315 15141 30315 15146 30315 15145 30316 15141 30316 15140 30316 15140 30317 15148 30317 15142 30317 15147 30318 15148 30318 15140 30318 15146 30319 15147 30319 15140 30319 15140 30320 15150 30320 15151 30320 15143 30321 15150 30321 15140 30321 15142 30322 15143 30322 15140 30322 15140 30323 15153 30323 15155 30323 15144 30324 15153 30324 15140 30324 15151 30325 15144 30325 15140 30325 15155 30326 15145 30326 15140 30326 15145 30327 15156 30327 15141 30327 15141 30328 15156 30328 13560 30328 15141 30329 13560 30329 15146 30329 15146 30330 13560 30330 13562 30330 15146 30331 13562 30331 15147 30331 15147 30332 13562 30332 13563 30332 15147 30333 13563 30333 15148 30333 15148 30334 13563 30334 15149 30334 15148 30335 15149 30335 15142 30335 15142 30336 15149 30336 13565 30336 15142 30337 13565 30337 15143 30337 15143 30338 13565 30338 13568 30338 15143 30339 13568 30339 15150 30339 15150 30340 13568 30340 13569 30340 15150 30341 13569 30341 15151 30341 15151 30342 13569 30342 15152 30342 15151 30343 15152 30343 15144 30343 15144 30344 15152 30344 13558 30344 15144 30345 13558 30345 15153 30345 15153 30346 13558 30346 13559 30346 15153 30347 13559 30347 15155 30347 15155 30348 13559 30348 15154 30348 15155 30349 15154 30349 15145 30349 15145 30350 15154 30350 15156 30350 15157 30351 15376 30351 15159 30351 15159 30352 15376 30352 15158 30352 15159 30353 15158 30353 13719 30353 13719 30354 15158 30354 15161 30354 13719 30355 15161 30355 15160 30355 15160 30356 15161 30356 15367 30356 15160 30357 15367 30357 15162 30357 15162 30358 15367 30358 15368 30358 15162 30359 15368 30359 15164 30359 15164 30360 15368 30360 15163 30360 15164 30361 15163 30361 13705 30361 13705 30362 15163 30362 15370 30362 13705 30363 15370 30363 13706 30363 13706 30364 15370 30364 15166 30364 13706 30365 15166 30365 15165 30365 15165 30366 15166 30366 15167 30366 15165 30367 15167 30367 13704 30367 13704 30368 15167 30368 15168 30368 13704 30369 15168 30369 15169 30369 15169 30370 15168 30370 15372 30370 15169 30371 15372 30371 13702 30371 13702 30372 15372 30372 15373 30372 13702 30373 15373 30373 15157 30373 15157 30374 15373 30374 15376 30374 13785 30375 13653 30375 15170 30375 15170 30376 13653 30376 13654 30376 15170 30377 13654 30377 13783 30377 13783 30378 13654 30378 13656 30378 13783 30379 13656 30379 13789 30379 13789 30380 13656 30380 15171 30380 13789 30381 15171 30381 13793 30381 13793 30382 15171 30382 13643 30382 13793 30383 13643 30383 13777 30383 13777 30384 13643 30384 13645 30384 13777 30385 13645 30385 13775 30385 13775 30386 13645 30386 15173 30386 13775 30387 15173 30387 15172 30387 15172 30388 15173 30388 15174 30388 15172 30389 15174 30389 15175 30389 15175 30390 15174 30390 13648 30390 15175 30391 13648 30391 13788 30391 13788 30392 13648 30392 15176 30392 13788 30393 15176 30393 15177 30393 15177 30394 15176 30394 15178 30394 15177 30395 15178 30395 13787 30395 13787 30396 15178 30396 15179 30396 13787 30397 15179 30397 13785 30397 13785 30398 15179 30398 13653 30398 13813 30399 13665 30399 15180 30399 15180 30400 13665 30400 15181 30400 15180 30401 15181 30401 15182 30401 15182 30402 15181 30402 15183 30402 15182 30403 15183 30403 13805 30403 13805 30404 15183 30404 13668 30404 13805 30405 13668 30405 15184 30405 15184 30406 13668 30406 13670 30406 15184 30407 13670 30407 13804 30407 13804 30408 13670 30408 13672 30408 13804 30409 13672 30409 15185 30409 15185 30410 13672 30410 13658 30410 15185 30411 13658 30411 13802 30411 13802 30412 13658 30412 13661 30412 13802 30413 13661 30413 13801 30413 13801 30414 13661 30414 13662 30414 13801 30415 13662 30415 15186 30415 15186 30416 13662 30416 15187 30416 15186 30417 15187 30417 13812 30417 13812 30418 15187 30418 13664 30418 13812 30419 13664 30419 15189 30419 15189 30420 13664 30420 15188 30420 15189 30421 15188 30421 13813 30421 13813 30422 15188 30422 13665 30422 15190 30423 13681 30423 15191 30423 15191 30424 13681 30424 15192 30424 15191 30425 15192 30425 13737 30425 13737 30426 15192 30426 13684 30426 13737 30427 13684 30427 15193 30427 15193 30428 13684 30428 15194 30428 15193 30429 15194 30429 15195 30429 15195 30430 15194 30430 15196 30430 15195 30431 15196 30431 15197 30431 15197 30432 15196 30432 15198 30432 15197 30433 15198 30433 15199 30433 15199 30434 15198 30434 13673 30434 15199 30435 13673 30435 13732 30435 13732 30436 13673 30436 13674 30436 13732 30437 13674 30437 15200 30437 15200 30438 13674 30438 13676 30438 15200 30439 13676 30439 13731 30439 13731 30440 13676 30440 13678 30440 13731 30441 13678 30441 13725 30441 13725 30442 13678 30442 15201 30442 13725 30443 15201 30443 15202 30443 15202 30444 15201 30444 13680 30444 15202 30445 13680 30445 15190 30445 15190 30446 13680 30446 13681 30446 15203 30447 15205 30447 15204 30447 15204 30448 15205 30448 15206 30448 15204 30449 15206 30449 15207 30449 15207 30450 15206 30450 15208 30450 15207 30451 15208 30451 15209 30451 15209 30452 15208 30452 13687 30452 15209 30453 13687 30453 15210 30453 15210 30454 13687 30454 15211 30454 15210 30455 15211 30455 13762 30455 13762 30456 15211 30456 15213 30456 13762 30457 15213 30457 15212 30457 15212 30458 15213 30458 13688 30458 15212 30459 13688 30459 13758 30459 13758 30460 13688 30460 15214 30460 13758 30461 15214 30461 13760 30461 13760 30462 15214 30462 15215 30462 13760 30463 15215 30463 15217 30463 15217 30464 15215 30464 15216 30464 15217 30465 15216 30465 13759 30465 13759 30466 15216 30466 15219 30466 13759 30467 15219 30467 15218 30467 15218 30468 15219 30468 15220 30468 15218 30469 15220 30469 15203 30469 15203 30470 15220 30470 15205 30470 14875 30471 14524 30471 15221 30471 15221 30472 14524 30472 15222 30472 15221 30473 15222 30473 14877 30473 14877 30474 15222 30474 15223 30474 14877 30475 15223 30475 14878 30475 14878 30476 15223 30476 15224 30476 14878 30477 15224 30477 14880 30477 14880 30478 15224 30478 15225 30478 14880 30479 15225 30479 15226 30479 15226 30480 15225 30480 14523 30480 15226 30481 14523 30481 14882 30481 14882 30482 14523 30482 15227 30482 14882 30483 15227 30483 15228 30483 15228 30484 15227 30484 14522 30484 15228 30485 14522 30485 15229 30485 15229 30486 14522 30486 14521 30486 15229 30487 14521 30487 14885 30487 14885 30488 14521 30488 14526 30488 14885 30489 14526 30489 15230 30489 15230 30490 14526 30490 15231 30490 15230 30491 15231 30491 14874 30491 14874 30492 15231 30492 15232 30492 14874 30493 15232 30493 14875 30493 14875 30494 15232 30494 14524 30494 15243 30495 15233 30495 14887 30495 14887 30496 15233 30496 14596 30496 14887 30497 14596 30497 15234 30497 15234 30498 14596 30498 14595 30498 15234 30499 14595 30499 14888 30499 14888 30500 14595 30500 14592 30500 14888 30501 14592 30501 14890 30501 14890 30502 14592 30502 14591 30502 14890 30503 14591 30503 15235 30503 15235 30504 14591 30504 14589 30504 15235 30505 14589 30505 14892 30505 14892 30506 14589 30506 15236 30506 14892 30507 15236 30507 14894 30507 14894 30508 15236 30508 15237 30508 14894 30509 15237 30509 14895 30509 14895 30510 15237 30510 14585 30510 14895 30511 14585 30511 15238 30511 15238 30512 14585 30512 14586 30512 15238 30513 14586 30513 15239 30513 15239 30514 14586 30514 15240 30514 15239 30515 15240 30515 15242 30515 15242 30516 15240 30516 15241 30516 15242 30517 15241 30517 15243 30517 15243 30518 15241 30518 15233 30518 14899 30519 15244 30519 14901 30519 14901 30520 15244 30520 15245 30520 14901 30521 15245 30521 14902 30521 14902 30522 15245 30522 14577 30522 14902 30523 14577 30523 14903 30523 14903 30524 14577 30524 15246 30524 14903 30525 15246 30525 14904 30525 14904 30526 15246 30526 15247 30526 14904 30527 15247 30527 14906 30527 14906 30528 15247 30528 14581 30528 14906 30529 14581 30529 14907 30529 14907 30530 14581 30530 15248 30530 14907 30531 15248 30531 14908 30531 14908 30532 15248 30532 14579 30532 14908 30533 14579 30533 14909 30533 14909 30534 14579 30534 15249 30534 14909 30535 15249 30535 14910 30535 14910 30536 15249 30536 14576 30536 14910 30537 14576 30537 14911 30537 14911 30538 14576 30538 15250 30538 14911 30539 15250 30539 15251 30539 15251 30540 15250 30540 15252 30540 15251 30541 15252 30541 14899 30541 14899 30542 15252 30542 15244 30542 15260 30543 14683 30543 14862 30543 14862 30544 14683 30544 14682 30544 14862 30545 14682 30545 14864 30545 14864 30546 14682 30546 14512 30546 14864 30547 14512 30547 15253 30547 15253 30548 14512 30548 15254 30548 15253 30549 15254 30549 14867 30549 14867 30550 15254 30550 14533 30550 14867 30551 14533 30551 14868 30551 14868 30552 14533 30552 14534 30552 14868 30553 14534 30553 15255 30553 15255 30554 14534 30554 14564 30554 15255 30555 14564 30555 14870 30555 14870 30556 14564 30556 15256 30556 14870 30557 15256 30557 15257 30557 15257 30558 15256 30558 15258 30558 15257 30559 15258 30559 15259 30559 15259 30560 15258 30560 14514 30560 15259 30561 14514 30561 14873 30561 14873 30562 14514 30562 14513 30562 14873 30563 14513 30563 14859 30563 14859 30564 14513 30564 14528 30564 14859 30565 14528 30565 15260 30565 15260 30566 14528 30566 14683 30566 15003 30567 15276 30567 14995 30567 14995 30568 15276 30568 15262 30568 14995 30569 15262 30569 15261 30569 15261 30570 15262 30570 15263 30570 15261 30571 15263 30571 14997 30571 14997 30572 15263 30572 13576 30572 14997 30573 13576 30573 15264 30573 15264 30574 13576 30574 13574 30574 15264 30575 13574 30575 14998 30575 14998 30576 13574 30576 15265 30576 14998 30577 15265 30577 15266 30577 15266 30578 15265 30578 13572 30578 15266 30579 13572 30579 15267 30579 15267 30580 13572 30580 15268 30580 15267 30581 15268 30581 15270 30581 15270 30582 15268 30582 15269 30582 15270 30583 15269 30583 15272 30583 15272 30584 15269 30584 15271 30584 15272 30585 15271 30585 15273 30585 15273 30586 15271 30586 15274 30586 15273 30587 15274 30587 15001 30587 15001 30588 15274 30588 15275 30588 15001 30589 15275 30589 15003 30589 15003 30590 15275 30590 15276 30590 15277 30591 13566 30591 15278 30591 15278 30592 13566 30592 13564 30592 15278 30593 13564 30593 15279 30593 15279 30594 13564 30594 15280 30594 15279 30595 15280 30595 15281 30595 15281 30596 15280 30596 15282 30596 15281 30597 15282 30597 15283 30597 15283 30598 15282 30598 13561 30598 15283 30599 13561 30599 15008 30599 15008 30600 13561 30600 15285 30600 15008 30601 15285 30601 15284 30601 15284 30602 15285 30602 15286 30602 15284 30603 15286 30603 15287 30603 15287 30604 15286 30604 15288 30604 15287 30605 15288 30605 15011 30605 15011 30606 15288 30606 15289 30606 15011 30607 15289 30607 15012 30607 15012 30608 15289 30608 13557 30608 15012 30609 13557 30609 15290 30609 15290 30610 13557 30610 13570 30610 15290 30611 13570 30611 15291 30611 15291 30612 13570 30612 13567 30612 15291 30613 13567 30613 15277 30613 15277 30614 13567 30614 13566 30614 14979 30615 13597 30615 15292 30615 15292 30616 13597 30616 15293 30616 15292 30617 15293 30617 14966 30617 14966 30618 15293 30618 15294 30618 14966 30619 15294 30619 14968 30619 14968 30620 15294 30620 13607 30620 14968 30621 13607 30621 14969 30621 14969 30622 13607 30622 13605 30622 14969 30623 13605 30623 15295 30623 15295 30624 13605 30624 15296 30624 15295 30625 15296 30625 14971 30625 14971 30626 15296 30626 15297 30626 14971 30627 15297 30627 14973 30627 14973 30628 15297 30628 13603 30628 14973 30629 13603 30629 15298 30629 15298 30630 13603 30630 13602 30630 15298 30631 13602 30631 14975 30631 14975 30632 13602 30632 15299 30632 14975 30633 15299 30633 14976 30633 14976 30634 15299 30634 15300 30634 14976 30635 15300 30635 15301 30635 15301 30636 15300 30636 15302 30636 15301 30637 15302 30637 14979 30637 14979 30638 15302 30638 13597 30638 15310 30639 13583 30639 15303 30639 15303 30640 13583 30640 15304 30640 15303 30641 15304 30641 14981 30641 14981 30642 15304 30642 13581 30642 14981 30643 13581 30643 15305 30643 15305 30644 13581 30644 13596 30644 15305 30645 13596 30645 14985 30645 14985 30646 13596 30646 13594 30646 14985 30647 13594 30647 14986 30647 14986 30648 13594 30648 13593 30648 14986 30649 13593 30649 14989 30649 14989 30650 13593 30650 15306 30650 14989 30651 15306 30651 14990 30651 14990 30652 15306 30652 13591 30652 14990 30653 13591 30653 15307 30653 15307 30654 13591 30654 15308 30654 15307 30655 15308 30655 14991 30655 14991 30656 15308 30656 13588 30656 14991 30657 13588 30657 15309 30657 15309 30658 13588 30658 13585 30658 15309 30659 13585 30659 14994 30659 14994 30660 13585 30660 13584 30660 14994 30661 13584 30661 15310 30661 15310 30662 13584 30662 13583 30662 15323 30663 13609 30663 14965 30663 14965 30664 13609 30664 15311 30664 14965 30665 15311 30665 14955 30665 14955 30666 15311 30666 15313 30666 14955 30667 15313 30667 15312 30667 15312 30668 15313 30668 15314 30668 15312 30669 15314 30669 15315 30669 15315 30670 15314 30670 13618 30670 15315 30671 13618 30671 15317 30671 15317 30672 13618 30672 15316 30672 15317 30673 15316 30673 14960 30673 14960 30674 15316 30674 13617 30674 14960 30675 13617 30675 15318 30675 15318 30676 13617 30676 15319 30676 15318 30677 15319 30677 14962 30677 14962 30678 15319 30678 15320 30678 14962 30679 15320 30679 15321 30679 15321 30680 15320 30680 13613 30680 15321 30681 13613 30681 14963 30681 14963 30682 13613 30682 13612 30682 14963 30683 13612 30683 15322 30683 15322 30684 13612 30684 13611 30684 15322 30685 13611 30685 15323 30685 15323 30686 13611 30686 13609 30686 15338 30687 14768 30687 15325 30687 15325 30688 14768 30688 15324 30688 15325 30689 15324 30689 14944 30689 14944 30690 15324 30690 14765 30690 14944 30691 14765 30691 15326 30691 15326 30692 14765 30692 15327 30692 15326 30693 15327 30693 14946 30693 14946 30694 15327 30694 14774 30694 14946 30695 14774 30695 14947 30695 14947 30696 14774 30696 15328 30696 14947 30697 15328 30697 15329 30697 15329 30698 15328 30698 15330 30698 15329 30699 15330 30699 15332 30699 15332 30700 15330 30700 15331 30700 15332 30701 15331 30701 14950 30701 14950 30702 15331 30702 15334 30702 14950 30703 15334 30703 15333 30703 15333 30704 15334 30704 15335 30704 15333 30705 15335 30705 14951 30705 14951 30706 15335 30706 14770 30706 14951 30707 14770 30707 15336 30707 15336 30708 14770 30708 15337 30708 15336 30709 15337 30709 15338 30709 15338 30710 15337 30710 14768 30710 15339 30711 15340 30711 15341 30711 15341 30712 15340 30712 15342 30712 15341 30713 15342 30713 14928 30713 14928 30714 15342 30714 15343 30714 14928 30715 15343 30715 14929 30715 14929 30716 15343 30716 13629 30716 14929 30717 13629 30717 14930 30717 14930 30718 13629 30718 13627 30718 14930 30719 13627 30719 15344 30719 15344 30720 13627 30720 13625 30720 15344 30721 13625 30721 14932 30721 14932 30722 13625 30722 15345 30722 14932 30723 15345 30723 14935 30723 14935 30724 15345 30724 15346 30724 14935 30725 15346 30725 14938 30725 14938 30726 15346 30726 13622 30726 14938 30727 13622 30727 15347 30727 15347 30728 13622 30728 15348 30728 15347 30729 15348 30729 14939 30729 14939 30730 15348 30730 15350 30730 14939 30731 15350 30731 15349 30731 15349 30732 15350 30732 15351 30732 15349 30733 15351 30733 15339 30733 15339 30734 15351 30734 15340 30734 14925 30735 13640 30735 14912 30735 14912 30736 13640 30736 15353 30736 14912 30737 15353 30737 15352 30737 15352 30738 15353 30738 13638 30738 15352 30739 13638 30739 14914 30739 14914 30740 13638 30740 15354 30740 14914 30741 15354 30741 15356 30741 15356 30742 15354 30742 15355 30742 15356 30743 15355 30743 15358 30743 15358 30744 15355 30744 15357 30744 15358 30745 15357 30745 15359 30745 15359 30746 15357 30746 15360 30746 15359 30747 15360 30747 14917 30747 14917 30748 15360 30748 15362 30748 14917 30749 15362 30749 15361 30749 15361 30750 15362 30750 15364 30750 15361 30751 15364 30751 15363 30751 15363 30752 15364 30752 13631 30752 15363 30753 13631 30753 14921 30753 14921 30754 13631 30754 15365 30754 14921 30755 15365 30755 14923 30755 14923 30756 15365 30756 15366 30756 14923 30757 15366 30757 14925 30757 14925 30758 15366 30758 13640 30758 15158 30759 14063 30759 15161 30759 15161 30760 14063 30760 14055 30760 15161 30761 14055 30761 15367 30761 15367 30762 14055 30762 14046 30762 15367 30763 14046 30763 15368 30763 15368 30764 14046 30764 15369 30764 15368 30765 15369 30765 15163 30765 15163 30766 15369 30766 15371 30766 15163 30767 15371 30767 15370 30767 15370 30768 15371 30768 14056 30768 15370 30769 14056 30769 15166 30769 15166 30770 14056 30770 14051 30770 15166 30771 14051 30771 15167 30771 15167 30772 14051 30772 14052 30772 15167 30773 14052 30773 15168 30773 15168 30774 14052 30774 14045 30774 15168 30775 14045 30775 15372 30775 15372 30776 14045 30776 15374 30776 15372 30777 15374 30777 15373 30777 15373 30778 15374 30778 15375 30778 15373 30779 15375 30779 15376 30779 15376 30780 15375 30780 14061 30780 15376 30781 14061 30781 15158 30781 15158 30782 14061 30782 14063 30782 12791 30783 14784 30783 13493 30783 12791 30784 13493 30784 12809 30784 12809 30785 13493 30785 13495 30785 12809 30786 13495 30786 12796 30786 12796 30787 13495 30787 15377 30787 12796 30788 15377 30788 12795 30788 12795 30789 15377 30789 12794 30789 12794 30790 15377 30790 13498 30790 12794 30791 13498 30791 15378 30791 15391 30792 15380 30792 15379 30792 15379 30793 15380 30793 15381 30793 15379 30794 15381 30794 15382 30794 14367 30795 14366 30795 15391 30795 15391 30796 14366 30796 15383 30796 15391 30797 15383 30797 15380 30797 15391 30798 15393 30798 14367 30798 14367 30799 15393 30799 15384 30799 14367 30800 15384 30800 14368 30800 14368 30801 15384 30801 15385 30801 15384 30802 15386 30802 15385 30802 15385 30803 15386 30803 15395 30803 15385 30804 15395 30804 14371 30804 14371 30805 15395 30805 15387 30805 14371 30806 15387 30806 15388 30806 15388 30807 15387 30807 15389 30807 15388 30808 15389 30808 14449 30808 15382 30809 15390 30809 15379 30809 15379 30810 15390 30810 15392 30810 15379 30811 15392 30811 15391 30811 15391 30812 15392 30812 15416 30812 15391 30813 15416 30813 15393 30813 15393 30814 15416 30814 15418 30814 15393 30815 15418 30815 15384 30815 15384 30816 15418 30816 15394 30816 15384 30817 15394 30817 15386 30817 15386 30818 15394 30818 15420 30818 15386 30819 15420 30819 15395 30819 15395 30820 15420 30820 15396 30820 15395 30821 15396 30821 15387 30821 15387 30822 15396 30822 15397 30822 15387 30823 15397 30823 15389 30823 15409 30824 15410 30824 14808 30824 14808 30825 15410 30825 15405 30825 14816 30826 15407 30826 14815 30826 14815 30827 15407 30827 15408 30827 14808 30828 14814 30828 15409 30828 15409 30829 14814 30829 15398 30829 15409 30830 15398 30830 15408 30830 15408 30831 15398 30831 14813 30831 15408 30832 14813 30832 14815 30832 14827 30833 14804 30833 15399 30833 15399 30834 14804 30834 15400 30834 15399 30835 15400 30835 15402 30835 15400 30836 15401 30836 15402 30836 15402 30837 15401 30837 14806 30837 15402 30838 14806 30838 15403 30838 15403 30839 14806 30839 15404 30839 15403 30840 15404 30840 15412 30840 15412 30841 15404 30841 14811 30841 15412 30842 14811 30842 15410 30842 15410 30843 14811 30843 14810 30843 15410 30844 14810 30844 15405 30844 14816 30845 15422 30845 15407 30845 15407 30846 15422 30846 15406 30846 15407 30847 15406 30847 15408 30847 15408 30848 15406 30848 15421 30848 15408 30849 15421 30849 15409 30849 15409 30850 15421 30850 15411 30850 15409 30851 15411 30851 15410 30851 15410 30852 15411 30852 15419 30852 15410 30853 15419 30853 15412 30853 15412 30854 15419 30854 15417 30854 15412 30855 15417 30855 15403 30855 15403 30856 15417 30856 15413 30856 15403 30857 15413 30857 15402 30857 15402 30858 15413 30858 15415 30858 15402 30859 15415 30859 15399 30859 12870 30860 12847 30860 15397 30860 15397 30861 12847 30861 15414 30861 15397 30862 15414 30862 15389 30862 15390 30863 15415 30863 15392 30863 15392 30864 15415 30864 15413 30864 15392 30865 15413 30865 15416 30865 15416 30866 15413 30866 15417 30866 15416 30867 15417 30867 15418 30867 15418 30868 15417 30868 15419 30868 15418 30869 15419 30869 15394 30869 15394 30870 15419 30870 15411 30870 15394 30871 15411 30871 15420 30871 15420 30872 15411 30872 15421 30872 15420 30873 15421 30873 15396 30873 15396 30874 15421 30874 15406 30874 15396 30875 15406 30875 15397 30875 15397 30876 15406 30876 15422 30876 15397 30877 15422 30877 12870 30877 12870 30878 15422 30878 14816 30878 12870 30879 14816 30879 15423 30879 14793 30880 13842 30880 14794 30880 14794 30881 13842 30881 13844 30881 14794 30882 13844 30882 14796 30882 14796 30883 13844 30883 13846 30883 14796 30884 13846 30884 14797 30884 14797 30885 13846 30885 13847 30885 14797 30886 13847 30886 15424 30886 15424 30887 13847 30887 13837 30887 15424 30888 13837 30888 14798 30888 14798 30889 13837 30889 15425 30889 14798 30890 15425 30890 14799 30890 14799 30891 15425 30891 15426 30891 14799 30892 15426 30892 14801 30892 14801 30893 15426 30893 15427 30893 14801 30894 15427 30894 15428 30894 15428 30895 15427 30895 13839 30895 15428 30896 13839 30896 14802 30896 14802 30897 13839 30897 15429 30897 14802 30898 15429 30898 15430 30898 15430 30899 15429 30899 13840 30899 15430 30900 13840 30900 14792 30900 14792 30901 13840 30901 15431 30901 14792 30902 15431 30902 14793 30902 14793 30903 15431 30903 13842 30903 15432 30904 14601 30904 15433 30904 15432 30905 15433 30905 12761 30905 14606 30906 12758 30906 15433 30906 15433 30907 12758 30907 12759 30907 15433 30908 12759 30908 12761 30908 15434 30909 15435 30909 12764 30909 15435 30910 15434 30910 14606 30910 15440 30911 14560 30911 15436 30911 15440 30912 12774 30912 15437 30912 15437 30913 15438 30913 15440 30913 15440 30914 15438 30914 15439 30914 15440 30915 15439 30915 12769 30915 15436 30916 15441 30916 15440 30916 15440 30917 15441 30917 15442 30917 15440 30918 15442 30918 12774 30918 15443 30919 15446 30919 13556 30919 13556 30920 15446 30920 14678 30920 13556 30921 14678 30921 15444 30921 12819 30922 12818 30922 12815 30922 15444 30923 15445 30923 13556 30923 13556 30924 15445 30924 14641 30924 13556 30925 14641 30925 13553 30925 13553 30926 14641 30926 15440 30926 13553 30927 15440 30927 12768 30927 12768 30928 15440 30928 12769 30928 12815 30929 12816 30929 12819 30929 12819 30930 12816 30930 12812 30930 12819 30931 12812 30931 15443 30931 15443 30932 12812 30932 14636 30932 15443 30933 14636 30933 15446 30933 14567 30934 14568 30934 12767 30934 12767 30935 14568 30935 12766 30935 12756 30936 15447 30936 14569 30936 15447 30937 12756 30937 14570 30937 14570 30938 12756 30938 15448 30938 14570 30939 15448 30939 12766 30939 15449 30940 17398 30940 15465 30940 17392 30941 15450 30941 15451 30941 15456 30942 15452 30942 15455 30942 15455 30943 15452 30943 15453 30943 15455 30944 15453 30944 17397 30944 15454 30945 17285 30945 17401 30945 17401 30946 17285 30946 17286 30946 15462 30947 17283 30947 15455 30947 15455 30948 17283 30948 17285 30948 15455 30949 17285 30949 15456 30949 15456 30950 17285 30950 15454 30950 17392 30951 15451 30951 15457 30951 15457 30952 15451 30952 15458 30952 15457 30953 15458 30953 15464 30953 15464 30954 15458 30954 17293 30954 15464 30955 17293 30955 15460 30955 17765 30956 15459 30956 17766 30956 17766 30957 15459 30957 15460 30957 17766 30958 15460 30958 15461 30958 15461 30959 15460 30959 17293 30959 15463 30960 15462 30960 15465 30960 15465 30961 15462 30961 15455 30961 15465 30962 15455 30962 15449 30962 15449 30963 15455 30963 17397 30963 17765 30964 17283 30964 15459 30964 15459 30965 17283 30965 15462 30965 15459 30966 15462 30966 15460 30966 15460 30967 15462 30967 15463 30967 15460 30968 15463 30968 15464 30968 15464 30969 15463 30969 15465 30969 15464 30970 15465 30970 15457 30970 15457 30971 15465 30971 17398 30971 15457 30972 17398 30972 17392 30972 20906 30973 15478 30973 15466 30973 15466 30974 15478 30974 15467 30974 15466 30975 15467 30975 15468 30975 15468 30976 15467 30976 19490 30976 15468 30977 19490 30977 20904 30977 20904 30978 19490 30978 15469 30978 20904 30979 15469 30979 15470 30979 15470 30980 15469 30980 15471 30980 15470 30981 15471 30981 15473 30981 15473 30982 15471 30982 15472 30982 15473 30983 15472 30983 20902 30983 20902 30984 15472 30984 15474 30984 20902 30985 15474 30985 20903 30985 20903 30986 15474 30986 19497 30986 20903 30987 19497 30987 20908 30987 20908 30988 19497 30988 19481 30988 20908 30989 19481 30989 15475 30989 15475 30990 19481 30990 19483 30990 15475 30991 19483 30991 20905 30991 20905 30992 19483 30992 19471 30992 20905 30993 19471 30993 15476 30993 15476 30994 19471 30994 15477 30994 15476 30995 15477 30995 20906 30995 20906 30996 15477 30996 15478 30996 19553 30997 17389 30997 17388 30997 17340 30998 19553 30998 17342 30998 17342 30999 19553 30999 17388 30999 17342 31000 17388 31000 15479 31000 15479 31001 17388 31001 15480 31001 16724 31002 15481 31002 20732 31002 20732 31003 15481 31003 19470 31003 20732 31004 19470 31004 15491 31004 15483 31005 19476 31005 15482 31005 15482 31006 15484 31006 15483 31006 15483 31007 15484 31007 15485 31007 15483 31008 15485 31008 19467 31008 19467 31009 15485 31009 20735 31009 19467 31010 20735 31010 15486 31010 20735 31011 15487 31011 15486 31011 15486 31012 15487 31012 20733 31012 15486 31013 20733 31013 15488 31013 20733 31014 15489 31014 15488 31014 15488 31015 15489 31015 15490 31015 15488 31016 15490 31016 15491 31016 15491 31017 15490 31017 15492 31017 15491 31018 15492 31018 20732 31018 16734 31019 17781 31019 15493 31019 15493 31020 17781 31020 19473 31020 19473 31021 15494 31021 15493 31021 15493 31022 15494 31022 19682 31022 15493 31023 19682 31023 19684 31023 19684 31024 19688 31024 15497 31024 15481 31025 16724 31025 15495 31025 15495 31026 16724 31026 16727 31026 15495 31027 16727 31027 15496 31027 15496 31028 16727 31028 16731 31028 15496 31029 16731 31029 15497 31029 15497 31030 16731 31030 15493 31030 15497 31031 15493 31031 19684 31031 17417 31032 15498 31032 15503 31032 15503 31033 15498 31033 15499 31033 15503 31034 15499 31034 15505 31034 15505 31035 15499 31035 15517 31035 15505 31036 15517 31036 15507 31036 15507 31037 15517 31037 15501 31037 15507 31038 15501 31038 15500 31038 15500 31039 15501 31039 15513 31039 17421 31040 17417 31040 15502 31040 15502 31041 17417 31041 15503 31041 15502 31042 15503 31042 15504 31042 15504 31043 15503 31043 15505 31043 15504 31044 15505 31044 15506 31044 15506 31045 15505 31045 15507 31045 15506 31046 15507 31046 18093 31046 18093 31047 15507 31047 15500 31047 15508 31048 15512 31048 15509 31048 15519 31049 15522 31049 15518 31049 15515 31050 15501 31050 15517 31050 15527 31051 15510 31051 15508 31051 15508 31052 15510 31052 15511 31052 15508 31053 15511 31053 15512 31053 15512 31054 15511 31054 15521 31054 15513 31055 15501 31055 18657 31055 18657 31056 15501 31056 15515 31056 18657 31057 15515 31057 15514 31057 18677 31058 15514 31058 15528 31058 15528 31059 15514 31059 15515 31059 15528 31060 15515 31060 15516 31060 15516 31061 15515 31061 15517 31061 15516 31062 15517 31062 15499 31062 15518 31063 15529 31063 15519 31063 15519 31064 15529 31064 15509 31064 15519 31065 15509 31065 15523 31065 15523 31066 15509 31066 15512 31066 15523 31067 15512 31067 15520 31067 15520 31068 15512 31068 15521 31068 15522 31069 15519 31069 15524 31069 15524 31070 15519 31070 15523 31070 15524 31071 15523 31071 15569 31071 15569 31072 15523 31072 15520 31072 15569 31073 15520 31073 15525 31073 15525 31074 15520 31074 15521 31074 15525 31075 15521 31075 15526 31075 15498 31076 15527 31076 15499 31076 15499 31077 15527 31077 15508 31077 15499 31078 15508 31078 15516 31078 15516 31079 15508 31079 15509 31079 15516 31080 15509 31080 15528 31080 15528 31081 15509 31081 15529 31081 15528 31082 15529 31082 18677 31082 18677 31083 15529 31083 15518 31083 18677 31084 15518 31084 18676 31084 18676 31085 15518 31085 15530 31085 15506 31086 18093 31086 15536 31086 15636 31087 15619 31087 15541 31087 15534 31088 15598 31088 15535 31088 15532 31089 15531 31089 15587 31089 15587 31090 15542 31090 15532 31090 15532 31091 15542 31091 15540 31091 15532 31092 15540 31092 15506 31092 15506 31093 15540 31093 15533 31093 15506 31094 15533 31094 15504 31094 15619 31095 15534 31095 15541 31095 15541 31096 15534 31096 15535 31096 15541 31097 15535 31097 15539 31097 15539 31098 15535 31098 17420 31098 15539 31099 17420 31099 15538 31099 15538 31100 17420 31100 17421 31100 15538 31101 17421 31101 15502 31101 15506 31102 15536 31102 15532 31102 15532 31103 15536 31103 15537 31103 15532 31104 15537 31104 15531 31104 15502 31105 15504 31105 15538 31105 15538 31106 15504 31106 15533 31106 15538 31107 15533 31107 15539 31107 15539 31108 15533 31108 15540 31108 15539 31109 15540 31109 15541 31109 15541 31110 15540 31110 15542 31110 15541 31111 15542 31111 15636 31111 15636 31112 15542 31112 15587 31112 15572 31113 15530 31113 15518 31113 15570 31114 18667 31114 15573 31114 15518 31115 15522 31115 15580 31115 15571 31116 15543 31116 15544 31116 15544 31117 15543 31117 15545 31117 15544 31118 15545 31118 15639 31118 15576 31119 15546 31119 15547 31119 15547 31120 15546 31120 15548 31120 15547 31121 15548 31121 15574 31121 15574 31122 15548 31122 15549 31122 15639 31123 15550 31123 15544 31123 15544 31124 15550 31124 15551 31124 15544 31125 15551 31125 15575 31125 15577 31126 15563 31126 15552 31126 15552 31127 15563 31127 15565 31127 15552 31128 15565 31128 20530 31128 20530 31129 15565 31129 15566 31129 20530 31130 15566 31130 20531 31130 20528 31131 20527 31131 15649 31131 15558 31132 15557 31132 15578 31132 15578 31133 15557 31133 15555 31133 15578 31134 15555 31134 15553 31134 15554 31135 15555 31135 15556 31135 15556 31136 15555 31136 15557 31136 15556 31137 15557 31137 15650 31137 15650 31138 15557 31138 15558 31138 15650 31139 15558 31139 15649 31139 15525 31140 15526 31140 15559 31140 15525 31141 15559 31141 15568 31141 15568 31142 15559 31142 20532 31142 15568 31143 20532 31143 15566 31143 15566 31144 20532 31144 15560 31144 15566 31145 15560 31145 20531 31145 15524 31146 15569 31146 15562 31146 15562 31147 15569 31147 15561 31147 15562 31148 15561 31148 15579 31148 15579 31149 15561 31149 15567 31149 15579 31150 15567 31150 15564 31150 15563 31151 15564 31151 15565 31151 15565 31152 15564 31152 15567 31152 15565 31153 15567 31153 15566 31153 15566 31154 15567 31154 15561 31154 15566 31155 15561 31155 15568 31155 15568 31156 15561 31156 15569 31156 15568 31157 15569 31157 15525 31157 15570 31158 15573 31158 15575 31158 15554 31159 15545 31159 15555 31159 15555 31160 15545 31160 15543 31160 15555 31161 15543 31161 15553 31161 15553 31162 15543 31162 15571 31162 15553 31163 15571 31163 15580 31163 15580 31164 15571 31164 15576 31164 15580 31165 15576 31165 15518 31165 15518 31166 15576 31166 15547 31166 15518 31167 15547 31167 15572 31167 15572 31168 15547 31168 15574 31168 15572 31169 15574 31169 15573 31169 15573 31170 15574 31170 15549 31170 15573 31171 15549 31171 15575 31171 15575 31172 15549 31172 15548 31172 15575 31173 15548 31173 15544 31173 15544 31174 15548 31174 15546 31174 15544 31175 15546 31175 15571 31175 15571 31176 15546 31176 15576 31176 20528 31177 15649 31177 15577 31177 15577 31178 15649 31178 15558 31178 15577 31179 15558 31179 15563 31179 15563 31180 15558 31180 15578 31180 15563 31181 15578 31181 15564 31181 15564 31182 15578 31182 15553 31182 15564 31183 15553 31183 15579 31183 15579 31184 15553 31184 15580 31184 15579 31185 15580 31185 15562 31185 15562 31186 15580 31186 15522 31186 15562 31187 15522 31187 15524 31187 15628 31188 15603 31188 15629 31188 15605 31189 15627 31189 15606 31189 15581 31190 15608 31190 15626 31190 15626 31191 15608 31191 15583 31191 15626 31192 15583 31192 15582 31192 15582 31193 15583 31193 15584 31193 15582 31194 15584 31194 15623 31194 15623 31195 15584 31195 15585 31195 15623 31196 15585 31196 15591 31196 15591 31197 15586 31197 15622 31197 15622 31198 15586 31198 15588 31198 15587 31199 15588 31199 15589 31199 15589 31200 15588 31200 15586 31200 15589 31201 15586 31201 15590 31201 15590 31202 15586 31202 15591 31202 15590 31203 15591 31203 15634 31203 15634 31204 15591 31204 15585 31204 15592 31205 15594 31205 15601 31205 15592 31206 15593 31206 15594 31206 15594 31207 15593 31207 20526 31207 15594 31208 20526 31208 15595 31208 15595 31209 20526 31209 15596 31209 15595 31210 15596 31210 15617 31210 15596 31211 15597 31211 15617 31211 15617 31212 15597 31212 15598 31212 15617 31213 15598 31213 15534 31213 15619 31214 15636 31214 15610 31214 15599 31215 15600 31215 15604 31215 15604 31216 15600 31216 20521 31216 15604 31217 20521 31217 15601 31217 15601 31218 20521 31218 15602 31218 15601 31219 15602 31219 15592 31219 15603 31220 15599 31220 15629 31220 15629 31221 15599 31221 15604 31221 15629 31222 15604 31222 15614 31222 17426 31223 15605 31223 15681 31223 15681 31224 15605 31224 15606 31224 15681 31225 15606 31225 15678 31225 15678 31226 15606 31226 15630 31226 15678 31227 15630 31227 15607 31227 15607 31228 15630 31228 15608 31228 15607 31229 15608 31229 15609 31229 15609 31230 15608 31230 15581 31230 15609 31231 15581 31231 15680 31231 15619 31232 15610 31232 15618 31232 15618 31233 15610 31233 15635 31233 15618 31234 15635 31234 15611 31234 15611 31235 15635 31235 15633 31235 15611 31236 15633 31236 15612 31236 15612 31237 15633 31237 15632 31237 15612 31238 15632 31238 15616 31238 15616 31239 15632 31239 15613 31239 15616 31240 15613 31240 15615 31240 15615 31241 15613 31241 15631 31241 15615 31242 15631 31242 15614 31242 15614 31243 15604 31243 15615 31243 15615 31244 15604 31244 15601 31244 15615 31245 15601 31245 15616 31245 15616 31246 15601 31246 15594 31246 15616 31247 15594 31247 15612 31247 15612 31248 15594 31248 15595 31248 15612 31249 15595 31249 15611 31249 15611 31250 15595 31250 15617 31250 15611 31251 15617 31251 15618 31251 15618 31252 15617 31252 15534 31252 15618 31253 15534 31253 15619 31253 15531 31254 15537 31254 15620 31254 15620 31255 15537 31255 15621 31255 15620 31256 15621 31256 18157 31256 15587 31257 15531 31257 15588 31257 15588 31258 15531 31258 15620 31258 15588 31259 15620 31259 15622 31259 15622 31260 15620 31260 18157 31260 15622 31261 18157 31261 15591 31261 15591 31262 18157 31262 18177 31262 15591 31263 18177 31263 15623 31263 15623 31264 18177 31264 15624 31264 15623 31265 15624 31265 15582 31265 15582 31266 15624 31266 15625 31266 15582 31267 15625 31267 15626 31267 15626 31268 15625 31268 18098 31268 15626 31269 18098 31269 15581 31269 15581 31270 18098 31270 18099 31270 15581 31271 18099 31271 15680 31271 15627 31272 15628 31272 15606 31272 15606 31273 15628 31273 15629 31273 15606 31274 15629 31274 15630 31274 15630 31275 15629 31275 15614 31275 15630 31276 15614 31276 15608 31276 15608 31277 15614 31277 15631 31277 15608 31278 15631 31278 15583 31278 15583 31279 15631 31279 15613 31279 15583 31280 15613 31280 15584 31280 15584 31281 15613 31281 15632 31281 15584 31282 15632 31282 15585 31282 15585 31283 15632 31283 15633 31283 15585 31284 15633 31284 15634 31284 15634 31285 15633 31285 15635 31285 15634 31286 15635 31286 15590 31286 15590 31287 15635 31287 15610 31287 15590 31288 15610 31288 15589 31288 15589 31289 15610 31289 15636 31289 15589 31290 15636 31290 15587 31290 15677 31291 17468 31291 15698 31291 15661 31292 15663 31292 15660 31292 15660 31293 15663 31293 15666 31293 15658 31294 15545 31294 15554 31294 15664 31295 15637 31295 15677 31295 15575 31296 15551 31296 15638 31296 15545 31297 15658 31297 15639 31297 18669 31298 18667 31298 15640 31298 15640 31299 18667 31299 15570 31299 15570 31300 15575 31300 15640 31300 15640 31301 15575 31301 15638 31301 15640 31302 15638 31302 15672 31302 15672 31303 15638 31303 15641 31303 15672 31304 15641 31304 15673 31304 15673 31305 15641 31305 15667 31305 15642 31306 15675 31306 15644 31306 15674 31307 15642 31307 15643 31307 15642 31308 15644 31308 15643 31308 15643 31309 15644 31309 15645 31309 15643 31310 15645 31310 15646 31310 15646 31311 18679 31311 15643 31311 15643 31312 18679 31312 15647 31312 15643 31313 15647 31313 15674 31313 15653 31314 17412 31314 15648 31314 20527 31315 17412 31315 15649 31315 15649 31316 17412 31316 15653 31316 15649 31317 15653 31317 15650 31317 15556 31318 15650 31318 15651 31318 15651 31319 15650 31319 15653 31319 15651 31320 15653 31320 15652 31320 15652 31321 15653 31321 15648 31321 15652 31322 15648 31322 17413 31322 15659 31323 15655 31323 15554 31323 15554 31324 15655 31324 15654 31324 15554 31325 15654 31325 15658 31325 15658 31326 15654 31326 15656 31326 15659 31327 15660 31327 15655 31327 15655 31328 15660 31328 15666 31328 15655 31329 15666 31329 15654 31329 15654 31330 15666 31330 15657 31330 15654 31331 15657 31331 15656 31331 15656 31332 15657 31332 15668 31332 15656 31333 15668 31333 15658 31333 15658 31334 15668 31334 15669 31334 15658 31335 15669 31335 15639 31335 15639 31336 15669 31336 15550 31336 15554 31337 15556 31337 15659 31337 15659 31338 15556 31338 15651 31338 15659 31339 15651 31339 15660 31339 15660 31340 15651 31340 15652 31340 15660 31341 15652 31341 15661 31341 15661 31342 15652 31342 17413 31342 15661 31343 17413 31343 17415 31343 15675 31344 15676 31344 15644 31344 15644 31345 15676 31345 15697 31345 15644 31346 15697 31346 18653 31346 18653 31347 15697 31347 15662 31347 17415 31348 15637 31348 15661 31348 15661 31349 15637 31349 15664 31349 15661 31350 15664 31350 15663 31350 15663 31351 15664 31351 15665 31351 15663 31352 15665 31352 15666 31352 15666 31353 15665 31353 15667 31353 15666 31354 15667 31354 15657 31354 15657 31355 15667 31355 15641 31355 15657 31356 15641 31356 15668 31356 15668 31357 15641 31357 15638 31357 15668 31358 15638 31358 15669 31358 15669 31359 15638 31359 15551 31359 15669 31360 15551 31360 15550 31360 18669 31361 15640 31361 15670 31361 15670 31362 15640 31362 15672 31362 15670 31363 15672 31363 15671 31363 15671 31364 15672 31364 15673 31364 15671 31365 15673 31365 15647 31365 15647 31366 15673 31366 15667 31366 15647 31367 15667 31367 15674 31367 15674 31368 15667 31368 15665 31368 15674 31369 15665 31369 15642 31369 15642 31370 15665 31370 15664 31370 15642 31371 15664 31371 15675 31371 15675 31372 15664 31372 15677 31372 15675 31373 15677 31373 15676 31373 15676 31374 15677 31374 15698 31374 15676 31375 15698 31375 15697 31375 15681 31376 15678 31376 15679 31376 15607 31377 15609 31377 15684 31377 15684 31378 15609 31378 15680 31378 15689 31379 15688 31379 15683 31379 17426 31380 15681 31380 17425 31380 17425 31381 15681 31381 15679 31381 17425 31382 15679 31382 17423 31382 17423 31383 15679 31383 15682 31383 17423 31384 15682 31384 17422 31384 17422 31385 15682 31385 15687 31385 17422 31386 15687 31386 15701 31386 15701 31387 15687 31387 15690 31387 18099 31388 18100 31388 15680 31388 15680 31389 18100 31389 15683 31389 15680 31390 15683 31390 15684 31390 15684 31391 15683 31391 15688 31391 18100 31392 15685 31392 15683 31392 15683 31393 15685 31393 15686 31393 15683 31394 15686 31394 15689 31394 15689 31395 15686 31395 15703 31395 15678 31396 15607 31396 15679 31396 15679 31397 15607 31397 15684 31397 15679 31398 15684 31398 15682 31398 15682 31399 15684 31399 15688 31399 15682 31400 15688 31400 15687 31400 15687 31401 15688 31401 15689 31401 15687 31402 15689 31402 15690 31402 15690 31403 15689 31403 15703 31403 15698 31404 17468 31404 17469 31404 15693 31405 18636 31405 15691 31405 17471 31406 15737 31406 15694 31406 15694 31407 15737 31407 15692 31407 15694 31408 15692 31408 15693 31408 15693 31409 15691 31409 15694 31409 15694 31410 15691 31410 15695 31410 15694 31411 15695 31411 17472 31411 15695 31412 18642 31412 17472 31412 17472 31413 18642 31413 18641 31413 17472 31414 18641 31414 15696 31414 15696 31415 18641 31415 18639 31415 15696 31416 18639 31416 17473 31416 17473 31417 18639 31417 18649 31417 17473 31418 18649 31418 17470 31418 17470 31419 18649 31419 18647 31419 17470 31420 18647 31420 15699 31420 18650 31421 15662 31421 15697 31421 15697 31422 15698 31422 18650 31422 18650 31423 15698 31423 17469 31423 18650 31424 17469 31424 18651 31424 18651 31425 17469 31425 15699 31425 18651 31426 15699 31426 18646 31426 18646 31427 15699 31427 18647 31427 18101 31428 15740 31428 15743 31428 15704 31429 15708 31429 15700 31429 19689 31430 15701 31430 15706 31430 15706 31431 15701 31431 15690 31431 15706 31432 15690 31432 15702 31432 15702 31433 15690 31433 15703 31433 15702 31434 15703 31434 15700 31434 15700 31435 15703 31435 15686 31435 15700 31436 15686 31436 15704 31436 15704 31437 15686 31437 15685 31437 15705 31438 19689 31438 15750 31438 15750 31439 19689 31439 15706 31439 15750 31440 15706 31440 15707 31440 15707 31441 15706 31441 15702 31441 15707 31442 15702 31442 15743 31442 15743 31443 15702 31443 15700 31443 15743 31444 15700 31444 18101 31444 18101 31445 15700 31445 15708 31445 18700 31446 18635 31446 15727 31446 18635 31447 18636 31447 15693 31447 15693 31448 15692 31448 18635 31448 18635 31449 15692 31449 15735 31449 18635 31450 15735 31450 15727 31450 15727 31451 15735 31451 15734 31451 15727 31452 15734 31452 15723 31452 15723 31453 15734 31453 15710 31453 15723 31454 15710 31454 15709 31454 15709 31455 15710 31455 15711 31455 17406 31456 15731 31456 15712 31456 15712 31457 15731 31457 15732 31457 15712 31458 15732 31458 17404 31458 15737 31459 17471 31459 15736 31459 15736 31460 17471 31460 15713 31460 15736 31461 15713 31461 15714 31461 15713 31462 17403 31462 15714 31462 15714 31463 17403 31463 15715 31463 15714 31464 15715 31464 15717 31464 15717 31465 15715 31465 15716 31465 15717 31466 15716 31466 15733 31466 15733 31467 15716 31467 17404 31467 15733 31468 17404 31468 15718 31468 15718 31469 17404 31469 15732 31469 15711 31470 15729 31470 15709 31470 15709 31471 15729 31471 15719 31471 15709 31472 15719 31472 15767 31472 15767 31473 18630 31473 15709 31473 15709 31474 18630 31474 15720 31474 15709 31475 15720 31475 15723 31475 15723 31476 15720 31476 15721 31476 15723 31477 15721 31477 15722 31477 15722 31478 15724 31478 15723 31478 15723 31479 15724 31479 15725 31479 15723 31480 15725 31480 15727 31480 15727 31481 15725 31481 15726 31481 15727 31482 15726 31482 18700 31482 15728 31483 15761 31483 15729 31483 15729 31484 15761 31484 15730 31484 15729 31485 15730 31485 15719 31485 15731 31486 15728 31486 15732 31486 15732 31487 15728 31487 15729 31487 15732 31488 15729 31488 15718 31488 15718 31489 15729 31489 15711 31489 15718 31490 15711 31490 15733 31490 15733 31491 15711 31491 15710 31491 15733 31492 15710 31492 15717 31492 15717 31493 15710 31493 15734 31493 15717 31494 15734 31494 15714 31494 15714 31495 15734 31495 15735 31495 15714 31496 15735 31496 15736 31496 15736 31497 15735 31497 15692 31497 15736 31498 15692 31498 15737 31498 15753 31499 15801 31499 15746 31499 15746 31500 15801 31500 17437 31500 15738 31501 15741 31501 15739 31501 15739 31502 15741 31502 15743 31502 15739 31503 15743 31503 15740 31503 15738 31504 18106 31504 15741 31504 15741 31505 18106 31505 15814 31505 15741 31506 15814 31506 15754 31506 15754 31507 15752 31507 15741 31507 15741 31508 15752 31508 15742 31508 15741 31509 15742 31509 15743 31509 15743 31510 15742 31510 15744 31510 15743 31511 15744 31511 15707 31511 17437 31512 15745 31512 15746 31512 15746 31513 15745 31513 15748 31513 15746 31514 15748 31514 15747 31514 15747 31515 15748 31515 17438 31515 15747 31516 17438 31516 15749 31516 15749 31517 17438 31517 15751 31517 15749 31518 15751 31518 15750 31518 15750 31519 15751 31519 15705 31519 15750 31520 15707 31520 15749 31520 15749 31521 15707 31521 15744 31521 15749 31522 15744 31522 15747 31522 15747 31523 15744 31523 15742 31523 15747 31524 15742 31524 15746 31524 15746 31525 15742 31525 15752 31525 15746 31526 15752 31526 15753 31526 15753 31527 15752 31527 15754 31527 15755 31528 15846 31528 18626 31528 15759 31529 15843 31529 15850 31529 15778 31530 15780 31530 17408 31530 15835 31531 15846 31531 15769 31531 15769 31532 15846 31532 15755 31532 15769 31533 15755 31533 15756 31533 15756 31534 15755 31534 15765 31534 15778 31535 17408 31535 15757 31535 15771 31536 15757 31536 15758 31536 15758 31537 15757 31537 17408 31537 15758 31538 17408 31538 15770 31538 15770 31539 17408 31539 15759 31539 15770 31540 15759 31540 15768 31540 15768 31541 15759 31541 15850 31541 17406 31542 15760 31542 15731 31542 15731 31543 15760 31543 15779 31543 15731 31544 15779 31544 15728 31544 15728 31545 15779 31545 15777 31545 15728 31546 15777 31546 15761 31546 15761 31547 15777 31547 15762 31547 15761 31548 15762 31548 15730 31548 15730 31549 15762 31549 15763 31549 15730 31550 15763 31550 15719 31550 15719 31551 15763 31551 15764 31551 15719 31552 15764 31552 15775 31552 18626 31553 15772 31553 15755 31553 15755 31554 15772 31554 15774 31554 15755 31555 15774 31555 15765 31555 15765 31556 15774 31556 15776 31556 15765 31557 15776 31557 15766 31557 15773 31558 18631 31558 15775 31558 15775 31559 18631 31559 15767 31559 15775 31560 15767 31560 15719 31560 15850 31561 15835 31561 15768 31561 15768 31562 15835 31562 15769 31562 15768 31563 15769 31563 15770 31563 15770 31564 15769 31564 15756 31564 15770 31565 15756 31565 15758 31565 15758 31566 15756 31566 15765 31566 15758 31567 15765 31567 15771 31567 15771 31568 15765 31568 15766 31568 15772 31569 15773 31569 15774 31569 15774 31570 15773 31570 15775 31570 15774 31571 15775 31571 15776 31571 15776 31572 15775 31572 15764 31572 15776 31573 15764 31573 15766 31573 15766 31574 15764 31574 15763 31574 15766 31575 15763 31575 15771 31575 15771 31576 15763 31576 15762 31576 15771 31577 15762 31577 15757 31577 15757 31578 15762 31578 15777 31578 15757 31579 15777 31579 15778 31579 15778 31580 15777 31580 15779 31580 15778 31581 15779 31581 15780 31581 15780 31582 15779 31582 15760 31582 17434 31583 17435 31583 15800 31583 15795 31584 15781 31584 15794 31584 15794 31585 15781 31585 15782 31585 15794 31586 15782 31586 15783 31586 15783 31587 15782 31587 18103 31587 15783 31588 18103 31588 15791 31588 15791 31589 18103 31589 15784 31589 15791 31590 15784 31590 15785 31590 15785 31591 15784 31591 15786 31591 15785 31592 15786 31592 15789 31592 15789 31593 15786 31593 15787 31593 15789 31594 15787 31594 15851 31594 15851 31595 15852 31595 15789 31595 15789 31596 15852 31596 15788 31596 15789 31597 15788 31597 15785 31597 15785 31598 15788 31598 15790 31598 15785 31599 15790 31599 15791 31599 15791 31600 15790 31600 15792 31600 15791 31601 15792 31601 15783 31601 15783 31602 15792 31602 15793 31602 15783 31603 15793 31603 15794 31603 15794 31604 15793 31604 15831 31604 15794 31605 15831 31605 15795 31605 15828 31606 15811 31606 15799 31606 15799 31607 15811 31607 15813 31607 15796 31608 15830 31608 15797 31608 15797 31609 15830 31609 15828 31609 15797 31610 15828 31610 15798 31610 15798 31611 15828 31611 15799 31611 17435 31612 17437 31612 15800 31612 15800 31613 17437 31613 15801 31613 15800 31614 15801 31614 15802 31614 15802 31615 15801 31615 15753 31615 15802 31616 15753 31616 15754 31616 15807 31617 15826 31617 15803 31617 15804 31618 15805 31618 15826 31618 15826 31619 15805 31619 15806 31619 15826 31620 15806 31620 15803 31620 15803 31621 17427 31621 15807 31621 15807 31622 17427 31622 15808 31622 15807 31623 15808 31623 15809 31623 15808 31624 17429 31624 15809 31624 15809 31625 17429 31625 15810 31625 15809 31626 15810 31626 15811 31626 15811 31627 15810 31627 15812 31627 15811 31628 15812 31628 15813 31628 18106 31629 18104 31629 15814 31629 15814 31630 18104 31630 15816 31630 15814 31631 15816 31631 15815 31631 15815 31632 15816 31632 15817 31632 15815 31633 15817 31633 15829 31633 15829 31634 15817 31634 15818 31634 15829 31635 15818 31635 15827 31635 15827 31636 15818 31636 15820 31636 15827 31637 15820 31637 15819 31637 15819 31638 15820 31638 15832 31638 15819 31639 15832 31639 15821 31639 15821 31640 15832 31640 15822 31640 15821 31641 15822 31641 15823 31641 15823 31642 15822 31642 15824 31642 15823 31643 15824 31643 15825 31643 15825 31644 15824 31644 15854 31644 15825 31645 15854 31645 15804 31645 15804 31646 15826 31646 15825 31646 15825 31647 15826 31647 15807 31647 15825 31648 15807 31648 15823 31648 15823 31649 15807 31649 15809 31649 15823 31650 15809 31650 15821 31650 15821 31651 15809 31651 15811 31651 15821 31652 15811 31652 15819 31652 15819 31653 15811 31653 15828 31653 15819 31654 15828 31654 15827 31654 15827 31655 15828 31655 15830 31655 15827 31656 15830 31656 15829 31656 15796 31657 17434 31657 15830 31657 15830 31658 17434 31658 15800 31658 15830 31659 15800 31659 15829 31659 15829 31660 15800 31660 15802 31660 15829 31661 15802 31661 15815 31661 15815 31662 15802 31662 15754 31662 15815 31663 15754 31663 15814 31663 18104 31664 15781 31664 15816 31664 15816 31665 15781 31665 15795 31665 15816 31666 15795 31666 15817 31666 15817 31667 15795 31667 15831 31667 15817 31668 15831 31668 15818 31668 15818 31669 15831 31669 15793 31669 15818 31670 15793 31670 15820 31670 15820 31671 15793 31671 15792 31671 15820 31672 15792 31672 15832 31672 15832 31673 15792 31673 15790 31673 15832 31674 15790 31674 15822 31674 15822 31675 15790 31675 15788 31675 15822 31676 15788 31676 15824 31676 15824 31677 15788 31677 15852 31677 15824 31678 15852 31678 15854 31678 15833 31679 15864 31679 15845 31679 15837 31680 15847 31680 15833 31680 15846 31681 15835 31681 15834 31681 15834 31682 15835 31682 15836 31682 15834 31683 15836 31683 15844 31683 15844 31684 15836 31684 15849 31684 15844 31685 15849 31685 15837 31685 17463 31686 15862 31686 15838 31686 15838 31687 15862 31687 15840 31687 15838 31688 15840 31688 15839 31688 15839 31689 15840 31689 15841 31689 15839 31690 15841 31690 15842 31690 15842 31691 15841 31691 15848 31691 15842 31692 15848 31692 15843 31692 15843 31693 15848 31693 15850 31693 15837 31694 15833 31694 15844 31694 15844 31695 15833 31695 15845 31695 15844 31696 15845 31696 15834 31696 15834 31697 15845 31697 18626 31697 15834 31698 18626 31698 15846 31698 15862 31699 15847 31699 15840 31699 15840 31700 15847 31700 15837 31700 15840 31701 15837 31701 15841 31701 15841 31702 15837 31702 15849 31702 15841 31703 15849 31703 15848 31703 15848 31704 15849 31704 15836 31704 15848 31705 15836 31705 15850 31705 15850 31706 15836 31706 15835 31706 15787 31707 18108 31707 15851 31707 15851 31708 18108 31708 15853 31708 15851 31709 15853 31709 15852 31709 15852 31710 15853 31710 15857 31710 15852 31711 15857 31711 15854 31711 15854 31712 15857 31712 15858 31712 15854 31713 15858 31713 15804 31713 15804 31714 15858 31714 15805 31714 18108 31715 18109 31715 15853 31715 15853 31716 18109 31716 15855 31716 15853 31717 15855 31717 15857 31717 15857 31718 15855 31718 15856 31718 15857 31719 15856 31719 15858 31719 15858 31720 15856 31720 15865 31720 15858 31721 15865 31721 17466 31721 15806 31722 15805 31722 15859 31722 15859 31723 15805 31723 15858 31723 15859 31724 15858 31724 15860 31724 15860 31725 15858 31725 17466 31725 17464 31726 17465 31726 15861 31726 17463 31727 17464 31727 15862 31727 15862 31728 17464 31728 15861 31728 15862 31729 15861 31729 15847 31729 15847 31730 15861 31730 15863 31730 15847 31731 15863 31731 15833 31731 15833 31732 15863 31732 15866 31732 15833 31733 15866 31733 15864 31733 15864 31734 15866 31734 18111 31734 17467 31735 17466 31735 15865 31735 15861 31736 17465 31736 17467 31736 17467 31737 15865 31737 15861 31737 15861 31738 15865 31738 15856 31738 15861 31739 15856 31739 15863 31739 15863 31740 15856 31740 15855 31740 15863 31741 15855 31741 15866 31741 15866 31742 15855 31742 18109 31742 15866 31743 18109 31743 18111 31743 15875 31744 17626 31744 15867 31744 19673 31745 19670 31745 17626 31745 17626 31746 15875 31746 19673 31746 19673 31747 15875 31747 15874 31747 19673 31748 15874 31748 19662 31748 19662 31749 15874 31749 19661 31749 19661 31750 15874 31750 15870 31750 19661 31751 15870 31751 15868 31751 15870 31752 18413 31752 15871 31752 15868 31753 15870 31753 15869 31753 15869 31754 15870 31754 15871 31754 15869 31755 15871 31755 18417 31755 15913 31756 18413 31756 15872 31756 15872 31757 18413 31757 15870 31757 15872 31758 15870 31758 15873 31758 15873 31759 15870 31759 15874 31759 15873 31760 15874 31760 15917 31760 15917 31761 15874 31761 15875 31761 15917 31762 15875 31762 15898 31762 15898 31763 15875 31763 15867 31763 15898 31764 15867 31764 17627 31764 15927 31765 15876 31765 15914 31765 15914 31766 15876 31766 15877 31766 15914 31767 15877 31767 15878 31767 15878 31768 15877 31768 15909 31768 15878 31769 15909 31769 15915 31769 15915 31770 15909 31770 15879 31770 15915 31771 15879 31771 15880 31771 15880 31772 15879 31772 15881 31772 15880 31773 15881 31773 15882 31773 15882 31774 15881 31774 15911 31774 15882 31775 15911 31775 15883 31775 15883 31776 15911 31776 15884 31776 15883 31777 15884 31777 15885 31777 15885 31778 15884 31778 15886 31778 15885 31779 15886 31779 15873 31779 15873 31780 15886 31780 15872 31780 15907 31781 15887 31781 15888 31781 15889 31782 15891 31782 15890 31782 15890 31783 15891 31783 15887 31783 15890 31784 15887 31784 15892 31784 15892 31785 15887 31785 15907 31785 15889 31786 17633 31786 15894 31786 15894 31787 17633 31787 15893 31787 15894 31788 15893 31788 15896 31788 15893 31789 15895 31789 15896 31789 15896 31790 15895 31790 17624 31790 15896 31791 17624 31791 15920 31791 15889 31792 15894 31792 15891 31792 15891 31793 15894 31793 15896 31793 15891 31794 15896 31794 15897 31794 15897 31795 15896 31795 15920 31795 15897 31796 15920 31796 15928 31796 15917 31797 15898 31797 15901 31797 15901 31798 15898 31798 17627 31798 15901 31799 17627 31799 15902 31799 15902 31800 17627 31800 17628 31800 15902 31801 17628 31801 15903 31801 15916 31802 15899 31802 15904 31802 15917 31803 15901 31803 15900 31803 15900 31804 15901 31804 15902 31804 15900 31805 15902 31805 15899 31805 15899 31806 15902 31806 15903 31806 15899 31807 15903 31807 15904 31807 15904 31808 15905 31808 15916 31808 15916 31809 15905 31809 17629 31809 15916 31810 17629 31810 15888 31810 15888 31811 17629 31811 15906 31811 15888 31812 15906 31812 15907 31812 15876 31813 18496 31813 15877 31813 15877 31814 18496 31814 15908 31814 15877 31815 15908 31815 15909 31815 15909 31816 15908 31816 18484 31816 15909 31817 18484 31817 15879 31817 15879 31818 18484 31818 18482 31818 15879 31819 18482 31819 15881 31819 15881 31820 18482 31820 15910 31820 15881 31821 15910 31821 15911 31821 15911 31822 15910 31822 15912 31822 15911 31823 15912 31823 15884 31823 15884 31824 15912 31824 18420 31824 15884 31825 18420 31825 15886 31825 15886 31826 18420 31826 15913 31826 15886 31827 15913 31827 15872 31827 15928 31828 15927 31828 15897 31828 15897 31829 15927 31829 15914 31829 15897 31830 15914 31830 15891 31830 15891 31831 15914 31831 15878 31831 15891 31832 15878 31832 15887 31832 15887 31833 15878 31833 15915 31833 15887 31834 15915 31834 15888 31834 15888 31835 15915 31835 15880 31835 15888 31836 15880 31836 15916 31836 15916 31837 15880 31837 15882 31837 15916 31838 15882 31838 15899 31838 15899 31839 15882 31839 15883 31839 15899 31840 15883 31840 15900 31840 15900 31841 15883 31841 15885 31841 15900 31842 15885 31842 15917 31842 15917 31843 15885 31843 15873 31843 15923 31844 15924 31844 15925 31844 17623 31845 17625 31845 15918 31845 15918 31846 15919 31846 17623 31846 17623 31847 15919 31847 15920 31847 17623 31848 15920 31848 17624 31848 15918 31849 19675 31849 15919 31849 15919 31850 19675 31850 19674 31850 15919 31851 19674 31851 15926 31851 15926 31852 19674 31852 15921 31852 15926 31853 15921 31853 15925 31853 15925 31854 15921 31854 15922 31854 15925 31855 15922 31855 15923 31855 15924 31856 18496 31856 15925 31856 15925 31857 18496 31857 15876 31857 15925 31858 15876 31858 15926 31858 15926 31859 15876 31859 15927 31859 15926 31860 15927 31860 15919 31860 15919 31861 15927 31861 15928 31861 15919 31862 15928 31862 15920 31862 15932 31863 18171 31863 15934 31863 15929 31864 17659 31864 17672 31864 17672 31865 15937 31865 15929 31865 15929 31866 15937 31866 15935 31866 15929 31867 15935 31867 17660 31867 17660 31868 15935 31868 15930 31868 15930 31869 15935 31869 15934 31869 15930 31870 15934 31870 17653 31870 17653 31871 15934 31871 15931 31871 15931 31872 15934 31872 18171 31872 15931 31873 18171 31873 18159 31873 18173 31874 15932 31874 15933 31874 15933 31875 15932 31875 15934 31875 15933 31876 15934 31876 15936 31876 15936 31877 15934 31877 15935 31877 15936 31878 15935 31878 15979 31878 15979 31879 15935 31879 15937 31879 15979 31880 15937 31880 15955 31880 15955 31881 15937 31881 17672 31881 15955 31882 17672 31882 17673 31882 15938 31883 17674 31883 15954 31883 15964 31884 15942 31884 15962 31884 15972 31885 15940 31885 15939 31885 15939 31886 15940 31886 15942 31886 15939 31887 15942 31887 15941 31887 15941 31888 15942 31888 15964 31888 15941 31889 15964 31889 15974 31889 15974 31890 15964 31890 15967 31890 15974 31891 15967 31891 15975 31891 15975 31892 15967 31892 15943 31892 15975 31893 15943 31893 15944 31893 15944 31894 15943 31894 15968 31894 15944 31895 15968 31895 15977 31895 15977 31896 15968 31896 15969 31896 15977 31897 15969 31897 15978 31897 15978 31898 15969 31898 15971 31898 15978 31899 15971 31899 15936 31899 15936 31900 15971 31900 15933 31900 15945 31901 15951 31901 17684 31901 17684 31902 15951 31902 15948 31902 15959 31903 17685 31903 15948 31903 15948 31904 17685 31904 15946 31904 15948 31905 15946 31905 17684 31905 15945 31906 17688 31906 15951 31906 15951 31907 17688 31907 15947 31907 15951 31908 15947 31908 15952 31908 15947 31909 17687 31909 15952 31909 15952 31910 17687 31910 17686 31910 15952 31911 17686 31911 15953 31911 15959 31912 15948 31912 15949 31912 15949 31913 15948 31913 15951 31913 15949 31914 15951 31914 15950 31914 15950 31915 15951 31915 15952 31915 15950 31916 15952 31916 15973 31916 15973 31917 15952 31917 15953 31917 15973 31918 15953 31918 15986 31918 15956 31919 15979 31919 15954 31919 15954 31920 15979 31920 15955 31920 15954 31921 15955 31921 15938 31921 15938 31922 15955 31922 17673 31922 15976 31923 15956 31923 15957 31923 15957 31924 15956 31924 15954 31924 15957 31925 15954 31925 17675 31925 17675 31926 15954 31926 17674 31926 15961 31927 15958 31927 15959 31927 15959 31928 15958 31928 17680 31928 15959 31929 17680 31929 17685 31929 17675 31930 17677 31930 15957 31930 15957 31931 17677 31931 15960 31931 15957 31932 15960 31932 15976 31932 15976 31933 15960 31933 17679 31933 15976 31934 17679 31934 15961 31934 15961 31935 17679 31935 17682 31935 15961 31936 17682 31936 15958 31936 15962 31937 15942 31937 15963 31937 15963 31938 15942 31938 15940 31938 15963 31939 15940 31939 15983 31939 15962 31940 15965 31940 15964 31940 15964 31941 15965 31941 15966 31941 15964 31942 15966 31942 15967 31942 15967 31943 15966 31943 18209 31943 15967 31944 18209 31944 15943 31944 15943 31945 18209 31945 18168 31945 15943 31946 18168 31946 15968 31946 15968 31947 18168 31947 15970 31947 15968 31948 15970 31948 15969 31948 15969 31949 15970 31949 18175 31949 15969 31950 18175 31950 15971 31950 15971 31951 18175 31951 18173 31951 15971 31952 18173 31952 15933 31952 15986 31953 15972 31953 15973 31953 15973 31954 15972 31954 15939 31954 15973 31955 15939 31955 15950 31955 15950 31956 15939 31956 15941 31956 15950 31957 15941 31957 15949 31957 15949 31958 15941 31958 15974 31958 15949 31959 15974 31959 15959 31959 15959 31960 15974 31960 15975 31960 15959 31961 15975 31961 15961 31961 15961 31962 15975 31962 15944 31962 15961 31963 15944 31963 15976 31963 15976 31964 15944 31964 15977 31964 15976 31965 15977 31965 15956 31965 15956 31966 15977 31966 15978 31966 15956 31967 15978 31967 15979 31967 15979 31968 15978 31968 15936 31968 15981 31969 17668 31969 15980 31969 15980 31970 15985 31970 15981 31970 15981 31971 15985 31971 15953 31971 15981 31972 15953 31972 17686 31972 15984 31973 17663 31973 15982 31973 15982 31974 17663 31974 18219 31974 15982 31975 18219 31975 18218 31975 15980 31976 17667 31976 15985 31976 15985 31977 17667 31977 17666 31977 15985 31978 17666 31978 15984 31978 15984 31979 17666 31979 17665 31979 15984 31980 17665 31980 17663 31980 18218 31981 15983 31981 15982 31981 15982 31982 15983 31982 15940 31982 15982 31983 15940 31983 15984 31983 15984 31984 15940 31984 15972 31984 15984 31985 15972 31985 15985 31985 15985 31986 15972 31986 15986 31986 15985 31987 15986 31987 15953 31987 15987 31988 17641 31988 15995 31988 15995 31989 15994 31989 15987 31989 15987 31990 15994 31990 15992 31990 15987 31991 15992 31991 19638 31991 19638 31992 15992 31992 15988 31992 15988 31993 15992 31993 15991 31993 15988 31994 15991 31994 19628 31994 19628 31995 15991 31995 15989 31995 15989 31996 15991 31996 18164 31996 15989 31997 18164 31997 18162 31997 18165 31998 18164 31998 15997 31998 15997 31999 18164 31999 15991 31999 15997 32000 15991 32000 15990 32000 15990 32001 15991 32001 15992 32001 15990 32002 15992 32002 15993 32002 15993 32003 15992 32003 15994 32003 15993 32004 15994 32004 17640 32004 17640 32005 15994 32005 15995 32005 16001 32006 18165 32006 15996 32006 15996 32007 18165 32007 15997 32007 15996 32008 15997 32008 15999 32008 15999 32009 15997 32009 15990 32009 15999 32010 15990 32010 15998 32010 15998 32011 15990 32011 15993 32011 15998 32012 15993 32012 17642 32012 17642 32013 15993 32013 17640 32013 17642 32014 17643 32014 15998 32014 15998 32015 17643 32015 16007 32015 15998 32016 16007 32016 15999 32016 15999 32017 16007 32017 16000 32017 15999 32018 16000 32018 15996 32018 15996 32019 16000 32019 16008 32019 15996 32020 16008 32020 16001 32020 16001 32021 16008 32021 18607 32021 16004 32022 16012 32022 16010 32022 18606 32023 18607 32023 16008 32023 16009 32024 16006 32024 16002 32024 16002 32025 16006 32025 16003 32025 16002 32026 16003 32026 17644 32026 18606 32027 16008 32027 16011 32027 16005 32028 18656 32028 16004 32028 16004 32029 16010 32029 16005 32029 16005 32030 16010 32030 16009 32030 16005 32031 16009 32031 16026 32031 16026 32032 16009 32032 16002 32032 16026 32033 16002 32033 16038 32033 16038 32034 16002 32034 17644 32034 16038 32035 17644 32035 16036 32035 17643 32036 16003 32036 16007 32036 16007 32037 16003 32037 16006 32037 16007 32038 16006 32038 16000 32038 16000 32039 16006 32039 16009 32039 16000 32040 16009 32040 16008 32040 16008 32041 16009 32041 16010 32041 16008 32042 16010 32042 16011 32042 16011 32043 16010 32043 16012 32043 16045 32044 16043 32044 16022 32044 16022 32045 16043 32045 17650 32045 16037 32046 17646 32046 16039 32046 16039 32047 17646 32047 16013 32047 16039 32048 16013 32048 16040 32048 16040 32049 16013 32049 17645 32049 16040 32050 17645 32050 16041 32050 16041 32051 17645 32051 17648 32051 16041 32052 17648 32052 16043 32052 16043 32053 17648 32053 17649 32053 16043 32054 17649 32054 17650 32054 16014 32055 16026 32055 16038 32055 16027 32056 16005 32056 16026 32056 16015 32057 18656 32057 16005 32057 16005 32058 16027 32058 16015 32058 16015 32059 16027 32059 16029 32059 16015 32060 16029 32060 16016 32060 16016 32061 16029 32061 16030 32061 16016 32062 16030 32062 16018 32062 16018 32063 16030 32063 16017 32063 16018 32064 16017 32064 16019 32064 16019 32065 16017 32065 16031 32065 16019 32066 16031 32066 18096 32066 18096 32067 16031 32067 16033 32067 18096 32068 16033 32068 18156 32068 18156 32069 16033 32069 16020 32069 18156 32070 16020 32070 18154 32070 18154 32071 16020 32071 16035 32071 18154 32072 16035 32072 18153 32072 16021 32073 17651 32073 16048 32073 16048 32074 17651 32074 16062 32074 16045 32075 16022 32075 16023 32075 16023 32076 16022 32076 16024 32076 16023 32077 16024 32077 16048 32077 16048 32078 16024 32078 16025 32078 16048 32079 16025 32079 16021 32079 16026 32080 16014 32080 16027 32080 16027 32081 16014 32081 16028 32081 16027 32082 16028 32082 16029 32082 16029 32083 16028 32083 16042 32083 16029 32084 16042 32084 16030 32084 16030 32085 16042 32085 16044 32085 16030 32086 16044 32086 16017 32086 16017 32087 16044 32087 16046 32087 16017 32088 16046 32088 16031 32088 16031 32089 16046 32089 16047 32089 16031 32090 16047 32090 16033 32090 16033 32091 16047 32091 16032 32091 16033 32092 16032 32092 16020 32092 16020 32093 16032 32093 16034 32093 16020 32094 16034 32094 16035 32094 16036 32095 16037 32095 16038 32095 16038 32096 16037 32096 16039 32096 16038 32097 16039 32097 16014 32097 16014 32098 16039 32098 16040 32098 16014 32099 16040 32099 16028 32099 16028 32100 16040 32100 16041 32100 16028 32101 16041 32101 16042 32101 16042 32102 16041 32102 16043 32102 16042 32103 16043 32103 16044 32103 16044 32104 16043 32104 16045 32104 16044 32105 16045 32105 16046 32105 16046 32106 16045 32106 16023 32106 16046 32107 16023 32107 16047 32107 16047 32108 16023 32108 16048 32108 16047 32109 16048 32109 16032 32109 16032 32110 16048 32110 16062 32110 16032 32111 16062 32111 16034 32111 19637 32112 16054 32112 16049 32112 16049 32113 16054 32113 16050 32113 16051 32114 19639 32114 16052 32114 16052 32115 19639 32115 16053 32115 16052 32116 16053 32116 16056 32116 16054 32117 16055 32117 16050 32117 16050 32118 16055 32118 19636 32118 16050 32119 19636 32119 16051 32119 16051 32120 19636 32120 19640 32120 16051 32121 19640 32121 19639 32121 16056 32122 16057 32122 16052 32122 16052 32123 16057 32123 16058 32123 16052 32124 16058 32124 16051 32124 16051 32125 16058 32125 16059 32125 16051 32126 16059 32126 16050 32126 16050 32127 16059 32127 16060 32127 16050 32128 16060 32128 16049 32128 16049 32129 16060 32129 16061 32129 17651 32130 16061 32130 16062 32130 16062 32131 16061 32131 16060 32131 16062 32132 16060 32132 16034 32132 16034 32133 16060 32133 16059 32133 16034 32134 16059 32134 16035 32134 16035 32135 16059 32135 16058 32135 16035 32136 16058 32136 18153 32136 18153 32137 16058 32137 16057 32137 16075 32138 17732 32138 16093 32138 16063 32139 17729 32139 17733 32139 17733 32140 16071 32140 16063 32140 16063 32141 16071 32141 16065 32141 16063 32142 16065 32142 16064 32142 16064 32143 16065 32143 16066 32143 16066 32144 16065 32144 16069 32144 16066 32145 16069 32145 17714 32145 17714 32146 16069 32146 16067 32146 16067 32147 16069 32147 18191 32147 16067 32148 18191 32148 18193 32148 16068 32149 18191 32149 16074 32149 16074 32150 18191 32150 16069 32150 16074 32151 16069 32151 16070 32151 16070 32152 16069 32152 16065 32152 16070 32153 16065 32153 16075 32153 16075 32154 16065 32154 16071 32154 16075 32155 16071 32155 17732 32155 17732 32156 16071 32156 17733 32156 18190 32157 16068 32157 16072 32157 16072 32158 16068 32158 16074 32158 16072 32159 16074 32159 16073 32159 16073 32160 16074 32160 16070 32160 16073 32161 16070 32161 16116 32161 16116 32162 16070 32162 16075 32162 16116 32163 16075 32163 16092 32163 16092 32164 16075 32164 16093 32164 16077 32165 16130 32165 16103 32165 16108 32166 18190 32166 16072 32166 16111 32167 16130 32167 16076 32167 16076 32168 16130 32168 16077 32168 16076 32169 16077 32169 16078 32169 16078 32170 16077 32170 16104 32170 16078 32171 16104 32171 16079 32171 16079 32172 16104 32172 16080 32172 16079 32173 16080 32173 16112 32173 16112 32174 16080 32174 16105 32174 16112 32175 16105 32175 16114 32175 16114 32176 16105 32176 16081 32176 16114 32177 16081 32177 16115 32177 16115 32178 16081 32178 16109 32178 16115 32179 16109 32179 16117 32179 16117 32180 16109 32180 16110 32180 16117 32181 16110 32181 16073 32181 16084 32182 16097 32182 16082 32182 16082 32183 16097 32183 16083 32183 16082 32184 19853 32184 16084 32184 16084 32185 19853 32185 16086 32185 16084 32186 16086 32186 16085 32186 16085 32187 16086 32187 16087 32187 16089 32188 16087 32188 19850 32188 16089 32189 19850 32189 16090 32189 16090 32190 19850 32190 16088 32190 16090 32191 16088 32191 16135 32191 16087 32192 16089 32192 16085 32192 16085 32193 16089 32193 16090 32193 16085 32194 16090 32194 16091 32194 16091 32195 16090 32195 16135 32195 16091 32196 16135 32196 16134 32196 16094 32197 16101 32197 19849 32197 19849 32198 16101 32198 16092 32198 19849 32199 16092 32199 16093 32199 19849 32200 19847 32200 16094 32200 16094 32201 19847 32201 16095 32201 16094 32202 16095 32202 16099 32202 16099 32203 16095 32203 16096 32203 16099 32204 16096 32204 16098 32204 16083 32205 16097 32205 16098 32205 16098 32206 16097 32206 16113 32206 16098 32207 16113 32207 16099 32207 16099 32208 16113 32208 16100 32208 16099 32209 16100 32209 16094 32209 16094 32210 16100 32210 16102 32210 16094 32211 16102 32211 16101 32211 16101 32212 16102 32212 16116 32212 16101 32213 16116 32213 16092 32213 16103 32214 18117 32214 16077 32214 16077 32215 18117 32215 18116 32215 16077 32216 18116 32216 16104 32216 16104 32217 18116 32217 18114 32217 16104 32218 18114 32218 16080 32218 18114 32219 18113 32219 16080 32219 16080 32220 18113 32220 16106 32220 16080 32221 16106 32221 16105 32221 16105 32222 16106 32222 18112 32222 16105 32223 18112 32223 16081 32223 16081 32224 18112 32224 16107 32224 16081 32225 16107 32225 16109 32225 16109 32226 16107 32226 16108 32226 16109 32227 16108 32227 16110 32227 16110 32228 16108 32228 16072 32228 16110 32229 16072 32229 16073 32229 16134 32230 16111 32230 16091 32230 16091 32231 16111 32231 16076 32231 16091 32232 16076 32232 16085 32232 16085 32233 16076 32233 16078 32233 16085 32234 16078 32234 16084 32234 16084 32235 16078 32235 16079 32235 16084 32236 16079 32236 16097 32236 16097 32237 16079 32237 16112 32237 16097 32238 16112 32238 16113 32238 16113 32239 16112 32239 16114 32239 16113 32240 16114 32240 16100 32240 16100 32241 16114 32241 16115 32241 16100 32242 16115 32242 16102 32242 16102 32243 16115 32243 16117 32243 16102 32244 16117 32244 16116 32244 16116 32245 16117 32245 16073 32245 18120 32246 18119 32246 16120 32246 16133 32247 16128 32247 16132 32247 17730 32248 16118 32248 16127 32248 16127 32249 16118 32249 16121 32249 16119 32250 18120 32250 17715 32250 17715 32251 18120 32251 16120 32251 17715 32252 16120 32252 16124 32252 16118 32253 16122 32253 16121 32253 16121 32254 16122 32254 16123 32254 16121 32255 16123 32255 16124 32255 16124 32256 16123 32256 16125 32256 16124 32257 16125 32257 17715 32257 18119 32258 16126 32258 16120 32258 16120 32259 16126 32259 16129 32259 16120 32260 16129 32260 16124 32260 16124 32261 16129 32261 16131 32261 16124 32262 16131 32262 16121 32262 16121 32263 16131 32263 16132 32263 16121 32264 16132 32264 16127 32264 16127 32265 16132 32265 16128 32265 16126 32266 16103 32266 16129 32266 16129 32267 16103 32267 16130 32267 16129 32268 16130 32268 16131 32268 16131 32269 16130 32269 16111 32269 16131 32270 16111 32270 16132 32270 16132 32271 16111 32271 16134 32271 16132 32272 16134 32272 16133 32272 16133 32273 16134 32273 16135 32273 16133 32274 16135 32274 16088 32274 16143 32275 16141 32275 16138 32275 16145 32276 16136 32276 16144 32276 19627 32277 16136 32277 16139 32277 16139 32278 16136 32278 16145 32278 16139 32279 16145 32279 16138 32279 16140 32280 16137 32280 16141 32280 16141 32281 16137 32281 19621 32281 16141 32282 19621 32282 16138 32282 16138 32283 19621 32283 19620 32283 16138 32284 19620 32284 16139 32284 18181 32285 16140 32285 18183 32285 18183 32286 16140 32286 16141 32286 18183 32287 16141 32287 16142 32287 16142 32288 16141 32288 16143 32288 16142 32289 16143 32289 18184 32289 16144 32290 16155 32290 16145 32290 16145 32291 16155 32291 16146 32291 16145 32292 16146 32292 16138 32292 16138 32293 16146 32293 16168 32293 16138 32294 16168 32294 16143 32294 16143 32295 16168 32295 16147 32295 16143 32296 16147 32296 18184 32296 16160 32297 16159 32297 18091 32297 16177 32298 19860 32298 16148 32298 16169 32299 16171 32299 16180 32299 16151 32300 16149 32300 16181 32300 16181 32301 16149 32301 16150 32301 16181 32302 16150 32302 16180 32302 16180 32303 16150 32303 19858 32303 16180 32304 19858 32304 16169 32304 16151 32305 16181 32305 16152 32305 16152 32306 16181 32306 16153 32306 16152 32307 16153 32307 16154 32307 16154 32308 16153 32308 16155 32308 16154 32309 16155 32309 16144 32309 18184 32310 16147 32310 16167 32310 16163 32311 16189 32311 16156 32311 16156 32312 16189 32312 16157 32312 16156 32313 16157 32313 16165 32313 16165 32314 16157 32314 18186 32314 16165 32315 18186 32315 16167 32315 16167 32316 18186 32316 18185 32316 16167 32317 18185 32317 18184 32317 16158 32318 16159 32318 16192 32318 16192 32319 16159 32319 16160 32319 16192 32320 16160 32320 16193 32320 16193 32321 16160 32321 16185 32321 16193 32322 16185 32322 16162 32322 16162 32323 16185 32323 16161 32323 16162 32324 16161 32324 16164 32324 16164 32325 16161 32325 16163 32325 16164 32326 16163 32326 16194 32326 16194 32327 16163 32327 16156 32327 16194 32328 16156 32328 16195 32328 16195 32329 16156 32329 16165 32329 16195 32330 16165 32330 16166 32330 16166 32331 16165 32331 16167 32331 16166 32332 16167 32332 16168 32332 16168 32333 16167 32333 16147 32333 16169 32334 16170 32334 16171 32334 16171 32335 16170 32335 19862 32335 16171 32336 19862 32336 16172 32336 16172 32337 19862 32337 16173 32337 16172 32338 16173 32338 16176 32338 16176 32339 16173 32339 19860 32339 16177 32340 16148 32340 16174 32340 16174 32341 16148 32341 16175 32341 16174 32342 16175 32342 16198 32342 19860 32343 16177 32343 16176 32343 16176 32344 16177 32344 16174 32344 16176 32345 16174 32345 16191 32345 16191 32346 16174 32346 16198 32346 16191 32347 16198 32347 16190 32347 16171 32348 16178 32348 16180 32348 16180 32349 16178 32349 16179 32349 16180 32350 16179 32350 16181 32350 16181 32351 16179 32351 16182 32351 16181 32352 16182 32352 16153 32352 16153 32353 16182 32353 16146 32353 16153 32354 16146 32354 16155 32354 18091 32355 16183 32355 16160 32355 16160 32356 16183 32356 16184 32356 16160 32357 16184 32357 16185 32357 16185 32358 16184 32358 16186 32358 16185 32359 16186 32359 16161 32359 16161 32360 16186 32360 16187 32360 16161 32361 16187 32361 16163 32361 16163 32362 16187 32362 16188 32362 16163 32363 16188 32363 16189 32363 16190 32364 16158 32364 16191 32364 16191 32365 16158 32365 16192 32365 16191 32366 16192 32366 16176 32366 16176 32367 16192 32367 16193 32367 16176 32368 16193 32368 16172 32368 16172 32369 16193 32369 16162 32369 16172 32370 16162 32370 16171 32370 16171 32371 16162 32371 16164 32371 16171 32372 16164 32372 16178 32372 16178 32373 16164 32373 16194 32373 16178 32374 16194 32374 16179 32374 16179 32375 16194 32375 16195 32375 16179 32376 16195 32376 16182 32376 16182 32377 16195 32377 16166 32377 16182 32378 16166 32378 16146 32378 16146 32379 16166 32379 16168 32379 16201 32380 16207 32380 16203 32380 17712 32381 16196 32381 16197 32381 16197 32382 16196 32382 16205 32382 16175 32383 16206 32383 16198 32383 16198 32384 16206 32384 16208 32384 16202 32385 19617 32385 16199 32385 16199 32386 19617 32386 19610 32386 16196 32387 19614 32387 16205 32387 16205 32388 19614 32388 16200 32388 16205 32389 16200 32389 16202 32389 16202 32390 16200 32390 19618 32390 16202 32391 19618 32391 19617 32391 16201 32392 16203 32392 18180 32392 19610 32393 18180 32393 16199 32393 16199 32394 18180 32394 16203 32394 16199 32395 16203 32395 16202 32395 16202 32396 16203 32396 16204 32396 16202 32397 16204 32397 16205 32397 16205 32398 16204 32398 16208 32398 16205 32399 16208 32399 16197 32399 16197 32400 16208 32400 16206 32400 16207 32401 18091 32401 16203 32401 16203 32402 18091 32402 16159 32402 16203 32403 16159 32403 16204 32403 16204 32404 16159 32404 16158 32404 16204 32405 16158 32405 16208 32405 16208 32406 16158 32406 16190 32406 16208 32407 16190 32407 16198 32407 16209 32408 19870 32408 16218 32408 17711 32409 17710 32409 16223 32409 16223 32410 17710 32410 17709 32410 16210 32411 16211 32411 16242 32411 16212 32412 17705 32412 16227 32412 16212 32413 16227 32413 16228 32413 18129 32414 16213 32414 16214 32414 16222 32415 16223 32415 16216 32415 16216 32416 16223 32416 17709 32416 16216 32417 17709 32417 16217 32417 19871 32418 16222 32418 16215 32418 16215 32419 16222 32419 16216 32419 16215 32420 16216 32420 19869 32420 19869 32421 16216 32421 16217 32421 19869 32422 16217 32422 17708 32422 19870 32423 16210 32423 16218 32423 16218 32424 16210 32424 16242 32424 16218 32425 16242 32425 16226 32425 16226 32426 16242 32426 16219 32426 16226 32427 16219 32427 16214 32427 16214 32428 16219 32428 16220 32428 16214 32429 16220 32429 18129 32429 19871 32430 16221 32430 16222 32430 16222 32431 16221 32431 16225 32431 16222 32432 16225 32432 16223 32432 16223 32433 16225 32433 16224 32433 16223 32434 16224 32434 17711 32434 17711 32435 16224 32435 16227 32435 17711 32436 16227 32436 17704 32436 17704 32437 16227 32437 17705 32437 16221 32438 16209 32438 16225 32438 16225 32439 16209 32439 16218 32439 16225 32440 16218 32440 16224 32440 16224 32441 16218 32441 16226 32441 16224 32442 16226 32442 16227 32442 16227 32443 16226 32443 16214 32443 16227 32444 16214 32444 16228 32444 16228 32445 16214 32445 16213 32445 16246 32446 16256 32446 16238 32446 16243 32447 16230 32447 16229 32447 16229 32448 16230 32448 16250 32448 16244 32449 19865 32449 16243 32449 19865 32450 16244 32450 16231 32450 18130 32451 18129 32451 16220 32451 18130 32452 16233 32452 16232 32452 16232 32453 16233 32453 16235 32453 16232 32454 16235 32454 16234 32454 16237 32455 16234 32455 16239 32455 16239 32456 16234 32456 16235 32456 16239 32457 16235 32457 16236 32457 16236 32458 16235 32458 16233 32458 18127 32459 16237 32459 16238 32459 16238 32460 16237 32460 16239 32460 16238 32461 16239 32461 16246 32461 16246 32462 16239 32462 16236 32462 16246 32463 16236 32463 16240 32463 16240 32464 16236 32464 16241 32464 16220 32465 16219 32465 16249 32465 16249 32466 16219 32466 16242 32466 16249 32467 16242 32467 16245 32467 16243 32468 16229 32468 16244 32468 16244 32469 16229 32469 16245 32469 16244 32470 16245 32470 16231 32470 16231 32471 16245 32471 16242 32471 16231 32472 16242 32472 16211 32472 16240 32473 16247 32473 16246 32473 16246 32474 16247 32474 16248 32474 16246 32475 16248 32475 16256 32475 16256 32476 16248 32476 16255 32476 18130 32477 16220 32477 16233 32477 16233 32478 16220 32478 16249 32478 16233 32479 16249 32479 16236 32479 16236 32480 16249 32480 16245 32480 16236 32481 16245 32481 16241 32481 16241 32482 16245 32482 16229 32482 16241 32483 16229 32483 16240 32483 16240 32484 16229 32484 16250 32484 16240 32485 16250 32485 16247 32485 16247 32486 16250 32486 16251 32486 16247 32487 16251 32487 16248 32487 16248 32488 16251 32488 16252 32488 16248 32489 16252 32489 16255 32489 18126 32490 18127 32490 16238 32490 16255 32491 16252 32491 17702 32491 18195 32492 18126 32492 19583 32492 19583 32493 18126 32493 16238 32493 19583 32494 16238 32494 16256 32494 17703 32495 19592 32495 17702 32495 17702 32496 19592 32496 16253 32496 17702 32497 16253 32497 16255 32497 16255 32498 16253 32498 16254 32498 16255 32499 16254 32499 16256 32499 16256 32500 16254 32500 16257 32500 16256 32501 16257 32501 19583 32501 16259 32502 16258 32502 16260 32502 16261 32503 20834 32503 16259 32503 16259 32504 16260 32504 16261 32504 16261 32505 16260 32505 16270 32505 16261 32506 16270 32506 20832 32506 20832 32507 16270 32507 16263 32507 20832 32508 16263 32508 16262 32508 16262 32509 16263 32509 16264 32509 16264 32510 16263 32510 16268 32510 16264 32511 16268 32511 18601 32511 18599 32512 18600 32512 16265 32512 16265 32513 18600 32513 16266 32513 16265 32514 16266 32514 16275 32514 16275 32515 16266 32515 16269 32515 16275 32516 16269 32516 16285 32516 16285 32517 16269 32517 16267 32517 16285 32518 16267 32518 16284 32518 16284 32519 16267 32519 17638 32519 16284 32520 17638 32520 17637 32520 18600 32521 16268 32521 16266 32521 16266 32522 16268 32522 16263 32522 16266 32523 16263 32523 16269 32523 16269 32524 16263 32524 16270 32524 16269 32525 16270 32525 16267 32525 16267 32526 16270 32526 16260 32526 16267 32527 16260 32527 17638 32527 17638 32528 16260 32528 16258 32528 18444 32529 16288 32529 16276 32529 16300 32530 16278 32530 16271 32530 16271 32531 16278 32531 19872 32531 18444 32532 16276 32532 16272 32532 16272 32533 16276 32533 16306 32533 16272 32534 16306 32534 16301 32534 16273 32535 18599 32535 16289 32535 16289 32536 18599 32536 16265 32536 16289 32537 16265 32537 16274 32537 16274 32538 16265 32538 16275 32538 16274 32539 16275 32539 16285 32539 16288 32540 16287 32540 16276 32540 16276 32541 16287 32541 16279 32541 16276 32542 16279 32542 16306 32542 16306 32543 16279 32543 16309 32543 19872 32544 16278 32544 19878 32544 19878 32545 16278 32545 16280 32545 19878 32546 16280 32546 16277 32546 16277 32547 16280 32547 16281 32547 16277 32548 16281 32548 19880 32548 19880 32549 16281 32549 16282 32549 19880 32550 16282 32550 19877 32550 16300 32551 16309 32551 16278 32551 16278 32552 16309 32552 16279 32552 16278 32553 16279 32553 16280 32553 16280 32554 16279 32554 16287 32554 16280 32555 16287 32555 16281 32555 16281 32556 16287 32556 16286 32556 16281 32557 16286 32557 16282 32557 16282 32558 16286 32558 16283 32558 16282 32559 16283 32559 19877 32559 17637 32560 19877 32560 16284 32560 16284 32561 19877 32561 16283 32561 16284 32562 16283 32562 16285 32562 16285 32563 16283 32563 16286 32563 16285 32564 16286 32564 16274 32564 16274 32565 16286 32565 16287 32565 16274 32566 16287 32566 16289 32566 16289 32567 16287 32567 16288 32567 16289 32568 16288 32568 16273 32568 16273 32569 16288 32569 18444 32569 16298 32570 16290 32570 16291 32570 16291 32571 16290 32571 16292 32571 16291 32572 16292 32572 16317 32572 16317 32573 16292 32573 16294 32573 16317 32574 16294 32574 16293 32574 16293 32575 16294 32575 16295 32575 16293 32576 16295 32576 16336 32576 16296 32577 16297 32577 16298 32577 16298 32578 16297 32578 16299 32578 16298 32579 16299 32579 16290 32579 16300 32580 16271 32580 16314 32580 16315 32581 19874 32581 16296 32581 16296 32582 19874 32582 19873 32582 16296 32583 19873 32583 16297 32583 16305 32584 16301 32584 16306 32584 16302 32585 18239 32585 16312 32585 16312 32586 18239 32586 16303 32586 16312 32587 16303 32587 16304 32587 16304 32588 16303 32588 16305 32588 16304 32589 16305 32589 16310 32589 16310 32590 16305 32590 16306 32590 16310 32591 16306 32591 16309 32591 16308 32592 16307 32592 16302 32592 16302 32593 16312 32593 16308 32593 16308 32594 16312 32594 16318 32594 16308 32595 16318 32595 16316 32595 16309 32596 16322 32596 16310 32596 16310 32597 16322 32597 16311 32597 16310 32598 16311 32598 16304 32598 16304 32599 16311 32599 16319 32599 16304 32600 16319 32600 16312 32600 16312 32601 16319 32601 16313 32601 16312 32602 16313 32602 16318 32602 16314 32603 16315 32603 16300 32603 16300 32604 16315 32604 16296 32604 16300 32605 16296 32605 16321 32605 16321 32606 16296 32606 16298 32606 16321 32607 16298 32607 16320 32607 16320 32608 16298 32608 16291 32608 16336 32609 16316 32609 16293 32609 16293 32610 16316 32610 16318 32610 16293 32611 16318 32611 16317 32611 16317 32612 16318 32612 16313 32612 16317 32613 16313 32613 16291 32613 16291 32614 16313 32614 16319 32614 16291 32615 16319 32615 16320 32615 16320 32616 16319 32616 16311 32616 16320 32617 16311 32617 16321 32617 16321 32618 16311 32618 16322 32618 16321 32619 16322 32619 16300 32619 16300 32620 16322 32620 16309 32620 16327 32621 16329 32621 16328 32621 17636 32622 16323 32622 16325 32622 16325 32623 16323 32623 17635 32623 16336 32624 16295 32624 17636 32624 17635 32625 16324 32625 16325 32625 16325 32626 16324 32626 19642 32626 16325 32627 19642 32627 16326 32627 16332 32628 16333 32628 16328 32628 16328 32629 16333 32629 16335 32629 16328 32630 16335 32630 16327 32630 16327 32631 16335 32631 19648 32631 16331 32632 16332 32632 18236 32632 18236 32633 16332 32633 16328 32633 18236 32634 16328 32634 18237 32634 18237 32635 16328 32635 16329 32635 18237 32636 16329 32636 19641 32636 16331 32637 16330 32637 16337 32637 16331 32638 16337 32638 16332 32638 16332 32639 16337 32639 16334 32639 16332 32640 16334 32640 16333 32640 16333 32641 16334 32641 16325 32641 16333 32642 16325 32642 16335 32642 16335 32643 16325 32643 16326 32643 16335 32644 16326 32644 19648 32644 17636 32645 16325 32645 16336 32645 16336 32646 16325 32646 16334 32646 16336 32647 16334 32647 16316 32647 16316 32648 16334 32648 16337 32648 16316 32649 16337 32649 16308 32649 16308 32650 16337 32650 16330 32650 16308 32651 16330 32651 16307 32651 16338 32652 17698 32652 16364 32652 16350 32653 17699 32653 16338 32653 16350 32654 16338 32654 16339 32654 16339 32655 16338 32655 16364 32655 16339 32656 16364 32656 16348 32656 16348 32657 16364 32657 16341 32657 16348 32658 16341 32658 16340 32658 16340 32659 16341 32659 16367 32659 16340 32660 16367 32660 16346 32660 16346 32661 16367 32661 16345 32661 16345 32662 16367 32662 16342 32662 16361 32663 16343 32663 16344 32663 16350 32664 16339 32664 16351 32664 16345 32665 18252 32665 16352 32665 16345 32666 16352 32666 16346 32666 16346 32667 16352 32667 16347 32667 16346 32668 16347 32668 16340 32668 16351 32669 16339 32669 16347 32669 16347 32670 16339 32670 16348 32670 16347 32671 16348 32671 16340 32671 17699 32672 16350 32672 16349 32672 16349 32673 16350 32673 16351 32673 16349 32674 16351 32674 17700 32674 17700 32675 16351 32675 16354 32675 16353 32676 16360 32676 17696 32676 18252 32677 18253 32677 16352 32677 16352 32678 18253 32678 16356 32678 16352 32679 16356 32679 16347 32679 16347 32680 16356 32680 16357 32680 16347 32681 16357 32681 16351 32681 16351 32682 16357 32682 16353 32682 16351 32683 16353 32683 16354 32683 16354 32684 16353 32684 17696 32684 18253 32685 16355 32685 16356 32685 16356 32686 16355 32686 16358 32686 16356 32687 16358 32687 16357 32687 16357 32688 16358 32688 16359 32688 16357 32689 16359 32689 16353 32689 16353 32690 16359 32690 16344 32690 16353 32691 16344 32691 16360 32691 16360 32692 16344 32692 16343 32692 16368 32693 16361 32693 16382 32693 16382 32694 16361 32694 16344 32694 16382 32695 16344 32695 16377 32695 16377 32696 16344 32696 16359 32696 16377 32697 16359 32697 16380 32697 16380 32698 16359 32698 16358 32698 16380 32699 16358 32699 18254 32699 18254 32700 16358 32700 16355 32700 16362 32701 16363 32701 16365 32701 16365 32702 16363 32702 16364 32702 16365 32703 16364 32703 17698 32703 16341 32704 16366 32704 16367 32704 16367 32705 16366 32705 18332 32705 16367 32706 18332 32706 16342 32706 16363 32707 19606 32707 16364 32707 16364 32708 19606 32708 19605 32708 16364 32709 19605 32709 16341 32709 16341 32710 19605 32710 19604 32710 16341 32711 19604 32711 16366 32711 16386 32712 17693 32712 16373 32712 16381 32713 16368 32713 16382 32713 16391 32714 18141 32714 16369 32714 16379 32715 18145 32715 18142 32715 18145 32716 16379 32716 16370 32716 16381 32717 16383 32717 16371 32717 16371 32718 16383 32718 16372 32718 16371 32719 16372 32719 17693 32719 17693 32720 16372 32720 16384 32720 17693 32721 16384 32721 16373 32721 18141 32722 18148 32722 16369 32722 16369 32723 18148 32723 16374 32723 16369 32724 16374 32724 16375 32724 16375 32725 16374 32725 16393 32725 16375 32726 16393 32726 16388 32726 18142 32727 16376 32727 16379 32727 16379 32728 16376 32728 16390 32728 16379 32729 16390 32729 16378 32729 16382 32730 16377 32730 16378 32730 16378 32731 16377 32731 16380 32731 16378 32732 16380 32732 16379 32732 16379 32733 16380 32733 18254 32733 16379 32734 18254 32734 16370 32734 16381 32735 16382 32735 16383 32735 16383 32736 16382 32736 16378 32736 16383 32737 16378 32737 16372 32737 16372 32738 16378 32738 16390 32738 16372 32739 16390 32739 16384 32739 16384 32740 16390 32740 16389 32740 16384 32741 16389 32741 16373 32741 16373 32742 16389 32742 16385 32742 16373 32743 16385 32743 16386 32743 17689 32744 16386 32744 16387 32744 16387 32745 16386 32745 16385 32745 16387 32746 16385 32746 16388 32746 16388 32747 16385 32747 16389 32747 16388 32748 16389 32748 16375 32748 16375 32749 16389 32749 16390 32749 16375 32750 16390 32750 16369 32750 16369 32751 16390 32751 16376 32751 16369 32752 16376 32752 16391 32752 16391 32753 16376 32753 18142 32753 17689 32754 16387 32754 16392 32754 16392 32755 16387 32755 19598 32755 16392 32756 19598 32756 19597 32756 16387 32757 16388 32757 19598 32757 19598 32758 16388 32758 16393 32758 19598 32759 16393 32759 19601 32759 19601 32760 16393 32760 19602 32760 19602 32761 16393 32761 16374 32761 19602 32762 16374 32762 16394 32762 16374 32763 18148 32763 16396 32763 16394 32764 16374 32764 16395 32764 16395 32765 16374 32765 16396 32765 16395 32766 16396 32766 19603 32766 16534 32767 18370 32767 16397 32767 16397 32768 18370 32768 16398 32768 16399 32769 16400 32769 18368 32769 18346 32770 18349 32770 16461 32770 16462 32771 16434 32771 16463 32771 16531 32772 18370 32772 16533 32772 18370 32773 16531 32773 16401 32773 16402 32774 16434 32774 16403 32774 19698 32775 16512 32775 16404 32775 16479 32776 16480 32776 19714 32776 16439 32777 16437 32777 16477 32777 16440 32778 19713 32778 16405 32778 16405 32779 19713 32779 16430 32779 16405 32780 16430 32780 16441 32780 16480 32781 16406 32781 16407 32781 16407 32782 16406 32782 16408 32782 16496 32783 16409 32783 16410 32783 16410 32784 16409 32784 16498 32784 16410 32785 16498 32785 19704 32785 19704 32786 16498 32786 16504 32786 19704 32787 16504 32787 16411 32787 16415 32788 16412 32788 16511 32788 16511 32789 16412 32789 19708 32789 16511 32790 19708 32790 16510 32790 16510 32791 19708 32791 19707 32791 16413 32792 16414 32792 16415 32792 16415 32793 16414 32793 16416 32793 16415 32794 16416 32794 16412 32794 19700 32795 16417 32795 19701 32795 19701 32796 16417 32796 16418 32796 19701 32797 16418 32797 16419 32797 16419 32798 16418 32798 16420 32798 16419 32799 16420 32799 16421 32799 16421 32800 16420 32800 16423 32800 16421 32801 16423 32801 16422 32801 16422 32802 16423 32802 16424 32802 16422 32803 16424 32803 16425 32803 16425 32804 16424 32804 16530 32804 16425 32805 16530 32805 16529 32805 16426 32806 16400 32806 16427 32806 16427 32807 16400 32807 16532 32807 16427 32808 16532 32808 16428 32808 17758 32809 16429 32809 16535 32809 19713 32810 17770 32810 16430 32810 16430 32811 17770 32811 16431 32811 16430 32812 16431 32812 16441 32812 16441 32813 16431 32813 16432 32813 16441 32814 16432 32814 16433 32814 16463 32815 16434 32815 18344 32815 18344 32816 16434 32816 16402 32816 18344 32817 16402 32817 16484 32817 16398 32818 16435 32818 16397 32818 16397 32819 16435 32819 16538 32819 16397 32820 16538 32820 16534 32820 16477 32821 16437 32821 16436 32821 16436 32822 16437 32822 16438 32822 16436 32823 16438 32823 16486 32823 16486 32824 16438 32824 16442 32824 16486 32825 16442 32825 16485 32825 16439 32826 16440 32826 16437 32826 16437 32827 16440 32827 16405 32827 16437 32828 16405 32828 16438 32828 16438 32829 16405 32829 16441 32829 16438 32830 16441 32830 16442 32830 16442 32831 16441 32831 16433 32831 16442 32832 16433 32832 16485 32832 16485 32833 16433 32833 17769 32833 16485 32834 17769 32834 16483 32834 17758 32835 16535 32835 16443 32835 16443 32836 16535 32836 16444 32836 16443 32837 16444 32837 16445 32837 16461 32838 18349 32838 16446 32838 16446 32839 18349 32839 16447 32839 16446 32840 16447 32840 16459 32840 16453 32841 16448 32841 16449 32841 16447 32842 16450 32842 16459 32842 16459 32843 16450 32843 16451 32843 16459 32844 16451 32844 16449 32844 16449 32845 16451 32845 16452 32845 16449 32846 16452 32846 16453 32846 16454 32847 16473 32847 16455 32847 16455 32848 18352 32848 16454 32848 16454 32849 18352 32849 18354 32849 16454 32850 18354 32850 16500 32850 16500 32851 18354 32851 18355 32851 16500 32852 18355 32852 18358 32852 16476 32853 16456 32853 16466 32853 16466 32854 16456 32854 18363 32854 16471 32855 16404 32855 16513 32855 16403 32856 16434 32856 16457 32856 16457 32857 16434 32857 16462 32857 16457 32858 16462 32858 16460 32858 16448 32859 16489 32859 16449 32859 16449 32860 16489 32860 16488 32860 16449 32861 16488 32861 16459 32861 16459 32862 16488 32862 16458 32862 16459 32863 16458 32863 16446 32863 16446 32864 16458 32864 16460 32864 16446 32865 16460 32865 16461 32865 16461 32866 16460 32866 16462 32866 16461 32867 16462 32867 18346 32867 18346 32868 16462 32868 16463 32868 16464 32869 16476 32869 16465 32869 16465 32870 16476 32870 16466 32870 16465 32871 16466 32871 16404 32871 16404 32872 16466 32872 18363 32872 16467 32873 16521 32873 16519 32873 16519 32874 16521 32874 16468 32874 16519 32875 16468 32875 16469 32875 16469 32876 16468 32876 16523 32876 16469 32877 16523 32877 16516 32877 16516 32878 16523 32878 16470 32878 16516 32879 16470 32879 16471 32879 16471 32880 16470 32880 16472 32880 16471 32881 16472 32881 16404 32881 16473 32882 16499 32882 16497 32882 16497 32883 16499 32883 16501 32883 16497 32884 16501 32884 16502 32884 16404 32885 16474 32885 16465 32885 16465 32886 16474 32886 16475 32886 16465 32887 16475 32887 16464 32887 16464 32888 16475 32888 16509 32888 16464 32889 16509 32889 16476 32889 16476 32890 16509 32890 18361 32890 16476 32891 18361 32891 16456 32891 16477 32892 16478 32892 16479 32892 16479 32893 16478 32893 16487 32893 16479 32894 16487 32894 16480 32894 16480 32895 16487 32895 16481 32895 16480 32896 16481 32896 16406 32896 16406 32897 16481 32897 16490 32897 16406 32898 16490 32898 16492 32898 16492 32899 16490 32899 16491 32899 16482 32900 18340 32900 16483 32900 16483 32901 18340 32901 16484 32901 16483 32902 16484 32902 16485 32902 16485 32903 16484 32903 16402 32903 16485 32904 16402 32904 16486 32904 16486 32905 16402 32905 16403 32905 16486 32906 16403 32906 16436 32906 16436 32907 16403 32907 16457 32907 16436 32908 16457 32908 16477 32908 16477 32909 16457 32909 16460 32909 16477 32910 16460 32910 16478 32910 16478 32911 16460 32911 16458 32911 16478 32912 16458 32912 16487 32912 16487 32913 16458 32913 16488 32913 16487 32914 16488 32914 16481 32914 16481 32915 16488 32915 16489 32915 16481 32916 16489 32916 16490 32916 16490 32917 16489 32917 16448 32917 16490 32918 16448 32918 16491 32918 16408 32919 16406 32919 19716 32919 19716 32920 16406 32920 16492 32920 19716 32921 16492 32921 16493 32921 16493 32922 16492 32922 16491 32922 16493 32923 16491 32923 16494 32923 16494 32924 16491 32924 16448 32924 16494 32925 16448 32925 19702 32925 19702 32926 16448 32926 16495 32926 19702 32927 16495 32927 16496 32927 16496 32928 16495 32928 16473 32928 16496 32929 16473 32929 16409 32929 16409 32930 16473 32930 16497 32930 16409 32931 16497 32931 16498 32931 16498 32932 16497 32932 16502 32932 16498 32933 16502 32933 16504 32933 16473 32934 16454 32934 16499 32934 16499 32935 16454 32935 16500 32935 16499 32936 16500 32936 16501 32936 16501 32937 16500 32937 18358 32937 16501 32938 18358 32938 16502 32938 16502 32939 18358 32939 16503 32939 16502 32940 16503 32940 16504 32940 16411 32941 16504 32941 16505 32941 16505 32942 16504 32942 16503 32942 16505 32943 16503 32943 16506 32943 16506 32944 16503 32944 18358 32944 16506 32945 18358 32945 16507 32945 16507 32946 18358 32946 16508 32946 16507 32947 16508 32947 19707 32947 19707 32948 16508 32948 16509 32948 19707 32949 16509 32949 16510 32949 16510 32950 16509 32950 16475 32950 16510 32951 16475 32951 16511 32951 16511 32952 16475 32952 16474 32952 16511 32953 16474 32953 16415 32953 16415 32954 16474 32954 16404 32954 16415 32955 16404 32955 16413 32955 16413 32956 16404 32956 16512 32956 16413 32957 16512 32957 16414 32957 16513 32958 16514 32958 16471 32958 16471 32959 16514 32959 16515 32959 16471 32960 16515 32960 16516 32960 16516 32961 16515 32961 16517 32961 16516 32962 16517 32962 16469 32962 16469 32963 16517 32963 16518 32963 16469 32964 16518 32964 16519 32964 16519 32965 16518 32965 16520 32965 16519 32966 16520 32966 16467 32966 16467 32967 16520 32967 16400 32967 16467 32968 16400 32968 16521 32968 16521 32969 16400 32969 16522 32969 16521 32970 16522 32970 16468 32970 16468 32971 16522 32971 16524 32971 16468 32972 16524 32972 16523 32972 16523 32973 16524 32973 16525 32973 16523 32974 16525 32974 16470 32974 16470 32975 16525 32975 16526 32975 16470 32976 16526 32976 16472 32976 16472 32977 16526 32977 16527 32977 16472 32978 16527 32978 16404 32978 16404 32979 16527 32979 16528 32979 16404 32980 16528 32980 19698 32980 16426 32981 16529 32981 16400 32981 16400 32982 16529 32982 16530 32982 16400 32983 16530 32983 16522 32983 16522 32984 16530 32984 16424 32984 16522 32985 16424 32985 16524 32985 16524 32986 16424 32986 16423 32986 16524 32987 16423 32987 16525 32987 16525 32988 16423 32988 16420 32988 16525 32989 16420 32989 16526 32989 16526 32990 16420 32990 16418 32990 16526 32991 16418 32991 16527 32991 16527 32992 16418 32992 16417 32992 16527 32993 16417 32993 16528 32993 16528 32994 16417 32994 19700 32994 16528 32995 19700 32995 19698 32995 18368 32996 18370 32996 16399 32996 16399 32997 18370 32997 16401 32997 16399 32998 16401 32998 16400 32998 16400 32999 16401 32999 16531 32999 16400 33000 16531 33000 16532 33000 16532 33001 16531 33001 16533 33001 16532 33002 16533 33002 16428 33002 16428 33003 16533 33003 18370 33003 16538 33004 16445 33004 16534 33004 16534 33005 16445 33005 16444 33005 16534 33006 16444 33006 18370 33006 18370 33007 16444 33007 16535 33007 18370 33008 16535 33008 16536 33008 16536 33009 16535 33009 16429 33009 16536 33010 16429 33010 18370 33010 18370 33011 16429 33011 16537 33011 18370 33012 16537 33012 16428 33012 16538 33013 16435 33013 16540 33013 16445 33014 16538 33014 16539 33014 16443 33015 16445 33015 16548 33015 17758 33016 16443 33016 16555 33016 16538 33017 16540 33017 16539 33017 16539 33018 16540 33018 16541 33018 16539 33019 16541 33019 16549 33019 16549 33020 16541 33020 16542 33020 16549 33021 16542 33021 16543 33021 16543 33022 16542 33022 18376 33022 16543 33023 18376 33023 16544 33023 16544 33024 18376 33024 18375 33024 16544 33025 18375 33025 16552 33025 16552 33026 18375 33026 16545 33026 16552 33027 16545 33027 16553 33027 16553 33028 16545 33028 16546 33028 16553 33029 16546 33029 16547 33029 16547 33030 16546 33030 16574 33030 16547 33031 16574 33031 16573 33031 16445 33032 16539 33032 16548 33032 16548 33033 16539 33033 16549 33033 16548 33034 16549 33034 16556 33034 16556 33035 16549 33035 16543 33035 16556 33036 16543 33036 16550 33036 16550 33037 16543 33037 16544 33037 16550 33038 16544 33038 16559 33038 16559 33039 16544 33039 16552 33039 16559 33040 16552 33040 16551 33040 16551 33041 16552 33041 16553 33041 16551 33042 16553 33042 16554 33042 16554 33043 16553 33043 16547 33043 16554 33044 16547 33044 16561 33044 16561 33045 16547 33045 16573 33045 16561 33046 16573 33046 16571 33046 16443 33047 16548 33047 16555 33047 16555 33048 16548 33048 16556 33048 16555 33049 16556 33049 16557 33049 16557 33050 16556 33050 16550 33050 16557 33051 16550 33051 16558 33051 16558 33052 16550 33052 16559 33052 16558 33053 16559 33053 16560 33053 16560 33054 16559 33054 16551 33054 16560 33055 16551 33055 16564 33055 16564 33056 16551 33056 16554 33056 16564 33057 16554 33057 16565 33057 16565 33058 16554 33058 16561 33058 16565 33059 16561 33059 16562 33059 16562 33060 16561 33060 16571 33060 16562 33061 16571 33061 16567 33061 17758 33062 16555 33062 17759 33062 17759 33063 16555 33063 16557 33063 17759 33064 16557 33064 16563 33064 16563 33065 16557 33065 16558 33065 16563 33066 16558 33066 17760 33066 17760 33067 16558 33067 16560 33067 17760 33068 16560 33068 17763 33068 17763 33069 16560 33069 16564 33069 17763 33070 16564 33070 17767 33070 17767 33071 16564 33071 16565 33071 17767 33072 16565 33072 16566 33072 16566 33073 16565 33073 16562 33073 16566 33074 16562 33074 17764 33074 17764 33075 16562 33075 16567 33075 17764 33076 16567 33076 16568 33076 16568 33077 16567 33077 16590 33077 16590 33078 16567 33078 16569 33078 16569 33079 16567 33079 16584 33079 16584 33080 16567 33080 16571 33080 16584 33081 16571 33081 16570 33081 16570 33082 16571 33082 16572 33082 16572 33083 16571 33083 16573 33083 16572 33084 16573 33084 16591 33084 16591 33085 16573 33085 16580 33085 16580 33086 16573 33086 16574 33086 16580 33087 16574 33087 18372 33087 16580 33088 16585 33088 16575 33088 16576 33089 16585 33089 16580 33089 16582 33090 16580 33090 18372 33090 16577 33091 17280 33091 16578 33091 16578 33092 17280 33092 16579 33092 17277 33093 17279 33093 16576 33093 16576 33094 17279 33094 16577 33094 16580 33095 16583 33095 16581 33095 17277 33096 16576 33096 16581 33096 16581 33097 16576 33097 16580 33097 16582 33098 16583 33098 16580 33098 16569 33099 16584 33099 16587 33099 16587 33100 16584 33100 16570 33100 16577 33101 16578 33101 16576 33101 16576 33102 16578 33102 16586 33102 16576 33103 16586 33103 16585 33103 16585 33104 16586 33104 16587 33104 16585 33105 16587 33105 16575 33105 16575 33106 16587 33106 16570 33106 16575 33107 16570 33107 16572 33107 16579 33108 16592 33108 16578 33108 16578 33109 16592 33109 16594 33109 16578 33110 16594 33110 16586 33110 16586 33111 16594 33111 16588 33111 16586 33112 16588 33112 16587 33112 16587 33113 16588 33113 16589 33113 16587 33114 16589 33114 16569 33114 16569 33115 16589 33115 16590 33115 16572 33116 16591 33116 16575 33116 16575 33117 16591 33117 16580 33117 19388 33118 16601 33118 16593 33118 16594 33119 16592 33119 19388 33119 19388 33120 16593 33120 16594 33120 16594 33121 16593 33121 16595 33121 16594 33122 16595 33122 16588 33122 16588 33123 16595 33123 16598 33123 16588 33124 16598 33124 16589 33124 16589 33125 16598 33125 17282 33125 16589 33126 17282 33126 16590 33126 17402 33127 17284 33127 16596 33127 16596 33128 17284 33128 16599 33128 16596 33129 16599 33129 16602 33129 16602 33130 16599 33130 16597 33130 16602 33131 16597 33131 16605 33131 16605 33132 16597 33132 16600 33132 16605 33133 16600 33133 16603 33133 16603 33134 16600 33134 19390 33134 16603 33135 19390 33135 19391 33135 17284 33136 17282 33136 16599 33136 16599 33137 17282 33137 16598 33137 16599 33138 16598 33138 16597 33138 16597 33139 16598 33139 16595 33139 16597 33140 16595 33140 16600 33140 16600 33141 16595 33141 16593 33141 16600 33142 16593 33142 19390 33142 19390 33143 16593 33143 16601 33143 20820 33144 20819 33144 16602 33144 19391 33145 16604 33145 16603 33145 16603 33146 16604 33146 20820 33146 16603 33147 20820 33147 16605 33147 16605 33148 20820 33148 16602 33148 20819 33149 17743 33149 16602 33149 16602 33150 17743 33150 17400 33150 16602 33151 17400 33151 16596 33151 16596 33152 17400 33152 17402 33152 16606 33153 16607 33153 16612 33153 16607 33154 16610 33154 16611 33154 19386 33155 16608 33155 16623 33155 16623 33156 16615 33156 19386 33156 19386 33157 16615 33157 16613 33157 19386 33158 16613 33158 16609 33158 16609 33159 16613 33159 16611 33159 16609 33160 16611 33160 19381 33160 19381 33161 16611 33161 16610 33161 19381 33162 16610 33162 19398 33162 16607 33163 16611 33163 16612 33163 16612 33164 16611 33164 16613 33164 16612 33165 16613 33165 16614 33165 16614 33166 16613 33166 16615 33166 16614 33167 16615 33167 16620 33167 16623 33168 16616 33168 16615 33168 16615 33169 16616 33169 16617 33169 16615 33170 16617 33170 16620 33170 16620 33171 16617 33171 16618 33171 16620 33172 16618 33172 16621 33172 16606 33173 16612 33173 16619 33173 16619 33174 16612 33174 16614 33174 16619 33175 16614 33175 17322 33175 17322 33176 16614 33176 16620 33176 17322 33177 16620 33177 17321 33177 17321 33178 16620 33178 16621 33178 17321 33179 16621 33179 17320 33179 16622 33180 16627 33180 17320 33180 16608 33181 16624 33181 16623 33181 16623 33182 16624 33182 16625 33182 16623 33183 16625 33183 16616 33183 16616 33184 16625 33184 16626 33184 17320 33185 16621 33185 16622 33185 16622 33186 16621 33186 16618 33186 16622 33187 16618 33187 16626 33187 16626 33188 16618 33188 16617 33188 16626 33189 16617 33189 16616 33189 17813 33190 16627 33190 16628 33190 16628 33191 16627 33191 16622 33191 16628 33192 16622 33192 16637 33192 16637 33193 16622 33193 16626 33193 16637 33194 16626 33194 16635 33194 16635 33195 16626 33195 16625 33195 16635 33196 16625 33196 16629 33196 16629 33197 16625 33197 16624 33197 16630 33198 19384 33198 16636 33198 17813 33199 16628 33199 16631 33199 16631 33200 16628 33200 16638 33200 16632 33201 16636 33201 16633 33201 16633 33202 16636 33202 19384 33202 16633 33203 19384 33203 16634 33203 16629 33204 16630 33204 16635 33204 16635 33205 16630 33205 16636 33205 16635 33206 16636 33206 16637 33206 16637 33207 16636 33207 16632 33207 16637 33208 16632 33208 16628 33208 16628 33209 16632 33209 16640 33209 16628 33210 16640 33210 16638 33210 16638 33211 16640 33211 17376 33211 16643 33212 17376 33212 16639 33212 16639 33213 17376 33213 16640 33213 16639 33214 16640 33214 16641 33214 16641 33215 16640 33215 16632 33215 16641 33216 16632 33216 19405 33216 19405 33217 16632 33217 16633 33217 19405 33218 16633 33218 16642 33218 16642 33219 16633 33219 16634 33219 17374 33220 16643 33220 16645 33220 16645 33221 16643 33221 16639 33221 16645 33222 16639 33222 16644 33222 16644 33223 16639 33223 16641 33223 16644 33224 16641 33224 16648 33224 16648 33225 16641 33225 19405 33225 16648 33226 19405 33226 19404 33226 17373 33227 17374 33227 16646 33227 16646 33228 17374 33228 16645 33228 16646 33229 16645 33229 16647 33229 16647 33230 16645 33230 16644 33230 16647 33231 16644 33231 16652 33231 16652 33232 16644 33232 16648 33232 16652 33233 16648 33233 19403 33233 19403 33234 16648 33234 19404 33234 17371 33235 17373 33235 16649 33235 16649 33236 17373 33236 16646 33236 16649 33237 16646 33237 16650 33237 16650 33238 16646 33238 16647 33238 16650 33239 16647 33239 16651 33239 16651 33240 16647 33240 16652 33240 16651 33241 16652 33241 20809 33241 20809 33242 16652 33242 19403 33242 16658 33243 20794 33243 16653 33243 16653 33244 20794 33244 20790 33244 16653 33245 20790 33245 19411 33245 19411 33246 20790 33246 19412 33246 16656 33247 20785 33247 16654 33247 16654 33248 20785 33248 16655 33248 16654 33249 16655 33249 16658 33249 16658 33250 16655 33250 20788 33250 16658 33251 20788 33251 20794 33251 16661 33252 16656 33252 16662 33252 16662 33253 16656 33253 16654 33253 16662 33254 16654 33254 16657 33254 16657 33255 16654 33255 16658 33255 16657 33256 16658 33256 16663 33256 16663 33257 16658 33257 16653 33257 16663 33258 16653 33258 19380 33258 16659 33259 16661 33259 16660 33259 16660 33260 16661 33260 16662 33260 16660 33261 16662 33261 16665 33261 16665 33262 16662 33262 16657 33262 16665 33263 16657 33263 16667 33263 16667 33264 16657 33264 16663 33264 16667 33265 16663 33265 16668 33265 16668 33266 16663 33266 19380 33266 15480 33267 16659 33267 16669 33267 16669 33268 16659 33268 16660 33268 16669 33269 16660 33269 16664 33269 16664 33270 16660 33270 16665 33270 16664 33271 16665 33271 16666 33271 16666 33272 16665 33272 16667 33272 16666 33273 16667 33273 19379 33273 19379 33274 16667 33274 16668 33274 15479 33275 15480 33275 16675 33275 16675 33276 15480 33276 16669 33276 16675 33277 16669 33277 16670 33277 16670 33278 16669 33278 16664 33278 16670 33279 16664 33279 16671 33279 16671 33280 16664 33280 16666 33280 16671 33281 16666 33281 19377 33281 19377 33282 16666 33282 19379 33282 16672 33283 16674 33283 16673 33283 16673 33284 16674 33284 16677 33284 16673 33285 16677 33285 16680 33285 19377 33286 19375 33286 16671 33286 16671 33287 19375 33287 16672 33287 16671 33288 16672 33288 16670 33288 16675 33289 16670 33289 16676 33289 15479 33290 16675 33290 16685 33290 16670 33291 16672 33291 16676 33291 16676 33292 16672 33292 16673 33292 16676 33293 16673 33293 16683 33293 16683 33294 16673 33294 16680 33294 16683 33295 16680 33295 16681 33295 16677 33296 16678 33296 16680 33296 16680 33297 16678 33297 16679 33297 16680 33298 16679 33298 16681 33298 16681 33299 16679 33299 20773 33299 16681 33300 20773 33300 16682 33300 16675 33301 16676 33301 16685 33301 16685 33302 16676 33302 16683 33302 16685 33303 16683 33303 16687 33303 16687 33304 16683 33304 16681 33304 16687 33305 16681 33305 16684 33305 16684 33306 16681 33306 16682 33306 16684 33307 16682 33307 20755 33307 15479 33308 16685 33308 16686 33308 16686 33309 16685 33309 16687 33309 16686 33310 16687 33310 17337 33310 17337 33311 16687 33311 16684 33311 17337 33312 16684 33312 17336 33312 17336 33313 16684 33313 20755 33313 17336 33314 20755 33314 20757 33314 16688 33315 16689 33315 19420 33315 19420 33316 16689 33316 20774 33316 19420 33317 20774 33317 19419 33317 19419 33318 20774 33318 19417 33318 19723 33319 19724 33319 16691 33319 16691 33320 19724 33320 20756 33320 16691 33321 20756 33321 16688 33321 16688 33322 20756 33322 20776 33322 16688 33323 20776 33323 16689 33323 16694 33324 19723 33324 16690 33324 16690 33325 19723 33325 16691 33325 16690 33326 16691 33326 16692 33326 16692 33327 16691 33327 16688 33327 16692 33328 16688 33328 16693 33328 16693 33329 16688 33329 19420 33329 16693 33330 19420 33330 16696 33330 19720 33331 16694 33331 16700 33331 16700 33332 16694 33332 16690 33332 16700 33333 16690 33333 16695 33333 16695 33334 16690 33334 16692 33334 16695 33335 16692 33335 16703 33335 16703 33336 16692 33336 16693 33336 16703 33337 16693 33337 16704 33337 16704 33338 16693 33338 16696 33338 16697 33339 19720 33339 16698 33339 16698 33340 19720 33340 16700 33340 16698 33341 16700 33341 16699 33341 16699 33342 16700 33342 16695 33342 16699 33343 16695 33343 16701 33343 16701 33344 16695 33344 16703 33344 16701 33345 16703 33345 16702 33345 16702 33346 16703 33346 16704 33346 19717 33347 16697 33347 16714 33347 16714 33348 16697 33348 16698 33348 16714 33349 16698 33349 16708 33349 16708 33350 16698 33350 16699 33350 16708 33351 16699 33351 16705 33351 16705 33352 16699 33352 16701 33352 16705 33353 16701 33353 19370 33353 19370 33354 16701 33354 16702 33354 16707 33355 19362 33355 16706 33355 16706 33356 19362 33356 19432 33356 16706 33357 19432 33357 16711 33357 19370 33358 19368 33358 16705 33358 16705 33359 19368 33359 16707 33359 16705 33360 16707 33360 16708 33360 16714 33361 16708 33361 16709 33361 19717 33362 16714 33362 16717 33362 16708 33363 16707 33363 16709 33363 16709 33364 16707 33364 16706 33364 16709 33365 16706 33365 16710 33365 16710 33366 16706 33366 16711 33366 16710 33367 16711 33367 16716 33367 19432 33368 19431 33368 16711 33368 16711 33369 19431 33369 20748 33369 16711 33370 20748 33370 16716 33370 16716 33371 20748 33371 16712 33371 16716 33372 16712 33372 16713 33372 16714 33373 16709 33373 16717 33373 16717 33374 16709 33374 16710 33374 16717 33375 16710 33375 16715 33375 16715 33376 16710 33376 16716 33376 16715 33377 16716 33377 16719 33377 16719 33378 16716 33378 16713 33378 16719 33379 16713 33379 16720 33379 19717 33380 16717 33380 17740 33380 17740 33381 16717 33381 16715 33381 17740 33382 16715 33382 16718 33382 16718 33383 16715 33383 16719 33383 16718 33384 16719 33384 17738 33384 17738 33385 16719 33385 16720 33385 17738 33386 16720 33386 15482 33386 19425 33387 16722 33387 16721 33387 16721 33388 16722 33388 16723 33388 16726 33389 16727 33389 16724 33389 16724 33390 20730 33390 16726 33390 16726 33391 20730 33391 16725 33391 16726 33392 16725 33392 16723 33392 16723 33393 16725 33393 20737 33393 16723 33394 20737 33394 16721 33394 16722 33395 19366 33395 16723 33395 16723 33396 19366 33396 16728 33396 16723 33397 16728 33397 16726 33397 16726 33398 16728 33398 16729 33398 16726 33399 16729 33399 16727 33399 16727 33400 16729 33400 16731 33400 19366 33401 16733 33401 16728 33401 16728 33402 16733 33402 16732 33402 16728 33403 16732 33403 16729 33403 16729 33404 16732 33404 16730 33404 16729 33405 16730 33405 16731 33405 16731 33406 16730 33406 15493 33406 16734 33407 15493 33407 16730 33407 16734 33408 16730 33408 16740 33408 16740 33409 16730 33409 16732 33409 16740 33410 16732 33410 16738 33410 16738 33411 16732 33411 16733 33411 16738 33412 16733 33412 16739 33412 16734 33413 16740 33413 16741 33413 16740 33414 16738 33414 16737 33414 19436 33415 16744 33415 16735 33415 16735 33416 16744 33416 16743 33416 16735 33417 16743 33417 19433 33417 19433 33418 16743 33418 16736 33418 19433 33419 16736 33419 19434 33419 19434 33420 16736 33420 16737 33420 19434 33421 16737 33421 19364 33421 19364 33422 16737 33422 16738 33422 19364 33423 16738 33423 16739 33423 16740 33424 16737 33424 16741 33424 16741 33425 16737 33425 16736 33425 16741 33426 16736 33426 16742 33426 16742 33427 16736 33427 16743 33427 16742 33428 16743 33428 16748 33428 16748 33429 16743 33429 16744 33429 16748 33430 16744 33430 16745 33430 16734 33431 16741 33431 17780 33431 17780 33432 16741 33432 16742 33432 17780 33433 16742 33433 16746 33433 16746 33434 16742 33434 16748 33434 16746 33435 16748 33435 16747 33435 16747 33436 16748 33436 16745 33436 16747 33437 16745 33437 20728 33437 16805 33438 16749 33438 16810 33438 16760 33439 16750 33439 16776 33439 16751 33440 16753 33440 16752 33440 16799 33441 16794 33441 16753 33441 16795 33442 19440 33442 16794 33442 19357 33443 16776 33443 16754 33443 16754 33444 16776 33444 16750 33444 16754 33445 16750 33445 19448 33445 19448 33446 16750 33446 20724 33446 19448 33447 20724 33447 16755 33447 19341 33448 19440 33448 16757 33448 16757 33449 19440 33449 16795 33449 16757 33450 16795 33450 16758 33450 19348 33451 19341 33451 16756 33451 16756 33452 19341 33452 16757 33452 16756 33453 16757 33453 16793 33453 16793 33454 16757 33454 16758 33454 16793 33455 16758 33455 16797 33455 20720 33456 16759 33456 16760 33456 16760 33457 16759 33457 16761 33457 16760 33458 16761 33458 16750 33458 16750 33459 16761 33459 20723 33459 16750 33460 20723 33460 20724 33460 16778 33461 16779 33461 16762 33461 17792 33462 16763 33462 16764 33462 16764 33463 16763 33463 16778 33463 16764 33464 16778 33464 16782 33464 16782 33465 16778 33465 16762 33465 16782 33466 16762 33466 16780 33466 19354 33467 16765 33467 16781 33467 16781 33468 16765 33468 16783 33468 16781 33469 16783 33469 16766 33469 16766 33470 16783 33470 16784 33470 16766 33471 16784 33471 16767 33471 16767 33472 16784 33472 16768 33472 16772 33473 16769 33473 16770 33473 16770 33474 16769 33474 16805 33474 16770 33475 16805 33475 16808 33475 16749 33476 16805 33476 16771 33476 16771 33477 16805 33477 16769 33477 16771 33478 16769 33478 16815 33478 16815 33479 16769 33479 16772 33479 16815 33480 16772 33480 16773 33480 16760 33481 16774 33481 20720 33481 20720 33482 16774 33482 16775 33482 20720 33483 16775 33483 19818 33483 19357 33484 16780 33484 16776 33484 16776 33485 16780 33485 16762 33485 16776 33486 16762 33486 16760 33486 16760 33487 16762 33487 16779 33487 16760 33488 16779 33488 16774 33488 16774 33489 16779 33489 17796 33489 16774 33490 17796 33490 16775 33490 16763 33491 16777 33491 16778 33491 16778 33492 16777 33492 17794 33492 16778 33493 17794 33493 16779 33493 16779 33494 17794 33494 17795 33494 16779 33495 17795 33495 17796 33495 19357 33496 19354 33496 16780 33496 16780 33497 19354 33497 16781 33497 16780 33498 16781 33498 16782 33498 16782 33499 16781 33499 16766 33499 16782 33500 16766 33500 16764 33500 16764 33501 16766 33501 16767 33501 16764 33502 16767 33502 17792 33502 16785 33503 17790 33503 16768 33503 16768 33504 17790 33504 17791 33504 16768 33505 17791 33505 16767 33505 16767 33506 17791 33506 17793 33506 16767 33507 17793 33507 17792 33507 16765 33508 19350 33508 16783 33508 16783 33509 19350 33509 16787 33509 16783 33510 16787 33510 16784 33510 16784 33511 16787 33511 16789 33511 16784 33512 16789 33512 16768 33512 16768 33513 16789 33513 16786 33513 16768 33514 16786 33514 16785 33514 16785 33515 16786 33515 16791 33515 19350 33516 19242 33516 16787 33516 16787 33517 19242 33517 16792 33517 16787 33518 16792 33518 16789 33518 16789 33519 16792 33519 16788 33519 16789 33520 16788 33520 16786 33520 16786 33521 16788 33521 16790 33521 16786 33522 16790 33522 16791 33522 16791 33523 16790 33523 17788 33523 19242 33524 19348 33524 16792 33524 16792 33525 19348 33525 16756 33525 16792 33526 16756 33526 16788 33526 16788 33527 16756 33527 16793 33527 16788 33528 16793 33528 16790 33528 16790 33529 16793 33529 16797 33529 16790 33530 16797 33530 17788 33530 17788 33531 16797 33531 16798 33531 16800 33532 17785 33532 17784 33532 16794 33533 16799 33533 16795 33533 16795 33534 16799 33534 16796 33534 16795 33535 16796 33535 16758 33535 16758 33536 16796 33536 16800 33536 16758 33537 16800 33537 16797 33537 16797 33538 16800 33538 17784 33538 16797 33539 17784 33539 16798 33539 16753 33540 16751 33540 16799 33540 16799 33541 16751 33541 16802 33541 16799 33542 16802 33542 16796 33542 16796 33543 16802 33543 16803 33543 16796 33544 16803 33544 16800 33544 16800 33545 16803 33545 17787 33545 16800 33546 17787 33546 17785 33546 16801 33547 16773 33547 16752 33547 16752 33548 16773 33548 16772 33548 16752 33549 16772 33549 16751 33549 16751 33550 16772 33550 16770 33550 16751 33551 16770 33551 16802 33551 16802 33552 16770 33552 16808 33552 16802 33553 16808 33553 16803 33553 16803 33554 16808 33554 16804 33554 16803 33555 16804 33555 17787 33555 16810 33556 16806 33556 16805 33556 16805 33557 16806 33557 16807 33557 16805 33558 16807 33558 16808 33558 16808 33559 16807 33559 16809 33559 16808 33560 16809 33560 16804 33560 16811 33561 19814 33561 17798 33561 16810 33562 16749 33562 17798 33562 17798 33563 16749 33563 16812 33563 17798 33564 16812 33564 16811 33564 16811 33565 16812 33565 20700 33565 20700 33566 16812 33566 20701 33566 20701 33567 16812 33567 16813 33567 20701 33568 16813 33568 20702 33568 20702 33569 16813 33569 20695 33569 20695 33570 16813 33570 19443 33570 20695 33571 19443 33571 16814 33571 16749 33572 16771 33572 16812 33572 16812 33573 16771 33573 16815 33573 16812 33574 16815 33574 16813 33574 16813 33575 16815 33575 16773 33575 16813 33576 16773 33576 19443 33576 19443 33577 16773 33577 16801 33577 16817 33578 19247 33578 16821 33578 20714 33579 16816 33579 16817 33579 16817 33580 16821 33580 20714 33580 20714 33581 16821 33581 16820 33581 20714 33582 16820 33582 20717 33582 20717 33583 16820 33583 16818 33583 20717 33584 16818 33584 20719 33584 20719 33585 16818 33585 16825 33585 20719 33586 16825 33586 16819 33586 16824 33587 16820 33587 16822 33587 16822 33588 16820 33588 16821 33588 16822 33589 16821 33589 19247 33589 19247 33590 16823 33590 16822 33590 16822 33591 16823 33591 16830 33591 16822 33592 16830 33592 16824 33592 16824 33593 16830 33593 16828 33593 16826 33594 16825 33594 16824 33594 16824 33595 16825 33595 16818 33595 16824 33596 16818 33596 16820 33596 20690 33597 16826 33597 16832 33597 16832 33598 16826 33598 16824 33598 16832 33599 16824 33599 16827 33599 16827 33600 16824 33600 16828 33600 19246 33601 16829 33601 19247 33601 19247 33602 16829 33602 16823 33602 16823 33603 16829 33603 16830 33603 16830 33604 16829 33604 20679 33604 16830 33605 20679 33605 16828 33605 16828 33606 20679 33606 16831 33606 16828 33607 16831 33607 16827 33607 16827 33608 16831 33608 20680 33608 16827 33609 20680 33609 16832 33609 20680 33610 20685 33610 16832 33610 16832 33611 20685 33611 17326 33611 16832 33612 17326 33612 20690 33612 20684 33613 20683 33613 16833 33613 16833 33614 20683 33614 19313 33614 16833 33615 19313 33615 19312 33615 20684 33616 16833 33616 16834 33616 16834 33617 16833 33617 16838 33617 16834 33618 16838 33618 20688 33618 20688 33619 16838 33619 16835 33619 20688 33620 16835 33620 20686 33620 20686 33621 16835 33621 16836 33621 20686 33622 16836 33622 16837 33622 16833 33623 19312 33623 19311 33623 19311 33624 16841 33624 16833 33624 16833 33625 16841 33625 16845 33625 16833 33626 16845 33626 16838 33626 16838 33627 16845 33627 16840 33627 16838 33628 16840 33628 16835 33628 16835 33629 16840 33629 17799 33629 16835 33630 17799 33630 16836 33630 16839 33631 17799 33631 16840 33631 16841 33632 19311 33632 16842 33632 16842 33633 16843 33633 16841 33633 16841 33634 16843 33634 16844 33634 16841 33635 16844 33635 16845 33635 16845 33636 16844 33636 16846 33636 16845 33637 16846 33637 16840 33637 16840 33638 16846 33638 16852 33638 16840 33639 16852 33639 16839 33639 16847 33640 19309 33640 16848 33640 16843 33641 16842 33641 16847 33641 16847 33642 16848 33642 16843 33642 16843 33643 16848 33643 16849 33643 16843 33644 16849 33644 16844 33644 16844 33645 16849 33645 16850 33645 16844 33646 16850 33646 16846 33646 16846 33647 16850 33647 16851 33647 16846 33648 16851 33648 16852 33648 19579 33649 16851 33649 16862 33649 16862 33650 16851 33650 16850 33650 16862 33651 16850 33651 16853 33651 16853 33652 16850 33652 16849 33652 16853 33653 16849 33653 16856 33653 16856 33654 16849 33654 16848 33654 16856 33655 16848 33655 16854 33655 16854 33656 16848 33656 19309 33656 16855 33657 16860 33657 16858 33657 16858 33658 19306 33658 19305 33658 19306 33659 16856 33659 16854 33659 16856 33660 19306 33660 16853 33660 16862 33661 16853 33661 16857 33661 19579 33662 16862 33662 16865 33662 16853 33663 19306 33663 16857 33663 16857 33664 19306 33664 16858 33664 16857 33665 16858 33665 16863 33665 16863 33666 16858 33666 16860 33666 16863 33667 16860 33667 16859 33667 16855 33668 16894 33668 16860 33668 16860 33669 16894 33669 16893 33669 16860 33670 16893 33670 16859 33670 16859 33671 16893 33671 16861 33671 16859 33672 16861 33672 16880 33672 16862 33673 16857 33673 16865 33673 16865 33674 16857 33674 16863 33674 16865 33675 16863 33675 16864 33675 16864 33676 16863 33676 16859 33676 16864 33677 16859 33677 16867 33677 16867 33678 16859 33678 16880 33678 16867 33679 16880 33679 16878 33679 19579 33680 16865 33680 17313 33680 17313 33681 16865 33681 16864 33681 17313 33682 16864 33682 16866 33682 16866 33683 16864 33683 16867 33683 16866 33684 16867 33684 17318 33684 17318 33685 16867 33685 16878 33685 17318 33686 16878 33686 16868 33686 16898 33687 17312 33687 16871 33687 16881 33688 16899 33688 16872 33688 16872 33689 16899 33689 16898 33689 16897 33690 16870 33690 16869 33690 16869 33691 16870 33691 16881 33691 16898 33692 16871 33692 16872 33692 16872 33693 16871 33693 16874 33693 16872 33694 16874 33694 16873 33694 16873 33695 16874 33695 16875 33695 16873 33696 16875 33696 16876 33696 16876 33697 16875 33697 19738 33697 16876 33698 19738 33698 16882 33698 16882 33699 19738 33699 19737 33699 16882 33700 19737 33700 16884 33700 16884 33701 19737 33701 16877 33701 16884 33702 16877 33702 16879 33702 16877 33703 16868 33703 16878 33703 16877 33704 16878 33704 16879 33704 16879 33705 16878 33705 16880 33705 16879 33706 16880 33706 16861 33706 16881 33707 16872 33707 16869 33707 16869 33708 16872 33708 16873 33708 16869 33709 16873 33709 16889 33709 16889 33710 16873 33710 16876 33710 16889 33711 16876 33711 16890 33711 16890 33712 16876 33712 16882 33712 16890 33713 16882 33713 16883 33713 16883 33714 16882 33714 16884 33714 16883 33715 16884 33715 16885 33715 16885 33716 16884 33716 16879 33716 16885 33717 16879 33717 16886 33717 16886 33718 16879 33718 16861 33718 16886 33719 16861 33719 16893 33719 16897 33720 16869 33720 16887 33720 16887 33721 16869 33721 16889 33721 16887 33722 16889 33722 16888 33722 16888 33723 16889 33723 16890 33723 16888 33724 16890 33724 19298 33724 19298 33725 16890 33725 16883 33725 19298 33726 16883 33726 19297 33726 19297 33727 16883 33727 16885 33727 19297 33728 16885 33728 16891 33728 16891 33729 16885 33729 16886 33729 16891 33730 16886 33730 16892 33730 16892 33731 16886 33731 16893 33731 16892 33732 16893 33732 16894 33732 16902 33733 16881 33733 16895 33733 16895 33734 16881 33734 16870 33734 16895 33735 16870 33735 16896 33735 16896 33736 16870 33736 16897 33736 17311 33737 17312 33737 16900 33737 16900 33738 17312 33738 16898 33738 16900 33739 16898 33739 16902 33739 16902 33740 16898 33740 16899 33740 16902 33741 16899 33741 16881 33741 17309 33742 17311 33742 16905 33742 16905 33743 17311 33743 16900 33743 16905 33744 16900 33744 16901 33744 16901 33745 16900 33745 16902 33745 16901 33746 16902 33746 16903 33746 16903 33747 16902 33747 16895 33747 16903 33748 16895 33748 19304 33748 17307 33749 17309 33749 16904 33749 16904 33750 17309 33750 16905 33750 16904 33751 16905 33751 16906 33751 16906 33752 16905 33752 16901 33752 16906 33753 16901 33753 16908 33753 16908 33754 16901 33754 16903 33754 16908 33755 16903 33755 19303 33755 19303 33756 16903 33756 19304 33756 16910 33757 17307 33757 16912 33757 16912 33758 17307 33758 16904 33758 16912 33759 16904 33759 16907 33759 16907 33760 16904 33760 16906 33760 16907 33761 16906 33761 16913 33761 16913 33762 16906 33762 16908 33762 16913 33763 16908 33763 19290 33763 19290 33764 16908 33764 19303 33764 16914 33765 19291 33765 16909 33765 16915 33766 16910 33766 16916 33766 16916 33767 16910 33767 16912 33767 16916 33768 16912 33768 16911 33768 16911 33769 16912 33769 16907 33769 16911 33770 16907 33770 16909 33770 16909 33771 16907 33771 16913 33771 16909 33772 16913 33772 16914 33772 16914 33773 16913 33773 19290 33773 16918 33774 16915 33774 16921 33774 16921 33775 16915 33775 16916 33775 16921 33776 16916 33776 16922 33776 16922 33777 16916 33777 16911 33777 16922 33778 16911 33778 16924 33778 16924 33779 16911 33779 16909 33779 16924 33780 16909 33780 19292 33780 19292 33781 16909 33781 19291 33781 16917 33782 16918 33782 16919 33782 16919 33783 16918 33783 16921 33783 16919 33784 16921 33784 16920 33784 16920 33785 16921 33785 16922 33785 16920 33786 16922 33786 16923 33786 16923 33787 16922 33787 16924 33787 16923 33788 16924 33788 16925 33788 16926 33789 16917 33789 16929 33789 16929 33790 16917 33790 16919 33790 16929 33791 16919 33791 16931 33791 16931 33792 16919 33792 16920 33792 16931 33793 16920 33793 16932 33793 16932 33794 16920 33794 16923 33794 16932 33795 16923 33795 16927 33795 16927 33796 16923 33796 16925 33796 16928 33797 16926 33797 16954 33797 16954 33798 16926 33798 16929 33798 16954 33799 16929 33799 16930 33799 16930 33800 16929 33800 16931 33800 16930 33801 16931 33801 16953 33801 16953 33802 16931 33802 16932 33802 16953 33803 16932 33803 19282 33803 19282 33804 16932 33804 16927 33804 16959 33805 17327 33805 19838 33805 16933 33806 16960 33806 16934 33806 16934 33807 16960 33807 16959 33807 16947 33808 16956 33808 16933 33808 16959 33809 19838 33809 16934 33809 16934 33810 19838 33810 19837 33810 16934 33811 19837 33811 16938 33811 16938 33812 19837 33812 16935 33812 16938 33813 16935 33813 16936 33813 16936 33814 16935 33814 19834 33814 16936 33815 19834 33815 16937 33815 16937 33816 19834 33816 16949 33816 16937 33817 16949 33817 16941 33817 16933 33818 16934 33818 16947 33818 16947 33819 16934 33819 16938 33819 16947 33820 16938 33820 16946 33820 16946 33821 16938 33821 16936 33821 16946 33822 16936 33822 16939 33822 16939 33823 16936 33823 16937 33823 16939 33824 16937 33824 16940 33824 16940 33825 16937 33825 16941 33825 16940 33826 16941 33826 16942 33826 16950 33827 16943 33827 16942 33827 16942 33828 16943 33828 19287 33828 16942 33829 19287 33829 16940 33829 16940 33830 19287 33830 16944 33830 16940 33831 16944 33831 16939 33831 16939 33832 16944 33832 16945 33832 16939 33833 16945 33833 16946 33833 16946 33834 16945 33834 19284 33834 16946 33835 19284 33835 16947 33835 16947 33836 19284 33836 16948 33836 16947 33837 16948 33837 16956 33837 16949 33838 19832 33838 16941 33838 16941 33839 19832 33839 16955 33839 16941 33840 16955 33840 16942 33840 16942 33841 16955 33841 16951 33841 16942 33842 16951 33842 16950 33842 16950 33843 16951 33843 16952 33843 19282 33844 16952 33844 16953 33844 16953 33845 16952 33845 16951 33845 16953 33846 16951 33846 16930 33846 16930 33847 16951 33847 16955 33847 16930 33848 16955 33848 16954 33848 16954 33849 16955 33849 19832 33849 16954 33850 19832 33850 16928 33850 16962 33851 16933 33851 16963 33851 16963 33852 16933 33852 16956 33852 16963 33853 16956 33853 19283 33853 19283 33854 16956 33854 16948 33854 16957 33855 17327 33855 16958 33855 16958 33856 17327 33856 16959 33856 16958 33857 16959 33857 16962 33857 16962 33858 16959 33858 16960 33858 16962 33859 16960 33859 16933 33859 17328 33860 16957 33860 16964 33860 16964 33861 16957 33861 16958 33861 16964 33862 16958 33862 16961 33862 16961 33863 16958 33863 16962 33863 16961 33864 16962 33864 16966 33864 16966 33865 16962 33865 16963 33865 16966 33866 16963 33866 16967 33866 17329 33867 17328 33867 16969 33867 16969 33868 17328 33868 16964 33868 16969 33869 16964 33869 16965 33869 16965 33870 16964 33870 16961 33870 16965 33871 16961 33871 16970 33871 16970 33872 16961 33872 16966 33872 16970 33873 16966 33873 16972 33873 16972 33874 16966 33874 16967 33874 19692 33875 17329 33875 16968 33875 16968 33876 17329 33876 16969 33876 16968 33877 16969 33877 16976 33877 16976 33878 16969 33878 16965 33878 16976 33879 16965 33879 16971 33879 16971 33880 16965 33880 16970 33880 16971 33881 16970 33881 19279 33881 19279 33882 16970 33882 16972 33882 19693 33883 19692 33883 16968 33883 16975 33884 16973 33884 16974 33884 16974 33885 19693 33885 16975 33885 16975 33886 19693 33886 16968 33886 16975 33887 16968 33887 16993 33887 16993 33888 16968 33888 16976 33888 16993 33889 16976 33889 16978 33889 16978 33890 16976 33890 16971 33890 16978 33891 16971 33891 19278 33891 19278 33892 16971 33892 19279 33892 16979 33893 16977 33893 17027 33893 16978 33894 19278 33894 19277 33894 16982 33895 19275 33895 16979 33895 16979 33896 19275 33896 19274 33896 16979 33897 19274 33897 16977 33897 16999 33898 16980 33898 17002 33898 16999 33899 17004 33899 16981 33899 16999 33900 16982 33900 16983 33900 16983 33901 16982 33901 16979 33901 16983 33902 16979 33902 16984 33902 16984 33903 16979 33903 17027 33903 16984 33904 17027 33904 17018 33904 17000 33905 17003 33905 17001 33905 17000 33906 16985 33906 16986 33906 17000 33907 16986 33907 16998 33907 19277 33908 17005 33908 16978 33908 16978 33909 17005 33909 17000 33909 16978 33910 17000 33910 16993 33910 16990 33911 16973 33911 16992 33911 16992 33912 16973 33912 16975 33912 16991 33913 16997 33913 16996 33913 17344 33914 16987 33914 16996 33914 16996 33915 16987 33915 16988 33915 16996 33916 16988 33916 16991 33916 16991 33917 16988 33917 16989 33917 16991 33918 16989 33918 16992 33918 16992 33919 16989 33919 17346 33919 16992 33920 17346 33920 16990 33920 16997 33921 16991 33921 16998 33921 16998 33922 16991 33922 16992 33922 16998 33923 16992 33923 17000 33923 17000 33924 16992 33924 16975 33924 17000 33925 16975 33925 16993 33925 16994 33926 17344 33926 16995 33926 16995 33927 17344 33927 16996 33927 16995 33928 16996 33928 17018 33928 17018 33929 16996 33929 16997 33929 17018 33930 16997 33930 16984 33930 16984 33931 16997 33931 16998 33931 16984 33932 16998 33932 16983 33932 16983 33933 16998 33933 16986 33933 16983 33934 16986 33934 16999 33934 16999 33935 16986 33935 16985 33935 16999 33936 16985 33936 16980 33936 16980 33937 16985 33937 17000 33937 16980 33938 17000 33938 17002 33938 17002 33939 17000 33939 17001 33939 17002 33940 17001 33940 16999 33940 16999 33941 17001 33941 17003 33941 16999 33942 17003 33942 17004 33942 17004 33943 17003 33943 17000 33943 17004 33944 17000 33944 16981 33944 16981 33945 17000 33945 17005 33945 16981 33946 17005 33946 16999 33946 16999 33947 17005 33947 19277 33947 17006 33948 17359 33948 19841 33948 17007 33949 17047 33949 17013 33949 17013 33950 17047 33950 17006 33950 17009 33951 17045 33951 17008 33951 17008 33952 17045 33952 17007 33952 17009 33953 17008 33953 17010 33953 17010 33954 17008 33954 17019 33954 17010 33955 17019 33955 19271 33955 19271 33956 17019 33956 17011 33956 17011 33957 17019 33957 17022 33957 17011 33958 17022 33958 17012 33958 17006 33959 19841 33959 17013 33959 17013 33960 19841 33960 17014 33960 17013 33961 17014 33961 17020 33961 17020 33962 17014 33962 17015 33962 17020 33963 17015 33963 17021 33963 17021 33964 17015 33964 19843 33964 17021 33965 19843 33965 17023 33965 17023 33966 19843 33966 17016 33966 17023 33967 17016 33967 17024 33967 17024 33968 17016 33968 19845 33968 17024 33969 19845 33969 17017 33969 19845 33970 16994 33970 16995 33970 19845 33971 16995 33971 17017 33971 17017 33972 16995 33972 17018 33972 17017 33973 17018 33973 17027 33973 17007 33974 17013 33974 17008 33974 17008 33975 17013 33975 17020 33975 17008 33976 17020 33976 17019 33976 17019 33977 17020 33977 17021 33977 17019 33978 17021 33978 17022 33978 17022 33979 17021 33979 17023 33979 17022 33980 17023 33980 17028 33980 17028 33981 17023 33981 17024 33981 17028 33982 17024 33982 17025 33982 17025 33983 17024 33983 17017 33983 17025 33984 17017 33984 17026 33984 17026 33985 17017 33985 17027 33985 17026 33986 17027 33986 16977 33986 17012 33987 17022 33987 19241 33987 19241 33988 17022 33988 17028 33988 19241 33989 17028 33989 17029 33989 17029 33990 17028 33990 17025 33990 17029 33991 17025 33991 17030 33991 17030 33992 17025 33992 17026 33992 17030 33993 17026 33993 19273 33993 19273 33994 17026 33994 16977 33994 19273 33995 16977 33995 19274 33995 17355 33996 17356 33996 17042 33996 17041 33997 17360 33997 17040 33997 17040 33998 17360 33998 17357 33998 17035 33999 17031 33999 17037 33999 17045 34000 17009 34000 19269 34000 17032 34001 19262 34001 17035 34001 17035 34002 19262 34002 19264 34002 17035 34003 19264 34003 17031 34003 17034 34004 17052 34004 17054 34004 17056 34005 17033 34005 17034 34005 17034 34006 17032 34006 17049 34006 17049 34007 17032 34007 17035 34007 17049 34008 17035 34008 17036 34008 17036 34009 17035 34009 17037 34009 17036 34010 17037 34010 17038 34010 17043 34011 17055 34011 17053 34011 17043 34012 17051 34012 17050 34012 17043 34013 17050 34013 17048 34013 17359 34014 17006 34014 17358 34014 17358 34015 17006 34015 17039 34015 17358 34016 17039 34016 17357 34016 17357 34017 17039 34017 17044 34017 17357 34018 17044 34018 17040 34018 17356 34019 17041 34019 17042 34019 17042 34020 17041 34020 17040 34020 17042 34021 17040 34021 17048 34021 17048 34022 17040 34022 17044 34022 17048 34023 17044 34023 17043 34023 17043 34024 17044 34024 17039 34024 19269 34025 17046 34025 17045 34025 17045 34026 17046 34026 17043 34026 17045 34027 17043 34027 17007 34027 17007 34028 17043 34028 17039 34028 17007 34029 17039 34029 17047 34029 17047 34030 17039 34030 17006 34030 17808 34031 17355 34031 17038 34031 17038 34032 17355 34032 17042 34032 17038 34033 17042 34033 17036 34033 17036 34034 17042 34034 17048 34034 17036 34035 17048 34035 17049 34035 17049 34036 17048 34036 17050 34036 17049 34037 17050 34037 17034 34037 17034 34038 17050 34038 17051 34038 17034 34039 17051 34039 17052 34039 17052 34040 17051 34040 17043 34040 17052 34041 17043 34041 17054 34041 17054 34042 17043 34042 17053 34042 17054 34043 17053 34043 17034 34043 17034 34044 17053 34044 17055 34044 17034 34045 17055 34045 17056 34045 17056 34046 17055 34046 17043 34046 17056 34047 17043 34047 17033 34047 17033 34048 17043 34048 17046 34048 17033 34049 17046 34049 17034 34049 17034 34050 17046 34050 19269 34050 17061 34051 19267 34051 17062 34051 17062 34052 19267 34052 17057 34052 17062 34053 17057 34053 17063 34053 17063 34054 17057 34054 17058 34054 17063 34055 17058 34055 17064 34055 17064 34056 17058 34056 17059 34056 17064 34057 17059 34057 17060 34057 17060 34058 17059 34058 17801 34058 19264 34059 17061 34059 17031 34059 17031 34060 17061 34060 17062 34060 17031 34061 17062 34061 17037 34061 17037 34062 17062 34062 17063 34062 17037 34063 17063 34063 17038 34063 17038 34064 17063 34064 17064 34064 17038 34065 17064 34065 17808 34065 17808 34066 17064 34066 17060 34066 17065 34067 17073 34067 17075 34067 17070 34068 17069 34068 17075 34068 17067 34069 17068 34069 17066 34069 17067 34070 17066 34070 17057 34070 17066 34071 17071 34071 17072 34071 17057 34072 19267 34072 17067 34072 17067 34073 19267 34073 17075 34073 17067 34074 17075 34074 17068 34074 17068 34075 17075 34075 17069 34075 17068 34076 17069 34076 17066 34076 17066 34077 17069 34077 17070 34077 17066 34078 17070 34078 17071 34078 17071 34079 17070 34079 17075 34079 17071 34080 17075 34080 17072 34080 17072 34081 17075 34081 17073 34081 17072 34082 17073 34082 17066 34082 17066 34083 17073 34083 17065 34083 17066 34084 17065 34084 17074 34084 17074 34085 17065 34085 17075 34085 17076 34086 17801 34086 17077 34086 17077 34087 17801 34087 17059 34087 17077 34088 17059 34088 17066 34088 17066 34089 17059 34089 17058 34089 17066 34090 17058 34090 17057 34090 17736 34091 17076 34091 17078 34091 17078 34092 17076 34092 17077 34092 17078 34093 17077 34093 17081 34093 17081 34094 17077 34094 17066 34094 17081 34095 17066 34095 17079 34095 17079 34096 17066 34096 17074 34096 17079 34097 17074 34097 19249 34097 19249 34098 17074 34098 17075 34098 17734 34099 17736 34099 17082 34099 17082 34100 17736 34100 17078 34100 17082 34101 17078 34101 17080 34101 17080 34102 17078 34102 17081 34102 17080 34103 17081 34103 17085 34103 17085 34104 17081 34104 17079 34104 17085 34105 17079 34105 19248 34105 19248 34106 17079 34106 19249 34106 17772 34107 17734 34107 17089 34107 17089 34108 17734 34108 17082 34108 17089 34109 17082 34109 17083 34109 17083 34110 17082 34110 17080 34110 17083 34111 17080 34111 17084 34111 17084 34112 17080 34112 17085 34112 17084 34113 17085 34113 17097 34113 17097 34114 17085 34114 19248 34114 17086 34115 17102 34115 17090 34115 17102 34116 17778 34116 17776 34116 17087 34117 17088 34117 17092 34117 17092 34118 17088 34118 17086 34118 17774 34119 17772 34119 17089 34119 17102 34120 17776 34120 17090 34120 17090 34121 17776 34121 17775 34121 17090 34122 17775 34122 17091 34122 17091 34123 17775 34123 17774 34123 17091 34124 17774 34124 17093 34124 17093 34125 17774 34125 17089 34125 17093 34126 17089 34126 17083 34126 17086 34127 17090 34127 17092 34127 17092 34128 17090 34128 17091 34128 17092 34129 17091 34129 17095 34129 17095 34130 17091 34130 17093 34130 17095 34131 17093 34131 17096 34131 17096 34132 17093 34132 17083 34132 17096 34133 17083 34133 17084 34133 17087 34134 17092 34134 17094 34134 17094 34135 17092 34135 17095 34135 17094 34136 17095 34136 19258 34136 19258 34137 17095 34137 17096 34137 19258 34138 17096 34138 19259 34138 19259 34139 17096 34139 17084 34139 19259 34140 17084 34140 17097 34140 17087 34141 19256 34141 17098 34141 17087 34142 17098 34142 17088 34142 17088 34143 17098 34143 17099 34143 17088 34144 17099 34144 17086 34144 17086 34145 17099 34145 17100 34145 17086 34146 17100 34146 17102 34146 17102 34147 17100 34147 17101 34147 17102 34148 17101 34148 17778 34148 18343 34149 17768 34149 17103 34149 17103 34150 17768 34150 20920 34150 17103 34151 20920 34151 17104 34151 17104 34152 20920 34152 17105 34152 17105 34153 20920 34153 20921 34153 17105 34154 20921 34154 17110 34154 17110 34155 20921 34155 20923 34155 17110 34156 20923 34156 17109 34156 17109 34157 20923 34157 19254 34157 17109 34158 19254 34158 17106 34158 17106 34159 17107 34159 17108 34159 17106 34160 17108 34160 17109 34160 17109 34161 17108 34161 17114 34161 17109 34162 17114 34162 17110 34162 17110 34163 17114 34163 17105 34163 17105 34164 17114 34164 17111 34164 17105 34165 17111 34165 17104 34165 17104 34166 17111 34166 17103 34166 17103 34167 17111 34167 18342 34167 17103 34168 18342 34168 18343 34168 18233 34169 18342 34169 17112 34169 17112 34170 18342 34170 17111 34170 17112 34171 17111 34171 17113 34171 17113 34172 17111 34172 17114 34172 17113 34173 17114 34173 17120 34173 17120 34174 17114 34174 17108 34174 17120 34175 17108 34175 19250 34175 19250 34176 17108 34176 17107 34176 17121 34177 17122 34177 17115 34177 17120 34178 19250 34178 19266 34178 18233 34179 17112 34179 17116 34179 17116 34180 17112 34180 17117 34180 18125 34181 17117 34181 17118 34181 17118 34182 17117 34182 17112 34182 17118 34183 17112 34183 17119 34183 17119 34184 17112 34184 17113 34184 17119 34185 17113 34185 17115 34185 17115 34186 17113 34186 17120 34186 17115 34187 17120 34187 17121 34187 17121 34188 17120 34188 19266 34188 17121 34189 19266 34189 19265 34189 17127 34190 18125 34190 17118 34190 17122 34191 19268 34191 17115 34191 17115 34192 19268 34192 19276 34192 17115 34193 19276 34193 17123 34193 17123 34194 19289 34194 17115 34194 17115 34195 19289 34195 19293 34195 17115 34196 19293 34196 17124 34196 17125 34197 19307 34197 17126 34197 17124 34198 17125 34198 17115 34198 17115 34199 17125 34199 17126 34199 17115 34200 17126 34200 17119 34200 17119 34201 17126 34201 17129 34201 17119 34202 17129 34202 17118 34202 17118 34203 17129 34203 17130 34203 17118 34204 17130 34204 17127 34204 17127 34205 17130 34205 18123 34205 19308 34206 19310 34206 17131 34206 17126 34207 17133 34207 17129 34207 17129 34208 17133 34208 17128 34208 17129 34209 17128 34209 17130 34209 17130 34210 17128 34210 17132 34210 17130 34211 17132 34211 18123 34211 19307 34212 19308 34212 17126 34212 17126 34213 19308 34213 17131 34213 17126 34214 17131 34214 17133 34214 18603 34215 17132 34215 17128 34215 17137 34216 17128 34216 17133 34216 17142 34217 17143 34217 17134 34217 19245 34218 17143 34218 19314 34218 19314 34219 17143 34219 17142 34219 19314 34220 17142 34220 19310 34220 17135 34221 17138 34221 17136 34221 17136 34222 17138 34222 17137 34222 17136 34223 17137 34223 17141 34223 17141 34224 17137 34224 17133 34224 17141 34225 17133 34225 17131 34225 17138 34226 19210 34226 17137 34226 17137 34227 19210 34227 17139 34227 17137 34228 17139 34228 17128 34228 17128 34229 17139 34229 19212 34229 17128 34230 19212 34230 18603 34230 17145 34231 17140 34231 19207 34231 19207 34232 17135 34232 17145 34232 17145 34233 17135 34233 17136 34233 17145 34234 17136 34234 17134 34234 17134 34235 17136 34235 17141 34235 17134 34236 17141 34236 17142 34236 17142 34237 17141 34237 17131 34237 17142 34238 17131 34238 19310 34238 19245 34239 19244 34239 17143 34239 17143 34240 19244 34240 17149 34240 17143 34241 17149 34241 17134 34241 17134 34242 17149 34242 17144 34242 17134 34243 17144 34243 17145 34243 17145 34244 17144 34244 17152 34244 17145 34245 17152 34245 17140 34245 17140 34246 17152 34246 18764 34246 18757 34247 17146 34247 17164 34247 17147 34248 17148 34248 17163 34248 17166 34249 17167 34249 19323 34249 17149 34250 19244 34250 17147 34250 17158 34251 17150 34251 17159 34251 17159 34252 17150 34252 17151 34252 17147 34253 17163 34253 17149 34253 17149 34254 17163 34254 17161 34254 17149 34255 17161 34255 17144 34255 17144 34256 17161 34256 17159 34256 17144 34257 17159 34257 17152 34257 17152 34258 17159 34258 17151 34258 17152 34259 17151 34259 18764 34259 18762 34260 17154 34260 17153 34260 17153 34261 17154 34261 17157 34261 19321 34262 17155 34262 17162 34262 17162 34263 17155 34263 17156 34263 17162 34264 17156 34264 17160 34264 17157 34265 17158 34265 17153 34265 17153 34266 17158 34266 17159 34266 17153 34267 17159 34267 17160 34267 17160 34268 17159 34268 17161 34268 17160 34269 17161 34269 17162 34269 17162 34270 17161 34270 17163 34270 17162 34271 17163 34271 19321 34271 19321 34272 17163 34272 17148 34272 17165 34273 17166 34273 17169 34273 17169 34274 17166 34274 19323 34274 17169 34275 19323 34275 17171 34275 17146 34276 18762 34276 17164 34276 17164 34277 18762 34277 17153 34277 17164 34278 17153 34278 17165 34278 17165 34279 17153 34279 17160 34279 17165 34280 17160 34280 17166 34280 17166 34281 17160 34281 17156 34281 17166 34282 17156 34282 17167 34282 17167 34283 17156 34283 17155 34283 17168 34284 18757 34284 17182 34284 17182 34285 18757 34285 17164 34285 17182 34286 17164 34286 17183 34286 17183 34287 17164 34287 17165 34287 17183 34288 17165 34288 17181 34288 17181 34289 17165 34289 17169 34289 17181 34290 17169 34290 17170 34290 17170 34291 17169 34291 17171 34291 17208 34292 17243 34292 17224 34292 17207 34293 19352 34293 17206 34293 19352 34294 17207 34294 19353 34294 19353 34295 17207 34295 17172 34295 19353 34296 17172 34296 19355 34296 17172 34297 17173 34297 19355 34297 19355 34298 17173 34298 17174 34298 19355 34299 17174 34299 17175 34299 17175 34300 17174 34300 17209 34300 17175 34301 17209 34301 19351 34301 19345 34302 17210 34302 17205 34302 17201 34303 19340 34303 17176 34303 17176 34304 19340 34304 19343 34304 17176 34305 19343 34305 17203 34305 17203 34306 19343 34306 19345 34306 17203 34307 19345 34307 17204 34307 17204 34308 19345 34308 17205 34308 17197 34309 17177 34309 17178 34309 17178 34310 17177 34310 19337 34310 17178 34311 19337 34311 17179 34311 17179 34312 19337 34312 17180 34312 17179 34313 17180 34313 17198 34313 17198 34314 17180 34314 19243 34314 17198 34315 19243 34315 17200 34315 17186 34316 17184 34316 19332 34316 19332 34317 17184 34317 19324 34317 17170 34318 19324 34318 17181 34318 17181 34319 19324 34319 17184 34319 17181 34320 17184 34320 17183 34320 17182 34321 17183 34321 17185 34321 17168 34322 17182 34322 17211 34322 17183 34323 17184 34323 17185 34323 17185 34324 17184 34324 17186 34324 17185 34325 17186 34325 17187 34325 17187 34326 17186 34326 17189 34326 17187 34327 17189 34327 17190 34327 19332 34328 19333 34328 17186 34328 17186 34329 19333 34329 17188 34329 17186 34330 17188 34330 17189 34330 17189 34331 17188 34331 17194 34331 17189 34332 17194 34332 17190 34332 17190 34333 17194 34333 17195 34333 17190 34334 17195 34334 17213 34334 17213 34335 17195 34335 17191 34335 17213 34336 17191 34336 17192 34336 17192 34337 17191 34337 17193 34337 17192 34338 17193 34338 17214 34338 17188 34339 19455 34339 17194 34339 17194 34340 19455 34340 19456 34340 17194 34341 19456 34341 17195 34341 17195 34342 19456 34342 17196 34342 17195 34343 17196 34343 17191 34343 17191 34344 17196 34344 17197 34344 17191 34345 17197 34345 17193 34345 17193 34346 17197 34346 17178 34346 17193 34347 17178 34347 17214 34347 17214 34348 17178 34348 17179 34348 17214 34349 17179 34349 17216 34349 17216 34350 17179 34350 17198 34350 17216 34351 17198 34351 17199 34351 17199 34352 17198 34352 17200 34352 17199 34353 17200 34353 17202 34353 19243 34354 17201 34354 17200 34354 17200 34355 17201 34355 17176 34355 17200 34356 17176 34356 17202 34356 17202 34357 17176 34357 17203 34357 17202 34358 17203 34358 17218 34358 17218 34359 17203 34359 17204 34359 17218 34360 17204 34360 17220 34360 17220 34361 17204 34361 17205 34361 17220 34362 17205 34362 17221 34362 17206 34363 17208 34363 17207 34363 17207 34364 17208 34364 17224 34364 17207 34365 17224 34365 17172 34365 17172 34366 17224 34366 17223 34366 17172 34367 17223 34367 17173 34367 17173 34368 17223 34368 17222 34368 17173 34369 17222 34369 17174 34369 17174 34370 17222 34370 17221 34370 17174 34371 17221 34371 17209 34371 17209 34372 17221 34372 17205 34372 17209 34373 17205 34373 19351 34373 19351 34374 17205 34374 17210 34374 17182 34375 17185 34375 17211 34375 17211 34376 17185 34376 17187 34376 17211 34377 17187 34377 17227 34377 17227 34378 17187 34378 17190 34378 17227 34379 17190 34379 17212 34379 17212 34380 17190 34380 17213 34380 17212 34381 17213 34381 17228 34381 17228 34382 17213 34382 17192 34382 17228 34383 17192 34383 17229 34383 17229 34384 17192 34384 17214 34384 17229 34385 17214 34385 17215 34385 17215 34386 17214 34386 17216 34386 17215 34387 17216 34387 17217 34387 17217 34388 17216 34388 17199 34388 17217 34389 17199 34389 17231 34389 17231 34390 17199 34390 17202 34390 17231 34391 17202 34391 17233 34391 17233 34392 17202 34392 17218 34392 17233 34393 17218 34393 17234 34393 17234 34394 17218 34394 17220 34394 17234 34395 17220 34395 17219 34395 17219 34396 17220 34396 17221 34396 17219 34397 17221 34397 17235 34397 17235 34398 17221 34398 17222 34398 17235 34399 17222 34399 17236 34399 17236 34400 17222 34400 17223 34400 17236 34401 17223 34401 17237 34401 17237 34402 17223 34402 17224 34402 17237 34403 17224 34403 17238 34403 17238 34404 17224 34404 17243 34404 17238 34405 17243 34405 17241 34405 17168 34406 17211 34406 17225 34406 17225 34407 17211 34407 17227 34407 17225 34408 17227 34408 17226 34408 17226 34409 17227 34409 17212 34409 17226 34410 17212 34410 18760 34410 18760 34411 17212 34411 17228 34411 18760 34412 17228 34412 18755 34412 18755 34413 17228 34413 17229 34413 18755 34414 17229 34414 17230 34414 17230 34415 17229 34415 17215 34415 17230 34416 17215 34416 18955 34416 18955 34417 17215 34417 17217 34417 18955 34418 17217 34418 18954 34418 18954 34419 17217 34419 17231 34419 18954 34420 17231 34420 17232 34420 17232 34421 17231 34421 17233 34421 17232 34422 17233 34422 18953 34422 18953 34423 17233 34423 17234 34423 18953 34424 17234 34424 18753 34424 18753 34425 17234 34425 17219 34425 18753 34426 17219 34426 18751 34426 18751 34427 17219 34427 17235 34427 18751 34428 17235 34428 18750 34428 18750 34429 17235 34429 17236 34429 18750 34430 17236 34430 18746 34430 18746 34431 17236 34431 17237 34431 18746 34432 17237 34432 18745 34432 18745 34433 17237 34433 17238 34433 18745 34434 17238 34434 18743 34434 18743 34435 17238 34435 17241 34435 18743 34436 17241 34436 17240 34436 19356 34437 17239 34437 17245 34437 18882 34438 17240 34438 17242 34438 17242 34439 17240 34439 17241 34439 17242 34440 17241 34440 17247 34440 17247 34441 17241 34441 17243 34441 17247 34442 17243 34442 17245 34442 17245 34443 17243 34443 17208 34443 17245 34444 17208 34444 19356 34444 19356 34445 17208 34445 17206 34445 19058 34446 18882 34446 17242 34446 17244 34447 19367 34447 17256 34447 17239 34448 19449 34448 17245 34448 17245 34449 19449 34449 17246 34449 17245 34450 17246 34450 19359 34450 19058 34451 17242 34451 19059 34451 19055 34452 19054 34452 17248 34452 17248 34453 19054 34453 17249 34453 19359 34454 17250 34454 17245 34454 17245 34455 17250 34455 17252 34455 17245 34456 17252 34456 17247 34456 17247 34457 17252 34457 17248 34457 17247 34458 17248 34458 17242 34458 17242 34459 17248 34459 17249 34459 17242 34460 17249 34460 19059 34460 19359 34461 19365 34461 17250 34461 17250 34462 19365 34462 17251 34462 17250 34463 17251 34463 17252 34463 17252 34464 17251 34464 17257 34464 17252 34465 17257 34465 17248 34465 17248 34466 17257 34466 17254 34466 17248 34467 17254 34467 19055 34467 19055 34468 17254 34468 19113 34468 18612 34469 19113 34469 17253 34469 17253 34470 19113 34470 17254 34470 17253 34471 17254 34471 17255 34471 17255 34472 17254 34472 17257 34472 17255 34473 17257 34473 17256 34473 17256 34474 17257 34474 17251 34474 17256 34475 17251 34475 17244 34475 17244 34476 17251 34476 19365 34476 17259 34477 17258 34477 17260 34477 17256 34478 19367 34478 17259 34478 17259 34479 17260 34479 17256 34479 17256 34480 17260 34480 17265 34480 17256 34481 17265 34481 17255 34481 17255 34482 17265 34482 17264 34482 17255 34483 17264 34483 17253 34483 17253 34484 17264 34484 18151 34484 17253 34485 18151 34485 18612 34485 17258 34486 19369 34486 17260 34486 17260 34487 19369 34487 17266 34487 19374 34488 17261 34488 17262 34488 17262 34489 17261 34489 19376 34489 17262 34490 19376 34490 19378 34490 18152 34491 18151 34491 17264 34491 18158 34492 17268 34492 17263 34492 17263 34493 17268 34493 18329 34493 18158 34494 18152 34494 17268 34494 17268 34495 18152 34495 17264 34495 17268 34496 17264 34496 17269 34496 17269 34497 17264 34497 17265 34497 17269 34498 17265 34498 17262 34498 17262 34499 17265 34499 17260 34499 17262 34500 17260 34500 19374 34500 19374 34501 17260 34501 17266 34501 17262 34502 19378 34502 17274 34502 19383 34503 17281 34503 17267 34503 17267 34504 17281 34504 19385 34504 17273 34505 17276 34505 17271 34505 17272 34506 18329 34506 17268 34506 17268 34507 17269 34507 17270 34507 17271 34508 17272 34508 17273 34508 17273 34509 17272 34509 17268 34509 17273 34510 17268 34510 17278 34510 17278 34511 17268 34511 17270 34511 17274 34512 19385 34512 17262 34512 17262 34513 19385 34513 17281 34513 17262 34514 17281 34514 17269 34514 17269 34515 17281 34515 17275 34515 17269 34516 17275 34516 17270 34516 16582 34517 18372 34517 17276 34517 16582 34518 17276 34518 16583 34518 16583 34519 17276 34519 17273 34519 16583 34520 17273 34520 16581 34520 16581 34521 17273 34521 17277 34521 17277 34522 17273 34522 17278 34522 17277 34523 17278 34523 17279 34523 17279 34524 17278 34524 17270 34524 17279 34525 17270 34525 16577 34525 16577 34526 17270 34526 17275 34526 16577 34527 17275 34527 17280 34527 17280 34528 17275 34528 17281 34528 17280 34529 17281 34529 16579 34529 19383 34530 19382 34530 17281 34530 17281 34531 19382 34531 19399 34531 17281 34532 19399 34532 16579 34532 16579 34533 19399 34533 16592 34533 17282 34534 17284 34534 17765 34534 17765 34535 17284 34535 17283 34535 17283 34536 17284 34536 17285 34536 17285 34537 17284 34537 17402 34537 17285 34538 17402 34538 17286 34538 17301 34539 17297 34539 17298 34539 17297 34540 17296 34540 17295 34540 17287 34541 19710 34541 17288 34541 17289 34542 15451 34542 15450 34542 17290 34543 17289 34543 17291 34543 17290 34544 19711 34544 17302 34544 17302 34545 19711 34545 17292 34545 17302 34546 17292 34546 17301 34546 15461 34547 17293 34547 17762 34547 17762 34548 17293 34548 17300 34548 17762 34549 17300 34549 17761 34549 17761 34550 17300 34550 17299 34550 17761 34551 17299 34551 17294 34551 17294 34552 17299 34552 17295 34552 17294 34553 17295 34553 17288 34553 17288 34554 17295 34554 17296 34554 17288 34555 17296 34555 17287 34555 17297 34556 17295 34556 17298 34556 17298 34557 17295 34557 17299 34557 17298 34558 17299 34558 17303 34558 17303 34559 17299 34559 17300 34559 17303 34560 17300 34560 17304 34560 17304 34561 17300 34561 17293 34561 17304 34562 17293 34562 15458 34562 17301 34563 17298 34563 17302 34563 17302 34564 17298 34564 17303 34564 17302 34565 17303 34565 17290 34565 17290 34566 17303 34566 17304 34566 17290 34567 17304 34567 17289 34567 17289 34568 17304 34568 15458 34568 17289 34569 15458 34569 15451 34569 17307 34570 16910 34570 17305 34570 17308 34571 17309 34571 17306 34571 17306 34572 17309 34572 17307 34572 17306 34573 17307 34573 19526 34573 19526 34574 17307 34574 17305 34574 19526 34575 17305 34575 19691 34575 17308 34576 19535 34576 17309 34576 17309 34577 19535 34577 17310 34577 17309 34578 17310 34578 17311 34578 17311 34579 17310 34579 19536 34579 17311 34580 19536 34580 17312 34580 19581 34581 19579 34581 17313 34581 17314 34582 17315 34582 19581 34582 19581 34583 17313 34583 17314 34583 17314 34584 17313 34584 16866 34584 17314 34585 16866 34585 19532 34585 19532 34586 16866 34586 17318 34586 19532 34587 17318 34587 17316 34587 17316 34588 17318 34588 17317 34588 17317 34589 17318 34589 16868 34589 17317 34590 16868 34590 19538 34590 17319 34591 19569 34591 19571 34591 17320 34592 17319 34592 17321 34592 17321 34593 17319 34593 19571 34593 17321 34594 19571 34594 17322 34594 17322 34595 19571 34595 19570 34595 17322 34596 19570 34596 16619 34596 16619 34597 19570 34597 19563 34597 16619 34598 19563 34598 16606 34598 16606 34599 19563 34599 19568 34599 17323 34600 16837 34600 17324 34600 17325 34601 17326 34601 19461 34601 19461 34602 17326 34602 17323 34602 19461 34603 17323 34603 19462 34603 19462 34604 17323 34604 17324 34604 19839 34605 17327 34605 16957 34605 16957 34606 17328 34606 17330 34606 17330 34607 17328 34607 17329 34607 17330 34608 17329 34608 17332 34608 17332 34609 17329 34609 19692 34609 17332 34610 19692 34610 17333 34610 19545 34611 19840 34611 19839 34611 19839 34612 16957 34612 19545 34612 19545 34613 16957 34613 17330 34613 19545 34614 17330 34614 17331 34614 17331 34615 17330 34615 17332 34615 17331 34616 17332 34616 19544 34616 19544 34617 17332 34617 19546 34617 19546 34618 17332 34618 17333 34618 19546 34619 17333 34619 17334 34619 20757 34620 17335 34620 17343 34620 20757 34621 17343 34621 17336 34621 17336 34622 17343 34622 17338 34622 17336 34623 17338 34623 17337 34623 17337 34624 17338 34624 17339 34624 17337 34625 17339 34625 16686 34625 16686 34626 17339 34626 17342 34626 16686 34627 17342 34627 15479 34627 17340 34628 17342 34628 17341 34628 17341 34629 17342 34629 17339 34629 17341 34630 17339 34630 19552 34630 19552 34631 17339 34631 17338 34631 19552 34632 17338 34632 19554 34632 19554 34633 17338 34633 19555 34633 19555 34634 17338 34634 17343 34634 19555 34635 17343 34635 19543 34635 19543 34636 17343 34636 19548 34636 19548 34637 17343 34637 17335 34637 19548 34638 17335 34638 19549 34638 16994 34639 17354 34639 17344 34639 17344 34640 17354 34640 17345 34640 17344 34641 17345 34641 16987 34641 16987 34642 17345 34642 16988 34642 16988 34643 17345 34643 17350 34643 16988 34644 17350 34644 16989 34644 16989 34645 17350 34645 17346 34645 17346 34646 17350 34646 17349 34646 17346 34647 17349 34647 16990 34647 17347 34648 17348 34648 19694 34648 16973 34649 16990 34649 19694 34649 19694 34650 16990 34650 17349 34650 19694 34651 17349 34651 17347 34651 17347 34652 17349 34652 17350 34652 17347 34653 17350 34653 17351 34653 17351 34654 17350 34654 17352 34654 17352 34655 17350 34655 17345 34655 17352 34656 17345 34656 19524 34656 19524 34657 17345 34657 17353 34657 17353 34658 17345 34658 17354 34658 17353 34659 17354 34659 19525 34659 17808 34660 17807 34660 17355 34660 17355 34661 17807 34661 17368 34661 17355 34662 17368 34662 17356 34662 17356 34663 17368 34663 17041 34663 17361 34664 17357 34664 17360 34664 17357 34665 17361 34665 17358 34665 17358 34666 17361 34666 17363 34666 17358 34667 17363 34667 17359 34667 17360 34668 17369 34668 17361 34668 17361 34669 17369 34669 17362 34669 17361 34670 17362 34670 17363 34670 17363 34671 17362 34671 17364 34671 17365 34672 17366 34672 17369 34672 17369 34673 17366 34673 17367 34673 17369 34674 17367 34674 17362 34674 17360 34675 17041 34675 17369 34675 17369 34676 17041 34676 17368 34676 17369 34677 17368 34677 17365 34677 17365 34678 17368 34678 17807 34678 17365 34679 17807 34679 17370 34679 17371 34680 17381 34680 17372 34680 17371 34681 17372 34681 17373 34681 17373 34682 17372 34682 17379 34682 17373 34683 17379 34683 17374 34683 17374 34684 17379 34684 17377 34684 17374 34685 17377 34685 16643 34685 17378 34686 19574 34686 17375 34686 17376 34687 16643 34687 17375 34687 17375 34688 16643 34688 17377 34688 17375 34689 17377 34689 17378 34689 17378 34690 17377 34690 17379 34690 17378 34691 17379 34691 19572 34691 19572 34692 17379 34692 19573 34692 19573 34693 17379 34693 17372 34693 19573 34694 17372 34694 17380 34694 17380 34695 17372 34695 19576 34695 19576 34696 17372 34696 17381 34696 19576 34697 17381 34697 19567 34697 17382 34698 19551 34698 17384 34698 17387 34699 17383 34699 16659 34699 16659 34700 17383 34700 16661 34700 17384 34701 16656 34701 16661 34701 17385 34702 20785 34702 16656 34702 16656 34703 17384 34703 17385 34703 17385 34704 17384 34704 19551 34704 17385 34705 19551 34705 19550 34705 16661 34706 17383 34706 17384 34706 17384 34707 17383 34707 17386 34707 17384 34708 17386 34708 17382 34708 16659 34709 15480 34709 17387 34709 17387 34710 15480 34710 17388 34710 17387 34711 17388 34711 17389 34711 17389 34712 19562 34712 17387 34712 17387 34713 19562 34713 17390 34713 17387 34714 17390 34714 17383 34714 17383 34715 17390 34715 19561 34715 17383 34716 19561 34716 17386 34716 17391 34717 15450 34717 17399 34717 17399 34718 15450 34718 17392 34718 17400 34719 17743 34719 17393 34719 17393 34720 20929 34720 17400 34720 17400 34721 20929 34721 20932 34721 17400 34722 20932 34722 17394 34722 17394 34723 17395 34723 17400 34723 17400 34724 17395 34724 17396 34724 17400 34725 17396 34725 19712 34725 19712 34726 17396 34726 20910 34726 15452 34727 15456 34727 19712 34727 15453 34728 15452 34728 17397 34728 17397 34729 15452 34729 19712 34729 17397 34730 19712 34730 15449 34730 15449 34731 19712 34731 17399 34731 15449 34732 17399 34732 17398 34732 17398 34733 17399 34733 17392 34733 15456 34734 15454 34734 19712 34734 19712 34735 15454 34735 17401 34735 19712 34736 17401 34736 17400 34736 17400 34737 17401 34737 17286 34737 17400 34738 17286 34738 17402 34738 17471 34739 17443 34739 15713 34739 15713 34740 17443 34740 17448 34740 15716 34741 15715 34741 17448 34741 17448 34742 15715 34742 17403 34742 17448 34743 17403 34743 15713 34743 17448 34744 17444 34744 15716 34744 15716 34745 17444 34745 17405 34745 15716 34746 17405 34746 17404 34746 17407 34747 17406 34747 17405 34747 17405 34748 17406 34748 15712 34748 17405 34749 15712 34749 17404 34749 17406 34750 17407 34750 15760 34750 15760 34751 17407 34751 17447 34751 15760 34752 17447 34752 15780 34752 15780 34753 17447 34753 17408 34753 17408 34754 17447 34754 17409 34754 17408 34755 17409 34755 15759 34755 15759 34756 17409 34756 17410 34756 15759 34757 17410 34757 15843 34757 15843 34758 17410 34758 15842 34758 15842 34759 17410 34759 17442 34759 15842 34760 17442 34760 15839 34760 15839 34761 17442 34761 15838 34761 15838 34762 17442 34762 17411 34762 15838 34763 17411 34763 17463 34763 20527 34764 17456 34764 17412 34764 17412 34765 17456 34765 17455 34765 17412 34766 17455 34766 15648 34766 15648 34767 17455 34767 17413 34767 17413 34768 17455 34768 17414 34768 17413 34769 17414 34769 17415 34769 17415 34770 17414 34770 17416 34770 17415 34771 17416 34771 15637 34771 15637 34772 17416 34772 15677 34772 15677 34773 17416 34773 17450 34773 15677 34774 17450 34774 17468 34774 15526 34775 15521 34775 17458 34775 17458 34776 15521 34776 17459 34776 17417 34777 17446 34777 15498 34777 15498 34778 17446 34778 17445 34778 15521 34779 15511 34779 17459 34779 17459 34780 15511 34780 15510 34780 17459 34781 15510 34781 17445 34781 17445 34782 15510 34782 15527 34782 17445 34783 15527 34783 15498 34783 15598 34784 17441 34784 15535 34784 15535 34785 17441 34785 17418 34785 15535 34786 17418 34786 17420 34786 17420 34787 17418 34787 17419 34787 17420 34788 17419 34788 17421 34788 15701 34789 17452 34789 17422 34789 17422 34790 17452 34790 17424 34790 17422 34791 17424 34791 17423 34791 17423 34792 17424 34792 17425 34792 17425 34793 17424 34793 17440 34793 17425 34794 17440 34794 17426 34794 15803 34795 15806 34795 17428 34795 15808 34796 17427 34796 17430 34796 17430 34797 17427 34797 15803 34797 17430 34798 15803 34798 17462 34798 17462 34799 15803 34799 17428 34799 15808 34800 17430 34800 17429 34800 17429 34801 17430 34801 17431 34801 17429 34802 17431 34802 15810 34802 15810 34803 17431 34803 15812 34803 15812 34804 17431 34804 17432 34804 15812 34805 17432 34805 15813 34805 15796 34806 15797 34806 17460 34806 17460 34807 15797 34807 15798 34807 17460 34808 15798 34808 17432 34808 17432 34809 15798 34809 15799 34809 17432 34810 15799 34810 15813 34810 15796 34811 17460 34811 17434 34811 17434 34812 17460 34812 17433 34812 17434 34813 17433 34813 17435 34813 17435 34814 17433 34814 17436 34814 17435 34815 17436 34815 17437 34815 17437 34816 17436 34816 15745 34816 15745 34817 17436 34817 17461 34817 15745 34818 17461 34818 15748 34818 15748 34819 17461 34819 17439 34819 15748 34820 17439 34820 17438 34820 17438 34821 17439 34821 15751 34821 15751 34822 17439 34822 19690 34822 15751 34823 19690 34823 15705 34823 17419 34824 17418 34824 17424 34824 20518 34825 17411 34825 17461 34825 20520 34826 17440 34826 20524 34826 17424 34827 17418 34827 17440 34827 17440 34828 17418 34828 17441 34828 17440 34829 17441 34829 20524 34829 17461 34830 17411 34830 17439 34830 17451 34831 17442 34831 17443 34831 17443 34832 17442 34832 17410 34832 17443 34833 17410 34833 17409 34833 17407 34834 17405 34834 17444 34834 17452 34835 17445 34835 17424 34835 17424 34836 17445 34836 17446 34836 17424 34837 17446 34837 17419 34837 17409 34838 17447 34838 17443 34838 17443 34839 17447 34839 17407 34839 17443 34840 17407 34840 17448 34840 17448 34841 17407 34841 17444 34841 20523 34842 20522 34842 17449 34842 17449 34843 20522 34843 20520 34843 17449 34844 20520 34844 20525 34844 20525 34845 20520 34845 20524 34845 17450 34846 17456 34846 20529 34846 17411 34847 17442 34847 17439 34847 17439 34848 17442 34848 17451 34848 17439 34849 17451 34849 19690 34849 19690 34850 17451 34850 17453 34850 19690 34851 17453 34851 17452 34851 17452 34852 17453 34852 17454 34852 17452 34853 17454 34853 17445 34853 17416 34854 17414 34854 17450 34854 17450 34855 17414 34855 17455 34855 17450 34856 17455 34856 17456 34856 20529 34857 17457 34857 17450 34857 17450 34858 17457 34858 17458 34858 17450 34859 17458 34859 17454 34859 17454 34860 17458 34860 17459 34860 17454 34861 17459 34861 17445 34861 17460 34862 17432 34862 17433 34862 17433 34863 17432 34863 17431 34863 20518 34864 17461 34864 20519 34864 20519 34865 17461 34865 17436 34865 20519 34866 17436 34866 17428 34866 17428 34867 17436 34867 17433 34867 17428 34868 17433 34868 17462 34868 17462 34869 17433 34869 17431 34869 17462 34870 17431 34870 17430 34870 17464 34871 17463 34871 17411 34871 17464 34872 17411 34872 17465 34872 20518 34873 17466 34873 17411 34873 17411 34874 17466 34874 17467 34874 17411 34875 17467 34875 17465 34875 17421 34876 17419 34876 17417 34876 17417 34877 17419 34877 17446 34877 17468 34878 17450 34878 17469 34878 17469 34879 17450 34879 17454 34879 17469 34880 17454 34880 15699 34880 15699 34881 17454 34881 17470 34881 17470 34882 17454 34882 17453 34882 17470 34883 17453 34883 17473 34883 17451 34884 17443 34884 17471 34884 17471 34885 15694 34885 17451 34885 17451 34886 15694 34886 17472 34886 17451 34887 17472 34887 17453 34887 17453 34888 17472 34888 15696 34888 17453 34889 15696 34889 17473 34889 20071 34890 20021 34890 17474 34890 17474 34891 20021 34891 20022 34891 17474 34892 20022 34892 20070 34892 20070 34893 20022 34893 20023 34893 20070 34894 20023 34894 20068 34894 20068 34895 20023 34895 17475 34895 20068 34896 17475 34896 20067 34896 20067 34897 17475 34897 17476 34897 20067 34898 17476 34898 20065 34898 20065 34899 17476 34899 17477 34899 20065 34900 17477 34900 17478 34900 17478 34901 17477 34901 17479 34901 17478 34902 17479 34902 17480 34902 17480 34903 17479 34903 17481 34903 17480 34904 17481 34904 20074 34904 20074 34905 17481 34905 17482 34905 20074 34906 17482 34906 20072 34906 20072 34907 17482 34907 20029 34907 20072 34908 20029 34908 17483 34908 17483 34909 20029 34909 17485 34909 17483 34910 17485 34910 17484 34910 17484 34911 17485 34911 20020 34911 17484 34912 20020 34912 20071 34912 20071 34913 20020 34913 20021 34913 20045 34914 17500 34914 17486 34914 17486 34915 17500 34915 20018 34915 17486 34916 20018 34916 17487 34916 17487 34917 20018 34917 17489 34917 17487 34918 17489 34918 17488 34918 17488 34919 17489 34919 17490 34919 17488 34920 17490 34920 20043 34920 20043 34921 17490 34921 17491 34921 20043 34922 17491 34922 20040 34922 20040 34923 17491 34923 17492 34923 20040 34924 17492 34924 20039 34924 20039 34925 17492 34925 17493 34925 20039 34926 17493 34926 17494 34926 17494 34927 17493 34927 20010 34927 17494 34928 20010 34928 17495 34928 17495 34929 20010 34929 20012 34929 17495 34930 20012 34930 17496 34930 17496 34931 20012 34931 17497 34931 17496 34932 17497 34932 20047 34932 20047 34933 17497 34933 17499 34933 20047 34934 17499 34934 17498 34934 17498 34935 17499 34935 20015 34935 17498 34936 20015 34936 20045 34936 20045 34937 20015 34937 17500 34937 17501 34938 17502 34938 20093 34938 20093 34939 17502 34939 17503 34939 20093 34940 17503 34940 17505 34940 17505 34941 17503 34941 17504 34941 17505 34942 17504 34942 20098 34942 20098 34943 17504 34943 17506 34943 20098 34944 17506 34944 17507 34944 17507 34945 17506 34945 20004 34945 17507 34946 20004 34946 17508 34946 17508 34947 20004 34947 17509 34947 17508 34948 17509 34948 17510 34948 17510 34949 17509 34949 17511 34949 17510 34950 17511 34950 17512 34950 17512 34951 17511 34951 17513 34951 17512 34952 17513 34952 20096 34952 20096 34953 17513 34953 20007 34953 20096 34954 20007 34954 17514 34954 17514 34955 20007 34955 17515 34955 17514 34956 17515 34956 17516 34956 17516 34957 17515 34957 17517 34957 17516 34958 17517 34958 17518 34958 17518 34959 17517 34959 19999 34959 17518 34960 19999 34960 17501 34960 17501 34961 19999 34961 17502 34961 17528 34962 19988 34962 17519 34962 17519 34963 19988 34963 19989 34963 17519 34964 19989 34964 17520 34964 17520 34965 19989 34965 17521 34965 17520 34966 17521 34966 20105 34966 20105 34967 17521 34967 17522 34967 20105 34968 17522 34968 17523 34968 17523 34969 17522 34969 19992 34969 17523 34970 19992 34970 20104 34970 20104 34971 19992 34971 19993 34971 20104 34972 19993 34972 20103 34972 20103 34973 19993 34973 19994 34973 20103 34974 19994 34974 17524 34974 17524 34975 19994 34975 17525 34975 17524 34976 17525 34976 20101 34976 20101 34977 17525 34977 17526 34977 20101 34978 17526 34978 17527 34978 17527 34979 17526 34979 19984 34979 17527 34980 19984 34980 20100 34980 20100 34981 19984 34981 19985 34981 20100 34982 19985 34982 20099 34982 20099 34983 19985 34983 19986 34983 20099 34984 19986 34984 17528 34984 17528 34985 19986 34985 19988 34985 20080 34986 17529 34986 17530 34986 17530 34987 17529 34987 19975 34987 17530 34988 19975 34988 17531 34988 17531 34989 19975 34989 19977 34989 17531 34990 19977 34990 20076 34990 20076 34991 19977 34991 17532 34991 20076 34992 17532 34992 17533 34992 17533 34993 17532 34993 17534 34993 17533 34994 17534 34994 20091 34994 20091 34995 17534 34995 17536 34995 20091 34996 17536 34996 17535 34996 17535 34997 17536 34997 19978 34997 17535 34998 19978 34998 20088 34998 20088 34999 19978 34999 17537 34999 20088 35000 17537 35000 20087 35000 20087 35001 17537 35001 19981 35001 20087 35002 19981 35002 20085 35002 20085 35003 19981 35003 19982 35003 20085 35004 19982 35004 17539 35004 17539 35005 19982 35005 17538 35005 17539 35006 17538 35006 20082 35006 20082 35007 17538 35007 19983 35007 20082 35008 19983 35008 20080 35008 20080 35009 19983 35009 17529 35009 17552 35010 19971 35010 17540 35010 17540 35011 19971 35011 19972 35011 17540 35012 19972 35012 17541 35012 17541 35013 19972 35013 19974 35013 17541 35014 19974 35014 20053 35014 20053 35015 19974 35015 17542 35015 20053 35016 17542 35016 17543 35016 17543 35017 17542 35017 19961 35017 17543 35018 19961 35018 17544 35018 17544 35019 19961 35019 19962 35019 17544 35020 19962 35020 20051 35020 20051 35021 19962 35021 17545 35021 20051 35022 17545 35022 17546 35022 17546 35023 17545 35023 19965 35023 17546 35024 19965 35024 20050 35024 20050 35025 19965 35025 17547 35025 20050 35026 17547 35026 20056 35026 20056 35027 17547 35027 17548 35027 20056 35028 17548 35028 17549 35028 17549 35029 17548 35029 19968 35029 17549 35030 19968 35030 17550 35030 17550 35031 19968 35031 17551 35031 17550 35032 17551 35032 17552 35032 17552 35033 17551 35033 19971 35033 17565 35034 17566 35034 20061 35034 20061 35035 17566 35035 19958 35035 20061 35036 19958 35036 17553 35036 17553 35037 19958 35037 17554 35037 17553 35038 17554 35038 17555 35038 17555 35039 17554 35039 19945 35039 17555 35040 19945 35040 17556 35040 17556 35041 19945 35041 19946 35041 17556 35042 19946 35042 17557 35042 17557 35043 19946 35043 17558 35043 17557 35044 17558 35044 20058 35044 20058 35045 17558 35045 17559 35045 20058 35046 17559 35046 17560 35046 17560 35047 17559 35047 19950 35047 17560 35048 19950 35048 17561 35048 17561 35049 19950 35049 19951 35049 17561 35050 19951 35050 20064 35050 20064 35051 19951 35051 19953 35051 20064 35052 19953 35052 17562 35052 17562 35053 19953 35053 19955 35053 17562 35054 19955 35054 17563 35054 17563 35055 19955 35055 17564 35055 17563 35056 17564 35056 17565 35056 17565 35057 17564 35057 17566 35057 20034 35058 17567 35058 17568 35058 17568 35059 17567 35059 19941 35059 17568 35060 19941 35060 17569 35060 17569 35061 19941 35061 19942 35061 17569 35062 19942 35062 17570 35062 17570 35063 19942 35063 19930 35063 17570 35064 19930 35064 20031 35064 20031 35065 19930 35065 17571 35065 20031 35066 17571 35066 17573 35066 17573 35067 17571 35067 17572 35067 17573 35068 17572 35068 17574 35068 17574 35069 17572 35069 17576 35069 17574 35070 17576 35070 17575 35070 17575 35071 17576 35071 19934 35071 17575 35072 19934 35072 20037 35072 20037 35073 19934 35073 19935 35073 20037 35074 19935 35074 17577 35074 17577 35075 19935 35075 17578 35075 17577 35076 17578 35076 17579 35076 17579 35077 17578 35077 19937 35077 17579 35078 19937 35078 20035 35078 20035 35079 19937 35079 19938 35079 20035 35080 19938 35080 20034 35080 20034 35081 19938 35081 17567 35081 17580 35082 20580 35082 17581 35082 17581 35083 20580 35083 17582 35083 17581 35084 17582 35084 17583 35084 17583 35085 17582 35085 17584 35085 17583 35086 17584 35086 20179 35086 20179 35087 17584 35087 17585 35087 20179 35088 17585 35088 20181 35088 20181 35089 17585 35089 20589 35089 20181 35090 20589 35090 20182 35090 20182 35091 20589 35091 17586 35091 20182 35092 17586 35092 20184 35092 20184 35093 17586 35093 20587 35093 20184 35094 20587 35094 17587 35094 17587 35095 20587 35095 20585 35095 17587 35096 20585 35096 20186 35096 20186 35097 20585 35097 20584 35097 20186 35098 20584 35098 17588 35098 17588 35099 20584 35099 20583 35099 17588 35100 20583 35100 17589 35100 17589 35101 20583 35101 17590 35101 17589 35102 17590 35102 20177 35102 20177 35103 17590 35103 17591 35103 20177 35104 17591 35104 17580 35104 17580 35105 17591 35105 20580 35105 20119 35106 20545 35106 20120 35106 20120 35107 20545 35107 20543 35107 20120 35108 20543 35108 20121 35108 20121 35109 20543 35109 17592 35109 20121 35110 17592 35110 20122 35110 20122 35111 17592 35111 20555 35111 20122 35112 20555 35112 17593 35112 17593 35113 20555 35113 17594 35113 17593 35114 17594 35114 20123 35114 20123 35115 17594 35115 20552 35115 20123 35116 20552 35116 20124 35116 20124 35117 20552 35117 17595 35117 20124 35118 17595 35118 17596 35118 17596 35119 17595 35119 17597 35119 17596 35120 17597 35120 20126 35120 20126 35121 17597 35121 20549 35121 20126 35122 20549 35122 17598 35122 17598 35123 20549 35123 17599 35123 17598 35124 17599 35124 20117 35124 20117 35125 17599 35125 20547 35125 20117 35126 20547 35126 17601 35126 17601 35127 20547 35127 17600 35127 17601 35128 17600 35128 20119 35128 20119 35129 17600 35129 20545 35129 17602 35130 17603 35130 20137 35130 20137 35131 17603 35131 17604 35131 20137 35132 17604 35132 20139 35132 20139 35133 17604 35133 20571 35133 20139 35134 20571 35134 20141 35134 20141 35135 20571 35135 17605 35135 20141 35136 17605 35136 20143 35136 20143 35137 17605 35137 17606 35137 20143 35138 17606 35138 20146 35138 20146 35139 17606 35139 20568 35139 20146 35140 20568 35140 17607 35140 17607 35141 20568 35141 20567 35141 17607 35142 20567 35142 20147 35142 20147 35143 20567 35143 20566 35143 20147 35144 20566 35144 17608 35144 17608 35145 20566 35145 20562 35145 17608 35146 20562 35146 20131 35146 20131 35147 20562 35147 20561 35147 20131 35148 20561 35148 20134 35148 20134 35149 20561 35149 20560 35149 20134 35150 20560 35150 17609 35150 17609 35151 20560 35151 20559 35151 17609 35152 20559 35152 17602 35152 17602 35153 20559 35153 17603 35153 17622 35154 20573 35154 20164 35154 20164 35155 20573 35155 17610 35155 20164 35156 17610 35156 17611 35156 17611 35157 17610 35157 20579 35157 17611 35158 20579 35158 20165 35158 20165 35159 20579 35159 17613 35159 20165 35160 17613 35160 17612 35160 17612 35161 17613 35161 17614 35161 17612 35162 17614 35162 20167 35162 20167 35163 17614 35163 17615 35163 20167 35164 17615 35164 20168 35164 20168 35165 17615 35165 20578 35165 20168 35166 20578 35166 17616 35166 17616 35167 20578 35167 20575 35167 17616 35168 20575 35168 17617 35168 17617 35169 20575 35169 17618 35169 17617 35170 17618 35170 20159 35170 20159 35171 17618 35171 17619 35171 20159 35172 17619 35172 20160 35172 20160 35173 17619 35173 17620 35173 20160 35174 17620 35174 20161 35174 20161 35175 17620 35175 17621 35175 20161 35176 17621 35176 17622 35176 17622 35177 17621 35177 20573 35177 17623 35178 17624 35178 17625 35178 17625 35179 17624 35179 19680 35179 19670 35180 19669 35180 17626 35180 17626 35181 19669 35181 15867 35181 15867 35182 19669 35182 17627 35182 17627 35183 19669 35183 19667 35183 17627 35184 19667 35184 17628 35184 17628 35185 19667 35185 19665 35185 17628 35186 19665 35186 15903 35186 15903 35187 19665 35187 15904 35187 15904 35188 19665 35188 17630 35188 15904 35189 17630 35189 15905 35189 17631 35190 15906 35190 17630 35190 17630 35191 15906 35191 17629 35191 17630 35192 17629 35192 15905 35192 17632 35193 15889 35193 17631 35193 17631 35194 15889 35194 15890 35194 15890 35195 15892 35195 17631 35195 17631 35196 15892 35196 15907 35196 17631 35197 15907 35197 15906 35197 15895 35198 15893 35198 17632 35198 17632 35199 15893 35199 17633 35199 17632 35200 17633 35200 15889 35200 17632 35201 17634 35201 15895 35201 15895 35202 17634 35202 19680 35202 15895 35203 19680 35203 17624 35203 17635 35204 16323 35204 19649 35204 19649 35205 16323 35205 17636 35205 19649 35206 17636 35206 16295 35206 20834 35207 20833 35207 19657 35207 20834 35208 19657 35208 16259 35208 17637 35209 17638 35209 19657 35209 19657 35210 17638 35210 16258 35210 19657 35211 16258 35211 16259 35211 19637 35212 16049 35212 17639 35212 17639 35213 16049 35213 16061 35213 17639 35214 16061 35214 17651 35214 17642 35215 17640 35215 19635 35215 19635 35216 17640 35216 15995 35216 19635 35217 15995 35217 17641 35217 17642 35218 19635 35218 17643 35218 17643 35219 19635 35219 19634 35219 17643 35220 19634 35220 16003 35220 17647 35221 16036 35221 19634 35221 19634 35222 16036 35222 17644 35222 19634 35223 17644 35223 16003 35223 17645 35224 16013 35224 19632 35224 19632 35225 16013 35225 17646 35225 19632 35226 17646 35226 17647 35226 17647 35227 17646 35227 16037 35227 17647 35228 16037 35228 16036 35228 17645 35229 19632 35229 17648 35229 17648 35230 19632 35230 19631 35230 17648 35231 19631 35231 17649 35231 17649 35232 19631 35232 17650 35232 17650 35233 19631 35233 19630 35233 17650 35234 19630 35234 16022 35234 17652 35235 17639 35235 17651 35235 17651 35236 16021 35236 17652 35236 17652 35237 16021 35237 16025 35237 17652 35238 16025 35238 19630 35238 19630 35239 16025 35239 16024 35239 19630 35240 16024 35240 16022 35240 15931 35241 18159 35241 18160 35241 18160 35242 18219 35242 17663 35242 15931 35243 18160 35243 17653 35243 20063 35244 17654 35244 17655 35244 17655 35245 17654 35245 17683 35245 17655 35246 17683 35246 20057 35246 20057 35247 17683 35247 17681 35247 20057 35248 17681 35248 17656 35248 17656 35249 17681 35249 17678 35249 17656 35250 17678 35250 20059 35250 20059 35251 17678 35251 17676 35251 20059 35252 17676 35252 20060 35252 20060 35253 17676 35253 17657 35253 20060 35254 17657 35254 17658 35254 17658 35255 17657 35255 17659 35255 17658 35256 17659 35256 17661 35256 17659 35257 15929 35257 17661 35257 17661 35258 15929 35258 17660 35258 17661 35259 17660 35259 15930 35259 15930 35260 17653 35260 17661 35260 17661 35261 17653 35261 18160 35261 17661 35262 18160 35262 17662 35262 17662 35263 18160 35263 17663 35263 17662 35264 17663 35264 17664 35264 17664 35265 17663 35265 17665 35265 17664 35266 17665 35266 17666 35266 17666 35267 17667 35267 17664 35267 17664 35268 17667 35268 15980 35268 17664 35269 15980 35269 20062 35269 20062 35270 15980 35270 17668 35270 20062 35271 17668 35271 17669 35271 17669 35272 17668 35272 17671 35272 17669 35273 17671 35273 20063 35273 20063 35274 17671 35274 17670 35274 20063 35275 17670 35275 17654 35275 17686 35276 17671 35276 15981 35276 15981 35277 17671 35277 17668 35277 17659 35278 17657 35278 17672 35278 17672 35279 17657 35279 17673 35279 17673 35280 17657 35280 15938 35280 15938 35281 17657 35281 17676 35281 15938 35282 17676 35282 17674 35282 17674 35283 17676 35283 17675 35283 17675 35284 17676 35284 17677 35284 17677 35285 17676 35285 17678 35285 17677 35286 17678 35286 15960 35286 15960 35287 17678 35287 17679 35287 17679 35288 17678 35288 17681 35288 17679 35289 17681 35289 17682 35289 17683 35290 17680 35290 17681 35290 17681 35291 17680 35291 15958 35291 17681 35292 15958 35292 17682 35292 17654 35293 15945 35293 17683 35293 17683 35294 15945 35294 17684 35294 17684 35295 15946 35295 17683 35295 17683 35296 15946 35296 17685 35296 17683 35297 17685 35297 17680 35297 17670 35298 17671 35298 17686 35298 17686 35299 17687 35299 17670 35299 17670 35300 17687 35300 15947 35300 17670 35301 15947 35301 17654 35301 17654 35302 15947 35302 17688 35302 17654 35303 17688 35303 15945 35303 17698 35304 17697 35304 16365 35304 16365 35305 17697 35305 16362 35305 19597 35306 17690 35306 16392 35306 16392 35307 17690 35307 17689 35307 17689 35308 17690 35308 16386 35308 16386 35309 17690 35309 17691 35309 16386 35310 17691 35310 17692 35310 17695 35311 16371 35311 17692 35311 17692 35312 16371 35312 17693 35312 17692 35313 17693 35313 16386 35313 17694 35314 16368 35314 17695 35314 17695 35315 16368 35315 16381 35315 17695 35316 16381 35316 16371 35316 19609 35317 17696 35317 17694 35317 17694 35318 17696 35318 16360 35318 16360 35319 16343 35319 17694 35319 17694 35320 16343 35320 16361 35320 17694 35321 16361 35321 16368 35321 17697 35322 17698 35322 17701 35322 17701 35323 17698 35323 16338 35323 17701 35324 16338 35324 17699 35324 17699 35325 16349 35325 17701 35325 17701 35326 16349 35326 17700 35326 17701 35327 17700 35327 19609 35327 19609 35328 17700 35328 16354 35328 19609 35329 16354 35329 17696 35329 16252 35330 19585 35330 17702 35330 17702 35331 19585 35331 17703 35331 17704 35332 17705 35332 18226 35332 18220 35333 17707 35333 17706 35333 17706 35334 17707 35334 17708 35334 17706 35335 17708 35335 16217 35335 16217 35336 17709 35336 17706 35336 17706 35337 17709 35337 17710 35337 17706 35338 17710 35338 18226 35338 18226 35339 17710 35339 17711 35339 18226 35340 17711 35340 17704 35340 17712 35341 16197 35341 17713 35341 17713 35342 16197 35342 16206 35342 17713 35343 16206 35343 16175 35343 19627 35344 19626 35344 16136 35344 16136 35345 19626 35345 16144 35345 16066 35346 17714 35346 17716 35346 17716 35347 17714 35347 16067 35347 17716 35348 16067 35348 18193 35348 17716 35349 20075 35349 17728 35349 16119 35350 17715 35350 17716 35350 17716 35351 17715 35351 16125 35351 16066 35352 17716 35352 16064 35352 16064 35353 17716 35353 17728 35353 16064 35354 17728 35354 16063 35354 20075 35355 17716 35355 20066 35355 20066 35356 17716 35356 16125 35356 20066 35357 16125 35357 17717 35357 17717 35358 16125 35358 16123 35358 17717 35359 16123 35359 17718 35359 17718 35360 16123 35360 16122 35360 17718 35361 16122 35361 16118 35361 16118 35362 17730 35362 17718 35362 17718 35363 17730 35363 17731 35363 17718 35364 17731 35364 20069 35364 20069 35365 17731 35365 19851 35365 20069 35366 19851 35366 17719 35366 17719 35367 19851 35367 19852 35367 17719 35368 19852 35368 17720 35368 17720 35369 19852 35369 17721 35369 17720 35370 17721 35370 17722 35370 17722 35371 17721 35371 17724 35371 17722 35372 17724 35372 17723 35372 17723 35373 17724 35373 19848 35373 17723 35374 19848 35374 20073 35374 20073 35375 19848 35375 17726 35375 20073 35376 17726 35376 17725 35376 17725 35377 17726 35377 17727 35377 17725 35378 17727 35378 17728 35378 17728 35379 17727 35379 17729 35379 17728 35380 17729 35380 16063 35380 17731 35381 17730 35381 16127 35381 16127 35382 16128 35382 17731 35382 17731 35383 16128 35383 16133 35383 17731 35384 16133 35384 16088 35384 16093 35385 17732 35385 17727 35385 17727 35386 17732 35386 17733 35386 17727 35387 17733 35387 17729 35387 17771 35388 19523 35388 17735 35388 17734 35389 17772 35389 17771 35389 17771 35390 17735 35390 17734 35390 17734 35391 17735 35391 19559 35391 17734 35392 19559 35392 17736 35392 19559 35393 19558 35393 17736 35393 17736 35394 19558 35394 17737 35394 17736 35395 17737 35395 17076 35395 17737 35396 19557 35396 17076 35396 17076 35397 19557 35397 17803 35397 17076 35398 17803 35398 17801 35398 15482 35399 19476 35399 19475 35399 15482 35400 19475 35400 17738 35400 19475 35401 19495 35401 17738 35401 17738 35402 19495 35402 17739 35402 17738 35403 17739 35403 16718 35403 17739 35404 19494 35404 16718 35404 16718 35405 19494 35405 19493 35405 16718 35406 19493 35406 17740 35406 19493 35407 17741 35407 17740 35407 17740 35408 17741 35408 19718 35408 17740 35409 19718 35409 19717 35409 20930 35410 17393 35410 17743 35410 20930 35411 17743 35411 17742 35411 17743 35412 17744 35412 17742 35412 17742 35413 17744 35413 20814 35413 17742 35414 20814 35414 17745 35414 17745 35415 20814 35415 20813 35415 17745 35416 20813 35416 19521 35416 19521 35417 20813 35417 17746 35417 19521 35418 17746 35418 19480 35418 19480 35419 17746 35419 20810 35419 19480 35420 20810 35420 19566 35420 19566 35421 20810 35421 16606 35421 19566 35422 16606 35422 19568 35422 17381 35423 17371 35423 20791 35423 17385 35424 19550 35424 17747 35424 20786 35425 20785 35425 17385 35425 17385 35426 17747 35426 20786 35426 20786 35427 17747 35427 17748 35427 20786 35428 17748 35428 17749 35428 17749 35429 17748 35429 19541 35429 17749 35430 19541 35430 17750 35430 17750 35431 19541 35431 19542 35431 17750 35432 19542 35432 20792 35432 20792 35433 19542 35433 19564 35433 20792 35434 19564 35434 20793 35434 20793 35435 19564 35435 19565 35435 20793 35436 19565 35436 20791 35436 20791 35437 19565 35437 19567 35437 20791 35438 19567 35438 17381 35438 17335 35439 20757 35439 20758 35439 17756 35440 19724 35440 19719 35440 17335 35441 20758 35441 19549 35441 19549 35442 20758 35442 19539 35442 19539 35443 20758 35443 20759 35443 19539 35444 20759 35444 19540 35444 19540 35445 20759 35445 20761 35445 19540 35446 20761 35446 17751 35446 20761 35447 20762 35447 17751 35447 17751 35448 20762 35448 17753 35448 17751 35449 17753 35449 17752 35449 17752 35450 17753 35450 17754 35450 17752 35451 17754 35451 17755 35451 17754 35452 20765 35452 17755 35452 17755 35453 20765 35453 17756 35453 17755 35454 17756 35454 19514 35454 19514 35455 17756 35455 19719 35455 19514 35456 19719 35456 17757 35456 19522 35457 19531 35457 17101 35457 17101 35458 19531 35458 17778 35458 19710 35459 17758 35459 17288 35459 17288 35460 17758 35460 17759 35460 17288 35461 17759 35461 17294 35461 17759 35462 16563 35462 17294 35462 17294 35463 16563 35463 17760 35463 17294 35464 17760 35464 17761 35464 17761 35465 17760 35465 17763 35465 17761 35466 17763 35466 17762 35466 17762 35467 17763 35467 15461 35467 15461 35468 17763 35468 17767 35468 15461 35469 17767 35469 17766 35469 16568 35470 17765 35470 17764 35470 17764 35471 17765 35471 17766 35471 17764 35472 17766 35472 16566 35472 16566 35473 17766 35473 17767 35473 17282 35474 17765 35474 16590 35474 16590 35475 17765 35475 16568 35475 18343 35476 18340 35476 16482 35476 16483 35477 20919 35477 16482 35477 16482 35478 20919 35478 17768 35478 16482 35479 17768 35479 18343 35479 16483 35480 17769 35480 20919 35480 20919 35481 17769 35481 16433 35481 20919 35482 16433 35482 16432 35482 16432 35483 16431 35483 20919 35483 20919 35484 16431 35484 17770 35484 20919 35485 17770 35485 19705 35485 17391 35486 19711 35486 17290 35486 17290 35487 17291 35487 17391 35487 17391 35488 17291 35488 17289 35488 17391 35489 17289 35489 15450 35489 17771 35490 17772 35490 17774 35490 17771 35491 17774 35491 19523 35491 19523 35492 17774 35492 17773 35492 17773 35493 17774 35493 17775 35493 17773 35494 17775 35494 19529 35494 19529 35495 17775 35495 17776 35495 19529 35496 17776 35496 17777 35496 17777 35497 17776 35497 17778 35497 17777 35498 17778 35498 19531 35498 19499 35499 19498 35499 16825 35499 16825 35500 19498 35500 16819 35500 20690 35501 17326 35501 19500 35501 19500 35502 17326 35502 17325 35502 20728 35503 17779 35503 16747 35503 16747 35504 17779 35504 19474 35504 16747 35505 19474 35505 16746 35505 16746 35506 19474 35506 17780 35506 17780 35507 19474 35507 17781 35507 17780 35508 17781 35508 16734 35508 16763 35509 17792 35509 19504 35509 16810 35510 17782 35510 16806 35510 16806 35511 17782 35511 17783 35511 16806 35512 17783 35512 16807 35512 17784 35513 17785 35513 17786 35513 17786 35514 17785 35514 17787 35514 17786 35515 17787 35515 19511 35515 19511 35516 17787 35516 16804 35516 19511 35517 16804 35517 17783 35517 17783 35518 16804 35518 16809 35518 17783 35519 16809 35519 16807 35519 17784 35520 17786 35520 16798 35520 16798 35521 17786 35521 19508 35521 16798 35522 19508 35522 17788 35522 17788 35523 19508 35523 16791 35523 16791 35524 19508 35524 17789 35524 16791 35525 17789 35525 16785 35525 16785 35526 17789 35526 17790 35526 17790 35527 17789 35527 19506 35527 17790 35528 19506 35528 17791 35528 19504 35529 17792 35529 19506 35529 19506 35530 17792 35530 17793 35530 19506 35531 17793 35531 17791 35531 16763 35532 19504 35532 16777 35532 16777 35533 19504 35533 19502 35533 16777 35534 19502 35534 17794 35534 17794 35535 19502 35535 17795 35535 17795 35536 19502 35536 17797 35536 17795 35537 17797 35537 17796 35537 17796 35538 17797 35538 16775 35538 16775 35539 17797 35539 19817 35539 16775 35540 19817 35540 19818 35540 19814 35541 19813 35541 19513 35541 19814 35542 19513 35542 17798 35542 17798 35543 19513 35543 17782 35543 17798 35544 17782 35544 16810 35544 16836 35545 17799 35545 17800 35545 17800 35546 17799 35546 19458 35546 17801 35547 17803 35547 17802 35547 17801 35548 17802 35548 17060 35548 17060 35549 17802 35549 17806 35549 17060 35550 17806 35550 17808 35550 17805 35551 17370 35551 17807 35551 17803 35552 17804 35552 17802 35552 17802 35553 17804 35553 17805 35553 17802 35554 17805 35554 17806 35554 17806 35555 17805 35555 17807 35555 17806 35556 17807 35556 17808 35556 19575 35557 19556 35557 17809 35557 17809 35558 19556 35558 17810 35558 17809 35559 17810 35559 16638 35559 17810 35560 17811 35560 17812 35560 16638 35561 17810 35561 16631 35561 16631 35562 17810 35562 17812 35562 16631 35563 17812 35563 17813 35563 16638 35564 17376 35564 17809 35564 17809 35565 17376 35565 17375 35565 17809 35566 17375 35566 19575 35566 19575 35567 17375 35567 19574 35567 17811 35568 19569 35568 17319 35568 17319 35569 17320 35569 16627 35569 17811 35570 17319 35570 17812 35570 17812 35571 17319 35571 16627 35571 17812 35572 16627 35572 17813 35572 17824 35573 18016 35573 18014 35573 20446 35574 20445 35574 18007 35574 20453 35575 18064 35575 17814 35575 20466 35576 18048 35576 17815 35576 20411 35577 20410 35577 18009 35577 20372 35578 18055 35578 18065 35578 17816 35579 17972 35579 17970 35579 17972 35580 17816 35580 20890 35580 20844 35581 17902 35581 20837 35581 17870 35582 17817 35582 17818 35582 17858 35583 20228 35583 17859 35583 20494 35584 17844 35584 20863 35584 17838 35585 17839 35585 20874 35585 18005 35586 17819 35586 18004 35586 17820 35587 17821 35587 17822 35587 18010 35588 17931 35588 18009 35588 17975 35589 19831 35589 17966 35589 19827 35590 18020 35590 18017 35590 18018 35591 18016 35591 19826 35591 19826 35592 18016 35592 17824 35592 19826 35593 17824 35593 19825 35593 19825 35594 17824 35594 17823 35594 17823 35595 17824 35595 17825 35595 17825 35596 17824 35596 17993 35596 17825 35597 17993 35597 17827 35597 17827 35598 17993 35598 17826 35598 17827 35599 17826 35599 17828 35599 17828 35600 17826 35600 19822 35600 19822 35601 17826 35601 17996 35601 19822 35602 17996 35602 19831 35602 17980 35603 17829 35603 17975 35603 18036 35604 17831 35604 17829 35604 18019 35605 18021 35605 18034 35605 18034 35606 18021 35606 17830 35606 18034 35607 17830 35607 17831 35607 17831 35608 17830 35608 17832 35608 17831 35609 17832 35609 17829 35609 18003 35610 20438 35610 20876 35610 20876 35611 20438 35611 20437 35611 20876 35612 20437 35612 17833 35612 17833 35613 20437 35613 17834 35613 17834 35614 20435 35614 17833 35614 17833 35615 20435 35615 18022 35615 17833 35616 18022 35616 20877 35616 20877 35617 18022 35617 20871 35617 17932 35618 17835 35618 18049 35618 18049 35619 17835 35619 17836 35619 17836 35620 17835 35620 20875 35620 20875 35621 17835 35621 17837 35621 20875 35622 17837 35622 17838 35622 17838 35623 17837 35623 20456 35623 17838 35624 20456 35624 17839 35624 17848 35625 17847 35625 20486 35625 20475 35626 20873 35626 20874 35626 20475 35627 17840 35627 20873 35627 20873 35628 17840 35628 20474 35628 20873 35629 20474 35629 20472 35629 17842 35630 17839 35630 20483 35630 20483 35631 17839 35631 17848 35631 20483 35632 17848 35632 17841 35632 17841 35633 17848 35633 20486 35633 17842 35634 20481 35634 17839 35634 17839 35635 20481 35635 17843 35635 17839 35636 17843 35636 20874 35636 20874 35637 17843 35637 20478 35637 20874 35638 20478 35638 20475 35638 17844 35639 17845 35639 18076 35639 17845 35640 17846 35640 18076 35640 18076 35641 17846 35641 20504 35641 18076 35642 20504 35642 17848 35642 20472 35643 17847 35643 20873 35643 20873 35644 17847 35644 17848 35644 20873 35645 17848 35645 17849 35645 20504 35646 20503 35646 17848 35646 17848 35647 20503 35647 20502 35647 17848 35648 20502 35648 17849 35648 17849 35649 20502 35649 20500 35649 17849 35650 20500 35650 17850 35650 17850 35651 20500 35651 20499 35651 20499 35652 17851 35652 17850 35652 17850 35653 17851 35653 17852 35653 17850 35654 17852 35654 20863 35654 20863 35655 17852 35655 20496 35655 20863 35656 20496 35656 20494 35656 17844 35657 18076 35657 20863 35657 20863 35658 18076 35658 18080 35658 20863 35659 18080 35659 20866 35659 17856 35660 17854 35660 17853 35660 17853 35661 17854 35661 20864 35661 17853 35662 20864 35662 18074 35662 20197 35663 17855 35663 20198 35663 20198 35664 17855 35664 17856 35664 20198 35665 17856 35665 20199 35665 20199 35666 17856 35666 17853 35666 20199 35667 17853 35667 17962 35667 20197 35668 20210 35668 17855 35668 17855 35669 20210 35669 17857 35669 17855 35670 17857 35670 20860 35670 20860 35671 17857 35671 20861 35671 17861 35672 17860 35672 20852 35672 20861 35673 17857 35673 20852 35673 20852 35674 17857 35674 17953 35674 20852 35675 17953 35675 17861 35675 17858 35676 17859 35676 20216 35676 17860 35677 17861 35677 20853 35677 20853 35678 17861 35678 17864 35678 20853 35679 17864 35679 17862 35679 20247 35680 20245 35680 17863 35680 17864 35681 20216 35681 17862 35681 17862 35682 20216 35682 17859 35682 17862 35683 17859 35683 20854 35683 20854 35684 17859 35684 17866 35684 17878 35685 20856 35685 17874 35685 17874 35686 20856 35686 17868 35686 17874 35687 17868 35687 20250 35687 20250 35688 20249 35688 17874 35688 17874 35689 20249 35689 20248 35689 17874 35690 20248 35690 17863 35690 17863 35691 20248 35691 17865 35691 17863 35692 17865 35692 20247 35692 20244 35693 20243 35693 17859 35693 17859 35694 20243 35694 20242 35694 17859 35695 20242 35695 17866 35695 17866 35696 20242 35696 20240 35696 17866 35697 20240 35697 20856 35697 20856 35698 20240 35698 17867 35698 20856 35699 17867 35699 17868 35699 17869 35700 17871 35700 17817 35700 20258 35701 17869 35701 20848 35701 20848 35702 17869 35702 17817 35702 20848 35703 17817 35703 20847 35703 20847 35704 17817 35704 17870 35704 17871 35705 17872 35705 17817 35705 17817 35706 17872 35706 20266 35706 17817 35707 20266 35707 17818 35707 17818 35708 20266 35708 20265 35708 17818 35709 20265 35709 20263 35709 17873 35710 17875 35710 17874 35710 17874 35711 17875 35711 17876 35711 17874 35712 17876 35712 17877 35712 17878 35713 17874 35713 20851 35713 20851 35714 17874 35714 17877 35714 20851 35715 17877 35715 20848 35715 20848 35716 17877 35716 20259 35716 20848 35717 20259 35717 20258 35717 17989 35718 20845 35718 17879 35718 17879 35719 20845 35719 20846 35719 20838 35720 17881 35720 17880 35720 17880 35721 17881 35721 17990 35721 17880 35722 17990 35722 17882 35722 17882 35723 17990 35723 17883 35723 17882 35724 17883 35724 20841 35724 17885 35725 20842 35725 20285 35725 20841 35726 17883 35726 20842 35726 20842 35727 17883 35727 17884 35727 20842 35728 17884 35728 20285 35728 20285 35729 20284 35729 17885 35729 17885 35730 20284 35730 17886 35730 17885 35731 17886 35731 18045 35731 17889 35732 20843 35732 17887 35732 17887 35733 20843 35733 18047 35733 17887 35734 18047 35734 18046 35734 17887 35735 17888 35735 17889 35735 17889 35736 17888 35736 17890 35736 17889 35737 17890 35737 20844 35737 20844 35738 17890 35738 17891 35738 20844 35739 17891 35739 17902 35739 17902 35740 17891 35740 17945 35740 17902 35741 17945 35741 17892 35741 20321 35742 17893 35742 17894 35742 17893 35743 20319 35743 17894 35743 17894 35744 20319 35744 20317 35744 17894 35745 20317 35745 17978 35745 20317 35746 17895 35746 17978 35746 17978 35747 17895 35747 17896 35747 17978 35748 17896 35748 17897 35748 17905 35749 20836 35749 17898 35749 17898 35750 20836 35750 17899 35750 17898 35751 17899 35751 17900 35751 17900 35752 17899 35752 20837 35752 17900 35753 20837 35753 17901 35753 17901 35754 20837 35754 17902 35754 17901 35755 17902 35755 20315 35755 20835 35756 20329 35756 20342 35756 17894 35757 17903 35757 20331 35757 20835 35758 20342 35758 20892 35758 20332 35759 17979 35759 17904 35759 17904 35760 17979 35760 17906 35760 17905 35761 20321 35761 20836 35761 20836 35762 20321 35762 17894 35762 20836 35763 17894 35763 20835 35763 20835 35764 17894 35764 20331 35764 20835 35765 20331 35765 20329 35765 17906 35766 17979 35766 20337 35766 20337 35767 17979 35767 17973 35767 20337 35768 17973 35768 20338 35768 20342 35769 20340 35769 20892 35769 20892 35770 20340 35770 17907 35770 20892 35771 17907 35771 17973 35771 17973 35772 17907 35772 17908 35772 17973 35773 17908 35773 20338 35773 17998 35774 17909 35774 17910 35774 17910 35775 17909 35775 17911 35775 17910 35776 17911 35776 17912 35776 20888 35777 20358 35777 20357 35777 20358 35778 20888 35778 17944 35778 17944 35779 20888 35779 20887 35779 17944 35780 20887 35780 17912 35780 17912 35781 20887 35781 17913 35781 17912 35782 17913 35782 17910 35782 20357 35783 17914 35783 20888 35783 20888 35784 17914 35784 17915 35784 20888 35785 17915 35785 20884 35785 18024 35786 17937 35786 17964 35786 17964 35787 17937 35787 20885 35787 17964 35788 20885 35788 17915 35788 17915 35789 20885 35789 17916 35789 17915 35790 17916 35790 20884 35790 20375 35791 17921 35791 17917 35791 17917 35792 17921 35792 17919 35792 17917 35793 17919 35793 17918 35793 17918 35794 17919 35794 20883 35794 17918 35795 20883 35795 17937 35795 17937 35796 20883 35796 17920 35796 17937 35797 17920 35797 20885 35797 20403 35798 17923 35798 18089 35798 20394 35799 20392 35799 17929 35799 17929 35800 20392 35800 20391 35800 20375 35801 20373 35801 17921 35801 17921 35802 20373 35802 18089 35802 17921 35803 18089 35803 17922 35803 17922 35804 18089 35804 17923 35804 17923 35805 17924 35805 17922 35805 17922 35806 17924 35806 17925 35806 17922 35807 17925 35807 17926 35807 17925 35808 20400 35808 17926 35808 17926 35809 20400 35809 20399 35809 17926 35810 20399 35810 17927 35810 20399 35811 20398 35811 17927 35811 17927 35812 20398 35812 20396 35812 17927 35813 20396 35813 17929 35813 17929 35814 20396 35814 20395 35814 17929 35815 20395 35815 20394 35815 20419 35816 17931 35816 17928 35816 17928 35817 17931 35817 20879 35817 17928 35818 20879 35818 20421 35818 20410 35819 20426 35819 17929 35819 17929 35820 20426 35820 20425 35820 17929 35821 20425 35821 17927 35821 17927 35822 20425 35822 17930 35822 17927 35823 17930 35823 20879 35823 20879 35824 17930 35824 20422 35824 20879 35825 20422 35825 20421 35825 20419 35826 20416 35826 17931 35826 17931 35827 20416 35827 20415 35827 17931 35828 20415 35828 18009 35828 18009 35829 20415 35829 20413 35829 18009 35830 20413 35830 20411 35830 20463 35831 20461 35831 17932 35831 17932 35832 20461 35832 20459 35832 17932 35833 20459 35833 17835 35833 17835 35834 20459 35834 20458 35834 17835 35835 20458 35835 17837 35835 17933 35836 20433 35836 18053 35836 18006 35837 17934 35837 18008 35837 18008 35838 17934 35838 17935 35838 18008 35839 17935 35839 18003 35839 18003 35840 17935 35840 20440 35840 18003 35841 20440 35841 20438 35841 17936 35842 20381 35842 17937 35842 17937 35843 20381 35843 20379 35843 17937 35844 20379 35844 17918 35844 17918 35845 20379 35845 20377 35845 17918 35846 20377 35846 17917 35846 18056 35847 20367 35847 18057 35847 18057 35848 20367 35848 17938 35848 18057 35849 17938 35849 17936 35849 17939 35850 20355 35850 17988 35850 20353 35851 20351 35851 17941 35851 17941 35852 20351 35852 17940 35852 17941 35853 17940 35853 17911 35853 17940 35854 17942 35854 17911 35854 17911 35855 17942 35855 20361 35855 17911 35856 20361 35856 17912 35856 17912 35857 20361 35857 17943 35857 17912 35858 17943 35858 17944 35858 17945 35859 17946 35859 17892 35859 17892 35860 17946 35860 17947 35860 17892 35861 17947 35861 17984 35861 17984 35862 17947 35862 20301 35862 17984 35863 20301 35863 20299 35863 18039 35864 20297 35864 18046 35864 18046 35865 20297 35865 20295 35865 18046 35866 20295 35866 17887 35866 17887 35867 20295 35867 17948 35867 17887 35868 17948 35868 17888 35868 17886 35869 17949 35869 18045 35869 18045 35870 17949 35870 17951 35870 18045 35871 17951 35871 17991 35871 20281 35872 17990 35872 20282 35872 20282 35873 17990 35873 17991 35873 20282 35874 17991 35874 17950 35874 17950 35875 17991 35875 17951 35875 20281 35876 20280 35876 17990 35876 17990 35877 20280 35877 20278 35877 17990 35878 20278 35878 17883 35878 17883 35879 20278 35879 20288 35879 17883 35880 20288 35880 17884 35880 17956 35881 17955 35881 17952 35881 17956 35882 17952 35882 17953 35882 17952 35883 20221 35883 17953 35883 17953 35884 20221 35884 20218 35884 17953 35885 20218 35885 17861 35885 17861 35886 20218 35886 17954 35886 17861 35887 17954 35887 17864 35887 17955 35888 17956 35888 17957 35888 17957 35889 17956 35889 18042 35889 17957 35890 18042 35890 17958 35890 17958 35891 18042 35891 17959 35891 17958 35892 17959 35892 20225 35892 20225 35893 17959 35893 20228 35893 20228 35894 17959 35894 17863 35894 20228 35895 17863 35895 17859 35895 17859 35896 17863 35896 20245 35896 17859 35897 20245 35897 20244 35897 17960 35898 17961 35898 20204 35898 17962 35899 17853 35899 20202 35899 20202 35900 17853 35900 18074 35900 20202 35901 18074 35901 20203 35901 17963 35902 20206 35902 18029 35902 20210 35903 20209 35903 18030 35903 18030 35904 20209 35904 17963 35904 18025 35905 18024 35905 17985 35905 17985 35906 18024 35906 17964 35906 17985 35907 17964 35907 17987 35907 17987 35908 17964 35908 17915 35908 17987 35909 17915 35909 17939 35909 17939 35910 17915 35910 17914 35910 17939 35911 17914 35911 20355 35911 19831 35912 17996 35912 17966 35912 17966 35913 17996 35913 17965 35913 17966 35914 17965 35914 17967 35914 17967 35915 17965 35915 17997 35915 17967 35916 17997 35916 17976 35916 17976 35917 17997 35917 17968 35917 17976 35918 17968 35918 17969 35918 17969 35919 17968 35919 17970 35919 17969 35920 17970 35920 17971 35920 17971 35921 17970 35921 17972 35921 17971 35922 17972 35922 17979 35922 17979 35923 17972 35923 20890 35923 17979 35924 20890 35924 17973 35924 17973 35925 20890 35925 17974 35925 17973 35926 17974 35926 20892 35926 17975 35927 17966 35927 17980 35927 17980 35928 17966 35928 17967 35928 17980 35929 17967 35929 17981 35929 17981 35930 17967 35930 17976 35930 17981 35931 17976 35931 17983 35931 17983 35932 17976 35932 17969 35932 17983 35933 17969 35933 17977 35933 17977 35934 17969 35934 17971 35934 17977 35935 17971 35935 17978 35935 17978 35936 17971 35936 17979 35936 17978 35937 17979 35937 17894 35937 17894 35938 17979 35938 20332 35938 17894 35939 20332 35939 17903 35939 17829 35940 17980 35940 18036 35940 18036 35941 17980 35941 17981 35941 18036 35942 17981 35942 17982 35942 17982 35943 17981 35943 17983 35943 17982 35944 17983 35944 17984 35944 17984 35945 17983 35945 17977 35945 17984 35946 17977 35946 17892 35946 17892 35947 17977 35947 17978 35947 17892 35948 17978 35948 17902 35948 17902 35949 17978 35949 17897 35949 17902 35950 17897 35950 20315 35950 18026 35951 18025 35951 17994 35951 17994 35952 18025 35952 17985 35952 17994 35953 17985 35953 17986 35953 17986 35954 17985 35954 17987 35954 17986 35955 17987 35955 17995 35955 17995 35956 17987 35956 17939 35956 17995 35957 17939 35957 17941 35957 17941 35958 17939 35958 17988 35958 17941 35959 17988 35959 20353 35959 20838 35960 20845 35960 17881 35960 17881 35961 20845 35961 17989 35961 17881 35962 17989 35962 17990 35962 17990 35963 17989 35963 18000 35963 17990 35964 18000 35964 17991 35964 17991 35965 18000 35965 17992 35965 17824 35966 18026 35966 17993 35966 17993 35967 18026 35967 17994 35967 17993 35968 17994 35968 17826 35968 17826 35969 17994 35969 17986 35969 17826 35970 17986 35970 17996 35970 17996 35971 17986 35971 17995 35971 17996 35972 17995 35972 17965 35972 17965 35973 17995 35973 17941 35973 17965 35974 17941 35974 17997 35974 17997 35975 17941 35975 17911 35975 17997 35976 17911 35976 17968 35976 17968 35977 17911 35977 17909 35977 17968 35978 17909 35978 17970 35978 17970 35979 17909 35979 17998 35979 17970 35980 17998 35980 17816 35980 20846 35981 17870 35981 17879 35981 17879 35982 17870 35982 17818 35982 17879 35983 17818 35983 17989 35983 17989 35984 17818 35984 17999 35984 17989 35985 17999 35985 18000 35985 18000 35986 17999 35986 18001 35986 18000 35987 18001 35987 17992 35987 17992 35988 18001 35988 18043 35988 20263 35989 17873 35989 17818 35989 17818 35990 17873 35990 17874 35990 17818 35991 17874 35991 17999 35991 17999 35992 17874 35992 17863 35992 17999 35993 17863 35993 18001 35993 18001 35994 17863 35994 17959 35994 18001 35995 17959 35995 18043 35995 18043 35996 17959 35996 18042 35996 20876 35997 18002 35997 18003 35997 18003 35998 18002 35998 18004 35998 18003 35999 18004 35999 18008 35999 18008 36000 18004 36000 17819 36000 18008 36001 17819 36001 17822 36001 17822 36002 17819 36002 18005 36002 17822 36003 18005 36003 17820 36003 20445 36004 18006 36004 18007 36004 18007 36005 18006 36005 18008 36005 18007 36006 18008 36006 18012 36006 18012 36007 18008 36007 17822 36007 18012 36008 17822 36008 18009 36008 18009 36009 17822 36009 17821 36009 18009 36010 17821 36010 18010 36010 20410 36011 17929 36011 18009 36011 18009 36012 17929 36012 18011 36012 18009 36013 18011 36013 18012 36013 18012 36014 18011 36014 18013 36014 18012 36015 18013 36015 18007 36015 18007 36016 18013 36016 18054 36016 18007 36017 18054 36017 20446 36017 18028 36018 18014 36018 18015 36018 18015 36019 18014 36019 18016 36019 18015 36020 18016 36020 18017 36020 18017 36021 18016 36021 18018 36021 18017 36022 18018 36022 19827 36022 18029 36023 18028 36023 18031 36023 18031 36024 18028 36024 18015 36024 18031 36025 18015 36025 18032 36025 18032 36026 18015 36026 18017 36026 18032 36027 18017 36027 18019 36027 18019 36028 18017 36028 18020 36028 18019 36029 18020 36029 18021 36029 20435 36030 20433 36030 18022 36030 18022 36031 20433 36031 17933 36031 18022 36032 17933 36032 18023 36032 17936 36033 17937 36033 18057 36033 18057 36034 17937 36034 18024 36034 18057 36035 18024 36035 18058 36035 18058 36036 18024 36036 18025 36036 18058 36037 18025 36037 18059 36037 18059 36038 18025 36038 18026 36038 18059 36039 18026 36039 18027 36039 18027 36040 18026 36040 17824 36040 18027 36041 17824 36041 18060 36041 18060 36042 17824 36042 18014 36042 18060 36043 18014 36043 18062 36043 18062 36044 18014 36044 18028 36044 18062 36045 18028 36045 18063 36045 18063 36046 18028 36046 18029 36046 18063 36047 18029 36047 17960 36047 17960 36048 18029 36048 20206 36048 17960 36049 20206 36049 17961 36049 17963 36050 18029 36050 18030 36050 18030 36051 18029 36051 18031 36051 18030 36052 18031 36052 18040 36052 18040 36053 18031 36053 18032 36053 18040 36054 18032 36054 18041 36054 18041 36055 18032 36055 18019 36055 18041 36056 18019 36056 18033 36056 18033 36057 18019 36057 18034 36057 18033 36058 18034 36058 18035 36058 18035 36059 18034 36059 17831 36059 18035 36060 17831 36060 18044 36060 18044 36061 17831 36061 18036 36061 18044 36062 18036 36062 18037 36062 18037 36063 18036 36063 17982 36063 18037 36064 17982 36064 18038 36064 18038 36065 17982 36065 17984 36065 18038 36066 17984 36066 18046 36066 18046 36067 17984 36067 20299 36067 18046 36068 20299 36068 18039 36068 20210 36069 18030 36069 17857 36069 17857 36070 18030 36070 18040 36070 17857 36071 18040 36071 17953 36071 17953 36072 18040 36072 18041 36072 17953 36073 18041 36073 17956 36073 17956 36074 18041 36074 18033 36074 17956 36075 18033 36075 18042 36075 18042 36076 18033 36076 18035 36076 18042 36077 18035 36077 18043 36077 18043 36078 18035 36078 18044 36078 18043 36079 18044 36079 17992 36079 17992 36080 18044 36080 18037 36080 17992 36081 18037 36081 17991 36081 17991 36082 18037 36082 18038 36082 17991 36083 18038 36083 18045 36083 18045 36084 18038 36084 18046 36084 18045 36085 18046 36085 17885 36085 17885 36086 18046 36086 18047 36086 17885 36087 18047 36087 20842 36087 18048 36088 20463 36088 17815 36088 17815 36089 20463 36089 17932 36089 17815 36090 17932 36090 18023 36090 18023 36091 17932 36091 18049 36091 18023 36092 18049 36092 18022 36092 18022 36093 18049 36093 18050 36093 18022 36094 18050 36094 20871 36094 18051 36095 20466 36095 18083 36095 18083 36096 20466 36096 17815 36096 18083 36097 17815 36097 18084 36097 18084 36098 17815 36098 18023 36098 18084 36099 18023 36099 18052 36099 18052 36100 18023 36100 17933 36100 18052 36101 17933 36101 18054 36101 18054 36102 17933 36102 18053 36102 18054 36103 18053 36103 20446 36103 18055 36104 18056 36104 18065 36104 18065 36105 18056 36105 18057 36105 18065 36106 18057 36106 18066 36106 18066 36107 18057 36107 18058 36107 18066 36108 18058 36108 18068 36108 18068 36109 18058 36109 18059 36109 18068 36110 18059 36110 18069 36110 18069 36111 18059 36111 18027 36111 18069 36112 18027 36112 18070 36112 18070 36113 18027 36113 18060 36113 18070 36114 18060 36114 18061 36114 18061 36115 18060 36115 18062 36115 18061 36116 18062 36116 18072 36116 18072 36117 18062 36117 18063 36117 18072 36118 18063 36118 18073 36118 18073 36119 18063 36119 17960 36119 18073 36120 17960 36120 18074 36120 18074 36121 17960 36121 20204 36121 18074 36122 20204 36122 20203 36122 18064 36123 18051 36123 17814 36123 17814 36124 18051 36124 18083 36124 17814 36125 18083 36125 18077 36125 20373 36126 20372 36126 18089 36126 18089 36127 20372 36127 18065 36127 18089 36128 18065 36128 18088 36128 18088 36129 18065 36129 18066 36129 18088 36130 18066 36130 18067 36130 18067 36131 18066 36131 18068 36131 18067 36132 18068 36132 18087 36132 18087 36133 18068 36133 18069 36133 18087 36134 18069 36134 18086 36134 18086 36135 18069 36135 18070 36135 18086 36136 18070 36136 18085 36136 18085 36137 18070 36137 18061 36137 18085 36138 18061 36138 18071 36138 18071 36139 18061 36139 18072 36139 18071 36140 18072 36140 18082 36140 18082 36141 18072 36141 18073 36141 18082 36142 18073 36142 18081 36142 18081 36143 18073 36143 18074 36143 18081 36144 18074 36144 18079 36144 18079 36145 18074 36145 20864 36145 18079 36146 20864 36146 18078 36146 20456 36147 18075 36147 17839 36147 17839 36148 18075 36148 20453 36148 17839 36149 20453 36149 17848 36149 17848 36150 20453 36150 17814 36150 17848 36151 17814 36151 18076 36151 18076 36152 17814 36152 18077 36152 18076 36153 18077 36153 18080 36153 18078 36154 20866 36154 18079 36154 18079 36155 20866 36155 18080 36155 18079 36156 18080 36156 18081 36156 18081 36157 18080 36157 18077 36157 18081 36158 18077 36158 18082 36158 18082 36159 18077 36159 18083 36159 18082 36160 18083 36160 18071 36160 18071 36161 18083 36161 18084 36161 18071 36162 18084 36162 18085 36162 18085 36163 18084 36163 18052 36163 18085 36164 18052 36164 18086 36164 18086 36165 18052 36165 18054 36165 18086 36166 18054 36166 18087 36166 18087 36167 18054 36167 18013 36167 18087 36168 18013 36168 18067 36168 18067 36169 18013 36169 18011 36169 18067 36170 18011 36170 18088 36170 18088 36171 18011 36171 17929 36171 18088 36172 17929 36172 18089 36172 18089 36173 17929 36173 20391 36173 18089 36174 20391 36174 20403 36174 18090 36175 18150 36175 18149 36175 16183 36176 18091 36176 18178 36176 18330 36177 18336 36177 18149 36177 18092 36178 18128 36178 18201 36178 15685 36179 18100 36179 18213 36179 15500 36180 15513 36180 18095 36180 15537 36181 15536 36181 18093 36181 18177 36182 18157 36182 18155 36182 16016 36183 18094 36183 16015 36183 16015 36184 18094 36184 18656 36184 16016 36185 16018 36185 18094 36185 18094 36186 16018 36186 15537 36186 18094 36187 15537 36187 18095 36187 18095 36188 15537 36188 18093 36188 18095 36189 18093 36189 15500 36189 18156 36190 15621 36190 18096 36190 18096 36191 15621 36191 15537 36191 18096 36192 15537 36192 16019 36192 16019 36193 15537 36193 16018 36193 15624 36194 18176 36194 15625 36194 15625 36195 18176 36195 18097 36195 15625 36196 18097 36196 18098 36196 18098 36197 18097 36197 18213 36197 18098 36198 18213 36198 18099 36198 18099 36199 18213 36199 18100 36199 15739 36200 15740 36200 18107 36200 18107 36201 15740 36201 18101 36201 18107 36202 18101 36202 18102 36202 18102 36203 18101 36203 15708 36203 18102 36204 15708 36204 18211 36204 18211 36205 15708 36205 15704 36205 15781 36206 18105 36206 15782 36206 15782 36207 18105 36207 18205 36207 15782 36208 18205 36208 18103 36208 15781 36209 18104 36209 18105 36209 18105 36210 18104 36210 18106 36210 18105 36211 18106 36211 18107 36211 18107 36212 18106 36212 15738 36212 18107 36213 15738 36213 15739 36213 18108 36214 15787 36214 18109 36214 18109 36215 15787 36215 18110 36215 18109 36216 18110 36216 18111 36216 18103 36217 18205 36217 15784 36217 15784 36218 18205 36218 18187 36218 15784 36219 18187 36219 15786 36219 16107 36220 18112 36220 18187 36220 16107 36221 18187 36221 16108 36221 15787 36222 15786 36222 18110 36222 18110 36223 15786 36223 18187 36223 18110 36224 18187 36224 16106 36224 16106 36225 18187 36225 18112 36225 16106 36226 18113 36226 18110 36226 18110 36227 18113 36227 18114 36227 18110 36228 18114 36228 18115 36228 18115 36229 18114 36229 18116 36229 18115 36230 18116 36230 18627 36230 18627 36231 18116 36231 18117 36231 18627 36232 18117 36232 18118 36232 18118 36233 18117 36233 16103 36233 18118 36234 16103 36234 16126 36234 18119 36235 18121 36235 16126 36235 16126 36236 18121 36236 18623 36236 16126 36237 18623 36237 18118 36237 18119 36238 18120 36238 18121 36238 18121 36239 18120 36239 16119 36239 18121 36240 16119 36240 18122 36240 18122 36241 16119 36241 18123 36241 18123 36242 16119 36242 17716 36242 18123 36243 17716 36243 18193 36243 17127 36244 18192 36244 18196 36244 18124 36245 18221 36245 18196 36245 18196 36246 18221 36246 18125 36246 18196 36247 18125 36247 17127 36247 18198 36248 18126 36248 18195 36248 18131 36249 16234 36249 18200 36249 18200 36250 16234 36250 16237 36250 18200 36251 16237 36251 18198 36251 18198 36252 16237 36252 18127 36252 18198 36253 18127 36253 18126 36253 18092 36254 18129 36254 18128 36254 18128 36255 18129 36255 18130 36255 18128 36256 18130 36256 18131 36256 18131 36257 18130 36257 16232 36257 18131 36258 16232 36258 16234 36258 18135 36259 18132 36259 18202 36259 18202 36260 18132 36260 18277 36260 18202 36261 18277 36261 18201 36261 18201 36262 18277 36262 18276 36262 18201 36263 18276 36263 18092 36263 18133 36264 18134 36264 18135 36264 18134 36265 18133 36265 18136 36265 18136 36266 18133 36266 18210 36266 18136 36267 18210 36267 18257 36267 18257 36268 18210 36268 18137 36268 18137 36269 18210 36269 18138 36269 18137 36270 18138 36270 18139 36270 18139 36271 18138 36271 18140 36271 18140 36272 18138 36272 18144 36272 18140 36273 18144 36273 18146 36273 18148 36274 18141 36274 18143 36274 18141 36275 16391 36275 18143 36275 18143 36276 16391 36276 18142 36276 18143 36277 18142 36277 18144 36277 18144 36278 18142 36278 18145 36278 18144 36279 18145 36279 18146 36279 18146 36280 18145 36280 16370 36280 18146 36281 16370 36281 18254 36281 19603 36282 16396 36282 18216 36282 18216 36283 16396 36283 18148 36283 18216 36284 18148 36284 18147 36284 18147 36285 18148 36285 18143 36285 18330 36286 18149 36286 18329 36286 18329 36287 18149 36287 17263 36287 17263 36288 18149 36288 18150 36288 17263 36289 18150 36289 18158 36289 18151 36290 18152 36290 18161 36290 16053 36291 18170 36291 16056 36291 16056 36292 18170 36292 18172 36292 16056 36293 18172 36293 16057 36293 16057 36294 18172 36294 18174 36294 16057 36295 18174 36295 18153 36295 18153 36296 18174 36296 18154 36296 18154 36297 18174 36297 18155 36297 18154 36298 18155 36298 18156 36298 18156 36299 18155 36299 18157 36299 18156 36300 18157 36300 15621 36300 18152 36301 18158 36301 18161 36301 18161 36302 18158 36302 18150 36302 18161 36303 18150 36303 18159 36303 18159 36304 18150 36304 18160 36304 18159 36305 18170 36305 18161 36305 18161 36306 18170 36306 16053 36306 18161 36307 16053 36307 18151 36307 18151 36308 16053 36308 18162 36308 18151 36309 18162 36309 18163 36309 18163 36310 18162 36310 18164 36310 18163 36311 18164 36311 18610 36311 18610 36312 18164 36312 18165 36312 18610 36313 18165 36313 18166 36313 18166 36314 18165 36314 16001 36314 18166 36315 16001 36315 18607 36315 18218 36316 18217 36316 15983 36316 15983 36317 18217 36317 18215 36317 15983 36318 18215 36318 15963 36318 15963 36319 18215 36319 15962 36319 15962 36320 18215 36320 18167 36320 15962 36321 18167 36321 15965 36321 15970 36322 18168 36322 18176 36322 15970 36323 18176 36323 18175 36323 15965 36324 18167 36324 15966 36324 15966 36325 18167 36325 18169 36325 15966 36326 18169 36326 18209 36326 18159 36327 18171 36327 18170 36327 18170 36328 18171 36328 15932 36328 18170 36329 15932 36329 18172 36329 18172 36330 15932 36330 18173 36330 18172 36331 18173 36331 18174 36331 18174 36332 18173 36332 18175 36332 18174 36333 18175 36333 18155 36333 18155 36334 18175 36334 18176 36334 18155 36335 18176 36335 18177 36335 18177 36336 18176 36336 15624 36336 18197 36337 18196 36337 18181 36337 18178 36338 18091 36338 18189 36338 18091 36339 16207 36339 18189 36339 18189 36340 16207 36340 16201 36340 18189 36341 16201 36341 18179 36341 18179 36342 16201 36342 18180 36342 18179 36343 18180 36343 18192 36343 18192 36344 18180 36344 19610 36344 18192 36345 19610 36345 18196 36345 18196 36346 19610 36346 19616 36346 18196 36347 19616 36347 18181 36347 18182 36348 18186 36348 18204 36348 18204 36349 18186 36349 16157 36349 16189 36350 16188 36350 18205 36350 16183 36351 18178 36351 16184 36351 16184 36352 18178 36352 18188 36352 16184 36353 18188 36353 16186 36353 18181 36354 18183 36354 18197 36354 18197 36355 18183 36355 16142 36355 18197 36356 16142 36356 18199 36356 18199 36357 16142 36357 18184 36357 18199 36358 18184 36358 18182 36358 18182 36359 18184 36359 18185 36359 18182 36360 18185 36360 18186 36360 16188 36361 16187 36361 18205 36361 18205 36362 16187 36362 16186 36362 18205 36363 16186 36363 18187 36363 18187 36364 16186 36364 18188 36364 18187 36365 18188 36365 16108 36365 16108 36366 18188 36366 18178 36366 16108 36367 18178 36367 18190 36367 18190 36368 18178 36368 18189 36368 18190 36369 18189 36369 16068 36369 16068 36370 18189 36370 18179 36370 16068 36371 18179 36371 18191 36371 18191 36372 18179 36372 18192 36372 18191 36373 18192 36373 18193 36373 18193 36374 18192 36374 17127 36374 18193 36375 17127 36375 18123 36375 18194 36376 18124 36376 18195 36376 18195 36377 18124 36377 18196 36377 18195 36378 18196 36378 18198 36378 18198 36379 18196 36379 18197 36379 18198 36380 18197 36380 18200 36380 18200 36381 18197 36381 18199 36381 18200 36382 18199 36382 18131 36382 18131 36383 18199 36383 18182 36383 18131 36384 18182 36384 18128 36384 18128 36385 18182 36385 18204 36385 18128 36386 18204 36386 18201 36386 18201 36387 18204 36387 18206 36387 18201 36388 18206 36388 18202 36388 18202 36389 18206 36389 18207 36389 18202 36390 18207 36390 18203 36390 16157 36391 16189 36391 18204 36391 18204 36392 16189 36392 18205 36392 18204 36393 18205 36393 18206 36393 18206 36394 18205 36394 18105 36394 18206 36395 18105 36395 18207 36395 18207 36396 18105 36396 18107 36396 18207 36397 18107 36397 18203 36397 18203 36398 18107 36398 18102 36398 18203 36399 18102 36399 18208 36399 18208 36400 18102 36400 18211 36400 18208 36401 18211 36401 18212 36401 18168 36402 18209 36402 18176 36402 18176 36403 18209 36403 18169 36403 18176 36404 18169 36404 18097 36404 18097 36405 18169 36405 18214 36405 18097 36406 18214 36406 18213 36406 18135 36407 18202 36407 18133 36407 18133 36408 18202 36408 18203 36408 18133 36409 18203 36409 18210 36409 18210 36410 18203 36410 18208 36410 18210 36411 18208 36411 18138 36411 18138 36412 18208 36412 18212 36412 18138 36413 18212 36413 18144 36413 18326 36414 19600 36414 18336 36414 18336 36415 19600 36415 19603 36415 18336 36416 19603 36416 18149 36416 18149 36417 19603 36417 18216 36417 18149 36418 18216 36418 18090 36418 15704 36419 15685 36419 18211 36419 18211 36420 15685 36420 18213 36420 18211 36421 18213 36421 18212 36421 18212 36422 18213 36422 18214 36422 18212 36423 18214 36423 18144 36423 18144 36424 18214 36424 18169 36424 18144 36425 18169 36425 18143 36425 18143 36426 18169 36426 18167 36426 18143 36427 18167 36427 18147 36427 18147 36428 18167 36428 18215 36428 18147 36429 18215 36429 18216 36429 18216 36430 18215 36430 18217 36430 18216 36431 18217 36431 18090 36431 18090 36432 18217 36432 18218 36432 18090 36433 18218 36433 18150 36433 18150 36434 18218 36434 18219 36434 18150 36435 18219 36435 18160 36435 18194 36436 18220 36436 18124 36436 18124 36437 18220 36437 18221 36437 17116 36438 17117 36438 18222 36438 18229 36439 18235 36439 18231 36439 18231 36440 18235 36440 18305 36440 18231 36441 18305 36441 18232 36441 18232 36442 18305 36442 18284 36442 18232 36443 18284 36443 18233 36443 18233 36444 18284 36444 18238 36444 18233 36445 18238 36445 18341 36445 18260 36446 18223 36446 18229 36446 18229 36447 18223 36447 18224 36447 18229 36448 18224 36448 18235 36448 17706 36449 18225 36449 18220 36449 18220 36450 18225 36450 18222 36450 18220 36451 18222 36451 18221 36451 18221 36452 18222 36452 17117 36452 18221 36453 17117 36453 18125 36453 18226 36454 18234 36454 17706 36454 17706 36455 18234 36455 18228 36455 17706 36456 18228 36456 18225 36456 18225 36457 18228 36457 18227 36457 18225 36458 18227 36458 18222 36458 18222 36459 18227 36459 18230 36459 18222 36460 18230 36460 17116 36460 18234 36461 18260 36461 18228 36461 18228 36462 18260 36462 18229 36462 18228 36463 18229 36463 18227 36463 18227 36464 18229 36464 18231 36464 18227 36465 18231 36465 18230 36465 18230 36466 18231 36466 18232 36466 18230 36467 18232 36467 17116 36467 17116 36468 18232 36468 18233 36468 18241 36469 18240 36469 18287 36469 18324 36470 18338 36470 18298 36470 18224 36471 18223 36471 18261 36471 18226 36472 17705 36472 18274 36472 18274 36473 17705 36473 16212 36473 18129 36474 18092 36474 16213 36474 16213 36475 18092 36475 18274 36475 16213 36476 18274 36476 16228 36476 16228 36477 18274 36477 16212 36477 18226 36478 18274 36478 18234 36478 18234 36479 18274 36479 18273 36479 18234 36480 18273 36480 18260 36480 18224 36481 18261 36481 18235 36481 18282 36482 18236 36482 18283 36482 18283 36483 18236 36483 18237 36483 18283 36484 18237 36484 18238 36484 18238 36485 18237 36485 19641 36485 18238 36486 19641 36486 18341 36486 16307 36487 16330 36487 18282 36487 18282 36488 16330 36488 16331 36488 18282 36489 16331 36489 18236 36489 18281 36490 18240 36490 18239 36490 18239 36491 18240 36491 18241 36491 18239 36492 18241 36492 16303 36492 18243 36493 18244 36493 18241 36493 18304 36494 18242 36494 18280 36494 18280 36495 18242 36495 18243 36495 16303 36496 18241 36496 16305 36496 16305 36497 18241 36497 18244 36497 16305 36498 18244 36498 16301 36498 18410 36499 18297 36499 18245 36499 18245 36500 18297 36500 18295 36500 18245 36501 18295 36501 18294 36501 18246 36502 18419 36502 18247 36502 18247 36503 18419 36503 18412 36503 18247 36504 18412 36504 18294 36504 18294 36505 18412 36505 18411 36505 18294 36506 18411 36506 18245 36506 18246 36507 18247 36507 18248 36507 18248 36508 18247 36508 18250 36508 18248 36509 18250 36509 18418 36509 18290 36510 18415 36510 18414 36510 18290 36511 18414 36511 18250 36511 18250 36512 18414 36512 18249 36512 18250 36513 18249 36513 18418 36513 18251 36514 18373 36514 18290 36514 18290 36515 18373 36515 18416 36515 18290 36516 18416 36516 18415 36516 16345 36517 18334 36517 18258 36517 16345 36518 18258 36518 18252 36518 18252 36519 18258 36519 18253 36519 18253 36520 18258 36520 16355 36520 16355 36521 18258 36521 18255 36521 16355 36522 18255 36522 18254 36522 18254 36523 18255 36523 18146 36523 18146 36524 18255 36524 18259 36524 18146 36525 18259 36525 18140 36525 18140 36526 18259 36526 18270 36526 18140 36527 18270 36527 18139 36527 18139 36528 18270 36528 18137 36528 18137 36529 18270 36529 18256 36529 18137 36530 18256 36530 18257 36530 18257 36531 18256 36531 18268 36531 18257 36532 18268 36532 18136 36532 18278 36533 18135 36533 18268 36533 18268 36534 18135 36534 18134 36534 18268 36535 18134 36535 18136 36535 18334 36536 18325 36536 18258 36536 18258 36537 18325 36537 18323 36537 18258 36538 18323 36538 18255 36538 18255 36539 18323 36539 18322 36539 18255 36540 18322 36540 18259 36540 18259 36541 18322 36541 18320 36541 18259 36542 18320 36542 18270 36542 18223 36543 18260 36543 18261 36543 18261 36544 18260 36544 18273 36544 18261 36545 18273 36545 18262 36545 18262 36546 18273 36546 18309 36546 18309 36547 18263 36547 18311 36547 18311 36548 18263 36548 18264 36548 18311 36549 18264 36549 18265 36549 18265 36550 18264 36550 18266 36550 18265 36551 18266 36551 18313 36551 18313 36552 18266 36552 18278 36552 18313 36553 18278 36553 18267 36553 18267 36554 18278 36554 18268 36554 18267 36555 18268 36555 18269 36555 18269 36556 18268 36556 18256 36556 18269 36557 18256 36557 18316 36557 18316 36558 18256 36558 18270 36558 18316 36559 18270 36559 18319 36559 18319 36560 18270 36560 18320 36560 18263 36561 18275 36561 18264 36561 18264 36562 18275 36562 18271 36562 18264 36563 18271 36563 18266 36563 18266 36564 18271 36564 18272 36564 18266 36565 18272 36565 18278 36565 18309 36566 18273 36566 18263 36566 18263 36567 18273 36567 18274 36567 18263 36568 18274 36568 18275 36568 18275 36569 18274 36569 18092 36569 18275 36570 18092 36570 18271 36570 18271 36571 18092 36571 18276 36571 18271 36572 18276 36572 18272 36572 18272 36573 18276 36573 18277 36573 18272 36574 18277 36574 18278 36574 18278 36575 18277 36575 18132 36575 18278 36576 18132 36576 18135 36576 18409 36577 18303 36577 18279 36577 18279 36578 18303 36578 18301 36578 18279 36579 18301 36579 18296 36579 18243 36580 18241 36580 18280 36580 18280 36581 18241 36581 18287 36581 18280 36582 18287 36582 18302 36582 18302 36583 18287 36583 18288 36583 18302 36584 18288 36584 18300 36584 18239 36585 16302 36585 18281 36585 18281 36586 16302 36586 16307 36586 18281 36587 16307 36587 18286 36587 18286 36588 16307 36588 18282 36588 18286 36589 18282 36589 18285 36589 18285 36590 18282 36590 18283 36590 18285 36591 18283 36591 18284 36591 18284 36592 18283 36592 18238 36592 18284 36593 18305 36593 18285 36593 18285 36594 18305 36594 18306 36594 18285 36595 18306 36595 18286 36595 18286 36596 18306 36596 18307 36596 18286 36597 18307 36597 18281 36597 18281 36598 18307 36598 18308 36598 18281 36599 18308 36599 18240 36599 18240 36600 18308 36600 18310 36600 18240 36601 18310 36601 18287 36601 18287 36602 18310 36602 18312 36602 18287 36603 18312 36603 18288 36603 18339 36604 18251 36604 18289 36604 18289 36605 18251 36605 18290 36605 18289 36606 18290 36606 18291 36606 18291 36607 18290 36607 18250 36607 18291 36608 18250 36608 18292 36608 18292 36609 18250 36609 18247 36609 18292 36610 18247 36610 18293 36610 18293 36611 18247 36611 18294 36611 18293 36612 18294 36612 18299 36612 18299 36613 18294 36613 18295 36613 18299 36614 18295 36614 18296 36614 18296 36615 18295 36615 18297 36615 18296 36616 18297 36616 18279 36616 18279 36617 18297 36617 18410 36617 18279 36618 18410 36618 18409 36618 18338 36619 18339 36619 18298 36619 18298 36620 18339 36620 18289 36620 18298 36621 18289 36621 18321 36621 18321 36622 18289 36622 18291 36622 18321 36623 18291 36623 18318 36623 18318 36624 18291 36624 18292 36624 18318 36625 18292 36625 18317 36625 18317 36626 18292 36626 18293 36626 18317 36627 18293 36627 18315 36627 18315 36628 18293 36628 18299 36628 18315 36629 18299 36629 18314 36629 18314 36630 18299 36630 18296 36630 18314 36631 18296 36631 18300 36631 18300 36632 18296 36632 18301 36632 18300 36633 18301 36633 18302 36633 18302 36634 18301 36634 18303 36634 18302 36635 18303 36635 18280 36635 18280 36636 18303 36636 18409 36636 18280 36637 18409 36637 18304 36637 18305 36638 18235 36638 18306 36638 18306 36639 18235 36639 18261 36639 18306 36640 18261 36640 18307 36640 18307 36641 18261 36641 18262 36641 18307 36642 18262 36642 18308 36642 18308 36643 18262 36643 18309 36643 18308 36644 18309 36644 18310 36644 18310 36645 18309 36645 18311 36645 18310 36646 18311 36646 18312 36646 18312 36647 18311 36647 18265 36647 18312 36648 18265 36648 18288 36648 18288 36649 18265 36649 18313 36649 18288 36650 18313 36650 18300 36650 18300 36651 18313 36651 18267 36651 18300 36652 18267 36652 18314 36652 18314 36653 18267 36653 18269 36653 18314 36654 18269 36654 18315 36654 18315 36655 18269 36655 18316 36655 18315 36656 18316 36656 18317 36656 18317 36657 18316 36657 18319 36657 18317 36658 18319 36658 18318 36658 18318 36659 18319 36659 18320 36659 18318 36660 18320 36660 18321 36660 18321 36661 18320 36661 18322 36661 18321 36662 18322 36662 18298 36662 18298 36663 18322 36663 18323 36663 18298 36664 18323 36664 18324 36664 18324 36665 18323 36665 18325 36665 18334 36666 16345 36666 16342 36666 18332 36667 18326 36667 18327 36667 17276 36668 18328 36668 18337 36668 18329 36669 17272 36669 18330 36669 18330 36670 17272 36670 18331 36670 18330 36671 18331 36671 18336 36671 18332 36672 18327 36672 16342 36672 18333 36673 18325 36673 18334 36673 18334 36674 16342 36674 18333 36674 18333 36675 16342 36675 18327 36675 18333 36676 18327 36676 18325 36676 18325 36677 18327 36677 18335 36677 18325 36678 18335 36678 18324 36678 18326 36679 18336 36679 18327 36679 18327 36680 18336 36680 18331 36680 18327 36681 18331 36681 18335 36681 18335 36682 18331 36682 17272 36682 18335 36683 17272 36683 18337 36683 18337 36684 17272 36684 17271 36684 18337 36685 17271 36685 17276 36685 18324 36686 18335 36686 18338 36686 18338 36687 18335 36687 18337 36687 18338 36688 18337 36688 18339 36688 18339 36689 18337 36689 18328 36689 18339 36690 18328 36690 18251 36690 18251 36691 18328 36691 17276 36691 18251 36692 17276 36692 18373 36692 16484 36693 18340 36693 20830 36693 20830 36694 18340 36694 19647 36694 18233 36695 18341 36695 18342 36695 18342 36696 18341 36696 19647 36696 18342 36697 19647 36697 18343 36697 18343 36698 19647 36698 18340 36698 20830 36699 18601 36699 18449 36699 20830 36700 18449 36700 16484 36700 16484 36701 18449 36701 18448 36701 16484 36702 18448 36702 18344 36702 18344 36703 18448 36703 18345 36703 18344 36704 18345 36704 16463 36704 16463 36705 18345 36705 18446 36705 16463 36706 18446 36706 18346 36706 18346 36707 18446 36707 18347 36707 18346 36708 18347 36708 18349 36708 18347 36709 18348 36709 18349 36709 18349 36710 18348 36710 18451 36710 18349 36711 18451 36711 16447 36711 18524 36712 16450 36712 18350 36712 18350 36713 16450 36713 16447 36713 18350 36714 16447 36714 18453 36714 18453 36715 16447 36715 18451 36715 16448 36716 16453 36716 18522 36716 18522 36717 16453 36717 16452 36717 18522 36718 16452 36718 18524 36718 18524 36719 16452 36719 16451 36719 18524 36720 16451 36720 16450 36720 18522 36721 18521 36721 16448 36721 16448 36722 18521 36722 18519 36722 16448 36723 18519 36723 16495 36723 16495 36724 18519 36724 18518 36724 16495 36725 18518 36725 16473 36725 16473 36726 18518 36726 18351 36726 16473 36727 18351 36727 16455 36727 16455 36728 18351 36728 18461 36728 16455 36729 18461 36729 18352 36729 18352 36730 18461 36730 18353 36730 18352 36731 18353 36731 18354 36731 18354 36732 18353 36732 18458 36732 18354 36733 18458 36733 18355 36733 18458 36734 18456 36734 18355 36734 18355 36735 18456 36735 18356 36735 18355 36736 18356 36736 18358 36736 18358 36737 18356 36737 18357 36737 18358 36738 18357 36738 16508 36738 16508 36739 18357 36739 18359 36739 16508 36740 18359 36740 16509 36740 18359 36741 18464 36741 16509 36741 16509 36742 18464 36742 18360 36742 16509 36743 18360 36743 18361 36743 18361 36744 18360 36744 18462 36744 18361 36745 18462 36745 16456 36745 16456 36746 18462 36746 18362 36746 16456 36747 18362 36747 18363 36747 18362 36748 18465 36748 18363 36748 18363 36749 18465 36749 18364 36749 18363 36750 18364 36750 16404 36750 16404 36751 18364 36751 18470 36751 16404 36752 18470 36752 16513 36752 18470 36753 18469 36753 16513 36753 16513 36754 18469 36754 18365 36754 16513 36755 18365 36755 16514 36755 16514 36756 18365 36756 18366 36756 16514 36757 18366 36757 16515 36757 16515 36758 18366 36758 18471 36758 16515 36759 18471 36759 16517 36759 16517 36760 18471 36760 18472 36760 16517 36761 18472 36761 16518 36761 16518 36762 18472 36762 16520 36762 18472 36763 18474 36763 16520 36763 16520 36764 18474 36764 18367 36764 16520 36765 18367 36765 16400 36765 16400 36766 18367 36766 18476 36766 16400 36767 18476 36767 18368 36767 18368 36768 18476 36768 18369 36768 18369 36769 18477 36769 18368 36769 18368 36770 18477 36770 18479 36770 18368 36771 18479 36771 18370 36771 18370 36772 18479 36772 18371 36772 18370 36773 18371 36773 16398 36773 17276 36774 18372 36774 16574 36774 17276 36775 16574 36775 18373 36775 16574 36776 16546 36776 18373 36776 18373 36777 16546 36777 16545 36777 18373 36778 16545 36778 18374 36778 16545 36779 18375 36779 18374 36779 18374 36780 18375 36780 18376 36780 18374 36781 18376 36781 18481 36781 18371 36782 18377 36782 16398 36782 16398 36783 18377 36783 18480 36783 16398 36784 18480 36784 16435 36784 16435 36785 18480 36785 18378 36785 16435 36786 18378 36786 16540 36786 16540 36787 18378 36787 18379 36787 16540 36788 18379 36788 16541 36788 16541 36789 18379 36789 18481 36789 16541 36790 18481 36790 16542 36790 16542 36791 18481 36791 18376 36791 18392 36792 18427 36792 18390 36792 18433 36793 18380 36793 18381 36793 18381 36794 18380 36794 18434 36794 18381 36795 18434 36795 18382 36795 18382 36796 18434 36796 18435 36796 18382 36797 18435 36797 18383 36797 18427 36798 18429 36798 18390 36798 18390 36799 18429 36799 18384 36799 18390 36800 18384 36800 18386 36800 18384 36801 18430 36801 18386 36801 18386 36802 18430 36802 18385 36802 18386 36803 18385 36803 18381 36803 18381 36804 18385 36804 18387 36804 18381 36805 18387 36805 18433 36805 20538 36806 18389 36806 18388 36806 18388 36807 18389 36807 18391 36807 18388 36808 18391 36808 18390 36808 18390 36809 18391 36809 18428 36809 18390 36810 18428 36810 18392 36810 18383 36811 18393 36811 18382 36811 18382 36812 18393 36812 18394 36812 18382 36813 18394 36813 18395 36813 18395 36814 18394 36814 18396 36814 18395 36815 18396 36815 20534 36815 20534 36816 18396 36816 18399 36816 20534 36817 18399 36817 18398 36817 18400 36818 18397 36818 18422 36818 18437 36819 18304 36819 18409 36819 18398 36820 18399 36820 18400 36820 18400 36821 18399 36821 18401 36821 18400 36822 18401 36822 18397 36822 18397 36823 18401 36823 18443 36823 18397 36824 18443 36824 18402 36824 18422 36825 18403 36825 18400 36825 18400 36826 18403 36826 18423 36826 18400 36827 18423 36827 18424 36827 18424 36828 18404 36828 18400 36828 18400 36829 18404 36829 18426 36829 18400 36830 18426 36830 20536 36830 20536 36831 18426 36831 18406 36831 20536 36832 18406 36832 18405 36832 18405 36833 18406 36833 18407 36833 18405 36834 18407 36834 20538 36834 20538 36835 18407 36835 18408 36835 20538 36836 18408 36836 18389 36836 18409 36837 18410 36837 18437 36837 18437 36838 18410 36838 18245 36838 18437 36839 18245 36839 18439 36839 18439 36840 18245 36840 18397 36840 18439 36841 18397 36841 18441 36841 18441 36842 18397 36842 18402 36842 18411 36843 18412 36843 18483 36843 18373 36844 18374 36844 18417 36844 18413 36845 18414 36845 15871 36845 15871 36846 18414 36846 18415 36846 15871 36847 18415 36847 18417 36847 18417 36848 18415 36848 18416 36848 18417 36849 18416 36849 18373 36849 18420 36850 18248 36850 15913 36850 15913 36851 18248 36851 18418 36851 15913 36852 18418 36852 18413 36852 18413 36853 18418 36853 18249 36853 18413 36854 18249 36854 18414 36854 18412 36855 18419 36855 18420 36855 18420 36856 18419 36856 18246 36856 18420 36857 18246 36857 18248 36857 18420 36858 15912 36858 18412 36858 18412 36859 15912 36859 15910 36859 18412 36860 15910 36860 18483 36860 18397 36861 18245 36861 18411 36861 18411 36862 18483 36862 18397 36862 18397 36863 18483 36863 18485 36863 18397 36864 18485 36864 18422 36864 18422 36865 18485 36865 18421 36865 18422 36866 18421 36866 18403 36866 18403 36867 18421 36867 18487 36867 18403 36868 18487 36868 18423 36868 18423 36869 18487 36869 18489 36869 18423 36870 18489 36870 18424 36870 18424 36871 18489 36871 18562 36871 18424 36872 18562 36872 18404 36872 18567 36873 18389 36873 18566 36873 18566 36874 18389 36874 18408 36874 18566 36875 18408 36875 18565 36875 18565 36876 18408 36876 18407 36876 18565 36877 18407 36877 18425 36877 18425 36878 18407 36878 18406 36878 18425 36879 18406 36879 18563 36879 18563 36880 18406 36880 18426 36880 18563 36881 18426 36881 18561 36881 18561 36882 18426 36882 18404 36882 18427 36883 18392 36883 18569 36883 18569 36884 18392 36884 18428 36884 18569 36885 18428 36885 18567 36885 18567 36886 18428 36886 18391 36886 18567 36887 18391 36887 18389 36887 18569 36888 18570 36888 18427 36888 18427 36889 18570 36889 18571 36889 18427 36890 18571 36890 18429 36890 18429 36891 18571 36891 18572 36891 18429 36892 18572 36892 18384 36892 18384 36893 18572 36893 18575 36893 18384 36894 18575 36894 18430 36894 18430 36895 18575 36895 18431 36895 18430 36896 18431 36896 18385 36896 18385 36897 18431 36897 18432 36897 18385 36898 18432 36898 18387 36898 18432 36899 18577 36899 18387 36899 18387 36900 18577 36900 18580 36900 18387 36901 18580 36901 18433 36901 18433 36902 18580 36902 18380 36902 18586 36903 18435 36903 18585 36903 18585 36904 18435 36904 18434 36904 18585 36905 18434 36905 18583 36905 18583 36906 18434 36906 18380 36906 18583 36907 18380 36907 18582 36907 18582 36908 18380 36908 18580 36908 18394 36909 18393 36909 18586 36909 18586 36910 18393 36910 18383 36910 18586 36911 18383 36911 18435 36911 18586 36912 18588 36912 18394 36912 18394 36913 18588 36913 18589 36913 18394 36914 18589 36914 18396 36914 18592 36915 18399 36915 18436 36915 18436 36916 18399 36916 18396 36916 18436 36917 18396 36917 18590 36917 18590 36918 18396 36918 18589 36918 18438 36919 18437 36919 18439 36919 18304 36920 18437 36920 18242 36920 18242 36921 18437 36921 18438 36921 18242 36922 18438 36922 18243 36922 18243 36923 18438 36923 18244 36923 16273 36924 18438 36924 18440 36924 18440 36925 18438 36925 18439 36925 18440 36926 18439 36926 18594 36926 18594 36927 18439 36927 18441 36927 18594 36928 18441 36928 18442 36928 18442 36929 18441 36929 18402 36929 18442 36930 18402 36930 18593 36930 18593 36931 18402 36931 18443 36931 18593 36932 18443 36932 18592 36932 18592 36933 18443 36933 18401 36933 18592 36934 18401 36934 18399 36934 16301 36935 18244 36935 16272 36935 16272 36936 18244 36936 18438 36936 16272 36937 18438 36937 18444 36937 18444 36938 18438 36938 16273 36938 18347 36939 18446 36939 18445 36939 18445 36940 18446 36940 18345 36940 18445 36941 18345 36941 18447 36941 18447 36942 18345 36942 18448 36942 18447 36943 18448 36943 18528 36943 18528 36944 18448 36944 18449 36944 18528 36945 18449 36945 18529 36945 18347 36946 18445 36946 18348 36946 18348 36947 18445 36947 18450 36947 18348 36948 18450 36948 18451 36948 18451 36949 18450 36949 18452 36949 18451 36950 18452 36950 18453 36950 18453 36951 18452 36951 18350 36951 18350 36952 18452 36952 18454 36952 18350 36953 18454 36953 18524 36953 18455 36954 18456 36954 18457 36954 18457 36955 18456 36955 18458 36955 18457 36956 18458 36956 18459 36956 18459 36957 18458 36957 18353 36957 18459 36958 18353 36958 18460 36958 18460 36959 18353 36959 18461 36959 18460 36960 18461 36960 18517 36960 18466 36961 18462 36961 18542 36961 18542 36962 18462 36962 18360 36962 18542 36963 18360 36963 18463 36963 18463 36964 18360 36964 18464 36964 18463 36965 18464 36965 18544 36965 18544 36966 18464 36966 18359 36966 18544 36967 18359 36967 18545 36967 18545 36968 18359 36968 18357 36968 18545 36969 18357 36969 18455 36969 18455 36970 18357 36970 18356 36970 18455 36971 18356 36971 18456 36971 18468 36972 18364 36972 18540 36972 18540 36973 18364 36973 18465 36973 18540 36974 18465 36974 18466 36974 18466 36975 18465 36975 18362 36975 18466 36976 18362 36976 18462 36976 18511 36977 18366 36977 18467 36977 18467 36978 18366 36978 18365 36978 18467 36979 18365 36979 18538 36979 18538 36980 18365 36980 18469 36980 18538 36981 18469 36981 18468 36981 18468 36982 18469 36982 18470 36982 18468 36983 18470 36983 18364 36983 18471 36984 18512 36984 18472 36984 18472 36985 18512 36985 18473 36985 18472 36986 18473 36986 18474 36986 18474 36987 18473 36987 18475 36987 18474 36988 18475 36988 18367 36988 18367 36989 18475 36989 18509 36989 18367 36990 18509 36990 18476 36990 18476 36991 18509 36991 18369 36991 18369 36992 18509 36992 18507 36992 18369 36993 18507 36993 18477 36993 18478 36994 18371 36994 18507 36994 18507 36995 18371 36995 18479 36995 18507 36996 18479 36996 18477 36996 18378 36997 18480 36997 18478 36997 18478 36998 18480 36998 18377 36998 18478 36999 18377 36999 18371 36999 18478 37000 18505 37000 18378 37000 18378 37001 18505 37001 18504 37001 18378 37002 18504 37002 18379 37002 18379 37003 18504 37003 18481 37003 18481 37004 18504 37004 15923 37004 18481 37005 15923 37005 18374 37005 18374 37006 15923 37006 19663 37006 18374 37007 19663 37007 18417 37007 15910 37008 18482 37008 18483 37008 18483 37009 18482 37009 18484 37009 18483 37010 18484 37010 18485 37010 18485 37011 18484 37011 18486 37011 18485 37012 18486 37012 18421 37012 18421 37013 18486 37013 18531 37013 18421 37014 18531 37014 18487 37014 18487 37015 18531 37015 18488 37015 18487 37016 18488 37016 18489 37016 18489 37017 18488 37017 18490 37017 18489 37018 18490 37018 18562 37018 18562 37019 18490 37019 18491 37019 18562 37020 18491 37020 18534 37020 18530 37021 18497 37021 18532 37021 18532 37022 18497 37022 18499 37022 18532 37023 18499 37023 18492 37023 18492 37024 18499 37024 18500 37024 18492 37025 18500 37025 18533 37025 18533 37026 18500 37026 18502 37026 18533 37027 18502 37027 18493 37027 18493 37028 18502 37028 18494 37028 18493 37029 18494 37029 18495 37029 15908 37030 18496 37030 18530 37030 18530 37031 18496 37031 15924 37031 18530 37032 15924 37032 18497 37032 18497 37033 15924 37033 18498 37033 18497 37034 18498 37034 18499 37034 18499 37035 18498 37035 18501 37035 18499 37036 18501 37036 18500 37036 18500 37037 18501 37037 18506 37037 18500 37038 18506 37038 18502 37038 18502 37039 18506 37039 18503 37039 18502 37040 18503 37040 18494 37040 18494 37041 18503 37041 18508 37041 18494 37042 18508 37042 18495 37042 15924 37043 15923 37043 18498 37043 18498 37044 15923 37044 18504 37044 18498 37045 18504 37045 18501 37045 18501 37046 18504 37046 18505 37046 18501 37047 18505 37047 18506 37047 18506 37048 18505 37048 18478 37048 18506 37049 18478 37049 18503 37049 18503 37050 18478 37050 18507 37050 18503 37051 18507 37051 18508 37051 18508 37052 18507 37052 18509 37052 18508 37053 18509 37053 18495 37053 18495 37054 18509 37054 18475 37054 18495 37055 18475 37055 18510 37055 18510 37056 18475 37056 18473 37056 18510 37057 18473 37057 18511 37057 18511 37058 18473 37058 18512 37058 18511 37059 18512 37059 18366 37059 18366 37060 18512 37060 18471 37060 18598 37061 18597 37061 18559 37061 18559 37062 18597 37062 18596 37062 18559 37063 18596 37063 18557 37063 18557 37064 18596 37064 18595 37064 18557 37065 18595 37065 18556 37065 18556 37066 18595 37066 18513 37066 18556 37067 18513 37067 18555 37067 18555 37068 18513 37068 18514 37068 18555 37069 18514 37069 18553 37069 18553 37070 18514 37070 18515 37070 18553 37071 18515 37071 18551 37071 18551 37072 18515 37072 18591 37072 18551 37073 18591 37073 18516 37073 18461 37074 18351 37074 18517 37074 18517 37075 18351 37075 18518 37075 18517 37076 18518 37076 18548 37076 18548 37077 18518 37077 18519 37077 18548 37078 18519 37078 18520 37078 18520 37079 18519 37079 18521 37079 18520 37080 18521 37080 18550 37080 18550 37081 18521 37081 18522 37081 18550 37082 18522 37082 18523 37082 18523 37083 18522 37083 18524 37083 18523 37084 18524 37084 18552 37084 18552 37085 18524 37085 18454 37085 18552 37086 18454 37086 18554 37086 18554 37087 18454 37087 18452 37087 18554 37088 18452 37088 18525 37088 18525 37089 18452 37089 18450 37089 18525 37090 18450 37090 18526 37090 18526 37091 18450 37091 18445 37091 18526 37092 18445 37092 18558 37092 18558 37093 18445 37093 18447 37093 18558 37094 18447 37094 18527 37094 18527 37095 18447 37095 18528 37095 18527 37096 18528 37096 18560 37096 18560 37097 18528 37097 18529 37097 18484 37098 15908 37098 18486 37098 18486 37099 15908 37099 18530 37099 18486 37100 18530 37100 18531 37100 18531 37101 18530 37101 18532 37101 18531 37102 18532 37102 18488 37102 18488 37103 18532 37103 18492 37103 18488 37104 18492 37104 18490 37104 18490 37105 18492 37105 18533 37105 18490 37106 18533 37106 18491 37106 18491 37107 18533 37107 18493 37107 18491 37108 18493 37108 18534 37108 18534 37109 18493 37109 18495 37109 18534 37110 18495 37110 18535 37110 18535 37111 18495 37111 18510 37111 18535 37112 18510 37112 18564 37112 18564 37113 18510 37113 18511 37113 18564 37114 18511 37114 18536 37114 18536 37115 18511 37115 18467 37115 18536 37116 18467 37116 18537 37116 18537 37117 18467 37117 18538 37117 18537 37118 18538 37118 18539 37118 18539 37119 18538 37119 18468 37119 18539 37120 18468 37120 18568 37120 18568 37121 18468 37121 18540 37121 18568 37122 18540 37122 18541 37122 18541 37123 18540 37123 18466 37123 18541 37124 18466 37124 18573 37124 18573 37125 18466 37125 18542 37125 18573 37126 18542 37126 18574 37126 18574 37127 18542 37127 18463 37127 18574 37128 18463 37128 18576 37128 18576 37129 18463 37129 18544 37129 18576 37130 18544 37130 18543 37130 18543 37131 18544 37131 18545 37131 18543 37132 18545 37132 18578 37132 18578 37133 18545 37133 18455 37133 18578 37134 18455 37134 18579 37134 18579 37135 18455 37135 18457 37135 18579 37136 18457 37136 18581 37136 18581 37137 18457 37137 18459 37137 18581 37138 18459 37138 18546 37138 18546 37139 18459 37139 18460 37139 18546 37140 18460 37140 18547 37140 18547 37141 18460 37141 18517 37141 18547 37142 18517 37142 18584 37142 18584 37143 18517 37143 18548 37143 18584 37144 18548 37144 18587 37144 18587 37145 18548 37145 18520 37145 18587 37146 18520 37146 18549 37146 18549 37147 18520 37147 18550 37147 18549 37148 18550 37148 18516 37148 18516 37149 18550 37149 18523 37149 18516 37150 18523 37150 18551 37150 18551 37151 18523 37151 18552 37151 18551 37152 18552 37152 18553 37152 18553 37153 18552 37153 18554 37153 18553 37154 18554 37154 18555 37154 18555 37155 18554 37155 18525 37155 18555 37156 18525 37156 18556 37156 18556 37157 18525 37157 18526 37157 18556 37158 18526 37158 18557 37158 18557 37159 18526 37159 18558 37159 18557 37160 18558 37160 18559 37160 18559 37161 18558 37161 18527 37161 18559 37162 18527 37162 18598 37162 18598 37163 18527 37163 18560 37163 18404 37164 18562 37164 18561 37164 18561 37165 18562 37165 18534 37165 18561 37166 18534 37166 18563 37166 18563 37167 18534 37167 18535 37167 18563 37168 18535 37168 18425 37168 18425 37169 18535 37169 18564 37169 18425 37170 18564 37170 18565 37170 18565 37171 18564 37171 18536 37171 18565 37172 18536 37172 18566 37172 18566 37173 18536 37173 18537 37173 18566 37174 18537 37174 18567 37174 18567 37175 18537 37175 18539 37175 18567 37176 18539 37176 18569 37176 18569 37177 18539 37177 18568 37177 18569 37178 18568 37178 18570 37178 18570 37179 18568 37179 18541 37179 18570 37180 18541 37180 18571 37180 18571 37181 18541 37181 18573 37181 18571 37182 18573 37182 18572 37182 18572 37183 18573 37183 18574 37183 18572 37184 18574 37184 18575 37184 18575 37185 18574 37185 18576 37185 18575 37186 18576 37186 18431 37186 18431 37187 18576 37187 18543 37187 18431 37188 18543 37188 18432 37188 18432 37189 18543 37189 18578 37189 18432 37190 18578 37190 18577 37190 18577 37191 18578 37191 18579 37191 18577 37192 18579 37192 18580 37192 18580 37193 18579 37193 18581 37193 18580 37194 18581 37194 18582 37194 18582 37195 18581 37195 18546 37195 18582 37196 18546 37196 18583 37196 18583 37197 18546 37197 18547 37197 18583 37198 18547 37198 18585 37198 18585 37199 18547 37199 18584 37199 18585 37200 18584 37200 18586 37200 18586 37201 18584 37201 18587 37201 18586 37202 18587 37202 18588 37202 18588 37203 18587 37203 18549 37203 18588 37204 18549 37204 18589 37204 18589 37205 18549 37205 18516 37205 18589 37206 18516 37206 18590 37206 18590 37207 18516 37207 18591 37207 18590 37208 18591 37208 18436 37208 18436 37209 18591 37209 18515 37209 18436 37210 18515 37210 18592 37210 18592 37211 18515 37211 18514 37211 18592 37212 18514 37212 18593 37212 18593 37213 18514 37213 18513 37213 18593 37214 18513 37214 18442 37214 18442 37215 18513 37215 18595 37215 18442 37216 18595 37216 18594 37216 18594 37217 18595 37217 18596 37217 18594 37218 18596 37218 18440 37218 18440 37219 18596 37219 18597 37219 18440 37220 18597 37220 16273 37220 16273 37221 18597 37221 18598 37221 16273 37222 18598 37222 18599 37222 18599 37223 18598 37223 18560 37223 18599 37224 18560 37224 18600 37224 18600 37225 18560 37225 18529 37225 18600 37226 18529 37226 16268 37226 16268 37227 18529 37227 18449 37227 16268 37228 18449 37228 18601 37228 18602 37229 18686 37229 19191 37229 18666 37230 18673 37230 18655 37230 15772 37231 18626 37231 18625 37231 15864 37232 18111 37232 18110 37232 17132 37233 18603 37233 18604 37233 18605 37234 16011 37234 16012 37234 18605 37235 16012 37235 18675 37235 16011 37236 18605 37236 18606 37236 18606 37237 18605 37237 18674 37237 18606 37238 18674 37238 18607 37238 18607 37239 18674 37239 18166 37239 18166 37240 18674 37240 18608 37240 18166 37241 18608 37241 18610 37241 18610 37242 18608 37242 18609 37242 18610 37243 18609 37243 18163 37243 19050 37244 19048 37244 18609 37244 19048 37245 18611 37245 18609 37245 18609 37246 18611 37246 19046 37246 18609 37247 19046 37247 18163 37247 18163 37248 19046 37248 18612 37248 18163 37249 18612 37249 18151 37249 18613 37250 19052 37250 18671 37250 18613 37251 18671 37251 19045 37251 19045 37252 18671 37252 18614 37252 19045 37253 18614 37253 19043 37253 18616 37254 18617 37254 18614 37254 18614 37255 18617 37255 19042 37255 18614 37256 19042 37256 19043 37256 18654 37257 19036 37257 18615 37257 18615 37258 19036 37258 19172 37258 18615 37259 19172 37259 18616 37259 18616 37260 19172 37260 19040 37260 18616 37261 19040 37261 18617 37261 19039 37262 19034 37262 18678 37262 18678 37263 19034 37263 18618 37263 19039 37264 18678 37264 18619 37264 18619 37265 18678 37265 18621 37265 18619 37266 18621 37266 18620 37266 18620 37267 18621 37267 18622 37267 18620 37268 18622 37268 19119 37268 18121 37269 18624 37269 18623 37269 18623 37270 18624 37270 18696 37270 18623 37271 18696 37271 18118 37271 18628 37272 18627 37272 18118 37272 18627 37273 18625 37273 18115 37273 18115 37274 18625 37274 18626 37274 18115 37275 18626 37275 18110 37275 18110 37276 18626 37276 15845 37276 18110 37277 15845 37277 15864 37277 18627 37278 18628 37278 18625 37278 18625 37279 18628 37279 15773 37279 18625 37280 15773 37280 15772 37280 18697 37281 15721 37281 15720 37281 18697 37282 15720 37282 18629 37282 15720 37283 18630 37283 18629 37283 18629 37284 18630 37284 15767 37284 18629 37285 15767 37285 18628 37285 18628 37286 15767 37286 18631 37286 18628 37287 18631 37287 15773 37287 18700 37288 15726 37288 18632 37288 18632 37289 15726 37289 15725 37289 18632 37290 15725 37290 15724 37290 15721 37291 18697 37291 15722 37291 15722 37292 18697 37292 18633 37292 15722 37293 18633 37293 15724 37293 15724 37294 18633 37294 18634 37294 15724 37295 18634 37295 18632 37295 18699 37296 18636 37296 18635 37296 18643 37297 15691 37297 19765 37297 19765 37298 15691 37298 18636 37298 19765 37299 18636 37299 18637 37299 18637 37300 18636 37300 18699 37300 18637 37301 18699 37301 18638 37301 18648 37302 18649 37302 19770 37302 19770 37303 18649 37303 18639 37303 19770 37304 18639 37304 18640 37304 18640 37305 18639 37305 18641 37305 18640 37306 18641 37306 19771 37306 19771 37307 18641 37307 18642 37307 19771 37308 18642 37308 18643 37308 18643 37309 18642 37309 15695 37309 18643 37310 15695 37310 15691 37310 18644 37311 18651 37311 18645 37311 18645 37312 18651 37312 18646 37312 18645 37313 18646 37313 18648 37313 18648 37314 18646 37314 18647 37314 18648 37315 18647 37315 18649 37315 19773 37316 15662 37316 18644 37316 18644 37317 15662 37317 18650 37317 18644 37318 18650 37318 18651 37318 18679 37319 15646 37319 18652 37319 18652 37320 15646 37320 15645 37320 18652 37321 15645 37321 18680 37321 18680 37322 15645 37322 15644 37322 18680 37323 15644 37323 18653 37323 15671 37324 18678 37324 18654 37324 18654 37325 18678 37325 18618 37325 18654 37326 18618 37326 19036 37326 18676 37327 15530 37327 18655 37327 18655 37328 15530 37328 15572 37328 18655 37329 15572 37329 18666 37329 18666 37330 15572 37330 15573 37330 18666 37331 15573 37331 18667 37331 16012 37332 16004 37332 18675 37332 18675 37333 16004 37333 18656 37333 18675 37334 18656 37334 15514 37334 15514 37335 18656 37335 18094 37335 15514 37336 18094 37336 18657 37336 18657 37337 18094 37337 18095 37337 18657 37338 18095 37338 15513 37338 18659 37339 18658 37339 18662 37339 18659 37340 18662 37340 19209 37340 18658 37341 18660 37341 18662 37341 18662 37342 18660 37342 18661 37342 18662 37343 18661 37343 18689 37343 18703 37344 18704 37344 18689 37344 18689 37345 18704 37345 18663 37345 18689 37346 18663 37346 18662 37346 18662 37347 18663 37347 18664 37347 18662 37348 18664 37348 18604 37348 18604 37349 18664 37349 18122 37349 18604 37350 18122 37350 17132 37350 17132 37351 18122 37351 18123 37351 18603 37352 19211 37352 18604 37352 18604 37353 19211 37353 19213 37353 18604 37354 19213 37354 18662 37354 18662 37355 19213 37355 18665 37355 18662 37356 18665 37356 19209 37356 18672 37357 18673 37357 18670 37357 18670 37358 18673 37358 18666 37358 18670 37359 18666 37359 18668 37359 18668 37360 18666 37360 18667 37360 18668 37361 18667 37361 18669 37361 18671 37362 18672 37362 18614 37362 18614 37363 18672 37363 18670 37363 18614 37364 18670 37364 18616 37364 18616 37365 18670 37365 18668 37365 18616 37366 18668 37366 18615 37366 18615 37367 18668 37367 18669 37367 18615 37368 18669 37368 18654 37368 18654 37369 18669 37369 15670 37369 18654 37370 15670 37370 15671 37370 19052 37371 19050 37371 18671 37371 18671 37372 19050 37372 18609 37372 18671 37373 18609 37373 18672 37373 18672 37374 18609 37374 18608 37374 18672 37375 18608 37375 18673 37375 18673 37376 18608 37376 18674 37376 18673 37377 18674 37377 18655 37377 18655 37378 18674 37378 18605 37378 18655 37379 18605 37379 18676 37379 18676 37380 18605 37380 18675 37380 18676 37381 18675 37381 18677 37381 18677 37382 18675 37382 15514 37382 15671 37383 15647 37383 18678 37383 18678 37384 15647 37384 18679 37384 18678 37385 18679 37385 18621 37385 18621 37386 18679 37386 18652 37386 18621 37387 18652 37387 18622 37387 18622 37388 18652 37388 18680 37388 18622 37389 18680 37389 19773 37389 19773 37390 18680 37390 18653 37390 19773 37391 18653 37391 15662 37391 18699 37392 18701 37392 18638 37392 18638 37393 18701 37393 18681 37393 18638 37394 18681 37394 18682 37394 18682 37395 18681 37395 18602 37395 18682 37396 18602 37396 18683 37396 18683 37397 18602 37397 19191 37397 18687 37398 18684 37398 18602 37398 18602 37399 18684 37399 18685 37399 18602 37400 18685 37400 18686 37400 19217 37401 19234 37401 18703 37401 18703 37402 19234 37402 18688 37402 18703 37403 18688 37403 18687 37403 18687 37404 18688 37404 19218 37404 18687 37405 19218 37405 18684 37405 18661 37406 18690 37406 18689 37406 18689 37407 18690 37407 18691 37407 18689 37408 18691 37408 18703 37408 18703 37409 18691 37409 19216 37409 18703 37410 19216 37410 19217 37410 18702 37411 18698 37411 18692 37411 18692 37412 18698 37412 18693 37412 18692 37413 18693 37413 18694 37413 18694 37414 18693 37414 18695 37414 18694 37415 18695 37415 18705 37415 18705 37416 18695 37416 18696 37416 18705 37417 18696 37417 18706 37417 18706 37418 18696 37418 18624 37418 18118 37419 18696 37419 18628 37419 18628 37420 18696 37420 18695 37420 18628 37421 18695 37421 18629 37421 18629 37422 18695 37422 18693 37422 18629 37423 18693 37423 18697 37423 18697 37424 18693 37424 18698 37424 18697 37425 18698 37425 18633 37425 18633 37426 18698 37426 18702 37426 18633 37427 18702 37427 18634 37427 18635 37428 18700 37428 18699 37428 18699 37429 18700 37429 18632 37429 18699 37430 18632 37430 18701 37430 18701 37431 18632 37431 18634 37431 18701 37432 18634 37432 18681 37432 18681 37433 18634 37433 18702 37433 18681 37434 18702 37434 18602 37434 18602 37435 18702 37435 18692 37435 18602 37436 18692 37436 18687 37436 18687 37437 18692 37437 18694 37437 18687 37438 18694 37438 18703 37438 18703 37439 18694 37439 18705 37439 18703 37440 18705 37440 18704 37440 18704 37441 18705 37441 18706 37441 18704 37442 18706 37442 18663 37442 18663 37443 18706 37443 18624 37443 18663 37444 18624 37444 18664 37444 18664 37445 18624 37445 18121 37445 18664 37446 18121 37446 18122 37446 19201 37447 19200 37447 18940 37447 19199 37448 18763 37448 18765 37448 19061 37449 19065 37449 18889 37449 19126 37450 18984 37450 18883 37450 18985 37451 19063 37451 18900 37451 18876 37452 19072 37452 18875 37452 19073 37453 18843 37453 18844 37453 18797 37454 18779 37454 18991 37454 18817 37455 19752 37455 18707 37455 18707 37456 19752 37456 19750 37456 18707 37457 19750 37457 18708 37457 18708 37458 19750 37458 18709 37458 18708 37459 18709 37459 18711 37459 18711 37460 18709 37460 18710 37460 18711 37461 18710 37461 18815 37461 18815 37462 18710 37462 18712 37462 18815 37463 18712 37463 19196 37463 18870 37464 19754 37464 18817 37464 18817 37465 19754 37465 19753 37465 18817 37466 19753 37466 19752 37466 18872 37467 18713 37467 19757 37467 19757 37468 18713 37468 18714 37468 18714 37469 18713 37469 18867 37469 18714 37470 18867 37470 19743 37470 19743 37471 18867 37471 18865 37471 19743 37472 18865 37472 19744 37472 19744 37473 18865 37473 18863 37473 19744 37474 18863 37474 19745 37474 19745 37475 18863 37475 18862 37475 19745 37476 18862 37476 19746 37476 19746 37477 18862 37477 18861 37477 19746 37478 18861 37478 19747 37478 19747 37479 18861 37479 18715 37479 19747 37480 18715 37480 18717 37480 18715 37481 18716 37481 18717 37481 18717 37482 18716 37482 18860 37482 18717 37483 18860 37483 19797 37483 19797 37484 18860 37484 18718 37484 18718 37485 18860 37485 18719 37485 18718 37486 18719 37486 19798 37486 19798 37487 18719 37487 18859 37487 19798 37488 18859 37488 18720 37488 18720 37489 18859 37489 18721 37489 18720 37490 18721 37490 19800 37490 19800 37491 18721 37491 18722 37491 18722 37492 18721 37492 18723 37492 18722 37493 18723 37493 18724 37493 18724 37494 18723 37494 18856 37494 18724 37495 18856 37495 18725 37495 18725 37496 18856 37496 18855 37496 18725 37497 18855 37497 19804 37497 18851 37498 19806 37498 18852 37498 18852 37499 19806 37499 19804 37499 18852 37500 19804 37500 18726 37500 18726 37501 19804 37501 18855 37501 18848 37502 18732 37502 18727 37502 18727 37503 18732 37503 19791 37503 18727 37504 19791 37504 18729 37504 18729 37505 19791 37505 18728 37505 18729 37506 18728 37506 18851 37506 18851 37507 18728 37507 18730 37507 18851 37508 18730 37508 19806 37508 18734 37509 19794 37509 18848 37509 18848 37510 19794 37510 18731 37510 18848 37511 18731 37511 18732 37511 18845 37512 19075 37512 18846 37512 18846 37513 19075 37513 18733 37513 18846 37514 18733 37514 18739 37514 18848 37515 18735 37515 18734 37515 18734 37516 18735 37516 18736 37516 18734 37517 18736 37517 18737 37517 18737 37518 18736 37518 18846 37518 18737 37519 18846 37519 18738 37519 18738 37520 18846 37520 18739 37520 18738 37521 18739 37521 18740 37521 18882 37522 18741 37522 17240 37522 17240 37523 18741 37523 18742 37523 17240 37524 18742 37524 18743 37524 18743 37525 18742 37525 18744 37525 18743 37526 18744 37526 18745 37526 18744 37527 18885 37527 18745 37527 18745 37528 18885 37528 18886 37528 18745 37529 18886 37529 18746 37529 18746 37530 18886 37530 18747 37530 18746 37531 18747 37531 18750 37531 18747 37532 18748 37532 18750 37532 18750 37533 18748 37533 18749 37533 18750 37534 18749 37534 18751 37534 18751 37535 18749 37535 18752 37535 18751 37536 18752 37536 18753 37536 18753 37537 18752 37537 18949 37537 18753 37538 18949 37538 18953 37538 18955 37539 18956 37539 17230 37539 17230 37540 18956 37540 18754 37540 17230 37541 18754 37541 18755 37541 18755 37542 18754 37542 18756 37542 18755 37543 18756 37543 18760 37543 17146 37544 18757 37544 18930 37544 18930 37545 18757 37545 17168 37545 18930 37546 17168 37546 18758 37546 18758 37547 17168 37547 17225 37547 18758 37548 17225 37548 18759 37548 18759 37549 17225 37549 17226 37549 18759 37550 17226 37550 18927 37550 18927 37551 17226 37551 18760 37551 18927 37552 18760 37552 18761 37552 18761 37553 18760 37553 18756 37553 18929 37554 18762 37554 17146 37554 18919 37555 17157 37555 17154 37555 17157 37556 18919 37556 17158 37556 18763 37557 18764 37557 18765 37557 18765 37558 18764 37558 17151 37558 18765 37559 17151 37559 18923 37559 18923 37560 17151 37560 17150 37560 18767 37561 19198 37561 18766 37561 18766 37562 19198 37562 19204 37562 18766 37563 19204 37563 19203 37563 18767 37564 18766 37564 18768 37564 18768 37565 18766 37565 18769 37565 18768 37566 18769 37566 18770 37566 18770 37567 18769 37567 19016 37567 18770 37568 19016 37568 18816 37568 18816 37569 19016 37569 19015 37569 18816 37570 19015 37570 18771 37570 18771 37571 19015 37571 19014 37571 18771 37572 19014 37572 18772 37572 18772 37573 19014 37573 19013 37573 18772 37574 19013 37574 18773 37574 18773 37575 19013 37575 18774 37575 18773 37576 18774 37576 18818 37576 18818 37577 18774 37577 19012 37577 18818 37578 19012 37578 18775 37578 18775 37579 19012 37579 19011 37579 18775 37580 19011 37580 18776 37580 18776 37581 19011 37581 18777 37581 18776 37582 18777 37582 18820 37582 18820 37583 18777 37583 19008 37583 18820 37584 19008 37584 18778 37584 18991 37585 18779 37585 18780 37585 18780 37586 18779 37586 18799 37586 18780 37587 18799 37587 18993 37587 18993 37588 18799 37588 18801 37588 18993 37589 18801 37589 18994 37589 18994 37590 18801 37590 18781 37590 18994 37591 18781 37591 18783 37591 18783 37592 18781 37592 18782 37592 18783 37593 18782 37593 18996 37593 18996 37594 18782 37594 18784 37594 18996 37595 18784 37595 18999 37595 18999 37596 18784 37596 18802 37596 18999 37597 18802 37597 19000 37597 19000 37598 18802 37598 18804 37598 19000 37599 18804 37599 19001 37599 19001 37600 18804 37600 18785 37600 19001 37601 18785 37601 18786 37601 18786 37602 18785 37602 18806 37602 18786 37603 18806 37603 18787 37603 18787 37604 18806 37604 18788 37604 18787 37605 18788 37605 19005 37605 19005 37606 18788 37606 18790 37606 19005 37607 18790 37607 18789 37607 18789 37608 18790 37608 18809 37608 18789 37609 18809 37609 18791 37609 18791 37610 18809 37610 18792 37610 18791 37611 18792 37611 18793 37611 18793 37612 18792 37612 18810 37612 18793 37613 18810 37613 18794 37613 18794 37614 18810 37614 18812 37614 18794 37615 18812 37615 18778 37615 18778 37616 18812 37616 18814 37616 18778 37617 18814 37617 18820 37617 18989 37618 18988 37618 18795 37618 18795 37619 18988 37619 18796 37619 18795 37620 18796 37620 18875 37620 18873 37621 18842 37621 18797 37621 18797 37622 18842 37622 18779 37622 18779 37623 18842 37623 18798 37623 18779 37624 18798 37624 18799 37624 18799 37625 18798 37625 18800 37625 18799 37626 18800 37626 18801 37626 18801 37627 18800 37627 18839 37627 18801 37628 18839 37628 18781 37628 18781 37629 18839 37629 18837 37629 18781 37630 18837 37630 18782 37630 18782 37631 18837 37631 18836 37631 18782 37632 18836 37632 18784 37632 18784 37633 18836 37633 18834 37633 18784 37634 18834 37634 18802 37634 18802 37635 18834 37635 18833 37635 18802 37636 18833 37636 18804 37636 18804 37637 18833 37637 18803 37637 18804 37638 18803 37638 18785 37638 18785 37639 18803 37639 18805 37639 18785 37640 18805 37640 18806 37640 18806 37641 18805 37641 18807 37641 18806 37642 18807 37642 18788 37642 18788 37643 18807 37643 18830 37643 18788 37644 18830 37644 18790 37644 18790 37645 18830 37645 18808 37645 18790 37646 18808 37646 18809 37646 18809 37647 18808 37647 18828 37647 18809 37648 18828 37648 18792 37648 18792 37649 18828 37649 18825 37649 18792 37650 18825 37650 18810 37650 18810 37651 18825 37651 18811 37651 18810 37652 18811 37652 18812 37652 18812 37653 18811 37653 18813 37653 18812 37654 18813 37654 18814 37654 18814 37655 18813 37655 18822 37655 18814 37656 18822 37656 18820 37656 19196 37657 19198 37657 18815 37657 18815 37658 19198 37658 18767 37658 18815 37659 18767 37659 18711 37659 18711 37660 18767 37660 18768 37660 18711 37661 18768 37661 18708 37661 18708 37662 18768 37662 18770 37662 18708 37663 18770 37663 18707 37663 18707 37664 18770 37664 18816 37664 18707 37665 18816 37665 18817 37665 18817 37666 18816 37666 18771 37666 18817 37667 18771 37667 18870 37667 18870 37668 18771 37668 18772 37668 18870 37669 18772 37669 18869 37669 18869 37670 18772 37670 18773 37670 18869 37671 18773 37671 18868 37671 18868 37672 18773 37672 18818 37672 18868 37673 18818 37673 18866 37673 18866 37674 18818 37674 18775 37674 18866 37675 18775 37675 18864 37675 18864 37676 18775 37676 18776 37676 18864 37677 18776 37677 18819 37677 18819 37678 18776 37678 18820 37678 18819 37679 18820 37679 18821 37679 18821 37680 18820 37680 18822 37680 18821 37681 18822 37681 18823 37681 18823 37682 18822 37682 18813 37682 18823 37683 18813 37683 18824 37683 18824 37684 18813 37684 18811 37684 18824 37685 18811 37685 18826 37685 18826 37686 18811 37686 18825 37686 18826 37687 18825 37687 18827 37687 18827 37688 18825 37688 18828 37688 18827 37689 18828 37689 18858 37689 18858 37690 18828 37690 18808 37690 18858 37691 18808 37691 18829 37691 18829 37692 18808 37692 18830 37692 18829 37693 18830 37693 18831 37693 18831 37694 18830 37694 18807 37694 18831 37695 18807 37695 18857 37695 18857 37696 18807 37696 18805 37696 18857 37697 18805 37697 18832 37697 18832 37698 18805 37698 18803 37698 18832 37699 18803 37699 18854 37699 18854 37700 18803 37700 18833 37700 18854 37701 18833 37701 18853 37701 18853 37702 18833 37702 18834 37702 18853 37703 18834 37703 18835 37703 18835 37704 18834 37704 18836 37704 18835 37705 18836 37705 18850 37705 18850 37706 18836 37706 18837 37706 18850 37707 18837 37707 18849 37707 18849 37708 18837 37708 18839 37708 18849 37709 18839 37709 18838 37709 18838 37710 18839 37710 18800 37710 18838 37711 18800 37711 18840 37711 18840 37712 18800 37712 18798 37712 18840 37713 18798 37713 18841 37713 18841 37714 18798 37714 18842 37714 18841 37715 18842 37715 18847 37715 18847 37716 18842 37716 18873 37716 18847 37717 18873 37717 18844 37717 18843 37718 18845 37718 18844 37718 18844 37719 18845 37719 18846 37719 18844 37720 18846 37720 18847 37720 18847 37721 18846 37721 18736 37721 18847 37722 18736 37722 18841 37722 18841 37723 18736 37723 18735 37723 18841 37724 18735 37724 18840 37724 18840 37725 18735 37725 18848 37725 18840 37726 18848 37726 18838 37726 18838 37727 18848 37727 18727 37727 18838 37728 18727 37728 18849 37728 18849 37729 18727 37729 18729 37729 18849 37730 18729 37730 18850 37730 18850 37731 18729 37731 18851 37731 18850 37732 18851 37732 18835 37732 18835 37733 18851 37733 18852 37733 18835 37734 18852 37734 18853 37734 18853 37735 18852 37735 18726 37735 18853 37736 18726 37736 18854 37736 18854 37737 18726 37737 18855 37737 18854 37738 18855 37738 18832 37738 18832 37739 18855 37739 18856 37739 18832 37740 18856 37740 18857 37740 18857 37741 18856 37741 18723 37741 18857 37742 18723 37742 18831 37742 18831 37743 18723 37743 18721 37743 18831 37744 18721 37744 18829 37744 18829 37745 18721 37745 18859 37745 18829 37746 18859 37746 18858 37746 18858 37747 18859 37747 18719 37747 18858 37748 18719 37748 18827 37748 18827 37749 18719 37749 18860 37749 18827 37750 18860 37750 18826 37750 18826 37751 18860 37751 18716 37751 18826 37752 18716 37752 18824 37752 18824 37753 18716 37753 18715 37753 18824 37754 18715 37754 18823 37754 18823 37755 18715 37755 18861 37755 18823 37756 18861 37756 18821 37756 18821 37757 18861 37757 18862 37757 18821 37758 18862 37758 18819 37758 18819 37759 18862 37759 18863 37759 18819 37760 18863 37760 18864 37760 18864 37761 18863 37761 18865 37761 18864 37762 18865 37762 18866 37762 18866 37763 18865 37763 18867 37763 18866 37764 18867 37764 18868 37764 18868 37765 18867 37765 18713 37765 18868 37766 18713 37766 18869 37766 18869 37767 18713 37767 18872 37767 18869 37768 18872 37768 18870 37768 18870 37769 18872 37769 18871 37769 18870 37770 18871 37770 19754 37770 19754 37771 18871 37771 18872 37771 19754 37772 18872 37772 19756 37772 19756 37773 18872 37773 19757 37773 18991 37774 18989 37774 18797 37774 18797 37775 18989 37775 18795 37775 18797 37776 18795 37776 18873 37776 18873 37777 18795 37777 18875 37777 18873 37778 18875 37778 18844 37778 18844 37779 18875 37779 19072 37779 18844 37780 19072 37780 19073 37780 18988 37781 18874 37781 18796 37781 18796 37782 18874 37782 19069 37782 18796 37783 19069 37783 18875 37783 18875 37784 19069 37784 19071 37784 18875 37785 19071 37785 18876 37785 18968 37786 18877 37786 18969 37786 18969 37787 18877 37787 18878 37787 18969 37788 18878 37788 18970 37788 18970 37789 18878 37789 18879 37789 18970 37790 18879 37790 18880 37790 18880 37791 18879 37791 18952 37791 18880 37792 18952 37792 18881 37792 18881 37793 18952 37793 18951 37793 18881 37794 18951 37794 18950 37794 18882 37795 19126 37795 18741 37795 18741 37796 19126 37796 18883 37796 18741 37797 18883 37797 18742 37797 18742 37798 18883 37798 18983 37798 18742 37799 18983 37799 18744 37799 18744 37800 18983 37800 18884 37800 18744 37801 18884 37801 18885 37801 18885 37802 18884 37802 18981 37802 18885 37803 18981 37803 18886 37803 18886 37804 18981 37804 18978 37804 18886 37805 18978 37805 18747 37805 18747 37806 18978 37806 18976 37806 18747 37807 18976 37807 18748 37807 18748 37808 18976 37808 18887 37808 18748 37809 18887 37809 18749 37809 18749 37810 18887 37810 18888 37810 18749 37811 18888 37811 18752 37811 18752 37812 18888 37812 18973 37812 18752 37813 18973 37813 18949 37813 19065 37814 19064 37814 18889 37814 18889 37815 19064 37815 18986 37815 18889 37816 18986 37816 18890 37816 18890 37817 18986 37817 18987 37817 18890 37818 18987 37818 18902 37818 18902 37819 18987 37819 18891 37819 18902 37820 18891 37820 18903 37820 18903 37821 18891 37821 18990 37821 18903 37822 18990 37822 18904 37822 18904 37823 18990 37823 18892 37823 18904 37824 18892 37824 18893 37824 18893 37825 18892 37825 18992 37825 18893 37826 18992 37826 18906 37826 18906 37827 18992 37827 18894 37827 18906 37828 18894 37828 18907 37828 18907 37829 18894 37829 18995 37829 18907 37830 18995 37830 18895 37830 18895 37831 18995 37831 18896 37831 18895 37832 18896 37832 18909 37832 18909 37833 18896 37833 18997 37833 18909 37834 18997 37834 18910 37834 18910 37835 18997 37835 18998 37835 18910 37836 18998 37836 18912 37836 18912 37837 18998 37837 18897 37837 18912 37838 18897 37838 18914 37838 18914 37839 18897 37839 19002 37839 18914 37840 19002 37840 18916 37840 18916 37841 19002 37841 19003 37841 18916 37842 19003 37842 18898 37842 18898 37843 19003 37843 19004 37843 18898 37844 19004 37844 18899 37844 19063 37845 19061 37845 18900 37845 18900 37846 19061 37846 18889 37846 18900 37847 18889 37847 18901 37847 18901 37848 18889 37848 18890 37848 18901 37849 18890 37849 18982 37849 18982 37850 18890 37850 18902 37850 18982 37851 18902 37851 18980 37851 18980 37852 18902 37852 18903 37852 18980 37853 18903 37853 18979 37853 18979 37854 18903 37854 18904 37854 18979 37855 18904 37855 18977 37855 18977 37856 18904 37856 18893 37856 18977 37857 18893 37857 18905 37857 18905 37858 18893 37858 18906 37858 18905 37859 18906 37859 18975 37859 18975 37860 18906 37860 18907 37860 18975 37861 18907 37861 18974 37861 18974 37862 18907 37862 18895 37862 18974 37863 18895 37863 18972 37863 18972 37864 18895 37864 18909 37864 18972 37865 18909 37865 18908 37865 18908 37866 18909 37866 18910 37866 18908 37867 18910 37867 18911 37867 18911 37868 18910 37868 18912 37868 18911 37869 18912 37869 18971 37869 18971 37870 18912 37870 18914 37870 18971 37871 18914 37871 18913 37871 18913 37872 18914 37872 18916 37872 18913 37873 18916 37873 18915 37873 18915 37874 18916 37874 18898 37874 18915 37875 18898 37875 18917 37875 18917 37876 18898 37876 18899 37876 18918 37877 18919 37877 18929 37877 18929 37878 18919 37878 17154 37878 18929 37879 17154 37879 18762 37879 18933 37880 18935 37880 18918 37880 18918 37881 18935 37881 18925 37881 18918 37882 18925 37882 18919 37882 18919 37883 18925 37883 18923 37883 18919 37884 18923 37884 17158 37884 17158 37885 18923 37885 17150 37885 18920 37886 19199 37886 18921 37886 18921 37887 19199 37887 18765 37887 18921 37888 18765 37888 18922 37888 18922 37889 18765 37889 18923 37889 18922 37890 18923 37890 18924 37890 18924 37891 18923 37891 18925 37891 18924 37892 18925 37892 18937 37892 18937 37893 18925 37893 18935 37893 18956 37894 18957 37894 18754 37894 18754 37895 18957 37895 18926 37895 18754 37896 18926 37896 18756 37896 18756 37897 18926 37897 18959 37897 18756 37898 18959 37898 18761 37898 18761 37899 18959 37899 18961 37899 18761 37900 18961 37900 18927 37900 18927 37901 18961 37901 18962 37901 18927 37902 18962 37902 18759 37902 18759 37903 18962 37903 18963 37903 18759 37904 18963 37904 18758 37904 18758 37905 18963 37905 18928 37905 18758 37906 18928 37906 18930 37906 18930 37907 18928 37907 18931 37907 17146 37908 18930 37908 18929 37908 18929 37909 18930 37909 18931 37909 18929 37910 18931 37910 18918 37910 18918 37911 18931 37911 18932 37911 18918 37912 18932 37912 18933 37912 18932 37913 18966 37913 18933 37913 18933 37914 18966 37914 18934 37914 18933 37915 18934 37915 18935 37915 18935 37916 18934 37916 18936 37916 18935 37917 18936 37917 18937 37917 18937 37918 18936 37918 18938 37918 18937 37919 18938 37919 18924 37919 18924 37920 18938 37920 18939 37920 18924 37921 18939 37921 18922 37921 18922 37922 18939 37922 19017 37922 18922 37923 19017 37923 18921 37923 18921 37924 19017 37924 18940 37924 18921 37925 18940 37925 18920 37925 18920 37926 18940 37926 19200 37926 19010 37927 18965 37927 19009 37927 19009 37928 18965 37928 18942 37928 19009 37929 18942 37929 18941 37929 18941 37930 18942 37930 18964 37930 18941 37931 18964 37931 18943 37931 18943 37932 18964 37932 18944 37932 18943 37933 18944 37933 18945 37933 18945 37934 18944 37934 18946 37934 18945 37935 18946 37935 19007 37935 19007 37936 18946 37936 18960 37936 19007 37937 18960 37937 19006 37937 19006 37938 18960 37938 18947 37938 19006 37939 18947 37939 18948 37939 18948 37940 18947 37940 18958 37940 18948 37941 18958 37941 18967 37941 18973 37942 18950 37942 18949 37942 18949 37943 18950 37943 18951 37943 18949 37944 18951 37944 18953 37944 18953 37945 18951 37945 18952 37945 18953 37946 18952 37946 17232 37946 17232 37947 18952 37947 18879 37947 17232 37948 18879 37948 18954 37948 18954 37949 18879 37949 18878 37949 18954 37950 18878 37950 18955 37950 18955 37951 18878 37951 18877 37951 18955 37952 18877 37952 18956 37952 18956 37953 18877 37953 18968 37953 18956 37954 18968 37954 18957 37954 18957 37955 18968 37955 18958 37955 18957 37956 18958 37956 18926 37956 18926 37957 18958 37957 18947 37957 18926 37958 18947 37958 18959 37958 18959 37959 18947 37959 18960 37959 18959 37960 18960 37960 18961 37960 18961 37961 18960 37961 18946 37961 18961 37962 18946 37962 18962 37962 18962 37963 18946 37963 18944 37963 18962 37964 18944 37964 18963 37964 18963 37965 18944 37965 18964 37965 18963 37966 18964 37966 18928 37966 18928 37967 18964 37967 18942 37967 18928 37968 18942 37968 18931 37968 18931 37969 18942 37969 18965 37969 18931 37970 18965 37970 18932 37970 18932 37971 18965 37971 19010 37971 18932 37972 19010 37972 18966 37972 19004 37973 18967 37973 18899 37973 18899 37974 18967 37974 18958 37974 18899 37975 18958 37975 18917 37975 18917 37976 18958 37976 18968 37976 18917 37977 18968 37977 18915 37977 18915 37978 18968 37978 18969 37978 18915 37979 18969 37979 18913 37979 18913 37980 18969 37980 18970 37980 18913 37981 18970 37981 18971 37981 18971 37982 18970 37982 18880 37982 18971 37983 18880 37983 18911 37983 18911 37984 18880 37984 18881 37984 18911 37985 18881 37985 18908 37985 18908 37986 18881 37986 18950 37986 18908 37987 18950 37987 18972 37987 18972 37988 18950 37988 18973 37988 18972 37989 18973 37989 18974 37989 18974 37990 18973 37990 18888 37990 18974 37991 18888 37991 18975 37991 18975 37992 18888 37992 18887 37992 18975 37993 18887 37993 18905 37993 18905 37994 18887 37994 18976 37994 18905 37995 18976 37995 18977 37995 18977 37996 18976 37996 18978 37996 18977 37997 18978 37997 18979 37997 18979 37998 18978 37998 18981 37998 18979 37999 18981 37999 18980 37999 18980 38000 18981 38000 18884 38000 18980 38001 18884 38001 18982 38001 18982 38002 18884 38002 18983 38002 18982 38003 18983 38003 18901 38003 18901 38004 18983 38004 18883 38004 18901 38005 18883 38005 18900 38005 18900 38006 18883 38006 18984 38006 18900 38007 18984 38007 18985 38007 18985 38008 18984 38008 19126 38008 19078 38009 19066 38009 18874 38009 18874 38010 19066 38010 19068 38010 18874 38011 19068 38011 19069 38011 19064 38012 19078 38012 18986 38012 18986 38013 19078 38013 18874 38013 18986 38014 18874 38014 18987 38014 18987 38015 18874 38015 18988 38015 18987 38016 18988 38016 18891 38016 18891 38017 18988 38017 18989 38017 18891 38018 18989 38018 18990 38018 18990 38019 18989 38019 18991 38019 18990 38020 18991 38020 18892 38020 18892 38021 18991 38021 18780 38021 18892 38022 18780 38022 18992 38022 18992 38023 18780 38023 18993 38023 18992 38024 18993 38024 18894 38024 18894 38025 18993 38025 18994 38025 18894 38026 18994 38026 18995 38026 18995 38027 18994 38027 18783 38027 18995 38028 18783 38028 18896 38028 18896 38029 18783 38029 18996 38029 18896 38030 18996 38030 18997 38030 18997 38031 18996 38031 18999 38031 18997 38032 18999 38032 18998 38032 18998 38033 18999 38033 19000 38033 18998 38034 19000 38034 18897 38034 18897 38035 19000 38035 19001 38035 18897 38036 19001 38036 19002 38036 19002 38037 19001 38037 18786 38037 19002 38038 18786 38038 19003 38038 19003 38039 18786 38039 18787 38039 19003 38040 18787 38040 19004 38040 19004 38041 18787 38041 19005 38041 19004 38042 19005 38042 18967 38042 18967 38043 19005 38043 18789 38043 18967 38044 18789 38044 18948 38044 18948 38045 18789 38045 18791 38045 18948 38046 18791 38046 19006 38046 19006 38047 18791 38047 18793 38047 19006 38048 18793 38048 19007 38048 19007 38049 18793 38049 18794 38049 19007 38050 18794 38050 18945 38050 18945 38051 18794 38051 18778 38051 18945 38052 18778 38052 18943 38052 18943 38053 18778 38053 19008 38053 18943 38054 19008 38054 18941 38054 18941 38055 19008 38055 18777 38055 18941 38056 18777 38056 19009 38056 19009 38057 18777 38057 19011 38057 19009 38058 19011 38058 19010 38058 19010 38059 19011 38059 19012 38059 19010 38060 19012 38060 18966 38060 18966 38061 19012 38061 18774 38061 18966 38062 18774 38062 18934 38062 18934 38063 18774 38063 19013 38063 18934 38064 19013 38064 18936 38064 18936 38065 19013 38065 19014 38065 18936 38066 19014 38066 18938 38066 18938 38067 19014 38067 19015 38067 18938 38068 19015 38068 18939 38068 18939 38069 19015 38069 19016 38069 18939 38070 19016 38070 19017 38070 19017 38071 19016 38071 18769 38071 19017 38072 18769 38072 18940 38072 18940 38073 18769 38073 18766 38073 18940 38074 18766 38074 19201 38074 19201 38075 18766 38075 19203 38075 19152 38076 19018 38076 19153 38076 19175 38077 19038 38077 19116 38077 19074 38078 19019 38078 19100 38078 19062 38079 19020 38079 19018 38079 19788 38080 19188 38080 19021 38080 19188 38081 19788 38081 19022 38081 19023 38082 18740 38082 19024 38082 19024 38083 18740 38083 18739 38083 19790 38084 19091 38084 19025 38084 19025 38085 19091 38085 19026 38085 19025 38086 19026 38086 19090 38086 19027 38087 19028 38087 19088 38087 19088 38088 19028 38088 19077 38088 19088 38089 19077 38089 19090 38089 19090 38090 19077 38090 19784 38090 19090 38091 19784 38091 19025 38091 19025 38092 19784 38092 19029 38092 19025 38093 19029 38093 19790 38093 19134 38094 19787 38094 19030 38094 19160 38095 19783 38095 19031 38095 19031 38096 19783 38096 19781 38096 19031 38097 19781 38097 19164 38097 19032 38098 19165 38098 19774 38098 19103 38099 19032 38099 19104 38099 19104 38100 19032 38100 19774 38100 19104 38101 19774 38101 19105 38101 19105 38102 19774 38102 19776 38102 19105 38103 19776 38103 19106 38103 19118 38104 19777 38104 19033 38104 19116 38105 18619 38105 19117 38105 19117 38106 18619 38106 18620 38106 19117 38107 18620 38107 19119 38107 19036 38108 18618 38108 19037 38108 19037 38109 18618 38109 19034 38109 19172 38110 19036 38110 19035 38110 19035 38111 19036 38111 19037 38111 19035 38112 19037 38112 19038 38112 19038 38113 19037 38113 19034 38113 19038 38114 19034 38114 19116 38114 19116 38115 19034 38115 19039 38115 19116 38116 19039 38116 18619 38116 19040 38117 19041 38117 18617 38117 18617 38118 19041 38118 19042 38118 19042 38119 19041 38119 19043 38119 19043 38120 19041 38120 19044 38120 19043 38121 19044 38121 19045 38121 19046 38122 18611 38122 19047 38122 19047 38123 18611 38123 19048 38123 18612 38124 19046 38124 19113 38124 19113 38125 19046 38125 19047 38125 19113 38126 19047 38126 19049 38126 19049 38127 19047 38127 19048 38127 19049 38128 19048 38128 19050 38128 19170 38129 19051 38129 19109 38129 19109 38130 19051 38130 19052 38130 19109 38131 19052 38131 18613 38131 19112 38132 19113 38132 19053 38132 19057 38133 17249 38133 19125 38133 19125 38134 17249 38134 19054 38134 19125 38135 19054 38135 19056 38135 19056 38136 19054 38136 19055 38136 19056 38137 19055 38137 19154 38137 18882 38138 19058 38138 19057 38138 19057 38139 19058 38139 19059 38139 19057 38140 19059 38140 17249 38140 19093 38141 19065 38141 19060 38141 19060 38142 19065 38142 19061 38142 19060 38143 19061 38143 19062 38143 19062 38144 19061 38144 19063 38144 19062 38145 19063 38145 19020 38145 19020 38146 19063 38146 18985 38146 19020 38147 18985 38147 19126 38147 19079 38148 19078 38148 19093 38148 19093 38149 19078 38149 19064 38149 19093 38150 19064 38150 19065 38150 19066 38151 19067 38151 19068 38151 19068 38152 19067 38152 19080 38152 19068 38153 19080 38153 19069 38153 19069 38154 19080 38154 19097 38154 19069 38155 19097 38155 19071 38155 19100 38156 19019 38156 19070 38156 19071 38157 19097 38157 18876 38157 18876 38158 19097 38158 19070 38158 18876 38159 19070 38159 19072 38159 19072 38160 19070 38160 19019 38160 19072 38161 19019 38161 19073 38161 19073 38162 19019 38162 18843 38162 18843 38163 19019 38163 19074 38163 18843 38164 19074 38164 18845 38164 18739 38165 18733 38165 19024 38165 19024 38166 18733 38166 19075 38166 19024 38167 19075 38167 19187 38167 19132 38168 19076 38168 19134 38168 19131 38169 19132 38169 19085 38169 19085 38170 19132 38170 19134 38170 19085 38171 19134 38171 19027 38171 19027 38172 19134 38172 19030 38172 19027 38173 19030 38173 19028 38173 19028 38174 19030 38174 19786 38174 19028 38175 19786 38175 19077 38175 19066 38176 19078 38176 19067 38176 19067 38177 19078 38177 19079 38177 19067 38178 19079 38178 19080 38178 19080 38179 19079 38179 19095 38179 19080 38180 19095 38180 19097 38180 19099 38181 19098 38181 19081 38181 19081 38182 19098 38182 19096 38182 19081 38183 19096 38183 19083 38183 19083 38184 19096 38184 19082 38184 19083 38185 19082 38185 19149 38185 19149 38186 19082 38186 19094 38186 19183 38187 19131 38187 19084 38187 19084 38188 19131 38188 19085 38188 19084 38189 19085 38189 19086 38189 19086 38190 19085 38190 19027 38190 19086 38191 19027 38191 19087 38191 19087 38192 19027 38192 19088 38192 19087 38193 19088 38193 19186 38193 19186 38194 19088 38194 19090 38194 19186 38195 19090 38195 19089 38195 19089 38196 19090 38196 19026 38196 19089 38197 19026 38197 19021 38197 19021 38198 19026 38198 19091 38198 19021 38199 19091 38199 19788 38199 19018 38200 19152 38200 19062 38200 19062 38201 19152 38201 19092 38201 19062 38202 19092 38202 19060 38202 19060 38203 19092 38203 19150 38203 19060 38204 19150 38204 19093 38204 19093 38205 19150 38205 19094 38205 19093 38206 19094 38206 19079 38206 19079 38207 19094 38207 19082 38207 19079 38208 19082 38208 19095 38208 19095 38209 19082 38209 19096 38209 19095 38210 19096 38210 19097 38210 19097 38211 19096 38211 19098 38211 19097 38212 19098 38212 19070 38212 19070 38213 19098 38213 19099 38213 19070 38214 19099 38214 19100 38214 19168 38215 19118 38215 19101 38215 19101 38216 19118 38216 19033 38216 19101 38217 19033 38217 19166 38217 19167 38218 19103 38218 19102 38218 19102 38219 19103 38219 19104 38219 19102 38220 19104 38220 19159 38220 19159 38221 19104 38221 19105 38221 19159 38222 19105 38222 19160 38222 19160 38223 19105 38223 19106 38223 19160 38224 19106 38224 19783 38224 19183 38225 19107 38225 19130 38225 19130 38226 19107 38226 19108 38226 19130 38227 19108 38227 19129 38227 18613 38228 19045 38228 19109 38228 19109 38229 19045 38229 19044 38229 19109 38230 19044 38230 19170 38230 19170 38231 19044 38231 19041 38231 19170 38232 19041 38232 19110 38232 19110 38233 19041 38233 19040 38233 19110 38234 19040 38234 19172 38234 19156 38235 19111 38235 19122 38235 19053 38236 19155 38236 19112 38236 19112 38237 19155 38237 19154 38237 19112 38238 19154 38238 19113 38238 19113 38239 19154 38239 19055 38239 19111 38240 19156 38240 19114 38240 19114 38241 19156 38241 19171 38241 19114 38242 19171 38242 19173 38242 19179 38243 19178 38243 19115 38243 19176 38244 19175 38244 19169 38244 19169 38245 19175 38245 19116 38245 19169 38246 19116 38246 19168 38246 19168 38247 19116 38247 19117 38247 19168 38248 19117 38248 19118 38248 19118 38249 19117 38249 19119 38249 19118 38250 19119 38250 19777 38250 19173 38251 19120 38251 19114 38251 19114 38252 19120 38252 19141 38252 19114 38253 19141 38253 19111 38253 19111 38254 19141 38254 19121 38254 19111 38255 19121 38255 19122 38255 19122 38256 19121 38256 19123 38256 19122 38257 19123 38257 19124 38257 19124 38258 19123 38258 19144 38258 19154 38259 19153 38259 19056 38259 19056 38260 19153 38260 19018 38260 19056 38261 19018 38261 19125 38261 19125 38262 19018 38262 19020 38262 19125 38263 19020 38263 19057 38263 19057 38264 19020 38264 19126 38264 19057 38265 19126 38265 18882 38265 19179 38266 19157 38266 19127 38266 19127 38267 19157 38267 19158 38267 19127 38268 19158 38268 19129 38268 19129 38269 19158 38269 19128 38269 19129 38270 19128 38270 19130 38270 19130 38271 19128 38271 19161 38271 19130 38272 19161 38272 19183 38272 19183 38273 19161 38273 19162 38273 19183 38274 19162 38274 19131 38274 19131 38275 19162 38275 19163 38275 19131 38276 19163 38276 19132 38276 19132 38277 19163 38277 19133 38277 19132 38278 19133 38278 19076 38278 19076 38279 19133 38279 19779 38279 19076 38280 19779 38280 19134 38280 19134 38281 19779 38281 19780 38281 19134 38282 19780 38282 19787 38282 19174 38283 19177 38283 19135 38283 19135 38284 19177 38284 19136 38284 19135 38285 19136 38285 19142 38285 19142 38286 19136 38286 19137 38286 19142 38287 19137 38287 19143 38287 19143 38288 19137 38288 19138 38288 19143 38289 19138 38289 19139 38289 19139 38290 19138 38290 19140 38290 19139 38291 19140 38291 19180 38291 19120 38292 19174 38292 19141 38292 19141 38293 19174 38293 19135 38293 19141 38294 19135 38294 19121 38294 19121 38295 19135 38295 19142 38295 19121 38296 19142 38296 19123 38296 19123 38297 19142 38297 19143 38297 19123 38298 19143 38298 19144 38298 19144 38299 19143 38299 19139 38299 19144 38300 19139 38300 19151 38300 19151 38301 19139 38301 19180 38301 19151 38302 19180 38302 19145 38302 19075 38303 18845 38303 19187 38303 19187 38304 18845 38304 19074 38304 19187 38305 19074 38305 19146 38305 19146 38306 19074 38306 19100 38306 19146 38307 19100 38307 19147 38307 19147 38308 19100 38308 19099 38308 19147 38309 19099 38309 19148 38309 19148 38310 19099 38310 19081 38310 19148 38311 19081 38311 19185 38311 19185 38312 19081 38312 19083 38312 19185 38313 19083 38313 19184 38313 19184 38314 19083 38314 19149 38314 19184 38315 19149 38315 19182 38315 19182 38316 19149 38316 19094 38316 19182 38317 19094 38317 19181 38317 19181 38318 19094 38318 19150 38318 19181 38319 19150 38319 19145 38319 19145 38320 19150 38320 19092 38320 19145 38321 19092 38321 19151 38321 19151 38322 19092 38322 19152 38322 19151 38323 19152 38323 19144 38323 19144 38324 19152 38324 19153 38324 19144 38325 19153 38325 19124 38325 19124 38326 19153 38326 19154 38326 19124 38327 19154 38327 19122 38327 19122 38328 19154 38328 19155 38328 19122 38329 19155 38329 19156 38329 19156 38330 19155 38330 19053 38330 19156 38331 19053 38331 19171 38331 19179 38332 19115 38332 19157 38332 19157 38333 19115 38333 19167 38333 19157 38334 19167 38334 19158 38334 19158 38335 19167 38335 19102 38335 19158 38336 19102 38336 19128 38336 19128 38337 19102 38337 19159 38337 19128 38338 19159 38338 19161 38338 19161 38339 19159 38339 19160 38339 19161 38340 19160 38340 19162 38340 19162 38341 19160 38341 19031 38341 19162 38342 19031 38342 19163 38342 19163 38343 19031 38343 19164 38343 19163 38344 19164 38344 19133 38344 19165 38345 19032 38345 19166 38345 19166 38346 19032 38346 19103 38346 19166 38347 19103 38347 19101 38347 19101 38348 19103 38348 19167 38348 19101 38349 19167 38349 19168 38349 19168 38350 19167 38350 19115 38350 19168 38351 19115 38351 19169 38351 19169 38352 19115 38352 19178 38352 19169 38353 19178 38353 19176 38353 19050 38354 19052 38354 19049 38354 19049 38355 19052 38355 19051 38355 19049 38356 19051 38356 19113 38356 19113 38357 19051 38357 19170 38357 19113 38358 19170 38358 19053 38358 19053 38359 19170 38359 19110 38359 19053 38360 19110 38360 19171 38360 19171 38361 19110 38361 19172 38361 19171 38362 19172 38362 19173 38362 19173 38363 19172 38363 19035 38363 19173 38364 19035 38364 19120 38364 19120 38365 19035 38365 19038 38365 19120 38366 19038 38366 19174 38366 19174 38367 19038 38367 19175 38367 19174 38368 19175 38368 19177 38368 19177 38369 19175 38369 19176 38369 19177 38370 19176 38370 19136 38370 19136 38371 19176 38371 19178 38371 19136 38372 19178 38372 19137 38372 19137 38373 19178 38373 19179 38373 19137 38374 19179 38374 19138 38374 19138 38375 19179 38375 19127 38375 19138 38376 19127 38376 19140 38376 19140 38377 19127 38377 19129 38377 19140 38378 19129 38378 19180 38378 19180 38379 19129 38379 19108 38379 19180 38380 19108 38380 19145 38380 19145 38381 19108 38381 19107 38381 19145 38382 19107 38382 19181 38382 19181 38383 19107 38383 19183 38383 19181 38384 19183 38384 19182 38384 19182 38385 19183 38385 19084 38385 19182 38386 19084 38386 19184 38386 19184 38387 19084 38387 19086 38387 19184 38388 19086 38388 19185 38388 19185 38389 19086 38389 19087 38389 19185 38390 19087 38390 19148 38390 19148 38391 19087 38391 19186 38391 19148 38392 19186 38392 19147 38392 19147 38393 19186 38393 19089 38393 19147 38394 19089 38394 19146 38394 19146 38395 19089 38395 19021 38395 19146 38396 19021 38396 19187 38396 19187 38397 19021 38397 19188 38397 19187 38398 19188 38398 19024 38398 19024 38399 19188 38399 19022 38399 19024 38400 19022 38400 19023 38400 19224 38401 19220 38401 19189 38401 19219 38402 19190 38402 19236 38402 18685 38403 18684 38403 19220 38403 19758 38404 19191 38404 19224 38404 19192 38405 19193 38405 19223 38405 19223 38406 19193 38406 19759 38406 19197 38407 19761 38407 19194 38407 19194 38408 19761 38408 19195 38408 19196 38409 18712 38409 19197 38409 19197 38410 19194 38410 19196 38410 19196 38411 19194 38411 19225 38411 19196 38412 19225 38412 19198 38412 19229 38413 19199 38413 18920 38413 19200 38414 19201 38414 19202 38414 19202 38415 19201 38415 19203 38415 19202 38416 19203 38416 19225 38416 19225 38417 19203 38417 19204 38417 19225 38418 19204 38418 19198 38418 17140 38419 19205 38419 19207 38419 19207 38420 19205 38420 19206 38420 19207 38421 19206 38421 17135 38421 19208 38422 19210 38422 17138 38422 19208 38423 19209 38423 19210 38423 19210 38424 19209 38424 18665 38424 19210 38425 18665 38425 17139 38425 18603 38426 19212 38426 19211 38426 19211 38427 19212 38427 17139 38427 19211 38428 17139 38428 19213 38428 19213 38429 17139 38429 18665 38429 18659 38430 19209 38430 19215 38430 19215 38431 19209 38431 19208 38431 19215 38432 19208 38432 19206 38432 19206 38433 19208 38433 17138 38433 19206 38434 17138 38434 17135 38434 18691 38435 18690 38435 19214 38435 19214 38436 18690 38436 18661 38436 19214 38437 18661 38437 19206 38437 19206 38438 18661 38438 18660 38438 19206 38439 18660 38439 19215 38439 19215 38440 18660 38440 18658 38440 19215 38441 18658 38441 18659 38441 19216 38442 19233 38442 19217 38442 19217 38443 19233 38443 19235 38443 19217 38444 19235 38444 19234 38444 18684 38445 19218 38445 19219 38445 19224 38446 19191 38446 19220 38446 19220 38447 19191 38447 18686 38447 19220 38448 18686 38448 18685 38448 19219 38449 19236 38449 19221 38449 19221 38450 19236 38450 19238 38450 19221 38451 19238 38451 19239 38451 18684 38452 19219 38452 19220 38452 19220 38453 19219 38453 19221 38453 19220 38454 19221 38454 19189 38454 19189 38455 19221 38455 19239 38455 19189 38456 19239 38456 19222 38456 19222 38457 19192 38457 19189 38457 19189 38458 19192 38458 19223 38458 19189 38459 19223 38459 19224 38459 19224 38460 19223 38460 19759 38460 19224 38461 19759 38461 19758 38461 19200 38462 19202 38462 19230 38462 19230 38463 19202 38463 19225 38463 19230 38464 19225 38464 19226 38464 19226 38465 19225 38465 19194 38465 19226 38466 19194 38466 19240 38466 19240 38467 19194 38467 19195 38467 19240 38468 19195 38468 19227 38468 18764 38469 18763 38469 17140 38469 17140 38470 18763 38470 19231 38470 17140 38471 19231 38471 19205 38471 19205 38472 19231 38472 19228 38472 19205 38473 19228 38473 19206 38473 19206 38474 19228 38474 19232 38474 19206 38475 19232 38475 19214 38475 19237 38476 19229 38476 19230 38476 19230 38477 19229 38477 18920 38477 19230 38478 18920 38478 19200 38478 18763 38479 19199 38479 19231 38479 19231 38480 19199 38480 19229 38480 19231 38481 19229 38481 19228 38481 19228 38482 19229 38482 19237 38482 19228 38483 19237 38483 19232 38483 19232 38484 19237 38484 19235 38484 19232 38485 19235 38485 19214 38485 19214 38486 19235 38486 19233 38486 19214 38487 19233 38487 18691 38487 18691 38488 19233 38488 19216 38488 19218 38489 18688 38489 19219 38489 19219 38490 18688 38490 19234 38490 19219 38491 19234 38491 19190 38491 19190 38492 19234 38492 19235 38492 19190 38493 19235 38493 19236 38493 19236 38494 19235 38494 19237 38494 19236 38495 19237 38495 19238 38495 19238 38496 19237 38496 19230 38496 19238 38497 19230 38497 19239 38497 19239 38498 19230 38498 19226 38498 19239 38499 19226 38499 19222 38499 19222 38500 19226 38500 19240 38500 19222 38501 19240 38501 19192 38501 19192 38502 19240 38502 19227 38502 19192 38503 19227 38503 19193 38503 19241 38504 17011 38504 17012 38504 19341 38505 19441 38505 19440 38505 19350 38506 14580 38506 19242 38506 20636 38507 19410 38507 20803 38507 19401 38508 14548 38508 20807 38508 20827 38509 20823 38509 20825 38509 19399 38510 19388 38510 16592 38510 19243 38511 19336 38511 17201 38511 19928 38512 19244 38512 19245 38512 19246 38513 19247 38513 16817 38513 20672 38514 20671 38514 19250 38514 20671 38515 20669 38515 19248 38515 19250 38516 20671 38516 19266 38516 19266 38517 20671 38517 19248 38517 19266 38518 19248 38518 19249 38518 20672 38519 19250 38519 20673 38519 20673 38520 19250 38520 17107 38520 20673 38521 17107 38521 19251 38521 19251 38522 17107 38522 17106 38522 19251 38523 17106 38523 19252 38523 19252 38524 17106 38524 19254 38524 19252 38525 19254 38525 19253 38525 19253 38526 19254 38526 19255 38526 19253 38527 19255 38527 20676 38527 20676 38528 19255 38528 19256 38528 20676 38529 19256 38529 20677 38529 20677 38530 19256 38530 17087 38530 20677 38531 17087 38531 20678 38531 20678 38532 17087 38532 17094 38532 20678 38533 17094 38533 19257 38533 19257 38534 17094 38534 19258 38534 19257 38535 19258 38535 20668 38535 20668 38536 19258 38536 19259 38536 20668 38537 19259 38537 20669 38537 20669 38538 19259 38538 17097 38538 20669 38539 17097 38539 19248 38539 19261 38540 19264 38540 19262 38540 19272 38541 17011 38541 20666 38541 20666 38542 17011 38542 19241 38542 20666 38543 19241 38543 20655 38543 20655 38544 19241 38544 17029 38544 20655 38545 17029 38545 20656 38545 20656 38546 17029 38546 17030 38546 20656 38547 17030 38547 20657 38547 17121 38548 19260 38548 17122 38548 17122 38549 19260 38549 20663 38549 17122 38550 20663 38550 19268 38550 19261 38551 19262 38551 19263 38551 19263 38552 19262 38552 17032 38552 19263 38553 17032 38553 17034 38553 19261 38554 19260 38554 19264 38554 19264 38555 19260 38555 17121 38555 19264 38556 17121 38556 17061 38556 17061 38557 17121 38557 19265 38557 17061 38558 19265 38558 19267 38558 19267 38559 19265 38559 19266 38559 19267 38560 19266 38560 17075 38560 17075 38561 19266 38561 19249 38561 20663 38562 20661 38562 19268 38562 19268 38563 20661 38563 20659 38563 19268 38564 20659 38564 20657 38564 17034 38565 19269 38565 19263 38565 19263 38566 19269 38566 17009 38566 19263 38567 17009 38567 19270 38567 19270 38568 17009 38568 17010 38568 19270 38569 17010 38569 19272 38569 19272 38570 17010 38570 19271 38570 19272 38571 19271 38571 17011 38571 17030 38572 19273 38572 19274 38572 20657 38573 17030 38573 19268 38573 19268 38574 17030 38574 19274 38574 19268 38575 19274 38575 19275 38575 19275 38576 16982 38576 19268 38576 19268 38577 16982 38577 16999 38577 19268 38578 16999 38578 19276 38578 20627 38579 19289 38579 20628 38579 20628 38580 19289 38580 17123 38580 16999 38581 19277 38581 19276 38581 19276 38582 19277 38582 19278 38582 19276 38583 19278 38583 17123 38583 17123 38584 19278 38584 19279 38584 17123 38585 19279 38585 20628 38585 20628 38586 19279 38586 19281 38586 20627 38587 20626 38587 19289 38587 19289 38588 20626 38588 19280 38588 19289 38589 19280 38589 20624 38589 16963 38590 20629 38590 16967 38590 16967 38591 20629 38591 19281 38591 16967 38592 19281 38592 16972 38592 16972 38593 19281 38593 19279 38593 16950 38594 16952 38594 19282 38594 16963 38595 19283 38595 20629 38595 20629 38596 19283 38596 16948 38596 20629 38597 16948 38597 20631 38597 20631 38598 16948 38598 19284 38598 20631 38599 19284 38599 20632 38599 20632 38600 19284 38600 16945 38600 20632 38601 16945 38601 19285 38601 19285 38602 16945 38602 16944 38602 19285 38603 16944 38603 19286 38603 19286 38604 16944 38604 19287 38604 19286 38605 19287 38605 19288 38605 19288 38606 19287 38606 16943 38606 19288 38607 16943 38607 20624 38607 20624 38608 16943 38608 16950 38608 20624 38609 16950 38609 19289 38609 19289 38610 16950 38610 19282 38610 19282 38611 16927 38611 19289 38611 19289 38612 16927 38612 16925 38612 19289 38613 16925 38613 19293 38613 19293 38614 16925 38614 16924 38614 16892 38615 16894 38615 20613 38615 20613 38616 16894 38616 20614 38616 19290 38617 17125 38617 16914 38617 16914 38618 17125 38618 17124 38618 16914 38619 17124 38619 19291 38619 19291 38620 17124 38620 19293 38620 19291 38621 19293 38621 19292 38621 19292 38622 19293 38622 16924 38622 16894 38623 16855 38623 20614 38623 20614 38624 16855 38624 16858 38624 20614 38625 16858 38625 19294 38625 19294 38626 16858 38626 19305 38626 19294 38627 19305 38627 19295 38627 19295 38628 19305 38628 17125 38628 19295 38629 17125 38629 20616 38629 20616 38630 17125 38630 19290 38630 20616 38631 19290 38631 20617 38631 16892 38632 20613 38632 16891 38632 16891 38633 20613 38633 19296 38633 16891 38634 19296 38634 19297 38634 19297 38635 19296 38635 19299 38635 19297 38636 19299 38636 19298 38636 19298 38637 19299 38637 19300 38637 19298 38638 19300 38638 16888 38638 16888 38639 19300 38639 20620 38639 16888 38640 20620 38640 16887 38640 16887 38641 20620 38641 19301 38641 16887 38642 19301 38642 16897 38642 16897 38643 19301 38643 19302 38643 16897 38644 19302 38644 16896 38644 19290 38645 19303 38645 20617 38645 20617 38646 19303 38646 19304 38646 20617 38647 19304 38647 19302 38647 19302 38648 19304 38648 16895 38648 19302 38649 16895 38649 16896 38649 19305 38650 19306 38650 17125 38650 17125 38651 19306 38651 16854 38651 17125 38652 16854 38652 19307 38652 19307 38653 16854 38653 19309 38653 19307 38654 19309 38654 19308 38654 19308 38655 19309 38655 16847 38655 19308 38656 16847 38656 19310 38656 19310 38657 16847 38657 16842 38657 19310 38658 16842 38658 19311 38658 19311 38659 19312 38659 19310 38659 19310 38660 19312 38660 19313 38660 19310 38661 19313 38661 19314 38661 19314 38662 19313 38662 20681 38662 19314 38663 20681 38663 19246 38663 19246 38664 16817 38664 19314 38664 19314 38665 16817 38665 16816 38665 19314 38666 16816 38666 19245 38666 19444 38667 19318 38667 19315 38667 19315 38668 19318 38668 19245 38668 19315 38669 19245 38669 20711 38669 20711 38670 19245 38670 16816 38670 19926 38671 19316 38671 19245 38671 19245 38672 19316 38672 19317 38672 19245 38673 19317 38673 19928 38673 19918 38674 19920 38674 19322 38674 19322 38675 19920 38675 19921 38675 19322 38676 19921 38676 19318 38676 19318 38677 19921 38677 19923 38677 19318 38678 19923 38678 19245 38678 19245 38679 19923 38679 19924 38679 19245 38680 19924 38680 19926 38680 19928 38681 19319 38681 19244 38681 19244 38682 19319 38682 19320 38682 19244 38683 19320 38683 19322 38683 19322 38684 19320 38684 19917 38684 19322 38685 19917 38685 19918 38685 19323 38686 17167 38686 19322 38686 19322 38687 17167 38687 17155 38687 19322 38688 17155 38688 19321 38688 19321 38689 17148 38689 19322 38689 19322 38690 17148 38690 17147 38690 19322 38691 17147 38691 19244 38691 19890 38692 17170 38692 19322 38692 19322 38693 17170 38693 17171 38693 19322 38694 17171 38694 19323 38694 19331 38695 19332 38695 19324 38695 19325 38696 19884 38696 19334 38696 19334 38697 19884 38697 19885 38697 19334 38698 19885 38698 19326 38698 19890 38699 19891 38699 17170 38699 17170 38700 19891 38700 19327 38700 17170 38701 19327 38701 19324 38701 19324 38702 19327 38702 19881 38702 19324 38703 19881 38703 19331 38703 19326 38704 19328 38704 19329 38704 19329 38705 19328 38705 19330 38705 19329 38706 19330 38706 20693 38706 20693 38707 19330 38707 19888 38707 20693 38708 19888 38708 20692 38708 19331 38709 19325 38709 19332 38709 19332 38710 19325 38710 19334 38710 19332 38711 19334 38711 19333 38711 19333 38712 19334 38712 17188 38712 19456 38713 19335 38713 17196 38713 17196 38714 19335 38714 17197 38714 17197 38715 19335 38715 17177 38715 17177 38716 19335 38716 19457 38716 17177 38717 19457 38717 19337 38717 19336 38718 19243 38718 19457 38718 19457 38719 19243 38719 17180 38719 19457 38720 17180 38720 19337 38720 19336 38721 19338 38721 17201 38721 17201 38722 19338 38722 19339 38722 17201 38723 19339 38723 19340 38723 19348 38724 19342 38724 19341 38724 19341 38725 19342 38725 19903 38725 19341 38726 19903 38726 19895 38726 19339 38727 19896 38727 19340 38727 19340 38728 19896 38728 19898 38728 19340 38729 19898 38729 19343 38729 19343 38730 19898 38730 19344 38730 19343 38731 19344 38731 19345 38731 19345 38732 19344 38732 19346 38732 19345 38733 19346 38733 14580 38733 14580 38734 19346 38734 19347 38734 14580 38735 19347 38735 19242 38735 19242 38736 19347 38736 19900 38736 19242 38737 19900 38737 19348 38737 19348 38738 19900 38738 19349 38738 19348 38739 19349 38739 19342 38739 19354 38740 19355 38740 16765 38740 16765 38741 19355 38741 17175 38741 16765 38742 17175 38742 19350 38742 19350 38743 17175 38743 19351 38743 19350 38744 19351 38744 14580 38744 14580 38745 19351 38745 17210 38745 14580 38746 17210 38746 19345 38746 19357 38747 19352 38747 19354 38747 19354 38748 19352 38748 19353 38748 19354 38749 19353 38749 19355 38749 19449 38750 17239 38750 16754 38750 16754 38751 17239 38751 19356 38751 16754 38752 19356 38752 19357 38752 19357 38753 19356 38753 17206 38753 19357 38754 17206 38754 19352 38754 19449 38755 19358 38755 17246 38755 17246 38756 19358 38756 19435 38756 17246 38757 19435 38757 19359 38757 19359 38758 19435 38758 19365 38758 19360 38759 19361 38759 17258 38759 17258 38760 19361 38760 20611 38760 17258 38761 20611 38761 19369 38761 19362 38762 16707 38762 20608 38762 20608 38763 16707 38763 19369 38763 20608 38764 19369 38764 19363 38764 19363 38765 19369 38765 20611 38765 19435 38766 19364 38766 19365 38766 19365 38767 19364 38767 16739 38767 19365 38768 16739 38768 17244 38768 17244 38769 16739 38769 16733 38769 20598 38770 19360 38770 16722 38770 16722 38771 19360 38771 17258 38771 16722 38772 17258 38772 19366 38772 19366 38773 17258 38773 17259 38773 19366 38774 17259 38774 16733 38774 16733 38775 17259 38775 19367 38775 16733 38776 19367 38776 17244 38776 16707 38777 19368 38777 19369 38777 19369 38778 19368 38778 19370 38778 19369 38779 19370 38779 17266 38779 14510 38780 19374 38780 19371 38780 19370 38781 16702 38781 17266 38781 17266 38782 16702 38782 16704 38782 17266 38783 16704 38783 16696 38783 19371 38784 19374 38784 19372 38784 19372 38785 19374 38785 17266 38785 19372 38786 17266 38786 20595 38786 20595 38787 17266 38787 16696 38787 20595 38788 16696 38788 19373 38788 16672 38789 19375 38789 19374 38789 19374 38790 19375 38790 19377 38790 19374 38791 19377 38791 17261 38791 17261 38792 19377 38792 19376 38792 19376 38793 19377 38793 19379 38793 19376 38794 19379 38794 19378 38794 19378 38795 19379 38795 16668 38795 19378 38796 16668 38796 19380 38796 17274 38797 19405 38797 16642 38797 17274 38798 16642 38798 19385 38798 19398 38799 19382 38799 19381 38799 19381 38800 19382 38800 16609 38800 16629 38801 19383 38801 16630 38801 16630 38802 19383 38802 17267 38802 16630 38803 17267 38803 19384 38803 19384 38804 17267 38804 19385 38804 19384 38805 19385 38805 16634 38805 16634 38806 19385 38806 16642 38806 16629 38807 16624 38807 19383 38807 19383 38808 16624 38808 16608 38808 19383 38809 16608 38809 19382 38809 19382 38810 16608 38810 19386 38810 19382 38811 19386 38811 16609 38811 19399 38812 19387 38812 19388 38812 19388 38813 19387 38813 19389 38813 19388 38814 19389 38814 19392 38814 19391 38815 19390 38815 19392 38815 19392 38816 19390 38816 16601 38816 19392 38817 16601 38817 19388 38817 19391 38818 19392 38818 16604 38818 16604 38819 19392 38819 19393 38819 16604 38820 19393 38820 20829 38820 20829 38821 19393 38821 19394 38821 20829 38822 19394 38822 20827 38822 19394 38823 19395 38823 20827 38823 20827 38824 19395 38824 19396 38824 20827 38825 19396 38825 20823 38825 20823 38826 19396 38826 19397 38826 20823 38827 19397 38827 20822 38827 20822 38828 19397 38828 20648 38828 20822 38829 20648 38829 19398 38829 19398 38830 20648 38830 20647 38830 19398 38831 20647 38831 19382 38831 19382 38832 20647 38832 20645 38832 19382 38833 20645 38833 19399 38833 19399 38834 20645 38834 19400 38834 19399 38835 19400 38835 19387 38835 14548 38836 19401 38836 19402 38836 19401 38837 20809 38837 19402 38837 19402 38838 20809 38838 19403 38838 19402 38839 19403 38839 17274 38839 17274 38840 19403 38840 19404 38840 17274 38841 19404 38841 19405 38841 20636 38842 20803 38842 20638 38842 20638 38843 20803 38843 19406 38843 20638 38844 19406 38844 19407 38844 19407 38845 19406 38845 20804 38845 19407 38846 20804 38846 19408 38846 19408 38847 20804 38847 20805 38847 19408 38848 20805 38848 19445 38848 19409 38849 16653 38849 19411 38849 19409 38850 19411 38850 19410 38850 19410 38851 19411 38851 19412 38851 19410 38852 19412 38852 20803 38852 20784 38853 16678 38853 14510 38853 14510 38854 16678 38854 16677 38854 14510 38855 16677 38855 19374 38855 19374 38856 16677 38856 16674 38856 19374 38857 16674 38857 16672 38857 19371 38858 20594 38858 14510 38858 14510 38859 20594 38859 20593 38859 14510 38860 20593 38860 20784 38860 20784 38861 20593 38861 19413 38861 20784 38862 19413 38862 19422 38862 19422 38863 19413 38863 20592 38863 19422 38864 20592 38864 19424 38864 19423 38865 19414 38865 19415 38865 19415 38866 19414 38866 19416 38866 19415 38867 19416 38867 19417 38867 19417 38868 19416 38868 19418 38868 19417 38869 19418 38869 19419 38869 19419 38870 19418 38870 19373 38870 19419 38871 19373 38871 19420 38871 19420 38872 19373 38872 16696 38872 20780 38873 20782 38873 19421 38873 19421 38874 20782 38874 19422 38874 19421 38875 19422 38875 19423 38875 19423 38876 19422 38876 19424 38876 19423 38877 19424 38877 19414 38877 20598 38878 16722 38878 20599 38878 20599 38879 16722 38879 19425 38879 20599 38880 19425 38880 19427 38880 19425 38881 19426 38881 19427 38881 19427 38882 19426 38882 20749 38882 19427 38883 20749 38883 20603 38883 20603 38884 20749 38884 19428 38884 20603 38885 19428 38885 19429 38885 19429 38886 19428 38886 20752 38886 19429 38887 20752 38887 20605 38887 20605 38888 20752 38888 19430 38888 20605 38889 19430 38889 20607 38889 20607 38890 19430 38890 19431 38890 20607 38891 19431 38891 20608 38891 20608 38892 19431 38892 19432 38892 20608 38893 19432 38893 19362 38893 19436 38894 16735 38894 19453 38894 19453 38895 16735 38895 19433 38895 19453 38896 19433 38896 19435 38896 19435 38897 19433 38897 19434 38897 19435 38898 19434 38898 19364 38898 19453 38899 19912 38899 19436 38899 19436 38900 19912 38900 19437 38900 19436 38901 19437 38901 19438 38901 19438 38902 19437 38902 19439 38902 19438 38903 19439 38903 20727 38903 20727 38904 19439 38904 16755 38904 16755 38905 19439 38905 19447 38905 16755 38906 19447 38906 19448 38906 19440 38907 19441 38907 16794 38907 16794 38908 19441 38908 14714 38908 16794 38909 14714 38909 16753 38909 16753 38910 14714 38910 16752 38910 16752 38911 14714 38911 19442 38911 16752 38912 19442 38912 16801 38912 19326 38913 19329 38913 19334 38913 19334 38914 19329 38914 16814 38914 19334 38915 16814 38915 19442 38915 19442 38916 16814 38916 19443 38916 19442 38917 19443 38917 16801 38917 19444 38918 20691 38918 19318 38918 19318 38919 20691 38919 20692 38919 19318 38920 20692 38920 19322 38920 19322 38921 20692 38921 19888 38921 19322 38922 19888 38922 19890 38922 20805 38923 20807 38923 19445 38923 19445 38924 20807 38924 14548 38924 19445 38925 14548 38925 20640 38925 20640 38926 14548 38926 19402 38926 16653 38927 19409 38927 19380 38927 19380 38928 19409 38928 19446 38928 19380 38929 19446 38929 19378 38929 19378 38930 19446 38930 20644 38930 19378 38931 20644 38931 17274 38931 17274 38932 20644 38932 20642 38932 17274 38933 20642 38933 19402 38933 19402 38934 20642 38934 20641 38934 19402 38935 20641 38935 20640 38935 19447 38936 19905 38936 19448 38936 19448 38937 19905 38937 19906 38937 19448 38938 19906 38938 16754 38938 16754 38939 19906 38939 19907 38939 16754 38940 19907 38940 19449 38940 19449 38941 19907 38941 19909 38941 19449 38942 19909 38942 19358 38942 19358 38943 19909 38943 19450 38943 19358 38944 19450 38944 19435 38944 19450 38945 19451 38945 19435 38945 19435 38946 19451 38946 19452 38946 19435 38947 19452 38947 19453 38947 19453 38948 19452 38948 19454 38948 19453 38949 19454 38949 19912 38949 17188 38950 19334 38950 19455 38950 19455 38951 19334 38951 19442 38951 19455 38952 19442 38952 19456 38952 19456 38953 19442 38953 14714 38953 19456 38954 14714 38954 19335 38954 19335 38955 14714 38955 19441 38955 19335 38956 19441 38956 19457 38956 19457 38957 19441 38957 19341 38957 19457 38958 19341 38958 19336 38958 19336 38959 19341 38959 19895 38959 19336 38960 19895 38960 19338 38960 19458 38961 17799 38961 16839 38961 19459 38962 17800 38962 19463 38962 19463 38963 17800 38963 19458 38963 19463 38964 19458 38964 19464 38964 19464 38965 19458 38965 16839 38965 19464 38966 16839 38966 16852 38966 16837 38967 16836 38967 17800 38967 17800 38968 19459 38968 16837 38968 16837 38969 19459 38969 19460 38969 16837 38970 19460 38970 17324 38970 19461 38971 19462 38971 19537 38971 19537 38972 19462 38972 17324 38972 19537 38973 17324 38973 19460 38973 19460 38974 19459 38974 19537 38974 19537 38975 19459 38975 19463 38975 19537 38976 19463 38976 19465 38976 19465 38977 19463 38977 19464 38977 19465 38978 19464 38978 16852 38978 16852 38979 16851 38979 19465 38979 19465 38980 16851 38980 19466 38980 19465 38981 19466 38981 19578 38981 15472 38982 19815 38982 19812 38982 15483 38983 19467 38983 19468 38983 19468 38984 19467 38984 15486 38984 19468 38985 15486 38985 19471 38985 19516 38986 19482 38986 19515 38986 19739 38987 19740 38987 19481 38987 15472 38988 19812 38988 15474 38988 19829 38989 19513 38989 19469 38989 19469 38990 19513 38990 19830 38990 19490 38991 19821 38991 19820 38991 19520 38992 19477 38992 19470 38992 19470 38993 19477 38993 15477 38993 19470 38994 15477 38994 15491 38994 15491 38995 15477 38995 19471 38995 15491 38996 19471 38996 15488 38996 15488 38997 19471 38997 15486 38997 20930 38998 17742 38998 20931 38998 20931 38999 17742 38999 17745 38999 20931 39000 17745 39000 19521 39000 19515 39001 19482 39001 19741 39001 19739 39002 19481 39002 19472 39002 15477 39003 19473 39003 15478 39003 15478 39004 19473 39004 17781 39004 15478 39005 17781 39005 15467 39005 15467 39006 17781 39006 19474 39006 15467 39007 19474 39007 19490 39007 19490 39008 19474 39008 17779 39008 19490 39009 17779 39009 19821 39009 19495 39010 19475 39010 19468 39010 19468 39011 19475 39011 19476 39011 19468 39012 19476 39012 15483 39012 19477 39013 19478 39013 15477 39013 15477 39014 19478 39014 20899 39014 15477 39015 20899 39015 19479 39015 19480 39016 19566 39016 19483 39016 19740 39017 19741 39017 19481 39017 19481 39018 19741 39018 19482 39018 19481 39019 19482 39019 19483 39019 19483 39020 19482 39020 19833 39020 19483 39021 19833 39021 19835 39021 19842 39022 19484 39022 19844 39022 19844 39023 19484 39023 19836 39023 19844 39024 19836 39024 19485 39024 19485 39025 19836 39025 19486 39025 19485 39026 19486 39026 19846 39026 19812 39027 19811 39027 15474 39027 15474 39028 19811 39028 19498 39028 15474 39029 19498 39029 19497 39029 19513 39030 19813 39030 19830 39030 19830 39031 19813 39031 19815 39031 19830 39032 19815 39032 19487 39032 19487 39033 19815 39033 15472 39033 19487 39034 15472 39034 19488 39034 19488 39035 15472 39035 15471 39035 19488 39036 15471 39036 19823 39036 19823 39037 15471 39037 15469 39037 19823 39038 15469 39038 19489 39038 19489 39039 15469 39039 19490 39039 19489 39040 19490 39040 19824 39040 19824 39041 19490 39041 19820 39041 19479 39042 19491 39042 15477 39042 15477 39043 19491 39043 19492 39043 15477 39044 19492 39044 19473 39044 17741 39045 19493 39045 19718 39045 19718 39046 19493 39046 19494 39046 19718 39047 19494 39047 19468 39047 19468 39048 19494 39048 17739 39048 19468 39049 17739 39049 19495 39049 19472 39050 19481 39050 19496 39050 19496 39051 19481 39051 19497 39051 19496 39052 19497 39052 19538 39052 19498 39053 19499 39053 19497 39053 19497 39054 19499 39054 20689 39054 19497 39055 20689 39055 19537 39055 19537 39056 20689 39056 19500 39056 19537 39057 19500 39057 19461 39057 19461 39058 19500 39058 17325 39058 19820 39059 19817 39059 19824 39059 19824 39060 19817 39060 17797 39060 19824 39061 17797 39061 19501 39061 19501 39062 17797 39062 19502 39062 19501 39063 19502 39063 19503 39063 19503 39064 19502 39064 19504 39064 19503 39065 19504 39065 19505 39065 19505 39066 19504 39066 19506 39066 19505 39067 19506 39067 19507 39067 19507 39068 19506 39068 17789 39068 19507 39069 17789 39069 19828 39069 19828 39070 17789 39070 19508 39070 19828 39071 19508 39071 19509 39071 19509 39072 19508 39072 17786 39072 19509 39073 17786 39073 19510 39073 19510 39074 17786 39074 19511 39074 19510 39075 19511 39075 19512 39075 19512 39076 19511 39076 17783 39076 19512 39077 17783 39077 19829 39077 19829 39078 17783 39078 17782 39078 19829 39079 17782 39079 19513 39079 15481 39080 15495 39080 15496 39080 17751 39081 17752 39081 19483 39081 19483 39082 17752 39082 17755 39082 19483 39083 17755 39083 19514 39083 19515 39084 19536 39084 19516 39084 19516 39085 19536 39085 19528 39085 19516 39086 19528 39086 19731 39086 19731 39087 19528 39087 19517 39087 15496 39088 15497 39088 15481 39088 15481 39089 15497 39089 19518 39089 15481 39090 19518 39090 19470 39090 19470 39091 19518 39091 19519 39091 19470 39092 19519 39092 19520 39092 19521 39093 19480 39093 20931 39093 20931 39094 19480 39094 19483 39094 20931 39095 19483 39095 19522 39095 19522 39096 19483 39096 19531 39096 19529 39097 19530 39097 17773 39097 17773 39098 19530 39098 19560 39098 17773 39099 19560 39099 19523 39099 19524 39100 17353 39100 19486 39100 19486 39101 17353 39101 19525 39101 19486 39102 19525 39102 19846 39102 17306 39103 19526 39103 19536 39103 19536 39104 19526 39104 19691 39104 19536 39105 19691 39105 19528 39105 19733 39106 19527 39106 19732 39106 19732 39107 19527 39107 19735 39107 19732 39108 19735 39108 19528 39108 19528 39109 19735 39109 19736 39109 19528 39110 19736 39110 19517 39110 19529 39111 17777 39111 19530 39111 19530 39112 17777 39112 19531 39112 19530 39113 19531 39113 19842 39113 19842 39114 19531 39114 19483 39114 19842 39115 19483 39115 19484 39115 19484 39116 19483 39116 19835 39116 17316 39117 19533 39117 19532 39117 19532 39118 19533 39118 17315 39118 19532 39119 17315 39119 17314 39119 19726 39120 19727 39120 19725 39120 19725 39121 19727 39121 19534 39121 19725 39122 19534 39122 17757 39122 17757 39123 19534 39123 19730 39123 17757 39124 19730 39124 19514 39124 19514 39125 19730 39125 19468 39125 19514 39126 19468 39126 19483 39126 19483 39127 19468 39127 19471 39127 17310 39128 19535 39128 19536 39128 19536 39129 19535 39129 17308 39129 19536 39130 17308 39130 17306 39130 19537 39131 19465 39131 19497 39131 19497 39132 19465 39132 19578 39132 19497 39133 19578 39133 19538 39133 19538 39134 19578 39134 19533 39134 19538 39135 19533 39135 17317 39135 17317 39136 19533 39136 17316 39136 19550 39137 19549 39137 17747 39137 17747 39138 19549 39138 19539 39138 17747 39139 19539 39139 17748 39139 17748 39140 19539 39140 19540 39140 17748 39141 19540 39141 19541 39141 19540 39142 17751 39142 19541 39142 19541 39143 17751 39143 19483 39143 19541 39144 19483 39144 19542 39144 19542 39145 19483 39145 19566 39145 19542 39146 19566 39146 19564 39146 17348 39147 17347 39147 17351 39147 19553 39148 19543 39148 19548 39148 17331 39149 19544 39149 19545 39149 19545 39150 19544 39150 19546 39150 19545 39151 19546 39151 19840 39151 19840 39152 19546 39152 17334 39152 19840 39153 17334 39153 19486 39153 19486 39154 17334 39154 19547 39154 19486 39155 19547 39155 19524 39155 19524 39156 19547 39156 17348 39156 19524 39157 17348 39157 17352 39157 17352 39158 17348 39158 17351 39158 19548 39159 19549 39159 19553 39159 19553 39160 19549 39160 19550 39160 19553 39161 19550 39161 17389 39161 17389 39162 19550 39162 19551 39162 17389 39163 19551 39163 17382 39163 17341 39164 19552 39164 17340 39164 17340 39165 19552 39165 19554 39165 17340 39166 19554 39166 19553 39166 19553 39167 19554 39167 19555 39167 19553 39168 19555 39168 19543 39168 17811 39169 17810 39169 19568 39169 19568 39170 17810 39170 19556 39170 19560 39171 17364 39171 17370 39171 17370 39172 17364 39172 17362 39172 17362 39173 17367 39173 17370 39173 17370 39174 17367 39174 17366 39174 17370 39175 17366 39175 17365 39175 19557 39176 17737 39176 17803 39176 17803 39177 17737 39177 19558 39177 17803 39178 19558 39178 19559 39178 17370 39179 17805 39179 19560 39179 19560 39180 17805 39180 17804 39180 19560 39181 17804 39181 19523 39181 19523 39182 17804 39182 17803 39182 19523 39183 17803 39183 17735 39183 17735 39184 17803 39184 19559 39184 17382 39185 17386 39185 17389 39185 17389 39186 17386 39186 19561 39186 17389 39187 19561 39187 19562 39187 19562 39188 19561 39188 17390 39188 19568 39189 19563 39189 19570 39189 19564 39190 19566 39190 19565 39190 19565 39191 19566 39191 19568 39191 19565 39192 19568 39192 19567 39192 19567 39193 19568 39193 19556 39193 19567 39194 19556 39194 19575 39194 17811 39195 19568 39195 19569 39195 19569 39196 19568 39196 19570 39196 19569 39197 19570 39197 19571 39197 19574 39198 17378 39198 19572 39198 19572 39199 19573 39199 19574 39199 19574 39200 19573 39200 17380 39200 19574 39201 17380 39201 19575 39201 19575 39202 17380 39202 19576 39202 19575 39203 19576 39203 19567 39203 19466 39204 19577 39204 19578 39204 19578 39205 19577 39205 19580 39205 19578 39206 19580 39206 19533 39206 19466 39207 16851 39207 19577 39207 19577 39208 16851 39208 19579 39208 19577 39209 19579 39209 19580 39209 19580 39210 19579 39210 19581 39210 19580 39211 19581 39211 19533 39211 19533 39212 19581 39212 17315 39212 18194 39213 18195 39213 19583 39213 18220 39214 18194 39214 19582 39214 19582 39215 18194 39215 19583 39215 19582 39216 19583 39216 19584 39216 19584 39217 19583 39217 16257 39217 19584 39218 16257 39218 16254 39218 19593 39219 19585 39219 19587 39219 19587 39220 19585 39220 19586 39220 19587 39221 19586 39221 19588 39221 19588 39222 19586 39222 19866 39222 19588 39223 19866 39223 19589 39223 19589 39224 19866 39224 19864 39224 19589 39225 19864 39225 20032 39225 20032 39226 19864 39226 19863 39226 20032 39227 19863 39227 20033 39227 20033 39228 19863 39228 19867 39228 20033 39229 19867 39229 19590 39229 19590 39230 19867 39230 19868 39230 19590 39231 19868 39231 19591 39231 19591 39232 19868 39232 17707 39232 19591 39233 17707 39233 20036 39233 20036 39234 17707 39234 18220 39234 20036 39235 18220 39235 20038 39235 20038 39236 18220 39236 19582 39236 16254 39237 16253 39237 19584 39237 19584 39238 16253 39238 19592 39238 19584 39239 19592 39239 19593 39239 19593 39240 19592 39240 17703 39240 19593 39241 17703 39241 19585 39241 19594 39242 19609 39242 20048 39242 20048 39243 19609 39243 17694 39243 20048 39244 17694 39244 20049 39244 20049 39245 17694 39245 17695 39245 20049 39246 17695 39246 19595 39246 19595 39247 17695 39247 17692 39247 19595 39248 17692 39248 20041 39248 20041 39249 17692 39249 17691 39249 20041 39250 17691 39250 20042 39250 20042 39251 17691 39251 17690 39251 20042 39252 17690 39252 19599 39252 18326 39253 18332 39253 16366 39253 20044 39254 19596 39254 19600 39254 19600 39255 19596 39255 19599 39255 17690 39256 19597 39256 19599 39256 19599 39257 19597 39257 19598 39257 19599 39258 19598 39258 19600 39258 19600 39259 19598 39259 19601 39259 19600 39260 19601 39260 19602 39260 19602 39261 16394 39261 19600 39261 19600 39262 16394 39262 16395 39262 19600 39263 16395 39263 19603 39263 19600 39264 18326 39264 20044 39264 20044 39265 18326 39265 16366 39265 20044 39266 16366 39266 19607 39266 19607 39267 16366 39267 19604 39267 19607 39268 19604 39268 19605 39268 19605 39269 19606 39269 19607 39269 19607 39270 19606 39270 16363 39270 19607 39271 16363 39271 19608 39271 19608 39272 16363 39272 16362 39272 19608 39273 16362 39273 20046 39273 20046 39274 16362 39274 17697 39274 20046 39275 17697 39275 19594 39275 19594 39276 17697 39276 17701 39276 19594 39277 17701 39277 19609 39277 16140 39278 18181 39278 19616 39278 19616 39279 19610 39279 19617 39279 19616 39280 19611 39280 19619 39280 19612 39281 16200 39281 19613 39281 19613 39282 16200 39282 19614 39282 19613 39283 19614 39283 16196 39283 19611 39284 19616 39284 19615 39284 19615 39285 19616 39285 19617 39285 19615 39286 19617 39286 19612 39286 19612 39287 19617 39287 19618 39287 19612 39288 19618 39288 16200 39288 16139 39289 19620 39289 19619 39289 19619 39290 19620 39290 19621 39290 19619 39291 19621 39291 19616 39291 19616 39292 19621 39292 16137 39292 19616 39293 16137 39293 16140 39293 16196 39294 17712 39294 19613 39294 19613 39295 17712 39295 17713 39295 19613 39296 17713 39296 20052 39296 20052 39297 17713 39297 19854 39297 20052 39298 19854 39298 19622 39298 19622 39299 19854 39299 19859 39299 19622 39300 19859 39300 19623 39300 19623 39301 19859 39301 19861 39301 19623 39302 19861 39302 20054 39302 20054 39303 19861 39303 19857 39303 20054 39304 19857 39304 20055 39304 20055 39305 19857 39305 19856 39305 20055 39306 19856 39306 19624 39306 19624 39307 19856 39307 19855 39307 19624 39308 19855 39308 19625 39308 19625 39309 19855 39309 19626 39309 19625 39310 19626 39310 19619 39310 19619 39311 19626 39311 19627 39311 19619 39312 19627 39312 16139 39312 15988 39313 19628 39313 19639 39313 19639 39314 19628 39314 16053 39314 16053 39315 19628 39315 15989 39315 16053 39316 15989 39316 18162 39316 20090 39317 19630 39317 19629 39317 19629 39318 19630 39318 19631 39318 19629 39319 19631 39319 20092 39319 20092 39320 19631 39320 19632 39320 20092 39321 19632 39321 19633 39321 19633 39322 19632 39322 17647 39322 19633 39323 17647 39323 20077 39323 20077 39324 17647 39324 19634 39324 20077 39325 19634 39325 20078 39325 20078 39326 19634 39326 19635 39326 20078 39327 19635 39327 20079 39327 20079 39328 19635 39328 17641 39328 20079 39329 17641 39329 20081 39329 20081 39330 17641 39330 15987 39330 19636 39331 16055 39331 20084 39331 20084 39332 16055 39332 16054 39332 20084 39333 16054 39333 20086 39333 20086 39334 16054 39334 19637 39334 20086 39335 19637 39335 20089 39335 20089 39336 19637 39336 17639 39336 20089 39337 17639 39337 20090 39337 20090 39338 17639 39338 17652 39338 20090 39339 17652 39339 19630 39339 15987 39340 19638 39340 20081 39340 20081 39341 19638 39341 15988 39341 20081 39342 15988 39342 20083 39342 20083 39343 15988 39343 19639 39343 20083 39344 19639 39344 20084 39344 20084 39345 19639 39345 19640 39345 20084 39346 19640 39346 19636 39346 19645 39347 20830 39347 19647 39347 19641 39348 16329 39348 18341 39348 18341 39349 16329 39349 16327 39349 18341 39350 16327 39350 19648 39350 16326 39351 19642 39351 19643 39351 19643 39352 19642 39352 16324 39352 19643 39353 16324 39353 20094 39353 20831 39354 19645 39354 19644 39354 19644 39355 19645 39355 19647 39355 19644 39356 19647 39356 19646 39356 19646 39357 19647 39357 18341 39357 19646 39358 18341 39358 19643 39358 19643 39359 18341 39359 19648 39359 19643 39360 19648 39360 16326 39360 16324 39361 17635 39361 20094 39361 20094 39362 17635 39362 19649 39362 20094 39363 19649 39363 19650 39363 19650 39364 19649 39364 19652 39364 19650 39365 19652 39365 19651 39365 19651 39366 19652 39366 19876 39366 19651 39367 19876 39367 19653 39367 19653 39368 19876 39368 19654 39368 19653 39369 19654 39369 20095 39369 20095 39370 19654 39370 19875 39370 20095 39371 19875 39371 20097 39371 20097 39372 19875 39372 19879 39372 20097 39373 19879 39373 19655 39373 19655 39374 19879 39374 19656 39374 19655 39375 19656 39375 19658 39375 19658 39376 19656 39376 19657 39376 19658 39377 19657 39377 19659 39377 19659 39378 19657 39378 20833 39378 19659 39379 20833 39379 19644 39379 19644 39380 20833 39380 19660 39380 19644 39381 19660 39381 20831 39381 15923 39382 15922 39382 19663 39382 19663 39383 15922 39383 15921 39383 19661 39384 15868 39384 19663 39384 19663 39385 15868 39385 15869 39385 19663 39386 15869 39386 18417 39386 19662 39387 19661 39387 19672 39387 19672 39388 19661 39388 19663 39388 19672 39389 19663 39389 20102 39389 20102 39390 19663 39390 15921 39390 20102 39391 15921 39391 19676 39391 19676 39392 15921 39392 19674 39392 19679 39393 17632 39393 20106 39393 20106 39394 17632 39394 17631 39394 20106 39395 17631 39395 20107 39395 20107 39396 17631 39396 17630 39396 20107 39397 17630 39397 19664 39397 19664 39398 17630 39398 19665 39398 19664 39399 19665 39399 19666 39399 19666 39400 19665 39400 19667 39400 19666 39401 19667 39401 19668 39401 19668 39402 19667 39402 19669 39402 19668 39403 19669 39403 19671 39403 19671 39404 19669 39404 19670 39404 19671 39405 19670 39405 19672 39405 19672 39406 19670 39406 19673 39406 19672 39407 19673 39407 19662 39407 19674 39408 19675 39408 19676 39408 19676 39409 19675 39409 15918 39409 19676 39410 15918 39410 19677 39410 19677 39411 15918 39411 17625 39411 19677 39412 17625 39412 19678 39412 19678 39413 17625 39413 19680 39413 19678 39414 19680 39414 19679 39414 19679 39415 19680 39415 17634 39415 19679 39416 17634 39416 17632 39416 20900 39417 19682 39417 20901 39417 20901 39418 19682 39418 15494 39418 20900 39419 19681 39419 19682 39419 19682 39420 19681 39420 20898 39420 19682 39421 20898 39421 20897 39421 19683 39422 19684 39422 19685 39422 19685 39423 19684 39423 19682 39423 19685 39424 19682 39424 20896 39424 20896 39425 19682 39425 20897 39425 19683 39426 19686 39426 19684 39426 19684 39427 19686 39427 19687 39427 19684 39428 19687 39428 19688 39428 15705 39429 19690 39429 19689 39429 19689 39430 19690 39430 17452 39430 19689 39431 17452 39431 15701 39431 16910 39432 16915 39432 17305 39432 17305 39433 16915 39433 19734 39433 19732 39434 19528 39434 19734 39434 19734 39435 19528 39435 19691 39435 19734 39436 19691 39436 17305 39436 19547 39437 17334 39437 17333 39437 16973 39438 19694 39438 16974 39438 16974 39439 19694 39439 19693 39439 19692 39440 19693 39440 17333 39440 17333 39441 19693 39441 19694 39441 17333 39442 19694 39442 19547 39442 19547 39443 19694 39443 17348 39443 19695 39444 19710 39444 20510 39444 20510 39445 19710 39445 19715 39445 19695 39446 19696 39446 16428 39446 19696 39447 20507 39447 16421 39447 16421 39448 20507 39448 16419 39448 16419 39449 20507 39449 19699 39449 16419 39450 19699 39450 19701 39450 17758 39451 19710 39451 16429 39451 16429 39452 19710 39452 19695 39452 16429 39453 19695 39453 16537 39453 16537 39454 19695 39454 16428 39454 16412 39455 16416 39455 20516 39455 20516 39456 16416 39456 16414 39456 20516 39457 16414 39457 19697 39457 16506 39458 20515 39458 16505 39458 16505 39459 20515 39459 19703 39459 16505 39460 19703 39460 16411 39460 16411 39461 19703 39461 19704 39461 16493 39462 16494 39462 20511 39462 20511 39463 16494 39463 20513 39463 16421 39464 16422 39464 19696 39464 19696 39465 16422 39465 16425 39465 19696 39466 16425 39466 16529 39466 16414 39467 16512 39467 19697 39467 19697 39468 16512 39468 19698 39468 19697 39469 19698 39469 19699 39469 19699 39470 19698 39470 19700 39470 19699 39471 19700 39471 19701 39471 16494 39472 19702 39472 20513 39472 20513 39473 19702 39473 16496 39473 20513 39474 16496 39474 19703 39474 19703 39475 16496 39475 16410 39475 19703 39476 16410 39476 19704 39476 17770 39477 19713 39477 19705 39477 19705 39478 19713 39478 19706 39478 16529 39479 16426 39479 19696 39479 19696 39480 16426 39480 16427 39480 19696 39481 16427 39481 16428 39481 16506 39482 16507 39482 20515 39482 20515 39483 16507 39483 19707 39483 20515 39484 19707 39484 20516 39484 20516 39485 19707 39485 19708 39485 20516 39486 19708 39486 16412 39486 20910 39487 20913 39487 19713 39487 19713 39488 20913 39488 19709 39488 19713 39489 19709 39489 19706 39489 19714 39490 19710 39490 16479 39490 16479 39491 19710 39491 16477 39491 16440 39492 19711 39492 19713 39492 19713 39493 19711 39493 17391 39493 17391 39494 17399 39494 19713 39494 19713 39495 17399 39495 19712 39495 19713 39496 19712 39496 20910 39496 16477 39497 19710 39497 16439 39497 16439 39498 19710 39498 17287 39498 16439 39499 17287 39499 17296 39499 17296 39500 17297 39500 16439 39500 16439 39501 17297 39501 17301 39501 16439 39502 17301 39502 16440 39502 16440 39503 17301 39503 17292 39503 16440 39504 17292 39504 19711 39504 19714 39505 16480 39505 19710 39505 19710 39506 16480 39506 16407 39506 19710 39507 16407 39507 19715 39507 19715 39508 16407 39508 16408 39508 19715 39509 16408 39509 20511 39509 20511 39510 16408 39510 19716 39510 20511 39511 19716 39511 16493 39511 19729 39512 16697 39512 19717 39512 19717 39513 19718 39513 19729 39513 19729 39514 19718 39514 19468 39514 19729 39515 19468 39515 19730 39515 16697 39516 19729 39516 19728 39516 17757 39517 19719 39517 19722 39517 16697 39518 19728 39518 19720 39518 19720 39519 19728 39519 19721 39519 19720 39520 19721 39520 16694 39520 16694 39521 19721 39521 19722 39521 16694 39522 19722 39522 19723 39522 19723 39523 19722 39523 19719 39523 19723 39524 19719 39524 19724 39524 17757 39525 19722 39525 19725 39525 19725 39526 19722 39526 19721 39526 19725 39527 19721 39527 19726 39527 19726 39528 19721 39528 19728 39528 19726 39529 19728 39529 19727 39529 19727 39530 19728 39530 19534 39530 19534 39531 19728 39531 19729 39531 19534 39532 19729 39532 19730 39532 19734 39533 16915 39533 16918 39533 16928 39534 19516 39534 19731 39534 16928 39535 19731 39535 16926 39535 19731 39536 19517 39536 16926 39536 16926 39537 19517 39537 19736 39537 16926 39538 19736 39538 16917 39538 19732 39539 19734 39539 19733 39539 19733 39540 19734 39540 16918 39540 19733 39541 16918 39541 19527 39541 19527 39542 16918 39542 16917 39542 19527 39543 16917 39543 19735 39543 19735 39544 16917 39544 19736 39544 19496 39545 19538 39545 16868 39545 16868 39546 16877 39546 19496 39546 19496 39547 16877 39547 19737 39547 19496 39548 19737 39548 19472 39548 19472 39549 19737 39549 19738 39549 19472 39550 19738 39550 19739 39550 19739 39551 19738 39551 16875 39551 19739 39552 16875 39552 19740 39552 19740 39553 16875 39553 16874 39553 19740 39554 16874 39554 19741 39554 19741 39555 16874 39555 16871 39555 19741 39556 16871 39556 19515 39556 19515 39557 16871 39557 17312 39557 19515 39558 17312 39558 19536 39558 19755 39559 18714 39559 19742 39559 19742 39560 18714 39560 19743 39560 19742 39561 19743 39561 20859 39561 20859 39562 19743 39562 19744 39562 20859 39563 19744 39563 20858 39563 20858 39564 19744 39564 19745 39564 20858 39565 19745 39565 20865 39565 20865 39566 19745 39566 19746 39566 20865 39567 19746 39567 20867 39567 20867 39568 19746 39568 19747 39568 20867 39569 19747 39569 20862 39569 20862 39570 19747 39570 18717 39570 20862 39571 18717 39571 20868 39571 20868 39572 18717 39572 19797 39572 20868 39573 19797 39573 20869 39573 19762 39574 18712 39574 19748 39574 19748 39575 18712 39575 18710 39575 19748 39576 18710 39576 19749 39576 19749 39577 18710 39577 18709 39577 19749 39578 18709 39578 20849 39578 20849 39579 18709 39579 19750 39579 20849 39580 19750 39580 20850 39580 20850 39581 19750 39581 19752 39581 20850 39582 19752 39582 19751 39582 19751 39583 19752 39583 19753 39583 19751 39584 19753 39584 20857 39584 20857 39585 19753 39585 19754 39585 20857 39586 19754 39586 20855 39586 20855 39587 19754 39587 19756 39587 20855 39588 19756 39588 19755 39588 19755 39589 19756 39589 19757 39589 19755 39590 19757 39590 18714 39590 19763 39591 19758 39591 19759 39591 19763 39592 19759 39592 19760 39592 19759 39593 19193 39593 19760 39593 19760 39594 19193 39594 19227 39594 19760 39595 19227 39595 20839 39595 20839 39596 19227 39596 19195 39596 20839 39597 19195 39597 20840 39597 20840 39598 19195 39598 19761 39598 20840 39599 19761 39599 19762 39599 19762 39600 19761 39600 19197 39600 19762 39601 19197 39601 18712 39601 19768 39602 18683 39602 19763 39602 19763 39603 18683 39603 19191 39603 19763 39604 19191 39604 19758 39604 20894 39605 19771 39605 20895 39605 20895 39606 19771 39606 18643 39606 20895 39607 18643 39607 19764 39607 19764 39608 18643 39608 19765 39608 19764 39609 19765 39609 19766 39609 19766 39610 19765 39610 18637 39610 19766 39611 18637 39611 19767 39611 19767 39612 18637 39612 18638 39612 19767 39613 18638 39613 19768 39613 19768 39614 18638 39614 18682 39614 19768 39615 18682 39615 18683 39615 20891 39616 18645 39616 19769 39616 19769 39617 18645 39617 18648 39617 19769 39618 18648 39618 20893 39618 20893 39619 18648 39619 19770 39619 20893 39620 19770 39620 20894 39620 20894 39621 19770 39621 18640 39621 20894 39622 18640 39622 19771 39622 19778 39623 18622 39623 19772 39623 19772 39624 18622 39624 19773 39624 19772 39625 19773 39625 20891 39625 20891 39626 19773 39626 18644 39626 20891 39627 18644 39627 18645 39627 19774 39628 19165 39628 19775 39628 19774 39629 19775 39629 19776 39629 19776 39630 19775 39630 19782 39630 19776 39631 19782 39631 19106 39631 19165 39632 19166 39632 19775 39632 19775 39633 19166 39633 19033 39633 19775 39634 19033 39634 20889 39634 20889 39635 19033 39635 19777 39635 20889 39636 19777 39636 19778 39636 19778 39637 19777 39637 19119 39637 19778 39638 19119 39638 18622 39638 19133 39639 20886 39639 19779 39639 19779 39640 20886 39640 19785 39640 19779 39641 19785 39641 19780 39641 19780 39642 19785 39642 19787 39642 19133 39643 19164 39643 20886 39643 20886 39644 19164 39644 19781 39644 20886 39645 19781 39645 19782 39645 19782 39646 19781 39646 19783 39646 19782 39647 19783 39647 19106 39647 20881 39648 19029 39648 19784 39648 20881 39649 19784 39649 20882 39649 19784 39650 19077 39650 20882 39650 20882 39651 19077 39651 19786 39651 20882 39652 19786 39652 19785 39652 19785 39653 19786 39653 19030 39653 19785 39654 19030 39654 19787 39654 20880 39655 19023 39655 19789 39655 19789 39656 19023 39656 19022 39656 19022 39657 19788 39657 19789 39657 19789 39658 19788 39658 19091 39658 19789 39659 19091 39659 20881 39659 20881 39660 19091 39660 19790 39660 20881 39661 19790 39661 19029 39661 19792 39662 19807 39662 19791 39662 19791 39663 18732 39663 19792 39663 19792 39664 18732 39664 18731 39664 19792 39665 18731 39665 19793 39665 19793 39666 18731 39666 19794 39666 19793 39667 19794 39667 20878 39667 20878 39668 19794 39668 18734 39668 20878 39669 18734 39669 19795 39669 19795 39670 18734 39670 18737 39670 19795 39671 18737 39671 19796 39671 19796 39672 18737 39672 18738 39672 19796 39673 18738 39673 20880 39673 20880 39674 18738 39674 18740 39674 20880 39675 18740 39675 19023 39675 19797 39676 18718 39676 20869 39676 20869 39677 18718 39677 19798 39677 20869 39678 19798 39678 19799 39678 19798 39679 18720 39679 19799 39679 19799 39680 18720 39680 19800 39680 19799 39681 19800 39681 20872 39681 20872 39682 19800 39682 18722 39682 20872 39683 18722 39683 19801 39683 19801 39684 18722 39684 18724 39684 19801 39685 18724 39685 19802 39685 19802 39686 18724 39686 18725 39686 19802 39687 18725 39687 19803 39687 19803 39688 18725 39688 19804 39688 19803 39689 19804 39689 19805 39689 19805 39690 19804 39690 19806 39690 19805 39691 19806 39691 20870 39691 20870 39692 19806 39692 18730 39692 20870 39693 18730 39693 19807 39693 19807 39694 18730 39694 18728 39694 19807 39695 18728 39695 19791 39695 16819 39696 19498 39696 20718 39696 20718 39697 19498 39697 19811 39697 20718 39698 19811 39698 19808 39698 19808 39699 19811 39699 19809 39699 19809 39700 19811 39700 19810 39700 19810 39701 19811 39701 19812 39701 19810 39702 19812 39702 20708 39702 20708 39703 19812 39703 19815 39703 20708 39704 19815 39704 20710 39704 19813 39705 19814 39705 19815 39705 19815 39706 19814 39706 19816 39706 19815 39707 19816 39707 20710 39707 19818 39708 19817 39708 19820 39708 19818 39709 19820 39709 19819 39709 19819 39710 19820 39710 19821 39710 19819 39711 19821 39711 20725 39711 20725 39712 19821 39712 17779 39712 20725 39713 17779 39713 20728 39713 19831 39714 19488 39714 19822 39714 19822 39715 19488 39715 19823 39715 19822 39716 19823 39716 17828 39716 17828 39717 19823 39717 19489 39717 17828 39718 19489 39718 17827 39718 17827 39719 19489 39719 19824 39719 17827 39720 19824 39720 17825 39720 17825 39721 19824 39721 19501 39721 17825 39722 19501 39722 17823 39722 17823 39723 19501 39723 19503 39723 17823 39724 19503 39724 19825 39724 19825 39725 19503 39725 19505 39725 19825 39726 19505 39726 19826 39726 19826 39727 19505 39727 19507 39727 19826 39728 19507 39728 18018 39728 18018 39729 19507 39729 19828 39729 18018 39730 19828 39730 19827 39730 19827 39731 19828 39731 19509 39731 19827 39732 19509 39732 18020 39732 18020 39733 19509 39733 19510 39733 18020 39734 19510 39734 18021 39734 18021 39735 19510 39735 19512 39735 18021 39736 19512 39736 17830 39736 17830 39737 19512 39737 19829 39737 17830 39738 19829 39738 17832 39738 17832 39739 19829 39739 19469 39739 17832 39740 19469 39740 17829 39740 17829 39741 19469 39741 19830 39741 17829 39742 19830 39742 17975 39742 17975 39743 19830 39743 19487 39743 17975 39744 19487 39744 19831 39744 19831 39745 19487 39745 19488 39745 19838 39746 17327 39746 19839 39746 19482 39747 19516 39747 16928 39747 16928 39748 19832 39748 19482 39748 19482 39749 19832 39749 16949 39749 19482 39750 16949 39750 19833 39750 19833 39751 16949 39751 19834 39751 19833 39752 19834 39752 19835 39752 19835 39753 19834 39753 16935 39753 19835 39754 16935 39754 19484 39754 19484 39755 16935 39755 19837 39755 19484 39756 19837 39756 19836 39756 19836 39757 19837 39757 19838 39757 19836 39758 19838 39758 19486 39758 19486 39759 19838 39759 19839 39759 19486 39760 19839 39760 19840 39760 17354 39761 16994 39761 19845 39761 17363 39762 17364 39762 19560 39762 19841 39763 17359 39763 17363 39763 17363 39764 19560 39764 19841 39764 19841 39765 19560 39765 19530 39765 19841 39766 19530 39766 17014 39766 17014 39767 19530 39767 19842 39767 17014 39768 19842 39768 17015 39768 17015 39769 19842 39769 19844 39769 17015 39770 19844 39770 19843 39770 19843 39771 19844 39771 19485 39771 19843 39772 19485 39772 17016 39772 17016 39773 19485 39773 19846 39773 17016 39774 19846 39774 19845 39774 19845 39775 19846 39775 19525 39775 19845 39776 19525 39776 17354 39776 19851 39777 17731 39777 16088 39777 16093 39778 17727 39778 19849 39778 19849 39779 17727 39779 17726 39779 19849 39780 17726 39780 19848 39780 16098 39781 16096 39781 17724 39781 17724 39782 16096 39782 16095 39782 17724 39783 16095 39783 19848 39783 19848 39784 16095 39784 19847 39784 19848 39785 19847 39785 19849 39785 16098 39786 17724 39786 16083 39786 16083 39787 17724 39787 17721 39787 16083 39788 17721 39788 16082 39788 16088 39789 19850 39789 19851 39789 19851 39790 19850 39790 16087 39790 19851 39791 16087 39791 19852 39791 19852 39792 16087 39792 16086 39792 19852 39793 16086 39793 17721 39793 17721 39794 16086 39794 19853 39794 17721 39795 19853 39795 16082 39795 19854 39796 17713 39796 16175 39796 16144 39797 19626 39797 16154 39797 16154 39798 19626 39798 19855 39798 16154 39799 19855 39799 16152 39799 16152 39800 19855 39800 16151 39800 16151 39801 19855 39801 19856 39801 16151 39802 19856 39802 16149 39802 16149 39803 19856 39803 16150 39803 16150 39804 19856 39804 19857 39804 16150 39805 19857 39805 19858 39805 19861 39806 16170 39806 19857 39806 19857 39807 16170 39807 16169 39807 19857 39808 16169 39808 19858 39808 16175 39809 16148 39809 19854 39809 19854 39810 16148 39810 19860 39810 19854 39811 19860 39811 19859 39811 19859 39812 19860 39812 16173 39812 19859 39813 16173 39813 19861 39813 19861 39814 16173 39814 19862 39814 19861 39815 19862 39815 16170 39815 16210 39816 19863 39816 16211 39816 16211 39817 19863 39817 19864 39817 16211 39818 19864 39818 16231 39818 16231 39819 19864 39819 19865 39819 19865 39820 19864 39820 19866 39820 19865 39821 19866 39821 16243 39821 19586 39822 19585 39822 16252 39822 16252 39823 16251 39823 19586 39823 19586 39824 16251 39824 16250 39824 19586 39825 16250 39825 19866 39825 19866 39826 16250 39826 16230 39826 19866 39827 16230 39827 16243 39827 17708 39828 17707 39828 19869 39828 19869 39829 17707 39829 19868 39829 19867 39830 19871 39830 19868 39830 19868 39831 19871 39831 16215 39831 19868 39832 16215 39832 19869 39832 16210 39833 19870 39833 19863 39833 19863 39834 19870 39834 16209 39834 19863 39835 16209 39835 19867 39835 19867 39836 16209 39836 16221 39836 19867 39837 16221 39837 19871 39837 16271 39838 19872 39838 19875 39838 19873 39839 19654 39839 16297 39839 16297 39840 19654 39840 19876 39840 16297 39841 19876 39841 16299 39841 19873 39842 19874 39842 19654 39842 19654 39843 19874 39843 16315 39843 19654 39844 16315 39844 19875 39844 19875 39845 16315 39845 16314 39845 19875 39846 16314 39846 16271 39846 19652 39847 19649 39847 16295 39847 16295 39848 16294 39848 19652 39848 19652 39849 16294 39849 16292 39849 19652 39850 16292 39850 19876 39850 19876 39851 16292 39851 16290 39851 19876 39852 16290 39852 16299 39852 17637 39853 19657 39853 19877 39853 19877 39854 19657 39854 19656 39854 19877 39855 19656 39855 19879 39855 19872 39856 19878 39856 19875 39856 19875 39857 19878 39857 16277 39857 19875 39858 16277 39858 19879 39858 19879 39859 16277 39859 19880 39859 19879 39860 19880 39860 19877 39860 19327 39861 19894 39861 19881 39861 19881 39862 19894 39862 19882 39862 19881 39863 19882 39863 19331 39863 19331 39864 19882 39864 20572 39864 19331 39865 20572 39865 19325 39865 19325 39866 20572 39866 19883 39866 19325 39867 19883 39867 19884 39867 19884 39868 19883 39868 19886 39868 19884 39869 19886 39869 19885 39869 19885 39870 19886 39870 19887 39870 19885 39871 19887 39871 19326 39871 19326 39872 19887 39872 20574 39872 19326 39873 20574 39873 19328 39873 19328 39874 20574 39874 20576 39874 19328 39875 20576 39875 19330 39875 19330 39876 20576 39876 20577 39876 19330 39877 20577 39877 19888 39877 19888 39878 20577 39878 19889 39878 19888 39879 19889 39879 19890 39879 19890 39880 19889 39880 19892 39880 19890 39881 19892 39881 19891 39881 19891 39882 19892 39882 19893 39882 19891 39883 19893 39883 19327 39883 19327 39884 19893 39884 19894 39884 19895 39885 20557 39885 19338 39885 19338 39886 20557 39886 20558 39886 19338 39887 20558 39887 19339 39887 19339 39888 20558 39888 19897 39888 19339 39889 19897 39889 19896 39889 19896 39890 19897 39890 19899 39890 19896 39891 19899 39891 19898 39891 19898 39892 19899 39892 20563 39892 19898 39893 20563 39893 19344 39893 19344 39894 20563 39894 20564 39894 19344 39895 20564 39895 19346 39895 19346 39896 20564 39896 20565 39896 19346 39897 20565 39897 19347 39897 19347 39898 20565 39898 19901 39898 19347 39899 19901 39899 19900 39899 19900 39900 19901 39900 20569 39900 19900 39901 20569 39901 19349 39901 19349 39902 20569 39902 19902 39902 19349 39903 19902 39903 19342 39903 19342 39904 19902 39904 20570 39904 19342 39905 20570 39905 19903 39905 19903 39906 20570 39906 20556 39906 19903 39907 20556 39907 19895 39907 19895 39908 20556 39908 20557 39908 19439 39909 19904 39909 19447 39909 19447 39910 19904 39910 20544 39910 19447 39911 20544 39911 19905 39911 19905 39912 20544 39912 20546 39912 19905 39913 20546 39913 19906 39913 19906 39914 20546 39914 19908 39914 19906 39915 19908 39915 19907 39915 19907 39916 19908 39916 19910 39916 19907 39917 19910 39917 19909 39917 19909 39918 19910 39918 20548 39918 19909 39919 20548 39919 19450 39919 19450 39920 20548 39920 20550 39920 19450 39921 20550 39921 19451 39921 19451 39922 20550 39922 20551 39922 19451 39923 20551 39923 19452 39923 19452 39924 20551 39924 19911 39924 19452 39925 19911 39925 19454 39925 19454 39926 19911 39926 20553 39926 19454 39927 20553 39927 19912 39927 19912 39928 20553 39928 20554 39928 19912 39929 20554 39929 19437 39929 19437 39930 20554 39930 19913 39930 19437 39931 19913 39931 19439 39931 19439 39932 19913 39932 19904 39932 19928 39933 19914 39933 19319 39933 19319 39934 19914 39934 19915 39934 19319 39935 19915 39935 19320 39935 19320 39936 19915 39936 19916 39936 19320 39937 19916 39937 19917 39937 19917 39938 19916 39938 20581 39938 19917 39939 20581 39939 19918 39939 19918 39940 20581 39940 20582 39940 19918 39941 20582 39941 19920 39941 19920 39942 20582 39942 19919 39942 19920 39943 19919 39943 19921 39943 19921 39944 19919 39944 19922 39944 19921 39945 19922 39945 19923 39945 19923 39946 19922 39946 20586 39946 19923 39947 20586 39947 19924 39947 19924 39948 20586 39948 19925 39948 19924 39949 19925 39949 19926 39949 19926 39950 19925 39950 20588 39950 19926 39951 20588 39951 19316 39951 19316 39952 20588 39952 19927 39952 19316 39953 19927 39953 19317 39953 19317 39954 19927 39954 19929 39954 19317 39955 19929 39955 19928 39955 19928 39956 19929 39956 19914 39956 19942 39957 20665 39957 19930 39957 19930 39958 20665 39958 19931 39958 19930 39959 19931 39959 17571 39959 17571 39960 19931 39960 19932 39960 17571 39961 19932 39961 17572 39961 17572 39962 19932 39962 19933 39962 17572 39963 19933 39963 17576 39963 17576 39964 19933 39964 20658 39964 17576 39965 20658 39965 19934 39965 19934 39966 20658 39966 20660 39966 19934 39967 20660 39967 19935 39967 19935 39968 20660 39968 20662 39968 19935 39969 20662 39969 17578 39969 17578 39970 20662 39970 19936 39970 17578 39971 19936 39971 19937 39971 19937 39972 19936 39972 20664 39972 19937 39973 20664 39973 19938 39973 19938 39974 20664 39974 19939 39974 19938 39975 19939 39975 17567 39975 17567 39976 19939 39976 19940 39976 17567 39977 19940 39977 19941 39977 19941 39978 19940 39978 19943 39978 19941 39979 19943 39979 19942 39979 19942 39980 19943 39980 20665 39980 17554 39981 19944 39981 19945 39981 19945 39982 19944 39982 20590 39982 19945 39983 20590 39983 19946 39983 19946 39984 20590 39984 19947 39984 19946 39985 19947 39985 17558 39985 17558 39986 19947 39986 19948 39986 17558 39987 19948 39987 17559 39987 17559 39988 19948 39988 19949 39988 17559 39989 19949 39989 19950 39989 19950 39990 19949 39990 20591 39990 19950 39991 20591 39991 19951 39991 19951 39992 20591 39992 19952 39992 19951 39993 19952 39993 19953 39993 19953 39994 19952 39994 19954 39994 19953 39995 19954 39995 19955 39995 19955 39996 19954 39996 19956 39996 19955 39997 19956 39997 17564 39997 17564 39998 19956 39998 19957 39998 17564 39999 19957 39999 17566 39999 17566 40000 19957 40000 19959 40000 17566 40001 19959 40001 19958 40001 19958 40002 19959 40002 19960 40002 19958 40003 19960 40003 17554 40003 17554 40004 19960 40004 19944 40004 19974 40005 20633 40005 17542 40005 17542 40006 20633 40006 20634 40006 17542 40007 20634 40007 19961 40007 19961 40008 20634 40008 19963 40008 19961 40009 19963 40009 19962 40009 19962 40010 19963 40010 20623 40010 19962 40011 20623 40011 17545 40011 17545 40012 20623 40012 19964 40012 17545 40013 19964 40013 19965 40013 19965 40014 19964 40014 20625 40014 19965 40015 20625 40015 17547 40015 17547 40016 20625 40016 19966 40016 17547 40017 19966 40017 17548 40017 17548 40018 19966 40018 19967 40018 17548 40019 19967 40019 19968 40019 19968 40020 19967 40020 19969 40020 19968 40021 19969 40021 17551 40021 17551 40022 19969 40022 19970 40022 17551 40023 19970 40023 19971 40023 19971 40024 19970 40024 20630 40024 19971 40025 20630 40025 19972 40025 19972 40026 20630 40026 19973 40026 19972 40027 19973 40027 19974 40027 19974 40028 19973 40028 20633 40028 19983 40029 20610 40029 17529 40029 17529 40030 20610 40030 19976 40030 17529 40031 19976 40031 19975 40031 19975 40032 19976 40032 20596 40032 19975 40033 20596 40033 19977 40033 19977 40034 20596 40034 20597 40034 19977 40035 20597 40035 17532 40035 17532 40036 20597 40036 20600 40036 17532 40037 20600 40037 17534 40037 17534 40038 20600 40038 20601 40038 17534 40039 20601 40039 17536 40039 17536 40040 20601 40040 20602 40040 17536 40041 20602 40041 19978 40041 19978 40042 20602 40042 19979 40042 19978 40043 19979 40043 17537 40043 17537 40044 19979 40044 19980 40044 17537 40045 19980 40045 19981 40045 19981 40046 19980 40046 20604 40046 19981 40047 20604 40047 19982 40047 19982 40048 20604 40048 20606 40048 19982 40049 20606 40049 17538 40049 17538 40050 20606 40050 20609 40050 17538 40051 20609 40051 19983 40051 19983 40052 20609 40052 20610 40052 17526 40053 19996 40053 19984 40053 19984 40054 19996 40054 20654 40054 19984 40055 20654 40055 19985 40055 19985 40056 20654 40056 20646 40056 19985 40057 20646 40057 19986 40057 19986 40058 20646 40058 19987 40058 19986 40059 19987 40059 19988 40059 19988 40060 19987 40060 20649 40060 19988 40061 20649 40061 19989 40061 19989 40062 20649 40062 20650 40062 19989 40063 20650 40063 17521 40063 17521 40064 20650 40064 19990 40064 17521 40065 19990 40065 17522 40065 17522 40066 19990 40066 19991 40066 17522 40067 19991 40067 19992 40067 19992 40068 19991 40068 20651 40068 19992 40069 20651 40069 19993 40069 19993 40070 20651 40070 20652 40070 19993 40071 20652 40071 19994 40071 19994 40072 20652 40072 19995 40072 19994 40073 19995 40073 17525 40073 17525 40074 19995 40074 20653 40074 17525 40075 20653 40075 17526 40075 17526 40076 20653 40076 19996 40076 20007 40077 19997 40077 17515 40077 17515 40078 19997 40078 19998 40078 17515 40079 19998 40079 17517 40079 17517 40080 19998 40080 20667 40080 17517 40081 20667 40081 19999 40081 19999 40082 20667 40082 20000 40082 19999 40083 20000 40083 17502 40083 17502 40084 20000 40084 20001 40084 17502 40085 20001 40085 17503 40085 17503 40086 20001 40086 20670 40086 17503 40087 20670 40087 17504 40087 17504 40088 20670 40088 20002 40088 17504 40089 20002 40089 17506 40089 17506 40090 20002 40090 20003 40090 17506 40091 20003 40091 20004 40091 20004 40092 20003 40092 20005 40092 20004 40093 20005 40093 17509 40093 17509 40094 20005 40094 20674 40094 17509 40095 20674 40095 17511 40095 17511 40096 20674 40096 20006 40096 17511 40097 20006 40097 17513 40097 17513 40098 20006 40098 20675 40098 17513 40099 20675 40099 20007 40099 20007 40100 20675 40100 19997 40100 17489 40101 20643 40101 17490 40101 17490 40102 20643 40102 20635 40102 17490 40103 20635 40103 17491 40103 17491 40104 20635 40104 20008 40104 17491 40105 20008 40105 17492 40105 17492 40106 20008 40106 20009 40106 17492 40107 20009 40107 17493 40107 17493 40108 20009 40108 20637 40108 17493 40109 20637 40109 20010 40109 20010 40110 20637 40110 20011 40110 20010 40111 20011 40111 20012 40111 20012 40112 20011 40112 20013 40112 20012 40113 20013 40113 17497 40113 17497 40114 20013 40114 20014 40114 17497 40115 20014 40115 17499 40115 17499 40116 20014 40116 20639 40116 17499 40117 20639 40117 20015 40117 20015 40118 20639 40118 20016 40118 20015 40119 20016 40119 17500 40119 17500 40120 20016 40120 20017 40120 17500 40121 20017 40121 20018 40121 20018 40122 20017 40122 20019 40122 20018 40123 20019 40123 17489 40123 17489 40124 20019 40124 20643 40124 20020 40125 20621 40125 20021 40125 20021 40126 20621 40126 20622 40126 20021 40127 20622 40127 20022 40127 20022 40128 20622 40128 20612 40128 20022 40129 20612 40129 20023 40129 20023 40130 20612 40130 20024 40130 20023 40131 20024 40131 17475 40131 17475 40132 20024 40132 20025 40132 17475 40133 20025 40133 17476 40133 17476 40134 20025 40134 20026 40134 17476 40135 20026 40135 17477 40135 17477 40136 20026 40136 20027 40136 17477 40137 20027 40137 17479 40137 17479 40138 20027 40138 20028 40138 17479 40139 20028 40139 17481 40139 17481 40140 20028 40140 20615 40140 17481 40141 20615 40141 17482 40141 17482 40142 20615 40142 20618 40142 17482 40143 20618 40143 20029 40143 20029 40144 20618 40144 20619 40144 20029 40145 20619 40145 17485 40145 17485 40146 20619 40146 20030 40146 17485 40147 20030 40147 20020 40147 20020 40148 20030 40148 20621 40148 20037 40149 19582 40149 17575 40149 17575 40150 19582 40150 19584 40150 17575 40151 19584 40151 17574 40151 17574 40152 19584 40152 19593 40152 17574 40153 19593 40153 17573 40153 17573 40154 19593 40154 19587 40154 17573 40155 19587 40155 20031 40155 20031 40156 19587 40156 19588 40156 20031 40157 19588 40157 17570 40157 17570 40158 19588 40158 19589 40158 17570 40159 19589 40159 17569 40159 17569 40160 19589 40160 20032 40160 17569 40161 20032 40161 17568 40161 17568 40162 20032 40162 20033 40162 17568 40163 20033 40163 20034 40163 20034 40164 20033 40164 19590 40164 20034 40165 19590 40165 20035 40165 20035 40166 19590 40166 19591 40166 20035 40167 19591 40167 17579 40167 17579 40168 19591 40168 20036 40168 17579 40169 20036 40169 17577 40169 17577 40170 20036 40170 20038 40170 17577 40171 20038 40171 20037 40171 20037 40172 20038 40172 19582 40172 17495 40173 20049 40173 17494 40173 17494 40174 20049 40174 19595 40174 17494 40175 19595 40175 20039 40175 20039 40176 19595 40176 20041 40176 20039 40177 20041 40177 20040 40177 20040 40178 20041 40178 20042 40178 20040 40179 20042 40179 20043 40179 20043 40180 20042 40180 19599 40180 20043 40181 19599 40181 17488 40181 17488 40182 19599 40182 19596 40182 17488 40183 19596 40183 17487 40183 17487 40184 19596 40184 20044 40184 17487 40185 20044 40185 17486 40185 17486 40186 20044 40186 19607 40186 17486 40187 19607 40187 20045 40187 20045 40188 19607 40188 19608 40188 20045 40189 19608 40189 17498 40189 17498 40190 19608 40190 20046 40190 17498 40191 20046 40191 20047 40191 20047 40192 20046 40192 19594 40192 20047 40193 19594 40193 17496 40193 17496 40194 19594 40194 20048 40194 17496 40195 20048 40195 17495 40195 17495 40196 20048 40196 20049 40196 20050 40197 19615 40197 17546 40197 17546 40198 19615 40198 19612 40198 17546 40199 19612 40199 20051 40199 20051 40200 19612 40200 19613 40200 20051 40201 19613 40201 17544 40201 17544 40202 19613 40202 20052 40202 17544 40203 20052 40203 17543 40203 17543 40204 20052 40204 19622 40204 17543 40205 19622 40205 20053 40205 20053 40206 19622 40206 19623 40206 20053 40207 19623 40207 17541 40207 17541 40208 19623 40208 20054 40208 17541 40209 20054 40209 17540 40209 17540 40210 20054 40210 20055 40210 17540 40211 20055 40211 17552 40211 17552 40212 20055 40212 19624 40212 17552 40213 19624 40213 17550 40213 17550 40214 19624 40214 19625 40214 17550 40215 19625 40215 17549 40215 17549 40216 19625 40216 19619 40216 17549 40217 19619 40217 20056 40217 20056 40218 19619 40218 19611 40218 20056 40219 19611 40219 20050 40219 20050 40220 19611 40220 19615 40220 17561 40221 20057 40221 17560 40221 17560 40222 20057 40222 17656 40222 17560 40223 17656 40223 20058 40223 20058 40224 17656 40224 20059 40224 20058 40225 20059 40225 17557 40225 17557 40226 20059 40226 20060 40226 17557 40227 20060 40227 17556 40227 17556 40228 20060 40228 17658 40228 17556 40229 17658 40229 17555 40229 17555 40230 17658 40230 17661 40230 17555 40231 17661 40231 17553 40231 17553 40232 17661 40232 17662 40232 17553 40233 17662 40233 20061 40233 20061 40234 17662 40234 17664 40234 20061 40235 17664 40235 17565 40235 17565 40236 17664 40236 20062 40236 17565 40237 20062 40237 17563 40237 17563 40238 20062 40238 17669 40238 17563 40239 17669 40239 17562 40239 17562 40240 17669 40240 20063 40240 17562 40241 20063 40241 20064 40241 20064 40242 20063 40242 17655 40242 20064 40243 17655 40243 17561 40243 17561 40244 17655 40244 20057 40244 20065 40245 20066 40245 20067 40245 20067 40246 20066 40246 17717 40246 20067 40247 17717 40247 20068 40247 20068 40248 17717 40248 17718 40248 20068 40249 17718 40249 20070 40249 20070 40250 17718 40250 20069 40250 20070 40251 20069 40251 17474 40251 17474 40252 20069 40252 17719 40252 17474 40253 17719 40253 20071 40253 20071 40254 17719 40254 17720 40254 20071 40255 17720 40255 17484 40255 17484 40256 17720 40256 17722 40256 17484 40257 17722 40257 17483 40257 17483 40258 17722 40258 17723 40258 17483 40259 17723 40259 20072 40259 20072 40260 17723 40260 20073 40260 20072 40261 20073 40261 20074 40261 20074 40262 20073 40262 17725 40262 20074 40263 17725 40263 17480 40263 17480 40264 17725 40264 17728 40264 17480 40265 17728 40265 17478 40265 17478 40266 17728 40266 20075 40266 17478 40267 20075 40267 20065 40267 20065 40268 20075 40268 20066 40268 20091 40269 20092 40269 17533 40269 17533 40270 20092 40270 19633 40270 17533 40271 19633 40271 20076 40271 20076 40272 19633 40272 20077 40272 20076 40273 20077 40273 17531 40273 17531 40274 20077 40274 20078 40274 17531 40275 20078 40275 17530 40275 17530 40276 20078 40276 20079 40276 17530 40277 20079 40277 20080 40277 20080 40278 20079 40278 20081 40278 20080 40279 20081 40279 20082 40279 20082 40280 20081 40280 20083 40280 20082 40281 20083 40281 17539 40281 17539 40282 20083 40282 20084 40282 17539 40283 20084 40283 20085 40283 20085 40284 20084 40284 20086 40284 20085 40285 20086 40285 20087 40285 20087 40286 20086 40286 20089 40286 20087 40287 20089 40287 20088 40287 20088 40288 20089 40288 20090 40288 20088 40289 20090 40289 17535 40289 17535 40290 20090 40290 19629 40290 17535 40291 19629 40291 20091 40291 20091 40292 19629 40292 20092 40292 17505 40293 19646 40293 20093 40293 20093 40294 19646 40294 19643 40294 20093 40295 19643 40295 17501 40295 17501 40296 19643 40296 20094 40296 17501 40297 20094 40297 17518 40297 17518 40298 20094 40298 19650 40298 17518 40299 19650 40299 17516 40299 17516 40300 19650 40300 19651 40300 17516 40301 19651 40301 17514 40301 17514 40302 19651 40302 19653 40302 17514 40303 19653 40303 20096 40303 20096 40304 19653 40304 20095 40304 20096 40305 20095 40305 17512 40305 17512 40306 20095 40306 20097 40306 17512 40307 20097 40307 17510 40307 17510 40308 20097 40308 19655 40308 17510 40309 19655 40309 17508 40309 17508 40310 19655 40310 19658 40310 17508 40311 19658 40311 17507 40311 17507 40312 19658 40312 19659 40312 17507 40313 19659 40313 20098 40313 20098 40314 19659 40314 19644 40314 20098 40315 19644 40315 17505 40315 17505 40316 19644 40316 19646 40316 17520 40317 20107 40317 17519 40317 17519 40318 20107 40318 19664 40318 17519 40319 19664 40319 17528 40319 17528 40320 19664 40320 19666 40320 17528 40321 19666 40321 20099 40321 20099 40322 19666 40322 19668 40322 20099 40323 19668 40323 20100 40323 20100 40324 19668 40324 19671 40324 20100 40325 19671 40325 17527 40325 17527 40326 19671 40326 19672 40326 17527 40327 19672 40327 20101 40327 20101 40328 19672 40328 20102 40328 20101 40329 20102 40329 17524 40329 17524 40330 20102 40330 19676 40330 17524 40331 19676 40331 20103 40331 20103 40332 19676 40332 19677 40332 20103 40333 19677 40333 20104 40333 20104 40334 19677 40334 19678 40334 20104 40335 19678 40335 17523 40335 17523 40336 19678 40336 19679 40336 17523 40337 19679 40337 20105 40337 20105 40338 19679 40338 20106 40338 20105 40339 20106 40339 17520 40339 17520 40340 20106 40340 20107 40340 20114 40341 20108 40341 20118 40341 20128 40342 20108 40342 20114 40342 20114 40343 20111 40343 20109 40343 20110 40344 20111 40344 20114 40344 20118 40345 20110 40345 20114 40345 20114 40346 20112 40346 20116 40346 20113 40347 20112 40347 20114 40347 20109 40348 20113 40348 20114 40348 20114 40349 20115 40349 20127 40349 20125 40350 20115 40350 20114 40350 20116 40351 20125 40351 20114 40351 20127 40352 20128 40352 20114 40352 20128 40353 17598 40353 20108 40353 20108 40354 17598 40354 20117 40354 20108 40355 20117 40355 20118 40355 20118 40356 20117 40356 17601 40356 20118 40357 17601 40357 20110 40357 20110 40358 17601 40358 20119 40358 20110 40359 20119 40359 20111 40359 20111 40360 20119 40360 20120 40360 20111 40361 20120 40361 20109 40361 20109 40362 20120 40362 20121 40362 20109 40363 20121 40363 20113 40363 20113 40364 20121 40364 20122 40364 20113 40365 20122 40365 20112 40365 20112 40366 20122 40366 17593 40366 20112 40367 17593 40367 20116 40367 20116 40368 17593 40368 20123 40368 20116 40369 20123 40369 20125 40369 20125 40370 20123 40370 20124 40370 20125 40371 20124 40371 20115 40371 20115 40372 20124 40372 17596 40372 20115 40373 17596 40373 20127 40373 20127 40374 17596 40374 20126 40374 20127 40375 20126 40375 20128 40375 20128 40376 20126 40376 17598 40376 20129 40377 20132 40377 20133 40377 20149 40378 20132 40378 20129 40378 20129 40379 20130 40379 20136 40379 20135 40380 20130 40380 20129 40380 20133 40381 20135 40381 20129 40381 20129 40382 20140 40382 20142 40382 20138 40383 20140 40383 20129 40383 20136 40384 20138 40384 20129 40384 20129 40385 20145 40385 20148 40385 20144 40386 20145 40386 20129 40386 20142 40387 20144 40387 20129 40387 20148 40388 20149 40388 20129 40388 20149 40389 17608 40389 20132 40389 20132 40390 17608 40390 20131 40390 20132 40391 20131 40391 20133 40391 20133 40392 20131 40392 20134 40392 20133 40393 20134 40393 20135 40393 20135 40394 20134 40394 17609 40394 20135 40395 17609 40395 20130 40395 20130 40396 17609 40396 17602 40396 20130 40397 17602 40397 20136 40397 20136 40398 17602 40398 20137 40398 20136 40399 20137 40399 20138 40399 20138 40400 20137 40400 20139 40400 20138 40401 20139 40401 20140 40401 20140 40402 20139 40402 20141 40402 20140 40403 20141 40403 20142 40403 20142 40404 20141 40404 20143 40404 20142 40405 20143 40405 20144 40405 20144 40406 20143 40406 20146 40406 20144 40407 20146 40407 20145 40407 20145 40408 20146 40408 17607 40408 20145 40409 17607 40409 20148 40409 20148 40410 17607 40410 20147 40410 20148 40411 20147 40411 20149 40411 20149 40412 20147 40412 17608 40412 20156 40413 20158 40413 20150 40413 20157 40414 20158 40414 20156 40414 20156 40415 20163 40415 20151 40415 20162 40416 20163 40416 20156 40416 20150 40417 20162 40417 20156 40417 20156 40418 20152 40418 20166 40418 20153 40419 20152 40419 20156 40419 20151 40420 20153 40420 20156 40420 20156 40421 20154 40421 20169 40421 20155 40422 20154 40422 20156 40422 20166 40423 20155 40423 20156 40423 20169 40424 20157 40424 20156 40424 20157 40425 20159 40425 20158 40425 20158 40426 20159 40426 20160 40426 20158 40427 20160 40427 20150 40427 20150 40428 20160 40428 20161 40428 20150 40429 20161 40429 20162 40429 20162 40430 20161 40430 17622 40430 20162 40431 17622 40431 20163 40431 20163 40432 17622 40432 20164 40432 20163 40433 20164 40433 20151 40433 20151 40434 20164 40434 17611 40434 20151 40435 17611 40435 20153 40435 20153 40436 17611 40436 20165 40436 20153 40437 20165 40437 20152 40437 20152 40438 20165 40438 17612 40438 20152 40439 17612 40439 20166 40439 20166 40440 17612 40440 20167 40440 20166 40441 20167 40441 20155 40441 20155 40442 20167 40442 20168 40442 20155 40443 20168 40443 20154 40443 20154 40444 20168 40444 17616 40444 20154 40445 17616 40445 20169 40445 20169 40446 17616 40446 17617 40446 20169 40447 17617 40447 20157 40447 20157 40448 17617 40448 20159 40448 20171 40449 20174 40449 20175 40449 20188 40450 20174 40450 20171 40450 20171 40451 20178 40451 20170 40451 20176 40452 20178 40452 20171 40452 20175 40453 20176 40453 20171 40453 20171 40454 20180 40454 20173 40454 20172 40455 20180 40455 20171 40455 20170 40456 20172 40456 20171 40456 20171 40457 20185 40457 20187 40457 20183 40458 20185 40458 20171 40458 20173 40459 20183 40459 20171 40459 20187 40460 20188 40460 20171 40460 20188 40461 17588 40461 20174 40461 20174 40462 17588 40462 17589 40462 20174 40463 17589 40463 20175 40463 20175 40464 17589 40464 20177 40464 20175 40465 20177 40465 20176 40465 20176 40466 20177 40466 17580 40466 20176 40467 17580 40467 20178 40467 20178 40468 17580 40468 17581 40468 20178 40469 17581 40469 20170 40469 20170 40470 17581 40470 17583 40470 20170 40471 17583 40471 20172 40471 20172 40472 17583 40472 20179 40472 20172 40473 20179 40473 20180 40473 20180 40474 20179 40474 20181 40474 20180 40475 20181 40475 20173 40475 20173 40476 20181 40476 20182 40476 20173 40477 20182 40477 20183 40477 20183 40478 20182 40478 20184 40478 20183 40479 20184 40479 20185 40479 20185 40480 20184 40480 17587 40480 20185 40481 17587 40481 20187 40481 20187 40482 17587 40482 20186 40482 20187 40483 20186 40483 20188 40483 20188 40484 20186 40484 17588 40484 20191 40485 20196 40485 20200 40485 20189 40486 20196 40486 20191 40486 20191 40487 20201 40487 20190 40487 20192 40488 20201 40488 20191 40488 20200 40489 20192 40489 20191 40489 20191 40490 20205 40490 20195 40490 20193 40491 20205 40491 20191 40491 20190 40492 20193 40492 20191 40492 20191 40493 20208 40493 20194 40493 20207 40494 20208 40494 20191 40494 20195 40495 20207 40495 20191 40495 20194 40496 20189 40496 20191 40496 20189 40497 20197 40497 20196 40497 20196 40498 20197 40498 20198 40498 20196 40499 20198 40499 20200 40499 20200 40500 20198 40500 20199 40500 20200 40501 20199 40501 20192 40501 20192 40502 20199 40502 17962 40502 20192 40503 17962 40503 20201 40503 20201 40504 17962 40504 20202 40504 20201 40505 20202 40505 20190 40505 20190 40506 20202 40506 20203 40506 20190 40507 20203 40507 20193 40507 20193 40508 20203 40508 20204 40508 20193 40509 20204 40509 20205 40509 20205 40510 20204 40510 17961 40510 20205 40511 17961 40511 20195 40511 20195 40512 17961 40512 20206 40512 20195 40513 20206 40513 20207 40513 20207 40514 20206 40514 17963 40514 20207 40515 17963 40515 20208 40515 20208 40516 17963 40516 20209 40516 20208 40517 20209 40517 20194 40517 20194 40518 20209 40518 20210 40518 20194 40519 20210 40519 20189 40519 20189 40520 20210 40520 20197 40520 20211 40521 20214 40521 20215 40521 20227 40522 20214 40522 20211 40522 20211 40523 20219 40523 20220 40523 20217 40524 20219 40524 20211 40524 20215 40525 20217 40525 20211 40525 20211 40526 20212 40526 20222 40526 20213 40527 20212 40527 20211 40527 20220 40528 20213 40528 20211 40528 20211 40529 20224 40529 20226 40529 20223 40530 20224 40530 20211 40530 20222 40531 20223 40531 20211 40531 20226 40532 20227 40532 20211 40532 20227 40533 17858 40533 20214 40533 20214 40534 17858 40534 20216 40534 20214 40535 20216 40535 20215 40535 20215 40536 20216 40536 17864 40536 20215 40537 17864 40537 20217 40537 20217 40538 17864 40538 17954 40538 20217 40539 17954 40539 20219 40539 20219 40540 17954 40540 20218 40540 20219 40541 20218 40541 20220 40541 20220 40542 20218 40542 20221 40542 20220 40543 20221 40543 20213 40543 20213 40544 20221 40544 17952 40544 20213 40545 17952 40545 20212 40545 20212 40546 17952 40546 17955 40546 20212 40547 17955 40547 20222 40547 20222 40548 17955 40548 17957 40548 20222 40549 17957 40549 20223 40549 20223 40550 17957 40550 17958 40550 20223 40551 17958 40551 20224 40551 20224 40552 17958 40552 20225 40552 20224 40553 20225 40553 20226 40553 20226 40554 20225 40554 20228 40554 20226 40555 20228 40555 20227 40555 20227 40556 20228 40556 17858 40556 20231 40557 20229 40557 20232 40557 20239 40558 20229 40558 20231 40558 20231 40559 20230 40559 20234 40559 20241 40560 20230 40560 20231 40560 20232 40561 20241 40561 20231 40561 20231 40562 20246 40562 20233 40562 20235 40563 20246 40563 20231 40563 20234 40564 20235 40564 20231 40564 20231 40565 20238 40565 20236 40565 20237 40566 20238 40566 20231 40566 20233 40567 20237 40567 20231 40567 20236 40568 20239 40568 20231 40568 20239 40569 17868 40569 20229 40569 20229 40570 17868 40570 17867 40570 20229 40571 17867 40571 20232 40571 20232 40572 17867 40572 20240 40572 20232 40573 20240 40573 20241 40573 20241 40574 20240 40574 20242 40574 20241 40575 20242 40575 20230 40575 20230 40576 20242 40576 20243 40576 20230 40577 20243 40577 20234 40577 20234 40578 20243 40578 20244 40578 20234 40579 20244 40579 20235 40579 20235 40580 20244 40580 20245 40580 20235 40581 20245 40581 20246 40581 20246 40582 20245 40582 20247 40582 20246 40583 20247 40583 20233 40583 20233 40584 20247 40584 17865 40584 20233 40585 17865 40585 20237 40585 20237 40586 17865 40586 20248 40586 20237 40587 20248 40587 20238 40587 20238 40588 20248 40588 20249 40588 20238 40589 20249 40589 20236 40589 20236 40590 20249 40590 20250 40590 20236 40591 20250 40591 20239 40591 20239 40592 20250 40592 17868 40592 20252 40593 20251 40593 20253 40593 20257 40594 20251 40594 20252 40594 20252 40595 20261 40595 20262 40595 20260 40596 20261 40596 20252 40596 20253 40597 20260 40597 20252 40597 20252 40598 20254 40598 20264 40598 20255 40599 20254 40599 20252 40599 20262 40600 20255 40600 20252 40600 20252 40601 20267 40601 20268 40601 20256 40602 20267 40602 20252 40602 20264 40603 20256 40603 20252 40603 20268 40604 20257 40604 20252 40604 20257 40605 17869 40605 20251 40605 20251 40606 17869 40606 20258 40606 20251 40607 20258 40607 20253 40607 20253 40608 20258 40608 20259 40608 20253 40609 20259 40609 20260 40609 20260 40610 20259 40610 17877 40610 20260 40611 17877 40611 20261 40611 20261 40612 17877 40612 17876 40612 20261 40613 17876 40613 20262 40613 20262 40614 17876 40614 17875 40614 20262 40615 17875 40615 20255 40615 20255 40616 17875 40616 17873 40616 20255 40617 17873 40617 20254 40617 20254 40618 17873 40618 20263 40618 20254 40619 20263 40619 20264 40619 20264 40620 20263 40620 20265 40620 20264 40621 20265 40621 20256 40621 20256 40622 20265 40622 20266 40622 20256 40623 20266 40623 20267 40623 20267 40624 20266 40624 17872 40624 20267 40625 17872 40625 20268 40625 20268 40626 17872 40626 17871 40626 20268 40627 17871 40627 20257 40627 20257 40628 17871 40628 17869 40628 20269 40629 20277 40629 20279 40629 20287 40630 20277 40630 20269 40630 20269 40631 20271 40631 20273 40631 20270 40632 20271 40632 20269 40632 20279 40633 20270 40633 20269 40633 20269 40634 20283 40634 20272 40634 20274 40635 20283 40635 20269 40635 20273 40636 20274 40636 20269 40636 20269 40637 20275 40637 20286 40637 20276 40638 20275 40638 20269 40638 20272 40639 20276 40639 20269 40639 20286 40640 20287 40640 20269 40640 20287 40641 20288 40641 20277 40641 20277 40642 20288 40642 20278 40642 20277 40643 20278 40643 20279 40643 20279 40644 20278 40644 20280 40644 20279 40645 20280 40645 20270 40645 20270 40646 20280 40646 20281 40646 20270 40647 20281 40647 20271 40647 20271 40648 20281 40648 20282 40648 20271 40649 20282 40649 20273 40649 20273 40650 20282 40650 17950 40650 20273 40651 17950 40651 20274 40651 20274 40652 17950 40652 17951 40652 20274 40653 17951 40653 20283 40653 20283 40654 17951 40654 17949 40654 20283 40655 17949 40655 20272 40655 20272 40656 17949 40656 17886 40656 20272 40657 17886 40657 20276 40657 20276 40658 17886 40658 20284 40658 20276 40659 20284 40659 20275 40659 20275 40660 20284 40660 20285 40660 20275 40661 20285 40661 20286 40661 20286 40662 20285 40662 17884 40662 20286 40663 17884 40663 20287 40663 20287 40664 17884 40664 20288 40664 20293 40665 20289 40665 20296 40665 20305 40666 20289 40666 20293 40666 20293 40667 20290 40667 20300 40667 20298 40668 20290 40668 20293 40668 20296 40669 20298 40669 20293 40669 20293 40670 20292 40670 20291 40670 20302 40671 20292 40671 20293 40671 20300 40672 20302 40672 20293 40672 20293 40673 20294 40673 20304 40673 20303 40674 20294 40674 20293 40674 20291 40675 20303 40675 20293 40675 20304 40676 20305 40676 20293 40676 20305 40677 17948 40677 20289 40677 20289 40678 17948 40678 20295 40678 20289 40679 20295 40679 20296 40679 20296 40680 20295 40680 20297 40680 20296 40681 20297 40681 20298 40681 20298 40682 20297 40682 18039 40682 20298 40683 18039 40683 20290 40683 20290 40684 18039 40684 20299 40684 20290 40685 20299 40685 20300 40685 20300 40686 20299 40686 20301 40686 20300 40687 20301 40687 20302 40687 20302 40688 20301 40688 17947 40688 20302 40689 17947 40689 20292 40689 20292 40690 17947 40690 17946 40690 20292 40691 17946 40691 20291 40691 20291 40692 17946 40692 17945 40692 20291 40693 17945 40693 20303 40693 20303 40694 17945 40694 17891 40694 20303 40695 17891 40695 20294 40695 20294 40696 17891 40696 17890 40696 20294 40697 17890 40697 20304 40697 20304 40698 17890 40698 17888 40698 20304 40699 17888 40699 20305 40699 20305 40700 17888 40700 17948 40700 20308 40701 20306 40701 20314 40701 20322 40702 20306 40702 20308 40702 20308 40703 20307 40703 20309 40703 20316 40704 20307 40704 20308 40704 20314 40705 20316 40705 20308 40705 20308 40706 20318 40706 20320 40706 20310 40707 20318 40707 20308 40707 20309 40708 20310 40708 20308 40708 20308 40709 20313 40709 20311 40709 20312 40710 20313 40710 20308 40710 20320 40711 20312 40711 20308 40711 20311 40712 20322 40712 20308 40712 20322 40713 17900 40713 20306 40713 20306 40714 17900 40714 17901 40714 20306 40715 17901 40715 20314 40715 20314 40716 17901 40716 20315 40716 20314 40717 20315 40717 20316 40717 20316 40718 20315 40718 17897 40718 20316 40719 17897 40719 20307 40719 20307 40720 17897 40720 17896 40720 20307 40721 17896 40721 20309 40721 20309 40722 17896 40722 17895 40722 20309 40723 17895 40723 20310 40723 20310 40724 17895 40724 20317 40724 20310 40725 20317 40725 20318 40725 20318 40726 20317 40726 20319 40726 20318 40727 20319 40727 20320 40727 20320 40728 20319 40728 17893 40728 20320 40729 17893 40729 20312 40729 20312 40730 17893 40730 20321 40730 20312 40731 20321 40731 20313 40731 20313 40732 20321 40732 17905 40732 20313 40733 17905 40733 20311 40733 20311 40734 17905 40734 17898 40734 20311 40735 17898 40735 20322 40735 20322 40736 17898 40736 17900 40736 20325 40737 20323 40737 20330 40737 20324 40738 20323 40738 20325 40738 20325 40739 20333 40739 20334 40739 20326 40740 20333 40740 20325 40740 20330 40741 20326 40741 20325 40741 20325 40742 20336 40742 20328 40742 20335 40743 20336 40743 20325 40743 20334 40744 20335 40744 20325 40744 20325 40745 20327 40745 20341 40745 20339 40746 20327 40746 20325 40746 20328 40747 20339 40747 20325 40747 20341 40748 20324 40748 20325 40748 20324 40749 20329 40749 20323 40749 20323 40750 20329 40750 20331 40750 20323 40751 20331 40751 20330 40751 20330 40752 20331 40752 17903 40752 20330 40753 17903 40753 20326 40753 20326 40754 17903 40754 20332 40754 20326 40755 20332 40755 20333 40755 20333 40756 20332 40756 17904 40756 20333 40757 17904 40757 20334 40757 20334 40758 17904 40758 17906 40758 20334 40759 17906 40759 20335 40759 20335 40760 17906 40760 20337 40760 20335 40761 20337 40761 20336 40761 20336 40762 20337 40762 20338 40762 20336 40763 20338 40763 20328 40763 20328 40764 20338 40764 17908 40764 20328 40765 17908 40765 20339 40765 20339 40766 17908 40766 17907 40766 20339 40767 17907 40767 20327 40767 20327 40768 17907 40768 20340 40768 20327 40769 20340 40769 20341 40769 20341 40770 20340 40770 20342 40770 20341 40771 20342 40771 20324 40771 20324 40772 20342 40772 20329 40772 20345 40773 20350 40773 20352 40773 20349 40774 20350 40774 20345 40774 20345 40775 20344 40775 20343 40775 20354 40776 20344 40776 20345 40776 20352 40777 20354 40777 20345 40777 20345 40778 20356 40778 20359 40778 20346 40779 20356 40779 20345 40779 20343 40780 20346 40780 20345 40780 20345 40781 20347 40781 20348 40781 20360 40782 20347 40782 20345 40782 20359 40783 20360 40783 20345 40783 20348 40784 20349 40784 20345 40784 20349 40785 17940 40785 20350 40785 20350 40786 17940 40786 20351 40786 20350 40787 20351 40787 20352 40787 20352 40788 20351 40788 20353 40788 20352 40789 20353 40789 20354 40789 20354 40790 20353 40790 17988 40790 20354 40791 17988 40791 20344 40791 20344 40792 17988 40792 20355 40792 20344 40793 20355 40793 20343 40793 20343 40794 20355 40794 17914 40794 20343 40795 17914 40795 20346 40795 20346 40796 17914 40796 20357 40796 20346 40797 20357 40797 20356 40797 20356 40798 20357 40798 20358 40798 20356 40799 20358 40799 20359 40799 20359 40800 20358 40800 17944 40800 20359 40801 17944 40801 20360 40801 20360 40802 17944 40802 17943 40802 20360 40803 17943 40803 20347 40803 20347 40804 17943 40804 20361 40804 20347 40805 20361 40805 20348 40805 20348 40806 20361 40806 17942 40806 20348 40807 17942 40807 20349 40807 20349 40808 17942 40808 17940 40808 20365 40809 20366 40809 20362 40809 20380 40810 20366 40810 20365 40810 20365 40811 20369 40811 20370 40811 20368 40812 20369 40812 20365 40812 20362 40813 20368 40813 20365 40813 20365 40814 20374 40814 20376 40814 20371 40815 20374 40815 20365 40815 20370 40816 20371 40816 20365 40816 20365 40817 20363 40817 20378 40817 20364 40818 20363 40818 20365 40818 20376 40819 20364 40819 20365 40819 20378 40820 20380 40820 20365 40820 20380 40821 17936 40821 20366 40821 20366 40822 17936 40822 17938 40822 20366 40823 17938 40823 20362 40823 20362 40824 17938 40824 20367 40824 20362 40825 20367 40825 20368 40825 20368 40826 20367 40826 18056 40826 20368 40827 18056 40827 20369 40827 20369 40828 18056 40828 18055 40828 20369 40829 18055 40829 20370 40829 20370 40830 18055 40830 20372 40830 20370 40831 20372 40831 20371 40831 20371 40832 20372 40832 20373 40832 20371 40833 20373 40833 20374 40833 20374 40834 20373 40834 20375 40834 20374 40835 20375 40835 20376 40835 20376 40836 20375 40836 17917 40836 20376 40837 17917 40837 20364 40837 20364 40838 17917 40838 20377 40838 20364 40839 20377 40839 20363 40839 20363 40840 20377 40840 20379 40840 20363 40841 20379 40841 20378 40841 20378 40842 20379 40842 20381 40842 20378 40843 20381 40843 20380 40843 20380 40844 20381 40844 17936 40844 20382 40845 20383 40845 20393 40845 20390 40846 20383 40846 20382 40846 20382 40847 20385 40847 20387 40847 20384 40848 20385 40848 20382 40848 20393 40849 20384 40849 20382 40849 20382 40850 20386 40850 20401 40850 20397 40851 20386 40851 20382 40851 20387 40852 20397 40852 20382 40852 20382 40853 20402 40853 20388 40853 20389 40854 20402 40854 20382 40854 20401 40855 20389 40855 20382 40855 20388 40856 20390 40856 20382 40856 20390 40857 20391 40857 20383 40857 20383 40858 20391 40858 20392 40858 20383 40859 20392 40859 20393 40859 20393 40860 20392 40860 20394 40860 20393 40861 20394 40861 20384 40861 20384 40862 20394 40862 20395 40862 20384 40863 20395 40863 20385 40863 20385 40864 20395 40864 20396 40864 20385 40865 20396 40865 20387 40865 20387 40866 20396 40866 20398 40866 20387 40867 20398 40867 20397 40867 20397 40868 20398 40868 20399 40868 20397 40869 20399 40869 20386 40869 20386 40870 20399 40870 20400 40870 20386 40871 20400 40871 20401 40871 20401 40872 20400 40872 17925 40872 20401 40873 17925 40873 20389 40873 20389 40874 17925 40874 17924 40874 20389 40875 17924 40875 20402 40875 20402 40876 17924 40876 17923 40876 20402 40877 17923 40877 20388 40877 20388 40878 17923 40878 20403 40878 20388 40879 20403 40879 20390 40879 20390 40880 20403 40880 20391 40880 20405 40881 20404 40881 20406 40881 20409 40882 20404 40882 20405 40882 20405 40883 20414 40883 20417 40883 20412 40884 20414 40884 20405 40884 20406 40885 20412 40885 20405 40885 20405 40886 20407 40886 20420 40886 20418 40887 20407 40887 20405 40887 20417 40888 20418 40888 20405 40888 20405 40889 20424 40889 20408 40889 20423 40890 20424 40890 20405 40890 20420 40891 20423 40891 20405 40891 20408 40892 20409 40892 20405 40892 20409 40893 20410 40893 20404 40893 20404 40894 20410 40894 20411 40894 20404 40895 20411 40895 20406 40895 20406 40896 20411 40896 20413 40896 20406 40897 20413 40897 20412 40897 20412 40898 20413 40898 20415 40898 20412 40899 20415 40899 20414 40899 20414 40900 20415 40900 20416 40900 20414 40901 20416 40901 20417 40901 20417 40902 20416 40902 20419 40902 20417 40903 20419 40903 20418 40903 20418 40904 20419 40904 17928 40904 20418 40905 17928 40905 20407 40905 20407 40906 17928 40906 20421 40906 20407 40907 20421 40907 20420 40907 20420 40908 20421 40908 20422 40908 20420 40909 20422 40909 20423 40909 20423 40910 20422 40910 17930 40910 20423 40911 17930 40911 20424 40911 20424 40912 17930 40912 20425 40912 20424 40913 20425 40913 20408 40913 20408 40914 20425 40914 20426 40914 20408 40915 20426 40915 20409 40915 20409 40916 20426 40916 20410 40916 20431 40917 20434 40917 20429 40917 20427 40918 20434 40918 20431 40918 20431 40919 20428 40919 20436 40919 20430 40920 20428 40920 20431 40920 20429 40921 20430 40921 20431 40921 20431 40922 20441 40922 20442 40922 20439 40923 20441 40923 20431 40923 20436 40924 20439 40924 20431 40924 20431 40925 20444 40925 20432 40925 20443 40926 20444 40926 20431 40926 20442 40927 20443 40927 20431 40927 20432 40928 20427 40928 20431 40928 20427 40929 18053 40929 20434 40929 20434 40930 18053 40930 20433 40930 20434 40931 20433 40931 20429 40931 20429 40932 20433 40932 20435 40932 20429 40933 20435 40933 20430 40933 20430 40934 20435 40934 17834 40934 20430 40935 17834 40935 20428 40935 20428 40936 17834 40936 20437 40936 20428 40937 20437 40937 20436 40937 20436 40938 20437 40938 20438 40938 20436 40939 20438 40939 20439 40939 20439 40940 20438 40940 20440 40940 20439 40941 20440 40941 20441 40941 20441 40942 20440 40942 17935 40942 20441 40943 17935 40943 20442 40943 20442 40944 17935 40944 17934 40944 20442 40945 17934 40945 20443 40945 20443 40946 17934 40946 18006 40946 20443 40947 18006 40947 20444 40947 20444 40948 18006 40948 20445 40948 20444 40949 20445 40949 20432 40949 20432 40950 20445 40950 20446 40950 20432 40951 20446 40951 20427 40951 20427 40952 20446 40952 18053 40952 20447 40953 20451 40953 20452 40953 20450 40954 20451 40954 20447 40954 20447 40955 20448 40955 20455 40955 20454 40956 20448 40956 20447 40956 20452 40957 20454 40957 20447 40957 20447 40958 20449 40958 20460 40958 20457 40959 20449 40959 20447 40959 20455 40960 20457 40960 20447 40960 20447 40961 20464 40961 20465 40961 20462 40962 20464 40962 20447 40962 20460 40963 20462 40963 20447 40963 20465 40964 20450 40964 20447 40964 20450 40965 18051 40965 20451 40965 20451 40966 18051 40966 18064 40966 20451 40967 18064 40967 20452 40967 20452 40968 18064 40968 20453 40968 20452 40969 20453 40969 20454 40969 20454 40970 20453 40970 18075 40970 20454 40971 18075 40971 20448 40971 20448 40972 18075 40972 20456 40972 20448 40973 20456 40973 20455 40973 20455 40974 20456 40974 17837 40974 20455 40975 17837 40975 20457 40975 20457 40976 17837 40976 20458 40976 20457 40977 20458 40977 20449 40977 20449 40978 20458 40978 20459 40978 20449 40979 20459 40979 20460 40979 20460 40980 20459 40980 20461 40980 20460 40981 20461 40981 20462 40981 20462 40982 20461 40982 20463 40982 20462 40983 20463 40983 20464 40983 20464 40984 20463 40984 18048 40984 20464 40985 18048 40985 20465 40985 20465 40986 18048 40986 20466 40986 20465 40987 20466 40987 20450 40987 20450 40988 20466 40988 18051 40988 20469 40989 20470 40989 20471 40989 20468 40990 20470 40990 20469 40990 20469 40991 20476 40991 20477 40991 20473 40992 20476 40992 20469 40992 20471 40993 20473 40993 20469 40993 20469 40994 20480 40994 20482 40994 20479 40995 20480 40995 20469 40995 20477 40996 20479 40996 20469 40996 20469 40997 20467 40997 20485 40997 20484 40998 20467 40998 20469 40998 20482 40999 20484 40999 20469 40999 20485 41000 20468 41000 20469 41000 20468 41001 17847 41001 20470 41001 20470 41002 17847 41002 20472 41002 20470 41003 20472 41003 20471 41003 20471 41004 20472 41004 20474 41004 20471 41005 20474 41005 20473 41005 20473 41006 20474 41006 17840 41006 20473 41007 17840 41007 20476 41007 20476 41008 17840 41008 20475 41008 20476 41009 20475 41009 20477 41009 20477 41010 20475 41010 20478 41010 20477 41011 20478 41011 20479 41011 20479 41012 20478 41012 17843 41012 20479 41013 17843 41013 20480 41013 20480 41014 17843 41014 20481 41014 20480 41015 20481 41015 20482 41015 20482 41016 20481 41016 17842 41016 20482 41017 17842 41017 20484 41017 20484 41018 17842 41018 20483 41018 20484 41019 20483 41019 20467 41019 20467 41020 20483 41020 17841 41020 20467 41021 17841 41021 20485 41021 20485 41022 17841 41022 20486 41022 20485 41023 20486 41023 20468 41023 20468 41024 20486 41024 17847 41024 20493 41025 20488 41025 20495 41025 20487 41026 20488 41026 20493 41026 20493 41027 20498 41027 20490 41027 20497 41028 20498 41028 20493 41028 20495 41029 20497 41029 20493 41029 20493 41030 20501 41030 20489 41030 20491 41031 20501 41031 20493 41031 20490 41032 20491 41032 20493 41032 20493 41033 20505 41033 20506 41033 20492 41034 20505 41034 20493 41034 20489 41035 20492 41035 20493 41035 20506 41036 20487 41036 20493 41036 20487 41037 17844 41037 20488 41037 20488 41038 17844 41038 20494 41038 20488 41039 20494 41039 20495 41039 20495 41040 20494 41040 20496 41040 20495 41041 20496 41041 20497 41041 20497 41042 20496 41042 17852 41042 20497 41043 17852 41043 20498 41043 20498 41044 17852 41044 17851 41044 20498 41045 17851 41045 20490 41045 20490 41046 17851 41046 20499 41046 20490 41047 20499 41047 20491 41047 20491 41048 20499 41048 20500 41048 20491 41049 20500 41049 20501 41049 20501 41050 20500 41050 20502 41050 20501 41051 20502 41051 20489 41051 20489 41052 20502 41052 20503 41052 20489 41053 20503 41053 20492 41053 20492 41054 20503 41054 20504 41054 20492 41055 20504 41055 20505 41055 20505 41056 20504 41056 17846 41056 20505 41057 17846 41057 20506 41057 20506 41058 17846 41058 17845 41058 20506 41059 17845 41059 20487 41059 20487 41060 17845 41060 17844 41060 20537 41061 20507 41061 20535 41061 20535 41062 20507 41062 19696 41062 20535 41063 19696 41063 20508 41063 20508 41064 19696 41064 19695 41064 20508 41065 19695 41065 20509 41065 20509 41066 19695 41066 20510 41066 20509 41067 20510 41067 20533 41067 20533 41068 20510 41068 19715 41068 20533 41069 19715 41069 20512 41069 20512 41070 19715 41070 20511 41070 20512 41071 20511 41071 20542 41071 20542 41072 20511 41072 20513 41072 20542 41073 20513 41073 20541 41073 20541 41074 20513 41074 19703 41074 20541 41075 19703 41075 20514 41075 20514 41076 19703 41076 20515 41076 20514 41077 20515 41077 20540 41077 20540 41078 20515 41078 20516 41078 20540 41079 20516 41079 20539 41079 20539 41080 20516 41080 19697 41080 20539 41081 19697 41081 20517 41081 20517 41082 19697 41082 19699 41082 20517 41083 19699 41083 20537 41083 20537 41084 19699 41084 20507 41084 20519 41085 17428 41085 15806 41085 17466 41086 20518 41086 15860 41086 15860 41087 20518 41087 20519 41087 15860 41088 20519 41088 15859 41088 15859 41089 20519 41089 15806 41089 17426 41090 17440 41090 15605 41090 15605 41091 17440 41091 20520 41091 20522 41092 15628 41092 20520 41092 20520 41093 15628 41093 15627 41093 20520 41094 15627 41094 15605 41094 20523 41095 20521 41095 20522 41095 20522 41096 20521 41096 15600 41096 15600 41097 15599 41097 20522 41097 20522 41098 15599 41098 15603 41098 20522 41099 15603 41099 15628 41099 17449 41100 20525 41100 20526 41100 20526 41101 15593 41101 17449 41101 17449 41102 15593 41102 15592 41102 17449 41103 15592 41103 20523 41103 20523 41104 15592 41104 15602 41104 20523 41105 15602 41105 20521 41105 17441 41106 15598 41106 20524 41106 20524 41107 15598 41107 15597 41107 20524 41108 15597 41108 20525 41108 20525 41109 15597 41109 15596 41109 20525 41110 15596 41110 20526 41110 17456 41111 20527 41111 20528 41111 17456 41112 20528 41112 20529 41112 20528 41113 15577 41113 20529 41113 20529 41114 15577 41114 15552 41114 20529 41115 15552 41115 17457 41115 17457 41116 15552 41116 20530 41116 17457 41117 20530 41117 20531 41117 20531 41118 15560 41118 17457 41118 17457 41119 15560 41119 20532 41119 17457 41120 20532 41120 17458 41120 17458 41121 20532 41121 15559 41121 17458 41122 15559 41122 15526 41122 20512 41123 18395 41123 20533 41123 20533 41124 18395 41124 20534 41124 20533 41125 20534 41125 20509 41125 20509 41126 20534 41126 18398 41126 20509 41127 18398 41127 20508 41127 20508 41128 18398 41128 18400 41128 20508 41129 18400 41129 20535 41129 20535 41130 18400 41130 20536 41130 20535 41131 20536 41131 20537 41131 20537 41132 20536 41132 18405 41132 20537 41133 18405 41133 20517 41133 20517 41134 18405 41134 20538 41134 20517 41135 20538 41135 20539 41135 20539 41136 20538 41136 18388 41136 20539 41137 18388 41137 20540 41137 20540 41138 18388 41138 18390 41138 20540 41139 18390 41139 20514 41139 20514 41140 18390 41140 18386 41140 20514 41141 18386 41141 20541 41141 20541 41142 18386 41142 18381 41142 20541 41143 18381 41143 20542 41143 20542 41144 18381 41144 18382 41144 20542 41145 18382 41145 20512 41145 20512 41146 18382 41146 18395 41146 19913 41147 17592 41147 19904 41147 19904 41148 17592 41148 20543 41148 19904 41149 20543 41149 20544 41149 20544 41150 20543 41150 20545 41150 20544 41151 20545 41151 20546 41151 20546 41152 20545 41152 17600 41152 20546 41153 17600 41153 19908 41153 19908 41154 17600 41154 20547 41154 19908 41155 20547 41155 19910 41155 19910 41156 20547 41156 17599 41156 19910 41157 17599 41157 20548 41157 20548 41158 17599 41158 20549 41158 20548 41159 20549 41159 20550 41159 20550 41160 20549 41160 17597 41160 20550 41161 17597 41161 20551 41161 20551 41162 17597 41162 17595 41162 20551 41163 17595 41163 19911 41163 19911 41164 17595 41164 20552 41164 19911 41165 20552 41165 20553 41165 20553 41166 20552 41166 17594 41166 20553 41167 17594 41167 20554 41167 20554 41168 17594 41168 20555 41168 20554 41169 20555 41169 19913 41169 19913 41170 20555 41170 17592 41170 20556 41171 17604 41171 20557 41171 20557 41172 17604 41172 17603 41172 20557 41173 17603 41173 20558 41173 20558 41174 17603 41174 20559 41174 20558 41175 20559 41175 19897 41175 19897 41176 20559 41176 20560 41176 19897 41177 20560 41177 19899 41177 19899 41178 20560 41178 20561 41178 19899 41179 20561 41179 20563 41179 20563 41180 20561 41180 20562 41180 20563 41181 20562 41181 20564 41181 20564 41182 20562 41182 20566 41182 20564 41183 20566 41183 20565 41183 20565 41184 20566 41184 20567 41184 20565 41185 20567 41185 19901 41185 19901 41186 20567 41186 20568 41186 19901 41187 20568 41187 20569 41187 20569 41188 20568 41188 17606 41188 20569 41189 17606 41189 19902 41189 19902 41190 17606 41190 17605 41190 19902 41191 17605 41191 20570 41191 20570 41192 17605 41192 20571 41192 20570 41193 20571 41193 20556 41193 20556 41194 20571 41194 17604 41194 19893 41195 20579 41195 19894 41195 19894 41196 20579 41196 17610 41196 19894 41197 17610 41197 19882 41197 19882 41198 17610 41198 20573 41198 19882 41199 20573 41199 20572 41199 20572 41200 20573 41200 17621 41200 20572 41201 17621 41201 19883 41201 19883 41202 17621 41202 17620 41202 19883 41203 17620 41203 19886 41203 19886 41204 17620 41204 17619 41204 19886 41205 17619 41205 19887 41205 19887 41206 17619 41206 17618 41206 19887 41207 17618 41207 20574 41207 20574 41208 17618 41208 20575 41208 20574 41209 20575 41209 20576 41209 20576 41210 20575 41210 20578 41210 20576 41211 20578 41211 20577 41211 20577 41212 20578 41212 17615 41212 20577 41213 17615 41213 19889 41213 19889 41214 17615 41214 17614 41214 19889 41215 17614 41215 19892 41215 19892 41216 17614 41216 17613 41216 19892 41217 17613 41217 19893 41217 19893 41218 17613 41218 20579 41218 19929 41219 17584 41219 19914 41219 19914 41220 17584 41220 17582 41220 19914 41221 17582 41221 19915 41221 19915 41222 17582 41222 20580 41222 19915 41223 20580 41223 19916 41223 19916 41224 20580 41224 17591 41224 19916 41225 17591 41225 20581 41225 20581 41226 17591 41226 17590 41226 20581 41227 17590 41227 20582 41227 20582 41228 17590 41228 20583 41228 20582 41229 20583 41229 19919 41229 19919 41230 20583 41230 20584 41230 19919 41231 20584 41231 19922 41231 19922 41232 20584 41232 20585 41232 19922 41233 20585 41233 20586 41233 20586 41234 20585 41234 20587 41234 20586 41235 20587 41235 19925 41235 19925 41236 20587 41236 17586 41236 19925 41237 17586 41237 20588 41237 20588 41238 17586 41238 20589 41238 20588 41239 20589 41239 19927 41239 19927 41240 20589 41240 17585 41240 19927 41241 17585 41241 19929 41241 19929 41242 17585 41242 17584 41242 20590 41243 20595 41243 19947 41243 19947 41244 20595 41244 19373 41244 19947 41245 19373 41245 19948 41245 19948 41246 19373 41246 19418 41246 19948 41247 19418 41247 19949 41247 19949 41248 19418 41248 19416 41248 19949 41249 19416 41249 20591 41249 20591 41250 19416 41250 19414 41250 20591 41251 19414 41251 19952 41251 19952 41252 19414 41252 19424 41252 19952 41253 19424 41253 19954 41253 19954 41254 19424 41254 20592 41254 19954 41255 20592 41255 19956 41255 19956 41256 20592 41256 19413 41256 19956 41257 19413 41257 19957 41257 19957 41258 19413 41258 20593 41258 19957 41259 20593 41259 19959 41259 19959 41260 20593 41260 20594 41260 19959 41261 20594 41261 19960 41261 19960 41262 20594 41262 19371 41262 19960 41263 19371 41263 19944 41263 19944 41264 19371 41264 19372 41264 19944 41265 19372 41265 20590 41265 20590 41266 19372 41266 20595 41266 19976 41267 19361 41267 20596 41267 20596 41268 19361 41268 19360 41268 20596 41269 19360 41269 20597 41269 20597 41270 19360 41270 20598 41270 20597 41271 20598 41271 20600 41271 20600 41272 20598 41272 20599 41272 20600 41273 20599 41273 20601 41273 20601 41274 20599 41274 19427 41274 20601 41275 19427 41275 20602 41275 20602 41276 19427 41276 20603 41276 20602 41277 20603 41277 19979 41277 19979 41278 20603 41278 19429 41278 19979 41279 19429 41279 19980 41279 19980 41280 19429 41280 20605 41280 19980 41281 20605 41281 20604 41281 20604 41282 20605 41282 20607 41282 20604 41283 20607 41283 20606 41283 20606 41284 20607 41284 20608 41284 20606 41285 20608 41285 20609 41285 20609 41286 20608 41286 19363 41286 20609 41287 19363 41287 20610 41287 20610 41288 19363 41288 20611 41288 20610 41289 20611 41289 19976 41289 19976 41290 20611 41290 19361 41290 20622 41291 19299 41291 20612 41291 20612 41292 19299 41292 19296 41292 20612 41293 19296 41293 20024 41293 20024 41294 19296 41294 20613 41294 20024 41295 20613 41295 20025 41295 20025 41296 20613 41296 20614 41296 20025 41297 20614 41297 20026 41297 20026 41298 20614 41298 19294 41298 20026 41299 19294 41299 20027 41299 20027 41300 19294 41300 19295 41300 20027 41301 19295 41301 20028 41301 20028 41302 19295 41302 20616 41302 20028 41303 20616 41303 20615 41303 20615 41304 20616 41304 20617 41304 20615 41305 20617 41305 20618 41305 20618 41306 20617 41306 19302 41306 20618 41307 19302 41307 20619 41307 20619 41308 19302 41308 19301 41308 20619 41309 19301 41309 20030 41309 20030 41310 19301 41310 20620 41310 20030 41311 20620 41311 20621 41311 20621 41312 20620 41312 19300 41312 20621 41313 19300 41313 20622 41313 20622 41314 19300 41314 19299 41314 20634 41315 19286 41315 19963 41315 19963 41316 19286 41316 19288 41316 19963 41317 19288 41317 20623 41317 20623 41318 19288 41318 20624 41318 20623 41319 20624 41319 19964 41319 19964 41320 20624 41320 19280 41320 19964 41321 19280 41321 20625 41321 20625 41322 19280 41322 20626 41322 20625 41323 20626 41323 19966 41323 19966 41324 20626 41324 20627 41324 19966 41325 20627 41325 19967 41325 19967 41326 20627 41326 20628 41326 19967 41327 20628 41327 19969 41327 19969 41328 20628 41328 19281 41328 19969 41329 19281 41329 19970 41329 19970 41330 19281 41330 20629 41330 19970 41331 20629 41331 20630 41331 20630 41332 20629 41332 20631 41332 20630 41333 20631 41333 19973 41333 19973 41334 20631 41334 20632 41334 19973 41335 20632 41335 20633 41335 20633 41336 20632 41336 19285 41336 20633 41337 19285 41337 20634 41337 20634 41338 19285 41338 19286 41338 20635 41339 19446 41339 20008 41339 20008 41340 19446 41340 19409 41340 20008 41341 19409 41341 20009 41341 20009 41342 19409 41342 19410 41342 20009 41343 19410 41343 20637 41343 20637 41344 19410 41344 20636 41344 20637 41345 20636 41345 20011 41345 20011 41346 20636 41346 20638 41346 20011 41347 20638 41347 20013 41347 20013 41348 20638 41348 19407 41348 20013 41349 19407 41349 20014 41349 20014 41350 19407 41350 19408 41350 20014 41351 19408 41351 20639 41351 20639 41352 19408 41352 19445 41352 20639 41353 19445 41353 20016 41353 20016 41354 19445 41354 20640 41354 20016 41355 20640 41355 20017 41355 20017 41356 20640 41356 20641 41356 20017 41357 20641 41357 20019 41357 20019 41358 20641 41358 20642 41358 20019 41359 20642 41359 20643 41359 20643 41360 20642 41360 20644 41360 20643 41361 20644 41361 20635 41361 20635 41362 20644 41362 19446 41362 20654 41363 19400 41363 20646 41363 20646 41364 19400 41364 20645 41364 20646 41365 20645 41365 19987 41365 19987 41366 20645 41366 20647 41366 19987 41367 20647 41367 20649 41367 20649 41368 20647 41368 20648 41368 20649 41369 20648 41369 20650 41369 20650 41370 20648 41370 19397 41370 20650 41371 19397 41371 19990 41371 19990 41372 19397 41372 19396 41372 19990 41373 19396 41373 19991 41373 19991 41374 19396 41374 19395 41374 19991 41375 19395 41375 20651 41375 20651 41376 19395 41376 19394 41376 20651 41377 19394 41377 20652 41377 20652 41378 19394 41378 19393 41378 20652 41379 19393 41379 19995 41379 19995 41380 19393 41380 19392 41380 19995 41381 19392 41381 20653 41381 20653 41382 19392 41382 19389 41382 20653 41383 19389 41383 19996 41383 19996 41384 19389 41384 19387 41384 19996 41385 19387 41385 20654 41385 20654 41386 19387 41386 19400 41386 19931 41387 20655 41387 19932 41387 19932 41388 20655 41388 20656 41388 19932 41389 20656 41389 19933 41389 19933 41390 20656 41390 20657 41390 19933 41391 20657 41391 20658 41391 20658 41392 20657 41392 20659 41392 20658 41393 20659 41393 20660 41393 20660 41394 20659 41394 20661 41394 20660 41395 20661 41395 20662 41395 20662 41396 20661 41396 20663 41396 20662 41397 20663 41397 19936 41397 19936 41398 20663 41398 19260 41398 19936 41399 19260 41399 20664 41399 20664 41400 19260 41400 19261 41400 20664 41401 19261 41401 19939 41401 19939 41402 19261 41402 19263 41402 19939 41403 19263 41403 19940 41403 19940 41404 19263 41404 19270 41404 19940 41405 19270 41405 19943 41405 19943 41406 19270 41406 19272 41406 19943 41407 19272 41407 20665 41407 20665 41408 19272 41408 20666 41408 20665 41409 20666 41409 19931 41409 19931 41410 20666 41410 20655 41410 19998 41411 20678 41411 20667 41411 20667 41412 20678 41412 19257 41412 20667 41413 19257 41413 20000 41413 20000 41414 19257 41414 20668 41414 20000 41415 20668 41415 20001 41415 20001 41416 20668 41416 20669 41416 20001 41417 20669 41417 20670 41417 20670 41418 20669 41418 20671 41418 20670 41419 20671 41419 20002 41419 20002 41420 20671 41420 20672 41420 20002 41421 20672 41421 20003 41421 20003 41422 20672 41422 20673 41422 20003 41423 20673 41423 20005 41423 20005 41424 20673 41424 19251 41424 20005 41425 19251 41425 20674 41425 20674 41426 19251 41426 19252 41426 20674 41427 19252 41427 20006 41427 20006 41428 19252 41428 19253 41428 20006 41429 19253 41429 20675 41429 20675 41430 19253 41430 20676 41430 20675 41431 20676 41431 19997 41431 19997 41432 20676 41432 20677 41432 19997 41433 20677 41433 19998 41433 19998 41434 20677 41434 20678 41434 16831 41435 20679 41435 20682 41435 16829 41436 19246 41436 20681 41436 16829 41437 20681 41437 20679 41437 16831 41438 20682 41438 20680 41438 17323 41439 17326 41439 20687 41439 20687 41440 17326 41440 20685 41440 20681 41441 19313 41441 20683 41441 20679 41442 20681 41442 20682 41442 20682 41443 20681 41443 20683 41443 20682 41444 20683 41444 20684 41444 20684 41445 16834 41445 20682 41445 20682 41446 16834 41446 20687 41446 20682 41447 20687 41447 20680 41447 20680 41448 20687 41448 20685 41448 16837 41449 17323 41449 20686 41449 20686 41450 17323 41450 20687 41450 20686 41451 20687 41451 20688 41451 20688 41452 20687 41452 16834 41452 19499 41453 16825 41453 16826 41453 19499 41454 16826 41454 20689 41454 20689 41455 16826 41455 20690 41455 20689 41456 20690 41456 19500 41456 19814 41457 16811 41457 20709 41457 20697 41458 20694 41458 20698 41458 20691 41459 20696 41459 20692 41459 20692 41460 20696 41460 20698 41460 20692 41461 20698 41461 20693 41461 20693 41462 20698 41462 20694 41462 20693 41463 20694 41463 19329 41463 19329 41464 20694 41464 20695 41464 19329 41465 20695 41465 16814 41465 20691 41466 19444 41466 20696 41466 20696 41467 19444 41467 19315 41467 20696 41468 19315 41468 20699 41468 20697 41469 20698 41469 20703 41469 20703 41470 20698 41470 20696 41470 20703 41471 20696 41471 20704 41471 20704 41472 20696 41472 20699 41472 20704 41473 20699 41473 20705 41473 16811 41474 20700 41474 20697 41474 20697 41475 20700 41475 20701 41475 20697 41476 20701 41476 20694 41476 20694 41477 20701 41477 20702 41477 20694 41478 20702 41478 20695 41478 16811 41479 20697 41479 20709 41479 20709 41480 20697 41480 20703 41480 20709 41481 20703 41481 20707 41481 20707 41482 20703 41482 20704 41482 20707 41483 20704 41483 20706 41483 20706 41484 20704 41484 20705 41484 20706 41485 20705 41485 20712 41485 19808 41486 19809 41486 20712 41486 20712 41487 19809 41487 19810 41487 20712 41488 19810 41488 20706 41488 20706 41489 19810 41489 20708 41489 20706 41490 20708 41490 20707 41490 20707 41491 20708 41491 20710 41491 20707 41492 20710 41492 20709 41492 20709 41493 20710 41493 19816 41493 20709 41494 19816 41494 19814 41494 19315 41495 20711 41495 20699 41495 20699 41496 20711 41496 20713 41496 20699 41497 20713 41497 20705 41497 20705 41498 20713 41498 20715 41498 20705 41499 20715 41499 20712 41499 20712 41500 20715 41500 20716 41500 20712 41501 20716 41501 19808 41501 19808 41502 20716 41502 20718 41502 20711 41503 16816 41503 20713 41503 20713 41504 16816 41504 20714 41504 20713 41505 20714 41505 20715 41505 20715 41506 20714 41506 20717 41506 20715 41507 20717 41507 20716 41507 20716 41508 20717 41508 20719 41508 20716 41509 20719 41509 20718 41509 20718 41510 20719 41510 16819 41510 19818 41511 19819 41511 20720 41511 20720 41512 19819 41512 20721 41512 20720 41513 20721 41513 16759 41513 16759 41514 20721 41514 16761 41514 16761 41515 20721 41515 20722 41515 16761 41516 20722 41516 20723 41516 20723 41517 20722 41517 20724 41517 20724 41518 20722 41518 20727 41518 20724 41519 20727 41519 16755 41519 19819 41520 20725 41520 20721 41520 20721 41521 20725 41521 20726 41521 20721 41522 20726 41522 20722 41522 20722 41523 20726 41523 20729 41523 20722 41524 20729 41524 20727 41524 20727 41525 20729 41525 19438 41525 20725 41526 20728 41526 20726 41526 20726 41527 20728 41527 16745 41527 20726 41528 16745 41528 20729 41528 20729 41529 16745 41529 16744 41529 20729 41530 16744 41530 19438 41530 19438 41531 16744 41531 19436 41531 16725 41532 20730 41532 20738 41532 16720 41533 16713 41533 20740 41533 20730 41534 16724 41534 20732 41534 15489 41535 20731 41535 20739 41535 20730 41536 20732 41536 20738 41536 20738 41537 20732 41537 15492 41537 20738 41538 15492 41538 20739 41538 20739 41539 15492 41539 15490 41539 20739 41540 15490 41540 15489 41540 15489 41541 20733 41541 20731 41541 20731 41542 20733 41542 15487 41542 20731 41543 15487 41543 20734 41543 15482 41544 16720 41544 15484 41544 15484 41545 16720 41545 20740 41545 15484 41546 20740 41546 15485 41546 15485 41547 20740 41547 20734 41547 15485 41548 20734 41548 20735 41548 20735 41549 20734 41549 15487 41549 20736 41550 20737 41550 16725 41550 16725 41551 20738 41551 20736 41551 20736 41552 20738 41552 20739 41552 20736 41553 20739 41553 20743 41553 20743 41554 20739 41554 20731 41554 20743 41555 20731 41555 20744 41555 20744 41556 20731 41556 20734 41556 20744 41557 20734 41557 20741 41557 20741 41558 20734 41558 20740 41558 20741 41559 20740 41559 20746 41559 20746 41560 20740 41560 16713 41560 20746 41561 16713 41561 16712 41561 20742 41562 16721 41562 20737 41562 20737 41563 20736 41563 20742 41563 20742 41564 20736 41564 20743 41564 20742 41565 20743 41565 20750 41565 20750 41566 20743 41566 20744 41566 20750 41567 20744 41567 20745 41567 20745 41568 20744 41568 20741 41568 20745 41569 20741 41569 20751 41569 20751 41570 20741 41570 20746 41570 20751 41571 20746 41571 20747 41571 20747 41572 20746 41572 16712 41572 20747 41573 16712 41573 20748 41573 19426 41574 19425 41574 16721 41574 16721 41575 20742 41575 19426 41575 19426 41576 20742 41576 20750 41576 19426 41577 20750 41577 20749 41577 20749 41578 20750 41578 20745 41578 20749 41579 20745 41579 19428 41579 19428 41580 20745 41580 20751 41580 19428 41581 20751 41581 20752 41581 20752 41582 20751 41582 20747 41582 20752 41583 20747 41583 19430 41583 19430 41584 20747 41584 20748 41584 19430 41585 20748 41585 19431 41585 20777 41586 20753 41586 20754 41586 20753 41587 20775 41587 20764 41587 20755 41588 16682 41588 20768 41588 20756 41589 19724 41589 17756 41589 20756 41590 17756 41590 20775 41590 20775 41591 17756 41591 20765 41591 20775 41592 20765 41592 20764 41592 20757 41593 20755 41593 20758 41593 20758 41594 20755 41594 20768 41594 20758 41595 20768 41595 20759 41595 20759 41596 20768 41596 20760 41596 20759 41597 20760 41597 20761 41597 20761 41598 20760 41598 20767 41598 20761 41599 20767 41599 20762 41599 20762 41600 20767 41600 20763 41600 20762 41601 20763 41601 17753 41601 17753 41602 20763 41602 20764 41602 17753 41603 20764 41603 17754 41603 17754 41604 20764 41604 20765 41604 20753 41605 20764 41605 20754 41605 20754 41606 20764 41606 20763 41606 20754 41607 20763 41607 20766 41607 20766 41608 20763 41608 20767 41608 20766 41609 20767 41609 20769 41609 20769 41610 20767 41610 20760 41610 20769 41611 20760 41611 20770 41611 20770 41612 20760 41612 20768 41612 20770 41613 20768 41613 20772 41613 20772 41614 20768 41614 16682 41614 20772 41615 16682 41615 20773 41615 20777 41616 20754 41616 20778 41616 20778 41617 20754 41617 20766 41617 20778 41618 20766 41618 20779 41618 20779 41619 20766 41619 20769 41619 20779 41620 20769 41620 20781 41620 20781 41621 20769 41621 20770 41621 20781 41622 20770 41622 20771 41622 20771 41623 20770 41623 20772 41623 20771 41624 20772 41624 20783 41624 20783 41625 20772 41625 20773 41625 20783 41626 20773 41626 16679 41626 19415 41627 19417 41627 20777 41627 20777 41628 19417 41628 20774 41628 20777 41629 20774 41629 20753 41629 20753 41630 20774 41630 16689 41630 20753 41631 16689 41631 20775 41631 20775 41632 16689 41632 20776 41632 20775 41633 20776 41633 20756 41633 19415 41634 20777 41634 19423 41634 19423 41635 20777 41635 20778 41635 19423 41636 20778 41636 19421 41636 19421 41637 20778 41637 20779 41637 19421 41638 20779 41638 20780 41638 20780 41639 20779 41639 20781 41639 20780 41640 20781 41640 20782 41640 20782 41641 20781 41641 20771 41641 20782 41642 20771 41642 19422 41642 19422 41643 20771 41643 20783 41643 19422 41644 20783 41644 20784 41644 20784 41645 20783 41645 16679 41645 20784 41646 16679 41646 16678 41646 16655 41647 20785 41647 20786 41647 20794 41648 20788 41648 20787 41648 20787 41649 20788 41649 16655 41649 19412 41650 20790 41650 20789 41650 20789 41651 20790 41651 20794 41651 20791 41652 17371 41652 16649 41652 16655 41653 20786 41653 20787 41653 20787 41654 20786 41654 17749 41654 20787 41655 17749 41655 20795 41655 20795 41656 17749 41656 17750 41656 20795 41657 17750 41657 20798 41657 20798 41658 17750 41658 20792 41658 20798 41659 20792 41659 20800 41659 20800 41660 20792 41660 20793 41660 20800 41661 20793 41661 20801 41661 20801 41662 20793 41662 20791 41662 20801 41663 20791 41663 20802 41663 20802 41664 20791 41664 16649 41664 20802 41665 16649 41665 16650 41665 20794 41666 20787 41666 20789 41666 20789 41667 20787 41667 20795 41667 20789 41668 20795 41668 20796 41668 20796 41669 20795 41669 20798 41669 20796 41670 20798 41670 20797 41670 20797 41671 20798 41671 20800 41671 20797 41672 20800 41672 20799 41672 20799 41673 20800 41673 20801 41673 20799 41674 20801 41674 20806 41674 20806 41675 20801 41675 20802 41675 20806 41676 20802 41676 20808 41676 20808 41677 20802 41677 16650 41677 20808 41678 16650 41678 16651 41678 19412 41679 20789 41679 20803 41679 20803 41680 20789 41680 20796 41680 20803 41681 20796 41681 19406 41681 19406 41682 20796 41682 20797 41682 19406 41683 20797 41683 20804 41683 20804 41684 20797 41684 20799 41684 20804 41685 20799 41685 20805 41685 20805 41686 20799 41686 20806 41686 20805 41687 20806 41687 20807 41687 20807 41688 20806 41688 20808 41688 20807 41689 20808 41689 19401 41689 19401 41690 20808 41690 16651 41690 19401 41691 16651 41691 20809 41691 19398 41692 16610 41692 20821 41692 16610 41693 16607 41693 20815 41693 16607 41694 16606 41694 20810 41694 16607 41695 20810 41695 20815 41695 20815 41696 20810 41696 17746 41696 20815 41697 17746 41697 20811 41697 20811 41698 17746 41698 20813 41698 20811 41699 20813 41699 20812 41699 20812 41700 20813 41700 20814 41700 20812 41701 20814 41701 20817 41701 20817 41702 20814 41702 17744 41702 20817 41703 17744 41703 20818 41703 20818 41704 17744 41704 17743 41704 20818 41705 17743 41705 20819 41705 16610 41706 20815 41706 20821 41706 20821 41707 20815 41707 20811 41707 20821 41708 20811 41708 20816 41708 20816 41709 20811 41709 20812 41709 20816 41710 20812 41710 20824 41710 20824 41711 20812 41711 20817 41711 20824 41712 20817 41712 20826 41712 20826 41713 20817 41713 20818 41713 20826 41714 20818 41714 20828 41714 20828 41715 20818 41715 20819 41715 20828 41716 20819 41716 20820 41716 19398 41717 20821 41717 20822 41717 20822 41718 20821 41718 20816 41718 20822 41719 20816 41719 20823 41719 20823 41720 20816 41720 20824 41720 20823 41721 20824 41721 20825 41721 20825 41722 20824 41722 20826 41722 20825 41723 20826 41723 20827 41723 20827 41724 20826 41724 20828 41724 20827 41725 20828 41725 20829 41725 20829 41726 20828 41726 20820 41726 20829 41727 20820 41727 16604 41727 18601 41728 20830 41728 16264 41728 16264 41729 20830 41729 19645 41729 16264 41730 19645 41730 16262 41730 16262 41731 19645 41731 20831 41731 16262 41732 20831 41732 20832 41732 20832 41733 20831 41733 19660 41733 20832 41734 19660 41734 16261 41734 16261 41735 19660 41735 20833 41735 16261 41736 20833 41736 20834 41736 20835 41737 19764 41737 20836 41737 20836 41738 19764 41738 19766 41738 20836 41739 19766 41739 17899 41739 17899 41740 19766 41740 20837 41740 20837 41741 19766 41741 19767 41741 20837 41742 19767 41742 20844 41742 17882 41743 19760 41743 17880 41743 17880 41744 19760 41744 20839 41744 17880 41745 20839 41745 20838 41745 20838 41746 20839 41746 20840 41746 20838 41747 20840 41747 20845 41747 17882 41748 20841 41748 19760 41748 19760 41749 20841 41749 20842 41749 19760 41750 20842 41750 19763 41750 19763 41751 20842 41751 18047 41751 19763 41752 18047 41752 19768 41752 19768 41753 18047 41753 20843 41753 19768 41754 20843 41754 19767 41754 19767 41755 20843 41755 17889 41755 19767 41756 17889 41756 20844 41756 20845 41757 20840 41757 20846 41757 20846 41758 20840 41758 19762 41758 20846 41759 19762 41759 17870 41759 19762 41760 19748 41760 17870 41760 17870 41761 19748 41761 19749 41761 17870 41762 19749 41762 20847 41762 20847 41763 19749 41763 20849 41763 20847 41764 20849 41764 20848 41764 20848 41765 20849 41765 20850 41765 20848 41766 20850 41766 20851 41766 20851 41767 20850 41767 19751 41767 20851 41768 19751 41768 17878 41768 17878 41769 19751 41769 20857 41769 17860 41770 19755 41770 20852 41770 20852 41771 19755 41771 19742 41771 17860 41772 20853 41772 19755 41772 19755 41773 20853 41773 17862 41773 19755 41774 17862 41774 20855 41774 17862 41775 20854 41775 20855 41775 20855 41776 20854 41776 17866 41776 20855 41777 17866 41777 20857 41777 20857 41778 17866 41778 20856 41778 20857 41779 20856 41779 17878 41779 20864 41780 17854 41780 20858 41780 20858 41781 17854 41781 17856 41781 20858 41782 17856 41782 20859 41782 17856 41783 17855 41783 20859 41783 20859 41784 17855 41784 20860 41784 20859 41785 20860 41785 19742 41785 19742 41786 20860 41786 20861 41786 19742 41787 20861 41787 20852 41787 20862 41788 20863 41788 20866 41788 20864 41789 20858 41789 18078 41789 18078 41790 20858 41790 20865 41790 18078 41791 20865 41791 20866 41791 20866 41792 20865 41792 20867 41792 20866 41793 20867 41793 20862 41793 20862 41794 20868 41794 20863 41794 20863 41795 20868 41795 20869 41795 20863 41796 20869 41796 17850 41796 19805 41797 20870 41797 18050 41797 18050 41798 20870 41798 20871 41798 18050 41799 18049 41799 19805 41799 19805 41800 18049 41800 17836 41800 19805 41801 17836 41801 19803 41801 19803 41802 17836 41802 20875 41802 20869 41803 19799 41803 17850 41803 17850 41804 19799 41804 20872 41804 17850 41805 20872 41805 17849 41805 17849 41806 20872 41806 19801 41806 17849 41807 19801 41807 20873 41807 20873 41808 19801 41808 19802 41808 20873 41809 19802 41809 20874 41809 20874 41810 19802 41810 19803 41810 20874 41811 19803 41811 17838 41811 17838 41812 19803 41812 20875 41812 18002 41813 19807 41813 18004 41813 18004 41814 19807 41814 19792 41814 18004 41815 19792 41815 18005 41815 18002 41816 20876 41816 19807 41816 19807 41817 20876 41817 17833 41817 19807 41818 17833 41818 20870 41818 20870 41819 17833 41819 20877 41819 20870 41820 20877 41820 20871 41820 18005 41821 19792 41821 17820 41821 17820 41822 19792 41822 19793 41822 17820 41823 19793 41823 17821 41823 19793 41824 20878 41824 17821 41824 17821 41825 20878 41825 19795 41825 17821 41826 19795 41826 18010 41826 18010 41827 19795 41827 19796 41827 18010 41828 19796 41828 17931 41828 17931 41829 19796 41829 20880 41829 17931 41830 20880 41830 20879 41830 20879 41831 20880 41831 19789 41831 20879 41832 19789 41832 17927 41832 17927 41833 19789 41833 20881 41833 17927 41834 20881 41834 17926 41834 17926 41835 20881 41835 20882 41835 17926 41836 20882 41836 17922 41836 17922 41837 20882 41837 19785 41837 17922 41838 19785 41838 17921 41838 17921 41839 19785 41839 20886 41839 17921 41840 20886 41840 17919 41840 17919 41841 20886 41841 20883 41841 19782 41842 19775 41842 20884 41842 20884 41843 17916 41843 19782 41843 19782 41844 17916 41844 20885 41844 19782 41845 20885 41845 20886 41845 20886 41846 20885 41846 17920 41846 20886 41847 17920 41847 20883 41847 17910 41848 17913 41848 20889 41848 20889 41849 17913 41849 20887 41849 20889 41850 20887 41850 19775 41850 19775 41851 20887 41851 20888 41851 19775 41852 20888 41852 20884 41852 17910 41853 20889 41853 17998 41853 17998 41854 20889 41854 19778 41854 17998 41855 19778 41855 17816 41855 17816 41856 19778 41856 19772 41856 17816 41857 19772 41857 20890 41857 19772 41858 20891 41858 20890 41858 20890 41859 20891 41859 19769 41859 20890 41860 19769 41860 17974 41860 17974 41861 19769 41861 20893 41861 17974 41862 20893 41862 20892 41862 20892 41863 20893 41863 20894 41863 20892 41864 20894 41864 20835 41864 20835 41865 20894 41865 20895 41865 20835 41866 20895 41866 19764 41866 15497 41867 19688 41867 19687 41867 15497 41868 19687 41868 19518 41868 19518 41869 19687 41869 19686 41869 19518 41870 19686 41870 19519 41870 20896 41871 19477 41871 19685 41871 19685 41872 19477 41872 19520 41872 19685 41873 19520 41873 19683 41873 19683 41874 19520 41874 19519 41874 19683 41875 19519 41875 19686 41875 19477 41876 20896 41876 20897 41876 19477 41877 20897 41877 19478 41877 19478 41878 20897 41878 20898 41878 19478 41879 20898 41879 20899 41879 19479 41880 20899 41880 20898 41880 20898 41881 19681 41881 19479 41881 19479 41882 19681 41882 20900 41882 19479 41883 20900 41883 19491 41883 19491 41884 20900 41884 20901 41884 19491 41885 20901 41885 19492 41885 19492 41886 20901 41886 15494 41886 19492 41887 15494 41887 19473 41887 15470 41888 15473 41888 20907 41888 20907 41889 15473 41889 20902 41889 20907 41890 20902 41890 20903 41890 15466 41891 15468 41891 20907 41891 20907 41892 15468 41892 20904 41892 20907 41893 20904 41893 15470 41893 20905 41894 15476 41894 20907 41894 20907 41895 15476 41895 20906 41895 20907 41896 20906 41896 15466 41896 20903 41897 20908 41897 20907 41897 20907 41898 20908 41898 15475 41898 20907 41899 15475 41899 20905 41899 20928 41900 20927 41900 20909 41900 20909 41901 20927 41901 20913 41901 20909 41902 20913 41902 17396 41902 17396 41903 20913 41903 20910 41903 20919 41904 19705 41904 19706 41904 20919 41905 19706 41905 20911 41905 20911 41906 19706 41906 19709 41906 20911 41907 19709 41907 20912 41907 20912 41908 19709 41908 20913 41908 20912 41909 20913 41909 20927 41909 20925 41910 20914 41910 20916 41910 20918 41911 20917 41911 20927 41911 20911 41912 20912 41912 20917 41912 20917 41913 20912 41913 20927 41913 20915 41914 20918 41914 20927 41914 20925 41915 20916 41915 20926 41915 20919 41916 20911 41916 20922 41916 20922 41917 20911 41917 20917 41917 20922 41918 20917 41918 20916 41918 20916 41919 20917 41919 20918 41919 20916 41920 20918 41920 20926 41920 20926 41921 20918 41921 20915 41921 20916 41922 20914 41922 19254 41922 17768 41923 20919 41923 20920 41923 20920 41924 20919 41924 20922 41924 20920 41925 20922 41925 20921 41925 20921 41926 20922 41926 20916 41926 20921 41927 20916 41927 20923 41927 20923 41928 20916 41928 19254 41928 19255 41929 19254 41929 20924 41929 20924 41930 19254 41930 20914 41930 20924 41931 20914 41931 20940 41931 20940 41932 20914 41932 20947 41932 20914 41933 20925 41933 20947 41933 20947 41934 20925 41934 20926 41934 20947 41935 20926 41935 20934 41935 20926 41936 20915 41936 20934 41936 20934 41937 20915 41937 20927 41937 20934 41938 20927 41938 20928 41938 20933 41939 20929 41939 20953 41939 20953 41940 20929 41940 17393 41940 20953 41941 17393 41941 20951 41941 20951 41942 17393 41942 20930 41942 20951 41943 20930 41943 20931 41943 17396 41944 17395 41944 20909 41944 20909 41945 17395 41945 17394 41945 20909 41946 17394 41946 20933 41946 20933 41947 17394 41947 20932 41947 20933 41948 20932 41948 20929 41948 20928 41949 20946 41949 20934 41949 20935 41950 20946 41950 20928 41950 20939 41951 20942 41951 20950 41951 19255 41952 20924 41952 20936 41952 20936 41953 20924 41953 20937 41953 20936 41954 20937 41954 20938 41954 20938 41955 20937 41955 20939 41955 20938 41956 20939 41956 20949 41956 20949 41957 20939 41957 20950 41957 20924 41958 20940 41958 20937 41958 20937 41959 20940 41959 20941 41959 20937 41960 20941 41960 20939 41960 20939 41961 20941 41961 20948 41961 20939 41962 20948 41962 20942 41962 20954 41963 20952 41963 20948 41963 20948 41964 20952 41964 20943 41964 20948 41965 20943 41965 20942 41965 20947 41966 20934 41966 20944 41966 20944 41967 20934 41967 20946 41967 20944 41968 20946 41968 20945 41968 20945 41969 20946 41969 20935 41969 20940 41970 20947 41970 20941 41970 20941 41971 20947 41971 20944 41971 20941 41972 20944 41972 20948 41972 20948 41973 20944 41973 20945 41973 20948 41974 20945 41974 20954 41974 20954 41975 20945 41975 20935 41975 20954 41976 20935 41976 20955 41976 20955 41977 20935 41977 20928 41977 20950 41978 17101 41978 17100 41978 20950 41979 17100 41979 20949 41979 20949 41980 17100 41980 17099 41980 20949 41981 17099 41981 20938 41981 20938 41982 17099 41982 17098 41982 20938 41983 17098 41983 20936 41983 20936 41984 17098 41984 19256 41984 20936 41985 19256 41985 19255 41985 19522 41986 17101 41986 20931 41986 20931 41987 17101 41987 20950 41987 20950 41988 20942 41988 20931 41988 20931 41989 20942 41989 20943 41989 20931 41990 20943 41990 20951 41990 20951 41991 20943 41991 20952 41991 20951 41992 20952 41992 20953 41992 20953 41993 20952 41993 20954 41993 20953 41994 20954 41994 20933 41994 20954 41995 20955 41995 20933 41995 20933 41996 20955 41996 20928 41996 20933 41997 20928 41997 20909 41997 20958 41998 21113 41998 20956 41998 21091 41999 21088 41999 20959 41999 20959 42000 21088 42000 21081 42000 20959 42001 21081 42001 20957 42001 20957 42002 20958 42002 20959 42002 20959 42003 20958 42003 20956 42003 20959 42004 20956 42004 20960 42004 20960 42005 20956 42005 20961 42005 20960 42006 20961 42006 21087 42006 21087 42007 20961 42007 20962 42007 21087 42008 20962 42008 20963 42008 20963 42009 20962 42009 21095 42009 20963 42010 21095 42010 21085 42010 21085 42011 21095 42011 21097 42011 21085 42012 21097 42012 21086 42012 21086 42013 21097 42013 21094 42013 21086 42014 21094 42014 20966 42014 21101 42015 20964 42015 21102 42015 21102 42016 20964 42016 21086 42016 21102 42017 21086 42017 20965 42017 20965 42018 21086 42018 20966 42018 20988 42019 20996 42019 20970 42019 20987 42020 20988 42020 20967 42020 20987 42021 20967 42021 20980 42021 20980 42022 20967 42022 20971 42022 20980 42023 20971 42023 20968 42023 20968 42024 20971 42024 20969 42024 20968 42025 20969 42025 21024 42025 20988 42026 20970 42026 20967 42026 20967 42027 20970 42027 20994 42027 20967 42028 20994 42028 20971 42028 20971 42029 20994 42029 20998 42029 20971 42030 20998 42030 20969 42030 21027 42031 20972 42031 21026 42031 21026 42032 20972 42032 20973 42032 21026 42033 20973 42033 21025 42033 21025 42034 20973 42034 20975 42034 21025 42035 20975 42035 21024 42035 21024 42036 20975 42036 20968 42036 20972 42037 20974 42037 20973 42037 20973 42038 20974 42038 20977 42038 20973 42039 20977 42039 20975 42039 20975 42040 20977 42040 20976 42040 20975 42041 20976 42041 20968 42041 20968 42042 20976 42042 20980 42042 20974 42043 20978 42043 20977 42043 20977 42044 20978 42044 20979 42044 20977 42045 20979 42045 20976 42045 20976 42046 20979 42046 20981 42046 20976 42047 20981 42047 20980 42047 20980 42048 20981 42048 20987 42048 21037 42049 21040 42049 20996 42049 21011 42050 20982 42050 20989 42050 21040 42051 21041 42051 21063 42051 20989 42052 20982 42052 21041 42052 21041 42053 20982 42053 21064 42053 21041 42054 21064 42054 21063 42054 20993 42055 20996 42055 21061 42055 21061 42056 20996 42056 21040 42056 21061 42057 21040 42057 20983 42057 20983 42058 21040 42058 21063 42058 21014 42059 21013 42059 20984 42059 20985 42060 20986 42060 21019 42060 21019 42061 20986 42061 21049 42061 20981 42062 20979 42062 20987 42062 20987 42063 20979 42063 20978 42063 21037 42064 20996 42064 21050 42064 21050 42065 20996 42065 20988 42065 21050 42066 20988 42066 21051 42066 21051 42067 20988 42067 20987 42067 21051 42068 20987 42068 21049 42068 21049 42069 20987 42069 20978 42069 21049 42070 20978 42070 21019 42070 21011 42071 20989 42071 20984 42071 20984 42072 20989 42072 20990 42072 20984 42073 20990 42073 21014 42073 21077 42074 20998 42074 20994 42074 21099 42075 21077 42075 20995 42075 21099 42076 20995 42076 21071 42076 21071 42077 20995 42077 20991 42077 21071 42078 20991 42078 20992 42078 20992 42079 20991 42079 20993 42079 20992 42080 20993 42080 21061 42080 21077 42081 20994 42081 20995 42081 20995 42082 20994 42082 20970 42082 20995 42083 20970 42083 20991 42083 20991 42084 20970 42084 20996 42084 20991 42085 20996 42085 20993 42085 21110 42086 21024 42086 20969 42086 21110 42087 20969 42087 20997 42087 20997 42088 20969 42088 20998 42088 20997 42089 20998 42089 21079 42089 21008 42090 21048 42090 21007 42090 21104 42091 21069 42091 21103 42091 21103 42092 21069 42092 21003 42092 21103 42093 21003 42093 20999 42093 20999 42094 21003 42094 21000 42094 20999 42095 21000 42095 21100 42095 21100 42096 21000 42096 21005 42096 21100 42097 21005 42097 21001 42097 21001 42098 21005 42098 21007 42098 21001 42099 21007 42099 21002 42099 21002 42100 21007 42100 21048 42100 21069 42101 21010 42101 21003 42101 21003 42102 21010 42102 21004 42102 21003 42103 21004 42103 21000 42103 21000 42104 21004 42104 21012 42104 21000 42105 21012 42105 21005 42105 21005 42106 21012 42106 21006 42106 21005 42107 21006 42107 21007 42107 21007 42108 21006 42108 21009 42108 21007 42109 21009 42109 21008 42109 21008 42110 21009 42110 21015 42110 21010 42111 21011 42111 21004 42111 21004 42112 21011 42112 20984 42112 21004 42113 20984 42113 21012 42113 21012 42114 20984 42114 21013 42114 21012 42115 21013 42115 21006 42115 21006 42116 21013 42116 21014 42116 21006 42117 21014 42117 21009 42117 21009 42118 21014 42118 20990 42118 21009 42119 20990 42119 21015 42119 21015 42120 20990 42120 20989 42120 21016 42121 21018 42121 21023 42121 21092 42122 21017 42122 21090 42122 21090 42123 21017 42123 21018 42123 21090 42124 21018 42124 21089 42124 21089 42125 21018 42125 21016 42125 21089 42126 21016 42126 21080 42126 21080 42127 21016 42127 21030 42127 21020 42128 21029 42128 21030 42128 21019 42129 21029 42129 20985 42129 20985 42130 21029 42130 21020 42130 20985 42131 21020 42131 20986 42131 21017 42132 21021 42132 21018 42132 21018 42133 21021 42133 21022 42133 21018 42134 21022 42134 21023 42134 21023 42135 21022 42135 21053 42135 21023 42136 21053 42136 21052 42136 21030 42137 21016 42137 21020 42137 21020 42138 21016 42138 21023 42138 21020 42139 21023 42139 20986 42139 20986 42140 21023 42140 21052 42140 20986 42141 21052 42141 21049 42141 21110 42142 21105 42142 21024 42142 21024 42143 21105 42143 21025 42143 21105 42144 21117 42144 21025 42144 21025 42145 21117 42145 21121 42145 21025 42146 21121 42146 21026 42146 21111 42147 21027 42147 21112 42147 21112 42148 21027 42148 21026 42148 21112 42149 21026 42149 21028 42149 21028 42150 21026 42150 21121 42150 21019 42151 20978 42151 21029 42151 21029 42152 20978 42152 20974 42152 21029 42153 20974 42153 21030 42153 21030 42154 20974 42154 20972 42154 21030 42155 20972 42155 21080 42155 21080 42156 20972 42156 21027 42156 21046 42157 21045 42157 21031 42157 21031 42158 21045 42158 21034 42158 21031 42159 21034 42159 21060 42159 21060 42160 21034 42160 21059 42160 21045 42161 21032 42161 21034 42161 21034 42162 21032 42162 21033 42162 21034 42163 21033 42163 21036 42163 21059 42164 21034 42164 21035 42164 21035 42165 21034 42165 21036 42165 21035 42166 21036 42166 21056 42166 21056 42167 21036 42167 21037 42167 21056 42168 21037 42168 21050 42168 21040 42169 21037 42169 21038 42169 21038 42170 21037 42170 21036 42170 21038 42171 21036 42171 21039 42171 21039 42172 21036 42172 21033 42172 21041 42173 21040 42173 21038 42173 20989 42174 21041 42174 21043 42174 21041 42175 21038 42175 21043 42175 21043 42176 21038 42176 21039 42176 21043 42177 21039 42177 21042 42177 20989 42178 21043 42178 21015 42178 21015 42179 21043 42179 21042 42179 21015 42180 21042 42180 21008 42180 21008 42181 21042 42181 21044 42181 21008 42182 21044 42182 21048 42182 21045 42183 21044 42183 21032 42183 21032 42184 21044 42184 21042 42184 21032 42185 21042 42185 21033 42185 21033 42186 21042 42186 21039 42186 21045 42187 21046 42187 21044 42187 21044 42188 21046 42188 21047 42188 21044 42189 21047 42189 21048 42189 21048 42190 21047 42190 21002 42190 21051 42191 21049 42191 21052 42191 21050 42192 21051 42192 21054 42192 21051 42193 21052 42193 21054 42193 21054 42194 21052 42194 21053 42194 21054 42195 21053 42195 21055 42195 21050 42196 21054 42196 21056 42196 21056 42197 21054 42197 21055 42197 21056 42198 21055 42198 21035 42198 21035 42199 21055 42199 21057 42199 21035 42200 21057 42200 21059 42200 21017 42201 21057 42201 21021 42201 21021 42202 21057 42202 21055 42202 21021 42203 21055 42203 21022 42203 21022 42204 21055 42204 21053 42204 21017 42205 21092 42205 21057 42205 21057 42206 21092 42206 21058 42206 21057 42207 21058 42207 21059 42207 21059 42208 21058 42208 21060 42208 20992 42209 21061 42209 21062 42209 21062 42210 21061 42210 20983 42210 21062 42211 20983 42211 21066 42211 21066 42212 20983 42212 21063 42212 21066 42213 21063 42213 21067 42213 21067 42214 21063 42214 21064 42214 21067 42215 21064 42215 21068 42215 21068 42216 21064 42216 20982 42216 21068 42217 20982 42217 21010 42217 21010 42218 20982 42218 21011 42218 21071 42219 20992 42219 21065 42219 21065 42220 20992 42220 21062 42220 21065 42221 21062 42221 21074 42221 21074 42222 21062 42222 21066 42222 21074 42223 21066 42223 21075 42223 21075 42224 21066 42224 21067 42224 21075 42225 21067 42225 21076 42225 21076 42226 21067 42226 21068 42226 21076 42227 21068 42227 21069 42227 21069 42228 21068 42228 21010 42228 21099 42229 21071 42229 21070 42229 21070 42230 21071 42230 21065 42230 21070 42231 21065 42231 21072 42231 21072 42232 21065 42232 21074 42232 21072 42233 21074 42233 21073 42233 21073 42234 21074 42234 21075 42234 21073 42235 21075 42235 21093 42235 21093 42236 21075 42236 21076 42236 21093 42237 21076 42237 21104 42237 21104 42238 21076 42238 21069 42238 21099 42239 21098 42239 21078 42239 21099 42240 21078 42240 21077 42240 21077 42241 21078 42241 21079 42241 21077 42242 21079 42242 20998 42242 21118 42243 20957 42243 21081 42243 21080 42244 21027 42244 21081 42244 21081 42245 21027 42245 21111 42245 21118 42246 21081 42246 21084 42246 21111 42247 21082 42247 21081 42247 21081 42248 21082 42248 21083 42248 21081 42249 21083 42249 21084 42249 21092 42250 20959 42250 21058 42250 21058 42251 20959 42251 20960 42251 21058 42252 20960 42252 21060 42252 21046 42253 20963 42253 21085 42253 21046 42254 21085 42254 21047 42254 21047 42255 21085 42255 21086 42255 21047 42256 21086 42256 21002 42256 21060 42257 20960 42257 21031 42257 21031 42258 20960 42258 21087 42258 21031 42259 21087 42259 21046 42259 21046 42260 21087 42260 20963 42260 21080 42261 21081 42261 21089 42261 21089 42262 21081 42262 21088 42262 21089 42263 21088 42263 21090 42263 21090 42264 21088 42264 21091 42264 21090 42265 21091 42265 21092 42265 21092 42266 21091 42266 20959 42266 21104 42267 20966 42267 21093 42267 21093 42268 20966 42268 21094 42268 21093 42269 21094 42269 21073 42269 21096 42270 21097 42270 21132 42270 21132 42271 21097 42271 21095 42271 21096 42272 21130 42272 21097 42272 21097 42273 21130 42273 21131 42273 21097 42274 21131 42274 21098 42274 21073 42275 21094 42275 21072 42275 21072 42276 21094 42276 21097 42276 21072 42277 21097 42277 21070 42277 21070 42278 21097 42278 21098 42278 21070 42279 21098 42279 21099 42279 21002 42280 21086 42280 21001 42280 21001 42281 21086 42281 20964 42281 21001 42282 20964 42282 21100 42282 21100 42283 20964 42283 21101 42283 21100 42284 21101 42284 20999 42284 20999 42285 21101 42285 21102 42285 20999 42286 21102 42286 21103 42286 21103 42287 21102 42287 20965 42287 21103 42288 20965 42288 21104 42288 21104 42289 20965 42289 20966 42289 21117 42290 21105 42290 21116 42290 21114 42291 20958 42291 20957 42291 20956 42292 21113 42292 21106 42292 21106 42293 21113 42293 21107 42293 21106 42294 21107 42294 21122 42294 21122 42295 21107 42295 21108 42295 21122 42296 21108 42296 21109 42296 21109 42297 21108 42297 21116 42297 21109 42298 21116 42298 21110 42298 21110 42299 21116 42299 21105 42299 21119 42300 21112 42300 21028 42300 21111 42301 21112 42301 21082 42301 21082 42302 21112 42302 21119 42302 21082 42303 21119 42303 21083 42303 21083 42304 21119 42304 21084 42304 21113 42305 20958 42305 21107 42305 21107 42306 20958 42306 21114 42306 21107 42307 21114 42307 21108 42307 21108 42308 21114 42308 21115 42308 21108 42309 21115 42309 21116 42309 21116 42310 21115 42310 21120 42310 21116 42311 21120 42311 21117 42311 21117 42312 21120 42312 21121 42312 20957 42313 21118 42313 21114 42313 21114 42314 21118 42314 21084 42314 21114 42315 21084 42315 21115 42315 21115 42316 21084 42316 21119 42316 21115 42317 21119 42317 21120 42317 21120 42318 21119 42318 21028 42318 21120 42319 21028 42319 21121 42319 21110 42320 20997 42320 21127 42320 21110 42321 21127 42321 21109 42321 21109 42322 21127 42322 21126 42322 21109 42323 21126 42323 21122 42323 21122 42324 21126 42324 21125 42324 21122 42325 21125 42325 21106 42325 21106 42326 21125 42326 20961 42326 21106 42327 20961 42327 20956 42327 20962 42328 20961 42328 21123 42328 21123 42329 20961 42329 21125 42329 21123 42330 21125 42330 21124 42330 21124 42331 21125 42331 21126 42331 21124 42332 21126 42332 21133 42332 21133 42333 21126 42333 21127 42333 21133 42334 21127 42334 21128 42334 21128 42335 21127 42335 20997 42335 21128 42336 20997 42336 21079 42336 21096 42337 21132 42337 21129 42337 21132 42338 21095 42338 20962 42338 21096 42339 21129 42339 21130 42339 21130 42340 21129 42340 21134 42340 21130 42341 21134 42341 21131 42341 21131 42342 21134 42342 21078 42342 21131 42343 21078 42343 21098 42343 20962 42344 21123 42344 21132 42344 21132 42345 21123 42345 21124 42345 21132 42346 21124 42346 21129 42346 21129 42347 21124 42347 21133 42347 21129 42348 21133 42348 21134 42348 21134 42349 21133 42349 21128 42349 21134 42350 21128 42350 21078 42350 21078 42351 21128 42351 21079 42351 21135 42352 21412 42352 21406 42352 21398 42353 21394 42353 21399 42353 21399 42354 21394 42354 21400 42354 21399 42355 21400 42355 21403 42355 21403 42356 21400 42356 21137 42356 21385 42357 21393 42357 21390 42357 21418 42358 21136 42358 21419 42358 21419 42359 21136 42359 21137 42359 21419 42360 21137 42360 21138 42360 21138 42361 21137 42361 21400 42361 21138 42362 21400 42362 21383 42362 21383 42363 21400 42363 21139 42363 21383 42364 21139 42364 21384 42364 21384 42365 21139 42365 21135 42365 21384 42366 21135 42366 21387 42366 21406 42367 21408 42367 21135 42367 21135 42368 21408 42368 21405 42368 21135 42369 21405 42369 21387 42369 21387 42370 21405 42370 21385 42370 21387 42371 21385 42371 21389 42371 21389 42372 21385 42372 21390 42372 21155 42373 21218 42373 21156 42373 21218 42374 21189 42374 21149 42374 21274 42375 21269 42375 21160 42375 21160 42376 21269 42376 21268 42376 21160 42377 21268 42377 21140 42377 21159 42378 21227 42378 21235 42378 21227 42379 21159 42379 21161 42379 21158 42380 21228 42380 21274 42380 21172 42381 21141 42381 21150 42381 21161 42382 21153 42382 21323 42382 21323 42383 21153 42383 21151 42383 21323 42384 21151 42384 21142 42384 21142 42385 21151 42385 21150 42385 21142 42386 21150 42386 21143 42386 21143 42387 21150 42387 21141 42387 21143 42388 21141 42388 21174 42388 21256 42389 21251 42389 21154 42389 21154 42390 21251 42390 21250 42390 21154 42391 21250 42391 21152 42391 21144 42392 21309 42392 21366 42392 21309 42393 21144 42393 21146 42393 21145 42394 21368 42394 21367 42394 21366 42395 21145 42395 21144 42395 21144 42396 21145 42396 21367 42396 21144 42397 21367 42397 21146 42397 21146 42398 21367 42398 21147 42398 21146 42399 21147 42399 21148 42399 21218 42400 21149 42400 21156 42400 21156 42401 21149 42401 21281 42401 21156 42402 21281 42402 21157 42402 21172 42403 21150 42403 21152 42403 21152 42404 21150 42404 21151 42404 21152 42405 21151 42405 21154 42405 21154 42406 21151 42406 21153 42406 21154 42407 21153 42407 21162 42407 21268 42408 21155 42408 21140 42408 21140 42409 21155 42409 21156 42409 21140 42410 21156 42410 21148 42410 21148 42411 21156 42411 21157 42411 21148 42412 21157 42412 21146 42412 21235 42413 21158 42413 21159 42413 21159 42414 21158 42414 21274 42414 21159 42415 21274 42415 21161 42415 21161 42416 21274 42416 21160 42416 21161 42417 21160 42417 21153 42417 21153 42418 21160 42418 21140 42418 21153 42419 21140 42419 21162 42419 21162 42420 21140 42420 21148 42420 21162 42421 21148 42421 21154 42421 21154 42422 21148 42422 21147 42422 21154 42423 21147 42423 21256 42423 21256 42424 21147 42424 21367 42424 21168 42425 21163 42425 21329 42425 21163 42426 21168 42426 21420 42426 21164 42427 21173 42427 21165 42427 21176 42428 21402 42428 21177 42428 21177 42429 21402 42429 21414 42429 21177 42430 21414 42430 21178 42430 21178 42431 21414 42431 21415 42431 21169 42432 21416 42432 21167 42432 21167 42433 21416 42433 21417 42433 21167 42434 21417 42434 21420 42434 21164 42435 21165 42435 21166 42435 21166 42436 21165 42436 21179 42436 21166 42437 21179 42437 21330 42437 21420 42438 21168 42438 21167 42438 21167 42439 21168 42439 21180 42439 21167 42440 21180 42440 21169 42440 21169 42441 21180 42441 21181 42441 21169 42442 21181 42442 21170 42442 21152 42443 21171 42443 21172 42443 21172 42444 21171 42444 21182 42444 21172 42445 21182 42445 21141 42445 21141 42446 21182 42446 21173 42446 21141 42447 21173 42447 21174 42447 21174 42448 21173 42448 21164 42448 21174 42449 21164 42449 21143 42449 21175 42450 21176 42450 21183 42450 21183 42451 21176 42451 21177 42451 21183 42452 21177 42452 21170 42452 21170 42453 21177 42453 21178 42453 21170 42454 21178 42454 21169 42454 21169 42455 21178 42455 21415 42455 21169 42456 21415 42456 21416 42456 21329 42457 21330 42457 21168 42457 21168 42458 21330 42458 21179 42458 21168 42459 21179 42459 21180 42459 21180 42460 21179 42460 21165 42460 21180 42461 21165 42461 21181 42461 21181 42462 21165 42462 21173 42462 21181 42463 21173 42463 21170 42463 21170 42464 21173 42464 21182 42464 21170 42465 21182 42465 21183 42465 21183 42466 21182 42466 21171 42466 21183 42467 21171 42467 21175 42467 21184 42468 21185 42468 21186 42468 21202 42469 21203 42469 21187 42469 21185 42470 21184 42470 21221 42470 21221 42471 21184 42471 21188 42471 21221 42472 21188 42472 21219 42472 21149 42473 21189 42473 21283 42473 21283 42474 21189 42474 21219 42474 21283 42475 21219 42475 21285 42475 21285 42476 21219 42476 21188 42476 21195 42477 21190 42477 21196 42477 21196 42478 21190 42478 21222 42478 21196 42479 21222 42479 21199 42479 21199 42480 21222 42480 21191 42480 21199 42481 21191 42481 21192 42481 21193 42482 21223 42482 21407 42482 21407 42483 21223 42483 21194 42483 21407 42484 21194 42484 21409 42484 21410 42485 21224 42485 21217 42485 21217 42486 21224 42486 21197 42486 21217 42487 21197 42487 21216 42487 21216 42488 21197 42488 21198 42488 21216 42489 21198 42489 21200 42489 21224 42490 21195 42490 21197 42490 21197 42491 21195 42491 21196 42491 21197 42492 21196 42492 21198 42492 21198 42493 21196 42493 21199 42493 21198 42494 21199 42494 21200 42494 21200 42495 21199 42495 21192 42495 21200 42496 21192 42496 21201 42496 21201 42497 21192 42497 21220 42497 21201 42498 21220 42498 21218 42498 21202 42499 21211 42499 21203 42499 21203 42500 21211 42500 21411 42500 21203 42501 21411 42501 21413 42501 21204 42502 21205 42502 21206 42502 21206 42503 21205 42503 21210 42503 21206 42504 21210 42504 21207 42504 21207 42505 21210 42505 21209 42505 21207 42506 21209 42506 21208 42506 21290 42507 21208 42507 21413 42507 21413 42508 21208 42508 21209 42508 21413 42509 21209 42509 21203 42509 21203 42510 21209 42510 21210 42510 21203 42511 21210 42511 21187 42511 21187 42512 21210 42512 21205 42512 21193 42513 21211 42513 21223 42513 21223 42514 21211 42514 21202 42514 21223 42515 21202 42515 21212 42515 21212 42516 21202 42516 21187 42516 21212 42517 21187 42517 21186 42517 21186 42518 21187 42518 21205 42518 21186 42519 21205 42519 21184 42519 21184 42520 21205 42520 21204 42520 21184 42521 21204 42521 21188 42521 21218 42522 21155 42522 21201 42522 21201 42523 21155 42523 21213 42523 21201 42524 21213 42524 21200 42524 21200 42525 21213 42525 21214 42525 21200 42526 21214 42526 21216 42526 21216 42527 21214 42527 21215 42527 21216 42528 21215 42528 21217 42528 21217 42529 21215 42529 21404 42529 21217 42530 21404 42530 21410 42530 21189 42531 21218 42531 21219 42531 21219 42532 21218 42532 21220 42532 21219 42533 21220 42533 21221 42533 21221 42534 21220 42534 21192 42534 21221 42535 21192 42535 21185 42535 21185 42536 21192 42536 21191 42536 21185 42537 21191 42537 21186 42537 21186 42538 21191 42538 21222 42538 21186 42539 21222 42539 21212 42539 21212 42540 21222 42540 21190 42540 21212 42541 21190 42541 21223 42541 21223 42542 21190 42542 21195 42542 21223 42543 21195 42543 21194 42543 21194 42544 21195 42544 21224 42544 21194 42545 21224 42545 21409 42545 21409 42546 21224 42546 21410 42546 21225 42547 21226 42547 21240 42547 21244 42548 21276 42548 21275 42548 21228 42549 21158 42549 21236 42549 21235 42550 21227 42550 21317 42550 21274 42551 21228 42551 21245 42551 21245 42552 21228 42552 21236 42552 21245 42553 21236 42553 21242 42553 21242 42554 21236 42554 21229 42554 21242 42555 21229 42555 21241 42555 21388 42556 21230 42556 21239 42556 21239 42557 21230 42557 21231 42557 21230 42558 21232 42558 21231 42558 21231 42559 21232 42559 21391 42559 21231 42560 21391 42560 21392 42560 21276 42561 21244 42561 21233 42561 21233 42562 21244 42562 21243 42562 21233 42563 21243 42563 21279 42563 21279 42564 21243 42564 21234 42564 21279 42565 21234 42565 21280 42565 21229 42566 21239 42566 21241 42566 21241 42567 21239 42567 21231 42567 21241 42568 21231 42568 21225 42568 21225 42569 21231 42569 21392 42569 21225 42570 21392 42570 21226 42570 21158 42571 21235 42571 21236 42571 21236 42572 21235 42572 21317 42572 21236 42573 21317 42573 21229 42573 21229 42574 21317 42574 21237 42574 21229 42575 21237 42575 21239 42575 21239 42576 21237 42576 21238 42576 21239 42577 21238 42577 21388 42577 21388 42578 21238 42578 21316 42578 21240 42579 21280 42579 21225 42579 21225 42580 21280 42580 21234 42580 21225 42581 21234 42581 21241 42581 21241 42582 21234 42582 21243 42582 21241 42583 21243 42583 21242 42583 21242 42584 21243 42584 21244 42584 21242 42585 21244 42585 21245 42585 21245 42586 21244 42586 21275 42586 21245 42587 21275 42587 21274 42587 21264 42588 21246 42588 21247 42588 21247 42589 21246 42589 21358 42589 21247 42590 21358 42590 21248 42590 21248 42591 21358 42591 21372 42591 21249 42592 21252 42592 21255 42592 21252 42593 21250 42593 21251 42593 21251 42594 21256 42594 21252 42594 21252 42595 21256 42595 21257 42595 21252 42596 21257 42596 21255 42596 21247 42597 21253 42597 21264 42597 21264 42598 21253 42598 21254 42598 21264 42599 21254 42599 21262 42599 21262 42600 21254 42600 21249 42600 21262 42601 21249 42601 21260 42601 21260 42602 21249 42602 21255 42602 21260 42603 21255 42603 21370 42603 21256 42604 21367 42604 21257 42604 21257 42605 21367 42605 21258 42605 21257 42606 21258 42606 21255 42606 21255 42607 21258 42607 21259 42607 21255 42608 21259 42608 21370 42608 21370 42609 21261 42609 21260 42609 21260 42610 21261 42610 21263 42610 21260 42611 21263 42611 21262 42611 21262 42612 21263 42612 21265 42612 21262 42613 21265 42613 21264 42613 21264 42614 21265 42614 21266 42614 21264 42615 21266 42615 21246 42615 21152 42616 21250 42616 21171 42616 21171 42617 21250 42617 21252 42617 21171 42618 21252 42618 21175 42618 21175 42619 21252 42619 21249 42619 21175 42620 21249 42620 21176 42620 21176 42621 21249 42621 21254 42621 21176 42622 21254 42622 21402 42622 21402 42623 21254 42623 21253 42623 21280 42624 21240 42624 21386 42624 21213 42625 21270 42625 21214 42625 21214 42626 21270 42626 21273 42626 21214 42627 21273 42627 21215 42627 21215 42628 21273 42628 21267 42628 21215 42629 21267 42629 21404 42629 21269 42630 21270 42630 21268 42630 21268 42631 21270 42631 21213 42631 21268 42632 21213 42632 21155 42632 21269 42633 21271 42633 21270 42633 21270 42634 21271 42634 21272 42634 21270 42635 21272 42635 21273 42635 21273 42636 21272 42636 21277 42636 21273 42637 21277 42637 21267 42637 21269 42638 21274 42638 21271 42638 21271 42639 21274 42639 21275 42639 21271 42640 21275 42640 21272 42640 21272 42641 21275 42641 21276 42641 21272 42642 21276 42642 21277 42642 21277 42643 21276 42643 21233 42643 21277 42644 21233 42644 21279 42644 21404 42645 21267 42645 21278 42645 21278 42646 21267 42646 21277 42646 21278 42647 21277 42647 21386 42647 21386 42648 21277 42648 21279 42648 21386 42649 21279 42649 21280 42649 21310 42650 21146 42650 21157 42650 21281 42651 21149 42651 21282 42651 21282 42652 21149 42652 21283 42652 21282 42653 21283 42653 21284 42653 21284 42654 21283 42654 21285 42654 21284 42655 21285 42655 21291 42655 21291 42656 21285 42656 21188 42656 21291 42657 21188 42657 21292 42657 21292 42658 21188 42658 21204 42658 21292 42659 21204 42659 21286 42659 21286 42660 21204 42660 21206 42660 21286 42661 21206 42661 21287 42661 21287 42662 21206 42662 21207 42662 21287 42663 21207 42663 21288 42663 21288 42664 21207 42664 21208 42664 21296 42665 21288 42665 21289 42665 21289 42666 21288 42666 21208 42666 21289 42667 21208 42667 21290 42667 21281 42668 21282 42668 21305 42668 21305 42669 21282 42669 21284 42669 21305 42670 21284 42670 21304 42670 21304 42671 21284 42671 21291 42671 21304 42672 21291 42672 21302 42672 21302 42673 21291 42673 21292 42673 21302 42674 21292 42674 21300 42674 21300 42675 21292 42675 21286 42675 21300 42676 21286 42676 21293 42676 21293 42677 21286 42677 21287 42677 21293 42678 21287 42678 21294 42678 21294 42679 21287 42679 21288 42679 21294 42680 21288 42680 21295 42680 21295 42681 21288 42681 21296 42681 21295 42682 21296 42682 21306 42682 21306 42683 21297 42683 21295 42683 21295 42684 21297 42684 21298 42684 21295 42685 21298 42685 21294 42685 21294 42686 21298 42686 21299 42686 21294 42687 21299 42687 21293 42687 21293 42688 21299 42688 21301 42688 21293 42689 21301 42689 21300 42689 21300 42690 21301 42690 21313 42690 21300 42691 21313 42691 21302 42691 21302 42692 21313 42692 21303 42692 21302 42693 21303 42693 21304 42693 21304 42694 21303 42694 21310 42694 21304 42695 21310 42695 21305 42695 21305 42696 21310 42696 21157 42696 21305 42697 21157 42697 21281 42697 21306 42698 21401 42698 21297 42698 21297 42699 21401 42699 21350 42699 21297 42700 21350 42700 21298 42700 21298 42701 21350 42701 21307 42701 21298 42702 21307 42702 21299 42702 21299 42703 21307 42703 21308 42703 21299 42704 21308 42704 21301 42704 21301 42705 21308 42705 21339 42705 21301 42706 21339 42706 21313 42706 21309 42707 21146 42707 21365 42707 21365 42708 21146 42708 21310 42708 21365 42709 21310 42709 21311 42709 21311 42710 21310 42710 21303 42710 21311 42711 21303 42711 21312 42711 21312 42712 21303 42712 21313 42712 21312 42713 21313 42713 21314 42713 21314 42714 21313 42714 21339 42714 21319 42715 21328 42715 21315 42715 21315 42716 21316 42716 21318 42716 21318 42717 21316 42717 21238 42717 21318 42718 21238 42718 21320 42718 21320 42719 21238 42719 21237 42719 21320 42720 21237 42720 21322 42720 21322 42721 21237 42721 21317 42721 21323 42722 21322 42722 21161 42722 21161 42723 21322 42723 21317 42723 21161 42724 21317 42724 21227 42724 21315 42725 21318 42725 21319 42725 21319 42726 21318 42726 21320 42726 21319 42727 21320 42727 21321 42727 21321 42728 21320 42728 21322 42728 21321 42729 21322 42729 21325 42729 21325 42730 21322 42730 21323 42730 21325 42731 21323 42731 21142 42731 21326 42732 21324 42732 21327 42732 21142 42733 21332 42733 21325 42733 21325 42734 21332 42734 21331 42734 21325 42735 21331 42735 21321 42735 21321 42736 21331 42736 21326 42736 21321 42737 21326 42737 21319 42737 21319 42738 21326 42738 21327 42738 21319 42739 21327 42739 21328 42739 21329 42740 21324 42740 21330 42740 21330 42741 21324 42741 21326 42741 21330 42742 21326 42742 21166 42742 21166 42743 21326 42743 21331 42743 21166 42744 21331 42744 21164 42744 21164 42745 21331 42745 21332 42745 21164 42746 21332 42746 21143 42746 21143 42747 21332 42747 21142 42747 21373 42748 21360 42748 21372 42748 21379 42749 21334 42749 21333 42749 21333 42750 21334 42750 21353 42750 21333 42751 21353 42751 21340 42751 21335 42752 21369 42752 21337 42752 21337 42753 21365 42753 21336 42753 21336 42754 21365 42754 21311 42754 21336 42755 21311 42755 21312 42755 21335 42756 21337 42756 21378 42756 21378 42757 21337 42757 21336 42757 21378 42758 21336 42758 21338 42758 21338 42759 21336 42759 21312 42759 21338 42760 21312 42760 21380 42760 21380 42761 21312 42761 21314 42761 21380 42762 21314 42762 21382 42762 21382 42763 21314 42763 21339 42763 21382 42764 21339 42764 21308 42764 21340 42765 21353 42765 21377 42765 21377 42766 21353 42766 21355 42766 21377 42767 21355 42767 21376 42767 21376 42768 21355 42768 21363 42768 21376 42769 21363 42769 21341 42769 21401 42770 21395 42770 21342 42770 21342 42771 21395 42771 21396 42771 21342 42772 21396 42772 21343 42772 21344 42773 21345 42773 21346 42773 21346 42774 21345 42774 21342 42774 21346 42775 21342 42775 21362 42775 21362 42776 21342 42776 21343 42776 21362 42777 21343 42777 21361 42777 21361 42778 21343 42778 21347 42778 21361 42779 21347 42779 21348 42779 21348 42780 21347 42780 21397 42780 21348 42781 21397 42781 21360 42781 21352 42782 21351 42782 21349 42782 21349 42783 21351 42783 21307 42783 21349 42784 21307 42784 21350 42784 21344 42785 21364 42785 21352 42785 21352 42786 21364 42786 21381 42786 21352 42787 21381 42787 21351 42787 21344 42788 21352 42788 21345 42788 21345 42789 21352 42789 21349 42789 21345 42790 21349 42790 21342 42790 21342 42791 21349 42791 21350 42791 21342 42792 21350 42792 21401 42792 21334 42793 21354 42793 21353 42793 21353 42794 21354 42794 21356 42794 21353 42795 21356 42795 21355 42795 21355 42796 21356 42796 21357 42796 21355 42797 21357 42797 21363 42797 21358 42798 21246 42798 21374 42798 21374 42799 21246 42799 21266 42799 21374 42800 21266 42800 21375 42800 21375 42801 21266 42801 21265 42801 21375 42802 21265 42802 21359 42802 21359 42803 21265 42803 21263 42803 21359 42804 21263 42804 21371 42804 21360 42805 21373 42805 21348 42805 21348 42806 21373 42806 21341 42806 21348 42807 21341 42807 21361 42807 21361 42808 21341 42808 21363 42808 21361 42809 21363 42809 21362 42809 21362 42810 21363 42810 21357 42810 21362 42811 21357 42811 21346 42811 21346 42812 21357 42812 21356 42812 21346 42813 21356 42813 21344 42813 21344 42814 21356 42814 21354 42814 21344 42815 21354 42815 21364 42815 21364 42816 21354 42816 21334 42816 21364 42817 21334 42817 21381 42817 21309 42818 21365 42818 21366 42818 21366 42819 21365 42819 21337 42819 21366 42820 21337 42820 21145 42820 21145 42821 21337 42821 21369 42821 21145 42822 21369 42822 21368 42822 21367 42823 21368 42823 21258 42823 21258 42824 21368 42824 21369 42824 21258 42825 21369 42825 21259 42825 21259 42826 21369 42826 21335 42826 21259 42827 21335 42827 21370 42827 21370 42828 21335 42828 21371 42828 21370 42829 21371 42829 21261 42829 21261 42830 21371 42830 21263 42830 21372 42831 21358 42831 21373 42831 21373 42832 21358 42832 21374 42832 21373 42833 21374 42833 21341 42833 21341 42834 21374 42834 21375 42834 21341 42835 21375 42835 21376 42835 21376 42836 21375 42836 21359 42836 21376 42837 21359 42837 21377 42837 21377 42838 21359 42838 21371 42838 21377 42839 21371 42839 21340 42839 21340 42840 21371 42840 21335 42840 21340 42841 21335 42841 21333 42841 21333 42842 21335 42842 21378 42842 21333 42843 21378 42843 21379 42843 21379 42844 21378 42844 21338 42844 21379 42845 21338 42845 21334 42845 21334 42846 21338 42846 21380 42846 21334 42847 21380 42847 21381 42847 21381 42848 21380 42848 21382 42848 21381 42849 21382 42849 21351 42849 21351 42850 21382 42850 21308 42850 21351 42851 21308 42851 21307 42851 21329 42852 21138 42852 21324 42852 21324 42853 21138 42853 21383 42853 21324 42854 21383 42854 21327 42854 21327 42855 21383 42855 21328 42855 21328 42856 21383 42856 21384 42856 21328 42857 21384 42857 21315 42857 21315 42858 21384 42858 21387 42858 21315 42859 21387 42859 21316 42859 21240 42860 21385 42860 21386 42860 21386 42861 21385 42861 21405 42861 21386 42862 21405 42862 21278 42862 21278 42863 21405 42863 21404 42863 21316 42864 21387 42864 21388 42864 21388 42865 21387 42865 21389 42865 21388 42866 21389 42866 21230 42866 21230 42867 21389 42867 21232 42867 21232 42868 21389 42868 21390 42868 21232 42869 21390 42869 21391 42869 21391 42870 21390 42870 21392 42870 21392 42871 21390 42871 21393 42871 21392 42872 21393 42872 21226 42872 21226 42873 21393 42873 21385 42873 21226 42874 21385 42874 21240 42874 21401 42875 21400 42875 21395 42875 21395 42876 21400 42876 21394 42876 21395 42877 21394 42877 21396 42877 21396 42878 21394 42878 21343 42878 21343 42879 21394 42879 21398 42879 21343 42880 21398 42880 21347 42880 21347 42881 21398 42881 21397 42881 21397 42882 21398 42882 21399 42882 21397 42883 21399 42883 21360 42883 21360 42884 21399 42884 21403 42884 21360 42885 21403 42885 21372 42885 21290 42886 21135 42886 21289 42886 21289 42887 21135 42887 21139 42887 21289 42888 21139 42888 21296 42888 21296 42889 21139 42889 21306 42889 21306 42890 21139 42890 21400 42890 21306 42891 21400 42891 21401 42891 21137 42892 21402 42892 21403 42892 21403 42893 21402 42893 21253 42893 21253 42894 21247 42894 21403 42894 21403 42895 21247 42895 21248 42895 21403 42896 21248 42896 21372 42896 21404 42897 21405 42897 21410 42897 21410 42898 21405 42898 21408 42898 21211 42899 21193 42899 21406 42899 21406 42900 21193 42900 21407 42900 21406 42901 21407 42901 21408 42901 21408 42902 21407 42902 21409 42902 21408 42903 21409 42903 21410 42903 21211 42904 21406 42904 21411 42904 21411 42905 21406 42905 21412 42905 21411 42906 21412 42906 21413 42906 21413 42907 21412 42907 21135 42907 21413 42908 21135 42908 21290 42908 21414 42909 21402 42909 21137 42909 21414 42910 21137 42910 21415 42910 21415 42911 21137 42911 21136 42911 21415 42912 21136 42912 21416 42912 21416 42913 21136 42913 21418 42913 21416 42914 21418 42914 21417 42914 21417 42915 21418 42915 21420 42915 21420 42916 21418 42916 21419 42916 21420 42917 21419 42917 21163 42917 21163 42918 21419 42918 21138 42918 21163 42919 21138 42919 21329 42919 21599 42920 21595 42920 21583 42920 21583 42921 21595 42921 21426 42921 21424 42922 21421 42922 21422 42922 21585 42923 21583 42923 21584 42923 21584 42924 21583 42924 21424 42924 21584 42925 21424 42925 21423 42925 21423 42926 21424 42926 21422 42926 21585 42927 21425 42927 21583 42927 21583 42928 21425 42928 21600 42928 21583 42929 21600 42929 21599 42929 21595 42930 21594 42930 21426 42930 21426 42931 21594 42931 21427 42931 21426 42932 21427 42932 21598 42932 21591 42933 21428 42933 21429 42933 21429 42934 21428 42934 21430 42934 21429 42935 21430 42935 21593 42935 21593 42936 21430 42936 21426 42936 21593 42937 21426 42937 21588 42937 21588 42938 21426 42938 21598 42938 21448 42939 21473 42939 21431 42939 21431 42940 21473 42940 21439 42940 21431 42941 21439 42941 21445 42941 21439 42942 21437 42942 21445 42942 21445 42943 21437 42943 21432 42943 21445 42944 21432 42944 21433 42944 21433 42945 21432 42945 21434 42945 21433 42946 21434 42946 21460 42946 21461 42947 21434 42947 21435 42947 21435 42948 21434 42948 21432 42948 21435 42949 21432 42949 21436 42949 21436 42950 21432 42950 21437 42950 21436 42951 21437 42951 21463 42951 21463 42952 21437 42952 21439 42952 21463 42953 21439 42953 21438 42953 21438 42954 21439 42954 21473 42954 21443 42955 21451 42955 21440 42955 21449 42956 21513 42956 21450 42956 21451 42957 21441 42957 21449 42957 21441 42958 21451 42958 21442 42958 21442 42959 21451 42959 21443 42959 21442 42960 21443 42960 21512 42960 21433 42961 21460 42961 21443 42961 21443 42962 21460 42962 21444 42962 21443 42963 21444 42963 21512 42963 21452 42964 21445 42964 21433 42964 21448 42965 21431 42965 21446 42965 21446 42966 21431 42966 21445 42966 21445 42967 21452 42967 21446 42967 21446 42968 21452 42968 21447 42968 21446 42969 21447 42969 21448 42969 21519 42970 21448 42970 21447 42970 21449 42971 21450 42971 21451 42971 21451 42972 21450 42972 21524 42972 21451 42973 21524 42973 21440 42973 21440 42974 21524 42974 21521 42974 21440 42975 21521 42975 21453 42975 21433 42976 21443 42976 21452 42976 21452 42977 21443 42977 21440 42977 21452 42978 21440 42978 21447 42978 21447 42979 21440 42979 21453 42979 21447 42980 21453 42980 21519 42980 21454 42981 21568 42981 21508 42981 21568 42982 21454 42982 21565 42982 21455 42983 21501 42983 21456 42983 21508 42984 21455 42984 21454 42984 21454 42985 21455 42985 21456 42985 21454 42986 21456 42986 21565 42986 21565 42987 21456 42987 21510 42987 21565 42988 21510 42988 21564 42988 21458 42989 21459 42989 21457 42989 21457 42990 21459 42990 21434 42990 21457 42991 21434 42991 21461 42991 21458 42992 21564 42992 21459 42992 21459 42993 21564 42993 21510 42993 21459 42994 21510 42994 21434 42994 21434 42995 21510 42995 21460 42995 21562 42996 21461 42996 21435 42996 21438 42997 21462 42997 21463 42997 21463 42998 21462 42998 21464 42998 21463 42999 21464 42999 21436 42999 21436 43000 21464 43000 21550 43000 21436 43001 21550 43001 21435 43001 21435 43002 21550 43002 21465 43002 21435 43003 21465 43003 21562 43003 21562 43004 21465 43004 21466 43004 21473 43005 21448 43005 21467 43005 21470 43006 21438 43006 21536 43006 21536 43007 21438 43007 21473 43007 21536 43008 21473 43008 21534 43008 21537 43009 21468 43009 21482 43009 21482 43010 21469 43010 21537 43010 21537 43011 21469 43011 21580 43011 21537 43012 21580 43012 21470 43012 21470 43013 21580 43013 21551 43013 21470 43014 21551 43014 21438 43014 21471 43015 21472 43015 21581 43015 21581 43016 21472 43016 21580 43016 21581 43017 21580 43017 21525 43017 21525 43018 21580 43018 21469 43018 21467 43019 21490 43019 21473 43019 21473 43020 21490 43020 21495 43020 21473 43021 21495 43021 21534 43021 21483 43022 21477 43022 21484 43022 21480 43023 21479 43023 21483 43023 21541 43024 21596 43024 21478 43024 21474 43025 21475 43025 21476 43025 21476 43026 21475 43026 21477 43026 21476 43027 21477 43027 21478 43027 21478 43028 21477 43028 21483 43028 21478 43029 21483 43029 21541 43029 21541 43030 21483 43030 21479 43030 21481 43031 21538 43031 21480 43031 21537 43032 21538 43032 21468 43032 21468 43033 21538 43033 21481 43033 21468 43034 21481 43034 21482 43034 21475 43035 21530 43035 21477 43035 21477 43036 21530 43036 21528 43036 21477 43037 21528 43037 21484 43037 21484 43038 21528 43038 21527 43038 21484 43039 21527 43039 21485 43039 21480 43040 21483 43040 21481 43040 21481 43041 21483 43041 21484 43041 21481 43042 21484 43042 21482 43042 21482 43043 21484 43043 21485 43043 21482 43044 21485 43044 21469 43044 21489 43045 21488 43045 21494 43045 21486 43046 21492 43046 21597 43046 21597 43047 21492 43047 21488 43047 21597 43048 21488 43048 21487 43048 21487 43049 21488 43049 21489 43049 21487 43050 21489 43050 21523 43050 21523 43051 21489 43051 21522 43051 21491 43052 21520 43052 21522 43052 21467 43053 21520 43053 21490 43053 21490 43054 21520 43054 21491 43054 21490 43055 21491 43055 21495 43055 21492 43056 21545 43056 21488 43056 21488 43057 21545 43057 21543 43057 21488 43058 21543 43058 21494 43058 21494 43059 21543 43059 21493 43059 21494 43060 21493 43060 21535 43060 21522 43061 21489 43061 21491 43061 21491 43062 21489 43062 21494 43062 21491 43063 21494 43063 21495 43063 21495 43064 21494 43064 21535 43064 21495 43065 21535 43065 21534 43065 21498 43066 21496 43066 21586 43066 21504 43067 21506 43067 21507 43067 21504 43068 21497 43068 21498 43068 21498 43069 21497 43069 21592 43069 21498 43070 21592 43070 21496 43070 21501 43071 21455 43071 21499 43071 21499 43072 21455 43072 21508 43072 21518 43073 21517 43073 21505 43073 21505 43074 21517 43074 21516 43074 21505 43075 21516 43075 21500 43075 21500 43076 21516 43076 21515 43076 21500 43077 21515 43077 21499 43077 21499 43078 21515 43078 21456 43078 21499 43079 21456 43079 21501 43079 21561 43080 21589 43080 21502 43080 21502 43081 21589 43081 21503 43081 21502 43082 21503 43082 21504 43082 21504 43083 21503 43083 21590 43083 21504 43084 21590 43084 21497 43084 21504 43085 21507 43085 21502 43085 21502 43086 21507 43086 21567 43086 21502 43087 21567 43087 21561 43087 21586 43088 21518 43088 21498 43088 21498 43089 21518 43089 21505 43089 21498 43090 21505 43090 21504 43090 21504 43091 21505 43091 21500 43091 21504 43092 21500 43092 21506 43092 21506 43093 21500 43093 21499 43093 21506 43094 21499 43094 21507 43094 21507 43095 21499 43095 21508 43095 21507 43096 21508 43096 21567 43096 21567 43097 21508 43097 21568 43097 21509 43098 21587 43098 21513 43098 21460 43099 21510 43099 21444 43099 21444 43100 21510 43100 21511 43100 21444 43101 21511 43101 21512 43101 21512 43102 21511 43102 21514 43102 21513 43103 21449 43103 21509 43103 21509 43104 21449 43104 21441 43104 21509 43105 21441 43105 21514 43105 21514 43106 21441 43106 21442 43106 21514 43107 21442 43107 21512 43107 21510 43108 21456 43108 21511 43108 21511 43109 21456 43109 21515 43109 21511 43110 21515 43110 21514 43110 21514 43111 21515 43111 21516 43111 21514 43112 21516 43112 21509 43112 21509 43113 21516 43113 21517 43113 21509 43114 21517 43114 21587 43114 21587 43115 21517 43115 21518 43115 21587 43116 21518 43116 21586 43116 21448 43117 21519 43117 21467 43117 21467 43118 21519 43118 21520 43118 21519 43119 21453 43119 21520 43119 21520 43120 21453 43120 21521 43120 21520 43121 21521 43121 21522 43121 21513 43122 21523 43122 21450 43122 21450 43123 21523 43123 21522 43123 21450 43124 21522 43124 21524 43124 21524 43125 21522 43125 21521 43125 21525 43126 21469 43126 21526 43126 21526 43127 21469 43127 21485 43127 21526 43128 21485 43128 21569 43128 21569 43129 21485 43129 21527 43129 21569 43130 21527 43130 21579 43130 21579 43131 21527 43131 21528 43131 21579 43132 21528 43132 21529 43132 21529 43133 21528 43133 21530 43133 21529 43134 21530 43134 21531 43134 21531 43135 21530 43135 21475 43135 21531 43136 21475 43136 21532 43136 21532 43137 21475 43137 21474 43137 21539 43138 21492 43138 21486 43138 21533 43139 21542 43139 21544 43139 21536 43140 21534 43140 21535 43140 21536 43141 21542 43141 21470 43141 21470 43142 21542 43142 21533 43142 21470 43143 21533 43143 21537 43143 21537 43144 21533 43144 21538 43144 21479 43145 21480 43145 21546 43145 21546 43146 21480 43146 21538 43146 21539 43147 21540 43147 21546 43147 21546 43148 21540 43148 21541 43148 21546 43149 21541 43149 21479 43149 21536 43150 21535 43150 21542 43150 21542 43151 21535 43151 21493 43151 21542 43152 21493 43152 21544 43152 21544 43153 21493 43153 21543 43153 21544 43154 21543 43154 21545 43154 21538 43155 21533 43155 21546 43155 21546 43156 21533 43156 21544 43156 21546 43157 21544 43157 21539 43157 21539 43158 21544 43158 21545 43158 21539 43159 21545 43159 21492 43159 21596 43160 21541 43160 21547 43160 21547 43161 21541 43161 21540 43161 21547 43162 21540 43162 21548 43162 21548 43163 21540 43163 21539 43163 21548 43164 21539 43164 21549 43164 21549 43165 21539 43165 21486 43165 21462 43166 21438 43166 21554 43166 21554 43167 21438 43167 21551 43167 21462 43168 21554 43168 21464 43168 21464 43169 21554 43169 21556 43169 21464 43170 21556 43170 21550 43170 21550 43171 21556 43171 21465 43171 21465 43172 21556 43172 21557 43172 21465 43173 21557 43173 21466 43173 21551 43174 21580 43174 21552 43174 21551 43175 21552 43175 21554 43175 21554 43176 21552 43176 21553 43176 21554 43177 21553 43177 21556 43177 21556 43178 21553 43178 21555 43178 21556 43179 21555 43179 21557 43179 21562 43180 21466 43180 21582 43180 21562 43181 21582 43181 21563 43181 21563 43182 21582 43182 21559 43182 21563 43183 21559 43183 21558 43183 21558 43184 21559 43184 21560 43184 21558 43185 21560 43185 21566 43185 21566 43186 21560 43186 21561 43186 21566 43187 21561 43187 21567 43187 21461 43188 21562 43188 21457 43188 21457 43189 21562 43189 21563 43189 21457 43190 21563 43190 21458 43190 21458 43191 21563 43191 21558 43191 21458 43192 21558 43192 21564 43192 21564 43193 21558 43193 21566 43193 21564 43194 21566 43194 21565 43194 21565 43195 21566 43195 21567 43195 21565 43196 21567 43196 21568 43196 21526 43197 21569 43197 21570 43197 21579 43198 21529 43198 21574 43198 21531 43199 21532 43199 21573 43199 21555 43200 21553 43200 21571 43200 21571 43201 21553 43201 21576 43201 21571 43202 21576 43202 21572 43202 21572 43203 21576 43203 21577 43203 21572 43204 21577 43204 21573 43204 21573 43205 21577 43205 21574 43205 21573 43206 21574 43206 21531 43206 21531 43207 21574 43207 21529 43207 21553 43208 21552 43208 21576 43208 21576 43209 21552 43209 21575 43209 21576 43210 21575 43210 21577 43210 21577 43211 21575 43211 21578 43211 21577 43212 21578 43212 21574 43212 21574 43213 21578 43213 21570 43213 21574 43214 21570 43214 21579 43214 21579 43215 21570 43215 21569 43215 21552 43216 21580 43216 21575 43216 21575 43217 21580 43217 21472 43217 21575 43218 21472 43218 21578 43218 21578 43219 21472 43219 21471 43219 21578 43220 21471 43220 21570 43220 21570 43221 21471 43221 21581 43221 21570 43222 21581 43222 21526 43222 21526 43223 21581 43223 21525 43223 21532 43224 21584 43224 21573 43224 21573 43225 21584 43225 21423 43225 21573 43226 21423 43226 21572 43226 21572 43227 21423 43227 21422 43227 21572 43228 21422 43228 21571 43228 21571 43229 21422 43229 21421 43229 21571 43230 21421 43230 21555 43230 21555 43231 21421 43231 21424 43231 21555 43232 21424 43232 21557 43232 21557 43233 21424 43233 21583 43233 21466 43234 21557 43234 21582 43234 21582 43235 21557 43235 21583 43235 21582 43236 21583 43236 21559 43236 21559 43237 21583 43237 21560 43237 21583 43238 21426 43238 21560 43238 21560 43239 21426 43239 21430 43239 21560 43240 21430 43240 21561 43240 21532 43241 21474 43241 21584 43241 21584 43242 21474 43242 21585 43242 21586 43243 21593 43243 21587 43243 21587 43244 21593 43244 21588 43244 21587 43245 21588 43245 21513 43245 21513 43246 21588 43246 21523 43246 21589 43247 21561 43247 21430 43247 21589 43248 21430 43248 21503 43248 21503 43249 21430 43249 21428 43249 21503 43250 21428 43250 21590 43250 21590 43251 21428 43251 21591 43251 21590 43252 21591 43252 21497 43252 21497 43253 21591 43253 21429 43253 21497 43254 21429 43254 21592 43254 21592 43255 21429 43255 21496 43255 21496 43256 21429 43256 21593 43256 21496 43257 21593 43257 21586 43257 21486 43258 21594 43258 21549 43258 21549 43259 21594 43259 21595 43259 21549 43260 21595 43260 21548 43260 21548 43261 21595 43261 21547 43261 21547 43262 21595 43262 21599 43262 21547 43263 21599 43263 21596 43263 21523 43264 21588 43264 21487 43264 21487 43265 21588 43265 21598 43265 21487 43266 21598 43266 21597 43266 21597 43267 21598 43267 21427 43267 21597 43268 21427 43268 21486 43268 21486 43269 21427 43269 21594 43269 21596 43270 21599 43270 21478 43270 21478 43271 21599 43271 21600 43271 21478 43272 21600 43272 21476 43272 21476 43273 21600 43273 21425 43273 21476 43274 21425 43274 21474 43274 21474 43275 21425 43275 21585 43275 21601 43276 21894 43276 21896 43276 21896 43277 21894 43277 21892 43277 21896 43278 21892 43278 21913 43278 21913 43279 21892 43279 21607 43279 21904 43280 21603 43280 21602 43280 21602 43281 21603 43281 21899 43281 21602 43282 21899 43282 21604 43282 21926 43283 21605 43283 21924 43283 21924 43284 21605 43284 21607 43284 21924 43285 21607 43285 21606 43285 21606 43286 21607 43286 21892 43286 21606 43287 21892 43287 21608 43287 21608 43288 21892 43288 21907 43288 21608 43289 21907 43289 21609 43289 21609 43290 21907 43290 21602 43290 21609 43291 21602 43291 21611 43291 21611 43292 21602 43292 21604 43292 21914 43293 21610 43293 21920 43293 21920 43294 21610 43294 21611 43294 21920 43295 21611 43295 21909 43295 21909 43296 21611 43296 21604 43296 21612 43297 21615 43297 21613 43297 21614 43298 21790 43298 21625 43298 21790 43299 21614 43299 21615 43299 21789 43300 21616 43300 21617 43300 21622 43301 21621 43301 21710 43301 21710 43302 21621 43302 21620 43302 21710 43303 21620 43303 21721 43303 21721 43304 21620 43304 21619 43304 21683 43305 21618 43305 21663 43305 21663 43306 21618 43306 21635 43306 21618 43307 21619 43307 21635 43307 21635 43308 21619 43308 21620 43308 21635 43309 21620 43309 21640 43309 21640 43310 21620 43310 21621 43310 21640 43311 21621 43311 21613 43311 21613 43312 21621 43312 21622 43312 21613 43313 21622 43313 21612 43313 21634 43314 21623 43314 21635 43314 21635 43315 21623 43315 21624 43315 21635 43316 21624 43316 21663 43316 21625 43317 21789 43317 21614 43317 21614 43318 21789 43318 21617 43318 21614 43319 21617 43319 21615 43319 21615 43320 21617 43320 21733 43320 21615 43321 21733 43321 21613 43321 21613 43322 21733 43322 21734 43322 21613 43323 21734 43323 21640 43323 21626 43324 21652 43324 21627 43324 21626 43325 21627 43325 21628 43325 21628 43326 21627 43326 21643 43326 21628 43327 21643 43327 21697 43327 21697 43328 21643 43328 21630 43328 21697 43329 21630 43329 21694 43329 21630 43330 21758 43330 21631 43330 21861 43331 21863 43331 21632 43331 21632 43332 21863 43332 21864 43332 21632 43333 21864 43333 21629 43333 21694 43334 21630 43334 21629 43334 21629 43335 21630 43335 21631 43335 21629 43336 21631 43336 21632 43336 21632 43337 21631 43337 21759 43337 21632 43338 21759 43338 21861 43338 21772 43339 21634 43339 21633 43339 21633 43340 21634 43340 21635 43340 21633 43341 21635 43341 21636 43341 21636 43342 21635 43342 21640 43342 21636 43343 21640 43343 21638 43343 21637 43344 21772 43344 21642 43344 21642 43345 21772 43345 21633 43345 21642 43346 21633 43346 21641 43346 21641 43347 21633 43347 21636 43347 21641 43348 21636 43348 21756 43348 21756 43349 21636 43349 21638 43349 21756 43350 21638 43350 21639 43350 21639 43351 21638 43351 21640 43351 21639 43352 21640 43352 21734 43352 21756 43353 21758 43353 21641 43353 21641 43354 21758 43354 21630 43354 21641 43355 21630 43355 21642 43355 21642 43356 21630 43356 21643 43356 21642 43357 21643 43357 21637 43357 21637 43358 21643 43358 21627 43358 21637 43359 21627 43359 21781 43359 21781 43360 21627 43360 21652 43360 21781 43361 21652 43361 21644 43361 21626 43362 21628 43362 21649 43362 21656 43363 21647 43363 21659 43363 21658 43364 21651 43364 21653 43364 21650 43365 21645 43365 21780 43365 21659 43366 21647 43366 21646 43366 21646 43367 21647 43367 21927 43367 21646 43368 21927 43368 21660 43368 21922 43369 21662 43369 21648 43369 21648 43370 21662 43370 21661 43370 21648 43371 21661 43371 21923 43371 21923 43372 21661 43372 21660 43372 21923 43373 21660 43373 21925 43373 21925 43374 21660 43374 21927 43374 21652 43375 21626 43375 21654 43375 21654 43376 21626 43376 21649 43376 21654 43377 21649 43377 21655 43377 21655 43378 21649 43378 21699 43378 21655 43379 21699 43379 21700 43379 21781 43380 21644 43380 21780 43380 21780 43381 21644 43381 21653 43381 21780 43382 21653 43382 21650 43382 21650 43383 21653 43383 21651 43383 21644 43384 21652 43384 21653 43384 21653 43385 21652 43385 21654 43385 21653 43386 21654 43386 21658 43386 21658 43387 21654 43387 21655 43387 21658 43388 21655 43388 21657 43388 21657 43389 21655 43389 21700 43389 21657 43390 21700 43390 21912 43390 21912 43391 21656 43391 21657 43391 21657 43392 21656 43392 21659 43392 21657 43393 21659 43393 21658 43393 21658 43394 21659 43394 21646 43394 21658 43395 21646 43395 21651 43395 21651 43396 21646 43396 21660 43396 21651 43397 21660 43397 21650 43397 21650 43398 21660 43398 21661 43398 21650 43399 21661 43399 21645 43399 21645 43400 21661 43400 21662 43400 21663 43401 21624 43401 21664 43401 21919 43402 21671 43402 21672 43402 21665 43403 21917 43403 21681 43403 21619 43404 21618 43404 21724 43404 21724 43405 21618 43405 21666 43405 21724 43406 21666 43406 21725 43406 21725 43407 21666 43407 21675 43407 21918 43408 21668 43408 21667 43408 21667 43409 21668 43409 21915 43409 21916 43410 21915 43410 21670 43410 21915 43411 21668 43411 21670 43411 21670 43412 21668 43412 21669 43412 21670 43413 21669 43413 21686 43413 21916 43414 21670 43414 21682 43414 21682 43415 21670 43415 21686 43415 21682 43416 21686 43416 21680 43416 21671 43417 21921 43417 21672 43417 21672 43418 21921 43418 21704 43418 21672 43419 21704 43419 21673 43419 21673 43420 21704 43420 21674 43420 21673 43421 21674 43421 21685 43421 21685 43422 21674 43422 21728 43422 21685 43423 21728 43423 21675 43423 21675 43424 21728 43424 21676 43424 21675 43425 21676 43425 21725 43425 21686 43426 21684 43426 21680 43426 21680 43427 21684 43427 21678 43427 21680 43428 21678 43428 21677 43428 21677 43429 21678 43429 21683 43429 21677 43430 21683 43430 21663 43430 21782 43431 21665 43431 21679 43431 21679 43432 21665 43432 21681 43432 21679 43433 21681 43433 21784 43433 21663 43434 21664 43434 21677 43434 21677 43435 21664 43435 21784 43435 21677 43436 21784 43436 21680 43436 21680 43437 21784 43437 21681 43437 21680 43438 21681 43438 21682 43438 21682 43439 21681 43439 21917 43439 21682 43440 21917 43440 21916 43440 21618 43441 21683 43441 21666 43441 21666 43442 21683 43442 21678 43442 21666 43443 21678 43443 21675 43443 21675 43444 21678 43444 21684 43444 21675 43445 21684 43445 21685 43445 21685 43446 21684 43446 21686 43446 21685 43447 21686 43447 21673 43447 21673 43448 21686 43448 21669 43448 21673 43449 21669 43449 21672 43449 21672 43450 21669 43450 21668 43450 21672 43451 21668 43451 21919 43451 21919 43452 21668 43452 21918 43452 21695 43453 21874 43453 21687 43453 21692 43454 21871 43454 21688 43454 21688 43455 21871 43455 21869 43455 21688 43456 21869 43456 21689 43456 21688 43457 21690 43457 21692 43457 21692 43458 21690 43458 21691 43458 21692 43459 21691 43459 21696 43459 21696 43460 21691 43460 21693 43460 21696 43461 21693 43461 21698 43461 21629 43462 21874 43462 21694 43462 21694 43463 21874 43463 21695 43463 21694 43464 21695 43464 21697 43464 21697 43465 21695 43465 21698 43465 21698 43466 21695 43466 21696 43466 21696 43467 21695 43467 21687 43467 21696 43468 21687 43468 21692 43468 21692 43469 21687 43469 21873 43469 21692 43470 21873 43470 21871 43470 21628 43471 21697 43471 21649 43471 21649 43472 21697 43472 21698 43472 21649 43473 21698 43473 21699 43473 21699 43474 21698 43474 21693 43474 21699 43475 21693 43475 21700 43475 21700 43476 21693 43476 21691 43476 21700 43477 21691 43477 21912 43477 21912 43478 21691 43478 21690 43478 21715 43479 21702 43479 21800 43479 21911 43480 21701 43480 21702 43480 21800 43481 21702 43481 21703 43481 21703 43482 21702 43482 21701 43482 21703 43483 21701 43483 21898 43483 21727 43484 21674 43484 21713 43484 21713 43485 21674 43485 21704 43485 21713 43486 21704 43486 21910 43486 21910 43487 21704 43487 21921 43487 21615 43488 21612 43488 21705 43488 21612 43489 21622 43489 21705 43489 21705 43490 21622 43490 21706 43490 21705 43491 21706 43491 21707 43491 21707 43492 21706 43492 21708 43492 21707 43493 21708 43493 21709 43493 21622 43494 21710 43494 21706 43494 21706 43495 21710 43495 21722 43495 21706 43496 21722 43496 21708 43496 21708 43497 21722 43497 21711 43497 21708 43498 21711 43498 21709 43498 21709 43499 21711 43499 21723 43499 21709 43500 21723 43500 21712 43500 21712 43501 21723 43501 21726 43501 21712 43502 21726 43502 21715 43502 21715 43503 21726 43503 21727 43503 21715 43504 21727 43504 21702 43504 21702 43505 21727 43505 21713 43505 21702 43506 21713 43506 21911 43506 21800 43507 21714 43507 21715 43507 21715 43508 21714 43508 21716 43508 21715 43509 21716 43509 21712 43509 21712 43510 21716 43510 21717 43510 21712 43511 21717 43511 21709 43511 21709 43512 21717 43512 21841 43512 21709 43513 21841 43513 21707 43513 21707 43514 21841 43514 21718 43514 21707 43515 21718 43515 21705 43515 21705 43516 21718 43516 21719 43516 21705 43517 21719 43517 21615 43517 21615 43518 21719 43518 21720 43518 21615 43519 21720 43519 21790 43519 21710 43520 21721 43520 21722 43520 21722 43521 21721 43521 21619 43521 21722 43522 21619 43522 21711 43522 21711 43523 21619 43523 21724 43523 21711 43524 21724 43524 21723 43524 21723 43525 21724 43525 21725 43525 21723 43526 21725 43526 21726 43526 21726 43527 21725 43527 21676 43527 21726 43528 21676 43528 21727 43528 21727 43529 21676 43529 21728 43529 21727 43530 21728 43530 21674 43530 21729 43531 21743 43531 21730 43531 21748 43532 21747 43532 21739 43532 21760 43533 21750 43533 21745 43533 21731 43534 21757 43534 21732 43534 21617 43535 21742 43535 21732 43535 21617 43536 21732 43536 21733 43536 21733 43537 21732 43537 21757 43537 21733 43538 21757 43538 21734 43538 21746 43539 21735 43539 21736 43539 21736 43540 21735 43540 21763 43540 21736 43541 21763 43541 21737 43541 21737 43542 21763 43542 21761 43542 21737 43543 21761 43543 21745 43543 21745 43544 21761 43544 21738 43544 21745 43545 21738 43545 21760 43545 21748 43546 21739 43546 21740 43546 21740 43547 21739 43547 21905 43547 21740 43548 21905 43548 21741 43548 21742 43549 21749 43549 21732 43549 21732 43550 21749 43550 21750 43550 21732 43551 21750 43551 21731 43551 21731 43552 21750 43552 21760 43552 21743 43553 21829 43553 21747 43553 21747 43554 21829 43554 21827 43554 21747 43555 21827 43555 21739 43555 21739 43556 21827 43556 21744 43556 21739 43557 21744 43557 21905 43557 21905 43558 21744 43558 21791 43558 21750 43559 21751 43559 21745 43559 21745 43560 21751 43560 21730 43560 21745 43561 21730 43561 21737 43561 21737 43562 21730 43562 21743 43562 21737 43563 21743 43563 21736 43563 21736 43564 21743 43564 21747 43564 21736 43565 21747 43565 21746 43565 21746 43566 21747 43566 21748 43566 21749 43567 21826 43567 21750 43567 21750 43568 21826 43568 21795 43568 21750 43569 21795 43569 21751 43569 21751 43570 21795 43570 21752 43570 21751 43571 21752 43571 21730 43571 21730 43572 21752 43572 21753 43572 21730 43573 21753 43573 21729 43573 21740 43574 21741 43574 21906 43574 21765 43575 21748 43575 21740 43575 21769 43576 21754 43576 21731 43576 21908 43577 21755 43577 21766 43577 21766 43578 21755 43578 21891 43578 21766 43579 21891 43579 21767 43579 21758 43580 21756 43580 21757 43580 21757 43581 21756 43581 21639 43581 21757 43582 21639 43582 21734 43582 21757 43583 21731 43583 21758 43583 21758 43584 21731 43584 21754 43584 21758 43585 21754 43585 21631 43585 21631 43586 21754 43586 21759 43586 21731 43587 21760 43587 21769 43587 21769 43588 21760 43588 21738 43588 21769 43589 21738 43589 21768 43589 21768 43590 21738 43590 21761 43590 21768 43591 21761 43591 21762 43591 21762 43592 21761 43592 21763 43592 21762 43593 21763 43593 21764 43593 21764 43594 21763 43594 21735 43594 21764 43595 21735 43595 21765 43595 21765 43596 21735 43596 21746 43596 21765 43597 21746 43597 21748 43597 21906 43598 21908 43598 21740 43598 21740 43599 21908 43599 21766 43599 21740 43600 21766 43600 21765 43600 21765 43601 21766 43601 21767 43601 21765 43602 21767 43602 21764 43602 21764 43603 21767 43603 21859 43603 21764 43604 21859 43604 21762 43604 21762 43605 21859 43605 21865 43605 21762 43606 21865 43606 21768 43606 21768 43607 21865 43607 21770 43607 21768 43608 21770 43608 21769 43608 21769 43609 21770 43609 21771 43609 21769 43610 21771 43610 21754 43610 21754 43611 21771 43611 21867 43611 21754 43612 21867 43612 21759 43612 21772 43613 21637 43613 21776 43613 21778 43614 21889 43614 21779 43614 21773 43615 21785 43615 21775 43615 21889 43616 21773 43616 21779 43616 21779 43617 21773 43617 21775 43617 21779 43618 21775 43618 21774 43618 21774 43619 21775 43619 21786 43619 21774 43620 21786 43620 21776 43620 21776 43621 21786 43621 21777 43621 21776 43622 21777 43622 21772 43622 21772 43623 21777 43623 21634 43623 21922 43624 21778 43624 21662 43624 21662 43625 21778 43625 21779 43625 21662 43626 21779 43626 21645 43626 21645 43627 21779 43627 21774 43627 21645 43628 21774 43628 21780 43628 21780 43629 21774 43629 21776 43629 21780 43630 21776 43630 21781 43630 21781 43631 21776 43631 21637 43631 21890 43632 21782 43632 21787 43632 21787 43633 21782 43633 21679 43633 21787 43634 21679 43634 21783 43634 21783 43635 21679 43635 21784 43635 21783 43636 21784 43636 21788 43636 21788 43637 21784 43637 21664 43637 21788 43638 21664 43638 21623 43638 21623 43639 21664 43639 21624 43639 21785 43640 21890 43640 21775 43640 21775 43641 21890 43641 21787 43641 21775 43642 21787 43642 21786 43642 21786 43643 21787 43643 21783 43643 21786 43644 21783 43644 21777 43644 21777 43645 21783 43645 21788 43645 21777 43646 21788 43646 21634 43646 21634 43647 21788 43647 21623 43647 21789 43648 21625 43648 21845 43648 21845 43649 21625 43649 21790 43649 21903 43650 21791 43650 21744 43650 21792 43651 21801 43651 21793 43651 21844 43652 21842 43652 21840 43652 21833 43653 21794 43653 21799 43653 21826 43654 21825 43654 21795 43654 21795 43655 21825 43655 21823 43655 21795 43656 21823 43656 21752 43656 21752 43657 21823 43657 21821 43657 21752 43658 21821 43658 21753 43658 21753 43659 21821 43659 21729 43659 21815 43660 21796 43660 21797 43660 21797 43661 21796 43661 21798 43661 21797 43662 21798 43662 21834 43662 21617 43663 21616 43663 21742 43663 21742 43664 21616 43664 21799 43664 21742 43665 21799 43665 21749 43665 21749 43666 21799 43666 21794 43666 21836 43667 21800 43667 21792 43667 21792 43668 21800 43668 21703 43668 21792 43669 21703 43669 21801 43669 21801 43670 21703 43670 21898 43670 21843 43671 21835 43671 21802 43671 21802 43672 21835 43672 21803 43672 21802 43673 21803 43673 21846 43673 21846 43674 21803 43674 21816 43674 21804 43675 21902 43675 21849 43675 21809 43676 21900 43676 21849 43676 21849 43677 21900 43677 21805 43677 21849 43678 21805 43678 21804 43678 21836 43679 21792 43679 21806 43679 21806 43680 21792 43680 21793 43680 21806 43681 21793 43681 21807 43681 21807 43682 21793 43682 21808 43682 21807 43683 21808 43683 21839 43683 21839 43684 21808 43684 21810 43684 21839 43685 21810 43685 21809 43685 21809 43686 21810 43686 21901 43686 21809 43687 21901 43687 21900 43687 21848 43688 21828 43688 21847 43688 21847 43689 21828 43689 21811 43689 21847 43690 21811 43690 21812 43690 21812 43691 21811 43691 21815 43691 21828 43692 21813 43692 21811 43692 21811 43693 21813 43693 21814 43693 21811 43694 21814 43694 21815 43694 21815 43695 21814 43695 21831 43695 21815 43696 21831 43696 21796 43696 21796 43697 21831 43697 21832 43697 21796 43698 21832 43698 21798 43698 21835 43699 21837 43699 21803 43699 21803 43700 21837 43700 21838 43700 21803 43701 21838 43701 21816 43701 21816 43702 21838 43702 21817 43702 21816 43703 21817 43703 21818 43703 21818 43704 21817 43704 21819 43704 21818 43705 21819 43705 21820 43705 21743 43706 21729 43706 21830 43706 21830 43707 21729 43707 21821 43707 21830 43708 21821 43708 21822 43708 21822 43709 21821 43709 21823 43709 21822 43710 21823 43710 21824 43710 21824 43711 21823 43711 21825 43711 21824 43712 21825 43712 21794 43712 21794 43713 21825 43713 21826 43713 21794 43714 21826 43714 21749 43714 21903 43715 21744 43715 21850 43715 21850 43716 21744 43716 21827 43716 21850 43717 21827 43717 21848 43717 21848 43718 21827 43718 21829 43718 21848 43719 21829 43719 21828 43719 21828 43720 21829 43720 21743 43720 21828 43721 21743 43721 21813 43721 21813 43722 21743 43722 21830 43722 21813 43723 21830 43723 21814 43723 21814 43724 21830 43724 21822 43724 21814 43725 21822 43725 21831 43725 21831 43726 21822 43726 21824 43726 21831 43727 21824 43727 21832 43727 21832 43728 21824 43728 21794 43728 21832 43729 21794 43729 21798 43729 21798 43730 21794 43730 21833 43730 21798 43731 21833 43731 21834 43731 21714 43732 21800 43732 21835 43732 21835 43733 21800 43733 21836 43733 21835 43734 21836 43734 21837 43734 21837 43735 21836 43735 21806 43735 21837 43736 21806 43736 21838 43736 21838 43737 21806 43737 21807 43737 21838 43738 21807 43738 21817 43738 21817 43739 21807 43739 21839 43739 21817 43740 21839 43740 21819 43740 21819 43741 21839 43741 21809 43741 21819 43742 21809 43742 21820 43742 21820 43743 21809 43743 21849 43743 21790 43744 21720 43744 21845 43744 21845 43745 21720 43745 21719 43745 21845 43746 21719 43746 21840 43746 21840 43747 21719 43747 21718 43747 21840 43748 21718 43748 21844 43748 21844 43749 21718 43749 21841 43749 21844 43750 21841 43750 21717 43750 21846 43751 21842 43751 21802 43751 21802 43752 21842 43752 21844 43752 21802 43753 21844 43753 21843 43753 21843 43754 21844 43754 21717 43754 21843 43755 21717 43755 21835 43755 21835 43756 21717 43756 21716 43756 21835 43757 21716 43757 21714 43757 21616 43758 21789 43758 21799 43758 21799 43759 21789 43759 21845 43759 21799 43760 21845 43760 21833 43760 21833 43761 21845 43761 21840 43761 21833 43762 21840 43762 21834 43762 21834 43763 21840 43763 21842 43763 21834 43764 21842 43764 21797 43764 21797 43765 21842 43765 21846 43765 21797 43766 21846 43766 21815 43766 21815 43767 21846 43767 21816 43767 21815 43768 21816 43768 21812 43768 21812 43769 21816 43769 21818 43769 21812 43770 21818 43770 21847 43770 21847 43771 21818 43771 21820 43771 21847 43772 21820 43772 21848 43772 21848 43773 21820 43773 21849 43773 21848 43774 21849 43774 21850 43774 21850 43775 21849 43775 21902 43775 21850 43776 21902 43776 21903 43776 21854 43777 21893 43777 21895 43777 21851 43778 21895 43778 21852 43778 21881 43779 21852 43779 21853 43779 21882 43780 21862 43780 21884 43780 21884 43781 21862 43781 21866 43781 21884 43782 21866 43782 21885 43782 21893 43783 21854 43783 21855 43783 21855 43784 21854 43784 21767 43784 21855 43785 21767 43785 21891 43785 21852 43786 21881 43786 21851 43786 21851 43787 21881 43787 21879 43787 21851 43788 21879 43788 21858 43788 21858 43789 21879 43789 21856 43789 21858 43790 21856 43790 21857 43790 21895 43791 21851 43791 21854 43791 21854 43792 21851 43792 21858 43792 21854 43793 21858 43793 21767 43793 21767 43794 21858 43794 21857 43794 21767 43795 21857 43795 21859 43795 21860 43796 21888 43796 21880 43796 21880 43797 21888 43797 21887 43797 21880 43798 21887 43798 21878 43798 21878 43799 21887 43799 21885 43799 21878 43800 21885 43800 21877 43800 21877 43801 21885 43801 21866 43801 21877 43802 21866 43802 21876 43802 21861 43803 21862 43803 21863 43803 21863 43804 21862 43804 21882 43804 21863 43805 21882 43805 21864 43805 21865 43806 21876 43806 21770 43806 21770 43807 21876 43807 21866 43807 21770 43808 21866 43808 21771 43808 21771 43809 21866 43809 21862 43809 21771 43810 21862 43810 21867 43810 21867 43811 21862 43811 21861 43811 21867 43812 21861 43812 21759 43812 21897 43813 21689 43813 21868 43813 21868 43814 21689 43814 21869 43814 21868 43815 21869 43815 21870 43815 21870 43816 21869 43816 21871 43816 21870 43817 21871 43817 21886 43817 21886 43818 21871 43818 21873 43818 21886 43819 21873 43819 21872 43819 21872 43820 21873 43820 21687 43820 21872 43821 21687 43821 21883 43821 21883 43822 21687 43822 21874 43822 21883 43823 21874 43823 21875 43823 21875 43824 21874 43824 21629 43824 21865 43825 21859 43825 21876 43825 21876 43826 21859 43826 21857 43826 21876 43827 21857 43827 21877 43827 21877 43828 21857 43828 21856 43828 21877 43829 21856 43829 21878 43829 21878 43830 21856 43830 21879 43830 21878 43831 21879 43831 21880 43831 21880 43832 21879 43832 21881 43832 21880 43833 21881 43833 21860 43833 21860 43834 21881 43834 21853 43834 21629 43835 21864 43835 21875 43835 21875 43836 21864 43836 21882 43836 21875 43837 21882 43837 21883 43837 21883 43838 21882 43838 21884 43838 21883 43839 21884 43839 21872 43839 21872 43840 21884 43840 21885 43840 21872 43841 21885 43841 21886 43841 21886 43842 21885 43842 21887 43842 21886 43843 21887 43843 21870 43843 21870 43844 21887 43844 21888 43844 21870 43845 21888 43845 21868 43845 21868 43846 21888 43846 21860 43846 21868 43847 21860 43847 21897 43847 21897 43848 21860 43848 21853 43848 21922 43849 21606 43849 21778 43849 21778 43850 21606 43850 21608 43850 21778 43851 21608 43851 21889 43851 21889 43852 21608 43852 21773 43852 21773 43853 21608 43853 21785 43853 21785 43854 21608 43854 21609 43854 21785 43855 21609 43855 21890 43855 21890 43856 21609 43856 21611 43856 21890 43857 21611 43857 21782 43857 21855 43858 21891 43858 21892 43858 21855 43859 21892 43859 21893 43859 21893 43860 21892 43860 21894 43860 21893 43861 21894 43861 21895 43861 21895 43862 21894 43862 21601 43862 21895 43863 21601 43863 21852 43863 21852 43864 21601 43864 21896 43864 21852 43865 21896 43865 21853 43865 21853 43866 21896 43866 21897 43866 21897 43867 21896 43867 21913 43867 21897 43868 21913 43868 21689 43868 21902 43869 21804 43869 21904 43869 21898 43870 21604 43870 21801 43870 21801 43871 21604 43871 21899 43871 21801 43872 21899 43872 21793 43872 21603 43873 21810 43873 21899 43873 21899 43874 21810 43874 21808 43874 21899 43875 21808 43875 21793 43875 21804 43876 21805 43876 21904 43876 21904 43877 21805 43877 21900 43877 21904 43878 21900 43878 21603 43878 21603 43879 21900 43879 21901 43879 21603 43880 21901 43880 21810 43880 21902 43881 21904 43881 21903 43881 21903 43882 21904 43882 21602 43882 21903 43883 21602 43883 21791 43883 21905 43884 21791 43884 21602 43884 21905 43885 21602 43885 21741 43885 21741 43886 21602 43886 21906 43886 21906 43887 21602 43887 21907 43887 21906 43888 21907 43888 21908 43888 21892 43889 21891 43889 21907 43889 21907 43890 21891 43890 21755 43890 21907 43891 21755 43891 21908 43891 21898 43892 21701 43892 21604 43892 21604 43893 21701 43893 21911 43893 21921 43894 21909 43894 21910 43894 21910 43895 21909 43895 21604 43895 21910 43896 21604 43896 21713 43896 21713 43897 21604 43897 21911 43897 21688 43898 21689 43898 21913 43898 21607 43899 21912 43899 21913 43899 21913 43900 21912 43900 21690 43900 21913 43901 21690 43901 21688 43901 21782 43902 21611 43902 21665 43902 21665 43903 21611 43903 21610 43903 21665 43904 21610 43904 21917 43904 21918 43905 21667 43905 21914 43905 21914 43906 21667 43906 21915 43906 21914 43907 21915 43907 21610 43907 21610 43908 21915 43908 21916 43908 21610 43909 21916 43909 21917 43909 21918 43910 21914 43910 21919 43910 21919 43911 21914 43911 21920 43911 21919 43912 21920 43912 21671 43912 21671 43913 21920 43913 21909 43913 21671 43914 21909 43914 21921 43914 21924 43915 21606 43915 21922 43915 21926 43916 21927 43916 21605 43916 21605 43917 21927 43917 21647 43917 21605 43918 21647 43918 21607 43918 21607 43919 21647 43919 21656 43919 21607 43920 21656 43920 21912 43920 21922 43921 21648 43921 21924 43921 21924 43922 21648 43922 21923 43922 21924 43923 21923 43923 21926 43923 21926 43924 21923 43924 21925 43924 21926 43925 21925 43925 21927 43925 21928 43926 22417 43926 21931 43926 22414 43927 22370 43927 22412 43927 22412 43928 22370 43928 21929 43928 22412 43929 21929 43929 22431 43929 22401 43930 22394 43930 22366 43930 22366 43931 22394 43931 22397 43931 22366 43932 22397 43932 22345 43932 22345 43933 22397 43933 22411 43933 22345 43934 22411 43934 21930 43934 21930 43935 22411 43935 22427 43935 22392 43936 22375 43936 22389 43936 22427 43937 22426 43937 21930 43937 21930 43938 22426 43938 22392 43938 21930 43939 22392 43939 22390 43939 22390 43940 22392 43940 22389 43940 22414 43941 21928 43941 22370 43941 22370 43942 21928 43942 21931 43942 22370 43943 21931 43943 21932 43943 21932 43944 21931 43944 22406 43944 21932 43945 22406 43945 22368 43945 22368 43946 22406 43946 21933 43946 22368 43947 21933 43947 22367 43947 22367 43948 21933 43948 21935 43948 22367 43949 21935 43949 21934 43949 21934 43950 21935 43950 22405 43950 21934 43951 22405 43951 22366 43951 22366 43952 22405 43952 22402 43952 22366 43953 22402 43953 22401 43953 22425 43954 22412 43954 21936 43954 21936 43955 22412 43955 22431 43955 21936 43956 22431 43956 22421 43956 22421 43957 22431 43957 22430 43957 22421 43958 22430 43958 22443 43958 22443 43959 22430 43959 22447 43959 21937 43960 21983 43960 21988 43960 21970 43961 21937 43961 21938 43961 21938 43962 21937 43962 21988 43962 21938 43963 21988 43963 21939 43963 21939 43964 21988 43964 21990 43964 21939 43965 21990 43965 21940 43965 21940 43966 21990 43966 21941 43966 21940 43967 21941 43967 21942 43967 21942 43968 21941 43968 21992 43968 21942 43969 21992 43969 22070 43969 22000 43970 22009 43970 22007 43970 22153 43971 22042 43971 21947 43971 21947 43972 22042 43972 21944 43972 21947 43973 21944 43973 21943 43973 21943 43974 21944 43974 22000 43974 21943 43975 22000 43975 21961 43975 21961 43976 22000 43976 22007 43976 21961 43977 22007 43977 21959 43977 21955 43978 21945 43978 21959 43978 21955 43979 21959 43979 21957 43979 22063 43980 21946 43980 21953 43980 22153 43981 21947 43981 21948 43981 21948 43982 21947 43982 21960 43982 21954 43983 21949 43983 21960 43983 21960 43984 21949 43984 22083 43984 21960 43985 22083 43985 21948 43985 21952 43986 21950 43986 22087 43986 21950 43987 21952 43987 21951 43987 21951 43988 21952 43988 21953 43988 21951 43989 21953 43989 22177 43989 22177 43990 21953 43990 22178 43990 22178 43991 21953 43991 21946 43991 22178 43992 21946 43992 22061 43992 22087 43993 21949 43993 21952 43993 21952 43994 21949 43994 21954 43994 21952 43995 21954 43995 21953 43995 21953 43996 21954 43996 21956 43996 21953 43997 21956 43997 22063 43997 22063 43998 21956 43998 22065 43998 21960 43999 21945 43999 21954 43999 21954 44000 21945 44000 21955 44000 21954 44001 21955 44001 21956 44001 21956 44002 21955 44002 21957 44002 21956 44003 21957 44003 22065 44003 22065 44004 21957 44004 21958 44004 21958 44005 21957 44005 21959 44005 21947 44006 21943 44006 21960 44006 21960 44007 21943 44007 21961 44007 21960 44008 21961 44008 21945 44008 21945 44009 21961 44009 21959 44009 22073 44010 21962 44010 21975 44010 22134 44011 22184 44011 21963 44011 21962 44012 21964 44012 21968 44012 21968 44013 21964 44013 22133 44013 21968 44014 22133 44014 22134 44014 22073 44015 21975 44015 21965 44015 21942 44016 22070 44016 21967 44016 21973 44017 21940 44017 21966 44017 21966 44018 21940 44018 21942 44018 21966 44019 21942 44019 21971 44019 21971 44020 21942 44020 21967 44020 21971 44021 21967 44021 21965 44021 22134 44022 21963 44022 21968 44022 21968 44023 21963 44023 22185 44023 21968 44024 22185 44024 21969 44024 22185 44025 22186 44025 21969 44025 21969 44026 22186 44026 22187 44026 21969 44027 22187 44027 21976 44027 21976 44028 22187 44028 22189 44028 21976 44029 22189 44029 21970 44029 21970 44030 21938 44030 21973 44030 21973 44031 21938 44031 21939 44031 21973 44032 21939 44032 21940 44032 21965 44033 21975 44033 21971 44033 21971 44034 21975 44034 21972 44034 21971 44035 21972 44035 21966 44035 21966 44036 21972 44036 21974 44036 21966 44037 21974 44037 21973 44037 21973 44038 21974 44038 21970 44038 21962 44039 21968 44039 21975 44039 21975 44040 21968 44040 21969 44040 21975 44041 21969 44041 21972 44041 21972 44042 21969 44042 21976 44042 21972 44043 21976 44043 21974 44043 21974 44044 21976 44044 21970 44044 21978 44045 21977 44045 22243 44045 22410 44046 21977 44046 21979 44046 21979 44047 21977 44047 21978 44047 21979 44048 21978 44048 21980 44048 21980 44049 21978 44049 21993 44049 21980 44050 21993 44050 22235 44050 22235 44051 21993 44051 21985 44051 21986 44052 21993 44052 21981 44052 21981 44053 21993 44053 21978 44053 21981 44054 21978 44054 21982 44054 21982 44055 21978 44055 22243 44055 21982 44056 22243 44056 22242 44056 21983 44057 21984 44057 21994 44057 21994 44058 21984 44058 21985 44058 21983 44059 21986 44059 21987 44059 21987 44060 21986 44060 21981 44060 21987 44061 21981 44061 21989 44061 21989 44062 21981 44062 21982 44062 21989 44063 21982 44063 21991 44063 21991 44064 21982 44064 22242 44064 21991 44065 22242 44065 22241 44065 21983 44066 21987 44066 21988 44066 21988 44067 21987 44067 21989 44067 21988 44068 21989 44068 21990 44068 21990 44069 21989 44069 21991 44069 21990 44070 21991 44070 21941 44070 21941 44071 21991 44071 22241 44071 21941 44072 22241 44072 21992 44072 21985 44073 21993 44073 21994 44073 21994 44074 21993 44074 21986 44074 21994 44075 21986 44075 21983 44075 21995 44076 21998 44076 22005 44076 22255 44077 21996 44077 22003 44077 21998 44078 22256 44078 22255 44078 22042 44079 21997 44079 21995 44079 21995 44080 21997 44080 22257 44080 21995 44081 22257 44081 21998 44081 21998 44082 22257 44082 21999 44082 21998 44083 21999 44083 22256 44083 22004 44084 21944 44084 22042 44084 22009 44085 22000 44085 22001 44085 22001 44086 22000 44086 21944 44086 21944 44087 22004 44087 22001 44087 22001 44088 22004 44088 22002 44088 22001 44089 22002 44089 22009 44089 22272 44090 22009 44090 22002 44090 22255 44091 22003 44091 21998 44091 21998 44092 22003 44092 22273 44092 21998 44093 22273 44093 22005 44093 22005 44094 22273 44094 22271 44094 22005 44095 22271 44095 22006 44095 22042 44096 21995 44096 22004 44096 22004 44097 21995 44097 22005 44097 22004 44098 22005 44098 22002 44098 22002 44099 22005 44099 22006 44099 22002 44100 22006 44100 22272 44100 22274 44101 22010 44101 22007 44101 22022 44102 21959 44102 22007 44102 22022 44103 22007 44103 22023 44103 22212 44104 22210 44104 22008 44104 22008 44105 22210 44105 22274 44105 22008 44106 22274 44106 22009 44106 22009 44107 22274 44107 22007 44107 22010 44108 22011 44108 22007 44108 22007 44109 22011 44109 22012 44109 22007 44110 22012 44110 22023 44110 22060 44111 22062 44111 22013 44111 22013 44112 22062 44112 22018 44112 22013 44113 22018 44113 22014 44113 22014 44114 22018 44114 22015 44114 22014 44115 22015 44115 22016 44115 22016 44116 22015 44116 22017 44116 22016 44117 22017 44117 22422 44117 22422 44118 22017 44118 22276 44118 22062 44119 22064 44119 22018 44119 22018 44120 22064 44120 22019 44120 22018 44121 22019 44121 22015 44121 22015 44122 22019 44122 22024 44122 22015 44123 22024 44123 22017 44123 22017 44124 22024 44124 22020 44124 22017 44125 22020 44125 22276 44125 22276 44126 22020 44126 22021 44126 22064 44127 22022 44127 22019 44127 22019 44128 22022 44128 22023 44128 22019 44129 22023 44129 22024 44129 22024 44130 22023 44130 22012 44130 22024 44131 22012 44131 22020 44131 22020 44132 22012 44132 22011 44132 22020 44133 22011 44133 22021 44133 22021 44134 22011 44134 22010 44134 21937 44135 21970 44135 22190 44135 22026 44136 22197 44136 22190 44136 22190 44137 22197 44137 21983 44137 22190 44138 21983 44138 21937 44138 22026 44139 22053 44139 22025 44139 22199 44140 22198 44140 22202 44140 22202 44141 22198 44141 22197 44141 22202 44142 22197 44142 22283 44142 22283 44143 22197 44143 22026 44143 22283 44144 22026 44144 22058 44144 22058 44145 22026 44145 22025 44145 22046 44146 22045 44146 22036 44146 22032 44147 22048 44147 22029 44147 22223 44148 22233 44148 22027 44148 22027 44149 22233 44149 22028 44149 22027 44150 22028 44150 22221 44150 22254 44151 22048 44151 22233 44151 22233 44152 22048 44152 22032 44152 22233 44153 22032 44153 22028 44153 22028 44154 22032 44154 22220 44154 22028 44155 22220 44155 22221 44155 22033 44156 22030 44156 22029 44156 22030 44157 22293 44157 22029 44157 22029 44158 22293 44158 22031 44158 22029 44159 22031 44159 22032 44159 22035 44160 22314 44160 22034 44160 22033 44161 22043 44161 22034 44161 22034 44162 22043 44162 22044 44162 22034 44163 22044 44163 22035 44163 22035 44164 22044 44164 22047 44164 21992 44165 22239 44165 22036 44165 22036 44166 22239 44166 22037 44166 22036 44167 22037 44167 22046 44167 22038 44168 22160 44168 22041 44168 22041 44169 22160 44169 22039 44169 22041 44170 22039 44170 22040 44170 22040 44171 22039 44171 22154 44171 22040 44172 22154 44172 22075 44172 22038 44173 22041 44173 22151 44173 22151 44174 22041 44174 22258 44174 22151 44175 22258 44175 22152 44175 22258 44176 22259 44176 22152 44176 22152 44177 22259 44177 22042 44177 22152 44178 22042 44178 22153 44178 22033 44179 22029 44179 22043 44179 22043 44180 22029 44180 22045 44180 22043 44181 22045 44181 22044 44181 22044 44182 22045 44182 22046 44182 22044 44183 22046 44183 22047 44183 22070 44184 21992 44184 22071 44184 22071 44185 21992 44185 22036 44185 22071 44186 22036 44186 22075 44186 22075 44187 22036 44187 22045 44187 22075 44188 22045 44188 22040 44188 22040 44189 22045 44189 22029 44189 22040 44190 22029 44190 22041 44190 22041 44191 22029 44191 22048 44191 22041 44192 22048 44192 22258 44192 22258 44193 22048 44193 22254 44193 22057 44194 22049 44194 22056 44194 22180 44195 22339 44195 22322 44195 22182 44196 22181 44196 22052 44196 22052 44197 22181 44197 22180 44197 22325 44198 22284 44198 22050 44198 22050 44199 22284 44199 22049 44199 22050 44200 22049 44200 22324 44200 22324 44201 22049 44201 22057 44201 22324 44202 22057 44202 22322 44202 22054 44203 22182 44203 22051 44203 22051 44204 22182 44204 22052 44204 22051 44205 22052 44205 22055 44205 22026 44206 22054 44206 22053 44206 22053 44207 22054 44207 22051 44207 22053 44208 22051 44208 22025 44208 22025 44209 22051 44209 22055 44209 22025 44210 22055 44210 22058 44210 22284 44211 22280 44211 22049 44211 22049 44212 22280 44212 22281 44212 22049 44213 22281 44213 22056 44213 22056 44214 22281 44214 22282 44214 22056 44215 22282 44215 22059 44215 22180 44216 22322 44216 22052 44216 22052 44217 22322 44217 22057 44217 22052 44218 22057 44218 22055 44218 22055 44219 22057 44219 22056 44219 22055 44220 22056 44220 22058 44220 22058 44221 22056 44221 22059 44221 22058 44222 22059 44222 22283 44222 22022 44223 22064 44223 21959 44223 21959 44224 22064 44224 21958 44224 22062 44225 22060 44225 22061 44225 22061 44226 21946 44226 22062 44226 22062 44227 21946 44227 22063 44227 22062 44228 22063 44228 22064 44228 22064 44229 22063 44229 22065 44229 22064 44230 22065 44230 21958 44230 22150 44231 22149 44231 22175 44231 22088 44232 22066 44232 22067 44232 22086 44233 21949 44233 22087 44233 22114 44234 22068 44234 22069 44234 22112 44235 22079 44235 22078 44235 22158 44236 22170 44236 22113 44236 22110 44237 22074 44237 22077 44237 22070 44238 22071 44238 21967 44238 21967 44239 22071 44239 22072 44239 21967 44240 22072 44240 21965 44240 21965 44241 22072 44241 22077 44241 21965 44242 22077 44242 22073 44242 22073 44243 22077 44243 22074 44243 22073 44244 22074 44244 21962 44244 22075 44245 22154 44245 22076 44245 22076 44246 22154 44246 22155 44246 22076 44247 22155 44247 22078 44247 22078 44248 22155 44248 22069 44248 22078 44249 22069 44249 22112 44249 22112 44250 22069 44250 22068 44250 22071 44251 22075 44251 22072 44251 22072 44252 22075 44252 22076 44252 22072 44253 22076 44253 22077 44253 22077 44254 22076 44254 22078 44254 22077 44255 22078 44255 22110 44255 22110 44256 22078 44256 22079 44256 22172 44257 22080 44257 22174 44257 22081 44258 22159 44258 22162 44258 22039 44259 22160 44259 22161 44259 22039 44260 22161 44260 22082 44260 22082 44261 22161 44261 22162 44261 22082 44262 22162 44262 22156 44262 22156 44263 22162 44263 22159 44263 22156 44264 22159 44264 22157 44264 21949 44265 22086 44265 22083 44265 22083 44266 22086 44266 22084 44266 22083 44267 22084 44267 21948 44267 22085 44268 22084 44268 22163 44268 22163 44269 22084 44269 22086 44269 22163 44270 22086 44270 22165 44270 22165 44271 22086 44271 22087 44271 22165 44272 22087 44272 21950 44272 22067 44273 22328 44273 22088 44273 22088 44274 22328 44274 22089 44274 22088 44275 22089 44275 22090 44275 22090 44276 22089 44276 22091 44276 22090 44277 22091 44277 22092 44277 22137 44278 22124 44278 22136 44278 22176 44279 22178 44279 22061 44279 22061 44280 22326 44280 22176 44280 22176 44281 22326 44281 22332 44281 22176 44282 22332 44282 22093 44282 22093 44283 22332 44283 22331 44283 22093 44284 22331 44284 22066 44284 22066 44285 22331 44285 22330 44285 22066 44286 22330 44286 22067 44286 22166 44287 22094 44287 22095 44287 22095 44288 22094 44288 22096 44288 22095 44289 22096 44289 22164 44289 22164 44290 22096 44290 22081 44290 22175 44291 22116 44291 22173 44291 22097 44292 22334 44292 22098 44292 22098 44293 22334 44293 22336 44293 22098 44294 22336 44294 22145 44294 22145 44295 22336 44295 22100 44295 22145 44296 22100 44296 22099 44296 22099 44297 22100 44297 22337 44297 22099 44298 22337 44298 22142 44298 22142 44299 22337 44299 22101 44299 22142 44300 22101 44300 22184 44300 22092 44301 22091 44301 22102 44301 22102 44302 22091 44302 22103 44302 22102 44303 22103 44303 22104 44303 22104 44304 22103 44304 22105 44304 22104 44305 22105 44305 22097 44305 22097 44306 22105 44306 22106 44306 22097 44307 22106 44307 22334 44307 22133 44308 21964 44308 22131 44308 22131 44309 21964 44309 22167 44309 22131 44310 22167 44310 22130 44310 21964 44311 21962 44311 22107 44311 22107 44312 21962 44312 22074 44312 22107 44313 22074 44313 22108 44313 22108 44314 22074 44314 22110 44314 22108 44315 22110 44315 22109 44315 22109 44316 22110 44316 22079 44316 22109 44317 22079 44317 22111 44317 22111 44318 22079 44318 22112 44318 22111 44319 22112 44319 22169 44319 22169 44320 22112 44320 22068 44320 22169 44321 22068 44321 22113 44321 22113 44322 22068 44322 22114 44322 22113 44323 22114 44323 22158 44323 22175 44324 22149 44324 22116 44324 22116 44325 22149 44325 22115 44325 22116 44326 22115 44326 22135 44326 22135 44327 22115 44327 22148 44327 22135 44328 22148 44328 22117 44328 22117 44329 22148 44329 22118 44329 22117 44330 22118 44330 22138 44330 22138 44331 22118 44331 22147 44331 22138 44332 22147 44332 22119 44332 22119 44333 22147 44333 22121 44333 22119 44334 22121 44334 22120 44334 22120 44335 22121 44335 22122 44335 22120 44336 22122 44336 22139 44336 22139 44337 22122 44337 22146 44337 22139 44338 22146 44338 22123 44338 22123 44339 22146 44339 22144 44339 22123 44340 22144 44340 22141 44340 22124 44341 22137 44341 22125 44341 22125 44342 22137 44342 22126 44342 22125 44343 22126 44343 22168 44343 22168 44344 22126 44344 22127 44344 22168 44345 22127 44345 22128 44345 22128 44346 22127 44346 22129 44346 22128 44347 22129 44347 22130 44347 22130 44348 22129 44348 22140 44348 22130 44349 22140 44349 22131 44349 22131 44350 22140 44350 22132 44350 22131 44351 22132 44351 22133 44351 22133 44352 22132 44352 22143 44352 22133 44353 22143 44353 22134 44353 22173 44354 22116 44354 22171 44354 22171 44355 22116 44355 22135 44355 22171 44356 22135 44356 22136 44356 22136 44357 22135 44357 22117 44357 22136 44358 22117 44358 22137 44358 22137 44359 22117 44359 22138 44359 22137 44360 22138 44360 22126 44360 22126 44361 22138 44361 22119 44361 22126 44362 22119 44362 22127 44362 22127 44363 22119 44363 22120 44363 22127 44364 22120 44364 22129 44364 22129 44365 22120 44365 22139 44365 22129 44366 22139 44366 22140 44366 22140 44367 22139 44367 22123 44367 22140 44368 22123 44368 22132 44368 22132 44369 22123 44369 22141 44369 22132 44370 22141 44370 22143 44370 22184 44371 22134 44371 22142 44371 22142 44372 22134 44372 22143 44372 22142 44373 22143 44373 22099 44373 22099 44374 22143 44374 22141 44374 22099 44375 22141 44375 22145 44375 22145 44376 22141 44376 22144 44376 22145 44377 22144 44377 22098 44377 22098 44378 22144 44378 22146 44378 22098 44379 22146 44379 22097 44379 22097 44380 22146 44380 22122 44380 22097 44381 22122 44381 22104 44381 22104 44382 22122 44382 22121 44382 22104 44383 22121 44383 22102 44383 22102 44384 22121 44384 22147 44384 22102 44385 22147 44385 22092 44385 22092 44386 22147 44386 22118 44386 22092 44387 22118 44387 22090 44387 22090 44388 22118 44388 22148 44388 22090 44389 22148 44389 22088 44389 22088 44390 22148 44390 22115 44390 22088 44391 22115 44391 22066 44391 22066 44392 22115 44392 22149 44392 22066 44393 22149 44393 22093 44393 22093 44394 22149 44394 22150 44394 22093 44395 22150 44395 22176 44395 22038 44396 22151 44396 22085 44396 22085 44397 22151 44397 22152 44397 22085 44398 22152 44398 22084 44398 22084 44399 22152 44399 22153 44399 22084 44400 22153 44400 21948 44400 22154 44401 22039 44401 22155 44401 22155 44402 22039 44402 22082 44402 22155 44403 22082 44403 22069 44403 22069 44404 22082 44404 22156 44404 22069 44405 22156 44405 22114 44405 22114 44406 22156 44406 22157 44406 22114 44407 22157 44407 22158 44407 22158 44408 22157 44408 22159 44408 22158 44409 22159 44409 22172 44409 22172 44410 22159 44410 22081 44410 22172 44411 22081 44411 22080 44411 22080 44412 22081 44412 22096 44412 22080 44413 22096 44413 22174 44413 22174 44414 22096 44414 22094 44414 22160 44415 22038 44415 22161 44415 22161 44416 22038 44416 22085 44416 22161 44417 22085 44417 22162 44417 22162 44418 22085 44418 22163 44418 22162 44419 22163 44419 22081 44419 22081 44420 22163 44420 22165 44420 22081 44421 22165 44421 22164 44421 22164 44422 22165 44422 21950 44422 22164 44423 21950 44423 22095 44423 22095 44424 21950 44424 21951 44424 22095 44425 21951 44425 22166 44425 22166 44426 21951 44426 22177 44426 21964 44427 22107 44427 22167 44427 22167 44428 22107 44428 22108 44428 22167 44429 22108 44429 22130 44429 22130 44430 22108 44430 22109 44430 22130 44431 22109 44431 22128 44431 22128 44432 22109 44432 22111 44432 22128 44433 22111 44433 22168 44433 22168 44434 22111 44434 22169 44434 22168 44435 22169 44435 22125 44435 22125 44436 22169 44436 22113 44436 22125 44437 22113 44437 22124 44437 22124 44438 22113 44438 22170 44438 22124 44439 22170 44439 22136 44439 22136 44440 22170 44440 22158 44440 22136 44441 22158 44441 22171 44441 22171 44442 22158 44442 22172 44442 22171 44443 22172 44443 22173 44443 22173 44444 22172 44444 22174 44444 22173 44445 22174 44445 22175 44445 22175 44446 22174 44446 22094 44446 22175 44447 22094 44447 22150 44447 22150 44448 22094 44448 22166 44448 22150 44449 22166 44449 22176 44449 22176 44450 22166 44450 22177 44450 22176 44451 22177 44451 22178 44451 22026 44452 22190 44452 22188 44452 22026 44453 22188 44453 22054 44453 22054 44454 22188 44454 22179 44454 22054 44455 22179 44455 22182 44455 22183 44456 22180 44456 22179 44456 22179 44457 22180 44457 22181 44457 22179 44458 22181 44458 22182 44458 22339 44459 22180 44459 22340 44459 22340 44460 22180 44460 22183 44460 22340 44461 22183 44461 22342 44461 21963 44462 22184 44462 22342 44462 21963 44463 22342 44463 22185 44463 22185 44464 22342 44464 22183 44464 22185 44465 22183 44465 22186 44465 22186 44466 22183 44466 22179 44466 22186 44467 22179 44467 22187 44467 22187 44468 22179 44468 22188 44468 22187 44469 22188 44469 22189 44469 22189 44470 22188 44470 22190 44470 22189 44471 22190 44471 21970 44471 22195 44472 22285 44472 22194 44472 22429 44473 22236 44473 22428 44473 22428 44474 22236 44474 22191 44474 22428 44475 22191 44475 22192 44475 22192 44476 22191 44476 22194 44476 22192 44477 22194 44477 22193 44477 22193 44478 22194 44478 22285 44478 22236 44479 22234 44479 22191 44479 22191 44480 22234 44480 22196 44480 22191 44481 22196 44481 22194 44481 22194 44482 22196 44482 22200 44482 22194 44483 22200 44483 22195 44483 22195 44484 22200 44484 22201 44484 22234 44485 22197 44485 22196 44485 22196 44486 22197 44486 22198 44486 22196 44487 22198 44487 22200 44487 22200 44488 22198 44488 22199 44488 22200 44489 22199 44489 22201 44489 22201 44490 22199 44490 22202 44490 22423 44491 22277 44491 22203 44491 22203 44492 22277 44492 22206 44492 22203 44493 22206 44493 22204 44493 22204 44494 22206 44494 22207 44494 22204 44495 22207 44495 22413 44495 22413 44496 22207 44496 22205 44496 22277 44497 22275 44497 22206 44497 22206 44498 22275 44498 22209 44498 22206 44499 22209 44499 22207 44499 22207 44500 22209 44500 22211 44500 22207 44501 22211 44501 22205 44501 22205 44502 22211 44502 22208 44502 22275 44503 22274 44503 22209 44503 22209 44504 22274 44504 22210 44504 22209 44505 22210 44505 22211 44505 22211 44506 22210 44506 22212 44506 22211 44507 22212 44507 22208 44507 22208 44508 22212 44508 22008 44508 22228 44509 22219 44509 22419 44509 22230 44510 22265 44510 22264 44510 22222 44511 22286 44511 22227 44511 22224 44512 22216 44512 22214 44512 22231 44513 22226 44513 22213 44513 22213 44514 22226 44514 22214 44514 22213 44515 22214 44515 22215 44515 22215 44516 22214 44516 22216 44516 22416 44517 22418 44517 22218 44517 22218 44518 22418 44518 22420 44518 22265 44519 22230 44519 22266 44519 22266 44520 22230 44520 22229 44520 22266 44521 22229 44521 22269 44521 22269 44522 22229 44522 22217 44522 22269 44523 22217 44523 22270 44523 22215 44524 22416 44524 22213 44524 22213 44525 22416 44525 22218 44525 22213 44526 22218 44526 22228 44526 22228 44527 22218 44527 22420 44527 22228 44528 22420 44528 22219 44528 22220 44529 22286 44529 22221 44529 22221 44530 22286 44530 22222 44530 22221 44531 22222 44531 22027 44531 22027 44532 22222 44532 22223 44532 22223 44533 22222 44533 22232 44533 22223 44534 22232 44534 22233 44534 22407 44535 22224 44535 22225 44535 22225 44536 22224 44536 22214 44536 22225 44537 22214 44537 22227 44537 22227 44538 22214 44538 22226 44538 22227 44539 22226 44539 22222 44539 22222 44540 22226 44540 22231 44540 22222 44541 22231 44541 22232 44541 22419 44542 22270 44542 22228 44542 22228 44543 22270 44543 22217 44543 22228 44544 22217 44544 22213 44544 22213 44545 22217 44545 22229 44545 22213 44546 22229 44546 22231 44546 22231 44547 22229 44547 22230 44547 22231 44548 22230 44548 22232 44548 22232 44549 22230 44549 22264 44549 22232 44550 22264 44550 22233 44550 21983 44551 22197 44551 21984 44551 21984 44552 22197 44552 22234 44552 21984 44553 22234 44553 21985 44553 21985 44554 22234 44554 22235 44554 22235 44555 22234 44555 22236 44555 22235 44556 22236 44556 21980 44556 21980 44557 22236 44557 21979 44557 21979 44558 22236 44558 22429 44558 21979 44559 22429 44559 22410 44559 22239 44560 21992 44560 22241 44560 22244 44561 22248 44561 22037 44561 22410 44562 22252 44562 22237 44562 22237 44563 22252 44563 22238 44563 22237 44564 22238 44564 22245 44564 22037 44565 22239 44565 22244 44565 22244 44566 22239 44566 22241 44566 22244 44567 22241 44567 22240 44567 22240 44568 22241 44568 22242 44568 22240 44569 22242 44569 22246 44569 22246 44570 22242 44570 22243 44570 22246 44571 22243 44571 21977 44571 22248 44572 22244 44572 22250 44572 22250 44573 22244 44573 22240 44573 22250 44574 22240 44574 22245 44574 22245 44575 22240 44575 22246 44575 22245 44576 22246 44576 22237 44576 22237 44577 22246 44577 21977 44577 22237 44578 21977 44578 22410 44578 22046 44579 22037 44579 22247 44579 22247 44580 22037 44580 22248 44580 22247 44581 22248 44581 22249 44581 22249 44582 22248 44582 22250 44582 22249 44583 22250 44583 22301 44583 22301 44584 22250 44584 22245 44584 22301 44585 22245 44585 22321 44585 22321 44586 22245 44586 22238 44586 22321 44587 22238 44587 22251 44587 22251 44588 22238 44588 22252 44588 22270 44589 22419 44589 22253 44589 22254 44590 22233 44590 22264 44590 21997 44591 22260 44591 22257 44591 22257 44592 22260 44592 22263 44592 21996 44593 22255 44593 22267 44593 22267 44594 22255 44594 22256 44594 22267 44595 22256 44595 22263 44595 22263 44596 22256 44596 21999 44596 22263 44597 21999 44597 22257 44597 22258 44598 22260 44598 22259 44598 22259 44599 22260 44599 21997 44599 22259 44600 21997 44600 22042 44600 22258 44601 22261 44601 22260 44601 22260 44602 22261 44602 22262 44602 22260 44603 22262 44603 22263 44603 22263 44604 22262 44604 22268 44604 22263 44605 22268 44605 22267 44605 22258 44606 22254 44606 22261 44606 22261 44607 22254 44607 22264 44607 22261 44608 22264 44608 22262 44608 22262 44609 22264 44609 22265 44609 22262 44610 22265 44610 22268 44610 22268 44611 22265 44611 22266 44611 22268 44612 22266 44612 22269 44612 21996 44613 22267 44613 22415 44613 22415 44614 22267 44614 22268 44614 22415 44615 22268 44615 22253 44615 22253 44616 22268 44616 22269 44616 22253 44617 22269 44617 22270 44617 22271 44618 22205 44618 22006 44618 22006 44619 22205 44619 22208 44619 22006 44620 22208 44620 22272 44620 22272 44621 22208 44621 22008 44621 22272 44622 22008 44622 22009 44622 21996 44623 22413 44623 22003 44623 22003 44624 22413 44624 22205 44624 22003 44625 22205 44625 22273 44625 22273 44626 22205 44626 22271 44626 22010 44627 22274 44627 22275 44627 22010 44628 22275 44628 22021 44628 22021 44629 22275 44629 22277 44629 22021 44630 22277 44630 22276 44630 22276 44631 22277 44631 22423 44631 22276 44632 22423 44632 22422 44632 22422 44633 22424 44633 22278 44633 22422 44634 22278 44634 22016 44634 22016 44635 22278 44635 22449 44635 22016 44636 22449 44636 22014 44636 22014 44637 22449 44637 22450 44637 22014 44638 22450 44638 22013 44638 22013 44639 22450 44639 22279 44639 22013 44640 22279 44640 22060 44640 22280 44641 22285 44641 22281 44641 22281 44642 22285 44642 22195 44642 22281 44643 22195 44643 22282 44643 22282 44644 22195 44644 22201 44644 22282 44645 22201 44645 22059 44645 22059 44646 22201 44646 22202 44646 22059 44647 22202 44647 22283 44647 22280 44648 22284 44648 22285 44648 22285 44649 22284 44649 22325 44649 22285 44650 22325 44650 22193 44650 22288 44651 22033 44651 22034 44651 22286 44652 22220 44652 22032 44652 22227 44653 22286 44653 22287 44653 22227 44654 22287 44654 22298 44654 22298 44655 22287 44655 22292 44655 22298 44656 22292 44656 22297 44656 22297 44657 22292 44657 22288 44657 22288 44658 22292 44658 22030 44658 22288 44659 22030 44659 22033 44659 22289 44660 22296 44660 22299 44660 22407 44661 22225 44661 22290 44661 22290 44662 22225 44662 22300 44662 22290 44663 22300 44663 22291 44663 22291 44664 22300 44664 22299 44664 22286 44665 22032 44665 22287 44665 22287 44666 22032 44666 22031 44666 22287 44667 22031 44667 22292 44667 22292 44668 22031 44668 22293 44668 22292 44669 22293 44669 22030 44669 22315 44670 22296 44670 22294 44670 22294 44671 22296 44671 22289 44671 22294 44672 22289 44672 22313 44672 22403 44673 22295 44673 22315 44673 22315 44674 22295 44674 22404 44674 22315 44675 22404 44675 22296 44675 22296 44676 22404 44676 22409 44676 22296 44677 22409 44677 22299 44677 22299 44678 22409 44678 22408 44678 22299 44679 22408 44679 22291 44679 22034 44680 22313 44680 22288 44680 22288 44681 22313 44681 22289 44681 22288 44682 22289 44682 22297 44682 22297 44683 22289 44683 22299 44683 22297 44684 22299 44684 22298 44684 22298 44685 22299 44685 22300 44685 22298 44686 22300 44686 22227 44686 22227 44687 22300 44687 22225 44687 22303 44688 22301 44688 22321 44688 22035 44689 22047 44689 22317 44689 22400 44690 22302 44690 22318 44690 22301 44691 22303 44691 22249 44691 22249 44692 22303 44692 22312 44692 22249 44693 22312 44693 22247 44693 22251 44694 22396 44694 22304 44694 22304 44695 22396 44695 22395 44695 22304 44696 22395 44696 22305 44696 22305 44697 22395 44697 22399 44697 22305 44698 22399 44698 22307 44698 22307 44699 22311 44699 22305 44699 22305 44700 22311 44700 22306 44700 22305 44701 22306 44701 22304 44701 22399 44702 22398 44702 22307 44702 22307 44703 22398 44703 22308 44703 22307 44704 22308 44704 22309 44704 22309 44705 22308 44705 22400 44705 22400 44706 22318 44706 22309 44706 22309 44707 22318 44707 22319 44707 22309 44708 22319 44708 22307 44708 22307 44709 22319 44709 22310 44709 22307 44710 22310 44710 22311 44710 22317 44711 22047 44711 22312 44711 22312 44712 22047 44712 22046 44712 22312 44713 22046 44713 22247 44713 22313 44714 22034 44714 22314 44714 22403 44715 22315 44715 22316 44715 22316 44716 22315 44716 22294 44716 22316 44717 22294 44717 22320 44717 22320 44718 22294 44718 22313 44718 22320 44719 22313 44719 22317 44719 22317 44720 22313 44720 22314 44720 22317 44721 22314 44721 22035 44721 22302 44722 22403 44722 22318 44722 22318 44723 22403 44723 22316 44723 22318 44724 22316 44724 22319 44724 22319 44725 22316 44725 22320 44725 22319 44726 22320 44726 22310 44726 22310 44727 22320 44727 22317 44727 22310 44728 22317 44728 22311 44728 22311 44729 22317 44729 22312 44729 22311 44730 22312 44730 22306 44730 22306 44731 22312 44731 22303 44731 22306 44732 22303 44732 22304 44732 22304 44733 22303 44733 22321 44733 22304 44734 22321 44734 22251 44734 22339 44735 22338 44735 22385 44735 22339 44736 22385 44736 22322 44736 22322 44737 22385 44737 22323 44737 22322 44738 22323 44738 22324 44738 22324 44739 22323 44739 22386 44739 22324 44740 22386 44740 22050 44740 22050 44741 22386 44741 22372 44741 22050 44742 22372 44742 22325 44742 22060 44743 22279 44743 22061 44743 22061 44744 22279 44744 22354 44744 22061 44745 22354 44745 22326 44745 22326 44746 22354 44746 22332 44746 22327 44747 22089 44747 22329 44747 22329 44748 22089 44748 22328 44748 22328 44749 22067 44749 22329 44749 22329 44750 22067 44750 22330 44750 22329 44751 22330 44751 22354 44751 22354 44752 22330 44752 22331 44752 22354 44753 22331 44753 22332 44753 22334 44754 22106 44754 22335 44754 22335 44755 22106 44755 22105 44755 22335 44756 22105 44756 22333 44756 22333 44757 22105 44757 22103 44757 22333 44758 22103 44758 22327 44758 22327 44759 22103 44759 22091 44759 22327 44760 22091 44760 22089 44760 22334 44761 22335 44761 22336 44761 22336 44762 22335 44762 22349 44762 22336 44763 22349 44763 22100 44763 22341 44764 22101 44764 22349 44764 22349 44765 22101 44765 22337 44765 22349 44766 22337 44766 22100 44766 22346 44767 22338 44767 22339 44767 22339 44768 22340 44768 22346 44768 22346 44769 22340 44769 22342 44769 22346 44770 22342 44770 22341 44770 22341 44771 22342 44771 22184 44771 22341 44772 22184 44772 22101 44772 22343 44773 22338 44773 22346 44773 22379 44774 22378 44774 22347 44774 22347 44775 22378 44775 22343 44775 22377 44776 22344 44776 22358 44776 22358 44777 22344 44777 22379 44777 22345 44778 21930 44778 22377 44778 22343 44779 22346 44779 22347 44779 22347 44780 22346 44780 22341 44780 22347 44781 22341 44781 22348 44781 22348 44782 22341 44782 22349 44782 22348 44783 22349 44783 22350 44783 22350 44784 22349 44784 22335 44784 22350 44785 22335 44785 22361 44785 22361 44786 22335 44786 22333 44786 22361 44787 22333 44787 22351 44787 22351 44788 22333 44788 22327 44788 22351 44789 22327 44789 22352 44789 22352 44790 22327 44790 22329 44790 22352 44791 22329 44791 22353 44791 22353 44792 22329 44792 22354 44792 22353 44793 22354 44793 22356 44793 22354 44794 22279 44794 22355 44794 22354 44795 22355 44795 22356 44795 22356 44796 22355 44796 22357 44796 22356 44797 22357 44797 22440 44797 22379 44798 22347 44798 22358 44798 22358 44799 22347 44799 22348 44799 22358 44800 22348 44800 22359 44800 22359 44801 22348 44801 22350 44801 22359 44802 22350 44802 22360 44802 22360 44803 22350 44803 22361 44803 22360 44804 22361 44804 22362 44804 22362 44805 22361 44805 22351 44805 22362 44806 22351 44806 22363 44806 22363 44807 22351 44807 22352 44807 22363 44808 22352 44808 22369 44808 22369 44809 22352 44809 22353 44809 22369 44810 22353 44810 22364 44810 22364 44811 22353 44811 22356 44811 22364 44812 22356 44812 22365 44812 22365 44813 22356 44813 22440 44813 22365 44814 22440 44814 22438 44814 22377 44815 22358 44815 22345 44815 22345 44816 22358 44816 22359 44816 22345 44817 22359 44817 22366 44817 22366 44818 22359 44818 22360 44818 22366 44819 22360 44819 21934 44819 21934 44820 22360 44820 22362 44820 21934 44821 22362 44821 22367 44821 22367 44822 22362 44822 22363 44822 22367 44823 22363 44823 22368 44823 22368 44824 22363 44824 22369 44824 22368 44825 22369 44825 21932 44825 21932 44826 22369 44826 22364 44826 21932 44827 22364 44827 22370 44827 22370 44828 22364 44828 22365 44828 22370 44829 22365 44829 21929 44829 21929 44830 22365 44830 22438 44830 21929 44831 22438 44831 22431 44831 22373 44832 22371 44832 22387 44832 22387 44833 22371 44833 22372 44833 22387 44834 22372 44834 22386 44834 22388 44835 22391 44835 22373 44835 22373 44836 22391 44836 22374 44836 22373 44837 22374 44837 22371 44837 22389 44838 22375 44838 22388 44838 22388 44839 22375 44839 22393 44839 22388 44840 22393 44840 22391 44840 22376 44841 22379 44841 22380 44841 22380 44842 22379 44842 22344 44842 22380 44843 22344 44843 22377 44843 22385 44844 22338 44844 22383 44844 22383 44845 22338 44845 22343 44845 22383 44846 22343 44846 22376 44846 22376 44847 22343 44847 22378 44847 22376 44848 22378 44848 22379 44848 22380 44849 22381 44849 22376 44849 22376 44850 22381 44850 22382 44850 22376 44851 22382 44851 22383 44851 22383 44852 22382 44852 22384 44852 22383 44853 22384 44853 22385 44853 22385 44854 22384 44854 22323 44854 22386 44855 22323 44855 22387 44855 22387 44856 22323 44856 22384 44856 22387 44857 22384 44857 22373 44857 22373 44858 22384 44858 22382 44858 22373 44859 22382 44859 22388 44859 22388 44860 22382 44860 22381 44860 22388 44861 22381 44861 22389 44861 22389 44862 22381 44862 22380 44862 22389 44863 22380 44863 22390 44863 22390 44864 22380 44864 22377 44864 22390 44865 22377 44865 21930 44865 22392 44866 22193 44866 22325 44866 22325 44867 22372 44867 22392 44867 22392 44868 22372 44868 22371 44868 22392 44869 22371 44869 22374 44869 22374 44870 22391 44870 22392 44870 22392 44871 22391 44871 22393 44871 22392 44872 22393 44872 22375 44872 22397 44873 22394 44873 22399 44873 22399 44874 22395 44874 22397 44874 22397 44875 22395 44875 22396 44875 22397 44876 22396 44876 22251 44876 22400 44877 22308 44877 22394 44877 22394 44878 22308 44878 22398 44878 22394 44879 22398 44879 22399 44879 22394 44880 22401 44880 22400 44880 22400 44881 22401 44881 22402 44881 22400 44882 22402 44882 22302 44882 22302 44883 22402 44883 22405 44883 22302 44884 22405 44884 22403 44884 22295 44885 22403 44885 22405 44885 22295 44886 22405 44886 22404 44886 22404 44887 22405 44887 21935 44887 22404 44888 21935 44888 22409 44888 21933 44889 22406 44889 22407 44889 22407 44890 22290 44890 21933 44890 21933 44891 22290 44891 22291 44891 21933 44892 22291 44892 21935 44892 21935 44893 22291 44893 22408 44893 21935 44894 22408 44894 22409 44894 22410 44895 22429 44895 22252 44895 22252 44896 22429 44896 22411 44896 22252 44897 22411 44897 22251 44897 22251 44898 22411 44898 22397 44898 22412 44899 22413 44899 21996 44899 22419 44900 22414 44900 22253 44900 22253 44901 22414 44901 22412 44901 22253 44902 22412 44902 22415 44902 22415 44903 22412 44903 21996 44903 22215 44904 22216 44904 21931 44904 21931 44905 22216 44905 22406 44905 22406 44906 22216 44906 22224 44906 22406 44907 22224 44907 22407 44907 22215 44908 21931 44908 22416 44908 22416 44909 21931 44909 22417 44909 22416 44910 22417 44910 22418 44910 22418 44911 22417 44911 21928 44911 22418 44912 21928 44912 22420 44912 22414 44913 22419 44913 21928 44913 21928 44914 22419 44914 22219 44914 21928 44915 22219 44915 22420 44915 22443 44916 22432 44916 22421 44916 22421 44917 22432 44917 22434 44917 22421 44918 22434 44918 22436 44918 22422 44919 22423 44919 22424 44919 22424 44920 22423 44920 22421 44920 22424 44921 22421 44921 22437 44921 22437 44922 22421 44922 22436 44922 22413 44923 22412 44923 22204 44923 22204 44924 22412 44924 22425 44924 22204 44925 22425 44925 22203 44925 22203 44926 22425 44926 21936 44926 22203 44927 21936 44927 22423 44927 22423 44928 21936 44928 22421 44928 22193 44929 22392 44929 22192 44929 22192 44930 22392 44930 22426 44930 22192 44931 22426 44931 22428 44931 22428 44932 22426 44932 22427 44932 22428 44933 22427 44933 22429 44933 22429 44934 22427 44934 22411 44934 22443 44935 22447 44935 22445 44935 22439 44936 22430 44936 22431 44936 22432 44937 22444 44937 22434 44937 22434 44938 22444 44938 22433 44938 22434 44939 22433 44939 22436 44939 22436 44940 22433 44940 22435 44940 22436 44941 22435 44941 22437 44941 22437 44942 22435 44942 22278 44942 22437 44943 22278 44943 22424 44943 22431 44944 22438 44944 22439 44944 22439 44945 22438 44945 22440 44945 22439 44946 22440 44946 22441 44946 22441 44947 22440 44947 22357 44947 22441 44948 22357 44948 22442 44948 22442 44949 22357 44949 22355 44949 22442 44950 22355 44950 22450 44950 22450 44951 22355 44951 22279 44951 22432 44952 22443 44952 22444 44952 22444 44953 22443 44953 22445 44953 22444 44954 22445 44954 22433 44954 22433 44955 22445 44955 22448 44955 22433 44956 22448 44956 22435 44956 22435 44957 22448 44957 22446 44957 22435 44958 22446 44958 22278 44958 22278 44959 22446 44959 22449 44959 22447 44960 22430 44960 22445 44960 22445 44961 22430 44961 22439 44961 22445 44962 22439 44962 22448 44962 22448 44963 22439 44963 22441 44963 22448 44964 22441 44964 22446 44964 22446 44965 22441 44965 22442 44965 22446 44966 22442 44966 22449 44966 22449 44967 22442 44967 22450 44967 22743 44968 22744 44968 22760 44968 22767 44969 22451 44969 22730 44969 22731 44970 22455 44970 22781 44970 22727 44971 22452 44971 22453 44971 22453 44972 22452 44972 22725 44972 22453 44973 22725 44973 22454 44973 22454 44974 22725 44974 22748 44974 22748 44975 22743 44975 22454 44975 22454 44976 22743 44976 22760 44976 22454 44977 22760 44977 22731 44977 22731 44978 22760 44978 22765 44978 22731 44979 22765 44979 22455 44979 22737 44980 22457 44980 22456 44980 22456 44981 22457 44981 22734 44981 22456 44982 22734 44982 22730 44982 22730 44983 22734 44983 22731 44983 22730 44984 22731 44984 22767 44984 22767 44985 22731 44985 22781 44985 22512 44986 22458 44986 22459 44986 22599 44987 22600 44987 22516 44987 22516 44988 22600 44988 22471 44988 22516 44989 22471 44989 22487 44989 22460 44990 22461 44990 22478 44990 22478 44991 22461 44991 22469 44991 22478 44992 22469 44992 22468 44992 22486 44993 22475 44993 22463 44993 22463 44994 22475 44994 22462 44994 22463 44995 22462 44995 22484 44995 22484 44996 22462 44996 22464 44996 22484 44997 22464 44997 22465 44997 22465 44998 22464 44998 22476 44998 22465 44999 22476 44999 22482 44999 22459 45000 22485 45000 22512 45000 22512 45001 22485 45001 22483 45001 22512 45002 22483 45002 22508 45002 22508 45003 22483 45003 22466 45003 22508 45004 22466 45004 22510 45004 22510 45005 22466 45005 22467 45005 22476 45006 22468 45006 22482 45006 22482 45007 22468 45007 22469 45007 22482 45008 22469 45008 22481 45008 22481 45009 22469 45009 22461 45009 22481 45010 22461 45010 22492 45010 22600 45011 22470 45011 22471 45011 22471 45012 22470 45012 22472 45012 22471 45013 22472 45013 22487 45013 22487 45014 22472 45014 22459 45014 22487 45015 22459 45015 22473 45015 22473 45016 22459 45016 22458 45016 22606 45017 22474 45017 22475 45017 22475 45018 22474 45018 22571 45018 22475 45019 22571 45019 22462 45019 22462 45020 22571 45020 22569 45020 22462 45021 22569 45021 22464 45021 22464 45022 22569 45022 22568 45022 22464 45023 22568 45023 22476 45023 22476 45024 22568 45024 22477 45024 22476 45025 22477 45025 22468 45025 22468 45026 22477 45026 22562 45026 22468 45027 22562 45027 22478 45027 22478 45028 22562 45028 22479 45028 22478 45029 22479 45029 22460 45029 22460 45030 22479 45030 22480 45030 22492 45031 22467 45031 22481 45031 22481 45032 22467 45032 22466 45032 22481 45033 22466 45033 22482 45033 22482 45034 22466 45034 22483 45034 22482 45035 22483 45035 22465 45035 22465 45036 22483 45036 22485 45036 22465 45037 22485 45037 22484 45037 22484 45038 22485 45038 22459 45038 22484 45039 22459 45039 22463 45039 22463 45040 22459 45040 22472 45040 22463 45041 22472 45041 22486 45041 22486 45042 22472 45042 22470 45042 22486 45043 22470 45043 22475 45043 22475 45044 22470 45044 22607 45044 22475 45045 22607 45045 22606 45045 22516 45046 22487 45046 22489 45046 22673 45047 22676 45047 22523 45047 22493 45048 22488 45048 22494 45048 22494 45049 22488 45049 22511 45049 22458 45050 22497 45050 22490 45050 22489 45051 22487 45051 22490 45051 22490 45052 22487 45052 22473 45052 22490 45053 22473 45053 22458 45053 22525 45054 22524 45054 22499 45054 22499 45055 22524 45055 22491 45055 22499 45056 22491 45056 22498 45056 22498 45057 22491 45057 22521 45057 22498 45058 22521 45058 22496 45058 22496 45059 22521 45059 22519 45059 22496 45060 22519 45060 22495 45060 22492 45061 22493 45061 22467 45061 22467 45062 22493 45062 22494 45062 22467 45063 22494 45063 22510 45063 22518 45064 22489 45064 22495 45064 22495 45065 22489 45065 22490 45065 22495 45066 22490 45066 22496 45066 22496 45067 22490 45067 22497 45067 22496 45068 22497 45068 22498 45068 22498 45069 22497 45069 22514 45069 22498 45070 22514 45070 22499 45070 22499 45071 22514 45071 22500 45071 22499 45072 22500 45072 22525 45072 22673 45073 22523 45073 22501 45073 22676 45074 22502 45074 22523 45074 22523 45075 22502 45075 22503 45075 22523 45076 22503 45076 22522 45076 22522 45077 22503 45077 22504 45077 22522 45078 22504 45078 22520 45078 22520 45079 22504 45079 22505 45079 22520 45080 22505 45080 22506 45080 22678 45081 22605 45081 22507 45081 22505 45082 22680 45082 22506 45082 22506 45083 22680 45083 22678 45083 22506 45084 22678 45084 22517 45084 22517 45085 22678 45085 22507 45085 22517 45086 22507 45086 22597 45086 22512 45087 22508 45087 22509 45087 22509 45088 22508 45088 22510 45088 22509 45089 22510 45089 22513 45089 22513 45090 22510 45090 22494 45090 22513 45091 22494 45091 22515 45091 22515 45092 22494 45092 22511 45092 22515 45093 22511 45093 22527 45093 22458 45094 22512 45094 22497 45094 22497 45095 22512 45095 22509 45095 22497 45096 22509 45096 22514 45096 22514 45097 22509 45097 22513 45097 22514 45098 22513 45098 22500 45098 22500 45099 22513 45099 22515 45099 22500 45100 22515 45100 22525 45100 22525 45101 22515 45101 22527 45101 22599 45102 22516 45102 22598 45102 22598 45103 22516 45103 22489 45103 22598 45104 22489 45104 22597 45104 22597 45105 22489 45105 22518 45105 22597 45106 22518 45106 22517 45106 22517 45107 22518 45107 22495 45107 22517 45108 22495 45108 22506 45108 22506 45109 22495 45109 22519 45109 22506 45110 22519 45110 22520 45110 22520 45111 22519 45111 22521 45111 22520 45112 22521 45112 22522 45112 22522 45113 22521 45113 22491 45113 22522 45114 22491 45114 22523 45114 22523 45115 22491 45115 22524 45115 22523 45116 22524 45116 22501 45116 22501 45117 22524 45117 22525 45117 22501 45118 22525 45118 22526 45118 22526 45119 22525 45119 22527 45119 22547 45120 22689 45120 22688 45120 22540 45121 22535 45121 22539 45121 22532 45122 22584 45122 22536 45122 22545 45123 22528 45123 22586 45123 22553 45124 22529 45124 22589 45124 22589 45125 22529 45125 22582 45125 22573 45126 22574 45126 22586 45126 22587 45127 22565 45127 22585 45127 22585 45128 22565 45128 22687 45128 22610 45129 22565 45129 22572 45129 22572 45130 22565 45130 22587 45130 22572 45131 22587 45131 22588 45131 22573 45132 22687 45132 22686 45132 22538 45133 22530 45133 22531 45133 22531 45134 22530 45134 22706 45134 22531 45135 22706 45135 22537 45135 22537 45136 22706 45136 22532 45136 22533 45137 22539 45137 22534 45137 22534 45138 22539 45138 22535 45138 22534 45139 22535 45139 22536 45139 22532 45140 22536 45140 22537 45140 22537 45141 22536 45141 22535 45141 22537 45142 22535 45142 22531 45142 22531 45143 22535 45143 22540 45143 22531 45144 22540 45144 22538 45144 22533 45145 22554 45145 22539 45145 22539 45146 22554 45146 22541 45146 22539 45147 22541 45147 22540 45147 22540 45148 22541 45148 22542 45148 22540 45149 22542 45149 22538 45149 22538 45150 22542 45150 22556 45150 22538 45151 22556 45151 22530 45151 22530 45152 22556 45152 22558 45152 22543 45153 22729 45153 22544 45153 22544 45154 22729 45154 22705 45154 22544 45155 22705 45155 22559 45155 22586 45156 22574 45156 22545 45156 22545 45157 22574 45157 22575 45157 22545 45158 22575 45158 22546 45158 22546 45159 22575 45159 22578 45159 22546 45160 22578 45160 22547 45160 22688 45161 22548 45161 22547 45161 22547 45162 22548 45162 22549 45162 22547 45163 22549 45163 22546 45163 22546 45164 22549 45164 22551 45164 22546 45165 22551 45165 22545 45165 22545 45166 22551 45166 22552 45166 22545 45167 22552 45167 22528 45167 22548 45168 22579 45168 22549 45168 22549 45169 22579 45169 22580 45169 22549 45170 22580 45170 22551 45170 22551 45171 22580 45171 22550 45171 22551 45172 22550 45172 22552 45172 22552 45173 22550 45173 22529 45173 22552 45174 22529 45174 22528 45174 22528 45175 22529 45175 22553 45175 22528 45176 22553 45176 22586 45176 22554 45177 22555 45177 22541 45177 22541 45178 22555 45178 22581 45178 22541 45179 22581 45179 22542 45179 22542 45180 22581 45180 22557 45180 22542 45181 22557 45181 22556 45181 22556 45182 22557 45182 22544 45182 22556 45183 22544 45183 22558 45183 22558 45184 22544 45184 22559 45184 22593 45185 22711 45185 22709 45185 22560 45186 22480 45186 22592 45186 22592 45187 22480 45187 22479 45187 22592 45188 22479 45188 22561 45188 22561 45189 22479 45189 22562 45189 22561 45190 22562 45190 22563 45190 22563 45191 22562 45191 22477 45191 22563 45192 22477 45192 22570 45192 22610 45193 22564 45193 22565 45193 22565 45194 22564 45194 22609 45194 22565 45195 22609 45195 22566 45195 22566 45196 22567 45196 22565 45196 22565 45197 22567 45197 22681 45197 22565 45198 22681 45198 22687 45198 22477 45199 22568 45199 22570 45199 22570 45200 22568 45200 22569 45200 22570 45201 22569 45201 22590 45201 22590 45202 22569 45202 22571 45202 22590 45203 22571 45203 22588 45203 22588 45204 22571 45204 22474 45204 22588 45205 22474 45205 22572 45205 22572 45206 22474 45206 22606 45206 22572 45207 22606 45207 22610 45207 22573 45208 22686 45208 22574 45208 22574 45209 22686 45209 22576 45209 22574 45210 22576 45210 22575 45210 22575 45211 22576 45211 22577 45211 22575 45212 22577 45212 22578 45212 22578 45213 22577 45213 22692 45213 22578 45214 22692 45214 22547 45214 22547 45215 22692 45215 22691 45215 22547 45216 22691 45216 22689 45216 22688 45217 22543 45217 22548 45217 22548 45218 22543 45218 22544 45218 22548 45219 22544 45219 22579 45219 22579 45220 22544 45220 22557 45220 22579 45221 22557 45221 22580 45221 22580 45222 22557 45222 22581 45222 22580 45223 22581 45223 22550 45223 22550 45224 22581 45224 22555 45224 22550 45225 22555 45225 22529 45225 22529 45226 22555 45226 22554 45226 22529 45227 22554 45227 22582 45227 22582 45228 22554 45228 22533 45228 22582 45229 22533 45229 22591 45229 22591 45230 22533 45230 22534 45230 22591 45231 22534 45231 22583 45231 22583 45232 22534 45232 22536 45232 22583 45233 22536 45233 22593 45233 22593 45234 22536 45234 22584 45234 22593 45235 22584 45235 22711 45235 22687 45236 22573 45236 22585 45236 22585 45237 22573 45237 22586 45237 22585 45238 22586 45238 22587 45238 22587 45239 22586 45239 22553 45239 22587 45240 22553 45240 22588 45240 22588 45241 22553 45241 22589 45241 22588 45242 22589 45242 22590 45242 22590 45243 22589 45243 22582 45243 22590 45244 22582 45244 22570 45244 22570 45245 22582 45245 22591 45245 22570 45246 22591 45246 22563 45246 22563 45247 22591 45247 22583 45247 22563 45248 22583 45248 22561 45248 22561 45249 22583 45249 22593 45249 22561 45250 22593 45250 22592 45250 22592 45251 22593 45251 22709 45251 22592 45252 22709 45252 22560 45252 22507 45253 22605 45253 22718 45253 22634 45254 22614 45254 22596 45254 22600 45255 22718 45255 22594 45255 22594 45256 22718 45256 22632 45256 22594 45257 22632 45257 22595 45257 22595 45258 22634 45258 22594 45258 22594 45259 22634 45259 22596 45259 22594 45260 22596 45260 22600 45260 22600 45261 22596 45261 22693 45261 22597 45262 22507 45262 22598 45262 22598 45263 22507 45263 22718 45263 22598 45264 22718 45264 22599 45264 22599 45265 22718 45265 22600 45265 22604 45266 22601 45266 22671 45266 22601 45267 22604 45267 22605 45267 22602 45268 22664 45268 22603 45268 22671 45269 22602 45269 22604 45269 22604 45270 22602 45270 22603 45270 22604 45271 22603 45271 22605 45271 22605 45272 22603 45272 22716 45272 22605 45273 22716 45273 22718 45273 22608 45274 22606 45274 22607 45274 22606 45275 22608 45275 22610 45275 22566 45276 22609 45276 22608 45276 22608 45277 22609 45277 22564 45277 22608 45278 22564 45278 22610 45278 22566 45279 22608 45279 22567 45279 22567 45280 22608 45280 22607 45280 22567 45281 22607 45281 22693 45281 22693 45282 22607 45282 22470 45282 22693 45283 22470 45283 22600 45283 22460 45284 22480 45284 22779 45284 22460 45285 22779 45285 22461 45285 22779 45286 22761 45286 22461 45286 22461 45287 22761 45287 22672 45287 22461 45288 22672 45288 22492 45288 22611 45289 22612 45289 22629 45289 22623 45290 22740 45290 22620 45290 22736 45291 22735 45291 22613 45291 22694 45292 22596 45292 22614 45292 22637 45293 22635 45293 22638 45293 22615 45294 22694 45294 22616 45294 22633 45295 22717 45295 22641 45295 22641 45296 22717 45296 22617 45296 22641 45297 22617 45297 22643 45297 22642 45298 22736 45298 22618 45298 22618 45299 22736 45299 22613 45299 22618 45300 22613 45300 22640 45300 22640 45301 22613 45301 22619 45301 22640 45302 22619 45302 22639 45302 22639 45303 22619 45303 22651 45303 22639 45304 22651 45304 22636 45304 22636 45305 22651 45305 22650 45305 22620 45306 22703 45306 22623 45306 22623 45307 22703 45307 22621 45307 22623 45308 22621 45308 22622 45308 22622 45309 22621 45309 22701 45309 22622 45310 22701 45310 22624 45310 22739 45311 22612 45311 22738 45311 22738 45312 22612 45312 22611 45312 22738 45313 22611 45313 22626 45313 22739 45314 22740 45314 22612 45314 22612 45315 22740 45315 22623 45315 22612 45316 22623 45316 22629 45316 22629 45317 22623 45317 22622 45317 22629 45318 22622 45318 22630 45318 22630 45319 22622 45319 22624 45319 22630 45320 22624 45320 22697 45320 22733 45321 22732 45321 22625 45321 22625 45322 22732 45322 22626 45322 22625 45323 22626 45323 22627 45323 22627 45324 22626 45324 22611 45324 22627 45325 22611 45325 22628 45325 22628 45326 22611 45326 22629 45326 22628 45327 22629 45327 22647 45327 22647 45328 22629 45328 22630 45328 22647 45329 22630 45329 22631 45329 22631 45330 22630 45330 22697 45330 22631 45331 22697 45331 22645 45331 22645 45332 22697 45332 22696 45332 22645 45333 22696 45333 22644 45333 22718 45334 22717 45334 22632 45334 22632 45335 22717 45335 22633 45335 22632 45336 22633 45336 22595 45336 22595 45337 22633 45337 22638 45337 22595 45338 22638 45338 22634 45338 22634 45339 22638 45339 22635 45339 22634 45340 22635 45340 22614 45340 22650 45341 22637 45341 22636 45341 22636 45342 22637 45342 22638 45342 22636 45343 22638 45343 22639 45343 22639 45344 22638 45344 22633 45344 22639 45345 22633 45345 22640 45345 22640 45346 22633 45346 22641 45346 22640 45347 22641 45347 22618 45347 22618 45348 22641 45348 22643 45348 22618 45349 22643 45349 22642 45349 22642 45350 22643 45350 22713 45350 22696 45351 22615 45351 22644 45351 22644 45352 22615 45352 22616 45352 22644 45353 22616 45353 22645 45353 22645 45354 22616 45354 22646 45354 22645 45355 22646 45355 22631 45355 22631 45356 22646 45356 22648 45356 22631 45357 22648 45357 22647 45357 22647 45358 22648 45358 22649 45358 22647 45359 22649 45359 22628 45359 22628 45360 22649 45360 22652 45360 22628 45361 22652 45361 22627 45361 22627 45362 22652 45362 22653 45362 22627 45363 22653 45363 22625 45363 22694 45364 22614 45364 22616 45364 22616 45365 22614 45365 22635 45365 22616 45366 22635 45366 22646 45366 22646 45367 22635 45367 22637 45367 22646 45368 22637 45368 22648 45368 22648 45369 22637 45369 22650 45369 22648 45370 22650 45370 22649 45370 22649 45371 22650 45371 22651 45371 22649 45372 22651 45372 22652 45372 22652 45373 22651 45373 22619 45373 22652 45374 22619 45374 22653 45374 22653 45375 22619 45375 22613 45375 22653 45376 22613 45376 22625 45376 22625 45377 22613 45377 22735 45377 22625 45378 22735 45378 22733 45378 22654 45379 22665 45379 22655 45379 22655 45380 22665 45380 22663 45380 22655 45381 22663 45381 22656 45381 22677 45382 22679 45382 22657 45382 22667 45383 22658 45383 22666 45383 22666 45384 22658 45384 22659 45384 22666 45385 22659 45385 22660 45385 22660 45386 22659 45386 22724 45386 22660 45387 22724 45387 22726 45387 22719 45388 22668 45388 22728 45388 22728 45389 22668 45389 22669 45389 22728 45390 22669 45390 22661 45390 22661 45391 22669 45391 22670 45391 22661 45392 22670 45392 22662 45392 22662 45393 22670 45393 22726 45393 22663 45394 22602 45394 22671 45394 22602 45395 22663 45395 22664 45395 22664 45396 22663 45396 22665 45396 22664 45397 22665 45397 22603 45397 22726 45398 22670 45398 22660 45398 22660 45399 22670 45399 22657 45399 22660 45400 22657 45400 22666 45400 22666 45401 22657 45401 22679 45401 22666 45402 22679 45402 22667 45402 22668 45403 22654 45403 22669 45403 22669 45404 22654 45404 22655 45404 22669 45405 22655 45405 22670 45405 22670 45406 22655 45406 22656 45406 22670 45407 22656 45407 22657 45407 22657 45408 22656 45408 22663 45408 22657 45409 22663 45409 22677 45409 22677 45410 22663 45410 22671 45410 22677 45411 22671 45411 22601 45411 22527 45412 22511 45412 22674 45412 22674 45413 22511 45413 22488 45413 22674 45414 22488 45414 22672 45414 22672 45415 22488 45415 22493 45415 22672 45416 22493 45416 22492 45416 22676 45417 22673 45417 22752 45417 22752 45418 22673 45418 22501 45418 22752 45419 22501 45419 22674 45419 22674 45420 22501 45420 22526 45420 22674 45421 22526 45421 22527 45421 22752 45422 22747 45422 22676 45422 22676 45423 22747 45423 22675 45423 22676 45424 22675 45424 22502 45424 22601 45425 22605 45425 22677 45425 22677 45426 22605 45426 22678 45426 22677 45427 22678 45427 22679 45427 22679 45428 22678 45428 22680 45428 22679 45429 22680 45429 22667 45429 22680 45430 22505 45430 22667 45430 22667 45431 22505 45431 22504 45431 22667 45432 22504 45432 22658 45432 22658 45433 22504 45433 22503 45433 22658 45434 22503 45434 22502 45434 22683 45435 22576 45435 22686 45435 22567 45436 22693 45436 22681 45436 22681 45437 22693 45437 22685 45437 22698 45438 22690 45438 22682 45438 22682 45439 22690 45439 22683 45439 22682 45440 22683 45440 22695 45440 22695 45441 22683 45441 22684 45441 22684 45442 22683 45442 22686 45442 22684 45443 22686 45443 22685 45443 22685 45444 22686 45444 22687 45444 22685 45445 22687 45445 22681 45445 22702 45446 22729 45446 22700 45446 22700 45447 22729 45447 22543 45447 22700 45448 22543 45448 22699 45448 22699 45449 22543 45449 22688 45449 22699 45450 22688 45450 22698 45450 22698 45451 22688 45451 22689 45451 22698 45452 22689 45452 22690 45452 22689 45453 22691 45453 22690 45453 22690 45454 22691 45454 22692 45454 22690 45455 22692 45455 22683 45455 22683 45456 22692 45456 22577 45456 22683 45457 22577 45457 22576 45457 22693 45458 22596 45458 22685 45458 22685 45459 22596 45459 22694 45459 22685 45460 22694 45460 22684 45460 22684 45461 22694 45461 22615 45461 22684 45462 22615 45462 22695 45462 22695 45463 22615 45463 22696 45463 22695 45464 22696 45464 22682 45464 22682 45465 22696 45465 22697 45465 22682 45466 22697 45466 22698 45466 22698 45467 22697 45467 22624 45467 22698 45468 22624 45468 22699 45468 22699 45469 22624 45469 22701 45469 22699 45470 22701 45470 22700 45470 22700 45471 22701 45471 22621 45471 22700 45472 22621 45472 22702 45472 22702 45473 22621 45473 22703 45473 22702 45474 22703 45474 22620 45474 22779 45475 22480 45475 22560 45475 22729 45476 22704 45476 22705 45476 22705 45477 22704 45477 22707 45477 22705 45478 22707 45478 22559 45478 22559 45479 22707 45479 22558 45479 22584 45480 22532 45480 22710 45480 22710 45481 22532 45481 22706 45481 22710 45482 22706 45482 22707 45482 22707 45483 22706 45483 22530 45483 22707 45484 22530 45484 22558 45484 22779 45485 22560 45485 22708 45485 22708 45486 22560 45486 22709 45486 22708 45487 22709 45487 22710 45487 22710 45488 22709 45488 22711 45488 22710 45489 22711 45489 22584 45489 22712 45490 22713 45490 22720 45490 22720 45491 22713 45491 22643 45491 22720 45492 22643 45492 22714 45492 22714 45493 22643 45493 22617 45493 22714 45494 22617 45494 22715 45494 22715 45495 22617 45495 22717 45495 22715 45496 22717 45496 22716 45496 22716 45497 22717 45497 22718 45497 22719 45498 22712 45498 22668 45498 22668 45499 22712 45499 22720 45499 22668 45500 22720 45500 22654 45500 22654 45501 22720 45501 22714 45501 22654 45502 22714 45502 22665 45502 22665 45503 22714 45503 22715 45503 22665 45504 22715 45504 22603 45504 22603 45505 22715 45505 22716 45505 22725 45506 22658 45506 22502 45506 22502 45507 22675 45507 22725 45507 22725 45508 22675 45508 22721 45508 22725 45509 22721 45509 22722 45509 22722 45510 22723 45510 22725 45510 22725 45511 22723 45511 22749 45511 22725 45512 22749 45512 22748 45512 22719 45513 22454 45513 22712 45513 22712 45514 22454 45514 22731 45514 22712 45515 22731 45515 22713 45515 22659 45516 22658 45516 22725 45516 22659 45517 22725 45517 22724 45517 22724 45518 22725 45518 22452 45518 22724 45519 22452 45519 22726 45519 22726 45520 22452 45520 22727 45520 22726 45521 22727 45521 22662 45521 22662 45522 22727 45522 22661 45522 22661 45523 22727 45523 22453 45523 22661 45524 22453 45524 22728 45524 22728 45525 22453 45525 22454 45525 22728 45526 22454 45526 22719 45526 22702 45527 22620 45527 22730 45527 22451 45528 22769 45528 22730 45528 22730 45529 22769 45529 22770 45529 22730 45530 22770 45530 22771 45530 22729 45531 22702 45531 22704 45531 22704 45532 22702 45532 22730 45532 22704 45533 22730 45533 22773 45533 22773 45534 22730 45534 22771 45534 22713 45535 22731 45535 22642 45535 22642 45536 22731 45536 22734 45536 22732 45537 22733 45537 22457 45537 22457 45538 22733 45538 22735 45538 22457 45539 22735 45539 22734 45539 22734 45540 22735 45540 22736 45540 22734 45541 22736 45541 22642 45541 22732 45542 22457 45542 22626 45542 22626 45543 22457 45543 22737 45543 22626 45544 22737 45544 22738 45544 22738 45545 22737 45545 22456 45545 22738 45546 22456 45546 22739 45546 22739 45547 22456 45547 22740 45547 22740 45548 22456 45548 22730 45548 22740 45549 22730 45549 22620 45549 22741 45550 22759 45550 22742 45550 22743 45551 22755 45551 22742 45551 22743 45552 22742 45552 22744 45552 22744 45553 22742 45553 22759 45553 22744 45554 22759 45554 22760 45554 22674 45555 22672 45555 22745 45555 22745 45556 22672 45556 22756 45556 22745 45557 22756 45557 22746 45557 22746 45558 22756 45558 22763 45558 22746 45559 22763 45559 22757 45559 22675 45560 22747 45560 22721 45560 22721 45561 22747 45561 22753 45561 22721 45562 22753 45562 22722 45562 22722 45563 22753 45563 22750 45563 22743 45564 22748 45564 22755 45564 22755 45565 22748 45565 22749 45565 22755 45566 22749 45566 22750 45566 22750 45567 22749 45567 22723 45567 22750 45568 22723 45568 22722 45568 22746 45569 22754 45569 22745 45569 22745 45570 22754 45570 22751 45570 22745 45571 22751 45571 22674 45571 22674 45572 22751 45572 22752 45572 22747 45573 22752 45573 22753 45573 22753 45574 22752 45574 22751 45574 22753 45575 22751 45575 22750 45575 22750 45576 22751 45576 22754 45576 22750 45577 22754 45577 22755 45577 22755 45578 22754 45578 22746 45578 22755 45579 22746 45579 22742 45579 22742 45580 22746 45580 22757 45580 22742 45581 22757 45581 22741 45581 22756 45582 22672 45582 22761 45582 22763 45583 22762 45583 22757 45583 22757 45584 22762 45584 22758 45584 22757 45585 22758 45585 22741 45585 22741 45586 22758 45586 22759 45586 22759 45587 22758 45587 22765 45587 22759 45588 22765 45588 22760 45588 22779 45589 22778 45589 22761 45589 22761 45590 22778 45590 22762 45590 22761 45591 22762 45591 22756 45591 22756 45592 22762 45592 22763 45592 22778 45593 22775 45593 22762 45593 22762 45594 22775 45594 22774 45594 22762 45595 22774 45595 22758 45595 22758 45596 22774 45596 22764 45596 22758 45597 22764 45597 22765 45597 22765 45598 22764 45598 22455 45598 22766 45599 22781 45599 22455 45599 22451 45600 22767 45600 22769 45600 22769 45601 22767 45601 22768 45601 22769 45602 22768 45602 22782 45602 22770 45603 22780 45603 22771 45603 22771 45604 22780 45604 22772 45604 22771 45605 22772 45605 22773 45605 22773 45606 22772 45606 22707 45606 22773 45607 22707 45607 22704 45607 22455 45608 22764 45608 22766 45608 22766 45609 22764 45609 22774 45609 22766 45610 22774 45610 22776 45610 22776 45611 22774 45611 22775 45611 22776 45612 22775 45612 22777 45612 22777 45613 22775 45613 22778 45613 22777 45614 22778 45614 22708 45614 22708 45615 22778 45615 22779 45615 22770 45616 22769 45616 22780 45616 22780 45617 22769 45617 22782 45617 22780 45618 22782 45618 22772 45618 22772 45619 22782 45619 22783 45619 22772 45620 22783 45620 22707 45620 22707 45621 22783 45621 22710 45621 22767 45622 22781 45622 22768 45622 22768 45623 22781 45623 22766 45623 22768 45624 22766 45624 22782 45624 22782 45625 22766 45625 22776 45625 22782 45626 22776 45626 22783 45626 22783 45627 22776 45627 22777 45627 22783 45628 22777 45628 22710 45628 22710 45629 22777 45629 22708 45629 22784 45630 22785 45630 24501 45630 24501 45631 22785 45631 22786 45631 24501 45632 22786 45632 22787 45632 22787 45633 22786 45633 26385 45633 22787 45634 26385 45634 22788 45634 22788 45635 26385 45635 22789 45635 22788 45636 22789 45636 24503 45636 24503 45637 22789 45637 22790 45637 24503 45638 22790 45638 24505 45638 24505 45639 22790 45639 26386 45639 24505 45640 26386 45640 22791 45640 22791 45641 26386 45641 22792 45641 22791 45642 22792 45642 24507 45642 24507 45643 22792 45643 22883 45643 24516 45644 26381 45644 24518 45644 24518 45645 26381 45645 22793 45645 24518 45646 22793 45646 22795 45646 22795 45647 22793 45647 22794 45647 22795 45648 22794 45648 24514 45648 24514 45649 22794 45649 26380 45649 24514 45650 26380 45650 22796 45650 22796 45651 26380 45651 22797 45651 22796 45652 22797 45652 22798 45652 22798 45653 22797 45653 22799 45653 22798 45654 22799 45654 22800 45654 22800 45655 22799 45655 22802 45655 22800 45656 22802 45656 22801 45656 22801 45657 22802 45657 26382 45657 24520 45658 26377 45658 24519 45658 24519 45659 26377 45659 26376 45659 24519 45660 26376 45660 22803 45660 22803 45661 26376 45661 22804 45661 22803 45662 22804 45662 24573 45662 24573 45663 22804 45663 26378 45663 24573 45664 26378 45664 24574 45664 24574 45665 26378 45665 22805 45665 24574 45666 22805 45666 22806 45666 22806 45667 22805 45667 22807 45667 22806 45668 22807 45668 24576 45668 24576 45669 22807 45669 26374 45669 24569 45670 22808 45670 22809 45670 22809 45671 22808 45671 22810 45671 22809 45672 22810 45672 22811 45672 22811 45673 22810 45673 26371 45673 22811 45674 26371 45674 22812 45674 22812 45675 26371 45675 22813 45675 22812 45676 22813 45676 22814 45676 22814 45677 22813 45677 22815 45677 22814 45678 22815 45678 24572 45678 24572 45679 22815 45679 26373 45679 24572 45680 26373 45680 22816 45680 22816 45681 26373 45681 26370 45681 22816 45682 26370 45682 22906 45682 22906 45683 26370 45683 22817 45683 24522 45684 26365 45684 24592 45684 24592 45685 26365 45685 26363 45685 24592 45686 26363 45686 22818 45686 22818 45687 26363 45687 22819 45687 22818 45688 22819 45688 24585 45688 24585 45689 22819 45689 26364 45689 24585 45690 26364 45690 24562 45690 24562 45691 26364 45691 26368 45691 24562 45692 26368 45692 22820 45692 22820 45693 26368 45693 22822 45693 22820 45694 22822 45694 22821 45694 22821 45695 22822 45695 26369 45695 24553 45696 22923 45696 24555 45696 24555 45697 22923 45697 22824 45697 24555 45698 22824 45698 22823 45698 22823 45699 22824 45699 26359 45699 22823 45700 26359 45700 24558 45700 24558 45701 26359 45701 26358 45701 24558 45702 26358 45702 22825 45702 22825 45703 26358 45703 26357 45703 22825 45704 26357 45704 24560 45704 24560 45705 26357 45705 22827 45705 24560 45706 22827 45706 22826 45706 22826 45707 22827 45707 22828 45707 22826 45708 22828 45708 24524 45708 24524 45709 22828 45709 22919 45709 22829 45710 26352 45710 22830 45710 22830 45711 26352 45711 22831 45711 22830 45712 22831 45712 22832 45712 22832 45713 22831 45713 22833 45713 22832 45714 22833 45714 24547 45714 24547 45715 22833 45715 22834 45715 24547 45716 22834 45716 24548 45716 24548 45717 22834 45717 26356 45717 24548 45718 26356 45718 24539 45718 24539 45719 26356 45719 22835 45719 24539 45720 22835 45720 22924 45720 22924 45721 22835 45721 26355 45721 22940 45722 26348 45722 22836 45722 22836 45723 26348 45723 26350 45723 22836 45724 26350 45724 22837 45724 22837 45725 26350 45725 22839 45725 22837 45726 22839 45726 22838 45726 22838 45727 22839 45727 22840 45727 22838 45728 22840 45728 24597 45728 24597 45729 22840 45729 22842 45729 24597 45730 22842 45730 22841 45730 22841 45731 22842 45731 22843 45731 22841 45732 22843 45732 22844 45732 22844 45733 22843 45733 22845 45733 22844 45734 22845 45734 24532 45734 24532 45735 22845 45735 22932 45735 24469 45736 22846 45736 24470 45736 24470 45737 22846 45737 26344 45737 24470 45738 26344 45738 22848 45738 22848 45739 26344 45739 22847 45739 22848 45740 22847 45740 24465 45740 24465 45741 22847 45741 26347 45741 24465 45742 26347 45742 22849 45742 22849 45743 26347 45743 26346 45743 22849 45744 26346 45744 22851 45744 22851 45745 26346 45745 22850 45745 22851 45746 22850 45746 22852 45746 22852 45747 22850 45747 22941 45747 22956 45748 22854 45748 22853 45748 22853 45749 22854 45749 26340 45749 22853 45750 26340 45750 24495 45750 24495 45751 26340 45751 26338 45751 24495 45752 26338 45752 22855 45752 22855 45753 26338 45753 26339 45753 22855 45754 26339 45754 22856 45754 22856 45755 26339 45755 26341 45755 22856 45756 26341 45756 22858 45756 22858 45757 26341 45757 22857 45757 22858 45758 22857 45758 22859 45758 22859 45759 22857 45759 26336 45759 24491 45760 22861 45760 22860 45760 22860 45761 22861 45761 22862 45761 22860 45762 22862 45762 22863 45762 22863 45763 22862 45763 22865 45763 22863 45764 22865 45764 22864 45764 22864 45765 22865 45765 22866 45765 22864 45766 22866 45766 22867 45766 22867 45767 22866 45767 22868 45767 22867 45768 22868 45768 22870 45768 22870 45769 22868 45769 22869 45769 22870 45770 22869 45770 22871 45770 22871 45771 22869 45771 26333 45771 22871 45772 26333 45772 22957 45772 22957 45773 26333 45773 22958 45773 22971 45774 22872 45774 24476 45774 24476 45775 22872 45775 22873 45775 24476 45776 22873 45776 22874 45776 22874 45777 22873 45777 26331 45777 22874 45778 26331 45778 22875 45778 22875 45779 26331 45779 22876 45779 22875 45780 22876 45780 22877 45780 22877 45781 22876 45781 26328 45781 22877 45782 26328 45782 24557 45782 24557 45783 26328 45783 22878 45783 24557 45784 22878 45784 24536 45784 24536 45785 22878 45785 22879 45785 22882 45786 24681 45786 22881 45786 22880 45787 26292 45787 23086 45787 23086 45788 26292 45788 23325 45788 23325 45789 26292 45789 22881 45789 22881 45790 26292 45790 26293 45790 22881 45791 26293 45791 22882 45791 24507 45792 22883 45792 24509 45792 24509 45793 22883 45793 22885 45793 24509 45794 22885 45794 22884 45794 22884 45795 22885 45795 22886 45795 22884 45796 22886 45796 24511 45796 24511 45797 22886 45797 22887 45797 24511 45798 22887 45798 22888 45798 22888 45799 22887 45799 22889 45799 22888 45800 22889 45800 22890 45800 22890 45801 22889 45801 26384 45801 22890 45802 26384 45802 22784 45802 22784 45803 26384 45803 22785 45803 22801 45804 26382 45804 22891 45804 22891 45805 26382 45805 22893 45805 22891 45806 22893 45806 22892 45806 22892 45807 22893 45807 26383 45807 22892 45808 26383 45808 24512 45808 24512 45809 26383 45809 26379 45809 24512 45810 26379 45810 22894 45810 22894 45811 26379 45811 22895 45811 22894 45812 22895 45812 22896 45812 22896 45813 22895 45813 22897 45813 22896 45814 22897 45814 24516 45814 24516 45815 22897 45815 26381 45815 24576 45816 26374 45816 24578 45816 24578 45817 26374 45817 22898 45817 24578 45818 22898 45818 24579 45818 24579 45819 22898 45819 22899 45819 24579 45820 22899 45820 22900 45820 22900 45821 22899 45821 26375 45821 22900 45822 26375 45822 24521 45822 24521 45823 26375 45823 22901 45823 24521 45824 22901 45824 22902 45824 22902 45825 22901 45825 22904 45825 22902 45826 22904 45826 22903 45826 22903 45827 22904 45827 22905 45827 22903 45828 22905 45828 24520 45828 24520 45829 22905 45829 26377 45829 22906 45830 22817 45830 24481 45830 24481 45831 22817 45831 22907 45831 24481 45832 22907 45832 24566 45832 24566 45833 22907 45833 26372 45833 24566 45834 26372 45834 24567 45834 24567 45835 26372 45835 22908 45835 24567 45836 22908 45836 24568 45836 24568 45837 22908 45837 22910 45837 24568 45838 22910 45838 22909 45838 22909 45839 22910 45839 22911 45839 22909 45840 22911 45840 24569 45840 24569 45841 22911 45841 22808 45841 22821 45842 26369 45842 24563 45842 24563 45843 26369 45843 22912 45843 24563 45844 22912 45844 24565 45844 24565 45845 22912 45845 22913 45845 24565 45846 22913 45846 22914 45846 22914 45847 22913 45847 22915 45847 22914 45848 22915 45848 22916 45848 22916 45849 22915 45849 26367 45849 22916 45850 26367 45850 22917 45850 22917 45851 26367 45851 26362 45851 22917 45852 26362 45852 24525 45852 24525 45853 26362 45853 26366 45853 24525 45854 26366 45854 24522 45854 24522 45855 26366 45855 26365 45855 24524 45856 22919 45856 22918 45856 22918 45857 22919 45857 22920 45857 22918 45858 22920 45858 24528 45858 24528 45859 22920 45859 26360 45859 24528 45860 26360 45860 24529 45860 24529 45861 26360 45861 22921 45861 24529 45862 22921 45862 24549 45862 24549 45863 22921 45863 26361 45863 24549 45864 26361 45864 24551 45864 24551 45865 26361 45865 22922 45865 24551 45866 22922 45866 24553 45866 24553 45867 22922 45867 22923 45867 22924 45868 26355 45868 24541 45868 24541 45869 26355 45869 26354 45869 24541 45870 26354 45870 24543 45870 24543 45871 26354 45871 26353 45871 24543 45872 26353 45872 22925 45872 22925 45873 26353 45873 22926 45873 22925 45874 22926 45874 22927 45874 22927 45875 22926 45875 22928 45875 22927 45876 22928 45876 22929 45876 22929 45877 22928 45877 22930 45877 22929 45878 22930 45878 24545 45878 24545 45879 22930 45879 22931 45879 24545 45880 22931 45880 22829 45880 22829 45881 22931 45881 26352 45881 24532 45882 22932 45882 22933 45882 22933 45883 22932 45883 22934 45883 22933 45884 22934 45884 22935 45884 22935 45885 22934 45885 26351 45885 22935 45886 26351 45886 24530 45886 24530 45887 26351 45887 26349 45887 24530 45888 26349 45888 22936 45888 22936 45889 26349 45889 22937 45889 22936 45890 22937 45890 22938 45890 22938 45891 22937 45891 22939 45891 22938 45892 22939 45892 22940 45892 22940 45893 22939 45893 26348 45893 22852 45894 22941 45894 24471 45894 24471 45895 22941 45895 22942 45895 24471 45896 22942 45896 22943 45896 22943 45897 22942 45897 26343 45897 22943 45898 26343 45898 22944 45898 22944 45899 26343 45899 26342 45899 22944 45900 26342 45900 22945 45900 22945 45901 26342 45901 22946 45901 22945 45902 22946 45902 22947 45902 22947 45903 22946 45903 26345 45903 22947 45904 26345 45904 24466 45904 24466 45905 26345 45905 22948 45905 24466 45906 22948 45906 24469 45906 24469 45907 22948 45907 22846 45907 22859 45908 26336 45908 22949 45908 22949 45909 26336 45909 22950 45909 22949 45910 22950 45910 24593 45910 24593 45911 22950 45911 22952 45911 24593 45912 22952 45912 22951 45912 22951 45913 22952 45913 26337 45913 22951 45914 26337 45914 24499 45914 24499 45915 26337 45915 22953 45915 24499 45916 22953 45916 24497 45916 24497 45917 22953 45917 26335 45917 24497 45918 26335 45918 22954 45918 22954 45919 26335 45919 22955 45919 22954 45920 22955 45920 22956 45920 22956 45921 22955 45921 22854 45921 22957 45922 22958 45922 24486 45922 24486 45923 22958 45923 22960 45923 24486 45924 22960 45924 22959 45924 22959 45925 22960 45925 26332 45925 22959 45926 26332 45926 24487 45926 24487 45927 26332 45927 26334 45927 24487 45928 26334 45928 22961 45928 22961 45929 26334 45929 22962 45929 22961 45930 22962 45930 24489 45930 24489 45931 22962 45931 22963 45931 24489 45932 22963 45932 24491 45932 24491 45933 22963 45933 22861 45933 24536 45934 22879 45934 22964 45934 22964 45935 22879 45935 26329 45935 22964 45936 26329 45936 22965 45936 22965 45937 26329 45937 22966 45937 22965 45938 22966 45938 24537 45938 24537 45939 22966 45939 22968 45939 24537 45940 22968 45940 22967 45940 22967 45941 22968 45941 26330 45941 22967 45942 26330 45942 22970 45942 22970 45943 26330 45943 22969 45943 22970 45944 22969 45944 22971 45944 22971 45945 22969 45945 22872 45945 22975 45946 23274 45946 22973 45946 22973 45947 23274 45947 23277 45947 23277 45948 23278 45948 22973 45948 22973 45949 23278 45949 22972 45949 22973 45950 22972 45950 23300 45950 22975 45951 22973 45951 22974 45951 22974 45952 22973 45952 25113 45952 25113 45953 22973 45953 25112 45953 25112 45954 22973 45954 23299 45954 25113 45955 26277 45955 22974 45955 22974 45956 26277 45956 25074 45956 22974 45957 25074 45957 22975 45957 22976 45958 24872 45958 22977 45958 22977 45959 24872 45959 24871 45959 22977 45960 24871 45960 22978 45960 22978 45961 24871 45961 25112 45961 22978 45962 25112 45962 23299 45962 22979 45963 22980 45963 22976 45963 22976 45964 22980 45964 22981 45964 22981 45965 24876 45965 22976 45965 22976 45966 24876 45966 24874 45966 22976 45967 24874 45967 24872 45967 22980 45968 22979 45968 26276 45968 26276 45969 22979 45969 23316 45969 23311 45970 25122 45970 22982 45970 22982 45971 25122 45971 25123 45971 22982 45972 25123 45972 23313 45972 23313 45973 25123 45973 25117 45973 23313 45974 25117 45974 23315 45974 23315 45975 25117 45975 22983 45975 23315 45976 22983 45976 23316 45976 23316 45977 22983 45977 26276 45977 25122 45978 23311 45978 25316 45978 25122 45979 25316 45979 22984 45979 22984 45980 25316 45980 23321 45980 22984 45981 23321 45981 25120 45981 22989 45982 25114 45982 22985 45982 22985 45983 25114 45983 22986 45983 22985 45984 22986 45984 23319 45984 23319 45985 22986 45985 22987 45985 23319 45986 22987 45986 23318 45986 23318 45987 22987 45987 22988 45987 23318 45988 22988 45988 23321 45988 23321 45989 22988 45989 25120 45989 25114 45990 22989 45990 22990 45990 22990 45991 22989 45991 23306 45991 22990 45992 23306 45992 23307 45992 22990 45993 23307 45993 24869 45993 24869 45994 23307 45994 22993 45994 24869 45995 22993 45995 24868 45995 23302 45996 23303 45996 22991 45996 22991 45997 24865 45997 23302 45997 23302 45998 24865 45998 22992 45998 23302 45999 22992 45999 22993 45999 22993 46000 22992 46000 22994 46000 22993 46001 22994 46001 24868 46001 22991 46002 23303 46002 25125 46002 25125 46003 23303 46003 22995 46003 23005 46004 25508 46004 22996 46004 22996 46005 26319 46005 23005 46005 23005 46006 26319 46006 22997 46006 23005 46007 22997 46007 22998 46007 23000 46008 26316 46008 25504 46008 25504 46009 26316 46009 22999 46009 25504 46010 22999 46010 25501 46010 23000 46011 25504 46011 25121 46011 25121 46012 25504 46012 23001 46012 25121 46013 23001 46013 23002 46013 23001 46014 23003 46014 23002 46014 23002 46015 23003 46015 23004 46015 23002 46016 23004 46016 22998 46016 22998 46017 23004 46017 25506 46017 22998 46018 25506 46018 23005 46018 25125 46019 22995 46019 23006 46019 23006 46020 22995 46020 25083 46020 25082 46021 25083 46021 23280 46021 23280 46022 25083 46022 22995 46022 23280 46023 22995 46023 23310 46023 25083 46024 23007 46024 23006 46024 23006 46025 23007 46025 23008 46025 23006 46026 23008 46026 25125 46026 25092 46027 25081 46027 23011 46027 23011 46028 25081 46028 23273 46028 23011 46029 23273 46029 23009 46029 25092 46030 23011 46030 23013 46030 23013 46031 23011 46031 23010 46031 23010 46032 23011 46032 25104 46032 25104 46033 23011 46033 23012 46033 23010 46034 26300 46034 23013 46034 23013 46035 26300 46035 23014 46035 23013 46036 23014 46036 25092 46036 23016 46037 24862 46037 23015 46037 23015 46038 24862 46038 24861 46038 23015 46039 24861 46039 23332 46039 23332 46040 24861 46040 25104 46040 23332 46041 25104 46041 23012 46041 23331 46042 26304 46042 23016 46042 23016 46043 26304 46043 23017 46043 23017 46044 23018 46044 23016 46044 23016 46045 23018 46045 23019 46045 23016 46046 23019 46046 24862 46046 26304 46047 23331 46047 23020 46047 23020 46048 23331 46048 23024 46048 25319 46049 23021 46049 23022 46049 23022 46050 23021 46050 25108 46050 23022 46051 25108 46051 23023 46051 23023 46052 25108 46052 25107 46052 23023 46053 25107 46053 23344 46053 23344 46054 25107 46054 23025 46054 23344 46055 23025 46055 23024 46055 23024 46056 23025 46056 23020 46056 23021 46057 25319 46057 23026 46057 23021 46058 23026 46058 25110 46058 25110 46059 23026 46059 23027 46059 25110 46060 23027 46060 23032 46060 23028 46061 26284 46061 23029 46061 23029 46062 26284 46062 25105 46062 23029 46063 25105 46063 23338 46063 23338 46064 25105 46064 23030 46064 23338 46065 23030 46065 23031 46065 23031 46066 23030 46066 25109 46066 23031 46067 25109 46067 23027 46067 23027 46068 25109 46068 23032 46068 26284 46069 23028 46069 23033 46069 23033 46070 23028 46070 23324 46070 23033 46071 23324 46071 23034 46071 23033 46072 23034 46072 24859 46072 24859 46073 23034 46073 23035 46073 24859 46074 23035 46074 24856 46074 23322 46075 23323 46075 23036 46075 23036 46076 24852 46076 23322 46076 23322 46077 24852 46077 24854 46077 23322 46078 24854 46078 23035 46078 23035 46079 24854 46079 24855 46079 23035 46080 24855 46080 24856 46080 23036 46081 23323 46081 23045 46081 23045 46082 23323 46082 23047 46082 23037 46083 26310 46083 23042 46083 23042 46084 26310 46084 23038 46084 23042 46085 23038 46085 25517 46085 25517 46086 23038 46086 25500 46086 26309 46087 23043 46087 23039 46087 23039 46088 23043 46088 23044 46088 23039 46089 23044 46089 23040 46089 23040 46090 23044 46090 23041 46090 25517 46091 25510 46091 23042 46091 23042 46092 25510 46092 25516 46092 23042 46093 25516 46093 25111 46093 25111 46094 25516 46094 25515 46094 25111 46095 25515 46095 23043 46095 23043 46096 25515 46096 25514 46096 23043 46097 25514 46097 23044 46097 23045 46098 23047 46098 23046 46098 23046 46099 23047 46099 25056 46099 25055 46100 25056 46100 23051 46100 23051 46101 25056 46101 23047 46101 23048 46102 23049 46102 23047 46102 23047 46103 23049 46103 23050 46103 23047 46104 23050 46104 23051 46104 25056 46105 26282 46105 23046 46105 23046 46106 26282 46106 26283 46106 23046 46107 26283 46107 23045 46107 23053 46108 23052 46108 23055 46108 25128 46109 23053 46109 24722 46109 24722 46110 23053 46110 23055 46110 24722 46111 23055 46111 23333 46111 23333 46112 23055 46112 23329 46112 23330 46113 23329 46113 23054 46113 23054 46114 23329 46114 23055 46114 23054 46115 23055 46115 24682 46115 24682 46116 23055 46116 23052 46116 23059 46117 24720 46117 23056 46117 23056 46118 24720 46118 23057 46118 23056 46119 23057 46119 23058 46119 23058 46120 23057 46120 24722 46120 23058 46121 24722 46121 23333 46121 23336 46122 25146 46122 23059 46122 23059 46123 25146 46123 24718 46123 24718 46124 24717 46124 23059 46124 23059 46125 24717 46125 23060 46125 23059 46126 23060 46126 24720 46126 23063 46127 23065 46127 23064 46127 23062 46128 23061 46128 23063 46128 24682 46129 23062 46129 23054 46129 23054 46130 23062 46130 23063 46130 23054 46131 23063 46131 23330 46131 23330 46132 23063 46132 23064 46132 25146 46133 23336 46133 25144 46133 25144 46134 23336 46134 23335 46134 23346 46135 23064 46135 23065 46135 23065 46136 23066 46136 23346 46136 23346 46137 23066 46137 24972 46137 23346 46138 24972 46138 23345 46138 23345 46139 24972 46139 23067 46139 23345 46140 23067 46140 23077 46140 25144 46141 23335 46141 23068 46141 25144 46142 23068 46142 23069 46142 23069 46143 23068 46143 23070 46143 23069 46144 23070 46144 23071 46144 23071 46145 23070 46145 23073 46145 23071 46146 23073 46146 23072 46146 23072 46147 23073 46147 23074 46147 23072 46148 23074 46148 25151 46148 23340 46149 23341 46149 23075 46149 23075 46150 23341 46150 23076 46150 23076 46151 23341 46151 24882 46151 24882 46152 23341 46152 23342 46152 24882 46153 23342 46153 24883 46153 24883 46154 23342 46154 23343 46154 24883 46155 23343 46155 24934 46155 24934 46156 23343 46156 23077 46156 24934 46157 23077 46157 23067 46157 23078 46158 25317 46158 24887 46158 24887 46159 25317 46159 25318 46159 24887 46160 25318 46160 23079 46160 23079 46161 25318 46161 24885 46161 24885 46162 25318 46162 23340 46162 24885 46163 23340 46163 23075 46163 23080 46164 23081 46164 23083 46164 23083 46165 23081 46165 23337 46165 23337 46166 23081 46166 23082 46166 23337 46167 23082 46167 23339 46167 23080 46168 23083 46168 24888 46168 24888 46169 23083 46169 23084 46169 24888 46170 23084 46170 23085 46170 23085 46171 23084 46171 25317 46171 23085 46172 25317 46172 23078 46172 22880 46173 23086 46173 24599 46173 24599 46174 23086 46174 23087 46174 24599 46175 23087 46175 24600 46175 24600 46176 23087 46176 23082 46176 23082 46177 23087 46177 23088 46177 23082 46178 23088 46178 23339 46178 24681 46179 23091 46179 22881 46179 22881 46180 23091 46180 23089 46180 22881 46181 23089 46181 23325 46181 23325 46182 23089 46182 23090 46182 23095 46183 23090 46183 23096 46183 23096 46184 23090 46184 23089 46184 23089 46185 23091 46185 23096 46185 23096 46186 23091 46186 24680 46186 23096 46187 24680 46187 24678 46187 23092 46188 23327 46188 23326 46188 23092 46189 23326 46189 23093 46189 23093 46190 23326 46190 23094 46190 23093 46191 23094 46191 24710 46191 24710 46192 23094 46192 23097 46192 24710 46193 23097 46193 24708 46193 23095 46194 23096 46194 23097 46194 23097 46195 23096 46195 23098 46195 23097 46196 23098 46196 24708 46196 23327 46197 23092 46197 23328 46197 23328 46198 23092 46198 25139 46198 23099 46199 23286 46199 23100 46199 23099 46200 23100 46200 25141 46200 25141 46201 23100 46201 23101 46201 25141 46202 23101 46202 23102 46202 23102 46203 23101 46203 23288 46203 23102 46204 23288 46204 25142 46204 25142 46205 23288 46205 23328 46205 25142 46206 23328 46206 25139 46206 23105 46207 23107 46207 23298 46207 23104 46208 26290 46208 23105 46208 23103 46209 23104 46209 23111 46209 23111 46210 23104 46210 23105 46210 23111 46211 23105 46211 23110 46211 23110 46212 23105 46212 23298 46212 23106 46213 23298 46213 23107 46213 23107 46214 23108 46214 23106 46214 23106 46215 23108 46215 24602 46215 23106 46216 24602 46216 23314 46216 23314 46217 24602 46217 23109 46217 23314 46218 23109 46218 23118 46218 23110 46219 23123 46219 23111 46219 23111 46220 23123 46220 23119 46220 23111 46221 23119 46221 23103 46221 23103 46222 23119 46222 23112 46222 23127 46223 23114 46223 23113 46223 23113 46224 23114 46224 25586 46224 25586 46225 23114 46225 25587 46225 25587 46226 23114 46226 23115 46226 25587 46227 23115 46227 23116 46227 23116 46228 23115 46228 23312 46228 23116 46229 23312 46229 23117 46229 23117 46230 23312 46230 23118 46230 23117 46231 23118 46231 23109 46231 24684 46232 23112 46232 23119 46232 23120 46233 24684 46233 23121 46233 23121 46234 24684 46234 23119 46234 23121 46235 23119 46235 23122 46235 23122 46236 23119 46236 23123 46236 23124 46237 23139 46237 23125 46237 23125 46238 23139 46238 25315 46238 23125 46239 25315 46239 25588 46239 25588 46240 25315 46240 23126 46240 23126 46241 25315 46241 23127 46241 23126 46242 23127 46242 23113 46242 23131 46243 23129 46243 23128 46243 23122 46244 23130 46244 23121 46244 23121 46245 23130 46245 24737 46245 23128 46246 23129 46246 23130 46246 23130 46247 23129 46247 24739 46247 23130 46248 24739 46248 24737 46248 23131 46249 23128 46249 24735 46249 24735 46250 23128 46250 23132 46250 24735 46251 23132 46251 24736 46251 24736 46252 23132 46252 23141 46252 24736 46253 23141 46253 25153 46253 23133 46254 23135 46254 23134 46254 23134 46255 23135 46255 23136 46255 23136 46256 23135 46256 23143 46256 23136 46257 23143 46257 23320 46257 23133 46258 23134 46258 25592 46258 25592 46259 23134 46259 23137 46259 25592 46260 23137 46260 23138 46260 23138 46261 23137 46261 23139 46261 23138 46262 23139 46262 23124 46262 25153 46263 23141 46263 23140 46263 23140 46264 23141 46264 23301 46264 26306 46265 23305 46265 24976 46265 24976 46266 23305 46266 23142 46266 24976 46267 23142 46267 24975 46267 24975 46268 23142 46268 23143 46268 23143 46269 23142 46269 23317 46269 23143 46270 23317 46270 23320 46270 23140 46271 23301 46271 23290 46271 23140 46272 23290 46272 23145 46272 23145 46273 23290 46273 23144 46273 23145 46274 23144 46274 25166 46274 25166 46275 23144 46275 23146 46275 25166 46276 23146 46276 23147 46276 23147 46277 23146 46277 23292 46277 23147 46278 23292 46278 25165 46278 25701 46279 25703 46279 23149 46279 26306 46280 23148 46280 23305 46280 23305 46281 23148 46281 23308 46281 23308 46282 23148 46282 23149 46282 23149 46283 23148 46283 24974 46283 23149 46284 24974 46284 25701 46284 23151 46285 23308 46285 25702 46285 25702 46286 23308 46286 23149 46286 25702 46287 23149 46287 25703 46287 23154 46288 23150 46288 25577 46288 25577 46289 23150 46289 23151 46289 25577 46290 23151 46290 25702 46290 23304 46291 24811 46291 23309 46291 23309 46292 24811 46292 24803 46292 23309 46293 24803 46293 23152 46293 23152 46294 24803 46294 23156 46294 23152 46295 23156 46295 23153 46295 23150 46296 23154 46296 23304 46296 23304 46297 23154 46297 23155 46297 23155 46298 24798 46298 23304 46298 23304 46299 24798 46299 24797 46299 23304 46300 24797 46300 24811 46300 23153 46301 23156 46301 23159 46301 23159 46302 23156 46302 25201 46302 25200 46303 23157 46303 23294 46303 23294 46304 23295 46304 25200 46304 25200 46305 23295 46305 23297 46305 25200 46306 23297 46306 23158 46306 23158 46307 23297 46307 23159 46307 23158 46308 23159 46308 25201 46308 26326 46309 23160 46309 23161 46309 23161 46310 23160 46310 24498 46310 23161 46311 24498 46311 26327 46311 26327 46312 24498 46312 24464 46312 26327 46313 24464 46313 23162 46313 23162 46314 24464 46314 24502 46314 23162 46315 24502 46315 23163 46315 23163 46316 24502 46316 24504 46316 23163 46317 24504 46317 26322 46317 26322 46318 24504 46318 24506 46318 26322 46319 24506 46319 26323 46319 26323 46320 24506 46320 23165 46320 26323 46321 23165 46321 23164 46321 23164 46322 23165 46322 23167 46322 23164 46323 23167 46323 23166 46323 23166 46324 23167 46324 24517 46324 23166 46325 24517 46325 23168 46325 23168 46326 24517 46326 23169 46326 23168 46327 23169 46327 26324 46327 26324 46328 23169 46328 23170 46328 26324 46329 23170 46329 26325 46329 26325 46330 23170 46330 23172 46330 26325 46331 23172 46331 23171 46331 23171 46332 23172 46332 26261 46332 25419 46333 23173 46333 25284 46333 25419 46334 25284 46334 25428 46334 25428 46335 25284 46335 23174 46335 25428 46336 23174 46336 23176 46336 23174 46337 23175 46337 23176 46337 23176 46338 23175 46338 25278 46338 23176 46339 25278 46339 23177 46339 23177 46340 25278 46340 23179 46340 23177 46341 23179 46341 23178 46341 23178 46342 23179 46342 23180 46342 23178 46343 23180 46343 25431 46343 25431 46344 23180 46344 23181 46344 25431 46345 23181 46345 23182 46345 23182 46346 23181 46346 25440 46346 25440 46347 23181 46347 25280 46347 25440 46348 25280 46348 23183 46348 25280 46349 23184 46349 23183 46349 23183 46350 23184 46350 25274 46350 23183 46351 25274 46351 25407 46351 25407 46352 25274 46352 25273 46352 25407 46353 25273 46353 25458 46353 25458 46354 25273 46354 23185 46354 25458 46355 23185 46355 25456 46355 23185 46356 25270 46356 25456 46356 25456 46357 25270 46357 23187 46357 25456 46358 23187 46358 25464 46358 25266 46359 25409 46359 25267 46359 25267 46360 25409 46360 25464 46360 25267 46361 25464 46361 23186 46361 23186 46362 25464 46362 23187 46362 25495 46363 25244 46363 23188 46363 25495 46364 23188 46364 25498 46364 25498 46365 23188 46365 23189 46365 25498 46366 23189 46366 23190 46366 23190 46367 23189 46367 23291 46367 23190 46368 23291 46368 25499 46368 25499 46369 23291 46369 23191 46369 25499 46370 23191 46370 25497 46370 25413 46371 23289 46371 23192 46371 25413 46372 23192 46372 25416 46372 25416 46373 23192 46373 23287 46373 25416 46374 23287 46374 23193 46374 23193 46375 23287 46375 23194 46375 23193 46376 23194 46376 25417 46376 25417 46377 23194 46377 23173 46377 25417 46378 23173 46378 25419 46378 25497 46379 23191 46379 23197 46379 23197 46380 23191 46380 23195 46380 23289 46381 25413 46381 23201 46381 23201 46382 25413 46382 23196 46382 23197 46383 23195 46383 26222 46383 23197 46384 26222 46384 25494 46384 26222 46385 23276 46385 25494 46385 25494 46386 23276 46386 23199 46386 25494 46387 23199 46387 23198 46387 23198 46388 23199 46388 23200 46388 23198 46389 23200 46389 25491 46389 23201 46390 23196 46390 23269 46390 23269 46391 23196 46391 25415 46391 23269 46392 25415 46392 26223 46392 26223 46393 25415 46393 25424 46393 26223 46394 25424 46394 23202 46394 23202 46395 25424 46395 25423 46395 23202 46396 25423 46396 23217 46396 25491 46397 23200 46397 23203 46397 23203 46398 23200 46398 25048 46398 23203 46399 25048 46399 25487 46399 25487 46400 25048 46400 23204 46400 25487 46401 23204 46401 25486 46401 25486 46402 23204 46402 25484 46402 25484 46403 23204 46403 23205 46403 25484 46404 23205 46404 25482 46404 25482 46405 23205 46405 23206 46405 25482 46406 23206 46406 25477 46406 25477 46407 23206 46407 25475 46407 25475 46408 23206 46408 23207 46408 25475 46409 23207 46409 25411 46409 25411 46410 23207 46410 25044 46410 25411 46411 25044 46411 25467 46411 25467 46412 25044 46412 23208 46412 23208 46413 25044 46413 23209 46413 23208 46414 23209 46414 23210 46414 23210 46415 23209 46415 25041 46415 23210 46416 25041 46416 25453 46416 25453 46417 25041 46417 23211 46417 23211 46418 25041 46418 23212 46418 23211 46419 23212 46419 25461 46419 25461 46420 23212 46420 25040 46420 25461 46421 25040 46421 25447 46421 25447 46422 25040 46422 23214 46422 25447 46423 23214 46423 23213 46423 23213 46424 23214 46424 25445 46424 25445 46425 23214 46425 25038 46425 25445 46426 25038 46426 25443 46426 25443 46427 25038 46427 23215 46427 25443 46428 23215 46428 25436 46428 25436 46429 23215 46429 23216 46429 23216 46430 23215 46430 25037 46430 23216 46431 25037 46431 25421 46431 25421 46432 25037 46432 23217 46432 25421 46433 23217 46433 25423 46433 25327 46434 25554 46434 23218 46434 23218 46435 25554 46435 23219 46435 23218 46436 23219 46436 25339 46436 25339 46437 23219 46437 25338 46437 23220 46438 25321 46438 23221 46438 23221 46439 25321 46439 25344 46439 23221 46440 25344 46440 23222 46440 23222 46441 25344 46441 25347 46441 23222 46442 25347 46442 23223 46442 23223 46443 25347 46443 25320 46443 23223 46444 25320 46444 25551 46444 25551 46445 25320 46445 25338 46445 25551 46446 25338 46446 25553 46446 25553 46447 25338 46447 23219 46447 25541 46448 23228 46448 25365 46448 23221 46449 25545 46449 23220 46449 23220 46450 25545 46450 25544 46450 23220 46451 25544 46451 23224 46451 23224 46452 25544 46452 23225 46452 23224 46453 23225 46453 25361 46453 25361 46454 23225 46454 23226 46454 25361 46455 23226 46455 25365 46455 25365 46456 23226 46456 23227 46456 25365 46457 23227 46457 25541 46457 25541 46458 25556 46458 23228 46458 23228 46459 25556 46459 25558 46459 23228 46460 25558 46460 23229 46460 23229 46461 25558 46461 25559 46461 23229 46462 25559 46462 25369 46462 25369 46463 25559 46463 25560 46463 25369 46464 25560 46464 23230 46464 25560 46465 25308 46465 23230 46465 23230 46466 25308 46466 25309 46466 23230 46467 25309 46467 23231 46467 25309 46468 25301 46468 23231 46468 23231 46469 25301 46469 23232 46469 23231 46470 23232 46470 25377 46470 25298 46471 25383 46471 23234 46471 23232 46472 25303 46472 25377 46472 25377 46473 25303 46473 25304 46473 25377 46474 25304 46474 25322 46474 25322 46475 25304 46475 23233 46475 25322 46476 23233 46476 23234 46476 23234 46477 23233 46477 25307 46477 23234 46478 25307 46478 25298 46478 23235 46479 23243 46479 25401 46479 25401 46480 23243 46480 23236 46480 25401 46481 23236 46481 23237 46481 25383 46482 25298 46482 23238 46482 23238 46483 25298 46483 23239 46483 23238 46484 23239 46484 23240 46484 23240 46485 23239 46485 25300 46485 23240 46486 25300 46486 23241 46486 23241 46487 25300 46487 23242 46487 23241 46488 23242 46488 23235 46488 23235 46489 23242 46489 25297 46489 23235 46490 25297 46490 23243 46490 23237 46491 23236 46491 25396 46491 25396 46492 23236 46492 25292 46492 25396 46493 25292 46493 23244 46493 23244 46494 25292 46494 23285 46494 23244 46495 23285 46495 23245 46495 23245 46496 23285 46496 23246 46496 23245 46497 23246 46497 23247 46497 23247 46498 23246 46498 23284 46498 23247 46499 23284 46499 25405 46499 25405 46500 23284 46500 23334 46500 25405 46501 23334 46501 25404 46501 25329 46502 23248 46502 23296 46502 25329 46503 23296 46503 23250 46503 23250 46504 23296 46504 23249 46504 23250 46505 23249 46505 23251 46505 23251 46506 23249 46506 23252 46506 23251 46507 23252 46507 25326 46507 25326 46508 23252 46508 25554 46508 25326 46509 25554 46509 25327 46509 25404 46510 23334 46510 23253 46510 23253 46511 23334 46511 23272 46511 23248 46512 25329 46512 26237 46512 26237 46513 25329 46513 23254 46513 23272 46514 23255 46514 23253 46514 23253 46515 23255 46515 26238 46515 23256 46516 25049 46516 23282 46516 23256 46517 23282 46517 23257 46517 23257 46518 23282 46518 23281 46518 23257 46519 23281 46519 25328 46519 25328 46520 23281 46520 23279 46520 25328 46521 23279 46521 26236 46521 25370 46522 23258 46522 23259 46522 23259 46523 23258 46523 23260 46523 23259 46524 23260 46524 25364 46524 25364 46525 23260 46525 23261 46525 25364 46526 23261 46526 23262 46526 23262 46527 23261 46527 23263 46527 23262 46528 23263 46528 25358 46528 25358 46529 23263 46529 23264 46529 25358 46530 23264 46530 25356 46530 25356 46531 23264 46531 25351 46531 25351 46532 23264 46532 23265 46532 25351 46533 23265 46533 23266 46533 23266 46534 23265 46534 25051 46534 23266 46535 25051 46535 23267 46535 23267 46536 25051 46536 25342 46536 25342 46537 25051 46537 23268 46537 25342 46538 23268 46538 25332 46538 25332 46539 23268 46539 25049 46539 25332 46540 25049 46540 23256 46540 23048 46541 23201 46541 23049 46541 23049 46542 23201 46542 23269 46542 23049 46543 23269 46543 23050 46543 23271 46544 23270 46544 26241 46544 23271 46545 26241 46545 25093 46545 25093 46546 26241 46546 26239 46546 25093 46547 26239 46547 25094 46547 23272 46548 23009 46548 23255 46548 23255 46549 23009 46549 23273 46549 23255 46550 23273 46550 26239 46550 26239 46551 23273 46551 25081 46551 26239 46552 25081 46552 25094 46552 23274 46553 23275 46553 23276 46553 23276 46554 23275 46554 25076 46554 23276 46555 25076 46555 23199 46555 23199 46556 25076 46556 25075 46556 23199 46557 25075 46557 23200 46557 23274 46558 23276 46558 23277 46558 23277 46559 23276 46559 26222 46559 23277 46560 26222 46560 23278 46560 23310 46561 26237 46561 23279 46561 23310 46562 23279 46562 23280 46562 23280 46563 23279 46563 23281 46563 23280 46564 23281 46564 25082 46564 25082 46565 23281 46565 25084 46565 25084 46566 23281 46566 23282 46566 25084 46567 23282 46567 23283 46567 23283 46568 23282 46568 25049 46568 23283 46569 25049 46569 25100 46569 23335 46570 23334 46570 23284 46570 23335 46571 23284 46571 23068 46571 23068 46572 23284 46572 23246 46572 23068 46573 23246 46573 23070 46573 23070 46574 23246 46574 23285 46574 23070 46575 23285 46575 23073 46575 23073 46576 23285 46576 25292 46576 23073 46577 25292 46577 23074 46577 23286 46578 23173 46578 23194 46578 23286 46579 23194 46579 23100 46579 23100 46580 23194 46580 23287 46580 23100 46581 23287 46581 23101 46581 23101 46582 23287 46582 23192 46582 23101 46583 23192 46583 23288 46583 23288 46584 23192 46584 23289 46584 23288 46585 23289 46585 23328 46585 23301 46586 23191 46586 23291 46586 23301 46587 23291 46587 23290 46587 23290 46588 23291 46588 23189 46588 23290 46589 23189 46589 23144 46589 23144 46590 23189 46590 23188 46590 23144 46591 23188 46591 23146 46591 23146 46592 23188 46592 25244 46592 23146 46593 25244 46593 23292 46593 25312 46594 25554 46594 23293 46594 23293 46595 25554 46595 23252 46595 23293 46596 23252 46596 23294 46596 23294 46597 23252 46597 23249 46597 23294 46598 23249 46598 23295 46598 23295 46599 23249 46599 23296 46599 23295 46600 23296 46600 23297 46600 23297 46601 23296 46601 23248 46601 23297 46602 23248 46602 23159 46602 23300 46603 23195 46603 23191 46603 22976 46604 22977 46604 23110 46604 23110 46605 22977 46605 23123 46605 22976 46606 23110 46606 22979 46606 22979 46607 23110 46607 23298 46607 22979 46608 23298 46608 23316 46608 23128 46609 23130 46609 22973 46609 22973 46610 23130 46610 23122 46610 22973 46611 23122 46611 23299 46611 23299 46612 23122 46612 23123 46612 23299 46613 23123 46613 22978 46613 22978 46614 23123 46614 22977 46614 23191 46615 23301 46615 23300 46615 23300 46616 23301 46616 23141 46616 23300 46617 23141 46617 22973 46617 22973 46618 23141 46618 23132 46618 22973 46619 23132 46619 23128 46619 22993 46620 23308 46620 23302 46620 23302 46621 23308 46621 23151 46621 23302 46622 23151 46622 23303 46622 23303 46623 23151 46623 23150 46623 23303 46624 23150 46624 22995 46624 22995 46625 23150 46625 23304 46625 22995 46626 23304 46626 23309 46626 22989 46627 23305 46627 23306 46627 23306 46628 23305 46628 23308 46628 23306 46629 23308 46629 23307 46629 23307 46630 23308 46630 22993 46630 23309 46631 23152 46631 22995 46631 22995 46632 23152 46632 23153 46632 22995 46633 23153 46633 23310 46633 23310 46634 23153 46634 23159 46634 23310 46635 23159 46635 26237 46635 26237 46636 23159 46636 23248 46636 23127 46637 23311 46637 23114 46637 23114 46638 23311 46638 23115 46638 23115 46639 23311 46639 23312 46639 23312 46640 23311 46640 22982 46640 23312 46641 22982 46641 23118 46641 23118 46642 22982 46642 23313 46642 23118 46643 23313 46643 23314 46643 23314 46644 23313 46644 23315 46644 23314 46645 23315 46645 23106 46645 23106 46646 23315 46646 23316 46646 23106 46647 23316 46647 23298 46647 23305 46648 22989 46648 22985 46648 23305 46649 22985 46649 23142 46649 23142 46650 22985 46650 23319 46650 23142 46651 23319 46651 23317 46651 23318 46652 23134 46652 23136 46652 23318 46653 23136 46653 23319 46653 23319 46654 23136 46654 23320 46654 23319 46655 23320 46655 23317 46655 23134 46656 23318 46656 23137 46656 23137 46657 23318 46657 23321 46657 23137 46658 23321 46658 23139 46658 23035 46659 23325 46659 23322 46659 23322 46660 23325 46660 23090 46660 23322 46661 23090 46661 23323 46661 23323 46662 23090 46662 23095 46662 23323 46663 23095 46663 23047 46663 23047 46664 23095 46664 23097 46664 23047 46665 23097 46665 23094 46665 23028 46666 23086 46666 23324 46666 23324 46667 23086 46667 23325 46667 23324 46668 23325 46668 23034 46668 23034 46669 23325 46669 23035 46669 23094 46670 23326 46670 23047 46670 23047 46671 23326 46671 23327 46671 23047 46672 23327 46672 23048 46672 23048 46673 23327 46673 23328 46673 23048 46674 23328 46674 23201 46674 23201 46675 23328 46675 23289 46675 23009 46676 23272 46676 23334 46676 23016 46677 23015 46677 23330 46677 23330 46678 23015 46678 23329 46678 23016 46679 23330 46679 23331 46679 23331 46680 23330 46680 23064 46680 23331 46681 23064 46681 23024 46681 23015 46682 23332 46682 23329 46682 23329 46683 23332 46683 23012 46683 23329 46684 23012 46684 23333 46684 23333 46685 23012 46685 23011 46685 23333 46686 23011 46686 23058 46686 23058 46687 23011 46687 23056 46687 23334 46688 23335 46688 23009 46688 23009 46689 23335 46689 23336 46689 23009 46690 23336 46690 23011 46690 23011 46691 23336 46691 23059 46691 23011 46692 23059 46692 23056 46692 23086 46693 23028 46693 23029 46693 23086 46694 23029 46694 23087 46694 23087 46695 23029 46695 23338 46695 23087 46696 23338 46696 23088 46696 23031 46697 23083 46697 23337 46697 23031 46698 23337 46698 23338 46698 23338 46699 23337 46699 23339 46699 23338 46700 23339 46700 23088 46700 23083 46701 23031 46701 23084 46701 23084 46702 23031 46702 23027 46702 23084 46703 23027 46703 25317 46703 23340 46704 25319 46704 23341 46704 23341 46705 25319 46705 23342 46705 23342 46706 25319 46706 23343 46706 23343 46707 25319 46707 23022 46707 23343 46708 23022 46708 23077 46708 23077 46709 23022 46709 23023 46709 23077 46710 23023 46710 23345 46710 23345 46711 23023 46711 23344 46711 23345 46712 23344 46712 23346 46712 23346 46713 23344 46713 23024 46713 23346 46714 23024 46714 23064 46714 23347 46715 26221 46715 26220 46715 26220 46716 23348 46716 23347 46716 23347 46717 23348 46717 23366 46717 23347 46718 23366 46718 23593 46718 23366 46719 23349 46719 23593 46719 23593 46720 23349 46720 23363 46720 23593 46721 23363 46721 23594 46721 23363 46722 23362 46722 23594 46722 23594 46723 23362 46723 23350 46723 23594 46724 23350 46724 23596 46724 23596 46725 23350 46725 23351 46725 23596 46726 23351 46726 23597 46726 23351 46727 23352 46727 23597 46727 23597 46728 23352 46728 23357 46728 23597 46729 23357 46729 23353 46729 26209 46730 23354 46730 23355 46730 23355 46731 23354 46731 23353 46731 23355 46732 23353 46732 23356 46732 23356 46733 23353 46733 23357 46733 23368 46734 26209 46734 23369 46734 23369 46735 26209 46735 23355 46735 23369 46736 23355 46736 23370 46736 23370 46737 23355 46737 23356 46737 23370 46738 23356 46738 23371 46738 23371 46739 23356 46739 23357 46739 23371 46740 23357 46740 23358 46740 23358 46741 23357 46741 23352 46741 23358 46742 23352 46742 23359 46742 23359 46743 23352 46743 23351 46743 23359 46744 23351 46744 23360 46744 23360 46745 23351 46745 23350 46745 23360 46746 23350 46746 23361 46746 23361 46747 23350 46747 23362 46747 23361 46748 23362 46748 23376 46748 23376 46749 23362 46749 23363 46749 23376 46750 23363 46750 23364 46750 23364 46751 23363 46751 23349 46751 23364 46752 23349 46752 23365 46752 23365 46753 23349 46753 23366 46753 23365 46754 23366 46754 23367 46754 23367 46755 23366 46755 23348 46755 23367 46756 23348 46756 26198 46756 26198 46757 23348 46757 26220 46757 25465 46758 26195 46758 23368 46758 23368 46759 23369 46759 25465 46759 25465 46760 23369 46760 23370 46760 25465 46761 23370 46761 23372 46761 23370 46762 23371 46762 23372 46762 23372 46763 23371 46763 23358 46763 23372 46764 23358 46764 23373 46764 23358 46765 23359 46765 23373 46765 23373 46766 23359 46766 23360 46766 23373 46767 23360 46767 23374 46767 23374 46768 23360 46768 23361 46768 23374 46769 23361 46769 23375 46769 23361 46770 23376 46770 23375 46770 23375 46771 23376 46771 23364 46771 23375 46772 23364 46772 25468 46772 26198 46773 25463 46773 23367 46773 23367 46774 25463 46774 25468 46774 23367 46775 25468 46775 23365 46775 23365 46776 25468 46776 23364 46776 23562 46777 26183 46777 26177 46777 26177 46778 23377 46778 23562 46778 23562 46779 23377 46779 23378 46779 23562 46780 23378 46780 23379 46780 23378 46781 23386 46781 23379 46781 23379 46782 23386 46782 23387 46782 23379 46783 23387 46783 23563 46783 23387 46784 23389 46784 23563 46784 23563 46785 23389 46785 23390 46785 23563 46786 23390 46786 23565 46786 23565 46787 23390 46787 23392 46787 23565 46788 23392 46788 23380 46788 23392 46789 23381 46789 23380 46789 23380 46790 23381 46790 23394 46790 23380 46791 23394 46791 23383 46791 23399 46792 26188 46792 23382 46792 23382 46793 26188 46793 23383 46793 23382 46794 23383 46794 23395 46794 23395 46795 23383 46795 23394 46795 26177 46796 26176 46796 23377 46796 23377 46797 26176 46797 23384 46797 23377 46798 23384 46798 23378 46798 23378 46799 23384 46799 23385 46799 23378 46800 23385 46800 23386 46800 23386 46801 23385 46801 23406 46801 23386 46802 23406 46802 23387 46802 23387 46803 23406 46803 23388 46803 23387 46804 23388 46804 23389 46804 23389 46805 23388 46805 23404 46805 23389 46806 23404 46806 23390 46806 23390 46807 23404 46807 23391 46807 23390 46808 23391 46808 23392 46808 23392 46809 23391 46809 23393 46809 23392 46810 23393 46810 23381 46810 23381 46811 23393 46811 23403 46811 23381 46812 23403 46812 23394 46812 23394 46813 23403 46813 23396 46813 23394 46814 23396 46814 23395 46814 23395 46815 23396 46815 23397 46815 23395 46816 23397 46816 23382 46816 23382 46817 23397 46817 23398 46817 23382 46818 23398 46818 23399 46818 23399 46819 23398 46819 23400 46819 23401 46820 25474 46820 23400 46820 23400 46821 23398 46821 23401 46821 23401 46822 23398 46822 23397 46822 23401 46823 23397 46823 23402 46823 23397 46824 23396 46824 23402 46824 23402 46825 23396 46825 23403 46825 23402 46826 23403 46826 25476 46826 23403 46827 23393 46827 25476 46827 25476 46828 23393 46828 23391 46828 25476 46829 23391 46829 25478 46829 25478 46830 23391 46830 23404 46830 25478 46831 23404 46831 23405 46831 23404 46832 23388 46832 23405 46832 23405 46833 23388 46833 23406 46833 23405 46834 23406 46834 25479 46834 26176 46835 25483 46835 23384 46835 23384 46836 25483 46836 25479 46836 23384 46837 25479 46837 23385 46837 23385 46838 25479 46838 23406 46838 26170 46839 23408 46839 23407 46839 23407 46840 23408 46840 23409 46840 23407 46841 23409 46841 23411 46841 23411 46842 23409 46842 23410 46842 23411 46843 23410 46843 23412 46843 23412 46844 23410 46844 23574 46844 23412 46845 23574 46845 23418 46845 23418 46846 23574 46846 23575 46846 23418 46847 23575 46847 23413 46847 23413 46848 23575 46848 23576 46848 23413 46849 23576 46849 23420 46849 23420 46850 23576 46850 23578 46850 23420 46851 23578 46851 23414 46851 23414 46852 23578 46852 23415 46852 26160 46853 26170 46853 23416 46853 23416 46854 26170 46854 23407 46854 23416 46855 23407 46855 23427 46855 23427 46856 23407 46856 23411 46856 23427 46857 23411 46857 23425 46857 23425 46858 23411 46858 23412 46858 23425 46859 23412 46859 23424 46859 23424 46860 23412 46860 23418 46860 23424 46861 23418 46861 23417 46861 23417 46862 23418 46862 23413 46862 23417 46863 23413 46863 23419 46863 23419 46864 23413 46864 23420 46864 23419 46865 23420 46865 23421 46865 23421 46866 23420 46866 23414 46866 23421 46867 26158 46867 23419 46867 23419 46868 26158 46868 23422 46868 23419 46869 23422 46869 23417 46869 23417 46870 23422 46870 25485 46870 23417 46871 25485 46871 23424 46871 23424 46872 25485 46872 23423 46872 23424 46873 23423 46873 23425 46873 23425 46874 23423 46874 23426 46874 23425 46875 23426 46875 23427 46875 23427 46876 23426 46876 23428 46876 23427 46877 23428 46877 23416 46877 23416 46878 23428 46878 23429 46878 23416 46879 23429 46879 26160 46879 26160 46880 23429 46880 25481 46880 23432 46881 23430 46881 26144 46881 26144 46882 23431 46882 23432 46882 23432 46883 23431 46883 23446 46883 23432 46884 23446 46884 23433 46884 23446 46885 23434 46885 23433 46885 23433 46886 23434 46886 23445 46886 23433 46887 23445 46887 23545 46887 23445 46888 23443 46888 23545 46888 23545 46889 23443 46889 23435 46889 23545 46890 23435 46890 23547 46890 23547 46891 23435 46891 23442 46891 23547 46892 23442 46892 23436 46892 23442 46893 23437 46893 23436 46893 23436 46894 23437 46894 23440 46894 23436 46895 23440 46895 23438 46895 26149 46896 23549 46896 23441 46896 23441 46897 23549 46897 23438 46897 23441 46898 23438 46898 23439 46898 23439 46899 23438 46899 23440 46899 26149 46900 23441 46900 26132 46900 26132 46901 23441 46901 23453 46901 23441 46902 23439 46902 23453 46902 23453 46903 23439 46903 23440 46903 23453 46904 23440 46904 23451 46904 23440 46905 23437 46905 23451 46905 23451 46906 23437 46906 23442 46906 23451 46907 23442 46907 23450 46907 23442 46908 23435 46908 23450 46908 23450 46909 23435 46909 23443 46909 23450 46910 23443 46910 23444 46910 23443 46911 23445 46911 23444 46911 23444 46912 23445 46912 23434 46912 23444 46913 23434 46913 23447 46913 26144 46914 26136 46914 23431 46914 23431 46915 26136 46915 23447 46915 23431 46916 23447 46916 23446 46916 23446 46917 23447 46917 23434 46917 26136 46918 25493 46918 23447 46918 23447 46919 25493 46919 25492 46919 23447 46920 25492 46920 23444 46920 23444 46921 25492 46921 23448 46921 23444 46922 23448 46922 23450 46922 23450 46923 23448 46923 23449 46923 23450 46924 23449 46924 23451 46924 23451 46925 23449 46925 23452 46925 23451 46926 23452 46926 23453 46926 23453 46927 23452 46927 25490 46927 23453 46928 25490 46928 26132 46928 26132 46929 25490 46929 23454 46929 23519 46930 25256 46930 25263 46930 25263 46931 23455 46931 23504 46931 23504 46932 23586 46932 25263 46932 25263 46933 23586 46933 23456 46933 25263 46934 23456 46934 23519 46934 23488 46935 25251 46935 25253 46935 25253 46936 23457 46936 23458 46936 23458 46937 23502 46937 25253 46937 25253 46938 23502 46938 23556 46938 25253 46939 23556 46939 23488 46939 23459 46940 23460 46940 25255 46940 25255 46941 23460 46941 23570 46941 23570 46942 23523 46942 25255 46942 25255 46943 23523 46943 23461 46943 25255 46944 23461 46944 25246 46944 23463 46945 23462 46945 23466 46945 23484 46946 23463 46946 23464 46946 23464 46947 23463 46947 23466 46947 23464 46948 23466 46948 23465 46948 23465 46949 23466 46949 25245 46949 23465 46950 25245 46950 25250 46950 24675 46951 23536 46951 24676 46951 24676 46952 23536 46952 23467 46952 24676 46953 23467 46953 25250 46953 25250 46954 23467 46954 23464 46954 25250 46955 23464 46955 23465 46955 23468 46956 23477 46956 23469 46956 23469 46957 23477 46957 26120 46957 23469 46958 26120 46958 24675 46958 24675 46959 26120 46959 23536 46959 23482 46960 23470 46960 25152 46960 25152 46961 23470 46961 23539 46961 23539 46962 23471 46962 25152 46962 25152 46963 23471 46963 23472 46963 25152 46964 23472 46964 23473 46964 23472 46965 23474 46965 23473 46965 23473 46966 23474 46966 23475 46966 23473 46967 23475 46967 23476 46967 23475 46968 26116 46968 23476 46968 23476 46969 26116 46969 23479 46969 23476 46970 23479 46970 25156 46970 26120 46971 23477 46971 26119 46971 26119 46972 23477 46972 25183 46972 26119 46973 25183 46973 26117 46973 26117 46974 25183 46974 25156 46974 26117 46975 25156 46975 23478 46975 23478 46976 25156 46976 23479 46976 23485 46977 23486 46977 23480 46977 23480 46978 23486 46978 23470 46978 23480 46979 23470 46979 23481 46979 23481 46980 23470 46980 23482 46980 23462 46981 23463 46981 23483 46981 23483 46982 23463 46982 23484 46982 23483 46983 23484 46983 25311 46983 25311 46984 23484 46984 23537 46984 25311 46985 23537 46985 23485 46985 23485 46986 23537 46986 23486 46986 25251 46987 23488 46987 23487 46987 23487 46988 23488 46988 23556 46988 23487 46989 23556 46989 24667 46989 24667 46990 23556 46990 23489 46990 24667 46991 23489 46991 23553 46991 24670 46992 24667 46992 23490 46992 23490 46993 24667 46993 23553 46993 24670 46994 23490 46994 25184 46994 25184 46995 23490 46995 23493 46995 25184 46996 23493 46996 23491 46996 23491 46997 23493 46997 23492 46997 23492 46998 23493 46998 23555 46998 23492 46999 23555 46999 25179 46999 23552 47000 25192 47000 23494 47000 23494 47001 25192 47001 25191 47001 23494 47002 25191 47002 26114 47002 26114 47003 25191 47003 23495 47003 26114 47004 23495 47004 26112 47004 26112 47005 23495 47005 23496 47005 26112 47006 23496 47006 23497 47006 23497 47007 23496 47007 25190 47007 23497 47008 25190 47008 26110 47008 26110 47009 25190 47009 25179 47009 26110 47010 25179 47010 23498 47010 23498 47011 25179 47011 23555 47011 25192 47012 23552 47012 24664 47012 24664 47013 23552 47013 23550 47013 24664 47014 23550 47014 23499 47014 23501 47015 23499 47015 23500 47015 23500 47016 23499 47016 23550 47016 23500 47017 23566 47017 23501 47017 23501 47018 23566 47018 23502 47018 23501 47019 23502 47019 25259 47019 25259 47020 23502 47020 23458 47020 25259 47021 23458 47021 23457 47021 23506 47022 23587 47022 23503 47022 23503 47023 23587 47023 23586 47023 23503 47024 23586 47024 24655 47024 24655 47025 23586 47025 23504 47025 24655 47026 23504 47026 23455 47026 23509 47027 23505 47027 23503 47027 23503 47028 23505 47028 23506 47028 25180 47029 23507 47029 23508 47029 23508 47030 23507 47030 23505 47030 23508 47031 23505 47031 23509 47031 23511 47032 25193 47032 23510 47032 23510 47033 23512 47033 23511 47033 23511 47034 23512 47034 23584 47034 23511 47035 23584 47035 25157 47035 23584 47036 23585 47036 25157 47036 25157 47037 23585 47037 26091 47037 25157 47038 26091 47038 23513 47038 26091 47039 26093 47039 23513 47039 23513 47040 26093 47040 26095 47040 23513 47041 26095 47041 23514 47041 23507 47042 25180 47042 26097 47042 26097 47043 25180 47043 23515 47043 26097 47044 23515 47044 23516 47044 23516 47045 23515 47045 23514 47045 23516 47046 23514 47046 26096 47046 26096 47047 23514 47047 26095 47047 24662 47048 23581 47048 24663 47048 24663 47049 23581 47049 23510 47049 24663 47050 23510 47050 25193 47050 23517 47051 23580 47051 24662 47051 24662 47052 23580 47052 23581 47052 25256 47053 23519 47053 23518 47053 23518 47054 23519 47054 23456 47054 23518 47055 23456 47055 23517 47055 23517 47056 23456 47056 23520 47056 23517 47057 23520 47057 23580 47057 23522 47058 23524 47058 24672 47058 24672 47059 23524 47059 23521 47059 24672 47060 23521 47060 25173 47060 25173 47061 23521 47061 23526 47061 25173 47062 23526 47062 23525 47062 25246 47063 23461 47063 24671 47063 24671 47064 23461 47064 23523 47064 24671 47065 23523 47065 23522 47065 23522 47066 23523 47066 23573 47066 23522 47067 23573 47067 23524 47067 23525 47068 23526 47068 23527 47068 23527 47069 23526 47069 23528 47069 23527 47070 23528 47070 25189 47070 23528 47071 23529 47071 25189 47071 25189 47072 23529 47072 26098 47072 25189 47073 26098 47073 23530 47073 26098 47074 26100 47074 23530 47074 23530 47075 26100 47075 23531 47075 23530 47076 23531 47076 25187 47076 23531 47077 26102 47077 25187 47077 25187 47078 26102 47078 26103 47078 25187 47079 26103 47079 25186 47079 26108 47080 25185 47080 26107 47080 26107 47081 25185 47081 23532 47081 26107 47082 23532 47082 26105 47082 26105 47083 23532 47083 25186 47083 26105 47084 25186 47084 23533 47084 23533 47085 25186 47085 26103 47085 25185 47086 26108 47086 24666 47086 24666 47087 26108 47087 23534 47087 24666 47088 23534 47088 24669 47088 24668 47089 24669 47089 23535 47089 23535 47090 24669 47090 23534 47090 23535 47091 23572 47091 24668 47091 24668 47092 23572 47092 23570 47092 24668 47093 23570 47093 25252 47093 25252 47094 23570 47094 23460 47094 25252 47095 23460 47095 23459 47095 23536 47096 26120 47096 23467 47096 23467 47097 26120 47097 23548 47097 23537 47098 23538 47098 23486 47098 23486 47099 23538 47099 23470 47099 23470 47100 23538 47100 23539 47100 23539 47101 23538 47101 23542 47101 23467 47102 26148 47102 26147 47102 26147 47103 23537 47103 23467 47103 23467 47104 23537 47104 23484 47104 23467 47105 23484 47105 23464 47105 26147 47106 23540 47106 23537 47106 23537 47107 23540 47107 26145 47107 23537 47108 26145 47108 23538 47108 23538 47109 26145 47109 23541 47109 23538 47110 23541 47110 23542 47110 23542 47111 23541 47111 23430 47111 23542 47112 23430 47112 26115 47112 26115 47113 23430 47113 23432 47113 26115 47114 23432 47114 23543 47114 23543 47115 23432 47115 23433 47115 23543 47116 23433 47116 23544 47116 23544 47117 23433 47117 23545 47117 23544 47118 23545 47118 23546 47118 23546 47119 23545 47119 23547 47119 23546 47120 23547 47120 26118 47120 26118 47121 23547 47121 23436 47121 26118 47122 23436 47122 23548 47122 23548 47123 23436 47123 23438 47123 23548 47124 23438 47124 23467 47124 23467 47125 23438 47125 23549 47125 23467 47126 23549 47126 26148 47126 23566 47127 23500 47127 23551 47127 23551 47128 23500 47128 23550 47128 23551 47129 23550 47129 23552 47129 23553 47130 23489 47130 23490 47130 23490 47131 23489 47131 23557 47131 23490 47132 23557 47132 23493 47132 23493 47133 23557 47133 23554 47133 23493 47134 23554 47134 23555 47134 23555 47135 23554 47135 26109 47135 23555 47136 26109 47136 23498 47136 26188 47137 26187 47137 23566 47137 26187 47138 23489 47138 23566 47138 23566 47139 23489 47139 23556 47139 23566 47140 23556 47140 23502 47140 26187 47141 26186 47141 23489 47141 23489 47142 26186 47142 23558 47142 23489 47143 23558 47143 23557 47143 23557 47144 23558 47144 23559 47144 23557 47145 23559 47145 23554 47145 23554 47146 23559 47146 23560 47146 23554 47147 23560 47147 26109 47147 26109 47148 23560 47148 26183 47148 26109 47149 26183 47149 26111 47149 26111 47150 26183 47150 23562 47150 26111 47151 23562 47151 23561 47151 23561 47152 23562 47152 23379 47152 23561 47153 23379 47153 26113 47153 26113 47154 23379 47154 23563 47154 26113 47155 23563 47155 23564 47155 23564 47156 23563 47156 23565 47156 23564 47157 23565 47157 23551 47157 23551 47158 23565 47158 23380 47158 23551 47159 23380 47159 23566 47159 23566 47160 23380 47160 23383 47160 23566 47161 23383 47161 26188 47161 23572 47162 23535 47162 23567 47162 23567 47163 23535 47163 23534 47163 23567 47164 23534 47164 26108 47164 23524 47165 23573 47165 23521 47165 23521 47166 23573 47166 23568 47166 23521 47167 23568 47167 23526 47167 23526 47168 23568 47168 23569 47168 23526 47169 23569 47169 23528 47169 23528 47170 23569 47170 26099 47170 23528 47171 26099 47171 23529 47171 23573 47172 23523 47172 23572 47172 23572 47173 23523 47173 23570 47173 23408 47174 23571 47174 23572 47174 23572 47175 23571 47175 26168 47175 23572 47176 26168 47176 23573 47176 23573 47177 26168 47177 26166 47177 23573 47178 26166 47178 26164 47178 23408 47179 23572 47179 23409 47179 23409 47180 23572 47180 23567 47180 23409 47181 23567 47181 23410 47181 23410 47182 23567 47182 23574 47182 23574 47183 23567 47183 26106 47183 23574 47184 26106 47184 23575 47184 23575 47185 26106 47185 23577 47185 23575 47186 23577 47186 23576 47186 23576 47187 23577 47187 26104 47187 23576 47188 26104 47188 23578 47188 23578 47189 26104 47189 26101 47189 23578 47190 26101 47190 23415 47190 23415 47191 26101 47191 26099 47191 23415 47192 26099 47192 26161 47192 26161 47193 26099 47193 23569 47193 26161 47194 23569 47194 26164 47194 26164 47195 23569 47195 23568 47195 26164 47196 23568 47196 23573 47196 23587 47197 23506 47197 23579 47197 23579 47198 23506 47198 23505 47198 23579 47199 23505 47199 23507 47199 23580 47200 23520 47200 23581 47200 23581 47201 23520 47201 23582 47201 23581 47202 23582 47202 23510 47202 23510 47203 23582 47203 23583 47203 23510 47204 23583 47204 23512 47204 23512 47205 23583 47205 23590 47205 23512 47206 23590 47206 23584 47206 23584 47207 23590 47207 23585 47207 23585 47208 23590 47208 26092 47208 23585 47209 26092 47209 26091 47209 23353 47210 23354 47210 23587 47210 23456 47211 23586 47211 23520 47211 23520 47212 23586 47212 23587 47212 23520 47213 23587 47213 23588 47213 23588 47214 23587 47214 23354 47214 23588 47215 26210 47215 23520 47215 23520 47216 26210 47216 26216 47216 23520 47217 26216 47217 23582 47217 23582 47218 26216 47218 23589 47218 23582 47219 23589 47219 23583 47219 23583 47220 23589 47220 23591 47220 23583 47221 23591 47221 23590 47221 23590 47222 23591 47222 26092 47222 26092 47223 23591 47223 26221 47223 26092 47224 26221 47224 26094 47224 26094 47225 26221 47225 23347 47225 26094 47226 23347 47226 23592 47226 23592 47227 23347 47227 23593 47227 23592 47228 23593 47228 23595 47228 23595 47229 23593 47229 23594 47229 23595 47230 23594 47230 23579 47230 23579 47231 23594 47231 23596 47231 23579 47232 23596 47232 23587 47232 23587 47233 23596 47233 23597 47233 23587 47234 23597 47234 23353 47234 23832 47235 23615 47235 23598 47235 23598 47236 23615 47236 23613 47236 23598 47237 23613 47237 23600 47237 23600 47238 23613 47238 23599 47238 23599 47239 23601 47239 23600 47239 23600 47240 23601 47240 23602 47240 23600 47241 23602 47241 23603 47241 23602 47242 23604 47242 23603 47242 23603 47243 23604 47243 23607 47243 23603 47244 23607 47244 23828 47244 26081 47245 23606 47245 23605 47245 23605 47246 23606 47246 23827 47246 23605 47247 23827 47247 23609 47247 23609 47248 23827 47248 23828 47248 23609 47249 23828 47249 23611 47249 23611 47250 23828 47250 23607 47250 23608 47251 26081 47251 23605 47251 23608 47252 23605 47252 23622 47252 23622 47253 23605 47253 23609 47253 23622 47254 23609 47254 23610 47254 23610 47255 23609 47255 23611 47255 23610 47256 23611 47256 23620 47256 23611 47257 23607 47257 23620 47257 23620 47258 23607 47258 23604 47258 23620 47259 23604 47259 23612 47259 23604 47260 23602 47260 23612 47260 23612 47261 23602 47261 23601 47261 23612 47262 23601 47262 23618 47262 23601 47263 23599 47263 23618 47263 23618 47264 23599 47264 23613 47264 23618 47265 23613 47265 23614 47265 23614 47266 23613 47266 23615 47266 23614 47267 23615 47267 26071 47267 26071 47268 23616 47268 23614 47268 23614 47269 23616 47269 23617 47269 23614 47270 23617 47270 23618 47270 23618 47271 23617 47271 25460 47271 23618 47272 25460 47272 23612 47272 23612 47273 25460 47273 23619 47273 23612 47274 23619 47274 23620 47274 23620 47275 23619 47275 25459 47275 23620 47276 25459 47276 23610 47276 23610 47277 25459 47277 23621 47277 23610 47278 23621 47278 23622 47278 23622 47279 23621 47279 25457 47279 23622 47280 25457 47280 23608 47280 23608 47281 25457 47281 23623 47281 26066 47282 23624 47282 23629 47282 23629 47283 23624 47283 23625 47283 23629 47284 23625 47284 23631 47284 23631 47285 23625 47285 23792 47285 23631 47286 23792 47286 23632 47286 23632 47287 23792 47287 23626 47287 23632 47288 23626 47288 23633 47288 23633 47289 23626 47289 23627 47289 23633 47290 23627 47290 23628 47290 23628 47291 23627 47291 23797 47291 23628 47292 23797 47292 23635 47292 23635 47293 23797 47293 26057 47293 23641 47294 26066 47294 23639 47294 23639 47295 26066 47295 23629 47295 23639 47296 23629 47296 23630 47296 23630 47297 23629 47297 23631 47297 23630 47298 23631 47298 23638 47298 23638 47299 23631 47299 23632 47299 23638 47300 23632 47300 23637 47300 23637 47301 23632 47301 23633 47301 23637 47302 23633 47302 23636 47302 23636 47303 23633 47303 23628 47303 23636 47304 23628 47304 23634 47304 23634 47305 23628 47305 23635 47305 23634 47306 26049 47306 23636 47306 23636 47307 26049 47307 25450 47307 23636 47308 25450 47308 23637 47308 23637 47309 25450 47309 25438 47309 23637 47310 25438 47310 23638 47310 23638 47311 25438 47311 25439 47311 23638 47312 25439 47312 23630 47312 23630 47313 25439 47313 23640 47313 23630 47314 23640 47314 23639 47314 23639 47315 23640 47315 25441 47315 23639 47316 25441 47316 23641 47316 23641 47317 25441 47317 25442 47317 26042 47318 23815 47318 23643 47318 23643 47319 23815 47319 23642 47319 23643 47320 23642 47320 23646 47320 23646 47321 23642 47321 23644 47321 23646 47322 23644 47322 23647 47322 23647 47323 23644 47323 23823 47323 23647 47324 23823 47324 23649 47324 23649 47325 23823 47325 23822 47325 23649 47326 23822 47326 23650 47326 23650 47327 23822 47327 23821 47327 23650 47328 23821 47328 26027 47328 26027 47329 23821 47329 26035 47329 26033 47330 26042 47330 23656 47330 23656 47331 26042 47331 23643 47331 23656 47332 23643 47332 23645 47332 23645 47333 23643 47333 23646 47333 23645 47334 23646 47334 23654 47334 23654 47335 23646 47335 23647 47335 23654 47336 23647 47336 23648 47336 23648 47337 23647 47337 23649 47337 23648 47338 23649 47338 23653 47338 23653 47339 23649 47339 23650 47339 23653 47340 23650 47340 23651 47340 23651 47341 23650 47341 26027 47341 23651 47342 23652 47342 23653 47342 23653 47343 23652 47343 25435 47343 23653 47344 25435 47344 23648 47344 23648 47345 25435 47345 23655 47345 23648 47346 23655 47346 23654 47346 23654 47347 23655 47347 25433 47347 23654 47348 25433 47348 23645 47348 23645 47349 25433 47349 25429 47349 23645 47350 25429 47350 23656 47350 23656 47351 25429 47351 23657 47351 23656 47352 23657 47352 26033 47352 26033 47353 23657 47353 26021 47353 23659 47354 26017 47354 23680 47354 23680 47355 23658 47355 23659 47355 23659 47356 23658 47356 23660 47356 23659 47357 23660 47357 23662 47357 23662 47358 23660 47358 23661 47358 23661 47359 23663 47359 23662 47359 23662 47360 23663 47360 23677 47360 23662 47361 23677 47361 23664 47361 23677 47362 23665 47362 23664 47362 23664 47363 23665 47363 23676 47363 23664 47364 23676 47364 23666 47364 23676 47365 23673 47365 23666 47365 23666 47366 23673 47366 23670 47366 23666 47367 23670 47367 23842 47367 23672 47368 23667 47368 23668 47368 23668 47369 23667 47369 23842 47369 23668 47370 23842 47370 23669 47370 23669 47371 23842 47371 23670 47371 23681 47372 23672 47372 23671 47372 23671 47373 23672 47373 23668 47373 23671 47374 23668 47374 23682 47374 23682 47375 23668 47375 23669 47375 23682 47376 23669 47376 23684 47376 23684 47377 23669 47377 23670 47377 23684 47378 23670 47378 23685 47378 23685 47379 23670 47379 23673 47379 23685 47380 23673 47380 23674 47380 23674 47381 23673 47381 23676 47381 23674 47382 23676 47382 23675 47382 23675 47383 23676 47383 23665 47383 23675 47384 23665 47384 23687 47384 23687 47385 23665 47385 23677 47385 23687 47386 23677 47386 23688 47386 23688 47387 23677 47387 23663 47387 23688 47388 23663 47388 23678 47388 23678 47389 23663 47389 23661 47389 23678 47390 23661 47390 23679 47390 23679 47391 23661 47391 23660 47391 23679 47392 23660 47392 23690 47392 23690 47393 23660 47393 23658 47393 23690 47394 23658 47394 23689 47394 23689 47395 23658 47395 23680 47395 23683 47396 25427 47396 23681 47396 23681 47397 23671 47397 23683 47397 23683 47398 23671 47398 23682 47398 23683 47399 23682 47399 23686 47399 23686 47400 23682 47400 23684 47400 23684 47401 23685 47401 23686 47401 23686 47402 23685 47402 23674 47402 23686 47403 23674 47403 25420 47403 23674 47404 23675 47404 25420 47404 25420 47405 23675 47405 23687 47405 25420 47406 23687 47406 25418 47406 23687 47407 23688 47407 25418 47407 25418 47408 23688 47408 23678 47408 25418 47409 23678 47409 23691 47409 23689 47410 25414 47410 23690 47410 23690 47411 25414 47411 23691 47411 23690 47412 23691 47412 23679 47412 23679 47413 23691 47413 23678 47413 25272 47414 23762 47414 23692 47414 23692 47415 23762 47415 23761 47415 23761 47416 23745 47416 23692 47416 23692 47417 23745 47417 23693 47417 23692 47418 23693 47418 25271 47418 25279 47419 23695 47419 23694 47419 23694 47420 23695 47420 23725 47420 23725 47421 23791 47421 23694 47421 23694 47422 23791 47422 23742 47422 23694 47423 23742 47423 23696 47423 23700 47424 23697 47424 23698 47424 23698 47425 23770 47425 23769 47425 23769 47426 23768 47426 23698 47426 23698 47427 23768 47427 23699 47427 23698 47428 23699 47428 23700 47428 23703 47429 25285 47429 23701 47429 23701 47430 23724 47430 23723 47430 23723 47431 23841 47431 23701 47431 23701 47432 23841 47432 23702 47432 23701 47433 23702 47433 23703 47433 25285 47434 23703 47434 23704 47434 23704 47435 23703 47435 23702 47435 23704 47436 23702 47436 23707 47436 23707 47437 23702 47437 23840 47437 23707 47438 23840 47438 23705 47438 24642 47439 23707 47439 23706 47439 23706 47440 23707 47440 23705 47440 24642 47441 23706 47441 23708 47441 23708 47442 23706 47442 23709 47442 23708 47443 23709 47443 25135 47443 25135 47444 23709 47444 25136 47444 25136 47445 23709 47445 23710 47445 25136 47446 23710 47446 23711 47446 23710 47447 23850 47447 23711 47447 23711 47448 23850 47448 23712 47448 23711 47449 23712 47449 25138 47449 25138 47450 23712 47450 23713 47450 23713 47451 23853 47451 25138 47451 25138 47452 23853 47452 23714 47452 25138 47453 23714 47453 23715 47453 23714 47454 23716 47454 23715 47454 23715 47455 23716 47455 23854 47455 23715 47456 23854 47456 23717 47456 23719 47457 25140 47457 23856 47457 23856 47458 25140 47458 23717 47458 23856 47459 23717 47459 23855 47459 23855 47460 23717 47460 23854 47460 25140 47461 23719 47461 23718 47461 23718 47462 23719 47462 23720 47462 23718 47463 23720 47463 25130 47463 23721 47464 25130 47464 23722 47464 23722 47465 25130 47465 23720 47465 23722 47466 23837 47466 23721 47466 23721 47467 23837 47467 23841 47467 23721 47468 23841 47468 25129 47468 25129 47469 23841 47469 23723 47469 25129 47470 23723 47470 23724 47470 23728 47471 23779 47471 24643 47471 24643 47472 23779 47472 23725 47472 24643 47473 23725 47473 23726 47473 23726 47474 23725 47474 23695 47474 23726 47475 23695 47475 25279 47475 24646 47476 23727 47476 24643 47476 24643 47477 23727 47477 23728 47477 23729 47478 23730 47478 23731 47478 23731 47479 23730 47479 23727 47479 23731 47480 23727 47480 24646 47480 23732 47481 23782 47481 25168 47481 25168 47482 23782 47482 23784 47482 25168 47483 23784 47483 25159 47483 23784 47484 23733 47484 25159 47484 25159 47485 23733 47485 23786 47485 25159 47486 23786 47486 23736 47486 23736 47487 23786 47487 23788 47487 23788 47488 23734 47488 23736 47488 23736 47489 23734 47489 23735 47489 23736 47490 23735 47490 23737 47490 23730 47491 23729 47491 25999 47491 25999 47492 23729 47492 23738 47492 25999 47493 23738 47493 23790 47493 23790 47494 23738 47494 23737 47494 23790 47495 23737 47495 23739 47495 23739 47496 23737 47496 23735 47496 24654 47497 23741 47497 25178 47497 25178 47498 23741 47498 23782 47498 25178 47499 23782 47499 23732 47499 24653 47500 23740 47500 24654 47500 24654 47501 23740 47501 23741 47501 23696 47502 23742 47502 23743 47502 23743 47503 23742 47503 23791 47503 23743 47504 23791 47504 24653 47504 24653 47505 23791 47505 23793 47505 24653 47506 23793 47506 23740 47506 25271 47507 23693 47507 23744 47507 23744 47508 23693 47508 23745 47508 23744 47509 23745 47509 24661 47509 24661 47510 23745 47510 23746 47510 24661 47511 23746 47511 23747 47511 23748 47512 24661 47512 23824 47512 23824 47513 24661 47513 23747 47513 23748 47514 23824 47514 25175 47514 25175 47515 23824 47515 23749 47515 25175 47516 23749 47516 25174 47516 25174 47517 23749 47517 25181 47517 25181 47518 23749 47518 23750 47518 25181 47519 23750 47519 23751 47519 23751 47520 23750 47520 23752 47520 23751 47521 23752 47521 23754 47521 23752 47522 23753 47522 23754 47522 23754 47523 23753 47523 23755 47523 23754 47524 23755 47524 25182 47524 25998 47525 23756 47525 23757 47525 23757 47526 23756 47526 25169 47526 23757 47527 25169 47527 25996 47527 25996 47528 25169 47528 25167 47528 25996 47529 25167 47529 25994 47529 25994 47530 25167 47530 25182 47530 25994 47531 25182 47531 23758 47531 23758 47532 25182 47532 23755 47532 23756 47533 25998 47533 25176 47533 25176 47534 25998 47534 23759 47534 25176 47535 23759 47535 24650 47535 24648 47536 24650 47536 23760 47536 23760 47537 24650 47537 23759 47537 23760 47538 23829 47538 24648 47538 24648 47539 23829 47539 23761 47539 24648 47540 23761 47540 24649 47540 24649 47541 23761 47541 23762 47541 24649 47542 23762 47542 25272 47542 23763 47543 23764 47543 23798 47543 23798 47544 23764 47544 23765 47544 23766 47545 23800 47545 24426 47545 24426 47546 23800 47546 23765 47546 24426 47547 23765 47547 23764 47547 23798 47548 23767 47548 23763 47548 23763 47549 23767 47549 23768 47549 23763 47550 23768 47550 24620 47550 24620 47551 23768 47551 23769 47551 24620 47552 23769 47552 23770 47552 23771 47553 23772 47553 25163 47553 25163 47554 23772 47554 23804 47554 25163 47555 23804 47555 25164 47555 23804 47556 23805 47556 25164 47556 25164 47557 23805 47557 23806 47557 25164 47558 23806 47558 25172 47558 23806 47559 23808 47559 25172 47559 25172 47560 23808 47560 23773 47560 25172 47561 23773 47561 23774 47561 23773 47562 23809 47562 23774 47562 23774 47563 23809 47563 23811 47563 23774 47564 23811 47564 25170 47564 23800 47565 23766 47565 23775 47565 23775 47566 23766 47566 23776 47566 23775 47567 23776 47567 23813 47567 23813 47568 23776 47568 25170 47568 23813 47569 25170 47569 23812 47569 23812 47570 25170 47570 23811 47570 24647 47571 23801 47571 23777 47571 23777 47572 23801 47572 23772 47572 23777 47573 23772 47573 23771 47573 24645 47574 23778 47574 24647 47574 24647 47575 23778 47575 23801 47575 23697 47576 23700 47576 24644 47576 24644 47577 23700 47577 23699 47577 24644 47578 23699 47578 24645 47578 24645 47579 23699 47579 23814 47579 24645 47580 23814 47580 23778 47580 23779 47581 23728 47581 23780 47581 23780 47582 23728 47582 23727 47582 23780 47583 23727 47583 23730 47583 23740 47584 23793 47584 23741 47584 23741 47585 23793 47585 23781 47585 23741 47586 23781 47586 23782 47586 23782 47587 23781 47587 23783 47587 23782 47588 23783 47588 23784 47588 23784 47589 23783 47589 23785 47589 23784 47590 23785 47590 23733 47590 23733 47591 23785 47591 23786 47591 23786 47592 23785 47592 23787 47592 23786 47593 23787 47593 23788 47593 23788 47594 23787 47594 23734 47594 23734 47595 23787 47595 23789 47595 23734 47596 23789 47596 23735 47596 23735 47597 23789 47597 23739 47597 23739 47598 23789 47598 23795 47598 23739 47599 23795 47599 23790 47599 23791 47600 23725 47600 23793 47600 23793 47601 23725 47601 23779 47601 23793 47602 23779 47602 23625 47602 23625 47603 23779 47603 23792 47603 23625 47604 23624 47604 23793 47604 23793 47605 23624 47605 26065 47605 23793 47606 26065 47606 23781 47606 23781 47607 26065 47607 23794 47607 23781 47608 23794 47608 23783 47608 23783 47609 23794 47609 26063 47609 23783 47610 26063 47610 23785 47610 23785 47611 26063 47611 26061 47611 23785 47612 26061 47612 23787 47612 23787 47613 26061 47613 26060 47613 23787 47614 26060 47614 23789 47614 23789 47615 26060 47615 26058 47615 23789 47616 26058 47616 23795 47616 23795 47617 26058 47617 26057 47617 23795 47618 26057 47618 23796 47618 23796 47619 26057 47619 23797 47619 23796 47620 23797 47620 23780 47620 23780 47621 23797 47621 23627 47621 23780 47622 23627 47622 23779 47622 23779 47623 23627 47623 23626 47623 23779 47624 23626 47624 23792 47624 23767 47625 23798 47625 23799 47625 23799 47626 23798 47626 23765 47626 23799 47627 23765 47627 23800 47627 23778 47628 23814 47628 23801 47628 23801 47629 23814 47629 23802 47629 23801 47630 23802 47630 23772 47630 23804 47631 23772 47631 23803 47631 23803 47632 23772 47632 23802 47632 23804 47633 23803 47633 23805 47633 23805 47634 23803 47634 23807 47634 23805 47635 23807 47635 23806 47635 23806 47636 23807 47636 23808 47636 23808 47637 23807 47637 23810 47637 23808 47638 23810 47638 23773 47638 23773 47639 23810 47639 23809 47639 23809 47640 23810 47640 23816 47640 23809 47641 23816 47641 23811 47641 23811 47642 23816 47642 23812 47642 23812 47643 23816 47643 23819 47643 23812 47644 23819 47644 23813 47644 23814 47645 23699 47645 23768 47645 23802 47646 23814 47646 23815 47646 23815 47647 26043 47647 23802 47647 23802 47648 26043 47648 26040 47648 23802 47649 26040 47649 23803 47649 23803 47650 26040 47650 26039 47650 23803 47651 26039 47651 23807 47651 23807 47652 26039 47652 26037 47652 23807 47653 26037 47653 23810 47653 23810 47654 26037 47654 23817 47654 23810 47655 23817 47655 23816 47655 23816 47656 23817 47656 23818 47656 23816 47657 23818 47657 23819 47657 23819 47658 23818 47658 26035 47658 23819 47659 26035 47659 23820 47659 23820 47660 26035 47660 23821 47660 23820 47661 23821 47661 23799 47661 23799 47662 23821 47662 23822 47662 23799 47663 23822 47663 23767 47663 23767 47664 23822 47664 23823 47664 23767 47665 23823 47665 23768 47665 23768 47666 23823 47666 23644 47666 23768 47667 23644 47667 23814 47667 23814 47668 23644 47668 23642 47668 23814 47669 23642 47669 23815 47669 23829 47670 23760 47670 25997 47670 25997 47671 23760 47671 23759 47671 25997 47672 23759 47672 25998 47672 23747 47673 23746 47673 23824 47673 23824 47674 23746 47674 23836 47674 23824 47675 23836 47675 23749 47675 23749 47676 23836 47676 23835 47676 23749 47677 23835 47677 23750 47677 23750 47678 23835 47678 23825 47678 23750 47679 23825 47679 23752 47679 23752 47680 23825 47680 23753 47680 23753 47681 23825 47681 23826 47681 23753 47682 23826 47682 23755 47682 23755 47683 23826 47683 23758 47683 23758 47684 23826 47684 25995 47684 23758 47685 25995 47685 25994 47685 23746 47686 23745 47686 23829 47686 23829 47687 23745 47687 23761 47687 23600 47688 23603 47688 23829 47688 23606 47689 23746 47689 23827 47689 23827 47690 23746 47690 23829 47690 23827 47691 23829 47691 23828 47691 23828 47692 23829 47692 23603 47692 23829 47693 25997 47693 23600 47693 23600 47694 25997 47694 23830 47694 23600 47695 23830 47695 23598 47695 23598 47696 23830 47696 23831 47696 23598 47697 23831 47697 23832 47697 23832 47698 23831 47698 25995 47698 23832 47699 25995 47699 23833 47699 23833 47700 25995 47700 23826 47700 23833 47701 23826 47701 23834 47701 23834 47702 23826 47702 23825 47702 23834 47703 23825 47703 26089 47703 26089 47704 23825 47704 23835 47704 26089 47705 23835 47705 26088 47705 26088 47706 23835 47706 23836 47706 26088 47707 23836 47707 26085 47707 26085 47708 23836 47708 23746 47708 26085 47709 23746 47709 26083 47709 26083 47710 23746 47710 23606 47710 23837 47711 23722 47711 23838 47711 23838 47712 23722 47712 23720 47712 23838 47713 23720 47713 23719 47713 23705 47714 23840 47714 23706 47714 23706 47715 23840 47715 23839 47715 23706 47716 23839 47716 23709 47716 23840 47717 23702 47717 23841 47717 23840 47718 23841 47718 23666 47718 26017 47719 23659 47719 23837 47719 23837 47720 23659 47720 23662 47720 23837 47721 23662 47721 23841 47721 23841 47722 23662 47722 23664 47722 23841 47723 23664 47723 23666 47723 23666 47724 23842 47724 23840 47724 23840 47725 23842 47725 23667 47725 23840 47726 23667 47726 23839 47726 23839 47727 23667 47727 23843 47727 23839 47728 23843 47728 23849 47728 23849 47729 23843 47729 23848 47729 23837 47730 23838 47730 26017 47730 26017 47731 23838 47731 25993 47731 26017 47732 25993 47732 26018 47732 26018 47733 25993 47733 23845 47733 26018 47734 23845 47734 23844 47734 23844 47735 23845 47735 23846 47735 23844 47736 23846 47736 23847 47736 23847 47737 23846 47737 23852 47737 23847 47738 23852 47738 23848 47738 23848 47739 23852 47739 23851 47739 23848 47740 23851 47740 23849 47740 23709 47741 23839 47741 23849 47741 23709 47742 23849 47742 23710 47742 23710 47743 23849 47743 23851 47743 23710 47744 23851 47744 23850 47744 23850 47745 23851 47745 23712 47745 23712 47746 23851 47746 23852 47746 23712 47747 23852 47747 23713 47747 23713 47748 23852 47748 23853 47748 23853 47749 23852 47749 23846 47749 23853 47750 23846 47750 23714 47750 23714 47751 23846 47751 23716 47751 23716 47752 23846 47752 23845 47752 23716 47753 23845 47753 23854 47753 23854 47754 23845 47754 23855 47754 23855 47755 23845 47755 25993 47755 23855 47756 25993 47756 23856 47756 25987 47757 23857 47757 23859 47757 23859 47758 23857 47758 23858 47758 23859 47759 23858 47759 23868 47759 23868 47760 23858 47760 24087 47760 23868 47761 24087 47761 23860 47761 23860 47762 24087 47762 23862 47762 23860 47763 23862 47763 23861 47763 23861 47764 23862 47764 23863 47764 23861 47765 23863 47765 23864 47765 23864 47766 23863 47766 24090 47766 23864 47767 24090 47767 23865 47767 23865 47768 24090 47768 23866 47768 23865 47769 23866 47769 23867 47769 23867 47770 23866 47770 24079 47770 25986 47771 25987 47771 23878 47771 23878 47772 25987 47772 23859 47772 23878 47773 23859 47773 23876 47773 23876 47774 23859 47774 23868 47774 23876 47775 23868 47775 23875 47775 23875 47776 23868 47776 23860 47776 23875 47777 23860 47777 23869 47777 23869 47778 23860 47778 23861 47778 23869 47779 23861 47779 23873 47779 23873 47780 23861 47780 23864 47780 23873 47781 23864 47781 23870 47781 23870 47782 23864 47782 23865 47782 23870 47783 23865 47783 25981 47783 25981 47784 23865 47784 23867 47784 25981 47785 23871 47785 23870 47785 23870 47786 23871 47786 23872 47786 23870 47787 23872 47787 23873 47787 23873 47788 23872 47788 23874 47788 23873 47789 23874 47789 23869 47789 23869 47790 23874 47790 25367 47790 23869 47791 25367 47791 23875 47791 23875 47792 25367 47792 25366 47792 23875 47793 25366 47793 23876 47793 23876 47794 25366 47794 23877 47794 23876 47795 23877 47795 23878 47795 23878 47796 23877 47796 23879 47796 23878 47797 23879 47797 25986 47797 25986 47798 23879 47798 23880 47798 23881 47799 23882 47799 23889 47799 23889 47800 23882 47800 24039 47800 23889 47801 24039 47801 23883 47801 23883 47802 24039 47802 24038 47802 23883 47803 24038 47803 23884 47803 23884 47804 24038 47804 23885 47804 23884 47805 23885 47805 23891 47805 23891 47806 23885 47806 23886 47806 23891 47807 23886 47807 23892 47807 23892 47808 23886 47808 24036 47808 23892 47809 24036 47809 23894 47809 23894 47810 24036 47810 23887 47810 23894 47811 23887 47811 25962 47811 25962 47812 23887 47812 23888 47812 23902 47813 23881 47813 23901 47813 23901 47814 23881 47814 23889 47814 23901 47815 23889 47815 23899 47815 23899 47816 23889 47816 23883 47816 23899 47817 23883 47817 23890 47817 23890 47818 23883 47818 23884 47818 23890 47819 23884 47819 23898 47819 23898 47820 23884 47820 23891 47820 23898 47821 23891 47821 23897 47821 23897 47822 23891 47822 23892 47822 23897 47823 23892 47823 23893 47823 23893 47824 23892 47824 23894 47824 23893 47825 23894 47825 23895 47825 23895 47826 23894 47826 25962 47826 23895 47827 25353 47827 23893 47827 23893 47828 25353 47828 25360 47828 23893 47829 25360 47829 23897 47829 23897 47830 25360 47830 23896 47830 23897 47831 23896 47831 23898 47831 23898 47832 23896 47832 25359 47832 23898 47833 25359 47833 23890 47833 23890 47834 25359 47834 25357 47834 23890 47835 25357 47835 23899 47835 23899 47836 25357 47836 23900 47836 23899 47837 23900 47837 23901 47837 23901 47838 23900 47838 25355 47838 23901 47839 25355 47839 23902 47839 23902 47840 25355 47840 23903 47840 25954 47841 23905 47841 23904 47841 23904 47842 23905 47842 23906 47842 23904 47843 23906 47843 23911 47843 23911 47844 23906 47844 24066 47844 23911 47845 24066 47845 23907 47845 23907 47846 24066 47846 24065 47846 23907 47847 24065 47847 23908 47847 23908 47848 24065 47848 24064 47848 23908 47849 24064 47849 23909 47849 23909 47850 24064 47850 23910 47850 23909 47851 23910 47851 25947 47851 25947 47852 23910 47852 24062 47852 25953 47853 25954 47853 23920 47853 23920 47854 25954 47854 23904 47854 23920 47855 23904 47855 23918 47855 23918 47856 23904 47856 23911 47856 23918 47857 23911 47857 23916 47857 23916 47858 23911 47858 23907 47858 23916 47859 23907 47859 23912 47859 23912 47860 23907 47860 23908 47860 23912 47861 23908 47861 23913 47861 23913 47862 23908 47862 23909 47862 23913 47863 23909 47863 25945 47863 25945 47864 23909 47864 25947 47864 25945 47865 23914 47865 23913 47865 23913 47866 23914 47866 23915 47866 23913 47867 23915 47867 23912 47867 23912 47868 23915 47868 25343 47868 23912 47869 25343 47869 23916 47869 23916 47870 25343 47870 23917 47870 23916 47871 23917 47871 23918 47871 23918 47872 23917 47872 23919 47872 23918 47873 23919 47873 23920 47873 23920 47874 23919 47874 23921 47874 23920 47875 23921 47875 25953 47875 25953 47876 23921 47876 25345 47876 25936 47877 23922 47877 23928 47877 23928 47878 23922 47878 24008 47878 23928 47879 24008 47879 23923 47879 23923 47880 24008 47880 24020 47880 23923 47881 24020 47881 23924 47881 23924 47882 24020 47882 24019 47882 23924 47883 24019 47883 23925 47883 23925 47884 24019 47884 24017 47884 23925 47885 24017 47885 23926 47885 23926 47886 24017 47886 24015 47886 23926 47887 24015 47887 23927 47887 23927 47888 24015 47888 24014 47888 23927 47889 24014 47889 23931 47889 23931 47890 24014 47890 24013 47890 25928 47891 25936 47891 23936 47891 23936 47892 25936 47892 23928 47892 23936 47893 23928 47893 23935 47893 23935 47894 23928 47894 23923 47894 23935 47895 23923 47895 23934 47895 23934 47896 23923 47896 23924 47896 23934 47897 23924 47897 23933 47897 23933 47898 23924 47898 23925 47898 23933 47899 23925 47899 23929 47899 23929 47900 23925 47900 23926 47900 23929 47901 23926 47901 23930 47901 23930 47902 23926 47902 23927 47902 23930 47903 23927 47903 25920 47903 25920 47904 23927 47904 23931 47904 25920 47905 25922 47905 23930 47905 23930 47906 25922 47906 23932 47906 23930 47907 23932 47907 23929 47907 23929 47908 23932 47908 25337 47908 23929 47909 25337 47909 23933 47909 23933 47910 25337 47910 25341 47910 23933 47911 25341 47911 23934 47911 23934 47912 25341 47912 25331 47912 23934 47913 25331 47913 23935 47913 23935 47914 25331 47914 25333 47914 23935 47915 25333 47915 23936 47915 23936 47916 25333 47916 23937 47916 23936 47917 23937 47917 25928 47917 25928 47918 23937 47918 25335 47918 23976 47919 23938 47919 25542 47919 25542 47920 25543 47920 23939 47920 23939 47921 23983 47921 25542 47921 25542 47922 23983 47922 23940 47922 25542 47923 23940 47923 23976 47923 25548 47924 23965 47924 23941 47924 23941 47925 23965 47925 23964 47925 23964 47926 23942 47926 23941 47926 23941 47927 23942 47927 23943 47927 23941 47928 23943 47928 25561 47928 25549 47929 23989 47929 23946 47929 23946 47930 23989 47930 23988 47930 23988 47931 23944 47931 23946 47931 23946 47932 23944 47932 23945 47932 23946 47933 23945 47933 25546 47933 23948 47934 25555 47934 23947 47934 23947 47935 23959 47935 23958 47935 23958 47936 23962 47936 23947 47936 23947 47937 23962 47937 23949 47937 23947 47938 23949 47938 23948 47938 25555 47939 23948 47939 23950 47939 23950 47940 23948 47940 23949 47940 23950 47941 23949 47941 23951 47941 23951 47942 23949 47942 24010 47942 23951 47943 24010 47943 23952 47943 23952 47944 24010 47944 23953 47944 23952 47945 23953 47945 24639 47945 24639 47946 23953 47946 23997 47946 24639 47947 23997 47947 23954 47947 23954 47948 23997 47948 25907 47948 23956 47949 23955 47949 24006 47949 24006 47950 23955 47950 25914 47950 25199 47951 23955 47951 25313 47951 25313 47952 23955 47952 23956 47952 25313 47953 23956 47953 25314 47953 25314 47954 23956 47954 23957 47954 23958 47955 23959 47955 23961 47955 25314 47956 23957 47956 23960 47956 23960 47957 23957 47957 24011 47957 23960 47958 24011 47958 23961 47958 23961 47959 24011 47959 23962 47959 23961 47960 23962 47960 23958 47960 24021 47961 24042 47961 23963 47961 23963 47962 24042 47962 23964 47962 23963 47963 23964 47963 25547 47963 25547 47964 23964 47964 23965 47964 25547 47965 23965 47965 25548 47965 23968 47966 23967 47966 23963 47966 23963 47967 23967 47967 24021 47967 25236 47968 24022 47968 23966 47968 23966 47969 24022 47969 23967 47969 23966 47970 23967 47970 23968 47970 25234 47971 25906 47971 24033 47971 24022 47972 25236 47972 23969 47972 23969 47973 25236 47973 25234 47973 23969 47974 25234 47974 24034 47974 24034 47975 25234 47975 24033 47975 23970 47976 23973 47976 23971 47976 23971 47977 23973 47977 24024 47977 23971 47978 24024 47978 23972 47978 23974 47979 23975 47979 23970 47979 23970 47980 23975 47980 23973 47980 25561 47981 23943 47981 24634 47981 24634 47982 23943 47982 23942 47982 24634 47983 23942 47983 23974 47983 23974 47984 23942 47984 24023 47984 23974 47985 24023 47985 23975 47985 23938 47986 23976 47986 25557 47986 25557 47987 23976 47987 23940 47987 25557 47988 23940 47988 25711 47988 25711 47989 23940 47989 24091 47989 25711 47990 24091 47990 23978 47990 25713 47991 25711 47991 23977 47991 23977 47992 25711 47992 23978 47992 25713 47993 23977 47993 25213 47993 25213 47994 23977 47994 25896 47994 25213 47995 25896 47995 25218 47995 23981 47996 23980 47996 24076 47996 24076 47997 23980 47997 25242 47997 24076 47998 25242 47998 23979 47998 23979 47999 25242 47999 25241 47999 23979 48000 25241 48000 24075 48000 24075 48001 25241 48001 25239 48001 23980 48002 23981 48002 24636 48002 24636 48003 23981 48003 24070 48003 24636 48004 24070 48004 23982 48004 23984 48005 23982 48005 24069 48005 24069 48006 23982 48006 24070 48006 24069 48007 24081 48007 23984 48007 23984 48008 24081 48008 23983 48008 23984 48009 23983 48009 25563 48009 25563 48010 23983 48010 23939 48010 25563 48011 23939 48011 25543 48011 23985 48012 24638 48012 24044 48012 24044 48013 24638 48013 23986 48013 25205 48014 24059 48014 24640 48014 24640 48015 24059 48015 23986 48015 24640 48016 23986 48016 24638 48016 24044 48017 23987 48017 23985 48017 23985 48018 23987 48018 23988 48018 23985 48019 23988 48019 25550 48019 25550 48020 23988 48020 23989 48020 25550 48021 23989 48021 25549 48021 24059 48022 25205 48022 23990 48022 23990 48023 25205 48023 25204 48023 23990 48024 25204 48024 24055 48024 24055 48025 25204 48025 23991 48025 24632 48026 23992 48026 25235 48026 25235 48027 23992 48027 24046 48027 25235 48028 24046 48028 23993 48028 24631 48029 23995 48029 24632 48029 24632 48030 23995 48030 23992 48030 25546 48031 23945 48031 23994 48031 23994 48032 23945 48032 23944 48032 23994 48033 23944 48033 24631 48033 24631 48034 23944 48034 24045 48034 24631 48035 24045 48035 23995 48035 23957 48036 23956 48036 24011 48036 24011 48037 23956 48037 24009 48037 24010 48038 23996 48038 23953 48038 23953 48039 23996 48039 23997 48039 23997 48040 23996 48040 23998 48040 23998 48041 23996 48041 24016 48041 23998 48042 24016 48042 25908 48042 25908 48043 24016 48043 23999 48043 23999 48044 24016 48044 24000 48044 23999 48045 24000 48045 25909 48045 25909 48046 24000 48046 25910 48046 25910 48047 24000 48047 24018 48047 25910 48048 24018 48048 24001 48048 24001 48049 24018 48049 24002 48049 24002 48050 24018 48050 24003 48050 24002 48051 24003 48051 24004 48051 24004 48052 24003 48052 24005 48052 24005 48053 24003 48053 24007 48053 24005 48054 24007 48054 25915 48054 25915 48055 24007 48055 24006 48055 24006 48056 24007 48056 24009 48056 24006 48057 24009 48057 23956 48057 23949 48058 23962 48058 24011 48058 24003 48059 24008 48059 24007 48059 24007 48060 24008 48060 23922 48060 24007 48061 23922 48061 24009 48061 24009 48062 23922 48062 25935 48062 24009 48063 25935 48063 24011 48063 24011 48064 25935 48064 25933 48064 24011 48065 25933 48065 25932 48065 25932 48066 25929 48066 24011 48066 24011 48067 25929 48067 24010 48067 24011 48068 24010 48068 23949 48068 25929 48069 24012 48069 24010 48069 24010 48070 24012 48070 24013 48070 24010 48071 24013 48071 23996 48071 23996 48072 24013 48072 24014 48072 23996 48073 24014 48073 24016 48073 24016 48074 24014 48074 24015 48074 24016 48075 24015 48075 24000 48075 24000 48076 24015 48076 24017 48076 24000 48077 24017 48077 24018 48077 24018 48078 24017 48078 24019 48078 24018 48079 24019 48079 24003 48079 24003 48080 24019 48080 24020 48080 24003 48081 24020 48081 24008 48081 24042 48082 24021 48082 24041 48082 24041 48083 24021 48083 23967 48083 24041 48084 23967 48084 24022 48084 23975 48085 24023 48085 23973 48085 23973 48086 24023 48086 24035 48086 23973 48087 24035 48087 24024 48087 24024 48088 24035 48088 25901 48088 25901 48089 24035 48089 24026 48089 25901 48090 24026 48090 24025 48090 24025 48091 24026 48091 25903 48091 25903 48092 24026 48092 24027 48092 25903 48093 24027 48093 25904 48093 25904 48094 24027 48094 24028 48094 24028 48095 24027 48095 24037 48095 24028 48096 24037 48096 24029 48096 24029 48097 24037 48097 24030 48097 24030 48098 24037 48098 24032 48098 24030 48099 24032 48099 24031 48099 24031 48100 24032 48100 24033 48100 24033 48101 24032 48101 24040 48101 24033 48102 24040 48102 24034 48102 24034 48103 24040 48103 23969 48103 23969 48104 24040 48104 24041 48104 23969 48105 24041 48105 24022 48105 23942 48106 23964 48106 24023 48106 24023 48107 23964 48107 24042 48107 24023 48108 24042 48108 25969 48108 25969 48109 24042 48109 25971 48109 25969 48110 23888 48110 24023 48110 24023 48111 23888 48111 23887 48111 24023 48112 23887 48112 24035 48112 24035 48113 23887 48113 24036 48113 24035 48114 24036 48114 24026 48114 24026 48115 24036 48115 23886 48115 24026 48116 23886 48116 24027 48116 24027 48117 23886 48117 23885 48117 24027 48118 23885 48118 24037 48118 23885 48119 24038 48119 24037 48119 24037 48120 24038 48120 24039 48120 24037 48121 24039 48121 24032 48121 24032 48122 24039 48122 23882 48122 24032 48123 23882 48123 24040 48123 24040 48124 23882 48124 25975 48124 24040 48125 25975 48125 24041 48125 24041 48126 25975 48126 24043 48126 24041 48127 24043 48127 24042 48127 24042 48128 24043 48128 25973 48128 24042 48129 25973 48129 25971 48129 23987 48130 24044 48130 24058 48130 24058 48131 24044 48131 23986 48131 24058 48132 23986 48132 24059 48132 23995 48133 24045 48133 23992 48133 23992 48134 24045 48134 24063 48134 23992 48135 24063 48135 24046 48135 24046 48136 24063 48136 24047 48136 24046 48137 24047 48137 24048 48137 24048 48138 24047 48138 24049 48138 24048 48139 24049 48139 24050 48139 24050 48140 24049 48140 24051 48140 24050 48141 24051 48141 24052 48141 24052 48142 24051 48142 25893 48142 25893 48143 24051 48143 24054 48143 25893 48144 24054 48144 25894 48144 25894 48145 24054 48145 24053 48145 24053 48146 24054 48146 24056 48146 24053 48147 24056 48147 25895 48147 25895 48148 24056 48148 24055 48148 24055 48149 24056 48149 24057 48149 24055 48150 24057 48150 23990 48150 23990 48151 24057 48151 24058 48151 23990 48152 24058 48152 24059 48152 25956 48153 24060 48153 23987 48153 23987 48154 24060 48154 24045 48154 23987 48155 24045 48155 23988 48155 23988 48156 24045 48156 23944 48156 24060 48157 24061 48157 24045 48157 24045 48158 24061 48158 24062 48158 24045 48159 24062 48159 24063 48159 24063 48160 24062 48160 23910 48160 24063 48161 23910 48161 24047 48161 24047 48162 23910 48162 24064 48162 24047 48163 24064 48163 24049 48163 24049 48164 24064 48164 24065 48164 24049 48165 24065 48165 24051 48165 24051 48166 24065 48166 24066 48166 24051 48167 24066 48167 24054 48167 24054 48168 24066 48168 23906 48168 24054 48169 23906 48169 24056 48169 24056 48170 23906 48170 23905 48170 24056 48171 23905 48171 24057 48171 24057 48172 23905 48172 24067 48172 24057 48173 24067 48173 24058 48173 24058 48174 24067 48174 25958 48174 24058 48175 25958 48175 23987 48175 23987 48176 25958 48176 24068 48176 23987 48177 24068 48177 25956 48177 24081 48178 24069 48178 24078 48178 24078 48179 24069 48179 24070 48179 24078 48180 24070 48180 23981 48180 23978 48181 24091 48181 23977 48181 23977 48182 24091 48182 24089 48182 23977 48183 24089 48183 25896 48183 25896 48184 24089 48184 24071 48184 25896 48185 24071 48185 25898 48185 25898 48186 24071 48186 24072 48186 25898 48187 24072 48187 25899 48187 25899 48188 24072 48188 24088 48188 25899 48189 24088 48189 24073 48189 24073 48190 24088 48190 24086 48190 24073 48191 24086 48191 24074 48191 24074 48192 24086 48192 24075 48192 24075 48193 24086 48193 24085 48193 24075 48194 24085 48194 23979 48194 23979 48195 24085 48195 24083 48195 23979 48196 24083 48196 24076 48196 24076 48197 24083 48197 24078 48197 24076 48198 24078 48198 23981 48198 23940 48199 23983 48199 24091 48199 24091 48200 23983 48200 24081 48200 24082 48201 24081 48201 24077 48201 24077 48202 24081 48202 24078 48202 24077 48203 24078 48203 24084 48203 24079 48204 24091 48204 25988 48204 25988 48205 24091 48205 24081 48205 25988 48206 24081 48206 24080 48206 24080 48207 24081 48207 24082 48207 24078 48208 24083 48208 24084 48208 24084 48209 24083 48209 24085 48209 24084 48210 24085 48210 23857 48210 23857 48211 24085 48211 24086 48211 23857 48212 24086 48212 23858 48212 23858 48213 24086 48213 24088 48213 23858 48214 24088 48214 24087 48214 24087 48215 24088 48215 24072 48215 24087 48216 24072 48216 23862 48216 23862 48217 24072 48217 24071 48217 23862 48218 24071 48218 23863 48218 23863 48219 24071 48219 24089 48219 23863 48220 24089 48220 24090 48220 24090 48221 24089 48221 24091 48221 24090 48222 24091 48222 23866 48222 23866 48223 24091 48223 24079 48223 25889 48224 24305 48224 24102 48224 24102 48225 24305 48225 24306 48225 24102 48226 24306 48226 24092 48226 24092 48227 24306 48227 24094 48227 24092 48228 24094 48228 24093 48228 24093 48229 24094 48229 24095 48229 24093 48230 24095 48230 24096 48230 24096 48231 24095 48231 24308 48231 24096 48232 24308 48232 24097 48232 24097 48233 24308 48233 24098 48233 24097 48234 24098 48234 24099 48234 24099 48235 24098 48235 24300 48235 24099 48236 24300 48236 24100 48236 24100 48237 24300 48237 24298 48237 25871 48238 25889 48238 24101 48238 24101 48239 25889 48239 24102 48239 24101 48240 24102 48240 24108 48240 24108 48241 24102 48241 24092 48241 24108 48242 24092 48242 24107 48242 24107 48243 24092 48243 24093 48243 24107 48244 24093 48244 24106 48244 24106 48245 24093 48245 24096 48245 24106 48246 24096 48246 24103 48246 24103 48247 24096 48247 24097 48247 24103 48248 24097 48248 24104 48248 24104 48249 24097 48249 24099 48249 24104 48250 24099 48250 25877 48250 25877 48251 24099 48251 24100 48251 25877 48252 25379 48252 24104 48252 24104 48253 25379 48253 25378 48253 24104 48254 25378 48254 24103 48254 24103 48255 25378 48255 25376 48255 24103 48256 25376 48256 24106 48256 24106 48257 25376 48257 24105 48257 24106 48258 24105 48258 24107 48258 24107 48259 24105 48259 25374 48259 24107 48260 25374 48260 24108 48260 24108 48261 25374 48261 25375 48261 24108 48262 25375 48262 24101 48262 24101 48263 25375 48263 24109 48263 24101 48264 24109 48264 25871 48264 25871 48265 24109 48265 25373 48265 25861 48266 24110 48266 24111 48266 24111 48267 24110 48267 24258 48267 24111 48268 24258 48268 24112 48268 24112 48269 24258 48269 24113 48269 24112 48270 24113 48270 24118 48270 24118 48271 24113 48271 24256 48271 24118 48272 24256 48272 24114 48272 24114 48273 24256 48273 24115 48273 24114 48274 24115 48274 24119 48274 24119 48275 24115 48275 24116 48275 24119 48276 24116 48276 24121 48276 24121 48277 24116 48277 24259 48277 24127 48278 25861 48278 24126 48278 24126 48279 25861 48279 24111 48279 24126 48280 24111 48280 24125 48280 24125 48281 24111 48281 24112 48281 24125 48282 24112 48282 24117 48282 24117 48283 24112 48283 24118 48283 24117 48284 24118 48284 24123 48284 24123 48285 24118 48285 24114 48285 24123 48286 24114 48286 24120 48286 24120 48287 24114 48287 24119 48287 24120 48288 24119 48288 25853 48288 25853 48289 24119 48289 24121 48289 25853 48290 24122 48290 24120 48290 24120 48291 24122 48291 24124 48291 24120 48292 24124 48292 24123 48292 24123 48293 24124 48293 25385 48293 24123 48294 25385 48294 24117 48294 24117 48295 25385 48295 25384 48295 24117 48296 25384 48296 24125 48296 24125 48297 25384 48297 25382 48297 24125 48298 25382 48298 24126 48298 24126 48299 25382 48299 25381 48299 24126 48300 25381 48300 24127 48300 24127 48301 25381 48301 25847 48301 25846 48302 24129 48302 24128 48302 24128 48303 24129 48303 24130 48303 24128 48304 24130 48304 24131 48304 24131 48305 24130 48305 24280 48305 24131 48306 24280 48306 24132 48306 24132 48307 24280 48307 24278 48307 24132 48308 24278 48308 24141 48308 24141 48309 24278 48309 24133 48309 24141 48310 24133 48310 24135 48310 24135 48311 24133 48311 24134 48311 24135 48312 24134 48312 24136 48312 24136 48313 24134 48313 24277 48313 24136 48314 24277 48314 24143 48314 24143 48315 24277 48315 24276 48315 24137 48316 25846 48316 24138 48316 24138 48317 25846 48317 24128 48317 24138 48318 24128 48318 24139 48318 24139 48319 24128 48319 24131 48319 24139 48320 24131 48320 24149 48320 24149 48321 24131 48321 24132 48321 24149 48322 24132 48322 24140 48322 24140 48323 24132 48323 24141 48323 24140 48324 24141 48324 24147 48324 24147 48325 24141 48325 24135 48325 24147 48326 24135 48326 24142 48326 24142 48327 24135 48327 24136 48327 24142 48328 24136 48328 24144 48328 24144 48329 24136 48329 24143 48329 24144 48330 24145 48330 24142 48330 24142 48331 24145 48331 24146 48331 24142 48332 24146 48332 24147 48332 24147 48333 24146 48333 24148 48333 24147 48334 24148 48334 24140 48334 24140 48335 24148 48335 25395 48335 24140 48336 25395 48336 24149 48336 24149 48337 25395 48337 24150 48337 24149 48338 24150 48338 24139 48338 24139 48339 24150 48339 24151 48339 24139 48340 24151 48340 24138 48340 24138 48341 24151 48341 24152 48341 24138 48342 24152 48342 24137 48342 24137 48343 24152 48343 25828 48343 24157 48344 24153 48344 24159 48344 24159 48345 24153 48345 24316 48345 24159 48346 24316 48346 24154 48346 24154 48347 24316 48347 24315 48347 24154 48348 24315 48348 24162 48348 24162 48349 24315 48349 24314 48349 24162 48350 24314 48350 24163 48350 24163 48351 24314 48351 24155 48351 24163 48352 24155 48352 24156 48352 24156 48353 24155 48353 24313 48353 24156 48354 24313 48354 25819 48354 25819 48355 24313 48355 25820 48355 25818 48356 24157 48356 24158 48356 24158 48357 24157 48357 24159 48357 24158 48358 24159 48358 24160 48358 24160 48359 24159 48359 24154 48359 24160 48360 24154 48360 24161 48360 24161 48361 24154 48361 24162 48361 24161 48362 24162 48362 24165 48362 24165 48363 24162 48363 24163 48363 24165 48364 24163 48364 24164 48364 24164 48365 24163 48365 24156 48365 24164 48366 24156 48366 25811 48366 25811 48367 24156 48367 25819 48367 25811 48368 25402 48368 24164 48368 24164 48369 25402 48369 25400 48369 24164 48370 25400 48370 24165 48370 24165 48371 25400 48371 24166 48371 24165 48372 24166 48372 24161 48372 24161 48373 24166 48373 25399 48373 24161 48374 25399 48374 24160 48374 24160 48375 25399 48375 25398 48375 24160 48376 25398 48376 24158 48376 24158 48377 25398 48377 24167 48377 24158 48378 24167 48378 25818 48378 25818 48379 24167 48379 24168 48379 24169 48380 25286 48380 24170 48380 24299 48381 24169 48381 24209 48381 24209 48382 24169 48382 24170 48382 24209 48383 24170 48383 24171 48383 24171 48384 24170 48384 25302 48384 24173 48385 24192 48385 25299 48385 25299 48386 24207 48386 24206 48386 24206 48387 24172 48387 25299 48387 25299 48388 24172 48388 24260 48388 25299 48389 24260 48389 24173 48389 24176 48390 24226 48390 24174 48390 24174 48391 24175 48391 24241 48391 24241 48392 24239 48392 24174 48392 24174 48393 24239 48393 24227 48393 24174 48394 24227 48394 24176 48394 24177 48395 24178 48395 25293 48395 25293 48396 24178 48396 24182 48396 24182 48397 24191 48397 25293 48397 25293 48398 24191 48398 24179 48398 25293 48399 24179 48399 24180 48399 24184 48400 24309 48400 24181 48400 24181 48401 24309 48401 24182 48401 24181 48402 24182 48402 24617 48402 24617 48403 24182 48403 24178 48403 24617 48404 24178 48404 24177 48404 24616 48405 24183 48405 24181 48405 24181 48406 24183 48406 24184 48406 25150 48407 24331 48407 24619 48407 24619 48408 24331 48408 24183 48408 24619 48409 24183 48409 24616 48409 24331 48410 25150 48410 24330 48410 24330 48411 25150 48411 24185 48411 24330 48412 24185 48412 24186 48412 24186 48413 24185 48413 24188 48413 24186 48414 24188 48414 24187 48414 24187 48415 24188 48415 25148 48415 24187 48416 25148 48416 24328 48416 24328 48417 25148 48417 25147 48417 24328 48418 25147 48418 24327 48418 24327 48419 25147 48419 24189 48419 24327 48420 24189 48420 25802 48420 25802 48421 24189 48421 25145 48421 25131 48422 24190 48422 25143 48422 25143 48423 24190 48423 24324 48423 25143 48424 24324 48424 25803 48424 25132 48425 24310 48425 25131 48425 25131 48426 24310 48426 24190 48426 24180 48427 24179 48427 25133 48427 25133 48428 24179 48428 24191 48428 25133 48429 24191 48429 25132 48429 25132 48430 24191 48430 24311 48430 25132 48431 24311 48431 24310 48431 24192 48432 24173 48432 24193 48432 24193 48433 24173 48433 24260 48433 24193 48434 24260 48434 24194 48434 24194 48435 24260 48435 24257 48435 24194 48436 24257 48436 24195 48436 24626 48437 24194 48437 24243 48437 24243 48438 24194 48438 24195 48438 24626 48439 24243 48439 24627 48439 24627 48440 24243 48440 24196 48440 24627 48441 24196 48441 24197 48441 24200 48442 25223 48442 24252 48442 24252 48443 25223 48443 25224 48443 24252 48444 25224 48444 24250 48444 24250 48445 25224 48445 25226 48445 24250 48446 25226 48446 24198 48446 24198 48447 25226 48447 25225 48447 24198 48448 25225 48448 24248 48448 24248 48449 25225 48449 24199 48449 24248 48450 24199 48450 24247 48450 24247 48451 24199 48451 25215 48451 25223 48452 24200 48452 24624 48452 24624 48453 24200 48453 24242 48453 24624 48454 24242 48454 24202 48454 24201 48455 24202 48455 24203 48455 24203 48456 24202 48456 24242 48456 24203 48457 24204 48457 24201 48457 24201 48458 24204 48458 24172 48458 24201 48459 24172 48459 24205 48459 24205 48460 24172 48460 24206 48460 24205 48461 24206 48461 24207 48461 24211 48462 24286 48462 24208 48462 24208 48463 24286 48463 24209 48463 24208 48464 24209 48464 24210 48464 24210 48465 24209 48465 24171 48465 24210 48466 24171 48466 25302 48466 24212 48467 24287 48467 24208 48467 24208 48468 24287 48468 24211 48468 24214 48469 24288 48469 24628 48469 24628 48470 24288 48470 24287 48470 24628 48471 24287 48471 24212 48471 24288 48472 24214 48472 24213 48472 24213 48473 24214 48473 25229 48473 24213 48474 25229 48474 24297 48474 24297 48475 25229 48475 25210 48475 24297 48476 25210 48476 24296 48476 24296 48477 25210 48477 25212 48477 24296 48478 25212 48478 24295 48478 24295 48479 25212 48479 24215 48479 24295 48480 24215 48480 24216 48480 24217 48481 24220 48481 24622 48481 24622 48482 24220 48482 24218 48482 24622 48483 24218 48483 25237 48483 24221 48484 24219 48484 24217 48484 24217 48485 24219 48485 24220 48485 25286 48486 24169 48486 25287 48486 25287 48487 24169 48487 24299 48487 25287 48488 24299 48488 24221 48488 24221 48489 24299 48489 24289 48489 24221 48490 24289 48490 24219 48490 24222 48491 24264 48491 24223 48491 24223 48492 24264 48492 24265 48492 24223 48493 24265 48493 24224 48493 24224 48494 24265 48494 24225 48494 24224 48495 24225 48495 25206 48495 24226 48496 24176 48496 24621 48496 24621 48497 24176 48497 24227 48497 24621 48498 24227 48498 24222 48498 24222 48499 24227 48499 24279 48499 24222 48500 24279 48500 24264 48500 25208 48501 24269 48501 24228 48501 25208 48502 24228 48502 25209 48502 24228 48503 24271 48503 25209 48503 25209 48504 24271 48504 24229 48504 25209 48505 24229 48505 24230 48505 24234 48506 24231 48506 24274 48506 24274 48507 24231 48507 25216 48507 24274 48508 25216 48508 24232 48508 24232 48509 25216 48509 25214 48509 24232 48510 25214 48510 24273 48510 24273 48511 25214 48511 24230 48511 24273 48512 24230 48512 24272 48512 24272 48513 24230 48513 24229 48513 24231 48514 24234 48514 24233 48514 24233 48515 24234 48515 24235 48515 24233 48516 24235 48516 24625 48516 24238 48517 24625 48517 24236 48517 24236 48518 24625 48518 24235 48518 24236 48519 24237 48519 24238 48519 24238 48520 24237 48520 24239 48520 24238 48521 24239 48521 24240 48521 24240 48522 24239 48522 24241 48522 24240 48523 24241 48523 24175 48523 24204 48524 24203 48524 24254 48524 24254 48525 24203 48525 24242 48525 24254 48526 24242 48526 24200 48526 24195 48527 24257 48527 24243 48527 24243 48528 24257 48528 24244 48528 24243 48529 24244 48529 24196 48529 24196 48530 24244 48530 24245 48530 24196 48531 24245 48531 24246 48531 24246 48532 24245 48532 24263 48532 24246 48533 24263 48533 24247 48533 24247 48534 24263 48534 24262 48534 24247 48535 24262 48535 24248 48535 24248 48536 24262 48536 24249 48536 24248 48537 24249 48537 24198 48537 24198 48538 24249 48538 24251 48538 24198 48539 24251 48539 24250 48539 24250 48540 24251 48540 24255 48540 24250 48541 24255 48541 24252 48541 24252 48542 24255 48542 24254 48542 24252 48543 24254 48543 24200 48543 24204 48544 24253 48544 25870 48544 24254 48545 24255 48545 24251 48545 24260 48546 24256 48546 24257 48546 24257 48547 24256 48547 24113 48547 24257 48548 24113 48548 24244 48548 24244 48549 24113 48549 24258 48549 25870 48550 25867 48550 24204 48550 24204 48551 25867 48551 24259 48551 24204 48552 24259 48552 24172 48552 24172 48553 24259 48553 24116 48553 24172 48554 24116 48554 24260 48554 24260 48555 24116 48555 24115 48555 24260 48556 24115 48556 24256 48556 24204 48557 24254 48557 24253 48557 24253 48558 24254 48558 24251 48558 24253 48559 24251 48559 25863 48559 25863 48560 24251 48560 24249 48560 25863 48561 24249 48561 24261 48561 24261 48562 24249 48562 24262 48562 24261 48563 24262 48563 24110 48563 24110 48564 24262 48564 24263 48564 24110 48565 24263 48565 24258 48565 24258 48566 24263 48566 24245 48566 24258 48567 24245 48567 24244 48567 24237 48568 24236 48568 24275 48568 24275 48569 24236 48569 24235 48569 24275 48570 24235 48570 24234 48570 24264 48571 24279 48571 24265 48571 24265 48572 24279 48572 24266 48572 24265 48573 24266 48573 24225 48573 24225 48574 24266 48574 24268 48574 24268 48575 24266 48575 24267 48575 24268 48576 24267 48576 25799 48576 25799 48577 24267 48577 24269 48577 24269 48578 24267 48578 24270 48578 24269 48579 24270 48579 24228 48579 24228 48580 24270 48580 24271 48580 24271 48581 24270 48581 24282 48581 24271 48582 24282 48582 24229 48582 24229 48583 24282 48583 24272 48583 24272 48584 24282 48584 24283 48584 24272 48585 24283 48585 24273 48585 24273 48586 24283 48586 24284 48586 24273 48587 24284 48587 24232 48587 24232 48588 24284 48588 24285 48588 24232 48589 24285 48589 24274 48589 24274 48590 24285 48590 24275 48590 24274 48591 24275 48591 24234 48591 24227 48592 24239 48592 24237 48592 24276 48593 24277 48593 24237 48593 24237 48594 24277 48594 24134 48594 24237 48595 24134 48595 24227 48595 24227 48596 24134 48596 24133 48596 24227 48597 24133 48597 24279 48597 24279 48598 24133 48598 24278 48598 24279 48599 24278 48599 24266 48599 24266 48600 24278 48600 24280 48600 24266 48601 24280 48601 24267 48601 24267 48602 24280 48602 24130 48602 24267 48603 24130 48603 24270 48603 24270 48604 24130 48604 24129 48604 24270 48605 24129 48605 24282 48605 24282 48606 24129 48606 24281 48606 24282 48607 24281 48607 24283 48607 24283 48608 24281 48608 25844 48608 24283 48609 25844 48609 24284 48609 24284 48610 25844 48610 25843 48610 24284 48611 25843 48611 24285 48611 24285 48612 25843 48612 25842 48612 24285 48613 25842 48613 24275 48613 24275 48614 25842 48614 25841 48614 24275 48615 25841 48615 24237 48615 24237 48616 25841 48616 24276 48616 24286 48617 24211 48617 24301 48617 24301 48618 24211 48618 24287 48618 24301 48619 24287 48619 24288 48619 24219 48620 24289 48620 24220 48620 24220 48621 24289 48621 24290 48621 24220 48622 24290 48622 24218 48622 24218 48623 24290 48623 24292 48623 24218 48624 24292 48624 24291 48624 24291 48625 24292 48625 24307 48625 24291 48626 24307 48626 24293 48626 24293 48627 24307 48627 24216 48627 24216 48628 24307 48628 24294 48628 24216 48629 24294 48629 24295 48629 24295 48630 24294 48630 24304 48630 24295 48631 24304 48631 24296 48631 24296 48632 24304 48632 24303 48632 24296 48633 24303 48633 24297 48633 24297 48634 24303 48634 24302 48634 24297 48635 24302 48635 24213 48635 24213 48636 24302 48636 24301 48636 24213 48637 24301 48637 24288 48637 24299 48638 24209 48638 24286 48638 25884 48639 24298 48639 24286 48639 24286 48640 24298 48640 24300 48640 24286 48641 24300 48641 24299 48641 24299 48642 24300 48642 24098 48642 24299 48643 24098 48643 24308 48643 25884 48644 24286 48644 25886 48644 25886 48645 24286 48645 24301 48645 25886 48646 24301 48646 25887 48646 25887 48647 24301 48647 24302 48647 25887 48648 24302 48648 25888 48648 25888 48649 24302 48649 24303 48649 25888 48650 24303 48650 25890 48650 25890 48651 24303 48651 24304 48651 25890 48652 24304 48652 24305 48652 24305 48653 24304 48653 24294 48653 24305 48654 24294 48654 24306 48654 24306 48655 24294 48655 24307 48655 24306 48656 24307 48656 24094 48656 24094 48657 24307 48657 24292 48657 24094 48658 24292 48658 24095 48658 24095 48659 24292 48659 24290 48659 24095 48660 24290 48660 24308 48660 24308 48661 24290 48661 24289 48661 24308 48662 24289 48662 24299 48662 24309 48663 24184 48663 24323 48663 24323 48664 24184 48664 24183 48664 24323 48665 24183 48665 24331 48665 24310 48666 24311 48666 24190 48666 24190 48667 24311 48667 24312 48667 24190 48668 24312 48668 24324 48668 24311 48669 24191 48669 24182 48669 24309 48670 25822 48670 25821 48670 25821 48671 25820 48671 24309 48671 24309 48672 25820 48672 24313 48672 24309 48673 24313 48673 24182 48673 24182 48674 24313 48674 24155 48674 24182 48675 24155 48675 24311 48675 24155 48676 24314 48676 24311 48676 24311 48677 24314 48677 24315 48677 24311 48678 24315 48678 24312 48678 24312 48679 24315 48679 24316 48679 24312 48680 24316 48680 24325 48680 24325 48681 24316 48681 24153 48681 24325 48682 24153 48682 24326 48682 24326 48683 24153 48683 24317 48683 24326 48684 24317 48684 24318 48684 24318 48685 24317 48685 24319 48685 24318 48686 24319 48686 24329 48686 24329 48687 24319 48687 25825 48687 24329 48688 25825 48688 24320 48688 24320 48689 25825 48689 24321 48689 24320 48690 24321 48690 24322 48690 24322 48691 24321 48691 25822 48691 24322 48692 25822 48692 24323 48692 24323 48693 25822 48693 24309 48693 24324 48694 24312 48694 24325 48694 24324 48695 24325 48695 25802 48695 25802 48696 24325 48696 24326 48696 25802 48697 24326 48697 24327 48697 24327 48698 24326 48698 24318 48698 24327 48699 24318 48699 24328 48699 24328 48700 24318 48700 24329 48700 24328 48701 24329 48701 24187 48701 24187 48702 24329 48702 24320 48702 24187 48703 24320 48703 24186 48703 24186 48704 24320 48704 24322 48704 24186 48705 24322 48705 24330 48705 24330 48706 24322 48706 24323 48706 24330 48707 24323 48707 24331 48707 24332 48708 24333 48708 24334 48708 24334 48709 24333 48709 25282 48709 24334 48710 25282 48710 24335 48710 24462 48711 24334 48711 24335 48711 24339 48712 24333 48712 24332 48712 24462 48713 24335 48713 24346 48713 24346 48714 24335 48714 24336 48714 24334 48715 24462 48715 24337 48715 24337 48716 24462 48716 24347 48716 24339 48717 24332 48717 25778 48717 25778 48718 24332 48718 24606 48718 24333 48719 24339 48719 24338 48719 24338 48720 24339 48720 24356 48720 24340 48721 25134 48721 24412 48721 24340 48722 24412 48722 25281 48722 24412 48723 24341 48723 25281 48723 25281 48724 24341 48724 24414 48724 25281 48725 24414 48725 24343 48725 24343 48726 24414 48726 24342 48726 24343 48727 24342 48727 24344 48727 24344 48728 24342 48728 24345 48728 24344 48729 24345 48729 25283 48729 25283 48730 24345 48730 24346 48730 25283 48731 24346 48731 24336 48731 24677 48732 24679 48732 24418 48732 24418 48733 24679 48733 24604 48733 24418 48734 24604 48734 24347 48734 24347 48735 24604 48735 24337 48735 24348 48736 25022 48736 24349 48736 24349 48737 25022 48737 24452 48737 24349 48738 24452 48738 24353 48738 25778 48739 24606 48739 24350 48739 24350 48740 24606 48740 24351 48740 24350 48741 24351 48741 25777 48741 25777 48742 24351 48742 24353 48742 25777 48743 24353 48743 24352 48743 24352 48744 24353 48744 24452 48744 25277 48745 25276 48745 24426 48745 24426 48746 25276 48746 24425 48746 25276 48747 25275 48747 24425 48747 24425 48748 25275 48748 24354 48748 24425 48749 24354 48749 24424 48749 24424 48750 24354 48750 24355 48750 24424 48751 24355 48751 24422 48751 24338 48752 24356 48752 24355 48752 24355 48753 24356 48753 24421 48753 24355 48754 24421 48754 24422 48754 24358 48755 24375 48755 24357 48755 24357 48756 24382 48756 24358 48756 24358 48757 24382 48757 24383 48757 24358 48758 24383 48758 25290 48758 25290 48759 24383 48759 24360 48759 25290 48760 24360 48760 25291 48760 25291 48761 24360 48761 24359 48761 24359 48762 24360 48762 24387 48762 24359 48763 24387 48763 24362 48763 24387 48764 24361 48764 24362 48764 24362 48765 24361 48765 24386 48765 24362 48766 24386 48766 24618 48766 24363 48767 24978 48767 24364 48767 24364 48768 24978 48768 24980 48768 24364 48769 24980 48769 25127 48769 25127 48770 24980 48770 24683 48770 24365 48771 24457 48771 24458 48771 24365 48772 24458 48772 24973 48772 24461 48773 24366 48773 24367 48773 24367 48774 24366 48774 24973 48774 24367 48775 24973 48775 24368 48775 24368 48776 24973 48776 24458 48776 24370 48777 24369 48777 25295 48777 24370 48778 25295 48778 24450 48778 25295 48779 25296 48779 24450 48779 24450 48780 25296 48780 24371 48780 24450 48781 24371 48781 24372 48781 24372 48782 24371 48782 24373 48782 24372 48783 24373 48783 24449 48783 25294 48784 24224 48784 24373 48784 24373 48785 24224 48785 24374 48785 24373 48786 24374 48786 24449 48786 24357 48787 24375 48787 24380 48787 24380 48788 24375 48788 25289 48788 24978 48789 24363 48789 24376 48789 24376 48790 24363 48790 24380 48790 25797 48791 24378 48791 24377 48791 24377 48792 24378 48792 24379 48792 24369 48793 24370 48793 24381 48793 24381 48794 24370 48794 24377 48794 25289 48795 24376 48795 24380 48795 24379 48796 24381 48796 24377 48796 24381 48797 24379 48797 25288 48797 25288 48798 24379 48798 24376 48798 25288 48799 24376 48799 25289 48799 24357 48800 24390 48800 24382 48800 24382 48801 24390 48801 24391 48801 24382 48802 24391 48802 24383 48802 24383 48803 24391 48803 24384 48803 24383 48804 24384 48804 24360 48804 24360 48805 24384 48805 24392 48805 24360 48806 24392 48806 24387 48806 24385 48807 24386 48807 24392 48807 24392 48808 24386 48808 24361 48808 24392 48809 24361 48809 24387 48809 24419 48810 24388 48810 24727 48810 24394 48811 24419 48811 24395 48811 24390 48812 24420 48812 24389 48812 24389 48813 24420 48813 24394 48813 24390 48814 24389 48814 24391 48814 24391 48815 24389 48815 24397 48815 24391 48816 24397 48816 24384 48816 24384 48817 24397 48817 24398 48817 24384 48818 24398 48818 24392 48818 24392 48819 24398 48819 24393 48819 24392 48820 24393 48820 24385 48820 24394 48821 24395 48821 24389 48821 24389 48822 24395 48822 24396 48822 24389 48823 24396 48823 24397 48823 24397 48824 24396 48824 24399 48824 24397 48825 24399 48825 24398 48825 24398 48826 24399 48826 25149 48826 24398 48827 25149 48827 24393 48827 24419 48828 24727 48828 24395 48828 24395 48829 24727 48829 24725 48829 24395 48830 24725 48830 24396 48830 24396 48831 24725 48831 24724 48831 24396 48832 24724 48832 24399 48832 24399 48833 24724 48833 24716 48833 24399 48834 24716 48834 25149 48834 24713 48835 24714 48835 24411 48835 24413 48836 24401 48836 24400 48836 24400 48837 24401 48837 24402 48837 24400 48838 24402 48838 24403 48838 24403 48839 24402 48839 24404 48839 24403 48840 24404 48840 24405 48840 24405 48841 24404 48841 24406 48841 24405 48842 24406 48842 24407 48842 24407 48843 24406 48843 24711 48843 24407 48844 24713 48844 24405 48844 24405 48845 24713 48845 24411 48845 24405 48846 24411 48846 24403 48846 24403 48847 24411 48847 24408 48847 24403 48848 24408 48848 24400 48848 24400 48849 24408 48849 24409 48849 24400 48850 24409 48850 24413 48850 24413 48851 24409 48851 24415 48851 24463 48852 24415 48852 24410 48852 24410 48853 24415 48853 24409 48853 24410 48854 24409 48854 24417 48854 24417 48855 24409 48855 24408 48855 24417 48856 24408 48856 24416 48856 24416 48857 24408 48857 24411 48857 24416 48858 24411 48858 25126 48858 25126 48859 24411 48859 24714 48859 25134 48860 24401 48860 24412 48860 24412 48861 24401 48861 24413 48861 24412 48862 24413 48862 24341 48862 24341 48863 24413 48863 24414 48863 24414 48864 24413 48864 24415 48864 24414 48865 24415 48865 24342 48865 24342 48866 24415 48866 24345 48866 24345 48867 24415 48867 24463 48867 24345 48868 24463 48868 24346 48868 24463 48869 24410 48869 24347 48869 24347 48870 24410 48870 24418 48870 25126 48871 24677 48871 24416 48871 24416 48872 24677 48872 24418 48872 24416 48873 24418 48873 24417 48873 24417 48874 24418 48874 24410 48874 24388 48875 24419 48875 25127 48875 25127 48876 24419 48876 24364 48876 24390 48877 24363 48877 24420 48877 24420 48878 24363 48878 24364 48878 24420 48879 24364 48879 24394 48879 24394 48880 24364 48880 24419 48880 24356 48881 25791 48881 24421 48881 24421 48882 25791 48882 24423 48882 24421 48883 24423 48883 24422 48883 24422 48884 24423 48884 25793 48884 24422 48885 25793 48885 24424 48885 24424 48886 25793 48886 24425 48886 24425 48887 25793 48887 25162 48887 24425 48888 25162 48888 24426 48888 24453 48889 25021 48889 24428 48889 24453 48890 24430 48890 24427 48890 24427 48891 24430 48891 25788 48891 25788 48892 24430 48892 25790 48892 25790 48893 24430 48893 24432 48893 25790 48894 24432 48894 24431 48894 24453 48895 24428 48895 24430 48895 24430 48896 24428 48896 24429 48896 24430 48897 24429 48897 24432 48897 24431 48898 24432 48898 25796 48898 25796 48899 24432 48899 24433 48899 25796 48900 24433 48900 25795 48900 25795 48901 24433 48901 24434 48901 25795 48902 24434 48902 25794 48902 24429 48903 24435 48903 24432 48903 24432 48904 24435 48904 24436 48904 24432 48905 24436 48905 24433 48905 24433 48906 24436 48906 25171 48906 24433 48907 25171 48907 24434 48907 24443 48908 24454 48908 24451 48908 24456 48909 24443 48909 24437 48909 24459 48910 24456 48910 24438 48910 24438 48911 24456 48911 24437 48911 24438 48912 24437 48912 24439 48912 24439 48913 24437 48913 24445 48913 25786 48914 24440 48914 24445 48914 24445 48915 24440 48915 24441 48915 24445 48916 24441 48916 24439 48916 24445 48917 24442 48917 25786 48917 25786 48918 24442 48918 24447 48918 25786 48919 24447 48919 25784 48919 24443 48920 24451 48920 24437 48920 24437 48921 24451 48921 24444 48921 24437 48922 24444 48922 24445 48922 24445 48923 24444 48923 24448 48923 24445 48924 24448 48924 24442 48924 24442 48925 24448 48925 24446 48925 24442 48926 24446 48926 24447 48926 24224 48927 24446 48927 24374 48927 24374 48928 24446 48928 24448 48928 24374 48929 24448 48929 24449 48929 24449 48930 24448 48930 24444 48930 24449 48931 24444 48931 24372 48931 24372 48932 24444 48932 24451 48932 24372 48933 24451 48933 24450 48933 24450 48934 24451 48934 24454 48934 24450 48935 24454 48935 24370 48935 24452 48936 25022 48936 24453 48936 24453 48937 25022 48937 25021 48937 24452 48938 24453 48938 24352 48938 24352 48939 24453 48939 24427 48939 24352 48940 24427 48940 25777 48940 25797 48941 24454 48941 24455 48941 24455 48942 24454 48942 24443 48942 24455 48943 24443 48943 25798 48943 25798 48944 24443 48944 24456 48944 25798 48945 24456 48945 24457 48945 24457 48946 24456 48946 24459 48946 24457 48947 24459 48947 24458 48947 24458 48948 24459 48948 24460 48948 24458 48949 24460 48949 24368 48949 24368 48950 24460 48950 25780 48950 24368 48951 25780 48951 24367 48951 24367 48952 25780 48952 25779 48952 24367 48953 25779 48953 24461 48953 24461 48954 25779 48954 25027 48954 24363 48955 24390 48955 24380 48955 24380 48956 24390 48956 24357 48956 24377 48957 24370 48957 25797 48957 25797 48958 24370 48958 24454 48958 25778 48959 25791 48959 24339 48959 24339 48960 25791 48960 24356 48960 24462 48961 24346 48961 24347 48961 24347 48962 24346 48962 24463 48962 24530 48963 22936 48963 24531 48963 24517 48964 24515 48964 23169 48964 23165 48965 24506 48965 24490 48965 24464 48966 24594 48966 24502 48966 22894 48967 22896 48967 24513 48967 24468 48968 22848 48968 24531 48968 24531 48969 22848 48969 24465 48969 24531 48970 24465 48970 22849 48970 24496 48971 24466 48971 24467 48971 24467 48972 24466 48972 24469 48972 24467 48973 24469 48973 24468 48973 24468 48974 24469 48974 24470 48974 24468 48975 24470 48975 22848 48975 22849 48976 22851 48976 24531 48976 24531 48977 22851 48977 22852 48977 24531 48978 22852 48978 24472 48978 24472 48979 22852 48979 24471 48979 24472 48980 24471 48980 22943 48980 22943 48981 22944 48981 24472 48981 24472 48982 22944 48982 22945 48982 24472 48983 22945 48983 24496 48983 24496 48984 22945 48984 22947 48984 24496 48985 22947 48985 24466 48985 24531 48986 22936 48986 24468 48986 24468 48987 22936 48987 22938 48987 24468 48988 22938 48988 25533 48988 25528 48989 25531 48989 24596 48989 24596 48990 25531 48990 24473 48990 24596 48991 24473 48991 24474 48991 24474 48992 24473 48992 25533 48992 24474 48993 25533 48993 24598 48993 24475 48994 25503 48994 25527 48994 24475 48995 25527 48995 24546 48995 24475 48996 24476 48996 25503 48996 25503 48997 24476 48997 22874 48997 25503 48998 22874 48998 25505 48998 25505 48999 22874 48999 22875 48999 24559 49000 25507 49000 24556 49000 24581 49001 24583 49001 24477 49001 24477 49002 24583 49002 24479 49002 24477 49003 24479 49003 24478 49003 24478 49004 24479 49004 25524 49004 25524 49005 24479 49005 24480 49005 25524 49006 24480 49006 24571 49006 22906 49007 24482 49007 22816 49007 22816 49008 24482 49008 24571 49008 22906 49009 24481 49009 24482 49009 24482 49010 24481 49010 24575 49010 24482 49011 24575 49011 25523 49011 25523 49012 24575 49012 24589 49012 25520 49013 24483 49013 24588 49013 24588 49014 24483 49014 25522 49014 24588 49015 24587 49015 25520 49015 25520 49016 24587 49016 24586 49016 25520 49017 24586 49017 25518 49017 22894 49018 24513 49018 25511 49018 25511 49019 24513 49019 24484 49019 25511 49020 24484 49020 24485 49020 22864 49021 22867 49021 24484 49021 24484 49022 22867 49022 22870 49022 22860 49023 22863 49023 24490 49023 22870 49024 22871 49024 24484 49024 24484 49025 22871 49025 22957 49025 24484 49026 22957 49026 24485 49026 22957 49027 24486 49027 24485 49027 24485 49028 24486 49028 22959 49028 24485 49029 22959 49029 24488 49029 24488 49030 22959 49030 24487 49030 24488 49031 24487 49031 25513 49031 25513 49032 24487 49032 22961 49032 25513 49033 22961 49033 24508 49033 24508 49034 22961 49034 24489 49034 24508 49035 24489 49035 24490 49035 24490 49036 24489 49036 24491 49036 24490 49037 24491 49037 22860 49037 24595 49038 24492 49038 24493 49038 24493 49039 24492 49039 24494 49039 24493 49040 24494 49040 25537 49040 25537 49041 24494 49041 24497 49041 24495 49042 24472 49042 22853 49042 22853 49043 24472 49043 24496 49043 22853 49044 24496 49044 22956 49044 22956 49045 24496 49045 25537 49045 22956 49046 25537 49046 22954 49046 22954 49047 25537 49047 24497 49047 22855 49048 22856 49048 24498 49048 24498 49049 22856 49049 24464 49049 22856 49050 22858 49050 24464 49050 24464 49051 22858 49051 22859 49051 24464 49052 22859 49052 24594 49052 24594 49053 22859 49053 22949 49053 24593 49054 22951 49054 24494 49054 24494 49055 22951 49055 24499 49055 24494 49056 24499 49056 24497 49056 24594 49057 24500 49057 22784 49057 22784 49058 24501 49058 24594 49058 24594 49059 24501 49059 22787 49059 24594 49060 22787 49060 24502 49060 24502 49061 22787 49061 22788 49061 24502 49062 22788 49062 24504 49062 22788 49063 24503 49063 24504 49063 24504 49064 24503 49064 24505 49064 24504 49065 24505 49065 24506 49065 24505 49066 22791 49066 24506 49066 24506 49067 22791 49067 24507 49067 24506 49068 24507 49068 24490 49068 24490 49069 24507 49069 24509 49069 24490 49070 24509 49070 24508 49070 24508 49071 24509 49071 22884 49071 24508 49072 22884 49072 24510 49072 24510 49073 22884 49073 24511 49073 24510 49074 24511 49074 25540 49074 25540 49075 24511 49075 22888 49075 25540 49076 22888 49076 24500 49076 24500 49077 22888 49077 22890 49077 24500 49078 22890 49078 22784 49078 22800 49079 22801 49079 24586 49079 24586 49080 22801 49080 22891 49080 24586 49081 22891 49081 25518 49081 25518 49082 22891 49082 22892 49082 25518 49083 22892 49083 25511 49083 25511 49084 22892 49084 24512 49084 25511 49085 24512 49085 22894 49085 22863 49086 22864 49086 24490 49086 24490 49087 22864 49087 24484 49087 24490 49088 24484 49088 23165 49088 23165 49089 24484 49089 24513 49089 23165 49090 24513 49090 23167 49090 23167 49091 24513 49091 22896 49091 24515 49092 22798 49092 22800 49092 24517 49093 24514 49093 24515 49093 24515 49094 24514 49094 22796 49094 24515 49095 22796 49095 22798 49095 22896 49096 24516 49096 23167 49096 23167 49097 24516 49097 24518 49097 23167 49098 24518 49098 24517 49098 24517 49099 24518 49099 22795 49099 24517 49100 22795 49100 24514 49100 23172 49101 23170 49101 24519 49101 24519 49102 23170 49102 24520 49102 24520 49103 23170 49103 23169 49103 24520 49104 23169 49104 22903 49104 22903 49105 23169 49105 22902 49105 22902 49106 23169 49106 24515 49106 22902 49107 24515 49107 24521 49107 24521 49108 24515 49108 24577 49108 24521 49109 24577 49109 22900 49109 23172 49110 24570 49110 26261 49110 26261 49111 24570 49111 24564 49111 26261 49112 24564 49112 24523 49112 24522 49113 24592 49113 24591 49113 24522 49114 24591 49114 24525 49114 22818 49115 24585 49115 24584 49115 22917 49116 24526 49116 22916 49116 22916 49117 24526 49117 24523 49117 22916 49118 24523 49118 22914 49118 22914 49119 24523 49119 24564 49119 22918 49120 24591 49120 24524 49120 24524 49121 24591 49121 24561 49121 22917 49122 24525 49122 24526 49122 24526 49123 24525 49123 24591 49123 24526 49124 24591 49124 24527 49124 24527 49125 24591 49125 22918 49125 22918 49126 24528 49126 24527 49126 24527 49127 24528 49127 24529 49127 24527 49128 24529 49128 26266 49128 26266 49129 24529 49129 24549 49129 26266 49130 24549 49130 24550 49130 24535 49131 24538 49131 26269 49131 26269 49132 24538 49132 24540 49132 26273 49133 24542 49133 24534 49133 24534 49134 24542 49134 22925 49134 24534 49135 22925 49135 22927 49135 22935 49136 24530 49136 26275 49136 26275 49137 24530 49137 24531 49137 26275 49138 24531 49138 23160 49138 23160 49139 24531 49139 24472 49139 23160 49140 24472 49140 24498 49140 24498 49141 24472 49141 24495 49141 24498 49142 24495 49142 22855 49142 22935 49143 26275 49143 22933 49143 22933 49144 26275 49144 24533 49144 22933 49145 24533 49145 24532 49145 24532 49146 24533 49146 26273 49146 24532 49147 26273 49147 22844 49147 22938 49148 22940 49148 25533 49148 25533 49149 22940 49149 22836 49149 25533 49150 22836 49150 24598 49150 24598 49151 22836 49151 22837 49151 24598 49152 22837 49152 22838 49152 22844 49153 26273 49153 22841 49153 22841 49154 26273 49154 24534 49154 22841 49155 24534 49155 24597 49155 26269 49156 24550 49156 24535 49156 24535 49157 24550 49157 24552 49157 24535 49158 24552 49158 22964 49158 22964 49159 24552 49159 24554 49159 22964 49160 24554 49160 24536 49160 24536 49161 24554 49161 24557 49161 24538 49162 22970 49162 24475 49162 24475 49163 22970 49163 22971 49163 24475 49164 22971 49164 24476 49164 22964 49165 22965 49165 24535 49165 24535 49166 22965 49166 24537 49166 24535 49167 24537 49167 24538 49167 24538 49168 24537 49168 22967 49168 24538 49169 22967 49169 22970 49169 24475 49170 24539 49170 24538 49170 24538 49171 24539 49171 22924 49171 24538 49172 22924 49172 24540 49172 24540 49173 22924 49173 24541 49173 24540 49174 24541 49174 24542 49174 24542 49175 24541 49175 24543 49175 24542 49176 24543 49176 22925 49176 22927 49177 22929 49177 24534 49177 24534 49178 22929 49178 24545 49178 24534 49179 24545 49179 24544 49179 24544 49180 24545 49180 22829 49180 24544 49181 22829 49181 24546 49181 24546 49182 22829 49182 22830 49182 22830 49183 22832 49183 24546 49183 24546 49184 22832 49184 24547 49184 24546 49185 24547 49185 24475 49185 24475 49186 24547 49186 24548 49186 24475 49187 24548 49187 24539 49187 24549 49188 24551 49188 24550 49188 24550 49189 24551 49189 24553 49189 24550 49190 24553 49190 24552 49190 24552 49191 24553 49191 24555 49191 24552 49192 24555 49192 24554 49192 24554 49193 24555 49193 22823 49193 24554 49194 22823 49194 24558 49194 22875 49195 22877 49195 25505 49195 25505 49196 22877 49196 24557 49196 25505 49197 24557 49197 24556 49197 24556 49198 24557 49198 24554 49198 24556 49199 24554 49199 24559 49199 24559 49200 24554 49200 24558 49200 24558 49201 22825 49201 24559 49201 24559 49202 22825 49202 24560 49202 24559 49203 24560 49203 24561 49203 24561 49204 24560 49204 22826 49204 24561 49205 22826 49205 24524 49205 24562 49206 22820 49206 24479 49206 24479 49207 22820 49207 22821 49207 24479 49208 22821 49208 24480 49208 24480 49209 22821 49209 24563 49209 24480 49210 24563 49210 24564 49210 24564 49211 24563 49211 24565 49211 24564 49212 24565 49212 22914 49212 24481 49213 24566 49213 24575 49213 24575 49214 24566 49214 24567 49214 24575 49215 24567 49215 24570 49215 24570 49216 24567 49216 24568 49216 22809 49217 24564 49217 24569 49217 24569 49218 24564 49218 24570 49218 24569 49219 24570 49219 22909 49219 22909 49220 24570 49220 24568 49220 22809 49221 22811 49221 24564 49221 24564 49222 22811 49222 22812 49222 24564 49223 22812 49223 24480 49223 24480 49224 22812 49224 22814 49224 24480 49225 22814 49225 24571 49225 24571 49226 22814 49226 24572 49226 24571 49227 24572 49227 22816 49227 24519 49228 22803 49228 23172 49228 23172 49229 22803 49229 24573 49229 23172 49230 24573 49230 24570 49230 24570 49231 24573 49231 24574 49231 24570 49232 24574 49232 24575 49232 24574 49233 22806 49233 24575 49233 24575 49234 22806 49234 24576 49234 24575 49235 24576 49235 24589 49235 24589 49236 24576 49236 24578 49236 24589 49237 24578 49237 24577 49237 24577 49238 24578 49238 24579 49238 24577 49239 24579 49239 22900 49239 24477 49240 24580 49240 24581 49240 24581 49241 24580 49241 24582 49241 24581 49242 24582 49242 24583 49242 24583 49243 24582 49243 24590 49243 24583 49244 24590 49244 24479 49244 24479 49245 24590 49245 24584 49245 24479 49246 24584 49246 24562 49246 24562 49247 24584 49247 24585 49247 22800 49248 24586 49248 24515 49248 24515 49249 24586 49249 24587 49249 24515 49250 24587 49250 24577 49250 24577 49251 24587 49251 24588 49251 24577 49252 24588 49252 24589 49252 24589 49253 24588 49253 25522 49253 24589 49254 25522 49254 25523 49254 24580 49255 25507 49255 24582 49255 24582 49256 25507 49256 24559 49256 24582 49257 24559 49257 24590 49257 24590 49258 24559 49258 24561 49258 24590 49259 24561 49259 24584 49259 24584 49260 24561 49260 24591 49260 24584 49261 24591 49261 22818 49261 22818 49262 24591 49262 24592 49262 22949 49263 24593 49263 24594 49263 24594 49264 24593 49264 24494 49264 24594 49265 24494 49265 24500 49265 24500 49266 24494 49266 24492 49266 24500 49267 24492 49267 25540 49267 25540 49268 24492 49268 24595 49268 25527 49269 25528 49269 24546 49269 24546 49270 25528 49270 24596 49270 24546 49271 24596 49271 24544 49271 24544 49272 24596 49272 24474 49272 24544 49273 24474 49273 24534 49273 24534 49274 24474 49274 24598 49274 24534 49275 24598 49275 24597 49275 24597 49276 24598 49276 22838 49276 25596 49277 24602 49277 23108 49277 26293 49278 26291 49278 24891 49278 24891 49279 26291 49279 24599 49279 24891 49280 24599 49280 24893 49280 24893 49281 24599 49281 24600 49281 24893 49282 24600 49282 24880 49282 24880 49283 24600 49283 23082 49283 25596 49284 24601 49284 24602 49284 24602 49285 24601 49285 24603 49285 24602 49286 24603 49286 23109 49286 24348 49287 24349 49287 24891 49287 22882 49288 26293 49288 24679 49288 24679 49289 26293 49289 24891 49289 24679 49290 24891 49290 24604 49290 24604 49291 24891 49291 24349 49291 24348 49292 24891 49292 24700 49292 24700 49293 24891 49293 24605 49293 24700 49294 24605 49294 24698 49294 24332 49295 24334 49295 24606 49295 24606 49296 24334 49296 24337 49296 24606 49297 24337 49297 24351 49297 24351 49298 24337 49298 24604 49298 24351 49299 24604 49299 24353 49299 24353 49300 24604 49300 24349 49300 24605 49301 24607 49301 24698 49301 24698 49302 24607 49302 24609 49302 24698 49303 24609 49303 24608 49303 24608 49304 24609 49304 24901 49304 24608 49305 24901 49305 24696 49305 24696 49306 24901 49306 24916 49306 24696 49307 24916 49307 24694 49307 24916 49308 24908 49308 24694 49308 24694 49309 24908 49309 25582 49309 24694 49310 25582 49310 24610 49310 24610 49311 25582 49311 25581 49311 24610 49312 25581 49312 24692 49312 24692 49313 25581 49313 25668 49313 24692 49314 25668 49314 24690 49314 24690 49315 25668 49315 24611 49315 24690 49316 24611 49316 24612 49316 23108 49317 26289 49317 25596 49317 25596 49318 26289 49318 26290 49318 25596 49319 26290 49319 24615 49319 24615 49320 26290 49320 23104 49320 24615 49321 23104 49321 24613 49321 24611 49322 25584 49322 24612 49322 24612 49323 25584 49323 25600 49323 24612 49324 25600 49324 24614 49324 24614 49325 25600 49325 24615 49325 24614 49326 24615 49326 24685 49326 24685 49327 24615 49327 24613 49327 24181 49328 24617 49328 24616 49328 24616 49329 24617 49329 24618 49329 24616 49330 24618 49330 24619 49330 24619 49331 24618 49331 24386 49331 23763 49332 24620 49332 23764 49332 23764 49333 24620 49333 25277 49333 23764 49334 25277 49334 24426 49334 24223 49335 24224 49335 25294 49335 24223 49336 25294 49336 24222 49336 24222 49337 25294 49337 24621 49337 24201 49338 24205 49338 24202 49338 24202 49339 24205 49339 25306 49339 25305 49340 25287 49340 24221 49340 24221 49341 24217 49341 25305 49341 25305 49342 24217 49342 24622 49342 25305 49343 24622 49343 24623 49343 24623 49344 24622 49344 25238 49344 24623 49345 25238 49345 25306 49345 25306 49346 25238 49346 24624 49346 25306 49347 24624 49347 24202 49347 24240 49348 24193 49348 24238 49348 24238 49349 24193 49349 24194 49349 24238 49350 24194 49350 24625 49350 24625 49351 24194 49351 24626 49351 24625 49352 24626 49352 24233 49352 24233 49353 24626 49353 24627 49353 24208 49354 24210 49354 24212 49354 24212 49355 24210 49355 25310 49355 24212 49356 25310 49356 24628 49356 24628 49357 25310 49357 24629 49357 24629 49358 25310 49358 24630 49358 24629 49359 24630 49359 25230 49359 25547 49360 23994 49360 23963 49360 23963 49361 23994 49361 24631 49361 23963 49362 24631 49362 23968 49362 23968 49363 24631 49363 24632 49363 23968 49364 24632 49364 23966 49364 23966 49365 24632 49365 25235 49365 23984 49366 25563 49366 23982 49366 23982 49367 25563 49367 25562 49367 24633 49368 24634 49368 23974 49368 23974 49369 23970 49369 24633 49369 24633 49370 23970 49370 23971 49370 24633 49371 23971 49371 24635 49371 24635 49372 23971 49372 25243 49372 24635 49373 25243 49373 25562 49373 25562 49374 25243 49374 24636 49374 25562 49375 24636 49375 23982 49375 24639 49376 23954 49376 24637 49376 23985 49377 25550 49377 24638 49377 24638 49378 25550 49378 24641 49378 23951 49379 23952 49379 24639 49379 25552 49380 23950 49380 23951 49380 23951 49381 24639 49381 25552 49381 25552 49382 24639 49382 24637 49382 25552 49383 24637 49383 24641 49383 24641 49384 24637 49384 24640 49384 24641 49385 24640 49385 24638 49385 23708 49386 25134 49386 24642 49386 24642 49387 25134 49387 24340 49387 24642 49388 24340 49388 23707 49388 23707 49389 24340 49389 23704 49389 23726 49390 24644 49390 24643 49390 24643 49391 24644 49391 24645 49391 24643 49392 24645 49392 24646 49392 24646 49393 24645 49393 24647 49393 24646 49394 24647 49394 23731 49394 23731 49395 24647 49395 23777 49395 24648 49396 24649 49396 24650 49396 24650 49397 24649 49397 24651 49397 24650 49398 24651 49398 25176 49398 25176 49399 24651 49399 25177 49399 25177 49400 24651 49400 24652 49400 25177 49401 24652 49401 25178 49401 23743 49402 24653 49402 24652 49402 24652 49403 24653 49403 24654 49403 24652 49404 24654 49404 25178 49404 23503 49405 24655 49405 23509 49405 23509 49406 24655 49406 25260 49406 23509 49407 25260 49407 23508 49407 23508 49408 25260 49408 24656 49408 25269 49409 23744 49409 24661 49409 25260 49410 25264 49410 24656 49410 24656 49411 25264 49411 25265 49411 24656 49412 25265 49412 24658 49412 25265 49413 24657 49413 24658 49413 24658 49414 24657 49414 25268 49414 24658 49415 25268 49415 24659 49415 24659 49416 25268 49416 24660 49416 24659 49417 24660 49417 25175 49417 25175 49418 24660 49418 25269 49418 25175 49419 25269 49419 23748 49419 23748 49420 25269 49420 24661 49420 24662 49421 24663 49421 25194 49421 23501 49422 25259 49422 23499 49422 23499 49423 25259 49423 24665 49423 25258 49424 23518 49424 23517 49424 23517 49425 24662 49425 25258 49425 25258 49426 24662 49426 25194 49426 25258 49427 25194 49427 24665 49427 24665 49428 25194 49428 24664 49428 24665 49429 24664 49429 23499 49429 24668 49430 25252 49430 23487 49430 24670 49431 25184 49431 24666 49431 23487 49432 24667 49432 24668 49432 24668 49433 24667 49433 24670 49433 24668 49434 24670 49434 24669 49434 24669 49435 24670 49435 24666 49435 24671 49436 23522 49436 25248 49436 25248 49437 23522 49437 24672 49437 24672 49438 25173 49438 25248 49438 25248 49439 25173 49439 24673 49439 25248 49440 24673 49440 24674 49440 24674 49441 24673 49441 23468 49441 24674 49442 23468 49442 23469 49442 23469 49443 24675 49443 24674 49443 24674 49444 24675 49444 24676 49444 24674 49445 24676 49445 25250 49445 24677 49446 24678 49446 24679 49446 24679 49447 24678 49447 24680 49447 24680 49448 23091 49448 24679 49448 24679 49449 23091 49449 24681 49449 24679 49450 24681 49450 22882 49450 24682 49451 23052 49451 23053 49451 25128 49452 25127 49452 23053 49452 23053 49453 25127 49453 24683 49453 23053 49454 24683 49454 24682 49454 24682 49455 24683 49455 23062 49455 24684 49456 23120 49456 24996 49456 23112 49457 24684 49457 23103 49457 23103 49458 24684 49458 24613 49458 23103 49459 24613 49459 23104 49459 24684 49460 24996 49460 24613 49460 24613 49461 24996 49461 24998 49461 24613 49462 24998 49462 24685 49462 24998 49463 24686 49463 24685 49463 24685 49464 24686 49464 24687 49464 24685 49465 24687 49465 24614 49465 24687 49466 24688 49466 24614 49466 24614 49467 24688 49467 25002 49467 24614 49468 25002 49468 24612 49468 25002 49469 24689 49469 24612 49469 24612 49470 24689 49470 25003 49470 24612 49471 25003 49471 24690 49471 25003 49472 25004 49472 24690 49472 24690 49473 25004 49473 24691 49473 24690 49474 24691 49474 24692 49474 24691 49475 25006 49475 24692 49475 24692 49476 25006 49476 25008 49476 24692 49477 25008 49477 24610 49477 25008 49478 25010 49478 24610 49478 24610 49479 25010 49479 25013 49479 24610 49480 25013 49480 24694 49480 25013 49481 24693 49481 24694 49481 24694 49482 24693 49482 25016 49482 24694 49483 25016 49483 24696 49483 25016 49484 24695 49484 24696 49484 24696 49485 24695 49485 24697 49485 24696 49486 24697 49486 24608 49486 24697 49487 25018 49487 24608 49487 24608 49488 25018 49488 24699 49488 24608 49489 24699 49489 24698 49489 24698 49490 24699 49490 25019 49490 24698 49491 25019 49491 24700 49491 24700 49492 25019 49492 25022 49492 24700 49493 25022 49493 24348 49493 24366 49494 24461 49494 24701 49494 24366 49495 24701 49495 24702 49495 24702 49496 24701 49496 25028 49496 24702 49497 25028 49497 24703 49497 24703 49498 25028 49498 24704 49498 24703 49499 24704 49499 24994 49499 24994 49500 24704 49500 24705 49500 24994 49501 24705 49501 24992 49501 24992 49502 24705 49502 25034 49502 24992 49503 25034 49503 24989 49503 24989 49504 25034 49504 25032 49504 24989 49505 25032 49505 24706 49505 24711 49506 25137 49506 24712 49506 23096 49507 24707 49507 23098 49507 23098 49508 24707 49508 24715 49508 23098 49509 24715 49509 24708 49509 24708 49510 24715 49510 24709 49510 24708 49511 24709 49511 24710 49511 24710 49512 24709 49512 24712 49512 24710 49513 24712 49513 23093 49513 23093 49514 24712 49514 25137 49514 23093 49515 25137 49515 23092 49515 24711 49516 24712 49516 24407 49516 24407 49517 24712 49517 24709 49517 24407 49518 24709 49518 24713 49518 24713 49519 24709 49519 24715 49519 24713 49520 24715 49520 24714 49520 24714 49521 24715 49521 24707 49521 24714 49522 24707 49522 25126 49522 24723 49523 24716 49523 24724 49523 24720 49524 23060 49524 24726 49524 24726 49525 23060 49525 24717 49525 24726 49526 24717 49526 24723 49526 24723 49527 24717 49527 24718 49527 24723 49528 24718 49528 25146 49528 24726 49529 24719 49529 24720 49529 24720 49530 24719 49530 24728 49530 24720 49531 24728 49531 23057 49531 23057 49532 24728 49532 24721 49532 23057 49533 24721 49533 24722 49533 24723 49534 24724 49534 24726 49534 24726 49535 24724 49535 24725 49535 24726 49536 24725 49536 24719 49536 24719 49537 24725 49537 24727 49537 24719 49538 24727 49538 24728 49538 24728 49539 24727 49539 24388 49539 24728 49540 24388 49540 24721 49540 24729 49541 24788 49541 24794 49541 24794 49542 24788 49542 24790 49542 24730 49543 25000 49543 24754 49543 24731 49544 24783 49544 24785 49544 24744 49545 25171 49545 24436 49545 24732 49546 25158 49546 24786 49546 24733 49547 24756 49547 24772 49547 24740 49548 24733 49548 24773 49548 25154 49549 24766 49549 24734 49549 23131 49550 24735 49550 24764 49550 24764 49551 24735 49551 25154 49551 25154 49552 24735 49552 24736 49552 25154 49553 24736 49553 25153 49553 24738 49554 24997 49554 23121 49554 23121 49555 24737 49555 24738 49555 24738 49556 24737 49556 24739 49556 24738 49557 24739 49557 24764 49557 24764 49558 24739 49558 23129 49558 24764 49559 23129 49559 23131 49559 24740 49560 24770 49560 24741 49560 24741 49561 24770 49561 24751 49561 24741 49562 24751 49562 25188 49562 25188 49563 24751 49563 24742 49563 25188 49564 24742 49564 24766 49564 24732 49565 24783 49565 24743 49565 24743 49566 24783 49566 24731 49566 24743 49567 24731 49567 24780 49567 24744 49568 24793 49568 25160 49568 25160 49569 24793 49569 24745 49569 25160 49570 24745 49570 25161 49570 25161 49571 24745 49571 24746 49571 25161 49572 24746 49572 24747 49572 24747 49573 24746 49573 24759 49573 24747 49574 24759 49574 24748 49574 24748 49575 24759 49575 24749 49575 24748 49576 24749 49576 24750 49576 24750 49577 24749 49577 24761 49577 24750 49578 24761 49578 25158 49578 24770 49579 24752 49579 24751 49579 24751 49580 24752 49580 24753 49580 24751 49581 24753 49581 24742 49581 24742 49582 24753 49582 24754 49582 24757 49583 24778 49583 24755 49583 24756 49584 24779 49584 24755 49584 24755 49585 24779 49585 24781 49585 24755 49586 24781 49586 24757 49586 24757 49587 24781 49587 24758 49587 24757 49588 24758 49588 25011 49588 25011 49589 24758 49589 25012 49589 24793 49590 24796 49590 24745 49590 24745 49591 24796 49591 24795 49591 24745 49592 24795 49592 24746 49592 24746 49593 24795 49593 24794 49593 24746 49594 24794 49594 24759 49594 24759 49595 24794 49595 24790 49595 24759 49596 24790 49596 24749 49596 24749 49597 24790 49597 24760 49597 24749 49598 24760 49598 24761 49598 24761 49599 24760 49599 24762 49599 24765 49600 24763 49600 24999 49600 25154 49601 24734 49601 24764 49601 24764 49602 24734 49602 24765 49602 24764 49603 24765 49603 24738 49603 24738 49604 24765 49604 24999 49604 24738 49605 24999 49605 24997 49605 24766 49606 24742 49606 24734 49606 24734 49607 24742 49607 24754 49607 24734 49608 24754 49608 24765 49608 24765 49609 24754 49609 25000 49609 24765 49610 25000 49610 24763 49610 24730 49611 24754 49611 25001 49611 25001 49612 24754 49612 24753 49612 25001 49613 24753 49613 24767 49613 24767 49614 24753 49614 24752 49614 24767 49615 24752 49615 24768 49615 24774 49616 24769 49616 24771 49616 24740 49617 24773 49617 24770 49617 24770 49618 24773 49618 24774 49618 24770 49619 24774 49619 24752 49619 24752 49620 24774 49620 24771 49620 24752 49621 24771 49621 24768 49621 24733 49622 24772 49622 24773 49622 24773 49623 24772 49623 24776 49623 24773 49624 24776 49624 24774 49624 24774 49625 24776 49625 24777 49625 24774 49626 24777 49626 24769 49626 24756 49627 24755 49627 24772 49627 24772 49628 24755 49628 24778 49628 24772 49629 24778 49629 24776 49629 24776 49630 24778 49630 24775 49630 24776 49631 24775 49631 24777 49631 25011 49632 25009 49632 24757 49632 24757 49633 25009 49633 25007 49633 24757 49634 25007 49634 24778 49634 24778 49635 25007 49635 25005 49635 24778 49636 25005 49636 24775 49636 24779 49637 24780 49637 24781 49637 24781 49638 24780 49638 24731 49638 24781 49639 24731 49639 24758 49639 24758 49640 24731 49640 24785 49640 24758 49641 24785 49641 25012 49641 25012 49642 24785 49642 25014 49642 24784 49643 25015 49643 24782 49643 24732 49644 24786 49644 24783 49644 24783 49645 24786 49645 24784 49645 24783 49646 24784 49646 24785 49646 24785 49647 24784 49647 24782 49647 24785 49648 24782 49648 25014 49648 25158 49649 24761 49649 24786 49649 24786 49650 24761 49650 24762 49650 24786 49651 24762 49651 24784 49651 24784 49652 24762 49652 24787 49652 24784 49653 24787 49653 25015 49653 24788 49654 24789 49654 24790 49654 24790 49655 24789 49655 24791 49655 24790 49656 24791 49656 24760 49656 24760 49657 24791 49657 24792 49657 24760 49658 24792 49658 24762 49658 24762 49659 24792 49659 25017 49659 24762 49660 25017 49660 24787 49660 24744 49661 24436 49661 24793 49661 24793 49662 24436 49662 24435 49662 24793 49663 24435 49663 24796 49663 24796 49664 24435 49664 24429 49664 24796 49665 24429 49665 24428 49665 24729 49666 24794 49666 25020 49666 25020 49667 24794 49667 24795 49667 25020 49668 24795 49668 25024 49668 25024 49669 24795 49669 24796 49669 25024 49670 24796 49670 25023 49670 25023 49671 24796 49671 24428 49671 25023 49672 24428 49672 25021 49672 24848 49673 25575 49673 24847 49673 25698 49674 24826 49674 24816 49674 24837 49675 24800 49675 24838 49675 24840 49676 24806 49676 24846 49676 24797 49677 24798 49677 24822 49677 24822 49678 24798 49678 23155 49678 24799 49679 24800 49679 24801 49679 24801 49680 24800 49680 24837 49680 24801 49681 24837 49681 24802 49681 23156 49682 24803 49682 24804 49682 24804 49683 24803 49683 24805 49683 24804 49684 24805 49684 25196 49684 25196 49685 24805 49685 24813 49685 25196 49686 24813 49686 25203 49686 25203 49687 24813 49687 24814 49687 25203 49688 24814 49688 24806 49688 24826 49689 24807 49689 24808 49689 24808 49690 24807 49690 25679 49690 24808 49691 25679 49691 25232 49691 24843 49692 24838 49692 24809 49692 24809 49693 24838 49693 24800 49693 24809 49694 24800 49694 24810 49694 24810 49695 24800 49695 24799 49695 24810 49696 24799 49696 24840 49696 24803 49697 24811 49697 24805 49697 24805 49698 24811 49698 24821 49698 24805 49699 24821 49699 24813 49699 24813 49700 24821 49700 24812 49700 24813 49701 24812 49701 24814 49701 24814 49702 24812 49702 24823 49702 24815 49703 24824 49703 24816 49703 24816 49704 24824 49704 24817 49704 24816 49705 24817 49705 25698 49705 25232 49706 25217 49706 24808 49706 24808 49707 25217 49707 24819 49707 24808 49708 24819 49708 24818 49708 24818 49709 24819 49709 24832 49709 24818 49710 24832 49710 24827 49710 24827 49711 24832 49711 24820 49711 24811 49712 24797 49712 24821 49712 24821 49713 24797 49713 24822 49713 24821 49714 24822 49714 24812 49714 24812 49715 24822 49715 24850 49715 24812 49716 24850 49716 24823 49716 24823 49717 24850 49717 24847 49717 24828 49718 25570 49718 24815 49718 24815 49719 25570 49719 25569 49719 24815 49720 25569 49720 24824 49720 24824 49721 25569 49721 24825 49721 24824 49722 24825 49722 24817 49722 24817 49723 24825 49723 25568 49723 24826 49724 24808 49724 24816 49724 24816 49725 24808 49725 24818 49725 24816 49726 24818 49726 24815 49726 24815 49727 24818 49727 24827 49727 24815 49728 24827 49728 24828 49728 24839 49729 24829 49729 24830 49729 24830 49730 24829 49730 24820 49730 24830 49731 24820 49731 24831 49731 24831 49732 24820 49732 24832 49732 24831 49733 24832 49733 24836 49733 24836 49734 24832 49734 24819 49734 24836 49735 24819 49735 25219 49735 25219 49736 24819 49736 25217 49736 24829 49737 24833 49737 24820 49737 24820 49738 24833 49738 24834 49738 24820 49739 24834 49739 24827 49739 24827 49740 24834 49740 24835 49740 24827 49741 24835 49741 24828 49741 25219 49742 24802 49742 24836 49742 24836 49743 24802 49743 24837 49743 24836 49744 24837 49744 24831 49744 24831 49745 24837 49745 24838 49745 24831 49746 24838 49746 24830 49746 24830 49747 24838 49747 24843 49747 24830 49748 24843 49748 24839 49748 24839 49749 24843 49749 24845 49749 24842 49750 25573 49750 24844 49750 24840 49751 24846 49751 24810 49751 24810 49752 24846 49752 24841 49752 24810 49753 24841 49753 24809 49753 24809 49754 24841 49754 24842 49754 24809 49755 24842 49755 24843 49755 24843 49756 24842 49756 24844 49756 24843 49757 24844 49757 24845 49757 24806 49758 24814 49758 24846 49758 24846 49759 24814 49759 24823 49759 24846 49760 24823 49760 24841 49760 24841 49761 24823 49761 24847 49761 24841 49762 24847 49762 24842 49762 24842 49763 24847 49763 25575 49763 24842 49764 25575 49764 25573 49764 24848 49765 24847 49765 25578 49765 25578 49766 24847 49766 24850 49766 25578 49767 24850 49767 24849 49767 24849 49768 24850 49768 24822 49768 24849 49769 24822 49769 24851 49769 24851 49770 24822 49770 23155 49770 24851 49771 23155 49771 23154 49771 26285 49772 23033 49772 24859 49772 23036 49773 26287 49773 24852 49773 24852 49774 26287 49774 26288 49774 24852 49775 26288 49775 24854 49775 24854 49776 26288 49776 24853 49776 24854 49777 24853 49777 24855 49777 24855 49778 24853 49778 26286 49778 24855 49779 26286 49779 24856 49779 24856 49780 26286 49780 24857 49780 24856 49781 24857 49781 24859 49781 24859 49782 24857 49782 24858 49782 24859 49783 24858 49783 26285 49783 26305 49784 25104 49784 24860 49784 24860 49785 25104 49785 24861 49785 24860 49786 24861 49786 26301 49786 26301 49787 24861 49787 24862 49787 26301 49788 24862 49788 26302 49788 26302 49789 24862 49789 23019 49789 26302 49790 23019 49790 24863 49790 24863 49791 23019 49791 24864 49791 24864 49792 23019 49792 23018 49792 24864 49793 23018 49793 26303 49793 26303 49794 23018 49794 23017 49794 26303 49795 23017 49795 26304 49795 26294 49796 22990 49796 24869 49796 22991 49797 25124 49797 24865 49797 24865 49798 25124 49798 24866 49798 24865 49799 24866 49799 22992 49799 22992 49800 24866 49800 24867 49800 22992 49801 24867 49801 22994 49801 22994 49802 24867 49802 26297 49802 22994 49803 26297 49803 24868 49803 24868 49804 26297 49804 26296 49804 24868 49805 26296 49805 24869 49805 24869 49806 26296 49806 26295 49806 24869 49807 26295 49807 26294 49807 26280 49808 25112 49808 26279 49808 26279 49809 25112 49809 24871 49809 26279 49810 24871 49810 24870 49810 24870 49811 24871 49811 24872 49811 24870 49812 24872 49812 24873 49812 24873 49813 24872 49813 24874 49813 24873 49814 24874 49814 24875 49814 24875 49815 24874 49815 26281 49815 26281 49816 24874 49816 24876 49816 26281 49817 24876 49817 26278 49817 26278 49818 24876 49818 22981 49818 26278 49819 22981 49819 22980 49819 24877 49820 25772 49820 24878 49820 25761 49821 25760 49821 24929 49821 24948 49822 24894 49822 24879 49822 24922 49823 24889 49823 24923 49823 24991 49824 24990 49824 25616 49824 24993 49825 24991 49825 24967 49825 24995 49826 24993 49826 24963 49826 24981 49827 24995 49827 24959 49827 24896 49828 24981 49828 24955 49828 24893 49829 24880 49829 24927 49829 25582 49830 24908 49830 24906 49830 23067 49831 24946 49831 24935 49831 23076 49832 24881 49832 23075 49832 23075 49833 24881 49833 24933 49833 23076 49834 24882 49834 24881 49834 24881 49835 24882 49835 24883 49835 24881 49836 24883 49836 24884 49836 24884 49837 24883 49837 24934 49837 24931 49838 23079 49838 24933 49838 24933 49839 23079 49839 24885 49839 24933 49840 24885 49840 23075 49840 24886 49841 23085 49841 24929 49841 24929 49842 23085 49842 23078 49842 24929 49843 23078 49843 24931 49843 24931 49844 23078 49844 24887 49844 24931 49845 24887 49845 23079 49845 23081 49846 23080 49846 24886 49846 24886 49847 23080 49847 24888 49847 24886 49848 24888 49848 23085 49848 24880 49849 23082 49849 23081 49849 24891 49850 24889 49850 24605 49850 24605 49851 24889 49851 24922 49851 24605 49852 24922 49852 24607 49852 24895 49853 24894 49853 24970 49853 24970 49854 24894 49854 24948 49854 24970 49855 24948 49855 24971 49855 24925 49856 24923 49856 24890 49856 24890 49857 24923 49857 24889 49857 24890 49858 24889 49858 24892 49858 24892 49859 24889 49859 24891 49859 24892 49860 24891 49860 24893 49860 24949 49861 24879 49861 24954 49861 24954 49862 24879 49862 24894 49862 24954 49863 24894 49863 24953 49863 24953 49864 24894 49864 24895 49864 24953 49865 24895 49865 24896 49865 24914 49866 24915 49866 24909 49866 25752 49867 24912 49867 24897 49867 24897 49868 24912 49868 24914 49868 24897 49869 24914 49869 24918 49869 24918 49870 24914 49870 24909 49870 24918 49871 24909 49871 24917 49871 24916 49872 24901 49872 24898 49872 24898 49873 24901 49873 24902 49873 24898 49874 24902 49874 24899 49874 24899 49875 24902 49875 24903 49875 24899 49876 24903 49876 24900 49876 24900 49877 24903 49877 24919 49877 24901 49878 24609 49878 24902 49878 24902 49879 24609 49879 24921 49879 24902 49880 24921 49880 24903 49880 24903 49881 24921 49881 24904 49881 24903 49882 24904 49882 24919 49882 24919 49883 24904 49883 24924 49883 24919 49884 24924 49884 25755 49884 25755 49885 24924 49885 25756 49885 24942 49886 24944 49886 24905 49886 24951 49887 25768 49887 24950 49887 24950 49888 25768 49888 24942 49888 24950 49889 24942 49889 24947 49889 24947 49890 24942 49890 24905 49890 24947 49891 24905 49891 24939 49891 25582 49892 24906 49892 25673 49892 25673 49893 24906 49893 24910 49893 25673 49894 24910 49894 25675 49894 25675 49895 24910 49895 24907 49895 25675 49896 24907 49896 25676 49896 25676 49897 24907 49897 25746 49897 25676 49898 25746 49898 25745 49898 24908 49899 24917 49899 24906 49899 24906 49900 24917 49900 24909 49900 24906 49901 24909 49901 24910 49901 24910 49902 24909 49902 24915 49902 24910 49903 24915 49903 24907 49903 24907 49904 24915 49904 24911 49904 24907 49905 24911 49905 25746 49905 24912 49906 25749 49906 24914 49906 24914 49907 25749 49907 24913 49907 24914 49908 24913 49908 24915 49908 24915 49909 24913 49909 25747 49909 24915 49910 25747 49910 24911 49910 24908 49911 24916 49911 24917 49911 24917 49912 24916 49912 24898 49912 24917 49913 24898 49913 24918 49913 24918 49914 24898 49914 24899 49914 24918 49915 24899 49915 24897 49915 24897 49916 24899 49916 24900 49916 24897 49917 24900 49917 25752 49917 25755 49918 25753 49918 24919 49918 24919 49919 25753 49919 24920 49919 24919 49920 24920 49920 24900 49920 24900 49921 24920 49921 25750 49921 24900 49922 25750 49922 25752 49922 24609 49923 24607 49923 24921 49923 24921 49924 24607 49924 24922 49924 24921 49925 24922 49925 24904 49925 24904 49926 24922 49926 24923 49926 24904 49927 24923 49927 24924 49927 24924 49928 24923 49928 24925 49928 24924 49929 24925 49929 25756 49929 25756 49930 24925 49930 24926 49930 24930 49931 25759 49931 25758 49931 24893 49932 24927 49932 24892 49932 24892 49933 24927 49933 24928 49933 24892 49934 24928 49934 24890 49934 24890 49935 24928 49935 24930 49935 24890 49936 24930 49936 24925 49936 24925 49937 24930 49937 25758 49937 24925 49938 25758 49938 24926 49938 24880 49939 23081 49939 24927 49939 24927 49940 23081 49940 24886 49940 24927 49941 24886 49941 24928 49941 24928 49942 24886 49942 24929 49942 24928 49943 24929 49943 24930 49943 24930 49944 24929 49944 25760 49944 24930 49945 25760 49945 25759 49945 25761 49946 24929 49946 25762 49946 25762 49947 24929 49947 24931 49947 25762 49948 24931 49948 24932 49948 24932 49949 24931 49949 24933 49949 24932 49950 24933 49950 25764 49950 25764 49951 24933 49951 25766 49951 25766 49952 24933 49952 24881 49952 25766 49953 24881 49953 24938 49953 23067 49954 24935 49954 24934 49954 24934 49955 24935 49955 24936 49955 24934 49956 24936 49956 24884 49956 24884 49957 24936 49957 24940 49957 24884 49958 24940 49958 24881 49958 24881 49959 24940 49959 24937 49959 24881 49960 24937 49960 24938 49960 24946 49961 24939 49961 24935 49961 24935 49962 24939 49962 24905 49962 24935 49963 24905 49963 24936 49963 24936 49964 24905 49964 24944 49964 24936 49965 24944 49965 24940 49965 24940 49966 24944 49966 25767 49966 24940 49967 25767 49967 24937 49967 25768 49968 24941 49968 24942 49968 24942 49969 24941 49969 24943 49969 24942 49970 24943 49970 24944 49970 24944 49971 24943 49971 24945 49971 24944 49972 24945 49972 25767 49972 24946 49973 24971 49973 24939 49973 24939 49974 24971 49974 24948 49974 24939 49975 24948 49975 24947 49975 24947 49976 24948 49976 24879 49976 24947 49977 24879 49977 24950 49977 24950 49978 24879 49978 24949 49978 24950 49979 24949 49979 24951 49979 24951 49980 24949 49980 25770 49980 24958 49981 25773 49981 24952 49981 24896 49982 24955 49982 24953 49982 24953 49983 24955 49983 24957 49983 24953 49984 24957 49984 24954 49984 24954 49985 24957 49985 24958 49985 24954 49986 24958 49986 24949 49986 24949 49987 24958 49987 24952 49987 24949 49988 24952 49988 25770 49988 24981 49989 24959 49989 24955 49989 24955 49990 24959 49990 24956 49990 24955 49991 24956 49991 24957 49991 24957 49992 24956 49992 24878 49992 24957 49993 24878 49993 24958 49993 24958 49994 24878 49994 25772 49994 24958 49995 25772 49995 25773 49995 24995 49996 24963 49996 24959 49996 24959 49997 24963 49997 24960 49997 24959 49998 24960 49998 24956 49998 24956 49999 24960 49999 24961 49999 24956 50000 24961 50000 24878 50000 24878 50001 24961 50001 24966 50001 24878 50002 24966 50002 24877 50002 24962 50003 24969 50003 24965 50003 24993 50004 24967 50004 24963 50004 24963 50005 24967 50005 24964 50005 24963 50006 24964 50006 24960 50006 24960 50007 24964 50007 24962 50007 24960 50008 24962 50008 24961 50008 24961 50009 24962 50009 24965 50009 24961 50010 24965 50010 24966 50010 24991 50011 25616 50011 24967 50011 24967 50012 25616 50012 24968 50012 24967 50013 24968 50013 24964 50013 24964 50014 24968 50014 25617 50014 24964 50015 25617 50015 24962 50015 24962 50016 25617 50016 25618 50016 24962 50017 25618 50017 24969 50017 24970 50018 24972 50018 23066 50018 24970 50019 24971 50019 24972 50019 24972 50020 24971 50020 24946 50020 24972 50021 24946 50021 23067 50021 24683 50022 24980 50022 24973 50022 25598 50023 24974 50023 24977 50023 23066 50024 26307 50024 24970 50024 24970 50025 26307 50025 23061 50025 24970 50026 23061 50026 24895 50026 23143 50027 25585 50027 24975 50027 24975 50028 25585 50028 25598 50028 24975 50029 25598 50029 24976 50029 24976 50030 25598 50030 24977 50030 23062 50031 24683 50031 23061 50031 23061 50032 24683 50032 24973 50032 23061 50033 24973 50033 24895 50033 24895 50034 24973 50034 24366 50034 24895 50035 24366 50035 24896 50035 24978 50036 24376 50036 24379 50036 24379 50037 24378 50037 24978 50037 24978 50038 24378 50038 24979 50038 24978 50039 24979 50039 24980 50039 24980 50040 24979 50040 24365 50040 24980 50041 24365 50041 24973 50041 24702 50042 24995 50042 24366 50042 24366 50043 24995 50043 24981 50043 24366 50044 24981 50044 24896 50044 25701 50045 24974 50045 24982 50045 24982 50046 24974 50046 25598 50046 24982 50047 25598 50047 24983 50047 24983 50048 25598 50048 24984 50048 24983 50049 24984 50049 25704 50049 25704 50050 24984 50050 24985 50050 25704 50051 24985 50051 25706 50051 25706 50052 24985 50052 25594 50052 25706 50053 25594 50053 25707 50053 25707 50054 25594 50054 24986 50054 25707 50055 24986 50055 24987 50055 24986 50056 25609 50056 24987 50056 24987 50057 25609 50057 25626 50057 24987 50058 25626 50058 25710 50058 25710 50059 25626 50059 24988 50059 25710 50060 24988 50060 24706 50060 24706 50061 24988 50061 24990 50061 24706 50062 24990 50062 24989 50062 24989 50063 24990 50063 24991 50063 24989 50064 24991 50064 24992 50064 24992 50065 24991 50065 24993 50065 24992 50066 24993 50066 24994 50066 24994 50067 24993 50067 24995 50067 24994 50068 24995 50068 24703 50068 24703 50069 24995 50069 24702 50069 24996 50070 23120 50070 23121 50070 23121 50071 24997 50071 24996 50071 24996 50072 24997 50072 24999 50072 24996 50073 24999 50073 24998 50073 24998 50074 24999 50074 24763 50074 24998 50075 24763 50075 24686 50075 24686 50076 24763 50076 25000 50076 24686 50077 25000 50077 24687 50077 25000 50078 24730 50078 24687 50078 24687 50079 24730 50079 25001 50079 24687 50080 25001 50080 24688 50080 24688 50081 25001 50081 24767 50081 24688 50082 24767 50082 25002 50082 25002 50083 24767 50083 24768 50083 25002 50084 24768 50084 24689 50084 24689 50085 24768 50085 24771 50085 24689 50086 24771 50086 25003 50086 24771 50087 24769 50087 25003 50087 25003 50088 24769 50088 24777 50088 25003 50089 24777 50089 25004 50089 25004 50090 24777 50090 24775 50090 25004 50091 24775 50091 24691 50091 24691 50092 24775 50092 25005 50092 24691 50093 25005 50093 25006 50093 25006 50094 25005 50094 25007 50094 25006 50095 25007 50095 25008 50095 25007 50096 25009 50096 25008 50096 25008 50097 25009 50097 25011 50097 25008 50098 25011 50098 25010 50098 25010 50099 25011 50099 25012 50099 25010 50100 25012 50100 25013 50100 25013 50101 25012 50101 25014 50101 25013 50102 25014 50102 24693 50102 24693 50103 25014 50103 24782 50103 24693 50104 24782 50104 25016 50104 24782 50105 25015 50105 25016 50105 25016 50106 25015 50106 24787 50106 25016 50107 24787 50107 24695 50107 24695 50108 24787 50108 25017 50108 24695 50109 25017 50109 24697 50109 24697 50110 25017 50110 25018 50110 25018 50111 25017 50111 24792 50111 25018 50112 24792 50112 24791 50112 24791 50113 24789 50113 25018 50113 25018 50114 24789 50114 24788 50114 25018 50115 24788 50115 24699 50115 24699 50116 24788 50116 24729 50116 24699 50117 24729 50117 25019 50117 25019 50118 24729 50118 25020 50118 25021 50119 25022 50119 25023 50119 25023 50120 25022 50120 25019 50120 25023 50121 25019 50121 25024 50121 25024 50122 25019 50122 25020 50122 25694 50123 25028 50123 25025 50123 25025 50124 25028 50124 24701 50124 25025 50125 24701 50125 25026 50125 25026 50126 24701 50126 24461 50126 25026 50127 24461 50127 25027 50127 25694 50128 25693 50128 25028 50128 25028 50129 25693 50129 25692 50129 25028 50130 25692 50130 24704 50130 25692 50131 25695 50131 24704 50131 24704 50132 25695 50132 25029 50132 24704 50133 25029 50133 24705 50133 24705 50134 25029 50134 25030 50134 24705 50135 25030 50135 25034 50135 25034 50136 25030 50136 25031 50136 25568 50137 25032 50137 25033 50137 25033 50138 25032 50138 25034 50138 25033 50139 25034 50139 25035 50139 25035 50140 25034 50140 25031 50140 25059 50141 23217 50141 25036 50141 25036 50142 23217 50142 25037 50142 25036 50143 25037 50143 25078 50143 25078 50144 25037 50144 23215 50144 25078 50145 23215 50145 25079 50145 25079 50146 23215 50146 25038 50146 25079 50147 25038 50147 25080 50147 25080 50148 25038 50148 23214 50148 25080 50149 23214 50149 25065 50149 25065 50150 23214 50150 25040 50150 25065 50151 25040 50151 25039 50151 25039 50152 25040 50152 23212 50152 25039 50153 23212 50153 25069 50153 25069 50154 23212 50154 25041 50154 25069 50155 25041 50155 25042 50155 25042 50156 25041 50156 23209 50156 25042 50157 23209 50157 25043 50157 25043 50158 23209 50158 25044 50158 25043 50159 25044 50159 25072 50159 25072 50160 25044 50160 23207 50160 25072 50161 23207 50161 25045 50161 25045 50162 23207 50162 23206 50162 25045 50163 23206 50163 25046 50163 25046 50164 23206 50164 23205 50164 25046 50165 23205 50165 25061 50165 25061 50166 23205 50166 23204 50166 25061 50167 23204 50167 25047 50167 25047 50168 23204 50168 25048 50168 25047 50169 25048 50169 25075 50169 25075 50170 25048 50170 23200 50170 25100 50171 25049 50171 25050 50171 25050 50172 25049 50172 23268 50172 25050 50173 23268 50173 25101 50173 25101 50174 23268 50174 25051 50174 25101 50175 25051 50175 25102 50175 25102 50176 25051 50176 23265 50176 25102 50177 23265 50177 25052 50177 25052 50178 23265 50178 23264 50178 25052 50179 23264 50179 25053 50179 25053 50180 23264 50180 23263 50180 25053 50181 23263 50181 25054 50181 25054 50182 23263 50182 23261 50182 25054 50183 23261 50183 25095 50183 25095 50184 23261 50184 23260 50184 25095 50185 23260 50185 25096 50185 25096 50186 23260 50186 23258 50186 23275 50187 23274 50187 22975 50187 25055 50188 25057 50188 25056 50188 25056 50189 25057 50189 25058 50189 25056 50190 25058 50190 26282 50190 26282 50191 25058 50191 25059 50191 26282 50192 25059 50192 25060 50192 25071 50193 25045 50193 25525 50193 25525 50194 25045 50194 25046 50194 25525 50195 25046 50195 25526 50195 25526 50196 25046 50196 25061 50196 25526 50197 25061 50197 25062 50197 25062 50198 25061 50198 25047 50198 25062 50199 25047 50199 25509 50199 25509 50200 25047 50200 25075 50200 25063 50201 25080 50201 25064 50201 25064 50202 25080 50202 25065 50202 25064 50203 25065 50203 25066 50203 25066 50204 25065 50204 25039 50204 25066 50205 25039 50205 25067 50205 25067 50206 25039 50206 25069 50206 25067 50207 25069 50207 25068 50207 25068 50208 25069 50208 25042 50208 25068 50209 25042 50209 25070 50209 25070 50210 25042 50210 25043 50210 25070 50211 25043 50211 25071 50211 25071 50212 25043 50212 25072 50212 25071 50213 25072 50213 25045 50213 25077 50214 25073 50214 26311 50214 26317 50215 26320 50215 26318 50215 26318 50216 26320 50216 25509 50216 26318 50217 25509 50217 25074 50217 25074 50218 25509 50218 25075 50218 25074 50219 25075 50219 22975 50219 22975 50220 25075 50220 25076 50220 22975 50221 25076 50221 23275 50221 26311 50222 25060 50222 25077 50222 25077 50223 25060 50223 25059 50223 25077 50224 25059 50224 25519 50224 25519 50225 25059 50225 25036 50225 25519 50226 25036 50226 25521 50226 25521 50227 25036 50227 25078 50227 25521 50228 25078 50228 25063 50228 25063 50229 25078 50229 25079 50229 25063 50230 25079 50230 25080 50230 25094 50231 25081 50231 25092 50231 25082 50232 25084 50232 25083 50232 25083 50233 25084 50233 23283 50233 25083 50234 23283 50234 23007 50234 23007 50235 23283 50235 25100 50235 23007 50236 25100 50236 26314 50236 25089 50237 25567 50237 25085 50237 25085 50238 25567 50238 23271 50238 25085 50239 23271 50239 25512 50239 25097 50240 25098 50240 25538 50240 25538 50241 25098 50241 25565 50241 25538 50242 25565 50242 25539 50242 25539 50243 25565 50243 25086 50243 25539 50244 25086 50244 25087 50244 25087 50245 25086 50245 25088 50245 25087 50246 25088 50246 25089 50246 25089 50247 25088 50247 25090 50247 25089 50248 25090 50248 25567 50248 25502 50249 26315 50249 25099 50249 25091 50250 26308 50250 26299 50250 26299 50251 26308 50251 25512 50251 26299 50252 25512 50252 23014 50252 23014 50253 25512 50253 23271 50253 23014 50254 23271 50254 25092 50254 25092 50255 23271 50255 25093 50255 25092 50256 25093 50256 25094 50256 25534 50257 25054 50257 25535 50257 25535 50258 25054 50258 25095 50258 25535 50259 25095 50259 25536 50259 25536 50260 25095 50260 25096 50260 25536 50261 25096 50261 25097 50261 25097 50262 25096 50262 25564 50262 25097 50263 25564 50263 25098 50263 25099 50264 26314 50264 25502 50264 25502 50265 26314 50265 25100 50265 25502 50266 25100 50266 25529 50266 25529 50267 25100 50267 25050 50267 25529 50268 25050 50268 25530 50268 25530 50269 25050 50269 25101 50269 25530 50270 25101 50270 25532 50270 25532 50271 25101 50271 25102 50271 25532 50272 25102 50272 25103 50272 25103 50273 25102 50273 25052 50273 25103 50274 25052 50274 25534 50274 25534 50275 25052 50275 25053 50275 25534 50276 25053 50276 25054 50276 26305 50277 26300 50277 25104 50277 25104 50278 26300 50278 23010 50278 25109 50279 23030 50279 26313 50279 26313 50280 23030 50280 25105 50280 26313 50281 25105 50281 26284 50281 23020 50282 23025 50282 26298 50282 26298 50283 23025 50283 25107 50283 26298 50284 25107 50284 25106 50284 25106 50285 25107 50285 25108 50285 26313 50286 26312 50286 25109 50286 25109 50287 26312 50287 23037 50287 25109 50288 23037 50288 23032 50288 23032 50289 23037 50289 23042 50289 23032 50290 23042 50290 25110 50290 25110 50291 23042 50291 25111 50291 25110 50292 25111 50292 23021 50292 23021 50293 25111 50293 23043 50293 23021 50294 23043 50294 25108 50294 25108 50295 23043 50295 26309 50295 25108 50296 26309 50296 25106 50296 23036 50297 23045 50297 26287 50297 26287 50298 23045 50298 26283 50298 26280 50299 26277 50299 25112 50299 25112 50300 26277 50300 25113 50300 22988 50301 22987 50301 25118 50301 25118 50302 22987 50302 22986 50302 25118 50303 22986 50303 25114 50303 26276 50304 22983 50304 25115 50304 25115 50305 22983 50305 25117 50305 25115 50306 25117 50306 25116 50306 25116 50307 25117 50307 25123 50307 25118 50308 25119 50308 22988 50308 22988 50309 25119 50309 23000 50309 22988 50310 23000 50310 25120 50310 25120 50311 23000 50311 25121 50311 25120 50312 25121 50312 22984 50312 22984 50313 25121 50313 23002 50313 22984 50314 23002 50314 25122 50314 25122 50315 23002 50315 22998 50315 25122 50316 22998 50316 25123 50316 25123 50317 22998 50317 22997 50317 25123 50318 22997 50318 25116 50318 22991 50319 25125 50319 25124 50319 25124 50320 25125 50320 23008 50320 24677 50321 25126 50321 24678 50321 24678 50322 25126 50322 24707 50322 24678 50323 24707 50323 23096 50323 24388 50324 25127 50324 24721 50324 24721 50325 25127 50325 25128 50325 24721 50326 25128 50326 24722 50326 23721 50327 25129 50327 25130 50327 25130 50328 25129 50328 23286 50328 25130 50329 23286 50329 23718 50329 23718 50330 23286 50330 23099 50330 25143 50331 25151 50331 25131 50331 25131 50332 25151 50332 23074 50332 25131 50333 23074 50333 25132 50333 25132 50334 23074 50334 25133 50334 23708 50335 25135 50335 25134 50335 25134 50336 25135 50336 25136 50336 24406 50337 24404 50337 23711 50337 23711 50338 24404 50338 24402 50338 23711 50339 24402 50339 25136 50339 25136 50340 24402 50340 24401 50340 25136 50341 24401 50341 25134 50341 24406 50342 23711 50342 24711 50342 24711 50343 23711 50343 25138 50343 24711 50344 25138 50344 25137 50344 25137 50345 25138 50345 23715 50345 25137 50346 23715 50346 23092 50346 23092 50347 23715 50347 23717 50347 23092 50348 23717 50348 25139 50348 25139 50349 23717 50349 25140 50349 25139 50350 25140 50350 25142 50350 25140 50351 23718 50351 23099 50351 23099 50352 25141 50352 25140 50352 25140 50353 25141 50353 23102 50353 25140 50354 23102 50354 25142 50354 25151 50355 25143 50355 25803 50355 25146 50356 25144 50356 25803 50356 25803 50357 25145 50357 25146 50357 25146 50358 25145 50358 24189 50358 25146 50359 24189 50359 24723 50359 24723 50360 24189 50360 25147 50360 24723 50361 25147 50361 24716 50361 24716 50362 25147 50362 25148 50362 24716 50363 25148 50363 25149 50363 25149 50364 25148 50364 24188 50364 25149 50365 24188 50365 24393 50365 24393 50366 24188 50366 24385 50366 24385 50367 24188 50367 24185 50367 24385 50368 24185 50368 24386 50368 24386 50369 24185 50369 25150 50369 24386 50370 25150 50370 24619 50370 23072 50371 25151 50371 23071 50371 23071 50372 25151 50372 25803 50372 23071 50373 25803 50373 23069 50373 23069 50374 25803 50374 25144 50374 25164 50375 25172 50375 23738 50375 25165 50376 23481 50376 23482 50376 25153 50377 23140 50377 23482 50377 23482 50378 25152 50378 25153 50378 25153 50379 25152 50379 23473 50379 25153 50380 23473 50380 25154 50380 25154 50381 23473 50381 23476 50381 25154 50382 23476 50382 24766 50382 25155 50383 25794 50383 24434 50383 23476 50384 25156 50384 24766 50384 24766 50385 25156 50385 25183 50385 24766 50386 25183 50386 25188 50386 23515 50387 24743 50387 23514 50387 23514 50388 24743 50388 24780 50388 23514 50389 24780 50389 23513 50389 23513 50390 24780 50390 24779 50390 23513 50391 24779 50391 25157 50391 25157 50392 24779 50392 24756 50392 25157 50393 24756 50393 23511 50393 23511 50394 24756 50394 24733 50394 25180 50395 25158 50395 23515 50395 23515 50396 25158 50396 24732 50396 23515 50397 24732 50397 24743 50397 25168 50398 24748 50398 25182 50398 23737 50399 24744 50399 23736 50399 23736 50400 24744 50400 25160 50400 23736 50401 25160 50401 25159 50401 25159 50402 25160 50402 25161 50402 25159 50403 25161 50403 25168 50403 25168 50404 25161 50404 24747 50404 25168 50405 24747 50405 24748 50405 23766 50406 24426 50406 25162 50406 23766 50407 25162 50407 23776 50407 23776 50408 25162 50408 25170 50408 23731 50409 23777 50409 23729 50409 23729 50410 23777 50410 23771 50410 23729 50411 23771 50411 23738 50411 23738 50412 23771 50412 25163 50412 23738 50413 25163 50413 25164 50413 23147 50414 25165 50414 25166 50414 25166 50415 25165 50415 23482 50415 25166 50416 23482 50416 23145 50416 23145 50417 23482 50417 23140 50417 25182 50418 25167 50418 25168 50418 25168 50419 25167 50419 25169 50419 25168 50420 25169 50420 23732 50420 23732 50421 25169 50421 23756 50421 25162 50422 25155 50422 25170 50422 25170 50423 25155 50423 24434 50423 25170 50424 24434 50424 23774 50424 23774 50425 24434 50425 25171 50425 23774 50426 25171 50426 25172 50426 25172 50427 25171 50427 24744 50427 25172 50428 24744 50428 23738 50428 23738 50429 24744 50429 23737 50429 24673 50430 25173 50430 23525 50430 25181 50431 24658 50431 25174 50431 25174 50432 24658 50432 24659 50432 25174 50433 24659 50433 25175 50433 23756 50434 25176 50434 23732 50434 23732 50435 25176 50435 25177 50435 23732 50436 25177 50436 25178 50436 24741 50437 25179 50437 24740 50437 24740 50438 25179 50438 25190 50438 24740 50439 25190 50439 24733 50439 23508 50440 24656 50440 25180 50440 25180 50441 24656 50441 24658 50441 25180 50442 24658 50442 25158 50442 25158 50443 24658 50443 25181 50443 25158 50444 25181 50444 24750 50444 24750 50445 25181 50445 23751 50445 24750 50446 23751 50446 24748 50446 24748 50447 23751 50447 23754 50447 24748 50448 23754 50448 25182 50448 23468 50449 24673 50449 23477 50449 23477 50450 24673 50450 23525 50450 23477 50451 23525 50451 25183 50451 25183 50452 23525 50452 23527 50452 25183 50453 23527 50453 25188 50453 24666 50454 25184 50454 25185 50454 25185 50455 25184 50455 23491 50455 25185 50456 23491 50456 23532 50456 23532 50457 23491 50457 23492 50457 23532 50458 23492 50458 25186 50458 25186 50459 23492 50459 25179 50459 25186 50460 25179 50460 25187 50460 25187 50461 25179 50461 24741 50461 25187 50462 24741 50462 23530 50462 23530 50463 24741 50463 25188 50463 23530 50464 25188 50464 25189 50464 25189 50465 25188 50465 23527 50465 25190 50466 23496 50466 24733 50466 24733 50467 23496 50467 23495 50467 24733 50468 23495 50468 23511 50468 23511 50469 23495 50469 25191 50469 23511 50470 25191 50470 25193 50470 25193 50471 25191 50471 25192 50471 25192 50472 24664 50472 25193 50472 25193 50473 24664 50473 25194 50473 25193 50474 25194 50474 24663 50474 25200 50475 23158 50475 25201 50475 25203 50476 24806 50476 25892 50476 24233 50477 24627 50477 24231 50477 24231 50478 24627 50478 24197 50478 24231 50479 24197 50479 25216 50479 25912 50480 23156 50480 25911 50480 25911 50481 23156 50481 24804 50481 25911 50482 24804 50482 25195 50482 25195 50483 24804 50483 25196 50483 25195 50484 25196 50484 25197 50484 25197 50485 25196 50485 25203 50485 25892 50486 24806 50486 25198 50486 25198 50487 24806 50487 24840 50487 25198 50488 24840 50488 25891 50488 23955 50489 25199 50489 23157 50489 23157 50490 25200 50490 23955 50490 23955 50491 25200 50491 25201 50491 23955 50492 25201 50492 25914 50492 25914 50493 25201 50493 23156 50493 25914 50494 23156 50494 25913 50494 25913 50495 23156 50495 25912 50495 25219 50496 25217 50496 25897 50496 25892 50497 25202 50497 25203 50497 25203 50498 25202 50498 23991 50498 25203 50499 23991 50499 25197 50499 25197 50500 23991 50500 25204 50500 25197 50501 25204 50501 25907 50501 25907 50502 25204 50502 25205 50502 25205 50503 24640 50503 25907 50503 25907 50504 24640 50504 24637 50504 25907 50505 24637 50505 23954 50505 24446 50506 24224 50506 25206 50506 25206 50507 25207 50507 24446 50507 24446 50508 25207 50508 25208 50508 24446 50509 25208 50509 24447 50509 24447 50510 25208 50510 25209 50510 24447 50511 25209 50511 25784 50511 25784 50512 25209 50512 25785 50512 25229 50513 25231 50513 25210 50513 25210 50514 25231 50514 25211 50514 25210 50515 25211 50515 25212 50515 25212 50516 25211 50516 25681 50516 25212 50517 25681 50517 24215 50517 25714 50518 25213 50518 25218 50518 25230 50519 24214 50519 24629 50519 24629 50520 24214 50520 24628 50520 24199 50521 25214 50521 25215 50521 25215 50522 25214 50522 25216 50522 25215 50523 25216 50523 25801 50523 25801 50524 25216 50524 24197 50524 25902 50525 25905 50525 24799 50525 25897 50526 25217 50526 25218 50526 25218 50527 25217 50527 25230 50527 25218 50528 25230 50528 25714 50528 25897 50529 25220 50529 25219 50529 25219 50530 25220 50530 25900 50530 25219 50531 25900 50531 24802 50531 24802 50532 25900 50532 25239 50532 24802 50533 25239 50533 25240 50533 24799 50534 25905 50534 24840 50534 24199 50535 25221 50535 25214 50535 25214 50536 25221 50536 25678 50536 25214 50537 25678 50537 24230 50537 24230 50538 25678 50538 25222 50538 24230 50539 25222 50539 25209 50539 25209 50540 25222 50540 25691 50540 25209 50541 25691 50541 25785 50541 25223 50542 25237 50542 25224 50542 25224 50543 25237 50543 25800 50543 25224 50544 25800 50544 25228 50544 24199 50545 25225 50545 25221 50545 25221 50546 25225 50546 25226 50546 25221 50547 25226 50547 25227 50547 25227 50548 25226 50548 25224 50548 25227 50549 25224 50549 25681 50549 25681 50550 25224 50550 25228 50550 25681 50551 25228 50551 24215 50551 25229 50552 24214 50552 25231 50552 25231 50553 24214 50553 25230 50553 25231 50554 25230 50554 25232 50554 25232 50555 25230 50555 25217 50555 25905 50556 25233 50556 24840 50556 24840 50557 25233 50557 25906 50557 24840 50558 25906 50558 25891 50558 25891 50559 25906 50559 25234 50559 25891 50560 25234 50560 23993 50560 23993 50561 25234 50561 25236 50561 23993 50562 25236 50562 25235 50562 25235 50563 25236 50563 23966 50563 25223 50564 24624 50564 25237 50564 25237 50565 24624 50565 25238 50565 25237 50566 25238 50566 24622 50566 25902 50567 24799 50567 25240 50567 25240 50568 24799 50568 24801 50568 25240 50569 24801 50569 24802 50569 25239 50570 25241 50570 25240 50570 25240 50571 25241 50571 25242 50571 25240 50572 25242 50572 23972 50572 23972 50573 25242 50573 23980 50573 23980 50574 24636 50574 23972 50574 23972 50575 24636 50575 25243 50575 23972 50576 25243 50576 23971 50576 25271 50577 23744 50577 25269 50577 25246 50578 24671 50578 25248 50578 23483 50579 23292 50579 23462 50579 23462 50580 23292 50580 25244 50580 23462 50581 25244 50581 23466 50581 25244 50582 26260 50582 23466 50582 23466 50583 26260 50583 26258 50583 23466 50584 26258 50584 25245 50584 25245 50585 26258 50585 25249 50585 25254 50586 25255 50586 26255 50586 26255 50587 25255 50587 25246 50587 26255 50588 25246 50588 25247 50588 25247 50589 25246 50589 25248 50589 25247 50590 25248 50590 25249 50590 25249 50591 25248 50591 24674 50591 25249 50592 24674 50592 25245 50592 25245 50593 24674 50593 25250 50593 23487 50594 25252 50594 25251 50594 25251 50595 25252 50595 23459 50595 26251 50596 23457 50596 26252 50596 26252 50597 23457 50597 25253 50597 26252 50598 25253 50598 26253 50598 26253 50599 25253 50599 25251 50599 26253 50600 25251 50600 25254 50600 25254 50601 25251 50601 23459 50601 25254 50602 23459 50602 25255 50602 25256 50603 23518 50603 25262 50603 25262 50604 23518 50604 25258 50604 25262 50605 25258 50605 25257 50605 25257 50606 25258 50606 24665 50606 25257 50607 24665 50607 26251 50607 26251 50608 24665 50608 25259 50608 26251 50609 25259 50609 23457 50609 25260 50610 24655 50610 25261 50610 25261 50611 24655 50611 23455 50611 25256 50612 25262 50612 25263 50612 25263 50613 25262 50613 26244 50613 25263 50614 26244 50614 23455 50614 23455 50615 26244 50615 26248 50615 23455 50616 26248 50616 25261 50616 25260 50617 25261 50617 25264 50617 25264 50618 25261 50618 26246 50618 25264 50619 26246 50619 25265 50619 25265 50620 26246 50620 26243 50620 25265 50621 26243 50621 24657 50621 24657 50622 26243 50622 25266 50622 24657 50623 25266 50623 25268 50623 25268 50624 25266 50624 25267 50624 25268 50625 25267 50625 24660 50625 24660 50626 25267 50626 23186 50626 24660 50627 23186 50627 25269 50627 25269 50628 23186 50628 23187 50628 25269 50629 23187 50629 25271 50629 25271 50630 23187 50630 25270 50630 25271 50631 25270 50631 23692 50631 23692 50632 25270 50632 23185 50632 23692 50633 23185 50633 25272 50633 25272 50634 23185 50634 25273 50634 25272 50635 25273 50635 24649 50635 24649 50636 25273 50636 24651 50636 24651 50637 25273 50637 25274 50637 24651 50638 25274 50638 24652 50638 24652 50639 25274 50639 23184 50639 24652 50640 23184 50640 23743 50640 24644 50641 23726 50641 23697 50641 23697 50642 23726 50642 25279 50642 25278 50643 25282 50643 24333 50643 24333 50644 24338 50644 25278 50644 25278 50645 24338 50645 24355 50645 25278 50646 24355 50646 24354 50646 25275 50647 25276 50647 23770 50647 23770 50648 25276 50648 25277 50648 23770 50649 25277 50649 24620 50649 24354 50650 25275 50650 25278 50650 25278 50651 25275 50651 23770 50651 25278 50652 23770 50652 23179 50652 23179 50653 23770 50653 23698 50653 23179 50654 23698 50654 23180 50654 23180 50655 23698 50655 23697 50655 23180 50656 23697 50656 23181 50656 23181 50657 23697 50657 25279 50657 23181 50658 25279 50658 25280 50658 25280 50659 25279 50659 23694 50659 25280 50660 23694 50660 23184 50660 23184 50661 23694 50661 23696 50661 23184 50662 23696 50662 23743 50662 24343 50663 25278 50663 25281 50663 25281 50664 25278 50664 23175 50664 25281 50665 23175 50665 24340 50665 24343 50666 24344 50666 25278 50666 25278 50667 24344 50667 25283 50667 25278 50668 25283 50668 25282 50668 25282 50669 25283 50669 24336 50669 25282 50670 24336 50670 24335 50670 23286 50671 25129 50671 23173 50671 23173 50672 25129 50672 23724 50672 23173 50673 23724 50673 25284 50673 25284 50674 23724 50674 23701 50674 25284 50675 23701 50675 23174 50675 23174 50676 23701 50676 25285 50676 23174 50677 25285 50677 23175 50677 23175 50678 25285 50678 23704 50678 23175 50679 23704 50679 24340 50679 25286 50680 25287 50680 25305 50680 24618 50681 24617 50681 24177 50681 25288 50682 25289 50682 24375 50682 25288 50683 24375 50683 23243 50683 23243 50684 24375 50684 24358 50684 23243 50685 24358 50685 25290 50685 25290 50686 25291 50686 23243 50686 23243 50687 25291 50687 24359 50687 23243 50688 24359 50688 24362 50688 25133 50689 23074 50689 24180 50689 24180 50690 23074 50690 25292 50690 24180 50691 25292 50691 25293 50691 25293 50692 25292 50692 23236 50692 25293 50693 23236 50693 24177 50693 24177 50694 23236 50694 23243 50694 24177 50695 23243 50695 24618 50695 24618 50696 23243 50696 24362 50696 24226 50697 24621 50697 25294 50697 25296 50698 23243 50698 24371 50698 24371 50699 23243 50699 25297 50699 24371 50700 25297 50700 24373 50700 24381 50701 25288 50701 24369 50701 24369 50702 25288 50702 23243 50702 24369 50703 23243 50703 25295 50703 25295 50704 23243 50704 25296 50704 24193 50705 24240 50705 24192 50705 24192 50706 24240 50706 24175 50706 25300 50707 24174 50707 23242 50707 23242 50708 24174 50708 24226 50708 23242 50709 24226 50709 25297 50709 25297 50710 24226 50710 25294 50710 25297 50711 25294 50711 24373 50711 24205 50712 24207 50712 25307 50712 25307 50713 24207 50713 25298 50713 25298 50714 24207 50714 25299 50714 25298 50715 25299 50715 23239 50715 23239 50716 25299 50716 24192 50716 23239 50717 24192 50717 25300 50717 25300 50718 24192 50718 24175 50718 25300 50719 24175 50719 24174 50719 25310 50720 24210 50720 25301 50720 25301 50721 24210 50721 25302 50721 25301 50722 25302 50722 23232 50722 23232 50723 25302 50723 24170 50723 23232 50724 24170 50724 25303 50724 25303 50725 24170 50725 25286 50725 25303 50726 25286 50726 25304 50726 25304 50727 25286 50727 25305 50727 25304 50728 25305 50728 23233 50728 23233 50729 25305 50729 24623 50729 23233 50730 24623 50730 25307 50730 25307 50731 24623 50731 25306 50731 25307 50732 25306 50732 24205 50732 25560 50733 24630 50733 25308 50733 25308 50734 24630 50734 25310 50734 25308 50735 25310 50735 25309 50735 25309 50736 25310 50736 25301 50736 25311 50737 23485 50737 23480 50737 23481 50738 25165 50738 23480 50738 23480 50739 25165 50739 23292 50739 23480 50740 23292 50740 25311 50740 25311 50741 23292 50741 23483 50741 23960 50742 23961 50742 25312 50742 23293 50743 23294 50743 23157 50743 23293 50744 23157 50744 25312 50744 23157 50745 25199 50745 25313 50745 23157 50746 25313 50746 25312 50746 25312 50747 25313 50747 25314 50747 25312 50748 25314 50748 23960 50748 23139 50749 23321 50749 25316 50749 23139 50750 25316 50750 25315 50750 25315 50751 25316 50751 23311 50751 25315 50752 23311 50752 23127 50752 25317 50753 23027 50753 23026 50753 25317 50754 23026 50754 25318 50754 25318 50755 23026 50755 25319 50755 25318 50756 25319 50756 23340 50756 25320 50757 25336 50757 25338 50757 25321 50758 25352 50758 25344 50758 25361 50759 25325 50759 23224 50759 23234 50760 25386 50760 25322 50760 23240 50761 25392 50761 23238 50761 25401 50762 25323 50762 23235 50762 26225 50763 25323 50763 25324 50763 25372 50764 25386 50764 26231 50764 25358 50765 25325 50765 23262 50765 23251 50766 25326 50766 25327 50766 23250 50767 23251 50767 25334 50767 23256 50768 23257 50768 25328 50768 25328 50769 26236 50769 23256 50769 23256 50770 26236 50770 23254 50770 23256 50771 23254 50771 25334 50771 25334 50772 23254 50772 25329 50772 25334 50773 25329 50773 23250 50773 23251 50774 25327 50774 25334 50774 25334 50775 25327 50775 23218 50775 25334 50776 23218 50776 25330 50776 25339 50777 25340 50777 23218 50777 23218 50778 25340 50778 25919 50778 23218 50779 25919 50779 25330 50779 25331 50780 25332 50780 25333 50780 25333 50781 25332 50781 23256 50781 25330 50782 25918 50782 25334 50782 25334 50783 25918 50783 25335 50783 25334 50784 25335 50784 23256 50784 23256 50785 25335 50785 23937 50785 23256 50786 23937 50786 25333 50786 25341 50787 25337 50787 25336 50787 25336 50788 25337 50788 23932 50788 25336 50789 23932 50789 25338 50789 25338 50790 23932 50790 25922 50790 25338 50791 25922 50791 25339 50791 25339 50792 25922 50792 25921 50792 25339 50793 25921 50793 25340 50793 23921 50794 23919 50794 23266 50794 25331 50795 25341 50795 25332 50795 25332 50796 25341 50796 25336 50796 25332 50797 25336 50797 25342 50797 25342 50798 25336 50798 23267 50798 23917 50799 25343 50799 25352 50799 25352 50800 25343 50800 23915 50800 25352 50801 23915 50801 25344 50801 25344 50802 23915 50802 23914 50802 25344 50803 23914 50803 25347 50803 23921 50804 23266 50804 25345 50804 25345 50805 23266 50805 23267 50805 25345 50806 23267 50806 25346 50806 25346 50807 23267 50807 25336 50807 25346 50808 25336 50808 25939 50808 25939 50809 25336 50809 25320 50809 25939 50810 25320 50810 25941 50810 23914 50811 25348 50811 25347 50811 25347 50812 25348 50812 25944 50812 25347 50813 25944 50813 25320 50813 25320 50814 25944 50814 25943 50814 25320 50815 25943 50815 25941 50815 23220 50816 25349 50816 25321 50816 25321 50817 25349 50817 25350 50817 25321 50818 25350 50818 25352 50818 25352 50819 25350 50819 25959 50819 25352 50820 25959 50820 25354 50820 23919 50821 23917 50821 23266 50821 23266 50822 23917 50822 25352 50822 23266 50823 25352 50823 25351 50823 25351 50824 25352 50824 25354 50824 23224 50825 25353 50825 23220 50825 23220 50826 25353 50826 25961 50826 23220 50827 25961 50827 25349 50827 25354 50828 23903 50828 25351 50828 25351 50829 23903 50829 25355 50829 25351 50830 25355 50830 25356 50830 25355 50831 23900 50831 25356 50831 25356 50832 23900 50832 25357 50832 25356 50833 25357 50833 25358 50833 25358 50834 25357 50834 25359 50834 25358 50835 25359 50835 25325 50835 25325 50836 25359 50836 23896 50836 25325 50837 23896 50837 23224 50837 23224 50838 23896 50838 25360 50838 23224 50839 25360 50839 25353 50839 25365 50840 25362 50840 25361 50840 25361 50841 25362 50841 25363 50841 25361 50842 25363 50842 25325 50842 25325 50843 25363 50843 25978 50843 25325 50844 25978 50844 23262 50844 25978 50845 25977 50845 23262 50845 23262 50846 25977 50846 23880 50846 23262 50847 23880 50847 25364 50847 23874 50848 23872 50848 23228 50848 23228 50849 23872 50849 23871 50849 23228 50850 23871 50850 25365 50850 25365 50851 23871 50851 25980 50851 25365 50852 25980 50852 25362 50852 23880 50853 23879 50853 25364 50853 25364 50854 23879 50854 23877 50854 25364 50855 23877 50855 23259 50855 23259 50856 23877 50856 25366 50856 25366 50857 25367 50857 23259 50857 23259 50858 25367 50858 25369 50858 23259 50859 25369 50859 25370 50859 23874 50860 23228 50860 25367 50860 25367 50861 23228 50861 23229 50861 25367 50862 23229 50862 25369 50862 23231 50863 25380 50863 23230 50863 23230 50864 25380 50864 25368 50864 23230 50865 25368 50865 25875 50865 25369 50866 23230 50866 25370 50866 25370 50867 23230 50867 25875 50867 25370 50868 25875 50868 26233 50868 26233 50869 25875 50869 25873 50869 26233 50870 25873 50870 26235 50870 26235 50871 25873 50871 25371 50871 26235 50872 25371 50872 25372 50872 25372 50873 25371 50873 25373 50873 25372 50874 25373 50874 25386 50874 24105 50875 25377 50875 25374 50875 25374 50876 25377 50876 25322 50876 25374 50877 25322 50877 25375 50877 25375 50878 25322 50878 25386 50878 25375 50879 25386 50879 24109 50879 24109 50880 25386 50880 25373 50880 24105 50881 25376 50881 25377 50881 25377 50882 25376 50882 25378 50882 25377 50883 25378 50883 23231 50883 23231 50884 25378 50884 25379 50884 23231 50885 25379 50885 25380 50885 23234 50886 25383 50886 24124 50886 25847 50887 25381 50887 25392 50887 25392 50888 25381 50888 25382 50888 25392 50889 25382 50889 23238 50889 23238 50890 25382 50890 25384 50890 23238 50891 25384 50891 25383 50891 25383 50892 25384 50892 25385 50892 25383 50893 25385 50893 24124 50893 24124 50894 24122 50894 23234 50894 23234 50895 24122 50895 25852 50895 23234 50896 25852 50896 25386 50896 25386 50897 25852 50897 25387 50897 25386 50898 25387 50898 26231 50898 26231 50899 25387 50899 25388 50899 26231 50900 25388 50900 25389 50900 25389 50901 25388 50901 25850 50901 25389 50902 25850 50902 25391 50902 25391 50903 25850 50903 25849 50903 25391 50904 25849 50904 25390 50904 25390 50905 25847 50905 25391 50905 25391 50906 25847 50906 25392 50906 25391 50907 25392 50907 26228 50907 26228 50908 25392 50908 25394 50908 23241 50909 24146 50909 23240 50909 23240 50910 24146 50910 24145 50910 23240 50911 24145 50911 25392 50911 25392 50912 24145 50912 25393 50912 25392 50913 25393 50913 25394 50913 24151 50914 23235 50914 24152 50914 24152 50915 23235 50915 25323 50915 24152 50916 25323 50916 25828 50916 25828 50917 25323 50917 26225 50917 25828 50918 26225 50918 25830 50918 25830 50919 26225 50919 26229 50919 25830 50920 26229 50920 25832 50920 25832 50921 26229 50921 26228 50921 25832 50922 26228 50922 25835 50922 25835 50923 26228 50923 25394 50923 24151 50924 24150 50924 23235 50924 23235 50925 24150 50925 25395 50925 23235 50926 25395 50926 23241 50926 23241 50927 25395 50927 24148 50927 23241 50928 24148 50928 24146 50928 25805 50929 24168 50929 25396 50929 25396 50930 24168 50930 24167 50930 25396 50931 24167 50931 25398 50931 25806 50932 25403 50932 25807 50932 25807 50933 25403 50933 25324 50933 25807 50934 25324 50934 25397 50934 25398 50935 25399 50935 25396 50935 25396 50936 25399 50936 24166 50936 25396 50937 24166 50937 23237 50937 23237 50938 24166 50938 25400 50938 23237 50939 25400 50939 25401 50939 25401 50940 25400 50940 25402 50940 25401 50941 25402 50941 25323 50941 25323 50942 25402 50942 25810 50942 25323 50943 25810 50943 25324 50943 25324 50944 25810 50944 25809 50944 25324 50945 25809 50945 25397 50945 26240 50946 26242 50946 26238 50946 26238 50947 26242 50947 25403 50947 26238 50948 25403 50948 23253 50948 23253 50949 25403 50949 25404 50949 23244 50950 23245 50950 23247 50950 25806 50951 25805 50951 25403 50951 25403 50952 25805 50952 25396 50952 25403 50953 25396 50953 25404 50953 25404 50954 25396 50954 23244 50954 25404 50955 23244 50955 25405 50955 25405 50956 23244 50956 23247 50956 23177 50957 25434 50957 23176 50957 23182 50958 25406 50958 25431 50958 25407 50959 25448 50959 23183 50959 25409 50960 25408 50960 25464 50960 25408 50961 25409 50961 25466 50961 26250 50962 25412 50962 26249 50962 25410 50963 25471 50963 26254 50963 26257 50964 25489 50964 25488 50964 25487 50965 25489 50965 23203 50965 25411 50966 25412 50966 25475 50966 25447 50967 25448 50967 25461 50967 25444 50968 26024 50968 25406 50968 25416 50969 23691 50969 25413 50969 25413 50970 23691 50970 25414 50970 26000 50971 25415 50971 25414 50971 25414 50972 25415 50972 23196 50972 25414 50973 23196 50973 25413 50973 26003 50974 25425 50974 25421 50974 25421 50975 25425 50975 25434 50975 25421 50976 25434 50976 23216 50976 25416 50977 23193 50977 23691 50977 23691 50978 23193 50978 25417 50978 23691 50979 25417 50979 25418 50979 25418 50980 25417 50980 25419 50980 25418 50981 25419 50981 25420 50981 25420 50982 25419 50982 25428 50982 25420 50983 25428 50983 23686 50983 26003 50984 25421 50984 25422 50984 25422 50985 25421 50985 25423 50985 25422 50986 25423 50986 26000 50986 26000 50987 25423 50987 25424 50987 26000 50988 25424 50988 25415 50988 25425 50989 26005 50989 25434 50989 25434 50990 26005 50990 25426 50990 25434 50991 25426 50991 23176 50991 23176 50992 25426 50992 25427 50992 23176 50993 25427 50993 25428 50993 25428 50994 25427 50994 23683 50994 25428 50995 23683 50995 23686 50995 25431 50996 23657 50996 23178 50996 23178 50997 23657 50997 25429 50997 23178 50998 25429 50998 23177 50998 26024 50999 25430 50999 25406 50999 25406 51000 25430 51000 25432 51000 25406 51001 25432 51001 25431 51001 25431 51002 25432 51002 26021 51002 25431 51003 26021 51003 23657 51003 25429 51004 25433 51004 23177 51004 23177 51005 25433 51005 23655 51005 23177 51006 23655 51006 25434 51006 25434 51007 23655 51007 25435 51007 25434 51008 25435 51008 23216 51008 23216 51009 25435 51009 23652 51009 23216 51010 23652 51010 25436 51010 25436 51011 23652 51011 25437 51011 25436 51012 25437 51012 25443 51012 25443 51013 25437 51013 26025 51013 25406 51014 25438 51014 25450 51014 25438 51015 25406 51015 25439 51015 25439 51016 25406 51016 23182 51016 25439 51017 23182 51017 23640 51017 23640 51018 23182 51018 25440 51018 23640 51019 25440 51019 25441 51019 25441 51020 25440 51020 23183 51020 25441 51021 23183 51021 25442 51021 26025 51022 25444 51022 25443 51022 25443 51023 25444 51023 25406 51023 25443 51024 25406 51024 25445 51024 25445 51025 25406 51025 25450 51025 23213 51026 25446 51026 25447 51026 25447 51027 25446 51027 26046 51027 25447 51028 26046 51028 25448 51028 25448 51029 26046 51029 25449 51029 25448 51030 25449 51030 23183 51030 23183 51031 25449 51031 26044 51031 23183 51032 26044 51032 25442 51032 25450 51033 26049 51033 25445 51033 25445 51034 26049 51034 25451 51034 25445 51035 25451 51035 23213 51035 23213 51036 25451 51036 26047 51036 23213 51037 26047 51037 25446 51037 23211 51038 25452 51038 25453 51038 25453 51039 25452 51039 25454 51039 25453 51040 25454 51040 23210 51040 26068 51041 25456 51041 26069 51041 26069 51042 25456 51042 25464 51042 26069 51043 25464 51043 25454 51043 25461 51044 23616 51044 23211 51044 23211 51045 23616 51045 25455 51045 23211 51046 25455 51046 25452 51046 26068 51047 23623 51047 25456 51047 25456 51048 23623 51048 25457 51048 25456 51049 25457 51049 25458 51049 25457 51050 23621 51050 25458 51050 25458 51051 23621 51051 25459 51051 25458 51052 25459 51052 25407 51052 25407 51053 25459 51053 23619 51053 25407 51054 23619 51054 25448 51054 25448 51055 23619 51055 25460 51055 25448 51056 25460 51056 25461 51056 25461 51057 25460 51057 23617 51057 25461 51058 23617 51058 23616 51058 25462 51059 26193 51059 26245 51059 26245 51060 26193 51060 26196 51060 26245 51061 26196 51061 26247 51061 26249 51062 25412 51062 26245 51062 26245 51063 25412 51063 26191 51063 26245 51064 26191 51064 25462 51064 25411 51065 25463 51065 25412 51065 25412 51066 25463 51066 26190 51066 25412 51067 26190 51067 26191 51067 25454 51068 25464 51068 23210 51068 23210 51069 25464 51069 25408 51069 23210 51070 25408 51070 23208 51070 26196 51071 26195 51071 26247 51071 26247 51072 26195 51072 25465 51072 26247 51073 25465 51073 25466 51073 25466 51074 25465 51074 23372 51074 25466 51075 23372 51075 25408 51075 25408 51076 23372 51076 23373 51076 25408 51077 23373 51077 23208 51077 23208 51078 23373 51078 23374 51078 23208 51079 23374 51079 25467 51079 25467 51080 23374 51080 23375 51080 25467 51081 23375 51081 25411 51081 25411 51082 23375 51082 25468 51082 25411 51083 25468 51083 25463 51083 25473 51084 26250 51084 25469 51084 25483 51085 25470 51085 25471 51085 25471 51086 25470 51086 25472 51086 25471 51087 25472 51087 26254 51087 26254 51088 25472 51088 26174 51088 26254 51089 26174 51089 25469 51089 25469 51090 26174 51090 26172 51090 25469 51091 26172 51091 25473 51091 25473 51092 25474 51092 26250 51092 26250 51093 25474 51093 23401 51093 26250 51094 23401 51094 25412 51094 25412 51095 23401 51095 23402 51095 25412 51096 23402 51096 25475 51096 25475 51097 23402 51097 25476 51097 25475 51098 25476 51098 25477 51098 25477 51099 25476 51099 25478 51099 25477 51100 25478 51100 25482 51100 25482 51101 25478 51101 23405 51101 25482 51102 23405 51102 25479 51102 25488 51103 26154 51103 26256 51103 26256 51104 26154 51104 25480 51104 26256 51105 25480 51105 25410 51105 25480 51106 26151 51106 25410 51106 25410 51107 26151 51107 25481 51107 25410 51108 25481 51108 25471 51108 25471 51109 25481 51109 23429 51109 25471 51110 23429 51110 23428 51110 25479 51111 25483 51111 25482 51111 25482 51112 25483 51112 25471 51112 25482 51113 25471 51113 25484 51113 25484 51114 25471 51114 23428 51114 23428 51115 23426 51115 25484 51115 25484 51116 23426 51116 23423 51116 25484 51117 23423 51117 25486 51117 23423 51118 25485 51118 25486 51118 25486 51119 25485 51119 23422 51119 25486 51120 23422 51120 25487 51120 25487 51121 23422 51121 26158 51121 25487 51122 26158 51122 25489 51122 25489 51123 26158 51123 26157 51123 25489 51124 26157 51124 25488 51124 25488 51125 26157 51125 26155 51125 25488 51126 26155 51126 26154 51126 26259 51127 26134 51127 26257 51127 26257 51128 26134 51128 23454 51128 26257 51129 23454 51129 25489 51129 25489 51130 23454 51130 25490 51130 25489 51131 25490 51131 23203 51131 25490 51132 23452 51132 23203 51132 23203 51133 23452 51133 23449 51133 23203 51134 23449 51134 25491 51134 25491 51135 23449 51135 23448 51135 25491 51136 23448 51136 23198 51136 23198 51137 23448 51137 25492 51137 23198 51138 25492 51138 25494 51138 25494 51139 25492 51139 25493 51139 26124 51140 26126 51140 25496 51140 25496 51141 26126 51141 26128 51141 25496 51142 26128 51142 26259 51142 26259 51143 26128 51143 26130 51143 26259 51144 26130 51144 26134 51144 26122 51145 25497 51145 25493 51145 25493 51146 25497 51146 23197 51146 25493 51147 23197 51147 25494 51147 25495 51148 25497 51148 25496 51148 25496 51149 25497 51149 26122 51149 25496 51150 26122 51150 26124 51150 25495 51151 25498 51151 25497 51151 25497 51152 25498 51152 23190 51152 25497 51153 23190 51153 25499 51153 25500 51154 25077 51154 25519 51154 25501 51155 25502 51155 25529 51155 25503 51156 23001 51156 25504 51156 25503 51157 25504 51157 25527 51157 23001 51158 25503 51158 23003 51158 23003 51159 25503 51159 25505 51159 23003 51160 25505 51160 23004 51160 23004 51161 25505 51161 25506 51161 25506 51162 25505 51162 24556 51162 25506 51163 24556 51163 23005 51163 23005 51164 24556 51164 25508 51164 25508 51165 24556 51165 25507 51165 25508 51166 25507 51166 25509 51166 24488 51167 25516 51167 24485 51167 24485 51168 25516 51168 25510 51168 24485 51169 25510 51169 25511 51169 25512 51170 23041 51170 24510 51170 24510 51171 23041 51171 24508 51171 24508 51172 23041 51172 23044 51172 24508 51173 23044 51173 25513 51173 25513 51174 23044 51174 25514 51174 25513 51175 25514 51175 24488 51175 24488 51176 25514 51176 25515 51176 24488 51177 25515 51177 25516 51177 25510 51178 25517 51178 25511 51178 25511 51179 25517 51179 25500 51179 25511 51180 25500 51180 25518 51180 25518 51181 25500 51181 25519 51181 25518 51182 25519 51182 25520 51182 25520 51183 25519 51183 25521 51183 25520 51184 25521 51184 24483 51184 24483 51185 25521 51185 25063 51185 24483 51186 25063 51186 25522 51186 25522 51187 25063 51187 25064 51187 25522 51188 25064 51188 25523 51188 25523 51189 25064 51189 25066 51189 25523 51190 25066 51190 24482 51190 24482 51191 25066 51191 25067 51191 24482 51192 25067 51192 24571 51192 24571 51193 25067 51193 25068 51193 24571 51194 25068 51194 25524 51194 25524 51195 25068 51195 25070 51195 25524 51196 25070 51196 24478 51196 24478 51197 25070 51197 25071 51197 24478 51198 25071 51198 24477 51198 24477 51199 25071 51199 25525 51199 24477 51200 25525 51200 24580 51200 24580 51201 25525 51201 25526 51201 24580 51202 25526 51202 25507 51202 25507 51203 25526 51203 25062 51203 25507 51204 25062 51204 25509 51204 25504 51205 25501 51205 25527 51205 25527 51206 25501 51206 25529 51206 25527 51207 25529 51207 25528 51207 25528 51208 25529 51208 25530 51208 25528 51209 25530 51209 25531 51209 25531 51210 25530 51210 25532 51210 25531 51211 25532 51211 24473 51211 24473 51212 25532 51212 25103 51212 24473 51213 25103 51213 25533 51213 25533 51214 25103 51214 25534 51214 25533 51215 25534 51215 24468 51215 24468 51216 25534 51216 25535 51216 24468 51217 25535 51217 24467 51217 24467 51218 25535 51218 25536 51218 24467 51219 25536 51219 24496 51219 24496 51220 25536 51220 25097 51220 24496 51221 25097 51221 25537 51221 25537 51222 25097 51222 25538 51222 25537 51223 25538 51223 24493 51223 24493 51224 25538 51224 25539 51224 24493 51225 25539 51225 24595 51225 24595 51226 25539 51226 25087 51226 24595 51227 25087 51227 25540 51227 25540 51228 25087 51228 25089 51228 25540 51229 25089 51229 24510 51229 24510 51230 25089 51230 25085 51230 24510 51231 25085 51231 25512 51231 25561 51232 24634 51232 24633 51232 25556 51233 25541 51233 25542 51233 25563 51234 25543 51234 23226 51234 25542 51235 25541 51235 25543 51235 25543 51236 25541 51236 23227 51236 25543 51237 23227 51237 23226 51237 25544 51238 25545 51238 23941 51238 23941 51239 25545 51239 23221 51239 23941 51240 23221 51240 25548 51240 23994 51241 25547 51241 25546 51241 25546 51242 25547 51242 25548 51242 25548 51243 23221 51243 25546 51243 25546 51244 23221 51244 23222 51244 25546 51245 23222 51245 23946 51245 23946 51246 23222 51246 23223 51246 23946 51247 23223 51247 25549 51247 25549 51248 23223 51248 25551 51248 25549 51249 25551 51249 25550 51249 25555 51250 25553 51250 23219 51250 25550 51251 25551 51251 24641 51251 24641 51252 25551 51252 25553 51252 24641 51253 25553 51253 25552 51253 25552 51254 25553 51254 25555 51254 25552 51255 25555 51255 23950 51255 25312 51256 23961 51256 25554 51256 25554 51257 23961 51257 23959 51257 25554 51258 23959 51258 23219 51258 23219 51259 23959 51259 23947 51259 23219 51260 23947 51260 25555 51260 25712 51261 24630 51261 25560 51261 25542 51262 23938 51262 25556 51262 25556 51263 23938 51263 25557 51263 25556 51264 25557 51264 25558 51264 25558 51265 25557 51265 25712 51265 25558 51266 25712 51266 25559 51266 25559 51267 25712 51267 25560 51267 23941 51268 25561 51268 25544 51268 25544 51269 25561 51269 24633 51269 25544 51270 24633 51270 23225 51270 23225 51271 24633 51271 24635 51271 23225 51272 24635 51272 23226 51272 23226 51273 24635 51273 25562 51273 23226 51274 25562 51274 25563 51274 25096 51275 23258 51275 25564 51275 25564 51276 23258 51276 26232 51276 25564 51277 26232 51277 25098 51277 25098 51278 26232 51278 26234 51278 25098 51279 26234 51279 25565 51279 25565 51280 26234 51280 26230 51280 25565 51281 26230 51281 25086 51281 25086 51282 26230 51282 25566 51282 25086 51283 25566 51283 25088 51283 25088 51284 25566 51284 26226 51284 25088 51285 26226 51285 25090 51285 25090 51286 26226 51286 26227 51286 25090 51287 26227 51287 25567 51287 25567 51288 26227 51288 26224 51288 25567 51289 26224 51289 23271 51289 23271 51290 26224 51290 23270 51290 25568 51291 24825 51291 25032 51291 25032 51292 24825 51292 25709 51292 24825 51293 25569 51293 25709 51293 25709 51294 25569 51294 25570 51294 25709 51295 25570 51295 25571 51295 25570 51296 24828 51296 25571 51296 25571 51297 24828 51297 24835 51297 25571 51298 24835 51298 25708 51298 24835 51299 24834 51299 25708 51299 25708 51300 24834 51300 24833 51300 25708 51301 24833 51301 25572 51301 25572 51302 24833 51302 24829 51302 24829 51303 24839 51303 25572 51303 25572 51304 24839 51304 24845 51304 25572 51305 24845 51305 25705 51305 24845 51306 24844 51306 25705 51306 25705 51307 24844 51307 25573 51307 25705 51308 25573 51308 25574 51308 25573 51309 25575 51309 25574 51309 25574 51310 25575 51310 24848 51310 25574 51311 24848 51311 25576 51311 25576 51312 24848 51312 25578 51312 23154 51313 25577 51313 24851 51313 24851 51314 25577 51314 25576 51314 24851 51315 25576 51315 24849 51315 24849 51316 25576 51316 25578 51316 25741 51317 25664 51317 25667 51317 25579 51318 25638 51318 25590 51318 25656 51319 25595 51319 25580 51319 25630 51320 25593 51320 25597 51320 25581 51321 25582 51321 25673 51321 25668 51322 25581 51322 25583 51322 24611 51323 25668 51323 25669 51323 25584 51324 24611 51324 25660 51324 25600 51325 25584 51325 25662 51325 25598 51326 25585 51326 25634 51326 24990 51327 24988 51327 25620 51327 23109 51328 24603 51328 25643 51328 25586 51329 25646 51329 23113 51329 23113 51330 25646 51330 25589 51330 25586 51331 25587 51331 25646 51331 25646 51332 25587 51332 23116 51332 25646 51333 23116 51333 25645 51333 25645 51334 23116 51334 23117 51334 25640 51335 25588 51335 25589 51335 25589 51336 25588 51336 23126 51336 25589 51337 23126 51337 23113 51337 25591 51338 23138 51338 25590 51338 25590 51339 23138 51339 23124 51339 25590 51340 23124 51340 25640 51340 25640 51341 23124 51341 23125 51341 25640 51342 23125 51342 25588 51342 23135 51343 23133 51343 25591 51343 25591 51344 23133 51344 25592 51344 25591 51345 25592 51345 23138 51345 25585 51346 23143 51346 23135 51346 24984 51347 25593 51347 24985 51347 24985 51348 25593 51348 25630 51348 24985 51349 25630 51349 25594 51349 24615 51350 25595 51350 25596 51350 25596 51351 25595 51351 25656 51351 25596 51352 25656 51352 24601 51352 25632 51353 25597 51353 25636 51353 25636 51354 25597 51354 25593 51354 25636 51355 25593 51355 25635 51355 25635 51356 25593 51356 24984 51356 25635 51357 24984 51357 25598 51357 25657 51358 25580 51358 25599 51358 25599 51359 25580 51359 25595 51359 25599 51360 25595 51360 25658 51360 25658 51361 25595 51361 24615 51361 25658 51362 24615 51362 25600 51362 25603 51363 25625 51363 25621 51363 25720 51364 25601 51364 25627 51364 25627 51365 25601 51365 25603 51365 25627 51366 25603 51366 25602 51366 25602 51367 25603 51367 25621 51367 25602 51368 25621 51368 25619 51368 25626 51369 25609 51369 25605 51369 25605 51370 25609 51370 25604 51370 25605 51371 25604 51371 25606 51371 25606 51372 25604 51372 25608 51372 25606 51373 25608 51373 25607 51373 25607 51374 25608 51374 25611 51374 25609 51375 24986 51375 25604 51375 25604 51376 24986 51376 25610 51376 25604 51377 25610 51377 25608 51377 25608 51378 25610 51378 25612 51378 25608 51379 25612 51379 25611 51379 25611 51380 25612 51380 25631 51380 25611 51381 25631 51381 25723 51381 25723 51382 25631 51382 25725 51382 25653 51383 25654 51383 25613 51383 25737 51384 25614 51384 25615 51384 25615 51385 25614 51385 25653 51385 25615 51386 25653 51386 25655 51386 25655 51387 25653 51387 25613 51387 25655 51388 25613 51388 25648 51388 24990 51389 25620 51389 25616 51389 25616 51390 25620 51390 25622 51390 25616 51391 25622 51391 24968 51391 24968 51392 25622 51392 25623 51392 24968 51393 25623 51393 25617 51393 25617 51394 25623 51394 25718 51394 25617 51395 25718 51395 25618 51395 24988 51396 25619 51396 25620 51396 25620 51397 25619 51397 25621 51397 25620 51398 25621 51398 25622 51398 25622 51399 25621 51399 25625 51399 25622 51400 25625 51400 25623 51400 25623 51401 25625 51401 25624 51401 25623 51402 25624 51402 25718 51402 25601 51403 25719 51403 25603 51403 25603 51404 25719 51404 25715 51404 25603 51405 25715 51405 25625 51405 25625 51406 25715 51406 25717 51406 25625 51407 25717 51407 25624 51407 24988 51408 25626 51408 25619 51408 25619 51409 25626 51409 25605 51409 25619 51410 25605 51410 25602 51410 25602 51411 25605 51411 25606 51411 25602 51412 25606 51412 25627 51412 25627 51413 25606 51413 25607 51413 25627 51414 25607 51414 25720 51414 25723 51415 25722 51415 25611 51415 25611 51416 25722 51416 25628 51416 25611 51417 25628 51417 25607 51417 25607 51418 25628 51418 25629 51418 25607 51419 25629 51419 25720 51419 24986 51420 25594 51420 25610 51420 25610 51421 25594 51421 25630 51421 25610 51422 25630 51422 25612 51422 25612 51423 25630 51423 25597 51423 25612 51424 25597 51424 25631 51424 25631 51425 25597 51425 25632 51425 25631 51426 25632 51426 25725 51426 25725 51427 25632 51427 25726 51427 25633 51428 25729 51428 25730 51428 25598 51429 25634 51429 25635 51429 25635 51430 25634 51430 25637 51430 25635 51431 25637 51431 25636 51431 25636 51432 25637 51432 25633 51432 25636 51433 25633 51433 25632 51433 25632 51434 25633 51434 25730 51434 25632 51435 25730 51435 25726 51435 25585 51436 23135 51436 25634 51436 25634 51437 23135 51437 25591 51437 25634 51438 25591 51438 25637 51438 25637 51439 25591 51439 25590 51439 25637 51440 25590 51440 25633 51440 25633 51441 25590 51441 25638 51441 25633 51442 25638 51442 25729 51442 25579 51443 25590 51443 25639 51443 25639 51444 25590 51444 25640 51444 25639 51445 25640 51445 25641 51445 25641 51446 25640 51446 25589 51446 25641 51447 25589 51447 25642 51447 25642 51448 25589 51448 25733 51448 25733 51449 25589 51449 25646 51449 25733 51450 25646 51450 25647 51450 23109 51451 25643 51451 23117 51451 23117 51452 25643 51452 25644 51452 23117 51453 25644 51453 25645 51453 25645 51454 25644 51454 25649 51454 25645 51455 25649 51455 25646 51455 25646 51456 25649 51456 25651 51456 25646 51457 25651 51457 25647 51457 24603 51458 25648 51458 25643 51458 25643 51459 25648 51459 25613 51459 25643 51460 25613 51460 25644 51460 25644 51461 25613 51461 25654 51461 25644 51462 25654 51462 25649 51462 25649 51463 25654 51463 25650 51463 25649 51464 25650 51464 25651 51464 25614 51465 25652 51465 25653 51465 25653 51466 25652 51466 25736 51466 25653 51467 25736 51467 25654 51467 25654 51468 25736 51468 25734 51468 25654 51469 25734 51469 25650 51469 24603 51470 24601 51470 25648 51470 25648 51471 24601 51471 25656 51471 25648 51472 25656 51472 25655 51472 25655 51473 25656 51473 25580 51473 25655 51474 25580 51474 25615 51474 25615 51475 25580 51475 25657 51475 25615 51476 25657 51476 25737 51476 25737 51477 25657 51477 25738 51477 25665 51478 25739 51478 25659 51478 25600 51479 25662 51479 25658 51479 25658 51480 25662 51480 25663 51480 25658 51481 25663 51481 25599 51481 25599 51482 25663 51482 25665 51482 25599 51483 25665 51483 25657 51483 25657 51484 25665 51484 25659 51484 25657 51485 25659 51485 25738 51485 25584 51486 25660 51486 25662 51486 25662 51487 25660 51487 25661 51487 25662 51488 25661 51488 25663 51488 25663 51489 25661 51489 25667 51489 25663 51490 25667 51490 25665 51490 25665 51491 25667 51491 25664 51491 25665 51492 25664 51492 25739 51492 24611 51493 25669 51493 25660 51493 25660 51494 25669 51494 25670 51494 25660 51495 25670 51495 25661 51495 25661 51496 25670 51496 25666 51496 25661 51497 25666 51497 25667 51497 25667 51498 25666 51498 25742 51498 25667 51499 25742 51499 25741 51499 25671 51500 25743 51500 25672 51500 25668 51501 25583 51501 25669 51501 25669 51502 25583 51502 25674 51502 25669 51503 25674 51503 25670 51503 25670 51504 25674 51504 25671 51504 25670 51505 25671 51505 25666 51505 25666 51506 25671 51506 25672 51506 25666 51507 25672 51507 25742 51507 25581 51508 25673 51508 25583 51508 25583 51509 25673 51509 25675 51509 25583 51510 25675 51510 25674 51510 25674 51511 25675 51511 25676 51511 25674 51512 25676 51512 25671 51512 25671 51513 25676 51513 25745 51513 25671 51514 25745 51514 25743 51514 25690 51515 25677 51515 25689 51515 25678 51516 25677 51516 25222 51516 25222 51517 25677 51517 25690 51517 25222 51518 25690 51518 25691 51518 25232 51519 25679 51519 25231 51519 25231 51520 25679 51520 25680 51520 25231 51521 25680 51521 25211 51521 25211 51522 25680 51522 25685 51522 25211 51523 25685 51523 25681 51523 25681 51524 25685 51524 25682 51524 25681 51525 25682 51525 25227 51525 25227 51526 25682 51526 25683 51526 25227 51527 25683 51527 25221 51527 25221 51528 25683 51528 25686 51528 25221 51529 25686 51529 25678 51529 25688 51530 25684 51530 25783 51530 25680 51531 25700 51531 25685 51531 25685 51532 25700 51532 25699 51532 25685 51533 25699 51533 25682 51533 25682 51534 25699 51534 25697 51534 25682 51535 25697 51535 25683 51535 25683 51536 25697 51536 25687 51536 25683 51537 25687 51537 25686 51537 25686 51538 25687 51538 25696 51538 25027 51539 25684 51539 25026 51539 25026 51540 25684 51540 25688 51540 25026 51541 25688 51541 25025 51541 25694 51542 25025 51542 25689 51542 25689 51543 25025 51543 25688 51543 25689 51544 25688 51544 25690 51544 25690 51545 25688 51545 25783 51545 25690 51546 25783 51546 25691 51546 25696 51547 25692 51547 25693 51547 25678 51548 25686 51548 25677 51548 25677 51549 25686 51549 25696 51549 25677 51550 25696 51550 25689 51550 25689 51551 25696 51551 25693 51551 25689 51552 25693 51552 25694 51552 25692 51553 25696 51553 25695 51553 25695 51554 25696 51554 25687 51554 25695 51555 25687 51555 25029 51555 25029 51556 25687 51556 25697 51556 25029 51557 25697 51557 25030 51557 25030 51558 25697 51558 25699 51558 25030 51559 25699 51559 25031 51559 25679 51560 24807 51560 25680 51560 25680 51561 24807 51561 24826 51561 25680 51562 24826 51562 25700 51562 25700 51563 24826 51563 25698 51563 25700 51564 25698 51564 24817 51564 25031 51565 25699 51565 25035 51565 25035 51566 25699 51566 25700 51566 25035 51567 25700 51567 25033 51567 25033 51568 25700 51568 24817 51568 25033 51569 24817 51569 25568 51569 25703 51570 25701 51570 24982 51570 25577 51571 25702 51571 25576 51571 25576 51572 25702 51572 25703 51572 25703 51573 24982 51573 25576 51573 25576 51574 24982 51574 24983 51574 25576 51575 24983 51575 25574 51575 25574 51576 24983 51576 25704 51576 25574 51577 25704 51577 25705 51577 25705 51578 25704 51578 25706 51578 25705 51579 25706 51579 25572 51579 25572 51580 25706 51580 25707 51580 25572 51581 25707 51581 25708 51581 25708 51582 25707 51582 24987 51582 25708 51583 24987 51583 25571 51583 25571 51584 24987 51584 25710 51584 25571 51585 25710 51585 25709 51585 25709 51586 25710 51586 24706 51586 25709 51587 24706 51587 25032 51587 25713 51588 25213 51588 25714 51588 25557 51589 25711 51589 25712 51589 25712 51590 25711 51590 25713 51590 25713 51591 25714 51591 25712 51591 25712 51592 25714 51592 25230 51592 25712 51593 25230 51593 24630 51593 25718 51594 25716 51594 25776 51594 25715 51595 26393 51595 25717 51595 25717 51596 26393 51596 25716 51596 25717 51597 25716 51597 25624 51597 25624 51598 25716 51598 25718 51598 25715 51599 25719 51599 26393 51599 26393 51600 25719 51600 25601 51600 26393 51601 25601 51601 25721 51601 25628 51602 26392 51602 25629 51602 25629 51603 26392 51603 25721 51603 25629 51604 25721 51604 25720 51604 25720 51605 25721 51605 25601 51605 25628 51606 25722 51606 26392 51606 26392 51607 25722 51607 25723 51607 26392 51608 25723 51608 25724 51608 25723 51609 25725 51609 25724 51609 25724 51610 25725 51610 25726 51610 25724 51611 25726 51611 25727 51611 25638 51612 25728 51612 25729 51612 25729 51613 25728 51613 25727 51613 25729 51614 25727 51614 25730 51614 25730 51615 25727 51615 25726 51615 25638 51616 25579 51616 25728 51616 25728 51617 25579 51617 25639 51617 25728 51618 25639 51618 26390 51618 25639 51619 25641 51619 26390 51619 26390 51620 25641 51620 25642 51620 26390 51621 25642 51621 25731 51621 25651 51622 25732 51622 25647 51622 25647 51623 25732 51623 25731 51623 25647 51624 25731 51624 25733 51624 25733 51625 25731 51625 25642 51625 25651 51626 25650 51626 25732 51626 25732 51627 25650 51627 25734 51627 25732 51628 25734 51628 26389 51628 25614 51629 25735 51629 25652 51629 25652 51630 25735 51630 26389 51630 25652 51631 26389 51631 25736 51631 25736 51632 26389 51632 25734 51632 25614 51633 25737 51633 25735 51633 25735 51634 25737 51634 25738 51634 25735 51635 25738 51635 25740 51635 25664 51636 26388 51636 25739 51636 25739 51637 26388 51637 25740 51637 25739 51638 25740 51638 25659 51638 25659 51639 25740 51639 25738 51639 25664 51640 25741 51640 26388 51640 26388 51641 25741 51641 25742 51641 26388 51642 25742 51642 25744 51642 25742 51643 25672 51643 25744 51643 25744 51644 25672 51644 25743 51644 25744 51645 25743 51645 26387 51645 25743 51646 25745 51646 26387 51646 26387 51647 25745 51647 25746 51647 26387 51648 25746 51648 26398 51648 25746 51649 24911 51649 26398 51649 26398 51650 24911 51650 25747 51650 26398 51651 25747 51651 25748 51651 24912 51652 25751 51652 25749 51652 25749 51653 25751 51653 25748 51653 25749 51654 25748 51654 24913 51654 24913 51655 25748 51655 25747 51655 24920 51656 25754 51656 25750 51656 25750 51657 25754 51657 25751 51657 25750 51658 25751 51658 25752 51658 25752 51659 25751 51659 24912 51659 24920 51660 25753 51660 25754 51660 25754 51661 25753 51661 25755 51661 25754 51662 25755 51662 25757 51662 25758 51663 26397 51663 24926 51663 24926 51664 26397 51664 25757 51664 24926 51665 25757 51665 25756 51665 25756 51666 25757 51666 25755 51666 25758 51667 25759 51667 26397 51667 26397 51668 25759 51668 25760 51668 26397 51669 25760 51669 25763 51669 25760 51670 25761 51670 25763 51670 25763 51671 25761 51671 25762 51671 25763 51672 25762 51672 26396 51672 25766 51673 25765 51673 25764 51673 25764 51674 25765 51674 26396 51674 25764 51675 26396 51675 24932 51675 24932 51676 26396 51676 25762 51676 25766 51677 24938 51677 25765 51677 25765 51678 24938 51678 24937 51678 25765 51679 24937 51679 26394 51679 24943 51680 25769 51680 24945 51680 24945 51681 25769 51681 26394 51681 24945 51682 26394 51682 25767 51682 25767 51683 26394 51683 24937 51683 24943 51684 24941 51684 25769 51684 25769 51685 24941 51685 25768 51685 25769 51686 25768 51686 26395 51686 25768 51687 24951 51687 26395 51687 26395 51688 24951 51688 25770 51688 26395 51689 25770 51689 25771 51689 25772 51690 25774 51690 25773 51690 25773 51691 25774 51691 25771 51691 25773 51692 25771 51692 24952 51692 24952 51693 25771 51693 25770 51693 25772 51694 24877 51694 25774 51694 25774 51695 24877 51695 24966 51695 25774 51696 24966 51696 25775 51696 24966 51697 24965 51697 25775 51697 25775 51698 24965 51698 24969 51698 25775 51699 24969 51699 25776 51699 25776 51700 24969 51700 25618 51700 25776 51701 25618 51701 25718 51701 25777 51702 24427 51702 25787 51702 25777 51703 25787 51703 24350 51703 24350 51704 25787 51704 25791 51704 24350 51705 25791 51705 25778 51705 25684 51706 25027 51706 25779 51706 24459 51707 24438 51707 24460 51707 24460 51708 24438 51708 25781 51708 24460 51709 25781 51709 25780 51709 25780 51710 25781 51710 25779 51710 24438 51711 24439 51711 25781 51711 25781 51712 24439 51712 24441 51712 25781 51713 24441 51713 25782 51713 25779 51714 25781 51714 25684 51714 25684 51715 25781 51715 25782 51715 25684 51716 25782 51716 25783 51716 25783 51717 25782 51717 25785 51717 25783 51718 25785 51718 25691 51718 25784 51719 25785 51719 25786 51719 25786 51720 25785 51720 25782 51720 25786 51721 25782 51721 24440 51721 24440 51722 25782 51722 24441 51722 24427 51723 25788 51723 25787 51723 25787 51724 25788 51724 25789 51724 25787 51725 25789 51725 25791 51725 25788 51726 25790 51726 25789 51726 25789 51727 25790 51727 24431 51727 25789 51728 24431 51728 25792 51728 25791 51729 25789 51729 24423 51729 24423 51730 25789 51730 25792 51730 24423 51731 25792 51731 25793 51731 25793 51732 25792 51732 25155 51732 25793 51733 25155 51733 25162 51733 25794 51734 25155 51734 25795 51734 25795 51735 25155 51735 25792 51735 25795 51736 25792 51736 25796 51736 25796 51737 25792 51737 24431 51737 24979 51738 24378 51738 25797 51738 24457 51739 24365 51739 25798 51739 25798 51740 24365 51740 24979 51740 25798 51741 24979 51741 24455 51741 24455 51742 24979 51742 25797 51742 25207 51743 25206 51743 24225 51743 24269 51744 25208 51744 25799 51744 25799 51745 25208 51745 25207 51745 25799 51746 25207 51746 24268 51746 24268 51747 25207 51747 24225 51747 24216 51748 24215 51748 24293 51748 24293 51749 24215 51749 25228 51749 24293 51750 25228 51750 24291 51750 24291 51751 25228 51751 25800 51751 24291 51752 25800 51752 24218 51752 24218 51753 25800 51753 25237 51753 24247 51754 25215 51754 24246 51754 24246 51755 25215 51755 25801 51755 24246 51756 25801 51756 24196 51756 24196 51757 25801 51757 24197 51757 25802 51758 25145 51758 24324 51758 24324 51759 25145 51759 25803 51759 25818 51760 24168 51760 25804 51760 25804 51761 24168 51761 25805 51761 25804 51762 25805 51762 25817 51762 25817 51763 25805 51763 25806 51763 25817 51764 25806 51764 25816 51764 25816 51765 25806 51765 25807 51765 25816 51766 25807 51766 25815 51766 25815 51767 25807 51767 25397 51767 25815 51768 25397 51768 25808 51768 25808 51769 25397 51769 25809 51769 25808 51770 25809 51770 25813 51770 25813 51771 25809 51771 25810 51771 25813 51772 25810 51772 25811 51772 25811 51773 25810 51773 25402 51773 25811 51774 25819 51774 25813 51774 25813 51775 25819 51775 25812 51775 25813 51776 25812 51776 25808 51776 25808 51777 25812 51777 25814 51777 25808 51778 25814 51778 25815 51778 25815 51779 25814 51779 25823 51779 25815 51780 25823 51780 25816 51780 25816 51781 25823 51781 25824 51781 25816 51782 25824 51782 25817 51782 25817 51783 25824 51783 25826 51783 25817 51784 25826 51784 25804 51784 25804 51785 25826 51785 25827 51785 25804 51786 25827 51786 25818 51786 25818 51787 25827 51787 24157 51787 25819 51788 25820 51788 25812 51788 25812 51789 25820 51789 25821 51789 25812 51790 25821 51790 25814 51790 25814 51791 25821 51791 25822 51791 25814 51792 25822 51792 25823 51792 25823 51793 25822 51793 24321 51793 25823 51794 24321 51794 25824 51794 25824 51795 24321 51795 25825 51795 25824 51796 25825 51796 25826 51796 25826 51797 25825 51797 24319 51797 25826 51798 24319 51798 25827 51798 25827 51799 24319 51799 24317 51799 25827 51800 24317 51800 24157 51800 24157 51801 24317 51801 24153 51801 24137 51802 25828 51802 25829 51802 25829 51803 25828 51803 25830 51803 25829 51804 25830 51804 25831 51804 25831 51805 25830 51805 25832 51805 25831 51806 25832 51806 25833 51806 25833 51807 25832 51807 25835 51807 25833 51808 25835 51808 25834 51808 25834 51809 25835 51809 25394 51809 25834 51810 25394 51810 25836 51810 25836 51811 25394 51811 25393 51811 25836 51812 25393 51812 24144 51812 24144 51813 25393 51813 24145 51813 24144 51814 24143 51814 25836 51814 25836 51815 24143 51815 25840 51815 25836 51816 25840 51816 25834 51816 25834 51817 25840 51817 25837 51817 25834 51818 25837 51818 25833 51818 25833 51819 25837 51819 25838 51819 25833 51820 25838 51820 25831 51820 25831 51821 25838 51821 25845 51821 25831 51822 25845 51822 25829 51822 25829 51823 25845 51823 25839 51823 25829 51824 25839 51824 24137 51824 24137 51825 25839 51825 25846 51825 24143 51826 24276 51826 25840 51826 25840 51827 24276 51827 25841 51827 25840 51828 25841 51828 25837 51828 25837 51829 25841 51829 25842 51829 25837 51830 25842 51830 25838 51830 25838 51831 25842 51831 25843 51831 25838 51832 25843 51832 25845 51832 25845 51833 25843 51833 25844 51833 25845 51834 25844 51834 25839 51834 25839 51835 25844 51835 24281 51835 25839 51836 24281 51836 25846 51836 25846 51837 24281 51837 24129 51837 24127 51838 25847 51838 25860 51838 25860 51839 25847 51839 25390 51839 25860 51840 25390 51840 25848 51840 25848 51841 25390 51841 25849 51841 25848 51842 25849 51842 25857 51842 25857 51843 25849 51843 25850 51843 25857 51844 25850 51844 25851 51844 25851 51845 25850 51845 25388 51845 25851 51846 25388 51846 25855 51846 25855 51847 25388 51847 25387 51847 25855 51848 25387 51848 25854 51848 25854 51849 25387 51849 25852 51849 25854 51850 25852 51850 25853 51850 25853 51851 25852 51851 24122 51851 25853 51852 24121 51852 25866 51852 25853 51853 25866 51853 25854 51853 25854 51854 25866 51854 25868 51854 25854 51855 25868 51855 25855 51855 25855 51856 25868 51856 25869 51856 25855 51857 25869 51857 25851 51857 25869 51858 25865 51858 25851 51858 25851 51859 25865 51859 25864 51859 25851 51860 25864 51860 25857 51860 25864 51861 25856 51861 25857 51861 25857 51862 25856 51862 25858 51862 25857 51863 25858 51863 25848 51863 25858 51864 25862 51864 25848 51864 25848 51865 25862 51865 25859 51865 25848 51866 25859 51866 25860 51866 25860 51867 25859 51867 25861 51867 25860 51868 25861 51868 24127 51868 24110 51869 25861 51869 24261 51869 24261 51870 25861 51870 25859 51870 24261 51871 25859 51871 25863 51871 25863 51872 25859 51872 25862 51872 25862 51873 25858 51873 25863 51873 25863 51874 25858 51874 25856 51874 25863 51875 25856 51875 24253 51875 25856 51876 25864 51876 24253 51876 24253 51877 25864 51877 25865 51877 24253 51878 25865 51878 25870 51878 24121 51879 24259 51879 25866 51879 25866 51880 24259 51880 25867 51880 25866 51881 25867 51881 25868 51881 25868 51882 25867 51882 25870 51882 25868 51883 25870 51883 25869 51883 25869 51884 25870 51884 25865 51884 25871 51885 25373 51885 25872 51885 25872 51886 25373 51886 25371 51886 25872 51887 25371 51887 25874 51887 25874 51888 25371 51888 25873 51888 25874 51889 25873 51889 25881 51889 25881 51890 25873 51890 25875 51890 25881 51891 25875 51891 25879 51891 25879 51892 25875 51892 25368 51892 25879 51893 25368 51893 25876 51893 25876 51894 25368 51894 25380 51894 25876 51895 25380 51895 25877 51895 25877 51896 25380 51896 25379 51896 25877 51897 24100 51897 25876 51897 25876 51898 24100 51898 25878 51898 25876 51899 25878 51899 25879 51899 25879 51900 25878 51900 25880 51900 25879 51901 25880 51901 25881 51901 25881 51902 25880 51902 25885 51902 25881 51903 25885 51903 25874 51903 25874 51904 25885 51904 25882 51904 25874 51905 25882 51905 25872 51905 25872 51906 25882 51906 25883 51906 25872 51907 25883 51907 25871 51907 25871 51908 25883 51908 25889 51908 24100 51909 24298 51909 25878 51909 25878 51910 24298 51910 25884 51910 25878 51911 25884 51911 25880 51911 25880 51912 25884 51912 25886 51912 25880 51913 25886 51913 25885 51913 25885 51914 25886 51914 25887 51914 25885 51915 25887 51915 25882 51915 25882 51916 25887 51916 25888 51916 25882 51917 25888 51917 25883 51917 25883 51918 25888 51918 25890 51918 25883 51919 25890 51919 25889 51919 25889 51920 25890 51920 24305 51920 23993 51921 24046 51921 25891 51921 25891 51922 24046 51922 24048 51922 25891 51923 24048 51923 25198 51923 25198 51924 24048 51924 24050 51924 25198 51925 24050 51925 25892 51925 24050 51926 24052 51926 25892 51926 25892 51927 24052 51927 25893 51927 25892 51928 25893 51928 25202 51928 25893 51929 25894 51929 25202 51929 25202 51930 25894 51930 24053 51930 25202 51931 24053 51931 23991 51931 23991 51932 24053 51932 25895 51932 23991 51933 25895 51933 24055 51933 25218 51934 25896 51934 25897 51934 25897 51935 25896 51935 25898 51935 25897 51936 25898 51936 25220 51936 25220 51937 25898 51937 25899 51937 25220 51938 25899 51938 25900 51938 25900 51939 25899 51939 24073 51939 25900 51940 24073 51940 25239 51940 25239 51941 24073 51941 24074 51941 25239 51942 24074 51942 24075 51942 25240 51943 23972 51943 24024 51943 24024 51944 25901 51944 25240 51944 25240 51945 25901 51945 24025 51945 25240 51946 24025 51946 25902 51946 24025 51947 25903 51947 25902 51947 25902 51948 25903 51948 25904 51948 25902 51949 25904 51949 25905 51949 25904 51950 24028 51950 25905 51950 25905 51951 24028 51951 24029 51951 25905 51952 24029 51952 25233 51952 25233 51953 24029 51953 24030 51953 25233 51954 24030 51954 25906 51954 25906 51955 24030 51955 24031 51955 25906 51956 24031 51956 24033 51956 25197 51957 25907 51957 23997 51957 23997 51958 23998 51958 25197 51958 25197 51959 23998 51959 25908 51959 25197 51960 25908 51960 25195 51960 25908 51961 23999 51961 25195 51961 25195 51962 23999 51962 25909 51962 25195 51963 25909 51963 25911 51963 25909 51964 25910 51964 25911 51964 25911 51965 25910 51965 24001 51965 25911 51966 24001 51966 25912 51966 24001 51967 24002 51967 25912 51967 25912 51968 24002 51968 24004 51968 25912 51969 24004 51969 25913 51969 25913 51970 24004 51970 24005 51970 25913 51971 24005 51971 25914 51971 25914 51972 24005 51972 25915 51972 25914 51973 25915 51973 24006 51973 25928 51974 25335 51974 25916 51974 25916 51975 25335 51975 25918 51975 25916 51976 25918 51976 25917 51976 25917 51977 25918 51977 25330 51977 25917 51978 25330 51978 25926 51978 25926 51979 25330 51979 25919 51979 25926 51980 25919 51980 25924 51980 25924 51981 25919 51981 25340 51981 25924 51982 25340 51982 25923 51982 25923 51983 25340 51983 25921 51983 25923 51984 25921 51984 25920 51984 25920 51985 25921 51985 25922 51985 25920 51986 23931 51986 25923 51986 25923 51987 23931 51987 25925 51987 25923 51988 25925 51988 25924 51988 25924 51989 25925 51989 25930 51989 25924 51990 25930 51990 25926 51990 25926 51991 25930 51991 25931 51991 25926 51992 25931 51992 25917 51992 25917 51993 25931 51993 25927 51993 25917 51994 25927 51994 25916 51994 25916 51995 25927 51995 25934 51995 25916 51996 25934 51996 25928 51996 25928 51997 25934 51997 25936 51997 23931 51998 24013 51998 25925 51998 25925 51999 24013 51999 24012 51999 25925 52000 24012 52000 25930 52000 25930 52001 24012 52001 25929 52001 25930 52002 25929 52002 25931 52002 25931 52003 25929 52003 25932 52003 25931 52004 25932 52004 25927 52004 25927 52005 25932 52005 25933 52005 25927 52006 25933 52006 25934 52006 25934 52007 25933 52007 25935 52007 25934 52008 25935 52008 25936 52008 25936 52009 25935 52009 23922 52009 25953 52010 25345 52010 25937 52010 25937 52011 25345 52011 25346 52011 25937 52012 25346 52012 25938 52012 25938 52013 25346 52013 25939 52013 25938 52014 25939 52014 25940 52014 25940 52015 25939 52015 25941 52015 25940 52016 25941 52016 25948 52016 25948 52017 25941 52017 25943 52017 25948 52018 25943 52018 25942 52018 25942 52019 25943 52019 25944 52019 25942 52020 25944 52020 25946 52020 25946 52021 25944 52021 25348 52021 25946 52022 25348 52022 25945 52022 25945 52023 25348 52023 23914 52023 25945 52024 25947 52024 25946 52024 25946 52025 25947 52025 25955 52025 25946 52026 25955 52026 25942 52026 25942 52027 25955 52027 25949 52027 25942 52028 25949 52028 25948 52028 25948 52029 25949 52029 25950 52029 25948 52030 25950 52030 25940 52030 25940 52031 25950 52031 25951 52031 25940 52032 25951 52032 25938 52032 25938 52033 25951 52033 25952 52033 25938 52034 25952 52034 25937 52034 25937 52035 25952 52035 25957 52035 25937 52036 25957 52036 25953 52036 25953 52037 25957 52037 25954 52037 25947 52038 24062 52038 25955 52038 25955 52039 24062 52039 24061 52039 25955 52040 24061 52040 25949 52040 25949 52041 24061 52041 24060 52041 25949 52042 24060 52042 25950 52042 25950 52043 24060 52043 25956 52043 25950 52044 25956 52044 25951 52044 25951 52045 25956 52045 24068 52045 25951 52046 24068 52046 25952 52046 25952 52047 24068 52047 25958 52047 25952 52048 25958 52048 25957 52048 25957 52049 25958 52049 24067 52049 25957 52050 24067 52050 25954 52050 25954 52051 24067 52051 23905 52051 23902 52052 23903 52052 25968 52052 25968 52053 23903 52053 25354 52053 25968 52054 25354 52054 25966 52054 25966 52055 25354 52055 25959 52055 25966 52056 25959 52056 25965 52056 25965 52057 25959 52057 25350 52057 25965 52058 25350 52058 25963 52058 25963 52059 25350 52059 25349 52059 25963 52060 25349 52060 25960 52060 25960 52061 25349 52061 25961 52061 25960 52062 25961 52062 23895 52062 23895 52063 25961 52063 25353 52063 23895 52064 25962 52064 25960 52064 25960 52065 25962 52065 25964 52065 25960 52066 25964 52066 25963 52066 25963 52067 25964 52067 25970 52067 25963 52068 25970 52068 25965 52068 25965 52069 25970 52069 25972 52069 25965 52070 25972 52070 25966 52070 25966 52071 25972 52071 25974 52071 25966 52072 25974 52072 25968 52072 25968 52073 25974 52073 25967 52073 25968 52074 25967 52074 23902 52074 23902 52075 25967 52075 23881 52075 25962 52076 23888 52076 25964 52076 25964 52077 23888 52077 25969 52077 25964 52078 25969 52078 25970 52078 25970 52079 25969 52079 25971 52079 25970 52080 25971 52080 25972 52080 25972 52081 25971 52081 25973 52081 25972 52082 25973 52082 25974 52082 25974 52083 25973 52083 24043 52083 25974 52084 24043 52084 25967 52084 25967 52085 24043 52085 25975 52085 25967 52086 25975 52086 23881 52086 23881 52087 25975 52087 23882 52087 25986 52088 23880 52088 25976 52088 25976 52089 23880 52089 25977 52089 25976 52090 25977 52090 25984 52090 25984 52091 25977 52091 25978 52091 25984 52092 25978 52092 25983 52092 25983 52093 25978 52093 25363 52093 25983 52094 25363 52094 25979 52094 25979 52095 25363 52095 25362 52095 25979 52096 25362 52096 25982 52096 25982 52097 25362 52097 25980 52097 25982 52098 25980 52098 25981 52098 25981 52099 25980 52099 23871 52099 25981 52100 23867 52100 25982 52100 25982 52101 23867 52101 25989 52101 25982 52102 25989 52102 25979 52102 25979 52103 25989 52103 25990 52103 25979 52104 25990 52104 25983 52104 25983 52105 25990 52105 25991 52105 25983 52106 25991 52106 25984 52106 25984 52107 25991 52107 25992 52107 25984 52108 25992 52108 25976 52108 25976 52109 25992 52109 25985 52109 25976 52110 25985 52110 25986 52110 25986 52111 25985 52111 25987 52111 23867 52112 24079 52112 25989 52112 25989 52113 24079 52113 25988 52113 25989 52114 25988 52114 25990 52114 25990 52115 25988 52115 24080 52115 25990 52116 24080 52116 25991 52116 25991 52117 24080 52117 24082 52117 25991 52118 24082 52118 25992 52118 25992 52119 24082 52119 24077 52119 25992 52120 24077 52120 25985 52120 25985 52121 24077 52121 24084 52121 25985 52122 24084 52122 25987 52122 25987 52123 24084 52123 23857 52123 23856 52124 25993 52124 23719 52124 23719 52125 25993 52125 23838 52125 25994 52126 25995 52126 23831 52126 25994 52127 23831 52127 25996 52127 25996 52128 23831 52128 23830 52128 25996 52129 23830 52129 23757 52129 23757 52130 23830 52130 25997 52130 23757 52131 25997 52131 25998 52131 23813 52132 23819 52132 23820 52132 23813 52133 23820 52133 23775 52133 23775 52134 23820 52134 23799 52134 23775 52135 23799 52135 23800 52135 23790 52136 23795 52136 23796 52136 23790 52137 23796 52137 25999 52137 25999 52138 23796 52138 23780 52138 25999 52139 23780 52139 23730 52139 26000 52140 25414 52140 23689 52140 23689 52141 26006 52141 26000 52141 26000 52142 26006 52142 26001 52142 26000 52143 26001 52143 25422 52143 26001 52144 26002 52144 25422 52144 25422 52145 26002 52145 26008 52145 25422 52146 26008 52146 26003 52146 26008 52147 26009 52147 26003 52147 26003 52148 26009 52148 26004 52148 26003 52149 26004 52149 25425 52149 25425 52150 26004 52150 26012 52150 25425 52151 26012 52151 26005 52151 26012 52152 26013 52152 26005 52152 26005 52153 26013 52153 26014 52153 26005 52154 26014 52154 25426 52154 23681 52155 25427 52155 26016 52155 26016 52156 25427 52156 25426 52156 26016 52157 25426 52157 26015 52157 26015 52158 25426 52158 26014 52158 23689 52159 23680 52159 26006 52159 26006 52160 23680 52160 26007 52160 26006 52161 26007 52161 26001 52161 26001 52162 26007 52162 26002 52162 26002 52163 26007 52163 26019 52163 26002 52164 26019 52164 26008 52164 26008 52165 26019 52165 26009 52165 26009 52166 26019 52166 26010 52166 26009 52167 26010 52167 26004 52167 26004 52168 26010 52168 26012 52168 26012 52169 26010 52169 26011 52169 26012 52170 26011 52170 26013 52170 26013 52171 26011 52171 26014 52171 26014 52172 26011 52172 26020 52172 26014 52173 26020 52173 26015 52173 26015 52174 26020 52174 26016 52174 26016 52175 26020 52175 23672 52175 26016 52176 23672 52176 23681 52176 23680 52177 26017 52177 26007 52177 26007 52178 26017 52178 26018 52178 26007 52179 26018 52179 26019 52179 26019 52180 26018 52180 23844 52180 26019 52181 23844 52181 26010 52181 26010 52182 23844 52182 23847 52182 26010 52183 23847 52183 26011 52183 26011 52184 23847 52184 23848 52184 26011 52185 23848 52185 26020 52185 26020 52186 23848 52186 23843 52186 26020 52187 23843 52187 23672 52187 23672 52188 23843 52188 23667 52188 26033 52189 26021 52189 26032 52189 26032 52190 26021 52190 25432 52190 26032 52191 25432 52191 26022 52191 26022 52192 25432 52192 25430 52192 26022 52193 25430 52193 26029 52193 26029 52194 25430 52194 26024 52194 26029 52195 26024 52195 26023 52195 26023 52196 26024 52196 25444 52196 26023 52197 25444 52197 26028 52197 26028 52198 25444 52198 26025 52198 26028 52199 26025 52199 26026 52199 26026 52200 26025 52200 25437 52200 26026 52201 25437 52201 23651 52201 23651 52202 25437 52202 23652 52202 23651 52203 26027 52203 26026 52203 26026 52204 26027 52204 26034 52204 26026 52205 26034 52205 26028 52205 26028 52206 26034 52206 26036 52206 26028 52207 26036 52207 26023 52207 26023 52208 26036 52208 26030 52208 26023 52209 26030 52209 26029 52209 26029 52210 26030 52210 26038 52210 26029 52211 26038 52211 26022 52211 26022 52212 26038 52212 26031 52212 26022 52213 26031 52213 26032 52213 26032 52214 26031 52214 26041 52214 26032 52215 26041 52215 26033 52215 26033 52216 26041 52216 26042 52216 26027 52217 26035 52217 26034 52217 26034 52218 26035 52218 23818 52218 26034 52219 23818 52219 26036 52219 26036 52220 23818 52220 23817 52220 26036 52221 23817 52221 26030 52221 26030 52222 23817 52222 26037 52222 26030 52223 26037 52223 26038 52223 26038 52224 26037 52224 26039 52224 26038 52225 26039 52225 26031 52225 26031 52226 26039 52226 26040 52226 26031 52227 26040 52227 26041 52227 26041 52228 26040 52228 26043 52228 26041 52229 26043 52229 26042 52229 26042 52230 26043 52230 23815 52230 23641 52231 25442 52231 26056 52231 26056 52232 25442 52232 26044 52232 26056 52233 26044 52233 26054 52233 26054 52234 26044 52234 25449 52234 26054 52235 25449 52235 26045 52235 26045 52236 25449 52236 26046 52236 26045 52237 26046 52237 26052 52237 26052 52238 26046 52238 25446 52238 26052 52239 25446 52239 26051 52239 26051 52240 25446 52240 26047 52240 26051 52241 26047 52241 26048 52241 26048 52242 26047 52242 25451 52242 26048 52243 25451 52243 23634 52243 23634 52244 25451 52244 26049 52244 23634 52245 23635 52245 26048 52245 26048 52246 23635 52246 26050 52246 26048 52247 26050 52247 26051 52247 26051 52248 26050 52248 26059 52248 26051 52249 26059 52249 26052 52249 26052 52250 26059 52250 26053 52250 26052 52251 26053 52251 26045 52251 26045 52252 26053 52252 26055 52252 26045 52253 26055 52253 26054 52253 26054 52254 26055 52254 26062 52254 26054 52255 26062 52255 26056 52255 26056 52256 26062 52256 26064 52256 26056 52257 26064 52257 23641 52257 23641 52258 26064 52258 26066 52258 23635 52259 26057 52259 26050 52259 26050 52260 26057 52260 26058 52260 26050 52261 26058 52261 26059 52261 26059 52262 26058 52262 26060 52262 26059 52263 26060 52263 26053 52263 26053 52264 26060 52264 26061 52264 26053 52265 26061 52265 26055 52265 26055 52266 26061 52266 26063 52266 26055 52267 26063 52267 26062 52267 26062 52268 26063 52268 23794 52268 26062 52269 23794 52269 26064 52269 26064 52270 23794 52270 26065 52270 26064 52271 26065 52271 26066 52271 26066 52272 26065 52272 23624 52272 23608 52273 23623 52273 26067 52273 26067 52274 23623 52274 26068 52274 26067 52275 26068 52275 26079 52275 26079 52276 26068 52276 26069 52276 26079 52277 26069 52277 26078 52277 26078 52278 26069 52278 25454 52278 26078 52279 25454 52279 26070 52279 26070 52280 25454 52280 25452 52280 26070 52281 25452 52281 26073 52281 26073 52282 25452 52282 25455 52282 26073 52283 25455 52283 26071 52283 26071 52284 25455 52284 23616 52284 23615 52285 26072 52285 26071 52285 26071 52286 26072 52286 26073 52286 26072 52287 26074 52287 26073 52287 26073 52288 26074 52288 26075 52288 26073 52289 26075 52289 26070 52289 26075 52290 26090 52290 26070 52290 26070 52291 26090 52291 26076 52291 26070 52292 26076 52292 26078 52292 26076 52293 26077 52293 26078 52293 26078 52294 26077 52294 26087 52294 26078 52295 26087 52295 26079 52295 26087 52296 26086 52296 26079 52296 26079 52297 26086 52297 26080 52297 26079 52298 26080 52298 26067 52298 26081 52299 23608 52299 26082 52299 26082 52300 23608 52300 26067 52300 26082 52301 26067 52301 26084 52301 26084 52302 26067 52302 26080 52302 26083 52303 23606 52303 26081 52303 26081 52304 26082 52304 26083 52304 26083 52305 26082 52305 26084 52305 26083 52306 26084 52306 26085 52306 26084 52307 26080 52307 26085 52307 26085 52308 26080 52308 26086 52308 26085 52309 26086 52309 26088 52309 26086 52310 26087 52310 26088 52310 26088 52311 26087 52311 26077 52311 26088 52312 26077 52312 26089 52312 26089 52313 26077 52313 26076 52313 26089 52314 26076 52314 23834 52314 26076 52315 26090 52315 23834 52315 23834 52316 26090 52316 26075 52316 23834 52317 26075 52317 23833 52317 23615 52318 23832 52318 26072 52318 26072 52319 23832 52319 23833 52319 26072 52320 23833 52320 26074 52320 26074 52321 23833 52321 26075 52321 26091 52322 26092 52322 26093 52322 26093 52323 26092 52323 26094 52323 26093 52324 26094 52324 26095 52324 26095 52325 26094 52325 26096 52325 26096 52326 26094 52326 23592 52326 26096 52327 23592 52327 23516 52327 23516 52328 23592 52328 23595 52328 23516 52329 23595 52329 26097 52329 26097 52330 23595 52330 23579 52330 26097 52331 23579 52331 23507 52331 23529 52332 26099 52332 26098 52332 26098 52333 26099 52333 26101 52333 26098 52334 26101 52334 26100 52334 26100 52335 26101 52335 23531 52335 23531 52336 26101 52336 26104 52336 23531 52337 26104 52337 26102 52337 26102 52338 26104 52338 26103 52338 26103 52339 26104 52339 23577 52339 26103 52340 23577 52340 23533 52340 23533 52341 23577 52341 26105 52341 26105 52342 23577 52342 26106 52342 26105 52343 26106 52343 26107 52343 26107 52344 26106 52344 23567 52344 26107 52345 23567 52345 26108 52345 23498 52346 26109 52346 26110 52346 26110 52347 26109 52347 26111 52347 26110 52348 26111 52348 23497 52348 23497 52349 26111 52349 23561 52349 23497 52350 23561 52350 26112 52350 26112 52351 23561 52351 26113 52351 26112 52352 26113 52352 26114 52352 26114 52353 26113 52353 23564 52353 26114 52354 23564 52354 23494 52354 23494 52355 23564 52355 23551 52355 23494 52356 23551 52356 23552 52356 23539 52357 23542 52357 23471 52357 23471 52358 23542 52358 26115 52358 23471 52359 26115 52359 23472 52359 23472 52360 26115 52360 23474 52360 23474 52361 26115 52361 23543 52361 23474 52362 23543 52362 23475 52362 23475 52363 23543 52363 26116 52363 26116 52364 23543 52364 23544 52364 26116 52365 23544 52365 23479 52365 23479 52366 23544 52366 23478 52366 23478 52367 23544 52367 23546 52367 23478 52368 23546 52368 26117 52368 26117 52369 23546 52369 26118 52369 26117 52370 26118 52370 26119 52370 26119 52371 26118 52371 23548 52371 26119 52372 23548 52372 26120 52372 26122 52373 25493 52373 26136 52373 26136 52374 26121 52374 26122 52374 26122 52375 26121 52375 26137 52375 26122 52376 26137 52376 26124 52376 26137 52377 26123 52377 26124 52377 26124 52378 26123 52378 26125 52378 26124 52379 26125 52379 26126 52379 26125 52380 26127 52380 26126 52380 26126 52381 26127 52381 26129 52381 26126 52382 26129 52382 26128 52382 26128 52383 26129 52383 26140 52383 26128 52384 26140 52384 26130 52384 26140 52385 26141 52385 26130 52385 26130 52386 26141 52386 26131 52386 26130 52387 26131 52387 26134 52387 26132 52388 23454 52388 26133 52388 26133 52389 23454 52389 26134 52389 26133 52390 26134 52390 26135 52390 26135 52391 26134 52391 26131 52391 26136 52392 26144 52392 26121 52392 26121 52393 26144 52393 26138 52393 26121 52394 26138 52394 26137 52394 26137 52395 26138 52395 26123 52395 26123 52396 26138 52396 26139 52396 26123 52397 26139 52397 26125 52397 26125 52398 26139 52398 26127 52398 26127 52399 26139 52399 26146 52399 26127 52400 26146 52400 26129 52400 26129 52401 26146 52401 26140 52401 26140 52402 26146 52402 26142 52402 26140 52403 26142 52403 26141 52403 26141 52404 26142 52404 26131 52404 26131 52405 26142 52405 26143 52405 26131 52406 26143 52406 26135 52406 26135 52407 26143 52407 26133 52407 26133 52408 26143 52408 26149 52408 26133 52409 26149 52409 26132 52409 26144 52410 23430 52410 26138 52410 26138 52411 23430 52411 23541 52411 26138 52412 23541 52412 26139 52412 26139 52413 23541 52413 26145 52413 26139 52414 26145 52414 26146 52414 26146 52415 26145 52415 23540 52415 26146 52416 23540 52416 26142 52416 26142 52417 23540 52417 26147 52417 26142 52418 26147 52418 26143 52418 26143 52419 26147 52419 26148 52419 26143 52420 26148 52420 26149 52420 26149 52421 26148 52421 23549 52421 26160 52422 25481 52422 26150 52422 26150 52423 25481 52423 26151 52423 26150 52424 26151 52424 26152 52424 26152 52425 26151 52425 25480 52425 26152 52426 25480 52426 26159 52426 26159 52427 25480 52427 26154 52427 26159 52428 26154 52428 26153 52428 26153 52429 26154 52429 26155 52429 26153 52430 26155 52430 26156 52430 26156 52431 26155 52431 26157 52431 26156 52432 26157 52432 23421 52432 23421 52433 26157 52433 26158 52433 23421 52434 23414 52434 26156 52434 26156 52435 23414 52435 26162 52435 26156 52436 26162 52436 26153 52436 26153 52437 26162 52437 26163 52437 26153 52438 26163 52438 26159 52438 26159 52439 26163 52439 26165 52439 26159 52440 26165 52440 26152 52440 26152 52441 26165 52441 26167 52441 26152 52442 26167 52442 26150 52442 26150 52443 26167 52443 26169 52443 26150 52444 26169 52444 26160 52444 26160 52445 26169 52445 26170 52445 23414 52446 23415 52446 26162 52446 26162 52447 23415 52447 26161 52447 26162 52448 26161 52448 26163 52448 26163 52449 26161 52449 26164 52449 26163 52450 26164 52450 26165 52450 26165 52451 26164 52451 26166 52451 26165 52452 26166 52452 26167 52452 26167 52453 26166 52453 26168 52453 26167 52454 26168 52454 26169 52454 26169 52455 26168 52455 23571 52455 26169 52456 23571 52456 26170 52456 26170 52457 23571 52457 23408 52457 23400 52458 25474 52458 26171 52458 26171 52459 25474 52459 25473 52459 26171 52460 25473 52460 26181 52460 26181 52461 25473 52461 26172 52461 26181 52462 26172 52462 26173 52462 26173 52463 26172 52463 26174 52463 26173 52464 26174 52464 26179 52464 26179 52465 26174 52465 25472 52465 26179 52466 25472 52466 26175 52466 26175 52467 25472 52467 25470 52467 26175 52468 25470 52468 26176 52468 26176 52469 25470 52469 25483 52469 26176 52470 26177 52470 26175 52470 26175 52471 26177 52471 26184 52471 26175 52472 26184 52472 26179 52472 26179 52473 26184 52473 26178 52473 26179 52474 26178 52474 26173 52474 26173 52475 26178 52475 26180 52475 26173 52476 26180 52476 26181 52476 26181 52477 26180 52477 26185 52477 26181 52478 26185 52478 26171 52478 26171 52479 26185 52479 26182 52479 26171 52480 26182 52480 23400 52480 23400 52481 26182 52481 23399 52481 26177 52482 26183 52482 26184 52482 26184 52483 26183 52483 23560 52483 26184 52484 23560 52484 26178 52484 26178 52485 23560 52485 23559 52485 26178 52486 23559 52486 26180 52486 26180 52487 23559 52487 23558 52487 26180 52488 23558 52488 26185 52488 26185 52489 23558 52489 26186 52489 26185 52490 26186 52490 26182 52490 26182 52491 26186 52491 26187 52491 26182 52492 26187 52492 23399 52492 23399 52493 26187 52493 26188 52493 26190 52494 25463 52494 26198 52494 26198 52495 26189 52495 26190 52495 26190 52496 26189 52496 26200 52496 26190 52497 26200 52497 26191 52497 26191 52498 26200 52498 26202 52498 26202 52499 26203 52499 26191 52499 26191 52500 26203 52500 26204 52500 26191 52501 26204 52501 25462 52501 26204 52502 26205 52502 25462 52502 25462 52503 26205 52503 26206 52503 25462 52504 26206 52504 26193 52504 26206 52505 26192 52505 26193 52505 26193 52506 26192 52506 26194 52506 26193 52507 26194 52507 26196 52507 23368 52508 26195 52508 26207 52508 26207 52509 26195 52509 26196 52509 26207 52510 26196 52510 26197 52510 26197 52511 26196 52511 26194 52511 26198 52512 26220 52512 26189 52512 26189 52513 26220 52513 26199 52513 26189 52514 26199 52514 26200 52514 26200 52515 26199 52515 26201 52515 26200 52516 26201 52516 26202 52516 26202 52517 26201 52517 26219 52517 26202 52518 26219 52518 26203 52518 26203 52519 26219 52519 26218 52519 26203 52520 26218 52520 26204 52520 26204 52521 26218 52521 26217 52521 26204 52522 26217 52522 26205 52522 26205 52523 26217 52523 26215 52523 26205 52524 26215 52524 26206 52524 26206 52525 26215 52525 26214 52525 26206 52526 26214 52526 26192 52526 26192 52527 26214 52527 26213 52527 26192 52528 26213 52528 26194 52528 26194 52529 26213 52529 26212 52529 26194 52530 26212 52530 26197 52530 26197 52531 26212 52531 26211 52531 26197 52532 26211 52532 26207 52532 26207 52533 26211 52533 26208 52533 26207 52534 26208 52534 23368 52534 23368 52535 26208 52535 26209 52535 23588 52536 23354 52536 26209 52536 26209 52537 26208 52537 23588 52537 23588 52538 26208 52538 26211 52538 23588 52539 26211 52539 26210 52539 26210 52540 26211 52540 26212 52540 26212 52541 26213 52541 26210 52541 26210 52542 26213 52542 26214 52542 26210 52543 26214 52543 26216 52543 26214 52544 26215 52544 26216 52544 26216 52545 26215 52545 26217 52545 26216 52546 26217 52546 23589 52546 26217 52547 26218 52547 23589 52547 23589 52548 26218 52548 26219 52548 23589 52549 26219 52549 23591 52549 26220 52550 26221 52550 26199 52550 26199 52551 26221 52551 23591 52551 26199 52552 23591 52552 26201 52552 26201 52553 23591 52553 26219 52553 23278 52554 26222 52554 22972 52554 22972 52555 26222 52555 23195 52555 22972 52556 23195 52556 23300 52556 23050 52557 23269 52557 23051 52557 23051 52558 23269 52558 26223 52558 23051 52559 26223 52559 25055 52559 25055 52560 26223 52560 25057 52560 25057 52561 26223 52561 23202 52561 25057 52562 23202 52562 25058 52562 25058 52563 23202 52563 23217 52563 25058 52564 23217 52564 25059 52564 25403 52565 23270 52565 25324 52565 25324 52566 23270 52566 26224 52566 25324 52567 26224 52567 26225 52567 26225 52568 26224 52568 26227 52568 25566 52569 25391 52569 26226 52569 26226 52570 25391 52570 26228 52570 26226 52571 26228 52571 26227 52571 26227 52572 26228 52572 26229 52572 26227 52573 26229 52573 26225 52573 26234 52574 25372 52574 26230 52574 26230 52575 25372 52575 26231 52575 26230 52576 26231 52576 25566 52576 25566 52577 26231 52577 25389 52577 25566 52578 25389 52578 25391 52578 23258 52579 25370 52579 26232 52579 26232 52580 25370 52580 26233 52580 26232 52581 26233 52581 26234 52581 26234 52582 26233 52582 26235 52582 26234 52583 26235 52583 25372 52583 23279 52584 26237 52584 26236 52584 26236 52585 26237 52585 23254 52585 26238 52586 23255 52586 26239 52586 26238 52587 26239 52587 26240 52587 26240 52588 26239 52588 26241 52588 26240 52589 26241 52589 26242 52589 26242 52590 26241 52590 23270 52590 26242 52591 23270 52591 25403 52591 25466 52592 25409 52592 26243 52592 26243 52593 25409 52593 25266 52593 26244 52594 26245 52594 26247 52594 26243 52595 26246 52595 25466 52595 25466 52596 26246 52596 25261 52596 25466 52597 25261 52597 26247 52597 26247 52598 25261 52598 26248 52598 26247 52599 26248 52599 26244 52599 26244 52600 25262 52600 26245 52600 26245 52601 25262 52601 25257 52601 26245 52602 25257 52602 26249 52602 26249 52603 25257 52603 26251 52603 26249 52604 26251 52604 26250 52604 26250 52605 26251 52605 26252 52605 26250 52606 26252 52606 25469 52606 25469 52607 26252 52607 26253 52607 25469 52608 26253 52608 26254 52608 26254 52609 26253 52609 25410 52609 25410 52610 26253 52610 25254 52610 25410 52611 25254 52611 26256 52611 26256 52612 25254 52612 26255 52612 26256 52613 26255 52613 25488 52613 26255 52614 25247 52614 25488 52614 25488 52615 25247 52615 25249 52615 25488 52616 25249 52616 26257 52616 26257 52617 25249 52617 26258 52617 26257 52618 26258 52618 26259 52618 26259 52619 26258 52619 26260 52619 26259 52620 26260 52620 25496 52620 25496 52621 26260 52621 25244 52621 25496 52622 25244 52622 25495 52622 23171 52623 26261 52623 26262 52623 26262 52624 26261 52624 24523 52624 26262 52625 24523 52625 26263 52625 26263 52626 24523 52626 24526 52626 26263 52627 24526 52627 26264 52627 26264 52628 24526 52628 24527 52628 26264 52629 24527 52629 26265 52629 26265 52630 24527 52630 26266 52630 26265 52631 26266 52631 26267 52631 26267 52632 26266 52632 24550 52632 26267 52633 24550 52633 26268 52633 26268 52634 24550 52634 26269 52634 26268 52635 26269 52635 26270 52635 26270 52636 26269 52636 24540 52636 26270 52637 24540 52637 26271 52637 26271 52638 24540 52638 24542 52638 26271 52639 24542 52639 26272 52639 26272 52640 24542 52640 26273 52640 26272 52641 26273 52641 26274 52641 26274 52642 26273 52642 24533 52642 26274 52643 24533 52643 26321 52643 26321 52644 24533 52644 26275 52644 26321 52645 26275 52645 26326 52645 26326 52646 26275 52646 23160 52646 26318 52647 25074 52647 26277 52647 25115 52648 26318 52648 26276 52648 26276 52649 26318 52649 26277 52649 26276 52650 26277 52650 26280 52650 26279 52651 24870 52651 24873 52651 26281 52652 26278 52652 26280 52652 26280 52653 26278 52653 22980 52653 26280 52654 22980 52654 26276 52654 26279 52655 24873 52655 26280 52655 26280 52656 24873 52656 24875 52656 26280 52657 24875 52657 26281 52657 26283 52658 26282 52658 25060 52658 25060 52659 26313 52659 26283 52659 26283 52660 26313 52660 26284 52660 26283 52661 26284 52661 26287 52661 26287 52662 26284 52662 23033 52662 23033 52663 26285 52663 26287 52663 26287 52664 26285 52664 24858 52664 26287 52665 24858 52665 24857 52665 24857 52666 26286 52666 26287 52666 26287 52667 26286 52667 24853 52667 26287 52668 24853 52668 26288 52668 23105 52669 26289 52669 23107 52669 23107 52670 26289 52670 23108 52670 26290 52671 26289 52671 23105 52671 24599 52672 26291 52672 22880 52672 22880 52673 26291 52673 26292 52673 26292 52674 26291 52674 26293 52674 23008 52675 23007 52675 26314 52675 26314 52676 25118 52676 23008 52676 23008 52677 25118 52677 25114 52677 23008 52678 25114 52678 25124 52678 25124 52679 25114 52679 22990 52679 22990 52680 26294 52680 25124 52680 25124 52681 26294 52681 26295 52681 25124 52682 26295 52682 26296 52682 26296 52683 26297 52683 25124 52683 25124 52684 26297 52684 24867 52684 25124 52685 24867 52685 24866 52685 26299 52686 23014 52686 26300 52686 26298 52687 26299 52687 23020 52687 23020 52688 26299 52688 26300 52688 23020 52689 26300 52689 26305 52689 24860 52690 26301 52690 26302 52690 24864 52691 26303 52691 26305 52691 26305 52692 26303 52692 26304 52692 26305 52693 26304 52693 23020 52693 24860 52694 26302 52694 26305 52694 26305 52695 26302 52695 24863 52695 26305 52696 24863 52696 24864 52696 23148 52697 24977 52697 24974 52697 24976 52698 24977 52698 26306 52698 26306 52699 24977 52699 23148 52699 23061 52700 26307 52700 23063 52700 23063 52701 26307 52701 23065 52701 23065 52702 26307 52702 23066 52702 25106 52703 26309 52703 26308 52703 26308 52704 25091 52704 25106 52704 25106 52705 25091 52705 26299 52705 25106 52706 26299 52706 26298 52706 23041 52707 25512 52707 23040 52707 23040 52708 25512 52708 26308 52708 23040 52709 26308 52709 23039 52709 23039 52710 26308 52710 26309 52710 26313 52711 25060 52711 26311 52711 25077 52712 25500 52712 23038 52712 25077 52713 23038 52713 25073 52713 23038 52714 26310 52714 25073 52714 25073 52715 26310 52715 23037 52715 25073 52716 23037 52716 26311 52716 26311 52717 23037 52717 26312 52717 26311 52718 26312 52718 26313 52718 25118 52719 26314 52719 25099 52719 25502 52720 25501 52720 22999 52720 25502 52721 22999 52721 26315 52721 22999 52722 26316 52722 26315 52722 26315 52723 26316 52723 23000 52723 26315 52724 23000 52724 25099 52724 25099 52725 23000 52725 25119 52725 25099 52726 25119 52726 25118 52726 25116 52727 22997 52727 26320 52727 26320 52728 26317 52728 25116 52728 25116 52729 26317 52729 26318 52729 25116 52730 26318 52730 25115 52730 25508 52731 25509 52731 22996 52731 22996 52732 25509 52732 26320 52732 22996 52733 26320 52733 26319 52733 26319 52734 26320 52734 22997 52734 26267 52735 26268 52735 23164 52735 23164 52736 26268 52736 26270 52736 23164 52737 26270 52737 26271 52737 26267 52738 23164 52738 26265 52738 26265 52739 23164 52739 23166 52739 26265 52740 23166 52740 23168 52740 26271 52741 26272 52741 23164 52741 23164 52742 26272 52742 26274 52742 23164 52743 26274 52743 26321 52743 23164 52744 26327 52744 23162 52744 23162 52745 23163 52745 23164 52745 23164 52746 23163 52746 26322 52746 23164 52747 26322 52747 26323 52747 23168 52748 26324 52748 26265 52748 26265 52749 26324 52749 26325 52749 26265 52750 26325 52750 23171 52750 23171 52751 26262 52751 26265 52751 26265 52752 26262 52752 26263 52752 26265 52753 26263 52753 26264 52753 26321 52754 26326 52754 23164 52754 23164 52755 26326 52755 23161 52755 23164 52756 23161 52756 26327 52756 22879 52757 22878 52757 26328 52757 26328 52758 22876 52758 26331 52758 26329 52759 22879 52759 22966 52759 22966 52760 22879 52760 26328 52760 22966 52761 26328 52761 22968 52761 22968 52762 26328 52762 26330 52762 22969 52763 26330 52763 22872 52763 22872 52764 26330 52764 26328 52764 22872 52765 26328 52765 22873 52765 22873 52766 26328 52766 26331 52766 26334 52767 26332 52767 22960 52767 22868 52768 22866 52768 26334 52768 26334 52769 22866 52769 22865 52769 22869 52770 22868 52770 26333 52770 26333 52771 22868 52771 26334 52771 26333 52772 26334 52772 22958 52772 22958 52773 26334 52773 22960 52773 22963 52774 22962 52774 22861 52774 22861 52775 22962 52775 26334 52775 22861 52776 26334 52776 22862 52776 22862 52777 26334 52777 22865 52777 22955 52778 26335 52778 22953 52778 22952 52779 22950 52779 26340 52779 26340 52780 22950 52780 26336 52780 26340 52781 22854 52781 22955 52781 22955 52782 22953 52782 26340 52782 26340 52783 22953 52783 26337 52783 26340 52784 26337 52784 22952 52784 26338 52785 26340 52785 26339 52785 26339 52786 26340 52786 26336 52786 26339 52787 26336 52787 26341 52787 26341 52788 26336 52788 22857 52788 26347 52789 26342 52789 26343 52789 22847 52790 26344 52790 26347 52790 26347 52791 26344 52791 22846 52791 22946 52792 26342 52792 26345 52792 26345 52793 26342 52793 26347 52793 26345 52794 26347 52794 22948 52794 22948 52795 26347 52795 22846 52795 22850 52796 26346 52796 22941 52796 22941 52797 26346 52797 26347 52797 22941 52798 26347 52798 22942 52798 22942 52799 26347 52799 26343 52799 26350 52800 26348 52800 22939 52800 22937 52801 26349 52801 22939 52801 22939 52802 26349 52802 26351 52802 22843 52803 22842 52803 22840 52803 22840 52804 22839 52804 22843 52804 22843 52805 22839 52805 26350 52805 22843 52806 26350 52806 22845 52806 22845 52807 26350 52807 22939 52807 22845 52808 22939 52808 22932 52808 22932 52809 22939 52809 26351 52809 22932 52810 26351 52810 22934 52810 26352 52811 22931 52811 22831 52811 22831 52812 22931 52812 22930 52812 26355 52813 22835 52813 26356 52813 22930 52814 22928 52814 22831 52814 22831 52815 22928 52815 22926 52815 22831 52816 22926 52816 26353 52816 26353 52817 26354 52817 22831 52817 22831 52818 26354 52818 26355 52818 22831 52819 26355 52819 22833 52819 22833 52820 26355 52820 26356 52820 22833 52821 26356 52821 22834 52821 22827 52822 26357 52822 26361 52822 26361 52823 26357 52823 26358 52823 22923 52824 22922 52824 22824 52824 22824 52825 22922 52825 26361 52825 22824 52826 26361 52826 26359 52826 26359 52827 26361 52827 26358 52827 26360 52828 22920 52828 22921 52828 22921 52829 22920 52829 22919 52829 22921 52830 22919 52830 26361 52830 26361 52831 22919 52831 22828 52831 26361 52832 22828 52832 22827 52832 26366 52833 26362 52833 26367 52833 22819 52834 26363 52834 26364 52834 26364 52835 26363 52835 26365 52835 26364 52836 26365 52836 26366 52836 26366 52837 26367 52837 26364 52837 26364 52838 26367 52838 22915 52838 26364 52839 22915 52839 22913 52839 22822 52840 26368 52840 26369 52840 26369 52841 26368 52841 26364 52841 26369 52842 26364 52842 22912 52842 22912 52843 26364 52843 22913 52843 26372 52844 26371 52844 22810 52844 22907 52845 22817 52845 26372 52845 26372 52846 22817 52846 26370 52846 22813 52847 26371 52847 22815 52847 22815 52848 26371 52848 26372 52848 22815 52849 26372 52849 26373 52849 26373 52850 26372 52850 26370 52850 22910 52851 22908 52851 22911 52851 22911 52852 22908 52852 26372 52852 22911 52853 26372 52853 22808 52853 22808 52854 26372 52854 22810 52854 26375 52855 22899 52855 22898 52855 22807 52856 22805 52856 26374 52856 26374 52857 22805 52857 22904 52857 26374 52858 22904 52858 22898 52858 22898 52859 22904 52859 22901 52859 22898 52860 22901 52860 26375 52860 22804 52861 26376 52861 26378 52861 26378 52862 26376 52862 26377 52862 26378 52863 26377 52863 22805 52863 22805 52864 26377 52864 22905 52864 22805 52865 22905 52865 22904 52865 22802 52866 22799 52866 22895 52866 22895 52867 26379 52867 26383 52867 22797 52868 26380 52868 22799 52868 22799 52869 26380 52869 22794 52869 22897 52870 22895 52870 26381 52870 26381 52871 22895 52871 22799 52871 26381 52872 22799 52872 22793 52872 22793 52873 22799 52873 22794 52873 22802 52874 22895 52874 26382 52874 26382 52875 22895 52875 26383 52875 26382 52876 26383 52876 22893 52876 22883 52877 22792 52877 26384 52877 22785 52878 26384 52878 22786 52878 22786 52879 26384 52879 22792 52879 22786 52880 22792 52880 26385 52880 26385 52881 22792 52881 26386 52881 26385 52882 26386 52882 22789 52882 22789 52883 26386 52883 22790 52883 22886 52884 22885 52884 22887 52884 22887 52885 22885 52885 22883 52885 22887 52886 22883 52886 22889 52886 22889 52887 22883 52887 26384 52887 26387 52888 26398 52888 26391 52888 26387 52889 26391 52889 25744 52889 25735 52890 25740 52890 26391 52890 26391 52891 25740 52891 26388 52891 26391 52892 26388 52892 25744 52892 25731 52893 25732 52893 26391 52893 26391 52894 25732 52894 26389 52894 26391 52895 26389 52895 25735 52895 25727 52896 25728 52896 26391 52896 26391 52897 25728 52897 26390 52897 26391 52898 26390 52898 25731 52898 25721 52899 26392 52899 26391 52899 26391 52900 26392 52900 25724 52900 26391 52901 25724 52901 25727 52901 25776 52902 25716 52902 26391 52902 26391 52903 25716 52903 26393 52903 26391 52904 26393 52904 25721 52904 25771 52905 25774 52905 26391 52905 26391 52906 25774 52906 25775 52906 26391 52907 25775 52907 25776 52907 26394 52908 25769 52908 26391 52908 26391 52909 25769 52909 26395 52909 26391 52910 26395 52910 25771 52910 25763 52911 26396 52911 26391 52911 26391 52912 26396 52912 25765 52912 26391 52913 25765 52913 26394 52913 25754 52914 25757 52914 26391 52914 26391 52915 25757 52915 26397 52915 26391 52916 26397 52916 25763 52916 26398 52917 25748 52917 26391 52917 26391 52918 25748 52918 25751 52918 26391 52919 25751 52919 25754 52919

+
+
+
+
+ + + + + + + + + + + + + + +
diff --git a/robots/b1_description/meshes/thigh_mirror.dae b/robots/b1_description/meshes/thigh_mirror.dae new file mode 100644 index 0000000..315da75 --- /dev/null +++ b/robots/b1_description/meshes/thigh_mirror.dae @@ -0,0 +1,63 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + 周四 2月 24 03:20:46 2022 + 周四 2月 24 03:20:46 2022 + + + + + + + + + -0.0361457 -2.93696e-06 0.00282163 -0.036308 -7.18051e-06 9.24191e-05 -0.0363733 -2.93696e-06 9.10211e-05 -0.0366083 -3.81947e-05 -0.00492182 -0.0365826 -2.93696e-06 -0.00241629 0.0688404 -2.72486e-05 -0.00331615 0.0683073 -8.51978e-06 0.00172962 0.0683861 -2.93696e-06 0.00170805 0.0679483 -2.93696e-06 0.00416211 0.0677223 -3.42888e-06 0.00515356 0.0689889 -2.93696e-06 -0.00324333 -0.0372307 -2.93696e-06 -0.0100521 -0.0488143 -0.000447097 -0.281426 -0.049529 -0.000310507 -0.281783 -0.0489673 -0.000257145 -0.281426 -0.0496458 -7.61723e-05 -0.28162 -0.0497175 -0.000147721 -0.281757 -0.0495438 -0.000258255 -0.281762 -0.049684 -0.000310507 -0.281861 -0.0498555 -0.000502937 -0.281926 -0.0497675 -3.96562e-05 -0.281601 -0.0498555 -3.96562e-05 -0.281614 -0.0497916 -3.28512e-06 -0.281426 -0.053513 -0.000438486 -0.281922 -0.053507 -5.80963e-05 -0.281653 -0.0498555 -0.000310507 -0.281888 -0.053511 -0.000213046 -0.281833 -0.0498555 -0.000147721 -0.281778 -0.0535131 -0.000502937 -0.281926 -0.0535696 -0.000502937 -0.281921 -0.053796 -0.000383588 -0.281698 -0.0535058 -3.43396e-05 -0.281599 -0.0536158 -3.28022e-05 -0.281513 -0.0535042 -1.28109e-05 -0.281524 -0.0535098 -0.000149378 -0.28178 -0.0538067 -0.000325614 -0.281502 -0.0537873 -0.000217082 -0.281529 -0.0536317 -0.000502937 -0.281902 -0.0536264 -0.000317863 -0.281866 -0.0535658 -0.000151317 -0.281774 -0.0537269 -0.000209046 -0.281708 -0.053621 -0.00010286 -0.281687 -0.0536185 -5.94317e-05 -0.281604 -0.0537925 -0.000282979 -0.28163 -0.0537214 -0.000121441 -0.281572 -0.0537307 -0.000343345 -0.281799 -0.0536232 -0.000161767 -0.281761 -0.0535686 -0.000312397 -0.281882 -0.0535124 -0.000330075 -0.281895 0.013401 -0.000442686 -0.278573 0.0119659 -0.000329878 -0.281427 0.011636 -3.38413e-05 -0.281427 0.0133368 -1.84317e-05 -0.277863 0.0134335 -0.000455087 -0.278483 0.013417 -0.000478837 -0.278541 0.0134128 -0.000400872 -0.278532 0.0134183 -0.000212252 -0.278329 0.0135061 -0.000254196 -0.278106 0.013381 -3.35867e-05 -0.277872 0.0133679 -8.00743e-06 -0.277638 0.0133904 -0.000235467 -0.278428 0.0134224 -0.000116042 -0.278107 0.0133766 -0.000141866 -0.278283 0.0133593 -6.96553e-05 -0.2781 0.0133537 -5.32766e-05 -0.278041 0.0134018 -0.000383313 -0.278547 0.0134156 -0.000285743 -0.278436 0.0134218 -0.000418892 -0.278516 0.0134471 -0.000262075 -0.278321 0.0134519 -0.000403584 -0.278399 0.0134241 -5.67438e-05 -0.27788 0.0134988 -0.000125745 -0.277892 0.013585 -0.000188132 -0.277685 0.0134735 -0.000179592 -0.278109 0.0133937 -0.0177694 -0.278597 0.0133454 -0.0188714 -0.278655 0.0131251 -0.0198537 -0.279088 0.0133112 -0.0187969 -0.278764 0.0131007 -0.0197341 -0.279192 0.00486584 -0.0240936 -0.0526372 -0.00642596 -0.0244327 -0.0477473 -0.0074039 -0.024276 -0.0500882 -0.00461186 -0.02461 -0.0459695 -0.00477258 -0.0246609 -0.0457255 -0.00225358 -0.0247812 -0.0450185 0.000293653 -0.0249134 -0.0450408 0.0010875 -0.025003 -0.0449626 0.00389873 -0.0250592 -0.0467395 -0.00444961 -0.0244339 -0.0461956 -0.00219306 -0.0246033 -0.0452814 0.000246773 -0.0247344 -0.0453002 0.00249692 -0.0248055 -0.0462542 0.00264186 -0.024985 -0.0460372 0.0044299 -0.0249898 -0.0478589 0.00538099 -0.0249351 -0.0502257 -0.00430043 -0.02401 -0.0463699 -0.0033006 -0.0239497 -0.0458569 -0.00597257 -0.0238285 -0.0480098 -0.00620119 -0.0236452 -0.0484 0.000221947 -0.0244665 -0.0454715 -0.00214415 -0.0243332 -0.0454526 -0.00433335 -0.0241606 -0.0463387 -0.00212741 -0.0241849 -0.0454928 -0.00601585 -0.0239816 -0.0479924 -0.00689179 -0.0236748 -0.050166 0.00401769 -0.0242535 -0.0481189 0.00406479 -0.024543 -0.0480918 0.00237392 -0.0242493 -0.0464426 0.00419089 -0.0242489 -0.0484006 0.00427404 -0.0242461 -0.0485494 -0.00100568 -0.0241113 -0.0454005 -0.000387666 -0.0241458 -0.0454323 0.00240376 -0.0245385 -0.0463975 0.00199455 -0.0242407 -0.0462042 -0.00713024 -0.0241071 -0.0501374 -0.00618286 -0.0242584 -0.0479 -0.00694402 -0.0238415 -0.0501634 0.00420984 -0.0248103 -0.0480004 0.00511972 -0.0247562 -0.0502691 0.00494745 -0.0244877 -0.0502929 0.00491785 -0.0243872 -0.0526617 0.00499468 -0.0241527 -0.0514006 0.00496232 -0.0241244 -0.0520214 0.0533046 -0.0101426 0.0305397 0.0544407 -0.00800294 0.031396 0.0544217 -0.00800294 0.0323886 0.0545285 -0.00800294 0.0322257 0.0545928 -0.00800294 0.0317551 0.0545735 -0.00800294 0.0321085 0.0536383 -0.0103157 0.0310864 0.0522476 -0.0122658 0.0298829 0.0522865 -0.012357 0.0300033 0.0523005 -0.0124452 0.0301535 0.0535877 -0.0104091 0.031416 0.0534238 -0.0104425 0.0316857 0.0520775 -0.0125844 0.0307412 0.0501154 -0.0158753 0.0276298 0.0510887 -0.0141788 0.0290637 0.0522404 -0.0125577 0.0304567 0.0556807 -0.0155822 0.021017 0.0546523 -0.0161684 0.0211867 0.0525224 -0.0171697 0.021757 0.052467 -0.0172884 0.0215888 0.0500834 -0.0168564 0.0254545 0.0499356 -0.0170192 0.0254886 0.0525502 -0.017004 0.0219012 0.0543501 -0.0156299 0.0215144 0.053738 -0.0160252 0.0216005 0.0525108 -0.0166038 0.0220547 0.0544086 -0.015728 0.021502 0.0549132 -0.0151906 0.0215096 0.0559753 -0.0141132 0.0216966 0.0560726 -0.0141981 0.0217151 0.0572488 -0.0122641 0.0223155 0.0509467 -0.0171033 0.0234282 0.0525316 -0.0167052 0.0220355 0.0544665 -0.0158273 0.0214721 0.0574699 -0.0124545 0.0223997 0.0573516 -0.01236 0.02237 0.0502144 -0.0157659 0.0266348 0.0503402 -0.015441 0.0272631 0.0501737 -0.016248 0.0258127 0.0511109 -0.0140894 0.0289462 0.050258 -0.0157264 0.027486 0.0510828 -0.01389 0.0287408 0.0503317 -0.0155397 0.0273347 0.0502071 -0.0165621 0.0253715 0.0504592 -0.0167589 0.0244152 0.056562 -0.0146014 0.0214563 0.0509745 -0.0143136 0.0293 0.0501198 -0.0155451 0.0282992 0.050283 -0.0175456 0.0238035 0.0507658 -0.0174695 0.0233151 0.05159 -0.0175112 0.0221742 0.057756 -0.0126338 0.0223677 0.0563767 -0.0144704 0.0216266 0.056171 -0.0142932 0.0217097 0.0545723 -0.0160158 0.0213592 0.0508763 -0.0173007 0.023386 0.0525456 -0.0168077 0.0220034 0.0501805 -0.0166631 0.0254023 0.0511082 -0.0139913 0.0288369 0.0521748 -0.012152 0.0297673 0.058463 -0.010242 0.0231647 0.0593256 -0.0110142 0.0227192 0.0603741 -0.00800294 0.0238213 0.0580337 -0.0127467 0.0222082 0.0602078 -0.00800294 0.0239143 0.0600495 -0.00800294 0.0239605 0.0675103 -0.00800294 -0.0259164 0.0637722 -0.0176177 -0.0252022 0.0648108 -0.015185 -0.0259141 0.0664451 -0.0129777 -0.025484 0.066338 -0.0129624 -0.0257658 0.0671381 -0.00800294 -0.0262998 0.0668755 -0.00800294 -0.0263783 0.0632278 -0.0172072 -0.0256112 0.0658153 -0.0128138 -0.0261346 0.066113 -0.0129046 -0.0260083 0.0650909 -0.0153181 -0.0257831 0.0653045 -0.0154025 -0.025537 0.0612851 -0.0176828 -0.0344266 0.0611908 -0.0175792 -0.0343926 0.0619936 -0.0191654 -0.0250656 0.0599933 -0.020334 -0.0253838 0.058427 -0.0208699 -0.0269252 0.0598731 -0.0193823 -0.0340924 0.0584323 -0.0203062 -0.0328009 0.0574368 -0.0209871 -0.0310094 0.0576412 -0.0209331 -0.0288968 0.0600686 -0.0202364 -0.0256037 0.0577469 -0.0207087 -0.028928 0.0584776 -0.0198517 -0.0325912 0.059472 -0.0191618 -0.03361 0.0598058 -0.0190544 -0.0338483 0.0584892 -0.020085 -0.0326743 0.0584914 -0.0199675 -0.0326268 0.0598433 -0.0191689 -0.0339113 0.0616548 -0.0185785 -0.0255249 0.0586118 -0.0202347 -0.0272224 0.059196 -0.0200048 -0.0266064 0.0600606 -0.0197301 -0.0260029 0.0595766 -0.0198354 -0.0263087 0.0586184 -0.0203513 -0.0271996 0.0586104 -0.0204695 -0.027165 0.0617265 -0.0186897 -0.0255056 0.0633433 -0.0173078 -0.0255924 0.0571269 -0.0211914 -0.0301978 0.0577433 -0.0208018 -0.0324718 0.0583106 -0.020479 -0.0329544 0.0598358 -0.0195412 -0.0343218 0.058965 -0.020746 -0.0260665 0.0574731 -0.0211125 -0.0288517 0.057578 -0.0211691 -0.0279032 0.0613716 -0.017784 -0.0344855 0.0576055 -0.0208088 -0.0309518 0.0577094 -0.0205849 -0.0309006 0.0585472 -0.0206928 -0.0270619 0.0601026 -0.0200667 -0.0258058 0.0600862 -0.019847 -0.0259549 0.0619186 -0.0190128 -0.0253017 0.0617969 -0.0188029 -0.0254622 0.0635837 -0.0174973 -0.0254532 0.0650807 -0.00800294 -0.0352634 0.0653053 -0.00800294 -0.0354139 0.0654666 -0.00800294 -0.0356279 0.0615182 -0.0179796 -0.0346934 0.0630139 -0.0156213 -0.0348453 0.0644125 -0.0132905 -0.0358951 0.0632964 -0.0158784 -0.0356487 0.0615846 -0.0181109 -0.0349791 0.0655482 -0.00800294 -0.0358818 0.0633045 -0.0158466 -0.0353537 0.064416 -0.0132702 -0.0355986 0.064304 -0.013212 -0.0353036 0.0632066 -0.015756 -0.0350624 0.0640901 -0.0131253 -0.0350814 0.0627851 -0.0154804 -0.0347422 -0.011241 -0.00800294 0.042319 -0.011138 -0.00849444 0.0421273 -0.0109457 -0.00800294 0.0424273 -0.010827 -0.00800294 0.0424346 -0.00923198 -0.0122964 0.0398535 -0.00909274 -0.012209 0.0398228 -0.00033308 -0.0122106 0.0446903 -0.00827382 -0.0139738 0.0385087 -0.00741138 -0.0154176 0.0373864 -0.0069147 -0.015578 0.0373831 -0.00479822 -0.0165961 0.0369862 -5.61134e-05 -0.0152658 0.0410626 -0.00100962 -0.0162361 0.0391635 -0.00263103 -0.0167322 0.0376945 -0.00475737 -0.0164348 0.0371168 -0.00872552 -0.0141816 0.0382835 -0.000446692 -0.0147276 0.0407858 -0.00058976 -0.0151189 0.0402679 -0.00115673 -0.0159512 0.0391377 -0.00111873 -0.0160488 0.0391554 -0.00180652 -0.0161823 0.0384069 -0.00205623 -0.0162559 0.0381942 -0.000406779 -0.0133658 0.0425226 -0.000424692 -0.0148263 0.0408471 -0.00600021 -0.0154036 0.0373736 -0.0066255 -0.0152421 0.037552 -0.00797177 -0.0136845 0.0384684 -0.00656062 -0.0151448 0.0375532 -0.00707182 -0.0145508 0.0378115 -0.00816099 -0.0138837 0.0385165 -0.0089681 -0.0121041 0.0397632 -0.00954789 -0.0124177 0.0398304 -0.00269214 -0.0163477 0.0377735 -0.00267348 -0.0165431 0.0377561 -0.00349944 -0.0163181 0.0374303 -0.00470669 -0.0162467 0.0371993 -0.00256776 -0.0168965 0.0375927 -0.000865359 -0.0163953 0.0391338 -0.00582873 -0.0163474 0.0368848 -0.00482566 -0.0167159 0.0368229 -0.00380171 -0.0169459 0.0369587 -0.00194125 -0.0169651 0.0378095 -0.00085523 -0.0119616 0.0443594 -0.000933452 -0.0117802 0.0440922 -0.000335941 -0.0135729 0.0427121 -0.000384362 -0.0149262 0.0409054 -0.000384674 -0.013471 0.0426167 -0.000874673 -0.0155627 0.0396111 -0.00118314 -0.0158545 0.0391121 -4.82894e-05 -0.0138047 0.0429576 -0.000261052 -0.0136656 0.0428039 -0.000249271 -0.0151153 0.0410031 -0.00676885 -0.0154271 0.0374992 -0.008059 -0.0137856 0.0385023 -0.00887887 -0.0120025 0.0396886 -0.00150625 -0.00987961 0.0450156 -0.00155506 -0.0100544 0.0456661 -0.000921367 -0.0116645 0.043955 -0.0020627 -0.00800294 0.0466203 -0.00135287 -0.0101482 0.0459387 -0.00198547 -0.00800294 0.0467902 -0.000659793 -0.0120739 0.0446036 -0.0380275 -0.00800294 -0.0279636 -0.0361055 -0.0151486 -0.0281224 -0.0358583 -0.0150014 -0.0280833 -0.0365857 -0.0154137 -0.0288266 -0.0377209 -0.0129895 -0.0287643 -0.038737 -0.00800294 -0.0283073 -0.0347341 -0.0173766 -0.0283712 -0.0363469 -0.0152883 -0.028282 -0.034878 -0.0175036 -0.0286294 -0.036895 -0.0128051 -0.0280261 -0.0371977 -0.0128152 -0.0280622 -0.0374618 -0.0129071 -0.0282206 -0.0376468 -0.0129686 -0.0284766 -0.0365167 -0.0153818 -0.0285387 -0.0339365 -0.0166655 -0.0191618 -0.0300669 -0.020267 -0.0257913 -0.0330763 -0.0190214 -0.0284746 -0.0349381 -0.0175468 -0.028918 -0.0312466 -0.0200794 -0.027595 -0.0290775 -0.0209158 -0.0238671 -0.0296745 -0.0205171 -0.0217194 -0.0326118 -0.0186593 -0.0189654 -0.0307802 -0.0199083 -0.0198059 -0.0309059 -0.0198101 -0.0199972 -0.0300155 -0.020341 -0.0206781 -0.0342367 -0.0169551 -0.0189152 -0.0325985 -0.0185095 -0.0192129 -0.0309859 -0.019643 -0.0201831 -0.0298189 -0.0203419 -0.0218193 -0.029278 -0.0207995 -0.0238622 -0.0313097 -0.0199101 -0.0274159 -0.0330395 -0.0188678 -0.0282448 -0.0299166 -0.0200086 -0.0219366 -0.030989 -0.0193144 -0.020388 -0.029547 -0.0204027 -0.0238631 -0.0297009 -0.0200425 -0.0226248 -0.0299015 -0.0201238 -0.0219037 -0.0324606 -0.0181932 -0.0194624 -0.034054 -0.0167769 -0.0191057 -0.0309338 -0.0196537 -0.0268954 -0.0327774 -0.0184837 -0.0279832 -0.0328908 -0.0185529 -0.0280271 -0.0300006 -0.0200696 -0.0255814 -0.0300811 -0.020039 -0.025745 -0.0313191 -0.0196964 -0.0272781 -0.0313039 -0.0195833 -0.0272306 -0.0329498 -0.0186628 -0.0280783 -0.034428 -0.0170876 -0.0281753 -0.0345313 -0.0171869 -0.0282094 -0.0320589 -0.0190955 -0.0189291 -0.0316831 -0.0193492 -0.0191343 -0.0298531 -0.0206609 -0.0259692 -0.0325193 -0.0183039 -0.019401 -0.0310037 -0.0194284 -0.0203332 -0.0294429 -0.0206217 -0.0238607 -0.0299887 -0.0204847 -0.0258689 -0.0354926 -0.0147854 -0.019033 -0.0361931 -0.0125582 -0.0190511 -0.0367568 -0.0126473 -0.0187769 -0.0378533 -0.00800294 -0.0187177 -0.0377335 -0.00800294 -0.0188284 -0.0369085 -0.0127069 -0.0184842 -0.0358861 -0.0150369 -0.0182414 -0.0343477 -0.0170716 -0.0186404 -0.0358615 -0.0150133 -0.0185409 -0.0357234 -0.0149246 -0.0188334 -0.0365051 -0.0125541 -0.0189772 0.0182715 -0.000193928 0.0511949 0.0111688 -0.000307105 0.0511061 0.0121425 -0.000195328 0.051158 0.00418336 -0.000310583 0.0500495 -0.00556195 -0.000203195 0.046856 0.000181123 -0.000200075 0.0489798 -0.000583702 -0.00031362 0.0487588 -0.0326889 -0.000329455 0.0197814 -0.0293915 -0.000332719 0.0260863 -0.0252417 -0.000332498 0.0319355 -0.0216064 -0.000330446 0.0359459 -0.0207471 -0.000329835 0.0367822 -0.0118755 -0.000322487 0.0435855 -0.0109786 -0.000206527 0.044103 -0.0343633 -0.000326327 0.0154712 -0.0378246 -0.000218023 -0.00759284 -0.037592 -0.000316409 -0.00476755 -0.0376563 -0.000314278 -0.00554065 -0.0378164 -0.000193976 -0.00759321 -0.0377143 -0.000310651 -0.00622821 -0.03775 -9.15217e-05 -0.00759994 -0.0364925 -2.93696e-06 0.00458869 -0.036607 -2.59447e-05 0.0046018 -0.0314232 -2.6352e-05 0.0220477 -0.0337055 -2.93696e-06 0.0164427 -0.0282912 -2.93696e-06 0.0272664 -0.0206211 -2.62393e-05 0.0366497 -0.0205412 -2.93696e-06 0.0365657 -0.0158963 -2.93696e-06 0.040497 -0.010893 -2.55581e-05 0.0439563 -0.0376483 -2.41635e-05 -0.00760767 -0.0367114 -9.93741e-05 0.00461376 -0.0367759 -0.000210007 0.00462114 -0.0357222 -0.000208967 0.0106718 -0.0339739 -0.000210715 0.0165402 -0.0315754 -0.000213672 0.0221238 -0.0284776 -0.000101882 0.0273883 -0.0285313 -0.00021509 0.0274235 -0.0248438 -0.000101636 0.0322979 -0.0248932 -0.000214593 0.032339 -0.0206939 -0.000100681 0.0367263 -0.0207384 -0.000212658 0.036773 -0.0160676 -0.000209803 0.040725 -0.0109457 -9.76622e-05 0.0440466 -0.00553561 -9.60265e-05 0.0467958 0.00612283 -9.319e-05 0.0503528 0.00611095 -0.000197399 0.050418 0.018268 -9.14963e-05 0.0511283 0.024381 -0.000193257 0.0505151 0.0243845 -0.000303968 0.0505356 0.0243697 -9.11696e-05 0.0504493 0.0121468 -9.21791e-05 0.0510916 0.000200407 -9.44984e-05 0.0489166 -0.00549397 -2.51878e-05 0.0467007 -0.0160286 -9.92738e-05 0.0406731 -0.0159655 -2.59221e-05 0.0405891 -0.0247624 -2.64543e-05 0.03223 -0.0283888 -2.65096e-05 0.0273302 -0.0315178 -0.000101182 0.022095 -0.033814 -2.60234e-05 0.0164821 -0.033913 -9.97231e-05 0.016518 -0.035659 -9.88621e-05 0.0106569 -0.0355568 -2.58292e-05 0.0106329 -0.0375399 -2.94375e-06 -0.00761699 -0.000113931 -2.93696e-06 0.0485935 0.000230547 -2.48412e-05 0.0488179 0.00614121 -2.45438e-05 0.0502517 0.0121534 -2.43137e-05 0.0509896 0.00616122 -2.93696e-06 0.0501417 0.0182627 -2.41582e-05 0.0510265 0.0121605 -2.93696e-06 0.0508786 0.0182569 -2.93696e-06 0.0509158 0.062292 -9.39995e-05 0.0226042 0.03028 -2.33036e-05 0.0489758 0.0302494 -2.93696e-06 0.0488716 0.0359605 -2.33765e-05 0.0469474 0.0370709 -2.93696e-06 0.0463426 0.0413954 -2.3506e-05 0.044266 0.046523 -2.36762e-05 0.0409476 0.0462477 -2.93696e-06 0.0410127 0.051193 -2.38605e-05 0.0370896 0.0541175 -2.93696e-06 0.0339889 0.0590049 -2.93696e-06 0.0277647 0.0303279 -0.000192638 0.0491393 0.0360269 -0.000193318 0.0471044 0.0414896 -0.000306635 0.0444319 0.0466355 -0.000308818 0.0411011 0.0513221 -0.000311174 0.0372287 0.054829 -0.00031299 0.0336482 0.0243526 -2.40837e-05 0.0503489 0.0414796 -0.000194527 0.0444143 0.0466239 -0.000196116 0.0410852 0.0513093 -0.000197837 0.0372148 0.0554805 -9.34206e-05 0.0327714 0.0555314 -0.000199426 0.0328148 0.0591837 -9.39483e-05 0.0278844 0.0592392 -0.000200514 0.0279216 0.0623513 -0.00020062 0.0226346 0.059097 -2.41472e-05 0.0278263 0.0512637 -9.26504e-05 0.0371657 0.0554013 -2.40307e-05 0.0327037 0.0465842 -9.18175e-05 0.0410311 0.0414463 -9.10487e-05 0.0443557 0.0360006 -9.04648e-05 0.0470422 0.0303089 -9.01361e-05 0.0490745 0.0268108 -2.93696e-06 0.0497549 0.0667413 -0.000308686 0.0120519 0.0666543 -8.72832e-05 0.0120241 0.062199 -2.41585e-05 0.0225565 0.0692945 -0.000189035 0.000888879 0.0699854 -0.000191296 -0.0106297 0.0697133 -2.35767e-05 -0.00486669 0.0697188 -2.93696e-06 -0.00792168 0.0691282 -2.36145e-05 0.000864787 0.0692281 -8.91151e-05 0.00087926 0.0665619 -2.44659e-05 0.0119945 0.0646063 -2.43764e-05 0.0173472 0.0667228 -0.000196697 0.012046 0.0693167 -0.000298138 0.000892093 0.0699673 -0.000302339 -0.0118412 0.0687551 -0.000193152 -0.0221226 0.0689489 -0.000307819 -0.0211423 0.0698171 -2.38657e-05 -0.0106256 0.0699129 -8.47197e-05 -0.0106279 0.0685893 -2.40719e-05 -0.0220921 0.0693596 -2.93696e-06 -0.0160698 0.0312516 -0.000324372 -0.197118 0.0255419 -0.000200154 -0.223127 0.05863 -9.29547e-05 -0.0715731 0.0686894 -9.11182e-05 -0.0221105 0.0682494 -2.93696e-06 -0.0232722 0.0585281 -2.38426e-05 -0.0715512 0.0668908 -2.93696e-06 -0.0302633 0.0475073 -2.54006e-05 -0.122071 0.0472635 -2.93696e-06 -0.12265 0.0587137 -0.000312498 -0.071591 0.0476757 -0.000213338 -0.122108 0.0586955 -0.000198702 -0.0715871 0.0476876 -0.000332235 -0.122111 0.0386557 -2.93696e-06 -0.161905 0.0254765 -9.3658e-05 -0.223113 0.0476119 -0.000100072 -0.122094 0.0226043 -2.93696e-06 -0.23485 0.0252666 -2.93696e-06 -0.223067 0.0253744 -2.39972e-05 -0.22309 0.0255594 -0.000314475 -0.223131 0.0148056 -0.000191844 -0.272126 0.0148264 -0.000302937 -0.27213 0.0133143 -2.93696e-06 -0.277626 0.0146455 -2.57731e-05 -0.272091 0.0134264 -2.57731e-05 -0.27765 0.0135215 -9.08049e-05 -0.277671 0.0147406 -9.08049e-05 -0.272111 0.0148041 -0.000188132 -0.272125 -0.0387694 -0.000305705 -0.0194397 -0.0382062 -2.93696e-06 -0.0160299 -0.0387564 -2.93696e-06 -0.0232552 -0.0407236 -9.37386e-05 -0.048613 -0.0378204 -0.000204703 -0.0075937 -0.0407976 -0.000223016 -0.0486082 -0.037821 -0.000218698 -0.00759291 -0.0378155 -0.000191457 -0.00759463 -0.0453715 -0.000332475 -0.129262 -0.0442433 -0.000101145 -0.110192 -0.0441125 -1.70698e-05 -0.110199 -0.0436399 -2.93696e-06 -0.103262 -0.0452739 -2.93696e-06 -0.132906 -0.0498239 -2.37984e-05 -0.212838 -0.0418191 -0.000314972 -0.0654216 -0.0443144 -0.000239543 -0.110188 -0.0442886 -0.000166871 -0.110189 -0.0407694 -0.000154747 -0.0486101 -0.0405967 -1.60826e-05 -0.0486209 -0.0499943 -0.00019682 -0.212829 -0.0527805 -0.000302937 -0.262913 -0.0538016 -0.000302937 -0.28141 -0.0526598 -2.18747e-05 -0.264267 -0.0536068 -2.18747e-05 -0.28142 -0.0536129 -2.42648e-05 -0.28142 -0.0537109 -8.79072e-05 -0.281415 -0.0537798 -0.00019067 -0.281411 -0.0512969 -2.25038e-05 -0.247144 -0.0509622 -0.000303852 -0.234723 -0.0499273 -9.22499e-05 -0.212833 -0.0513994 -8.79324e-05 -0.247138 -0.0514682 -0.000190723 -0.247133 0.0130837 -0.0197009 -0.279226 0.0130986 -0.0197291 -0.279196 0.0131188 -0.0197941 -0.279141 0.0110549 -0.0195029 -0.28775 0.00955049 -0.0195232 -0.295297 0.0127875 -0.0195237 -0.279828 0.00971683 -0.0196918 -0.295334 0.0130283 -0.0196369 -0.279339 -0.050188 -0.0197301 -0.324075 -0.0502832 -0.0198029 -0.32389 -0.050101 -0.0195751 -0.324035 -0.0500184 -0.0195216 -0.323997 -0.0501485 -0.0196333 -0.324057 -0.0439676 -0.0198029 -0.334246 -0.000808873 -0.0196381 -0.373933 0.0235967 -0.0196333 -0.345967 0.0217062 -0.0195216 -0.340246 0.0118333 -0.0195751 -0.318234 0.00836198 -0.0195751 -0.301126 0.00827293 -0.0195216 -0.301107 0.0196537 -0.0195029 -0.363228 0.0225302 -0.0195029 -0.357323 -0.000892611 -0.0195029 -0.373679 -0.0068068 -0.0195029 -0.3727 -0.017434 -0.0195029 -0.36606 -0.0170728 -0.0195216 -0.366593 -0.0361753 -0.0195216 -0.34345 -0.0283698 -0.0195029 -0.352797 -0.053456 -0.0195029 -0.313386 -0.0524165 -0.0198029 -0.318403 -0.0495383 -0.0195029 -0.324769 -0.047364 -0.0198029 -0.329371 -0.0471083 -0.0195029 -0.329214 -0.0431803 -0.0195029 -0.334749 -0.0546857 -0.0195216 -0.301388 -0.0545816 -0.0195029 -0.301391 0.00912182 -0.0198029 -0.298147 0.00845631 -0.0197317 -0.301145 0.00944463 -0.0195029 -0.295274 0.0118809 -0.0196333 -0.318212 0.0219607 -0.0195029 -0.341108 0.0117504 -0.0195216 -0.318271 0.00918526 -0.0195029 -0.312812 0.00936643 -0.0195751 -0.31274 0.00941502 -0.0196333 -0.31272 0.00781004 -0.0195029 -0.307029 0.00841319 -0.0196333 -0.301137 0.00965078 -0.0195897 -0.295319 0.0218371 -0.0196333 -0.340188 0.0236392 -0.0197282 -0.34596 0.0235451 -0.0195751 -0.345976 0.0217893 -0.0195751 -0.340209 0.00846461 -0.0198029 -0.301148 0.00803815 -0.0198029 -0.305677 0.00810077 -0.0197334 -0.307004 0.00810892 -0.0198029 -0.307004 0.0119206 -0.0197301 -0.318194 0.0218768 -0.0197301 -0.34017 0.0236485 -0.0198029 -0.345958 0.0238535 -0.0198029 -0.347428 0.00805656 -0.0196333 -0.307008 0.00945547 -0.0197301 -0.312704 0.0234492 -0.0195193 -0.345993 0.0236845 -0.0195032 -0.349019 0.0233024 -0.0198029 -0.355705 0.0151559 -0.0198029 -0.368597 0.0225781 -0.0196333 -0.357953 0.0239044 -0.0198029 -0.352028 0.0225288 -0.0195751 -0.357936 0.0224429 -0.0195216 -0.357905 0.0198156 -0.0195751 -0.363337 0.0197322 -0.0195183 -0.363281 0.0186962 -0.0195029 -0.364551 0.0157689 -0.0195204 -0.367815 0.0158661 -0.0196333 -0.367925 0.019859 -0.0196333 -0.363366 0.015799 -0.0196388 -0.367989 -0.0068902 -0.0197275 -0.372978 -0.00689291 -0.0198029 -0.372988 -0.0124532 -0.0198029 -0.370519 -0.0068628 -0.0195751 -0.372887 -0.00687783 -0.0196333 -0.372937 -0.000901768 -0.0196333 -0.373927 0.0226192 -0.0197301 -0.357968 0.0198947 -0.0197277 -0.36339 0.0178935 -0.0195216 -0.365685 0.0158314 -0.0195751 -0.367886 0.015702 -0.0195029 -0.36774 0.0133216 -0.0195033 -0.36961 0.01087 -0.0198029 -0.371389 0.00790923 -0.0198029 -0.372652 0.00514105 -0.0198029 -0.373438 0.00490951 -0.0195029 -0.373181 -0.000896388 -0.0195191 -0.373777 -0.000899832 -0.0195751 -0.373874 -0.0039067 -0.0195216 -0.37348 -0.00683583 -0.0195204 -0.372797 -0.00965132 -0.0195034 -0.371665 -0.0172067 -0.0197288 -0.366723 -0.0171755 -0.0196333 -0.366693 -0.0172132 -0.0198029 -0.366729 -0.0207974 -0.0198029 -0.362497 -0.0210944 -0.0197301 -0.362121 -0.0362861 -0.0196333 -0.343541 -0.0363198 -0.0197301 -0.343568 -0.0438937 -0.0196333 -0.334255 -0.0362457 -0.0195751 -0.343507 -0.0210607 -0.0196333 -0.362093 -0.017138 -0.0195751 -0.366656 -0.0266847 -0.0198029 -0.355323 -0.0439279 -0.0197301 -0.334282 -0.0438526 -0.0195751 -0.334223 -0.0437811 -0.0195216 -0.334167 -0.0210202 -0.0195751 -0.36206 -0.0209499 -0.0195216 -0.362002 -0.0122977 -0.0195029 -0.370262 -0.0111997 -0.0195029 -0.370889 -0.0539501 -0.0197301 -0.312425 -0.0547654 -0.0198029 -0.306357 -0.0547565 -0.0197301 -0.306357 -0.054713 -0.0196333 -0.306354 -0.0539074 -0.0196333 -0.312417 -0.053856 -0.0195751 -0.312407 -0.0546608 -0.0195751 -0.30635 -0.05457 -0.0195216 -0.306343 -0.0537667 -0.0195216 -0.312389 -0.054803 -0.0196965 -0.299911 -0.0548815 -0.0198029 -0.301383 -0.0546344 -0.0195245 -0.29992 -0.0547767 -0.0195751 -0.301386 -0.054829 -0.0196333 -0.301385 -0.0548613 -0.0196947 -0.301384 -0.0548725 -0.0197301 -0.301383 -0.0548224 -0.0198054 -0.29991 -0.0546279 -0.0194178 -0.296765 -0.0544594 -0.0192516 -0.296803 -0.0545229 -0.0195029 -0.299926 -0.0545614 -0.0193172 -0.296786 -0.0547367 -0.0195928 -0.299915 -0.0539893 -0.0118431 -0.284811 -0.0539501 -0.0107199 -0.2841 -0.0541783 -0.0155951 -0.288235 -0.0542404 -0.0172321 -0.290987 -0.0544851 -0.0187499 -0.293791 -0.0541855 -0.0184671 -0.293908 -0.0540246 -0.0171573 -0.291041 -0.0541373 -0.0171738 -0.291026 -0.0539919 -0.0153781 -0.288425 -0.0542976 -0.0184857 -0.293896 -0.0540955 -0.0154296 -0.288377 -0.0537645 -0.0105774 -0.284355 -0.0537476 -0.00467836 -0.282112 -0.0538128 -0.00469684 -0.282005 -0.0538126 -0.00150294 -0.28161 -0.0539705 -0.0132041 -0.286126 -0.0538686 -0.0106109 -0.284292 -0.0538748 -0.00782299 -0.282736 -0.0536895 -0.00772515 -0.283012 -0.0536432 -0.00466669 -0.282183 -0.0538788 -0.0153641 -0.288443 -0.0538666 -0.0131609 -0.286182 -0.053753 -0.0131495 -0.286202 -0.0536317 -0.00150294 -0.281902 -0.0535131 -0.00150294 -0.281926 -0.0496723 -0.00150294 -0.281898 -0.0496723 -0.000502937 -0.281898 -0.0495066 -0.000502937 -0.281814 -0.0510139 -0.0116817 -0.284642 -0.050847 -0.00927842 -0.283507 -0.0510729 -0.0116214 -0.28473 -0.0509184 -0.00924178 -0.283556 -0.051083 -0.00918098 -0.283617 -0.0501168 -0.00415638 -0.282123 -0.0498555 -0.00150294 -0.281926 -0.0509659 -0.0117987 -0.284469 -0.0509012 -0.0108513 -0.283966 -0.0507376 -0.00935741 -0.283385 -0.0507862 -0.00931746 -0.28345 -0.0506853 -0.00929865 -0.283276 -0.0505566 -0.00674745 -0.282691 -0.0499102 -0.00419763 -0.282091 -0.0504264 -0.00678997 -0.282653 -0.0503111 -0.00683795 -0.282585 -0.0524138 -0.0195029 -0.2999 -0.0509803 -0.0117397 -0.284557 -0.0521289 -0.0195029 -0.298696 -0.0518613 -0.0195029 -0.29745 -0.0515117 -0.0148541 -0.287793 -0.0513485 -0.0114945 -0.284905 -0.051565 -0.0114666 -0.284935 -0.0512212 -0.0166002 -0.289095 -0.0511301 -0.0152617 -0.287443 -0.051311 -0.0149552 -0.287712 -0.0511486 -0.0115703 -0.284802 -0.0515623 -0.0195029 -0.295273 -0.0516136 -0.0193341 -0.295479 -0.0517291 -0.0148179 -0.287814 -0.051747 -0.0191361 -0.295521 -0.0515146 -0.0175287 -0.291358 -0.0519497 -0.0190045 -0.295543 -0.0520647 -0.0183903 -0.293696 -0.0517162 -0.0174087 -0.291412 -0.0497296 -0.00424483 -0.281988 -0.0488061 -0.000502937 -0.281426 -0.0495066 -0.00150294 -0.281814 -0.0498502 -0.0195029 -0.282095 -0.0502193 -0.00688729 -0.282494 -0.0386432 0.00239706 -0.0954285 -0.0386432 0.00239706 -0.0941035 -0.0375932 0.00239706 -0.0957099 -0.0365433 0.00239706 -0.0975286 -0.0352183 0.00239706 -0.0975286 -0.0368246 0.00239706 -0.0985785 -0.0375933 0.00239706 -0.0993472 -0.0369308 0.00239706 -0.100495 -0.0403558 0.00239706 -0.100495 -0.0404619 0.00239706 -0.0985785 -0.0404619 0.00239706 -0.0964785 -0.0416094 0.00239706 -0.095816 -0.0403557 0.00239706 -0.0945624 0.0437644 0.00239706 -0.106031 0.0475768 0.00239706 -0.108997 0.0489018 0.00239706 -0.108997 0.0454768 0.00239706 -0.111097 0.0437643 0.00239706 -0.111963 0.0436582 0.00239706 -0.110047 0.0425107 0.00239706 -0.110709 0.0420518 0.00239706 -0.108997 0.0357257 0.00239706 -0.165284 0.0361846 0.00239706 -0.166997 0.0327596 0.00239706 -0.169097 0.034472 0.00239706 -0.169963 0.0327595 0.00239706 -0.170422 0.0317096 0.00239706 -0.168815 0.031047 0.00239706 -0.169963 0.0297934 0.00239706 -0.168709 0.0306596 0.00239706 -0.166997 0.0317096 0.00239706 -0.165178 0.0297935 0.00239706 -0.165284 0.0310471 0.00239706 -0.164031 0.0327596 0.00239706 -0.164897 0.0327596 0.00239706 -0.163572 0.0344721 0.00239706 -0.164031 0.0338096 0.00239706 -0.165178 -0.0400974 0.00239706 -0.155766 -0.0384911 0.00239706 -0.156816 -0.0400974 0.00239706 -0.157866 -0.0408661 0.00239706 -0.158635 -0.0419161 0.00239706 -0.160241 -0.0436286 0.00239706 -0.159782 -0.0437347 0.00239706 -0.157866 -0.0448822 0.00239706 -0.158528 -0.0440161 0.00239706 -0.156816 -0.0453411 0.00239706 -0.156816 -0.0448822 0.00239706 -0.155103 -0.042966 0.00239706 -0.154997 -0.041916 0.00239706 -0.154716 -0.040866 0.00239706 -0.154997 0.0222995 0.00239706 -0.224047 0.023447 0.00239706 -0.224709 0.0215308 0.00239706 -0.224815 0.0221933 0.00239706 -0.225963 0.0204808 0.00239706 -0.225097 0.0204808 0.00239706 -0.226422 0.0187683 0.00239706 -0.225963 0.0175147 0.00239706 -0.224709 0.0194309 0.00239706 -0.221178 0.0204809 0.00239706 -0.220897 0.0204809 0.00239706 -0.219572 0.0215309 0.00239706 -0.221178 0.0221934 0.00239706 -0.22003 0.0225809 0.00239706 -0.222997 0.0114818 0.00239706 -0.273383 0.0113756 0.00239706 -0.275299 0.00966308 0.00239706 -0.274433 0.00795057 0.00239706 -0.275299 0.00784444 0.00239706 -0.273383 0.00756311 0.00239706 -0.272333 0.00623811 0.00239706 -0.272333 0.006697 0.00239706 -0.270621 0.00861313 0.00239706 -0.270515 0.00966316 0.00239706 -0.268908 0.0114818 0.00239706 -0.271283 0.0130881 0.00239706 -0.272333 -0.0502705 0.00239706 -0.276262 -0.0505518 0.00239706 -0.275212 -0.0501643 0.00239706 -0.272246 -0.0484518 0.00239706 -0.273112 -0.0474018 0.00239706 -0.273394 -0.0467393 0.00239706 -0.272246 -0.0454857 0.00239706 -0.2735 -0.0450268 0.00239706 -0.275213 -0.0454857 0.00239706 -0.276925 -0.0467394 0.00239706 -0.278179 -0.0484519 0.00239706 -0.278637 -0.0501644 0.00239706 -0.278179 -0.00259624 -0.00250294 0.0404235 -0.00354792 -0.00250294 0.0394719 -0.00297294 -0.00250294 0.0384759 -0.00709958 -0.00250294 0.0404236 -0.00859789 -0.00250294 0.0417236 -0.00709954 -0.00250294 0.0430236 -0.00484786 -0.00250294 0.0443236 -0.00297285 -0.00250294 0.0449711 -0.00259621 -0.00250294 0.0430235 -0.00160027 -0.00250294 0.0435985 -0.00224789 -0.00250294 0.0417235 -0.00109789 -0.00250294 0.0417235 0.0569214 -0.00250294 0.024703 0.0565447 -0.00250294 0.0227554 0.0533697 -0.00250294 0.0237514 0.0520697 -0.00250294 0.0260031 0.0546698 -0.00250294 0.028603 0.0565448 -0.00250294 0.0292506 0.0569214 -0.00250294 0.027303 0.0572697 -0.00250294 0.026003 0.0584197 -0.00250294 0.026003 0.0584046 -0.00250294 -0.029997 0.0608547 -0.00250294 -0.0277454 0.0621547 -0.00250294 -0.026247 0.0640297 -0.00250294 -0.0267495 0.0634547 -0.00250294 -0.0277454 0.0644063 -0.00250294 -0.0286971 0.0647546 -0.00250294 -0.0299971 0.0659046 -0.00250294 -0.0299971 0.0644063 -0.00250294 -0.0312971 0.0634546 -0.00250294 -0.0322487 0.0621546 -0.00250294 -0.032597 0.0608546 -0.00250294 -0.0322487 0.0621546 -0.00250294 -0.033747 0.0602796 -0.00250294 -0.0332446 0.0599029 -0.00250294 -0.031297 0.058907 -0.00250294 -0.031872 -0.0322017 -0.00250294 -0.0269224 -0.0340767 -0.00250294 -0.0262748 -0.0353767 -0.00250294 -0.0259264 -0.0340767 -0.00250294 -0.0274248 -0.0363284 -0.00250294 -0.0249748 -0.0373242 -0.00250294 -0.0217998 -0.0359516 -0.00250294 -0.0204272 -0.0327767 -0.00250294 -0.0214231 -0.0308291 -0.00250294 -0.0217998 -0.0314767 -0.00250294 -0.0236748 -0.031825 -0.00250294 -0.0249748 -0.0535288 -0.0046638 -0.282206 -0.0535752 -0.00771938 -0.283034 -0.0506904 -0.0067136 -0.282697 -0.0509373 -0.00772234 -0.283035 -0.0536505 -0.0105688 -0.284376 -0.05217 -0.0189608 -0.295542 -0.0543485 -0.0192317 -0.296813 -0.051935 -0.0173671 -0.291422 -0.051694 -0.0142309 -0.287198 -0.0538089 -0.014231 -0.287198 -0.0227009 -0.0195029 -0.359705 -0.0524201 -0.0195029 -0.299926 -0.0033481 -0.0195029 -0.37346 0.0120004 -0.0195029 -0.281427 -0.0345351 -0.0195029 -0.345284 0.0236055 -0.0195029 -0.352002 0.0233528 -0.0195029 -0.346009 0.00499085 -0.0195029 -0.349996 0.0236772 -0.0195029 -0.349173 0.00843789 -0.0195029 -0.310574 -9.08344e-06 -0.0195029 -0.344996 0.00432101 -0.0195029 -0.347496 0.0118323 -0.0195029 -0.318704 -0.0521311 -0.0195029 -0.31831 -0.0544662 -0.0195029 -0.306336 -0.051687 -0.0195029 -0.296447 -0.0509659 -0.0195029 -0.284469 -0.0025092 -0.0195029 -0.354326 -9.21146e-06 -0.0195029 -0.354996 0.0107341 -0.0195029 -0.371121 0.0125643 -0.0195029 -0.370087 -0.00433924 -0.0195029 -0.347496 0.00782783 -0.0195029 -0.303326 -0.0488061 -0.0195029 -0.281426 -0.00250909 -0.0195029 -0.345666 -0.0506795 -0.0195029 -0.283263 -0.0513359 -0.0178959 -0.291171 0.0655413 -0.00800294 -0.0361486 0.0644063 -0.00800294 -0.0312971 0.0665614 -0.00800294 -0.030944 0.0649203 -0.00800294 -0.0352104 0.0611908 -0.00800294 -0.0343926 0.0621546 -0.00800294 -0.032597 0.0608547 -0.00800294 -0.0277454 0.0616126 -0.00800294 -0.0255298 0.0621547 -0.00800294 -0.027397 0.0674559 -0.00800294 -0.0260159 0.0673583 -0.00800294 -0.0261391 0.0672195 -0.00800294 -0.0262534 0.0638113 -0.0131177 -0.0349672 0.0666017 -0.00800294 -0.0263652 0.066443 -0.00898291 -0.0263304 0.0631184 -0.00800294 -0.0256015 0.0661334 -0.0105362 -0.0262625 0.0654945 -0.0128204 -0.0261224 0.0645436 -0.0150436 -0.025914 0.0597932 -0.00800294 -0.0338276 0.0582599 -0.00800294 -0.0322512 0.0577386 -0.0203496 -0.0308625 0.0581464 -0.0200669 -0.0320423 0.0576568 -0.00800294 -0.0301365 0.05778 -0.0204731 -0.028942 0.0576576 -0.0204367 -0.0301631 0.0595604 -0.00800294 -0.0263201 0.0581278 -0.00800294 -0.0279885 0.0580205 -0.0204228 -0.0282197 0.0631184 -0.0171066 -0.0256015 0.0627258 -0.0175804 -0.0255334 0.0609176 -0.019101 -0.0256704 0.0600259 -0.0196149 -0.0260324 -0.0340767 -0.00800294 -0.0262748 -0.0353767 -0.00800294 -0.0259264 -0.0382993 -0.00800294 -0.0279944 -0.0380273 -0.00800294 -0.0183919 -0.0380507 -0.00800294 -0.0181268 -0.0388516 -0.00800294 -0.0285513 -0.0387998 -0.00800294 -0.0284141 -0.0385456 -0.00800294 -0.0281137 -0.0366767 -0.00800294 -0.0236748 -0.0363283 -0.00800294 -0.0223748 -0.0309275 -0.00800294 -0.0268893 -0.0297803 -0.00800294 -0.0250132 -0.0296591 -0.00800294 -0.0228175 -0.0305929 -0.00800294 -0.0208265 -0.0327767 -0.00800294 -0.0214231 -0.0323586 -0.00800294 -0.0195157 -0.0353766 -0.00800294 -0.0214231 -0.0372879 -0.00800294 -0.0189907 -0.0374934 -0.00800294 -0.0189526 -0.0379176 -0.00800294 -0.0186344 -0.0338286 -0.00800294 -0.0191816 -0.0343247 -0.00800294 -0.028168 -0.0343247 -0.0169869 -0.028168 -0.00182201 -0.00800294 0.0469809 -0.0108728 -0.00800294 0.0425506 -0.00789054 -0.00800294 0.0384081 -0.00881482 -0.00800294 0.0395991 -0.00614792 -0.00800294 0.0394719 -0.0100768 -0.00800294 0.0419554 -0.0102693 -0.00800294 0.0422047 -0.00709954 -0.00800294 0.0430236 -0.00614786 -0.00800294 0.0439752 -0.0110958 -0.00800294 0.0423902 -0.00768233 -0.00800294 0.0443854 -0.0105971 -0.00800294 0.0423967 -0.0105353 -0.00800294 0.0423744 -0.00209981 -0.00800294 0.0462827 -0.00354792 -0.00800294 0.0394719 -0.00181851 -0.00800294 0.038396 -0.00224789 -0.00800294 0.0417235 -0.00259621 -0.00800294 0.0430235 -0.000880965 -0.00800294 0.0438481 -0.00354786 -0.00800294 0.0439752 -0.00484786 -0.00800294 0.0443236 -0.00209614 -0.00800294 0.046248 -0.00208121 -0.00800294 0.0465531 -0.00187646 -0.00800294 0.0469307 -0.00199221 -0.00800294 0.045923 -0.00952345 -0.0100641 0.0409222 0.0604245 -0.00800294 0.0237808 0.0568673 -0.00800294 0.029325 0.0545741 -0.00800294 0.0316717 0.0546698 -0.00800294 0.028603 0.0542225 -0.00800294 0.0311817 0.0510174 -0.00800294 0.0286319 0.0502078 -0.00800294 0.0265873 0.052418 -0.00800294 0.0247031 0.0504637 -0.00800294 0.0244032 0.0533697 -0.00800294 0.0237514 0.0569214 -0.00800294 0.027303 0.054601 -0.00800294 0.0319632 0.059387 -0.00800294 0.0238109 0.0596836 -0.00800294 0.0239472 0.0599552 -0.00800294 0.0239724 0.0520906 -0.01205 0.0296906 0.0520906 -0.00800294 0.0296906 0.0572488 -0.00800294 0.0223155 0.0559824 -0.0141046 0.0216988 0.0536879 -0.00800294 0.0216115 0.0558861 -0.00800294 0.0216706 0.0528902 -0.0164534 0.0218698 0.0517241 -0.00800294 0.0226011 0.0514719 -0.0168732 0.0228372 0.0517313 -0.0168284 0.0225949 0.050219 -0.0164621 0.0253388 0.0505856 -0.0168221 0.0241138 0.0509718 -0.0168986 0.0234387 0.0505167 -0.0148557 0.0277359 0.0503311 -0.0153436 0.0271972 0.0510383 -0.0137906 0.0286606 0.000694713 -0.0203029 -0.0484561 0.00199474 -0.0203029 -0.0462044 -0.00394979 -0.0203029 -0.0497005 -0.00700533 -0.0203029 -0.0514004 -0.00620152 -0.0203029 -0.0544005 -0.00400539 -0.0203029 -0.0565966 0.00199461 -0.0203029 -0.0565967 0.00419079 -0.0203029 -0.0544006 0.00193914 -0.0203029 -0.0531006 0.00193918 -0.0203029 -0.0497006 0.00499468 -0.0203029 -0.0514006 -0.0425376 -0.0305863 -0.26431 0.00973767 -0.0198029 -0.295338 0.0114671 -0.0210338 -0.286314 0.0145518 -0.0196206 -0.272093 0.0134335 -0.0177694 -0.278483 0.00828773 -0.0206179 -0.3021 0.00808157 -0.0226008 -0.302067 0.00923715 -0.0256418 -0.314208 0.00885773 -0.0216725 -0.310955 0.00780078 -0.0253388 -0.310293 0.00805338 -0.0210923 -0.306112 0.00716909 -0.0250359 -0.306148 0.0116345 -0.0225332 -0.317541 0.00970233 -0.0219632 -0.313272 0.0213942 -0.0253112 -0.339082 0.0230361 -0.0256598 -0.343297 0.0234129 -0.0280909 -0.347287 0.0235509 -0.0281632 -0.351235 0.0239575 -0.0259899 -0.351256 0.0230153 -0.028172 -0.355152 0.0218314 -0.0281716 -0.358922 0.0176753 -0.0281716 -0.365614 0.0148196 -0.0281716 -0.368347 0.0115482 -0.0281716 -0.370565 -0.0112031 -0.0281174 -0.370761 -0.00807087 -0.0260021 -0.372601 -0.00758078 -0.0281716 -0.372342 -0.00533729 -0.0260029 -0.373396 -0.0152845 -0.0256328 -0.368506 -0.0145081 -0.0279678 -0.368596 -0.0348626 -0.022209 -0.345358 -0.0190582 -0.0251134 -0.364616 -0.0177171 -0.0253312 -0.366196 -0.0402214 -0.0254405 -0.337799 -0.0389858 -0.0218553 -0.340334 -0.0502823 -0.0209113 -0.323889 -0.049779 -0.0209669 -0.324957 -0.0539777 -0.0203379 -0.31233 -0.0546669 -0.0219368 -0.301586 -0.0548574 -0.0198042 -0.300646 -0.0545421 -0.020166 -0.308698 -0.0350225 -0.0320011 -0.265334 -0.0394371 -0.0320029 -0.294713 -0.042148 -0.0317885 -0.294222 -0.0458528 -0.0311364 -0.301776 -0.0405405 -0.0320029 -0.30189 -0.0409392 -0.0320029 -0.305927 -0.0405971 -0.0320029 -0.313802 -0.0340817 -0.0320029 -0.330804 -0.0371393 -0.0320029 -0.325484 -0.0210108 -0.0320029 -0.350631 -0.00424452 -0.0320029 -0.310726 -0.00502667 -0.0320029 -0.306657 -0.00263202 -0.0318185 -0.306557 -0.00525974 -0.0320029 -0.300889 -0.00520104 -0.0320029 -0.299931 -0.00273156 -0.0318105 -0.300328 -0.00286487 -0.0320011 -0.269718 -0.0037778 -0.0320029 -0.281809 0.00190128 -0.0310587 -0.284216 0.000709149 -0.0316903 -0.270204 0.00363977 -0.0309442 -0.270605 0.0167201 -0.0320029 -0.345132 0.0190589 -0.031552 -0.344453 0.0199427 -0.0315674 -0.347688 0.0177839 -0.0320029 -0.348639 0.0201705 -0.0315755 -0.351056 0.0197247 -0.0315764 -0.354416 0.0179435 -0.0320029 -0.350938 0.01871 -0.0315764 -0.357646 0.0134837 -0.0320029 -0.36191 0.0127 -0.0315764 -0.365724 0.0113036 -0.0320029 -0.363996 0.00989722 -0.0315764 -0.367625 0.00872832 -0.0320029 -0.365733 0.00681413 -0.0315764 -0.369031 0.00188332 -0.0320029 -0.367896 -0.00320963 -0.0315764 -0.369962 0.0134696 -0.0314725 -0.334386 0.00320493 -0.0318429 -0.32136 0.00311693 -0.0312947 -0.316981 0.00107826 -0.0318346 -0.317905 0.000968685 -0.031261 -0.311988 -0.000183004 -0.0312273 -0.306455 -0.00020602 -0.0311936 -0.300734 0.00722915 -0.0293058 -0.271095 0.0021712 -0.0302024 -0.306357 0.00507668 -0.030359 -0.316093 0.00513693 -0.0313297 -0.320485 0.0148444 -0.0307716 -0.333764 -0.00130712 -0.0318265 -0.312552 -0.0035324 -0.0320029 -0.313104 0.010641 -0.0320029 -0.335668 0.0120394 -0.0318768 -0.335034 0.0151523 -0.0320029 -0.342463 0.00699413 -0.0304402 -0.319643 0.00864841 -0.0291959 -0.318894 0.0068223 -0.0290501 -0.315302 0.00510505 -0.0289095 -0.310962 0.00315638 -0.0302807 -0.311445 0.00222174 -0.0301241 -0.301125 0.00426818 -0.0287688 -0.306269 0.00438425 -0.0286282 -0.301472 0.00470348 -0.0298109 -0.284831 0.00719951 -0.0280658 -0.285378 0.0106525 -0.0235213 -0.286135 0.00737581 -0.024733 -0.301953 -0.046743 -0.0287317 -0.323485 -0.0492041 -0.0286192 -0.316407 -0.0522799 -0.0266018 -0.309317 -0.0525958 -0.026421 -0.301631 -0.0505365 -0.0285069 -0.309078 -0.0507347 -0.0283899 -0.301671 -0.0485461 -0.0267082 -0.26349 -0.0518904 -0.0247135 -0.31722 -0.0507754 -0.0267753 -0.316882 -0.0539163 -0.0242195 -0.301602 -0.0520629 -0.0261934 -0.293675 -0.0518954 -0.0216624 -0.263034 -0.0534515 -0.0239021 -0.293598 -0.0542407 -0.0215262 -0.293555 -0.0535169 -0.0244716 -0.309486 -0.05422 -0.0222629 -0.309583 -0.0525241 -0.0225756 -0.317412 0.0119736 -0.0251477 -0.271742 0.00613415 -0.0267892 -0.301754 0.00596505 -0.0270065 -0.306199 0.00823485 -0.027441 -0.314662 0.0109369 -0.025956 -0.317857 0.0177631 -0.0272385 -0.332441 0.0170599 -0.0285861 -0.33276 0.0211659 -0.0277577 -0.339738 0.0197355 -0.0300323 -0.340386 0.0226091 -0.0279525 -0.343421 0.0212083 -0.0301227 -0.343828 0.0220437 -0.030187 -0.347445 0.0200338 -0.0281716 -0.362443 0.0079522 -0.0281716 -0.372206 0.00413291 -0.0281716 -0.373223 0.000197377 -0.0281716 -0.373589 0.000185735 -0.0302244 -0.372258 -0.00374388 -0.0281716 -0.373292 -0.00353309 -0.0302244 -0.371978 -0.00715366 -0.0302244 -0.371082 -0.0105674 -0.0301993 -0.369583 -0.013669 -0.0301299 -0.36752 -0.0174014 -0.0277426 -0.365907 -0.0199541 -0.0274613 -0.362825 -0.0300969 -0.0261682 -0.350319 -0.0287363 -0.0292945 -0.349203 -0.0385657 -0.0289567 -0.33644 -0.0449724 -0.031101 -0.294066 -0.0459634 -0.0311645 -0.308451 -0.0484348 -0.0299914 -0.30172 -0.0450823 -0.0311914 -0.315159 -0.0483821 -0.0300565 -0.308782 -0.0431853 -0.0288442 -0.330133 -0.00959195 -0.0315703 -0.367774 -0.00853047 -0.0320029 -0.365805 -0.0108011 -0.0320029 -0.364225 -0.0147769 -0.0315286 -0.363504 -0.0171011 -0.0314973 -0.360484 -0.0154194 -0.0320029 -0.358665 -0.0490697 -0.0249558 -0.324613 -0.0496186 -0.022889 -0.324879 -0.0451205 -0.0251981 -0.331483 -0.048104 -0.0269491 -0.324145 -0.045061 -0.0301817 -0.32267 -0.0472623 -0.030119 -0.315819 -0.0476875 -0.0299093 -0.293916 -0.0501059 -0.0282425 -0.293783 0.00966631 -0.0275706 -0.271427 0.00921929 -0.0259203 -0.285821 0.0066819 -0.0272237 -0.310571 0.00998706 -0.0276663 -0.318287 0.016069 -0.0297913 -0.333209 0.0175407 -0.0315303 -0.34138 0.0222171 -0.0302206 -0.351164 0.0217169 -0.0302246 -0.354861 0.0205998 -0.0302244 -0.358419 0.0189034 -0.0302244 -0.361741 0.0171691 -0.0315764 -0.360664 0.0166783 -0.0302244 -0.364733 0.0151484 -0.0315764 -0.363381 0.0139833 -0.0302244 -0.367312 0.0108968 -0.0302244 -0.369405 0.00750315 -0.0302244 -0.370953 0.00389965 -0.0302244 -0.371913 0.00354172 -0.0315764 -0.369903 0.000167871 -0.0315764 -0.370217 -0.00649828 -0.0315764 -0.369148 -0.0123814 -0.0315537 -0.36587 -0.0163659 -0.0300253 -0.364959 -0.0188284 -0.0298947 -0.361901 -0.0266485 -0.0313533 -0.34749 -0.0360252 -0.0312723 -0.334355 -0.0402158 -0.0312453 -0.328061 -0.0392879 -0.0320029 -0.319871 -0.0431728 -0.0312184 -0.321754 -0.029782 -0.0320029 -0.266049 -0.0048584 -0.0320029 -0.36733 0.000148432 -0.0320029 -0.367995 -9.21786e-06 -0.0320029 -0.355496 -0.0373211 -0.0320029 -0.280631 0.00475396 -0.0320029 -0.352746 0.00274079 -0.0320029 -0.354759 0.00606435 -0.0320029 -0.36694 -0.00477232 -0.0320029 -0.352746 -0.00275921 -0.0320029 -0.354759 -0.0152215 -0.0320029 -0.358941 -0.0130478 -0.0320029 -0.361922 -9.07704e-06 -0.0320029 -0.344496 -0.000861562 -0.0320029 -0.318892 -0.00275909 -0.0320029 -0.345233 0.0174039 -0.0320029 -0.354557 0.0141905 -0.0320029 -0.361057 0.0166535 -0.0320029 -0.356804 0.0173876 -0.0320029 -0.354619 -0.0402304 -0.0320029 -0.316025 0.00475403 -0.0320029 -0.347246 0.0154732 -0.0320029 -0.342971 0.00131582 -0.0320029 -0.322216 -0.00477225 -0.0320029 -0.347246 -0.0504726 -0.00714569 -0.234807 -0.0501288 -0.000306333 -0.214948 -0.0513442 -0.000303094 -0.244736 -0.0500136 -0.000307009 -0.212828 -0.0471416 -0.0109678 -0.213219 -0.0467022 -0.0116991 -0.213279 -0.0498541 -0.0107137 -0.234903 -0.0487247 -0.0141981 -0.233754 -0.0499065 -0.0144936 -0.23981 -0.0507756 -0.0149316 -0.245183 -0.0512198 -0.00735143 -0.245105 -0.0514001 -0.0154444 -0.249883 -0.0527805 -0.017001 -0.262913 0.0180867 -0.00739837 -0.254552 0.0206217 -0.000306393 -0.244476 0.0201233 -0.00716501 -0.244429 0.0227868 -0.0109445 -0.222753 0.0223223 -0.0117133 -0.22269 0.0195693 -0.0105659 -0.244388 -0.0450357 -0.013964 -0.213507 -0.0469626 -0.0140114 -0.225052 -0.0435443 -0.0218082 -0.235758 -0.0515698 -0.0224289 -0.263078 0.0148264 -0.0170029 -0.27213 0.0172205 -0.0149905 -0.257682 0.0153227 -0.020645 -0.262238 0.0122664 -0.0249141 -0.261791 0.0134915 -0.0226983 -0.271948 0.019438 -0.0139803 -0.234117 0.0166625 -0.0174305 -0.233749 0.00904777 -0.0239326 -0.24293 0.00463951 -0.0231246 -0.232141 -0.00545098 -0.0262088 -0.240926 0.00969164 -0.0203929 -0.220968 0.0149435 -0.0183179 -0.221684 0.00897723 -0.0218882 -0.232731 0.0173812 -0.0168473 -0.222016 0.0130571 -0.0200483 -0.233274 0.0206165 -0.0139713 -0.222457 -0.0322118 -0.0231505 -0.227115 -0.0393323 -0.0315506 -0.264745 -0.0382534 -0.0317507 -0.264892 -0.0276915 -0.0301248 -0.25631 -0.0328295 -0.0301878 -0.255608 -0.0265415 -0.0283465 -0.248394 -0.0316416 -0.0283983 -0.247699 -0.0380729 -0.02979 -0.25489 -0.023113 -0.0242598 -0.228333 -0.0345918 -0.0254889 -0.236966 -0.0392795 -0.0241261 -0.236333 -0.0417915 -0.0264584 -0.246326 -0.0474867 -0.0251016 -0.253636 -0.0461651 -0.0236764 -0.245754 -0.0505911 -0.0208529 -0.253239 -0.0406606 -0.0201718 -0.225946 -0.0138099 -0.0320029 -0.268226 0.00289437 -0.0297361 -0.260479 0.0176581 -0.0146317 -0.254547 0.00792919 -0.027986 -0.261177 -0.00237821 -0.0301944 -0.259764 -0.00754782 -0.0301224 -0.259057 -0.0176351 -0.0300716 -0.257684 -0.0165545 -0.0282969 -0.249758 -0.00448529 -0.0242617 -0.230873 -0.0138055 -0.0245505 -0.229594 -0.0151691 -0.0263232 -0.239596 -0.0121778 -0.0230029 -0.217986 -0.0235868 -0.0224215 -0.216431 -0.0365589 -0.0219842 -0.226519 -0.0418372 -0.0168825 -0.213943 -0.0442525 -0.0175116 -0.225439 -0.0469537 -0.018442 -0.235303 -0.04821 -0.0189988 -0.240023 -0.0489843 -0.0142469 -0.235032 -0.0493682 -0.0196995 -0.245349 -0.0443485 -0.0297576 -0.264063 -0.0431114 -0.0281143 -0.254213 -0.0368164 -0.0280037 -0.246991 -0.0248481 -0.0262106 -0.23828 -0.00052882 -0.0260564 -0.24161 -0.00652168 -0.0283432 -0.251125 -0.00137461 -0.0284089 -0.251832 0.00436965 -0.0254132 -0.242283 0.00384231 -0.0279191 -0.252541 0.00881014 -0.0262589 -0.253233 0.0132619 -0.0215446 -0.243514 0.0166374 -0.0181926 -0.243989 0.0131273 -0.0233935 -0.253849 0.016267 -0.0193981 -0.254316 0.0187345 -0.0140146 -0.243767 -0.0272718 -0.0164854 0.0122033 -0.0274912 -0.0146081 0.0174701 0.0497213 -0.0170026 0.0258538 0.042618 -0.0179684 0.0304926 -0.0100357 -0.0119834 0.0400844 -0.036691 -0.00593089 0.00127871 -0.0365331 -0.000325475 0.00655011 -0.037506 -0.000318267 -0.00372968 -0.0366822 -0.00263524 0.00401524 -0.0375301 -0.000317793 -0.00402083 -0.0152143 -0.000325342 0.0413698 0.0178333 -0.00487312 0.050974 0.023835 -0.000304005 0.0506265 0.0182726 -0.000304843 0.0512154 0.00576352 -0.0047574 0.0500524 -0.00015034 -0.00465551 0.0485291 0.0455966 -0.00465771 0.041512 0.0405932 -0.00475827 0.0446333 0.036035 -0.000304971 0.0471235 0.0352564 -0.00482997 0.047176 0.0296425 -0.00487306 0.0491021 0.0303338 -0.000304033 0.0491595 0.0623671 -0.00031497 0.0226427 0.0612923 -0.00395294 0.0241291 0.0616659 -0.000315247 0.0239634 0.059254 -0.000314827 0.0279315 -0.0104005 -0.0146457 0.0365753 -0.0105569 -0.011933 0.0397986 -0.00983466 -0.0124472 0.0397125 -0.000558409 -0.0164075 0.039289 -0.00249048 -0.0170219 0.0374618 0.000152457 -0.009088 0.047205 -0.000380855 -0.0120977 0.0447825 -0.00107767 -0.0101776 0.0461027 -0.0112957 -0.00436096 0.04345 -0.00269057 -0.000315112 0.0480312 -0.0091913 -0.000320223 0.0451174 0.0546976 -0.0162676 0.0209807 0.0586015 -0.0154475 0.0162093 0.0534143 -0.0169345 0.0212006 0.0503971 -0.0185189 0.0204189 0.0601142 -0.0108419 0.0215334 0.0605852 -0.00800294 0.0235832 0.0607804 -0.00771998 0.0234378 0.0555452 -0.000313344 0.0328267 0.069835 -0.000304618 -0.0141174 0.0695457 -0.00585237 -0.0130124 0.0691642 -0.0086015 -0.00847589 0.070007 -0.000301265 -0.0106302 0.069988 -0.00260778 -0.0102579 0.0577979 -0.0169528 0.0131327 0.0638012 -0.0147201 0.0048714 0.0670607 -0.0102366 0.00438259 0.0686544 -0.00862526 -0.00081163 0.0688979 -0.00696351 0.000525023 0.0697975 -0.0045485 -0.0114058 0.0661934 -0.00338018 0.0133041 0.065871 -0.00660367 0.0128475 0.0654209 -0.0092986 0.0114024 0.0593724 -0.0133445 0.0190051 0.0691925 -0.00252605 0.00175249 0.0690928 -0.0049358 0.00149456 0.0643681 -0.0133473 0.00727453 0.0649071 -0.0114868 0.00944809 0.0582377 -0.0127741 0.021974 0.0696252 -0.000307303 -0.0164095 0.0692694 -0.00664702 -0.0148037 0.0687536 -0.00979032 -0.0111366 0.0681046 -0.0111234 -0.00396803 0.0662455 -0.0131732 0.000499842 0.0626403 -0.0166325 -0.000177895 0.0561598 -0.0189426 0.00668329 0.0485212 -0.0205154 0.0127683 0.039839 -0.0215871 0.0177906 0.0303376 -0.0222192 0.0215444 0.0319868 -0.0202372 0.0307626 0.0202699 -0.0224306 0.0238562 0.0543979 -0.00436814 0.033704 0.0443209 -0.0127279 0.0376946 0.0450565 -0.00909234 0.0403577 0.0342541 -0.0131879 0.0429509 0.0434885 -0.0155955 0.0342582 0.0232291 -0.0133416 0.0459411 0.00992652 -0.0222181 0.0245914 0.0215444 -0.0204508 0.0333539 0.032788 -0.0185801 0.035182 0.0221554 -0.0187844 0.0379108 0.000122265 -0.017958 0.0368548 -0.0102962 -0.0169034 0.0330516 0.000205391 -0.0138673 0.0430521 0.000254483 -0.0149458 0.0416744 0.011108 -0.0185794 0.0384969 0.000206302 -0.0155871 0.0407788 0.0107333 -0.0202364 0.0339875 -0.000350204 -0.0215708 0.0236882 -0.0192746 -0.0188304 0.0172834 -0.0195253 -0.0168674 0.0240657 -0.0102435 -0.0184784 0.0292107 -0.0101975 -0.0204623 0.0211971 -0.0277929 -0.0114105 0.0222687 -0.030847 -0.0130869 0.0137437 -0.0198768 -0.0132863 0.0302774 -0.0108379 -0.00968798 0.04157 0.0118554 -0.00942742 0.0494487 0.0059537 -0.00928641 0.048668 0.0506284 -0.0175938 0.023224 0.0417053 -0.019598 0.0263799 0.0335426 -0.0161432 0.0392383 0.0227161 -0.0163261 0.0420999 0.01143 -0.0161426 0.0426446 0.0117006 -0.0131875 0.0464503 0.000237228 -0.0127215 0.0443766 -0.00160465 -0.00800294 0.047107 0.0117879 -0.00482983 0.0508685 0.0177746 -0.0095117 0.0495439 0.0238119 -0.00488749 0.0503778 0.02363 -0.00953967 0.0489617 0.0293466 -0.00951159 0.0477227 0.0348601 -0.0094277 0.0458541 0.0401143 -0.00928811 0.0433873 0.053812 -0.00852856 0.0327685 -0.0236952 -0.0158378 0.0209263 -0.0240541 -0.0124259 0.0264591 -0.0310357 -0.0101779 0.0177647 -0.0340969 -0.00252696 0.0156578 -0.035087 -0.000325147 0.0131599 -0.0356307 -0.0038482 0.00975829 -0.0337428 -0.00696616 0.0143664 -0.0355449 -0.0067269 0.00801519 -0.0355615 -0.00867976 0.00560988 -0.0336115 -0.0126766 0.00622538 -0.0366518 -0.00460197 0.0028765 -0.0287281 -0.00336028 0.0264748 -0.0209968 -0.00393777 0.035937 -0.0204691 -0.0076901 0.0350625 -0.0201235 -0.0107977 0.0329798 -0.0196777 -0.0153756 0.0273107 -1.52656e-05 -0.0195856 0.0325859 -0.0336146 -0.0111286 0.00978246 -0.0336738 -0.00862875 0.0129989 -0.0280015 -0.00924064 0.0243368 -0.0338678 -0.00493759 0.0153674 -0.0282907 -0.00656448 0.0258985 -0.00103864 -0.0239315 0.0056298 -0.000911269 -0.0250369 -0.0126259 -0.0378368 -0.000304206 -0.00759184 -0.0368986 -0.00799245 -0.00412643 -0.0369206 -0.0093901 -0.00771662 -0.0357436 -0.0117458 -0.00248969 -0.0349846 -0.0148975 -0.00798056 -0.0336107 -0.0150336 -0.000999741 -0.0187779 -0.021476 0.00351526 -0.00986394 -0.0242885 -0.0114053 0.0245755 -0.025354 -0.0161006 0.0467102 -0.0237465 -0.0191182 0.0447216 -0.0230364 -0.00276391 0.0528416 -0.0216422 -0.00641272 0.0687755 -0.000303823 -0.0221264 0.067799 -0.0105032 -0.0219933 0.0687082 -0.00783976 -0.0184434 0.0679199 -0.0115936 -0.0165421 0.0632537 -0.0187443 -0.0213736 0.015531 -0.0255028 -0.0148675 0.0176831 -0.0246704 0.00458029 0.0269941 -0.0244909 0.00283428 -0.0367587 -0.0067501 -0.000503997 -0.0377999 -0.000303643 -0.0071935 -0.0356204 -0.00989305 0.00293815 -0.030728 -0.0148508 0.00931488 -0.0304945 -0.0174856 0.000320754 -0.0268366 -0.0192053 0.00150891 -0.0101154 -0.0229578 0.00493188 0.00828453 -0.0244894 0.00552215 0.0360575 -0.0239556 0.000355321 0.0602877 -0.0194232 -0.0104329 0.0653799 -0.014964 -0.00379339 0.0675106 -0.0126698 -0.00746624 0.0636249 -0.0176533 -0.0125137 0.0663052 -0.0150236 -0.0145725 0.0693786 -0.000309889 -0.0184117 0.00623859 -0.0212884 -0.220497 -0.0121262 -0.0216969 -0.111112 -0.0299867 -0.021036 -0.0357735 0.0472946 -0.00668576 -0.118932 0.0483567 -0.000331486 -0.119064 -0.0470551 -0.000327856 -0.159652 -0.0457899 -0.00605084 -0.160072 -0.0442255 -0.00627988 -0.133479 -0.0391866 -0.00799356 -0.0328927 -0.0397344 -0.000307601 -0.032586 -0.0384727 -0.00800294 -0.0234139 -0.0369269 -0.0127514 -0.0181853 -0.0294917 -0.0206286 -0.0216184 -0.0251817 -0.0215167 -0.00931702 -0.0291448 -0.0208354 -0.0227961 -0.0343694 -0.0171077 -0.0183247 -0.0335269 -0.0168824 -0.00817929 -0.0342809 -0.0172026 -0.0183303 -0.0308758 -0.0190586 -0.00854073 -0.0292337 -0.0209046 -0.0249265 -0.0296814 -0.0207754 -0.0260776 -0.0302537 -0.020567 -0.0269326 -0.00160293 -0.0249934 -0.0125316 -0.00167937 -0.0249885 -0.0125212 -0.0219448 -0.0230945 -0.037977 -0.0183399 -0.0230991 -0.0102498 0.0113476 -0.0252193 -0.045542 0.0150843 -0.0255033 -0.0148066 0.00670127 -0.0253808 -0.0136637 -0.00539553 -0.0246978 -0.0423149 0.0321592 -0.0250258 -0.0171345 0.0500456 -0.0232653 -0.019573 0.0575232 -0.0215797 -0.0205924 0.0593262 -0.0198939 -0.0342798 0.058469 -0.0212601 -0.0207213 0.0582707 -0.0209793 -0.0267766 0.0611187 -0.0197793 -0.0249592 0.0638694 -0.0176492 -0.0249179 0.065595 -0.0161399 -0.0216928 0.0675676 -0.00800294 -0.0257368 0.0672814 -0.0124162 -0.0219227 0.065408 -0.0154244 -0.0252536 0.00466493 -0.0250528 -0.0477062 -0.00193187 -0.024861 -0.0446777 0.0027988 -0.0250485 -0.0458056 0.00494005 -0.0247957 -0.0546994 -0.000104188 -0.0244462 -0.0581765 -0.0077677 -0.023618 -0.0642766 -0.00489826 -0.0242304 -0.0570515 -0.00600087 -0.0242 -0.0561116 -0.00771972 -0.0243205 -0.0500238 -0.00703476 -0.0244322 -0.0481696 0.0625612 -0.0122224 -0.0470506 0.0615648 -0.0181563 -0.0352726 -0.0311426 -0.0201837 -0.0277873 -0.0321752 -0.019649 -0.0284053 -0.0377032 -0.0138405 -0.135502 -0.0492304 -0.00590277 -0.212935 -0.0426555 -0.00932466 -0.133985 -0.0443042 -0.0089813 -0.160581 -0.0474687 -0.00592635 -0.18646 -0.0486835 -0.00763269 -0.213009 -0.0443452 -0.011416 -0.1871 -0.0261108 -0.0185149 -0.109084 -0.0347249 -0.0152923 -0.136422 -0.0156121 -0.0211672 -0.142257 -0.0404284 -0.0118969 -0.134672 -0.0422371 -0.0114888 -0.161267 -0.0395745 -0.0153556 -0.188059 -0.0370035 -0.0150166 -0.163002 -0.0338788 -0.0179886 -0.18919 0.00212654 -0.0229602 -0.11311 -0.042496 -0.0163905 -0.213853 -0.0278016 -0.0197967 -0.190376 -0.0399005 -0.0180988 -0.214207 -0.0332803 -0.0206649 -0.215109 -0.0299985 -0.0214304 -0.215557 0.0414621 -0.0063184 -0.14516 0.0246733 -0.0175035 -0.145633 0.0401684 -0.0143475 -0.118026 0.0370627 -0.011564 -0.145234 0.042647 -0.00033462 -0.145087 0.0358085 -0.00608357 -0.171195 0.039742 -0.00931474 -0.145216 0.0317132 -0.0112112 -0.171346 0.0261479 -0.0146244 -0.171606 0.0310179 -0.0147971 -0.145379 0.0201232 -0.0174081 -0.171961 0.0180892 -0.0196184 -0.145859 -0.00315462 -0.0226505 -0.219216 0.00037388 -0.0222856 -0.219697 0.0180689 -0.0163413 -0.22211 0.0220241 -0.0151221 -0.196455 0.0302801 -0.00594589 -0.19706 0.0269265 -0.0112667 -0.196816 0.0246248 -0.0114227 -0.209641 0.027535 -0.00590837 -0.210014 0.0242869 -0.00759942 -0.222957 0.0247885 -0.00590512 -0.223026 0.0102103 -0.019786 -0.195555 0.0163263 -0.017935 -0.196032 0.00551239 -0.0250142 -0.0495561 0.00563003 -0.0248927 -0.052835 0.00846626 -0.0241788 -0.0666605 0.0579786 -0.00769224 -0.0723696 0.0571805 -0.0117221 -0.0723127 0.063388 -0.0080037 -0.0468761 0.0526128 -0.0183074 -0.0718397 0.0608876 -0.0162049 -0.0472004 0.0489154 -0.0200288 -0.071427 0.0578539 -0.0192462 -0.0472376 0.0539603 -0.021088 -0.0472126 0.0409766 -0.0219278 -0.0705443 0.0455468 -0.0230405 -0.0471702 0.032809 -0.0249886 -0.0172231 0.0534655 -0.000322203 -0.0957585 0.0585389 -0.00031273 -0.0724042 0.0526782 -0.0071924 -0.0955654 0.0515541 -0.0108309 -0.0953055 0.0495191 -0.0139865 -0.0948877 0.0555398 -0.0154781 -0.0721573 0.0465522 -0.0163173 -0.0943159 0.0358357 -0.0200009 -0.092257 0.0247456 -0.0236722 -0.0687075 0.0283772 -0.0247311 -0.04691 0.0235767 -0.0253833 -0.0159644 0.0457484 -0.00992911 -0.118738 0.0432217 -0.0124779 -0.118416 0.0431031 -0.0178957 -0.0936579 0.0369349 -0.0158698 -0.117614 0.0302377 -0.0183637 -0.116766 0.0233573 -0.0202939 -0.115892 -0.00675906 -0.0241897 -0.0551514 -0.00760563 -0.0242063 -0.0532966 -0.0353652 -0.0183157 -0.0598462 -0.0336527 -0.0190443 -0.0347666 -0.0381921 -0.0153945 -0.0593791 -0.0365798 -0.0160382 -0.0339154 -0.038334 -0.0121758 -0.0332971 0.0369464 -0.000331665 -0.171104 0.0289365 -0.00883801 -0.196969 0.0341834 -0.00897499 -0.17128 0.0137778 -0.0194545 -0.172278 0.00728197 -0.0208931 -0.172427 0.000716392 -0.0217706 -0.172267 0.0113708 -0.0211782 -0.145927 0.00457968 -0.0221668 -0.145699 0.0163567 -0.0217231 -0.114995 0.00926923 -0.0226352 -0.114069 0.0208977 -0.0224206 -0.089448 -0.00964202 -0.0223731 -0.085281 -0.0248904 -0.0202485 -0.083975 -0.0323493 -0.0183243 -0.0833692 -0.0239349 -0.0221775 -0.0616963 -0.0318045 -0.0202633 -0.0604233 -0.0418567 -0.0071768 -0.0826769 -0.0399271 -0.0116937 -0.0590741 -0.0408213 -0.00768937 -0.0589001 -0.0284899 -0.0175894 -0.138393 -0.0311346 -0.0174658 -0.164982 -0.0187654 -0.0208894 -0.168886 -0.0215651 -0.0209698 -0.191537 -0.0230643 -0.0213083 -0.203289 -0.0104134 -0.0220566 -0.205048 -0.00766106 -0.0229189 -0.218602 -0.0388777 -0.00800294 -0.0287023 -0.0428417 -0.00665263 -0.106644 -0.0406613 -0.0108215 -0.0827329 -0.0413401 -0.00993426 -0.106865 -0.0386738 -0.0140877 -0.0828631 -0.0391039 -0.0127569 -0.107192 -0.0357959 -0.0166141 -0.0830875 -0.0362116 -0.0148813 -0.107613 -0.0329577 -0.0163849 -0.108086 0.0056871 -0.023238 -0.0870202 -0.00222898 -0.0225162 -0.145039 -0.00585898 -0.0220722 -0.171652 -0.00884882 -0.0218548 -0.193574 0.00392269 -0.0209721 -0.195009 0.00222626 -0.0213105 -0.206737 0.013518 -0.000329615 -0.278098 0.0136073 -0.000302937 -0.27769 0.0141299 -0.000302937 -0.275307 0.0141299 -0.0173862 -0.275307 0.0697204 -2.93696e-06 -0.0080318 0.0693883 -2.93696e-06 -0.00216688 0.0391096 -2.93696e-06 -0.159833 0.0323879 -2.93696e-06 -0.190527 -0.0320516 -2.93696e-06 -0.0201674 -0.0320517 -2.93696e-06 -0.0271822 0.00401817 -2.93696e-06 -0.0232687 0.00167937 -2.93696e-06 -0.0498506 0.00054471 -2.93696e-06 -0.0487159 -0.00369002 -2.93696e-06 -0.0529505 -0.0194627 -2.93696e-06 -0.0232684 -0.00368998 -2.93696e-06 -0.0498505 -0.00410532 -2.93696e-06 -0.0514005 0.0601297 -2.93696e-06 -0.0264896 0.049911 -2.93696e-06 -0.0232692 0.0586472 -2.93696e-06 -0.027972 0.0581046 -2.93696e-06 -0.029997 0.0656621 -2.93696e-06 -0.0279721 -0.0340767 -2.93696e-06 -0.0277248 -0.0382901 -2.93696e-06 -0.0171135 -0.0375841 -2.93696e-06 -0.0216498 -0.0381267 -2.93696e-06 -0.0236747 -0.038158 -2.93696e-06 -0.0232681 -0.0375841 -2.93696e-06 -0.0256998 -0.0361017 -2.93696e-06 -0.0271822 -0.0300267 -2.93696e-06 -0.0236748 -0.0305693 -2.93696e-06 -0.0256998 -0.0194634 -2.93696e-06 -0.074152 -0.0420171 -2.93696e-06 -0.0741427 -0.0381587 -2.93696e-06 -0.0741518 -0.0367807 -2.93696e-06 -0.0943026 -0.0386432 -2.93696e-06 -0.0938035 -0.0367808 -2.93696e-06 -0.100754 -0.0354173 -2.93696e-06 -0.0956661 -0.043545 -2.93696e-06 -0.101537 -0.0418692 -2.93696e-06 -0.099391 -0.0435465 -2.93696e-06 -0.103262 -0.0405058 -2.93696e-06 -0.100754 -0.03977 -2.93696e-06 -0.103262 -0.0456411 -2.93696e-06 -0.156816 -0.0400536 -2.93696e-06 -0.160042 -0.0386901 -2.93696e-06 -0.158678 -0.0386901 -2.93696e-06 -0.154953 -0.0400535 -2.93696e-06 -0.15359 -0.0469386 -2.93696e-06 -0.217285 -0.0511906 -2.93696e-06 -0.247151 -0.0432136 -2.93696e-06 -0.217285 -0.0485654 -2.93696e-06 -0.19221 -0.045076 -2.93696e-06 -0.210334 -0.0469385 -2.93696e-06 -0.210833 -0.0497141 -2.93696e-06 -0.212845 -0.0483019 -2.93696e-06 -0.212196 0.00401501 -2.93696e-06 -0.270048 0.00643714 -2.93696e-06 -0.274196 0.00780057 -2.93696e-06 -0.275559 0.00966306 -2.93696e-06 -0.276058 0.0115256 -2.93696e-06 -0.275559 0.0133881 -2.93696e-06 -0.272333 0.0145334 -2.93696e-06 -0.272066 0.00401529 -2.93696e-06 -0.247665 0.0115257 -2.93696e-06 -0.269107 0.00966316 -2.93696e-06 -0.268608 0.00780065 -2.93696e-06 -0.269107 0.00643719 -2.93696e-06 -0.270471 0.0186184 -2.93696e-06 -0.219771 0.0237068 -2.93696e-06 -0.224859 0.0242059 -2.93696e-06 -0.222997 0.0262598 -2.93696e-06 -0.218528 0.0172549 -2.93696e-06 -0.224859 0.0186183 -2.93696e-06 -0.226222 0.0204808 -2.93696e-06 -0.226722 0.0169531 -2.93696e-06 -0.259288 0.0266203 -2.93696e-06 -0.190528 0.0308971 -2.93696e-06 -0.163771 0.0266206 -2.93696e-06 -0.161907 0.030897 -2.93696e-06 -0.170223 0.0359856 -2.93696e-06 -0.165134 0.0346221 -2.93696e-06 -0.163771 0.034622 -2.93696e-06 -0.170223 0.0436144 -2.93696e-06 -0.105771 0.045013 -2.93696e-06 -0.132906 0.0626098 -2.93696e-06 -0.0515958 0.0578552 -2.93696e-06 -0.0741537 0.0577926 -2.93696e-06 -0.0744441 0.0499104 -2.93696e-06 -0.0741529 0.0499228 -2.93696e-06 -0.110537 0.0492018 -2.93696e-06 -0.108997 0.0668122 -2.93696e-06 -0.0232695 0.0684805 -2.93696e-06 -0.022072 0.0682281 -2.93696e-06 -0.0205918 0.0687596 -2.93696e-06 -0.0169143 0.0689515 -2.93696e-06 -0.0150749 0.0697071 -2.93696e-06 -0.010623 0.069225 -2.93696e-06 -0.00821367 0.0690199 -2.93696e-06 0.000849099 0.068333 -2.93696e-06 0.00478285 0.0546698 -2.93696e-06 0.030053 0.0552458 -2.93696e-06 0.0327155 0.0511623 -2.93696e-06 0.0280281 0.0506197 -2.93696e-06 0.0260031 0.0511623 -2.93696e-06 0.0239781 0.0624623 -2.93696e-06 0.00471113 0.0641106 -2.93696e-06 0.0182367 0.0621004 -2.93696e-06 0.0225059 0.0581771 -2.93696e-06 0.023978 0.0243339 -2.93696e-06 0.0502399 0.0266233 -2.93696e-06 0.048573 0.0002634 -2.93696e-06 0.0487102 -0.00544852 -2.93696e-06 0.0465968 -0.0108354 -2.93696e-06 0.0438576 -0.00282294 -2.93696e-06 0.0382161 -0.00134052 -2.93696e-06 0.0396985 0.000648886 -2.93696e-06 0.0338636 -0.000797893 -2.93696e-06 0.0417235 0.000649075 -2.93696e-06 0.0485734 -0.00484784 -2.93696e-06 0.0457736 -0.024673 -2.93696e-06 0.0321554 -0.0313192 -2.93696e-06 0.0219958 -0.0354449 -2.93696e-06 0.0106066 -0.0374217 -2.93696e-06 -0.0124506 -0.0371103 -2.93696e-06 -0.0100936 -0.0324716 -2.93696e-06 0.00471235 -0.0375379 -2.93696e-06 -0.00761716 -0.0367897 -0.000162321 -0.00768296 -0.0400652 -2.93696e-06 -0.0418021 -0.0397696 -2.93696e-06 -0.0741518 -0.042884 -2.93696e-06 -0.0895688 -0.0418692 -2.93696e-06 -0.095666 -0.0423683 -2.93696e-06 -0.0975285 -0.0484718 -2.93696e-06 -0.190527 -0.0435476 -2.93696e-06 -0.190527 -0.0468808 -2.93696e-06 -0.161906 -0.0484518 -2.93696e-06 -0.271487 -0.0484519 -2.93696e-06 -0.278937 -0.0498555 -2.93696e-06 -0.281426 -0.0525178 -2.93759e-06 -0.263586 -0.0465893 -2.93696e-06 -0.271987 -0.0503143 -2.93696e-06 -0.271987 -0.0521768 -2.93696e-06 -0.275212 -0.053502 -2.93696e-06 -0.281426 -0.0503144 -2.93696e-06 -0.278438 -0.0324719 -2.93696e-06 -0.0160378 0.000648247 -2.93696e-06 -0.0160382 -0.0194626 -2.93696e-06 -0.0160379 -0.0194623 -2.93696e-06 0.00471218 0.000648513 -2.93696e-06 0.00471192 -0.00687294 -2.93696e-06 0.0382162 0.000648155 -2.93696e-06 -0.0232686 0.00401826 -2.93696e-06 -0.0160382 0.0040189 -2.93696e-06 0.0338636 0.0621547 -2.93696e-06 -0.025947 0.0499114 -2.93696e-06 0.00471129 0.0566947 -2.93696e-06 0.0224956 0.0665797 -2.93696e-06 0.0115682 0.0674201 -2.93696e-06 0.00660184 0.0668126 -2.93696e-06 0.00471108 0.0668123 -2.93696e-06 -0.016039 0.062462 -2.93696e-06 -0.016039 0.0624619 -2.93696e-06 -0.0232694 0.0391187 -2.93696e-06 -0.103263 0.04991 -2.93696e-06 -0.103263 0.039119 -2.93696e-06 -0.0741528 0.0391197 -2.93696e-06 -0.0232691 0.0499111 -2.93696e-06 -0.0160388 0.03912 -2.93696e-06 0.00471143 0.0499117 -2.93696e-06 0.033863 0.0413415 -2.93696e-06 0.044171 -0.038159 -2.93696e-06 -0.103262 -0.0397704 -2.93696e-06 -0.132906 -0.0435469 -2.93696e-06 -0.132906 0.0391183 -2.93696e-06 -0.132907 0.0266214 -2.93696e-06 -0.103263 0.0266218 -2.93696e-06 -0.0741526 0.0266225 -2.93696e-06 -0.0160385 0.0266228 -2.93696e-06 0.00471159 0.0391198 -2.93696e-06 -0.0160387 -0.0397711 -2.93696e-06 -0.190527 0.0223434 -2.93696e-06 -0.219771 0.0204809 -2.93696e-06 -0.219272 0.0266186 -2.93696e-06 -0.216888 0.00401639 -2.93696e-06 -0.161906 0.00401676 -2.93696e-06 -0.132906 0.026621 -2.93696e-06 -0.132907 0.00401752 -2.93696e-06 -0.0741523 0.0266224 -2.93696e-06 -0.0232689 0.00401853 -2.93696e-06 0.00471188 0.00401909 -2.93696e-06 0.0485733 -0.0397715 -2.93696e-06 -0.218527 -0.0397721 -2.93696e-06 -0.270048 -0.0435483 -2.93696e-06 -0.247664 -0.0435486 -2.93696e-06 -0.270048 -0.0397707 -2.93696e-06 -0.161906 -0.0381602 -2.93696e-06 -0.190527 -0.0381605 -2.93696e-06 -0.218527 -0.0381609 -2.93696e-06 -0.247664 -0.0397718 -2.93696e-06 -0.247664 -0.0386433 -2.93696e-06 -0.101254 -0.0324734 -2.93696e-06 -0.132906 -0.0381594 -2.93696e-06 -0.132906 -0.0381598 -2.93696e-06 -0.161906 -0.0324741 -2.93696e-06 -0.190527 -0.0324745 -2.93696e-06 -0.218527 -0.0324749 -2.93696e-06 -0.247664 -0.0381612 -2.93696e-06 -0.270048 -0.0381613 -2.93696e-06 -0.281426 -0.0194637 -2.93696e-06 -0.103262 -0.0324726 -2.93696e-06 -0.0741519 -0.032473 -2.93696e-06 -0.103262 -0.0324738 -2.93696e-06 -0.161906 -0.0324752 -2.93696e-06 -0.270048 -0.0324753 -2.93696e-06 -0.281427 0.000647503 -2.93696e-06 -0.0741523 0.000647131 -2.93696e-06 -0.103263 -0.0194641 -2.93696e-06 -0.132906 0.000646751 -2.93696e-06 -0.132906 0.00064638 -2.93696e-06 -0.161906 -0.0194645 -2.93696e-06 -0.161906 -0.0194648 -2.93696e-06 -0.190528 0.000645655 -2.93696e-06 -0.218528 -0.0194652 -2.93696e-06 -0.218528 0.000645282 -2.93696e-06 -0.247665 -0.0194656 -2.93696e-06 -0.247664 0.000644996 -2.93696e-06 -0.270048 0.00064485 -2.93696e-06 -0.281427 -0.0194659 -2.93696e-06 -0.270048 0.00401714 -2.93696e-06 -0.103263 0.00401603 -2.93696e-06 -0.190528 0.00401567 -2.93696e-06 -0.218528 0.000646014 -2.93696e-06 -0.190528 0.00809067 -0.0208172 -0.303779 0.00970182 -0.0198029 -0.31327 0.0127688 -0.0228813 -0.320045 0.0171598 -0.0242236 -0.329736 0.0215595 -0.0198029 -0.339447 0.0236723 -0.025825 -0.346108 0.0238515 -0.0258844 -0.347427 0.0235693 -0.0260047 -0.354474 0.0222069 -0.0260029 -0.359076 0.0226277 -0.0198029 -0.357971 0.0205876 -0.0198029 -0.362315 0.0206501 -0.0260029 -0.362208 0.0199027 -0.0198029 -0.363395 0.0175205 -0.0260029 -0.366388 0.0150745 -0.0260029 -0.368662 0.0108835 -0.0260029 -0.371381 0.00790906 -0.0260029 -0.372651 0.00420402 -0.0260029 -0.373622 0.000120672 -0.0198029 -0.373995 0.00294349 -0.0260029 -0.373813 0.00012068 -0.0260029 -0.373995 -0.00380814 -0.0260029 -0.373692 -0.0080697 -0.0198029 -0.372602 -0.0113969 -0.025918 -0.371121 -0.0152811 -0.0198029 -0.368509 -0.0129912 -0.025827 -0.37018 -0.0439676 -0.0214844 -0.334246 -0.0464834 -0.0212815 -0.330754 -0.051688 -0.0207381 -0.320496 -0.0527092 -0.0205874 -0.317468 -0.0539777 -0.0198029 -0.31233 0.0133937 -0.000502937 -0.278597 0.0125986 -0.0195029 -0.280212 0.0129798 -0.0196007 -0.279437 -0.0421099 0.00239706 -0.212347 -0.042976 0.00239706 -0.214059 -0.041651 0.00239706 -0.214059 -0.045076 0.00239706 -0.216159 -0.046126 0.00239706 -0.215878 -0.0450761 0.00239706 -0.217484 -0.0468947 0.00239706 -0.215109 -0.048501 0.00239706 -0.214059 -0.0468947 0.00239706 -0.213009 -0.046126 0.00239706 -0.21224 -0.0480421 0.00239706 -0.212346 -0.0467885 0.00239706 -0.211093 -0.045076 0.00239706 -0.211959 -0.045076 0.00239706 -0.210634 -0.0546481 -0.0195272 -0.296745 -0.0538125 -0.000476764 -0.281608 -0.0538126 -0.000502937 -0.28161 -0.0538106 -0.000388161 -0.281573 -0.0538071 -0.000402937 -0.28151 -0.0537199 -0.000302937 -0.27993 -0.0537143 -0.0182966 -0.279829 -0.0538332 -0.00517527 -0.281982 -0.0540526 -0.0133437 -0.285957 -0.0542763 -0.0168941 -0.29001 -0.0543242 -0.0174182 -0.290877 -0.00410532 -0.0200029 -0.0514005 -0.00255536 -0.0200029 -0.0540852 -0.00255536 -2.93696e-06 -0.0540852 -0.00100536 -2.93696e-06 -0.0545005 -0.00100536 -0.0200029 -0.0545005 0.000544641 -2.93696e-06 -0.0540852 0.000544641 -0.0200029 -0.0540852 0.00167933 -2.93696e-06 -0.0529506 0.00209468 -2.93696e-06 -0.0514006 0.00167933 -0.0200029 -0.0529506 -0.00100529 -2.93696e-06 -0.0483005 -0.00100529 -0.0200029 -0.0483005 -0.00255529 -2.93696e-06 -0.0487158 -0.00368998 -0.0200029 -0.0498505 -0.0010054 -0.0203029 -0.0574005 -0.00161765 -0.0235646 -0.057369 -0.00100525 -0.023599 -0.0574005 9.78802e-05 -0.0236651 -0.0572982 -0.00400524 -0.0234483 -0.0565967 -0.00400534 -0.0238886 -0.0462043 -0.00620144 -0.0203029 -0.0484005 -0.00560641 -0.0237227 -0.0475494 -0.00687604 -0.0235233 -0.0501617 -0.00211629 -0.0240398 -0.0455043 -0.00400526 -0.0203029 -0.0462043 -0.00100525 -0.0203029 -0.0454005 0.000222173 -0.0241761 -0.0455274 0.00419087 -0.0203029 -0.0484006 0.0048918 -0.0241965 -0.0502942 -0.000347893 -0.0139385 0.0417235 -0.0004019 -0.00800294 0.0424186 -0.000603394 -0.00800294 0.0402288 -0.00375707 -0.00800294 0.0373578 -0.00518331 -0.0158431 0.0372363 -0.00465173 -0.0160519 0.0372278 -0.00376667 -0.0162787 0.0373554 -0.00793293 -0.0135413 0.0384475 -0.00790151 -0.0135851 0.0384182 -0.00595613 -0.00800294 0.0373622 -0.00650262 -0.0150487 0.0375388 -0.00881482 -0.0118996 0.0395991 -0.000880965 -0.0115611 0.0438481 -0.000493848 -0.0128112 0.0428601 -0.000404341 -0.0132625 0.0424341 -0.029781 -0.020144 -0.0250153 -0.0311611 -0.019535 -0.0271026 -0.0328268 -0.00800294 -0.0279977 -0.0338286 -0.016565 -0.0191816 -0.0320537 -0.0183766 -0.0196551 -0.0309611 -0.019202 -0.0204278 -0.0295767 -0.0201642 -0.0236749 -0.0299152 -0.0198948 -0.0219623 -0.0305644 -0.0194706 -0.0208616 -0.0308291 -0.00250294 -0.0255498 -0.0322017 -0.000302937 -0.0269224 -0.0359517 -0.00250294 -0.0269224 -0.0373243 -0.00250294 -0.0255498 -0.0373243 -0.000302937 -0.0255498 -0.0378267 -0.00250294 -0.0236747 -0.0359516 -0.000302937 -0.0204272 -0.0340766 -0.00250294 -0.0199248 -0.0322016 -0.00250294 -0.0204272 -0.0322016 -0.000302937 -0.0204272 -0.0303267 -0.00250294 -0.0236748 0.0654022 -0.00250294 -0.0318721 0.0640296 -0.00250294 -0.0332447 0.0640296 -0.000302937 -0.0332447 0.0621546 -0.000302937 -0.033747 0.0602796 -0.000302937 -0.0332446 0.0589071 -0.00250294 -0.028122 0.0584046 -0.000302937 -0.029997 0.0589071 -0.000302937 -0.028122 0.0602797 -0.00250294 -0.0267494 0.0621547 -0.000302937 -0.026247 0.0654022 -0.00250294 -0.0281221 0.0579173 -0.00250294 0.024128 0.0565447 -0.000302937 0.0227554 0.0546697 -0.00250294 0.022253 0.0527947 -0.000302937 0.0227555 0.0527947 -0.00250294 0.0227555 0.0514221 -0.00250294 0.0241281 0.0509197 -0.00250294 0.0260031 0.0509197 -0.000302937 0.0260031 0.0514221 -0.00250294 0.0278781 0.0527948 -0.00250294 0.0292507 0.0546698 -0.00250294 0.029753 0.0579173 -0.00250294 0.027878 0.0579173 -0.000302937 0.027878 -0.00160032 -0.00250294 0.0398485 -0.00160032 -0.000302937 0.0398485 -0.00484794 -0.00250294 0.0379736 -0.00672294 -0.00250294 0.038476 -0.00672294 -0.000302937 0.038476 -0.00809551 -0.00250294 0.0398486 -0.00859789 -0.000302937 0.0417236 -0.00809546 -0.00250294 0.0435986 -0.00672285 -0.00250294 0.0449712 -0.00484785 -0.00250294 0.0454736 -0.00672285 -0.000302937 0.0449712 -0.00160027 -0.000302937 0.0435985 -0.00109789 -0.000302937 0.0417235 -0.0516778 -2.93696e-06 -0.277075 -0.0484519 0.00209706 -0.278937 -0.0465894 -2.93696e-06 -0.278438 -0.0465894 0.00209706 -0.278438 -0.0452259 0.00209706 -0.277075 -0.0452259 -2.93696e-06 -0.277075 -0.0447268 -2.93696e-06 -0.275213 -0.0452259 0.00209706 -0.27335 -0.0452259 -2.93696e-06 -0.27335 -0.0465893 0.00209706 -0.271987 -0.0484518 0.00209706 -0.271487 -0.0521768 0.00209706 -0.275212 -0.0516778 -2.93696e-06 -0.27335 -0.0516778 0.00209706 -0.277075 0.00593811 -2.93696e-06 -0.272333 0.00780057 0.00209706 -0.275559 0.0115256 0.00209706 -0.275559 0.012889 0.00209706 -0.274196 0.012889 -2.93696e-06 -0.274196 0.0128891 0.00209706 -0.270471 0.0128891 -2.93696e-06 -0.270471 0.00966316 0.00209706 -0.268608 0.00643719 0.00209706 -0.270471 0.00593811 0.00209706 -0.272333 -0.048302 0.00209706 -0.215921 -0.048302 -2.93696e-06 -0.215921 -0.0469386 0.00209706 -0.217285 -0.0450761 0.00209706 -0.217784 -0.0450761 -2.93696e-06 -0.217784 -0.0418501 -2.93696e-06 -0.215922 -0.041351 0.00209706 -0.214059 -0.041351 -2.93696e-06 -0.214059 -0.0418501 0.00209706 -0.212197 -0.0418501 -2.93696e-06 -0.212197 -0.0432135 0.00209706 -0.210833 -0.0432135 -2.93696e-06 -0.210833 -0.045076 0.00209706 -0.210334 -0.0469385 0.00209706 -0.210833 -0.048801 0.00209706 -0.214059 -0.048801 -2.93696e-06 -0.214059 0.0167559 -2.93696e-06 -0.222996 0.0172549 0.00209706 -0.224859 0.0186183 0.00209706 -0.226222 0.0223433 -2.93696e-06 -0.226222 0.0237068 -2.93696e-06 -0.221134 0.0204809 0.00209706 -0.219272 0.0172549 0.00209706 -0.221134 0.0172549 -2.93696e-06 -0.221134 0.0167559 0.00209706 -0.222996 -0.045142 -2.93696e-06 -0.158678 -0.0437786 -2.93696e-06 -0.160042 -0.0437786 0.00209706 -0.160042 -0.0419161 -2.93696e-06 -0.160541 -0.0381911 0.00209706 -0.156816 -0.0381911 -2.93696e-06 -0.156816 -0.0386901 0.00209706 -0.154953 -0.0400535 0.00209706 -0.15359 -0.041916 -2.93696e-06 -0.153091 -0.041916 0.00209706 -0.153091 -0.0437785 -2.93696e-06 -0.15359 -0.045142 0.00209706 -0.154953 -0.045142 -2.93696e-06 -0.154953 -0.045142 0.00209706 -0.158678 0.0295336 -2.93696e-06 -0.168859 0.030897 0.00209706 -0.170223 0.0327595 -2.93696e-06 -0.170722 0.0327595 0.00209706 -0.170722 0.0359855 0.00209706 -0.168859 0.0359855 -2.93696e-06 -0.168859 0.0364846 -2.93696e-06 -0.166997 0.0364846 0.00209706 -0.166997 0.0359856 0.00209706 -0.165134 0.0346221 0.00209706 -0.163771 0.0327596 0.00209706 -0.163272 0.0327596 -2.93696e-06 -0.163272 0.0308971 0.00209706 -0.163771 0.0295337 -2.93696e-06 -0.165134 0.0290346 -2.93696e-06 -0.166997 0.0290346 0.00209706 -0.166997 0.0422509 0.00209706 -0.110859 0.0422509 -2.93696e-06 -0.110859 0.0436143 -2.93696e-06 -0.112223 0.0454768 -2.93696e-06 -0.112722 0.0473393 -2.93696e-06 -0.112223 0.0487028 -2.93696e-06 -0.110859 0.0492018 0.00209706 -0.108997 0.0487028 -2.93696e-06 -0.107134 0.0473394 -2.93696e-06 -0.105771 0.0454769 0.00209706 -0.105272 0.0454769 -2.93696e-06 -0.105272 0.0436144 0.00209706 -0.105771 0.0422509 0.00209706 -0.107134 0.0422509 -2.93696e-06 -0.107134 0.0417518 -2.93696e-06 -0.108997 -0.0418692 0.00209706 -0.099391 -0.0405058 0.00209706 -0.100754 -0.0367808 0.00209706 -0.100754 -0.0354173 0.00209706 -0.0993911 -0.0354173 -2.93696e-06 -0.0993911 -0.0349183 -2.93696e-06 -0.0975286 -0.0367807 0.00209706 -0.0943026 -0.0405057 0.00209706 -0.0943026 -0.0405057 -2.93696e-06 -0.0943026 -0.0418692 0.00209706 -0.095666 -0.0423683 0.00209706 -0.0975285 0.00966311 -0.00986474 -0.272333 0.00756311 -0.00860294 -0.272333 0.0117631 -0.00860294 -0.272333 0.0114818 -0.00860294 -0.273383 0.0117631 0.00239706 -0.272333 0.0107131 0.00239706 -0.274152 0.0107131 -0.00860294 -0.274152 0.00966308 -0.00860294 -0.274433 0.00861309 -0.00860294 -0.274152 0.00861309 0.00239706 -0.274152 0.00784444 -0.00860294 -0.273383 0.00784447 -0.00860294 -0.271283 0.00784447 0.00239706 -0.271283 0.00861313 -0.00860294 -0.270515 0.00966314 -0.00860294 -0.270233 0.0107131 -0.00860294 -0.270515 0.00966314 0.00239706 -0.270233 0.0107131 0.00239706 -0.270515 0.0114818 -0.00860294 -0.271283 -0.0466332 -0.00860294 -0.276262 -0.0463518 -0.00860294 -0.275212 -0.0484518 -0.00986474 -0.275212 -0.0502705 -0.00860294 -0.276262 -0.0484518 -0.00860294 -0.273112 -0.0466332 0.00239706 -0.276262 -0.0474019 -0.00860294 -0.277031 -0.0474019 0.00239706 -0.277031 -0.0484519 -0.00860294 -0.277312 -0.0484519 0.00239706 -0.277312 -0.0495019 -0.00860294 -0.277031 -0.0495019 0.00239706 -0.277031 -0.0505518 -0.00860294 -0.275212 -0.0502705 -0.00860294 -0.274162 -0.0502705 0.00239706 -0.274162 -0.0495018 -0.00860294 -0.273394 -0.0495018 0.00239706 -0.273394 -0.0474018 -0.00860294 -0.273394 -0.0466332 -0.00860294 -0.274163 -0.0466332 0.00239706 -0.274163 -0.0463518 0.00239706 -0.275212 0.0222995 -0.00860294 -0.224047 0.0204809 -0.00986474 -0.222997 0.0186622 -0.00860294 -0.224046 0.0204808 -0.00860294 -0.225097 0.0194308 -0.00860294 -0.224815 0.0215308 -0.00860294 -0.224815 0.0183809 -0.00860294 -0.222996 0.0215309 -0.00860294 -0.221178 0.0194309 -0.00860294 -0.221178 0.0222995 -0.00860294 -0.221947 0.0194308 0.00239706 -0.224815 0.0186622 0.00239706 -0.224046 0.0183809 0.00239706 -0.222996 0.0186622 -0.00860294 -0.221946 0.0186622 0.00239706 -0.221946 0.0204809 -0.00860294 -0.220897 0.0225809 -0.00860294 -0.222997 0.0222995 0.00239706 -0.221947 -0.044026 -0.00860294 -0.215878 -0.045076 -0.00860294 -0.216159 -0.045076 -0.00986474 -0.214059 -0.0468947 -0.00860294 -0.213009 -0.046126 -0.00860294 -0.21224 -0.047176 -0.00860294 -0.214059 -0.042976 -0.00860294 -0.214059 -0.0432574 -0.00860294 -0.215109 -0.0432574 0.00239706 -0.215109 -0.044026 0.00239706 -0.215878 -0.046126 -0.00860294 -0.215878 -0.0468947 -0.00860294 -0.215109 -0.047176 0.00239706 -0.214059 -0.045076 -0.00860294 -0.211959 -0.044026 -0.00860294 -0.21224 -0.044026 0.00239706 -0.21224 -0.0432574 -0.00860294 -0.213009 -0.0432574 0.00239706 -0.213009 0.0309409 -0.00860294 -0.168047 0.0317096 -0.00860294 -0.168815 0.0309409 -0.00860294 -0.165947 0.0306596 -0.00860294 -0.166997 0.0345783 -0.00860294 -0.165947 0.0348596 -0.00860294 -0.166997 0.0327596 -0.00986474 -0.166997 0.0345782 -0.00860294 -0.168047 0.0348596 0.00239706 -0.166997 0.0338096 -0.00860294 -0.168815 0.0345782 0.00239706 -0.168047 0.0338096 0.00239706 -0.168815 0.0327596 -0.00860294 -0.169097 0.0309409 0.00239706 -0.168047 0.0317096 -0.00860294 -0.165178 0.0309409 0.00239706 -0.165947 0.0327596 -0.00860294 -0.164897 0.0338096 -0.00860294 -0.165178 0.0345783 0.00239706 -0.165947 -0.0408661 -0.00860294 -0.158635 -0.0398161 -0.00860294 -0.156816 -0.0419161 -0.00860294 -0.158916 -0.0419161 -0.00986474 -0.156816 -0.041916 -0.00860294 -0.154716 -0.0400974 -0.00860294 -0.157866 -0.0429661 -0.00860294 -0.158635 -0.0419161 0.00239706 -0.158916 -0.0429661 0.00239706 -0.158635 -0.0437347 -0.00860294 -0.157866 -0.0440161 -0.00860294 -0.156816 -0.0437347 -0.00860294 -0.155766 -0.0437347 0.00239706 -0.155766 -0.042966 -0.00860294 -0.154997 -0.040866 -0.00860294 -0.154997 -0.0400974 -0.00860294 -0.155766 -0.0398161 0.00239706 -0.156816 0.0472955 -0.00860294 -0.110047 0.0475768 -0.00860294 -0.108997 0.0436582 -0.00860294 -0.110047 0.0444269 -0.00860294 -0.107178 0.0433768 -0.00860294 -0.108997 0.0454768 -0.00986474 -0.108997 0.0465269 -0.00860294 -0.107178 0.0454769 -0.00860294 -0.106897 0.0472955 -0.00860294 -0.107947 0.0472955 0.00239706 -0.110047 0.0465268 0.00239706 -0.110816 0.0465268 -0.00860294 -0.110816 0.0454768 -0.00860294 -0.111097 0.0444268 -0.00860294 -0.110815 0.0444268 0.00239706 -0.110815 0.0433768 0.00239706 -0.108997 0.0436582 0.00239706 -0.107947 0.0436582 -0.00860294 -0.107947 0.0444269 0.00239706 -0.107178 0.0454769 0.00239706 -0.106897 0.0465269 0.00239706 -0.107178 0.0472955 0.00239706 -0.107947 -0.0368246 -0.00860294 -0.0985785 -0.0386433 -0.00986474 -0.0975285 -0.0396933 -0.00860294 -0.0993472 -0.0375933 -0.00860294 -0.0993472 -0.0404619 -0.00860294 -0.0985785 -0.0368246 -0.00860294 -0.0964786 -0.0386433 -0.00860294 -0.0996285 -0.0386433 0.00239706 -0.0996285 -0.0396933 0.00239706 -0.0993472 -0.0407433 -0.00860294 -0.0975285 -0.0407433 0.00239706 -0.0975285 -0.0404619 -0.00860294 -0.0964785 -0.0396932 -0.00860294 -0.0957099 -0.0386432 -0.00860294 -0.0954285 -0.0396932 0.00239706 -0.0957099 -0.0375932 -0.00860294 -0.0957099 -0.0368246 0.00239706 -0.0964786 -0.0365433 -0.00860294 -0.0975286 -0.00433931 -0.0195029 -0.352496 -0.0025092 -0.0315029 -0.354326 0.0024908 -0.0195029 -0.354326 0.0024908 -0.0315029 -0.354326 0.00432095 -0.0195029 -0.352496 0.00499085 -0.0315029 -0.349996 0.00249091 -0.0315029 -0.345666 0.00249091 -0.0195029 -0.345666 -9.08344e-06 -0.0315029 -0.344996 -0.00250909 -0.0315029 -0.345666 -0.00500915 -0.0195029 -0.349996 -0.00433924 -0.0315029 -0.347496 -0.00259624 -0.00800294 0.0404235 -0.00484793 -0.00800294 0.0391236 -0.00484793 -0.00250294 0.0391236 -0.00709958 -0.00800294 0.0404236 -0.00614792 -0.00250294 0.0394719 -0.00744789 -0.00800294 0.0417236 -0.00744789 -0.00250294 0.0417236 -0.00614786 -0.00250294 0.0439752 -0.00354786 -0.00250294 0.0439752 0.0569214 -0.00800294 0.024703 0.0559697 -0.00800294 0.0237514 0.0559697 -0.00250294 0.0237514 0.0546697 -0.00250294 0.0234031 0.0546697 -0.00800294 0.0234031 0.052418 -0.00250294 0.0247031 0.0520697 -0.00800294 0.0260031 0.0524181 -0.00250294 0.0273031 0.0524181 -0.00800294 0.0273031 0.0533697 -0.00800294 0.0282547 0.0533697 -0.00250294 0.0282547 0.0559697 -0.00800294 0.0282547 0.0559697 -0.00250294 0.0282547 0.0572697 -0.00800294 0.026003 0.0647546 -0.00800294 -0.0299971 0.0634546 -0.00800294 -0.0322487 0.0608546 -0.00800294 -0.0322487 0.0599029 -0.00800294 -0.031297 0.0595546 -0.00800294 -0.029997 0.0595546 -0.00250294 -0.029997 0.059903 -0.00800294 -0.028697 0.059903 -0.00250294 -0.028697 0.0634547 -0.00800294 -0.0277454 0.0621547 -0.00250294 -0.027397 0.0644063 -0.00800294 -0.0286971 -0.031825 -0.00800294 -0.0249748 -0.0327767 -0.00800294 -0.0259265 -0.0327767 -0.00250294 -0.0259265 -0.0363284 -0.00800294 -0.0249748 -0.0366767 -0.00250294 -0.0236748 -0.0363283 -0.00250294 -0.0223748 -0.0353766 -0.00250294 -0.0214231 -0.0340766 -0.00800294 -0.0210748 -0.0340766 -0.00250294 -0.0210748 -0.031825 -0.00800294 -0.0223748 -0.031825 -0.00250294 -0.0223748 -0.0314767 -0.00800294 -0.0236748 0.0654022 -0.000302937 -0.0318721 0.065662 -2.93696e-06 -0.0320221 0.0641796 -2.93696e-06 -0.0335045 0.0621546 -2.93696e-06 -0.034047 0.0601296 -2.93696e-06 -0.0335044 0.058907 -0.000302937 -0.031872 0.0586472 -2.93696e-06 -0.032022 0.0602797 -0.000302937 -0.0267494 0.0640297 -0.000302937 -0.0267495 0.0654022 -0.000302937 -0.0281221 0.0641797 -2.93696e-06 -0.0264897 0.0659046 -0.000302937 -0.0299971 0.0662046 -2.93696e-06 -0.0299971 0.0546697 -0.000302937 0.022253 0.0546697 -2.93696e-06 0.0219531 0.0526447 -2.93696e-06 0.0224957 0.0514221 -0.000302937 0.0241281 0.0514221 -0.000302937 0.0278781 0.0527948 -0.000302937 0.0292507 0.0526448 -2.93696e-06 0.0295105 0.0546698 -0.000302937 0.029753 0.0565448 -0.000302937 0.0292506 0.0566948 -2.93696e-06 0.0295104 0.0581772 -2.93696e-06 0.028028 0.0584197 -0.000302937 0.026003 0.0587197 -2.93696e-06 0.026003 0.0579173 -0.000302937 0.024128 -0.00297294 -0.000302937 0.0384759 -0.00484795 -2.93696e-06 0.0376736 -0.00484794 -0.000302937 0.0379736 -0.00809551 -0.000302937 0.0398486 -0.00835532 -2.93696e-06 0.0396986 -0.00889789 -2.93696e-06 0.0417236 -0.00809546 -0.000302937 0.0435986 -0.00835527 -2.93696e-06 0.0437486 -0.00687285 -2.93696e-06 0.045231 -0.00484785 -0.000302937 0.0454736 -0.00297285 -0.000302937 0.0449711 -0.00282285 -2.93696e-06 0.0452309 -0.00134046 -2.93696e-06 0.0437485 -0.0340767 -0.000302937 -0.0274248 -0.0359517 -0.000302937 -0.0269224 -0.0378267 -0.000302937 -0.0236747 -0.0373242 -0.000302937 -0.0217998 -0.0361016 -2.93696e-06 -0.0201674 -0.0340766 -0.000302937 -0.0199248 -0.0340766 -2.93696e-06 -0.0196248 -0.0308291 -0.000302937 -0.0217998 -0.0303267 -0.000302937 -0.0236748 -0.0305692 -2.93696e-06 -0.0216498 -0.0308291 -0.000302937 -0.0255498 0.0436143 0.00209706 -0.112223 0.0454768 0.00209706 -0.112722 0.0454768 0.00239706 -0.112422 0.0471893 0.00239706 -0.111963 0.0473393 0.00209706 -0.112223 0.048443 0.00239706 -0.110709 0.0487028 0.00209706 -0.110859 0.048443 0.00239706 -0.107284 0.0487028 0.00209706 -0.107134 0.0471894 0.00239706 -0.106031 0.0473394 0.00209706 -0.105771 0.0454769 0.00239706 -0.105572 0.0425107 0.00239706 -0.107284 0.0417518 0.00209706 -0.108997 -0.0386433 0.00239706 -0.100954 -0.0386433 0.00209706 -0.101254 -0.0356771 0.00239706 -0.0992411 -0.0349183 0.00209706 -0.0975286 -0.0356771 0.00239706 -0.0958161 -0.0369307 0.00239706 -0.0945624 -0.0354173 0.00209706 -0.0956661 -0.0386432 0.00209706 -0.0938035 -0.0420683 0.00239706 -0.0975285 -0.0416094 0.00239706 -0.099241 -0.0419161 0.00209706 -0.160541 -0.0402036 0.00239706 -0.159782 -0.0400536 0.00209706 -0.160042 -0.03895 0.00239706 -0.158528 -0.0386901 0.00209706 -0.158678 -0.0389499 0.00239706 -0.155103 -0.0402035 0.00239706 -0.15385 -0.041916 0.00239706 -0.153391 -0.0437785 0.00209706 -0.15359 -0.0436285 0.00239706 -0.15385 -0.0456411 0.00209706 -0.156816 0.0295336 0.00209706 -0.168859 0.034622 0.00209706 -0.170223 0.0357257 0.00239706 -0.168709 0.0295337 0.00209706 -0.165134 0.0293346 0.00239706 -0.166997 0.0204808 0.00209706 -0.226722 0.0223433 0.00209706 -0.226222 0.0237068 0.00209706 -0.224859 0.0239059 0.00239706 -0.222997 0.0242059 0.00209706 -0.222997 0.023447 0.00239706 -0.221284 0.0237068 0.00209706 -0.221134 0.0223434 0.00209706 -0.219771 0.0186184 0.00209706 -0.219771 0.0187684 0.00239706 -0.22003 0.0175147 0.00239706 -0.221284 0.0170559 0.00239706 -0.222996 -0.0480422 0.00239706 -0.215771 -0.0467886 0.00239706 -0.217025 -0.0433636 0.00239706 -0.217025 -0.0432136 0.00209706 -0.217285 -0.0421099 0.00239706 -0.215772 -0.0418501 0.00209706 -0.215922 -0.0433635 0.00239706 -0.211093 -0.0483019 0.00209706 -0.212196 0.00643714 0.00209706 -0.274196 0.00669695 0.00239706 -0.274046 0.00966307 0.00239706 -0.275758 0.00966306 0.00209706 -0.276058 0.0126292 0.00239706 -0.274046 0.0133881 0.00209706 -0.272333 0.0126293 0.00239706 -0.270621 0.0115257 0.00209706 -0.269107 0.0113756 0.00239706 -0.269367 0.00795065 0.00239706 -0.269367 0.00780065 0.00209706 -0.269107 -0.0503144 0.00209706 -0.278438 -0.0447268 0.00209706 -0.275213 -0.0484518 0.00239706 -0.271787 -0.051418 0.00239706 -0.2735 -0.0503143 0.00209706 -0.271987 -0.0518768 0.00239706 -0.275212 -0.0516778 0.00209706 -0.27335 -0.051418 0.00239706 -0.276925 -9.21146e-06 -0.0315029 -0.354996 0.00432095 -0.0315029 -0.352496 0.00432101 -0.0315029 -0.347496 0.00549085 -0.0320029 -0.349996 0.00274091 -0.0320029 -0.345233 -0.00500915 -0.0315029 -0.349996 -0.00550915 -0.0320029 -0.349996 -0.00433931 -0.0315029 -0.352496 -0.053731 -0.000502937 -0.281832 -0.053731 -0.00150294 -0.281832 -0.0537947 -0.00150294 -0.281729 -0.0537947 -0.000502937 -0.281729 0.0025215 -0.0245635 -0.0568892 0.00268158 -0.0246125 -0.0571356 -0.00472518 -0.024195 -0.0568003 -0.00319468 -0.0242959 -0.0578949 0.0052444 -0.0247819 -0.0527487 0.0041245 -0.0245298 -0.0549502 0.00434587 -0.0247068 -0.0551132 0.00237668 -0.0243877 -0.0566489 0.000112908 -0.0242446 -0.057549 0.000156279 -0.0244191 -0.0578322 -0.00238777 -0.0242896 -0.0578003 -0.00231994 -0.0241164 -0.0575159 -0.00455349 -0.024023 -0.0565577 -0.0065022 -0.0241563 -0.0549839 -0.00625106 -0.0239848 -0.0548206 -0.00715687 -0.0240141 -0.052567 -0.00744954 -0.0241858 -0.0526262 -0.00225129 -0.0236824 -0.0572845 0.00129194 -0.0237432 -0.0569433 0.00199463 -0.0237931 -0.0565968 0.00359574 -0.0239258 -0.0552515 -0.00604331 -0.0235457 -0.0546863 -0.00690289 -0.0234229 -0.0525045 -0.00700533 -0.0234621 -0.0514004 -0.00697319 -0.0234904 -0.0507797 -0.0016417 -0.0235633 -0.0573665 -0.00431781 -0.023436 -0.0564033 -0.00440525 -0.0235856 -0.0563621 -0.00625018 -0.0233927 -0.0543142 0.00419075 -0.0239887 -0.0544008 0.00395191 -0.0241077 -0.0548048 0.00227133 -0.0239618 -0.0564433 0.00228848 -0.0241132 -0.0564853 9.253e-05 -0.0238147 -0.0573136 -0.00226768 -0.0238372 -0.0573286 -0.0044355 -0.0237419 -0.0563987 -0.00691667 -0.0235757 -0.0525109 0.00508865 -0.0246575 -0.0527101 0.00496517 -0.0244899 -0.0526764 0.00398332 -0.0242575 -0.0548359 9.27545e-05 -0.0239678 -0.0573599 -0.00608352 -0.0237027 -0.0547121 -0.00696273 -0.0237324 -0.0525235 -0.00394983 -0.0203029 -0.0531005 -0.00270536 -0.0203029 -0.054345 -0.00100537 -0.0203029 -0.0548005 0.000694637 -0.0203029 -0.054345 0.00239468 -0.0203029 -0.0514006 0.00209468 -0.0200029 -0.0514006 0.00167937 -0.0200029 -0.0498506 0.00054471 -0.0200029 -0.0487159 -0.00100528 -0.0203029 -0.0480005 -0.00255529 -0.0200029 -0.0487158 -0.00270529 -0.0203029 -0.048456 -0.00440532 -0.0203029 -0.0514005 -0.00369002 -0.0200029 -0.0529505 0.0688385 -2.93696e-06 -0.00324521 0.0684698 -5.8962e-05 -0.00325703 0.0684721 -5.96787e-05 -0.00332788 0.0686102 -2.93696e-06 -0.0169008 0.0687944 -0.000159714 -0.0132172 0.0687092 -4.94569e-05 -0.0154055 -0.0489519 -0.000268883 -0.281426 -0.0488519 -0.000370979 -0.281426 -0.0492209 -0.000120213 -0.281426 -0.0493446 -7.66735e-05 -0.281426 -0.0397723 -2.93696e-06 -0.281426 -0.0435488 -2.93696e-06 -0.281426 -0.0497652 -4.08076e-06 -0.281426 -0.049784 -3.46274e-06 -0.281426 -0.019466 -2.93696e-06 -0.281427 0.0118372 -0.000149384 -0.281427 0.0120004 -0.000502937 -0.281427 0.0114431 -2.93696e-06 -0.281427 0.00401486 -2.93696e-06 -0.281427 -0.0370403 -2.62698e-05 -0.00956646 -0.036308 -2.93696e-06 9.24562e-05 -0.0364581 -2.93696e-06 -0.00242676 0.0353322 0.0820971 0.00642379 0.0336033 0.0815971 0.0082296 0.0336315 0.0815971 0.00952339 0.0336033 0.0820971 0.0082296 0.0336315 0.0820971 0.00952339 0.0354373 0.0820971 0.0112523 0.0249526 0.0815971 -0.0291947 0.0249526 0.0820971 -0.0291947 0.0233394 0.0815971 -0.0277441 0.0233394 0.0820971 -0.0277441 0.0234677 0.0815971 -0.0255785 0.0231564 0.0820971 -0.0266467 0.0234677 0.0820971 -0.0255785 0.0252408 0.0815971 -0.0243285 0.00638722 0.0815971 -0.0366269 0.00638722 0.0820971 -0.0366269 0.00641538 0.0815971 -0.0353331 0.00641538 0.0820971 -0.0353331 0.00708665 0.0815971 -0.0342267 0.00822119 0.0815971 -0.0336042 -0.0120558 0.0815971 -0.0374737 -0.0110837 0.0820971 -0.0380149 -0.0120558 0.0820971 -0.0374737 -0.0126969 0.0815971 -0.0365643 -0.0125686 0.0815971 -0.0343987 -0.0128799 0.0820971 -0.0354669 -0.0118247 0.0815971 -0.0335714 -0.0118247 0.0820971 -0.0335714 -0.0107955 0.0815971 -0.0331487 -0.00968485 0.0815971 -0.0332145 -0.0284745 0.0815971 -0.0275119 -0.0275023 0.0820971 -0.0280531 -0.0291155 0.0820971 -0.0266026 -0.0292985 0.0815971 -0.0255051 -0.0289873 0.0815971 -0.0244369 -0.0289873 0.0820971 -0.0244369 -0.0282433 0.0815971 -0.0236096 -0.0282433 0.0820971 -0.0236096 -0.0272141 0.0815971 -0.023187 -0.0377125 0.0815971 -0.0106755 -0.0377125 0.0820971 -0.0106755 -0.0385366 0.0815971 -0.00866865 -0.0385366 0.0820971 -0.00866865 -0.0382253 0.0820971 -0.00760047 -0.0364522 0.0815971 -0.00635051 -0.0374814 0.0820971 -0.00677314 -0.0353415 0.0815971 -0.00641629 -0.0364522 0.0820971 -0.00635051 -0.0353415 0.0820971 -0.00641629 -0.0273329 0.0815971 0.024943 -0.0279739 0.0815971 0.0258523 -0.0273329 0.0820971 0.024943 -0.0260726 0.0815971 0.0292679 -0.0271018 0.0820971 0.0288453 -0.00952431 0.0820971 0.0336399 -0.0104964 0.0815971 0.034181 -0.0104964 0.0820971 0.034181 -0.0113205 0.0815971 0.0361878 -0.0113205 0.0820971 0.0361878 -0.0110092 0.0820971 0.037256 -0.0102653 0.0815971 0.0380834 -0.0092361 0.0815971 0.038506 0.00967552 0.0820971 0.033222 0.00856914 0.0815971 0.0338933 0.00794663 0.0820971 0.0350278 0.00797479 0.0820971 0.0363216 0.0097806 0.0820971 0.0380505 0.0110744 0.0815971 0.0380224 0.0243934 0.0815971 0.0263599 0.0243934 0.0820971 0.0263599 0.0250647 0.0815971 0.0274662 0.0261992 0.0820971 0.0280887 0.0349143 0.0820971 -0.012776 0.0339422 0.0815971 -0.0122349 0.0339422 0.0820971 -0.0122349 0.0333012 0.0815971 -0.0113255 0.0333012 0.0820971 -0.0113255 0.0334294 0.0820971 -0.00915988 0.0341733 0.0815971 -0.00833255 0.0352026 0.0815971 -0.00790992 0.0363132 0.0815971 -0.00797571 0.0352026 0.0820971 -0.00790992 0.0363132 0.0820971 -0.00797571 -0.0367422 0.0820971 0.00654311 -0.0385124 0.0815971 0.00761715 -0.0385124 0.0820971 0.00761715 -0.0395084 0.0815971 0.0094324 -0.0395084 0.0820971 0.0094324 -0.0394634 0.0820971 0.0115025 -0.0365741 0.0815971 0.0142687 -0.0383893 0.0820971 0.0132727 0.056285 0.0819047 -0.0342201 0.0605567 0.0820971 -0.0360874 0.0606563 0.0819047 -0.0359197 0.0613211 0.0816611 -0.0359169 0.0565052 0.0812971 -0.0336538 0.0378374 0.0815971 0.0105528 0.0378374 0.0820971 0.0105528 0.0384599 0.0815971 0.00941831 0.0384599 0.0820971 0.00941831 0.0384318 0.0815971 0.00812452 0.036626 0.0815971 0.00639564 0.0377605 0.0820971 0.00701815 0.0263514 0.0820971 -0.0243943 0.0274578 0.0820971 -0.0250656 0.0280803 0.0815971 -0.0262001 0.0280803 0.0820971 -0.0262001 0.0262464 0.0820971 -0.0292228 0.00951498 0.0820971 -0.0336324 0.0106214 0.0820971 -0.0343037 0.0112439 0.0815971 -0.0354382 0.0112157 0.0815971 -0.036732 0.0105444 0.0820971 -0.0378383 0.0105444 0.0815971 -0.0378383 0.00940989 0.0820971 -0.0384609 0.0081161 0.0815971 -0.0384327 -0.00857848 0.0815971 -0.0338858 -0.00857848 0.0820971 -0.0338858 -0.00795597 0.0815971 -0.0350203 -0.00795597 0.0820971 -0.0350203 -0.00798412 0.0815971 -0.0363141 -0.0086554 0.0815971 -0.0374205 -0.00978993 0.0820971 -0.038043 -0.0110837 0.0815971 -0.0380149 -0.0261035 0.0815971 -0.0232528 -0.0249971 0.0815971 -0.023924 -0.0261035 0.0820971 -0.0232528 -0.0243746 0.0815971 -0.0250586 -0.0243746 0.0820971 -0.0250586 -0.0262085 0.0820971 -0.0280812 -0.0275023 0.0815971 -0.0280531 -0.0336126 0.0815971 -0.0082221 -0.0342351 0.0820971 -0.00708757 -0.0336408 0.0820971 -0.00951589 -0.0336408 0.0815971 -0.00951589 -0.0354466 0.0820971 -0.0112448 -0.0249619 0.0820971 0.0292022 -0.0238555 0.0815971 0.0285309 -0.0238555 0.0820971 0.0285309 -0.023233 0.0820971 0.0273963 -0.0232612 0.0820971 0.0261026 -0.025067 0.0820971 0.0243737 -0.00812544 0.0820971 0.0384402 -0.00701906 0.0815971 0.0377689 -0.00639655 0.0815971 0.0366344 -0.00701906 0.0820971 0.0377689 -0.00639655 0.0820971 0.0366344 -0.00709599 0.0815971 0.0342342 -0.00823052 0.0815971 0.0336117 -0.00709599 0.0820971 0.0342342 0.0121808 0.0815971 0.0373511 0.0128033 0.0820971 0.0362165 0.0127751 0.0815971 0.0349228 0.0127751 0.0820971 0.0349228 0.0121038 0.0815971 0.0338164 0.0109693 0.0820971 0.0331939 0.027493 0.0820971 0.0280606 0.0291062 0.0815971 0.0266101 0.0292892 0.0815971 0.0255126 0.0291062 0.0820971 0.0266101 0.0289779 0.0815971 0.0244444 0.0289779 0.0820971 0.0244444 0.0272048 0.0815971 0.0231945 0.0260941 0.0820971 0.0232603 0.0374196 0.0820971 -0.00864698 0.0374196 0.0815971 -0.00864698 0.0380421 0.0815971 -0.00978152 0.0380421 0.0820971 -0.00978152 0.0373427 0.0815971 -0.0121817 0.0373427 0.0820971 -0.0121817 0.0362081 0.0820971 -0.0128042 0.0362081 0.0815971 -0.0128042 0.0349143 0.0815971 -0.012776 -0.034504 0.0815971 0.0142236 -0.034504 0.0820971 0.0142236 -0.0327338 0.0820971 0.0131496 -0.0317378 0.0815971 0.0113343 -0.0328569 0.0815971 0.00749407 -0.0317828 0.0820971 0.00926427 -0.0367422 0.0815971 0.00654311 -0.0704639 0.0705971 0.00240027 -0.0705378 0.0710971 0.00292474 -0.0765526 0.071078 0.00410142 -0.0705378 0.0776971 0.00292474 -0.0699668 0.0776971 0.00230609 -0.0702154 0.0708471 0.00235319 -0.0704675 0.0705971 0.00229126 -0.0699704 0.0710971 0.00219241 -0.0681634 0.0800249 0.00186186 -0.0684794 0.0799211 0.00194013 -0.0674644 0.0807869 0.0023136 -0.065749 0.0807869 0.00197249 -0.0631677 0.0800971 0.00140209 -0.0586227 0.0807869 0.00713289 -0.0561132 0.0800971 0.0163544 -0.0527279 0.0800971 0.0252183 -0.0520852 0.0800971 0.0278407 -0.0565146 0.0807869 0.0336613 -0.0599272 0.0789197 0.0355359 -0.0602019 0.0798906 0.035095 -0.0594108 0.0795445 0.0353612 -0.0581447 0.0807869 0.0342951 -0.0610652 0.0776971 0.0354306 -0.0610652 0.0710971 0.0354306 -0.0461099 0.0802965 0.0314363 -0.0455852 0.0805172 0.0318083 -0.0498716 0.0805971 0.0243664 -0.0559869 0.0800971 -0.00140683 -0.0554794 0.0805971 0.00167985 -0.0554233 0.0805971 -0.00300098 -0.0556496 0.0800971 0.00629994 -0.0540064 0.0805971 0.0128125 -0.0532883 0.0805971 0.0155312 -0.0604862 0.0708471 0.0357395 -0.0602513 0.0710971 0.0356457 -0.0606656 0.0705971 0.0359272 -0.0607211 0.0705971 0.0358333 0.0758951 0.0709705 -0.00385534 0.0704546 0.0705971 -0.00239277 0.070206 0.0708471 -0.00234569 0.0705284 0.0776971 -0.00291724 0.0699575 0.0710971 -0.0022986 0.068154 0.0800249 -0.00185436 0.0684701 0.0799211 -0.00193263 0.0686268 0.0805537 -0.00253909 0.0688822 0.0797034 -0.00203442 0.0698288 0.0784751 -0.00226709 0.0699575 0.0776971 -0.0022986 0.0657397 0.0807869 -0.00196499 0.0675736 0.0800971 -0.00171015 0.0658582 0.0800971 -0.00136904 0.0606941 0.0800971 -0.00249796 0.0586134 0.0807869 -0.00712539 0.0526831 0.0807869 -0.0278542 0.0520759 0.0800971 -0.0278332 0.0531008 0.0807869 -0.0302701 0.0525358 0.0800971 -0.0304937 0.0544499 0.0807869 -0.0323172 0.0540216 0.0800971 -0.0327482 0.056285 0.0800971 -0.0342201 0.0601975 0.0781644 -0.0356231 0.0599179 0.0789197 -0.0355284 0.0608298 0.0788892 -0.0353353 0.0594014 0.0795445 -0.0353537 0.0592463 0.0805548 -0.0347196 0.0587042 0.0799552 -0.0351187 0.0602419 0.0776971 -0.0356382 0.0451242 0.0805971 -0.0323016 0.0461006 0.0802965 -0.0314288 0.0503115 0.0800971 -0.0245783 0.053759 0.0800971 -0.0156636 0.053279 0.0805971 -0.0155237 0.0524241 0.0805971 -0.0182026 0.0498623 0.0805971 -0.0243589 0.0607118 0.0705971 -0.0358258 0.0610558 0.0710971 -0.0354231 0.0667612 0.071078 -0.0376619 0.0669693 0.0710923 -0.0377275 0.0604769 0.0708471 -0.035732 0.0606563 0.0705971 -0.0359197 0.0710043 0.0749971 -0.00301188 0.07196 0.0749971 -0.00225231 0.0718551 0.0813992 -0.00233568 0.071377 0.0812983 -0.00271565 0.0708042 0.0812971 -0.00297207 0.073759 0.0726698 -0.00271235 0.0719425 0.0727279 -0.00319843 0.0712493 0.0737657 -0.0030606 0.0724565 0.0735303 -0.00237996 0.0704582 0.0819047 -0.00228376 0.0704643 0.0820971 -0.00208882 0.0710174 0.0816611 -0.00264328 0.0711604 0.0820971 -0.00222724 0.0743402 0.0725971 -0.00285956 0.0657397 0.0812971 -0.00196499 0.0840772 0.0725971 -0.00338215 0.083947 0.0725971 -0.00387942 0.0841156 0.0717971 -0.00490507 0.0836206 0.0725971 -0.00427658 0.0831581 0.0725971 -0.00450076 0.0833447 0.0717971 -0.0052787 0.0824881 0.0717971 -0.00529546 0.0826441 0.0725971 -0.00451082 0.0592715 0.0821958 -0.00408048 0.0589141 0.0823893 -0.00514734 0.0588548 0.0820519 -0.00602163 0.0587125 0.0825381 -0.00597553 0.060333 0.0812971 -0.00360098 0.0586134 0.0822724 -0.00712539 0.0575956 0.0826389 -0.0125906 0.0566872 0.0822724 -0.0165169 0.0532667 0.0822724 -0.025473 0.0527895 0.0813014 -0.0292051 0.052961 0.0821444 -0.0262456 0.0526803 0.081545 -0.0279671 0.0527317 0.0825377 -0.0264983 0.0547882 0.0820971 -0.0336381 0.0531008 0.0812971 -0.0302701 0.0528238 0.0812971 -0.0293694 0.0615081 0.0810957 -0.035599 0.0616633 0.0812983 -0.036049 0.0613242 0.0820246 -0.036308 0.0618187 0.0815013 -0.0364996 0.0619061 0.0749971 -0.036753 0.0615081 0.0749971 -0.035599 0.061951 0.0745292 -0.0367676 0.0622332 0.0737727 -0.0368597 0.0617419 0.0737631 -0.0356899 0.06338 0.072038 -0.0363268 0.0645298 0.0717971 -0.0367739 0.063452 0.0727384 -0.0372594 0.0735839 0.0717971 -0.0410456 0.072559 0.0725971 -0.0408722 0.073687 0.0717971 -0.0418961 -0.0712394 0.0820246 0.00232253 -0.0710268 0.0816611 0.00265077 -0.0711697 0.0820971 0.00223474 -0.0642924 0.0820971 0.00106331 -0.0628411 0.0812971 0.00211442 -0.0626094 0.0820971 0.0013487 -0.0717595 0.0815013 0.00242657 -0.0592809 0.0821958 0.00408798 -0.0596675 0.0814431 0.00441075 -0.0587218 0.0825381 0.00598303 -0.0588641 0.0820519 0.00602913 -0.0586227 0.0822724 0.00713289 -0.0597775 0.0820971 0.00304197 -0.0710137 0.0741971 0.00301938 -0.0713864 0.0812983 0.00272316 -0.0719693 0.0741971 0.00225981 -0.0718644 0.0813992 0.00234317 -0.0566966 0.0822724 0.0165244 -0.057605 0.0826389 0.0125981 -0.0553535 0.0826389 0.0203241 -0.0722971 0.073223 0.00235341 -0.0720541 0.0736811 0.00228404 -0.0528331 0.0812971 0.0293769 -0.0526896 0.081545 0.0279746 -0.0520524 0.0820971 0.0295513 -0.0521669 0.0821737 0.0285574 -0.053276 0.0822724 0.0254805 -0.0733989 0.0717971 0.00349369 -0.0565146 0.0812971 0.0336613 -0.0541381 0.0812971 0.0319795 -0.0531101 0.0812971 0.0302776 -0.0846689 0.0717971 0.00425062 -0.084125 0.0717971 0.00491257 -0.0831674 0.0725971 0.00450826 -0.0824974 0.0717971 0.00530295 -0.0613304 0.0816611 0.0359244 -0.0606656 0.0819047 0.0359272 -0.0617374 0.0808628 0.035692 -0.0613335 0.0820246 0.0363155 -0.0621096 0.0735844 0.0366718 -0.061897 0.0733545 0.0357541 -0.062347 0.0726466 0.035929 -0.0626084 0.0729221 0.0368327 -0.0630862 0.0726696 0.0369874 -0.0721798 0.0725971 0.0404934 -0.0638003 0.0720121 0.0364941 -0.0724302 0.0720121 0.0398495 -0.0736041 0.0720121 0.041085 -0.0730062 0.0725971 0.0418606 0.00757928 0.0820971 -0.0309816 0.0153405 0.0820971 -0.027963 0.00769816 0.0815971 -0.0314673 0.0224017 0.0815971 -0.0233996 0.0306214 0.0820971 -0.00892104 0.0276954 0.0815971 -0.0168029 0.0318878 0.0820971 -0.000690322 0.0323877 0.0815971 -0.000701201 0.0233986 0.0815971 0.0224101 0.016802 0.0815971 0.0277039 -0.0173369 0.0679971 -0.0831593 0.0345746 0.0679971 -0.0775899 0.00905733 0.0679971 -0.0844615 0.0133769 0.0675971 -0.0834806 0.0175089 0.0675971 -0.0827125 0.0220848 0.0679971 -0.082024 0.057834 0.0679971 -0.0622152 0.0528654 0.0675971 -0.065977 0.0462227 0.0679971 -0.0712671 0.0372462 0.0679971 -0.0763433 0.0372958 0.0675971 -0.0758737 0.0658872 0.0679971 -0.0536131 0.0660374 0.0675971 -0.0527896 -0.0825754 0.0675971 0.00491064 -0.0832607 0.0675971 0.00489723 -0.083354 0.0679971 0.0052862 -0.084125 0.0679971 0.00491257 -0.0838775 0.0675971 0.00459832 -0.0843126 0.0675971 0.00406877 -0.0848859 0.0679971 0.00342183 0.0730791 0.0675971 -0.0425106 0.0732888 0.0675971 -0.0418581 0.073687 0.0679971 -0.0418961 0.0735839 0.0679971 -0.0410456 0.0732063 0.0675971 -0.0411777 0.0728467 0.0675971 -0.0405942 0.0722759 0.0675971 -0.0402148 -0.0770543 0.0675971 0.00381275 0.0724208 0.0679971 -0.039842 -0.0765526 0.0679971 0.00410142 -0.0751623 0.0675971 0.00295902 -0.0733517 0.0675971 -0.000657448 -0.0729517 0.0679971 -0.000653842 0.0667612 0.0679971 -0.0376619 0.0627938 0.0679971 -0.0381724 0.0629993 0.0675971 -0.0385156 0.0224539 0.0679971 -0.0694031 0.022577 0.0675971 -0.0697837 0.0535427 0.0679971 -0.049538 -0.0143792 0.0679971 -0.071516 -0.014458 0.0675971 -0.0719082 0.0210952 0.0675971 -0.0702459 -0.037461 0.0679971 -0.062596 -0.0376664 0.0675971 -0.0629392 -0.0263011 0.0679971 -0.0680418 -0.0264453 0.0675971 -0.0684149 -0.056233 0.0679971 -0.0464729 -0.0475356 0.0679971 -0.0553362 -0.0477963 0.0675971 -0.0556396 -0.0717833 0.0679971 -0.0130166 -0.0702314 0.0675971 -0.0211725 -0.0689108 0.0675971 -0.0251391 -0.0685351 0.0679971 -0.025002 -0.0633011 0.0679971 -0.0362629 0.0822037 0.0679971 0.0214114 0.0818199 0.0679971 0.0228346 0.0758121 0.0675971 0.0374272 0.0724286 0.0679971 0.0443876 0.0723056 0.0675971 0.0438208 0.0705113 0.0675971 0.0466535 0.0299103 0.0675971 0.0790847 0.0563957 0.0679971 0.0635294 0.0464473 0.0679971 0.0711284 0.0420446 0.0679971 0.0738168 0.0300519 0.0679971 0.0794588 0.017246 0.0675971 0.0827752 0.011518 0.0679971 0.0841686 0.0041814 0.0679971 0.0848505 -0.0256308 0.0679971 0.0809964 -0.0344211 0.0675971 0.077232 -0.0438486 0.0675971 0.0722977 -0.0460144 0.0675971 0.070939 -0.056755 0.0679971 0.0632169 -0.0564878 0.0675971 0.0629193 -0.0578433 0.0679971 0.0622227 -0.0734342 0.0679971 0.0427192 -0.070388 0.0675971 0.0468534 -0.0730884 0.0675971 0.0425181 0.0824881 0.0679971 -0.00529546 0.0833447 0.0679971 -0.0052787 0.0844769 0.0675971 -0.00339824 -0.0736964 0.0679971 0.0419036 -0.0731436 0.0679971 0.0403238 -0.0732156 0.0675971 0.0411852 -0.0670386 0.0675971 0.0381824 0.0766552 0.0675971 -0.00370989 -0.0666586 0.0675971 0.0380534 -0.0626795 0.0679971 0.0382564 -0.0628948 0.0675971 0.0385935 -0.0611788 0.0679971 0.0397458 -0.0359561 0.0679971 0.0634797 -0.0543732 0.0675971 0.0492408 -0.0540767 0.0679971 0.0489723 -0.0211751 0.0675971 0.0702322 0.00900211 0.0679971 0.0723956 0.0090515 0.0675971 0.0727925 -0.00264447 0.0675971 0.0733062 -0.00263008 0.0679971 0.0729065 -0.0141954 0.0679971 0.0715602 0.0671743 0.0679971 -0.0378021 0.076967 0.0679971 -0.00419757 0.0765433 0.0679971 -0.00409392 0.0746844 0.0679971 -0.00308659 0.073408 0.0679971 -0.00140104 0.0734712 0.0705971 -0.00153203 -0.0757074 0.0709171 0.00376921 -0.0749198 0.0679971 0.0032771 -0.0749362 0.0705971 0.0032896 -0.0734805 0.0679971 0.00153952 -0.0734173 0.0705971 0.00140854 -0.0628031 0.0705971 0.0381799 -0.0649505 0.0705971 0.0374875 -0.0671836 0.0710971 0.0378096 -0.0660957 0.0709705 0.0375224 -0.0646615 0.0679971 0.0375204 -0.0649711 0.0705971 0.0374858 0.0846595 0.0679971 -0.00424312 0.0848765 0.0717971 -0.00341434 0.0841156 0.0679971 -0.00490507 0.0846595 0.0717971 -0.00424312 0.0731343 0.0679971 -0.0403163 0.0724208 0.0717971 -0.039842 0.0731343 0.0717971 -0.0403163 -0.0848859 0.0717971 0.00342183 -0.0846689 0.0679971 0.00425062 -0.083354 0.0717971 0.0052862 -0.0824974 0.0679971 0.00530295 -0.0734342 0.0717971 0.0427192 -0.0735932 0.0679971 0.0410531 -0.0731553 0.0720121 0.040336 -0.0696309 0.079889 0.00274441 -0.0708135 0.0812971 0.00297957 -0.070301 0.0788867 0.00287765 -0.0710137 0.0810957 0.00301938 -0.0711975 0.0732734 0.00305592 -0.0717174 0.0724951 0.00315931 -0.0686361 0.0805537 0.00254659 -0.0724894 0.0719785 0.00331282 -0.0724302 0.0679971 0.0398495 -0.0592557 0.0805548 0.0347271 -0.0613272 0.0812971 0.0355325 -0.0617374 0.0741971 0.035692 -0.0608392 0.0788892 0.0353428 -0.0630153 0.0721766 0.0361889 -0.065749 0.0812971 0.00197249 -0.0632975 0.0807869 0.0019957 -0.0589443 0.0819665 0.00579514 -0.0594097 0.0807869 0.00481092 -0.0610598 0.0807869 0.0029976 -0.0603424 0.0812971 0.00360848 -0.0610598 0.0812971 0.0029976 -0.053276 0.0807869 0.0254805 -0.0526925 0.0807869 0.0278617 -0.0529703 0.0821444 0.0262531 -0.0527988 0.0813014 0.0292126 -0.0531101 0.0807869 0.0302776 -0.0544592 0.0807869 0.0323247 0.0601926 0.0798906 -0.0350875 0.0613179 0.0812971 -0.035525 0.0581353 0.0807869 -0.0342876 0.0610558 0.0776971 -0.0354231 0.0671743 0.0710971 -0.0378021 0.0624011 0.0727263 -0.0359462 0.0696216 0.079889 -0.00273691 0.0702916 0.0788867 -0.00287015 0.0710043 0.0810957 -0.00301188 0.0674551 0.0807869 -0.0023061 0.0729716 0.072039 -0.00340307 0.0705284 0.0710971 -0.00291724 0.0741842 0.0717971 -0.0036442 0.076967 0.0710971 -0.00419757 0.0532667 0.0807869 -0.025473 0.0565052 0.0807869 -0.0336538 0.0541288 0.0812971 -0.031972 0.0632881 0.0807869 -0.0019882 0.0628318 0.0812971 -0.00210692 0.0610505 0.0807869 -0.0029901 0.0610505 0.0812971 -0.0029901 0.058935 0.0819665 -0.00578764 0.0596581 0.0814431 -0.00440325 0.0594004 0.0807869 -0.00480342 -0.0473733 0.0695971 -0.0679806 -0.0462617 0.0695971 -0.0675241 -0.0472231 0.0693971 -0.0677457 -0.046377 0.0693971 -0.0673607 -0.0454583 0.0695971 -0.0666306 -0.0453891 0.0693971 -0.064723 -0.0453198 0.0695971 -0.0642917 -0.0461458 0.0693971 -0.0634583 -0.0460121 0.0695971 -0.0633096 -0.0485168 0.0677971 -0.0677175 -0.0474062 0.0693971 -0.0677833 -0.0472231 0.0677971 -0.0677457 -0.046377 0.0677971 -0.0673607 -0.0460885 0.0693971 -0.0671232 -0.0456331 0.0693971 -0.0665333 -0.0454172 0.0677971 -0.0660168 -0.0454172 0.0693971 -0.0660168 -0.0453218 0.0693971 -0.0654652 -0.0453891 0.0677971 -0.064723 -0.0455048 0.0693971 -0.0643677 -0.0460116 0.0693971 -0.0635885 -0.047118 0.0677971 -0.0629172 -0.0460121 0.0675971 -0.0633096 -0.0461458 0.0677971 -0.0634583 -0.0460116 0.0677971 -0.0635885 -0.0455048 0.0677971 -0.0643677 -0.0453198 0.0675971 -0.0642917 -0.0453218 0.0677971 -0.0654652 -0.0451221 0.0675971 -0.065477 -0.0454583 0.0675971 -0.0666306 -0.0456331 0.0677971 -0.0665333 -0.0460885 0.0677971 -0.0671232 -0.0462617 0.0675971 -0.0675241 -0.0473733 0.0675971 -0.0679806 -0.0474062 0.0677971 -0.0677833 -0.0485728 0.0675971 -0.0679095 -0.0666446 0.0693971 -0.0425217 -0.0656724 0.0693971 -0.0430629 -0.0646487 0.0695971 -0.0450816 -0.0651597 0.0693971 -0.0461379 -0.0649849 0.0695971 -0.0462352 -0.0657883 0.0695971 -0.0471287 -0.0680994 0.0695971 -0.0475141 -0.0650314 0.0693971 -0.0439723 -0.0648484 0.0693971 -0.0450697 -0.0651597 0.0677971 -0.0461379 -0.0659036 0.0677971 -0.0469652 -0.0659036 0.0693971 -0.0469652 -0.0669328 0.0677971 -0.0473879 -0.0669328 0.0693971 -0.0473879 -0.0680434 0.0677971 -0.0473221 -0.0648484 0.0677971 -0.0450697 -0.0650314 0.0677971 -0.0439723 -0.0656724 0.0677971 -0.0430629 -0.0733728 0.0693971 -0.0302594 -0.0714497 0.0695971 -0.0320177 -0.0714801 0.0695971 -0.033415 -0.0716721 0.0693971 -0.033359 -0.0722664 0.0693971 -0.0309307 -0.0716439 0.0693971 -0.0320652 -0.0723434 0.0677971 -0.0344654 -0.0723434 0.0693971 -0.0344654 -0.0734779 0.0677971 -0.0350879 -0.0734779 0.0693971 -0.0350879 -0.0747717 0.0677971 -0.0350598 -0.0734304 0.0675971 -0.0352822 -0.0716721 0.0677971 -0.033359 -0.0716439 0.0677971 -0.0320652 -0.072122 0.0675971 -0.0307924 -0.0722664 0.0677971 -0.0309307 -0.080341 0.0695971 -0.00789657 -0.0803739 0.0693971 -0.00769929 -0.0793446 0.0693971 -0.00727666 -0.0790562 0.0693971 -0.00703916 -0.078426 0.0695971 -0.00654661 -0.0783849 0.0693971 -0.00593278 -0.0780898 0.0695971 -0.00539298 -0.0783568 0.0693971 -0.00463899 -0.0782875 0.0695971 -0.00420774 -0.0784725 0.0693971 -0.00428371 -0.0800856 0.0693971 -0.00283318 -0.0800297 0.0695971 -0.00264117 -0.0789798 0.0695971 -0.00322563 -0.0791135 0.0693971 -0.00337435 -0.0800856 0.0677971 -0.00283318 -0.0789793 0.0693971 -0.00350446 -0.0789793 0.0677971 -0.00350446 -0.0783849 0.0677971 -0.00593278 -0.0782895 0.0693971 -0.00538116 -0.0786007 0.0693971 -0.00644933 -0.0790562 0.0677971 -0.00703916 -0.0801907 0.0677971 -0.00766167 -0.0801907 0.0693971 -0.00766167 -0.0815405 0.0675971 -0.00782552 -0.0801432 0.0675971 -0.00785593 -0.0783568 0.0677971 -0.00463899 -0.0781929 0.0675971 -0.00598874 -0.0781625 0.0675971 -0.00459144 -0.0788348 0.0675971 -0.00336615 -0.0453068 0.0695971 -0.0715039 -0.045261 0.0694472 -0.0717102 -0.0452153 0.0692971 -0.0719163 -0.0736196 0.0694472 -0.0420899 -0.0708542 0.0692971 -0.0468667 -0.067111 0.0695971 -0.0515944 -0.0671667 0.0692971 -0.0520132 -0.0799582 0.0692971 -0.0287006 -0.0797666 0.0694472 -0.0287896 -0.0749913 0.0695971 -0.0392726 -0.0841772 0.0692971 -0.0114632 -0.0848038 0.0694472 0.000357068 -0.0846544 0.0695971 0.000207631 -0.0840484 0.0694472 -0.0112959 -0.0841772 0.0717971 -0.0114632 -0.0838443 0.0721844 -0.0110307 -0.0837735 0.0720971 -0.0109386 -0.0833765 0.0725971 -0.0114139 -0.0803969 0.0725971 -0.0112208 -0.0777327 0.0720971 -0.00980859 -0.0754057 0.0725971 -0.00789089 -0.0761694 0.0720971 -0.00822424 -0.0747977 0.0725971 -0.00484517 -0.0757939 0.0725971 -0.00190346 -0.0792463 0.0720971 4.70168e-05 -0.078349 0.0720971 -0.000302272 -0.0841528 0.0725971 0.000560916 -0.0811409 0.0720971 0.000255132 -0.0844851 0.0720971 3.83223e-05 -0.0849532 0.0692971 0.000506419 -0.0849532 0.0717971 0.000506419 -0.0845673 0.0721844 0.000120484 -0.0847603 0.0719909 0.000313524 -0.0731644 0.0725771 -0.0416163 -0.073801 0.0718137 -0.0420412 -0.0703964 0.0720971 -0.0403467 -0.0731577 0.0725971 -0.0415878 -0.0642916 0.0720971 -0.0494972 -0.0621783 0.0725971 -0.047974 -0.0626088 0.0720971 -0.0477197 -0.0622043 0.0720971 -0.0429641 -0.0635627 0.0720971 -0.040928 -0.0632189 0.0725971 -0.0405649 -0.068109 0.0720971 -0.0394754 -0.0681785 0.0725971 -0.0389802 -0.0658052 0.0720971 -0.0396416 -0.0665269 0.0725771 -0.0515655 -0.0666307 0.0720971 -0.0510577 -0.0671388 0.0694472 -0.0518039 -0.0671636 0.0718137 -0.05199 -0.0670794 0.0695971 -0.051357 -0.0670794 0.071559 -0.051357 -0.0447682 0.0725771 -0.0712761 -0.0452204 0.0718137 -0.0718935 -0.0429758 0.0725971 -0.0688612 -0.0424093 0.0720971 -0.0663185 -0.0425105 0.0720971 -0.0638729 -0.0504065 0.0720971 -0.0604649 -0.0480447 0.0720971 -0.059822 -0.0480654 0.0725971 -0.0593225 -0.0462786 0.0720971 -0.060037 -0.0454397 0.0725971 -0.0598086 -0.0456379 0.0720971 -0.0602676 -0.0539163 0.0720971 -0.0643377 -0.0542349 0.071559 -0.064773 -0.0544734 0.0695971 -0.0647942 -0.054871 0.0718137 -0.0648296 -0.0548943 0.0717971 -0.0648317 -0.0546839 0.0694472 -0.064813 -0.0799369 0.0718137 -0.0287104 -0.0792368 0.0725771 -0.0284014 -0.0762915 0.0720971 -0.0276272 -0.0788643 0.0720971 -0.0287618 -0.0792252 0.0725971 -0.0283745 -0.0799582 0.0717971 -0.0287006 -0.079575 0.0695971 -0.0288786 -0.0698893 0.0720971 -0.0362307 -0.0686595 0.0720971 -0.0336355 -0.0696599 0.0720971 -0.0293762 -0.0702352 0.0720971 -0.0287191 -0.0764933 0.0725971 -0.0271697 -0.0738715 0.0725971 -0.026663 -0.0744258 0.0720971 -0.0388266 -0.071853 0.0720971 -0.037692 -0.0751112 0.0718137 -0.0396532 -0.0750548 0.0694472 -0.0394741 -0.0804293 0.0695971 -0.0107218 -0.0811409 0.0695971 0.000255132 -0.0833773 0.0695971 -0.00447796 -0.0844851 0.0695971 3.83223e-05 -0.0834077 0.0695971 -0.00587525 -0.0839195 0.0695971 -0.0111284 -0.0837735 0.0695971 -0.0109386 -0.0815405 0.0695971 -0.00782552 -0.0780033 0.0695971 -0.00997798 -0.0792294 0.0695971 -0.00744013 -0.075318 0.0695971 -0.0058339 -0.0770397 0.0695971 -0.00120571 -0.0792463 0.0695971 4.70168e-05 -0.081427 0.0695971 -0.00261076 -0.0826523 0.0695971 -0.00328307 -0.0642916 0.0695971 -0.0494972 -0.0703964 0.0695971 -0.0403467 -0.0731842 0.071559 -0.0422065 -0.0727355 0.0720971 -0.0419072 -0.0734154 0.0695971 -0.0421446 -0.0692943 0.0695971 -0.0467891 -0.0731842 0.0695971 -0.0422065 -0.0668999 0.0695971 -0.0475851 -0.0618593 0.0695971 -0.0453317 -0.0648464 0.0695971 -0.0438963 -0.0655387 0.0695971 -0.0429142 -0.0665886 0.0695971 -0.0423297 -0.0681789 0.0695971 -0.0394857 -0.0692112 0.0695971 -0.0429716 -0.0749193 0.071559 -0.0390442 -0.0762915 0.0695971 -0.0276272 -0.0793578 0.071559 -0.0289794 -0.0725335 0.0720971 -0.0273792 -0.0744344 0.0695971 -0.0271715 -0.0738883 0.0720971 -0.0271627 -0.071853 0.0695971 -0.037692 -0.0748276 0.0695971 -0.0352518 -0.0734304 0.0695971 -0.0352822 -0.0722051 0.0695971 -0.0346099 -0.0697507 0.0695971 -0.0360617 -0.072122 0.0695971 -0.0307924 -0.0725335 0.0695971 -0.0273792 -0.0733169 0.0695971 -0.0300674 -0.0747142 0.0695971 -0.030037 -0.0793578 0.0695971 -0.0289794 -0.0749193 0.0695971 -0.0390442 -0.0766948 0.0695971 -0.0333015 -0.0760225 0.0695971 -0.0345268 -0.0453587 0.071559 -0.0712701 -0.0450401 0.0720971 -0.0708348 -0.0433793 0.0720971 -0.0685659 -0.0522555 0.0695971 -0.0620688 -0.0522555 0.0720971 -0.0620688 -0.0462786 0.0695971 -0.060037 -0.0484973 0.0695971 -0.0598595 -0.0496846 0.0695971 -0.0633671 -0.0504096 0.0695971 -0.0645619 -0.0542349 0.0695971 -0.064773 -0.0506047 0.0695971 -0.0605759 -0.0484593 0.0695971 -0.0626948 -0.047062 0.0695971 -0.0627252 -0.0440151 0.0695971 -0.0613434 -0.0426101 0.0695971 -0.0635471 -0.0451221 0.0695971 -0.065477 -0.0453587 0.0695971 -0.0712701 -0.0485728 0.0695971 -0.0679095 0.00587433 0.0695971 -0.0833993 0.00709962 0.0695971 -0.0827269 0.00582678 0.0693971 -0.083205 0.00667286 0.0693971 -0.08282 0.0071827 0.0695971 -0.0789095 0.00593186 0.0693971 -0.0783765 0.00598782 0.0695971 -0.0781845 0.00703824 0.0693971 -0.0790478 0.00690399 0.0677971 -0.0789177 0.00690399 0.0693971 -0.0789177 0.00703824 0.0677971 -0.0790478 0.00754504 0.0693971 -0.079827 0.00766075 0.0693971 -0.0801823 0.00763259 0.0677971 -0.0814761 0.00772805 0.0693971 -0.0809245 0.00763259 0.0693971 -0.0814761 0.00741678 0.0677971 -0.0819926 0.00741678 0.0693971 -0.0819926 0.00696131 0.0677971 -0.0825825 0.00696131 0.0693971 -0.0825825 0.00582678 0.0677971 -0.083205 0.00564365 0.0677971 -0.0832426 0.00564365 0.0693971 -0.0832426 0.00453299 0.0677971 -0.0831768 0.00593186 0.0677971 -0.0783765 0.00754504 0.0677971 -0.079827 0.00785501 0.0675971 -0.0801348 0.00766075 0.0677971 -0.0801823 0.00772805 0.0677971 -0.0809245 0.00782461 0.0675971 -0.0815321 0.00709962 0.0675971 -0.0827269 0.00667286 0.0677971 -0.08282 0.0333006 0.0695971 -0.0766864 0.0345259 0.0695971 -0.0760141 0.0343876 0.0693971 -0.0758696 0.0352509 0.0695971 -0.0748192 0.0352813 0.0695971 -0.0734219 0.0334141 0.0695971 -0.0714717 0.0344645 0.0693971 -0.072335 0.0343302 0.0677971 -0.0722048 0.0343302 0.0693971 -0.0722048 0.0349713 0.0677971 -0.0731142 0.0349713 0.0693971 -0.0731142 0.035087 0.0677971 -0.0734695 0.0351543 0.0677971 -0.0742116 0.035087 0.0693971 -0.0734695 0.0351543 0.0693971 -0.0742116 0.034843 0.0677971 -0.0752798 0.0350588 0.0693971 -0.0747633 0.034843 0.0693971 -0.0752798 0.0343876 0.0677971 -0.0758696 0.0340991 0.0693971 -0.0761072 0.033253 0.0693971 -0.0764922 0.0330699 0.0677971 -0.0765298 0.0330699 0.0693971 -0.0765298 0.0319593 0.0677971 -0.076464 0.0334141 0.0675971 -0.0714717 0.0344645 0.0677971 -0.072335 0.0350588 0.0677971 -0.0747633 0.0352509 0.0675971 -0.0748192 0.0340991 0.0677971 -0.0761072 0.033253 0.0677971 -0.0764922 0.0333006 0.0675971 -0.0766864 0.0455154 0.0693971 -0.0697639 0.0466499 0.0693971 -0.0691414 0.0475132 0.0695971 -0.068091 0.0473212 0.0693971 -0.068035 0.0472336 0.0693971 -0.066386 0.0475436 0.0695971 -0.0666937 0.0474166 0.0693971 -0.0674834 0.0456204 0.0677971 -0.0649354 0.0467268 0.0693971 -0.0656067 0.0472336 0.0677971 -0.066386 0.0473493 0.0693971 -0.0667412 0.0474166 0.0677971 -0.0674834 0.0471053 0.0693971 -0.0685516 0.0471053 0.0677971 -0.0685516 0.0463614 0.0693971 -0.0693789 0.0463614 0.0677971 -0.0693789 0.0453322 0.0677971 -0.0698015 0.0453651 0.0675971 -0.0699988 0.0464767 0.0675971 -0.0695424 0.0472801 0.0675971 -0.0686489 0.0474186 0.0675971 -0.06631 0.0465926 0.0677971 -0.0654766 0.0456764 0.0675971 -0.0647434 0.0677166 0.0693971 -0.0485084 0.0679086 0.0695971 -0.0485644 0.0670453 0.0693971 -0.0496148 0.0659583 0.0695971 -0.0504316 0.0660159 0.0693971 -0.0454088 0.0671222 0.0677971 -0.0460801 0.0671222 0.0693971 -0.0460801 0.0677447 0.0693971 -0.0472146 0.0670453 0.0677971 -0.0496148 0.0659108 0.0677971 -0.0502373 0.0659108 0.0693971 -0.0502373 0.064561 0.0675971 -0.0504012 0.0679086 0.0675971 -0.0485644 0.0677166 0.0677971 -0.0485084 0.0677447 0.0677971 -0.0472146 0.0672667 0.0675971 -0.0459418 0.0660718 0.0675971 -0.0452168 0.0114623 0.0692971 -0.0841688 0.0112949 0.0694472 -0.08404 0.0396747 0.0692971 -0.0751099 0.0345746 0.0692971 -0.0775899 0.0394732 0.0694472 -0.0750464 0.0420889 0.0694472 -0.0736112 0.0518029 0.0694472 -0.0671304 0.0658872 0.0692971 -0.0536131 0.0647933 0.0695971 -0.054465 0.0648308 0.0717971 -0.0548859 0.064812 0.0694472 -0.0546755 0.0620679 0.0720971 -0.0522471 0.0641819 0.0725971 -0.0544141 0.0643368 0.0720971 -0.0539079 0.0688603 0.0725971 -0.0429674 0.068565 0.0720971 -0.0433709 0.0668552 0.0720971 -0.0425286 0.064321 0.0720971 -0.0423998 0.0604748 0.0725971 -0.0442651 0.060284 0.0720971 -0.0500282 0.0617725 0.0725971 -0.0526506 0.0598265 0.0725971 -0.05023 0.0598166 0.0720971 -0.0478521 0.0593515 0.0725971 -0.0471607 0.0708339 0.0720971 -0.0450317 0.0712696 0.0725971 -0.044731 0.0718926 0.0718137 -0.045212 0.0717092 0.0694472 -0.0452526 0.0719154 0.0717971 -0.0452069 0.0715029 0.0695971 -0.0452984 0.0712692 0.071559 -0.0453503 0.0392717 0.0695971 -0.0749829 0.0396523 0.0718137 -0.0751028 0.0390433 0.0695971 -0.0749109 0.0390433 0.071559 -0.0749109 0.0393533 0.0725971 -0.0743748 0.0365545 0.0725971 -0.0695006 0.0271618 0.0720971 -0.0738798 0.026662 0.0725971 -0.0738631 0.0290768 0.0725971 -0.0692503 0.03152 0.0725971 -0.0681729 0.0341888 0.0725971 -0.0682622 0.0341974 0.0720971 -0.0687835 0.0276263 0.0720971 -0.0762831 0.0283736 0.0725971 -0.0792168 0.0289785 0.071559 -0.0793494 0.0287609 0.0720971 -0.0788558 0.0289785 0.0695971 -0.0793494 0.0288777 0.0695971 -0.0795666 0.0287886 0.0694472 -0.0797582 -0.000208548 0.0695971 -0.084646 -0.000507336 0.0717971 -0.0849448 -0.000357986 0.0694472 -0.0847954 -0.000540506 0.0725771 -0.0841645 -0.00025605 0.0720971 -0.0811325 -7.41379e-05 0.0720971 -0.0839384 0.00873787 0.0720971 -0.0765385 0.00766851 0.0720971 -0.0758456 0.00677119 0.0720971 -0.0754963 0.00484426 0.0725971 -0.0747892 0.0048766 0.0720971 -0.0752882 0.000301355 0.0720971 -0.0783406 0.00179125 0.0720971 -0.0764862 -0.000146925 0.0725971 -0.0781191 0.00416016 0.0720971 -0.0753822 0.0109028 0.0720971 -0.0832268 0.0113945 0.0725771 -0.0833908 0.0114623 0.0717971 -0.0841688 0.0111275 0.0695971 -0.0839111 0.0109377 0.071559 -0.0837651 0.0515645 0.0725771 -0.0665184 0.0510568 0.0720971 -0.0666222 0.0494962 0.0720971 -0.0642832 0.0519891 0.0718137 -0.0671552 0.0513561 0.0695971 -0.067071 0.0477188 0.0720971 -0.0626004 0.0454295 0.0725971 -0.0613572 0.0438015 0.0720971 -0.0619507 0.0427852 0.0725971 -0.0617286 0.0429632 0.0720971 -0.0621958 0.040564 0.0725971 -0.0632105 0.0392056 0.0725971 -0.0655095 0.0399298 0.0725971 -0.0706655 0.0416154 0.0725771 -0.073156 0.0421436 0.0695971 -0.073407 0.0420343 0.0717971 -0.0738152 0.0420343 0.0692971 -0.0738152 0.0388256 0.0720971 -0.0744173 0.0376911 0.0695971 -0.0718446 0.0376911 0.0720971 -0.0718446 0.0317261 0.0695971 -0.0686435 0.0340612 0.0720971 -0.0687457 0.0316149 0.0720971 -0.0686638 0.0294437 0.0695971 -0.0696013 0.0293753 0.0720971 -0.0696515 0.0278124 0.0695971 -0.0714631 0.027786 0.0720971 -0.071513 0.0271628 0.0695971 -0.0738516 0.034609 0.0695971 -0.0721966 0.0341974 0.0695971 -0.0687835 0.0322146 0.0695971 -0.0714006 0.0302996 0.0695971 -0.0727506 0.0299634 0.0695971 -0.0739042 0.0301611 0.0695971 -0.0750894 0.0276263 0.0695971 -0.0762831 0.0308534 0.0695971 -0.0760716 0.0513561 0.071559 -0.067071 0.0494962 0.0695971 -0.0642832 0.0422056 0.071559 -0.0731758 0.0403457 0.0695971 -0.070388 0.0419063 0.0720971 -0.072727 0.0403457 0.0720971 -0.070388 0.0464598 0.0720971 -0.0620552 0.0453872 0.0720971 -0.0618554 0.0438015 0.0695971 -0.0619507 0.0414051 0.0720971 -0.0631061 0.040927 0.0720971 -0.0635543 0.0398314 0.0720971 -0.065251 0.0396819 0.0720971 -0.0656617 0.0394745 0.0720971 -0.0681006 0.0515935 0.0695971 -0.0671026 0.0467882 0.0695971 -0.0692859 0.0394484 0.0695971 -0.0678836 0.0433653 0.0695971 -0.0651288 0.0398314 0.0695971 -0.065251 0.0414051 0.0695971 -0.0631061 0.0468713 0.0695971 -0.0654684 0.0464598 0.0695971 -0.0620552 0.0431157 0.0695971 -0.0693433 0.0422056 0.0695971 -0.0731758 0.0455629 0.0695971 -0.0699582 0.0107209 0.0720971 -0.0804208 -3.92395e-05 0.071559 -0.0844767 -0.00025605 0.0695971 -0.0811325 0.00416016 0.0695971 -0.0753822 0.00218004 0.0720971 -0.0762014 0.00179125 0.0695971 -0.0764862 0.000199362 0.0695971 -0.078559 -3.92395e-05 0.0695971 -0.0844767 0.0109377 0.0695971 -0.0837651 0.00782461 0.0695971 -0.0815321 0.0107209 0.0695971 -0.0804208 0.00785501 0.0695971 -0.0801348 0.00260984 0.0695971 -0.0814186 0.00264025 0.0695971 -0.0800213 0.00459053 0.0695971 -0.0781541 0.068565 0.0695971 -0.0433709 0.0647721 0.071559 -0.0542265 0.0635111 0.0695971 -0.0498167 0.0620679 0.0695971 -0.0522471 0.0628188 0.0695971 -0.0488346 0.0604213 0.0695971 -0.0503165 0.0626211 0.0695971 -0.0476494 0.0603825 0.0695971 -0.0453786 0.0629573 0.0695971 -0.0464957 0.0637607 0.0695971 -0.0456022 0.064321 0.0695971 -0.0423998 0.0660718 0.0695971 -0.0452168 0.0672667 0.0695971 -0.0459418 0.067939 0.0695971 -0.0471671 0.0712692 0.0695971 -0.0453503 0.0647721 0.0695971 -0.0542265 0.0671836 0.0695971 -0.0497593 0.0659107 0.0720971 -0.0423412 0.0630972 0.0720971 -0.0427766 0.0619987 0.0720971 -0.0434223 0.0619987 0.0695971 -0.0434223 0.0608783 0.0720971 -0.0445604 0.0603825 0.0720971 -0.0453786 0.0598486 0.0720971 -0.0472147 0.0598166 0.0695971 -0.0478521 -0.00479764 0.0695971 0.0781209 -0.0059412 0.0693971 0.078384 -0.00368609 0.0695971 0.0785774 -0.00380133 0.0693971 0.0787408 -0.00351288 0.0693971 0.0789784 -0.00288267 0.0695971 0.0794709 -0.0028416 0.0693971 0.0800847 -0.00274614 0.0693971 0.0806364 -0.00343648 0.0695971 0.0827919 -0.00448637 0.0695971 0.0833763 -0.00343595 0.0693971 0.082513 -0.00292915 0.0693971 0.0817338 -0.0035702 0.0693971 0.0826432 -0.00281344 0.0693971 0.0813785 -0.00305741 0.0693971 0.0795682 -0.00351288 0.0677971 0.0789784 -0.0059412 0.0677971 0.078384 -0.00483054 0.0693971 0.0783182 -0.00464741 0.0677971 0.0783558 -0.00464741 0.0693971 0.0783558 -0.00459986 0.0675971 0.0781616 -0.00337456 0.0675971 0.0788339 -0.0028416 0.0677971 0.0800847 -0.00264958 0.0675971 0.0800288 -0.00281344 0.0677971 0.0813785 -0.00343595 0.0677971 0.082513 -0.00329149 0.0675971 0.0826514 -0.00448637 0.0675971 0.0833763 -0.0319126 0.0695971 0.0766635 -0.0308627 0.0695971 0.0760791 -0.0299727 0.0695971 0.0739117 -0.0303089 0.0695971 0.0727581 -0.0311124 0.0695971 0.0718646 -0.0312276 0.0693971 0.072028 -0.0322568 0.0693971 0.0716054 -0.0333675 0.0693971 0.0716712 -0.0322239 0.0695971 0.0714081 -0.0334234 0.0695971 0.0714792 -0.0319686 0.0693971 0.0764715 -0.0309965 0.0693971 0.0759303 -0.0303554 0.0693971 0.075021 -0.0301724 0.0693971 0.0739235 -0.0304837 0.0693971 0.0728554 -0.0312276 0.0677971 0.072028 -0.0322568 0.0677971 0.0716054 -0.0322239 0.0675971 0.0714081 -0.0304837 0.0677971 0.0728554 -0.0303089 0.0675971 0.0727581 -0.0301724 0.0677971 0.0739235 -0.0299727 0.0675971 0.0739117 -0.0303554 0.0677971 0.075021 -0.0301704 0.0675971 0.0750969 -0.0309965 0.0677971 0.0759303 -0.0308627 0.0675971 0.0760791 -0.0442884 0.0695971 0.0647205 -0.0434899 0.0693971 0.0652998 -0.0432014 0.0693971 0.0655373 -0.0423382 0.0695971 0.0665877 -0.042746 0.0693971 0.0661271 -0.0425302 0.0693971 0.0666437 -0.0424347 0.0693971 0.0671953 -0.0423077 0.0695971 0.067985 -0.0441749 0.0695971 0.0699353 -0.0431245 0.0693971 0.069072 -0.0426177 0.0693971 0.0682927 -0.042502 0.0693971 0.0679374 -0.0426177 0.0677971 0.0682927 -0.0424347 0.0677971 0.0671953 -0.0434899 0.0677971 0.0652998 -0.044336 0.0693971 0.0649148 -0.0456298 0.0693971 0.0649429 -0.0445191 0.0677971 0.0648771 -0.0433747 0.0675971 0.0651363 -0.042746 0.0677971 0.0661271 -0.0425712 0.0675971 0.0660298 -0.0422351 0.0675971 0.0671835 -0.0432588 0.0677971 0.0692021 -0.0424327 0.0675971 0.0683687 -0.0646263 0.0693971 0.0502167 -0.0635205 0.0695971 0.0498242 -0.0626305 0.0695971 0.0476568 -0.0631414 0.0693971 0.0466005 -0.0638853 0.0693971 0.0457732 -0.0660252 0.0693971 0.0454163 -0.0636542 0.0677971 0.0496755 -0.0636542 0.0693971 0.0496755 -0.0630131 0.0693971 0.0487661 -0.0628301 0.0677971 0.0476687 -0.0628301 0.0693971 0.0476687 -0.0631414 0.0677971 0.0466005 -0.0649145 0.0677971 0.0453505 -0.0649145 0.0693971 0.0453505 -0.0660811 0.0675971 0.0452243 -0.0638853 0.0677971 0.0457732 -0.0637701 0.0675971 0.0456097 -0.0629667 0.0675971 0.0465032 -0.0630131 0.0677971 0.0487661 -0.0628281 0.0675971 0.0488421 -0.0646263 0.0677971 0.0502167 -0.0645704 0.0675971 0.0504087 -0.0113043 0.0694472 0.0840475 0.000498002 0.0692971 0.0849523 -0.028798 0.0694472 0.0797657 -0.0372555 0.0692971 0.0763508 -0.0520216 0.0692971 0.0671658 -0.0480713 0.0692971 0.0700473 -0.0516028 0.0695971 0.0671101 -0.0518123 0.0694472 0.0671379 -0.0717186 0.0694472 0.0452601 -0.0647814 0.0720971 0.054234 -0.0648159 0.0719909 0.0546216 -0.0647814 0.0695971 0.054234 -0.0648026 0.0695971 0.0544725 -0.0648214 0.0694472 0.054683 -0.0685743 0.0720971 0.0433784 -0.0712785 0.0720971 0.0453578 -0.0688696 0.0725971 0.0429749 -0.0719248 0.0692971 0.0452144 -0.0715123 0.0695971 0.0453059 -0.071392 0.0721844 0.0453326 -0.0394825 0.0694472 0.0750539 -0.039281 0.0695971 0.0749904 -0.0390526 0.0695971 0.0749184 -0.0396617 0.0718137 0.0751103 -0.0393531 0.0725771 0.07441 -0.038835 0.0720971 0.0744248 -0.0390526 0.071559 0.0749184 -0.0342068 0.0720971 0.068791 -0.0343467 0.0725971 0.0683109 -0.0362926 0.0720971 0.0699346 -0.0366221 0.0725971 0.0695586 -0.0283829 0.0725971 0.0792243 -0.0287702 0.0720971 0.0788633 -0.0287189 0.0718137 0.079936 -0.028887 0.0695971 0.0795741 -0.028709 0.0717971 0.0799573 -0.028709 0.0692971 0.0799573 2.99059e-05 0.0695971 0.0844842 0.000481445 0.0718137 0.0849357 0.000498002 0.0717971 0.0849523 0.000348652 0.0694472 0.0848029 0.000531172 0.0725771 0.084172 -0.0087472 0.0720971 0.076546 -0.00692041 0.0725971 0.0750238 -0.00906588 0.0725971 0.0761607 -0.0101398 0.0720971 0.0782823 -0.0114038 0.0725771 0.0833983 -0.0114717 0.0717971 0.0841763 -0.0114531 0.0718137 0.084162 -0.0513655 0.071559 0.0670785 -0.0495056 0.0720971 0.0642907 -0.0477281 0.0720971 0.0626079 -0.0403551 0.0720971 0.0703955 -0.0419156 0.0720971 0.0727345 -0.0416248 0.0725771 0.0731635 -0.042215 0.071559 0.0731833 -0.0420497 0.0718137 0.0738 -0.0420983 0.0694472 0.0736187 -0.0420436 0.0692971 0.0738227 -0.0685743 0.0695971 0.0433784 -0.0712785 0.0695971 0.0453578 -0.0620772 0.0695971 0.0522546 -0.0620772 0.0720971 0.0522546 -0.0638813 0.0695971 0.0425095 -0.0668645 0.0720971 0.0425361 -0.062008 0.0720971 0.0434298 -0.0598305 0.0695971 0.0480438 -0.0598259 0.0720971 0.0478596 -0.0645704 0.0695971 0.0504087 -0.0659677 0.0695971 0.0504391 -0.0628281 0.0695971 0.0488421 -0.0604733 0.0695971 0.0504056 -0.060276 0.0695971 0.045637 -0.0629667 0.0695971 0.0465032 -0.0637701 0.0695971 0.0456097 -0.0617218 0.0695971 0.0436618 -0.0648816 0.0695971 0.0451533 -0.066327 0.0695971 0.0424084 -0.0660811 0.0695971 0.0452243 -0.0679483 0.0695971 0.0471746 -0.0671929 0.0695971 0.0497668 -0.0377004 0.0695971 0.0718521 -0.0289879 0.071559 0.0793569 -0.0377004 0.0720971 0.0718521 -0.0362391 0.0695971 0.0698884 -0.0317355 0.0720971 0.068651 -0.0277953 0.0695971 0.0715205 -0.0278218 0.0720971 0.0714706 -0.0271711 0.0695971 0.0738873 -0.0271721 0.0720971 0.0738591 -0.0276356 0.0695971 0.0762906 -0.0301704 0.0695971 0.0750969 -0.0289879 0.0695971 0.0793569 -0.0352602 0.0695971 0.0748267 -0.0340706 0.0695971 0.0687532 -0.0316242 0.0695971 0.0686713 -0.0293846 0.0695971 0.069659 -0.0510661 0.0720971 0.0666297 -0.0495056 0.0695971 0.0642907 -0.042215 0.0695971 0.0731833 -0.048184 0.0720971 0.0629087 -0.0477281 0.0695971 0.0626079 -0.0464691 0.0720971 0.0620627 -0.0453965 0.0720971 0.0618629 -0.0429726 0.0720971 0.0622033 -0.0429726 0.0695971 0.0622033 -0.0414145 0.0720971 0.0631136 -0.0409364 0.0695971 0.0635618 -0.0409364 0.0720971 0.0635618 -0.0396913 0.0695971 0.0656692 -0.0398407 0.0720971 0.0652585 -0.0394838 0.0695971 0.0681081 -0.0403551 0.0695971 0.0703955 -0.0394577 0.0720971 0.0678911 -0.0513655 0.0695971 0.0670785 -0.0429801 0.0695971 0.0692103 -0.042153 0.0695971 0.0734145 -0.0455722 0.0695971 0.0699657 -0.0467975 0.0695971 0.0692934 -0.0456857 0.0695971 0.0647509 -0.0430631 0.0695971 0.0653928 -0.0453965 0.0695971 0.0618629 -0.010947 0.071559 0.0837726 -0.0109122 0.0720971 0.0832343 -0.0107302 0.0695971 0.0804283 2.99059e-05 0.071559 0.0844842 6.48043e-05 0.0720971 0.0839459 0.000246716 0.0720971 0.08114 -0.0107302 0.0720971 0.0804283 -0.00838558 0.0695971 0.0762712 -0.00611616 0.0720971 0.0753541 -0.00367356 0.0695971 0.0755125 -0.000142428 0.0695971 0.0787234 0.000246716 0.0695971 0.08114 -0.000208696 0.0720971 0.0785665 -0.00254649 0.0695971 0.0806245 -0.00274414 0.0695971 0.0818098 0.000199215 0.0695971 0.0846535 -0.0111368 0.0695971 0.0839186 -0.010947 0.0695971 0.0837726 -0.00710896 0.0695971 0.0827344 -0.00154156 0.0695971 0.076715 -0.00599715 0.0695971 0.078192 -0.00611616 0.0695971 0.0753541 -0.0100323 0.0695971 0.0780822 -0.00786435 0.0695971 0.0801423 0.0494796 0.0693971 0.0671838 0.0496134 0.0695971 0.0673326 0.0501207 0.0693971 0.0662745 0.0503057 0.0695971 0.0663504 0.0505033 0.0695971 0.0651652 0.0501672 0.0695971 0.0640116 0.0493637 0.0695971 0.0631181 0.0492485 0.0693971 0.0632815 0.0494796 0.0677971 0.0671838 0.0501207 0.0677971 0.0662745 0.0503037 0.0677971 0.065177 0.0503037 0.0693971 0.065177 0.0499924 0.0693971 0.0641088 0.0492485 0.0677971 0.0632815 0.0482193 0.0693971 0.0628589 0.0471086 0.0693971 0.0629247 0.0482193 0.0677971 0.0628589 0.0499924 0.0677971 0.0641088 0.0501672 0.0675971 0.0640116 0.0505033 0.0675971 0.0651652 0.0503057 0.0675971 0.0663504 0.0485075 0.0677971 0.067725 0.0665793 0.0695971 0.0423372 0.0677788 0.0695971 0.0422662 0.0696938 0.0695971 0.0436161 0.0690062 0.0693971 0.0467884 0.06914 0.0695971 0.0469371 0.0696473 0.0693971 0.0458791 0.0680341 0.0677971 0.0473296 0.0691405 0.0677971 0.0466583 0.0691405 0.0693971 0.0466583 0.069763 0.0693971 0.0455238 0.0697348 0.0677971 0.04423 0.0698303 0.0693971 0.0447816 0.0697348 0.0693971 0.04423 0.069519 0.0693971 0.0437134 0.0690636 0.0693971 0.0431236 0.0687751 0.0693971 0.0428861 0.0677459 0.0693971 0.0424635 0.067929 0.0693971 0.0425011 0.0666352 0.0677971 0.0425292 0.067929 0.0677971 0.0425011 0.0690636 0.0677971 0.0431236 0.0692019 0.0675971 0.0429791 0.069763 0.0677971 0.0455238 0.0699573 0.0675971 0.0455713 0.069285 0.0675971 0.0467966 0.0744741 0.0693971 0.0302012 0.0759301 0.0695971 0.0307168 0.0762473 0.0693971 0.0314511 0.0766551 0.0695971 0.0319117 0.0766855 0.0695971 0.033309 0.0764912 0.0693971 0.0332615 0.0748183 0.0695971 0.0352593 0.0757345 0.0693971 0.0345261 0.0747624 0.0677971 0.0350673 0.0758687 0.0693971 0.034396 0.0758687 0.0677971 0.034396 0.0763755 0.0677971 0.0336167 0.0763755 0.0693971 0.0336167 0.0764912 0.0677971 0.0332615 0.0765586 0.0677971 0.0325193 0.0764631 0.0677971 0.0319677 0.0765586 0.0693971 0.0325193 0.0764631 0.0693971 0.0319677 0.0762473 0.0677971 0.0314511 0.0757918 0.0677971 0.0308613 0.0757918 0.0693971 0.0308613 0.0755034 0.0693971 0.0306238 0.0746573 0.0677971 0.0302388 0.0746573 0.0693971 0.0302388 0.0744741 0.0677971 0.0302012 0.0757345 0.0677971 0.0345261 0.0760132 0.0675971 0.0345343 0.0766551 0.0675971 0.0319117 0.0759301 0.0675971 0.0307168 0.0747048 0.0675971 0.0300445 0.0755034 0.0677971 0.0306238 0.0800204 0.0695971 0.00264867 0.0825046 0.0693971 0.00343503 0.0831348 0.0695971 0.00392758 0.0831759 0.0693971 0.00454141 0.0832714 0.0693971 0.00509303 0.0832734 0.0695971 0.00626645 0.0814752 0.0693971 0.00764101 0.0830884 0.0693971 0.00619048 0.0814752 0.0677971 0.00764101 0.0825816 0.0677971 0.00696973 0.0824473 0.0693971 0.00709984 0.0825816 0.0693971 0.00696973 0.0832041 0.0677971 0.0058352 0.0832041 0.0693971 0.0058352 0.0829601 0.0693971 0.00402486 0.0822162 0.0693971 0.00319753 0.0825046 0.0677971 0.00343503 0.0800763 0.0693971 0.00284068 0.0800763 0.0677971 0.00284068 0.081187 0.0693971 0.0027749 0.0813701 0.0677971 0.00281252 0.0813701 0.0693971 0.00281252 0.0826429 0.0675971 0.00329057 0.0831759 0.0677971 0.00454141 0.0833679 0.0675971 0.00448545 0.0815311 0.0675971 0.00783302 0.0464473 0.0692971 0.0711284 0.0546746 0.0694472 0.0648205 0.0452975 0.0695971 0.0715114 0.0738142 0.0692971 0.0420427 0.0734061 0.0695971 0.0421521 0.0671295 0.0694472 0.0518114 0.0724286 0.0692971 0.0443876 0.0750455 0.0694472 0.0394816 0.0847945 0.0694472 -0.000349569 0.0844572 0.0692971 0.00909727 0.0839102 0.0695971 0.0111359 0.0841678 0.0717971 0.0114707 0.084039 0.0694472 0.0113034 0.0841536 0.0718137 0.0114522 0.0837641 0.0695971 0.0109461 0.0833898 0.0725771 0.0114029 0.0832258 0.0720971 0.0109112 0.0837641 0.071559 0.0109461 0.0833671 0.0725971 0.0114214 0.0804199 0.0720971 0.0107293 0.077741 0.0725971 0.0104168 0.0803876 0.0725971 0.0112283 0.0757405 0.0725971 0.00850364 0.0748116 0.0725971 0.00589599 0.0752873 0.0720971 0.00488502 0.0770303 0.0720971 0.00121321 0.0790971 0.0725971 -0.000519551 0.0849273 0.0718137 -0.000482362 0.0844758 0.071559 -3.08231e-05 0.0846451 0.0695971 -0.000200132 0.0849438 0.0692971 -0.000498919 0.0737916 0.0718137 0.0420487 0.0738142 0.0717971 0.0420427 0.0736102 0.0694472 0.0420974 0.0727261 0.0720971 0.0419147 0.0731551 0.0725771 0.0416238 0.0624036 0.0720971 0.0473655 0.06185 0.0720971 0.0453392 0.0618462 0.0720971 0.0445736 0.0622257 0.0720971 0.0428926 0.0617613 0.0725971 0.0427075 0.0648986 0.0720971 0.0399983 0.0665175 0.0725771 0.051573 0.0666213 0.0720971 0.0510652 0.0642823 0.0720971 0.0495047 0.0670701 0.071559 0.0513645 0.0671543 0.0718137 0.0519975 0.045206 0.0692971 0.0719239 0.0452517 0.0694472 0.0717177 0.045206 0.0717971 0.0719239 0.045211 0.0718137 0.071901 0.0453493 0.071559 0.0712776 0.04473 0.0725971 0.0712781 0.0429665 0.0725971 0.0688687 0.0418773 0.0725971 0.0662338 0.0423716 0.0720971 0.0661581 0.0421273 0.0725971 0.0633937 0.0426007 0.0720971 0.0635546 0.0436601 0.0725971 0.0609896 0.0461294 0.0725971 0.0595644 0.0456285 0.0720971 0.0602751 0.0526497 0.0725971 0.061781 0.0522462 0.0720971 0.0620763 0.0548616 0.0718137 0.0648371 0.0544641 0.0695971 0.0648017 0.0799276 0.0718137 0.0287179 0.0793485 0.071559 0.0289869 0.0762822 0.0720971 0.0276347 0.0788549 0.0720971 0.0287693 0.0795656 0.0695971 0.0288861 0.0797573 0.0694472 0.0287971 0.0697414 0.0720971 0.0360692 0.0686502 0.0720971 0.033643 0.0685951 0.0720971 0.0332614 0.0681581 0.0725971 0.0337317 0.0683492 0.0725971 0.0308358 0.0698771 0.0725971 0.0283684 0.0751019 0.0718137 0.0396607 0.07491 0.071559 0.0390517 0.0744016 0.0725771 0.0393521 0.0751089 0.0717971 0.0396831 0.074982 0.0695971 0.0392801 0.0670701 0.0695971 0.0513645 0.0642823 0.0695971 0.0495047 0.0731748 0.0695971 0.042214 0.0731748 0.071559 0.042214 0.0625851 0.0720971 0.0477028 0.0624036 0.0695971 0.0473655 0.0618462 0.0695971 0.0445736 0.0627594 0.0720971 0.041877 0.0636363 0.0720971 0.0408586 0.0657959 0.0720971 0.0396491 0.0681696 0.0720971 0.0394932 0.0703871 0.0695971 0.0403542 0.0703871 0.0720971 0.0403542 0.0698323 0.0695971 0.045955 0.0671016 0.0695971 0.0516019 0.0680901 0.0695971 0.0475216 0.0666928 0.0695971 0.047552 0.0627594 0.0695971 0.041877 0.0648986 0.0695971 0.0399983 0.0676905 0.0695971 0.0394409 0.0688903 0.0695971 0.0427226 0.07003 0.0695971 0.0447698 0.0744164 0.0720971 0.0388341 0.0718437 0.0720971 0.0376995 0.0696248 0.0695971 0.0359157 0.0696248 0.0720971 0.0359157 0.0685951 0.0695971 0.0332614 0.0688254 0.0720971 0.0309884 0.0690305 0.0695971 0.0304479 0.0690305 0.0720971 0.0304479 0.0702259 0.0720971 0.0287266 0.0708144 0.0720971 0.028229 0.0708144 0.0695971 0.028229 0.0725242 0.0720971 0.0273867 0.0760132 0.0695971 0.0345343 0.07491 0.0695971 0.0390517 0.0718437 0.0695971 0.0376995 0.0721957 0.0695971 0.0346174 0.0714707 0.0695971 0.0334225 0.0734687 0.0695971 0.0271993 0.0747048 0.0695971 0.0300445 0.0762822 0.0695971 0.0276347 0.0793485 0.0695971 0.0289869 0.0450307 0.0720971 0.0708423 0.0453493 0.0695971 0.0712776 0.0433699 0.0720971 0.0685734 0.0542256 0.071559 0.0647805 0.053907 0.0720971 0.0643452 0.0433699 0.0695971 0.0685734 0.0424 0.0695971 0.0663261 0.0436534 0.0695971 0.0617209 0.0440057 0.0720971 0.0613509 0.0462693 0.0720971 0.0600445 0.0480354 0.0695971 0.0598295 0.048488 0.0720971 0.059867 0.0503972 0.0695971 0.0604724 0.0505953 0.0720971 0.0605834 0.0522462 0.0695971 0.0620763 0.0485635 0.0695971 0.067917 0.0471662 0.0695971 0.0679474 0.0542256 0.0695971 0.0647805 0.0482522 0.0695971 0.0626616 0.0470527 0.0695971 0.0627327 0.0456285 0.0695971 0.0602751 0.0425011 0.0695971 0.0638804 0.0452159 0.0695971 0.0660802 0.0839375 0.0720971 -6.57215e-05 0.0811316 0.0720971 -0.000247633 0.0844758 0.0695971 -3.08231e-05 0.0812199 0.0695971 0.00257762 0.0783397 0.0695971 0.000309771 0.0777234 0.0695971 0.00981609 0.0801338 0.0695971 0.00786343 0.0823314 0.0695971 0.00303406 0.083471 0.0695971 0.00508121 0.082581 0.0695971 0.00724856 0.0804199 0.0695971 0.0107293 0.0779939 0.0720971 0.00998548 0.0777234 0.0720971 0.00981609 0.0761601 0.0720971 0.00823174 0.0758447 0.0695971 0.00767693 0.0758447 0.0720971 0.00767693 0.0753086 0.0720971 0.00584139 0.0752873 0.0695971 0.00488502 0.0756209 0.0720971 0.00332322 0.0762005 0.0695971 0.00218845 0.0762005 0.0720971 0.00218845 0.0783397 0.0720971 0.000309771 0.0811316 0.0695971 -0.000247633 0.0539627 0.0812971 -0.0656013 0.058975 0.0812971 -0.0611346 0.058975 0.0749971 -0.0611346 0.0559776 0.0812971 -0.0493435 0.0584196 0.0820971 -0.0605589 0.0552096 0.0820971 -0.0495678 0.0527817 0.0812971 -0.0654163 0.0479742 0.0820971 -0.0564645 0.0601587 0.0728739 -0.0590909 0.0615753 0.0717971 -0.0585148 0.0594187 0.0738294 -0.0600446 0.0589806 0.0747891 -0.0611293 0.0558412 0.0812971 -0.0465481 0.0467771 0.0812971 -0.0563676 0.0441743 0.0820971 -0.0558322 0.0451387 0.0820971 -0.0553535 0.0462143 0.0820971 -0.0553065 0.0462912 0.0812971 -0.0561431 0.0527817 0.0741971 -0.0654163 0.0527642 0.073924 -0.0654325 0.0526295 0.073416 -0.0655561 0.0535623 0.0727193 -0.0659286 0.0523728 0.0729939 -0.0657886 0.0520224 0.0727106 -0.0660991 0.0826226 0.0740638 0.0197327 0.0827265 0.0732258 0.0192924 0.0828894 0.0725216 0.0185798 0.0833714 0.0717971 0.0162804 0.0737232 0.0812971 0.011552 0.0684695 0.0812971 0.0229141 0.0690049 0.0812971 0.0225625 0.079216 0.0725971 0.0283818 0.0793021 0.0726239 0.0280999 0.0794462 0.0728099 0.0276098 0.0795587 0.0731485 0.027209 0.080475 0.0723375 0.0271981 0.0796318 0.0735992 0.0269392 0.0823351 0.0812971 0.0190981 0.0707982 0.0820971 0.0218577 0.079997 0.0820971 0.026099 0.0704632 0.0812971 0.0225842 0.0825856 0.0812971 0.019887 0.0807575 0.0812971 0.0263471 0.0753049 0.0725971 0.00974692 0.074514 0.0729186 0.0106495 0.0825081 0.0727724 0.0172559 0.0824307 0.0732339 0.0181558 0.0739351 0.0737971 0.0113102 0.0823743 0.0738298 0.0187296 0.0823395 0.0745962 0.0190571 0.0724019 0.0733 0.00656151 0.0738436 0.0740786 0.0114146 0.0737593 0.0729186 0.00981211 0.0732206 0.0729186 0.00882182 0.0743348 0.0725971 0.00837619 0.0729278 0.0729186 0.00773322 0.0741152 0.0725971 0.00755974 0.0728969 0.0729186 0.00660635 0.0741865 0.0733 0.0110233 0.0721064 0.0749971 0.00926745 0.0730422 0.0737971 0.0103196 0.072405 0.0737971 0.00914805 0.0720586 0.0737971 0.00786022 0.0717404 0.0749971 0.0079067 0.0717018 0.0749971 0.00649811 0.0720221 0.0737971 0.00652711 0.0572421 0.0737971 -0.0441914 0.057544 0.0733 -0.0444245 0.0581603 0.0727798 -0.0449003 0.0579375 0.0729186 -0.0447282 0.0573581 0.0729186 -0.0456953 0.0584528 0.0725971 -0.0461868 0.0569427 0.0729186 -0.0478954 0.0581995 0.0725971 -0.0469934 0.0581412 0.0725971 -0.0478369 0.0565568 0.0737971 -0.0453354 0.0561571 0.0737971 -0.0466077 0.0570203 0.0729186 -0.0467707 0.0560652 0.0737971 -0.0479382 0.0571294 0.0729186 -0.0490071 0.0562634 0.0749971 -0.0452037 0.0558412 0.0749971 -0.0465481 0.0592391 0.0744314 -0.0602701 0.0562862 0.0737971 -0.0492533 0.0600994 0.0729174 -0.0591688 0.0597216 0.0733008 -0.0596589 0.0582813 0.0725971 -0.0486707 0.0609953 0.0725971 -0.0579637 0.0607353 0.0726226 -0.0583198 0.0569876 0.0749971 -0.0439949 0.0569876 0.0812971 -0.0439949 0.0557441 0.0749971 -0.0479538 0.0737232 0.0749971 0.011552 0.0727798 0.0749971 0.0105053 0.0717018 0.0812971 0.00649811 0.0721064 0.0812971 0.00926745 0.0469073 0.0730657 -0.0571509 0.0473014 0.0741971 -0.0568974 0.0471211 0.0733971 -0.0570133 0.0462312 0.0733971 -0.0563489 0.0448037 0.0733971 -0.0566277 0.0451671 0.0728114 -0.057087 0.0457492 0.0725971 -0.0576749 0.0454836 0.0733971 -0.056315 0.0455959 0.0728114 -0.0568898 0.0703735 0.0733971 0.0227788 0.0704632 0.0741971 0.0225842 0.070267 0.0730657 0.0230098 0.0697837 0.0728114 0.0232216 0.0697244 0.0725971 0.0240194 0.0697364 0.0741971 0.022419 0.0692659 0.0733971 0.0226965 0.0698271 0.0733971 0.0226375 0.0696536 0.0725971 0.0240268 0.0701283 0.0728114 0.0233107 0.0700497 0.0727189 0.0234811 0.046083 0.0812971 -0.0560956 0.0462912 0.0741971 -0.0561431 0.0454425 0.0741971 -0.0561046 0.0453384 0.0812971 -0.0561282 0.069843 0.0741971 0.0224238 0.069843 0.0812971 0.0224238 0.069206 0.0741971 0.0224907 0.0684695 0.0741971 0.0229141 0.0683943 0.0741971 0.02299 0.0683943 0.0812971 0.02299 0.0680092 0.0741971 0.0236282 0.0680092 0.0812971 0.0236282 0.0823351 0.0749971 0.0190981 0.079662 0.0741971 0.0268255 0.079662 0.0812971 0.0268255 0.0473014 0.0812971 -0.0568974 0.0591875 0.0749971 -0.0603346 0.0591875 0.0812971 -0.0603346 0.0559776 0.0749971 -0.0493435 -0.0259736 0.0815971 0.04623 0.00447903 0.0815971 0.0553223 0.0155228 0.0815971 0.0532874 0.0097806 0.0815971 0.0380505 0.04153 0.0815971 0.0227935 0.0493129 0.0815971 0.0254602 0.0425413 0.0815971 0.0262639 0.0380139 0.0815971 -0.0110753 0.0330668 0.0815971 -0.00624847 0.0331182 0.0815971 -0.0102281 0.0334294 0.0815971 -0.00915988 0.0293528 0.0815971 -0.0189933 0.0274578 0.0815971 -0.0250656 0.047686 0.0815971 -0.0283837 0.0280522 0.0815971 -0.0274939 0.0273809 0.0815971 -0.0286003 0.0227851 0.0815971 -0.0415309 -0.0208431 0.0815971 -0.0514356 -0.0100618 0.0815971 -0.0545774 -0.00978993 0.0815971 -0.038043 -0.0128799 0.0815971 -0.0354669 -0.00047249 0.0815971 -0.0347534 -0.025074 0.0815971 -0.0274587 -0.0182817 0.0815971 -0.0295636 -0.0457298 0.0815971 -0.0215649 -0.0383893 0.0815971 0.0132727 -0.0394634 0.0815971 0.0115025 -0.0139488 0.0815971 0.0427258 -0.0067483 0.0815971 0.0550925 0.00147448 0.0815971 0.0382313 0.0149507 0.0815971 -0.0392479 0.00113113 0.0815971 -0.0554846 0.00940989 0.0815971 -0.0384609 0.00700973 0.0815971 -0.0377614 0.015581 0.0815971 -0.0284013 -0.000709617 0.0815971 -0.0323886 0.0231564 0.0815971 -0.0266467 0.0262464 0.0815971 -0.0292228 0.0250681 0.0815971 -0.0336965 0.0172338 0.0815971 -0.0314135 0.0239804 0.0815971 -0.0286535 0.00951498 0.0815971 -0.0336324 0.0242116 0.0815971 -0.0247512 0.0263514 0.0815971 -0.0243943 0.0349623 0.0815971 0.000255976 0.0311015 0.0815971 -0.00906093 0.0354373 0.0815971 0.0112523 0.039247 0.0815971 0.0149592 0.0367311 0.0815971 0.0112241 0.0377605 0.0815971 0.00701815 0.0353322 0.0815971 0.00642379 0.0314664 0.0815971 0.00770657 0.0342258 0.0815971 0.00709507 0.0284004 0.0815971 0.0155894 0.0343027 0.0815971 0.0106298 0.0249878 0.0815971 0.0239315 0.0336956 0.0815971 0.0250765 0.028234 0.0815971 0.0236171 0.0260941 0.0815971 0.0232603 -0.00770749 0.0815971 0.0314748 -0.0110092 0.0815971 0.037256 -0.0172431 0.0815971 0.031421 -0.00952431 0.0815971 0.0336399 -0.023233 0.0815971 0.0273963 -0.0232612 0.0815971 0.0261026 -0.022411 0.0815971 0.0234071 -0.0239324 0.0815971 0.0249962 -0.0311108 0.0815971 0.00906843 -0.0343121 0.0815971 -0.0106223 -0.0314757 0.0815971 -0.00769907 -0.0168113 0.0815971 -0.0276964 -0.0244027 0.0815971 -0.0263524 -0.0262085 0.0815971 -0.0280812 -0.0307712 0.0815971 -0.0461879 -0.0394397 0.0815971 -0.0390491 -0.0337049 0.0815971 -0.025069 -0.0291155 0.0815971 -0.0266026 -0.023408 0.0815971 -0.0224026 -0.0305376 0.0815971 0.0122866 -0.0327338 0.0815971 0.0131496 -0.0286421 0.0815971 0.018791 -0.0554794 0.0815971 0.00167985 -0.0317828 0.0815971 0.00926427 -0.0346721 0.0815971 0.00649806 0.0243652 0.0815971 0.0250661 0.0182724 0.0815971 0.0295711 0.0261992 0.0815971 0.0280887 0.0192837 0.0815971 0.0330415 0.027493 0.0815971 0.0280606 0.0347069 0.0815971 0.028547 0.0284651 0.0815971 0.0275194 0.00794663 0.0815971 0.0350278 0.00797479 0.0815971 0.0363216 0.00864607 0.0815971 0.037428 0.00967552 0.0815971 0.033222 0.0128033 0.0815971 0.0362165 0.0109693 0.0815971 0.0331939 -0.00812544 0.0815971 0.0384402 0.000463156 0.0815971 0.0347609 -0.00642471 0.0815971 0.0353406 -0.0292679 0.0815971 0.0349252 -0.025067 0.0815971 0.0243737 -0.0263608 0.0815971 0.0244018 -0.0335526 0.0815971 0.020222 -0.028157 0.0815971 0.0269498 -0.0278457 0.0815971 0.028018 -0.0271018 0.0815971 0.0288453 -0.0243574 0.0815971 0.0334942 -0.0249619 0.0815971 0.0292022 -0.0391621 0.0815971 0.000972673 -0.0354466 0.0815971 -0.0112448 -0.0367404 0.0815971 -0.0112166 -0.0383536 0.0815971 -0.00976609 -0.0382253 0.0815971 -0.00760047 -0.0374814 0.0815971 -0.00677314 -0.0342516 0.0815971 -0.000458308 -0.0342351 0.0815971 -0.00708757 -0.0220744 0.0815971 0.0413286 -0.0210631 0.0815971 0.044799 -0.0149601 0.0815971 0.0392554 0.0314126 0.0815971 0.0172422 0.0352771 0.0815971 0.0428458 -0.0251866 0.0815971 0.049462 -0.0370101 0.0815971 0.0413662 -0.0269849 0.0815971 0.0427595 -0.0111375 0.0815971 0.0350904 0.0106214 0.0815971 -0.0343037 -0.0434468 0.0815971 -0.0137305 -0.0385362 0.0815971 -0.0151615 -0.0408193 0.0815971 -0.0229959 -0.0314219 0.0815971 -0.0172347 0.0372822 0.0820971 -0.046812 0.053522 0.0820971 -0.0324933 0.0433096 0.0820971 -0.0412987 0.052043 0.0820971 -0.0295438 0.0606563 0.0820971 -0.0359197 -0.058726 0.0820971 -0.0115644 -0.0704675 0.0820971 0.00229126 0.0305601 0.0820971 -0.0514532 0.0534545 0.0820971 -0.0649835 0.0472168 0.0820971 -0.0556993 -0.0704736 0.0820971 0.00209632 -0.0631422 0.0820971 -0.0329067 -0.0566039 0.0820971 -0.0194525 -0.0534275 0.0820971 -0.0269782 -0.0492558 0.0820971 -0.0340013 -0.0441667 0.0820971 -0.040391 -0.038255 0.0820971 -0.0460281 -0.0268387 0.0820971 -0.065946 -0.0316307 0.0820971 -0.0508078 -0.0244173 0.0820971 -0.054641 -0.0167491 0.0820971 -0.0574562 -0.00876906 0.0820971 -0.059201 0.0222191 0.0820971 -0.067639 0.0550551 0.0820971 -0.0463996 0.00752921 0.0820971 -0.0593702 0.0337175 0.0820971 -0.062704 0.0792275 0.0725771 0.0284089 0.0799691 0.0717971 0.0286515 0.0651192 0.0717971 0.0545508 0.0544098 0.0725771 0.0642194 0.0607789 0.0725971 0.058198 0.0544132 0.0725971 0.0641903 0.0731484 0.0725971 0.0415953 0.0447588 0.0725771 0.0712836 0.0354901 0.0717971 0.0771829 0.0348911 0.0717971 0.0774556 -0.039684 0.0717971 0.0751174 -0.0284099 0.0725771 0.0792359 -0.0114224 0.0725971 0.0833756 -0.0200106 0.0725971 0.081741 -0.0256308 0.0717971 0.0809964 -0.0644916 0.0723908 0.0543859 -0.0647917 0.0721844 0.0543497 -0.0583308 0.0725971 0.0606608 -0.0515739 0.0725771 0.0665259 -0.0588853 0.0717971 0.0612375 -0.0519984 0.0718137 0.0671627 0.0648287 0.0718137 -0.0548625 0.064211 0.0725771 -0.0544107 0.0420403 0.0718137 -0.0737925 0.0393437 0.0725771 -0.0744025 0.0415869 0.0725971 -0.0731493 0.0287095 0.0718137 -0.0799285 0.0284005 0.0725771 -0.0792284 0.0114438 0.0718137 -0.0841545 0.0200013 0.0725971 -0.0817335 0.0220848 0.0717971 -0.082024 -0.0452153 0.0717971 -0.0719163 -0.000490778 0.0718137 -0.0849282 -0.012109 0.0717971 -0.0840795 -0.0671667 0.0717971 -0.0520132 -0.0544191 0.0725771 -0.0642119 -0.0751183 0.0717971 -0.0396756 -0.0744109 0.0725771 -0.0393446 -0.0743832 0.0725971 -0.0393543 -0.0840108 0.0719909 -0.0112471 -0.0836106 0.0723908 -0.0112224 0.0619061 0.0812971 -0.036753 0.0618624 0.0813992 -0.0366263 0.0563544 0.0820971 -0.043506 0.0612182 0.0820971 -0.0363446 0.0717502 0.0815013 -0.00241907 0.0712301 0.0820246 -0.00231503 0.0446707 0.0812971 -0.0564596 -0.0719693 0.0812971 0.00225981 0.0340964 0.0812971 -0.0634085 0.0101472 0.0812971 -0.071277 0.0100344 0.0820971 -0.0704849 -0.00213236 0.0812971 -0.0719648 -0.0024603 0.0820971 -0.0711539 -0.0146112 0.0812971 -0.0704991 -0.0148792 0.0820971 -0.0696252 -0.037868 0.0812971 -0.0612365 -0.0379695 0.0820971 -0.0602301 -0.0479277 0.0820971 -0.0526538 -0.0564059 0.0820971 -0.0434513 -0.0638516 0.0812971 -0.0332765 -0.0679285 0.0820971 -0.0213456 -0.0686917 0.0812971 -0.0215855 -0.070617 0.0820971 -0.00912526 -0.0712657 0.0812971 -0.0102851 0.0304755 0.0820971 0.0643497 0.0565923 0.0820971 0.0432036 0.0672535 0.0820971 0.0233657 0.0627537 0.0731476 -0.03703 0.0609458 0.0727798 -0.0410399 0.0617076 0.0725971 -0.0415529 0.0603 0.0733 -0.040605 0.0598684 0.0740786 -0.0403144 0.0571322 0.0740786 -0.0441065 0.0597169 0.0749971 -0.0402123 0.0719719 0.0749971 0.00184151 0.0721545 0.0740786 0.00184617 0.0720881 0.0742206 -0.00228529 0.0730308 0.0729932 -0.00252693 0.0734301 0.0727796 -0.00262874 0.0734529 0.0727798 0.00187932 0.0726746 0.0733 0.00185945 -0.0266453 0.0741971 -0.0668863 -0.0209796 0.0735848 -0.0690006 0.0456635 0.0725971 -0.0577144 0.0380711 0.0727189 -0.0622654 -0.0729487 0.0727187 0.00253832 -0.072813 0.0727189 -0.00511074 -0.0726762 0.0728654 0.00246115 -0.0731594 0.0726477 0.00259781 -0.0734237 0.0725971 -0.00515365 -0.0722706 0.0725971 -0.013946 -0.0716694 0.0727189 -0.01383 -0.0668491 0.0725971 -0.0307985 -0.0722952 0.0730657 -0.00507437 0.0133908 0.0741971 -0.0707392 0.0134135 0.0735848 -0.0708588 0.0218384 0.0735848 -0.0687307 0.0300903 0.0730657 -0.0659204 0.0305602 0.0725971 -0.0669496 0.0135746 0.0727189 -0.0717096 0.013478 0.0730657 -0.0711996 0.00485138 0.0727189 -0.0728222 0.00481684 0.0730657 -0.0723043 -0.00391433 0.0730657 -0.0723593 -0.00389562 0.0735848 -0.072013 -0.0125074 0.0741971 -0.0709024 -0.0125285 0.0735848 -0.0710223 -0.00397536 0.0725971 -0.0734891 -0.0126789 0.0727189 -0.0718751 -0.0210805 0.0730657 -0.0693325 -0.0376053 0.0725971 -0.0632667 -0.0372925 0.0727189 -0.0627404 -0.0445678 0.0727189 -0.0578005 -0.0508321 0.0730657 -0.0516515 -0.0516257 0.0725971 -0.052458 -0.0655066 0.0735848 -0.0301799 -0.0626595 0.0725971 -0.038614 -0.0621382 0.0727189 -0.0382928 -0.066293 0.0727189 -0.0305423 -0.0658216 0.0730657 -0.030325 -0.0689914 0.0730657 -0.0221894 -0.0708192 0.0735848 -0.0136658 -0.0706996 0.0741971 -0.0136428 0.0449615 0.0730657 -0.0568271 0.0376194 0.0735848 -0.0615266 0.0383905 0.0725971 -0.0627877 0.0378003 0.0730657 -0.0618225 0.0299463 0.0735848 -0.0656049 0.0218015 0.0741971 -0.0686147 0.0226377 0.0741971 -0.0683433 0.0298957 0.0741971 -0.0654941 0.0341747 0.0741971 -0.0633664 0.0221007 0.0727189 -0.069556 0.0303059 0.0727189 -0.0663926 0.0219435 0.0730657 -0.0690613 0.00479377 0.0735848 -0.0719582 0.00478566 0.0741971 -0.0718367 0.0136885 0.0725971 -0.0723112 -0.00394233 0.0727189 -0.0728777 -0.0209442 0.0741971 -0.0688841 -0.0125887 0.0730657 -0.0713639 -0.0440391 0.0735848 -0.0571147 -0.0292663 0.0730657 -0.0662945 -0.0294759 0.0727189 -0.0667694 -0.0212314 0.0727189 -0.0698291 -0.0127852 0.0725971 -0.0724781 -0.0368501 0.0735848 -0.061996 -0.0291262 0.0735848 -0.0659772 -0.0297231 0.0725971 -0.0673296 -0.0370273 0.0730657 -0.0622941 -0.0442509 0.0730657 -0.0573894 -0.0612974 0.0741971 -0.0377745 -0.0564044 0.0735848 -0.0449476 -0.0565476 0.0741971 -0.0445708 -0.0563091 0.0741971 -0.0448717 -0.0505889 0.0735848 -0.0514043 -0.0505035 0.0741971 -0.0513175 -0.0479377 0.0741971 -0.0537217 -0.0511962 0.0727189 -0.0520215 -0.0570815 0.0727189 -0.0454873 -0.0566756 0.0730657 -0.0451638 -0.0616964 0.0730657 -0.0380204 -0.0614011 0.0735848 -0.0378384 -0.0685453 0.0741971 -0.0220459 -0.0686612 0.0735848 -0.0220832 -0.068392 0.0741971 -0.0225167 -0.0634357 0.0741971 -0.0340625 -0.0694855 0.0727189 -0.0223484 -0.0711597 0.0730657 -0.0137316 -0.0712657 0.0741971 -0.0102851 -0.0719492 0.0735848 -0.00505006 -0.0386201 0.0735848 0.0609168 -0.0576642 0.0741971 0.0431243 -0.0146005 0.0727189 0.0715171 -0.005804 0.0730657 0.07224 0.0204154 0.0727189 0.0700768 -0.0316054 0.0725971 0.0664745 -0.0313425 0.0727189 0.0659215 -0.06355 0.0725971 0.0371381 -0.0577617 0.0735848 0.0431972 -0.0620343 0.0738213 0.0366476 -0.014723 0.0725971 0.0721171 -0.0584552 0.0727189 0.0437158 -0.0527403 0.0727189 0.0504632 -0.0531827 0.0725971 0.0508865 -0.00584554 0.0727189 0.0727574 0.00297384 0.0730657 0.0724111 -0.00589454 0.0725971 0.0733677 0.00302034 0.0725971 0.0735416 -0.0229768 0.0730657 0.068735 -0.0231413 0.0727189 0.0692273 -0.0551286 0.0741971 0.0463217 -0.0521146 0.0735848 0.0498646 -0.0580395 0.0730657 0.0434049 -0.0622434 0.0733243 0.0367149 -0.0523652 0.0730657 0.0501044 -0.0467678 0.0741971 0.0547505 -0.0520266 0.0741971 0.0497804 -0.0390837 0.0727189 0.0616482 -0.0462514 0.0727189 0.0564701 -0.0388058 0.0730657 0.0612098 -0.0459225 0.0730657 0.0560685 -0.0457027 0.0735848 0.0558002 -0.0311196 0.0730657 0.0654527 -0.0228668 0.0735848 0.0684061 -0.0309707 0.0735848 0.0651394 -0.014403 0.0741971 0.0705494 -0.0144274 0.0735848 0.0706687 -0.0151318 0.0741971 0.0703967 -0.0264938 0.0741971 0.0669539 -0.0144967 0.0730657 0.0710086 -0.00577625 0.0735848 0.0718942 0.00295958 0.0735848 0.0720646 -0.00335849 0.0741971 0.0719256 0.00295458 0.0741971 0.0719429 0.00850599 0.0741971 0.071499 0.00299517 0.0727189 0.0729298 0.0117919 0.0727189 0.0720318 0.0202702 0.0730657 0.0695784 0.011708 0.0730657 0.0715196 0.0116519 0.0735848 0.0711773 0.0201731 0.0735848 0.0692454 0.0116322 0.0741971 0.0710571 0.0600998 0.0783447 -0.0357033 0.0592558 0.0796334 -0.0353752 0.0692538 0.0794024 -0.00204426 0.0694583 0.079167 -0.0021762 0.0690728 0.0795651 -0.00200827 -0.0602068 0.0781644 0.0356306 -0.0600185 0.078621 0.0356756 -0.0597896 0.0790638 0.0355866 -0.0592651 0.0796334 0.0353827 -0.0587136 0.0799552 0.0351262 -0.0675829 0.0800971 0.00171764 -0.0698382 0.0784751 0.00227459 -0.0699704 0.0776971 0.00219241 -0.0699169 0.0782026 0.00218176 -0.0694676 0.079167 0.0021837 -0.0688916 0.0797034 0.00204192 -0.0690822 0.0795651 0.00201577 -0.0683696 0.0799631 0.00187408 0.00740333 0.0830971 -0.0583781 0.00741291 0.0827144 -0.0584536 0.0586217 0.0830971 -0.00512201 0.0586633 0.0830971 -0.00462134 0.0530765 0.0821732 0.0268132 -0.00871302 0.0821732 -0.0588225 -0.000625711 0.0820971 -0.059843 -0.00062174 0.0821732 -0.0594604 0.0155438 0.0820971 -0.0577913 0.00748104 0.0821732 -0.0589905 0.0232687 0.0820971 -0.0551358 0.0521575 0.0821737 -0.0285499 0.0485302 0.0820971 -0.0350161 0.0523394 0.0823097 -0.0277218 0.0522223 0.08239 -0.0277493 0.0522893 0.0822737 -0.0279202 0.0531865 0.0826389 -0.0254346 0.0529499 0.0826115 -0.025957 0.0553442 0.0826389 -0.0203166 0.0588603 0.0824272 -0.00534611 0.0585252 0.0826389 -0.00711466 0.0575614 0.0827144 -0.0125831 0.0566019 0.0826389 -0.016492 0.0597682 0.0820971 -0.00303447 0.0593292 0.0821743 -0.00393821 0.0593629 0.0821732 0.00344609 0.0565946 0.0820971 0.01946 0.0370437 0.0821732 -0.0465127 0.0562327 0.0821732 0.0193356 0.0583412 0.0821732 0.0114979 0.0587167 0.0820971 0.0115719 0.0229095 0.0827144 -0.0542847 0.0229938 0.08239 -0.0544844 0.0303647 0.0821732 -0.0511242 0.0231199 0.0821732 -0.0547833 0.0311332 0.0827144 0.050031 0.0450749 0.0830971 0.0378344 0.0434757 0.0827144 0.0397749 0.0434195 0.0830971 0.0397235 0.0312477 0.08239 0.050215 0.0380011 0.0821732 0.0457413 0.0486646 0.08239 0.0336071 0.0436356 0.08239 0.0399212 0.0382457 0.0820971 0.0460356 0.043875 0.0821732 0.0401402 0.052787 0.08239 0.026667 0.0525935 0.0827144 0.0265692 0.0557209 0.0827144 0.0191597 0.0427979 0.08239 -0.0408108 0.0300494 0.0830971 -0.0505934 0.0300883 0.0827144 -0.0506589 0.0367066 0.0827144 -0.0460893 0.0368416 0.08239 -0.0462589 0.0167398 0.0820971 0.0574637 0.0164813 0.0827144 0.0565767 0.0314192 0.0821732 0.0504904 0.0242519 0.0821732 0.0542991 0.0241196 0.08239 0.0540029 0.0240311 0.0827144 0.0538049 0.0376552 0.0827144 0.0453251 0.0271663 0.0830971 0.0522059 0.0377938 0.08239 0.0454918 0.0484862 0.0827144 0.0334839 0.0525255 0.0830971 0.0265349 0.0515891 0.0830971 0.0283129 0.0484236 0.0830971 0.0334407 0.0441574 0.0820971 0.0403985 0.0489316 0.0821732 0.0337914 0.0492465 0.0820971 0.0340088 0.0559259 0.08239 0.0192302 0.0561206 0.0830971 0.0177035 0.0580229 0.08239 0.0114352 0.0590391 0.08239 0.00342731 0.0578103 0.0827144 0.0113933 0.0584952 0.0830971 0.00641391 0.0589553 0.08239 -0.00464436 0.0588226 0.0827144 0.00341476 0.0587467 0.0830971 0.00341036 0.0587392 0.0827144 -0.00462733 0.0574871 0.0830971 -0.0125669 0.0553114 0.0827144 -0.0203045 0.0521975 0.0830971 -0.0271672 0.0482199 0.0821732 -0.0347922 0.0479568 0.08239 -0.0346023 0.0521706 0.0821838 -0.0284773 0.0520308 0.0827144 -0.0276475 0.0477193 0.0830971 -0.034431 0.047781 0.0827144 -0.0344755 0.042641 0.0827144 -0.0406612 0.037826 0.0830971 -0.0450758 0.0458936 0.0830971 -0.0368292 0.0430327 0.0821732 -0.0410347 0.030199 0.08239 -0.0508452 0.0154444 0.0821732 -0.0574218 0.0153601 0.08239 -0.0571085 0.0176951 0.0830971 -0.0561215 0.0153038 0.0827144 -0.0568991 0.015284 0.0830971 -0.0568256 0.0074402 0.08239 -0.0586687 -0.000618374 0.08239 -0.059136 0.00640549 0.0830971 -0.0584961 -0.00513043 0.0830971 -0.0586226 -0.00866551 0.08239 -0.0585016 -0.00863377 0.0827144 -0.0582871 -0.000616124 0.0827144 -0.0589192 -0.0165513 0.08239 -0.0567773 -0.0164907 0.0827144 -0.0565692 -0.0535314 0.0820971 0.0325008 0.0713637 0.0820971 0.00956454 0.0709051 0.0820971 0.00642595 0.059745 0.0820971 0.00346824 0.0626001 0.0820971 -0.0013412 0.064283 0.0820971 -0.00105581 0.0534181 0.0820971 0.0269857 0.0627122 0.0820971 0.0337088 0.0490477 0.0820971 0.051611 0.0316214 0.0820971 0.0508153 0.0402684 0.0820971 0.0587193 0.0199153 0.0820971 0.0683604 0.024408 0.0820971 0.0546485 0.0818079 0.0820971 0.0196998 0.073196 0.0820971 0.0121537 0.0689821 0.0820971 0.0217226 0.0679183 0.0820971 0.0223343 -0.0606656 0.0820971 0.0359272 -0.060566 0.0820971 0.0360949 -0.0305695 0.0820971 0.0514607 -0.0548608 0.0820971 0.0453936 0.00875973 0.0820971 0.0592085 0.000616378 0.0820971 0.0598505 -0.00347485 0.0820971 0.0711191 -0.00753854 0.0820971 0.0593777 -0.0155531 0.0820971 0.0577988 0.0446707 0.0741971 -0.0564596 0.0375558 0.0741971 -0.0614227 0.0224688 0.0812971 -0.068399 0.0104113 0.0741971 -0.0712388 -0.00248789 0.0812971 -0.0719534 -0.00213236 0.0741971 -0.0719648 -0.00388905 0.0741971 -0.0718914 -0.0146112 0.0741971 -0.0704991 -0.0150463 0.0812971 -0.0704075 -0.0266453 0.0812971 -0.0668863 -0.0271402 0.0812971 -0.066687 -0.0290771 0.0741971 -0.0658658 -0.0367879 0.0741971 -0.0618913 -0.0383961 0.0812971 -0.0609069 -0.037868 0.0741971 -0.0612365 -0.0479377 0.0812971 -0.0537217 -0.0439647 0.0741971 -0.0570183 -0.0484662 0.0812971 -0.0532455 -0.0565476 0.0812971 -0.0445708 -0.0570396 0.0812971 -0.0439395 -0.0634357 0.0812971 -0.0340625 -0.068392 0.0812971 -0.0225167 -0.065396 0.0741971 -0.0301289 -0.0718277 0.0741971 -0.00504153 -0.0714104 0.0812971 -0.00922783 0.0308179 0.0812971 0.0650727 0.0201391 0.0741971 0.0691285 0.040721 0.0812971 0.059379 0.040721 0.0741971 0.059379 0.0430458 0.0741971 0.0577156 0.0495989 0.0812971 0.0521908 0.055449 0.0741971 0.0459264 0.0572282 0.0812971 0.043689 0.0572282 0.0741971 0.043689 0.0605133 0.0741971 0.0390112 0.0634169 0.0812971 0.0340876 -0.0717833 0.0705971 -0.0130166 -0.056233 0.0705971 -0.0464729 -0.0475356 0.0705971 -0.0553362 -0.0263011 0.0705971 -0.0680418 -0.0143792 0.0705971 -0.071516 -0.00204074 0.0679971 -0.0729178 0.0103567 0.0679971 -0.0722067 0.0339003 0.0679971 -0.0645885 0.0443643 0.0679971 -0.0579022 0.0204049 0.0679971 0.0700406 0.00900211 0.0705971 0.0723956 -0.00263008 0.0705971 0.0729065 -0.0141954 0.0705971 0.0715602 -0.0253992 0.0705971 0.068391 -0.0359561 0.0705971 0.0634797 -0.0253992 0.0679971 0.068391 -0.0455971 0.0705971 0.0569514 -0.0455971 0.0679971 0.0569514 -0.0540767 0.0705971 0.0489723 -0.0611788 0.0705971 0.0397458 -0.0746937 0.0705971 0.00309409 0.0626701 0.0705971 -0.0382489 0.0646522 0.0705971 -0.0375129 0.0649618 0.0705971 -0.0374783 0.0611695 0.0705971 -0.0397383 0.0409954 0.0705971 -0.0374027 0.0535427 0.0705971 -0.049538 0.0443643 0.0705971 -0.0579022 0.0326263 0.0705971 -0.0448902 0.0339003 0.0705971 -0.0645885 0.0224539 0.0705971 -0.0694031 0.0122776 0.0705971 -0.0541201 -0.0394397 0.0705971 -0.0390491 -0.0208431 0.0705971 -0.0514356 -0.037461 0.0705971 -0.062596 -0.0100618 0.0705971 -0.0545774 0.00113113 0.0705971 -0.0554846 -0.00204074 0.0705971 -0.0729178 0.0103567 0.0705971 -0.0722067 -0.0566359 0.0705971 -0.000750683 -0.0729517 0.0705971 -0.000653842 -0.0685351 0.0705971 -0.025002 -0.0633011 0.0705971 -0.0362629 0.0749269 0.0705971 -0.0032821 0.0749104 0.0705971 -0.0032696 0.0704582 0.0705971 -0.00228376 0.0578244 0.0705971 0.000228505 -0.0445788 0.0705971 0.0330704 -0.0279264 0.0705971 0.0479686 -0.0370101 0.0705971 0.0413662 -0.0451335 0.0705971 0.0323091 0.0413733 0.0705971 0.0600834 0.0155228 0.0705971 0.0532874 0.0204049 0.0705971 0.0700406 0.00447903 0.0705971 0.0553223 0.043179 0.0705971 0.0348667 0.0352771 0.0705971 0.0428458 0.0486507 0.0800971 -0.0312518 0.0578244 0.0800971 0.000228505 0.0631583 0.0800971 -0.00139459 0.0559776 0.0800971 0.00141433 0.0588769 0.0800971 -0.00449492 0.0580102 0.0800971 -0.00705203 0.0561039 0.0800971 -0.0163469 0.0556403 0.0800971 -0.00629244 0.0527185 0.0800971 -0.0252108 0.0464559 0.0800971 -0.0312598 0.0601839 0.0710971 -0.0357361 0.0602419 0.0710971 -0.0356382 -0.0699668 0.0710971 0.00230609 -0.0540309 0.0800971 0.0327557 -0.0473652 0.0800971 0.0310626 -0.0525451 0.0800971 0.0305012 -0.0588863 0.0800971 0.00450242 -0.0607034 0.0800971 0.00250546 -0.0580196 0.0800971 0.00705953 -0.0537684 0.0800971 0.0156711 -0.0503209 0.0800971 0.0245858 -0.0601933 0.0776971 0.0357436 -0.0601933 0.0710971 0.0357436 -0.0602513 0.0776971 0.0356457 0.07196 0.0812971 -0.00225231 0.0727333 0.0725971 -0.0423094 0.0712752 0.0725771 -0.0447598 0.0734248 0.0717971 -0.0427117 0.0849438 0.0717971 -0.000498919 0.0841636 0.0725771 -0.00053209 0.0841435 0.0725971 -0.000553417 0.0721309 0.0725971 -0.0405876 0.0642399 0.0725971 -0.0375195 0.0659647 0.0725971 -0.0418441 0.0628954 0.0725971 -0.0423191 0.0588873 0.0725971 -0.0454615 0.0728906 0.0725971 -0.0418201 0.0728287 0.0725971 -0.0413098 0.0825862 0.0725971 0.0161271 0.0747388 0.0725971 0.00911891 0.0751522 0.0725971 0.00314889 0.0743711 0.0725971 0.00190277 0.0740921 0.0725971 0.00671459 0.0766898 0.0725971 0.000847064 0.0811639 0.0725971 -0.000746586 -0.0781275 0.0725971 0.000146008 -0.0811733 0.0725971 0.000754085 -0.0826534 0.0725971 0.00451832 -0.08363 0.0725971 0.00428408 -0.0839563 0.0725971 0.00388692 -0.0735549 0.0725971 0.00270905 -0.0817852 0.0725971 -0.0198247 0.0515693 0.0725971 -0.0664895 0.0499122 0.0725971 -0.0640057 0.0222861 0.0725971 -0.0701395 0.00788998 0.0725971 -0.0753973 0.00489212 0.0725971 -0.0734332 0.00190255 0.0725971 -0.0757855 0.0479731 0.0725971 -0.0621699 0.0459072 0.0725971 -0.0577109 0.0381486 0.0725971 -0.0716428 0.0389793 0.0725971 -0.0681701 0.011413 0.0725971 -0.0833681 -0.0419177 0.0725971 -0.0664096 -0.0346358 0.0725971 -0.0766898 -0.0447394 0.0725971 -0.0712706 0.0458435 0.0725971 -0.0576792 -0.000561833 0.0725971 -0.0841444 -0.011995 0.0725971 -0.0832876 -0.000755002 0.0725971 -0.0811648 -0.0235477 0.0725971 -0.0807858 -0.0214095 0.0725971 -0.0704149 0.0271688 0.0725971 -0.0764848 0.0112199 0.0725971 -0.0803885 0.0102236 0.0725971 -0.0774468 0.027343 0.0725971 -0.0712811 -0.042028 0.0725971 -0.0637416 -0.043285 0.0725971 -0.0613857 -0.0449416 0.0725971 -0.0582854 -0.0607883 0.0725971 -0.0581905 -0.0664979 0.0725971 -0.0515702 -0.0682706 0.0725971 -0.0341897 -0.0681813 0.0725971 -0.0315209 -0.0692587 0.0725971 -0.0290777 -0.0700684 0.0725971 -0.0225359 -0.0774552 0.0725971 -0.0102245 -0.0712896 0.0725971 -0.0273439 -0.0544226 0.0725971 -0.0641828 -0.052659 0.0725971 -0.0617735 -0.0640141 0.0725971 -0.0499131 -0.0506419 0.0725971 -0.0600237 -0.0706739 0.0725971 -0.0399307 -0.0716513 0.0725971 -0.0381495 -0.069509 0.0725971 -0.0365554 -0.0655179 0.0725971 -0.0392066 -0.061737 0.0725971 -0.0427862 -0.0613656 0.0725971 -0.0454305 -0.0575603 0.0725971 -0.045869 0.0695206 0.0725971 0.0241532 0.0723843 0.0725971 0.0269067 0.0697933 0.0725971 0.0240372 -0.0415962 0.0725971 0.0731568 -0.0393627 0.0725971 0.0743823 -0.0599434 0.0725971 0.0451651 -0.0589455 0.0725971 0.0440825 -0.0593259 0.0725971 0.0478635 -0.0515786 0.0725971 0.066497 -0.0499215 0.0725971 0.0640132 -0.0729482 0.0725971 0.0413022 -0.0726544 0.0725971 0.0408119 -0.0641912 0.0725971 0.0544216 -0.0484798 0.0725971 0.0625056 -0.0599856 0.0725971 0.0505519 -0.0316507 0.0725971 0.0681582 -0.0389602 0.0725971 0.0679409 -0.0381579 0.0725971 0.0716503 -0.0466393 0.0725971 0.0569438 -0.0394115 0.0725971 0.0621653 -0.0233354 0.0725971 0.069808 -0.039378 0.0725971 0.065069 0.0507012 0.0725971 0.0533505 0.0613514 0.0725971 0.0453765 0.0664886 0.0725971 0.0515777 -0.0291608 0.0725971 0.0692032 0.000552499 0.0725971 0.0841519 0.0120551 0.0725971 0.0832851 0.000248856 0.0725971 0.0783648 0.03668 0.0725971 0.0638096 0.0440024 0.0725971 0.0589981 0.0640048 0.0725971 0.0499206 0.0621533 0.0725971 0.0479549 0.0485498 0.0725971 0.0593709 0.0633001 0.0725971 0.0404885 0.0618581 0.0725971 0.039878 0.065656 0.0725971 0.039169 0.0682455 0.0725971 0.0389989 0.0693485 0.0725971 0.0363785 0.0716419 0.0725971 0.038157 0.0743739 0.0725971 0.0393618 0.0706646 0.0725971 0.0399382 0.0235383 0.0725971 0.0807933 0.0345625 0.0725971 0.0767262 -0.00148775 0.0725971 0.0761036 0.0205867 0.0725971 0.0706646 0.0118908 0.0725971 0.0726361 -0.0112292 0.0725971 0.080396 -0.0266725 0.0725971 0.0738398 -0.0105851 0.0725971 0.0780549 0.0719154 0.0692971 -0.0452069 0.0734248 0.0679971 -0.0427117 0.0591824 0.0737501 -0.0609339 0.0597283 0.0727511 -0.0603988 0.0567456 0.0679971 -0.0632094 0.0605957 0.0720358 -0.0595285 0.0663499 0.0679971 -0.0530394 0.0648308 0.0692971 -0.0548859 0.048062 0.0679971 -0.0700398 0.0520123 0.0717971 -0.0671583 0.0520598 0.0717971 -0.0671215 0.0520123 0.0692971 -0.0671583 0.0525113 0.0718645 -0.0667688 0.0530984 0.0721822 -0.0663028 0.0567456 0.0812971 -0.0632094 0.0539627 0.0741971 -0.0656013 0.0538597 0.0734146 -0.0656859 0.0396747 0.0717971 -0.0751099 0.0286997 0.0692971 -0.0799498 0.0462227 0.0692971 -0.0712671 0.0134402 0.0679971 -0.0838756 0.0201915 0.0717971 -0.0825106 0.0256214 0.0679971 -0.0809889 0.0286997 0.0717971 -0.0799498 -0.00419074 0.0679971 -0.084843 0.00905733 0.0692971 -0.0844615 -0.000507336 0.0692971 -0.0849448 0.000966951 0.0679971 -0.0849407 -0.0548943 0.0692971 -0.0648317 -0.0530231 0.0692971 -0.0663706 -0.0464566 0.0679971 -0.0711209 -0.0420539 0.0717971 -0.0738093 -0.0354994 0.0679971 -0.0771754 -0.034965 0.0717971 -0.077419 -0.0300612 0.0717971 -0.0794513 -0.0237715 0.0717971 -0.0815538 -0.0173369 0.0717971 -0.0831593 -0.0115274 0.0679971 -0.0841611 -0.00419074 0.0717971 -0.084843 -0.0651286 0.0679971 -0.0545433 -0.0627017 0.0717971 -0.0573163 -0.0613661 0.0717971 -0.0587438 -0.056405 0.0679971 -0.0635219 -0.0738236 0.0717971 -0.0420352 -0.0738236 0.0692971 -0.0420352 -0.0708542 0.0679971 -0.0468667 -0.0751183 0.0692971 -0.0396756 -0.0724379 0.0679971 -0.0443801 -0.0772822 0.0692971 -0.0352763 -0.0818292 0.0679971 -0.0228271 -0.0825627 0.0717971 -0.0200132 -0.0818292 0.0717971 -0.0228271 -0.0844666 0.0679971 -0.00908977 -0.0843845 0.0679971 -0.00982224 -0.0843845 0.0692971 -0.00982224 -0.082213 0.0679971 -0.0214039 0.0671574 0.0717971 0.0520207 0.0354901 0.0679971 0.0771829 0.0548849 0.0692971 0.0648392 0.0530137 0.0679971 0.0663781 0.0671574 0.0692971 0.0520207 0.0651192 0.0679971 0.0545508 0.0626924 0.0679971 0.0573238 0.0613568 0.0717971 0.0587513 0.0563957 0.0717971 0.0635294 0.0548849 0.0717971 0.0648392 0.0708449 0.0679971 0.0468742 0.0799488 0.0717971 0.0287081 0.0799488 0.0692971 0.0287081 0.0807575 0.0741971 0.0263471 0.0807415 0.0737065 0.0263961 0.0806474 0.0729538 0.0266822 0.0772729 0.0679971 0.0352838 0.0751089 0.0692971 0.0396831 0.0781649 0.0692971 0.0332606 0.0781649 0.0679971 0.0332606 0.0802405 0.0719359 0.0278823 0.0841678 0.0692971 0.0114707 0.0831043 0.0720119 0.0175935 0.0828506 0.072656 0.0187522 0.0822037 0.0812971 0.0214114 0.0825856 0.0749971 0.019887 0.0848765 0.0679971 -0.00341434 0.0843751 0.0679971 0.00982974 -0.0840865 0.0725971 0.00338965 -0.0843602 0.0723908 0.000340786 -0.0716585 0.0719909 0.0452735 -0.0719248 0.0717971 0.0452144 -0.0713357 0.0723908 0.0450356 -0.071279 0.0725971 0.0447385 -0.0736118 0.071844 0.0423183 -0.0737025 0.0720121 0.0418204 -0.0566966 0.0807869 0.0165244 0.0566872 0.0807869 -0.0165169 0.0723029 0.0675971 0.012326 0.0814346 0.0675971 0.0227271 0.0774193 0.0675971 0.018954 0.0827086 0.0675971 0.0175315 0.0706988 0.0675971 0.0387983 -0.0219901 0.0675971 0.0816453 -0.0175229 0.0675971 0.082719 -0.0732982 0.0675971 0.0418656 -0.072856 0.0675971 0.0406017 -0.0647183 0.0675971 0.0379163 -0.067276 0.0675971 0.0459493 -0.0722852 0.0675971 0.0402223 -0.0679483 0.0675971 0.0471746 -0.0671929 0.0675971 0.0497668 -0.0655862 0.0675971 0.0533681 -0.0648816 0.0675971 0.0451533 -0.0615142 0.0675971 0.0399637 -0.0596487 0.0675971 0.0426981 -0.0626305 0.0675971 0.0476568 -0.0635205 0.0675971 0.0498242 -0.0468806 0.0675971 0.0654759 -0.055128 0.0675971 0.0575798 -0.0444862 0.0675971 0.0646799 -0.0458471 0.0675971 0.0572636 -0.0456857 0.0675971 0.0647509 -0.0528787 0.0675971 0.0659814 -0.0455722 0.0675971 0.0699657 -0.0441749 0.0675971 0.0699353 -0.043125 0.0675971 0.0693508 -0.0420734 0.0675971 0.0600907 -0.0374563 0.0675971 0.0758066 -0.0352602 0.0675971 0.0748267 -0.0387992 0.0675971 0.0707072 -0.0361532 0.0675971 0.0638278 -0.0311124 0.0675971 0.0718646 -0.0255384 0.0675971 0.068766 -0.00261917 0.0675971 0.0814261 -0.009024 0.0675971 0.0840713 -0.0189549 0.0675971 0.0774278 -0.0142732 0.0675971 0.0719526 -0.00599715 0.0675971 0.078192 0.0205168 0.0675971 0.0704246 -0.00710896 0.0675971 0.0827344 0.00416169 0.0675971 0.084451 0.0228444 0.0675971 0.078412 0.0459409 0.0675971 0.0672751 0.0314593 0.0675971 0.0662627 0.0418466 0.0675971 0.0734692 0.0452159 0.0675971 0.0660802 0.0575714 0.0675971 0.0551271 0.0482522 0.0675971 0.0626616 0.0470527 0.0675971 0.0627327 0.0458578 0.0675971 0.0634576 0.0496134 0.0675971 0.0673326 0.0527641 0.0675971 0.0660656 0.0623971 0.0675971 0.0570539 0.0493637 0.0675971 0.0631181 0.0680901 0.0675971 0.0475216 0.0665793 0.0675971 0.0423372 0.0699269 0.0675971 0.044174 0.0679766 0.0675971 0.0423068 0.0648371 0.0675971 0.0439038 0.0601234 0.0675971 0.0420137 0.0584712 0.0675971 0.0442847 0.0646394 0.0675971 0.0450891 0.0659599 0.0675971 0.052894 0.065779 0.0675971 0.0471362 0.0668906 0.0675971 0.0475926 0.0766855 0.0675971 0.033309 0.0733075 0.0675971 0.0300749 0.076909 0.0675971 0.0351177 0.0748183 0.0675971 0.0352593 0.0721126 0.0675971 0.0307999 0.0714707 0.0675971 0.0334225 0.0843032 0.0675971 -0.00406127 0.0838681 0.0675971 -0.00459083 0.0814176 0.0675971 0.00261826 0.0832514 0.0675971 -0.00488973 0.0833983 0.0675971 0.00588275 0.0733424 0.0675971 0.000664947 0.0784167 0.0675971 0.00655411 0.0803316 0.0675971 0.00790407 0.0839778 0.0675971 0.00978347 0.082726 0.0675971 0.00710804 0.0789705 0.0675971 0.00323312 0.074945 0.0675971 -0.00278315 0.0800204 0.0675971 0.00264867 0.077045 0.0675971 -0.00380525 0.0825661 0.0675971 -0.00490314 0.0538363 0.0675971 -0.0498096 0.0104135 0.0675971 -0.0726026 -0.0818259 0.0675971 -0.0213031 0.00587433 0.0675971 -0.0833993 0.0551187 0.0675971 -0.0575723 0.0649748 0.0675971 -0.0378786 0.0670293 0.0675971 -0.0381749 0.0615049 0.0675971 -0.0399562 0.0575616 0.0675971 -0.0619222 0.0659583 0.0675971 -0.0504316 0.067939 0.0675971 -0.0471671 0.0671836 0.0675971 -0.0497593 0.0628188 0.0675971 -0.0488346 0.0648723 0.0675971 -0.0451458 0.0626211 0.0675971 -0.0476494 0.0629573 0.0675971 -0.0464957 0.0596646 0.0675971 -0.0426553 0.0422984 0.0675971 -0.0679775 0.0437978 0.0675971 -0.0723153 0.0441656 0.0675971 -0.0699278 0.0430538 0.0675971 -0.0653853 0.0442791 0.0675971 -0.064713 0.0446076 0.0675971 -0.0582197 0.0467263 0.0675971 -0.0653279 0.0476163 0.0675971 -0.0674952 0.0478357 0.0675971 -0.06971 0.034609 0.0675971 -0.0721966 0.0352813 0.0675971 -0.0734219 0.0345259 0.0675971 -0.0760141 0.0370708 0.0675971 -0.0759838 0.0420365 0.0675971 -0.0601025 0.0387898 0.0675971 -0.0706997 0.0299634 0.0675971 -0.0739042 0.031103 0.0675971 -0.0718571 0.0340862 0.0675971 -0.0649426 0.0322146 0.0675971 -0.0714006 0.0255008 0.0675971 -0.0806075 0.0189456 0.0675971 -0.0774202 0.0071827 0.0675971 -0.0789095 0.000962376 0.0675971 -0.0845407 0.00447704 0.0675971 -0.0833688 -0.0114731 0.0675971 -0.0837648 -0.00205191 0.0675971 -0.0733177 0.00478831 0.0675971 -0.0781134 0.00598782 0.0675971 -0.0781845 -0.0497677 0.0675971 -0.0671845 -0.0462379 0.0675971 -0.070786 -0.0504096 0.0675971 -0.0645619 -0.0561394 0.0675971 -0.0632228 -0.0484593 0.0675971 -0.0626948 -0.047062 0.0675971 -0.0627252 -0.0425192 0.0675971 -0.0597686 -0.0205261 0.0675971 -0.0704171 -0.0236596 0.0675971 -0.0811698 -0.0353323 0.0675971 -0.076812 -0.0660841 0.0675971 -0.0527429 -0.0692943 0.0675971 -0.0467891 -0.0720968 0.0675971 -0.0441711 -0.0600619 0.0675971 -0.0421074 -0.0648464 0.0675971 -0.0438963 -0.0646487 0.0675971 -0.0450816 -0.0565413 0.0675971 -0.0467277 -0.0649849 0.0675971 -0.0462352 -0.0575807 0.0675971 -0.0551196 -0.0657883 0.0675971 -0.0471287 -0.0668999 0.0675971 -0.0475851 -0.0692112 0.0675971 -0.0429716 -0.0679859 0.0675971 -0.0422993 -0.0655387 0.0675971 -0.0429142 -0.0722274 0.0675971 -0.0439574 -0.0707081 0.0675971 -0.0387908 -0.0758 0.0675971 -0.0374631 -0.0759395 0.0675971 -0.0307093 -0.0733169 0.0675971 -0.0300674 -0.0636481 0.0675971 -0.0364617 -0.0714497 0.0675971 -0.0320177 -0.0714801 0.0675971 -0.033415 -0.0722051 0.0675971 -0.0346099 -0.0721769 0.0675971 -0.013088 -0.0774287 0.0675971 -0.0189465 -0.0827239 0.0675971 -0.0174957 -0.0789179 0.0675971 -0.00718362 -0.0840688 0.0675971 -0.00904695 -0.0827354 0.0675971 -0.00710054 -0.0833773 0.0675971 -0.00447796 -0.0826523 0.0675971 -0.00328307 -0.0832287 0.0675971 0.00196066 -0.0845361 0.0675971 -0.00176791 -0.0844862 0.0675971 0.00340574 -0.0738382 0.0675971 0.00136045 -0.0554233 0.0705971 -0.00300098 0.0554139 0.0805971 0.00300848 0.055355 0.0705971 0.00394853 0.0550158 0.0805971 -0.00727603 0.0551434 0.0805971 -0.00623623 0.055355 0.0815971 0.00394853 0.0550158 0.0815971 -0.00727603 0.0524241 0.0815971 -0.0182026 0.047686 0.0805971 -0.0283837 0.0409954 0.0815971 -0.0374027 -0.0551528 0.0805971 0.00624372 -0.0540064 0.0815971 0.0128125 -0.0503226 0.0815971 0.0234208 -0.0503226 0.0805971 0.0234208 -0.0445788 0.0815971 0.0330704 -0.0546812 0.0815971 -0.00952143 -0.0516445 0.0815971 -0.0203328 -0.0546812 0.0705971 -0.00952143 -0.0464938 0.0815971 -0.0303115 -0.0516445 0.0705971 -0.0203328 -0.0464938 0.0705971 -0.0303115 -0.0307712 0.0705971 -0.0461879 0.0122776 0.0815971 -0.0541201 0.0229212 0.0815971 -0.0505398 0.0229212 0.0705971 -0.0505398 0.0326263 0.0815971 -0.0448902 0.0534277 0.0815971 0.0150116 0.0534277 0.0705971 0.0150116 0.0493129 0.0705971 0.0254602 0.043179 0.0815971 0.0348667 0.0259309 0.0815971 0.049071 0.0259309 0.0705971 0.049071 -0.0067483 0.0705971 0.0550925 -0.0176996 0.0815971 0.0526074 -0.0176996 0.0705971 0.0526074 -0.0279264 0.0815971 0.0479686 -0.0663592 0.0692971 0.0530469 -0.0658965 0.0679971 0.0536206 -0.0648401 0.0692971 0.0548934 -0.0648401 0.0717971 0.0548934 -0.0420436 0.0717971 0.0738227 -0.0480713 0.0679971 0.0700473 -0.0520216 0.0717971 0.0671658 -0.034584 0.0679971 0.0775974 -0.0372555 0.0679971 0.0763508 -0.039684 0.0692971 0.0751174 -0.0462321 0.0679971 0.0712746 -0.000976285 0.0679971 0.0849482 -0.00906667 0.0679971 0.084469 -0.000976285 0.0692971 0.0849482 -0.0114717 0.0692971 0.0841763 -0.0134495 0.0717971 0.0838831 -0.0134495 0.0679971 0.0838831 -0.0220942 0.0679971 0.0820315 -0.0202008 0.0717971 0.0825181 0.0237621 0.0679971 0.0815613 0.0237621 0.0717971 0.0815613 0.0173276 0.0679971 0.0831668 0.0729424 0.0705971 0.000661341 0.0719086 0.0679971 0.0122588 0.0719086 0.0705971 0.0122588 0.0690429 0.0705971 0.023544 0.0644181 0.0705971 0.0342295 0.0581523 0.0705971 0.0440432 0.0581523 0.0679971 0.0440432 0.0504049 0.0705971 0.0527349 0.0312877 0.0705971 0.0659013 0.0413733 0.0679971 0.0600834 -0.0619906 0.0741971 0.0366335 -0.0554772 0.0812971 0.0459036 -0.0456255 0.0741971 0.0557059 -0.0374682 0.0812971 0.0614894 -0.0385549 0.0741971 0.060814 -0.0371356 0.0741971 0.0616908 -0.0309184 0.0741971 0.0650294 -0.0153598 0.0812971 0.0703473 -0.0228282 0.0741971 0.0682905 -0.0267828 0.0812971 0.0668389 -0.0057665 0.0741971 0.0717728 0.0201391 0.0812971 0.0691285 0.00842877 0.0812971 0.0715081 -0.058631 0.0830971 0.00512951 -0.0370531 0.0821732 0.0465202 -0.030374 0.0821732 0.0511317 -0.0302083 0.08239 0.0508527 0.0166328 0.0821732 0.0570963 -0.0597543 0.0820971 -0.00346074 -0.0593723 0.0821732 -0.00343859 -0.0485395 0.0820971 0.0350236 -0.0522987 0.0822737 0.0279277 -0.0553207 0.0827144 0.020312 -0.0531958 0.0826389 0.0254421 -0.0529592 0.0826115 0.0259645 -0.0527411 0.0825377 0.0265058 -0.0522316 0.08239 0.0277568 -0.0523487 0.0823097 0.0277293 -0.0575708 0.0827144 0.0125906 -0.0566112 0.0826389 0.0164995 -0.0589235 0.0823893 0.00515484 -0.0588696 0.0824272 0.00535361 -0.0587485 0.0827144 0.00463483 -0.0585345 0.0826389 0.00712216 -0.0593385 0.0821743 0.00394571 -0.0372915 0.0820971 0.0468195 -0.0580323 0.08239 -0.0114277 -0.0583506 0.0821732 -0.0114904 -0.056242 0.0821732 -0.0193281 -0.0230031 0.08239 0.0544919 -0.0231292 0.0821732 0.0547908 -0.0232781 0.0820971 0.0551433 -0.0376645 0.0827144 -0.0453176 -0.0378031 0.08239 -0.0454843 -0.0526028 0.0827144 -0.0265617 -0.0438844 0.0821732 -0.0401327 -0.0486739 0.08239 -0.0335996 -0.0527963 0.08239 -0.0266595 -0.0561299 0.0830971 -0.017696 -0.0367159 0.0827144 0.0460968 -0.036851 0.08239 0.0462664 -0.0428072 0.08239 0.0408183 -0.0242612 0.0821732 -0.0542916 -0.0166421 0.0821732 -0.0570888 -0.0164694 0.0830971 -0.0564961 -0.0314285 0.0821732 -0.0504829 -0.0312571 0.08239 -0.0502075 -0.0241289 0.08239 -0.0539954 -0.0240405 0.0827144 -0.0537974 -0.0271756 0.0830971 -0.0521984 -0.0376159 0.0830971 -0.045259 -0.0368376 0.0830971 -0.0458946 -0.0311425 0.0827144 -0.0500235 -0.0311023 0.0830971 -0.0499588 -0.0380104 0.0821732 -0.0457338 -0.043645 0.08239 -0.0399137 -0.0484956 0.0827144 -0.0334764 -0.043485 0.0827144 -0.0397674 -0.0525348 0.0830971 -0.0265274 -0.0484329 0.0830971 -0.0334332 -0.0489409 0.0821732 -0.0337839 -0.0530859 0.0821732 -0.0268057 -0.0559352 0.08239 -0.0192227 -0.0557302 0.0827144 -0.0191522 -0.0578196 0.0827144 -0.0113858 -0.0577449 0.0830971 -0.0113711 -0.058832 0.0827144 -0.00340726 -0.0590484 0.08239 -0.00341981 -0.0589646 0.08239 0.00465186 -0.0565045 0.0830971 0.0164685 -0.0522068 0.0830971 0.0271747 -0.051973 0.0830971 0.0276193 -0.0521799 0.0821838 0.0284848 -0.0477903 0.0827144 0.034483 -0.0520402 0.0827144 0.027655 -0.0477286 0.0830971 0.0344385 -0.0482292 0.0821732 0.0347997 -0.0479661 0.08239 0.0346098 -0.0300588 0.0830971 0.0506009 -0.0366685 0.0830971 0.0460373 -0.0426503 0.0827144 0.0406687 -0.0425952 0.0830971 0.0406161 -0.045903 0.0830971 0.0368367 -0.0433189 0.0820971 0.0413062 -0.043042 0.0821732 0.0410421 -0.0300976 0.0827144 0.0506664 -0.0228892 0.0830971 0.054222 -0.0177044 0.0830971 0.056129 -0.0154537 0.0821732 0.0574293 -0.0229188 0.0827144 0.0542921 -0.00749037 0.0821732 0.058998 -0.00744953 0.08239 0.0586762 -0.0153694 0.08239 0.057116 -0.0153131 0.0827144 0.0569066 0.00060904 0.08239 0.0591435 -0.00742224 0.0827144 0.0584611 0.000606001 0.0830971 0.0588506 -0.00641483 0.0830971 0.0585036 0.000612407 0.0821732 0.0594679 0.00870369 0.0821732 0.05883 0.00865618 0.08239 0.0585091 0.00862444 0.0827144 0.0582946 0.000606791 0.0827144 0.0589267 0.0051211 0.0830971 0.0586301 0.016542 0.08239 0.0567848 0.01646 0.0830971 0.0565036 0.0661582 0.0725971 0.0322441 0.0689422 0.0727189 0.0239523 0.0656078 0.0727189 0.0319758 0.0566813 0.0725971 0.0469469 0.0562097 0.0727189 0.0465564 0.0436363 0.0727189 0.0585073 0.0359432 0.0735848 0.0625281 0.0361161 0.0730657 0.0628288 0.0285978 0.0727189 0.0671536 0.0288377 0.0725971 0.0677169 0.0363748 0.0727189 0.0632788 0.0282585 0.0735848 0.066357 0.0613434 0.0727189 0.0395463 0.0651411 0.0730657 0.0317485 0.0687649 0.0728114 0.0238907 0.0648293 0.0735848 0.0315965 0.0282107 0.0741971 0.0662449 0.0358825 0.0741971 0.0624226 0.0308179 0.0741971 0.0650727 0.0283944 0.0730657 0.0666761 0.043326 0.0730657 0.0580913 0.0431186 0.0735848 0.0578133 0.0502793 0.0727189 0.0529067 0.0496828 0.0735848 0.0522791 0.0495989 0.0741971 0.0521908 0.0558099 0.0730657 0.0462253 0.0555428 0.0735848 0.0460041 0.0499217 0.0730657 0.0525305 0.0609072 0.0730657 0.0392651 0.0647199 0.0741971 0.0315432 0.0606156 0.0735848 0.0390772 0.0634169 0.0741971 0.0340876 -0.0619716 0.0813494 0.0365628 -0.0619906 0.0812971 0.0366335 -0.0612275 0.0820971 0.0363521 -0.0471216 0.0812971 0.0544463 -0.0465981 0.0820971 0.0538414 -0.0370519 0.0820971 0.0608062 -0.0264852 0.0820971 0.0660963 -0.0151892 0.0820971 0.0695657 -0.00351384 0.0812971 0.0719182 0.00833506 0.0820971 0.0707136 0.0121697 0.0717971 0.0840769 0.01646 0.0935971 0.0565036 0.0368283 0.0830971 0.0459021 0.031093 0.0830971 0.0499663 0.0271663 0.0935971 0.0522059 0.0240001 0.0830971 0.0537354 0.0376066 0.0830971 0.0452665 0.0368283 0.0935971 0.0459021 0.0515891 0.0935971 0.0283129 0.0556489 0.0830971 0.0191349 0.0561206 0.0935971 0.0177035 0.0577356 0.0830971 0.0113786 0.0552399 0.0830971 -0.0202783 0.0521975 0.0935971 -0.0271672 0.0564952 0.0935971 -0.016461 0.0564952 0.0830971 -0.016461 0.0519636 0.0830971 -0.0276118 0.037826 0.0935971 -0.0450758 0.0425859 0.0830971 -0.0406086 0.0458936 0.0935971 -0.0368292 0.0366592 0.0830971 -0.0460298 0.0283045 0.0935971 -0.05159 0.0283045 0.0830971 -0.05159 0.0228799 0.0830971 -0.0542145 0.00640549 0.0935971 -0.0584961 -0.000615335 0.0830971 -0.0588431 -0.00862262 0.0830971 -0.0582118 -0.0164694 0.0935971 -0.0564961 -0.0240094 0.0830971 -0.0537279 -0.0368376 0.0935971 -0.0458946 -0.0434289 0.0830971 -0.039716 -0.0450842 0.0830971 -0.0378269 -0.0450842 0.0935971 -0.0378269 -0.0556582 0.0830971 -0.0191274 -0.0515984 0.0935971 -0.0283054 -0.0515984 0.0830971 -0.0283054 -0.058756 0.0830971 -0.00340286 -0.058631 0.0935971 0.00512951 -0.0585045 0.0935971 -0.00640641 -0.0585045 0.0830971 -0.00640641 -0.0586726 0.0830971 0.00462884 -0.0574964 0.0830971 0.0125744 -0.0552492 0.0830971 0.0202858 -0.0565045 0.0935971 0.0164685 -0.045903 0.0935971 0.0368367 -0.0378353 0.0935971 0.0450833 -0.0378353 0.0830971 0.0450833 -0.0283138 0.0830971 0.0515975 -0.0177044 0.0935971 0.056129 -0.00741266 0.0830971 0.0583856 -0.0152933 0.0830971 0.0568331 -0.00641483 0.0935971 0.0585036 0.0051211 0.0935971 0.0586301 0.00861329 0.0830971 0.0582193 0.0468645 0.0741971 -0.0564289 0.0690049 0.0741971 0.0225625 0.0681242 0.0735848 0.0236682 0.0686171 0.0733971 0.0230695 0.0682117 0.0733971 0.0236985 0.0684519 0.0730657 0.023782 0.0690206 0.0728114 0.023494 0.0695718 0.0725971 0.0240738 0.0694298 0.0728114 0.0232587 0.0467362 0.0733971 -0.0566006 0.0460674 0.0728114 -0.0569111 0.0466286 0.0728114 -0.0573302 0.0463859 0.0728114 -0.0570699 0.0459558 0.0725971 -0.057763 0.0699024 0.0820971 0.021626 0.069206 0.0812971 0.0224907 0.0697364 0.0812971 0.022419 0.0744251 0.0720971 0.027179 0.0764839 0.0725971 0.0271772 0.0734687 0.0720971 0.0271993 0.074458 0.0725971 0.0266801 0.0508487 0.0725971 0.0601524 0.0676905 0.0720971 0.0394409 0.079237 0.0720971 -3.95176e-05 0.0793353 0.0677971 0.00728416 0.0792201 0.0675971 0.00744763 0.0785914 0.0677971 0.00645683 0.0782801 0.0677971 0.00538866 0.0780805 0.0675971 0.00540048 0.0784631 0.0677971 0.00429121 0.0791042 0.0677971 0.00338184 0.0782781 0.0675971 0.00421524 0.0784631 0.0693971 0.00429121 0.0783474 0.0693971 0.00464649 0.0783756 0.0693971 0.00594028 0.0803645 0.0677971 0.00770679 0.0815311 0.0695971 0.00783302 0.0801814 0.0693971 0.00766917 0.0789085 0.0695971 0.00719112 0.0793353 0.0693971 0.00728416 0.0790469 0.0693971 0.00704666 0.0785914 0.0693971 0.00645683 0.0781836 0.0695971 0.00599623 0.0789699 0.0693971 0.00351196 0.0788255 0.0695971 0.00337365 0.0781532 0.0695971 0.00459894 0.0782801 0.0693971 0.00538866 0.073421 0.0675971 0.0352897 0.0734686 0.0677971 0.0350954 0.0721957 0.0675971 0.0346174 0.0714403 0.0675971 0.0320252 0.0716346 0.0677971 0.0320727 0.0733635 0.0677971 0.0302669 0.0722571 0.0677971 0.0309382 0.0733635 0.0693971 0.0302669 0.0716346 0.0693971 0.0320727 0.0716628 0.0677971 0.0333665 0.072334 0.0677971 0.0344729 0.072334 0.0693971 0.0344729 0.0734686 0.0693971 0.0350954 0.0747624 0.0693971 0.0350673 0.0733075 0.0695971 0.0300749 0.0722571 0.0693971 0.0309382 0.0721126 0.0695971 0.0307999 0.0716628 0.0693971 0.0333665 0.0714403 0.0695971 0.0320252 0.073421 0.0695971 0.0352897 0.0649756 0.0675971 0.0462427 0.0648391 0.0677971 0.0450772 0.0650221 0.0677971 0.0439798 0.0656631 0.0677971 0.0430704 0.0655294 0.0675971 0.0429217 0.0666352 0.0693971 0.0425292 0.0655289 0.0693971 0.0432005 0.0650221 0.0693971 0.0439798 0.0649345 0.0693971 0.0456288 0.0651503 0.0677971 0.0461454 0.0658942 0.0677971 0.0469727 0.0669235 0.0677971 0.0473954 0.0667403 0.0693971 0.0473577 0.0680341 0.0693971 0.0473296 0.0658942 0.0693971 0.0469727 0.0656058 0.0693971 0.0467352 0.0654675 0.0695971 0.0468797 0.0651503 0.0693971 0.0461454 0.0647425 0.0695971 0.0456848 0.0648391 0.0693971 0.0450772 0.0653844 0.0695971 0.0430622 0.0649064 0.0693971 0.0443351 0.0647121 0.0695971 0.0442875 0.0472137 0.0677971 0.0677532 0.0485635 0.0675971 0.067917 0.0471662 0.0675971 0.0679474 0.0460792 0.0677971 0.0671306 0.0451855 0.0675971 0.0646829 0.0471086 0.0677971 0.0629247 0.0460023 0.0677971 0.063596 0.0460023 0.0693971 0.063596 0.0453798 0.0677971 0.0647305 0.0453798 0.0693971 0.0647305 0.0454079 0.0677971 0.0660243 0.0485075 0.0693971 0.067725 0.0458578 0.0695971 0.0634576 0.0451855 0.0695971 0.0646829 0.0454079 0.0693971 0.0660243 0.0460792 0.0693971 0.0671306 0.0459409 0.0695971 0.0672751 0.0472137 0.0693971 0.0677532 -0.046609 0.0725971 0.0615827 -0.0438108 0.0720971 0.0619582 -0.043709 0.0725971 0.0614687 -0.0399392 0.0725971 0.070673 -0.0410948 0.0725971 0.0627291 0.000745669 0.0725971 0.0811723 -0.00180058 0.0720971 0.0764937 -0.00416949 0.0720971 0.0753897 -0.00407201 0.0725971 0.0748993 -0.00678052 0.0720971 0.0755038 -0.0276356 0.0720971 0.0762906 -0.0271781 0.0725971 0.0764923 -0.029453 0.0720971 0.0696089 -0.0273812 0.0725971 0.0712342 -0.0604306 0.0720971 0.050324 -0.0617819 0.0725971 0.0526581 -0.0603919 0.0720971 0.0453861 -0.0617064 0.0725971 0.0430311 -0.0643303 0.0720971 0.0424073 -0.0642398 0.0725971 0.0419156 -0.0670044 0.0725971 0.0420561 -0.0659201 0.0677971 0.0502448 -0.0659677 0.0675971 0.0504391 -0.0679179 0.0675971 0.0485719 -0.0671316 0.0677971 0.0460876 -0.0660252 0.0677971 0.0454163 -0.0677541 0.0677971 0.0472221 -0.0677259 0.0677971 0.0485159 -0.0670546 0.0677971 0.0496223 -0.0670546 0.0693971 0.0496223 -0.067276 0.0695971 0.0459493 -0.0671316 0.0693971 0.0460876 -0.0677541 0.0693971 0.0472221 -0.0677259 0.0693971 0.0485159 -0.0679179 0.0695971 0.0485719 -0.0659201 0.0693971 0.0502448 -0.0467975 0.0675971 0.0692934 -0.0475225 0.0675971 0.0680985 -0.0473587 0.0677971 0.0667487 -0.0475529 0.0675971 0.0667012 -0.0467361 0.0677971 0.0656142 -0.0456298 0.0677971 0.0649429 -0.0473587 0.0693971 0.0667487 -0.0473305 0.0677971 0.0680425 -0.0473305 0.0693971 0.0680425 -0.0466592 0.0677971 0.0691489 -0.0466592 0.0693971 0.0691489 -0.0455247 0.0677971 0.0697714 -0.0455247 0.0693971 0.0697714 -0.0442309 0.0677971 0.0697433 -0.0442309 0.0693971 0.0697433 -0.0467361 0.0693971 0.0656142 -0.0468806 0.0695971 0.0654759 -0.0475529 0.0695971 0.0667012 -0.0475225 0.0695971 0.0680985 -0.0319686 0.0677971 0.0764715 -0.0332624 0.0677971 0.0764997 -0.0319126 0.0675971 0.0766635 -0.0333099 0.0675971 0.0766939 -0.0345352 0.0675971 0.0760216 -0.0352906 0.0675971 0.0734294 -0.0346183 0.0675971 0.0722041 -0.0334234 0.0675971 0.0714792 -0.0333675 0.0677971 0.0716712 -0.0344738 0.0677971 0.0723425 -0.0350963 0.0677971 0.073477 -0.0350682 0.0677971 0.0747708 -0.0350682 0.0693971 0.0747708 -0.0343969 0.0693971 0.0758772 -0.0343969 0.0677971 0.0758772 -0.0332624 0.0693971 0.0764997 -0.0344738 0.0693971 0.0723425 -0.0350963 0.0693971 0.073477 -0.0346183 0.0695971 0.0722041 -0.0352906 0.0695971 0.0734294 -0.0345352 0.0695971 0.0760216 -0.0333099 0.0695971 0.0766939 -0.00454233 0.0677971 0.0831843 -0.00583612 0.0677971 0.0832125 -0.00588366 0.0675971 0.0834068 -0.00697065 0.0677971 0.08259 -0.00764193 0.0677971 0.0814836 -0.00783394 0.0675971 0.0815396 -0.00786435 0.0675971 0.0801423 -0.00719204 0.0675971 0.078917 -0.00704757 0.0677971 0.0790553 -0.00767008 0.0677971 0.0801898 -0.00767008 0.0693971 0.0801898 -0.00764193 0.0693971 0.0814836 -0.00697065 0.0693971 0.08259 -0.00583612 0.0693971 0.0832125 -0.00454233 0.0693971 0.0831843 -0.00719204 0.0695971 0.078917 -0.00704757 0.0693971 0.0790553 -0.00783394 0.0695971 0.0815396 -0.00588366 0.0695971 0.0834068 0.0668552 0.0695971 -0.0425286 0.0101305 0.0695971 -0.0782748 0.00873787 0.0695971 -0.0765385 0.00980768 0.0720971 -0.0777243 0.00677119 0.0695971 -0.0754963 0.0481746 0.0695971 -0.0629012 0.0362833 0.0695971 -0.0699271 0.0362298 0.0720971 -0.0698809 0.0660159 0.0677971 -0.0454088 0.063876 0.0677971 -0.0457657 0.0631321 0.0677971 -0.046593 0.0637607 0.0675971 -0.0456022 0.0630038 0.0677971 -0.0487586 0.0635111 0.0675971 -0.0498167 0.064617 0.0677971 -0.0502092 0.064617 0.0693971 -0.0502092 0.0636449 0.0677971 -0.049668 0.0628208 0.0693971 -0.0476612 0.0628208 0.0677971 -0.0476612 0.0631321 0.0693971 -0.046593 0.0649052 0.0677971 -0.045343 0.063876 0.0693971 -0.0457657 0.064561 0.0695971 -0.0504012 0.0636449 0.0693971 -0.049668 0.0630038 0.0693971 -0.0487586 0.0649052 0.0693971 -0.045343 0.0648723 0.0695971 -0.0451458 0.0443266 0.0677971 -0.0649073 0.0423288 0.0675971 -0.0665802 0.0431152 0.0677971 -0.0690645 0.0429707 0.0675971 -0.0692028 0.0442216 0.0693971 -0.0697358 0.0442216 0.0677971 -0.0697358 0.0432494 0.0693971 -0.0691946 0.0426084 0.0693971 -0.0682852 0.0424927 0.0693971 -0.0679299 0.0424927 0.0677971 -0.0679299 0.0425208 0.0693971 -0.0666362 0.0425208 0.0677971 -0.0666362 0.0427366 0.0693971 -0.0661196 0.0431921 0.0677971 -0.0655298 0.0431921 0.0693971 -0.0655298 0.0434806 0.0693971 -0.0652923 0.0456204 0.0693971 -0.0649354 0.0445098 0.0693971 -0.0648696 0.0456764 0.0695971 -0.0647434 0.0444769 0.0695971 -0.0646724 0.0443266 0.0693971 -0.0649073 0.0425619 0.0695971 -0.0660223 0.0422257 0.0695971 -0.067176 0.0424234 0.0695971 -0.0683612 0.0424254 0.0693971 -0.0671878 0.0441656 0.0695971 -0.0699278 0.0431152 0.0693971 -0.0690645 0.0319033 0.0675971 -0.076656 0.0308534 0.0675971 -0.0760716 0.0301611 0.0675971 -0.0750894 0.0302585 0.0677971 -0.0733644 0.0302996 0.0675971 -0.0727506 0.0312183 0.0677971 -0.0720205 0.0333581 0.0677971 -0.0716637 0.0309871 0.0677971 -0.0759228 0.0309871 0.0693971 -0.0759228 0.0308529 0.0677971 -0.0757927 0.0308529 0.0693971 -0.0757927 0.0303461 0.0677971 -0.0750135 0.0302304 0.0677971 -0.0746582 0.0301631 0.0677971 -0.073916 0.0302304 0.0693971 -0.0746582 0.0301631 0.0693971 -0.073916 0.0302585 0.0693971 -0.0733644 0.0304743 0.0677971 -0.0728479 0.0304743 0.0693971 -0.0728479 0.0309298 0.0677971 -0.072258 0.0309298 0.0693971 -0.072258 0.0312183 0.0693971 -0.0720205 0.0320643 0.0677971 -0.0716355 0.0322475 0.0677971 -0.0715979 0.0333581 0.0693971 -0.0716637 0.0322475 0.0693971 -0.0715979 0.0320643 0.0693971 -0.0716355 0.031103 0.0695971 -0.0718571 0.0319593 0.0693971 -0.076464 0.0319033 0.0695971 -0.076656 0.0303461 0.0693971 -0.0750135 0.00342662 0.0677971 -0.0825056 0.00342714 0.0675971 -0.0827844 0.00291981 0.0677971 -0.0817263 0.0027348 0.0675971 -0.0818023 0.00280411 0.0677971 -0.081371 0.00253715 0.0675971 -0.080617 0.0027368 0.0677971 -0.0806288 0.00287333 0.0675971 -0.0794634 0.00304808 0.0677971 -0.0795607 0.00350354 0.0677971 -0.0789709 0.00367676 0.0675971 -0.0785699 0.00463807 0.0677971 -0.0783483 0.00453299 0.0693971 -0.0831768 0.00342662 0.0693971 -0.0825056 0.00356087 0.0677971 -0.0826357 0.00280411 0.0693971 -0.081371 0.00283226 0.0693971 -0.0800772 0.00283226 0.0677971 -0.0800772 0.00350354 0.0693971 -0.0789709 0.00463807 0.0693971 -0.0783483 0.00379199 0.0677971 -0.0787333 0.00482121 0.0677971 -0.0783107 0.00447704 0.0695971 -0.0833688 0.00328215 0.0695971 -0.0826439 0.00336523 0.0695971 -0.0788264 -0.0433793 0.0695971 -0.0685659 -0.0423809 0.0695971 -0.0661506 -0.0436627 0.0720971 -0.0617134 -0.0440151 0.0720971 -0.0613434 -0.0687541 0.0720971 -0.0340622 -0.0686595 0.0695971 -0.0336355 -0.0686722 0.0720971 -0.0316158 -0.0688347 0.0720971 -0.0309809 -0.0688347 0.0695971 -0.0309809 -0.0702352 0.0695971 -0.0287191 -0.0715215 0.0720971 -0.0277869 -0.0625945 0.0695971 -0.0476953 -0.0618638 0.0720971 -0.0453881 -0.062235 0.0695971 -0.0428851 -0.0636456 0.0695971 -0.0408511 -0.0656701 0.0720971 -0.0396828 -0.0658052 0.0695971 -0.0396416 -0.0804293 0.0720971 -0.0107218 -0.075854 0.0720971 -0.00766943 -0.0761694 0.0695971 -0.00822424 -0.075318 0.0720971 -0.0058339 -0.0752966 0.0720971 -0.00487752 -0.0756302 0.0720971 -0.00331572 -0.0756302 0.0695971 -0.00331572 -0.0762098 0.0720971 -0.00218095 -0.0770397 0.0720971 -0.00120571 -0.0800297 0.0675971 -0.00264117 -0.081427 0.0675971 -0.00261076 -0.082514 0.0677971 -0.00342753 -0.0831852 0.0677971 -0.00453391 -0.0834077 0.0675971 -0.00587525 -0.0814845 0.0677971 -0.00763351 -0.0814845 0.0693971 -0.00763351 -0.0825909 0.0677971 -0.00696223 -0.0832134 0.0677971 -0.0058277 -0.0832134 0.0693971 -0.0058277 -0.0831852 0.0693971 -0.00453391 -0.082514 0.0693971 -0.00342753 -0.0813794 0.0677971 -0.00280502 -0.0825909 0.0693971 -0.00696223 -0.0827354 0.0695971 -0.00710054 -0.0813794 0.0693971 -0.00280502 -0.0733728 0.0677971 -0.0302594 -0.0758011 0.0677971 -0.0308538 -0.0747142 0.0675971 -0.030037 -0.0764724 0.0677971 -0.0319602 -0.0766644 0.0675971 -0.0319042 -0.0765006 0.0677971 -0.033254 -0.0766948 0.0675971 -0.0333015 -0.0760225 0.0675971 -0.0345268 -0.0758781 0.0677971 -0.0343885 -0.0748276 0.0675971 -0.0352518 -0.0747717 0.0693971 -0.0350598 -0.0758781 0.0693971 -0.0343885 -0.0765006 0.0693971 -0.033254 -0.0764724 0.0693971 -0.0319602 -0.0746666 0.0693971 -0.0302313 -0.0746666 0.0677971 -0.0302313 -0.0766644 0.0695971 -0.0319042 -0.0758011 0.0693971 -0.0308538 -0.0759395 0.0695971 -0.0307093 -0.0665886 0.0675971 -0.0423297 -0.0679384 0.0677971 -0.0424936 -0.0697442 0.0677971 -0.0442225 -0.0699362 0.0675971 -0.0441665 -0.0699666 0.0675971 -0.0455638 -0.0680994 0.0675971 -0.0475141 -0.0680434 0.0693971 -0.0473221 -0.0691498 0.0677971 -0.0466508 -0.0697723 0.0677971 -0.0455163 -0.0691498 0.0693971 -0.0466508 -0.0697723 0.0693971 -0.0455163 -0.0697442 0.0693971 -0.0442225 -0.0690729 0.0677971 -0.0431161 -0.0690729 0.0693971 -0.0431161 -0.0666446 0.0677971 -0.0425217 -0.0679384 0.0693971 -0.0424936 -0.0699666 0.0695971 -0.0455638 -0.0699362 0.0695971 -0.0441665 -0.0679859 0.0695971 -0.0422993 -0.0495463 0.0677971 -0.0635115 -0.0502176 0.0677971 -0.0646179 -0.0496846 0.0675971 -0.0633671 -0.05044 0.0675971 -0.0659592 -0.0496232 0.0677971 -0.0670462 -0.0502457 0.0677971 -0.0659117 -0.0502176 0.0693971 -0.0646179 -0.0484118 0.0677971 -0.062889 -0.0484118 0.0693971 -0.062889 -0.0485168 0.0693971 -0.0677175 -0.0496232 0.0693971 -0.0670462 -0.0497677 0.0695971 -0.0671845 -0.0502457 0.0693971 -0.0659117 -0.05044 0.0695971 -0.0659592 -0.0495463 0.0693971 -0.0635115 -0.047118 0.0693971 -0.0629172 -0.0769763 0.0710971 0.00420507 -0.0767633 0.0710923 0.00415786 -0.0769763 0.0679971 0.00420507 0.0649412 0.0679971 -0.03748 0.0611695 0.0679971 -0.0397383 0.0658699 0.0709171 -0.037488 0.0312877 0.0679971 0.0659013 0.0504049 0.0679971 0.0527349 0.0506813 0.0675971 0.0530241 0.0428777 0.0675971 0.0595128 0.0416002 0.0675971 0.0604128 0.0702358 0.0675971 0.0211343 0.0690429 0.0679971 0.023544 0.0694215 0.0675971 0.0236731 0.0647714 0.0675971 0.0344172 0.0644181 0.0679971 0.0342295 -0.0671836 0.0679971 0.0378096 -0.0667705 0.0679971 0.0376694 0.0729424 0.0679971 0.000661341 0.0737707 0.0675971 -0.00123245 -0.0772822 0.0679971 -0.0352763 -0.0781742 0.0679971 -0.0332531 -0.0778062 0.0675971 -0.0330965 -0.0648219 0.0675971 -0.0542864 -0.0627017 0.0679971 -0.0573163 -0.0530231 0.0679971 -0.0663706 -0.0237715 0.0679971 -0.0815538 -0.0300612 0.0679971 -0.0794513 -0.0420539 0.0679971 -0.0738093 0.00892013 0.0820971 0.0306299 0.00906001 0.0815971 0.0311099 0.000700284 0.0815971 0.0323961 -0.00758862 0.0820971 0.0309891 -0.0155903 0.0815971 0.0284088 -0.0277048 0.0815971 0.0168104 -0.032397 0.0815971 0.0007087 -0.03099 0.0820971 -0.0075802 -0.0279714 0.0820971 -0.0153414 -0.0284097 0.0815971 -0.0155819 -0.0230468 0.0820971 -0.0220568 -0.016552 0.0820971 -0.0272689 -0.00892946 0.0820971 -0.0306224 -0.00906935 0.0815971 -0.0311024 -0.0578338 0.0705971 -0.000221006 -0.0658676 0.0800971 0.00137654 -0.0684811 0.0799209 0.00189624 -0.0692631 0.0794024 0.00205176 -0.0696179 0.0789525 0.0021223 0.0579151 0.0800971 -0.0348539 0.0601839 0.0776971 -0.0357361 0.0486507 0.0705971 -0.0312518 0.0600091 0.078621 -0.0356681 0.0585784 0.0799923 -0.0351118 0.0597802 0.0790638 -0.0355791 -0.0658676 0.0819047 0.00137654 -0.0704675 0.0819047 0.00229126 -0.0562944 0.0800971 0.0342276 -0.04866 0.0800971 0.0312593 -0.0601091 0.0783447 0.0357108 -0.0579245 0.0800971 0.0348614 -0.0585877 0.0799923 0.0351193 0.0699611 0.0710971 -0.00218491 0.0683603 0.0799631 -0.00186658 0.0684717 0.0799209 -0.00188874 0.0699611 0.0776971 -0.00218491 0.0699076 0.0782026 -0.00217426 0.0696085 0.0789525 -0.0021148 -0.0562944 0.0819047 0.0342276 -0.0547975 0.0820971 0.0336456 0.0704582 0.0820971 -0.00228376 0.0658582 0.0819047 -0.00136904 0.0566266 0.0800971 0.000758182 0.0566266 0.0705971 0.000758182 0.0557686 0.0705971 0.0017477 0.0557752 0.0802903 0.00173554 0.0555256 0.0805175 0.00234447 0.0554139 0.0705971 0.00300848 0.0451242 0.0705971 -0.0323016 0.0455759 0.0805172 -0.0318008 0.0461006 0.0705971 -0.0314288 0.0473559 0.0705971 -0.0310551 0.0473559 0.0800971 -0.0310551 -0.0451335 0.0805971 0.0323091 -0.0461099 0.0705971 0.0314363 -0.0464653 0.0800971 0.0312673 -0.0473652 0.0705971 0.0310626 -0.04866 0.0705971 0.0312593 -0.0578338 0.0800971 -0.000221006 -0.0566359 0.0800971 -0.000750683 -0.0557779 0.0705971 -0.00174021 -0.0557845 0.0802903 -0.00172804 -0.0555349 0.0805175 -0.00233697 0.027268 0.0820971 -0.0165436 0.0309807 0.0820971 0.0075877 -0.0318971 0.0820971 0.000697821 0.027962 0.0820971 0.0153489 0.0230375 0.0820971 0.0220643 -0.0306308 0.0820971 0.00892854 -0.000698738 0.0820971 -0.0318887 0.0220559 0.0820971 -0.0230384 -0.0220653 0.0820971 0.0230459 0.0165426 0.0820971 0.0272764 -0.0272773 0.0820971 0.0165511 0.000689405 0.0820971 0.0318962 -0.0153498 0.0820971 0.0279705 -0.0365741 0.0820971 0.0142687 -0.0346721 0.0820971 0.00649806 -0.0328569 0.0820971 0.00749407 -0.0317378 0.0820971 0.0113343 0.0331182 0.0820971 -0.0102281 0.0341733 0.0820971 -0.00833255 0.0380139 0.0820971 -0.0110753 0.0292892 0.0820971 0.0255126 0.0284651 0.0820971 0.0275194 0.028234 0.0820971 0.0236171 0.0272048 0.0820971 0.0231945 0.0250647 0.0820971 0.0274662 0.0249878 0.0820971 0.0239315 0.0243652 0.0820971 0.0250661 0.00864607 0.0820971 0.037428 0.00856914 0.0820971 0.0338933 0.0121038 0.0820971 0.0338164 0.0110744 0.0820971 0.0380224 0.0121808 0.0820971 0.0373511 -0.0111375 0.0820971 0.0350904 -0.00642471 0.0820971 0.0353406 -0.0102653 0.0820971 0.0380834 -0.0092361 0.0820971 0.038506 -0.00823052 0.0820971 0.0336117 -0.028157 0.0820971 0.0269498 -0.0279739 0.0820971 0.0258523 -0.0260726 0.0820971 0.0292679 -0.0278457 0.0820971 0.028018 -0.0239324 0.0820971 0.0249962 -0.0263608 0.0820971 0.0244018 -0.0383536 0.0820971 -0.00976609 -0.0336126 0.0820971 -0.0082221 -0.0343121 0.0820971 -0.0106223 -0.0367404 0.0820971 -0.0112166 -0.0272141 0.0820971 -0.023187 -0.0292985 0.0820971 -0.0255051 -0.025074 0.0820971 -0.0274587 -0.0244027 0.0820971 -0.0263524 -0.0249971 0.0820971 -0.023924 -0.0284745 0.0820971 -0.0275119 -0.0125686 0.0820971 -0.0343987 -0.0107955 0.0820971 -0.0331487 -0.0086554 0.0820971 -0.0374205 -0.00798412 0.0820971 -0.0363141 -0.0126969 0.0820971 -0.0365643 -0.00968485 0.0820971 -0.0332145 0.00708665 0.0820971 -0.0342267 0.0112157 0.0820971 -0.036732 0.0112439 0.0820971 -0.0354382 0.0081161 0.0820971 -0.0384327 0.00822119 0.0820971 -0.0336042 0.00700973 0.0820971 -0.0377614 0.0280522 0.0820971 -0.0274939 0.0252408 0.0820971 -0.0243285 0.0242116 0.0820971 -0.0247512 0.0273809 0.0820971 -0.0286003 0.0239804 0.0820971 -0.0286535 0.0384318 0.0820971 0.00812452 0.0343027 0.0820971 0.0106298 0.0342258 0.0820971 0.00709507 0.0367311 0.0820971 0.0112241 0.036626 0.0820971 0.00639564 -0.0271756 0.0935971 -0.0521984 -0.00513043 0.0935971 -0.0586226 0.0176951 0.0935971 -0.0561215 0.0584952 0.0935971 0.00641391 0.0586217 0.0935971 -0.00512201 0.0450749 0.0935971 0.0378344 -4.66678e-06 0.0935971 3.74959e-06 -0.0283138 0.0935971 0.0515975 -0.0522068 0.0935971 0.0271747 -0.0561299 0.0935971 -0.017696 -0.0509201 0.00924613 -0.28356 -0.0501866 0.00672087 -0.282453 -0.0501866 0.0067115 -0.282453 -0.0495066 0.00149706 -0.281814 -0.051565 0.0114607 -0.284935 -0.0513485 0.0114886 -0.284905 -0.0510838 0.0104247 -0.284141 -0.0507878 0.00932193 -0.283454 -0.0510138 0.0116759 -0.284642 -0.0509476 0.0105166 -0.28401 -0.0503093 0.00682334 -0.282583 -0.050525 0.00841042 -0.282952 -0.0496723 0.00149706 -0.281898 -0.0506883 0.00669918 -0.282694 -0.0505546 0.006733 -0.282688 -0.0509372 0.0077163 -0.283035 -0.0510849 0.00918525 -0.283622 -0.0504246 0.00677545 -0.28265 -0.0495857 0.00149706 -0.281862 -0.0497864 0.00457999 -0.282037 -0.00410532 0.0189971 -0.0514005 -0.00369002 0.0189971 -0.0529505 -0.00255536 0.00899706 -0.0540852 -0.00255536 0.0189971 -0.0540852 -0.00100536 0.0189971 -0.0545005 0.000544641 0.00899706 -0.0540852 0.00167933 0.0189971 -0.0529506 0.00054471 0.00899706 -0.0487159 -0.00100529 0.0189971 -0.0483005 -0.00100529 0.00899706 -0.0483005 -0.00255529 0.0189971 -0.0487158 -0.00368998 0.0189971 -0.0498505 -0.00368998 0.00899706 -0.0498505 -0.00410532 0.00899706 -0.0514005 -0.0449581 0.00899707 -0.166171 -0.0478637 0.00467533 -0.204407 -0.0458283 0.00520267 -0.166128 -0.0462285 0.000291062 -0.166088 -0.038689 0.00899707 -0.103528 -0.0349283 0.00899706 -0.10224 -0.0332275 0.00899706 -0.100111 -0.0332275 0.000297063 -0.100111 -0.0326438 0.000297063 -0.0974495 -0.0332975 0.000297063 -0.0948041 -0.0400823 0.000297063 -0.0868427 -0.038013 0.000297063 -0.0493576 -0.038013 0.00899706 -0.0493576 -0.0400899 0.0118971 -0.0871174 -0.0400899 0.00899706 -0.0871174 -0.0397771 0.00899706 -0.0888589 -0.03846 0.00899706 -0.0908118 -0.0301883 0.0228931 -0.0967643 -0.030377 0.0232831 -0.0967754 -0.0302332 0.0230987 -0.0967732 -0.0310717 0.0222791 -0.111951 -0.0312174 0.0224643 -0.111953 -0.0305886 0.0233822 -0.0967692 -0.0314315 0.0225624 -0.111947 -0.0316431 0.0225578 -0.111935 -0.0307723 0.0230763 -0.0934619 -0.0327297 0.0228992 -0.0911113 -0.0310488 0.0234109 -0.0944087 -0.0303464 0.0231484 -0.0949467 -0.0315671 0.0226648 -0.091889 -0.0334883 0.0220017 -0.0899549 -0.0335223 0.0220952 -0.0899433 -0.0323624 0.022424 -0.0909193 -0.0324283 0.0226235 -0.0909147 -0.0335756 0.022201 -0.0899514 -0.0306993 0.0234321 -0.0950111 -0.0311111 0.0233592 -0.0935707 -0.0309113 0.0232603 -0.0935004 -0.0325615 0.0228025 -0.0909821 -0.0318032 0.023187 -0.0922543 -0.0307248 0.0228712 -0.0934615 -0.0304891 0.0233337 -0.0949728 -0.0314807 0.0229065 -0.0920971 -0.0316168 0.0230892 -0.0921517 -0.0324875 0.0227199 -0.0909389 -0.0333404 0.0227267 -0.0908273 -0.0320134 0.0219335 -0.115243 -0.0318851 0.0223682 -0.114116 -0.0315407 0.0220864 -0.114205 -0.0312223 0.0222019 -0.113097 -0.0321517 0.022115 -0.115201 -0.0320826 0.0223667 -0.114043 -0.0313669 0.0223861 -0.113083 -0.0316827 0.0222694 -0.114177 -0.0326902 0.0218357 -0.116178 -0.0326369 0.0217493 -0.116196 -0.0350633 0.0208723 -0.0880545 -0.0344606 0.0214184 -0.0890388 -0.035389 0.0200364 -0.0851707 -0.0354593 0.0202264 -0.0865923 -0.0354774 0.0203417 -0.0865597 -0.0360419 0.0205088 -0.0850848 -0.0360598 0.020698 -0.0865132 -0.0357811 0.0205102 -0.0858104 -0.0356434 0.0204236 -0.0858285 -0.0357594 0.0206606 -0.0864935 -0.0355458 0.0203045 -0.085849 -0.0354471 0.0202628 -0.0851816 -0.0354931 0.0201752 -0.0858687 -0.0356754 0.0212521 -0.087911 -0.035911 0.0207021 -0.0864967 -0.0353061 0.0211062 -0.0878261 -0.0356273 0.0205762 -0.0865051 -0.0355316 0.0204635 -0.0865289 -0.035364 0.0205983 -0.0872269 -0.0353402 0.0204894 -0.0872645 -0.0345501 0.0216169 -0.0890045 -0.0357879 0.0212357 -0.0879648 -0.0363122 0.020521 -0.0863235 -0.0361879 0.0206571 -0.0865386 -0.0359399 0.0205479 -0.0857978 -0.0358605 0.0205331 -0.0851243 -0.0358137 0.0205281 -0.0851333 -0.0351309 0.020792 -0.0878983 -0.0344947 0.0215159 -0.0890141 -0.0352174 0.0210045 -0.0878363 -0.0346264 0.0217124 -0.0890145 -0.0336307 0.0222833 -0.0899771 -0.0351596 0.0208959 -0.0878624 -0.0354206 0.0207126 -0.0871955 -0.0354036 0.021177 -0.087832 -0.0355487 0.0212374 -0.0878656 -0.0337008 0.0223625 -0.090026 -0.0338402 0.0224558 -0.0901645 -0.0337812 0.0215676 -0.119696 -0.0330597 0.0216307 -0.121445 -0.0332542 0.0217263 -0.121546 -0.0318272 0.0219123 -0.122846 -0.0302256 0.0223671 -0.123858 -0.0282908 0.0226086 -0.123833 -0.0335124 0.0211117 -0.11901 -0.0333744 0.021315 -0.117835 -0.0275113 0.0223932 -0.123527 -0.0265322 0.0226579 -0.12313 -0.0265253 0.0225694 -0.123117 -0.0300696 0.0219922 -0.123549 -0.0282639 0.0223474 -0.123687 -0.0282497 0.0222568 -0.123677 -0.0300505 0.0218986 -0.123545 -0.0334677 0.0211027 -0.119657 -0.0328836 0.0213393 -0.12138 -0.0330393 0.0211941 -0.121065 -0.0316868 0.0216327 -0.122742 -0.0324987 0.0213305 -0.121926 -0.0316159 0.0215473 -0.122783 -0.0306995 0.021758 -0.123315 -0.025103 0.0230573 -0.121996 -0.0264987 0.0229139 -0.123263 -0.0265307 0.0227484 -0.123158 -0.0301244 0.0221803 -0.123618 -0.0300944 0.0220883 -0.123573 -0.0317202 0.0217333 -0.122757 -0.0335158 0.021317 -0.119662 -0.0335808 0.0214202 -0.11967 -0.0334775 0.0215238 -0.117833 -0.0334126 0.0214222 -0.117838 -0.0334789 0.021208 -0.119658 -0.0329202 0.0214451 -0.121388 -0.0282762 0.0224401 -0.123716 -0.0251351 0.0229055 -0.12195 -0.0329341 0.0220151 -0.11604 -0.0335668 0.0216095 -0.11782 -0.0336733 0.0216705 -0.117799 -0.0336717 0.0215068 -0.119681 -0.0337867 0.0217026 -0.117774 -0.0338984 0.0215984 -0.119712 -0.0331933 0.0217734 -0.122029 -0.0319639 0.0220135 -0.122996 -0.0282884 0.0227178 -0.124006 -0.0291677 0.0225938 -0.124223 -0.0266794 0.0230117 -0.12374 -0.0325931 0.0216377 -0.116201 -0.0327655 0.0219187 -0.116142 -0.0329797 0.0215455 -0.121409 -0.0317677 0.0218293 -0.122792 -0.0301577 0.0222612 -0.123684 -0.0282854 0.0225293 -0.123765 -0.0264327 0.0230252 -0.123413 -0.0249823 0.0232374 -0.122117 -0.024803 0.0233144 -0.12227 -0.0326293 0.0243236 -0.0810416 -0.0325616 0.0242728 -0.0810571 -0.0302557 0.0266944 -0.0802421 -0.0324971 0.024218 -0.081059 -0.0301908 0.0266208 -0.0802632 -0.0303181 0.0267619 -0.0802019 -0.0353649 0.0210285 -0.083732 -0.0356037 0.0210042 -0.0836006 -0.036013 0.0205176 -0.0850916 -0.0361401 0.0204626 -0.0850601 -0.0347198 0.0220172 -0.0825417 -0.0338034 0.0231799 -0.0816591 -0.0341738 0.022913 -0.0817122 -0.0323375 0.0250229 -0.0806231 -0.0304056 0.0267949 -0.0801486 -0.0273219 0.0283775 -0.0805293 -0.0328741 0.0244485 -0.0808657 -0.0288747 0.0277228 -0.0802104 -0.0281304 0.0281341 -0.080317 -0.0302386 0.0264431 -0.0802803 -0.0323865 0.0241061 -0.0810257 -0.0343005 0.0218032 -0.0826419 -0.0355055 0.0206604 -0.084437 -0.0355999 0.0204397 -0.0851681 -0.0355626 0.0204099 -0.0851728 -0.0350981 0.0209093 -0.0837876 -0.0355068 0.0203526 -0.0851784 -0.0349956 0.0208091 -0.0837751 -0.0354065 0.0201592 -0.0851794 -0.0349261 0.0207015 -0.0837418 -0.0350429 0.0208611 -0.0837845 -0.0343942 0.0218823 -0.0826533 -0.0351599 0.0209516 -0.0837839 -0.0352264 0.0209864 -0.0837732 -0.0357019 0.0204967 -0.085153 -0.0289342 0.027821 -0.0801589 -0.0283888 0.0281116 -0.0802407 -0.0280587 0.0280725 -0.0803395 -0.0356563 0.0206991 -0.0843991 -0.0354951 0.0210324 -0.083671 -0.0346141 0.0219945 -0.0826008 -0.034502 0.0219485 -0.0826396 -0.0336304 0.0231013 -0.0817429 -0.034227 0.0217196 -0.0826095 -0.0324381 0.0241616 -0.0810479 -0.0251354 0.0228183 -0.121938 -0.022326 0.0236302 -0.120075 -0.0251216 0.0229945 -0.121973 -0.0238903 0.0231753 -0.120736 -0.0250523 0.023158 -0.12205 -0.0190639 0.0239154 -0.119328 -0.0207654 0.0236781 -0.119346 -0.0238378 0.0233413 -0.120831 -0.0223894 0.0235193 -0.119917 -0.0224224 0.0233508 -0.11981 -0.0207768 0.0235074 -0.119231 -0.0190455 0.0236336 -0.119033 0.0351986 0.0284801 -0.0774166 -0.0273229 0.0283445 -0.0805348 -0.0234138 0.0284976 -0.0817379 -0.0196183 0.0285421 -0.0827278 -0.0117518 0.028418 -0.0842311 -0.0117483 0.0285844 -0.0842028 -0.00377541 0.0286043 -0.0849325 0.00423027 0.0286146 -0.0849097 0.00423194 0.0284411 -0.0849407 0.0122012 0.0286213 -0.084134 0.0122058 0.0284465 -0.0841652 0.0200705 0.0284488 -0.082643 0.0277584 0.0284471 -0.080387 0.0351925 0.0285661 -0.0774027 -0.0190658 0.0239439 -0.119518 0.0188094 0.0239561 -0.119034 -0.000119338 0.0242933 -0.119153 -0.000119813 0.0244026 -0.119332 0.0188151 0.0241298 -0.119154 0.0188186 0.0242388 -0.119334 0.00113256 0.0244348 -0.119523 -0.000118587 0.0241199 -0.119034 -0.0190568 0.0238059 -0.119151 -0.0145197 0.024179 -0.11952 0.0436866 0.0242467 -0.0812231 0.040447 0.0266215 -0.0773534 0.0378614 0.0276933 -0.0768166 0.0427308 0.0256585 -0.078839 0.0437045 0.0243428 -0.0812466 0.0437498 0.0244516 -0.0812654 0.0351964 0.0285234 -0.0774113 0.0365168 0.0281463 -0.0769836 0.0402976 0.0263363 -0.0774029 0.0392388 0.0268339 -0.0770399 0.0378212 0.0276007 -0.0768505 0.0377798 0.0275007 -0.0768623 0.0440865 0.0247124 -0.0812395 0.0435751 0.0252701 -0.0796357 0.0379046 0.0277959 -0.0767464 0.0405376 0.0267272 -0.0772562 0.0404145 0.0268743 -0.0770495 0.0438078 0.0245362 -0.0812729 0.0433555 0.0250596 -0.0800153 0.0425781 0.0255543 -0.0789228 0.0432177 0.0248923 -0.0800276 0.0424551 0.0253957 -0.0789524 0.0415904 0.0260825 -0.0780207 0.0414857 0.0259332 -0.0780637 0.0403627 0.026483 -0.0774037 0.036724 0.0279771 -0.0769503 0.0351993 0.0284365 -0.0774183 0.0188195 0.0242651 -0.119526 0.0226961 0.0240363 -0.120636 0.0226543 0.0239158 -0.120191 0.0242416 0.0237542 -0.121414 0.0225732 0.0240254 -0.120347 0.0208215 0.023682 -0.119263 0.0227015 0.0237441 -0.120083 0.0255613 0.0232275 -0.122902 0.0243247 0.0234001 -0.121288 0.0234535 0.0234914 -0.120535 0.0208003 0.0240449 -0.119419 0.0208219 0.0238716 -0.119301 0.0243109 0.0235846 -0.121324 0.0433086 0.0241198 -0.0856751 0.0426208 0.0240664 -0.0861171 0.043694 0.023865 -0.0841439 0.0438378 0.024054 -0.084206 0.0435357 0.0240197 -0.0849031 0.0418878 0.0237465 -0.0864716 0.043002 0.0238375 -0.0854572 0.0433392 0.023617 -0.0848404 0.0436615 0.0237566 -0.0841251 0.0442957 0.0247182 -0.0811763 0.0443173 0.0243464 -0.0827514 0.0438921 0.0246174 -0.0812712 0.0440956 0.0242531 -0.0827321 0.0440073 0.0241685 -0.0827156 0.0439087 0.0239631 -0.0826766 0.0421543 0.0242318 -0.086763 0.0425073 0.0238801 -0.0860194 0.043128 0.0240256 -0.0855438 0.0433995 0.0238307 -0.0848285 0.0444625 0.0242083 -0.0835501 0.0442023 0.0243138 -0.0827443 0.0440514 0.024146 -0.0842845 0.0439405 0.0241148 -0.084245 0.0437534 0.0239677 -0.0841714 0.0439443 0.0240685 -0.0826965 0.0299731 0.0225832 -0.125244 0.0306242 0.0224975 -0.12515 0.0316714 0.022462 -0.124802 0.0343754 0.0229554 -0.118777 0.0349054 0.0227045 -0.121075 0.0343728 0.0226443 -0.122433 0.0333717 0.0226902 -0.124009 0.031862 0.0228448 -0.12511 0.0300547 0.0230568 -0.125589 0.0305942 0.0230156 -0.125716 0.0281447 0.0233115 -0.125557 0.0300286 0.0229503 -0.125403 0.0317676 0.022741 -0.124937 0.0332171 0.0225892 -0.123872 0.0347234 0.0227381 -0.120603 0.027109 0.0229738 -0.12452 0.0282505 0.0229079 -0.125057 0.0267043 0.023125 -0.124242 0.026702 0.023034 -0.124229 0.0281968 0.0232831 -0.125379 0.026639 0.0233873 -0.124369 0.0282373 0.0231744 -0.125206 0.0266952 0.0232181 -0.12427 0.0343437 0.0223523 -0.120569 0.0343187 0.0222197 -0.120929 0.0340256 0.0225757 -0.118856 0.0336328 0.0221608 -0.123025 0.0340052 0.022155 -0.122282 0.0315266 0.022381 -0.124858 0.0320419 0.022317 -0.124592 0.0325971 0.0222523 -0.124204 0.0330797 0.0223037 -0.123767 0.0330683 0.0222035 -0.123764 0.0344352 0.0225534 -0.120587 0.034377 0.0224553 -0.120578 0.0341005 0.0224599 -0.122323 0.0316942 0.0225622 -0.124826 0.033108 0.0224067 -0.123785 0.0340144 0.0222563 -0.122287 0.0340455 0.0223607 -0.1223 0.0253714 0.0236538 -0.123057 0.0265415 0.0234976 -0.12451 0.0254533 0.0235761 -0.123001 0.0255165 0.0234723 -0.122954 0.0255398 0.0234089 -0.122934 0.0292413 0.0226805 -0.125239 0.0282528 0.0230028 -0.125087 0.029985 0.0226781 -0.125252 0.0299988 0.0227754 -0.125281 0.0300136 0.0228685 -0.125332 0.0317268 0.0226579 -0.124871 0.0331544 0.0225049 -0.12382 0.0341775 0.0225449 -0.122354 0.0345167 0.0226376 -0.120594 0.0341158 0.0227702 -0.11885 0.0341893 0.022851 -0.118833 0.0410879 0.0243429 -0.0876683 0.0401983 0.0243841 -0.0887503 0.038772 0.0240383 -0.0912157 0.0391013 0.0243223 -0.0913013 0.0403728 0.0243836 -0.0888669 0.0420305 0.0241364 -0.0866034 0.0393417 0.0242716 -0.0898876 0.039215 0.0240886 -0.089829 0.0400232 0.0242842 -0.0886345 0.0399041 0.0241001 -0.088557 0.0409325 0.0242441 -0.0875232 0.0408229 0.0240595 -0.0874293 0.0419353 0.0239631 -0.0864993 0.0340775 0.0232209 -0.116618 0.0338751 0.0232097 -0.116633 0.0340227 0.0233586 -0.11444 0.0342225 0.023367 -0.114485 0.0338276 0.0232554 -0.114393 0.0336772 0.0231059 -0.116639 0.0340594 0.022674 -0.118857 0.0334775 0.0227773 -0.116009 0.0335438 0.0229266 -0.116633 0.0387325 0.0238368 -0.0911976 0.0386656 0.023823 -0.0915026 0.0385987 0.0238107 -0.0918077 0.0393025 0.0243284 -0.0913457 0.0389038 0.02422 -0.0912532 0.038966 0.0242958 -0.0919064 0.0387696 0.024193 -0.0918595 0.0361284 0.0233627 -0.103074 0.0336976 0.0230745 -0.114356 0.0386384 0.0240117 -0.091824 -0.0528175 0.0199971 -0.269452 -0.0511174 0.0235448 -0.270262 -0.0508332 0.0233693 -0.270505 -0.0504457 0.0233131 -0.270596 -0.0512909 0.0236588 -0.269904 -0.0473996 0.0285511 -0.279823 -0.0455537 0.0297815 -0.279186 -0.0441337 0.0303477 -0.277509 -0.0456383 0.0295683 -0.278967 -0.0435672 0.0304809 -0.275364 -0.0439914 0.0302058 -0.273192 -0.0441727 0.0299864 -0.273315 -0.0470161 0.0283188 -0.270387 -0.0488164 0.0267778 -0.270041 -0.0470012 0.0281297 -0.270691 -0.0440928 0.0296763 -0.27633 -0.0444121 0.0298514 -0.277292 -0.0456101 0.0290169 -0.278702 -0.0472301 0.0281527 -0.279557 -0.0465513 0.0284487 -0.279291 -0.0488194 0.0267285 -0.279715 -0.0456404 0.0291573 -0.278741 -0.0489389 0.0268585 -0.279757 -0.0442768 0.029713 -0.273418 -0.0447809 0.0291112 -0.27261 -0.045334 0.0287326 -0.271968 -0.0453682 0.0288721 -0.271919 -0.0468349 0.0277338 -0.270997 -0.0482038 0.0261054 -0.270719 -0.046906 0.0278723 -0.270922 -0.0483304 0.0262377 -0.270695 -0.0484533 0.0263682 -0.270636 -0.0439547 0.0296911 -0.275372 -0.0439114 0.0299811 -0.275366 -0.0440241 0.0296093 -0.27441 -0.044295 0.0294261 -0.273489 -0.0452664 0.0294889 -0.271439 -0.0433252 0.0305956 -0.274793 -0.0449705 0.0301046 -0.279039 -0.0469153 0.0291511 -0.28025 -0.0474376 0.028747 -0.280105 -0.0472982 0.0282915 -0.27962 -0.0456564 0.0292996 -0.278798 -0.0443095 0.0301263 -0.277386 -0.0437781 0.0302577 -0.275363 -0.0453644 0.0292801 -0.271668 -0.0453861 0.0290136 -0.271852 -0.0486801 0.0266166 -0.270396 -0.0525394 0.0199971 -0.279494 -0.0526711 0.0199974 -0.279495 -0.052905 0.0199984 -0.27954 -0.0531322 0.019998 -0.279643 -0.0534547 0.0199974 -0.279961 -0.052051 0.0239833 -0.280121 -0.0535086 0.0199975 -0.280057 -0.0493444 0.0272772 -0.280269 -0.0521423 0.0240252 -0.280474 -0.0491744 0.0271079 -0.279954 -0.0518367 0.0238685 -0.279807 -0.0515358 0.0236992 -0.279613 -0.0511731 0.0236147 -0.279569 -0.0486999 0.0265964 -0.279706 -0.0457866 0.0079972 -0.151207 -0.04552 0.00799706 -0.151824 -0.0443181 0.0119198 -0.151893 -0.0453111 0.00799712 -0.151995 -0.0440167 0.0117909 -0.152127 -0.0445089 0.0120058 -0.151549 -0.0421934 0.015621 -0.152015 -0.0419417 0.015411 -0.152242 -0.0429359 0.0152092 -0.16192 -0.0427413 0.0150712 -0.161578 -0.0410967 0.0168765 -0.161501 -0.0411616 0.0170562 -0.161808 -0.0393079 0.0181686 -0.160736 -0.0378867 0.0189333 -0.159209 -0.0377176 0.019153 -0.159359 -0.0370409 0.0194755 -0.15719 -0.0375923 0.0191477 -0.155034 -0.0405705 0.0175714 -0.152003 -0.0379874 0.0183677 -0.15901 -0.0375809 0.0185907 -0.158023 -0.0408657 0.0164969 -0.161207 -0.0400607 0.0170047 -0.160916 -0.0421641 0.0146294 -0.161309 -0.0379933 0.0185116 -0.159043 -0.0392756 0.0177581 -0.160475 -0.039304 0.0179006 -0.160542 -0.0424564 0.0148567 -0.161363 -0.0418068 0.0153013 -0.152299 -0.0403592 0.017013 -0.152579 -0.0381469 0.0183872 -0.154358 -0.0394557 0.0175772 -0.153048 -0.0402769 0.0168848 -0.152625 -0.0409922 0.0161147 -0.152412 -0.0388295 0.0181589 -0.153526 -0.0373846 0.0189751 -0.157143 -0.0374568 0.0186925 -0.156212 -0.0423528 0.0157625 -0.151678 -0.0423954 0.0158124 -0.151313 -0.0399919 0.0180667 -0.151921 -0.038718 0.0187762 -0.153086 -0.0374069 0.019369 -0.15493 -0.036877 0.0195705 -0.157888 -0.0392386 0.0183765 -0.160983 -0.0411456 0.0171429 -0.162136 -0.0424229 0.0159368 -0.162304 -0.0409555 0.0166298 -0.161276 -0.0379792 0.0186575 -0.159088 -0.0372518 0.0192523 -0.157165 -0.0388154 0.0185648 -0.153298 -0.0377029 0.0188734 -0.155116 -0.0388426 0.0182994 -0.153466 -0.040433 0.0171432 -0.152508 -0.0405386 0.0173868 -0.152291 -0.0440311 0.0114792 -0.161206 -0.0455946 0.00799707 -0.161188 -0.0458476 0.00799715 -0.161307 -0.0459602 0.00799706 -0.161392 -0.0449804 0.0117194 -0.161798 -0.0461683 0.00799708 -0.161642 -0.045061 0.0117456 -0.16217 -0.0430053 0.0152474 -0.162295 -0.0447562 0.0116298 -0.161463 -0.0423102 0.0147438 -0.161318 -0.0444278 0.0114918 -0.161253 -0.0408773 0.0167986 -0.0919347 -0.0417727 0.00915341 -0.0928489 -0.041648 0.0137669 -0.0925741 -0.0406477 0.0147936 -0.092911 -0.0413318 0.0136834 -0.0928075 -0.040636 0.0166659 -0.0926353 -0.0390277 0.0194227 -0.0924064 -0.0408234 0.0167635 -0.0922981 -0.040344 0.0165216 -0.0928632 -0.0418493 0.0138227 -0.0922305 -0.0390701 0.019481 -0.0920473 -0.0385352 0.0191821 -0.092958 -0.038647 0.0190376 -0.0929579 -0.0388792 0.0192665 -0.0927366 -0.0378353 0.019919 -0.0930303 -0.0358149 0.0218209 -0.0930911 -0.0388892 0.0195707 -0.0924102 -0.0380537 0.0204045 -0.0920877 -0.0376938 0.0206782 -0.0921707 -0.0357937 0.0210262 -0.0940457 -0.0356673 0.0214032 -0.0940897 -0.0364671 0.0205987 -0.0935897 -0.0371756 0.0209944 -0.0926923 -0.0387529 0.0194122 -0.0927358 -0.0371747 0.0207988 -0.0930035 -0.0370931 0.0205272 -0.0932373 -0.0340685 0.0223103 -0.100041 -0.0337777 0.0224335 -0.0982676 -0.0335083 0.0225699 -0.0983163 -0.033568 0.0226225 -0.0964926 -0.0338305 0.0224836 -0.0965486 -0.0347414 0.0218068 -0.0951964 -0.0342262 0.021676 -0.0966685 -0.0355328 0.0218919 -0.0937072 -0.0344672 0.0223093 -0.0949449 -0.0340489 0.0222583 -0.0965982 -0.0340018 0.0222083 -0.0982176 -0.035635 0.0216766 -0.0939233 -0.0346418 0.0220869 -0.0950873 -0.0346086 0.0216707 -0.0996292 -0.0344994 0.0219565 -0.0997467 -0.0367021 0.0205131 -0.101652 -0.0365965 0.0202208 -0.101536 -0.0355004 0.0208988 -0.100749 -0.0355093 0.0212118 -0.10083 -0.0346254 0.0213691 -0.099555 -0.0341424 0.0219223 -0.0981739 -0.0343925 0.0214945 -0.0990053 -0.0341866 0.0219742 -0.0966333 -0.0341767 0.0216811 -0.0969808 -0.0382193 0.0200486 -0.102947 -0.038226 0.019972 -0.102602 -0.0367467 0.0207879 -0.101868 -0.0367161 0.0209922 -0.102153 -0.0372086 0.0197674 -0.101794 -0.0379925 0.019533 -0.102049 -0.0354632 0.0214945 -0.101007 -0.0343078 0.0221792 -0.099892 -0.0353387 0.0217112 -0.101233 -0.0391777 0.0182594 -0.10208 -0.0381478 0.0197908 -0.102279 -0.039633 0.0186336 -0.102647 -0.0396963 0.0186711 -0.103024 -0.0425221 0.00799726 -0.101837 -0.0417104 0.0132585 -0.101935 -0.0429244 0.00799687 -0.101975 -0.0422885 0.0134157 -0.10248 -0.0394493 0.0184884 -0.102301 -0.0388913 0.0180096 -0.102022 -0.0413482 0.0161674 -0.102921 -0.0432643 0.00799737 -0.102315 -0.0412724 0.0161406 -0.102545 -0.0420544 0.0133539 -0.102144 -0.0410529 0.0160426 -0.102204 -0.0407287 0.0158901 -0.101991 0.0476835 0.00987773 -0.114088 0.0483409 0.00799884 -0.114337 0.0475932 0.0137193 -0.114367 0.0477327 0.0137742 -0.114749 0.0477182 0.013791 -0.115127 0.0487206 0.00799727 -0.115135 0.0486971 0.00799706 -0.115336 0.0464267 0.015446 -0.113812 0.0473158 0.0136355 -0.114077 0.0463955 0.0164595 -0.113875 0.044752 0.0189975 -0.113516 0.044943 0.0192413 -0.113792 0.0466542 0.0166003 -0.114163 0.0450232 0.0193989 -0.114167 0.0467804 0.0166921 -0.114544 0.0467601 0.0167195 -0.114923 0.0449867 0.0194438 -0.114546 0.0446372 0.0188695 -0.113437 0.0432294 0.0206938 -0.113192 0.0417439 0.0215816 -0.111898 0.0431657 0.0208955 -0.113496 0.0408902 0.0221024 -0.110073 0.0432075 0.0221092 -0.104594 0.0451958 0.0210453 -0.104268 0.0452688 0.0212476 -0.103988 0.0418558 0.0216821 -0.106325 0.0432774 0.0214507 -0.105057 0.0450031 0.0206268 -0.104508 0.0427326 0.0203772 -0.112563 0.0418359 0.0211323 -0.111664 0.0410685 0.0216514 -0.10996 0.0414384 0.0212243 -0.110982 0.0410754 0.0214969 -0.109933 0.0410264 0.0220412 -0.108054 0.0415002 0.0217339 -0.106891 0.0418327 0.0219889 -0.106275 0.0431585 0.0202596 -0.112871 0.0418301 0.0212891 -0.111727 0.0409768 0.0216484 -0.108997 0.0472223 0.0197338 -0.104143 0.0415676 0.0218004 -0.112106 0.0410391 0.0220686 -0.111875 0.0406539 0.0223274 -0.11016 0.0402615 0.022556 -0.10955 0.0406369 0.0225614 -0.107992 0.0415468 0.0225056 -0.106007 0.0420573 0.0225021 -0.105046 0.0430931 0.0222354 -0.104328 0.0442076 0.0218492 -0.103877 0.0466283 0.0204628 -0.103682 0.0469915 0.0195767 -0.104433 0.0467064 0.0193417 -0.104592 0.0450744 0.020773 -0.104457 0.0432791 0.0218887 -0.104834 0.0417262 0.0222795 -0.106164 0.0432925 0.0216029 -0.105005 0.0408741 0.0223343 -0.108034 0.0410359 0.0218083 -0.109993 0.0432027 0.0204119 -0.112953 0.049301 0.0138108 -0.10516 0.0499926 0.00799731 -0.105373 0.0501065 0.0139629 -0.104387 0.0491405 0.0169799 -0.104179 0.0489957 0.0169502 -0.104524 0.0496721 0.013892 -0.105015 0.0499586 0.0139457 -0.104732 0.0508544 0.00799734 -0.105029 0.0464406 0.019094 -0.104601 0.0469012 0.0185519 -0.104702 0.0465709 0.0192188 -0.104613 0.0483701 0.0167218 -0.104956 0.0487216 0.0168591 -0.104809 0.0504487 0.00799864 -0.105313 0.0506185 0.00799718 -0.105229 0.0323315 0.016469 -0.172172 0.0356885 0.00799706 -0.173278 0.0356999 0.00799764 -0.172899 0.0356454 0.0079974 -0.1727 0.0341826 0.0121109 -0.171986 0.0353656 0.00799712 -0.172304 0.033814 0.0121231 -0.171835 0.0357068 0.0079972 -0.173171 0.0345535 0.0123484 -0.173043 0.0336839 0.014456 -0.172474 0.0345836 0.0123008 -0.172664 0.03225 0.0163248 -0.171807 0.0344521 0.0122261 -0.172279 0.0300138 0.0176107 -0.170562 0.029158 0.0184013 -0.169716 0.0282596 0.0190215 -0.166997 0.0283721 0.018841 -0.167996 0.0283666 0.0189922 -0.168026 0.0287304 0.0185447 -0.169001 0.0298854 0.018471 -0.171525 0.0305135 0.0180587 -0.171535 0.0295971 0.018648 -0.171304 0.0281393 0.0194981 -0.169503 0.0289185 0.0190563 -0.170174 0.027921 0.0199268 -0.166063 0.0279873 0.0200795 -0.164932 0.0288093 0.0198763 -0.164056 0.0325116 0.0186263 -0.162 0.0305288 0.0192517 -0.162857 0.0304581 0.0194716 -0.162622 0.0289843 0.019651 -0.164208 0.0279738 0.0196576 -0.168241 0.0281991 0.019434 -0.168148 0.0291102 0.0190622 -0.164364 0.031956 0.0179992 -0.162569 0.0290879 0.0193643 -0.164314 0.0301329 0.0187961 -0.163343 0.0305418 0.0189688 -0.163024 0.0305268 0.0188184 -0.163076 0.032259 0.0180036 -0.162511 0.0339854 0.0167348 -0.162592 0.0282986 0.019412 -0.166114 0.0283366 0.0191456 -0.168062 0.03048 0.0174362 -0.170894 0.0319261 0.0159631 -0.171439 0.0320614 0.0161024 -0.171533 0.0344962 0.0171267 -0.162155 0.0317345 0.0191016 -0.161823 0.0323271 0.0181497 -0.162461 0.0324426 0.0184224 -0.162275 0.028151 0.0197007 -0.166098 0.0290824 0.0188404 -0.16996 0.0305685 0.0178616 -0.171225 0.029157 0.0185543 -0.169783 0.0305302 0.0175855 -0.170979 0.0369267 0.00799706 -0.163303 0.0362475 0.0124591 -0.163087 0.0366091 0.0125638 -0.162944 0.037683 0.00799706 -0.163176 0.037919 0.00799708 -0.162974 0.038131 0.00799706 -0.162551 0.0342666 0.0169685 -0.162438 0.0338519 0.0166129 -0.162613 0.0365343 0.0140658 -0.162218 0.0346307 0.0171837 -0.161816 0.0350361 0.0145493 -0.162889 0.0353601 0.0147101 -0.162893 0.0357003 0.0148627 -0.162748 0.0359687 0.0149653 -0.16247 0.0368909 0.0126337 -0.162665 0.0156186 0.0179481 -0.221776 0.0154747 0.017896 -0.223072 0.0169491 0.016463 -0.226034 0.0182675 0.0150677 -0.227118 0.0195171 0.0127523 -0.227392 0.0174128 0.0154456 -0.226289 0.0169488 0.0161142 -0.2258 0.0159777 0.0173468 -0.224109 0.0182557 0.0146086 -0.226923 0.0183271 0.0147232 -0.227009 0.0166055 0.0163191 -0.225284 0.0160894 0.0168516 -0.223979 0.0160679 0.0171037 -0.224037 0.0169654 0.016234 -0.225868 0.0158252 0.017554 -0.224187 0.0168667 0.0166543 -0.226225 0.0159873 0.0174064 -0.22524 0.0182986 0.0168254 -0.218355 0.0170041 0.0167335 -0.22014 0.0186268 0.0165314 -0.218479 0.0168721 0.0174452 -0.219792 0.0158407 0.017772 -0.221834 0.0194944 0.0150159 -0.218606 0.0184697 0.0158438 -0.218971 0.0194319 0.0154557 -0.218569 0.018524 0.0159693 -0.218932 0.0185701 0.0160984 -0.218873 0.0170182 0.016861 -0.220108 0.0160803 0.017334 -0.221903 0.0164649 0.0169743 -0.220966 0.0161124 0.0170747 -0.221917 0.02105 0.0138352 -0.218464 0.0205752 0.0150869 -0.218009 0.020275 0.0146938 -0.218443 0.0204516 0.0149166 -0.218268 0.0186254 0.0163369 -0.218704 0.0169738 0.0172383 -0.219945 0.0170183 0.0169925 -0.220064 0.0160175 0.0175105 -0.221884 0.0241658 0.00799707 -0.219176 0.0228724 0.0104286 -0.218914 0.0243354 0.00799707 -0.219167 0.0217317 0.0128811 -0.218597 0.0220367 0.0130886 -0.218446 0.0222819 0.0132285 -0.218164 0.0247355 0.00799706 -0.219032 0.013379 0.0200738 -0.278399 0.0129134 0.0223072 -0.277947 0.0125573 0.0209164 -0.277575 0.0114669 0.024072 -0.277336 0.0130423 0.022391 -0.278698 0.0121068 0.0245634 -0.278485 0.0130527 0.0223705 -0.278323 0.0120046 0.0244084 -0.277745 0.0126407 0.0222114 -0.277662 0.00908592 0.0279549 -0.277813 0.0121224 0.0245247 -0.278114 0.00905339 0.0277136 -0.277094 0.0117665 0.0242336 -0.277469 0.0054223 0.0298904 -0.273975 0.00516311 0.0298284 -0.272333 0.00471445 0.0308045 -0.270752 0.00480013 0.0305767 -0.273097 0.00524234 0.0303315 -0.275105 0.00721221 0.0292255 -0.276701 0.00532695 0.0301549 -0.270965 0.0091175 0.0278933 -0.277448 0.00563042 0.0301171 -0.275189 0.00502406 0.0303519 -0.273042 0.00579714 0.0298984 -0.27501 0.00682324 0.0287 -0.275824 0.0088978 0.0274454 -0.27684 0.0088029 0.0273051 -0.276768 0.00725592 0.0287468 -0.276203 0.00721763 0.0285996 -0.276127 0.00869932 0.0271628 -0.276729 0.00544729 0.0295915 -0.273907 0.00589055 0.0294681 -0.274808 0.00516413 0.0300662 -0.272992 0.00588198 0.0296174 -0.274863 0.00727521 0.0290211 -0.276422 0.010896 0.0267189 -0.267902 0.00548306 0.0298217 -0.270667 0.0105195 0.02785 -0.266788 0.00642628 0.0293294 -0.269207 0.00564099 0.0297535 -0.270315 0.00754581 0.0286705 -0.268362 0.00759961 0.0288263 -0.268317 0.00910075 0.0276433 -0.267868 0.0101001 0.0273612 -0.267772 0.00526055 0.0303239 -0.270939 0.00496136 0.0306775 -0.270833 0.00599725 0.03027 -0.268955 0.0103072 0.0276525 -0.267537 0.00948936 0.0284985 -0.266805 0.00927746 0.0279617 -0.267775 0.00853116 0.028795 -0.267686 0.00709073 0.0289441 -0.268641 0.00622985 0.0296038 -0.269404 0.00844954 0.0285012 -0.267929 0.0106269 0.0263845 -0.267938 0.00988264 0.0270421 -0.267839 0.00948928 0.0284466 -0.267178 0.00942027 0.0282549 -0.267531 0.00760537 0.0294873 -0.267708 0.00615528 0.0300507 -0.269171 0.00766365 0.0292787 -0.268013 0.00622815 0.0297596 -0.269343 0.00763966 0.0289852 -0.268243 0.0151307 0.0199971 -0.268605 0.013554 0.0237564 -0.2685 0.0133262 0.0233695 -0.26853 0.0147348 0.0199971 -0.268764 0.0150453 0.019997 -0.268657 0.0147856 0.0220266 -0.268517 0.0128876 0.0257525 -0.267676 0.0139076 0.0239479 -0.268314 0.0154246 0.0199973 -0.268296 0.0150677 0.0220954 -0.268193 0.0141681 0.0240617 -0.267974 0.0114609 0.0271686 -0.266928 0.0126527 0.0256068 -0.268031 0.0113557 0.027151 -0.267345 0.011155 0.0269912 -0.267691 0.0115081 0.0256291 -0.268131 -0.046166 0.0131432 -0.219459 -0.0460992 0.013066 -0.219107 -0.0458987 0.0129345 -0.218797 -0.045672 0.0137936 -0.219458 -0.0449392 0.0131887 -0.218557 -0.0449245 0.0131771 -0.218556 -0.0405781 0.0171283 -0.214197 -0.0436389 0.0148805 -0.218323 -0.0451906 0.0133894 -0.218626 -0.0438062 0.015101 -0.218426 -0.0452912 0.0134706 -0.218688 -0.0454345 0.0135877 -0.218824 -0.0440086 0.0154881 -0.218876 -0.0406189 0.0178325 -0.216338 -0.041057 0.0169538 -0.216083 -0.0405454 0.0173812 -0.21419 -0.040979 0.0174445 -0.216225 -0.0400652 0.0180009 -0.214184 -0.0408501 0.0176534 -0.216334 -0.0422797 0.0164456 -0.217631 -0.0410492 0.0172003 -0.216139 -0.0455488 0.013683 -0.218998 -0.0438501 0.0157395 -0.219105 -0.0422564 0.0168726 -0.217984 -0.0439386 0.0153165 -0.218618 -0.0422962 0.0166774 -0.217787 -0.0432552 0.0152889 -0.218174 -0.046685 0.0103387 -0.218477 -0.0477721 0.00799706 -0.218417 -0.0479924 0.00799707 -0.218426 -0.0456182 0.0127409 -0.218602 -0.0421551 0.01605 -0.210577 -0.0409643 0.0170061 -0.21214 -0.0406605 0.017014 -0.213191 -0.0424809 0.0162357 -0.209566 -0.0407471 0.0174636 -0.211904 -0.0402749 0.0178448 -0.214183 -0.0400871 0.0179558 -0.213503 -0.0455694 0.0130739 -0.208541 -0.0453672 0.0128912 -0.209252 -0.0451091 0.0126861 -0.209484 -0.0436767 0.0145648 -0.20972 -0.0438618 0.0149579 -0.209193 -0.0435883 0.0144446 -0.209797 -0.0421237 0.015923 -0.210648 -0.044828 0.0124699 -0.209566 -0.0414897 0.0165967 -0.211274 -0.0408889 0.0172551 -0.21203 -0.0449714 0.0125795 -0.209541 -0.0421673 0.0162907 -0.210389 -0.0438096 0.0147893 -0.209492 -0.042109 0.0164853 -0.210161 -0.0404418 0.0176315 -0.214185 -0.045529 0.013028 -0.208909 -0.0478571 0.00799718 -0.20926 -0.0480537 0.00799706 -0.209103 0.00792213 0.0195105 -0.303274 0.00777486 0.0194971 -0.306563 -0.0462508 0.0195105 -0.330725 -0.0538706 0.0197971 -0.31287 -0.0515812 0.0197971 -0.320781 -0.0520749 0.0196246 -0.319254 -0.0547644 0.0196191 -0.299913 0.0134163 0.0197606 -0.278551 0.0106358 0.0194971 -0.316064 0.00826171 0.0194971 -0.309873 0.00853304 0.0194971 -0.310914 -0.0509258 0.0195898 -0.322207 -0.0256656 0.0194971 -0.356092 -0.0257342 0.0195105 -0.356148 -0.0340238 0.0195105 -0.346047 -0.0340895 0.0195526 -0.346101 -0.0204586 0.0194971 -0.362437 -0.0174043 0.0195095 -0.366218 -0.0173417 0.0194971 -0.36616 -0.0122505 0.0194971 -0.370291 -0.00937027 0.019623 -0.372035 -0.00680459 0.0194971 -0.372701 -0.00624214 0.019532 -0.373007 -0.00666885 0.0194971 -0.372741 0.000478454 0.0194971 -0.373691 0.0181086 0.0195084 -0.365402 0.0222972 0.0194971 -0.34199 0.021616 0.0194971 -0.340299 0.0127145 0.0194971 -0.320652 0.0162068 0.0195105 -0.328144 0.00783367 0.0194971 -0.303266 0.0106338 0.0195105 -0.290265 0.0130242 0.0195094 -0.279347 0.0107169 0.0195526 -0.290284 0.0131705 0.0195462 -0.27905 0.0133106 0.0196177 -0.278765 0.013318 0.0196232 -0.27875 0.010783 0.0196191 -0.290298 -0.0545887 0.0197971 -0.308292 -0.0547012 0.0196191 -0.306433 -0.0546968 0.0195526 -0.299917 -0.0548078 0.0197034 -0.299911 -0.0546974 0.0196229 -0.306521 -0.0546588 0.0195756 -0.306475 -0.0546167 0.0195455 -0.306516 -0.0520994 0.0196191 -0.31917 -0.0520354 0.0195526 -0.319148 -0.0543327 0.0195868 -0.309654 -0.0535767 0.0194971 -0.31281 -0.0546119 0.0195105 -0.299921 -0.0424894 0.0196197 -0.335973 -0.0463782 0.0196191 -0.330809 -0.0424313 0.0196191 -0.336043 -0.0423133 0.0195105 -0.335946 -0.042379 0.0195526 -0.336 -0.0463217 0.0195526 -0.330772 -0.0463317 0.0196227 -0.330884 -0.0443587 0.0195105 -0.333395 -0.0496639 0.0197971 -0.325196 -0.0520005 0.019548 -0.31923 -0.0175501 0.0197034 -0.366354 -0.0341754 0.0197034 -0.346172 -0.0258859 0.0197034 -0.356273 -0.0175183 0.0196191 -0.366324 -0.0258523 0.0196191 -0.356245 -0.0341418 0.0196191 -0.346144 -0.0258 0.0195526 -0.356202 -0.0174688 0.0195526 -0.366278 0.000483411 0.0196191 -0.373932 -0.0061929 0.0196191 -0.373125 -0.00627236 0.0196285 -0.373111 0.000484613 0.0197971 -0.373991 0.000484335 0.0196992 -0.373974 0.00714125 0.0197971 -0.372906 0.000482021 0.0195526 -0.373865 -0.00617541 0.0195526 -0.37306 -0.0145718 0.0194971 -0.368694 -0.0151142 0.019623 -0.368574 0.000480544 0.0195085 -0.373773 0.0174583 0.0197971 -0.366455 0.0182635 0.0197034 -0.365533 0.0218717 0.0197971 -0.359856 0.021858 0.0197034 -0.35985 0.0218183 0.0196191 -0.359832 0.0237488 0.0197971 -0.353393 0.0182304 0.0196191 -0.365505 0.0217567 0.0195526 -0.359804 0.0181789 0.0195526 -0.365461 0.00200569 0.0194971 -0.37361 0.00384925 0.019623 -0.373628 0.00705178 0.0194971 -0.37262 0.010413 0.0194971 -0.371282 0.0132327 0.0197971 -0.370013 0.0130671 0.0194971 -0.369763 0.0158639 0.019623 -0.367923 0.021876 0.0197034 -0.340182 0.0191248 0.0197971 -0.334073 0.0217746 0.0195526 -0.340227 0.0163459 0.0196191 -0.328081 0.0163855 0.0197034 -0.328063 0.0218363 0.0196191 -0.3402 0.0162843 0.0195526 -0.328109 0.0108558 0.0196191 -0.315964 0.00843102 0.0195526 -0.309834 0.0107941 0.0195526 -0.315992 0.0216962 0.0195102 -0.340263 0.0229963 0.019623 -0.34336 0.0229876 0.019623 -0.356669 0.0216731 0.0195085 -0.359766 0.0215982 0.0194971 -0.359733 0.0180466 0.0194971 -0.365349 0.0080339 0.019637 -0.306633 0.00813231 0.0197971 -0.303295 0.00855392 0.0197971 -0.309805 0.0108954 0.0197034 -0.315946 0.00849693 0.0196191 -0.309818 0.0085393 0.0197034 -0.309809 0.00811787 0.0197049 -0.303294 0.00807409 0.0196191 -0.30329 0.00935668 0.0196191 -0.296803 0.00929059 0.0195526 -0.296788 0.0184179 0.0197971 -0.332513 0.011151 0.0197971 -0.316474 0.008016 0.0196191 -0.306548 0.00800676 0.0195526 -0.303283 0.0133972 0.019711 -0.27859 0.0108255 0.0197034 -0.290307 0.00939918 0.0197034 -0.296812 0.00920752 0.0195105 -0.29677 -0.0547351 0.0195849 -0.299915 -0.053832 0.00506483 -0.281961 -0.0537947 0.00149706 -0.281729 -0.0538158 0.00504263 -0.282073 -0.0538731 0.00846113 -0.28311 -0.0538896 0.00850465 -0.283005 -0.0539657 0.0115951 -0.284785 -0.0541085 0.0144374 -0.28697 -0.0542611 0.0167068 -0.289734 -0.0546049 0.019334 -0.29635 -0.0544165 0.0182965 -0.29294 -0.0542427 0.0166134 -0.289797 -0.0540909 0.0143576 -0.287051 -0.0541767 0.0165277 -0.289858 -0.054025 0.0142844 -0.287128 -0.0538075 0.00842127 -0.28321 -0.053731 0.00149706 -0.281832 -0.0545385 0.0192338 -0.296374 -0.0543502 0.0182017 -0.292983 -0.0544364 0.0191685 -0.296392 -0.0538999 0.0115374 -0.284875 -0.0537963 0.0115008 -0.284935 -0.0537036 0.0083961 -0.283277 -0.0536461 0.0050095 -0.282249 -0.0537502 0.00502231 -0.282179 -0.0535131 0.00149706 -0.281926 -0.0535324 0.00500634 -0.282272 -0.0539217 0.0142377 -0.28718 -0.053809 0.0142253 -0.287199 -0.0539615 0.0164575 -0.289917 -0.0540737 0.0164727 -0.289901 -0.0542477 0.0181404 -0.293014 -0.0541361 0.0181226 -0.293028 -0.0545232 0.0194971 -0.299926 -0.0538126 0.00149706 -0.28161 -0.053731 0.000297063 -0.281832 -0.0536317 0.00149706 -0.281902 -0.0537729 0.00023198 -0.281761 -0.0538131 0.000297063 -0.281626 -0.053808 0.00024483 -0.28161 -0.0537729 0.000150824 -0.28166 -0.0535131 4.58466e-06 -0.281693 -0.0536056 1.17461e-05 -0.281621 -0.0536891 5.43579e-05 -0.281617 -0.0537729 0.000179788 -0.28172 -0.0536631 9.39373e-05 -0.281788 -0.0537979 0.000204358 -0.281611 -0.0537992 0.000208336 -0.28161 -0.0537947 0.000297063 -0.281729 -0.0537729 0.000297063 -0.281776 -0.0536631 0.000297063 -0.281886 -0.0536317 0.000297063 -0.281902 -0.0536631 4.37693e-05 -0.281684 -0.0535131 1.98992e-05 -0.281741 -0.0536631 0.000184337 -0.28186 -0.0535131 0.000297063 -0.281926 -0.0498555 0.000182258 -0.281903 -0.0535131 0.000166898 -0.281897 -0.0498555 8.4931e-05 -0.281838 -0.0535131 6.25136e-05 -0.281813 -0.0498555 1.98992e-05 -0.281741 -0.0496793 0.000182258 -0.281876 -0.0495066 0.000297063 -0.281814 -0.0495299 0.000147063 -0.281782 -0.0496723 0.000297063 -0.281898 -0.0496991 8.4931e-05 -0.281814 -0.0497288 1.98992e-05 -0.281721 -0.0498555 -2.93696e-06 -0.281626 -0.0497639 -2.93696e-06 -0.281612 -0.0496143 1.98992e-05 -0.281664 -0.0495938 3.72554e-05 -0.281692 -0.047848 3.72554e-05 -0.281031 -0.0495577 8.4931e-05 -0.281743 -0.0495198 0.000182258 -0.281796 -0.0517048 3.72554e-05 -0.267327 -0.0518452 -2.93696e-06 -0.26738 -0.0519369 1.98992e-05 -0.266042 -0.0511147 -2.93696e-06 -0.268526 -0.0510075 3.72554e-05 -0.268421 -0.0499839 -2.93696e-06 -0.269281 -0.050929 0.000147063 -0.268344 -0.0499281 3.72554e-05 -0.269142 -0.0486499 3.72554e-05 -0.269366 -0.051752 0.000297063 -0.266052 -0.0517748 0.000182258 -0.266051 -0.0517921 0.000147063 -0.26605 -0.0518397 8.4931e-05 -0.266047 -0.051602 0.000147063 -0.267288 -0.0515644 0.000297063 -0.267274 -0.0498873 0.000147063 -0.26904 -0.0486536 0.000147063 -0.269256 -0.0517672 1.98992e-05 -0.262969 -0.0518819 -2.93696e-06 -0.262963 -0.0519017 3.72554e-05 -0.266044 -0.0518521 1.98992e-05 -0.264506 -0.0516051 0.000182258 -0.262978 -0.05169 0.000182258 -0.264515 -0.0517549 8.4931e-05 -0.264511 -0.0503628 -2.93696e-06 -0.243185 -0.0515823 0.000297063 -0.262979 -0.0516701 8.4931e-05 -0.262975 -0.0510095 -2.93696e-06 -0.252684 -0.0493533 0.000182552 -0.223376 -0.0494211 8.22317e-05 -0.223373 -0.0502515 1.85205e-05 -0.24319 -0.0495229 1.69787e-05 -0.223369 -0.0490119 0.000182746 -0.222009 -0.0482104 8.2643e-05 -0.220838 -0.0469697 8.31724e-05 -0.220124 -0.0496303 -2.93696e-06 -0.223364 -0.0487714 -2.93696e-06 -0.221118 -0.0470021 1.71878e-05 -0.220027 -0.0455304 -2.93696e-06 -0.219741 -0.0473166 -2.93696e-06 -0.22003 -0.048278 1.70701e-05 -0.220761 -0.0492621 -2.93696e-06 -0.221889 -0.0490731 8.23252e-05 -0.22198 -0.0481656 0.000183406 -0.220889 -0.0455543 0.000297063 -0.22004 -0.0469483 0.000184505 -0.220188 -0.0469414 0.000295036 -0.220209 -0.0493306 0.000292328 -0.223377 -0.0483242 1.68677e-05 -0.205812 -0.0471878 -2.93696e-06 -0.207557 -0.0449398 -2.93696e-06 -0.208361 -0.0454847 -2.93696e-06 -0.208308 -0.0449362 3.72554e-05 -0.208211 -0.0475625 1.69336e-05 -0.207067 -0.0483109 -2.93696e-06 -0.20613 -0.0484348 8.21124e-05 -0.204364 -0.0474873 8.24991e-05 -0.206997 -0.0464171 -2.93696e-06 -0.208023 -0.0463303 8.29979e-05 -0.207832 -0.0463023 0.000184437 -0.20777 -0.0482281 8.22012e-05 -0.205777 -0.0481641 0.000182781 -0.205754 -0.0481429 0.000292824 -0.205747 -0.047421 0.000293685 -0.206936 -0.0474374 0.0001834 -0.206951 -0.0449332 0.00018584 -0.208082 -0.0485368 1.68481e-05 -0.204358 -0.0483669 0.000182596 -0.204367 -0.0464591 -2.93696e-06 -0.165531 -0.0424243 8.3676e-05 -0.162705 -0.0424191 3.72554e-05 -0.162644 -0.0424062 -2.93696e-06 -0.162495 -0.0424286 0.000147063 -0.162754 -0.0438749 1.70063e-05 -0.162769 -0.0438432 8.28217e-05 -0.162867 -0.0450859 8.21464e-05 -0.163568 -0.046419 1.76442e-05 -0.166077 -0.0461445 -2.93696e-06 -0.164605 -0.0463196 8.15949e-05 -0.166082 -0.0451528 1.6857e-05 -0.163491 -0.045957 8.17243e-05 -0.164697 -0.0458959 0.000181785 -0.164728 -0.0438223 0.000184067 -0.162931 -0.0450414 0.000182663 -0.163619 -0.0462513 0.000182293 -0.166086 -0.0458753 0.000291437 -0.164738 -0.0451609 1.66921e-05 -0.148569 -0.0443992 1.68026e-05 -0.149823 -0.044024 -2.93696e-06 -0.150314 -0.0453734 1.66581e-05 -0.147115 -0.0450651 8.14073e-05 -0.148534 -0.0452038 0.000180808 -0.147124 -0.0443242 8.19064e-05 -0.149754 -0.0431673 8.26937e-05 -0.150589 -0.043254 -2.93696e-06 -0.15078 -0.0417735 3.72554e-05 -0.150968 -0.0431393 0.000183804 -0.150527 -0.0451804 0.000290079 -0.147126 -0.045001 0.000181128 -0.148511 -0.0442574 0.000291971 -0.149693 -0.0442742 0.000182167 -0.149708 -0.0431301 0.000294245 -0.150507 -0.0417699 0.000297063 -0.150818 -0.0431422 1.73474e-05 -0.10679 -0.0429749 0.000179622 -0.106799 -0.0452718 8.12537e-05 -0.147121 -0.0432505 -2.93696e-06 -0.106784 -0.0405982 1.69033e-05 -0.103482 -0.0391536 0.000185843 -0.103485 -0.039152 0.000147063 -0.103467 -0.0405665 8.23478e-05 -0.10358 -0.0418759 1.66602e-05 -0.104204 -0.0418093 8.12496e-05 -0.104281 -0.0426807 8.05414e-05 -0.10541 -0.042867 -2.93696e-06 -0.105319 -0.0430434 8.03205e-05 -0.106795 -0.0405455 0.000183077 -0.103644 -0.0417646 0.000180792 -0.104332 -0.0426194 0.000179316 -0.10544 -0.0400583 -2.93696e-06 -0.0889634 -0.0399177 3.72554e-05 -0.0889111 -0.040232 3.72554e-05 -0.0868344 -0.0397771 0.000297063 -0.0888589 -0.0398148 0.000147063 -0.0888729 -0.03846 0.000297063 -0.0908118 -0.0385611 3.72554e-05 -0.0909226 -0.0384871 0.000147063 -0.0908415 -0.036705 0.000297063 -0.0918502 -0.0401224 0.000147063 -0.0868405 -0.0380531 0.000147063 -0.0493554 -0.0326615 3.72554e-05 -0.031836 -0.0291029 -2.93696e-06 -0.0267713 -0.0288944 0.000182258 -0.026954 -0.0356 -2.93696e-06 -0.037284 -0.0354611 3.72554e-05 -0.0373407 -0.0373119 3.72554e-05 -0.0432325 -0.0325681 0.000147063 -0.0318938 -0.0353595 0.000147063 -0.0373822 -0.0381628 3.72554e-05 -0.0493493 -0.0325339 0.000297063 -0.0319149 -0.0353223 0.000297063 -0.0373974 -0.0372048 0.000147063 -0.0432566 0.0325257 0.000182258 0.0112603 0.0346078 -2.93696e-06 0.00246658 0.0327876 -2.93696e-06 0.0113509 0.0343314 0.000182258 0.0024469 0.0325871 8.4931e-05 0.0112815 0.0326791 1.98992e-05 0.0113134 0.0286324 1.98992e-05 0.0193958 0.0285519 8.4931e-05 0.0193412 0.0227049 -2.93696e-06 0.0262405 0.0226297 1.98992e-05 0.0261537 0.0151311 -2.93696e-06 0.0312287 0.022566 8.4931e-05 0.0260801 0.0225235 0.000182258 0.0260309 0.015081 1.98992e-05 0.0311254 0.0150386 8.4931e-05 0.0310378 0.00648356 8.4931e-05 0.0338758 -0.0113413 8.4931e-05 0.0325751 -0.01132 0.000182258 0.0325137 -0.0113125 0.000297063 0.0324921 -0.0194485 1.98992e-05 0.0286058 -0.0261955 1.98992e-05 0.0225909 -0.0261218 8.4931e-05 0.0225273 -0.0193937 8.4931e-05 0.0285253 -0.0311535 1.98992e-05 0.0150332 -0.033984 1.98992e-05 0.00644889 -0.0310659 8.4931e-05 0.0149909 -0.0310073 0.000182258 0.0149626 -0.0338884 8.4931e-05 0.00643075 -0.0344935 1.98992e-05 -0.00257562 0.028498 0.000182258 0.0193048 0.0311484 0.000297063 0.014593 0.0325041 0.000297063 0.0112528 0.0225085 0.000297063 0.0260137 0.0150102 0.000182258 0.0309793 0.0150002 0.000297063 0.0309588 0.00109589 0.000297063 0.0343861 0.00647133 0.000182258 0.0338119 -0.00251461 8.4931e-05 0.0344002 0.00650187 1.98992e-05 0.0339714 -0.00253005 -2.93696e-06 0.0346117 -0.00252169 1.98992e-05 0.0344972 -0.0114111 -2.93696e-06 0.0327754 -0.0113733 1.98992e-05 0.032667 -0.00250988 0.000182258 0.0343353 -0.0260725 0.000182258 0.0224848 -0.0260552 0.000297063 0.0224699 -0.0222153 0.000297063 0.0262725 -0.0193572 0.000182258 0.0284715 -0.0193443 0.000297063 0.0284526 -0.0301609 0.000297063 0.0165555 -0.0262824 -2.93696e-06 0.0226658 -0.0343089 0.000297063 -0.00256181 -0.0343316 0.000182258 -0.00256351 -0.0338245 0.000182258 0.00641863 -0.0340915 0.000297063 0.00463472 -0.0324941 0.000182258 -0.0113703 -0.0325555 8.4931e-05 -0.0113918 -0.0343965 8.4931e-05 -0.00256836 -0.0326473 1.98992e-05 -0.0114239 -0.0286663 -2.93696e-06 -0.0195564 -0.0284374 0.000182258 -0.0194002 0.0343487 0.000147063 0.00244814 0.0354869 0.000297063 -0.00181665 0.0343962 8.4931e-05 0.00245152 0.0355228 0.000147063 -0.0017985 0.0344582 3.72554e-05 0.00245593 0.0344933 1.98992e-05 0.00245843 0.0357546 -2.93696e-06 -0.00168119 0.0356208 3.72554e-05 -0.00174892 0.0383202 3.72554e-05 -0.00517611 0.0384173 -2.93696e-06 -0.00506186 0.058641 0.000182258 -0.0618926 0.0571128 0.000147063 -0.0706804 0.0571598 8.4931e-05 -0.0706886 0.0587051 8.4931e-05 -0.0619039 0.057221 3.72554e-05 -0.0706994 0.0570868 0.000297063 -0.0708281 0.0572193 3.72554e-05 -0.0707385 0.0573687 -2.93696e-06 -0.0707254 0.0571099 0.000147063 -0.0707481 0.0571021 0.000297063 -0.07087 0.0571399 0.000147063 -0.0708562 0.0571246 0.000147063 -0.0708143 0.057243 3.72554e-05 -0.0708186 0.0572278 3.72554e-05 -0.0707767 0.057384 -2.93696e-06 -0.0707673 0.0573821 3.72554e-05 -0.0728356 0.0573214 8.4931e-05 -0.0728226 0.0572748 0.000147063 -0.0728125 0.0565949 0.000182258 -0.0758824 0.0559509 8.84479e-05 -0.0791869 0.0566584 8.4931e-05 -0.0758962 0.0561577 -2.93696e-06 -0.0792308 0.0567536 1.98992e-05 -0.0759168 0.0558444 0.000299687 -0.0792807 0.055473 0.000182364 -0.0810635 0.0558863 0.000193602 -0.0791731 0.0555384 8.29564e-05 -0.0810785 0.0560517 1.89589e-05 -0.0792084 0.0557425 -2.93696e-06 -0.0811266 0.0554508 0.000288434 -0.0810571 0.0551773 0.000290411 -0.0822902 0.0552666 8.1399e-05 -0.0823096 0.0556366 1.77032e-05 -0.081101 0.0517047 1.76154e-05 -0.0991638 0.0554705 -2.93696e-06 -0.0823537 0.0553661 1.67062e-05 -0.0823311 0.0516063 8.26941e-05 -0.0991424 0.0552001 0.000181066 -0.0822951 0.0515406 0.000182034 -0.099128 0.0524186 0.000290596 -0.094992 0.0510647 -2.93696e-06 -0.100964 0.0497346 -2.93696e-06 -0.102355 0.0479668 1.79366e-05 -0.103073 0.0479407 8.40991e-05 -0.102975 0.0479235 0.000184925 -0.102911 0.0496113 8.34031e-05 -0.102184 0.0508891 8.29188e-05 -0.100849 0.0508329 0.000182497 -0.100812 0.0479179 0.000294705 -0.10289 0.0495721 0.000183494 -0.10213 0.0508139 0.000291345 -0.1008 0.0461026 0.000147063 -0.10307 0.0461046 0.000186635 -0.103051 0.0442663 3.72554e-05 -0.103273 0.0460911 3.72554e-05 -0.103179 0.0460976 8.4931e-05 -0.103117 0.0443775 0.00018584 -0.114874 0.039924 0.000297063 -0.106724 0.0395459 0.000147063 -0.109582 0.0404756 0.000297063 -0.112312 0.0442436 0.000147063 -0.103166 0.0416587 0.000147063 -0.104421 0.0400628 3.72554e-05 -0.106781 0.0399612 0.000147063 -0.106739 0.0396551 3.72554e-05 -0.109572 0.0405091 0.000147063 -0.112289 0.0406007 3.72554e-05 -0.112229 0.0426271 0.000147063 -0.114231 0.0443809 0.000147063 -0.114855 0.0444011 3.72554e-05 -0.114747 0.0460753 -2.93696e-06 -0.103328 0.041729 3.72554e-05 -0.104505 0.0418251 -2.93696e-06 -0.10462 0.0427513 -2.93696e-06 -0.114003 0.0426796 3.72554e-05 -0.114135 0.0444287 -2.93696e-06 -0.1146 0.0474426 -2.93696e-06 -0.119149 0.0468098 1.68611e-05 -0.116297 0.0473983 -2.93696e-06 -0.117341 0.0473609 1.67658e-05 -0.117657 0.0472386 8.1606e-05 -0.119104 0.0458324 -2.93696e-06 -0.115169 0.0457163 8.28435e-05 -0.115344 0.0467246 8.21694e-05 -0.116353 0.0456787 0.000184115 -0.115401 0.0466679 0.000182714 -0.116391 0.0472607 8.17389e-05 -0.117676 0.0471938 0.000181818 -0.117688 0.0471712 0.000291485 -0.117692 0.0456665 0.000294676 -0.115419 0.0473382 1.67364e-05 -0.119126 0.0471721 0.000181541 -0.119089 0.0385872 8.26017e-05 -0.158554 0.0386856 1.75943e-05 -0.158575 0.0359614 -2.93696e-06 -0.161481 0.0387921 -2.93696e-06 -0.158599 0.0341795 1.98992e-05 -0.161358 0.0356451 1.699e-05 -0.161433 0.0342195 0.000185842 -0.161199 0.035619 0.000183911 -0.161265 0.0356294 8.27472e-05 -0.161332 0.0369325 0.000182357 -0.160781 0.038009 8.15263e-05 -0.159863 0.0385216 0.000181844 -0.158539 0.037022 1.68247e-05 -0.160926 0.0375764 -2.93696e-06 -0.16065 0.0369683 8.19996e-05 -0.160839 0.0356156 0.000294391 -0.161243 0.0369206 0.000292233 -0.160761 0.0379345 0.000290862 -0.15981 0.0379534 0.000181372 -0.159824 0.031659 0.00018584 -0.172873 0.0342247 0.000297063 -0.161178 0.0291633 0.000297063 -0.171799 0.0274318 0.000182258 -0.169706 0.0274115 0.000297063 -0.169717 0.0267829 0.000182258 -0.167074 0.0290549 0.000182258 -0.162306 0.0290407 0.000297063 -0.162288 0.0315219 8.4931e-05 -0.161216 0.0273638 0.000182258 -0.164425 0.0274225 8.4931e-05 -0.164453 0.029177 0.000182258 -0.171781 0.0290952 8.4931e-05 -0.162357 0.0291555 1.98992e-05 -0.162433 0.0275104 1.98992e-05 -0.164495 0.0268479 8.4931e-05 -0.167073 0.0274898 8.4931e-05 -0.169677 0.0269453 1.98992e-05 -0.167072 0.0275765 1.98992e-05 -0.169633 0.0292159 8.4931e-05 -0.171729 0.0342033 8.4931e-05 -0.161264 0.0315083 0.000182258 -0.161152 0.0342191 0.000182258 -0.1612 0.0315663 -2.93696e-06 -0.161423 0.0315423 1.98992e-05 -0.161311 0.0270601 -2.93696e-06 -0.16707 0.0276789 -2.93696e-06 -0.169581 0.0292743 1.98992e-05 -0.171651 0.0316892 1.98992e-05 -0.172712 0.0340064 8.17355e-05 -0.174353 0.0346426 1.66455e-05 -0.175657 0.0346198 1.66089e-05 -0.177126 0.0317103 -2.93696e-06 -0.172599 0.0340914 1.67647e-05 -0.174296 0.0345205 8.1032e-05 -0.177104 0.0345426 8.1197e-05 -0.175675 0.0331139 -2.93696e-06 -0.173169 0.0316712 8.4931e-05 -0.172808 0.0316593 0.000182258 -0.172872 0.0329979 8.25928e-05 -0.173344 0.0344756 0.00018069 -0.175688 0.0339497 0.000181812 -0.17439 0.032948 0.000293955 -0.173419 0.0329603 0.000183595 -0.1734 0.0262396 0.000180709 -0.214538 0.0344539 0.000180347 -0.177089 0.0264033 1.75068e-05 -0.214574 0.0263568 -2.93696e-06 -0.215116 0.0252961 -2.93696e-06 -0.216646 0.0263052 8.2128e-05 -0.214553 0.0265097 -2.93696e-06 -0.214598 0.0259127 1.65451e-05 -0.215768 0.025925 1.65613e-05 -0.215749 0.0246506 0.000180036 -0.21678 0.0257276 8.01464e-05 -0.215863 0.0254816 0.000287148 -0.21603 0.0256521 0.000286834 -0.215809 0.0219413 0.000242077 -0.217182 0.0219211 8.4931e-05 -0.217262 0.0233473 8.21007e-05 -0.217331 0.0218974 1.98992e-05 -0.217357 0.0246382 0.000288995 -0.21676 0.0241288 0.000290282 -0.21702 0.0233334 0.000292509 -0.217242 0.0247399 1.65813e-05 -0.216925 0.0258102 1.64168e-05 -0.215921 0.0259311 1.65694e-05 -0.215739 0.0259371 1.65775e-05 -0.215729 0.0259611 1.66101e-05 -0.21569 0.0260076 1.66756e-05 -0.21561 0.0261737 1.69432e-05 -0.215279 0.0256719 0.000178489 -0.215823 0.0224359 0.000295345 -0.217264 0.0233343 0.000238055 -0.217247 0.0233368 0.000182559 -0.217264 0.0246865 8.08883e-05 -0.216838 0.0233629 1.68498e-05 -0.217432 0.021937 0.000182258 -0.217199 0.0192276 0.000297063 -0.217129 0.0167694 0.000297063 -0.218282 0.0150713 0.000297063 -0.220401 0.0144811 0.000297063 -0.223051 0.0145039 0.000182258 -0.223051 0.0153445 0.000297063 -0.226098 0.0192324 0.000182258 -0.217151 0.0167835 0.000182258 -0.2183 0.0150919 0.000182258 -0.220411 0.0151505 8.4931e-05 -0.220439 0.0151402 0.000182258 -0.22568 0.0168702 0.000182258 -0.22776 0.0169095 8.4931e-05 -0.227708 0.019246 8.4931e-05 -0.217215 0.0168237 8.4931e-05 -0.218351 0.014569 8.4931e-05 -0.223051 0.0151983 8.4931e-05 -0.225651 0.0192663 1.98992e-05 -0.21731 0.0168839 1.98992e-05 -0.218428 0.0152382 1.98992e-05 -0.220481 0.0146663 1.98992e-05 -0.22305 0.0152852 1.98992e-05 -0.225608 0.0153878 -2.93696e-06 -0.225556 0.0169683 1.98992e-05 -0.22763 0.0193707 1.98992e-05 -0.228704 0.0193926 -2.93696e-06 -0.228592 0.0205999 1.71358e-05 -0.229176 0.0193521 8.4931e-05 -0.2288 0.0223081 1.63679e-05 -0.231682 0.022349 -2.93696e-06 -0.231371 0.021768 1.65378e-05 -0.230312 0.0214868 -2.93696e-06 -0.229773 0.0206196 1.70898e-05 -0.229188 0.0206589 1.69982e-05 -0.229212 0.0204186 1.75534e-05 -0.229073 0.020641 0.00018241 -0.229403 0.0200097 0.000294587 -0.22909 0.0216056 0.000288681 -0.230417 0.0216256 0.000179794 -0.230404 0.0221411 0.000178195 -0.231711 0.0221171 0.000286445 -0.231715 0.0206098 1.71128e-05 -0.229182 0.0206048 1.71243e-05 -0.229179 0.0205801 1.71819e-05 -0.229164 0.0199376 -2.93696e-06 -0.22874 0.0200822 1.83134e-05 -0.228915 0.0200182 0.000184039 -0.22907 0.0193397 0.000182258 -0.228864 0.0193354 0.000297063 -0.228886 0.0222084 7.9987e-05 -0.231699 0.0216828 8.07538e-05 -0.230367 0.0206791 8.20102e-05 -0.229347 0.0207363 1.68159e-05 -0.229262 0.0223723 -2.93696e-06 -0.233179 0.0185711 1.77872e-05 -0.248641 0.0184729 8.3445e-05 -0.248617 0.022267 1.72225e-05 -0.233155 0.0221696 8.0979e-05 -0.233132 0.0221039 0.000178499 -0.233117 0.0151278 0.000186386 -0.264195 0.0184077 0.00018358 -0.248601 0.0108812 0.000182258 -0.266993 0.0108451 1.98992e-05 -0.267152 0.0147908 1.73681e-05 -0.265522 0.0152935 1.80989e-05 -0.264225 0.0136006 0.000185791 -0.2665 0.0122921 0.000185873 -0.267024 0.0123224 1.73343e-05 -0.267191 0.0136378 8.37928e-05 -0.266557 0.0145987 0.000185738 -0.265506 0.0123041 8.38322e-05 -0.26709 0.0149299 1.75129e-05 -0.26528 0.015107 0.000296721 -0.264191 0.0145809 0.000296743 -0.265494 0.0151936 8.481e-05 -0.264207 0.0150867 1.7707e-05 -0.264941 0.0148391 1.74163e-05 -0.265442 0.0148152 1.73921e-05 -0.265482 0.0146551 8.37673e-05 -0.265543 0.014803 1.73801e-05 -0.265502 0.0152513 -2.93696e-06 -0.264814 0.0148 1.73771e-05 -0.265507 0.0147969 1.73741e-05 -0.265512 0.0147406 1.73199e-05 -0.2656 0.0142248 -2.93696e-06 -0.266367 0.0136942 1.73256e-05 -0.266642 0.00859817 0.000297063 -0.266937 0.00860259 0.000182258 -0.26696 0.0108667 8.4931e-05 -0.267057 0.0108815 0.00018597 -0.266992 0.00650758 0.000182258 -0.267856 0.00861518 8.4931e-05 -0.267024 0.00654504 8.4931e-05 -0.26791 0.00863403 1.98992e-05 -0.267119 0.00865626 -2.93696e-06 -0.267232 0.0049392 0.000297063 -0.269516 0.00501467 8.4931e-05 -0.269561 0.00660112 1.98992e-05 -0.267989 0.00495881 0.000182258 -0.269528 0.00428898 8.4931e-05 -0.271693 0.00509826 1.98992e-05 -0.269611 0.00449962 -2.93696e-06 -0.271718 0.00420173 0.000297063 -0.271683 0.0042244 0.000182258 -0.271685 0.00438562 1.98992e-05 -0.271705 0.0132659 3.04603e-05 -0.278489 0.0120467 3.72554e-05 -0.280993 0.0134029 0.000193194 -0.278536 0.0121452 0.000147063 -0.281042 0.0134178 0.000255988 -0.278541 0.0140969 0.000182258 -0.275351 0.0133699 0.000126538 -0.278525 0.0133369 8.48813e-05 -0.278513 0.0131352 -2.93696e-06 -0.278442 0.0141192 0.000297063 -0.275355 0.0140334 8.4931e-05 -0.275337 0.0147406 8.4931e-05 -0.272111 0.0139383 1.98992e-05 -0.275316 0.0138262 -2.93696e-06 -0.275291 0.0252666 -2.93696e-06 -0.223067 0.0253748 1.82457e-05 -0.22309 0.0195777 -2.93696e-06 -0.247502 0.0146455 1.98992e-05 -0.272091 0.0254767 8.79493e-05 -0.223113 0.0148041 0.000182258 -0.272125 0.018254 0.000299041 -0.254473 0.0406829 -2.93696e-06 -0.152778 0.0561643 1.78599e-05 -0.0825037 0.0255419 0.000194382 -0.223127 0.0563312 0.000190782 -0.0825399 0.0255594 0.000308601 -0.223131 0.0563954 1.87334e-05 -0.0814664 0.0562864 -2.93696e-06 -0.0814412 0.0561707 -2.93696e-06 -0.0819606 0.0562656 8.62045e-05 -0.0825257 0.0563502 0.000303683 -0.082544 0.056966 0.000292713 -0.0797733 0.0565604 0.000192097 -0.0815035 0.0564957 8.75955e-05 -0.081489 0.0595304 1.57576e-05 -0.0669197 0.0596307 7.97299e-05 -0.066941 0.0626465 1.59172e-05 -0.0519961 0.0682838 -2.93696e-06 -0.0231127 0.0581033 0.000179063 -0.0744101 0.0582402 0.000285342 -0.0738911 0.0631741 0.000288393 -0.0503942 0.0596983 0.000179124 -0.0669553 0.0668359 -2.93696e-06 -0.030569 0.0686897 8.14076e-05 -0.0221096 0.0627473 8.0472e-05 -0.0520168 0.0644137 0.000288971 -0.0442963 0.0628148 0.000180683 -0.0520307 0.0667637 0.000177769 0.0119439 0.0693202 0.000184455 0.000665734 0.0699771 0.000181927 -0.01089 0.0699117 0.000294945 -0.00511427 0.0699034 7.6448e-05 -0.0108881 0.068485 -2.93696e-06 -0.02207 0.06859 1.67951e-05 -0.0220903 0.0686773 -2.93696e-06 -0.0210339 0.0698006 1.43833e-05 -0.0108853 0.0691471 1.54203e-05 0.000641424 0.0681069 -2.93696e-06 0.00584939 0.0674238 -2.93696e-06 0.00867726 0.0665012 -2.93696e-06 0.011861 0.0622168 1.6036e-05 0.0225656 0.0665963 1.41029e-05 0.0118909 0.0623058 7.80068e-05 0.0226112 0.0666931 7.45436e-05 0.0119216 0.068107 1.68581e-05 0.00634166 0.0692531 8.31482e-05 0.000656311 0.0697202 1.71838e-05 -0.00512801 0.0687565 0.00018084 -0.0221225 0.0623668 0.000173749 0.0226425 0.0540091 -2.93696e-06 0.0341382 0.0577476 1.60544e-05 0.0297789 0.0491838 -2.93696e-06 0.0387399 0.0521649 1.62197e-05 0.0361849 0.0490104 1.63199e-05 0.0390222 0.0304157 -2.93696e-06 0.0488278 0.0304441 1.42115e-05 0.0489236 0.0382953 -2.93696e-06 0.0457787 0.0456507 1.40162e-05 0.0415771 0.00252721 -2.93696e-06 0.0493676 0.0137263 -2.93696e-06 0.0509661 0.0221459 -2.93696e-06 0.0505721 -0.000244661 -2.93696e-06 0.0485786 -0.0105305 1.51989e-05 0.0442 -0.00287317 1.33621e-05 0.0477784 -0.0201076 -2.93696e-06 0.0370526 -0.0235826 -2.93696e-06 0.0335148 -0.0236529 1.22822e-05 0.0335777 -0.028457 -2.93696e-06 0.0271315 -0.03265 -2.93696e-06 0.0192669 -0.035439 1.26721e-05 0.0112489 -0.0355398 7.28087e-05 0.0112737 -0.0342611 1.47597e-05 0.0153201 -0.0327371 1.24016e-05 0.019304 -0.0328318 7.14846e-05 0.0193447 -0.0287886 1.43287e-05 0.0268008 -0.0237296 7.08684e-05 0.0336461 -0.0207124 1.4571e-05 0.0366233 -0.0176722 5.69863e-05 0.0394034 -0.0105791 7.42953e-05 0.0442853 -0.00291023 7.63501e-05 0.0478773 0.00114322 1.58758e-05 0.0491029 0.00528903 1.37137e-05 0.0500941 0.0136919 1.63905e-05 0.0510709 0.0136884 7.96157e-05 0.0511716 0.0221587 1.41544e-05 0.0506711 0.0221722 8.04773e-05 0.050778 0.0266699 -2.93696e-06 0.0497912 0.026352 1.66283e-05 0.0499684 0.0383416 1.6576e-05 0.0458745 0.0383856 8.04475e-05 0.0459656 0.0578281 7.81115e-05 0.0298383 0.0522828 0.000175531 0.0363057 0.052235 7.88508e-05 0.0362567 0.0457123 7.97403e-05 0.0416651 0.0457515 0.000177385 0.041721 0.0384152 0.000178858 0.046027 0.0304749 8.07379e-05 0.049027 0.0221808 0.00017892 0.0508456 0.00526845 7.81995e-05 0.0501987 -0.0176029 7.23261e-05 0.0394838 -0.0237812 0.000158798 0.0336922 -0.0288698 7.04328e-05 0.0268524 -0.0356068 0.00016288 0.0112903 -0.0370116 0.000262765 0.00289153 -0.0356358 0.000264563 0.0112975 -0.0328953 0.000160095 0.0193719 -0.0289282 0.00015788 0.0268896 -0.0176464 0.000161866 0.0395375 -0.0176654 0.000263106 0.039561 -0.0106133 0.000166001 0.0443452 -0.00293426 0.000170306 0.0479417 -0.0106276 0.000269028 0.0443702 0.00525514 0.000174171 0.0502659 0.0136861 0.000177125 0.0512399 0.00525012 0.000280613 0.0502913 0.0304943 0.000179462 0.0490923 0.0457656 0.000285127 0.0417412 0.0523005 0.000282525 0.0363239 0.0579041 0.000280354 0.0298943 0.0578833 0.000173988 0.0298789 -0.0369813 0.000161628 0.00288908 -0.0369125 7.22132e-05 0.00288352 -0.0377519 8.06587e-05 -0.0075975 -0.0368156 1.47304e-05 0.00287569 -0.0375447 -2.93696e-06 -0.00761277 -0.0423119 -2.93696e-06 -0.0787101 -0.0378436 0.000284883 -0.00759075 -0.037853 -2.93696e-06 -0.0114531 -0.0378198 0.00017913 -0.00759249 -0.0406005 1.57914e-05 -0.0481323 -0.0393014 -2.93696e-06 -0.0305576 -0.037651 1.66457e-05 -0.00760493 -0.0387548 -2.93696e-06 -0.0231067 -0.0429958 1.79263e-05 -0.0891902 -0.0428859 -2.93696e-06 -0.0891933 -0.0418362 1.54417e-05 -0.0686576 -0.0407021 7.91643e-05 -0.0481258 -0.0419371 7.75568e-05 -0.0686518 -0.0407709 0.000177478 -0.0481213 -0.0420061 0.000174103 -0.0686478 -0.043169 0.00019809 -0.0891855 -0.043102 8.90554e-05 -0.0891873 -0.0431438 9.00877e-05 -0.0901224 -0.0484807 -2.93696e-06 -0.190527 -0.0452958 -2.93696e-06 -0.132906 -0.0432094 0.000196986 -0.0901187 -0.0499943 0.000190946 -0.212829 -0.0430402 1.93263e-05 -0.0901282 -0.0497141 -2.93696e-06 -0.212844 -0.0513346 -2.93696e-06 -0.249204 -0.0525892 1.73447e-05 -0.262924 -0.0502643 -2.93696e-06 -0.224144 -0.0500084 -2.93696e-06 -0.218526 -0.0498238 1.79244e-05 -0.212838 -0.0499273 8.63759e-05 -0.212833 -0.0538126 0.000297063 -0.28161 -0.0527592 0.00018597 -0.262914 -0.053812 0.000278848 -0.28161 -0.0537554 0.000120727 -0.281613 -0.053773 0.000147924 -0.281612 -0.0526917 8.3879e-05 -0.262918 -0.0536631 3.73943e-05 -0.281618 -0.0498555 0.000297063 -0.281926 -0.0516135 0.0193284 -0.295479 -0.0515623 0.0194971 -0.295273 -0.0524138 0.0194971 -0.2999 -0.0521482 0.0194971 -0.29878 -0.0517291 0.014812 -0.287814 -0.0513109 0.0149493 -0.287712 -0.0511485 0.0115645 -0.284802 -0.051935 0.0173613 -0.291422 -0.0520647 0.0183844 -0.293696 -0.0519497 0.0189986 -0.295543 -0.0517469 0.0191303 -0.295521 -0.051686 0.0194971 -0.296441 -0.0513359 0.0178901 -0.291171 -0.0515145 0.0175229 -0.291358 -0.0517161 0.0174028 -0.291412 -0.0515116 0.0148482 -0.287793 0.0471496 0.0002911 -0.119085 0.0465232 0.00899707 -0.118959 0.0466032 0.00899706 -0.118351 0.0464528 0.00899706 -0.117182 0.0466491 0.00029273 -0.116403 0.0459151 0.00899706 -0.11612 0.0443735 0.000297063 -0.114895 0.0450492 0.00899706 -0.115294 0.0439586 0.00899706 -0.114802 0.0509308 0.00899706 -0.0990804 0.0502871 0.00899708 -0.100653 0.0499325 0.00899713 -0.101149 0.049559 0.000292726 -0.102112 0.0461068 0.000297063 -0.10303 0.0481573 0.00899719 -0.102533 -0.0498723 0.000297063 -0.269002 -0.0509003 0.000297063 -0.268316 -0.0509003 0.00899706 -0.268316 0.057275 0.00899706 -0.0715495 0.0334377 0.00899706 -0.176501 0.0339305 0.000291477 -0.174403 0.0341241 0.00504638 -0.175716 0.0344309 0.000289436 -0.177084 0.0344526 0.000289915 -0.175692 0.0341378 0.0046094 -0.177037 0.033628 0.00494657 -0.174388 0.0333704 0.00899706 -0.175321 0.0314508 0.00467785 -0.172852 0.0309236 0.00899706 -0.172709 -0.0422054 0.00466636 -0.162809 -0.0434868 0.00486344 -0.162992 -0.0427324 0.00899706 -0.163089 -0.044125 0.00899706 -0.164087 -0.0432335 0.00899706 -0.16334 -0.0447179 0.00899706 -0.165058 -0.0455208 0.00516454 -0.164856 -0.0446939 0.00504501 -0.163712 -0.0450265 0.000292658 -0.163636 -0.0438154 0.000294607 -0.162952 0.025593 0.00541686 -0.21442 0.0250906 0.0053558 -0.215602 0.0205912 0.00899706 -0.216998 0.0209686 0.00899706 -0.216989 0.0232474 0.00899706 -0.21615 0.0228622 0.00492718 -0.217102 0.0241226 0.0051834 -0.216581 0.0219425 0.000297063 -0.217177 0.0218087 0.00899706 -0.216856 0.0222264 0.00899706 -0.216723 0.0203977 0.00899706 -0.232492 0.0210406 0.00523636 -0.230342 0.0199124 0.00899706 -0.230078 0.0201237 0.00497909 -0.229341 0.0192557 0.00899706 -0.229281 0.0189917 0.00470096 -0.228809 0.0208532 0.000291502 -0.229587 0.0218754 0.000287593 -0.230917 0.0221589 0.000285836 -0.232605 0.0215031 0.00541024 -0.231632 -0.0456268 0.00899706 -0.220479 -0.0464274 0.00504816 -0.220271 -0.0489915 0.000292598 -0.222019 -0.0472102 0.00899706 -0.222145 -0.0483607 0.00552181 -0.222126 -0.0475764 0.00533152 -0.220997 -0.0481508 0.000293514 -0.220905 -0.0464645 0.00899706 -0.204605 -0.0464048 0.00899706 -0.205361 -0.0462823 0.00899706 -0.205811 -0.0459237 0.00899706 -0.206544 -0.0456221 0.00899706 -0.206949 -0.045752 0.00508925 -0.207741 -0.044601 0.00899706 -0.2078 -0.0445556 0.00477297 -0.208082 -0.0449327 0.000297063 -0.208061 -0.0462933 0.000295122 -0.20775 -0.0468127 0.00538174 -0.206902 -0.047473 0.00557905 -0.205702 -0.0483442 0.000292568 -0.204369 -0.0495677 0.00289199 -0.281859 -0.0493024 0.0194971 -0.281679 -0.0497313 0.00425012 -0.281989 -0.0501678 0.00661468 -0.282431 -0.0493024 0.000297063 -0.281679 -0.0488061 0.00949706 -0.281426 -0.0478325 0.000297063 -0.28118 -0.0487904 0.00941713 -0.28142 -0.0509659 0.0117929 -0.284469 -0.0508768 0.0106145 -0.283853 -0.0506914 0.00932893 -0.283291 -0.0505388 0.0194971 -0.282977 0.0431522 0.0247084 -0.0799922 0.0420587 0.0254179 -0.078589 0.0425755 0.0183971 -0.07915 0.0403019 0.0183971 -0.0774048 0.0374863 0.0183971 -0.0768686 0.0424642 0.0236712 -0.0859971 0.0418878 0.0183971 -0.0864716 0.0436533 0.0236519 -0.0841146 0.0438753 0.0183971 -0.0830804 0.0438944 0.0238316 -0.0828053 0.039177 0.0238852 -0.0898078 0.0398645 0.0183971 -0.088537 0.0398663 0.023895 -0.0885343 0.0407834 0.0238534 -0.0874059 -0.0273229 0.0183971 -0.0805395 -0.0349399 0.0205284 -0.0838048 -0.0344898 0.0183971 -0.0829972 -0.0344573 0.0212217 -0.0829484 -0.0324014 0.0183971 -0.0810342 -0.033729 0.0222921 -0.0820575 -0.0303023 0.0229413 -0.0949386 -0.0304048 0.0229318 -0.0944608 -0.031706 0.0183971 -0.0916952 -0.0314905 0.0218823 -0.114197 -0.0319594 0.0217313 -0.115236 -0.0238962 0.0229957 -0.120698 -0.0251354 0.0183971 -0.121938 -0.022421 0.0231679 -0.11977 -0.0207693 0.0233216 -0.119192 -0.0190332 0.0234455 -0.118996 0.0255613 0.0183971 -0.122902 0.0282427 0.0228152 -0.125045 0.0284365 0.0183971 -0.125101 0.0265079 0.0183971 -0.124066 0.0306248 0.0183971 -0.12515 0.0325981 0.0183971 -0.124203 0.0343272 0.0183971 -0.120313 0.0188032 0.0237662 -0.118997 0.0213445 0.0183971 -0.119423 0.0224474 0.0235772 -0.119901 0.0239237 0.0183971 -0.120913 0.0387325 0.0183971 -0.0911976 0.0431761 0.0183971 -0.0851206 0.0436866 0.0183971 -0.0812231 -0.0304499 0.0183971 -0.094287 -0.0190332 0.0183971 -0.118996 -0.0310262 0.0183971 -0.111943 -0.0224203 0.0183971 -0.11977 -0.0262963 0.0183971 -0.12298 -0.0325731 0.0183971 -0.116192 -0.0314851 0.0183971 -0.114182 0.0339284 0.0183971 -0.122465 0.0188032 0.0183971 -0.118997 -0.0133366 0.0183971 -0.0839948 -0.0334883 0.0183971 -0.0899549 0.0340117 0.0183971 -0.118846 0.0335013 0.0183971 -0.116619 -0.0296532 0.0183971 -0.0802203 -0.035389 0.0183971 -0.0851707 0.0336585 0.0183971 -0.114339 -0.0310262 0.0220723 -0.111943 -0.0301883 0.0183971 -0.0967643 0.0351993 0.0183971 -0.0774183 0.0216267 0.0183971 -0.0822494 -0.0273229 0.0282779 -0.0805395 -0.0196231 0.0283851 -0.0827526 0.00423585 0.0183971 -0.0849405 -0.0037765 0.0284334 -0.0849626 0.0454769 0.00249706 -0.105247 0.0441769 0.00249706 -0.106745 0.0436019 0.00249706 -0.105749 0.0422292 0.00249706 -0.110872 0.0441768 0.00249706 -0.111248 0.0454768 0.00249706 -0.111597 0.0454768 0.00249706 -0.112747 0.0467768 0.00249706 -0.111249 0.0477285 0.00249706 -0.110297 0.0492268 0.00249706 -0.108997 0.0473519 0.00249706 -0.105749 -0.046376 0.00249706 -0.211807 -0.045076 0.00249706 -0.210309 -0.0473277 0.00249706 -0.212759 -0.046951 0.00249706 -0.210811 -0.047676 0.00249706 -0.214059 -0.048826 0.00249706 -0.214059 -0.0463761 0.00249706 -0.216311 -0.0450761 0.00249706 -0.216659 -0.0437761 0.00249706 -0.216311 -0.0428244 0.00249706 -0.215359 -0.0432011 0.00249706 -0.217307 -0.0418285 0.00249706 -0.215934 -0.0418284 0.00249706 -0.212184 -0.043776 0.00249706 -0.211807 -0.043201 0.00249706 -0.210811 0.0119148 0.00249706 -0.273633 0.0129107 0.00249706 -0.274208 0.0122631 0.00249706 -0.272333 0.0119148 0.00249706 -0.271033 0.00966314 0.00249706 -0.269733 0.00966316 0.00249706 -0.268583 0.00836314 0.00249706 -0.270082 0.00741146 0.00249706 -0.271033 0.00706311 0.00249706 -0.272333 0.00641554 0.00249706 -0.270458 0.00966306 0.00249706 -0.276083 0.0109631 0.00249706 -0.274585 -0.0465769 0.00249706 -0.27846 -0.0462002 0.00249706 -0.276513 -0.0452043 0.00249706 -0.277088 -0.0447018 0.00249706 -0.275213 -0.0462002 0.00249706 -0.273912 -0.0471518 0.00249706 -0.272961 -0.0484518 0.00249706 -0.272612 -0.0503268 0.00249706 -0.271965 -0.0516994 0.00249706 -0.273337 -0.0516995 0.00249706 -0.277087 -0.0497519 0.00249706 -0.277464 -0.0484519 0.00249706 -0.277812 -0.0471519 0.00249706 -0.277464 -0.0360433 0.00249706 -0.0975286 -0.0353956 0.00249706 -0.0956536 -0.0373432 0.00249706 -0.0952769 -0.0367682 0.00249706 -0.094281 -0.0386432 0.00249706 -0.0949285 -0.0399432 0.00249706 -0.0952768 -0.0405182 0.00249706 -0.0942809 -0.0408949 0.00249706 -0.0962285 -0.0412433 0.00249706 -0.0975285 -0.0418908 0.00249706 -0.0956535 -0.0418909 0.00249706 -0.0994035 -0.0386433 0.00249706 -0.100129 -0.0386433 0.00249706 -0.101279 -0.0373433 0.00249706 -0.0997802 -0.0363916 0.00249706 -0.0988286 0.0327596 0.00249706 -0.164397 0.0314596 0.00249706 -0.164745 0.029512 0.00249706 -0.165122 0.0301596 0.00249706 -0.166997 0.0290096 0.00249706 -0.166997 0.0314596 0.00249706 -0.169248 0.0327595 0.00249706 -0.170747 0.0327596 0.00249706 -0.169597 0.0340596 0.00249706 -0.169248 0.0360072 0.00249706 -0.168872 -0.0441677 0.00249706 -0.155516 -0.0456661 0.00249706 -0.156816 -0.0451637 0.00249706 -0.158691 -0.0419161 0.00249706 -0.159416 -0.0400411 0.00249706 -0.160064 -0.0396644 0.00249706 -0.158116 -0.0386684 0.00249706 -0.154941 -0.040041 0.00249706 -0.153568 0.0191809 0.00249706 -0.220745 0.0178809 0.00249706 -0.222996 0.0191808 0.00249706 -0.225248 0.0186058 0.00249706 -0.226244 0.0204808 0.00249706 -0.225597 0.0204808 0.00249706 -0.226747 0.0230809 0.00249706 -0.222997 0.0237284 0.00249706 -0.224872 0.0242309 0.00249706 -0.222997 0.0223559 0.00249706 -0.219749 0.0204809 0.00249706 -0.220397 0.0621547 -0.00240294 -0.026572 0.0611047 -0.00240294 -0.0281784 0.0604422 -0.00240294 -0.0270309 0.060336 -0.00240294 -0.028947 0.0591885 -0.00240294 -0.0282845 0.0587296 -0.00240294 -0.029997 0.060336 -0.00240294 -0.031047 0.0591885 -0.00240294 -0.0317095 0.0611046 -0.00240294 -0.0318157 0.0621546 -0.00240294 -0.032097 0.0632046 -0.00240294 -0.0318157 0.0639733 -0.00240294 -0.0310471 0.0642546 -0.00240294 -0.0299971 0.0655796 -0.00240294 -0.0299971 0.0639733 -0.00240294 -0.0289471 0.0632047 -0.00240294 -0.0281784 -0.0357891 -0.00240294 -0.0207086 -0.0358953 -0.00240294 -0.0226248 -0.0370428 -0.00240294 -0.0219623 -0.0361767 -0.00240294 -0.0236748 -0.0358953 -0.00240294 -0.0247248 -0.0375017 -0.00240294 -0.0236748 -0.0370428 -0.00240294 -0.0253873 -0.0357892 -0.00240294 -0.0266409 -0.0340767 -0.00240294 -0.0257748 -0.0330267 -0.00240294 -0.0254935 -0.032258 -0.00240294 -0.0247248 -0.0311106 -0.00240294 -0.0253873 -0.0306517 -0.00240294 -0.0236748 -0.0319767 -0.00240294 -0.0236748 -0.0311105 -0.00240294 -0.0219623 -0.0330267 -0.00240294 -0.0218562 -0.0323641 -0.00240294 -0.0207087 -0.0340766 -0.00240294 -0.0215748 -0.00589787 -0.00240294 0.0435422 -0.00666656 -0.00240294 0.0406736 -0.00484792 -0.00240294 0.0396236 -0.00379792 -0.00240294 0.0399049 -0.00188178 -0.00240294 0.040011 -0.00302923 -0.00240294 0.0427735 -0.00313536 -0.00240294 0.0446897 -0.00484785 -0.00240294 0.0451486 0.0529573 -0.00240294 0.0289692 0.0525697 -0.00240294 0.0260031 0.0517036 -0.00240294 0.0242906 0.0536197 -0.00240294 0.0241844 0.0546697 -0.00240294 0.022578 0.0563822 -0.00240294 0.0230369 0.0564884 -0.00240294 0.024953 0.0576358 -0.00240294 0.0242905 0.0567697 -0.00240294 0.026003 0.0564884 -0.00240294 0.027053 0.0576359 -0.00240294 0.0277155 0.0563823 -0.00240294 0.0289692 -0.0486999 0.0199971 -0.279706 -0.047202 0.0199971 -0.279535 -0.0471553 0.028016 -0.279522 -0.0453195 0.0291686 -0.278443 -0.0449471 0.0293474 -0.278035 -0.0444327 0.0295631 -0.277236 -0.0440343 0.0199971 -0.274355 -0.0449806 0.0289778 -0.272349 -0.044968 0.0199971 -0.272364 -0.0462946 0.0279946 -0.271263 0.0106269 0.0199971 -0.267938 0.0122824 0.0222295 -0.277514 0.0126065 0.0200733 -0.277586 -0.0403946 0.0157285 -0.101939 -0.0413253 0.0132633 -0.101887 -0.0419002 0.00799706 -0.0928419 -0.0377977 0.019256 -0.101948 -0.0343469 0.00799706 -0.0988669 -0.0341853 0.0216211 -0.0981424 -0.0351642 0.0213429 -0.0946743 -0.0348312 0.0214838 -0.0951373 -0.0383952 0.0187977 -0.0930354 -0.0382884 0.0189341 -0.0930425 -0.0380936 0.0191647 -0.0930622 -0.037639 0.0196376 -0.093142 -0.0351594 0.00799706 -0.0946802 -0.0356304 0.0211153 -0.094186 -0.0463017 0.00799706 -0.162091 -0.0460461 0.00799706 -0.156596 -0.0456449 0.00799742 -0.151659 -0.0457324 0.00799767 -0.151474 -0.0445161 0.00799706 -0.156816 -0.0441678 0.00799706 -0.158116 -0.0406662 0.00799706 -0.161139 -0.0421641 0.00799706 -0.161309 -0.0432161 0.00799706 -0.159068 -0.0453884 0.00799706 -0.161145 -0.041668 0.00799706 -0.152323 -0.040616 0.00799706 -0.154564 -0.0396644 0.00799706 -0.155516 -0.0374985 0.00799706 -0.155959 -0.0393161 0.00799706 -0.156816 -0.0376197 0.00799706 -0.158154 -0.0406161 0.00799706 -0.159068 -0.0452174 0.00799706 -0.161141 -0.0436374 0.0117822 -0.152214 -0.0448196 0.00799706 -0.152149 -0.0407701 0.0163664 -0.161168 -0.0392328 0.0176176 -0.160428 -0.0387842 0.0179062 -0.160047 -0.0387669 0.00799706 -0.16003 -0.0384929 0.0180812 -0.159737 -0.0374268 0.0186844 -0.157127 -0.0384463 0.0182278 -0.153951 -0.0377291 0.0185859 -0.155167 -0.041668 0.0151899 -0.152323 -0.040198 0.00799706 -0.152657 -0.0384322 0.00799706 -0.153968 -0.0388007 0.0180204 -0.153569 -0.0453241 0.0125319 -0.218552 -0.0462259 0.0103181 -0.209489 -0.044828 0.00799706 -0.209566 -0.0451282 0.0128569 -0.218559 -0.0453241 0.00799706 -0.218552 -0.0438261 0.00799706 -0.218382 -0.042214 0.0162109 -0.217532 -0.0419269 0.00799706 -0.217273 -0.0419486 0.0164069 -0.217295 -0.0417144 0.0165673 -0.217051 -0.0407987 0.017074 -0.215457 -0.0409009 0.0168033 -0.21238 -0.0415922 0.00799706 -0.211211 -0.0419657 0.0158998 -0.210807 -0.0416083 0.0162129 -0.211191 -0.0435296 0.0142811 -0.209833 0.023949 0.00799706 -0.21915 0.0171555 0.0164126 -0.226874 0.0179139 0.0155873 -0.227041 0.0183809 0.0148829 -0.227143 0.01892 0.0139237 -0.227262 0.019222 0.0133403 -0.227328 0.0337234 0.0164891 -0.162601 0.0358616 0.012472 -0.16307 0.0480768 0.00799706 -0.108997 0.0477285 0.00799706 -0.107697 0.0510717 0.00799706 -0.104594 0.0502443 0.00799848 -0.105366 0.0477285 0.00799706 -0.110297 0.0486123 0.00799713 -0.114669 0.0487072 0.0079974 -0.114958 0.0498861 0.00799706 -0.109965 0.0498752 0.00799706 -0.105354 0.0467768 0.00799706 -0.111249 0.0445131 0.00799706 -0.113392 0.0431154 0.00799706 -0.112827 0.0432252 0.00799706 -0.110297 0.0415821 0.00799706 -0.111251 0.04145 0.00799706 -0.106988 0.0454769 0.00799706 -0.106397 0.0464406 0.00799706 -0.104601 0.0480344 0.016577 -0.104951 0.0489237 0.0138122 -0.105146 0.0479284 0.00799706 -0.114141 0.0445131 0.0187396 -0.113392 0.0108863 0.000297063 -0.266971 0.0108788 0.00464708 -0.266969 0.0117961 0.00899706 -0.267045 0.0135889 0.000296816 -0.266482 0.0135697 0.00899706 -0.266458 0.0122883 0.000296928 -0.267003 0.0129435 0.00899706 -0.266791 0.0146793 0.00899706 -0.265256 0.015072 0.00899706 -0.264149 -0.0393717 0.00899706 -0.103588 -0.0420069 0.00899706 -0.105724 -0.0417493 0.000290051 -0.10435 -0.0405385 0.00029323 -0.103666 -0.0404852 0.00899706 -0.103994 -0.0425979 0.000287992 -0.105451 -0.0422575 0.00899706 -0.106862 -0.044988 0.000297063 -0.280112 -0.044988 0.00899706 -0.280112 -0.043032 0.00899706 -0.277786 -0.042466 0.00899706 -0.274801 -0.045691 0.00899706 -0.269885 -0.045691 0.000297063 -0.269885 -0.048655 0.000297063 -0.269216 -0.0451944 0.00474125 -0.220058 -0.044176 0.00899706 -0.219991 -0.0436049 0.000297063 -0.219876 -0.040959 0.00899706 -0.218424 -0.0393549 0.00899706 -0.215867 -0.0393549 0.000297063 -0.215867 -0.0405293 0.00899706 -0.210144 -0.0405293 0.000297063 -0.210144 -0.0430107 0.00899706 -0.208426 -0.0430107 0.000297063 -0.208426 -0.0414985 0.00899706 -0.162801 -0.0404781 0.000297063 -0.162641 -0.0404781 0.00899706 -0.162641 -0.0378199 0.00899706 -0.1612 -0.036035 0.000297063 -0.155627 -0.036035 0.00899706 -0.155627 -0.0373616 0.00899706 -0.15291 -0.0373616 0.000297063 -0.15291 -0.0415801 0.00469782 -0.150825 -0.0543255 0.0191488 -0.296402 -0.05217 0.018955 -0.295542 -0.0536831 0.0114914 -0.284956 -0.0535901 0.00838977 -0.283298 -0.0498555 0.00149706 -0.281926 0.0134205 0.0197971 -0.278542 0.0134205 0.000297063 -0.278542 0.0121813 0.000297063 -0.28106 0.0129668 0.019502 -0.279464 -0.0511301 0.0152559 -0.287443 -0.0512212 0.0165943 -0.289095 -0.0509659 0.0194971 -0.284469 0.00420173 0.00899706 -0.271683 0.0049463 0.00899706 -0.269505 0.00651707 0.00899706 -0.267822 0.00649442 0.000297063 -0.267838 0.0586185 0.000297063 -0.0618887 0.0570732 0.000297063 -0.0706734 -0.0288773 0.00899706 -0.0269691 -0.0288773 0.000297063 -0.0269691 -0.0353223 0.00899706 -0.0373974 -0.0371655 0.000297063 -0.0432655 -0.0334838 0.00899706 -0.00790263 -0.0324725 0.000297063 -0.0113627 -0.0309868 0.000297063 0.0149527 -0.0338021 0.000297063 0.00641437 -0.0340915 0.00899706 0.00463472 -0.0334838 0.000297063 -0.00790263 -0.00250822 0.000297063 0.0343125 0.0133577 0.000297063 0.0317024 0.00646703 0.000297063 0.0337895 0.0238404 0.000297063 0.0247983 0.0284791 0.000297063 0.019292 0.0311484 0.00899706 0.014593 0.0343086 0.00899706 0.00244528 0.0343086 0.000297063 0.00244528 0.0565726 0.000297063 -0.0758776 0.0558641 0.000299886 -0.0791694 0.0214619 0.00547307 -0.232911 0.0220803 0.000285781 -0.233111 0.0183861 0.000292845 -0.248596 0.0186882 0.00502334 -0.246311 0.0208205 0.00479208 -0.236554 -0.0487018 0.00539026 -0.223349 -0.0497086 0.00496193 -0.238854 -0.0501957 0.00899706 -0.248238 -0.0489816 0.00899706 -0.236441 -0.0515823 0.00464706 -0.262979 -0.0503479 0.000296542 -0.24803 -0.0498954 0.00029541 -0.238806 -0.0516672 0.000297063 -0.264516 -0.051752 0.00464706 -0.266052 -0.051752 0.00899706 -0.266052 -0.0294872 0.0349971 -0.029478 -0.065244 0.0349971 -0.0449219 -0.0496331 0.0349971 0.068703 -0.00984246 0.0349971 0.0841808 0.0486279 0.0349971 0.0694115 0.0710953 0.0349971 -0.0461195 0.0567798 0.0349971 -0.0629095 0.0565614 0.0349971 -0.0565638 -0.0380414 0.0349971 -0.0757311 -0.0442748 0.0349971 -0.0706987 -0.0567908 0.0349971 -0.0629081 -0.0694391 0.0349971 -0.0485907 -0.0707082 0.0349971 -0.0442646 -0.0711058 0.0349971 -0.0461177 -5.04421e-06 0.0349971 -0.0294784 -0.0200868 0.0349971 -0.0200778 -0.0284047 0.0349971 4.11317e-06 -0.0294863 0.0349971 0.0387995 -4.30321e-06 0.0349971 0.0284037 0.0262334 0.0349971 -0.0108648 0.0387907 0.0349971 3.25294e-06 0.0200774 0.0349971 0.0200853 -0.0826037 0.0349971 -0.00418332 -0.0828851 0.0349971 -0.00523332 -0.0834673 0.0349971 -0.0147119 -0.0807851 0.0349971 -0.00733335 -0.0797351 0.0349971 -0.00705201 -0.0786851 0.0349971 -0.00523337 -0.0758909 0.0349971 -0.0337096 -0.0740722 0.0349971 -0.0305596 -0.0794202 0.0349971 -0.0295891 -0.0721094 0.0349971 -0.0445324 -0.070708 0.0349971 -0.0294775 -0.0684355 0.0349971 -0.0484646 -0.0645702 0.0349971 -0.0548948 0.00523246 0.0349971 -0.0786767 0.00341379 0.0349971 -0.0797266 0.00341376 0.0349971 -0.0818266 0.0178842 0.0349971 -0.0828368 0.0041824 0.0349971 -0.0825953 0.00705107 0.0349971 -0.0818267 0.00733243 0.0349971 -0.0807767 0.00705109 0.0349971 -0.0797267 0.0316087 0.0349971 -0.0722452 0.0380301 0.0349971 -0.0757321 0.0344773 0.0349971 -0.0751139 0.0326587 0.0349971 -0.0761638 0.0337087 0.0349971 -0.0758825 0.0337087 0.0349971 -0.0722452 0.0178635 0.0349971 -0.0706994 0.0305587 0.0349971 -0.0740638 0.03084 0.0349971 -0.0751138 0.019539 0.0349971 -0.0824621 0.0487558 0.0349971 -0.0693142 0.0494133 0.0349971 -0.068847 0.0347587 0.0349971 -0.0740639 0.0388454 0.0349971 -0.0753171 0.043871 0.0349971 -0.0691542 0.0459949 0.0349971 -0.0711763 0.044921 0.0349971 -0.0694356 0.0544708 0.0349971 -0.0649192 0.0484637 0.0349971 -0.0684271 0.0552006 0.0349971 -0.0642998 0.0774191 0.0349971 2.75842e-06 0.0828758 0.0349971 0.00524082 0.0838105 0.0349971 2.6766e-06 0.0842128 0.0349971 0.00948985 0.0811853 0.0349971 0.0243093 0.0807758 0.0349971 0.00734084 0.0786757 0.0349971 0.00524087 0.0797257 0.0349971 0.0034222 0.0807757 0.0349971 0.00314084 0.0733915 0.0349971 0.0423778 0.0779451 0.0349971 0.0332663 0.0730129 0.0349971 0.0344858 0.0722443 0.0349971 0.0337171 0.0730129 0.0349971 0.0308485 0.0740629 0.0349971 0.0305671 0.0758816 0.0349971 0.0316171 0.0684262 0.0349971 0.0484721 0.0683847 0.0349971 0.0467481 0.0694347 0.0349971 0.0449294 0.0691533 0.0349971 0.0438794 0.0568922 0.0349971 0.0628154 0.0499081 0.0349971 0.0653248 0.0387917 0.0349971 0.0707062 -0.0294858 0.0349971 0.0774279 -0.00629174 0.0349971 0.0826028 -0.00706043 0.0349971 0.0797342 -0.00524179 0.0349971 0.0786842 -0.00314176 0.0349971 0.0807841 -0.033718 0.0349971 0.07589 -0.032668 0.0349971 0.0761713 -0.044273 0.0349971 0.0707073 -0.0335942 0.0349971 0.0778132 -0.033718 0.0349971 0.0722527 -0.0308494 0.0349971 0.0730213 -0.0486355 0.0349971 0.0694127 -0.0568999 0.0349971 0.0628169 -0.0616488 0.0349971 0.0581635 -0.0642757 0.0349971 0.0496351 -0.0663757 0.0349971 0.0496352 -0.0688829 0.0349971 0.0493834 -0.0684343 0.0349971 0.0484738 -0.0846112 0.0349971 0.00493261 -0.0707076 0.0349971 4.65473e-06 -0.0797351 0.0349971 -0.00341471 -0.0294861 0.0349971 0.0565709 -0.046749 0.0349971 0.0683931 -0.048473 0.0349971 0.0684346 -0.0484732 0.0349971 0.0565712 -0.046749 0.0349971 0.0662931 -0.0428303 0.0349971 0.0673431 -0.0294859 0.0349971 0.0684344 -0.0294859 0.0349971 0.0707071 -0.0449303 0.0349971 0.0694431 -0.0635071 0.0349971 0.0467665 -0.0630013 0.0349971 0.0566958 -0.0635071 0.0349971 0.0488665 -0.0565708 0.0349971 0.0484737 -0.068394 0.0349971 -0.0467406 -0.066294 0.0349971 -0.0467406 -0.0655254 0.0349971 -0.0459719 -0.069444 0.0349971 -0.0449219 -0.0691627 0.0349971 -0.0438719 -0.0494244 0.0349971 -0.0688458 -0.0484748 0.0349971 -0.0684259 -0.0478174 0.0349971 -0.0632173 -0.0484746 0.0349971 -0.0565624 0.045971 0.0349971 -0.065517 0.044921 0.0349971 -0.0652356 0.0467396 0.0349971 -0.0683856 0.047021 0.0349971 -0.0673356 0.0467397 0.0349971 -0.0662856 0.0484637 0.0349971 -0.0642271 0.0565616 0.0349971 -0.0442662 0.0565615 0.0349971 -0.0484662 0.0632164 0.0349971 -0.047809 0.062759 0.0349971 -0.0569461 0.0653164 0.0349971 -0.049909 0.0663664 0.0349971 -0.0496277 0.0674164 0.0349971 -0.047809 0.0565628 0.0349971 0.0484722 0.0652347 0.0349971 0.0449294 0.065516 0.0349971 0.0438794 0.0496267 0.0349971 0.0663748 0.0488581 0.0349971 0.0671435 0.0484654 0.0349971 0.0684334 0.0478081 0.0349971 0.0674248 0.0467039 0.0349971 0.0707206 0.0387916 0.0349971 0.0684335 0.0467581 0.0349971 0.0671435 0.0457081 0.0349971 0.0653249 0.0459894 0.0349971 0.0642749 -0.056571 0.0349971 0.0387999 -0.0565707 0.0349971 0.0565713 -4.04629e-06 0.0349971 0.048473 -3.79075e-06 0.0349971 0.068434 -3.67561e-06 0.0349971 0.0774275 -3.59379e-06 0.0349971 0.0838189 0.0178654 0.0349971 0.0774273 -3.76165e-06 0.0349971 0.0707067 0.0178653 0.0349971 0.0684338 0.0178651 0.0349971 0.0565703 -3.94262e-06 0.0349971 0.0565706 0.017865 0.0349971 0.0484727 -4.17013e-06 0.0349971 0.0387992 0.0289826 0.0349971 0.0796423 0.0178653 0.0349971 0.0707065 0.0178649 0.0349971 0.0387989 0.0387912 0.0349971 0.0387987 -0.0484737 0.0349971 0.0178734 -0.0442737 0.0349971 0.0178734 -0.0484734 0.0349971 0.0387998 -0.0484733 0.0349971 0.0484736 -0.0442732 0.0349971 0.0565711 -0.0294868 0.0349971 4.12702e-06 -0.0294866 0.0349971 0.0178732 -0.0442734 0.0349971 0.0387997 -0.0442733 0.0349971 0.0484735 -0.0294862 0.0349971 0.0484733 -0.067344 0.0349971 -0.0428219 -0.0684353 0.0349971 -0.0294775 -0.0642353 0.0349971 -0.0294776 -0.0707074 0.0349971 0.0178737 0.072099 0.0349971 -0.0445342 0.0706979 0.0349971 -0.0294793 0.0774187 0.0349971 -0.0294794 0.0706983 0.0349971 2.84446e-06 0.0774193 0.0349971 0.0178718 0.0706985 0.0349971 0.0178719 0.017864 0.0349971 -0.0294786 0.0108632 0.0349971 -0.0262346 0.0565618 0.0349971 -0.0294791 0.0684252 0.0349971 -0.0294793 0.0565621 0.0349971 3.02543e-06 0.0684256 0.0349971 2.87356e-06 0.0565626 0.0349971 0.0387984 0.0684261 0.0349971 0.0387983 0.0684249 0.0349971 -0.0484663 0.068425 0.0349971 -0.0442663 0.0706977 0.0349971 -0.0442664 0.0684258 0.0349971 0.0178719 0.0706988 0.0349971 0.0387983 -0.0642355 0.0349971 -0.0484646 0.0387901 0.0349971 -0.048466 0.0178638 0.0349971 -0.0484657 0.0178638 0.0349971 -0.0442657 0.0387902 0.0349971 -0.044266 -0.0565722 0.0349971 -0.0565623 -0.0565721 0.0349971 -0.0484647 -0.0544817 0.0349971 -0.0649178 -0.0499174 0.0349971 -0.0653173 -0.0496361 0.0349971 -0.0663673 -0.0642355 0.0349971 -0.0442646 -0.056572 0.0349971 -0.0442647 -0.0484745 0.0349971 -0.0484648 -0.0642344 0.0349971 0.0388 -0.0484739 0.0349971 4.37009e-06 -0.0442739 0.0349971 4.31632e-06 -0.0294874 0.0349971 -0.0442651 -5.28728e-06 0.0349971 -0.0484655 -5.23351e-06 0.0349971 -0.0442655 0.03879 0.0349971 -0.0565635 0.0484638 0.0349971 -0.0565637 0.0484639 0.0349971 -0.0484661 0.0484648 0.0349971 0.0178722 0.0565624 0.0349971 0.0178721 0.048465 0.0349971 0.0387985 0.0565629 0.0349971 0.0565698 -0.0684344 0.0349971 0.0388 -0.0565712 0.0349971 0.0178735 -0.0565715 0.0349971 4.47376e-06 -0.0484743 0.0349971 -0.0294778 -0.0442743 0.0349971 -0.0294778 -0.0294874 0.0349971 -0.0484651 0.0178637 0.0349971 -0.0565633 0.0387899 0.0349971 -0.064227 0.048464 0.0349971 -0.0442661 0.0387904 0.0349971 -0.0294789 0.0484642 0.0349971 -0.029479 0.0484645 0.0349971 3.1291e-06 0.038791 0.0349971 0.0178723 0.0387914 0.0349971 0.0484725 0.0484652 0.0349971 0.0484723 0.0387915 0.0349971 0.0565701 0.0484653 0.0349971 0.0565699 0.046758 0.0349971 0.0635062 -0.0707071 0.0349971 0.0388001 -0.0684347 0.0349971 0.0178737 -0.0642347 0.0349971 0.0178736 -0.0642349 0.0349971 4.57186e-06 -0.0484744 0.0349971 -0.0442648 -0.0442744 0.0349971 -0.0442649 -0.0442745 0.0349971 -0.0484649 -0.0294875 0.0349971 -0.0565627 -5.39095e-06 0.0349971 -0.0565631 0.0178636 0.0349971 -0.0642267 0.0178635 0.0349971 -0.0684267 0.0387899 0.0349971 -0.068427 0.0387898 0.0349971 -0.0706997 -0.0294877 0.0349971 -0.0706988 -0.0442748 0.0349971 -0.0684259 -0.0457174 0.0349971 -0.0653174 0.00628245 0.0349971 -0.078958 -5.57192e-06 0.0349971 -0.0706992 -0.0294876 0.0349971 -0.0642261 -0.0294877 0.0349971 -0.0684261 -0.0442747 0.0349971 -0.0642259 -0.0459987 0.0349971 -0.0642674 0.0326587 0.0349971 -0.0719638 -5.54282e-06 0.0349971 -0.0684265 -5.48905e-06 0.0349971 -0.0642265 -0.0442746 0.0349971 -0.0565625 -0.0565718 0.0349971 -0.0294777 -0.0684349 0.0349971 4.62563e-06 -0.0382986 0.0192618 -0.140713 0.0247028 0.00622747 -0.223014 -0.0366222 0.0210974 -0.102453 -0.0309076 0.0234279 -0.0950489 -0.030799 0.0233801 -0.0967575 -0.0331103 0.0220198 -0.115909 -0.0353806 0.0220224 -0.0934763 -0.0321077 0.0231418 -0.0946503 -0.0351615 0.0218331 -0.101468 -0.0342474 0.0224471 -0.0947914 -0.0419043 0.0138418 -0.0918627 -0.0419097 0.0136732 -0.0907375 -0.0407537 0.0170369 -0.0912625 -0.0481858 0.00645349 -0.194319 -0.0489793 0.000301848 -0.194113 -0.0500136 0.000301135 -0.212828 -0.0491414 0.0062151 -0.212947 -0.0457017 0.0123387 -0.194917 -0.0413308 0.0168637 -0.195879 -0.0438333 0.0150463 -0.208888 -0.0437564 0.0148439 -0.195355 -0.0463245 0.0119998 -0.208498 -0.0420418 0.0165749 -0.209893 -0.0407741 0.0174661 -0.211377 -0.0368678 0.0195002 -0.21462 -0.0347265 0.0202426 -0.214912 -0.0247311 0.0222804 -0.216275 -0.010061 0.0219337 -0.201709 -0.0230091 0.0215612 -0.199583 -0.0221745 0.0225604 -0.216623 0.00304977 0.0215279 -0.20314 -0.00444657 0.0227425 -0.21904 0.021952 0.0169997 -0.204509 0.00409661 0.0217126 -0.220205 0.00976854 0.0203633 -0.220978 0.0123585 0.0194728 -0.221331 0.0165912 0.0176509 -0.219777 0.0232676 0.0120616 -0.218006 0.0224211 0.013278 -0.217825 0.0245049 0.0150243 -0.204663 0.0204064 0.0153796 -0.217716 0.0264547 0.0124665 -0.204756 0.0251987 0.00799706 -0.218413 0.0504829 0.012168 -0.104468 0.0557941 0.00819862 -0.0829209 0.0473545 0.019787 -0.103798 0.0513226 0.0201917 -0.0857606 0.0428251 0.0237268 -0.0903044 0.040608 0.0227087 -0.107108 0.0345631 0.0229698 -0.118706 0.030664 0.0208453 -0.150614 0.0341332 0.0226514 -0.123355 0.0323549 0.0228116 -0.125074 0.0251635 0.0237252 -0.123184 0.0259341 0.0236013 -0.124203 0.0119912 0.0227828 -0.15045 -0.000119933 0.0244298 -0.119523 -0.0245867 0.0224897 -0.144581 -0.0222494 0.0236654 -0.120242 -0.031656 0.0221128 -0.123454 -0.0457873 0.00799706 -0.151102 -0.0452893 0.00733675 -0.138273 -0.0458756 0.00030454 -0.13796 -0.0445594 0.0120349 -0.15118 -0.0437233 0.013799 -0.151233 -0.0411211 0.017147 -0.139869 -0.043168 0.014235 -0.139178 -0.0444908 0.0108818 -0.13865 -0.0423716 0.0134336 -0.102852 -0.0434063 0.00799706 -0.102779 -0.0432263 0.000308201 -0.0901178 -0.0369372 0.0195932 -0.155534 -0.0379877 0.0191834 -0.153468 -0.0341151 0.0215787 -0.119742 -0.0338631 0.0217447 -0.117291 -0.047239 0.00673745 -0.17576 -0.0429365 0.0155388 -0.177527 -0.0397812 0.0181076 -0.161641 0.036912 0.00799706 -0.167915 0.0328728 0.00677643 -0.186683 0.0410465 0.00738466 -0.150044 0.0403423 0.0110029 -0.150217 0.0370401 0.0126574 -0.162324 0.0336562 0.0144847 -0.172856 0.0306981 0.0131323 -0.187096 0.0287323 0.0158683 -0.187303 0.0322927 0.016512 -0.172568 0.0259582 0.0178338 -0.187454 0.0372874 0.0176169 -0.150563 0.0342432 0.0175625 -0.161744 0.0294729 0.0198356 -0.162956 0.0269915 0.0216056 -0.150622 0.0285934 0.020012 -0.163886 0.0361153 0.015001 -0.162131 0.0392376 0.0145065 -0.150416 0.0429305 0.0210487 -0.113742 0.0342011 0.0196539 -0.150603 0.0416236 0.000303315 -0.149889 0.0251511 0.00420908 -0.223075 0.0126401 0.0211675 -0.187938 0.0195104 0.0224325 -0.150603 0.019485 0.0200757 -0.187722 0.027547 0.0199697 -0.167136 0.00958171 0.0208333 -0.203664 0.0159836 0.0195012 -0.204116 -0.0350343 0.0205946 -0.141649 -0.0316094 0.0214683 -0.142624 -0.0214791 0.0217595 -0.184277 -0.0174538 0.0228944 -0.146426 -0.0355877 0.0194636 -0.197082 -0.0293751 0.020847 -0.198349 -0.0344306 0.0199737 -0.180361 -0.0280294 0.0211964 -0.182382 0.00570895 0.0216897 -0.187995 -0.0080703 0.0219714 -0.187089 -0.00291838 0.0229605 -0.149264 0.0218152 0.0241086 -0.120167 -0.0479448 0.000302593 -0.175396 -0.0463052 0.00993808 -0.176195 -0.044893 0.0129251 -0.176787 -0.0375115 0.0189761 -0.179358 -0.0404128 0.0175621 -0.178398 -0.0378663 0.0191232 -0.160059 0.0165957 0.00964744 -0.262338 0.0208653 0.0122267 -0.227688 0.0182256 0.0154257 -0.227109 0.0198914 0.0122662 -0.233914 0.0187978 0.0127636 -0.244094 0.0175254 0.0165254 -0.243932 0.0164037 0.0189699 -0.262316 0.0148264 0.000297063 -0.27213 0.017985 0.00918887 -0.254443 0.0204067 0.00449763 -0.244327 0.0206465 0.000303555 -0.244361 0.0197972 0.00872498 -0.244237 0.0215978 0.0084971 -0.234161 0.022983 0.00799706 -0.228152 0.0176736 0.0136272 -0.254404 0.0175352 0.0167898 -0.245991 0.0172851 0.0179211 -0.254353 -0.0114352 0.0319971 -0.26855 -0.0190578 0.0319971 -0.267511 0.0177842 0.0154822 -0.231613 0.0164981 0.0188788 -0.261612 -0.00304591 0.0319946 -0.269693 -0.0486346 0.0143739 -0.235035 -0.0441803 0.0168258 -0.225223 -0.0419858 0.0171247 -0.218051 -0.0525029 0.0196264 -0.262951 -0.0523688 0.0166863 -0.25841 -0.049887 0.0251754 -0.263308 -0.0491411 0.0260649 -0.26341 -4.84828e-06 0.0318216 -0.270105 0.0034457 0.0311755 -0.270579 0.00752463 0.0295588 -0.267373 0.00573184 0.0301452 -0.266294 0.00572692 0.0304147 -0.268807 0.0129916 0.0257685 -0.267281 0.0155578 0.0199971 -0.267928 0.015482 0.0208368 -0.267901 0.015327 0.0217338 -0.267635 0.0151498 0.0222301 -0.267803 0.0142665 0.0241003 -0.267582 0.0156344 0.0177027 -0.224261 0.0151946 0.0178463 -0.22765 0.0115023 0.0198369 -0.227178 0.00344641 0.0222649 -0.226093 -0.0122759 0.0229971 -0.217973 -8.00103e-05 0.0223353 -0.219635 -0.0317561 0.0210409 -0.215317 -0.023967 0.0240373 -0.22803 -0.016825 0.0229105 -0.217353 -0.0408238 0.0194911 -0.225719 -0.0483107 0.0142619 -0.233568 -0.0468726 0.0180065 -0.235175 -0.0369272 0.0213988 -0.226276 -0.0350862 0.0251526 -0.236791 -0.0327505 0.0226767 -0.226854 -0.00581466 0.0242467 -0.230498 -0.0148639 0.0245082 -0.229255 -0.0162786 0.0262921 -0.239327 -0.0257084 0.026051 -0.238052 -0.0304036 0.0257681 -0.237418 0.00300995 0.0231685 -0.231728 0.0112899 0.0205679 -0.232843 0.0153697 0.0200338 -0.243666 0.0149776 0.0183105 -0.233308 0.0176618 0.0155691 -0.233625 0.00755174 0.0212551 -0.226653 0.00723998 0.0221242 -0.232307 0.00256457 0.0255673 -0.241917 0.000594778 0.0312158 -0.265588 0.00637376 0.02909 -0.260895 0.0156177 0.0196391 -0.267676 0.0142452 0.0241446 -0.267481 0.0168493 0.0198606 -0.254295 0.0160772 0.0210203 -0.262269 0.0149493 0.0233756 -0.262106 0.0117851 0.0253967 -0.253571 0.0111552 0.0269536 -0.261565 0.00206284 0.0282216 -0.252214 -0.0088848 0.030088 -0.258814 0.00125796 0.0300573 -0.260189 -0.0195407 0.0313093 -0.26285 -0.00959352 0.0313245 -0.264205 -0.0348929 0.0319954 -0.265352 -0.0514591 0.0212826 -0.258531 -0.0486118 0.0256919 -0.258907 -0.0444315 0.0289002 -0.259464 -0.0395425 0.0307745 -0.26012 -0.0436338 0.0279289 -0.254093 -0.0336317 0.0301564 -0.255434 -0.045023 0.0293591 -0.263971 -0.0399949 0.0313731 -0.264656 -0.0344132 0.0313531 -0.260816 -0.0293868 0.0313336 -0.261505 -0.0188032 0.0300524 -0.257464 -0.00790254 0.0282964 -0.25086 -0.0507632 0.0206038 -0.253159 -0.0506337 0.015293 -0.245099 -0.0478504 0.0248716 -0.253539 -0.0464339 0.0235079 -0.245656 -0.0387437 0.0296702 -0.254742 -0.0373855 0.027876 -0.246844 -0.0286259 0.0301073 -0.256122 -0.032368 0.0283069 -0.247519 -0.0274378 0.0282979 -0.248196 -0.0177078 0.0282755 -0.249524 0.0167735 0.0181666 -0.243845 0.0115854 0.0228498 -0.243159 0.0156292 0.022082 -0.254121 0.00718842 0.0246059 -0.242556 0.00706871 0.0273431 -0.252908 -0.00683838 0.0261646 -0.24062 -0.0396012 0.023735 -0.236183 -0.0436817 0.0213667 -0.235626 -0.0422084 0.0263093 -0.246208 -0.0494567 0.0195255 -0.24526 -0.0527805 0.0169965 -0.262913 -0.0465293 0.0138265 -0.224874 -0.0482439 0.0106963 -0.224833 -0.0461865 0.0131147 -0.219458 -0.0518905 0.00803552 -0.253061 -0.0513308 0.00029789 -0.244504 -0.0496192 0.00420955 -0.212882 -0.0515507 0.0159602 -0.251519 -0.0508041 0.0038076 -0.23474 -0.0488968 0.00799706 -0.219346 -0.049519 0.00729224 -0.224668 -0.0503338 0.00740606 -0.2348 -0.0511668 0.00769783 -0.245093 0.0147881 0.0199971 -0.272305 0.0113713 0.0197971 -0.287888 0.011921 0.0202721 -0.285381 0.00836936 0.0216523 -0.308922 0.00836934 0.0197971 -0.308921 0.00843243 0.0197971 -0.301303 0.0131092 0.0227344 -0.320796 0.00880121 0.0217848 -0.310761 0.0184232 0.0243199 -0.332524 0.0218897 0.0197971 -0.340176 0.0225134 0.0254282 -0.341707 0.022686 0.0197971 -0.342192 0.0237574 0.0197971 -0.346656 0.0237308 0.025795 -0.346473 0.0239865 0.0197971 -0.350459 0.0235507 0.0259964 -0.354571 0.0172782 0.0259971 -0.366644 0.0174583 0.0259971 -0.366455 0.018275 0.0197971 -0.365543 0.0222108 0.0259969 -0.359067 0.0223491 0.0259968 -0.35872 0.0222108 0.0197971 -0.359067 0.00188559 0.0197971 -0.373921 0.0103656 0.0259971 -0.371638 0.0103656 0.0197971 -0.371638 -0.00685167 0.0197971 -0.373 -0.00108544 0.0259971 -0.373972 -0.017561 0.0197971 -0.366364 -0.0153207 0.0259971 -0.368477 -0.0146587 0.0197971 -0.369006 -0.0124055 0.0197971 -0.370548 -0.00685167 0.0259971 -0.373 -0.00612601 0.0259971 -0.373204 -0.0207104 0.0197971 -0.362603 -0.0286665 0.0197971 -0.352908 -0.0427099 0.0257458 -0.335796 -0.034187 0.0197971 -0.346181 -0.0453251 0.0197971 -0.33244 -0.0529581 0.0235855 -0.316619 -0.0544681 0.0225664 -0.309292 -0.0548228 0.0197971 -0.29991 -0.0548878 0.0214656 -0.301663 -0.0545759 0.0204913 -0.295437 -0.054625 0.019443 -0.296327 -0.0542137 0.0194577 -0.288876 -0.0544356 0.0183997 -0.292896 -0.0539826 0.011658 -0.28469 -0.0527805 0.000297063 -0.262913 0.0173905 0.0319971 -0.354608 0.0171309 0.0319971 -0.345458 0.0152225 0.0319971 -0.341548 0.00475403 0.0319971 -0.347246 -0.00127861 0.0319971 -0.313636 -0.0365977 0.0319971 -0.282648 -0.0399394 0.0319971 -0.305543 0.00549085 0.0319971 -0.349996 0.017824 0.0319971 -0.348357 0.0179337 0.0319971 -0.351353 0.00475396 0.0319971 -0.352746 -0.00385069 0.0319971 -0.275531 0.00849675 0.0319971 -0.365859 0.00274079 0.0319971 -0.354759 0.00573725 0.0319971 -0.367054 -9.21786e-06 0.0319971 -0.355496 -0.000178606 0.0319971 -0.367995 -0.00275921 0.0319971 -0.354759 -0.0111408 0.0319971 -0.363817 -0.00477232 0.0319971 -0.352746 -0.0142542 0.0319971 -0.359875 -0.00477225 0.0319971 -0.347246 -0.0325918 0.0319971 -0.331209 -0.0392326 0.0319971 -0.316133 -0.00275909 0.0319971 -0.345233 -0.0400297 0.0319971 -0.307529 0.00229131 0.0314481 -0.270421 -0.00420481 0.0319971 -0.283696 0.000941164 0.0312787 -0.307369 -0.00389863 0.0319971 -0.299079 -0.00314751 0.0319971 -0.307684 -0.00287249 0.0319971 -0.30885 0.00238703 0.0312978 -0.312591 0.00652379 0.0313419 -0.320591 0.000833145 0.0319971 -0.317867 0.0143229 0.0314737 -0.334677 0.0180604 0.031536 -0.341793 0.0177517 0.0319971 -0.347885 0.0201115 0.0315857 -0.351518 0.017463 0.0319971 -0.354325 0.0150752 0.0319971 -0.359816 0.0142861 0.0319971 -0.360933 0.0110169 0.0319971 -0.364223 0.0123535 0.0315863 -0.365947 0.00643394 0.0315863 -0.369121 0.00316288 0.0315863 -0.369927 0.00119935 0.0319971 -0.367955 -0.00019903 0.0315863 -0.370177 -0.00355365 0.0315863 -0.369863 -0.00607554 0.0319971 -0.366942 -0.00681102 0.0315863 -0.368997 -0.00632432 0.0319971 -0.366849 -0.0356086 0.0315781 -0.333685 -0.0263968 0.0315863 -0.346887 -0.024918 0.0319971 -0.343295 -0.0171409 0.0315863 -0.360053 -0.0125678 0.0315863 -0.365588 -0.00948949 0.0319971 -0.365161 -0.00985401 0.0315863 -0.367559 -0.0382662 0.0319971 -0.294338 -0.0450835 0.0312739 -0.301692 -0.038437 0.0319971 -0.319288 -0.0444485 0.0314275 -0.314814 -0.0360752 0.0319971 -0.278385 -0.0424415 0.0310313 -0.278033 -0.0441574 0.0311876 -0.294012 -0.043651 0.030567 -0.277062 -0.0413957 0.0309705 -0.264465 -0.0440199 0.0302115 -0.272559 -0.0458388 0.0291734 -0.270641 -0.0466714 0.0282853 -0.263746 -0.0470437 0.0280043 -0.263695 -0.048841 0.0268248 -0.269663 -0.0513265 0.0236921 -0.269526 -0.0519164 0.0225782 -0.269495 -0.0512813 0.0230074 -0.263118 -0.0519142 0.0216076 -0.263032 -0.053397 0.0175495 -0.274082 -0.0546449 0.0232859 -0.301463 -0.0545888 0.0224259 -0.308292 -0.0321761 0.0259971 -0.348632 -0.030601 0.0270487 -0.350337 -0.040759 0.0269504 -0.337911 -0.0456916 0.0265592 -0.331604 -0.0453261 0.0254707 -0.332439 -0.04969 0.0259321 -0.32469 -0.0467921 0.025261 -0.330282 -0.0504691 0.0244837 -0.323478 -0.0515818 0.0241399 -0.320779 -0.0525578 0.025136 -0.317238 -0.000230923 0.028179 -0.373584 -0.00415271 0.028179 -0.373217 -0.0108874 0.0259971 -0.37139 -0.0115412 0.028179 -0.370567 -0.0146587 0.0259971 -0.369006 0.00888077 0.0259971 -0.372289 0.0111369 0.028179 -0.370785 0.00752184 0.028179 -0.37235 0.00398875 0.0259971 -0.373661 0.00369724 0.028179 -0.373291 0.00188559 0.0259971 -0.373921 0.0203906 0.025997 -0.362639 0.0197585 0.028179 -0.362866 0.0133811 0.0259971 -0.369914 0.0216255 0.028179 -0.359397 0.0238575 0.0259955 -0.352519 0.0239865 0.0259621 -0.350458 0.0235121 0.0281738 -0.351777 0.0239604 0.0259786 -0.351203 0.0227758 0.0279362 -0.343964 0.0103088 0.0220849 -0.314615 0.00852258 0.0211085 -0.30088 0.00960592 0.0227133 -0.294912 0.00799882 0.0231211 -0.30279 0.00843242 0.0211363 -0.301303 0.00803446 0.0214086 -0.305395 0.00861966 0.0217352 -0.310079 -0.0536061 0.0199971 -0.280418 -0.0478785 0.0302895 -0.301625 -0.0452722 0.031353 -0.308232 -0.0425936 0.0314935 -0.321283 -0.0446681 0.0308082 -0.322279 -0.0397131 0.0315456 -0.327472 -0.0356766 0.0319971 -0.326123 -0.051847 0.0266194 -0.293588 -0.0523937 0.0271927 -0.301517 -0.0521151 0.0277183 -0.309149 -0.0506485 0.028213 -0.316668 -0.0502233 0.0292418 -0.308895 -0.0147961 0.028179 -0.368352 -0.0188122 0.0259971 -0.364916 -0.0234364 0.0259971 -0.359281 -0.0403194 0.0281032 -0.337551 -0.0451813 0.0278013 -0.331251 -0.0518657 0.0267032 -0.317031 -0.0534586 0.0260111 -0.309329 -0.0542225 0.024239 -0.309432 0.00757695 0.0268769 -0.294467 0.00464136 0.0288448 -0.302374 0.00480256 0.0289241 -0.307072 0.00943117 0.0291942 -0.319274 0.00899428 0.0266959 -0.286563 0.00622963 0.0271018 -0.302571 0.00887046 0.0248339 -0.294751 0.00732578 0.0253207 -0.306877 0.00627801 0.0272249 -0.306958 0.00811107 0.0254986 -0.310958 0.0071717 0.027352 -0.311226 0.0105421 0.0276444 -0.31877 0.0174643 0.0285206 -0.333254 0.011331 0.0259076 -0.318413 0.0214386 0.027712 -0.340263 0.0226859 0.0254736 -0.342192 0.0184317 0.0256936 -0.332816 0.0180811 0.0271334 -0.332975 0.0117796 0.0241049 -0.31821 0.00864517 0.0235748 -0.310805 0.00792153 0.0233443 -0.306832 0.00735753 0.0251485 -0.302711 0.0112958 0.0223851 -0.287067 0.0104615 0.0245807 -0.286884 -0.0533567 0.0244737 -0.293505 -0.0538289 0.0252757 -0.301482 -0.0490844 0.0273174 -0.324399 -0.0480192 0.0286521 -0.323888 -0.0287225 0.0302397 -0.348796 -0.0302422 0.028179 -0.350043 -0.0201603 0.028179 -0.362531 -0.018967 0.0302397 -0.361552 -0.0108744 0.0302397 -0.369378 -0.00795949 0.028179 -0.372205 -0.00750561 0.0302397 -0.370937 0.00348606 0.0302397 -0.371961 0.0144405 0.028179 -0.36864 0.010501 0.0302397 -0.369598 0.0136157 0.0302397 -0.367576 0.0173421 0.028179 -0.365976 0.0186302 0.0302397 -0.362131 0.0203907 0.0302397 -0.35886 0.0228887 0.0281791 -0.355666 0.0234735 0.0280955 -0.347839 0.0221125 0.0302013 -0.347963 0.0214158 0.030128 -0.344324 -0.0542151 0.0222465 -0.293457 -0.0497211 0.0285342 -0.293705 -0.0494198 0.0273391 -0.280624 -0.0470974 0.0300858 -0.29385 -0.0503727 0.0289034 -0.301565 -0.0489344 0.0295604 -0.316155 -0.0478885 0.0304763 -0.308582 -0.0465192 0.0298431 -0.323168 -0.046819 0.0306522 -0.315523 -0.0430203 0.0300658 -0.329758 -0.0384577 0.0302048 -0.336023 -0.0139155 0.0302397 -0.36726 -0.00391596 0.0302397 -0.371892 -0.000218319 0.0302397 -0.372237 0.0070919 0.0302397 -0.371074 0.00952799 0.0315863 -0.367782 0.016352 0.0302397 -0.365064 0.0148367 0.0315863 -0.363667 0.0169035 0.0315863 -0.361007 0.018501 0.0315863 -0.358038 0.0215816 0.0302398 -0.355343 0.0195812 0.0315863 -0.354849 0.0221681 0.0302373 -0.351674 0.0200295 0.0315773 -0.348155 0.0201036 0.0300248 -0.340868 0.0193346 0.0315601 -0.344875 0.0165958 0.0297584 -0.333648 0.00584891 0.029006 -0.311603 0.00575547 0.0287 -0.294068 0.000484694 0.0312602 -0.301858 0.000988483 0.0312263 -0.293023 0.00152086 0.0311991 -0.284924 0.00692814 0.0285835 -0.28611 0.00685849 0.0294651 -0.276836 0.00237116 0.0311812 -0.276895 0.00449756 0.0307389 -0.272895 0.0450776 0.0277438 -0.0726497 0.0509742 0.0272059 -0.0686492 -0.0430113 0.00324679 -0.0861036 -0.0423556 0.0241866 -0.0745605 -0.0423368 0.0253365 -0.0742301 0.040377 0.0268903 -0.0770354 0.0365729 0.0283404 -0.0768884 0.0351872 0.0286077 -0.0773907 -0.0335964 0.0226234 -0.0906162 -0.031465 0.023301 -0.0948659 -0.0339675 0.022463 -0.0903408 -0.0356173 0.0214529 -0.0885381 -0.0362343 0.020386 -0.0850332 -0.0377938 0.0185416 -0.0834206 -0.0358017 0.0208117 -0.0837586 -0.0348832 0.022 -0.0823938 -0.0302805 0.0268936 -0.0801374 -0.0302071 0.0280983 -0.0795485 -0.00986784 0.0289971 -0.0843717 -5.7543e-06 0.0289971 -0.0849463 0.00985635 0.0289971 -0.084372 0.0377824 0.0279249 -0.0766748 0.0388118 0.0284244 -0.0757214 0.0373289 0.0280893 -0.0767282 0.042282 0.0242304 -0.0869463 0.0435658 0.0241013 -0.0856914 0.0442586 0.0241278 -0.0843528 0.0391665 0.0243031 -0.0919507 0.0435678 0.0240041 -0.0863603 0.0448866 0.0232815 -0.0892978 0.0472062 0.0231182 -0.0844283 0.0489187 0.0218589 -0.0871544 0.0506338 0.0214366 -0.0824616 0.0565786 0.000304551 -0.0815084 -0.0375682 0.022989 -0.0783978 -0.0368773 0.0262553 -0.0771255 -0.0305551 0.0271388 -0.0798495 -0.0424232 0.020898 -0.0757479 -0.0424057 0.0216761 -0.0754394 -0.0385466 0.0194742 -0.0802471 -0.0425488 0.0160758 -0.0779567 -0.0426203 0.0136884 -0.0792137 -0.0390993 0.0177098 -0.0813186 -0.0396707 0.0159868 -0.0824512 -0.0426622 0.0123682 -0.0799522 -0.0427353 0.0101913 -0.0812387 -0.0429618 0.00433491 -0.0852299 -0.0431855 0.000311175 -0.0891853 -0.0427797 0.00793432 -0.0903306 -0.0411679 0.0160981 -0.0910765 -0.0388167 0.0197404 -0.0920347 -0.038911 0.0196467 -0.0920533 -0.0389247 0.0196328 -0.0920574 -0.0318161 0.0232298 -0.0926292 -0.0347148 0.0222714 -0.0923934 -0.035434 0.0219994 -0.0934216 -0.0357565 0.0218496 -0.0931364 -0.0361619 0.0216418 -0.092849 -0.0364131 0.0215035 -0.0926982 -0.036941 0.0211886 -0.0924356 -0.0371331 0.0210656 -0.0923564 -0.0380032 0.0204442 -0.0920976 -0.0383097 0.0201961 -0.0920471 -0.0384382 0.0200865 -0.0920338 -0.0384966 0.0200355 -0.0920295 -0.0385952 0.0199476 -0.0920252 0.0561224 0.0109519 -0.0786155 0.0576688 0.00370943 -0.0764276 0.0547748 0.0137061 -0.0835978 0.0532812 0.017626 -0.0845577 0.0550781 0.0134557 -0.0819477 0.0536012 0.0174436 -0.0829667 0.0462 0.0245893 -0.0791434 0.0428763 0.0256912 -0.0787253 0.0566142 0.000306172 -0.0813525 0.055956 0.00928379 -0.0812547 -0.039417 0.0160473 -0.0855551 -0.0426987 0.0112638 -0.0805939 -0.0431041 0.00146021 -0.0877438 -0.042501 0.00844946 -0.0889735 -0.0430172 0.00312308 -0.0862074 -0.041842 0.0126341 -0.0893664 -0.0406107 0.016698 -0.0899732 -0.0393557 0.0177148 -0.0883301 -0.0381862 0.0201181 -0.0910209 -0.0367775 0.0208244 -0.0894153 -0.0375906 0.0191913 -0.0864136 -0.0408353 0.01401 -0.087605 -0.0417896 0.0101984 -0.0870364 -0.0407989 0.0128028 -0.0847883 -0.042792 0.00860075 -0.082237 -0.0273201 0.02841 -0.0805217 0.050877 0.0281221 -0.0682047 0.0466752 0.0289971 -0.0709715 0.0450051 0.0283597 -0.0722121 0.0563518 0.0262258 -0.0642662 0.0611013 0.0232318 -0.0603311 0.0563518 0.0230419 -0.0661484 0.0563393 0.019684 -0.0688669 0.0606133 0.0192752 -0.0626225 0.0599945 0.0152258 -0.0655266 0.0575246 0.00314814 -0.0771018 0.0550043 0.0147887 -0.0795693 0.0523467 0.0215271 -0.0752908 0.0545208 0.019022 -0.0736338 0.0489224 0.0247796 -0.0745192 0.0388384 0.0278917 -0.0761678 0.038895 0.0274987 -0.076687 0.0508424 0.0289971 -0.0680483 0.0513191 0.0252987 -0.0702542 0.0593466 0.0115466 -0.0685662 0.0563037 0.0163906 -0.0720792 0.0585832 0.00770129 -0.0721456 0.0533219 0.0184646 -0.0807872 0.049499 0.0235173 -0.0771641 0.045731 0.0255271 -0.07649 0.0453425 0.0265829 -0.0742262 0.0412148 0.0265211 -0.0774187 0.0518018 0.0233732 -0.0725669 0.0484282 0.026139 -0.0722674 0.0277482 0.0286221 -0.0803571 0.025668 0.0286236 -0.0810455 0.020063 0.0286245 -0.0826121 -0.0565781 0.0144768 -0.00503661 0.0676219 0.0022056 0.0098355 -0.0605827 0.0164387 0.0110929 0.0765238 0.0178254 -0.0231827 -0.0780067 0.0289971 0.0336517 0.0636576 0.000280753 0.0200481 0.0667825 0.000285629 0.011966 0.0675016 0.000287738 0.00953857 0.0688694 0.000293151 0.00358402 0.0259611 0.00247887 0.0505848 0.0196633 0.00249708 0.0514906 0.0221839 0.000287275 0.0508695 0.0136852 0.000284764 0.0512646 0.00691614 0.00254034 0.0510339 -0.00294381 0.000275151 0.0479673 -0.0111772 0.00262313 0.0447327 -0.0165654 0.00265269 0.0412321 -0.0238045 0.000258688 0.033713 -0.0258636 0.00270659 0.0324164 -0.0289549 0.000257363 0.0269065 -0.0296222 0.00272714 0.0272358 -0.0329237 0.00026056 0.0193841 -0.0327017 0.00274076 0.0216483 -0.035068 0.00274886 0.0157517 -0.0844359 0.0289971 0.00937722 -0.0849465 0.0289971 -0.00116905 -0.0840052 0.0272558 0.00926727 -0.084506 0.0272681 -0.00122913 -0.0681017 0.0272993 0.0500951 -0.0684595 0.0289971 0.0503072 -0.0626483 0.0273099 0.056781 -0.0629905 0.0289971 0.0570063 -0.0546086 0.0289971 0.0650799 -0.0498938 0.0273297 0.068281 -0.0427248 0.0273391 0.072993 -0.0381292 0.0289971 0.0759183 -0.00186488 0.027385 0.0846128 -0.0106733 0.0289971 0.0842812 -0.0104466 0.0273753 0.0839729 -0.0195944 0.0289971 0.0826642 -0.0271541 0.0273571 0.0801209 -3.5793e-06 0.0289971 0.084954 -0.00207044 0.0289971 0.0849286 0.054601 0.0289971 0.0650785 0.0611814 0.0274933 0.058624 0.0381218 0.0289971 0.0759174 0.0319334 0.0289971 0.0787214 0.0320432 0.0274308 0.07839 0.0195872 0.0289971 0.0826637 0.0671229 0.0289971 0.0520652 0.0611823 0.0289971 0.058933 0.0723635 0.0275369 0.0441212 -0.0669477 0.019354 0.0217245 -0.0588829 0.0164176 0.0184689 -0.0564409 0.0164115 0.0256318 -0.0564997 0.0193945 0.0432134 -0.0532845 0.0164203 0.0325046 -0.0493619 0.016417 0.0389774 -0.0447098 0.0163979 0.0449506 -0.0459318 0.019387 0.0551155 -0.0330864 0.0193579 0.0644335 -0.0335341 0.0163294 0.055104 -0.0260091 0.0193416 0.0680069 -0.0109504 0.0193159 0.0728256 -0.00609178 0.0161748 0.0669259 -0.00313077 0.0193091 0.0740266 0.0047732 0.0193072 0.0744058 0.00882708 0.0161266 0.0681712 0.0162952 0.0161116 0.0675936 0.0281691 0.019326 0.0705874 0.0377462 0.016086 0.0611501 0.0443064 0.0160775 0.0574991 0.0426737 0.0193487 0.0640128 0.0816974 0.0229848 -0.0141839 0.0773092 0.0157946 0.000316959 0.0763656 0.0158288 0.00804037 0.0746925 0.0158764 0.015582 0.078794 0.0227847 0.0233937 0.0692288 0.0159723 0.0298255 0.0654852 0.0160065 0.0364002 0.0611001 0.0160317 0.0425394 0.0560589 0.0160507 0.0481446 0.0412529 0.0225448 0.0696588 0.035586 0.0193371 0.0676901 0.0337096 0.0225201 0.0733607 0.020506 0.0193166 0.0726807 0.0177702 0.0224763 0.0782847 0.0126796 0.0193099 0.0739566 0.00954285 0.0224579 0.0794772 -0.0186035 0.0193271 0.0708127 -0.0308388 0.0224081 0.0727515 -0.0381973 0.0224033 0.0689758 -0.0397538 0.0193739 0.0601226 -0.0515705 0.0223909 0.0592284 -0.0515402 0.0193949 0.0494599 -0.0574366 0.0223806 0.0533478 -0.060739 0.0193829 0.0364485 -0.0626591 0.0223658 0.0468673 -0.0642147 0.0193631 0.0292531 -0.0709292 0.0223202 0.0323847 -0.0689044 0.0193564 0.0139394 0.083276 0.0262214 -0.0138141 0.0842883 0.0261827 -0.00365077 0.0826193 0.0229429 -0.00459459 0.0824083 0.022891 0.00497599 0.0811092 0.0228365 0.0143564 0.0801264 0.0260257 0.0259276 0.0755454 0.0227369 0.0319617 0.0765918 0.0259741 0.0349101 0.0714546 0.0226931 0.0399506 0.066632 0.0226563 0.0472875 0.0611666 0.0226259 0.0539343 0.0611789 0.0258575 0.0576243 0.0550639 0.0225982 0.0599068 0.0483989 0.0225709 0.0651635 0.0547334 0.0258298 0.0637154 0.0258539 0.0224971 0.0762428 0.007353 0.0256972 0.0833313 0.00125607 0.0224425 0.0798142 -0.00700709 0.0224301 0.0792976 -0.00119936 0.0256809 0.0835896 -0.0151647 0.0224206 0.077938 -0.0181064 0.025652 0.0815042 -0.0231351 0.0224135 0.0757484 -0.04176 0.0256133 0.0721376 -0.0451327 0.022398 0.0644537 -0.0554956 0.025586 0.0620879 -0.0669431 0.0255541 0.0494081 -0.0671732 0.0223451 0.0398543 -0.0756024 0.0255163 0.0345662 0.0846548 0.0289971 0.00702323 0.0840662 0.0261338 0.00648711 0.0826525 0.02608 0.0164053 0.0805995 0.0289971 0.0268266 0.0779982 0.0289971 0.0336497 0.0768752 0.0275662 0.0357092 0.0721702 0.0259273 0.043232 0.0670926 0.0275127 0.0517698 0.0669951 0.0258887 0.0508143 0.0477323 0.0258032 0.0690541 0.0546431 0.0274761 0.0647471 0.0475511 0.0274598 0.0701081 0.040259 0.0257785 0.0735979 0.0399893 0.0274447 0.0746651 0.0323987 0.0257556 0.0773178 0.0242372 0.0257345 0.0801902 0.0237989 0.027418 0.08126 0.0153425 0.0274062 0.0832571 0.0158602 0.025715 0.0821968 0.00675946 0.0273952 0.0843759 -0.0097132 0.0256659 0.0829761 -0.0189036 0.0273661 0.0824703 -0.0262973 0.0256388 0.0791892 -0.0342074 0.0256261 0.0760566 -0.03512 0.0273482 0.0769513 -0.0488796 0.0256001 0.0674663 -0.0565576 0.02732 0.062861 -0.0615388 0.0255708 0.0560504 -0.0716492 0.0255357 0.0422244 -0.0728598 0.0272882 0.0428656 -0.0826097 0.0254803 0.00891125 -0.0830798 0.0254918 -0.00142357 -0.0824457 0.027257 0.0185932 -0.0810927 0.0254842 0.018127 -0.0800764 0.0272664 0.0270403 -0.0768667 0.027277 0.0351567 -0.0760912 0.0222893 0.0164062 -0.0774537 0.0222766 0.00759716 -0.0749261 0.0209995 -0.00253519 -0.0702808 0.0192473 -0.00316849 -0.0376847 0.00278352 0.0034292 -0.0367337 0.00276333 0.00964923 -0.0341796 0.00523926 0.0224209 -0.031046 0.00521722 0.0280883 -0.027214 0.00518308 0.0333338 -0.0214872 0.00268106 0.0371061 -0.0064109 0.00499283 0.0485933 -0.0054075 0.00259379 0.0475573 -0.000269854 0.00494575 0.0507141 0.0060669 0.00490264 0.0520923 0.000654358 0.00256593 0.0496668 0.0125073 0.00486413 0.0527141 0.0132839 0.00251739 0.0516431 0.0693287 0.00390057 -0.0222018 0.069875 0.000288024 -0.0136392 0.0687795 0.000289879 -0.0221269 0.0706048 0.00399737 -0.0114003 0.0702287 0.00394489 -0.0168406 0.0718818 0.00793236 -0.0164659 0.0745822 0.0120002 -0.00218466 0.0679386 0.00435065 0.0106856 0.0747153 0.0119366 -0.00906774 0.037953 0.00244535 0.046603 0.0434782 0.00242788 0.0435983 0.048327 0.00468548 0.0411424 0.048587 0.00240866 0.0399821 0.0530592 0.00464971 0.0369675 0.0608411 0.0045631 0.0271875 0.0572897 0.00236179 0.0311587 -0.0422239 0.00737562 -0.00699356 -0.0421583 0.00755974 -0.00132609 -0.0397351 0.00528453 -0.00192215 -0.0417067 0.0075914 0.00471972 -0.0393124 0.00530895 0.00393876 -0.0406103 0.00755015 0.0111527 -0.0382994 0.00527527 0.0102472 -0.0365835 0.00525169 0.0164365 -0.0331221 0.0074827 0.0293264 -0.0291908 0.00744112 0.0346597 -0.0227523 0.00514024 0.0380717 -0.0139093 0.00726666 0.0472611 -0.0177412 0.0050924 0.0422312 -0.0122647 0.00504244 0.045754 -0.0079447 0.00720485 0.050142 -0.00169463 0.00714627 0.0522999 0.0047504 0.00709279 0.0537127 0.0113002 0.0070453 0.0543681 0.0189595 0.00483028 0.0525772 0.0178649 0.00700388 0.054264 0.025333 0.00480016 0.0516895 0.0243565 0.00696739 0.0534076 0.0320867 0.00246196 0.0489454 0.0305011 0.000288033 0.0491152 0.0384257 0.000287188 0.0460487 0.0728464 0.0118404 -0.0226814 0.0741905 0.0118905 -0.0159336 0.072306 0.0079958 -0.0104335 0.07 0.000291408 -0.0108906 0.0696968 0.00208642 -0.00098658 0.0693419 0.000294933 0.000668785 0.0705845 0.00831239 0.00772498 0.0637881 0.00450848 0.0217529 0.071634 0.00818819 0.00168954 0.0722132 0.00808129 -0.00437014 0.0701057 0.00415341 -0.000402904 0.0636229 0.002301 0.0207131 0.0623899 0.000280017 0.0226543 0.0607736 0.0023341 0.0260915 0.0532109 0.00238679 0.0358133 0.0431151 0.00471682 0.0447533 -0.045244 0.00962566 -0.000557685 -0.0447363 0.00966172 0.00572629 -0.0435391 0.00961794 0.0123136 -0.0416433 0.00958947 0.018763 -0.0485898 0.0132315 0.0219816 -0.0457479 0.0132282 0.0285203 -0.0390669 0.00957747 0.0249932 -0.0421425 0.0132104 0.0346905 -0.0357382 0.00955146 0.0308838 -0.032816 0.0131242 0.0455178 -0.0269898 0.00945099 0.0412273 -0.0212407 0.013005 0.0538663 -0.0160164 0.0093194 0.0491709 -0.00812946 0.012886 0.0593752 -0.00121713 0.0128342 0.0609979 -0.00353569 0.00918888 0.0543328 0.00304521 0.00913119 0.0558003 0.00973479 0.00908032 0.0565069 0.0128927 0.0127524 0.0619171 0.02309 0.00899824 0.055636 0.0199214 0.0127216 0.061212 0.0268215 0.0126952 0.0597417 0.0335109 0.0126709 0.0575244 0.0399088 0.0126461 0.0545846 0.0515151 0.0125857 0.0466824 0.0473479 0.00885861 0.0452247 0.0565717 0.0125468 0.0418115 0.0569935 0.00876414 0.0362573 0.0609534 0.00870726 0.0310258 0.0648448 0.0124476 0.0305421 0.0642552 0.00863852 0.0254092 -0.0452669 0.00942158 -0.00657871 -0.0388162 0.00752216 0.0174594 -0.0363404 0.00750862 0.0235566 -0.0316866 0.00950766 0.0363236 -0.0246209 0.00738825 0.0394703 -0.0217366 0.00938683 0.0455274 -0.0194979 0.00732886 0.0436893 -0.00991934 0.00925234 0.052116 0.0164452 0.00903641 0.0564501 0.0295844 0.00896388 0.0540791 0.0315396 0.00477239 0.0500693 0.0358454 0.00893093 0.0518026 0.0417923 0.00889658 0.0488377 0.037494 0.00474528 0.0477446 0.052438 0.00881486 0.0410123 0.0572485 0.00460868 0.0322921 0.0669348 0.00854973 0.0196169 0.0690363 0.00843845 0.0137125 0.0724962 0.0121829 0.0113882 -0.0787643 0.0254988 0.0265081 -0.0739147 0.0223011 0.0245432 -0.0700511 0.0193332 0.00571344 -0.06149 0.0164062 0.00353988 -0.0615933 0.0162544 -0.00435288 -0.0528583 0.0132516 0.00135625 -0.0521766 0.0132894 0.00823312 -0.0507402 0.0132521 0.015193 -0.0378053 0.0131741 0.0403839 -0.0394051 0.0163672 0.0503463 -0.0272646 0.0130664 0.0500286 -0.0271824 0.0162881 0.0591754 -0.020435 0.0162468 0.0625208 -0.0148329 0.0129437 0.0569912 -0.0133768 0.0162083 0.0651117 0.00133729 0.0161474 0.0679479 0.00581863 0.0127896 0.0618464 0.0236593 0.0161012 0.066221 0.0308368 0.0160933 0.064067 0.0459361 0.0126184 0.0509567 0.0504366 0.016066 0.0531496 0.0610386 0.0125024 0.0364049 0.0680159 0.0123761 0.0243817 0.0723113 0.0159279 0.0228685 0.0705679 0.0122858 0.0179835 0.0738317 0.0120831 0.0046501 0.0774755 0.0157728 -0.00750484 0.0768194 0.0157589 -0.0153229 -0.0435147 0.00972058 -0.0797528 -0.0829865 0.0289971 -0.0181765 -0.0431399 0.000889989 -0.0883778 -0.0406064 0.00296675 -0.0385813 -0.0393549 0.00028648 -0.0271488 -0.0429074 0.00299985 -0.0766011 -0.0434908 0.00628978 -0.0806269 -0.0432497 0.00474907 -0.0824719 -0.0430982 0.00149137 -0.0863411 -0.0428653 0.00666551 -0.0835285 -0.0429055 0.0100979 -0.0809548 -0.0432601 0.00646533 -0.082034 -0.043658 0.0164787 -0.0765243 -0.0461996 0.0287925 -0.0712896 -0.0613018 0.0289971 -0.0588109 -0.0847084 0.0277202 -0.00120154 -0.0848435 0.0281534 -0.00118313 -0.0840129 0.0284923 -0.0124764 -0.0845836 0.027978 -0.00665705 -0.0839863 0.0265747 -0.00677679 -0.0838475 0.0262902 -0.00131891 -0.0794178 0.0230462 -0.00192282 -0.0815091 0.0242786 -0.00163771 -0.0829927 0.0253828 -0.00668167 -0.077049 0.0219008 -0.00224577 -0.0755547 0.0209501 -0.0109961 -0.0428712 0.00780606 -0.01352 -0.042957 0.00792712 -0.00689361 -0.0458695 0.00965081 -0.0142583 -0.0388215 0.00362176 -0.00745742 -0.0388456 0.0030656 -0.0131119 -0.0404539 0.0056515 -0.0130967 -0.044069 0.00800741 -0.0386843 -0.0463525 0.00981328 -0.0267776 -0.0527622 0.013005 -0.00555685 -0.0681108 0.0190824 -0.0393787 -0.068883 0.0184606 -0.0336685 -0.0744224 0.0260474 -0.040139 -0.0756162 0.0289971 -0.0387182 -0.0774295 0.0276775 -0.0347533 -0.0776078 0.0289971 -0.0345542 -0.0763543 0.0248073 -0.0350575 -0.0745061 0.0223493 -0.0349426 -0.0726163 0.0197034 -0.0286765 -0.0719768 0.0202545 -0.0344586 -0.0691945 0.0180845 -0.0277087 -0.0615371 0.0154906 -0.0314606 -0.0760053 0.0209198 -0.017369 -0.0828064 0.0276239 -0.0183947 -0.0822913 0.0261768 -0.018559 -0.0806139 0.0255595 -0.0242219 -0.084811 0.0289971 -0.00493457 -0.0837301 0.0289971 -0.0143685 -0.082898 0.0256433 -0.0127591 -0.0818444 0.0244833 -0.0126315 -0.083637 0.026971 -0.0127161 -0.0817113 0.0243443 -0.00643056 -0.0790169 0.0225475 -0.0119858 -0.081485 0.024885 -0.0185654 -0.0791261 0.0226993 -0.0181737 -0.0511903 0.0259214 -0.0678661 -0.0585846 0.0215585 -0.0596169 -0.0599511 0.0242734 -0.0594706 -0.0653292 0.0289971 -0.0543029 -0.0652079 0.0281473 -0.0544174 -0.0643131 0.025181 -0.0548193 -0.0609213 0.0271995 -0.0591095 -0.0582321 0.0289971 -0.0618515 -0.0562365 0.0264641 -0.0635857 -0.0523313 0.0289971 -0.0669173 -0.0627814 0.0189006 -0.0496343 -0.0651824 0.0210639 -0.0500488 -0.0670583 0.0235071 -0.0501787 -0.0692129 0.0221482 -0.0452178 -0.0668884 0.0199442 -0.0448448 -0.0729727 0.0233769 -0.0402401 -0.0708406 0.0210703 -0.0399714 -0.0568343 0.0190483 -0.0595551 -0.0610107 0.0200548 -0.0548032 -0.0629074 0.022487 -0.0549443 -0.0683533 0.0262601 -0.0499936 -0.070013 0.0289971 -0.0481142 -0.0709313 0.0246755 -0.0452623 -0.0719911 0.0275539 -0.0449498 -0.0735741 0.0289971 -0.0424703 -0.0436492 0.00583778 -0.0699874 -0.0417913 0.000279338 -0.0644962 -0.0410304 0.000282245 -0.0518265 -0.0429384 0.00487679 -0.0848165 -0.0452281 0.012093 -0.075198 -0.0469583 0.0145089 -0.0721845 -0.0460645 0.011542 -0.072587 -0.0456507 0.0187547 -0.0736531 -0.0424293 0.0206369 -0.0758548 -0.0432267 0.0201522 -0.0754035 -0.0455515 0.015364 -0.0744863 -0.0502465 0.0159891 -0.0669512 -0.0486874 0.0133769 -0.0669931 -0.047969 0.0138649 -0.069668 -0.0449363 0.00870002 -0.0728625 -0.044605 0.00898168 -0.0757473 -0.0439842 0.00941771 -0.0784751 -0.0428552 0.000275701 -0.0829879 -0.0431308 0.00309074 -0.0828509 -0.0430358 0.00324642 -0.0858637 -0.0422077 0.00295294 -0.0639643 -0.0414378 0.00294342 -0.0512895 -0.0402004 0.000284696 -0.0391203 -0.0419316 0.00570361 -0.0384127 -0.0402574 0.00557361 -0.00726166 -0.0433877 0.00576722 -0.0637169 -0.0436315 0.00616226 -0.0791709 -0.0425223 0.000276036 -0.0771506 -0.0437436 0.00599749 -0.0761673 -0.0450908 0.00851261 -0.0698819 -0.0466003 0.0111512 -0.0698131 -0.0471323 0.0106575 -0.0639727 -0.0491992 0.012999 -0.0642061 -0.0472768 0.0103705 -0.0579223 -0.051134 0.0154108 -0.0643679 -0.0523528 0.0145509 -0.0588998 -0.051536 0.0187449 -0.0667632 -0.046863 0.00996113 -0.0393118 -0.0536663 0.0132205 -0.0412256 -0.0677727 0.0182126 -0.00855171 -0.0596887 0.015593 -0.00461254 -0.0597699 0.0155928 -0.0059877 -0.0530205 0.0127248 -0.0163606 -0.0536121 0.0128294 -0.0289387 -0.0472314 0.0101847 -0.051769 -0.0446988 0.00809162 -0.0512831 -0.0499537 0.0196937 -0.0689698 -0.045756 0.0255855 -0.0719362 -0.0456538 0.0221965 -0.0727678 -0.042706 0.00571073 -0.0510899 -0.0451149 0.00828979 -0.0637662 -0.053075 0.0139558 -0.0531626 -0.0542223 0.0206511 -0.0642679 -0.0528224 0.017954 -0.0643961 -0.0490915 0.0167099 -0.0693895 -0.047589 0.0176161 -0.0716394 -0.0439681 0.0128698 -0.0775794 -0.0815288 0.0285151 -0.0238309 -0.0797663 0.0289971 -0.0292296 -0.0812021 0.0269676 -0.0240973 -0.0787237 0.0231239 -0.0240843 -0.0792564 0.0264933 -0.0296148 -0.077793 0.0238301 -0.0297086 -0.076033 0.0211151 -0.0235128 -0.0727394 0.0194278 -0.0226145 -0.0755333 0.0215915 -0.0293707 -0.0690319 0.0179612 -0.0214918 -0.0610127 0.0153502 -0.0189189 -0.0613186 0.0158171 -0.0374709 -0.0534774 0.0135312 -0.047252 -0.0607976 0.0163049 -0.0433172 -0.0599456 0.0169693 -0.0489841 -0.0586735 0.0178576 -0.0544233 -0.0547315 0.016726 -0.0593022 -0.0553497 0.0234935 -0.063992 -0.050614 0.0227851 -0.0684407 0.0625011 0.0270513 -0.0576903 0.0569991 0.00131622 -0.0795571 0.0574352 0.002811 -0.07752 0.0599073 0.000286121 -0.0660839 0.0678388 0.00759144 -0.035082 0.0704736 0.00716225 -0.0223579 0.0752041 0.0157326 -0.0230028 0.07458 0.0147327 -0.0229177 0.0731455 0.0147615 -0.0286759 0.0789447 0.021817 -0.0235128 0.0806256 0.0251885 -0.023742 0.0612106 0.0243351 -0.0598178 0.06128 0.025128 -0.0594916 0.0614628 0.0289971 -0.0586328 0.0607903 0.0205924 -0.0617913 0.0582569 0.00619821 -0.0736743 0.0605683 0.0076924 -0.0661154 0.0605228 0.0115804 -0.0659498 0.0592426 0.0109943 -0.0690541 0.0599375 0.0148831 -0.0657943 0.0602076 0.00387034 -0.06609 0.0573924 0.000285538 -0.0778207 0.0582359 0.000285358 -0.0739109 0.05837 0.00389882 -0.0738389 0.0581795 0.00585403 -0.0740368 0.0675929 0.0264951 -0.0514715 0.0629653 0.0230955 -0.0580528 0.0689193 0.0149078 -0.0439148 0.0719361 0.0260603 -0.0449007 0.0712991 0.022283 -0.0447454 0.067483 0.0226323 -0.051564 0.0671199 0.0188107 -0.0515375 0.0634161 0.0191418 -0.0584089 0.0785676 0.0255239 -0.0307929 0.0745258 0.0220293 -0.0376496 0.0770954 0.0218821 -0.0302448 0.0711665 0.0148129 -0.0363584 0.0707862 0.00787194 -0.0224005 0.0667612 0.00388563 -0.0347195 0.0635425 0.00386857 -0.0504321 0.0664135 0.0150447 -0.0513495 0.0581887 0.00589486 -0.0739935 0.0582834 0.00585314 -0.0737261 0.0625696 0.00763738 -0.0584434 0.0600416 0.015512 -0.0653056 0.0643817 0.00761304 -0.0506825 0.0632137 0.0114135 -0.0586021 0.065433 0.0113231 -0.0510326 0.0635329 0.0152423 -0.058608 0.0702573 0.0185714 -0.0443997 0.0755968 0.0257361 -0.038009 0.0735637 0.0289971 -0.0424722 0.0053083 -2.93696e-06 0.0499974 0.0022472 -2.93696e-06 0.0483199 -0.0427653 -2.93696e-06 -0.274822 -0.0375893 -2.93696e-06 -0.153105 -0.0363291 -2.93696e-06 -0.155686 0.0126282 -2.93696e-06 -0.267234 0.00966316 -2.93696e-06 -0.268283 0.0108195 -2.93696e-06 -0.267263 0.00615573 -2.93696e-06 -0.270308 0.00666726 -2.93696e-06 -0.268083 0.00519687 -2.93696e-06 -0.26967 0.00615568 -2.93696e-06 -0.274358 0.00763807 -2.93696e-06 -0.275841 0.0131705 -2.93696e-06 -0.274358 0.0131705 -2.93696e-06 -0.270308 0.0169735 -2.93696e-06 -0.220971 0.0153418 -2.93696e-06 -0.220531 0.0147811 -2.93696e-06 -0.223049 0.0164309 -2.93696e-06 -0.222996 0.0169734 -2.93696e-06 -0.225021 0.0204809 -2.93696e-06 -0.218947 0.0225059 -2.93696e-06 -0.219489 0.0239883 -2.93696e-06 -0.220972 0.0218571 -2.93696e-06 -0.230254 0.0245309 -2.93696e-06 -0.222997 0.0195383 -2.93696e-06 -0.247664 0.0169595 -2.93696e-06 -0.259253 0.0186776 -2.93696e-06 -0.248667 0.0154021 -2.93696e-06 -0.264245 0.0170376 -2.93696e-06 -0.227539 0.0225058 -2.93696e-06 -0.226504 0.0192903 -2.93696e-06 -0.217422 0.0218695 -2.93696e-06 -0.217468 0.0169549 -2.93696e-06 -0.218518 0.0236812 -2.93696e-06 -0.217479 0.0247958 -2.93696e-06 -0.217015 0.0347845 -2.93696e-06 -0.170504 0.0337995 -2.93696e-06 -0.173752 0.0346797 -2.93696e-06 -0.175341 0.0347239 -2.93696e-06 -0.177149 0.038681 -2.93696e-06 -0.161907 0.0262621 -2.93696e-06 -0.218528 0.0266201 -2.93696e-06 -0.216896 0.0324037 -2.93696e-06 -0.190528 0.0322385 -2.93696e-06 -0.172738 0.0327595 -2.93696e-06 -0.171047 0.0293431 -2.93696e-06 -0.171559 0.0307345 -2.93696e-06 -0.170504 0.0292522 -2.93696e-06 -0.169022 0.0292522 -2.93696e-06 -0.164972 0.027614 -2.93696e-06 -0.164545 0.0292267 -2.93696e-06 -0.162524 0.0304756 -2.93696e-06 -0.161774 0.0341515 -2.93696e-06 -0.161469 0.0381791 -2.93696e-06 -0.159984 0.0475018 -2.93696e-06 -0.112504 0.0502575 -2.93696e-06 -0.109107 0.0391181 -2.93696e-06 -0.159913 0.0386379 -2.93696e-06 -0.15912 0.0454769 -2.93696e-06 -0.104947 0.0442974 -2.93696e-06 -0.10342 0.0419695 -2.93696e-06 -0.106972 0.0414268 -2.93696e-06 -0.108997 0.0402017 -2.93696e-06 -0.106838 0.0419694 -2.93696e-06 -0.111022 0.0398044 -2.93696e-06 -0.109557 0.0505601 -2.93696e-06 -0.101617 0.0489843 -2.93696e-06 -0.106972 0.0475019 -2.93696e-06 -0.105489 0.048471 -2.93696e-06 -0.103029 0.0449569 -2.93696e-06 -0.114738 0.0465179 -2.93696e-06 -0.115752 0.0407257 -2.93696e-06 -0.112146 0.0560571 -2.93696e-06 -0.0824805 0.0568658 -2.93696e-06 -0.0759411 0.0596106 -2.93696e-06 -0.0660383 0.0556049 -2.93696e-06 -0.0817398 0.0518113 -2.93696e-06 -0.0991871 0.0589306 -2.93696e-06 -0.0409553 0.0598339 -2.93696e-06 -0.0514487 0.058914 -2.93696e-06 -0.0619406 0.0561506 -2.93696e-06 -0.0305531 0.0546697 -2.93696e-06 0.022278 0.0565322 -2.93696e-06 0.0227771 0.0502367 -2.93696e-06 0.033863 0.0528073 -2.93696e-06 0.029229 0.0578957 -2.93696e-06 0.0278655 0.0580279 -2.93696e-06 0.0292161 0.0546698 -2.93696e-06 0.029728 0.0287275 -2.93696e-06 0.0194602 0.0391204 -2.93696e-06 0.0338631 0.00652347 -2.93696e-06 0.0340841 -0.00298543 -2.93696e-06 0.0384976 -0.00857289 -2.93696e-06 0.0417236 -0.00954677 -2.93696e-06 0.0446304 -0.00283919 -2.93696e-06 0.047687 -0.00298535 -2.93696e-06 0.0449495 -0.0195163 -2.93696e-06 0.0375917 -0.037833 -2.93696e-06 -0.0231103 -0.0378017 -2.93696e-06 -0.0236747 -0.0373026 -2.93696e-06 -0.0218123 -0.0359391 -2.93696e-06 -0.0204488 -0.0340993 -2.93696e-06 0.0154821 -0.0353463 -2.93696e-06 0.0112258 -0.0340968 -2.93696e-06 0.00647028 -0.0367145 -2.93696e-06 0.00286751 -0.0371357 -2.93696e-06 -0.00237215 -0.034608 -2.93696e-06 -0.00258418 -0.019513 -2.93696e-06 0.0287007 -0.019462 -2.93696e-06 0.0338639 -0.0312569 -2.93696e-06 0.015083 -0.0327557 -2.93696e-06 -0.0114619 -0.0340766 -2.93696e-06 -0.0199498 -0.0303517 -2.93696e-06 -0.0236748 -0.0327891 -2.93696e-06 -0.0317572 -0.0374582 -2.93696e-06 -0.0431996 -0.0383125 -2.93696e-06 -0.0493411 -0.0435505 -2.93696e-06 -0.101326 -0.0394706 -2.93696e-06 -0.032933 -0.0398171 -2.93696e-06 -0.037908 -0.0394445 -2.93696e-06 -0.0635996 -0.0403818 -2.93696e-06 -0.0868261 -0.0429033 -2.93696e-06 -0.0896641 -0.042927 -2.93696e-06 -0.0901346 -0.0426933 -2.93696e-06 -0.0975285 -0.0421506 -2.93696e-06 -0.0955035 -0.0406682 -2.93696e-06 -0.0940211 -0.0386622 -2.93696e-06 -0.0910334 -0.0366183 -2.93696e-06 -0.101036 -0.0351359 -2.93696e-06 -0.0995536 -0.0351141 -2.93696e-06 -0.102005 -0.0345933 -2.93696e-06 -0.0975286 -0.0329438 -2.93696e-06 -0.0974534 -0.0351358 -2.93696e-06 -0.0955036 -0.0366182 -2.93696e-06 -0.0940211 -0.0368019 -2.93696e-06 -0.0921341 -0.04238 -2.93696e-06 -0.104567 -0.0409191 -2.93696e-06 -0.103487 -0.0391299 -2.93696e-06 -0.103208 -0.0454799 -2.93696e-06 -0.147109 -0.0431823 -2.93696e-06 -0.106247 -0.0468988 -2.93696e-06 -0.161906 -0.0463231 -2.93696e-06 -0.151489 -0.0451471 -2.93696e-06 -0.148887 -0.0423209 -2.93696e-06 -0.151065 -0.0417772 -2.93696e-06 -0.151118 -0.043941 -2.93696e-06 -0.153309 -0.039891 -2.93696e-06 -0.153309 -0.0384086 -2.93696e-06 -0.154791 -0.0364877 -2.93696e-06 -0.158554 -0.0384087 -2.93696e-06 -0.158841 -0.0398911 -2.93696e-06 -0.160323 -0.0380247 -2.93696e-06 -0.160981 -0.0435472 -2.93696e-06 -0.161906 -0.0439411 -2.93696e-06 -0.160323 -0.0456558 -2.93696e-06 -0.163851 -0.0441945 -2.93696e-06 -0.162773 -0.046528 -2.93696e-06 -0.166071 -0.0486437 -2.93696e-06 -0.204352 -0.049126 -2.93696e-06 -0.214059 -0.0415686 -2.93696e-06 -0.212034 -0.0407567 -2.93696e-06 -0.21034 -0.0394924 -2.93696e-06 -0.212913 -0.039641 -2.93696e-06 -0.215777 -0.0430511 -2.93696e-06 -0.217566 -0.043548 -2.93696e-06 -0.218527 -0.0450761 -2.93696e-06 -0.218109 -0.0471011 -2.93696e-06 -0.217566 -0.0436784 -2.93696e-06 -0.219585 -0.0495639 -2.93696e-06 -0.222803 -0.0520515 -2.93696e-06 -0.266036 -0.0528559 -2.93696e-06 -0.269722 -0.0519667 -2.93696e-06 -0.264499 -0.052481 -2.93696e-06 -0.26293 -0.0535131 -2.93696e-06 -0.281626 -0.0519592 -2.93696e-06 -0.273187 -0.0486448 -2.93696e-06 -0.269516 -0.0464268 -2.93696e-06 -0.271705 -0.0434585 -2.93696e-06 -0.272464 -0.0444018 -2.93696e-06 -0.275213 -0.0449445 -2.93696e-06 -0.277238 -0.0451612 -2.93696e-06 -0.279867 -0.0464269 -2.93696e-06 -0.27872 -0.0478634 -2.93696e-06 -0.280882 -0.049681 -2.93696e-06 -0.28157 -0.0484519 -2.93696e-06 -0.279262 -0.0378331 -2.93696e-06 -0.0305603 0.0266233 -2.93696e-06 0.0483196 -0.00162193 -2.93696e-06 0.043586 0.0266232 -2.93696e-06 0.0338633 0.0520913 -2.93696e-06 0.0361093 0.0455935 -2.93696e-06 0.0414958 0.0690448 -2.93696e-06 0.000627048 0.0621234 -2.93696e-06 0.0225177 0.0578956 -2.93696e-06 0.0241405 0.0697001 -2.93696e-06 -0.0108829 0.0697236 -2.93696e-06 -0.00904465 0.067827 -2.93696e-06 -0.0231116 0.0584296 -2.93696e-06 -0.029997 0.0584118 -2.93696e-06 -0.0305615 0.0602921 -2.93696e-06 -0.033223 0.0621546 -2.93696e-06 -0.033722 0.0625805 -2.93696e-06 -0.051797 0.0589287 -2.93696e-06 -0.0281345 0.0602922 -2.93696e-06 -0.0267711 0.0584119 -2.93696e-06 -0.0231115 0.0640172 -2.93696e-06 -0.0267711 0.0678453 -2.93696e-06 -0.0253868 0.0653806 -2.93696e-06 -0.0281346 0.0658796 -2.93696e-06 -0.0299971 0.0558619 0.00124484 -0.0791599 0.055982 0.00171809 -0.078584 0.0565726 0.00372982 -0.0758776 0.0571112 0.00595256 -0.0733823 0.0545055 0.00899706 -0.0827506 0.0570953 0.00588497 -0.0734555 0.055854 0.00132065 -0.0791811 0.0572355 0.00650371 -0.0728041 0.0572812 0.00682138 -0.072544 0.0487584 0.00899706 -0.0169248 0.00167937 0.00899706 -0.0498506 0.039924 0.00899706 -0.106724 0.0416329 0.00899706 -0.10439 0.00310401 0.00899706 -0.280927 -0.046621 0.00899706 -0.280926 0.00209468 0.00899706 -0.0514006 0.0322717 0.00899706 -0.161017 0.0294174 0.00899706 -0.162014 -0.0398568 0.00899706 -0.0852741 -0.00369002 0.00899706 -0.0529505 -0.0332975 0.00899706 -0.0948041 -0.0326438 0.00899706 -0.0974495 -0.0428748 0.00899706 -0.119826 -0.0373953 0.00899706 -0.103397 0.0553903 0.00899724 -0.0778526 0.0547742 0.00899708 -0.0812213 0.0171456 0.00899706 -0.218009 0.0276387 0.00899706 -0.170123 0.0238404 0.00899706 0.0247983 0.0571021 0.00899706 -0.07087 0.0570868 0.00899706 -0.0708281 0.00167933 0.00899706 -0.0529506 0.0442353 0.00899706 -0.103127 -0.0399171 0.00899706 -0.0860836 -0.0350538 0.00899706 -0.0927207 -0.0399524 0.00899706 -0.0863557 0.0349045 0.00899706 -0.161028 0.0342211 0.00899706 -0.161101 -0.0398447 0.00899706 -0.151185 -0.0391985 0.00899706 -0.212853 -0.00255529 0.00899706 -0.0487158 -0.0399212 0.00899706 -0.0839245 -0.0399595 0.00899706 -0.10375 0.0410738 0.00899706 -0.143267 0.0404756 0.00899706 -0.112312 -0.0434352 0.00899706 -0.271921 -0.0398908 0.00899706 -0.0841986 -0.03988 0.00899706 -0.0843203 0.0298136 0.00899706 -0.172224 0.0153445 0.00899706 -0.226098 0.0144845 0.00899706 -0.223206 -0.00100536 0.00899706 -0.0545005 0.0267641 0.00899706 -0.167229 0.0151401 0.00899706 -0.220262 0.0376392 0.00899706 -0.158387 -0.0411462 0.00899706 -0.104478 -0.0413941 0.00899706 -0.104733 0.0490628 0.00899707 -0.101988 0.0457647 0.00899706 -0.103004 0.0458916 0.00899708 -0.103008 0.00863891 0.00899706 -0.266929 0.0108611 0.00899706 -0.266965 -0.0410273 0.00899706 -0.150882 -0.0432288 0.00899706 -0.14972 -0.036202 0.00899706 -0.158646 0.0328885 0.00899706 -0.174197 -0.0455249 0.00899706 -0.180087 -0.0438824 0.00899706 -0.163832 -0.0450652 0.00899706 -0.207483 -0.04347 0.00899706 -0.208278 -0.036705 0.00899706 -0.0918502 -0.0400396 0.00899706 -0.0868706 0.0354869 0.00899706 -0.00181665 0.0262337 0.00899706 0.0108716 0.0108632 0.00899706 -0.0262346 0.0240179 0.00899706 -0.21531 0.0244584 0.00899706 -0.214289 0.0292391 0.00899706 -0.194414 0.0320334 0.00899706 -0.173284 -0.0515823 0.00899706 -0.262979 0.0200774 0.00899706 0.0200853 0.0133577 0.00899706 0.0317024 0.0108639 0.00899706 0.0262418 0.00109589 0.00899706 0.0343861 -0.0108725 0.00899706 0.0262421 -0.0113125 0.00899706 0.0324921 -0.0222153 0.00899706 0.0262725 -0.0200862 0.00899706 0.0200858 -0.0301609 0.00899706 0.0165555 -0.0284047 0.00899706 4.11317e-06 -0.026243 0.00899706 -0.0108641 -0.0200868 0.00899706 -0.0200778 -0.0284185 0.00899706 -0.0193873 -0.0436049 0.00899706 -0.219876 -0.0499051 0.00899706 -0.245277 0.0139421 0.00899706 -0.266171 0.020124 0.00899706 -0.230469 0.020444 0.00899706 -0.231732 -0.0498723 0.00899706 -0.269002 -0.0515644 0.00899706 -0.267274 -0.048655 0.00899706 -0.269216 0.0197219 0.00899706 -0.236449 0.0176661 0.00899706 -0.249346 -0.046564 0.00899706 -0.221199 -0.0475035 0.00899706 -0.223224 -0.045328 0.00899706 -0.220329 -0.0444069 0.00899706 -0.220032 0.054616 0.00817104 -0.0826752 0.0531153 0.00473167 -0.0909109 0.0518632 0.00899711 -0.0948381 0.0522388 0.00469377 -0.0949455 0.0515183 0.000290703 -0.0991232 0.0241445 0.00799706 -0.222938 0.0195171 0.00799706 -0.227392 0.0182292 0.00799706 -0.224296 0.0178809 0.00799706 -0.222996 0.0182292 0.00799706 -0.221696 0.0191809 0.00799706 -0.220745 0.0199388 0.00799706 -0.218529 0.0230809 0.00799706 -0.222997 0.0246597 0.00799712 -0.219072 0.0250282 0.00799706 -0.218774 0.0217809 0.00799706 -0.220745 0.0227325 0.00799706 -0.221697 -0.0487855 0.00799706 -0.218961 -0.0481774 0.00799713 -0.20895 -0.0484402 0.00799706 -0.210704 -0.0484682 0.00799712 -0.218609 -0.0473277 0.00799706 -0.215359 -0.0485455 0.00799706 -0.213028 -0.047676 0.00799706 -0.214059 -0.0473211 0.00799706 -0.209428 -0.045076 0.00799706 -0.211459 -0.043776 0.00799706 -0.211807 -0.0433579 0.00799706 -0.2099 -0.042476 0.00799706 -0.214059 -0.0406585 0.00799706 -0.213202 -0.0407797 0.00799706 -0.215397 -0.0483365 0.00799706 -0.208381 -0.048324 0.00799714 -0.20858 -0.0482774 0.00799707 -0.208753 -0.0481598 0.00799707 -0.218462 0.0372979 0.00799718 -0.163316 0.0375305 0.00799682 -0.163253 0.0355495 0.00799706 -0.172514 0.0350112 0.00799706 -0.168297 0.0370907 0.00799732 -0.163326 0.0349087 0.00799706 -0.172075 0.0327596 0.00799706 -0.169597 0.0317958 0.00799706 -0.171392 0.0305079 0.00799706 -0.168297 0.0301596 0.00799706 -0.166997 0.0305079 0.00799706 -0.165697 0.0287327 0.00799706 -0.164988 0.0322175 0.00799706 -0.162529 -0.042797 0.00799736 -0.0921636 -0.0428488 0.00799706 -0.0917919 -0.0373934 0.00799706 -0.101851 -0.0386433 0.00799706 -0.100129 -0.0408949 0.00799706 -0.0988285 -0.0430704 0.00799706 -0.102082 -0.0412433 0.00799706 -0.0975285 -0.0425889 0.00799708 -0.0925155 -0.0399432 0.00799706 -0.0952768 -0.0423373 0.0079986 -0.0927149 -0.0386432 0.00799706 -0.0949285 -0.0383952 0.00799706 -0.0930354 -0.0369251 0.00799706 -0.0933694 -0.0373432 0.00799706 -0.0952769 -0.0342257 0.00799706 -0.0966712 -0.0360433 0.00799706 -0.0975286 -0.0363916 0.00799706 -0.0988286 -0.0354941 0.00799706 -0.100743 -0.0373433 0.00799706 -0.0997802 -0.0388913 0.00799706 -0.102022 -0.0423451 0.00799706 -0.101831 -0.0427132 0.00799715 -0.101879 0.0148264 0.019997 -0.27213 0.0153699 0.0199973 -0.268377 0.0109631 0.0199971 -0.270082 0.0143528 0.0199971 -0.268755 0.0145741 0.0199972 -0.268778 0.0119148 0.0199971 -0.273633 0.0126065 0.0199971 -0.277586 0.00966308 0.0199971 -0.274933 0.00869932 0.0199971 -0.276729 0.00836308 0.0199971 -0.274585 0.00741143 0.0199971 -0.273633 0.00576841 0.0199971 -0.274587 0.00706311 0.0199971 -0.272333 0.00516527 0.0199971 -0.272473 0.00836314 0.0199971 -0.270082 0.00912105 0.0199971 -0.267866 0.00966314 0.0199971 -0.269733 0.0133826 0.0199971 -0.278423 0.0119148 0.0199971 -0.271033 -0.0527683 0.0199971 -0.269829 -0.0528083 0.0199971 -0.269665 -0.0526216 0.0199971 -0.270108 -0.0522327 0.0199971 -0.270422 -0.0518456 0.0199971 -0.270518 -0.0482038 0.0199971 -0.270719 -0.0471518 0.0199971 -0.272961 -0.0467337 0.0199971 -0.271053 -0.0462002 0.0199971 -0.273912 -0.0458518 0.0199971 -0.275212 -0.0441555 0.0199971 -0.276551 -0.0533851 0.0199971 -0.277429 -0.0453027 0.0199971 -0.278427 -0.0471519 0.0199971 -0.277464 -0.0484519 0.0199971 -0.277812 -0.0497519 0.0199971 -0.277464 -0.0400823 0.0117406 -0.0868427 -0.0399954 0.0118971 -0.0866268 -0.0399915 0.0118971 -0.0866042 -0.0400218 0.0114804 -0.0857437 -0.0399524 0.0118971 -0.0863557 -0.03988 0.0118971 -0.0843203 -0.0399212 0.0118971 -0.0839245 -0.000117767 0.0239305 -0.118997 0.0379234 0.00736091 -0.158427 0.0471337 0.000982046 -0.119082 0.0384992 0.000290439 -0.158534 0.033372 0.00899706 -0.176877 0.030324 0.000287983 -0.195809 0.0283526 0.000287155 -0.204797 0.0262168 0.000286176 -0.214533 -0.0025092 0.0194971 -0.354326 -9.21146e-06 0.0194971 -0.354996 -0.0445728 0.0194971 -0.332962 -0.0422447 0.0194971 -0.33589 -0.0339551 0.0194971 -0.345991 0.0102585 0.0194971 -0.291562 0.0128667 0.0194971 -0.279667 0.0220385 0.0194971 -0.358691 0.0234518 0.0194971 -0.353351 0.0024908 0.0194971 -0.354326 0.00432095 0.0194971 -0.352496 0.0173931 0.0194971 -0.366085 -0.0515726 0.0194971 -0.295436 0.0236908 0.0194971 -0.350122 0.0234604 0.0194971 -0.346698 -0.00433931 0.0194971 -0.352496 -0.0506071 0.0194971 -0.322407 -0.0493946 0.0194971 -0.325064 -0.0518952 0.0194971 -0.29762 -0.0524201 0.0194971 -0.299926 0.00787721 0.0194971 -0.302868 -0.0540591 0.0194971 -0.310057 0.0116892 0.0194971 -0.281427 0.00432101 0.0194971 -0.347496 0.00249091 0.0194971 -0.345666 0.0145538 0.0194971 -0.324711 -0.0441384 0.00899706 -0.147236 -0.0449159 0.00458429 -0.147143 -0.0429511 0.000287348 -0.1068 -0.0441389 0.00899706 -0.147529 -0.0428448 0.00481 -0.15051 -0.0439763 0.00495378 -0.149669 -0.0446838 0.00504843 -0.148445 -0.0449791 0.000290525 -0.148503 -0.0438861 0.00899706 -0.148683 -0.0422275 0.00899706 -0.150491 0.0364191 0.00899706 -0.160322 0.036165 0.00899706 -0.160507 0.0353957 0.00899706 -0.160891 0.0371934 0.00899706 -0.159458 0.0426079 0.000297063 -0.114266 0.0426079 0.00899706 -0.114266 0.0395059 0.000297063 -0.109586 0.0395059 0.00899706 -0.109586 0.0416329 0.000297063 -0.10439 0.0442353 0.000297063 -0.103127 -0.0191499 0.0289971 0.0827683 -0.00986568 0.0347971 0.0843795 -0.077257 0.0289971 0.035339 -0.073233 0.0289971 0.0430632 -0.0681444 0.0289971 0.0507332 -0.0381292 0.0347971 0.0759183 -0.0502071 0.0289971 0.0685327 -0.0290583 0.0347971 0.079831 -0.0274188 0.0289971 0.0804088 -0.0195944 0.0347971 0.0826642 -0.0836639 0.0289971 0.0147562 -0.0836639 0.0347971 0.0147562 -0.0813856 0.0347971 0.0243687 -0.080482 0.0289971 0.0272048 -0.081571 0.0289971 -0.0237331 -0.0836643 0.0347971 -0.0147466 -0.0840406 0.0289971 -0.0124247 -0.0751084 0.0289971 -0.0396942 -0.0735741 0.0347971 -0.0424703 -0.0780076 0.0347971 -0.0336422 -0.0809237 0.0289971 -0.0258537 -0.0813862 0.0347971 -0.0243591 -0.0813862 0.0289971 -0.0243591 -0.0640314 0.0289971 -0.0558271 -0.0689646 0.0289971 -0.049605 -0.0722353 0.0289971 -0.0447091 -0.0567532 0.0289971 -0.063211 -0.0546103 0.0347971 -0.065071 -0.0617958 0.0289971 -0.0582917 -0.0423047 0.0289971 -0.0736658 -0.0466864 0.0289971 -0.0709703 -0.0517528 0.0289971 -0.0673656 -0.0195965 0.0347971 -0.0826562 -0.023342 0.0289971 -0.0816778 -0.0290603 0.0347971 -0.0798228 -0.0290603 0.0289971 -0.0798228 -0.0366156 0.0289971 -0.0766522 0.00985635 0.0347971 -0.084372 -5.7543e-06 0.0347971 -0.0849463 -0.0164369 0.0289971 -0.0833418 0.0290489 0.0289971 -0.0798235 0.0118394 0.0289971 -0.0841165 0.0256795 0.0289971 -0.0809705 0.0388026 0.0289971 -0.0755641 0.0381199 0.0347971 -0.0759108 0.0466752 0.0347971 -0.0709715 0.0563496 0.0289971 -0.0635628 0.0721206 0.0289971 -0.0448788 0.068135 0.0347971 -0.0507257 0.067629 0.0289971 -0.0513985 0.0624405 0.0289971 -0.0575905 0.061785 0.0289971 -0.0582933 0.0779974 0.0347971 -0.0336442 0.0791163 0.0289971 -0.0309214 0.0681363 0.0347971 0.0507315 0.0681363 0.0289971 0.0507315 0.0724235 0.0289971 0.044396 0.0779982 0.0347971 0.0336497 0.0836549 0.0289971 0.0147541 0.0848015 0.0347971 -0.00493674 0.0848015 0.0289971 -0.00493674 0.0838355 0.0289971 -0.0136828 0.0815233 0.0289971 -0.0238643 0.0813762 0.0347971 -0.0243612 0.0813762 0.0289971 -0.0243612 -3.57926e-06 0.0347971 0.0849537 0.0065761 0.0289971 0.0846985 0.029051 0.0347971 0.0798303 0.046677 0.0347971 0.0709778 0.0474948 0.0289971 0.0704332 0.0617865 0.0347971 0.0582992 0.0455875 0.000297063 -0.0127468 0.038223 0.00899706 -0.00529036 0.0515558 0.000297063 -0.0213616 0.0559488 0.00899706 -0.0308767 0.0593109 0.00899706 -0.0462082 0.0586351 0.000297063 -0.0410069 0.0586185 0.00899706 -0.0618887 -0.0275814 0.00899706 -0.0245968 -0.0274181 0.00899706 -0.0218985 -0.0284185 0.000297063 -0.0193873 0.0200769 0.0349971 -0.0200783 0.0200769 0.00899706 -0.0200783 0.0262334 0.00899706 -0.0108648 0.0283953 0.0349971 3.38602e-06 0.0262337 0.0349971 0.0108716 0.0283953 0.00899706 3.38602e-06 0.0108639 0.0349971 0.0262418 -0.0108725 0.0349971 0.0262421 -4.30321e-06 0.00899706 0.0284037 -0.0200862 0.0349971 0.0200858 -0.0262427 0.0349971 0.0108723 -0.0262427 0.00899706 0.0108723 -0.026243 0.0349971 -0.0108641 -0.0108732 0.0349971 -0.0262343 -0.0108732 0.00899706 -0.0262343 -5.03036e-06 0.0349971 -0.0283963 -5.03036e-06 0.00899706 -0.0283963 0.0316551 0.000297063 -0.172894 0.0336403 0.00899706 -0.161062 0.0276387 0.000297063 -0.170123 0.0267601 0.000297063 -0.167074 0.0273432 0.000297063 -0.164416 0.0274118 0.00899706 -0.164276 0.0315035 0.000297063 -0.16113 0.0294174 0.000297063 -0.162014 0.0168564 0.000297063 -0.227778 0.0180326 0.00899706 -0.228474 0.0175026 0.00899706 -0.228205 0.0151197 0.000297063 -0.225691 0.0171456 0.000297063 -0.218009 0.019994 0.00899706 -0.217016 0.0216276 0.00449351 -0.217107 0.0410772 0.0217316 -0.108052 0.040979 0.00799706 -0.109136 0.0415879 0.0211262 -0.111261 0.044607 0.0206799 -0.104582 0.0449348 0.00799706 -0.10453 0.0414092 0.021742 -0.107072 0.0428826 0.00799706 -0.10532 0.0428583 0.021432 -0.105337 0.0282617 0.00799706 -0.167136 0.0288712 0.0184414 -0.169262 0.0288649 0.00799706 -0.169251 0.0291374 0.0182507 -0.169667 0.0303981 0.00799706 -0.170827 0.0317958 0.0158375 -0.171392 0.0316172 0.0160717 -0.171349 0.0337234 0.00799706 -0.162601 0.0301654 0.00799706 -0.16332 0.0283481 0.0191077 -0.166109 0.0287575 0.0191152 -0.164939 0.0163498 0.0165772 -0.224781 0.015983 0.00799706 -0.223136 0.0159809 0.0170297 -0.222996 0.0181194 0.00799706 -0.226827 0.0181726 0.0144956 -0.226859 0.0169175 0.0159956 -0.225745 0.0165862 0.00799706 -0.225251 0.0214446 0.0126626 -0.218601 0.0214446 0.00799706 -0.218601 0.020796 0.0135999 -0.218508 0.016454 0.00799706 -0.220988 0.0178866 0.00799706 -0.21932 0.0176952 0.0163529 -0.219462 0.00563626 0.0199971 -0.270325 0.00560438 0.0294918 -0.274277 0.00536879 0.0298526 -0.270988 0.00730164 0.0199971 -0.276164 0.00577525 0.0293852 -0.274599 0.00839601 0.0281305 -0.268015 0.00621088 0.0294507 -0.269447 0.00706889 0.0199971 -0.268656 0.0578956 -0.00210294 0.0241405 0.0565322 -0.00210294 0.0227771 0.0546697 -0.00210294 0.022278 0.0528072 -2.93696e-06 0.0227771 0.0528072 -0.00210294 0.0227771 0.0514438 -2.93696e-06 0.0241406 0.0514438 -0.00210294 0.0241406 0.0509447 -2.93696e-06 0.0260031 0.0509447 -0.00210294 0.0260031 0.0514438 -2.93696e-06 0.0278656 0.0514438 -0.00210294 0.0278656 0.0546698 -0.00210294 0.029728 0.0565323 -0.00210294 0.029229 0.0565323 -2.93696e-06 0.029229 0.0578957 -0.00210294 0.0278655 0.0583947 -2.93696e-06 0.026003 -0.00162197 -2.93696e-06 0.039861 -0.00298543 -0.00210294 0.0384976 -0.00484794 -2.93696e-06 0.0379986 -0.00671043 -2.93696e-06 0.0384976 -0.00807386 -2.93696e-06 0.0398611 -0.00807386 -0.00210294 0.0398611 -0.00857289 -0.00210294 0.0417236 -0.00807381 -0.00210294 0.0435861 -0.00807381 -2.93696e-06 0.0435861 -0.00671035 -2.93696e-06 0.0449495 -0.00484785 -2.93696e-06 0.0454486 -0.00484785 -0.00210294 0.0454486 -0.00298535 -0.00210294 0.0449495 -0.00162193 -0.00210294 0.043586 -0.00112289 -2.93696e-06 0.0417235 -0.0308508 -2.93696e-06 -0.0255373 -0.0322142 -0.00210294 -0.0269008 -0.0322142 -2.93696e-06 -0.0269008 -0.0340767 -2.93696e-06 -0.0273998 -0.0359392 -2.93696e-06 -0.0269007 -0.0373026 -2.93696e-06 -0.0255373 -0.0373026 -0.00210294 -0.0218123 -0.0322141 -2.93696e-06 -0.0204489 -0.0308507 -0.00210294 -0.0218123 -0.0308507 -2.93696e-06 -0.0218123 0.0653806 -2.93696e-06 -0.0318596 0.0653806 -0.00210294 -0.0318596 0.0640171 -2.93696e-06 -0.033223 0.0621546 -0.00210294 -0.033722 0.0589287 -0.00210294 -0.0318595 0.0589287 -2.93696e-06 -0.0318595 0.0584296 -0.00210294 -0.029997 0.0589287 -0.00210294 -0.0281345 0.0621547 -0.00210294 -0.026272 0.0621547 -2.93696e-06 -0.026272 0.0640172 -0.00210294 -0.0267711 0.0653806 -0.00210294 -0.0281346 0.0658796 -0.00210294 -0.0299971 0.0167309 0.000297063 -0.222996 0.0172332 0.00249706 -0.224871 0.0186058 0.000297063 -0.226244 0.0204808 0.000297063 -0.226747 0.0223558 0.00249706 -0.226244 0.0223558 0.000297063 -0.226244 0.0237284 0.000297063 -0.224872 0.0242309 0.000297063 -0.222997 0.0237285 0.00249706 -0.221122 0.0223559 0.000297063 -0.219749 0.0204809 0.000297063 -0.219247 0.0204809 0.00249706 -0.219247 0.0186059 0.00249706 -0.219749 0.0172333 0.00249706 -0.221121 0.0167309 0.00249706 -0.222996 -0.0456661 0.000297063 -0.156816 -0.0451637 0.000297063 -0.158691 -0.0437911 0.00249706 -0.160064 -0.0419161 0.00249706 -0.160566 -0.0400411 0.000297063 -0.160064 -0.0386685 0.00249706 -0.158691 -0.0386685 0.000297063 -0.158691 -0.0381661 0.00249706 -0.156816 -0.040041 0.000297063 -0.153568 -0.041916 0.00249706 -0.153066 -0.041916 0.000297063 -0.153066 -0.043791 0.00249706 -0.153568 -0.043791 0.000297063 -0.153568 -0.0451636 0.00249706 -0.154941 0.029512 0.00249706 -0.168872 0.029512 0.000297063 -0.168872 0.0308845 0.00249706 -0.170244 0.0346345 0.00249706 -0.170244 0.0365096 0.00249706 -0.166997 0.0360072 0.00249706 -0.165122 0.0346346 0.00249706 -0.163749 0.0346346 0.000297063 -0.163749 0.0327596 0.00249706 -0.163247 0.0308846 0.00249706 -0.163749 0.0290096 0.000297063 -0.166997 -0.0423933 0.000297063 -0.0975285 -0.0418909 0.000297063 -0.0994035 -0.0405183 0.00249706 -0.100776 -0.0405183 0.000297063 -0.100776 -0.0367683 0.00249706 -0.100776 -0.0353957 0.00249706 -0.0994036 -0.0348933 0.00249706 -0.0975286 -0.0348933 0.000297063 -0.0975286 -0.0353956 0.000297063 -0.0956536 -0.0386432 0.00249706 -0.0937785 -0.0423933 0.00249706 -0.0975285 -0.0418908 0.000297063 -0.0956535 -0.0522018 0.000297063 -0.275212 -0.0503269 0.00249706 -0.27846 -0.0484519 0.00249706 -0.278962 -0.0452042 0.00249706 -0.273338 -0.0465768 0.00249706 -0.271965 -0.0484518 0.000297063 -0.271462 -0.0484518 0.00249706 -0.271462 -0.0503268 0.000297063 -0.271965 -0.0516994 0.000297063 -0.273337 -0.0522018 0.00249706 -0.275212 0.00591311 0.00249706 -0.272333 0.00641549 0.00249706 -0.274208 0.00778807 0.00249706 -0.275581 0.00778807 0.000297063 -0.275581 0.0115381 0.00249706 -0.275581 0.0134131 0.00249706 -0.272333 0.0129107 0.00249706 -0.270458 0.0115382 0.00249706 -0.269086 0.00778815 0.00249706 -0.269086 0.00966316 0.000297063 -0.268583 -0.048826 0.000297063 -0.214059 -0.0483236 0.00249706 -0.215934 -0.0469511 0.00249706 -0.217307 -0.0483236 0.000297063 -0.215934 -0.0469511 0.000297063 -0.217307 -0.0450761 0.00249706 -0.217809 -0.0450761 0.000297063 -0.217809 -0.041326 0.00249706 -0.214059 -0.0418285 0.000297063 -0.215934 -0.043201 0.000297063 -0.210811 -0.0483236 0.00249706 -0.212184 -0.0483236 0.000297063 -0.212184 0.0417268 0.00249706 -0.108997 0.0436018 0.00249706 -0.112244 0.0473518 0.00249706 -0.112244 0.0473518 0.000297063 -0.112244 0.0487244 0.00249706 -0.110872 0.0487244 0.000297063 -0.110872 0.0487245 0.00249706 -0.107122 0.0473519 0.000297063 -0.105749 0.0422293 0.00249706 -0.107122 0.0422293 0.000297063 -0.107122 0.0227325 0.00249706 -0.224297 0.0227325 0.00799706 -0.224297 0.0217808 0.00249706 -0.225248 0.0217808 0.00799706 -0.225248 0.0204808 0.00799706 -0.225597 0.0191808 0.00799706 -0.225248 0.0182292 0.00249706 -0.224296 0.0182292 0.00249706 -0.221696 0.0204809 0.00799706 -0.220397 0.0217809 0.00249706 -0.220745 0.0227325 0.00249706 -0.221697 -0.0428244 0.00799706 -0.215359 -0.0437761 0.00799706 -0.216311 -0.0450761 0.00799706 -0.216659 -0.0473277 0.00249706 -0.215359 -0.0463761 0.00799706 -0.216311 -0.0473277 0.00799706 -0.212759 -0.046376 0.00799706 -0.211807 -0.045076 0.00249706 -0.211459 -0.0428243 0.00249706 -0.212759 -0.042476 0.00249706 -0.214059 -0.0428243 0.00799706 -0.212759 0.0350112 0.00249706 -0.168297 0.0340596 0.00799706 -0.169248 0.0305079 0.00249706 -0.168297 0.0314596 0.00799706 -0.169248 0.0305079 0.00249706 -0.165697 0.0314596 0.00799706 -0.164745 0.0327596 0.00799706 -0.164397 0.0340596 0.00249706 -0.164745 0.0340596 0.00799706 -0.164745 0.0350113 0.00249706 -0.165697 0.0350113 0.00799706 -0.165697 0.0353596 0.00249706 -0.166997 0.0353596 0.00799706 -0.166997 -0.0393161 0.00249706 -0.156816 -0.0396644 0.00799706 -0.158116 -0.0406161 0.00249706 -0.159068 -0.0419161 0.00799706 -0.159416 -0.0432161 0.00249706 -0.159068 -0.0441678 0.00249706 -0.158116 -0.0445161 0.00249706 -0.156816 -0.043216 0.00249706 -0.154564 -0.0441677 0.00799706 -0.155516 -0.043216 0.00799706 -0.154564 -0.041916 0.00249706 -0.154216 -0.040616 0.00249706 -0.154564 -0.041916 0.00799706 -0.154216 -0.0396644 0.00249706 -0.155516 0.0480768 0.00249706 -0.108997 0.0454768 0.00799706 -0.111597 0.0441768 0.00799706 -0.111248 0.0432252 0.00249706 -0.110297 0.0428768 0.00799706 -0.108997 0.0428768 0.00249706 -0.108997 0.0432252 0.00799706 -0.107697 0.0432252 0.00249706 -0.107697 0.0441769 0.00799706 -0.106745 0.0454769 0.00249706 -0.106397 0.0467769 0.00249706 -0.106745 0.0477285 0.00249706 -0.107697 0.0467769 0.00799706 -0.106745 -0.0399433 0.00249706 -0.0997802 -0.0408949 0.00249706 -0.0988285 -0.0399433 0.00799706 -0.0997802 -0.0408949 0.00799706 -0.0962285 -0.0363916 0.00249706 -0.0962286 -0.0363916 0.00799706 -0.0962286 0.0122631 0.0199971 -0.272333 0.00966308 0.00249706 -0.274933 0.0109631 0.0199971 -0.274585 0.00836308 0.00249706 -0.274585 0.00741143 0.00249706 -0.273633 0.00741146 0.0199971 -0.271033 0.0109631 0.00249706 -0.270082 -0.0458518 0.00249706 -0.275212 -0.0462002 0.0199971 -0.276513 -0.0507035 0.0199971 -0.276512 -0.0507035 0.00249706 -0.276512 -0.0510518 0.00249706 -0.275212 -0.0510518 0.0199971 -0.275212 -0.0507035 0.00249706 -0.273912 -0.0497518 0.00249706 -0.272961 -0.0507035 0.0199971 -0.273912 -0.0497518 0.0199971 -0.272961 -0.0484518 0.0199971 -0.272612 -0.0340767 0.0135971 -0.0257748 -0.0330267 0.0135971 -0.0218562 -0.0319767 0.0135971 -0.0236748 -0.032258 0.0135971 -0.0226248 -0.0351267 0.0135971 -0.0218561 -0.0358953 0.0135971 -0.0226248 -0.0340767 0.0148589 -0.0236748 -0.0358953 0.0135971 -0.0247248 -0.0351267 0.0135971 -0.0254934 -0.0351267 -0.00240294 -0.0254934 -0.0330267 0.0135971 -0.0254935 -0.032258 0.0135971 -0.0247248 -0.032258 -0.00240294 -0.0226248 -0.0340766 0.0135971 -0.0215748 -0.0351267 -0.00240294 -0.0218561 -0.0361767 0.0135971 -0.0236748 -0.00484789 0.0148589 0.0417236 -0.00666656 0.0135971 0.0406736 -0.00484792 0.0135971 0.0396236 -0.00379792 0.0135971 0.0399049 -0.00302923 0.0135971 0.0427735 -0.00666653 0.0135971 0.0427736 -0.00589792 0.0135971 0.0399049 -0.00589792 -0.00240294 0.0399049 -0.00302925 0.0135971 0.0406735 -0.00302925 -0.00240294 0.0406735 -0.00274789 0.0135971 0.0417235 -0.00274789 -0.00240294 0.0417235 -0.00379787 0.0135971 0.0435422 -0.00484787 0.0135971 0.0438236 -0.00379787 -0.00240294 0.0435422 -0.00589787 0.0135971 0.0435422 -0.00484787 -0.00240294 0.0438236 -0.00694789 0.0135971 0.0417236 -0.00666653 -0.00240294 0.0427736 -0.00694789 -0.00240294 0.0417236 0.0546697 0.0135971 0.023903 0.0546697 0.0148589 0.026003 0.0567697 0.0135971 0.026003 0.0536197 0.0135971 0.0278217 0.0528511 0.0135971 0.0270531 0.0525697 0.0135971 0.0260031 0.0528511 0.0135971 0.0249531 0.0528511 -0.00240294 0.0249531 0.0536197 0.0135971 0.0241844 0.0546697 -0.00240294 0.023903 0.0557197 -0.00240294 0.0241844 0.0557197 0.0135971 0.0241844 0.0564884 0.0135971 0.024953 0.0564884 0.0135971 0.027053 0.0557197 0.0135971 0.0278217 0.0546697 0.0135971 0.028103 0.0557197 -0.00240294 0.0278217 0.0546697 -0.00240294 0.028103 0.0536197 -0.00240294 0.0278217 0.0528511 -0.00240294 0.0270531 0.060336 0.0135971 -0.031047 0.0611046 0.0135971 -0.0318157 0.0639733 0.0135971 -0.0289471 0.0632047 0.0135971 -0.0281784 0.0611047 0.0135971 -0.0281784 0.060336 0.0135971 -0.028947 0.0600546 0.0135971 -0.029997 0.0621546 0.0148589 -0.029997 0.0621546 0.0135971 -0.032097 0.0632046 0.0135971 -0.0318157 0.0639733 0.0135971 -0.0310471 0.0642546 0.0135971 -0.0299971 0.0621547 0.0135971 -0.027897 0.0621547 -0.00240294 -0.027897 0.0600546 -0.00240294 -0.029997 0.048858 0.0259971 0.0635062 0.0496267 0.0259971 0.0642748 0.0478081 0.0247353 0.0653248 0.0499081 0.0259971 0.0653248 0.0496267 0.0349971 0.0642748 0.048858 0.0349971 0.0635062 0.047808 0.0259971 0.0632248 0.047808 0.0349971 0.0632248 0.046758 0.0259971 0.0635062 0.0459894 0.0259971 0.0642749 0.0457081 0.0259971 0.0653249 0.0459894 0.0259971 0.0663749 0.0459894 0.0349971 0.0663749 0.0467581 0.0259971 0.0671435 0.0478081 0.0259971 0.0674248 0.0488581 0.0259971 0.0671435 0.0496267 0.0259971 0.0663748 0.0691533 0.0259971 0.0438794 0.0694347 0.0259971 0.0449294 0.0683847 0.0259971 0.0431107 0.0673347 0.0247353 0.0449294 0.065516 0.0259971 0.0438794 0.0652347 0.0259971 0.0449294 0.0673347 0.0259971 0.0470294 0.0673347 0.0259971 0.0428294 0.0683847 0.0349971 0.0431107 0.0662847 0.0259971 0.0431108 0.0673347 0.0349971 0.0428294 0.0662847 0.0349971 0.0431108 0.065516 0.0259971 0.0459794 0.065516 0.0349971 0.0459794 0.0662847 0.0259971 0.0467481 0.0662847 0.0349971 0.0467481 0.0673347 0.0349971 0.0470294 0.0683847 0.0259971 0.0467481 0.0691533 0.0349971 0.0459794 0.0691533 0.0259971 0.0459794 0.0730129 0.0259971 0.0308485 0.0740629 0.0259971 0.0305671 0.0740629 0.0247353 0.0326671 0.0758816 0.0259971 0.0316171 0.0761629 0.0349971 0.0326671 0.0751129 0.0259971 0.0308484 0.0751129 0.0349971 0.0308484 0.0722443 0.0259971 0.0316171 0.0722443 0.0349971 0.0316171 0.0719629 0.0349971 0.0326671 0.0719629 0.0259971 0.0326671 0.0722443 0.0259971 0.0337171 0.0730129 0.0259971 0.0344858 0.074063 0.0259971 0.0347671 0.074063 0.0349971 0.0347671 0.0751129 0.0259971 0.0344857 0.0751129 0.0349971 0.0344857 0.0758816 0.0259971 0.0337171 0.0758816 0.0349971 0.0337171 0.0761629 0.0259971 0.0326671 0.0807757 0.0247353 0.00524084 0.0789571 0.0259971 0.00419087 0.0807757 0.0259971 0.00314084 0.0789571 0.0259971 0.00629087 0.0807758 0.0259971 0.00734084 0.0797258 0.0259971 0.00705951 0.0825944 0.0259971 0.00629082 0.0828758 0.0259971 0.00524082 0.0825944 0.0259971 0.00419082 0.0818257 0.0259971 0.00342218 0.0825944 0.0349971 0.00419082 0.0818257 0.0349971 0.00342218 0.0797257 0.0259971 0.0034222 0.0786757 0.0259971 0.00524087 0.0789571 0.0349971 0.00419087 0.0789571 0.0349971 0.00629087 0.0797258 0.0349971 0.00705951 0.0818258 0.0259971 0.00705948 0.0818258 0.0349971 0.00705948 0.0825944 0.0349971 0.00629082 0.0674164 0.0259971 -0.047809 0.0653164 0.0247353 -0.047809 0.0663664 0.0259971 -0.0496277 0.0634978 0.0259971 -0.046759 0.0653164 0.0259971 -0.045709 0.0642664 0.0259971 -0.0459903 0.0671351 0.0259971 -0.048859 0.0671351 0.0349971 -0.048859 0.0653164 0.0259971 -0.049909 0.0642664 0.0259971 -0.0496276 0.0642664 0.0349971 -0.0496276 0.0634978 0.0259971 -0.048859 0.0634978 0.0349971 -0.048859 0.0632164 0.0259971 -0.047809 0.0634978 0.0349971 -0.046759 0.0642664 0.0349971 -0.0459903 0.0663664 0.0259971 -0.0459903 0.0653164 0.0349971 -0.045709 0.0671351 0.0259971 -0.046759 0.0663664 0.0349971 -0.0459903 0.0671351 0.0349971 -0.046759 0.044921 0.0247353 -0.0673356 0.045971 0.0259971 -0.0691543 0.0431024 0.0259971 -0.0662856 0.045971 0.0259971 -0.065517 0.044921 0.0259971 -0.0652356 0.047021 0.0259971 -0.0673356 0.0467396 0.0259971 -0.0683856 0.045971 0.0349971 -0.0691543 0.044921 0.0259971 -0.0694356 0.043871 0.0259971 -0.0691542 0.0431023 0.0259971 -0.0683856 0.0431023 0.0349971 -0.0683856 0.042821 0.0349971 -0.0673356 0.042821 0.0259971 -0.0673356 0.0431024 0.0349971 -0.0662856 0.043871 0.0259971 -0.0655169 0.043871 0.0349971 -0.0655169 0.0467397 0.0259971 -0.0662856 0.0326587 0.0259971 -0.0761638 0.0316087 0.0259971 -0.0722452 0.03084 0.0259971 -0.0730138 0.0326587 0.0259971 -0.0719638 0.0326587 0.0247353 -0.0740638 0.0344773 0.0259971 -0.0751139 0.0337087 0.0259971 -0.0758825 0.0316087 0.0259971 -0.0758825 0.0316087 0.0349971 -0.0758825 0.03084 0.0259971 -0.0751138 0.0305587 0.0259971 -0.0740638 0.03084 0.0349971 -0.0730138 0.0337087 0.0259971 -0.0722452 0.0344774 0.0259971 -0.0730139 0.0347587 0.0259971 -0.0740639 0.0344774 0.0349971 -0.0730139 0.0062824 0.0259971 -0.0825953 0.0052324 0.0259971 -0.0828767 0.00341379 0.0259971 -0.0797266 0.00341376 0.0259971 -0.0818266 0.00705109 0.0259971 -0.0797267 0.00523243 0.0247353 -0.0807767 0.00733243 0.0259971 -0.0807767 0.00705107 0.0259971 -0.0818267 0.0062824 0.0349971 -0.0825953 0.0052324 0.0349971 -0.0828767 0.0041824 0.0259971 -0.0825953 0.00313243 0.0349971 -0.0807766 0.00313243 0.0259971 -0.0807766 0.00418245 0.0259971 -0.078958 0.00418245 0.0349971 -0.078958 0.00523246 0.0259971 -0.0786767 0.00628245 0.0259971 -0.078958 -0.0496361 0.0259971 -0.0663673 -0.0488674 0.0259971 -0.067136 -0.0478174 0.0259971 -0.0674173 -0.0499174 0.0259971 -0.0653173 -0.0478174 0.0247353 -0.0653173 -0.0478174 0.0259971 -0.0632173 -0.0459988 0.0259971 -0.0663674 -0.0459988 0.0349971 -0.0663674 -0.0467674 0.0259971 -0.067136 -0.0467674 0.0349971 -0.067136 -0.0478174 0.0349971 -0.0674173 -0.0488674 0.0349971 -0.067136 -0.049636 0.0259971 -0.0642673 -0.049636 0.0349971 -0.0642673 -0.0488674 0.0259971 -0.0634987 -0.0488674 0.0349971 -0.0634987 -0.0467674 0.0259971 -0.0634987 -0.0467674 0.0349971 -0.0634987 -0.0459987 0.0259971 -0.0642674 -0.0457174 0.0259971 -0.0653174 -0.067344 0.0247353 -0.0449219 -0.066294 0.0259971 -0.0467406 -0.0655254 0.0259971 -0.0459719 -0.068394 0.0259971 -0.0431032 -0.069444 0.0259971 -0.0449219 -0.067344 0.0259971 -0.0470219 -0.067344 0.0349971 -0.0470219 -0.068394 0.0259971 -0.0467406 -0.0691627 0.0259971 -0.0459719 -0.0691627 0.0349971 -0.0459719 -0.0691627 0.0259971 -0.0438719 -0.067344 0.0259971 -0.0428219 -0.068394 0.0349971 -0.0431032 -0.066294 0.0349971 -0.0431033 -0.066294 0.0259971 -0.0431033 -0.0655253 0.0259971 -0.0438719 -0.0655253 0.0349971 -0.0438719 -0.065244 0.0259971 -0.0449219 -0.0740723 0.0247353 -0.0326596 -0.0751223 0.0259971 -0.0344782 -0.0761723 0.0259971 -0.0326596 -0.0758909 0.0259971 -0.0337096 -0.0740722 0.0259971 -0.0305596 -0.0730222 0.0259971 -0.030841 -0.0722536 0.0259971 -0.0337096 -0.0722536 0.0349971 -0.0337096 -0.0730223 0.0259971 -0.0344783 -0.0740723 0.0259971 -0.0347596 -0.0730223 0.0349971 -0.0344783 -0.0740723 0.0349971 -0.0347596 -0.0751223 0.0349971 -0.0344782 -0.0761723 0.0349971 -0.0326596 -0.0758909 0.0259971 -0.0316096 -0.0751222 0.0259971 -0.0308409 -0.0758909 0.0349971 -0.0316096 -0.0751222 0.0349971 -0.0308409 -0.0730222 0.0349971 -0.030841 -0.0722536 0.0259971 -0.0316096 -0.0722536 0.0349971 -0.0316096 -0.0719723 0.0259971 -0.0326596 -0.0719723 0.0349971 -0.0326596 -0.0789664 0.0259971 -0.00628337 -0.0818351 0.0259971 -0.00705199 -0.0807851 0.0247353 -0.00523335 -0.0826037 0.0259971 -0.00418332 -0.0828851 0.0259971 -0.00523332 -0.0797351 0.0259971 -0.00341471 -0.0807851 0.0259971 -0.00313335 -0.0797351 0.0259971 -0.00705201 -0.0789664 0.0349971 -0.00628337 -0.0807851 0.0259971 -0.00733335 -0.0818351 0.0349971 -0.00705199 -0.0826037 0.0349971 -0.00628332 -0.0826037 0.0259971 -0.00628332 -0.0818351 0.0259971 -0.00341468 -0.0818351 0.0349971 -0.00341468 -0.0807851 0.0349971 -0.00313335 -0.0789664 0.0259971 -0.00418337 -0.0786851 0.0259971 -0.00523337 -0.0789664 0.0349971 -0.00418337 -0.0653258 0.0247353 0.0478165 -0.0635071 0.0259971 0.0467665 -0.0653258 0.0259971 0.0457165 -0.0642758 0.0259971 0.0459978 -0.0671444 0.0259971 0.0488665 -0.0642757 0.0259971 0.0496351 -0.0663757 0.0259971 0.0496352 -0.0632258 0.0259971 0.0478165 -0.0632258 0.0349971 0.0478165 -0.0642758 0.0349971 0.0459978 -0.0663758 0.0259971 0.0459978 -0.0653258 0.0349971 0.0457165 -0.0671444 0.0259971 0.0467665 -0.0663758 0.0349971 0.0459978 -0.0671444 0.0349971 0.0467665 -0.0674258 0.0349971 0.0478165 -0.0674258 0.0259971 0.0478165 -0.0671444 0.0349971 0.0488665 -0.0653257 0.0349971 0.0499165 -0.0653257 0.0259971 0.0499165 -0.0635071 0.0259971 0.0488665 -0.0459804 0.0259971 0.0655245 -0.0449304 0.0259971 0.0652431 -0.0449303 0.0247353 0.0673431 -0.046749 0.0259971 0.0662931 -0.0459803 0.0259971 0.0691618 -0.0431117 0.0259971 0.0683931 -0.0428303 0.0259971 0.0673431 -0.0431117 0.0259971 0.0662931 -0.0431117 0.0349971 0.0662931 -0.0438804 0.0259971 0.0655244 -0.0438804 0.0349971 0.0655244 -0.0449304 0.0349971 0.0652431 -0.0459804 0.0349971 0.0655245 -0.0470303 0.0259971 0.0673431 -0.0470303 0.0349971 0.0673431 -0.046749 0.0259971 0.0683931 -0.0459803 0.0349971 0.0691618 -0.0449303 0.0259971 0.0694431 -0.0438803 0.0259971 0.0691617 -0.0438803 0.0349971 0.0691617 -0.0431117 0.0349971 0.0683931 -0.0308494 0.0259971 0.0730213 -0.030568 0.0259971 0.0740713 -0.0344867 0.0259971 0.0730214 -0.033718 0.0259971 0.0722527 -0.031618 0.0259971 0.0722527 -0.0344867 0.0259971 0.0751214 -0.032668 0.0247353 0.0740713 -0.031618 0.0259971 0.07589 -0.032668 0.0259971 0.0761713 -0.030568 0.0349971 0.0740713 -0.031618 0.0349971 0.0722527 -0.032668 0.0259971 0.0719713 -0.032668 0.0349971 0.0719713 -0.0344867 0.0349971 0.0730214 -0.034768 0.0349971 0.0740714 -0.034768 0.0259971 0.0740714 -0.0344867 0.0349971 0.0751214 -0.033718 0.0259971 0.07589 -0.031618 0.0349971 0.07589 -0.0308494 0.0259971 0.0751213 -0.0308494 0.0349971 0.0751213 -0.00524176 0.0247353 0.0807842 -0.00706043 0.0259971 0.0797342 -0.00419174 0.0259971 0.0826028 -0.00342309 0.0259971 0.0818341 -0.00314176 0.0259971 0.0807841 -0.00342312 0.0259971 0.0797341 -0.00342312 0.0349971 0.0797341 -0.00419179 0.0259971 0.0789655 -0.00419179 0.0349971 0.0789655 -0.00524179 0.0259971 0.0786842 -0.00629179 0.0259971 0.0789655 -0.00629179 0.0349971 0.0789655 -0.00734176 0.0259971 0.0807842 -0.0070604 0.0259971 0.0818342 -0.00734176 0.0349971 0.0807842 -0.0070604 0.0349971 0.0818342 -0.00629174 0.0259971 0.0826028 -0.00524173 0.0259971 0.0828842 -0.00524173 0.0349971 0.0828842 -0.00419174 0.0349971 0.0826028 -0.00342309 0.0349971 0.0818341 -0.00433931 0.0314971 -0.352496 -0.0025092 0.0314971 -0.354326 0.00499085 0.0314971 -0.349996 0.00499085 0.0194971 -0.349996 0.00249091 0.0314971 -0.345666 -9.08344e-06 0.0314971 -0.344996 -9.08344e-06 0.0194971 -0.344996 -0.00433924 0.0314971 -0.347496 -0.00250909 0.0194971 -0.345666 -0.00500915 0.0314971 -0.349996 -0.00433924 0.0194971 -0.347496 -0.00500915 0.0194971 -0.349996 0.0340117 0.0224789 -0.118846 0.0335012 0.0227285 -0.116618 0.0336585 0.0228743 -0.114339 -0.0325009 0.0183971 -0.121923 -0.0295096 0.0220107 -0.123659 -0.0306999 0.0183971 -0.123315 -0.0284564 0.0183971 -0.123697 -0.0255663 0.0227394 -0.12241 -0.033437 0.0183971 -0.119849 -0.0332887 0.0183971 -0.117578 -0.0332693 0.0212554 -0.117519 -0.0325731 0.0215393 -0.116192 -0.0354604 0.0200271 -0.0856406 -0.0354196 0.0183971 -0.0868859 -0.035484 0.0200942 -0.0861109 -0.0346877 0.0183971 -0.0887284 -0.0337058 0.0218895 -0.0897925 0.0024908 0.0314971 -0.354326 -9.21146e-06 0.0314971 -0.354996 -0.00550915 0.0319971 -0.349996 -0.00250909 0.0314971 -0.345666 -9.07704e-06 0.0319971 -0.344496 0.00274091 0.0319971 -0.345233 0.00432101 0.0314971 -0.347496 0.00432095 0.0314971 -0.352496 -0.0303517 -0.00210294 -0.0236748 -0.0308508 -0.00210294 -0.0255373 -0.0323642 -0.00240294 -0.026641 -0.0340767 -0.00240294 -0.0270998 -0.0340767 -0.00210294 -0.0273998 -0.0359392 -0.00210294 -0.0269007 -0.0373026 -0.00210294 -0.0255373 -0.0378017 -0.00210294 -0.0236747 -0.0359391 -0.00210294 -0.0204488 -0.0340766 -0.00240294 -0.0202498 -0.0340766 -0.00210294 -0.0199498 -0.0322141 -0.00210294 -0.0204489 -0.00162197 -0.00210294 0.039861 -0.00313543 -0.00240294 0.0387574 -0.00484794 -0.00210294 0.0379986 -0.00484794 -0.00240294 0.0382986 -0.00671043 -0.00210294 0.0384976 -0.00656043 -0.00240294 0.0387575 -0.00781405 -0.00240294 0.0400111 -0.00827289 -0.00240294 0.0417236 -0.00781401 -0.00240294 0.0434361 -0.00671035 -0.00210294 0.0449495 -0.00656036 -0.00240294 0.0446897 -0.00188173 -0.00240294 0.043436 -0.00142289 -0.00240294 0.0417235 -0.00112289 -0.00210294 0.0417235 0.0583947 -0.00210294 0.026003 0.0529572 -0.00240294 0.0230369 0.0512447 -0.00240294 0.0260031 0.0517036 -0.00240294 0.0277156 0.0528073 -0.00210294 0.029229 0.0546698 -0.00240294 0.029428 0.0580947 -0.00240294 0.026003 0.0651207 -0.00240294 -0.0317096 0.0638671 -0.00240294 -0.0329632 0.0640171 -0.00210294 -0.033223 0.0621546 -0.00240294 -0.033422 0.0604421 -0.00240294 -0.0329632 0.0602921 -0.00210294 -0.033223 0.0602922 -0.00210294 -0.0267711 0.0638672 -0.00240294 -0.0270309 0.0651208 -0.00240294 -0.0282846 -0.0437911 0.000297063 -0.160064 -0.0419161 0.000297063 -0.160566 -0.0419161 -2.93696e-06 -0.160866 -0.0381661 0.000297063 -0.156816 -0.0378661 -2.93696e-06 -0.156816 -0.0386684 0.000297063 -0.154941 -0.041916 -2.93696e-06 -0.152766 -0.0451636 0.000297063 -0.154941 -0.0454234 -2.93696e-06 -0.154791 -0.0459661 -2.93696e-06 -0.156816 -0.0454235 -2.93696e-06 -0.158841 -0.0421507 -2.93696e-06 -0.0995535 -0.0406683 -2.93696e-06 -0.101036 -0.0386433 0.000297063 -0.101279 -0.0367683 0.000297063 -0.100776 -0.0386433 -2.93696e-06 -0.101579 -0.0353957 0.000297063 -0.0994036 -0.0367682 0.000297063 -0.094281 -0.0386432 0.000297063 -0.0937785 -0.0386432 -2.93696e-06 -0.0934785 -0.0405182 0.000297063 -0.0942809 0.0422292 0.000297063 -0.110872 0.0436018 0.000297063 -0.112244 0.0434518 -2.93696e-06 -0.112504 0.0454768 0.000297063 -0.112747 0.0454768 -2.93696e-06 -0.113047 0.0492268 0.000297063 -0.108997 0.0489842 -2.93696e-06 -0.111022 0.0495268 -2.93696e-06 -0.108997 0.0487245 0.000297063 -0.107122 0.0454769 0.000297063 -0.105247 0.0436019 0.000297063 -0.105749 0.0434519 -2.93696e-06 -0.105489 0.0417268 0.000297063 -0.108997 0.0308845 0.000297063 -0.170244 0.0327595 0.000297063 -0.170747 0.0346345 0.000297063 -0.170244 0.0360072 0.000297063 -0.168872 0.036267 -2.93696e-06 -0.169022 0.0368096 -2.93696e-06 -0.166997 0.0365096 0.000297063 -0.166997 0.0360072 0.000297063 -0.165122 0.036267 -2.93696e-06 -0.164972 0.0347846 -2.93696e-06 -0.163489 0.0327596 -2.93696e-06 -0.162947 0.0327596 0.000297063 -0.163247 0.0308846 0.000297063 -0.163749 0.0307346 -2.93696e-06 -0.163489 0.029512 0.000297063 -0.165122 0.0287096 -2.93696e-06 -0.166997 -0.0485835 -2.93696e-06 -0.216084 -0.0432011 0.000297063 -0.217307 -0.0415686 -2.93696e-06 -0.216084 -0.041326 0.000297063 -0.214059 -0.041026 -2.93696e-06 -0.214059 -0.0418284 0.000297063 -0.212184 -0.045076 0.000297063 -0.210309 -0.043051 -2.93696e-06 -0.210552 -0.045076 -2.93696e-06 -0.210009 -0.047101 -2.93696e-06 -0.210552 -0.046951 0.000297063 -0.210811 -0.0485834 -2.93696e-06 -0.212034 -0.0519593 -2.93696e-06 -0.277237 -0.0503269 0.000297063 -0.27846 -0.0504769 -2.93696e-06 -0.27872 -0.0484519 0.000297063 -0.278962 -0.0465769 0.000297063 -0.27846 -0.0452043 0.000297063 -0.277088 -0.0447018 0.000297063 -0.275213 -0.0452042 0.000297063 -0.273338 -0.0449444 -2.93696e-06 -0.273188 -0.0465768 0.000297063 -0.271965 -0.0484518 -2.93696e-06 -0.271162 -0.0504768 -2.93696e-06 -0.271705 -0.0525018 -2.93696e-06 -0.275212 -0.0516995 0.000297063 -0.277087 0.0172332 0.000297063 -0.224871 0.0184558 -2.93696e-06 -0.226504 0.0204808 -2.93696e-06 -0.227047 0.0239882 -2.93696e-06 -0.225022 0.0237285 0.000297063 -0.221122 0.0186059 0.000297063 -0.219749 0.0172333 0.000297063 -0.221121 0.0184559 -2.93696e-06 -0.219489 0.00966306 0.000297063 -0.276083 0.00966306 -2.93696e-06 -0.276383 0.0115381 0.000297063 -0.275581 0.0116881 -2.93696e-06 -0.275841 0.0129107 0.000297063 -0.274208 0.0134131 0.000297063 -0.272333 0.0137131 -2.93696e-06 -0.272333 0.0129107 0.000297063 -0.270458 0.0115382 0.000297063 -0.269086 0.0116882 -2.93696e-06 -0.268826 0.00778815 0.000297063 -0.269086 0.00763816 -2.93696e-06 -0.268826 0.00641554 0.000297063 -0.270458 0.00591311 0.000297063 -0.272333 0.00561311 -2.93696e-06 -0.272333 0.00641549 0.000297063 -0.274208 0.0575288 -2.93696e-06 -0.0728672 0.0576047 -2.93696e-06 -0.071807 0.0573054 0.000297063 -0.0718276 0.0573455 0.000147063 -0.0718249 0.0572355 0.000297063 -0.0728041 0.057455 3.72554e-05 -0.0718173 0.0570732 0.00899706 -0.0706734 0.0570699 0.000297063 -0.0707517 0.038223 0.000297063 -0.00529036 0.0588175 1.98992e-05 -0.0409751 0.0588009 1.98992e-05 -0.0619208 0.0562311 -2.93696e-06 -0.030775 0.0528249 -2.93696e-06 -0.0230505 0.0518163 -2.93696e-06 -0.0212128 0.0458184 -2.93696e-06 -0.0125552 0.0517166 1.98992e-05 -0.0212697 0.0516321 8.4931e-05 -0.021318 0.0457301 1.98992e-05 -0.0126286 0.0382799 8.4931e-05 -0.00522343 0.038249 0.000147063 -0.00525974 0.0456552 8.4931e-05 -0.0126907 0.0560315 8.4931e-05 -0.0308469 0.0559703 0.000182258 -0.030869 0.0597191 1.98992e-05 -0.0514486 0.0561231 1.98992e-05 -0.0308139 0.0596218 8.4931e-05 -0.0514486 0.0587216 8.4931e-05 -0.0409918 0.0586561 0.000185975 -0.0410032 0.0595553 0.000185997 -0.0514485 0.0593109 0.000297063 -0.0462082 0.0595339 0.000297063 -0.0514485 0.045604 0.000185766 -0.0127331 0.0487584 0.000297063 -0.0169248 0.0515743 0.000185996 -0.0213511 0.0559488 0.000297063 -0.0308767 -0.0289075 0.000147063 -0.0269426 -0.0289433 8.4931e-05 -0.0269111 -0.0289901 3.72554e-05 -0.0268702 -0.0278697 -2.93696e-06 -0.0245138 -0.0275814 0.000297063 -0.0245968 -0.0276034 0.000182258 -0.0245904 -0.0274181 0.000297063 -0.0218985 -0.0276658 8.4931e-05 -0.0245725 -0.0277594 1.98992e-05 -0.0245455 -0.027601 1.98992e-05 -0.0219279 -0.0274407 0.000182258 -0.0219022 -0.0284911 8.4931e-05 -0.0194368 -0.0275049 8.4931e-05 -0.0219125 -0.0277143 -2.93696e-06 -0.0219461 -0.0285715 1.98992e-05 -0.0194917 -0.0391555 0.000297063 -0.103507 -0.0391427 3.72554e-05 -0.103357 -0.0374037 0.000147063 -0.103358 -0.0373953 0.000297063 -0.103397 -0.0349283 0.000297063 -0.10224 -0.0349532 0.000147063 -0.102209 -0.032684 0.000147063 -0.09745 -0.0333333 0.000147063 -0.0948223 -0.0350538 0.000297063 -0.0927207 -0.0350778 0.000147063 -0.0927529 -0.036718 0.000147063 -0.0918882 -0.0391479 8.36794e-05 -0.103418 -0.0350212 3.72554e-05 -0.102122 -0.0332638 0.000147063 -0.100094 -0.0374265 3.72554e-05 -0.103251 -0.0374577 -2.93696e-06 -0.103104 -0.0333629 3.72554e-05 -0.100047 -0.0334983 -2.93696e-06 -0.099982 -0.0327938 3.72554e-05 -0.0974514 -0.0334311 3.72554e-05 -0.0948722 -0.0351435 3.72554e-05 -0.0928409 -0.0335648 -2.93696e-06 -0.0949403 -0.0352332 -2.93696e-06 -0.0929611 -0.0367535 3.72554e-05 -0.0919922 -0.042432 0.000297063 -0.162794 -0.0424302 0.000185841 -0.162772 -0.0417704 0.00018584 -0.150839 -0.0404877 0.000147063 -0.162602 -0.0378199 0.000297063 -0.1612 -0.0378474 0.000147063 -0.161171 -0.036202 0.000297063 -0.158646 -0.0360744 0.000147063 -0.155635 -0.0398447 0.000297063 -0.151185 -0.0398586 0.000147063 -0.151223 -0.0405141 3.72554e-05 -0.162495 -0.0362402 0.000147063 -0.158634 -0.0373921 0.000147063 -0.152936 -0.0374754 3.72554e-05 -0.153008 -0.0417709 0.000147063 -0.150858 -0.04055 -2.93696e-06 -0.16235 -0.0379223 3.72554e-05 -0.161091 -0.0363448 3.72554e-05 -0.1586 -0.0361821 3.72554e-05 -0.155657 -0.0398965 3.72554e-05 -0.151326 -0.0399483 -2.93696e-06 -0.151466 -0.0455472 8.38792e-05 -0.219951 -0.0455511 0.000147063 -0.22 -0.0455526 0.00018597 -0.220019 -0.0455424 3.72554e-05 -0.21989 -0.0436147 0.000147063 -0.219837 -0.040959 0.000297063 -0.218424 -0.0409866 0.000147063 -0.218394 -0.0393932 0.000147063 -0.215855 -0.0391985 0.000297063 -0.212853 -0.0392379 0.000147063 -0.212861 -0.0405598 0.000147063 -0.21017 -0.0430245 0.000147063 -0.208463 -0.0449336 0.000147063 -0.208101 -0.0436417 3.72554e-05 -0.21973 -0.0410619 3.72554e-05 -0.218315 -0.0393454 3.72554e-05 -0.212883 -0.040643 3.72554e-05 -0.210242 -0.0430623 3.72554e-05 -0.208566 -0.0411649 -2.93696e-06 -0.218205 -0.0394979 3.72554e-05 -0.215822 -0.043114 -2.93696e-06 -0.208707 -0.0434688 0.000147063 -0.271943 -0.0434352 0.000297063 -0.271921 -0.0425061 0.000147063 -0.274804 -0.0457095 0.000147063 -0.269921 -0.0478366 0.000147063 -0.28114 -0.0450112 0.000147063 -0.280079 -0.0450746 3.72554e-05 -0.279989 -0.0431675 3.72554e-05 -0.277722 -0.043032 0.000297063 -0.277786 -0.0430683 0.000147063 -0.277769 -0.042466 0.000297063 -0.274801 -0.0426156 3.72554e-05 -0.274811 -0.043303 -2.93696e-06 -0.277658 -0.0435606 3.72554e-05 -0.272003 -0.0457601 3.72554e-05 -0.270019 -0.043686 -2.93696e-06 -0.272086 -0.0458291 -2.93696e-06 -0.270152 0.0129252 0.0199971 -0.277716 0.012945 0.0200732 -0.277729 0.0132317 0.0200736 -0.278019 0.0132319 0.0199971 -0.278019 0.0133691 0.0199971 -0.278776 0.0133691 0.0200717 -0.278776 0.0133923 0.0200734 -0.278562 -0.00986784 0.0347971 -0.0843717 -0.0195504 0.0349971 -0.0824616 -0.0381311 0.0347971 -0.0759099 -0.0466864 0.0347971 -0.0709703 -0.0445714 0.0349971 -0.0720821 -0.0460061 0.0349971 -0.0711751 -0.0487669 0.0349971 -0.069313 -0.0679853 0.0349971 -0.0506046 -0.0681457 0.0347971 -0.050724 -0.0617958 0.0347971 -0.0582917 -0.0627698 0.0349971 -0.0569445 -0.0552116 0.0349971 -0.0642984 -0.0685225 0.0349971 -0.0498748 -0.0778239 0.0349971 -0.033563 -0.0847547 0.0349971 4.83455e-06 -0.084811 0.0347971 -0.00493457 -0.0848109 0.0347971 0.00494424 -0.081194 0.0349971 0.0243114 -0.0681444 0.0347971 0.0507332 -0.0645501 0.0349971 0.054926 -0.0692986 0.0349971 0.0487984 -0.0710321 0.0349971 0.0462386 -0.073573 0.0347971 0.0424797 -0.0733998 0.0349971 0.0423797 -0.0780067 0.0347971 0.0336517 -0.0466845 0.0347971 0.070979 -0.0546086 0.0347971 0.0650799 -0.0617943 0.0347971 0.0583008 -0.0295141 0.0349971 0.0794503 -0.0443902 0.0349971 0.0722013 -0.0465746 0.0349971 0.0708119 -0.0467115 0.0349971 0.0707218 -0.0289899 0.0349971 0.0796431 -0.0114078 0.0349971 0.0839831 0.00983529 0.0349971 0.0841806 0.00985851 0.0347971 0.0843792 0.0114006 0.0349971 0.0839828 0.0179942 0.0349971 0.0828204 0.0195872 0.0347971 0.0826637 0.054601 0.0347971 0.0650785 0.0496255 0.0349971 0.0687017 0.0381218 0.0347971 0.0759174 0.0465671 0.0349971 0.0708107 0.0692905 0.0349971 0.0487966 0.071024 0.0349971 0.0462368 0.0688749 0.0349971 0.0493816 0.0629934 0.0349971 0.0566942 0.061641 0.0349971 0.0581619 0.0735647 0.0347971 0.0424778 0.0813769 0.0347971 0.0243666 0.0836549 0.0347971 0.0147541 0.0848017 0.0347971 0.00494207 0.084602 0.0349971 0.00493044 0.0694286 0.0349971 -0.0485924 0.0836546 0.0347971 -0.0147487 0.0834576 0.0349971 -0.014714 0.0778137 0.0349971 -0.033565 0.0774954 0.0349971 -0.0342936 0.0735637 0.0347971 -0.0424722 0.0545993 0.0347971 -0.0650724 0.061785 0.0347971 -0.0582933 0.0679746 0.0349971 -0.0506063 0.0685119 0.0349971 -0.0498766 -5.75174e-06 0.0349971 -0.0847462 0.0195851 0.0347971 -0.0826567 0.0290489 0.0347971 -0.0798235 -0.0399954 0.00899706 -0.0866268 -0.0400396 0.0118971 -0.0868706 -0.0398568 0.0118971 -0.0852741 -0.0399171 0.0118971 -0.0860836 -0.0398713 0.0118971 -0.0844421 -0.0398713 0.00899706 -0.084442 -0.0399049 0.0118971 -0.0840614 -0.0399049 0.00899706 -0.0840614 -0.0398908 0.0118971 -0.0841986 0.000544641 0.0189971 -0.0540852 -0.00100532 0.0189971 -0.0514005 0.00209468 0.0189971 -0.0514006 0.00167937 0.0189971 -0.0498506 0.00054471 0.0189971 -0.0487159 -0.0488061 0.0194971 -0.281426 0.00360401 0.000497063 -0.281427 0.0118705 0.000424531 -0.281393 0.0118705 0.0194971 -0.281393 0.0119658 0.000386411 -0.281344 0.0120272 0.0194971 -0.281296 0.0120272 0.000361874 -0.281296 0.0121378 0.0194971 -0.281148 0.0121378 0.000317625 -0.281148 0.0116892 0.000497063 -0.281427 0.0118609 0.000268707 -0.281363 0.0117657 0.000305721 -0.281389 0.0119176 0.000325381 -0.281363 0.0121025 8.4931e-05 -0.281021 0.01199 9.99011e-05 -0.281182 0.0120864 0.000196245 -0.281182 0.0117999 0.000220434 -0.281344 0.0118306 0.00014351 -0.281281 0.00348429 0.000197758 -0.281327 0.0118687 4.84671e-05 -0.281148 0.00342125 4.01469e-05 -0.28113 0.0118745 3.50983e-05 -0.281118 0.0119121 -2.93696e-06 -0.280927 0.00360401 0.00949706 -0.281427 -0.0487496 0.00934791 -0.281404 -0.0486306 0.00924706 -0.281359 -0.0478325 0.00906645 -0.28118 0.00314421 0.000147063 -0.280927 0.00312685 0.000182258 -0.280927 0.0031471 0.000314297 -0.28113 0.00323088 0.00034781 -0.28126 0.00317961 0.000218652 -0.281158 0.0033047 0.000377341 -0.281327 0.00346004 0.000403814 -0.281404 0.00334155 0.00032658 -0.281346 0.00338518 0.000278233 -0.281352 0.00324164 0.000134688 -0.281168 0.00312708 0.000182417 -0.280943 0.00319188 8.4931e-05 -0.280927 0.00351076 0.000353094 -0.281404 0.00348503 0.000378083 -0.281406 0.00343353 0.000234601 -0.281346 0.0031921 8.51502e-05 -0.280944 0.00328937 2.01273e-05 -0.280943 0.00353687 0.000329208 -0.281398 0.0033256 7.26614e-05 -0.281158 0.00340408 -2.7613e-06 -0.28094 0.00310401 0.000297063 -0.280927 0.00314743 0.000147063 -0.280873 0.00319478 8.4931e-05 -0.280878 0.00340401 -2.93696e-06 -0.280927 0.00340542 -2.93696e-06 -0.280903 0.00328921 1.98992e-05 -0.280927 0.00325647 3.72554e-05 -0.280886 0.00325401 3.72554e-05 -0.280927 0.00310752 0.000297063 -0.280868 0.00310752 0.00899706 -0.280868 0.00310419 0.000297133 -0.28094 0.00312691 0.00901996 -0.281077 0.003171 0.00906405 -0.281177 0.00323387 0.00912693 -0.281263 0.00335401 0.00924706 -0.28136 0.00343615 0.000429921 -0.281398 0.0355056 0.0189971 0.00253045 0.0326312 0.0189971 0.0153048 0.0484984 0.0189971 0.0257615 0.0328823 0.0189971 0.0136348 0.051607 0.0189971 -0.0183826 0.0511253 0.00142542 0.0213466 0.0517148 0.00207574 0.0221211 0.0521087 0.00304901 0.0226385 0.052247 0.00419706 0.0228202 0.0498435 0.00142542 0.0226936 0.0484472 0.00304901 0.025033 0.0484656 0.00142542 0.0234095 0.0484786 0.00119706 0.0222615 0.0492441 0.00142542 0.023224 0.0484546 0.00207574 0.0243827 0.0511825 0.00304901 0.0236118 0.0499927 0.00304901 0.0246647 0.0496929 0.00207574 0.0240876 0.0506461 0.00207574 0.023244 0.0551899 0.00119706 -0.00975164 0.0474286 0.00119706 -0.00844326 0.0551952 0.00119706 0.00972881 0.0526986 0.00119706 0.0190817 0.0504299 0.00119706 0.0204331 0.0523912 0.00119706 0.0193843 0.0392345 0.00119706 7.9672e-05 0.0487148 0.00119706 0.0222053 0.0488966 0.00119706 0.0220443 0.0482437 0.00119706 0.0221999 0.0356978 0.00119706 0.0152497 0.053858 0.00119706 -0.0155017 0.0531246 0.00119706 -0.0157947 0.0532934 0.00304901 0.022005 0.0532369 0.00269706 0.0218408 0.0544018 0.00269706 0.0211194 0.0530817 0.00207574 0.0213901 0.0528795 0.00159899 0.0208026 0.0527649 0.00142542 0.0204698 0.0536315 0.00159899 0.0203368 0.0525792 0.00119706 0.0192678 0.0546837 0.00419706 0.0214058 0.0533677 0.00419706 0.0222209 0.0511924 0.00207574 -0.0168114 0.0517103 0.00159899 -0.0164682 0.050795 0.00269706 -0.0170747 0.051607 0.00419706 -0.0183826 0.0531147 0.00419706 -0.0188535 0.0545268 0.00269706 -0.0182404 0.0559727 0.00419706 -0.0177118 0.0518103 0.00269706 -0.0180359 0.0523658 0.00159899 -0.0170886 0.0531449 0.00269706 -0.0184527 0.0532273 0.00159899 -0.0173577 0.0541195 0.00159899 -0.0172207 0.0556747 0.00269706 -0.0174421 0.0563547 0.00269706 -0.0162204 0.0552994 0.00159899 -0.0159167 0.0533399 0.00119706 -0.015862 0.053563 0.00119706 -0.0158277 0.0548605 0.00159899 -0.0167053 0.0537482 0.00119706 -0.0156989 0.0331912 0.00419706 0.0168979 0.033527 0.00269706 0.0166771 0.0328823 0.00419706 0.0136348 0.0330313 0.00269706 0.0152669 0.0344445 0.00159899 0.0160738 0.0341245 0.00159899 0.0151634 0.0358751 0.00119706 0.0154133 0.034268 0.00159899 0.0142092 0.0356178 0.00119706 0.0150221 0.0468006 0.00419706 0.02483 0.047866 0.0184971 0.0252065 0.0484447 0.0184971 0.0252613 0.0484447 0.00419706 0.0252613 0.0492806 0.0184971 0.0251698 0.0513708 0.0184971 0.0237409 0.0513708 0.00419706 0.0237409 0.050098 0.0184971 0.0248673 0.050098 0.00419706 0.0248673 0.034432 0.00419706 0.0180434 0.0469105 0.00304901 0.0246298 0.0346253 0.00269706 0.017691 0.046994 0.00269706 0.0244776 0.0351535 0.00159899 0.0167284 0.0476915 0.00142542 0.0232064 0.0475222 0.00159899 0.023515 0.0472233 0.00207574 0.0240597 0.0365576 0.00419706 -0.00127484 0.0355056 0.00419706 0.00253045 0.0359065 0.00269706 0.00255898 0.0369163 0.00269706 -0.00109337 0.0395699 0.00207574 -0.00370712 0.0399725 0.00159899 -0.00323388 0.0370018 0.00159899 0.00263692 0.037896 0.00159899 -0.000597584 0.038498 0.00119706 0.00274338 0.0529607 0.00119706 -0.0156396 0.0465697 0.00142542 -0.00920504 0.0520037 0.00142542 -0.0162737 0.0409445 0.00119706 -0.0020914 0.0458416 0.00207574 -0.00985085 0.0506503 0.00304901 -0.0171706 0.0453551 0.00304901 -0.0102824 0.0451842 0.00419706 -0.0104339 0.039261 0.00269706 -0.00407024 0.0390005 0.00419706 -0.00437637 0.0375613 0.00119706 0.00887814 0.0361015 0.00159899 0.00853328 0.0356537 0.00119706 0.0147835 0.0332536 0.00269706 0.0137887 0.0350329 0.00269706 0.00828082 0.0346417 0.00419706 0.00818842 0.0559097 0.00119706 -0.00389339 0.0559684 0.00119706 0.00293953 0.054109 0.00159899 0.0195922 0.0577483 0.00269706 -0.0102038 0.056667 0.00159899 -0.0100127 0.0574061 0.00159899 -0.00399769 0.0585629 0.00269706 0.00307561 0.0574663 0.00159899 0.00301809 0.0566725 0.00159899 0.00998907 0.0551416 0.00269706 0.019966 0.0581441 0.00419706 -0.0102738 0.0585015 0.00269706 -0.00407404 0.0589643 0.00419706 0.00309666 0.0581497 0.00419706 0.0102493 0.0577539 0.00269706 0.0101796 0.0555195 0.00419706 0.0201028 0.034432 0.0189971 0.0180434 0.0471567 0.0186486 0.0250254 0.0504599 0.00419706 -0.0172967 0.0451842 0.0189971 -0.0104339 0.0390005 0.0189971 -0.00437637 0.0365576 0.0189971 -0.00127484 0.0326312 0.00419706 0.0153048 0.0331912 0.0189971 0.0168979 0.0555195 0.0184971 0.0201028 0.0553754 0.0186488 0.0204966 0.0549875 0.0189529 0.0215166 0.0549304 0.0189757 0.0216618 0.0548083 0.0189971 0.0219684 0.0567409 0.00419706 -0.0163316 0.0567409 0.0189971 -0.0163316 0.0589024 0.00419706 -0.00410198 0.0589024 0.0189971 -0.00410198 0.0581497 0.0189971 0.0102493 0.0559727 0.0189971 -0.0177118 0.0546759 0.00419706 -0.0186136 0.0546759 0.0189971 -0.0186136 0.0531147 0.0189971 -0.0188535 0.0504599 0.0189971 -0.0172967 0.050565 0.0184971 0.0245759 0.0513963 0.0186701 0.0237584 0.0514261 0.0187471 0.0237788 0.050652 0.0188506 0.0246937 0.0507593 0.0189662 0.0248388 0.051577 0.0189301 0.0238823 0.0517832 0.0189971 0.0240237 0.0480842 0.0189528 0.0255346 0.0468006 0.0184971 0.02483 0.0476066 0.0188205 0.0252723 0.0478487 0.0188961 0.0254052 0.0492876 0.0186701 0.0251999 0.0478605 0.0186701 0.0252369 0.0493943 0.0189971 0.0256567 0.049355 0.0189662 0.0254881 0.0508622 0.0189971 0.024978 0.0493139 0.0188506 0.0253124 0.0505834 0.0186701 0.0246008 0.0533778 0.0186701 0.0222501 0.052247 0.0184971 0.0228202 0.0522875 0.0187471 0.0228735 0.0533895 0.0187471 0.0222842 0.0534154 0.0188506 0.0223594 0.0534491 0.0189301 0.0224573 0.0534741 0.0189662 0.02253 0.0523984 0.0189301 0.0230192 0.0514916 0.0188506 0.0238237 0.0525498 0.0189971 0.0232181 0.0551894 0.0188208 0.0209924 0.0546904 0.0184971 0.0213992 0.0535305 0.0189971 0.0226937 0.0547934 0.0188506 0.0215033 0.0533677 0.0184971 0.0222209 0.0547121 0.0186701 0.0214212 -0.0529702 0.0189971 0.0162197 -0.0204206 0.0189971 0.0291679 -0.0190193 0.0189971 0.0312403 -0.0335037 0.0189971 0.0126469 -0.0554908 0.0189971 0.0195431 -0.0552664 0.0189971 0.0208134 -0.0328979 0.0189971 0.0136197 -0.01898 0.0189971 0.0326374 -0.0193594 0.0189971 0.0337188 -0.031096 0.0189971 0.049942 -0.0239929 0.00390183 0.0334714 -0.024103 0.00391941 0.0333621 -0.0239065 0.00395028 0.0336086 -0.0239906 0.00413804 0.0336763 -0.0311206 0.0147196 0.047922 -0.0351468 0.0135522 0.0402435 -0.0310694 0.01465 0.0477543 -0.0314222 0.0147759 0.0478349 -0.0385038 0.0152081 0.0422704 -0.0406153 0.0136083 0.0331691 -0.0533895 0.0159616 0.0196183 -0.053431 0.0160252 0.0200678 -0.0532726 0.015934 0.0197363 -0.0398976 0.0108822 0.0228292 -0.0350998 0.00705153 0.020541 -0.0449031 0.0136332 0.0253431 -0.0446385 0.0155578 0.0356618 -0.0306794 0.010786 0.0371997 -0.0532207 0.015885 0.0194521 -0.0358719 0.0108497 0.030374 -0.0260552 0.00922599 0.0386615 -0.0270003 0.00759924 0.0346657 -0.0357637 0.00769125 0.020767 -0.0319517 0.00765952 0.0280581 -0.0378768 0.0077401 0.0150395 -0.0375749 0.00756595 0.0153509 -0.0289206 0.0153684 0.0488561 -0.029323 0.0154839 0.0491319 -0.0322614 0.0166873 0.0493198 -0.0322875 0.0175311 0.0494479 -0.030728 0.0174943 0.0499993 -0.0311936 0.0158151 0.0493793 -0.0310687 0.0166369 0.0498171 -0.0309852 0.0170712 0.049932 -0.02945 0.0174379 0.0498931 -0.0308898 0.0146324 0.0478548 -0.0301115 0.0148586 0.0485682 -0.0296181 0.0146641 0.0482079 -0.028572 0.0152436 0.0484983 -0.0281457 0.0163012 0.0489764 -0.0292011 0.0164634 0.0496516 -0.0302311 0.0156787 0.0494295 -0.0298052 0.0165322 0.0498259 -0.0277194 0.0173163 0.0487982 -0.0286439 0.0163861 0.0493669 -0.0296155 0.0169887 0.0498987 -0.0306583 0.0150337 0.0487449 -0.0313486 0.0147686 0.0478759 -0.0372618 0.00926589 0.0118075 -0.0363159 0.00687909 0.014767 -0.0346168 0.0070843 0.0140824 -0.0362681 0.00715278 0.0134053 -0.0374862 0.00827681 0.0125123 -0.0366573 0.00850309 0.0119667 -0.036545 0.0101647 0.0114828 -0.0367526 0.00913735 0.0116904 -0.0348009 0.00996821 0.0117213 -0.0338488 0.00987531 0.0123055 -0.0339702 0.00921707 0.0122983 -0.0328979 0.0098087 0.0136197 -0.0330039 0.00908448 0.0135974 -0.0359672 0.0100967 0.0114623 -0.0357721 0.0095243 0.0115238 -0.0362066 0.00899958 0.0116586 -0.0361223 0.00831494 0.0119991 -0.0349379 0.00790579 0.012488 -0.0337886 0.0084 0.012877 -0.0366292 0.00787824 0.0124565 -0.0350599 0.00721029 0.0133651 -0.033863 0.00760976 0.0138184 -0.0334281 0.00913312 0.0128678 -0.0343809 0.00853767 0.0123019 -0.035008 0.00869504 0.0119317 -0.0345657 0.00931705 0.0118982 -0.0356204 0.00885092 0.0117304 -0.0351708 0.00942076 0.0116488 -0.0353122 0.0100229 0.0115557 -0.0353843 0.0100309 0.0115391 -0.0383017 0.00809477 0.0139283 -0.0370298 0.00715394 0.0150876 -0.0368726 0.00712718 0.0140202 -0.0374476 0.00748401 0.0137471 -0.0370859 0.00759407 0.0130627 -0.0343456 0.00772108 0.0130394 -0.0355944 0.0074189 0.0128686 -0.0370822 0.00808779 0.0124434 -0.0371428 0.00867385 0.0120288 -0.0378492 0.0084487 0.0126437 -0.0377516 0.00798273 0.0131058 -0.0381756 0.00860593 0.0128278 -0.0379206 0.00781138 0.0137567 -0.0376855 0.00761342 0.0151717 -0.0531133 0.0158426 0.0194055 -0.0534621 0.0160117 0.019847 -0.0550943 0.018793 0.0179615 -0.0551153 0.0183333 0.0180835 -0.0550653 0.0178665 0.0182445 -0.054202 0.0187319 0.0168668 -0.0531374 0.0181429 0.0163216 -0.054301 0.0182478 0.017004 -0.0543422 0.0177548 0.0172169 -0.0543158 0.0172779 0.0175042 -0.0542178 0.0168443 0.0178562 -0.055352 0.0179374 0.0194803 -0.0549272 0.0170863 0.01962 -0.054163 0.0164501 0.0203516 -0.0547361 0.0169932 0.0186687 -0.0538276 0.016197 0.0186809 -0.0541386 0.0163305 0.0191719 -0.0220757 0.00441999 0.0348677 -0.0213746 0.00461898 0.0349041 -0.023463 0.0117206 0.0407039 -0.0210517 0.00985033 0.0368031 -0.0196683 0.00558728 0.0341455 -0.0199477 0.00756141 0.0347911 -0.0193594 0.00592792 0.0337188 -0.0238803 0.00435422 0.0339927 -0.0250719 0.00750975 0.0366339 -0.0233798 0.00429403 0.0343727 -0.0227757 0.00430984 0.0346764 -0.0227025 0.00431705 0.034704 -0.0220886 0.00441717 0.0348656 -0.0215819 0.00881668 0.0372464 -0.0226704 0.00797918 0.0374838 -0.0244307 0.0107947 0.0408278 -0.0233176 0.00768958 0.0374173 -0.0239635 0.00751762 0.0372342 -0.0270543 0.0106323 0.0406508 -0.0245593 0.00746319 0.0369616 -0.0307177 0.0145234 0.0476735 -0.0256326 0.0102545 0.0405505 -0.0277553 0.0161642 0.0484958 -0.0229558 0.0127117 0.0402733 -0.0273056 0.0172711 0.0482009 -0.0533561 0.0160354 0.0183208 -0.0453189 0.0125893 0.0159731 -0.0453275 0.013191 0.0149119 -0.0534231 0.0166618 0.0172737 -0.0450922 0.0141095 0.0141443 -0.053376 0.0171044 0.0168577 -0.0532756 0.0176198 0.0165297 -0.0415695 0.0110975 0.0138162 -0.0414085 0.0103481 0.0159852 -0.0450952 0.0124023 0.0170613 -0.037111 0.010234 0.0115982 -0.0407623 0.0129166 0.0126622 -0.0412519 0.0119694 0.0130251 -0.0377347 0.0093863 0.0120003 -0.041615 0.0105261 0.0148925 -0.0381199 0.00793591 0.0150287 -0.0244567 0.00640849 0.0260126 -0.0212067 0.00388436 0.0291991 -0.0218531 0.00317913 0.0296081 -0.0225808 0.00271952 0.0303123 -0.0254244 0.0049037 0.0264709 -0.0275031 0.00440912 0.0285148 -0.0237359 0.00288067 0.0320799 -0.0232481 0.00262557 0.0311969 -0.022931 0.00262439 0.0307431 -0.028234 0.00532362 0.0296546 -0.027957 0.00481095 0.0291583 -0.0315446 0.00584952 0.0249296 -0.0302535 0.00539915 0.0237782 -0.0268746 0.00424183 0.0277742 -0.0261403 0.00440662 0.0270484 -0.0287422 0.00611893 0.0227262 -0.0248449 0.00562234 0.0261258 -0.0319413 0.00631749 0.0253615 -0.0346167 0.00661709 0.0201879 -0.0309744 0.00550678 0.0243869 -0.0339628 0.00631562 0.0197535 -0.0316061 0.00700129 0.0184563 -0.0294674 0.00560597 0.0231912 -0.0281853 0.00683506 0.0224455 -0.0278385 0.00761454 0.0223498 -0.0307319 0.00848493 0.0181614 -0.0354776 0.00683554 0.014416 -0.0331741 0.00624737 0.0192743 -0.032346 0.00648027 0.0188172 -0.0333153 0.00831795 0.0136563 -0.0310566 0.00771295 0.0182375 -0.0318001 0.0152184 0.0484598 -0.038992 0.015645 0.0428389 -0.0320947 0.0158799 0.0489801 -0.0393826 0.0163109 0.0433155 -0.0496431 0.0158307 0.0282136 -0.0452249 0.0159898 0.0361525 -0.0503117 0.0162586 0.0286085 -0.0457013 0.0166588 0.0365661 -0.0512015 0.0177654 0.0291641 -0.0547678 0.0171229 0.0205923 -0.0508604 0.0169299 0.0289429 -0.0396152 0.01713 0.0436284 -0.0459928 0.0174872 0.036839 -0.0513032 0.0186419 0.0292503 -0.0551478 0.0179636 0.0207516 -0.0201259 0.00536337 0.0293987 -0.0204206 0.00538071 0.0291679 -0.023853 0.00410401 0.0337996 -0.0211752 0.00265551 0.0327543 -0.0220215 0.00252327 0.0306951 -0.0215164 0.00347072 0.0341308 -0.0205845 0.00363053 0.0338813 -0.0196948 0.00535738 0.0298487 -0.0192662 0.00467285 0.0307523 -0.0197955 0.00399251 0.0334311 -0.0192554 0.0044883 0.0328614 -0.0197254 0.00363332 0.0327815 -0.0201423 0.00371512 0.0300744 -0.0207262 0.00466163 0.0290798 -0.0206675 0.00375983 0.0295657 -0.0190475 0.00575065 0.0329425 -0.0201761 0.00519646 0.0345509 -0.0206984 0.00490107 0.0347814 -0.0209356 0.00420376 0.0345294 -0.0201884 0.00451483 0.0342601 -0.0192157 0.00532462 0.0333366 -0.0189278 0.00558118 0.0320351 -0.0190224 0.00485383 0.0315867 -0.0190532 0.00544926 0.0311066 -0.0192327 0.00539837 0.0306065 -0.0223099 0.00238147 0.0319964 -0.0230766 0.00270274 0.0326591 -0.0240089 0.00335893 0.0328187 -0.0233785 0.00337103 0.033538 -0.0218827 0.00236206 0.0316237 -0.0216649 0.00265467 0.0330087 -0.0232439 0.00373532 0.0340019 -0.0214853 0.0030966 0.0337061 -0.0226049 0.00290226 0.0333719 -0.0209963 0.00254435 0.031874 -0.0214538 0.00245235 0.0312472 -0.0205187 0.00323018 0.0333306 -0.0207051 0.00275113 0.0324625 -0.0199198 0.00320712 0.0318265 -0.0202179 0.00302389 0.0312086 -0.0206839 0.00294247 0.0305641 -0.0224432 0.00352174 0.0341575 -0.0217641 0.00401567 0.034606 -0.0196031 0.00490626 0.03384 -0.018986 0.00502635 0.0322707 -0.0192235 0.00421619 0.0321652 -0.0194389 0.00390451 0.0312273 -0.01972 0.00377312 0.030656 -0.0198625 0.00456922 0.0298115 -0.0212669 0.00300526 0.030001 -0.0552664 0.0188462 0.0208134 -0.0500241 0.0189971 0.0313877 -0.046073 0.0183554 0.0369444 -0.0322875 0.0189971 0.0494479 -0.0414757 0.0189971 0.0420401 -0.0396701 0.0179875 0.043748 -0.0414755 0.0180935 0.0420403 -0.037111 0.0189971 0.0115982 -0.0529702 0.0186606 0.0162197 -0.0446919 0.0151071 0.0138073 -0.0551216 0.0189971 0.018015 -0.0541209 0.0189971 0.0168026 -0.0544198 0.0187457 0.0170598 -0.0553146 0.018812 0.0184829 -0.0554836 0.018834 0.0193536 -0.0554273 0.0188451 0.0202417 -0.019602 0.0189971 0.02997 -0.0306052 0.00921263 0.0181963 -0.0277698 0.0189971 0.022285 -0.0276807 0.00834663 0.0223957 -0.0242485 0.00714262 0.0260728 -0.0337103 0.0098632 0.0124312 -0.0346177 0.0189971 0.0118028 -0.0359731 0.0189971 0.011462 -0.0295242 0.0189971 0.0499125 -0.029068 0.0174165 0.0497644 -0.0281989 0.0173575 0.0492593 -0.0281238 0.0189971 0.049198 -0.0273056 0.0189971 0.0482009 0.0499041 0.0189971 0.0295233 0.0337104 0.0189971 0.0193585 0.0481925 0.0189971 0.0273047 0.0352493 0.00119706 0.0435785 0.0361106 0.00208576 0.045528 0.0179591 0.00306863 0.0505173 0.0272715 0.00245526 0.0488336 0.017925 0.00208576 0.0498698 0.0271129 0.00176634 0.048168 0.0178735 0.00142814 0.0488944 0.0269116 0.00133225 0.0473237 0.0178126 0.00119706 0.0477414 0.0267074 0.00119706 0.0464571 0.0160517 0.00357989 0.0500906 0.0151439 0.00306863 0.0485191 0.015331 0.00388338 0.0493978 0.0157664 0.00208576 0.0483377 0.0163725 0.00159899 0.0481611 0.0162247 0.00208576 0.0491631 0.0169946 0.00208576 0.0497095 0.0157417 0.00306863 0.0495956 0.0167457 0.00306863 0.0503082 0.0173695 0.00142814 0.0488076 0.0169524 0.00142814 0.0485116 0.0277523 0.00728227 0.0513474 0.0265917 0.00633135 0.0509366 0.0199877 0.0091923 0.054518 0.019647 0.00901883 0.0543753 0.0273675 0.00328045 0.0492363 0.0185212 0.00615249 0.0520267 0.0193059 0.00884387 0.0542327 0.0304784 0.00638134 0.0499292 0.0371362 0.00419706 0.0459108 0.0369977 0.00306863 0.0457395 0.0363726 0.00306863 0.0461211 0.0368834 0.00269706 0.0455983 0.0357159 0.00142814 0.0446346 0.0361928 0.00159899 0.0447446 0.0268898 0.00119706 0.0276921 0.0145647 0.00119706 0.0358122 0.0147587 0.00119706 0.0356689 0.0322673 0.00119706 0.0219886 0.0316171 0.00119706 0.0221402 0.0304331 0.00419706 0.0193108 0.0294888 0.00269706 0.0206502 0.0306161 0.00269706 0.0196686 0.0320718 0.00269706 0.0193292 0.0320777 0.00419706 0.0189273 0.0303883 0.00159899 0.0212799 0.0335171 0.00269706 0.0197108 0.0311161 0.00159899 0.0206463 0.0317991 0.00119706 0.0219817 0.0320558 0.00159899 0.0204271 0.032034 0.00119706 0.021927 0.011916 0.00269706 0.035504 0.0136113 0.00419706 0.032897 0.013765 0.00269706 0.0332684 0.0125626 0.00269706 0.0341564 0.0144699 0.00119706 0.0362708 0.0129913 0.00159899 0.0357262 0.0134088 0.00159899 0.0348562 0.0144603 0.00119706 0.0360297 0.0171879 0.0104652 0.0544379 0.0197909 0.00919944 0.054548 0.0196187 0.00915472 0.0545202 0.0194183 0.00902256 0.0544039 0.0190353 0.00951699 0.0548328 0.0182853 0.0090676 0.0543026 0.0178303 0.00982809 0.0546323 0.0173055 0.00956253 0.0540847 0.0165747 0.0102531 0.0535954 0.0185404 0.0100442 0.0550424 0.0180939 0.0106488 0.0550866 0.0193086 0.0107625 0.0554191 0.0177338 0.0112727 0.0549688 0.0191743 0.0113621 0.0554674 0.0202156 0.0113731 0.0554302 0.016941 0.0108014 0.0542679 0.0194548 0.010176 0.0552417 0.0158413 0.00727913 0.0511149 0.016352 0.0106096 0.0532976 0.0162113 0.0109728 0.0529693 0.0154595 0.00783591 0.0503895 0.0149324 0.00419706 0.0485808 0.0175237 0.00634776 0.052024 0.0179623 0.00322918 0.0505771 0.0169867 0.00335111 0.0504987 0.0166998 0.0034079 0.0504133 0.0165671 0.00674261 0.0517095 0.0156011 0.0037491 0.0497185 0.0115897 0.00419706 0.0371101 0.0119756 0.00269706 0.0369976 0.0153183 0.00269706 0.0484683 0.0167042 0.00142814 0.0480645 0.0130298 0.00159899 0.0366904 0.0481925 0.00419706 0.0273047 0.0474709 0.00159899 0.0286197 0.0467493 0.00119706 0.0299348 0.0329888 0.00159899 0.0206735 0.0197753 0.00269706 0.0300852 0.0203786 0.00159899 0.0310027 0.014185 0.00159899 0.0342829 0.0212027 0.00119706 0.032256 0.0222766 0.00419706 0.0277689 0.0258447 0.00159899 0.0266162 0.0291595 0.00419706 0.0204197 0.0250796 0.00269706 0.0258285 0.039896 0.00119706 0.0393679 0.0365898 0.00208576 0.0452354 0.0409639 0.00159899 0.0404213 0.0491029 0.00269706 0.0320668 0.0417456 0.00269706 0.0411925 0.0293044 0.00777252 0.0510786 0.0335147 0.0068982 0.0486181 0.0368028 0.00375309 0.0461063 0.0250088 0.00908794 0.0532593 0.0208872 0.00900528 0.0542123 0.0204573 0.0101742 0.0551207 0.0208049 0.01136 0.0552655 0.0296723 0.0086936 0.0510545 0.0333097 0.00608874 0.0486261 0.0328526 0.00541904 0.0485496 0.0364095 0.00332622 0.0462045 0.0479991 0.00269706 0.027657 0.0495142 0.00269706 0.0296208 0.0499041 0.00419706 0.0295233 0.0499604 0.00419706 0.0309534 0.0494395 0.00419706 0.0322866 0.049564 0.00269706 0.0308868 0.0489618 0.00269706 0.0284807 0.0480923 0.00159899 0.0291514 0.048449 0.00159899 0.0298875 0.0484811 0.00159899 0.0307047 0.0469047 0.00119706 0.0300677 0.0469939 0.00119706 0.0302517 0.0470019 0.00119706 0.030456 0.0481835 0.00159899 0.0314665 0.0469275 0.00119706 0.0306465 0.0494395 0.0189971 0.0322866 0.0499604 0.0189971 0.0309534 0.04928 0.00419706 0.0282352 0.04928 0.0189971 0.0282352 0.0313793 0.0189971 0.0500232 0.0358363 0.00536872 0.0469327 0.0420317 0.00419706 0.0414748 0.0420317 0.0189971 0.0414748 0.01675 0.0111333 0.0540611 0.0185595 0.0113356 0.0553405 0.0167942 0.0189971 0.0541199 0.0170797 0.0111917 0.0544485 0.0162113 0.0189971 0.0529693 0.0180066 0.0189971 0.0551207 0.0195347 0.0189971 0.0554899 0.0208049 0.0189971 0.0552655 0.0291595 0.0189971 0.0204197 0.0247996 0.00419706 0.0255402 0.0222766 0.0189971 0.0277689 0.0195544 0.00419706 0.0297494 0.0122529 0.00419706 0.0339002 0.0136113 0.0189971 0.032897 0.0122529 0.0189971 0.0339002 0.0115224 0.00419706 0.0354227 0.0115224 0.0189971 0.0354227 0.0115897 0.0189971 0.0371101 0.0337104 0.00419706 0.0193585 0.0320777 0.0189971 0.0189273 0.0304331 0.0189971 0.0193108 -0.0590533 0.0189971 0.000403466 -0.0517141 0.0189971 -0.0262339 -0.0537952 0.0189971 -0.0243576 -0.0355376 0.0189971 0.00864598 -0.0364977 0.0189971 0.00966161 -0.0350631 0.0189971 0.00618966 -0.0577943 0.0189971 0.0121386 -0.0561689 0.0189971 0.0144211 -0.0382951 0.00449498 -0.0149212 -0.0383982 0.00468601 -0.0149355 -0.0382825 0.00448808 -0.0147728 -0.0393216 0.00602322 -0.0158716 -0.0395514 0.0065272 -0.0104532 -0.0400138 0.00704295 -0.00718554 -0.0436999 0.00987326 -0.00671735 -0.0466888 0.0113647 -0.0206126 -0.0514789 0.0133272 -0.0233795 -0.0552122 0.0148856 -0.0141455 -0.0568501 0.0158541 -0.00496248 -0.04097 0.00775488 -0.0170283 -0.0415254 0.00831971 -0.0107544 -0.0439625 0.00991807 -0.0189619 -0.0463146 0.0112642 -0.0118972 -0.0460757 0.0112772 -0.00489481 -0.0556065 0.0154331 -0.00333953 -0.0458245 0.0114033 0.00124122 -0.0400205 0.00806306 0.00742435 -0.0472545 0.0125941 0.00971742 -0.0449645 0.0114095 0.00902813 -0.040537 0.00787788 -0.000118777 -0.0402257 0.00824739 0.00757457 -0.040077 0.00809153 0.00728496 -0.0555384 0.0160384 0.0118966 -0.0552726 0.015543 0.00382468 -0.0556896 0.0160971 0.0119814 -0.0552275 0.0159415 0.0120893 -0.0556215 0.015517 -0.000450437 -0.0460228 0.0112195 -0.00641532 -0.0498898 0.0130921 -0.00590303 -0.0427716 0.00928381 -0.00541736 -0.0460995 0.0113713 -0.00245658 -0.0558486 0.0161348 0.0117029 -0.0404116 0.00752229 -0.00360953 -0.0402077 0.00724227 -0.00580881 -0.0550923 0.0178501 0.0146705 -0.0562589 0.017967 0.0141855 -0.0568869 0.0171927 0.0129251 -0.0571628 0.0180453 0.0132896 -0.0571948 0.0189433 0.0134846 -0.0556975 0.0179126 0.0144852 -0.0553351 0.0169328 0.0140506 -0.0554483 0.016287 0.013126 -0.0554768 0.0160299 0.0120949 -0.0558304 0.0161327 0.0117686 -0.054846 0.016838 0.014127 -0.0543435 0.0167352 0.0141062 -0.0538355 0.0176623 0.0146618 -0.054457 0.0177806 0.0147361 -0.0559818 0.0164281 0.0128723 -0.0562156 0.0170896 0.0136354 -0.057078 0.0189389 0.0136356 -0.0561201 0.0188985 0.0144499 -0.0514164 0.0135338 -0.0245238 -0.0530069 0.0153909 -0.0252513 -0.0534171 0.0163474 -0.0249995 -0.0534929 0.0163513 -0.0248934 -0.0518272 0.0157699 -0.0261507 -0.05251 0.0153358 -0.0256602 -0.0520664 0.0143555 -0.0253069 -0.0513965 0.0132972 -0.0233424 -0.0500462 0.0139306 -0.0253834 -0.0506795 0.0151263 -0.0262158 -0.0493943 0.0149106 -0.025922 -0.0491101 0.015549 -0.0260169 -0.0520709 0.0135417 -0.0231063 -0.0524767 0.0138525 -0.0240197 -0.0519322 0.0134912 -0.023292 -0.0517169 0.0134134 -0.0233952 -0.0528562 0.0145139 -0.0247209 -0.0534155 0.0154359 -0.0247524 -0.0533788 0.0146178 -0.0238778 -0.0537233 0.0154698 -0.0241757 -0.0519997 0.0137102 -0.0243767 -0.051094 0.014155 -0.0255547 -0.0520288 0.0147917 -0.0256792 -0.0519465 0.0152726 -0.025963 -0.0508917 0.0146116 -0.0259441 -0.0504713 0.015662 -0.0263642 -0.0505323 0.0161983 -0.0264129 -0.0383204 0.00964604 0.0101264 -0.0451586 0.0153096 0.0123809 -0.0456809 0.0142825 0.0123016 -0.0418438 0.0122026 0.0111802 -0.0463003 0.0133418 0.0117449 -0.0391185 0.00886369 0.00961749 -0.0425483 0.0113006 0.0106375 -0.0431675 0.0107352 0.00968805 -0.0468667 0.0127462 0.0107946 -0.0548334 0.0161296 0.0132009 -0.0390569 0.00613631 -0.0173245 -0.0383636 0.00468278 -0.0159062 -0.0393753 0.00617168 -0.0166669 -0.0362872 0.00517508 -0.0181592 -0.0344413 0.00629616 -0.0180359 -0.040965 0.0124839 -0.0216154 -0.0403052 0.00752153 -0.0181782 -0.0380234 0.00463016 -0.01669 -0.0387612 0.00835346 -0.0196131 -0.0382184 0.00885032 -0.0197786 -0.0395546 0.00630895 -0.0160403 -0.04064 0.00753102 -0.0175522 -0.0437046 0.0098329 -0.0195252 -0.0393263 0.00793952 -0.0192693 -0.0398576 0.00765502 -0.0187726 -0.0496839 0.0144112 -0.0257252 -0.0415968 0.0113922 -0.0216593 -0.0424881 0.01039 -0.0211322 -0.0429472 0.0100553 -0.020662 -0.0433621 0.00987059 -0.0201081 -0.0507578 0.0133572 -0.0244667 -0.050788 0.0133435 -0.0244207 -0.0342265 0.00737023 -0.0101442 -0.0355516 0.00753397 -0.00643082 -0.0394419 0.00661664 -0.00699589 -0.0383073 0.00455299 -0.0146178 -0.038718 0.00569073 -0.0108433 -0.0379391 0.00413122 -0.0140895 -0.0391087 0.00597502 -0.011661 -0.0373266 0.00379449 -0.0135357 -0.0364704 0.00364542 -0.0130481 -0.0373006 0.00633965 -0.00653689 -0.036027 0.00700995 -0.00642191 -0.0346239 0.00662993 -0.0099703 -0.0330548 0.00632498 -0.0132268 -0.0331686 0.00537154 -0.013217 -0.0335762 0.00485522 -0.0129261 -0.0336936 0.00473909 -0.0128713 -0.0357908 0.00470167 -0.0114743 -0.0367725 0.00453798 -0.0117329 -0.0361752 0.00365152 -0.0129311 -0.0344842 0.00416183 -0.0126848 -0.0352818 0.00594973 -0.00989973 -0.0361541 0.0054622 -0.00997124 -0.0371129 0.00526502 -0.0101848 -0.0380035 0.00536622 -0.0104964 -0.0351954 0.00943554 -0.00537916 -0.035094 0.00847807 -0.00652262 -0.040537 0.00787537 -0.000156899 -0.038797 0.00635162 -0.00682328 -0.0386427 0.00631392 -0.00678685 -0.039928 0.00748126 -8.57615e-05 -0.0391475 0.00722391 -6.17299e-05 -0.03778 0.00625942 -0.00661272 -0.0382481 0.00719589 -5.33467e-05 -0.0367009 0.00656007 -0.00646473 -0.0373395 0.0074539 -6.54692e-05 -0.0359981 0.00868523 -0.00014452 -0.0356924 0.00944655 -0.000197104 -0.0353949 0.00777524 -0.00644673 -0.0399297 0.00793402 0.00699722 -0.0385635 0.00727809 0.00674155 -0.0374178 0.00729335 0.00653974 -0.0365563 0.00798087 -9.78193e-05 -0.0356038 0.0101669 -0.000248005 -0.0569773 0.0159365 -0.00310007 -0.0576329 0.0162775 -0.00505347 -0.058525 0.0189893 0.00789529 -0.0588179 0.0180646 0.00347412 -0.0576651 0.018075 0.012103 -0.0572608 0.0172316 0.01201 -0.0566206 0.016558 0.0118691 -0.0569502 0.0161234 0.00339885 -0.0588181 0.018675 -0.00527714 -0.0590547 0.0188753 4.50555e-06 -0.0584007 0.0172194 0.00346461 -0.0577423 0.0165453 0.0034379 -0.0586891 0.0177915 -0.00522236 -0.0570026 0.0168152 -0.0148896 -0.0566161 0.0159667 -0.014668 -0.0582809 0.0169501 -0.00514455 -0.0559835 0.0152959 -0.0144066 -0.0527941 0.0139472 -0.0235014 -0.034767 0.00401764 -0.0126736 -0.0371591 0.00347304 -0.0139739 -0.0378225 0.00383179 -0.0147925 -0.0370791 0.0032494 -0.0147771 -0.0374591 0.00384567 -0.0136362 -0.0356215 0.00364976 -0.017126 -0.0366141 0.00353834 -0.0167231 -0.0362655 0.00309929 -0.0160212 -0.0361242 0.00293816 -0.0154515 -0.0372149 0.00339155 -0.0156551 -0.033542 0.00607522 -0.0173294 -0.0341328 0.00564986 -0.0177931 -0.0339599 0.00617818 -0.0177175 -0.0349692 0.00592187 -0.0182382 -0.0356998 0.00547833 -0.0182863 -0.0355587 0.00471987 -0.0179753 -0.0343163 0.00493863 -0.0176846 -0.0337086 0.00549618 -0.0174258 -0.0347723 0.00516664 -0.0179907 -0.0345535 0.00579034 -0.0180546 -0.0352004 0.00536025 -0.0181808 -0.0328917 0.00596107 -0.0136273 -0.0328607 0.00519326 -0.0139691 -0.032731 0.00507604 -0.0150139 -0.0326283 0.00587026 -0.0148137 -0.0329142 0.00514918 -0.0161062 -0.035465 0.00376701 -0.0127396 -0.0350941 0.00329608 -0.013475 -0.0340667 0.00374223 -0.0134911 -0.0345569 0.0034786 -0.0134583 -0.0338603 0.00344163 -0.0148799 -0.0349845 0.00299461 -0.0156092 -0.0336444 0.00406766 -0.0135681 -0.0331187 0.00421726 -0.0149493 -0.0337059 0.00397096 -0.016358 -0.0346361 0.00405655 -0.0172794 -0.0360432 0.00406327 -0.0175175 -0.034625 0.0033578 -0.0163547 -0.0343552 0.00315085 -0.0148478 -0.033302 0.00443217 -0.0136803 -0.0333604 0.00435243 -0.0163001 -0.0338311 0.00466095 -0.0171784 -0.0384906 0.00481804 -0.0152541 -0.0383624 0.00468218 -0.0159103 -0.0380062 0.0040885 -0.0155702 -0.0374383 0.00371589 -0.0161638 -0.0371872 0.00422634 -0.0171859 -0.0376175 0.00468733 -0.0172519 -0.0370059 0.0048709 -0.0177956 -0.0364045 0.00438689 -0.0176997 -0.038349 0.00457924 -0.0150789 -0.0327417 0.00588387 -0.0158641 -0.0329621 0.005934 -0.0164662 -0.0332885 0.00532451 -0.0168971 -0.0351242 0.00442698 -0.0177364 -0.0363086 0.0051649 -0.0181518 -0.0361969 0.00321252 -0.0136533 -0.0360945 0.0030149 -0.0141504 -0.0360608 0.00290388 -0.0147842 -0.0349559 0.00307936 -0.0140686 -0.0349073 0.00295712 -0.0148201 -0.0351644 0.00317132 -0.0162848 -0.0341316 0.00363126 -0.0163783 -0.0334445 0.00380626 -0.0149144 -0.0350631 0.0102278 0.00618966 -0.0350232 0.0102285 0.00649314 -0.0351031 0.009524 0.00702412 -0.035328 0.0102966 0.00825572 -0.0355224 0.00966716 0.0084854 -0.0359061 0.00976226 0.00904614 -0.0368424 0.00995655 0.00982294 -0.0365023 0.0104593 0.00966481 -0.0387042 0.00924847 0.00994238 -0.0372791 0.00943675 0.00986508 -0.0377943 0.00894377 0.00976069 -0.0353676 0.00891197 0.00621407 -0.0354092 0.00877342 0.00712992 -0.03524 0.00958319 0.00780611 -0.0378861 0.0101414 0.010205 -0.0377654 0.00743722 0.00790074 -0.0389666 0.00774692 0.00831196 -0.0386145 0.00742441 0.00770052 -0.0387478 0.00731878 0.00677497 -0.0399316 0.00796339 0.00721723 -0.0382852 0.00783991 0.00872686 -0.0393929 0.00807097 0.00859568 -0.0388998 0.00822948 0.00909681 -0.038351 0.00852741 0.00949899 -0.0367819 0.00750831 0.00643232 -0.0367402 0.00755576 0.00727309 -0.0359639 0.0080784 0.00721863 -0.0369011 0.00770601 0.00802077 -0.037564 0.00812644 0.00903303 -0.0362094 0.00786291 0.00633922 -0.0355766 0.00887187 0.00795795 -0.0358999 0.00900722 0.00864671 -0.0361409 0.00821122 0.00803839 -0.0363185 0.00915449 0.00918488 -0.0364705 0.00839157 0.00869706 -0.0368844 0.00858451 0.00918864 -0.0397911 0.0083699 0.00871656 -0.0401703 0.00820046 0.00755229 -0.0537952 0.0163671 -0.0243576 -0.0571055 0.0177082 -0.0150428 -0.0575656 0.0189971 -0.0131735 -0.0589531 0.0189526 0.0034663 -0.0350514 0.0189971 0.00733565 -0.0360613 0.0104016 0.00929872 -0.0375307 0.0189971 0.0101581 -0.0350099 0.0102324 0.00679778 -0.0352174 0.0102786 0.00798534 -0.0327013 0.00589968 -0.0142402 -0.0326321 0.0189971 -0.0147436 -0.0326469 0.00587928 -0.0145762 -0.0326249 0.00586677 -0.0149675 -0.032823 0.0189971 -0.0161281 -0.0329935 0.00594147 -0.0165309 -0.03367 0.00610676 -0.0174621 -0.0335404 0.0189971 -0.0173276 -0.0328917 0.0189971 -0.0136273 -0.0340239 0.00801469 -0.0104867 -0.0349799 0.00919845 -0.00663672 -0.0353929 0.0189971 -0.00387393 -0.035447 0.00978195 -0.00334312 -0.0387159 0.0109682 -0.0203814 -0.037377 0.009855 -0.0196467 -0.0489233 0.0189971 -0.0259821 -0.0464292 0.0151572 -0.0246136 -0.0344413 0.0189971 -0.0180359 -0.0412301 0.0131887 0.0112361 -0.0375307 0.0105859 0.0101581 -0.0489233 0.0161148 -0.0259821 -0.0529229 0.0163218 -0.0255379 -0.0523336 0.0162913 -0.0259581 -0.0521711 0.0162829 -0.0260448 -0.0501492 0.0189971 -0.0263836 -0.0516812 0.0162577 -0.0262447 -0.0502784 0.0161851 -0.0263982 -0.0530557 0.0189971 -0.0254144 -0.0577943 0.0189609 0.0121386 -0.0573012 0.0189971 0.0133305 -0.0557368 0.0188811 0.014641 -0.0547795 0.0188353 0.0148952 -0.0546735 0.0189971 0.0149061 -0.0533898 0.0189971 0.0147796 -0.0540889 0.0188007 0.0149081 -0.0533898 0.0187642 0.0147796 0.00786593 0.0189971 0.0351786 0.00930001 0.0189971 0.0360703 -0.013182 0.0189971 0.0575647 -0.026392 0.0189971 0.0501483 0.00039505 0.0189971 0.0590524 -0.00118723 0.0189971 0.0368495 0.000116579 0.0189971 0.0356035 -0.00183563 0.0189971 0.0388026 -0.00157891 0.0189971 0.0404731 -0.00138594 0.0189971 0.0422382 0.0147712 0.0189971 0.0533889 0.0148977 0.0189971 0.0546726 0.00538981 0.00119706 0.0468301 0.00981673 0.00142814 0.0486787 0.000576366 0.00142814 0.0468105 0.0097131 0.00208576 0.0496499 0.000107397 0.00306863 0.0483664 -0.0116105 0.00119706 0.0399159 -0.0172569 0.00208576 0.0384458 -0.0131148 0.00304802 0.0422433 -0.0127674 0.00208576 0.0417058 -0.0164462 0.00131879 0.0374483 -0.0159126 0.00119706 0.0367919 -0.00892411 0.00394708 0.0412278 -0.00871222 0.00419706 0.0406906 -0.0106107 0.00306863 0.0425096 -0.00954291 0.00306863 0.0417738 -0.00955146 0.00208576 0.0404663 -0.00910051 0.00269706 0.0405868 -0.00892506 0.00306863 0.0406337 -0.0117291 0.00142814 0.0410643 -0.0122372 0.00142814 0.0408855 -0.0118931 0.00301129 0.0426571 -0.0118295 0.00208576 0.0420359 -0.0108439 0.00208576 0.0419046 -0.0111952 0.00142814 0.0409932 -0.0118003 0.00301729 0.0426676 -0.0100252 0.00208576 0.0413404 -0.0107517 0.00142814 0.0406876 -0.0101613 0.00159899 0.0403032 -0.00200604 0.00369493 0.0452078 -0.00200427 0.00349265 0.0458209 -0.00183417 0.00396341 0.0445145 -0.00137672 0.00306863 0.044124 -0.00184512 0.00306863 0.045333 -0.00171422 0.00306863 0.0466229 -0.000234638 0.00142814 0.0455505 -0.000324187 0.00159899 0.0448518 -0.000180267 0.00142814 0.0460862 -0.0011022 0.00208576 0.0464088 0.000111206 0.00142814 0.0465391 -0.000564155 0.00208576 0.0472447 -0.00101249 0.00306863 0.0477131 0.000294508 0.00208576 0.0477456 -0.00120257 0.00208576 0.0454197 0.00993923 0.00119706 0.0475306 0.0110477 0.00142814 0.0472076 0.00968511 0.0023906 0.0499123 0.0126598 0.00306863 0.0481009 0.0128525 0.00369092 0.0480372 0.012071 0.00306863 0.0493145 0.0109802 0.00306863 0.050108 0.0110562 0.00311721 0.050097 0.0109724 0.00311384 0.0501305 0.00964431 0.00306863 0.0502946 0.0124336 0.00269706 0.0468038 0.0115738 0.00208576 0.0488984 0.0107374 0.00208576 0.0495068 0.0113793 0.00159899 0.047111 0.0120252 0.00208576 0.0479679 0.0110693 0.00142814 0.0477675 0.0108247 0.00142814 0.0482716 0.0103716 0.00142814 0.0486012 -0.0181904 0.00269706 0.0355421 -0.0183463 0.00315629 0.038204 -0.0184451 0.00306863 0.0379378 -0.0187761 0.00342834 0.03725 -0.018834 0.00380022 0.0362365 -0.0178544 0.00208576 0.0376705 -0.0186903 0.00306863 0.036685 -0.0180424 0.00208576 0.0367099 -0.0172277 0.00159899 0.0360703 -0.0166408 0.00142814 0.0376878 -0.0170664 0.00142814 0.0367475 -0.0169645 0.00142814 0.0372678 -0.0147844 0.00119706 0.0356621 -0.015023 0.00119706 0.0356262 -0.0154142 0.00119706 0.0358835 -0.0109114 0.00119706 0.0370308 -0.0138052 0.00119706 0.0384114 -0.0107094 0.00119706 0.0371469 -0.010582 0.00119706 0.0373418 -0.0104876 0.00159899 0.0355919 -0.0100637 0.00419706 0.0341531 -0.00864993 0.00419706 0.0349655 -0.00797929 0.00269706 0.0379007 -0.010312 0.00207574 0.0349959 -0.00892585 0.00269706 0.0352577 -0.00967968 0.00159899 0.0360562 -0.00813603 0.00269706 0.0364658 -0.00916981 0.00159899 0.0368361 -0.0105567 0.00119706 0.0375734 -0.00906862 0.00159899 0.0377623 -0.010639 0.00119706 0.0377913 0.00714807 0.00119706 0.0381606 0.00213545 0.00119706 0.041241 0.00150745 0.00119706 0.0446578 0.00190624 0.00119706 0.0386114 0.000899762 0.0120631 0.0576014 -0.0173795 0.0119287 0.0506537 -0.0126066 0.00700169 0.0456856 -0.017654 0.00302349 0.0389344 -0.0091614 0.00872523 0.0495218 -0.00549804 0.00919516 0.0516173 -0.0186318 0.00642647 0.0410005 -0.0142643 0.00931054 0.0477679 -0.0110773 0.00826832 0.0480159 -0.00337054 0.00754398 0.0504056 0.00963972 0.00318152 0.0503376 0.0115752 0.0106597 0.0566471 0.0116678 0.0104568 0.0563857 0.00124334 0.0117119 0.0571016 0.00375834 0.00908459 0.0539312 0.00569292 0.00612333 0.0514145 -0.0238139 0.0142643 0.0521148 -0.0168953 0.013745 0.0548227 -0.0106307 0.013219 0.0564475 -0.00651976 0.0128385 0.0571228 -0.0022353 0.0124062 0.0575135 -0.00831856 0.011817 0.0546551 -0.000736513 0.00269706 0.0401508 -0.00089862 0.00304901 0.0402128 -0.0013237 0.00419706 0.0386776 -0.00109659 0.00304901 0.0387015 0.000401242 0.00419706 0.0360162 -0.000449846 0.00207574 0.0387696 -0.000588346 0.00304901 0.0372645 0.000515804 0.00304901 0.0362138 0.0019762 0.00304901 0.0357773 -0.000291225 0.00207574 0.0399805 -4.26258e-05 0.00207574 0.0376182 0.000518079 0.00142542 0.0388715 0.000774102 0.00142542 0.0381476 0.000842047 0.00207574 0.0367763 0.00201215 0.00207574 0.0364266 0.00165982 0.00119706 0.0389916 0.0017375 0.00119706 0.038772 0.0013303 0.00142542 0.0376183 0.00212943 0.00119706 0.0385447 -0.00939808 0.00159899 0.0386339 -0.00815712 0.00419706 0.0394766 -0.00848963 0.00269706 0.0392508 -0.0100421 0.0061973 0.0441698 -0.00989229 0.00771444 0.0472584 -0.0086108 0.00797979 0.0460528 -0.00890333 0.00781601 0.0463742 -0.00475328 0.00760061 0.0474945 -0.00468307 0.00734768 0.0483649 -0.00556186 0.00802335 0.0474329 -0.00637292 0.00827417 0.0472533 -0.00734567 0.00818416 0.0473671 -0.00380497 0.00677008 0.048268 -0.00302791 0.00604592 0.0480591 -0.00398205 0.00701447 0.047439 -0.00562635 0.00776614 0.0483229 -0.00790098 0.0081144 0.0486052 -0.00658874 0.00801477 0.0481303 -0.0075331 0.00809023 0.047787 -0.0111596 0.00308955 0.0426673 -0.0104455 0.0032368 0.0425083 -0.010273 0.00532158 0.0435409 -0.00980359 0.00344345 0.042189 -0.00308527 0.00686002 0.0497071 -0.00560435 0.00777276 0.0492088 -0.0105299 0.00792369 0.0477057 -0.0100383 0.00678936 0.045045 -0.0104158 0.00668881 0.0452375 -0.0117864 0.00502266 0.043871 -0.00968877 0.00693995 0.0448239 -0.0110138 0.00510626 0.0437881 -0.0125126 0.00505991 0.0438052 -0.0125441 0.00300228 0.0425045 -0.00883359 0.00757765 0.0427009 -0.00893386 0.00648949 0.0421277 -0.00884789 0.00713216 0.0417236 -0.00213868 0.00693045 0.0446664 -0.00295869 0.00763367 0.0453691 -0.00300518 0.00884177 0.0452739 -0.00575577 0.0102446 0.0457107 -0.00509738 0.0107625 0.0457158 -0.00738633 0.0108672 0.0448149 -0.00781516 0.00985094 0.0445417 -0.00792329 0.0105017 0.0442813 -0.00878037 0.00843015 0.0424556 -0.0018338 0.00329963 0.0465227 -0.00149299 0.00316234 0.0471737 -0.00237658 0.00518891 0.0477763 -0.00107786 0.00309528 0.0476636 -0.00603129 0.00913042 0.0462152 -0.00531608 0.00884549 0.0463615 -0.00449599 0.00868583 0.0461348 -0.00392384 0.00770735 0.0463337 -0.00933787 0.00365997 0.0417992 -0.00919439 0.00605808 0.0426561 -0.00964688 0.00565228 0.0431474 -0.00911797 0.00737207 0.0443237 -0.00876224 0.00792271 0.043802 -0.00788351 0.00914051 0.0449172 -0.00699848 0.0085863 0.0465826 -0.0062572 0.00850683 0.0468566 -0.00541396 0.0085264 0.0466664 -0.00549718 0.00824818 0.0470269 -0.00468501 0.00807157 0.0467199 -0.00672854 0.00921759 0.0459634 -0.00685154 0.00887966 0.046247 -0.00614197 0.00879672 0.0465073 -0.00460326 0.00836683 0.0464 -0.00398558 0.00744287 0.0466677 -0.00279081 0.00571571 0.0463075 -0.00473616 0.00781248 0.0470883 -0.00275951 0.0055436 0.0466743 -0.00277361 0.00590639 0.0459573 -0.00271154 0.00610944 0.0456321 -0.00247608 0.00652826 0.0450778 -0.00322418 0.00712709 0.0458675 -0.0035472 0.00858077 0.0456142 -0.0038257 0.00799188 0.0460447 -0.00520806 0.00919133 0.0461179 -0.0042293 0.00934691 0.0457741 -0.0049795 0.00990865 0.0458141 -0.00592858 0.00949276 0.0459855 -0.00663165 0.00958463 0.0457371 -0.00651529 0.0103463 0.045456 -0.0072929 0.00946561 0.0453767 -0.00721537 0.0102125 0.0450576 -0.00837874 0.00862075 0.0443813 -0.00828829 0.00927744 0.0439469 -0.00862519 0.00851271 0.043319 -0.00903094 0.00706371 0.0432156 -0.00792021 0.00825269 0.0465576 -0.00922262 0.00771792 0.0466888 -0.0112027 0.00663786 0.0455204 -0.0119543 0.00675999 0.0456631 -0.0129686 0.00616813 0.0446097 -0.00139316 0.00515105 0.0489177 -0.00103726 0.00556029 0.0494072 -0.00551418 0.0079947 0.0499845 -0.006312 0.00856939 0.0505115 -0.0082234 0.00836788 0.0493155 -0.0115731 0.0080123 0.0474377 -0.0094375 0.00658223 0.043726 -0.0086846 0.00800985 0.0449051 -0.00920823 0.00753849 0.0454645 -0.00814731 0.00848131 0.0454356 -0.00752779 0.00877379 0.0458878 -0.00716516 0.00835115 0.0469605 -0.0040059 0.00720883 0.0470397 -0.00328125 0.00627546 0.0472808 -0.00267855 0.0053957 0.0470483 -0.00348648 0.00672825 0.0490503 -0.00192651 0.00511107 0.0484157 -0.000469767 0.00308195 0.0481245 0.000100944 0.00312536 0.0483878 0.000145587 0.00159899 0.044029 0.00063902 0.00159899 0.0413444 -0.00121627 0.00419706 0.0434003 -0.00155793 0.00419706 0.0439987 -0.000456443 0.00269706 0.0414201 -0.000851362 0.00269706 0.0435687 -0.00122735 0.00269706 0.0442273 -0.000843421 0.00208576 0.0444928 0.00169008 0.00119706 0.0392226 0.000289086 0.00159899 0.0397585 0.000909551 0.00119706 0.045705 0.00740457 0.00159899 0.0366059 0.00786593 0.00419706 0.0351786 0.00901171 0.00269706 0.0363504 0.0101496 0.00419706 0.0375297 0.00726944 0.00119706 0.0383691 0.00822404 0.00159899 0.0371155 0.00774231 0.00269706 0.0355611 0.00644189 0.00159899 0.0365394 0.00976377 0.00269706 0.0376422 0.0069432 0.00119706 0.0380332 -0.0136357 0.00419706 0.0328907 -0.0180443 0.00419706 0.0344404 -0.0168988 0.00419706 0.0331996 -0.0137232 0.00304901 0.0331017 -0.017692 0.00269706 0.0346337 -0.016678 0.00269706 0.0335354 -0.0152678 0.00269706 0.0330397 -0.0139722 0.00207574 0.0337025 -0.0167293 0.00159899 0.0351619 -0.0160747 0.00159899 0.0344529 -0.0152506 0.00119706 0.0357062 -0.0151643 0.00159899 0.0341329 -0.0243479 0.0158747 0.053566 -0.0255648 0.0169823 0.0529008 -0.0254066 0.0161515 0.0529012 -0.0255913 0.0152634 0.0519337 -0.0250632 0.0153559 0.0527351 -0.0260429 0.0169605 0.0521905 -0.0264217 0.0168838 0.0505488 -0.0260568 0.0162928 0.0491432 -0.026382 0.016415 0.0504145 -0.0260328 0.015797 0.0494191 -0.0240005 0.0142556 0.0519703 -0.0258018 0.0151038 0.0510211 -0.0250296 0.0144695 0.0513683 -0.0241051 0.0141104 0.0515252 -0.0240644 0.0140592 0.0514201 -0.025423 0.0169856 0.0530547 -0.0248554 0.016991 0.0535237 -0.024272 0.0153685 0.0533128 -0.0262023 0.0165114 0.0517354 -0.0262777 0.0159572 0.0506156 -0.0260664 0.0160795 0.051827 -0.0260833 0.0155127 0.050821 -0.0248963 0.0146153 0.0519218 -0.0241071 0.0141997 0.0517549 0.0126079 0.00306863 0.046753 0.0119854 0.00208576 0.0469344 0.00870954 0.00159899 0.0379494 0.0106012 0.00696389 0.0526532 0.0100642 0.0051457 0.0513182 0.011358 0.00507726 0.0510529 0.0118547 0.00691958 0.0523405 0.0124721 0.00705234 0.0520032 0.0125555 0.00537067 0.0502251 0.013199 0.00598457 0.0490358 0.012216 0.0033011 0.0492666 0.0120005 0.00517491 0.0507063 0.0118561 0.0102294 0.0561015 0.0130441 0.0102508 0.0557383 0.0131037 0.0102635 0.0557108 0.0130058 0.00729743 0.0515572 0.0136373 0.00803959 0.0504934 0.0147142 0.011558 0.0542122 -0.0188561 0.0036295 0.036675 -0.0184975 0.00321802 0.0379581 -0.0201511 0.00935869 0.044009 -0.0249567 0.014278 0.0508145 -0.0259905 0.0167781 0.0489224 -0.0194006 0.00663117 0.0403218 -0.0256759 0.0148898 0.0500957 -0.0209805 0.00958272 0.0433693 -0.019933 0.00709126 0.0394525 -0.0259064 0.0153191 0.0497417 -0.0216015 0.0101344 0.0425741 -0.0200935 0.00773744 0.0385538 -0.0218542 0.0109282 0.0417814 -0.021725 0.0117826 0.0411485 -0.0198868 0.00843013 0.0377983 -0.0185427 0.00419706 0.0353487 -0.0183496 0.00306863 0.0354547 -0.0177811 0.00208576 0.0357666 -0.0169249 0.00142814 0.0362365 -0.0142101 0.00159899 0.0342764 -0.0143448 0.00142542 0.0346016 -0.0101773 0.00269706 0.0345386 -0.0137896 0.00269706 0.033262 -0.00758056 0.00419706 0.0379513 -0.00775765 0.00419706 0.0363303 -0.00879551 0.0184971 0.0348355 0.00625108 0.00269706 0.035458 0.00633392 0.00207574 0.0359275 0.00206596 0.00142542 0.0373984 0.00650304 0.00142542 0.036886 0.00670253 0.00119706 0.0380166 0.00622092 0.00304901 0.0352871 0.00618124 0.00419706 0.0350622 0.00196357 0.00419706 0.0355493 -0.0155816 0.0147231 0.0564937 -0.0241546 0.014921 0.052978 -0.0113311 0.0159289 0.0579576 0.0114761 0.010682 0.0566744 -0.00654003 0.0133 0.0577588 0.00270921 0.0129572 0.058613 -0.00652827 0.0139346 0.0582703 -0.0154916 0.0140759 0.0559538 0.00911576 0.0135474 0.0583454 0.00292 0.0144027 0.0589813 0.00260475 0.0123421 0.0581589 -0.0156077 0.0154962 0.0568403 0.00281777 0.013668 0.0588932 -0.00648401 0.0146814 0.0585936 0.0145989 0.012846 0.0558126 0.0134908 0.0113869 0.0566329 0.0137512 0.0112503 0.0562849 0.0129489 0.0105653 0.0562243 0.0148761 0.0126277 0.0538755 0.0136012 0.0129899 0.0570982 0.0121302 0.0130689 0.0577934 0.0135754 0.0129922 0.0571186 0.0116587 0.0111463 0.0571558 0.0118383 0.0117305 0.0575226 0.0119996 0.0123903 0.057739 0.0132412 0.0122858 0.0572485 0.0134255 0.0126407 0.0572041 0.0144129 0.0128858 0.0561677 0.0118619 0.0104277 0.0563522 0.0117587 0.0105652 0.0565272 0.0141208 0.0107363 0.0550385 0.0140728 0.0109263 0.0554868 0.014735 0.011748 0.0547746 0.0146307 0.0118788 0.0553544 0.0139461 0.0110974 0.0559033 0.0126774 0.0108269 0.0566405 0.0127826 0.0116053 0.0571999 0.0141267 0.0121074 0.0564053 0.014349 0.0124904 0.0562229 0.0144273 0.0119984 0.0558989 0.014764 0.0127965 0.0553718 0.0148938 0.0127225 0.0547143 -0.000779978 0.00419706 0.0371403 -0.00076919 0.0184971 0.0371238 -0.00133655 0.0184971 0.0388328 -0.00111191 0.0184971 0.0402944 -0.00111191 0.00419706 0.0402944 -0.000857411 0.00419706 0.0414478 -0.00430876 0.0184971 0.0456871 -0.00530915 0.0184971 0.0456969 -0.00475843 0.0105887 0.0457226 -0.00424823 0.0102448 0.0456784 -0.00353452 0.0095612 0.0455018 -0.00246962 0.0184971 0.0449397 -0.00628069 0.0184971 0.0454581 -0.00629499 0.0110648 0.0454527 -0.00719963 0.0184971 0.0449592 -0.00789971 0.0184971 0.0443094 -0.0086673 0.00907565 0.0429119 -0.00829002 0.0100405 0.0437611 -0.0088056 0.0057361 0.0411434 -0.00876705 0.0184971 0.0425237 -0.00883155 0.00782009 0.0420845 -0.00815712 0.0184971 0.0394766 -0.00230917 0.00741985 0.0448147 -0.00121627 0.0184971 0.0434003 -0.00879601 0.0186884 0.0413929 -0.008688 0.0188506 0.0414019 -0.00848482 0.0184971 0.0433887 -0.00845021 0.0186884 0.0433729 -0.00329995 0.0184971 0.0454119 -0.00171922 0.0186884 0.0441543 -0.000891371 0.0184971 0.0423117 -0.000929017 0.0186884 0.0423061 -0.00168916 0.0184971 0.0441776 -0.00835167 0.0188506 0.0433278 -0.00717726 0.0186884 0.0449284 -0.00529227 0.0188506 0.0455514 -0.00530476 0.0186884 0.0456591 -0.00335663 0.0188506 0.0452769 -0.00331468 0.0186884 0.0453768 -0.00180481 0.0188506 0.0440878 -0.00114746 0.0186884 0.040308 -0.00103623 0.0188506 0.0422902 -0.00124869 0.0188506 0.0403468 -0.00852635 0.018959 0.0414154 -0.00866907 0.0184971 0.0405409 -0.00883393 0.0184971 0.0413897 -0.00812563 0.0186884 0.0394979 -0.00803596 0.0188506 0.0395588 -0.00701816 0.018959 0.0447095 -0.00711353 0.0188506 0.0448407 -0.0034194 0.018959 0.0451273 -0.00193291 0.018959 0.0439883 -0.00774346 0.0189971 0.0397574 -0.00788664 0.0189662 0.0396602 -0.00833568 0.0189971 0.0414314 -0.00820418 0.018959 0.0432602 -0.0080302 0.0189971 0.0431806 -0.00690567 0.0189971 0.0445547 -0.00527356 0.018959 0.0453903 -0.0052515 0.0189971 0.0452002 -0.00349345 0.0189971 0.0449509 -0.00208401 0.0189971 0.0438709 -0.00119667 0.018959 0.0422663 -0.00114077 0.0186701 0.0403055 -0.00136739 0.0186701 0.0388309 -0.00166289 0.0189662 0.0388131 -0.00140019 0.018959 0.0404047 0.000424733 0.0189662 0.0356315 0.000506438 0.0188506 0.0357925 0.00057273 0.0184971 0.0359231 0.00157732 0.0186483 0.0355685 0.000393745 0.0189793 0.0356013 -0.00104254 0.0189662 0.0369444 0.000558741 0.0186701 0.0358955 -0.000795028 0.0186701 0.0371068 -0.00089163 0.0188506 0.0370435 -0.00148273 0.0188506 0.0388239 0.000568463 0.0189525 0.0355988 0.00108846 0.0188201 0.035587 0.00196357 0.0184971 0.0355493 0.00618124 0.0189971 0.0350622 0.0121302 0.0189971 0.0577934 0.0133221 0.0189971 0.0573003 0.0144127 0.0189971 0.056168 0.014911 0.0126834 0.0543681 -0.0155704 0.0163007 0.0569652 -0.0064136 0.0154563 0.0587049 0.00232901 0.0144769 0.0590076 0.0147712 0.0125724 0.0533889 0.0136394 0.00887283 0.049505 0.0128194 0.00419706 0.0466913 0.0101496 0.0189971 0.0375297 -0.0180443 0.0189971 0.0344404 -0.0259905 0.0189971 0.0489224 -0.0262424 0.0169414 0.051713 -0.0262424 0.0189971 0.0517132 -0.0264014 0.0168653 0.0502258 -0.0254229 0.0189971 0.0530548 -0.024366 0.0189971 0.0537943 -0.024366 0.0169884 0.0537943 -0.0100637 0.0184971 0.0341531 -0.00922052 0.0188201 0.0343902 -0.0136357 0.0189971 0.0328907 -0.00854756 0.0189793 0.0345633 -0.00827829 0.0189971 0.034629 -0.0153057 0.00419706 0.0326396 -0.0153057 0.0189971 0.0326396 -0.0168988 0.0189971 0.0331996 0.00930001 0.00419706 0.0360703 -0.00969217 0.0186483 0.0342603 -0.00877558 0.0186701 0.0348119 -0.00871708 0.0189525 0.0345209 -0.0072946 0.0189971 0.0361405 -0.00858467 0.0189662 0.0345857 -0.0076036 0.0184971 0.0381052 -0.00757315 0.0186701 0.0381105 -0.00813155 0.0186701 0.0394939 -0.00745929 0.0188506 0.0381301 -0.00773532 0.0186701 0.0363012 -0.00776436 0.0184971 0.0363117 -0.00870107 0.0188506 0.0347236 -0.00762677 0.0188506 0.0362616 -0.00745719 0.0189662 0.0361998 -0.00728142 0.0189662 0.0381608 -0.00711088 0.0189971 0.0381902 -0.0482018 0.0189971 -0.0272972 -0.0371715 0.0189971 -0.0253095 -0.0380538 0.0189971 -0.0241856 -0.0491989 0.0189971 -0.0281154 -0.0421282 0.0189971 -0.0410922 -0.0390615 0.0189971 -0.0411356 -0.0364748 0.0189971 -0.0262241 -0.0494488 0.0189971 -0.0322791 -0.0395771 0.0189971 -0.0233411 -0.0499429 0.0189971 -0.0310876 -0.0372362 0.0189971 -0.0390938 -0.0331716 0.0189971 -0.0306769 -0.0401698 0.00684139 -0.0276772 -0.0391572 0.00610534 -0.0276555 -0.0395982 0.00692047 -0.0271194 -0.0389304 0.00716276 -0.0266833 -0.037882 0.00664375 -0.0268979 -0.0372291 0.00703737 -0.0267983 -0.0376136 0.0107817 -0.0255431 -0.0367336 0.00917181 -0.0266649 -0.0403066 0.00807788 -0.0256452 -0.0392606 0.00784306 -0.0260639 -0.038546 0.0082862 -0.0258556 -0.0389685 0.0086854 -0.0252351 -0.0374729 0.00945022 -0.0259671 -0.0402068 0.00615318 -0.0294798 -0.0396514 0.00601454 -0.0282375 -0.0408881 0.007084 -0.0288701 -0.0391138 0.00506799 -0.0285626 -0.0387186 0.00515293 -0.0280509 -0.0375172 0.00559045 -0.0272595 -0.038548 0.00632046 -0.0271905 -0.0369381 0.00586036 -0.0271293 -0.0362539 0.00622119 -0.0271541 -0.0411975 0.00763913 -0.0274764 -0.0406603 0.00752256 -0.0269374 -0.0399946 0.00758183 -0.0264427 -0.0382381 0.00754965 -0.0264265 -0.0379337 0.00884838 -0.0258325 -0.0375985 0.00803087 -0.0263672 -0.0370679 0.00854394 -0.0264818 -0.0366477 0.00745511 -0.0268741 -0.0357254 0.00653412 -0.0273192 -0.0401345 0.0105861 -0.0237645 -0.0395018 0.0104771 -0.0239398 -0.0397026 0.0110387 -0.0238254 -0.0391409 0.010972 -0.0240484 -0.0404326 0.00948028 -0.0241284 -0.0393356 0.00980776 -0.0242009 -0.0399397 0.00996574 -0.0239575 -0.0388918 0.010365 -0.0242467 -0.0378964 0.0108185 -0.0250937 -0.037816 0.0101399 -0.0253366 -0.038039 0.0108366 -0.024914 -0.0383154 0.0102501 -0.0247075 -0.0387409 0.00963766 -0.0246079 -0.0380907 0.00962724 -0.0252313 -0.0425915 0.0109679 -0.024257 -0.0427598 0.0105899 -0.0244687 -0.041709 0.0103733 -0.0239559 -0.0428872 0.010221 -0.0247423 -0.0419943 0.00997085 -0.0242358 -0.0422396 0.00960613 -0.0246106 -0.0417804 0.00896573 -0.024903 -0.0410573 0.00855643 -0.0250309 -0.0412355 0.0080624 -0.0261283 -0.0410676 0.00803961 -0.0260285 -0.0415839 0.00842769 -0.0255658 -0.0420915 0.00877453 -0.0254568 -0.0425156 0.0087601 -0.0266002 -0.0425571 0.00906866 -0.025564 -0.0429679 0.00931126 -0.0258426 -0.0385604 0.0109016 -0.0244144 -0.0383804 0.0108794 -0.0245643 -0.0387787 0.00883813 -0.0252094 -0.0395093 0.00835091 -0.0253574 -0.0393095 0.00906376 -0.0246586 -0.0404685 0.00884851 -0.0245966 -0.0398751 0.00928215 -0.0243132 -0.0400854 0.00812966 -0.0255536 -0.0409432 0.00906849 -0.0244579 -0.0414001 0.00926746 -0.0244261 -0.0409774 0.00966072 -0.0240661 -0.0405451 0.0101129 -0.0238453 -0.0414016 0.0107896 -0.0237781 -0.0348456 0.00628232 -0.0278896 -0.0389451 0.00395511 -0.0302003 -0.0375486 0.00486114 -0.0275898 -0.0371921 0.00297093 -0.0300182 -0.036913 0.00352239 -0.0286159 -0.0393928 0.00466117 -0.0301928 -0.0383656 0.00375017 -0.0292023 -0.0391109 0.00440127 -0.0294828 -0.0361446 0.00326776 -0.0291087 -0.0360153 0.00299814 -0.0300116 -0.0366082 0.00292692 -0.0300052 -0.0372505 0.00296221 -0.0309368 -0.0374439 0.00319906 -0.0316972 -0.0378771 0.00379015 -0.0324487 -0.033668 0.00588393 -0.0305081 -0.0338092 0.00590637 -0.0314923 -0.0338243 0.00509611 -0.0310921 -0.0339968 0.00518451 -0.0317602 -0.0339527 0.00594165 -0.0318908 -0.0344851 0.0054257 -0.0326607 -0.0353383 0.00590735 -0.0275619 -0.0346571 0.00622547 -0.0280697 -0.0344682 0.00440052 -0.0319919 -0.033777 0.00509933 -0.0303439 -0.0338625 0.00519097 -0.0296685 -0.0340275 0.00531287 -0.0291354 -0.0359832 0.00551393 -0.0273624 -0.0363194 0.00486821 -0.0275256 -0.0367459 0.00514719 -0.0273585 -0.0348874 0.00573518 -0.0279046 -0.0355186 0.00528462 -0.0276161 -0.0350265 0.00500162 -0.0280308 -0.0344413 0.00554087 -0.0283952 -0.0340898 0.00604546 -0.0288423 -0.0338364 0.0059576 -0.0294354 -0.0393941 0.00462842 -0.0304354 -0.038769 0.00400005 -0.0317091 -0.039157 0.00506211 -0.0286331 -0.0385613 0.00413894 -0.0288542 -0.0382896 0.00469821 -0.0280415 -0.038156 0.00533337 -0.0275762 -0.0359146 0.00426686 -0.0330731 -0.0366271 0.00358721 -0.032563 -0.035596 0.00399271 -0.0326965 -0.0352695 0.00369232 -0.0320928 -0.0363303 0.00324927 -0.0319947 -0.0360835 0.00298844 -0.0310953 -0.0353255 0.00400911 -0.0285275 -0.0363632 0.00360548 -0.0285211 -0.0377691 0.0040383 -0.0282983 -0.0374455 0.00352415 -0.0287695 -0.0382154 0.00334777 -0.0300912 -0.0377354 0.0031182 -0.0300481 -0.0383827 0.00351249 -0.0312796 -0.0379458 0.00331809 -0.0314967 -0.0347691 0.00461727 -0.0325722 -0.0342357 0.0042361 -0.0311644 -0.0341756 0.0042422 -0.0302035 -0.0350073 0.00346117 -0.0311738 -0.0343006 0.00441232 -0.029368 -0.0349389 0.00346978 -0.0300808 -0.0350817 0.0037088 -0.0291551 -0.0345226 0.00462927 -0.0287636 -0.0358452 0.00450781 -0.0278502 -0.0368121 0.00416194 -0.0279366 -0.0423226 0.00859926 -0.0266912 -0.0422071 0.00849599 -0.0268533 -0.0408747 0.00667693 -0.0339988 -0.0429229 0.00861962 -0.0382074 -0.042567 0.00829344 -0.0381044 -0.0425788 0.00829203 -0.0383541 -0.0422834 0.00801128 -0.0381445 -0.0393818 0.00461965 -0.0303162 -0.0395178 0.00491352 -0.0302218 -0.0396027 0.00512202 -0.0298736 -0.0394506 0.00480435 -0.0300309 -0.0394383 0.00470207 -0.0305723 -0.0415855 0.00787854 -0.0279978 -0.0427269 0.00892568 -0.0266334 -0.0481703 0.0120157 -0.0306398 -0.0480844 0.0119767 -0.0302826 -0.0482426 0.012048 -0.03034 -0.0479982 0.011938 -0.0299254 -0.0368173 0.0184971 -0.0265883 -0.0357777 0.00670746 -0.0272951 -0.039195 0.00739103 -0.0392023 -0.0406093 0.00752052 -0.039699 -0.0411315 0.0078878 -0.0400476 -0.0416754 0.00780675 -0.0394557 -0.0422237 0.007958 -0.0380085 -0.041319 0.00751161 -0.0391877 -0.0416984 0.00753261 -0.0383107 -0.0411495 0.00728327 -0.0385697 -0.039846 0.00720004 -0.0390367 -0.042173 0.00900004 -0.0404984 -0.0428147 0.00870101 -0.0393157 -0.0410512 0.0105684 -0.041432 -0.0431049 0.0108464 -0.0403605 -0.0387514 0.00966387 -0.0409085 -0.0391434 0.0103074 -0.0411728 -0.0407756 0.0105309 -0.0414608 -0.0377219 0.0101133 -0.0400297 -0.0379931 0.00949184 -0.0402571 -0.0376552 0.008749 -0.0393301 -0.0390708 0.0082297 -0.0403352 -0.0411463 0.0101371 -0.0413871 -0.0400428 0.00933773 -0.0412482 -0.040579 0.00887089 -0.0410495 -0.039845 0.00857274 -0.0408477 -0.0403588 0.00998871 -0.0414279 -0.0395547 0.00983112 -0.0412793 -0.0408025 0.00954707 -0.0413114 -0.0392451 0.00910062 -0.0409671 -0.0384429 0.00883736 -0.0403771 -0.0422992 0.00830695 -0.0395455 -0.0427701 0.00847413 -0.0383281 -0.0416066 0.00820787 -0.040161 -0.0420033 0.00807288 -0.0395533 -0.0424623 0.00818064 -0.038316 -0.0427917 0.0100531 -0.0405381 -0.0430239 0.00939108 -0.0398988 -0.0426246 0.00920973 -0.0402459 -0.0418688 0.00934661 -0.0409048 -0.0416727 0.00875974 -0.0406493 -0.0398251 0.0077658 -0.0401028 -0.0404983 0.00814985 -0.0405327 -0.0411176 0.00848044 -0.0406779 -0.0412522 0.00912542 -0.0410507 -0.0415185 0.00973432 -0.0412037 -0.0421864 0.00990315 -0.0409439 -0.0481753 0.0120178 -0.0301095 -0.0489173 0.0124823 -0.0300062 -0.0497583 0.0147701 -0.0290425 -0.0493038 0.0138755 -0.0284659 -0.049221 0.0130827 -0.0316397 -0.0494534 0.0138964 -0.0320309 -0.0494488 0.0147504 -0.0322791 -0.049864 0.0139492 -0.0308547 -0.0499718 0.0147839 -0.0309335 -0.048201 0.0120295 -0.03058 -0.0487679 0.01243 -0.0311518 -0.0494725 0.01314 -0.0297827 -0.0491132 0.0130551 -0.0289091 -0.0489099 0.0138236 -0.0279986 -0.0487854 0.0147076 -0.0276986 -0.0483285 0.0122685 -0.0290503 -0.0495105 0.0131498 -0.0307381 -0.0498106 0.0139417 -0.0295993 -0.0500023 0.0147858 -0.0306991 -0.0410898 0.0111978 -0.0236987 -0.041239 0.0184971 -0.0237183 -0.0408018 0.0111653 -0.023679 -0.0383856 0.0184971 -0.0245596 -0.0391518 0.0109733 -0.024043 -0.0397688 0.0110464 -0.0238063 -0.0376136 0.0184971 -0.0255431 -0.0427786 0.00896472 -0.0266626 -0.0429664 0.00987614 -0.0250708 -0.0484908 0.012906 -0.0282278 -0.0484397 0.0137608 -0.0276148 -0.0482018 0.0146699 -0.0272972 -0.0383806 0.00486053 -0.0337757 -0.0374246 0.00500544 -0.0341681 -0.038015 0.00596062 -0.0356891 -0.0391708 0.0042875 -0.0311698 -0.0404435 0.0062315 -0.0344299 -0.0389557 0.00578144 -0.0353497 -0.0397975 0.00589785 -0.0349015 -0.0359854 0.00781408 -0.0356551 -0.0364331 0.00709216 -0.0358261 -0.0349513 0.0049274 -0.0329238 -0.0372362 0.01005 -0.0390938 -0.038657 0.00394957 -0.0318278 -0.0375951 0.00379168 -0.03261 -0.0369069 0.00389414 -0.0328981 -0.0362078 0.00412866 -0.0330514 -0.0373855 0.0093417 -0.0392492 -0.0377541 0.00859004 -0.0393427 -0.0371288 0.00642996 -0.0358518 -0.0385919 0.0077261 -0.0393096 -0.0401129 0.00716649 -0.0389558 -0.0338306 0.0184971 -0.0294536 -0.0337729 0.00593377 -0.0296576 -0.0341374 0.0059897 -0.032259 -0.0340635 0.00597027 -0.0321243 -0.0357254 0.0184971 -0.0273192 -0.0344423 0.00615912 -0.0283125 -0.0463405 0.013195 -0.0366009 -0.0464329 0.012408 -0.0362888 -0.0460003 0.0110368 -0.0352761 -0.0433219 0.0101836 -0.0399737 -0.0433672 0.00954557 -0.039448 -0.0463191 0.0116547 -0.0358303 -0.0432258 0.00900661 -0.0388356 -0.0455287 0.0106222 -0.0347007 -0.0411084 0.0189528 -0.0234047 -0.0412561 0.0189194 -0.0234859 -0.042392 0.0113409 -0.0241094 -0.042392 0.0184971 -0.0241094 -0.0420359 0.0186486 -0.0239139 -0.0431049 0.0189971 -0.0403605 -0.0499134 0.0189971 -0.0295158 -0.0499032 0.0147794 -0.0294761 -0.0492616 0.0147383 -0.0281922 -0.0357648 0.00849091 -0.0354031 -0.0341374 0.0184971 -0.032259 -0.0339416 0.0186483 -0.031924 -0.0336891 0.0188202 -0.0315032 -0.0334261 0.0189485 -0.0310779 -0.0378241 0.0189971 -0.0401631 -0.0380844 0.0101623 -0.0404519 -0.0405999 0.0189971 -0.0414677 -0.0393744 0.0103392 -0.0412647 -0.0427016 0.0107918 -0.0407287 -0.042386 0.0107491 -0.040948 -0.0415993 0.0106428 -0.0413071 -0.0375543 0.0187471 -0.0255118 -0.0374841 0.0188506 -0.0254747 -0.0382884 0.0188506 -0.0244501 -0.0381686 0.0189662 -0.0243151 -0.0406943 0.0189971 -0.0231778 -0.041586 0.0188205 -0.0236671 -0.0412613 0.0188506 -0.0235735 -0.0412437 0.0186701 -0.0236877 -0.0397185 0.0184971 -0.0238207 -0.039626 0.0189662 -0.0235071 -0.0396771 0.0188506 -0.0236802 -0.0383651 0.0186701 -0.0245365 -0.0397097 0.0186701 -0.0237911 -0.035665 0.0188506 -0.0271858 -0.0366461 0.0189301 -0.0264062 -0.0355906 0.0189662 -0.0270213 -0.0375862 0.0186701 -0.0255286 -0.0367714 0.0187471 -0.0265396 -0.0356978 0.0187471 -0.0272582 -0.0373925 0.0189301 -0.0254263 -0.0335658 0.0188506 -0.0310744 -0.0336799 0.0186701 -0.0310565 -0.0337105 0.0184971 -0.0310517 -0.0334145 0.0189526 -0.0310595 -0.0344152 0.0189662 -0.0278495 -0.0356223 0.0189301 -0.0270914 -0.0346504 0.0184971 -0.0280767 -0.0357126 0.0186701 -0.0272911 -0.0335189 0.0189662 -0.0293551 -0.033691 0.0188506 -0.0294095 -0.0345451 0.0188506 -0.0279749 -0.0346282 0.0186701 -0.0280552 -0.0338011 0.0186701 -0.0294443 -0.0333538 0.0189971 -0.029303 -0.0342907 0.0189971 -0.0277293 -0.0355193 0.0189971 -0.0268637 0.00366354 0.0285471 -0.038522 -0.00323068 0.0285471 -0.0385616 0.0158245 0.0285471 -0.0353109 0.00771454 0.0287471 -0.0381227 0.0310557 0.0287471 -0.0234155 0.0333566 0.0285471 -0.0196104 0.0331817 0.0285797 -0.0199683 0.0355739 0.0285471 -0.0152231 0.0383814 0.0287471 -0.00629848 0.0381841 0.0285471 -0.00626608 0.0387155 0.0285797 -0.000978602 0.0385748 0.0285471 0.00305527 0.0386941 0.0285471 -0.000301925 0.0312173 0.0285471 0.0228703 0.0336623 0.0285471 0.0190884 0.0237855 0.0285471 0.0305278 0.0292298 0.0285471 0.0253619 0.0108785 0.0287471 0.0373503 0.0195296 0.0285471 -0.0280978 0.0204596 0.0274971 -0.0297928 0.0204596 0.0285471 -0.0297928 0.0157867 0.0274971 -0.0342666 0.0174461 0.0274971 -0.0343648 0.0177197 0.0285471 -0.0343086 0.0181395 0.0285471 -0.0341793 0.0194147 0.0285471 -0.0333786 0.0204175 0.0274971 -0.0317257 0.0204175 0.0285471 -0.0317257 0.0324156 0.0274971 -0.0153743 0.0324156 0.0285471 -0.0153743 0.0336468 0.0274971 -0.0183724 0.0333733 0.0285471 -0.0167328 0.0328001 0.0285471 -0.0205275 0.0331817 0.0274971 -0.0199683 0.0320703 0.0274971 -0.0212043 0.0305327 0.0285471 -0.0218357 0.0288733 0.0274971 -0.0217375 0.0374844 0.0285471 0.00201957 0.0385729 0.0274971 -0.00180273 0.0382505 0.0285471 -0.00257445 0.0382505 0.0274971 -0.00257445 0.0371391 0.0285471 -0.00381049 0.035875 0.0274971 -0.00438568 0.0356014 0.0285471 -0.0044419 0.0341784 0.0285471 0.0181479 0.0331771 0.0285471 0.0196175 0.0344083 0.0285471 0.0166193 0.0344083 0.0274971 0.0166193 0.0339432 0.0285471 0.0150234 0.0339432 0.0274971 0.0150234 0.0328318 0.0274971 0.0137874 0.0312942 0.0274971 0.013156 0.0296349 0.0285471 0.0132543 0.0191956 0.0285471 0.0335125 0.0196095 0.0285471 0.033365 0.0205266 0.0285471 0.0328086 0.020648 0.0285471 0.032704 0.0208486 0.0274971 0.0325097 0.0216057 0.0274971 0.0313455 0.0216057 0.0285471 0.0313455 0.0217786 0.0274971 0.0308147 0.0218792 0.0285471 0.0297059 0.0214141 0.0285471 0.02811 0.0214141 0.0274971 0.02811 0.0207336 0.0274971 0.0272288 0.0203027 0.0285471 0.026874 0.0203027 0.0274971 0.026874 0.0187651 0.0285471 0.0262426 0.00137122 0.0274971 0.0313113 0.00164482 0.0285471 0.0313676 0.00333981 0.0274971 0.0322976 0.00438477 0.0285471 0.0358834 0.0042119 0.0274971 0.0364142 0.00345474 0.0285471 0.0375784 0.00180181 0.0285471 0.0385813 0.00180181 0.0274971 0.0385813 -0.0142581 0.0274971 0.0279903 -0.014689 0.0274971 0.0276355 -0.0159531 0.0274971 0.0270603 -0.013386 0.0285471 0.032107 -0.013386 0.0274971 0.032107 -0.0141431 0.0274971 0.0332712 -0.0290397 0.0274971 0.0145312 -0.0273447 0.0285471 0.0154612 -0.0273447 0.0274971 0.0154612 -0.0263418 0.0285471 0.0171141 -0.0262997 0.0285471 0.0190471 -0.0272297 0.0274971 0.0207421 -0.0328444 0.0274971 -0.00228745 -0.0312679 0.0274971 0.000544439 -0.0315413 0.0274971 0.00218403 -0.0324991 0.0285471 0.00354262 -0.0324991 0.0274971 0.00354262 -0.0339514 0.0285471 0.00435112 -0.0298012 0.0285471 -0.0204605 -0.0298012 0.0274971 -0.0204605 -0.0281062 0.0274971 -0.0195305 -0.0271033 0.0285471 -0.0178776 -0.0270612 0.0285471 -0.0159446 -0.0279913 0.0274971 -0.0142497 -0.019205 0.0285471 -0.033505 -0.0145742 0.0285471 -0.0309642 -0.0155771 0.0274971 -0.0326171 -0.0145321 0.0285471 -0.0290312 -0.0145321 0.0274971 -0.0290312 -0.0171151 0.0274971 -0.0263334 0.00138582 0.0285471 -0.0380407 0.00296228 0.0285471 -0.0352088 0.00268886 0.0285471 -0.0335692 0.000278769 0.0285471 -0.0314021 -0.00015182 0.0274971 -0.0386721 0.0158427 0.0272971 -0.0340746 0.0177197 0.0274971 -0.0343086 0.0189837 0.0274971 -0.0337334 0.0194147 0.0274971 -0.0333786 0.0200951 0.0274971 -0.0324974 0.0205602 0.0274971 -0.0309016 0.0191953 0.0272971 -0.0280521 0.0202867 0.0274971 -0.029262 0.0195296 0.0274971 -0.0280978 0.019329 0.0274971 -0.0279034 -0.0200578 0.0285471 0.017055 0.00327225 0.0287471 0.0280165 0.00149849 0.0287471 0.0290265 0.0154105 0.0287471 0.0248032 0.0143186 0.0287471 0.0252906 0.0293798 0.0285471 -0.000952903 0.0290057 0.0285471 0.00101933 0.027695 0.0287471 0.00249459 0.0260132 0.0287471 0.00342107 0.0260692 0.0285471 0.00361308 0.00816631 0.0287471 -0.0121777 -0.0247321 0.0285471 0.027422 -0.0246013 0.0290971 0.0268878 -0.0257305 0.0285471 0.0268742 -0.026346 0.0285471 0.0247621 -0.0257982 0.0285471 0.0237637 -0.0248246 0.0285471 0.023173 -0.034748 0.0290971 0.0109877 -0.03413 0.0285471 0.0119328 -0.0351911 0.0290971 0.0102575 -0.0357191 0.0285471 0.0104113 -0.0352097 0.0290971 0.00940357 -0.0351961 0.0285471 0.00827442 -0.0342225 0.0285471 0.0076837 -0.0256783 0.0290971 -0.022598 -0.0258091 0.0285471 -0.0220637 -0.0268074 0.0285471 -0.0226115 -0.0268701 0.0290971 -0.023739 -0.0264779 0.0290971 -0.0253417 -0.0268751 0.0285471 -0.0257221 -0.0259015 0.0285471 -0.0263128 -0.010189 0.0290971 -0.0319959 -0.0113182 0.0285471 -0.0320094 -0.0113809 0.0290971 -0.0331369 -0.0113995 0.0290971 -0.0339908 -0.0119337 0.0285471 -0.0341216 -0.0109886 0.0290971 -0.0347396 -0.0104123 0.0285471 -0.0357107 0.00792401 0.0290971 -0.0323901 0.00679486 0.0285471 -0.0324036 0.00717522 0.0290971 -0.0328009 0.00673217 0.0290971 -0.0335311 0.00620414 0.0285471 -0.0333772 0.00712445 0.0290971 -0.0351338 0.00617936 0.0285471 -0.0345158 0.00785466 0.0290971 -0.0355769 0.00672717 0.0285471 -0.0355142 0.0324566 0.0290971 -0.00859651 0.0320135 0.0290971 -0.00932672 0.0314607 0.0285471 -0.0103114 0.0320085 0.0285471 -0.0113098 0.0335302 0.0290971 0.00674059 0.0328 0.0290971 0.00718363 0.0319567 0.0285471 0.00748902 0.0323891 0.0290971 0.00793243 0.0323447 0.0290971 0.00842226 0.0324077 0.0290971 0.00878633 0.0325502 0.0290971 0.00912725 0.0327243 0.0285471 0.0101228 0.0328508 0.0290971 0.00951653 0.0330411 0.0290971 0.00967329 0.0246612 0.0285471 0.022096 0.0241735 0.0290971 0.0229812 0.0238057 0.0285471 0.0225722 0.0232416 0.0285471 0.0233725 0.0237504 0.0290971 0.0235814 0.023674 0.0290971 0.0238159 0.0236296 0.0290971 0.0243057 0.023835 0.0290971 0.0250107 0.0241356 0.0290971 0.0254 0.0240091 0.0285471 0.0260063 0.0249148 0.0285471 0.0263782 0.0258922 0.0285471 0.0263203 0.0248844 0.0290971 0.0258108 0.024326 0.0290971 0.0255567 -0.00946668 0.0290971 0.0351921 -0.00894112 0.0285471 0.0318881 0.0289293 0.0272971 -0.0215454 0.0305327 0.0274971 -0.0218357 0.0319551 0.0272971 -0.0210409 0.0333733 0.0274971 -0.0167328 0.0322819 0.0272971 -0.015523 0.0371391 0.0274971 -0.00381049 0.0374317 0.0272971 -0.00331119 0.03757 0.0274971 -0.00345565 0.0383809 0.0272971 -0.00174677 0.0387155 0.0274971 -0.000978602 0.038615 0.0274971 0.000130193 0.0384421 0.0274971 0.000660987 0.0376849 0.0274971 0.00182518 0.0296349 0.0274971 0.0132543 0.0342086 0.0272971 0.0166311 0.0341349 0.0274971 0.0182589 0.0331771 0.0274971 0.0196175 0.0330434 0.0272971 0.0194687 0.0189911 0.0272971 0.0264931 0.0190387 0.0274971 0.0262988 0.0171057 0.0274971 0.0263409 0.0205953 0.0272971 0.0273733 0.0217365 0.0274971 0.0288817 0.0218792 0.0274971 0.0297059 0.0215445 0.0272971 0.0289377 0.0215843 0.0272971 0.0307671 0.0207041 0.0272971 0.0323713 0.0191956 0.0274971 0.0335125 -0.000232148 0.0272971 0.0316016 0.00164482 0.0274971 0.0313676 0.00290886 0.0274971 0.0319427 0.00279363 0.0272971 0.0321062 0.00402027 0.0274971 0.0331788 0.00428567 0.0272971 0.0347865 0.0043427 0.0274971 0.0339505 0.00448532 0.0274971 0.0347746 0.00438477 0.0274971 0.0358834 0.00402689 0.0272971 0.0363383 0.00312044 0.0272971 0.0376241 0.00345474 0.0274971 0.0375784 0.00325417 0.0274971 0.0377728 -0.017886 0.0274971 0.0271024 -0.0143964 0.0272971 0.0281348 -0.0135776 0.0274971 0.0288715 -0.0132552 0.0274971 0.0296433 -0.0134472 0.0272971 0.0296992 -0.0131126 0.0274971 0.0304674 -0.0132131 0.0274971 0.0315762 -0.0142876 0.0272971 0.0331329 -0.0157961 0.0274971 0.0342741 -0.015852 0.0272971 0.0340821 -0.0309166 0.0272971 0.0147653 -0.0290872 0.0272971 0.0147255 -0.0263418 0.0274971 0.0171141 -0.0262997 0.0274971 0.0190471 -0.026494 0.0272971 0.0189995 -0.0289386 0.0272971 0.0215529 -0.034382 0.0274971 -0.00291885 -0.0329596 0.0272971 -0.00212398 -0.031733 0.0274971 -0.00105141 -0.0319077 0.0272971 -0.000954134 -0.0314676 0.0272971 0.000556264 -0.0317263 0.0272971 0.00210806 -0.0282445 0.0272971 -0.019386 -0.0271033 0.0274971 -0.0178776 -0.0270612 0.0274971 -0.0159446 -0.0272555 0.0272971 -0.0159922 -0.0281357 0.0272971 -0.014388 -0.0172721 0.0274971 -0.0335471 -0.0173196 0.0272971 -0.0333528 -0.0145742 0.0274971 -0.0309642 -0.0154621 0.0274971 -0.0273362 -0.0156066 0.0272971 -0.0274746 -0.017171 0.0272971 -0.0265254 -0.000184718 0.0272971 -0.0384748 0.00138582 0.0274971 -0.0380407 0.00127059 0.0272971 -0.0378772 0.00249723 0.0274971 -0.0368046 0.00276263 0.0272971 -0.035197 0.00296228 0.0274971 -0.0352088 0.00268886 0.0274971 -0.0335692 0.00250385 0.0272971 -0.0336452 0.00173113 0.0274971 -0.0322106 0.000278769 0.0274971 -0.0314021 0.000222814 0.0272971 -0.0315941 -0.018714 0.0287471 0.0161656 -0.0201137 0.0287471 0.016863 -0.00590272 0.0369971 0.0123691 0.00439937 0.0369971 0.0263147 0.00439937 0.0287471 0.0263147 0.00327225 0.0369971 0.0280165 0.013519 0.0287471 0.00586448 0.0134311 0.0369971 0.00588875 0.0143186 0.0369971 0.0252906 0.0291799 0.0369971 -0.000946396 0.0288221 0.0369971 0.00094009 0.0291799 0.0287471 -0.000946396 0.0288221 0.0287471 0.00094009 0.027695 0.0369971 0.00249459 -0.0246013 0.0366471 0.0268878 -0.0251598 0.0366471 0.0266337 -0.0253501 0.0290971 0.0264769 -0.0256507 0.0366471 0.0260877 -0.0257932 0.0366471 0.0257467 -0.0257932 0.0290971 0.0257467 -0.0257354 0.0366471 0.0246583 -0.0258118 0.0290971 0.0248928 -0.0254009 0.0290971 0.024144 -0.0331453 0.0290971 0.01138 -0.0339992 0.0290971 0.0113985 -0.034748 0.0366471 0.0109877 -0.0347988 0.0366471 0.00865478 -0.0347988 0.0290971 0.00865478 -0.0340686 0.0366471 0.00821174 -0.0248244 0.0290971 -0.0226165 -0.0264271 0.0366471 -0.0230088 -0.0268701 0.0366471 -0.023739 -0.0264271 0.0290971 -0.0230088 -0.0268887 0.0290971 -0.0245929 -0.0268887 0.0366471 -0.0245929 -0.00933513 0.0290971 -0.0320144 -0.010189 0.0366471 -0.0319959 -0.0109378 0.0366471 -0.0324067 -0.0109378 0.0290971 -0.0324067 -0.0112384 0.0366471 -0.032796 -0.0113809 0.0366471 -0.0331369 -0.0114439 0.0366471 -0.033501 -0.0113231 0.0366471 -0.0342253 -0.0102584 0.0290971 -0.0351827 -0.0109 0.0366471 -0.0348255 0.00877791 0.0366471 -0.0324086 0.00712445 0.0366471 -0.0351338 0.00671359 0.0290971 -0.034385 0.00785466 0.0366471 -0.0355769 0.0340593 0.0290971 -0.00820424 0.0332054 0.0290971 -0.00818565 0.0319949 0.0366471 -0.0101806 0.0319949 0.0290971 -0.0101806 0.0324058 0.0366471 -0.0109294 0.0324058 0.0290971 -0.0109294 0.033136 0.0366471 -0.0113725 0.0335996 0.0366471 0.00992739 0.0337204 0.0290971 0.00995222 0.0335996 0.0290971 0.00992739 0.0328508 0.0366471 0.00951653 0.0323891 0.0366471 0.00793243 0.0324655 0.0290971 0.00769794 0.0328 0.0366471 0.00718363 0.0328886 0.0290971 0.00709776 0.0257383 0.0290971 0.0257923 0.0250053 0.0290971 0.0258357 0.0257383 0.0366471 0.0257923 0.0248844 0.0366471 0.0258108 0.0236926 0.0366471 0.0246698 0.0236926 0.0290971 0.0246698 0.023674 0.0366471 0.0238159 0.0240849 0.0366471 0.0230671 0.0248151 0.0366471 0.022624 0.0240849 0.0290971 0.0230671 -0.00859702 0.0366471 0.0356278 -0.0092763 0.0366471 0.0353488 -0.00871789 0.0290971 0.0356029 -0.00946668 0.0366471 0.0351921 -0.00976729 0.0366471 0.0348028 -0.00990972 0.0290971 0.0344619 -0.00990972 0.0366471 0.0344619 -0.00992831 0.0290971 0.033608 -0.00951745 0.0290971 0.0328592 0.0161898 0.0272971 -0.0280581 0.0142395 0.0272971 -0.0299253 0.0147919 0.0278971 -0.03118 0.0142091 0.0272971 -0.0313226 0.0148814 0.0272971 -0.0325479 0.0162442 0.0278971 -0.0326969 -0.0237474 0.0366471 0.0268692 -0.0244805 0.0366471 0.0269126 -0.0253501 0.0366471 0.0264769 -0.0258118 0.0366471 0.0248928 -0.0246707 0.0366471 0.023701 -0.0254009 0.0366471 0.024144 -0.0253123 0.0366471 0.0240582 -0.0258562 0.0366471 0.0253827 -0.0242091 0.0376385 0.0252851 -0.0351911 0.0366471 0.0102575 -0.0339992 0.0366471 0.0113985 -0.033607 0.0376385 0.00979584 -0.0352097 0.0366471 0.00940357 -0.0248244 0.0366471 -0.0226165 -0.0256783 0.0366471 -0.022598 -0.0264779 0.0366471 -0.0253417 -0.0100682 0.0366471 -0.031971 -0.0113995 0.0366471 -0.0339908 -0.0109886 0.0366471 -0.0347396 -0.0107474 0.0366471 -0.03225 0.00673217 0.0366471 -0.0335311 0.00792401 0.0366471 -0.0323901 0.00717522 0.0366471 -0.0328009 0.00671359 0.0366471 -0.034385 0.0320135 0.0366471 -0.00932672 0.0324566 0.0366471 -0.00859651 0.0332054 0.0366471 -0.00818565 0.0344535 0.0366471 0.00990881 0.0324077 0.0366471 0.00878633 0.0241356 0.0366471 0.0254 -0.00871789 0.0366471 0.0356029 -0.00997273 0.0366471 0.0340978 -0.00985194 0.0366471 0.0333735 -0.00942885 0.0366471 0.0327733 -0.00878724 0.0366471 0.0324161 -0.00951745 0.0366471 0.0328592 -0.00992831 0.0366471 0.033608 0.0305058 0.0278971 -0.0161355 0.0306737 0.0272971 -0.0155594 0.0273261 0.0272971 -0.0173962 0.0279021 0.0278971 -0.0175641 0.0278785 0.0278971 -0.0186509 0.0272957 0.0272971 -0.0187935 0.027968 0.0272971 -0.0200188 0.0357424 0.0272971 0.00183441 0.0337771 0.0278971 0.000958617 0.0334314 0.0272971 0.00144901 0.032628 0.0272971 0.000555494 0.0328907 0.0278971 -0.000633609 0.0322918 0.0272971 -0.000598134 0.0331818 0.0272971 -0.00276549 0.0343995 0.0278971 -0.00277391 0.0301806 0.0278971 0.0188799 0.0300379 0.0272971 0.0194627 0.0288126 0.0272971 0.0187904 0.0280876 0.0272971 0.0175955 0.0291629 0.0278971 0.0153878 0.0300923 0.0278971 0.014824 0.0287295 0.0272971 0.0149729 0.0166338 0.0278971 0.0284744 0.0160544 0.0278971 0.0300509 0.0163158 0.0278971 0.0309481 0.0162835 0.0272971 0.031877 0.0169407 0.0278971 0.0316431 0.0189061 0.0272971 0.0325189 0.0178053 0.0278971 0.0319981 0.0176514 0.0278971 0.0319665 -0.00069541 0.0278971 0.0365123 -0.00111034 0.0272971 0.0369457 -0.00128294 0.0278971 0.0344962 -0.0171865 0.0278971 0.0327596 -0.018051 0.0278971 0.0324046 -0.0172851 0.0272971 0.0333514 -0.0186759 0.0278971 0.0317097 -0.0183967 0.0272971 0.032895 -0.0192001 0.0272971 0.0320015 -0.0187836 0.0278971 0.0298905 -0.0193387 0.0272971 0.0296626 -0.0175964 0.0272971 0.028096 -0.0291722 0.0272971 0.0207513 -0.0305695 0.0272971 0.0207817 -0.0317948 0.0272971 0.0201094 -0.0319674 0.0278971 0.0176598 -0.0318779 0.0272971 0.0162919 -0.0344089 0.0278971 0.00278141 -0.0356383 0.0272971 0.00338786 -0.0370125 0.0278971 0.0013528 -0.0370362 0.0278971 0.000266013 -0.0369467 0.0272971 -0.00110193 -0.0299338 0.0272971 -0.0142404 -0.0311884 0.0278971 -0.0147928 -0.0321414 0.0278971 -0.0153157 -0.0327053 0.0278971 -0.0162451 -0.032206 0.0278971 -0.0182849 -0.0312767 0.0278971 -0.0188487 -0.0326394 0.0272971 -0.0186998 -0.0174046 0.0272971 -0.027327 -0.0186041 0.0272971 -0.027256 -0.01937 0.0278971 -0.0282028 -0.0202563 0.0278971 -0.029795 -0.0201026 0.0278971 -0.0307169 -0.0208553 0.0272971 -0.0297596 -0.0195641 0.0278971 -0.0314808 -0.00140809 0.0272971 -0.0323654 -0.00221845 0.0278971 -0.0334711 -0.00278233 0.0278971 -0.0344004 -0.00263338 0.0272971 -0.0330377 -0.00280598 0.0278971 -0.0354872 -0.00338877 0.0272971 -0.0356299 0.0174192 0.0278971 -0.0286646 0.0163324 0.0278971 -0.0286409 0.0164863 0.0372971 -0.0286093 0.0153794 0.0278971 -0.0291638 0.0148156 0.0278971 -0.0300932 0.0148891 0.0372971 -0.0314784 0.0153148 0.0278971 -0.032133 0.0154276 0.0372971 -0.0322423 0.0305058 0.0372971 -0.0161355 0.029419 0.0278971 -0.0161118 0.028466 0.0278971 -0.0166347 0.0279021 0.0372971 -0.0175641 0.0284014 0.0278971 -0.0196039 0.0355746 0.0278971 0.00125837 0.0346416 0.0278971 0.00131362 0.0337771 0.0372971 0.000958617 0.0331522 0.0372971 0.000263657 0.0331522 0.0278971 0.000263657 0.0328907 0.0372971 -0.000633609 0.0330444 0.0278971 -0.00155547 0.0335829 0.0372971 -0.00231933 0.0335829 0.0278971 -0.00231933 0.0301806 0.0372971 0.0188799 0.0312673 0.0278971 0.0188562 0.0292275 0.0278971 0.018357 0.0292275 0.0372971 0.018357 0.0286637 0.0372971 0.0174276 0.0286637 0.0278971 0.0174276 0.0291629 0.0372971 0.0153878 0.02864 0.0278971 0.0163409 0.0187382 0.0372971 0.0319428 0.0166984 0.0372971 0.0314436 0.0166984 0.0278971 0.0314436 0.0163158 0.0372971 0.0309481 0.0161345 0.0372971 0.0305142 0.0160544 0.0372971 0.0300509 0.0161345 0.0278971 0.0305142 0.0161109 0.0278971 0.0294274 0.0162081 0.0372971 0.029129 0.0162081 0.0278971 0.029129 0.0166338 0.0372971 0.0284744 0.0167466 0.0372971 0.0283651 0.0167466 0.0278971 0.0283651 0.0175632 0.0372971 0.0279106 0.00134438 0.0372971 0.0370116 0.00134438 0.0278971 0.0370116 0.000257597 0.0372971 0.0370353 -0.00045311 0.0372971 0.0367119 0.000257597 0.0278971 0.0370353 -0.00125928 0.0278971 0.035583 -0.00128294 0.0372971 0.0344962 -0.00118574 0.0372971 0.0341978 -0.000760027 0.0278971 0.0335432 0.000169328 0.0278971 0.0329793 -0.0162535 0.0372971 0.0327044 -0.0171865 0.0372971 0.0327596 -0.0162535 0.0278971 0.0327044 -0.018051 0.0372971 0.0324046 -0.0189374 0.0278971 0.0308124 -0.0182451 0.0372971 0.0291267 -0.0182451 0.0278971 0.0291267 -0.0174286 0.0372971 0.0286721 -0.0174286 0.0278971 0.0286721 -0.0304269 0.0278971 0.0201989 -0.0313799 0.0278971 0.019676 -0.0319438 0.0372971 0.0187466 -0.0319674 0.0372971 0.0176598 -0.0319438 0.0278971 0.0187466 -0.0314445 0.0278971 0.0167068 -0.0305151 0.0372971 0.016143 -0.0354956 0.0372971 0.00280506 -0.0354956 0.0278971 0.00280506 -0.0362063 0.0372971 0.00248166 -0.0364486 0.0372971 0.00228215 -0.0364486 0.0278971 0.00228215 -0.0370927 0.0372971 0.000889433 -0.0370362 0.0372971 0.000266013 -0.0365133 0.0278971 -0.000686994 -0.0355839 0.0372971 -0.00125087 -0.0301016 0.0372971 -0.0148165 -0.0311884 0.0372971 -0.0147928 -0.0301016 0.0278971 -0.0148165 -0.0321414 0.0372971 -0.0153157 -0.0327289 0.0372971 -0.0173319 -0.032206 0.0372971 -0.0182849 -0.0327289 0.0278971 -0.0173319 -0.0312767 0.0372971 -0.0188487 -0.0185054 0.0278971 -0.0278478 -0.0186593 0.0372971 -0.0278794 -0.0199949 0.0278971 -0.0288978 -0.0201762 0.0372971 -0.0293317 -0.0201998 0.0372971 -0.0304185 -0.0196769 0.0372971 -0.0313715 -0.0187475 0.0372971 -0.0319353 -0.00126544 0.0278971 -0.0329482 -0.00260104 0.0372971 -0.0339665 -0.00286251 0.0372971 -0.0348638 -0.00280598 0.0372971 -0.0354872 -0.00270878 0.0372971 -0.0357857 -0.00228307 0.0372971 -0.0364402 -0.00228307 0.0278971 -0.0364402 -0.0021703 0.0372971 -0.0365495 -0.00135371 0.0278971 -0.0370041 -0.00135371 0.0372971 -0.0370041 -0.0245579 0.0284971 0.0301757 -0.0387836 0.0284971 -0.00306354 -0.0387836 0.0287471 -0.00306354 -0.0196155 0.0284971 -0.0335913 -0.0171602 0.0284971 -0.034909 -0.0315771 0.0284971 -0.0227205 -0.0269971 0.0287471 -0.0280073 -0.0269971 0.0284971 -0.0280073 -0.0369227 0.0287471 -0.0122548 -0.0329162 0.0287471 -0.0207336 -0.0383908 0.0287471 0.00630598 -0.0357671 0.0287471 0.0153092 -0.0357671 0.0284971 0.0153092 -0.0383908 0.0284971 0.00630598 -0.0313915 0.0284971 0.0229837 -0.0353583 0.0284971 0.0162313 -0.0310651 0.0287471 0.023423 -0.0192934 0.0284971 0.0337847 -0.00772387 0.0287471 0.0381302 -0.00772387 0.0284971 0.0381302 -0.0385966 0.0282971 0.00181442 -0.0388755 0.0284971 0.0015103 -0.0389042 0.0284971 0.000189702 -0.0386389 0.0282971 -0.00012626 -0.0386503 0.0284971 -0.000735157 -0.0376374 0.0284971 -0.00217195 -0.0316282 0.0284971 -0.0129959 -0.02964 0.0282971 -0.0132324 -0.0335423 0.0284971 -0.0195643 -0.0333979 0.0282971 -0.0194259 -0.0337856 0.0284971 -0.019285 -0.0206674 0.0282971 -0.0327077 -0.0188098 0.0284971 -0.026023 -0.0170549 0.0284971 -0.0261269 -0.0171109 0.0282971 -0.026319 -0.0203207 0.0282971 -0.0268542 -0.0214365 0.0282971 -0.0280952 -0.0219035 0.0282971 -0.0296975 -0.0218025 0.0282971 -0.0308107 -0.0216289 0.0282971 -0.0313437 -0.0192651 0.0284971 -0.0337115 -0.00138302 0.0282971 -0.031289 -0.00170527 0.0284971 -0.0311512 -0.00349783 0.0284971 -0.0321348 -0.00292684 0.0282971 -0.031923 -0.00440867 0.0282971 -0.0358795 -0.00423511 0.0282971 -0.0364124 -0.00361937 0.0284971 -0.0377196 -0.0034749 0.0282971 -0.0375813 0.0158926 0.0284971 -0.026844 0.0135552 0.0282971 -0.0288567 0.0141001 0.0284971 -0.0278275 0.0130394 0.0284971 -0.0295756 0.0131892 0.0282971 -0.0315723 0.0157266 0.0284971 -0.034473 0.0133628 0.0282971 -0.0321052 0.026126 0.0284971 -0.0170465 0.0271866 0.0284971 -0.0152984 0.0277576 0.0282971 -0.0150866 0.0266418 0.0282971 -0.0163276 0.026318 0.0282971 -0.0171025 0.0261748 0.0282971 -0.0179299 0.0260815 0.0284971 -0.0190907 0.0288132 0.0284971 -0.0219439 0.0272096 0.0282971 -0.0207449 0.0315181 0.0282971 -0.00218223 0.0313331 0.0284971 -0.0022582 0.031044 0.0284971 -0.000524228 0.0327112 0.0284971 0.00247067 0.0360362 0.0282971 0.00284248 0.0343373 0.0284971 0.00313843 0.031729 0.0282971 0.0204404 0.0297883 0.0282971 0.0204826 0.0284039 0.0284971 0.0200686 0.0285192 0.0282971 0.0199051 0.0280865 0.0282971 0.0195488 0.0272285 0.0284971 0.0187614 0.0267367 0.0284971 0.0170737 0.0270373 0.0282971 0.0159486 0.0272109 0.0282971 0.0154157 0.0295747 0.0284971 0.0130479 0.0279711 0.0282971 0.0142468 0.0145082 0.0282971 0.0290352 0.0143139 0.0284971 0.0289876 0.0155574 0.0282971 0.0326354 0.0172592 0.0282971 0.0335692 0.0172116 0.0284971 0.0337634 0.00150189 0.0284971 0.0388746 -0.00195186 0.0282971 0.0324021 -0.00284339 0.0282971 0.0360446 -0.00307989 0.0284971 0.0340564 -0.00197479 0.0284971 0.0378486 -0.000182225 0.0284971 0.0388322 0.000181286 0.0284971 0.0389033 -0.0157919 0.0282971 0.0342885 -0.0174908 0.0284971 0.0345844 -0.0193484 0.0282971 0.0278997 -0.0194821 0.0284971 0.027751 -0.0207841 0.0284971 0.0309218 -0.0202923 0.0284971 0.0326095 -0.0288225 0.0284971 0.0219514 -0.0288785 0.0282971 0.0217593 -0.0329145 0.0284971 0.0207439 -0.0327808 0.0284971 0.0154275 -0.0326363 0.0282971 0.0155658 -0.0337199 0.0284971 0.0192642 -0.00308218 0.0282971 -0.010557 -0.00749326 0.0284971 -0.00832457 -0.0101802 0.0282971 -0.00417466 -0.0109854 0.0282971 0.000654123 -0.0096158 0.0282971 0.00535409 -0.00184695 0.0284971 0.0110512 -0.000327294 0.0284971 -0.0293945 0.0239187 0.0284971 -0.0164373 0.0220206 0.0282971 -0.0169775 0.0220518 0.0284971 -0.0171751 -0.00590272 0.0282971 0.0123691 -0.00581662 0.0284971 0.0121886 -0.00702224 0.0282971 0.0120678 -0.00700611 0.0284971 0.0118685 -0.0244526 0.0284971 -0.00377677 -0.0260225 0.0282971 -0.00341357 -0.00895459 0.0284971 -0.023059 -0.0103029 0.0284971 -0.0247131 -0.0122526 0.0284971 -0.0255807 -0.0143839 0.0284971 -0.0254751 -0.0077241 0.0281471 0.0360644 -0.00883676 0.0281471 0.0360886 -0.00981246 0.0284971 0.0355532 -0.00981246 0.0281471 0.0355532 -0.0103898 0.0281471 0.0346018 -0.010414 0.0284971 0.0334891 -0.010414 0.0281471 0.0334891 -0.00987861 0.0284971 0.0325134 -0.00987861 0.0281471 0.0325134 -0.0236076 0.0281471 0.0273492 -0.0245627 0.0284971 0.0274058 -0.0260876 0.0284971 0.0263309 -0.0260876 0.0281471 0.0263309 -0.0263553 0.0281471 0.0254122 -0.0263553 0.0284971 0.0254122 -0.0261979 0.0281471 0.0244684 -0.0256466 0.0284971 0.0236864 -0.0330055 0.0281471 0.01186 -0.0341181 0.0281471 0.0118842 -0.0350938 0.0281471 0.0113488 -0.0356953 0.0281471 0.0092847 -0.03516 0.0281471 0.008309 -0.0342085 0.0281471 0.0077317 -0.0256397 0.0281471 -0.0220799 -0.0265248 0.0281471 -0.0224434 -0.0274323 0.0284971 -0.0240735 -0.0271646 0.0281471 -0.0231549 -0.0272749 0.0281471 -0.0250173 -0.0267236 0.0284971 -0.0257994 -0.0258875 0.0284971 -0.0262648 -0.0267236 0.0281471 -0.0257994 -0.00919525 0.0284971 -0.0315344 -0.0103079 0.0284971 -0.0315102 -0.0112836 0.0284971 -0.0320456 -0.0113498 0.0284971 -0.0350854 0.00780514 0.0284971 -0.0319044 0.0089178 0.0281471 -0.0319286 0.00682944 0.0284971 -0.0324397 0.00682944 0.0281471 -0.0324397 0.00676329 0.0281471 -0.0354796 0.00676329 0.0284971 -0.0354796 0.0341992 0.0281471 -0.0077242 0.0330865 0.0284971 -0.00769999 0.0330865 0.0281471 -0.00769999 0.0321108 0.0284971 -0.00823535 0.0315093 0.0284971 -0.0102995 0.0315093 0.0281471 -0.0102995 0.0320446 0.0281471 -0.0112752 0.0320446 0.0284971 -0.0112752 0.0329961 0.0284971 -0.0118525 0.0334807 0.0281471 0.0104131 0.0336382 0.0284971 0.0104454 0.032505 0.0281471 0.0098777 0.0321133 0.0281471 0.00937045 0.0321133 0.0284971 0.00937045 0.0318456 0.0284971 0.00845182 0.0319277 0.0281471 0.00892621 0.0318456 0.0281471 0.00845182 0.032003 0.0284971 0.00750801 0.0325543 0.0284971 0.00672596 0.0258782 0.0284971 0.0262723 0.024923 0.0284971 0.0263289 0.0240379 0.0281471 0.0259654 0.0233981 0.0284971 0.0252539 0.0231305 0.0284971 0.0243353 0.0233981 0.0281471 0.0252539 0.0232878 0.0284971 0.0233915 0.0238391 0.0284971 0.0226094 0.0246752 0.0281471 0.022144 -0.0360455 0.0256971 -0.00283498 -0.0360455 0.0282971 -0.00283498 -0.0375037 0.0282971 -0.00202323 -0.0377051 0.0282971 -0.00182806 -0.0384653 0.0282971 -0.000659186 -0.0386389 0.0256971 -0.00012626 -0.0387398 0.0282971 0.000986989 -0.0382729 0.0282971 0.00258925 -0.0375897 0.0282971 0.00347399 -0.0358879 0.0256971 0.00440775 -0.037157 0.0282971 0.00383025 -0.0358879 0.0282971 0.00440775 -0.0356132 0.0282971 0.00446419 -0.0339472 0.0282971 0.00436552 -0.0315807 0.0282971 -0.0131901 -0.0332825 0.0282971 -0.0141239 -0.0332825 0.0256971 -0.0141239 -0.0342894 0.0282971 -0.0157835 -0.0343316 0.0256971 -0.0177241 -0.0343316 0.0282971 -0.0177241 -0.0317383 0.0282971 -0.0204329 -0.0317383 0.0256971 -0.0204329 -0.0187769 0.0282971 -0.0262203 -0.0190515 0.0256971 -0.0262767 -0.0190515 0.0282971 -0.0262767 -0.0207533 0.0256971 -0.0272105 -0.0207533 0.0282971 -0.0272105 -0.0217603 0.0282971 -0.02887 -0.0217603 0.0256971 -0.02887 -0.0208687 0.0256971 -0.0325125 -0.0208687 0.0282971 -0.0325125 0.000282966 0.0256971 -0.0313877 -0.00165772 0.0282971 -0.0313455 -0.00335952 0.0282971 -0.0322792 -0.00404271 0.0282971 -0.033164 -0.00436643 0.0282971 -0.0339388 -0.00436643 0.0256971 -0.0339388 -0.00450963 0.0256971 -0.0347662 -0.00450963 0.0282971 -0.0347662 -0.00327353 0.0282971 -0.0377765 -0.0034749 0.0256971 -0.0375813 0.0178808 0.0256971 -0.0270805 0.0162149 0.0282971 -0.0269818 0.0159402 0.0282971 -0.0270382 0.0162149 0.0256971 -0.0269818 0.014671 0.0282971 -0.0276157 0.014671 0.0256971 -0.0276157 0.0142384 0.0282971 -0.027972 0.0132314 0.0282971 -0.0296316 0.0132314 0.0256971 -0.0296316 0.0130883 0.0282971 -0.030459 0.0130883 0.0256971 -0.030459 0.0131892 0.0256971 -0.0315723 0.014123 0.0282971 -0.0332741 0.014123 0.0256971 -0.0332741 0.0143244 0.0282971 -0.0334692 0.0143244 0.0256971 -0.0334692 0.0293015 0.0282971 -0.0144527 0.0290268 0.0282971 -0.0145091 0.0293015 0.0256971 -0.0144527 0.0290268 0.0256971 -0.0145091 0.027325 0.0282971 -0.0154429 0.0277576 0.0256971 -0.0150866 0.026318 0.0256971 -0.0171025 0.0262758 0.0282971 -0.0190431 0.0262758 0.0256971 -0.0190431 0.0264494 0.0282971 -0.0195761 0.0264494 0.0256971 -0.0195761 0.0274109 0.0256971 -0.0209401 0.0274109 0.0282971 -0.0209401 0.0288691 0.0256971 -0.0217519 0.0360362 0.0256971 0.00284248 0.0343702 0.0282971 0.00294115 0.0328264 0.0282971 0.00230721 0.0317105 0.0282971 0.00106621 0.0312436 0.0282971 -0.000536053 0.0315181 0.0256971 -0.00218223 0.0324797 0.0282971 -0.00354627 0.0339379 0.0282971 -0.00435802 0.0339379 0.0256971 -0.00435802 0.030063 0.0282971 0.020539 0.031729 0.0256971 0.0204404 0.0297883 0.0256971 0.0204826 0.0280865 0.0256971 0.0195488 0.0274033 0.0282971 0.0186641 0.0270796 0.0282971 0.0178893 0.0269364 0.0282971 0.0170618 0.0270373 0.0256971 0.0159486 0.0281725 0.0282971 0.0140516 0.0296307 0.0256971 0.0132399 0.0191998 0.0256971 0.0335269 0.0172592 0.0256971 0.0335692 0.0145504 0.0282971 0.0309759 0.015442 0.0282971 0.0273334 0.015442 0.0256971 0.0273334 -0.000134676 0.0282971 0.0386379 0.00180601 0.0256971 0.0385957 -0.00183647 0.0282971 0.0377042 -0.00183647 0.0256971 0.0377042 -0.00284339 0.0256971 0.0360446 -0.00288563 0.0282971 0.0341039 -0.000292299 0.0282971 0.0313952 -0.00195186 0.0256971 0.0324021 -0.0174579 0.0282971 0.0343871 -0.0174579 0.0256971 0.0343871 -0.0190017 0.0282971 0.0337532 -0.0201176 0.0282971 0.0325122 -0.0205845 0.0282971 0.0309099 -0.02031 0.0282971 0.0292638 -0.0178902 0.0282971 0.027088 -0.0308191 0.0282971 0.0218016 -0.0325209 0.0282971 0.0208678 -0.0335279 0.0282971 0.0192083 -0.0335279 0.0256971 0.0192083 -0.0335701 0.0282971 0.0172676 0.00307285 0.0282971 0.0105645 -0.00181405 0.0282971 0.0108539 -0.00634257 0.0282971 0.00899435 -0.0096158 0.0264971 0.00535409 -0.00735954 0.0282971 -0.00817585 -0.0101802 0.0264971 -0.00417466 0.00825353 0.0282971 -0.0122045 0.00816631 0.0257971 -0.0121777 -0.00150782 0.0257971 -0.029019 0.0251215 0.0257971 -0.0148729 0.0238064 0.0282971 -0.0162718 0.0221995 0.0257971 -0.0169455 -0.0244673 0.0282971 -0.00357732 -0.0104244 0.0282971 -0.0245542 -0.0122893 0.0282971 -0.0253841 -0.0118708 0.0257971 -0.0252845 -0.0122893 0.0257971 -0.0253841 -0.0136973 0.0257971 -0.0254177 -0.014328 0.0257971 -0.0252831 -0.0124045 0.0257971 -0.00640188 -0.0069827 0.0254971 0.0386086 -0.00946677 0.0254971 0.0386626 -0.0129339 0.0254971 0.0353432 -0.00892713 0.0281471 0.0319361 0.0117458 0.0257971 0.0403265 0.0204239 0.0257971 0.0367008 0.0280776 0.0257971 0.0312349 0.0343231 0.0259971 0.024203 0.0388473 0.0259971 0.0159577 0.0414232 0.0257971 0.00691229 0.0414232 0.0259971 0.00691229 0.0419219 0.0257971 -0.00247949 0.0419219 0.0259971 -0.00247949 0.0366924 0.0259971 -0.0204248 0.0312265 0.0257971 -0.0280785 0.0241946 0.0259971 -0.034324 -0.00248791 0.0257971 -0.0419228 -0.0117552 0.0257971 -0.040319 -0.0116712 0.0254971 -0.040031 0.0158353 0.0254971 -0.0385707 0.0159492 0.0257971 -0.0388482 0.00690388 0.0257971 -0.0414242 0.0366924 0.0257971 -0.0204248 0.0240218 0.0254971 -0.0340788 0.0241946 0.0257971 -0.034324 0.0209508 0.0254971 -0.0360484 0.0383489 0.0254971 -0.0163638 0.0364303 0.0254971 -0.0202789 0.0403181 0.0257971 -0.0117468 0.0370376 0.0254971 0.0191547 0.0388473 0.0257971 0.0159577 0.0385698 0.0254971 0.0158437 0.0343231 0.0257971 0.024203 0.0365692 0.0254971 0.0200347 0.020278 0.0254971 0.0364387 0.0163628 0.0254971 0.0383573 -0.0245627 0.0281471 0.0274058 -0.0254478 0.0281471 0.0270424 -0.0249986 0.0254971 0.0300197 -0.0269747 0.0254971 0.0292083 -0.028403 0.0254971 0.0276198 -0.0290007 0.0254971 0.0255689 -0.0274185 0.0254971 0.0217158 -0.0256466 0.0281471 0.0236864 -0.0322641 0.0254971 0.0144042 -0.0347481 0.0254971 0.0144582 -0.0369264 0.0254971 0.013263 -0.0356711 0.0281471 0.0103974 -0.0382153 0.0254971 0.0111388 -0.0382693 0.0254971 0.00865469 -0.0260756 0.0254971 -0.019466 -0.0280517 0.0254971 -0.0202775 -0.0274323 0.0281471 -0.0240735 -0.0103079 0.0281471 -0.0315102 -0.0112836 0.0281471 -0.0320456 -0.0109379 0.0254971 -0.0289362 -0.0118609 0.0281471 -0.032997 -0.0118851 0.0281471 -0.0341097 -0.0113498 0.0281471 -0.0350854 -0.0103983 0.0281471 -0.0356627 0.00780514 0.0281471 -0.0319044 0.00625214 0.0281471 -0.0333912 0.00499682 0.0254971 -0.0305256 0.00370797 0.0254971 -0.0326498 0.00622793 0.0281471 -0.0345039 0.0302782 0.0254971 -0.00632119 0.0321108 0.0281471 -0.00823535 0.0315335 0.0281471 -0.00918683 0.0301305 0.0254971 -0.0131078 0.0329961 0.0281471 -0.0118525 0.0324388 0.0281471 0.00683786 0.0314918 0.0254971 0.00422718 0.0333903 0.0281471 0.00626056 0.0320233 0.0254971 0.00394694 0.0323636 0.0254971 0.0038093 0.032003 0.0281471 0.00750801 0.0319035 0.0281471 0.00781356 0.0293295 0.0254971 0.00718354 0.0293835 0.0254971 0.00966762 0.0306724 0.0254971 0.0117919 0.0327531 0.0281471 0.010082 0.0340843 0.0254971 0.0131238 0.0346832 0.0254971 0.0130746 0.0350442 0.0254971 0.0130079 0.0218095 0.0254971 0.0208887 0.0237237 0.0281471 0.0227213 0.0232878 0.0281471 0.0233915 0.0231883 0.0281471 0.023697 0.0206684 0.0254971 0.0255511 0.0231305 0.0281471 0.0243353 0.0232125 0.0281471 0.0248097 0.0247655 0.0281471 0.0262965 0.0241355 0.0254971 0.0288705 0.0237898 0.0281471 0.0257611 0.0290976 0.0254971 0.00105895 0.0278936 0.0254971 0.00271944 0.0260132 0.0257971 0.00342107 0.00930953 0.0257971 -0.0127832 0.00825024 0.0254971 -0.0118897 0.00439937 0.0257971 0.0263147 0.00468108 0.0254971 0.0264178 0.00347712 0.0254971 0.0282357 0.0288132 0.0254971 -0.0219439 0.0261748 0.0256971 -0.0179299 0.0260815 0.0254971 -0.0190907 0.0272096 0.0256971 -0.0207449 0.0270651 0.0254971 -0.0208832 0.0266418 0.0256971 -0.0163276 0.0271866 0.0254971 -0.0152984 0.027325 0.0256971 -0.0154429 0.0157266 0.0254971 -0.034473 0.0157825 0.0256971 -0.034281 0.0133628 0.0256971 -0.0321052 0.0135552 0.0256971 -0.0288567 0.0141001 0.0254971 -0.0278275 0.0142384 0.0256971 -0.027972 0.0179368 0.0254971 -0.0268885 0.0159402 0.0256971 -0.0270382 0.0158926 0.0254971 -0.026844 -0.0018713 0.0254971 -0.0387802 -0.00181534 0.0256971 -0.0385882 -0.00327353 0.0256971 -0.0377765 -0.00423511 0.0256971 -0.0364124 -0.00460294 0.0254971 -0.035927 -0.00440867 0.0256971 -0.0358795 -0.00404271 0.0256971 -0.033164 -0.00335952 0.0256971 -0.0322792 -0.00138302 0.0256971 -0.031289 -0.00165772 0.0256971 -0.0313455 -0.00292684 0.0256971 -0.031923 -0.0208917 0.0254971 -0.027066 -0.0219523 0.0254971 -0.0288141 -0.0218025 0.0256971 -0.0308107 -0.0219968 0.0254971 -0.0308583 -0.0192092 0.0256971 -0.0335195 -0.0210132 0.0254971 -0.0326508 -0.0315807 0.0256971 -0.0131901 -0.0342894 0.0256971 -0.0157835 -0.0333979 0.0256971 -0.0194259 -0.0375037 0.0256971 -0.00202323 -0.0376374 0.0254971 -0.00217195 -0.0377051 0.0256971 -0.00182806 -0.0385966 0.0256971 0.00181442 -0.0384653 0.0256971 -0.000659186 -0.0386503 0.0254971 -0.000735157 -0.0387398 0.0256971 0.000986989 -0.0382729 0.0256971 0.00258925 -0.0375897 0.0256971 0.00347399 -0.0372723 0.0254971 0.00399371 -0.037157 0.0256971 0.00383025 -0.0356132 0.0256971 0.00446419 -0.0288785 0.0256971 0.0217593 -0.0308191 0.0256971 0.0218016 -0.0325209 0.0256971 0.0208678 -0.0335701 0.0256971 0.0172676 -0.0326363 0.0256971 0.0155658 -0.0327808 0.0254971 0.0154275 -0.0309768 0.0256971 0.0145589 -0.0310327 0.0254971 0.0143668 -0.0190017 0.0256971 0.0337532 -0.0174908 0.0254971 0.0345844 -0.0201176 0.0256971 0.0325122 -0.0191169 0.0254971 0.0339167 -0.0205845 0.0256971 0.0309099 -0.02031 0.0256971 0.0292638 -0.020495 0.0254971 0.0291878 -0.0193484 0.0256971 0.0278997 -0.0194821 0.0254971 0.027751 -0.000134676 0.0256971 0.0386379 -0.000182225 0.0254971 0.0388322 -0.00303541 0.0254971 0.0361006 -0.00307989 0.0254971 0.0340564 -0.00288563 0.0256971 0.0341039 -0.000348254 0.0254971 0.0312032 0.0155574 0.0256971 0.0326354 0.015419 0.0254971 0.0327799 0.0145504 0.0256971 0.0309759 0.0145082 0.0256971 0.0290352 0.0143584 0.0254971 0.0310318 0.0143139 0.0254971 0.0289876 0.0171015 0.0256971 0.0263265 0.0297407 0.0254971 0.0206769 0.0279482 0.0254971 0.0196933 0.0270796 0.0256971 0.0178893 0.0279711 0.0256971 0.0142468 0.0278266 0.0254971 0.0141085 0.0343702 0.0256971 0.00294115 0.0343373 0.0254971 0.00313843 0.0328264 0.0256971 0.00230721 0.0327112 0.0254971 0.00247067 0.0317105 0.0256971 0.00106621 0.0315358 0.0254971 0.00116349 0.0312436 0.0256971 -0.000536053 0.0324797 0.0256971 -0.00354627 0.032346 0.0254971 -0.00369499 0.0271663 0.0286971 0.0522059 0.0368283 0.0286971 0.0459021 0.0450749 0.0286971 0.0378344 0.0449217 0.0288971 0.0377058 0.0515891 0.0286971 0.0283129 0.0584952 0.0286971 0.00641391 0.0586217 0.0286971 -0.00512201 0.0584224 0.0288971 -0.00510459 0.0520201 0.0288971 -0.0270748 0.0521975 0.0286971 -0.0271672 0.037826 0.0286971 -0.0450758 0.0376974 0.0288971 -0.0449226 0.0283045 0.0286971 -0.05159 0.0176951 0.0286971 -0.0561215 0.0282083 0.0288971 -0.0514147 0.0176349 0.0288971 -0.0559307 -0.00513043 0.0286971 -0.0586226 0.0271663 0.0281971 0.0522059 0.0450749 0.0281971 0.0378344 0.0515891 0.0281971 0.0283129 0.0561206 0.0286971 0.0177035 0.0586217 0.0281971 -0.00512201 0.0564952 0.0286971 -0.016461 0.0564952 0.0281971 -0.016461 0.0521975 0.0281971 -0.0271672 0.0458936 0.0281971 -0.0368292 0.0458936 0.0286971 -0.0368292 0.037826 0.0281971 -0.0450758 0.0283045 0.0281971 -0.05159 0.00640549 0.0286971 -0.0584961 -0.00513043 0.0281971 -0.0586226 -0.0164694 0.0281971 -0.0564961 0.00640549 0.0281971 -0.0584961 0.0176951 0.0281971 -0.0561215 0.0167778 0.0259971 -0.0532127 0.0358653 0.0259971 -0.0427395 0.049492 0.0259971 -0.025759 0.053567 0.0259971 -0.0156076 0.0555833 0.0259971 -0.00485636 0.0584952 0.0281971 0.00641391 0.0554633 0.0259971 0.00608169 0.0561206 0.0281971 0.0177035 0.0532118 0.0259971 0.0167862 0.0427386 0.0259971 0.0358737 0.0349194 0.0259971 0.0435233 0.0368283 0.0281971 0.0459021 0.0265199 0.0292971 0.050964 0.0265199 0.0288971 0.050964 0.0359521 0.0288971 0.0448102 0.0359521 0.0292971 0.0448102 0.0440025 0.0288971 0.0369344 0.0440025 0.0292971 0.0369344 0.0547854 0.0288971 0.0172824 0.0571035 0.0288971 0.00626142 0.0571035 0.0292971 0.00626142 0.057227 0.0292971 -0.00500008 0.0551511 0.0288971 -0.0160693 0.027631 0.0292971 -0.0503626 0.027631 0.0288971 -0.0503626 0.017274 0.0288971 -0.0547863 0.017274 0.0292971 -0.0547863 0.006253 0.0292971 -0.0571044 -0.0160777 0.0292971 -0.055152 -0.0379992 0.0805971 0.0362345 -0.0390847 0.0790971 0.0372697 -0.014033 0.0790971 0.0521498 -0.00423574 0.0805971 0.052333 0.00546369 0.0790971 0.0537262 0.0146835 0.0805971 0.0504072 -0.0237155 0.0412971 -0.0813618 -0.00999981 0.0412971 -0.0841548 0.00399798 0.0414971 -0.0848519 0.0179102 0.0414971 -0.0830358 0.00398856 0.0412971 -0.0846521 0.017868 0.0412971 -0.0828403 0.0313337 0.0414971 -0.0789545 0.0312599 0.0412971 -0.0787686 0.0552734 0.0414971 -0.0645008 0.0551433 0.0412971 -0.0643489 0.0651366 0.0414971 -0.0545226 0.0730505 0.0412971 -0.0429556 0.083237 0.0414971 -0.0169469 0.0846918 0.0412971 -0.00300749 0.0840323 0.0412971 0.0109742 0.0812718 0.0414971 0.0247147 0.0759169 0.0412971 0.0376665 0.0597147 0.0414971 0.0604198 0.0686823 0.0412971 0.0496491 0.0595741 0.0412971 0.0602775 0.0488408 0.0412971 0.0692618 0.0367751 0.0412971 0.0763569 0.0237621 0.0414971 0.0815613 0.0489561 0.0670971 0.0694253 0.0366449 0.0675971 0.0760867 0.0723083 0.0675971 0.043623 0.068465 0.0675971 0.0494375 0.0684392 0.0675971 0.0494734 0.0593632 0.0675971 0.0600642 0.0812718 0.0670971 0.0247147 0.075744 0.0675971 0.0373393 0.0842636 0.0675971 0.00554125 0.0732229 0.0670971 -0.043057 0.0793117 0.0670971 -0.0304169 0.084392 0.0675971 -0.00299683 0.0647532 0.0675971 -0.0542016 0.0680969 0.0675971 -0.049936 0.0651366 0.0670971 -0.0545226 0.0552734 0.0670971 -0.0645008 0.046834 0.0675971 -0.0702667 0.0497256 0.0675971 -0.068251 0.0439024 0.0670971 -0.0727195 0.043644 0.0675971 -0.0722915 0.0313337 0.0670971 -0.0789545 0.00370399 0.0675971 -0.0843648 0.00399798 0.0670971 -0.0848519 -0.0237715 0.0644971 -0.0815538 -0.00999981 0.0642971 -0.0841548 0.00398856 0.0642971 -0.0846521 0.0313337 0.0644971 -0.0789545 0.017868 0.0642971 -0.0828403 0.0312599 0.0642971 -0.0787686 0.043799 0.0642971 -0.0725483 0.0439024 0.0644971 -0.0727195 0.0551433 0.0642971 -0.0643489 0.0651366 0.0644971 -0.0545226 0.0649832 0.0642971 -0.0543942 0.079125 0.0642971 -0.0303452 0.0840323 0.0642971 0.0109742 0.0842306 0.0644971 0.011 0.0812718 0.0644971 0.0247147 0.076096 0.0644971 0.0377554 0.0759169 0.0642971 0.0376665 0.0686823 0.0642971 0.0496491 0.0688444 0.0644971 0.0497663 0.0595741 0.0642971 0.0602775 0.0597147 0.0644971 0.0604198 0.0489561 0.0644971 0.0694253 0.0367751 0.0642971 0.0763569 0.0237621 0.0644971 0.0815613 0.0488408 0.0632971 0.0692618 0.0597147 0.0630971 0.0604198 0.0688444 0.0630971 0.0497663 0.0842306 0.0630971 0.011 0.083041 0.0632971 -0.016907 0.079125 0.0632971 -0.0303452 0.0732229 0.0630971 -0.043057 0.0730505 0.0632971 -0.0429556 0.0651366 0.0630971 -0.0545226 0.0649832 0.0632971 -0.0543942 0.0552734 0.0630971 -0.0645008 0.0179102 0.0630971 -0.0830358 0.017868 0.0632971 -0.0828403 0.00399798 0.0630971 -0.0848519 0.00398856 0.0632971 -0.0846521 -0.0237715 0.0619971 -0.0815538 -0.0237155 0.0617971 -0.0813618 -0.0100234 0.0619971 -0.0843534 -0.00999981 0.0617971 -0.0841548 0.00399798 0.0619971 -0.0848519 0.0179102 0.0619971 -0.0830358 0.043799 0.0617971 -0.0725483 0.0551433 0.0617971 -0.0643489 0.0651366 0.0619971 -0.0545226 0.0730505 0.0617971 -0.0429556 0.0846918 0.0617971 -0.00300749 0.0812718 0.0619971 0.0247147 0.076096 0.0619971 0.0377554 0.0810805 0.0617971 0.0246566 0.0759169 0.0617971 0.0376665 0.0688444 0.0619971 0.0497663 0.0597147 0.0619971 0.0604198 0.0488408 0.0617971 0.0692618 0.0368619 0.0619971 0.0765371 0.0237062 0.0607971 0.0813693 0.0368619 0.0605971 0.0765371 0.0367751 0.0607971 0.0763569 0.0488408 0.0607971 0.0692618 0.0595741 0.0607971 0.0602775 0.0688444 0.0605971 0.0497663 0.0686823 0.0607971 0.0496491 0.076096 0.0605971 0.0377554 0.0812718 0.0605971 0.0247147 0.0810805 0.0607971 0.0246566 0.0842306 0.0605971 0.011 0.0552734 0.0605971 -0.0645008 0.0439024 0.0605971 -0.0727195 0.0313337 0.0605971 -0.0789545 0.0179102 0.0605971 -0.0830358 0.0312599 0.0607971 -0.0787686 0.00399798 0.0605971 -0.0848519 -0.00999981 0.0607971 -0.0841548 -0.0237715 0.0594971 -0.0815538 0.00399798 0.0594971 -0.0848519 0.00398856 0.0592971 -0.0846521 0.017868 0.0592971 -0.0828403 0.0439024 0.0594971 -0.0727195 0.043799 0.0592971 -0.0725483 0.0552734 0.0594971 -0.0645008 0.0649832 0.0592971 -0.0543942 0.0730505 0.0592971 -0.0429556 0.079125 0.0592971 -0.0303452 0.083041 0.0592971 -0.016907 0.0848917 0.0594971 -0.0030146 0.0812718 0.0594971 0.0247147 0.0759169 0.0592971 0.0376665 0.0688444 0.0594971 0.0497663 0.0686823 0.0592971 0.0496491 0.0488408 0.0592971 0.0692618 0.0237062 0.0592971 0.0813693 0.0237621 0.0580971 0.0815613 0.0368619 0.0580971 0.0765371 0.0367751 0.0582971 0.0763569 0.0489561 0.0580971 0.0694253 0.076096 0.0580971 0.0377554 0.0759169 0.0582971 0.0376665 0.0812718 0.0580971 0.0247147 0.0840323 0.0582971 0.0109742 0.0848917 0.0580971 -0.0030146 0.0846918 0.0582971 -0.00300749 0.0793117 0.0580971 -0.0304169 0.0651366 0.0580971 -0.0545226 0.0649832 0.0582971 -0.0543942 0.0439024 0.0580971 -0.0727195 0.043799 0.0582971 -0.0725483 0.0313337 0.0580971 -0.0789545 0.0312599 0.0582971 -0.0787686 0.0179102 0.0580971 -0.0830358 0.017868 0.0582971 -0.0828403 -0.0100234 0.0580971 -0.0843534 -0.0237715 0.0569971 -0.0815538 -0.0237155 0.0567971 -0.0813618 -0.0100234 0.0569971 -0.0843534 0.0313337 0.0569971 -0.0789545 0.0312599 0.0567971 -0.0787686 0.0439024 0.0569971 -0.0727195 0.0730505 0.0567971 -0.0429556 0.0842306 0.0569971 0.011 0.0810805 0.0567971 0.0246566 0.0597147 0.0569971 0.0604198 0.0489561 0.0569971 0.0694253 0.0368619 0.0569971 0.0765371 0.0237621 0.0569971 0.0815613 0.0367751 0.0567971 0.0763569 0.0368619 0.0555971 0.0765371 0.0367751 0.0557971 0.0763569 0.0489561 0.0555971 0.0694253 0.0488408 0.0557971 0.0692618 0.0597147 0.0555971 0.0604198 0.0686823 0.0557971 0.0496491 0.0759169 0.0557971 0.0376665 0.076096 0.0555971 0.0377554 0.0810805 0.0557971 0.0246566 0.0812718 0.0555971 0.0247147 0.0842306 0.0555971 0.011 0.0846918 0.0557971 -0.00300749 0.083237 0.0555971 -0.0169469 0.083041 0.0557971 -0.016907 0.0793117 0.0555971 -0.0304169 0.0730505 0.0557971 -0.0429556 0.0651366 0.0555971 -0.0545226 0.0552734 0.0555971 -0.0645008 0.0439024 0.0555971 -0.0727195 0.0179102 0.0555971 -0.0830358 0.00399798 0.0555971 -0.0848519 -0.0100234 0.0555971 -0.0843534 -0.0237155 0.0542971 -0.0813618 -0.00999981 0.0542971 -0.0841548 0.00399798 0.0544971 -0.0848519 0.017868 0.0542971 -0.0828403 0.0313337 0.0544971 -0.0789545 0.0439024 0.0544971 -0.0727195 0.0551433 0.0542971 -0.0643489 0.0649832 0.0542971 -0.0543942 0.0732229 0.0544971 -0.043057 0.083237 0.0544971 -0.0169469 0.083041 0.0542971 -0.016907 0.0846918 0.0542971 -0.00300749 0.0842306 0.0544971 0.011 0.0840323 0.0542971 0.0109742 0.0810805 0.0542971 0.0246566 0.0759169 0.0542971 0.0376665 0.0595741 0.0542971 0.0602775 0.0488408 0.0542971 0.0692618 0.0368619 0.0544971 0.0765371 0.0368619 0.0530971 0.0765371 0.0488408 0.0532971 0.0692618 0.0846918 0.0532971 -0.00300749 0.0848917 0.0530971 -0.0030146 0.083041 0.0532971 -0.016907 0.0793117 0.0530971 -0.0304169 0.0732229 0.0530971 -0.043057 0.0551433 0.0532971 -0.0643489 0.043799 0.0532971 -0.0725483 0.0312599 0.0532971 -0.0787686 0.0313337 0.0530971 -0.0789545 0.00398856 0.0532971 -0.0846521 -0.0100234 0.0530971 -0.0843534 -0.00999981 0.0532971 -0.0841548 -0.00999981 0.0517971 -0.0841548 0.0651366 0.0519971 -0.0545226 0.0649832 0.0517971 -0.0543942 0.0730505 0.0517971 -0.0429556 0.079125 0.0517971 -0.0303452 0.0840323 0.0517971 0.0109742 0.0812718 0.0519971 0.0247147 0.076096 0.0519971 0.0377554 0.0688444 0.0519971 0.0497663 0.0595741 0.0517971 0.0602775 0.0489561 0.0519971 0.0694253 0.0367751 0.0517971 0.0763569 0.0368619 0.0505971 0.0765371 0.0367751 0.0507971 0.0763569 0.0489561 0.0505971 0.0694253 0.0810805 0.0507971 0.0246566 0.0842306 0.0505971 0.011 0.079125 0.0507971 -0.0303452 0.0649832 0.0507971 -0.0543942 0.0551433 0.0507971 -0.0643489 0.043799 0.0507971 -0.0725483 0.0313337 0.0505971 -0.0789545 0.0179102 0.0505971 -0.0830358 0.00399798 0.0505971 -0.0848519 -0.0237715 0.0505971 -0.0815538 -0.0237155 0.0507971 -0.0813618 -0.0100234 0.0494971 -0.0843534 -0.00999981 0.0492971 -0.0841548 0.00398856 0.0492971 -0.0846521 0.0313337 0.0494971 -0.0789545 0.0439024 0.0494971 -0.0727195 0.0312599 0.0492971 -0.0787686 0.0552734 0.0494971 -0.0645008 0.043799 0.0492971 -0.0725483 0.0551433 0.0492971 -0.0643489 0.0649832 0.0492971 -0.0543942 0.0793117 0.0494971 -0.0304169 0.083237 0.0494971 -0.0169469 0.083041 0.0492971 -0.016907 0.0846918 0.0492971 -0.00300749 0.0840323 0.0492971 0.0109742 0.0842306 0.0494971 0.011 0.0812718 0.0494971 0.0247147 0.076096 0.0494971 0.0377554 0.0688444 0.0494971 0.0497663 0.0686823 0.0492971 0.0496491 0.0595741 0.0492971 0.0602775 0.0488408 0.0492971 0.0692618 0.0367751 0.0492971 0.0763569 0.0368619 0.0494971 0.0765371 0.0237621 0.0494971 0.0815613 0.0237062 0.0482971 0.0813693 0.0367751 0.0482971 0.0763569 0.0488408 0.0482971 0.0692618 0.0686823 0.0482971 0.0496491 0.0688444 0.0480971 0.0497663 0.076096 0.0480971 0.0377554 0.0842306 0.0480971 0.011 0.0846918 0.0482971 -0.00300749 0.0793117 0.0480971 -0.0304169 0.0730505 0.0482971 -0.0429556 0.0649832 0.0482971 -0.0543942 0.0312599 0.0482971 -0.0787686 0.0313337 0.0480971 -0.0789545 0.0179102 0.0480971 -0.0830358 0.00399798 0.0480971 -0.0848519 -0.0100234 0.0480971 -0.0843534 0.00398856 0.0482971 -0.0846521 -0.00999981 0.0467971 -0.0841548 0.00399798 0.0469971 -0.0848519 0.017868 0.0467971 -0.0828403 0.0312599 0.0467971 -0.0787686 0.043799 0.0467971 -0.0725483 0.0551433 0.0467971 -0.0643489 0.0649832 0.0467971 -0.0543942 0.079125 0.0467971 -0.0303452 0.083041 0.0467971 -0.016907 0.083237 0.0469971 -0.0169469 0.0842306 0.0469971 0.011 0.0812718 0.0469971 0.0247147 0.076096 0.0469971 0.0377554 0.0688444 0.0469971 0.0497663 0.0759169 0.0467971 0.0376665 0.0595741 0.0467971 0.0602775 0.0489561 0.0469971 0.0694253 0.0488408 0.0467971 0.0692618 0.0368619 0.0469971 0.0765371 0.0367751 0.0467971 0.0763569 0.0368619 0.0455971 0.0765371 0.0488408 0.0457971 0.0692618 0.0489561 0.0455971 0.0694253 0.0595741 0.0457971 0.0602775 0.0686823 0.0457971 0.0496491 0.0812718 0.0455971 0.0247147 0.0759169 0.0457971 0.0376665 0.0840323 0.0457971 0.0109742 0.0846918 0.0457971 -0.00300749 0.0848917 0.0455971 -0.0030146 0.083041 0.0457971 -0.016907 0.079125 0.0457971 -0.0303452 0.0793117 0.0455971 -0.0304169 0.0649832 0.0457971 -0.0543942 0.0651366 0.0455971 -0.0545226 0.043799 0.0457971 -0.0725483 0.0439024 0.0455971 -0.0727195 0.0313337 0.0455971 -0.0789545 0.0179102 0.0455971 -0.0830358 0.00399798 0.0455971 -0.0848519 -0.00999981 0.0457971 -0.0841548 0.0366449 0.0642971 0.0760867 0.0366449 0.0632971 0.0760867 0.0486679 0.0632971 0.0690167 0.0486679 0.0642971 0.0690167 0.0684392 0.0642971 0.0494734 0.0756481 0.0632971 0.0375332 0.0807935 0.0632971 0.0245693 0.0837348 0.0642971 0.0109353 0.084392 0.0632971 -0.00299683 0.0827471 0.0632971 -0.0168471 0.0788449 0.0642971 -0.0302378 0.0727919 0.0632971 -0.0428036 0.0727919 0.0642971 -0.0428036 0.0647532 0.0642971 -0.0542016 0.0647532 0.0632971 -0.0542016 0.054948 0.0632971 -0.0641211 0.0311492 0.0642971 -0.0784898 0.0178047 0.0632971 -0.082547 0.0178047 0.0642971 -0.082547 0.00397442 0.0642971 -0.0843525 -0.00996442 0.0642971 -0.0838569 -0.0236316 0.0642971 -0.0810738 0.0236223 0.0617971 0.0810813 0.0366449 0.0617971 0.0760867 0.0593632 0.0617971 0.0600642 0.0684392 0.0607971 0.0494734 0.0684392 0.0617971 0.0494734 0.0807935 0.0617971 0.0245693 0.0837348 0.0607971 0.0109353 0.084392 0.0617971 -0.00299683 0.0788449 0.0617971 -0.0302378 0.0727919 0.0607971 -0.0428036 0.0727919 0.0617971 -0.0428036 0.0647532 0.0607971 -0.0542016 0.054948 0.0607971 -0.0641211 0.043644 0.0607971 -0.0722915 0.0178047 0.0617971 -0.082547 0.00397442 0.0617971 -0.0843525 -0.0236316 0.0607971 -0.0810738 0.0486679 0.0582971 0.0690167 0.0486679 0.0592971 0.0690167 0.0593632 0.0582971 0.0600642 0.0684392 0.0582971 0.0494734 0.0684392 0.0592971 0.0494734 0.0807935 0.0592971 0.0245693 0.0827471 0.0582971 -0.0168471 0.0827471 0.0592971 -0.0168471 0.0788449 0.0592971 -0.0302378 0.0727919 0.0582971 -0.0428036 0.0727919 0.0592971 -0.0428036 0.0647532 0.0592971 -0.0542016 0.043644 0.0592971 -0.0722915 0.0311492 0.0582971 -0.0784898 0.00397442 0.0582971 -0.0843525 -0.00996442 0.0592971 -0.0838569 0.0366449 0.0567971 0.0760867 0.0366449 0.0557971 0.0760867 0.0486679 0.0557971 0.0690167 0.0593632 0.0557971 0.0600642 0.0593632 0.0567971 0.0600642 0.0684392 0.0557971 0.0494734 0.0756481 0.0557971 0.0375332 0.0807935 0.0567971 0.0245693 0.0837348 0.0557971 0.0109353 0.0837348 0.0567971 0.0109353 0.0827471 0.0557971 -0.0168471 0.0788449 0.0557971 -0.0302378 0.0788449 0.0567971 -0.0302378 0.0727919 0.0567971 -0.0428036 0.0647532 0.0557971 -0.0542016 0.0647532 0.0567971 -0.0542016 0.043644 0.0557971 -0.0722915 0.0311492 0.0567971 -0.0784898 0.0178047 0.0557971 -0.082547 0.00397442 0.0557971 -0.0843525 0.00397442 0.0567971 -0.0843525 -0.00996442 0.0567971 -0.0838569 -0.0236316 0.0567971 -0.0810738 0.0366449 0.0532971 0.0760867 0.0366449 0.0542971 0.0760867 0.0593632 0.0532971 0.0600642 0.0486679 0.0542971 0.0690167 0.0684392 0.0542971 0.0494734 0.0837348 0.0532971 0.0109353 0.0837348 0.0542971 0.0109353 0.084392 0.0542971 -0.00299683 0.0827471 0.0532971 -0.0168471 0.0727919 0.0532971 -0.0428036 0.0727919 0.0542971 -0.0428036 0.0647532 0.0532971 -0.0542016 0.0647532 0.0542971 -0.0542016 0.054948 0.0542971 -0.0641211 0.054948 0.0532971 -0.0641211 0.043644 0.0532971 -0.0722915 0.0311492 0.0532971 -0.0784898 0.0311492 0.0542971 -0.0784898 0.0178047 0.0532971 -0.082547 -0.00996442 0.0542971 -0.0838569 -0.0236316 0.0532971 -0.0810738 -0.0236316 0.0542971 -0.0810738 0.0236223 0.0507971 0.0810813 0.0486679 0.0507971 0.0690167 0.0593632 0.0507971 0.0600642 0.0593632 0.0517971 0.0600642 0.0684392 0.0507971 0.0494734 0.0684392 0.0517971 0.0494734 0.0756481 0.0507971 0.0375332 0.0807935 0.0507971 0.0245693 0.0807935 0.0517971 0.0245693 0.0837348 0.0507971 0.0109353 0.084392 0.0517971 -0.00299683 0.084392 0.0507971 -0.00299683 0.0827471 0.0507971 -0.0168471 0.0788449 0.0517971 -0.0302378 0.0727919 0.0507971 -0.0428036 0.054948 0.0507971 -0.0641211 0.0647532 0.0517971 -0.0542016 0.0311492 0.0507971 -0.0784898 0.0178047 0.0517971 -0.082547 0.00397442 0.0517971 -0.0843525 0.00397442 0.0507971 -0.0843525 -0.00996442 0.0517971 -0.0838569 -0.0236316 0.0507971 -0.0810738 0.0366449 0.0482971 0.0760867 0.0486679 0.0482971 0.0690167 0.0486679 0.0492971 0.0690167 0.0684392 0.0482971 0.0494734 0.0756481 0.0482971 0.0375332 0.0756481 0.0492971 0.0375332 0.0807935 0.0492971 0.0245693 0.0807935 0.0482971 0.0245693 0.0837348 0.0492971 0.0109353 0.084392 0.0482971 -0.00299683 0.0827471 0.0492971 -0.0168471 0.0788449 0.0482971 -0.0302378 0.0727919 0.0482971 -0.0428036 0.054948 0.0492971 -0.0641211 0.054948 0.0482971 -0.0641211 0.043644 0.0482971 -0.0722915 0.0311492 0.0482971 -0.0784898 0.0178047 0.0482971 -0.082547 0.0178047 0.0492971 -0.082547 0.00397442 0.0492971 -0.0843525 -0.00996442 0.0482971 -0.0838569 -0.0236316 0.0492971 -0.0810738 0.0236223 0.0467971 0.0810813 0.0366449 0.0457971 0.0760867 0.0593632 0.0457971 0.0600642 0.0593632 0.0467971 0.0600642 0.0684392 0.0467971 0.0494734 0.0807935 0.0457971 0.0245693 0.084392 0.0457971 -0.00299683 0.0788449 0.0457971 -0.0302378 0.0727919 0.0457971 -0.0428036 0.0647532 0.0457971 -0.0542016 0.0647532 0.0467971 -0.0542016 0.043644 0.0457971 -0.0722915 0.0178047 0.0457971 -0.082547 -0.00996442 0.0457971 -0.0838569 -0.0236316 0.0457971 -0.0810738 -0.0236316 0.0467971 -0.0810738 -0.00999981 0.0442971 -0.0841548 0.00399798 0.0444971 -0.0848519 0.00398856 0.0442971 -0.0846521 0.0179102 0.0444971 -0.0830358 0.043799 0.0442971 -0.0725483 0.0439024 0.0444971 -0.0727195 0.0551433 0.0442971 -0.0643489 0.079125 0.0442971 -0.0303452 0.083041 0.0442971 -0.016907 0.0812718 0.0444971 0.0247147 0.0810805 0.0442971 0.0246566 0.076096 0.0444971 0.0377554 0.0759169 0.0442971 0.0376665 0.0686823 0.0442971 0.0496491 0.0488408 0.0442971 0.0692618 0.0368619 0.0444971 0.0765371 0.0367751 0.0442971 0.0763569 0.0237062 0.0442971 0.0813693 0.0368619 0.0430971 0.0765371 0.0488408 0.0432971 0.0692618 0.0597147 0.0430971 0.0604198 0.076096 0.0430971 0.0377554 0.0686823 0.0432971 0.0496491 0.0812718 0.0430971 0.0247147 0.0810805 0.0432971 0.0246566 0.0842306 0.0430971 0.011 0.0840323 0.0432971 0.0109742 0.0848917 0.0430971 -0.0030146 0.083041 0.0432971 -0.016907 0.079125 0.0432971 -0.0303452 0.0730505 0.0432971 -0.0429556 0.0651366 0.0430971 -0.0545226 0.0649832 0.0432971 -0.0543942 0.0551433 0.0432971 -0.0643489 0.0312599 0.0432971 -0.0787686 0.0313337 0.0430971 -0.0789545 0.017868 0.0432971 -0.0828403 -0.0100234 0.0430971 -0.0843534 0.0236223 0.0432971 0.0810813 0.0366449 0.0442971 0.0760867 0.0486679 0.0442971 0.0690167 0.0593632 0.0432971 0.0600642 0.0684392 0.0432971 0.0494734 0.0684392 0.0442971 0.0494734 0.0807935 0.0432971 0.0245693 0.0807935 0.0442971 0.0245693 0.084392 0.0432971 -0.00299683 0.084392 0.0442971 -0.00299683 0.0827471 0.0432971 -0.0168471 0.0788449 0.0432971 -0.0302378 0.0788449 0.0442971 -0.0302378 0.0647532 0.0432971 -0.0542016 0.043644 0.0432971 -0.0722915 0.054948 0.0442971 -0.0641211 0.0311492 0.0442971 -0.0784898 0.0178047 0.0442971 -0.082547 0.00397442 0.0432971 -0.0843525 -0.00996442 0.0432971 -0.0838569 -0.0439645 0.0728471 -0.000726593 -0.0439176 0.0722221 -0.000565812 -0.0535183 0.0722221 0.00223193 -0.0436148 0.0715971 0.000473489 -0.0532154 0.0715971 0.00327123 -0.0433119 0.0722221 0.00151279 -0.0529126 0.0722221 0.00431053 -0.0437896 0.0717645 -0.000126552 -0.0434399 0.0717645 0.00107353 -0.0373898 0.0728471 0.021835 -0.037343 0.0722221 0.0219957 -0.0469436 0.0722221 0.0247935 -0.0468156 0.0717645 0.0252327 -0.0370401 0.0715971 0.023035 -0.0367372 0.0722221 0.0240743 -0.0464659 0.0717645 0.0264328 -0.0463379 0.0722221 0.0268721 -0.0372149 0.0717645 0.022435 -0.0368652 0.0717645 0.0236351 0.0469811 0.0728471 -0.0246252 0.0469343 0.0722221 -0.024786 0.0372056 0.0717645 -0.0224275 0.0370308 0.0715971 -0.0230275 0.0368559 0.0717645 -0.0236276 0.0464566 0.0717645 -0.0264253 0.0463285 0.0722221 -0.0268646 0.0367279 0.0722221 -0.0240668 0.036681 0.0728471 -0.0242276 0.0373336 0.0722221 -0.0219882 0.0535558 0.0728471 -0.00206365 0.0436054 0.0715971 -0.00046599 0.053381 0.0717645 -0.00266369 0.0532061 0.0715971 -0.00326373 0.0434306 0.0717645 -0.00106603 0.0433026 0.0722221 -0.00150529 0.0528564 0.0728471 -0.00446381 0.0437803 0.0717645 0.000134051 0.0439083 0.0722221 0.000573311 0.0428844 0.0728471 -0.000255859 0.0432557 0.0728471 -0.00166607 -0.0812327 0.0420471 0.0029792 -0.081411 0.0412971 0.0037077 -0.0823186 0.0412971 0.00320969 -0.0818384 0.0420471 0.000900595 -0.0828782 0.0412971 0.00128956 -0.0823802 0.0412971 0.00038193 -0.0805858 0.0420471 0.00296512 -0.0812327 0.0528471 0.0029792 -0.0817999 0.0528471 0.00266794 -0.0817999 0.0420471 0.00266794 -0.0821497 0.0528471 0.00146786 -0.0821356 0.0420471 0.00211476 -0.0821497 0.0420471 0.00146786 -0.0818384 0.0528471 0.000900595 -0.0812852 0.0528471 0.000564956 -0.0814951 0.0535971 -0.000155093 -0.0828782 0.0535971 0.00128956 -0.0821356 0.0528471 0.00211476 -0.0823186 0.0535971 0.00320969 -0.0729161 0.0412971 -0.0394118 -0.0721876 0.0420471 -0.0392335 -0.0728936 0.0412971 -0.0383768 -0.0723566 0.0412971 -0.0374917 -0.0720656 0.0420471 -0.0383284 -0.0706238 0.0420471 -0.0377363 -0.0712707 0.0420471 -0.0377222 -0.0711791 0.0528471 -0.0377034 -0.0711791 0.0420471 -0.0377034 -0.0712707 0.0528471 -0.0377222 -0.0716937 0.0420471 -0.0379147 -0.0718379 0.0420471 -0.0380334 -0.0721736 0.0528471 -0.0385866 -0.0721736 0.0420471 -0.0385866 -0.0722213 0.0420471 -0.0388624 -0.0721876 0.0528471 -0.0392335 -0.0721298 0.0528471 -0.0394112 -0.0721298 0.0420471 -0.0394112 -0.0718764 0.0528471 -0.0398008 -0.0718764 0.0420471 -0.0398008 -0.0718093 0.0420471 -0.0398658 -0.071449 0.0535971 -0.0369937 -0.0716937 0.0528471 -0.0379147 -0.0718379 0.0528471 -0.0380334 -0.0720656 0.0528471 -0.0383284 -0.0728936 0.0535971 -0.0383768 -0.0722213 0.0528471 -0.0388624 -0.0713232 0.0528471 -0.0401364 -0.0724181 0.0535971 -0.0403195 -0.0718093 0.0528471 -0.0398658 -0.0433785 0.0412971 -0.0677591 -0.0431955 0.0420471 -0.068854 -0.0439155 0.0412971 -0.0686442 -0.0439381 0.0412971 -0.0696793 -0.0434401 0.0412971 -0.0705869 -0.0422926 0.0420471 -0.0679896 -0.0428598 0.0420471 -0.0683009 -0.0432096 0.0420471 -0.0695009 -0.0428983 0.0528471 -0.0700682 -0.0428983 0.0420471 -0.0700682 -0.0423451 0.0528471 -0.0704039 -0.0434401 0.0535971 -0.0705869 -0.0432096 0.0528471 -0.0695009 -0.0431955 0.0528471 -0.068854 -0.0439155 0.0535971 -0.0686442 -0.0428598 0.0528471 -0.0683009 -0.0422926 0.0528471 -0.0679896 -0.0433785 0.0535971 -0.0677591 -0.0827413 0.0672971 3.61523e-05 -0.0833638 0.0672971 0.00117068 -0.0836552 0.0675971 0.00109936 -0.0836237 0.0675971 0.00254841 -0.0826644 0.0672971 0.00357085 -0.0815299 0.0672971 0.00419336 -0.0816012 0.0675971 0.00448476 -0.0802361 0.0672971 0.0041652 -0.0816349 0.0535971 -0.000635126 -0.0827413 0.0535971 3.61523e-05 -0.0833638 0.0535971 0.00117068 -0.0833357 0.0535971 0.00246447 -0.0833357 0.0672971 0.00246447 -0.0826644 0.0535971 0.00357085 -0.0717568 0.0675971 -0.0416245 -0.0728456 0.0675971 -0.0410184 -0.0732861 0.0672971 -0.039886 -0.0735636 0.0675971 -0.0399999 -0.0734691 0.0672971 -0.0387885 -0.0737686 0.0675971 -0.0387708 -0.0713847 0.0672971 -0.0364704 -0.0725868 0.0675971 -0.0366478 -0.070274 0.0672971 -0.0365362 -0.071434 0.0675971 -0.0361745 -0.0716729 0.0672971 -0.0413365 -0.0732861 0.0535971 -0.039886 -0.072645 0.0672971 -0.0407953 -0.0734691 0.0535971 -0.0387885 -0.0731578 0.0672971 -0.0377204 -0.0724139 0.0672971 -0.036893 -0.041296 0.0672971 -0.0668036 -0.0424066 0.0672971 -0.0667378 -0.042456 0.0675971 -0.0664419 -0.0425898 0.0672971 -0.0667754 -0.0436087 0.0675971 -0.0669153 -0.0444419 0.0675971 -0.0678419 -0.0437243 0.0672971 -0.067398 -0.0445855 0.0675971 -0.0702674 -0.0444237 0.0672971 -0.0697981 -0.0438676 0.0675971 -0.0712858 -0.044308 0.0672971 -0.0701534 -0.043667 0.0672971 -0.0710628 -0.0438012 0.0672971 -0.0709326 -0.0438012 0.0535971 -0.0709326 -0.044491 0.0672971 -0.069056 -0.0443956 0.0672971 -0.0685043 -0.0441798 0.0672971 -0.0679878 -0.0437243 0.0535971 -0.067398 -0.0434358 0.0672971 -0.0671604 -0.0425898 0.0535971 -0.0667754 -0.0824566 0.0672971 -0.00709235 -0.0815684 0.0675971 -0.00792153 -0.0826572 0.0675971 -0.00731543 -0.0830977 0.0672971 -0.00618298 -0.0832807 0.0672971 -0.00508553 -0.0829694 0.0672971 -0.00401736 -0.0832316 0.0675971 -0.00387144 -0.0823984 0.0675971 -0.00294483 -0.0733728 0.0672971 -0.0302594 -0.0746666 0.0672971 -0.0302313 -0.0758011 0.0672971 -0.0308538 -0.0765187 0.0675971 -0.0312977 -0.0768674 0.0675971 -0.0324941 -0.0764724 0.0672971 -0.0319602 -0.0765679 0.0672971 -0.0325118 -0.0763849 0.0672971 -0.0336092 -0.0766624 0.0675971 -0.0337232 -0.0747717 0.0672971 -0.0350598 -0.0757438 0.0672971 -0.0345186 -0.0759444 0.0675971 -0.0347417 -0.0758781 0.0672971 -0.0343885 -0.0681274 0.0675971 -0.0476101 -0.0699341 0.0675971 -0.0459855 -0.0698396 0.0672971 -0.0447741 -0.0695284 0.0672971 -0.0437059 -0.0687844 0.0672971 -0.0428786 -0.0677552 0.0672971 -0.042456 -0.0689573 0.0675971 -0.0426334 -0.0678046 0.0675971 -0.0421601 -0.0485168 0.0672971 -0.0677175 -0.0486008 0.0675971 -0.0680055 -0.0495463 0.0672971 -0.0635115 -0.0484118 0.0672971 -0.062889 -0.047034 0.0675971 -0.0626292 -0.0825909 0.0415971 -0.00696223 -0.0835048 0.0412971 -0.00589902 -0.0830977 0.0415971 -0.00618298 -0.0832134 0.0415971 -0.0058277 -0.0832807 0.0415971 -0.00508553 -0.0834733 0.0412971 -0.00444998 -0.0831852 0.0415971 -0.00453391 -0.0829694 0.0415971 -0.00401736 -0.0827214 0.0412971 -0.00321084 -0.0800017 0.0412971 -0.00254516 -0.0822255 0.0415971 -0.00319003 -0.0811963 0.0672971 -0.0027674 -0.0813794 0.0415971 -0.00280502 -0.082514 0.0415971 -0.00342753 -0.0822255 0.0672971 -0.00319003 -0.0814845 0.0415971 -0.00763351 -0.0764724 0.0415971 -0.0319602 -0.0767604 0.0412971 -0.0318762 -0.076792 0.0412971 -0.0333253 -0.0748556 0.0412971 -0.0353478 -0.0744835 0.0672971 -0.0301937 -0.0755127 0.0672971 -0.0306163 -0.0746666 0.0415971 -0.0302313 -0.0758011 0.0415971 -0.0308538 -0.0762566 0.0672971 -0.0314436 -0.0765006 0.0415971 -0.033254 -0.0765006 0.0672971 -0.033254 -0.0758781 0.0415971 -0.0343885 -0.0747717 0.0415971 -0.0350598 -0.0665606 0.0412971 -0.0422337 -0.0678046 0.0412971 -0.0421601 -0.0697905 0.0412971 -0.04356 -0.0698396 0.0415971 -0.0447741 -0.0701391 0.0412971 -0.0447564 -0.0699341 0.0412971 -0.0459855 -0.0692162 0.0412971 -0.047004 -0.0677552 0.0415971 -0.042456 -0.0687844 0.0415971 -0.0428786 -0.0695284 0.0415971 -0.0437059 -0.0696566 0.0415971 -0.0458716 -0.0696566 0.0672971 -0.0458716 -0.0690156 0.0672971 -0.0467809 -0.0690156 0.0415971 -0.0467809 -0.0495463 0.0415971 -0.0635115 -0.0497538 0.0412971 -0.0632948 -0.0505371 0.0412971 -0.065983 -0.0502457 0.0415971 -0.0659117 -0.0485168 0.0415971 -0.0677175 -0.047118 0.0415971 -0.0629172 -0.0484118 0.0415971 -0.062889 -0.0502176 0.0672971 -0.0646179 -0.0502176 0.0415971 -0.0646179 -0.0502457 0.0672971 -0.0659117 -0.0496232 0.0672971 -0.0670462 -0.0496232 0.0415971 -0.0670462 0.0695526 0.0420471 -0.0407869 0.0687274 0.0412971 -0.0400443 0.0683384 0.0420471 -0.0410841 0.0678197 0.0412971 -0.0405423 0.0672827 0.0412971 -0.0414274 0.0677582 0.0412971 -0.0433701 0.0689057 0.0420471 -0.0407728 0.0680028 0.0420471 -0.0416373 0.0679887 0.0420471 -0.0422842 0.0682999 0.0528471 -0.0428514 0.0682999 0.0420471 -0.0428514 0.0679887 0.0528471 -0.0422842 0.0680028 0.0528471 -0.0416373 0.0683384 0.0528471 -0.0410841 0.0689057 0.0528471 -0.0407728 0.0687274 0.0535971 -0.0400443 0.0386383 0.0420471 -0.0697509 0.0370153 0.0412971 -0.0704055 0.0380325 0.0420471 -0.0718295 0.0386383 0.0528471 -0.0697509 0.0382152 0.0528471 -0.0699434 0.038071 0.0420471 -0.0700622 0.038071 0.0528471 -0.0700622 0.0378433 0.0528471 -0.0703571 0.0377354 0.0420471 -0.0706153 0.0377791 0.0528471 -0.0714399 0.0377213 0.0420471 -0.0712622 0.0385857 0.0420471 -0.0721651 0.0392851 0.0528471 -0.069765 0.0387298 0.0528471 -0.0697321 0.0386065 0.0535971 -0.0689923 0.0377831 0.0535971 -0.0693304 0.0377354 0.0528471 -0.0706153 0.0369389 0.0535971 -0.0708468 0.0376876 0.0528471 -0.0708911 0.0377213 0.0528471 -0.0712622 0.0370853 0.0535971 -0.0717248 0.0385857 0.0528471 -0.0721651 0.0383759 0.0535971 -0.0728852 0.0375982 0.0535971 -0.0724523 0.0380997 0.0528471 -0.0718946 0.0380325 0.0528471 -0.0718295 -0.00197157 0.0420471 -0.0796941 -0.00120641 0.0412971 -0.079007 -0.00248617 0.0420471 -0.0799054 -0.00285813 0.0420471 -0.0803191 -0.0029183 0.0412971 -0.0792924 -0.00376246 0.0412971 -0.0808088 -0.00260174 0.0420471 -0.0818566 -0.0023255 0.0412971 -0.0828472 -0.00141624 0.0528471 -0.079727 -0.00296604 0.0528471 -0.0805774 -0.00301377 0.0420471 -0.0808532 -0.00292226 0.0420471 -0.0814019 -0.00206313 0.0528471 -0.0797129 -0.00248617 0.0528471 -0.0799054 -0.0026304 0.0528471 -0.0800242 -0.00285813 0.0528471 -0.0803191 -0.00301377 0.0528471 -0.0808532 -0.00370861 0.0535971 -0.0814026 -0.00266886 0.0528471 -0.0817915 -0.0032106 0.0535971 -0.0823102 -0.00292226 0.0528471 -0.0814019 -0.00298012 0.0528471 -0.0812243 0.067397 0.0672971 -0.0437159 0.0671803 0.0675971 -0.0439233 0.0665147 0.0675971 -0.0412036 0.067474 0.0672971 -0.0401812 0.0672665 0.0675971 -0.0399645 0.0699023 0.0672971 -0.0395868 0.0685034 0.0672971 -0.0443872 0.0667745 0.0535971 -0.0425813 0.0667745 0.0672971 -0.0425813 0.0668027 0.0672971 -0.0412876 0.0686085 0.0535971 -0.0395587 0.0686085 0.0672971 -0.0395587 0.0371296 0.0672971 -0.0726939 0.0369129 0.0675971 -0.0729014 0.0365071 0.0672971 -0.0715594 0.0365353 0.0672971 -0.0702656 0.0372065 0.0672971 -0.0691592 0.0382698 0.0675971 -0.0682453 0.0396349 0.0672971 -0.0685649 0.0371296 0.0535971 -0.0726939 0.0365071 0.0535971 -0.0715594 0.0372065 0.0535971 -0.0691592 0.0383411 0.0535971 -0.0685367 0.0383411 0.0672971 -0.0685367 -0.00378846 0.0675971 -0.0828634 -0.00448568 0.0675971 -0.0815928 -0.00416612 0.0672971 -0.0802277 -0.00349484 0.0672971 -0.0791213 -0.00445414 0.0675971 -0.0801437 -0.00243163 0.0675971 -0.0782074 -0.000982588 0.0675971 -0.0782389 -0.00357177 0.0672971 -0.082656 -0.00419428 0.0535971 -0.0815214 -0.00419428 0.0672971 -0.0815214 -0.00416612 0.0535971 -0.0802277 -0.00349484 0.0535971 -0.0791213 -0.00236031 0.0535971 -0.0784988 -0.00236031 0.0672971 -0.0784988 0.064617 0.0672971 -0.0502092 0.0634443 0.0675971 -0.0498911 0.0636449 0.0672971 -0.049668 0.0630038 0.0672971 -0.0487586 0.0625213 0.0675971 -0.0476434 0.0628208 0.0672971 -0.0476612 0.0631321 0.0672971 -0.046593 0.06287 0.0675971 -0.0464471 0.0637031 0.0675971 -0.0455205 0.0649052 0.0672971 -0.045343 0.0660159 0.0672971 -0.0454088 0.0443266 0.0672971 -0.0649073 0.0427366 0.0672971 -0.0661196 0.0422328 0.0675971 -0.0665522 0.0422013 0.0675971 -0.0680013 0.0431152 0.0672971 -0.0690645 0.0428985 0.0675971 -0.0692719 0.0426084 0.0672971 -0.0682852 0.0424254 0.0672971 -0.0671878 0.031993 0.0675971 -0.0713441 0.0320643 0.0672971 -0.0716355 0.0307223 0.0675971 -0.0720413 0.0309298 0.0672971 -0.072258 0.0304743 0.0672971 -0.0728479 0.0301631 0.0672971 -0.073916 0.029939 0.0675971 -0.0747295 0.0302304 0.0672971 -0.0746582 0.0309871 0.0672971 -0.0759228 0.0306362 0.0675971 -0.0760002 0.0303461 0.0672971 -0.0750135 0.00444906 0.0675971 -0.0834648 0.00280411 0.0672971 -0.081371 0.00350354 0.0672971 -0.0789709 0.00254424 0.0675971 -0.0799933 0.00329608 0.0675971 -0.0787542 0.00463807 0.0672971 -0.0783483 0.0660998 0.0412971 -0.0451208 0.063876 0.0415971 -0.0457657 0.06287 0.0412971 -0.0464471 0.0625213 0.0412971 -0.0476434 0.0627263 0.0412971 -0.0488726 0.0649052 0.0415971 -0.045343 0.063876 0.0672971 -0.0457657 0.0631321 0.0415971 -0.046593 0.0628208 0.0415971 -0.0476612 0.0630038 0.0415971 -0.0487586 0.0636449 0.0415971 -0.049668 0.0457044 0.0412971 -0.0646474 0.0445098 0.0415971 -0.0648696 0.0444604 0.0412971 -0.0645737 0.0434806 0.0415971 -0.0652923 0.0424745 0.0412971 -0.0659737 0.0423309 0.0412971 -0.0683992 0.0430488 0.0412971 -0.0694177 0.0434806 0.0672971 -0.0652923 0.0431921 0.0672971 -0.0655298 0.0427366 0.0415971 -0.0661196 0.0425208 0.0672971 -0.0666362 0.0424254 0.0415971 -0.0671878 0.0424927 0.0672971 -0.0679299 0.0426084 0.0415971 -0.0682852 0.0432494 0.0415971 -0.0691946 0.0308529 0.0415971 -0.0757927 0.0303461 0.0415971 -0.0750135 0.0302304 0.0415971 -0.0746582 0.0299705 0.0412971 -0.0732805 0.0301631 0.0415971 -0.073916 0.0302585 0.0415971 -0.0733644 0.0309298 0.0415971 -0.072258 0.0320643 0.0415971 -0.0716355 0.0322475 0.0672971 -0.0715979 0.0322475 0.0415971 -0.0715979 0.0312183 0.0672971 -0.0720205 0.0312183 0.0415971 -0.0720205 0.0302585 0.0672971 -0.0733644 0.0304743 0.0415971 -0.0728479 0.0308529 0.0672971 -0.0757927 0.0309871 0.0415971 -0.0759228 0.00350354 0.0415971 -0.0789709 0.00329608 0.0412971 -0.0787542 0.00280411 0.0415971 -0.081371 0.00342662 0.0415971 -0.0825056 0.00320992 0.0412971 -0.082713 0.00593186 0.0415971 -0.0783765 0.00463807 0.0415971 -0.0783483 0.00283226 0.0672971 -0.0800772 0.00283226 0.0415971 -0.0800772 0.00342662 0.0672971 -0.0825056 -0.0706568 0.0412971 0.0406114 -0.070048 0.0420471 0.041065 -0.0704263 0.0420471 0.0416973 -0.0711323 0.0412971 0.042554 -0.0703044 0.0420471 0.0426025 -0.0705953 0.0412971 0.0434391 -0.0699324 0.0420471 0.0430161 -0.0696877 0.0412971 0.0439371 -0.0694178 0.0420471 0.0432275 -0.0695094 0.0528471 0.0432086 -0.0699324 0.0528471 0.0430161 -0.0695094 0.0420471 0.0432086 -0.0700766 0.0420471 0.0428974 -0.0703044 0.0528471 0.0426025 -0.0704123 0.0528471 0.0423442 -0.0704123 0.0420471 0.0423442 -0.0704263 0.0528471 0.0416973 -0.07046 0.0420471 0.0420684 -0.0703685 0.0420471 0.0415197 -0.0701151 0.0528471 0.04113 -0.070048 0.0528471 0.041065 -0.0701151 0.0420471 0.04113 -0.0696877 0.0535971 0.0439371 -0.0694178 0.0528471 0.0432275 -0.0700766 0.0528471 0.0428974 -0.0711323 0.0535971 0.042554 -0.0711548 0.0535971 0.041519 -0.07046 0.0528471 0.0420684 -0.0703685 0.0528471 0.0415197 -0.0706568 0.0535971 0.0406114 -0.0391504 0.0420471 0.0722055 -0.039665 0.0420471 0.0719942 -0.0401926 0.0420471 0.0710465 -0.0401011 0.0420471 0.0704977 -0.0397805 0.0420471 0.0700431 -0.038595 0.0528471 0.0721726 -0.0400369 0.0420471 0.0715805 -0.0401011 0.0528471 0.0704977 -0.0397805 0.0528471 0.0700431 -0.0395043 0.0535971 0.0690524 -0.040282 0.0535971 0.0694854 -0.0407949 0.0535971 0.0702128 -0.0409413 0.0535971 0.0710908 -0.0401926 0.0528471 0.0710465 -0.0400369 0.0528471 0.0715805 -0.0400971 0.0535971 0.0726072 -0.039665 0.0528471 0.0719942 -0.0392737 0.0535971 0.0729453 -0.0391504 0.0528471 0.0722055 0.00155101 0.0420471 0.0821676 0.00231617 0.0412971 0.0828547 0.000604275 0.0412971 0.0825692 0.000664448 0.0420471 0.0815426 -9.34702e-05 0.0412971 0.0801749 0.0014069 0.0420471 0.0797345 0.00145945 0.0528471 0.0821487 0.00103641 0.0528471 0.0819562 0.00103641 0.0420471 0.0819562 0.000508809 0.0420471 0.0810085 0.000600314 0.0420471 0.0804598 0.000600314 0.0528471 0.0804598 0.000920841 0.0420471 0.0800051 0.000373513 0.0535971 0.0823792 0.000892179 0.0528471 0.0818375 0.000664448 0.0528471 0.0815426 0.00055654 0.0528471 0.0812843 -0.00016351 0.0535971 0.0814941 0.000508809 0.0528471 0.0810085 -0.000186035 0.0535971 0.0804591 0.000853716 0.0528471 0.0800701 0.000542461 0.0528471 0.0806374 -0.071018 0.0672971 0.0402656 -0.0712347 0.0675971 0.0400581 -0.0716405 0.0672971 0.0414001 -0.0716124 0.0672971 0.0426939 -0.0719319 0.0675971 0.0413288 -0.0719004 0.0675971 0.0427779 -0.0709411 0.0672971 0.0438003 -0.0716405 0.0535971 0.0414001 -0.0698065 0.0535971 0.0444228 -0.0698065 0.0672971 0.0444228 -0.0397281 0.0675971 0.0682844 -0.0407506 0.0672971 0.0692437 -0.0413449 0.0672971 0.071672 -0.041633 0.0675971 0.0717559 -0.0408811 0.0675971 0.0729951 -0.0396442 0.0672971 0.0685724 -0.0413731 0.0535971 0.0703782 -0.0413731 0.0672971 0.0703782 -0.0413449 0.0535971 0.071672 -0.0406737 0.0535971 0.0727784 -0.0406737 0.0672971 0.0727784 -0.0395391 0.0672971 0.0734009 0.00116227 0.0672971 0.0833629 0.00109095 0.0675971 0.0836543 -0.000931563 0.0675971 0.081718 2.7736e-05 0.0672971 0.0827404 -0.000427727 0.0672971 0.0821506 0.000973254 0.0675971 0.0782464 -4.91892e-05 0.0672971 0.0792057 -0.000555993 0.0672971 0.0799849 -0.000963098 0.0675971 0.0802689 -0.000671699 0.0672971 0.0803402 -0.000739005 0.0672971 0.0810824 -0.000643543 0.0672971 0.081634 -0.000739005 0.0535971 0.0810824 0.000316188 0.0535971 0.0829779 0.000316188 0.0672971 0.0829779 0.0013454 0.0535971 0.0834005 -0.0673483 0.0675971 0.0458801 -0.0677541 0.0672971 0.0472221 -0.0680455 0.0675971 0.0471508 -0.0670546 0.0672971 0.0496223 -0.0672621 0.0675971 0.049839 -0.0645424 0.0675971 0.0505047 -0.0465436 0.0675971 0.0696316 -0.0466592 0.0672971 0.0691489 -0.0473305 0.0672971 0.0680425 -0.0477254 0.0675971 0.0675086 -0.047426 0.0672971 0.0674909 -0.0475205 0.0675971 0.0662795 -0.0472429 0.0672971 0.0663935 -0.0457137 0.0675971 0.0646549 -0.0345402 0.0675971 0.0719893 -0.0352581 0.0675971 0.0730077 -0.0354631 0.0675971 0.0742369 -0.0341085 0.0672971 0.0761147 -0.0342813 0.0675971 0.0763599 -0.0319686 0.0672971 0.0764715 -0.0059412 0.0672971 0.078384 -0.00711391 0.0675971 0.0787021 -0.00773739 0.0672971 0.080932 -0.00803686 0.0675971 0.0809497 -0.00742611 0.0672971 0.0820002 -0.00768823 0.0675971 0.0821461 -0.0066822 0.0672971 0.0828275 -0.00454233 0.0672971 0.0831843 -0.0659201 0.0415971 0.0502448 -0.0670546 0.0415971 0.0496223 -0.0672621 0.0412971 0.049839 -0.0680139 0.0412971 0.0485999 -0.0660252 0.0415971 0.0454163 -0.0646263 0.0415971 0.0502167 -0.0659201 0.0672971 0.0502448 -0.0677259 0.0672971 0.0485159 -0.0677259 0.0415971 0.0485159 -0.0677541 0.0415971 0.0472221 -0.0671316 0.0672971 0.0460876 -0.0671316 0.0415971 0.0460876 -0.0660252 0.0672971 0.0454163 -0.0442309 0.0415971 0.0697433 -0.0476501 0.0412971 0.0666774 -0.0453416 0.0672971 0.069809 -0.0455247 0.0672971 0.0697714 -0.0455247 0.0415971 0.0697714 -0.0463708 0.0672971 0.0693864 -0.0471147 0.0672971 0.0685591 -0.0466592 0.0415971 0.0691489 -0.0473305 0.0415971 0.0680425 -0.0473587 0.0415971 0.0667487 -0.0473587 0.0672971 0.0667487 -0.0467361 0.0415971 0.0656142 -0.0467361 0.0672971 0.0656142 -0.0466019 0.0672971 0.0654841 -0.0456298 0.0415971 0.0649429 -0.0318847 0.0412971 0.0767595 -0.0331286 0.0412971 0.0768332 -0.0341085 0.0415971 0.0761147 -0.0351636 0.0415971 0.0742192 -0.0349806 0.0415971 0.0731217 -0.0352581 0.0412971 0.0730077 -0.0345402 0.0412971 0.0719893 -0.0330792 0.0672971 0.0765373 -0.0330792 0.0415971 0.0765373 -0.0348524 0.0672971 0.0752873 -0.0348524 0.0415971 0.0752873 -0.0351636 0.0672971 0.0742192 -0.0349806 0.0672971 0.0731217 -0.0343396 0.0672971 0.0722123 -0.0343396 0.0415971 0.0722123 -0.0333675 0.0415971 0.0716712 -0.00726427 0.0412971 0.0788478 -0.00796148 0.0412971 0.0801185 -0.00755438 0.0415971 0.0798345 -0.00767008 0.0415971 0.0801898 -0.00764193 0.0415971 0.0814836 -0.00583612 0.0415971 0.0832125 -0.00590744 0.0412971 0.0835039 -0.00717811 0.0412971 0.0828067 -0.0066822 0.0415971 0.0828275 -0.00742611 0.0415971 0.0820002 -0.00565298 0.0672971 0.0832501 -0.00697065 0.0415971 0.08259 -0.00773739 0.0415971 0.080932 -0.00755438 0.0672971 0.0798345 -0.00704757 0.0415971 0.0790553 -0.00691332 0.0672971 0.0789252 0.080629 0.0420471 -0.000543378 0.0804507 0.0412971 0.000185118 0.0797261 0.0420471 -0.00140782 0.079712 0.0420471 -0.00205472 0.0800233 0.0420471 -0.00262198 0.0805764 0.0420471 -0.00295762 0.0812759 0.0420471 -0.000557457 0.0800617 0.0420471 -0.000854634 0.0797261 0.0528471 -0.00140782 0.0800233 0.0528471 -0.00262198 0.0805764 0.0528471 -0.00295762 0.0803666 0.0535971 -0.00367767 0.079712 0.0528471 -0.00205472 0.0794815 0.0535971 -0.00314065 0.0789835 0.0535971 -0.00223302 0.0800617 0.0528471 -0.000854634 0.079006 0.0535971 -0.00119799 0.0795431 0.0535971 -0.00031289 0.080629 0.0528471 -0.000543378 0.0804507 0.0535971 0.000185118 0.0814857 0.0535971 0.000162593 0.0701284 0.0420471 0.0380143 0.0697163 0.0420471 0.0390178 0.069872 0.0420471 0.0395518 0.0702439 0.0420471 0.0399655 0.070667 0.0420471 0.040158 0.0707585 0.0528471 0.0401768 0.0707585 0.0420471 0.0401768 0.0700997 0.0528471 0.0398468 0.0700997 0.0420471 0.0398468 0.069872 0.0528471 0.0395518 0.0697641 0.0528471 0.0392936 0.0697641 0.0420471 0.0392936 0.0697163 0.0528471 0.0390178 0.06975 0.0528471 0.0386467 0.06975 0.0420471 0.0386467 0.0698078 0.0420471 0.038469 0.0700612 0.0528471 0.0380794 0.0700612 0.0420471 0.0380794 0.0701284 0.0528471 0.0380143 0.070667 0.0528471 0.040158 0.0702439 0.0528471 0.0399655 0.069581 0.0535971 0.0403885 0.069044 0.0535971 0.0395034 0.0695195 0.0535971 0.0375607 0.0698078 0.0528471 0.038469 0.0411503 0.0420471 0.0682818 0.0410832 0.0420471 0.0683468 0.0408298 0.0420471 0.0687364 0.0407719 0.0420471 0.0689141 0.040786 0.0420471 0.069561 0.0408337 0.0412971 0.0708459 0.0408939 0.0420471 0.0698193 0.0411216 0.0420471 0.0701142 0.0417805 0.0420471 0.0704442 0.0425456 0.0412971 0.0711314 0.0416889 0.0420471 0.0704254 0.0412659 0.0420471 0.0702329 0.0416364 0.0528471 0.0680112 0.0411503 0.0528471 0.0682818 0.0410832 0.0528471 0.0683468 0.0407719 0.0528471 0.0689141 0.0407383 0.0420471 0.0692852 0.0407383 0.0528471 0.0692852 0.040786 0.0528471 0.069561 0.0408939 0.0528471 0.0698193 0.0411216 0.0528471 0.0701142 0.0417805 0.0528471 0.0704442 0.0416571 0.0535971 0.071184 0.0416889 0.0528471 0.0704254 0.0412659 0.0528471 0.0702329 0.0402386 0.0535971 0.0701841 0.0408298 0.0528471 0.0687364 0.0414265 0.0535971 0.0672911 0.0817095 0.0675971 0.000930645 0.0804656 0.0675971 0.00100432 0.0805149 0.0672971 0.000708408 0.0794857 0.0672971 0.00028578 0.0793129 0.0675971 0.000530978 0.0787418 0.0672971 -0.000541553 0.0784797 0.0675971 -0.000395635 0.078526 0.0672971 -0.0010581 0.0784305 0.0672971 -0.00160973 0.0781311 0.0675971 -0.00159199 0.078336 0.0675971 -0.00282113 0.0792546 0.0672971 -0.00361654 0.0791204 0.0672971 -0.00348642 0.0802267 0.0672971 -0.0041577 0.0802267 0.0535971 -0.0041577 0.0791204 0.0535971 -0.00348642 0.0786136 0.0672971 -0.00270718 0.0784978 0.0672971 -0.00235189 0.0784978 0.0535971 -0.00235189 0.0791973 0.0672971 4.8272e-05 0.0816256 0.0672971 0.000642626 0.0803318 0.0672971 0.000670782 0.0803318 0.0535971 0.000670782 0.0701808 0.0675971 0.0362557 0.0689416 0.0675971 0.0370075 0.0685358 0.0672971 0.0383495 0.0682444 0.0675971 0.0382782 0.0692353 0.0672971 0.0407497 0.0690278 0.0675971 0.0409664 0.0703698 0.0672971 0.0413722 0.0702647 0.0672971 0.0365437 0.0691583 0.0672971 0.037215 0.068564 0.0672971 0.0396433 0.0716636 0.0672971 0.041344 0.0400497 0.0675971 0.0712338 0.0395859 0.0672971 0.0699107 0.0394904 0.0672971 0.0693591 0.0401803 0.0672971 0.0674824 0.0399636 0.0675971 0.0672749 0.0403145 0.0535971 0.0673523 0.0396735 0.0672971 0.0682616 0.0395578 0.0672971 0.0686169 0.0394904 0.0535971 0.0693591 0.0398017 0.0535971 0.0704273 0.0398017 0.0672971 0.0704273 0.0402572 0.0672971 0.0710171 0.0405456 0.0672971 0.0712546 0.0413917 0.0672971 0.0716396 0.0415749 0.0535971 0.0716772 0.0426855 0.0672971 0.0716114 0.0426855 0.0535971 0.0716114 0.0765208 0.0665971 -0.023785 0.0765208 0.0675971 -0.023785 0.07611 0.0665971 -0.0230362 0.0761286 0.0665971 -0.0221823 0.0761286 0.0675971 -0.0221823 0.0765716 0.0665971 -0.0214521 0.0773204 0.0665971 -0.0210413 0.0781743 0.0665971 -0.0210599 0.0774325 0.0665971 0.0181079 0.0774325 0.0675971 0.0181079 0.0770403 0.0675971 0.0197105 0.0774833 0.0675971 0.0204408 0.079086 0.0665971 0.020833 0.0568834 0.0665971 0.0564467 0.0568648 0.0675971 0.0555928 0.0568834 0.0675971 0.0564467 0.0573264 0.0665971 0.0571769 0.0580752 0.0665971 0.0575878 0.0589291 0.0665971 0.0575692 0.0175934 0.0665971 -0.0785277 0.0177142 0.0675971 -0.079252 0.0175934 0.0675971 -0.0785277 0.0177988 0.0675971 -0.0778227 0.0189691 0.0675971 -0.0769978 0.0547848 0.0665971 -0.0596095 0.054374 0.0665971 -0.0588607 0.0548356 0.0665971 -0.0572766 0.0543926 0.0675971 -0.0580068 0.0555844 0.0675971 -0.0568657 0.0564383 0.0665971 -0.0568843 -0.0595801 0.0665971 -0.0572045 -0.0595801 0.0675971 -0.0572045 -0.0600032 0.0665971 -0.0566043 -0.0601239 0.0665971 -0.05588 -0.0601239 0.0675971 -0.05588 -0.0599185 0.0665971 -0.055175 -0.0594275 0.0665971 -0.054629 -0.0599185 0.0675971 -0.055175 -0.0587482 0.0675971 -0.05435 -0.0797369 0.0665971 -0.0204684 -0.0797369 0.0675971 -0.0204684 -0.08016 0.0665971 -0.0198682 -0.08016 0.0675971 -0.0198682 -0.0802808 0.0665971 -0.0191439 -0.0795844 0.0675971 -0.0178928 -0.0795844 0.0665971 -0.0178928 -0.0781721 0.0675971 -0.0176573 -0.0781836 0.0675971 0.0210674 -0.0793247 0.0665971 0.0222592 -0.0793061 0.0665971 0.0231131 -0.0788631 0.0675971 0.0238433 -0.0788631 0.0665971 0.0238433 -0.0781143 0.0675971 0.0242542 -0.0564476 0.0675971 0.0568918 -0.0571778 0.0665971 0.0573348 -0.0575887 0.0665971 0.0580836 -0.0571778 0.0675971 0.0573348 -0.0575887 0.0675971 0.0580836 -0.0575701 0.0675971 0.0589375 -0.0571271 0.0665971 0.0596677 -0.0563783 0.0665971 0.0600786 -0.0563783 0.0675971 0.0600786 -0.0197115 0.0665971 0.0770487 -0.0204417 0.0675971 0.0774917 -0.0208525 0.0675971 0.0782405 -0.0208525 0.0665971 0.0782405 -0.0208339 0.0665971 0.0790944 -0.0208339 0.0675971 0.0790944 -0.0203909 0.0675971 0.0798246 -0.0203909 0.0665971 0.0798246 -0.0187882 0.0665971 0.0802169 -0.0187882 0.0675971 0.0802169 0.0784631 0.0672971 0.00429121 0.0789036 0.0675971 0.00315876 0.0781856 0.0675971 0.00417725 0.0779806 0.0675971 0.00540639 0.0793353 0.0672971 0.00728416 0.0803152 0.0675971 0.00800271 0.0803645 0.0672971 0.00770679 0.0733635 0.0672971 0.0302669 0.0722571 0.0672971 0.0309382 0.0720404 0.0675971 0.0307308 0.0716346 0.0672971 0.0320727 0.072334 0.0672971 0.0344729 0.0721266 0.0675971 0.0346896 0.066669 0.0675971 0.0476491 0.0669235 0.0672971 0.0473954 0.0653983 0.0675971 0.0469519 0.0646465 0.0675971 0.0457128 0.0648391 0.0672971 0.0450772 0.064615 0.0675971 0.0442637 0.0650221 0.0672971 0.0439798 0.0653122 0.0675971 0.0429931 0.0656631 0.0672971 0.0430704 0.0665513 0.0675971 0.0422412 0.0485914 0.0675971 0.068013 0.0485075 0.0672971 0.067725 0.0472137 0.0672971 0.0677532 0.0463676 0.0672971 0.0673682 0.0458717 0.0675971 0.0673473 0.0451199 0.0675971 0.0661082 0.0460023 0.0672971 0.063596 0.0457856 0.0675971 0.0633885 0.0453798 0.0672971 0.0647305 0.0793353 0.0415971 0.00728416 0.0785914 0.0415971 0.00645683 0.0782801 0.0415971 0.00538866 0.0784631 0.0415971 0.00429121 0.0779806 0.0412971 0.00540639 0.0781856 0.0412971 0.00417725 0.0791042 0.0415971 0.00338184 0.0814752 0.0415971 0.00764101 0.0803645 0.0415971 0.00770679 0.0785914 0.0672971 0.00645683 0.0782801 0.0672971 0.00538866 0.0791042 0.0672971 0.00338184 0.0734686 0.0415971 0.0350954 0.0748463 0.0412971 0.0353553 0.0721266 0.0412971 0.0346896 0.0713747 0.0412971 0.0334505 0.0734686 0.0672971 0.0350954 0.0747624 0.0415971 0.0350673 0.072334 0.0415971 0.0344729 0.0716628 0.0672971 0.0333665 0.0716628 0.0415971 0.0333665 0.0716346 0.0415971 0.0320727 0.0722571 0.0415971 0.0309382 0.0733635 0.0415971 0.0302669 0.0666352 0.0415971 0.0425292 0.0655289 0.0415971 0.0432005 0.064615 0.0412971 0.0442637 0.0649064 0.0415971 0.0443351 0.0649345 0.0415971 0.0456288 0.0653983 0.0412971 0.0469519 0.0658942 0.0415971 0.0469727 0.0680341 0.0415971 0.0473296 0.068118 0.0412971 0.0476176 0.066669 0.0412971 0.0476491 0.0667403 0.0415971 0.0473577 0.0669235 0.0415971 0.0473954 0.0667403 0.0672971 0.0473577 0.0658942 0.0672971 0.0469727 0.0656058 0.0672971 0.0467352 0.0651503 0.0672971 0.0461454 0.0656058 0.0415971 0.0467352 0.0649345 0.0672971 0.0456288 0.0651503 0.0415971 0.0461454 0.0649064 0.0672971 0.0443351 0.0648391 0.0415971 0.0450772 0.0655289 0.0672971 0.0432005 0.0650221 0.0415971 0.0439798 0.0656631 0.0415971 0.0430704 0.0473968 0.0415971 0.0677908 0.0473475 0.0412971 0.0680867 0.0453616 0.0412971 0.0666867 0.045013 0.0412971 0.0654904 0.0452179 0.0412971 0.0642612 0.0461365 0.0415971 0.0634658 0.0471086 0.0415971 0.0629247 0.0463676 0.0415971 0.0673682 0.0460792 0.0672971 0.0671306 0.0456237 0.0672971 0.0665408 0.0454079 0.0672971 0.0660243 0.0456237 0.0415971 0.0665408 0.0453124 0.0672971 0.0654726 0.0453124 0.0415971 0.0654726 0.0454955 0.0415971 0.0643752 0.0454955 0.0672971 0.0643752 -0.031689 0.0675971 0.0437313 -0.031689 0.0790971 0.0437313 -0.0232454 0.0675971 0.0487466 -0.014033 0.0675971 0.0521498 -0.0232454 0.0790971 0.0487466 -0.00435662 0.0790971 0.0538281 -0.00435662 0.0675971 0.0538281 0.00546369 0.0675971 0.0537262 0.0368619 0.0414971 0.0765371 0.0489561 0.0414971 0.0694253 0.0489561 0.0430971 0.0694253 0.0688444 0.0414971 0.0497663 0.0688444 0.0430971 0.0497663 0.076096 0.0414971 0.0377554 0.0842306 0.0414971 0.011 0.0848917 0.0414971 -0.0030146 0.083237 0.0430971 -0.0169469 0.0793117 0.0414971 -0.0304169 0.0793117 0.0430971 -0.0304169 0.0732229 0.0430971 -0.043057 0.0732229 0.0414971 -0.043057 0.0439024 0.0414971 -0.0727195 0.0552734 0.0430971 -0.0645008 0.0439024 0.0430971 -0.0727195 0.0179102 0.0430971 -0.0830358 0.00399798 0.0430971 -0.0848519 -0.0100234 0.0414971 -0.0843534 0.0237621 0.0444971 0.0815613 0.0237621 0.0455971 0.0815613 0.0489561 0.0444971 0.0694253 0.0597147 0.0444971 0.0604198 0.0688444 0.0444971 0.0497663 0.0597147 0.0455971 0.0604198 0.0688444 0.0455971 0.0497663 0.076096 0.0455971 0.0377554 0.0842306 0.0455971 0.011 0.0842306 0.0444971 0.011 0.0848917 0.0444971 -0.0030146 0.083237 0.0444971 -0.0169469 0.083237 0.0455971 -0.0169469 0.0793117 0.0444971 -0.0304169 0.0732229 0.0444971 -0.043057 0.0651366 0.0444971 -0.0545226 0.0732229 0.0455971 -0.043057 0.0552734 0.0444971 -0.0645008 0.0552734 0.0455971 -0.0645008 0.0313337 0.0444971 -0.0789545 -0.0100234 0.0444971 -0.0843534 -0.0100234 0.0455971 -0.0843534 -0.0237715 0.0444971 -0.0815538 0.0237621 0.0469971 0.0815613 0.0237621 0.0480971 0.0815613 0.0368619 0.0480971 0.0765371 0.0489561 0.0480971 0.0694253 0.0597147 0.0469971 0.0604198 0.0597147 0.0480971 0.0604198 0.0812718 0.0480971 0.0247147 0.0848917 0.0469971 -0.0030146 0.0848917 0.0480971 -0.0030146 0.083237 0.0480971 -0.0169469 0.0793117 0.0469971 -0.0304169 0.0732229 0.0469971 -0.043057 0.0732229 0.0480971 -0.043057 0.0651366 0.0469971 -0.0545226 0.0552734 0.0469971 -0.0645008 0.0651366 0.0480971 -0.0545226 0.0552734 0.0480971 -0.0645008 0.0439024 0.0480971 -0.0727195 0.0439024 0.0469971 -0.0727195 0.0313337 0.0469971 -0.0789545 0.0179102 0.0469971 -0.0830358 -0.0100234 0.0469971 -0.0843534 0.0237621 0.0505971 0.0815613 0.0489561 0.0494971 0.0694253 0.0597147 0.0494971 0.0604198 0.0597147 0.0505971 0.0604198 0.0688444 0.0505971 0.0497663 0.076096 0.0505971 0.0377554 0.0812718 0.0505971 0.0247147 0.0848917 0.0505971 -0.0030146 0.0848917 0.0494971 -0.0030146 0.083237 0.0505971 -0.0169469 0.0793117 0.0505971 -0.0304169 0.0732229 0.0494971 -0.043057 0.0651366 0.0494971 -0.0545226 0.0732229 0.0505971 -0.043057 0.0651366 0.0505971 -0.0545226 0.0552734 0.0505971 -0.0645008 0.0439024 0.0505971 -0.0727195 0.0179102 0.0494971 -0.0830358 0.00399798 0.0494971 -0.0848519 -0.0100234 0.0505971 -0.0843534 0.0368619 0.0519971 0.0765371 0.0489561 0.0530971 0.0694253 0.0597147 0.0519971 0.0604198 0.0597147 0.0530971 0.0604198 0.0688444 0.0530971 0.0497663 0.076096 0.0530971 0.0377554 0.0842306 0.0519971 0.011 0.0812718 0.0530971 0.0247147 0.0842306 0.0530971 0.011 0.0848917 0.0519971 -0.0030146 0.083237 0.0519971 -0.0169469 0.083237 0.0530971 -0.0169469 0.0793117 0.0519971 -0.0304169 0.0732229 0.0519971 -0.043057 0.0552734 0.0519971 -0.0645008 0.0651366 0.0530971 -0.0545226 0.0552734 0.0530971 -0.0645008 0.0439024 0.0519971 -0.0727195 0.0439024 0.0530971 -0.0727195 0.0313337 0.0519971 -0.0789545 0.0179102 0.0519971 -0.0830358 0.00399798 0.0519971 -0.0848519 0.0179102 0.0530971 -0.0830358 0.00399798 0.0530971 -0.0848519 -0.0100234 0.0519971 -0.0843534 -0.0237715 0.0519971 -0.0815538 -0.0237715 0.0530971 -0.0815538 0.0237621 0.0544971 0.0815613 0.0489561 0.0544971 0.0694253 0.0597147 0.0544971 0.0604198 0.0688444 0.0544971 0.0497663 0.0688444 0.0555971 0.0497663 0.076096 0.0544971 0.0377554 0.0812718 0.0544971 0.0247147 0.0848917 0.0544971 -0.0030146 0.0848917 0.0555971 -0.0030146 0.0793117 0.0544971 -0.0304169 0.0732229 0.0555971 -0.043057 0.0651366 0.0544971 -0.0545226 0.0552734 0.0544971 -0.0645008 0.0313337 0.0555971 -0.0789545 0.0179102 0.0544971 -0.0830358 -0.0100234 0.0544971 -0.0843534 -0.0237715 0.0544971 -0.0815538 0.0688444 0.0569971 0.0497663 0.0597147 0.0580971 0.0604198 0.0688444 0.0580971 0.0497663 0.076096 0.0569971 0.0377554 0.0812718 0.0569971 0.0247147 0.0842306 0.0580971 0.011 0.0848917 0.0569971 -0.0030146 0.083237 0.0569971 -0.0169469 0.083237 0.0580971 -0.0169469 0.0793117 0.0569971 -0.0304169 0.0732229 0.0569971 -0.043057 0.0732229 0.0580971 -0.043057 0.0651366 0.0569971 -0.0545226 0.0552734 0.0580971 -0.0645008 0.0552734 0.0569971 -0.0645008 0.0179102 0.0569971 -0.0830358 0.00399798 0.0569971 -0.0848519 0.00399798 0.0580971 -0.0848519 0.0368619 0.0594971 0.0765371 0.0489561 0.0594971 0.0694253 0.0489561 0.0605971 0.0694253 0.0597147 0.0594971 0.0604198 0.0597147 0.0605971 0.0604198 0.076096 0.0594971 0.0377554 0.0842306 0.0594971 0.011 0.0848917 0.0605971 -0.0030146 0.083237 0.0594971 -0.0169469 0.0793117 0.0594971 -0.0304169 0.083237 0.0605971 -0.0169469 0.0793117 0.0605971 -0.0304169 0.0732229 0.0605971 -0.043057 0.0732229 0.0594971 -0.043057 0.0651366 0.0605971 -0.0545226 0.0651366 0.0594971 -0.0545226 0.0313337 0.0594971 -0.0789545 0.0179102 0.0594971 -0.0830358 -0.0100234 0.0594971 -0.0843534 -0.0100234 0.0605971 -0.0843534 0.0368619 0.0670971 0.0765371 0.0368619 0.0644971 0.0765371 0.0597147 0.0670971 0.0604198 0.0688444 0.0670971 0.0497663 0.076096 0.0670971 0.0377554 0.0842306 0.0670971 0.011 0.0848917 0.0670971 -0.0030146 0.0848917 0.0644971 -0.0030146 0.083237 0.0644971 -0.0169469 0.083237 0.0670971 -0.0169469 0.0793117 0.0644971 -0.0304169 0.0732229 0.0644971 -0.043057 0.0552734 0.0644971 -0.0645008 0.0179102 0.0670971 -0.0830358 0.0179102 0.0644971 -0.0830358 0.00399798 0.0644971 -0.0848519 -0.0100234 0.0644971 -0.0843534 -0.0100234 0.0670971 -0.0843534 0.0237621 0.0630971 0.0815613 0.0368619 0.0630971 0.0765371 0.0489561 0.0630971 0.0694253 0.0489561 0.0619971 0.0694253 0.076096 0.0630971 0.0377554 0.0842306 0.0619971 0.011 0.0812718 0.0630971 0.0247147 0.0848917 0.0630971 -0.0030146 0.0848917 0.0619971 -0.0030146 0.083237 0.0619971 -0.0169469 0.0793117 0.0619971 -0.0304169 0.083237 0.0630971 -0.0169469 0.0793117 0.0630971 -0.0304169 0.0732229 0.0619971 -0.043057 0.0552734 0.0619971 -0.0645008 0.0439024 0.0630971 -0.0727195 0.0439024 0.0619971 -0.0727195 0.0313337 0.0619971 -0.0789545 0.0313337 0.0630971 -0.0789545 -0.0100234 0.0630971 -0.0843534 0.0237062 0.0412971 0.0813693 0.0237621 0.0410971 0.0815613 0.0368619 0.0410971 0.0765371 0.0810805 0.0412971 0.0246566 0.0848917 0.0410971 -0.0030146 0.083237 0.0410971 -0.0169469 0.083041 0.0412971 -0.016907 0.0793117 0.0410971 -0.0304169 0.079125 0.0412971 -0.0303452 0.0732229 0.0410971 -0.043057 0.0651366 0.0410971 -0.0545226 0.0649832 0.0412971 -0.0543942 0.0552734 0.0410971 -0.0645008 0.0439024 0.0410971 -0.0727195 0.043799 0.0412971 -0.0725483 0.0774413 0.0397971 -0.0210164 0.076762 0.0397971 -0.0212954 0.0760655 0.0397971 -0.0225464 0.0761863 0.0349971 -0.0232707 0.077251 0.0397971 -0.0242281 0.0766094 0.0349971 -0.0238709 0.079086 0.0349971 0.020833 0.0782321 0.0349971 0.0208516 0.0774833 0.0397971 0.0204408 0.0774833 0.0349971 0.0204408 0.0770217 0.0397971 0.0188566 0.0774325 0.0349971 0.0181079 0.0781627 0.0349971 0.0176648 0.0589291 0.0349971 0.0575692 0.0575168 0.0349971 0.0573337 0.0568204 0.0349971 0.0560826 0.0568204 0.0397971 0.0560826 0.0569412 0.0397971 0.0553583 0.0197021 0.0397971 -0.0770412 0.0197021 0.0349971 -0.0770412 0.0188482 0.0349971 -0.0770226 0.0180994 0.0349971 -0.0774335 0.0176564 0.0397971 -0.0781637 0.0176564 0.0349971 -0.0781637 0.0176378 0.0349971 -0.0790176 0.0180487 0.0397971 -0.0797664 0.0180487 0.0349971 -0.0797664 0.0564383 0.0349971 -0.0568843 0.0557052 0.0397971 -0.0568409 0.055026 0.0397971 -0.0571198 0.055026 0.0349971 -0.0571198 0.054535 0.0397971 -0.0576659 0.0543295 0.0349971 -0.0583709 0.0544503 0.0349971 -0.0590952 -0.0781143 0.0397971 0.0242542 -0.0781143 0.0349971 0.0242542 -0.0788631 0.0397971 0.0238433 -0.0788631 0.0349971 0.0238433 -0.0793061 0.0349971 0.0231131 -0.0793247 0.0349971 0.0222592 -0.079026 0.0397971 -0.0176387 -0.079026 0.0349971 -0.0176387 -0.0802364 0.0349971 -0.0196337 -0.0798255 0.0349971 -0.0203825 -0.0596179 0.0397971 -0.0547857 -0.0588691 0.0349971 -0.0543749 -0.0600795 0.0397971 -0.0563698 -0.0600795 0.0349971 -0.0563698 -0.0196421 0.0349971 0.0802355 -0.0196421 0.0397971 0.0802355 -0.0203909 0.0397971 0.0798246 -0.0208525 0.0349971 0.0782405 -0.0208525 0.0397971 0.0782405 -0.0204417 0.0397971 0.0774917 -0.0204417 0.0349971 0.0774917 -0.0555244 0.0349971 0.06006 -0.0562574 0.0349971 0.0601034 -0.0563783 0.0397971 0.0600786 -0.0569367 0.0397971 0.0598245 -0.0575701 0.0397971 0.0589375 -0.0574277 0.0349971 0.0592785 -0.0575887 0.0397971 0.0580836 -0.0575123 0.0349971 0.0578492 -0.0575123 0.0397971 0.0578492 -0.0570892 0.0349971 0.057249 -0.0571778 0.0397971 0.0573348 -0.0564476 0.0349971 0.0568918 -0.0564476 0.0397971 0.0568918 -0.00511301 0.0292971 -0.0584234 0.00638371 0.0292971 -0.0582973 0.0283045 0.0294971 -0.05159 0.0458936 0.0294971 -0.0368292 0.0564952 0.0294971 -0.016461 0.0563032 0.0292971 -0.016405 0.0584224 0.0292971 -0.00510459 0.0561206 0.0294971 0.0177035 0.0559298 0.0292971 0.0176433 0.0450749 0.0294971 0.0378344 0.0449217 0.0292971 0.0377058 0.0367031 0.0292971 0.0457461 0.0270739 0.0292971 0.0520285 0.01646 0.0294971 0.0565036 0.0179102 0.0355971 -0.0830358 -0.00995263 0.0349971 -0.0837576 0.0207474 0.0349971 -0.0817537 0.0178609 0.0349971 -0.0824325 0.0311123 0.0349971 -0.0783968 0.0313337 0.0355971 -0.0789545 0.0439024 0.0355971 -0.0727195 0.0552562 0.0349971 -0.0637235 0.0727057 0.0349971 -0.0427529 0.0651366 0.0355971 -0.0545226 0.0732229 0.0355971 -0.043057 0.0777137 0.0349971 -0.03278 0.0787515 0.0349971 -0.030202 0.0848917 0.0355971 -0.0030146 0.0812718 0.0355971 0.0247147 0.0842306 0.0355971 0.011 0.076096 0.0355971 0.0377554 0.0742799 0.0349971 0.0399627 0.061419 0.0349971 0.0578142 0.0592929 0.0349971 0.059993 0.0368619 0.0355971 0.0765371 0.0366015 0.0349971 0.0759966 -0.0814508 0.0349971 -0.00251363 -0.0832134 0.0352971 -0.0058277 -0.0835048 0.0349971 -0.00589902 -0.0828076 0.0349971 -0.0071697 -0.0800856 0.0410971 -0.00283318 -0.0800856 0.0352971 -0.00283318 -0.0811963 0.0410971 -0.0027674 -0.0813794 0.0352971 -0.00280502 -0.0822255 0.0410971 -0.00319003 -0.082514 0.0352971 -0.00342753 -0.0831852 0.0410971 -0.00453391 -0.0831852 0.0352971 -0.00453391 -0.0832807 0.0410971 -0.00508553 -0.0832134 0.0410971 -0.0058277 -0.0825909 0.0410971 -0.00696223 -0.0825909 0.0352971 -0.00696223 -0.0812292 0.0412971 -0.00257012 -0.0813794 0.0410971 -0.00280502 -0.082514 0.0410971 -0.00342753 -0.0829694 0.0410971 -0.00401736 -0.0832827 0.0412971 -0.00625895 -0.0830977 0.0410971 -0.00618298 -0.0824566 0.0410971 -0.00709235 -0.0825904 0.0412971 -0.00724107 -0.0747717 0.0352971 -0.0350598 -0.0757438 0.0352971 -0.0345186 -0.0760948 0.0349971 -0.034596 -0.0767604 0.0349971 -0.0318762 -0.0732889 0.0349971 -0.0299714 -0.0744835 0.0352971 -0.0301937 -0.0755127 0.0352971 -0.0306163 -0.0746666 0.0352971 -0.0302313 -0.0755127 0.0410971 -0.0306163 -0.0758011 0.0352971 -0.0308538 -0.0764724 0.0410971 -0.0319602 -0.0762566 0.0352971 -0.0314436 -0.0765679 0.0410971 -0.0325118 -0.0764724 0.0352971 -0.0319602 -0.0765679 0.0352971 -0.0325118 -0.0765006 0.0352971 -0.033254 -0.0763849 0.0410971 -0.0336092 -0.0763849 0.0352971 -0.0336092 -0.0757438 0.0410971 -0.0345186 -0.0758781 0.0352971 -0.0343885 -0.0744835 0.0410971 -0.0301937 -0.0746666 0.0410971 -0.0302313 -0.0758011 0.0410971 -0.0308538 -0.0762566 0.0410971 -0.0314436 -0.0766644 0.0412971 -0.0319042 -0.0765006 0.0410971 -0.033254 -0.0766948 0.0412971 -0.0333015 -0.0747717 0.0410971 -0.0350598 -0.0758781 0.0410971 -0.0343885 -0.0760225 0.0412971 -0.0345268 -0.0690729 0.0352971 -0.0431161 -0.0692804 0.0349971 -0.0428994 -0.0697442 0.0352971 -0.0442225 -0.0700637 0.0349971 -0.0455876 -0.0693665 0.0349971 -0.0468583 -0.0666446 0.0410971 -0.0425217 -0.0666446 0.0352971 -0.0425217 -0.0679384 0.0352971 -0.0424936 -0.0679384 0.0410971 -0.0424936 -0.0687844 0.0410971 -0.0428786 -0.0690729 0.0410971 -0.0431161 -0.0697442 0.0410971 -0.0442225 -0.0697723 0.0352971 -0.0455163 -0.0698396 0.0410971 -0.0447741 -0.0697723 0.0410971 -0.0455163 -0.0691498 0.0352971 -0.0466508 -0.0690156 0.0410971 -0.0467809 -0.0677881 0.0412971 -0.0422587 -0.0677552 0.0410971 -0.042456 -0.0688997 0.0412971 -0.0427151 -0.0695284 0.0410971 -0.0437059 -0.0697031 0.0412971 -0.0436087 -0.0696566 0.0410971 -0.0458716 -0.0698416 0.0412971 -0.0459475 -0.0691498 0.0410971 -0.0466508 -0.0484831 0.0349971 -0.0625976 -0.0497538 0.0349971 -0.0632948 -0.0495463 0.0352971 -0.0635115 -0.0505056 0.0349971 -0.064534 -0.0496232 0.0352971 -0.0670462 -0.0498399 0.0349971 -0.0672537 -0.0485168 0.0352971 -0.0677175 -0.047118 0.0352971 -0.0629172 -0.0484118 0.0410971 -0.062889 -0.0495463 0.0410971 -0.0635115 -0.0484118 0.0352971 -0.062889 -0.0502176 0.0352971 -0.0646179 -0.0502457 0.0352971 -0.0659117 -0.0496232 0.0410971 -0.0670462 -0.0497677 0.0412971 -0.0671845 -0.0502457 0.0410971 -0.0659117 -0.0504096 0.0412971 -0.0645619 -0.0502176 0.0410971 -0.0646179 -0.0496846 0.0412971 -0.0633671 -0.0484593 0.0412971 -0.0626948 -0.047118 0.0410971 -0.0629172 -0.0816487 0.0351971 0.00467902 -0.0830102 0.0351971 0.00393201 -0.0831485 0.0349971 0.00407648 -0.0838157 0.0351971 0.00260436 -0.0838495 0.0351971 0.00105181 -0.0831025 0.0351971 -0.000309625 -0.0817748 0.0351971 -0.00111516 -0.0832469 0.0349971 -0.000447936 -0.0718687 0.0349971 -0.0420086 -0.0718128 0.0351971 -0.0418165 -0.0740137 0.0349971 -0.0399347 -0.0731404 0.0351971 -0.041011 -0.0716867 0.0351971 -0.0360224 -0.0717342 0.0349971 -0.0358281 -0.0740457 0.0349971 -0.0380411 -0.0738875 0.0351971 -0.0396496 -0.0411561 0.0351971 -0.0663236 -0.0411001 0.0349971 -0.0661316 -0.0442084 0.0349971 -0.0668923 -0.0450676 0.0349971 -0.0683085 -0.0451037 0.0349971 -0.0699645 -0.0449094 0.0351971 -0.069917 -0.0441624 0.0351971 -0.0712784 -0.0428347 0.0351971 -0.072084 -0.0821803 0.0379971 0.00306522 -0.0805019 0.0382471 0.00325314 -0.081304 0.0382471 0.0032706 -0.0820074 0.0382471 0.00288464 -0.0824236 0.0411471 0.00219869 -0.0824236 0.0382471 0.00219869 -0.0824411 0.0382471 0.00139654 -0.0820551 0.0411471 0.000693129 -0.0813692 0.0411471 0.000276936 -0.0820551 0.0382471 0.000693129 -0.0813692 0.0382471 0.000276936 -0.0814111 0.0412971 0.000132926 -0.0821635 0.0412971 0.000589396 -0.0824411 0.0411471 0.00139654 -0.0820074 0.0411471 0.00288464 -0.081304 0.0411471 0.0032706 -0.0813397 0.0412971 0.0034163 -0.0705398 0.0382471 -0.0374482 -0.071342 0.0382471 -0.0374308 -0.0704699 0.0379971 -0.0372082 -0.0714014 0.0379971 -0.037188 -0.0722183 0.0379971 -0.0376362 -0.0720454 0.0382471 -0.0378167 -0.0724616 0.0382471 -0.0385027 -0.0727016 0.0379971 -0.0384328 -0.0720931 0.0382471 -0.0400083 -0.0714071 0.0382471 -0.0404245 -0.0722737 0.0379971 -0.0401811 -0.0705398 0.0411471 -0.0374482 -0.072479 0.0382471 -0.0393048 -0.0720931 0.0411471 -0.0400083 -0.072479 0.0411471 -0.0393048 -0.0724616 0.0411471 -0.0385027 -0.0726247 0.0412971 -0.0393405 -0.0720454 0.0411471 -0.0378167 -0.071342 0.0411471 -0.0374308 -0.0414918 0.0379971 -0.0674756 -0.0423639 0.0382471 -0.0676982 -0.0424233 0.0379971 -0.0674554 -0.0430673 0.0382471 -0.0680842 -0.0432402 0.0379971 -0.0679036 -0.0437438 0.0379971 -0.0696317 -0.043115 0.0382471 -0.0702757 -0.0424291 0.0382471 -0.0706919 -0.0432956 0.0379971 -0.0704486 -0.0423639 0.0411471 -0.0676982 -0.0430673 0.0411471 -0.0680842 -0.0434835 0.0382471 -0.0687701 -0.043115 0.0411471 -0.0702757 -0.043501 0.0382471 -0.0695723 -0.043501 0.0411471 -0.0695723 -0.0432234 0.0412971 -0.0703794 -0.0434835 0.0411471 -0.0687701 -0.0415618 0.0411471 -0.0677157 -0.0423996 0.0412971 -0.0675525 -0.0800962 0.0379971 0.00464524 -0.0838495 0.0379971 0.00105181 -0.0831025 0.0379971 -0.000309625 -0.0716867 0.0379971 -0.0360224 -0.0701341 0.0351971 -0.0360561 -0.0730481 0.0351971 -0.0367694 -0.0738875 0.0379971 -0.0396496 -0.0738537 0.0351971 -0.038097 -0.0731404 0.0379971 -0.041011 -0.0718128 0.0379971 -0.0418165 -0.0427086 0.0379971 -0.0662898 -0.0427086 0.0351971 -0.0662898 -0.0440701 0.0351971 -0.0670368 -0.0448756 0.0379971 -0.0683644 -0.0448756 0.0351971 -0.0683644 -0.0441624 0.0379971 -0.0712784 -0.0659201 0.0352971 0.0502448 -0.0659914 0.0349971 0.0505362 -0.0672621 0.0349971 0.049839 -0.0677259 0.0352971 0.0485159 -0.0680139 0.0349971 0.0485999 -0.0677541 0.0352971 0.0472221 -0.0671316 0.0352971 0.0460876 -0.0659201 0.0410971 0.0502448 -0.0677259 0.0410971 0.0485159 -0.0670546 0.0352971 0.0496223 -0.0677541 0.0410971 0.0472221 -0.0671316 0.0410971 0.0460876 -0.0660252 0.0352971 0.0454163 -0.0679179 0.0412971 0.0485719 -0.0670546 0.0410971 0.0496223 -0.0659677 0.0412971 0.0504391 -0.0468667 0.0349971 0.0693656 -0.0476185 0.0349971 0.0681265 -0.0476501 0.0349971 0.0666774 -0.0455247 0.0352971 0.0697714 -0.0466592 0.0410971 0.0691489 -0.0466592 0.0352971 0.0691489 -0.0473305 0.0410971 0.0680425 -0.0473305 0.0352971 0.0680425 -0.0473587 0.0352971 0.0667487 -0.0467361 0.0410971 0.0656142 -0.0456298 0.0410971 0.0649429 -0.0467361 0.0352971 0.0656142 -0.0473587 0.0410971 0.0667487 -0.0455247 0.0410971 0.0697714 -0.0455722 0.0412971 0.0699657 -0.0318847 0.0349971 0.0767595 -0.0341085 0.0352971 0.0761147 -0.0348524 0.0352971 0.0752873 -0.0354631 0.0349971 0.0742369 -0.0343396 0.0352971 0.0722123 -0.0319686 0.0352971 0.0764715 -0.0330792 0.0352971 0.0765373 -0.0341085 0.0410971 0.0761147 -0.0351636 0.0352971 0.0742192 -0.0351636 0.0410971 0.0742192 -0.0349806 0.0352971 0.0731217 -0.0349806 0.0410971 0.0731217 -0.0343396 0.0410971 0.0722123 -0.0353633 0.0412971 0.074231 -0.0350271 0.0412971 0.0753846 -0.0348524 0.0410971 0.0752873 -0.0342237 0.0412971 0.0762781 -0.0330792 0.0410971 0.0765373 -0.0331121 0.0412971 0.0767346 -0.0319686 0.0410971 0.0764715 -0.00454233 0.0352971 0.0831843 -0.00583612 0.0352971 0.0832125 -0.00590744 0.0349971 0.0835039 -0.00717811 0.0349971 0.0828067 -0.00764193 0.0352971 0.0814836 -0.00792995 0.0349971 0.0815675 -0.00796148 0.0349971 0.0801185 -0.00704757 0.0352971 0.0790553 -0.00726427 0.0349971 0.0788478 -0.00583612 0.0410971 0.0832125 -0.00697065 0.0352971 0.08259 -0.00773739 0.0410971 0.080932 -0.00767008 0.0352971 0.0801898 -0.00691332 0.0410971 0.0789252 -0.0059412 0.0410971 0.078384 -0.00565298 0.0410971 0.0832501 -0.0066822 0.0410971 0.0828275 -0.00697065 0.0410971 0.08259 -0.00742611 0.0410971 0.0820002 -0.00764193 0.0410971 0.0814836 -0.00773939 0.0412971 0.0797586 -0.00767008 0.0410971 0.0801898 -0.00755438 0.0410971 0.0798345 -0.00599715 0.0412971 0.078192 -0.00704705 0.0412971 0.0787764 -0.00704757 0.0410971 0.0790553 -0.069973 0.0349971 0.0451027 -0.0714252 0.0349971 0.0443059 -0.0712868 0.0351971 0.0441615 -0.0722844 0.0349971 0.0428898 -0.0721262 0.0351971 0.0412813 -0.0713792 0.0351971 0.0399198 -0.0700515 0.0351971 0.0391143 -0.0407885 0.0349971 0.073588 -0.041566 0.0351971 0.0724317 -0.0421392 0.0349971 0.0711618 -0.0417199 0.0351971 0.069833 -0.0410844 0.0349971 0.068593 -0.000554816 0.0349971 0.0787216 -0.000410351 0.0351971 0.0788599 -0.00135163 0.0349971 0.0801738 -0.00131559 0.0349971 0.0818299 -0.000864596 0.0351971 0.0823938 2.81017e-05 0.0351971 0.0833866 -0.000318041 0.0351971 0.0831016 -0.000456352 0.0349971 0.083246 -0.0696401 0.0379971 0.0437429 -0.0707003 0.0382471 0.0424281 -0.0707177 0.0382471 0.041626 -0.0709606 0.0379971 0.0415666 -0.0703318 0.0382471 0.0409226 -0.0705124 0.0379971 0.0407497 -0.0696458 0.0382471 0.0405064 -0.0687785 0.0411471 0.0434826 -0.0687785 0.0382471 0.0434826 -0.0695807 0.0382471 0.0435 -0.0702841 0.0382471 0.0431141 -0.0702841 0.0411471 0.0431141 -0.0707003 0.0411471 0.0424281 -0.0703318 0.0411471 0.0409226 -0.0696458 0.0411471 0.0405064 -0.0696878 0.0412971 0.0403624 -0.0707177 0.0411471 0.041626 -0.0704401 0.0412971 0.0408188 -0.0708443 0.0412971 0.0424701 -0.0695807 0.0411471 0.0435 -0.0696163 0.0412971 0.0436457 -0.0687366 0.0412971 0.0436266 -0.0392408 0.0379971 0.072748 -0.0405175 0.0379971 0.0718481 -0.0404921 0.0382471 0.0710642 -0.0401483 0.0379971 0.0696341 -0.0391997 0.0382471 0.0725014 -0.0391997 0.0411471 0.0725014 -0.0398378 0.0411471 0.0722394 -0.0398378 0.0382471 0.0722394 -0.0402991 0.0382471 0.0717265 -0.0404921 0.0411471 0.0710642 -0.0403786 0.0382471 0.0703838 -0.0403786 0.0411471 0.0703838 -0.0399811 0.0411471 0.06982 -0.0399811 0.0382471 0.06982 -0.0400814 0.0412971 0.0697084 -0.0405173 0.0412971 0.0703268 -0.0402991 0.0411471 0.0717265 -0.0399243 0.0412971 0.072362 0.00226022 0.0379971 0.0826627 0.00146054 0.0379971 0.0827101 0.000863553 0.0382471 0.0822014 0.000183891 0.0379971 0.0818101 0.000402326 0.0382471 0.0816885 0.000209333 0.0382471 0.0810262 -4.02292e-05 0.0379971 0.081041 9.1539e-05 0.0379971 0.0802508 0.00219027 0.0382471 0.0824227 0.00150166 0.0411471 0.0824635 0.000863553 0.0411471 0.0822014 0.00150166 0.0382471 0.0824635 0.000402326 0.0411471 0.0816885 0.000322801 0.0382471 0.0803458 0.000720254 0.0382471 0.079782 0.00132297 0.0411471 0.0794465 0.00128101 0.0412971 0.0793025 0.000720254 0.0411471 0.079782 0.00061996 0.0412971 0.0796705 0.000322801 0.0411471 0.0803458 0.000209333 0.0411471 0.0810262 5.95958e-05 0.0412971 0.0810351 0.00219027 0.0411471 0.0824227 -0.0683729 0.0351971 0.0448747 -0.0699254 0.0351971 0.0449085 -0.0720924 0.0379971 0.0428338 -0.0720924 0.0351971 0.0428338 -0.0721262 0.0379971 0.0412813 -0.0713792 0.0379971 0.0399198 -0.0381054 0.0351971 0.0738528 -0.0394382 0.0351971 0.0739317 -0.0406733 0.0351971 0.0734245 -0.0419395 0.0351971 0.0711499 -0.0409506 0.0351971 0.0687418 -0.0397841 0.0379971 0.0680924 0.0010434 0.0351971 0.0838486 -0.00112358 0.0351971 0.0817739 -0.00123813 0.0351971 0.081112 -0.00115736 0.0351971 0.0802214 -0.00101852 0.0351971 0.079795 -0.000249252 0.0379971 0.0787038 0.0649052 0.0352971 -0.045343 0.06287 0.0349971 -0.0464471 0.0625213 0.0349971 -0.0476434 0.0636449 0.0352971 -0.049668 0.0649052 0.0410971 -0.045343 0.063876 0.0410971 -0.0457657 0.063876 0.0352971 -0.0457657 0.0628208 0.0410971 -0.0476612 0.0631321 0.0352971 -0.046593 0.0628208 0.0352971 -0.0476612 0.0630038 0.0352971 -0.0487586 0.064617 0.0410971 -0.0502092 0.0636449 0.0410971 -0.049668 0.0630038 0.0410971 -0.0487586 0.0626211 0.0412971 -0.0476494 0.0631321 0.0410971 -0.046593 0.0629573 0.0412971 -0.0464957 0.0637607 0.0412971 -0.0456022 0.0660718 0.0412971 -0.0452168 0.0445098 0.0352971 -0.0648696 0.0457044 0.0349971 -0.0646474 0.0444604 0.0349971 -0.0645737 0.0433077 0.0349971 -0.0650471 0.0427366 0.0352971 -0.0661196 0.0424745 0.0349971 -0.0659737 0.0423309 0.0349971 -0.0683992 0.0430488 0.0349971 -0.0694177 0.0434806 0.0352971 -0.0652923 0.0424254 0.0352971 -0.0671878 0.0426084 0.0352971 -0.0682852 0.0432494 0.0410971 -0.0691946 0.0432494 0.0352971 -0.0691946 0.0442216 0.0410971 -0.0697358 0.0426084 0.0410971 -0.0682852 0.0431157 0.0412971 -0.0693433 0.0424234 0.0412971 -0.0683612 0.0422257 0.0412971 -0.067176 0.0424254 0.0410971 -0.0671878 0.0427366 0.0410971 -0.0661196 0.0425619 0.0412971 -0.0660223 0.0434806 0.0410971 -0.0652923 0.0433653 0.0412971 -0.0651288 0.0445098 0.0410971 -0.0648696 0.0456204 0.0410971 -0.0649354 0.0456764 0.0412971 -0.0647434 0.0322475 0.0352971 -0.0715979 0.0310454 0.0349971 -0.0717753 0.0304743 0.0352971 -0.0728479 0.0301631 0.0352971 -0.073916 0.0298636 0.0349971 -0.0738983 0.0307865 0.0349971 -0.0761459 0.0322475 0.0410971 -0.0715979 0.0312183 0.0410971 -0.0720205 0.0312183 0.0352971 -0.0720205 0.0301631 0.0410971 -0.073916 0.0303461 0.0410971 -0.0750135 0.0303461 0.0352971 -0.0750135 0.0309871 0.0352971 -0.0759228 0.0319033 0.0412971 -0.076656 0.0309871 0.0410971 -0.0759228 0.0301611 0.0412971 -0.0750894 0.0299634 0.0412971 -0.0739042 0.0304743 0.0410971 -0.0728479 0.0333581 0.0410971 -0.0716637 0.00456675 0.0349971 -0.0780569 0.00283226 0.0352971 -0.0800772 0.00254424 0.0349971 -0.0799933 0.00342662 0.0352971 -0.0825056 0.00453299 0.0352971 -0.0831768 0.00593186 0.0410971 -0.0783765 0.00463807 0.0352971 -0.0783483 0.00350354 0.0410971 -0.0789709 0.00350354 0.0352971 -0.0789709 0.00283226 0.0410971 -0.0800772 0.00280411 0.0352971 -0.081371 0.00453299 0.0410971 -0.0831768 0.00342662 0.0410971 -0.0825056 0.00447704 0.0412971 -0.0833688 0.00280411 0.0410971 -0.081371 0.00260984 0.0412971 -0.0814186 0.00264025 0.0412971 -0.0800213 0.00463807 0.0410971 -0.0783483 0.00336523 0.0412971 -0.0788264 0.0700981 0.0349971 -0.0389148 0.0671282 0.0351971 -0.03982 0.0663227 0.0351971 -0.0411477 0.0661306 0.0349971 -0.0410917 0.0662889 0.0351971 -0.0427002 0.0367225 0.0349971 -0.0686536 0.0368608 0.0351971 -0.0687981 0.0360552 0.0351971 -0.0701257 0.0358632 0.0349971 -0.0700698 0.0360214 0.0351971 -0.0716783 0.036624 0.0349971 -0.073178 -0.00393293 0.0351971 -0.0830017 -0.00390555 0.0349971 -0.0833066 -0.00467994 0.0351971 -0.0816403 -0.00476071 0.0351971 -0.0807497 -0.00496036 0.0349971 -0.0807379 -0.00456192 0.0349971 -0.0793706 -0.00384062 0.0351971 -0.0787601 -0.00360971 0.0349971 -0.0783116 -0.00229232 0.0349971 -0.0777707 0.0697064 0.0379971 -0.0402589 0.0681309 0.0382471 -0.0408674 0.0687749 0.0379971 -0.0402386 0.0677148 0.0382471 -0.0415533 0.067958 0.0379971 -0.0406868 0.0674747 0.0379971 -0.0414834 0.0674545 0.0379971 -0.0424149 0.0679027 0.0379971 -0.0432318 0.0687692 0.0382471 -0.0434751 0.0696365 0.0382471 -0.0404989 0.0688343 0.0382471 -0.0404814 0.0681309 0.0411471 -0.0408674 0.0676973 0.0411471 -0.0423555 0.0676973 0.0382471 -0.0423555 0.0680832 0.0382471 -0.0430589 0.0687692 0.0411471 -0.0434751 0.0687272 0.0412971 -0.0436191 0.0680832 0.0411471 -0.0430589 0.0677148 0.0411471 -0.0415533 0.0688343 0.0411471 -0.0404814 0.0680272 0.0412971 -0.040759 0.0378991 0.0382471 -0.0721176 0.0372703 0.0379971 -0.0716488 0.0374299 0.0382471 -0.0713336 0.0373881 0.0382471 -0.0708734 0.0378983 0.0379971 -0.0694939 0.0375811 0.0382471 -0.0702111 0.0386394 0.0379971 -0.0691896 0.0393691 0.0382471 -0.069477 0.039439 0.0379971 -0.0692369 0.0380424 0.0382471 -0.0696982 0.0386805 0.0382471 -0.0694362 0.0385669 0.0382471 -0.0694595 0.0378635 0.0382471 -0.0698455 0.0374473 0.0382471 -0.0705314 0.0374473 0.0411471 -0.0705314 0.0374299 0.0411471 -0.0713336 0.0375016 0.0382471 -0.0715538 0.0378158 0.0411471 -0.072037 0.0378158 0.0382471 -0.072037 0.0377075 0.0412971 -0.0721407 0.0372842 0.0412971 -0.0713692 0.0373033 0.0412971 -0.0704894 0.0377598 0.0412971 -0.0697371 0.0378635 0.0411471 -0.0698455 0.0385669 0.0411471 -0.0694595 0.0393691 0.0411471 -0.069477 0.039411 0.0412971 -0.0693329 -0.00219961 0.0382471 -0.0824152 -0.00327151 0.0382471 -0.0812956 -0.00325406 0.0382471 -0.0804934 -0.00301075 0.0379971 -0.0796269 -0.00213445 0.0382471 -0.0794215 -0.00202091 0.0411471 -0.0793982 -0.00265902 0.0382471 -0.0796602 -0.00265902 0.0411471 -0.0796602 -0.00283786 0.0382471 -0.0798075 -0.00312025 0.0382471 -0.0801732 -0.00331324 0.0382471 -0.0808354 -0.00319978 0.0411471 -0.0815159 -0.00319978 0.0382471 -0.0815159 -0.00288556 0.0382471 -0.081999 -0.00280232 0.0411471 -0.0820797 -0.00331324 0.0411471 -0.0808354 -0.00346298 0.0412971 -0.0808266 -0.00312025 0.0411471 -0.0801732 -0.00325131 0.0412971 -0.0801002 -0.00204559 0.0412971 -0.0792502 0.0700422 0.0351971 -0.0391068 0.0684896 0.0351971 -0.039073 0.0663227 0.0379971 -0.0411477 0.0670359 0.0379971 -0.0440617 0.0670359 0.0351971 -0.0440617 0.0683635 0.0351971 -0.0448672 0.0397748 0.0379971 -0.0680849 0.0382222 0.0379971 -0.0680511 0.0368608 0.0379971 -0.0687981 0.0382222 0.0351971 -0.0680511 0.0367685 0.0351971 -0.0730397 0.0380961 0.0379971 -0.0738453 -0.000926633 0.0351971 -0.0780469 -0.00225942 0.0351971 -0.0779679 -0.00247918 0.0379971 -0.0780131 -0.00247918 0.0351971 -0.0780131 -0.00349448 0.0351971 -0.0784751 -0.00438717 0.0351971 -0.0794679 -0.00464615 0.0351971 -0.0800878 -0.00454109 0.0351971 -0.0820667 -0.00467994 0.0379971 -0.0816403 -0.00393293 0.0379971 -0.0830017 -0.00377183 0.0351971 -0.0831579 0.0783756 0.0352971 0.00594028 0.0780876 0.0349971 0.00602421 0.078056 0.0349971 0.00457517 0.0799924 0.0349971 0.00255266 0.0803645 0.0410971 0.00770679 0.0801814 0.0352971 0.00766917 0.0793353 0.0410971 0.00728416 0.0790469 0.0410971 0.00704666 0.0790469 0.0352971 0.00704666 0.0785914 0.0410971 0.00645683 0.0783756 0.0410971 0.00594028 0.0783474 0.0352971 0.00464649 0.0782801 0.0410971 0.00538866 0.0783474 0.0410971 0.00464649 0.0784631 0.0410971 0.00429121 0.0789699 0.0352971 0.00351196 0.0815311 0.0412971 0.00783302 0.0814752 0.0410971 0.00764101 0.0801814 0.0410971 0.00766917 0.0784167 0.0412971 0.00655411 0.0789705 0.0412971 0.00323312 0.0800763 0.0410971 0.00284068 0.0800204 0.0412971 0.00264867 0.0791042 0.0410971 0.00338184 0.0789699 0.0410971 0.00351196 0.0747624 0.0352971 0.0350673 0.0721266 0.0349971 0.0346896 0.0713747 0.0349971 0.0334505 0.0720404 0.0349971 0.0307308 0.0734686 0.0352971 0.0350954 0.072334 0.0410971 0.0344729 0.072334 0.0352971 0.0344729 0.0716628 0.0352971 0.0333665 0.0716628 0.0410971 0.0333665 0.0716346 0.0410971 0.0320727 0.0716346 0.0352971 0.0320727 0.0722571 0.0352971 0.0309382 0.0722571 0.0410971 0.0309382 0.0714707 0.0412971 0.0334225 0.0721957 0.0412971 0.0346174 0.0734686 0.0410971 0.0350954 0.0748183 0.0412971 0.0352593 0.0657214 0.0349971 0.0472179 0.0651503 0.0352971 0.0461454 0.0648882 0.0349971 0.0462913 0.0645396 0.0349971 0.045095 0.0656631 0.0352971 0.0430704 0.0654625 0.0349971 0.0428473 0.0665513 0.0349971 0.0422412 0.0680341 0.0410971 0.0473296 0.0669235 0.0410971 0.0473954 0.0680341 0.0352971 0.0473296 0.0669235 0.0352971 0.0473954 0.0658942 0.0410971 0.0469727 0.0658942 0.0352971 0.0469727 0.0648391 0.0410971 0.0450772 0.0648391 0.0352971 0.0450772 0.0650221 0.0352971 0.0439798 0.0650221 0.0410971 0.0439798 0.0656631 0.0410971 0.0430704 0.0666352 0.0410971 0.0425292 0.0655294 0.0412971 0.0429217 0.0649756 0.0412971 0.0462427 0.0651503 0.0410971 0.0461454 0.0471424 0.0349971 0.0680446 0.0460792 0.0352971 0.0671306 0.0454079 0.0352971 0.0660243 0.0471086 0.0352971 0.0629247 0.0472137 0.0352971 0.0677532 0.0463676 0.0410971 0.0673682 0.0456237 0.0410971 0.0665408 0.0453124 0.0410971 0.0654726 0.0454955 0.0410971 0.0643752 0.0453798 0.0352971 0.0647305 0.0460023 0.0352971 0.063596 0.0485075 0.0410971 0.067725 0.0473968 0.0410971 0.0677908 0.0472137 0.0410971 0.0677532 0.0462524 0.0412971 0.0675316 0.0460792 0.0410971 0.0671306 0.0454079 0.0410971 0.0660243 0.045449 0.0412971 0.0666381 0.0451128 0.0412971 0.0654845 0.0453798 0.0410971 0.0647305 0.0470527 0.0412971 0.0627327 0.0461365 0.0410971 0.0634658 0.0460023 0.0410971 0.063596 0.0818214 0.0349971 0.00131467 0.0802129 0.0351971 0.00115645 0.077854 0.0349971 -0.000862262 0.0787592 0.0351971 -0.0038322 0.0702509 0.0351971 0.0418578 0.0678559 0.0349971 0.0381831 0.0680502 0.0351971 0.0382306 0.0701248 0.0351971 0.0360636 0.0686527 0.0349971 0.0367309 0.0428814 0.0349971 0.0722835 0.0399114 0.0351971 0.0713782 0.0391059 0.0351971 0.0700506 0.0397731 0.0349971 0.0715227 0.0398191 0.0351971 0.0671366 0.0813598 0.0382471 -0.000269437 0.0794381 0.0382471 -0.00132389 0.0794206 0.0382471 -0.00212604 0.0791981 0.0379971 -0.00125395 0.0791778 0.0379971 -0.00218547 0.0798066 0.0382471 -0.00282945 0.079626 0.0379971 -0.00300234 0.0804925 0.0382471 -0.00324564 0.0805577 0.0382471 -0.00025198 0.0798543 0.0382471 -0.000637936 0.0794381 0.0411471 -0.00132389 0.0798066 0.0411471 -0.00282945 0.0804506 0.0412971 -0.00338965 0.0794206 0.0411471 -0.00212604 0.0792941 0.0412971 -0.00128192 0.0798543 0.0411471 -0.000637936 0.0805577 0.0411471 -0.00025198 0.0705305 0.0382471 0.0374557 0.0698445 0.0382471 0.0378719 0.0692991 0.0379971 0.0382601 0.0695303 0.0382471 0.0383551 0.0694586 0.0382471 0.0385753 0.0694169 0.0382471 0.0390355 0.069476 0.0382471 0.0393775 0.069927 0.0379971 0.040415 0.0713978 0.0382471 0.040432 0.0705956 0.0382471 0.0404494 0.0700711 0.0382471 0.0402107 0.0707092 0.0382471 0.0404727 0.0705956 0.0411471 0.0404494 0.0698922 0.0382471 0.0400635 0.0696098 0.0382471 0.0396978 0.0694586 0.0411471 0.0385753 0.0705305 0.0411471 0.0374557 0.0699278 0.0382471 0.0377913 0.0698445 0.0411471 0.0378719 0.0693129 0.0412971 0.0385397 0.069476 0.0411471 0.0393775 0.069332 0.0412971 0.0394195 0.0697885 0.0412971 0.0401718 0.0698922 0.0411471 0.0400635 0.0417311 0.0382471 0.0707402 0.041093 0.0382471 0.0704781 0.040949 0.0379971 0.0706825 0.0404133 0.0379971 0.0700868 0.0405523 0.0382471 0.0686225 0.040321 0.0379971 0.0685275 0.0415524 0.0382471 0.0677232 0.0414825 0.0379971 0.0674831 0.0424197 0.0411471 0.0706994 0.0417311 0.0411471 0.0707402 0.041093 0.0411471 0.0704781 0.0406318 0.0411471 0.0699652 0.0406318 0.0382471 0.0699652 0.0404388 0.0382471 0.0693029 0.0409497 0.0411471 0.0680587 0.0409497 0.0382471 0.0680587 0.0415524 0.0411471 0.0677232 0.0415105 0.0412971 0.0675792 0.0405523 0.0411471 0.0686225 0.0404388 0.0411471 0.0693029 0.040289 0.0412971 0.0693118 0.0410066 0.0412971 0.0706007 0.0417064 0.0412971 0.0708881 0.0817655 0.0351971 0.00112266 0.0788515 0.0351971 0.000409434 0.078046 0.0351971 -0.000918217 0.0780122 0.0351971 -0.00247076 0.0780122 0.0379971 -0.00247076 0.0787592 0.0379971 -0.0038322 0.0718035 0.0379971 0.041824 0.0718035 0.0351971 0.041824 0.0688895 0.0351971 0.0411108 0.0688895 0.0379971 0.0411108 0.0680839 0.0379971 0.0397832 0.0680839 0.0351971 0.0397832 0.0680502 0.0379971 0.0382306 0.0687972 0.0379971 0.0368692 0.0687972 0.0351971 0.0368692 0.0701248 0.0379971 0.0360636 0.0412728 0.0351971 0.0721252 0.0390721 0.0351971 0.068498 0.0390721 0.0379971 0.068498 0.0271663 0.0294971 0.0522059 0.0368283 0.0349971 0.0459021 0.0368283 0.0294971 0.0459021 0.0515891 0.0294971 0.0283129 0.0584952 0.0294971 0.00641391 0.0584952 0.0349971 0.00641391 0.0586217 0.0349971 -0.00512201 0.0586217 0.0294971 -0.00512201 0.0521975 0.0294971 -0.0271672 0.0521975 0.0349971 -0.0271672 0.037826 0.0294971 -0.0450758 0.0458936 0.0349971 -0.0368292 0.0176951 0.0294971 -0.0561215 0.00640549 0.0294971 -0.0584961 -0.00513043 0.0294971 -0.0586226 -0.0164694 0.0294971 -0.0564961 -0.00513043 0.0349971 -0.0586226 0.0489561 0.0355971 0.0694253 0.0489561 0.0410971 0.0694253 0.0597147 0.0410971 0.0604198 0.0597147 0.0355971 0.0604198 0.0688444 0.0410971 0.0497663 0.0688444 0.0355971 0.0497663 0.076096 0.0410971 0.0377554 0.0812718 0.0410971 0.0247147 0.0842306 0.0410971 0.011 0.083237 0.0355971 -0.0169469 0.0793117 0.0355971 -0.0304169 0.0552734 0.0355971 -0.0645008 0.0313337 0.0410971 -0.0789545 0.00399798 0.0355971 -0.0848519 0.0179102 0.0410971 -0.0830358 0.00399798 0.0410971 -0.0848519 -0.0100234 0.0355971 -0.0843534 -0.0100234 0.0410971 -0.0843534 0.0780346 0.0400971 -0.0215392 0.0775234 0.0400971 -0.0215089 0.0781743 0.0397971 -0.0210599 0.0770497 0.0400971 -0.0217035 0.0767072 0.0400971 -0.0220843 0.076271 0.0397971 -0.0218414 0.076564 0.0400971 -0.0225759 0.0766482 0.0400971 -0.0230811 0.0769433 0.0400971 -0.0234996 0.0761863 0.0397971 -0.0232707 0.0766094 0.0397971 -0.0238709 0.0773907 0.0400971 -0.0237487 0.079086 0.0397971 0.020833 0.0782321 0.0397971 0.0208516 0.0770403 0.0397971 0.0197105 0.0775067 0.0400971 0.0189753 0.0774325 0.0397971 0.0181079 0.0777932 0.0400971 0.0184531 0.0582782 0.0400971 0.0571201 0.0578045 0.0400971 0.0569256 0.0581961 0.0397971 0.0576126 0.0575168 0.0397971 0.0573337 0.0570258 0.0397971 0.0567876 0.057403 0.0400971 0.055548 0.0581456 0.0400971 0.0548803 0.0573643 0.0397971 0.0547581 0.0188482 0.0397971 -0.0770226 0.0180994 0.0397971 -0.0774335 0.0181357 0.0400971 -0.0783034 0.0181228 0.0400971 -0.0788989 0.0176378 0.0397971 -0.0790176 0.0184093 0.0400971 -0.0794211 0.0189186 0.0400971 -0.0797301 0.0557874 0.0400971 -0.0573334 0.0564383 0.0397971 -0.0568843 0.0549712 0.0400971 -0.0579087 0.054828 0.0400971 -0.0584004 0.0543295 0.0397971 -0.0583709 0.0549122 0.0400971 -0.0589055 0.0544503 0.0397971 -0.0590952 0.0552073 0.0400971 -0.0593241 0.0548734 0.0397971 -0.0596954 -0.0772604 0.0397971 0.0242356 -0.0785178 0.0400971 0.0234827 -0.0788268 0.0400971 0.0229734 -0.0793061 0.0397971 0.0231131 -0.0793247 0.0397971 0.0222592 -0.0785532 0.0400971 0.0218557 -0.0789138 0.0397971 0.0215104 -0.0794295 0.0400971 -0.0184102 -0.0797748 0.0397971 -0.0180496 -0.0797385 0.0400971 -0.0189195 -0.0802178 0.0397971 -0.0187798 -0.0794649 0.0400971 -0.0200372 -0.0802364 0.0397971 -0.0196337 -0.0798255 0.0397971 -0.0203825 -0.0592726 0.0400971 -0.0551464 -0.0588691 0.0397971 -0.0543749 -0.0595816 0.0400971 -0.0556556 -0.0600609 0.0397971 -0.0555159 -0.0595946 0.0400971 -0.0562511 -0.0596687 0.0397971 -0.0571186 -0.0587988 0.0400971 -0.0570823 -0.0195234 0.0400971 0.0797505 -0.0200456 0.0400971 0.079464 -0.0203546 0.0400971 0.0789547 -0.0208339 0.0397971 0.0790944 -0.020081 0.0400971 0.077837 -0.0562596 0.0400971 0.0595936 -0.0568172 0.0400971 0.0576801 -0.0570908 0.0400971 0.0587979 -0.0576331 0.0397971 0.0585735 -0.0567818 0.0400971 0.0593071 -0.0574277 0.0397971 0.0592785 -0.0571271 0.0397971 0.0596677 0.0168148 0.0384971 -0.0305793 0.0174192 0.0372971 -0.0286646 0.0168029 0.0384971 -0.0307795 0.0153148 0.0372971 -0.032133 0.0147919 0.0372971 -0.03118 0.016729 0.0384971 -0.0306746 0.0147354 0.0372971 -0.0305566 0.0167724 0.0384971 -0.0305967 0.0167418 0.0384971 -0.0306307 0.0149968 0.0372971 -0.0296593 0.0148156 0.0372971 -0.0300932 0.0163324 0.0372971 -0.0286409 0.0156217 0.0372971 -0.0289643 0.0153794 0.0372971 -0.0291638 0.0298895 0.0384971 -0.0182504 0.0285142 0.0372971 -0.0197132 0.0298231 0.0384971 -0.0181907 0.0298156 0.0384971 -0.0181455 0.0278785 0.0372971 -0.0186509 0.0279757 0.0372971 -0.0189493 0.0284014 0.0372971 -0.0196039 0.027822 0.0372971 -0.0180274 0.029859 0.0384971 -0.0180675 0.028466 0.0372971 -0.0166347 0.0280834 0.0372971 -0.0171302 0.0295729 0.0372971 -0.0160802 0.029419 0.0372971 -0.0161118 0.0287083 0.0372971 -0.0164352 0.0349701 0.0384971 -0.000656308 0.0349278 0.0384971 -0.000673697 0.0346416 0.0372971 0.00131362 0.0348972 0.0384971 -0.000707738 0.0348919 0.0384971 -0.000796845 0.0330444 0.0372971 -0.00155547 0.0349183 0.0384971 -0.000834261 0.0349583 0.0384971 -0.000856528 0.0306087 0.0384971 0.0169144 0.0305799 0.0384971 0.0168157 0.02864 0.0372971 0.0163409 0.0306055 0.0384971 0.016769 0.0300923 0.0372971 0.014824 0.0180764 0.0384971 0.0298556 0.0161109 0.0372971 0.0294274 0.0180519 0.0384971 0.0299555 0.0180796 0.0384971 0.030001 0.0169407 0.0372971 0.0316431 0.0176514 0.0372971 0.0319665 0.0181262 0.0384971 0.0300266 0.0181795 0.0384971 0.0300255 0.0178053 0.0372971 0.0319981 0.000728075 0.0384971 0.0348967 -0.000647258 0.0372971 0.0334339 -0.000760027 0.0372971 0.0335432 -0.00125928 0.0372971 0.035583 -0.00133947 0.0372971 0.0351196 0.000697586 0.0384971 0.0350795 -0.00069541 0.0372971 0.0365123 -0.001078 0.0372971 0.0360169 0.000666977 0.0384971 0.0350455 0.000411427 0.0372971 0.0370669 0.000739934 0.0384971 0.0350969 -0.0186759 0.0372971 0.0317097 -0.0189374 0.0372971 0.0308124 -0.0187836 0.0372971 0.0298905 -0.0169098 0.0384971 0.0306117 -0.0298988 0.0384971 0.0182579 -0.0299521 0.0384971 0.018259 -0.0304269 0.0372971 0.0201989 -0.0313799 0.0372971 0.019676 -0.0300264 0.0384971 0.0181879 -0.0300275 0.0384971 0.0181346 -0.0300019 0.0384971 0.018088 -0.0299564 0.0384971 0.0180603 -0.0314445 0.0372971 0.0167068 -0.0349676 0.0384971 0.000864027 -0.0364005 0.0372971 -0.00079629 -0.0365133 0.0372971 -0.000686994 -0.0350991 0.0384971 0.000771352 -0.036939 0.0372971 -3.24253e-05 -0.0350863 0.0384971 0.000815303 -0.0368312 0.0372971 0.0017867 -0.0370125 0.0372971 0.0013528 -0.0353418 0.0372971 0.00283667 -0.0350556 0.0384971 0.000849344 -0.0306604 0.0384971 -0.0167339 -0.0307136 0.0384971 -0.0167327 -0.0307879 0.0384971 -0.0168038 -0.0327053 0.0372971 -0.0162451 -0.0307891 0.0384971 -0.0168571 -0.0307179 0.0384971 -0.0169314 -0.0181845 0.0384971 -0.0298193 -0.0182343 0.0384971 -0.0299903 -0.0201026 0.0372971 -0.0307169 -0.0182588 0.0384971 -0.0298904 -0.0202563 0.0372971 -0.029795 -0.01937 0.0372971 -0.0282028 -0.0196123 0.0372971 -0.0284023 -0.0199949 0.0372971 -0.0288978 -0.000737409 0.0384971 -0.0348892 -0.000794966 0.0384971 -0.0350867 -0.000834965 0.0384971 -0.0350645 -0.00278233 0.0372971 -0.0344004 -0.00111161 0.0372971 -0.0329166 -0.00126544 0.0372971 -0.0329482 -0.000783108 0.0384971 -0.0348865 -0.00197615 0.0372971 -0.0332716 -0.00221845 0.0372971 -0.0334711 -0.000178662 0.0372971 -0.0329718 0.00117641 0.0372971 -0.0341903 -0.000666272 0.0384971 -0.0349635 -0.000667431 0.0384971 -0.0350167 0.00124995 0.0372971 -0.0355755 0.00133014 0.0372971 -0.0351121 -0.000266931 0.0372971 -0.0370278 0.000443777 0.0372971 -0.0367044 -0.0181888 0.0384971 -0.030018 -0.0180889 0.0384971 -0.0299935 -0.0180613 0.0384971 -0.029948 -0.0180601 0.0384971 -0.0298947 -0.0181312 0.0384971 -0.0298204 -0.0306299 0.0384971 -0.0169167 -0.0305993 0.0384971 -0.0168826 -0.0294792 0.0372971 -0.018549 -0.0305865 0.0384971 -0.0168387 -0.0285928 0.0372971 -0.0169568 -0.030594 0.0384971 -0.0167935 -0.0287465 0.0372971 -0.0160349 -0.029285 0.0372971 -0.0152711 -0.0349719 0.0384971 0.000665355 -0.0350252 0.0384971 0.000666514 -0.0349221 0.0384971 0.000836407 -0.0330538 0.0372971 0.00156297 -0.0329001 0.0372971 0.000641108 -0.0344971 0.0372971 -0.00127452 -0.0295822 0.0372971 0.0160877 -0.0287177 0.0372971 0.0164427 -0.0298684 0.0384971 0.018075 -0.0280928 0.0372971 0.0171377 -0.027985 0.0372971 0.0189568 -0.0298325 0.0384971 0.0181982 -0.0285235 0.0372971 0.0197207 -0.0168698 0.0384971 0.0305895 -0.0167699 0.0384971 0.0306139 -0.0167411 0.0384971 0.0307127 -0.0148249 0.0372971 0.0301007 -0.0148012 0.0372971 0.0311875 -0.0167667 0.0384971 0.0307594 -0.0153241 0.0372971 0.0321405 0.000781309 0.0384971 0.0348956 0.00082799 0.0384971 0.0349212 0.00220912 0.0372971 0.0334786 0.000855611 0.0384971 0.0349667 0.000856769 0.0384971 0.0350199 0.00277299 0.0372971 0.0344079 0.000785633 0.0384971 0.0350942 0.00227374 0.0372971 0.0364477 0.0181219 0.0384971 0.0298279 0.0182195 0.0384971 0.0300032 0.0196676 0.0372971 0.031379 0.0182458 0.0384971 0.0299658 0.0201905 0.0372971 0.030426 0.0200933 0.0372971 0.0307244 0.0182406 0.0384971 0.0298767 0.019603 0.0372971 0.0284098 0.0184961 0.0372971 0.0278553 0.0181676 0.0384971 0.0298252 0.01821 0.0384971 0.0298426 0.0186499 0.0372971 0.0278869 0.0193607 0.0372971 0.0282103 0.0306967 0.0384971 0.0167386 0.0310252 0.0372971 0.0147687 0.0307391 0.0384971 0.016756 0.0307697 0.0384971 0.0167901 0.030775 0.0384971 0.0168792 0.0307486 0.0384971 0.0169166 0.0320839 0.0372971 0.0184017 0.0307086 0.0384971 0.0169389 0.0312673 0.0372971 0.0188562 0.0343995 0.0372971 -0.00277391 0.0354863 0.0372971 -0.00279756 0.0350582 0.0384971 -0.000832073 0.0350858 0.0384971 -0.00078655 0.0370032 0.0372971 -0.0013453 0.0370268 0.0372971 -0.000258514 0.035087 0.0384971 -0.000733316 0.0314352 0.0372971 -0.0166993 0.0299926 0.0384971 -0.0180805 0.030017 0.0384971 -0.0181804 0.0299894 0.0384971 -0.0182259 0.0311283 0.0372971 -0.019868 0.0313706 0.0372971 -0.0196685 0.0169028 0.0384971 -0.030755 0.0188478 0.0372971 -0.0312683 0.0169305 0.0384971 -0.0307095 0.0183486 0.0372971 -0.0292285 0.0168605 0.0384971 -0.030582 -0.00626233 0.0292971 0.0571119 -0.0172833 0.0292971 0.0547938 -0.0176443 0.0292971 0.0559382 -0.0276404 0.0292971 0.0503701 -0.0369353 0.0292971 0.0440109 -0.045747 0.0292971 0.0367115 -0.0520294 0.0292971 0.0270823 -0.0563125 0.0292971 0.0164125 -0.0572363 0.0292971 0.00500758 -0.0571128 0.0292971 -0.00625392 -0.0584318 0.0292971 0.00511209 -0.0440118 0.0292971 -0.0369269 -0.0514231 0.0292971 -0.0282092 -0.0270832 0.0292971 -0.052021 -0.0164134 0.0292971 -0.0563041 -0.00500849 0.0292971 -0.0572279 0.0176349 0.0292971 -0.0559307 0.0282083 0.0292971 -0.0514147 0.036926 0.0292971 -0.0440034 0.0376974 0.0292971 -0.0449226 0.0448018 0.0292971 -0.035953 0.0457377 0.0292971 -0.036704 0.0509556 0.0292971 -0.0265208 0.0520201 0.0292971 -0.0270748 0.0551511 0.0292971 -0.0160693 0.0582964 0.0292971 0.00639212 0.0547854 0.0292971 0.0172824 0.0503617 0.0292971 0.0276394 0.0514137 0.0292971 0.0282167 0.0160684 0.0292971 0.0551595 0.00510368 0.0292971 0.0584309 0.0829227 0.0412971 -0.00187579 0.0824115 0.0412971 -0.00258441 0.0826736 0.0412971 -0.00273033 0.0820785 0.0412971 -0.00339219 0.0812058 0.0412971 -0.00343438 0.0812551 0.0412971 -0.0037303 0.0803666 0.0412971 -0.00367767 0.0796982 0.0412971 -0.00293318 0.0792749 0.0412971 -0.0021617 0.0794815 0.0412971 -0.00314065 0.0789835 0.0412971 -0.00223302 0.079006 0.0412971 -0.00119799 0.0797505 0.0412971 -0.000529588 0.0795431 0.0412971 -0.00031289 0.080522 0.0412971 -0.000106281 0.0814018 0.0412971 -0.000125427 0.0822634 0.0412971 -0.000270339 0.069044 0.0412971 0.0395034 0.069581 0.0412971 0.0403885 0.07056 0.0412971 0.0405951 0.0704887 0.0412971 0.0408865 0.0714398 0.0412971 0.040576 0.0715237 0.0412971 0.040864 0.0724088 0.0412971 0.040327 0.0726154 0.0412971 0.039348 0.0728843 0.0412971 0.0383843 0.0723472 0.0412971 0.0374992 0.0713683 0.0412971 0.0372926 0.0714396 0.0412971 0.0370012 0.0704046 0.0412971 0.0370237 0.0704885 0.0412971 0.0373117 0.0697362 0.0412971 0.0377682 0.0695195 0.0412971 0.0375607 0.0690215 0.0412971 0.0384684 0.0783293 0.0412971 0.00660275 0.0792201 0.0412971 0.00744763 0.0791625 0.0412971 0.00752936 0.0803152 0.0412971 0.00800271 0.0803316 0.0412971 0.00790407 0.0815591 0.0412971 0.00792903 0.0827983 0.0412971 0.0071772 0.0833679 0.0412971 0.00448545 0.0814176 0.0412971 0.00261826 0.0814414 0.0412971 0.00252112 0.0799924 0.0412971 0.00255266 0.0789036 0.0412971 0.00315876 0.0782781 0.0412971 0.00421524 0.0780805 0.0412971 0.00540048 0.0759351 0.0412971 0.0347492 0.0766531 0.0412971 0.0337307 0.0766855 0.0412971 0.033309 0.076858 0.0412971 0.0325016 0.0766551 0.0412971 0.0319117 0.0759301 0.0412971 0.0307168 0.0765094 0.0412971 0.0313052 0.0745235 0.0412971 0.0299052 0.0732796 0.0412971 0.0299789 0.0720404 0.0412971 0.0307308 0.0721126 0.0412971 0.0307999 0.0714403 0.0412971 0.0320252 0.0713432 0.0412971 0.0320014 0.073421 0.0412971 0.0352897 0.0733972 0.0412971 0.0353868 0.0668906 0.0412971 0.0475926 0.065779 0.0412971 0.0471362 0.0646465 0.0412971 0.0457128 0.0646394 0.0412971 0.0450891 0.0653122 0.0412971 0.0429931 0.0648371 0.0412971 0.0439038 0.0665513 0.0412971 0.0422412 0.0665793 0.0412971 0.0423372 0.0680004 0.0412971 0.0422097 0.0679766 0.0412971 0.0423068 0.0700229 0.0412971 0.044146 0.0700544 0.0412971 0.0455951 0.0699573 0.0412971 0.0455713 0.0693572 0.0412971 0.0468658 0.069285 0.0412971 0.0467966 0.0461948 0.0412971 0.0676134 0.047364 0.0412971 0.0679881 0.0485914 0.0412971 0.068013 0.0498306 0.0412971 0.0672612 0.0504002 0.0412971 0.0645695 0.0504963 0.0412971 0.0645415 0.0496753 0.0412971 0.0633746 0.0484737 0.0412971 0.0626051 0.0470247 0.0412971 0.0626367 0.0460028 0.0412971 0.0633171 0.0459359 0.0412971 0.0632428 0.0453104 0.0412971 0.0642992 0.0405007 0.0412971 0.0700381 0.0399896 0.0412971 0.0693295 0.0402386 0.0412971 0.0701841 0.0416571 0.0412971 0.071184 0.0424617 0.0412971 0.0708434 0.043214 0.0412971 0.0703869 0.0434307 0.0412971 0.0705944 0.0433692 0.0412971 0.0677666 0.0423902 0.0412971 0.06756 0.0424616 0.0412971 0.0672686 0.0408494 0.0412971 0.0679471 0.0414265 0.0412971 0.0672911 0.0406488 0.0412971 0.0677241 0.040136 0.0412971 0.0684516 0.0404135 0.0412971 0.0685655 -0.00329149 0.0412971 0.0826514 -0.00261917 0.0412971 0.0814261 -0.00264958 0.0412971 0.0800288 -0.00337456 0.0412971 0.0788339 -0.00362848 0.0412971 0.0784956 -0.00459986 0.0412971 0.0781616 -0.00793704 0.0412971 0.0809438 -0.00760086 0.0412971 0.0820974 -0.00792995 0.0412971 0.0815675 -0.00679743 0.0412971 0.082991 -0.00568588 0.0412971 0.0834474 -0.00445839 0.0412971 0.0834723 -0.0354631 0.0412971 0.0742369 -0.0351145 0.0412971 0.0754332 -0.0342813 0.0412971 0.0763599 -0.0319126 0.0412971 0.0766635 -0.0300454 0.0412971 0.0747132 -0.0300758 0.0412971 0.0733159 -0.0308008 0.0412971 0.0721211 -0.0320023 0.0412971 0.0713516 -0.0334234 0.0412971 0.0714792 -0.0334514 0.0412971 0.0713832 -0.0344733 0.0412971 0.0720636 -0.0351656 0.0412971 0.0730457 -0.0424839 0.0412971 0.0659812 -0.0444862 0.0412971 0.0646799 -0.0457137 0.0412971 0.0646549 -0.0456857 0.0412971 0.0647509 -0.0468806 0.0412971 0.0654759 -0.0475529 0.0412971 0.0667012 -0.0469528 0.0412971 0.0654067 -0.0475225 0.0412971 0.0680985 -0.0476185 0.0412971 0.0681265 -0.0467975 0.0412971 0.0692934 -0.0468667 0.0412971 0.0693656 -0.045596 0.0412971 0.0700628 -0.044147 0.0412971 0.0700313 -0.0424327 0.0412971 0.0683687 -0.0423402 0.0412971 0.0684067 -0.0421352 0.0412971 0.0671775 -0.0660811 0.0412971 0.0452243 -0.0648652 0.0412971 0.0450546 -0.067276 0.0412971 0.0459493 -0.0673483 0.0412971 0.0458801 -0.0679483 0.0412971 0.0471746 -0.0680455 0.0412971 0.0471508 -0.0671929 0.0412971 0.0497668 -0.0659914 0.0412971 0.0505362 -0.0634536 0.0412971 0.0498986 -0.0628281 0.0412971 0.0488421 -0.0626305 0.0412971 0.0476568 -0.0625307 0.0412971 0.0476509 -0.0629667 0.0412971 0.0465032 -0.0628793 0.0412971 0.0464546 -0.0637701 0.0412971 0.0456097 0.000184044 0.0412971 0.0802888 0.000271265 0.0412971 0.0817615 -0.000239879 0.0412971 0.0810528 0.000777127 0.0412971 0.082324 9.14305e-06 0.0412971 0.0819074 0.00147699 0.0412971 0.0826114 0.00142764 0.0412971 0.0829073 0.00223224 0.0412971 0.0825667 0.00340788 0.0412971 0.0813387 0.00369928 0.0412971 0.0814101 0.00338873 0.0412971 0.080459 0.00367675 0.0412971 0.080375 0.00293226 0.0412971 0.0797066 0.00313973 0.0412971 0.0794899 0.00119707 0.0412971 0.0790145 0.000419372 0.0412971 0.0794474 -0.0404301 0.0412971 0.0717994 -0.0406922 0.0412971 0.0719453 -0.0392244 0.0412971 0.0726494 -0.0400971 0.0412971 0.0726072 -0.0392737 0.0412971 0.0729453 -0.0384691 0.0412971 0.0726047 -0.0375001 0.0412971 0.0723557 -0.0372935 0.0412971 0.0713767 -0.0373127 0.0412971 0.0704969 -0.0370246 0.0412971 0.070413 -0.0377691 0.0412971 0.0697446 -0.0375617 0.0412971 0.0695279 -0.0384693 0.0412971 0.0690299 -0.0395043 0.0412971 0.0690524 -0.040282 0.0412971 0.0694854 -0.0406418 0.0412971 0.0710731 -0.0407949 0.0412971 0.0702128 -0.0409413 0.0412971 0.0710908 -0.0676396 0.0412971 0.0426402 -0.0677268 0.0412971 0.0411676 -0.0682327 0.0412971 0.040605 -0.0688832 0.0412971 0.0400217 -0.0708634 0.0412971 0.0415903 -0.0711548 0.0412971 0.041519 -0.0703878 0.0412971 0.0432224 -0.0686526 0.0412971 0.0439146 -0.0673621 0.0412971 0.0427542 0.00567655 0.0412971 -0.0834399 0.0058981 0.0412971 -0.0834964 0.0067881 0.0412971 -0.0829834 0.0079277 0.0412971 -0.0809363 0.00795215 0.0412971 -0.080111 0.00598782 0.0412971 -0.0781845 0.0060158 0.0412971 -0.0780885 0.00456675 0.0412971 -0.0780569 0.00459053 0.0412971 -0.0781541 0.00254424 0.0412971 -0.0799933 0.00251271 0.0412971 -0.0814423 0.00328215 0.0412971 -0.0826439 0.0352813 0.0412971 -0.0734219 0.0352509 0.0412971 -0.0748192 0.0354538 0.0412971 -0.0742294 0.034272 0.0412971 -0.0763524 0.0331193 0.0412971 -0.0768257 0.0308534 0.0412971 -0.0760716 0.0306362 0.0412971 -0.0760002 0.029939 0.0412971 -0.0747295 0.0302996 0.0412971 -0.0727506 0.031103 0.0412971 -0.0718571 0.0307223 0.0412971 -0.0720413 0.031993 0.0412971 -0.0713441 0.0322146 0.0412971 -0.0714006 0.0421259 0.0412971 -0.06717 0.0433077 0.0412971 -0.0650471 0.0444769 0.0412971 -0.0646724 0.0468713 0.0412971 -0.0654684 0.0475436 0.0412971 -0.0666937 0.0469435 0.0412971 -0.0653992 0.0476092 0.0412971 -0.068119 0.0475132 0.0412971 -0.068091 0.0467882 0.0412971 -0.0692859 0.0455629 0.0412971 -0.0699582 0.0468573 0.0412971 -0.0693581 0.0455867 0.0412971 -0.0700553 0.0441656 0.0412971 -0.0699278 0.0637031 0.0412971 -0.0455205 0.0648723 0.0412971 -0.0451458 0.0648559 0.0412971 -0.0450471 0.0672667 0.0412971 -0.0459418 0.067939 0.0412971 -0.0471671 0.0680046 0.0412971 -0.0485924 0.0672528 0.0412971 -0.0498315 0.064561 0.0412971 -0.0504012 0.0659821 0.0412971 -0.0505287 0.0635111 0.0412971 -0.0498167 0.0634443 0.0412971 -0.0498911 0.0628188 0.0412971 -0.0488346 -0.00361605 0.0412971 -0.0816868 -0.00351343 0.0412971 -0.0799543 -0.00274545 0.0412971 -0.0795376 -0.00129034 0.0412971 -0.079295 -0.00209493 0.0412971 -0.0789543 -0.000538004 0.0412971 -0.0797514 -0.000114697 0.0412971 -0.0805229 -0.000321307 0.0412971 -0.079544 -0.000133843 0.0412971 -0.0814027 0.000154176 0.0412971 -0.0814866 -0.00129047 0.0412971 -0.0828697 -0.00290262 0.0412971 -0.0821912 -0.00310321 0.0412971 -0.0824143 -0.00333853 0.0412971 -0.0815728 0.0409319 0.0412971 -0.0710833 0.0404208 0.0412971 -0.0717919 0.0406829 0.0412971 -0.0719378 0.0400878 0.0412971 -0.0725997 0.0384598 0.0412971 -0.0725972 0.0383759 0.0412971 -0.0728852 0.0374908 0.0412971 -0.0723482 0.0369928 0.0412971 -0.0714405 0.0375523 0.0412971 -0.0695204 0.0385313 0.0412971 -0.0693138 0.0384599 0.0412971 -0.0690224 0.039495 0.0412971 -0.0690449 0.0407855 0.0412971 -0.0702053 0.0708999 0.0412971 -0.0420875 0.0701823 0.0412971 -0.0433764 0.0694825 0.0412971 -0.0436638 0.0679749 0.0412971 -0.0431626 0.0686433 0.0412971 -0.0439071 0.0672602 0.0412971 -0.0424625 0.0675516 0.0412971 -0.0423912 0.0675707 0.0412971 -0.0415114 0.0687987 0.0412971 -0.0403357 0.0697624 0.0412971 -0.0400669 -0.0454583 0.0412971 -0.0666306 -0.0462617 0.0412971 -0.0675241 -0.0473733 0.0412971 -0.0679806 -0.0462041 0.0412971 -0.0676059 -0.0473568 0.0412971 -0.0680792 -0.0486008 0.0412971 -0.0680055 -0.05044 0.0412971 -0.0659592 -0.0498399 0.0412971 -0.0672537 -0.0505056 0.0412971 -0.064534 -0.0484831 0.0412971 -0.0625976 -0.0451221 0.0412971 -0.065477 -0.0452273 0.0412971 -0.0642537 -0.0450223 0.0412971 -0.0654829 -0.0453709 0.0412971 -0.0666792 -0.0689573 0.0412971 -0.0426334 -0.0665886 0.0412971 -0.0423297 -0.0653937 0.0412971 -0.0430547 -0.0647214 0.0412971 -0.04428 -0.0647518 0.0412971 -0.0456773 -0.0646558 0.0412971 -0.0457053 -0.0654077 0.0412971 -0.0469444 -0.0666783 0.0412971 -0.0476416 -0.0681274 0.0412971 -0.0476101 -0.0680994 0.0412971 -0.0475141 -0.0691493 0.0412971 -0.0469296 -0.0700393 0.0412971 -0.0447623 -0.0732889 0.0412971 -0.0299714 -0.0722001 0.0412971 -0.0305775 -0.0712772 0.0412971 -0.0328252 -0.0714497 0.0412971 -0.0320177 -0.0714801 0.0412971 -0.033415 -0.0748276 0.0412971 -0.0352518 -0.0760948 0.0412971 -0.034596 -0.0760086 0.0412971 -0.0306371 -0.0759395 0.0412971 -0.0307093 -0.0747142 0.0412971 -0.030037 -0.0747379 0.0412971 -0.0299399 -0.0733169 0.0412971 -0.0300674 -0.0791718 0.0412971 -0.00752186 -0.0801432 0.0412971 -0.00785593 -0.0815405 0.0412971 -0.00782552 -0.0828076 0.0412971 -0.0071697 -0.0834804 0.0412971 -0.00507371 -0.0831442 0.0412971 -0.00392008 -0.0823407 0.0412971 -0.00302656 -0.0814508 0.0412971 -0.00251363 -0.0402479 0.0412971 -0.0701766 -0.0416664 0.0412971 -0.0711765 -0.0415912 0.0412971 -0.070855 -0.042471 0.0412971 -0.0708359 -0.042555 0.0412971 -0.0711239 -0.0436467 0.0412971 -0.0696079 -0.0436275 0.0412971 -0.0687281 -0.043171 0.0412971 -0.0679758 -0.0424709 0.0412971 -0.0672611 -0.0415198 0.0412971 -0.0675717 -0.0406582 0.0412971 -0.0677166 -0.0695904 0.0412971 -0.040381 -0.0690533 0.0412971 -0.0394959 -0.0694881 0.0412971 -0.0397632 -0.0690308 0.0412971 -0.0384609 -0.0695288 0.0412971 -0.0375532 -0.0698368 0.0412971 -0.0376722 -0.0704979 0.0412971 -0.0373042 -0.071449 0.0412971 -0.0369937 -0.0713776 0.0412971 -0.0372851 -0.0721491 0.0412971 -0.0377084 -0.0726056 0.0412971 -0.0384607 -0.0724181 0.0412971 -0.0403195 -0.0722014 0.0412971 -0.040112 -0.0714491 0.0412971 -0.0405685 -0.071533 0.0412971 -0.0408565 -0.070498 0.0412971 -0.040879 -0.0792385 0.0412971 0.00166453 -0.078939 0.0412971 0.00164679 -0.0794501 0.0412971 0.000938168 -0.079956 0.0412971 0.000375581 -0.079188 0.0412971 0.00079225 -0.0806559 0.0412971 8.81941e-05 -0.0797832 0.0412971 0.000130383 -0.0814951 0.0412971 -0.000155093 -0.0825868 0.0412971 0.00136088 -0.0825676 0.0412971 0.00224065 -0.0828556 0.0412971 0.00232459 -0.0821111 0.0412971 0.00299299 -0.080376 0.0412971 0.00368517 -0.0797988 0.0412971 0.00302916 -0.0795983 0.0412971 0.00325224 -0.0793629 0.0412971 0.00241079 -0.0790854 0.0412971 0.00252475 -0.0557124 0.0400971 0.0573582 -0.0555937 0.0397971 0.0568732 -0.0551902 0.0400971 0.0576447 -0.0544019 0.0397971 0.0580143 -0.0551548 0.0400971 0.0592717 -0.0547942 0.0397971 0.059617 -0.0555244 0.0397971 0.06006 -0.0195718 0.0400971 0.077528 -0.0197115 0.0397971 0.0770487 -0.0189763 0.0400971 0.0775151 -0.0181088 0.0397971 0.077441 -0.0184541 0.0400971 0.0778016 -0.0181451 0.0400971 0.0783108 -0.0176657 0.0397971 0.0781712 -0.0181321 0.0400971 0.0789064 -0.0582033 0.0400971 -0.0570953 -0.0589385 0.0397971 -0.0575617 -0.0580846 0.0397971 -0.0575803 -0.0573358 0.0397971 -0.0571694 -0.057681 0.0400971 -0.0568088 -0.0573721 0.0400971 -0.0562995 -0.0573591 0.0400971 -0.055704 -0.057285 0.0397971 -0.0548365 -0.0789557 0.0400971 -0.0203462 -0.0790953 0.0397971 -0.0208255 -0.0779707 0.0400971 -0.0201819 -0.0783623 0.0397971 -0.0208689 -0.077192 0.0397971 -0.020044 -0.0769866 0.0397971 -0.019339 -0.0775692 0.0400971 -0.0188043 -0.0778643 0.0400971 -0.0183857 -0.0783118 0.0400971 -0.0181367 -0.0775305 0.0397971 -0.0180145 -0.0780439 0.0400971 0.0215467 -0.0781836 0.0397971 0.0210674 -0.0769526 0.0400971 0.0235071 -0.0761193 0.0397971 0.0230437 -0.0765733 0.0400971 0.0225834 -0.077059 0.0400971 0.021711 -0.0762803 0.0397971 0.0218489 -0.0775327 0.0400971 0.0215164 -0.0773297 0.0397971 0.0210488 -0.0767713 0.0397971 0.0213029 0.0567724 0.0400971 -0.0592996 0.0570814 0.0400971 -0.0587904 0.0570944 0.0400971 -0.0581948 0.0575608 0.0397971 -0.05893 0.0575793 0.0397971 -0.0580761 0.0568078 0.0400971 -0.0576726 0.0571685 0.0397971 -0.0573273 0.0562986 0.0400971 -0.0573637 0.0187789 0.0397971 -0.0802094 0.0195119 0.0397971 -0.0802528 0.0199035 0.0400971 -0.0795658 0.0201912 0.0397971 -0.0799739 0.0202459 0.0400971 -0.079185 0.0203892 0.0400971 -0.0786933 0.0195624 0.0400971 -0.0775205 0.0587411 0.0400971 0.0548673 0.0588598 0.0397971 0.0543824 0.0592633 0.0400971 0.0551539 0.0600516 0.0397971 0.0555234 0.0595852 0.0400971 0.0562586 0.0600702 0.0397971 0.0563773 0.0596593 0.0397971 0.0571261 0.0592987 0.0400971 0.0567809 0.0587894 0.0400971 0.0570898 0.0589291 0.0397971 0.0575692 0.0781627 0.0397971 0.0176648 0.0796298 0.0400971 0.0186892 0.0796888 0.0400971 0.019686 0.0801507 0.0397971 0.0198757 0.0793938 0.0400971 0.0201046 0.0797276 0.0397971 0.0204759 0.0785084 0.0400971 -0.0234752 0.0788174 0.0400971 -0.0229659 0.0793154 0.0397971 -0.0222517 0.0789045 0.0397971 -0.0215029 -0.077683 0.0349971 -0.02059 0.0252367 0.0349971 -0.0767357 0.0681864 0.0349971 -0.049644 0.037826 0.0349971 -0.0450758 -0.0368376 0.0349971 -0.0458946 0.0449462 0.0349971 0.0704268 -0.0691297 0.0349971 -0.0415518 -0.0681775 0.0349971 -0.0404928 -0.0680097 0.0349971 -0.0422022 -0.0665606 0.0349971 -0.0422337 -0.0716283 0.0349971 -0.0445493 -0.0654719 0.0349971 -0.0428398 -0.0647539 0.0349971 -0.0438583 -0.0645489 0.0349971 -0.0450875 -0.0613981 0.0349971 -0.0473154 -0.0657307 0.0349971 -0.0472104 0.000861345 0.0349971 0.0778624 -0.00336961 0.0349971 0.0828662 -0.00265163 0.0349971 0.0818478 -0.00445839 0.0349971 0.0834723 0.0235943 0.0349971 0.0809853 0.000995849 0.0349971 0.0840428 -0.00250628 0.0349971 0.0843166 0.0026519 0.0349971 0.0840068 0.0099433 0.0349971 0.0837651 0.00486487 0.0349971 0.0816954 -0.031038 0.0349971 0.0784375 -0.0320023 0.0349971 0.0713516 -0.0334514 0.0349971 0.0713832 -0.0358365 0.0349971 0.0717333 -0.0366333 0.0349971 0.0731855 -0.0345402 0.0349971 0.0719893 -0.0352581 0.0349971 0.0730077 -0.0374069 0.0349971 0.075608 -0.0380495 0.0349971 0.0740448 -0.0351145 0.0349971 0.0754332 -0.0342813 0.0349971 0.0763599 -0.0331286 0.0349971 0.0768332 -0.0411941 0.0349971 0.0736132 -0.0394711 0.0349971 0.074129 -0.0469528 0.0349971 0.0654067 -0.0422421 0.0349971 0.0665597 -0.0442647 0.0349971 0.0646234 -0.0548923 0.0349971 0.0640527 -0.045596 0.0349971 0.0700628 -0.03984 0.0349971 0.0679003 -0.038184 0.0349971 0.0678643 -0.0367318 0.0349971 0.0686611 -0.0422106 0.0349971 0.0680088 -0.0429078 0.0349971 0.0692794 -0.0419049 0.0349971 0.069757 -0.044147 0.0349971 0.0700313 -0.0417407 0.0349971 0.072529 -0.0681958 0.0349971 0.0496515 -0.0680455 0.0349971 0.0471508 -0.0673483 0.0349971 0.0458801 -0.0661091 0.0349971 0.0451283 -0.0646858 0.0349971 0.054145 -0.059943 0.0349971 0.0535374 -0.062606 0.0349971 0.0484822 -0.0626376 0.0349971 0.0470331 -0.0633894 0.0349971 0.045794 -0.0686858 0.0349971 0.0388381 -0.0646601 0.0349971 0.0450968 -0.066252 0.0349971 0.04321 -0.0673684 0.0349971 0.039379 -0.0715236 0.0349971 0.0397815 -0.0723204 0.0349971 0.0412337 -0.072715 0.0349971 0.0427604 0.0660998 0.0349971 -0.0451208 0.0643235 0.0349971 -0.0442507 0.0648559 0.0349971 -0.0450471 0.0680361 0.0349971 -0.0471433 0.0672528 0.0349971 -0.0498315 0.0646765 0.0349971 -0.0541375 0.0614875 0.0349971 -0.0539827 0.0634443 0.0349971 -0.0498911 0.0627263 0.0349971 -0.0488726 0.0599336 0.0349971 -0.0535299 0.0637031 0.0349971 -0.0455205 0.0421259 0.0349971 -0.06717 0.0476407 0.0349971 -0.0666699 0.0469435 0.0349971 -0.0653992 0.0473145 0.0349971 -0.0613897 0.0476092 0.0349971 -0.068119 0.054883 0.0349971 -0.0640452 0.0435923 0.0349971 -0.0722059 0.0353784 0.0349971 -0.0733982 0.0380402 0.0349971 -0.0740373 0.0364725 0.0349971 -0.0760511 0.0399885 0.0349971 -0.0742625 0.0321981 0.0349971 -0.071302 0.0273636 0.0349971 -0.069437 0.0353469 0.0349971 -0.0748472 0.034595 0.0349971 -0.0760863 0.0310286 0.0349971 -0.07843 0.0263578 0.0349971 -0.0728885 0.0300686 0.0349971 -0.0751274 0.0302122 0.0349971 -0.0727019 0.0060158 0.0349971 -0.0780885 0.00321738 0.0349971 -0.0764738 0.00329608 0.0349971 -0.0787542 0.0129494 0.0349971 -0.0793098 0.00276457 0.0349971 -0.0780276 0.00251271 0.0349971 -0.0814423 0.00396971 0.0349971 -0.0842526 0.000974609 0.0349971 -0.0843406 0.00444906 0.0349971 -0.0834648 0.00320992 0.0349971 -0.082713 0.00725494 0.0349971 -0.0788403 0.0177836 0.0349971 -0.0824493 0.0441376 0.0349971 -0.0700238 0.0420076 0.0349971 -0.0718603 0.0411848 0.0349971 -0.0736057 0.0310868 0.0349971 -0.0566608 0.0381747 0.0349971 -0.0678568 0.0398307 0.0349971 -0.0678928 0.0358272 0.0349971 -0.0717258 0.0346812 0.0349971 -0.0721275 0.0660946 0.0349971 -0.0427478 0.0684611 0.0349971 -0.0300522 0.0669899 0.0349971 -0.0396756 0.0690798 0.0349971 -0.0456367 0.0683076 0.0349971 -0.0450592 0.0668914 0.0349971 -0.0442 0.0723973 0.0349971 -0.0421762 0.0719988 0.0349971 -0.0435435 0.0705932 0.0349971 -0.0461575 0.0697292 0.0349971 -0.0451434 0.0827121 0.0349971 0.00321834 0.0786147 0.0349971 -0.00397051 0.0778179 0.0349971 -0.00251831 0.0787132 0.0349971 0.000553899 0.0787532 0.0349971 0.00330449 0.0801654 0.0349971 0.00135071 0.0814414 0.0349971 0.00252112 0.0793089 0.0349971 0.0129578 0.0788394 0.0349971 0.00726335 0.0835217 0.0349971 0.0117628 0.0801101 0.0349971 0.00796056 0.0836357 0.0349971 0.0109224 0.0745235 0.0349971 0.0299052 0.0713432 0.0349971 0.0320014 0.0733972 0.0349971 0.0353868 0.076858 0.0349971 0.0325016 0.0806978 0.0349971 0.0245402 0.0410908 0.0349971 0.0661391 0.0202851 0.0349971 0.0696297 0.0388778 0.0349971 0.0684505 0.0224166 0.0349971 0.0769439 0.00482883 0.0349971 0.0800393 0.0451805 0.0349971 0.0690221 0.0459284 0.0349971 0.0700923 0.044782 0.0349971 0.0676548 0.043797 0.0349971 0.0627781 0.0438298 0.0349971 0.0665958 0.0389139 0.0349971 0.0701065 0.0412253 0.0349971 0.0723195 0.042752 0.0349971 0.0727141 0.0740724 0.0349971 0.0397046 0.0740364 0.0349971 0.0380486 0.0755585 0.0349971 0.0374888 0.068118 0.0349971 0.0476176 0.0702034 0.0349971 0.0420521 0.0687512 0.0349971 0.0412553 0.0680004 0.0349971 0.0422097 0.0693572 0.0349971 0.0468658 0.0683581 0.0349971 0.0494148 0.0700544 0.0349971 0.0455951 0.0718594 0.0349971 0.0420161 0.0736237 0.0349971 0.0411594 0.0647445 0.0349971 0.0438658 0.060383 0.0349971 0.0438714 0.0678919 0.0349971 0.0398391 0.0842921 0.0349971 -0.00299328 0.0840344 0.0349971 -0.000996766 0.0841822 0.0349971 0.00524679 0.0834639 0.0349971 0.00445748 0.0832376 0.0349971 0.000455435 -0.017339 0.0349971 0.0642861 -0.0310961 0.0349971 0.0566683 -0.0449117 0.0349971 0.0491571 -0.064287 0.0349971 -0.0173306 -0.061451 0.0349971 -0.00759857 -0.0566692 0.0349971 -0.0310877 -0.0164694 0.0349971 -0.0564961 0.00640549 0.0349971 -0.0584961 0.0497979 0.0349971 -0.0400178 0.0469619 0.0349971 -0.0497497 0.0564952 0.0349971 -0.016461 0.0539355 0.0349971 -0.0258192 0.0700689 0.0349971 0.0358716 0.069436 0.0349971 0.0273721 0.0663371 0.0349971 0.0167379 0.0515891 0.0349971 0.0283129 0.0561206 0.0349971 0.0177035 0.0593635 0.0349971 -0.00719261 0.01646 0.0349971 0.0565036 0.0271663 0.0349971 0.0522059 -0.0800402 0.0349971 0.00483725 -0.0787959 0.0349971 0.00414456 -0.0779754 0.0349971 0.00298057 -0.0777411 0.0349971 0.00157584 -0.0764822 0.0349971 -0.0032183 -0.0781395 0.0349971 0.000208576 -0.0804091 0.0349971 -0.00139137 -0.0818308 0.0349971 -0.00130717 -0.0843486 0.0349971 -0.00100573 -0.0840438 0.0349971 0.00100427 -0.0816963 0.0349971 0.00487329 -0.0786548 0.0349971 0.0128191 -0.0814401 0.0349971 0.0136308 -0.0700322 0.0349971 -0.0441385 -0.0721665 0.0349971 -0.0436723 -0.0680133 0.0349971 -0.0377208 -0.0755679 0.0349971 -0.0374813 -0.076792 0.0349971 -0.0333253 -0.0747379 0.0349971 -0.0299399 -0.0714821 0.0349971 -0.031596 -0.0712772 0.0349971 -0.0328252 -0.0731864 0.0349971 -0.0366249 -0.073633 0.0349971 -0.0411519 -0.0732849 0.0349971 -0.0411493 -0.0742893 0.0349971 -0.0399552 -0.0740817 0.0349971 -0.0396971 -0.047034 0.0349971 -0.0626292 -0.0366109 0.0349971 -0.0759891 -0.0443068 0.0349971 -0.0714167 -0.0505371 0.0349971 -0.065983 -0.0427562 0.0349971 -0.0660955 -0.0535383 0.0349971 -0.0599345 -0.0539911 0.0349971 -0.0614884 -0.0236036 0.0349971 -0.0809778 -0.0391994 0.0349971 -0.0707602 -0.0486196 0.0349971 -0.0689274 -0.0761379 0.0349971 0.0221898 -0.0781836 0.0349971 0.0210674 -0.0843014 0.0349971 0.00300078 -0.0840077 0.0349971 0.00266032 -0.0789138 0.0349971 0.0215104 -0.0826584 0.0349971 0.0168347 -0.0787608 0.0349971 0.0302095 -0.0760121 0.0349971 0.0322574 0.0470247 0.0349971 0.0626367 0.0457856 0.0349971 0.0633885 0.0450884 0.0349971 0.0646592 0.0451199 0.0349971 0.0661082 0.0458717 0.0349971 0.0673473 0.0461073 0.0349971 0.0706339 0.0446015 0.0349971 0.071055 0.0475709 0.0349971 0.0696564 0.0486103 0.0349971 0.0689349 0.0485914 0.0349971 0.068013 0.0506032 0.0349971 0.0651593 0.0482686 0.0349971 0.062563 0.0596086 0.0349971 0.0547932 0.0625099 0.0349971 0.0511702 0.0668741 0.0349971 0.0476913 0.0683053 0.0349971 0.0494877 0.0580059 0.0349971 0.054401 0.0573643 0.0349971 0.0547581 0.0581961 0.0349971 0.0576126 0.053529 0.0349971 0.059942 0.0638305 0.0349971 0.0551399 0.0600516 0.0349971 0.0555234 0.0518758 0.0349971 0.0542691 0.0569412 0.0349971 0.0553583 0.0570258 0.0349971 0.0567876 0.0770217 0.0349971 0.0188566 0.0756762 0.0349971 0.0303786 0.0808397 0.0349971 0.0240683 0.0728876 0.0349971 0.0263662 0.0770403 0.0349971 0.0197105 0.0817736 0.0349971 0.0206733 0.0808627 0.0349971 0.012505 0.0825404 0.0349971 0.01736 0.0774413 0.0349971 -0.0210164 0.0839984 0.0349971 -0.00265282 0.0786454 0.0349971 -0.0128116 0.0831587 0.0349971 -0.0140953 0.0826491 0.0349971 -0.0168272 0.0781743 0.0349971 -0.0210599 0.0789045 0.0349971 -0.0215029 0.0781049 0.0349971 -0.0242467 0.0760655 0.0349971 -0.0225464 0.0732174 0.0349971 -0.0314382 0.076271 0.0349971 -0.0218414 0.076762 0.0349971 -0.0212954 0.0641289 0.0349971 -0.054785 0.0602944 0.0349971 -0.0589789 0.0557052 0.0349971 -0.0568409 0.0575793 0.0349971 -0.0580761 0.0578677 0.0349971 -0.0613616 0.0575608 0.0349971 -0.05893 0.0571177 0.0349971 -0.0596602 0.0548734 0.0349971 -0.0596954 0.054535 0.0349971 -0.0576659 0.0187789 0.0349971 -0.0802094 0.0146025 0.0349971 -0.0736368 0.024218 0.0349971 -0.0807934 0.0195119 0.0349971 -0.0802528 0.0124966 0.0349971 -0.0808636 0.000545483 0.0349971 -0.0787141 -0.00266123 0.0349971 -0.0839993 -0.0047261 0.0349971 -0.0821426 -0.0593023 0.0349971 -0.0599855 -0.0593585 0.0349971 -0.0599299 -0.0614284 0.0349971 -0.0578067 -0.0600609 0.0349971 -0.0555159 -0.0596179 0.0349971 -0.0547857 -0.0625193 0.0349971 -0.0511627 -0.0580152 0.0349971 -0.0543935 -0.0580846 0.0349971 -0.0575803 -0.0589385 0.0349971 -0.0575617 -0.0596687 0.0349971 -0.0571186 -0.0568741 0.0349971 -0.0555853 -0.0573358 0.0349971 -0.0571694 -0.0638398 0.0349971 -0.0551324 -0.0808491 0.0349971 -0.0240608 -0.0807071 0.0349971 -0.0245327 -0.0760086 0.0349971 -0.0306371 -0.0790953 0.0349971 -0.0208255 -0.0802178 0.0349971 -0.0187798 -0.0797748 0.0349971 -0.0180496 -0.0827924 0.0349971 -0.00137945 -0.0834733 0.0349971 -0.00444998 -0.0815684 0.0349971 -0.00792153 -0.0791718 0.0349971 -0.00752186 -0.0827214 0.0349971 -0.00321084 -0.0511711 0.0349971 0.0625183 -0.0548449 0.0349971 0.0572841 -0.0645424 0.0349971 0.0505047 -0.0641382 0.0349971 0.0547925 -0.0576331 0.0349971 0.0585735 -0.0569367 0.0349971 0.0598245 -0.0188576 0.0349971 0.0770301 -0.0197115 0.0349971 0.0770487 -0.018058 0.0349971 0.0797739 -0.0203909 0.0349971 0.0798246 -0.0208339 0.0349971 0.0790944 -0.025246 0.0349971 0.0767432 -0.0207567 0.0349971 0.0817612 -0.0146119 0.0349971 0.0736443 0.016505 0.0349971 0.0566579 0.018632 0.0349971 0.0639567 0.0421438 0.0349971 0.0571051 0.0396746 0.0349971 0.0669983 -0.0129587 0.0349971 0.0793173 -0.00602513 0.0349971 0.078096 0.0497488 0.0349971 0.0469703 0.0566598 0.0349971 0.0310952 0.0597828 0.0349971 0.0418119 0.0491487 0.0349971 0.0449108 0.0450749 0.0349971 0.0378344 0.0394167 0.0349971 0.0477468 0.0400168 0.0349971 0.0498063 -0.0279731 0.0349971 0.067385 -0.0167388 0.0349971 0.0663455 -0.027373 0.0349971 0.0694444 0.0684421 0.0349971 -0.0388787 -0.0723446 0.0349971 0.0109802 -0.0732267 0.0349971 0.0314457 0.0627696 0.0349971 -0.0437979 0.0738891 0.0349971 -0.0114255 0.0723353 0.0349971 -0.0109727 0.0669073 0.0349971 -0.0295994 0.0628151 0.0349971 -0.00819844 -0.0781721 0.0349971 -0.0176573 -0.0793182 0.0349971 -0.0129503 -0.0666716 0.0349971 0.00932705 -0.0669166 0.0349971 0.0296069 -0.05427 0.0349971 0.0518842 0.043863 0.0349971 -0.0603839 0.0504134 0.0349971 -0.0507556 0.0532495 0.0349971 -0.0410236 0.0573871 0.0349971 -0.0268251 0.0697887 0.0349971 0.0157321 0.0732796 0.0349971 0.0299789 -0.0688339 0.0349971 -0.0365568 -0.0700782 0.0349971 -0.0358641 -0.0673859 0.0349971 -0.0279647 -0.058631 0.0349971 0.00512951 -0.0469712 0.0349971 0.0497572 -0.0418128 0.0349971 0.0597912 -0.0378353 0.0349971 0.0450833 -0.0283138 0.0349971 0.0515975 -0.0177044 0.0349971 0.056129 -0.0694454 0.0349971 -0.0273646 -0.0767441 0.0349971 -0.0252376 -0.0736452 0.0349971 -0.0146035 -0.0663465 0.0349971 -0.0167304 -0.0708092 0.0349971 -0.00487147 -0.0635104 0.0349971 -0.00699842 -0.0593728 0.0349971 0.00720011 -0.0539448 0.0349971 0.0258267 -0.0612436 0.0349971 0.0279537 -0.0438723 0.0349971 0.0603914 -0.0457137 0.0349971 0.0646549 0.0283045 0.0349971 -0.05159 0.0176951 0.0349971 -0.0561215 0.0167295 0.0349971 -0.066338 0.0157237 0.0349971 -0.0697896 -0.050764 0.0349971 -0.0504144 -0.0497582 0.0349971 -0.0469628 -0.0603923 0.0349971 -0.0438639 -0.0450842 0.0349971 -0.0378269 0.0069975 0.0349971 -0.063502 -0.0518851 0.0349971 -0.0542616 -0.0186413 0.0349971 -0.0639492 -0.0271756 0.0349971 -0.0521984 -0.000870678 0.0349971 -0.0778549 -0.0207473 0.0349971 -0.071176 -0.0202945 0.0349971 -0.0696222 0.00487055 0.0349971 -0.0708008 0.00599167 0.0349971 -0.0669536 -0.0175202 0.0349971 -0.060102 -0.0165143 0.0349971 -0.0566504 -0.0407416 0.0379971 0.071079 -0.0406098 0.0379971 0.0702888 -0.0419395 0.0379971 0.0711499 -0.0417199 0.0379971 0.069833 -0.0394484 0.0379971 0.0692444 -0.0409506 0.0379971 0.0687418 -0.0368701 0.0379971 0.0688056 -0.0371964 0.0379971 0.0714005 -0.0376446 0.0379971 0.0722174 -0.0381054 0.0379971 0.0738528 -0.0399819 0.0379971 0.0724437 -0.0394382 0.0379971 0.0739317 -0.0406733 0.0379971 0.0734245 -0.041566 0.0379971 0.0724317 -0.0489654 0.0410971 -0.0694178 -0.0489654 0.0355971 -0.0694178 -0.0597241 0.0355971 -0.0604123 -0.0688537 0.0410971 -0.0497588 -0.0761054 0.0355971 -0.0377479 -0.08424 0.0355971 -0.0109925 -0.084901 0.0410971 0.0030221 -0.084901 0.0355971 0.0030221 -0.0832464 0.0355971 0.0169544 -0.0832464 0.0410971 0.0169544 -0.079321 0.0410971 0.0304244 -0.0651459 0.0410971 0.0545301 -0.0552827 0.0410971 0.0645083 -0.0552827 0.0355971 0.0645083 -0.031343 0.0355971 0.078962 -0.031343 0.0410971 0.078962 -0.0179195 0.0355971 0.0830433 -0.00400731 0.0355971 0.0848594 0.0100141 0.0410971 0.0843609 -0.0368376 0.0294971 -0.0458946 -0.0515984 0.0349971 -0.0283054 -0.0561299 0.0349971 -0.017696 -0.0585045 0.0349971 -0.00640641 -0.0565045 0.0349971 0.0164685 -0.0565045 0.0294971 0.0164685 -0.0522068 0.0349971 0.0271747 -0.045903 0.0294971 0.0368367 -0.045903 0.0349971 0.0368367 -0.0283138 0.0294971 0.0515975 -0.0177044 0.0294971 0.056129 -0.00641483 0.0349971 0.0585036 0.0051211 0.0349971 0.0586301 0.0411468 0.0351971 0.0663311 0.0424795 0.0351971 0.0662521 0.0426993 0.0351971 0.0662973 0.0448663 0.0379971 0.0683719 0.0449001 0.0351971 0.0699245 0.0449001 0.0379971 0.0699245 0.0428254 0.0351971 0.0720915 0.0428254 0.0379971 0.0720915 0.0401892 0.0379971 0.0693177 0.0399114 0.0379971 0.0713782 0.0412728 0.0379971 0.0721252 0.04169 0.0379971 0.0709867 0.044153 0.0379971 0.0712859 0.0424897 0.0379971 0.0709394 0.0432863 0.0379971 0.0704561 0.0437345 0.0379971 0.0696392 0.0440607 0.0379971 0.0670443 0.0426993 0.0379971 0.0662973 0.0411468 0.0379971 0.0663311 0.0398191 0.0379971 0.0671366 0.0407825 0.0379971 0.0678728 0.0391059 0.0379971 0.0700506 0.0716774 0.0351971 0.0360299 0.0714576 0.0379971 0.0359847 0.0726927 0.0379971 0.0364919 0.0735854 0.0379971 0.0374847 0.0735854 0.0351971 0.0374847 0.0738443 0.0351971 0.0381045 0.0739589 0.0351971 0.0387665 0.0738781 0.0351971 0.0396571 0.0737393 0.0379971 0.0400834 0.0731311 0.0351971 0.0410185 0.0726923 0.0379971 0.0384403 0.0722089 0.0379971 0.0376437 0.0713921 0.0379971 0.0371955 0.0704605 0.0379971 0.0372157 0.0697606 0.0379971 0.0376054 0.0739589 0.0379971 0.0387665 0.0722643 0.0379971 0.0401886 0.07297 0.0379971 0.0411746 0.0706681 0.0379971 0.0407193 0.0702509 0.0379971 0.0418578 0.0693914 0.0379971 0.0398194 0.0691673 0.0379971 0.0390503 0.0800868 0.0351971 -0.00463774 0.0826547 0.0379971 -0.00420952 0.0830008 0.0351971 -0.00392451 0.0835474 0.0379971 -0.00321672 0.0838064 0.0351971 -0.00259686 0.0839209 0.0351971 -0.00193491 0.0839209 0.0379971 -0.00193491 0.0837013 0.0379971 -0.000617974 0.0830931 0.0351971 0.000317124 0.082932 0.0379971 0.000473261 0.0817655 0.0379971 0.00112266 0.0804982 0.0379971 -9.14776e-06 0.0796814 0.0379971 -0.000457355 0.0802129 0.0379971 0.00115645 0.0788515 0.0379971 0.000409434 0.078046 0.0379971 -0.000918217 0.0804226 0.0379971 -0.00348566 0.0800868 0.0379971 -0.00463774 0.0814196 0.0379971 -0.00471668 0.0824989 0.0379971 -0.00263305 0.0825913 0.0379971 -0.0010738 0.0431057 0.0411471 0.0702832 0.0434916 0.0411471 0.0695798 0.0434742 0.0411471 0.0687776 0.0436373 0.0412971 0.0696154 0.0436182 0.0412971 0.0687357 0.0423546 0.0411471 0.0677057 0.0431617 0.0412971 0.0679833 0.043058 0.0411471 0.0680917 0.043058 0.0382471 0.0680917 0.0434742 0.0382471 0.0687776 0.0423546 0.0382471 0.0677057 0.042414 0.0379971 0.0674629 0.0432309 0.0379971 0.0679111 0.0437142 0.0379971 0.0687077 0.0434916 0.0382471 0.0695798 0.0431057 0.0382471 0.0702832 0.0424197 0.0382471 0.0706994 0.0713978 0.0411471 0.040432 0.0721921 0.0412971 0.0401195 0.0720837 0.0411471 0.0400158 0.0724522 0.0411471 0.0385102 0.0725963 0.0412971 0.0384682 0.0713326 0.0411471 0.0374383 0.0721398 0.0412971 0.0377159 0.0720361 0.0411471 0.0378242 0.0724697 0.0411471 0.0393123 0.0713326 0.0382471 0.0374383 0.0720361 0.0382471 0.0378242 0.0724522 0.0382471 0.0385102 0.0727125 0.0379971 0.0393718 0.0724697 0.0382471 0.0393123 0.0720837 0.0382471 0.0400158 0.0714677 0.0379971 0.040672 0.0819625 0.0411471 -0.000604959 0.0820628 0.0412971 -0.000493419 0.0824988 0.0412971 -0.00111179 0.08236 0.0411471 -0.00116876 0.0826232 0.0412971 -0.00185805 0.0822805 0.0411471 -0.00251145 0.0819057 0.0412971 -0.003147 0.0811811 0.0411471 -0.00328643 0.0804925 0.0411471 -0.00324564 0.0811811 0.0382471 -0.00328643 0.0818192 0.0411471 -0.0030244 0.0822805 0.0382471 -0.00251145 0.0824735 0.0411471 -0.00184918 0.0824735 0.0382471 -0.00184918 0.08236 0.0382471 -0.00116876 0.0813598 0.0411471 -0.000269437 0.0812223 0.0379971 -0.00353302 0.0819633 0.0379971 -0.00322873 0.0818192 0.0382471 -0.0030244 0.082723 0.0379971 -0.00186396 0.0819625 0.0382471 -0.000604959 0.0821297 0.0379971 -0.000419059 0.0814298 0.0379971 -2.94205e-05 0.0439919 0.0351971 0.0714421 0.0441257 0.0349971 0.0715908 0.044153 0.0351971 0.0712859 0.0447612 0.0351971 0.0703508 0.0449808 0.0351971 0.0690339 0.0448663 0.0351971 0.0683719 0.0446073 0.0351971 0.0677521 0.0440607 0.0351971 0.0670443 0.0437146 0.0351971 0.0667593 0.0425124 0.0349971 0.0660549 0.0732756 0.0349971 0.0411568 0.0737393 0.0351971 0.0400834 0.0731771 0.0349971 0.0366324 0.0717249 0.0349971 0.0358356 0.0726927 0.0351971 0.0364919 0.0730388 0.0351971 0.0367769 0.0837013 0.0351971 -0.000617974 0.0838402 0.0351971 -0.00104431 0.0800309 0.0349971 -0.00482975 0.0816394 0.0351971 -0.00467152 0.0816869 0.0349971 -0.00486579 0.0826547 0.0351971 -0.00420952 0.0831391 0.0349971 -0.00406898 0.0835474 0.0351971 -0.00321672 0.04845 0.0412971 0.0627023 0.049537 0.0410971 0.063519 0.0502082 0.0410971 0.0646254 0.0496139 0.0410971 0.0670537 0.0485635 0.0412971 0.067917 0.0497583 0.0412971 0.067192 0.0501207 0.0410971 0.0662745 0.0504307 0.0412971 0.0659667 0.0471086 0.0410971 0.0629247 0.0482193 0.0352971 0.0628589 0.0484024 0.0410971 0.0628965 0.0492485 0.0352971 0.0632815 0.0492485 0.0410971 0.0632815 0.0499924 0.0410971 0.0641088 0.0499924 0.0352971 0.0641088 0.0503037 0.0410971 0.065177 0.0503037 0.0352971 0.065177 0.0502364 0.0410971 0.0659192 0.0501207 0.0352971 0.0662745 0.0485075 0.0352971 0.067725 0.0494214 0.0349971 0.0630363 0.0502545 0.0349971 0.0639629 0.0503982 0.0349971 0.0663884 0.0494796 0.0352971 0.0671838 0.0496802 0.0349971 0.0674069 0.0680901 0.0412971 0.0475216 0.0691405 0.0410971 0.0466583 0.0699269 0.0412971 0.044174 0.0690636 0.0410971 0.0431236 0.0692019 0.0412971 0.0429791 0.067929 0.0410971 0.0425011 0.0666352 0.0352971 0.0425292 0.067929 0.0352971 0.0425011 0.0697348 0.0352971 0.04423 0.0697348 0.0410971 0.04423 0.069763 0.0410971 0.0455238 0.0691405 0.0352971 0.0466583 0.0690636 0.0352971 0.0431236 0.069271 0.0349971 0.0429069 0.0700229 0.0349971 0.044146 0.069763 0.0352971 0.0455238 0.0747624 0.0410971 0.0350673 0.0758687 0.0410971 0.034396 0.0760132 0.0412971 0.0345343 0.0746573 0.0410971 0.0302388 0.0747048 0.0412971 0.0300445 0.0733075 0.0412971 0.0300749 0.0733635 0.0352971 0.0302669 0.0733635 0.0410971 0.0302669 0.0757918 0.0410971 0.0308613 0.0762473 0.0352971 0.0314511 0.0764631 0.0410971 0.0319677 0.0764912 0.0410971 0.0332615 0.0759351 0.0349971 0.0347492 0.0748463 0.0349971 0.0353553 0.0757345 0.0352971 0.0345261 0.0758687 0.0352971 0.034396 0.0763755 0.0352971 0.0336167 0.0766531 0.0349971 0.0337307 0.0764912 0.0352971 0.0332615 0.0765586 0.0352971 0.0325193 0.0764631 0.0352971 0.0319677 0.0765094 0.0349971 0.0313052 0.0757918 0.0352971 0.0308613 0.0755034 0.0352971 0.0306238 0.0744741 0.0352971 0.0302012 0.0746573 0.0352971 0.0302388 0.082726 0.0412971 0.00710804 0.0833983 0.0412971 0.00588275 0.0831759 0.0410971 0.00454141 0.0826429 0.0412971 0.00329057 0.0813701 0.0410971 0.00281252 0.0800763 0.0352971 0.00284068 0.0825046 0.0410971 0.00343503 0.0825046 0.0352971 0.00343503 0.0832041 0.0410971 0.0058352 0.0825816 0.0410971 0.00696973 0.0832041 0.0352971 0.0058352 0.0814752 0.0352971 0.00764101 0.0813701 0.0352971 0.00281252 0.0831759 0.0352971 0.00454141 0.0825816 0.0352971 0.00696973 0.0834955 0.0349971 0.00590652 0.0827983 0.0349971 0.0071772 0.0815591 0.0349971 0.00792903 -0.00105273 0.0351971 -0.0838411 -3.74352e-05 0.0351971 -0.0833791 -0.00127249 0.0379971 -0.0838862 -3.74352e-05 0.0379971 -0.0833791 0.000308708 0.0351971 -0.0830941 0.000855263 0.0351971 -0.0823863 0.000855263 0.0379971 -0.0823863 0.00111424 0.0351971 -0.0817664 0.0012288 0.0379971 -0.0811045 0.00114803 0.0351971 -0.0802139 0.00100918 0.0379971 -0.0797875 0.000239919 0.0379971 -0.0786963 0.000401018 0.0351971 -0.0788524 -0.000100873 0.0379971 -0.0802433 -0.000926633 0.0379971 -0.0780469 -0.00219389 0.0379971 -0.0791787 -0.00384062 0.0379971 -0.0787601 -0.00464615 0.0379971 -0.0800878 -0.00349407 0.0379971 -0.0804235 -0.00351435 0.0379971 -0.081355 -0.00306614 0.0379971 -0.0821719 -0.00260528 0.0379971 -0.0838073 0.0380961 0.0351971 -0.0738453 0.0396487 0.0379971 -0.073879 0.0410101 0.0379971 -0.073132 0.0410101 0.0351971 -0.073132 0.0418156 0.0351971 -0.0718044 0.0397748 0.0351971 -0.0680849 0.0371386 0.0379971 -0.0708586 0.0360552 0.0379971 -0.0701257 0.0373627 0.0379971 -0.0700895 0.0411024 0.0379971 -0.0688904 0.0402356 0.0379971 -0.0697203 0.0418494 0.0379971 -0.0702518 0.0406838 0.0379971 -0.0705371 0.0418156 0.0379971 -0.0718044 0.0406635 0.0379971 -0.0714687 0.0401802 0.0379971 -0.0722652 0.0393634 0.0379971 -0.0727134 0.0384318 0.0379971 -0.0726932 0.0367685 0.0379971 -0.0730397 0.0377319 0.0379971 -0.0723035 0.0360214 0.0379971 -0.0716783 0.0696963 0.0379971 -0.0449461 0.0709314 0.0379971 -0.044439 0.0709314 0.0351971 -0.044439 0.0718241 0.0351971 -0.0434462 0.071978 0.0379971 -0.0408474 0.071978 0.0351971 -0.0408474 0.0712087 0.0379971 -0.0397562 0.0700422 0.0379971 -0.0391068 0.0684896 0.0379971 -0.039073 0.0671282 0.0379971 -0.03982 0.0662889 0.0379971 -0.0427002 0.0686993 0.0379971 -0.0437151 0.0694989 0.0379971 -0.0437625 0.0683635 0.0379971 -0.0448672 0.0718241 0.0379971 -0.0434462 0.0721976 0.0379971 -0.0421644 0.0709997 0.0379971 -0.0420934 0.0704064 0.0379971 -0.0406485 -0.000694046 0.0411471 -0.0820467 -0.000590313 0.0412971 -0.082155 -0.00139746 0.0411471 -0.0824327 -0.0013618 0.0412971 -0.0825783 -0.00224157 0.0412971 -0.0825592 -0.00219961 0.0411471 -0.0824152 -0.001511 0.0382471 -0.082456 -0.00139746 0.0382471 -0.0824327 -0.000694046 0.0382471 -0.0820467 -0.000411659 0.0382471 -0.081681 -0.000277853 0.0411471 -0.0813607 -0.000260396 0.0382471 -0.0805586 -0.000260396 0.0411471 -0.0805586 -0.00133231 0.0411471 -0.079439 -0.000646353 0.0411471 -0.0798552 -0.00126236 0.0379971 -0.079199 -0.00133231 0.0382471 -0.079439 -0.000729587 0.0382471 -0.0797745 -0.000562431 0.0379971 -0.0795886 -0.000646353 0.0382471 -0.0798552 -0.000332134 0.0382471 -0.0803383 3.08957e-05 0.0379971 -0.0810335 -0.000218667 0.0382471 -0.0810187 -0.000277853 0.0382471 -0.0813607 -0.000193225 0.0379971 -0.0818026 -0.000728843 0.0379971 -0.0823983 -0.000872887 0.0382471 -0.0821939 -0.00226955 0.0379971 -0.0826552 -0.00146987 0.0379971 -0.0827026 0.0391904 0.0411471 -0.0724939 0.0392151 0.0412971 -0.0726419 0.0398285 0.0411471 -0.0722319 0.0399149 0.0412971 -0.0723545 0.0400073 0.0411471 -0.0720847 0.0404235 0.0411471 -0.0713987 0.0406325 0.0412971 -0.0710656 0.0404827 0.0411471 -0.0710567 0.040441 0.0411471 -0.0705966 0.040508 0.0412971 -0.0703193 0.040055 0.0411471 -0.0698931 0.0400721 0.0412971 -0.0697009 0.0385018 0.0411471 -0.0724532 0.0385018 0.0382471 -0.0724532 0.0393039 0.0411471 -0.0724706 0.0402897 0.0411471 -0.071719 0.0400073 0.0382471 -0.0720847 0.0404235 0.0382471 -0.0713987 0.0403693 0.0411471 -0.0703763 0.040055 0.0382471 -0.0698931 0.0399718 0.0411471 -0.0698125 0.0393039 0.0382471 -0.0724706 0.040441 0.0382471 -0.0705966 0.0696785 0.0412971 -0.0403549 0.0703395 0.0412971 -0.0407229 0.0707501 0.0411471 -0.0420786 0.0707754 0.0412971 -0.0413412 0.0705571 0.0411471 -0.0427409 0.0706882 0.0412971 -0.0428139 0.0694578 0.0411471 -0.0435159 0.0694578 0.0382471 -0.0435159 0.0700959 0.0411471 -0.0432538 0.0705571 0.0382471 -0.0427409 0.0706367 0.0411471 -0.0413982 0.0707501 0.0382471 -0.0420786 0.0706367 0.0382471 -0.0413982 0.0702392 0.0411471 -0.0408344 0.0702392 0.0382471 -0.0408344 0.0696365 0.0411471 -0.0404989 0.0700959 0.0382471 -0.0432538 0.07024 0.0379971 -0.0434582 0.0707756 0.0379971 -0.0428625 0.0708679 0.0379971 -0.0413033 0.00100918 0.0351971 -0.0797875 0.0013423 0.0349971 -0.0801663 0.0012288 0.0351971 -0.0811045 0.00130626 0.0349971 -0.0818224 0.000447019 0.0349971 -0.0832385 -0.00260528 0.0351971 -0.0838073 -0.00100518 0.0349971 -0.0840353 0.0396487 0.0351971 -0.073879 0.0396962 0.0349971 -0.0740733 0.0411484 0.0349971 -0.0732765 0.0418494 0.0351971 -0.0702518 0.0420437 0.0349971 -0.0702043 0.0411024 0.0351971 -0.0688904 0.0412469 0.0349971 -0.0687521 0.0696963 0.0351971 -0.0449461 0.0710466 0.0349971 -0.0446024 0.0721976 0.0351971 -0.0421644 0.0712087 0.0351971 -0.0397562 0.072163 0.0349971 -0.0407715 0.0713424 0.0349971 -0.0396075 0.00667286 0.0410971 -0.08282 0.00696131 0.0410971 -0.0825825 0.00759152 0.0412971 -0.0820899 0.00763259 0.0410971 -0.0814761 0.00772805 0.0410971 -0.0809245 0.00766075 0.0410971 -0.0801823 0.00773005 0.0412971 -0.0797511 0.00703772 0.0412971 -0.0787689 0.00703824 0.0410971 -0.0790478 0.00564365 0.0410971 -0.0832426 0.00582678 0.0410971 -0.083205 0.00696131 0.0352971 -0.0825825 0.00741678 0.0410971 -0.0819926 0.00766075 0.0352971 -0.0801823 0.00754504 0.0410971 -0.079827 0.00690399 0.0410971 -0.0789177 0.00703824 0.0352971 -0.0790478 0.00582678 0.0352971 -0.083205 0.0058981 0.0349971 -0.0834964 0.00716878 0.0349971 -0.0827992 0.00792061 0.0349971 -0.08156 0.00763259 0.0352971 -0.0814761 0.00795215 0.0349971 -0.080111 0.00593186 0.0352971 -0.0783765 0.0334141 0.0412971 -0.0714717 0.0344645 0.0410971 -0.072335 0.034609 0.0412971 -0.0721966 0.0350588 0.0410971 -0.0747633 0.0345259 0.0412971 -0.0760141 0.0333006 0.0412971 -0.0766864 0.0319593 0.0410971 -0.076464 0.033253 0.0410971 -0.0764922 0.0319593 0.0352971 -0.076464 0.0343876 0.0410971 -0.0758696 0.035087 0.0410971 -0.0734695 0.0344645 0.0352971 -0.072335 0.0333581 0.0352971 -0.0716637 0.0318753 0.0349971 -0.076752 0.033253 0.0352971 -0.0764922 0.0333244 0.0349971 -0.0767836 0.0343876 0.0352971 -0.0758696 0.0350588 0.0352971 -0.0747633 0.035087 0.0352971 -0.0734695 0.0334421 0.0349971 -0.0713757 0.0467268 0.0410971 -0.0656067 0.0473493 0.0410971 -0.0667412 0.0473212 0.0410971 -0.068035 0.0466499 0.0410971 -0.0691414 0.0455154 0.0410971 -0.0697639 0.0442216 0.0352971 -0.0697358 0.0455154 0.0352971 -0.0697639 0.0473212 0.0352971 -0.068035 0.0473493 0.0352971 -0.0667412 0.0467268 0.0352971 -0.0656067 0.0456204 0.0352971 -0.0649354 0.0455867 0.0349971 -0.0700553 0.0466499 0.0352971 -0.0691414 0.0468573 0.0349971 -0.0693581 0.0677166 0.0410971 -0.0485084 0.0679086 0.0412971 -0.0485644 0.0671836 0.0412971 -0.0497593 0.0659583 0.0412971 -0.0504316 0.064617 0.0352971 -0.0502092 0.0659108 0.0410971 -0.0502373 0.0670453 0.0410971 -0.0496148 0.0677447 0.0410971 -0.0472146 0.0677447 0.0352971 -0.0472146 0.0671222 0.0410971 -0.0460801 0.0660159 0.0410971 -0.0454088 0.0671222 0.0352971 -0.0460801 0.0660159 0.0352971 -0.0454088 0.0645331 0.0349971 -0.0504972 0.0659108 0.0352971 -0.0502373 0.0659821 0.0349971 -0.0505287 0.0670453 0.0352971 -0.0496148 0.0677166 0.0352971 -0.0485084 0.0680046 0.0349971 -0.0485924 0.0673389 0.0349971 -0.0458726 0.000917299 0.0351971 0.0780544 0.00246985 0.0379971 0.0780206 0.00467061 0.0379971 0.0816478 0.00392359 0.0379971 0.0830093 0.00392359 0.0351971 0.0830093 0.00259594 0.0351971 0.0838148 0.00071951 0.0379971 0.0824058 2.81017e-05 0.0379971 0.0833866 -0.000864596 0.0379971 0.0823938 -0.00123813 0.0379971 0.081112 -0.00101852 0.0379971 0.079795 0.000553097 0.0379971 0.0795961 0.000917299 0.0379971 0.0780544 0.00383128 0.0379971 0.0787676 0.00463682 0.0379971 0.0800953 0.00350501 0.0379971 0.0813625 0.00259594 0.0379971 0.0838148 0.00126315 0.0379971 0.0838937 -0.0382315 0.0379971 0.0680586 -0.0397841 0.0351971 0.0680924 -0.0360646 0.0379971 0.0701332 -0.0360308 0.0379971 0.0716858 -0.0367778 0.0379971 0.0730472 -0.0360308 0.0351971 0.0716858 -0.0367778 0.0351971 0.0730472 -0.068499 0.0379971 0.0390805 -0.0671375 0.0351971 0.0398275 -0.0671375 0.0379971 0.0398275 -0.066591 0.0351971 0.0405353 -0.0662174 0.0351971 0.0418171 -0.0662982 0.0351971 0.0427077 -0.0662982 0.0379971 0.0427077 -0.0670452 0.0379971 0.0440692 -0.0683729 0.0379971 0.0448747 -0.0672063 0.0351971 0.0442253 -0.0670452 0.0351971 0.0440692 -0.066332 0.0379971 0.0411552 -0.0700515 0.0379971 0.0391143 -0.0712868 0.0379971 0.0441615 -0.0709403 0.0379971 0.0424981 -0.070457 0.0379971 0.0432947 -0.0699254 0.0379971 0.0449085 -0.0687086 0.0379971 0.0437226 -0.0675471 0.0379971 0.0426782 -0.0676395 0.0379971 0.041119 0.00287622 0.0411471 0.0820065 0.00298457 0.0412971 0.0821102 0.00326218 0.0411471 0.0813031 0.00212512 0.0411471 0.079429 0.00216078 0.0412971 0.0792833 0.00212512 0.0382471 0.079429 0.00282853 0.0411471 0.079815 0.00324472 0.0411471 0.0805009 0.00324472 0.0382471 0.0805009 0.00326218 0.0382471 0.0813031 0.00132297 0.0382471 0.0794465 0.00125303 0.0379971 0.0792065 0.00282853 0.0382471 0.079815 0.00218456 0.0379971 0.0791862 0.00300142 0.0379971 0.0796344 0.00348474 0.0379971 0.080431 0.00287622 0.0382471 0.0820065 0.00305681 0.0379971 0.0821794 -0.0378252 0.0411471 0.0720445 -0.0377168 0.0412971 0.0721482 -0.0374392 0.0411471 0.0713411 -0.0374567 0.0411471 0.0705389 -0.0385763 0.0411471 0.069467 -0.0385406 0.0412971 0.0693213 -0.0394204 0.0412971 0.0693404 -0.0393784 0.0411471 0.0694844 -0.0378729 0.0411471 0.0698529 -0.0378729 0.0382471 0.0698529 -0.0374392 0.0382471 0.0713411 -0.0385111 0.0411471 0.0724607 -0.0393784 0.0382471 0.0694844 -0.0385763 0.0382471 0.069467 -0.0385168 0.0379971 0.0692242 -0.0377 0.0379971 0.0696724 -0.0374567 0.0382471 0.0705389 -0.0372166 0.0379971 0.070469 -0.0378252 0.0382471 0.0720445 -0.0385111 0.0382471 0.0724607 -0.0384412 0.0379971 0.0727007 -0.0681758 0.0411471 0.0431471 -0.0680755 0.0412971 0.0432586 -0.0676649 0.0411471 0.0419028 -0.0675152 0.0412971 0.041894 -0.0683191 0.0411471 0.0407276 -0.0689572 0.0411471 0.0404656 -0.0689325 0.0412971 0.0403176 -0.0689572 0.0382471 0.0404656 -0.0678579 0.0411471 0.0412406 -0.0677784 0.0382471 0.0425833 -0.0677784 0.0411471 0.0425833 -0.0697158 0.0379971 0.0402664 -0.0689161 0.0379971 0.040219 -0.0683191 0.0382471 0.0407276 -0.0681751 0.0379971 0.0405233 -0.0678579 0.0382471 0.0412406 -0.0676649 0.0382471 0.0419028 -0.0674153 0.0379971 0.0418881 -0.0681758 0.0382471 0.0431471 -0.0680087 0.0379971 0.043333 0.00246985 0.0351971 0.0780206 0.00383128 0.0351971 0.0787676 0.00251739 0.0349971 0.0778263 0.0039696 0.0349971 0.0786231 0.00463682 0.0351971 0.0800953 0.00467061 0.0351971 0.0816478 0.00406806 0.0349971 0.0831476 -0.0382315 0.0351971 0.0680586 -0.0368701 0.0351971 0.0688056 -0.0358726 0.0349971 0.0700773 -0.0360646 0.0351971 0.0701332 -0.0683169 0.0349971 0.0450667 -0.0670726 0.0349971 0.044374 -0.066437 0.0351971 0.0431341 -0.0660178 0.0349971 0.0418053 -0.066332 0.0351971 0.0411552 -0.0664162 0.0349971 0.040438 -0.0674837 0.0351971 0.0395425 -0.0701075 0.0349971 0.0389223 -0.0687187 0.0351971 0.0390354 -0.068499 0.0351971 0.0390805 -0.00380133 0.0410971 0.0787408 -0.00454233 0.0410971 0.0831843 -0.00343595 0.0410971 0.082513 -0.00448637 0.0412971 0.0833763 -0.00274614 0.0410971 0.0806364 -0.00464741 0.0410971 0.0783558 -0.00351288 0.0410971 0.0789784 -0.00380133 0.0352971 0.0787408 -0.00305741 0.0410971 0.0795682 -0.00305741 0.0352971 0.0795682 -0.0028416 0.0410971 0.0800847 -0.00281344 0.0410971 0.0813785 -0.00292915 0.0410971 0.0817338 -0.0035702 0.0352971 0.0826432 -0.0059412 0.0352971 0.078384 -0.00478119 0.0349971 0.0780223 -0.00483054 0.0352971 0.0783182 -0.00362848 0.0349971 0.0784956 -0.00279529 0.0349971 0.0794223 -0.00274614 0.0352971 0.0806364 -0.00244666 0.0349971 0.0806186 -0.00292915 0.0352971 0.0817338 -0.0307177 0.0412971 0.0759385 -0.0302679 0.0410971 0.0733719 -0.0333675 0.0410971 0.0716712 -0.0320261 0.0412971 0.0714488 -0.0320737 0.0410971 0.071643 -0.0309391 0.0410971 0.0722655 -0.0309391 0.0352971 0.0722655 -0.0302397 0.0410971 0.0746657 -0.0302679 0.0352971 0.0733719 -0.0308622 0.0410971 0.0758002 -0.0333675 0.0352971 0.0716712 -0.0320737 0.0352971 0.071643 -0.0307317 0.0349971 0.0720488 -0.0299798 0.0349971 0.073288 -0.0299483 0.0349971 0.074737 -0.0302397 0.0352971 0.0746657 -0.0306455 0.0349971 0.0760077 -0.0308622 0.0352971 0.0758002 -0.044336 0.0410971 0.0649148 -0.0434899 0.0410971 0.0652998 -0.0433747 0.0412971 0.0651363 -0.0425712 0.0412971 0.0660298 -0.0422351 0.0412971 0.0671835 -0.0424347 0.0410971 0.0671953 -0.042502 0.0410971 0.0679374 -0.043125 0.0412971 0.0693508 -0.0442309 0.0410971 0.0697433 -0.0441749 0.0412971 0.0699353 -0.0432588 0.0410971 0.0692021 -0.0456298 0.0352971 0.0649429 -0.0445191 0.0410971 0.0648771 -0.044336 0.0352971 0.0649148 -0.0432014 0.0352971 0.0655373 -0.0432014 0.0410971 0.0655373 -0.042746 0.0410971 0.0661271 -0.0425302 0.0410971 0.0666437 -0.0426177 0.0410971 0.0682927 -0.0431245 0.0410971 0.069072 -0.0425302 0.0352971 0.0666437 -0.042994 0.0349971 0.0653206 -0.042502 0.0352971 0.0679374 -0.0431245 0.0352971 0.069072 -0.0442309 0.0352971 0.0697433 -0.0660252 0.0410971 0.0454163 -0.0647314 0.0410971 0.0453882 -0.0648816 0.0412971 0.0451533 -0.0635969 0.0410971 0.0460107 -0.0635205 0.0412971 0.0498242 -0.0646263 0.0410971 0.0502167 -0.0645704 0.0412971 0.0504087 -0.0635199 0.0410971 0.0495454 -0.0649145 0.0410971 0.0453505 -0.0647314 0.0352971 0.0453882 -0.0638853 0.0410971 0.0457732 -0.0631414 0.0410971 0.0466005 -0.0629256 0.0410971 0.0471171 -0.0628301 0.0410971 0.0476687 -0.0628974 0.0410971 0.0484108 -0.0630131 0.0410971 0.0487661 -0.0636542 0.0410971 0.0496755 -0.0635969 0.0352971 0.0460107 -0.0629256 0.0352971 0.0471171 -0.0628974 0.0352971 0.0484108 -0.0635199 0.0352971 0.0495454 -0.0646263 0.0352971 0.0502167 -0.0633032 0.0349971 0.0497528 -0.0415019 0.0351971 -0.0721629 -0.0412822 0.0351971 -0.0721178 -0.0402669 0.0351971 -0.0716558 -0.0399207 0.0351971 -0.0713707 -0.0391152 0.0379971 -0.0700431 -0.0390007 0.0351971 -0.0693811 -0.0390814 0.0351971 -0.0684905 -0.0392203 0.0351971 -0.0680642 -0.0411561 0.0379971 -0.0663236 -0.0401986 0.0379971 -0.0693102 -0.0399207 0.0379971 -0.0713707 -0.0409583 0.0379971 -0.070675 -0.0412822 0.0379971 -0.0721178 -0.0428347 0.0379971 -0.072084 -0.0449094 0.0379971 -0.069917 -0.0437235 0.0379971 -0.0687002 -0.0440701 0.0379971 -0.0670368 -0.0398284 0.0379971 -0.0671291 -0.0390814 0.0379971 -0.0684905 -0.07048 0.0379971 -0.0418955 -0.0683523 0.0379971 -0.0403955 -0.0691766 0.0379971 -0.0390428 -0.0679787 0.0379971 -0.0391137 -0.0681983 0.0379971 -0.0377968 -0.0689676 0.0379971 -0.0367055 -0.0701341 0.0379971 -0.0360561 -0.0730481 0.0379971 -0.0367694 -0.0738537 0.0379971 -0.038097 -0.0727219 0.0379971 -0.0393643 -0.0714771 0.0379971 -0.0406645 -0.069245 0.0379971 -0.0413883 -0.080442 0.0379971 -0.0011941 -0.0783143 0.0379971 0.000305855 -0.0779408 0.0379971 0.00158766 -0.0779408 0.0351971 0.00158766 -0.0781604 0.0351971 0.0029046 -0.0789296 0.0379971 0.00399584 -0.079732 0.0379971 0.00310352 -0.0804319 0.0379971 0.00349316 -0.0813634 0.0379971 0.00351343 -0.0816487 0.0379971 0.00467902 -0.0830102 0.0379971 0.00393201 -0.0826636 0.0379971 0.00226863 -0.0826839 0.0379971 0.0013371 -0.0838157 0.0379971 0.00260436 -0.0822357 0.0379971 0.00052024 -0.0814391 0.0379971 3.69197e-05 -0.0806394 0.0379971 -1.04438e-05 -0.0817748 0.0379971 -0.00111516 -0.0798984 0.0379971 0.000293849 -0.079207 0.0379971 -0.000686944 -0.0793628 0.0379971 0.000889528 -0.0792704 0.0379971 0.00244878 -0.0781604 0.0379971 0.0029046 -0.0408758 0.0411471 -0.0681319 -0.0407675 0.0412971 -0.0680281 -0.0404898 0.0411471 -0.0688353 -0.0403441 0.0412971 -0.0687996 -0.0409235 0.0411471 -0.0703234 -0.0403633 0.0412971 -0.0696794 -0.0408198 0.0412971 -0.0704317 -0.0424291 0.0411471 -0.0706919 -0.0416269 0.0382471 -0.0707093 -0.0416269 0.0411471 -0.0707093 -0.0405073 0.0411471 -0.0696374 -0.0406411 0.0382471 -0.0699577 -0.0404481 0.0382471 -0.0692954 -0.0405616 0.0382471 -0.068615 -0.040959 0.0382471 -0.0680512 -0.0415618 0.0382471 -0.0677157 -0.0407919 0.0379971 -0.0678653 -0.0408758 0.0382471 -0.0681319 -0.0404898 0.0382471 -0.0688353 -0.0403303 0.0379971 -0.06852 -0.0404227 0.0379971 -0.0700793 -0.0405073 0.0382471 -0.0696374 -0.0409235 0.0382471 -0.0703234 -0.0411023 0.0382471 -0.0704706 -0.0417404 0.0382471 -0.0707327 -0.042499 0.0379971 -0.0709319 -0.0416993 0.0379971 -0.0709793 -0.0694009 0.0412971 -0.0382906 -0.0694262 0.0411471 -0.039028 -0.0692764 0.0412971 -0.0390369 -0.069994 0.0412971 -0.0403258 -0.0707185 0.0411471 -0.0404652 -0.0706938 0.0412971 -0.0406132 -0.0714071 0.0411471 -0.0404245 -0.0707185 0.0382471 -0.0404652 -0.0700804 0.0411471 -0.0402032 -0.0696192 0.0411471 -0.0396903 -0.0696192 0.0382471 -0.0396903 -0.0694262 0.0382471 -0.039028 -0.0695397 0.0411471 -0.0383476 -0.0699371 0.0411471 -0.0377838 -0.0700804 0.0382471 -0.0402032 -0.0706774 0.0379971 -0.0407118 -0.0699364 0.0379971 -0.0404075 -0.0694007 0.0379971 -0.0398119 -0.0693084 0.0379971 -0.0382526 -0.0695397 0.0382471 -0.0383476 -0.0699371 0.0382471 -0.0377838 -0.0697699 0.0379971 -0.0375979 -0.0804599 0.0412971 0.00339715 -0.0798991 0.0411471 0.00291762 -0.0793882 0.0411471 0.00167339 -0.0795812 0.0411471 0.00101113 -0.0800424 0.0411471 0.000498181 -0.0806805 0.0411471 0.000236151 -0.0800424 0.0382471 0.000498181 -0.0795017 0.0411471 0.00235381 -0.0795017 0.0382471 0.00235381 -0.0805019 0.0411471 0.00325314 -0.0798991 0.0382471 0.00291762 -0.0806805 0.0382471 0.000236151 -0.0795812 0.0382471 0.00101113 -0.0793882 0.0382471 0.00167339 -0.0791387 0.0379971 0.00165861 -0.0398558 0.0349971 -0.0668242 -0.0399895 0.0351971 -0.066973 -0.0398284 0.0351971 -0.0671291 -0.0390353 0.0349971 -0.0679882 -0.038801 0.0349971 -0.069393 -0.0391152 0.0351971 -0.0700431 -0.0393742 0.0351971 -0.070663 -0.0401517 0.0349971 -0.0718192 -0.0428907 0.0349971 -0.072276 -0.041469 0.0349971 -0.0723602 -0.07048 0.0351971 -0.0418955 -0.0704471 0.0349971 -0.0420928 -0.069245 0.0351971 -0.0413883 -0.0683523 0.0351971 -0.0403955 -0.0679787 0.0351971 -0.0391137 -0.0677791 0.0349971 -0.0391255 -0.0681983 0.0351971 -0.0377968 -0.0689676 0.0351971 -0.0367055 -0.080442 0.0351971 -0.0011941 -0.0790918 0.0349971 -0.00085041 -0.079207 0.0351971 -0.000686944 -0.0783143 0.0351971 0.000305855 -0.0789296 0.0351971 0.00399584 -0.0800962 0.0351971 0.00464524 -0.0485728 0.0412971 -0.0679095 -0.0474062 0.0410971 -0.0677833 -0.0472231 0.0410971 -0.0677457 -0.0456331 0.0410971 -0.0665333 -0.0454172 0.0410971 -0.0660168 -0.0453198 0.0412971 -0.0642917 -0.0455048 0.0410971 -0.0643677 -0.047062 0.0412971 -0.0627252 -0.0461458 0.0410971 -0.0634583 -0.0460121 0.0412971 -0.0633096 -0.0485168 0.0410971 -0.0677175 -0.046377 0.0410971 -0.0673607 -0.0472231 0.0352971 -0.0677457 -0.046377 0.0352971 -0.0673607 -0.0460885 0.0410971 -0.0671232 -0.0460885 0.0352971 -0.0671232 -0.0453218 0.0410971 -0.0654652 -0.0453891 0.0410971 -0.064723 -0.0453891 0.0352971 -0.064723 -0.0455048 0.0352971 -0.0643677 -0.0460116 0.0410971 -0.0635885 -0.0460116 0.0352971 -0.0635885 -0.0461458 0.0352971 -0.0634583 -0.0459453 0.0349971 -0.0632353 -0.0452273 0.0349971 -0.0642537 -0.0450223 0.0349971 -0.0654829 -0.0453218 0.0352971 -0.0654652 -0.0453709 0.0349971 -0.0666792 -0.0454172 0.0352971 -0.0660168 -0.0456331 0.0352971 -0.0665333 -0.0462041 0.0349971 -0.0676059 -0.0473568 0.0349971 -0.0680792 -0.0486008 0.0349971 -0.0680055 -0.0474062 0.0352971 -0.0677833 -0.0667021 0.0412971 -0.0475445 -0.0654768 0.0412971 -0.0468722 -0.0651597 0.0410971 -0.0461379 -0.0650314 0.0410971 -0.0439723 -0.0680434 0.0410971 -0.0473221 -0.0667497 0.0410971 -0.0473502 -0.0659036 0.0410971 -0.0469652 -0.0656151 0.0410971 -0.0467277 -0.0651597 0.0352971 -0.0461379 -0.0649438 0.0410971 -0.0456214 -0.0648484 0.0352971 -0.0450697 -0.0648484 0.0410971 -0.0450697 -0.0649157 0.0410971 -0.0443276 -0.0650314 0.0352971 -0.0439723 -0.0656724 0.0352971 -0.0430629 -0.0655382 0.0410971 -0.043193 -0.0680434 0.0352971 -0.0473221 -0.0669328 0.0352971 -0.0473879 -0.0681274 0.0349971 -0.0476101 -0.0668834 0.0349971 -0.0476838 -0.0659036 0.0352971 -0.0469652 -0.0648975 0.0349971 -0.0462838 -0.0733728 0.0410971 -0.0302594 -0.0722664 0.0410971 -0.0309307 -0.072122 0.0412971 -0.0307924 -0.0722051 0.0412971 -0.0346099 -0.0734779 0.0410971 -0.0350879 -0.0734304 0.0412971 -0.0352822 -0.0726318 0.0352971 -0.0347029 -0.0723434 0.0410971 -0.0344654 -0.0715766 0.0352971 -0.0328074 -0.0716721 0.0410971 -0.033359 -0.0716439 0.0410971 -0.0320652 -0.0717596 0.0352971 -0.03171 -0.0724007 0.0352971 -0.0308006 -0.0733728 0.0352971 -0.0302594 -0.0722664 0.0352971 -0.0309307 -0.0722001 0.0349971 -0.0305775 -0.0716439 0.0352971 -0.0320652 -0.0716721 0.0352971 -0.033359 -0.0718879 0.0352971 -0.0338756 -0.0716258 0.0349971 -0.0340215 -0.0723434 0.0352971 -0.0344654 -0.072459 0.0349971 -0.0349481 -0.0736117 0.0349971 -0.0354215 -0.0748556 0.0349971 -0.0353478 -0.073661 0.0352971 -0.0351255 -0.0734779 0.0352971 -0.0350879 -0.0801907 0.0410971 -0.00766167 -0.0790562 0.0410971 -0.00703916 -0.0789179 0.0412971 -0.00718362 -0.0786007 0.0410971 -0.00644933 -0.0783849 0.0410971 -0.00593278 -0.0781929 0.0412971 -0.00598874 -0.0781625 0.0412971 -0.00459144 -0.0800297 0.0412971 -0.00264117 -0.0788348 0.0412971 -0.00336615 -0.0789793 0.0410971 -0.00350446 -0.0784725 0.0410971 -0.00428371 -0.0814845 0.0410971 -0.00763351 -0.0814845 0.0352971 -0.00763351 -0.0793446 0.0352971 -0.00727666 -0.0793446 0.0410971 -0.00727666 -0.0786007 0.0352971 -0.00644933 -0.0782895 0.0410971 -0.00538116 -0.0783568 0.0410971 -0.00463899 -0.0784725 0.0352971 -0.00428371 -0.0803739 0.0352971 -0.00769929 -0.0803245 0.0349971 -0.00799521 -0.0783386 0.0349971 -0.00659525 -0.0782895 0.0352971 -0.00538116 -0.07799 0.0349971 -0.0053989 -0.078195 0.0349971 -0.00416975 -0.0791135 0.0352971 -0.00337435 -0.0789129 0.0349971 -0.00315127 -0.0800017 0.0349971 -0.00254516 0.0237621 0.0355971 0.0815613 -0.017793 0.0349971 0.0824568 -0.00397904 0.0349971 0.0842601 0.0100141 0.0355971 0.0843609 -0.0242273 0.0349971 0.0808009 -0.0399978 0.0349971 0.07427 -0.0311217 0.0349971 0.0784044 -0.0436016 0.0349971 0.0722134 -0.0439117 0.0355971 0.072727 -0.0578771 0.0349971 0.0613691 -0.0552655 0.0349971 0.063731 -0.079321 0.0355971 0.0304244 -0.0732322 0.0355971 0.0430645 -0.0651459 0.0355971 0.0545301 -0.0841916 0.0349971 -0.00523929 -0.083531 0.0349971 -0.0117553 -0.083645 0.0349971 -0.0109149 -0.0812812 0.0355971 -0.0247072 -0.081783 0.0349971 -0.0206658 -0.0683147 0.0349971 -0.0494802 -0.0688537 0.0355971 -0.0497588 -0.0683675 0.0349971 -0.0494073 -0.0368713 0.0355971 -0.0765296 -0.0237715 0.0355971 -0.0815538 0.0164041 0.0292971 0.0563116 0.0051211 0.0294971 0.0586301 -0.00641483 0.0294971 0.0585036 -0.00639304 0.0292971 0.0583048 -0.0282176 0.0292971 0.0514222 -0.0378353 0.0294971 0.0450833 -0.0377067 0.0292971 0.0449301 -0.0522068 0.0294971 0.0271747 -0.058631 0.0294971 0.00512951 -0.0585045 0.0294971 -0.00640641 -0.0583057 0.0292971 -0.00638463 -0.0561299 0.0294971 -0.017696 -0.0559392 0.0292971 -0.0176358 -0.0515984 0.0294971 -0.0283054 -0.0450842 0.0294971 -0.0378269 -0.044931 0.0292971 -0.0376983 -0.0367125 0.0292971 -0.0457386 -0.0271756 0.0294971 -0.0521984 -0.0548449 0.0397971 0.0572841 -0.0555937 0.0349971 0.0568732 -0.0544019 0.0349971 0.0580143 -0.0543833 0.0349971 0.0588682 -0.0543833 0.0397971 0.0588682 -0.0547942 0.0349971 0.059617 -0.0188576 0.0397971 0.0770301 -0.0181088 0.0349971 0.077441 -0.0176657 0.0349971 0.0781712 -0.0176471 0.0397971 0.0790251 -0.0176471 0.0349971 0.0790251 -0.018058 0.0397971 0.0797739 -0.0187882 0.0397971 0.0802169 -0.0187882 0.0349971 0.0802169 -0.0568927 0.0349971 -0.0564392 -0.0568927 0.0397971 -0.0564392 -0.0568741 0.0397971 -0.0555853 -0.0580152 0.0397971 -0.0543935 -0.057285 0.0349971 -0.0548365 -0.077683 0.0397971 -0.02059 -0.0783623 0.0349971 -0.0208689 -0.077192 0.0349971 -0.020044 -0.0769866 0.0349971 -0.019339 -0.0771074 0.0397971 -0.0186147 -0.0771074 0.0349971 -0.0186147 -0.0775305 0.0349971 -0.0180145 -0.0781721 0.0397971 -0.0176573 -0.0774506 0.0397971 0.0210239 -0.0773297 0.0349971 0.0210488 -0.0765809 0.0349971 0.0214596 -0.0765809 0.0397971 0.0214596 -0.0761379 0.0397971 0.0221898 -0.0760749 0.0397971 0.0225539 -0.0761193 0.0349971 0.0230437 -0.0761957 0.0397971 0.0232782 -0.0765302 0.0349971 0.0237925 -0.0765302 0.0397971 0.0237925 -0.0766188 0.0397971 0.0238784 -0.0772604 0.0349971 0.0242356 0.055515 0.0397971 -0.0600525 0.055515 0.0349971 -0.0600525 0.0563689 0.0349971 -0.0600711 0.0563689 0.0397971 -0.0600711 0.0571177 0.0397971 -0.0596602 0.0571685 0.0349971 -0.0573273 0.0201912 0.0349971 -0.0799739 0.0206822 0.0397971 -0.0794278 0.0206822 0.0349971 -0.0794278 0.0208876 0.0397971 -0.0787228 0.0208876 0.0349971 -0.0787228 0.0207668 0.0397971 -0.0779985 0.0207668 0.0349971 -0.0779985 0.0203437 0.0397971 -0.0773984 0.0203437 0.0349971 -0.0773984 0.0580059 0.0397971 0.054401 0.0588598 0.0349971 0.0543824 0.0596086 0.0397971 0.0547932 0.0600702 0.0349971 0.0563773 0.0596593 0.0349971 0.0571261 0.0788958 0.0397971 0.0176214 0.0795751 0.0397971 0.0179003 0.0788958 0.0349971 0.0176214 0.0795751 0.0349971 0.0179003 0.080066 0.0397971 0.0184464 0.0802715 0.0397971 0.0191514 0.080066 0.0349971 0.0184464 0.0802715 0.0349971 0.0191514 0.0801507 0.0349971 0.0198757 0.0797276 0.0349971 0.0204759 0.0781049 0.0397971 -0.0242467 0.077251 0.0349971 -0.0242281 0.0788537 0.0397971 -0.0238358 0.0788537 0.0349971 -0.0238358 0.0792968 0.0397971 -0.0231056 0.0792968 0.0349971 -0.0231056 0.0793154 0.0349971 -0.0222517 -0.0237715 0.0410971 -0.0815538 -0.0368713 0.0410971 -0.0765296 -0.0367845 0.0412971 -0.0763494 -0.0488502 0.0412971 -0.0692543 -0.0597241 0.0410971 -0.0604123 -0.0761054 0.0410971 -0.0377479 -0.0759262 0.0412971 -0.037659 -0.0810898 0.0412971 -0.0246491 -0.0812812 0.0410971 -0.0247072 -0.08424 0.0410971 -0.0109925 -0.0847012 0.0412971 0.00301499 -0.0732322 0.0410971 0.0430645 -0.0649926 0.0412971 0.0544017 -0.0551526 0.0412971 0.0643564 -0.0439117 0.0410971 0.072727 -0.0438083 0.0412971 0.0725558 -0.0179195 0.0410971 0.0830433 -0.0178773 0.0412971 0.0828478 -0.00400731 0.0410971 0.0848594 0.0785439 0.0400971 -0.0218482 0.0779862 0.0400971 -0.0237617 0.0788304 0.0400971 -0.0223704 0.0775196 0.0400971 0.0195709 0.0797731 0.0400971 0.0191809 0.0792874 0.0400971 0.0183084 0.0788137 0.0400971 0.0181139 0.0783024 0.0400971 0.0181442 0.0783508 0.0400971 0.0203666 0.0778286 0.0400971 0.0200801 0.0789463 0.0400971 0.0203537 0.0574621 0.0400971 0.0565448 0.0573188 0.0400971 0.0560531 0.0576981 0.0400971 0.0551294 0.0595723 0.0400971 0.0556631 0.020305 0.0400971 -0.0781882 0.0200099 0.0400971 -0.0777696 0.0184447 0.0400971 -0.0777941 0.0189669 0.0400971 -0.0775076 0.0194298 0.0400971 -0.0797603 0.0553136 0.0400971 -0.0575279 0.0562502 0.0400971 -0.0595861 0.0556547 0.0400971 -0.0595732 -0.0767166 0.0400971 0.0220918 -0.0788397 0.0400971 0.0223779 -0.0779956 0.0400971 0.0237692 -0.0774001 0.0400971 0.0237562 -0.0766575 0.0400971 0.0230886 -0.0789073 0.0400971 -0.0181237 -0.0797514 0.0400971 -0.019515 -0.0776283 0.0400971 -0.0198011 -0.077485 0.0400971 -0.0193095 -0.0784444 0.0400971 -0.0203765 -0.0576456 0.0400971 -0.0551818 -0.0581549 0.0400971 -0.0548728 -0.059308 0.0400971 -0.0567734 -0.0587504 0.0400971 -0.0548599 -0.0184186 0.0400971 0.0794286 -0.0203676 0.0400971 0.0783592 -0.0189279 0.0400971 0.0797376 -0.0571037 0.0400971 0.0582023 -0.0556641 0.0400971 0.0595807 -0.0563079 0.0400971 0.0573712 -0.0548683 0.0400971 0.0587495 -0.0548812 0.0400971 0.058154 -0.0489654 0.0619971 -0.0694178 -0.0489654 0.0630971 -0.0694178 -0.0688537 0.0619971 -0.0497588 -0.0597241 0.0630971 -0.0604123 -0.0688537 0.0630971 -0.0497588 -0.0812812 0.0619971 -0.0247072 -0.08424 0.0619971 -0.0109925 -0.0812812 0.0630971 -0.0247072 -0.0832464 0.0619971 0.0169544 -0.079321 0.0630971 0.0304244 -0.0732322 0.0630971 0.0430645 -0.0651459 0.0619971 0.0545301 -0.0439117 0.0630971 0.072727 -0.0179195 0.0630971 0.0830433 -0.00400731 0.0630971 0.0848594 0.0237621 0.0619971 0.0815613 -0.0237715 0.0670971 -0.0815538 -0.0368713 0.0644971 -0.0765296 -0.0489654 0.0670971 -0.0694178 -0.0489654 0.0644971 -0.0694178 -0.0688537 0.0644971 -0.0497588 -0.0688537 0.0670971 -0.0497588 -0.0761054 0.0670971 -0.0377479 -0.0812812 0.0670971 -0.0247072 -0.08424 0.0670971 -0.0109925 -0.08424 0.0644971 -0.0109925 -0.084901 0.0644971 0.0030221 -0.0832464 0.0644971 0.0169544 -0.079321 0.0644971 0.0304244 -0.0651459 0.0670971 0.0545301 -0.0552827 0.0644971 0.0645083 -0.0552827 0.0670971 0.0645083 -0.0439117 0.0644971 0.072727 -0.031343 0.0644971 0.078962 -0.031343 0.0670971 0.078962 -0.0179195 0.0644971 0.0830433 -0.0179195 0.0670971 0.0830433 0.0100141 0.0670971 0.0843609 -0.0368713 0.0594971 -0.0765296 -0.0489654 0.0605971 -0.0694178 -0.0688537 0.0594971 -0.0497588 -0.0761054 0.0594971 -0.0377479 -0.0688537 0.0605971 -0.0497588 -0.0812812 0.0605971 -0.0247072 -0.08424 0.0605971 -0.0109925 -0.084901 0.0594971 0.0030221 -0.0832464 0.0605971 0.0169544 -0.0832464 0.0594971 0.0169544 -0.079321 0.0605971 0.0304244 -0.0651459 0.0605971 0.0545301 -0.0552827 0.0594971 0.0645083 -0.031343 0.0594971 0.078962 -0.0439117 0.0605971 0.072727 -0.0179195 0.0605971 0.0830433 0.0237621 0.0594971 0.0815613 -0.0368713 0.0569971 -0.0765296 -0.0489654 0.0569971 -0.0694178 -0.0489654 0.0580971 -0.0694178 -0.0597241 0.0580971 -0.0604123 -0.0688537 0.0580971 -0.0497588 -0.0761054 0.0580971 -0.0377479 -0.0761054 0.0569971 -0.0377479 -0.0812812 0.0569971 -0.0247072 -0.08424 0.0569971 -0.0109925 -0.084901 0.0569971 0.0030221 -0.0832464 0.0569971 0.0169544 -0.0832464 0.0580971 0.0169544 -0.0552827 0.0569971 0.0645083 -0.0439117 0.0580971 0.072727 -0.0439117 0.0569971 0.072727 -0.031343 0.0580971 0.078962 -0.00400731 0.0569971 0.0848594 -0.0368713 0.0544971 -0.0765296 -0.0489654 0.0544971 -0.0694178 -0.0368713 0.0555971 -0.0765296 -0.0597241 0.0544971 -0.0604123 -0.0597241 0.0555971 -0.0604123 -0.0688537 0.0555971 -0.0497588 -0.0688537 0.0544971 -0.0497588 -0.0812812 0.0544971 -0.0247072 -0.0812812 0.0555971 -0.0247072 -0.08424 0.0544971 -0.0109925 -0.08424 0.0555971 -0.0109925 -0.084901 0.0544971 0.0030221 -0.0832464 0.0555971 0.0169544 -0.0832464 0.0544971 0.0169544 -0.079321 0.0555971 0.0304244 -0.0552827 0.0555971 0.0645083 -0.0439117 0.0555971 0.072727 -0.0439117 0.0544971 0.072727 -0.0179195 0.0544971 0.0830433 -0.00400731 0.0555971 0.0848594 0.0100141 0.0544971 0.0843609 -0.0368713 0.0530971 -0.0765296 -0.0597241 0.0530971 -0.0604123 -0.0688537 0.0530971 -0.0497588 -0.0761054 0.0519971 -0.0377479 -0.0812812 0.0519971 -0.0247072 -0.08424 0.0519971 -0.0109925 -0.0812812 0.0530971 -0.0247072 -0.084901 0.0519971 0.0030221 -0.08424 0.0530971 -0.0109925 -0.0832464 0.0519971 0.0169544 -0.0832464 0.0530971 0.0169544 -0.079321 0.0519971 0.0304244 -0.079321 0.0530971 0.0304244 -0.0732322 0.0519971 0.0430645 -0.0732322 0.0530971 0.0430645 -0.0651459 0.0519971 0.0545301 -0.0651459 0.0530971 0.0545301 -0.0552827 0.0530971 0.0645083 -0.031343 0.0519971 0.078962 -0.0179195 0.0530971 0.0830433 0.0100141 0.0519971 0.0843609 0.0100141 0.0530971 0.0843609 -0.0368713 0.0494971 -0.0765296 -0.0489654 0.0505971 -0.0694178 -0.0597241 0.0494971 -0.0604123 -0.0597241 0.0505971 -0.0604123 -0.0688537 0.0505971 -0.0497588 -0.0761054 0.0505971 -0.0377479 -0.0812812 0.0494971 -0.0247072 -0.0812812 0.0505971 -0.0247072 -0.084901 0.0505971 0.0030221 -0.0732322 0.0494971 0.0430645 -0.0732322 0.0505971 0.0430645 -0.0651459 0.0494971 0.0545301 -0.031343 0.0505971 0.078962 -0.00400731 0.0494971 0.0848594 -0.00400731 0.0505971 0.0848594 0.0100141 0.0505971 0.0843609 -0.0237715 0.0469971 -0.0815538 -0.0237715 0.0480971 -0.0815538 -0.0368713 0.0469971 -0.0765296 -0.0489654 0.0469971 -0.0694178 -0.0368713 0.0480971 -0.0765296 -0.0597241 0.0469971 -0.0604123 -0.0597241 0.0480971 -0.0604123 -0.0688537 0.0480971 -0.0497588 -0.0688537 0.0469971 -0.0497588 -0.0761054 0.0469971 -0.0377479 -0.0761054 0.0480971 -0.0377479 -0.08424 0.0469971 -0.0109925 -0.0812812 0.0480971 -0.0247072 -0.084901 0.0469971 0.0030221 -0.084901 0.0480971 0.0030221 -0.0832464 0.0469971 0.0169544 -0.079321 0.0469971 0.0304244 -0.0832464 0.0480971 0.0169544 -0.079321 0.0480971 0.0304244 -0.0651459 0.0480971 0.0545301 -0.0552827 0.0480971 0.0645083 -0.0552827 0.0469971 0.0645083 -0.031343 0.0469971 0.078962 -0.031343 0.0480971 0.078962 -0.00400731 0.0469971 0.0848594 0.0100141 0.0469971 0.0843609 0.0100141 0.0480971 0.0843609 -0.0489654 0.0444971 -0.0694178 -0.0597241 0.0455971 -0.0604123 -0.0688537 0.0455971 -0.0497588 -0.0761054 0.0455971 -0.0377479 -0.0761054 0.0444971 -0.0377479 -0.0812812 0.0444971 -0.0247072 -0.08424 0.0444971 -0.0109925 -0.084901 0.0455971 0.0030221 -0.084901 0.0444971 0.0030221 -0.0832464 0.0444971 0.0169544 -0.0832464 0.0455971 0.0169544 -0.079321 0.0444971 0.0304244 -0.0651459 0.0444971 0.0545301 -0.0552827 0.0455971 0.0645083 -0.0179195 0.0444971 0.0830433 0.0100141 0.0455971 0.0843609 0.0100141 0.0444971 0.0843609 -0.0237715 0.0430971 -0.0815538 -0.0368713 0.0430971 -0.0765296 -0.0489654 0.0414971 -0.0694178 -0.0597241 0.0414971 -0.0604123 -0.084901 0.0414971 0.0030221 -0.079321 0.0430971 0.0304244 -0.0732322 0.0414971 0.0430645 -0.0732322 0.0430971 0.0430645 -0.0651459 0.0414971 0.0545301 -0.0552827 0.0430971 0.0645083 -0.0439117 0.0430971 0.072727 -0.00400731 0.0430971 0.0848594 0.0237621 0.0430971 0.0815613 0.0151031 0.0675971 0.0518473 0.0151031 0.0790971 0.0518473 0.0242429 0.0675971 0.0482537 0.0325806 0.0675971 0.0430642 0.0242429 0.0790971 0.0482537 0.0398406 0.0675971 0.0364504 0.0457826 0.0675971 0.0286311 0.0457826 0.0790971 0.0286311 0.0385495 0.0675971 -0.037806 0.0451785 0.0790971 -0.0295679 0.0385495 0.0790971 -0.037806 0.0110811 0.0790971 -0.0528461 -0.0201157 0.0675971 -0.0501116 -0.0377461 0.0790971 -0.0386173 -0.0496434 0.0790971 -0.0212564 -0.0528348 0.0675971 -0.0111756 -0.0528348 0.0790971 -0.0111756 -0.0540005 0.0675971 -0.000666054 -0.0540005 0.0790971 -0.000666054 -0.0482646 0.0805971 -0.0206659 0.0439234 0.0805971 -0.0287465 -0.0525006 0.0805971 -0.000647448 -0.0308089 0.0805971 0.0425167 0.0205795 0.0805971 -0.0482927 -0.00968739 0.0805971 -0.0515956 -0.0433114 0.0805971 -0.0296741 -0.0225998 0.0805971 0.0473927 -0.0136433 0.0805971 0.0507013 0.0387338 0.0805971 0.035438 0.0488153 0.0805971 0.0193133 0.00531179 0.0805971 0.0522339 0.0524913 0.0805971 0.000654947 -0.0470305 0.0769971 0.0186031 0.0390032 0.0769971 -0.0162591 -0.0459972 0.0675971 -0.0708234 -0.025246 0.0675971 0.0767432 -0.0196421 0.0675971 0.0802355 0.0589291 0.0675971 0.0575692 0.0836272 0.0675971 0.0117303 0.0311492 0.0675971 -0.0784898 0.0311903 0.0675971 -0.0784735 0.0578858 0.0675971 0.00843395 -0.0180791 0.0675971 0.0617463 0.0304423 0.0675971 -0.0445943 0.0461652 0.0675971 -0.0274251 0.0483202 0.0675971 -0.0243912 -0.0468434 0.0675971 0.0702742 -0.0440357 0.0675971 0.0720667 -0.0698779 0.0675971 0.0447142 -0.0691451 0.0675971 0.0454522 0.0207939 0.0675971 0.0713755 0.0702985 0.0675971 0.0416636 0.0695004 0.0675971 0.0479709 0.0328515 0.0675971 -0.0777926 0.0318753 0.0675971 -0.076752 0.0331193 0.0675971 -0.0768257 0.034272 0.0675971 -0.0763524 0.0351357 0.0675971 -0.0696349 0.0362157 0.0675971 -0.0716307 0.0699862 0.0675971 -0.0392988 0.0664831 0.0675971 -0.0426527 0.0642353 0.0675971 -0.0548144 0.0645331 0.0675971 -0.0504972 0.0659821 0.0675971 -0.0505287 0.0672528 0.0675971 -0.0498315 0.0684195 0.0675971 -0.0446752 0.0685372 0.0675971 -0.0392673 0.0648559 0.0675971 -0.0450471 0.0673389 0.0675971 -0.0458726 0.0627263 0.0675971 -0.0488726 0.0727919 0.0675971 -0.0428036 0.0708161 0.0675971 -0.0442755 0.0696634 0.0675971 -0.0447489 0.0680361 0.0675971 -0.0471433 0.071075 0.0675971 -0.0399049 0.0757548 0.0675971 -0.0323859 0.0381521 0.0675971 -0.0736532 0.0375555 0.0675971 -0.0756338 0.039396 0.0675971 -0.0737269 0.0405487 0.0675971 -0.0732536 0.043829 0.0675971 -0.0721794 0.0417305 0.0675971 -0.0711306 0.0415256 0.0675971 -0.0699015 0.0408076 0.0675971 -0.068883 0.0442553 0.0675971 -0.0646159 0.0429846 0.0675971 -0.0653131 0.0453816 0.0675971 -0.0700975 0.0465343 0.0675971 -0.0696241 0.0477161 0.0675971 -0.0675011 0.0511617 0.0675971 -0.0625108 0.0419578 0.0675971 -0.0598287 0.0457044 0.0675971 -0.0646474 0.0764169 0.0675971 0.00303378 0.079054 0.0675971 -0.00383962 0.0828625 0.0675971 -0.00378005 0.0843994 0.0675971 -0.00278065 0.0836144 0.0675971 -0.00254091 0.0836459 0.0675971 -0.00109186 0.0844418 0.0675971 0.000772123 0.0733972 0.0675971 0.0353868 0.0725774 0.0675971 0.0366553 0.0734106 0.0675971 0.0375819 0.0699137 0.0675971 0.0361042 0.0756481 0.0675971 0.0375332 0.0737592 0.0675971 0.0387783 0.0735543 0.0675971 0.0400074 0.0765716 0.0675971 -0.0214521 0.0788159 0.0675971 -0.021417 0.0773204 0.0675971 -0.0210413 0.0779841 0.0675971 -0.0242715 0.0786633 0.0675971 -0.0239926 0.0791543 0.0675971 -0.0234465 0.0788449 0.0675971 -0.0302378 0.0793598 0.0675971 -0.0227415 0.0713747 0.0675971 0.0334505 0.0732796 0.0675971 0.0299789 0.0736359 0.0675971 0.014611 0.0786071 0.0675971 0.0308581 0.0772511 0.0675971 0.0341117 0.0766531 0.0675971 0.0337307 0.0759351 0.0675971 0.0347492 -0.0392757 0.0675971 -0.0685381 -0.0202945 0.0675971 -0.0696222 -0.0447905 0.0675971 -0.0690382 0.0486679 0.0675971 0.0690167 0.0471424 0.0675971 0.0680446 0.0427694 0.0675971 0.0718995 0.0413204 0.0675971 0.071931 0.0392979 0.0675971 0.0699946 0.0392664 0.0675971 0.0685456 0.0445762 0.0675971 0.0702749 0.0450884 0.0675971 0.0646592 0.0496802 0.0675971 0.0674069 0.0435994 0.0675971 0.0669227 0.0447812 0.0675971 0.0690457 0.0482686 0.0675971 0.062563 0.0540377 0.0675971 0.0616879 0.0548837 0.0675971 0.0641837 0.0503982 0.0675971 0.0663884 -0.0129587 0.0675971 0.0793173 -0.0178141 0.0675971 0.0825545 -0.00398375 0.0675971 0.08436 -0.00255358 0.0675971 0.0800008 -0.00570233 0.0675971 0.083546 -0.00685505 0.0675971 0.0830727 -0.0118228 0.0675971 0.0836227 -0.0124499 0.0675971 0.0810632 -0.00783189 0.0675971 0.0797206 -0.0366543 0.0675971 -0.0760792 -0.0400591 0.0675971 -0.0712263 -0.0236316 0.0675971 -0.0810738 -0.02237 0.0675971 -0.0767444 0.00456675 0.0675971 -0.0780569 0.0058981 0.0675971 -0.0834964 0.00792061 0.0675971 -0.08156 0.00725494 0.0675971 -0.0788403 0.00397442 0.0675971 -0.0843525 0.00102915 0.0675971 -0.0810926 0.000680515 0.0675971 -0.082289 0.00251271 0.0675971 -0.0814423 0.00320992 0.0675971 -0.082713 -0.00996442 0.0675971 -0.0838569 0.000824173 0.0675971 -0.0798635 0.000106194 0.0675971 -0.078845 -0.00370231 0.0675971 -0.0789046 -0.0789992 0.0675971 -0.00025747 -0.0800017 0.0675971 -0.00254516 -0.0812457 0.0675971 -0.00247148 -0.0787107 0.0675971 0.0126271 -0.0801521 0.0675971 0.00445322 -0.0835802 0.0675971 -0.0050678 -0.0833752 0.0675971 -0.00629694 -0.0837442 0.0675971 -0.0109278 -0.082958 0.0675971 -0.000171314 -0.0828719 0.0675971 0.00378755 -0.0844013 0.0675971 0.00300433 -0.0645808 0.0675971 0.0441221 -0.0699956 0.0675971 0.0393063 -0.0685465 0.0675971 0.0392748 -0.0672758 0.0675971 0.039972 -0.0708185 0.0675971 0.0460168 -0.0711485 0.0675971 0.044017 -0.0375648 0.0675971 0.0756413 -0.0307317 0.0675971 0.0720488 -0.0299798 0.0675971 0.073288 -0.0318847 0.0675971 0.0767595 -0.0331286 0.0675971 0.0768332 -0.0396104 0.0675971 0.0736923 -0.0381614 0.0675971 0.0736607 -0.0351145 0.0675971 0.0754332 -0.0361497 0.0675971 0.070807 -0.0384842 0.0675971 0.0682107 -0.0680139 0.0675971 0.0485999 -0.0684288 0.0675971 0.0446827 -0.0661091 0.0675971 0.0451283 -0.0659914 0.0675971 0.0505362 -0.0647625 0.0675971 0.0542091 -0.0681062 0.0675971 0.0499435 -0.0648652 0.0675971 0.0450546 -0.0628349 0.0675971 0.0436134 -0.045066 0.0675971 0.0492021 -0.0442647 0.0675971 0.0646234 -0.0422106 0.0675971 0.0680088 -0.0571271 0.0675971 0.0596677 -0.0453909 0.0675971 0.070105 -0.0473768 0.0675971 0.068705 -0.0549574 0.0675971 0.0641286 -0.0555244 0.0675971 0.06006 -0.057814 0.0675971 0.0615657 -0.0544597 0.0675971 0.0591027 -0.0468025 0.0675971 0.065261 -0.0543389 0.0675971 0.0583784 -0.0545443 0.0675971 0.0576734 -0.0502308 0.0675971 0.0507071 -0.0409673 0.0675971 0.0690362 -0.0416645 0.0675971 0.0703069 -0.0748556 0.0675971 -0.0353478 -0.0756855 0.0675971 -0.0303711 -0.0745328 0.0675971 -0.0298977 -0.0793182 0.0675971 -0.0129503 -0.0788487 0.0675971 -0.00725585 -0.0741464 0.0675971 0.011297 -0.0780654 0.0675971 -0.00456767 -0.0734066 0.0675971 -0.0353793 -0.0734199 0.0675971 -0.0375744 -0.0757533 0.0675971 -0.0373318 -0.0756574 0.0675971 -0.0375257 -0.0721359 0.0675971 -0.0346821 -0.0699231 0.0675971 -0.0360967 -0.068951 0.0675971 -0.037 -0.0666783 0.0675971 -0.0476416 -0.0625193 0.0675971 -0.0511627 -0.0646558 0.0675971 -0.0457053 -0.0723176 0.0675971 -0.0436155 -0.0646243 0.0675971 -0.0442562 -0.0653215 0.0675971 -0.0429856 -0.0682853 0.0675971 -0.0397197 -0.0690371 0.0675971 -0.0409589 -0.0692162 0.0675971 -0.047004 -0.0684485 0.0675971 -0.0494659 -0.0701391 0.0675971 -0.0447564 -0.0697905 0.0675971 -0.04356 0.0211676 0.0675971 -0.0496726 0.0204526 0.0675971 -0.0535619 0.0110811 0.0675971 -0.0528461 -0.0151741 0.0675971 -0.0520512 -0.00996404 0.0675971 -0.0530699 0.000569531 0.0675971 -0.0539932 -0.0536817 0.0675971 0.00167137 -0.0535703 0.0675971 -0.0204535 -0.0644413 0.0675971 -0.0172856 -0.00815509 0.0675971 0.0588543 0.0484086 0.0675971 0.042371 0.0538601 0.0675971 -0.00538055 0.00716878 0.0675971 -0.0827992 0.0178047 0.0675971 -0.082547 0.0209245 0.0675971 -0.0818117 0.0182898 0.0675971 -0.0772767 0.0146025 0.0675971 -0.0736368 0.0197021 0.0675971 -0.0770412 0.0208432 0.0675971 -0.078233 0.0181373 0.0675971 -0.0798522 0.0187789 0.0675971 -0.0802094 0.0548356 0.0675971 -0.0572766 0.0553684 0.0675971 -0.0637585 0.054948 0.0675971 -0.0641211 0.0564383 0.0675971 -0.0568843 0.0547848 0.0675971 -0.0596095 0.055515 0.0675971 -0.0600525 0.0578047 0.0675971 -0.0615582 0.079239 0.0675971 -0.0220172 0.0812947 0.0675971 -0.0133753 0.0827471 0.0675971 -0.0168471 0.0834955 0.0675971 0.00590652 0.0837348 0.0675971 0.0109353 0.0827983 0.0675971 0.0071772 0.0791625 0.0675971 0.00752936 0.0793089 0.0675971 0.0129578 0.0799924 0.0675971 0.00255266 0.0827271 0.0675971 0.00119493 0.0814414 0.0675971 0.00252112 0.0770217 0.0675971 0.0188566 0.0807935 0.0675971 0.0245693 0.0818261 0.0675971 0.020873 0.0797276 0.0675971 0.0204759 0.0782321 0.0675971 0.0208516 0.080066 0.0675971 0.0184464 0.0580752 0.0675971 0.0575878 0.053529 0.0675971 0.059942 0.0573264 0.0675971 0.0571769 0.0572757 0.0675971 0.054844 0.0518758 0.0675971 0.0542691 0.0580059 0.0675971 0.054401 0.0693572 0.0675971 0.0468658 0.068118 0.0675971 0.0476176 0.0594182 0.0675971 0.0546365 0.0599938 0.0675971 0.0566118 0.0236223 0.0675971 0.0810813 0.0024223 0.0675971 0.0782149 -0.000265887 0.0675971 0.0789982 0.00447634 0.0675971 0.0816003 0.00995509 0.0675971 0.0838644 0.00444481 0.0675971 0.0801512 0.00369297 0.0675971 0.0789121 -0.000748605 0.0675971 0.0844505 0.00253999 0.0675971 0.0836228 -0.00017973 0.0675971 0.0829571 -0.0189784 0.0675971 0.0770053 -0.0182991 0.0675971 0.0772842 -0.0181466 0.0675971 0.0798597 -0.0642446 0.0675971 0.0548219 -0.0605397 0.0675971 0.0588877 -0.0616888 0.0675971 0.0540461 -0.059943 0.0675971 0.0535374 -0.0793061 0.0675971 0.0231131 -0.0832984 0.0675971 0.0139308 -0.0766188 0.0675971 0.0238784 -0.0731708 0.0675971 0.0316377 -0.0788542 0.0675971 0.0302453 -0.0767713 0.0675971 0.0213029 -0.0761957 0.0675971 0.0232782 -0.0793247 0.0675971 0.0222592 -0.0789138 0.0675971 0.0215104 -0.0827564 0.0675971 0.0168546 -0.0774506 0.0675971 0.0210239 -0.069606 0.0675971 -0.0157805 -0.0774419 0.0675971 -0.0181004 -0.0802808 0.0675971 -0.0191439 -0.0818354 0.0675971 -0.0208655 -0.0789051 0.0675971 -0.0176139 -0.0809625 0.0675971 -0.0240301 -0.0790953 0.0675971 -0.0208255 -0.0782414 0.0675971 -0.0208441 -0.0774926 0.0675971 -0.0204333 -0.0810641 0.0675971 -0.0124415 -0.0826957 0.0675971 -0.0171425 -0.0800754 0.0675971 -0.0184389 -0.0573358 0.0675971 -0.0571694 -0.0594275 0.0675971 -0.054629 -0.0600032 0.0675971 -0.0566043 -0.0580846 0.0675971 -0.0575803 -0.0593726 0.0675971 -0.0600567 -0.0497538 0.0675971 -0.0632948 -0.0450223 0.0675971 -0.0654829 -0.0456898 0.0675971 -0.0699487 -0.0453709 0.0675971 -0.0666792 -0.0436143 0.0675971 -0.0628265 -0.0535383 0.0675971 -0.0599345 -0.0484831 0.0675971 -0.0625976 -0.0505056 0.0675971 -0.064534 -0.0505371 0.0675971 -0.065983 -0.0548931 0.0675971 -0.0641762 -0.0498399 0.0675971 -0.0672537 -0.0462041 0.0675971 -0.0676059 0.0502102 0.0675971 0.019865 0.0529769 0.0675971 0.0104419 0.0707439 0.0675971 0.00468695 0.0783293 0.0675971 0.00660275 0.06154 0.0675971 0.00736909 0.0723912 0.0675971 -0.0107807 0.0575143 0.0675971 -0.0064454 0.0667182 0.0675971 -0.00912754 0.0611783 0.0675971 -0.0281382 0.0668513 0.0675971 -0.0297914 0.0731615 0.0675971 -0.0316302 0.0787014 0.0675971 -0.0126196 0.07611 0.0675971 -0.0230362 0.0519744 0.0675971 -0.0254561 0.0542606 0.0675971 -0.0518767 0.0599336 0.0675971 -0.0535299 0.0535609 0.0675971 0.020461 0.0662596 0.0675971 0.037169 0.0607778 0.0675971 0.018358 0.064432 0.0675971 0.0172931 0.0713432 0.0675971 0.0320014 0.0341857 0.0675971 -0.0460266 0.0414025 0.0675971 -0.0481297 0.0310868 0.0675971 -0.0566608 0.0383036 0.0675971 -0.0587638 0.0450567 0.0675971 -0.0491946 0.054374 0.0675971 -0.0588607 0.0180698 0.0675971 -0.0617388 0.0395749 0.0675971 -0.0680056 -0.00457609 0.0675971 0.0780644 -0.00252594 0.0675971 0.0781712 -0.0030347 0.0675971 0.0764253 -0.00468787 0.0675971 0.0707524 0.0202851 0.0675971 0.0696297 0.018632 0.0675971 0.0639567 -0.0518851 0.0675971 -0.0542616 -0.0419611 0.0675971 -0.0571535 -0.0186413 0.0675971 -0.0639492 0.0129494 0.0675971 -0.0793098 -0.0146119 0.0675971 0.0736443 0.0491936 0.0675971 0.0450651 0.0625099 0.0675971 0.0511702 0.0598278 0.0675971 0.0419662 -0.0373315 0.0675971 0.068684 -0.0287132 0.0675971 0.0648452 -0.0279282 0.0675971 0.0675393 -0.017294 0.0675971 0.0644404 -0.00737001 0.0675971 0.0615484 0.0159498 0.0675971 0.0547527 0.0151647 0.0675971 0.0520587 0.0590427 0.0675971 0.0392721 0.0670447 0.0675971 0.0398631 0.068276 0.0675971 0.0397272 -0.0682538 0.0675971 -0.0382707 -0.0598371 0.0675971 -0.0419587 -0.0484179 0.0675971 -0.0423635 -0.0384939 0.0675971 -0.0452555 -0.039279 0.0675971 -0.0479496 0.0172847 0.0675971 -0.0644329 0.0279188 0.0675971 -0.0675318 0.0287039 0.0675971 -0.0648377 0.0359208 0.0675971 -0.0669408 0.0369991 0.0675971 -0.0689425 0.0362472 0.0675971 -0.0701817 -0.049203 0.0675971 -0.0450576 -0.0159591 0.0675971 -0.0547452 0.0252367 0.0675971 -0.0767357 0.0299705 0.0675971 -0.0732805 -0.0390847 0.0675971 0.0372697 -0.034195 0.0675971 0.0460341 -0.0395843 0.0675971 0.0680131 -0.059052 0.0675971 -0.0392646 -0.0294963 0.0675971 -0.0452317 -0.0770496 0.0675971 -0.019703 -0.0727049 0.0675971 -0.0264147 -0.0675402 0.0675971 -0.0279197 -0.0566692 0.0675971 -0.0310877 -0.0496434 0.0675971 -0.0212564 -0.046035 0.0675971 -0.0341866 -0.0445487 0.0675971 -0.0305221 -0.0377461 0.0675971 -0.0386173 -0.0627356 0.0675971 0.0488801 -0.0625307 0.0675971 0.0476509 -0.0531227 0.0675971 0.0407831 -0.0451878 0.0675971 0.0295754 -0.0724006 0.0675971 0.0107882 -0.0626884 0.0675971 0.00795797 -0.0686065 0.0675971 0.0303076 -0.0571484 0.0675971 0.0269686 -0.047958 0.0675971 0.039278 -0.0519837 0.0675971 0.0254636 -0.0461745 0.0675971 0.0274326 -0.0762803 0.0675971 0.0218489 -0.0668606 0.0675971 0.0297989 -0.0575236 0.0675971 0.0064529 0.0492485 0.0672971 0.0632815 0.049537 0.0672971 0.063519 0.0502082 0.0415971 0.0646254 0.0502082 0.0672971 0.0646254 0.0503037 0.0672971 0.065177 0.0502364 0.0415971 0.0659192 0.0496139 0.0672971 0.0670537 0.0496139 0.0415971 0.0670537 0.0484024 0.0415971 0.0628965 0.049537 0.0415971 0.063519 0.0497444 0.0412971 0.0633023 0.0505278 0.0412971 0.0659905 0.0485075 0.0415971 0.067725 0.0666352 0.0672971 0.0425292 0.067929 0.0672971 0.0425011 0.0697348 0.0672971 0.04423 0.069763 0.0672971 0.0455238 0.0691405 0.0672971 0.0466583 0.0691405 0.0415971 0.0466583 0.0680341 0.0672971 0.0473296 0.067929 0.0415971 0.0425011 0.069271 0.0412971 0.0429069 0.0690636 0.0415971 0.0431236 0.0697348 0.0415971 0.04423 0.069763 0.0415971 0.0455238 0.0744741 0.0672971 0.0302012 0.0744741 0.0415971 0.0302012 0.0746573 0.0415971 0.0302388 0.0755034 0.0672971 0.0306238 0.0757918 0.0672971 0.0308613 0.0757918 0.0415971 0.0308613 0.0764631 0.0672971 0.0319677 0.0762473 0.0415971 0.0314511 0.0765586 0.0415971 0.0325193 0.0764912 0.0415971 0.0332615 0.0763755 0.0415971 0.0336167 0.0758687 0.0672971 0.034396 0.0758687 0.0415971 0.034396 0.0757345 0.0415971 0.0345261 0.0757345 0.0672971 0.0345261 0.0747624 0.0672971 0.0350673 0.0764631 0.0415971 0.0319677 0.0755034 0.0415971 0.0306238 0.0756762 0.0412971 0.0303786 0.0813701 0.0415971 0.00281252 0.0825046 0.0415971 0.00343503 0.0831759 0.0672971 0.00454141 0.0831759 0.0415971 0.00454141 0.0825816 0.0415971 0.00696973 0.0814752 0.0672971 0.00764101 0.0800763 0.0415971 0.00284068 0.0827121 0.0412971 0.00321834 0.0834639 0.0412971 0.00445748 0.0832041 0.0415971 0.0058352 0.0834955 0.0412971 0.00590652 0.0470247 0.0675971 0.0626367 0.0471086 0.0672971 0.0629247 0.0482193 0.0672971 0.0628589 0.0484024 0.0672971 0.0628965 0.0494214 0.0675971 0.0630363 0.0502545 0.0675971 0.0639629 0.0499924 0.0672971 0.0641088 0.0506032 0.0675971 0.0651593 0.0502364 0.0672971 0.0659192 0.0494796 0.0672971 0.0671838 0.0501207 0.0672971 0.0662745 0.0700544 0.0675971 0.0455951 0.0690636 0.0672971 0.0431236 0.0700229 0.0675971 0.044146 0.069271 0.0675971 0.0429069 0.0680004 0.0675971 0.0422097 0.0745235 0.0675971 0.0299052 0.0746573 0.0672971 0.0302388 0.0756762 0.0675971 0.0303786 0.0762473 0.0672971 0.0314511 0.0765094 0.0675971 0.0313052 0.076858 0.0675971 0.0325016 0.0765586 0.0672971 0.0325193 0.0764912 0.0672971 0.0332615 0.0763755 0.0672971 0.0336167 0.0748463 0.0675971 0.0353553 0.0825816 0.0672971 0.00696973 0.0815591 0.0675971 0.00792903 0.0832041 0.0672971 0.0058352 0.0834639 0.0675971 0.00445748 0.0825046 0.0672971 0.00343503 0.0827121 0.0675971 0.00321834 0.0813701 0.0672971 0.00281252 0.0800763 0.0672971 0.00284068 -0.0177235 0.0675971 0.0792596 -0.0176027 0.0665971 0.0785352 -0.0178082 0.0665971 0.0778302 -0.0176027 0.0675971 0.0785352 -0.0182991 0.0665971 0.0772842 -0.0178082 0.0675971 0.0778302 -0.0189784 0.0665971 0.0770053 -0.0197115 0.0675971 0.0770487 -0.0555244 0.0665971 0.06006 -0.0548828 0.0665971 0.0597029 -0.0548828 0.0675971 0.0597029 -0.0544597 0.0665971 0.0591027 -0.0543389 0.0665971 0.0583784 -0.0545443 0.0665971 0.0576734 -0.0550353 0.0675971 0.0571273 -0.0557146 0.0675971 0.0568484 -0.0766188 0.0665971 0.0238784 -0.0772604 0.0675971 0.0242356 -0.0761957 0.0665971 0.0232782 -0.0762803 0.0665971 0.0218489 -0.0760749 0.0675971 0.0225539 -0.0767713 0.0665971 0.0213029 -0.0781836 0.0665971 0.0210674 -0.077031 0.0675971 -0.0188491 -0.0770496 0.0665971 -0.019703 -0.0790953 0.0665971 -0.0208255 -0.0580152 0.0675971 -0.0543935 -0.057285 0.0665971 -0.0548365 -0.057285 0.0675971 -0.0548365 -0.0568741 0.0675971 -0.0555853 -0.0568927 0.0665971 -0.0564392 -0.0568927 0.0675971 -0.0564392 -0.0573358 0.0665971 -0.0571694 -0.0589385 0.0665971 -0.0575617 -0.0589385 0.0675971 -0.0575617 0.0570799 0.0665971 -0.0572415 0.0570799 0.0675971 -0.0572415 0.057503 0.0665971 -0.0578417 0.057503 0.0675971 -0.0578417 0.0576238 0.0675971 -0.058566 0.0574183 0.0675971 -0.059271 0.0569273 0.0675971 -0.059817 0.0562481 0.0675971 -0.0600959 0.055515 0.0665971 -0.0600525 0.0197021 0.0665971 -0.0770412 0.0204323 0.0665971 -0.0774842 0.0204323 0.0675971 -0.0774842 0.0208246 0.0665971 -0.0790869 0.0208246 0.0675971 -0.0790869 0.0203816 0.0665971 -0.0798171 0.0203816 0.0675971 -0.0798171 0.0196328 0.0665971 -0.080228 0.0196328 0.0675971 -0.080228 0.0595707 0.0675971 0.057212 0.0599938 0.0665971 0.0566118 0.0601146 0.0665971 0.0558875 0.0601146 0.0675971 0.0558875 0.0599092 0.0665971 0.0551825 0.0594182 0.0665971 0.0546365 0.0599092 0.0675971 0.0551825 0.0587389 0.0675971 0.0543575 0.0587389 0.0665971 0.0543575 0.0580059 0.0665971 0.054401 0.079086 0.0675971 0.020833 0.0801507 0.0665971 0.0198757 0.0801507 0.0675971 0.0198757 0.0802715 0.0665971 0.0191514 0.0802715 0.0675971 0.0191514 0.080066 0.0665971 0.0184464 0.0795751 0.0665971 0.0179003 0.0795751 0.0675971 0.0179003 0.0788958 0.0675971 0.0176214 0.0781627 0.0675971 0.0176648 0.0781743 0.0675971 -0.0210599 0.079239 0.0665971 -0.0220172 0.0793598 0.0665971 -0.0227415 0.0779841 0.0665971 -0.0242715 0.077251 0.0675971 -0.0242281 0.0408337 0.0535971 0.0708459 0.0405456 0.0535971 0.0712546 0.0425456 0.0535971 0.0711314 0.0434307 0.0535971 0.0705944 0.0439287 0.0535971 0.0696867 0.0439062 0.0535971 0.0686517 0.0433692 0.0535971 0.0677666 0.0406488 0.0535971 0.0677241 0.040136 0.0535971 0.0684516 0.0399896 0.0535971 0.0693295 0.0396735 0.0535971 0.0682616 0.0437919 0.0535971 0.0709402 0.0442987 0.0672971 0.0701609 0.0444144 0.0535971 0.0698056 0.0444144 0.0672971 0.0698056 0.0441704 0.0672971 0.0679953 0.0443862 0.0535971 0.0685118 0.043715 0.0672971 0.0674055 0.043715 0.0535971 0.0674055 0.0434265 0.0672971 0.0671679 0.0412866 0.0535971 0.0668111 0.0425804 0.0535971 0.0667829 0.0412027 0.0675971 0.0665231 0.0412866 0.0672971 0.0668111 0.0423973 0.0672971 0.0667453 0.0425804 0.0672971 0.0667829 0.0424466 0.0675971 0.0664494 0.0444325 0.0675971 0.0678494 0.0443862 0.0672971 0.0685118 0.0444817 0.0672971 0.0690635 0.0438582 0.0675971 0.0712933 0.0436576 0.0672971 0.0710703 0.0437919 0.0672971 0.0709402 0.0714396 0.0535971 0.0370012 0.0713754 0.0535971 0.0364779 0.0691583 0.0535971 0.037215 0.0690215 0.0535971 0.0384684 0.0685358 0.0535971 0.0383495 0.068564 0.0535971 0.0396433 0.0704887 0.0535971 0.0408865 0.0692353 0.0535971 0.0407497 0.0703698 0.0535971 0.0413722 0.0729068 0.0535971 0.0394193 0.0732768 0.0535971 0.0398935 0.0716636 0.0535971 0.041344 0.0726357 0.0535971 0.0408028 0.0726357 0.0672971 0.0408028 0.0732768 0.0672971 0.0398935 0.0734598 0.0535971 0.038796 0.0731485 0.0672971 0.0377279 0.0731485 0.0535971 0.0377279 0.0724046 0.0535971 0.0369005 0.0702647 0.0535971 0.0365437 0.0713754 0.0672971 0.0364779 0.0717475 0.0675971 0.041632 0.0728363 0.0675971 0.0410259 0.0734598 0.0672971 0.038796 0.0724046 0.0672971 0.0369005 0.0714247 0.0675971 0.036182 0.0827763 0.0535971 -0.000997829 0.0834218 0.0535971 -0.00190535 0.0826736 0.0535971 -0.00273033 0.0820785 0.0535971 -0.00339219 0.0812551 0.0535971 -0.0037303 0.0813374 0.0535971 -0.00422349 0.078526 0.0535971 -0.0010581 0.0791973 0.0535971 4.8272e-05 0.0822634 0.0535971 -0.000270339 0.082732 0.0672971 -2.86532e-05 0.0816256 0.0535971 0.000642626 0.0825977 0.0535971 0.000101461 0.0832388 0.0535971 -0.000807901 0.0832388 0.0672971 -0.000807901 0.0833545 0.0672971 -0.00116319 0.0833263 0.0672971 -0.00245697 0.0831105 0.0672971 -0.00297352 0.0831105 0.0535971 -0.00297352 0.0826551 0.0672971 -0.00356335 0.0823666 0.0672971 -0.00380086 0.0823666 0.0535971 -0.00380086 0.0801428 0.0675971 -0.00444572 0.0815918 0.0675971 -0.00447726 0.0815205 0.0672971 -0.00418586 0.0834218 0.0672971 -0.00190535 0.0829487 0.0675971 0.000178813 0.042889 0.0528471 0.0700757 0.0431862 0.0528471 0.0688616 0.0422832 0.0528471 0.0679971 0.0424616 0.0535971 0.0672686 0.0416364 0.0420471 0.0680112 0.0422832 0.0420471 0.0679971 0.0428505 0.0528471 0.0683084 0.0431862 0.0420471 0.0688616 0.0432002 0.0528471 0.0695084 0.0423358 0.0528471 0.0704113 0.0428505 0.0420471 0.0683084 0.0439062 0.0412971 0.0686517 0.0432002 0.0420471 0.0695084 0.0439287 0.0412971 0.0696867 0.042889 0.0420471 0.0700757 0.0423358 0.0420471 0.0704113 0.0715237 0.0535971 0.040864 0.071867 0.0528471 0.0398083 0.0724088 0.0535971 0.040327 0.0721642 0.0528471 0.0385941 0.0728843 0.0535971 0.0383843 0.0718286 0.0528471 0.0380409 0.0723472 0.0535971 0.0374992 0.0712613 0.0528471 0.0377297 0.0706144 0.0528471 0.0377438 0.0704046 0.0535971 0.0370237 0.0706144 0.0420471 0.0377438 0.0721783 0.0528471 0.039241 0.0721783 0.0420471 0.039241 0.071867 0.0420471 0.0398083 0.0713139 0.0528471 0.0401439 0.0712613 0.0420471 0.0377297 0.0718286 0.0420471 0.0380409 0.0721642 0.0420471 0.0385941 0.0729068 0.0412971 0.0394193 0.0713139 0.0420471 0.0401439 0.0829227 0.0535971 -0.00187579 0.082174 0.0528471 -0.00183145 0.0811318 0.0528471 -0.00299051 0.0816464 0.0528471 -0.0027792 0.0816464 0.0420471 -0.0027792 0.0820183 0.0420471 -0.00236553 0.0820183 0.0528471 -0.00236553 0.0820825 0.0528471 -0.00128272 0.0817619 0.0528471 -0.000828039 0.0820825 0.0420471 -0.00128272 0.0812759 0.0528471 -0.000557457 0.0811318 0.0420471 -0.00299051 0.082174 0.0420471 -0.00183145 0.0827763 0.0412971 -0.000997829 0.0817619 0.0420471 -0.000828039 0.0814857 0.0412971 0.000162593 -0.00464741 0.0415971 0.0783558 -0.00351288 0.0672971 0.0789784 -0.00351288 0.0415971 0.0789784 -0.00305741 0.0415971 0.0795682 -0.00281344 0.0672971 0.0813785 -0.00292915 0.0415971 0.0817338 -0.0035702 0.0415971 0.0826432 -0.00454233 0.0415971 0.0831843 -0.00336961 0.0412971 0.0828662 -0.00343595 0.0415971 0.082513 -0.00265163 0.0412971 0.0818478 -0.00281344 0.0415971 0.0813785 -0.00244666 0.0412971 0.0806186 -0.00274614 0.0415971 0.0806364 -0.0028416 0.0415971 0.0800847 -0.00279529 0.0412971 0.0794223 -0.0059412 0.0415971 0.078384 -0.00602513 0.0412971 0.078096 -0.00483054 0.0415971 0.0783182 -0.00478119 0.0412971 0.0780223 -0.00380133 0.0415971 0.0787408 -0.0333675 0.0672971 0.0716712 -0.0309391 0.0672971 0.0722655 -0.0320737 0.0415971 0.071643 -0.0302397 0.0672971 0.0746657 -0.0302397 0.0415971 0.0746657 -0.0309391 0.0415971 0.0722655 -0.0307317 0.0412971 0.0720488 -0.0302679 0.0415971 0.0733719 -0.0299798 0.0412971 0.073288 -0.0299483 0.0412971 0.074737 -0.0308622 0.0415971 0.0758002 -0.0319686 0.0415971 0.0764715 -0.0306455 0.0412971 0.0760077 -0.044336 0.0672971 0.0649148 -0.0434899 0.0415971 0.0652998 -0.042746 0.0415971 0.0661271 -0.042502 0.0672971 0.0679374 -0.0426177 0.0415971 0.0682927 -0.0426177 0.0672971 0.0682927 -0.0431245 0.0672971 0.069072 -0.0442309 0.0672971 0.0697433 -0.0445191 0.0415971 0.0648771 -0.0444698 0.0412971 0.0645812 -0.043317 0.0412971 0.0650546 -0.0424347 0.0415971 0.0671953 -0.0432588 0.0415971 0.0692021 -0.0430582 0.0412971 0.0694252 -0.0649145 0.0672971 0.0453505 -0.0649145 0.0415971 0.0453505 -0.0647314 0.0415971 0.0453882 -0.0638853 0.0672971 0.0457732 -0.0635969 0.0672971 0.0460107 -0.0635969 0.0415971 0.0460107 -0.0631414 0.0415971 0.0466005 -0.0629256 0.0672971 0.0471171 -0.0628301 0.0415971 0.0476687 -0.0628974 0.0672971 0.0484108 -0.0628974 0.0415971 0.0484108 -0.0630131 0.0415971 0.0487661 -0.0635199 0.0415971 0.0495454 -0.0636542 0.0672971 0.0496755 -0.0646263 0.0672971 0.0502167 -0.0636542 0.0415971 0.0496755 -0.0645424 0.0412971 0.0505047 -0.0627356 0.0412971 0.0488801 -0.0629256 0.0415971 0.0471171 -0.0637125 0.0412971 0.045528 -0.0661091 0.0412971 0.0451283 -0.0638853 0.0415971 0.0457732 -0.00445839 0.0675971 0.0834723 -0.00343595 0.0672971 0.082513 -0.00321925 0.0675971 0.0827205 -0.00252204 0.0675971 0.0814498 -0.0028416 0.0672971 0.0800847 -0.00330541 0.0675971 0.0787617 -0.00464741 0.0672971 0.0783558 -0.00602513 0.0675971 0.078096 -0.0308622 0.0672971 0.0758002 -0.0306455 0.0675971 0.0760077 -0.0299483 0.0675971 0.074737 -0.0302679 0.0672971 0.0733719 -0.0320737 0.0672971 0.071643 -0.0320023 0.0675971 0.0713516 -0.0334514 0.0675971 0.0713832 -0.0456298 0.0672971 0.0649429 -0.0434899 0.0672971 0.0652998 -0.0432014 0.0672971 0.0655373 -0.042994 0.0675971 0.0653206 -0.0422421 0.0675971 0.0665597 -0.042746 0.0672971 0.0661271 -0.0425302 0.0672971 0.0666437 -0.044147 0.0675971 0.0700313 -0.0429078 0.0675971 0.0692794 -0.0424347 0.0672971 0.0671953 -0.0637125 0.0675971 0.045528 -0.0647314 0.0672971 0.0453882 -0.0628793 0.0675971 0.0464546 -0.0631414 0.0672971 0.0466005 -0.0628301 0.0672971 0.0476687 -0.0634536 0.0675971 0.0498986 -0.0635199 0.0672971 0.0495454 -0.0630131 0.0672971 0.0487661 -0.000555993 0.0535971 0.0799849 8.506e-05 0.0535971 0.0790756 0.000311973 0.0535971 0.0795515 0.00119707 0.0535971 0.0790145 0.00235098 0.0535971 0.0785063 0.0020856 0.0535971 0.0789618 -0.000427727 0.0535971 0.0821506 0.00128114 0.0535971 0.0828772 0.00245606 0.0535971 0.0833348 0.00309387 0.0535971 0.0824218 0.00360671 0.0535971 0.0816943 0.00356243 0.0535971 0.0826635 0.00418494 0.0535971 0.0815289 0.00375312 0.0535971 0.0808163 0.00290897 0.0535971 0.0792999 0.00245606 0.0672971 0.0833348 0.00418494 0.0672971 0.0815289 0.00415679 0.0535971 0.0802352 0.00348551 0.0535971 0.0791288 0.00235098 0.0672971 0.0785063 0.00105719 0.0535971 0.0785344 0.00377913 0.0675971 0.0828709 0.00356243 0.0672971 0.0826635 0.00415679 0.0672971 0.0802352 0.00348551 0.0672971 0.0791288 0.00105719 0.0672971 0.0785344 -0.0372732 0.0535971 0.0728316 -0.0395391 0.0535971 0.0734009 -0.0406922 0.0535971 0.0719453 -0.0407506 0.0535971 0.0692437 -0.0396442 0.0535971 0.0685724 -0.0385335 0.0535971 0.0685066 -0.0367604 0.0535971 0.0697566 -0.0364491 0.0535971 0.0708247 -0.0366322 0.0535971 0.0719222 -0.0382453 0.0535971 0.0733727 -0.0366322 0.0672971 0.0719222 -0.0375043 0.0535971 0.0689292 -0.0375043 0.0672971 0.0689292 -0.0382453 0.0672971 0.0733727 -0.0372732 0.0672971 0.0728316 -0.0370726 0.0675971 0.0730546 -0.0363546 0.0675971 0.0720361 -0.0364491 0.0672971 0.0708247 -0.0367604 0.0672971 0.0697566 -0.0364983 0.0675971 0.0696106 -0.0385335 0.0672971 0.0685066 -0.0674647 0.0535971 0.0410217 -0.066812 0.0535971 0.0412951 -0.0672157 0.0535971 0.0418762 -0.0674064 0.0535971 0.0437234 -0.0678749 0.0535971 0.0434817 -0.0685127 0.0535971 0.0443947 -0.0686526 0.0535971 0.0439146 -0.0709411 0.0535971 0.0438003 -0.0705953 0.0535971 0.0434391 -0.0716124 0.0535971 0.0426939 -0.071018 0.0535971 0.0402656 -0.0697717 0.0535971 0.0400744 -0.0686178 0.0535971 0.0395662 -0.0685127 0.0672971 0.0443947 -0.0667839 0.0535971 0.0425888 -0.066812 0.0672971 0.0412951 -0.0674833 0.0535971 0.0401887 -0.0686178 0.0672971 0.0395662 -0.0699116 0.0535971 0.0395943 -0.0674064 0.0672971 0.0437234 -0.0667839 0.0672971 0.0425888 -0.0671897 0.0675971 0.0439308 -0.0664925 0.0675971 0.0426602 -0.066524 0.0675971 0.0412111 -0.0674833 0.0672971 0.0401887 -0.0699116 0.0672971 0.0395943 0.0014069 0.0528471 0.0797345 0.0020538 0.0528471 0.0797204 0.00262106 0.0528471 0.0800317 0.0028488 0.0528471 0.0803266 0.0035041 0.0535971 0.0799618 0.0029567 0.0528471 0.0805849 0.00297078 0.0528471 0.0812318 0.00210634 0.0528471 0.0821347 0.00231617 0.0535971 0.0828547 0.0025924 0.0528471 0.0818641 0.00196223 0.0528471 0.0797016 0.00247684 0.0528471 0.0799129 0.0029567 0.0420471 0.0805849 0.00300443 0.0528471 0.0808607 0.00297078 0.0420471 0.0812318 0.00291293 0.0528471 0.0814094 0.00265953 0.0420471 0.081799 0.00265953 0.0528471 0.081799 0.0020538 0.0420471 0.0797204 0.0022321 0.0412971 0.0789919 0.00262106 0.0420471 0.0800317 0.00320127 0.0412971 0.0823177 0.00210634 0.0420471 0.0821347 -0.0383852 0.0535971 0.0728927 -0.0375001 0.0535971 0.0723557 -0.0377447 0.0528471 0.0706228 -0.0370021 0.0535971 0.071448 -0.0380803 0.0528471 0.0700696 -0.0370246 0.0535971 0.070413 -0.0375617 0.0535971 0.0695279 -0.0386476 0.0528471 0.0697584 -0.0384693 0.0535971 0.0690299 -0.0392945 0.0528471 0.0697725 -0.0392945 0.0420471 0.0697725 -0.0386476 0.0420471 0.0697584 -0.0380803 0.0420471 0.0700696 -0.0377306 0.0528471 0.0712697 -0.0380419 0.0528471 0.071837 -0.0380419 0.0420471 0.071837 -0.038595 0.0420471 0.0721726 -0.0377447 0.0420471 0.0706228 -0.0377306 0.0420471 0.0712697 -0.0370021 0.0412971 0.071448 -0.0383852 0.0412971 0.0728927 -0.0688832 0.0535971 0.0400217 -0.0695619 0.0528471 0.0407944 -0.0690066 0.0528471 0.0407615 -0.0680598 0.0535971 0.0403598 -0.0683477 0.0528471 0.0410916 -0.0680121 0.0528471 0.0416448 -0.0679644 0.0528471 0.0419206 -0.0673621 0.0535971 0.0427542 -0.0683764 0.0528471 0.042924 -0.0688625 0.0420471 0.0431946 -0.0688625 0.0528471 0.0431946 -0.0683093 0.0420471 0.0428589 -0.0683093 0.0528471 0.0428589 -0.0680559 0.0420471 0.0424693 -0.0680559 0.0528471 0.0424693 -0.067998 0.0528471 0.0422917 -0.06812 0.0528471 0.0413865 -0.06812 0.0420471 0.0413865 -0.068492 0.0528471 0.0409728 -0.068915 0.0528471 0.0407803 -0.068915 0.0420471 0.0407803 -0.0678749 0.0412971 0.0434817 -0.0683764 0.0420471 0.042924 -0.067998 0.0420471 0.0422917 -0.0679644 0.0420471 0.0419206 -0.0672157 0.0412971 0.0418762 -0.0680121 0.0420471 0.0416448 -0.0674647 0.0412971 0.0410217 -0.0683477 0.0420471 0.0410916 -0.0680598 0.0412971 0.0403598 -0.068492 0.0420471 0.0409728 -0.0695619 0.0420471 0.0407944 -0.0697717 0.0412971 0.0400744 -0.0690066 0.0420471 0.0407615 0.00453299 0.0672971 -0.0831768 0.00564365 0.0672971 -0.0832426 0.00582678 0.0672971 -0.083205 0.00564365 0.0415971 -0.0832426 0.00667286 0.0672971 -0.08282 0.00696131 0.0415971 -0.0825825 0.00741678 0.0415971 -0.0819926 0.00763259 0.0672971 -0.0814761 0.00772805 0.0672971 -0.0809245 0.00772805 0.0415971 -0.0809245 0.00754504 0.0672971 -0.079827 0.00754504 0.0415971 -0.079827 0.00703824 0.0672971 -0.0790478 0.00703824 0.0415971 -0.0790478 0.00690399 0.0415971 -0.0789177 0.00725494 0.0412971 -0.0788403 0.00792061 0.0412971 -0.08156 0.00766075 0.0415971 -0.0801823 0.00763259 0.0415971 -0.0814761 0.00716878 0.0412971 -0.0827992 0.00453299 0.0415971 -0.0831768 0.00444906 0.0412971 -0.0834648 0.00582678 0.0415971 -0.083205 0.00667286 0.0415971 -0.08282 0.0330699 0.0672971 -0.0765298 0.033253 0.0672971 -0.0764922 0.0340991 0.0672971 -0.0761072 0.0343876 0.0415971 -0.0758696 0.034843 0.0672971 -0.0752798 0.034843 0.0415971 -0.0752798 0.0350588 0.0672971 -0.0747633 0.0351543 0.0415971 -0.0742116 0.0349713 0.0415971 -0.0731142 0.0344645 0.0415971 -0.072335 0.0343302 0.0672971 -0.0722048 0.0334421 0.0412971 -0.0713757 0.0333581 0.0415971 -0.0716637 0.0343302 0.0415971 -0.0722048 0.0345308 0.0412971 -0.0719818 0.0352488 0.0412971 -0.0730002 0.035087 0.0415971 -0.0734695 0.0350588 0.0415971 -0.0747633 0.0351052 0.0412971 -0.0754257 0.0319593 0.0415971 -0.076464 0.0318753 0.0412971 -0.076752 0.0330699 0.0415971 -0.0765298 0.033253 0.0415971 -0.0764922 0.0340991 0.0415971 -0.0761072 0.0442216 0.0415971 -0.0697358 0.0463614 0.0672971 -0.0693789 0.0466499 0.0415971 -0.0691414 0.0471053 0.0672971 -0.0685516 0.0473493 0.0415971 -0.0667412 0.0472336 0.0672971 -0.066386 0.0467268 0.0672971 -0.0656067 0.0467268 0.0415971 -0.0656067 0.0456204 0.0672971 -0.0649354 0.0441376 0.0412971 -0.0700238 0.0455154 0.0415971 -0.0697639 0.0473212 0.0415971 -0.068035 0.0476407 0.0412971 -0.0666699 0.0456204 0.0415971 -0.0649354 0.0677166 0.0672971 -0.0485084 0.0671222 0.0672971 -0.0460801 0.0660159 0.0415971 -0.0454088 0.064617 0.0415971 -0.0502092 0.0659108 0.0415971 -0.0502373 0.0645331 0.0412971 -0.0504972 0.0670453 0.0415971 -0.0496148 0.0677166 0.0415971 -0.0485084 0.0677447 0.0415971 -0.0472146 0.0680361 0.0412971 -0.0471433 0.0671222 0.0415971 -0.0460801 0.0673389 0.0412971 -0.0458726 0.00696131 0.0672971 -0.0825825 0.00741678 0.0672971 -0.0819926 0.00795215 0.0675971 -0.080111 0.00766075 0.0672971 -0.0801823 0.00593186 0.0672971 -0.0783765 0.0060158 0.0675971 -0.0780885 0.00690399 0.0672971 -0.0789177 0.0319593 0.0672971 -0.076464 0.0343876 0.0672971 -0.0758696 0.0351052 0.0675971 -0.0754257 0.0354538 0.0675971 -0.0742294 0.0351543 0.0672971 -0.0742116 0.035087 0.0672971 -0.0734695 0.0349713 0.0672971 -0.0731142 0.0352488 0.0675971 -0.0730002 0.0345308 0.0675971 -0.0719818 0.0333581 0.0672971 -0.0716637 0.0334421 0.0675971 -0.0713757 0.0344645 0.0672971 -0.072335 0.0441376 0.0675971 -0.0700238 0.0442216 0.0672971 -0.0697358 0.0453322 0.0672971 -0.0698015 0.0455154 0.0672971 -0.0697639 0.0466499 0.0672971 -0.0691414 0.0473675 0.0675971 -0.0686975 0.0473212 0.0672971 -0.068035 0.0474166 0.0672971 -0.0674834 0.0473493 0.0672971 -0.0667412 0.0475111 0.0675971 -0.066272 0.0465926 0.0672971 -0.0654766 0.0467931 0.0675971 -0.0652535 0.0660998 0.0675971 -0.0451208 0.0677447 0.0672971 -0.0472146 0.0680046 0.0675971 -0.0485924 0.0670453 0.0672971 -0.0496148 0.0659108 0.0672971 -0.0502373 0.000154176 0.0535971 -0.0814866 0.000418393 0.0535971 -0.0821431 -0.000382847 0.0535971 -0.0823717 -0.000325522 0.0535971 -0.0829704 -0.00246539 0.0535971 -0.0833272 -0.0023255 0.0535971 -0.0828472 -0.00357177 0.0535971 -0.082656 -0.00368609 0.0535971 -0.0803675 -0.00314906 0.0535971 -0.0794824 -0.00224144 0.0535971 -0.0789844 -0.00120641 0.0535971 -0.079007 -0.000321307 0.0535971 -0.079544 -9.43935e-05 0.0535971 -0.0790681 0.00054666 0.0535971 -0.0799775 -0.00106652 0.0535971 -0.0785269 -9.43935e-05 0.0672971 -0.0790681 0.000729671 0.0535971 -0.0810749 -0.00135473 0.0535971 -0.083393 -0.00106652 0.0672971 -0.0785269 0.00054666 0.0672971 -0.0799775 0.000729671 0.0672971 -0.0810749 0.000418393 0.0672971 -0.0821431 -0.000325522 0.0672971 -0.0829704 -0.00135473 0.0672971 -0.083393 -0.00015267 0.0675971 -0.0832156 -0.00246539 0.0672971 -0.0833272 -0.00130539 0.0675971 -0.0836889 -0.00254932 0.0675971 -0.0836153 0.041248 0.0535971 -0.0700154 0.040607 0.0535971 -0.0691061 0.0396349 0.0535971 -0.0685649 0.0414311 0.0535971 -0.0711129 0.0403185 0.0535971 -0.0724097 0.0403759 0.0535971 -0.0730084 0.0365353 0.0535971 -0.0702656 0.037188 0.0535971 -0.0699923 0.0414311 0.0672971 -0.0711129 0.0411198 0.0535971 -0.072181 0.0393467 0.0535971 -0.073431 0.0393467 0.0672971 -0.073431 0.038236 0.0535971 -0.0733652 0.0397188 0.0675971 -0.0682769 0.040607 0.0672971 -0.0691061 0.041248 0.0672971 -0.0700154 0.0411198 0.0672971 -0.072181 0.0403759 0.0672971 -0.0730084 0.0413819 0.0675971 -0.072327 0.038236 0.0672971 -0.0733652 0.0709503 0.0535971 -0.0429598 0.0703552 0.0535971 -0.0436216 0.067397 0.0535971 -0.0437159 0.0677582 0.0535971 -0.0433701 0.0672602 0.0535971 -0.0424625 0.0672827 0.0535971 -0.0414274 0.0668027 0.0535971 -0.0412876 0.067474 0.0535971 -0.0401812 0.0678197 0.0535971 -0.0405423 0.0699023 0.0535971 -0.0395868 0.0708744 0.0535971 -0.040128 0.0710529 0.0535971 -0.0412273 0.0711994 0.0535971 -0.0421052 0.0715155 0.0535971 -0.0410374 0.0715155 0.0672971 -0.0410374 0.0716985 0.0535971 -0.0421348 0.0713872 0.0535971 -0.043203 0.0716985 0.0672971 -0.0421348 0.0713872 0.0672971 -0.043203 0.0706433 0.0535971 -0.0440303 0.0706433 0.0672971 -0.0440303 0.0696141 0.0672971 -0.0444529 0.0696141 0.0535971 -0.0444529 0.0685034 0.0535971 -0.0443872 0.0708744 0.0672971 -0.040128 0.071793 0.0675971 -0.0409234 0.0719979 0.0675971 -0.0421525 0.0716493 0.0675971 -0.0433489 -0.00086305 0.0528471 -0.0800626 0.000176702 0.0535971 -0.0804516 -0.000551795 0.0528471 -0.0806299 -0.00129047 0.0535971 -0.0828697 -0.00146878 0.0528471 -0.0821413 -0.00211567 0.0528471 -0.0821272 -0.00211567 0.0420471 -0.0821272 -0.00146878 0.0420471 -0.0821413 -0.000901512 0.0528471 -0.08183 -0.000565873 0.0528471 -0.0812768 -0.000565873 0.0420471 -0.0812768 -0.00086305 0.0420471 -0.0800626 -0.00141624 0.0420471 -0.079727 -0.000901512 0.0420471 -0.08183 -0.000382847 0.0412971 -0.0823717 -0.000551795 0.0420471 -0.0806299 0.000176702 0.0412971 -0.0804516 0.0394109 0.0535971 -0.0729077 0.0392326 0.0528471 -0.0721792 0.0397999 0.0528471 -0.071868 0.0400276 0.0528471 -0.071573 0.0408556 0.0535971 -0.0715246 0.0401832 0.0528471 -0.071039 0.039495 0.0535971 -0.0690449 0.0398383 0.0528471 -0.0701006 0.0403801 0.0535971 -0.0695819 0.0400917 0.0528471 -0.0704902 0.0408781 0.0535971 -0.0704896 0.0396556 0.0528471 -0.0719867 0.0400276 0.0420471 -0.071573 0.0401355 0.0528471 -0.0713148 0.0401832 0.0420471 -0.071039 0.0401496 0.0528471 -0.0706679 0.0397712 0.0420471 -0.0700356 0.0392851 0.0420471 -0.069765 0.039141 0.0420471 -0.072198 0.0392644 0.0412971 -0.0729378 0.0396556 0.0420471 -0.0719867 0.0400917 0.0420471 -0.0704902 0.0402727 0.0412971 -0.0694779 0.0695318 0.0535971 -0.0439597 0.0686433 0.0535971 -0.0439071 0.0688531 0.0528471 -0.0431871 0.0694085 0.0528471 -0.04322 0.0695 0.0528471 -0.0432011 0.0699231 0.0528471 -0.0430086 0.0700673 0.0528471 -0.0428899 0.070295 0.0528471 -0.042595 0.0695526 0.0528471 -0.0407869 0.0697624 0.0535971 -0.0400669 0.0705401 0.0535971 -0.0404998 0.0701058 0.0528471 -0.0411225 0.0703592 0.0528471 -0.0415122 0.0700386 0.0420471 -0.0410575 0.0700386 0.0528471 -0.0410575 0.0703592 0.0420471 -0.0415122 0.070417 0.0528471 -0.0416898 0.0704507 0.0420471 -0.0420609 0.0704507 0.0528471 -0.0420609 0.0704029 0.0420471 -0.0423367 0.0704029 0.0528471 -0.0423367 0.070295 0.0420471 -0.042595 0.0699231 0.0420471 -0.0430086 0.0695 0.0420471 -0.0432011 0.0694085 0.0420471 -0.04322 0.0705401 0.0412971 -0.0404998 0.0701058 0.0420471 -0.0411225 0.0710529 0.0412971 -0.0412273 0.070417 0.0420471 -0.0416898 0.0711994 0.0412971 -0.0421052 0.0709503 0.0412971 -0.0429598 0.0700673 0.0420471 -0.0428899 0.0703552 0.0412971 -0.0436216 0.0695318 0.0412971 -0.0439597 0.0688531 0.0420471 -0.0431871 -0.046377 0.0672971 -0.0673607 -0.0453218 0.0415971 -0.0654652 -0.0455048 0.0415971 -0.0643677 -0.0461458 0.0672971 -0.0634583 -0.0461458 0.0415971 -0.0634583 -0.047118 0.0672971 -0.0629172 -0.0474062 0.0415971 -0.0677833 -0.046377 0.0415971 -0.0673607 -0.0456331 0.0415971 -0.0665333 -0.0459453 0.0412971 -0.0632353 -0.047034 0.0412971 -0.0626292 -0.0680434 0.0672971 -0.0473221 -0.0680434 0.0415971 -0.0473221 -0.0667497 0.0415971 -0.0473502 -0.0656151 0.0415971 -0.0467277 -0.0649438 0.0415971 -0.0456214 -0.0666446 0.0672971 -0.0425217 -0.0649157 0.0415971 -0.0443276 -0.0646243 0.0412971 -0.0442562 -0.0655382 0.0415971 -0.043193 -0.0653215 0.0412971 -0.0429856 -0.0666446 0.0415971 -0.0425217 -0.073661 0.0415971 -0.0351255 -0.0734779 0.0415971 -0.0350879 -0.0734779 0.0672971 -0.0350879 -0.0718879 0.0415971 -0.0338756 -0.0716439 0.0672971 -0.0320652 -0.0722664 0.0672971 -0.0309307 -0.0733728 0.0415971 -0.0302594 -0.0724007 0.0415971 -0.0308006 -0.0722664 0.0415971 -0.0309307 -0.0717596 0.0415971 -0.03171 -0.0714821 0.0412971 -0.031596 -0.0716439 0.0415971 -0.0320652 -0.0715766 0.0415971 -0.0328074 -0.0716258 0.0412971 -0.0340215 -0.0716721 0.0415971 -0.033359 -0.072459 0.0412971 -0.0349481 -0.0723434 0.0415971 -0.0344654 -0.0726318 0.0415971 -0.0347029 -0.0736117 0.0412971 -0.0354215 -0.0803739 0.0415971 -0.00769929 -0.0793446 0.0415971 -0.00727666 -0.0786007 0.0415971 -0.00644933 -0.0790562 0.0672971 -0.00703916 -0.0783849 0.0415971 -0.00593278 -0.0782895 0.0415971 -0.00538116 -0.0783849 0.0672971 -0.00593278 -0.0789793 0.0672971 -0.00350446 -0.0800856 0.0415971 -0.00283318 -0.0791135 0.0415971 -0.00337435 -0.0800856 0.0672971 -0.00283318 -0.0789793 0.0415971 -0.00350446 -0.0789129 0.0412971 -0.00315127 -0.0784725 0.0415971 -0.00428371 -0.0783568 0.0415971 -0.00463899 -0.078195 0.0412971 -0.00416975 -0.07799 0.0412971 -0.0053989 -0.0783386 0.0412971 -0.00659525 -0.0790562 0.0415971 -0.00703916 -0.0815684 0.0412971 -0.00792153 -0.0803245 0.0412971 -0.00799521 -0.0801907 0.0415971 -0.00766167 -0.0459453 0.0675971 -0.0632353 -0.0452273 0.0675971 -0.0642537 -0.0455048 0.0672971 -0.0643677 -0.0453218 0.0672971 -0.0654652 -0.0456331 0.0672971 -0.0665333 -0.0473568 0.0675971 -0.0680792 -0.0474062 0.0672971 -0.0677833 -0.0665606 0.0675971 -0.0422337 -0.0655382 0.0672971 -0.043193 -0.0649157 0.0672971 -0.0443276 -0.0649438 0.0672971 -0.0456214 -0.0654077 0.0675971 -0.0469444 -0.0656151 0.0672971 -0.0467277 -0.0667497 0.0672971 -0.0473502 -0.0732889 0.0675971 -0.0299714 -0.0720498 0.0675971 -0.0307233 -0.0713525 0.0675971 -0.0319939 -0.0716721 0.0672971 -0.033359 -0.0713841 0.0675971 -0.033443 -0.0723434 0.0672971 -0.0344654 -0.0787626 0.0675971 -0.00329699 -0.0783568 0.0672971 -0.00463899 -0.0780969 0.0675971 -0.00601671 -0.0801907 0.0672971 -0.00766167 -0.0801194 0.0675971 -0.00795307 -0.0814845 0.0672971 -0.00763351 -0.0395671 0.0535971 -0.0686094 -0.0401896 0.0535971 -0.0674749 -0.0414359 0.0535971 -0.0672836 -0.041296 0.0535971 -0.0668036 -0.0424709 0.0535971 -0.0672611 -0.0443956 0.0535971 -0.0685043 -0.0444237 0.0535971 -0.0697981 -0.0439381 0.0535971 -0.0696793 -0.042555 0.0535971 -0.0711239 -0.0416664 0.0535971 -0.0711765 -0.0395671 0.0672971 -0.0686094 -0.0395952 0.0535971 -0.0699032 -0.0395952 0.0672971 -0.0699032 -0.0402665 0.0535971 -0.0710096 -0.0402665 0.0672971 -0.0710096 -0.0414011 0.0535971 -0.0716321 -0.0426948 0.0535971 -0.0716039 -0.041212 0.0675971 -0.0665156 -0.0401896 0.0672971 -0.0674749 -0.0399729 0.0675971 -0.0672674 -0.0393072 0.0675971 -0.0699871 -0.0414011 0.0672971 -0.0716321 -0.0426948 0.0672971 -0.0716039 -0.0413297 0.0675971 -0.0719235 -0.0427788 0.0675971 -0.0718919 -0.0731578 0.0535971 -0.0377204 -0.0723566 0.0535971 -0.0374917 -0.0724139 0.0535971 -0.036893 -0.0713847 0.0535971 -0.0364704 -0.0704139 0.0535971 -0.0370162 -0.070274 0.0535971 -0.0365362 -0.0691677 0.0535971 -0.0372075 -0.0685733 0.0535971 -0.0396358 -0.0690533 0.0535971 -0.0394959 -0.0692446 0.0535971 -0.0407422 -0.070498 0.0535971 -0.040879 -0.0703791 0.0535971 -0.0413647 -0.071533 0.0535971 -0.0408565 -0.0716729 0.0535971 -0.0413365 -0.072645 0.0535971 -0.0407953 -0.0729161 0.0535971 -0.0394118 -0.0685451 0.0535971 -0.038342 -0.0685451 0.0672971 -0.038342 -0.0685733 0.0672971 -0.0396358 -0.0692446 0.0672971 -0.0407422 -0.0703791 0.0672971 -0.0413647 -0.0701901 0.0675971 -0.0362482 -0.0691677 0.0672971 -0.0372075 -0.0703078 0.0675971 -0.0416561 -0.0789928 0.0535971 0.00224052 -0.0790154 0.0535971 0.00120549 -0.0785072 0.0535971 0.00235939 -0.08046 0.0535971 -0.000177619 -0.0823802 0.0535971 0.00038193 -0.0828556 0.0535971 0.00232459 -0.081411 0.0535971 0.0037077 -0.0815299 0.0535971 0.00419336 -0.080376 0.0535971 0.00368517 -0.0802361 0.0535971 0.0041652 -0.0791297 0.0535971 0.00349392 -0.0785072 0.0672971 0.00235939 -0.0785353 0.0535971 0.0010656 -0.0792066 0.0535971 -4.07729e-05 -0.0803412 0.0535971 -0.000663283 -0.0816349 0.0672971 -0.000635126 -0.0791297 0.0672971 0.00349392 -0.078913 0.0675971 0.00370139 -0.0782158 0.0675971 0.00243071 -0.0785353 0.0672971 0.0010656 -0.0782473 0.0675971 0.000981671 -0.0792066 0.0672971 -4.07729e-05 -0.0803412 0.0672971 -0.000663283 -0.0802698 0.0675971 -0.000954682 -0.0817189 0.0675971 -0.000923146 -0.0416982 0.0528471 -0.0704179 -0.0412752 0.0528471 -0.0702254 -0.0408431 0.0535971 -0.0708384 -0.041131 0.0528471 -0.0701067 -0.0402479 0.0535971 -0.0701766 -0.0409032 0.0528471 -0.0698118 -0.0407953 0.0528471 -0.0695535 -0.0399989 0.0535971 -0.069322 -0.0407476 0.0528471 -0.0692777 -0.0401453 0.0535971 -0.0684441 -0.0408391 0.0528471 -0.0687289 -0.0416457 0.0528471 -0.0680037 -0.0406582 0.0535971 -0.0677166 -0.0410925 0.0528471 -0.0683393 -0.0416457 0.0420471 -0.0680037 -0.0411596 0.0528471 -0.0682743 -0.0410925 0.0420471 -0.0683393 -0.0408391 0.0420471 -0.0687289 -0.0407812 0.0420471 -0.0689066 -0.0407812 0.0528471 -0.0689066 -0.0416982 0.0420471 -0.0704179 -0.0417898 0.0420471 -0.0704367 -0.0417898 0.0528471 -0.0704367 -0.0423451 0.0420471 -0.0704039 -0.0414359 0.0412971 -0.0672836 -0.0411596 0.0420471 -0.0682743 -0.0401453 0.0412971 -0.0684441 -0.0407476 0.0420471 -0.0692777 -0.0407953 0.0420471 -0.0695535 -0.0399989 0.0412971 -0.069322 -0.0409032 0.0420471 -0.0698118 -0.0408431 0.0412971 -0.0708384 -0.041131 0.0420471 -0.0701067 -0.0412752 0.0420471 -0.0702254 -0.0695288 0.0535971 -0.0375532 -0.0697734 0.0528471 -0.0392861 -0.0690308 0.0535971 -0.0384609 -0.0706763 0.0528471 -0.0401505 -0.0695904 0.0535971 -0.040381 -0.0713232 0.0420471 -0.0401364 -0.0706763 0.0420471 -0.0401505 -0.070109 0.0528471 -0.0398393 -0.0697734 0.0420471 -0.0392861 -0.0697593 0.0528471 -0.0386392 -0.0700706 0.0420471 -0.0380719 -0.0700706 0.0528471 -0.0380719 -0.0706238 0.0528471 -0.0377363 -0.070109 0.0420471 -0.0398393 -0.0697593 0.0420471 -0.0386392 -0.0704139 0.0412971 -0.0370162 -0.0806383 0.0528471 0.000550878 -0.0802153 0.0528471 0.000743379 -0.0795524 0.0535971 0.000320389 -0.0800711 0.0528471 0.000862133 -0.0798433 0.0528471 0.00115705 -0.0797354 0.0528471 0.00141532 -0.0796877 0.0528471 0.00169113 -0.0794909 0.0535971 0.00314815 -0.0797213 0.0528471 0.00206222 -0.0802153 0.0420471 0.000743379 -0.0796877 0.0420471 0.00169113 -0.0797792 0.0420471 0.00223986 -0.0797792 0.0528471 0.00223986 -0.0800997 0.0420471 0.00269454 -0.0800326 0.0528471 0.00262948 -0.0805858 0.0528471 0.00296512 -0.0812852 0.0420471 0.000564956 -0.0807299 0.0420471 0.000532065 -0.0806065 0.0412971 -0.00020772 -0.0798433 0.0420471 0.00115705 0.0474019 0.0747265 -0.0231813 0.0461652 0.0790971 -0.0274251 0.0530312 0.0717645 -0.00386377 0.0529032 0.0734721 -0.00430303 0.053509 0.0722221 -0.00222443 0.0536723 0.0790971 -0.00166387 0.053381 0.0739296 -0.00266369 0.0517315 0.0772431 -0.00832378 0.0512337 0.0775971 -0.0100322 0.0486038 0.0775971 -0.0190568 0.0476839 0.069459 -0.0222136 0.048106 0.068451 -0.0207652 0.0466314 0.0715971 -0.0258253 0.0471488 0.0675971 -0.0240498 0.0468063 0.0717645 -0.0252252 0.0474019 0.0709676 -0.0231813 0.0473029 0.0727471 -0.0235211 0.0473029 0.0729471 -0.0235211 0.0469343 0.0734721 -0.024786 0.0536723 0.0675971 -0.00166387 0.0526887 0.0675971 -0.00503918 0.0521536 0.069459 -0.00687545 0.0529032 0.0722221 -0.00430303 0.0524356 0.0709676 -0.00590771 0.0525346 0.0727471 -0.00556789 0.0525346 0.0729471 -0.00556789 0.0512337 0.0680971 -0.0100322 0.0434306 0.0739296 -0.00106603 0.0439552 0.0728471 0.000734092 0.0439083 0.0734721 0.000573311 0.0436054 0.0740971 -0.00046599 0.0437803 0.0739296 0.000134051 0.0433026 0.0734721 -0.00150529 0.0530312 0.0739296 -0.00386377 0.0532061 0.0740971 -0.00326373 0.053509 0.0734721 -0.00222443 0.0370308 0.0740971 -0.0230275 0.0372056 0.0739296 -0.0224275 0.0363097 0.0728471 -0.0228174 0.0462817 0.0728471 -0.0270254 0.0367279 0.0734721 -0.0240668 0.0463285 0.0734721 -0.0268646 0.0368559 0.0739296 -0.0236276 0.0464566 0.0739296 -0.0264253 0.0466314 0.0740971 -0.0258253 0.0468063 0.0739296 -0.0252252 0.0373336 0.0734721 -0.0219882 0.0373805 0.0728471 -0.0218275 -0.0463379 0.0734721 0.0268721 -0.0473122 0.0729471 0.0235286 -0.0474112 0.0747265 0.0231888 -0.0523697 0.0704221 0.00617349 -0.0535652 0.0728471 0.00207115 -0.0535183 0.0734721 0.00223193 -0.0536817 0.0790971 0.00167137 -0.0530406 0.0739296 0.00387127 -0.0521629 0.0762351 0.00688295 -0.0524449 0.0747265 0.00591521 -0.052544 0.0729471 0.00557539 -0.052698 0.0675971 0.00504668 -0.0533903 0.0717645 0.00267119 -0.0517409 0.0772431 0.00833128 -0.0486132 0.0775971 0.0190643 -0.0476932 0.0762351 0.0222211 -0.0471581 0.0675971 0.0240573 -0.0466407 0.0715971 0.0258328 -0.0474865 0.0704221 0.0229305 -0.0469905 0.0728471 0.0246327 -0.0469436 0.0734721 0.0247935 -0.0461745 0.0790971 0.0274326 -0.0468156 0.0739296 0.0252327 -0.0479627 0.06872 0.0212965 -0.051243 0.0680971 0.0100397 -0.0530406 0.0717645 0.00387127 -0.0368652 0.0739296 0.0236351 -0.036319 0.0728471 0.0228249 -0.0366904 0.0728471 0.0242351 -0.046291 0.0728471 0.0270329 -0.0367372 0.0734721 0.0240743 -0.0464659 0.0739296 0.0264328 -0.0370401 0.0740971 0.023035 -0.0466407 0.0740971 0.0258328 -0.0372149 0.0739296 0.022435 -0.037343 0.0734721 0.0219957 -0.0436148 0.0740971 0.000473489 -0.0428937 0.0728471 0.000263358 -0.0432651 0.0728471 0.00167357 -0.0528657 0.0728471 0.00447131 -0.0433119 0.0734721 0.00151279 -0.0529126 0.0734721 0.00431053 -0.0434399 0.0739296 0.00107353 -0.0532154 0.0740971 0.00327123 -0.0437896 0.0739296 -0.000126552 -0.0439176 0.0734721 -0.000565812 -0.0533903 0.0739296 0.00267119 0.0539912 0.0675971 0.000673553 0.0451785 0.0675971 -0.0295679 0.0727919 0.0432971 -0.0428036 0.054948 0.0432971 -0.0641211 0.0311492 0.0432971 -0.0784898 0.043799 0.0432971 -0.0725483 0.0178047 0.0432971 -0.082547 0.00398856 0.0432971 -0.0846521 -0.00999981 0.0432971 -0.0841548 -0.0237155 0.0432971 -0.0813618 -0.0236316 0.0432971 -0.0810738 -0.0367845 0.0432971 -0.0763494 -0.0488502 0.0432971 -0.0692543 -0.0686916 0.0432971 -0.0496416 -0.0756574 0.0432971 -0.0375257 -0.0808028 0.0432971 -0.0245618 -0.0840416 0.0432971 -0.0109667 -0.0830504 0.0432971 0.0169145 -0.0728012 0.0432971 0.0428111 -0.0647625 0.0432971 0.0542091 -0.0730598 0.0432971 0.0429631 -0.0549574 0.0432971 0.0641286 -0.0551526 0.0432971 0.0643564 -0.0436533 0.0432971 0.072299 -0.0438083 0.0432971 0.0725558 -0.0311586 0.0432971 0.0784973 -0.0178773 0.0432971 0.0828478 -0.00398375 0.0432971 0.08436 -0.00399789 0.0432971 0.0846596 0.00999047 0.0432971 0.0841623 0.0237062 0.0432971 0.0813693 0.0367751 0.0432971 0.0763569 0.0366449 0.0432971 0.0760867 0.0486679 0.0432971 0.0690167 0.0595741 0.0432971 0.0602775 0.0756481 0.0432971 0.0375332 0.0759169 0.0432971 0.0376665 0.0837348 0.0432971 0.0109353 0.0846918 0.0432971 -0.00300749 -0.0366543 0.0432971 -0.0760792 -0.0486773 0.0432971 -0.0690092 -0.0593726 0.0432971 -0.0600567 -0.0486773 0.0442971 -0.0690092 -0.0593726 0.0442971 -0.0600567 -0.0684485 0.0432971 -0.0494659 -0.0756574 0.0442971 -0.0375257 -0.0808028 0.0442971 -0.0245618 -0.0837442 0.0432971 -0.0109278 -0.0844013 0.0432971 0.00300433 -0.0844013 0.0442971 0.00300433 -0.0827564 0.0442971 0.0168546 -0.0827564 0.0432971 0.0168546 -0.0788542 0.0432971 0.0302453 -0.0647625 0.0442971 0.0542091 -0.0549574 0.0442971 0.0641286 -0.0311586 0.0442971 0.0784973 -0.0178141 0.0432971 0.0825545 -0.0178141 0.0442971 0.0825545 0.00995509 0.0432971 0.0838644 0.00995509 0.0442971 0.0838644 0.0647532 0.0442971 -0.0542016 0.0649832 0.0442971 -0.0543942 0.0727919 0.0442971 -0.0428036 0.0730505 0.0442971 -0.0429556 0.0827471 0.0442971 -0.0168471 0.0837348 0.0442971 0.0109353 0.0846918 0.0442971 -0.00300749 0.0840323 0.0442971 0.0109742 0.0756481 0.0442971 0.0375332 0.0593632 0.0442971 0.0600642 0.0595741 0.0442971 0.0602775 0.0236223 0.0442971 0.0810813 -0.00398375 0.0442971 0.08436 -0.0436533 0.0442971 0.072299 -0.0438083 0.0442971 0.0725558 -0.0728012 0.0442971 0.0428111 -0.0730598 0.0442971 0.0429631 -0.0788542 0.0442971 0.0302453 -0.0837442 0.0442971 -0.0109278 -0.0840416 0.0442971 -0.0109667 -0.0810898 0.0442971 -0.0246491 -0.0684485 0.0442971 -0.0494659 -0.0686916 0.0442971 -0.0496416 -0.0595835 0.0442971 -0.06027 -0.0366543 0.0442971 -0.0760792 -0.0367845 0.0442971 -0.0763494 -0.0236316 0.0442971 -0.0810738 -0.0237155 0.0442971 -0.0813618 -0.00996442 0.0442971 -0.0838569 0.00397442 0.0442971 -0.0843525 0.017868 0.0442971 -0.0828403 0.0312599 0.0442971 -0.0787686 0.043644 0.0442971 -0.0722915 -0.0489654 0.0430971 -0.0694178 -0.0597241 0.0430971 -0.0604123 -0.0595835 0.0432971 -0.06027 -0.0688537 0.0430971 -0.0497588 -0.0759262 0.0432971 -0.037659 -0.0761054 0.0430971 -0.0377479 -0.0812812 0.0430971 -0.0247072 -0.0810898 0.0432971 -0.0246491 -0.08424 0.0430971 -0.0109925 -0.084901 0.0430971 0.0030221 -0.0832464 0.0430971 0.0169544 -0.0847012 0.0432971 0.00301499 -0.0791343 0.0432971 0.0303527 -0.0649926 0.0432971 0.0544017 -0.0651459 0.0430971 0.0545301 -0.031343 0.0430971 0.078962 -0.0312692 0.0432971 0.0787761 -0.0179195 0.0430971 0.0830433 0.0100141 0.0430971 0.0843609 0.00999047 0.0442971 0.0841623 -0.00399789 0.0442971 0.0846596 -0.00400731 0.0444971 0.0848594 -0.0178773 0.0442971 0.0828478 -0.031343 0.0444971 0.078962 -0.0439117 0.0444971 0.072727 -0.0312692 0.0442971 0.0787761 -0.0552827 0.0444971 0.0645083 -0.0551526 0.0442971 0.0643564 -0.0649926 0.0442971 0.0544017 -0.0732322 0.0444971 0.0430645 -0.0791343 0.0442971 0.0303527 -0.0830504 0.0442971 0.0169145 -0.0847012 0.0442971 0.00301499 -0.0759262 0.0442971 -0.037659 -0.0688537 0.0444971 -0.0497588 -0.0597241 0.0444971 -0.0604123 -0.0488502 0.0442971 -0.0692543 -0.0368713 0.0444971 -0.0765296 0.0551433 0.0457971 -0.0643489 0.0311492 0.0457971 -0.0784898 0.0312599 0.0457971 -0.0787686 0.017868 0.0457971 -0.0828403 0.00398856 0.0457971 -0.0846521 0.00397442 0.0457971 -0.0843525 -0.0367845 0.0457971 -0.0763494 -0.0488502 0.0457971 -0.0692543 -0.0486773 0.0457971 -0.0690092 -0.0593726 0.0457971 -0.0600567 -0.0595835 0.0457971 -0.06027 -0.0756574 0.0457971 -0.0375257 -0.0808028 0.0457971 -0.0245618 -0.0810898 0.0457971 -0.0246491 -0.0847012 0.0457971 0.00301499 -0.0844013 0.0457971 0.00300433 -0.0791343 0.0457971 0.0303527 -0.0788542 0.0457971 0.0302453 -0.0728012 0.0457971 0.0428111 -0.0647625 0.0457971 0.0542091 -0.0549574 0.0457971 0.0641286 -0.0436533 0.0457971 0.072299 -0.0438083 0.0457971 0.0725558 -0.0312692 0.0457971 0.0787761 -0.0178773 0.0457971 0.0828478 0.00999047 0.0457971 0.0841623 0.0236223 0.0457971 0.0810813 0.0237062 0.0457971 0.0813693 0.0486679 0.0457971 0.0690167 0.0367751 0.0457971 0.0763569 0.0684392 0.0457971 0.0494734 0.0756481 0.0457971 0.0375332 0.0837348 0.0457971 0.0109353 0.0810805 0.0457971 0.0246566 0.0827471 0.0457971 -0.0168471 0.0730505 0.0457971 -0.0429556 0.054948 0.0457971 -0.0641211 -0.0366543 0.0457971 -0.0760792 -0.0486773 0.0467971 -0.0690092 -0.0684485 0.0457971 -0.0494659 -0.0756574 0.0467971 -0.0375257 -0.0837442 0.0467971 -0.0109278 -0.0837442 0.0457971 -0.0109278 -0.0827564 0.0457971 0.0168546 -0.0827564 0.0467971 0.0168546 -0.0788542 0.0467971 0.0302453 -0.0728012 0.0467971 0.0428111 -0.0647625 0.0467971 0.0542091 -0.0549574 0.0467971 0.0641286 -0.0436533 0.0467971 0.072299 -0.0311586 0.0457971 0.0784973 -0.0178141 0.0457971 0.0825545 -0.00398375 0.0457971 0.08436 -0.0178141 0.0467971 0.0825545 -0.00398375 0.0467971 0.08436 0.00995509 0.0457971 0.0838644 0.00995509 0.0467971 0.0838644 0.0727919 0.0467971 -0.0428036 0.0730505 0.0467971 -0.0429556 0.0788449 0.0467971 -0.0302378 0.0827471 0.0467971 -0.0168471 0.084392 0.0467971 -0.00299683 0.0846918 0.0467971 -0.00300749 0.0840323 0.0467971 0.0109742 0.0837348 0.0467971 0.0109353 0.0807935 0.0467971 0.0245693 0.0810805 0.0467971 0.0246566 0.0756481 0.0467971 0.0375332 0.0686823 0.0467971 0.0496491 0.0486679 0.0467971 0.0690167 0.0366449 0.0467971 0.0760867 0.0237062 0.0467971 0.0813693 0.00999047 0.0467971 0.0841623 -0.0178773 0.0467971 0.0828478 -0.0311586 0.0467971 0.0784973 -0.0312692 0.0467971 0.0787761 -0.0649926 0.0467971 0.0544017 -0.0730598 0.0467971 0.0429631 -0.0844013 0.0467971 0.00300433 -0.0808028 0.0467971 -0.0245618 -0.0840416 0.0467971 -0.0109667 -0.0810898 0.0467971 -0.0246491 -0.0684485 0.0467971 -0.0494659 -0.0593726 0.0467971 -0.0600567 -0.0595835 0.0467971 -0.06027 -0.0366543 0.0467971 -0.0760792 -0.0367845 0.0467971 -0.0763494 -0.00996442 0.0467971 -0.0838569 0.00397442 0.0467971 -0.0843525 0.00398856 0.0467971 -0.0846521 0.0178047 0.0467971 -0.082547 0.0311492 0.0467971 -0.0784898 0.043644 0.0467971 -0.0722915 0.054948 0.0467971 -0.0641211 -0.0593726 0.0482971 -0.0600567 -0.0756574 0.0482971 -0.0375257 -0.0810898 0.0482971 -0.0246491 -0.0808028 0.0482971 -0.0245618 -0.0840416 0.0482971 -0.0109667 -0.0788542 0.0482971 0.0302453 -0.0728012 0.0482971 0.0428111 -0.0649926 0.0482971 0.0544017 -0.0647625 0.0482971 0.0542091 -0.0549574 0.0482971 0.0641286 -0.0436533 0.0482971 0.072299 -0.0311586 0.0482971 0.0784973 -0.0178773 0.0482971 0.0828478 0.0595741 0.0482971 0.0602775 0.0593632 0.0482971 0.0600642 0.0759169 0.0482971 0.0376665 0.0837348 0.0482971 0.0109353 0.0810805 0.0482971 0.0246566 0.0840323 0.0482971 0.0109742 0.0827471 0.0482971 -0.0168471 0.083041 0.0482971 -0.016907 0.079125 0.0482971 -0.0303452 0.0647532 0.0482971 -0.0542016 0.0551433 0.0482971 -0.0643489 0.043799 0.0482971 -0.0725483 0.017868 0.0482971 -0.0828403 0.00397442 0.0482971 -0.0843525 -0.00999981 0.0482971 -0.0841548 -0.0236316 0.0482971 -0.0810738 -0.0237155 0.0482971 -0.0813618 -0.0486773 0.0482971 -0.0690092 -0.0366543 0.0482971 -0.0760792 -0.0366543 0.0492971 -0.0760792 -0.0684485 0.0482971 -0.0494659 -0.0684485 0.0492971 -0.0494659 -0.0756574 0.0492971 -0.0375257 -0.0837442 0.0482971 -0.0109278 -0.0837442 0.0492971 -0.0109278 -0.0844013 0.0492971 0.00300433 -0.0844013 0.0482971 0.00300433 -0.0827564 0.0482971 0.0168546 -0.0827564 0.0492971 0.0168546 -0.0647625 0.0492971 0.0542091 -0.0549574 0.0492971 0.0641286 -0.0178141 0.0482971 0.0825545 -0.00398375 0.0482971 0.08436 0.00995509 0.0482971 0.0838644 0.0236223 0.0482971 0.0810813 0.00995509 0.0492971 0.0838644 0.0236223 0.0492971 0.0810813 0.0647532 0.0492971 -0.0542016 0.0727919 0.0492971 -0.0428036 0.0730505 0.0492971 -0.0429556 0.0788449 0.0492971 -0.0302378 0.079125 0.0492971 -0.0303452 0.084392 0.0492971 -0.00299683 0.0810805 0.0492971 0.0246566 0.0759169 0.0492971 0.0376665 0.0684392 0.0492971 0.0494734 0.0593632 0.0492971 0.0600642 0.0366449 0.0492971 0.0760867 0.0237062 0.0492971 0.0813693 -0.00398375 0.0492971 0.08436 -0.0178141 0.0492971 0.0825545 -0.0311586 0.0492971 0.0784973 -0.0178773 0.0492971 0.0828478 -0.0436533 0.0492971 0.072299 -0.0438083 0.0492971 0.0725558 -0.0551526 0.0492971 0.0643564 -0.0728012 0.0492971 0.0428111 -0.0788542 0.0492971 0.0302453 -0.0808028 0.0492971 -0.0245618 -0.0840416 0.0492971 -0.0109667 -0.0810898 0.0492971 -0.0246491 -0.0593726 0.0492971 -0.0600567 -0.0686916 0.0492971 -0.0496416 -0.0486773 0.0492971 -0.0690092 -0.0367845 0.0492971 -0.0763494 -0.00996442 0.0492971 -0.0838569 0.017868 0.0492971 -0.0828403 0.0311492 0.0492971 -0.0784898 0.043644 0.0492971 -0.0722915 -0.0486773 0.0507971 -0.0690092 -0.0488502 0.0507971 -0.0692543 -0.0684485 0.0507971 -0.0494659 -0.0808028 0.0507971 -0.0245618 -0.0810898 0.0507971 -0.0246491 -0.0837442 0.0507971 -0.0109278 -0.0844013 0.0507971 0.00300433 -0.0847012 0.0507971 0.00301499 -0.0827564 0.0507971 0.0168546 -0.0830504 0.0507971 0.0169145 -0.0788542 0.0507971 0.0302453 -0.0791343 0.0507971 0.0303527 -0.0730598 0.0507971 0.0429631 -0.0649926 0.0507971 0.0544017 -0.0436533 0.0507971 0.072299 -0.00398375 0.0507971 0.08436 -0.0178773 0.0507971 0.0828478 -0.00399789 0.0507971 0.0846596 0.00999047 0.0507971 0.0841623 0.0237062 0.0507971 0.0813693 0.0366449 0.0507971 0.0760867 0.0488408 0.0507971 0.0692618 0.0595741 0.0507971 0.0602775 0.0686823 0.0507971 0.0496491 0.0759169 0.0507971 0.0376665 0.0840323 0.0507971 0.0109742 0.0846918 0.0507971 -0.00300749 0.083041 0.0507971 -0.016907 0.0788449 0.0507971 -0.0302378 0.0647532 0.0507971 -0.0542016 0.0730505 0.0507971 -0.0429556 0.043644 0.0507971 -0.0722915 0.0312599 0.0507971 -0.0787686 0.0178047 0.0507971 -0.082547 0.017868 0.0507971 -0.0828403 0.00398856 0.0507971 -0.0846521 -0.00996442 0.0507971 -0.0838569 -0.00999981 0.0507971 -0.0841548 -0.0366543 0.0517971 -0.0760792 -0.0366543 0.0507971 -0.0760792 -0.0486773 0.0517971 -0.0690092 -0.0593726 0.0517971 -0.0600567 -0.0593726 0.0507971 -0.0600567 -0.0756574 0.0507971 -0.0375257 -0.0844013 0.0517971 0.00300433 -0.0728012 0.0507971 0.0428111 -0.0728012 0.0517971 0.0428111 -0.0647625 0.0517971 0.0542091 -0.0647625 0.0507971 0.0542091 -0.0549574 0.0507971 0.0641286 -0.0549574 0.0517971 0.0641286 -0.0436533 0.0517971 0.072299 -0.0311586 0.0507971 0.0784973 -0.0178141 0.0507971 0.0825545 0.00995509 0.0507971 0.0838644 0.054948 0.0517971 -0.0641211 0.0727919 0.0517971 -0.0428036 0.083041 0.0517971 -0.016907 0.0827471 0.0517971 -0.0168471 0.0846918 0.0517971 -0.00300749 0.0837348 0.0517971 0.0109353 0.0810805 0.0517971 0.0246566 0.0756481 0.0517971 0.0375332 0.0759169 0.0517971 0.0376665 0.0686823 0.0517971 0.0496491 0.0486679 0.0517971 0.0690167 0.0366449 0.0517971 0.0760867 0.0488408 0.0517971 0.0692618 0.0236223 0.0517971 0.0810813 0.00995509 0.0517971 0.0838644 0.00999047 0.0517971 0.0841623 -0.00398375 0.0517971 0.08436 -0.0178141 0.0517971 0.0825545 -0.0311586 0.0517971 0.0784973 -0.0312692 0.0517971 0.0787761 -0.0438083 0.0517971 0.0725558 -0.0649926 0.0517971 0.0544017 -0.0788542 0.0517971 0.0302453 -0.0827564 0.0517971 0.0168546 -0.0847012 0.0517971 0.00301499 -0.0837442 0.0517971 -0.0109278 -0.0810898 0.0517971 -0.0246491 -0.0808028 0.0517971 -0.0245618 -0.0756574 0.0517971 -0.0375257 -0.0759262 0.0517971 -0.037659 -0.0684485 0.0517971 -0.0494659 -0.0686916 0.0517971 -0.0496416 -0.0488502 0.0517971 -0.0692543 -0.0367845 0.0517971 -0.0763494 -0.0236316 0.0517971 -0.0810738 -0.0237155 0.0517971 -0.0813618 0.00398856 0.0517971 -0.0846521 0.017868 0.0517971 -0.0828403 0.0311492 0.0517971 -0.0784898 0.0312599 0.0517971 -0.0787686 0.043644 0.0517971 -0.0722915 0.043799 0.0517971 -0.0725483 0.0551433 0.0517971 -0.0643489 0.0730505 0.0532971 -0.0429556 0.0649832 0.0532971 -0.0543942 0.017868 0.0532971 -0.0828403 0.00397442 0.0532971 -0.0843525 -0.00996442 0.0532971 -0.0838569 -0.0367845 0.0532971 -0.0763494 -0.0486773 0.0532971 -0.0690092 -0.0488502 0.0532971 -0.0692543 -0.0593726 0.0532971 -0.0600567 -0.0595835 0.0532971 -0.06027 -0.0684485 0.0532971 -0.0494659 -0.0686916 0.0532971 -0.0496416 -0.0810898 0.0532971 -0.0246491 -0.0837442 0.0532971 -0.0109278 -0.0840416 0.0532971 -0.0109667 -0.0844013 0.0532971 0.00300433 -0.0847012 0.0532971 0.00301499 -0.0827564 0.0532971 0.0168546 -0.0730598 0.0532971 0.0429631 -0.0649926 0.0532971 0.0544017 -0.0549574 0.0532971 0.0641286 -0.0436533 0.0532971 0.072299 -0.0312692 0.0532971 0.0787761 -0.0178773 0.0532971 0.0828478 -0.00399789 0.0532971 0.0846596 0.00995509 0.0532971 0.0838644 0.0236223 0.0532971 0.0810813 0.0237062 0.0532971 0.0813693 0.0367751 0.0532971 0.0763569 0.0486679 0.0532971 0.0690167 0.0595741 0.0532971 0.0602775 0.0686823 0.0532971 0.0496491 0.0684392 0.0532971 0.0494734 0.0756481 0.0532971 0.0375332 0.0807935 0.0532971 0.0245693 0.0759169 0.0532971 0.0376665 0.0810805 0.0532971 0.0246566 0.0840323 0.0532971 0.0109742 0.084392 0.0532971 -0.00299683 0.0788449 0.0532971 -0.0302378 0.079125 0.0532971 -0.0303452 -0.0366543 0.0532971 -0.0760792 -0.0366543 0.0542971 -0.0760792 -0.0756574 0.0532971 -0.0375257 -0.0684485 0.0542971 -0.0494659 -0.0808028 0.0532971 -0.0245618 -0.0788542 0.0542971 0.0302453 -0.0788542 0.0532971 0.0302453 -0.0728012 0.0532971 0.0428111 -0.0728012 0.0542971 0.0428111 -0.0647625 0.0532971 0.0542091 -0.0436533 0.0542971 0.072299 -0.0311586 0.0532971 0.0784973 -0.0178141 0.0532971 0.0825545 -0.0178141 0.0542971 0.0825545 -0.00398375 0.0532971 0.08436 0.00995509 0.0542971 0.0838644 0.0236223 0.0542971 0.0810813 0.0827471 0.0542971 -0.0168471 0.079125 0.0542971 -0.0303452 0.0807935 0.0542971 0.0245693 0.0756481 0.0542971 0.0375332 0.0686823 0.0542971 0.0496491 0.0593632 0.0542971 0.0600642 0.0367751 0.0542971 0.0763569 0.0237062 0.0542971 0.0813693 0.00999047 0.0542971 0.0841623 -0.00399789 0.0542971 0.0846596 -0.00398375 0.0542971 0.08436 -0.0311586 0.0542971 0.0784973 -0.0178773 0.0542971 0.0828478 -0.0312692 0.0542971 0.0787761 -0.0549574 0.0542971 0.0641286 -0.0551526 0.0542971 0.0643564 -0.0649926 0.0542971 0.0544017 -0.0647625 0.0542971 0.0542091 -0.0730598 0.0542971 0.0429631 -0.0827564 0.0542971 0.0168546 -0.0844013 0.0542971 0.00300433 -0.0830504 0.0542971 0.0169145 -0.0847012 0.0542971 0.00301499 -0.0837442 0.0542971 -0.0109278 -0.0808028 0.0542971 -0.0245618 -0.0810898 0.0542971 -0.0246491 -0.0756574 0.0542971 -0.0375257 -0.0593726 0.0542971 -0.0600567 -0.0595835 0.0542971 -0.06027 -0.0486773 0.0542971 -0.0690092 -0.0367845 0.0542971 -0.0763494 0.00397442 0.0542971 -0.0843525 0.0178047 0.0542971 -0.082547 0.00398856 0.0542971 -0.0846521 0.0312599 0.0542971 -0.0787686 0.043644 0.0542971 -0.0722915 0.043799 0.0542971 -0.0725483 0.0730505 0.0542971 -0.0429556 0.0788449 0.0542971 -0.0302378 0.0727919 0.0557971 -0.0428036 0.054948 0.0557971 -0.0641211 0.0649832 0.0557971 -0.0543942 0.0551433 0.0557971 -0.0643489 0.043799 0.0557971 -0.0725483 0.0311492 0.0557971 -0.0784898 0.0312599 0.0557971 -0.0787686 0.017868 0.0557971 -0.0828403 0.00398856 0.0557971 -0.0846521 -0.00996442 0.0557971 -0.0838569 -0.00999981 0.0557971 -0.0841548 -0.0366543 0.0557971 -0.0760792 -0.0237155 0.0557971 -0.0813618 -0.0686916 0.0557971 -0.0496416 -0.0759262 0.0557971 -0.037659 -0.0837442 0.0557971 -0.0109278 -0.0840416 0.0557971 -0.0109667 -0.0847012 0.0557971 0.00301499 -0.0830504 0.0557971 0.0169145 -0.0791343 0.0557971 0.0303527 -0.0728012 0.0557971 0.0428111 -0.0730598 0.0557971 0.0429631 -0.0647625 0.0557971 0.0542091 -0.0649926 0.0557971 0.0544017 -0.0551526 0.0557971 0.0643564 -0.0436533 0.0557971 0.072299 -0.0312692 0.0557971 0.0787761 -0.0178773 0.0557971 0.0828478 -0.00398375 0.0557971 0.08436 -0.00399789 0.0557971 0.0846596 0.0236223 0.0557971 0.0810813 0.00999047 0.0557971 0.0841623 0.0237062 0.0557971 0.0813693 0.0595741 0.0557971 0.0602775 0.0807935 0.0557971 0.0245693 0.084392 0.0557971 -0.00299683 0.0840323 0.0557971 0.0109742 0.079125 0.0557971 -0.0303452 -0.0236316 0.0557971 -0.0810738 -0.0366543 0.0567971 -0.0760792 -0.0486773 0.0567971 -0.0690092 -0.0486773 0.0557971 -0.0690092 -0.0593726 0.0557971 -0.0600567 -0.0593726 0.0567971 -0.0600567 -0.0684485 0.0557971 -0.0494659 -0.0684485 0.0567971 -0.0494659 -0.0756574 0.0557971 -0.0375257 -0.0756574 0.0567971 -0.0375257 -0.0808028 0.0567971 -0.0245618 -0.0808028 0.0557971 -0.0245618 -0.0837442 0.0567971 -0.0109278 -0.0844013 0.0557971 0.00300433 -0.0827564 0.0557971 0.0168546 -0.0827564 0.0567971 0.0168546 -0.0788542 0.0567971 0.0302453 -0.0788542 0.0557971 0.0302453 -0.0728012 0.0567971 0.0428111 -0.0549574 0.0557971 0.0641286 -0.0549574 0.0567971 0.0641286 -0.0436533 0.0567971 0.072299 -0.0311586 0.0557971 0.0784973 -0.0178141 0.0557971 0.0825545 -0.00398375 0.0567971 0.08436 0.00995509 0.0567971 0.0838644 0.00995509 0.0557971 0.0838644 0.0236223 0.0567971 0.0810813 0.043644 0.0567971 -0.0722915 0.054948 0.0567971 -0.0641211 0.043799 0.0567971 -0.0725483 0.0551433 0.0567971 -0.0643489 0.0649832 0.0567971 -0.0543942 0.079125 0.0567971 -0.0303452 0.083041 0.0567971 -0.016907 0.0827471 0.0567971 -0.0168471 0.084392 0.0567971 -0.00299683 0.0846918 0.0567971 -0.00300749 0.0840323 0.0567971 0.0109742 0.0756481 0.0567971 0.0375332 0.0759169 0.0567971 0.0376665 0.0684392 0.0567971 0.0494734 0.0686823 0.0567971 0.0496491 0.0595741 0.0567971 0.0602775 0.0488408 0.0567971 0.0692618 0.0486679 0.0567971 0.0690167 0.0237062 0.0567971 0.0813693 0.00999047 0.0567971 0.0841623 -0.00399789 0.0567971 0.0846596 -0.0178141 0.0567971 0.0825545 -0.0311586 0.0567971 0.0784973 -0.0178773 0.0567971 0.0828478 -0.0647625 0.0567971 0.0542091 -0.0730598 0.0567971 0.0429631 -0.0791343 0.0567971 0.0303527 -0.0844013 0.0567971 0.00300433 -0.0810898 0.0567971 -0.0246491 -0.0759262 0.0567971 -0.037659 -0.0488502 0.0567971 -0.0692543 -0.0367845 0.0567971 -0.0763494 -0.00999981 0.0567971 -0.0841548 0.00398856 0.0567971 -0.0846521 0.0178047 0.0567971 -0.082547 0.017868 0.0567971 -0.0828403 0.079125 0.0582971 -0.0303452 0.0730505 0.0582971 -0.0429556 0.0647532 0.0582971 -0.0542016 0.054948 0.0582971 -0.0641211 0.0551433 0.0582971 -0.0643489 0.043644 0.0582971 -0.0722915 0.0178047 0.0582971 -0.082547 0.00398856 0.0582971 -0.0846521 -0.00996442 0.0582971 -0.0838569 -0.00999981 0.0582971 -0.0841548 -0.0236316 0.0582971 -0.0810738 -0.0486773 0.0582971 -0.0690092 -0.0367845 0.0582971 -0.0763494 -0.0488502 0.0582971 -0.0692543 -0.0595835 0.0582971 -0.06027 -0.0684485 0.0582971 -0.0494659 -0.0686916 0.0582971 -0.0496416 -0.0759262 0.0582971 -0.037659 -0.0840416 0.0582971 -0.0109667 -0.0844013 0.0582971 0.00300433 -0.0827564 0.0582971 0.0168546 -0.0791343 0.0582971 0.0303527 -0.0728012 0.0582971 0.0428111 -0.0649926 0.0582971 0.0544017 -0.0549574 0.0582971 0.0641286 -0.0551526 0.0582971 0.0643564 -0.0438083 0.0582971 0.0725558 -0.00398375 0.0582971 0.08436 0.00995509 0.0582971 0.0838644 0.00999047 0.0582971 0.0841623 0.0237062 0.0582971 0.0813693 0.0366449 0.0582971 0.0760867 0.0488408 0.0582971 0.0692618 0.0595741 0.0582971 0.0602775 0.0686823 0.0582971 0.0496491 0.0756481 0.0582971 0.0375332 0.0807935 0.0582971 0.0245693 0.0810805 0.0582971 0.0246566 0.0837348 0.0582971 0.0109353 0.084392 0.0582971 -0.00299683 0.083041 0.0582971 -0.016907 0.0788449 0.0582971 -0.0302378 -0.0366543 0.0582971 -0.0760792 -0.0366543 0.0592971 -0.0760792 -0.0486773 0.0592971 -0.0690092 -0.0593726 0.0582971 -0.0600567 -0.0684485 0.0592971 -0.0494659 -0.0756574 0.0582971 -0.0375257 -0.0808028 0.0582971 -0.0245618 -0.0837442 0.0582971 -0.0109278 -0.0844013 0.0592971 0.00300433 -0.0788542 0.0582971 0.0302453 -0.0788542 0.0592971 0.0302453 -0.0647625 0.0592971 0.0542091 -0.0647625 0.0582971 0.0542091 -0.0436533 0.0582971 0.072299 -0.0311586 0.0582971 0.0784973 -0.0178141 0.0582971 0.0825545 -0.0178141 0.0592971 0.0825545 0.0236223 0.0582971 0.0810813 0.0311492 0.0592971 -0.0784898 0.0312599 0.0592971 -0.0787686 0.054948 0.0592971 -0.0641211 0.0551433 0.0592971 -0.0643489 0.0846918 0.0592971 -0.00300749 0.084392 0.0592971 -0.00299683 0.0837348 0.0592971 0.0109353 0.0840323 0.0592971 0.0109742 0.0810805 0.0592971 0.0246566 0.0756481 0.0592971 0.0375332 0.0593632 0.0592971 0.0600642 0.0595741 0.0592971 0.0602775 0.0366449 0.0592971 0.0760867 0.0367751 0.0592971 0.0763569 0.0236223 0.0592971 0.0810813 0.00995509 0.0592971 0.0838644 -0.00398375 0.0592971 0.08436 -0.0311586 0.0592971 0.0784973 -0.0178773 0.0592971 0.0828478 -0.0438083 0.0592971 0.0725558 -0.0436533 0.0592971 0.072299 -0.0549574 0.0592971 0.0641286 -0.0728012 0.0592971 0.0428111 -0.0730598 0.0592971 0.0429631 -0.0827564 0.0592971 0.0168546 -0.0847012 0.0592971 0.00301499 -0.0840416 0.0592971 -0.0109667 -0.0837442 0.0592971 -0.0109278 -0.0808028 0.0592971 -0.0245618 -0.0756574 0.0592971 -0.0375257 -0.0593726 0.0592971 -0.0600567 -0.0686916 0.0592971 -0.0496416 -0.0595835 0.0592971 -0.06027 -0.0488502 0.0592971 -0.0692543 -0.0367845 0.0592971 -0.0763494 -0.0236316 0.0592971 -0.0810738 -0.0237155 0.0592971 -0.0813618 -0.00999981 0.0592971 -0.0841548 0.00397442 0.0592971 -0.0843525 0.0178047 0.0592971 -0.082547 0.0788449 0.0607971 -0.0302378 0.079125 0.0607971 -0.0303452 0.0730505 0.0607971 -0.0429556 0.0649832 0.0607971 -0.0543942 0.0551433 0.0607971 -0.0643489 0.043799 0.0607971 -0.0725483 0.0311492 0.0607971 -0.0784898 0.0178047 0.0607971 -0.082547 0.017868 0.0607971 -0.0828403 0.00397442 0.0607971 -0.0843525 -0.00996442 0.0607971 -0.0838569 0.00398856 0.0607971 -0.0846521 -0.0237155 0.0607971 -0.0813618 -0.0367845 0.0607971 -0.0763494 -0.0684485 0.0607971 -0.0494659 -0.0810898 0.0607971 -0.0246491 -0.0837442 0.0607971 -0.0109278 -0.0840416 0.0607971 -0.0109667 -0.0844013 0.0607971 0.00300433 -0.0791343 0.0607971 0.0303527 -0.0730598 0.0607971 0.0429631 -0.0549574 0.0607971 0.0641286 -0.0436533 0.0607971 0.072299 -0.0438083 0.0607971 0.0725558 -0.0312692 0.0607971 0.0787761 -0.0178141 0.0607971 0.0825545 -0.00398375 0.0607971 0.08436 0.00995509 0.0607971 0.0838644 0.0236223 0.0607971 0.0810813 0.0366449 0.0607971 0.0760867 0.0486679 0.0607971 0.0690167 0.0593632 0.0607971 0.0600642 0.0756481 0.0607971 0.0375332 0.0759169 0.0607971 0.0376665 0.0807935 0.0607971 0.0245693 0.084392 0.0607971 -0.00299683 0.0840323 0.0607971 0.0109742 0.0846918 0.0607971 -0.00300749 0.0827471 0.0607971 -0.0168471 0.083041 0.0607971 -0.016907 -0.0236316 0.0617971 -0.0810738 -0.0366543 0.0607971 -0.0760792 -0.0486773 0.0617971 -0.0690092 -0.0486773 0.0607971 -0.0690092 -0.0593726 0.0607971 -0.0600567 -0.0593726 0.0617971 -0.0600567 -0.0684485 0.0617971 -0.0494659 -0.0756574 0.0607971 -0.0375257 -0.0808028 0.0607971 -0.0245618 -0.0808028 0.0617971 -0.0245618 -0.0837442 0.0617971 -0.0109278 -0.0827564 0.0617971 0.0168546 -0.0827564 0.0607971 0.0168546 -0.0788542 0.0607971 0.0302453 -0.0728012 0.0607971 0.0428111 -0.0647625 0.0607971 0.0542091 -0.0311586 0.0607971 0.0784973 -0.00398375 0.0617971 0.08436 0.017868 0.0617971 -0.0828403 0.0312599 0.0617971 -0.0787686 0.0311492 0.0617971 -0.0784898 0.043644 0.0617971 -0.0722915 0.054948 0.0617971 -0.0641211 0.0647532 0.0617971 -0.0542016 0.0649832 0.0617971 -0.0543942 0.079125 0.0617971 -0.0303452 0.0827471 0.0617971 -0.0168471 0.083041 0.0617971 -0.016907 0.0837348 0.0617971 0.0109353 0.0840323 0.0617971 0.0109742 0.0756481 0.0617971 0.0375332 0.0686823 0.0617971 0.0496491 0.0595741 0.0617971 0.0602775 0.0486679 0.0617971 0.0690167 0.0367751 0.0617971 0.0763569 0.0237062 0.0617971 0.0813693 0.00995509 0.0617971 0.0838644 0.00999047 0.0617971 0.0841623 -0.0178141 0.0617971 0.0825545 -0.0311586 0.0617971 0.0784973 -0.0436533 0.0617971 0.072299 -0.0438083 0.0617971 0.0725558 -0.0549574 0.0617971 0.0641286 -0.0647625 0.0617971 0.0542091 -0.0728012 0.0617971 0.0428111 -0.0649926 0.0617971 0.0544017 -0.0788542 0.0617971 0.0302453 -0.0830504 0.0617971 0.0169145 -0.0844013 0.0617971 0.00300433 -0.0847012 0.0617971 0.00301499 -0.0840416 0.0617971 -0.0109667 -0.0810898 0.0617971 -0.0246491 -0.0756574 0.0617971 -0.0375257 -0.0595835 0.0617971 -0.06027 -0.0488502 0.0617971 -0.0692543 -0.0366543 0.0617971 -0.0760792 -0.00996442 0.0617971 -0.0838569 0.00398856 0.0617971 -0.0846521 0.043644 0.0632971 -0.0722915 0.0551433 0.0632971 -0.0643489 0.043799 0.0632971 -0.0725483 0.0312599 0.0632971 -0.0787686 0.0311492 0.0632971 -0.0784898 0.00397442 0.0632971 -0.0843525 -0.00996442 0.0632971 -0.0838569 -0.0236316 0.0632971 -0.0810738 -0.00999981 0.0632971 -0.0841548 -0.0486773 0.0632971 -0.0690092 -0.0595835 0.0632971 -0.06027 -0.0684485 0.0632971 -0.0494659 -0.0686916 0.0632971 -0.0496416 -0.0759262 0.0632971 -0.037659 -0.0808028 0.0632971 -0.0245618 -0.0837442 0.0632971 -0.0109278 -0.0830504 0.0632971 0.0169145 -0.0791343 0.0632971 0.0303527 -0.0728012 0.0632971 0.0428111 -0.0647625 0.0632971 0.0542091 -0.0649926 0.0632971 0.0544017 -0.0549574 0.0632971 0.0641286 -0.0551526 0.0632971 0.0643564 -0.0436533 0.0632971 0.072299 -0.0311586 0.0632971 0.0784973 -0.0312692 0.0632971 0.0787761 -0.0178773 0.0632971 0.0828478 0.00995509 0.0632971 0.0838644 0.0367751 0.0632971 0.0763569 0.0593632 0.0632971 0.0600642 0.0595741 0.0632971 0.0602775 0.0684392 0.0632971 0.0494734 0.0686823 0.0632971 0.0496491 0.0759169 0.0632971 0.0376665 0.0837348 0.0632971 0.0109353 0.0810805 0.0632971 0.0246566 0.0840323 0.0632971 0.0109742 0.0846918 0.0632971 -0.00300749 0.0788449 0.0632971 -0.0302378 -0.0366543 0.0642971 -0.0760792 -0.0366543 0.0632971 -0.0760792 -0.0593726 0.0632971 -0.0600567 -0.0593726 0.0642971 -0.0600567 -0.0684485 0.0642971 -0.0494659 -0.0756574 0.0632971 -0.0375257 -0.0844013 0.0632971 0.00300433 -0.0827564 0.0632971 0.0168546 -0.0788542 0.0632971 0.0302453 -0.0311586 0.0642971 0.0784973 -0.0178141 0.0632971 0.0825545 -0.00398375 0.0632971 0.08436 0.00995509 0.0642971 0.0838644 0.0236223 0.0632971 0.0810813 0.043644 0.0642971 -0.0722915 0.054948 0.0642971 -0.0641211 0.0730505 0.0642971 -0.0429556 0.0827471 0.0642971 -0.0168471 0.083041 0.0642971 -0.016907 0.084392 0.0642971 -0.00299683 0.0846918 0.0642971 -0.00300749 0.0807935 0.0642971 0.0245693 0.0756481 0.0642971 0.0375332 0.0810805 0.0642971 0.0246566 0.0593632 0.0642971 0.0600642 0.0488408 0.0642971 0.0692618 0.0236223 0.0642971 0.0810813 0.0237062 0.0642971 0.0813693 -0.00398375 0.0642971 0.08436 -0.0178141 0.0642971 0.0825545 -0.0178773 0.0642971 0.0828478 -0.0436533 0.0642971 0.072299 -0.0438083 0.0642971 0.0725558 -0.0549574 0.0642971 0.0641286 -0.0551526 0.0642971 0.0643564 -0.0647625 0.0642971 0.0542091 -0.0649926 0.0642971 0.0544017 -0.0728012 0.0642971 0.0428111 -0.0730598 0.0642971 0.0429631 -0.0788542 0.0642971 0.0302453 -0.0827564 0.0642971 0.0168546 -0.0844013 0.0642971 0.00300433 -0.0830504 0.0642971 0.0169145 -0.0837442 0.0642971 -0.0109278 -0.0840416 0.0642971 -0.0109667 -0.0808028 0.0642971 -0.0245618 -0.0810898 0.0642971 -0.0246491 -0.0756574 0.0642971 -0.0375257 -0.0759262 0.0642971 -0.037659 -0.0486773 0.0642971 -0.0690092 -0.0367845 0.0642971 -0.0763494 -0.0237155 0.0642971 -0.0813618 -0.0237715 0.0455971 -0.0815538 -0.0368713 0.0455971 -0.0765296 -0.0237155 0.0457971 -0.0813618 -0.0489654 0.0455971 -0.0694178 -0.0686916 0.0457971 -0.0496416 -0.0759262 0.0457971 -0.037659 -0.0812812 0.0455971 -0.0247072 -0.08424 0.0455971 -0.0109925 -0.0840416 0.0457971 -0.0109667 -0.0830504 0.0457971 0.0169145 -0.079321 0.0455971 0.0304244 -0.0732322 0.0455971 0.0430645 -0.0730598 0.0457971 0.0429631 -0.0651459 0.0455971 0.0545301 -0.0649926 0.0457971 0.0544017 -0.0551526 0.0457971 0.0643564 -0.0439117 0.0455971 0.072727 -0.031343 0.0455971 0.078962 -0.0179195 0.0455971 0.0830433 -0.00400731 0.0455971 0.0848594 -0.00399789 0.0457971 0.0846596 -0.00399789 0.0467971 0.0846596 -0.0179195 0.0469971 0.0830433 -0.0439117 0.0469971 0.072727 -0.0438083 0.0467971 0.0725558 -0.0551526 0.0467971 0.0643564 -0.0651459 0.0469971 0.0545301 -0.0732322 0.0469971 0.0430645 -0.0791343 0.0467971 0.0303527 -0.0830504 0.0467971 0.0169145 -0.0847012 0.0467971 0.00301499 -0.0812812 0.0469971 -0.0247072 -0.0759262 0.0467971 -0.037659 -0.0686916 0.0467971 -0.0496416 -0.0488502 0.0467971 -0.0692543 -0.0237155 0.0467971 -0.0813618 -0.0489654 0.0480971 -0.0694178 -0.0367845 0.0482971 -0.0763494 -0.0488502 0.0482971 -0.0692543 -0.0595835 0.0482971 -0.06027 -0.0686916 0.0482971 -0.0496416 -0.0759262 0.0482971 -0.037659 -0.08424 0.0480971 -0.0109925 -0.0847012 0.0482971 0.00301499 -0.0830504 0.0482971 0.0169145 -0.0791343 0.0482971 0.0303527 -0.0732322 0.0480971 0.0430645 -0.0730598 0.0482971 0.0429631 -0.0551526 0.0482971 0.0643564 -0.0439117 0.0480971 0.072727 -0.0438083 0.0482971 0.0725558 -0.0312692 0.0482971 0.0787761 -0.0179195 0.0480971 0.0830433 -0.00400731 0.0480971 0.0848594 -0.00399789 0.0482971 0.0846596 0.00999047 0.0482971 0.0841623 0.0100141 0.0494971 0.0843609 0.00999047 0.0492971 0.0841623 -0.00399789 0.0492971 0.0846596 -0.0179195 0.0494971 0.0830433 -0.031343 0.0494971 0.078962 -0.0439117 0.0494971 0.072727 -0.0312692 0.0492971 0.0787761 -0.0552827 0.0494971 0.0645083 -0.0649926 0.0492971 0.0544017 -0.0730598 0.0492971 0.0429631 -0.079321 0.0494971 0.0304244 -0.0791343 0.0492971 0.0303527 -0.0832464 0.0494971 0.0169544 -0.0830504 0.0492971 0.0169145 -0.084901 0.0494971 0.0030221 -0.08424 0.0494971 -0.0109925 -0.0847012 0.0492971 0.00301499 -0.0761054 0.0494971 -0.0377479 -0.0759262 0.0492971 -0.037659 -0.0688537 0.0494971 -0.0497588 -0.0595835 0.0492971 -0.06027 -0.0489654 0.0494971 -0.0694178 -0.0488502 0.0492971 -0.0692543 -0.0237715 0.0494971 -0.0815538 -0.0237155 0.0492971 -0.0813618 -0.0368713 0.0505971 -0.0765296 -0.0367845 0.0507971 -0.0763494 -0.0595835 0.0507971 -0.06027 -0.0686916 0.0507971 -0.0496416 -0.0759262 0.0507971 -0.037659 -0.08424 0.0505971 -0.0109925 -0.0840416 0.0507971 -0.0109667 -0.0832464 0.0505971 0.0169544 -0.079321 0.0505971 0.0304244 -0.0651459 0.0505971 0.0545301 -0.0552827 0.0505971 0.0645083 -0.0551526 0.0507971 0.0643564 -0.0439117 0.0505971 0.072727 -0.0438083 0.0507971 0.0725558 -0.0312692 0.0507971 0.0787761 -0.0179195 0.0505971 0.0830433 0.0237621 0.0519971 0.0815613 0.0237062 0.0517971 0.0813693 -0.00400731 0.0519971 0.0848594 -0.0179195 0.0519971 0.0830433 -0.00399789 0.0517971 0.0846596 -0.0178773 0.0517971 0.0828478 -0.0439117 0.0519971 0.072727 -0.0552827 0.0519971 0.0645083 -0.0551526 0.0517971 0.0643564 -0.0730598 0.0517971 0.0429631 -0.0791343 0.0517971 0.0303527 -0.0830504 0.0517971 0.0169145 -0.0840416 0.0517971 -0.0109667 -0.0688537 0.0519971 -0.0497588 -0.0597241 0.0519971 -0.0604123 -0.0595835 0.0517971 -0.06027 -0.0489654 0.0519971 -0.0694178 -0.0368713 0.0519971 -0.0765296 -0.0237155 0.0532971 -0.0813618 -0.0489654 0.0530971 -0.0694178 -0.0761054 0.0530971 -0.0377479 -0.0759262 0.0532971 -0.037659 -0.084901 0.0530971 0.0030221 -0.0830504 0.0532971 0.0169145 -0.0791343 0.0532971 0.0303527 -0.0439117 0.0530971 0.072727 -0.0551526 0.0532971 0.0643564 -0.0438083 0.0532971 0.0725558 -0.031343 0.0530971 0.078962 -0.00400731 0.0530971 0.0848594 0.0237621 0.0530971 0.0815613 0.00999047 0.0532971 0.0841623 -0.00400731 0.0544971 0.0848594 -0.031343 0.0544971 0.078962 -0.0552827 0.0544971 0.0645083 -0.0438083 0.0542971 0.0725558 -0.0651459 0.0544971 0.0545301 -0.0732322 0.0544971 0.0430645 -0.079321 0.0544971 0.0304244 -0.0791343 0.0542971 0.0303527 -0.0840416 0.0542971 -0.0109667 -0.0759262 0.0542971 -0.037659 -0.0761054 0.0544971 -0.0377479 -0.0686916 0.0542971 -0.0496416 -0.0488502 0.0542971 -0.0692543 -0.0237715 0.0555971 -0.0815538 -0.0489654 0.0555971 -0.0694178 -0.0367845 0.0557971 -0.0763494 -0.0488502 0.0557971 -0.0692543 -0.0595835 0.0557971 -0.06027 -0.0761054 0.0555971 -0.0377479 -0.0810898 0.0557971 -0.0246491 -0.084901 0.0555971 0.0030221 -0.0732322 0.0555971 0.0430645 -0.0651459 0.0555971 0.0545301 -0.0438083 0.0557971 0.0725558 -0.031343 0.0555971 0.078962 -0.0179195 0.0555971 0.0830433 0.0100141 0.0555971 0.0843609 0.0237621 0.0555971 0.0815613 0.0100141 0.0569971 0.0843609 -0.0179195 0.0569971 0.0830433 -0.031343 0.0569971 0.078962 -0.0312692 0.0567971 0.0787761 -0.0438083 0.0567971 0.0725558 -0.0551526 0.0567971 0.0643564 -0.0651459 0.0569971 0.0545301 -0.0649926 0.0567971 0.0544017 -0.0732322 0.0569971 0.0430645 -0.079321 0.0569971 0.0304244 -0.0830504 0.0567971 0.0169145 -0.0847012 0.0567971 0.00301499 -0.0840416 0.0567971 -0.0109667 -0.0686916 0.0567971 -0.0496416 -0.0688537 0.0569971 -0.0497588 -0.0597241 0.0569971 -0.0604123 -0.0595835 0.0567971 -0.06027 -0.0237155 0.0582971 -0.0813618 -0.0237715 0.0580971 -0.0815538 -0.0368713 0.0580971 -0.0765296 -0.0812812 0.0580971 -0.0247072 -0.0810898 0.0582971 -0.0246491 -0.08424 0.0580971 -0.0109925 -0.084901 0.0580971 0.0030221 -0.0847012 0.0582971 0.00301499 -0.0830504 0.0582971 0.0169145 -0.079321 0.0580971 0.0304244 -0.0732322 0.0580971 0.0430645 -0.0730598 0.0582971 0.0429631 -0.0651459 0.0580971 0.0545301 -0.0552827 0.0580971 0.0645083 -0.0312692 0.0582971 0.0787761 -0.0179195 0.0580971 0.0830433 -0.0178773 0.0582971 0.0828478 -0.00400731 0.0580971 0.0848594 -0.00399789 0.0582971 0.0846596 0.0100141 0.0580971 0.0843609 0.0100141 0.0594971 0.0843609 -0.00400731 0.0594971 0.0848594 0.00999047 0.0592971 0.0841623 -0.00399789 0.0592971 0.0846596 -0.0179195 0.0594971 0.0830433 -0.0312692 0.0592971 0.0787761 -0.0439117 0.0594971 0.072727 -0.0551526 0.0592971 0.0643564 -0.0651459 0.0594971 0.0545301 -0.0649926 0.0592971 0.0544017 -0.0732322 0.0594971 0.0430645 -0.079321 0.0594971 0.0304244 -0.0791343 0.0592971 0.0303527 -0.0830504 0.0592971 0.0169145 -0.08424 0.0594971 -0.0109925 -0.0812812 0.0594971 -0.0247072 -0.0810898 0.0592971 -0.0246491 -0.0759262 0.0592971 -0.037659 -0.0597241 0.0594971 -0.0604123 -0.0489654 0.0594971 -0.0694178 -0.0237715 0.0605971 -0.0815538 -0.0368713 0.0605971 -0.0765296 -0.0488502 0.0607971 -0.0692543 -0.0597241 0.0605971 -0.0604123 -0.0595835 0.0607971 -0.06027 -0.0686916 0.0607971 -0.0496416 -0.0761054 0.0605971 -0.0377479 -0.0759262 0.0607971 -0.037659 -0.0847012 0.0607971 0.00301499 -0.084901 0.0605971 0.0030221 -0.0830504 0.0607971 0.0169145 -0.0732322 0.0605971 0.0430645 -0.0649926 0.0607971 0.0544017 -0.0552827 0.0605971 0.0645083 -0.0551526 0.0607971 0.0643564 -0.031343 0.0605971 0.078962 -0.0178773 0.0607971 0.0828478 -0.00400731 0.0605971 0.0848594 -0.00399789 0.0607971 0.0846596 0.0100141 0.0605971 0.0843609 0.00999047 0.0607971 0.0841623 0.0237621 0.0605971 0.0815613 0.0100141 0.0619971 0.0843609 -0.00400731 0.0619971 0.0848594 -0.00399789 0.0617971 0.0846596 -0.0179195 0.0619971 0.0830433 -0.031343 0.0619971 0.078962 -0.0178773 0.0617971 0.0828478 -0.0312692 0.0617971 0.0787761 -0.0439117 0.0619971 0.072727 -0.0552827 0.0619971 0.0645083 -0.0551526 0.0617971 0.0643564 -0.0730598 0.0617971 0.0429631 -0.0732322 0.0619971 0.0430645 -0.079321 0.0619971 0.0304244 -0.0791343 0.0617971 0.0303527 -0.084901 0.0619971 0.0030221 -0.0759262 0.0617971 -0.037659 -0.0761054 0.0619971 -0.0377479 -0.0686916 0.0617971 -0.0496416 -0.0597241 0.0619971 -0.0604123 -0.0368713 0.0619971 -0.0765296 -0.0367845 0.0617971 -0.0763494 -0.0237155 0.0632971 -0.0813618 -0.0237715 0.0630971 -0.0815538 -0.0368713 0.0630971 -0.0765296 -0.0367845 0.0632971 -0.0763494 -0.0488502 0.0632971 -0.0692543 -0.0761054 0.0630971 -0.0377479 -0.08424 0.0630971 -0.0109925 -0.0810898 0.0632971 -0.0246491 -0.0840416 0.0632971 -0.0109667 -0.084901 0.0630971 0.0030221 -0.0847012 0.0632971 0.00301499 -0.0832464 0.0630971 0.0169544 -0.0730598 0.0632971 0.0429631 -0.0651459 0.0630971 0.0545301 -0.0552827 0.0630971 0.0645083 -0.0438083 0.0632971 0.0725558 -0.031343 0.0630971 0.078962 -0.00399789 0.0632971 0.0846596 0.00999047 0.0632971 0.0841623 0.0100141 0.0630971 0.0843609 0.0237062 0.0632971 0.0813693 0.00999047 0.0642971 0.0841623 0.0100141 0.0644971 0.0843609 -0.00400731 0.0644971 0.0848594 -0.00399789 0.0642971 0.0846596 -0.0312692 0.0642971 0.0787761 -0.0651459 0.0644971 0.0545301 -0.0732322 0.0644971 0.0430645 -0.0791343 0.0642971 0.0303527 -0.0847012 0.0642971 0.00301499 -0.0812812 0.0644971 -0.0247072 -0.0761054 0.0644971 -0.0377479 -0.0686916 0.0642971 -0.0496416 -0.0595835 0.0642971 -0.06027 -0.0597241 0.0644971 -0.0604123 -0.0488502 0.0642971 -0.0692543 -0.0418154 0.0727471 0.00307391 -0.0414835 0.0698833 0.00421276 -0.0504616 0.0698833 0.00682907 -0.0411159 0.0690053 0.0054742 -0.0496604 0.0686971 0.00957849 -0.0496604 0.0769971 0.00957849 -0.0406823 0.0769971 0.00696218 -0.0412488 0.0764545 0.00501805 -0.0507935 0.0729471 0.00569022 -0.0507072 0.0744969 0.0059862 -0.0506417 0.0749721 0.00621115 -0.0370056 0.0744969 0.0195791 -0.0458974 0.0729471 0.0224914 -0.0372512 0.0758108 0.0187362 -0.0462293 0.0758108 0.0213525 -0.0470305 0.0686971 0.0186031 -0.0369193 0.0727471 0.0198751 -0.0458974 0.0727471 0.0224914 0.0458881 0.0727471 -0.0224839 0.0459743 0.0711972 -0.0221879 0.0378701 0.0727471 -0.0201473 0.0380219 0.0707221 -0.0196264 0.0384366 0.0692397 -0.0182032 0.0384366 0.0764545 -0.0182032 0.04622 0.0758108 -0.021345 0.0460399 0.0749721 -0.0219629 0.0459743 0.0744969 -0.0221879 0.0427661 0.0729471 -0.00334619 0.0426143 0.0749721 -0.00386712 0.0504523 0.0758108 -0.00682157 0.0421996 0.0764545 -0.00529032 0.0500847 0.0766888 -0.00808302 0.041633 0.0769971 -0.00723445 0.0500847 0.0690053 -0.00808302 0.0426143 0.0707221 -0.00386712 0.0427661 0.0727471 -0.00334619 -0.0368713 0.0670971 -0.0765296 -0.0486773 0.0675971 -0.0690092 -0.0484558 0.0675971 -0.0691648 -0.0638732 0.0675971 -0.0552467 -0.0597241 0.0670971 -0.0604123 -0.0808028 0.0675971 -0.0245618 -0.0772604 0.0675971 -0.0341042 -0.0758552 0.0675971 -0.0371243 -0.0836365 0.0675971 -0.0117228 -0.084901 0.0670971 0.0030221 -0.0832464 0.0670971 0.0169544 -0.0842729 0.0675971 -0.00553375 -0.0732322 0.0670971 0.0430645 -0.0728012 0.0675971 0.0428111 -0.0777406 0.0675971 0.0330026 -0.079321 0.0670971 0.0304244 -0.0436533 0.0675971 0.072299 -0.0438383 0.0675971 0.0721869 -0.0439117 0.0670971 0.072727 -0.0311997 0.0675971 0.078481 -0.0311586 0.0675971 0.0784973 -0.00400731 0.0670971 0.0848594 0.0237621 0.0670971 0.0815613 0.00999047 0.0412971 0.0841623 0.0100141 0.0414971 0.0843609 -0.00400731 0.0414971 0.0848594 -0.0179195 0.0414971 0.0830433 -0.00399789 0.0412971 0.0846596 -0.031343 0.0414971 0.078962 -0.0312692 0.0412971 0.0787761 -0.0439117 0.0414971 0.072727 -0.0552827 0.0414971 0.0645083 -0.0730598 0.0412971 0.0429631 -0.0791343 0.0412971 0.0303527 -0.079321 0.0414971 0.0304244 -0.0832464 0.0414971 0.0169544 -0.0830504 0.0412971 0.0169145 -0.08424 0.0414971 -0.0109925 -0.0840416 0.0412971 -0.0109667 -0.0812812 0.0414971 -0.0247072 -0.0761054 0.0414971 -0.0377479 -0.0688537 0.0414971 -0.0497588 -0.0686916 0.0412971 -0.0496416 -0.0595835 0.0412971 -0.06027 -0.0368713 0.0414971 -0.0765296 -0.0237715 0.0414971 -0.0815538 0.0507841 0.0729471 -0.00568273 0.0524356 0.0747265 -0.00590771 0.0506979 0.0744969 -0.0059787 0.0506323 0.0749721 -0.00620365 0.0521536 0.0762351 -0.00687545 0.049651 0.0769971 -0.00957099 0.0502176 0.0764545 -0.00762686 0.048106 0.0772431 -0.0207652 0.0470212 0.0769971 -0.0185956 0.0465875 0.0766888 -0.0200836 0.0464546 0.0764545 -0.0205397 0.0476839 0.0762351 -0.0222136 0.0458881 0.0729471 -0.0224839 0.0507841 0.0727471 -0.00568273 0.0517315 0.068451 -0.00832378 0.0502176 0.0692397 -0.00762686 0.0504523 0.0698833 -0.00682157 0.0506979 0.0711972 -0.0059787 0.0506323 0.0707221 -0.00620365 0.0460399 0.0707221 -0.0219629 0.04622 0.0698833 -0.021345 0.0470212 0.0686971 -0.0185956 0.0465875 0.0690053 -0.0200836 0.0486038 0.0680971 -0.0190568 0.0464546 0.0692397 -0.0205397 0.049651 0.0686971 -0.00957099 -0.046464 0.0692397 0.0205472 -0.0486132 0.0680971 0.0190643 -0.0460492 0.0707221 0.0219704 -0.0518935 0.06872 0.00780754 -0.0502269 0.0692397 0.00763436 -0.0506417 0.0707221 0.00621115 -0.0473122 0.0727471 0.0235286 -0.0507935 0.0727471 0.00569022 -0.052544 0.0727471 0.00557539 -0.0459837 0.0744969 0.0221954 -0.0481153 0.0772431 0.0207727 -0.0465969 0.0766888 0.0200911 -0.0504616 0.0758108 0.00682907 -0.050094 0.0766888 0.00809052 -0.0502269 0.0764545 0.00763436 -0.051243 0.0775971 0.0100397 0.0304423 0.0790971 -0.0445943 0.0374786 0.0805971 -0.0367557 0.0295965 0.0805971 -0.0433555 0.0211676 0.0790971 -0.0496726 0.000569531 0.0790971 -0.0539932 0.0107731 0.0805971 -0.051378 0.000553581 0.0805971 -0.0524933 -0.00996404 0.0790971 -0.0530699 -0.0195571 0.0805971 -0.0487195 -0.0201157 0.0790971 -0.0501116 -0.0294963 0.0790971 -0.0452317 -0.0286771 0.0805971 -0.0439751 -0.0366977 0.0805971 -0.0375445 -0.0445487 0.0790971 -0.0305221 -0.0513673 0.0805971 -0.010865 -0.0447344 0.0805971 0.027013 -0.0522416 0.0805971 0.00125171 0.0447251 0.0805971 -0.0270055 -0.0451878 0.0790971 0.0295754 -0.0439327 0.0805971 0.028754 0.0522322 0.0805971 -0.00124421 0.0235693 0.0805971 0.0469134 0.0325806 0.0790971 0.0430642 0.0316755 0.0805971 0.041868 0.0398406 0.0790971 0.0364504 0.0445107 0.0805971 0.0278359 0.0502102 0.0790971 0.019865 0.0529769 0.0790971 0.0104419 0.0515052 0.0805971 0.0101519 0.0539912 0.0790971 0.000673553 0.0786633 0.0665971 -0.0239926 0.0791543 0.0665971 -0.0234465 0.0788159 0.0665971 -0.021417 0.077251 0.0665971 -0.0242281 0.0788958 0.0665971 0.0176214 0.0782321 0.0665971 0.0208516 0.0797276 0.0665971 0.0204759 0.0770403 0.0665971 0.0197105 0.0774833 0.0665971 0.0204408 0.0770217 0.0665971 0.0188566 0.0781627 0.0665971 0.0176648 0.0595707 0.0665971 0.057212 0.0572757 0.0665971 0.054844 0.0568648 0.0665971 0.0555928 0.0181373 0.0665971 -0.0798522 0.0177988 0.0665971 -0.0778227 0.0182898 0.0665971 -0.0772767 0.0189691 0.0665971 -0.0769978 0.0177142 0.0665971 -0.079252 0.0208432 0.0665971 -0.078233 0.0187789 0.0665971 -0.0802094 0.0576238 0.0665971 -0.058566 0.0574183 0.0665971 -0.059271 0.0543926 0.0665971 -0.0580068 0.0555844 0.0665971 -0.0568657 0.0562481 0.0665971 -0.0600959 0.0569273 0.0665971 -0.059817 -0.0580152 0.0665971 -0.0543935 -0.0587482 0.0665971 -0.05435 -0.0568741 0.0665971 -0.0555853 -0.0580846 0.0665971 -0.0575803 -0.0774926 0.0665971 -0.0204333 -0.0782414 0.0665971 -0.0208441 -0.0781721 0.0665971 -0.0176573 -0.0774419 0.0665971 -0.0181004 -0.0789051 0.0665971 -0.0176139 -0.0800754 0.0665971 -0.0184389 -0.077031 0.0665971 -0.0188491 -0.0781143 0.0665971 0.0242542 -0.0772604 0.0665971 0.0242356 -0.0760749 0.0665971 0.0225539 -0.0789138 0.0665971 0.0215104 -0.0774506 0.0665971 0.0210239 -0.0575701 0.0665971 0.0589375 -0.0564476 0.0665971 0.0568918 -0.0557146 0.0665971 0.0568484 -0.0550353 0.0665971 0.0571273 -0.0196421 0.0665971 0.0802355 -0.0181466 0.0665971 0.0798597 -0.0204417 0.0665971 0.0774917 -0.0177235 0.0665971 0.0792596 0.0378701 0.0729471 -0.0201473 0.0380219 0.0749721 -0.0196264 0.0390032 0.0686971 -0.0162591 0.041633 0.0686971 -0.00723445 0.0421996 0.0692397 -0.00529032 -0.0416636 0.0749721 0.00359484 -0.0376188 0.0766888 0.0174748 -0.0380524 0.0769971 0.0159868 -0.0418154 0.0729471 0.00307391 -0.0374859 0.0692397 0.0179309 -0.0406823 0.0686971 0.00696218 -0.0417291 0.0711972 0.00336989 -0.0380524 0.0686971 0.0159868 -0.0369193 0.0729471 0.0198751 -0.0370711 0.0707221 0.0193541 -0.0160777 0.0288971 -0.055152 -0.0265292 0.0292971 -0.0509565 -0.0359614 0.0288971 -0.0448027 -0.0359614 0.0292971 -0.0448027 -0.050371 0.0288971 -0.0276319 -0.050371 0.0292971 -0.0276319 -0.0547947 0.0292971 -0.0172749 -0.0572363 0.0288971 0.00500758 -0.0551604 0.0292971 0.0160768 -0.050965 0.0288971 0.0265283 -0.050965 0.0292971 0.0265283 -0.0448111 0.0288971 0.0359605 -0.0448111 0.0292971 0.0359605 -0.0369353 0.0288971 0.0440109 -0.00626233 0.0288971 0.0571119 0.00499916 0.0288971 0.0572354 0.00499916 0.0292971 0.0572354 0.01646 0.0281971 0.0565036 -0.00608261 0.0259971 0.0554717 -0.00641483 0.0281971 0.0585036 -0.0268466 0.0259971 0.0489236 -0.0358747 0.0259971 0.042747 -0.045903 0.0281971 0.0368367 -0.0495013 0.0259971 0.0257665 -0.0535763 0.0259971 0.0156151 -0.0555926 0.0259971 0.00486386 -0.0554727 0.0259971 -0.00607419 -0.0585045 0.0281971 -0.00640641 -0.0532211 0.0259971 -0.0167787 -0.0561299 0.0281971 -0.017696 -0.0489245 0.0259971 -0.0268382 -0.0450842 0.0281971 -0.0378269 -0.0349287 0.0259971 -0.0435158 -0.0257674 0.0259971 -0.0494929 -0.0156161 0.0259971 -0.0535679 -0.0164694 0.0286971 -0.0564961 -0.0271756 0.0286971 -0.0521984 -0.0271756 0.0281971 -0.0521984 -0.0368376 0.0281971 -0.0458946 -0.0515984 0.0281971 -0.0283054 -0.0561299 0.0286971 -0.017696 -0.058631 0.0281971 0.00512951 -0.058631 0.0286971 0.00512951 -0.0565045 0.0281971 0.0164685 -0.0522068 0.0286971 0.0271747 -0.0522068 0.0281971 0.0271747 -0.045903 0.0286971 0.0368367 -0.0378353 0.0281971 0.0450833 -0.0378353 0.0286971 0.0450833 -0.0283138 0.0281971 0.0515975 -0.0177044 0.0281971 0.056129 -0.0177044 0.0286971 0.056129 0.0051211 0.0281971 0.0586301 0.0051211 0.0286971 0.0586301 0.0448018 0.0288971 -0.035953 0.036926 0.0288971 -0.0440034 0.0457377 0.0288971 -0.036704 0.006253 0.0288971 -0.0571044 -0.00500849 0.0288971 -0.0572279 0.00638371 0.0288971 -0.0582973 -0.00511301 0.0288971 -0.0584234 -0.0265292 0.0288971 -0.0509565 -0.0440118 0.0288971 -0.0369269 -0.0547947 0.0288971 -0.0172749 -0.0571128 0.0288971 -0.00625392 -0.0583057 0.0288971 -0.00638463 -0.0551604 0.0288971 0.0160768 -0.0520294 0.0288971 0.0270823 -0.0276404 0.0288971 0.0503701 -0.0176443 0.0288971 0.0559382 -0.0172833 0.0288971 0.0547938 0.0160684 0.0288971 0.0551595 0.0164041 0.0288971 0.0563116 0.0270739 0.0288971 0.0520285 0.0367031 0.0288971 0.0457461 0.0503617 0.0288971 0.0276394 0.0514137 0.0288971 0.0282167 0.0559298 0.0288971 0.0176433 0.0582964 0.0288971 0.00639212 0.057227 0.0288971 -0.00500008 0.0563032 0.0288971 -0.016405 0.0509556 0.0288971 -0.0265208 -0.0164134 0.0288971 -0.0563041 -0.0270832 0.0288971 -0.052021 -0.0367125 0.0288971 -0.0457386 -0.0368376 0.0286971 -0.0458946 -0.044931 0.0288971 -0.0376983 -0.0450842 0.0286971 -0.0378269 -0.0514231 0.0288971 -0.0282092 -0.0515984 0.0286971 -0.0283054 -0.0585045 0.0286971 -0.00640641 -0.0559392 0.0288971 -0.0176358 -0.0584318 0.0288971 0.00511209 -0.0565045 0.0286971 0.0164685 -0.0563125 0.0288971 0.0164125 -0.045747 0.0288971 0.0367115 -0.0377067 0.0288971 0.0449301 -0.0283138 0.0286971 0.0515975 -0.0282176 0.0288971 0.0514222 -0.00641483 0.0286971 0.0585036 -0.00639304 0.0288971 0.0583048 0.00510368 0.0288971 0.0584309 0.01646 0.0286971 0.0565036 -0.0312359 0.0259971 0.028086 -0.0435242 0.0259971 0.0349278 -0.0403274 0.0259971 0.0117543 0.0489152 0.0259971 0.0268457 0.0280776 0.0259971 0.0312349 0.0204239 0.0259971 0.0367008 0.0257581 0.0259971 0.0495004 0.0117458 0.0259971 0.0403265 0.0156067 0.0259971 0.0535754 0.00485545 0.0259971 0.0555917 -0.0159586 0.0259971 0.0388557 -0.0167871 0.0259971 0.0532202 0.0312265 0.0259971 -0.0280785 0.0435149 0.0259971 -0.0349203 0.0403181 0.0259971 -0.0117468 -0.0427479 0.0259971 -0.0358662 -0.0280869 0.0259971 -0.0312275 -0.0117552 0.0259971 -0.040319 -0.00486478 0.0259971 -0.0555842 -0.00248791 0.0259971 -0.0419228 0.00690388 0.0259971 -0.0414242 0.00607328 0.0259971 -0.0554642 0.0159492 0.0259971 -0.0388482 0.0268373 0.0259971 -0.0489161 -0.00735954 0.0264971 -0.00817585 0.00180471 0.0264971 -0.0108464 0.00960647 0.0264971 -0.00534659 -0.0109854 0.0264971 0.000654123 -0.00308218 0.0264971 -0.010557 0.0101708 0.0264971 0.00418216 0.00307285 0.0264971 0.0105645 -0.00181405 0.0264971 0.0108539 -0.00634257 0.0264971 0.00899435 0.0358786 0.0256971 -0.00440025 0.0359261 0.0254971 -0.00459452 0.0375804 0.0256971 -0.00346649 0.0377187 0.0254971 -0.00361095 0.0387793 0.0254971 -0.00186288 0.0316189 0.0254971 0.0130034 0.0332731 0.0256971 0.0141314 0.0344721 0.0254971 0.015735 0.0345166 0.0254971 0.0177792 0.0333885 0.0256971 0.0194334 0.033533 0.0254971 0.0195717 0.0170456 0.0254971 0.0261344 0.0190898 0.0254971 0.02609 0.0208823 0.0254971 0.0270735 0.020744 0.0256971 0.027218 0.0217509 0.0256971 0.0288776 0.0217932 0.0256971 0.0308182 0.0219874 0.0254971 0.0308658 0.0208594 0.0256971 0.03252 0.0192558 0.0254971 0.033719 0.00361004 0.0254971 0.0377271 0.00346557 0.0256971 0.0375888 0.00422578 0.0256971 0.0364199 0.00439934 0.0256971 0.035887 0.00450029 0.0256971 0.0347737 0.00454911 0.0254971 0.0338904 0.00403338 0.0256971 0.0331715 0.00164838 0.0256971 0.031353 0.0029175 0.0256971 0.0319305 0.00348849 0.0254971 0.0321423 0.00335018 0.0256971 0.0322867 -0.0159495 0.0256971 0.0270457 -0.0142477 0.0256971 0.0279795 -0.0132408 0.0256971 0.0296391 -0.0141094 0.0254971 0.027835 -0.0130043 0.0254971 0.0316273 -0.0131985 0.0256971 0.0315798 -0.0141323 0.0256971 0.0332816 -0.0139878 0.0254971 0.0334199 -0.0157919 0.0256971 0.0342885 -0.0157359 0.0254971 0.0344805 -0.0272866 0.0254971 0.0210963 -0.0262737 0.0254971 0.0196595 -0.0263274 0.0256971 0.01711 -0.0262851 0.0256971 0.0190506 -0.0266511 0.0256971 0.0163351 -0.0264763 0.0254971 0.0162378 -0.0273343 0.0256971 0.0154504 -0.0293108 0.0256971 0.0144602 -0.0290361 0.0256971 0.0145166 -0.027767 0.0256971 0.0150941 -0.0324031 0.0256971 -0.00194345 -0.0322647 0.0254971 -0.00208791 -0.0312041 0.0254971 -0.000339838 -0.0311596 0.0254971 0.00170435 -0.0322877 0.0256971 0.0033586 -0.0338913 0.0254971 0.00455753 -0.0317943 0.0254971 -0.0206249 -0.0300394 0.0254971 -0.0207288 -0.0285285 0.0256971 -0.0198976 -0.0272379 0.0254971 -0.0187539 -0.0267461 0.0254971 -0.0170662 -0.0272202 0.0256971 -0.0154082 -0.0280481 0.0254971 -0.0138954 -0.0192651 0.0254971 -0.0337115 -0.0172685 0.0256971 -0.0335617 -0.0155667 0.0256971 -0.0326279 -0.0145598 0.0256971 -0.0309684 -0.0145175 0.0256971 -0.0290277 -0.0143233 0.0254971 -0.0289801 0.00174116 0.0256971 -0.0321995 0.00283406 0.0256971 -0.0360371 0.00268508 0.0254971 -0.0369092 0.0031769 0.0254971 -0.0352215 0.00194253 0.0256971 -0.0323946 0.00288774 0.0254971 -0.0334875 0.0015097 0.0254971 -0.0382164 0.000125343 0.0256971 -0.0386304 -0.000116455 0.0254971 -0.0388842 0.00139446 0.0256971 -0.0380529 0.019339 0.0256971 -0.0278922 0.0194728 0.0254971 -0.0277435 0.0207748 0.0254971 -0.0309143 0.0203006 0.0256971 -0.0292563 0.0204742 0.0256971 -0.0297892 0.0205751 0.0256971 -0.0309024 0.020283 0.0254971 -0.032602 0.019425 0.0256971 -0.0333894 0.0191076 0.0254971 -0.0339092 0.0174814 0.0254971 -0.0345769 0.0177232 0.0256971 -0.0343232 0.0309674 0.0256971 -0.0145514 0.0325594 0.0254971 -0.0152144 0.0335722 0.0254971 -0.0166512 0.0338614 0.0254971 -0.0183851 0.0336617 0.0256971 -0.0183733 0.0321942 0.0254971 -0.02138 0.030568 0.0254971 -0.0220478 0.00885521 0.0254971 0.02311 0.0102329 0.0254971 0.0248 0.0104151 0.0257971 0.0245617 0.0122249 0.0254971 0.0256865 0.013688 0.0257971 0.0254252 0.0154105 0.0257971 0.0248032 0.0248413 0.0257971 0.00918361 0.0234652 0.0254971 0.00785 0.0257759 0.0257971 0.0107585 0.0260601 0.0254971 0.0106625 0.0262871 0.0254971 0.0126054 0.0113584 0.0254971 0.00710592 0.013519 0.0257971 0.00586448 0.0122541 0.0254971 0.00614034 0.0134433 0.0254971 0.00557418 0.00775505 0.0257971 0.0112943 0.00758513 0.0254971 0.0110471 0.00614555 0.0254971 0.0131967 0.00665943 0.0254971 0.011984 -0.00931886 0.0257971 0.0127907 -0.0151739 0.0257971 0.0245726 -0.0154109 0.0254971 0.0247567 -0.0162632 0.0254971 0.022996 -0.0159719 0.0257971 0.0229243 -0.0160297 0.0257971 0.0210939 -0.0153373 0.0257971 0.0193985 -0.00694672 0.0257971 0.0283665 0.00149849 0.0257971 0.0290265 0.00235097 0.0257971 0.015647 0.00068973 0.0257971 0.0139632 0.000810298 0.0254971 0.0136885 -0.00590272 0.0257971 0.0123691 -0.00950997 0.0254971 0.0125595 -0.0070478 0.0254971 0.0117651 -0.00577357 0.0254971 0.0120984 -0.0200339 0.0257971 -0.00293239 -0.0199698 0.0254971 -0.00322548 -0.029489 0.0254971 0.000963657 -0.0288666 0.0257971 -0.000848785 -0.0291444 0.0254971 -0.000961933 -0.0280458 0.0254971 -0.00258045 -0.0260225 0.0257971 -0.00341357 -0.0283266 0.0254971 0.00825709 -0.0239842 0.0254971 0.0165276 -0.025389 0.0254971 0.0150332 -0.0153211 0.0257971 0.01324 -0.0151096 0.0254971 0.0134528 -0.018714 0.0257971 0.0161656 -0.0185346 0.0254971 0.0164061 -0.0118421 0.0257971 0.00878525 -0.0123743 0.0257971 0.00986542 -0.0115528 0.0254971 0.00886485 -0.0136624 0.0257971 0.00107858 -0.0118369 0.0254971 0.00629337 -0.0147064 0.0257971 -0.00104395 -0.0137119 0.0254971 -0.000215087 -0.0133634 0.0254971 0.00105504 -0.0074765 0.0257971 -0.0188101 -0.0100631 0.0254971 -0.0246485 -0.0091347 0.0257971 -0.0229721 -0.0102568 0.0257971 -0.0244194 -0.0155782 0.0254971 -0.0250505 -0.0248507 0.0257971 -0.00917611 -0.0234745 0.0254971 -0.0078425 -0.0250712 0.0254971 -0.00897267 -0.0259977 0.0257971 -0.01257 -0.0257127 0.0254971 -0.014465 -0.0191258 0.0257971 -0.00664251 -0.01473 0.0257971 -0.00577784 -0.00776438 0.0257971 -0.0112868 -0.0113677 0.0254971 -0.00709842 -0.00759446 0.0254971 -0.0110396 -0.00666877 0.0254971 -0.0119765 0.0154015 0.0254971 -0.0247492 0.0163156 0.0254971 -0.0210332 0.0070087 0.0254971 -0.0286504 -0.000328391 0.0254971 -0.0294945 -0.00223717 0.0254971 -0.0290664 -0.00211204 0.0257971 -0.0287938 -0.00464659 0.0257971 -0.0242799 -0.00494453 0.0254971 -0.0242448 -0.00358106 0.0257971 -0.0277003 -0.00380635 0.0254971 -0.0278984 -0.00169097 0.0257971 -0.0146385 0.000474964 0.0257971 -0.0136879 0.00698871 0.0254971 -0.0117613 0.0200246 0.0257971 0.00293989 0.0253797 0.0254971 -0.0150257 0.0283173 0.0254971 -0.00824959 0.0291799 0.0257971 -0.000946396 0.0294797 0.0254971 -0.000956157 0.023881 0.0257971 -0.01622 0.0203024 0.0254971 -0.0172163 0.0203683 0.0257971 -0.0169236 0.0118275 0.0254971 -0.00628587 0.0121256 0.0254971 -0.0100388 0.0136531 0.0257971 -0.00107108 0.0139718 0.0257971 9.01814e-05 0.0137026 0.0254971 0.000222586 0.0258782 0.0281471 0.0262723 0.0267142 0.0281471 0.0258069 0.027365 0.0281471 0.0247193 0.0273408 0.0281471 0.0236066 0.0271552 0.0281471 0.0231624 0.0239338 0.0254971 0.0195998 0.0256303 0.0281471 0.0220874 0.0257878 0.0281471 0.0221198 0.034503 0.0281471 0.00623634 0.035133 0.0254971 0.00366232 0.036056 0.0281471 0.00772318 0.0386001 0.0254971 0.00698178 0.0355448 0.0281471 0.00981154 0.0386542 0.0254971 0.00946586 0.0345933 0.0281471 0.0103888 0.0349406 0.0254971 -0.00518003 0.0355865 0.0281471 -0.00897166 0.0383892 0.0254971 -0.0100721 0.0377916 0.0254971 -0.012123 0.0348364 0.0281471 -0.0115456 0.0363633 0.0254971 -0.0137115 0.0343872 0.0254971 -0.014523 0.0339513 0.0281471 -0.0119091 0.0115257 0.0254971 -0.0304235 0.00986928 0.0281471 -0.0325059 0.0104046 0.0281471 -0.0334816 0.0125102 0.0254971 -0.0363274 0.0103804 0.0281471 -0.0345943 0.0110819 0.0254971 -0.0379159 0.00910583 0.0254971 -0.0387274 0.00771477 0.0281471 -0.0360569 -0.00513438 0.0254971 -0.0324574 -0.00780791 0.0281471 -0.0327819 -0.00770841 0.0281471 -0.0330874 -0.00765052 0.0281471 -0.0337257 -0.00518845 0.0254971 -0.0349415 -0.00791822 0.0281471 -0.0346443 -0.00928562 0.0281471 -0.0356869 -0.0086556 0.0254971 -0.0382609 -0.00855799 0.0281471 -0.0353558 -0.0218189 0.0254971 -0.0208812 -0.020494 0.0254971 -0.0244781 -0.0258875 0.0281471 -0.0262648 -0.0241449 0.0254971 -0.028863 -0.0219666 0.0254971 -0.0276678 -0.0303976 0.0254971 0.0133651 -0.0291668 0.0254971 0.0116191 -0.0315186 0.0281471 0.010307 -0.0288154 0.0254971 0.00951204 -0.029413 0.0254971 0.00746115 -0.0315428 0.0281471 0.00919433 -0.0321201 0.0281471 0.00824285 -0.0332533 0.0281471 0.00767513 -0.0330958 0.0281471 0.00770749 -0.0323682 0.0281471 0.00803859 -0.0226561 0.0281471 0.0267719 -0.0195467 0.0254971 0.0264263 -0.0221207 0.0281471 0.0257962 -0.0221449 0.0281471 0.0246836 -0.0196008 0.0254971 0.0239422 -0.0227222 0.0281471 0.0237321 -0.0248106 0.0281471 0.023221 -0.00151825 0.0254971 0.0416763 -0.0405134 0.0254971 0.00664806 -0.0244452 0.0254971 -0.0038765 0.0268431 0.0254971 0.015901 0.0268875 0.0254971 0.0179452 -0.029443 0.0254971 -0.0295305 -0.012988 0.0254971 0.0328591 -0.0116451 0.0254971 0.0374674 -0.00686387 0.0254971 0.0411358 -0.00231846 0.0254971 0.0386276 -0.0038854 0.0254971 0.0358236 -0.0147642 0.0254971 0.0348007 -0.0117928 0.0254971 0.0306808 -0.00701804 0.0254971 0.0286579 0.000319058 0.0254971 0.029502 0.00818658 0.0254971 0.0281126 0.00158242 0.0254971 0.0293146 0.0045936 0.0254971 0.0359345 -0.0308413 0.0254971 0.00587267 -0.0328174 0.0254971 0.00506123 -0.0370741 0.0254971 0.00647638 -0.0400394 0.0254971 0.0116703 -0.0377413 0.0254971 0.016161 0.0139062 0.0254971 -0.0260104 0.00717512 0.0254971 -0.0293304 0.0130394 0.0254971 -0.0295756 0.0096592 0.0254971 -0.0293844 0.0129949 0.0254971 -0.0316198 0.0139785 0.0254971 -0.0334124 0.0127565 0.0254971 -0.0321694 0.0131079 0.0254971 -0.0342765 0.0388238 0.0254971 0.000181307 0.0416224 0.0254971 -0.00246176 0.0411273 0.0254971 0.00686295 0.0313331 0.0254971 -0.0022582 0.030211 0.0254971 -0.00364102 0.037459 0.0254971 0.0116442 0.035513 0.0254971 0.0145533 0.0353347 0.0254971 0.012933 0.0305247 0.0254971 0.00500524 0.0260971 0.0254971 0.00370909 0.0219429 0.0254971 0.0288216 0.0219572 0.0254971 0.0276753 0.0266196 0.0254971 0.0288165 0.0284861 0.0254971 0.0277774 0.0340779 0.0254971 0.0240302 0.0297169 0.0254971 0.0260315 0.0257034 0.0254971 0.0144725 0.0260662 0.0254971 0.0194735 0.0280423 0.0254971 0.020285 -0.0206777 0.0254971 -0.0255436 -0.00845385 0.0254971 -0.0289902 -0.0190991 0.0254971 -0.0260825 -0.0170549 0.0254971 -0.0261269 -0.0202873 0.0254971 -0.0364312 -0.0153068 0.0254971 -0.0271876 -0.0143678 0.0254971 -0.0310243 -0.0131162 0.0254971 -0.0301314 -0.0144051 0.0254971 -0.0322556 -0.0144591 0.0254971 -0.0347397 -0.0154284 0.0254971 -0.0327724 -0.0132639 0.0254971 -0.036918 -0.0172209 0.0254971 -0.033756 -0.0111397 0.0254971 -0.0382069 -0.00680309 0.0254971 -0.0411383 -0.0064773 0.0254971 -0.0370657 -0.00544151 0.0254971 -0.0363615 -0.0063296 0.0254971 -0.0302791 -0.0213132 0.0254971 -0.0203971 -0.0239431 0.0254971 -0.0195923 -0.0300776 0.0254971 -0.0239169 -0.0311467 0.0254971 -0.021417 -0.0227051 0.0254971 -0.0313307 -0.0266289 0.0254971 -0.028809 -0.0284954 0.0254971 -0.0277699 -0.0340872 0.0254971 -0.0240227 -0.0297262 0.0254971 -0.026024 -0.00886454 0.0254971 -0.0231025 -0.0206236 0.0254971 -0.0230595 -0.0137382 0.0254971 -0.0257149 -0.0117872 0.0254971 -0.0255726 -0.00719066 0.0254971 -0.0189012 -0.00612559 0.0254971 -0.0145059 -0.0286493 0.0254971 0.0234618 -0.0249004 0.0254971 0.0205352 -0.0271121 0.0254971 0.0130636 -0.0276517 0.0254971 0.0149307 0.0361239 0.0254971 0.0199714 0.0317849 0.0254971 0.0206324 0.0295747 0.0254971 0.0130479 0.0250618 0.0254971 0.00898017 0.0244359 0.0254971 0.003884 0.0199605 0.0254971 0.00323298 0.019195 0.0254971 0.00636048 0.0147576 0.0254971 0.00548763 0.0156216 0.0254971 0.00195772 0.0199457 0.0254971 0.0366217 0.0210039 0.0254971 0.0326583 0.027877 0.0254971 0.0310119 0.0152975 0.0254971 0.0271951 0.0149452 0.0254971 0.0335968 0.00169593 0.0254971 0.0311587 -0.00413167 0.0254971 0.0316656 -0.00209633 0.0254971 0.0322638 -0.00197479 0.0254971 0.0378486 0.0116619 0.0254971 0.0400385 -0.0130488 0.0254971 0.0295831 -0.0179461 0.0254971 0.026896 -0.0159019 0.0254971 0.0268515 -0.0139156 0.0254971 0.0260179 -0.0163249 0.0254971 0.0210407 -0.0200298 0.0254971 0.017151 -0.0155853 0.0254971 0.0192298 -0.0127838 0.0254971 0.0156795 -0.0207841 0.0254971 0.0309218 -0.0202923 0.0254971 0.0326095 -0.0205307 0.0254971 0.0363021 -0.0292779 0.0254971 0.0142629 -0.0335978 0.0254971 0.0149536 -0.0337644 0.0254971 0.01722 -0.0337199 0.0254971 0.0192642 -0.0326593 0.0254971 0.0210123 -0.0308667 0.0254971 0.0219958 -0.0288225 0.0254971 0.0219514 -0.025552 0.0254971 0.0206768 -0.0259845 0.0254971 0.0179256 -0.0349499 0.0254971 0.00518753 -0.0298843 0.0254971 0.0035506 -0.0321432 0.0254971 0.00349691 -0.0340573 0.0254971 -0.00307148 -0.0361015 0.0254971 -0.00302699 -0.0413259 0.0254971 -0.00560377 -0.0389395 0.0254971 0.000998814 -0.0384477 0.0254971 0.00268653 -0.0356461 0.0254971 0.00466147 -0.0363699 0.0254971 0.0054406 -0.0316282 0.0254971 -0.0129959 -0.029584 0.0254971 -0.0130404 -0.0270352 0.0254971 -0.0153322 -0.0284133 0.0254971 -0.0200611 -0.02948 0.0254971 -0.021866 -0.0365786 0.0254971 -0.0200272 -0.0335423 0.0254971 -0.0195643 -0.0345259 0.0254971 -0.0177717 -0.00455845 0.0254971 -0.0338829 -0.00349783 0.0254971 -0.0321348 -0.00170527 0.0254971 -0.0311512 0.00033892 0.0254971 -0.0311957 0.00187488 0.0254971 -0.0320507 0.00365391 0.0254971 -0.0351339 0.00484913 0.0254971 -0.0373122 0.00685453 0.0254971 -0.0411283 0.00697337 0.0254971 -0.0386011 -0.00247017 0.0254971 -0.0416233 -0.00284876 0.0254971 -0.0415991 -0.00361937 0.0254971 -0.0377196 0.0204856 0.0254971 -0.0291803 0.0310234 0.0254971 -0.0143593 0.0333696 0.0254971 -0.0200729 0.00611625 0.0254971 0.0145134 0.00138143 0.0254971 0.00476024 0.0213039 0.0254971 0.0204046 0.0206143 0.0254971 0.023067 0.0155688 0.0254971 0.025058 0.0167353 0.0254971 0.0256214 0.0144026 0.0254971 0.0255786 0.00718133 0.0254971 0.0189087 -0.00835497 0.0254971 0.0119265 0.0049352 0.0254971 0.0242523 0.00409009 0.0254971 0.0198095 0.00262728 0.0254971 0.0155302 0.00668346 0.0254971 0.0229545 0.0018952 0.0254971 0.0144353 -0.000473794 0.0254971 0.0133955 -0.012135 0.0254971 0.0100463 -0.0114485 0.0254971 0.0075519 -0.0276847 0.0254971 -0.00953679 -0.0263834 0.0254971 -0.0036115 -0.0332274 0.0254971 -0.00792158 -0.0230679 0.0254971 0.0206227 -0.0208896 0.0254971 0.0218179 -0.0220767 0.0254971 0.0172813 -0.0207419 0.0254971 0.0286046 -0.0228662 0.0254971 0.0298934 -0.02181 0.0254971 0.0312579 -0.0240311 0.0254971 0.0340863 -0.0262964 0.0254971 -0.0125979 -0.0260694 0.0254971 -0.010655 -0.0192044 0.0254971 -0.00635298 -0.0147669 0.0254971 -0.00548013 -0.0156309 0.0254971 -0.00195022 -0.0145052 0.0254971 -0.00126647 -0.0133565 0.0254971 -0.00559323 -0.0122235 0.0254971 -0.00616266 0.00950063 0.0254971 -0.012552 0.0151003 0.0254971 -0.0134453 0.0127745 0.0254971 -0.015672 0.0185253 0.0254971 -0.0163986 0.015576 0.0254971 -0.0192223 0.0182169 0.0254971 -0.022913 0.0162539 0.0254971 -0.0229885 -0.00263661 0.0254971 -0.0155227 -0.00615488 0.0254971 -0.0131892 -0.00190453 0.0254971 -0.0144278 -0.00139076 0.0254971 -0.00475274 -0.000819632 0.0254971 -0.013681 0.000464461 0.0254971 -0.013388 0.00576423 0.0254971 -0.0120909 -0.00343943 0.0254971 -0.0294912 -0.00476411 0.0254971 -0.0261927 -0.00819591 0.0254971 -0.0281051 -0.00473389 0.0254971 -0.0162249 -0.00409942 0.0254971 -0.019802 0.000352833 0.0254971 -0.0305963 0.0144959 0.0254971 0.00127397 0.00993017 0.0254971 0.00226903 0.00715799 0.0254971 -0.00724394 0.0115435 0.0254971 -0.00885735 0.0114392 0.0254971 -0.0075444 0.0240546 0.0254971 -0.0164647 0.0222584 0.0254971 -0.0172397 0.0293187 0.0254971 -0.00338101 0.0298749 0.0254971 -0.0035431 0.0271027 0.0254971 -0.0130561 0.0265465 0.0254971 -0.012894 0.0232034 0.0254971 -0.0243662 0.0172116 0.0254971 0.0337634 0.0364157 0.0254971 0.0203125 0.0311374 0.0254971 0.0214245 0.0300683 0.0254971 0.0239244 0.0294706 0.0254971 0.0218735 0.0328507 0.0254971 0.0129871 0.0334114 0.0254971 0.0139869 0.0346208 0.0254971 0.0148133 0.0368077 0.0254971 0.0195931 0.035177 0.0254971 0.0146512 0.0322547 0.0254971 -0.0143967 0.0289353 0.0254971 -0.0109295 0.0289893 0.0254971 -0.00844543 0.0324565 0.0254971 -0.00512597 0.0411374 0.0254971 -0.00679468 0.0338819 0.0254971 -0.00455003 0.036807 0.0254971 -0.00621907 0.0380379 0.0254971 -0.00796504 0.0400301 0.0254971 -0.0116628 0.0310035 0.0254971 -0.0278779 0.026126 0.0254971 -0.0170465 0.0240956 0.0254971 -0.0246262 0.0147549 0.0254971 -0.0347933 -0.0397131 0.0254971 -0.00603159 -0.0344814 0.0254971 -0.0157275 -0.0334208 0.0254971 -0.0139794 0.00186196 0.0254971 0.0387877 0.0101887 0.0254971 0.0349829 0.0129431 0.0254971 0.0267265 0.0378402 0.0254971 0.00197387 0.0373113 0.0254971 0.00485754 0.0360922 0.0254971 0.00303449 0.0326489 0.0254971 0.00371638 0.031044 0.0254971 -0.000524228 -0.0111257 0.0254971 0.00840495 -0.0138979 0.0254971 -0.00110802 0.00613791 0.0254971 0.00337414 0.00336573 0.0254971 -0.00613883 0.013354 0.0254971 -0.00104755 0.0198043 0.0254971 -0.0366909 0.020083 0.0254971 -0.036539 0.0197414 0.0254971 -0.0362464 0.0205214 0.0254971 -0.0362946 0.0237596 0.0254971 -0.0245283 0.0274388 0.0254971 -0.013154 0.0289792 0.0254971 -0.0143149 0.00246084 0.0254971 0.0416308 0.00247858 0.0257971 0.0419303 -0.00691321 0.0257971 0.0414317 -0.013522 0.0254971 0.0394521 -0.0158446 0.0254971 0.0385782 -0.0242039 0.0257971 0.0343315 -0.0312359 0.0257971 0.028086 -0.0310128 0.0254971 0.0278854 -0.0364396 0.0254971 0.0202864 -0.0403274 0.0257971 0.0117543 -0.0416317 0.0254971 0.00246926 -0.0414326 0.0257971 -0.0069048 -0.0411367 0.0254971 -0.00685545 -0.0385791 0.0254971 -0.0158362 -0.0280869 0.0257971 -0.0312275 -0.0278863 0.0254971 -0.0310044 -0.0204332 0.0257971 -0.0366933 -0.0204332 0.0259971 -0.0366933 -0.0343324 0.0257971 -0.0241955 -0.0343324 0.0259971 -0.0241955 -0.0388566 0.0257971 -0.0159502 -0.0388566 0.0259971 -0.0159502 -0.0414326 0.0259971 -0.0069048 -0.0419312 0.0257971 0.00248699 -0.0419312 0.0259971 0.00248699 -0.0367017 0.0257971 0.0204323 -0.0367017 0.0259971 0.0204323 -0.0242039 0.0259971 0.0343315 -0.0159586 0.0257971 0.0388557 -0.00691321 0.0259971 0.0414317 0.00247858 0.0259971 0.0419303 -0.00511622 0.0254971 0.0375695 -0.00623726 0.0281471 0.0345114 -0.00353401 0.0254971 0.0337164 -0.00617938 0.0281471 0.0338731 -0.00555998 0.0254971 0.0300771 -0.00683877 0.0281471 0.0324472 -0.00966853 0.0254971 0.0293919 -0.00753607 0.0254971 0.0292656 -0.00708684 0.0281471 0.032243 -0.0116221 0.0257971 -0.00725742 -0.0116221 0.0282971 -0.00725742 -0.0134404 0.0257971 -0.00588125 -0.0233559 0.0257971 -0.00811807 -0.0254513 0.0282971 -0.0143179 -0.0257852 0.0257971 -0.010751 -0.0257852 0.0282971 -0.010751 -0.0254513 0.0257971 -0.0143179 -0.0210965 0.0257971 -0.0201896 -0.0154198 0.0257971 -0.0247957 -0.014328 0.0282971 -0.0252831 -0.0154198 0.0282971 -0.0247957 -0.0091347 0.0282971 -0.0229721 -0.00642141 0.0282971 -0.0144561 -0.00642141 0.0257971 -0.0144561 -0.0064482 0.0257971 -0.0132522 -0.00691803 0.0282971 -0.0121434 -0.00691803 0.0257971 -0.0121434 -0.0153211 0.0282971 0.01324 -0.0238157 0.0257971 0.0162793 -0.02203 0.0257971 0.016985 -0.0203777 0.0282971 0.0169311 -0.0201137 0.0257971 0.016863 -0.0251309 0.0257971 0.0148804 -0.0280386 0.0282971 0.00817315 -0.0280386 0.0257971 0.00817315 -0.0291892 0.0257971 0.000953895 -0.0262818 0.0257971 -0.00332923 -0.027838 0.0257971 -0.00236399 -0.0288314 0.0282971 -0.00093259 -0.0291892 0.0282971 0.000953895 -0.0200339 0.0282971 -0.00293239 -0.0244673 0.0257971 -0.00357732 -0.0157356 0.0282971 -0.00166909 -0.0157356 0.0257971 -0.00166909 -0.0147064 0.0282971 -0.00104395 -0.0139811 0.0282971 -8.26822e-05 -0.0139811 0.0257971 -8.26822e-05 -0.0121018 0.0257971 0.00643418 -0.0136624 0.0282971 0.00107858 -0.0117467 0.0282971 0.00758484 -0.0117467 0.0257971 0.00758484 -0.0123743 0.0282971 0.00986542 0.00380007 0.0257971 0.0198863 0.0021027 0.0257971 0.0288013 0.0021027 0.0282971 0.0288013 0.00327225 0.0257971 0.0280165 0.00446835 0.0282971 0.026111 0.00463726 0.0282971 0.0242874 0.00463726 0.0257971 0.0242874 0.000315766 0.0282971 0.029202 0.000315766 0.0257971 0.029202 -0.0160297 0.0282971 0.0210939 -0.0159719 0.0282971 0.0229243 -0.0137741 0.0257971 0.0257534 -0.0125621 0.0257971 0.0158815 -0.00826286 0.0257971 0.012212 -0.00706774 0.0257971 0.0120645 -0.000484297 0.0257971 0.0136954 -0.000484297 0.0282971 0.0136954 0.00068973 0.0282971 0.0139632 0.00168164 0.0282971 0.014646 0.00168164 0.0257971 0.014646 0.0191165 0.0282971 0.00665001 0.0147206 0.0257971 0.00578534 0.0191165 0.0257971 0.00665001 0.025442 0.0257971 0.0143254 0.0259884 0.0257971 0.0125775 0.0257759 0.0282971 0.0107585 0.0248413 0.0282971 0.00918361 0.0233466 0.0257971 0.00812557 0.0210872 0.0282971 0.0201971 0.0210872 0.0257971 0.0201971 0.0118615 0.0282971 0.025292 0.0122799 0.0257971 0.0253916 0.0143186 0.0257971 0.0252906 0.00912536 0.0257971 0.0229796 0.00641208 0.0282971 0.0144636 0.00746717 0.0257971 0.0188176 0.00641208 0.0257971 0.0144636 0.0069087 0.0282971 0.0121509 0.00643886 0.0257971 0.0132597 0.0069087 0.0257971 0.0121509 0.00775505 0.0282971 0.0112943 0.0116128 0.0257971 0.00726492 0.0116128 0.0282971 0.00726492 0.0123952 0.0282971 0.00640938 0.0124318 0.0257971 0.00638211 0.0147206 0.0282971 0.00578534 0.012365 0.0257971 -0.00985792 0.0153117 0.0257971 -0.0132325 0.0187047 0.0282971 -0.0161581 0.0201044 0.0257971 -0.0168555 0.0187047 0.0257971 -0.0161581 0.0201044 0.0282971 -0.0168555 0.0280293 0.0282971 -0.00816565 0.0280293 0.0257971 -0.00816565 0.024458 0.0282971 0.00358482 0.024458 0.0257971 0.00358482 0.027695 0.0257971 0.00249459 0.0288221 0.0257971 0.00094009 0.0157263 0.0282971 0.00167659 0.0157263 0.0257971 0.00167659 0.0146971 0.0257971 0.00105145 0.0139718 0.0282971 9.01814e-05 0.0136531 0.0282971 -0.00107108 0.0117374 0.0282971 -0.00757734 0.0120924 0.0257971 -0.00642668 0.0117374 0.0257971 -0.00757734 0.0118327 0.0282971 -0.00877775 0.0118327 0.0257971 -0.00877775 -0.0023603 0.0282971 -0.0156395 -0.0038094 0.0282971 -0.0198788 -0.0038094 0.0257971 -0.0198788 -0.00150782 0.0282971 -0.029019 -0.00328159 0.0257971 -0.028009 -0.00328159 0.0282971 -0.028009 -0.0044087 0.0282971 -0.0263072 -0.00447768 0.0257971 -0.0261035 -0.000325099 0.0257971 -0.0291945 0.00693738 0.0257971 -0.028359 0.0160203 0.0257971 -0.0210864 0.0160203 0.0282971 -0.0210864 0.0159625 0.0282971 -0.0229168 0.0159625 0.0257971 -0.0229168 0.0151646 0.0257971 -0.0245651 0.0137648 0.0257971 -0.0257459 0.015328 0.0257971 -0.019391 0.0125527 0.0257971 -0.015874 0.00816631 0.0282971 -0.0121777 0.00701291 0.0257971 -0.0120603 0.0070584 0.0282971 -0.012057 0.00589339 0.0257971 -0.0123616 0.00589339 0.0282971 -0.0123616 -0.000699064 0.0257971 -0.0139557 -0.0023603 0.0257971 -0.0156395 0.00180471 0.0282971 -0.0108464 0.00960647 0.0282971 -0.00534659 0.00633324 0.0264971 -0.00898685 0.0109761 0.0264971 -0.000646624 0.0101708 0.0282971 0.00418216 0.00735021 0.0282971 0.00818335 0.00735021 0.0264971 0.00818335 -0.0273343 0.0282971 0.0154504 -0.0263274 0.0282971 0.01711 -0.0261842 0.0256971 0.0179374 -0.0262851 0.0282971 0.0190506 -0.0264587 0.0256971 0.0195836 -0.0274203 0.0256971 0.0209476 -0.0272189 0.0256971 0.0207524 -0.0272189 0.0282971 0.0207524 -0.0159495 0.0282971 0.0270457 -0.0178902 0.0256971 0.027088 -0.0142477 0.0282971 0.0279795 -0.0132408 0.0282971 0.0296391 -0.0131985 0.0282971 0.0315798 -0.0141323 0.0282971 0.0332816 -0.000292299 0.0256971 0.0313952 0.00137369 0.0282971 0.0312965 0.0029175 0.0282971 0.0319305 0.00403338 0.0282971 0.0331715 0.00450029 0.0282971 0.0347737 0.0043571 0.0256971 0.0339463 0.00422578 0.0282971 0.0364199 0.00180601 0.0282971 0.0385957 0.0190422 0.0282971 0.0262842 0.0190422 0.0256971 0.0262842 0.0217509 0.0282971 0.0288776 0.0217932 0.0282971 0.0308182 0.0208594 0.0282971 0.03252 0.0191998 0.0282971 0.0335269 0.0312966 0.0282971 0.0131412 0.0315713 0.0256971 0.0131976 0.0315713 0.0282971 0.0131976 0.0342801 0.0256971 0.015791 0.0341487 0.0282971 0.0182646 0.0343223 0.0256971 0.0177316 0.0331872 0.0282971 0.0196286 0.0375804 0.0282971 -0.00346649 0.0385873 0.0282971 -0.00180692 0.0386295 0.0282971 0.000133759 0.0385873 0.0256971 -0.00180692 0.0386295 0.0256971 0.000133759 0.0376958 0.0256971 0.00183556 0.0376958 0.0282971 0.00183556 0.0305351 0.0282971 -0.0218505 0.0305351 0.0256971 -0.0218505 0.0308098 0.0256971 -0.0217941 0.0320789 0.0256971 -0.0212166 0.0325116 0.0282971 -0.0208603 0.0325116 0.0256971 -0.0208603 0.0331948 0.0282971 -0.0199756 0.0331948 0.0256971 -0.0199756 0.0335185 0.0256971 -0.0192008 0.0336617 0.0282971 -0.0183733 0.0335608 0.0282971 -0.0172601 0.0335608 0.0256971 -0.0172601 0.0333872 0.0282971 -0.0167271 0.0333872 0.0256971 -0.0167271 0.032627 0.0282971 -0.0155583 0.032627 0.0256971 -0.0155583 0.0309674 0.0282971 -0.0145514 0.0324256 0.0256971 -0.0153631 0.0174485 0.0282971 -0.0343796 0.0174485 0.0256971 -0.0343796 0.0177232 0.0282971 -0.0343232 0.0189923 0.0256971 -0.0337457 0.019425 0.0282971 -0.0333894 0.0201082 0.0256971 -0.0325047 0.0204319 0.0282971 -0.0317299 0.0204319 0.0256971 -0.0317299 0.0205751 0.0282971 -0.0309024 0.0195404 0.0282971 -0.0280874 0.0195404 0.0256971 -0.0280874 0.0178808 0.0282971 -0.0270805 -0.00181534 0.0282971 -0.0385882 -0.000149353 0.0282971 -0.0386869 -0.000149353 0.0256971 -0.0386869 0.000125343 0.0282971 -0.0386304 0.00139446 0.0282971 -0.0380529 0.00182714 0.0282971 -0.0376967 0.00251034 0.0282971 -0.0368119 0.00182714 0.0256971 -0.0376967 0.00251034 0.0256971 -0.0368119 0.00283406 0.0282971 -0.0360371 0.00297725 0.0282971 -0.0352097 0.00297725 0.0256971 -0.0352097 0.00287629 0.0282971 -0.0340964 0.00287629 0.0256971 -0.0340964 0.00270274 0.0256971 -0.0335635 -0.0172685 0.0282971 -0.0335617 -0.0145598 0.0282971 -0.0309684 -0.0154513 0.0256971 -0.0273259 -0.0154513 0.0282971 -0.0273259 -0.0171109 0.0256971 -0.026319 -0.0300723 0.0256971 -0.0205315 -0.0285285 0.0282971 -0.0198976 -0.0269457 0.0282971 -0.0170543 -0.0274126 0.0256971 -0.0186566 -0.0269457 0.0256971 -0.0170543 -0.0281818 0.0256971 -0.0140441 -0.02964 0.0256971 -0.0132324 -0.0341049 0.0282971 -0.00287721 -0.0341049 0.0256971 -0.00287721 -0.0313961 0.0282971 -0.000283883 -0.0313961 0.0256971 -0.000283883 -0.0313539 0.0256971 0.0016568 -0.0313539 0.0282971 0.0016568 -0.0339472 0.0256971 0.00436552 0.0265155 0.0281471 0.0224509 0.0267635 0.0284971 0.0226552 0.0267635 0.0281471 0.0226552 0.0274229 0.0281471 0.024081 0.0272655 0.0281471 0.0250248 0.027365 0.0284971 0.0247193 0.0268297 0.0284971 0.025695 0.0268297 0.0281471 0.025695 0.0354787 0.0281471 0.0067717 0.036056 0.0284971 0.00772318 0.0355448 0.0284971 0.00981154 0.0360802 0.0281471 0.00883584 0.0341088 0.0281471 -0.0118767 0.0350845 0.0284971 -0.0113413 0.0350845 0.0281471 -0.0113413 0.0354762 0.0281471 -0.0108341 0.0356618 0.0281471 -0.0103899 0.0357439 0.0281471 -0.00991546 0.035686 0.0281471 -0.0092772 0.0350352 0.0281471 -0.00818961 0.0351506 0.0281471 -0.0083015 0.00866993 0.0281471 -0.0361135 0.00771477 0.0284971 -0.0360569 0.00882743 0.0284971 -0.0360811 0.00882743 0.0281471 -0.0360811 0.00955506 0.0281471 -0.03575 0.00980312 0.0281471 -0.0355457 0.0101948 0.0281471 -0.0350385 0.0103804 0.0284971 -0.0345943 0.0104625 0.0281471 -0.0341199 0.0104046 0.0284971 -0.0334816 0.00986928 0.0284971 -0.0325059 0.0089178 0.0284971 -0.0319286 0.00975383 0.0281471 -0.032394 0.0103051 0.0281471 -0.0331761 -0.00944311 0.0284971 -0.0357193 -0.00830992 0.0281471 -0.0351516 -0.00791822 0.0284971 -0.0346443 -0.00773262 0.0281471 -0.0342001 -0.00780791 0.0284971 -0.0327819 -0.00824376 0.0281471 -0.0321117 -0.00835922 0.0284971 -0.0319998 -0.00919525 0.0281471 -0.0315344 -0.0247749 0.0284971 -0.026289 -0.0247749 0.0281471 -0.026289 -0.0237992 0.0281471 -0.0257537 -0.0232219 0.0281471 -0.0248022 -0.0231977 0.0281471 -0.0236895 -0.023733 0.0281471 -0.0227138 -0.0246845 0.0281471 -0.0221365 -0.0342085 0.0284971 0.0077317 -0.0330958 0.0284971 0.00770749 -0.0321201 0.0284971 0.00824285 -0.0317284 0.0281471 0.0087501 -0.0315428 0.0284971 0.00919433 -0.0314607 0.0281471 0.00966873 -0.0315186 0.0284971 0.010307 -0.0316181 0.0281471 0.0106125 -0.0321694 0.0281471 0.0113946 -0.0330055 0.0284971 0.01186 -0.032054 0.0281471 0.0112827 -0.032054 0.0284971 0.0112827 -0.0236979 0.0284971 0.0231967 -0.0236979 0.0281471 0.0231967 -0.0221207 0.0284971 0.0257962 -0.0226561 0.0284971 0.0267719 -0.00797196 0.0281471 0.0318795 -0.00781447 0.0284971 0.0319119 -0.00781447 0.0281471 0.0319119 -0.00683877 0.0284971 0.0324472 -0.00644708 0.0281471 0.0329545 -0.00626147 0.0281471 0.0333987 -0.00626147 0.0284971 0.0333987 -0.00623726 0.0284971 0.0345114 -0.00677262 0.0284971 0.0354871 -0.00688807 0.0281471 0.035599 -0.0077241 0.0284971 0.0360644 -0.00677262 0.0281471 0.0354871 -0.00633677 0.0281471 0.0348169 -0.00776438 0.0282971 -0.0112868 -0.0076511 0.0284971 -0.011122 -0.0135284 0.0282971 -0.00585698 -0.0134779 0.0284971 -0.00566345 -0.0134404 0.0282971 -0.00588125 -0.0124411 0.0282971 -0.00637461 -0.023435 0.0284971 -0.00793435 -0.0191258 0.0282971 -0.00664251 -0.01473 0.0282971 -0.00577784 -0.0259977 0.0282971 -0.01257 -0.0248507 0.0282971 -0.00917611 -0.0233559 0.0282971 -0.00811807 -0.0210965 0.0282971 -0.0201896 -0.0155254 0.0284971 -0.0249656 -0.0062242 0.0284971 -0.0144893 -0.0074765 0.0282971 -0.0188101 -0.0064482 0.0282971 -0.0132522 -0.00675186 0.0284971 -0.0120321 -0.0151801 0.0284971 0.0133819 -0.0122148 0.0284971 0.009986 -0.0251309 0.0282971 0.0148804 -0.0238904 0.0282971 0.0162275 -0.0240061 0.0284971 0.0163907 -0.0222089 0.0282971 0.016953 -0.0222481 0.0284971 0.0171491 -0.018714 0.0282971 0.0161656 -0.0278367 0.0284971 -0.00263699 -0.0277043 0.0282971 -0.00248709 -0.0290151 0.0284971 -0.00101183 -0.0156658 0.0284971 -0.00185651 -0.0138016 0.0284971 -0.000170952 -0.0145723 0.0284971 -0.0011923 -0.0134631 0.0284971 0.00106289 -0.0121018 0.0282971 0.00643418 -0.0118421 0.0282971 0.00878525 -0.0115479 0.0284971 0.00756288 -0.0119252 0.0284971 0.0063403 0.00380007 0.0282971 0.0198863 0.00399342 0.0284971 0.0198351 0.00357172 0.0282971 0.0277078 0.0046593 0.0284971 0.0261704 -0.0042956 0.0284971 0.0290889 -0.00694672 0.0282971 0.0283665 -0.00699426 0.0284971 0.0285608 -0.00651375 0.0284971 0.0286741 -0.0162265 0.0284971 0.0210585 -0.0161661 0.0284971 0.0229721 -0.0151739 0.0282971 0.0245726 -0.0137741 0.0282971 0.0257534 -0.0138684 0.0284971 0.0259297 -0.00931886 0.0282971 0.0127907 -0.0125621 0.0282971 0.0158815 -0.0127099 0.0284971 0.0157468 -0.0153373 0.0282971 0.0193985 -0.00817565 0.0282971 0.0121852 0.00235097 0.0282971 0.015647 0.00253517 0.0284971 0.0155691 0.0191688 0.0284971 0.00645699 0.025442 0.0282971 0.0143254 0.0259884 0.0282971 0.0125775 0.0233466 0.0282971 0.00812557 0.0154105 0.0282971 0.0248032 0.0102474 0.0282971 0.0244269 0.0118058 0.0284971 0.0254841 0.0137153 0.0284971 0.0256233 0.013688 0.0282971 0.0254252 0.00746717 0.0282971 0.0188176 0.00912536 0.0282971 0.0229796 0.00643886 0.0282971 0.0132597 0.00624332 0.0284971 0.0132177 0.0134311 0.0282971 0.00588875 0.0153117 0.0282971 -0.0132325 0.0122054 0.0284971 -0.0099785 0.0200484 0.0284971 -0.0170475 0.0185851 0.0284971 -0.0163184 0.0291799 0.0282971 -0.000946396 0.0282213 0.0284971 -0.00822161 0.0251215 0.0282971 -0.0148729 0.0262724 0.0282971 0.00333673 0.0244432 0.0284971 0.00378427 0.0278287 0.0282971 0.00237149 0.0263402 0.0284971 0.00352491 0.0279672 0.0284971 0.00251579 0.0288573 0.0282971 0.000856284 0.0290425 0.0284971 0.000931716 0.0200246 0.0282971 0.00293989 0.0146971 0.0282971 0.00105145 0.0137923 0.0284971 0.000178451 0.0145629 0.0284971 0.0011998 0.012365 0.0282971 -0.00985792 0.0116399 0.0284971 -0.00883082 0.0120924 0.0282971 -0.00642668 -0.00464659 0.0282971 -0.0242799 -0.00400275 0.0284971 -0.0198276 -0.00254451 0.0284971 -0.0155616 -0.00341817 0.0284971 -0.0281551 -0.00459651 0.0284971 -0.026376 0.0137648 0.0282971 -0.0257459 0.00693738 0.0282971 -0.028359 -0.000325099 0.0282971 -0.0291945 0.0162172 0.0284971 -0.021051 0.0161568 0.0284971 -0.0229646 0.0151646 0.0282971 -0.0245651 0.0125527 0.0282971 -0.015874 0.0127006 0.0284971 -0.0157393 0.015328 0.0282971 -0.019391 0.00943693 0.0284971 -0.0126291 0.00930953 0.0282971 -0.0127832 0.00704511 0.0284971 -0.0118574 0.00831494 0.0284971 -0.0120141 0.000467962 0.0284971 -0.013488 -0.00169097 0.0282971 -0.0146385 -0.00183335 0.0284971 -0.014498 -0.000699064 0.0282971 -0.0139557 0.000474964 0.0282971 -0.0136879 0.00748393 0.0284971 0.00833207 0.0109761 0.0282971 -0.000646624 0.0111757 0.0284971 -0.000658449 0.00633324 0.0282971 -0.00898685 -0.0270744 0.0284971 0.0208907 -0.0260909 0.0284971 0.0190982 -0.0261354 0.0284971 0.017054 -0.0290361 0.0282971 0.0145166 -0.027196 0.0284971 0.0153059 -0.0289885 0.0284971 0.0143224 -0.0309768 0.0282971 0.0145589 0.0032642 0.0282971 0.037784 0.00339792 0.0284971 0.0379327 0.00420812 0.0284971 0.0330742 0.0171015 0.0282971 0.0263265 0.0219429 0.0284971 0.0288216 0.020744 0.0282971 0.027218 0.0210039 0.0284971 0.0326583 0.0207355 0.0284971 0.0329136 0.0196062 0.0284971 0.0335988 0.0296307 0.0282971 0.0132399 0.0313295 0.0284971 0.0129439 0.0328405 0.0282971 0.0137751 0.0332731 0.0282971 0.0141314 0.0339563 0.0282971 0.0150161 0.0342801 0.0282971 0.015791 0.0344232 0.0282971 0.0166184 0.0333885 0.0282971 0.0194334 0.0343223 0.0282971 0.0177316 0.0358786 0.0282971 -0.00440025 0.0388949 0.0284971 -0.000182203 0.0388661 0.0284971 -0.00150281 0.0360922 0.0284971 0.00303449 0.0378402 0.0284971 0.00197387 0.0288691 0.0282971 -0.0217519 0.030568 0.0284971 -0.0220478 0.0308098 0.0282971 -0.0217941 0.0320789 0.0282971 -0.0212166 0.0335904 0.0284971 -0.0196071 0.0335185 0.0282971 -0.0192008 0.0338614 0.0284971 -0.0183851 0.0335722 0.0284971 -0.0166512 0.0310234 0.0284971 -0.0143593 0.0324256 0.0282971 -0.0153631 0.0174814 0.0284971 -0.0345769 0.0157825 0.0282971 -0.034281 0.018126 0.0284971 -0.0344126 0.0189923 0.0282971 -0.0337457 0.0201082 0.0282971 -0.0325047 0.0204742 0.0282971 -0.0297892 0.0204856 0.0284971 -0.0291803 0.0179368 0.0284971 -0.0268885 0.019339 0.0282971 -0.0278922 0.0203006 0.0282971 -0.0292563 -0.000116455 0.0284971 -0.0388842 0.00268508 0.0284971 -0.0369092 0.000282966 0.0282971 -0.0313877 0.00174116 0.0282971 -0.0321995 0.00187488 0.0284971 -0.0320507 0.00194253 0.0282971 -0.0323946 0.00270274 0.0282971 -0.0335635 -0.0153068 0.0284971 -0.0271876 -0.0145175 0.0282971 -0.0290277 -0.0155667 0.0282971 -0.0326279 -0.0154284 0.0284971 -0.0327724 -0.0192092 0.0282971 -0.0335195 -0.029584 0.0284971 -0.0130404 -0.0281818 0.0282971 -0.0140441 -0.0280481 0.0284971 -0.0138954 -0.0272202 0.0282971 -0.0154082 -0.0274126 0.0282971 -0.0186566 -0.0272379 0.0284971 -0.0187539 -0.0300723 0.0282971 -0.0205315 -0.0300394 0.0284971 -0.0207288 -0.0322877 0.0282971 0.0033586 -0.0338913 0.0284971 0.00455753 -0.0311596 0.0284971 0.00170435 -0.0312041 0.0284971 -0.000339838 -0.0324031 0.0282971 -0.00194345 -0.0322647 0.0284971 -0.00208791 -0.0340573 0.0284971 -0.00307148 -0.0361015 0.0284971 -0.00302699 0.0310557 0.0284971 -0.0234155 0.0258406 0.0284971 -0.0280269 -0.0149386 0.0284971 -0.0273845 -0.0208011 0.0284971 -0.0328564 -0.0207448 0.0284971 -0.0329061 -0.0345259 0.0284971 -0.0177717 -0.0344211 0.0284971 -0.0181269 -0.0384477 0.0284971 0.00268653 -0.0310651 0.0284971 0.023423 -0.0226994 0.0284971 0.0315974 -0.0181354 0.0284971 0.0344201 0.0100933 0.0284971 -0.00885463 0.000770109 0.0284971 0.0137801 -0.0259747 0.0284971 -0.010687 -0.0232219 0.0284971 -0.0248022 0.0114374 0.0284971 -0.0350707 0.0031769 0.0284971 -0.0352215 0.00622793 0.0284971 -0.0345039 0.00288774 0.0284971 -0.0334875 0.00315679 0.0284971 -0.0326577 0.00625214 0.0284971 -0.0333912 0.0109332 0.0284971 -0.0373268 0.00698493 0.0284971 -0.0285533 -0.0143233 0.0284971 -0.0289801 -0.0143678 0.0284971 -0.0310243 -0.0172209 0.0284971 -0.033756 -0.0118609 0.0284971 -0.032997 -0.0118851 0.0284971 -0.0341097 -0.00455845 0.0284971 -0.0338829 -0.00163402 0.0284971 -0.0388621 -0.0018713 0.0284971 -0.0387802 -0.00460294 0.0284971 -0.035927 -0.0103983 0.0284971 -0.0356627 -0.0108879 0.0284971 -0.0373428 -0.00855799 0.0284971 -0.0353558 -0.00765052 0.0284971 -0.0337257 -0.029181 0.0284971 -0.0257247 -0.0272749 0.0284971 -0.0250173 -0.0231977 0.0284971 -0.0236895 -0.021241 0.0284971 -0.0203279 -0.023733 0.0284971 -0.0227138 -0.00853012 0.0284971 -0.029252 -0.00728594 0.0284971 -0.0188709 -0.00551075 0.0284971 -0.0188908 -0.00625266 0.0284971 -0.0132102 -0.0222092 0.0284971 -0.0252657 -0.0192485 0.0284971 -0.0222231 -0.0114525 0.0284971 -0.00715142 -0.0123227 0.0284971 -0.00621343 -0.0132805 0.0284971 -0.00204323 -0.0199912 0.0284971 -0.00312778 -0.0147546 0.0284971 -0.00557937 -0.0191782 0.0284971 -0.00644949 -0.0249977 0.0284971 -0.00904048 -0.0260785 0.0284971 -0.00360558 -0.0293891 0.0284971 0.000960403 -0.0203337 0.0284971 0.0171262 -0.0101026 0.0284971 0.00886212 -0.0116492 0.0284971 0.00883831 -0.000477295 0.0284971 0.0134955 -0.00944627 0.0284971 0.0126366 -0.00645781 0.0284971 0.00915782 -0.0185944 0.0284971 0.0163259 -0.0155027 0.0284971 0.019286 -0.00883676 0.0284971 0.0360886 -0.0036376 0.0284971 0.0387337 0.00469994 0.0284971 0.0347619 0.00182401 0.0284971 0.0145055 0.0103558 0.0284971 0.00425813 0.00370933 0.0284971 0.0127486 0.0031288 0.0284971 0.0107565 0.00674252 0.0284971 0.0120396 0.00764177 0.0284971 0.0111295 0.0114432 0.0284971 0.00715892 0.0122745 0.0284971 0.0062499 0.0192558 0.0284971 0.033719 0.0108785 0.0284971 0.0373503 0.0194999 0.0284971 0.0336606 0.00894526 0.0284971 0.0230665 0.00727661 0.0284971 0.0188784 0.00621486 0.0284971 0.0144968 0.015419 0.0284971 0.0327799 0.0143584 0.0284971 0.0310318 0.00668346 0.0284971 0.0229545 0.0101183 0.0284971 0.0245796 0.0246752 0.0284971 0.022144 0.0257878 0.0284971 0.0221198 0.029275 0.0284971 0.0256145 0.0273408 0.0284971 0.0236066 0.0269878 0.0284971 0.0280148 0.0152975 0.0284971 0.0271951 0.015516 0.0284971 0.0249731 0.0192392 0.0284971 0.0222306 0.0170456 0.0284971 0.0261344 0.0190898 0.0284971 0.02609 0.0212317 0.0284971 0.0203354 0.0229338 0.0284971 0.0183936 0.0240379 0.0284971 0.0259654 0.0220607 0.0284971 0.0320401 0.0219874 0.0284971 0.0308658 0.0208823 0.0284971 0.0270735 0.026651 0.0284971 0.0171358 0.0156565 0.0284971 0.00186401 0.0133751 0.0284971 0.00569674 0.0259654 0.0284971 0.0106945 0.0236768 0.0284971 0.00692987 0.0249883 0.0284971 0.00904798 0.0234256 0.0284971 0.00794185 0.0132712 0.0284971 0.00205073 0.0134537 0.0284971 -0.00105539 0.0119158 0.0284971 -0.0063328 0.0115386 0.0284971 -0.00755538 0.0147453 0.0284971 0.00558687 0.0199819 0.0284971 0.00313528 0.0277623 0.0284971 0.0057393 0.0293798 0.0284971 -0.000952903 0.0315358 0.0284971 0.00116349 0.0289792 0.0284971 -0.0143149 0.0252936 0.0284971 -0.0149748 0.0151708 0.0284971 -0.0133744 0.0154933 0.0284971 -0.0192785 0.00183761 0.0284971 -0.0110437 0.00580728 0.0284971 -0.0121811 0.00644848 0.0284971 -0.00915032 0.0129949 0.0284971 -0.0316198 0.0138591 0.0284971 -0.0259222 -0.000779443 0.0284971 -0.0137726 -0.00313814 0.0284971 -0.010749 -0.00484522 0.0284971 -0.0242565 0.00033892 0.0284971 -0.0311957 -0.00156378 0.0284971 -0.0292111 0.00978121 0.0284971 -0.00544387 -0.0082316 0.0284971 0.0119932 -0.00979055 0.0284971 0.00545137 -0.0111851 0.0284971 0.000665948 -0.0103652 0.0284971 -0.00425063 0.00162468 0.0284971 0.0388696 0.00186196 0.0284971 0.0387877 0.00441079 0.0284971 0.0364959 0.00483589 0.0284971 0.024264 0.00303274 0.0284971 0.031767 0.00140659 0.0284971 0.0310993 0.00372192 0.0284971 0.0278398 0.00218612 0.0284971 0.028983 -0.000348254 0.0284971 0.0312032 -0.00209633 0.0284971 0.0322638 0.000317961 0.0284971 0.029402 -0.00303541 0.0284971 0.0361006 -0.00140576 0.0284971 0.0388785 -0.0153319 0.0284971 0.0246953 -0.0159019 0.0284971 0.0268515 -0.0141094 0.0284971 0.027835 -0.00892713 0.0284971 0.0319361 -0.0130488 0.0284971 0.0295831 -0.0130043 0.0284971 0.0316273 -0.0139878 0.0284971 0.0334199 -0.0103898 0.0284971 0.0346018 -0.0157359 0.0284971 0.0344805 -0.0166238 0.0284971 0.035175 -0.0160445 0.0284971 0.0345571 -0.0203437 0.0284971 0.0197579 -0.020495 0.0284971 0.0291878 -0.0227222 0.0284971 0.0237321 -0.0221449 0.0284971 0.0246836 -0.0179461 0.0284971 0.026896 -0.0236076 0.0284971 0.0273492 -0.0248106 0.0284971 0.023221 -0.0254478 0.0284971 0.0270424 -0.0261979 0.0284971 0.0244684 -0.027642 0.0284971 0.0218848 -0.0282306 0.0284971 0.00822911 -0.025303 0.0284971 0.0149823 -0.0308667 0.0284971 0.0219958 -0.0326593 0.0284971 0.0210123 -0.0310327 0.0284971 0.0143668 -0.0350938 0.0284971 0.0113488 -0.0356711 0.0284971 0.0103974 -0.0356953 0.0284971 0.0092847 -0.0321432 0.0284971 0.00349691 -0.0341181 0.0284971 0.0118842 -0.0337644 0.0284971 0.01722 -0.0335997 0.0284971 0.0196146 -0.03516 0.0284971 0.008309 -0.0385412 0.0284971 0.00530866 -0.0356461 0.0284971 0.00466147 -0.0372723 0.0284971 0.00399371 -0.0368621 0.0284971 -0.00975462 -0.0317943 0.0284971 -0.0206249 -0.0271646 0.0284971 -0.0231549 -0.0265248 0.0284971 -0.0224434 -0.0256397 0.0284971 -0.0220799 -0.0284133 0.0284971 -0.0200611 -0.0246845 0.0284971 -0.0221365 -0.0267461 0.0284971 -0.0170662 -0.0256256 0.0284971 -0.014416 -0.0270352 0.0284971 -0.0153322 -0.0261968 0.0284971 -0.0125886 -0.0295637 0.0284971 -0.0118815 -0.0334208 0.0284971 -0.0139794 -0.0369227 0.0284971 -0.0122548 -0.0344814 0.0284971 -0.0157275 -0.0324238 0.0284971 -0.0214953 -0.0329162 0.0284971 -0.0207336 -0.0216113 0.0284971 -0.0279979 -0.0220701 0.0284971 -0.0320326 -0.0221031 0.0284971 -0.0296857 -0.021814 0.0284971 -0.0314196 -0.0228199 0.0284971 -0.0273614 -0.0237992 0.0284971 -0.0257537 -0.020217 0.0284971 -0.0258463 -0.0204359 0.0284971 -0.0266908 -0.0195093 0.0284971 -0.0336531 -0.00914082 0.0284971 -0.0313476 0.0107828 0.0284971 -0.0373706 0.00771454 0.0284971 -0.0381227 0.0015097 0.0284971 -0.0382164 0.00139643 0.0284971 -0.038871 -0.000190619 0.0284971 -0.0388958 0.00980312 0.0284971 -0.0355457 0.0139785 0.0284971 -0.0334124 0.01579 0.0284971 -0.0355454 0.0166145 0.0284971 -0.0351675 0.0192841 0.0284971 -0.0337772 0.020283 0.0284971 -0.032602 0.0207748 0.0284971 -0.0309143 0.0194728 0.0284971 -0.0277435 0.0185423 0.0284971 -0.0259001 0.0153225 0.0284971 -0.0246878 0.0270651 0.0284971 -0.0208832 0.0321942 0.0284971 -0.02138 0.0325594 0.0284971 -0.0152144 0.0315335 0.0284971 -0.00918683 0.0351506 0.0284971 -0.0083015 0.035686 0.0284971 -0.0092772 0.0385319 0.0284971 -0.00530117 0.0383814 0.0284971 -0.00629848 0.0356618 0.0284971 -0.0103899 0.0357578 0.0284971 -0.0153017 0.0341992 0.0284971 -0.0077242 0.0359261 0.0284971 -0.00459452 0.0338819 0.0284971 -0.00455003 0.032346 0.0284971 -0.00369499 0.0341088 0.0284971 -0.0118767 0.0353489 0.0284971 -0.0162238 0.0377187 0.0284971 -0.00361095 0.0387793 0.0284971 -0.00186288 0.0388238 0.0284971 0.000181307 0.0387742 0.0284971 0.00307104 0.034503 0.0284971 0.00623634 0.0341311 0.0284971 0.0149189 0.0361095 0.0284971 0.0144598 0.0346229 0.0284971 0.0166066 0.0333903 0.0284971 0.00626056 0.0354787 0.0284971 0.0067717 0.0350607 0.0284971 0.00361248 0.037327 0.0284971 0.0109379 0.0360802 0.0284971 0.00883584 0.0369133 0.0284971 0.0122623 0.0329557 0.0284971 0.0136117 0.0345933 0.0284971 0.0103888 0.0327531 0.0284971 0.010082 0.0280387 0.0284971 0.0139029 0.0261875 0.0284971 0.0125961 0.0270259 0.0284971 0.0153397 0.0256163 0.0284971 0.0144235 0.0333209 0.0284971 0.0197773 0.0329069 0.0284971 0.0207411 0.0317849 0.0284971 0.0206324 0.0300301 0.0284971 0.0207363 0.0166145 0.0287471 -0.0351675 0.0269878 0.0287471 0.0280148 0.0194999 0.0287471 0.0336606 0.0329069 0.0287471 0.0207411 0.0344117 0.0284971 0.0181344 0.0337763 0.0284971 0.0192925 0.0369133 0.0287471 0.0122623 0.0387742 0.0287471 0.00307104 0.0357578 0.0287471 -0.0153017 0.0245486 0.0287471 -0.0301682 0.0245486 0.0284971 -0.0301682 0.0329052 0.0284971 -0.0207364 0.0144177 0.0284971 -0.0361239 -0.00163402 0.0287471 -0.0388621 -0.00151122 0.0284971 -0.0388671 -0.00042076 0.0278971 -0.0370594 0.000686077 0.0372971 -0.0365048 0.00106867 0.0278971 -0.0360094 0.00106867 0.0372971 -0.0360094 0.00133014 0.0278971 -0.0351121 0.0012736 0.0372971 -0.0344887 0.00117641 0.0278971 -0.0341903 0.000750694 0.0372971 -0.0335357 -0.0176608 0.0372971 -0.031959 -0.0187475 0.0278971 -0.0319353 -0.0167078 0.0372971 -0.0314361 -0.0176608 0.0278971 -0.031959 -0.0167078 0.0278971 -0.0314361 -0.0161439 0.0372971 -0.0305067 -0.0161439 0.0278971 -0.0305067 -0.0161202 0.0372971 -0.0294199 -0.0166431 0.0372971 -0.0284669 -0.0161202 0.0278971 -0.0294199 -0.0175725 0.0372971 -0.0279031 -0.0303437 0.0372971 -0.018904 -0.0303437 0.0278971 -0.018904 -0.0294792 0.0278971 -0.018549 -0.0288543 0.0372971 -0.017854 -0.0288543 0.0278971 -0.017854 -0.0285928 0.0278971 -0.0169568 -0.029285 0.0278971 -0.0152711 -0.0337864 0.0372971 -0.000951117 -0.0335441 0.0372971 -0.000751611 -0.0331615 0.0372971 -0.000256158 -0.0331615 0.0278971 -0.000256158 -0.0329802 0.0372971 0.000177745 -0.0329001 0.0278971 0.000641108 -0.0329566 0.0372971 0.00126453 -0.0335923 0.0278971 0.00232683 -0.0334795 0.0372971 0.00221753 -0.0344089 0.0372971 0.00278141 -0.0295822 0.0278971 0.0160877 -0.0278313 0.0372971 0.0180349 -0.0280928 0.0278971 0.0171377 -0.027985 0.0278971 0.0189568 -0.0285235 0.0278971 0.0197207 -0.0293401 0.0372971 0.0201752 -0.0163418 0.0372971 0.0286484 -0.0153888 0.0372971 0.0291713 -0.0153888 0.0278971 0.0291713 -0.0148249 0.0278971 0.0301007 -0.0148012 0.0278971 0.0311875 -0.0153241 0.0278971 0.0321405 0.000169328 0.0372971 0.0329793 0.00110228 0.0278971 0.0329241 0.00125611 0.0372971 0.0329557 0.00125611 0.0278971 0.0329557 0.00196682 0.0278971 0.0332791 0.00220912 0.0278971 0.0334786 0.00259171 0.0278971 0.033974 0.00279664 0.0372971 0.0354947 0.00216097 0.0278971 0.036557 0.00227374 0.0278971 0.0364477 0.0195548 0.0372971 0.0314883 0.0196676 0.0278971 0.031379 0.0200933 0.0278971 0.0307244 0.0201905 0.0278971 0.030426 0.020247 0.0372971 0.0298025 0.0201668 0.0278971 0.0293392 0.0201668 0.0372971 0.0293392 0.019603 0.0278971 0.0284098 0.0199855 0.0372971 0.0289053 0.0193607 0.0278971 0.0282103 0.0184961 0.0278971 0.0278553 0.0318898 0.0372971 0.0151237 0.0325147 0.0372971 0.0158187 0.0327761 0.0372971 0.0167159 0.0327761 0.0278971 0.0167159 0.0326224 0.0372971 0.0176378 0.0320839 0.0278971 0.0184017 0.0364393 0.0372971 -0.00227465 0.0365039 0.0372971 0.000694493 0.0355746 0.0372971 0.00125837 0.0365039 0.0278971 0.000694493 0.0293308 0.0372971 -0.0201677 0.0304175 0.0372971 -0.0201914 0.0311283 0.0278971 -0.019868 0.0317531 0.0278971 -0.019173 0.0317531 0.0372971 -0.019173 0.0319344 0.0372971 -0.0187391 0.0320146 0.0278971 -0.0182758 0.0320146 0.0372971 -0.0182758 0.0319581 0.0372971 -0.0176523 0.0318609 0.0278971 -0.0173539 0.0318609 0.0372971 -0.0173539 0.0162442 0.0372971 -0.0326969 0.0171771 0.0278971 -0.0327521 0.017331 0.0278971 -0.0327205 0.017331 0.0372971 -0.0327205 0.018284 0.0372971 -0.0321976 0.018928 0.0278971 -0.0308049 0.0188715 0.0372971 -0.0301815 0.0183486 0.0278971 -0.0292285 0.000443777 0.0278971 -0.0367044 0.000637924 0.0278971 -0.0334264 -0.000178662 0.0278971 -0.0329718 0.0010391 0.0272971 -0.0329802 -1.07973e-05 0.0272971 -0.0323958 -0.0166431 0.0278971 -0.0284669 -0.0155374 0.0272971 -0.0292773 -0.0162097 0.0272971 -0.028052 -0.0175725 0.0278971 -0.0279031 -0.030245 0.0272971 -0.0194958 -0.0279939 0.0272971 -0.0169922 -0.0287465 0.0278971 -0.0160349 -0.0355839 0.0278971 -0.00125087 -0.034651 0.0278971 -0.00130613 -0.0345523 0.0272971 -0.00189795 -0.0337864 0.0278971 -0.000951117 -0.0334407 0.0272971 -0.00144151 -0.0326373 0.0272971 -0.000547994 -0.0330538 0.0278971 0.00156297 -0.0305151 0.0278971 0.016143 -0.0287177 0.0278971 0.0164427 -0.0278313 0.0278971 0.0180349 -0.0272323 0.0272971 0.0179995 -0.0293401 0.0278971 0.0201752 -0.0163418 0.0278971 0.0286484 -0.0149738 0.0272971 0.0287379 -0.0148908 0.0272971 0.0325554 -0.0160856 0.0272971 0.0332804 0.00256214 0.0272971 0.0370032 0.00325448 0.0272971 0.0360211 0.00269945 0.0278971 0.0357932 0.00279664 0.0278971 0.0354947 0.00285318 0.0278971 0.0348713 0.00277299 0.0278971 0.0344079 0.00231252 0.0272971 0.0327887 0.0187382 0.0278971 0.0319428 0.0195548 0.0278971 0.0314883 0.019956 0.0272971 0.0319344 0.020247 0.0278971 0.0298025 0.0199855 0.0278971 0.0289053 0.0197064 0.0272971 0.0277199 0.0175632 0.0278971 0.0279106 0.0185948 0.0272971 0.0272635 0.0186499 0.0278971 0.0278869 0.0299244 0.0272971 0.0142479 0.0310252 0.0278971 0.0147687 0.0318898 0.0278971 0.0151237 0.0325147 0.0278971 0.0158187 0.0330389 0.0272971 0.0155268 0.0333751 0.0272971 0.0166805 0.0326224 0.0278971 0.0176378 0.0324851 0.0272971 0.0188478 0.0354863 0.0278971 -0.00279756 0.0364393 0.0278971 -0.00227465 0.0368542 0.0272971 -0.00270805 0.0370032 0.0278971 -0.0013453 0.0375792 0.0272971 -0.00151316 0.0370268 0.0278971 -0.000258514 0.0369373 0.0272971 0.00110943 0.0293308 0.0278971 -0.0201677 0.0291629 0.0272971 -0.0207438 0.0302637 0.0278971 -0.020223 0.0322774 0.0272971 -0.0194649 0.0326136 0.0272971 -0.0183112 0.0324159 0.0272971 -0.017126 0.0313224 0.0278971 -0.01659 0.0317236 0.0272971 -0.0161439 -0.00793334 0.0366471 0.0323976 -0.00713378 0.0366471 0.0351413 -0.00674151 0.0366471 0.0335386 -0.00688395 0.0366471 0.0331977 -0.00832562 0.0376385 0.0340002 0.0252767 0.0376385 0.0242082 0.0264685 0.0366471 0.0253492 0.0268608 0.0366471 0.0237465 0.0335302 0.0366471 0.00674059 0.0356389 0.0366471 0.00822714 0.0339918 0.0376385 0.0083247 0.0355182 0.0366471 0.00895146 0.033869 0.0366471 -0.0114159 0.0335976 0.0376385 -0.00978834 0.0340593 0.0366471 -0.00820424 0.035124 0.0366471 -0.00916158 0.00926697 0.0366471 -0.0353413 0.00831628 0.0376385 -0.0339927 0.00941951 0.0366471 -0.0327658 0.0099634 0.0366471 -0.0340903 -0.00835509 0.0366471 -0.0344011 -0.00819407 0.0366471 -0.0332063 -0.00979676 0.0376385 -0.0335986 -0.0243353 0.0366471 -0.0255492 -0.0237597 0.0366471 -0.0235739 -0.025286 0.0376385 -0.0242007 -0.0320806 0.0366471 0.0104226 -0.0102568 0.0369971 -0.0244194 -0.0091347 0.0369971 -0.0229721 -0.0124411 0.0369971 -0.00637461 -0.00642141 0.0369971 -0.0144561 -0.01473 0.0369971 -0.00577784 -0.0233559 0.0369971 -0.00811807 -0.0254513 0.0369971 -0.0143179 -0.0136973 0.0369971 -0.0254177 -0.0154198 0.0369971 -0.0247957 0.0125527 0.0369971 -0.015874 0.00930953 0.0369971 -0.0127832 0.00825353 0.0369971 -0.0122045 -0.0023603 0.0369971 -0.0156395 0.0160203 0.0369971 -0.0210864 0.0151646 0.0369971 -0.0245651 0.015328 0.0369971 -0.019391 0.0280293 0.0369971 -0.00816565 0.0139718 0.0369971 9.01814e-05 0.0260132 0.0369971 0.00342107 0.0117374 0.0369971 -0.00757734 0.0187047 0.0369971 -0.0161581 0.0147206 0.0369971 0.00578534 0.0123952 0.0369971 0.00640938 0.0116128 0.0369971 0.00726492 0.0069087 0.0369971 0.0121509 0.0248413 0.0369971 0.00918361 0.0257759 0.0369971 0.0107585 0.0233466 0.0369971 0.00812557 0.0259884 0.0369971 0.0125775 0.025442 0.0369971 0.0143254 0.0122799 0.0369971 0.0253916 0.00746717 0.0369971 0.0188176 0.0210872 0.0369971 0.0201971 -0.00702224 0.0369971 0.0120678 -0.000484297 0.0369971 0.0136954 -0.0160297 0.0369971 0.0210939 -0.0137741 0.0369971 0.0257534 -0.00694672 0.0369971 0.0283665 -0.0125621 0.0369971 0.0158815 0.00149849 0.0369971 0.0290265 0.00463726 0.0369971 0.0242874 0.00380007 0.0369971 0.0198863 0.00235097 0.0369971 0.015647 -0.0136624 0.0369971 0.00107858 -0.0121018 0.0369971 0.00643418 -0.0118421 0.0369971 0.00878525 -0.0147064 0.0369971 -0.00104395 -0.0238157 0.0369971 0.0162793 -0.0201137 0.0369971 0.016863 -0.0123743 0.0369971 0.00986542 -0.027838 0.0369971 -0.00236399 -0.0291892 0.0369971 0.000953895 -0.0244673 0.0369971 -0.00357732 -0.0200339 0.0369971 -0.00293239 0.0182358 0.0278971 -0.0291192 0.018637 0.0272971 -0.028673 0.0187743 0.0278971 -0.029883 0.0193293 0.0272971 -0.0296551 0.0188715 0.0278971 -0.0301815 0.0191908 0.0272971 -0.031994 0.0188478 0.0278971 -0.0312683 0.0186665 0.0278971 -0.0317022 0.0183874 0.0272971 -0.0328875 0.018284 0.0278971 -0.0321976 0.0180417 0.0278971 -0.0323971 0.0160763 0.0272971 -0.0332729 0.0172758 0.0272971 -0.0333439 0.00192909 0.0272971 -0.0351476 0.00173144 0.0272971 -0.0339624 0.0015974 0.0272971 -0.0323593 -0.0016066 0.0272971 -0.0315543 -0.00335837 0.0272971 -0.0342326 -0.00416002 0.0272971 -0.033999 -0.00419983 0.0272971 -0.0358284 -0.00271646 0.0272971 -0.0368552 -0.00152158 0.0272971 -0.0375801 -0.0033196 0.0272971 -0.0374326 -0.000322067 0.0272971 -0.0376512 0.000789481 0.0272971 -0.0371947 0.00159291 0.0272971 -0.0363012 0.00232248 0.0272971 -0.0367074 -0.0205191 0.0272971 -0.0286059 -0.0206047 0.0272971 -0.0273658 -0.0197157 0.0272971 -0.0277124 -0.0147264 0.0272971 -0.0290788 -0.0147662 0.0272971 -0.0309082 -0.0155678 0.0272971 -0.0306746 -0.0157154 0.0272971 -0.0324726 -0.0162928 0.0272971 -0.0318695 -0.0175181 0.0272971 -0.0325418 -0.019149 0.0272971 -0.033313 -0.0189154 0.0272971 -0.0325114 -0.0199653 0.0272971 -0.0319269 -0.0206576 0.0272971 -0.0309448 -0.0215937 0.0272971 -0.0307596 -0.0215539 0.0272971 -0.0289302 -0.0291335 0.0272971 -0.0190394 -0.0298487 0.0272971 -0.0202663 -0.0316781 0.0272971 -0.0202264 -0.0314445 0.0272971 -0.0194248 -0.0341228 0.0272971 -0.017673 -0.034083 0.0272971 -0.0158436 -0.0333117 0.0272971 -0.0174745 -0.0332813 0.0272971 -0.0160772 -0.0325563 0.0272971 -0.0148823 -0.0315296 0.0272971 -0.013399 -0.031331 0.0272971 -0.01421 -0.0297001 0.0272971 -0.0134388 -0.0288839 0.0272971 -0.0148249 -0.0281915 0.0272971 -0.015807 -0.0272953 0.0272971 -0.0178216 -0.02833 0.0272971 -0.0181459 -0.0323011 0.0272971 0.000605633 -0.0324988 0.0272971 0.00179088 -0.0331911 0.0272971 0.00277299 -0.034241 0.0272971 0.00335745 -0.0326328 0.0272971 0.0033939 -0.0368636 0.0272971 0.00271555 -0.037441 0.0272971 0.00331869 -0.0383902 0.0272971 0.00175427 -0.0375886 0.0272971 0.00152066 -0.037619 0.0272971 0.000123368 -0.0357518 0.0272971 -0.00182691 -0.0344149 0.0272971 -0.00272158 -0.02743 0.0272971 0.0191847 -0.0265338 0.0272971 0.0171701 -0.027483 0.0272971 0.0156057 -0.0275685 0.0272971 0.0168458 -0.028372 0.0272971 0.0159523 -0.0294835 0.0272971 0.0154959 -0.030683 0.0272971 0.0155669 -0.0325502 0.0272971 0.0175172 -0.0333215 0.0272971 0.0191481 -0.0325198 0.0272971 0.0189145 -0.0273742 0.0272971 0.0206037 -0.0281223 0.0272971 0.0201668 -0.0195363 0.0272971 0.0308479 -0.0186463 0.0272971 0.0286805 -0.0161991 0.0272971 0.0280656 -0.01783 0.0272971 0.0272944 -0.0160006 0.0272971 0.0272546 -0.0142488 0.0272971 0.0299328 -0.0142184 0.0272971 0.0313301 -0.0134074 0.0272971 0.0315286 0.00151224 0.0272971 0.0375876 0.000114952 0.0272971 0.0376181 -8.3562e-05 0.0272971 0.0384291 -0.00168779 0.0272971 0.0375489 -0.00183532 0.0272971 0.0357509 -0.00186573 0.0272971 0.0343536 -0.00119342 0.0272971 0.0331283 -0.00179656 0.0272971 0.0325508 1.46377e-06 0.0272971 0.0324033 0.00120097 0.0272971 0.0323322 0.00133832 0.0272971 0.0315086 0.00311595 0.0272971 0.0336822 0.00384552 0.0272971 0.0332761 0.00345213 0.0272971 0.0348358 0.0205098 0.0272971 0.0286134 0.0171617 0.0272971 0.0265329 0.0173953 0.0272971 0.0273345 0.014717 0.0272971 0.0290863 0.0162004 0.0272971 0.0280595 0.0155281 0.0272971 0.0292848 0.0155585 0.0272971 0.0306821 0.0173103 0.0272971 0.0333604 0.0175088 0.0272971 0.0325493 0.0191397 0.0272971 0.0333205 0.0206483 0.0272971 0.0309523 0.020846 0.0272971 0.0297671 0.0327166 0.0272971 0.0139509 0.0337685 0.0272971 0.0151207 0.0339498 0.0272971 0.0181829 0.0331774 0.0272971 0.0178657 0.0316688 0.0272971 0.0202339 0.0314352 0.0272971 0.0194323 0.027286 0.0272971 0.0178291 0.0280572 0.0272971 0.0161982 0.0296908 0.0272971 0.0134463 0.0311239 0.0272971 0.0141769 0.0322355 0.0272971 0.0146333 0.0312613 0.0272971 0.0133533 0.0342317 0.0272971 -0.00334995 0.0356289 0.0272971 -0.00338036 0.0358275 0.0272971 -0.00419142 0.0376096 0.0272971 -0.000115869 0.0384207 0.0272971 8.26448e-05 0.0375405 0.0272971 0.00168687 0.0345429 0.0272971 0.00190545 0.0344056 0.0272971 0.00272908 0.0329503 0.0272971 0.00213148 0.0324894 0.0272971 -0.00178338 0.031717 0.0272971 -0.00210056 0.0326235 0.0272971 -0.0033864 0.033007 0.0272971 -0.019871 0.0334471 0.0272971 -0.0183606 0.0331883 0.0272971 -0.0168088 0.0292764 0.0272971 -0.015529 0.0280511 0.0272971 -0.0162013 0.0274736 0.0272971 -0.0155982 0.0265245 0.0272971 -0.0171626 0.0264846 0.0272971 -0.018992 0.0303624 0.0272971 -0.0208148 0.0304998 0.0272971 -0.0216385 0.031474 0.0272971 -0.0203584 -0.00805421 0.0290971 0.0323727 -0.00737493 0.0366471 0.0326517 -0.00718455 0.0366471 0.0328084 -0.0066785 0.0290971 0.0339027 -0.0066785 0.0366471 0.0339027 -0.00672292 0.0366471 0.0343925 -0.00679929 0.0290971 0.034627 -0.00679929 0.0366471 0.034627 -0.00722239 0.0290971 0.0352272 -0.00786399 0.0366471 0.0355844 0.025669 0.0366471 0.0226055 0.0248151 0.0290971 0.022624 0.025669 0.0290971 0.0226055 0.0264178 0.0290971 0.0230163 0.0264178 0.0366471 0.0230163 0.0268794 0.0366471 0.0246004 0.0264685 0.0290971 0.0253492 0.0342632 0.0366471 0.00669717 0.0349425 0.0366471 0.00697611 0.0351329 0.0290971 0.00713286 0.0354335 0.0366471 0.00752215 0.0350951 0.0366471 0.00955164 0.0344535 0.0290971 0.00990881 0.033136 0.0290971 -0.0113725 0.0345483 0.0366471 -0.0111369 0.033869 0.0290971 -0.0114159 0.0345483 0.0290971 -0.0111369 0.0350393 0.0366471 -0.0105909 0.0352448 0.0366471 -0.0098859 0.0352448 0.0290971 -0.0098859 0.0347009 0.0366471 -0.00856141 0.00858769 0.0366471 -0.0356203 0.00926697 0.0290971 -0.0353413 0.00975795 0.0366471 -0.0347953 0.0099634 0.0290971 -0.0340903 0.00984261 0.0366471 -0.033366 0.00984261 0.0290971 -0.033366 0.00941951 0.0290971 -0.0327658 0.00877791 0.0290971 -0.0324086 -0.0102584 0.0366471 -0.0351827 -0.00952535 0.0290971 -0.0352261 -0.00940449 0.0366471 -0.0352012 -0.00884608 0.0366471 -0.0349471 -0.0086557 0.0366471 -0.0347904 -0.00835509 0.0290971 -0.0344011 -0.00821265 0.0366471 -0.0340602 -0.00814965 0.0366471 -0.0336961 -0.00814965 0.0290971 -0.0336961 -0.00827044 0.0290971 -0.0329718 -0.00869353 0.0290971 -0.0323716 -0.00827044 0.0366471 -0.0329718 -0.00860493 0.0366471 -0.0324575 -0.00933513 0.0366471 -0.0320144 -0.0257476 0.0366471 -0.0257848 -0.0250146 0.0366471 -0.0258282 -0.0257476 0.0290971 -0.0257848 -0.0243353 0.0290971 -0.0255492 -0.0238444 0.0366471 -0.0250032 -0.0238444 0.0290971 -0.0250032 -0.0236389 0.0366471 -0.0242982 -0.0236389 0.0290971 -0.0242982 -0.0241828 0.0366471 -0.0229737 -0.0241828 0.0290971 -0.0229737 -0.0340686 0.0290971 0.00821174 -0.0333356 0.0366471 0.00816832 -0.0326563 0.0366471 0.00844725 -0.0321653 0.0366471 0.00899329 -0.0321653 0.0290971 0.00899329 -0.0319599 0.0366471 0.00969829 -0.0319599 0.0290971 0.00969829 -0.0325037 0.0366471 0.0110228 -0.0325037 0.0290971 0.0110228 -0.0331453 0.0366471 0.01138 -0.0246707 0.0290971 0.023701 -0.0238168 0.0366471 0.0236824 -0.0232584 0.0290971 0.0239365 -0.023068 0.0366471 0.0240933 -0.0227674 0.0290971 0.0244826 -0.022625 0.0290971 0.0248235 -0.022625 0.0366471 0.0248235 -0.0226064 0.0366471 0.0256774 -0.0226064 0.0290971 0.0256774 -0.0230172 0.0366471 0.0264262 -0.0231058 0.0290971 0.026512 -0.00642141 0.0287471 -0.0144561 -0.0074765 0.0287471 -0.0188101 -0.0074765 0.0369971 -0.0188101 -0.0118708 0.0369971 -0.0252845 -0.0136973 0.0287471 -0.0254177 -0.0210965 0.0287471 -0.0201896 -0.0210965 0.0369971 -0.0201896 -0.0248507 0.0369971 -0.00917611 -0.0248507 0.0287471 -0.00917611 -0.0257852 0.0287471 -0.010751 -0.0257852 0.0369971 -0.010751 -0.0259977 0.0369971 -0.01257 -0.0259977 0.0287471 -0.01257 -0.0191258 0.0369971 -0.00664251 -0.01473 0.0287471 -0.00577784 -0.0135284 0.0369971 -0.00585698 -0.0134404 0.0287471 -0.00588125 -0.0124045 0.0287471 -0.00640188 -0.0116221 0.0369971 -0.00725742 -0.00776438 0.0369971 -0.0112868 -0.00691803 0.0287471 -0.0121434 -0.00691803 0.0369971 -0.0121434 -0.0064482 0.0369971 -0.0132522 0.0125527 0.0287471 -0.015874 0.0159625 0.0369971 -0.0229168 0.0160203 0.0287471 -0.0210864 0.0137648 0.0287471 -0.0257459 0.0137648 0.0369971 -0.0257459 0.00693738 0.0369971 -0.028359 -0.000325099 0.0369971 -0.0291945 -0.00464659 0.0369971 -0.0242799 -0.00447768 0.0287471 -0.0261035 -0.00447768 0.0369971 -0.0261035 -0.00358106 0.0369971 -0.0277003 -0.00211204 0.0369971 -0.0287938 -0.0038094 0.0369971 -0.0198788 -0.0023603 0.0287471 -0.0156395 -0.00169097 0.0369971 -0.0146385 0.000474964 0.0287471 -0.0136879 -0.000699064 0.0369971 -0.0139557 0.000474964 0.0369971 -0.0136879 0.00589339 0.0287471 -0.0123616 0.00589339 0.0369971 -0.0123616 0.0070584 0.0369971 -0.012057 0.00701291 0.0287471 -0.0120603 0.00930953 0.0287471 -0.0127832 0.0200246 0.0287471 0.00293989 0.0200246 0.0369971 0.00293989 0.024458 0.0287471 0.00358482 0.024458 0.0369971 0.00358482 0.0280293 0.0287471 -0.00816565 0.0203683 0.0369971 -0.0169236 0.0221995 0.0369971 -0.0169455 0.023881 0.0369971 -0.01622 0.0251215 0.0369971 -0.0148729 0.0153117 0.0287471 -0.0132325 0.0153117 0.0369971 -0.0132325 0.012365 0.0287471 -0.00985792 0.012365 0.0369971 -0.00985792 0.0118327 0.0287471 -0.00877775 0.0118327 0.0369971 -0.00877775 0.0117374 0.0287471 -0.00757734 0.0120924 0.0369971 -0.00642668 0.0136531 0.0369971 -0.00107108 0.0139718 0.0287471 9.01814e-05 0.0146971 0.0287471 0.00105145 0.0146971 0.0369971 0.00105145 0.0157263 0.0369971 0.00167659 0.00641208 0.0369971 0.0144636 0.00746717 0.0287471 0.0188176 0.00912536 0.0287471 0.0229796 0.0122799 0.0287471 0.0253916 0.0104151 0.0369971 0.0245617 0.00912536 0.0369971 0.0229796 0.0154105 0.0369971 0.0248032 0.0210872 0.0287471 0.0201971 0.025442 0.0287471 0.0143254 0.0248413 0.0287471 0.00918361 0.0191165 0.0369971 0.00665001 0.0116128 0.0287471 0.00726492 0.00775505 0.0287471 0.0112943 0.00775505 0.0369971 0.0112943 0.0069087 0.0287471 0.0121509 0.00643886 0.0369971 0.0132597 0.00641208 0.0287471 0.0144636 -0.0125621 0.0287471 0.0158815 -0.00931886 0.0369971 0.0127907 -0.0151739 0.0369971 0.0245726 -0.0159719 0.0369971 0.0229243 -0.0151739 0.0287471 0.0245726 -0.0153373 0.0369971 0.0193985 -0.0160297 0.0287471 0.0210939 0.000315766 0.0287471 0.029202 0.000315766 0.0369971 0.029202 0.00380007 0.0287471 0.0198863 0.00235097 0.0287471 0.015647 0.00168164 0.0287471 0.014646 0.00068973 0.0287471 0.0139632 0.00168164 0.0369971 0.014646 0.00068973 0.0369971 0.0139632 -0.00590272 0.0287471 0.0123691 -0.00817565 0.0369971 0.0121852 -0.00826286 0.0287471 0.012212 -0.0200339 0.0287471 -0.00293239 -0.0288666 0.0369971 -0.000848785 -0.0288666 0.0287471 -0.000848785 -0.0262818 0.0369971 -0.00332923 -0.0262818 0.0287471 -0.00332923 -0.0244673 0.0287471 -0.00357732 -0.0280386 0.0287471 0.00817315 -0.0280386 0.0369971 0.00817315 -0.02203 0.0369971 0.016985 -0.0238157 0.0287471 0.0162793 -0.0251309 0.0369971 0.0148804 -0.018714 0.0369971 0.0161656 -0.0153211 0.0287471 0.01324 -0.0153211 0.0369971 0.01324 -0.0123743 0.0287471 0.00986542 -0.0117467 0.0369971 0.00758484 -0.0139811 0.0369971 -8.26822e-05 -0.0157356 0.0287471 -0.00166909 -0.0157356 0.0369971 -0.00166909 0.0201017 0.0272971 -0.0293379 0.0175871 0.0272971 -0.0280885 0.0159913 0.0272971 -0.0272471 0.0149645 0.0272971 -0.0287304 0.0134379 0.0272971 -0.0296917 0.0174132 0.0272971 -0.0341676 0.0188685 0.0272971 -0.03357 0.0199204 0.0272971 -0.0324001 0.019527 0.0272971 -0.0308404 0.0203605 0.0272971 -0.0308897 -0.00165415 0.0274971 -0.0313601 -0.00334914 0.0274971 -0.0322901 -0.00435203 0.0274971 -0.033943 -0.00321083 0.0272971 -0.0324345 -0.0043941 0.0274971 -0.0358759 -0.00346407 0.0274971 -0.0375709 -0.00181114 0.0274971 -0.0385738 -0.00175519 0.0272971 -0.0383818 -0.0190004 0.0272971 -0.0264856 -0.020312 0.0274971 -0.0268665 -0.0214234 0.0274971 -0.0281025 -0.0217459 0.0274971 -0.0288742 -0.0218885 0.0274971 -0.0296984 -0.0208579 0.0274971 -0.0325022 -0.0207134 0.0272971 -0.0323638 -0.0296442 0.0274971 -0.0132468 -0.0315771 0.0274971 -0.0132047 -0.0331338 0.0272971 -0.0142792 -0.0332721 0.0274971 -0.0141347 -0.0343171 0.0274971 -0.0177206 -0.0332426 0.0272971 -0.0192773 -0.033387 0.0274971 -0.0194156 -0.0317341 0.0274971 -0.0204185 -0.0358368 0.0272971 0.00419892 -0.0340074 0.0272971 0.0041591 -0.0375793 0.0274971 0.00346315 -0.0382598 0.0274971 0.00258195 -0.03843 0.0272971 -7.51456e-05 -0.0375498 0.0272971 -0.00167937 -0.0360413 0.0274971 -0.00282058 -0.0359854 0.0272971 -0.00262856 -0.0288827 0.0274971 0.0217449 -0.0325106 0.0274971 0.020857 -0.030768 0.0272971 0.0215927 -0.0323723 0.0272971 0.0207125 -0.0335555 0.0274971 0.0172711 -0.0333613 0.0272971 0.0173187 -0.032481 0.0272971 0.0157145 -0.0309726 0.0274971 0.0145733 -0.0174554 0.0274971 0.0343723 -0.0174225 0.0272971 0.0341751 -0.0188778 0.0272971 0.0335775 -0.018993 0.0274971 0.0337409 -0.019424 0.0274971 0.0333861 -0.0199297 0.0272971 0.0324076 -0.0203698 0.0272971 0.0308972 -0.0205695 0.0274971 0.0309091 -0.0201111 0.0272971 0.0293454 -0.0202961 0.0274971 0.0292695 -0.0192046 0.0272971 0.0280596 0.00174586 0.0272971 0.0383893 -0.00139515 0.0274971 0.0380482 -0.00263698 0.0272971 0.0359845 -0.00282899 0.0274971 0.0360404 -0.00297161 0.0274971 0.0352163 -0.00287106 0.0274971 0.0341075 -0.00267679 0.0272971 0.034155 -0.00194103 0.0274971 0.0324125 0.0172627 0.0274971 0.0335546 0.015706 0.0272971 0.0324801 0.0147569 0.0272971 0.0309157 0.0155973 0.0272971 0.0274821 0.0282352 0.0272971 0.0193935 0.0298394 0.0272971 0.0202738 0.0297918 0.0274971 0.020468 0.0280969 0.0274971 0.019538 0.0274164 0.0274971 0.0186568 0.027094 0.0274971 0.0178851 0.0272462 0.0272971 0.0159997 0.0281264 0.0272971 0.0143955 0.036032 0.0274971 0.00282807 0.035976 0.0272971 0.00263606 0.0343727 0.0274971 0.00292635 0.0340991 0.0274971 0.00287014 0.0318984 0.0272971 0.000961633 0.0314582 0.0272971 -0.000548765 0.0314012 0.0274971 0.000287185 0.0312586 0.0274971 -0.00053694 0.0322892 0.0274971 -0.00334073 0.033998 0.0272971 -0.0041516 0.0309632 0.0274971 -0.0145658 0.0309073 0.0272971 -0.0147578 0.0290303 0.0274971 -0.0145237 0.0290779 0.0272971 -0.014718 0.0263324 0.0274971 -0.0171066 0.0273649 0.0272971 -0.0205962 -0.00878724 0.0290971 0.0324161 -0.00796374 0.0285471 0.0318302 -0.00737493 0.0290971 0.0326517 -0.00705804 0.0285471 0.0322021 -0.00688395 0.0290971 0.0331977 -0.00640339 0.0285471 0.0329302 -0.00612947 0.0285471 0.0338702 -0.00786399 0.0290971 0.0355844 0.0257997 0.0285471 0.0220712 0.0267981 0.0285471 0.022619 0.0268608 0.0290971 0.0237465 0.0268794 0.0290971 0.0246004 0.0274136 0.0285471 0.0247312 0.0268658 0.0285471 0.0257296 0.0346073 0.0285471 0.0104368 0.0355809 0.0285471 0.00984612 0.0351837 0.0290971 0.00946576 0.0355182 0.0290971 0.00895146 0.0355945 0.0290971 0.00871697 0.0356389 0.0290971 0.00822714 0.0355759 0.0290971 0.00786307 0.0354335 0.0290971 0.00752215 0.0333763 0.0285471 0.00621255 0.0343841 0.0290971 0.00672201 0.0349425 0.0290971 0.00697611 0.0355132 0.0285471 0.00673559 0.0329821 0.0285471 -0.0119005 0.0350393 0.0290971 -0.0105909 0.0357938 0.0285471 -0.00991842 0.035124 0.0290971 -0.00916158 0.0347009 0.0290971 -0.00856141 0.0356327 0.0285471 -0.00895266 0.0350686 0.0285471 -0.00815243 0.0342131 0.0285471 -0.0076762 0.00858769 0.0290971 -0.0356203 0.00975795 0.0290971 -0.0347953 0.0102385 0.0285471 -0.0350628 0.0105124 0.0285471 -0.0341228 0.00978726 0.0285471 -0.0323568 -0.00884608 0.0290971 -0.0349471 -0.00852918 0.0285471 -0.0353967 -0.00776166 0.0285471 -0.0327629 -0.00918126 0.0285471 -0.0314864 -0.0250146 0.0290971 -0.0258282 -0.0249241 0.0285471 -0.0263707 -0.0240184 0.0285471 -0.0259988 -0.0237597 0.0290971 -0.0235739 -0.0232509 0.0285471 -0.023365 -0.023815 0.0285471 -0.0225647 -0.0333356 0.0290971 0.00816832 -0.0326563 0.0290971 0.00844725 -0.0323394 0.0285471 0.00799772 -0.0316847 0.0285471 0.00872578 -0.0320806 0.0290971 0.0104226 -0.0314108 0.0285471 0.00966577 -0.0315719 0.0285471 0.0106315 -0.032136 0.0285471 0.0114318 -0.0329915 0.0285471 0.011908 -0.0235936 0.0285471 0.0273972 -0.0237474 0.0290971 0.0268692 -0.0227381 0.0285471 0.026921 -0.0230172 0.0290971 0.0264262 -0.022174 0.0285471 0.0261208 -0.0226827 0.0290971 0.0259119 -0.0220129 0.0285471 0.025155 -0.022562 0.0290971 0.0251875 -0.0229415 0.0285471 0.023487 -0.023068 0.0290971 0.0240933 -0.0239377 0.0290971 0.0236576 -0.0238168 0.0290971 0.0236824 -0.0154198 0.0287471 -0.0247957 -0.0137246 0.0285471 -0.0256158 -0.0118708 0.0287471 -0.0252845 -0.0118151 0.0285471 -0.0254766 -0.0102568 0.0287471 -0.0244194 -0.0101277 0.0285471 -0.0245721 -0.0091347 0.0287471 -0.0229721 -0.0233559 0.0287471 -0.00811807 -0.0259747 0.0285471 -0.010687 -0.0261968 0.0285471 -0.0125886 -0.0254513 0.0287471 -0.0143179 -0.0147546 0.0285471 -0.00557937 -0.0191258 0.0287471 -0.00664251 -0.0191782 0.0285471 -0.00644949 -0.0133845 0.0285471 -0.00568924 -0.0116221 0.0287471 -0.00725742 -0.00776438 0.0287471 -0.0112868 -0.0076511 0.0285471 -0.011122 -0.0064482 0.0287471 -0.0132522 0.0154933 0.0285471 -0.0192785 0.00943693 0.0285471 -0.0126291 0.0151646 0.0287471 -0.0245651 0.0159625 0.0287471 -0.0229168 0.015328 0.0287471 -0.019391 0.00693738 0.0287471 -0.028359 -0.000327294 0.0285471 -0.0293945 -0.00464659 0.0287471 -0.0242799 -0.00466863 0.0285471 -0.0261629 -0.00358106 0.0287471 -0.0277003 -0.00373125 0.0285471 -0.0278323 -0.00211204 0.0287471 -0.0287938 -0.000325099 0.0287471 -0.0291945 -0.0038094 0.0287471 -0.0198788 -0.00484522 0.0285471 -0.0242565 -0.000699064 0.0287471 -0.0139557 -0.00169097 0.0287471 -0.0146385 -0.00183335 0.0285471 -0.014498 0.00580728 0.0285471 -0.0121811 0.0157263 0.0287471 0.00167659 0.0282213 0.0285471 -0.00822161 0.0187047 0.0287471 -0.0161581 0.0185851 0.0285471 -0.0163184 0.0203683 0.0287471 -0.0169236 0.0221995 0.0287471 -0.0169455 0.023881 0.0287471 -0.01622 0.0222388 0.0285471 -0.0171416 0.0239967 0.0285471 -0.0163832 0.0251215 0.0287471 -0.0148729 0.0116399 0.0285471 -0.00883082 0.0120924 0.0287471 -0.00642668 0.0136531 0.0287471 -0.00107108 0.0134537 0.0285471 -0.00105539 0.0137923 0.0285471 0.000178451 0.00727661 0.0285471 0.0188784 0.0104151 0.0287471 0.0245617 0.0102936 0.0285471 0.0247205 0.0234256 0.0285471 0.00794185 0.0257759 0.0287471 0.0107585 0.0259654 0.0285471 0.0106945 0.0259884 0.0287471 0.0125775 0.0261875 0.0285471 0.0125961 0.0191165 0.0287471 0.00665001 0.0233466 0.0287471 0.00812557 0.0147206 0.0287471 0.00578534 0.0124318 0.0287471 0.00638211 0.0114432 0.0285471 0.00715892 0.0123134 0.0285471 0.00622093 0.0134311 0.0287471 0.00588875 0.00764177 0.0285471 0.0111295 0.00621486 0.0285471 0.0144968 0.00643886 0.0287471 0.0132597 0.00674252 0.0285471 0.0120396 -0.0153373 0.0287471 0.0193985 -0.0155027 0.0285471 0.019286 -0.0127099 0.0285471 0.0157468 -0.00944627 0.0285471 0.0126366 -0.0159719 0.0287471 0.0229243 -0.0161661 0.0285471 0.0229721 -0.0162265 0.0285471 0.0210585 -0.00694672 0.0287471 0.0283665 -0.0137741 0.0287471 0.0257534 0.00253517 0.0285471 0.0155691 0.00463726 0.0287471 0.0242874 0.00483589 0.0285471 0.024264 -0.000484297 0.0287471 0.0136954 0.00182401 0.0285471 0.0145055 -0.00581662 0.0285471 0.0121886 -0.00705445 0.0285471 0.0118649 -0.00931886 0.0287471 0.0127907 -0.00832427 0.0285471 0.0120216 -0.00817565 0.0287471 0.0121852 -0.00706774 0.0287471 0.0120645 -0.0199912 0.0285471 -0.00312778 -0.0156658 0.0285471 -0.00185651 -0.0290518 0.0285471 -0.000924217 -0.027838 0.0287471 -0.00236399 -0.0279765 0.0285471 -0.00250829 -0.0291892 0.0287471 0.000953895 -0.0282306 0.0285471 0.00822911 -0.02203 0.0287471 0.016985 -0.0220611 0.0285471 0.0171826 -0.0251309 0.0287471 0.0148804 -0.0122148 0.0285471 0.009986 -0.0121018 0.0287471 0.00643418 -0.0117467 0.0287471 0.00758484 -0.0118421 0.0287471 0.00878525 -0.0116492 0.0285471 0.00883831 -0.0119252 0.0285471 0.0063403 -0.0134631 0.0285471 0.00106289 -0.0147064 0.0287471 -0.00104395 -0.0139811 0.0287471 -8.26822e-05 -0.0145723 0.0285471 -0.0011923 -0.0136624 0.0287471 0.00107858 -0.0138016 0.0285471 -0.000170952 0.0178207 0.0272971 -0.0272869 0.0159437 0.0274971 -0.0270528 0.0142487 0.0274971 -0.0279828 0.014387 0.0272971 -0.0281273 0.0132458 0.0274971 -0.0296358 0.013398 0.0272971 -0.0315211 0.0142783 0.0272971 -0.0331254 -0.00334914 0.0285471 -0.0322901 -0.00346407 0.0285471 -0.0375709 -0.019205 0.0274971 -0.033505 -0.020536 0.0285471 -0.0328011 -0.0206573 0.0285471 -0.0326965 -0.0216151 0.0274971 -0.031338 -0.0216151 0.0285471 -0.031338 -0.0217879 0.0274971 -0.0308072 -0.0214234 0.0285471 -0.0281025 -0.020743 0.0274971 -0.0272213 -0.020312 0.0285471 -0.0268665 -0.019048 0.0274971 -0.0262913 -0.0187744 0.0285471 -0.0262351 -0.0171151 0.0285471 -0.0263334 -0.0317341 0.0285471 -0.0204185 -0.0343171 0.0285471 -0.0177206 -0.034275 0.0274971 -0.0157877 -0.034275 0.0285471 -0.0157877 -0.0360413 0.0285471 -0.00282058 -0.0374937 0.0285471 -0.00201208 -0.0376943 0.0274971 -0.00181769 -0.0384514 0.0274971 -0.000653488 -0.0386243 0.0274971 -0.000122694 -0.0387248 0.0285797 0.000986102 -0.0387248 0.0274971 0.000986102 -0.0386801 0.0285471 0.00138196 -0.0382598 0.0285471 0.00258195 -0.0385822 0.0274971 0.00181023 -0.0371484 0.0274971 0.00381799 -0.0356107 0.0285471 0.0044494 -0.0358843 0.0274971 0.00439318 -0.0339514 0.0274971 0.00435112 -0.033366 0.0285471 0.0196179 -0.0335135 0.0285471 0.0192041 -0.0335135 0.0274971 0.0192041 -0.0326255 0.0274971 0.0155761 -0.0308156 0.0274971 0.021787 -0.0288827 0.0285471 0.0217449 -0.017886 0.0285471 0.0271024 -0.0193383 0.0274971 0.0279109 -0.0195389 0.0285471 0.0281053 -0.0195389 0.0274971 0.0281053 -0.0204689 0.0274971 0.0298003 -0.017729 0.0274971 0.0343161 -0.017729 0.0285471 0.0343161 -0.019424 0.0285471 0.0333861 -0.0201044 0.0274971 0.0325049 -0.0204269 0.0274971 0.0317332 -0.00297161 0.0285471 0.0352163 -0.00174046 0.0285471 0.0322181 -0.00269819 0.0274971 0.0335767 -0.000288102 0.0274971 0.0314096 -0.00250656 0.0274971 0.0368121 -0.00139515 0.0285471 0.0380482 -0.0018261 0.0274971 0.0376933 -0.00013111 0.0274971 0.0386234 0.00137355 0.0285471 0.0386792 0.0155677 0.0274971 0.0326246 0.0145648 0.0285471 0.0309717 0.0145228 0.0285471 0.0290387 0.0145648 0.0274971 0.0309717 0.0145228 0.0274971 0.0290387 0.0154528 0.0274971 0.0273437 0.0171057 0.0285471 0.0263409 0.0300654 0.0285471 0.0205242 0.0317248 0.0274971 0.020426 0.0274164 0.0285471 0.0186568 0.0285278 0.0285471 0.0198928 0.0285278 0.0274971 0.0198928 0.0269513 0.0274971 0.0170609 0.0270519 0.0274971 0.0159521 0.0272248 0.0274971 0.0154214 0.0279819 0.0274971 0.0142572 0.036032 0.0285471 0.00282807 0.032835 0.0274971 0.00229495 0.0314012 0.0285471 0.000287185 0.0317236 0.0274971 0.00105891 0.0324041 0.0274971 0.00194011 0.0313591 0.0274971 -0.00164574 0.0313591 0.0285471 -0.00164574 0.031532 0.0274971 -0.00217653 0.0322892 0.0285471 -0.00334073 0.0324897 0.0274971 -0.00353512 0.0339421 0.0285471 -0.00434362 0.0339421 0.0274971 -0.00434362 0.0273353 0.0285471 -0.0154537 0.0273353 0.0274971 -0.0154537 0.0262904 0.0285471 -0.0190396 0.0262904 0.0274971 -0.0190396 0.0272204 0.0285471 -0.0207346 0.0272204 0.0274971 -0.0207346 0.0288733 0.0285471 -0.0217375 0.0384421 0.0285471 0.000660987 -0.0384514 0.0285471 -0.000653488 -0.0367936 0.0285471 -0.0095194 0.01908 0.0285471 -0.0336632 0.0244223 0.0285471 -0.0300131 0.0259092 0.0285471 -0.0277917 -0.0138684 0.0285471 0.0259297 0.0256163 0.0285471 0.0144235 0.0244432 0.0285471 0.00378427 -0.00165415 0.0285471 -0.0313601 -0.00984704 0.0285471 0.0355894 -0.00884865 0.0285471 0.0361372 -0.00768418 0.0285471 0.0379341 -0.00771011 0.0285471 0.0361124 -0.00367287 0.0285471 0.0385295 -0.00685464 0.0285471 0.0356362 -0.0104625 0.0285471 0.0334772 -0.00629051 0.0285471 0.0348359 -0.00699426 0.0285471 0.0285608 -0.00991473 0.0285471 0.0324788 0.026849 0.0285471 0.0278708 0.0273888 0.0285471 0.0235926 0.0230805 0.0285471 0.0243382 0.0233545 0.0285471 0.0252782 0.0212317 0.0285471 0.0203354 0.00698493 0.0285471 -0.0285533 0.0138591 0.0285471 -0.0259222 0.00893179 0.0285471 -0.0318806 0.0103514 0.0285471 -0.0331571 0.00779325 0.0285471 -0.0318558 0.0114544 0.0285471 -0.0351017 0.0110308 0.0285471 -0.0370895 0.00767485 0.0285471 -0.0379266 0.00958386 0.0285471 -0.0357909 0.00867816 0.0285471 -0.0361628 0.00770078 0.0285471 -0.0361049 -0.0108319 0.0285471 -0.0371508 -0.00943489 0.0285471 -0.0357686 -0.00832579 0.0285471 -0.0319626 -0.00435203 0.0285471 -0.033943 -0.0043941 0.0285471 -0.0358759 -0.00760061 0.0285471 -0.0337286 -0.0246705 0.0285471 -0.0220885 -0.0274229 0.0285471 -0.0247237 -0.0268583 0.0285471 -0.0278633 -0.0230899 0.0285471 -0.0243307 -0.0233638 0.0285471 -0.0252707 -0.0238472 0.0285471 0.0231151 -0.0204689 0.0285471 0.0298003 -0.0222868 0.0285471 0.024215 -0.0260785 0.0285471 0.0211739 -0.0277106 0.0285471 0.0216495 -0.0263212 0.0285471 0.0259006 -0.00625266 0.0285471 -0.0132102 -0.0062242 0.0285471 -0.0144893 -0.0114525 0.0285471 -0.00715142 -0.00160063 0.0285471 -0.00547293 -0.00675186 0.0285471 -0.0120321 -0.0315413 0.0285471 0.00218403 -0.0312679 0.0285471 0.000544439 -0.0313199 0.0285471 0.0031876 -0.0293891 0.0285471 0.000960403 -0.031733 0.0285471 -0.00105141 -0.0263495 0.0285471 -0.00351741 -0.0249977 0.0285471 -0.00904048 -0.023435 0.0285471 -0.00793435 -0.0244526 0.0285471 -0.00377677 -0.0122838 0.0285471 -0.0062424 -0.0281062 0.0285471 -0.0195305 -0.032747 0.0285471 -0.020627 -0.033387 0.0285471 -0.0194156 -0.0367328 0.0285471 -0.0121918 -0.0351615 0.0285471 -0.00999501 -0.0273982 0.0285471 -0.0235852 -0.0256256 0.0285471 -0.014416 -0.0285286 0.0285471 -0.0234502 -0.0332721 0.0285471 -0.0141347 -0.0315771 0.0285471 -0.0132047 -0.0296442 0.0285471 -0.0132468 -0.0279913 0.0285471 -0.0142497 -0.021241 0.0285471 -0.0203279 -0.0155254 0.0285471 -0.0249656 -0.0154621 0.0285471 -0.0273362 -0.0054422 0.0285471 -0.0186555 -0.00728594 0.0285471 -0.0188709 -0.00895459 0.0285471 -0.023059 -0.0103198 0.0285471 -0.0314616 -0.0119089 0.0285471 -0.0329831 0.00822227 0.0285471 -0.0119857 -0.00254451 0.0285471 -0.0155616 -0.000779443 0.0285471 -0.0137726 0.000467962 0.0285471 -0.013488 -0.00853711 0.0285471 -0.029276 -0.00400275 0.0285471 -0.0198276 -0.00219546 0.0285471 -0.0289755 0.00173113 0.0285471 -0.0322106 0.00511793 0.0285471 -0.0332552 0.0122054 0.0285471 -0.0099785 0.0151708 0.0285471 -0.0133744 0.0127006 0.0285471 -0.0157393 0.0203244 0.0285471 -0.0171187 0.0162172 0.0285471 -0.021051 0.0161568 0.0285471 -0.0229646 0.0145629 0.0285471 0.0011998 0.00699678 0.0285471 -0.011861 0.0115386 0.0285471 -0.00755538 0.0119158 0.0285471 -0.0063328 0.0185868 0.0285471 -0.0256579 0.0252936 0.0285471 -0.0149748 0.0263324 0.0285471 -0.0171066 0.0236323 0.0285471 0.00668765 0.0276698 0.0285471 0.00551107 0.0147453 0.0285471 0.00558687 0.0156565 0.0285471 0.00186401 0.0134686 0.0285471 0.00567095 0.00895791 0.0285471 0.00333371 0.0191688 0.0285471 0.00645699 0.0199819 0.0285471 0.00313528 0.015516 0.0285471 0.0249731 0.0143746 0.0285471 0.0254826 0.0122432 0.0285471 0.0255882 0.00624332 0.0285471 0.0132177 0.00852778 0.0285471 0.0292835 0.00894526 0.0285471 0.0230665 -0.00577531 0.0285471 0.00762714 -0.000477295 0.0285471 0.0134955 0.000770109 0.0285471 0.0137801 0.00399342 0.0285471 0.0198351 0.00364079 0.0285471 0.0125134 -0.000288102 0.0285471 0.0314096 0.000317961 0.0285471 0.029402 0.00340883 0.0285471 0.0281626 0.00668346 0.0285471 0.0229545 0.00458718 0.0285471 0.0263835 -0.0115479 0.0285471 0.00756288 -0.00896724 0.0285471 -0.00332622 -0.0151801 0.0285471 0.0133819 -0.0185944 0.0285471 0.0163259 0.0309632 0.0285471 -0.0145658 0.0314855 0.0285471 -0.00917284 0.0320762 0.0285471 -0.00819923 0.0339595 0.0285471 -0.0119584 0.0348652 0.0285471 -0.0115865 0.0355199 0.0285471 -0.0108584 0.0383413 0.0285471 -0.00521886 0.0330746 0.0285471 -0.00765142 0.030896 0.0285471 -0.0232951 0.0320703 0.0285471 -0.0212043 0.0132458 0.0285471 -0.0296358 0.0153225 0.0285471 -0.0246878 0.0178767 0.0285471 -0.0270949 0.016529 0.0285471 -0.0349866 0.0141338 0.0285471 -0.0332637 0.0140456 0.0285471 -0.0360557 -0.000310341 0.0285471 -0.038695 -0.00015182 0.0285471 -0.0386721 0.00249723 0.0285471 -0.0368046 -0.00787453 0.0285471 -0.0346686 -0.00181114 0.0285471 -0.0385738 -0.00162564 0.0285471 -0.0386623 -0.00138288 0.0285471 -0.0386717 -0.0196188 0.0285471 -0.0333575 -0.019409 0.0285471 -0.03348 -0.0113859 0.0285471 -0.03512 -0.0172721 0.0285471 -0.0335471 -0.0155771 0.0285471 -0.0326171 -0.0237948 0.0285471 -0.0305203 -0.0218885 0.0285471 -0.0296984 -0.0221922 0.0285471 -0.0252967 -0.0328444 0.0285471 -0.00228745 -0.034382 0.0285471 -0.00291885 -0.0385842 0.0285471 -0.00304777 -0.0357439 0.0285471 0.00927281 -0.0351284 0.0285471 0.011385 -0.0355832 0.0285471 0.0152306 -0.0351533 0.0285471 0.0161983 -0.0309726 0.0285471 0.0145733 -0.0381934 0.0285471 0.00627358 -0.0332451 0.0285471 0.00762581 -0.0297829 0.0285471 0.0144269 -0.0290397 0.0285471 0.0145312 -0.028128 0.0285471 0.014141 -0.025303 0.0285471 0.0149823 -0.023928 0.0285471 0.0164448 -0.0371484 0.0285471 0.00381799 -0.0326255 0.0285471 0.0155761 -0.0335555 0.0285471 0.0172711 -0.0325106 0.0285471 0.020857 -0.0272297 0.0285471 0.0207421 -0.0308156 0.0285471 0.021787 -0.0204269 0.0285471 0.0317332 -0.0165384 0.0285471 0.0349941 -0.0157961 0.0285471 0.0342741 -0.0110401 0.0285471 0.037097 -0.0104378 0.0285471 0.0346158 -0.0163507 0.0285471 0.0183391 -0.0162267 0.0285471 0.0270041 -0.0153319 0.0285471 0.0246953 -0.014689 0.0285471 0.0276355 -0.0135776 0.0285471 0.0288715 -0.0131126 0.0285471 0.0304674 -0.013308 0.0285471 0.0287803 -0.0114637 0.0285471 0.0351092 -0.0143437 0.0285471 0.0334656 0.000301008 0.0285471 0.0387025 0.000142487 0.0285471 0.0386796 -0.00269819 0.0285471 0.0335767 -0.00512726 0.0285471 0.0332627 -0.00250656 0.0285471 0.0368121 0.00155444 0.0285471 0.0292186 0.00333981 0.0285471 0.0322976 0.0043427 0.0285471 0.0339505 0.0155677 0.0285471 0.0326246 0.0154528 0.0285471 0.0273437 0.0193996 0.0285471 0.0334875 0.0108226 0.0285471 0.0371583 0.0172627 0.0285471 0.0335546 0.0221828 0.0285471 0.0253042 0.0281825 0.0285471 0.0140628 0.0272248 0.0285471 0.0154214 0.026675 0.0285471 0.0171288 0.0269513 0.0285471 0.0170609 0.0285193 0.0285471 0.0234577 0.0323177 0.0285471 0.0212865 0.0317248 0.0285471 0.020426 0.0327377 0.0285471 0.0206345 0.0358632 0.0285471 0.014536 0.0361288 0.0285471 0.00884773 0.0367235 0.0285471 0.0121993 0.036104 0.0285471 0.0077092 0.0345149 0.0285471 0.00618778 0.0325209 0.0285471 0.00668878 0.0317957 0.0285471 0.00845477 0.0249883 0.0285471 0.00904798 0.0320696 0.0285471 0.00939477 0.0312942 0.0285471 0.013156 0.0328318 0.0285471 0.0137874 0.03363 0.0285471 0.0104947 0.0290303 0.0285471 -0.0145237 0.0297736 0.0285471 -0.0144194 0.0278274 0.0285471 0.00264449 0.0324041 0.0285471 0.00194011 0.0349922 0.0285471 0.00337725 0.0340991 0.0285471 0.00287014 0.0386256 0.0285471 0.00232654 0.0386708 0.0285471 -0.00137446 0.035144 0.0285471 -0.0161908 0.0336468 0.0285471 -0.0183724 0.0015913 0.0285471 0.00548043 0.00576598 0.0285471 -0.00761964 0.0178767 0.0274971 -0.0270949 0.0159437 0.0285471 -0.0270528 0.0142487 0.0285471 -0.0279828 0.0132038 0.0285471 -0.0315687 0.0132038 0.0274971 -0.0315687 0.0141338 0.0274971 -0.0332637 0.0157867 0.0285471 -0.0342666 0.00161631 0.0285471 0.0386698 0.00162468 0.0287471 0.0388696 -0.0245579 0.0287471 0.0301757 -0.0190893 0.0285471 0.0336707 -0.0166238 0.0287471 0.035175 -0.0181488 0.0285471 0.0341868 -0.0244317 0.0285471 0.0300206 -0.0257583 0.0285471 0.0288905 -0.0328095 0.0285471 0.020535 -0.0309054 0.0285471 0.0233026 -0.0387035 0.0285471 0.000309424 -0.0383506 0.0285471 0.00522636 -0.0341877 0.0285471 -0.0181404 -0.0292392 0.0285471 -0.0253544 -0.0336716 0.0285471 -0.0190809 -0.0195093 0.0287471 -0.0336531 -0.0180011 0.0285471 -0.0342573 -0.0108879 0.0287471 -0.0373428 0.0168561 0.0384971 -0.0307806 0.016906 0.0384971 -0.0306096 0.0169316 0.0384971 -0.0306563 0.0167629 0.0384971 -0.0307572 0.0167365 0.0384971 -0.0307198 0.0298495 0.0384971 -0.0182281 0.0299471 0.0384971 -0.0180528 0.0299014 0.0384971 -0.0180501 0.0298284 0.0384971 -0.0181016 0.0300182 0.0384971 -0.0181271 0.0299427 0.0384971 -0.0182515 0.0350613 0.0384971 -0.000686635 0.0350158 0.0384971 -0.000659014 0.0350115 0.0384971 -0.000857686 0.0348844 0.0384971 -0.000751689 0.030651 0.0384971 0.0167414 0.030581 0.0384971 0.0168689 0.0306554 0.0384971 0.01694 0.0307825 0.0384971 0.016834 0.0182534 0.0384971 0.0299206 0.0180508 0.0384971 0.0299022 0.000654169 0.0384971 0.0350015 0.000661699 0.0384971 0.0349564 0.000688076 0.0384971 0.034919 0.000831156 0.0384971 0.0350666 -0.0169437 0.0384971 0.0306943 -0.0169003 0.0384971 0.0307723 -0.0168579 0.0384971 0.0307897 -0.0169309 0.0384971 0.0307383 -0.0169362 0.0384971 0.0306491 -0.0168122 0.0384971 0.030787 -0.0167423 0.0384971 0.0306594 -0.0168166 0.0384971 0.0305883 -0.0299107 0.0384971 0.0180576 -0.0298377 0.0384971 0.0181091 -0.0298249 0.0384971 0.018153 -0.0298588 0.0384971 0.0182356 -0.0299988 0.0384971 0.0182334 -0.0348965 0.0384971 0.000789726 -0.0350133 0.0384971 0.000866734 -0.0349252 0.0384971 0.000690969 -0.0350652 0.0384971 0.00068878 -0.0348976 0.0384971 0.000736491 -0.0350915 0.0384971 0.000726197 -0.0306722 0.0384971 -0.0169341 -0.0307634 0.0384971 -0.0169037 -0.0306204 0.0384971 -0.0167561 -0.0307603 0.0384971 -0.0167583 -0.0180857 0.0384971 -0.0298481 -0.0182312 0.0384971 -0.0298449 -0.0182599 0.0384971 -0.0299437 -0.0181356 0.0384971 -0.0300191 -0.000691886 0.0384971 -0.0349168 -0.000868872 0.0384971 -0.0349819 -0.000856064 0.0384971 -0.0349379 -0.000861342 0.0384971 -0.035027 -0.000825455 0.0384971 -0.0349039 -0.000695051 0.0384971 -0.0350623 -0.000741732 0.0384971 -0.0350879 -0.0196181 0.0795971 0.0263459 -0.0189755 0.0795971 0.026453 -0.0189061 0.0795971 0.0276249 -0.0192845 0.0795971 0.0263261 -0.0201288 0.0795971 0.0272767 -0.0195865 0.0795971 0.0277958 -0.019198 0.0795971 0.0277874 -0.0187521 0.0795971 0.0267015 -0.0186586 0.0795971 0.0270222 -0.0187136 0.0795971 0.0273518 -0.0199272 0.0795971 0.0276089 -0.019408 0.0800481 0.0270666 -0.0199503 0.0795971 0.0265475 -0.0201372 0.0795971 0.0268882 0.0315554 0.0795971 0.0120413 0.0308994 0.0800481 0.0124065 0.0316488 0.0795971 0.0123621 0.0315939 0.0795971 0.0126916 0.0303803 0.0795971 0.0129487 0.0306894 0.0795971 0.0116857 0.0307209 0.0795971 0.0131357 0.0310229 0.0795971 0.011666 0.031332 0.0795971 0.0117929 0.0314014 0.0795971 0.0129647 0.0311095 0.0795971 0.0131272 0.0303572 0.0795971 0.0118873 0.0301787 0.0795971 0.0126165 0.0301702 0.0795971 0.012228 -0.0613427 0.0417971 0.0468443 -0.0631951 0.0417971 0.0443136 -0.0620173 0.0417971 0.0453948 -0.0620173 0.0665971 0.0453948 -0.0631951 0.0665971 0.0443136 -0.0622817 0.0665971 0.0455884 -0.0622817 0.0417971 0.0455884 -0.0613427 0.0665971 0.0468443 -0.0306578 0.0665971 0.0704979 -0.0317851 0.0665971 0.0700675 -0.0330623 0.0665971 0.0697431 -0.0330623 0.0417971 0.0697431 -0.0297047 0.0417971 0.0712379 -0.0317851 0.0417971 0.0700675 -0.0306578 0.0417971 0.0704979 -0.0297047 0.0665971 0.0712379 -0.0420276 0.0665971 0.0644476 -0.0410679 0.0417971 0.0653505 -0.0429962 0.0417971 0.063728 -0.0441323 0.0665971 0.0633215 -0.0429962 0.0665971 0.063728 -0.0441323 0.0417971 0.0633215 -0.0420276 0.0417971 0.0644476 -0.0410679 0.0665971 0.0653505 -0.00656149 0.0665971 0.0769024 -0.00499771 0.0665971 0.0770197 -0.00343187 0.0665971 0.0771053 -0.00499771 0.0417971 0.0770197 -0.00497651 0.0417971 0.0766928 -0.00656149 0.0417971 0.0769024 -0.00497651 0.0665971 0.0766928 -0.00343187 0.0417971 0.0771053 0.0453864 0.0417971 0.0620164 0.0443052 0.0665971 0.0631941 0.0453864 0.0665971 0.0620164 0.0468359 0.0665971 0.0613418 0.0443052 0.0417971 0.0631941 0.0468359 0.0417971 0.0613418 0.04558 0.0665971 0.0622808 0.04558 0.0417971 0.0622808 0.0700591 0.0417971 0.0317842 0.0712295 0.0665971 0.0297038 0.0704895 0.0665971 0.0306569 0.0700591 0.0665971 0.0317842 0.0697347 0.0665971 0.0330614 0.0697347 0.0417971 0.0330614 0.0712295 0.0417971 0.0297038 0.0704895 0.0417971 0.0306569 0.0633131 0.0665971 0.0441314 0.0637195 0.0665971 0.0429953 0.0637195 0.0417971 0.0429953 0.0644391 0.0665971 0.0420267 0.0653421 0.0665971 0.0410669 0.0653421 0.0417971 0.0410669 0.0644391 0.0417971 0.0420267 0.0633131 0.0417971 0.0441314 0.076894 0.0665971 0.00656057 0.0766843 0.0665971 0.00497559 0.0770968 0.0665971 0.00343095 0.0770113 0.0665971 0.00499679 0.0770113 0.0417971 0.00499679 0.0766843 0.0417971 0.00497559 0.076894 0.0417971 0.00656057 0.0770968 0.0417971 0.00343095 0.0302694 0.0384971 0.00602654 0.0308256 0.0384971 0.00625494 0.0312277 0.0384971 0.00670205 0.0313959 0.0384971 0.00727933 0.0291128 0.0384971 0.00833512 0.0296692 0.0384971 0.00606209 0.031297 0.0384971 0.00787242 0.0309505 0.0384971 0.00836387 0.0304252 0.0384971 0.00865633 0.02875 0.0384971 0.0077372 0.0290713 0.0384971 0.00642487 0.0287348 0.0384971 0.007038 0.029726 0.0384971 0.00867154 0.0300472 0.0376853 0.00735921 -0.0210226 0.0384971 0.0236488 -0.0200519 0.0384971 0.0222718 -0.0201508 0.0384971 0.0228649 -0.0206221 0.0384971 0.0212474 -0.0226977 0.0384971 0.0227297 -0.0223349 0.0384971 0.0233276 -0.0202201 0.0384971 0.0216945 -0.0204972 0.0384971 0.0233563 -0.0217786 0.0384971 0.0210546 -0.0211784 0.0384971 0.021019 -0.0227129 0.0384971 0.0220305 -0.0223765 0.0384971 0.0214173 -0.0214006 0.0376853 0.0223517 -0.0217218 0.0384971 0.023664 0.0579028 0.0400971 -0.00929915 0.0579028 0.0390471 -0.00929915 0.0565011 0.0390471 -0.0157099 0.056521 0.0390471 -0.0156382 0.056521 0.0387471 -0.0156382 0.0565881 0.0390471 -0.0155849 0.0565881 0.0400971 -0.0155849 0.057891 0.0390471 -0.00937268 0.057891 0.0387471 -0.00937268 0.0584522 0.0387471 -0.0116015 0.0584522 0.0400971 -0.0116015 0.0579613 0.0387471 -0.0138469 0.0572917 0.0387471 -0.0125242 0.0565011 0.0400971 -0.0157099 0.0579297 0.0390471 -0.00944908 0.0579297 0.0400971 -0.00944908 0.0579613 0.0400971 -0.0138469 0.058645 0.0390471 0.00019232 0.0582738 0.0390471 0.00659508 0.0582654 0.0390471 0.00666909 0.0583317 0.0390471 0.00653196 0.0583317 0.0400971 0.00653196 0.058645 0.0387471 0.00019232 0.0595486 0.0387471 0.0023057 0.0582738 0.0387471 0.00659508 0.0594156 0.0387471 0.0046003 0.0594156 0.0400971 0.0046003 0.058547 0.0387471 0.00339878 0.0586952 0.0390471 0.000261703 0.0586452 0.0400971 0.000117837 0.0595486 0.0400971 0.0023057 0.0586952 0.0400971 0.000261703 0.0582654 0.0400971 0.00666909 0.0586452 0.0390471 0.000117837 0.0564489 0.0400971 0.0160892 0.0544071 0.0400971 0.0220288 0.0564395 0.0390471 0.0159372 0.0564193 0.0390471 0.0160088 0.0543343 0.0390471 0.022074 0.0564395 0.0400971 0.0159372 0.0543063 0.0400971 0.022143 0.0543063 0.0390471 0.022143 0.055972 0.0400971 0.0204612 0.0544071 0.0390471 0.0220288 0.0543343 0.0387471 0.022074 0.055972 0.0387471 0.0204612 0.0567192 0.0387471 0.0182876 0.0567192 0.0400971 0.0182876 0.0554598 0.0387471 0.0190699 0.0564193 0.0387471 0.0160088 0.0564489 0.0390471 0.0160892 0.0463192 0.0400971 0.0359749 0.048259 0.0387471 0.033327 0.0500088 0.0390471 0.0306383 0.0464471 0.0390471 0.0358922 0.0464471 0.0400971 0.0358922 0.0500088 0.0387471 0.0306383 0.0500156 0.0390471 0.0307237 0.0483769 0.0400971 0.0348049 0.0496828 0.0387471 0.0329135 0.0496828 0.0400971 0.0329135 0.0463648 0.0387471 0.0359161 0.0483769 0.0387471 0.0348049 0.0500477 0.0400971 0.0305748 0.0500477 0.0390471 0.0305748 0.0463192 0.0390471 0.0359749 0.0463648 0.0390471 0.0359161 0.0500156 0.0400971 0.0307237 0.0398891 0.0387471 0.0429958 0.0374787 0.0387471 0.0451127 0.0349563 0.0390471 0.0470947 0.0399436 0.0400971 0.0429451 0.0348965 0.0400971 0.047139 0.0348965 0.0390471 0.047139 0.0350419 0.0400971 0.0470939 0.0398891 0.0390471 0.0429958 0.0349563 0.0387471 0.0470947 0.0371935 0.0387471 0.0465676 0.0389613 0.0400971 0.0450986 0.0398726 0.0400971 0.0430798 0.0389613 0.0387471 0.0450986 0.0398726 0.0390471 0.0430798 0.0399436 0.0390471 0.0429451 0.0350419 0.0390471 0.0470939 0.0371935 0.0400971 0.0465676 0.0268768 0.0390471 0.0521306 0.0268768 0.0400971 0.0521306 0.0268106 0.0390471 0.0521647 0.0268106 0.0387471 0.0521647 0.0267721 0.0390471 0.0522412 0.0209549 0.0390471 0.0547808 0.0209549 0.0387471 0.0547808 0.0253499 0.0400971 0.0539393 0.0232513 0.0387471 0.0548768 0.0239185 0.0387471 0.0535528 0.0253499 0.0387471 0.0539393 0.0267721 0.0400971 0.0522412 0.0210375 0.0390471 0.0548031 0.0208853 0.0390471 0.0548073 0.0208853 0.0400971 0.0548073 0.0232513 0.0400971 0.0548768 0.0210375 0.0400971 0.0548031 0.0118163 0.0400971 0.0574501 0.0053248 0.0390471 0.0584111 0.00539897 0.0390471 0.0584043 0.0117433 0.0390471 0.0574651 0.0117433 0.0387471 0.0574651 0.009858 0.0387471 0.0587798 0.0116856 0.0390471 0.0575284 0.00547254 0.0390471 0.0584481 0.00758433 0.0387471 0.0591164 0.00758433 0.0400971 0.0591164 0.009858 0.0400971 0.0587798 0.00539897 0.0387471 0.0584043 0.008584 0.0387471 0.0580215 0.0053248 0.0400971 0.0584111 0.0116856 0.0400971 0.0575284 0.00547254 0.0400971 0.0584481 0.0118163 0.0390471 0.0574501 -0.010631 0.0390471 0.0576831 -0.010631 0.0400971 0.0576831 -0.0105577 0.0390471 0.0576965 -0.00636531 0.0400971 0.0592611 -0.00864548 0.0400971 0.0589718 -0.0104987 0.0400971 0.0577586 -0.0041209 0.0390471 0.0585091 -0.00419519 0.0390471 0.0585039 -0.0105577 0.0387471 0.0576965 -0.00419519 0.0387471 0.0585039 -0.00426784 0.0390471 0.0585492 -0.0104987 0.0390471 0.0577586 -0.00864548 0.0387471 0.0589718 -0.00738749 0.0387471 0.0581872 -0.00636531 0.0387471 0.0592611 -0.00426784 0.0400971 0.0585492 -0.0041209 0.0400971 0.0585091 -0.0198229 0.0390471 0.0552039 -0.0257986 0.0400971 0.0526772 -0.0257986 0.0390471 0.0526772 -0.0199051 0.0390471 0.055228 -0.0257317 0.0387471 0.0527099 -0.0257317 0.0390471 0.0527099 -0.0242344 0.0387471 0.0544538 -0.0256916 0.0390471 0.0527856 -0.0242344 0.0400971 0.0544538 -0.0221169 0.0400971 0.0553476 -0.0228114 0.0387471 0.0540378 -0.0221169 0.0387471 0.0553476 -0.0198229 0.0387471 0.0552039 -0.0197528 0.0400971 0.055229 -0.0199051 0.0400971 0.055228 -0.0256916 0.0400971 0.0527856 -0.0197528 0.0390471 0.055229 -0.0389976 0.0390471 0.0438144 -0.0390532 0.0390471 0.0437648 -0.0362285 0.0400971 0.0473295 -0.0340665 0.0400971 0.0478111 -0.0389794 0.0400971 0.0438981 -0.0390532 0.0400971 0.0437648 -0.0339201 0.0390471 0.0478531 -0.0339201 0.0400971 0.0478531 -0.0389976 0.0387471 0.0438144 -0.0339809 0.0390471 0.04781 -0.0340665 0.0390471 0.0478111 -0.0339809 0.0387471 0.04781 -0.0389794 0.0390471 0.0438981 -0.0380264 0.0400971 0.0458976 -0.0362285 0.0387471 0.0473295 -0.0380264 0.0387471 0.0458976 -0.0365439 0.0387471 0.0458808 -0.045572 0.0400971 0.0369285 -0.0494118 0.0390471 0.0316069 -0.0475664 0.0387471 0.0343214 -0.0493716 0.0387471 0.0316696 -0.0493716 0.0390471 0.0316696 -0.0493767 0.0390471 0.0317551 -0.0489984 0.0400971 0.0339376 -0.0476536 0.0400971 0.0358015 -0.0476536 0.0387471 0.0358015 -0.0489984 0.0387471 0.0339376 -0.0456189 0.0387471 0.0368706 -0.0457016 0.0400971 0.0368485 -0.045572 0.0390471 0.0369285 -0.0493767 0.0400971 0.0317551 -0.0494118 0.0400971 0.0316069 -0.0456189 0.0390471 0.0368706 -0.0457016 0.0390471 0.0368485 -0.0550615 0.0387471 0.0202168 -0.053874 0.0390471 0.0231969 -0.0560843 0.0387471 0.0171763 -0.0538445 0.0390471 0.0232653 -0.0538445 0.0400971 0.0232653 -0.0561061 0.0400971 0.0171051 -0.0561061 0.0390471 0.0171051 -0.0539477 0.0390471 0.0231533 -0.0539477 0.0400971 0.0231533 -0.0560843 0.0390471 0.0171763 -0.0561123 0.0390471 0.0172573 -0.0563369 0.0387471 0.0194608 -0.0555447 0.0400971 0.0216185 -0.0555447 0.0387471 0.0216185 -0.053874 0.0387471 0.0231969 -0.0563369 0.0400971 0.0194608 -0.0561123 0.0400971 0.0172573 -0.0310322 0.0795971 -0.0116585 -0.0315647 0.0795971 -0.0120338 -0.0313413 0.0795971 -0.0117854 -0.0311188 0.0795971 -0.0131197 -0.0309088 0.0800481 -0.012399 -0.0316032 0.0795971 -0.0126841 -0.0303896 0.0795971 -0.0129412 -0.030188 0.0795971 -0.012609 -0.0306987 0.0795971 -0.0116782 -0.0301796 0.0795971 -0.0122205 -0.0307303 0.0795971 -0.0131282 -0.0303665 0.0795971 -0.0118798 -0.0314107 0.0795971 -0.0129572 -0.0316582 0.0795971 -0.0123546 0.0191887 0.0795971 -0.0277799 0.0195222 0.0795971 -0.0277996 0.0201481 0.0795971 -0.0271035 0.0198312 0.0795971 -0.0276727 0.0200931 0.0795971 -0.026774 0.0200546 0.0795971 -0.0274243 0.0199006 0.0795971 -0.0265009 0.0188795 0.0795971 -0.0265169 0.0196087 0.0795971 -0.0263384 0.018678 0.0795971 -0.0268491 0.0186695 0.0795971 -0.0272376 0.0193987 0.0800481 -0.0270591 0.0192202 0.0795971 -0.0263299 0.0188564 0.0795971 -0.0275783 0.000123162 0.0795971 -0.0508786 0.00100051 0.0799471 -0.0507323 0.00130551 0.0799471 -0.0503931 0.00100051 0.0795971 -0.0507323 0.00130551 0.0795971 -0.0503931 0.00143314 0.0799471 -0.0499551 0.0013581 0.0799471 -0.0495052 0.00109527 0.0795971 -0.0491323 0.000578532 0.0799471 -0.0509056 0.00109527 0.0799471 -0.0491323 0.000578532 0.0795971 -0.0509056 -0.000585681 0.0795971 -0.0501382 -0.000298913 0.0795971 -0.0491541 0.000166245 0.0795971 -0.0488989 -0.000330452 0.0795971 -0.0506034 0.0013581 0.0795971 -0.0495052 0.00143314 0.0795971 -0.0499551 0.000696699 0.0799471 -0.0489105 0.000166245 0.0799471 -0.0488989 0.00040993 0.0805629 -0.0498945 -0.000585681 0.0799471 -0.0501382 0.000696699 0.0795971 -0.0489105 -0.000298913 0.0799471 -0.0491541 -0.000574137 0.0799471 -0.0496078 -0.000574137 0.0795971 -0.0496078 -0.000330452 0.0799471 -0.0506034 0.000123162 0.0799471 -0.0508786 -0.0269913 0.0795971 -0.0428714 -0.0265693 0.0795971 -0.0426981 -0.026451 0.0799471 -0.0426008 -0.0261758 0.0799471 -0.0421471 -0.0261367 0.0799471 -0.041921 -0.0261367 0.0795971 -0.041921 -0.0261643 0.0799471 -0.0416167 -0.0264745 0.0795971 -0.0410982 -0.0264195 0.0799471 -0.0411515 -0.0269162 0.0799471 -0.042856 -0.0265693 0.0799471 -0.0426981 -0.0262643 0.0799471 -0.0423589 -0.0268731 0.0799471 -0.0408763 -0.0262117 0.0799471 -0.041471 -0.0262643 0.0795971 -0.0423589 -0.0274036 0.0795971 -0.0408648 -0.0262117 0.0795971 -0.041471 -0.0281555 0.0795971 -0.0421041 -0.0281439 0.0795971 -0.0415736 -0.0279003 0.0795971 -0.0425692 -0.0278687 0.0795971 -0.04112 -0.0273285 0.0799471 -0.0408493 -0.0274036 0.0799471 -0.0408648 -0.0271599 0.0805629 -0.0418604 -0.0281439 0.0799471 -0.0415736 -0.0281831 0.0799471 -0.0417998 -0.0281555 0.0799471 -0.0421041 -0.0278452 0.0799471 -0.0426226 -0.0274466 0.0799471 -0.0428444 -0.028108 0.0799471 -0.0422497 -0.0277505 0.0799471 -0.0410226 -0.0268731 0.0795971 -0.0408763 -0.0280555 0.0799471 -0.0413618 -0.0278687 0.0799471 -0.04112 -0.0279003 0.0799471 -0.0425692 -0.0274466 0.0795971 -0.0428444 -0.0466703 0.0665971 -0.0613811 -0.0468452 0.0665971 -0.0613343 -0.0466703 0.0417971 -0.0613811 -0.0468452 0.0417971 -0.0613343 -0.0443145 0.0665971 -0.0631866 -0.0443145 0.0417971 -0.0631866 -0.0453233 0.0665971 -0.0620632 -0.0453233 0.0417971 -0.0620632 -0.069744 0.0417971 -0.0330539 -0.069744 0.0665971 -0.0330539 -0.0712388 0.0665971 -0.0296963 -0.0704989 0.0665971 -0.0306494 -0.0700684 0.0665971 -0.0317767 -0.0712388 0.0417971 -0.0296963 -0.0700684 0.0417971 -0.0317767 -0.0704989 0.0417971 -0.0306494 -0.0637289 0.0665971 -0.0429878 -0.0633224 0.0417971 -0.0441239 -0.0637289 0.0417971 -0.0429878 -0.0644485 0.0665971 -0.0420192 -0.0653515 0.0665971 -0.0410594 -0.0633224 0.0665971 -0.0441239 -0.0644485 0.0417971 -0.0420192 -0.0653515 0.0417971 -0.0410594 -0.0766937 0.0665971 -0.00496809 -0.0766937 0.0417971 -0.00496809 -0.0771062 0.0665971 -0.00342345 -0.0770206 0.0665971 -0.00498929 -0.0769033 0.0417971 -0.00655307 -0.0770206 0.0417971 -0.00498929 -0.0769033 0.0665971 -0.00655307 -0.0771062 0.0417971 -0.00342345 0.0622724 0.0417971 -0.0455809 0.0622724 0.0665971 -0.0455809 0.0631857 0.0665971 -0.0443061 0.062008 0.0665971 -0.0453873 0.0631857 0.0417971 -0.0443061 0.062008 0.0417971 -0.0453873 0.0613334 0.0665971 -0.0468368 0.0613334 0.0417971 -0.0468368 0.0306485 0.0665971 -0.0704904 0.0317758 0.0665971 -0.07006 0.0296953 0.0665971 -0.0712304 0.0296953 0.0417971 -0.0712304 0.0317758 0.0417971 -0.07006 0.033053 0.0417971 -0.0697356 0.033053 0.0665971 -0.0697356 0.0306485 0.0417971 -0.0704904 0.0410585 0.0665971 -0.065343 0.044123 0.0417971 -0.063314 0.0420183 0.0417971 -0.0644401 0.044123 0.0665971 -0.063314 0.0429869 0.0665971 -0.0637205 0.0429869 0.0417971 -0.0637205 0.0420183 0.0665971 -0.0644401 0.0410585 0.0417971 -0.065343 0.00487691 0.0665971 -0.0766921 0.00342253 0.0417971 -0.0770978 0.00655215 0.0665971 -0.0768949 0.00655215 0.0417971 -0.0768949 0.0063795 0.0665971 -0.0768404 0.00342253 0.0665971 -0.0770978 0.0063795 0.0417971 -0.0768404 0.00487691 0.0417971 -0.0766921 -0.00736345 0.0384971 -0.0300776 -0.00833936 0.0384971 -0.031012 -0.00866057 0.0376853 -0.0296996 -0.00963649 0.0384971 -0.030634 -0.00903857 0.0384971 -0.0309968 -0.00768466 0.0384971 -0.0287653 -0.00828257 0.0384971 -0.0284025 -0.00772623 0.0384971 -0.0306755 -0.00734823 0.0384971 -0.0293784 -0.00997291 0.0384971 -0.0300208 -0.00959491 0.0384971 -0.0287237 -0.00995769 0.0384971 -0.0293216 -0.00898178 0.0384971 -0.0283873 0.00259423 0.0387471 -0.0585886 -0.00381893 0.0387471 -0.0585221 0.00259423 0.0390471 -0.0585886 -0.00389326 0.0390471 -0.0585172 -0.00381893 0.0390471 -0.0585221 -0.00389326 0.0400971 -0.0585172 -0.00375314 0.0390471 -0.0585769 0.00266864 0.0390471 -0.0585853 0.00252732 0.0400971 -0.0586421 -0.00375314 0.0400971 -0.0585769 0.00266864 0.0400971 -0.0585853 -0.00197674 0.0400971 -0.0595128 -0.00197674 0.0387471 -0.0595128 0.000422581 0.0400971 -0.0596137 0.00252732 0.0390471 -0.0586421 0.000422581 0.0387471 -0.0596137 0.0183766 0.0390471 -0.0556914 0.0128014 0.0400971 -0.0576377 0.0182559 0.0400971 -0.0557842 0.0167982 0.0400971 -0.057117 0.0128014 0.0387471 -0.0576377 0.0148543 0.0400971 -0.0577961 0.0182559 0.0390471 -0.0557842 0.0183059 0.0387471 -0.0557147 0.0121126 0.0387471 -0.0573809 0.0183059 0.0390471 -0.0557147 0.0121126 0.0390471 -0.0573809 0.0120397 0.0390471 -0.0573962 0.0120397 0.0400971 -0.0573962 0.0183766 0.0400971 -0.0556914 0.0167982 0.0387471 -0.057117 0.0148543 0.0387471 -0.0577961 0.0121907 0.0400971 -0.0574159 0.0121907 0.0390471 -0.0574159 0.0326595 0.0390471 -0.0487084 0.0271454 0.0390471 -0.0519837 0.0327214 0.0400971 -0.0486669 0.0314137 0.0400971 -0.0506399 0.0272301 0.0400971 -0.0519964 0.0326595 0.0387471 -0.0487084 0.0326301 0.0390471 -0.0487888 0.0294376 0.0400971 -0.0518137 0.0314137 0.0387471 -0.0506399 0.0299473 0.0387471 -0.0504215 0.0294376 0.0387471 -0.0518137 0.0271454 0.0387471 -0.0519837 0.0326301 0.0400971 -0.0487888 0.0327214 0.0390471 -0.0486669 0.0270794 0.0400971 -0.0520181 0.0270794 0.0390471 -0.0520181 0.0272301 0.0390471 -0.0519964 0.0401647 0.0387471 -0.0427308 0.0401104 0.0400971 -0.0427818 0.0401647 0.0390471 -0.0427308 0.0445906 0.0390471 -0.0380893 0.044584 0.0390471 -0.0381747 0.0439121 0.0400971 -0.0402853 0.0402497 0.0390471 -0.0427202 0.0445906 0.0387471 -0.0380893 0.042326 0.0387471 -0.0419487 0.0424412 0.0387471 -0.0404706 0.0439121 0.0387471 -0.0402853 0.044584 0.0400971 -0.0381747 0.044639 0.0400971 -0.0380326 0.044639 0.0390471 -0.0380326 0.042326 0.0400971 -0.0419487 0.0402497 0.0400971 -0.0427202 0.0401104 0.0390471 -0.0427818 0.0532143 0.0390471 -0.024645 0.0532143 0.0387471 -0.024645 0.0501662 0.0390471 -0.0303723 0.0501662 0.0400971 -0.0303723 0.0532456 0.0390471 -0.0245774 0.0502048 0.0387471 -0.0303086 0.0520749 0.0387471 -0.0289724 0.053231 0.0390471 -0.024729 0.0520749 0.0400971 -0.0289724 0.0531534 0.0387471 -0.0269427 0.051787 0.0387471 -0.027518 0.0532456 0.0400971 -0.0245774 0.0531534 0.0400971 -0.0269427 0.0502837 0.0400971 -0.0302754 0.053231 0.0400971 -0.024729 0.0502048 0.0390471 -0.0303086 0.0502837 0.0390471 -0.0302754 -0.0586396 0.0390471 0.00133493 -0.0586866 0.0400971 0.0014798 -0.0586396 0.0400971 0.00133493 -0.058193 0.0400971 0.00774117 -0.0581338 0.0387471 0.00780307 -0.0581238 0.0390471 0.00787688 -0.0581338 0.0390471 0.00780307 -0.0586378 0.0390471 0.00140939 -0.0586378 0.0387471 0.00140939 -0.0586866 0.0390471 0.0014798 -0.0594974 0.0400971 0.00354107 -0.0593167 0.0400971 0.00583241 -0.0594974 0.0387471 0.00354107 -0.0584733 0.0387471 0.00461313 -0.0593167 0.0387471 0.00583241 -0.058193 0.0390471 0.00774117 -0.0581238 0.0400971 0.00787688 -0.0568244 0.0400971 -0.0145339 -0.0580824 0.0390471 -0.0081692 -0.0568428 0.0390471 -0.0144618 -0.0581227 0.0390471 -0.00824477 -0.0580824 0.0387471 -0.0081692 -0.0568428 0.0387471 -0.0144618 -0.0569087 0.0390471 -0.0144071 -0.0582456 0.0387471 -0.012641 -0.0582456 0.0400971 -0.012641 -0.0586898 0.0400971 -0.0103859 -0.0581227 0.0400971 -0.00824477 -0.0586898 0.0387471 -0.0103859 -0.0575487 0.0387471 -0.0113324 -0.0580928 0.0400971 -0.00809543 -0.0580928 0.0390471 -0.00809543 -0.0568244 0.0390471 -0.0145339 -0.0569087 0.0400971 -0.0144071 -0.0507951 0.0390471 -0.0293246 -0.0537237 0.0390471 -0.0235353 -0.0537536 0.0400971 -0.0234671 -0.0523563 0.0387471 -0.0264373 -0.0508323 0.0390471 -0.0292601 -0.0509106 0.0390471 -0.0292253 -0.0509106 0.0400971 -0.0292253 -0.0537421 0.0390471 -0.023619 -0.0537105 0.0387471 -0.0258337 -0.0526743 0.0387471 -0.0278853 -0.0526743 0.0400971 -0.0278853 -0.0537105 0.0400971 -0.0258337 -0.0508323 0.0387471 -0.0292601 -0.0537237 0.0387471 -0.0235353 -0.0537536 0.0390471 -0.0234671 -0.0537421 0.0400971 -0.023619 -0.0507951 0.0400971 -0.0293246 -0.045428 0.0390471 -0.037098 -0.0448625 0.0387471 -0.0391484 -0.0417711 0.0400971 -0.0417346 -0.0435878 0.0387471 -0.0407654 -0.0435878 0.0400971 -0.0407654 -0.0448625 0.0400971 -0.0391484 -0.0453809 0.0387471 -0.0371556 -0.0453761 0.0390471 -0.0372412 -0.045428 0.0400971 -0.037098 -0.0411369 0.0400971 -0.0418756 -0.040999 0.0390471 -0.0419401 -0.0411369 0.0390471 -0.0418756 -0.0453761 0.0400971 -0.0372412 -0.040999 0.0400971 -0.0419401 -0.0453809 0.0390471 -0.0371556 -0.0410522 0.0390471 -0.041888 -0.0417711 0.0387471 -0.0417346 -0.0410522 0.0387471 -0.041888 -0.0282278 0.0390471 -0.0514091 -0.0336727 0.0390471 -0.04802 -0.0281625 0.0400971 -0.0514449 -0.033645 0.0390471 -0.0481011 -0.0323917 0.0387471 -0.0500513 -0.0303138 0.0400971 -0.0512551 -0.0323917 0.0400971 -0.0500513 -0.033645 0.0400971 -0.0481011 -0.0336727 0.0387471 -0.04802 -0.0282278 0.0387471 -0.0514091 -0.0337337 0.0400971 -0.0479772 -0.0337337 0.0390471 -0.0479772 -0.0283127 0.0400971 -0.05142 -0.0281625 0.0390471 -0.0514449 -0.0283127 0.0390471 -0.05142 -0.0303138 0.0387471 -0.0512551 -0.0195378 0.0390471 -0.055298 -0.0167128 0.0387471 -0.0573314 -0.013389 0.0390471 -0.0571505 -0.0149927 0.0387471 -0.0575219 -0.0194676 0.0387471 -0.0553227 -0.0194676 0.0390471 -0.0553227 -0.0195378 0.0400971 -0.055298 -0.0132376 0.0400971 -0.0571339 -0.0132376 0.0390471 -0.0571339 -0.019419 0.0390471 -0.0553933 -0.0182659 0.0387471 -0.0565681 -0.019419 0.0400971 -0.0553933 -0.0167128 0.0400971 -0.0573314 -0.0133102 0.0387471 -0.0571171 -0.0133102 0.0390471 -0.0571171 -0.013389 0.0400971 -0.0571505 -0.0182659 0.0400971 -0.0565681 -0.0149927 0.0400971 -0.0575219 + + + + + + + + + + 0.0649182 0.997876 -0.00541148 0.0649183 0.997876 -0.00541993 0.156831 0.987504 -0.0155009 -0.486333 0.873743 -0.00731895 -0.0873026 0.996098 -0.0129222 -0.0873025 0.996098 -0.0129211 -0.0737928 0.997207 -0.0114979 -0.074268 0.99715 -0.0132487 -0.0346783 0.999371 -0.00741132 -0.0431174 0.999026 -0.00933572 -0.176016 0.984262 -0.0156925 -0.0876568 0.996149 -0.00193869 -0.158029 0.987406 -0.00750836 -0.152706 0.988097 -0.0185893 -0.265003 0.962452 0.058819 -0.218358 0.975603 0.0227761 -0.170627 0.985027 0.0246633 0.151969 0.988311 -0.0121011 -0.0926553 0.992149 0.0839927 0.483429 0.0707919 -0.872517 0.452497 0.436434 -0.777671 0.413572 0.541314 -0.732077 0.505468 0.195621 -0.840378 0.406932 0.398538 -0.821933 0.462 0.228391 -0.856968 0.0310653 0.942637 -0.33237 0.16446 0.953151 -0.253881 0.389807 0.693571 -0.605813 0.271244 0.770364 -0.577032 0.367744 0.681146 -0.633091 0.0228321 0.979289 -0.201176 0.258226 0.950479 -0.172943 0.168698 0.834723 -0.524193 0.44033 0.193942 -0.876639 0.440367 0.193907 -0.876628 0.624911 0.508415 -0.592453 0.236514 0.678193 -0.695784 0.404467 0.433727 -0.805163 0.151668 0.193902 -0.969226 0.151457 0.194089 -0.969222 0.128539 0.553951 -0.822567 0.128812 0.553779 -0.82264 0.0859037 0.831651 -0.548614 0.0858695 0.831662 -0.548603 0.0313057 0.979295 -0.200006 0.00534992 0.981457 -0.191609 -1.62592e-05 0.0673577 -0.997729 0.0022776 0.196353 -0.980531 -8.2434e-07 0.9949 -0.100864 0.00245711 0.981468 -0.191612 0.00168528 0.834745 -0.550635 -0.000333669 0.916238 -0.400635 0.000259139 0.961684 -0.274159 0.000578114 0.242176 -0.970232 -0.000779921 0.465268 -0.88517 0.00253239 0.55843 -0.829548 4.53687e-05 0.643499 -0.765447 -0.000109467 0.810487 -0.585757 -0.053765 0.465077 -0.883636 -0.0942489 0.0671934 -0.993279 -0.991311 0.0657195 -0.113946 -0.988966 0.0135703 -0.147521 -0.98812 0.029494 -0.150826 -0.843064 0.128821 -0.522157 -0.363235 0.928756 -0.0739792 -0.185314 0.90186 -0.390265 -0.198872 0.941517 -0.272021 -0.193375 0.944652 -0.265025 -0.184075 0.978104 -0.0971058 -0.1822 0.978642 -0.0951945 -0.0975038 0.641492 -0.760908 -0.981677 0.190411 0.00734974 -0.983312 0.18053 0.0224861 -0.984611 0.154835 -0.0810401 -0.988301 0.145871 -0.0445218 -0.987685 0.109328 -0.111921 -0.848518 0.31538 -0.424914 -0.853049 0.109848 -0.510139 -0.562815 0.172644 -0.808352 -0.563948 0.173458 -0.807388 -0.288288 0.191072 -0.938286 -0.254364 0.541072 -0.801586 -0.28583 0.536531 -0.794 -0.278366 0.753401 -0.595735 -0.558399 0.655329 -0.50866 -0.602324 0.681266 -0.416033 -0.0856143 0.808407 -0.582365 -0.157045 0.81728 -0.554429 -0.209856 0.870082 -0.446001 -0.559641 0.742099 -0.368905 -0.551906 0.804141 -0.22081 -0.594177 0.793853 -0.129424 -0.54618 0.83552 -0.0599434 -0.829709 0.553697 -0.0707361 -0.8343 0.547911 -0.0611302 -0.845766 0.465843 -0.260134 -0.842691 0.467175 -0.267619 -0.850752 0.310552 -0.424003 -0.562102 0.474147 -0.677662 -0.555992 0.471904 -0.684237 -0.27618 0.540573 -0.794673 -0.284198 0.192605 -0.93922 -0.15682 0.197722 -0.967633 -0.282711 0.233772 -0.930282 0.895557 0.0602458 -0.440848 0.88227 0.175609 -0.436762 0.881488 0.180956 -0.436158 0.82653 0.391075 -0.404856 0.754534 0.538357 -0.375299 0.695081 0.632479 -0.341809 0.537119 0.800839 -0.264877 0.483324 0.841545 -0.241245 0.420397 0.883128 -0.208209 0.313491 0.937076 -0.153663 0.1577 0.98428 -0.0795169 0.110343 0.992408 -0.054318 0.914504 0.0430647 -0.402278 0.956492 0.0428075 -0.288602 0.926201 0.0782376 -0.368823 0.916066 0.120144 -0.382606 0.882805 0.179949 -0.433905 0.8392 0.438387 -0.321808 0.947434 0.177917 -0.265924 0.955279 0.195068 -0.22224 0.747184 0.451798 -0.487436 0.858354 0.464697 -0.217452 0.731925 0.599529 -0.323806 0.889273 0.378132 -0.257314 0.318449 0.947412 -0.0316187 0.0709221 0.992011 -0.104331 0.461961 0.88408 -0.0706742 0.813571 0.555581 -0.171556 0.650935 0.736615 -0.183527 0.542982 0.831461 -0.117654 0.261501 0.956178 -0.131686 0.818676 0.463753 -0.338678 0.692725 0.634303 -0.343209 0.733627 0.618366 -0.281807 0.551998 0.792249 -0.260076 0.57035 0.803291 -0.171537 0.899904 0.267044 -0.344761 0.92474 0.230992 -0.302488 0.933478 0.21045 -0.290397 0.947353 0.178029 -0.266134 0.96359 0.0744449 -0.256811 0.292321 0.943361 -0.156904 0.441053 0.880532 -0.173598 0.53744 0.814883 -0.217082 0.647913 0.735732 -0.197249 0.75259 0.613188 -0.240017 0.856993 0.4678 -0.216165 0.895513 0.382176 -0.22803 0.970542 0.130465 -0.202553 0.96228 0.124948 -0.241673 0.962102 0 -0.272689 0.943859 -0.000211069 -0.330349 0.92215 0 -0.386833 0.943586 -0.0240312 -0.330254 0.964676 -0.11076 -0.239023 0.949441 -0.0251965 -0.312934 0.941736 -0.0562672 -0.331614 0.926012 -0.0365554 -0.37572 -0.972409 -0.184199 0.14315 -0.284811 -0.95763 -0.0427411 0.170646 -0.953822 -0.247193 0.0547504 -0.995277 -0.0801581 0.115614 -0.986693 -0.114325 0.0636721 -0.984539 -0.163182 0.0088611 -0.98009 -0.198354 0.0237229 -0.968142 -0.249276 -0.0525694 -0.982163 -0.180533 -0.0747676 -0.943726 -0.322166 -0.0957102 -0.983281 -0.154912 -0.329105 -0.943136 -0.046733 -0.146281 -0.985357 -0.0875956 -0.195718 -0.975426 -0.101182 -0.169803 -0.975336 -0.14102 -0.125479 -0.984742 -0.120571 -0.150047 -0.974712 -0.165597 -0.1182 -0.975165 -0.187303 0.474518 -0.842614 -0.254625 0.455279 -0.854367 -0.250557 0.335191 -0.840411 -0.425858 0.329317 -0.844737 -0.421866 0.15559 -0.830239 -0.535252 0.15185 -0.834575 -0.529552 -0.0476476 -0.822248 -0.567132 -0.0486985 -0.826165 -0.56132 -0.245644 -0.818015 -0.520106 -0.244666 -0.820947 -0.515931 -0.411648 -0.817941 -0.401894 -0.410559 -0.819202 -0.400436 -0.522528 -0.821307 -0.228953 -0.523608 -0.820446 -0.22957 -0.562594 -0.826498 -0.0197379 0.447336 0.121145 -0.886123 0.0523666 0.366732 -0.928852 0.345417 0.575943 -0.74093 0.277259 -0.0967498 -0.955912 0.0872388 -0.0850876 -0.992547 0.567469 -0.392437 -0.723859 0.655043 0.431708 -0.620118 0.786281 -0.235442 -0.571253 0.870832 0.348795 -0.346401 0.928344 -0.0861827 -0.361594 -0.0223561 -0.25945 -0.965498 0.340827 -0.28182 -0.896891 0.34307 -0.261559 -0.902158 0.655594 -0.28767 -0.698171 0.659952 -0.266612 -0.702411 0.872667 -0.291323 -0.391896 0.875553 -0.280628 -0.393263 -0.702716 -0.178718 -0.688658 -0.702668 -0.179913 -0.688396 -0.835936 -0.18433 -0.516946 -0.863407 -0.138997 -0.484983 -0.925642 0.0834527 -0.369085 -0.92593 -0.178416 -0.332898 -0.977386 -0.187224 -0.098302 -0.907487 -0.419915 0.0118022 -0.806276 -0.591381 -0.013665 -0.627516 -0.778249 -0.0235016 -0.0498517 0.0273155 -0.998383 -0.160402 -0.186416 -0.969288 -0.389584 -0.173759 -0.904451 -0.350219 0.121578 -0.928744 -0.525986 -0.183829 -0.830389 0.748805 -0.559755 -0.354917 0.743529 -0.567017 -0.35448 0.558826 -0.545675 -0.624462 0.550186 -0.559042 -0.620296 0.2819 -0.536609 -0.795351 0.275864 -0.549596 -0.788571 -0.0350057 -0.530351 -0.847055 -0.0372016 -0.540868 -0.840285 -0.345546 -0.528124 -0.775682 -0.345063 -0.534503 -0.771517 -0.606173 -0.529859 -0.59313 -0.605732 -0.531166 -0.592412 -0.779948 -0.534502 -0.32556 -0.781948 -0.53075 -0.326897 -0.841093 -0.540748 -0.0124357 -0.97804 0.207355 0.0210202 -0.997835 0.0379189 0.053736 0.698306 -0.0863746 -0.710569 0.748119 -0.447258 0.490182 0.786908 -0.449824 0.422415 0.923988 -0.321464 -0.207139 0.92744 -0.372169 -0.0366864 0.91879 -0.393646 0.0294627 0.893891 -0.415006 0.169497 0.839766 -0.436846 0.322426 0.825182 -0.288903 -0.485396 0.872387 -0.246124 -0.422331 0.782194 -0.192024 -0.592705 0.883514 -0.340269 -0.321901 0.747256 -0.173592 -0.641463 0.632491 -0.0587599 -0.772336 0.859591 -0.401606 -0.315936 0.850265 -0.526027 -0.0185514 0.851996 -0.522937 -0.0252991 0.711241 -0.605443 0.357177 0.714481 -0.604453 0.352353 0.765443 -0.126409 0.630966 0.784597 -0.59975 0.157186 0.830936 -0.554832 -0.041312 0.442534 -0.666459 0.599997 0.523299 -0.717011 0.460493 0.469665 -0.750551 0.464852 0.475842 -0.760969 0.441023 0.461018 -0.789472 0.40521 0.805032 -0.545116 0.234033 0.740631 -0.616507 0.267179 0.719134 -0.569586 0.398018 0.686811 -0.613687 0.389461 0.584227 -0.60854 0.53699 0.592518 -0.583065 0.55584 0.471612 -0.622546 0.624515 0.44875 -0.556046 0.699598 0.398788 -0.587428 0.704199 0.331802 -0.537766 0.775058 0.319056 -0.550821 0.771233 0.15855 -0.0305792 0.986877 -0.344089 0.882594 0.32036 -0.159355 0.690998 0.705073 0.46047 -0.0736619 0.884614 0.576338 -0.0370388 0.816372 0.0727967 -0.0825335 0.993926 -0.553767 0.510749 0.65763 -0.180418 0.00716995 0.983564 -0.231231 -0.0536791 0.971417 -0.301973 -0.126552 0.944879 -0.456848 0.0163392 0.889395 0.549054 0.488586 0.678103 0.43792 0.645872 0.62536 0.582006 -0.169759 0.795268 0.367534 -0.232093 0.900584 0.318849 -0.0977307 0.942754 0.0832773 -0.242257 0.966632 -0.0388892 -0.0962318 0.994599 -0.175134 -0.235076 0.956069 -0.323734 -0.109594 0.93978 0.983004 -0.0304822 -0.181038 0.96298 -0.0833049 -0.256379 0.580588 0.39848 -0.710022 0.872601 -0.00327709 -0.488423 0.792599 -0.126191 -0.596542 0.365466 0.794958 -0.484228 0.565562 0.691396 -0.449568 0.988731 -0.0761657 0.128878 0.859359 -0.401957 -0.31612 0.862622 -0.467531 -0.193128 0.834454 -0.274771 -0.47769 0.797235 -0.602227 0.0417105 0.83444 -0.543127 0.0933985 0.919075 -0.377283 -0.113834 0.931887 -0.25848 -0.25451 0.865668 -0.36196 -0.34584 0.773177 -0.134881 -0.619681 0.854043 -0.130722 0.50351 0.850789 0.456002 0.261191 0.756492 0.636151 0.151765 0.944822 -0.241548 -0.221281 0.99482 -0.0996904 -0.0198772 0.969854 -0.233395 0.0700783 0.945458 -0.162009 0.2826 0.964968 -0.0302316 0.260619 0.723171 -0.685955 0.0805543 0.536631 -0.645902 0.542991 0.251246 -0.528151 0.81113 0.660015 -0.682561 0.313832 0.244277 -0.708041 0.662576 0.61595 -0.708102 0.345248 0.508235 -0.773679 0.378309 0.550022 -0.754935 0.35714 0.537592 -0.766954 0.350394 0.480984 -0.803743 0.350218 0.486018 -0.798124 0.356069 0.470967 -0.797257 0.377587 0.457395 -0.815411 0.354817 0.467958 -0.787328 0.401411 -0.0904782 -0.313462 0.94528 0.0464226 -0.379549 0.924006 0.120176 -0.30383 0.945117 0.235201 -0.398645 0.886432 0.383265 -0.306417 0.87133 0.431054 -0.408608 0.804508 0.657724 -0.335557 0.674389 0.654666 -0.373644 0.657117 0.832376 -0.382342 0.401204 0.856528 -0.321116 0.404034 0.899115 -0.410763 0.151214 0.950214 -0.295893 0.097675 0.912819 -0.40468 -0.0547296 0.925103 -0.111908 -0.362853 0.841867 -0.244904 -0.480918 0.678495 0.0075631 -0.734566 -0.357428 -0.157806 0.920512 -0.508181 -0.0557854 0.859442 -0.415928 -0.0895536 0.904978 -0.0374319 -0.311463 0.949521 -0.0882207 -0.287647 0.953665 -0.0771472 -0.293535 0.95283 0.57132 -0.593317 0.56707 0.692381 -0.451178 0.563069 0.558804 -0.449598 0.69685 0.162034 -0.388408 0.90713 0.429882 -0.473505 0.768762 0.304442 -0.442836 0.843333 0.253921 -0.424665 0.869013 0.115454 -0.373736 0.920321 0.928308 -0.224533 -0.296361 0.755283 -0.571076 -0.321589 -0.0475559 -0.0277458 -0.998483 -0.0366301 -0.0509617 -0.998029 -0.040661 -0.0760394 -0.996275 -0.055932 -0.104901 -0.992909 -0.13835 -0.0542182 -0.988898 0.856734 -0.216725 -0.468015 0.906655 -0.225147 -0.35677 0.852021 -0.393639 -0.345121 0.767118 -0.203602 -0.608338 0.69533 -0.195107 -0.6917 0.625464 -0.179163 -0.759405 0.489657 -0.153451 -0.858306 0.353617 -0.129051 -0.926445 0.284537 -0.110941 -0.952224 0.0682024 -0.0654605 -0.995522 -0.0210097 -0.0394848 -0.998999 0.566933 -0.49203 -0.660676 0.566478 -0.491893 -0.661168 0.269932 -0.323964 -0.906744 0.269862 -0.323933 -0.906776 0.0190043 -0.162602 -0.986509 -0.0360217 -0.0773874 -0.99635 0.322516 -0.222185 -0.920118 0.323861 -0.222926 -0.919466 0.648298 -0.338174 -0.682165 0.649916 -0.339045 -0.68019 0.853345 -0.393491 -0.342004 0.755905 -0.571072 -0.320132 0.380533 0.0435186 0.923743 0.615091 -0.732577 -0.291537 0.560444 -0.731256 0.388803 0.525927 -0.799643 -0.289777 0.494 -0.844766 -0.205753 0.492527 -0.845431 -0.206552 0.662442 -0.610274 0.434438 0.679003 -0.650535 0.340233 0.691788 -0.641358 0.331796 0.671955 -0.696663 0.251269 0.735463 -0.658818 0.158282 0.701013 -0.702544 0.122523 0.73385 -0.677339 -0.0517262 0.721971 -0.689791 -0.0542757 0.675522 -0.694746 -0.246976 0.696535 -0.670249 -0.256135 0.589662 -0.704628 -0.394714 0.618423 -0.649851 -0.441867 0.524065 -0.693491 -0.494395 0.524451 -0.629501 -0.573306 0.511487 -0.638536 -0.575024 0.481073 -0.593094 -0.645607 0.984127 -0.144552 -0.102949 0.947285 0.320386 0.00209022 0.985642 -0.138268 0.0969076 0.863871 -0.0515462 0.50107 0.748056 -0.112315 0.654063 0.41605 0.454639 0.787531 0.615694 -0.370959 0.695206 0.943831 -0.163836 0.286952 0.847136 0.280269 0.451454 0.857648 -0.206108 0.471126 0.741658 -0.262957 0.617087 0.723381 -0.135663 0.67699 0.539311 -0.263561 0.7998 0.457428 -0.121998 0.880838 -0.124647 -0.0390852 -0.991431 -0.363462 0.305369 -0.880139 0.0948297 -0.110211 -0.989374 0.214475 -0.0307112 -0.976247 -0.161457 0.623955 -0.764599 0.424404 -0.102729 -0.899627 0.863171 -0.0492956 -0.5025 0.739053 -0.0886574 -0.667788 0.208755 0.742202 -0.636835 0.376697 0.511413 -0.77237 0.541477 -0.0519385 -0.83911 0.941104 -0.150398 -0.302826 0.755182 0.452434 -0.474345 0.892654 -0.181498 -0.412586 0.679706 -0.2484 -0.690143 0.664548 -0.154206 -0.731161 0.422972 -0.262838 -0.867186 0.35075 -0.13752 -0.926317 0.181833 -0.251861 -0.950528 0.0452722 -0.133093 -0.990069 0.435999 -0.897975 -0.0595432 0.587028 -0.809308 0.0204533 0.489369 -0.87204 -0.00796352 0.485623 -0.874061 -0.0137184 0.571692 -0.816799 0.0775135 0.548107 -0.814576 -0.189854 0.647806 -0.758254 0.0734814 0.456761 -0.875103 -0.159891 0.458349 -0.874062 -0.161037 0.482531 -0.866203 -0.129829 0.410139 -0.906589 -0.0994092 0.623438 -0.773362 -0.115047 0.572948 -0.35554 0.738459 0.638541 -0.444062 0.62855 0.740377 -0.371706 0.560068 0.747767 -0.464117 0.474805 0.875794 -0.388891 0.285919 0.855761 -0.453875 0.248335 0.909854 -0.412918 -0.0407978 0.901402 -0.430724 -0.0441792 0.827314 -0.438542 -0.351045 0.842087 -0.403678 -0.357677 0.662488 -0.460473 -0.590825 0.677113 -0.378182 -0.631266 0.478162 -0.468689 -0.74276 0.454295 -0.359689 -0.81501 0.329569 -0.445327 -0.832507 0.254403 -0.341965 -0.904621 0.376319 -0.0755052 0.923409 0.314086 -0.022979 0.949116 0.377927 -0.040222 0.924961 0.55501 -0.0779067 0.828188 0.691894 -0.117903 0.712308 0.790648 -0.139343 0.596204 0.907587 -0.17891 0.379839 0.93559 -0.184935 0.300784 0.757844 -0.507887 0.40954 0.757263 -0.506564 0.412245 0.595919 -0.331063 0.731627 0.595056 -0.329937 0.732837 0.414953 -0.166273 0.894521 0.918716 -0.394534 0.0174351 0.798994 -0.599814 0.0427917 0.79857 -0.60064 0.038956 0.977398 -0.209886 -0.0253366 0.977694 -0.21002 0.00266014 0.918627 -0.394801 0.0159952 0.857896 -0.332919 0.391381 0.857679 -0.332847 0.391918 0.659714 -0.216367 0.719696 0.65968 -0.216355 0.719731 0.372243 -0.0729803 0.925261 0.353024 -0.107247 0.929447 0.283474 -0.0558796 0.95735 -0.223533 -0.666859 0.710867 0.84311 -0.0597474 0.534411 0.738543 -0.169679 0.652505 -0.402751 -0.404633 0.821014 -0.214959 -0.446243 0.868712 -0.066659 -0.558461 0.826848 -0.194243 -0.45466 0.869226 0.27203 -0.422462 0.864596 -0.0524814 -0.518621 0.853392 0.11993 -0.478408 0.869909 0.143546 -0.470181 0.870818 0.412519 -0.36359 0.835243 0.309675 -0.413278 0.856331 0.587385 -0.262883 0.765422 0.510625 -0.314397 0.80026 0.4877 -0.327118 0.809409 0.787905 -0.0935758 0.608645 -0.439527 -0.672353 0.595615 -0.989221 -0.081108 -0.121917 0.156234 -0.561988 0.812257 -0.227762 -0.718861 0.656783 -0.234649 -0.739659 0.630749 -0.240867 -0.743764 0.623537 -0.692214 -0.570141 0.442469 -0.62542 -0.60982 0.486795 -0.605656 -0.549272 0.575744 -0.540941 -0.60014 0.589249 -0.465141 -0.550852 0.692969 -0.435837 -0.58946 0.680134 -0.285428 -0.581963 0.761479 -0.289414 -0.556969 0.778476 -0.141606 -0.600985 0.786616 -0.110118 -0.537133 0.836279 -0.0447578 -0.581732 0.812148 -0.97697 -0.101022 0.187945 -0.956599 -0.0333705 0.28949 -0.747677 0.653633 -0.117232 -0.74289 -0.0262406 0.668899 -0.833862 -0.233913 0.499959 -0.713706 -0.153892 0.683331 -0.605182 0.665114 0.437469 -0.644551 0.489753 0.587108 -0.534619 -0.125727 0.835689 -0.99813 -0.0244466 -0.0560341 -0.813333 0.44285 -0.377324 -0.987942 -0.111325 0.107601 -0.964023 -0.258375 -0.0624709 -0.972163 -0.129845 -0.195035 -0.833866 0.185484 -0.519868 -0.933536 -0.00581261 -0.358438 0.634857 -0.0600475 0.770293 0.369102 -0.0847833 0.925514 0.32029 0.295808 0.899951 0.291112 -0.0331753 0.956114 0.341324 0.363741 0.866713 0.230952 -0.165316 0.958818 0.342161 -0.238884 0.908768 0.769389 0.47769 0.424091 0.586123 -0.00547397 0.810203 0.430603 -0.401933 0.808104 0.316106 -0.467885 0.825325 0.589357 -0.266875 0.762519 0.716947 -0.126442 0.685565 0.459396 -0.360367 0.811844 0.369707 -0.255378 0.893364 0.237796 -0.37587 0.895642 -0.0933202 -0.63138 0.769838 -0.0577095 -0.673316 0.737099 -0.209528 -0.698103 0.684653 -0.392163 -0.118948 0.912173 -0.106911 0.670532 0.734137 -0.0954252 0.691137 0.716396 -0.16624 -0.0968333 0.981319 -0.0370928 -0.134573 0.990209 -0.279795 -0.778252 0.562174 -0.324994 -0.743801 0.584071 -0.320866 -0.752433 0.57523 -0.387553 -0.721285 0.574065 -0.362989 -0.737184 0.569911 -0.388972 -0.732084 0.559244 -0.393227 -0.707941 0.586679 -0.243 -0.762214 0.599984 -0.250266 -0.760113 0.599663 -0.259216 -0.78293 0.565533 -0.267117 -0.769668 0.579879 -0.282223 -0.770416 0.571673 -0.938003 -0.344198 0.0409789 -0.925987 -0.369257 0.0787305 -0.943997 -0.251443 0.213648 -0.942685 -0.254286 0.216065 -0.889575 -0.0988151 0.445972 -0.685991 0.707099 -0.171545 -0.826721 -0.0786623 0.557085 -0.441555 -0.695291 0.567098 -0.745685 -0.57825 0.331031 -0.686386 -0.606139 0.401833 -0.850762 -0.483876 0.205104 -0.866004 -0.392269 0.310099 -0.839324 -0.424068 0.34015 -0.80014 -0.304934 0.516518 -0.726056 -0.398574 0.560341 -0.585197 -0.308252 0.750017 -0.554907 -0.367459 0.746359 -0.291017 -0.354533 0.888603 -0.293189 -0.316604 0.90211 -0.023931 -0.396071 0.917908 0.0233347 -0.291223 0.956371 0.187002 -0.401058 0.896762 0.469056 -0.110097 0.876279 0.585293 -0.245074 0.772898 0.728484 -0.098921 0.677883 0.804587 0.0158138 0.593624 -0.947815 -0.0988819 -0.303098 -0.906471 -0.340484 0.249761 -0.913245 -0.0597772 -0.403001 -0.956705 -0.175525 -0.232177 -0.96416 -0.255045 -0.0731221 -0.965812 -0.212707 -0.148197 -0.968633 -0.226479 -0.102265 -0.9593 -0.274571 0.0659801 -0.83996 -0.385495 0.381918 -0.794007 -0.411677 0.447297 -0.7133 -0.430007 0.553441 -0.605021 -0.451059 0.656122 -0.489242 -0.465338 0.737633 -0.445072 -0.462101 0.767056 -0.932122 -0.361075 0.0278021 -0.763525 -0.531484 0.366818 -0.75658 -0.533985 0.377422 -0.463604 -0.611457 0.641243 -0.452401 -0.610899 0.64972 -0.116981 -0.040507 0.992308 -0.110426 -0.0779392 0.990824 -0.0169069 -0.0556229 0.998309 -0.092803 -0.107284 0.989888 -0.161212 -0.166001 0.972859 -0.873125 -0.415425 0.255097 -0.939707 -0.224107 0.258315 -0.960096 -0.224802 0.166371 -0.112828 -0.0398014 0.992817 -0.433181 -0.111754 0.894352 -0.478078 -0.124597 0.869435 -0.700765 -0.169963 0.69285 -0.773411 -0.190413 0.60463 -0.844361 -0.202293 0.496118 -0.913388 -0.216419 0.344796 -0.380119 -0.330423 0.863904 -0.379976 -0.330346 0.863997 -0.622909 -0.506528 0.596166 -0.62273 -0.506449 0.59642 -0.761466 -0.598715 0.248415 -0.115412 -0.0795898 0.990124 -0.44091 -0.228785 0.867903 -0.441151 -0.228938 0.86774 -0.716832 -0.351172 0.602354 -0.71693 -0.35124 0.602197 -0.873064 -0.415428 0.255301 -0.761342 -0.598698 0.248835 -0.217753 0.0415106 -0.975121 -0.885196 0.381979 0.265557 -0.961963 -0.232686 0.14312 -0.953519 -0.0553056 -0.296213 -0.637163 -0.731606 0.242439 -0.488447 -0.750532 -0.445109 -0.567953 -0.789897 0.231283 -0.529511 -0.832144 0.164786 -0.534164 -0.829898 0.161052 -0.501052 -0.864771 0.0334413 -0.470791 -0.881765 0.0290897 -0.607406 -0.775828 -0.170732 -0.575696 -0.816636 -0.0409942 -0.548503 -0.833421 -0.0674849 -0.528457 -0.848446 -0.0295512 -0.511725 -0.85886 -0.0223106 -0.519643 -0.854378 -0.00303367 -0.63227 -0.587996 -0.504476 -0.665385 -0.622284 -0.412341 -0.667513 -0.620602 -0.411436 -0.665987 -0.674163 -0.31932 -0.727015 -0.636 -0.258753 -0.695914 -0.68914 -0.201966 -0.755153 -0.653352 -0.0536265 -0.73275 -0.679207 -0.0419031 -0.723906 -0.672642 0.153339 -0.737951 -0.65663 0.155773 -0.655762 -0.685176 0.317033 -0.689634 -0.631565 0.354303 -0.597859 -0.676868 0.429435 -0.609942 -0.610314 0.505458 -0.577565 -0.633026 0.515458 -0.55547 -0.580799 0.595084 -0.873228 -0.0972977 -0.477499 -0.404565 0.696668 -0.592437 -0.751335 -0.046337 -0.658293 -0.630124 -0.115315 -0.767884 -0.216881 0.436247 -0.873299 -0.526302 -0.356567 -0.771923 -0.992955 -0.033977 -0.113513 -0.91256 0.348073 -0.214661 -0.936934 -0.204167 -0.283674 -0.841194 -0.247777 -0.480624 -0.842427 -0.141676 -0.519851 -0.639956 -0.264405 -0.721489 -0.59494 -0.125485 -0.793915 -0.423543 -0.257766 -0.868429 -0.324799 -0.129435 -0.936884 -0.669762 0.0127358 0.742466 -0.59023 -0.270329 0.760626 -0.403545 0.0828763 0.911199 -0.269326 -0.161193 0.949463 -0.0836856 0.0130053 0.996407 -0.933266 -0.0624583 0.353715 -0.898276 -0.140715 0.416293 -0.784915 -0.17005 0.595812 -0.668275 0.397934 0.628536 -0.678016 -0.205507 0.705735 -0.56108 -0.255495 0.787344 -0.501651 -0.129263 0.855358 -0.326082 -0.249848 0.911727 -0.198719 -0.126623 0.971842 -0.729082 -0.672476 -0.127338 -0.682404 -0.714337 -0.155071 -0.61875 -0.772135 0.144764 -0.606915 -0.781305 -0.145657 -0.486814 -0.865481 0.118127 -0.496023 -0.859621 0.122528 -0.515418 -0.852754 0.0845836 -0.438899 -0.895792 0.0701803 -0.499711 -0.863788 0.0644881 -0.484178 -0.357316 -0.798684 -0.562916 -0.429172 -0.706355 -0.653199 -0.358378 -0.667006 -0.686345 -0.454124 -0.568069 -0.823962 -0.368948 -0.430075 -0.812175 -0.45076 -0.370387 -0.913537 -0.390216 -0.114813 -0.897976 -0.428177 -0.101507 -0.883534 -0.417822 0.21164 -0.892972 -0.396605 0.212851 -0.756317 -0.443213 0.481194 -0.776312 -0.36551 0.513559 -0.592614 -0.454877 0.664752 -0.58057 -0.344998 0.737505 -0.444774 -0.439287 0.780515 -0.380046 -0.330502 0.863906 -0.503715 -0.334806 -0.796352 -0.969097 -0.228204 -0.0936732 -0.286551 -0.172595 -0.94239 -0.147529 -0.0544332 -0.987559 -0.136594 -0.0483745 -0.989445 -0.969676 -0.228971 -0.0854409 -0.891901 -0.204236 -0.403486 -0.853146 -0.198445 -0.482455 -0.778797 -0.176195 -0.602022 -0.671017 -0.149165 -0.726282 -0.905872 -0.409898 -0.10667 -0.905447 -0.408145 -0.116547 -0.800848 -0.351597 -0.484792 -0.800271 -0.35108 -0.486117 -0.552188 -0.230679 -0.801172 -0.586806 -0.132261 -0.798853 -0.45767 -0.0946166 -0.884073 -0.803055 -0.583237 -0.122214 -0.803076 -0.585241 -0.112077 -0.709978 -0.498133 -0.497791 -0.713042 -0.502378 -0.489068 -0.495473 -0.330413 -0.803327 -0.553016 -0.230913 -0.800532 -0.230782 -0.0804742 -0.969672 -0.230849 -0.0448819 -0.971954 -0.181964 -0.0306927 -0.982826 -0.738644 0.50738 0.443814 0.0608817 0.834709 0.547316 -0.881215 -0.465358 0.0830775 0.103502 0.181485 0.977932 -0.0059576 0.181436 0.983385 -0.0144954 -0.314373 0.949189 -0.104515 0.515607 0.850427 -0.123515 -0.561206 0.818408 -0.179296 0.65053 0.738013 -0.350064 0.6357 0.687997 -0.304505 -0.666438 0.680542 -0.253454 0.683654 0.684381 -0.307253 0.339591 0.888973 -0.259455 -0.117771 0.958548 -0.702681 0.644151 0.302175 -0.67681 -0.645657 0.353632 -0.718025 0.560547 0.412586 -0.695068 -0.523147 0.49315 -0.761095 0.321651 0.563272 -0.736534 -0.108309 0.667673 -0.63174 0.500743 0.591744 -0.693411 0.10774 0.712442 -0.642216 0.107567 0.758939 -0.589226 -0.383775 0.711006 -0.482252 0.490183 0.726053 -0.482275 0.490103 0.726092 -0.495207 -0.0420218 0.867758 -0.772378 0.620782 0.134393 -0.776346 -0.606983 0.169879 -0.719412 0.660622 0.214534 -0.870312 0.41011 0.272704 -0.912841 -0.202663 0.354471 -0.985836 0.140864 0.0910185 -0.993127 0.083064 0.0824593 -0.992262 0.0925234 0.0828004 -0.937991 0.322549 0.127021 -0.980643 0.174795 0.0882345 -0.989283 0.119329 0.0841392 -0.993402 0.0797986 0.0823681 -0.98436 0.154825 0.0840554 -0.835084 0.54541 0.071852 -0.00335058 0.999994 0.000286962 -0.195186 0.980623 0.0167487 -0.193244 0.980574 0.03363 -0.192753 0.980673 0.0335545 -0.1875 0.980673 0.0558984 -0.188296 0.980508 0.0561188 -0.1805 0.980509 0.0775962 -0.181788 0.98023 0.0781193 -0.171562 0.980229 0.0985777 -0.172144 0.980095 0.0988967 -0.159583 0.980095 0.118099 -0.159392 0.980142 0.117964 -0.144719 0.980143 0.135556 -0.144047 0.980326 0.13495 -0.127542 0.980325 0.150651 -0.126654 0.980595 0.149643 -0.108472 0.980596 0.163298 -0.107585 0.980906 0.162017 -0.0881773 0.980906 0.173343 -0.0874255 0.981222 0.171933 -0.549007 0.834483 0.0472213 -0.859583 0.505694 0.0734198 -0.850207 0.505209 0.148029 -0.848726 0.507787 0.147707 -0.825608 0.507785 0.246018 -0.828008 0.503461 0.246841 -0.793841 0.503481 0.341061 -0.797666 0.496135 0.342897 -0.752872 0.496125 0.432486 -0.754558 0.492619 0.433553 -0.699505 0.492617 0.517708 -0.698965 0.493841 0.517271 -0.634542 0.493848 0.594534 -0.63262 0.498651 0.59257 -0.559942 0.498638 0.661684 -0.557422 0.505711 0.658436 -0.477163 0.505718 0.718725 -0.474677 0.513813 0.714618 -0.388776 0.513816 0.764753 -0.386701 0.522043 0.76022 -0.295906 0.52204 0.799947 -0.294428 0.529753 0.795408 -0.199992 0.529754 0.824235 -0.199169 0.536343 0.820164 -0.102838 0.536352 0.837706 -0.102564 0.54145 0.834453 -0.00510015 0.541439 0.840725 -0.00516903 0.544868 0.838506 0.0926693 0.544865 0.833387 0.100624 0.413893 0.904747 0.160428 0.184363 0.969677 0.0925896 0.546508 0.83232 0.0609622 0.834097 0.548239 -0.00339965 0.834099 0.551605 -0.00336479 0.832816 0.553539 -0.0675264 0.832825 0.549403 -0.0678019 0.83094 0.552216 -0.131292 0.830933 0.540659 -0.132058 0.828501 0.544193 -0.194391 0.828501 0.525165 -0.195746 0.825657 0.529126 -0.255783 0.825659 0.502855 -0.257688 0.822618 0.50685 -0.314602 0.822615 0.473635 -0.3169 0.819611 0.477297 -0.370186 0.819606 0.437274 -0.372524 0.816983 0.440187 -0.420856 0.816992 0.394215 -0.422645 0.815211 0.395983 -0.465551 0.815205 0.344533 -0.46605 0.814755 0.344923 -0.502727 0.814757 0.288855 -0.501164 0.816056 0.287902 -0.530982 0.816063 0.228253 -0.527486 0.818774 0.226643 -0.550208 0.81876 0.164023 -0.548031 0.82036 0.163314 -0.563378 0.820361 0.0980481 -0.564702 0.819418 0.0983137 -0.570617 0.819766 0.0487873 -0.190688 0.981514 0.0164069 -0.0676009 0.981229 0.18061 -0.0813523 0.972146 0.219803 -0.0564785 0.981576 0.182535 -0.0451655 0.981516 0.185977 -0.0448332 0.981769 0.184713 -0.0231896 0.98177 0.188651 -0.0230465 0.981967 0.187645 -0.00116698 0.981966 0.189056 -0.00114992 0.982097 0.188371 0.0208175 0.982097 0.187223 0.020787 0.982161 0.186892 0.479566 0.83086 0.282292 0.0458682 0.982862 0.178547 0.0620686 0.982825 0.173787 0.038983 0.993692 0.105151 0.16455 0.928289 0.333472 0.0840083 0.982674 0.16521 0.100786 0.982652 0.155683 0.116348 0.976626 0.180736 0.104152 0.986544 0.126026 0.0380073 0.99837 0.042585 0.360103 0.86658 0.345492 0.142728 0.98165 0.126463 0.141608 0.984093 0.107275 0.149999 0.982104 0.113893 0.162297 0.982106 0.0955333 0.162339 0.982097 0.0955588 0.221508 0.184066 0.957629 0.188703 0.546518 0.81591 0.221484 0.18505 0.957445 0.330533 0.185054 0.925474 0.330656 0.182308 0.925975 0.435138 0.182303 0.881715 0.435445 0.177478 0.882547 0.534808 0.177473 0.826126 0.535318 0.171099 0.827139 0.627622 0.171104 0.759483 0.628266 0.164201 0.760474 0.704746 0.164285 0.690177 0.614235 0.524923 0.589213 0.744307 0.158116 0.64885 0.787102 0.157861 0.59628 0.787596 0.153528 0.596759 0.844387 0.153637 0.51323 0.124053 0.834716 0.536526 0.188331 0.549503 0.813989 0.280971 0.549511 0.786824 0.281376 0.54785 0.787838 0.370167 0.547844 0.750229 0.371097 0.544845 0.751952 0.455615 0.544834 0.703968 0.457056 0.54095 0.706026 0.535681 0.540961 0.648388 0.537476 0.536746 0.650402 0.60883 0.536742 0.584153 0.61068 0.532832 0.585798 0.674486 0.532822 0.511047 0.675859 0.530153 0.512008 0.730708 0.530154 0.430119 0.696999 0.588104 0.410275 0.872765 0.153328 0.463435 0.730834 0.529915 0.430199 0.479442 0.830957 0.282215 0.443454 0.830956 0.335947 0.442276 0.831926 0.335099 0.400429 0.831933 0.384115 0.39885 0.833355 0.382673 0.352098 0.833358 0.426077 0.350574 0.834895 0.424321 0.299117 0.834887 0.462053 0.29789 0.836318 0.460254 0.242621 0.836325 0.491625 0.241862 0.837395 0.490175 0.183842 0.837398 0.514749 0.183508 0.838004 0.513882 0.12304 0.837998 0.53162 0.148166 0.753919 0.640041 0.03608 0.98221 0.184289 0.913379 0.152836 0.377332 0.784179 0.529266 0.323944 0.772931 0.548446 0.319037 0.81474 0.548443 0.188173 0.809746 0.556214 0.186918 0.170246 0.982136 0.0801625 0.243723 0.963288 0.112585 0.127731 0.990681 0.0472943 0.154006 0.986467 0.0562513 0.226668 0.972209 0.0585687 0.190103 -0.980788 0.0437586 0.182951 0.982603 0.0319453 0.184318 0.982609 0.022519 0.829576 0.556181 0.049649 0.825943 0.561589 0.0493619 0.404217 -0.914356 0.0237035 0.536537 0.843822 0.00962704 0.386441 0.922288 0.0069181 0.120543 0.992684 0.00692096 0.385833 0.921727 0.0393966 0.541697 0.838753 0.0553085 0.531531 0.838116 0.122623 0.53112 0.838391 0.122523 0.511044 0.839033 0.186701 0.405791 -0.898627 0.166742 0.504877 0.831074 0.233271 0.910841 0.170042 0.376103 0.960164 0.170043 0.221744 0.954595 0.200682 0.22017 0.977911 0.200663 0.0585256 0.979723 0.191556 0.0587264 0.980824 0.192199 -0.0322984 0.901664 0.429198 -0.0528362 0.587765 0.805693 -0.0734206 0.934525 0.324194 -0.146836 0.968014 0.184738 -0.169769 0.186522 0.982379 -0.0118987 0.186788 0.9824 -0.000959226 0.334215 0.942484 0.00486204 0.54263 0.838443 -0.0506472 0.406265 0.912713 -0.0436391 0.822691 0.561612 -0.0881619 0.832826 0.546326 -0.0890386 0.534528 0.843198 -0.0574216 0.547853 0.834514 -0.0586791 0.165298 -0.986085 -0.0176823 0.185808 0.982209 -0.0272135 0.965093 0.154992 -0.211122 0.963074 0.184714 -0.19588 0.827597 0.535476 -0.168367 0.820103 0.547362 -0.166809 0.54156 0.833412 -0.110171 0.538918 0.835194 -0.109625 0.184288 0.982231 -0.0354861 0.184671 0.981992 -0.0398559 0.165741 0.98555 -0.0349333 0.679414 -0.72062 -0.138213 0.338064 0.938675 -0.067843 0.187652 0.981558 -0.0364671 0.183024 0.982292 -0.0400496 0.183007 0.982296 -0.0400463 0.182696 0.982356 -0.0399842 0.177801 0.983295 -0.0389552 0.185452 0.981812 -0.0406575 0.188931 0.981115 -0.0414599 0.189012 0.981098 -0.0414944 0.967178 0.160775 -0.196767 0.964943 0.160784 -0.207443 0.961878 0.176347 -0.209028 0.920855 0.334131 -0.200957 0.846417 0.499439 -0.184769 0.825128 0.535495 -0.180026 0.558729 0.820333 -0.121968 0.53993 0.833424 -0.11781 0.214388 0.975627 -0.0467982 0.195547 0.979767 -0.0426372 0.968414 0.131319 -0.211964 0.970775 0.110865 -0.212849 0.971578 0.102558 -0.213351 0.971618 0.102558 -0.213169 0.17637 0.983566 -0.0386224 0.173635 0.984076 -0.0380289 0.541718 0.83214 -0.118676 0.558644 0.820332 -0.122359 0.827181 0.531912 -0.18122 0.846296 0.499423 -0.185363 0.975756 0.0468466 -0.213787 0.975638 0.0493315 -0.213767 0.182752 0.982292 -0.0412917 0.191761 0.98077 -0.0363134 0.962514 0.154981 -0.222594 0.0349527 0.999356 -0.00808261 0.109294 0.993721 -0.0239666 0.542718 0.831462 -0.118862 0.541724 0.832141 -0.118647 0.812193 0.555594 -0.177926 0.827199 0.531909 -0.181147 0.904816 0.376863 -0.198195 0.411331 -0.907004 -0.0902826 0.961195 0.188515 -0.20141 0.0898022 0.995765 -0.0196904 0.190781 0.980785 -0.0407986 0.27781 0.958703 -0.0609136 0.54269 0.831462 -0.118992 0.54269 0.831462 -0.118992 0.81216 0.555594 -0.178077 0.81216 0.555594 -0.178077 0.958028 0.195084 -0.21006 0.958028 0.19508 -0.210061 0.903295 0.37686 -0.205022 0.95928 0.188522 -0.210336 -0.186165 0.982464 0.0103634 -0.980139 0.182698 0.0771301 -0.00335236 0.999994 0.000266298 -0.190799 0.981513 0.0151112 -0.219188 0.975535 0.0169764 -0.256672 0.966302 0.0194865 -0.25289 0.96733 0.0178465 -0.731964 0.679298 0.0527538 -0.519766 0.853484 0.0375335 -0.549578 0.834494 0.0398016 -0.294735 0.0665408 0.953259 -0.936786 0.348113 0.0353406 -0.732912 0.678201 0.0536975 -0.885209 -0.461773 0.0563066 -0.654212 0.754825 0.0473998 -0.921277 0.383125 0.0668211 -0.99639 0.0454573 0.0716941 -0.797507 0.600508 0.0580707 -0.934535 0.34949 0.0670903 -0.83354 0.549146 0.0604055 -0.998456 0.0051486 0.055313 -0.997963 0.031928 0.0552379 -0.983384 0.173076 0.0547799 -0.940685 0.335243 0.0521945 -0.821678 0.568132 0.045511 -0.840561 0.539709 0.0465956 -0.539303 0.841579 0.0299386 -0.550239 0.834448 0.0305634 -0.15475 0.987917 0.00853026 -0.144606 0.989457 0.00801236 -0.158777 0.987276 0.00877044 -0.183377 0.98299 0.0101937 -0.185508 0.982589 0.0103232 -0.200542 0.97962 0.0112703 -0.156629 0.98762 0.00865001 -0.153324 0.98814 0.00843264 -0.997299 -0.0481018 0.0555083 -0.817946 0.573409 0.0465584 -0.940605 0.335242 0.0536273 -0.922202 0.383112 0.0526277 -0.821604 0.568131 0.0468421 -0.798317 0.600512 0.0455567 -0.539261 0.841578 0.030721 -0.52026 0.853491 0.0296903 -0.345894 0.938066 0.0197336 -0.10894 0.994027 0.00657497 -0.983457 0.173075 0.0534637 -0.862344 0.501717 0.0681439 -0.178354 0.983917 0.0098395 -0.980172 0.190616 0.0541084 -0.17739 0.984092 0.0097924 -0.359434 0.93296 0.0198417 -0.543429 0.838916 0.0300783 -0.980174 0.19061 0.0541081 -0.411993 0.910763 0.0277844 -0.828319 0.557465 0.0558592 -0.828397 0.55735 0.0558639 -0.530918 -0.846667 0.0358022 -0.535859 0.843228 0.0426828 -0.210983 0.977345 0.0168291 -0.180027 0.983554 0.0145379 -0.924102 0.380151 0.0389967 -0.186295 0.982461 0.00801784 -0.180451 0.983553 0.00778574 -0.550609 0.834428 0.0236748 -0.537072 0.843219 0.0231523 -0.841094 0.539678 0.03616 -0.829577 0.557248 0.035744 -0.970353 0.23806 0.0417361 -0.959607 -0.278955 0.0365848 0.184951 0.982018 -0.0378747 0.938389 0.284633 -0.195986 0.975919 -0.0780815 -0.203679 0.961271 0.188565 -0.201003 0.952786 0.228975 -0.199421 0.971507 0.122554 -0.202867 0.179682 0.982973 -0.0384546 0.263764 0.963009 -0.0551613 0.532256 0.839229 -0.111348 0.566645 0.815439 -0.11821 0.816084 0.552156 -0.170677 0.781592 0.601878 -0.163882 0.879796 0.438441 -0.183652 -0.486253 0.860942 -0.149458 -0.718225 0.66711 -0.197781 -0.894349 0.281477 -0.347723 -0.436761 0.860943 -0.260802 -0.650849 0.667162 -0.362341 -0.481801 0.860942 -0.163238 -0.698082 0.667147 -0.259994 -0.850714 0.409988 -0.32893 -0.802441 0.41001 -0.433567 -0.881714 -0.0456654 -0.469569 -0.809533 0.163141 -0.563952 0.0402175 0.987163 -0.154569 0.078156 0.706281 -0.703604 0.667158 0.665262 -0.335152 0.872185 0.410824 0.265551 0.461451 0.862181 0.209062 0.508689 0.860153 -0.0370517 0.340498 0.936752 0.0809744 0 1 0 0.0428651 0.999081 -0.000205898 0.695384 0.704769 -0.140506 0.707522 0.706464 -0.0179325 0.129689 0.987101 -0.0938737 0.145277 0.986856 -0.0707791 0.0916435 0.994747 -0.0456089 0.625125 0.771478 -0.118497 0.014162 0.98622 -0.164832 -0.014607 0.986395 -0.163743 -0.0241993 0.971125 -0.237343 -0.0285762 0.9911 -0.130019 -0.0384793 0.985252 -0.166724 -0.0586512 0.985264 -0.160668 -0.0639987 0.994879 -0.0782287 -0.202851 0.964104 -0.171331 -0.13626 0.984342 -0.111823 -0.136236 0.984347 -0.111804 -0.120206 0.987738 -0.0996156 -0.591286 0.788417 -0.169647 -0.683263 0.706657 -0.183814 -0.662429 0.706734 -0.248426 -0.108845 0.993098 -0.0436937 -0.492281 0.822044 -0.286188 -0.620837 0.706657 -0.339408 -0.58601 0.70675 -0.396353 -0.098817 0.992632 -0.0701232 -0.148352 0.981437 -0.121547 -0.13621 0.984354 -0.111777 -0.136267 0.98434 -0.111829 -0.176406 0.984309 -0.00411674 -0.176409 0.984308 -0.00411688 -0.506888 0.861931 -0.0118293 -0.506895 0.861926 -0.0118293 -0.744161 0.667775 -0.0173664 -0.744159 0.667777 -0.0173664 -0.884616 0.465863 -0.0206442 -0.91169 0.410281 -0.0221382 -0.952991 0.30218 -0.0222395 0.959271 0.188573 -0.210332 0.964491 0.159788 -0.210299 0.81399 0.552173 -0.180347 0.980163 -0.0232756 -0.196821 0.179518 0.982973 -0.0392028 0.494828 0.862182 -0.108574 0.531286 0.83924 -0.115804 0.831801 0.410618 0.373497 0.164526 0.986208 0.0180321 0.159918 0.986085 0.0454203 0.90237 0.332774 0.273842 0.136626 0.988695 0.0617682 0.160556 0.984343 0.0727408 0.162839 0.983937 0.0731549 0.459648 0.862172 0.213034 0.316501 0.937887 0.142111 0.678935 0.667919 0.304846 0.722364 0.66533 0.188482 0.457344 0.882614 0.108762 0.469499 0.882312 -0.0331171 0.746172 0.664209 -0.0453229 0.726621 0.668245 -0.159592 0.830544 0.41062 0.376282 0.830533 0.410646 0.376277 0.87339 0.407979 0.265975 0.911158 0.410587 0.0347696 0.747128 0.664399 0.0193374 0.714231 0.665271 0.21746 0.714199 0.665308 0.217451 0.677668 0.66821 0.307021 0.969821 0.11966 -0.212435 0.988629 0.118107 -0.0930751 0.438871 -0.898163 -0.0263774 0.991757 0.116693 0.0529216 0.966369 0.115538 0.229743 0.573589 0.806064 0.145793 0.907822 -0.0984593 0.407633 0.901385 0.144145 0.408323 0.903283 0.128859 0.409237 0.63612 -0.744115 0.20407 0.949212 0.124486 0.288963 0.98259 0.125439 0.13705 0.353037 0.935601 0.00390729 0.892361 0.408021 -0.192902 0.912676 0.404899 -0.0554997 0.914046 0.401793 -0.0555197 0.890878 0.401753 0.211967 0.888655 0.406977 0.211333 0.831901 0.410378 0.373538 0.678652 0.668261 0.304726 0.677624 0.668264 0.307001 0.461411 0.862207 0.209044 0.487432 0.860457 0.148407 0.478119 0.866182 0.145365 0.502948 0.864313 -0.00268772 0.996062 -0.0436398 0.0771725 0.644067 0.764416 -0.0290757 0.012352 0.999923 0.00126615 0.951247 0.12207 -0.283246 0.226851 0.973221 -0.0371387 0.687076 -0.367311 -0.626904 0.392037 0.695692 -0.601929 0.0893826 0.98016 -0.176909 0.893489 0.407699 -0.188307 0.733168 0.664392 -0.145077 0.505246 0.858827 -0.0845104 0.455356 0.860421 -0.228751 0.442316 0.868815 -0.222526 0.391136 0.869958 -0.300309 0.249612 0.949083 -0.192185 0.0706549 0.995293 -0.0663371 0.590483 -0.0499024 -0.805506 0.26573 0.861645 -0.432384 0.410435 0.664493 -0.624494 0.561613 0.665316 -0.49188 0.413395 -0.835472 -0.362065 0.684576 0.411496 -0.601687 0.742091 0.125566 -0.658434 0.837629 0.126636 -0.531357 -0.148857 0.411767 -0.899049 -0.0832183 -0.79253 -0.604129 -0.155691 0.125895 -0.97975 -0.130732 -0.393967 -0.90978 -0.309048 0.12684 -0.94255 -0.177581 0.910384 -0.373718 -0.373163 0.411737 -0.831398 -0.314326 0.664432 -0.678033 -0.121962 0.665233 -0.736608 -0.121951 0.665297 -0.736551 0.0787837 0.664514 -0.743111 0.898465 0.121608 -0.421867 0.42878 0.877436 -0.215067 0.815896 0.407902 -0.409792 0.814367 0.411634 -0.409102 0.667141 0.665284 -0.335143 0.561656 0.665251 -0.491919 0.350843 -0.884583 -0.307281 0.356003 0.864583 -0.354623 0.121415 0.985251 -0.120574 0.105599 0.985261 -0.134569 0.0030932 0.999987 -0.00413518 0.443562 0.553774 -0.704689 0.348202 0.706737 -0.615855 0.277773 0.706297 -0.651143 0.171191 0.858065 -0.484168 0.189812 0.718907 -0.668689 0.0729087 0.680448 -0.72916 0.0685563 0.865059 -0.496963 -0.0494637 0.86783 -0.494393 -0.0759849 -0.885218 -0.458928 -0.113758 0.864575 -0.489459 -0.227341 0.861653 -0.453729 -0.372763 -0.0566899 -0.926193 -0.355011 0.609795 -0.708602 -0.00144559 0.999993 -0.00350542 -0.123046 0.977177 -0.17316 -0.565455 0.409276 -0.716068 -0.696181 0.411744 -0.588046 -0.696527 0.410704 -0.588364 -0.672285 0.124389 -0.729768 -0.757239 0.123903 -0.641277 -0.74658 0.211813 -0.630678 -0.767218 0.12227 -0.629624 -0.767217 0.122281 -0.629623 -0.704803 0.410735 -0.578402 -0.704847 0.41061 -0.578438 -0.705312 0.41061 -0.57787 -0.575529 0.668146 -0.471537 -0.575472 0.668227 -0.471491 -0.575092 0.668227 -0.471954 -0.575085 0.668238 -0.471949 -0.568349 0.668201 -0.480091 -0.568937 0.667356 -0.480569 -0.455878 0.664494 -0.592135 -0.772619 0.0409782 -0.633546 -0.768967 0.108451 -0.630022 -0.70533 0.410561 -0.577884 -0.750204 0.409952 -0.518781 -0.617989 0.667165 -0.41591 -0.430443 0.86095 -0.271079 -0.391905 0.862154 -0.321093 -0.391811 0.862225 -0.321018 -0.391554 0.862225 -0.321332 -0.391614 0.862179 -0.321381 -0.387045 0.862156 -0.326929 -0.387723 0.861644 -0.327477 -0.300323 0.858859 -0.414932 -0.433973 0.704822 -0.561153 -0.350447 0.70696 -0.614325 -0.882252 0.410011 -0.231348 -0.967693 0.0410277 -0.24877 -0.971433 0.199755 -0.128125 -0.992242 0.122142 -0.0231616 -0.992293 0.121728 -0.0231567 -0.983922 0.121671 -0.130741 -0.904117 0.410048 -0.120137 -0.904104 0.410078 -0.120136 -0.738068 0.66756 -0.0980733 -0.738089 0.667537 -0.0980756 -0.50285 0.861787 -0.0668176 -0.502836 0.861796 -0.066816 -0.175021 0.98429 -0.0232565 -0.110307 0.993772 -0.0158072 -0.983212 0.176315 0.0469696 -0.976498 0.211529 0.0413163 -0.99194 0.122424 0.0326751 -0.189384 0.981874 0.00759281 -0.176103 0.984338 0.00810545 -0.554462 0.831943 0.0210239 -0.5061 0.862137 0.0241589 -0.743463 0.66818 0.0282585 -0.841436 0.539022 0.0379632 -0.883928 0.466266 0.0355947 -0.952403 0.302451 0.0381051 -0.981394 0.188308 0.037505 -0.182846 0.980263 -0.0751751 -0.193209 0.978302 -0.0748065 -0.545623 0.836945 -0.0426429 -0.556479 0.829804 -0.0419176 -0.834333 0.551257 -0.00180078 -0.84266 0.538445 -0.000801051 -0.983559 0.1763 0.039119 -0.856736 0.133414 -0.498201 -0.839223 0.537797 -0.0804964 -0.983126 0.182827 0.00615163 -0.998479 -5.28114e-06 0.0551259 -0.937894 0.1675 -0.303806 -0.996046 0.0384483 -0.0800838 -0.931714 0.320998 -0.169908 -0.934627 0.277396 -0.222539 -0.934011 0.278615 -0.223601 -0.998479 -1.7282e-05 0.05513 -0.932436 0.319407 -0.168945 -0.92918 0.3529 -0.109938 -0.834491 0.511791 -0.204192 -0.827933 0.554509 -0.0839499 -0.553488 0.812461 -0.183189 -0.186394 0.897537 -0.399606 -0.194682 0.812229 -0.549895 -0.187697 0.813313 -0.550719 -0.191862 0.951695 -0.239719 -0.18534 0.952759 -0.240624 -0.193985 0.896242 -0.398898 -0.554554 0.768092 -0.320165 -0.561655 0.695203 -0.448594 -0.557465 0.697319 -0.450532 -0.563771 0.60289 -0.564522 -0.560125 0.604433 -0.566498 -0.565424 0.491059 -0.662689 -0.849051 0.050783 -0.525865 -0.857034 0.0491038 -0.512915 -0.988891 0.0183294 -0.147509 -0.970467 0.0297007 -0.239398 -0.936465 0.226228 -0.268055 -0.93597 0.22706 -0.269079 -0.562448 0.49204 -0.664492 -0.566707 0.400585 -0.719982 -0.842823 0.247284 -0.478017 -0.844284 0.136861 -0.518126 -0.566038 0.223482 -0.793509 -0.567488 0.0752137 -0.819939 -0.571022 0.0748468 -0.817516 -0.193843 0.730813 -0.654475 0.372456 0.649488 -0.662904 -0.191298 0.670395 -0.716921 -0.195264 0.571466 -0.797056 -0.190462 0.57203 -0.797813 -0.195296 0.422036 -0.885294 -0.191658 0.422387 -0.885921 -0.194963 0.259154 -0.945954 -0.192688 0.259321 -0.946374 -0.194376 0.0876766 -0.977001 -0.201021 0.0873338 -0.975686 0.154602 0 -0.987977 0.154602 0 -0.987977 0.448852 0 -0.893606 0.448852 0 -0.893606 0.498065 0.014339 -0.867021 0.836609 0.170876 -0.520467 0.509843 0.082837 -0.85627 0.704298 0.00552535 -0.709883 0.722582 0.0829243 -0.686294 0.866407 0.162715 -0.472083 0.636513 0.307582 -0.70728 0.60919 0.163623 -0.775961 0.41468 0.240138 -0.87771 0.349188 0.266456 -0.89837 -0.144927 0.379249 -0.913874 0.118409 0.289129 -0.949939 0.448718 0.0244296 -0.893339 0.164327 0.0560929 -0.98481 0.154342 0.0578937 -0.98632 0.988207 0.0136151 -0.152516 0.987843 -0.13688 0.073687 0.87778 0.0870508 -0.471088 0.838938 0.191944 -0.509254 0.863681 0.0102335 -0.503934 0.753315 0.250968 -0.607891 0.531325 0.358415 -0.767615 0.44471 0.396291 -0.803235 0.180097 0.462732 -0.868012 0.841399 0.125756 -0.525579 0.0964174 0.197363 -0.975578 0.186124 0.180016 -0.965895 0.319117 0.139594 -0.937378 0.52836 0.0779966 -0.84543 0.553433 0.185424 -0.811991 0.719877 0.101493 -0.686641 0.74633 0.241073 -0.620383 0.943785 0.0718658 -0.322653 0.178382 0.798782 -0.574566 0.553788 0.821932 -0.13322 0.990703 0.0585141 -0.122816 0.699568 0.698599 -0.150216 0.549243 0.814367 -0.187453 0.847243 0.510375 -0.1473 0.761241 0.379814 -0.525599 0.874271 0.281211 -0.395691 0.95086 0.171059 -0.258078 0.533644 0.536184 -0.654012 -0.203858 0.643795 -0.737543 0.185651 0.617244 -0.764555 0.99848 -7.55507e-07 -0.0551187 0.914049 0.305764 -0.266502 0.910281 0.243878 -0.334533 0.538309 0.534348 -0.651687 0.980794 0.157049 -0.115669 0.91745 0.355834 -0.177954 0.912919 0.3077 -0.26814 0.535947 0.675369 -0.506594 0.541891 0.671868 -0.504923 0.187922 0.797356 -0.573505 0.183352 0.706056 -0.684008 0.183744 0.936116 -0.299874 0.190785 0.967858 -0.163865 0.562095 0.816311 -0.132985 0.979781 0.17088 -0.104068 0.834356 0.528851 -0.155456 0.827943 0.506086 -0.241635 0.539092 0.77516 -0.329402 0.545791 0.770815 -0.328567 -0.391194 0.865714 -0.312261 0.188413 0.891588 -0.41179 0.608226 0.000742449 -0.793764 0.539067 0 -0.842263 0.47972 0.00449708 -0.87741 0.484645 0 -0.874711 0.97294 0 -0.231057 0.988379 0.0130359 -0.151448 0.954168 0.0001513 -0.299271 0.81544 -0.00029814 -0.578841 0.847944 0.0080156 -0.530025 0.721097 -0.000854563 -0.692834 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.62308e-05 0.0881425 -0.996108 0.0134661 0.0725776 -0.997272 -0.00913713 0.220963 -0.975239 0.0216278 0.261126 -0.965062 -7.72459e-06 0.31755 -0.948242 0.000130936 0.426142 -0.904656 -0.0411864 0.457739 -0.888132 0.029168 0.576557 -0.816536 -0.0407341 0.634074 -0.772199 -1.73916e-06 0.992442 -0.122714 -0.0754893 0.993739 -0.0823619 0.055252 0.953036 -0.297775 -0.00966884 0.967153 -0.254013 0.00798315 0.911788 -0.410584 0.0155251 0.909126 -0.416233 -0.0227972 0.817105 -0.576037 -0.0436581 0.823407 -0.565769 0.0184315 0.722919 -0.690687 -9.66463e-05 0.73945 -0.673212 -9.85846e-05 0.677579 -0.73545 -1.62962e-05 0 -1 -1.62962e-05 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.99848 1.25527e-06 -0.0551183 0.99848 -6.27921e-07 -0.0551188 0.99848 -6.40575e-07 -0.0551188 0.99848 0 -0.0551179 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.214175 0 0.976795 0.214175 -1.01923e-07 0.976795 0.214175 1.86291e-07 0.976795 -0.214176 1.43546e-06 -0.976795 -0.214176 -4.06203e-07 -0.976795 -0.214176 -1.89323e-07 -0.976795 -0.214175 4.16569e-07 -0.976795 -0.214177 0 -0.976795 0.374769 0 0.927118 0.716842 -0.00683429 0.697202 0.718014 -0.00709062 0.695993 0.409804 0.00599621 0.912154 0.961607 -0.00975284 0.274258 0.945374 -0.00325116 0.325971 0.856042 0.000896209 0.516906 0.976737 -0.0108594 -0.214164 0.995015 0.000282252 -0.0997295 0.993365 -0.000177325 0.115007 0.758671 0.000408259 -0.651474 0.62521 -0.0341374 -0.77971 0.728149 -0.014101 -0.685273 0.859992 0.00207407 -0.510304 0.948849 -0.00231563 -0.315721 -0.0475299 0 -0.99887 -0.150622 -0.0171348 -0.988443 -0.00750187 -0.000495262 -0.999972 0.193448 0.000315725 -0.981111 0.359348 -0.010681 -0.933143 0.379925 -0.00768719 -0.924986 0.523843 -0.000105255 -0.851815 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.055119 2.97148e-08 -0.99848 -0.0551189 0 -0.99848 0.0551182 -1.03738e-08 0.99848 0.0551182 -3.07208e-08 0.99848 0.0551181 0 0.99848 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.88154 2.57367e-07 -0.47211 -0.88154 0 -0.47211 0.88154 0 0.47211 0.88154 1.1349e-07 0.47211 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.573129 7.78384e-08 0.819465 -0.573129 0 0.819465 0.573128 0 -0.819466 0.573129 8.16956e-07 -0.819465 -0.437812 0 0.899067 -0.427764 -0.0025726 0.903887 0.139583 -0.000480936 0.99021 0.0172267 -0.0112273 0.999789 -0.026872 -0.0187407 0.999463 -0.174985 0.00164045 0.98457 -0.290877 -0.000168673 0.95676 0.302451 0.000586989 0.953165 0.449978 -0.0151809 0.892911 0.443405 -0.0163702 0.896172 0.769085 -0.00485427 0.639128 0.682661 4.16083e-05 0.730735 0.569564 -0.000114921 0.821947 0.993204 0.00155311 0.116375 0.998873 -0.0396009 -0.0261513 0.994543 -0.0173919 0.102871 0.967807 -0.00015858 0.251693 0.819465 0.000362152 0.573129 0.917188 -0.0506142 0.395228 0.86636 -0.0263003 0.498726 0.887957 -0.0368183 -0.45845 0.948268 -0.0104417 -0.317298 0.979214 -0.000411339 -0.202831 0.929758 0.00152161 -0.368169 0.702297 -0.00100366 -0.711883 0.699484 0 -0.714649 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.282902 -0.958326 0.0397253 -0.544629 -0.181765 -0.818743 0.975062 -0.0962441 -0.199977 0.971488 -0.122655 -0.202894 0.963365 -0.189104 -0.190178 0.972061 -0.132369 -0.193843 0.981288 -0.0494891 -0.186075 0.973968 -0.105028 -0.200885 0.973968 -0.105028 -0.200885 0.999736 -0.0183615 -0.0138176 0.989096 -0.104569 -0.103704 0.974914 -0.104644 -0.196448 0.914667 -0.200271 0.351106 0.952395 -0.240789 0.186989 0.962463 -0.217339 0.162568 0.972178 -0.217175 -0.0877751 0.877167 -0.218352 0.427668 0.877142 -0.218272 0.427761 0.877297 -0.218274 0.427442 0.877483 -0.219503 0.42643 0.910667 -0.206271 0.357962 0.959852 -0.189941 0.206413 0.90954 -0.189422 0.36994 0.911932 -0.183518 0.367016 0.884403 -0.196102 0.423527 0.881254 -0.205553 0.425605 0.878359 -0.209679 0.429558 0.980693 -0.192838 0.0324616 0.972769 -0.184376 0.140452 0.946978 -0.226754 0.22763 0.982318 -0.183391 0.0376843 0.974006 -0.183524 -0.132779 0.970404 -0.211747 -0.116097 0.943497 -0.148524 -0.296235 0.942661 -0.182956 -0.279137 0.875515 -0.183224 -0.447105 0.877011 -0.20217 -0.435867 0.791914 -0.161461 -0.5889 0.790808 -0.154829 -0.592157 0.676854 -0.204034 -0.707276 0.669437 -0.183419 -0.719869 0.551672 -0.183223 -0.813687 0.538279 -0.147319 -0.829791 0.405865 -0.210338 -0.889399 0.386453 -0.178191 -0.904932 0.252607 -0.189856 -0.948759 0.24916 -0.183273 -0.950963 0.0910911 -0.183224 -0.978842 0.143694 -0.279956 -0.949198 0.0633557 -0.181545 -0.98134 -0.0739437 -0.186102 -0.979744 -0.0756215 -0.183245 -0.980154 -0.236118 -0.183225 -0.954294 -0.182922 -0.270156 -0.94528 -0.395591 -0.181947 -0.900224 -0.402789 -0.197677 -0.893692 -0.27498 -0.174977 -0.945394 -0.687605 -0.201832 -0.697469 -0.590545 -0.16602 -0.789743 -0.501905 -0.255825 -0.826223 -0.772231 -0.158566 -0.615236 -0.774342 -0.167386 -0.610226 -0.773861 -0.170188 -0.610061 -0.761625 -0.183566 -0.621475 -0.76607 -0.174412 -0.618641 -0.677668 -0.174316 -0.714409 -0.84093 -0.198922 -0.503256 -0.803827 -0.173787 -0.568912 -0.777663 -0.201664 -0.595459 -0.767451 -0.172142 -0.617565 -0.767381 -0.172213 -0.617632 -0.919237 -0.120825 -0.374705 -0.902583 -0.092304 -0.420504 -0.867765 -0.0921444 -0.488358 -0.967386 -0.09667 -0.234134 -0.964923 -0.167282 -0.202336 -0.984892 -0.0884598 -0.148868 -0.990122 -0.130995 -0.0499907 -0.992892 -0.109374 0.0469435 -0.994148 -0.103064 0.0323723 -0.994514 -0.0960766 -0.0413729 -0.99016 -0.123706 0.0654173 -0.992305 -0.109267 0.0582395 -0.99274 -0.102897 0.0622869 -0.98458 -0.158063 0.0749545 -0.979813 -0.187823 0.0684743 -0.179066 -0.983518 0.0250436 -0.0756999 -0.997064 0.011492 -0.0765092 -0.997003 0.0114431 -0.0767678 -0.996982 0.0115353 -0.0767208 -0.996983 0.0117951 -0.234812 -0.971569 0.030272 -0.234753 -0.971552 0.0312633 -0.161117 -0.986916 -0.00617957 -0.160845 -0.986956 0.00681368 -0.172927 -0.984787 0.0170776 -0.156479 -0.987542 -0.0165872 -0.175802 -0.984396 -0.00763851 -0.16467 -0.980025 -0.111514 -0.179404 -0.978357 -0.103107 -0.157559 -0.982363 -0.100694 -0.182856 -0.980645 -0.0699884 -0.170499 -0.978691 -0.114431 -0.183464 -0.974698 -0.127691 -0.177949 -0.977022 -0.117313 0.0680379 -0.997597 0.0130798 0.0760154 -0.996942 0.0181329 0.0766512 -0.997053 0.00309725 0.0753429 -0.997155 0.00248742 0.0769305 -0.997025 -0.00471469 0.0767205 -0.997034 -0.0060253 0.0857772 -0.996294 -0.00632338 0.083946 -0.996455 -0.00561107 0.239001 -0.970737 -0.0234236 0.243688 -0.969582 -0.0229729 0.151415 -0.983845 0.0955137 0.159032 -0.983562 0.0855306 0.162199 -0.982311 0.0935775 0.174379 -0.983288 0.0523122 0.174972 -0.983141 0.0530848 0.191268 -0.981419 0.0152865 0.189163 -0.981858 0.0131307 0.1872 -0.982015 -0.0245555 0.182279 -0.982871 -0.0271809 0.183376 -0.981855 -0.0483126 0.184086 -0.981206 -0.0578521 0.179084 -0.981993 -0.0601486 0.168488 -0.981942 -0.086029 0.15265 -0.984318 -0.0884074 0.155799 -0.980971 -0.115853 0.145204 -0.982046 -0.120419 0.130807 -0.981941 -0.136679 0.13081 -0.981941 -0.13668 0.106174 -0.981941 -0.156588 0.105405 -0.982068 -0.156305 0.0788005 -0.98182 -0.172687 0.0780727 -0.981949 -0.172282 0.0486904 -0.981941 -0.182814 0.0402045 -0.9836 -0.175828 0.0180044 -0.980915 -0.193601 0.0107505 -0.982025 -0.188444 -0.0142177 -0.981942 -0.188646 -0.0231029 -0.98447 -0.174027 -0.0465754 -0.981031 -0.188174 0.210781 -0.967661 0.138581 0.199344 -0.97134 0.129464 0.200945 -0.971465 0.126002 0.200518 -0.971645 0.125295 0.213619 -0.972123 0.0966605 0.216594 -0.971152 0.0997494 0.228714 -0.972112 0.0518467 0.232197 -0.971155 0.0542543 0.234482 -0.972108 0.00499836 0.238318 -0.971164 0.00668381 0.233928 -0.972007 -0.0219054 0.410151 -0.911054 -0.0419103 0.398467 -0.916165 -0.0431912 0.398488 -0.916161 -0.0430867 0.396943 -0.916829 -0.0431529 0.404433 -0.914515 0.00977609 0.398912 -0.916962 0.00701043 0.394358 -0.914497 0.0904251 0.389424 -0.916974 0.0866528 0.368251 -0.914504 0.167555 0.364096 -0.917014 0.162846 0.343794 -0.916032 0.206619 0.344428 -0.91555 0.207696 0.342438 -0.91534 0.211869 0.359742 -0.905534 0.224931 0.0735683 -0.997047 0.0220271 0.0709075 -0.996946 0.0327228 0.0699201 -0.997018 0.0326554 0.0649036 -0.996986 0.0425084 0.0652002 -0.996966 0.042524 0.0642763 -0.996937 0.0445579 0.0686507 -0.996541 0.0468269 0.0690854 -0.996556 0.0458705 0.223824 -0.968375 0.110239 0.151142 -0.983829 0.0961097 0.362761 -0.905869 0.218645 0.525827 -0.807733 0.266594 0.508742 -0.806299 0.301769 0.488981 -0.823475 0.287727 0.490856 -0.823678 0.283928 0.490149 -0.82453 0.282673 0.516218 -0.825773 0.227195 0.520456 -0.821612 0.23255 0.551361 -0.82567 0.119457 0.556476 -0.821579 0.123864 0.564138 -0.825652 0.00690356 0.569972 -0.8216 0.0102915 0.559939 -0.82562 -0.0694174 0.561366 -0.824654 -0.0693761 0.560724 -0.824799 -0.0727692 0.57195 -0.817111 -0.072125 0.929393 -0.328132 -0.168993 0.933143 -0.317672 -0.168309 0.933031 -0.317679 -0.168917 0.932985 -0.317814 -0.168918 0.948689 -0.3153 -0.0239822 -0.722576 -0.644359 -0.250371 -0.708775 -0.664831 -0.235875 -0.737525 -0.662399 -0.13147 -0.724647 -0.678353 -0.121344 -0.736751 -0.676011 -0.0143772 -0.726783 -0.686813 -0.00859507 -0.724342 -0.686065 0.0681515 -0.719548 -0.690878 0.07027 -0.719411 -0.69084 0.0720347 -0.828673 -0.472118 -0.300677 -0.821073 -0.491518 -0.290258 -0.856075 -0.489899 -0.164728 -0.848533 -0.505269 -0.157146 -0.863475 -0.503634 -0.0276377 -0.857457 -0.514035 -0.0231491 -0.855051 -0.513793 0.0700363 -0.851926 -0.518702 0.0719084 -0.851482 -0.518621 0.0775289 -0.809922 -0.580425 0.0844632 -0.916222 -0.393496 0.0754808 -0.946195 -0.315644 0.0713019 -0.946468 -0.315665 0.0674877 -0.947738 -0.312098 0.0662428 -0.949353 -0.311892 -0.0381205 -0.951577 -0.304696 -0.0407533 -0.933721 -0.305386 -0.186828 -0.9363 -0.294691 -0.191046 -0.895818 -0.295345 -0.332088 0.836823 -0.53013 -0.136709 0.842516 -0.521164 -0.136219 0.842791 -0.521124 -0.134661 0.842402 -0.521751 -0.134663 0.855822 -0.517248 -0.00482339 0.853382 -0.52124 -0.00699048 0.839633 -0.517241 0.165765 0.837643 -0.521255 0.163239 0.789697 -0.517316 0.329791 0.788136 -0.521543 0.326856 0.755628 -0.521098 0.396842 0.755991 -0.519916 0.397699 0.755229 -0.519871 0.399204 0.767108 -0.496337 0.406442 0.772558 -0.496623 0.395627 0.737097 -0.567901 0.3663 0.755604 -0.568085 0.3261 0.759915 -0.554199 0.339696 0.808728 -0.55728 0.188143 0.813768 -0.546545 0.197662 0.835192 -0.548557 0.0392304 0.838964 -0.542403 0.0440167 0.831993 -0.54325 -0.112551 0.832562 -0.542483 -0.112043 0.801438 -0.542543 -0.251682 0.801404 -0.542583 -0.251703 0.748098 -0.542585 -0.382036 0.748123 -0.542557 -0.382026 0.674068 -0.542555 -0.501265 0.674078 -0.542545 -0.501262 0.580783 -0.542569 -0.606886 0.580789 -0.542563 -0.606886 0.471394 -0.54256 -0.695281 0.471411 -0.542543 -0.695283 0.348734 -0.542566 -0.764204 0.348724 -0.542576 -0.764201 0.216123 -0.542572 -0.81173 0.21616 -0.542531 -0.811748 0.0778365 -0.54255 -0.83641 0.0778078 -0.542585 -0.836389 -0.0632171 -0.542583 -0.83762 -0.0631816 -0.542533 -0.837655 -0.201762 -0.542545 -0.815437 -0.201781 -0.542579 -0.81541 -0.342873 -0.542257 -0.767069 -0.341826 -0.539924 -0.76918 -0.478609 -0.538738 -0.693322 -0.476745 -0.532894 -0.699098 -0.598806 -0.530819 -0.599718 -0.597434 -0.52334 -0.607608 -0.67956 -0.522239 -0.515233 -0.678947 -0.51335 -0.524883 -0.691871 -0.512963 -0.508117 -0.698258 -0.490224 -0.521647 -0.691373 -0.490413 -0.530564 -0.683386 -0.519865 -0.512566 -0.68456 -0.519827 -0.511036 -0.681905 -0.543287 -0.48974 -0.410075 -0.910718 0.0493075 -0.399142 -0.915563 0.0492971 -0.39911 -0.915551 0.0497765 -0.404045 -0.913463 0.0482985 -0.405174 -0.914179 0.0105532 -0.417041 -0.908872 0.0052706 -0.410225 -0.9106 -0.0502205 -0.425977 -0.902758 -0.0597666 -0.410198 -0.904708 -0.115066 -0.428262 -0.894337 -0.129434 -0.368504 -0.894554 -0.252938 -0.0745803 -0.983713 -0.163541 -0.0731976 -0.981619 -0.176259 -0.111901 -0.981499 -0.155361 -0.111718 -0.980683 -0.16056 -0.141071 -0.981098 -0.132463 -0.142054 -0.980117 -0.138532 -0.163163 -0.979829 -0.115384 -0.164751 -0.978989 -0.120154 -0.165858 -0.978968 -0.118799 -0.944578 -0.0967884 -0.313694 -0.920712 -0.170397 -0.351076 -0.898066 -0.281987 -0.337581 -0.835889 -0.282597 -0.470563 -0.770699 -0.473549 -0.426351 -0.725344 -0.542101 -0.424268 -0.676887 -0.646841 -0.351312 -0.545945 -0.790069 -0.278811 -0.586064 -0.787368 -0.191261 -0.568075 -0.804115 -0.175183 -0.590342 -0.801538 -0.0950423 -0.574213 -0.814371 -0.0841401 -0.583658 -0.811995 -0.00278713 -0.571392 -0.82067 0.00330365 -0.56951 -0.819739 0.0607162 -0.564025 -0.823376 0.0626725 -0.563419 -0.823141 0.0707039 -0.580159 -0.811574 0.0690146 0.713799 -0.69294 -0.101612 0.713794 -0.692945 -0.101613 0.713999 -0.692901 -0.100465 0.71305 -0.693875 -0.100479 0.72489 -0.688838 0.006089 0.720304 -0.693652 0.00290345 0.709133 -0.688826 0.150494 0.705223 -0.693672 0.146559 0.664797 -0.688887 0.288927 0.66162 -0.693868 0.284264 0.631441 -0.692824 0.348248 0.632047 -0.691681 0.34942 0.63066 -0.691555 0.352164 0.648392 -0.66869 0.363926 0.652511 -0.669052 0.355807 0.459614 -0.848197 0.26328 0.477024 -0.849228 0.226407 0.486081 -0.838539 0.246124 0.521062 -0.842723 0.13532 0.530876 -0.834252 0.148974 0.546139 -0.837044 0.0330209 0.553041 -0.832221 0.0394061 0.547846 -0.83337 -0.0732007 0.548833 -0.832775 -0.0725885 0.528038 -0.832864 -0.165873 0.527983 -0.832894 -0.165895 0.49289 -0.832893 -0.251692 0.492924 -0.832875 -0.251685 0.444124 -0.832875 -0.330262 0.444133 -0.83287 -0.330262 0.382651 -0.832888 -0.399845 0.382668 -0.832879 -0.399847 0.310592 -0.832878 -0.458091 0.310613 -0.832866 -0.458097 0.229762 -0.832882 -0.503505 0.229758 -0.832884 -0.503503 0.142415 -0.832882 -0.534814 0.142448 -0.832861 -0.534838 0.0512663 -0.832874 -0.551084 0.0512475 -0.832887 -0.551065 -0.041626 -0.832886 -0.551876 -0.0415984 -0.832862 -0.551916 -0.132951 -0.83287 -0.537263 -0.132968 -0.83289 -0.537228 -0.227881 -0.832586 -0.504848 -0.227115 -0.831166 -0.507525 -0.321572 -0.830011 -0.455713 -0.32075 -0.826459 -0.462694 -0.406327 -0.824355 -0.394129 -0.406649 -0.819833 -0.403126 -0.464126 -0.818395 -0.338846 -0.466225 -0.812354 -0.350306 -0.478371 -0.811799 -0.334878 -0.49338 -0.79465 -0.353706 -0.490817 -0.794774 -0.356978 -0.472013 -0.816713 -0.331938 -0.47241 -0.816691 -0.331429 -0.461809 -0.83329 -0.303907 -0.507222 -0.829366 -0.23426 -0.163555 -0.983869 -0.0724731 -0.175844 -0.983301 -0.0468904 -0.172144 -0.984168 -0.0421911 -0.169765 -0.985087 -0.0279963 -0.000320065 -1 0.000165479 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.000188854 -1 0.000139484 -0.982213 -0.172269 0.0747068 -0.996533 -0.0718277 0.0419928 -0.994679 -0.0720811 0.0736096 -0.999081 -0.0196272 0.0381102 -0.996658 -0.0217133 0.0787525 -0.988778 -0.139423 0.053653 -0.89843 -0.269078 -0.347017 -0.981861 -0.17339 0.0767171 -0.904221 -0.422123 0.0647872 -0.977605 -0.172696 0.120273 -0.849188 -0.518507 0.100156 -0.885232 -0.452336 0.108425 -0.791653 -0.595967 0.134566 -0.950518 -0.241145 0.195868 -0.949243 -0.241057 0.202063 -0.949771 -0.242719 0.197542 -0.962056 -0.211112 0.17286 -0.991799 -0.0592799 0.113228 -0.988677 -0.0593494 0.137827 -0.996675 -0.0238056 0.0779259 -0.994435 0 0.105352 0.965038 -0.137273 -0.223289 0.986549 0 -0.163468 0.980372 -0.0316334 -0.194601 0.975379 -0.0723165 -0.208343 0.939672 -0.285789 -0.187994 0.968443 -0.16008 -0.19103 0.900082 -0.412251 -0.141074 0.843175 -0.520542 -0.134506 0.784395 -0.606146 -0.131574 0.942018 -0.321847 -0.0949563 0.966638 -0.246512 -0.0695968 0.97707 -0.0583392 -0.204768 0.978103 -0.0724229 -0.195114 0.980027 -0.0308273 -0.19646 0.979686 -0.161051 -0.119491 0.979048 -0.16619 -0.117668 0.965164 -0.248415 -0.0821508 -0.677829 -0.725995 0.116103 -0.430571 -0.860073 0.273649 -0.795117 -0.57916 0.179897 -0.38533 -0.901125 0.198732 -0.282483 -0.935336 0.212953 0.983328 -0.105265 -0.148272 0.964865 -0.242679 -0.100705 0.582914 -0.809851 0.0659723 0.723834 -0.689955 -0.00510366 0.812551 -0.5828 -0.0102292 0.847219 -0.52908 -0.0478981 0.938415 -0.328348 -0.107542 0.772763 -0.629932 -0.0776118 0.893283 -0.444981 -0.0635443 0.780713 -0.623305 0.0444827 0.707308 -0.705082 0.0507489 0.593697 -0.794449 0.127967 0.502598 -0.853941 0.134838 0.424244 -0.887315 0.180802 0.319894 -0.928544 0.188345 0.293819 -0.934065 0.20296 0.156002 -0.964413 0.213475 0.15033 -0.96461 0.216632 0.0560398 -0.981203 0.18466 0.037092 -0.981739 0.186584 0.179453 -0.979158 0.0951139 0.141026 -0.98072 0.135278 0.264007 -0.95767 0.114755 0.285643 -0.952703 0.103758 0.376899 -0.921447 0.0942432 0.417614 -0.906128 0.0673044 0.520335 -0.852897 0.04264 0.5879 -0.808923 0.00418799 0.592967 -0.805218 0.00369348 0.680095 -0.732998 -0.0135921 -0.00446857 -0.981152 0.193187 -0.0455253 -0.978762 0.199879 -0.360652 -0.896996 0.255593 -0.423076 -0.853712 0.303615 -0.215822 -0.9398 0.264946 -0.256949 -0.945147 0.20168 -0.153607 -0.969148 0.192761 -0.0479225 -0.98003 0.192987 -0.0493958 -0.979795 0.193809 0.0360352 -0.983855 0.175302 0.0247821 -0.98258 0.184179 0.0251007 -0.982585 0.184112 0.01266 -0.981197 0.192595 0.0205653 -0.982073 0.187376 0.0312901 -0.981075 0.191084 0.034434 -0.976162 0.214292 0.0411368 -0.976119 0.213309 0.0392254 -0.975847 0.214905 -0.0427897 -0.97305 0.226591 -0.0431733 -0.972957 0.226916 -0.274471 -0.927593 0.253451 -0.084249 -0.964737 0.249371 -0.233442 -0.931897 0.27762 -0.23371 -0.932216 0.276321 -0.480497 -0.819593 0.312072 -0.499701 -0.833838 0.234549 -0.773977 -0.587587 0.236013 -0.787466 -0.591558 0.17308 -0.906342 -0.393785 0.153226 -0.974055 -0.188209 0.125676 -0.960731 -0.235123 0.147356 -0.948787 -0.256411 0.184546 -0.75132 -0.626299 0.208012 -0.743084 -0.623287 0.243596 -0.679395 -0.668272 0.303041 -0.660876 -0.704392 0.258988 -0.647676 -0.697473 0.306671 -0.558436 -0.797558 0.228146 0.0243446 -0.983842 0.177376 0.108569 -0.979028 0.172385 0.108476 -0.979043 0.17236 0.261608 -0.955924 0.133304 0.342068 -0.929766 0.136106 0.423708 -0.901313 0.0900357 0.584692 -0.808539 0.0663268 0.965456 -0.237298 -0.10763 0.956714 -0.282597 -0.069555 0.812833 -0.582474 -0.00519944 0.787701 -0.615205 0.032407 0.584122 -0.806536 0.0911153 0.560722 -0.819832 0.116047 0.344028 -0.924724 0.162879 0.333718 -0.926795 0.172289 0.112769 -0.971416 0.208888 0.118927 -0.971783 0.2037 0.0161547 -0.975898 0.217629 0.0172935 -0.976085 0.216701 0.0244633 -0.976135 0.215784 0.0248273 -0.976255 0.215199 0.0340505 -0.976253 0.213941 0.11863 -0.985334 0.122653 0.0487025 -0.990146 0.131301 0.053452 -0.984474 0.167193 0.0120417 -0.984864 0.172908 0.073529 -0.991634 0.106092 0.0357686 -0.991239 0.127142 -0.0128043 -0.990911 0.13391 -0.0297054 -0.988023 0.151422 -0.100154 -0.983906 0.147981 -0.127885 -0.977127 0.169905 -0.230687 -0.955027 0.186301 -0.201875 -0.964625 0.169544 -0.370264 -0.904647 0.210995 -0.333182 -0.924568 0.184834 -0.56917 -0.802594 0.178575 -0.510444 -0.846091 0.153547 -0.575609 -0.800953 0.164768 -0.768851 -0.614717 0.176043 -0.770179 -0.614986 0.169163 -0.847525 -0.45401 0.274911 -0.877811 -0.437498 0.195047 -0.857111 -0.432912 0.279192 -0.914859 -0.353678 0.194796 -0.903997 -0.351854 0.242876 -0.942495 -0.284332 0.175665 -0.945743 -0.28463 0.156701 -0.559603 -0.806306 0.19161 -0.536792 -0.81868 0.204001 -0.524572 -0.811298 0.258109 -0.258586 -0.935769 0.23973 -0.248874 -0.924964 0.287235 -0.03939 -0.967102 0.251321 -0.0376562 -0.967051 0.251783 0.0372924 -0.978984 0.200497 0.0163344 -0.97884 0.203975 0.0303443 -0.98197 0.186587 0.0369694 -0.981916 0.185673 0.0230777 -0.97902 0.202453 0.0578968 -0.978357 0.198659 0.0181504 -0.974693 0.222811 0.155557 -0.965398 0.209303 0.121874 -0.965616 0.229635 0.321209 -0.923629 0.209129 0.335503 -0.920541 0.200107 0.503726 -0.845075 0.179188 0.561334 -0.815893 0.138645 0.708051 -0.696667 0.115405 0.787995 -0.614149 0.0434204 0.893117 -0.44936 0.0204143 0.955891 -0.282827 -0.079255 -0.578033 -0.775961 0.252513 0.20161 -0.928566 0.311638 0.332958 -0.884945 0.325592 -0.278313 -0.773797 0.569017 -0.430829 -0.591617 0.681451 0.634947 -0.0790592 0.7685 -0.811171 -0.103894 0.575506 -0.994082 -0.0703089 0.082813 -0.994083 -0.0694157 0.0835488 -0.993903 -0.0808719 0.0749473 -0.994794 -0.0390593 0.0941263 -0.993507 -0.0787388 0.0821187 -0.994152 -0.0651977 0.0860919 -0.994053 -0.0713632 0.0822497 -0.994065 -0.0709194 0.0824999 -0.734995 -0.125879 0.666286 -0.493134 -0.0997944 0.864211 -0.549726 -0.106721 0.8285 -0.606254 -0.190699 0.772069 -0.632383 -0.134951 0.762811 -0.692449 -0.118801 0.711618 0.213487 -0.0602302 0.975087 0.163002 -0.0542695 0.985132 0.0989548 -0.0544065 0.993604 0.105081 -0.0625375 0.992495 -0.0177944 -0.051042 0.998538 -0.0153347 -0.0545558 0.998393 -0.134744 -0.0703753 0.988378 -0.14933 -0.052426 0.987397 -0.249882 -0.0881714 0.964254 -0.260524 -0.0769081 0.962399 -0.325278 -0.0822939 0.942031 0.529381 -0.0464109 0.847114 0.541978 -0.0712572 0.837366 0.430176 -0.0458385 0.901581 0.44154 -0.065586 0.894842 0.324514 -0.0448689 0.944816 0.335647 -0.0625744 0.939907 0.225115 -0.0462681 0.973233 0.751843 -0.0708994 0.655519 0.712829 -0.0661634 0.69821 0.881111 -0.0691856 0.467821 0.852772 -0.0639736 0.51835 0.997681 -0.0325612 0.0597732 0.997269 -0.0458215 -0.0579173 -0.336942 -0.821586 0.459855 -0.345269 -0.763357 0.545963 -0.394508 -0.712393 0.580396 -0.450952 -0.721413 0.525553 -0.404799 -0.672358 0.619735 -0.0925536 -0.851345 0.516377 -0.182396 -0.851608 0.491422 -0.202469 -0.864023 0.460945 -0.251257 -0.877686 0.408089 -0.208241 -0.669999 0.712557 -0.103451 -0.612463 0.783701 -0.169921 -0.59945 0.782168 -0.330336 -0.460541 0.823881 -0.411889 -0.179202 0.89344 -0.413702 -0.138894 0.899755 -0.403537 -0.161473 0.900602 0.763164 -0.215476 0.609222 0.365173 -0.892644 0.264266 0.302511 -0.912333 0.275926 0.537218 -0.786623 0.304336 0.47981 -0.841619 0.247913 0.422197 -0.889704 0.173713 0.414084 -0.887753 0.201071 0.389236 -0.887905 0.245193 0.70461 -0.596746 0.383952 0.704993 -0.597572 0.38196 0.771908 -0.451343 0.447713 0.844478 -0.398497 0.357851 0.804089 -0.28698 0.520657 0.818975 -0.209337 0.534283 0.806004 -0.14407 0.57411 0.805594 -0.148189 0.573636 0.793497 -0.0944385 0.601202 0.993409 -0.0698981 -0.0908414 0.992657 -0.0712364 -0.0977573 0.985706 -0.167444 -0.0185867 0.992031 -0.107532 0.0656587 0.955173 -0.289344 0.0626433 0.889913 -0.420159 0.177545 0.997812 0.0024603 0.0660741 0.996627 -0.0483088 0.066341 0.99142 -0.120038 0.0517359 0.462264 -0.838193 0.289386 0.594202 -0.772804 0.222931 0.652948 -0.71366 0.253668 0.744625 -0.639898 0.189907 0.828711 -0.516152 0.21639 0.891129 -0.431781 0.139475 0.935417 -0.294471 0.195659 0.983755 -0.175295 0.0386899 0.990772 -0.126322 0.0491319 0.995339 -0.0483612 -0.0834394 0.999373 -0.0134968 -0.0327235 0.924232 -0.00925694 0.381718 0.908205 -0.102542 0.40577 0.903952 -0.147264 0.401478 0.891701 -0.196042 0.407967 0.85946 -0.345572 0.376707 0.833381 -0.406363 0.374626 0.798837 -0.494056 0.343173 0.759655 -0.559708 0.331137 0.973868 0.0324899 0.224777 0.966664 -0.0723092 0.245625 0.966961 -0.0663277 0.246144 0.958551 -0.131649 0.252684 0.948986 -0.205552 0.239112 0.929721 -0.282188 0.236618 0.939831 -0.232227 0.250575 0.862564 -0.434314 0.259528 0.831048 -0.507266 0.228124 0.745025 -0.586668 0.317424 0.698073 -0.651322 0.297445 0.603074 -0.708449 0.366609 0.625252 -0.692188 0.360467 0.988812 -0.0863179 -0.121655 0.989735 -0.0847108 -0.115106 0.973915 -0.220804 -0.0522922 0.973997 -0.220569 -0.0517654 0.928117 -0.371591 0.0227934 0.927077 -0.374779 0.00824202 0.812669 -0.571353 0.114567 0.81488 -0.574702 0.0754233 0.665674 -0.72686 0.168975 0.675469 -0.72752 0.120234 0.509759 -0.836812 0.19973 0.503589 -0.853278 0.135336 0.344871 -0.918038 0.195629 0.348801 -0.92418 0.155656 0.229274 -0.954083 0.192766 0.235637 -0.956791 0.170368 0.141268 -0.970755 0.194108 0.146392 -0.972183 0.182835 0.0660984 -0.977885 0.198426 0.659571 -0.141317 0.738238 0.646705 -0.252883 0.719599 0.658943 -0.25215 0.708671 0.462834 -0.725808 0.508908 0.461588 -0.732903 0.499789 0.326159 -0.763167 0.55785 0.540213 -0.599819 0.590243 0.549006 -0.563359 0.61743 0.393593 -0.593737 0.701827 0.404248 -0.676348 0.615741 0.350883 -0.607041 0.713009 0.388316 -0.818039 0.42429 0.388428 -0.817445 0.425332 0.279077 -0.840201 0.46495 0.318876 -0.770384 0.552112 0.171834 -0.786538 0.593153 0.213734 -0.618347 0.756283 0.239629 -0.697093 0.67575 -0.00554907 -0.978794 0.204774 0.0683509 -0.978461 0.194788 0.101019 -0.93866 0.329715 0.103407 -0.937336 0.332729 0.141516 -0.861937 0.486866 0.0103454 -0.863023 0.505059 0.0108343 -0.862529 0.505891 0.000788114 -0.939206 0.343353 0.00159271 -0.938677 0.344793 -0.00727148 -0.978322 0.206962 -0.0800047 -0.973928 0.212281 -0.215089 -0.877843 0.427936 -0.223799 -0.904853 0.362153 -0.221103 -0.908869 0.353654 -0.297764 -0.718421 0.628655 0.727272 -0.527625 0.438962 -0.136568 -0.765265 0.629061 -0.136377 -0.801987 0.581565 -0.126862 -0.850914 0.509756 -0.124954 -0.848003 0.515051 -0.105056 -0.930583 0.350682 -0.102794 -0.92833 0.357262 -0.0875191 -0.971553 0.220059 -0.399886 -0.88427 0.241159 -0.406666 -0.883541 0.232334 -0.968325 -0.218625 0.120621 -0.732906 -0.638587 0.234641 -0.56368 -0.7189 0.406754 -0.465271 -0.812345 0.351595 -0.356976 -0.854974 0.376281 -0.300791 -0.919002 0.254874 -0.267436 -0.935696 0.230111 -0.631416 -0.726094 0.272217 -0.691792 -0.620216 0.369805 -0.734981 -0.565304 0.374479 -0.282827 -0.845833 0.452299 -0.331339 -0.798864 0.502027 -0.428017 -0.766679 0.478544 -0.467883 -0.68725 0.555674 -0.484107 -0.665232 0.568425 -0.521392 -0.567839 0.636953 -0.552582 -0.505554 0.662622 -0.560345 -0.461874 0.687522 -0.596928 -0.260755 0.758738 -0.612515 -0.395343 0.684493 -0.600246 -0.245429 0.761229 -0.513998 -0.261446 0.816977 -0.481045 -0.26244 0.836494 0.168438 -0.623997 0.763057 0.0742693 -0.625128 0.77698 0.0239958 -0.666639 0.744994 -0.0214411 -0.622786 0.782099 -0.117745 -0.616165 0.778766 0.296409 -0.920873 0.253247 0.304569 -0.906729 0.291685 0.209928 -0.924026 0.31954 0.271205 -0.846518 0.4581 0.143986 -0.85987 0.489787 0.169402 -0.789078 0.590473 0.0166871 -0.790626 0.612073 0.0164914 -0.790301 0.612497 -0.142536 -0.77684 0.613354 -0.160156 -0.655485 0.738031 -0.214387 -0.603084 0.768328 -0.399962 -0.205685 0.893154 -0.232611 -0.292942 0.927403 -0.243222 -0.29286 0.924703 -0.243213 -0.29287 0.924702 -0.131758 -0.29483 0.946422 -0.132248 -0.294244 0.946536 -0.0187874 -0.295265 0.955231 -0.0195522 -0.29435 0.955498 0.0941326 -0.294413 0.951031 0.0932042 -0.29328 0.951472 0.205085 -0.292354 0.934061 0.204007 -0.290984 0.934724 0.312666 -0.289025 0.904823 0.311371 -0.287273 0.905827 0.415495 -0.284234 0.864046 0.413884 -0.28185 0.865598 0.512476 -0.277684 0.812564 0.510456 -0.274315 0.814976 0.641177 -0.265513 0.719996 0.59048 -0.484799 0.645216 0.717946 -0.447346 0.533325 -0.510228 -0.816615 0.269829 -0.588924 -0.704418 0.396186 -0.63106 -0.66326 0.402306 -0.691794 -0.531951 0.488313 -0.769738 -0.47766 0.42349 -0.929025 -0.0818764 0.360846 -0.950471 -0.08984 0.297547 -0.954973 -0.123249 0.269883 -0.953546 -0.119739 0.276427 -0.946938 -0.187253 0.261238 -0.946944 -0.186642 0.261654 -0.934132 -0.249061 0.255667 -0.92779 -0.286507 0.238996 -0.915573 -0.325518 0.236144 -0.902039 -0.385198 0.194805 -0.887115 -0.423495 0.183518 -0.971855 -0.197856 0.127868 -0.974452 -0.171035 0.145567 -0.977477 -0.149874 0.148582 -0.979263 -0.125479 0.159055 -0.981814 -0.106252 0.157327 -0.984162 -0.0183601 0.17632 -0.962839 -0.169012 0.210658 -0.761785 -0.221067 0.608944 -0.762813 -0.213882 0.610222 -0.751675 -0.248109 0.611086 -0.718958 -0.406638 0.563689 -0.6988 -0.450247 0.555838 -0.685602 -0.492357 0.536222 -0.596479 -0.616809 0.513575 -0.557233 -0.696044 0.452786 -0.42886 -0.751894 0.500733 -0.355554 -0.86647 0.350446 -0.219145 -0.903788 0.367619 -0.181033 -0.954899 0.235361 -0.164055 -0.961449 0.220686 -0.773115 -0.581828 0.252524 -0.80801 -0.494707 0.319976 -0.839952 -0.435851 0.323287 -0.884437 -0.173757 0.433105 -0.840496 -0.364564 0.400824 -0.848122 -0.332401 0.412552 -0.869218 -0.260829 0.420033 -0.878537 -0.198102 0.434659 -0.891481 -0.136733 0.431933 -0.89118 -0.139897 0.431541 -0.848444 -0.288758 0.443579 -0.111148 -0.991888 0.0616848 -0.0562176 -0.996613 0.0600209 -0.0544882 -0.996712 0.0599729 -0.058936 -0.996461 0.0599267 -0.0383317 -0.998037 0.0495339 -0.0144693 -0.998762 0.0475984 -0.99257 -0.0796769 0.0919535 -0.993868 -0.100842 0.0453481 -0.962431 -0.250984 0.103605 -0.940701 -0.333622 0.0614672 -0.859644 -0.485284 0.159724 -0.790659 -0.59508 0.144006 -0.654442 -0.734035 0.181378 -0.612502 -0.773348 0.163626 -0.4647 -0.868184 0.174101 -0.376629 -0.916027 0.138005 -0.303382 -0.94028 0.154379 -0.210036 -0.971722 0.107896 -0.184927 -0.976658 0.109277 -0.128025 -0.988654 0.0785624 -0.0741247 -0.994049 0.0798314 0.0689085 -0.99695 0.0366416 0.0499697 -0.997503 0.0499031 0.0635207 -0.996881 0.0468446 0.118393 -0.992298 0.0364349 0.0962797 -0.993841 0.0548622 0.19781 -0.977981 0.0665191 0.154062 -0.984077 0.0886402 0.310467 -0.949209 0.0511102 0.980211 -0.0961093 -0.173058 0.979175 -0.0954831 -0.179162 0.963625 -0.262575 -0.0498116 0.967051 -0.242435 -0.0777078 0.908997 -0.414417 -0.0445258 0.899754 -0.435872 -0.0214176 0.745175 -0.666189 0.0301064 0.720463 -0.691314 0.0549392 0.472958 -0.876666 0.0881342 0.499301 -0.863913 0.0659813 0.331519 -0.937163 0.108718 0.235858 -0.961658 0.139948 -0.00858863 -0.998992 0.0440675 0.00665467 -0.999094 0.0420286 0.0267175 -0.998851 0.039798 0.0207909 -0.998831 0.0436348 0.0348635 -0.998548 0.0410631 -0.993721 -0.0695797 0.08762 -0.993646 -0.0890026 0.0688912 -0.967597 -0.225026 0.114536 -0.962443 -0.249498 0.10702 -0.883184 -0.437385 0.169354 -0.859575 -0.485838 0.158404 -0.723826 -0.655982 0.213924 -0.656379 -0.72843 0.196359 -0.560867 -0.798329 0.219315 -0.469251 -0.860194 0.199676 -0.396148 -0.89358 0.211142 -0.306065 -0.936893 0.168987 -0.24654 -0.953331 0.174293 -0.190203 -0.970534 0.147941 -0.147813 -0.977689 0.149252 -0.115825 -0.984313 0.133088 -0.0738687 -0.988489 0.132035 -0.0578644 -0.990721 0.122981 -0.0119141 -0.99279 0.119271 -0.00746616 -0.993174 0.116407 0.0459293 -0.992956 0.109215 0.0403863 -0.992738 0.113319 0.105793 -0.989225 0.101204 0.0898619 -0.989304 0.114901 0.175874 -0.979822 0.0949585 0.148375 -0.981256 0.122967 0.269014 -0.958938 0.0898332 0.228603 -0.963306 0.140653 0.411332 -0.907708 0.0828941 0.362978 -0.91685 0.166232 0.594508 -0.799968 0.0813103 0.534243 -0.832079 0.149098 0.76593 -0.641439 0.0436766 0.734288 -0.671735 0.0979474 0.90989 -0.414499 -0.0170432 0.905229 -0.424918 0.00214697 0.968345 -0.239788 -0.0693481 0.968366 -0.239254 -0.0708828 0.988454 -0.087484 -0.123714 0.984088 -0.0869636 -0.154948 -0.039023 -0.99554 0.085887 0.173929 -0.983532 0.0491337 -0.22074 -0.975299 0.00811862 -0.591669 -0.806174 0.00328708 -0.907509 -0.418028 0.0409901 -0.906599 -0.419328 0.0473467 -0.241153 -0.970134 0.0261717 0.978944 -0.044916 -0.199124 0.958346 -0.187158 -0.21574 0.963334 -0.16532 -0.211323 0.963291 -0.165388 -0.211465 0.969142 -0.137488 -0.204602 0.965145 -0.154491 -0.211251 -0.97366 -0.219718 0.0609054 -0.974059 -0.219403 0.0554112 -0.972725 -0.225623 0.0538525 -0.974101 -0.221142 0.0471588 -0.978944 -0.19671 0.0545277 -0.995294 -0.0734512 0.0632088 -0.994587 -0.0737975 0.0731494 -0.994592 -0.0738668 0.0730131 -0.994072 -0.0776248 0.0761299 -0.993694 -0.0792558 0.0793171 -0.993764 -0.0794468 0.0782358 -0.990416 -0.101163 0.0940375 -0.970199 -0.230539 0.0746034 -0.936273 -0.334291 0.107896 -0.416753 -0.905164 0.0836404 -0.383742 -0.920936 0.067963 -0.358047 -0.93189 0.0581694 -0.905978 -0.414657 0.0852284 -0.802761 -0.591103 0.0785573 -0.799615 -0.595211 0.079622 -0.727057 -0.68241 0.0755333 -0.627068 -0.775717 0.0710496 -0.634855 -0.768979 0.0750355 -0.390397 -0.919409 0.0477284 -0.499383 -0.854663 0.142013 -0.461848 -0.879913 0.111582 -0.33166 -0.942078 0.0498964 -0.246974 -0.96867 0.0261238 -0.260506 -0.965013 0.0297796 -0.362426 -0.9313 0.0364468 -0.390242 -0.919968 0.0370179 -0.424094 -0.904934 0.035198 -0.471762 -0.881349 0.0257813 -0.0647105 -0.997903 -0.00166541 -0.0850857 -0.996373 0.000890909 -0.0966317 -0.99532 -0.00079217 -0.136592 -0.990471 0.0175938 -0.221537 -0.974731 0.0286403 -0.000328303 -0.999958 -0.00919795 -0.0156096 -0.999851 -0.00733914 -0.0330357 -0.999405 -0.00987677 -0.0457396 -0.998943 -0.00450206 -0.0630029 -0.998012 -0.00188394 0.05492 -0.998348 -0.0168595 0.0411713 -0.999038 -0.01512 0.0269918 -0.999493 -0.0168789 0.138633 -0.989869 -0.0306642 0.214138 -0.975863 -0.0428587 0.225562 -0.973038 -0.0481619 0.312316 -0.948125 -0.0593133 0.560922 -0.812711 -0.157695 0.416729 -0.904626 -0.0893815 0.339159 -0.938208 -0.0688219 0.0263714 -0.999592 -0.0109807 0.294476 -0.954421 -0.0486223 0.345785 -0.936714 -0.0547633 0.368151 -0.928132 -0.0550977 0.400335 -0.914957 -0.0508442 0.46259 -0.886226 -0.0247844 0.443787 -0.896115 -0.00557715 0.607857 -0.782291 -0.136126 0.736446 -0.671792 -0.0796438 0.800804 -0.577676 -0.158126 0.900052 -0.415693 -0.130791 0.98745 -0.0961789 -0.125266 0.93655 -0.262002 -0.232872 0.955801 -0.225277 -0.188932 0.905163 -0.397777 -0.149846 -0.0157993 -0.99948 -0.0281165 -0.046954 -0.998897 0.000195929 -0.0181223 -0.999616 -0.0209538 -0.0168597 -0.997139 0.0736811 -0.0203631 -0.999713 0.0126118 -0.0196143 -0.999739 -0.01169 -0.00066373 -0.998662 -0.0517033 -0.0193227 -0.998177 -0.0571791 -0.0346756 -0.997187 -0.0664581 -0.0458136 -0.995926 -0.0776699 -0.0545379 -0.996278 -0.0667574 -0.0669405 -0.996079 -0.0578486 -0.0742715 -0.995725 -0.0549071 -0.118345 -0.992216 -0.0387652 -0.103902 -0.994355 -0.0214931 -0.100801 -0.994763 -0.016903 -0.0744501 -0.996927 -0.0243789 -0.0621407 -0.997822 -0.0221402 0.979764 -0.0649292 -0.189333 0.979453 -0.0618293 -0.191962 0.979047 -0.0533543 -0.196522 0.957796 -0.213703 -0.192244 0.967035 -0.182171 -0.177926 0.8954 -0.403965 -0.187274 0.909407 -0.375408 -0.17902 0.776093 -0.613844 -0.144482 0.700508 -0.69688 -0.153775 0.426799 -0.902957 -0.0501131 -0.471794 -0.881331 0.0257958 -0.612015 -0.787983 0.0672376 -0.713042 -0.700753 0.0226987 -0.787702 -0.611578 0.0741441 -0.903935 -0.42461 0.0510631 -0.782251 -0.622502 0.02395 -0.420809 -0.907078 -0.0113476 -0.580519 -0.814247 0.000659088 -0.575074 -0.81767 0.0265654 -0.553891 -0.832311 0.0215015 -0.791232 -0.595923 0.137214 -0.627621 -0.77581 0.0648953 -0.851249 -0.518278 0.0822447 -0.980571 -0.188447 0.0544816 -0.988038 -0.139548 0.0656235 -0.950808 -0.303306 0.0630002 -0.886114 -0.462321 0.0325884 -0.884502 -0.464057 0.0480357 -0.887386 -0.458406 0.0490914 -0.886781 -0.458996 0.0542496 -0.865826 -0.498126 0.0470681 -0.863315 -0.499559 0.0716102 -0.901906 -0.422599 0.0893099 -0.2994 -0.953956 -0.018115 -0.346137 -0.938183 -0.00152839 -0.270042 -0.962811 -0.00848314 -0.261795 -0.964897 0.0209329 -0.753814 -0.656898 0.015774 -0.750404 -0.659887 0.0379987 -0.76523 -0.642374 0.0421874 -0.762037 -0.644713 0.0603659 -0.548719 -0.83493 0.0424221 -0.625996 -0.776237 0.0747352 -0.37008 -0.927625 0.050524 -0.407884 -0.910652 0.0659021 -0.275456 -0.959909 0.051954 -0.088532 -0.996072 -0.00177388 -0.101431 -0.994827 -0.00556696 -0.100871 -0.994895 -0.00283826 -0.0911789 -0.995834 0.0004065 -0.0907341 -0.995872 0.00249803 -0.679325 -0.72613 0.106079 -0.586711 -0.803759 0.0987033 -0.403328 -0.910719 0.0889819 -0.514951 -0.847656 0.12769 -0.271959 -0.959782 0.0696917 -0.346247 -0.931742 0.109405 -0.137662 -0.988332 0.0651888 -0.208748 -0.969603 0.127646 -0.140286 -0.986093 0.0891126 0.851986 -0.485386 -0.196265 0.877801 -0.430967 -0.209125 0.635132 -0.75531 -0.161603 0.193814 -0.979839 -0.0485 0.226326 -0.972095 -0.0617033 0.261519 -0.962822 -0.0676812 0.307375 -0.947558 -0.0874877 0.337096 -0.936876 -0.0928985 0.393596 -0.911536 -0.119102 0.409977 -0.90386 -0.122296 0.469461 -0.871341 -0.14273 0.50322 -0.851974 -0.144602 0.686757 -0.70381 -0.181704 0.95968 -0.186518 -0.210298 0.959549 -0.187465 -0.210055 0.858118 -0.476751 -0.190638 0.853272 -0.486274 -0.18832 0.665614 -0.730761 -0.151484 0.637101 -0.757819 -0.140759 0.523135 -0.843961 -0.118574 0.471313 -0.877018 -0.0932905 0.422047 -0.902645 -0.0843113 0.393773 -0.916433 -0.0713694 0.309002 -0.949361 -0.0568386 0.307088 -0.950032 -0.0560066 0.216953 -0.975302 -0.0414543 0.226368 -0.972983 -0.0453953 0.0697975 -0.99455 0.077448 -0.0675307 -0.997646 0.0118876 -0.0651923 -0.997523 0.0264331 0.060165 -0.998145 0.00934908 0.0690036 -0.994637 0.0770449 0.11063 -0.992119 0.0588266 0.587217 -0.807749 -0.0521397 0.44143 -0.897081 -0.0196299 0.96415 -0.168749 -0.204791 0.888205 -0.418582 -0.189422 0.861378 -0.467944 -0.197625 0.760005 -0.637058 -0.128643 0.610498 -0.785679 -0.100004 0.674464 -0.735072 -0.0690443 0.792488 -0.605889 -0.0697163 0.626815 -0.773551 -0.0933836 0.842771 -0.520513 -0.137128 0.871851 -0.469531 -0.139345 0.895104 -0.411837 -0.170821 0.937672 -0.285601 -0.197996 0.290838 -0.956623 0.0169091 0.366747 -0.930302 -0.00588305 0.514995 -0.857063 -0.014968 -0.00944449 -0.999258 -0.0373431 0.00692198 -0.998718 -0.05015 0.0244622 -0.99832 -0.0525235 0.0229402 -0.997656 -0.064463 0.1435 -0.985896 -0.0861207 0.974923 -0.0750022 -0.209521 0.975264 -0.0752117 -0.207856 0.959365 -0.192915 -0.205921 0.961388 -0.179807 -0.208331 0.895097 -0.399221 -0.198556 0.905099 -0.372628 -0.204802 0.676044 -0.717972 -0.165776 0.698107 -0.694224 -0.175213 0.407779 -0.904973 -0.121405 0.423441 -0.896913 -0.127453 0.222376 -0.970909 -0.0888002 0.224704 -0.970251 -0.0901192 0.096782 -0.993102 -0.0661956 0.0975125 -0.994809 -0.029083 0.0860685 -0.996057 -0.0214897 0.97049 -0.117135 -0.210779 0.971787 -0.0748305 -0.223673 0.927841 -0.302251 -0.218532 0.951555 -0.191853 -0.240282 0.806618 -0.549138 -0.218664 0.881051 -0.3956 -0.259326 0.579826 -0.788446 -0.205317 0.660858 -0.71072 -0.241128 0.38008 -0.906716 -0.182771 0.396885 -0.898002 -0.189931 0.2469 -0.95635 -0.156316 0.216025 -0.966737 -0.136942 0.09389 -0.989482 -0.110043 0.0993825 -0.992938 -0.0647898 0.024401 -0.99832 -0.0525589 0.0273045 -0.999485 -0.0168302 0.0133491 -0.99985 -0.0110622 0.963367 -0.165393 -0.211115 0.9672 -0.117168 -0.225378 0.877291 -0.430864 -0.211465 0.922505 -0.30215 -0.240187 0.68379 -0.702734 -0.19646 0.79861 -0.547975 -0.248887 0.495511 -0.84823 -0.187014 0.575933 -0.787207 -0.220467 0.399743 -0.898325 -0.18226 0.381896 -0.907473 -0.175069 0.32614 -0.931212 -0.162721 0.254352 -0.959362 -0.122183 0.253701 -0.959552 -0.122047 0.14751 -0.98688 -0.0656447 0.19215 -0.979474 -0.0608971 -0.0811535 -0.995271 -0.0533855 -0.0941941 -0.994201 -0.0518771 -0.0968295 -0.993951 -0.0518247 -0.10837 -0.993678 -0.029323 -0.238985 -0.970866 -0.017482 -0.250998 -0.967915 -0.0118329 -0.478889 -0.877841 0.00779726 -0.475911 -0.879466 0.00694831 -0.716029 -0.697483 0.0286318 -0.712294 -0.701347 0.0273699 -0.902983 -0.427165 0.0463758 -0.906512 -0.419422 0.0481825 -0.973906 -0.219914 0.0560788 0.962874 -0.168591 -0.210835 0.960504 -0.186744 -0.2063 0.887724 -0.418438 -0.191977 0.859998 -0.478171 -0.178201 0.755851 -0.635451 -0.157768 0.667784 -0.733971 -0.1239 0.609071 -0.78506 -0.112754 0.523893 -0.848908 -0.0699412 0.438748 -0.896935 -0.0548487 0.421254 -0.905744 -0.0466209 0.287834 -0.957368 -0.0244458 0.308278 -0.950699 -0.0337077 0.184161 -0.982793 -0.0142276 0.216773 -0.975796 -0.0288339 0.132066 -0.991109 -0.0161793 0.131664 -0.99081 -0.030975 0.142796 -0.989115 -0.0355163 0.142609 -0.988954 -0.0404068 0.123336 -0.991817 -0.0329728 0.121242 -0.991432 -0.0486195 0.0511926 -0.998569 -0.0154728 0.0452662 -0.997606 -0.0522795 -0.060571 -0.997447 -0.0378251 -0.0425886 -0.99756 -0.0553238 -0.141709 -0.988841 -0.0459621 -0.101348 -0.991507 -0.0815014 -0.254662 -0.964303 -0.0725704 -0.247226 -0.965992 -0.0757576 -0.4478 -0.891788 -0.0647255 -0.485983 -0.872245 -0.0548547 -0.661 -0.749176 -0.0426011 -0.720311 -0.693243 -0.0238012 -0.854414 -0.519469 -0.0113812 -0.904969 -0.425296 0.0124045 -0.949962 -0.311846 0.0179835 -0.974918 -0.219342 0.0377265 -0.439948 -0.897994 -0.00719157 -0.431099 -0.901882 0.0276015 -0.340236 -0.94014 0.0194158 -0.375413 -0.926269 0.0330356 -0.260406 -0.965262 0.0214153 -0.249898 -0.966656 0.0559277 -0.180164 -0.983299 0.0257583 -0.175493 -0.983174 0.0507067 -0.054074 -0.997901 0.0356408 -0.0478668 -0.995697 0.0793541 0.0279699 -0.997216 0.0691239 -0.969876 -0.226129 0.09059 -0.975963 -0.205881 0.0714809 -0.977005 -0.204888 0.0590128 -0.994878 -0.0801442 0.0615953 -0.994322 -0.098119 0.0411848 -0.994972 -0.092303 0.0388734 -0.949558 -0.311932 0.0322035 -0.909013 -0.416642 0.0102504 -0.854171 -0.51997 0.00490916 -0.784798 -0.619428 -0.0200079 -0.660732 -0.750048 -0.0293463 -0.59573 -0.801834 -0.0465534 -0.447443 -0.89259 -0.0554789 -0.42593 -0.902741 -0.0603478 -0.254478 -0.964584 -0.0694207 -0.30342 -0.951494 -0.050948 -0.14288 -0.987842 -0.0612599 -0.222434 -0.974939 -0.00412747 -0.0586388 -0.998069 -0.0204851 -0.0880885 -0.996112 0.00141498 0.0432263 -0.998928 -0.0165358 0.0427962 -0.998889 -0.0197282 0.0490957 -0.99855 -0.0220657 0.0489712 -0.998528 -0.023337 0.0438294 -0.998813 -0.0212699 0.0443301 -0.99889 -0.0159524 0.066053 -0.997485 -0.0257097 0.071009 -0.997304 0.0185082 0.185499 -0.982643 0.0015234 0.135808 -0.990006 0.0380078 0.253285 -0.967225 0.0179287 0.976801 0 -0.214151 0.976795 1.24696e-07 -0.214175 0.976793 3.46285e-07 -0.214185 0.976795 -7.54737e-08 -0.214176 0.976795 0 -0.214175 0.976795 0 -0.214176 0.976795 0 -0.214176 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0199027 0.998939 0.0415203 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.314566 0.947733 0.053386 -0.171742 0.985142 0.000881961 0.011873 0.999407 -0.0323362 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0720925 0.99581 0.0562551 -0.0368869 0.999319 4.76809e-07 0.0610718 0.997551 -0.0341023 0 1 0 0 1 0 0 1 0 0.205048 0.978027 -0.0376605 0.210525 0.977228 0.0265559 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.8559e-08 1 6.92654e-08 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -9.14167e-08 1 -3.05109e-08 -3.26021e-08 1 5.11256e-08 2.44968e-08 1 9.14206e-08 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -5.87278e-08 1 5.87292e-08 -1.80177e-07 1 4.82808e-08 -2.20806e-07 1 4.70895e-08 0 1 0 0 1 0 0.101578 0.994698 -0.0160871 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.93949 3.44126e-05 0.342577 0.999676 0.0178944 -0.0180924 0.976051 0.039043 -0.214011 0.985755 -0.135496 -0.099641 0.989995 -0.105942 -0.0932036 0.976133 0.0380231 -0.213818 0.961096 -0.205789 0.184242 0.961258 0.127622 0.244329 0.99856 -0.00615299 0.0532846 0.911043 -9.74407e-06 0.412312 0.910819 -0.000939562 0.412805 0.910898 -0.000481822 0.412632 0.910869 -7.1165e-07 0.412696 0.910869 -1.14978e-06 0.412696 0.931693 -0.00390237 0.363226 0.951469 0.0392069 0.305236 0.975314 -0.00164502 0.220815 0.990412 0.000474707 0.138141 0.990897 -0.000310725 0.134623 0.999939 -0.000328236 0.011067 0.999554 0.011988 0.0273445 0.986795 -0.0116637 -0.161552 0.992612 0.0189425 -0.119841 0.958301 -0.0153889 -0.285347 0.958763 -0.0144686 -0.283839 0.90509 0.0143358 -0.424978 0.895501 0.00134104 -0.445056 0.844427 -0.000735464 -0.535669 0.800328 -0.0182278 -0.599285 0.738078 0.0414834 -0.673439 0.680989 -0.00126392 -0.732292 0.545754 0.00162049 -0.837944 0.544217 0.000138608 -0.838944 0.392382 -0.00029213 -0.919802 0.392738 -9.00756e-05 -0.91965 0.253453 -9.04745e-05 -0.967348 0.273047 -0.0126501 -0.961917 0.149675 0.00679265 -0.988712 0.110376 0.021022 -0.993668 0.0644262 -2.39004e-05 -0.997922 -0.142235 -2.39749e-05 -0.989833 -0.0767086 0.074818 -0.994242 -0.189959 0.0170393 -0.981644 -0.279236 -0.00677425 -0.960199 -0.311565 -9.68459e-06 -0.950225 -0.406646 1.09119e-05 -0.913586 -0.429137 0.0147832 -0.903118 -0.508138 -0.00298341 -0.86127 -0.579232 0.00595557 -0.815141 -0.589595 -4.79952e-05 -0.807699 -0.677547 3.84322e-05 -0.73548 -0.689189 -0.00714617 -0.724546 -0.7631 0.00715279 -0.646241 -0.761576 0.00918578 -0.64801 -0.773018 6.08989e-07 -0.634384 -0.773018 1.79315e-06 -0.634384 -0.773018 2.88176e-06 -0.634384 -0.773263 0.00373035 -0.634074 -0.773891 -3.52278e-05 -0.633319 -0.820525 -3.55805e-05 -0.57161 -0.807767 0.0666509 -0.585722 -0.879382 -0.0857759 -0.468327 -0.864638 0.0802941 -0.495937 -0.904618 -0.000967838 -0.426222 -0.932032 -0.000964142 -0.362374 -0.96552 0.227055 -0.127345 -0.906759 -0.421117 -0.0211662 -0.910229 0.152681 -0.384932 -0.947652 -0.0257107 -0.318267 -0.966492 0.064508 -0.248461 -0.970851 -1.96088e-05 -0.239684 -0.98814 1.87173e-07 -0.153557 0.897824 -0.000736728 -0.440353 0.897166 3.4265e-05 -0.441694 0.897194 -1.95252e-06 -0.441637 0.897178 1.14295e-05 -0.44167 0.897189 0 -0.441647 0.897177 1.14796e-06 -0.44167 0.897188 0 -0.44165 0.897187 -8.15572e-08 -0.441651 0.897178 1.80753e-06 -0.441669 0.897193 -5.67366e-07 -0.441639 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.99848 -3.3406e-07 0.0551184 -0.99848 0 0.0551186 -0.99848 1.25254e-07 0.0551188 -0.998482 -5.58368e-06 0.0550842 -0.99848 -4.41553e-05 0.0551227 -0.99848 1.30934e-05 0.0551191 -0.99848 1.42905e-05 0.0551179 -0.99848 1.495e-05 0.0551114 -0.998481 -2.84163e-05 0.0551013 -0.99848 0 0.0551174 -0.99848 4.34112e-07 0.0551171 -0.99848 1.19858e-07 0.0551179 -0.99848 5.97063e-07 0.0551208 -0.99848 -1.67425e-07 0.055118 -0.99848 -2.25734e-07 0.0551179 -0.99848 2.97741e-07 0.0551186 -0.99848 5.43118e-08 0.0551184 -0.99848 -8.77622e-07 0.0551181 -0.99848 1.87121e-06 0.0551185 -0.99848 4.732e-07 0.0551184 0.965929 0 0.258806 0.965929 0 0.258806 0.707116 0 0.707098 0.707116 0 0.707098 0.258831 0 0.965923 0.258831 0 0.965923 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.258831 0 -0.965923 -0.258831 0 -0.965923 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965922 0 -0.258832 0.965922 0 -0.258832 0.44217 -1.13287e-05 -0.896931 -0.987939 -0.0166444 0.153948 -0.964639 -0.0515403 0.258488 -0.933912 -8.65728e-06 0.357503 -0.819462 -2.17566e-05 0.573134 -0.706218 -0.049884 0.706235 -0.643276 -1.20871e-05 0.765634 -0.258409 -0.0554512 0.964443 -0.286976 -0.0378224 0.957191 -0.442329 -1.26545e-05 0.896853 0.258832 -1.58781e-05 0.965922 0.307094 -0.0500197 0.950364 0.103615 -0.00984746 0.994569 0.0513584 1.25297e-06 0.99868 -0.0923405 -5.40756e-06 0.995728 0.998663 0 -0.0516979 0.995723 0 0.0923862 0.964203 -0.0597608 0.258344 0.940704 -0.00535143 0.339187 0.707089 0.0085921 0.707072 0.733414 -0.0312224 0.679065 0.526286 6.90704e-07 0.850308 0.707098 -1.73555e-05 -0.707116 0.636292 -0.0802228 -0.767266 0.819524 -9.01168e-06 -0.573044 0.965922 4.0918e-05 -0.258832 0.92657 -0.102055 -0.362013 0.987494 -0.0204868 -0.156321 0.282608 -0.0367126 -0.958533 0.258482 -0.0500667 -0.964718 0.0930106 -9.45859e-06 -0.995665 -0.258504 -0.0503122 -0.964699 -0.154867 -0.0167126 -0.987794 -0.0513917 6.74067e-06 -0.998679 -0.851879 -7.49874e-06 -0.523739 -0.713885 -0.0186276 -0.700015 -0.706891 -0.0252503 -0.706872 -0.532078 -1.35607e-05 -0.846695 -0.356735 -2.64297e-05 -0.934205 -0.998645 0 0.0520483 -0.995705 0 -0.0925847 -0.964817 -0.0479648 -0.258509 -0.942569 -0.00727842 -0.333932 -0.87301 -7.45332e-06 -0.487702 -0.991956 -0.0235905 0.124365 -0.995672 -0.0156139 0.0916162 -0.96382 -0.000382716 0.266555 -0.91751 0.000426347 0.397713 -0.833375 -0.0152408 0.552498 -0.845231 -0.0196881 0.534039 -0.391371 -0.00409739 0.920224 -0.548614 -0.0283806 0.835594 -0.472095 -0.00795765 0.881512 -0.648576 6.90144e-05 0.76115 -0.749184 -0.000210956 0.662362 0.00199727 0.0015269 0.999997 0.143815 -0.0414816 0.988735 0.00916692 -0.0171589 0.999811 -0.142675 -0.000119234 0.98977 -0.269969 3.61318e-05 0.962869 0.625648 -0.0710712 0.776862 0.56014 -0.0386624 0.827496 0.424635 -0.0102347 0.905307 0.312257 -0.000397728 0.949998 0.475623 0.0026186 0.879645 0.790003 -0.00168455 0.613101 0.793931 0 0.608008 -0.931075 0 -0.364829 -0.948108 -0.0110432 -0.317757 -0.978665 -0.000148951 -0.205463 -0.996842 0.000229571 -0.0794059 -0.988582 2.9291e-05 0.150687 -0.998423 -0.0106529 0.0551157 -0.853092 -0.0103957 0.521657 -0.897343 -0.00440451 0.441313 -0.932346 -1.01169e-05 0.361568 -0.481643 -0.00645255 0.876344 -0.673469 -3.14328e-05 0.739215 -0.803397 0.00011396 0.595444 -0.504059 -0.0011731 0.863668 -0.112911 0.000850378 0.993605 -0.118592 0 0.992943 -0.257745 0 -0.966213 -0.221586 0.00659327 -0.975119 -0.580444 -0.006114 -0.814277 -0.596036 -0.00898557 -0.802907 -0.993055 0.00156362 -0.117645 -0.951535 -0.00161842 -0.307536 -0.905321 -0.0110305 -0.424586 -0.861454 -0.00057936 -0.507835 -0.737932 0.00023817 -0.674875 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258831 0 0.965923 0.258831 0 0.965923 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965923 0 0.258829 -0.965923 0 0.258829 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707116 0 0.707097 0.707116 0 0.707097 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.25883 0.965923 0 -0.25883 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258831 0 0.965923 0.258831 0 0.965923 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258807 0 0.965929 -0.258807 0 0.965929 0.25883 0 0.965923 0.25883 0 0.965923 0.707116 0 0.707098 0.707116 0 0.707098 0.965929 0 0.258806 0.965929 0 0.258806 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965929 0 -0.258808 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.258841 0 -0.96592 -0.258841 0 -0.96592 0.258811 0 -0.965928 0.258811 0 -0.965928 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.25883 0.965923 0 -0.25883 0.965929 0 0.258807 0.965929 0 0.258807 0.707122 0 0.707091 0.707122 0 0.707091 0.258826 0 0.965924 0.258826 0 0.965924 -0.258811 0 0.965928 -0.258811 0 0.965928 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.707122 0 -0.707091 -0.707122 0 -0.707091 -0.258827 0 -0.965924 -0.258827 0 -0.965924 0.258811 0 -0.965928 0.258811 0 -0.965928 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.258831 0.965923 0 -0.258831 0.965929 0 0.258808 0.965929 0 0.258808 0.707114 0 0.707099 0.707114 0 0.707099 0.258841 0 0.96592 0.258841 0 0.96592 -0.258811 0 0.965928 -0.258811 0 0.965928 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.707118 0 -0.707095 -0.707118 0 -0.707095 -0.258827 0 -0.965924 -0.258827 0 -0.965924 0.258803 0 -0.96593 0.258803 0 -0.96593 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707099 0.707115 0 0.707099 0.258834 0 0.965922 0.258834 0 0.965922 -0.258811 0 0.965928 -0.258811 0 0.965928 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.965929 0 -0.258808 -0.965929 0 -0.258806 -0.707118 0 -0.707096 -0.707118 0 -0.707096 -0.258827 0 -0.965924 -0.258827 0 -0.965924 0.258803 0 -0.96593 0.258803 0 -0.96593 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965923 0 -0.258831 0.965923 0 -0.258831 0.965929 0 0.258806 0.965929 0 0.258806 0.707114 0 0.7071 0.707114 0 0.7071 0.258834 0 0.965922 0.258834 0 0.965922 -0.258811 0 0.965928 -0.258811 0 0.965928 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.965922 0 0.258833 -0.965922 0 0.258833 -0.965929 0 -0.258806 -0.965929 0 -0.258807 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.258834 0 -0.965922 -0.258834 0 -0.965922 0.258811 0 -0.965928 0.258811 0 -0.965928 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258808 0.965929 0 0.258808 0.707118 0 0.707095 0.707118 0 0.707095 0.258827 0 0.965924 0.258827 0 0.965924 -0.258803 0 0.96593 -0.258803 0 0.96593 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.965929 0 -0.258807 -0.965929 0 -0.258808 -0.707118 0 -0.707095 -0.707118 0 -0.707095 -0.258827 0 -0.965924 -0.258827 0 -0.965924 0.258803 0 -0.96593 0.258803 0 -0.96593 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707099 0.707115 0 0.707099 0.258834 0 0.965922 0.258834 0 0.965922 -0.258811 0 0.965928 -0.258811 0 0.965928 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258808 -0.965929 0 -0.258807 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.258831 0 -0.965923 -0.258831 0 -0.965923 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.258831 0.965923 0 -0.258831 0.965929 0 0.258807 0.965929 0 0.258807 0.707116 0 0.707097 0.707116 0 0.707097 0.258831 0 0.965923 0.258831 0 0.965923 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.258834 0 -0.965922 -0.258834 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.25883 0.965923 0 -0.25883 0.965929 0 0.258806 0.965929 0 0.258806 0.707116 0 0.707097 0.707116 0 0.707097 0.258834 0 0.965922 0.258834 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258807 -0.373487 0.849119 0.373502 -0.510201 0.84912 0.136715 0.3735 0.849119 0.373491 0.136717 0.849118 0.510202 -0.136703 0.849119 0.510206 0.373493 0.849121 -0.373494 0.510201 0.84912 -0.136715 0.510204 0.84912 0.136703 -0.373497 0.849121 -0.373488 -0.136716 0.849122 -0.510197 0.136701 0.849122 -0.510201 -0.510205 0.84912 -0.136699 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.707093 0 0.707121 -0.707093 0 0.707121 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258835 0 0.965922 0.258835 0 0.965922 0.707115 0 0.707099 0.707115 0 0.707099 0.965929 0 0.258808 0.965929 0 0.258808 0.965923 0 -0.258832 0.965923 0 -0.258832 0.707106 0 -0.707108 0.707106 0 -0.707108 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258835 0 -0.965922 -0.258835 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965931 0 -0.258802 -0.965931 0 -0.258802 -0.373492 0.849121 0.373494 -0.5102 0.84912 0.136715 0.373497 0.849121 0.373488 0.136716 0.849122 0.510197 -0.136701 0.849122 0.510201 0.373487 0.849119 -0.373502 0.510201 0.84912 -0.136715 0.510205 0.84912 0.1367 -0.3735 0.849119 -0.373491 -0.136717 0.849119 -0.510202 0.136702 0.849119 -0.510206 -0.510204 0.84912 -0.136703 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.707105 0 0.707108 -0.707105 0 0.707108 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258835 0 0.965922 0.258835 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.96593 0 0.258802 0.96593 0 0.258802 0.965923 0 -0.258832 0.965923 0 -0.258832 0.707093 0 -0.707121 0.707093 0 -0.707121 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258835 0 -0.965922 -0.258835 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965928 0 -0.258809 -0.965928 0 -0.258809 -0.373487 0.849119 0.373502 -0.510201 0.84912 0.136713 0.3735 0.849119 0.373491 0.136717 0.849118 0.510202 -0.136703 0.849119 0.510206 0.37349 0.84912 -0.373498 0.510201 0.84912 -0.136715 0.510204 0.849119 0.136703 -0.373498 0.84912 -0.373489 -0.136716 0.84912 -0.5102 0.136702 0.84912 -0.510203 -0.510204 0.84912 -0.136703 -0.965923 0 0.258828 -0.965923 0 0.258828 -0.707092 0 0.707121 -0.707092 0 0.707121 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258834 0 0.965922 0.258834 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.965928 0 0.258809 0.965928 0 0.258809 0.965923 0 -0.258832 0.965923 0 -0.258832 0.707099 0 -0.707114 0.707099 0 -0.707114 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258834 0 -0.965922 -0.258834 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965928 0 -0.258809 -0.965928 0 -0.258809 -0.37349 0.84912 0.373498 -0.510201 0.84912 0.136715 0.373498 0.84912 0.373489 0.13671 0.849119 0.510203 -0.136696 0.849119 0.510206 0.373489 0.84912 -0.373498 0.5102 0.84912 -0.136715 0.510204 0.84912 0.136701 -0.373498 0.84912 -0.37349 -0.136716 0.84912 -0.5102 0.136702 0.84912 -0.510203 -0.510205 0.84912 -0.1367 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.258795 0 0.965932 -0.258795 0 0.965932 0.258821 0 0.965925 0.258821 0 0.965925 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258806 0.965929 0 0.258806 0.965923 0 -0.258832 0.965923 0 -0.258832 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258835 0 -0.965922 -0.258835 0 -0.965922 -0.707114 0 -0.7071 -0.707114 0 -0.7071 -0.96593 0 -0.258803 -0.96593 0 -0.258803 -0.373487 0.849119 0.373502 -0.510201 0.84912 0.136715 0.373498 0.84912 0.373489 0.13671 0.849119 0.510203 -0.136703 0.849119 0.510206 0.37349 0.84912 -0.373498 0.510201 0.84912 -0.136715 0.510204 0.84912 0.1367 -0.373499 0.84912 -0.37349 -0.136716 0.84912 -0.5102 0.136702 0.84912 -0.510203 -0.510205 0.84912 -0.136701 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.707093 0 0.707121 -0.707093 0 0.707121 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258821 0 0.965925 0.258821 0 0.965925 0.707115 0 0.707098 0.707115 0 0.707098 0.96593 0 0.258804 0.96593 0 0.258804 0.965923 0 -0.258832 0.965923 0 -0.258832 0.707099 0 -0.707114 0.707099 0 -0.707114 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258835 0 -0.965922 -0.258835 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.37349 0.84912 0.373498 -0.510201 0.84912 0.136715 0.373498 0.84912 0.373489 0.136716 0.84912 0.5102 -0.136702 0.84912 0.510203 0.373486 0.849119 -0.373503 0.5102 0.84912 -0.136715 0.510204 0.84912 0.136701 -0.373502 0.849119 -0.373487 -0.13671 0.849119 -0.510203 0.136703 0.849119 -0.510206 -0.510205 0.849119 -0.136702 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258834 0 0.965922 0.258834 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258806 0.965929 0 0.258806 0.965923 0 -0.258832 0.965923 0 -0.258832 0.707091 0 -0.707122 0.707091 0 -0.707122 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258822 0 -0.965925 -0.258822 0 -0.965925 -0.70712 0 -0.707093 -0.70712 0 -0.707093 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.37349 0.84912 0.373498 -0.5102 0.84912 0.136717 0.373498 0.84912 0.37349 0.136713 0.84912 0.510201 -0.136699 0.84912 0.510205 0.373491 0.849119 -0.373498 0.510201 0.849119 -0.136715 0.510204 0.84912 0.136701 -0.373499 0.849119 -0.37349 -0.136716 0.849119 -0.510201 0.136702 0.849119 -0.510204 -0.510204 0.84912 -0.136702 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.258801 0 0.965931 -0.258801 0 0.965931 0.258828 0 0.965923 0.258828 0 0.965923 0.707114 0 0.7071 0.707114 0 0.7071 0.96593 0 0.258804 0.96593 0 0.258804 0.965923 0 -0.258832 0.965923 0 -0.258832 0.7071 0 -0.707114 0.7071 0 -0.707114 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258834 0 -0.965922 -0.258834 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.373489 0.84912 0.373498 -0.5102 0.84912 0.136715 0.373499 0.84912 0.37349 0.136716 0.84912 0.5102 -0.136702 0.84912 0.510203 0.373491 0.849119 -0.373498 0.510201 0.849119 -0.136715 0.510204 0.84912 0.136702 -0.373499 0.849119 -0.37349 -0.136717 0.849119 -0.510201 0.136702 0.849119 -0.510205 -0.510204 0.84912 -0.136702 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258835 0 0.965922 0.258835 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.258832 0.965923 0 -0.258832 0.7071 0 -0.707114 0.7071 0 -0.707114 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258835 0 -0.965922 -0.258835 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 0.96593 0 0.258805 0.96593 0 0.258805 0.707112 0 0.707102 0.707112 0 0.707102 0.258839 0 0.96592 0.258839 0 0.96592 -0.258816 0 0.965927 -0.258816 0 0.965927 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965922 0 0.258834 -0.965922 0 0.258834 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.707112 0 -0.707102 -0.707112 0 -0.707102 -0.258839 0 -0.96592 -0.258839 0 -0.96592 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.258831 0.965923 0 -0.258831 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258805 0 0.96593 -0.258805 0 0.96593 0.25883 0 0.965923 0.25883 0 0.965923 0.707116 0 0.707098 0.707116 0 0.707098 0.965929 0 0.258806 0.965929 0 0.258806 0.965923 0 -0.258831 0.965923 0 -0.258831 0.707097 0 -0.707117 0.707097 0 -0.707117 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258831 0 0.965923 0.258831 0 0.965923 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258808 0 0.965929 -0.258808 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.96593 0 0.258805 0.96593 0 0.258805 0.965923 0 -0.25883 0.965923 0 -0.25883 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.508584 0.694746 0.508597 -0.508585 0.694745 0.508597 -0.186148 0.694746 0.69475 -0.186148 0.694744 0.694752 0.186167 0.694744 0.694747 0.186165 0.694746 0.694745 0.508597 0.694746 0.508584 0.508595 0.694748 0.508582 0.694749 0.694747 0.186148 0.694747 0.694748 0.186148 0.694743 0.694748 -0.186164 0.694745 0.694746 -0.186165 0.508584 0.694746 -0.508597 0.508584 0.694745 -0.508598 0.186147 0.694746 -0.69475 0.186148 0.694748 -0.694747 -0.186165 0.694748 -0.694743 -0.186166 0.694746 -0.694745 -0.508597 0.694746 -0.508584 -0.508597 0.694747 -0.508583 -0.69475 0.694746 -0.186147 -0.694743 0.694753 -0.186147 -0.694739 0.694753 0.186162 -0.694748 0.694743 0.186167 -0.508583 0.694747 0.508596 -0.508583 0.694747 0.508597 -0.186148 0.694748 0.694748 -0.186148 0.694746 0.69475 0.186166 0.694746 0.694745 0.186165 0.694746 0.694745 0.508597 0.694746 0.508584 0.508596 0.694746 0.508584 0.694749 0.694746 0.186148 0.694752 0.694744 0.186148 0.694747 0.694744 -0.186167 0.694744 0.694747 -0.186165 0.508583 0.694747 -0.508596 0.508584 0.694745 -0.508598 0.186148 0.694746 -0.69475 0.186148 0.694746 -0.694749 -0.186166 0.694746 -0.694745 -0.186165 0.694746 -0.694745 -0.508597 0.694746 -0.508584 -0.508597 0.694745 -0.508585 -0.69475 0.694745 -0.186147 -0.694748 0.694748 -0.186147 -0.694743 0.694748 0.186164 -0.694744 0.694747 0.186165 -0.508583 0.694746 0.508597 -0.508582 0.69475 0.508594 -0.186147 0.694751 0.694745 -0.186147 0.694748 0.694748 0.186164 0.694748 0.694743 0.186165 0.694746 0.694745 0.508596 0.694747 0.508583 0.508598 0.694745 0.508584 0.69475 0.694746 0.186148 0.69475 0.694746 0.186148 0.694745 0.694746 -0.186166 0.694744 0.694747 -0.186165 0.508582 0.694749 -0.508594 0.508583 0.694746 -0.508597 0.186148 0.694746 -0.694749 0.186148 0.694744 -0.694752 -0.186167 0.694744 -0.694747 -0.186165 0.694746 -0.694745 -0.508596 0.694746 -0.508583 -0.508597 0.694745 -0.508584 -0.694749 0.694746 -0.186148 -0.694749 0.694747 -0.186148 -0.694744 0.694747 0.186166 -0.694744 0.694746 0.186166 -0.508583 0.694747 0.508596 -0.508583 0.694746 0.508596 -0.186148 0.694748 0.694748 -0.186148 0.694746 0.69475 0.186166 0.694746 0.694745 0.186165 0.694747 0.694744 0.508594 0.694749 0.508582 0.508597 0.694747 0.508583 0.694749 0.694746 0.186148 0.694752 0.694744 0.186148 0.694747 0.694744 -0.186167 0.694744 0.694747 -0.186165 0.508583 0.694747 -0.508596 0.508584 0.694745 -0.508598 0.186148 0.694746 -0.69475 0.186148 0.694746 -0.694749 -0.186166 0.694746 -0.694745 -0.186165 0.694746 -0.694745 -0.508597 0.694746 -0.508584 -0.508598 0.694745 -0.508584 -0.69475 0.694746 -0.186148 -0.69475 0.694746 -0.186148 -0.694745 0.694746 0.186166 -0.694744 0.694747 0.186166 -0.69475 0.694746 -0.186149 -0.508597 0.694745 -0.508585 -0.508595 0.694749 -0.508581 -0.186166 0.694751 -0.69474 -0.186166 0.694744 -0.694747 0.186149 0.694744 -0.694751 0.186148 0.694746 -0.69475 0.508584 0.694745 -0.508598 0.508583 0.694746 -0.508597 0.694745 0.694746 -0.186165 0.694742 0.694749 -0.186165 0.694749 0.694747 0.186147 0.69475 0.694746 0.186148 0.508597 0.694745 0.508585 0.508595 0.694749 0.508581 0.186163 0.69475 0.694741 0.186164 0.694753 0.694739 -0.186145 0.694753 0.694743 -0.186148 0.694747 0.694749 -0.508582 0.694748 0.508596 -0.508584 0.694746 0.508597 -0.694745 0.694746 0.186166 -0.694744 0.694747 0.186166 -0.694746 0.69475 -0.186147 -0.69475 0.694746 -0.186149 -0.508598 0.694745 -0.508583 -0.5086 0.694742 -0.508586 -0.186165 0.694741 -0.694749 -0.186166 0.694752 -0.694738 0.186145 0.694753 -0.694743 0.186149 0.694746 -0.69475 0.508586 0.694745 -0.508596 0.508579 0.694752 -0.508593 0.694742 0.694749 -0.186165 0.694746 0.694745 -0.186165 0.694753 0.694743 0.186149 0.69475 0.694746 0.186147 0.508598 0.694745 0.508584 0.508597 0.694746 0.508584 0.186165 0.694743 0.694748 0.186166 0.694752 0.694738 -0.186145 0.694753 0.694743 -0.186148 0.694747 0.694749 -0.508584 0.694748 0.508594 -0.50858 0.694752 0.508592 -0.694742 0.694749 0.186165 -0.694741 0.694749 0.186165 -0.694748 0.694747 -0.186148 -0.69475 0.694746 -0.186148 -0.508597 0.694745 -0.508585 -0.508598 0.694743 -0.508587 -0.186166 0.694741 -0.694749 -0.186166 0.694753 -0.694738 0.186145 0.694753 -0.694743 0.186153 0.694738 -0.694756 0.508586 0.694742 -0.5086 0.508588 0.694739 -0.508601 0.694747 0.694744 -0.186166 0.694744 0.694747 -0.186166 0.694746 0.694749 0.186147 0.694749 0.694746 0.186149 0.508597 0.694745 0.508585 0.508592 0.694755 0.508576 0.186167 0.69476 0.69473 0.186165 0.694735 0.694756 -0.186155 0.694734 0.694759 -0.186144 0.694754 0.694742 -0.50858 0.694752 0.508593 -0.508579 0.694752 0.508593 -0.694742 0.694749 0.186166 -0.694748 0.694743 0.186166 -0.69475 0.694745 -0.186148 -0.694749 0.694746 -0.186149 -0.508597 0.694745 -0.508585 -0.508591 0.694757 -0.508574 -0.186166 0.694761 -0.69473 -0.186165 0.694735 -0.694756 0.186155 0.694734 -0.694759 0.186143 0.694755 -0.694741 0.508577 0.694755 -0.508591 0.50858 0.694752 -0.508592 0.694742 0.694749 -0.186166 0.694744 0.694747 -0.186166 0.694746 0.69475 0.186146 0.69475 0.694746 0.186148 0.508597 0.694745 0.508585 0.508598 0.694743 0.508587 0.186166 0.694741 0.694749 0.186166 0.694753 0.694738 -0.186145 0.694753 0.694744 -0.186153 0.694738 0.694756 -0.508587 0.69474 0.508601 -0.508588 0.694739 0.508601 -0.694747 0.694744 0.186166 -0.694744 0.694747 0.186166 -0.694746 0.694749 -0.186147 -0.694748 0.694748 -0.186147 -0.508596 0.694746 -0.508584 -0.508592 0.694755 -0.508576 -0.186167 0.69476 -0.69473 -0.186165 0.694735 -0.694756 0.186155 0.694734 -0.694759 0.186143 0.694755 -0.694742 0.508579 0.694753 -0.508592 0.508579 0.694752 -0.508593 0.694742 0.694749 -0.186166 0.694746 0.694745 -0.186166 0.694748 0.694747 0.186147 0.694748 0.694748 0.186147 0.508596 0.694746 0.508584 0.508598 0.694743 0.508587 0.186166 0.694741 0.694749 0.186166 0.694753 0.694738 -0.186145 0.694753 0.694744 -0.186153 0.694738 0.694756 -0.508587 0.69474 0.508601 -0.508588 0.694739 0.508601 -0.694747 0.694744 0.186166 -0.694741 0.694749 0.186166 -0.694753 0.694742 -0.18615 -0.694749 0.694746 -0.186149 -0.508597 0.694745 -0.508585 -0.508592 0.694755 -0.508576 -0.186167 0.69476 -0.69473 -0.186165 0.694735 -0.694756 0.186155 0.694734 -0.694759 0.186143 0.694755 -0.694741 0.508577 0.694755 -0.508591 0.50858 0.694752 -0.508592 0.694742 0.694749 -0.186166 0.694744 0.694747 -0.186166 0.694746 0.69475 0.186146 0.69475 0.694746 0.186148 0.508597 0.694745 0.508585 0.508598 0.694743 0.508587 0.186166 0.694741 0.694749 0.186166 0.694753 0.694738 -0.186144 0.694753 0.694744 -0.186153 0.694737 0.694757 -0.508589 0.694738 0.508602 -0.508588 0.694739 0.508602 -0.694747 0.694744 0.186166 -0.694748 0.694743 0.186166 -0.69475 0.694745 -0.18615 -0.694749 0.694746 -0.186149 -0.508599 0.694745 -0.508582 -0.508595 0.694756 -0.508573 -0.186166 0.69476 -0.69473 -0.186165 0.694736 -0.694755 0.186161 0.694733 -0.694759 0.186149 0.694755 -0.69474 0.508576 0.694753 -0.508595 0.508588 0.69474 -0.508601 0.694746 0.694745 -0.186165 0.694745 0.694746 -0.186166 0.694747 0.694748 0.186148 0.694749 0.694746 0.186149 0.508599 0.694745 0.508582 0.508606 0.694731 0.508595 0.186165 0.694723 0.694768 0.186167 0.69477 0.694721 -0.18614 0.694771 0.694727 -0.186149 0.694756 0.69474 -0.508575 0.694754 0.508595 -0.508588 0.69474 0.508601 -0.694747 0.694744 0.186166 -0.694745 0.694745 0.186166 -0.694748 0.694748 -0.186148 -0.694749 0.694746 -0.186149 -0.5086 0.694745 -0.508582 -0.508607 0.69473 -0.508596 -0.186164 0.694723 -0.694768 -0.186167 0.69477 -0.694721 0.18614 0.694771 -0.694727 0.186149 0.694755 -0.69474 0.508576 0.694752 -0.508596 0.508588 0.694739 -0.508602 0.694747 0.694744 -0.186166 0.694748 0.694743 -0.186166 0.69475 0.694745 0.186148 0.69475 0.694746 0.186148 0.508599 0.694745 0.508582 0.508593 0.694758 0.508571 0.186166 0.694761 0.694729 0.186165 0.694735 0.694756 -0.186161 0.694734 0.694759 -0.186148 0.694756 0.694739 -0.508574 0.694755 0.508594 -0.508588 0.694739 0.508601 -0.694747 0.694744 0.186166 -0.694744 0.694747 0.186166 -0.694746 0.694749 -0.186147 0.508599 -0.694739 0.508592 0.508592 -0.694755 0.508576 0.186168 -0.69476 0.69473 0.186166 -0.694741 0.694749 -0.186156 -0.69474 0.694753 -0.186148 -0.694755 0.694741 -0.508579 -0.694752 0.508593 -0.508582 -0.694749 0.508594 -0.694743 -0.694747 0.186167 -0.694746 -0.694745 0.186167 -0.694749 -0.694747 -0.186146 -0.694752 -0.694743 -0.186149 -0.508599 -0.694739 -0.508592 -0.508592 -0.694755 -0.508576 -0.186168 -0.69476 -0.69473 -0.186166 -0.694741 -0.694749 0.186148 -0.694741 -0.694754 0.186153 -0.694733 -0.694761 0.50859 -0.694736 -0.508604 0.508593 -0.694734 -0.508605 0.694749 -0.694741 -0.186167 0.694746 -0.694745 -0.186167 0.694749 -0.694747 0.186146 0.694752 -0.694743 0.186149 -0.0944624 0 -0.995528 -0.201788 -0.00615412 -0.97941 -0.293699 0 -0.955898 -0.572628 0 -0.819815 -0.572628 0 -0.819815 -0.850148 0 -0.526544 -0.850148 0 -0.526544 -0.989057 0 -0.147534 -0.989057 0 -0.147534 0.131803 -0.990562 -0.0376096 -0.260964 -0.950184 0.170438 -0.151131 -0.988503 0.00451087 -0.261341 -0.962796 0.0687302 -0.16373 -0.98249 0.0889153 -0.109884 -0.986102 0.124613 -0.121524 -0.97809 0.169035 -0.0490734 -0.992115 0.115324 -0.0230844 -0.964862 0.261743 -0.00249668 -0.996091 0.0883007 0.23756 -0.971035 -0.0256185 0.0572281 -0.998213 0.0171994 0.108724 -0.99358 0.0312727 0.0806698 -0.993962 0.0743818 0.0325792 -0.998054 0.0531602 0.0578411 -0.993306 0.0999862 0.0231121 -0.992046 0.123733 -0.58196 -0.789225 0.196078 -0.529531 -0.828825 0.180685 -0.41079 -0.840118 0.354193 -0.41712 -0.834799 0.359335 -0.240812 -0.846769 0.474333 -0.244593 -0.841743 0.481293 -0.036924 -0.853253 0.520189 -0.0376043 -0.849478 0.526282 0.171582 -0.859076 0.482232 0.172523 -0.856973 0.485626 0.352003 -0.862834 0.362782 0.352472 -0.862382 0.363402 0.472646 -0.862855 0.179129 0.470908 -0.864023 0.178073 0.511578 -0.858317 -0.039734 0.520024 -0.85329 -0.038361 0.0665954 0.320242 0.944992 0.0412744 0.547142 0.836021 -0.0977361 -0.0984059 0.990335 -0.289075 -0.0877461 0.953276 -0.274909 0.558454 0.782658 -0.434202 0.101806 0.895044 -0.614058 -0.376392 0.69373 -0.608246 0.436827 0.662736 -0.804377 -0.236218 0.54514 -0.836998 -0.433526 0.333901 -0.905748 -0.19195 0.377858 -0.923666 0.127976 0.361198 0.559902 -0.609015 0.561792 0.862592 0.393715 0.317685 0.923918 -0.0989643 0.369568 0.991687 -0.0932027 0.0887088 0.847765 0.530202 0.0134124 0.952529 0.302371 -0.0354928 0.98235 -0.0975346 -0.159611 0.109816 0.117773 0.98695 0.220796 -0.601492 0.767761 0.382088 0.349353 0.855547 0.522884 -0.071632 0.849389 0.711435 -0.233229 0.662921 -0.788274 -0.279264 0.548302 -0.68201 -0.283205 0.674283 -0.683891 -0.265579 0.67953 -0.372002 -0.286557 0.882893 -0.371732 -0.268905 0.888541 -0.00442154 -0.289128 0.95728 -0.00238059 -0.273573 0.961848 0.365637 -0.290441 0.884282 0.368094 -0.279355 0.88683 0.681001 -0.289628 0.672572 0.68221 -0.285273 0.673208 0.890564 -0.286124 0.353594 0.889436 -0.289868 0.353383 0.959653 -0.280324 -0.0220319 0.953918 -0.299303 -0.0213957 -0.743226 -0.605109 0.28541 -0.78904 -0.535479 0.301126 -0.603101 -0.55366 0.574221 -0.609679 -0.541177 0.579154 -0.336524 -0.559626 0.757344 -0.340741 -0.547284 0.764445 -0.0185534 -0.565088 0.824822 -0.0196519 -0.554639 0.831859 0.303866 -0.569503 0.763762 0.304909 -0.562457 0.768552 0.580565 -0.571524 0.579918 0.581536 -0.569002 0.581423 0.765036 -0.569782 0.300113 0.763497 -0.572448 0.298956 0.825164 -0.564062 -0.030634 0.816781 -0.575997 -0.0330964 0.508597 -0.694746 0.508584 0.508596 -0.694747 0.508583 0.186165 -0.694747 0.694744 0.186165 -0.694749 0.694742 -0.186148 -0.694749 0.694747 -0.186149 -0.694747 0.694748 -0.508583 -0.694747 0.508596 -0.508583 -0.694747 0.508596 -0.694744 -0.694747 0.186166 -0.694744 -0.694747 0.186166 -0.694748 -0.694747 -0.186147 -0.694749 -0.694747 -0.186148 -0.508597 -0.694746 -0.508584 -0.508596 -0.694747 -0.508583 -0.186165 -0.694747 -0.694744 -0.186165 -0.694749 -0.694742 0.186148 -0.694749 -0.694747 0.186149 -0.694747 -0.694748 0.508583 -0.694747 -0.508596 0.508584 -0.694746 -0.508596 0.694744 -0.694747 -0.186166 0.694744 -0.694747 -0.186166 0.694748 -0.694747 0.186147 0.694749 -0.694747 0.186148 0.149764 -0.98861 0.014881 0.00525721 0.999986 0.000757261 0.0406709 0.999158 0.00546374 0.149763 -0.98861 0.0148809 0.149763 -0.98861 0.0148826 -0.576518 0.814613 0.0635069 0.638833 -0.766498 -0.0661352 -1.03638e-05 -1.35649e-05 -1 -1.05241e-05 -1.0307e-05 -1 -1.01207e-05 -1.87459e-05 -1 -9.92547e-06 -2.81894e-05 -1 -1.44424e-05 0.000326848 -1 0 -6.1133e-06 -1 -1.31958e-05 0 -1 -1.57831e-05 4.67451e-05 -1 -1.11817e-05 -1.63741e-06 -1 -1.08666e-05 -5.37195e-06 -1 -1.43024e-05 -0.000433988 -1 -1.42873e-05 -0.000612796 -1 -1.41764e-05 -0.0026007 -0.999997 -1.5724e-05 2.47023e-06 -1 -1.14542e-05 -1.10559e-06 -1 -1.27431e-05 8.33579e-07 -1 -1.33371e-05 -1.25051e-07 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.20361e-05 -3.43983e-07 -1 -1.76868e-05 -2.658e-06 -1 0.99131 0.0108441 -0.131097 -0.991294 -0.0134319 0.13098 -0.998237 0.000357666 0.0593528 -0.998229 0.000355976 0.0594822 -0.997479 0.0386731 0.059502 0.982781 -0.175869 -0.0566785 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854942 0 -0.518724 0.854942 0 -0.518724 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217578 0 -0.999763 -0.0217578 0 -0.999763 0.486393 0 0.87374 0.486393 0 0.87374 0.817329 0 0.576172 0.817329 0 0.576172 0.986379 0 0.16449 0.986379 0 0.16449 0.960066 0 -0.279774 0.960066 0 -0.279774 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591253 0 -0.998251 -0.0591253 0 -0.998251 0.518724 0 0.854942 0.518724 0 0.854942 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.0217574 0.999763 0 -0.0217574 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.486395 0 0.873739 0.486395 0 0.873739 0.817327 0 0.576174 0.817327 0 0.576174 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279775 0.960066 0 -0.279775 0.743601 0 -0.668624 0.743601 0 -0.668624 0.379854 0 -0.925047 0.379854 0 -0.925047 -0.0591235 0 -0.998251 -0.0591235 0 -0.998251 0.486394 0 0.87374 0.486394 0 0.87374 0.817327 0 0.576174 0.817327 0 0.576174 0.986379 0 0.164488 0.986379 0 0.164488 0.960066 0 -0.279774 0.960066 0 -0.279774 0.7436 0 -0.668624 0.7436 0 -0.668624 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591253 0 -0.998251 -0.0591253 0 -0.998251 0.486395 0 0.873739 0.486395 0 0.873739 0.817327 0 0.576174 0.817327 0 0.576174 0.986379 0 0.164487 0.986379 0 0.164487 0.960066 0 -0.279774 0.960066 0 -0.279774 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379856 0 -0.925046 0.379856 0 -0.925046 -0.0591249 0 -0.998251 -0.0591249 0 -0.998251 0.486395 0 0.873739 0.486395 0 0.873739 0.817327 0 0.576174 0.817327 0 0.576174 0.986379 0 0.16449 0.986379 0 0.16449 0.960065 0 -0.279776 0.960065 0 -0.279776 0.7436 0 -0.668624 0.7436 0 -0.668624 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591253 0 -0.998251 -0.0591253 0 -0.998251 0.486395 0 0.873739 0.486395 0 0.873739 0.817328 0 0.576173 0.817328 0 0.576173 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279775 0.960066 0 -0.279775 0.743601 0 -0.668624 0.743601 0 -0.668624 0.379854 0 -0.925047 0.379854 0 -0.925047 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.518724 0 0.854942 0.518724 0 0.854942 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.518724 0 0.854942 0.518724 0 0.854942 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217585 0.999763 0 -0.0217585 0.854942 0 -0.518724 0.854942 0 -0.518724 0.48104 0 -0.876699 0.48104 0 -0.876699 -0.0217585 0 -0.999763 -0.0217585 0 -0.999763 0.486395 0 0.873739 0.486395 0 0.873739 0.817326 0 0.576175 0.817326 0 0.576175 0.986379 0 0.164487 0.986379 0 0.164487 0.960066 0 -0.279774 0.960066 0 -0.279774 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379856 0 -0.925046 0.379856 0 -0.925046 -0.0591242 0 -0.998251 -0.0591242 0 -0.998251 0.518724 0 0.854942 0.518724 0 0.854942 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217575 0.999763 0 -0.0217575 0.854942 0 -0.518724 0.854942 0 -0.518724 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217579 0 -0.999763 -0.0217579 0 -0.999763 0.256245 0.707106 0.659045 0.256239 0.707118 0.659033 0.256248 0.70711 0.659039 0.256247 0.70711 0.659039 0.256245 0.707105 0.659046 0.256245 0.707105 0.659046 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217574 0 0.999763 0.0217574 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.8767 0 -0.481039 -0.8767 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217585 0 0.999763 0.0217585 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217585 -0.999763 0 0.0217585 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217585 0 0.999763 0.0217585 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.85494 0 0.518726 -0.85494 0 0.518726 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.999763 0 0.0217585 -0.999763 0 0.0217585 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481039 0 0.8767 -0.481039 0 0.8767 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.986379 0 -0.164488 -0.986379 0 -0.164488 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.7436 0 0.668624 -0.7436 0 0.668624 -0.379854 0 0.925047 -0.379854 0 0.925047 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217575 -0.999763 0 0.0217575 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217577 0 0.999763 0.0217577 0 0.999763 0.137911 -0.707102 0.693532 0.13791 -0.707106 0.693528 0.13784 -0.707465 0.693177 0.137907 -0.707118 0.693517 0.13791 -0.707102 0.693533 0.629329 -0.516323 0.580822 0.629329 -0.516324 0.580822 0.73486 0 0.678219 0.73486 0 0.678219 0.706745 -0.707079 -0.023476 0.706694 -0.707145 -0.0230028 0.706798 -0.707051 -0.0226971 0.257728 -0.656627 0.708814 0.270722 -0.66243 0.698496 0.371717 -0.592791 0.714441 0.462588 -0.551132 0.694454 0.49966 -0.548174 0.670705 0.56675 -0.421568 0.707866 0.665676 -0.357968 0.654778 0.668135 -0.266518 0.694668 0.745243 -0.122396 0.655463 0.731632 -0.0936308 0.67524 0.146355 -0.660977 0.735996 0.146355 -0.660977 0.735996 -0.00716858 -0.653016 0.75731 -0.0071685 -0.653016 0.75731 -0.309494 -0.653016 0.691219 -0.309493 -0.653016 0.691219 -0.560142 -0.653017 0.509716 -0.560143 -0.653016 0.509716 -0.717266 -0.653015 0.243106 -0.717264 -0.653017 0.243106 -0.70203 -0.659746 0.268121 -0.702031 -0.659745 0.268121 -0.736165 -0.659745 0.150986 -0.736164 -0.659747 0.150985 -0.735576 -0.653017 0.180269 -0.735577 -0.653016 0.180268 -0.746275 -0.653016 -0.129012 -0.746274 -0.653017 -0.129011 -0.632368 -0.653017 -0.41675 -0.632368 -0.653016 -0.41675 -0.412876 -0.653017 -0.634904 -0.412876 -0.653017 -0.634904 -0.271936 -0.660977 -0.6994 -0.271936 -0.660977 -0.6994 0.255092 -0.0554222 -0.965327 0.289077 -0.124765 -0.949141 0.209407 -0.197653 -0.957644 0.204969 -0.356021 -0.911722 0.144075 -0.375071 -0.915731 0.0488905 -0.536367 -0.842568 0.0303925 -0.534727 -0.844478 -0.157602 -0.642014 -0.75032 -0.132454 -0.653845 -0.744945 0.255484 0 -0.966813 0.255484 0 -0.966813 0.576955 -0.745839 -0.332936 0.612168 -0.706189 -0.355736 0.554035 -0.765444 -0.327324 0.44605 -0.854541 -0.266083 0.665768 -0.745589 -0.029139 0.632809 -0.773755 -0.0292631 0.929774 -0.368088 -0.0055751 0.608776 -0.793309 0.00729368 0.705606 -0.706804 -0.0504922 0.69721 -0.706465 -0.121677 0.818845 -0.549974 -0.164381 0.683773 -0.706993 -0.180598 0.660714 -0.705813 -0.255509 0.72499 -0.632549 -0.272528 0.638255 -0.70709 -0.304392 0.218801 -0.516319 -0.827974 0.218794 -0.516328 -0.82797 -0.256244 -0.707108 -0.659043 -0.256246 -0.707105 -0.659046 -0.256245 -0.707107 -0.659043 0.608334 -0.707054 -0.360563 0.608406 -0.707144 -0.360264 0.608738 -0.70707 -0.359847 -0.137911 -0.707103 -0.693532 -0.13791 -0.707106 -0.693529 -0.137909 -0.707115 -0.69352 -0.629323 -0.516337 -0.580817 -0.62934 -0.516316 -0.580817 -0.73486 0 -0.678219 -0.73486 0 -0.678219 -0.706755 -0.707069 0.0234763 -0.706699 -0.707141 0.0229557 -0.706788 -0.707061 0.0226967 -0.257725 -0.656626 -0.708816 -0.270724 -0.66243 -0.698494 -0.371724 -0.592788 -0.71444 -0.462589 -0.551132 -0.694454 -0.49966 -0.548174 -0.670705 -0.56675 -0.421569 -0.707866 -0.665673 -0.35797 -0.654781 -0.668132 -0.266516 -0.694672 -0.745241 -0.122391 -0.655467 -0.731632 -0.0936308 -0.67524 -0.146355 -0.660976 -0.735997 -0.146355 -0.660976 -0.735997 0.00716851 -0.653016 -0.75731 0.00716853 -0.653016 -0.75731 0.309492 -0.653018 -0.691218 0.309494 -0.653015 -0.691219 0.560143 -0.653015 -0.509717 0.560143 -0.653015 -0.509717 0.717266 -0.653015 -0.243106 0.717266 -0.653015 -0.243106 0.702031 -0.659746 -0.268121 0.702031 -0.659745 -0.268121 0.736165 -0.659745 -0.150986 0.736166 -0.659744 -0.150986 0.735577 -0.653016 -0.180269 0.735577 -0.653016 -0.180268 0.746275 -0.653016 0.129011 0.746276 -0.653014 0.129011 0.632369 -0.653015 0.416751 0.632367 -0.653018 0.416748 0.412876 -0.653018 0.634903 0.412876 -0.653015 0.634905 0.271936 -0.660976 0.699401 0.271936 -0.660975 0.699402 -0.255092 -0.0554222 0.965327 -0.289077 -0.124765 0.949141 -0.209407 -0.197653 0.957644 -0.204969 -0.356021 0.911722 -0.144074 -0.375071 0.915732 -0.0488902 -0.536367 0.842568 -0.0303925 -0.534727 0.844478 0.157602 -0.642014 0.75032 0.132458 -0.653843 0.744946 -0.255484 0 0.966813 -0.255484 0 0.966813 -0.669803 -0.742134 0.024526 -0.64363 -0.765033 0.0215706 -0.518892 -0.854705 0.015183 -0.509703 -0.793173 0.333285 -0.570473 -0.733547 0.369418 -0.582861 -0.721056 0.374635 -0.694843 -0.597011 0.400963 -0.70727 -0.706266 0.0309551 -0.701857 -0.707091 0.0861302 -0.751743 -0.641956 0.150911 -0.692931 -0.706083 0.145921 -0.673748 -0.706993 0.214999 -0.778963 -0.549975 0.301238 -0.653428 -0.706466 0.271915 -0.622269 -0.706805 0.336465 -0.218799 -0.516321 0.827973 -0.218794 -0.516328 0.82797 0.256245 -0.707107 0.659044 0.256246 -0.707104 0.659046 0.256248 -0.7071 0.65905 0.256216 -0.707186 0.658969 0.256193 -0.70725 0.65891 -0.608334 -0.707054 0.360563 -0.608407 -0.707145 0.360259 -0.608729 -0.707073 0.359856 0.622226 0 -0.782838 0.622231 1.19973e-06 -0.782834 0.62222 -4.54978e-07 -0.782843 0.622247 9.63511e-07 -0.782821 0.622211 0 -0.78285 0.351375 0.505902 -0.787781 0.351367 0.50548 -0.788055 0.351541 0.50562 -0.787888 0.351622 0.505283 -0.788068 -0.0895204 0.706252 -0.702278 0.0107289 0.732281 -0.680918 0.0555835 0.704939 -0.707086 0.167158 0.661212 -0.731339 0.285344 0.638593 -0.714687 0.331089 0.561479 -0.758367 0.504989 0.436208 -0.744788 0.509534 0.377958 -0.772996 0.624161 0.154483 -0.765871 0.616558 0.134667 -0.775707 -0.137906 0.707109 -0.693527 -0.13791 0.707105 -0.693529 -0.13791 0.707106 -0.693529 -0.137912 0.707105 -0.693529 -0.137905 0.707112 -0.693523 -0.13791 0.707109 -0.693526 -0.13791 0.707108 -0.693527 -0.13791 0.707107 -0.693527 -0.0546422 0.704583 -0.707515 0.0308439 0.774381 -0.631967 0.118693 0.704295 -0.699915 0.368335 0.696303 -0.616029 0.370341 0.552185 -0.746953 0.459123 0.706014 -0.539213 0.692027 0.698758 -0.181209 0.692026 0.698758 -0.181211 0.552713 0.698758 -0.454143 0.552713 0.698758 -0.454143 0.311977 0.698758 -0.643745 0.311977 0.698758 -0.643745 0.0139932 0.698758 -0.715221 0.0139936 0.698758 -0.715221 0.838516 0.511364 -0.188146 0.848739 0.453602 -0.271822 0.925076 0.330103 -0.187794 0.922008 0.335246 -0.193679 0.941364 0.291655 -0.169623 0.945175 0.29078 -0.148631 0.962083 0.235649 -0.137351 0.8134 0.525108 -0.250283 0.767432 0.552313 -0.325575 0.605406 0.698132 -0.382223 0.95818 0.23545 -0.162649 0.94438 -0.265762 -0.19369 0.941786 0.23557 -0.239887 0.92322 0.235569 -0.303598 0.900593 -0.265756 -0.343956 0.895554 0.235453 -0.37755 0.696004 0.706824 0.12641 0.74154 0.667659 -0.0659451 0.820487 0.554927 -0.137322 0.840486 0.495386 -0.219489 0.844873 0.469763 -0.255952 0.880514 0.235691 -0.411273 0.881288 0.263386 -0.392377 0.881991 0.262706 -0.39125 0.897273 0.350559 -0.268344 0.80979 0.472565 -0.347738 0.833934 0.466409 -0.294986 0.41463 0.696302 0.585872 0.300911 0.807761 0.506927 0.47611 0.704294 0.526583 0.609451 0.702169 0.368141 0.706576 0.612555 0.354298 0.676916 0.706013 0.208158 0.719996 0.50544 0.475537 0.719731 0.505526 0.475847 0.71981 0.505718 0.475524 0.719498 0.505735 0.475978 0.945361 -2.73911e-06 0.326027 0.945366 0 0.326012 0.94536 -3.36871e-07 0.326027 0.945361 -6.28134e-08 0.326025 0.945361 0 0.326026 0.942315 0.0802135 0.324975 0.942706 0.156949 0.294401 0.883174 0.284083 0.373229 0.827067 0.439086 0.350946 0.745996 0.501862 0.437749 0.624049 0.638079 0.451019 0.5518 0.64585 0.527632 0.375798 0.726838 0.574876 0.333165 0.70464 0.626486 0.256244 0.707108 0.659042 0.256244 0.707108 0.659042 0.396022 0.698759 0.595737 0.396019 0.698757 0.595741 0.608961 0.698758 0.375372 0.608961 0.698757 0.375373 0.710155 0.698757 0.0861316 0.710155 0.698757 0.0861319 0.681039 0.698757 -0.218915 0.681036 0.69876 -0.218919 0.137904 0.70711 0.693526 0.13791 0.707106 0.693529 0.13791 0.707106 0.693529 0.137914 0.707105 0.693529 0.137907 0.707112 0.693523 0.13791 0.70711 0.693525 0.0546422 0.704583 0.707515 -0.030844 0.774381 0.631967 -0.118693 0.704295 0.699915 -0.368335 0.696305 0.616027 -0.370341 0.552185 0.746953 -0.459122 0.706012 0.539216 -0.351378 0.505901 0.78778 -0.35137 0.505478 0.788055 -0.351545 0.505617 0.787888 -0.351627 0.505276 0.78807 -0.838515 0.511366 0.188142 -0.848739 0.453602 0.271822 -0.925067 0.330121 0.187806 -0.922007 0.335251 0.193676 -0.941362 0.291661 0.169621 -0.945173 0.290787 0.14863 -0.962081 0.235658 0.13735 -0.813391 0.525115 0.250299 -0.767432 0.552313 0.325575 -0.605409 0.698131 0.382222 -0.622223 0 0.78284 -0.622224 1.851e-07 0.782839 -0.622226 5.50591e-07 0.782837 -0.622219 2.01595e-07 0.782843 -0.622211 0 0.78285 -0.958178 0.235459 0.162648 -0.944383 -0.265753 0.193691 -0.941786 0.235569 0.239886 -0.92322 0.235569 0.303598 -0.900592 -0.265758 0.343956 -0.895554 0.235456 0.377551 -0.0409125 0.710098 0.702913 0.0818718 0.764801 0.639043 0.00219849 0.700436 0.713712 -0.153009 0.667519 0.728702 -0.280492 0.633436 0.721168 -0.326468 0.572592 0.752035 -0.499245 0.433183 0.750404 -0.509029 0.386558 0.769065 -0.620042 0.153818 0.769343 -0.616299 0.137656 0.775388 -0.696004 0.706824 -0.12641 -0.74154 0.667659 0.0659451 -0.820487 0.554927 0.137322 -0.840494 0.495356 0.219529 -0.844875 0.46976 0.255952 -0.880513 0.235693 0.411273 -0.881287 0.263392 0.392374 -0.881993 0.262711 0.391244 -0.897273 0.350558 0.268346 -0.809789 0.472566 0.347741 -0.83394 0.466407 0.294971 0.13791 0.707108 0.693527 0.13791 0.707107 0.693528 -0.41463 0.696303 -0.585871 -0.300912 0.807761 -0.506927 -0.476108 0.704295 -0.526583 -0.60945 0.70217 -0.368141 -0.706575 0.612556 -0.354298 -0.676915 0.706013 -0.208161 -0.692027 0.698757 0.181209 -0.692026 0.698758 0.181211 -0.552713 0.698758 0.454143 -0.552713 0.698758 0.454143 -0.311974 0.698758 0.643746 -0.311973 0.698759 0.643746 -0.0139937 0.698758 0.715221 -0.0139936 0.698758 0.715221 -0.256245 0.707106 -0.659044 -0.256243 0.70711 -0.659042 -0.256257 0.707108 -0.659037 -0.256243 0.707109 -0.659042 -0.256242 0.707107 -0.659045 -0.256244 0.707108 -0.659043 -0.720014 0.50543 -0.475521 -0.719686 0.505412 -0.476037 -0.719575 0.505897 -0.475688 -0.965689 -1.14195e-05 -0.259701 -0.965688 0 -0.259706 -0.965688 0 -0.259706 -0.960651 0.102004 -0.258351 -0.958449 0.164387 -0.233136 -0.922742 0.264766 -0.280084 -0.867612 0.396346 -0.300264 -0.838851 0.462043 -0.287828 -0.737073 0.556828 -0.382969 -0.626367 0.67645 -0.387401 -0.526267 0.701845 -0.480059 -0.362418 0.778314 -0.512719 -0.30505 0.760951 -0.572623 -0.234157 0.763206 -0.602235 -0.234157 0.763206 -0.602235 -0.637959 0.765318 -0.0854205 -0.651481 0.755639 -0.0676964 -0.562155 0.755356 -0.336779 -0.562155 0.755353 -0.336784 -0.365083 0.755353 -0.544203 -0.365085 0.755355 -0.544198 0.107989 -0.704061 0.701881 0.107988 -0.704062 0.70188 -0.0773509 -0.704062 0.705913 -0.0773509 -0.704062 0.705913 -0.257419 -0.704062 0.66184 -0.257419 -0.704062 0.66184 -0.419945 -0.704062 0.572664 -0.419945 -0.704062 0.572664 -0.553852 -0.704062 0.444461 -0.553852 -0.704061 0.444461 -0.650015 -0.704061 0.285969 -0.650014 -0.704062 0.285969 -0.701879 -0.704062 0.107988 -0.70188 -0.704062 0.107988 -0.705913 -0.704062 -0.0773509 -0.705913 -0.704062 -0.0773509 -0.66184 -0.704062 -0.257419 -0.66184 -0.704062 -0.257419 -0.572663 -0.704062 -0.419945 -0.572663 -0.704062 -0.419945 -0.444461 -0.704062 -0.553852 -0.444461 -0.704062 -0.553851 -0.285969 -0.704062 -0.650014 -0.285969 -0.704061 -0.650015 -0.171246 -0.706837 -0.686336 -0.0336577 -0.84134 -0.539457 -0.111759 -0.843838 -0.524831 -0.1202 -0.706895 -0.69703 -0.0654702 -0.706775 -0.704402 0.299017 -0.707053 -0.640831 0.214402 -0.816206 -0.536507 -0.0133878 -0.706947 -0.70714 0.0418302 -0.706707 -0.706268 0.0466645 -0.83618 -0.546467 0.0937192 -0.706985 -0.700992 0.129252 -0.706995 -0.695307 0.170536 -0.580476 -0.79622 0.159162 -0.780713 -0.60428 0.198657 -0.707024 -0.678714 0.251168 -0.706544 -0.661597 0.483137 -0.749663 -0.45231 0.518993 -0.706144 -0.481671 0.476934 -0.707094 -0.522065 0.439042 -0.740726 -0.508496 0.539621 -0.488022 -0.686035 0.421562 -0.706866 -0.568002 0.39249 -0.707079 -0.58821 0.367479 -0.735246 -0.569537 0.402688 -0.575129 -0.712088 0.344504 -0.696454 -0.629499 0.311014 -0.707106 -0.635036 0.550405 -0.707104 -0.443912 0.584146 -0.706144 -0.400167 0.584143 -0.706148 -0.400165 -0.0139937 -0.698758 0.715221 -0.0139937 -0.698758 0.715221 -0.311975 -0.698757 0.643747 -0.311975 -0.698758 0.643745 -0.552713 -0.698758 0.454143 -0.552713 -0.698758 0.454143 -0.692026 -0.698758 0.181209 -0.692024 -0.698761 0.181205 0.681035 -0.698762 -0.218914 0.681038 -0.698756 -0.218921 0.710155 -0.698757 0.0861316 0.710155 -0.698757 0.0861313 0.608962 -0.698756 0.375373 0.608957 -0.69876 0.375374 0.396022 -0.698758 0.595738 0.396023 -0.698757 0.595738 0.13791 -0.707108 0.693527 0.13791 -0.707108 0.693527 0.256245 -0.707107 0.659043 0.256245 -0.707104 0.659047 0.16811 -0.706771 0.687178 0.266741 -0.76118 0.591147 0.321365 -0.701067 0.636577 0.551625 -0.697813 0.45691 0.551623 -0.697815 0.456909 0.696323 -0.697816 0.167891 0.696326 -0.697813 0.167891 0.227363 -0.706767 0.669915 0.0925818 -0.761178 0.641901 0.0709155 -0.701068 0.709559 -0.219817 -0.697813 0.681717 -0.219817 -0.697813 0.681717 -0.497125 -0.697814 0.515676 -0.497126 -0.697812 0.515678 0.705247 -0.705821 0.0666524 -0.274661 -0.705818 0.65298 -0.58431 -0.707019 0.398379 -0.435717 -0.833762 0.339104 -0.274657 -0.705825 0.652973 -0.368072 -0.706398 0.604587 -0.298418 -0.832368 0.467022 -0.417824 -0.707026 0.570559 -0.477145 -0.705823 0.523591 -0.477145 -0.705822 0.523591 -0.548757 -0.706407 0.447051 0.144254 -0.856825 0.495018 0.16881 -0.706789 0.686988 0.0799687 -0.705824 0.703859 0.0799689 -0.70582 0.703863 -0.0405694 -0.70582 0.707229 -0.0405691 -0.705822 0.707226 -0.159931 -0.705822 0.690099 -0.129743 -0.798341 0.588063 -0.210569 -0.707084 0.67505 0.301904 -0.856344 0.418961 0.386909 -0.706833 0.59219 0.310667 -0.705822 0.636633 0.310669 -0.705816 0.636638 0.226672 -0.706781 0.670134 0.424556 -0.856371 0.293907 0.562654 -0.70683 0.428733 0.505619 -0.705821 0.496152 0.505619 -0.70582 0.496152 0.435966 -0.706737 0.557186 0.705248 -0.705821 0.0666526 0.688033 -0.706538 0.165573 0.514128 -0.84632 0.139337 0.671037 -0.706967 0.223397 0.642388 -0.705824 0.298579 0.64239 -0.705823 0.298579 0.597178 -0.706741 0.379336 0.707682 -0.706024 0.0267914 0.707676 -0.706029 0.0267915 0.69818 -0.706728 0.114373 0.862341 -0.47982 0.16168 0.658505 -0.73505 0.161469 0.682726 -0.707095 0.184126 0.667997 -0.706359 0.234174 0.557393 -0.804902 0.203584 0.647038 -0.707076 0.28528 0.638766 -0.707066 0.303374 0.720942 -0.577124 0.383627 0.635334 -0.689154 0.34845 0.366647 -0.843778 0.391929 0.591988 -0.713406 0.37497 0.596462 -0.707055 0.379876 0.571599 -0.706739 0.416886 0.628467 -0.620728 0.468749 0.51139 -0.739358 0.437984 0.532166 -0.707022 0.465745 0.496681 -0.706626 0.503972 0.222004 -0.853249 0.471891 0.45562 -0.706989 0.540904 0.414692 -0.706706 0.573234 0.295851 -0.849792 0.436264 0.368588 -0.706944 0.603633 0.323186 -0.706775 0.629301 0.273065 -0.706892 0.652487 0.224264 -0.706835 0.670887 0.145386 -0.854376 0.498903 0.171245 -0.706839 0.686333 0.1202 -0.706896 0.69703 0.0662521 -0.853248 0.51728 0.0654709 -0.706775 0.704402 0.0133869 -0.706945 0.707142 -0.0151739 -0.84979 0.526903 -0.0418296 -0.706706 0.70627 -0.0937186 -0.706989 0.700987 -0.0970338 -0.786566 0.609834 -0.170537 -0.580467 0.796226 -0.165279 -0.706981 0.687649 -0.198657 -0.707028 0.678709 -0.184199 -0.83479 0.518842 -0.251167 -0.706544 0.661597 -0.300612 -0.707038 0.640102 -0.295928 -0.714288 0.634208 -0.348683 -0.68916 0.6352 -0.401994 -0.577126 0.710863 -0.375795 -0.707068 0.599026 -0.392492 -0.707079 0.588209 -0.374152 -0.769181 0.518045 -0.539593 -0.488101 0.686 -0.457555 -0.706969 0.539295 -0.476934 -0.707094 0.522065 -0.451753 -0.781488 0.430344 -0.516817 -0.706256 0.483841 -0.569526 -0.706704 0.419774 -0.767389 -0.359964 0.530603 -0.600332 -0.706944 0.373939 0.0139932 -0.698758 -0.715221 0.0139937 -0.698758 -0.715221 0.311976 -0.69876 -0.643744 0.311975 -0.698758 -0.643746 0.552713 -0.698758 -0.454143 0.552713 -0.698758 -0.454143 0.692026 -0.698758 -0.181209 0.692029 -0.698754 -0.181214 -0.681038 -0.698756 0.218921 -0.681038 -0.698756 0.218921 -0.710155 -0.698757 -0.0861316 -0.710155 -0.698757 -0.0861317 -0.608958 -0.698758 -0.375377 -0.608963 -0.698754 -0.375375 -0.396027 -0.698755 -0.595739 -0.396017 -0.698761 -0.595737 -0.13791 -0.707107 -0.693527 -0.13791 -0.707108 -0.693527 -0.256244 -0.707109 -0.659041 -0.256244 -0.707106 -0.659044 -0.16811 -0.70677 -0.687179 -0.168108 -0.706771 -0.687178 -0.0503919 -0.698977 -0.713367 -0.0503909 -0.698979 -0.713365 0.248948 -0.69898 -0.670412 0.248948 -0.698976 -0.670416 0.503773 -0.698975 -0.507589 0.503771 -0.69898 -0.507584 0.584192 -0.707019 -0.398552 0.445519 -0.826986 -0.342938 0.302671 -0.841782 -0.446983 0.424069 -0.706923 -0.566061 0.485345 -0.705976 -0.515789 0.485342 -0.705979 -0.515787 0.550905 -0.706528 -0.44421 0.147237 -0.841059 -0.52052 0.225283 -0.706938 -0.670437 0.298739 -0.705982 -0.64214 0.29874 -0.705979 -0.642143 0.377658 -0.706707 -0.598281 -0.143251 -0.705976 -0.693597 -0.14325 -0.705981 -0.693592 -0.031076 -0.705982 -0.707548 -0.0310758 -0.705975 -0.707555 0.0818912 -0.705975 -0.703486 0.0818914 -0.705974 -0.703488 0.171121 -0.706688 -0.68652 0.300637 0 0.953739 0.321385 -0.00153858 0.946947 0.341982 0 0.939707 -0.23763 0 -0.971356 -0.305197 0.00987401 -0.952238 -0.476172 -0.0332955 -0.878722 -0.504266 -0.0178852 -0.863363 -0.604843 -0.0034634 -0.796338 -0.796929 0.0268125 -0.603477 -0.770056 -0.0134094 -0.637836 -0.97537 0.0126219 -0.220213 -0.972141 0 -0.234396 0.365805 0 0.930692 0.450474 -0.0288732 0.892323 0.527894 -0.000740602 0.84931 0.627613 0.000231681 0.778525 0.769938 -0.022052 0.637738 0.797167 0.0110306 0.603658 0.972074 -0.0118254 0.234377 0.975448 0 0.22023 0.704434 0 -0.709769 0.693989 0.0118252 -0.719888 0.348089 -0.0110305 -0.937397 0.306813 0.0220531 -0.951514 -0.321386 0 -0.946948 -0.254129 0.00987363 -0.96712 -0.0704249 -0.0332964 -0.996961 -0.0384751 -0.0178845 -0.999099 0.0821208 -0.00349148 -0.996616 0.967385 0 -0.253312 0.967385 0 -0.253312 0.772638 0 -0.634847 0.772638 0 -0.634847 0.436113 0 -0.899892 0.436113 0 -0.899892 0.0195611 0 -0.999809 0.0195611 0 -0.999809 0.5536 0 0.832783 0.5536 0 0.832783 0.851267 0 0.524733 0.851267 0 0.524733 0.992725 0 0.120403 0.992725 0 0.120403 0.952025 0 -0.306022 0.952025 0 -0.306022 -0.967385 0 0.253312 -0.967385 0 0.253312 -0.772638 0 0.634847 -0.772638 0 0.634847 -0.436109 0 0.899894 -0.436109 0 0.899894 -0.0195618 0 0.999809 -0.0195618 0 0.999809 -0.992717 -0.00402437 -0.120402 -0.952022 0 0.306029 -0.915049 -0.0232936 0.402669 -0.98365 0.00221254 0.180076 -0.991153 -0.00162918 -0.132712 -0.857834 0.0017657 -0.513923 -0.851263 -0.000882771 -0.524739 -0.557113 0.000900337 -0.830437 -0.553604 0 -0.83278 0.195035 3.14285e-07 0.980796 0.195038 1.03515e-06 0.980796 0.195033 -5.13403e-07 0.980797 0.195037 0 0.980796 0.195037 0 0.980796 0.195033 -6.07621e-07 0.980797 0.195035 -1.94873e-07 0.980796 0.195034 0 0.980796 0.195034 6.47349e-07 0.980796 0.195034 -2.42639e-07 0.980797 0.195034 -4.33397e-07 0.980797 0.195034 -6.19026e-07 0.980797 0.195035 1.06121e-06 0.980796 0.195034 -6.92718e-07 0.980796 0.195034 -2.80116e-07 0.980796 0.195034 0 0.980796 0.195034 0 0.980796 -0.362384 0 -0.932029 -0.362384 -2.03932e-06 -0.932029 -0.362386 -3.69138e-06 -0.932028 -0.362384 -9.73956e-07 -0.932029 -0.362384 -3.8841e-06 -0.932029 -0.362385 0 -0.932028 -0.362386 -6.93359e-07 -0.932028 -0.362381 1.43541e-06 -0.93203 -0.362387 0 -0.932028 -0.362387 0 -0.932028 -0.362384 7.11615e-07 -0.932029 -0.362383 1.16053e-06 -0.932029 -0.362384 0 -0.932029 -0.362385 -3.113e-06 -0.932029 -0.362385 -1.36266e-06 -0.932028 -0.362382 8.70725e-06 -0.93203 -0.362387 -1.09962e-06 -0.932028 -0.00946543 0 0.999955 -0.0479018 -0.185548 0.981467 -0.403948 0.151367 0.902172 -0.444202 0 0.895927 -0.976908 0 0.213659 -0.951479 0.0781197 0.297633 -0.941822 0.105228 0.319216 -0.876773 -0.0529027 0.477986 -0.734352 0.119072 0.668243 -0.741178 0.378153 0.554667 -0.648295 0 0.76139 -0.929851 0 0.367936 -0.967909 0.0829814 0.237207 -0.987828 -0.019281 0.154348 -0.996274 0.0163457 -0.084683 -0.935872 0.298397 -0.187358 -0.959419 0.22805 -0.165859 -0.955827 0 -0.29393 -0.834981 0 -0.550278 -0.841095 0.185548 -0.508067 -0.531954 -0.218794 -0.818018 -0.577681 0 -0.816262 0.362384 0 0.932029 0.362384 -6.88269e-07 0.932029 0.36239 -6.0037e-06 0.932027 0.362385 -3.0842e-06 0.932029 0.362384 -1.2947e-06 0.932029 0.362385 0 0.932029 0.362384 5.58974e-07 0.932029 0.362384 6.68674e-07 0.932029 0.362388 0 0.932027 0.362388 0 0.932027 0.36238 1.14876e-06 0.93203 0.362384 -4.82881e-08 0.932029 0.362384 0 0.932029 0.362385 -5.67803e-06 0.932029 0.362385 -4.75006e-06 0.932028 0.362383 5.1632e-06 0.932029 0.362386 -1.93343e-06 0.932028 -0.195034 -3.66664e-07 -0.980797 -0.195033 -6.5439e-07 -0.980797 -0.195035 1.62664e-07 -0.980796 -0.195034 0 -0.980797 -0.195034 0 -0.980797 -0.195034 0 -0.980797 -0.195035 1.34134e-07 -0.980796 -0.195034 0 -0.980796 -0.195034 -6.04193e-07 -0.980796 -0.195035 2.6286e-06 -0.980796 -0.195034 -5.4812e-07 -0.980797 -0.195035 1.15602e-07 -0.980796 -0.195034 -5.146e-07 -0.980796 -0.195034 0 -0.980796 -0.195034 3.45286e-07 -0.980796 -0.195034 0 -0.980796 -0.195034 0 -0.980796 0.92985 0 -0.36794 0.967909 0.0829842 -0.237206 0.987829 -0.0192807 -0.154346 0.996274 0.0163457 0.084683 0.935872 0.298397 0.187358 0.95942 0.228046 0.165857 0.955828 0 0.293926 0.834981 0 0.550279 0.841094 0.185554 0.508066 0.531955 -0.21879 0.818019 0.577681 0 0.816262 0.00946533 0 -0.999955 0.0479016 -0.185547 -0.981467 0.403946 0.151371 -0.902172 0.444202 0 -0.895927 0.976908 0 -0.213659 0.951479 0.0781197 -0.297633 0.941822 0.105228 -0.319216 0.876773 -0.0529028 -0.477986 0.734352 0.119072 -0.668243 0.741179 0.378141 -0.554674 0.648297 0 -0.761388 0.0423371 0.698074 0.714773 0.0423391 0.698068 0.714778 -0.142357 0.706855 0.692886 -0.296458 0.625229 0.721943 -0.295438 0.700859 0.64924 -0.450089 0.706115 0.546646 -0.610195 0.571511 0.548669 -0.562809 0.703111 0.434604 -0.654519 0.704861 0.273453 -0.800718 0.551728 0.23334 -0.698951 0.704866 0.120962 -0.70628 0.698067 -0.11778 -0.876372 0.475032 -0.0794754 -0.673293 0.706111 -0.219277 -0.585231 0.69807 -0.412557 -0.348276 0.698063 -0.625629 -0.348272 0.698067 -0.625626 -0.492303 0.706852 -0.507935 -0.668095 0.604027 -0.434512 0.0591303 0 0.99825 0.0591303 0 0.99825 -0.201252 0 0.97954 -0.201252 0 0.97954 -0.414185 0 0.910193 -0.414185 0 0.910193 -0.635632 0 0.771992 -0.635632 0 0.771992 -0.791485 0 0.611188 -0.791485 0 0.611188 -0.922708 0 0.385501 -0.922708 0 0.385501 -0.985353 0 0.170527 -0.985353 0 0.170527 -0.995913 0 -0.0903162 -0.995913 0 -0.0903162 -0.950844 0 -0.30967 -0.950844 0 -0.30967 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.695972 0 -0.718069 -0.695972 0 -0.718069 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.348274 -0.698063 -0.62563 -0.348274 -0.698068 -0.625626 -0.492303 -0.706852 -0.507935 -0.637873 -0.625235 -0.449667 -0.59796 -0.700858 -0.388898 -0.673293 -0.706111 -0.219277 -0.809417 -0.571511 -0.134979 -0.708167 -0.703118 -0.0642215 -0.698951 -0.704866 0.120962 -0.800718 -0.551728 0.23334 -0.654519 -0.704861 0.273453 -0.532447 -0.69806 0.478761 -0.696479 -0.47504 0.537824 -0.450089 -0.706115 0.546646 -0.27199 -0.698071 0.662358 0.0423388 -0.698074 0.714773 0.0423374 -0.698069 0.714778 -0.142357 -0.706855 0.692886 -0.330093 -0.604019 0.725396 -0.348276 0.698066 -0.625626 -0.348275 0.698068 -0.625625 -0.585233 0.698066 -0.41256 -0.585238 0.698061 -0.412562 -0.706286 0.69806 -0.117779 -0.706273 0.698073 -0.117781 -0.687433 0.698073 0.200326 -0.687428 0.698079 0.200322 -0.532435 0.69808 0.478747 -0.532443 0.698063 0.478762 -0.271987 0.698065 0.662366 -0.271987 0.698072 0.662359 0.0423343 0.698069 0.714778 0.0423351 0.698067 0.71478 -0.486397 0 -0.873738 -0.486397 0 -0.873738 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.986379 0 -0.164486 -0.986379 0 -0.164486 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.743603 0 0.668622 -0.743603 0 0.668622 -0.379852 0 0.925047 -0.379852 0 0.925047 0.0591236 0 0.998251 0.0591236 0 0.998251 0.0423345 -0.698066 0.71478 0.042335 -0.698068 0.714778 -0.271985 -0.698072 0.66236 -0.271989 -0.698065 0.662365 -0.532447 -0.698062 0.478758 -0.532431 -0.698079 0.478751 -0.687427 -0.698079 0.200324 -0.687433 -0.698073 0.200324 -0.706273 -0.698074 -0.117777 -0.706285 -0.698061 -0.117783 -0.585238 -0.698061 -0.412564 -0.585234 -0.698066 -0.412559 -0.348275 -0.698068 -0.625624 -0.348276 -0.698066 -0.625626 -0.373099 0.694739 -0.614927 -0.373097 0.694742 -0.614925 -0.630573 0.694743 -0.345991 -0.630573 0.694743 -0.345991 -0.719089 0.694742 0.015649 -0.719098 0.694733 0.0156518 -0.614931 0.694732 0.373104 -0.614923 0.694745 0.373095 -0.345991 0.694745 0.630571 -0.345991 0.694743 0.630573 0.0156489 0.694742 0.719089 0.0156497 0.69474 0.719091 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.48104 0 0.876699 -0.48104 0 0.876699 0.021757 0 0.999763 0.021757 0 0.999763 0.015649 -0.694739 0.719091 0.0156496 -0.694742 0.719089 -0.345992 -0.694743 0.630573 -0.34599 -0.694745 0.630571 -0.61492 -0.694745 0.373097 -0.614933 -0.694733 0.373101 -0.719098 -0.694732 0.0156492 -0.719089 -0.694742 0.0156516 -0.630573 -0.694743 -0.345991 -0.630573 -0.694743 -0.345991 -0.373098 -0.694742 -0.614924 -0.373098 -0.694739 -0.614927 0.042335 0.698068 0.714779 0.0423353 0.698068 0.714779 -0.142356 0.706855 0.692886 -0.296455 0.625231 0.721943 -0.295435 0.700853 0.649248 -0.450105 0.706106 0.546645 -0.610189 0.571518 0.548669 -0.562799 0.703127 0.434592 -0.6545 0.704877 0.273458 -0.800723 0.551721 0.233338 -0.698946 0.704873 0.120951 -0.706273 0.698073 -0.117781 -0.876383 0.475013 -0.0794722 -0.673301 0.706104 -0.219278 -0.585237 0.698062 -0.412562 -0.348275 0.698067 -0.625625 -0.348276 0.698066 -0.625626 -0.492292 0.706851 -0.507947 -0.668103 0.604014 -0.434518 -0.486396 0 -0.873738 -0.51855 0.0259913 -0.854652 -0.695954 0 -0.718086 -0.8383 0 -0.545209 -0.875874 0.0433749 -0.480587 -0.950845 0 -0.309667 -0.995914 0 -0.0903114 -0.998407 0.0520747 0.0217276 -0.985355 0 0.170513 -0.922701 0 0.385516 -0.85378 0.0520758 0.518023 -0.791488 0 0.611185 -0.635646 0 0.771981 -0.480587 0.0433762 0.875874 0.0591248 0 0.998251 0.0217504 0.0259923 0.999425 -0.201251 0 0.97954 -0.414178 0 0.910196 0.0156495 -0.694741 0.71909 0.0156492 -0.69474 0.719091 -0.345993 -0.694741 0.630574 -0.345992 -0.694742 0.630573 -0.614922 -0.694744 0.373098 -0.614932 -0.694734 0.373101 -0.719098 -0.694733 0.0156492 -0.719089 -0.694742 0.0156516 -0.630574 -0.694742 -0.345992 -0.630573 -0.694744 -0.345991 -0.373097 -0.694743 -0.614924 -0.373098 -0.69474 -0.614926 -0.452163 0.702328 -0.549804 -0.451731 0.702922 -0.5494 -0.345832 0.810662 -0.47247 -0.420872 0.686882 -0.592503 -0.421202 0.68625 -0.593001 -0.612375 0.69524 -0.376349 -0.61184 0.695867 -0.376059 -0.43428 0.852911 -0.289731 -0.584964 0.694387 -0.4191 -0.585445 0.69375 -0.419481 -0.643483 0.696953 -0.316522 -0.668639 0.692014 -0.272099 -0.668071 0.692642 -0.271896 -0.482294 0.849797 -0.212689 -0.642976 0.697552 -0.316232 -0.704631 0.703968 -0.0890145 -0.72797 0.684436 -0.0400825 -0.727385 0.685059 -0.0400676 -0.618846 0.784487 -0.0401204 -0.704098 0.704524 -0.0888364 -0.792511 0 0.609858 -0.792527 -2.36734e-06 0.609837 -0.792516 9.01194e-07 0.609851 -0.792514 1.15295e-06 0.609854 -0.792515 7.70221e-07 0.609852 -0.792526 0 0.609839 -0.0457415 0.707101 0.705631 -0.0457468 0.707102 0.70563 -0.0457447 0.707111 0.705621 -0.0457467 0.707106 0.705626 -0.230714 0.694746 0.681248 -0.230714 0.694746 0.681249 -0.540428 0.694745 0.474622 -0.605267 0.52629 0.59722 -0.615239 0.706514 0.349741 -0.705331 0.694751 0.140818 -0.877133 0.406228 0.256157 -0.708273 0.705761 0.0158194 -0.695182 0.703329 -0.148494 -0.813638 0.511924 -0.275549 -0.631836 0.704717 -0.322734 -0.540368 0.704693 -0.459794 -0.566949 0.511688 -0.645558 -0.0777957 0.701697 -0.708216 -0.165486 0.534389 -0.828881 -0.256991 0.705745 -0.660212 -0.403701 0.703359 -0.585074 0.0457463 0.707111 -0.705621 0.0457472 0.707106 -0.705626 0.045747 0.707105 -0.705628 0.0457471 0.707099 -0.705633 -0.707132 0 -0.707081 -0.707147 1.45741e-05 -0.707066 -0.707144 0 -0.707069 -0.707134 2.42892e-06 -0.70708 -0.707142 -1.0252e-06 -0.707072 -0.707144 -1.44595e-06 -0.70707 -0.258869 0 -0.965912 -0.258873 -1.04427e-06 -0.965911 -0.258826 7.67509e-06 -0.965924 -0.258853 2.26643e-06 -0.965917 -0.258878 0 -0.96591 -0.024651 0.501819 -0.864621 -0.024584 0.501622 -0.864738 0.39243 0.707106 -0.588217 0.39243 0.707106 -0.588217 0.392466 0.707114 -0.588183 -0.519959 0.698073 0.492277 -0.51996 0.698071 0.492278 -0.68206 0.698071 0.217925 -0.682058 0.698074 0.217923 -0.709066 0.698074 -0.0995907 -0.709066 0.698074 -0.0995908 -0.595636 0.698074 -0.39738 -0.595637 0.698073 -0.39738 -0.364232 0.698074 -0.616464 0.254877 0.698073 -0.669127 0.254877 0.698072 -0.669128 -0.0514443 0.699091 -0.71318 -0.0625131 0.675284 -0.734904 -0.206563 0.707079 -0.676292 -0.364231 0.698075 -0.616463 -0.392484 0.707099 0.58819 -0.392428 0.707109 0.588215 -0.392431 0.707106 0.588217 -0.807795 0.501741 0.309393 -0.807891 0.501741 0.309141 -0.991268 0 0.131866 -0.991264 2.37739e-06 0.131892 -0.991281 -2.26316e-05 0.131763 -0.991266 -1.27188e-06 0.13188 -0.991265 0 0.131885 -0.97626 0 -0.216602 -0.97626 1.47959e-07 -0.2166 -0.976272 1.00277e-05 -0.21655 -0.976261 1.52622e-06 -0.216596 -0.97626 0 -0.216601 -0.864873 0.501822 0.0129861 -0.864989 0.501621 0.0130597 -0.570625 0.707097 0.417613 -0.570587 0.707106 0.41765 -0.570588 0.707105 0.41765 -0.657406 0.698073 0.283746 -0.657405 0.698074 0.283745 -0.715415 0.698072 -0.0295925 -0.715414 0.698074 -0.0295931 -0.631727 0.698073 -0.337068 -0.631725 0.698075 -0.337068 -0.512326 0.706726 -0.487915 -0.462552 0.621859 -0.631931 0.46919 0.698074 -0.540882 0.46919 0.698073 -0.540883 0.188045 0.698073 -0.690893 0.188044 0.698073 -0.690893 -0.0859921 0.702405 -0.706564 -0.145306 0.602367 -0.784882 -0.23971 0.706429 -0.665956 -0.393793 0.701459 -0.594039 0.570586 0.707107 -0.41765 0.570585 0.707108 -0.417649 0.570572 0.707103 -0.417675 0.273954 0.501742 -0.82049 0.273713 0.501743 -0.82057 0.0886309 0 -0.996065 0.0886249 -1.73041e-06 -0.996065 0.0884759 -2.86597e-05 -0.996078 0.0886334 1.71159e-06 -0.996064 0.0886145 0 -0.996066 -0.172992 0.501737 -0.847546 -0.173247 0.501738 -0.847493 0.285318 0.707104 -0.646991 0.285318 0.707108 -0.646987 0.285305 0.707105 -0.646995 -0.42127 0 -0.906935 -0.421269 3.61476e-07 -0.906936 -0.421312 -8.2073e-06 -0.906916 -0.42127 5.85103e-07 -0.906935 -0.421276 0 -0.906932 -0.42746 0.69807 0.574435 -0.42746 0.698071 0.574435 -0.634366 0.69807 0.332082 -0.634364 0.698072 0.33208 -0.690627 0.706826 0.153075 -0.774944 0.631498 0.02594 -0.713131 0.701016 -0.00447749 -0.685638 0.706476 -0.175478 -0.728498 0.605045 -0.321264 -0.633117 0.702266 -0.325553 -0.532814 0.705986 -0.466576 -0.526258 0.585731 -0.616418 0.135889 0.698071 -0.703016 0.135889 0.698074 -0.703013 -0.11205 0.70433 -0.700973 -0.208642 0.574979 -0.791118 -0.264843 0.705357 -0.657517 -0.417154 0.703372 -0.575544 -0.285407 0.70709 0.646967 -0.285318 0.707106 0.646989 -0.285319 0.707104 0.646991 -0.742477 0.501739 0.443831 -0.742612 0.501739 0.443605 -0.953763 0 0.300559 -0.953772 -2.51195e-06 0.300532 -0.953799 -2.02208e-05 0.300444 -0.953761 2.90517e-06 0.300567 -0.953764 0 0.300557 -0.0646954 0 0.997905 -0.0646954 0 0.997905 0.0646954 0 -0.997905 0.0646954 0 -0.997905 -0.109191 0 -0.994021 -0.109191 0 -0.994021 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.554984 0 0.831861 -0.55498 -9.22728e-07 0.831864 -0.55498 0 0.831864 0.55498 0 -0.831864 0.554982 2.7016e-06 -0.831863 0.55498 0 -0.831864 -0.0655361 0 -0.99785 -0.0719453 0.00611405 -0.99739 0.361948 -0.00628864 -0.932177 0.35596 0 -0.934501 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.403499 0 0.91498 -0.4035 2.51036e-07 0.91498 -0.4035 0 0.91498 0.403501 0 -0.914979 0.4035 -1.3508e-06 -0.91498 0.403501 0 -0.914979 -0.10862 0 -0.994083 -0.157731 0.0379517 -0.986753 0.238018 -0.0485595 -0.970046 0.189781 0 -0.981826 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.80693 0 0.590647 -0.806931 1.89974e-07 0.590646 -0.806931 0 0.590646 0.806932 0 -0.590645 0.806933 3.65509e-06 -0.590643 0.806931 0 -0.590646 -0.0797239 0 -0.996817 -0.120732 0.0367348 -0.992005 0.321544 -0.04403 -0.945871 0.262559 0.022037 -0.964664 0.67059 -0.0202118 -0.741553 0.65527 0 -0.755395 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0156477 0.694746 0.719085 0.0481258 0.580885 0.812562 -0.142358 0.706855 0.692886 -0.345992 0.694742 0.630574 -0.376228 0.418156 0.8268 -0.450099 0.706113 0.54664 -0.562803 0.70312 0.434597 -0.749514 0.481066 0.454758 -0.65451 0.704867 0.273457 -0.69895 0.704868 0.120957 -0.876478 0.481065 0.0190744 -0.708166 0.703119 -0.0642225 -0.673296 0.706111 -0.219271 -0.745584 0.526065 -0.409097 -0.348272 0.698073 -0.625621 -0.413408 0.604024 -0.681358 -0.492291 0.706846 -0.507955 -0.597967 0.70085 -0.388902 -0.486395 0 -0.873739 -0.486395 0 -0.873739 -0.695949 0 -0.718092 -0.695949 0 -0.718092 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.950847 0 -0.309661 -0.950847 0 -0.309661 -0.995913 0 -0.0903178 -0.995913 0 -0.0903178 -0.985354 0 0.170521 -0.985354 0 0.170521 -0.922704 0 0.385509 -0.922704 0 0.385509 -0.791487 0 0.611186 -0.791487 0 0.611186 -0.635644 0 0.771982 -0.635644 0 0.771982 -0.414177 0 0.910196 -0.414177 0 0.910196 -0.201253 0 0.979539 -0.201253 0 0.979539 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.373097 -0.694745 -0.614921 -0.395921 -0.580878 -0.711215 -0.492291 -0.706846 -0.507955 -0.630579 -0.694735 -0.345995 -0.761493 -0.418151 -0.495256 -0.673296 -0.706111 -0.219271 -0.708167 -0.703119 -0.0642225 -0.876478 -0.481065 0.0190744 -0.69895 -0.704868 0.120957 -0.65451 -0.704867 0.273457 -0.749514 -0.481066 0.454758 -0.562803 -0.70312 0.434596 -0.450099 -0.706113 0.54664 -0.409095 -0.52607 0.745581 0.042334 -0.698073 0.714774 0.0173382 -0.604029 0.796774 -0.142358 -0.706855 0.692886 -0.295433 -0.700857 0.649245 0.0156477 0.694746 0.719085 0.0481258 0.580885 0.812562 -0.142358 0.706854 0.692887 -0.345992 0.69474 0.630576 -0.376228 0.418153 0.826801 -0.450101 0.706115 0.546636 -0.5628 0.703123 0.434596 -0.749514 0.481066 0.454758 -0.654507 0.704872 0.273452 -0.698945 0.704873 0.120959 -0.876476 0.481068 0.019075 -0.708165 0.70312 -0.0642219 -0.673294 0.706112 -0.219273 -0.74558 0.526071 -0.409095 -0.34827 0.698075 -0.625619 -0.413402 0.604034 -0.681353 -0.492288 0.706853 -0.507948 -0.597963 0.700855 -0.3889 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.695951 0 -0.718089 -0.695951 0 -0.718089 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.950846 0 -0.309664 -0.950846 0 -0.309664 -0.995913 0 -0.0903171 -0.995913 0 -0.0903171 -0.985353 0 0.170525 -0.985353 0 0.170525 -0.922706 0 0.385505 -0.922706 0 0.385505 -0.791485 0 0.611188 -0.791485 0 0.611188 -0.635649 0 0.771979 -0.635649 0 0.771979 -0.414177 0 0.910197 -0.414177 0 0.910197 -0.201252 0 0.97954 -0.201252 0 0.97954 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.373094 -0.694748 -0.614919 -0.395915 -0.580891 -0.711208 -0.492288 -0.706853 -0.507948 -0.630576 -0.694739 -0.345993 -0.76149 -0.41816 -0.495253 -0.673294 -0.706112 -0.219273 -0.708165 -0.70312 -0.0642219 -0.876476 -0.481068 0.019075 -0.698945 -0.704873 0.120959 -0.654507 -0.704872 0.273452 -0.749514 -0.481066 0.454758 -0.5628 -0.703123 0.434596 -0.450101 -0.706115 0.546636 -0.409096 -0.526067 0.745583 0.0423341 -0.698073 0.714774 0.0173383 -0.604029 0.796774 -0.142358 -0.706854 0.692887 -0.295434 -0.700855 0.649246 0.0156477 0.694746 0.719085 0.015649 0.694742 0.719089 -0.345992 0.694743 0.630573 -0.376228 0.418153 0.826801 -0.4501 0.70611 0.546642 -0.562806 0.703118 0.434597 -0.749514 0.481066 0.454758 -0.654511 0.704866 0.273459 -0.698952 0.704866 0.120956 -0.876476 0.481068 0.019075 -0.373095 0.694745 -0.614923 -0.373103 0.694733 -0.61493 -0.597964 0.700853 -0.388901 -0.74558 0.526071 -0.409095 -0.673294 0.706112 -0.219273 -0.708165 0.70312 -0.0642219 -0.518723 0 -0.854943 -0.486173 -0.0302262 -0.87334 -0.838017 0.0259934 -0.545025 -0.817327 0 -0.576174 -0.950846 0 -0.309664 -0.985782 0.0347852 -0.164391 -0.995913 0 -0.0903171 -0.985354 0 0.170519 -0.95933 0.0391463 0.279559 -0.922703 0 0.385511 -0.791488 0 0.611185 -0.743151 0.0347849 0.668219 -0.635644 0 0.771983 -0.414177 0 0.910197 -0.379764 0.0217186 0.924829 0.0217497 -0.0259918 0.999426 0.0591236 0 0.998251 0.0423341 -0.698073 0.714774 0.0423329 -0.698069 0.714778 -0.271986 -0.698069 0.662362 -0.271987 -0.698068 0.662363 -0.532442 -0.698067 0.478756 -0.532436 -0.698074 0.478753 -0.687433 -0.698072 0.200326 -0.687436 -0.69807 0.200325 -0.706282 -0.698064 -0.117781 -0.70628 -0.698066 -0.11778 -0.585236 -0.698062 -0.412562 -0.585234 -0.698066 -0.412559 -0.348274 -0.698068 -0.625625 -0.348274 -0.698072 -0.625621 -0.373097 0.694739 -0.614928 -0.373103 0.694732 -0.614933 -0.630586 0.694729 -0.345994 -0.630573 0.694743 -0.345991 -0.719089 0.694742 0.015649 -0.719085 0.694746 0.0156477 -0.614923 0.694745 0.373095 -0.614923 0.694745 0.373095 -0.345989 0.694745 0.630572 -0.34599 0.694743 0.630574 0.015649 0.694742 0.719089 0.0156498 0.69474 0.719091 -0.518722 0 -0.854943 -0.518722 0 -0.854943 -0.876702 0 -0.481035 -0.876702 0 -0.481035 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.854943 0 0.518723 -0.854943 0 0.518723 -0.481038 0 0.8767 -0.481038 0 0.8767 0.0217571 0 0.999763 0.0217571 0 0.999763 0.0156491 -0.694739 0.719091 0.0156497 -0.694742 0.719089 -0.34599 -0.694743 0.630573 -0.345989 -0.694745 0.630572 -0.614923 -0.694745 0.373095 -0.614923 -0.694745 0.373095 -0.719085 -0.694746 0.0156489 -0.719089 -0.694742 0.0156477 -0.630574 -0.694743 -0.345988 -0.630584 -0.69473 -0.345998 -0.373101 -0.694732 -0.614934 -0.373099 -0.694739 -0.614927 0.0860226 0.702322 -0.706643 0.0367022 0.686245 -0.726444 0.0366907 0.686903 -0.725822 0.0378798 0.810663 -0.584286 0.0858715 0.70293 -0.706057 0.314331 0.695245 -0.646398 0.268446 0.69376 -0.668307 0.26825 0.694381 -0.66774 0.210651 0.852909 -0.477674 0.314039 0.695864 -0.645874 0.37272 0.696936 -0.612666 0.372435 0.697566 -0.612123 0.292537 0.849796 -0.438484 0.417421 0.692646 -0.588219 0.417789 0.692022 -0.588692 0.592482 0.684428 -0.42488 0.590857 0.681061 -0.432486 0.497119 0.789315 -0.360354 0.546147 0.704531 -0.453166 0.546516 0.703951 -0.453622 0.996064 0 0.0886424 0.996062 3.84906e-06 0.0886557 0.996077 -2.64126e-05 0.0884883 0.996064 1.57709e-06 0.0886335 0.996066 0 0.088616 0.820488 0.501823 0.273813 0.820579 0.501615 0.273921 0.417648 0.707109 0.570585 0.41765 0.707106 0.570587 0.417674 0.707101 0.570575 -0.260135 0.694744 -0.670568 -0.404303 0.403602 -0.820759 -0.137909 0.705745 -0.694914 0.0261996 0.70336 -0.710351 0.131399 0.511689 -0.849063 0.208771 0.704692 -0.678103 0.359549 0.704717 -0.611636 0.538242 0.511919 -0.669503 0.506583 0.703329 -0.4987 0.605893 0.705762 -0.367143 0.787632 0.535049 -0.305547 0.560562 0.694749 0.450659 0.560568 0.694743 0.450661 0.698526 0.699676 0.150046 0.806682 0.57765 0.12484 0.706811 0.70651 -0.0355188 0.684172 0.701661 -0.198948 -0.417616 0.707095 -0.570625 -0.417651 0.707104 -0.570589 -0.417652 0.707103 -0.570589 -0.0131232 0.501739 -0.86492 -0.0128724 0.501739 -0.864923 0.216585 0 -0.976264 0.216615 -2.76413e-06 -0.976257 0.21655 1.00277e-05 -0.976272 0.216596 1.52622e-06 -0.976261 0.216601 0 -0.97626 -0.300559 0 -0.953763 -0.300562 3.29543e-07 -0.953762 -0.300661 2.01405e-05 -0.953731 -0.300539 -2.94536e-06 -0.95377 -0.300548 0 -0.953767 -0.443685 0.50182 -0.742509 -0.443805 0.501621 -0.742572 -0.647003 0.70712 -0.285252 -0.646987 0.707108 -0.285317 -0.646988 0.707106 -0.285318 -0.574434 0.698073 -0.427458 -0.574432 0.698074 -0.427458 -0.332079 0.698074 -0.634362 0.703013 0.698074 0.135889 0.703014 0.698073 0.135889 0.692354 0.698073 -0.182595 0.692354 0.698073 -0.182595 0.544564 0.698073 -0.464913 0.544564 0.698073 -0.464913 0.288916 0.698072 -0.655151 0.288916 0.698078 -0.655145 -0.0239525 0.698077 -0.715622 -0.0239545 0.698072 -0.715626 -0.189096 0.707076 -0.681385 -0.351569 0.672668 -0.651089 0.646988 0.707107 0.285318 0.646991 0.707104 0.285318 0.64702 0.707095 0.285275 0.847544 0.501739 -0.172993 0.847492 0.50174 -0.173246 0.906933 0 -0.421274 0.90693 -1.99487e-06 -0.42128 0.906916 -8.2073e-06 -0.421312 0.906932 -7.66684e-07 -0.421277 0.906936 0 -0.421269 0.707075 0 -0.707139 0.707072 -1.28526e-06 -0.707142 0.707057 -4.96825e-06 -0.707157 0.707086 2.76405e-06 -0.707128 0.707064 0 -0.70715 0.736458 0.501822 -0.453657 0.736596 0.501619 -0.453657 0.705626 0.707106 0.0457466 0.705626 0.707106 0.0457466 0.705635 0.707099 0.0457084 -0.68125 0.694745 -0.230714 -0.681249 0.694745 -0.230714 -0.527798 0.70333 -0.47619 -0.566857 0.511922 -0.645453 -0.385821 0.704714 -0.595416 -0.256992 0.705745 -0.660212 -0.165486 0.534387 -0.828881 -0.0777965 0.701696 -0.708217 0.0921041 0.70634 -0.701856 0.264711 0.564787 -0.781629 0.705336 0.694745 -0.14082 0.705334 0.694747 -0.14082 0.557791 0.698593 -0.448149 0.598937 0.603814 -0.526007 0.418025 0.706765 -0.570735 0.272925 0.700232 -0.659687 -0.705633 0.707095 -0.0458089 -0.705626 0.707106 -0.0457466 -0.705626 0.707106 -0.0457467 -0.671839 0.501738 -0.544878 -0.671678 0.501738 -0.545076 -0.609838 0 -0.792526 -0.609857 2.12518e-06 -0.792512 -0.609927 1.90596e-05 -0.792458 -0.609852 2.08853e-06 -0.792515 -0.609846 0 -0.79252 -0.309392 0.501736 -0.807798 -0.309149 0.501737 -0.807891 -0.588194 0.707097 -0.392482 -0.588217 0.707106 -0.392431 -0.588217 0.707106 -0.392431 -0.1319 0 -0.991263 -0.131894 -5.78375e-07 -0.991264 -0.13204 2.77167e-05 -0.991244 -0.13188 -1.27188e-06 -0.991266 -0.131885 0 -0.991265 -0.492277 0.698073 -0.519959 -0.492275 0.698076 -0.519958 -0.217923 0.698076 -0.682056 -0.360636 0.419757 -0.832914 -0.12984 0.705354 -0.696862 0.0995911 0.698071 -0.709069 0.0522494 0.492243 -0.868889 0.198756 0.705986 -0.679765 0.397382 0.698071 -0.595638 0.419402 0.555637 -0.717892 0.484038 0.706476 -0.516332 0.616466 0.698072 -0.364233 0.669131 0.698071 0.254876 0.669128 0.698073 0.254876 0.71345 0.698073 -0.060688 0.713451 0.698072 -0.0606885 0.664744 0.706824 -0.241898 0.665343 0.6105 -0.429661 0.588218 0.707104 0.392432 0.588216 0.707106 0.392432 0.588309 0.707083 0.392334 0.864671 0.50174 -0.0245176 0.864664 0.50174 -0.0247747 0.965912 0 -0.258869 0.965911 -1.04427e-06 -0.258873 0.965905 -5.47341e-06 -0.258897 0.965913 1.61407e-07 -0.258868 0.965912 0 -0.25887 -0.91498 0 -0.403499 -0.91498 2.78175e-07 -0.4035 -0.91498 0 -0.4035 0.91498 0 0.4035 0.914979 1.19188e-06 0.403501 0.91498 0 0.4035 -0.26741 0 -0.963583 -0.0565537 0.0120125 -0.998327 -0.0334507 -0.00961051 -0.999394 0.386956 0.00972341 -0.922047 0.403488 -0.00729426 -0.914956 0.75211 0.00737739 -0.658996 0.760527 -0.00491908 -0.649288 0.964931 0.00497581 -0.262455 0.966935 -0.00248782 -0.25501 0.982308 0.00251654 0.187257 0.981826 0 0.189782 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.831861 0 -0.554984 -0.831863 -7.19185e-07 -0.554981 -0.831863 0 -0.554981 0.831863 0 0.554981 0.831864 -2.70159e-06 0.55498 0.831863 0 0.554982 -0.183169 0 -0.983081 -0.0392011 0.0629003 -0.99725 0.0600252 0 -0.998197 0.280639 0 -0.959814 0.433579 0.0572147 -0.899297 0.504438 0 -0.863448 0.683923 0 -0.729554 0.805319 0.0480747 -0.590889 0.840062 0 -0.54249 0.939715 0 -0.341959 0.988959 0.035483 -0.143876 0.996245 -0.017753 -0.0847432 0.941212 0.0194494 0.337257 0.934502 0 0.355958 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.997905 0 -0.0646955 -0.997905 -2.79871e-08 -0.0646954 -0.997905 0 -0.0646954 0.997905 0 0.0646954 0.997905 -3.97294e-08 0.0646954 0.997905 0 0.0646954 -0.109192 0 -0.994021 -0.0436022 0.0500202 -0.997796 0.130114 0 -0.991499 0.382293 0 -0.924041 0.422112 0.0375261 -0.905767 0.590891 0 -0.806751 0.793096 0 -0.609096 0.779357 0.0228985 -0.626162 0.984395 -0.0249445 -0.174198 0.980647 0 -0.195786 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.590651 0 -0.806927 -0.590647 1.2009e-06 -0.80693 -0.590646 0 -0.806931 0.590646 0 0.806931 0.590646 -6.35672e-07 0.806931 0.590646 0 0.806931 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.194658 0 -0.980871 -0.0506831 0.0556149 -0.997165 0.0368576 0 -0.999321 0.294246 0 -0.95573 0.402267 0.059228 -0.913605 0.506772 0 -0.86208 0.71263 0 -0.70154 0.769752 0.0554681 -0.635929 0.855239 0 -0.518234 0.960227 0 -0.279221 0.973851 0.0443324 -0.222822 0.99874 0 -0.0501889 0.971192 0 0.238299 0.977275 0.0294434 0.209923 0.760441 -0.0330305 0.648566 0.779368 0 0.626566 0.0423378 0.69806 0.714786 0.0423343 0.698069 0.714778 -0.142358 0.706855 0.692886 -0.296453 0.625232 0.721942 -0.295434 0.700856 0.649246 -0.450101 0.70611 0.546642 -0.610194 0.571515 0.548666 -0.562808 0.703114 0.4346 -0.654513 0.704864 0.273458 -0.800724 0.551719 0.233341 -0.69895 0.704867 0.120957 -0.706278 0.698068 -0.11778 -0.876369 0.475038 -0.0794757 -0.673294 0.706111 -0.219275 -0.585231 0.69807 -0.412557 -0.348278 0.698061 -0.625631 -0.348271 0.698069 -0.625625 -0.4923 0.706855 -0.507935 -0.668093 0.604029 -0.434511 -0.486395 0 -0.873739 -0.518551 0.0259935 -0.854651 -0.695969 0 -0.718072 -0.8383 0 -0.545209 -0.875874 0.0433748 -0.480587 -0.950845 0 -0.309667 -0.995913 0 -0.0903169 -0.998407 0.0520776 0.0217282 -0.985354 0 0.170521 -0.922704 0 0.385509 -0.853781 0.0520773 0.518021 -0.791487 0 0.611186 -0.635644 0 0.771982 -0.480587 0.0433764 0.875874 0.0591236 0 0.998251 0.0217497 0.0259918 0.999426 -0.201253 0 0.979539 -0.414177 0 0.910196 0.0156492 -0.694733 0.719098 0.0156516 -0.694742 0.719089 -0.345992 -0.694742 0.630574 -0.345991 -0.694744 0.630573 -0.614924 -0.694743 0.373097 -0.614927 -0.69474 0.373098 -0.71909 -0.69474 0.0156495 -0.71909 -0.694741 0.0156495 -0.630574 -0.694742 -0.345992 -0.630573 -0.694742 -0.345992 -0.373098 -0.694744 -0.614922 -0.3731 -0.694734 -0.614932 -0.348278 0.69806 -0.625632 -0.348271 0.698069 -0.625625 -0.585233 0.698068 -0.412556 -0.585229 0.698073 -0.412555 -0.706275 0.698072 -0.11778 -0.70628 0.698067 -0.117779 -0.687439 0.698066 0.200327 -0.68744 0.698065 0.200328 -0.532446 0.698063 0.478759 -0.532443 0.698067 0.478755 -0.271987 0.698068 0.662363 -0.271987 0.698069 0.662362 0.0423343 0.698069 0.714778 0.0423379 0.69806 0.714787 -0.486395 0 -0.873739 -0.486395 0 -0.873739 -0.817329 0 -0.576171 -0.817329 0 -0.576171 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743601 0 0.668624 -0.743601 0 0.668624 -0.379853 0 0.925047 -0.379853 0 0.925047 0.0591236 0 0.998251 0.0591236 0 0.998251 0.0423348 -0.69806 0.714787 0.0423374 -0.698069 0.714778 -0.271986 -0.698069 0.662362 -0.271987 -0.698068 0.662363 -0.532442 -0.698067 0.478756 -0.532447 -0.698063 0.478758 -0.68744 -0.698065 0.200328 -0.687439 -0.698066 0.200328 -0.70628 -0.698067 -0.11778 -0.706275 -0.698071 -0.117778 -0.585229 -0.698073 -0.412554 -0.585232 -0.698069 -0.412558 -0.348274 -0.698069 -0.625623 -0.348275 -0.69806 -0.625633 0.0156518 0.694733 0.719098 0.015649 0.694742 0.719089 -0.345992 0.69474 0.630576 -0.376228 0.418161 0.826797 -0.450098 0.706115 0.546639 -0.5628 0.703123 0.434596 -0.749518 0.48106 0.454758 -0.654513 0.704866 0.273455 -0.698951 0.704866 0.12096 -0.876483 0.481055 0.019075 -0.373101 0.694736 -0.614929 -0.373097 0.694741 -0.614925 -0.597963 0.700855 -0.3889 -0.74558 0.526072 -0.409095 -0.673299 0.706106 -0.219279 -0.708172 0.703113 -0.0642219 -0.518726 0 -0.854941 -0.486172 -0.0302305 -0.87334 -0.838017 0.0259909 -0.545025 -0.817329 0 -0.576171 -0.950844 0 -0.30967 -0.985782 0.034786 -0.164391 -0.995913 0 -0.0903162 -0.985353 0 0.170525 -0.95933 0.0391441 0.279559 -0.922706 0 0.385505 -0.791485 0 0.611188 -0.743149 0.0347843 0.668221 -0.635644 0 0.771983 -0.414178 0 0.910196 -0.379765 0.0217187 0.924828 0.0217497 -0.0259918 0.999426 0.0591236 0 0.998251 0.0423348 -0.69806 0.714787 0.0423374 -0.698069 0.714778 -0.271987 -0.698069 0.662361 -0.271986 -0.69807 0.66236 -0.532437 -0.698073 0.478754 -0.532449 -0.69806 0.478759 -0.687443 -0.698062 0.200328 -0.687439 -0.698066 0.200329 -0.70628 -0.698067 -0.11778 -0.706278 -0.698068 -0.11778 -0.585231 -0.69807 -0.412555 -0.585234 -0.698066 -0.412559 -0.348274 -0.698068 -0.625626 -0.348274 -0.698063 -0.62563 -0.348274 0.698066 -0.625627 -0.348273 0.698067 -0.625626 -0.585233 0.698066 -0.41256 -0.585238 0.698061 -0.412562 -0.706286 0.69806 -0.117779 -0.706274 0.698072 -0.117781 -0.687431 0.698075 0.200325 -0.68744 0.698064 0.200331 -0.532442 0.698064 0.47876 -0.532438 0.698073 0.478753 -0.271989 0.698071 0.662359 -0.271989 0.698066 0.662363 0.0423343 0.698069 0.714778 0.0423354 0.698067 0.71478 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.986379 0 -0.164487 -0.986379 0 -0.164487 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743598 0 0.668627 -0.743598 0 0.668627 -0.379857 0 0.925045 -0.379857 0 0.925045 0.0591236 0 0.998251 0.0591236 0 0.998251 0.0423345 -0.698066 0.71478 0.0423352 -0.698069 0.714778 -0.27199 -0.698066 0.662363 -0.271987 -0.698071 0.66236 -0.532436 -0.698073 0.478755 -0.532444 -0.698065 0.478758 -0.687441 -0.698064 0.200328 -0.687431 -0.698074 0.200328 -0.706274 -0.698073 -0.117777 -0.706285 -0.698061 -0.117783 -0.585238 -0.698061 -0.412564 -0.585234 -0.698066 -0.412559 -0.348274 -0.698068 -0.625626 -0.348274 -0.698066 -0.625627 -0.0535082 0.684006 0.727511 -0.0473715 0.681062 0.730692 -0.0430137 0.780793 0.623307 -0.00208558 0.704899 0.709305 -0.0019623 0.704344 0.709856 -0.32265 0.701691 0.635238 -0.282523 0.686965 0.669522 -0.282309 0.687596 0.668964 -0.231779 0.818559 0.525585 -0.32233 0.702275 0.634755 -0.422597 0.696975 0.579342 -0.383197 0.691988 0.611811 -0.382901 0.692612 0.61129 -0.29261 0.849714 0.438595 -0.422212 0.697593 0.578879 -0.549662 0.702403 0.452219 -0.549264 0.70299 0.451791 -0.473472 0.809764 0.346565 -0.592481 0.686808 0.421023 -0.59298 0.686175 0.421353 -0.996063 0 -0.088651 -0.996064 1.72635e-05 -0.0886347 -0.996064 0 -0.0886394 -0.996064 -1.09498e-06 -0.0886327 -0.996065 -3.46003e-06 -0.0886249 -0.996064 -1.39046e-06 -0.0886356 -0.417651 0.707104 -0.570589 -0.417649 0.707107 -0.570586 -0.417648 0.707109 -0.570585 -0.417653 0.707101 -0.570592 0.314839 0.701697 0.639139 0.314838 0.701697 0.639138 0.417653 0.707101 0.570591 0.417653 0.707101 0.570591 0.417648 0.707113 0.57058 0.41765 0.707106 0.570587 -0.216602 0 0.97626 -0.2166 1.47959e-07 0.97626 -0.216596 1.02882e-06 0.976261 -0.216596 1.00572e-06 0.976261 -0.216596 1.02128e-06 0.976261 -0.216618 0 0.976256 0.300559 0 0.953763 0.300528 -2.95914e-06 0.953773 0.300404 -2.78524e-05 0.953812 0.300571 3.74866e-06 0.953759 0.300559 0 0.953763 0.443686 0.501824 0.742506 0.443812 0.501615 0.742572 0.646967 0.70709 0.285407 0.646989 0.707106 0.285318 0.646991 0.707104 0.285319 0.344001 0.69859 0.627404 0.344004 0.698586 0.627406 0.576764 0.698587 0.423461 0.576764 0.698587 0.423461 -0.64699 0.707105 -0.285318 -0.646988 0.707107 -0.285318 -0.64702 0.707097 -0.285271 -0.847545 0.501738 0.172991 -0.847493 0.501739 0.173245 -0.906935 0 0.42127 -0.906936 3.61476e-07 0.421269 -0.906916 -8.2073e-06 0.421312 -0.906932 -7.66684e-07 0.421277 -0.906936 0 0.421269 -0.707075 0 0.707139 -0.707072 -1.28526e-06 0.707142 -0.707058 -4.83172e-06 0.707156 -0.70707 -1.47285e-06 0.707144 -0.707082 0 0.707132 -0.736458 0.501822 0.453657 -0.736596 0.50162 0.453657 -0.705626 0.707106 -0.0457466 -0.705626 0.707106 -0.0457466 -0.705635 0.707099 -0.0457083 0.334543 0.699679 0.631293 0.334544 0.699677 0.631294 0.557341 0.699677 0.447015 0.557343 0.699676 0.447015 0.688862 0.699677 0.189529 0.688861 0.699678 0.189529 0.705629 0.707102 0.0457739 0.705626 0.707106 0.0457466 0.705626 0.707106 0.0457467 0.67184 0.501737 0.544877 0.671679 0.501738 0.545075 0.609858 0 0.792511 0.609837 -2.36734e-06 0.792527 0.60991 1.51836e-05 0.792471 0.609854 2.51695e-06 0.792514 0.609847 0 0.792519 0.309393 0.501741 0.807795 0.309154 0.501741 0.807886 0.588194 0.707097 0.392482 0.588217 0.707106 0.392431 0.588217 0.707106 0.392431 0.131863 0 0.991268 0.131894 2.77086e-06 0.991264 0.131744 -2.61743e-05 0.991284 0.131878 -1.86093e-06 0.991266 0.131885 0 0.991265 0.514948 0.701661 0.492444 0.282056 0.704327 0.651435 0.337334 0.646993 0.683817 0.389724 0.70667 0.590536 0.514947 0.701661 0.492444 -0.588217 0.707106 -0.39243 -0.588217 0.707106 -0.39243 -0.588183 0.707114 -0.392466 -0.864673 0.501737 0.0245138 -0.864665 0.501738 0.0247713 -0.965914 0 0.258864 -0.965915 1.66013e-06 0.258858 -0.965924 7.67509e-06 0.258826 -0.965913 -6.12001e-07 0.258868 -0.965915 0 0.258861 0.590646 0 0.806931 0.590646 0 0.806931 -0.590645 0 -0.806931 -0.590645 0 -0.806931 0.396278 0 0.918131 0.441361 0.0491192 0.895984 -0.0412542 -0.0598314 0.997356 0.0506984 0.0498921 0.997467 -0.470196 -0.0484124 0.881233 -0.402671 0.0387499 0.914524 -0.806362 -0.037561 0.590228 -0.770632 0.0281818 0.636657 -0.982925 -0.0272865 0.181971 -0.974647 0.0181958 0.223006 -0.964749 -0.0175975 -0.262583 -0.971154 0.00880113 -0.23829 -0.755368 -0.00849953 -0.655245 -0.760857 0 -0.64892 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.914978 0 0.403505 0.914979 -8.95589e-07 0.403501 0.91498 0 0.4035 -0.914979 0 -0.403501 -0.914979 6.35671e-07 -0.403501 -0.914979 0 -0.403501 0.802252 0 0.596986 0.806055 0.00629092 0.591807 0.46377 -0.00646677 0.885932 0.480729 0.0129337 0.876774 0.0334523 -0.0132865 0.999352 0.0565576 0.0106302 0.998343 -0.403479 -0.0105171 0.914928 -0.386964 0.00788864 0.922061 -0.760513 -0.00780277 0.649276 -0.75212 0.00520231 0.659005 -0.966925 -0.00514575 0.255008 -0.96494 0.00257278 0.262458 -0.981823 -0.00254487 -0.189781 -0.982311 0 -0.187258 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.831865 0 0.554978 0.831864 7.32755e-07 0.55498 0.831863 0 0.554981 -0.831864 0 -0.55498 -0.831863 2.7016e-06 -0.554982 -0.831864 0 -0.55498 0.722722 0 0.691139 0.687018 0.0379519 0.725649 0.550813 0 0.834629 0.397332 0 0.917675 0.303902 0.0543515 0.951152 0.183169 0 0.983081 -0.0600252 0 0.998197 -0.138912 0.0503853 0.989022 -0.280639 0 0.959814 -0.504437 0 0.863448 -0.554468 0.0429606 0.831095 -0.683923 0 0.729554 -0.860952 0 0.508685 -0.839428 0.0388704 0.54208 -0.995365 -0.0455914 0.0846702 -0.989325 0.022818 0.14393 -0.934293 -0.0211381 -0.35588 -0.941389 0 -0.337322 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.997905 0 0.0646955 0.997905 -2.79871e-08 0.0646954 0.997905 0 0.0646954 -0.997905 0 -0.0646954 -0.997905 -3.97294e-08 -0.0646954 -0.997905 0 -0.0646954 0.958489 0 0.285128 0.963976 0.0202133 0.265221 0.739678 -0.0220346 0.6726 0.779332 0.0440312 0.625062 0.468045 -0.0293698 0.883216 0.374323 0.0440139 0.926253 0.219804 0 0.975544 -0.0646945 0 0.997905 -0.0182575 0.0454276 0.998801 -0.490533 -0.0545986 0.869711 -0.422131 0.0364356 0.905802 -0.820045 -0.0344022 0.571264 -0.792979 0.0172109 0.609006 -0.987152 -0.0161879 0.158961 -0.984701 0 0.174252 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.348273 0.698072 -0.625621 -0.348276 0.698068 -0.625624 -0.585235 0.698066 -0.412558 -0.585231 0.69807 -0.412557 -0.706278 0.698068 -0.11778 -0.70628 0.698067 -0.11778 -0.687439 0.698066 0.200327 -0.687437 0.698068 0.200326 -0.532442 0.698065 0.47876 -0.532441 0.698068 0.478757 -0.271991 0.698068 0.662361 -0.271992 0.698056 0.662373 0.0423399 0.698055 0.714792 0.0423327 0.698073 0.714774 -0.486395 0 -0.873739 -0.486395 0 -0.873739 -0.817329 0 -0.576171 -0.817329 0 -0.576171 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743598 0 0.668627 -0.743598 0 0.668627 -0.379859 0 0.925044 -0.379859 0 0.925044 0.0591303 0 0.99825 0.0591303 0 0.99825 0.0423388 -0.698074 0.714773 0.0423337 -0.698055 0.714791 -0.271995 -0.698056 0.662372 -0.271987 -0.698068 0.662363 -0.53244 -0.698068 0.478758 -0.532443 -0.698065 0.478759 -0.687437 -0.698069 0.200327 -0.687439 -0.698066 0.200327 -0.70628 -0.698067 -0.11778 -0.706278 -0.698068 -0.11778 -0.585231 -0.69807 -0.412555 -0.585234 -0.698066 -0.412559 -0.348274 -0.698068 -0.625625 -0.348274 -0.698072 -0.625621 0.0423354 0.698067 0.71478 0.0423343 0.698069 0.714778 -0.14236 0.706853 0.692887 -0.296454 0.625231 0.721943 -0.295435 0.700859 0.649242 -0.450097 0.706114 0.54664 -0.610187 0.571525 0.548663 -0.562805 0.703115 0.434603 -0.654515 0.704864 0.273454 -0.800722 0.551723 0.233338 -0.698957 0.70486 0.120962 -0.706287 0.698059 -0.117779 -0.876361 0.475053 -0.0794792 -0.67329 0.706116 -0.219274 -0.585229 0.698072 -0.412556 -0.348274 0.698066 -0.625627 -0.348273 0.698067 -0.625626 -0.492303 0.706852 -0.507935 -0.668093 0.60403 -0.434511 -0.486394 0 -0.87374 -0.51855 0.0259932 -0.854652 -0.695971 0 -0.71807 -0.8383 0 -0.545209 -0.875874 0.0433749 -0.480586 -0.950845 0 -0.309667 -0.995913 0 -0.0903217 -0.998407 0.0520793 0.0217276 -0.985353 0 0.170526 -0.922707 0 0.385503 -0.85378 0.0520801 0.518022 -0.791483 0 0.611191 -0.635643 0 0.771983 -0.480587 0.0433751 0.875873 0.0591236 0 0.998251 0.0217498 0.0259918 0.999426 -0.201256 0 0.979539 -0.41418 0 0.910195 0.0156491 -0.694739 0.719091 0.0156497 -0.694742 0.719089 -0.345992 -0.694743 0.630573 -0.345995 -0.694739 0.630575 -0.614924 -0.694742 0.373098 -0.614918 -0.694748 0.373097 -0.719085 -0.694746 0.0156489 -0.719089 -0.694742 0.0156477 -0.630573 -0.694743 -0.345991 -0.630572 -0.694745 -0.34599 -0.373096 -0.694745 -0.614922 -0.373098 -0.694739 -0.614928 0.0156498 0.69474 0.719091 0.0481258 0.580885 0.812562 -0.14236 0.706855 0.692885 -0.345992 0.694743 0.630573 -0.376228 0.418162 0.826797 -0.450099 0.706112 0.546642 -0.562801 0.703121 0.434599 -0.749515 0.481062 0.454761 -0.654507 0.704872 0.273452 -0.698944 0.704873 0.12096 -0.876479 0.481062 0.0190726 -0.708165 0.70312 -0.0642248 -0.673294 0.706112 -0.219275 -0.745577 0.526077 -0.409094 -0.348274 0.698066 -0.625627 -0.413408 0.604019 -0.681363 -0.492302 0.706853 -0.507934 -0.597961 0.700857 -0.388899 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.695971 0 -0.71807 -0.695971 0 -0.71807 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.950845 0 -0.309667 -0.950845 0 -0.309667 -0.995913 0 -0.0903212 -0.995913 0 -0.0903212 -0.985353 0 0.170526 -0.985353 0 0.170526 -0.922706 0 0.385505 -0.922706 0 0.385505 -0.791484 0 0.61119 -0.791484 0 0.61119 -0.635643 0 0.771983 -0.635643 0 0.771983 -0.414178 0 0.910196 -0.414178 0 0.910196 -0.201256 0 0.979539 -0.201256 0 0.979539 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.373099 -0.694739 -0.614927 -0.395922 -0.580874 -0.711219 -0.492302 -0.706853 -0.507934 -0.630574 -0.694742 -0.345992 -0.761487 -0.418167 -0.495252 -0.673294 -0.706112 -0.219275 -0.708165 -0.70312 -0.0642248 -0.876479 -0.481062 0.0190726 -0.698944 -0.704873 0.12096 -0.654507 -0.704872 0.273452 -0.749515 -0.481062 0.454761 -0.5628 -0.703121 0.434599 -0.450099 -0.706112 0.546642 -0.409095 -0.526074 0.745579 0.0423345 -0.698066 0.71478 0.0173404 -0.604028 0.796775 -0.14236 -0.706855 0.692885 -0.295434 -0.700858 0.649243 0.0423355 0.698067 0.714779 0.0423353 0.698068 0.714779 -0.142363 0.706852 0.692887 -0.296453 0.625232 0.721942 -0.295433 0.700858 0.649243 -0.4501 0.706114 0.546638 -0.610186 0.571528 0.548661 -0.562804 0.703116 0.434603 -0.654515 0.704864 0.273455 -0.800723 0.551721 0.233338 -0.698957 0.704859 0.120962 -0.706286 0.69806 -0.117779 -0.876361 0.475053 -0.079479 -0.673289 0.706116 -0.219274 -0.585228 0.698073 -0.412555 -0.348273 0.698067 -0.625626 -0.348274 0.698066 -0.625627 -0.492306 0.706851 -0.507934 -0.668093 0.60403 -0.434511 -0.486393 0 -0.87374 -0.51855 0.0259937 -0.854652 -0.695974 0 -0.718067 -0.8383 0 -0.545209 -0.875874 0.0433747 -0.480587 -0.950845 0 -0.309668 -0.995913 0 -0.0903214 -0.998407 0.0520793 0.0217276 -0.985353 0 0.170526 -0.922706 0 0.385504 -0.85378 0.0520798 0.518023 -0.791483 0 0.611191 -0.635646 0 0.771981 -0.480587 0.0433762 0.875874 0.0591248 0 0.998251 0.0217503 0.0259923 0.999425 -0.20126 0 0.979538 -0.414178 0 0.910196 0.0156494 -0.69474 0.71909 0.0156495 -0.694741 0.71909 -0.345992 -0.694742 0.630574 -0.345992 -0.694742 0.630573 -0.614922 -0.694744 0.373098 -0.614921 -0.694745 0.373098 -0.719085 -0.694746 0.0156489 -0.719089 -0.694742 0.0156478 -0.630574 -0.694742 -0.345992 -0.630573 -0.694743 -0.345991 -0.373098 -0.694742 -0.614924 -0.373098 -0.69474 -0.614926 0.382995 0.704333 0.597687 0.435956 0.684002 0.584879 0.435589 0.684632 0.584416 0.371918 0.776854 0.508109 0.382795 0.704911 0.597133 0.613397 0.701686 0.362466 0.612862 0.702275 0.362229 0.477839 0.818561 0.318792 0.597479 0.687603 0.412579 0.59796 0.686971 0.412935 0.667663 0.696977 0.261626 0.66709 0.697595 0.261443 0.482417 0.849714 0.212743 0.651345 0.692613 0.309898 0.651885 0.691977 0.310184 0.706561 0.702389 0.0861457 0.726508 0.68617 0.0368416 0.725886 0.686828 0.0368298 0.58553 0.809761 0.0379605 0.705976 0.702996 0.0859934 0.792526 0 -0.609838 0.792512 2.12518e-06 -0.609857 0.792458 1.90596e-05 -0.609927 0.792515 2.08853e-06 -0.609852 0.79252 0 -0.609846 0.544952 0.50182 -0.671717 0.54497 0.501621 -0.671851 0.0458089 0.707095 -0.705633 0.0457466 0.707106 -0.705626 0.0457467 0.707106 -0.705626 0.210099 0.697374 -0.685221 0.210099 0.697374 -0.685221 0.375278 0.706955 -0.599484 0.528208 0.644911 -0.552346 0.508567 0.699679 -0.501806 0.615242 0.706511 -0.349743 0.753204 0.600588 -0.268288 0.683941 0.701663 -0.199734 0.708269 0.705765 -0.0158249 0.814818 0.570844 0.101033 0.69518 0.703331 0.148493 0.631838 0.704715 0.322735 0.688788 0.560251 0.460099 0.54037 0.704689 0.459797 0.353834 0.697375 0.623273 0.506979 0.450678 0.734753 0.256988 0.705746 0.660211 -0.0457466 0.707106 0.705626 -0.0457466 0.707106 0.705626 -0.0457084 0.707099 0.705635 0.453565 0.501738 0.736571 0.453786 0.501739 0.736435 0.707139 0 0.707075 0.707142 -1.25848e-06 0.707072 0.707157 -5.11236e-06 0.707057 0.707128 2.75733e-06 0.707085 0.70715 0 0.707064 0.258864 0 0.965914 0.258873 -2.67761e-06 0.965911 0.259027 -3.14435e-05 0.96587 0.258862 1.49643e-06 0.965914 0.258878 0 0.96591 0.0246483 0.50182 0.864621 0.02458 0.50162 0.864739 -0.392429 0.707109 0.588214 -0.39243 0.707106 0.588217 -0.392391 0.707096 0.588255 0.521372 0.697862 -0.49108 0.521372 0.697863 -0.491079 0.622862 0.706893 -0.33518 0.73546 0.637786 -0.228753 0.688408 0.700511 -0.188093 0.707956 0.706248 -0.00348256 0.796631 0.591955 0.122347 0.694018 0.7027 0.156689 0.627648 0.705171 0.329838 0.675093 0.570157 0.468157 0.537878 0.704441 0.463088 0.34998 0.697861 0.624903 0.500125 0.459644 0.733896 0.25699 0.705747 0.660211 0.392482 0.707097 -0.588194 0.39243 0.707107 -0.588217 0.39243 0.707106 -0.588217 0.807798 0.501736 -0.309392 0.807891 0.501737 -0.309149 0.991263 0 -0.1319 0.991264 -5.78375e-07 -0.131894 0.991244 2.77167e-05 -0.13204 0.991266 -1.27188e-06 -0.13188 0.991265 0 -0.131885 0.97626 0 0.216602 0.976262 7.90209e-07 0.216593 0.976242 -1.68652e-05 0.216683 0.97626 -2.04841e-06 0.216603 0.976261 0 0.216596 0.864875 0.50182 -0.01299 0.86499 0.501618 -0.0130636 0.570571 0.70711 -0.417666 0.570588 0.707106 -0.417649 0.570587 0.707106 -0.417649 0.662901 0.696761 -0.274018 0.6629 0.696763 -0.274017 0.714539 0.696763 0.0629005 0.714539 0.696762 0.0629004 0.604833 0.696764 0.385614 0.604836 0.696761 0.385615 0.358557 0.696761 0.621258 0.467241 0.533754 0.704836 0.239711 0.706427 0.665958 -0.570588 0.707105 0.417651 -0.570587 0.707106 0.41765 -0.570575 0.707101 0.417674 -0.273954 0.501737 0.820493 -0.273709 0.501737 0.820575 -0.0886314 0 0.996064 -0.0886249 -1.88102e-06 0.996065 -0.0887559 2.1795e-05 0.996053 -0.0886356 -1.39046e-06 0.996064 -0.088651 0 0.996063 0.172994 0.501738 0.847545 0.173248 0.501738 0.847493 -0.28526 0.707107 0.647013 -0.285241 0.707295 0.646816 -0.290619 0.708388 0.643216 0.421274 0 0.906933 0.42128 -1.99487e-06 0.90693 0.421312 -8.2073e-06 0.906916 0.42127 5.85103e-07 0.906935 0.421276 0 0.906932 0.439801 0.696371 -0.567135 0.439801 0.696372 -0.567134 0.563229 0.70705 -0.427614 0.683426 0.662156 -0.307374 0.65824 0.697881 -0.282281 0.700072 0.706889 -0.101032 0.775322 0.629491 0.0511598 0.711217 0.699271 0.0720434 0.661547 0.706618 0.251089 0.680158 0.600003 0.421166 0.314837 0.701699 0.639137 0.411987 0.575236 0.706661 0.457163 0.706233 0.54059 0.586131 0.700537 0.407061 0.285335 0.707105 -0.646983 0.285316 0.707108 -0.646987 0.285319 0.707104 -0.646991 0.742481 0.501737 -0.443825 0.742614 0.501738 -0.443603 0.953775 0 -0.300522 0.953763 3.61825e-06 -0.30056 0.953812 -2.78524e-05 -0.300404 0.953768 -1.5932e-06 -0.300543 0.953767 0 -0.300548 0.554984 0 -0.831861 0.55498 -9.22728e-07 -0.831864 0.55498 0 -0.831864 -0.554979 0 0.831864 -0.554979 -1.43025e-06 0.831865 -0.55498 0 0.831864 0.727938 0 -0.685643 0.750927 0.0344587 -0.659486 0.880593 0 -0.473873 0.964641 0 -0.263568 0.978974 0.0583827 -0.195452 0.999988 0 -0.00491912 0.975448 0 0.220228 0.944719 0.0717109 0.319942 0.88521 0 0.465191 0.757828 0 0.652454 0.658048 0.0744442 0.749287 0.563138 0 0.826363 0.362742 0 0.93189 0.195351 0.0665902 0.97847 0.10919 0 0.994021 -0.108352 0 0.994113 -0.32049 0.0416509 0.946336 -0.361956 0 0.932195 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.403505 0 -0.914978 0.4035 -1.09235e-06 -0.91498 0.403499 0 -0.91498 -0.403499 0 0.91498 -0.403499 -4.76753e-07 0.91498 -0.4035 0 0.91498 0.612809 0 -0.790231 0.626458 0.0186506 -0.779232 0.796462 0 -0.604688 0.919055 0 -0.394129 0.931745 0.0346501 -0.361455 0.989746 0 -0.142836 0.994909 0 0.10078 0.987097 0.0479806 0.152763 0.934924 0 0.354849 0.821353 0 0.57042 0.778029 0.0586281 0.625487 0.645729 0 0.763566 0.441893 0 0.897068 0.360867 0.0665893 0.930237 0.194658 0 0.980871 0.0211847 0 0.999776 -0.1526 0.066372 0.986057 -0.238301 0 0.971191 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.80693 0 -0.590647 0.806932 4.74933e-07 -0.590645 0.806932 0 -0.590645 -0.806931 0 0.590645 -0.806931 -9.53507e-07 0.590646 -0.806931 0 0.590645 0.918131 0 -0.396278 0.924052 -0.0151622 -0.381967 0.999046 0.0141308 0.0413241 0.99575 -0.0282508 0.0876552 0.881965 0.026184 0.470587 0.842557 -0.0392519 0.537175 0.59026 0.0361488 0.806404 0.552529 0 0.833494 0.338677 0 0.940903 0.181862 0.0440155 0.982338 0.0796893 -0.0293701 0.996387 -0.262479 0.0330594 0.964371 -0.321812 -0.0165406 0.946659 -0.655158 0.0183805 0.755268 -0.670727 0 0.741704 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0646955 0 -0.997905 0.0646954 -2.79871e-08 -0.997905 0.0646954 0 -0.997905 -0.0646954 0 0.997905 -0.0646954 -1.98647e-08 0.997905 -0.0646954 0 0.997905 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.293145 0 -0.956068 0.320629 0.0294434 -0.946747 0.530609 0 -0.847617 0.711823 0 -0.702359 0.750372 0.0515844 -0.659 0.869351 0 -0.494195 0.959905 0 -0.280325 0.978484 0.0663699 -0.195355 0.99975 0 -0.0223374 0.977939 0 0.208892 0.944575 0.0737975 0.319894 0.890552 0 0.454882 0.761604 0 0.648042 0.658077 0.0738712 0.749318 0.567925 0 0.82308 0.36274 0 0.93189 0.195351 0.0665894 0.97847 0.109191 0 0.994021 0.460957 0.707025 -0.536315 0.451689 0.734213 -0.506862 0.481772 0.707051 -0.517663 0.73431 0.650191 -0.195038 -0.128887 0.553543 -0.822787 0.966489 0 -0.256707 0.966489 0 -0.256707 0.67875 0.707109 0.198229 0.678752 0.707107 0.19823 -0.594682 0.707107 -0.38256 -0.594682 0.707107 -0.38256 -0.15476 0 -0.987952 -0.15476 0 -0.987952 0.815099 0.542205 -0.204028 0.780958 0.555908 -0.284729 0.645666 0.589901 -0.484904 0.648409 0.71887 -0.250581 0.599072 0.700912 -0.387085 0.94619 0.181949 -0.267618 0.907111 0.323028 -0.269818 0.899418 0.354707 -0.255401 0.782646 0.503018 -0.366657 0.984829 0.0718786 -0.157938 0.950368 0.131605 -0.281923 0.966312 0.0191871 -0.256659 0.716071 0.697152 0.0349366 0.716072 0.697152 0.0349363 0.654016 0.697152 -0.29367 0.654015 0.697154 -0.293668 -0.508058 0.69932 -0.50282 -0.50806 0.699319 -0.50282 -0.260785 0.699319 -0.66554 0.317854 0.699321 -0.640249 0.317854 0.69932 -0.64025 0.0312087 0.69932 -0.714127 0.0312094 0.69932 -0.714127 -0.157362 0.706485 -0.690012 -0.310332 0.672668 -0.671723 0.354227 0.703718 -0.615877 -0.154399 0.0682397 -0.985649 -0.166813 0.127654 -0.97769 -0.10101 0.260449 -0.960189 -0.0972812 0.364826 -0.92598 0.0072622 0.479027 -0.87777 0.0299399 0.553917 -0.832033 0.164945 0.62886 -0.759821 0.197585 0.676064 -0.709857 0.372584 0.698707 -0.610729 0.95227 0.0414742 -0.302427 0.941971 0.0907739 -0.323189 0.948983 0.159298 -0.272132 0.919355 0.266168 -0.289725 0.918991 0.315151 -0.236929 0.884256 0.407995 -0.227224 0.870987 0.462876 -0.164704 0.870822 0.463797 -0.162977 0.806765 0.577949 -0.122903 0.773975 0.630889 0.0542323 0.718018 0.693604 -0.0580027 0.709393 0.697151 -0.103643 0.709394 0.69715 -0.103644 0.585206 0.69715 -0.414144 0.585205 0.697152 -0.414142 0.602791 0.696908 0.388538 0.626105 0.682123 0.377759 0.502258 0.706951 0.497953 0.357458 0.696907 0.621727 0.409451 0.666107 0.623419 0.237945 0.706485 0.666529 0.654936 0.706771 0.267458 0.605803 0.717737 0.343302 0.596239 0.676626 0.432061 0.520186 0.646716 0.557822 0.517691 0.576416 0.63225 0.448384 0.496615 0.743186 0.456074 0.401428 0.794262 0.399714 0.281668 0.872292 0.423106 0.148632 0.893806 0.398974 0.0781799 0.913623 0.95309 0 -0.302688 0.95309 0 -0.302688 0.466006 0.707107 -0.531825 0.466006 0.707107 -0.531825 -0.296073 0.707107 0.642137 -0.296073 0.707108 0.642136 0.400199 0 0.916428 0.400199 0 0.916428 0.724129 0.650192 -0.229973 0.333294 0.553543 0.76322 0.680653 0.706831 0.192615 0.653155 0.732642 0.191377 0.685918 0.707093 0.171859 0.170569 0.965926 -0.194661 0.13599 0.980356 -0.142856 0.396369 0.79334 -0.462065 0.354826 0.843944 -0.402314 0.521859 0.608756 -0.597561 0.517514 0.618432 -0.591373 0.591211 0.442295 -0.674422 0.619568 0.332073 -0.71124 0.649335 0.195091 -0.735054 0.656713 0.0838202 -0.749468 0.795095 0.606095 -0.0217696 0.667086 0.439828 -0.601288 0.454155 0.791309 -0.409357 0.193497 0.965474 -0.17441 0.193497 0.965474 -0.174409 0.228837 0.965474 -0.124472 0.228837 0.965474 -0.124472 0.251557 0.965474 -0.0676662 0.251557 0.965474 -0.0676674 0.260402 0.965474 -0.00713129 0.260401 0.965474 -0.00713012 0.611188 0.791308 -0.0167378 0.702088 0.707001 -0.0849786 0.685199 0.70465 -0.184312 0.685201 0.704647 -0.184317 0.623317 0.704647 -0.339042 0.623316 0.704649 -0.339037 0.567044 0.707001 -0.422623 0.590809 0.606095 -0.532535 0.728711 0.193794 -0.656829 0.746776 0.258203 -0.612908 0.848917 0.257146 -0.461753 0.848918 0.257152 -0.461748 0.933199 0.257152 -0.251024 0.933199 0.257148 -0.251028 0.96601 0.257148 -0.0264523 0.966009 0.257152 -0.0264492 0.770413 0.439825 -0.461539 0.524501 0.791307 -0.314217 0.168476 0.980525 -0.100931 0.381535 0.895649 -0.228569 0.247284 0.965561 -0.0808889 0.248528 0.965474 -0.0780637 0.248527 0.965474 -0.078063 0.25988 0.965474 -0.0179461 0.25988 0.965474 -0.0179458 0.256898 0.965474 0.0431596 0.256899 0.965474 0.0431594 0.682317 0.606099 -0.408763 0.637829 0.707 -0.305491 0.676948 0.704649 -0.21263 0.676949 0.704647 -0.212633 0.707872 0.704647 -0.0488839 0.707871 0.704648 -0.0488823 0.69975 0.704648 0.117561 0.699751 0.704648 0.11756 0.841579 0.19379 -0.504173 0.850847 0.258203 -0.457592 0.921961 0.257147 -0.289591 0.921961 0.257149 -0.289589 0.964076 0.257149 -0.0665755 0.964076 0.257148 -0.0665767 0.953016 0.257148 0.160109 0.953016 0.257149 0.16011 0.463436 0.875734 0.135342 0.953116 0.118685 0.278358 0.929163 0.258815 0.263954 0.894062 0.364322 0.26062 0.678736 0.707107 0.198287 0.594417 0.788351 0.158653 0.765956 0.602552 0.224148 0.248439 0.965926 0.0725568 0.0923089 0.995722 0.00409709 0.299464 0.950246 0.085753 0.857841 0 -0.513915 0.911939 -0.0262559 -0.409485 0.98618 0 0.16568 0.998468 -0.0262556 0.0487145 0.997624 0 -0.0688922 0.954044 0 -0.299668 0.742792 0 -0.669522 0.815991 -0.0262554 -0.577469 0.999625 0 -0.0273728 0.989154 -0.0262558 -0.144516 0.965674 0 -0.259759 0.878457 0 -0.477821 -0.217674 0.965925 -0.140022 -0.154551 0.982244 -0.106355 -0.514416 0.793348 -0.325539 -0.437848 0.852969 -0.284136 -0.668122 0.60876 -0.427814 -0.653878 0.629169 -0.420227 -0.812351 0.258819 -0.522588 -0.830079 0.0858434 -0.550998 -0.792446 0.334212 -0.510228 -0.0438485 0.251981 -0.966738 0.40442 0.25198 -0.879176 0.40442 0.25198 -0.879176 0.335023 0.597763 -0.728313 0.215725 0.704719 -0.675895 0.258978 0.784828 -0.563006 0.111085 0.964023 -0.241494 0.111085 0.964023 -0.241494 -0.0438511 0.251978 -0.966739 -0.032497 0.696907 -0.716425 -0.0324918 0.696909 -0.716423 -0.0120432 0.964023 -0.265545 -0.0120431 0.964023 -0.265545 0.129457 0.256133 0.957934 -0.242161 0.254959 0.936138 -0.24216 0.254959 0.936138 -0.0430302 0.258712 0.964996 -0.199861 0.602591 0.772619 -0.0633422 0.707067 0.704304 -0.153995 0.788594 0.595319 -0.112201 0.894019 0.433751 0.0769067 0.961438 0.264049 -0.0496195 0.980175 0.19182 0.10051 0.272767 0.956815 0.0744644 0.701398 0.708869 0.0744644 0.701398 0.708869 0.027448 0.964869 0.261293 0.0274466 0.964869 0.261293 -0.404444 0.25882 0.877176 -0.405834 0.190493 0.893874 -0.336204 0.608753 0.7186 -0.355165 0.521845 0.775587 -0.256561 0.793357 0.552052 -0.266224 0.771926 0.577282 -0.185173 0.896874 0.401656 -0.146631 0.938358 0.313022 -0.0789975 0.98078 0.178408 -0.0383683 0.995793 0.0832147 -0.222348 0 -0.974967 -0.0453099 0.00535034 -0.998959 0.04366 -0.00267607 -0.999043 0.417902 0.0031144 -0.908487 0.444671 0 -0.895694 -0.250436 0 0.968133 -0.250436 0 0.968133 -0.0445468 0 0.999007 -0.0445468 0 0.999007 0.133924 0 0.990992 0.133924 0 0.990992 0.336209 0 0.941787 0.336209 0 0.941787 0.548968 0 0.835843 0.548968 0 0.835843 0.710144 0 0.704057 0.710144 0 0.704057 0.856226 0 0.516602 0.856226 0 0.516602 0.659032 0 -0.752115 0.659032 0 -0.752115 -0.418712 0 0.908119 -0.418712 0 0.908119 -0.841008 0 -0.541023 -0.841008 0 -0.541023 0.959901 0 0.28034 0.959901 0 0.28034 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.708536 0.69581 0.11758 0.697722 0.706965 0.115694 0.698468 0.706246 0.115582 0.687827 0.716883 0.113895 0.433253 0.707107 -0.55883 0.433103 0.707105 -0.55895 0.43305 0.707305 -0.558738 0.665516 0.707111 0.238918 0.665589 0.707106 0.238731 0.665652 0.707109 0.238547 0.545473 0.713707 0.43941 0.456733 0.707117 0.539797 0.463354 0.706886 0.53443 0.551127 0.706568 0.44387 0.556769 0.701323 0.445145 0.475789 0.769418 0.42617 0.535834 0.706629 0.462123 0.490717 0.706816 0.509517 0.461769 0.739009 0.490546 0.463496 0.704023 0.538073 0.615193 0.712458 0.337552 0.615152 0.712505 0.337529 0.620304 0.706668 0.340356 0.620305 0.706667 0.340357 0.625004 0.701259 0.342936 0.624991 0.701275 0.342928 0.346905 0.678614 0.64741 0.326308 0.728087 0.602837 0.337797 0.704722 0.623908 0.325694 0.724474 0.607504 0.29296 0.707106 0.643565 0.245044 0.706244 0.664208 0.245044 0.706242 0.66421 -0.337467 0.712631 0.615039 -0.337531 0.712504 0.615151 -0.340358 0.706668 0.620304 -0.340356 0.70667 0.620302 -0.342992 0.701141 0.625107 -0.342984 0.701157 0.625093 -0.238918 0.707111 0.665516 -0.226283 0.706719 0.670331 -0.103075 0.711264 0.695327 -0.10366 0.706793 0.699785 -0.101913 0.704072 0.702778 -0.131725 0.747101 0.651528 -0.132293 0.706628 0.695109 -0.190865 0.706911 0.681064 -0.19069 0.749149 0.63436 -0.230477 0.701319 0.674561 -0.515733 0.70665 0.484423 -0.531314 0.687977 0.494361 -0.532099 0.686972 0.494915 -0.50209 0.725091 0.471326 -0.502727 0.724294 0.471873 -0.476128 0.685458 0.550862 -0.46265 0.706607 0.535407 -0.463349 0.705265 0.536572 -0.450492 0.724581 0.521574 0.539589 0.707109 -0.456991 0.526815 0.706474 -0.47261 0.535202 0.697627 -0.476314 0.526285 0.706965 -0.472467 0.337536 0.712494 -0.61516 0.337463 0.71264 -0.615031 0.340356 0.706668 -0.620304 0.340357 0.706667 -0.620305 0.342951 0.701227 -0.625033 0.342944 0.701242 -0.625019 0.136058 0.685874 -0.714888 0.238918 0.707111 -0.665516 0.211871 0.706116 -0.675656 0.128663 0.724338 -0.677333 0.132221 0.70531 -0.696459 0.132205 0.706629 -0.695125 0.176006 0.707085 -0.684874 0.193888 0.739178 -0.644999 0.218657 0.692733 -0.687248 -0.359402 0.714523 -0.600239 -0.00416205 0.707114 -0.707088 -0.0195314 0.706658 -0.707286 -0.0169908 0.700301 -0.713646 -0.047609 0.770784 -0.635316 -0.0679099 0.706721 -0.704226 -0.122602 0.706936 -0.69657 -0.131798 0.782455 -0.608599 -0.171245 0.70684 -0.686333 -0.224263 0.70684 -0.670883 -0.215776 0.782455 -0.584127 -0.270792 0.706935 -0.653387 -0.334617 0.706285 -0.623853 -0.276038 0.793683 -0.542098 -0.368999 0.70035 -0.611023 -0.363635 0.706485 -0.607164 -0.516369 0.707085 -0.483108 -0.510031 0.739178 -0.439869 -0.530371 0.720622 -0.446554 -0.541961 0.705794 -0.456217 -0.553618 0.692733 -0.462199 -0.456914 0.707111 -0.539651 -0.485431 0.705728 -0.516047 -0.495016 0.687931 -0.530763 -0.484996 0.706631 -0.515221 -0.615039 0.712631 -0.337467 -0.615183 0.712468 -0.337549 -0.620304 0.706668 -0.340358 -0.620302 0.70667 -0.340356 -0.625107 0.701141 -0.342992 -0.625093 0.701157 -0.342984 -0.684292 0.707056 -0.178368 -0.700921 0.707136 -0.0931084 -0.714959 0.685956 -0.135267 -0.695425 0.706626 -0.130626 -0.696766 0.705292 -0.130696 -0.677514 0.724297 -0.127936 -0.665516 0.707111 -0.238918 -0.674558 0.706256 -0.214883 -0.684566 0.694588 -0.221171 -0.635123 0.748636 -0.190167 0.608676 0.707106 -0.35988 0.570465 0.724194 -0.387443 0.585741 0.706441 -0.397302 0.58575 0.706428 -0.397311 0.607052 0.67934 -0.412292 0.707454 0.706451 0.0208701 0.690571 0.723058 0.0172871 0.690252 0.723364 0.0172281 0.71114 0.702748 0.0206123 0.733505 0.679339 0.021638 0.389081 0.705737 -0.592074 -0.7074 0.705975 -0.0344179 -0.685014 0.727903 -0.030218 -0.684664 0.728234 -0.0301599 -0.712233 0.701105 -0.0342856 -0.741717 0.669742 -0.0360873 0.389083 0.705735 -0.592075 0.279426 0.705735 -0.651045 0.279427 0.705734 -0.651046 0.16114 0.705734 -0.689909 0.161139 0.705738 -0.689905 0.0396194 0.705814 -0.707289 0.0371642 0.718863 -0.694157 -0.0226453 0.707105 -0.706746 -0.084374 0.70583 -0.703339 -0.0845416 0.721916 -0.686797 -0.145582 0.707106 -0.691959 -0.205773 0.705849 -0.677816 -0.202552 0.724884 -0.65842 -0.264073 0.707103 -0.65595 -0.320856 0.705866 -0.63151 -0.313295 0.727767 -0.610083 -0.37445 0.707104 -0.599825 -0.426092 0.705886 -0.565836 -0.413451 0.730568 -0.543442 -0.47335 0.707103 -0.525305 -0.521055 0.705736 -0.480041 -0.496235 0.734867 -0.4623 -0.557732 0.707101 -0.434675 -0.597045 0.705735 -0.381412 -0.566525 0.737877 -0.366862 -0.625008 0.707103 -0.330711 -0.654592 0.705738 -0.271003 -0.618841 0.740839 -0.26114 -0.673119 0.707101 -0.216608 -0.691926 0.705738 -0.152226 -0.651754 0.743758 -0.14846 -0.700588 0.707098 -0.0958606 0.251455 0.70599 0.662079 0.251455 0.705991 0.662078 0.353001 0.705991 0.613976 0.353002 0.70599 0.613977 0.445662 0.70599 0.550421 0.445662 0.70599 0.550421 0.527104 0.70599 0.47301 0.527104 0.705991 0.47301 0.595279 0.705991 0.383693 0.59528 0.705989 0.383694 0.64847 0.70599 0.284719 0.648469 0.705992 0.284718 0.158285 0.980766 -0.11421 0.696417 0.555529 -0.454303 0.42522 0.868478 -0.254822 0.467278 0.831415 -0.300667 0.147874 0.985151 -0.0872452 0.165307 0.980766 -0.103785 0.852728 0.0978199 -0.513115 0.78584 0.354853 -0.506493 0.652913 0.649672 -0.389398 0.158286 0.980766 -0.114211 0.358819 0.896781 -0.258906 0.445781 0.831176 -0.332304 0.49383 0.7932 -0.356322 0.67438 0.555369 -0.486598 0.635641 0.608712 -0.474795 0.727382 0.442104 -0.524842 0.795372 0.194991 -0.5739 0.795372 0.194992 -0.5739 0.828787 0.195014 -0.524482 0.19486 0.980766 0.0112997 0.980796 0.195013 -0.00285066 0.986541 0.163191 -0.0102544 0.831497 0.5555 0.00572029 0.880918 0.472862 -0.0196281 0.683712 0.729739 0.00446823 0.555876 0.831164 -0.0130069 0.471096 0.882079 -0.00241758 0.316272 0.948667 -0.0016366 0.195396 0.980668 -0.0104611 0.123955 0.992288 -0.000803626 0.259621 0.965708 0.00217086 0.55451 0.831176 0.0408078 0.607938 0.793201 0.0352539 0.830212 0.555365 0.0481433 0.791198 0.608707 0.0589984 0.979995 0.195069 0.0394596 0.964339 0.258697 0.0559225 -0.324365 0.194925 -0.92563 -0.551541 0.831005 -0.0723368 0.111812 0.980717 -0.160289 -0.980648 0.194855 -0.0190232 -0.320835 0.947118 -0.00567487 -0.47582 0.879502 -0.00842695 -0.556209 0.831021 -0.00603618 -0.688514 0.725057 -0.0155418 -0.883936 0.467498 -0.0101375 -0.127525 0.991833 -0.00212777 -0.195575 0.980689 0.000265296 -0.193777 0.980716 -0.0254145 -0.193775 0.980717 -0.0254144 -0.189312 0.980717 -0.0485344 -0.182099 0.980717 -0.0709493 -0.18931 0.980717 -0.048534 -0.538835 0.831007 -0.138143 -0.551538 0.831008 -0.0723367 -0.824875 0.554867 -0.108186 -0.831536 0.55514 -0.0191842 -0.986768 0.161324 -0.0162314 0.299271 0.554864 -0.776249 0.162215 0.195047 -0.967286 0.240213 0.194747 -0.950984 0.203742 0.554875 -0.8066 0.299269 0.554874 -0.776242 0.200103 0.831007 -0.519024 0.070303 0.980717 -0.182352 0.0478622 0.980717 -0.189483 0.13623 0.831006 -0.539324 0.0703785 0.831006 -0.551794 0.105257 0.554865 -0.825255 0.00524291 0.554865 -0.831924 0.0478621 0.980717 -0.189483 0.0247263 0.980717 -0.193864 0.0703785 0.831006 -0.551794 0.0035059 0.831006 -0.556253 0.00524335 0.55487 -0.83192 -0.0948456 0.55487 -0.826513 -0.111823 0.194758 -0.974456 -0.184661 0.195078 -0.963247 -0.0222808 0.980717 -0.194161 -0.04547 0.980717 -0.190072 -0.129421 0.831006 -0.540999 -0.193544 0.831006 -0.521508 -0.289461 0.554869 -0.779957 -0.381163 0.554869 -0.739483 -0.0895405 0.980717 -0.173715 -0.109783 0.980717 -0.161686 -0.312475 0.831005 -0.460207 -0.365554 0.831005 -0.419286 -0.546715 0.554867 -0.627076 -0.618163 0.554867 -0.556774 -0.145215 0.980717 -0.130794 -0.159891 0.980717 -0.11238 -0.455096 0.831007 -0.319867 -0.490262 0.831007 -0.262813 -0.733229 0.55487 -0.393059 -0.775178 0.554871 -0.302024 -0.159892 0.980717 -0.112381 -0.172247 0.980717 -0.0923358 -0.490266 0.831004 -0.262815 -0.518315 0.831004 -0.201945 -0.775178 0.55487 -0.302024 -0.805875 0.554869 -0.206604 -0.950124 0.194757 -0.243585 -0.967143 0.195046 -0.163071 0.144669 0.965727 -0.215505 0.320875 0.830915 -0.454553 0.348681 0.792823 -0.499853 0.475969 0.554869 -0.682329 0.457988 0.608189 -0.648347 0.556049 0.194816 -0.807995 0.552694 0.258381 -0.792319 0.0917235 0.980717 -0.172573 0.261071 0.831007 -0.491192 0.261071 0.831006 -0.491193 0.390456 0.554864 -0.734623 0.390454 0.554869 -0.734619 0.469293 -0.0128287 -0.88295 0.488807 0.195021 -0.850314 0.240213 0.194751 -0.950984 0.302744 0.195089 -0.932891 0.35713 0.119935 -0.926323 0.358415 0.194822 -0.913008 0.436696 0.194993 -0.878222 0.0917236 0.980717 -0.172573 0.0703032 0.980717 -0.182352 0.200104 0.831005 -0.519028 0.13623 0.831005 -0.539326 0.203742 0.55487 -0.806603 0.105257 0.55487 -0.825252 0.126519 0.00471074 -0.991953 -0.111824 0.19474 -0.97446 -0.0409507 0.195067 -0.979935 0.00629049 0.0604566 -0.998151 0.0181574 0.19488 -0.980659 0.103654 0.194952 -0.97532 0.0247263 0.980717 -0.193863 0.00123175 0.980717 -0.19543 0.00350594 0.831006 -0.556252 -0.0634174 0.831006 -0.552636 -0.0948463 0.554866 -0.826516 -0.193559 0.554866 -0.80911 -0.232477 0.0397349 -0.97179 -0.242364 0.194897 -0.950408 0.00123169 0.980717 -0.195431 -0.0222808 0.980717 -0.19416 -0.0634175 0.831006 -0.552637 -0.12942 0.831006 -0.540998 -0.19356 0.554865 -0.80911 -0.289463 0.554865 -0.779959 -0.347881 0.017855 -0.937369 -0.626302 0.194973 -0.754806 -0.550982 0.194753 -0.811474 -0.46733 0.55487 -0.688274 -0.381163 0.55487 -0.739483 -0.25486 0.831005 -0.494446 -0.193545 0.831005 -0.521509 -0.0679984 0.980717 -0.183222 -0.0454695 0.980717 -0.19007 -0.567415 0.0739624 -0.820104 -0.508437 0.195086 -0.838709 -0.44939 0.194752 -0.871849 -0.44939 0.194752 -0.871849 -0.379528 0.195061 -0.904383 -0.0679993 0.980717 -0.183224 -0.0895412 0.980717 -0.173716 -0.254859 0.831006 -0.494445 -0.312474 0.831006 -0.460206 -0.467331 0.554869 -0.688275 -0.546715 0.554869 -0.627076 -0.65714 -0.00732804 -0.753733 -0.849884 0.19501 -0.489559 -0.802468 0.194752 -0.564019 -0.680636 0.554869 -0.478388 -0.618162 0.554869 -0.556773 -0.413326 0.831006 -0.372279 -0.365553 0.831006 -0.419286 -0.128431 0.980717 -0.147309 -0.109783 0.980717 -0.161686 -0.809275 0.158705 -0.565585 -0.768611 0.195089 -0.609244 -0.728812 0.194749 -0.656434 -0.728812 0.194751 -0.656434 -0.670627 0.195036 -0.715695 -0.128431 0.980717 -0.147309 -0.145215 0.980717 -0.130794 -0.413326 0.831005 -0.372279 -0.455098 0.831005 -0.319868 -0.680637 0.554866 -0.478389 -0.733231 0.554866 -0.39306 -0.881252 -0.0149854 -0.472409 -0.950124 0.194758 -0.243585 -0.932622 0.195098 -0.303567 -0.92111 0.150869 -0.358881 -0.912698 0.194785 -0.359223 -0.877835 0.195001 -0.437471 -0.172245 0.980717 -0.0923349 -0.1821 0.980717 -0.0709495 -0.518317 0.831003 -0.201946 -0.538842 0.831003 -0.138144 -0.80588 0.554862 -0.206605 -0.824878 0.554862 -0.108186 -0.991496 -0.0050991 -0.130039 -0.975225 0.194971 -0.104514 -0.5155 0.195083 0.834388 -0.768489 0.195017 0.60942 -0.0780219 0.831001 0.550772 0.0432122 0.980716 0.190601 0.0198466 0.980716 0.194429 -0.0944508 0.980716 0.1711 -0.114448 0.980716 0.158423 -0.132766 0.980716 0.14342 -0.612033 0.675819 0.410712 -0.387777 0.887148 0.250194 -0.460835 0.831172 0.311101 -0.12829 0.988418 0.0810652 -0.16285 0.980725 0.107976 -0.81615 0.194817 0.544009 -0.829872 0.116865 0.545578 -0.792283 0.305978 0.527887 -0.0274119 0.980716 0.193507 -0.0274118 0.980716 0.193506 -0.0506108 0.980716 0.188771 -0.634837 0.554862 0.53769 -0.424479 0.831 0.359522 -0.424479 0.831001 0.359521 -0.149134 0.980716 0.126313 -0.149135 0.980716 0.126313 -0.0162214 0.554859 0.831786 -0.0108463 0.831001 0.556165 -0.0108464 0.831003 0.556163 -0.00381077 0.980716 0.195401 -0.00381075 0.980716 0.195402 -0.215442 0.554854 0.803568 -0.0620945 0.195062 0.978823 -0.137573 0.194743 0.971158 -0.116687 0.554859 0.823721 -0.215441 0.554859 0.803565 -0.144052 0.831003 0.537292 -0.730166 0.194997 0.654855 -0.762975 -0.0164769 0.646218 -0.634837 0.554862 0.537689 -0.692271 0.555 0.461233 -0.742725 0.462109 0.484577 -0.629264 0.19508 0.75231 -0.132766 0.980716 0.143421 -0.377889 0.831 0.408215 -0.377888 0.831001 0.408214 -0.565157 0.554864 0.610511 -0.565158 0.554862 0.610513 -0.677352 0.0761175 0.731711 -0.673709 0.194857 0.712844 -0.114448 0.980716 0.158423 -0.32575 0.831002 0.450914 -0.325751 0.831 0.450916 -0.487184 0.554858 0.674377 -0.487182 0.554864 0.674373 -0.574385 0.194751 0.795082 -0.574385 0.194746 0.795083 -0.0944509 0.980716 0.171101 -0.268832 0.831001 0.486998 -0.268832 0.831002 0.486997 -0.402059 0.554858 0.728341 -0.402059 0.554858 0.728341 -0.474022 0.194755 0.858705 -0.472838 0.0333296 0.880519 -0.0730672 0.980716 0.181266 -0.207968 0.831003 0.51593 -0.207969 0.831001 0.515933 -0.311033 0.554855 0.771618 -0.311033 0.554858 0.771616 -0.37382 -0.0149652 0.92738 -0.3912 0.194994 0.899411 -0.137574 0.194752 0.971157 -0.2011 0.195094 0.959946 -0.256761 0.130054 0.957685 -0.258895 0.194807 0.946057 -0.335996 0.195027 0.921451 -0.0730673 0.980716 0.181267 -0.0506111 0.980716 0.188772 -0.144052 0.831 0.537296 -0.0780219 0.831 0.550773 -0.116687 0.554858 0.823721 -0.0162214 0.554859 0.831787 -0.0194917 0.0257772 0.999478 -0.00269013 0.194912 0.980817 0.137258 0.195037 0.971144 0.0198466 0.980716 0.194429 0.056489 0.830999 0.553398 0.0564881 0.831002 0.553393 0.0844821 0.554865 0.82764 0.084483 0.554859 0.827644 0.101549 -0.000876961 0.99483 0.0781827 0.194952 0.977692 0.0432124 0.980716 0.190602 0.122994 0.831 0.542505 0.122995 0.830999 0.542506 0.183946 0.554864 0.81135 0.183946 0.554865 0.81135 0.216871 0.194748 0.956577 0.216872 0.194738 0.956579 -0.852232 -0.136208 0.505122 -0.727177 -0.0911385 0.680373 -0.88376 -0.332038 0.329727 -0.916395 -0.360927 0.173066 -0.692594 -0.468272 0.548666 -0.728928 -0.683691 0.0350808 -0.446629 -0.563462 0.695006 -0.51678 -0.855258 -0.0383706 -0.204819 -0.800261 0.563588 -0.281723 -0.887821 -0.363877 -0.275949 -0.949972 0.146304 -0.25167 -0.709908 -0.657794 -0.985903 -0.164298 0.0316598 -0.88742 -0.103445 0.449205 -0.908655 -0.343495 -0.237398 -0.816225 -0.479412 0.3224 -0.787344 -0.596302 -0.156565 -0.571686 -0.71863 0.395912 -0.577641 -0.725283 0.374559 -0.503413 -0.76848 -0.394987 -0.507 -0.861805 0.0156033 -0.352666 -0.935699 0.00965501 0.852231 -0.136213 -0.505122 0.727161 -0.0911375 -0.68039 0.883746 -0.332028 -0.329774 0.916395 -0.360927 -0.173066 0.692582 -0.468274 -0.548679 0.728922 -0.683696 -0.0351071 0.446616 -0.563454 -0.695021 0.516774 -0.855263 0.0383436 0.204818 -0.80026 -0.56359 0.281722 -0.887817 0.363886 0.275938 -0.949973 -0.146322 0.251669 -0.709941 0.657759 0.985903 -0.164298 -0.0316598 0.887421 -0.103446 -0.449203 0.908655 -0.343496 0.237397 0.816225 -0.479412 -0.322399 0.787344 -0.596302 0.156565 0.571686 -0.71863 -0.395912 0.577641 -0.725283 -0.37456 0.503413 -0.768479 0.394988 0.507009 -0.861801 -0.0155176 0.352697 -0.935688 -0.00959633 0.115151 0.195084 -0.974003 0.977415 0.195086 -0.0812491 0.316171 0.830868 -0.457925 0.512672 0.830869 0.21639 -0.0417668 0.980697 -0.19102 -0.0153673 0.980697 -0.19493 0.0113187 0.980697 -0.195205 0.0377938 0.980697 -0.191846 0.0635649 0.980697 -0.184913 0.193978 0.980697 0.0246136 0.0673884 0.980697 0.183554 0.144264 0.985196 -0.0926077 0.310404 0.932393 -0.185182 0.58631 0.758122 -0.285467 0.629321 0.734885 -0.252781 0.404779 0.896355 -0.180836 0.728495 0.582466 -0.360594 0.744294 0.555441 -0.370826 0.896584 0.209964 -0.389939 0.585123 0.742532 -0.326003 0.384938 0.9161 -0.112175 0.861858 0.420564 -0.283419 0.836085 0.420382 -0.352479 0.797756 0.594116 -0.103013 0.828638 0.555574 -0.0685294 0.584458 0.809951 -0.0488804 0.815735 0.571247 -0.0908461 0.831498 0.548484 -0.088182 0.438552 0.896358 -0.064921 0.894544 0.420396 -0.151847 0.879183 0.420579 -0.223941 0.556387 0.830913 -0.00426076 0.195371 0.980729 0.00069673 0.174559 0.984646 -0.00065064 0.352683 0.935742 -0.00147191 0.180145 0.980697 0.0760359 0.180145 0.980697 0.0760359 0.168114 0.980697 0.0998574 0.111097 0.980697 -0.160907 0.111097 0.980697 -0.160907 0.131972 0.980697 -0.14428 0.803498 0.554676 0.216163 0.537362 0.830869 0.144565 0.537362 0.830869 0.144565 0.188821 0.980697 0.050798 0.188822 0.980697 0.0507981 0.375119 0.554672 -0.742714 0.250872 0.830867 -0.496712 0.250871 0.830869 -0.49671 0.088152 0.980697 -0.174536 0.0881519 0.980697 -0.174536 0.486865 0.554674 0.674758 0.73767 0.195043 0.646375 0.676901 0.194649 0.709872 0.574209 0.554677 0.602178 0.486864 0.554677 0.674757 0.325606 0.830867 0.451265 0.114413 0.980697 0.158568 0.134939 0.980697 0.141512 0.384021 0.830867 0.402726 0.435282 0.830867 0.346684 0.650855 0.55468 0.51838 0.715379 0.55468 0.424927 0.134937 0.980697 0.14151 0.152949 0.980697 0.121818 0.43528 0.830868 0.346683 0.478433 0.830868 0.284183 0.715384 0.554673 0.424929 0.766582 0.554672 0.32356 0.903675 0.194647 0.381424 0.931525 0.195069 0.306935 0.561589 0.554676 -0.613964 0.486411 0.195062 -0.851678 0.557304 0.194652 -0.80717 0.472757 0.554676 -0.684716 0.561589 0.554676 -0.613964 0.375579 0.830869 -0.410606 0.0673884 0.980697 0.183554 0.191782 0.830866 0.52238 0.191781 0.830868 0.522378 0.286762 0.554679 0.781088 0.286764 0.554673 0.781092 0.338047 0.194651 0.92078 0.338046 0.194658 0.920778 0.0917547 0.980697 0.172668 0.261126 0.830867 0.491399 0.261127 0.830866 0.4914 0.390451 0.554674 0.734769 0.390449 0.554678 0.734766 0.463755 -0.152638 0.872716 0.426641 0.195005 0.883148 0.6769 0.194653 0.709871 0.620363 0.195084 0.759666 0.58462 0.0415997 0.81024 0.567111 0.194755 0.800284 0.485919 0.194952 0.851983 0.0917547 0.980697 0.172668 0.114412 0.980697 0.158566 0.325604 0.830869 0.451263 0.384019 0.830868 0.402724 0.574208 0.554678 0.602177 0.650856 0.554678 0.51838 0.77756 -0.108972 0.619294 0.903674 0.194652 0.381424 0.867788 0.195062 0.45705 0.857642 -0.070224 0.509429 0.834613 0.194838 0.515227 0.780087 0.194878 0.594548 0.15295 0.980697 0.121819 0.168113 0.980697 0.0998573 0.478431 0.830869 0.284182 0.512671 0.830869 0.216389 0.766579 0.554677 0.323559 0.803497 0.554678 0.216163 0.965472 -0.0199766 0.259739 0.950351 0.1948 0.242664 0.977377 0.195036 0.0818295 0.19398 0.980697 0.0246138 0.552047 0.830866 0.0700483 0.552041 0.830869 0.070048 0.825447 0.554678 0.10474 0.825448 0.554676 0.10474 0.98278 -0.136352 0.124704 0.969537 0.194918 0.148341 0.530333 0.847772 -0.00550349 0.832019 0.55468 -0.00863421 0.832021 0.554678 -0.00863439 0.98082 0.19465 -0.0101786 0.980818 0.19466 -0.0101781 0.982787 0.108151 -0.149777 0.970298 0.194654 -0.143638 0.950459 0.194982 -0.242096 0.948 -0.158042 -0.276258 0.931721 0.194984 -0.306393 0.897253 0.194708 -0.396264 0.907106 0.113708 -0.405252 0.868053 0.195088 -0.456535 0.164924 0.98072 -0.104829 0.47103 0.830943 -0.296083 0.439396 0.855649 -0.273488 0.706407 0.55468 -0.439681 0.706409 0.554677 -0.439682 0.832743 0.194649 -0.518315 0.832743 0.194652 -0.518315 0.150389 0.980697 -0.124966 0.427991 0.830869 -0.355641 0.427993 0.830867 -0.355642 0.639959 0.554676 -0.531776 0.639958 0.55468 -0.531775 0.761938 -0.13635 -0.633134 0.780413 0.195025 -0.594071 0.557304 0.194649 -0.80717 0.620811 0.195071 -0.759303 0.674798 -0.0199776 -0.737732 0.671216 0.194801 -0.715207 0.738069 0.194919 -0.645957 0.150389 0.980697 -0.124967 0.131972 0.980697 -0.144281 0.37558 0.830867 -0.410608 0.316171 0.830867 -0.457925 0.472755 0.554682 -0.684712 0.375116 0.554682 -0.742708 0.449714 -0.0702317 -0.890407 0.427174 0.194851 -0.882925 0.274955 0.195049 -0.941465 0.0635649 0.980697 -0.184913 0.180899 0.830869 -0.526244 0.180899 0.830869 -0.526244 0.270492 0.554674 -0.786874 0.270492 0.554672 -0.786875 0.323148 -0.108965 -0.940054 0.338573 0.19489 -0.920536 0.0377938 0.980697 -0.191846 0.107558 0.830867 -0.545977 0.107557 0.830869 -0.545975 0.160826 0.554679 -0.816374 0.160826 0.554673 -0.816378 0.189588 0.194654 -0.962375 0.189588 0.194654 -0.962375 0.0113187 0.980697 -0.195206 0.0322119 0.830868 -0.555537 0.0322119 0.830868 -0.555537 0.0481652 0.554675 -0.830672 0.0481653 0.55468 -0.830669 0.0567793 0.194649 -0.979228 0.0493529 0.0191414 -0.998598 -0.114579 0.195005 -0.974087 -0.0153671 0.980697 -0.194928 -0.0437335 0.830868 -0.554749 -0.0437335 0.830868 -0.554749 -0.0653926 0.554682 -0.829489 -0.0653934 0.554675 -0.829494 -0.0776705 -0.152644 -0.985224 -0.0478381 0.194948 -0.979646 -0.0417672 0.980697 -0.191022 -0.118865 0.830868 -0.543627 -0.118865 0.830868 -0.543627 -0.177734 0.554672 -0.812865 -0.177732 0.554682 -0.812858 -0.209518 0.194658 -0.958233 -0.209519 0.194651 -0.958234 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.572121 0 -0.820169 0.548868 0.0338262 -0.835224 0.365416 0.00138749 -0.930843 0.394141 0.0365572 -0.918323 0.445243 -0.000407232 -0.89541 0.498376 0.000347666 -0.866961 0.308675 -0.000121842 -0.951167 0.244897 0.00643002 -0.969528 0.227342 0.0301346 -0.973349 0.165392 0.000857357 -0.986228 0.105681 -0.00140717 -0.994399 0.055891 0.0364578 -0.997771 0.0185123 0 -0.999829 -0.0320253 0 -0.999487 -0.0417527 -0.000487683 -0.999128 -0.113996 0.0138194 -0.993385 -0.119082 0.0211032 -0.99266 -0.188278 0 -0.982116 -0.205884 0 -0.978576 -0.290487 -0.0054648 -0.956863 -0.246424 0.074036 -0.96633 -0.330708 0 -0.943733 -0.373454 0 -0.927649 -0.386961 -0.00109748 -0.922095 -0.452871 0.0204394 -0.891342 -0.458128 0.0122732 -0.888801 -0.518398 0 -0.85514 -0.529551 0 -0.848278 -0.60153 -0.00765003 -0.798813 -0.567831 0.0633161 -0.820706 -0.638557 0 -0.769575 -0.669414 0 -0.74289 -0.683757 -0.00195195 -0.729707 -0.731456 0.0248428 -0.681436 -0.743034 0.00340213 -0.669245 -0.783668 0 -0.621179 -0.788747 0 -0.614719 -0.839336 -0.00983562 -0.543525 -0.81853 0.0525727 -0.572053 -0.86652 0 -0.499142 -0.883891 0 -0.467694 -0.895012 -0.00304969 -0.446031 -0.920966 0.0280418 -0.388632 -0.930521 0 -0.366238 -0.951926 0 -0.306328 -0.999812 0 -0.0193949 -0.998368 0.030036 -0.0485747 -0.994297 -0.00439151 -0.106558 -0.990768 0 -0.135566 -0.986081 0 -0.166264 -0.974662 0.0272749 -0.222013 -0.968665 -0.0038714 -0.248339 -0.950895 0.00046146 -0.309514 0.462685 0.0637355 0.884229 0.498434 0 0.866928 0.410067 0 0.912056 0.35495 0.023958 0.934578 0.336424 0 0.941711 0.532454 0 0.846459 0.581892 0 0.813266 0.629088 0.0239583 0.776965 0.644573 0 0.764543 0.73086 0 0.682528 0.744051 0.0239579 0.667693 0.782699 0 0.6224 0.840527 0 0.54177 0.816695 0.0637349 0.573539 0.923432 0 0.383762 0.915369 0.0239589 0.401903 0.890078 0 0.455808 0.86137 0 0.507978 0.995564 0 0.0940901 0.995564 0 0.0940901 0.965182 0 0.26158 0.965182 0 0.26158 0.906833 0 0.421491 0.906833 0 0.421491 0.822207 0 0.569188 0.822207 0 0.569188 0.713757 0 0.700393 0.713757 0 0.700393 0.584625 0 0.811303 0.584625 0 0.811303 0.438554 0 0.898705 0.438554 0 0.898705 0.279774 0 0.960066 0.279774 0 0.960066 0.112888 0 0.993608 0.112888 0 0.993608 -0.0572698 0 0.998359 -0.0572698 0 0.998359 -0.225767 0 0.974181 -0.225767 0 0.974181 -0.387724 0 0.921776 -0.387724 0 0.921776 -0.538444 0 0.842661 -0.538444 0 0.842661 -0.673564 0 0.739129 -0.673564 0 0.739129 -0.789166 0 0.61418 -0.789166 0 0.61418 -0.202264 0 -0.979331 -0.202264 0 -0.979331 -0.0438784 0 -0.999037 -0.0438784 0 -0.999037 0.115627 0 -0.993293 0.115627 0 -0.993293 0.272186 0 -0.962245 0.272186 0 -0.962245 0.421811 0 -0.906684 0.421811 0 -0.906684 0.560691 0 -0.828026 0.560691 0 -0.828026 0.685287 0 -0.728273 0.685287 0 -0.728273 0.792426 0 -0.609969 0.792426 0 -0.609969 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.999485 0 0.032096 -0.999485 0 0.032096 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.860249 0 0.509874 -0.860249 0 0.509874 0.999485 0 -0.032096 0.999485 0 -0.032096 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.860249 0 -0.509874 0.860249 0 -0.509874 0.810938 0 -0.585132 0.827063 0.0210443 -0.561716 0.845011 0 -0.534749 0.999565 0 0.0294875 0.997545 0.0394745 0.0578482 0.999996 0 -0.00290646 0.610743 0.700508 -0.369163 0.605143 0.707058 -0.365884 0.605389 0.70663 -0.366304 0.599919 0.713017 -0.362909 0.707088 0.707114 -0.00416204 0.707258 0.706767 -0.0163285 0.712029 0.702013 -0.0138621 0.706963 0.707057 -0.0165705 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.513717 0 -0.85796 0.855626 0 -0.517594 0.855626 0 -0.517594 0.80048 -0.172367 -0.574039 0.744364 0 -0.667774 0.682297 -0.000607904 -0.731075 0.681275 0 -0.732028 0.681275 0 -0.732028 0.686682 -0.00331382 -0.726951 0.692463 -0.00795449 -0.721409 0.674415 0.0133155 -0.738233 0.704343 -0.00947496 -0.709796 0.82418 0.0441825 -0.564602 0.778387 0 -0.627784 0.769472 0 -0.638681 0.72792 -0.0756629 -0.681475 0.726743 -0.0482584 -0.685212 0.715924 -0.0254303 -0.697715 0.555043 0 -0.831822 0.578061 0.0488927 -0.814527 0.612565 -0.135211 -0.77877 0.612596 0 -0.790396 0.615556 -9.01099e-05 -0.788093 0.639351 -0.00762935 -0.768877 0.62975 -0.0250592 -0.776394 0.637466 -0.0138713 -0.770354 0.651816 0 -0.758377 0.651816 0 -0.758377 0.648008 -0.00296308 -0.761627 0.642929 -0.00761669 -0.765888 0.481041 0 -0.876698 0.481041 0 -0.876698 0.353393 -0.0927248 -0.930868 0.372734 0 -0.927938 0.422842 0 -0.906204 0.437027 0.0363328 -0.898714 0.490102 -0.0932224 -0.866666 0.474352 -0.166178 -0.864509 0.519736 0 -0.854327 0.146637 0 -0.98919 0.186576 0.0213266 -0.982209 0.209387 -0.0208518 -0.977611 0.248903 0 -0.968528 0.28091 0 -0.959734 0.299161 0.0185415 -0.954023 0.319839 0 -0.947472 -0.027604 0 -0.999619 0.120745 -0.0399976 -0.991877 0.132516 0 -0.991181 0.0504588 0 -0.998726 0.059003 0.063796 -0.996217 -0.0189233 -0.024588 -0.999519 -0.644082 -0.021927 -0.764643 -0.635191 0 -0.772355 -0.586131 0 -0.810216 -0.578233 0.0540177 -0.814081 -0.520985 -0.0245883 -0.853212 -0.513717 0 -0.85796 -0.456839 0 -0.889549 -0.453752 0.00670223 -0.891103 -0.386051 -0.00482912 -0.922465 -0.382864 0 -0.923805 -0.317036 0 -0.948413 -0.317036 0 -0.948413 -0.242086 0 -0.970255 -0.242086 0 -0.970255 -0.169937 0 -0.985455 -0.17334 -0.00536308 -0.984847 -0.092543 0.00723612 -0.995682 -0.0959868 0 -0.995383 -0.027604 0 -0.999619 -0.778753 0 -0.62733 -0.764832 0.0185405 -0.643963 -0.752508 0 -0.658584 -0.730234 0 -0.683197 -0.701783 -0.0208515 -0.712085 -0.685014 0.0213268 -0.728218 -0.655077 0 -0.755562 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.804928 -0.139488 -0.576744 -0.801589 0 -0.597876 -0.851967 0 -0.523596 -0.841408 0.0697654 -0.535878 -0.874752 -0.0666235 -0.47997 -0.87649 -0.119326 -0.466397 -0.89732 0 -0.441382 -0.915011 0 -0.40343 -0.925134 0.0488911 -0.376478 -0.935027 -0.13521 -0.327784 -0.952823 0 -0.303526 -0.965484 0.00645727 -0.260384 -0.967667 0 -0.252233 -0.952823 0 -0.303526 -0.999734 0 0.023081 -0.999734 0 0.023081 -0.991492 -0.125856 -0.0332292 -0.997975 0.0320467 -0.0549492 -0.993781 0 -0.111356 -0.992115 0 -0.125332 -0.980056 -0.0756667 -0.183751 -0.981033 0 -0.19384 -0.982386 -0.0225022 -0.185505 0.778753 0 0.62733 0.346122 0 0.93819 0.513717 0 0.85796 0.475604 0.0420169 0.878655 0.456839 0 0.889549 0.414307 0 0.910137 0.386049 -0.00533853 0.922463 0.315578 0.0957868 0.944053 0.655077 0 0.755562 0.537542 -0.0857407 0.838867 0.521142 0 0.85347 0.597625 0 0.801776 0.582265 0.114674 0.804871 0.644082 -0.021927 0.764643 0.809254 -0.181098 0.558849 0.778753 0 0.62733 0.752507 0 0.658585 0.744833 0.0111561 0.667157 0.701784 -0.0208521 0.712085 0.693694 0 0.720269 0.655077 0 0.755562 0.876699 0 0.481039 0.790628 0.164809 0.589699 0.843463 0 0.537187 0.860924 0 0.508734 0.878954 -0.0932201 0.467708 0.941284 0 0.337617 0.959654 0 0.281182 0.959654 0 0.281182 0.958678 -0.00285314 0.28448 0.956701 -0.00899421 0.290934 0.965171 0.0262412 0.260299 0.952338 -0.011363 0.304833 0.943037 -0.000125683 0.332689 0.876699 0 0.481039 0.864508 -0.166185 0.47435 0.901902 0.0490218 0.429149 0.915011 0 0.40343 0.931069 0 0.364843 0.935027 -0.135208 0.327785 0.952158 -0.00965652 0.305453 0.949463 -0.0206643 0.313199 0.980056 -0.0756659 0.183751 0.981033 0 0.193839 0.983219 -0.082307 0.162807 0.978751 -0.0261558 0.203376 0.975798 -0.0112193 0.218387 0.97437 -0.00696099 0.224845 0.973511 -0.00470299 0.228592 0.970016 0 0.24304 0.970016 0 0.24304 0.971074 -0.000986371 0.238776 0.972241 -0.00239706 0.233969 0.999734 0 -0.023081 0.999734 0 -0.023081 0.990092 -0.135323 0.0374829 0.998122 -0.0344979 0.0506153 0.992634 0.00551991 0.121024 -0.706963 0.707057 0.0165705 -0.712316 0.701725 0.013708 -0.713151 0.700882 0.0134031 -0.699741 0.714212 0.016261 -0.700592 0.713379 0.0161747 -0.59737 0.707138 0.378292 -0.605017 0.70659 0.366994 -0.599611 0.713372 0.362721 -0.608169 0.701726 0.371096 -0.602972 0.710956 0.361893 -0.61199 0.707245 0.35394 -0.61415 0.706998 0.350675 -0.979609 0 0.200915 -0.979609 0 0.200915 -0.934186 0 0.356786 -0.934186 0 0.356786 0.979609 0 -0.200915 0.979609 0 -0.200915 0.934186 0 -0.356786 0.934186 0 -0.356786 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.993586 0 0.11308 -0.998038 0 -0.0626089 -0.992554 0 0.121804 -0.994956 -0.0957013 0.0300613 -0.978538 0 0.206066 -0.951555 -0.208812 0.225701 -0.95267 0 0.304005 -0.923251 0 0.384198 -0.874207 -0.265037 0.40684 -0.879646 0 0.47563 -0.836957 0 0.547269 -0.774039 -0.266735 0.574209 -0.777296 0 0.629135 0.955907 -0.265038 -0.126476 0.985111 0 -0.171921 0.808164 0 -0.588958 0.856033 -0.0870046 -0.509546 0.854781 -0.0966845 -0.509904 0.902607 0 -0.430465 0.944663 0 -0.328042 0.900327 -0.273623 -0.338439 0.966845 0 -0.255364 0.587945 0 -0.808901 0.738741 0 -0.67399 0.738741 0 -0.67399 0.808164 0 -0.588958 0.99745 0 -0.0713762 0.999928 0 0.01198 0.961332 -0.266735 0.068502 0.993586 0 0.11308 0.962745 0 0.270412 0.962745 0 0.270412 0.888604 0 0.458675 0.888604 0 0.458675 0.778084 0 0.628161 0.778084 0 0.628161 0.635708 0 0.77193 0.635708 0 0.77193 0.467307 0 0.884095 0.467307 0 0.884095 0.279774 0 0.960066 0.279774 0 0.960066 0.0807873 0 0.996731 0.0807873 0 0.996731 -0.121507 0 0.992591 -0.121507 0 0.992591 -0.318827 0 0.947813 -0.318827 0 0.947813 -0.503094 0 0.864232 -0.503094 0 0.864232 -0.666764 0 0.745269 -0.666764 0 0.745269 -0.777296 0 0.629135 -0.995859 -0.0861201 0.0291393 -0.998038 0 -0.0626089 -0.985162 0 -0.171625 -0.985162 0 -0.171625 -0.930448 0 -0.366423 -0.930448 0 -0.366423 -0.837641 0 -0.54622 -0.837641 0 -0.54622 -0.710541 0 -0.703655 -0.710541 0 -0.703655 -0.554352 0 -0.832282 -0.554352 0 -0.832282 -0.375467 0 -0.926836 -0.375467 0 -0.926836 -0.18121 0 -0.983444 -0.18121 0 -0.983444 0.0204648 0 -0.999791 0.0204648 0 -0.999791 0.221302 0 -0.975205 0.221302 0 -0.975205 0.387316 0 -0.921947 0.412991 0.020749 -0.910499 0.478601 0 -0.878033 0.587945 0 -0.808901 -0.146637 0 0.98919 -0.855627 0 0.517592 -0.855627 0 0.517592 -0.804252 -0.163075 0.571477 -0.82181 -0.0417371 0.568231 -0.772225 0.00552165 0.635326 -0.72792 -0.0756629 0.681475 -0.674461 0.00645927 0.738283 -0.728942 -0.0225006 0.684205 -0.723325 0 0.690508 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.555045 0 0.83182 -0.589318 0 0.807901 -0.612564 -0.135209 0.77877 -0.640606 0 0.76787 -0.653403 0.0277546 0.756501 -0.319837 0 0.947473 -0.353393 -0.0927285 0.930868 -0.387399 0.084208 0.918058 -0.422844 0 0.906203 -0.452854 0 0.891585 -0.490101 -0.0932221 0.866666 -0.474349 -0.166187 0.864508 -0.530172 0.0490227 0.846472 0.0747145 0.0457576 0.996155 0.027604 0 0.999619 0.0189218 -0.0245921 0.999519 -0.00276435 0 0.999996 -0.0591225 0 0.998251 -0.0730634 0.0885519 0.993388 -0.132484 -0.0219272 0.990943 -0.146637 0 0.98919 -0.209432 0 0.977823 -0.198097 -0.0267575 0.979817 -0.280871 0.017074 0.959594 -0.26985 0 0.962902 -0.319837 0 0.947473 0.242086 0 0.970255 0.211755 0.053722 0.975845 0.169935 -0.00533918 0.985441 0.0925434 0.00818032 0.995675 -0.996051 0 -0.0887864 -0.996051 0 -0.0887864 -0.969238 0 -0.246126 -0.969238 0 -0.246126 -0.917734 0 -0.397196 -0.917734 0 -0.397196 -0.842851 0 -0.538147 -0.842851 0 -0.538147 -0.746497 0 -0.665389 -0.746497 0 -0.665389 -0.631126 0 -0.775681 -0.631126 0 -0.775681 -0.499677 0 -0.866212 -0.499677 0 -0.866212 -0.355499 0 -0.934677 -0.355499 0 -0.934677 -0.832093 0 0.554636 -0.817923 0.0269731 0.574696 -0.783532 -0.0018832 0.621349 -0.744453 0.00276301 0.667669 -0.714471 0.0343449 0.698822 -0.686872 -0.00308958 0.726772 -0.641591 0.000892344 0.767047 -0.589289 0.0191243 0.807696 -0.585551 0.0125134 0.810539 -0.525598 -0.000486796 0.850733 -0.447662 0.00439686 0.894192 -0.472485 0.0509826 0.879863 -0.263951 -0.00176778 0.964534 -0.293455 0.0319017 0.95544 -0.342574 0.00128212 0.93949 -0.398856 -0.00137296 0.917013 -0.20504 0.000222955 0.978754 -0.140253 0.00927551 0.990072 -0.131425 0.0214091 0.991095 -0.0633106 -0.00034323 0.997994 0.0343148 0.00179434 0.999409 -0.00273725 0.0632241 0.997996 0.221105 0 0.97525 0.199063 0.0275906 0.979598 0.139945 0.00024618 0.990159 0.0797122 -0.000417532 0.996818 -0.115148 0.195075 0.974006 -0.977414 0.195086 0.0812563 -0.316171 0.830868 0.457925 -0.512676 0.830866 -0.216391 0.0417668 0.980697 0.19102 0.0153673 0.980697 0.19493 -0.0113187 0.980697 0.195205 -0.0377938 0.980697 0.191846 -0.0635648 0.980697 0.184913 -0.19398 0.980697 -0.0246138 -0.0673884 0.980697 -0.183554 -0.144264 0.985196 0.0926077 -0.310441 0.932377 0.185202 -0.586311 0.758126 0.285456 -0.629309 0.734897 0.25278 -0.404781 0.896354 0.180837 -0.728495 0.582466 0.360594 -0.744294 0.555441 0.370826 -0.896448 0.210521 0.389952 -0.585122 0.742531 0.326005 -0.384935 0.916102 0.112174 -0.861858 0.420564 0.283419 -0.836085 0.420382 0.352479 -0.797746 0.594127 0.103024 -0.828643 0.555567 0.0685237 -0.584452 0.809955 0.0488756 -0.815739 0.571242 0.0908478 -0.831503 0.548477 0.0881834 -0.438557 0.896355 0.064922 -0.894544 0.420396 0.151847 -0.879184 0.420579 0.22394 -0.556382 0.830915 0.00426097 -0.195373 0.980729 -0.000696849 -0.174559 0.984646 0.00065064 -0.352663 0.935749 0.00147181 -0.180144 0.980697 -0.0760353 -0.180145 0.980697 -0.0760357 -0.168113 0.980697 -0.0998573 -0.111097 0.980697 0.160907 -0.111097 0.980697 0.160907 -0.131972 0.980697 0.14428 -0.803497 0.554676 -0.216163 -0.537366 0.830866 -0.144566 -0.537366 0.830866 -0.144566 -0.188819 0.980697 -0.0507975 -0.18882 0.980697 -0.0507976 -0.375119 0.554672 0.742714 -0.250872 0.830867 0.496712 -0.250871 0.830869 0.49671 -0.088152 0.980697 0.174536 -0.0881519 0.980697 0.174536 -0.486863 0.55468 -0.674756 -0.73767 0.195043 -0.646375 -0.676901 0.194649 -0.709871 -0.574211 0.554672 -0.60218 -0.486866 0.554673 -0.674759 -0.325606 0.830867 -0.451266 -0.114412 0.980697 -0.158567 -0.134938 0.980697 -0.141511 -0.384018 0.830869 -0.402723 -0.435279 0.830869 -0.346682 -0.650855 0.554681 -0.51838 -0.715379 0.55468 -0.424927 -0.134938 0.980697 -0.141511 -0.152951 0.980697 -0.121819 -0.435283 0.830866 -0.346685 -0.478436 0.830866 -0.284185 -0.71538 0.554678 -0.424927 -0.766578 0.554679 -0.323559 -0.903673 0.194657 -0.381424 -0.931522 0.195079 -0.306937 -0.561587 0.554681 0.613962 -0.486411 0.195062 0.851678 -0.557304 0.194652 0.80717 -0.472755 0.55468 0.684713 -0.561587 0.554681 0.613962 -0.375579 0.830869 0.410606 -0.0673884 0.980697 -0.183554 -0.191782 0.830866 -0.52238 -0.191781 0.830868 -0.522378 -0.286762 0.554679 -0.781089 -0.286764 0.554672 -0.781093 -0.338047 0.194651 -0.92078 -0.338046 0.194658 -0.920778 -0.0917547 0.980697 -0.172668 -0.261126 0.830867 -0.4914 -0.261127 0.830866 -0.4914 -0.390449 0.554679 -0.734765 -0.39045 0.554678 -0.734766 -0.463755 -0.152642 -0.872715 -0.426641 0.195005 -0.883148 -0.6769 0.194653 -0.709871 -0.620363 0.195084 -0.759666 -0.58462 0.0415983 -0.81024 -0.567112 0.19475 -0.800285 -0.48592 0.194947 -0.851984 -0.0917543 0.980697 -0.172668 -0.114411 0.980697 -0.158566 -0.325604 0.830869 -0.451263 -0.384019 0.830868 -0.402724 -0.574208 0.554678 -0.602177 -0.650856 0.554678 -0.518381 -0.77756 -0.10897 -0.619295 -0.903674 0.194652 -0.381424 -0.867789 0.195062 -0.457049 -0.857642 -0.0702304 -0.509429 -0.834612 0.194846 -0.515227 -0.780086 0.194886 -0.594547 -0.15295 0.980697 -0.121819 -0.168113 0.980697 -0.0998573 -0.478432 0.830869 -0.284183 -0.512672 0.830869 -0.21639 -0.766579 0.554677 -0.323559 -0.803496 0.554678 -0.216163 -0.965472 -0.0199768 -0.259739 -0.950351 0.1948 -0.242664 -0.977378 0.195027 -0.0818308 -0.193978 0.980697 -0.0246136 -0.552042 0.830869 -0.070048 -0.552046 0.830866 -0.0700483 -0.825447 0.554677 -0.10474 -0.825448 0.554676 -0.10474 -0.982781 -0.136349 -0.124703 -0.969537 0.194918 -0.148341 -0.530333 0.847772 0.00550349 -0.832023 0.554674 0.00863426 -0.832021 0.554678 0.008634 -0.98082 0.19465 0.0101781 -0.98082 0.194651 0.0101781 -0.982786 0.10816 0.149777 -0.970298 0.194654 0.143638 -0.950459 0.194982 0.242096 -0.948001 -0.158037 0.276258 -0.931722 0.194984 0.306392 -0.897253 0.194708 0.396264 -0.907106 0.113709 0.405252 -0.868053 0.195088 0.456535 -0.164923 0.98072 0.104829 -0.47103 0.830943 0.296083 -0.439393 0.855652 0.273486 -0.70641 0.554675 0.439683 -0.706409 0.554677 0.439682 -0.832743 0.194649 0.518315 -0.832743 0.194652 0.518314 -0.150389 0.980697 0.124966 -0.427992 0.830869 0.355641 -0.427993 0.830867 0.355642 -0.639957 0.554681 0.531774 -0.63996 0.554675 0.531777 -0.761937 -0.136353 0.633134 -0.780413 0.195025 0.594071 -0.557304 0.194648 0.80717 -0.620809 0.195071 0.759304 -0.674798 -0.0199841 0.737732 -0.671217 0.194801 0.715207 -0.738069 0.194919 0.645957 -0.150389 0.980697 0.124966 -0.131972 0.980697 0.144281 -0.37558 0.830867 0.410608 -0.316171 0.830867 0.457925 -0.472754 0.554682 0.684712 -0.375116 0.554682 0.742708 -0.449714 -0.0702317 0.890407 -0.427174 0.194851 0.882925 -0.274955 0.195049 0.941465 -0.0635649 0.980697 0.184913 -0.1809 0.830866 0.526248 -0.180899 0.830869 0.526244 -0.270491 0.55468 0.78687 -0.270492 0.554672 0.786875 -0.323148 -0.108965 0.940054 -0.338573 0.19489 0.920536 -0.0377938 0.980697 0.191846 -0.107558 0.830868 0.545976 -0.107558 0.830866 0.545979 -0.160826 0.554679 0.816374 -0.160826 0.55468 0.816373 -0.189588 0.194645 0.962377 -0.189589 0.194654 0.962375 -0.0113187 0.980697 0.195206 -0.0322119 0.830868 0.555537 -0.0322119 0.830868 0.555537 -0.0481652 0.554675 0.830672 -0.0481653 0.55468 0.830669 -0.0567793 0.194649 0.979228 -0.0493529 0.0191414 0.998598 0.114579 0.195005 0.974087 0.0153671 0.980697 0.194928 0.0437335 0.830868 0.554749 0.0437335 0.830868 0.554749 0.0653926 0.554682 0.829489 0.0653934 0.554675 0.829494 0.0776705 -0.152644 0.985224 0.0478381 0.194948 0.979646 0.0417672 0.980697 0.191022 0.118865 0.830868 0.543627 0.118865 0.830868 0.543627 0.177734 0.554672 0.812865 0.177732 0.554682 0.812858 0.209518 0.194658 0.958233 0.209519 0.194651 0.958234 0.180463 0.980718 0.0749972 0.170271 0.980719 0.0959107 0.157667 0.980719 0.115465 0.14283 0.980718 0.133384 0.125967 0.980718 0.149412 0.107319 0.980718 0.163322 0.187135 0.831017 0.523824 0.0657461 0.980718 0.184035 0.0657459 0.980719 0.184034 0.370995 0.554887 0.744623 0.248057 0.831017 0.497874 0.248058 0.831016 0.497875 0.0871496 0.980719 0.174917 0.0871498 0.980718 0.174918 0.180462 0.980719 0.074997 0.409013 0.896557 0.169979 0.514984 0.830925 0.210608 0.27988 0.554889 0.783432 0.170271 0.980719 0.0959108 0.484651 0.831016 0.272995 0.484651 0.831016 0.272995 0.724843 0.554889 0.408291 0.724845 0.554885 0.408292 0.562769 0.792838 0.233877 0.733091 0.608079 0.30466 0.769493 0.554799 0.316352 0.828494 0.441644 0.344309 0.905748 0.194762 0.376415 0.329982 0.19476 0.923678 0.329982 0.194756 0.923678 0.40219 0.195052 0.894538 0.454733 0.194938 0.869032 0.445909 0.0132315 0.894981 0.370996 0.554884 0.744624 0.279881 0.554884 0.783435 0.187136 0.831016 0.523825 0.570715 0.195056 0.797645 0.107318 0.980718 0.163322 0.305464 0.831016 0.464869 0.305465 0.831016 0.46487 0.456854 0.554886 0.69526 0.456853 0.554887 0.69526 0.549103 0.0132387 0.83565 0.522239 0.194938 0.83022 0.125967 0.980718 0.149412 0.358541 0.831018 0.425274 0.358542 0.831017 0.425275 0.536238 0.554884 0.636044 0.536237 0.554886 0.636043 0.63223 0.19476 0.749902 0.63223 0.19476 0.749902 0.142829 0.980718 0.133384 0.406538 0.831017 0.379654 0.406538 0.831018 0.379653 0.608021 0.554886 0.567813 0.608022 0.554884 0.567814 0.716864 0.194761 0.669458 0.716864 0.19476 0.669458 0.157668 0.980718 0.115466 0.448775 0.831016 0.328654 0.448773 0.831017 0.328653 0.671189 0.554885 0.491536 0.671188 0.554887 0.491535 0.806718 0.0132354 0.590788 0.767665 0.195056 0.610445 0.905751 0.194748 0.376415 0.872983 0.195044 0.447054 0.871208 0.013237 0.490736 0.844843 0.194947 0.498232 0.802658 0.194947 0.563681 -0.608839 0.707127 0.359565 -0.581356 0.703685 0.408477 -0.606622 0.673957 0.421654 -0.579025 0.706038 0.407726 -0.506377 0.705885 0.495286 -0.506377 0.705885 0.495286 -0.417486 0.705885 0.572217 -0.417485 0.705885 0.572217 -0.317094 0.705885 0.633386 -0.317093 0.705886 0.633386 -0.207968 0.705886 0.677108 -0.207968 0.705885 0.677108 -0.0931132 0.705885 0.70218 -0.0931138 0.705883 0.702182 0.0243062 0.705883 0.707911 0.0243064 0.705885 0.70791 0.141056 0.705885 0.69414 0.141056 0.705884 0.694141 0.00416205 0.707114 0.707088 0.0530373 0.705084 0.707137 0.0515926 0.68064 0.730799 0.0531972 0.706275 0.705936 0.150133 0.706244 0.691867 0.150133 0.706242 0.691869 0.372433 0.0228473 0.927778 0.578183 0 0.815907 0.546239 0.0257036 0.837235 0.495425 0 0.868651 0.434992 0 0.900434 0.632515 0 0.774548 0.690081 0.00734479 0.723695 0.699193 0.0183587 0.714697 0.850921 0 0.525294 0.825028 0.0269277 0.564449 0.795335 0 0.60617 0.752115 0 0.659032 0.884784 0 0.466002 0.921173 0.0163163 0.38881 0.919559 0.0122382 0.392762 0.949771 0 0.312946 0.968912 0 0.247404 0.978243 0.0265196 0.205761 0.99994 0.00346869 -0.0103765 0.999723 0.0208067 0.010963 0.996513 0 0.0834317 0.988497 0 0.151242 0.996563 0 -0.0828407 0.988586 0 -0.150661 0.982571 0.0244794 -0.184269 0.914761 0 -0.403996 0.927742 0.0244792 -0.372418 0.949954 0 -0.312389 0.969058 0 -0.246833 0.885059 0 -0.465479 0.848977 0.00346898 -0.528419 0.83733 0.0208071 -0.546301 0.684326 0 -0.729176 0.714567 0.0265197 -0.699065 0.752503 0 -0.658589 0.795692 0 -0.605702 0.632971 0 -0.774176 0.568133 0.0116277 -0.822854 0.564586 0.0155021 -0.825229 0.495937 0 -0.868358 0.435521 0 -0.900178 0.392648 0.0269275 -0.919294 0.19328 0.00734483 -0.981116 0.205799 0.0183587 -0.978422 0.28034 0 -0.959901 0.345192 0 -0.938532 0.117407 0 -0.993084 0.049362 0 -0.998781 0.0109618 0.0257037 -0.99961 -0.0487739 0 -0.99881 -0.116822 0 -0.993153 -0.184276 0.0228471 -0.982609 -0.213605 0 -0.97692 -0.344639 0 -0.938735 -0.372433 0.0228473 -0.927778 -0.578182 0 -0.815908 -0.546239 0.0257035 -0.837235 -0.495425 0 -0.86865 -0.434992 0 -0.900434 -0.632515 0 -0.774548 -0.690082 0.00734482 -0.723694 -0.699193 0.0183586 -0.714697 -0.752115 0 -0.659032 -0.795335 0 -0.60617 -0.825028 0.0269276 -0.564449 -0.921234 0.0116274 -0.388836 -0.919517 0.0155022 -0.392744 -0.884784 0 -0.466 -0.85092 0 -0.525294 -0.94977 0 -0.312949 -0.968912 0 -0.247404 -0.978243 0.0265198 -0.205761 -0.99994 0.00346905 0.0103765 -0.999723 0.0208071 -0.010963 -0.996513 0 -0.0834329 -0.988497 0 -0.151242 -0.996562 0 0.0828481 -0.988586 0 0.150661 -0.982571 0.0244794 0.184269 -0.914761 0 0.403996 -0.927742 0.0244796 0.372418 -0.949955 0 0.312388 -0.969058 0 0.246833 -0.885059 0 0.465479 -0.848977 0.00346896 0.528419 -0.83733 0.0208072 0.546301 -0.795692 0 0.605702 -0.752502 0 0.658589 -0.714567 0.0265194 0.699065 -0.568096 0.0163159 0.8228 -0.564612 0.0122379 0.825266 -0.632969 0 0.774177 -0.684326 0 0.729176 -0.495937 0 0.868358 -0.435521 0 0.900178 -0.392648 0.0269275 0.919294 -0.19328 0.00734523 0.981116 -0.205799 0.0183587 0.978422 -0.28034 0 0.959901 -0.345192 0 0.938532 -0.117403 0 0.993084 -0.049362 0 0.998781 -0.0109618 0.0257037 0.99961 0.0487739 0 0.99881 0.116822 0 0.993153 0.184276 0.0228471 0.982609 0.213605 0 0.97692 0.344639 0 0.938735 -0.731314 0 -0.682041 -0.710761 -0.00267606 -0.703429 -0.446147 0.00223654 -0.894957 -0.419399 0 -0.907802 0.324791 0.258394 0.909804 0.840459 0.191023 0.507089 0.782882 0.273647 0.55876 0.685967 0.258712 0.680087 0.530826 0.254959 0.80822 0.757991 0.432144 0.48857 0.673826 0.597766 0.434321 0.545048 0.704719 0.454196 0.476368 0.29424 0.828551 0.357456 0.696908 0.621727 0.357456 0.696908 0.621727 0.132493 0.964023 0.230446 0.132485 0.964024 0.230447 0.168557 0.979686 0.108647 0.144274 0.964872 0.219562 0.380379 0.891741 0.245175 0.520884 0.784831 0.335738 -0.431404 0.254956 -0.865383 -0.4314 0.254959 -0.865384 -0.317998 0.701398 -0.637901 -0.318003 0.701397 -0.6379 -0.449697 0.788592 -0.419399 -0.431783 0.707067 -0.560017 -0.583627 0.602593 -0.544299 -0.70715 0.254955 -0.659498 -0.707146 0.254958 -0.659501 -0.192138 0.964869 -0.179193 -0.192143 0.964869 -0.17919 -0.117217 0.964869 -0.235133 -0.11721 0.96487 -0.235135 0.0744638 0.701397 0.708871 -0.178504 0.701397 0.690057 -0.178503 0.701397 0.690058 -0.0315063 0.706952 0.70656 0.0968733 0.690489 0.716827 0.0773924 0.701662 0.708295 -0.169792 0.701662 0.691984 -0.169791 0.701662 0.691984 0.0150082 0.705763 0.708289 0.164451 0.535054 0.828657 -0.479207 0.699677 0.529917 -0.479207 0.699677 0.529917 -0.229953 0.699677 0.676442 -0.229953 0.69968 0.676439 0.0569591 0.699681 0.712182 0.0569602 0.699678 0.712184 0.0468931 0.69859 0.713983 -0.258987 0.698592 0.667004 -0.258987 0.698591 0.667005 -0.076653 0.706768 0.70328 0.0870378 0.603818 0.792356 0.0777961 0.701697 0.708215 0.0777957 0.701698 0.708215 -0.0423352 -0.698068 -0.714779 -0.0423351 -0.698068 -0.714779 0.271987 -0.698071 -0.66236 0.271988 -0.69807 -0.66236 0.532437 -0.698072 -0.478755 0.532444 -0.698065 -0.478758 0.687441 -0.698064 -0.200328 0.687432 -0.698073 -0.200328 0.706273 -0.698073 0.117777 0.706285 -0.698061 0.117783 0.585236 -0.698062 0.412563 0.585235 -0.698065 0.41256 0.348274 -0.698066 0.625627 0.348274 -0.698067 0.625626 0.518723 0 0.854943 0.486171 -0.0302279 0.873341 0.838017 0.0259938 0.545025 0.817327 0 0.576175 0.950851 0 0.309649 0.985783 0.0347819 0.164387 0.995913 0 0.0903214 0.985353 0 -0.170526 0.95933 0.0391437 -0.27956 0.922706 0 -0.385504 0.791488 0 -0.611185 0.743149 0.0347865 -0.668222 0.635636 0 -0.771989 0.414178 0 -0.910196 0.379766 0.0217177 -0.924828 -0.0217505 -0.0259922 -0.999425 -0.0591248 0 -0.998251 -0.0156492 0.694741 -0.71909 -0.0156496 0.69474 -0.719091 0.345991 0.694742 -0.630575 0.376227 0.418166 -0.826795 0.450094 0.706112 -0.546646 0.562804 0.703121 -0.434595 0.749513 0.481069 -0.454756 0.654507 0.704873 -0.273451 0.698944 0.704873 -0.12096 0.876479 0.481062 -0.0190727 0.373097 0.69474 0.614927 0.3731 0.694735 0.61493 0.597969 0.700847 0.388904 0.745589 0.526057 0.409099 0.673298 0.706112 0.219263 0.708165 0.70312 0.064225 -0.0156491 -0.694739 -0.719091 -0.0156497 -0.694742 -0.719089 0.34599 -0.694743 -0.630573 0.345989 -0.694745 -0.630572 0.614923 -0.694745 -0.373095 0.614923 -0.694745 -0.373095 0.719085 -0.694746 -0.0156489 0.719089 -0.694742 -0.0156477 0.630574 -0.694743 0.345988 0.630583 -0.694731 0.345996 0.3731 -0.694735 0.614931 0.373098 -0.694739 0.614927 0.518722 0 0.854943 0.518722 0 0.854943 0.876702 0 0.481035 0.876702 0 0.481035 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854943 0 -0.518723 0.854943 0 -0.518723 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.373097 0.694739 0.614928 0.3731 0.694735 0.614931 0.630585 0.694731 0.345994 0.630573 0.694743 0.345991 0.719089 0.694742 -0.015649 0.719085 0.694746 -0.0156477 0.614923 0.694745 -0.373095 0.614923 0.694745 -0.373095 0.345989 0.694745 -0.630572 0.34599 0.694743 -0.630574 -0.015649 0.694742 -0.719089 -0.0156498 0.69474 -0.719091 -0.0423345 -0.698066 -0.71478 -0.042335 -0.698068 -0.714778 0.271986 -0.698072 -0.662359 0.271987 -0.69807 -0.66236 0.532437 -0.698073 -0.478754 0.532441 -0.698069 -0.478755 0.687439 -0.698066 -0.200328 0.687433 -0.698072 -0.200328 0.706273 -0.698074 0.117777 0.706285 -0.698061 0.117783 0.585238 -0.698061 0.412564 0.585237 -0.698062 0.412562 0.348276 -0.698062 0.625631 0.348276 -0.698066 0.625626 0.518722 0 0.854943 0.486172 -0.0302273 0.87334 0.838017 0.0259941 0.545025 0.817326 0 0.576175 0.950851 0 0.309649 0.985783 0.0347819 0.164387 0.995913 0 0.0903212 0.985353 0 -0.170526 0.95933 0.0391438 -0.27956 0.922706 0 -0.385505 0.791488 0 -0.611185 0.743149 0.034786 -0.668221 0.635639 0 -0.771987 0.414177 0 -0.910197 0.379765 0.0217178 -0.924828 -0.0217498 -0.0259918 -0.999426 -0.0591236 0 -0.998251 -0.0156498 0.69474 -0.719091 -0.015649 0.694742 -0.719089 0.34599 0.694743 -0.630574 0.376226 0.418164 -0.826796 0.450094 0.706115 -0.546642 0.562802 0.703123 -0.434594 0.749512 0.481071 -0.454755 0.654507 0.704872 -0.273452 0.698944 0.704873 -0.12096 0.876479 0.481062 -0.0190727 0.373097 0.694739 0.614928 0.373103 0.694732 0.614933 0.597971 0.700845 0.388905 0.745591 0.526053 0.4091 0.673299 0.70611 0.219263 0.708165 0.70312 0.0642248 -0.0156489 -0.694746 -0.719085 -0.0156477 -0.694742 -0.719089 0.345991 -0.694743 -0.630573 0.345992 -0.694742 -0.630574 0.614927 -0.694739 -0.373099 0.614927 -0.694739 -0.373099 0.719091 -0.694739 -0.0156491 0.719089 -0.694742 -0.0156497 0.630573 -0.694743 0.34599 0.630572 -0.694745 0.345989 0.373095 -0.694745 0.614923 0.373095 -0.694745 0.614923 0.518723 0 0.854943 0.518723 0 0.854943 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.373095 0.694745 0.614923 0.373095 0.694745 0.614923 0.630572 0.694745 0.345989 0.630574 0.694743 0.34599 0.719089 0.694742 -0.015649 0.719091 0.69474 -0.0156498 0.614927 0.694739 -0.373099 0.614927 0.694739 -0.373099 0.345992 0.694742 -0.630574 0.345991 0.694743 -0.630573 -0.015649 0.694742 -0.719089 -0.0156477 0.694746 -0.719085 0.12984 0.705354 0.696862 0.0328561 0.548033 0.835811 -0.0426673 0.703371 0.709541 -0.198755 0.705987 0.679764 -0.358495 0.564438 0.743567 -0.675616 0.696374 -0.242089 -0.675617 0.696372 -0.242089 -0.710206 0.69637 0.103323 -0.710203 0.696374 0.103321 -0.599086 0.701017 0.386874 -0.651303 0.589435 0.477881 -0.484035 0.706479 0.51633 -0.359115 0.702269 0.614699 -0.706329 0.696761 0.124992 -0.706329 0.696762 0.124991 -0.56889 0.696763 0.436906 -0.56889 0.696762 0.436906 -0.302997 0.696762 0.650166 -0.302997 0.696761 0.650167 -0.0130258 0.701456 0.712593 0.0352581 0.58976 0.806809 0.155574 0.706427 0.690476 -0.703563 0.697861 -0.13412 -0.703563 0.697862 -0.13412 -0.691123 0.697863 0.187981 -0.691123 0.697863 0.187981 -0.538699 0.697864 0.472006 -0.538699 0.697863 0.472007 -0.277164 0.697864 0.660429 -0.277164 0.697862 0.660431 0.0405107 0.697861 0.715087 0.0405101 0.697862 0.715086 -0.54531 0.697376 -0.465084 -0.545311 0.697375 -0.465085 -0.69606 0.697374 -0.170791 -0.696061 0.697374 -0.170791 -0.698653 0.697374 0.159856 -0.698652 0.697374 0.159856 -0.552537 0.697375 0.456477 -0.552536 0.697376 0.456476 -0.288814 0.697375 0.655938 -0.288814 0.697375 0.655938 0.0363812 0.697375 0.715783 0.0363809 0.697375 0.715782 -0.0156491 -0.694739 -0.719091 -0.0156497 -0.694742 -0.719089 0.34599 -0.694743 -0.630573 0.345994 -0.694738 -0.630577 0.614933 -0.694733 -0.373101 0.614921 -0.694744 -0.373098 0.719085 -0.694746 -0.0156489 0.719089 -0.694742 -0.0156478 0.630576 -0.69474 0.345993 0.630574 -0.694742 0.345991 0.373099 -0.694739 0.614927 0.373099 -0.694739 0.614927 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854943 0 -0.518723 0.854943 0 -0.518723 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.373099 0.694739 0.614927 0.373099 0.694739 0.614927 0.630574 0.694742 0.345992 0.630576 0.69474 0.345992 0.719089 0.694742 -0.015649 0.719085 0.694746 -0.0156477 0.614923 0.694745 -0.373095 0.614931 0.694734 -0.373103 0.345992 0.694738 -0.630577 0.345991 0.694743 -0.630573 -0.015649 0.694742 -0.719089 -0.0156498 0.69474 -0.719091 -0.0156492 -0.694733 -0.719098 -0.0156516 -0.694742 -0.719089 0.345994 -0.694739 -0.630575 0.34599 -0.694745 -0.630572 0.614922 -0.694745 -0.373096 0.614928 -0.694739 -0.373098 0.719091 -0.694739 -0.015649 0.719089 -0.694742 -0.0156496 0.630573 -0.694743 0.34599 0.630576 -0.694739 0.345993 0.373098 -0.694742 0.614924 0.373101 -0.694733 0.614933 0.518726 0 0.854941 0.518726 0 0.854941 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.021757 0.999763 0 -0.021757 0.854941 0 -0.518725 0.854941 0 -0.518725 0.48104 0 -0.876699 0.48104 0 -0.876699 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.373103 0.694733 0.614932 0.373096 0.694741 0.614926 0.630577 0.694739 0.345992 0.630573 0.694743 0.345991 0.719089 0.694742 -0.0156489 0.719091 0.69474 -0.0156497 0.614927 0.694739 -0.373099 0.614923 0.694745 -0.373095 0.345991 0.694745 -0.630571 0.345992 0.69474 -0.630576 -0.015649 0.694742 -0.719089 -0.0156518 0.694733 -0.719097 -0.0156492 -0.694732 -0.719098 -0.0156516 -0.694742 -0.719089 0.345991 -0.694743 -0.630573 0.345992 -0.694742 -0.630574 0.614927 -0.694739 -0.373099 0.614927 -0.694739 -0.373099 0.719091 -0.694739 -0.015649 0.719089 -0.694742 -0.0156496 0.630573 -0.694743 0.345992 0.630571 -0.694745 0.34599 0.373097 -0.694745 0.61492 0.373101 -0.694733 0.614933 0.518727 0 0.85494 0.518727 0 0.85494 0.876699 0 0.48104 0.876699 0 0.48104 0.999763 0 -0.021757 0.999763 0 -0.021757 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.373104 0.694732 0.614931 0.373095 0.694745 0.614923 0.630571 0.694745 0.345991 0.630573 0.694743 0.345991 0.719089 0.694742 -0.0156489 0.719091 0.69474 -0.0156497 0.614927 0.694739 -0.373099 0.614927 0.694739 -0.373099 0.345992 0.694742 -0.630574 0.345991 0.694743 -0.630573 -0.015649 0.694742 -0.719089 -0.0156518 0.694733 -0.719098 -0.0156492 -0.694733 -0.719098 -0.0156516 -0.694742 -0.719089 0.345992 -0.694742 -0.630574 0.345991 -0.694743 -0.630573 0.614924 -0.694742 -0.373098 0.614926 -0.69474 -0.373098 0.71909 -0.694741 -0.0156495 0.719091 -0.69474 -0.0156492 0.630574 -0.694741 0.345993 0.630573 -0.694742 0.345992 0.373098 -0.694743 0.614922 0.373101 -0.694734 0.614932 0.518727 0 0.85494 0.518727 0 0.85494 0.876699 0 0.48104 0.876699 0 0.48104 0.999763 0 -0.0217577 0.999763 0 -0.0217577 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.373103 0.694733 0.614931 0.373096 0.694743 0.614924 0.630573 0.694742 0.345992 0.630574 0.694741 0.345992 0.719091 0.69474 -0.0156495 0.71909 0.694741 -0.0156492 0.614926 0.69474 -0.373099 0.614924 0.694742 -0.373097 0.345991 0.694744 -0.630572 0.345992 0.694742 -0.630574 -0.015649 0.694742 -0.719089 -0.0156518 0.694733 -0.719098 -0.441893 0 -0.897068 -0.441893 0 -0.897068 -0.964172 0 -0.265276 -0.945897 -0.0515841 -0.320341 -0.779553 0.0370376 -0.62524 -0.742474 0 -0.669875 -0.5438 0 -0.839215 -0.467785 0.0445725 -0.882718 -0.362744 0 -0.931889 -0.722722 0 -0.691139 -0.687016 -0.0379536 -0.72565 -0.442245 0.027238 -0.896481 -0.397335 0 -0.917674 -0.80607 0 -0.59182 -0.802236 -0.00611366 -0.596976 -0.480763 0.00593514 -0.876831 -0.475128 0 -0.879916 -0.0423345 -0.698066 -0.71478 -0.0423352 -0.698069 -0.714778 0.27199 -0.698066 -0.662363 0.271987 -0.698071 -0.66236 0.532436 -0.698073 -0.478755 0.532444 -0.698065 -0.478758 0.687441 -0.698064 -0.200328 0.687444 -0.698062 -0.200328 0.706287 -0.698059 0.117784 0.706273 -0.698074 0.117777 0.58523 -0.698072 0.412554 0.585234 -0.698066 0.412559 0.348274 -0.698068 0.625626 0.348274 -0.698066 0.625627 0.486394 0 0.87374 0.486394 0 0.87374 0.81733 0 0.57617 0.81733 0 0.57617 0.986378 0 0.164493 0.986378 0 0.164493 0.960066 0 -0.279774 0.960066 0 -0.279774 0.743598 0 -0.668627 0.743598 0 -0.668627 0.379857 0 -0.925045 0.379857 0 -0.925045 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.348274 0.698066 0.625627 0.348273 0.698067 0.625626 0.585236 0.698066 0.412558 0.585229 0.698072 0.412556 0.706272 0.698074 0.117782 0.706287 0.698059 0.117779 0.687444 0.698061 -0.200329 0.687442 0.698064 -0.200327 0.532442 0.698064 -0.47876 0.532438 0.698073 -0.478753 0.271989 0.698071 -0.662359 0.271989 0.698066 -0.662363 -0.0423343 0.698069 -0.714778 -0.0423354 0.698067 -0.71478 -0.0156489 -0.694746 -0.719085 -0.0156477 -0.694742 -0.719089 0.345991 -0.694743 -0.630573 0.345992 -0.694742 -0.630574 0.614927 -0.694739 -0.373099 0.614927 -0.694739 -0.373099 0.719091 -0.694739 -0.0156491 0.719089 -0.694742 -0.0156497 0.630573 -0.694743 0.34599 0.630577 -0.694738 0.345994 0.373101 -0.694733 0.614933 0.373098 -0.694744 0.614921 0.486395 0 0.873739 0.518548 0.0259903 0.854654 0.695951 0 0.718089 0.8383 0 0.545209 0.875875 0.0433757 0.480585 0.950846 0 0.309664 0.995913 0 0.0903162 0.998407 0.052077 -0.0217276 0.985354 0 -0.170521 0.922703 0 -0.385511 0.853781 0.0520766 -0.518021 0.791488 0 -0.611185 0.635644 0 -0.771983 0.480586 0.0433763 -0.875874 -0.0591236 0 -0.998251 -0.0217497 0.0259918 -0.999426 0.201252 0 -0.97954 0.414177 0 -0.910197 -0.0423327 0.698073 -0.714774 -0.0423343 0.698069 -0.714778 0.142357 0.706855 -0.692886 0.296453 0.625232 -0.721942 0.295433 0.700856 -0.649246 0.450101 0.70611 -0.546643 0.610189 0.571519 -0.548667 0.562801 0.703125 -0.434593 0.654505 0.704873 -0.273456 0.800722 0.551723 -0.233338 0.698952 0.704866 -0.120957 0.70628 0.698067 0.11778 0.876372 0.475032 0.0794754 0.673299 0.706107 0.219275 0.585237 0.698062 0.412561 0.348273 0.698072 0.625621 0.348276 0.698068 0.625624 0.492289 0.706853 0.507948 0.668101 0.604017 0.434516 0.348273 -0.698072 0.625621 0.348273 -0.698069 0.625624 0.492287 -0.706855 0.507947 0.637878 -0.625227 0.449669 0.597966 -0.700851 0.388902 0.673299 -0.706107 0.219275 0.809417 -0.571511 0.134979 0.708167 -0.703118 0.0642215 0.698951 -0.704866 -0.12096 0.80072 -0.551725 -0.233339 0.654508 -0.704869 -0.273455 0.532438 -0.698072 -0.478754 0.696477 -0.475047 -0.53782 0.450099 -0.706112 -0.546641 0.271987 -0.698069 -0.662361 -0.042334 -0.698074 -0.714773 -0.0423328 -0.698069 -0.714778 0.14236 -0.706855 -0.692885 0.330083 -0.604029 -0.725393 0.486395 0 0.873739 0.486395 0 0.873739 0.695951 0 0.718089 0.695951 0 0.718089 0.8383 0 0.545209 0.8383 0 0.545209 0.950846 0 0.309664 0.950846 0 0.309664 0.995913 0 0.0903162 0.995913 0 0.0903162 0.985354 0 -0.170524 0.985354 0 -0.170524 0.922704 0 -0.385508 0.922704 0 -0.385508 0.791487 0 -0.611186 0.791487 0 -0.611186 0.635644 0 -0.771983 0.635644 0 -0.771983 0.414177 0 -0.910197 0.414177 0 -0.910197 0.201256 0 -0.979539 0.201256 0 -0.979539 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 -0.0423325 0.698074 -0.714774 -0.0423343 0.698069 -0.714778 0.14236 0.706855 -0.692885 0.296452 0.625235 -0.72194 0.295433 0.700857 -0.649245 0.450099 0.706112 -0.546641 0.610188 0.571522 -0.548665 0.562802 0.703122 -0.434596 0.654508 0.704869 -0.273455 0.80072 0.551725 -0.233339 0.698951 0.704866 -0.12096 0.70628 0.698067 0.11778 0.876372 0.475032 0.0794754 0.673299 0.706107 0.219275 0.585237 0.698062 0.41256 0.348272 0.698072 0.625622 0.348274 0.698069 0.625623 0.492287 0.706855 0.507947 0.668099 0.604021 0.434514 0.348273 -0.698073 0.62562 0.348273 -0.698069 0.625624 0.492285 -0.706855 0.507948 0.637878 -0.625226 0.44967 0.597966 -0.700851 0.388902 0.673299 -0.706108 0.219272 0.809414 -0.571515 0.134978 0.708166 -0.703119 0.0642218 0.69895 -0.704867 -0.120959 0.80072 -0.551724 -0.233339 0.654508 -0.70487 -0.273456 0.532438 -0.698072 -0.478754 0.696479 -0.475044 -0.53782 0.450101 -0.70611 -0.546642 0.271987 -0.698068 -0.662362 -0.042334 -0.698073 -0.714774 -0.0423329 -0.698069 -0.714778 0.142358 -0.706855 -0.692886 0.330085 -0.604025 -0.725395 0.486395 0 0.873739 0.518547 -0.0259901 0.854654 0.695949 0 0.718092 0.8383 0 0.545209 0.875875 -0.0433763 0.480584 0.950847 0 0.309661 0.995913 0 0.0903169 0.998407 -0.0520776 -0.0217282 0.985354 0 -0.170523 0.922704 0 -0.38551 0.853781 -0.0520772 -0.518021 0.791487 0 -0.611186 0.635645 0 -0.771982 0.480587 -0.0433764 -0.875874 0.414177 0 -0.910196 0.201253 0 -0.979539 -0.0217497 -0.0259918 -0.999426 -0.0591236 0 -0.998251 0.373094 0.694746 0.614922 0.373104 0.694732 0.614932 0.63058 0.694735 0.345994 0.630574 0.694742 0.345992 0.71909 0.694741 -0.0156494 0.71909 0.69474 -0.0156495 0.614926 0.694739 -0.373099 0.614924 0.694742 -0.373097 0.345991 0.694744 -0.630572 0.345992 0.694742 -0.630574 -0.015649 0.694742 -0.719089 -0.0156477 0.694746 -0.719085 -0.924158 0 0.382012 -0.91801 0.0161877 0.396226 -0.996 -0.0172104 -0.087677 -0.998554 0.034401 -0.0413053 -0.881965 -0.0261854 -0.470588 -0.842556 0.0392515 -0.537176 -0.724148 0 -0.689644 -0.552529 0 -0.833494 -0.499288 0.0481594 -0.865097 -0.338677 0 -0.940903 -0.596853 0.0211386 0.802072 -0.612809 0 0.790231 -0.88581 -0.0177523 0.463708 -0.911431 0.0354828 0.409919 -0.976306 0 0.216394 -0.99998 0 -0.00627851 -0.996676 0.0480759 -0.0657667 -0.968775 0 -0.247942 -0.889316 0 -0.457293 -0.848809 0.0572136 -0.525595 -0.752322 0 -0.658795 -0.586861 0 -0.809688 -0.502661 0.0628988 -0.862192 -0.373623 0 -0.927581 -0.727938 0 0.685643 -0.72617 0.00254578 0.68751 -0.954874 -0.00257099 0.296999 -0.952547 0.00514514 0.304347 -0.988398 -0.00520281 -0.151799 -0.99025 0.00780268 -0.139084 -0.82172 -0.00788816 -0.569837 -0.831818 0.0105176 -0.554949 -0.508662 -0.00961024 -0.860913 -0.488604 0.012011 -0.872423 -0.292113 0 -0.956384 -0.293145 0 0.956068 -0.320629 -0.0294434 0.946747 -0.69091 0.0258284 0.72248 -0.711823 0 0.702359 -0.869351 0 0.494195 -0.941097 0.0443323 0.335217 -0.959904 0 0.280329 -0.999751 0 0.0223296 -0.990872 0.0554685 -0.122865 -0.977939 0 -0.208892 -0.890552 0 -0.454882 -0.830085 0.0592284 -0.554482 -0.761604 0 -0.648043 -0.567925 0 -0.82308 -0.492931 0.0556145 -0.868289 -0.362743 0 -0.931889 -0.0156495 -0.694741 -0.71909 -0.0156494 -0.694741 -0.71909 0.345992 -0.694742 -0.630574 0.345992 -0.694742 -0.630573 0.614922 -0.694744 -0.373098 0.614932 -0.694734 -0.3731 0.719098 -0.694733 -0.0156492 0.719089 -0.694742 -0.0156516 0.630574 -0.694742 0.345992 0.630573 -0.694743 0.345991 0.373098 -0.694742 0.614924 0.373098 -0.69474 0.614926 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.85494 0 -0.518726 0.85494 0 -0.518726 0.48104 0 -0.876699 0.48104 0 -0.876699 -0.0217577 0 -0.999763 -0.0217577 0 -0.999763 0.373099 0.69474 0.614926 0.373097 0.694742 0.614924 0.630572 0.694744 0.345991 0.630574 0.694742 0.345992 0.719089 0.694742 -0.015649 0.719098 0.694733 -0.0156518 0.614931 0.694733 -0.373103 0.614924 0.694743 -0.373096 0.345992 0.694742 -0.630573 0.345992 0.694742 -0.630574 -0.0156495 0.694741 -0.71909 -0.0156494 0.694741 -0.71909 -0.015649 -0.694739 -0.719091 -0.0156496 -0.694742 -0.719089 0.345991 -0.694743 -0.630573 0.345992 -0.694742 -0.630574 0.614922 -0.694744 -0.373098 0.614933 -0.694733 -0.373101 0.719098 -0.694732 -0.0156492 0.719089 -0.694742 -0.0156516 0.630573 -0.694743 0.345991 0.630574 -0.694742 0.345992 0.373099 -0.694739 0.614927 0.373099 -0.694739 0.614927 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.85494 0 -0.518726 0.85494 0 -0.518726 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.021757 0 -0.999763 -0.021757 0 -0.999763 0.373099 0.694739 0.614927 0.373099 0.694739 0.614927 0.630574 0.694742 0.345992 0.630573 0.694743 0.345991 0.719089 0.694742 -0.015649 0.719098 0.694733 -0.0156518 0.614931 0.694733 -0.373103 0.614924 0.694743 -0.373096 0.345992 0.694742 -0.630574 0.345991 0.694743 -0.630573 -0.0156489 0.694742 -0.719089 -0.0156497 0.69474 -0.719091 -0.015649 -0.694739 -0.719091 -0.0156496 -0.694742 -0.719089 0.345992 -0.694743 -0.630573 0.34599 -0.694745 -0.630571 0.61492 -0.694745 -0.373097 0.614933 -0.694733 -0.373101 0.719098 -0.694732 -0.0156492 0.719089 -0.694742 -0.0156516 0.630573 -0.694743 0.345991 0.630572 -0.694745 0.34599 0.373096 -0.694745 0.614922 0.373098 -0.694739 0.614928 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.85494 0 -0.518727 0.85494 0 -0.518727 0.48104 0 -0.876699 0.48104 0 -0.876699 -0.021757 0 -0.999763 -0.021757 0 -0.999763 0.373099 0.694739 0.614927 0.373095 0.694745 0.614923 0.630571 0.694745 0.34599 0.630573 0.694743 0.345991 0.719089 0.694742 -0.015649 0.719098 0.694733 -0.0156518 0.614931 0.694732 -0.373104 0.614923 0.694745 -0.373095 0.345991 0.694745 -0.630571 0.345991 0.694743 -0.630573 -0.0156489 0.694742 -0.719089 -0.0156497 0.69474 -0.719091 -0.0156492 -0.694733 -0.719098 -0.0156516 -0.694742 -0.719089 0.345994 -0.694739 -0.630575 0.34599 -0.694745 -0.630572 0.614922 -0.694745 -0.373096 0.614928 -0.694739 -0.373098 0.719091 -0.694739 -0.015649 0.719089 -0.694742 -0.0156497 0.630579 -0.694736 0.345994 0.630577 -0.694739 0.345992 0.373096 -0.694741 0.614926 0.373095 -0.694745 0.614923 0.518722 0 0.854943 0.518722 0 0.854943 0.8767 0 0.481038 0.8767 0 0.481038 0.999763 0 -0.021757 0.999763 0 -0.021757 0.854941 0 -0.518725 0.854941 0 -0.518725 0.48104 0 -0.876699 0.48104 0 -0.876699 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.373094 0.694745 0.614923 0.373096 0.694741 0.614926 0.630577 0.694739 0.345992 0.630579 0.694736 0.345993 0.719089 0.694742 -0.0156489 0.719091 0.69474 -0.0156498 0.614927 0.694739 -0.373099 0.614923 0.694745 -0.373095 0.345991 0.694745 -0.630571 0.345992 0.69474 -0.630576 -0.015649 0.694742 -0.719089 -0.0156518 0.694733 -0.719097 0.216381 0 0.976309 0.23763 -0.00153769 0.971355 0.258767 0 0.96594 -0.111131 0.000231544 0.993806 -0.347984 -0.0268114 0.937117 -0.306859 0.0134116 0.951661 -0.704379 -0.012619 0.709712 -0.694038 0 0.719938 0.0110001 -0.000740509 0.999939 0.0994062 -0.0288728 0.994628 0.191432 0 0.981506 -0.705437 -0.705978 -0.0628815 -0.353888 -0.705979 -0.61348 -0.353888 -0.705978 -0.613481 -0.251776 -0.705978 -0.66197 -0.251777 -0.705976 -0.661971 -0.484603 -0.818184 -0.309411 -0.571839 -0.707041 -0.416044 -0.528696 -0.705976 -0.471253 -0.528696 -0.705976 -0.471253 -0.446986 -0.705976 -0.549365 -0.388375 -0.794358 -0.467077 -0.40727 -0.707089 -0.578063 -0.705438 -0.705976 -0.0628818 -0.68906 -0.706433 -0.161706 -0.561257 -0.815277 -0.142524 -0.673372 -0.707048 -0.215993 -0.649972 -0.705976 -0.281308 -0.649973 -0.705974 -0.281309 -0.603719 -0.706452 -0.369389 -0.227362 -0.706769 -0.669913 -0.227363 -0.706769 -0.669913 -0.697585 -0.698978 -0.157496 -0.69758 -0.698983 -0.157497 -0.57012 -0.698982 -0.431726 -0.570125 -0.698977 -0.431727 -0.34072 -0.698977 -0.628761 -0.340721 -0.698977 -0.628761 -0.615907 -0.735248 -0.282966 -0.722183 -0.575131 -0.384287 -0.628743 -0.696452 -0.345885 -0.707236 -0.706944 0.00682287 -0.915022 -0.402236 -0.0306664 -0.70598 -0.706781 -0.0453182 -0.702709 -0.707107 -0.0787407 -0.669633 -0.735002 -0.106598 -0.862956 -0.478675 -0.161796 -0.688319 -0.70701 -0.162338 -0.682729 -0.707091 -0.184127 -0.595081 -0.777649 -0.202832 -0.667997 -0.706358 -0.234174 -0.647036 -0.707078 -0.28528 -0.603459 -0.707109 -0.368557 -0.596461 -0.707056 -0.379876 -0.492763 -0.798567 -0.345652 -0.633238 -0.613135 -0.472309 -0.547413 -0.707082 -0.447631 -0.532166 -0.707023 -0.465744 -0.402164 -0.828 -0.390742 -0.496679 -0.706629 -0.50397 -0.45562 -0.706988 -0.540905 -0.332923 -0.83618 -0.43585 -0.414695 -0.706701 -0.573238 -0.36859 -0.706941 -0.603636 -0.261408 -0.841341 -0.473087 -0.224264 -0.706837 -0.670886 -0.187677 -0.843838 -0.502707 -0.273065 -0.706894 -0.652485 -0.323186 -0.706774 -0.629302 -0.107989 -0.704061 -0.701881 -0.107988 -0.704062 -0.70188 0.0773509 -0.704062 -0.705913 0.0773509 -0.704062 -0.705913 0.257419 -0.704062 -0.66184 0.257419 -0.704062 -0.66184 0.419945 -0.704062 -0.572664 0.419945 -0.704062 -0.572664 0.553852 -0.704062 -0.444461 0.553852 -0.704061 -0.444461 0.650015 -0.704061 -0.285969 0.650014 -0.704062 -0.285969 0.70188 -0.704062 -0.107989 0.70188 -0.704062 -0.107989 0.705913 -0.704062 0.077351 0.705915 -0.704061 0.0773513 0.661841 -0.704061 0.257419 0.66184 -0.704062 0.257419 0.572663 -0.704062 0.419945 0.572663 -0.704062 0.419945 0.444461 -0.704062 0.553852 0.444461 -0.704062 0.553851 0.285969 -0.704062 0.650014 0.285969 -0.704061 0.650015 0.195034 4.58943e-07 0.980796 0.19504 -4.33424e-06 0.980795 0.195034 0 0.980796 0.195034 -9.86975e-08 0.980796 0.195034 0 0.980796 0.195034 -2.16674e-07 0.980796 0.195034 7.10992e-08 0.980797 0.195032 1.07101e-06 0.980797 0.195041 -3.02498e-06 0.980795 0.195034 -2.61735e-07 0.980797 0.195033 7.94909e-08 0.980797 0.362385 0 0.932029 0.362384 -1.20177e-06 0.932029 0.362384 -2.16675e-06 0.932029 0.362385 0 0.932029 0.362385 0 0.932029 0.362385 5.4014e-06 0.932029 0.362382 -4.73418e-06 0.93203 0.362387 3.5957e-06 0.932028 0.362388 5.94791e-06 0.932027 0.362382 -3.75264e-06 0.93203 0.195034 3.94224e-06 0.980796 0.195034 0 0.980796 -0.999518 0 0.0310579 0.362384 0 0.932029 0.362384 1.87726e-07 0.932029 0.859731 0 -0.510747 -0.362385 0 -0.932029 -0.362385 8.98717e-07 -0.932029 -0.362385 1.84173e-06 -0.932028 -0.362384 0 -0.932029 -0.362385 9.61916e-08 -0.932029 -0.362385 -3.98927e-06 -0.932029 -0.362376 -1.20586e-05 -0.932032 -0.362387 6.47231e-06 -0.932028 -0.36238 -7.78632e-06 -0.93203 -0.362385 -1.34024e-07 -0.932028 -0.195034 4.58943e-07 -0.980796 -0.195021 9.17647e-06 -0.980799 -0.195034 0 -0.980796 -0.195034 -9.86975e-08 -0.980796 -0.195034 0 -0.980796 -0.195034 -3.25012e-07 -0.980796 -0.195034 0 -0.980797 -0.195035 -5.18239e-07 -0.980796 -0.195041 -3.02498e-06 -0.980795 -0.195035 -8.70268e-07 -0.980796 -0.195035 -4.23951e-07 -0.980796 -0.859735 0 0.510741 -0.362385 0 -0.932029 -0.362385 -5.63177e-07 -0.932029 0.999518 0 -0.0310579 -0.195034 3.56679e-06 -0.980796 -0.195034 0 -0.980796 -0.404425 0 -0.914571 -0.404425 0 -0.914571 -0.710943 0 -0.70325 -0.755513 -0.00637048 -0.655103 -0.846109 -9.32553e-05 -0.53301 -0.925273 0.000153466 -0.379303 -0.962611 -0.00728864 -0.270791 -0.98615 0 -0.165856 -0.742549 0 0.669792 -0.666448 -0.00728817 0.745516 -0.221851 -0.00904014 0.975039 -0.429355 0 0.903136 -0.578441 0 0.815724 -0.285324 0 0.958431 0.1502 0 0.988656 0.1502 0 0.988656 0.742549 0 -0.669792 0.666446 -0.0072883 -0.745518 0.22185 -0.00904026 -0.975039 0.429359 0 -0.903134 0.578439 0 -0.815726 0.285324 0 -0.958431 -0.1502 0 -0.988656 -0.1502 0 -0.988656 0.404424 0 0.914572 0.404424 0 0.914572 0.710945 0 0.703248 0.755514 -0.00637039 0.655102 0.846104 -9.35905e-05 0.533017 0.925275 0.000153118 0.379298 0.962611 -0.00728864 0.270791 0.98615 0 0.165856 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.437048 -0.347863 -0.829446 0.377565 -0.0777305 -0.922715 0.724793 -0.000288246 -0.688966 0.712663 -0.0274499 -0.700969 0.737043 0.00741649 -0.675805 0.517131 -0.00478012 -0.855893 0.592405 -0.00586072 -0.805619 0.842893 -0.1244 -0.523503 0.180102 -0.463039 -0.867846 0.741833 -0.259666 -0.618269 0.535234 -0.401005 -0.743451 0.972282 -0.0666675 -0.224105 0.930392 -0.112181 -0.348979 0.922723 -0.0541848 -0.381637 0.859021 -0.0959689 -0.502864 0.861371 -0.0308704 -0.507038 0.819943 -0.251754 -0.514113 0.757173 -0.278912 -0.590675 0.747566 -0.207046 -0.631091 0.686718 -0.229146 -0.689863 0.665645 -0.128865 -0.735058 0.901548 0.0219654 -0.432122 0.693611 -0.0725468 -0.716687 0.15348 -0.120247 -0.980808 0.306146 -0.0914541 -0.947582 0.0813357 -0.135355 -0.987453 0.118426 -0.289075 -0.949953 -0.147548 -0.379646 -0.91329 0.415915 -0.243658 -0.876154 0.347974 -0.261883 -0.900184 0.553606 -0.187889 -0.811307 0.519 -0.0449347 -0.853592 0.743114 0.0104666 -0.669083 0.651756 -0.00054277 -0.758429 0.965929 0 0.258806 0.965929 0 0.258806 0.707116 0 0.707098 0.707116 0 0.707098 0.258831 0 0.965923 0.258831 0 0.965923 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.258831 0 -0.965923 -0.258831 0 -0.965923 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965922 0 -0.258832 0.965922 0 -0.258832 0.973825 -0.22381 -0.0396677 0.950262 -0.309315 -0.0364178 0.966172 -0.253415 -0.0478814 0.995324 -0.0815237 -0.0517994 0.992493 -0.109305 -0.0548572 0.0619815 -0.00581713 -0.99806 0.100782 0 -0.994909 0.424663 0 -0.905352 0.424663 0 -0.905352 0.7813 0 -0.624156 0.7813 0 -0.624156 0.976784 0 -0.214225 0.976784 0 -0.214225 0.9708 0 0.239891 0.9708 0 0.239891 0.764579 0 0.64453 0.764579 0 0.64453 0.466321 0 0.884616 0.466321 0 0.884616 0.998473 0 -0.055239 0.998491 0 -0.0549208 0.998475 2.766e-05 -0.0552014 0.99848 -2.08845e-07 -0.0551185 0.99848 0 -0.0551185 0.999618 0 -0.0276497 0.999618 0 -0.0276497 0.984232 0.00644196 0.176763 0.988739 0 0.149648 0.829068 0 0.559147 0.829068 0 0.559147 0.509234 0 0.860628 0.509234 0 0.860628 0.976128 0.210006 0.0554232 0.97499 0.215448 0.0545597 0.789671 0.612682 0.0322669 0.787939 0.614935 0.0317267 0.423879 0.905718 0.000928104 0.423998 0.905662 0.00095456 -0.0148926 0.999459 -0.0293305 -0.0114509 0.999523 -0.0286941 0.975443 0.210374 -0.0652237 0.975154 0.211687 -0.0652975 0.786664 0.612619 -0.0765352 0.783849 0.616203 -0.0766434 0.421138 0.904127 -0.0720934 0.413597 0.90761 -0.0719917 -0.0128083 0.998501 -0.0532221 -0.0243154 0.998313 -0.0527328 0.859185 0.200225 0.470863 -0.246892 0.944367 0.217292 -0.0240875 0.999485 0.0212264 -0.243436 0.967786 0.0642575 -0.159769 0.980159 0.117309 0.0262738 0.993314 0.112415 -0.151056 0.987275 0.0496953 0.0521568 0.996497 0.0653688 0.93537 0.217513 0.278875 0.847027 0.440204 0.297937 0.954788 0.211482 0.208938 0.725464 0.224314 0.65068 0.617166 0.127577 0.776422 0.602707 0.180878 0.777192 0.533396 0.328562 0.779446 0.42976 0.518424 0.739285 0.394868 0.904987 0.158362 0.392778 0.905928 0.158175 0.34011 0.894123 0.291324 0.317605 0.904303 0.285241 0.237883 0.881362 0.408184 0.210287 0.894039 0.395568 0.3024 0.679879 0.668071 0.456177 0.470051 0.755615 0.600696 0.521303 0.606142 0.709223 0.296928 0.639403 0.871274 0.101879 0.480106 0.751119 0.612929 0.24523 0.748111 0.616575 0.245287 0.676738 0.600484 0.425962 0.660888 0.619084 0.424219 0.559531 0.59056 0.581519 0.462415 0.699433 0.544946 0.325012 0.650373 0.686572 0.0988067 0.854036 0.510744 0.0809963 0.862743 0.499114 -0.134837 0.948643 0.286175 -0.166869 0.950336 0.26271 -0.0779646 0.987005 -0.140511 0.761857 0.323896 -0.56095 0.378125 0.902659 -0.205497 0.346143 0.891281 -0.292922 0.968072 0.20704 -0.141319 0.966793 -0.177085 -0.184264 0.82561 0.113229 -0.552764 0.811025 0.195976 -0.551209 0.87719 0.218259 -0.427668 0.880516 0.198876 -0.430279 0.931924 0.217295 -0.290347 0.410673 0.904264 -0.116851 0.236964 0.961999 -0.135673 -0.0260158 0.996148 -0.0837357 0.53046 0.691644 -0.490144 0.282548 0.885481 -0.368903 0.158307 0.952269 -0.261004 -0.0616546 0.98714 -0.14749 -0.0378086 0.995882 -0.0824039 0.778147 0.611072 -0.14518 0.773583 0.617256 -0.143405 0.745431 0.605002 -0.27983 0.738442 0.615148 -0.276217 0.690717 0.598042 -0.406517 0.68183 0.612027 -0.400663 0.622015 0.59225 -0.512189 0.66403 0.522072 -0.535262 0.808758 0.13794 0.571737 0.561194 0.101681 0.821415 0.983229 0.180855 -0.0234968 -0.394993 0.909095 0.132386 -0.32432 0.937226 0.128158 0.988597 -0.0128815 -0.150033 0.99873 -0.0223867 0.0451283 0.988636 0.139471 0.0560947 0.926329 0.360901 0.108007 0.918078 0.381325 0.10828 0.768921 0.618818 0.160699 -0.259477 0.956965 0.129961 0.521756 0.848282 0.0904887 -0.0511424 0.975679 0.213157 0.241788 0.945381 0.218615 0.253635 0.942945 0.215693 0.54059 0.817827 0.197283 0.763749 0.640434 -0.0808155 0.776679 0.610229 0.156177 0.540245 0.818024 0.197413 0.709538 0.698735 -0.0912458 0.827858 0.554031 -0.0877511 0.914381 0.389391 -0.110828 0.926544 0.360367 -0.107943 0.983874 0.132221 -0.120459 -0.275064 0.915316 0.294171 -0.340211 0.902452 0.264265 -0.0213757 0.931383 0.363412 -0.0650608 0.935091 0.348384 0.267023 0.871473 0.41138 0.233701 0.884671 0.403412 0.515424 0.744555 0.424236 0.513938 0.745659 0.4241 0.912314 0.251885 0.322858 0.751683 0.566916 0.337015 0.888034 0.362203 0.283205 0.901291 0.330364 0.28024 0.966677 0.136284 0.216706 0.973381 0.0938302 0.209108 0.687418 0.0569283 0.724028 0.731551 -0.168123 0.660732 0.587616 0.248682 0.769977 0.546171 0.334136 0.768147 0.41908 0.514107 0.748375 -0.265622 0.925072 0.271451 -0.923027 0.358893 -0.138624 -0.599712 0.785914 0.150611 -0.632925 0.765127 0.118266 -0.604393 0.787118 0.123107 -0.0945096 0.994977 0.0330093 0.10827 0.99408 0.00908457 0.229824 0.973122 -0.014626 0.268549 0.963185 -0.0124992 0.527671 0.848196 -0.0461133 0.481148 0.875033 -0.0530413 0.618137 0.783787 -0.0598637 0.894541 0.0964931 0.436447 0.884293 -0.101821 0.455695 0.765332 0.267091 0.585602 0.727433 0.342006 0.594872 0.584788 0.531565 0.61275 0.470218 0.455009 0.756215 0.279289 0.671017 0.686829 0.933626 0.0836745 0.348339 0.924101 0.131472 0.358821 0.854106 0.308087 0.419029 0.838015 0.344872 0.42284 0.687969 0.55296 0.470037 0.627836 0.486718 0.607395 0.448162 0.666139 0.596162 0.592712 -0.805025 0.0250451 0.194899 0.79167 0.579028 0.0702078 0.858867 0.507364 -0.0517409 0.897795 0.437363 -0.295582 0.921614 0.251512 -0.269975 0.924028 0.270714 -0.084995 0.98504 -0.149904 0.451715 0.865217 0.217607 0.232083 0.961279 0.148597 0.356849 0.916594 0.180316 0.236857 0.891108 0.387073 0.235905 0.891599 0.386522 0.0772934 0.857804 0.508132 0.0691706 0.864303 0.498192 -0.108355 0.830331 0.546634 -0.11466 0.842172 0.526877 -0.295653 0.811018 0.504816 0.318599 0.893361 -0.31686 0.844781 0.501763 -0.185953 0.885092 -0.464824 -0.0234695 0.940064 0.332991 -0.0734613 -0.74275 0.0942123 0.662907 -0.409676 -0.664733 0.624736 -0.114662 -0.672674 0.731001 -0.39782 0.103497 0.911607 -0.600009 0.0708954 0.796846 0.17503 -0.580279 0.795387 -0.00743053 0.111606 0.993725 -0.212075 0.0773937 0.974184 0.46389 -0.576303 0.672816 0.310877 0.106403 0.944476 0.188991 0.0831507 0.978452 0.99207 0.10629 0.0670717 0.949746 0.102951 0.295609 0.894793 -0.34544 0.282872 0.770842 0.341056 0.538037 0.693617 -0.520905 0.497548 0.657799 0.195486 0.727383 0.502202 9.78773e-05 0.86475 -0.63128 0.427497 0.647095 -0.574036 0.592303 0.565385 -0.480054 0.77167 0.417222 -0.605396 0.505754 0.614581 -0.333512 0.549279 0.7662 -0.342776 0.424264 0.838155 -0.0207672 0.479264 0.877425 -0.0137154 0.437324 0.899199 0.302288 0.497717 0.812957 0.316162 0.459484 0.83001 0.587831 0.517879 0.621495 0.601471 0.490678 0.63045 0.787371 0.532609 0.310442 0.792674 0.52355 0.31235 0.846317 0.527038 -0.0773161 0.838488 0.539231 -0.0785315 0.945746 0.316879 -0.0717718 0.890027 0.313073 0.331417 0.884887 0.329015 0.329734 0.688779 0.284422 0.666849 0.676482 0.324361 0.661182 0.383913 0.261293 0.885628 0.370461 0.313046 0.874506 0.0255353 0.247145 0.968642 0.0170214 0.300648 0.953583 -0.336224 0.240454 0.910569 -0.337366 0.289347 0.895803 -0.650794 0.239097 0.720625 -0.646272 0.279238 0.710183 0.0742132 0.994423 -0.0749376 -0.141009 0.984091 -0.108084 0.204413 0.94086 -0.27018 0.417327 0.8426 -0.340386 0.484843 0.871342 -0.0754334 0.491981 0.867362 -0.0750813 0.257087 0.964066 -0.0669556 0.261843 0.962792 -0.0668526 -0.0834067 0.995325 -0.0487004 -0.0951897 0.99481 0.0359483 0.044129 0.993767 0.102374 -0.13018 0.988267 0.0798826 -0.0513445 0.982568 0.178672 -0.141385 0.982877 0.118166 -0.0117088 0.864226 0.502967 -0.167774 0.978335 0.121296 -0.231737 0.863946 0.447096 -0.195835 0.974718 0.107577 -0.296003 0.937155 0.184725 0.866612 0.12852 -0.482148 0.874886 -0.331822 -0.352802 0.819628 0.342166 -0.459492 0.84225 0.288433 -0.455435 0.717129 0.535873 -0.445608 0.743813 0.496541 -0.447424 0.581493 0.703184 -0.409143 0.598514 0.686764 -0.412476 0.684151 0.725008 -0.0793697 0.692465 0.717154 -0.0786286 0.643995 0.714287 0.27398 0.641651 0.716731 0.273096 0.476567 0.679971 0.557246 0.465699 0.694133 0.548911 0.229524 0.643564 0.730167 0.217557 0.667537 0.712084 -0.0539435 0.615637 0.786181 -0.0591803 0.644867 0.762 -0.333498 0.598076 0.728755 -0.293694 0.825827 0.481408 -0.462518 0.797867 0.386634 -0.276221 0.948739 0.153609 0.944368 0.043219 -0.326038 0.111602 0.42424 -0.898647 0.0124796 0.308279 -0.951214 0.253535 0.076041 -0.964333 -0.350737 0.490758 -0.797584 0.0578413 0.969494 -0.238194 0.120693 0.868171 -0.481364 0.0312537 0.749727 -0.661009 0.0709484 0.737695 -0.671396 -0.36393 0.910309 -0.197212 -0.328376 0.920815 -0.210403 -0.453194 0.877123 -0.158965 -0.443689 0.803768 -0.396354 -0.458315 0.800261 -0.38669 -0.477522 0.796086 -0.371779 -0.691371 0.722364 -0.0139891 -0.637091 0.769708 -0.0408027 -0.493954 0.738164 -0.459482 -0.454865 0.732062 -0.507132 -0.400754 0.678564 -0.615587 -0.459376 0.673644 -0.578945 -0.287796 0.527746 -0.79916 -0.31229 0.488262 -0.814908 -0.297084 0.167094 -0.940117 -0.132178 0.572563 -0.809136 -0.21747 0.627099 -0.747967 -0.284167 0.549461 -0.785711 -0.136665 0.409754 -0.9019 -0.227428 0.333605 -0.914869 -0.23078 0.338664 -0.912166 -0.294666 0.297778 -0.90802 -0.122182 0.127714 -0.984256 0.324019 0.00394658 -0.946042 0.363545 -0.0351533 -0.930913 0.80792 0.143583 -0.571533 0.548209 0.282264 -0.78727 0.883349 -0.0964722 -0.45868 0.657154 0.311878 -0.686208 0.428009 0.84842 -0.311436 -0.329226 0.914864 -0.233742 0.527301 0.728627 -0.437101 0.490958 0.753971 -0.436449 0.621247 0.647284 -0.441673 0.603795 0.662857 -0.442778 0.743121 0.509891 -0.433338 0.700987 0.55941 -0.442355 0.855617 0.326595 -0.401566 0.929917 0.108057 -0.351536 0.815765 0.395666 -0.421871 0.709169 0.253912 -0.657729 0.580396 0.401683 -0.708372 0.495982 0.483694 -0.721139 0.47675 0.498842 -0.723786 0.293386 0.627996 -0.720795 0.361604 0.590047 -0.721864 0.231967 0.663491 -0.711316 0.326637 0.7868 -0.523693 0.105377 0.874365 -0.47369 0.176571 0.947885 -0.26521 0.217342 0.939328 -0.265379 0.363537 -0.555427 0.747891 -0.327326 0.369481 -0.869679 -0.30746 0.232112 -0.922817 -0.276227 0.0678233 -0.958696 -0.271217 0.0347308 -0.961891 -0.20384 0.116818 -0.97201 -0.312857 0.414581 -0.854543 -0.112329 0.180968 -0.977053 0.0230396 0.294324 -0.955428 0.138005 0.195396 -0.970966 -0.138742 0.97315 -0.183655 0.494724 0.743568 -0.449838 -0.152237 0.910998 -0.383283 -0.230924 0.806273 -0.544608 -0.153143 0.799357 -0.581013 -0.230034 0.696954 -0.679219 -0.0118265 0.626958 -0.778963 -0.0742853 0.646637 -0.759172 0.200952 0.502239 -0.841056 -0.35513 0.691956 -0.628553 0.365721 0.306448 -0.878828 0.286027 0.3667 -0.885279 0.534032 0.146948 -0.832596 0.410848 0.258177 -0.874385 0.847487 -0.391832 -0.358096 0.498631 0.11933 -0.858561 -0.671798 0.42462 0.606948 -0.710934 0.0986976 0.696299 -0.372253 0.822602 0.429829 -0.122908 0.842671 0.524213 -0.701148 0.274252 0.658163 -0.706576 0.170354 0.686826 -0.540023 0.193329 0.819146 -0.538567 0.174208 0.824377 -0.342142 0.196166 0.918944 -0.339973 0.178754 0.92329 -0.125297 0.197548 0.972253 -0.12299 0.183228 0.975347 -0.216796 0.970549 0.105044 -0.267026 0.949501 0.164756 -0.259085 0.953556 0.153645 -0.505938 0.770248 0.388258 -0.119711 0.981597 0.148785 -0.120438 0.981099 0.151456 -0.136752 0.963674 0.229417 -0.253195 0.835809 0.48715 -0.614488 0.590224 0.523488 -0.63756 0.524086 0.56467 -0.494598 0.543599 0.67814 -0.496037 0.533652 0.684955 -0.324257 0.55279 0.767646 -0.324271 0.54342 0.774302 -0.135251 0.559949 0.817413 -0.1341 0.551781 0.823137 0.370262 0.0436253 -0.927902 -0.276478 0.0678168 -0.958624 -0.239087 -0.488816 -0.838985 -0.295995 0.167118 -0.940457 -0.293888 0.23239 -0.92716 -0.250892 0.158864 -0.95489 -0.182694 0.159196 -0.970196 -0.182641 0.168529 -0.968628 -0.0902502 0.168765 -0.981516 -0.090286 0.173259 -0.980729 0.00258524 0.173392 -0.98485 0.00252389 0.17597 -0.984392 0.0951995 0.176036 -0.97977 0.095145 0.177384 -0.979532 0.186969 0.177431 -0.966209 0.186918 0.178334 -0.966053 0.264877 0.178437 -0.947629 0.273393 -0.23866 -0.931825 0.309294 0.177702 -0.934216 0.353744 0.300862 -0.885634 0.364178 0.177494 -0.91426 0.360714 0.216555 -0.907188 0.367112 0.130523 -0.920974 -0.0510245 0.98752 0.149 -0.00393399 0.99004 0.14073 0.00168851 0.19306 0.981185 0.00169918 0.19362 0.981075 0.00490796 0.56483 0.825193 0.00494446 0.566481 0.82406 0.00740823 0.853994 0.52023 0.00746189 0.855787 0.517275 0.00846362 0.975584 0.219464 0.00952252 0.990656 0.13605 -0.00491371 0.192125 0.981358 -0.00492757 0.193031 0.98118 -0.0144178 0.562167 0.826898 -0.0144494 0.56472 0.825156 -0.0218414 0.850748 0.525119 -0.021856 0.853779 0.520177 -0.020244 0.791789 0.610459 -0.017201 0.9899 0.140718 -0.905927 0.0663442 -0.418205 -0.0747104 0.709258 -0.700979 0.0991744 0.626475 -0.773106 0.0600148 0.546348 -0.835406 0.277988 0.45997 -0.843297 0.366071 0.752528 -0.547443 0.131417 0.843029 -0.521566 0.195463 0.916812 -0.348209 -0.575537 0.0292041 -0.817254 -0.170484 0.757495 -0.630188 -0.250033 0.802701 -0.541437 -0.80351 0.235672 -0.546654 -0.336026 0.834204 -0.437253 -0.84797 0.274583 -0.453378 0.375747 0.301055 -0.876459 0.358292 0.637772 -0.681816 0.276001 0.214941 -0.936816 -0.33641 -0.912078 0.234396 0.339009 0.130343 -0.93171 -0.740819 0.465555 -0.484197 -0.8649 0.221224 -0.450564 -0.770094 0.155031 -0.618806 -0.600291 0.420398 -0.68038 -0.675794 6.22271e-05 -0.737091 -0.273147 0.520816 -0.80879 -0.429044 0.18489 -0.884159 -0.273184 0.115355 -0.95502 -0.409228 -0.583229 -0.701695 -0.0565165 0.139617 -0.988591 0.113969 0.0694216 -0.991056 0.0665369 0.948813 -0.308752 0.178264 0.945636 -0.272019 0.0789998 0.926512 -0.367879 0.122594 0.900909 -0.416333 0.322516 0.674333 -0.664274 0.233959 0.631927 -0.738872 0.287387 0.883955 -0.368826 0.244573 0.856302 -0.454897 0.176648 0.848629 -0.498623 -0.603077 0.635919 -0.481566 -0.66018 0.579025 -0.478427 -0.569765 0.516419 -0.639281 -0.544493 0.542101 -0.640042 -0.436917 0.481064 -0.760053 -0.412606 0.507116 -0.756696 -0.285709 0.444735 -0.848871 -0.266079 0.468008 -0.842716 -0.0423965 0.36378 -0.93052 -0.044349 0.360347 -0.931763 0.203991 0.257255 -0.944567 0.039967 -0.145613 -0.988534 0.360941 0.266129 -0.893811 0.305123 0.0435216 -0.951318 0.0806799 0.987429 0.135925 0.251987 0.499711 0.828729 0.251981 0.959381 0.12686 0.384026 0.838141 0.387353 0.664308 0.604683 0.439378 0.530868 0.785864 0.31717 0.214485 0.972746 0.0880971 0.273935 0.949553 0.152673 0.130444 0.987088 0.0929632 0.252055 0.849436 0.463603 0.103326 0.978814 0.176767 0.105264 0.8502 0.515829 0.136961 0.187537 0.972662 0.136053 0.198824 0.970546 0.388116 0.184398 0.902975 0.788677 0.194738 0.583152 0.791703 0.175081 0.58528 0.652993 0.193855 0.732135 0.56431 0.482518 0.669873 0.536683 0.100284 0.837804 0.358505 0.385191 0.850354 0.133274 0.558582 0.818672 0.13167 0.567873 0.812517 0.352172 0.555255 0.753437 0.349561 0.563559 0.74847 0.545485 0.546711 0.635258 0.541182 0.556575 0.630354 0.695025 0.537939 0.477034 0.738023 0.434884 0.515944 -0.263096 0.964508 0.022492 -0.508413 0.822164 0.256052 -0.324219 0.921292 0.214719 -0.262336 0.917985 0.297462 -0.363706 0.804923 0.468847 -0.205958 0.901879 0.37973 -0.914012 0.110849 0.39025 -0.798339 0.535447 0.275594 -0.642531 0.72676 0.242845 -0.4592 0.874505 0.156129 -0.605666 0.230371 0.761641 -0.605563 0.206996 0.768405 -0.724183 0.219226 0.653834 -0.693857 0.468565 0.546818 -0.826413 0.204159 0.524748 -0.902571 0.234766 0.360903 0.0417883 0.972517 -0.229051 -0.277879 0.923087 -0.265883 -0.388183 0.883031 -0.263761 -0.499028 0.821958 -0.27451 -0.665945 0.696763 -0.266531 -0.69217 0.670674 -0.266641 -0.808878 0.533231 -0.247752 -0.841015 0.483037 -0.243659 -0.914111 0.343064 -0.21612 -0.937923 0.277774 -0.207707 -0.974646 0.138278 -0.17591 -0.933128 0.298259 -0.20078 0.0641491 0.997256 0.0369577 0.073052 0.99701 0.0252 0.0679068 0.996182 -0.0548604 0.0690402 0.996059 -0.0556739 0.0500784 0.99242 -0.112222 -0.449081 0.628071 0.635494 -0.452867 0.614553 0.645938 -0.561479 0.625901 0.541285 -0.561607 0.625547 0.54156 -0.652129 0.630637 0.420743 -0.650647 0.633801 0.418275 -0.723347 0.631384 0.279505 -0.874639 0.3247 0.359968 -0.343489 0.91296 -0.220272 0.116543 0.982014 -0.148548 -0.276209 0.957985 -0.0772926 -0.294518 0.952704 -0.0749234 -0.496731 0.867441 -0.0283485 -0.516849 0.855705 -0.0252144 -0.689312 0.724108 0.0227235 -0.708936 0.704777 0.0264406 -0.837769 0.541329 0.0714567 -0.854293 0.514288 0.0754438 -0.934413 0.337399 0.114165 -0.945379 0.303863 0.118011 -0.981951 -0.0665329 0.177045 -0.981324 0.0940339 0.167811 0.017027 0.085793 0.996167 -0.317148 -0.0847515 0.944582 0.318376 0.888921 0.329326 -0.0293899 0.9919 -0.123574 -0.165117 0.977232 -0.133249 0.0345056 0.997733 -0.0577775 -0.3632 0.926171 0.101457 0.0569557 0.998351 -0.00712451 -0.237171 0.913464 0.330656 0.0630143 0.996578 0.0535022 0.0539328 0.984834 0.164903 0.0949712 0.992175 0.0810472 0.13197 0.959593 0.248525 0.133111 0.984098 0.117616 0.159806 0.85312 0.496636 0.161932 0.845321 0.509126 -0.0292008 0.868226 0.495309 -0.0304586 0.864438 0.501815 -0.212153 0.884778 0.414921 -0.211967 0.884969 0.414609 -0.360561 0.897154 0.255167 -0.356898 0.899472 0.252137 -0.441111 0.896625 0.0385359 -0.435784 0.899308 0.0365796 -0.436136 0.880075 -0.187759 -0.436216 0.880036 -0.187759 -0.127726 0.103168 0.986429 -0.280459 -0.549669 0.786897 -0.2089 0.304969 0.929169 0.427817 0.0768124 0.900596 0.334236 -0.53399 0.776621 0.588033 0.0967798 0.803026 0.180683 0.97816 0.102743 0.333144 0.840703 0.426887 0.341163 0.830509 0.440298 0.441896 0.5587 0.701842 0.449589 0.534532 0.715643 0.757431 0.197822 0.622225 0.752702 0.0718802 0.654426 0.749212 0.253436 0.611924 0.477693 0.290654 0.829054 0.476816 0.256853 0.840639 -0.913155 -0.357888 0.195098 -0.733437 0.652855 -0.189345 -0.972932 0.121666 -0.196473 -0.730271 -0.518713 0.444568 -0.889003 0.102446 0.446294 -0.970415 0.0989492 0.220235 -0.435383 0.168221 0.884389 -0.562506 -0.358909 0.74483 -0.544264 -0.515865 0.661559 -0.673796 0.0962933 0.732616 -0.787323 0.105874 0.607382 -0.834723 0.506233 -0.216717 -0.847316 0.484318 -0.217924 -0.846537 0.514793 0.13551 -0.853095 0.503579 0.13652 -0.721298 0.507847 0.470978 -0.720053 0.510088 0.470461 -0.482068 0.49015 0.726198 -0.475302 0.504389 0.720888 -0.174546 0.470521 0.864953 -0.167073 0.493085 0.853788 -0.216939 0.273961 0.936954 -0.540072 0.310504 0.782247 -0.546736 0.289221 0.785768 -0.799182 0.310585 0.51463 -0.800833 0.305484 0.515117 -0.939516 0.301064 0.16331 -0.934803 0.315775 0.162569 -0.935572 0.283443 -0.210631 -0.925676 0.314172 -0.210761 0.174249 0.984628 0.012042 0.2629 0.958687 0.108642 0.486673 0.819042 0.30384 0.516393 0.786309 0.339201 0.676933 0.526578 0.514273 0.64742 0.605254 0.463158 0.71042 0.436257 0.552253 0.203349 0.104907 0.97347 0.0115635 -0.594802 0.803789 0.145502 0.297775 0.943483 0.140078 0.26325 0.954504 0.163494 0.5703 0.805002 0.141012 0.457306 0.878058 0.162691 0.633162 0.756728 -0.115942 0.666438 0.736491 -0.121893 0.652563 0.747866 -0.384752 0.682018 0.621946 -0.389726 0.674884 0.626614 -0.600461 0.692325 0.400166 -0.600164 0.692665 0.400025 -0.71786 0.688772 0.101337 -0.710765 0.696246 0.100267 -0.711441 0.669244 -0.214392 -0.700737 0.680937 -0.21282 -0.309565 0.906843 0.286015 -0.318092 0.900739 0.295783 -0.382804 0.902111 0.19914 -0.13973 0.990162 0.00735276 -0.933666 0.209279 0.29064 -0.934304 0.20497 0.291657 -0.860593 0.209241 0.464326 -0.860531 0.209781 0.464197 -0.754648 0.207865 0.622333 -0.754 0.214915 0.620722 -0.617311 0.20455 0.759662 -0.615156 0.231433 0.753672 -0.00969993 0.999789 -0.0180929 -0.0326173 0.999416 -0.0101747 -0.423019 0.891825 0.160322 0.033419 0.998362 0.0464321 0.139681 0.987178 -0.0772529 0.0693413 0.996767 0.0405795 -0.223488 0.900229 0.373685 -0.220552 0.902878 0.369009 -0.766615 0.602118 0.223059 -0.766491 0.602308 0.222972 -0.701352 0.605994 0.375336 -0.699232 0.609692 0.373296 -0.603666 0.607817 0.515894 -0.599653 0.616077 0.51075 -0.474787 0.606502 0.637756 -0.46565 0.629236 0.622281 -0.801817 0.597372 0.0153462 -0.472631 0.880815 -0.0279962 -0.0450241 0.990543 -0.129608 -0.0501403 0.996671 -0.0642881 -0.0563424 0.996331 -0.0644228 -0.0290496 0.9918 -0.124452 -0.449511 0.868727 -0.207974 -0.463717 0.885544 -0.0279032 -0.810392 0.585689 0.0152619 -0.431176 0.879199 -0.202723 -0.69302 0.679574 -0.240631 -0.782178 0.574016 -0.242287 -0.826958 0.504167 -0.24891 -0.917585 0.31074 -0.247948 -0.975529 0.198685 0.0941628 -0.868043 0.495785 0.0264199 -0.97705 0.205882 -0.0546474 -0.953508 0.187138 -0.236223 -0.96514 0.116946 -0.234156 -0.957767 0.205901 0.200719 -0.957837 0.204556 0.201754 -0.0377071 0.998733 -0.0333331 -0.0436965 0.998469 -0.0339269 -0.447441 0.892233 0.0609753 -0.451469 0.890243 0.0603607 -0.785933 0.600512 0.147292 -0.787466 0.598611 0.146841 -0.957753 0.205229 0.201471 -0.957676 0.205243 0.201822 -0.0432715 0.998551 -0.0319865 -0.78855 0.596869 0.148108 -0.451135 0.890307 0.0618966 -0.454626 0.888467 0.0627794 -0.0489853 0.998325 -0.0307767 -0.957946 0.20462 0.20117 -0.953273 0.226787 0.199597 -0.787273 0.598646 0.147731 -0.878386 0.461788 -0.123243 -0.943559 0.328699 -0.0406512 -0.916626 0.331449 -0.22347 -0.846797 0.333147 -0.414665 -0.809917 0.316644 -0.493731 -0.833809 0.33441 -0.43924 -0.561008 0.202937 -0.80255 -0.6108 0.23481 -0.756167 -0.241215 0.0792913 -0.967227 -0.217887 0.0663799 -0.973714 -0.209598 0.118514 -0.970579 -0.127359 0.0583655 -0.990138 -0.779704 0.613076 -0.12728 -0.779733 0.613082 -0.127072 -0.688497 0.524356 -0.501022 -0.688453 0.524331 -0.501108 -0.478343 0.344193 -0.80791 -0.478181 0.34409 -0.80805 -0.270163 0.172912 -0.947161 -0.518399 0.60481 0.604539 -0.560673 0.642099 0.522833 -0.591626 0.621951 0.512988 -0.598952 0.677582 0.426778 -0.679365 0.639868 0.35921 -0.654993 0.690464 0.306991 -0.731338 0.66489 0.151875 -0.718728 0.680093 0.14458 -0.725824 0.685681 -0.0549637 -0.753419 0.654941 -0.0584104 -0.688802 0.691321 -0.218237 -0.732775 0.628638 -0.260491 -0.655064 0.67614 -0.337232 -0.675581 0.611094 -0.412498 -0.633294 0.643213 -0.430366 -0.624175 0.593661 -0.50791 -0.933568 0.130796 0.333682 -0.927905 -0.267927 0.259244 -0.67964 0.0563082 0.731382 -0.849009 0.157476 0.504366 -0.703718 -0.239451 0.668913 -0.731094 -0.0334983 0.681454 -0.571885 0.102533 0.813901 -0.10182 -0.525629 0.844599 -0.378184 0.0357304 0.925041 -0.216796 0.135026 0.966834 -0.0999472 -0.0201914 0.994788 -0.667986 0.21384 0.712788 -0.554502 0.258318 0.791075 -0.516055 0.127949 0.846945 -0.305334 0.2622 0.915436 -0.206097 0.122647 0.970815 -0.749978 -0.213238 -0.626149 -0.775563 -0.0668394 -0.627722 -0.747807 0.0484181 -0.662148 -0.640832 0.108943 -0.759912 -0.236866 -0.408362 -0.881553 -0.538115 0.319163 -0.780107 -0.192586 -0.00565983 -0.981264 -0.751607 0.202948 -0.627614 -0.649389 0.257552 -0.715515 -0.588127 0.133335 -0.797702 -0.428512 0.253183 -0.867338 -0.30644 0.136441 -0.942061 -0.979895 0.14302 0.139107 -0.987163 0.148613 -0.0585047 -0.941373 -0.261874 -0.212694 -0.958327 0.123978 -0.257371 -0.887081 0.162341 -0.432126 -0.659177 0.739773 -0.134988 -0.479674 0.780296 0.401312 -0.599909 0.791406 -0.117413 -0.533107 0.84466 -0.0484406 -0.521925 0.852429 -0.0309743 -0.561749 0.826668 -0.0325336 -0.467532 0.883737 0.0205762 -0.556465 0.827964 0.0694442 -0.46391 0.883293 0.0676781 -0.522207 0.839106 0.152318 -0.506925 0.85018 0.142198 -0.507392 0.849237 0.146113 -0.553174 0.799479 0.234161 -0.592725 0.799936 0.0936979 -0.6035 0.753844 0.259822 -0.351613 0.353833 0.866701 -0.446769 0.436985 0.780668 -0.567647 0.358714 0.741013 -0.60523 0.451151 0.655866 -0.770562 0.374549 0.515701 -0.76354 0.445533 0.467447 -0.890937 0.403822 0.207749 -0.883258 0.423591 0.201062 -0.894326 0.432366 -0.115065 -0.912528 0.391839 -0.117279 -0.803483 0.452141 -0.387277 -0.829411 0.361686 -0.425747 -0.670267 0.457988 -0.583943 -0.665083 0.346965 -0.661272 -0.530554 0.448641 -0.71919 -0.480804 0.341323 -0.807667 -0.00876428 0.0241539 0.99967 -0.106308 0.0643964 0.992246 -0.186806 0.0886399 0.97839 -0.456283 0.186183 0.870139 -0.408934 0.174878 0.895651 -0.678434 0.256296 0.688505 -0.739205 0.284794 0.610302 -0.829779 0.310806 0.463536 -0.902259 0.334278 0.272373 -0.909978 0.334121 0.245566 -0.739134 0.619181 0.265133 -0.739325 0.619414 0.264055 -0.601689 0.521708 0.604807 -0.602268 0.522299 0.603719 -0.365955 0.339976 0.86631 -0.366617 0.340627 0.865774 -0.154302 0.170973 0.973118 -0.0936008 0.117063 0.988704 -0.0142915 0.0575612 0.99824 -0.825699 0.53774 -0.170462 -0.956754 0.290833 -0.00615249 -0.945357 0.288321 -0.152223 -0.939974 0.283369 -0.190135 -0.872962 0.258725 -0.413519 -0.820238 0.246597 -0.516139 -0.775952 0.227297 -0.588417 -0.561986 0.157768 -0.811961 -0.622655 0.185957 -0.76008 -0.298283 0.076758 -0.951386 -0.222879 0.0421078 -0.973936 -0.22105 0.0915565 -0.970955 -0.133287 0.045445 -0.990035 -0.89443 0.41928 -0.155565 -0.762278 0.42067 -0.491903 -0.749292 0.412316 -0.518225 -0.74582 0.410883 -0.524336 -0.515545 0.269165 -0.813488 -0.513005 0.268014 -0.815472 -0.287761 0.13467 -0.948187 -0.609711 0.551236 0.569554 -0.659312 0.580123 0.478295 -0.626597 0.607936 0.487638 -0.642899 0.665604 0.379015 -0.690543 0.637364 0.341933 -0.664979 0.696223 0.270326 -0.739612 0.659831 0.132658 -0.715707 0.688895 0.114837 -0.729011 0.679071 -0.0860533 -0.743379 0.663289 -0.086226 -0.676623 0.689033 -0.259642 -0.719248 0.628641 -0.295793 -0.648322 0.667228 -0.366723 -0.668327 0.589961 -0.453085 -0.675249 0.584264 -0.450195 -0.657103 0.532574 -0.533461 -0.830617 -0.41789 0.368025 -0.663596 0.0453723 0.746714 -0.491295 -0.476095 0.729357 -0.354408 -0.658401 0.664005 -0.833853 0.0904775 0.544522 -0.927394 0.0469673 0.371126 -0.559606 0.102105 0.822445 0.0172631 -0.51817 0.855104 -0.3537 0.0240603 0.93505 -0.227215 0.125954 0.965665 -0.0776881 -0.0188662 0.996799 -0.949511 0.172362 0.262146 -0.777106 0.25188 0.576769 -0.77291 0.139038 0.619094 -0.553691 0.263491 0.789936 -0.490529 0.117213 0.863506 -0.339425 0.242759 0.908768 -0.210697 0.111998 0.971114 -0.154853 0.0180857 -0.987772 0.152483 -0.284004 -0.946621 -0.777031 -0.11912 -0.618088 -0.746454 -0.268336 -0.608935 -0.745435 0.0502427 -0.664682 -0.657648 0.0939572 -0.747443 -0.0139583 -0.625664 -0.779968 -0.467916 0.0151075 -0.883644 -0.372778 0.0904503 -0.923501 -0.743052 0.202613 -0.637825 -0.638286 0.250829 -0.727788 -0.57475 0.119568 -0.809547 -0.439076 0.229049 -0.868763 -0.301088 0.117338 -0.94635 -0.976813 0.150499 0.15227 -0.98931 0.141888 -0.0336572 -0.94137 -0.295574 -0.162664 -0.962668 0.129603 -0.237641 -0.892787 0.155954 -0.422622 -0.716853 0.674527 -0.176452 -0.654969 0.739838 0.153807 -0.617511 0.756781 -0.214388 -0.487477 0.873135 -0.00126369 -0.524233 0.845573 -0.100928 -0.537022 0.836738 -0.107132 -0.46535 0.884486 -0.0336819 -0.571294 0.820437 -0.0224982 -0.461923 0.886835 0.0122442 -0.555914 0.827095 0.0829096 -0.514116 0.854621 0.0728583 -0.516102 0.853052 0.0770755 -0.609433 0.770242 0.187933 -0.609923 0.773065 0.174253 -0.717958 0.680895 0.144631 -0.666117 0.656374 0.354207 -0.746844 0.633362 0.202674 -0.399539 0.32726 0.856312 -0.513756 0.397608 0.760239 -0.570408 0.349682 0.743207 -0.627934 0.449039 0.63566 -0.765203 0.369032 0.527522 -0.763073 0.456545 0.457478 -0.89329 0.394181 0.215995 -0.877946 0.436273 0.197171 -0.898749 0.420873 -0.122945 -0.907208 0.40252 -0.122276 -0.795718 0.44432 -0.411598 -0.821041 0.362529 -0.440982 -0.659468 0.448447 -0.603322 -0.650988 0.32806 -0.684538 -0.554733 0.406635 -0.725892 -0.488984 0.300505 -0.818897 -0.0253471 0.02743 0.999302 -0.116074 0.0626534 0.991263 -0.203613 0.0862179 0.975248 -0.421174 0.15732 0.893232 -0.47401 0.179267 0.862078 -0.587921 0.210034 0.781175 -0.767453 0.265691 0.58346 -0.741708 0.262596 0.617181 -0.926099 0.304862 0.222262 -0.912112 0.307594 0.270995 -0.840554 0.500826 0.2065 -0.83894 0.499074 0.217038 -0.699257 0.429577 0.571405 -0.695427 0.426566 0.578293 -0.433131 0.282304 0.85598 -0.429591 0.2797 0.858615 -0.187922 0.141801 0.971894 -0.114783 0.0945162 0.988884 -0.0255905 0.0478321 0.998528 -0.93421 0.32067 -0.156279 -0.278767 0.024885 -0.960036 -0.576952 0.0858293 -0.812256 -0.852965 0.133967 -0.504483 -0.84584 0.131662 -0.516934 -0.978074 0.157544 -0.136203 -0.975721 0.155805 -0.153927 -0.193424 0.0277832 -0.980722 -0.304266 0.0383067 -0.951817 -0.618637 0.0967162 -0.779702 -0.213606 0.0899528 -0.97277 -0.129606 0.0501606 -0.990296 -0.487877 0.298199 -0.820399 -0.490743 0.299625 -0.818166 -0.709205 0.458212 -0.535789 -0.712885 0.459834 -0.529478 -0.817908 0.544777 -0.185054 -0.263891 0.072973 -0.961788 -0.553915 0.176826 -0.813579 -0.550713 0.175042 -0.816135 -0.81038 0.271958 -0.518965 -0.806507 0.269253 -0.526355 -0.931781 0.321164 -0.169229 -0.820031 0.545149 -0.174247 -0.214476 0.116983 -0.969698 -0.173346 0.133193 -0.975813 -0.458455 0.353898 -0.815215 -0.422274 0.371121 -0.827015 -0.636116 0.554704 -0.536339 -0.618568 0.565324 -0.545694 -0.719024 0.668476 -0.19012 -0.714756 0.672062 -0.193538 -0.457648 0.354744 -0.815301 -0.533064 0.833028 -0.148009 -0.54881 0.820166 -0.161664 -0.551879 0.825247 -0.119985 -0.523635 0.839872 -0.142904 -0.515808 0.845281 -0.139437 -0.510855 0.847839 -0.142113 -0.668404 0.718118 -0.193758 -0.672323 0.71459 -0.193247 -0.665292 0.720098 -0.197094 -0.655665 0.725373 -0.209612 -0.650936 0.727449 -0.217025 -0.645491 0.729468 -0.226316 -0.63507 0.73187 -0.247088 -0.618484 0.772037 -0.146409 -0.58714 0.803769 -0.0960365 -0.565928 0.818149 -0.101774 -0.283303 0.176679 -0.942616 -0.227255 0.0544007 -0.972315 -0.224323 0.106821 -0.968643 -0.689749 0.148451 -0.708667 -0.548845 0.819792 -0.163435 -0.615449 0.684345 -0.391018 -0.625197 0.65986 -0.416789 -0.633418 0.455688 -0.625404 -0.636202 0.384677 -0.668783 -0.550227 0.0874859 -0.83042 -0.465086 -0.189749 -0.864691 -0.627457 0.731686 -0.266334 -0.64461 0.732324 -0.219499 -0.588868 0.601816 -0.539493 -0.640213 0.649452 -0.410291 -0.463882 0.372807 -0.803635 -0.55679 0.439567 -0.704816 -0.356369 0.119415 -0.926683 -0.49759 0.215344 -0.840257 -0.472651 0.881099 0.0163017 -0.450057 0.892922 0.0117744 -0.457162 0.888486 -0.0399417 -0.4604 0.886782 -0.0406151 -0.452065 0.888117 -0.0829765 -0.476978 0.873153 -0.10048 -0.471169 0.875089 -0.110541 -0.498136 0.85338 -0.153631 -0.745889 0.123161 -0.654585 -0.759388 -0.0387536 -0.649483 -0.823143 0.127559 -0.553322 -0.922327 0.195358 -0.333388 -0.924356 0.16361 -0.34467 -0.670704 0.659258 -0.339905 -0.63916 0.702295 -0.313459 -0.704834 0.680784 -0.199355 -0.682614 0.70443 -0.194463 -0.712737 0.700152 -0.0423488 -0.71284 0.700049 -0.0423212 -0.692562 0.71324 0.107916 -0.71092 0.692323 0.12362 -0.654428 0.717903 0.23736 -0.77026 0.395648 -0.500162 -0.750457 0.454019 -0.480292 -0.862875 0.41772 -0.284529 -0.849071 0.446367 -0.282552 -0.897196 0.43977 -0.0405125 -0.899048 0.436054 -0.0396102 -0.867087 0.456775 0.198787 -0.879088 0.42486 0.2161 -0.78353 0.46767 0.409103 -0.790168 0.412811 0.453014 -0.670737 0.469349 0.574303 -0.484018 0.16521 0.859321 -0.616034 0.0872574 0.782872 -0.626811 0.177367 0.758715 -0.822703 0.119577 0.555753 -0.818617 0.179725 0.545496 -0.922813 0.139595 0.359068 -0.948165 -0.0542777 0.313109 -0.965014 0.159179 0.208352 -0.989958 0.137463 -0.0329801 -0.99893 -0.0452182 0.00975658 -0.977165 0.147917 -0.15254 -0.568816 0.815366 0.107828 -0.585484 0.793689 0.165127 -0.58213 0.64123 0.499949 -0.490713 0.867667 0.0797133 -0.525748 0.840621 0.130171 -0.622269 0.666311 0.410867 -0.604764 0.676589 0.420105 -0.502297 0.386832 0.773343 -0.336229 0.10424 0.935994 -0.319632 0.0369152 0.946822 -0.558833 0.454494 0.693643 -0.652162 0.400218 0.643825 -0.618092 0.709013 0.339504 -0.675472 0.681539 0.281499 -0.493418 0.866377 0.0770065 -0.455117 0.888952 0.0513009 -0.142411 0.0668596 0.987547 -0.226986 0.188196 0.955541 -0.396339 0.348348 0.849452 -0.444871 0.431592 0.784741 -0.59172 0.582061 0.557739 -0.607041 0.621664 0.49501 -0.680414 0.709129 0.184856 -0.678731 0.719558 0.146832 -0.124284 0.0675502 0.989945 -0.0322088 0.0169205 0.999338 -0.12411 0.0377322 0.991551 -0.214276 0.0513399 0.975423 -0.413537 0.0885733 0.906169 -0.494023 0.10747 0.862781 -0.587565 0.120683 0.800127 -0.796193 0.157754 0.584115 -0.758425 0.155881 0.632845 -0.682045 0.471285 0.559201 -0.677169 0.466467 0.569079 -0.425933 0.312772 0.848973 -0.418713 0.306333 0.854892 -0.107185 0.107438 0.988417 -0.914101 0.347512 0.20894 -0.814339 0.543786 0.202854 -0.815654 0.545983 0.191339 -0.940113 0.182813 0.287691 -0.958271 0.179361 0.222592 -0.912208 0.345455 0.220315 -0.757038 0.296292 0.582328 -0.762333 0.296743 0.575145 -0.469265 0.193957 0.861493 -0.473783 0.194768 0.858834 -0.121711 0.0661801 0.990357 -0.103223 0.104015 0.989205 0.94972 0.312273 -0.02275 0.428728 0.0300594 0.902934 0.706857 0.0888151 0.701759 0.939152 0.150955 0.308555 0.922917 0.142729 0.357565 0.983822 0.163291 0.0736882 0.984898 0.170444 -0.0304065 0.978848 0.169521 -0.114538 0.342195 0.0307573 0.939126 0.457822 0.0422181 0.888041 0.769561 0.11089 0.628871 0.293281 0.0487671 0.954782 0.329217 0.0689797 0.941731 0.434515 0.155735 0.887098 0.632275 0.308799 0.710543 0.628121 0.30649 0.715212 0.803073 0.468617 0.368066 0.799937 0.466805 0.377087 0.83763 0.546 -0.0161435 0.411896 0.0694519 0.90858 0.686235 0.173264 0.706443 0.688011 0.174401 0.704433 0.892775 0.265223 0.364157 0.894047 0.266563 0.360033 0.949685 0.311944 -0.0281153 0.837725 0.546068 -0.00514882 0.448801 0.14014 0.882575 0.500754 0.386152 -0.774682 0.669641 0.622978 0.404326 0.661908 0.68115 0.31291 0.67089 0.675036 0.306974 0.629336 0.738199 0.242895 0.706561 0.695194 0.132202 0.663522 0.739843 0.111224 0.702204 0.708016 -0.0749793 0.683032 0.726725 -0.0730561 0.640636 0.718442 -0.270973 0.64936 0.707928 -0.277794 0.544264 0.724877 -0.422292 0.559258 0.686615 -0.464533 0.467924 0.715652 -0.518546 0.452327 0.662408 -0.597174 0.476144 0.648819 -0.593566 0.124958 -0.355622 -0.926239 0.214076 0.307653 -0.927104 -0.0486114 -0.0438831 -0.997853 0.712886 0.165895 -0.681376 0.632969 -0.121415 -0.764597 0.534461 0.225908 -0.814443 0.393293 0.262715 -0.88108 0.361998 0.144456 -0.920918 0.149002 0.259904 -0.954069 0.0435988 0.122655 -0.991491 0.348829 -0.0104284 0.937128 0.612128 0.293809 0.73415 0.465693 -0.391881 0.793448 0.793937 0.354426 0.49401 0.838648 -0.181932 0.513391 0.693144 -0.540486 0.476893 0.948089 0.0951507 0.303435 0.981344 -0.190259 0.0276563 0.843199 0.148608 -0.516654 0.890164 -0.0750872 -0.449412 0.889379 -0.204172 -0.409046 0.935681 0.151305 -0.318759 0.980011 0.16003 -0.118186 0.550581 0.263188 0.792207 0.712144 0.158463 0.683916 0.740585 0.272779 0.614105 0.913601 0.179552 0.36482 0.907917 0.257941 0.330385 0.970783 0.221189 0.0930401 0.993656 0.060623 0.0947189 0.422294 0.613034 -0.667725 0.518716 0.716862 -0.465878 0.609573 0.714084 -0.344245 0.633764 0.772924 0.030528 0.596138 0.799671 -0.0717351 0.517227 0.855004 0.0380112 0.434016 0.899422 -0.0516782 0.439552 0.897468 -0.0366917 0.471076 0.881672 -0.0272274 0.385071 0.917877 -0.096032 0.507753 0.852331 -0.125372 0.364793 0.920295 -0.14136 0.474284 0.844497 -0.248756 0.386797 0.899745 -0.202106 0.398884 0.88298 -0.247465 0.431789 0.872582 -0.228385 0.431751 0.827923 -0.357959 0.495163 0.868366 0.027458 0.210595 0.359526 -0.90906 0.317101 0.440788 -0.839734 0.41351 0.387029 -0.824147 0.452841 0.473518 -0.755457 0.650388 0.412395 -0.637907 0.647605 0.46601 -0.602862 0.822447 0.438735 -0.362068 0.818276 0.450078 -0.357567 0.885063 0.463223 -0.0456953 0.900061 0.433154 -0.0476182 0.837528 0.483874 0.253797 0.867692 0.415317 0.273171 0.719696 0.495978 0.485843 0.739414 0.393386 0.546365 0.619925 0.472579 0.626388 0.5897 0.357565 0.724156 0.253087 0.0753474 -0.964505 0.0265672 0.0398021 -0.998854 -0.0555299 0.0932092 -0.994097 -0.0399805 0.0570467 -0.997571 -0.0366611 0.0585695 -0.99761 -0.0368049 0.0322609 -0.998802 -0.156419 0.00983783 -0.987642 0.562016 0.452829 -0.692159 0.885864 0.13847 -0.442799 0.79978 0.14944 -0.581395 0.895811 0.205608 -0.394015 0.869627 0.305551 -0.387798 0.868401 0.304947 -0.391008 0.761372 0.535171 -0.365929 0.758815 0.533491 -0.373613 0.266851 0.296631 -0.916952 0.564483 0.454602 -0.688982 0.653083 0.258816 -0.711686 0.654428 0.258909 -0.710415 0.68386 0.135825 -0.716859 0.642377 0.134373 -0.754517 -0.146598 0.0593824 -0.987412 0.0238423 0.144052 -0.989283 0.00190648 0.138787 -0.99032 0.267874 0.297413 -0.9164 0.324138 0.168814 -0.930826 0.324751 0.168904 -0.930596 0.343116 0.0923433 -0.934743 0.438076 0.102756 -0.893045 0.796534 0.479823 0.367838 0.952543 0.257243 -0.162751 0.967999 0.249782 0.0242345 0.938629 0.229443 0.25755 0.909097 0.221364 0.352903 0.87059 0.200909 0.449121 0.699075 0.142391 0.700728 0.742658 0.163455 0.649416 0.447193 0.0667617 0.891943 0.381355 0.0383993 0.923631 0.381527 0.0927107 0.919697 0.29515 0.0466762 0.95431 0.828275 0.559954 -0.0203017 0.828653 0.559468 -0.018161 0.920134 0.389803 -0.0375202 0.96535 0.257163 -0.0443403 0.921763 0.386976 -0.0245565 0.871336 0.331892 0.361417 0.692322 0.296243 0.657974 0.652799 0.269242 0.708069 0.671135 0.278549 0.687014 0.459423 0.144499 0.876385 0.293517 0.0485232 0.954721 0.162118 -0.310327 0.936704 0.627163 0.360502 0.690438 0.42542 -0.405078 0.809277 0.748928 0.1122 0.653084 0.993261 0.0555998 0.101697 0.946108 0.0948358 0.309653 0.652979 -0.565735 0.503549 0.810619 -0.242615 0.532949 0.846582 0.0581019 0.529078 0.661474 0.749784 0.0166184 0.519679 0.799295 -0.301764 0.548842 0.835355 0.0309019 0.529359 0.848323 0.0113348 0.467609 0.883105 -0.0383215 0.45814 0.887352 -0.0521082 0.521453 0.852371 -0.039379 0.399698 0.910852 -0.102906 0.511473 0.847079 -0.144404 0.380951 0.91305 -0.14566 0.415307 0.891084 -0.183 0.398653 0.893646 -0.206088 0.410287 0.612904 -0.675288 0.465731 0.651416 -0.598959 0.45318 0.658377 -0.600972 0.467694 0.710856 -0.525306 0.57003 0.678166 -0.46385 0.555443 0.715681 -0.423419 0.661025 0.698127 -0.275072 0.653835 0.706963 -0.269637 0.693678 0.7167 -0.0717759 0.71761 0.69258 -0.0732699 0.678099 0.727407 0.105169 0.723391 0.678001 0.130461 0.650438 0.723202 0.232185 0.688715 0.661028 0.297849 0.685325 0.66355 0.300051 0.690664 0.606281 0.394216 0.933372 0.146423 -0.327684 0.897204 -0.190124 -0.398595 0.849361 0.145962 -0.507228 0.46994 0.489848 -0.734306 0.174601 -0.450649 -0.87546 0.177389 0.272548 -0.945648 -0.052683 -0.0404403 -0.997792 0.717983 0.164014 -0.676461 0.640699 -0.11854 -0.758586 0.537963 0.224336 -0.81257 0.397621 0.261241 -0.879574 0.367594 0.144381 -0.918711 0.146046 0.260093 -0.954475 0.0417464 0.120577 -0.991826 0.980996 0.157678 -0.113072 0.936094 -0.33512 0.106876 0.981587 0.190889 -0.00697173 0.906745 0.256054 0.335038 0.910954 0.169313 0.376159 0.743 0.270626 0.612138 0.707954 0.152049 0.689698 0.559206 0.257755 0.787941 0.458334 0.145796 0.87674 0.615824 0.699315 -0.362931 0.513807 0.727119 -0.455302 0.522773 0.85245 0.00620061 0.441571 0.839454 -0.316753 0.407789 0.879859 -0.244043 0.400619 0.891919 -0.209726 0.203736 0.357754 -0.91132 0.310229 0.442001 -0.841661 0.416935 0.384501 -0.823604 0.454554 0.469948 -0.756657 0.658911 0.406126 -0.633165 0.656089 0.459464 -0.598699 0.829641 0.431416 -0.354369 0.826083 0.44116 -0.350663 0.888905 0.456468 -0.0385435 0.906521 0.42028 -0.0397976 0.841588 0.476676 0.253988 0.872876 0.400656 0.278501 0.729302 0.488094 0.479462 0.745381 0.382763 0.545802 0.636261 0.462029 0.61782 0.605971 0.360866 0.708925 -0.0413272 0.0704183 -0.996661 -0.135093 0.0195433 -0.99064 -0.0422225 0.0454775 -0.998073 0.0458472 0.0620641 -0.997019 0.260635 0.110678 -0.959072 0.330791 0.129941 -0.934715 0.446318 0.149701 -0.882264 0.666191 0.193195 -0.720323 0.638799 0.191259 -0.745222 0.887144 0.223584 -0.403715 0.870927 0.225139 -0.436805 0.539123 0.469185 -0.699437 0.542042 0.471604 -0.695543 0.250609 0.306047 -0.918439 0.252172 0.307405 -0.917557 0.0107132 0.15393 -0.988024 0.822517 0.40591 -0.398375 0.738513 0.558235 -0.378117 0.7358 0.556074 -0.386498 -0.140547 0.0515975 -0.988729 -0.0610248 0.0978493 -0.993329 -0.0460861 0.0676587 -0.996644 0.305676 0.200661 -0.930751 0.30824 0.201112 -0.929808 0.625915 0.308494 -0.716284 0.629885 0.308834 -0.712648 0.786972 0.353617 -0.505599 0.853938 0.336427 -0.396996 0.990328 0.105349 0.0902841 0.602144 0.792265 -0.0986856 0.520067 0.851375 -0.0684902 0.695277 0.310595 0.648167 0.676067 0.327196 0.660209 0.742031 0.665272 0.0824855 0.778612 0.578557 0.242972 0.801013 0.494305 0.337699 0.795333 0.392037 0.462334 0.787797 0.306468 0.534279 0.625889 0.239964 0.742079 0.57636 0.202592 0.791685 0.503962 0.110498 0.856629 0.603718 0.00378958 0.797189 0.0725745 -0.554989 0.828686 0.778098 0.0854027 0.62231 0.983804 0.128313 -0.125158 0.893833 -0.446336 0.0429648 0.939872 0.338931 -0.0420391 0.940773 0.336481 -0.0415553 0.822092 0.566559 -0.0563551 0.814249 0.577522 -0.0588769 0.631284 0.771851 -0.0756747 0.618421 0.785705 -0.0149128 0.810801 -0.23832 0.534607 0.602866 0.203044 0.771574 0.699468 0.0954282 0.708264 0.77194 0.227377 0.593639 0.85022 0.163923 0.500255 0.83827 0.0330957 0.544249 0.954732 0.141953 0.261411 0.757307 -0.362184 0.543424 0.883767 0.399585 0.243492 0.900585 0.295469 0.318819 0.77984 0.616126 0.110625 0.822968 0.537741 0.183191 0.644812 0.764301 -0.00785224 0.657783 0.753108 0.0122759 0.249286 0.117043 -0.961331 0.590027 0.765952 -0.255314 0.686598 0.672563 -0.276119 0.669096 0.645299 -0.368647 0.501347 0.518336 -0.692806 0.568161 0.792343 -0.222228 0.577103 0.800148 -0.163448 0.585178 0.793568 -0.166782 0.842001 0.0379665 -0.538139 0.721405 0.0876677 -0.686942 0.0896968 -0.73499 -0.672119 0.545711 0.0215709 -0.837696 0.596692 0.605553 -0.526559 0.67112 0.559049 -0.486891 0.647548 0.63257 -0.424896 0.755959 0.586582 -0.290598 0.764875 0.572831 -0.294671 0.428575 0.136726 -0.893101 0.417129 0.0974567 -0.903607 0.468878 0.223746 -0.854454 0.651675 0.110747 -0.750369 0.673289 0.234177 -0.701315 0.837947 0.17259 -0.517743 0.786401 -0.395334 -0.474642 0.93375 0.132928 -0.332326 -0.0411546 0.0708028 -0.996641 0.0256141 0.156547 -0.987338 0.247488 0.305553 -0.919449 0.245198 0.302489 -0.921075 0.558588 0.545349 -0.624959 0.556476 0.547237 -0.625193 0.610488 0.707877 -0.355267 0.597387 0.766285 -0.236507 0.126935 0.0478282 -0.990757 0.313917 0.305243 -0.899046 0.381226 0.364791 -0.849467 0.422702 0.3282 -0.844753 0.374675 0.204081 -0.904417 0.552957 0.393333 -0.734525 0.674358 0.317161 -0.666821 0.69224 0.412297 -0.592296 0.861709 0.339007 -0.377533 0.859971 0.346876 -0.374337 -0.0627243 0.0990861 -0.9931 -0.119061 0.0435753 -0.99193 0.730766 0.56552 -0.382319 0.0529462 0.134803 -0.989457 0.177006 0.206619 -0.962277 0.272844 0.253713 -0.928001 0.281673 0.258618 -0.924001 0.440971 0.329721 -0.834762 0.588495 0.393163 -0.706468 0.605693 0.398304 -0.688833 0.571396 0.38452 -0.725018 0.817539 0.427118 -0.386265 0.987204 0.137544 0.0806891 0.924395 0.11923 0.362322 0.925869 0.120382 0.358153 0.707005 0.0780372 0.70289 0.708742 0.078825 0.70105 0.430268 0.0328634 0.902103 0.390106 0.0109912 0.920704 0.372481 0.0750973 0.924997 0.348129 0.123753 0.929242 0.279197 0.061865 0.958239 0.918317 0.395828 -0.00383157 0.988769 0.148199 -0.0193315 0.983941 0.142301 -0.107757 0.918142 0.396242 0.00279298 0.861762 0.335158 0.380835 0.863008 0.337092 0.376278 0.664943 0.21899 0.714068 0.666595 0.220468 0.712071 0.382301 0.0777208 0.920763 0.381451 0.0374533 0.92363 0.749868 0.660536 0.0372909 0.749977 0.659833 0.0464182 0.720097 0.561894 0.407105 0.717833 0.559389 0.414487 0.57426 0.368938 0.730829 0.571194 0.366139 0.734629 0.403028 0.184208 0.896458 0.736844 0.147321 0.659816 0.889063 0.430183 0.156555 0.437605 0.896355 -0.0710609 0.433851 0.898153 -0.0713727 0.468146 0.883612 -0.00833507 0.483922 0.875109 0.00176219 0.537403 0.839366 0.0816183 0.920864 0.377234 -0.0985134 0.584555 0.806838 0.0854898 0.566706 0.823589 -0.0233614 0.623982 0.645093 0.441024 0.481396 0.876404 -0.0131829 0.681198 0.655399 0.326224 0.63724 0.683233 0.356536 0.748533 0.657934 -0.0825895 0.71543 0.695049 -0.0711806 0.689278 0.715071 0.116482 0.732263 0.667749 0.133799 0.659859 0.708339 0.250683 0.879632 -0.0267455 0.474902 0.800516 0.254327 0.542671 0.453563 0.141587 0.879906 0.541437 0.268511 0.796711 0.367623 -0.0103063 0.929918 0.980133 0.118358 0.159158 0.923461 0.157281 0.349976 0.894725 0.0760296 0.440099 0.863617 0.216263 0.455408 0.761054 0.261047 0.593845 0.478343 -0.431069 0.765093 0.624972 0.352881 0.696337 0.977397 0.146823 -0.152114 0.977726 -0.197912 -0.0698808 0.900374 0.425506 -0.0909461 0.87735 0.456187 0.148831 0.933128 0.119614 0.339064 0.851974 0.420499 0.311962 0.738881 0.473814 0.479119 0.758073 0.373447 0.534661 0.594807 0.475513 0.648145 0.573364 0.364194 0.733905 0.207779 0.466793 -0.859612 0.935652 0.153602 -0.317744 0.560044 0.809678 -0.175422 0.519073 0.818107 -0.247519 0.834188 0.420129 -0.357242 0.842194 0.389356 -0.372977 0.590899 -0.146572 -0.793319 0.762037 0.0845238 -0.641993 0.842375 0.0453034 -0.536984 0.544904 0.0548318 -0.836703 0.445946 0.104191 -0.888975 0.449486 0.140533 -0.882164 0.282782 0.122381 -0.951345 0.127862 0.117331 -0.984827 0.149875 0.201041 -0.96805 0.358765 0.487963 -0.795726 0.700609 0.6678 -0.251378 0.675692 0.703596 -0.219987 0.599638 0.737682 -0.310257 0.436515 0.693292 -0.573412 0.438967 0.704383 -0.557811 0.559569 0.820852 -0.114384 0.505539 0.854549 -0.119062 0.488946 0.869671 -0.0678628 0.480442 0.874158 -0.07087 0.454784 0.889744 -0.0390907 0.448223 0.892313 -0.053598 0.443308 0.894894 -0.0514064 0.290277 0.177088 -0.940414 0.456309 0.487888 -0.744142 0.414177 0.454865 -0.788388 0.431188 -0.38254 -0.817153 0.669495 0.168065 -0.723554 0.482961 0.266533 -0.834092 0.553014 0.485908 -0.676808 0.523684 0.451327 -0.722537 -0.0220582 0.124482 -0.991977 0.0031815 0.201195 -0.979546 0.259046 0.488761 -0.833071 0.30503 0.457738 -0.835125 0.487928 0.723437 -0.488431 0.51444 0.707299 -0.48485 0.520889 0.680475 -0.515391 0.556298 0.731634 -0.39401 0.627111 0.693604 -0.354466 0.678059 0.418652 -0.604124 0.687007 0.489595 -0.536952 0.680084 0.273576 -0.680178 0.877672 0.182927 -0.442979 0.783764 -0.282687 -0.552994 0.914982 0.0730194 -0.396834 0.935967 0.0953725 -0.338924 0.682762 0.147056 -0.715689 -0.0713012 0.117379 -0.990524 0.274083 0.359806 -0.891862 0.340309 0.251382 -0.906089 -0.1047 0.0344658 -0.993906 0.00254334 0.074397 -0.997225 0.0861241 0.0966606 -0.991584 0.148526 0.115597 -0.982129 0.323623 0.106123 -0.940216 0.515363 0.124307 -0.847908 0.580369 0.542815 -0.607062 0.570872 0.541133 -0.617479 0.671795 0.374609 -0.63903 0.65906 0.3743 -0.652335 0.727163 0.163224 -0.666778 0.817342 0.166111 -0.551688 0.77292 0.225915 -0.592923 0.949664 0.174304 -0.260299 0.838972 0.434905 -0.327082 0.866754 0.425587 -0.260025 0.747319 0.616135 -0.248781 0.757489 0.613153 -0.224173 0.636423 0.745575 -0.197699 0.63862 0.745052 -0.192515 0.474718 0.658101 -0.58442 0.477397 0.658953 -0.581269 0.0140631 0.252351 -0.967534 0.268361 0.416248 -0.868746 0.0241511 0.2187 -0.975493 -0.0739115 0.165305 -0.983469 -0.77714 0.567227 0.272593 -0.466777 0.364991 0.805544 -0.607186 0.458299 0.649067 -0.641571 0.46407 0.610757 -0.731177 0.592232 0.338589 -0.76615 0.581495 0.273637 -0.108475 0.0853187 0.990431 -0.367237 0.232902 0.900496 -0.399041 0.294487 0.868357 -0.156545 0.138547 0.977905 -0.101058 0.0528373 0.993476 -0.0347373 0.0150308 0.999283 -0.0964027 -0.0631692 0.993336 -0.978548 0.122012 0.166 -0.71335 -0.0241781 0.70039 -0.702766 0.100342 0.70431 -0.437402 0.0837255 0.89536 -0.231001 0.0432317 0.971993 -0.342562 0.169031 0.924164 -0.386526 0.207576 0.898615 -0.530001 0.35923 0.768149 -0.493389 0.331029 0.804356 -0.672643 0.519154 0.527286 -0.599674 0.467752 0.649307 -0.648379 0.74161 0.172104 -0.603093 0.781828 0.158188 -0.926086 0.110644 0.360726 -0.897893 -0.351721 0.264725 -0.918667 0.336965 0.206168 -0.905877 0.370901 0.204498 -0.801387 0.576869 0.158117 -0.778789 0.608052 0.154143 -0.608883 0.787824 0.0927056 -0.594248 0.799196 0.0903042 -0.641946 0.741168 0.196407 -0.749479 0.539708 0.383401 -0.726898 0.611385 0.312775 -0.796789 0.297926 0.525706 -0.797182 0.391766 0.459369 -0.642199 -0.325092 0.694187 -0.844236 0.143192 0.51649 -0.716617 0.609612 0.33887 -0.755126 0.632704 0.171669 -0.678558 0.680374 0.276857 -0.675781 0.5162 0.526173 -0.694985 0.575986 0.43039 -0.609967 0.284602 0.739555 -0.668888 0.382422 0.63745 -0.381863 -0.109198 0.917745 -0.614279 0.154414 0.773833 -0.100605 0.0963499 0.99025 -0.040506 0.0443839 0.998193 -0.253591 0.162379 0.953585 -0.208527 0.140358 0.967893 -0.426566 0.254223 0.867993 -0.41611 0.249863 0.874311 -0.693094 0.383949 0.610086 -0.686334 0.381675 0.619088 -0.846349 0.456489 0.274429 -0.854245 0.457775 0.246388 -0.673029 0.226669 -0.704027 -0.75569 0.0929486 -0.6483 -0.876169 0.173238 -0.449795 -0.882481 0.217646 -0.416962 -0.960351 0.0280715 -0.277378 -0.870957 -0.420059 -0.254921 -0.989298 0.13 -0.0662503 -0.649651 0.754972 -0.0892776 -0.643008 0.760229 -0.0926954 -0.612325 0.789824 -0.0351615 -0.653656 0.755881 -0.0371182 -0.564261 0.825325 0.0211498 -0.596579 0.801838 0.0339044 -0.754686 0.63576 -0.162044 -0.760046 0.639761 -0.114174 -0.680966 0.511015 -0.524547 -0.305341 0.113896 -0.945407 -0.505945 0.283271 -0.814725 -0.580791 0.386321 -0.716546 -0.723259 0.539163 -0.43151 -0.716018 0.546476 -0.434375 -0.693283 0.706958 -0.139889 -0.691567 0.709682 -0.134487 -0.752838 0.0546015 -0.655937 -0.672403 0.229268 -0.703783 -0.657072 0.23926 -0.71485 -0.508194 0.00748855 -0.86121 -0.322333 0.0920698 -0.942138 -0.799181 0.344134 -0.49283 -0.800583 0.044184 -0.597591 -0.854417 0.403031 -0.327929 -0.930627 0.340705 -0.133617 -0.916763 0.381754 -0.117519 -0.173366 -0.00644384 -0.984836 -0.453604 0.217905 -0.864153 -0.56491 0.106747 -0.818219 -0.671179 0.295441 -0.679877 -0.699048 0.417623 -0.580451 -0.728767 0.601636 -0.327006 -0.780161 0.560159 -0.278515 -0.739062 0.636631 -0.220201 -0.806408 0.587814 -0.0646677 -0.785918 0.615423 -0.0598932 -0.810599 0.563557 -0.159164 -0.29701 0.115453 -0.947869 -0.131295 0.0497867 -0.990092 -0.440996 0.224413 -0.869 -0.295173 0.127805 -0.946857 -0.59376 0.312602 -0.741437 -0.521286 0.261321 -0.812387 -0.720131 0.377508 -0.58215 -0.755975 0.402146 -0.516508 -0.805811 0.427517 -0.409754 -0.776416 0.409306 -0.479214 -0.867847 0.438308 -0.23394 -0.892742 0.447107 -0.0557478 0.961682 -0.175452 -0.210675 0.436491 -0.895564 -0.0862606 0.443683 -0.896037 -0.0162073 -0.174545 -0.917526 -0.357324 -0.317529 -0.618069 -0.719142 -0.398654 -0.895092 -0.199711 -0.681031 -0.711925 -0.171348 -0.682009 -0.668706 -0.296135 -0.922734 0.277927 -0.267056 -0.699442 0.712653 -0.0539081 -0.758808 -0.651273 -0.00735139 -0.888995 -0.457835 -0.00861266 0.974984 -0.060861 -0.213778 0 -1 0 -0.371904 -0.912629 -0.16969 -0.115686 -0.988738 -0.0949387 -0.115688 -0.988738 -0.0949402 -0.115686 -0.988738 -0.0949389 -0.342687 -0.896368 -0.281229 -0.115688 -0.988738 -0.0949403 -0.17022 -0.975307 -0.140718 -0.110762 -0.989511 -0.0927357 -0.113975 -0.959523 -0.257539 -0.138644 -0.92279 -0.359494 -0.0715158 -0.967771 -0.241464 -0.0222186 -0.986062 -0.164891 -0.0183952 -0.9902 -0.138438 0.117832 -0.990234 -0.0745147 0.103188 -0.990436 -0.0915943 0.344927 -0.872201 -0.346829 0.19046 -0.955794 -0.224013 0.328547 -0.940993 0.0811771 0.513318 -0.83803 0.184963 0.137709 -0.988919 0.0554501 0.135119 -0.988936 0.0612284 0.136313 -0.988739 0.0617603 0.136335 -0.988735 0.0617709 0.136293 -0.988742 0.0617505 0.106639 -0.994074 -0.0210743 0.148596 -0.988764 -0.0162638 0.14994 -0.988691 -0.00267427 0.0903236 -0.995706 -0.0202926 0.146188 -0.988737 -0.0320536 0.227462 -0.972508 -0.049894 0.433008 -0.896382 -0.0948882 0.411687 -0.906828 -0.0904311 0.684798 -0.713134 -0.149976 0.669696 -0.727968 -0.146866 0.789447 -0.588907 -0.173096 0.868013 -0.45859 -0.19039 0.877572 -0.439182 -0.192317 -0.987371 -0.157752 -0.0145664 -0.946352 0.322055 -0.0264298 -0.712908 -0.692284 -0.111826 -0.646305 -0.763044 -0.00735248 -0.719474 -0.694488 -0.00660343 -0.444041 -0.895989 -0.00571572 -0.904601 0.425777 -0.0202899 -0.181672 -0.982057 -0.0505972 -0.765217 -0.63319 -0.116246 -0.643844 -0.757835 -0.105603 -0.584076 -0.81169 -0.00387558 -0.955503 0.11448 -0.271859 -0.308207 -0.939048 -0.152308 -0.643526 -0.711928 -0.281128 -0.874713 -0.32854 -0.356284 -0.123599 -0.992329 0.00251589 -0.685782 -0.706705 -0.173983 -0.69195 -0.707097 -0.145664 -0.403265 -0.912351 -0.0706667 -0.371598 -0.927261 -0.045838 -0.121514 -0.992574 -0.00556711 -0.150146 -0.988651 -0.00513207 -0.330062 -0.910617 -0.248669 -0.120314 -0.988581 -0.0907265 -0.559897 -0.712922 -0.422207 -0.361833 -0.896276 -0.256449 -0.345916 -0.896357 -0.277283 -0.768795 0.269903 -0.579747 -0.560219 -0.712518 -0.422461 -0.615614 -0.711981 -0.337792 -0.80116 0.357 -0.480307 -0.805545 0.343969 -0.482476 -0.633469 -0.608534 -0.477915 -0.541839 -0.713222 -0.444664 -0.342687 -0.896368 -0.281229 -0.342686 -0.896369 -0.281228 -0.115686 -0.988738 -0.0949387 -0.116778 -0.988737 -0.093608 -0.102378 -0.99141 -0.0813937 -0.142619 -0.984603 -0.101081 -0.0429593 -0.998733 -0.0262284 -0.617884 -0.706626 -0.344819 -0.632556 -0.7071 -0.316041 -0.653692 0.722271 -0.225857 -0.357585 -0.923014 -0.14205 -0.12308 -0.991666 -0.0380869 -0.757094 -0.158004 -0.633911 -0.694046 -0.434694 -0.573882 -0.763305 -0.158025 -0.626413 -0.763301 -0.158059 -0.626409 -0.763301 -0.158058 -0.626409 -0.686894 -0.458708 -0.563705 -0.686894 -0.458708 -0.563705 -0.68481 -0.458706 -0.566236 -0.68512 -0.457916 -0.566501 -0.66466 -0.157732 -0.730306 -0.0938807 -0.986084 -0.137203 -0.557686 -0.454845 -0.694336 -0.434381 -0.708832 -0.555761 -0.540739 -0.712526 -0.447111 -0.540282 -0.713114 -0.446726 -0.541921 -0.713116 -0.444732 -0.771101 0.121408 -0.625031 -0.76471 -0.158056 -0.624689 -0.651181 -0.538017 -0.535257 -0.686893 -0.45871 -0.563706 -0.541915 -0.713124 -0.444728 -0.541916 -0.713124 -0.444727 -0.342681 -0.896372 -0.281224 -0.341646 -0.896371 -0.282485 -0.338283 -0.898501 -0.279751 -0.260855 -0.89548 -0.360652 -0.0993237 0.993864 -0.0486764 -0.106441 -0.461504 -0.88073 -0.120967 0.3845 -0.915165 -0.123361 -0.163817 -0.978747 -0.131431 0.18892 -0.973157 0.0489271 -0.165358 -0.985019 0.079036 -0.908979 -0.40928 0.147163 -0.461374 -0.874916 0.125922 -0.708715 -0.694166 -0.0845306 -0.709678 -0.699437 -0.084537 -0.709615 -0.6995 -0.287597 -0.708712 -0.644217 -0.0976607 -0.989478 -0.106753 -0.280198 -0.90643 -0.316026 -0.2927 -0.85634 -0.425451 -0.386267 -0.706923 -0.592502 -0.343467 -0.706907 -0.618315 -0.0439515 0.977949 -0.204169 -0.199461 -0.799481 -0.566608 -0.0506879 -0.906378 -0.419416 -0.0524019 -0.900009 -0.432711 0.0947769 -0.898111 -0.429434 -0.0292385 0.993907 -0.106276 0.289754 -0.893114 -0.344079 0.735451 -0.158043 -0.658889 0.834749 -0.156571 -0.527902 0.834742 -0.156619 -0.527897 0.752625 -0.454986 -0.475966 0.752643 -0.454946 -0.475976 0.587547 -0.454722 -0.66934 0.907243 -0.158104 -0.389761 0.54872 -0.822664 -0.148763 0.8565 -0.454703 -0.244239 0.68092 -0.708718 -0.184571 0.595393 -0.709741 -0.37653 0.59543 -0.709697 -0.376553 0.458384 -0.708802 -0.536176 0.00725844 -0.990431 -0.137815 0.051851 -0.836175 -0.546006 0.0616855 -0.94733 -0.314262 0.18699 -0.706844 -0.682207 0.261968 -0.70604 -0.657936 0.252805 -0.72324 -0.642661 0.359615 -0.689614 -0.628578 0.349037 -0.706208 -0.61599 0.410793 -0.706839 -0.575872 0.167848 0.977217 -0.129899 0.303089 -0.900831 -0.31087 0.368318 -0.900049 -0.232926 0.36841 -0.899995 -0.232987 0.428547 -0.898088 -0.0989212 0.0834806 0.99389 -0.0722026 0.274373 -0.959366 0.06585 0.918413 -0.157985 0.362711 0.899418 -0.158142 0.407478 0.899282 -0.159033 0.407431 0.899422 -0.158037 0.40751 0.681321 -0.708692 0.183187 0.857011 -0.454689 0.242466 0.809474 -0.458532 0.366742 0.809486 -0.458507 0.366748 0.809481 -0.458507 0.366759 0.638536 -0.713148 0.289296 0.638536 -0.713148 0.289296 0.638532 -0.713148 0.289306 0.638532 -0.713148 0.289306 0.65506 -0.712537 0.251372 0.301813 -0.952333 0.0443901 0.286416 -0.951788 0.109842 0.284391 -0.952477 0.109132 0.276582 -0.95263 0.126486 0.403753 -0.896393 0.182932 0.403761 -0.896392 0.182917 0.402579 -0.89703 0.182394 0.419602 -0.896293 0.143502 0.186201 0.977944 0.0946247 0.69654 -0.70681 0.123496 0.707027 -0.705902 0.0426061 0.738573 -0.67234 0.049697 0.679544 -0.731567 -0.0550476 0.705999 -0.706282 -0.0522597 0.696327 -0.70689 -0.124243 0.290148 -0.953896 -0.0767975 0.482725 -0.858481 -0.173169 0.127028 -0.990445 -0.0536863 0.117758 -0.990246 -0.0744664 0.966566 -0.158096 0.20188 0.956586 0.245315 0.157366 0.556159 -0.830745 0.0234317 0.987667 -0.155063 -0.021686 0.834111 -0.445797 0.324844 0.922045 -0.156667 0.353962 0.831272 -0.455139 0.319116 0.879652 -0.457381 0.130443 0.948924 -0.282976 0.139528 0.701147 -0.71301 -0.00313646 0.890402 -0.454898 -0.015873 0.97686 -0.155196 -0.147169 0.752445 0.641676 -0.148589 0.873793 -0.454546 -0.172839 0.871814 -0.458503 -0.172382 0.687783 -0.713064 -0.135994 0.899411 -0.158113 0.407504 0.899394 -0.158229 0.407497 0.809477 -0.458516 0.366757 0.82997 -0.457892 0.318568 0.657649 -0.709774 0.252426 0.694767 -0.711943 0.102157 0.446433 -0.891716 0.0744315 0.451846 -0.89206 -0.00805494 0.70039 -0.712777 -0.0374561 0.689317 -0.71153 -0.136265 0.434943 -0.896344 -0.0859802 0.956061 -0.20437 -0.210194 0.964878 -0.155594 -0.211663 0.964506 -0.158129 -0.211481 0.868027 -0.45859 -0.190327 0.868031 -0.458582 -0.190328 0.684761 -0.713133 -0.150143 0.684756 -0.713138 -0.150142 0.432997 -0.896381 -0.0949406 0.432997 -0.896381 -0.0949406 0.146188 -0.988737 -0.0320538 0.280243 -0.958112 -0.0590284 -0.445687 -0.892872 -0.064365 -0.758982 -0.650727 -0.0223853 -0.988861 -0.0198916 -0.147505 -0.848812 -0.0560377 -0.525717 -0.990141 -0.0193359 -0.13873 -0.989728 -0.0564328 -0.131354 -0.989781 -0.0563377 -0.130997 -0.98898 -0.0914138 -0.116458 -0.989064 -0.0911597 -0.115938 -0.987902 -0.122623 -0.0949377 -0.988012 -0.122181 -0.0943564 -0.986544 -0.148804 -0.0677337 -0.986689 -0.148121 -0.0671262 -0.984972 -0.168914 -0.0360451 -0.985137 -0.168054 -0.0355392 -0.98324 -0.182315 -0.00115794 -0.98344 -0.18123 -0.000778507 -0.981433 -0.188482 0.0355447 -0.98662 -0.158099 0.039814 -0.888889 -0.458112 0.00312516 -0.834018 -0.551695 -0.00681651 -0.840061 -0.530189 -0.114876 -0.838039 -0.533188 -0.115766 -0.843601 -0.491387 -0.21651 -0.841752 -0.493957 -0.217853 -0.846784 -0.433053 -0.308906 -0.845165 -0.435064 -0.31051 -0.849447 -0.357119 -0.388466 -0.848152 -0.358469 -0.390048 -0.851557 -0.266409 -0.451527 -0.85058 -0.26719 -0.452905 -0.852911 -0.1646 -0.495429 -0.852377 -0.164879 -0.496255 -0.853585 -0.0556258 -0.517976 -0.570629 -0.0834954 -0.816953 -0.64684 -0.761597 -0.0396052 -0.544917 -0.836941 -0.0509388 -0.554032 -0.804488 -0.21412 -0.548523 -0.807956 -0.215243 -0.556969 -0.744592 -0.367924 -0.551897 -0.747556 -0.369553 -0.559533 -0.655363 -0.507367 -0.555129 -0.657647 -0.509246 -0.561633 -0.539777 -0.627064 -0.557945 -0.541377 -0.628974 -0.563101 -0.402332 -0.721835 -0.560342 -0.403255 -0.723465 -0.563866 -0.248396 -0.787626 -0.562236 -0.24876 -0.788676 -0.564048 -0.0836317 -0.821496 -0.200834 -0.0973065 -0.974781 -0.193353 -0.0971634 -0.976306 -0.191253 -0.287879 -0.938375 -0.194094 -0.287852 -0.9378 -0.189992 -0.467055 -0.863576 -0.194108 -0.466892 -0.862748 -0.188182 -0.627929 -0.755177 -0.194149 -0.627507 -0.754016 -0.186639 -0.764207 -0.617377 -0.193908 -0.763467 -0.61605 -0.185082 -0.870559 -0.455929 -0.193445 -0.869458 -0.454558 -0.183622 -0.943221 -0.276797 -0.192611 -0.941792 -0.275551 -0.182099 -0.979524 -0.0858686 -0.153974 -0.984092 -0.0886274 -0.999617 0 0.0276921 -0.989054 0.0024112 -0.147534 -0.984609 0 -0.174772 -0.90584 0 -0.42362 -0.850137 0.0050254 -0.526538 -0.801706 0 -0.597719 -0.619492 0 -0.785003 -0.572623 0.00420623 -0.819808 -0.448867 0 -0.893598 -0.201792 0 -0.979428 -0.201792 0 -0.979428 -0.964245 -0.238765 -0.114991 -0.964241 -0.165199 -0.207242 -0.990813 -0.116765 -0.0682367 -0.999158 -0.0302881 0.0276794 -0.892761 -0.210362 -0.398404 -0.546953 -0.833285 -0.0804932 -0.700824 -0.689709 -0.182063 -0.839997 -0.541483 -0.0346578 -0.914374 -0.404006 -0.0264645 -0.257314 -0.960252 -0.108193 -0.165688 -0.931776 -0.323018 -0.410122 -0.907808 -0.0876606 -0.956283 -0.238137 -0.169744 -0.707067 -0.687585 -0.165176 -0.698036 -0.645141 -0.310706 -0.698061 -0.645145 -0.310643 -0.698039 -0.446339 -0.559931 -0.698104 -0.446419 -0.559787 -0.942005 -0.295809 -0.158505 -0.94129 -0.195956 -0.274906 -0.901626 -0.0963469 -0.421649 -0.794331 -0.135322 -0.592221 -0.706319 -0.26299 -0.657229 -0.609789 -0.176299 -0.772707 -0.439819 -0.199772 -0.875586 -0.258009 -0.920509 -0.293418 -0.294593 -0.861009 -0.414584 -0.256461 -0.832503 -0.491088 -0.252771 -0.603246 -0.75644 -0.252743 -0.603222 -0.756469 -0.255513 -0.270453 -0.928207 -0.19693 -0.218188 -0.955831 -1.59825e-05 -0.195273 -0.980749 -0.000908366 -0.222546 -0.974922 0.000761256 -0.555551 -0.831482 -0.00154921 -0.623462 -0.781852 0.0012803 -0.831488 -0.555541 -4.13947e-06 -0.861309 -0.508081 -1.58971e-06 -0.980783 -0.195101 0.00268922 -0.993709 -0.111963 -2.47474e-06 -0.952762 -0.303719 0.440421 -0.192912 -0.876821 0.440343 -0.192755 -0.876894 0.4034 -0.438104 -0.803326 0.347497 -0.552661 -0.757503 0.151695 -0.193013 -0.969399 0.151636 -0.192919 -0.969427 0.128973 -0.550912 -0.824538 0.128867 -0.550765 -0.824652 0.0864883 -0.828373 -0.553459 0.086469 -0.828357 -0.553487 0.0304659 -0.980328 -0.195011 0.0304553 -0.980325 -0.195025 0.357718 -0.604049 -0.712154 0.275328 -0.789777 -0.54813 0.21662 -0.830462 -0.513234 0.200433 -0.894772 -0.39901 0.088599 -0.980327 -0.176378 0.08861 -0.980331 -0.176348 0.310804 -0.252721 -0.916261 0.0713709 -0.979483 -0.188463 0.0987388 -0.963382 -0.249289 0.160904 -0.890838 -0.424874 0.220183 -0.783258 -0.581401 0.259984 -0.694329 -0.671056 0.284462 -0.595694 -0.751152 0.352293 0.102429 -0.930268 0.594167 -0.440495 -0.673001 0.542064 -0.194904 -0.817422 0.602788 -0.699388 0.384061 0.196896 -0.979958 0.030227 0.4444 -0.89466 0.0457339 0.261042 -0.964495 0.0400752 0.222735 -0.964495 0.141913 0.222731 -0.964496 0.141911 0.146619 -0.964496 0.219659 0.146623 -0.964494 0.219664 0.0456261 -0.964495 0.260132 0.0456148 -0.964505 0.260094 0.602795 -0.699381 0.384064 0.396818 -0.699365 0.594495 0.396806 -0.699383 0.594482 0.123467 -0.699381 0.704005 0.123474 -0.69936 0.704024 0.971324 -0.191386 0.141071 0.890183 -0.434624 0.136661 0.706454 -0.6994 0.108455 0.791499 -0.601928 0.105886 0.609916 -0.786915 0.0936343 0.9561 -0.253629 0.146779 0.815786 -0.253641 0.519769 0.815806 -0.253573 0.519771 0.537027 -0.253556 0.804557 0.537003 -0.25365 0.804543 0.167097 -0.253651 0.952754 0.167096 -0.253655 0.952753 0.194791 -0.980786 -0.0107526 0.55473 -0.831467 -0.0306229 0.979293 -0.195096 -0.0540577 0.979299 -0.195065 -0.0540604 0.830212 -0.555561 -0.0458303 0.194797 -0.980785 -0.0107534 0.194797 -0.980785 -0.0107534 0.194791 -0.980786 -0.0107526 0.441626 -0.896868 -0.0243781 0.554896 -0.831472 -0.0272976 0.554716 -0.831477 -0.0306207 0.830197 -0.555583 -0.0458275 0.979293 -0.195096 -0.0540601 0.979293 -0.195096 -0.0540601 0.895509 -0.442289 -0.0494349 0.830391 -0.555558 -0.0425068 0.792157 -0.608748 -0.0437296 0.607837 -0.793352 -0.0335545 0.978664 -0.202313 -0.0358648 0.188992 -0.981954 -0.00698425 0.188714 -0.981948 -0.0128471 0.977477 -0.194994 -0.0807185 0.554034 -0.831408 -0.0425165 0.5877 -0.807821 -0.0450949 0.19447 -0.98077 -0.016506 0.216404 -0.976245 -0.0107367 0.319287 -0.947484 -0.0181484 0.830121 -0.555582 -0.0471986 0.826887 -0.560401 -0.0469975 0.21534 0.976463 -0.0121627 0.538856 -0.842164 -0.0198721 0.182069 -0.983262 -0.00676875 0.808637 -0.552593 -0.201858 0.274529 -0.835345 -0.476269 0.0748239 -0.99606 -0.0476036 0.181416 -0.983172 -0.0214559 0.0869307 -0.9958 -0.0287303 0.538246 -0.43876 -0.71957 0.0977003 -0.430025 -0.897515 0.0962747 -0.602953 -0.791946 0.0665438 -0.835356 -0.545666 0.0677722 -0.789507 -0.609988 0.0377245 -0.964269 -0.262224 0.0630728 -0.918828 -0.389585 0.0646787 -0.991584 -0.112152 0.27364 -0.836344 -0.475026 0.417821 -0.838577 -0.34959 0.306153 -0.92353 -0.231006 0.378256 -0.922315 -0.0791007 0.530741 -0.837115 -0.132487 0.808919 -0.552137 -0.201977 0.665328 -0.552185 -0.502424 0.666269 -0.550588 -0.50293 0.416646 -0.550603 -0.723355 0.417765 -0.547914 -0.724751 0.101278 -0.547944 -0.830361 0.118509 -0.184921 -0.975582 0.118853 -0.190714 -0.974424 0.489925 -0.190722 -0.850646 0.489814 -0.194936 -0.849754 0.782696 -0.194962 -0.591081 0.782404 -0.197609 -0.590588 0.951084 -0.19759 -0.237481 0.950942 -0.198396 -0.237378 0.20118 -0.42933 0.880456 0.467138 -0.837516 0.28346 0.183225 -0.982707 0.0267683 0.0454036 -0.996145 0.0750627 0.024847 -0.965761 0.258241 0.0457582 -0.987672 0.149699 0.718569 -0.404818 0.565492 0.540459 -0.837655 0.0789865 0.540708 -0.837492 0.0789983 0.824524 -0.552845 0.12051 0.393235 -0.916485 0.0736281 0.109409 -0.991779 0.0663708 0.467829 -0.836954 0.283979 0.339967 -0.839164 0.424531 0.225506 -0.922898 0.3121 0.0732009 -0.921839 0.380598 0.166071 -0.699171 0.695399 0.182448 -0.547934 0.816383 0.489336 -0.548378 0.678109 0.48857 -0.55092 0.676599 0.713407 -0.550906 0.433074 0.712644 -0.552397 0.432431 0.824836 -0.55238 0.120507 0.9699 -0.197983 0.141761 0.97006 -0.197226 0.141722 0.838024 -0.197217 0.508745 0.838536 -0.194816 0.508827 0.573932 -0.194841 0.795386 0.574688 -0.190661 0.795853 0.2184 -0.190636 0.957058 0.219078 -0.185056 0.957998 0.181315 -0.983374 -0.0100103 0.184925 -0.9827 -0.0102205 0.977921 -0.201862 -0.0540555 0.977312 -0.204804 -0.0540131 0.82682 -0.560608 -0.0456989 0.825808 -0.562102 -0.0456373 0.537648 -0.842645 -0.0297189 0.539705 -0.841325 -0.0298403 0.0631496 -0.991739 -0.111649 0.184174 -0.982613 -0.0234924 0.0633304 -0.789847 -0.610025 0.0359316 -0.964279 -0.26244 0.0616594 -0.915898 -0.396648 0.0912338 -0.430321 -0.898053 0.0906487 -0.60339 -0.792277 0.0625701 -0.836326 -0.54465 0.269783 -0.836309 -0.477289 0.268655 -0.837587 -0.475682 0.111594 -0.185082 -0.976366 0.0953829 -0.549309 -0.830158 0.411209 -0.549275 -0.727464 0.409765 -0.552769 -0.72563 0.660144 -0.552757 -0.508595 0.530449 -0.836281 -0.138776 0.375979 -0.922901 -0.0830278 0.0907362 -0.995397 -0.0308435 0.805181 -0.554311 -0.21077 0.546361 -0.39195 -0.740179 0.0732749 -0.99618 -0.0474989 0.412939 -0.839796 -0.352455 0.302775 -0.924106 -0.23314 0.65891 -0.554853 -0.507913 0.804878 -0.5548 -0.210639 0.112026 -0.192099 -0.974961 0.482527 -0.192104 -0.854555 0.482388 -0.197625 -0.853374 0.776365 -0.197646 -0.598493 0.77597 -0.201213 -0.597816 0.947668 -0.201176 -0.2479 0.947725 -0.200855 -0.247942 0.201542 -0.429331 0.880373 0.465223 -0.839005 0.282202 0.182346 -0.982874 0.0266308 0.0451792 -0.996185 0.0746645 0.0249201 -0.965756 0.258252 0.0458347 -0.987647 0.14984 0.722708 -0.392746 0.568722 0.537987 -0.839279 0.0786186 0.538443 -0.838985 0.0786404 0.821638 -0.557218 0.12008 0.393693 -0.916282 0.073711 0.108822 -0.991869 0.06598 0.466389 -0.838062 0.283077 0.338924 -0.840253 0.423209 0.225253 -0.923181 0.311444 0.0732559 -0.922139 0.37986 0.166327 -0.699183 0.695326 0.182566 -0.549509 0.815297 0.488809 -0.549947 0.677218 0.487575 -0.554011 0.67479 0.71168 -0.553974 0.432001 0.710372 -0.556502 0.430902 0.822166 -0.556439 0.120077 0.968464 -0.20504 0.141548 0.968742 -0.203766 0.141484 0.836893 -0.203728 0.50804 0.837783 -0.199645 0.508194 0.573451 -0.199637 0.794543 0.574636 -0.193149 0.795291 0.218568 -0.193125 0.95652 0.219546 -0.185059 0.95789 0.180445 -0.983535 -0.00996725 0.183584 -0.982952 -0.0101496 0.976412 -0.209057 -0.0539938 0.974986 -0.215631 -0.0538968 0.823848 -0.564977 -0.0455533 0.821372 -0.568583 -0.0454034 0.535155 -0.844236 -0.029593 0.535975 -0.843713 -0.0296412 0.182844 -0.982867 -0.0232446 0.0628902 -0.991822 -0.111061 0.0635496 -0.789826 -0.610029 0.03607 -0.96428 -0.262418 0.0622201 -0.915003 -0.398621 0.0914829 -0.430305 -0.898036 0.0909437 -0.603409 -0.792229 0.0627555 -0.837246 -0.543213 0.269259 -0.837206 -0.476011 0.267413 -0.839289 -0.473377 0.111891 -0.185152 -0.976319 0.0957353 -0.551733 -0.828508 0.410655 -0.551675 -0.72596 0.408345 -0.557237 -0.723009 0.657827 -0.557246 -0.506696 0.526819 -0.838728 -0.137825 0.373318 -0.924022 -0.0825657 0.090043 -0.995469 -0.0305669 0.800977 -0.560781 -0.209668 0.552873 -0.367153 -0.748017 0.0725875 -0.996253 -0.0470219 0.411056 -0.841467 -0.350666 0.300711 -0.925213 -0.231417 0.65567 -0.560867 -0.505495 0.800949 -0.560825 -0.209657 0.112567 -0.196068 -0.974108 0.482158 -0.196065 -0.853863 0.481905 -0.205188 -0.85186 0.775086 -0.205173 -0.597617 0.7744 -0.210994 -0.596478 0.945657 -0.210965 -0.247439 0.945557 -0.211497 -0.247368 0.261019 -0.964525 0.0395058 0.261015 -0.964526 0.0395055 0.706532 -0.699555 0.106936 0.706532 -0.699555 0.106936 0.956381 -0.253737 0.144751 0.956383 -0.253731 0.144751 0.220355 -0.964032 0.148614 0.220359 -0.964031 0.148616 0.594546 -0.696945 0.400979 0.594545 -0.696945 0.400978 0.802311 -0.252002 0.541102 0.802311 -0.252003 0.541102 0.134434 -0.964525 0.227198 0.134435 -0.964524 0.227201 0.363888 -0.699558 0.614983 0.363886 -0.699561 0.614981 0.49257 -0.253734 0.832462 0.492566 -0.253758 0.832458 0.258426 -0.965926 -0.0142658 0.258426 -0.965926 -0.0142658 0.706038 -0.707101 -0.038975 0.706037 -0.707102 -0.038975 0.964455 -0.258829 -0.0532403 0.964455 -0.258827 -0.0532403 0.721661 -0.441052 -0.533552 0.49056 -0.792343 -0.36269 0.208789 -0.965701 -0.154366 0.636721 -0.607558 -0.474826 0.787765 -0.19448 -0.584469 0.208788 -0.965701 -0.154365 0.231441 -0.965702 -0.11771 0.23144 -0.965702 -0.117709 0.24772 -0.965702 -0.0778135 0.247723 -0.965701 -0.0778145 0.257181 -0.965701 -0.0357749 0.257179 -0.965701 -0.0357747 0.569561 -0.705888 -0.421098 0.631359 -0.705887 -0.321107 0.631369 -0.705876 -0.321112 0.675779 -0.705876 -0.212275 0.675769 -0.705888 -0.212272 0.701567 -0.705889 -0.0975908 0.701577 -0.705879 -0.0975925 0.776875 -0.257991 -0.574374 0.861167 -0.25799 -0.437987 0.861163 -0.258007 -0.437984 0.921739 -0.258004 -0.289536 0.921744 -0.257986 -0.289537 0.956934 -0.257986 -0.133114 0.956932 -0.257995 -0.133113 -0.961137 -0.193493 -0.196919 -0.19271 -0.980461 -0.0394827 -0.192712 -0.980461 -0.0394832 -0.816706 -0.552261 -0.167328 -0.880398 -0.439296 -0.178658 -0.77967 -0.605473 -0.15974 -0.547501 -0.829253 -0.112173 -0.599713 -0.790859 -0.122008 -0.436288 -0.895356 -0.0893872 -0.1759 -0.980461 -0.0880684 -0.175896 -0.980462 -0.0880664 -0.499737 -0.829253 -0.250205 -0.499745 -0.829247 -0.250209 -0.745457 -0.552261 -0.37323 -0.745459 -0.552259 -0.373231 -0.108201 -0.980461 -0.164285 -0.1082 -0.980461 -0.164283 -0.307403 -0.829251 -0.46674 -0.307405 -0.829249 -0.466742 -0.458548 -0.552268 -0.696228 -0.458547 -0.552271 -0.696226 -0.539645 -0.193472 -0.81936 -0.061937 -0.980461 -0.186708 -0.0619378 -0.980461 -0.18671 -0.175969 -0.829248 -0.530455 -0.175966 -0.829254 -0.530446 -0.262487 -0.552271 -0.791263 -0.26249 -0.552259 -0.79127 0.0883854 -0.980461 -0.175739 0.0883854 -0.980461 -0.175739 0.251105 -0.829257 -0.499279 0.251109 -0.829251 -0.499286 0.37458 -0.55225 -0.744788 0.374576 -0.552264 -0.74478 0.440819 -0.193497 -0.876492 0.130902 -0.980461 -0.146835 0.130902 -0.980461 -0.146835 0.371903 -0.829251 -0.41717 0.371904 -0.82925 -0.417171 0.554764 -0.552263 -0.622288 0.554764 -0.552262 -0.622289 0.186818 -0.980461 -0.0615988 0.186818 -0.980461 -0.061599 0.530766 -0.829253 -0.175008 0.530776 -0.829245 -0.175012 0.791746 -0.552255 -0.26106 0.791728 -0.552285 -0.261054 0.93176 -0.193483 -0.307226 0.196399 -0.980461 -0.0110888 0.196399 -0.980461 -0.0110889 0.557996 -0.829246 -0.0315049 0.557994 -0.829247 -0.0315047 0.83233 -0.552285 -0.0469939 0.832333 -0.55228 -0.0469942 -0.750253 -0.194072 -0.632026 -0.852892 -0.194522 -0.484497 -0.36059 0.915085 -0.180537 -0.908833 -0.194831 -0.368867 -0.961139 -0.19348 -0.196919 -0.661102 -0.19502 -0.724507 -0.425194 0.822538 -0.377679 -0.623289 -0.552265 -0.553637 -0.623291 -0.552261 -0.553639 -0.417841 -0.829251 -0.371148 -0.417845 -0.829248 -0.371151 -0.147074 -0.980461 -0.130638 -0.14707 -0.980462 -0.130636 -0.108294 -0.194524 -0.974901 -0.284366 -0.194072 -0.938867 -0.179064 0.822539 -0.539784 -0.404537 -0.195021 -0.893486 -0.539645 -0.193475 -0.81936 0.0200288 -0.194839 -0.980631 -0.02346 0.915085 -0.402579 -0.0484997 -0.552251 -0.832266 -0.0484992 -0.552261 -0.83226 -0.0325128 -0.829252 -0.557929 -0.0325125 -0.829254 -0.557925 -0.0114438 -0.980461 -0.19638 -0.011444 -0.980461 -0.196382 0.0398309 -0.980461 -0.192638 0.0398311 -0.980461 -0.192639 0.113162 -0.829252 -0.547298 0.113161 -0.829257 -0.547291 0.168805 -0.552251 -0.816409 0.168806 -0.552247 -0.816411 0.198656 -0.193487 -0.96078 0.198656 -0.1935 -0.960778 0.805854 -0.194057 -0.559411 0.690206 -0.194508 -0.696981 0.268348 0.915085 -0.301011 0.593169 -0.194835 -0.781146 0.44082 -0.193482 -0.876495 0.871874 -0.195029 -0.449221 0.475516 0.822539 -0.311953 0.697062 -0.552256 -0.457294 0.697058 -0.552264 -0.457291 0.467293 -0.829253 -0.306558 0.467294 -0.829252 -0.306559 0.164477 -0.980461 -0.107902 0.164478 -0.980461 -0.107902 0.9694 -0.194511 0.149764 0.980542 -0.194061 -0.0296122 0.567802 0.822541 -0.0320585 0.96808 -0.195006 -0.157461 0.931764 -0.193462 -0.307228 0.941454 -0.194841 0.275138 0.39476 0.915085 0.0823669 0.816099 -0.552257 0.17028 0.816083 -0.552281 0.170277 0.547092 -0.829253 0.114151 0.547101 -0.829247 0.114153 0.192571 -0.98046 0.04018 0.192565 -0.980461 0.040179 0.175583 -0.98046 0.0887046 0.175577 -0.980461 0.088702 0.49883 -0.829252 0.25201 0.498836 -0.829248 0.252013 0.744105 -0.552258 0.375923 0.744102 -0.552264 0.375922 0.875695 -0.193488 0.442403 0.875695 -0.193488 0.442403 -0.946019 -0.191406 -0.261556 -0.867765 -0.435227 -0.239921 -0.931737 -0.254147 -0.259375 -0.759806 -0.254063 -0.598454 -0.770237 -0.601152 -0.212956 -0.687437 -0.700279 -0.192457 -0.594087 -0.787452 -0.164254 -0.433129 -0.893342 -0.119752 -0.253339 -0.964704 -0.0718676 -0.191662 -0.980029 -0.052991 -0.759808 -0.254057 -0.598454 -0.627791 -0.601144 -0.494473 -0.562229 -0.700279 -0.439896 -0.484212 -0.787455 -0.381384 -0.207126 -0.964616 -0.163141 -0.207125 -0.964617 -0.163139 -0.951324 -0.258802 0.167343 -0.966153 -0.19508 0.168795 -0.781188 -0.608787 0.138287 -0.818896 -0.555572 0.144048 -0.599568 -0.793344 0.105467 -0.54707 -0.83147 0.0968155 -0.255056 -0.965925 0.0439943 -0.192139 -0.980786 0.0337983 -0.260661 -0.965365 0.0112684 -0.709475 -0.704063 0.0306705 -0.943476 -0.256755 -0.209595 -0.943477 -0.256753 -0.209591 -0.693237 -0.704064 -0.154001 -0.693258 -0.704053 -0.15396 -0.254698 -0.965365 -0.0565637 -0.621915 -0.741227 -0.252595 -0.795112 -0.605488 0.0343572 -0.965574 -0.256762 0.041723 -0.965579 -0.256733 0.0417878 -0.907568 -0.25882 -0.330655 -0.907568 -0.25882 -0.330656 -0.664376 -0.707117 -0.242053 -0.664361 -0.707098 -0.24215 -0.243174 -0.965925 -0.0886334 -0.243175 -0.965926 -0.088618 -0.252999 -0.965926 0.05457 -0.190021 -0.980781 0.0442903 -0.595604 -0.793338 0.125976 -0.54308 -0.83147 0.117139 -0.775517 -0.608764 0.167274 -0.81312 -0.55557 0.173718 -0.943695 -0.258818 0.206039 -0.95874 -0.195076 0.206793 -0.958866 -0.195076 0.206208 -0.956516 -0.207244 0.20525 -0.828372 -0.531632 0.176539 -0.813011 -0.55557 0.174225 -0.546657 -0.82919 0.116659 -0.543306 -0.83147 0.116091 -0.193586 -0.980203 0.0415599 -0.190723 -0.980785 0.0410491 -0.953708 -0.212614 0.212687 -0.963297 -0.20744 0.170377 -0.963226 -0.165622 0.211578 -0.809152 -0.559276 0.180232 -0.827211 -0.531625 0.181924 -0.53049 -0.839422 0.118115 -0.545884 -0.829185 0.120264 -0.181714 -0.982517 0.0405023 -0.193417 -0.980202 0.042362 -0.181649 -0.982518 0.0407733 -0.954038 -0.212594 0.211222 -0.523633 -0.843921 0.116646 -0.80935 -0.559273 0.17935 -0.805889 -0.564302 0.179184 -0.954907 -0.208039 0.211832 -0.176754 -0.983494 0.0386985 -0.181829 -0.982484 0.0407811 -0.530658 -0.83942 0.117374 -0.956139 -0.205878 0.208358 -0.180854 -0.982724 0.0393127 -0.176817 -0.983494 0.0384077 -0.530228 -0.83998 0.115288 -0.524225 -0.843924 0.11393 -0.809388 -0.560293 0.175962 -0.806727 -0.564309 0.175348 -0.959881 -0.187315 0.208665 -0.955836 -0.20804 0.2076 -0.173427 -0.982149 0.072848 0 -1 0 -0.0493675 -0.994476 0.0926291 -0.0616302 -0.60231 0.79588 -0.0427549 -0.788802 0.613159 -0.0247612 -0.964612 0.262509 -0.0933422 -0.659364 0.746007 -0.0611308 -0.430037 0.900739 -0.0757963 -0.184334 0.979937 -0.0649318 -0.546803 0.83474 -0.358694 -0.546772 0.756558 -0.35746 -0.550287 0.75459 -0.603485 -0.550286 0.577054 -0.277309 -0.923445 0.265236 -0.360041 -0.922599 0.138493 -0.506229 -0.835782 0.212605 -0.0428852 -0.833147 0.551386 -0.215616 -0.834809 0.506561 -0.164953 -0.923011 0.347623 -0.278199 -0.922988 0.265892 -0.602201 -0.552702 0.576086 -0.768341 -0.55269 0.322779 -0.767675 -0.553834 0.322403 -0.0761272 -0.191104 0.978613 -0.420188 -0.191106 0.887086 -0.420032 -0.196822 0.885909 -0.708451 -0.196812 0.677763 -0.708042 -0.200784 0.677025 -0.903173 -0.200772 0.379432 -0.902872 -0.202589 0.379183 -0.0507052 -0.185115 0.981408 -0.0411219 -0.603996 0.795925 -0.0465589 -0.430978 0.90116 -0.0135089 -0.96512 0.261458 -0.0316556 -0.789698 0.612678 -0.32925 -0.186553 -0.925631 -0.0542355 -0.25603 0.965146 -0.422614 -0.25168 0.870663 -0.422614 -0.251673 0.870665 -0.780887 -0.251673 0.571731 -0.780889 -0.251662 0.571734 -0.957647 -0.251674 0.139902 -0.957646 -0.251679 0.139901 -0.911806 -0.25168 -0.324448 -0.911809 -0.251671 -0.324449 -0.654026 -0.251666 -0.713382 -0.654026 -0.251668 -0.713382 -0.32802 -0.256017 -0.909317 -0.302221 -0.432161 -0.849647 -0.0421851 -0.70315 0.709789 -0.313358 -0.696446 0.645577 -0.313361 -0.696438 0.645584 -0.579013 -0.69644 0.423929 -0.579012 -0.696441 0.423928 -0.710077 -0.696441 0.103734 -0.710068 -0.69645 0.103732 -0.676079 -0.696451 -0.240569 -0.676092 -0.696437 -0.240572 -0.48495 -0.696436 -0.528961 -0.48494 -0.69645 -0.528952 -0.238432 -0.702729 -0.670315 -0.238431 -0.702732 -0.670312 -0.0135087 -0.965118 0.261465 -0.116212 -0.963936 0.239419 -0.116215 -0.963934 0.239425 -0.214736 -0.963935 0.15722 -0.214732 -0.963936 0.157217 -0.263341 -0.963936 0.0384709 -0.263343 -0.963935 0.0384713 -0.250736 -0.963935 -0.089219 -0.25073 -0.963937 -0.0892171 -0.179843 -0.963938 -0.196166 -0.179848 -0.963936 -0.19617 -0.0877425 -0.965118 -0.246675 -0.0877442 -0.965117 -0.246679 -0.339704 -0.42938 -0.8368 -0.505258 -0.838382 -0.204524 -0.184621 -0.982806 0.00288114 -0.0566546 -0.996169 -0.0666157 -0.065888 -0.965757 -0.250942 -0.0692092 -0.987646 -0.14059 -0.802584 -0.397461 -0.444841 -0.544679 -0.838602 0.00845882 -0.545052 -0.838359 0.00850131 -0.831457 -0.55544 0.0129011 -0.4004 -0.916288 -0.00979952 -0.118237 -0.991832 -0.0478366 -0.506368 -0.83757 -0.205106 -0.402844 -0.839765 -0.364021 -0.272385 -0.923038 -0.271675 -0.133157 -0.921988 -0.363603 -0.27538 -0.699178 -0.659785 -0.31076 -0.548742 -0.776087 -0.591213 -0.549186 -0.590645 -0.58986 -0.552621 -0.588791 -0.772472 -0.552598 -0.312927 -0.771223 -0.55476 -0.312181 -0.831926 -0.554735 0.0129802 -0.979241 -0.202132 0.0151897 -0.979458 -0.201069 0.0152798 -0.907895 -0.201092 -0.367816 -0.908681 -0.197501 -0.36782 -0.693486 -0.197509 -0.692869 -0.694587 -0.191937 -0.693332 -0.368839 -0.191912 -0.909466 -0.369836 -0.185122 -0.910468 -0.176877 -0.983469 0.038774 -0.180688 -0.982742 0.0396208 -0.955822 -0.206093 0.209593 -0.955707 -0.206655 0.209566 -0.807147 -0.563196 0.176987 -0.808759 -0.560764 0.17735 -0.52455 -0.843575 0.115015 -0.529766 -0.840149 0.116178 -0.0444511 -0.991752 0.120218 -0.17783 -0.982656 0.0525799 0.027304 -0.826351 0.562493 0.00829127 -0.979978 0.198932 0.00255974 -0.915773 0.401688 0.0602281 -0.371934 0.926303 0.0393508 -0.547864 0.835642 0.0250448 -0.836513 0.547375 -0.189901 -0.836465 0.514067 -0.188935 -0.837903 0.512076 0.0460046 -0.1851 0.981642 0.0385675 -0.549663 0.834495 -0.289493 -0.549624 0.78365 -0.288269 -0.553403 0.781438 -0.569996 -0.553408 0.607325 -0.503013 -0.835064 0.222815 -0.357433 -0.923086 0.141962 -0.0845155 -0.99541 0.0448939 -0.761913 -0.552962 0.337226 -0.421668 -0.388396 0.819357 -0.0646356 -0.996192 0.0585161 -0.350953 -0.840098 0.413602 -0.261289 -0.924289 0.278242 -0.568705 -0.555842 0.606312 -0.76031 -0.555783 0.336207 0.0452878 -0.19282 0.980189 -0.339553 -0.192824 0.92061 -0.339609 -0.198933 0.919289 -0.670432 -0.198937 0.714804 -0.67012 -0.20284 0.713999 -0.895495 -0.202795 0.396186 -0.895511 -0.202692 0.396202 -0.240807 -0.824604 0.511899 -0.356765 -0.545484 0.758397 -0.373987 -0.368023 -0.851289 0.0175816 -0.183977 0.982773 0.0172996 -0.190137 0.981605 -0.38297 -0.191646 0.903662 -0.307041 -0.692616 0.652694 -0.395343 -0.184111 -0.899893 -0.395111 -0.190233 -0.898721 -0.726012 -0.19173 -0.660414 -0.552015 -0.692631 -0.464266 -0.856322 -0.194966 -0.478228 -0.953213 -0.190201 -0.234963 -0.953211 -0.190214 -0.234963 -0.958951 -0.1902 0.210327 -0.958955 -0.190176 0.210329 -0.767378 -0.190164 0.612346 -0.767371 -0.190221 0.612338 -0.577552 -0.194985 0.792726 -0.356772 -0.545455 0.758415 -0.655127 -0.545451 0.522773 -0.655117 -0.545471 0.522764 -0.818682 -0.545452 0.179562 -0.818692 -0.545435 0.179565 -0.8138 -0.545426 -0.200599 -0.813799 -0.545427 -0.200598 -0.641459 -0.545416 -0.539492 -0.641457 -0.54542 -0.539491 -0.337125 -0.545409 -0.767382 -0.337134 -0.545382 -0.767398 -0.240824 -0.824573 0.511941 -0.442211 -0.82458 0.352871 -0.442214 -0.824577 0.352874 -0.552594 -0.824591 0.121202 -0.552581 -0.8246 0.121198 -0.549279 -0.824597 -0.135395 -0.549277 -0.824599 -0.135395 -0.432947 -0.824602 -0.364126 -0.432961 -0.824591 -0.364136 -0.227548 -0.824589 -0.517953 -0.227538 -0.824604 -0.517933 0.00357999 -0.979771 0.20009 0.00357916 -0.979774 0.200077 0.0101183 -0.824606 0.565616 0.0101183 -0.824606 0.565617 0.0149907 -0.545484 0.837987 0.0149941 -0.545431 0.838021 0.0166284 -0.368791 0.929363 -0.0601101 -0.980592 0.18662 -0.234578 0.834451 0.498663 -0.101155 -0.98048 0.168602 -0.156397 -0.979778 0.1248 -0.156403 -0.979776 0.124806 -0.195456 -0.979775 0.0428696 -0.195458 -0.979775 0.0428699 -0.194291 -0.979774 -0.0478921 -0.194291 -0.979774 -0.0478921 -0.153148 -0.979773 -0.128804 -0.153142 -0.979775 -0.128799 -0.0804856 -0.979774 -0.183206 -0.0804826 -0.979776 -0.183199 -0.349498 -0.369984 -0.860792 -0.5038 -0.839411 -0.203897 -0.184021 -0.982918 0.00288295 -0.0564567 -0.996196 -0.0663723 -0.049702 -0.98069 -0.189149 -0.045732 -0.994628 -0.0928653 -0.805423 -0.389968 -0.446339 -0.542992 -0.839696 0.00845548 -0.543475 -0.839382 0.00851023 -0.829518 -0.558331 0.0129059 -0.400439 -0.916271 -0.00977359 -0.117802 -0.991893 -0.0476458 -0.505204 -0.838388 -0.204633 -0.401892 -0.840568 -0.363219 -0.272069 -0.923261 -0.271232 -0.13154 -0.92207 -0.363983 -0.212345 -0.826184 -0.521853 -0.314292 -0.547788 -0.775338 -0.313887 -0.55042 -0.773636 -0.59061 -0.550496 -0.590029 -0.588912 -0.554786 -0.587704 -0.77113 -0.554772 -0.312388 -0.769528 -0.557528 -0.311432 -0.830077 -0.557497 0.0129995 -0.978247 -0.206885 0.0152095 -0.978534 -0.205517 0.0153253 -0.907036 -0.205549 -0.367473 -0.908033 -0.201071 -0.367486 -0.692968 -0.201078 -0.69236 -0.694379 -0.194005 -0.692965 -0.368756 -0.193981 -0.90906 -0.370047 -0.185195 -0.910367 -0.95381 -0.215555 0.209242 -0.953986 -0.214748 0.209272 -0.954805 -0.210912 0.209436 -0.954675 -0.211532 0.209403 -0.80519 -0.566108 0.176611 -0.806986 -0.563417 0.177015 -0.522906 -0.84464 0.114687 -0.528496 -0.840982 0.115936 -0.176301 -0.983577 0.038658 -0.180304 -0.982816 0.0395484 0.172743 -0.0918523 0.980675 -0.427457 -0.864362 0.264876 -0.736118 0.444939 0.510059 -0.074635 -0.99404 0.079456 -0.10738 -0.983493 0.145638 -0.516042 -0.83973 0.168976 -0.151987 -0.987099 0.0503595 -0.177471 -0.982731 0.0523868 -0.43485 -0.85769 0.27436 -0.419371 -0.874185 0.244802 -0.567067 -0.559153 0.6048 -0.565607 -0.562913 0.602676 -0.671314 0.188903 0.716696 -0.772659 -0.21825 0.596125 0.0443097 -0.279406 0.95915 0.0386732 -0.54779 0.835722 0.0390213 -0.55289 0.83234 0.0254861 -0.826213 0.562781 0.0262769 -0.837586 0.545672 0.0081749 -0.979983 0.198914 0.00233304 -0.914469 0.40465 -0.640161 -0.209615 0.739091 -0.444474 -0.211553 0.870453 -0.267547 0.51033 0.817302 -0.267294 -0.10555 0.957817 -0.0255208 -0.105421 0.9941 -0.371358 -0.839946 0.395708 -0.3697 -0.841361 0.39425 -0.442457 -0.846175 0.297018 -0.797764 -0.279097 0.534488 -0.489382 -0.815626 0.308641 -0.452591 -0.845746 0.282623 -0.433327 -0.859642 0.270635 -0.432032 -0.861211 0.2677 -0.428972 -0.864721 0.261229 -0.380941 -0.894998 0.232085 -0.304359 -0.935795 0.177913 -0.192694 -0.976413 0.0974017 -0.376963 -0.906587 0.189734 -0.31872 -0.937159 0.141955 -0.756018 -0.562796 0.334212 -0.760173 -0.555592 0.33683 -0.893324 -0.214225 0.395071 -0.893795 -0.211404 0.395524 0.0338935 0.732943 0.679445 0.0439534 -0.285367 0.95741 -0.331681 -0.285366 0.899197 -0.288875 -0.552915 0.78156 -0.286853 -0.55912 0.777882 -0.189345 -0.837668 0.512309 -0.18781 -0.839947 0.509133 -0.0441974 -0.991863 0.119395 -0.070109 -0.983188 0.168601 0.00356737 -0.979783 0.200031 0.0100842 -0.824641 0.565566 0.0177578 -0.0897238 0.995808 0.0149458 -0.545422 0.838028 0.0171297 -0.277823 0.960479 0.0154396 -0.190341 0.981597 -0.382121 -0.191762 0.903997 -0.306914 -0.69128 0.654168 -0.576403 -0.19493 0.793576 -0.766083 -0.190196 0.613956 -0.766079 -0.190226 0.613952 -0.958273 -0.190223 0.213375 -0.958274 -0.190216 0.213376 -0.954203 -0.190214 -0.230901 -0.954204 -0.19021 -0.230901 -0.858648 -0.19494 -0.474049 -0.555499 -0.691253 -0.462158 -0.729591 -0.191703 -0.656466 -0.400637 -0.190183 -0.896282 -0.400623 -0.190294 -0.896264 0.0149414 -0.545493 0.837982 -0.355985 -0.545489 0.75876 -0.355986 -0.545484 0.758763 -0.654009 -0.545485 0.524136 -0.654004 -0.545495 0.524132 -0.818082 -0.54549 0.18216 -0.818085 -0.545485 0.182161 -0.81461 -0.545485 -0.197121 -0.814604 -0.545495 -0.19712 -0.644282 -0.545508 -0.536024 -0.644289 -0.545494 -0.536029 -0.342018 -0.545493 -0.765154 -0.342018 -0.545495 -0.765153 0.0100871 -0.824612 0.565609 -0.240276 -0.824614 0.512133 -0.240264 -0.824634 0.512105 -0.441404 -0.824635 0.35375 -0.441422 -0.824619 0.353766 -0.552157 -0.824625 0.122947 -0.552138 -0.824639 0.122942 -0.549815 -0.824623 -0.133046 -0.549799 -0.824634 -0.133043 -0.434846 -0.824636 -0.361779 -0.434859 -0.824626 -0.361788 -0.230843 -0.824625 -0.516436 -0.230849 -0.824615 -0.516449 0.00356927 -0.979777 0.200061 -0.084988 -0.979777 0.181145 -0.0849886 -0.979777 0.181147 -0.156135 -0.979778 0.12513 -0.156125 -0.97978 0.125121 -0.195295 -0.97978 0.0434855 -0.195299 -0.979779 0.0434864 -0.194465 -0.97978 -0.0470575 -0.19447 -0.979779 -0.0470585 -0.153815 -0.979778 -0.127969 -0.153806 -0.97978 -0.127962 -0.0816473 -0.97978 -0.182659 -0.0816456 -0.979781 -0.182655 -0.540412 -0.127406 -0.831699 -0.310929 -0.801948 -0.510101 -0.160167 -0.830184 -0.533987 -0.0499197 -0.985697 -0.160964 -0.0514774 -0.980684 -0.188706 -0.186936 -0.982361 0.00464162 -0.394803 -0.918751 -0.00510042 -0.117546 -0.991991 -0.0462262 -0.166994 -0.983214 -0.0735038 -0.143227 -0.983534 -0.110213 -0.504447 -0.840244 -0.198803 -0.502459 -0.841674 -0.197787 -0.539865 -0.841626 0.0145626 -0.545268 -0.838142 0.0141949 -0.277059 -0.849245 -0.449468 -0.294497 -0.842843 -0.45043 -0.249669 -0.862572 -0.44004 -0.284342 -0.194898 -0.938703 -0.463714 -0.194928 -0.864275 -0.392765 -0.559164 -0.730117 -0.594565 -0.553302 -0.583395 -0.964036 -0.219578 0.149731 -0.932458 0.360427 0.0247691 -0.462376 -0.419293 -0.781282 -0.708039 0.291775 -0.643077 -0.697438 -0.209023 -0.685485 -0.860233 -0.212443 -0.463537 -0.861448 0.376951 -0.340317 -0.934102 -0.218155 -0.282597 -0.974898 -0.217906 -0.045739 -0.282646 -0.846819 -0.450566 -0.398207 -0.66026 -0.636779 -0.339364 -0.761948 -0.551604 -0.313939 -0.79795 -0.514508 -0.27419 -0.850542 -0.448774 -0.273822 -0.850712 -0.448677 -0.271333 -0.851882 -0.447969 -0.291824 -0.826058 -0.482148 -0.184875 -0.927586 -0.324661 -0.0940843 -0.976023 -0.196283 -0.18288 -0.90405 -0.386326 -0.137083 -0.934843 -0.327533 -0.380654 0.045404 -0.923602 -0.240391 -0.553625 -0.797315 -0.284271 -0.194198 -0.93887 -0.827432 -0.561143 0.0217889 -0.825791 -0.563547 0.0219863 -0.768641 -0.563608 -0.302552 -0.770977 -0.559673 -0.303907 -0.591098 -0.55963 -0.580877 -0.38698 -0.84028 -0.379705 -0.389356 -0.83789 -0.382548 -0.0783414 -0.993968 -0.0767529 -0.509677 0.393804 -0.764949 -0.180779 -0.982578 0.0431259 -0.178309 -0.983056 0.0425179 -0.529904 -0.83858 0.126432 -0.522981 -0.843171 0.124714 -0.808143 -0.556524 0.192835 -0.799932 -0.568966 0.190755 -0.953109 -0.199635 0.227439 -0.948865 -0.220133 0.226269 -0.183295 -0.982302 0.0385395 -0.181959 -0.982562 0.0382484 -0.537053 -0.835955 0.112932 -0.533301 -0.838464 0.112107 -0.817599 -0.549519 0.171935 -0.813178 -0.556346 0.17094 -0.96109 -0.188293 0.202118 -0.95893 -0.199546 0.201579 0.0190926 -0.547648 0.836491 0.00364031 -0.979974 0.199092 -0.784391 0.340322 0.518568 -0.823898 -0.199887 0.530319 -0.573869 -0.739427 0.352025 -0.528833 -0.834757 0.15335 -0.159628 -0.986072 0.0466908 -0.181517 -0.98221 0.0481245 0.0221612 -0.185113 0.982467 0.0221779 -0.184919 0.982503 -0.365057 -0.185615 0.912294 -0.365054 -0.185128 0.912394 -0.311611 -0.544453 0.778762 0.0189027 -0.544434 0.83859 0.0377481 -0.368788 0.928747 -0.00620571 -0.921864 0.387463 -0.0485362 -0.99143 0.121291 -0.204878 -0.83417 0.51204 -0.389236 -0.834172 0.390708 -0.591852 -0.544746 0.594108 -0.693471 -0.185875 0.696095 -0.693492 -0.185604 0.696147 -0.59189 -0.544674 0.594136 -0.31154 -0.544664 0.778643 -0.204905 -0.834133 0.512091 0.012224 -0.834145 0.551409 0.0136746 -0.82625 0.563138 -0.456991 -0.842572 0.28501 -0.446451 -0.859301 0.249565 -0.911308 -0.184638 0.368002 -0.911141 -0.185795 0.367834 -0.779337 -0.541781 0.314813 -0.777692 -0.544705 0.313832 -0.329304 -0.934748 0.133438 -0.391692 -0.901971 0.18173 -0.191078 -0.977535 0.0889608 -0.313663 -0.933169 0.175532 -0.483336 -0.825897 0.290311 -0.45522 -0.847344 0.273465 -0.456569 -0.844404 0.280226 -0.456801 -0.843525 0.282488 -0.612123 -0.694416 0.378275 -0.658389 -0.631042 0.410256 -0.660938 -0.627207 0.412035 -0.456998 -0.842523 0.285145 -0.456908 -0.839331 0.294548 -0.389159 -0.834237 0.390645 -0.0792562 -0.993675 0.0795542 -0.41714 -0.486709 0.767534 0.0144508 -0.184627 0.982702 0.0141089 -0.191053 0.981478 0.0029285 -0.979949 0.199226 0.00293002 -0.979945 0.199248 0.0082939 -0.825729 0.564005 0.0082941 -0.825728 0.564008 0.0123098 -0.546936 0.837084 0.0123054 -0.546999 0.837043 0.013673 -0.367128 0.93007 -0.386234 -0.191036 0.902402 -0.386237 -0.19091 0.902427 -0.329403 -0.546948 0.769637 -0.329362 -0.547153 0.769509 -0.221954 -0.825729 0.518564 -0.221967 -0.825703 0.5186 -0.078402 -0.979949 0.183178 -0.0784074 -0.979945 0.183192 -0.720066 -0.190927 0.667122 -0.720068 -0.190905 0.667126 -0.614022 -0.547135 0.568877 -0.614022 -0.547135 0.568877 -0.413799 -0.825708 0.383375 -0.413815 -0.825692 0.383392 -0.146176 -0.979945 0.13543 -0.146183 -0.979943 0.135437 -0.929229 -0.190944 0.316345 -0.929219 -0.191005 0.316339 -0.792403 -0.547107 0.269762 -0.792421 -0.547077 0.26977 -0.533999 -0.825709 0.181793 -0.53399 -0.825716 0.18179 -0.188649 -0.979942 0.064223 -0.188645 -0.979943 0.0642214 -0.959147 -0.258808 0.11426 -0.974027 -0.195097 0.114927 -0.787689 -0.608756 0.0946682 -0.825632 -0.55557 0.0983548 -0.60448 -0.793359 0.0720097 -0.55161 -0.831466 0.0662689 -0.257102 -0.965925 0.0297941 -0.193719 -0.980786 0.0230771 0.211533 -0.971808 -0.10413 0.231673 -0.965926 -0.115392 0.546563 -0.793307 -0.268203 0.529556 -0.807225 -0.260688 0.689143 -0.640311 -0.33924 0.711406 -0.608811 -0.35107 0.796546 -0.460881 -0.391285 0.868762 -0.242953 -0.43154 0.865364 -0.258847 -0.429119 0.895055 -0.0689149 -0.440599 0.97449 -0.0686614 -0.213671 0.95837 -0.195083 -0.208492 0.947644 -0.242885 -0.207313 0.866735 -0.460983 -0.190433 0.81256 -0.555556 -0.176364 0.75017 -0.64046 -0.164487 0.542666 -0.831479 -0.118983 0.576501 -0.8075 -0.12486 0.190173 -0.980783 -0.0435663 0.230454 -0.97177 -0.0505301 0.958028 -0.195083 -0.210061 0.958026 -0.195091 -0.210061 0.812184 -0.555557 -0.178083 0.81216 -0.555594 -0.178076 0.542665 -0.831479 -0.118986 0.54269 -0.831462 -0.118992 0.190564 -0.980785 -0.0417839 0.190565 -0.980785 -0.0417839 0.0220777 -0.999742 -0.00535702 0.0420363 -0.999072 -0.00935427 0.191762 -0.98077 -0.0363098 0.962828 -0.195037 -0.186876 0.962524 -0.154764 -0.2227 0.183015 -0.982186 -0.0426087 0.0486445 -0.998759 -0.0106851 0.542492 -0.831616 -0.118814 0.542717 -0.831462 -0.118864 0.827467 -0.531449 -0.181275 0.81221 -0.555592 -0.177856 0.425588 0.900075 -0.0934892 0.148038 0.988345 -0.0354697 0.962829 -0.169209 -0.210545 0.181912 -0.982516 -0.0396224 0.186959 -0.981512 -0.0409998 0.186604 -0.981583 -0.0409225 0.184825 -0.981935 -0.0405357 0.183629 -0.98217 -0.0402777 0.183532 -0.982189 -0.0402583 0.183531 -0.982189 -0.0402581 0.269251 -0.961259 -0.0590313 0.225012 -0.973109 -0.0492819 0.537754 -0.834836 -0.117774 0.542475 -0.831627 -0.118814 0.821995 -0.540292 -0.180025 0.827481 -0.53144 -0.181236 0.915828 -0.34789 -0.20058 0.965008 -0.154781 -0.211666 0.181883 -0.982516 -0.0397527 0.185505 -0.981775 -0.0413095 0.182151 -0.982467 -0.0397539 0.537478 -0.834834 -0.119041 0.5435 -0.830856 -0.119526 0.821638 -0.54029 -0.181654 0.824721 -0.535565 -0.181672 0.962384 -0.169202 -0.212575 0.963094 -0.165444 -0.212316 0.806534 -0.566696 -0.168398 0.959367 -0.209584 -0.188918 0.961858 -0.16548 -0.217818 0.96185 -0.168267 -0.21571 0.946785 -0.245914 -0.207663 0.935282 -0.289214 -0.203966 0.543973 -0.830849 -0.117402 0.517292 -0.848458 -0.111931 0.518089 -0.848459 -0.10817 0.520193 -0.847117 -0.108589 0.175169 -0.983912 -0.0351144 0.172619 -0.984331 -0.0359986 0.177115 -0.983495 -0.0369718 0.167374 -0.985232 -0.0361224 0.185754 -0.981772 -0.0402328 0.177946 -0.983442 -0.0343142 0.178116 -0.983409 -0.0343657 0.952862 -0.223151 -0.205568 0.953247 -0.22097 -0.206134 0.951377 -0.231193 -0.203548 0.957016 -0.205822 -0.204345 0.965391 -0.166216 -0.200977 0.950057 -0.240922 -0.198365 0.803962 -0.570509 -0.167823 0.803115 -0.570511 -0.171824 0.747632 -0.644188 -0.161458 0.824996 -0.535562 -0.18043 0.188698 -0.981347 -0.0367558 0.271056 -0.961057 -0.053842 0.526541 -0.843688 -0.104621 0.521228 -0.847114 -0.103539 0.809514 -0.564643 -0.160829 0.808138 -0.566691 -0.160546 0.854052 -0.49174 -0.169667 0.952486 -0.23513 -0.193609 0.873474 -0.237885 0.424798 0.420485 -0.890754 0.172478 0.907862 -0.229511 0.350873 0.461549 -0.880986 0.104098 0.499456 -0.858812 0.113952 0.935542 -0.2192 0.27697 0.977794 -0.204851 -0.044208 0.978703 -0.204728 0.0150832 0.391024 -0.920107 0.0224301 0.976177 -0.194492 0.0961875 0.968268 -0.194612 0.156793 0.821424 -0.563316 -0.0890887 0.178359 -0.983408 -0.0331086 0.586843 -0.807201 -0.0635743 0.169515 -0.98538 -0.0170802 0.169894 -0.98546 -0.0021691 0.334799 -0.942276 0.00513241 0.0739115 -0.997251 0.00518753 0.17424 -0.984556 0.0170062 0.172283 -0.984561 0.0309398 0.36415 -0.926099 0.0986722 0.161903 -0.985691 0.0469134 0.165044 -0.983953 0.0678013 0.156408 -0.985594 0.0643474 0.488606 -0.849128 0.200613 0.474278 -0.858523 0.194934 0.493957 -0.859092 0.134043 0.389355 0.916761 0.0891792 0.164002 -0.985664 0.0396201 0.21365 -0.976122 0.0392319 0.526419 -0.844758 0.0962709 0.53255 -0.84476 0.0526399 0.405025 0.914034 0.0222843 0.516999 -0.855952 0.00763407 0.514957 -0.85538 -0.0560724 0.535021 -0.842846 -0.0579833 0.969818 -0.209217 -0.125224 0.475083 -0.87843 -0.0515395 0.815691 -0.571665 -0.0885811 0.81921 -0.571589 0.0466951 0.830845 -0.554505 0.0471227 0.811663 -0.554504 0.183652 0.79335 -0.581595 0.179841 0.752503 -0.581574 0.309049 0.753165 -0.580579 0.309307 0.692066 -0.580666 0.428803 0.104981 -0.990773 0.0857156 0.291111 0.922444 0.253675 0.128113 -0.983895 0.124647 0.119964 -0.983884 0.13259 0.134296 -0.979623 0.149342 0.0978116 -0.987013 0.127427 0.0421375 -0.985587 0.163835 0.0612119 -0.98551 0.158188 0.0654118 -0.983501 0.168662 0.091567 -0.983499 0.156032 0.0852267 -0.985674 0.145542 0.102259 -0.985748 0.133581 -0.036804 -0.986018 0.162526 -0.0191071 -0.985934 0.16604 -0.0200215 -0.98438 0.174917 0.00861234 -0.982881 0.184041 0.00772859 -0.985557 0.169167 0.0284805 -0.985631 0.166497 -0.0848045 -0.962152 0.258984 -0.0877073 -0.98865 0.121975 -0.0483056 -0.996487 0.0684192 -0.236795 -0.829216 0.506289 -0.0685144 -0.986255 0.150354 -0.053579 -0.986316 0.155916 -0.0947812 -0.991135 0.0930978 -0.114296 -0.987216 0.111095 -0.126957 -0.987159 0.0969466 -0.20491 -0.966431 0.154993 -0.110333 -0.992153 0.0588226 -0.141839 -0.987047 0.0749591 -0.149417 -0.987117 0.0572184 -0.50369 -0.859927 0.0825988 -0.49601 -0.864511 0.0812135 -0.781895 -0.610135 0.127969 -0.576851 0.793557 0.193675 -0.481852 -0.865019 0.13986 -0.154924 -0.986886 0.045331 -0.159728 -0.986818 0.0260179 -0.169892 -0.98507 0.0278101 -0.152885 -0.987228 0.0447919 -0.173369 -0.982661 0.0657375 -0.464945 -0.867396 0.177343 -0.440956 -0.8669 0.23247 -0.446484 -0.863246 0.235496 -0.40245 -0.863237 0.304723 -0.395989 -0.86798 0.299671 -0.356296 -0.868485 0.344656 -0.420896 0.7924 0.44153 -0.128434 -0.981659 0.140891 -0.22147 -0.940817 0.256545 -0.500566 -0.662286 0.557504 -0.276954 -0.871471 0.404766 -0.291511 -0.856083 0.426783 -0.218981 -0.856084 0.468154 -0.217527 -0.858219 0.46491 -0.159996 -0.858739 0.486795 -0.176983 0.761977 0.622951 -0.0409632 -0.988744 0.143897 -0.0634341 -0.962644 0.263235 -0.120829 -0.855479 0.503544 -0.0596296 -0.854956 0.515261 -0.0610201 -0.846233 0.529308 0.0249119 -0.846221 0.532249 0.0244325 -0.850907 0.524749 0.0871574 -0.851449 0.517145 0.138789 0.739931 0.65821 0.0272383 -0.987096 0.157794 0.0498264 -0.979053 0.197415 0.129455 -0.850981 0.508992 0.189697 -0.85044 0.49068 0.193153 -0.844693 0.499186 0.271076 -0.844682 0.461551 0.264788 -0.852206 0.451256 0.316538 -0.852751 0.415475 0.424818 0.746428 0.512225 0.354171 -0.848229 0.393791 0.399958 -0.847639 0.348627 0.398333 -0.849005 0.347163 0.449161 -0.849004 0.278294 0.263802 -0.950628 0.163449 0.152129 -0.983974 0.0930142 0.448912 -0.849184 0.278145 0.692415 -0.580098 0.429008 0.614065 -0.5801 0.535172 0.616036 -0.576333 0.536973 0.521564 -0.576347 0.629122 0.523528 -0.571827 0.631611 0.415238 -0.571821 0.707529 0.416447 -0.56823 0.709709 0.296965 -0.568236 0.767411 0.297313 -0.566741 0.768381 0.170032 -0.566742 0.80616 0.169863 -0.568089 0.805246 0.0381987 -0.568087 0.822082 0.0381332 -0.572462 0.819044 -0.0940227 -0.572468 0.814518 -0.0933171 -0.57966 0.809498 -0.222372 -0.579653 0.783934 -0.220362 -0.589076 0.777451 -0.342624 -0.589087 0.731837 -0.339179 -0.599553 0.72491 -0.451555 -0.599542 0.660793 -0.447108 -0.609592 0.654593 -0.546756 -0.609605 0.573969 -0.542691 -0.617023 0.569886 -0.627546 -0.617007 0.474856 -0.626132 -0.619226 0.473833 -0.694476 -0.619237 0.3664 -0.698226 -0.613882 0.368278 -0.748425 -0.613884 0.251011 -0.753386 -0.607144 0.252558 -0.784157 -0.607136 0.12839 -0.945502 -0.2865 0.15474 -0.946986 -0.281384 0.155049 -0.909785 -0.281386 0.305143 -0.9066 -0.292767 0.303915 -0.845694 -0.292768 0.446193 -0.843243 -0.301872 0.444763 -0.760234 -0.301868 0.575256 -0.761151 -0.298099 0.576009 -0.658378 -0.298114 0.691134 -0.660913 -0.285527 0.694023 -0.540723 -0.285518 0.791263 -0.543295 -0.268653 0.795397 -0.408424 -0.268661 0.87236 -0.410223 -0.25116 0.876719 -0.264157 -0.251154 0.931205 -0.265039 -0.2355 0.935037 -0.111456 -0.235506 0.965461 -0.111626 -0.223532 0.968284 0.0452348 -0.223528 0.973647 0.0454054 -0.216276 0.975276 0.201489 -0.216276 0.955315 0.201616 -0.214105 0.955777 0.352525 -0.214103 0.910981 0.352301 -0.216534 0.910493 0.494152 -0.216533 0.841978 0.493405 -0.222482 0.840865 0.622241 -0.222482 0.750545 0.621047 -0.230002 0.749266 0.73367 -0.22999 0.6394 0.73249 -0.236216 0.638483 0.826006 -0.236217 0.511777 0.825797 -0.237193 0.511663 -0.171046 -0.985167 0.0137478 -0.954862 -0.287376 0.075188 -0.972256 -0.220741 0.0774029 -0.788876 -0.611409 0.0620818 -0.819978 -0.568669 0.0652116 -0.507582 -0.860677 0.0399574 -0.533058 -0.845019 0.0423334 -0.186249 -0.982393 0.0146656 -0.180162 -0.983536 0.0140619 -0.131167 -0.991328 0.00802002 -0.988249 -0.143793 0.0518344 -0.850104 -0.523172 0.0601162 -0.984534 -0.162947 0.0643463 -0.942294 -0.329955 0.0566656 -0.972435 -0.220744 0.0751229 -0.180133 -0.983536 0.0144615 -0.200293 -0.979613 0.0155 -0.368943 -0.92908 0.0262823 -0.254504 -0.966909 0.0177283 -0.696546 -0.715715 0.050749 -0.816649 -0.57406 0.0594887 -0.82039 -0.568675 0.0597415 -0.526847 -0.849093 0.0383833 -0.533318 -0.845023 0.0388316 -0.688379 -0.723618 0.050114 -0.507659 -0.860753 0.0372367 -0.954882 -0.291948 0.0544718 -0.914868 -0.400476 0.0513336 -0.811724 -0.582283 0.0452811 -0.850646 -0.523546 0.047961 -0.522661 -0.852041 0.0291716 -0.555556 -0.83089 0.0312758 -0.208317 -0.977992 0.0116468 -0.186263 -0.982447 0.0101988 -0.111921 -0.993694 0.00675493 -0.527277 -0.8491 0.0317581 -0.522526 -0.852041 0.0315048 -0.817325 -0.574071 0.0492198 -0.811512 -0.582283 0.0489296 -0.946726 -0.316951 0.0570227 -0.970824 -0.233129 0.0561448 -0.988631 -0.143839 0.043803 -0.192387 -0.981271 0.00970178 -0.987614 -0.150924 0.0429037 -0.851328 -0.523295 0.0374484 -0.851107 -0.523652 0.0374955 -0.562964 -0.826125 0.0242717 -0.555771 -0.830956 0.0251019 -0.184411 -0.982822 0.00727367 -0.186357 -0.982458 0.00687774 -0.982974 -0.175525 0.0543415 -0.983438 -0.172899 0.0543591 -0.983406 -0.173086 0.0543584 -0.186152 -0.982467 0.0102882 -0.186181 -0.982462 0.0102899 -0.200023 -0.979729 0.0110568 -0.20073 -0.979584 0.011094 -0.192331 -0.981272 0.0107146 -0.987031 -0.150937 0.0546684 -0.980822 -0.187205 0.0542408 -0.850834 -0.523322 0.0470701 -0.840573 -0.539701 0.0464837 -0.562594 -0.826147 0.0311256 -0.55024 -0.834452 0.0304276 -0.193549 -0.981032 0.0107109 -0.186516 -0.982398 0.0103091 -0.186216 -0.982461 0.00964449 -0.979048 -0.188466 0.0771109 -0.0303192 -0.999539 0.00129495 -0.183285 -0.982941 0.0153077 -0.0363096 -0.999339 0.00165419 -0.158516 -0.987318 0.00876364 -0.543106 -0.839128 0.0299965 -0.55024 -0.834452 0.0304112 -0.832523 -0.552079 0.0459772 -0.840575 -0.5397 0.0464571 -0.258049 0.966028 0.0141495 -0.984057 -0.173077 0.0409362 -0.183574 -0.982954 0.0101338 -0.980577 -0.188518 0.0541302 -0.997968 -0.0302985 0.0560503 -0.991522 -0.117607 0.0552536 -0.97041 -0.235417 0.0536983 -0.838248 -0.543292 0.0466229 -0.832507 -0.552079 0.0462608 -0.912845 -0.405194 0.0503177 -0.95183 -0.302082 0.052585 -0.706038 -0.707112 0.0387776 -0.544201 -0.838405 0.0303523 -0.54309 -0.839128 0.0302963 -0.406548 -0.913355 0.0223735 -0.174633 -0.984585 0.00978788 -0.156192 -0.987689 0.00862217 0.517137 0 -0.855903 0.448844 -0.00600392 -0.89359 0.37871 0 -0.925515 0.154602 0 -0.987977 0.154602 0 -0.987977 0.183766 -0.936112 -0.299873 0.834402 -0.528728 -0.155629 0.99848 7.555e-07 -0.0551187 0.997758 -0.0213305 -0.0634347 0.553788 -0.821932 -0.13322 0.561099 -0.816991 -0.133014 0.19092 -0.968338 -0.160845 0.692623 -0.705294 -0.151106 0.178154 -0.636389 -0.750514 0.185887 -0.634937 -0.749867 0.822731 -0.347319 -0.449981 0.90949 -0.237462 -0.341234 0.974637 -0.11742 -0.190513 0.912966 -0.307793 -0.267876 0.914069 -0.305545 -0.266683 0.54197 -0.672054 -0.504591 0.53376 -0.536362 -0.653771 0.538454 -0.534055 -0.651808 0.188425 -0.891586 -0.41179 -0.391117 -0.865743 -0.312277 0.539147 -0.774957 -0.329791 0.549499 -0.81558 -0.181326 0.843834 -0.515314 -0.149654 0.972027 -0.207682 -0.109693 0.970681 -0.20214 -0.130067 0.829842 -0.511011 -0.224119 0.917452 -0.351241 -0.186845 0.545867 -0.770938 -0.328152 0.535996 -0.675114 -0.506881 0.178425 -0.799058 -0.57417 0.187922 -0.797071 -0.573902 -0.999612 -0.0231019 0.0155438 -0.988496 -0.077271 0.130021 -0.997835 -0.0655314 -0.00559487 -0.989089 -0.0741712 -0.127286 -0.925516 -0.0544254 -0.374776 -0.890547 -0.0604478 -0.450856 -0.707113 -0.0366899 -0.706149 -0.689889 -0.0385307 -0.722889 -0.37603 -0.0133365 -0.926512 -0.411483 -0.00988762 -0.911364 -0.923603 -0.0641782 0.377939 -0.920186 -0.0621888 0.386509 -0.811786 -0.0589029 0.580977 -0.721931 -0.045416 0.690473 -0.693587 -0.0497498 0.718653 -0.515269 -0.041537 0.856021 -0.428103 -0.0252083 0.903378 -0.0772969 -0.0386612 0.996258 -0.205171 -0.00752001 0.978697 0.0355359 -0.00161848 0.999367 0.98842 0 0.151741 0.172746 0 0.984966 0.172746 0 0.984966 0.555159 0 0.831744 0.555159 0 0.831744 0.84337 0 0.537333 0.84337 0 0.537333 0.98842 0 0.151741 0.98842 0 0.151741 -0.984894 0 0.173158 -0.997439 0.0041449 0.071399 -0.999993 -0.00354071 0.00148676 -0.9782 0.00322117 -0.20764 -0.969124 0 -0.246574 -0.969838 -0.175411 0.169248 -0.98699 -0.150623 -0.0562399 -0.376176 -0.00867597 -0.926508 -0.706956 -0.0437549 -0.705903 -0.933555 -0.0595691 -0.353448 -0.924902 -0.0657278 -0.374482 -0.997573 -0.0678629 0.0155747 -0.99755 -0.0688429 0.0124207 -0.979886 -0.192269 0.0534328 -0.923866 -0.140669 -0.355926 -0.909007 -0.14752 -0.389799 -0.612196 -0.0745412 -0.787184 -0.728289 -0.0659406 -0.68209 -0.433376 -0.0315534 -0.900661 -0.459876 -0.0266719 -0.887583 0.138488 -0.0208549 -0.990144 0.226502 -0.0640331 -0.971904 0.784993 -0.195545 -0.587833 0.841178 -0.169838 -0.513395 0.713953 -0.167343 -0.679903 0.49343 -0.127571 -0.860379 0.601093 -0.103467 -0.792453 0.44562 -0.102092 -0.889382 0.953327 -0.221014 -0.20572 0.948617 -0.211207 -0.235622 0.968271 -0.0808366 -0.236466 0.964613 -0.0762792 -0.252395 0.804674 -0.0728097 -0.589235 0.790423 -0.0649789 -0.609106 0.505773 -0.0490462 -0.861271 0.491444 -0.0430113 -0.869846 0.138818 -0.0187049 -0.990141 0.11382 -0.00938992 -0.993457 -0.0254188 -0.0326937 0.999142 -0.911544 -0.119537 0.393445 -0.0217021 -0.0292778 0.999336 -0.156577 -0.0486792 0.986465 -0.483351 -0.155677 0.861474 -0.453032 -0.0801587 0.887883 -0.651528 -0.0961216 0.75251 -0.696395 -0.113515 0.708624 -0.786696 -0.111913 0.607111 -0.908164 -0.116997 0.401933 -0.268241 -0.0562494 0.961708 -0.365915 -0.0835451 0.926891 -0.343376 -0.182893 0.921218 -0.670543 -0.233452 0.704182 -0.711311 -0.261904 0.65226 -0.875639 -0.289018 0.386942 -0.878104 -0.292085 0.378972 0.173776 -0.00346133 0.984779 0.00851894 -0.0358237 0.999322 0.0157037 -0.0562656 0.998292 -0.300172 -0.134771 0.944316 -0.956625 -0.290853 0.0165234 -0.957873 -0.281216 0.0582797 -0.930242 -0.281285 -0.235644 -0.905119 -0.232655 -0.355852 -0.857086 -0.224591 -0.463641 -0.706049 -0.163465 -0.689038 -0.76243 -0.155268 -0.628166 -0.409167 -0.0747311 -0.909394 -0.549462 -0.057776 -0.833519 -0.289248 -0.00575329 -0.957237 -0.417375 -0.0384993 -0.907918 -0.507857 -0.03377 -0.860779 -0.725156 -0.0768677 -0.684281 -0.738853 -0.0741366 -0.669776 -0.876412 -0.0928592 -0.472524 -0.929872 -0.116247 -0.349035 -0.951377 -0.109299 -0.287986 -0.991908 -0.118098 -0.046608 -0.990968 -0.131661 0.0254487 -0.980676 -0.122793 0.152305 0.601085 -0.163081 -0.782369 0.443605 -0.136598 -0.885752 0.155788 -0.0579515 -0.986089 0.306353 -0.0509605 -0.950553 0.175326 -0.0265124 -0.984153 0.492931 -0.182864 -0.850635 0.775917 -0.246205 -0.580806 0.795843 -0.266392 -0.543754 0.963501 -0.117519 -0.24053 0.921357 -0.297443 -0.250257 0.924677 -0.307327 -0.224773 0.959475 -0.120941 -0.25452 0.807497 -0.109264 -0.579664 0.793985 -0.101466 -0.599411 0.519812 -0.0748025 -0.850999 0.498208 -0.0651553 -0.864606 0.162653 -0.030461 -0.986213 0.120804 -0.0138028 -0.99258 0.26915 -0.018182 0.962927 0.949706 -0.304021 0.0750332 0.949712 -0.304204 0.0742141 0.916802 -0.311413 0.249991 0.860775 -0.286443 0.420734 0.829416 -0.253192 0.497958 0.777092 -0.248278 0.578348 0.675701 -0.213209 0.70567 0.586279 -0.155628 0.79502 0.558021 -0.152035 0.815781 0.258067 -0.0614467 0.964171 0.388451 -0.057082 0.9197 0.222629 -0.0269094 0.974532 0.607122 -0.0699906 0.79152 0.58367 -0.0752167 0.8085 0.863655 -0.106563 0.492691 0.849506 -0.11204 0.515545 0.970614 -0.124743 0.205783 0.983853 -0.106623 0.143754 0.552663 0 -0.833405 0.616039 -0.00129785 -0.787715 0.644725 -0.00257896 -0.76441 0.772301 -0.000307139 -0.635257 0.827035 -0.000218655 -0.56215 0.723936 -0.00828712 -0.689817 0.746542 -0.0113412 -0.665241 0.703138 -0.00575449 -0.71103 0.396192 0.0038484 -0.918159 0.538673 -0.00340664 -0.842508 0.5617 0 -0.827341 0.453762 0 -0.891123 0.453762 0 -0.891123 0.218742 0 -0.975783 0.321216 0.00971382 -0.946956 0.35346 0.00688124 -0.935424 0.378411 0.00505874 -0.925624 0.989723 0 -0.142996 0.961356 -0.00945063 -0.275145 0.946711 -0.00426599 -0.322056 0.897634 0.000136982 -0.440742 -0.917278 0 -0.398248 -0.881249 0.0174997 -0.472329 -0.791019 -0.00934491 -0.611721 -0.608809 0.0185604 -0.7931 -0.558687 -0.000100648 -0.829378 -0.324259 5.27707e-05 -0.945968 -0.187038 0.0189096 -0.982171 -0.11879 0.00451527 -0.992909 0.0822189 -0.00196345 -0.996612 0.233719 0.0102996 -0.97225 0.29344 0 -0.955978 -0.635589 0 0.772027 -0.79637 0.0326947 0.603925 -0.723658 -0.0144239 0.690008 -0.917839 0.00737649 0.396884 -0.945715 0.0238364 0.324122 -0.983305 -0.00574914 0.181873 -0.994843 0.00861139 -0.101064 -0.991488 0 -0.130202 -0.95248 0 0.3046 -0.919897 -0.0246165 0.391386 -0.879421 5.61175e-05 0.476044 -0.776024 -5.69472e-05 0.630704 -0.714128 -0.0247595 0.699577 -0.645847 0 0.763467 -0.262362 0 -0.96497 -0.040275 0.0175938 -0.999034 -0.135715 -0.0172635 -0.990598 0.283954 0.0135071 -0.958743 0.327317 0.000555434 -0.944914 0.924051 0 -0.382269 0.939602 0.0716038 -0.334696 0.871733 -0.00157171 -0.489978 0.684879 0.00470124 -0.728641 0.72953 0.0699152 -0.680366 0.609728 -0.000407388 -0.79261 0.998055 0 0.0623413 0.994322 -0.0172369 0.105012 0.650514 0 0.759495 0.698411 -0.0239768 0.715295 0.977779 -0.00169858 0.209631 0.952325 0.00221184 0.305077 0.899604 -0.0251797 0.43598 0.881864 -0.00728735 0.471448 0.772763 0.00367575 0.634684 0.979633 0 -0.200795 0.979417 0.000668327 -0.201848 0.91147 -0.000335134 -0.411365 0.879108 -0.0253509 -0.475949 0.841513 0 -0.540237 -0.707364 0 0.706849 -0.623385 -0.0425632 0.780756 -0.532209 -1.76829e-05 0.846613 -0.330525 1.57814e-05 0.943797 -0.222528 -0.0397516 0.974116 -0.111979 0 0.993711 0.775676 0 0.631131 0.190271 -0.003989 0.981724 0.421031 0.00707445 0.907019 0.472709 0.0253819 0.880853 0.581749 0.00435589 0.813357 0.757689 -0.00868532 0.652559 -0.56392 0.086911 0.821243 -0.432721 8.11243e-05 0.901528 -0.682308 -1.61962e-05 0.731064 -0.454484 0.0375626 0.889963 -0.308376 -9.46125e-06 0.951265 0.0225134 4.34311e-05 0.999747 -0.130784 0.0816889 0.98804 0.00969526 0.0305142 0.999487 -0.793661 0.0279651 0.607717 -0.793794 0.0280572 0.607539 -0.894034 -0.00355854 0.447984 -0.983197 0.0112169 0.182203 -0.973957 0.0339968 0.224167 -0.976972 -0.0361093 -0.210288 -0.989308 0 -0.145839 0.130504 0 0.991448 0.165171 -0.0135042 0.986173 0.365716 0.00802269 0.930692 0.500185 -0.026621 0.86551 0.532383 -0.0137078 0.846393 0.654079 0.00420586 0.756415 0.771988 -0.0142984 0.635476 0.793944 0 0.607991 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.976793 0 0.214185 -0.976795 0 0.214176 -0.976795 1.54621e-08 0.214176 -0.976795 -4.93021e-07 0.214176 -0.976795 -6.33707e-07 0.214174 0.99848 0 -0.0551185 0.99848 0 -0.0551185 0.370561 0 -0.928808 0.335183 -0.0299942 -0.941675 0.281573 0.00602084 -0.959521 0.190009 -0.00902538 -0.981741 0.152764 -0.0449891 -0.987238 0.0967983 1.84966e-05 -0.995304 -0.239839 0 -0.970813 -0.27515 -0.0538002 -0.959895 -0.184621 0.0060271 -0.982791 -0.0537297 -0.0150418 -0.998442 -0.090936 -0.0747836 -0.993045 0.00273521 -1.82213e-05 -0.999996 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0551178 0 0.99848 0.0551192 9.5208e-07 0.99848 -0.0551237 0 -0.99848 -0.0551214 1.55329e-06 -0.99848 -0.112918 0 0.993604 -0.664464 0.000116771 0.74732 -0.534224 0.00753893 0.845309 -0.504014 0.0138713 0.863584 -0.356458 0.000469699 0.934311 -0.117364 -0.00102231 0.993089 -0.73882 -0.00015032 0.673902 -0.853088 0.0105767 0.52166 -0.842336 0.0142023 0.538766 -0.959285 -0.000579096 -0.28244 -0.997418 0.000653227 -0.0718094 -0.998382 0.0139794 0.0551135 -0.989762 0.00315394 0.142692 -0.93627 -0.00195672 0.351276 -0.596915 0.0114044 -0.802224 -0.733378 0.000131813 -0.679821 -0.905378 -0.00054317 -0.424607 -0.804783 0.0473798 -0.591676 -0.878014 0.019656 -0.478232 -0.596017 0.0116446 -0.802887 -0.221567 -0.0134383 -0.975053 -0.274057 0 -0.961713 -0.214178 -4.62513e-06 -0.976795 -0.214171 -9.12864e-07 -0.976796 -0.214176 0 -0.976795 0.214174 2.98169e-06 0.976795 0.214184 6.22245e-06 0.976793 0.214176 0 0.976795 0.214175 1.08053e-06 0.976795 0.214174 3.14952e-06 0.976795 0.0551156 0 0.99848 0.0551226 1.36283e-06 0.99848 0.0551188 -4.05658e-07 0.99848 -0.0551216 1.22345e-06 -0.99848 -0.0551181 0 -0.99848 -0.0551193 -3.39816e-06 -0.99848 -0.0668942 0 0.99776 -0.112912 0.00449702 0.993595 -0.253315 -0.000770267 0.967383 -0.388872 0.0015836 0.92129 -0.504029 0.0105783 0.863622 -0.583248 0.000103517 0.812294 -0.806605 -0.000112273 0.591091 -0.853104 0.00907707 0.521663 -0.920863 0.000885447 0.389886 -0.972334 -0.000891152 0.233591 -0.99844 0.00890979 0.0551167 -0.999967 0.00374411 0.00723758 -0.723372 4.28836e-05 -0.690458 -0.811774 -3.5734e-05 -0.583972 -0.905349 0.00764363 -0.424599 -0.930041 3.60976e-05 -0.367455 -0.987665 -6.84207e-06 -0.156583 -0.221592 0 -0.97514 -0.0904622 0.0184848 -0.995728 -0.11803 0.0149641 -0.992897 -0.181054 0.00810978 -0.98344 -0.354371 -0.00346396 -0.935099 -0.596042 0.00763012 -0.802917 -0.566122 0.012579 -0.824225 -0.653163 0.0050778 -0.7572 -0.000157293 1 7.31601e-06 -0.00714967 0.999974 0.0003185 -0.0244422 0.999701 0.00115112 0.0143622 0.999882 0.00540848 0.000230732 1 -6.18272e-05 -1.69818e-05 1 -0.00011823 0 1 0 2.78287e-06 1 3.43944e-06 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.09921e-05 1 3.81477e-06 4.45259e-05 1 -1.85584e-05 0.000394584 1 -0.000181146 -0.00128011 0.999999 0.000700388 0.000248279 1 -0.000135841 0.00548718 0.999983 0.00200964 -0.000407516 1 -0.00014925 1.2778e-05 1 -1.27782e-05 0.000153142 1 0.000101665 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.055117 5.85867e-07 0.99848 0.0551159 0 0.99848 -0.0551149 0 -0.99848 -0.0551183 -1.77591e-06 -0.99848 -0.101002 0 0.994886 -0.112908 0.0020048 0.993603 -0.333911 -0.00091514 0.942604 -0.514465 0.0133339 0.857408 -0.504031 0.0113211 0.863612 -0.647534 0.000169253 0.762036 -0.729198 -0.000104798 0.684303 -0.85311 0.0079976 0.52167 -0.823947 0.0175415 0.566395 -0.998399 0.01272 0.0551128 -0.985552 0.00150515 0.169364 -0.924618 -0.00134181 0.380893 -0.905377 -0.00053388 -0.424608 -0.812224 0.0389971 -0.582041 -0.889949 0.0146989 -0.455824 -0.967625 -0.00220316 -0.252384 -0.999458 0.00312008 -0.0327669 -0.221596 0 -0.975139 -0.150831 0.0150811 -0.988445 -0.286646 0.000874843 -0.958036 -0.457339 -0.000885955 -0.889292 -0.596004 0.0133875 -0.80287 -0.625527 0.0080539 -0.780161 -0.732935 0.000130564 -0.680298 0.0551194 -2.35155e-07 0.99848 0.0551198 0 0.99848 -0.0551224 0 -0.99848 -0.0551201 1.39159e-06 -0.99848 -0.364373 0.00198603 0.931251 0.0333781 0 0.999443 -0.112917 0.0058885 0.993587 -0.0479873 0.0234655 0.998572 -0.173708 -0.0036556 0.98479 -0.536539 0.0179634 0.843684 -0.504034 0.00951876 0.863631 -0.66599 0.000159178 0.745961 -0.72151 -0.000118564 0.692404 -0.853112 0.00758575 0.521672 -0.830123 0.0169697 0.557321 -0.998371 0.0147875 0.0551108 -0.985021 -0.00093289 0.172433 -0.924491 0.000563125 0.381203 -0.905278 0.0146837 -0.424565 -0.958773 0.000112751 -0.284175 -0.996661 -0.000131481 -0.0816474 -0.541407 0.0173578 -0.840582 -0.732203 0.000191362 -0.681086 -0.859304 -0.000464561 -0.511464 -0.59604 -0.00774279 -0.802918 -0.221594 0.00431904 -0.975129 -0.201584 0 -0.979471 -0.214177 -4.30375e-06 -0.976795 -0.214184 0 -0.976793 0.214107 -7.32499e-05 0.97681 0.214175 0 0.976795 0.21416 -1.1832e-05 0.976799 0.214443 0.000750663 0.976736 0.21363 -0.00103608 0.976914 0.209642 -0.00152542 0.977777 0.213877 -0.000256002 0.976861 0.212995 -0.00111963 0.977053 0.214064 0.000163283 0.97682 -0.214174 0 -0.976796 -0.214177 7.02936e-07 -0.976795 -0.214172 -1.71981e-06 -0.976796 0.214173 0 0.976796 0.214175 -1.07642e-06 0.976795 0 1 0 0 1 0 -4.83438e-05 1 -4.59814e-05 0.00225624 0.999997 -0.000498004 0.00986757 0.999949 -0.00218453 -0.000876752 1 0.000337016 0.0203151 0.999509 -0.0238397 -0.225076 0.938013 0.263577 -1.2935e-05 1 1.29353e-05 -2.31761e-06 1 1.50815e-05 -0.00155616 0.999999 0.000435884 0.00266715 0.999996 -0.000561286 0 1 0 -0.0018491 0.999997 0.00169445 -0.00477538 0.999978 0.00454532 0.0183267 0.999784 0.00985428 -0.00529866 0.999984 -0.00210943 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.214171 0 -0.976796 -0.214175 2.16787e-07 -0.976795 -0.214178 6.64249e-07 -0.976795 -0.214174 -7.22823e-07 -0.976795 0.214175 1.77642e-06 0.976795 0.214176 -7.21195e-07 0.976795 0.214173 0 0.976796 0.022569 -0.000351645 0.999745 0.0468641 0.00752684 0.998873 0.0850193 -0.000562874 0.996379 -0.778735 0.00920312 0.627286 -0.610591 -0.00350772 0.791938 -0.371497 -0.00335342 0.928428 -0.46893 0.0138305 0.883127 -0.216254 -0.00746734 0.976308 -0.705718 -0.0113794 0.708401 -0.92725 0.000253917 0.374443 -0.942487 -0.00542206 0.334198 0.114278 -0.0172199 -0.9933 0.265022 -0.0024767 -0.964239 0.0876041 -0.00718602 -0.996129 0.849128 -0.0577441 -0.525021 0.715356 -0.0598209 -0.696194 0.491517 -0.0468734 -0.869605 0.590573 -0.0340446 -0.806266 0.420954 -0.036782 -0.906336 0.79001 -0.0727098 -0.608768 0.964816 -0.0733978 -0.252475 0.973526 -0.079038 -0.214476 0.205257 0 -0.978708 0.35164 -0.0216338 -0.935885 0.446413 0 -0.894827 0.765245 0 -0.643739 0.765245 0 -0.643739 0.982498 0 -0.186273 0.982498 0 -0.186273 0.947766 0 0.318966 0.947766 0 0.318966 0.669953 0 0.742403 0.669953 0 0.742403 0.220325 0 0.975426 0.220325 0 0.975426 0.186543 -0.0111313 0.982384 0.197759 -0.0319502 -0.97973 0.0838577 -0.0108265 -0.996419 0.113793 0 -0.993504 0.481146 0 -0.87664 0.481146 0 -0.87664 0.847074 0 -0.531475 0.847074 0 -0.531475 0.998656 0 -0.0518237 0.998656 0 -0.0518237 0.897537 0 0.440939 0.897537 0 0.440939 0.569303 0 0.822128 0.569303 0 0.822128 0.306202 0 0.951967 0.200678 -0.00604123 0.979639 0.187302 -0.00638229 0.982282 0.155162 -0.0235812 -0.987608 0.0778774 -0.00753787 -0.996934 0.0967867 0 -0.995305 0.476549 0 -0.879148 0.476549 0 -0.879148 0.844774 0 -0.535123 0.844774 0 -0.535123 0.998475 0 -0.0552047 0.998475 0 -0.0552047 0.898618 0 0.438732 0.898618 0 0.438732 0.570562 0 0.821255 0.570562 0 0.821255 0.247957 0 0.968771 0.178564 -0.00995833 0.983878 -0.992979 0 0.11829 -0.992979 0 0.11829 -1.39379e-06 -0.995151 -0.098361 -0.0411648 -0.991884 -0.120297 0.0307649 -0.955816 -0.292351 0.0249136 -0.954691 -0.296555 -0.0402118 -0.881859 -0.469796 0.0972787 -0.905574 -0.412883 -0.121134 -0.770459 -0.625875 0.0585097 -0.81373 -0.578291 -0.0489869 -0.634834 -0.771094 -0.00213552 -0.651609 -0.758552 0.00166336 -0.471295 -0.881974 -0.0274985 -0.456083 -0.889512 0.0213569 -0.289949 -0.956804 0.0420171 -0.307952 -0.950474 -0.088967 -0.0980523 -0.991197 -1.61215e-05 -0.146069 -0.989274 -1.62962e-05 0 -1 -1.62962e-05 0 -1 0.899402 0 -0.437122 0.897225 -2.41256e-06 -0.441573 0.897074 -8.01364e-06 -0.441881 0.897193 -4.39311e-08 -0.441638 0.897065 -3.79128e-06 -0.441898 0.897083 -3.28788e-06 -0.441861 0.897139 0 -0.441748 0.897186 5.3886e-07 -0.441653 0.897188 1.79378e-07 -0.441649 0.89737 2.70928e-05 -0.44128 0.897123 -2.83826e-06 -0.441782 0.99848 0 -0.0551179 0.99848 6.45741e-07 -0.0551188 0.99848 6.232e-07 -0.0551188 0.99848 -1.25527e-06 -0.0551183 0.0147036 -0.000365213 0.999892 -0.946646 0 0.322275 -0.94624 0.000331056 0.323466 -0.73356 -0.00032805 0.679624 -0.730994 0.000657207 0.682384 -0.39348 -0.000654121 0.919333 -0.387697 0.000978625 0.921786 0.0158798 -0.000982014 0.999873 0.0161447 -0.000845564 0.999869 -0.984879 0 0.173245 -0.984879 0 0.173245 -0.939584 0 -0.34232 -0.939584 0 -0.34232 0.850652 0 -0.525729 0.798656 -0.11613 -0.590477 0.891341 0 -0.453333 0.975616 0 -0.219487 0.947584 -0.11613 -0.297655 0.990463 0 -0.137778 0.892562 0 0.450924 0.913625 -0.0540665 0.402948 0.95985 0 0.280514 0.888944 0 -0.458016 0.949206 -0.0324405 -0.312979 0.949206 -0.0324406 -0.312979 0.987029 0 -0.160543 0.998827 0 0.0484205 0.993187 -0.112607 -0.029994 0.988276 0 0.15268 0.82147 0 -0.570252 0.772509 -0.0648676 -0.631682 0.703644 0 -0.710552 0.604759 0 -0.796409 0.494778 -0.0540663 -0.867336 0.44931 0 -0.893376 0.202483 0 -0.979286 0.150673 -0.0540664 -0.987104 0.0204202 0 -0.999792 -0.674044 0 -0.738691 -0.549748 -0.0324405 -0.8347 -0.549748 -0.0324405 -0.8347 -0.412456 0 -0.910977 -0.213805 0 -0.976876 -0.288034 -0.112607 -0.950976 -0.110403 0 -0.993887 -0.764793 0 -0.644276 -0.811325 -0.0648675 -0.580985 -0.869501 0 -0.493932 -0.92659 0 -0.376074 -0.966372 -0.0540664 -0.251398 -0.97965 0 -0.200712 -0.96384 0 -0.266483 -0.96384 0 -0.266483 -0.785583 0 -0.618756 -0.785583 0 -0.618756 -0.977355 0 0.211605 -0.977605 -0.00434169 0.210405 -0.973113 -0.12352 0.194405 -0.971409 -0.111389 0.209659 -0.971495 -0.0499175 0.231745 -0.97859 -0.00494034 0.205761 -0.980905 -0.030177 0.19213 -0.977798 -0.120622 0.171352 -0.97346 -0.0895054 0.210626 -0.955302 -0.253401 0.152272 -0.943942 -0.251965 0.213277 -0.939459 -0.302759 0.160477 0.995605 0 -0.0936537 0.948215 -0.313189 -0.0529205 0.989571 -0.10639 -0.0971107 0.987842 -0.116233 -0.103242 0.987566 -0.111876 -0.110445 0.996608 0 -0.0822914 0.995936 -0.0195341 -0.0879205 0.998024 -0.0188996 -0.0599283 0.997981 -0.0404524 -0.0489664 0.997149 -0.0405719 -0.0636291 0.991847 -0.122145 -0.0363314 0.99848 0 -0.0551193 0.99848 0 -0.0551169 0.99848 4.27784e-07 -0.0551181 0.99848 0 -0.0551181 0.99848 0 -0.0551181 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.496896 0.867635 -0.0174417 0.191217 0.978067 -0.0825835 0.951477 0.217926 -0.217256 -0.94692 0.318592 0.0429161 -0.545314 0.838073 -0.0163162 -0.2525 0.966806 -0.0391166 -0.234962 0.971092 -0.0421033 -0.229036 0.972598 -0.039954 -0.247783 0.968008 -0.0395585 -0.267818 0.962955 -0.0314794 -0.310902 0.94965 0.0387921 -0.423042 0.904817 -0.0483845 -0.357059 0.933282 -0.0386445 -0.324433 0.945189 -0.0368922 -0.294371 0.954993 -0.0365185 -0.292966 0.955402 -0.0371195 -0.307257 0.951308 -0.0246371 -0.681586 0.731607 -0.0138117 -0.996917 0.0599702 0.0505926 -0.996974 0.0597779 0.0496965 -0.986735 0.153366 0.0532308 -0.986975 0.159721 0.0192326 -0.953914 0.297398 0.0400274 -0.943714 0.326486 -0.0530088 -0.912952 0.407394 0.0234414 -0.82938 0.556876 -0.0449323 -0.560358 0.576827 0.594364 -0.990065 0.129532 0.0547132 -0.993371 0.101 0.0548987 -0.989693 0.129686 0.060746 -0.971363 0.232936 0.046849 -0.946705 0.319314 0.0422754 -0.948364 0.314027 0.0446314 -0.891226 0.449717 0.0589144 -0.919626 0.391458 0.0323976 -0.787911 0.615438 0.020769 -0.604634 0.796376 0.0142645 -0.65449 0.755798 0.0203157 -0.637875 0.769991 0.0151367 -0.749325 0.662051 0.0141551 -0.816937 0.575661 0.0350478 -0.56585 0.824425 0.0117186 -0.408704 0.91243 0.0207838 -0.474255 0.87901 0.0492351 -0.418888 0.906843 0.0465672 -0.423041 0.905518 0.0327686 -0.324343 0.945592 0.025649 -0.21093 0.976961 0.0324978 -0.253315 0.966262 0.0465823 -0.106412 0.993975 0.0262856 -0.165581 0.9844 0.059497 0.0405685 0.997393 0.0596826 -0.00989663 0.997732 0.0665771 -0.0172501 0.997416 0.0697367 -0.0576527 0.996786 0.0556278 -0.101553 0.993402 0.0532792 0.0968961 0.994833 0.0303119 0.489329 0.868085 -0.0835781 0.377907 0.919131 -0.111286 0.596981 0.784597 -0.167395 0.15009 0.988472 0.0199077 0.107092 0.994098 0.0173309 0.228269 0.973303 -0.0239579 0.202006 0.97908 -0.0243981 0.316078 0.946285 -0.0681198 0.421529 0.902312 -0.0902525 0.415176 0.90726 -0.0671514 0.789539 0.579539 -0.2019 0.701764 0.683241 -0.201763 0.591375 0.789501 -0.164209 0.774875 0.598068 -0.204655 0.923351 0.306353 -0.231452 0.878062 0.436764 -0.19556 0.931223 0.295102 -0.213867 0.928378 0.302211 -0.216295 0.975089 0.0611256 -0.213227 0.975145 0.0498647 -0.215883 0.975166 0.0521684 -0.215241 0.975286 0.0585289 -0.213051 0.96677 0.142902 -0.21198 0.965696 0.152926 -0.209868 0.954559 0.209697 -0.211762 0.93025 0.304226 -0.205136 0.927734 0.311229 -0.206027 0.816403 0.545249 -0.190238 0.821458 0.536704 -0.192755 0.621831 0.767856 -0.154026 0.358986 0.928806 -0.0919195 0.659916 0.735477 -0.153574 0.500547 0.854066 -0.141506 0.381308 0.918123 -0.107952 0.259315 0.959916 -0.106376 0.309332 0.946225 -0.094721 0.269863 0.958332 -0.0936712 0.180136 0.980121 -0.0831526 0.220975 0.970922 -0.0920932 0.281811 0.953642 -0.105592 0.317403 0.941324 -0.114735 0.202115 0.975357 -0.0884739 0.169216 0.982424 -0.0787964 0.178053 0.980929 -0.0779426 0.19161 0.978056 -0.0818098 0.251523 0.963006 -0.0967297 0.198334 0.976002 -0.0899103 0.172435 0.981175 -0.0869569 0.0770118 0.995051 -0.0627944 0.0899223 0.993768 -0.065879 0.109387 0.991351 -0.0725046 0.114976 0.990703 -0.0727177 0.142196 0.986883 -0.0764389 0.063552 0.996169 -0.060072 0.0452762 0.997278 -0.0581885 0.0499164 0.996959 -0.0598412 -0.0139193 0.998749 -0.0480318 -0.0039949 0.998792 -0.0489678 0.00957081 0.998663 -0.0508092 -0.106557 0.993589 -0.0377616 -0.0779335 0.99613 -0.040633 -0.0676606 0.996784 -0.0429339 -0.0516132 0.997783 -0.0420115 -0.017402 0.9988 -0.0457908 -0.28033 0.959392 -0.0313358 -0.246369 0.968541 -0.0350722 -0.255877 0.966142 -0.0331068 -0.199598 0.979308 -0.0334127 -0.154681 0.98716 -0.0398531 -0.15784 0.986631 -0.0405613 -0.130168 0.990768 -0.0378862 -0.955156 0.291485 0.0520832 -0.980287 0.191678 0.0479216 -0.995088 0.0852073 0.0503935 -0.992202 0.111927 0.0548366 -0.974644 0.222271 0.025789 -0.927384 0.372041 0.0393122 -0.903044 0.428755 0.0260947 -0.816129 0.577628 0.0167063 -0.833931 0.551127 0.0285902 -0.680546 0.732288 0.0247326 -0.60431 0.796339 -0.0255724 -0.601463 0.798841 -0.0097866 -0.81722 0.576274 0.00776318 -0.834403 0.551013 0.0125128 -0.928445 0.370497 0.0268544 -0.935838 0.35112 0.0303713 -0.973752 0.223761 0.0416946 -0.981086 0.187385 0.0485601 -0.995044 0.0852396 0.0512009 -0.996193 0.0675065 0.055159 -0.35874 0.933261 -0.0181489 -0.386389 0.922236 -0.0135645 -0.381655 0.924184 -0.01498 -0.384118 0.922936 -0.0253432 -0.37246 0.92762 -0.0281866 -0.359581 0.932747 -0.0261765 -0.315207 0.948867 -0.0172219 -0.97341 0.224436 0.0458434 -0.971516 0.232627 0.045187 -0.95777 0.28482 0.0394347 -0.948181 0.314733 0.0435489 -0.901913 0.431227 0.0244313 -0.794484 0.605982 0.0397684 -0.862281 0.506397 0.00579013 -0.763804 0.645387 0.00889431 -0.625354 0.780341 0.000695514 -0.685645 0.727835 -0.0121363 -0.576143 0.817334 -0.00489486 0.957191 0.190004 -0.218367 0.959696 0.177274 -0.218078 0.964804 0.14753 -0.217687 0.960451 0.176642 -0.215247 0.945933 0.232436 -0.226241 0.934584 0.282418 -0.216315 0.891706 0.394064 -0.222653 0.800112 0.558354 -0.219229 0.795455 0.565858 -0.216923 0.575146 0.799356 -0.17389 0.5756 0.799033 -0.173869 0.435903 0.888559 -0.14301 0.374075 0.918161 -0.130571 0.329302 0.935678 -0.126755 0.301532 0.946711 -0.113214 0.545787 0.823911 -0.152603 0.520106 0.839793 -0.155681 0.317356 0.941173 -0.1161 0.35638 0.927808 -0.110295 0.201932 0.974363 -0.0991981 0.278023 0.957118 -0.0814149 0.254217 0.963401 -0.0850448 0.912298 0.34426 -0.221806 0.882897 0.416026 -0.217752 0.834249 0.513576 -0.200669 0.794252 0.570344 -0.209453 0.668902 0.719804 -0.185614 0.373953 0.91921 -0.123341 0.566122 0.807714 -0.164632 0.545342 0.823125 -0.158327 0.808046 0.553834 -0.200825 0.833026 0.512438 -0.208506 0.923558 0.317161 -0.215519 0.934102 0.282127 -0.218763 0.96152 0.170238 -0.215636 0.960535 0.176678 -0.214845 0.973558 0.0746015 -0.215915 0.973031 0.074506 -0.21831 0.971666 0.10223 -0.213108 0.971319 0.104715 -0.213479 0.0754004 0.996284 -0.0416215 0.0456375 0.998066 -0.0422135 0.159134 0.985266 -0.0626649 0.109481 0.991987 -0.0630576 0.237078 0.967509 -0.0878648 0.205474 0.97455 -0.0896255 0.0372837 0.997583 0.0586274 0.029213 0.999448 -0.0158073 0.103407 0.994223 -0.0287784 0.07537 0.996512 -0.0358332 0.199324 0.978123 -0.0595492 0.159254 0.984857 -0.068524 0.377747 0.919002 -0.112881 0.329318 0.936155 -0.123141 0.595414 0.783413 -0.178176 0.575262 0.798169 -0.178884 0.772517 0.59672 -0.217123 0.800935 0.559374 -0.213552 0.924546 0.301137 -0.233519 0.923881 0.300703 -0.236688 0.940711 0.257308 -0.221034 -0.386047 0.922371 -0.0141278 -0.388433 0.92137 -0.0140296 -0.31392 0.949236 -0.0201205 -0.252324 0.967447 -0.0194519 -0.194943 0.980515 -0.0242592 -0.149413 0.988568 -0.0202147 -0.0929736 0.99534 -0.0255865 -0.0626257 0.997766 -0.0232554 -0.0215889 0.999384 -0.0276679 -0.00939977 0.999647 -0.024861 -0.41582 0.909224 -0.0201271 -0.31027 0.950619 -0.00753172 -0.220162 0.975355 -0.0145225 -0.189296 0.981904 -0.00552943 -0.113804 0.993429 -0.0121439 -0.0868669 0.996211 -0.00422325 -0.0303818 0.999489 -0.00991209 -0.0158817 0.999874 -0.000410211 0.0200879 0.999784 -0.00530777 0.0185441 0.999417 -0.0286611 0.00947403 0.999484 -0.0306836 0.00795737 0.998736 -0.049633 0.040015 0.997592 -0.0566568 -0.992545 0.11163 0.048926 -0.957379 0.285391 0.0444736 -0.920356 0.390549 0.020414 -0.901729 0.431504 0.0262659 -0.788456 0.614901 0.0152812 -0.79867 0.601622 0.0132837 -0.639947 0.768419 -0.000517531 -0.625153 0.7805 0.00164895 -0.441464 0.897189 -0.0126598 -0.441441 0.897202 -0.0125715 -0.458659 0.888482 -0.0152045 0.983111 0.0704656 -0.168902 0.756032 0.644501 -0.114165 0.80985 0.582194 -0.0720618 0.946892 0.31833 0.0454083 0.942687 0.322534 -0.0855127 0.829783 0.556603 0.0406652 0.827481 0.560885 -0.0261276 0.991279 0.0908098 -0.0954916 0.989137 0.0218895 -0.145355 0.991267 0.0207234 -0.130233 0.989574 0.0207174 -0.142525 0.984581 2.32733e-07 -0.174928 0.983917 0.000878379 -0.178623 0.984812 -0.00459173 -0.173561 0.981224 0.0303221 -0.190472 0.975164 0.0302361 -0.21941 0.971515 0.057465 -0.229904 0.974522 0.0575281 -0.216788 0.968903 0.104616 -0.224238 0.955975 0.242429 -0.165349 0.906375 0.415384 -0.0770751 0.893252 0.415627 -0.171336 0.880023 0.45541 -0.134761 0.930363 0.302447 -0.207247 0.945694 0.217381 -0.241678 0.940608 0.278858 -0.193634 0.946514 0.2467 -0.207966 0.974686 0.144139 -0.170915 0.975422 0.144155 -0.166645 0.957056 0.242468 -0.158915 0.992252 0.0705269 -0.102288 0.961384 0.262445 -0.0828472 0.99576 0.0902941 -0.0175705 0.0197337 0.989272 0.144746 0.4704 0.88162 -0.0383415 0.713702 0.700326 -0.0131748 0.975677 0.219215 0.00047013 0.981057 0.158769 -0.11099 0.02 0.989283 0.144635 -0.873062 0.432205 0.225745 -0.647157 0.743836 0.16702 -0.600912 0.784892 0.151158 -0.769547 0.620312 0.151693 -0.735445 0.666794 0.120444 -0.989561 0.10588 0.097763 -0.968283 0.19573 0.155299 -0.950709 0.287214 0.116876 -0.820444 0.544659 0.173833 -0.821504 0.543477 0.172521 -0.901661 0.415125 0.121152 -0.524451 0.837383 0.154081 -0.575468 0.796235 0.186674 -0.581407 0.790755 0.191501 -0.66207 0.736465 0.138863 -0.750486 0.645512 0.141722 0.174085 0.978774 0.108147 0.0729817 0.989715 0.123035 0.28932 0.954283 0.0750871 0.241897 0.964828 0.102921 0.416315 0.884387 0.211048 0.362518 0.926741 0.0986467 0.175914 0.978833 0.104597 0.912593 0.408656 0.0132152 0.780978 0.615757 -0.104483 0.366249 0.170041 0.914849 0.984226 0.0441504 -0.171317 0.990278 0.0927812 -0.103643 0.983615 0.134147 0.120443 0.932294 0.241204 -0.269534 0.891203 0.394408 0.224052 0.726956 0.683819 -0.0626665 0.612311 0.789276 -0.0460197 0.575125 0.817086 -0.0400168 0.60296 0.796008 -0.0530183 0.412993 0.907008 -0.0822989 0.44713 0.894415 -0.00977833 0.326478 0.94514 0.0110523 0.339615 0.940443 0.015125 0.238642 0.969307 0.059103 0.246524 0.967055 0.0634862 0.157047 0.984737 0.0750246 0.170822 0.981835 0.0825783 -0.0341238 0.99126 0.127435 -0.000726289 0.991127 0.13292 0.045467 0.991443 0.122366 0.0491618 0.991035 0.124231 0.107971 0.987279 0.116716 -0.154097 0.978616 0.136251 -0.0886949 0.985943 0.141597 -0.0463108 0.989705 0.135423 -0.131672 0.979836 0.150277 -0.268856 0.950151 0.157892 -0.23848 0.960428 0.143895 -0.598136 0.786814 0.152172 -0.728261 0.671931 0.134703 -0.418554 0.896802 0.143386 -0.403074 0.902936 0.149127 -0.304749 0.939797 0.15463 -0.882102 0.425515 0.202073 -0.74165 0.612585 0.273304 -0.681164 0.682401 0.265225 -0.56337 0.76677 0.307698 -0.450488 0.844426 0.289836 -0.382301 0.870992 0.308577 -0.251796 0.92456 0.285985 -0.243505 0.926152 0.288005 -0.0913953 0.961019 0.260938 -0.114516 0.960002 0.255504 0.0532127 0.982096 0.180711 0.0364924 0.984887 0.169311 -0.0269257 0.983662 0.178001 0.00153854 0.980456 0.196733 -0.0316783 0.978836 0.202179 0.227097 0.950122 0.213763 0.262495 0.938135 0.225831 0.387494 0.896426 0.215103 0.374838 0.902884 0.210467 0.602422 0.775524 0.188813 0.529944 0.83306 0.158652 0.798548 0.588148 0.128075 0.716462 0.68846 0.112715 0.909347 0.415195 0.0264922 0.632059 0.740001 -0.23 0.619077 0.78428 0.040604 0.479176 0.876087 0.0535037 0.528158 0.844454 0.0891481 0.348493 0.931176 0.107072 0.370011 0.921089 0.121186 0.253819 0.958026 0.133272 0.254736 0.957704 0.133839 0.140026 0.979297 0.146187 0.148512 0.964021 0.22047 0.0866941 0.980385 0.177001 0.0320844 0.986798 0.158747 0.038293 0.977976 0.205174 0.206768 0.961513 0.180944 0.21867 0.96798 0.123279 0.222559 0.961455 0.16147 0.412616 0.901974 0.127244 0.41968 0.898117 0.131354 0.530057 0.844146 0.0803607 0.979515 0.158815 -0.12381 0.98314 0.138826 -0.119011 0.898015 0.434717 -0.0677583 0.90926 0.411851 -0.0601995 0.687057 0.72647 0.0139284 0.740161 0.668879 0.0690094 0.591464 0.803631 0.0659359 0.972335 0.220782 -0.076289 0.982663 0.171602 -0.0701865 0.875922 0.482229 -0.0146789 0.901722 0.432263 -0.00674958 0.656993 0.751026 0.0657279 0.689994 0.718735 0.0856096 0.394848 0.907142 0.145564 0.421205 0.892983 0.158643 0.195512 0.961471 0.193256 0.208543 0.957485 0.199328 0.0329191 0.974714 0.221017 0.0326987 0.975091 0.219383 0.0284584 0.975098 0.219942 0.0186191 0.988835 0.147848 0.0200752 0.988785 0.147991 -0.971178 0.195794 0.135932 -0.964135 0.21732 0.152364 -0.820209 0.544614 0.175082 -0.800928 0.564428 0.199837 -0.579063 0.78966 0.202788 -0.55196 0.802361 0.227064 -0.324375 0.921227 0.214759 -0.298328 0.925249 0.234338 -0.0810589 0.973891 0.212049 -0.0620072 0.972337 0.225201 0.0329126 0.976634 0.212374 0.0393367 0.975459 0.216638 0.0351383 0.975486 0.217237 -0.385397 0.911542 0.143385 -0.330492 0.925961 0.18268 -0.253993 0.955286 0.151383 -0.0922975 0.985939 0.139303 -0.0995464 0.983688 0.14983 0.0227447 0.990196 0.137819 0.0215025 0.98998 0.13956 0.0328422 0.974294 0.222873 0.0269506 0.97429 0.223679 0.0259816 0.975914 0.216603 0.0365717 0.975866 0.215284 -0.962281 0.219811 0.160308 -0.943442 0.26967 0.192858 -0.798934 0.563892 0.209118 -0.761382 0.601873 0.240928 -0.549623 0.800995 0.237323 -0.509601 0.820007 0.260569 -0.296518 0.923514 0.24331 -0.267729 0.928587 0.256996 -0.0610834 0.971011 0.231097 -0.0517382 0.9706 0.235072 0.0399686 0.974384 0.221313 0.0316982 0.975448 0.217938 0.0351628 0.975445 0.217418 0.0314727 0.976296 0.214141 0.0271754 0.976295 0.214733 0.908787 0.413291 0.0574201 0.915482 0.396073 0.0708435 0.799791 0.591601 0.101699 0.874521 0.471385 0.114061 0.602909 0.779969 0.167777 0.65653 0.729696 0.191078 0.387853 0.893582 0.226012 0.398733 0.887723 0.230131 0.229814 0.941548 0.246318 0.199556 0.951173 0.235473 0.0949842 0.965074 0.244152 0.0345536 0.979135 0.20025 0.0405624 0.979037 0.199605 0.0234805 0.981945 0.187704 0.000710634 0.981622 0.190833 0.0310587 0.976972 0.211096 -0.0289175 0.974878 0.220856 0.0343495 0.970826 0.237314 -0.0916451 0.9614 0.259445 -0.0461212 0.961474 0.271001 -0.247527 0.919401 0.305667 -0.258082 0.91747 0.302724 -0.439992 0.835563 0.329001 -0.497036 0.810681 0.309438 -0.663373 0.67363 0.325822 -0.750408 0.597658 0.282301 -0.85826 0.427291 0.284276 -0.939608 0.269301 0.211219 -0.995847 0 0.0910442 -0.78984 0.599669 0.128644 -0.478444 0.866651 0.141444 -0.797819 0.579248 0.167204 -0.903243 0.394842 0.168085 -0.875624 0.46646 0.125288 -0.906301 0.419619 0.0503841 -0.996806 0.0147031 0.0785002 -0.998548 0.0343371 0.0415175 -0.993529 0.100976 0.0520002 -0.971281 0.232966 0.048367 -0.993089 -0.00723995 0.11714 -0.997328 0.029784 0.0667019 -0.995497 0.0248859 0.0914697 -0.995359 0.0293456 0.0916462 -0.996269 0.0285537 0.0814381 -0.991528 0.129713 0.00685578 -0.98814 0.130497 0.0809301 -0.975818 0.21256 0.0509674 -0.945864 0.319008 0.059785 -0.933635 0.352741 0.0624376 -0.923262 0.353157 0.151222 -0.959846 0.268817 0.0802086 -0.944456 0.237956 0.226671 -0.967345 0.238766 0.0850559 -0.977299 0.0687724 0.200392 -0.986531 0.0693755 0.148136 0.976833 0.0018765 -0.213994 0.976795 0 -0.214176 0.976795 0 -0.214176 0.976798 2.30885e-07 -0.214165 0.976795 1.23655e-07 -0.214176 0.976795 4.72278e-08 -0.214176 0.976795 3.43178e-06 -0.214176 0.976795 4.02509e-06 -0.214175 0.976795 6.26822e-06 -0.214175 0.976795 4.22614e-06 -0.214175 0.978868 -0.00430131 0.20445 0.977414 -5.70123e-07 0.211335 0.999114 -6.17074e-06 0.0420939 0.974529 0.197524 0.106195 0.980075 -0.13286 -0.147653 0.995303 4.76719e-06 -0.0968045 0.978035 2.1629e-06 -0.208439 0.910869 4.32254e-06 0.412696 0.91087 1.25494e-06 0.412694 0.930749 0.0481207 0.36248 0.927893 0.0614039 0.367756 0.96626 0.003632 0.257541 0.910869 9.13616e-08 0.412695 0.910869 8.27724e-08 0.412697 0.913367 0.00229304 0.407132 0.910822 0.0112981 0.412645 0.942519 -0.0136271 0.333874 0.930093 -5.0118e-06 0.367324 0.97148 7.84495e-06 0.237121 0.972383 -0.00282359 0.233374 0.997938 0.00245948 0.0641348 0.998189 -6.16033e-06 0.0601518 0.999383 1.20705e-06 -0.0351253 0.99672 -0.00549992 -0.080741 0.964988 -0.0188535 -0.261616 0.989004 0.00352087 -0.147847 0.996932 -0.00647647 -0.0780061 0.644133 -0.00460074 -0.764899 0.723872 0 -0.689934 0.744811 0 -0.667275 0.792811 0.0148479 -0.609286 0.844561 -0.0380235 -0.534108 0.890988 0.00905897 -0.453936 0.918799 0 -0.394726 0.928596 0 -0.371093 0.960521 -0.00590082 -0.278146 0.04961 0 -0.998769 0.122535 0 -0.992464 0.189556 -0.0231898 -0.981596 0.270143 0.0200988 -0.96261 0.36605 -0.0100042 -0.930542 0.401407 0 -0.9159 0.492987 0 -0.870037 0.49624 0.00198984 -0.868183 0.64283 -0.00315101 -0.766002 -0.133822 -0.0169012 -0.990861 -0.150568 -0.0351228 -0.987976 0.0170697 0.00736484 -0.999827 -0.773018 -8.51837e-07 -0.634383 -0.773019 -1.45901e-06 -0.634383 -0.766717 -0.00476039 -0.641968 -0.713853 0.0194705 -0.700025 -0.67306 -0.00872907 -0.739536 -0.624494 0 -0.78103 -0.564705 0 -0.825293 -0.534255 0.0160093 -0.845172 -0.403788 -0.0253533 -0.914501 -0.370548 0 -0.928813 -0.270335 0 -0.962766 -0.773018 1.49715e-06 -0.634384 -0.773018 9.10281e-07 -0.634384 -0.773018 9.25935e-07 -0.634384 -0.776775 -0.0136793 -0.62963 -0.788761 1.26924e-05 -0.614699 -0.827104 -7.94004e-06 -0.562049 -0.857572 -0.0273149 -0.513638 -0.880589 0.0222713 -0.473358 -0.923533 -0.018209 -0.383086 -0.917262 1.92561e-05 -0.398284 -0.949386 -1.91238e-05 -0.314111 -0.959661 -0.0436999 -0.277744 -0.979691 0.0419447 -0.196079 -0.987837 -0.0129426 -0.154951 -0.99281 3.17481e-06 -0.119703 -0.998984 -1.47514e-05 -0.0450724 -0.997288 -0.0681309 -0.0278523 -0.998483 0.0163094 0.0525826 -0.99848 8.85301e-07 0.0551138 -0.99848 -3.22437e-06 0.0551187 -0.99848 2.0023e-06 0.0551187 -0.99848 -3.22888e-07 0.0551193 -0.99848 -5.89907e-08 0.0551184 -0.99848 2.75916e-07 0.0551184 -0.99848 2.96226e-07 0.0551184 -0.99848 -2.40759e-07 0.0551187 -0.99848 -1.40312e-07 0.0551187 -0.99848 -2.32928e-08 0.0551186 -0.99848 0 0.0551186 -0.99848 -4.11014e-07 0.0551185 -0.99848 0 0.0551185 0 1 0 0.000339849 1 0.000369237 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -8.66651e-05 1 0.000135631 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.989982 0.120472 0.073629 0.12757 0.991765 -0.0113026 0.96878 0.143371 -0.202263 0.970466 0.120237 -0.20914 0.971026 0.12454 -0.203956 0.224736 0.973703 -0.0373622 0.274651 0.960449 -0.0458665 0.311042 0.94847 -0.0604832 0.15524 0.987116 -0.0387721 0.11862 0.991577 -0.0520073 0.0558336 0.998414 -0.00728212 0.164864 0.986288 -0.0075192 0.138615 0.990342 0.00275885 0.136785 0.990583 -0.00593249 0.162403 0.986709 -0.00547995 0.176819 0.98408 0.0179569 0.171903 0.985 0.0150068 0.169912 0.984645 0.0400577 0.166228 0.984837 0.0496368 0.171335 0.983559 0.0570572 0.162017 0.98275 0.0891795 0.149159 0.986007 0.0744467 0.159865 0.982291 0.0977087 0.157049 0.982969 0.0954285 0.167738 0.981079 0.096684 0.16632 0.983103 0.0764643 0.172327 0.981443 0.0841065 0.182377 0.982121 0.046651 0.186152 0.981509 0.0445771 0.1844 0.982444 0.0282946 0.186357 0.982457 0.00699659 0.186114 0.982504 0.00681515 0.183412 0.982607 -0.0290349 0.183389 0.982611 -0.0290463 0.179235 0.982733 -0.0459393 0.177585 0.982266 -0.0601427 0.153659 0.98576 -0.0683056 0.163496 0.982612 -0.0879886 0.151247 0.982706 -0.106832 0.150785 0.981602 -0.11714 0.123799 0.984651 -0.123033 0.125576 0.982613 -0.136756 0.101105 0.982613 -0.155722 0.101105 0.982614 -0.155719 0.0737526 0.982613 -0.170389 0.0737542 0.982614 -0.170381 0.0363485 0.98245 -0.182952 0.0406017 0.98547 -0.164923 0.00570717 0.980073 -0.198555 0.0137732 0.982615 -0.185143 -0.0172548 0.982615 -0.184852 -0.0292648 0.98604 -0.163914 -0.0477452 0.98262 -0.179385 -0.0647407 0.982735 -0.173324 -0.089351 0.981803 -0.167568 -0.092294 0.994168 -0.0557807 -0.0907771 0.994202 -0.0576348 -0.10284 0.99215 -0.0711427 -0.107538 0.991792 -0.0691674 -0.13454 0.986384 -0.0945819 -0.133716 0.985377 -0.105609 -0.139794 0.98342 -0.115511 -0.112236 0.98407 -0.137872 -0.110106 0.982298 -0.151547 -0.0743424 0.984733 -0.1574 -0.135059 0.99065 0.0192786 -0.135009 0.990639 0.0201596 -0.120309 0.992405 0.0256609 -0.134718 0.990865 0.00612542 -0.123982 0.992162 0.0155813 -0.120458 0.992656 -0.0111587 -0.109163 0.994021 -0.00241428 -0.115807 0.992842 -0.0292063 -0.11009 0.993691 -0.0214154 -0.100862 0.994066 -0.0407323 -0.119599 0.992762 0.0109765 -0.14987 0.988703 0.00214944 -0.272938 0.961698 0.025347 -0.148976 0.988672 0.018255 -0.143672 0.989307 0.0251041 -0.360366 0.931585 0.0478092 -0.348796 0.937099 0.0136324 -0.332903 0.942277 0.0359082 -0.348142 0.936928 0.0310327 -0.385638 0.921843 0.0385859 -0.400559 0.915212 0.044046 -0.469088 0.882542 0.0327982 -0.541221 0.83979 0.0428122 -0.610186 0.791753 0.0282974 -0.600278 0.799468 0.0227601 -0.673584 0.736893 0.0572059 -0.781999 0.622117 0.0380554 -0.76473 0.643925 0.0234246 -0.878916 0.468058 0.0918097 -0.838272 0.54323 0.0469224 -0.907958 0.414369 0.0625354 -0.942693 0.329914 0.0498651 -0.956005 0.286593 0.0626052 -0.99259 0.105651 0.0600249 -0.989996 0.129802 0.0553099 -0.992336 0.10141 0.0706121 -0.991753 0.105118 0.0733254 -0.98969 0.125392 0.0692152 -0.983304 0.179368 -0.0306742 -0.985619 0.136463 -0.0996656 -0.972985 0.126853 -0.192894 -0.968033 0.180228 -0.174443 -0.766671 0.127889 -0.629174 -0.767499 0.132225 -0.627265 -0.766814 0.143064 -0.625723 -0.776987 0.227785 -0.586861 -0.778277 0.196272 -0.596458 -0.825052 0.142474 -0.546801 -0.849275 0.242043 -0.469199 -0.880635 0.083347 -0.466406 -0.918463 0.217667 -0.330223 -0.894984 0.299193 -0.330887 -0.946706 0.126018 -0.296425 -0.092738 0.0776868 -0.992655 -0.262961 0.23198 -0.936502 -0.250939 0.216414 -0.943501 -0.36643 0.148664 -0.918492 -0.406273 0.213329 -0.8885 -0.527722 0.156702 -0.834838 -0.550282 0.207591 -0.808762 0.539623 0.134078 -0.831162 0.392354 0.211179 -0.895244 0.387841 0.216349 -0.895976 0.267543 0.139815 -0.953348 0.234502 0.192969 -0.952771 0.120496 0.18167 -0.975949 0.0723921 0.22066 -0.97266 0.0168254 0.168749 -0.985516 -0.146669 0.228664 -0.962393 0.862445 0.201665 -0.464242 0.782137 0.164201 -0.601082 0.777662 0.173947 -0.604139 0.711163 0.186568 -0.67782 0.662467 0.201364 -0.721519 0.637044 0.133907 -0.759107 0.47957 0.257022 -0.839019 0.926089 0.209827 -0.313579 0.911803 0.18934 -0.36437 0.878396 0.167784 -0.447514 0.966292 0.205895 -0.154558 0.964739 0.22024 -0.144129 0.949676 0.149987 -0.274988 0.965451 0.250311 0.0724466 0.980848 0.192419 -0.0302102 0.980698 0.180851 -0.0743337 0.914548 0.213747 0.343386 0.959267 0.141114 0.244733 0.959539 0.215144 0.181654 0.992915 0.118211 0.012064 0.903384 0.0835978 0.420605 0.903477 0.0830555 0.420513 0.903954 0.0869439 0.418697 0.919876 0.0266056 0.391306 0.925127 0.0897963 0.368885 0.971739 0.113576 -0.206938 0.975098 0.0920656 -0.201763 0.978305 0.0667798 -0.196112 0.984823 0.150903 -0.085743 0.998805 0.0459798 -0.0165655 0.985652 0.133839 0.10285 0.982793 0.0364451 0.18108 0.97383 0.0716477 0.215691 0.960737 0.0902581 0.26237 -0.591167 0.804071 0.0631795 -0.934457 0.341013 0.102471 -0.992315 0.105567 0.0645553 -0.994127 0.0858093 0.0659454 -0.472442 0.878832 0.0667277 -0.348142 0.936171 0.0488046 -0.347425 0.935823 0.0594267 -0.330689 0.942389 0.0504707 -0.331527 0.943093 0.0258031 -0.320135 0.947146 0.0206966 -0.314666 0.948888 -0.0244498 -0.303389 0.952479 -0.0271873 -0.290953 0.954129 -0.0705951 -0.281975 0.956785 -0.0710795 -0.261953 0.958341 -0.113855 -0.0986637 0.994412 -0.0375543 -0.0924432 0.994138 -0.0560685 -0.662904 0.742082 0.09936 -0.642267 0.761296 0.0889994 -0.645396 0.763297 0.0290155 -0.628921 0.777127 0.0230694 -0.620024 0.781496 -0.069526 -0.60295 0.794507 -0.0721823 -0.579323 0.798757 -0.162395 -0.564798 0.809192 -0.161902 -0.525028 0.813145 -0.251278 -0.612994 0.191027 -0.766647 -0.698532 0.206947 -0.685001 -0.706972 0.275309 -0.651456 -0.755618 0.210984 -0.620103 -0.757835 0.226664 -0.611809 -0.699694 0.37978 -0.605141 -0.721109 0.379871 -0.579397 -0.696053 0.442391 -0.565509 -0.720237 0.441975 -0.534711 -0.718067 0.446524 -0.533851 -0.79159 0.444272 -0.419531 -0.795594 0.436079 -0.420554 -0.854378 0.433618 -0.286382 -0.861732 0.418429 -0.286942 -0.897292 0.415817 -0.148199 -0.905194 0.398692 -0.147205 -0.91817 0.396138 -0.00620203 -0.925224 0.379402 -0.0036703 -0.920926 0.378584 0.092569 0.536524 0.840468 -0.0758669 0.656308 0.745801 -0.114193 0.661539 0.744897 -0.0865688 0.691429 0.714384 -0.107615 0.69618 0.713289 -0.0809464 0.729472 0.676285 -0.102517 0.740727 0.670801 0.0367377 0.753918 0.656424 0.0267342 0.736439 0.651613 0.181821 0.748825 0.639014 0.175846 0.695016 0.633457 0.340125 0.708382 0.618316 0.340412 0.693938 0.617616 0.370137 0.700333 0.609475 0.371582 0.717317 0.610189 0.336341 0.732266 0.672952 -0.104506 0.800422 0.578888 -0.155603 0.805127 0.578428 -0.131115 0.825878 0.543658 -0.149538 0.830664 0.543009 -0.12304 0.852744 0.502596 -0.142217 0.86648 0.498656 0.0235481 0.875805 0.482483 0.0132716 0.856068 0.479258 0.193544 0.865124 0.46548 0.186787 0.803175 0.46154 0.376684 0.81238 0.446262 0.375352 0.796811 0.445866 0.407794 0.800837 0.438287 0.408123 0.80262 0.438356 0.404531 0.892967 0.152599 0.423466 0.914303 0.212251 0.344964 0.906663 0.0821302 0.413783 0.880865 0.258307 0.39668 0.868297 0.25821 0.423542 0.866571 0.263412 0.423873 0.881423 0.263513 0.391988 0.877136 0.274713 0.393909 0.942503 0.276529 0.187671 0.938188 0.287268 0.19308 0.957464 0.288543 -0.00237621 0.953486 0.301391 0.00519399 0.936663 0.303154 -0.175384 0.928214 0.334335 -0.163212 0.924033 0.334545 -0.185047 0.915721 0.362406 -0.173544 0.912273 0.362519 -0.190627 0.897939 0.403804 -0.175066 -0.811322 0.574942 0.10582 -0.795806 0.597557 0.0980751 -0.800215 0.59943 0.0184163 -0.786492 0.617446 0.0138211 -0.77615 0.621805 -0.104637 -0.761398 0.639486 -0.106448 -0.732048 0.643834 -0.222676 -0.718939 0.658751 -0.221752 -0.669799 0.66282 -0.334723 -0.57743 0.755372 -0.309818 -0.533949 0.757404 -0.375817 -0.54024 0.752461 -0.376752 -0.514001 0.753429 -0.410058 -0.576551 0.690027 -0.437551 -0.56298 0.690277 -0.454501 -0.635876 0.599316 -0.486295 -0.588913 0.59891 -0.542668 -0.621713 0.557435 -0.550217 -0.465439 0.561623 -0.684066 -0.477467 0.549831 -0.685354 -0.347204 0.550347 -0.75932 -0.351904 0.545514 -0.760643 -0.215386 0.545705 -0.809824 -0.215446 0.545639 -0.809853 -0.0779526 0.545628 -0.834394 -0.0779285 0.545657 -0.834378 0.0621982 0.54566 -0.835695 0.0621911 0.545651 -0.835702 0.200283 0.545631 -0.813741 0.200297 0.545654 -0.813722 0.332898 0.545658 -0.769049 0.3329 0.545662 -0.769046 0.456336 0.545638 -0.702878 0.456339 0.54565 -0.702866 0.566765 0.545651 -0.617286 0.566767 0.545669 -0.617268 0.661783 0.545645 -0.514116 0.661783 0.545639 -0.514122 0.737908 0.545638 -0.397205 0.737899 0.545679 -0.397165 0.793727 0.545674 -0.268771 0.793731 0.545663 -0.268782 0.827572 0.545653 -0.131859 0.827629 0.545544 -0.131954 0.838231 0.544983 0.0190274 0.839218 0.543502 0.0178649 0.8229 0.542007 0.170484 0.824862 0.539555 0.16877 0.782328 0.537219 0.315212 0.784464 0.53491 0.313826 0.752086 0.534854 0.385095 -0.990532 0.134957 -0.0251409 -0.989798 0.124486 0.0693102 -0.92805 0.359729 0.0965364 -0.927821 0.35969 0.0988533 -0.812364 0.575275 0.0955143 -0.765752 0.633973 0.108176 -0.664393 0.742742 0.0831611 -0.50326 0.859424 0.0901096 -0.503936 0.859825 0.0821586 -0.483227 0.872578 0.0714123 -0.484991 0.873988 0.0304749 -0.469838 0.882416 0.0243737 -0.46245 0.88559 -0.043242 -0.447173 0.893249 -0.0462782 -0.429188 0.896284 -0.111684 -0.416651 0.902164 -0.111815 -0.387671 0.904987 -0.175245 -0.30826 0.937582 -0.160984 -0.288877 0.93841 -0.189569 -0.295246 0.936303 -0.190174 -0.279137 0.936964 -0.210191 -0.336163 0.912273 -0.233992 -0.324657 0.912662 -0.248286 -0.405967 0.868182 -0.285397 -0.371033 0.868626 -0.328365 -0.415545 0.842273 -0.343363 -0.304191 0.846651 -0.436635 -0.320359 0.83842 -0.440933 -0.228229 0.839373 -0.493319 -0.234377 0.835956 -0.496231 -0.140966 0.83627 -0.529888 -0.141051 0.836218 -0.529948 -0.0509976 0.836212 -0.54603 -0.0509654 0.836235 -0.545998 0.0406959 0.836237 -0.546856 0.0406834 0.836226 -0.546874 0.131077 0.836213 -0.53251 0.13109 0.836228 -0.532483 0.217845 0.83623 -0.503252 0.217845 0.836232 -0.503249 0.298631 0.836216 -0.459959 0.298632 0.836223 -0.459946 0.370893 0.836223 -0.403942 0.370892 0.836239 -0.403911 0.433063 0.836223 -0.336435 0.433062 0.836223 -0.336433 0.482889 0.836221 -0.259909 0.482873 0.836243 -0.259868 0.51939 0.83624 -0.175887 0.519395 0.836235 -0.175896 0.541606 0.836219 -0.0860282 0.541676 0.836165 -0.0861077 0.549087 0.835606 0.0163457 0.550142 0.834927 0.0154874 0.539516 0.83337 0.120066 0.541277 0.832373 0.119052 0.512951 0.829869 0.219543 0.51415 0.82925 0.219076 0.490991 0.828565 0.269087 0.499334 0.823439 0.269469 0.49476 0.823053 0.278921 0.486496 0.828571 0.277113 0.498068 0.829422 0.252958 0.48247 0.838251 0.254081 0.519831 0.843491 0.135272 0.507155 0.849817 0.143541 0.518546 0.854443 0.0322125 0.506062 0.861332 0.0448173 0.49696 0.86624 -0.0515577 0.464186 0.885437 -0.0230749 0.458209 0.887171 -0.0545238 0.430816 0.902086 -0.0252854 0.419187 0.904116 -0.0827986 0.357394 0.933268 -0.035772 0.355642 0.925371 -0.13118 0.320809 0.944836 -0.066077 0.403899 0.5994 -0.691076 0.524005 0.416126 -0.74314 -0.408937 0.40488 -0.817828 0.500611 0.853884 -0.142376 -0.97948 0.154825 -0.129025 -0.486153 0.248672 -0.837745 0.258493 0.929834 -0.261897 0.254403 0.901132 -0.351057 0.377684 0.525474 -0.762386 -0.817624 0.480076 -0.317834 -0.551322 0.783491 -0.28668 -0.31395 0.94944 -0.000514745 -0.229718 0.97294 -0.0248524 -0.495312 0.868083 0.0331348 -0.600634 0.7593 0.250403 -0.721578 0.6894 0.0636621 -0.748768 0.662006 0.0330784 -0.749406 0.625176 -0.218048 -0.722481 0.68285 -0.108341 -0.669865 0.527301 -0.522718 -0.649545 0.709253 -0.273954 -0.649675 0.705709 -0.28266 -0.363274 0.509364 -0.780115 -0.328041 0.389033 -0.860838 -0.331628 0.379195 -0.863849 -0.293876 0.232624 -0.927105 -0.304745 0.156951 -0.939413 -0.25111 0.151248 -0.956069 -0.222735 0.310072 -0.924254 -0.183862 -0.039887 -0.982142 -0.148299 0.288584 -0.9459 -0.0911559 0.00774253 -0.995807 -0.051534 0.463569 -0.884561 0.00292458 -0.0631569 -0.997999 0.0509767 0.480734 -0.875383 0.0968478 -0.0258693 -0.994963 0.125975 0.166658 -0.977934 0.185194 0.222701 -0.957135 0.160314 0.690592 -0.705254 0.358391 0.610136 -0.706604 0.31787 0.654433 -0.686059 0.351754 0.60057 -0.718042 0.232888 0.962482 -0.139254 0.302093 0.943486 -0.136288 0.314527 0.931789 -0.181227 0.315147 0.93303 -0.173601 0.305498 0.930753 -0.200921 0.261737 0.947225 -0.185091 0.281476 0.937591 -0.204193 0.221801 0.964469 -0.14354 0.232728 0.971413 -0.0468372 0.198094 0.974299 -0.107241 0.191843 0.977819 -0.0840606 0.23055 0.963846 -0.133597 0.287584 0.951975 -0.105071 0.403864 0.900326 -0.162193 0.483218 0.869962 -0.0983157 0.623183 0.765774 -0.158849 0.797535 0.600282 -0.0600008 0.812615 0.574573 -0.0975868 0.974845 0.0584002 -0.215095 0.987046 0.0724909 -0.143126 -0.555196 0.284661 -0.781489 -0.508553 0.403794 -0.760476 -0.486683 0.40454 -0.774266 -0.388169 0.586807 -0.710621 -0.308021 0.544675 -0.780034 -0.345418 0.525955 -0.777212 -0.562954 0.358033 -0.744913 -0.557185 0.325583 -0.763899 -0.555962 0.317121 -0.768336 -0.493915 0.686683 -0.533398 -0.519324 0.506626 -0.68821 -0.704645 0.473952 -0.528058 -0.711053 0.514083 -0.479711 -0.734271 0.333361 -0.591369 -0.786956 0.499278 -0.362521 -0.802027 0.31079 -0.510062 -0.804231 0.318214 -0.501949 -0.915511 0.236762 -0.325243 -0.978702 0.153749 -0.136027 -0.978054 0.151444 -0.143088 -0.977442 0.148246 -0.150436 -0.996466 0.0839097 -0.00393767 -0.996402 0.0827819 -0.0181795 -0.997271 0.0596233 0.0435329 -0.981992 0.0781131 0.172015 -0.976416 0.166648 0.137263 -0.972669 0.159427 0.168813 -0.904837 0.316646 0.284614 -0.904806 0.316591 0.284775 -0.754874 0.609411 0.242452 -0.697226 0.635666 0.331368 -0.722161 0.625152 0.296088 -0.756178 0.607364 0.243525 -0.878413 0.429175 0.210239 -0.247199 0.968932 -0.00797415 -0.242617 0.970095 -0.00721779 -0.313622 0.94954 0.00392142 -0.32848 0.944388 -0.0152291 -0.378386 0.925436 0.019809 -0.395934 0.917644 0.0341442 -0.407018 0.911884 0.0529527 -0.416976 0.906026 0.0724357 -0.426181 0.897495 0.113459 -0.432474 0.88184 0.187947 -0.424351 0.861608 0.278492 -0.442297 0.858297 0.260192 -0.515941 0.836104 0.186372 -0.574489 0.80533 0.146309 -0.595145 0.791571 0.138631 -0.613047 0.778775 0.132973 -0.634866 0.760872 0.134238 -0.645744 0.751118 0.137249 -0.655283 0.742122 0.140922 -0.678539 0.71814 0.154465 0.946273 0.108103 -0.304764 0.945956 0.106273 -0.306387 0.946339 0.10842 -0.304446 0.946879 0.110988 -0.30183 0.948289 0.112848 -0.29667 0.93703 0.327016 -0.122614 0.938776 0.308461 -0.153464 0.940204 0.338478 -0.0380606 0.77808 0.601246 -0.181923 0.762954 0.640419 -0.0881141 0.43093 0.867513 -0.248436 0.424616 0.87459 -0.234081 0.289192 0.917467 -0.273172 0.245791 0.937826 -0.24509 0.962708 0.0690865 -0.261574 0.96342 0.0710815 -0.258398 0.965855 0.0735239 -0.248432 0.97211 0.0737017 -0.222644 -0.719984 0.684383 0.115076 -0.785098 0.539278 0.304632 -0.797876 0.596096 -0.0898004 -0.888184 0.421523 0.182885 -0.82123 0.496893 -0.280496 -0.885822 0.434143 -0.163826 -0.807561 0.32392 -0.492871 -0.996274 0.0805479 -0.0308141 -0.964658 0.188897 0.183721 -0.964772 0.170721 0.200173 -0.911442 0.273989 0.306926 -0.908757 0.316032 0.272552 -0.829865 0.40627 0.382452 -0.766296 0.607394 0.209435 -0.349446 0.936323 0.0344509 -0.48387 0.864945 0.133188 -0.481301 0.875773 0.0370393 -0.679448 0.668713 0.301949 -0.730949 0.66278 0.162592 -0.806412 0.40617 0.429797 -0.852876 0.516436 0.0767879 -0.896701 0.27612 0.345954 -0.922577 0.383915 -0.0382263 -0.944594 0.325961 0.0386159 -0.917381 0.244387 -0.314144 -0.302881 0.209137 -0.929798 -0.351803 0.167837 -0.920905 -0.378513 0.207692 -0.901993 -0.381582 0.192497 -0.904068 -0.456007 0.193494 -0.868687 -0.482056 0.137611 -0.865266 0.688556 0.125983 -0.714156 0.704917 0.175033 -0.687354 0.566246 0.166722 -0.807198 0.563059 0.116946 -0.8181 0.473967 0.339455 -0.812481 0.703762 0.216686 -0.676585 0.704713 0.240723 -0.667407 0.718833 0.35378 -0.59843 0.74527 0.253394 -0.616737 0.746764 0.280245 -0.603163 0.76787 0.401343 -0.499299 0.804971 0.258489 -0.534046 0.808196 0.270828 -0.522945 0.977293 0.145776 -0.153779 0.952402 0.226958 -0.203522 0.961534 0.25455 -0.103227 0.809615 0.507045 -0.295684 0.803545 0.554935 -0.21532 0.596596 0.714729 -0.365015 0.582882 0.745882 -0.322348 0.382076 0.825858 -0.4147 0.421289 0.762651 -0.490795 0.342216 0.78316 -0.51918 0.282743 0.838298 -0.466169 0.189184 0.792723 -0.579482 0.29179 0.777643 -0.556893 0.623233 0.161461 -0.765187 0.616301 0.194211 -0.763187 0.622757 0.394016 -0.675962 0.622003 0.398476 -0.674039 0.662231 0.548943 -0.510011 0.675724 0.462303 -0.574171 0.808712 0.272502 -0.521275 0.811962 0.281179 -0.511524 0.888166 0.315911 -0.333708 0.868649 0.225892 -0.440933 0.871179 0.23184 -0.432778 0.968401 0.15523 -0.1952 0.972051 0.179382 -0.151455 0.978132 0.192902 -0.0777619 0.91595 0.361515 -0.17419 0.915017 0.398937 -0.0599474 0.664616 0.696606 -0.270233 0.648558 0.732189 -0.208017 0.399994 0.857997 -0.322251 0.403217 0.853909 -0.329021 0.271412 0.889275 -0.368137 0.246222 0.909126 -0.335952 0.940259 0.248434 -0.232796 0.859469 0.380976 -0.340839 0.855042 0.357322 -0.375798 0.747814 0.5562 -0.362513 0.742763 0.582567 -0.330029 0.533172 0.701542 -0.472828 0.570648 0.586709 -0.574572 0.417442 0.748948 -0.514606 0.50622 0.538287 -0.673786 0.413098 0.559257 -0.718736 0.480534 0.239478 -0.843645 0.415617 0.24714 -0.87532 0.345721 0.503723 -0.791669 0.370216 0.0366941 -0.928221 0.314097 0.223503 -0.922708 0.309267 0.178173 -0.934135 0.264695 0.182134 -0.946976 -0.35634 -0.933926 0.0283601 0.828915 -0.532104 -0.172526 0.872062 -0.463775 -0.156272 0.952713 -0.240826 0.185311 -0.597982 -0.800832 0.0329361 -0.802425 -0.594955 0.0462867 -0.32353 -0.946056 0.0175205 -0.317678 -0.947258 0.0422338 0.834209 -0.520918 -0.180942 -0.905055 -0.24519 0.347501 0.932687 -0.0076476 0.360605 0.953678 -0.103556 0.282444 0.977895 -0.0905276 0.188484 0.967504 0.120381 0.22236 0.986003 -0.0477132 0.159757 0.503044 -0.109967 0.857236 0.201212 -0.222872 0.953856 0.141078 -0.115414 0.983248 0.0223723 -0.24676 0.968818 0.0458975 -0.158912 0.986225 -0.0942734 -0.182818 0.978617 -0.111304 -0.235264 0.965537 -0.211149 -0.161171 0.964075 -0.262208 -0.274489 0.92515 -0.32403 -0.180057 0.928754 -0.421202 -0.29594 0.857326 -0.412266 -0.231922 0.88105 -0.528682 -0.248416 0.811656 -0.537512 -0.302904 0.786975 -0.625579 -0.232751 0.744632 -0.649928 -0.33429 0.682528 -0.709175 -0.246702 0.660461 -0.759552 -0.347756 0.549678 -0.764636 -0.283731 0.578644 -0.838924 -0.288209 0.461674 -0.835701 -0.327601 0.440774 -0.899049 -0.248589 0.360437 -0.880442 -0.409307 0.239354 -0.928467 -0.202597 0.311293 -0.937357 -0.317986 0.14229 -0.945759 -0.285588 0.15485 -0.96897 -0.242684 0.0469122 -0.99012 -0.122107 0.0689376 -0.952802 -0.299324 0.0507228 -0.910911 -0.410358 0.0429834 -0.81097 -0.238867 0.534106 -0.811076 -0.237707 0.534464 -0.781106 -0.2368 0.577754 -0.750308 -0.249043 0.612385 -0.751078 -0.23472 0.617081 -0.687129 -0.231314 0.688729 -0.686392 -0.145172 0.712594 -0.605161 -0.281848 0.744542 -0.600868 -0.228557 0.765976 -0.535151 -0.223556 0.814639 -0.520777 -0.0591454 0.851641 -0.443604 -0.275274 0.852901 -0.368052 -0.092082 0.925234 -0.0727017 -0.196066 0.977892 -0.171894 -0.207115 0.963097 -0.171116 -0.202031 0.964315 -0.223017 -0.207695 0.952432 -0.266654 -0.22438 0.93731 -0.270878 -0.208658 0.939727 -0.377281 -0.218837 0.899872 0.0375892 -0.248257 0.967965 -0.0120338 -0.193718 0.980984 -0.0735215 -0.200754 0.976879 0.0271683 -0.194361 0.980554 0.127325 -0.18179 0.975059 0.154365 -0.0436495 0.987049 0.750693 -0.133411 0.647041 0.674883 -0.148919 0.722742 0.677142 -0.138694 0.722663 0.594484 -0.155426 0.788943 0.596861 -0.144979 0.789137 0.498354 -0.161828 0.851736 0.514999 -0.0696367 0.854358 0.401478 -0.231778 0.886056 0.419232 -0.159686 0.893726 0.29936 -0.177352 0.937513 0.328486 0.0371903 0.943776 0.223249 -0.243558 0.943843 0.813601 -0.186959 0.550545 0.788876 -0.135357 0.59946 0.748427 -0.144067 0.64738 0.815609 -0.139162 0.561619 0.874619 -0.12409 0.468661 0.887156 -0.0338671 0.460225 0.948893 -0.230575 -0.215495 -0.306421 -0.948799 0.0767245 -0.316164 -0.946107 0.0701538 -0.30046 -0.947404 0.110225 -0.309942 -0.944954 0.104868 -0.29208 -0.945538 0.14369 -0.301108 -0.943332 0.139496 -0.280872 -0.943166 0.177619 -0.288988 -0.941266 0.174655 -0.266579 -0.940272 0.211716 -0.273334 -0.938744 0.209878 -0.248952 -0.936868 0.245565 -0.254211 -0.935709 0.244592 -0.227932 -0.932913 0.278784 -0.231613 -0.932118 0.278409 -0.203375 -0.928354 0.311122 -0.205426 -0.927917 0.311078 -0.175014 -0.923104 0.342416 -0.175436 -0.923015 0.342442 -0.142828 -0.917086 0.372228 -0.141577 -0.917352 0.37205 -0.106598 -0.910203 0.400209 -0.103695 -0.910829 0.399547 -0.066194 -0.90234 0.425912 -0.0617216 -0.90333 0.424483 -0.0217448 -0.893413 0.44871 -0.0157877 -0.894787 0.446213 0.0268982 -0.88327 0.468093 0.0341345 -0.885046 0.464251 0.079547 -0.871784 0.483389 0.0878372 -0.873999 0.477923 0.135966 -0.85884 0.49387 0.145056 -0.86156 0.486491 0.196115 -0.844241 0.498795 0.205652 -0.847548 0.489254 0.259333 -0.827948 0.497241 0.268973 -0.831981 0.485244 0.345365 -0.801079 0.488872 0.82652 -0.535984 -0.172009 0.828888 -0.532573 -0.171201 0.831853 -0.550711 -0.0688342 0.82524 -0.55883 -0.081782 0.808753 -0.587846 0.0188431 0.807434 -0.589776 0.0146073 0.776721 -0.622229 0.097652 0.77755 -0.620148 0.104081 0.739338 -0.652007 0.168127 0.73853 -0.648205 0.185481 0.697719 -0.677488 0.232805 0.691965 -0.674024 0.258605 0.650952 -0.700338 0.292896 0.638612 -0.698378 0.323178 0.601124 -0.720365 0.346013 0.581469 -0.720114 0.378589 0.546902 -0.73886 0.39368 0.521201 -0.739978 0.425184 0.482562 -0.759293 0.436587 0.45566 -0.760833 0.462069 0.41539 -0.779413 0.469005 0.388721 -0.781003 0.488805 0.350146 -0.797556 0.491225 0.334118 -0.781708 0.526591 0.273729 -0.805845 0.525058 0.266302 -0.800242 0.537305 0.208371 -0.821834 0.530256 0.200639 -0.817177 0.540339 0.145397 -0.836391 0.528498 0.137689 -0.832519 0.536613 0.0856144 -0.849423 0.520722 0.078272 -0.846237 0.527027 0.0291343 -0.861108 0.507587 0.0224303 -0.858522 0.512286 -0.0237112 -0.871508 0.489807 -0.0295257 -0.869466 0.493109 -0.0726477 -0.880709 0.468054 -0.0773334 -0.87918 0.470173 -0.117755 -0.888882 0.442745 -0.121169 -0.887829 0.443935 -0.158813 -0.896072 0.414529 -0.160826 -0.895476 0.41504 -0.195876 -0.90239 0.383829 -0.196402 -0.902239 0.383916 -0.229085 -0.907935 0.350961 -0.228097 -0.908214 0.350883 -0.258393 -0.912748 0.316423 -0.25582 -0.913469 0.316435 -0.283992 -0.916929 0.28034 -0.279806 -0.918101 0.280712 -0.30593 -0.920531 0.242958 -0.300128 -0.92217 0.243978 -0.324126 -0.923604 0.204691 -0.316787 -0.925712 0.206647 -0.338496 -0.926199 0.166057 -0.330118 -0.928671 0.169091 -0.34917 -0.928292 0.127884 -0.340457 -0.930965 0.131882 -0.357109 -0.929768 0.0894705 0.871158 -0.447989 -0.200974 0.890161 -0.411912 -0.194788 0.899218 -0.428493 -0.0883237 0.895829 -0.435007 -0.0908816 0.886816 -0.461807 0.0170507 0.886983 -0.461482 0.017211 0.861301 -0.494579 0.11641 0.86469 -0.487612 0.120603 0.825509 -0.524476 0.208472 0.831121 -0.511764 0.217565 0.781573 -0.550579 0.293269 0.787721 -0.534148 0.306892 0.730268 -0.573777 0.370794 0.735341 -0.555925 0.387584 0.673122 -0.594794 0.439462 0.676314 -0.576393 0.458662 0.611131 -0.613852 0.499705 0.611951 -0.595999 0.519905 0.543207 -0.632525 0.552122 0.541873 -0.617081 0.570601 0.47121 -0.651959 0.594063 0.468154 -0.638603 0.610752 0.396215 -0.671722 0.625942 0.3918 -0.660182 0.640822 0.320295 -0.690969 0.648054 0.314862 -0.681002 0.661134 0.244608 -0.709357 0.661044 0.238463 -0.700751 0.672372 0.169997 -0.726688 0.665602 0.163416 -0.719264 0.675244 0.0976793 -0.742654 0.662513 0.0909577 -0.736299 0.670515 0.0279405 -0.757354 0.652406 0.0213353 -0.751959 0.658864 -0.038606 -0.770735 0.635985 -0.0448449 -0.766222 0.641009 -0.101412 -0.782789 0.613968 -0.10703 -0.779113 0.61768 -0.160496 -0.793682 0.586779 -0.165302 -0.790786 0.589349 -0.215389 -0.80339 0.555132 -0.219182 -0.801252 0.556735 -0.266019 -0.812019 0.51948 -0.268618 -0.810629 0.520312 -0.312434 -0.819675 0.480123 -0.313683 -0.819033 0.480403 -0.354318 -0.826379 0.437671 -0.354004 -0.826536 0.43763 -0.391752 -0.832278 0.392231 -0.389673 -0.833295 0.392142 -0.42458 -0.837462 0.344078 -0.420534 -0.839423 0.344268 -0.452451 -0.84203 0.293724 -0.446347 -0.844987 0.29457 -0.475107 -0.846075 0.241721 -0.467523 -0.849785 0.243489 -0.492462 -0.84944 0.189557 0.954692 -0.181278 -0.236011 0.975551 -0.191547 -0.10775 0.970279 -0.221486 -0.0974828 0.984663 -0.174048 0.0120798 0.978546 -0.20501 0.0204535 0.966945 -0.222211 0.125061 0.958051 -0.252714 0.135184 0.951643 -0.1907 0.240849 0.942049 -0.225232 0.248625 0.905079 -0.248524 0.345061 0.89636 -0.270608 0.351156 0.909136 -0.304465 0.284207 0.823029 -0.364942 0.435248 0.82793 -0.344113 0.442852 0.765121 -0.379341 0.52028 0.769504 -0.357574 0.529155 0.700171 -0.392844 0.596182 0.703666 -0.371279 0.60581 0.628523 -0.406269 0.663253 0.630867 -0.38688 0.672556 0.550954 -0.421254 0.720413 0.552296 -0.403672 0.729396 0.468261 -0.437294 0.767793 0.468699 -0.421404 0.776363 0.382277 -0.453725 0.804983 0.381912 -0.439387 0.81307 0.294086 -0.470214 0.832113 0.293015 -0.457269 0.839671 0.204594 -0.486471 0.849404 0.202915 -0.474811 0.856376 0.115348 -0.50207 0.8571 0.11317 -0.491616 0.863427 0.0268287 -0.516971 0.855583 0.0242616 -0.507641 0.861227 -0.0599776 -0.53096 0.845272 -0.0628129 -0.522705 0.850197 -0.144077 -0.543874 0.826706 -0.147041 -0.536677 0.830877 -0.225278 -0.555786 0.80022 -0.228236 -0.549613 0.803638 -0.302613 -0.56654 0.766457 -0.305406 -0.561412 0.769119 -0.375679 -0.57618 0.725867 -0.37813 -0.572136 0.72779 -0.444247 -0.58478 0.678733 -0.446162 -0.581892 0.679957 -0.507469 -0.592328 0.625797 -0.508599 -0.590748 0.626374 -0.565178 -0.599028 0.567221 -0.565251 -0.598933 0.567249 -0.616854 -0.605036 0.503411 -0.615558 -0.60666 0.503043 -0.661748 -0.610569 0.43508 -0.658842 -0.614076 0.434556 -0.699471 -0.615826 0.362628 -0.9254 -0.354955 0.132823 -0.955849 -0.24657 0.159862 -0.767062 -0.628605 0.128343 -0.782125 -0.622047 0.0365904 -0.82584 -0.561167 0.0554993 -0.718369 -0.69493 0.0319049 -0.608772 -0.792893 0.0268091 -0.93978 -0.24313 0.240209 -0.959877 -0.0780794 0.269331 -0.749504 -0.627496 0.210933 -0.772026 -0.622704 0.127344 -0.51028 -0.855861 0.0843601 -0.519335 -0.853486 0.0430428 -0.503926 -0.863069 0.034199 -0.433418 -0.90104 0.0165823 -0.388496 -0.92125 0.0192011 -0.886484 -0.242901 0.393885 -0.891997 -0.282232 0.35311 -0.725528 -0.625158 0.287728 -0.753602 -0.622733 0.210448 -0.498386 -0.855585 0.139948 -0.516582 -0.852386 0.0811236 -0.356454 -0.932605 0.0564719 -0.363479 -0.93122 0.0266985 -0.350718 -0.936306 0.0181293 -0.821485 -0.55546 0.128945 -0.828385 -0.546061 0.124888 -0.803303 -0.553212 0.220594 -0.806945 -0.54854 0.218962 -0.773492 -0.553069 0.309557 -0.773386 -0.553198 0.309591 -0.728853 -0.55507 0.400837 -0.729493 -0.554318 0.400713 -0.674432 -0.553097 0.489106 -0.676921 -0.550209 0.488925 -0.612477 -0.545781 0.571834 -0.616095 -0.541526 0.571993 -0.543079 -0.533856 0.648123 -0.546887 -0.529218 0.648724 -0.466021 -0.518249 0.717106 -0.46929 -0.514051 0.717996 -0.38143 -0.499745 0.777667 -0.38365 -0.496689 0.778533 -0.289817 -0.47905 0.828564 -0.290689 -0.477746 0.829011 -0.192008 -0.456838 0.868581 -0.19143 -0.457789 0.868207 -0.0891672 -0.43375 0.89661 -0.0871968 -0.437362 0.895048 0.0171945 -0.410429 0.91173 0.0203923 -0.417037 0.908661 0.125372 -0.387528 0.913293 0.129513 -0.397309 0.9085 -0.833137 -0.549538 0.0623764 -0.813182 -0.580619 0.0402049 -0.958782 -0.272909 0.0791009 -0.956103 -0.28319 0.0752953 0.930078 -0.333812 -0.153377 0.959567 -0.232155 -0.159168 0.980285 -0.151737 -0.126562 0.984968 -0.166886 -0.0445809 0.985861 -0.153726 -0.0666757 0.924072 -0.377441 -0.0602461 0.915691 -0.363527 -0.171344 0.89944 -0.405946 -0.161915 0.832976 -0.54455 0.098066 0.806854 -0.570847 0.152053 0.87211 -0.462007 0.16116 0.860998 -0.504762 -0.062427 0.849835 -0.526652 0.0204306 0.889297 -0.456891 0.020051 0.365948 -0.155487 0.917554 0.344919 -0.361209 0.866348 0.339978 -0.345037 0.874851 0.540335 -0.309162 0.782597 0.54442 -0.330682 0.77088 0.631124 -0.293777 0.717898 0.634217 -0.317137 0.70512 0.713826 -0.279642 0.642069 0.715672 -0.30406 0.628778 0.787143 -0.266216 0.556358 0.787649 -0.290917 0.543118 0.8493 -0.253438 0.463097 -0.672893 -0.739056 0.031796 -0.680701 -0.732065 0.0269559 -0.676328 -0.734591 0.0543756 -0.680107 -0.731259 0.0520967 -0.667043 -0.737009 0.108954 -0.67652 -0.728938 0.104741 -0.652543 -0.735479 0.182368 -0.659581 -0.729743 0.180077 -0.629897 -0.733922 0.254144 -0.634167 -0.730555 0.253222 -0.596091 -0.732325 0.329204 -0.599856 -0.729412 0.328834 -0.554358 -0.728227 0.402955 -0.558141 -0.72529 0.403029 -0.506306 -0.721026 0.473049 -0.50973 -0.718301 0.473517 -0.451972 -0.710916 0.538814 -0.454563 -0.708759 0.539474 -0.391065 -0.698153 0.599709 -0.392476 -0.696901 0.600243 -0.323431 -0.682936 0.654974 -0.323485 -0.682883 0.655002 -0.249178 -0.66542 0.703653 -0.247809 -0.666875 0.702757 -0.168596 -0.645789 0.744669 -0.165885 -0.649033 0.742454 -0.0822661 -0.624245 0.776885 -0.0784018 -0.62955 0.772994 0.00887845 -0.601075 0.799143 0.0136399 -0.608734 0.793257 0.103672 -0.576675 0.810369 0.108969 -0.586911 0.802285 0.208997 -0.547944 0.809986 0.233572 -0.365582 0.900996 0.238309 -0.378597 0.894356 0.256608 -0.112188 0.959982 0.354499 -0.187009 0.916165 0.861196 -0.479713 -0.167979 0.865706 -0.497452 -0.0556377 0.923694 -0.378248 -0.0609685 0.914991 -0.400703 0.0472112 0.986859 -0.154604 0.0469809 0.974845 -0.212163 0.0682976 0.996302 0.0845684 0.015175 0.98958 -0.105941 0.0975084 0.810789 -0.560408 0.169009 0.780086 -0.587906 0.214086 0.880319 -0.411347 0.236287 0.830066 -0.458232 0.317828 0.910046 -0.230404 0.344573 0.848609 -0.276065 0.451277 0.850292 -0.52588 0.0213078 0.829638 -0.551158 0.0890241 0.913812 -0.395036 0.0943156 0.885104 -0.428916 0.180614 0.957309 -0.217016 0.190956 0.903985 -0.266098 0.334669 0.933857 -0.0972538 0.34417 0.874869 -0.137821 0.464338 0.899001 -0.0242728 0.437274 0.788094 -0.289154 0.543414 0.848042 -0.068849 0.525438 0.73988 -0.176017 0.649304 0.743571 -0.164457 0.648117 0.66536 -0.108674 0.73857 0.624529 -0.205599 0.753454 0.575146 -0.0906496 0.813013 0.462618 -0.244673 0.852126 0.447516 -0.345256 0.824941 0.4428 -0.326202 0.835177 -0.428261 -0.903273 0.0262669 -0.423086 -0.905514 0.0322997 -0.4199 -0.906373 0.0466025 -0.427073 -0.903346 0.0396836 -0.414712 -0.906364 0.0807403 -0.426454 -0.901678 0.0715162 -0.406352 -0.904992 0.125969 -0.417368 -0.900952 0.118705 -0.394248 -0.902975 0.170891 -0.404221 -0.899577 0.165428 -0.377002 -0.900265 0.217697 -0.385608 -0.897517 0.213938 -0.354946 -0.896638 0.264677 -0.361923 -0.894529 0.262355 -0.328445 -0.892016 0.310535 -0.333665 -0.890506 0.309301 -0.297527 -0.886337 0.354803 -0.300847 -0.885409 0.354318 -0.262019 -0.879533 0.3972 -0.263313 -0.879181 0.397124 -0.221661 -0.8715 0.43744 -0.22088 -0.871709 0.437419 -0.17636 -0.862117 0.475028 -0.173417 -0.862898 0.474693 -0.125958 -0.851263 0.509398 -0.120841 -0.852623 0.508362 -0.070427 -0.838804 0.539859 -0.0631846 -0.840754 0.537717 -0.0099824 -0.824653 0.565551 -0.000662953 -0.827231 0.561862 0.0551877 -0.808733 0.585581 0.066387 -0.811971 0.579911 0.124613 -0.790998 0.598994 0.13745 -0.794956 0.590891 0.197674 -0.771459 0.604794 0.211822 -0.776229 0.593801 0.273694 -0.750135 0.601988 0.288655 -0.755817 0.587724 0.351567 -0.727141 0.589633 0.366787 -0.733892 0.571726 0.430154 -0.702623 0.566824 0.444935 -0.710622 0.545022 0.50802 -0.676792 0.532793 0.521554 -0.686257 0.506984 0.583096 -0.650185 0.487092 0.594549 -0.661399 0.457233 0.652932 -0.623714 0.429721 0.661311 -0.636722 0.396551 0.703901 -0.606698 0.369378 0.70839 -0.620059 0.337209 0.74593 -0.591637 0.305866 -0.54002 -0.841097 0.0305606 -0.552018 -0.833481 0.0241882 -0.547224 -0.83555 0.0490011 -0.553219 -0.831783 0.0456869 -0.540593 -0.836162 0.0926966 -0.550836 -0.829902 0.0885542 -0.529197 -0.834797 0.151868 -0.537864 -0.829701 0.149326 -0.512093 -0.832821 0.210166 -0.518923 -0.82891 0.208871 -0.486908 -0.830193 0.271479 -0.492593 -0.826974 0.271048 -0.455263 -0.825971 0.332426 -0.459936 -0.823303 0.332613 -0.418157 -0.819895 0.391046 -0.42168 -0.817827 0.391593 -0.37564 -0.811961 0.446783 -0.377831 -0.810613 0.447382 -0.32747 -0.802178 0.499274 -0.328215 -0.801689 0.499569 -0.273414 -0.790516 0.548023 -0.272714 -0.791015 0.547652 -0.213415 -0.77691 0.592339 -0.211314 -0.778567 0.590914 -0.147476 -0.761313 0.63139 -0.144124 -0.764302 0.628547 -0.0758071 -0.743685 0.664218 -0.0714306 -0.748197 0.65962 0.00109325 -0.724061 0.689735 0.00622218 -0.730335 0.683061 0.0825643 -0.702561 0.706817 0.0880718 -0.710816 0.697842 0.167671 -0.679349 0.714403 0.150499 -0.645847 0.748487 0.271586 -0.596131 0.755559 0.286842 -0.606189 0.741793 0.363797 -0.570546 0.736294 0.379612 -0.582334 0.718875 0.454557 -0.544767 0.704703 0.470189 -0.558331 0.683512 0.542288 -0.519072 0.660672 0.556901 -0.534402 0.635827 0.625347 -0.493643 0.604366 0.638089 -0.510684 0.576233 0.701858 -0.46873 0.536366 0.711989 -0.487443 0.505441 0.769642 -0.444961 0.457887 0.776428 -0.464688 0.425704 0.81587 -0.432273 0.384051 0.822968 -0.481177 0.30198 0.746578 -0.604835 0.277122 0.782512 -0.57545 0.237765 -0.860971 -0.239889 0.448533 -0.860618 -0.242734 0.44768 -0.695287 -0.620741 0.362295 -0.729647 -0.620381 0.28765 -0.484792 -0.853277 0.19208 -0.506134 -0.851565 0.136621 -0.348183 -0.932653 0.0944894 -0.361656 -0.930802 0.0530346 -0.312636 -0.948746 0.0462514 -0.318341 -0.947712 0.0223874 -0.325238 -0.945366 0.0224325 -0.335296 -0.941903 0.019865 -0.339361 -0.940499 0.0172209 -0.333073 -0.941871 0.0440598 -0.338974 -0.939997 0.0387649 -0.32805 -0.941843 0.0729053 -0.338775 -0.938627 0.0648956 -0.321803 -0.940522 0.108915 -0.332182 -0.937643 0.102375 -0.312844 -0.93869 0.14488 -0.322629 -0.936153 0.139746 -0.300539 -0.93631 0.181657 -0.309235 -0.934178 0.178002 -0.284677 -0.933336 0.21873 -0.291874 -0.931653 0.216406 -0.265186 -0.929752 0.255415 -0.270757 -0.928501 0.254119 -0.242028 -0.925505 0.291313 -0.245875 -0.924669 0.290745 -0.215048 -0.920528 0.326164 -0.217092 -0.920096 0.32603 -0.183976 -0.914723 0.35977 -0.184197 -0.914677 0.359773 -0.148739 -0.90799 0.391702 -0.147066 -0.908333 0.391539 -0.109124 -0.900217 0.421545 -0.105554 -0.900945 0.420899 -0.0650197 -0.891273 0.448781 -0.0596061 -0.892385 0.447321 -0.0165396 -0.881058 0.472718 -0.00933372 -0.88257 0.470088 0.0363669 -0.869433 0.49271 0.0451814 -0.871357 0.488565 0.0934669 -0.856276 0.507991 0.10368 -0.858648 0.50197 0.154452 -0.841488 0.517729 0.165808 -0.844373 0.509453 0.219104 -0.824918 0.52106 0.231211 -0.828398 0.510194 0.286689 -0.806539 0.517015 0.299145 -0.810753 0.503181 0.356523 -0.786327 0.50456 0.368802 -0.791457 0.487424 0.427569 -0.764358 0.48264 0.439028 -0.77064 0.461918 0.497935 -0.741111 0.450351 0.507864 -0.748874 0.425748 0.565633 -0.717241 0.40697 0.573058 -0.726701 0.378827 0.620094 -0.698747 0.356702 0.623752 -0.708866 0.329306 0.668437 -0.680355 0.300516 0.668379 -0.690587 0.276331 0.71279 -0.659904 0.237605 0.70991 -0.669702 0.218008 0.749813 -0.639339 0.17037 0.745957 -0.647116 0.157444 0.780814 -0.61701 0.0981289 0.778449 -0.62078 0.093002 0.805981 -0.591642 0.0187947 0.807448 -0.589562 0.0210677 0.822773 -0.564282 -0.0680483 0.829964 -0.554611 -0.0597199 0.827195 -0.535066 -0.171619 0.840237 -0.516972 -0.163528 -0.897577 0.203757 -0.390946 -0.774327 -0.150287 -0.614681 -0.425733 -0.904448 -0.0269124 -0.976762 -0.0977654 -0.19073 -0.878924 -0.13547 -0.457319 -0.986278 0.131091 -0.100359 -0.998573 0.00431065 0.0532322 -0.976464 -0.202056 0.0754359 -0.958813 -0.282248 0.0318439 -0.984182 -0.162943 0.0695318 -0.986883 -0.15102 0.0570511 -0.994877 -0.0514734 -0.0870099 -0.982827 0.150296 -0.107065 -0.999395 0.0346085 0.00345118 -0.996893 0.0143948 0.0774446 -0.984607 -0.174596 0.00803708 -0.99858 0.00361205 0.053153 -0.953441 0.200902 -0.224921 -0.867123 0.21773 -0.447986 -0.952367 0.185742 -0.241861 -0.955555 0.187832 -0.22723 -0.804785 0.254276 -0.536345 -0.87986 0.252987 -0.402298 -0.891866 0.259237 -0.370635 -0.845302 0.289018 -0.44937 -0.86084 0.283488 -0.422598 -0.707042 0.311172 -0.63503 -0.604843 0.313632 -0.731984 -0.678585 0.470696 -0.563887 -0.649744 0.292749 -0.701521 -0.545565 0.132355 -0.827551 -0.555663 -0.0250447 -0.83103 -0.579524 0.0265565 -0.814523 -0.739578 -0.0545863 -0.670854 -0.723938 -0.0388251 -0.688772 -0.70339 -0.0309275 -0.710131 -0.992059 -0.120598 -0.0357071 -0.912912 -0.406186 -0.0400637 -0.954466 -0.296163 -0.0358161 -0.987903 -0.149243 -0.042113 -0.993566 -0.0495856 -0.101823 -0.968461 -0.221282 -0.114536 -0.829799 -0.558006 -0.00797994 -0.43211 -0.901403 0.0274636 -0.505266 -0.862667 0.0226292 -0.721874 -0.691798 -0.0176988 -0.76812 -0.640306 0.00054834 -0.610733 -0.791812 0.00629902 -0.631426 -0.775271 0.0160066 -0.538743 -0.842396 0.011176 -0.386616 -0.92161 0.0341152 -0.349015 -0.936591 0.0314089 -0.338234 -0.940775 0.023235 -0.321643 -0.946319 0.0320309 -0.60057 -0.799543 0.00683335 -0.542395 -0.840083 0.00832705 -0.526807 -0.849835 0.0159765 -0.430557 -0.902538 0.00684981 -0.800984 -0.595469 0.0619796 -0.848899 -0.528117 0.0215423 -0.848029 -0.527734 0.0484128 -0.554788 -0.831757 0.0197517 -0.52565 -0.850651 0.00924001 -0.395757 -0.918349 0.00335006 -0.402968 -0.914606 0.0333552 -0.355772 -0.933999 0.0327299 -0.404872 -0.907513 -0.111796 -0.393256 -0.906792 -0.151916 -0.557192 -0.814031 -0.163985 -0.446543 -0.867201 -0.220366 -0.69794 -0.673486 -0.24351 -0.569767 -0.760122 -0.312378 -0.835551 -0.441177 -0.32744 -0.719566 -0.560243 -0.410308 -0.904238 -0.179321 -0.387553 -0.840593 -0.264787 -0.472537 -0.900673 -0.0567485 -0.430776 -0.918907 -0.129829 -0.372499 -0.934191 -0.0736028 -0.349099 -0.813134 -0.43309 -0.388903 -0.903576 -0.306764 -0.299077 -0.647747 -0.699441 -0.302003 -0.774039 -0.592463 -0.223276 -0.496631 -0.843108 -0.20622 -0.615146 -0.775531 -0.141943 -0.393688 -0.909968 -0.13026 -0.484553 -0.871069 -0.0803014 -0.353655 -0.932175 -0.0773157 -0.357583 -0.931712 -0.0636231 -0.450089 -0.892595 -0.0263312 -0.323356 -0.945018 0.0488117 -0.325152 -0.94434 0.0499883 -0.381656 -0.922663 0.0550657 -0.342712 -0.938591 0.0399346 -0.373959 -0.926932 0.0308352 -0.424862 -0.904891 0.0257676 -0.415355 -0.909536 -0.0149851 -0.502621 -0.863598 0.0396307 -0.474439 -0.875129 -0.0951659 -0.594963 -0.803428 -0.0228439 -0.965335 -0.0874979 -0.24591 -0.971416 -0.0373749 -0.234424 -0.917679 -0.296661 -0.264305 -0.962725 -0.166562 -0.213115 -0.824969 -0.513733 -0.235594 -0.912645 -0.364962 -0.18407 -0.993788 -0.0440109 -0.102219 -0.986767 -0.0379507 -0.15764 -0.958368 -0.205617 -0.198124 -0.970734 -0.17699 -0.162326 -0.861891 -0.473866 -0.18054 -0.938877 -0.319724 -0.127618 -0.725573 -0.674184 -0.137912 -0.845308 -0.527168 -0.0868824 -0.920622 -0.388636 -0.0376584 -0.919623 -0.384619 -0.0797604 -0.761692 -0.641985 -0.0876431 -0.873735 -0.485183 -0.0344115 -0.623909 -0.780304 -0.043169 -0.740289 -0.672288 0.00082572 -0.563922 -0.825803 -0.00640294 -0.548667 -0.831237 -0.0894973 -0.67911 -0.734012 -0.00602604 -0.650579 -0.735817 -0.187934 -0.783575 -0.613611 -0.0974268 -0.614831 -0.444749 -0.651292 -0.612486 0.0165875 -0.790307 -0.674339 -0.0224688 -0.73808 -0.617584 -0.0773096 -0.782696 -0.764754 -0.142346 -0.628402 -0.633668 -0.280102 -0.721116 -0.813846 -0.100507 -0.572323 -0.787691 -0.0893803 -0.609552 -0.807188 -0.0358044 -0.589207 -0.761218 -0.0213071 -0.648146 -0.72294 -0.126027 -0.67932 -0.751923 -0.115877 -0.648987 -0.735353 -0.162624 -0.657882 -0.664225 -0.12937 -0.736253 -0.715322 -0.0890252 -0.693101 -0.676488 -0.0291404 -0.735877 -0.642266 -0.0176621 -0.766279 -0.719725 -0.583126 -0.376776 -0.549877 -0.698154 -0.458493 -0.684212 -0.550733 -0.478067 -0.732018 -0.505748 -0.456474 -0.69471 -0.557538 -0.454456 -0.613288 -0.706551 -0.353078 -0.592834 -0.725114 -0.350367 -0.867842 -0.129525 -0.47966 -0.868187 -0.129036 -0.479167 -0.763969 -0.395406 -0.509907 -0.864677 -0.272565 -0.42195 -0.639318 -0.6405 -0.42548 -0.772186 -0.531164 -0.348702 -0.510573 -0.797186 -0.322195 -0.642781 -0.721478 -0.25749 -0.453838 -0.859011 -0.236922 -0.462481 -0.861685 -0.208832 -0.526062 -0.831902 -0.176627 -0.473624 -0.811039 -0.34336 -0.636685 -0.723407 -0.267047 -0.749942 -0.532587 -0.39235 -0.553728 -0.673629 -0.489499 -0.78035 -0.365445 -0.507448 -0.612276 -0.51241 -0.602124 -0.717098 -0.346119 -0.604957 -0.740315 -0.35996 -0.567769 -0.760477 -0.319742 -0.56519 -0.778056 -0.330075 -0.534489 -0.843515 -0.159269 -0.512949 -0.777826 -0.222586 -0.587743 -0.836364 -0.0504817 -0.545845 -0.856732 -0.0595215 -0.512315 -0.931389 -0.360542 0.0502358 -0.984966 -0.164114 0.0539316 -0.984504 -0.165083 0.0591627 -0.996989 0.0694348 -0.0345079 -0.990195 -0.0404653 -0.133704 -0.991121 0.027246 -0.130138 -0.986913 0.034271 -0.157572 -0.986926 0.0333121 -0.157694 -0.941609 0.076964 -0.327793 -0.941549 0.0887172 -0.324985 -0.975353 0.0596688 -0.212427 -0.868378 -0.0877441 -0.488079 -0.93601 -0.129687 -0.32721 -0.912065 -0.228597 -0.340412 -0.887031 -0.211562 -0.410388 -0.857333 -0.297123 -0.420354 -0.832283 -0.281647 -0.477472 -0.753187 -0.619121 -0.222258 -0.835553 -0.502736 -0.221602 -0.737851 -0.663605 -0.123304 -0.583022 0.278787 -0.763127 -0.603526 0.198108 -0.77234 -0.70715 0.17553 -0.684929 -0.600596 0.296997 -0.742346 -0.774422 0.266045 -0.574013 -0.638444 0.166017 -0.75155 -0.751187 0.136725 -0.645775 -0.731534 0.0418135 -0.680522 -0.797268 -0.469759 -0.379064 -0.819042 -0.483891 -0.308252 -0.85655 -0.415647 -0.305874 -0.873972 -0.428534 -0.229198 -0.913008 -0.340699 -0.224367 -0.924795 -0.353486 -0.14072 -0.956879 -0.257209 -0.135004 -0.938792 -0.235618 -0.251305 -0.994216 -0.0986292 -0.0425067 -0.990992 -0.0852991 -0.103239 -0.992696 -0.0650121 -0.101627 -0.995096 -0.0963079 -0.0225557 -0.994757 -0.0956048 -0.0363182 -0.996142 0.0834675 -0.0271088 -0.98699 0.125551 -0.10044 -0.879345 -0.475154 0.0313266 -0.920603 -0.389016 0.0340166 -0.919034 -0.390248 0.0555274 -0.98485 -0.162812 0.0596959 -0.984413 -0.163682 0.0643385 -0.734595 -0.677742 0.0321912 -0.734889 -0.676916 0.0415017 -0.667667 -0.744012 0.0258267 -0.666539 -0.745365 0.0125002 -0.674136 -0.738384 0.0181632 -0.984658 -0.162048 0.0647204 -0.905803 -0.419425 0.0600337 -0.906791 -0.418943 0.0470862 -0.824784 -0.563886 0.04201 -0.824679 -0.565099 -0.02383 -0.984486 -0.166237 0.0561529 -0.984053 -0.156257 0.0849916 -0.963867 -0.261589 -0.0503134 -0.962908 -0.269719 0.00772758 -0.91331 -0.407251 0.00341612 -0.879039 -0.470785 -0.0751767 -0.866341 -0.493645 -0.0759556 -0.868037 -0.496034 -0.021484 -0.750025 -0.649825 -0.123248 -0.758138 -0.650254 -0.0489453 -0.746346 -0.663729 -0.049303 -0.613781 -0.777425 -0.137417 -0.744009 -0.614456 -0.262478 -0.802423 -0.535626 -0.263101 -0.768899 -0.51466 -0.379368 -0.779548 -0.328398 -0.533348 -0.805246 -0.343854 -0.483056 -0.431268 -0.902217 -0.00343788 -0.504895 -0.861078 -0.0602198 -0.52336 -0.846635 -0.0964537 -0.323561 -0.945552 0.0352115 -0.316494 -0.948408 0.0188099 -0.335289 -0.941905 0.0199192 -0.343042 -0.937958 0.0505713 -0.324527 -0.944842 0.0442236 -0.314063 -0.949377 0.00688007 -0.38631 -0.922309 0.0105032 -0.384877 -0.922955 0.00478755 -0.575077 -0.817983 0.0137715 -0.573394 -0.819276 0.00225403 -0.639878 -0.768007 0.0268532 -0.744184 -0.0448854 -0.666465 -0.588771 0.0125667 -0.808202 -0.70206 0.149663 -0.696213 -0.538106 0.185524 -0.822206 -0.569985 0.235513 -0.787179 -0.983656 -0.166461 0.0686493 -0.896663 -0.438109 0.0636895 -0.897371 -0.43789 0.0545676 -0.767856 -0.638929 0.0465436 -0.767355 -0.641038 0.0153997 -0.638056 -0.769937 0.00904386 -0.715236 -0.698704 -0.0158232 -0.538486 -0.842361 -0.0214648 -0.60957 -0.776966 -0.157317 -0.651483 -0.741826 -0.158948 -0.584411 -0.711314 -0.390508 -0.819269 -0.405997 -0.404926 -0.759483 -0.368741 -0.535925 -0.743854 -0.223952 -0.629704 -0.775951 -0.137613 -0.615599 -0.794338 -0.146593 -0.589523 -0.817431 -0.0655126 -0.572289 -0.838128 -0.0753349 -0.540247 -0.85738 0.0270581 -0.513972 -0.749424 0.0691703 -0.658468 -0.891756 0.195892 -0.40792 -0.730715 0.248672 -0.635781 -0.804403 0.29546 -0.515401 -0.958754 -0.0264101 -0.283009 -0.954502 -0.0411922 -0.295347 -0.938155 -0.143851 -0.314916 -0.935352 -0.149236 -0.320694 -0.867439 -0.32936 -0.372922 -0.951755 -0.152896 -0.266056 -0.747643 -0.596692 -0.291527 -0.861483 -0.466268 -0.201101 -0.560128 -0.805413 -0.193823 -0.69007 -0.714231 -0.116954 -0.429374 -0.89646 -0.109539 -0.534429 -0.843779 -0.049223 -0.354347 -0.933794 -0.049659 -0.426094 -0.904653 -0.00679869 -0.306428 -0.951832 -0.0108643 -0.319626 -0.94754 0.00275634 -0.319111 -0.947713 0.00273288 -0.299742 -0.951963 -0.0626202 -0.333724 -0.942239 -0.0285212 -0.367278 -0.923609 -0.109789 -0.381519 -0.922443 -0.0595173 -0.427123 -0.888379 -0.168371 -0.447445 -0.88932 -0.0943513 -0.513873 -0.819401 -0.254001 -0.520966 -0.821922 -0.230301 -0.662391 -0.641864 -0.386327 -0.596801 -0.598588 -0.534342 -0.801878 -0.266141 -0.53494 -0.686282 -0.204462 -0.698006 -0.684021 0.00794044 -0.729419 -0.597594 0.0369278 -0.800948 -0.594451 0.0791013 -0.800232 -0.522037 0.0985882 -0.847206 -0.522185 0.0824054 -0.848841 0.891239 0.177586 -0.417321 0.730018 0.0576553 -0.680991 0.976939 -0.0320514 -0.211098 0.975998 0.0143309 -0.217306 0.975451 0.0148577 -0.219716 0.976944 0.00885052 -0.213313 0.973866 -0.102362 -0.202751 0.969834 -0.151483 -0.190982 0.974303 -0.104165 -0.19971 0.937194 -0.291294 -0.191876 0.921057 -0.33297 -0.201952 0.82183 -0.530648 -0.207384 0.831033 -0.51522 -0.2096 0.933388 -0.159377 -0.321537 0.819653 -0.534569 -0.205923 0.829912 -0.510129 -0.225864 0.823273 -0.518439 -0.231175 0.884924 -0.394895 -0.246916 0.854127 -0.444219 -0.270436 0.931326 -0.229523 -0.282757 0.933429 -0.228882 -0.276267 0.85657 -0.0499914 -0.513604 0.823481 0.0046853 -0.567325 0.762955 0.209041 -0.61172 0.759613 0.189415 -0.622182 0.738773 0.146965 -0.657736 0.768196 0.103923 -0.631724 0.724399 0.0536347 -0.687292 0.757427 0.245477 -0.605017 0.810613 0.143549 -0.567715 0.814052 0.227735 -0.534281 0.944034 0.110989 -0.310614 0.94488 0.102665 -0.310905 0.922312 0.0272274 -0.385487 0.894746 0.188921 -0.404646 0.896661 0.177984 -0.405365 0.94668 0.0602004 -0.316501 0.971518 0.056318 -0.230178 0.972503 -0.0316087 -0.230735 0.97466 -0.0819923 -0.208125 0.977477 0.00855023 -0.210867 0.977012 0.00518321 -0.21312 0.969286 -0.0311125 -0.243962 0.961344 0.0722858 -0.265693 0.961812 0.0668438 -0.265422 0.765254 0.0567129 -0.641226 0.774032 0.00731854 -0.633105 0.771712 0.147253 -0.61869 0.820323 -0.00965013 -0.571819 0.816968 0.143449 -0.558557 0.892395 -0.361622 -0.269927 0.841802 -0.446215 -0.303745 0.831797 -0.0481414 -0.552988 0.818466 -0.160698 -0.551625 0.872269 -0.0131151 -0.488851 0.86753 -0.0858273 -0.489924 0.875224 -0.0864612 -0.475927 0.880159 0.0504651 -0.471989 0.832221 0.0531091 -0.551894 0.911433 -0.158067 -0.379874 0.845062 -0.395729 -0.35954 0.901898 -0.291492 -0.318768 0.80813 -0.512315 -0.290618 0.866948 -0.444063 -0.226294 0.822571 -0.526283 -0.215413 0.87519 -0.439156 -0.20294 0.865611 -0.46288 -0.190943 0.892482 -0.405076 -0.198467 0.974167 -0.108555 -0.198028 0.974528 -0.102396 -0.199524 0.937236 -0.291287 -0.19168 0.950718 -0.227187 -0.211 0.877225 -0.438691 -0.195006 0.913595 -0.286136 -0.288914 0.901591 -0.336101 -0.272341 0.911773 -0.266805 -0.312227 0.881298 -0.362042 -0.303709 0.941566 0.120279 -0.31462 0.941609 0.119642 -0.314734 0.970345 0.107134 -0.216688 0.957168 -0.0921706 -0.274471 0.963302 -0.0925996 -0.251943 0.967424 0.0220787 -0.252196 0.923759 -0.171945 -0.342206 0.926098 0.173107 -0.335227 0.887904 -0.0747334 -0.453918 0.871914 0.201231 -0.446399 0.874217 0.186752 -0.448183 0.974766 -0.0820004 -0.207621 0.960802 -0.187012 -0.204658 0.948147 -0.227353 -0.222099 0.959002 -0.173008 -0.224463 0.918589 -0.286024 -0.272737 0.956259 -0.0801657 -0.281323 0.893439 -0.266196 -0.361811 0.910922 -0.189178 -0.366652 0.896769 -0.188211 -0.400477 0.874729 -0.282239 -0.393941 0.869558 -0.281863 -0.405489 0.895103 -0.167922 -0.41303 0.840231 -0.287352 -0.459826 0.877076 -0.0970441 -0.470447 0.900835 -0.0310484 -0.433051 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -9.83782e-10 -1 6.21525e-10 8.5461e-10 -1 -1.30908e-10 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.984773 -0.00399094 0.173802 -0.97623 -0.0119902 0.216407 -0.956946 -0.0193096 0.289625 -0.971808 -0.0367727 0.232887 -0.948735 -0.116682 0.293747 -0.974369 -0.0158589 0.224397 -0.977495 0 0.210961 -0.97752 5.30695e-05 0.210844 -0.977319 0.000166419 0.211773 -0.977655 0 0.210217 -0.97461 -0.0588714 0.21603 -0.978366 -0.115137 0.171882 -0.949449 -0.0994881 0.29774 -0.986045 -0.0737953 0.149231 -0.966579 -0.070449 0.2465 -0.979675 -0.0901837 0.179175 -0.955644 -0.105324 0.275049 -0.950164 -0.106675 0.29293 -0.949374 -0.0987187 0.298235 -0.94964 -0.105022 0.295219 -0.949638 -0.132509 0.283952 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 2.37631e-05 -1 4.40361e-05 5.62586e-06 -1 9.97287e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -8.67246e-06 -1 -2.59236e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1.9897e-05 -1 -8.58714e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -2.98027e-06 -1 9.93997e-07 5.5625e-06 -1 -1.20004e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 9.66769e-05 -1 -0.000180077 9.78582e-06 -1 -1.28857e-05 -1.10067e-05 -1 1.44934e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.06988e-06 -1 3.0463e-07 6.46484e-07 -1 -8.887e-07 1.80967e-06 -1 -1.62196e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -3.34602e-05 -1 0.000112341 0.000111896 -1 -0.000359749 0.000151148 -1 -0.000481781 0 -1 0 0 -1 0 0 -1 0 0 -1 0 9.35703e-07 -1 -9.4829e-08 -5.24334e-06 -1 -3.90642e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -4.43861e-06 -1 4.4851e-07 3.2339e-06 -1 -3.07967e-06 8.48321e-06 -1 -5.17754e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.26577e-06 -1 3.2769e-08 6.57078e-07 -1 1.50313e-06 1.47809e-05 -1 9.79928e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 6.66068e-06 -1 -6.81737e-07 -5.28446e-07 -1 -2.75956e-08 -1.207e-06 -1 1.26147e-07 3.2703e-07 -1 -6.1589e-07 6.2355e-07 -1 -8.08747e-07 1.86475e-06 -1 -1.50209e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -2.98213e-07 -1 1.15176e-07 -2.50211e-08 -1 -2.93234e-07 9.50252e-08 -1 -4.29004e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.69739e-05 -1 4.73228e-06 -0.977353 -0.0597027 0.203017 -0.976311 -0.0408528 0.212479 -0.97635 -0.042088 0.212058 -0.974507 -0.0668091 0.21418 -0.968864 -0.109275 0.222173 -0.972984 -0.0897977 0.212694 -0.973044 -0.0902391 0.212233 -0.96108 -0.0904129 0.261058 -0.976203 -0.0420891 0.212735 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.000190077 1 0.000118973 0.00116216 0.999999 -0.000873821 1.02886e-05 1 -8.08235e-06 0 1 0 0 1 0 0 1 0 -2.03062e-05 1 9.69994e-06 5.76586e-06 1 -5.12637e-06 0 1 0 0.000428217 1 -0.000104493 -0.000492965 1 0.000117791 0.000193057 1 -5.02704e-05 -0.000324738 1 0.000131445 0 1 0 0 1 0 0 1 0 0 1 0 -8.59543e-05 1 -4.65462e-05 2.91307e-05 1 -2.91317e-05 0.000250038 1 9.93236e-05 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.00343855 0.999994 0.000153549 0.00112252 0.999999 -9.60688e-05 -0.000571935 1 4.53458e-05 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 2.12609e-05 1 -3.08943e-06 -3.43129e-07 1 1.59266e-06 0.000144584 1 -3.28549e-05 -3.19881e-06 1 -2.74056e-06 0.00214794 0.999995 -0.00211342 -0.00348934 0.999987 0.00369835 -0.00077704 0.999999 0.000823584 0.0222442 0.99974 -0.00507463 0.00647516 0.999978 -0.00145861 -0.00214715 0.999997 0.000638446 -0.0304196 0.999441 -0.0138783 -6.65537e-05 1 6.65547e-05 -1.48502e-05 1 7.40007e-05 0 1 0 0 1 0 0 1 0 -0.00140852 0.999998 0.00112733 0.000693473 1 -0.000716242 0.000603454 1 0.000275314 -0.000136793 1 -4.10974e-05 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.00257666 0.999997 0.000120371 -0.00413737 0.999991 0.000209968 0 1 0 0 1 0 -0.00186056 0.999998 0.00113904 0.00258212 0.999995 -0.00172636 0.00805658 0.999953 -0.0053865 9.38803e-05 1 2.51539e-05 0.000167595 1 -5.97281e-06 9.77623e-05 1 -2.61968e-05 0.00587281 0.999979 0.00267608 -0.00946905 0.999946 -0.00432331 0.000309119 1 -0.000309126 0.00457157 0.999983 0.0036741 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.00114401 0.999999 -0.000552542 -0.000657907 1 0.000422113 0 1 0 0.000624174 0.999999 -0.000802735 -0.000847835 1 4.78349e-05 -0.000292087 1 -3.26411e-05 0.0031792 0.999995 -0.00057421 0 1 0 -0.000612758 1 0.000655618 0.000626325 0.999999 -0.000805407 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.58859e-05 1 6.05108e-07 -7.36138e-06 1 -1.35323e-06 -1.43015e-05 1 0.000611798 3.34435e-05 1 8.96067e-06 1.98653e-05 1 -2.70782e-05 -0.00290757 0.999988 0.00385023 5.89625e-07 1 -1.58e-07 0.000803329 1 -6.56856e-05 -0.00183393 0.999998 0.000130264 -3.60395e-07 1 -4.60913e-07 -6.36317e-07 1 -1.70492e-07 -5.17639e-07 1 -5.17627e-07 -0.00195632 0.999998 0.00020896 -0.0041319 0.999989 -0.00208982 9.56864e-05 1 4.13838e-05 3.71053e-07 1 -3.71053e-07 6.12074e-06 1 5.24688e-06 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.00208065 0.999998 0.000194758 0.0007215 1 0.000117765 -0.0056056 0.999984 0.000415074 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -5.05992e-07 1 6.94961e-07 0.00250916 0.999996 0.00102878 0.00416792 0.99999 0.00160218 0.937988 -0.289451 -0.190777 0.942463 -0.287175 -0.171154 0.939803 -0.302474 -0.158998 0.9314 -0.339376 -0.131594 0.919217 -0.366095 -0.144962 0.934794 -0.333857 -0.121245 0.952177 -0.2972 -0.0709354 0.923256 -0.383848 0.0161114 0.861173 -0.504526 0.0619229 0.839563 -0.538208 0.0739352 0.818107 -0.568894 0.0840299 0.791915 -0.603295 0.0943711 1.26044e-05 0 1 1.27995e-05 -6.6687e-07 1 1.29945e-05 0 1 -0.960578 -0.172268 0.218204 -0.965251 -0.146504 0.216395 -0.973469 -0.0774297 0.215322 -0.973245 -0.0824981 0.214448 -0.976524 -0.0234285 0.21413 -0.926912 -0.30187 0.222953 -0.952022 -0.219877 0.212856 -0.958239 -0.175443 0.225828 -0.974486 -0.0684892 0.213741 -0.970627 -0.0979602 0.219742 -0.96941 -0.122584 0.212646 -0.96941 -0.122568 0.212655 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.983654 -0.174266 -0.0453469 0.985124 -0.165321 -0.0469018 0.995195 -0.0796501 -0.0569517 0.996578 -0.0616209 -0.0550987 0.984825 -0.173545 -0.00156955 0.965577 -0.151538 0.211417 0.241328 -0.00873206 0.970404 0.223041 -0.0133824 0.974717 0.592968 -0.036881 0.804381 0.585002 -0.0393512 0.810077 0.86262 -0.0545548 0.502903 0.853414 -0.0592997 0.51785 0.987697 -0.0602745 0.1443 0.986174 -0.0630843 0.153238 0.975905 -0.190769 0.105906 0.852195 -0.141857 0.503628 0.835307 -0.147803 0.529544 0.585449 -0.0981734 0.804743 0.607472 -0.0931563 0.78886 0.23857 -0.0395937 0.970318 0.309939 -0.0272945 0.950364 0.0464804 -0.0208778 0.998701 -0.106201 -0.00887129 0.994305 0.0677035 -0.00882823 0.997666 -0.681642 -0.0874041 0.726447 -0.742497 -0.0763683 0.665482 -0.58663 -0.0745026 0.806421 -0.345752 -0.0574008 0.936568 -0.446345 -0.0474164 0.893604 -0.268237 -0.0456931 0.962269 -0.910448 -0.0937942 0.402848 -0.867873 -0.078097 0.490609 -0.910241 -0.167521 0.378679 -0.335128 -0.00591703 -0.942154 -0.368307 0 -0.929704 -0.675776 0 -0.737107 -0.675776 0 -0.737107 -0.942133 0 -0.335239 -0.942133 0 -0.335239 -0.989497 0 0.144555 -0.989497 0 0.144555 -0.806858 0 0.590746 -0.806858 0 0.590746 -0.43667 0 0.899622 -0.43667 0 0.899622 -0.0515969 0 0.998668 -0.0801318 -0.0061595 0.996765 0.127762 0 -0.991805 -0.173634 0.00436624 0.984801 -0.175699 0.00777952 0.984413 -0.0581298 -0.00882553 0.99827 -0.893526 0.0150531 0.44876 -0.886854 -0.00550573 0.462017 -0.834993 0.00640867 0.550224 -0.83547 0.00502784 0.549513 -0.803972 0 0.594667 -0.766036 0 0.642798 -0.772543 0.0176674 0.634717 -0.686084 -0.020811 0.727225 -0.693741 0 0.720224 -0.597148 0 0.802131 -0.616635 0.0429533 0.786076 -0.499043 -0.0614964 0.864393 -0.52169 0 0.853135 -0.396068 0 0.918221 -0.386594 -0.0174233 0.922085 -0.286761 0.0143626 0.957894 -0.276974 0 0.960877 -0.227989 0 0.973664 -0.999727 0.0233698 1.28179e-05 -0.99845 -0.0275975 0.0483397 -0.992938 0.0245263 0.116071 -0.989856 0 0.142074 -0.973042 0 0.230629 -0.968421 -0.0298253 0.247529 -0.939484 0.0208555 0.341958 -0.933552 0 0.358443 -0.913853 0 0.406046 -0.968533 0.0327197 -0.246725 -0.97303 0.00611182 -0.230599 -0.959088 0 -0.283108 -0.981463 -0.00136145 -0.191648 -0.987478 0.00091624 -0.157753 -0.993079 0.0179697 -0.116061 -0.994752 0 -0.102319 -0.999353 0 -0.0359701 -0.875215 0 -0.483734 -0.887018 0.0137498 -0.461531 -0.893374 0.0243171 -0.448655 -0.902112 0.0056698 -0.431465 -0.92674 -0.00479946 -0.375674 -0.93941 0.0247351 -0.341903 -0.945914 0.00814929 -0.324315 -0.955313 0 -0.295598 -0.761042 0.0302795 -0.647996 -0.765865 0.0221291 -0.642621 -0.740682 0 -0.671855 -0.79084 -0.00640889 -0.611989 -0.817979 0.00451454 -0.57523 -0.835298 0.0217268 -0.549368 -0.837301 0.0176631 -0.546456 -0.858254 0 -0.513225 -0.642343 -0.008445 -0.766371 -0.676709 0.0139536 -0.736118 -0.68604 0.0247631 -0.727142 -0.703722 0.00366364 -0.710466 -0.724484 0 -0.689292 -0.396053 0.0140311 -0.918121 -0.464776 -0.00811523 -0.885391 -0.499858 0.0247272 -0.865754 -0.523967 0 -0.851738 -0.597169 0 -0.802115 -0.579337 0.0367145 -0.814261 -0.612534 0.0109072 -0.790369 -0.286736 0.0236099 -0.957719 -0.308569 0 -0.951202 -0.386951 0 -0.9221 0.0581321 0 -0.998309 0.0581351 5.12966e-06 -0.998309 -0.0581577 5.12962e-06 -0.998307 -0.0581608 0 -0.998307 -0.173661 0 -0.984806 -0.154808 0.0323952 -0.987413 -0.234263 -0.0127002 -0.97209 0.322248 0 -0.946655 0.22154 0.0328219 -0.974599 0.172706 -0.103301 -0.979541 0.286717 0.0228343 -0.957743 0.400203 0 -0.916427 0.396054 -0.00827049 -0.91819 0.503872 0.0076758 -0.863745 0.499988 0 -0.866032 0.574284 0 -0.818656 0.596966 0.0247496 -0.801885 0.631479 -0.0112408 -0.775311 0.686124 0.0177547 -0.727268 0.694081 0.00359225 -0.719887 0.835311 0.0201461 -0.549408 0.823475 -0.00604466 -0.567321 0.766465 0.00761941 -0.642241 0.766007 0.00869851 -0.642773 0.731235 0 -0.682126 0.725443 0 -0.688283 0.939688 0 -0.342032 0.945062 0.0294973 -0.325558 0.892973 -0.0382582 -0.448482 0.901269 0 -0.43326 0.857642 0 -0.514247 0.765978 0.0139471 0.642715 0.796204 0 0.605029 0.835495 0 0.549498 0.827997 0.0223694 0.560287 0.893303 -0.0274112 0.448619 0.887666 0 0.460489 0.939697 0 0.342008 0.934083 0.0258558 0.356119 0.972531 -0.0325843 0.230481 0.969434 0 0.245352 0.99324 0 0.11608 0.991523 0.0209107 0.12824 0.99968 -0.0253156 -1.28173e-05 0.999925 0 0.012267 0.993237 0 -0.116106 0.993897 0.0108387 -0.109776 0.972972 -0.0120213 -0.230611 0.975153 0.00575407 -0.221459 0.958882 0 -0.283804 -0.0750306 0.0224205 0.996929 -0.0122661 4.11036e-05 0.999925 0.0581577 4.10368e-05 0.998307 0.0387828 0.0330245 0.998702 0.173492 -0.0440293 0.983851 0.154512 0 0.987991 0.286816 0 0.957986 0.304036 -0.0309459 0.952158 0.396002 0.0212881 0.918003 0.412717 0 0.910859 0.500011 0 0.866019 0.504986 -0.00984947 0.863071 0.597146 0.00887105 0.802084 0.601798 0 0.798649 0.686251 0 0.727365 0.682467 0.00877813 0.730864 0.756297 -0.00729066 0.654188 -0.711476 0 -0.702711 -0.740242 -0.0521127 -0.670318 -0.796567 0 -0.604551 -0.845905 0 -0.533333 -0.905145 -0.0779157 -0.417901 -0.888895 0 -0.458112 -0.966594 0 -0.256313 -0.975463 -0.0521129 -0.213909 -0.991664 0 -0.128847 -0.999027 0 0.0441108 -0.99315 -0.0779157 0.0870812 -0.999095 0 -0.0425283 0.877605 0 -0.479384 0.877605 0 -0.479384 0.998175 0 -0.0603951 0.998175 0 -0.0603951 0.929002 0 0.370075 0.929002 0 0.370075 -0.195078 0 0.980788 -0.195078 0 0.980788 -0.55556 0 0.831477 -0.55556 0 0.831477 -0.831462 0 0.555581 -0.831462 0 0.555581 -0.980783 0 0.195103 -0.980783 0 0.195103 -0.980788 0 -0.195078 -0.980788 0 -0.195078 -0.831477 0 -0.55556 -0.831477 0 -0.55556 -0.555581 0 -0.831463 -0.555581 0 -0.831463 -0.195103 0 -0.980783 -0.195103 0 -0.980783 0.195078 0 -0.980788 0.195078 0 -0.980788 0.55556 0 -0.831477 0.55556 0 -0.831477 0.831462 0 -0.555581 0.831462 0 -0.555581 0.980783 0 -0.195103 0.980783 0 -0.195103 0.980788 0 0.195078 0.980788 0 0.195078 0.831477 0 0.55556 0.831477 0 0.55556 0.555581 0 0.831463 0.555581 0 0.831463 0.195103 0 0.980783 0.195103 0 0.980783 -0.402198 -0.00999502 -0.915498 0.0178856 -0.012203 0.999766 -0.390733 -0.0171465 -0.920344 -0.400499 -0.0147349 -0.916179 -0.739548 0.0224795 -0.672728 -0.694647 0 -0.719351 -0.873076 0 -0.487584 -0.957181 0.0114728 -0.289264 -0.97093 -0.00382546 -0.239331 -0.976772 0.00427602 0.214237 -0.976772 0.00427581 0.214237 -0.781637 -0.00382535 0.623721 -0.74825 0.0114734 0.663317 0.0329462 -0.0158985 0.999331 -0.329766 0.0168474 0.943912 -0.390203 0 0.920729 -0.588854 0 0.80824 -0.408034 -0.0158022 -0.91283 0.0178276 -0.0154142 0.999722 -0.403025 -0.0187379 -0.914997 -0.452764 -0.0101391 -0.891573 -0.743192 0.0223752 -0.668704 -0.698652 0 -0.715462 -0.875443 0 -0.483321 -0.958439 0.0114196 -0.28507 -0.971941 -0.00380791 -0.235193 -0.976086 0.00425622 0.217342 -0.976086 0.00425608 0.217341 -0.780321 -0.00380748 0.625367 -0.746934 0.011419 0.6648 -0.587676 0 0.809096 -0.389347 0 0.921091 -0.329031 0.0167689 0.94417 0.0159494 -0.0143404 0.99977 -0.0314091 -0.0315039 0.99901 0.947073 0.000850049 -0.321017 0.976747 0.00992774 -0.214164 0.885791 0.0338235 0.462851 0.945909 0.0123883 0.324197 0.994497 -0.000912855 0.104763 0.994393 0.00123815 -0.105738 0.961653 -0.000212424 0.27427 0.71686 0.000214964 0.697217 0.753694 0.00927977 0.65716 0.374756 -0.00819828 0.927087 0.422178 0 0.906513 -0.0106779 0 -0.999943 -0.0475329 -0.0053299 -0.998855 0.359364 0.00545447 -0.933182 0.894037 -8.25277e-05 -0.447994 0.84655 0.000690471 -0.53231 0.758639 0.00907003 -0.651448 0.701972 0.000355079 -0.712205 0.396426 -0.000464325 -0.918067 0.976722 0.0122152 -0.214159 0.943244 0.016721 0.331681 0.993707 -0.00122238 0.112002 0.995057 0.0014514 -0.0992968 0.886346 0.0421271 0.461103 0.961653 -0.000292285 0.274269 0.835675 7.15689e-05 0.549225 0.71683 0.00923281 0.697187 0.717863 0.00948057 0.69612 0.374765 0 0.92712 0.262178 0.022782 0.964751 0.434982 -0.00746668 0.900408 -0.0181665 0 -0.999835 -0.047533 -0.00519218 -0.998856 0.35936 0.00570584 -0.933181 0.943839 -0.000647964 -0.330406 0.852578 0.00039942 -0.5226 0.758625 0.0108741 -0.651436 0.706581 0.000609184 -0.707632 0.390426 -0.000797605 -0.920634 0.976687 0.0148498 -0.214153 0.961652 -0.00114658 0.274269 0.899585 0.0448359 0.434439 0.952723 0.0174301 0.303339 0.993925 -0.00146176 0.110051 0.992654 0.00210557 -0.120969 0.374773 0 0.927117 0.370125 0.0015876 0.928981 0.599949 -0.000936837 0.800038 0.716746 0.0175846 0.697113 0.744481 0.010389 0.667563 0.82819 0.000304909 0.560447 -0.14248 0 -0.989798 -0.0475209 0.0111435 -0.998808 0.359327 0.0147555 -0.933095 0.343747 0.0115066 -0.938992 0.0682707 -0.00657662 -0.997645 0.937563 -0.00029701 -0.347816 0.83762 0.000303446 -0.546253 0.75858 0.0154898 -0.651396 0.700964 0.00386984 -0.713186 0.534738 -0.00219268 -0.845015 0.912199 -4.47636e-05 -0.409748 0.976766 0.0077728 -0.21417 0.942754 0.0305475 -0.332086 0.888863 0.0455185 0.455906 0.922854 0.0302757 0.383958 0.984023 -0.00230935 0.178027 0.988498 0.00236253 -0.151218 0.961653 -0.00035447 0.27427 0.71686 0.00035677 0.697217 0.764345 0.0168483 0.644587 0.374727 -0.0155961 0.927004 0.434399 0 0.90072 -0.131939 0 -0.991258 -0.0475416 0.00902249 -0.998829 0.0380283 -0.000226196 -0.999277 0.204081 0.000221356 -0.978954 0.359326 0.0149024 -0.933093 0.383557 0.0101896 -0.923461 0.836081 0.000127067 -0.548606 0.747765 0.0161894 -0.663766 0.758598 0.0137931 -0.651413 0.648428 -0.000276765 -0.761276 0.521993 0.000189101 -0.85295 0.965922 0 -0.258832 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707099 0 0.707115 -0.707099 0 0.707115 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258831 0 0.965923 0.258831 0 0.965923 0.707116 0 0.707098 0.707116 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258832 0.965923 0 -0.258832 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.25883 0 -0.965923 -0.25883 0 -0.965923 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965923 0 0.258832 -0.965923 0 0.258832 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.258832 0.965923 0 -0.258832 0.707098 0 -0.707116 0.707098 0 -0.707116 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258831 0 -0.965923 -0.258831 0 -0.965923 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707099 0 0.707115 -0.707099 0 0.707115 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258832 0 0.965923 0.258832 0 0.965923 0.707116 0 0.707098 0.707116 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.258832 0.965923 0 -0.25883 0.707097 0 -0.707116 0.707097 0 -0.707116 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707115 0 -0.707099 -0.707115 0 -0.707099 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965923 0.258832 0 0.965923 0.707116 0 0.707097 0.707116 0 0.707097 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.25883 0.965929 0 0.258806 0.965929 0 0.258806 0.707114 0 0.7071 0.707114 0 0.7071 0.258836 0 0.965921 0.258836 0 0.965921 -0.258805 0 0.96593 -0.258805 0 0.96593 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707114 0 -0.7071 -0.707114 0 -0.7071 -0.258836 0 -0.965921 -0.258836 0 -0.965921 0.258812 0 -0.965928 0.258812 0 -0.965928 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965929 0 0.258806 0.965929 0 0.258806 0.707115 0 0.707099 0.707115 0 0.707099 0.258835 0 0.965921 0.258835 0 0.965921 -0.258813 0 0.965928 -0.258813 0 0.965928 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965922 0 0.258833 -0.965922 0 0.258833 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707118 0 -0.707095 -0.707118 0 -0.707095 -0.258828 0 -0.965923 -0.258828 0 -0.965923 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.258831 0.965923 0 -0.258831 0.965929 0 0.258807 0.965929 0 0.258807 0.707118 0 0.707096 0.707118 0 0.707096 0.258828 0 0.965923 0.258828 0 0.965923 -0.258805 0 0.96593 -0.258805 0 0.96593 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707114 0 -0.7071 -0.707114 0 -0.7071 -0.258829 0 -0.965923 -0.258829 0 -0.965923 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.25883 0.965923 0 -0.25883 0.965929 0 0.258807 0.965929 0 0.258807 0.707115 0 0.707098 0.707115 0 0.707098 0.258832 0 0.965922 0.258832 0 0.965922 -0.258805 0 0.96593 -0.258805 0 0.96593 -0.707099 0 0.707115 -0.707099 0 0.707115 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707099 0 -0.707115 0.707099 0 -0.707115 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965928 0 0.25881 0.965928 0 0.25881 0.707121 0 0.707092 0.707121 0 0.707092 0.258822 0 0.965925 0.258822 0 0.965925 -0.258805 0 0.96593 -0.258805 0 0.96593 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.96593 0 -0.258804 -0.96593 0 -0.258804 -0.707114 0 -0.7071 -0.707114 0 -0.7071 -0.258835 0 -0.965921 -0.258835 0 -0.965921 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.258829 0.965923 0 -0.258829 0.965929 0 0.258806 0.965929 0 0.258806 0.707114 0 0.7071 0.707114 0 0.7071 0.258836 0 0.965921 0.258836 0 0.965921 -0.258805 0 0.96593 -0.258805 0 0.96593 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965923 0 0.258829 -0.965923 0 0.258829 -0.965928 0 -0.25881 -0.965928 0 -0.25881 -0.707122 0 -0.707092 -0.707122 0 -0.707092 -0.258821 0 -0.965925 -0.258821 0 -0.965925 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965922 0 -0.258833 0.965922 0 -0.258833 0.965929 0 0.258808 0.965929 0 0.258808 0.707118 0 0.707095 0.707118 0 0.707095 0.258828 0 0.965923 0.258828 0 0.965923 -0.258805 0 0.96593 -0.258805 0 0.96593 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.707118 0 -0.707095 -0.707118 0 -0.707095 -0.258828 0 -0.965923 -0.258828 0 -0.965923 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.258831 0.965923 0 -0.258831 0.965929 0 0.258807 0.965929 0 0.258807 0.707116 0 0.707097 0.707116 0 0.707097 0.258832 0 0.965922 0.258832 0 0.965922 -0.258809 0 0.965929 -0.258809 0 0.965929 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.258831 0.965923 0 -0.258831 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707101 0 0.707112 -0.707101 0 0.707112 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258837 0 0.965921 0.258837 0 0.965921 0.707116 0 0.707098 0.707116 0 0.707098 0.965929 0 0.258806 0.965929 0 0.258806 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707096 0 -0.707118 0.707096 0 -0.707118 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258827 0 -0.965924 -0.258827 0 -0.965924 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.965922 0 0.258833 -0.965922 0 0.258833 -0.707101 0 0.707112 -0.707101 0 0.707112 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258827 0 0.965924 0.258827 0 0.965924 0.707121 0 0.707093 0.707121 0 0.707093 0.965929 0 0.258807 0.965929 0 0.258807 0.965924 0 -0.258828 0.965924 0 -0.258828 0.707094 0 -0.707119 0.707094 0 -0.707119 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258827 0 -0.965924 -0.258827 0 -0.965924 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258833 -0.965922 0 0.258833 -0.707101 0 0.707112 -0.707101 0 0.707112 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258837 0 0.965921 0.258837 0 0.965921 0.707116 0 0.707098 0.707116 0 0.707098 0.965928 0 0.25881 0.965928 0 0.25881 0.965923 0 -0.25883 0.965923 0 -0.25883 0.707096 0 -0.707117 0.707096 0 -0.707117 0.258804 0 -0.96593 0.258804 0 -0.96593 -0.258827 0 -0.965924 -0.258827 0 -0.965924 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258833 -0.965922 0 0.258833 -0.707096 0 0.707118 -0.707096 0 0.707118 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258827 0 0.965924 0.258827 0 0.965924 0.707115 0 0.707098 0.707115 0 0.707098 0.96593 0 0.258804 0.96593 0 0.258804 0.965923 0 -0.25883 0.965923 0 -0.25883 0.7071 0 -0.707114 0.7071 0 -0.707114 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258837 0 -0.965921 -0.258837 0 -0.965921 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.258805 0 0.96593 -0.258805 0 0.96593 0.258827 0 0.965924 0.258827 0 0.965924 0.707119 0 0.707094 0.707119 0 0.707094 0.965929 0 0.258808 0.965929 0 0.258808 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707096 0 -0.707118 0.707096 0 -0.707118 0.25881 0 -0.965928 0.25881 0 -0.965928 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.96593 0 -0.258804 -0.96593 0 -0.258804 -0.965922 0 0.258833 -0.965922 0 0.258833 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.25881 0 0.965928 -0.25881 0 0.965928 0.258833 0 0.965922 0.258833 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258833 0.965922 0 -0.258833 0.707098 0 -0.707115 0.707098 0 -0.707115 0.25881 0 -0.965928 0.25881 0 -0.965928 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.965922 0 0.258834 -0.965922 0 0.258834 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.258795 0 0.965932 -0.258795 0 0.965932 0.258837 0 0.965921 0.258837 0 0.965921 0.707116 0 0.707098 0.707116 0 0.707098 0.965928 0 0.258812 0.965928 0 0.258812 0.965923 0 -0.258829 0.965923 0 -0.258829 0.707096 0 -0.707118 0.707096 0 -0.707118 0.258815 0 -0.965927 0.258815 0 -0.965927 -0.258837 0 -0.965921 -0.258837 0 -0.965921 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.965923 0 0.25883 -0.965923 0 0.25883 -0.707096 0 0.707118 -0.707096 0 0.707118 -0.258815 0 0.965927 -0.258815 0 0.965927 0.258838 0 0.965921 0.258838 0 0.965921 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965921 0 -0.258836 0.965921 0 -0.258836 0.707107 0 -0.707107 0.707107 0 -0.707107 0.258795 0 -0.965932 0.258795 0 -0.965932 -0.258817 0 -0.965926 -0.258817 0 -0.965926 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 0.3735 -0.849119 0.37349 0.510205 -0.849119 0.136702 -0.373489 -0.84912 0.3735 -0.136702 -0.84912 0.510204 0.136715 -0.84912 0.510201 -0.373499 -0.84912 -0.373489 -0.510204 -0.84912 -0.136702 -0.510201 -0.84912 0.136715 0.37349 -0.849119 -0.373499 0.136702 -0.849119 -0.510205 -0.136715 -0.84912 -0.510201 0.510201 -0.849119 -0.136715 0.965929 0 0.258807 0.965929 0 0.258807 0.707116 0 0.707097 0.707116 0 0.707097 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707097 0 0.707117 -0.707097 0 0.707117 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965923 0 -0.258831 0.965923 0 -0.258831 0.3735 -0.84912 0.373489 0.510204 -0.84912 0.136702 -0.373489 -0.84912 0.373499 -0.136702 -0.84912 0.510204 0.136715 -0.84912 0.510201 -0.373499 -0.849119 -0.37349 -0.510205 -0.849119 -0.136702 -0.510201 -0.84912 0.136715 0.37349 -0.849119 -0.373499 0.136702 -0.849119 -0.510205 -0.136715 -0.849119 -0.510201 0.510201 -0.849119 -0.136715 0.965929 0 0.258807 0.965929 0 0.258807 0.707117 0 0.707097 0.707117 0 0.707097 0.258831 0 0.965923 0.258831 0 0.965923 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.258831 0 -0.965923 -0.258831 0 -0.965923 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707116 0.707098 0 -0.707116 0.965922 0 -0.258832 0.965922 0 -0.258832 0.3735 -0.849119 0.37349 0.510205 -0.849119 0.136702 -0.373489 -0.84912 0.3735 -0.136702 -0.84912 0.510204 0.136715 -0.84912 0.510201 -0.373499 -0.84912 -0.373489 -0.510204 -0.84912 -0.136702 -0.510201 -0.84912 0.136715 0.37349 -0.849119 -0.373499 0.136702 -0.849119 -0.510205 -0.136715 -0.84912 -0.510201 0.510201 -0.849119 -0.136715 0.965929 0 0.258807 0.965929 0 0.258807 0.707116 0 0.707097 0.707116 0 0.707097 0.258832 0 0.965922 0.258832 0 0.965922 -0.258807 0 0.965929 -0.258807 0 0.965929 -0.707097 0 0.707117 -0.707097 0 0.707117 -0.965923 0 0.258831 -0.965923 0 0.258831 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707116 0 -0.707097 -0.707116 0 -0.707097 -0.258832 0 -0.965922 -0.258832 0 -0.965922 0.258807 0 -0.965929 0.258807 0 -0.965929 0.707098 0 -0.707115 0.707098 0 -0.707115 0.965923 0 -0.258831 0.965923 0 -0.258831 0.373499 -0.849119 0.373489 0.510204 -0.84912 0.136702 -0.373488 -0.849119 0.373501 -0.136703 -0.849119 0.510205 0.136715 -0.849119 0.510201 -0.3735 -0.84912 -0.373488 -0.510205 -0.849119 -0.136702 -0.510202 -0.849119 0.136713 0.373489 -0.84912 -0.373499 0.136701 -0.84912 -0.510204 -0.136715 -0.84912 -0.510201 0.510201 -0.84912 -0.136715 0.965929 0 0.258807 0.965929 0 0.258807 0.707116 0 0.707097 0.707116 0 0.707097 0.258831 0 0.965923 0.258831 0 0.965923 -0.258808 0 0.965929 -0.258808 0 0.965929 -0.707095 0 0.707119 -0.707095 0 0.707119 -0.965923 0 0.258828 -0.965923 0 0.258828 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.707118 0 -0.707096 -0.707118 0 -0.707096 -0.258831 0 -0.965923 -0.258831 0 -0.965923 0.258806 0 -0.965929 0.258806 0 -0.965929 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965922 0 -0.258832 0.965922 0 -0.258832 -0.37349 0.849119 0.373499 -0.510201 0.84912 0.136715 0.3735 0.849119 0.37349 0.136717 0.849119 0.510201 -0.136702 0.849119 0.510205 0.37349 0.84912 -0.373499 0.510201 0.849119 -0.136715 0.510205 0.849119 0.136702 -0.373498 0.84912 -0.373489 -0.136716 0.84912 -0.5102 0.136702 0.84912 -0.510204 -0.510204 0.84912 -0.136702 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258835 0 0.965922 0.258835 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258835 0 -0.965922 -0.258835 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.373489 0.84912 0.373498 -0.5102 0.84912 0.136716 0.373499 0.849119 0.37349 0.136715 0.84912 0.510201 -0.136702 0.84912 0.510204 0.37349 0.849119 -0.3735 0.510201 0.849119 -0.136717 0.510205 0.849119 0.136702 -0.373498 0.84912 -0.37349 -0.136715 0.849119 -0.510201 0.136702 0.849119 -0.510205 -0.510203 0.84912 -0.136702 -0.965922 0 0.258834 -0.965922 0 0.258834 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258835 0.965922 0 -0.258835 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707114 0 -0.7071 -0.707114 0 -0.7071 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.37349 0.84912 0.373499 -0.5102 0.84912 0.136717 0.373498 0.849119 0.373491 0.136715 0.849119 0.510202 -0.136702 0.849119 0.510205 0.37349 0.849119 -0.373499 0.510201 0.849119 -0.136717 0.510205 0.849119 0.136702 -0.373498 0.84912 -0.373489 -0.136715 0.84912 -0.510201 0.136702 0.84912 -0.510204 -0.510203 0.84912 -0.136702 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707114 0 0.7071 0.707114 0 0.7071 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258835 0.965922 0 -0.258835 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.37349 0.84912 0.373498 -0.5102 0.84912 0.136716 0.373499 0.849119 0.373491 0.136715 0.849119 0.510201 -0.136702 0.84912 0.510204 0.37349 0.849119 -0.373499 0.510201 0.849119 -0.136717 0.510205 0.849119 0.136702 -0.373498 0.84912 -0.37349 -0.136715 0.84912 -0.510201 0.136702 0.849119 -0.510205 -0.510203 0.84912 -0.136702 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707114 0 0.707099 0.707114 0 0.707099 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258835 0.965922 0 -0.258835 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707114 0 -0.707099 -0.707114 0 -0.707099 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.37349 0.849119 0.3735 -0.510201 0.849119 0.136717 0.373498 0.84912 0.37349 0.136715 0.849119 0.510201 -0.136702 0.849119 0.510205 0.373489 0.84912 -0.373498 0.5102 0.84912 -0.136716 0.510204 0.84912 0.136702 -0.373499 0.849119 -0.37349 -0.136715 0.84912 -0.510201 0.136702 0.84912 -0.510204 -0.510205 0.849119 -0.136702 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707114 0 0.7071 0.707114 0 0.7071 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258835 0.965922 0 -0.258835 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.373489 0.84912 0.373498 -0.510201 0.84912 0.136715 0.373499 0.84912 0.37349 0.136717 0.84912 0.5102 -0.136702 0.84912 0.510203 0.37349 0.849119 -0.373499 0.510202 0.849119 -0.136715 0.510205 0.849119 0.136702 -0.373499 0.849119 -0.37349 -0.136717 0.849119 -0.510201 0.136702 0.849119 -0.510205 -0.510204 0.84912 -0.136702 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258835 0 0.965922 0.258835 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258835 0 -0.965922 -0.258835 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.373489 0.84912 0.373498 -0.510201 0.84912 0.136715 0.373498 0.84912 0.37349 0.136717 0.84912 0.5102 -0.136702 0.84912 0.510203 0.373491 0.849119 -0.373498 0.510201 0.849119 -0.136716 0.510204 0.84912 0.136702 -0.373499 0.849119 -0.37349 -0.136716 0.849119 -0.510201 0.136702 0.849119 -0.510205 -0.510204 0.84912 -0.136702 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258835 0 0.965922 0.258835 0 0.965922 0.707115 0 0.707099 0.707115 0 0.707099 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258833 0.965922 0 -0.258833 0.7071 0 -0.707114 0.7071 0 -0.707114 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258834 0 -0.965922 -0.258834 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.37349 0.84912 0.373498 -0.510201 0.84912 0.136715 0.373498 0.84912 0.37349 0.136716 0.84912 0.5102 -0.136702 0.84912 0.510203 0.373491 0.849119 -0.373499 0.510201 0.849119 -0.136715 0.510204 0.84912 0.136702 -0.373499 0.849119 -0.37349 -0.136717 0.849119 -0.510201 0.136702 0.849119 -0.510205 -0.510205 0.849119 -0.136702 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707099 0 0.707114 -0.707099 0 0.707114 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258835 0 0.965922 0.258835 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707099 0 -0.707114 0.707099 0 -0.707114 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258835 0 -0.965922 -0.258835 0 -0.965922 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.373489 0.849119 0.3735 -0.510201 0.84912 0.136716 0.373498 0.849119 0.373491 0.136717 0.849119 0.510201 -0.136702 0.849119 0.510205 0.37349 0.84912 -0.373498 0.510201 0.849119 -0.136715 0.510205 0.849119 0.136701 -0.373498 0.84912 -0.373489 -0.136713 0.84912 -0.510202 0.136699 0.84912 -0.510205 -0.510204 0.84912 -0.136702 -0.965922 0 0.258833 -0.965922 0 0.258833 -0.707097 0 0.707117 -0.707097 0 0.707117 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258835 0 0.965922 0.258835 0 0.965922 0.707114 0 0.7071 0.707114 0 0.7071 0.96593 0 0.258804 0.96593 0 0.258804 0.965922 0 -0.258832 0.965922 0 -0.258832 0.7071 0 -0.707114 0.7071 0 -0.707114 0.258801 0 -0.965931 0.258801 0 -0.965931 -0.258828 0 -0.965924 -0.258828 0 -0.965924 -0.707115 0 -0.707098 -0.707115 0 -0.707098 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.373488 0.849119 0.373501 -0.510202 0.849119 0.136713 0.3735 0.849119 0.373489 0.136715 0.849119 0.510201 -0.136702 0.849119 0.510205 0.373489 0.84912 -0.373498 0.510201 0.84912 -0.136713 0.510205 0.849119 0.136702 -0.373501 0.84912 -0.373488 -0.136715 0.84912 -0.510201 0.136701 0.84912 -0.510204 -0.510205 0.849119 -0.136702 -0.965923 0 0.258828 -0.965923 0 0.258828 -0.707095 0 0.707119 -0.707095 0 0.707119 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707117 0 0.707097 0.707117 0 0.707097 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.258828 0.965923 0 -0.258828 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707119 0 -0.707095 -0.707119 0 -0.707095 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.373488 0.84912 0.373501 -0.510201 0.84912 0.136713 0.373501 0.84912 0.373488 0.136715 0.84912 0.510201 -0.136702 0.84912 0.510204 0.37349 0.84912 -0.373499 0.510202 0.849119 -0.136713 0.510205 0.849119 0.136702 -0.3735 0.849119 -0.373489 -0.136715 0.849119 -0.510201 0.136701 0.849119 -0.510205 -0.510205 0.849119 -0.136702 -0.965923 0 0.258828 -0.965923 0 0.258828 -0.707095 0 0.707119 -0.707095 0 0.707119 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707119 0 0.707095 0.707119 0 0.707095 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.258828 0.965923 0 -0.258828 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707117 0 -0.707097 -0.707117 0 -0.707097 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.373488 0.849119 0.373501 -0.510201 0.84912 0.136713 0.3735 0.849119 0.373489 0.136715 0.84912 0.510201 -0.136702 0.849119 0.510205 0.37349 0.84912 -0.373498 0.510201 0.84912 -0.136713 0.510205 0.849119 0.136702 -0.3735 0.84912 -0.373488 -0.136715 0.84912 -0.510201 0.136701 0.84912 -0.510205 -0.510205 0.849119 -0.136702 -0.965923 0 0.258828 -0.965923 0 0.258828 -0.707095 0 0.707118 -0.707095 0 0.707118 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707118 0 0.707096 0.707118 0 0.707096 0.965929 0 0.258807 0.965929 0 0.258807 0.965923 0 -0.258828 0.965923 0 -0.258828 0.707099 0 -0.707115 0.707099 0 -0.707115 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707118 0 -0.707096 -0.707118 0 -0.707096 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.37349 0.849119 0.373499 -0.510201 0.849119 0.136716 0.373498 0.84912 0.373489 0.136715 0.84912 0.510201 -0.136702 0.84912 0.510204 0.37349 0.84912 -0.373499 0.5102 0.84912 -0.136717 0.510203 0.84912 0.136702 -0.373498 0.849119 -0.373491 -0.136715 0.849119 -0.510202 0.136702 0.849119 -0.510205 -0.510205 0.849119 -0.136702 -0.965922 0 0.258834 -0.965922 0 0.258834 -0.707098 0 0.707115 -0.707098 0 0.707115 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258832 0 0.965922 0.258832 0 0.965922 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258807 0.965929 0 0.258807 0.965922 0 -0.258835 0.965922 0 -0.258835 0.707098 0 -0.707115 0.707098 0 -0.707115 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258832 0 -0.965922 -0.258832 0 -0.965922 -0.707114 0 -0.7071 -0.707114 0 -0.7071 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.373489 0.849119 0.3735 -0.5102 0.84912 0.136717 0.373498 0.84912 0.373491 0.136713 0.849119 0.510202 -0.136702 0.849119 0.510205 0.373489 0.849119 -0.3735 0.510201 0.849119 -0.136715 0.510205 0.84912 0.1367 -0.373501 0.84912 -0.373488 -0.136713 0.84912 -0.510202 0.136702 0.849119 -0.510205 -0.510204 0.84912 -0.136702 -0.965922 0 0.258835 -0.965922 0 0.258835 -0.707097 0 0.707117 -0.707097 0 0.707117 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258828 0 0.965923 0.258828 0 0.965923 0.707114 0 0.7071 0.707114 0 0.7071 0.96593 0 0.258803 0.96593 0 0.258803 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707097 0 -0.707117 0.707097 0 -0.707117 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258828 0 -0.965924 -0.258828 0 -0.965924 -0.707119 0 -0.707095 -0.707119 0 -0.707095 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.373488 0.84912 0.373501 -0.510201 0.84912 0.136715 0.373499 0.84912 0.37349 0.136713 0.849119 0.510202 -0.136702 0.849119 0.510205 0.373489 0.849119 -0.3735 0.510201 0.849119 -0.136715 0.510205 0.849119 0.136701 -0.373501 0.84912 -0.373488 -0.136713 0.84912 -0.510201 0.136702 0.849119 -0.510205 -0.510204 0.84912 -0.136702 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707095 0 0.707119 -0.707095 0 0.707119 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258828 0 0.965923 0.258828 0 0.965923 0.707115 0 0.707098 0.707115 0 0.707098 0.965929 0 0.258806 0.965929 0 0.258806 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707097 0 -0.707117 0.707097 0 -0.707117 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.707119 0 -0.707095 -0.707119 0 -0.707095 -0.965929 0 -0.258807 -0.965929 0 -0.258807 -0.373488 0.84912 0.3735 -0.510201 0.84912 0.136715 0.373498 0.84912 0.37349 0.136713 0.84912 0.510201 -0.136702 0.849119 0.510205 0.373489 0.84912 -0.3735 0.510201 0.84912 -0.136715 0.510205 0.84912 0.136701 -0.373501 0.849119 -0.373488 -0.136713 0.84912 -0.510201 0.136702 0.849119 -0.510205 -0.510205 0.849119 -0.136702 -0.965922 0 0.258832 -0.965922 0 0.258832 -0.707096 0 0.707118 -0.707096 0 0.707118 -0.258807 0 0.965929 -0.258807 0 0.965929 0.258828 0 0.965923 0.258828 0 0.965923 0.707115 0 0.707098 0.707115 0 0.707098 0.96593 0 0.258805 0.96593 0 0.258805 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707096 0 -0.707118 0.707096 0 -0.707118 0.258807 0 -0.965929 0.258807 0 -0.965929 -0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.707119 0 -0.707095 -0.707119 0 -0.707095 -0.965929 0 -0.258807 -0.965929 0 -0.258807 0.96593 0 0.258805 0.96593 0 0.258805 0.707112 0 0.707102 0.707112 0 0.707102 0.258839 0 0.96592 0.258839 0 0.96592 -0.258816 0 0.965927 -0.258816 0 0.965927 -0.707097 0 0.707116 -0.707097 0 0.707116 -0.965922 0 0.258834 -0.965922 0 0.258834 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.707112 0 -0.707102 -0.707112 0 -0.707102 -0.258839 0 -0.96592 -0.258839 0 -0.96592 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707097 0 -0.707116 0.707097 0 -0.707116 0.965923 0 -0.258831 0.965923 0 -0.258831 -0.974759 0 -0.22326 -0.974745 3.38698e-05 -0.223323 -0.999239 -9.05476e-06 -0.0390146 -0.99752 -0.0149951 0.068763 -0.994181 0 0.10772 0.910397 0.0492021 0.410801 0.610801 0.0440879 0.790555 0.696356 0.000172866 0.717697 0.846901 -0.000121582 0.531751 0.0156475 -0.00609519 0.999859 0.196695 0.0468934 0.979343 0.167836 0.0334974 0.985246 0.333328 1.94052e-05 0.942811 0.50222 -1.01884e-05 0.86474 -0.199943 0.00555153 0.979792 -0.314732 0.0340289 0.94857 -0.385523 0.0089607 0.922655 -0.592662 -0.00623808 0.805427 -0.668029 0.0145065 0.743994 -0.738232 0 0.674547 0.956839 -0.00974094 0.290455 0.997607 0.00643772 0.0688379 0.996734 0.0477787 -0.0650978 0.987036 -0.00335198 -0.160466 0.888599 0.0034894 -0.458672 0.885532 0 -0.464579 0.998781 0.0460173 -0.0178618 0.998487 0.0305873 -0.0456853 0.988642 0 -0.150292 0.855507 -0.0111136 0.517672 0.91234 0.0272265 0.408527 0.939597 0.0568814 0.337523 0.928888 0.0315055 0.369019 0.985077 -0.00627339 0.172003 0.998416 0.012829 0.0547813 0.699915 0.0207448 0.713925 0.714941 0.0119978 0.699081 0.598504 0 0.80112 -0.508581 0.694749 0.508595 -0.50858 0.694752 0.508592 -0.186152 0.694755 0.694739 -0.186151 0.694741 0.694754 0.186173 0.69474 0.694748 0.186162 0.694759 0.694733 0.508587 0.694756 0.50858 0.508603 0.694739 0.508587 0.694753 0.694743 0.186147 0.694748 0.694747 0.186148 0.694746 0.694745 -0.186166 0.694749 0.694741 -0.186168 0.508592 0.694733 -0.508606 0.508591 0.694736 -0.508603 0.18615 0.694733 -0.694762 0.186151 0.694741 -0.694754 -0.186173 0.69474 -0.694748 -0.186162 0.694759 -0.694733 -0.508587 0.694756 -0.50858 -0.508603 0.694739 -0.508587 -0.694753 0.694743 -0.186147 -0.694748 0.694747 -0.186148 -0.694746 0.694744 0.186168 -0.694743 0.694747 0.186166 0.694745 -0.694746 -0.186166 0.508584 -0.694745 -0.508597 0.508583 -0.694746 -0.508597 0.186148 -0.694748 -0.694748 0.186148 -0.694746 -0.69475 -0.186166 -0.694746 -0.694745 -0.186166 -0.694746 -0.694745 -0.508597 -0.694745 -0.508584 -0.508597 -0.694746 -0.508583 -0.69475 -0.694746 -0.186148 -0.694748 -0.694748 -0.186148 -0.694743 -0.694748 0.186165 -0.694745 -0.694746 0.186167 -0.508584 -0.694745 0.508597 -0.508582 -0.694749 0.508594 -0.186148 -0.694749 0.694747 -0.186148 -0.694746 0.69475 0.186166 -0.694746 0.694745 0.186166 -0.694746 0.694745 0.508597 -0.694745 0.508584 0.508596 -0.694746 0.508584 0.694749 -0.694746 0.186148 0.69475 -0.694746 0.186148 0.694745 -0.694746 -0.186166 0.694745 -0.694746 -0.186166 0.508584 -0.694746 -0.508596 0.508584 -0.694746 -0.508596 0.186148 -0.694746 -0.69475 0.186148 -0.694744 -0.694752 -0.186166 -0.694744 -0.694747 -0.186165 -0.694746 -0.694745 -0.508597 -0.694746 -0.508583 -0.508598 -0.694745 -0.508584 -0.69475 -0.694745 -0.186148 -0.694751 -0.694745 -0.186148 -0.694744 -0.694747 0.186165 -0.694745 -0.694746 0.186166 -0.508584 -0.694745 0.508597 -0.508583 -0.694746 0.508597 -0.186148 -0.694746 0.69475 -0.186148 -0.694748 0.694748 0.186165 -0.694748 0.694743 0.186166 -0.694746 0.694744 0.508597 -0.694746 0.508584 0.508595 -0.694748 0.508583 0.694749 -0.694747 0.186148 0.694749 -0.694746 0.186148 0.694744 -0.694746 -0.186166 0.694745 -0.694746 -0.186167 0.508584 -0.694745 -0.508597 0.508583 -0.694746 -0.508597 0.186148 -0.694748 -0.694748 0.186148 -0.694746 -0.69475 -0.186166 -0.694746 -0.694745 -0.186165 -0.694747 -0.694744 -0.508594 -0.694749 -0.508582 -0.508597 -0.694746 -0.508583 -0.69475 -0.694746 -0.186148 -0.694748 -0.694748 -0.186148 -0.694743 -0.694748 0.186165 -0.694745 -0.694746 0.186167 -0.508584 -0.694745 0.508597 -0.508582 -0.694749 0.508594 -0.186148 -0.694749 0.694747 -0.186148 -0.694746 0.69475 0.186166 -0.694746 0.694745 0.186165 -0.694747 0.694744 0.508594 -0.694749 0.508582 0.508597 -0.694746 0.508583 0.69475 -0.694746 0.186148 0.694748 -0.694748 0.186148 0.694743 -0.694748 -0.186165 0.694741 -0.69475 -0.186164 0.508582 -0.694749 -0.508594 0.508584 -0.694745 -0.508598 0.186148 -0.694745 -0.69475 0.186148 -0.694748 -0.694748 -0.186165 -0.694748 -0.694743 -0.186167 -0.694746 -0.694745 -0.508597 -0.694745 -0.508584 -0.508592 -0.694751 -0.508581 -0.694744 -0.694751 -0.186148 -0.694752 -0.694744 -0.186148 -0.694747 -0.694744 0.186167 -0.694745 -0.694746 0.186165 -0.508583 -0.694747 0.508596 -0.508584 -0.694745 0.508598 -0.186148 -0.694745 0.69475 -0.186148 -0.694748 0.694748 0.186165 -0.694748 0.694743 0.186165 -0.694748 0.694743 0.508596 -0.694747 0.508583 0.508598 -0.694745 0.508584 0.69475 -0.694746 0.186149 0.694752 -0.694744 0.186149 0.694747 -0.694743 -0.186168 0.508597 -0.694745 0.508586 0.508598 -0.694743 0.508587 0.18617 -0.694742 0.694748 0.18617 -0.694735 0.694755 -0.186155 -0.694734 0.694759 -0.186144 -0.694756 0.694741 -0.508577 -0.694755 0.508591 -0.50858 -0.694752 0.508592 -0.694742 -0.694749 0.186167 -0.694744 -0.694747 0.186166 -0.694746 -0.69475 -0.186147 -0.69475 -0.694746 -0.186149 -0.508599 -0.694745 -0.508582 -0.5086 -0.694742 -0.508585 -0.186165 -0.694741 -0.69475 -0.186165 -0.694753 -0.694738 0.186145 -0.694753 -0.694743 0.186153 -0.694738 -0.694756 0.508586 -0.694742 -0.5086 0.508588 -0.694739 -0.508601 0.694747 -0.694744 -0.186166 0.694744 -0.694747 -0.186166 0.694746 -0.69475 0.186147 0.69475 -0.694746 0.186149 0.508597 -0.694745 0.508585 0.508595 -0.694749 0.508581 0.186165 -0.694751 0.69474 0.186165 -0.694745 0.694746 -0.186148 -0.694743 0.694753 -0.186146 -0.694745 0.69475 -0.508586 -0.694745 0.508597 -0.508585 -0.694746 0.508596 -0.694745 -0.694746 0.186165 -0.694744 -0.694747 0.186165 -0.694746 -0.69475 -0.186146 -0.69475 -0.694746 -0.186148 -0.508597 -0.694745 -0.508585 -0.508595 -0.694749 -0.508581 -0.186165 -0.694751 -0.69474 -0.186165 -0.694744 -0.694747 0.186148 -0.694744 -0.694752 0.186147 -0.694745 -0.69475 0.508586 -0.694745 -0.508597 0.508585 -0.694746 -0.508596 0.694744 -0.694746 -0.186166 0.694748 -0.694743 -0.186166 0.69475 -0.694745 0.186149 0.69475 -0.694746 0.186148 0.508598 -0.694745 0.508584 0.508599 -0.694743 0.508586 0.186167 -0.694742 0.694749 0.186167 -0.694744 0.694747 -0.18615 -0.694744 0.694751 -0.186148 -0.694747 0.694748 -0.508582 -0.694748 0.508596 -0.508584 -0.694746 0.508597 -0.694744 -0.694746 0.186166 -0.694744 -0.694747 0.186166 -0.694746 -0.694749 -0.186148 -0.694747 -0.694748 -0.186148 -0.508593 -0.694752 -0.50858 -0.508595 -0.694749 -0.508582 -0.186165 -0.694751 -0.69474 -0.186165 -0.694753 -0.694738 0.186145 -0.694753 -0.694743 0.186148 -0.694747 -0.694748 0.508582 -0.694748 -0.508596 0.508584 -0.694746 -0.508597 0.694745 -0.694746 -0.186166 0.694741 -0.694749 -0.186166 0.694749 -0.694747 0.186148 0.69475 -0.694746 0.186149 0.508599 -0.694745 0.508583 0.5086 -0.694742 0.508585 0.186165 -0.694741 0.69475 0.186165 -0.694753 0.694738 -0.186145 -0.694753 0.694743 -0.186153 -0.694738 0.694756 -0.508586 -0.694742 0.5086 -0.508588 -0.694739 0.508601 -0.694747 -0.694744 0.186166 -0.694748 -0.694743 0.186166 -0.69475 -0.694745 -0.186148 -0.69475 -0.694746 -0.186148 -0.508596 -0.694745 -0.508586 -0.508595 -0.694746 -0.508585 -0.186165 -0.694743 -0.694748 -0.186165 -0.694753 -0.694738 0.186145 -0.694753 -0.694743 0.186144 -0.694755 -0.694742 0.508578 -0.694753 -0.508592 0.508579 -0.694752 -0.508593 0.694743 -0.694748 -0.186165 0.694739 -0.694752 -0.186165 0.694751 -0.694745 0.186149 0.69475 -0.694746 0.186148 0.508599 -0.694745 0.508582 0.5086 -0.694742 0.508585 0.186165 -0.694741 0.69475 0.186165 -0.694753 0.694738 -0.186145 -0.694753 0.694743 -0.186153 -0.694738 0.694756 -0.508586 -0.694742 0.5086 -0.508588 -0.694739 0.508601 -0.694747 -0.694744 0.186166 -0.694748 -0.694743 0.186166 -0.69475 -0.694745 -0.186149 -0.694746 -0.69475 -0.186146 -0.50859 -0.694758 -0.508573 -0.508598 -0.694743 -0.508587 -0.186165 -0.694741 -0.69475 -0.186165 -0.694753 -0.694738 0.186145 -0.694753 -0.694743 0.186144 -0.694756 -0.694741 0.508577 -0.694755 -0.508591 0.50858 -0.694752 -0.508592 0.694743 -0.694748 -0.186165 0.694739 -0.694752 -0.186165 0.694751 -0.694745 0.186149 0.69475 -0.694746 0.186149 0.508601 -0.694746 0.50858 0.508609 -0.694729 0.508595 0.186165 -0.694723 0.694768 0.186166 -0.69477 0.694721 -0.186141 -0.694771 0.694727 -0.186149 -0.694755 0.69474 -0.50858 -0.694752 0.508593 -0.508568 -0.694765 0.508587 -0.694738 -0.694753 0.186164 -0.694744 -0.694747 0.186164 -0.694747 -0.69475 -0.186145 -0.69475 -0.694746 -0.186148 -0.508596 -0.694745 -0.508586 -0.508591 -0.694755 -0.508577 -0.186165 -0.69476 -0.694731 -0.186165 -0.694735 -0.694756 0.18615 -0.694735 -0.69476 0.18614 -0.694754 -0.694744 0.50858 -0.694752 -0.508593 0.50859 -0.69474 -0.508599 0.694748 -0.694744 -0.186165 0.694748 -0.694743 -0.186165 0.69475 -0.694745 0.186151 0.694749 -0.694746 0.18615 0.508596 -0.694745 0.508586 0.50859 -0.694757 0.508575 0.186165 -0.694761 0.69473 0.186165 -0.694753 0.694738 -0.186145 -0.694753 0.694743 -0.186153 -0.694738 0.694756 -0.508587 -0.69474 0.508601 -0.508588 -0.694739 0.508602 -0.694747 -0.694744 0.186166 -0.694746 -0.694745 0.186166 -0.694748 -0.694747 -0.186147 -0.694748 -0.694748 -0.186147 -0.508595 -0.694746 -0.508585 -0.508596 -0.694744 -0.508587 -0.18617 -0.694743 -0.694747 -0.18617 -0.694735 -0.694755 0.186155 -0.694734 -0.694759 0.186144 -0.694754 -0.694742 0.50858 -0.694752 -0.508593 0.508579 -0.694752 -0.508593 0.694742 -0.694749 -0.186166 0.694746 -0.694745 -0.186166 0.694748 -0.694747 0.186147 0.69475 -0.694746 0.186148 0.508596 -0.694745 0.508586 0.508591 -0.694756 0.508576 0.186165 -0.69476 0.694731 0.186165 -0.694735 0.694756 -0.18615 -0.694735 0.69476 -0.186158 -0.69472 0.694773 -0.508596 -0.694727 0.50861 -0.508586 -0.694739 0.508605 -0.694748 -0.694743 0.186164 -0.694745 -0.694746 0.186164 -0.694747 -0.694748 -0.18615 -0.69474 -0.694756 -0.186145 -0.508583 -0.694773 -0.508561 -0.508603 -0.694731 -0.508598 -0.186164 -0.694723 -0.694768 -0.186166 -0.69477 -0.694721 0.186141 -0.694771 -0.694727 0.186149 -0.694756 -0.69474 0.508578 -0.694753 -0.508592 0.508568 -0.694765 -0.508587 0.694738 -0.694753 -0.186165 0.694746 -0.694746 -0.186165 0.694748 -0.694748 0.186147 0.694749 -0.694746 0.186148 -0.260545 -0.965282 0.018651 -0.260546 -0.965281 0.0186513 -0.964089 -0.256455 0.0690117 -0.964092 -0.256443 0.0690139 -0.708781 -0.703601 0.0507376 -0.791623 -0.606204 0.0764873 -0.610999 -0.790422 0.0437386 -0.25552 -0.965281 -0.0542386 -0.255524 -0.96528 -0.0542388 -0.695107 -0.703602 -0.147547 -0.695094 -0.703616 -0.147547 -0.94549 -0.256453 -0.200699 -0.945493 -0.256445 -0.200698 -0.999065 0 0.043237 -0.996159 0.00117522 -0.0875591 -0.976202 0 -0.216865 -0.687951 -0.257894 -0.678391 -0.184791 -0.965682 -0.182514 -0.189251 -0.980645 -0.050184 -0.195074 -0.980645 -0.016793 -0.195047 -0.980645 0.0171021 -0.195047 -0.980645 0.0171021 -0.554886 -0.830503 0.0486533 -0.183407 -0.980786 -0.0664939 -0.157125 -0.98512 -0.0696495 -0.0794921 -0.99616 -0.0367011 -0.171049 -0.980779 -0.0938836 -0.160948 -0.980644 -0.111503 -0.160944 -0.980645 -0.1115 -0.139925 -0.980661 -0.136842 -0.433607 -0.792273 -0.429288 -0.538419 -0.830494 -0.142773 -0.505728 -0.830494 -0.233492 -0.505719 -0.830501 -0.233488 -0.457873 -0.8305 -0.317209 -0.457874 -0.830499 -0.31721 -0.396305 -0.8305 -0.391423 -0.565234 -0.607325 -0.558271 -0.594361 -0.548852 -0.587789 -0.687116 -0.548883 -0.476025 -0.687307 -0.548524 -0.476163 -0.759132 -0.548522 -0.350488 -0.755787 -0.554151 -0.348858 -0.80461 -0.554148 -0.213359 -0.808167 -0.548551 -0.214379 -0.195071 -0.980645 -0.0167927 -0.554963 -0.830502 -0.0477741 -0.554886 -0.830503 0.0486533 -0.832949 -0.548508 0.0730344 -0.829241 -0.554131 0.0727872 -0.978459 -0.187803 0.0857181 -0.977178 -0.194376 0.0856808 -0.189254 -0.980645 -0.0501847 -0.53841 -0.830501 -0.142771 -0.554964 -0.830501 -0.0477742 -0.833035 -0.548552 -0.0717121 -0.833064 -0.548509 -0.0717151 -0.472914 0.880168 -0.0407088 -0.981221 -0.188311 -0.0417674 -0.698762 -0.188202 -0.690154 -0.782255 -0.188705 -0.593689 -0.390534 0.879942 -0.270529 -0.830772 -0.188309 -0.523792 -0.89172 -0.187799 -0.411785 -0.890588 -0.194383 -0.41118 -0.948175 -0.194383 -0.251354 -0.94939 -0.18783 -0.251751 -0.973917 -0.188341 -0.126541 0.86152 -0.190582 -0.470598 0.861522 -0.190569 -0.470599 0.790788 -0.433664 -0.431961 0.735899 -0.546424 -0.399841 0.70247 -0.599413 -0.383718 0.495788 -0.825137 -0.27082 0.544152 -0.785809 -0.293944 0.174143 -0.97968 -0.0995068 0.232352 -0.964315 -0.12692 0.979881 -0.190571 -0.0592882 0.979881 -0.190573 -0.0592881 0.836107 -0.546229 -0.050589 0.83611 -0.546224 -0.0505894 0.563899 -0.825138 -0.0341191 0.563891 -0.825144 -0.0341181 0.199343 -0.979855 -0.0120612 0.199346 -0.979855 -0.0120616 0.911975 -0.190579 0.363292 0.911975 -0.190577 0.363292 0.778169 -0.546223 0.309989 0.778165 -0.546229 0.309988 0.524814 -0.825144 0.209064 0.524822 -0.825138 0.209067 0.185532 -0.979855 0.0739078 0.185529 -0.979856 0.0739069 0.0608916 -0.186792 -0.980511 0.0492587 -0.606927 -0.793229 0.0558785 -0.432646 -0.89983 0.0162063 -0.965212 -0.260966 0.0378467 -0.79193 -0.609438 0.0644859 -0.256335 -0.964434 0.410906 -0.252472 -0.876022 0.410902 -0.252528 -0.876007 0.75598 -0.252516 -0.603929 0.755982 -0.252505 -0.603931 0.945132 -0.252507 -0.207283 0.945135 -0.252492 -0.207285 0.939345 -0.252491 0.232118 0.939341 -0.252507 0.232118 0.739801 -0.252514 0.623643 0.739813 -0.252465 0.623649 0.450801 -0.255843 0.855174 0.45079 -0.255901 0.855163 0.0498781 -0.703663 -0.708781 0.304229 -0.697693 -0.64859 0.304233 -0.697682 -0.6486 0.559725 -0.697687 -0.447147 0.559722 -0.697691 -0.447145 0.699768 -0.69769 -0.153471 0.699766 -0.697692 -0.153471 0.695481 -0.69769 0.171858 0.695488 -0.697682 0.171859 0.547752 -0.697682 0.461745 0.547746 -0.697689 0.461741 0.331747 -0.702767 0.629335 0.331748 -0.702765 0.629337 0.0162062 -0.965211 -0.260969 0.112657 -0.96417 -0.240176 0.112654 -0.964173 -0.240167 0.207262 -0.964172 -0.165575 0.207262 -0.964172 -0.165576 0.259122 -0.964171 -0.0568299 0.259125 -0.96417 -0.0568306 0.257539 -0.96417 0.0636394 0.257532 -0.964172 0.0636381 0.202825 -0.964172 0.170978 0.202823 -0.964173 0.170976 0.122075 -0.965126 0.23158 0.12208 -0.965124 0.231588 0.0765167 -0.186265 -0.979515 0.0619585 -0.60593 -0.793102 0.0702504 -0.431771 -0.899243 0.0204126 -0.96504 -0.261306 0.0476285 -0.791198 -0.609703 0.184027 -0.18628 0.965108 0.0793974 -0.25577 -0.963472 0.461289 -0.251033 -0.850996 0.461292 -0.251004 -0.851004 0.817732 -0.250996 -0.517992 0.817727 -0.251019 -0.517988 0.96651 -0.251005 -0.0534374 0.966505 -0.251025 -0.053436 0.86985 -0.251002 0.424686 0.869848 -0.251011 0.424686 0.552295 -0.251013 0.794961 0.552288 -0.25105 0.794954 0.185121 -0.25579 0.948842 0.16896 -0.4317 0.886052 0.0606528 -0.702722 -0.708875 0.342456 -0.695404 -0.631773 0.342462 -0.69539 -0.631786 0.607074 -0.695401 -0.38455 0.60707 -0.695406 -0.384547 0.717507 -0.695421 -0.0396695 0.717517 -0.695411 -0.0396707 0.645762 -0.695406 0.315281 0.645764 -0.695405 0.315281 0.410016 -0.695403 0.590171 0.410006 -0.695419 0.590159 0.133343 -0.702311 0.69927 0.133341 -0.702317 0.699265 0.0204126 -0.965041 -0.261304 0.127162 -0.96374 -0.234594 0.127158 -0.963743 -0.234585 0.225416 -0.963742 -0.142789 0.225412 -0.963743 -0.142787 0.266433 -0.963741 -0.0147308 0.266435 -0.96374 -0.0147311 0.239786 -0.963741 0.117071 0.239779 -0.963743 0.117068 0.152239 -0.963745 0.219131 0.152258 -0.963737 0.219155 0.0490968 -0.965037 0.257473 0.049096 -0.965038 0.25747 0.0823969 -0.186139 -0.979062 0.0667356 -0.605571 -0.792988 0.0756497 -0.431552 -0.89891 0.0219785 -0.965042 -0.261173 0.051313 -0.790925 -0.609757 0.183289 -0.186285 0.965248 0.0851887 -0.255756 -0.962981 0.465739 -0.251033 -0.848569 0.46574 -0.251022 -0.848572 0.819952 -0.251024 -0.514457 0.819947 -0.25105 -0.514452 0.966675 -0.251042 -0.0501641 0.966683 -0.251014 -0.050166 0.868803 -0.251007 0.426823 0.868795 -0.251037 0.426821 0.551073 -0.251035 0.795801 0.55108 -0.251001 0.795808 0.184402 -0.255713 0.949003 0.168274 -0.43172 0.886173 0.0649104 -0.702748 -0.708471 0.345736 -0.695456 -0.629927 0.345725 -0.695484 -0.629902 0.608664 -0.695477 -0.381889 0.608688 -0.695446 -0.381907 0.7176 -0.69546 -0.0372399 0.717591 -0.695469 -0.0372387 0.644938 -0.69546 0.316845 0.644948 -0.695448 0.316849 0.409092 -0.695443 0.590765 0.409075 -0.695471 0.590744 0.132797 -0.702341 0.699344 0.1328 -0.70233 0.699354 0.0219785 -0.965043 -0.261167 0.128377 -0.963748 -0.233899 0.128383 -0.963744 -0.233912 0.226017 -0.963746 -0.141809 0.226002 -0.963751 -0.141798 0.266452 -0.963749 -0.0138273 0.266457 -0.963748 -0.0138279 0.239472 -0.963749 0.117647 0.23948 -0.963747 0.117651 0.151902 -0.963746 0.219362 0.151897 -0.963748 0.219355 0.0488949 -0.965043 0.257491 0.0488906 -0.965047 0.257475 0.681169 -0.69531 0.229246 0.917449 -0.250903 0.308763 0.91744 -0.250938 0.308762 0.648515 -0.250951 0.718646 0.648533 -0.250866 0.71866 0.21328 -0.250855 0.944237 0.21327 -0.25095 0.944214 0.68119 -0.695287 0.229251 0.481524 -0.69528 0.533592 0.481528 -0.695274 0.533596 0.158355 -0.695268 0.70109 0.158359 -0.695256 0.7011 0.340476 -0.250854 -0.906172 0.340475 -0.250893 -0.906162 0.252788 -0.695309 -0.672788 0.25278 -0.695339 -0.67276 0.0938896 -0.963714 -0.249882 0.0938815 -0.963721 -0.249856 0.740765 -0.250908 -0.623147 0.740754 -0.250979 -0.623132 0.549982 -0.695321 -0.462653 0.550028 -0.695256 -0.462697 0.204254 -0.963721 -0.171823 0.204243 -0.963724 -0.171814 0.95106 -0.250942 -0.180313 0.951059 -0.250948 -0.180312 0.706156 -0.695284 -0.133881 0.706146 -0.695294 -0.133878 0.262248 -0.963719 -0.0497195 0.262256 -0.963717 -0.0497216 0.253882 -0.964351 0.0746415 0.593596 -0.779573 0.199772 0.221889 -0.965877 0.133592 0.17883 -0.963717 0.198167 0.178819 -0.963721 0.198156 0.058806 -0.963721 0.260352 0.0588005 -0.963727 0.260332 0.390128 4.81512e-06 0.920761 0.378573 0.0570863 0.923809 0.701326 -0.063068 0.710045 0.711003 -0.000520689 0.703188 0.936956 0.00111174 0.349447 0.930631 -0.06644 0.359879 0.999275 0 -0.0380632 0.947495 -0.303659 -0.100224 0.996412 0.0219497 0.0817412 -0.0290813 0.968124 -0.248778 -0.0411585 0.706508 -0.706507 -0.468004 0.58925 -0.658602 -0.564429 0.326563 -0.75814 -0.433897 0.706848 -0.558659 -0.122902 0.706504 -0.696956 -0.202982 0.706504 -0.677976 -0.0856699 0.968123 -0.235367 -0.280319 0.7065 -0.64983 -0.345107 0.706754 -0.617577 -0.451909 0.427961 -0.782706 -0.387007 0.689533 -0.612184 -0.385043 0.725162 -0.570861 -0.569441 0.707105 -0.419212 -0.553378 0.706925 -0.440489 -0.735653 0.278911 -0.617271 -0.590519 0.618245 -0.518711 -0.424381 0.799294 -0.425477 -0.640548 0.358833 -0.678924 -0.487919 0.674359 -0.554233 -0.457587 0.707094 -0.539103 -0.701069 0.558146 -0.443818 -0.802466 0.278392 -0.527775 -0.711557 0.513522 -0.479564 -0.594996 0.682343 -0.42472 -0.443606 0.865914 -0.231097 -0.63244 0.706499 -0.317614 -0.656262 0.706985 -0.263614 -0.901606 0.281829 -0.328145 -0.343967 0.934308 -0.0935709 -0.688634 0.706505 -0.1632 -0.702924 0.706505 -0.0821509 -0.378742 0.924909 -0.0331308 -0.962617 0.270866 1.23422e-05 -0.706964 0.70695 0.0205795 -0.702926 0.7065 0.0821696 -0.246668 0.968123 0.0434975 -0.49276 0.780258 0.385207 -0.735448 0.279762 0.61713 -0.603959 0.596561 0.528534 -0.606211 0.668566 0.43073 -0.695367 0.542862 0.470921 -0.803241 0.275113 0.528315 -0.602819 0.706974 0.36986 -0.63243 0.706501 0.317629 -0.229988 0.968123 0.0992105 -0.665037 0.706492 0.242063 -0.688642 0.706492 0.163221 -0.400187 0.702762 0.588197 -0.469061 0.587645 0.659284 -0.567916 0.309045 0.762865 -0.336349 0.845243 0.415251 -0.643878 0.345879 0.682488 -0.495089 0.706829 0.505252 -0.520024 0.707077 0.479184 -0.27435 0.67619 0.683739 -0.38126 0.270888 0.88389 -0.202068 0.898919 0.388734 -0.457122 0.405121 0.791781 -0.379509 0.707064 0.596686 -0.389119 0.707105 0.590415 -0.244028 0.7071 0.663671 -0.202965 0.706504 0.677981 -0.0674919 0.959524 0.273419 -0.148041 0.522564 0.839649 -0.088616 0.707084 0.701555 -0.0411408 0.706501 0.706515 3.22444e-06 0.968124 0.250473 0.0411589 0.706502 0.706513 0.0886358 0.707086 0.701551 0.147992 0.52283 0.839492 0.148172 0.521535 0.840266 0.157005 0.825025 0.542848 0.643893 0.345887 0.682469 0.33636 0.845243 0.415243 0.567938 0.309037 0.762852 0.469045 0.587712 0.659236 0.202981 0.706508 0.677972 0.280316 0.706508 0.649823 0.112414 0.968124 0.223828 0.353859 0.70651 0.612884 0.389124 0.707108 0.590407 0.400205 0.702761 0.588186 0.69538 0.542859 0.470903 0.80325 0.275132 0.528291 0.602822 0.706982 0.369841 0.606223 0.668564 0.430715 0.463222 0.804127 0.372566 0.675353 0.471993 0.566674 0.52004 0.707072 0.479173 0.495105 0.706824 0.505243 0.633087 0.706469 0.316391 0.601795 0.73926 0.302223 0.698295 0.669758 0.252605 0.665045 0.706491 0.242047 0.688648 0.70649 0.163204 0.359446 0.930272 0.0734324 0.95518 0.274172 0.111632 0.70468 0.70697 0.0601603 0.707713 0.7065 -9.0733e-06 0.25005 0.968123 -0.0145669 0.594991 0.682336 -0.424738 0.711551 0.51351 -0.479585 0.802448 0.278408 -0.527794 0.702933 0.706493 -0.0821704 0.688641 0.706494 -0.16322 0.23995 0.968123 -0.0718396 0.665028 0.706501 -0.24206 0.647961 0.707096 -0.283127 0.702654 0.617851 -0.352898 0.454014 0.858272 -0.239248 0.701052 0.558156 -0.443833 0.457566 0.7071 -0.539113 0.48791 0.674353 -0.554249 0.640528 0.358842 -0.678938 0.424371 0.799292 -0.42549 0.657128 0.513935 -0.55141 0.546392 0.706682 -0.449507 0.569443 0.707092 -0.419232 0.43388 0.706853 -0.558665 0.564408 0.326575 -0.758151 0.468006 0.589212 -0.658634 0.0411404 0.706508 -0.706508 0.0301708 0.958743 -0.282669 0.149556 0.508063 -0.848237 0.156169 0.707095 -0.689657 0.202962 0.706514 -0.677971 0.0856639 0.968123 -0.235369 0.280304 0.706496 -0.64984 0.320758 0.70709 -0.630189 0.398651 0.603555 -0.690506 0.387778 0.633523 -0.669535 0.385023 0.725169 -0.570865 -0.983906 1.4362e-05 0.178688 -0.983936 0 0.178523 -0.979937 0 0.199308 -0.979937 0 0.199308 -0.991688 -9.90965e-07 0.128668 -0.985987 1.4361e-05 0.166824 -0.987624 9.43004e-05 0.156839 -0.987794 0 0.155765 -0.991689 0 0.128657 -0.999848 -3.06195e-06 -0.0174507 -0.999848 0 -0.01744 -0.997237 0 0.0742827 -0.997237 -5.73515e-07 0.0742806 -0.997427 -4.5886e-06 -0.0716935 -0.997419 0 -0.0718022 -0.996144 0 -0.0877389 -0.996144 0 -0.0877389 -0.992974 0 -0.118331 -0.992974 0 -0.118331 -0.994768 0 -0.102161 -0.994768 0 -0.102161 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.251e-05 0 -1 -1.28086e-05 -1.56492e-06 -1 -1.47441e-05 0 -1 -1.47441e-05 0 -1 0.18447 0 -0.982838 0.18447 0 -0.982838 0.460738 0 -0.887536 0.528367 0.000436966 -0.849016 0.616337 0 -0.787482 0.800332 0 -0.599557 0.800332 0 -0.599557 0.200901 -0.570968 -0.796011 0.769273 -0.149676 -0.621141 0.156697 -0.156698 -0.975137 0.0721773 -0.446415 -0.891911 0.2274 -0.101669 -0.96848 0.078054 -0.256867 -0.96329 0.473437 -0.37547 -0.796793 0.159186 -0.780556 -0.604477 0.310912 -0.572867 -0.758391 0.45999 -0.45999 -0.759486 0.459989 -0.459992 -0.759485 0.612511 -0.248089 -0.750521 0.439124 -0.0651041 -0.896065 0.241928 -0.865164 -0.439274 0.851768 -0.226895 -0.472239 0.175408 -0.95841 -0.225126 0.285038 -0.881049 -0.3775 0.473022 -0.784123 -0.401748 0.617618 -0.617618 -0.486925 0.639079 -0.602216 -0.47845 0.855335 -0.258769 -0.448821 -1.44609e-05 -0.195083 -0.980787 0.000584087 -0.170459 -0.985365 -0.0003838 -0.4704 -0.882453 -0.000417504 -0.472421 -0.881373 0.000228791 -0.633211 -0.773979 -0.00202085 -0.813343 -0.581781 -0.000550992 -0.781487 -0.623922 2.4371e-05 -0.911012 -0.412381 -0.000278507 -0.975376 -0.220551 0.000281115 -0.980785 -0.195089 -1.85569e-07 -0.999912 -0.0132443 -2.76129e-05 -0.964708 -0.263321 -0.000793305 -0.915514 -0.402286 -1.90422e-06 -0.988489 -0.151294 0.366801 -0.00289956 -0.930295 -1.23667e-05 -0.150908 -0.988548 0.000732316 -0.400914 -0.916116 -1.27367e-05 -0.258729 -0.96595 -9.36777e-06 -0.703749 -0.710448 -0.000517875 -0.627455 -0.778652 1.68921e-06 -0.807673 -0.589631 -0.192334 0.0577481 -0.979629 -0.372216 -0.121011 -0.920224 -0.896734 -0.442223 -0.017531 -0.980689 -0.19507 -0.0140151 -0.442221 -0.896735 -0.017533 -0.980607 -0.195311 -0.0162426 -0.954696 -0.185588 -0.232621 -0.933415 -0.238793 -0.267796 -0.820796 -0.114968 -0.559533 -0.620177 -0.318547 -0.716874 -0.62614 -0.175704 -0.759656 -0.467761 -0.0152264 -0.883724 -0.128129 -0.0441014 -0.990776 -0.293574 -0.209473 -0.932703 -0.334955 -0.181464 -0.924595 -0.547875 -0.398314 -0.735649 -0.596516 -0.357248 -0.71871 -0.784804 -0.545656 -0.29384 -0.798275 -0.531124 -0.284013 -0.831281 -0.555549 -0.0183749 -0.707866 -0.543165 -0.451551 -0.0441015 -0.128129 -0.990776 -0.223692 -0.30756 -0.924862 -0.173843 -0.327126 -0.928852 -0.411706 -0.560265 -0.71875 -0.349814 -0.588104 -0.729222 -0.548164 -0.786659 -0.284049 -0.5296 -0.796112 -0.292794 -0.524391 -0.788694 -0.320899 -0.608657 -0.793216 -0.0185763 0.0577491 -0.192334 -0.979629 -0.165156 -0.413939 -0.895197 0.00678699 -0.44371 -0.896145 -0.274023 -0.707102 -0.651857 -0.0554436 -0.740638 -0.669613 -0.25038 -0.939197 -0.234986 -0.183531 -0.947473 -0.261938 -0.195364 -0.980631 -0.0140213 -0.195064 -0.980656 -0.0162467 -0.964343 -0.258389 0.0572526 -0.952622 -0.189487 0.23792 -0.895603 -0.441666 0.0531573 -0.792477 -0.608085 0.0470364 -0.792476 -0.608088 0.047032 -0.608361 -0.792839 0.0361052 -0.195077 -0.98072 0.0115762 -0.230381 -0.948903 0.215658 -0.442137 -0.896564 0.0262459 -0.608364 -0.792836 0.0361134 -0.998242 0 0.0592651 -0.998242 0 0.0592651 -0.999912 0 -0.0132362 -0.97539 0.000316424 -0.220487 -0.988458 -0.00136195 -0.151487 -0.840318 0.00138048 -0.542092 -0.915247 -0.00245948 -0.402886 -0.807696 5.35197e-05 -0.589599 -0.675752 -4.71068e-05 -0.737129 -0.473374 0.00264863 -0.880858 -0.626267 -0.00247744 -0.779605 -0.260358 0.00173206 -0.965511 -0.170233 0 -0.985404 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.143073 0.980302 -0.136153 -0.210726 0.89461 -0.394039 -0.0931392 0.980302 -0.174162 -0.0931389 0.980302 -0.174162 -0.250946 0.7921 -0.55642 -0.264314 0.828166 -0.494245 -0.375895 0.60386 -0.702891 -0.362384 0.547632 -0.754173 -0.423998 0.437756 -0.79284 -0.462744 0.192706 -0.865293 -0.462744 0.192706 -0.865293 -0.143072 0.980302 -0.136153 -0.406018 0.828166 -0.386381 -0.406017 0.828167 -0.386381 -0.604683 0.550663 -0.575438 -0.604682 0.550663 -0.575438 -0.710829 0.192706 -0.676451 -0.710829 0.192706 -0.676452 -0.650727 0.189465 -0.735294 -0.227613 0.189465 -0.955142 0.249176 0.189463 -0.949745 0.249178 0.189465 -0.949744 0.228927 0.431546 -0.87256 0.17975 0.547437 -0.817314 0.203568 0.597103 -0.775904 0.157436 0.784301 -0.600071 0.0906525 0.828504 -0.552597 0.115001 0.891426 -0.438332 0.050975 0.979618 -0.194294 0.0509757 0.979618 -0.194293 -0.227613 0.189464 -0.955142 -0.194523 0.543916 -0.816282 -0.194522 0.543917 -0.816282 -0.131495 0.823545 -0.551799 -0.131495 0.823545 -0.551799 -0.0465639 0.979618 -0.195398 -0.0465635 0.979618 -0.195398 -0.650728 0.189464 -0.735293 -0.556125 0.543916 -0.628395 -0.556124 0.543917 -0.628396 -0.375935 0.823545 -0.42479 -0.375934 0.823545 -0.42479 -0.133122 0.979618 -0.150423 -0.133122 0.979618 -0.150423 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.814394 0.252825 -0.522343 -0.516905 0.190439 -0.834591 -0.55272 0.255375 -0.793275 -0.474514 0.433419 -0.766149 -0.42157 0.599143 -0.680666 -0.445116 0.705385 -0.551638 -0.325589 0.7859 -0.525692 -0.237604 0.892396 -0.383632 -0.21623 0.964768 -0.149891 -0.105229 0.979827 -0.1699 -0.814393 0.252825 -0.522344 -0.602612 0.698189 -0.38651 -0.602612 0.698189 -0.38651 -0.223005 0.964267 -0.143033 -0.223005 0.964267 -0.143033 -0.471583 0 -0.881822 -0.471583 0 -0.881822 -0.724407 0 -0.689373 -0.724407 0 -0.689373 0.137525 0.979786 0.145283 0.425362 0.785583 0.449364 0.619646 0.433044 0.654608 0.674892 0.190244 0.712972 0.626646 0.255137 0.736356 0.28848 0.252575 0.923572 0.288481 0.252574 0.923572 -0.146951 0.252575 0.956353 -0.146951 0.252574 0.956353 -0.552452 0.252574 0.794357 -0.552453 0.252576 0.794356 -0.845438 0.252576 0.470574 -0.845438 0.252575 0.470575 0.550608 0.598736 0.581675 0.421267 0.705123 0.570382 0.213558 0.69781 0.683706 0.213558 0.69781 0.683706 -0.108785 0.69781 0.707974 -0.108786 0.69781 0.707974 -0.408973 0.69781 0.58805 -0.408972 0.697809 0.588051 -0.625866 0.697809 0.34836 -0.625866 0.69781 0.348357 0.310474 0.892203 0.327993 0.0913962 0.964918 0.246129 0.0790674 0.964195 0.253134 0.0790658 0.964195 0.253134 -0.0402765 0.964195 0.262119 -0.0402752 0.964195 0.262119 -0.151417 0.964195 0.217718 -0.151417 0.964195 0.217718 -0.231719 0.964195 0.128975 -0.231719 0.964195 0.128977 0.656497 0.251666 -0.711109 0.656497 0.251666 -0.711109 0.91305 0.251666 -0.320941 0.91305 0.251664 -0.320942 0.957051 0.251665 0.14394 0.95705 0.251667 0.143942 0.486786 0.69643 -0.527281 0.486786 0.696429 -0.527281 0.677018 0.69643 -0.237976 0.677018 0.696429 -0.237976 0.709644 0.696429 0.106732 0.709644 0.69643 0.106732 0.180534 0.963933 -0.195553 0.180534 0.963933 -0.195553 0.251086 0.963933 -0.0882583 0.251086 0.963933 -0.0882585 0.263186 0.963933 0.0395837 0.263187 0.963933 0.0395818 0.333215 0 -0.942851 0.253767 0.00656112 -0.967243 0.0943072 0 -0.995543 -0.108885 0 -0.994054 -0.231805 0.00732193 -0.972735 -0.719566 0 -0.694424 -0.662718 0.00638102 -0.748842 -0.529419 0 -0.84836 -0.346993 0 -0.937868 0.471796 0.195091 -0.859854 0.469398 0.258816 -0.844204 0.431432 0.442285 -0.786289 0.381634 0.608762 -0.695532 0.346489 0.707088 -0.616418 0.0938459 0.980785 -0.171035 0.129258 0.965912 -0.224293 0.212759 0.896872 -0.387756 0.292838 0.793354 -0.5337 0.932215 0.254057 0.257739 0.759807 0.254059 0.598454 0.759808 0.254058 0.598454 0.627795 0.601138 0.494476 0.576022 0.702601 0.417793 0.484208 0.787459 0.381381 0.207124 0.964617 0.163139 0.207124 0.964617 0.163139 0.932215 0.254059 0.25774 0.688276 0.700046 0.190296 0.688276 0.700045 0.190295 0.254122 0.964617 0.07026 0.254122 0.964617 0.07026 0.155037 0.980693 0.119182 0.136845 0.980693 0.139695 0.155038 0.980693 0.119182 0.351348 0.89644 0.270093 0.444946 0.830635 0.334765 0.188052 0.965579 0.179703 0.385506 0.830635 0.401783 0.42666 0.792628 0.435547 0.582288 0.554625 0.594417 0.549212 0.608092 0.573229 0.711396 0.441413 0.546873 0.663366 0.554425 0.502551 0.629556 0.607817 0.483961 0.483383 0.792629 0.371592 0.777654 0.19463 0.597808 0.777654 0.194628 0.597808 0.694645 0.194771 0.692483 0.676048 0.258225 0.69013 0.256629 0.965716 0.0391816 0.247033 0.965715 0.0798009 0.247034 0.965715 0.0798009 0.673959 0.70596 0.217714 0.67396 0.705959 0.217714 0.919356 0.258038 0.296986 0.919356 0.258038 0.296985 0.256629 0.965715 0.0391815 0.700139 0.70596 0.106896 0.700138 0.70596 0.106896 0.955068 0.258036 0.145818 0.955067 0.258038 0.145818 -0.25247 0.965836 0.0584797 -0.25247 0.965836 0.0584794 -0.25722 0.965836 0.0316059 -0.25722 0.965836 0.031606 -0.259259 0.965805 0.00222753 -0.25926 0.965805 0.00222764 -0.257604 0.965805 -0.0293369 -0.257604 0.965805 -0.029337 -0.250938 0.965683 -0.0669838 -0.250938 0.965683 -0.0669838 -0.689346 0.706617 0.159673 -0.689347 0.706615 0.159673 -0.702316 0.706615 0.0862975 -0.702316 0.706616 0.0862972 -0.707739 0.706448 0.00608092 -0.707738 0.706448 0.00608082 -0.703219 0.706448 -0.0800856 -0.70322 0.706447 -0.0800854 -0.684464 0.705781 -0.182706 -0.684462 0.705783 -0.182706 -0.941099 0.258484 0.217986 -0.941099 0.258484 0.217986 -0.958804 0.258484 0.117813 -0.958805 0.258483 0.117814 -0.966011 0.258369 0.0083005 -0.96601 0.258371 0.0083 -0.959841 0.258371 -0.109311 -0.959841 0.258372 -0.109311 -0.933482 0.257918 -0.249178 -0.933483 0.257916 -0.249178 -0.527679 0 -0.849444 -0.526541 -0.000145722 -0.85015 -0.842461 0.00014477 -0.538757 -0.84174 0 -0.539883 0.481028 -0.00660623 -0.87668 0.481061 0.00286272 -0.876683 0.481054 0.00154894 -0.876689 0.481039 0 -0.876699 0.481039 0 -0.876699 0.481046 0.00024325 -0.876695 0.481037 -0.000216152 -0.8767 0.988545 0 0.15093 0.972743 0.0310724 0.229796 0.951582 0 0.307396 0.792815 0 0.609463 0.792815 0 0.609463 0.699781 0 0.714357 0.699781 0 0.714357 0.785583 0 0.618756 0.785583 0 0.618756 0.96384 0 0.266483 0.96384 0 0.266483 0.988878 0 0.148726 0.988878 0 0.148726 0.943415 0 -0.331614 0.943415 0 -0.331614 0.67833 0 -0.734757 0.67833 0 -0.734757 -0.966171 0 -0.257904 -0.941121 -0.213583 -0.262055 -0.931021 -0.25537 -0.260741 -0.895707 -0.365773 -0.252821 -0.799047 -0.557 -0.226442 -0.517991 -0.842539 -0.147694 -0.974207 0 0.225655 -0.984496 -0.0221164 0.174005 -0.992535 0 0.121958 -0.999963 0 0.00859224 -0.998189 -0.0296368 -0.0523546 -0.993578 0 -0.113153 -0.966171 0 -0.257904 -0.873768 0 0.486343 -0.873768 0 0.486343 -0.570964 0 0.820975 -0.570964 0 0.820975 -0.151875 0 0.9884 -0.151875 0 0.9884 0.298147 0 0.95452 0.298147 0 0.95452 0.687446 0 0.726235 0.687446 0 0.726235 0.328158 0.173551 -0.928543 -0.341671 0.174462 -0.923485 -0.107214 0.174556 -0.978793 -0.70866 0.17344 -0.6839 -0.70866 0.173438 -0.6839 -0.653099 0.419772 -0.63028 -0.6152 0.533083 -0.580819 -0.573801 0.603414 -0.553754 -0.391781 0.838781 -0.378094 -0.450686 0.790317 -0.415069 -0.113841 0.98436 -0.134448 -0.188675 0.965012 -0.182083 -0.0185913 0.987132 -0.158826 0.23172 0.517576 -0.823663 0.222227 0.562173 -0.796603 0.240807 0.58783 -0.772313 -0.0168396 0.984148 -0.17655 -0.0287618 0.83834 -0.544388 0.00267439 0.914174 -0.405314 -0.037069 0.532514 -0.845609 -0.020843 0.596511 -0.802334 -0.0253162 -0.222843 -0.974526 0.0928485 0.1752 -0.980145 -0.0752836 0.983778 -0.162828 -0.0752828 0.983779 -0.162825 -0.229611 0.83705 -0.496614 -0.229611 0.837051 -0.496614 -0.355569 0.531175 -0.769041 -0.355569 0.531169 -0.769045 -0.409766 -0.215933 -0.886265 -0.521224 0.175268 -0.835229 -0.464421 0.173628 -0.868428 -0.713403 0.173634 -0.678901 -0.692096 0.256192 -0.67481 -0.466151 0.256193 -0.846799 -0.427938 0.420161 -0.800209 -0.375898 0.60385 -0.702898 -0.347243 0.703621 -0.619952 -0.289386 0.789581 -0.541127 -0.20234 0.903273 -0.378359 -0.133889 0.965528 -0.223226 -0.0839368 0.984032 -0.156955 -0.657361 0.42017 -0.625566 -0.577421 0.603856 -0.549493 -0.505103 0.703621 -0.499788 -0.444534 0.789576 -0.423035 -0.189741 0.965088 -0.180564 -0.189741 0.965088 -0.180565 -0.723011 0.513295 -0.462368 -0.413534 0.832366 -0.368993 -0.523412 0.72488 -0.447873 -0.680906 0.534436 -0.500745 -0.798343 0.173473 -0.576677 -0.226077 0.901407 -0.369263 -0.0972459 0.983542 -0.15228 -0.0507951 0.994691 -0.0894923 -0.428268 0.851653 -0.302114 -0.273043 0.855718 -0.439539 -0.310173 0.787628 -0.532386 -0.519859 0.171519 -0.836856 -0.519859 0.171519 -0.836856 -0.447652 0.529447 -0.72062 -0.465082 0.417219 -0.780786 -0.422532 0.599015 -0.680182 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.300196 0.946677 -0.116985 0.47056 0.772777 -0.425897 0.654745 0.482173 -0.582081 0.639823 0.51216 -0.572991 0.643687 0.497783 -0.581274 0.646797 0.497893 -0.577716 0.672044 0.473221 -0.569578 0.669495 0.483609 -0.563825 0.256808 0.916323 -0.30725 0.336025 0.887165 -0.316267 0.267556 0.921962 -0.28 0.26097 0.917165 -0.301169 0.258213 0.917608 -0.302193 0.258781 0.917812 -0.301088 0.265599 0.922812 -0.279062 0.280013 0.916671 -0.285144 0.312594 0.920529 -0.234333 0.303474 0.923958 -0.23282 0.322962 0.940766 -0.103217 0.325899 0.939798 -0.102808 0.325611 0.939933 -0.102491 0.442434 0.881219 -0.16645 0.545902 0.817327 -0.184305 0.540189 0.820545 -0.186823 0.61762 0.754663 -0.221426 0.66239 0.67171 -0.331732 0.51638 0.767456 -0.379952 0.668163 0.601636 -0.437713 0.500653 0.735127 -0.457093 0.614084 0.629902 -0.475525 0.320944 0.929524 -0.181604 0.335771 0.924385 -0.181026 0.394273 0.893927 -0.213176 0.359644 0.892893 -0.270921 0.366723 0.890085 -0.270672 0.336207 0.888041 -0.313605 0.326996 0.939488 -0.102161 0.300262 0.946652 -0.117013 0.355888 0.92414 -0.138959 0.341998 0.928305 -0.145904 0.420612 0.895914 -0.142913 0.390575 0.897563 -0.204526 0.50297 0.822734 -0.26482 0.402016 0.830624 -0.385288 0.407141 0.808278 -0.425351 0.466034 0.813911 -0.346932 0.464266 0.817653 -0.340442 0.510527 0.818539 -0.263356 0.602182 0.735023 -0.311639 0.63434 0.738751 -0.22773 0.661705 0.70849 -0.24533 0.629707 0.753451 -0.189157 0.315298 0.853932 -0.413989 0.00953315 0.724863 -0.688828 -0.282721 0.785983 -0.549818 -0.168238 0.752548 -0.636685 -0.187934 0.777744 -0.599829 -0.0732984 0.717182 -0.69302 0.390571 0.149963 -0.908276 0.331842 -0.05173 -0.941915 -0.0724393 0.199589 -0.977198 0.340399 0.670232 -0.659482 0.392133 0.424348 -0.816187 0.367979 0.392967 -0.842715 0.385462 0.165981 -0.907672 -0.00793943 0.257113 -0.966349 -0.0244572 -0.00365637 -0.999694 -0.3124 0.103127 -0.944336 0.200021 0.872663 -0.445478 0.142898 0.887814 -0.437454 0.12514 0.89821 -0.421377 0.0739439 0.916352 -0.393486 -0.585686 0.517857 -0.623535 -0.515997 0.516728 -0.683183 -0.482684 0.494193 -0.723042 -0.389781 0.495599 -0.776178 -0.347972 0.472822 -0.80954 -0.179126 0.478408 -0.859674 -0.1898 0.489923 -0.850853 -0.803174 0.174563 -0.569596 -0.733624 0.193838 -0.651324 -0.677253 0.158366 -0.718504 -0.587377 0.181675 -0.788659 -0.491604 0.129774 -0.861095 -0.430432 0.1651 -0.887395 -0.350212 0.158145 -0.923223 -0.242126 0.250112 -0.937453 0.0193352 0.149617 -0.988555 0.0399133 0.404473 -0.913679 0.110438 0.454138 -0.88406 0.13379 0.678298 -0.722504 0.276243 0.712737 -0.644744 0.25345 0.847722 -0.465972 0.273247 0.852582 -0.445466 0.432288 0.529647 0.729795 0.371349 0.927962 0.0314127 -0.0342546 0.945574 0.323599 -0.168942 0.947691 0.270816 -0.42361 0.810732 0.404064 0.324262 0.876714 0.355284 0.16242 0.96626 0.199903 0.134083 0.970622 0.199787 0.5116 0.656689 0.554099 0.298187 0.386247 0.872868 0.258525 0.41814 0.870818 0.22434 0.277993 0.934019 0.383329 0.0277905 0.923194 0.0681798 0.290424 0.954466 0.233461 0.0399656 0.971545 0.0964186 0.154934 0.983209 0.156769 0.414101 0.896629 0.105762 0.453243 0.885091 -0.299764 0.0766636 0.950928 -0.36038 0.121067 0.924916 -0.519341 0.0442303 0.853422 -0.544737 0.0912887 0.833623 -0.662308 0.113992 0.74051 -0.706546 0.141482 0.69338 -0.825004 0.0188145 0.564813 -0.856078 0.109699 0.505071 -0.123328 0.0644955 0.990268 0.125233 0.148248 0.980989 -0.0453148 0.283568 0.957881 0.00346475 0.445663 0.895194 -0.134742 0.542098 0.829442 -0.14232 0.561747 0.814975 -0.331836 0.523566 0.784706 -0.476317 0.607136 0.636009 0.324596 0.738639 0.590805 0.212264 0.813591 0.541308 0.133275 0.811128 0.569482 -0.0295456 0.909793 0.41401 -0.264668 0.753733 0.601529 -0.418611 0.826054 0.377359 -0.636982 0.602642 0.480704 -0.781358 0.356797 0.512031 -0.783924 0.391457 0.481896 -0.622388 0.314984 0.716532 -0.637892 0.389195 0.664546 -0.438435 0.269662 0.857355 -0.471612 0.378338 0.796519 -0.250914 0.229153 0.940495 -0.300963 0.363603 0.881598 -0.153869 0.257886 0.953844 -0.184521 0.107732 0.976906 -0.208465 0.1303 0.969311 0.655867 0.653114 0.378525 0.60117 0.798961 0.0160054 0.626492 0.77912 0.0219164 0.558173 0.819886 -0.127394 0.578216 0.813311 0.0647442 0.52379 0.851788 0.0100778 0.375515 0.863258 0.337305 0.484238 0.786901 0.382492 0.444496 0.699136 0.560028 0.429364 0.718072 0.54774 -0.634017 0.628101 0.451122 -0.470217 0.550766 0.689603 -0.266702 0.790529 0.551303 -0.0717227 0.672494 0.736619 0.0311628 0.705432 0.708092 0.168707 0.612761 0.77205 0.257253 0.603298 0.754886 0.298833 0.571508 0.76425 0.386567 0.558907 0.733613 0.572685 0.38557 0.723442 0.48122 0.433659 0.761818 0.580722 0.339667 0.739857 0.589151 0.62785 0.508632 0.696496 0.628472 0.34629 0.539443 0.769192 0.342556 0.56934 0.821683 0.0262318 0.544948 0.838339 0.014832 0.797973 0.12022 0.590582 0.952112 0.146777 -0.268216 0.46342 0.884921 -0.046438 0.55553 0.728726 0.400431 0.37583 0.92342 0.0777688 0.394438 0.915894 0.0745406 0.522575 0.843329 -0.125346 0.920241 0.060534 0.386643 0.952289 0.247469 0.178617 0.961883 0.175393 0.209807 0.961839 0.171345 0.213322 0.887748 0.422949 0.181705 0.878183 0.459906 0.131456 0.711774 0.698426 0.0746942 0.672389 0.737694 -0.0608386 0.477383 0.875154 -0.0788109 0.46597 0.0236339 0.884485 0.510237 0.136347 0.849157 0.509031 0.198562 0.837533 0.543702 0.294011 0.786096 0.534901 0.377016 0.756135 0.561091 0.449733 0.694922 0.541244 0.544707 0.640585 0.559522 0.594977 0.577008 0.471098 0.788282 0.395827 0.988608 0.136034 -0.0644186 0.963866 0.213534 -0.159267 0.894057 0.421256 -0.152332 0.887391 0.431715 -0.16174 0.710264 0.689379 -0.142413 0.66409 0.075038 0.743877 0.796882 0.123852 0.591304 0.791508 0.185322 0.582383 0.801008 0.270087 0.534265 0.783009 0.352235 0.512666 0.776833 0.486858 0.399374 0.769447 0.498337 0.399514 0.614036 0.747031 0.254764 0.671485 0.703057 0.234134 0.428982 0.902932 0.0262281 0.432628 0.901251 0.0241022 -0.707569 0.224186 -0.67014 -0.802912 0.161574 -0.573782 -0.00273668 0.606018 -0.795447 0.0535488 0.626606 -0.777494 -0.123081 0.58075 -0.804724 -0.166779 0.559151 -0.812118 -0.347346 0.483081 -0.803731 -0.542494 0.474212 -0.693414 -0.801675 0.164839 -0.574583 -0.775465 0.133119 -0.617198 -0.84979 0.051287 -0.52462 -0.831529 0.0627988 -0.55192 0.503767 0.65835 -0.55928 0.446308 0.659881 -0.604455 0.320315 0.667955 -0.671739 0.262327 0.659118 -0.704804 0.208477 0.655766 -0.725609 0.0962104 0.640338 -0.762044 -0.539034 0.358248 -0.762299 -0.47279 0.390565 -0.789892 -0.528921 0.491257 -0.692032 -0.2329 0.680063 -0.695178 -0.156833 0.70427 -0.692392 -0.0216514 0.765717 -0.642813 0.172255 0.800552 -0.573973 0.185235 0.803857 -0.565244 0.644915 0.738175 -0.197947 0.3804 0.788642 -0.483052 0.211204 0.897516 -0.387115 0.10724 0.884702 -0.453655 -0.223313 0.789911 -0.571115 -0.261967 0.766706 -0.586119 -0.582587 0.525996 -0.619613 -0.587714 0.519666 -0.620113 -0.815473 0.178012 -0.550741 -0.813491 0.183477 -0.551878 0.410495 0.909191 0.0697552 0.410694 0.908943 0.0717793 0.45914 0.774985 0.434268 0.459039 0.774437 0.435351 0.448267 0.586532 0.674564 0.428895 0.512066 0.744202 0.417422 0.428625 0.801273 0.370449 0.257082 0.892568 0.338555 0.176351 0.924273 0.312354 0.0853656 0.946122 0.359934 0.165709 0.918144 0.35993 0.165704 0.918146 0.482896 0.485372 0.728852 0.482908 0.485387 0.728835 0.532129 0.738282 0.414463 0.532173 0.738344 0.414295 0.496598 0.866692 0.0472876 0.496609 0.866709 0.0468626 0.379025 0.153962 0.912489 0.378855 0.153798 0.912587 0.538477 0.450733 0.711957 0.53812 0.450378 0.712451 0.616116 0.685015 0.388788 0.615868 0.684776 0.3896 0.594861 0.803633 0.0177225 0.594835 0.803636 0.0184478 -0.579693 0.148124 0.801259 -0.601571 0.105607 0.791808 -0.459744 0.405461 0.790087 -0.496273 0.358938 0.790491 -0.2762 0.658962 0.69963 -0.333368 0.612878 0.716412 -0.0405544 0.85539 0.516394 -0.121255 0.821649 0.556948 0.145396 0.934629 0.324545 0.126559 0.932002 0.33964 0.592722 0.70219 -0.394474 0.659041 0.577613 -0.481694 0.487913 0.852378 -0.188129 0.577798 0.765835 -0.282219 0.324297 0.943921 0.0620027 0.426828 0.903977 -0.025367 0.256607 0.950204 0.176818 0.564423 0.764936 -0.310323 0.626884 0.689664 -0.362463 0.415675 0.899938 -0.131631 0.490305 0.851496 -0.185892 0.212896 0.973801 0.0799176 0.290952 0.956238 0.0309202 -0.0273807 0.953743 0.299375 0.0431512 0.963963 0.262514 -0.27078 0.827994 0.491023 -0.216015 0.856239 0.469246 -0.478815 0.617071 0.624467 -0.441886 0.65216 0.615974 -0.627028 0.3636 0.688935 -0.604949 0.398073 0.689619 -0.711951 0.110002 0.69356 -0.700248 0.141135 0.69981 0.548084 0.802152 -0.236973 0.599808 0.754465 -0.266482 0.367938 0.925625 -0.088547 0.426339 0.896778 -0.118429 0.136584 0.987043 0.0842109 0.19508 0.979077 0.0578886 -0.124958 0.957139 0.261286 -0.0738465 0.967467 0.24198 -0.379717 0.826725 0.415141 -0.341115 0.848694 0.404178 -0.58949 0.615893 0.522663 -0.564226 0.642133 0.518955 -0.732011 0.364577 0.575537 -0.717649 0.390158 0.576851 -0.806423 0.112652 0.58051 -0.799672 0.135735 0.584894 0.538453 0.824267 -0.175079 0.576533 0.794889 -0.189107 0.335198 0.940259 -0.0596233 0.376878 0.923342 -0.0735056 0.0823876 0.993891 0.0734313 0.123108 0.990483 0.0615429 -0.195949 0.958106 0.208896 -0.161077 0.966354 0.200536 -0.460944 0.825242 0.326354 -0.435076 0.840837 0.322027 -0.674265 0.615024 0.408794 -0.657705 0.633276 0.407904 -0.814765 0.365603 0.449991 -0.805742 0.383365 0.451454 -0.883135 0.115207 0.454753 -0.879393 0.131258 0.457646 0.356013 0.850581 -0.386998 0.341064 0.863807 -0.370828 0.484603 0.663808 -0.569666 0.475053 0.679156 -0.559528 0.573398 0.41547 -0.706116 0.56876 0.429443 -0.701492 0.611408 0.137215 -0.779328 0.706284 0.342432 -0.619599 0.684484 0.143464 -0.714772 0.610131 0.147581 -0.778434 0.4263 0.867999 -0.25465 0.414065 0.875813 -0.247997 0.617384 0.682038 -0.391997 0.609511 0.691394 -0.387906 0.755118 0.428955 -0.495777 0.751298 0.437588 -0.494032 0.816979 0.439899 -0.372873 0.819928 0.433721 -0.373637 0.657238 0.695043 -0.291469 0.66336 0.688361 -0.293449 0.438932 0.879408 -0.184339 0.448461 0.873878 -0.187668 0.395411 0.860389 -0.321528 0.381409 0.87065 -0.310637 0.557392 0.673988 -0.484824 0.548399 0.686108 -0.478032 0.672279 0.422962 -0.607573 0.6679 0.434095 -0.604542 0.724661 0.148684 -0.672874 0.821332 0.142976 -0.552242 0.820308 0.149427 -0.552056 0.897069 0.145105 -0.417388 0.896302 0.149706 -0.417409 0.342024 0.613183 -0.712058 -0.960081 0.223415 -0.168316 -0.602641 0.160265 0.781754 0.572208 0.591019 -0.568572 0.545094 0.571744 -0.613173 0.12117 0.94399 0.306921 0.110389 0.60104 -0.791559 0.0155044 0.551729 -0.83388 -0.179995 0.433015 -0.883233 -0.300361 0.824332 -0.479854 -0.402376 0.835325 -0.374601 -0.301877 0.936279 -0.179586 0.111176 0.993711 0.0133362 0.0223159 0.750972 -0.659957 -0.293544 0.706529 -0.643933 -0.328564 0.744867 -0.580705 -0.842092 0.154756 0.516654 -0.806556 0.476157 -0.350344 -0.843985 0.485335 -0.228342 -0.803258 0.587405 -0.0986474 -0.823105 0.56789 0.000310657 -0.740607 0.651625 0.163971 -0.734089 0.64482 0.212888 -0.627125 0.687197 0.366708 -0.623311 0.680778 0.384739 -0.467889 0.683271 0.560553 -0.716128 0.119914 0.687591 -0.623098 0.188009 0.759211 -0.581522 0.356249 0.731382 -0.450093 0.400714 0.798026 -0.304552 0.671166 0.675859 -0.869503 0.272919 -0.411678 -0.880914 -0.0831287 -0.465918 -0.739594 0.397715 -0.542976 -0.125516 0.588258 -0.798873 -0.328017 0.417817 -0.847251 -0.460191 0.436071 -0.773348 -0.533912 0.339894 -0.774216 -0.680123 0.297974 -0.669809 -0.782948 -0.022994 -0.621662 -0.852825 0.425437 -0.30281 -0.976817 0.011704 -0.213755 -0.993148 0.114367 0.0240303 -0.990653 0.050812 0.126591 -0.957314 0.149785 0.247211 -0.939115 0.108885 0.325896 -0.848556 0.14165 0.509793 0.1613 0.98074 0.110147 0.324132 0.941437 -0.0929276 0.325127 0.942226 -0.0806431 0.504964 0.797675 -0.329738 0.470903 0.77264 -0.425766 0.590351 0.610717 -0.527741 0.596543 0.627788 -0.500019 0.0240965 0.965585 0.25897 0.147098 0.982124 0.117453 -0.11909 0.97506 -0.187286 0.112474 0.938972 -0.325087 0.115473 0.934082 -0.337871 0.379809 0.79456 -0.47373 0.292074 0.709238 -0.641618 0.548899 0.572679 -0.608891 0.543372 0.549323 -0.634815 0.545455 0.55152 -0.631114 0.30144 0.577048 -0.759045 0.312226 0.713675 -0.627044 0.0513086 0.77904 -0.624871 0.0142133 0.842965 -0.537781 -0.246893 0.846045 -0.472495 -0.10063 0.976517 -0.190496 -0.156815 0.975382 -0.155044 -0.202557 0.979262 0.00409141 -0.583361 0.622243 -0.522019 -0.626944 0.651151 -0.42772 -0.585973 0.756098 -0.291465 -0.614305 0.759517 -0.213923 -0.525121 0.850142 -0.0388258 -0.524263 0.851556 0.000352894 -0.409526 0.896843 0.167214 -0.408038 0.894628 0.182062 -0.245205 0.897152 0.367414 -0.247437 0.900896 0.356597 -0.0605894 0.849514 0.524075 0.229013 0.600891 -0.765822 0.10435 0.58611 -0.803484 0.0147564 0.660966 -0.750271 -0.205892 0.588329 -0.78197 -0.299926 0.62807 -0.718034 -0.472467 0.517324 -0.713548 -0.59055 0.526538 -0.611563 -0.696759 0.410087 -0.588519 -0.813297 0.371613 -0.447718 -0.930161 0.0699833 -0.360421 -0.94161 0.296741 -0.159106 -0.958693 0.283703 -0.020517 -0.92406 0.371825 0.0886529 -0.922989 0.329914 0.198112 -0.85653 0.396636 0.330206 -0.806486 0.356221 0.471898 -0.758387 0.40554 0.51028 -0.616673 0.409064 0.672593 -0.471834 0.690837 0.54783 -0.28786 0.639768 0.712625 -0.0722127 0.867742 0.491741 0.905113 0 -0.425172 0.783846 -0.484335 -0.388594 0.790064 0.316018 -0.525293 0.663603 -0.525393 -0.532535 0.742486 3.51964e-06 -0.669862 0.627646 0 -0.778499 0.578088 -0.269178 -0.770297 0.68716 -2.4384e-05 -0.726506 0.279774 0 0.960066 0.279774 0 0.960066 0.279774 1.77173e-07 0.960066 0.279774 -8.21372e-08 0.960066 0.921209 0.0214818 0.388474 0.450543 0.0773123 0.889401 0.465029 0 0.885296 0.76965 -0.0635089 0.6353 0.75519 -0.303808 0.580852 0.662387 -0.0215235 0.748852 0.872865 -0.453215 0.180836 0.947248 -0.224404 0.228833 0.990921 0.118053 -0.0643397 0.918001 -0.361921 -0.162134 0.96261 0 -0.270892 -0.927903 0 -0.372822 -0.943622 -0.0028204 -0.331013 -0.991368 0.00202787 -0.131092 -0.999592 -0.00514976 0.0280897 -0.991022 0.00116525 0.133695 -0.941208 -0.000973581 0.337825 -0.908906 -0.00516898 0.416968 -0.853805 0.00117821 0.520592 -0.722145 -0.00124005 0.691741 -0.699865 -0.00304022 0.714269 -0.61647 0 0.787378 -0.860593 0 0.509293 -0.888461 0.0677739 0.453921 -0.820702 -0.000934722 0.571356 -0.68357 0.00186056 0.729883 -0.721369 0.0526382 0.690548 -0.628749 0 0.777608 -0.876699 0 -0.481039 -0.876699 -1.22637e-07 -0.481039 -0.8767 0 -0.481038 -0.876699 -1.91798e-07 -0.481039 -0.876699 -1.96556e-08 -0.481039 -0.825553 0 0.564325 -0.84886 0.00672525 0.528574 -0.672277 -0.00226913 0.740297 -0.603892 -0.00698003 0.797035 -0.522783 0.00291048 0.852461 -0.308334 -0.00233445 0.951275 -0.22498 -0.00941994 0.974318 -0.243882 -0.00767014 0.969775 -0.130765 -5.58449e-05 0.991413 0.0356009 5.37202e-05 0.999366 0.118814 -0.00535004 0.992902 0.199647 0 0.979868 0.333375 0 -0.942794 -0.319476 -0.00338849 -0.947588 -0.0824744 0.00850003 -0.996557 -0.018734 -0.0426987 -0.998912 0.38239 0.0584381 -0.922151 -0.504676 -0.0649621 -0.860861 -0.454439 -0.0124679 -0.890691 -0.692896 0.00478189 -0.721022 -0.772569 -0.0351019 -0.63396 -0.822028 0 -0.569447 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.0629202 0.980398 -0.186712 -0.0539731 0.988471 -0.141463 -0.171986 0.82809 -0.533561 -0.155559 0.893086 -0.422136 -0.222984 0.703423 -0.674888 -0.272456 0.549312 -0.789952 -0.283032 0.447024 -0.848565 -0.301351 0.332334 -0.893723 -0.134159 0.348265 -0.927746 -0.130554 0.447036 -0.884938 -0.113498 0.549323 -0.827866 -0.10573 0.703435 -0.702851 -0.0739577 0.828675 -0.554822 -0.0675827 0.893749 -0.443448 -0.023531 0.980469 -0.195259 -0.0215336 0.988584 -0.149126 0.327762 0.319715 -0.889019 0.789397 0.263197 -0.554598 0.67115 0.263743 -0.692819 0.909112 0.190638 -0.370367 0.831998 0.307154 -0.461991 0.789203 0.43025 -0.438228 0.70969 0.545167 -0.446243 0.701212 0.597239 -0.389367 0.542255 0.784409 -0.301102 0.116364 0.979582 -0.163945 0.328859 0.822908 -0.46333 0.328857 0.822907 -0.463333 0.486769 0.541025 -0.685819 0.48677 0.541027 -0.685817 0.530073 0.401588 -0.746827 0.488914 0.317803 -0.812382 0.03413 0.979582 -0.198125 0.096456 0.822906 -0.55993 0.0964587 0.822907 -0.559928 0.142777 0.541027 -0.828797 0.142775 0.541026 -0.828798 0.15065 0.461018 -0.87451 0.11793 0.344635 -0.9313 0.337779 0.865228 -0.370522 0.496732 0.822908 -0.275826 0.175764 0.979582 -0.0975987 -0.209366 0.591837 -0.778392 -0.284459 0.459437 -0.841428 -0.188388 0.574172 -0.796766 -0.0820903 0.724214 -0.684672 -0.0780729 0.726445 -0.682775 -0.0774115 0.719523 -0.690141 -0.0746357 0.719951 -0.690001 -0.127764 0.460128 -0.878612 -0.0754549 0.714257 -0.695804 -0.0825109 0.721354 -0.687634 -0.0756745 0.645199 -0.760257 -0.114688 0.66233 -0.740382 -0.128981 0.457526 -0.879792 -0.231928 0.427881 -0.873572 -0.289551 0.476041 -0.830388 -0.673203 0.191098 -0.714338 -0.513486 0.287113 -0.80864 -0.49172 0.33097 -0.805401 -0.468947 0.436014 -0.768102 -0.367117 0.550367 -0.749881 -0.323549 0.94407 -0.0636191 -0.173758 0.828181 -0.532846 -0.319935 0.789323 -0.524033 -0.415481 0.603535 -0.68053 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.635537 0.251665 0.729902 0.635537 0.251666 0.729902 0.219795 0.251666 0.942526 0.219795 0.251665 0.942526 -0.247115 0.251665 0.935734 -0.247114 0.251665 0.935735 0.471244 0.69643 0.541215 0.471245 0.69643 0.541215 0.162976 0.69643 0.698874 0.162976 0.69643 0.698874 -0.183233 0.69643 0.693838 -0.183234 0.69643 0.693837 0.174771 0.963933 0.200721 0.174771 0.963933 0.200721 0.0604432 0.963933 0.259192 0.0604425 0.963933 0.259192 -0.0679561 0.963933 0.257324 -0.0679559 0.963933 0.257324 0.967044 0.251666 -0.0386168 0.967043 0.251666 -0.0386165 0.872563 0.251666 0.418685 0.872564 0.251665 0.418684 0.574957 0.251665 0.778517 0.574955 0.251667 0.778518 0.717054 0.69643 -0.0286337 0.717053 0.69643 -0.0286335 0.646998 0.69643 0.31045 0.646997 0.69643 0.310451 0.426324 0.69643 0.577264 0.426324 0.69643 0.577263 0.265934 0.963933 -0.0106193 0.265934 0.963933 -0.0106189 0.239952 0.963933 0.115137 0.239952 0.963933 0.115137 0.158111 0.963933 0.21409 0.158113 0.963933 0.214089 -0.241672 0.375302 -0.894842 0.0930429 0.657773 -0.747447 0.758839 0.0312656 -0.650527 0.604488 0.147369 -0.782864 0.634337 0.0768731 -0.769225 -0.0987246 0.554499 -0.826308 -0.10657 0.55117 -0.827559 0.00396424 0.656943 -0.75393 0.0915955 0.691986 -0.716077 0.26819 0.513842 -0.814887 0.440723 0.56588 -0.696809 0.66239 0.186919 -0.725466 0.475375 0.408078 -0.779417 0.234948 0.242334 -0.941315 0.15722 0.3215 -0.933766 -0.193247 0.239475 -0.951476 -0.118111 0.154389 -0.980925 0.552042 0.164231 -0.817482 0.405795 0.0620253 -0.911857 0.242983 0.187178 -0.9518 0.195594 0.122332 -0.973025 -0.036442 0.0722666 -0.996719 0.898498 -0.0464669 -0.436512 0.832596 0.146117 -0.534261 0.844189 0.0851191 -0.529244 0.753504 0.244909 -0.610124 0.650379 0.474801 -0.592935 0.448484 0.185385 -0.874354 0.275526 0.567261 -0.77608 0.124064 0.465021 -0.876563 -0.088436 0.565277 -0.820147 -0.0169066 0.575151 -0.817872 0.730951 0.321738 -0.601826 0.874425 0.164946 -0.45626 0.938459 0.0554543 -0.34091 0.91291 0.11641 -0.391208 0.905095 0.0755757 -0.41844 0.907202 0.0744086 -0.414062 0.423674 0.509049 -0.749246 0.0865191 0.429282 -0.899017 0.122909 0.616864 -0.777414 0.081804 0.617412 -0.782375 0.125778 0.432032 -0.893045 0.419959 0.350788 -0.837008 0.45022 0.503341 -0.73753 0.719507 0.327463 -0.612437 0.330319 0.353345 -0.875235 0.489662 0.332746 -0.805923 0.711589 0.224789 -0.665666 0.669758 0.233296 -0.704981 0.788201 0.179253 -0.588734 0.942275 0.191623 -0.27459 0.929188 0.258813 -0.263867 0.862552 0.439116 -0.251358 0.763046 0.606891 -0.22236 0.681237 0.707081 -0.189612 0.188409 0.980555 -0.0549045 0.250249 0.965907 -0.0663326 0.42564 0.896351 -0.124036 0.586245 0.791916 -0.170838 -0.464648 0.258819 0.846826 -0.464648 0.258818 0.846827 -0.340146 0.707107 0.61992 -0.340146 0.707107 0.619919 -0.124502 0.965926 0.226907 -0.124502 0.965926 0.226907 0.5683 0.25855 0.781145 0.197887 0.965635 0.168495 0.162668 0.965635 0.202704 0.121644 0.965635 0.229679 0.121644 0.965635 0.229679 0.331691 0.705521 0.626276 0.331691 0.705521 0.626276 0.452222 0.25774 0.853853 0.452222 0.25774 0.853853 0.162668 0.965635 0.202704 0.443554 0.705521 0.552721 0.443554 0.705521 0.552721 0.604733 0.25774 0.75357 0.661117 0.0532007 0.748395 0.197887 0.965635 0.168495 0.539586 0.705521 0.459441 0.539587 0.705521 0.459442 0.735664 0.257739 0.626395 0.735663 0.257739 0.626394 -0.752224 0.25761 -0.606462 -0.752224 0.25761 -0.606462 -0.202435 0.9656 -0.163209 -0.202436 0.9656 -0.163209 -0.174045 0.965824 -0.192072 -0.174045 0.965824 -0.192072 -0.410426 0.791454 -0.452936 -0.486455 0.706905 -0.513466 -0.551861 0.70533 -0.444925 -0.551862 0.705329 -0.444926 -0.659071 0.191335 -0.727335 -0.657502 0.258591 -0.707687 -0.603459 0.438555 -0.665963 -0.533987 0.606291 -0.589295 -0.463421 0.230158 -0.855727 -0.492609 0.116145 -0.862465 -0.316139 0.431357 -0.844977 -0.289116 0.452863 -0.843403 -0.289209 0.453308 -0.843131 -0.524449 0.124409 -0.842304 -0.53716 0.106653 -0.836711 -0.574904 0.0729518 -0.814962 -0.198143 0.554639 -0.808155 -0.197808 0.555141 -0.807893 -0.155714 0.56983 -0.806875 -0.327193 0.208445 -0.921681 -0.426793 0.00881951 -0.904306 -0.413309 0.14154 -0.899523 -0.464552 0.162774 -0.870457 -0.375535 0.354159 -0.856472 -0.364878 0.347711 -0.863691 -0.628864 0.253707 0.734958 -0.628863 0.253706 0.734959 -0.870484 0.253706 0.421772 -0.870484 0.253708 0.42177 -0.966532 0.253707 0.0380483 -0.966532 0.253708 0.038047 -0.900945 0.253708 -0.352037 -0.900946 0.253707 -0.352036 -0.464596 0.699518 0.542978 -0.464596 0.699517 0.54298 -0.643103 0.699517 0.311599 -0.643103 0.699518 0.311598 -0.714063 0.699517 0.0281086 -0.714063 0.699517 0.0281096 -0.665608 0.699517 -0.26008 -0.665609 0.699517 -0.260079 -0.171648 0.964517 0.200607 -0.171649 0.964517 0.200606 -0.237599 0.964517 0.115122 -0.237599 0.964517 0.115123 -0.263815 0.964517 0.0103853 -0.263815 0.964517 0.0103853 -0.245913 0.964517 -0.0960879 -0.245912 0.964517 -0.0960888 -0.93142 0 -0.363945 -0.93142 0 -0.363945 -0.999226 0 0.0393353 -0.999226 0 0.0393353 -0.899928 0 0.436039 -0.899928 0 0.436039 -0.650136 0 0.759818 -0.650136 0 0.759818 -0.428975 0 -0.903316 -0.44411 -0.0160864 -0.895828 -0.534205 0.00389239 -0.845346 -0.625755 -0.0198823 -0.779766 -0.605371 -0.043094 -0.794776 -0.630969 -0.0237156 -0.775445 -0.778499 0 -0.627646 -0.778499 0 -0.627646 -0.671477 0 -0.741026 -0.481039 0 0.876699 -0.481039 0 0.876699 0.960066 1.04597e-07 -0.279774 0.960066 0 -0.279774 0.960066 -7.43664e-08 -0.279774 0.960066 0 -0.279774 0.896773 0 -0.442492 0.763769 -0.037148 -0.64442 0.4103 0.00344628 -0.911944 0.623015 -0.00661666 -0.782182 0.636559 -0.00917298 -0.771174 0.891988 0.013611 -0.451853 0.202712 -0.0134639 -0.979146 0.234811 -0.00823042 -0.972006 -0.0358234 0.00462606 -0.999347 -0.173916 -0.0078222 -0.984729 -0.269077 0 -0.963119 0.761387 0 0.648298 0.729716 0.0214795 0.683414 0.662054 0 0.749456 0.588304 0 0.80864 0.509176 0.0214795 0.860394 0.468035 0 0.88371 0.594078 0 0.804408 0.594078 0 0.804408 0.901582 0 0.432609 0.901582 0 0.432609 0.999204 0 -0.039901 0.999204 0 -0.039901 -0.255333 0 0.966853 -0.255333 0 0.966853 0.227104 0 0.97387 0.227104 0 0.97387 0.656673 0 0.754176 0.656673 0 0.754176 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.82431 0.566122 -0.00444982 0.880385 0.471308 -0.0528409 0.880437 0.471629 -0.0489456 0.876183 0.478749 -0.0557108 0.781887 0.622927 -0.0247806 0.881103 0.469677 -0.0553352 0.821663 0.569962 0.003647 0.836698 0.546476 -0.0360582 0.746614 0.664574 -0.0301504 0.799157 0.600845 0.0182436 0.673876 0.73854 -0.0212164 0.610775 0.791427 0.0244318 0.530274 0.84687 -0.0402661 0.499431 0.866134 -0.0195242 0.391022 0.920095 -0.0229612 0.349122 0.936882 -0.0191438 0.341809 0.939589 -0.0184425 0.33259 0.942911 -0.0174186 0.322515 0.946427 -0.0161545 0.346069 0.938009 -0.0193607 0.364779 0.930506 -0.0330748 0.723614 0.689663 -0.0273542 0.573106 0.818959 0.0292605 0.675943 0.734697 -0.0576316 0.449087 0.892571 0.0404733 0.525911 0.850443 -0.0127771 0.443586 0.896189 -0.00871521 0.434091 0.900731 -0.0157636 0.390579 0.918544 -0.0610295 0.341854 0.939576 -0.0182371 0.544037 0.837245 -0.0551814 0.541672 0.837994 -0.0660155 0.668986 0.740605 -0.0629409 0.630647 0.769788 -0.0985424 0.634386 0.766921 -0.0968814 0.368959 0.926957 -0.0679782 0.446938 0.893162 -0.0500746 0.542884 0.837616 -0.0606264 0.540711 0.838907 -0.0621769 0.661424 0.74739 -0.0626667 0.619212 0.778678 -0.101176 0.626811 0.773198 -0.0962905 0.330471 0.941872 -0.0605532 0.323249 0.945128 -0.0473655 0.332013 0.941047 -0.0647882 0.340197 0.939924 -0.0284498 0.353388 0.935134 -0.0253286 0.396211 0.91783 -0.0246037 0.499862 0.865967 -0.015465 0.433708 0.900851 -0.0190884 0.383701 0.905905 0.17919 0.602004 0.79549 -0.0691868 0.51851 0.854895 0.0173714 0.513109 0.857863 -0.0280989 0.393387 0.918829 -0.0316235 0.392245 0.919093 -0.0375865 0.334271 0.941899 -0.0329934 0.337042 0.940365 -0.0459992 0.330923 0.941635 -0.0617586 0.331303 0.941549 -0.0610225 0.323868 0.944918 -0.0473322 0.3902 0.919557 -0.0464707 0.392506 0.918999 -0.0371431 0.553044 0.831749 -0.0483297 0.567644 0.821151 0.0590816 0.618349 0.784749 -0.0425797 0.620241 0.783975 -0.0261492 0.461824 0.881433 -0.0989617 0.260365 0.135398 -0.955969 0.241286 0.7815 -0.57536 0.227718 0.503096 -0.83369 0.142702 0.494981 -0.857106 0.120918 0.184116 -0.975439 0.0263442 0.156981 -0.98725 0.446882 0.490923 -0.747858 0.476848 0.173501 -0.861692 0.446283 0.159728 -0.880522 0.676185 0.694174 -0.246771 0.838651 0.437783 -0.324053 0.839766 0.419243 -0.345004 0.912006 0.148415 -0.382386 0.907475 0.119802 -0.402662 0.783316 0.158454 -0.601089 0.319678 0.917257 -0.237582 0.304191 0.163296 -0.938511 0.301896 0.477633 -0.825061 0.441136 0.495171 -0.748469 0.393372 0.730434 -0.558324 0.437871 0.741383 -0.508547 0.351649 0.905986 -0.235653 0.392454 0.896767 -0.204425 0.453165 0.878162 -0.15321 0.268737 0.929524 -0.25252 0.267429 0.767081 -0.583154 0.136409 0.787726 -0.600733 0.071369 0.520425 -0.85092 -0.00427075 0.515723 -0.856745 -0.0799931 0.193758 -0.977783 -0.169433 0.172244 -0.970373 0.453663 0.873668 -0.175771 0.607433 0.739107 -0.291111 0.566584 0.700603 -0.43375 0.676587 0.463551 -0.572146 0.655804 0.423963 -0.624641 0.698427 0.199845 -0.687213 0.646022 0.117778 -0.754178 0.150591 0.143482 0.978129 0.26105 0.947362 0.185361 0.576338 0.192494 0.794217 0.638712 0.119131 0.760168 0.728847 0.180364 0.660493 0.806599 0.156004 0.570141 0.379997 0.064139 0.922761 0.471495 0.136098 0.871304 0.515107 0.191713 0.835411 0.481266 0.178742 0.858158 0.469744 0.387805 0.793062 0.584331 0.494372 0.643547 0.584806 0.496785 0.641254 0.256843 0.948454 0.185651 0.204707 0.892981 0.40085 0.172165 0.819016 0.547333 0.0810025 0.815561 0.572973 0.0133722 0.645351 0.763769 -0.044857 0.601141 0.797883 -0.0760794 0.489971 0.868412 -0.132337 0.428919 0.893597 -0.159682 0.32056 0.933672 -0.221391 0.239034 0.945436 -0.232908 0.148424 0.961106 -0.291553 0.0375293 0.955818 0.45463 0.885139 0.0992006 0.773251 0.121803 0.622292 0.710508 0.449555 0.541368 0.580215 0.492204 0.648911 0.483267 0.752189 0.447957 0.547462 0.705443 0.450151 0.389583 0.907193 0.158825 0.401562 0.90226 0.157083 0.441017 0.891066 0.107265 0.669578 0.686009 0.284707 0.628476 0.717121 0.301257 0.770219 0.481574 0.418149 0.794298 0.459949 0.396909 0.876416 0.144827 0.459261 0.860831 0.166503 0.480882 0.323812 0.927438 0.187096 0.32687 0.926739 0.185231 0.364353 0.77719 0.513053 0.301762 0.771943 0.559503 0.311507 0.601156 0.735918 0.271145 0.552171 0.788408 0.26978 0.454875 0.848709 0.223053 0.381697 0.89697 0.219756 0.297851 0.928974 0.167961 0.201859 0.964905 0.162959 0.107688 0.980738 -0.0532392 0.0843842 0.99501 -0.108234 0.247688 -0.962775 -0.18942 0.171041 -0.966884 -0.227189 0.0791163 -0.970632 -0.159695 0.154652 -0.974977 -0.189035 0.172441 -0.966711 0.0181903 0.50026 -0.865684 0.141623 0.545185 -0.826266 0.318416 0.710727 -0.627279 0.316377 0.710013 -0.629116 0.49651 0.822591 -0.277167 0.440246 0.823862 -0.356979 0.0197854 0.404206 -0.914454 0.0873944 0.462571 -0.882264 0.0194995 0.504225 -0.863352 0.234778 0.760198 -0.605787 0.228972 0.757561 -0.611288 0.413223 0.88288 -0.223091 0.379988 0.887091 -0.262065 0.313359 0.91816 -0.242464 0.308406 0.913904 -0.263942 0.157904 0.79161 -0.590271 0.152083 0.781518 -0.605062 -0.0292889 0.523237 -0.851684 -0.0284738 0.525232 -0.850483 -0.204619 0.178427 -0.962442 -0.202693 0.184764 -0.961654 0.602368 0.623371 0.498559 0.782504 0.605612 0.144641 0.0820548 0.4667 0.880601 -0.404733 0.0784966 0.91106 -0.450831 0.0942795 0.887617 -0.455239 0.0653711 0.887966 -0.406666 0.199544 0.891518 -0.37634 0.181309 0.908568 -0.37856 0.170023 0.909827 -0.355821 0.177558 0.917532 -0.336157 0.159692 0.928169 -0.197214 0.221293 0.955058 0.435105 0.845223 0.310292 0.701911 0.703018 0.1144 0.487078 0.837458 0.24783 0.590361 0.747523 0.304439 0.629197 0.73054 0.265375 0.70669 0.637 0.307929 0.733578 0.620331 0.277583 0.155447 0.72676 0.669072 0.199404 0.743002 0.638894 -0.0909371 0.525678 0.845809 0.0549823 0.592487 0.803701 -0.147636 0.453928 0.878723 -0.0615027 0.37522 0.924893 -0.00798739 0.399692 0.916615 0.813464 0.580375 0.037966 0.813082 0.579706 0.0532676 0.751922 0.655361 0.071521 0.714257 0.697993 0.0514067 0.671643 0.73266 0.11002 0.589474 0.807358 0.026341 0.531359 0.83911 0.116413 0.437006 0.897147 0.0644383 0.197763 0.530032 0.824594 0.139896 0.51263 0.847136 0.404604 0.626081 0.666572 0.334789 0.617456 0.711803 0.516519 0.665798 0.538444 0.357668 0.816764 0.452737 0.306819 0.809939 0.499861 -0.354964 0.29008 0.888738 -0.2468 0.475833 0.8442 -0.18265 0.579949 0.793914 -0.128795 0.637314 0.759765 0.0350598 0.797702 0.602032 0.0702833 0.820291 0.567612 0.169708 0.88973 0.423768 0.191584 0.898922 0.393998 0.296877 0.92573 0.234283 0.310399 0.925995 0.214908 0.527017 0.767106 -0.365789 -0.885913 0.101172 -0.452683 0.275701 0.941656 -0.193063 -0.956468 0.1086 -0.270878 -0.94948 0.152739 -0.274151 -0.862923 0.386916 -0.325054 -0.698491 0.627831 -0.343421 -0.799705 0.49718 -0.336577 -0.886551 0.346456 -0.306587 -0.130821 0.948507 -0.288479 -0.114871 0.952593 -0.281728 0.410326 0.899087 -0.15256 0.610149 0.789614 -0.0650237 0.795239 0.601776 -0.0738909 0.749036 0.649214 -0.13216 0.636052 0.743974 -0.204794 0.527999 0.798395 -0.289451 0.661067 0.748256 -0.055699 0.459961 0.879093 -0.125022 0.511869 0.804261 -0.301918 0.17581 0.889852 -0.421015 0.39635 0.799405 -0.451507 -0.291098 0.899112 -0.326894 -0.509898 0.795069 -0.328435 -0.435809 0.830628 -0.346596 -0.692956 0.63472 -0.34197 -0.62515 0.546839 -0.556915 -0.920924 0.0876236 -0.379765 -0.917105 0.105594 -0.384407 -0.811549 0.321024 -0.488191 -0.796245 0.35081 -0.492876 -0.708346 0.465525 -0.530596 -0.356746 0.647216 -0.67368 -0.214136 0.758539 -0.615438 0.0210311 0.806757 -0.590508 0.0263127 0.809864 -0.586028 0.189274 0.832135 -0.521274 -0.572503 0.605596 -0.552715 -0.197322 0.798317 -0.568994 -0.394659 0.777889 -0.489011 -0.0279675 0.889188 -0.456686 -0.0861715 0.89436 -0.43897 0.232051 0.899086 -0.371209 0.18909 0.954543 -0.230418 0.107282 0.967566 -0.228705 -0.97085 0.226154 0.0793966 -0.973853 0.124121 -0.190275 0.546959 0.835347 -0.0550575 0.603804 0.796557 -0.0302857 0.585525 0.809188 -0.0487348 0.550031 0.832598 -0.0651599 0.401588 0.90999 -0.103175 0.546601 0.835993 -0.0484103 0.261683 0.958072 -0.116707 0.314355 0.943583 -0.10408 0.0880591 0.987977 -0.127075 -0.136081 0.975644 -0.17205 0.032071 0.99148 -0.126251 -0.321839 0.931401 -0.170035 -0.27165 0.949058 -0.159674 -0.539777 0.824658 -0.169058 -0.554821 0.814117 -0.171428 -0.732129 0.661419 -0.162826 -0.778175 0.605659 -0.166196 -0.833014 0.530696 -0.156363 -0.922095 0.360622 -0.140332 -0.915223 0.376266 -0.144189 -0.994407 -0.063577 -0.0843368 -0.990003 0.0518326 -0.131176 0.546944 0.835472 -0.0532732 0.452578 0.889916 -0.0567761 0.313887 0.948937 -0.0315207 0.211035 0.977135 -0.025898 0.031242 0.999455 -0.0106413 -0.0155777 0.999797 -0.0128188 -0.27288 0.961837 0.0201447 -0.317245 0.948147 0.0192861 -0.556593 0.829782 0.0408178 -0.520936 0.852477 0.043692 -0.780889 0.622376 0.0534834 -0.775602 0.628867 0.054479 -0.923249 0.376174 0.0781297 -0.990167 0.126056 0.0606635 -0.990982 0.117291 -0.0647872 0.476325 0.879246 -0.00637926 0.988136 0.150134 -0.0323528 0.974681 0.148885 -0.166825 0.984137 0.148962 -0.0963583 0.943724 0.30561 -0.126445 0.889756 0.440542 -0.119398 0.890093 0.439872 -0.119361 0.710227 0.697432 -0.0957376 0.7115 0.696139 -0.0957055 0.522711 0.852092 -0.0266854 0.988421 0.146716 0.0387149 0.95424 0.299003 0.00474505 0.899713 0.436482 -0.000380973 0.896698 0.442641 -0.00136525 0.720895 0.692946 -0.0116413 0.7151 0.698905 -0.0128226 0.469103 0.882875 -0.0217946 0.466669 0.882156 -0.0634135 0.469144 0.88084 -0.0634423 0.977568 0.139725 0.157599 0.976142 0.152129 0.15493 0.893003 0.435953 0.111766 0.890211 0.442077 0.10997 0.716035 0.696026 0.0533003 0.71554 0.696552 0.0530836 0.472116 0.881488 -0.00925131 0.476443 0.879171 -0.00774454 0.939275 0.138911 0.313794 0.937736 0.160901 0.307834 0.866792 0.435457 0.243 0.859674 0.453166 0.235801 0.703775 0.695357 0.145528 0.693112 0.707468 0.138146 0.473848 0.879884 0.0356832 0.461842 0.88649 0.0289515 0.817531 0.574299 -0.0427136 -0.389418 0.718914 -0.575775 -0.811151 0.399776 -0.426865 0.0761776 0.47588 0.876205 0.338218 0.896344 -0.286665 0.35512 0.909094 -0.217804 0.616014 0.787078 0.0321813 0.812409 0.572713 -0.109508 0.812484 0.572675 -0.109144 0.603754 0.764606 -0.22552 0.626575 0.75665 -0.186774 0.71749 0.686211 -0.119678 0.553966 0.75804 -0.344234 0.37052 0.810809 -0.453105 0.381403 0.824749 -0.417517 -0.129505 0.608926 0.782584 0.167904 0.762671 0.624613 0.102001 0.865369 0.490645 0.393737 0.854454 0.33894 0.350235 0.920465 0.173435 0.367311 0.925433 0.0930368 0.321364 0.946782 0.0181211 0.316873 0.936963 -0.14728 -0.685426 0.184051 0.704498 -0.643308 0.102065 0.758774 -0.516089 0.0465984 0.855267 -0.534531 0.0875757 0.840599 -0.389533 0.0524912 0.919515 -0.0667363 0.492902 0.867522 -0.0363648 0.32374 0.945447 -0.212135 0.404197 0.889732 -0.280374 0.521396 0.805938 -0.499255 0.147812 0.853754 -0.646988 0.40534 0.645837 -0.782197 0.00413458 0.623017 -0.880984 0.156014 0.446684 -0.805834 0.135901 0.576335 -0.641565 0.0572555 0.764928 -0.522962 0.379976 0.762974 -0.451106 0.24606 0.85788 -0.317605 0.206148 0.925543 -0.331393 0.229968 0.915037 -0.165696 0.167552 0.971839 -0.903497 0.143387 -0.403899 -0.947689 0.0971559 -0.304049 -0.976063 0.166578 -0.139829 -0.966633 0.193054 -0.168377 -0.985484 0.148307 -0.0826236 -0.990617 0.1344 -0.0248113 -0.977619 0.12111 0.172029 -0.973921 0.185661 0.130411 -0.222239 0.774867 -0.59177 -0.238924 0.758505 -0.606288 0.00747222 0.843793 -0.536616 -0.413228 0.695189 -0.58818 -0.471299 0.844935 -0.252907 -0.501061 0.823219 -0.266925 -0.487314 0.850968 0.195902 -0.467346 0.860716 0.20188 -0.27428 0.909956 0.311048 -0.695572 0.492194 -0.523378 -0.744016 0.632747 -0.214643 -0.772056 0.592609 -0.229662 -0.759854 0.619222 0.197957 -0.74059 0.63927 0.207028 -0.663777 0.519445 0.538124 -0.530196 0.60732 0.591655 -0.422194 0.428868 0.798639 -0.114465 0.708363 0.696505 -0.458083 0.865902 0.200933 -0.326674 0.942019 0.0767093 -0.331186 0.906489 -0.261905 -0.556626 0.813538 -0.168295 -0.285928 0.876788 -0.386636 -0.7104 0.47135 -0.522648 -0.828959 0.302002 -0.470768 -0.878639 0.433429 -0.200335 -0.904551 0.396507 -0.15675 -0.887225 0.41555 0.200374 -0.876439 0.447825 0.176939 -0.787589 0.311768 0.531512 0.841618 0.537531 0.052333 0.842492 0.536179 0.0521482 0.804939 0.572429 0.156202 0.726406 0.613398 0.309963 0.729796 0.625661 0.275583 0.59428 0.651628 0.471393 0.598177 0.629311 0.496137 0.406131 0.489464 0.771675 0.401442 0.630351 0.664456 0.00924636 0.49834 0.866932 0.289875 0.694409 0.658611 0.290664 0.688868 0.664059 0.484898 0.72899 0.483164 0.418356 0.837923 0.350518 0.66126 0.729517 0.174757 0.663674 0.742786 0.0883531 0.818173 0.574961 -0.00355242 0.810627 0.584502 0.0352243 -0.931251 0.103474 0.349377 -0.879746 0.152867 0.450198 -0.772416 0.435695 0.462108 -0.64351 0.214729 0.734702 -0.409611 0.575085 0.708165 -0.270203 0.335262 0.902546 0.0023119 0.634067 0.773275 0.0883196 0.492273 0.865949 0.238961 0.465648 0.852097 0.186457 0.837024 -0.514417 0.0193288 0.854085 -0.519773 -0.0103257 0.928481 -0.371237 -0.0280145 0.936878 -0.348533 -0.0431559 0.983694 -0.174597 -0.0505644 0.985241 -0.163537 -0.0443186 0.997477 0.0554622 -0.0422888 0.997775 0.0515414 -0.00964916 0.961587 0.274332 -0.00254501 0.967282 0.25369 0.0551174 0.880491 0.470848 -0.20319 0.79956 0.56517 -0.228444 0.775429 0.588662 -0.380804 0.735528 0.560345 -0.522663 0.619949 0.585224 -0.616204 0.75971 0.207684 -0.636525 0.744812 0.200226 -0.649816 0.717181 -0.251775 -0.619747 0.748084 -0.237241 -0.556972 0.582798 -0.591717 -0.56083 0.576056 -0.594667 0.547119 0.784353 -0.292322 -0.370951 0.546655 -0.750708 -0.325636 0.944765 -0.0371559 -0.965884 0.225881 0.126674 -0.964016 0.220887 0.147925 -0.988814 0.143326 0.0412853 -0.981476 0.0725097 -0.177331 -0.981641 0.0768784 -0.174556 -0.909544 0.131187 -0.394359 -0.912846 0.142394 -0.382669 -0.820783 0.0458101 -0.5694 -0.816262 0.0298049 -0.576912 -0.610798 0.158259 -0.775809 -0.615306 0.174514 -0.768728 -0.351939 -0.0557738 -0.93436 -0.398742 0.224932 -0.889051 -0.113153 0.505262 -0.855515 -0.0906933 0.29613 -0.950832 0.0481195 0.613639 -0.788119 -0.925099 0.379413 0.0154434 -0.912889 0.340525 -0.225116 -0.90275 0.387215 -0.187368 -0.839354 0.300524 -0.452958 -0.835845 0.381575 -0.394668 -0.726408 0.259946 -0.636207 -0.736197 0.370204 -0.566536 -0.534541 0.173906 -0.827056 -0.538062 0.391491 -0.746475 -0.221608 0.107592 -0.969182 -0.260844 0.370193 -0.891582 -0.257097 0.935258 -0.243297 -0.20652 0.96611 -0.154859 0.00922573 0.994661 -0.102786 -0.0400692 0.987446 -0.152791 0.189548 0.972092 -0.138236 -0.151114 0.873943 -0.46194 -0.186162 0.831956 -0.522679 0.106477 0.918537 -0.380726 0.0866785 0.900901 -0.425281 0.4355 0.875153 -0.210824 0.424261 0.890794 -0.162753 0.441588 0.889823 -0.11496 0.448325 0.865331 -0.224071 0.470218 0.844112 -0.257622 0.232227 0.795512 -0.559671 0.233227 0.837385 -0.494359 0.0205773 0.705336 -0.708575 0.030692 0.782672 -0.621677 -0.532521 0.84441 -0.0582592 -0.559324 0.828731 -0.0190097 -0.55295 0.795378 -0.248235 -0.527687 0.803656 -0.275108 -0.487324 0.748979 -0.448938 -0.352101 0.760028 -0.546244 -0.356453 0.727875 -0.585781 -0.192395 0.559362 -0.806287 -0.77503 0.629068 0.0600156 -0.776073 0.627501 0.0628761 -0.775082 0.589727 -0.226872 -0.749586 0.608529 -0.260409 -0.708342 0.551341 -0.440766 -0.660082 0.572006 -0.48693 -0.605118 0.510951 -0.610541 -0.536171 0.527957 -0.658622 -0.382944 0.374609 -0.844406 -0.176696 0.682194 -0.7095 0.0673605 0.46484 -0.882829 0.176562 0.660221 -0.730024 0.379992 0.661676 -0.646367 0.364365 0.722833 -0.587155 0.518194 0.806008 -0.286053 0.509191 0.814416 -0.278302 0.942269 0 0.334857 0.940282 -0.124053 0.316986 0.980063 0.117473 0.16024 0.637916 -0.766927 0.0699001 0.98286 -0.177232 0.0507523 0.995328 0.0913568 -0.031252 0.336048 -0.941522 -0.0246714 0.0280913 -0.999601 -0.00301368 0.985498 0 -0.169685 -0.937524 -0.00698797 -0.347849 -0.817734 0.00611259 -0.575563 -0.726668 -0.0078939 -0.686943 -0.638735 5.302e-05 -0.769427 -0.433182 -0.000106279 -0.901306 -0.432465 0 -0.901651 -0.991444 0 0.130536 -0.999044 -0.00304337 0.0436046 -0.999934 -0.00536761 0.0101838 -0.985012 0.00590707 -0.172385 -0.925829 -0.0105265 -0.377796 -0.955005 0 -0.29659 -0.974009 -0.00355684 -0.226483 -0.98713 -0.000929272 -0.15992 -0.996962 0.000128326 -0.0778895 -0.990624 -0.00338833 0.136575 -0.991625 -0.0027432 0.129123 -0.999759 -0.000171233 -0.0219618 -0.719943 -5.22763e-06 0.694033 -0.82425 2.66036e-05 0.566226 -0.858201 -0.00462513 0.513293 -0.899284 -0.00174551 0.437362 -0.939072 0.00110212 0.343718 -0.661201 -0.00118227 0.750208 -0.618079 -0.00368543 0.786108 -0.551669 0 0.834063 -0.996492 0 0.0836902 -0.998768 0.0372956 0.0327253 -0.998697 0.00293231 -0.0509547 -0.92615 0 -0.377154 -0.942461 0.0015642 -0.334312 -0.968046 0.0285581 -0.249142 -0.968243 0.0292007 -0.2483 -0.985412 0.00641808 -0.170065 -0.992473 -0.00122282 -0.122455 -0.481039 -9.74905e-08 0.876699 -0.481039 1.02823e-07 0.876699 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.481039 1.21172e-06 0.876699 -0.481039 0 0.876699 -0.279774 0 -0.960066 -0.279774 -1.49311e-07 -0.960066 -0.279774 1.42376e-07 -0.960066 -0.279774 0 -0.960066 -0.311236 0.0093652 0.950287 -0.29354 0 0.955947 0.578225 -0.0493741 0.814382 0.521244 -0.013502 0.853301 0.736788 0.00537166 0.676102 0.469631 -0.0175459 0.882688 0.377978 0.000892498 0.925814 0.0951901 -0.00277786 0.995455 0.143249 -0.0299705 0.989233 -0.0579308 -0.00252603 0.998317 0.819312 0 0.573348 0.869353 -0.046771 0.491974 0.813327 -0.0198879 0.581467 0.76189 0.556084 -0.332106 0.92403 0 -0.38232 0.77224 -0.199899 -0.603063 0.463164 -0.744475 -0.48087 0.646848 0.100039 -0.756029 0.444343 -0.0408508 -0.894925 0.258243 -0.547062 -0.796263 0.25097 -0.0996527 -0.962852 0.021341 0.0531822 -0.998357 -0.0938761 -0.289342 -0.952612 -0.180847 0 -0.983511 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0478496 0.980514 -0.190535 0.0298963 0.980514 -0.194162 0.0475646 0.970769 -0.235255 0.111012 0.828373 -0.549067 0.111013 0.828371 -0.54907 0.15012 0.652813 -0.742495 0.170908 0.549218 -0.818016 0.172562 0.491706 -0.853491 0.184476 0.365333 -0.912415 0.185127 0.356042 -0.915949 0.110996 0.980541 -0.161925 0.487313 0.556853 -0.672637 0.489484 0.553195 -0.674078 0.328501 0.829117 -0.452384 0.328498 0.82912 -0.452382 0.196457 0.942449 -0.270545 0.102407 0.982331 -0.156648 0.0868252 0.989797 -0.112979 -0.546262 0.783556 -0.296036 -0.477564 0.539945 -0.693103 0.182293 0.556546 -0.810571 -0.940179 0.19154 -0.281737 -0.0995698 0.880581 -0.463318 -0.258844 0.247481 -0.933677 -0.496857 0.482851 -0.721102 -0.509664 0.45471 -0.730398 -0.688599 0.267699 -0.673921 -0.70588 0.596153 -0.382538 -0.716063 0.544145 -0.437219 -0.794072 0.42926 -0.430332 -0.836068 0.309354 -0.45309 -0.83747 0.306753 -0.452268 0.0669201 0.97947 -0.190158 0.188973 0.822156 -0.536981 0.0580327 0.559083 -0.827078 -0.109408 0.560255 -0.821063 -0.0751905 0.822155 -0.564276 -0.322991 0.822155 -0.468762 -0.114379 0.97947 -0.166 -0.133625 0.542298 -0.829492 -0.477563 0.539946 -0.693103 -0.322988 0.822156 -0.468763 -0.45389 0.828074 -0.329055 -0.27038 0.962671 0.0126331 0.383217 0.551978 -0.740584 0.266703 0.595415 -0.757859 0.188973 0.822156 -0.536982 -0.0751884 0.822156 -0.564275 -0.026626 0.97947 -0.199823 0.873593 0.279502 -0.398389 0.532323 0.77293 -0.345269 0.893679 0.296852 0.336476 0.960914 0.263721 0.084237 0.826475 0.191508 0.5294 0.888339 0.303965 0.34418 0.842178 0.429265 0.326295 0.796903 0.544148 0.262391 0.748642 0.596157 0.290055 0.56635 0.822158 -0.0574737 0.837397 0.539949 -0.0849797 0.837397 0.539949 -0.0849799 0.893538 0.439737 -0.0906771 0.900862 0.42175 -0.102837 0.165484 0.962668 0.214209 0.641104 0.760405 0.103781 0.169509 0.979471 -0.109106 0.478674 0.822159 -0.308101 0.478674 0.822158 -0.308103 0.70776 0.539949 -0.455556 0.70776 0.539949 -0.455555 0.577487 0.726874 -0.371704 0.604053 0.00319778 -0.796938 0.101583 0.979471 -0.174121 0.286859 0.822158 -0.491699 0.286858 0.822158 -0.491701 0.424143 0.539949 -0.72702 0.424144 0.53995 -0.727018 0.0808728 0.987038 -0.138623 0.367091 0.364706 -0.855707 0.530811 0.822158 0.205658 0.56635 0.822158 -0.0574741 0.200557 0.979471 -0.0203529 -0.181785 0.979376 -0.0881904 -0.0279508 0.979376 -0.200105 -0.453881 0.890891 0.0174727 -0.201898 0.979376 0.00777228 -0.118863 0.979376 -0.163385 -0.802951 0.595244 0.0309103 -0.121203 0.482052 -0.867719 -0.981804 0.186098 0.0377954 -0.941985 0.305883 0.138201 -0.876056 0.227804 -0.425007 -0.838236 0.463709 -0.286941 -0.576838 0.196366 -0.792905 -0.503296 0.661037 -0.556528 -0.357958 0.364863 -0.859501 -0.125308 0.423673 -0.897106 -0.126659 0.348272 -0.928797 -0.902905 0.428433 0.0347581 -0.839502 0.543279 -0.00920019 -0.75781 0.53904 -0.367641 -0.757809 0.539041 -0.367642 -0.495506 0.53904 -0.681109 -0.495507 0.53904 -0.681109 -0.160008 0.543548 -0.823986 -0.105941 0.643045 -0.758466 -0.621763 0.78284 0.0239353 -0.559149 0.827635 -0.0487079 -0.512991 0.821525 -0.248871 -0.512991 0.821525 -0.248871 -0.335428 0.821525 -0.461069 -0.335428 0.821525 -0.461069 -0.0788746 0.821525 -0.564691 -0.0788765 0.821524 -0.564691 0.197669 0.979505 -0.0386806 0.870282 0.429571 0.240993 0.663027 0.54705 -0.51101 0.834598 0.350228 -0.425189 0.902367 0.350379 -0.250936 0.865079 0.472211 -0.169281 0.958535 0.282875 -0.0345465 0.946145 0.282627 0.157895 0.908806 0.332773 0.251661 0.904334 0.190658 0.381877 0.595064 0.671228 -0.441986 0.670445 0.541036 -0.507724 0.825819 0.540285 -0.161599 0.825819 0.540285 -0.161599 0.818976 0.544468 0.181199 0.500233 0.86562 -0.0216357 0.598461 0.783824 0.165722 0.773508 0.596495 0.214195 0.450615 0.822392 -0.347299 0.450615 0.822392 -0.347301 0.558332 0.822392 -0.109256 0.558332 0.822392 -0.109257 0.548288 0.822392 0.151829 0.194113 0.979505 0.0537527 0.270896 0.939693 -0.208787 0.209939 0.977656 -0.0106659 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.308625 0.785051 0.537072 -0.482138 0.252158 0.839023 -0.482138 0.252157 0.839023 -0.809951 0.252158 0.529524 -0.809951 0.252157 0.529524 -0.961963 0.252157 0.105089 -0.961963 0.252158 0.105089 -0.905177 0.252158 -0.342155 -0.905178 0.252158 -0.342155 -0.399314 0.598058 0.694892 -0.423392 0.704666 0.569372 -0.600043 0.697177 0.392292 -0.600043 0.697178 0.392291 -0.712659 0.697177 0.0778538 -0.712659 0.697177 0.0778545 -0.67059 0.697177 -0.253482 -0.670591 0.697177 -0.253481 -0.132348 0.964075 0.230312 -0.132349 0.964075 0.23031 -0.222332 0.964075 0.145355 -0.222332 0.964075 0.145354 -0.264059 0.964075 0.0288472 -0.26406 0.964075 0.0288476 -0.248472 0.964075 -0.0939217 -0.248473 0.964075 -0.0939207 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0613767 0.836035 -0.545232 0.227756 0.909095 -0.348818 0.244687 0.899908 -0.360963 0.247975 0.903776 -0.348853 0.248941 0.905099 -0.344709 0.435729 0.634624 -0.638273 0.476714 0.516925 -0.711008 0.489635 0.550984 -0.675777 0.290939 0.747644 -0.596979 0.312539 0.650462 -0.692256 0.253212 0.75013 -0.610892 0.357948 0.752574 -0.552726 0.357958 0.753883 -0.550932 0.286693 0.746914 -0.599939 0.292734 0.755815 -0.585705 0.2421 0.75717 -0.606697 0.176404 0.719913 -0.671273 0.226585 0.637233 -0.736609 0.151257 0.695656 -0.702271 0.194373 0.556489 -0.807799 0.176388 0.449136 -0.875879 0.00994865 0.791543 -0.611032 0.0456592 0.802046 -0.595515 0.0539244 0.789454 -0.611436 0.149251 0.816278 -0.558045 -0.00740238 0.784376 -0.620241 0.00837695 0.791286 -0.611389 0.0205402 0.787336 -0.616182 0.0493257 0.795645 -0.603752 0.088088 0.707056 -0.70165 0.0707921 0.672416 -0.73678 0.108875 0.56725 -0.816317 0.0768162 0.432009 -0.898592 0.227137 0.882876 -0.411022 0.181471 0.893659 -0.410417 0.200651 0.88035 -0.429794 0.158031 0.866333 -0.473807 0.130514 0.878837 -0.458925 0.269207 0.871245 -0.410438 0.201868 0.823897 -0.529569 0.232263 0.831885 -0.504005 0.232326 0.832564 -0.502854 0.152439 0.813784 -0.560819 0.124001 0.886117 -0.446565 0.107299 0.846691 -0.521153 0.794664 0.598058 -0.104096 0.973483 0.189919 -0.127521 0.973483 0.18992 -0.12752 0.92561 0.18992 0.327378 0.92561 0.189919 0.327378 0.676831 0.189919 0.711217 0.676832 0.189919 0.711217 0.281144 0.189918 0.940686 0.281142 0.189921 0.940686 0.894033 0.432423 -0.117113 0.832979 0.548362 -0.0737892 0.790532 0.544868 0.279602 0.790531 0.544869 0.279603 0.578058 0.54487 0.607426 0.578058 0.54487 0.607426 0.240113 0.54487 0.803407 0.240116 0.544868 0.803408 0.614184 0.785051 -0.0804545 0.558896 0.829044 -0.0179329 0.533884 0.824204 0.188829 0.533885 0.824203 0.188829 0.390391 0.824203 0.410225 0.390389 0.824204 0.410225 0.162162 0.824204 0.542579 0.162161 0.824204 0.542579 0.227068 0.965133 -0.130222 0.198693 0.979716 -0.0260277 0.188922 0.979716 0.0668193 0.188922 0.979716 0.0668194 0.138144 0.979716 0.145164 0.138144 0.979716 0.145164 0.057383 0.979716 0.191999 0.057383 0.979716 0.191999 -0.2385 0.965001 -0.10905 -0.2385 0.965001 -0.10905 -0.560246 0.787722 -0.256162 -0.676756 0.695499 -0.241415 -0.893048 0.189033 -0.408329 -0.901346 0.252746 -0.351704 -0.819275 0.434126 -0.374598 -0.726548 0.601474 -0.3322 0.395567 0.486433 -0.779044 0.867427 0.0637578 0.493463 -0.40471 0.601408 -0.688852 -0.136814 0.98644 -0.0906562 -0.417243 0.905133 0.0814978 0.185844 0.940278 0.285201 0.428046 0.859484 0.2794 0.386251 0.893637 0.228523 0.603568 0.77737 0.177208 0.213004 0.921428 0.32496 -0.0106951 0.959591 0.281197 -0.123021 0.936013 0.329765 0.430994 0.893272 -0.12771 0.633311 0.742517 -0.21814 0.680932 0.732325 -0.00568078 0.729696 0.682272 0.0452689 0.554832 0.822668 0.124009 0.553865 0.808917 0.197198 0.406077 0.913682 -0.0169166 0.149985 0.988626 -0.0111197 0.180911 0.935458 0.303628 0.0776696 0.996964 0.00547321 -0.0011722 0.975996 0.217784 -0.0555452 0.488107 -0.871014 -0.399113 0.467298 -0.788886 -0.280979 0.444516 -0.850562 -0.508779 0.415531 -0.753975 0.51556 0.72292 -0.459984 0.381126 0.833492 -0.400043 0.376542 0.878165 -0.29503 0.215292 0.931972 -0.29168 0.192654 0.948606 -0.25106 0.0293021 0.945562 -0.32412 0.062806 0.935365 -0.348062 -0.546019 0.834704 -0.0716373 -0.669339 0.742953 -0.00231476 -0.488023 0.841158 -0.232994 -0.385863 0.872028 -0.301125 -0.214974 0.871323 -0.441115 -0.271345 0.733918 -0.622685 -0.0157319 0.717158 -0.696733 0.0991863 0.719072 -0.687821 0.215763 0.785332 -0.580258 -0.539201 0.778001 -0.322454 -0.579264 0.676334 -0.455001 -0.451412 0.740002 -0.498623 -0.552288 0.66687 -0.500262 -0.150645 0.698052 -0.700022 -0.146132 0.509768 -0.84781 0.103508 0.511258 -0.853171 0.0656223 0.502885 -0.861859 0.187675 0.522801 -0.831539 -0.980138 0.108885 0.165748 -0.997321 0.0691407 0.0238947 -0.996621 0.0775098 0.0271888 -0.992808 0.0732565 -0.0946873 -0.987298 0.0345417 -0.155081 0.939247 0.169516 0.298462 0.751271 0.0433821 0.658567 0.70469 0.123494 0.698685 0.648351 -0.00480153 0.761327 0.674761 0.238579 0.698411 0.535399 -0.0106752 0.844532 0.443732 0.213398 0.870381 0.370537 -0.0215982 0.928567 0.268879 0.293688 0.917306 0.201276 -0.042557 0.97861 0.143479 0.0861303 0.985898 -0.0647931 0.153847 0.985968 -0.01516 0.00947687 0.99984 -0.261604 0.323658 0.90929 -0.198357 0.0653357 0.97795 -0.511158 0.160626 0.844344 -0.520175 0.17418 0.83611 -0.68062 0.0917811 0.726865 -0.743827 0.138053 0.653959 -0.819859 0.0900063 0.565447 -0.858272 0.119586 0.499067 -0.919485 0.0910449 0.382437 -0.952286 0.128847 0.276677 -0.983794 0.0507662 0.171963 0.802565 0.425134 0.418511 0.915355 0.385475 -0.116334 0.92222 0.383684 -0.0479162 0.835958 0.42421 -0.348167 0.864513 0.445894 -0.23194 0.705377 0.466286 -0.533874 0.741798 0.48507 -0.46308 0.535361 0.483714 -0.692394 0.831787 0.4693 0.29646 -0.212362 0.55288 0.805745 -0.216524 0.56579 0.795612 0.06194 0.521838 0.850793 0.055749 0.563305 0.824366 0.319245 0.477095 0.818818 0.320299 0.539577 0.778631 0.537627 0.424738 0.728392 0.547219 0.495954 0.674226 0.707447 0.368474 0.603113 0.625703 0.137574 0.767834 -0.839437 0.226702 -0.493914 -0.805041 0.241731 -0.541734 -0.815311 0.377021 -0.439458 -0.863297 0.392088 -0.317782 -0.856068 0.446053 -0.261121 -0.883195 0.452004 -0.125135 -0.85863 0.510466 -0.0466797 -0.859015 0.504531 0.086846 -0.801746 0.565993 0.191977 -0.779493 0.549058 0.30154 -0.668696 0.606184 0.430566 -0.63989 0.585213 0.498064 -0.440142 0.625426 0.644296 -0.388522 0.771306 0.50412 -0.135956 0.774637 0.617619 -0.139433 0.78416 0.604691 0.131337 0.741175 0.658339 0.122863 0.771762 0.623929 0.382897 0.686497 0.618153 0.374034 0.733309 0.567764 0.593397 0.61726 0.516594 -0.473929 0.54941 0.688142 -0.37048 0.672519 0.640674 -0.176715 0.669675 0.721323 -0.180641 0.681029 0.709626 0.0973309 0.637023 0.764676 0.0897198 0.673476 0.733745 0.354681 0.586709 0.727993 0.350431 0.641981 0.681951 0.571358 0.525206 0.630641 0.571715 0.588571 0.5716 0.764836 0.428787 0.480799 0.585298 0.671452 0.454509 0.782749 0.506558 0.361528 0.82614 0.533939 0.180006 0.94514 0.319265 0.0691469 0.936323 0.287002 0.202311 0.949978 0.297397 0.0953784 0.925513 0.215734 0.311264 0.856964 0.164582 0.48839 0.793259 0.273796 0.543852 0.779026 0.181959 0.600008 0.66106 0.320801 0.678297 0.654452 0.219453 0.723556 0.479224 0.358907 0.800956 0.486512 0.258994 0.834403 0.251184 0.383559 0.888701 0.273355 0.299904 0.913966 -0.00539996 0.391372 0.920217 0.0213108 0.338817 0.940611 -0.262546 0.383842 0.885288 -0.250814 0.368666 0.895085 -0.495252 0.366378 0.787713 -0.511141 0.382006 0.76994 -0.687259 0.344557 0.639496 -0.724065 0.37548 0.578571 -0.830132 0.320884 0.455975 -0.867743 0.351781 0.351101 -0.921047 0.295035 0.254219 -0.941053 0.316445 0.11951 -0.962627 0.265869 0.0516131 -0.95707 0.274619 -0.092744 -0.962879 0.232659 -0.136873 -0.934157 0.229855 -0.27298 -0.92618 0.122671 -0.356571 -0.983477 0.057049 -0.171811 -0.936336 0.0456155 -0.34813 -0.262237 0.927997 0.264676 -0.433819 0.818262 0.377159 -0.281848 0.955424 0.0879075 -0.246656 0.96774 0.0513872 -0.124884 0.982126 -0.140825 -0.290438 0.895961 -0.336005 -0.0603988 0.868313 -0.492325 0.0410577 0.855567 -0.516062 0.257423 0.751377 -0.60759 0.229059 0.682859 -0.693711 0.42692 0.639653 -0.639206 0.0565546 0.601647 -0.796757 0.431584 0.512518 -0.742334 0.287679 0.62142 -0.728751 0.383182 0.733343 -0.561587 0.276054 0.740681 -0.612524 0.270649 0.827249 -0.492349 0.241896 0.816528 -0.524184 0.215417 0.846472 -0.48691 0.202288 0.830513 -0.518968 0.218402 0.821296 -0.527043 0.207901 0.815879 -0.539554 -0.691383 0.32829 -0.643595 -0.62367 0.347949 -0.699977 -0.634458 0.506256 -0.584096 -0.694438 0.531468 -0.485075 -0.686165 0.594671 -0.418981 -0.729479 0.613479 -0.302496 -0.703291 0.67664 -0.218036 -0.721858 0.684992 -0.098529 -0.66413 0.747572 0.00824948 -0.658541 0.744412 0.110338 -0.55073 0.800397 0.236773 -0.533204 0.790118 0.302336 -0.312866 0.829724 0.462249 -0.322294 0.860923 0.393623 -0.0911369 0.863012 0.496894 -0.0939925 0.870487 0.483134 0.162696 0.829647 0.534057 0.15392 0.853789 0.497345 0.402418 0.772173 0.49174 0.389854 0.80967 0.438689 0.602201 0.697178 0.388969 0.586843 0.741286 0.325745 0.803421 0.55284 0.221094 0.672977 0.693322 -0.257695 0.829284 0.55733 0.0408725 0.809813 0.579308 -0.0927649 0.765732 0.627902 -0.139261 0.784788 0.61671 -0.0614545 0.606818 0.718621 -0.339641 0.475844 0.678575 -0.559561 0.571875 0.503506 -0.647643 0.341387 0.465419 -0.816603 0.531524 0.790816 0.303467 0.706417 0.695785 0.129838 0.958144 0.193032 -0.211421 0.877678 0.438378 -0.193666 0.777865 0.604537 -0.171642 0.682556 0.696248 -0.222162 0.598582 0.790098 -0.132081 0.951978 0.251243 0.174972 0.839044 0.257921 0.479043 0.773678 0.191315 0.604004 0.78078 0.437798 0.445776 0.929853 0.253487 -0.266678 0.951978 0.251242 0.174972 0.706417 0.695785 0.129838 0.615213 0.705789 0.351248 0.56219 0.600188 0.568962 0.255349 0.965206 -0.0563446 0.255349 0.965206 -0.0563446 0.262198 0.96381 0.0481916 0.262198 0.96381 0.0481916 0.225547 0.965684 0.128774 0.225548 0.965684 0.128774 -0.378937 0.696429 0.60942 -0.0676944 0.189539 0.979537 -0.11413 0.254265 0.960377 -0.511048 0.251667 0.821885 -0.511048 0.251667 0.821885 -0.8364 0.251666 0.486928 -0.8364 0.251666 0.486928 -0.620183 0.69643 0.361052 -0.230007 0.963933 0.133904 -0.230007 0.963933 0.133903 -0.140536 0.963933 0.226016 -0.0621914 0.431686 0.899878 -0.0552984 0.597259 0.80014 -0.128931 0.704101 0.698297 -0.0427614 0.784422 0.618752 -0.0312332 0.891501 0.45194 -0.620183 0.696429 0.361053 -0.378937 0.696429 0.60942 -0.140536 0.963933 0.226015 -0.112717 0.965339 0.235404 -0.0138443 0.979634 0.200314 -0.0673757 0.891501 0.447981 -0.119286 0.597257 0.79313 -0.14603 0.189539 0.970953 0.711109 0.251666 0.656497 0.711109 0.251666 0.656497 0.320941 0.251666 0.91305 0.32094 0.251667 0.913051 -0.096548 0.254265 0.962303 -0.134155 0.431692 0.891989 0.527281 0.696429 0.486787 0.52728 0.69643 0.486787 0.237974 0.696429 0.677019 0.237974 0.69643 0.677019 -0.0253445 0.704101 0.709647 -0.0922439 0.784422 0.61333 0.195552 0.963933 0.180535 0.195554 0.963933 0.180534 0.0882575 0.963933 0.251086 0.0882587 0.963933 0.251086 0.0590663 0.965339 0.254228 -0.0298651 0.979634 0.198558 0.476478 0.183995 -0.859718 0.817293 0.155394 -0.554874 0.726707 0.138079 -0.672927 0.476705 0.696496 -0.536327 0.59805 0.649902 -0.469004 0.731794 0.42675 -0.531377 0.77457 0.385349 -0.501544 0.830147 0.193653 -0.522834 0.86448 0.171908 -0.472358 0.919768 0.0656873 -0.386927 0.984258 0.0837201 -0.155654 0.953844 0.00633252 0.300234 0.962529 0.139029 0.232828 0.95801 0.17339 0.228369 0.946151 0.283874 0.155609 0.928307 0.342766 0.144073 0.901448 0.427001 0.071149 0.861851 0.504617 0.0507362 0.34696 0.807342 -0.477302 0.346666 0.796408 -0.495538 0.360405 0.843831 -0.397564 0.827404 0.561339 -0.0173249 0.654916 0.750948 -0.0846331 0.719274 0.680342 -0.140637 0.387429 0.885833 -0.255342 0.39931 0.875536 -0.272008 0.628645 0.152643 -0.762565 0.559613 0.224139 -0.797869 0.560443 0.393962 -0.72849 0.524137 0.442588 -0.727597 0.462879 0.605632 -0.647266 0.99599 0.0675097 0.0587011 0.981985 0.123987 -0.142596 0.97665 0.159045 -0.144429 0.947154 0.257565 -0.191207 0.928598 0.316392 -0.193912 0.846682 0.457348 -0.271959 0.849453 0.450513 -0.274715 0.653386 0.705656 -0.27411 0.68343 0.64843 -0.335353 0.387367 0.864262 -0.320933 0.389947 0.859522 -0.330399 -0.942275 0.191623 0.274589 -0.924997 0.258811 0.278205 -0.862552 0.439116 0.251358 -0.763047 0.60689 0.22236 -0.675834 0.707066 0.208099 -0.586244 0.791917 0.170838 -0.42564 0.896351 0.124036 -0.246258 0.965896 0.0800169 -0.188409 0.980555 0.0549045 -0.88393 0.292417 -0.36491 -0.170269 0.615394 -0.76961 -0.985126 0.132396 0.109537 -0.988477 0.142331 0.0515301 -0.990419 0.119461 0.0692815 -0.153757 0.467758 -0.87038 -0.131844 0.591501 -0.795452 -0.450972 0.589797 -0.669899 -0.483763 0.576433 -0.658557 -0.65335 0.534475 -0.536162 -0.675693 0.51949 -0.523039 -0.886245 0.385081 -0.257455 -0.880277 0.384697 -0.277707 -0.89527 0.299595 -0.329748 -0.677073 0.397823 -0.61912 -0.563677 0.461511 -0.685037 -0.476769 0.443511 -0.758939 -0.346215 0.45374 -0.82113 -0.115932 0.440893 -0.890041 -0.136987 0.743645 -0.65439 -0.210628 0.733895 -0.645782 -0.448476 0.711669 -0.540737 -0.410284 0.722783 -0.556104 -0.648763 0.626452 -0.432046 -0.604308 0.655074 -0.453531 -0.863741 0.468355 -0.185999 -0.873574 0.453663 -0.176236 -0.97828 0.159496 0.132399 -0.978115 0.161443 0.131251 0.96403 0.227551 0.137357 0.882401 0.41359 -0.224304 0.834578 0.539606 0.110931 0.422589 0.849561 -0.315696 0.692241 0.716942 -0.0824394 0.907946 0.236438 0.346023 0.888623 0.393759 0.235164 0.894362 0.0782504 0.440447 0.451895 0.843423 -0.290565 0.532827 0.724579 -0.437128 0.555658 0.722391 -0.411576 0.637423 0.525364 -0.563635 0.662998 0.525887 -0.5328 0.706611 0.704807 -0.0628331 0.774302 0.605244 -0.184762 0.784434 0.598174 -0.163863 0.851709 0.435778 -0.291014 0.807561 0.447525 -0.384143 0.86699 0.462136 0.186436 0.913133 0.394243 0.103732 0.914491 0.38776 0.115533 0.958507 0.283212 0.0324998 0.953544 0.299962 -0.0278732 0.902863 0.159315 0.399322 0.919693 0.134278 0.368964 0.918745 0.131822 0.372197 0.934045 0.096393 0.343901 0.932624 0.0946116 0.348225 0.860452 0.191623 0.472125 0.807673 0.258066 0.530157 0.787653 0.439116 0.432181 0.696787 0.606891 0.382323 0.569713 0.703692 0.424552 0.172048 0.980555 0.094402 0.191287 0.963363 0.187992 0.38868 0.896351 0.213266 0.535338 0.791917 0.293736 -0.147538 0.896624 0.41749 -0.0888838 0.98067 0.174319 -0.0863522 0.965834 0.244352 -0.203019 0.792936 0.574487 -0.203019 0.792936 0.574487 -0.264483 0.608218 0.748412 -0.264483 0.608218 0.748411 -0.298919 0.441787 0.845856 -0.340718 0.258159 0.904027 -0.326814 0.194825 0.924789 -0.927309 0 -0.374296 -0.935401 0.00229981 -0.35358 -0.996004 -0.00256574 0.089274 -0.994086 -0.000325474 0.108598 -0.819804 0.000359068 0.572644 -0.836993 -0.0035479 0.547203 -0.473869 0.00317902 0.880589 -0.498238 0 0.86704 0.108812 0.6085 0.786059 0.0954456 0.554885 0.826434 0.0699206 0.792829 0.60542 0.0753572 0.830637 0.551691 0.0508157 0.896561 0.439996 0.0224208 0.980719 0.194135 0.0224209 0.980719 0.194135 0.102933 0.441651 0.891263 0.112532 0.194757 0.974375 0.112532 0.194758 0.974375 0.351517 0.193492 -0.915968 -0.0288058 0.122886 -0.992003 0.20095 0.643912 -0.738238 0.282866 0.767267 -0.575576 0.257662 0.815281 -0.518583 0.305701 0.6347 -0.70972 0.309816 0.620325 -0.720563 0.0992384 0.734605 -0.671199 0.160874 0.12595 -0.978906 0.206559 0.333587 -0.919812 0.23722 0.138362 -0.961552 0.345205 0.12841 -0.929701 0.0317951 0.713408 -0.700027 0.0473702 0.827706 -0.55916 -0.0225807 0.536628 -0.843517 0.168608 0.800309 -0.575393 0.0722569 0.356227 -0.931601 0.0947752 0.623665 -0.775925 0.20699 0.611636 -0.763581 0.195255 0.730667 -0.654218 0.199365 0.845764 -0.494912 -0.162112 0.109841 -0.98064 -0.0427244 0.3781 -0.924778 -0.105412 0.132768 -0.985526 -0.0729652 0.326846 -0.942257 -0.0602734 0.374045 -0.92545 -0.0158917 0.595594 -0.803128 0.0961879 0.580547 -0.808525 0.103982 0.695842 -0.710627 0.133943 0.804081 -0.579235 0.334985 0.461244 -0.821607 0.337286 0.394545 -0.854735 0.209899 0.405842 -0.889514 0.207169 0.378372 -0.902173 0.0723117 0.392705 -0.916817 0.0468776 0.137807 -0.989349 0.0532542 0.17131 -0.983777 -0.026496 0.724576 -0.688686 -0.905876 0.21733 -0.363534 -0.457498 0.656361 -0.599905 -0.453873 0.590686 -0.667151 -0.58126 0.724986 -0.369502 -0.556774 0.631806 -0.539281 -0.528768 0.716376 -0.455203 -0.52538 0.662642 -0.533743 -0.961558 0.203565 0.184303 -0.989241 0.14574 -0.0127141 -0.733234 0.169089 -0.658618 -0.369743 0.144754 -0.917789 -0.424457 -0.03888 -0.904613 -0.616548 0.07236 -0.783985 -0.199072 0.564315 -0.801199 -0.259266 0.357599 -0.897164 -0.330922 0.287288 -0.898864 -0.361301 0.0712007 -0.929727 -0.680697 0.268083 -0.68175 -0.726371 0.0215403 -0.686966 -0.879653 0.0767488 -0.469382 -0.408914 0.727491 -0.550951 -0.18551 0.807968 -0.559261 -0.172 0.779679 -0.602093 -0.164045 0.775534 -0.60962 -0.129922 0.741198 -0.658593 -0.0718383 0.726658 -0.683233 -0.862223 0.488686 -0.133258 -0.851381 0.443999 -0.279311 -0.849076 0.46165 -0.256806 -0.808453 0.415611 -0.416738 -0.810258 0.430833 -0.397322 -0.744394 0.39496 -0.53841 -0.746938 0.401678 -0.529847 -0.662442 0.380849 -0.645078 -0.120528 0.719294 -0.684171 -0.209995 0.589051 -0.780334 -0.39912 0.569966 -0.718221 -0.498522 0.39129 -0.773543 -0.618893 0.31952 -0.717551 -0.68346 0.0498089 -0.728287 -0.817141 0.220605 -0.532554 -0.908644 0.118925 -0.400278 -0.917015 0.140206 -0.373398 -0.96756 0.144386 -0.207317 -0.967625 0.144916 -0.206645 -0.985439 0.156481 -0.0665149 -0.977894 0.203969 0.0460415 0.259533 0 0.965734 0.286354 0.00280773 0.95812 0.66681 -0.0031417 0.745221 0.689378 0.000318017 0.724402 0.949066 -0.000351448 0.315077 0.942765 -0.00277073 0.333446 0.988392 0.0025359 -0.151903 0.991529 0 -0.129884 0.866687 0.0632677 0.494825 0.97651 0 -0.215473 0.994038 0.00892601 -0.108672 0.95812 -0.0150015 0.285973 0.00981179 0.00271142 0.999948 -0.21542 -0.00351261 0.976515 -0.0172171 0.00546691 0.999837 0.0860434 -0.000420386 0.996291 0.263142 0.000911924 0.964757 0.24314 0.00337918 0.969985 0.494309 -0.00422759 0.869276 -0.23863 -0.000256272 0.97111 -0.477163 0.000270801 0.878815 -0.504023 -0.00400341 0.863681 -0.680309 0.0027835 0.73292 -0.704736 -0.000413862 0.709469 -0.916679 0.00675841 0.399567 -0.97053 -0.000346346 0.240979 -0.817456 0.000387531 0.575991 -0.843969 0.0041794 0.536376 -0.950647 -0.00823962 0.310165 -0.996079 0.00649175 -0.0882253 -0.999773 0.017058 0.012753 -0.990708 0.000390553 0.136008 -0.998259 0.00360891 0.0588766 -0.981574 -0.012627 -0.190665 -0.901176 0 -0.433453 -0.909443 -0.00160804 -0.415825 -0.97884 0.000811644 -0.204624 0.405935 0.00910825 0.913857 0.548585 -0.00149521 0.836093 0.698647 0.00204063 0.715463 0.665461 0.00567788 0.746411 0.854284 -0.0112409 0.519684 0.808251 0 0.588839 0.983525 0 0.18077 0.929688 0.354049 -0.101637 -0.97946 0.193187 0.0577678 -0.744053 0.655362 0.129941 -0.827331 0.542815 0.144485 -0.273461 0.658855 0.700806 -0.932643 0.193869 0.30429 -0.828053 0.193333 0.526261 -0.582966 0.657692 0.477067 -0.667421 0.193743 0.719036 -0.468147 0.193474 0.86221 -0.234114 0.193624 0.952733 0.00962614 0.193624 0.981029 0.10564 0.658855 0.744815 0.25817 0.193485 0.946526 0.484946 0.193752 0.852812 0.458169 0.657691 0.597933 0.97957 0.170216 -0.10709 0.976336 0.189022 -0.105066 0.940177 0.193186 0.280618 0.694499 0.65536 0.296942 0.838129 0.193871 0.509857 0.685467 0.193335 0.701966 -0.827332 0.542814 0.144485 -0.649958 0.542815 0.53189 -0.649958 0.542815 0.53189 -0.305298 0.542815 0.782397 -0.305297 0.542819 0.782394 0.117939 0.54282 0.831527 0.117939 0.542803 0.831538 0.510824 0.542806 0.666649 0.510818 0.542825 0.666638 0.772225 0.54282 0.330175 0.772225 0.54282 0.330175 0.834879 0.542814 -0.0912721 0.834878 0.542815 -0.0912721 -0.519253 0.834168 -0.185848 -0.887441 0.173928 -0.426846 -0.458072 0.884451 -0.0889779 -0.887513 0.352599 -0.296639 -0.925764 0.188934 -0.327514 -0.791765 0.542815 -0.280108 -0.791763 0.542817 -0.280108 -0.535808 0.822787 -0.189557 -0.559878 0.822786 0.0977767 -0.559878 0.822786 0.0977767 -0.439844 0.822787 0.359944 -0.439844 0.822787 0.359944 -0.206603 0.822788 0.529468 -0.206604 0.822786 0.529469 0.0798116 0.822786 0.562719 0.0798115 0.822787 0.562718 0.345687 0.822787 0.451135 0.34569 0.822783 0.45114 0.522591 0.822784 0.223441 0.522591 0.822784 0.223441 0.564985 0.822786 -0.0617664 0.564986 0.822786 -0.0617664 -0.171157 0.983381 -0.0605514 -0.190075 0.979597 -0.0652815 -0.198426 0.979503 0.034653 -0.198426 0.979503 0.0346529 -0.155886 0.979503 0.127569 -0.155886 0.979503 0.127569 -0.0732234 0.979503 0.187652 -0.0732224 0.979503 0.18765 0.0282861 0.979503 0.199434 0.0282861 0.979503 0.199433 0.122515 0.979503 0.159887 0.122514 0.979503 0.159887 0.18521 0.979503 0.079189 0.18521 0.979503 0.0791893 0.200236 0.979503 -0.0218906 0.200236 0.979503 -0.0218906 0.124565 0.983612 0.130349 0.973674 0.171948 -0.149641 0.973674 0.171949 -0.149641 0.923157 0.357285 -0.141877 0.837665 0.530171 -0.131287 0.827541 0.546809 -0.127182 0.54152 0.836558 -0.0832244 0.557021 0.825799 -0.0882211 0.177513 0.983804 -0.0248745 0.197109 0.979913 -0.030293 0.149818 0.953573 0.261254 0.194602 0.840942 0.504922 0.223305 0.831279 0.509029 0.305726 0.537267 0.786051 0.249369 0.630809 0.734775 0.304366 0.173754 0.936574 0.228377 0.475057 0.849803 0.0628028 0.937166 0.343185 0.0902075 0.990807 0.100815 0.36825 0.833677 0.411552 0.36825 0.833677 0.411552 0.567083 0.526077 0.633766 0.567082 0.526081 0.633764 0.657101 0.170067 0.734368 0.657101 0.170052 0.734371 0.172468 0.98335 0.0572572 0.172467 0.98335 0.0572567 0.524125 0.833676 0.174002 0.524126 0.833676 0.174002 0.80712 0.526078 0.267952 0.80712 0.526079 0.267952 0.935243 0.170053 0.310487 0.935243 0.170051 0.310488 0.0552338 0.783622 0.618778 0.0814364 0.450369 0.889121 0.0896554 0.266021 0.959789 0.114729 0 0.993397 0.114729 0 0.993397 0.0989241 0.127038 0.986953 0.0953611 0.166132 0.981482 -0.423083 0 -0.906091 -0.382293 0.0118253 -0.923965 -0.622277 -0.0025667 -0.782793 -0.720205 -0.0101137 -0.693688 -0.753536 7.07307e-06 -0.657406 -0.885826 -8.81896e-06 -0.464017 -0.951167 -0.0109748 -0.308482 -0.937051 -0.0191081 -0.348668 -0.97752 0 0.210844 -0.997363 -0.0109527 0.0717443 -0.995156 -0.00682124 0.0980687 -0.998772 0.000290518 -0.0495394 -0.98107 -0.000678422 -0.193653 0.339143 0 -0.940735 0.318622 -0.0721144 -0.945135 0.229027 0.0135175 -0.973326 0.146555 -0.0381712 -0.988466 0.108248 -0.11121 -0.987884 0.0374928 0.0259362 -0.99896 -0.180099 0 -0.983648 -0.106577 -0.0416595 -0.993431 -0.10801 -0.0439855 -0.993176 -0.0457433 -0.0096766 -0.998906 -0.960066 0 0.279774 -0.960066 3.80677e-08 0.279774 -0.960066 4.13433e-08 0.279774 -0.960066 0 0.279774 0.876699 0 0.481039 0.876699 -7.77615e-07 0.48104 0.876699 0 0.481039 0.876699 -8.54458e-09 0.481039 0.876699 3.55981e-08 0.481039 0.922695 1.49614e-06 -0.385531 0.988359 -2.20371e-05 -0.152142 0.99495 -0.0319889 -0.0951429 0.998022 -0.00209266 0.0628283 0.950303 0.00715434 0.311243 0.953742 0 0.300626 0.829279 -0.0492555 -0.55666 0.853203 -0.020299 -0.521185 0.735251 -2.087e-05 -0.677795 0.636971 -1.22996e-05 -0.770888 0.573102 -0.0293157 -0.81896 0.483973 0 -0.875083 -0.333199 0 0.942857 -0.333199 0 0.942857 -0.317193 0.111608 0.941771 -0.312639 0.148838 0.938139 -0.303158 0.243272 0.921365 -0.282079 0.419962 0.862591 -0.2014 0.757712 0.620734 -0.148726 0 0.988878 -0.148726 0 0.988878 0.331615 0 0.943415 0.331615 0 0.943415 0.734757 0 0.67833 0.734757 0 0.67833 -0.864216 0 0.503121 -0.864216 0 0.503121 -0.528043 0 0.849217 -0.528043 0 0.849217 -0.0689441 0 0.997621 -0.0689441 0 0.997621 -0.416984 0.475065 0.774879 -0.510832 0.173753 0.841938 -0.44494 0.535035 0.718168 -0.305098 0.840941 0.446916 -0.333984 0.831275 0.444338 -0.415036 0.698676 0.582749 -0.110138 0.991328 0.0716782 -0.139749 0.937177 0.319639 -0.205676 0.953578 0.219969 -0.508052 0.836559 -0.205068 -0.508053 0.836558 -0.205069 -0.913498 0.171948 -0.368721 -0.913498 0.171947 -0.368721 -0.786112 0.53042 -0.317304 -0.855092 0.359104 -0.37398 -0.776396 0.546809 -0.313382 -0.550049 0.833676 0.049302 -0.550048 0.833677 0.049302 -0.847041 0.526077 0.0759223 -0.847042 0.526075 0.0759222 -0.9815 0.170054 0.0879739 -0.9815 0.170054 0.087974 -0.807862 0.170064 0.564303 -0.807864 0.170052 0.564303 -0.697192 0.526077 0.486997 -0.697194 0.526074 0.486998 -0.45274 0.833676 0.316244 -0.452739 0.833677 0.316244 -0.148978 0.98335 0.104063 -0.180998 0.98335 0.0162232 -0.180998 0.98335 0.0162232 -0.166665 0.983716 -0.067272 -0.166665 0.983716 -0.0672723 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.788204 0.559557 -0.256185 0.50448 0.678275 -0.534269 0.483886 0.648368 -0.587769 0.314685 0.634542 -0.705925 0.28326 0.585871 -0.759288 0.100211 0.546301 -0.831573 0.0575595 0.478587 -0.876152 -0.117131 0.421851 -0.899067 -0.169115 0.338696 -0.925573 -0.316654 0.275991 -0.907502 -0.762882 0.0329506 -0.645698 -0.543356 0.40296 -0.73647 -0.712172 0.246574 -0.657277 0.328079 0.876725 -0.351736 0.171031 0.88737 -0.428163 0.249558 0.863032 -0.4392 0.0171398 0.851993 -0.523272 -0.0305708 0.849542 -0.526634 -0.0983341 0.79131 -0.603456 -0.273018 0.733004 -0.62303 -0.288497 0.703814 -0.649165 -0.405903 0.617614 -0.673643 -0.589931 0.496684 -0.636621 -0.427546 0.496778 -0.755259 -0.667464 0.366016 -0.648478 -0.532576 0.225301 -0.815845 -0.653974 0.130867 -0.745112 -0.51107 0.0215036 -0.85927 0.689317 0.552513 -0.468585 0.792557 0.533865 -0.294691 0.73126 0.632103 -0.256329 0.682299 0.678217 -0.27293 0.579211 0.793335 -0.187443 0.656409 0.739566 -0.148894 0.610289 0.786709 -0.0929257 0.617131 0.545381 -0.567193 0.60566 0.526609 -0.596539 0.452356 0.511625 -0.730489 0.42421 0.47069 -0.773626 0.251991 0.43733 -0.863274 0.210179 0.381767 -0.900044 0.0524353 0.340439 -0.938804 -0.0142115 0.26742 -0.963475 -0.156827 0.231236 -0.960175 -0.229742 0.145072 -0.962379 -0.349987 0.09967 -0.931437 0.53859 0.808101 -0.238523 0.44412 0.858329 -0.256961 0.527486 0.769912 -0.359158 0.316252 0.793093 -0.520566 0.395288 0.761905 -0.513077 0.0840042 0.736796 -0.670876 0.186469 0.709397 -0.679695 -0.161182 0.620518 -0.767449 -0.0401957 0.601521 -0.797845 -0.389346 0.457006 -0.799722 -0.26059 0.451394 -0.853426 -0.490624 0.32712 -0.807639 -0.373637 0.183433 -0.909257 -0.244706 0.24371 -0.938469 -0.441419 -0.00841147 -0.897262 -0.308339 0.490552 -0.815038 -0.839271 0.0924011 -0.535804 0.0478412 0.815485 -0.576797 0.659585 0.60591 -0.44477 -0.121511 0.00637449 -0.99257 -0.262675 0.12176 -0.957171 -0.325873 0.18616 -0.926904 -0.136252 0.150688 -0.979147 -0.360445 0.0606738 -0.930805 -0.431684 0.11852 -0.894204 0.00151469 0.330694 -0.943737 -0.0476225 0.474756 -0.878828 -0.113948 0.262453 -0.958193 -0.170867 0.370383 -0.913029 -0.205934 0.504324 -0.838599 -0.325751 0.183174 -0.927542 -0.369973 0.346788 -0.861892 -0.449683 -0.00139393 -0.893187 -0.507843 0.185684 -0.8412 -0.769832 0.132324 -0.624379 -0.707563 0.0863985 -0.701349 -0.763881 0.137909 -0.630449 -0.690908 0.380072 -0.614973 -0.673932 0.215976 -0.706519 -0.594722 0.501082 -0.628667 0.31459 0.199117 -0.928109 0.359546 -0.0938723 -0.928394 0.394554 0.308886 -0.865399 0.446534 0.0517215 -0.893271 0.466562 0.41731 -0.779854 0.525455 0.202219 -0.826441 0.527024 0.519698 -0.672428 0.590544 0.350059 -0.727129 0.571331 0.618807 -0.539128 0.545934 0.638901 -0.541998 0.536989 0.657438 -0.528601 0.366013 0.796852 -0.480688 0.384344 0.73716 -0.555765 0.21474 0.8802 -0.423243 0.202446 0.849742 -0.48678 0.507529 0.843529 -0.175706 0.332402 0.871659 -0.360165 0.519682 0.82684 -0.215099 0.51914 0.82729 -0.214675 0.561901 0.797826 -0.218498 0.556546 0.802095 -0.216566 0.623684 0.755645 -0.200046 0.594784 0.778973 -0.198577 0.65134 0.741099 -0.162876 -0.622722 0.144253 -0.769031 -0.605867 0.116402 -0.787004 -0.536071 0.364341 -0.761501 -0.508103 0.217544 -0.83337 -0.403456 0.469104 -0.785599 -0.484235 0.540512 -0.688014 -0.416069 0.627621 -0.658011 -0.294304 0.70983 -0.639943 -0.168873 0.713718 -0.67977 -0.165568 0.688293 -0.706286 0.0054321 0.541949 -0.840394 -0.0249903 0.643178 -0.765309 0.155088 0.492692 -0.856272 0.109864 0.604343 -0.789113 -0.0878889 0.779249 -0.620521 0.036037 0.805915 -0.590933 0.13843 0.724624 -0.675098 0.271908 0.690021 -0.670774 0.262307 0.707103 -0.656659 0.395041 0.600613 -0.69513 0.348085 0.401402 -0.847179 0.302473 0.576563 -0.759003 0.230567 0.240124 -0.942963 0.186848 0.468169 -0.863658 0.110629 0.0732613 -0.991158 0.066303 0.350047 -0.934383 0.0414761 0.192338 -0.980452 0.0818875 0.12986 -0.988145 -0.0797759 0.700978 0.708707 0.838479 0.542933 -0.0466487 -0.44957 0.319085 -0.834309 -0.946707 0.147262 -0.28646 0.846728 0.510652 -0.149288 0.638139 0.769737 0.0168571 0.64309 0.732626 -0.222924 0.276213 0.826357 0.490754 0.212184 0.604349 -0.767945 0.0754586 0.997047 -0.0142632 0.479884 0.876472 -0.0388436 0.136403 0.784599 0.604813 0.152261 0.84028 0.520333 0.0874238 0.875624 0.475016 0.0290309 0.962129 0.271045 0.255515 0.962063 0.0956359 0.263177 0.900707 -0.345636 0.0777759 0.917268 -0.390603 0.110074 0.92207 -0.37104 0.0606186 0.922196 -0.381942 -0.0420366 0.85941 -0.509555 0.839364 0.533361 -0.104853 0.83586 0.531483 -0.137347 0.689 0.67606 -0.261193 0.688384 0.644511 -0.332766 0.463072 0.709164 -0.531649 0.499349 0.626652 -0.598296 0.337685 0.560555 -0.756139 0.369132 0.497526 -0.78499 -0.116943 0.9469 -0.299508 -0.11926 0.992862 -0.00137855 -0.0158336 0.998686 0.0487409 0.0183062 0.955904 0.293107 0.304787 0.928585 0.211742 0.368389 0.822039 0.434213 0.487923 0.767495 0.415791 -0.940656 0.118133 -0.318137 -0.984348 0.12064 -0.128469 -0.984396 0.107663 -0.139189 -0.986757 0.150031 0.0616603 -0.98563 0.0891655 0.143469 -0.952493 0.148904 0.265679 -0.852416 0.174329 0.492947 -0.848847 0.161209 0.503459 -0.889951 0.127355 0.437913 -0.931507 0.113836 0.345452 -0.699406 0.315916 0.641115 -0.82289 0.074044 -0.563356 -0.718641 0.0910834 -0.68939 -0.249133 0.412044 -0.876443 -0.449885 -0.17428 -0.875917 -0.587325 0.0669002 -0.806581 -0.677612 0.0717449 -0.731912 -0.728329 0.114533 -0.675588 -0.788413 0.333566 0.516855 -0.787939 0.317963 0.527305 -0.857204 0.433064 0.27867 -0.864883 0.386827 0.319911 -0.902521 0.4271 0.0551469 -0.902074 0.428226 0.0537124 -0.904149 0.392913 -0.167733 -0.884175 0.413894 -0.216626 -0.867764 0.353438 -0.349382 -0.825366 0.362211 -0.433099 -0.7539 0.206868 -0.623571 -0.495571 0.587771 -0.63948 -0.430304 0.421489 -0.798239 -0.300652 0.388865 -0.870858 -0.294593 0.375495 -0.87876 -0.157848 0.318428 -0.934713 -0.0607231 0.115845 -0.991409 -0.0337951 0.492188 -0.869833 -0.258748 -0.0646822 -0.963777 -0.395404 0.19264 -0.898079 -0.533412 0.225398 -0.815271 -0.540499 0.241255 -0.806013 -0.666138 0.247453 -0.703582 -0.727465 0.425947 -0.537925 -0.84686 0.133857 -0.514694 -0.911894 0.0832126 -0.401903 0.847842 0.53012 0.0116683 0.832581 0.553889 -0.00400514 0.663838 0.741225 0.0995212 0.732054 0.673036 0.105448 0.854246 0.492119 -0.167579 0.85653 0.428907 -0.287045 0.72434 0.562742 -0.398314 0.687464 0.55556 -0.467703 0.60903 0.543444 -0.577712 0.607276 0.561348 -0.562231 0.489282 0.446161 -0.749363 -0.260201 0.662504 0.702413 -0.207608 0.738919 0.641013 -0.24805 0.807113 0.535761 -0.263729 0.762305 0.591048 -0.3399 0.884533 0.319482 -0.355423 0.867107 0.348998 -0.401019 0.915896 0.0178596 -0.400382 0.916191 0.0170004 -0.399916 0.870627 -0.28649 -0.375529 0.871941 -0.314161 -0.348346 0.78569 -0.51122 -0.304 0.772736 -0.557192 -0.239799 0.604474 -0.759676 0.00835901 0.727426 -0.686135 0.169286 0.704892 -0.688818 0.192763 0.726112 -0.660003 0.425765 0.742198 -0.517558 0.377746 0.854361 -0.356897 0.432784 0.846512 -0.310026 0.426064 0.902521 0.0626477 0.432078 0.899572 0.0638633 0.522012 0.774834 0.35656 0.621286 0.734001 0.27431 -0.470661 0.526348 0.708122 -0.470488 0.474868 0.743735 -0.560746 0.637175 0.528745 -0.57431 0.565474 0.591952 -0.649761 0.68967 0.319634 -0.664605 0.65746 0.355031 -0.708301 0.704785 0.0398372 -0.707642 0.705511 0.0386888 -0.709155 0.662561 -0.241064 -0.68352 0.674287 -0.279531 -0.660926 0.595643 -0.456493 -0.612234 0.593912 -0.521956 -0.540791 0.423418 -0.726817 -0.194672 0.712536 -0.674088 -0.129106 0.564507 -0.815269 0.0430498 0.479914 -0.876259 0.040133 0.557774 -0.829022 0.180728 0.259908 -0.94857 0.197204 0.527766 -0.82618 0.631081 0.775076 -0.0315243 0.64081 0.76703 -0.0320456 0.671789 0.739948 -0.0342935 0.680808 0.731572 -0.036083 0.745002 0.66554 -0.0450279 0.699883 0.71422 -0.00726405 0.702889 0.710644 -0.0305291 0.689487 0.724298 -0.000201916 0.680865 0.731498 -0.0365165 0.696769 0.716331 -0.037187 0.702829 0.710675 -0.0311745 0.902503 0.426219 -0.0618548 0.837095 0.534632 -0.115937 0.889838 0.453044 -0.054214 0.897116 0.43683 -0.0660478 0.897099 0.436691 -0.0671868 0.898733 0.4346 -0.0583259 0.827334 0.543872 -0.140437 0.859471 0.506599 -0.0683256 0.791342 0.609617 -0.0463157 0.720993 0.690916 -0.0529526 0.581992 0.812581 -0.0315635 0.61326 0.789263 -0.0312572 0.619606 0.784291 -0.0312332 0.411104 0.911588 0.000581764 0.410796 0.911727 0.000727402 0.484173 0.874848 0.0147435 0.508001 0.860893 -0.0282659 0.508559 0.860525 -0.0293896 0.41112 0.911581 -0.000348551 0.41161 0.91136 -0.000695437 -0.786818 0 -0.617186 -0.795497 -0.00217018 -0.605954 -0.546899 0.00195993 -0.837196 -0.556224 0.000768126 -0.831032 -0.418566 0 -0.908187 -0.750696 0.0880656 0.654752 -0.139477 0.875807 0.462069 -0.0352497 0.883048 0.467958 0.354254 0.825929 0.438572 0.303925 0.846716 0.436695 0.142955 0.780713 0.608318 0.0645421 0.792337 0.606661 0.220774 0.708127 0.670682 0.308181 0.689674 0.655267 0.407932 0.776001 0.481055 0.515631 0.850169 0.106479 0.680281 0.709598 0.183543 0.526363 0.824437 0.207955 0.477818 0.858511 0.186139 0.198163 0.935844 0.291422 0.215947 0.929619 0.298622 0.0141055 0.906327 0.422341 0.655586 0.566737 0.499015 0.726946 0.590006 0.351345 0.782881 0.522617 0.337594 0.665664 0.589002 0.458223 0.575751 0.662048 0.479795 0.114124 0.0778763 0.99041 0.675664 0.193874 0.71126 0.735888 0.0836112 0.671922 -0.592173 0.2677 0.760045 -0.627332 0.137343 0.766545 -0.444917 -0.203494 0.872146 -0.517511 0.265147 0.81356 -0.191598 -0.0535 0.980014 -0.288586 0.407118 0.866587 -0.145348 -0.0517526 0.988026 -0.882124 0.0842215 0.463427 -0.832452 0.170424 0.527237 -0.799253 0.29194 0.525324 -0.719881 0.389464 0.574534 -0.715813 0.400014 0.572364 -0.571141 0.62664 0.530207 -0.583504 0.587302 0.560891 0.228343 0.050791 0.972255 0.31658 0.1351 0.938896 0.205917 0.241619 0.948271 0.22401 0.328466 0.917567 0.059037 0.478695 0.875994 0.105754 0.284155 0.952928 -0.141762 0.521072 0.841658 -0.11674 0.343388 0.93191 0.0732043 0.11641 0.9905 0.0836772 0.174589 0.981079 -0.103583 0.349557 0.931172 -0.0513506 0.113184 0.992246 -0.323207 0.374384 0.869123 -0.287521 0.153654 0.945369 -0.482701 0.339062 0.807488 -0.356048 0.57176 0.739135 -0.359199 0.428266 0.829195 0.691429 0.701892 0.171095 0.640701 0.754108 0.144301 0.732868 0.669575 0.120721 0.67846 0.724858 0.119469 0.358183 0.642312 0.677599 0.636677 0.552298 0.538154 0.467159 0.748248 0.471049 0.595232 0.789025 0.152114 0.597312 0.787045 0.1542 0.708309 0.418239 0.56866 0.810498 0.234155 0.536903 0.570435 0.458167 0.681679 0.696588 0.240306 0.676031 0.569256 0.376161 0.731061 0.576615 0.356092 0.735333 0.456166 0.478991 0.749987 0.490203 0.672724 0.554206 0.522845 0.642415 0.5603 0.615475 0.772934 0.154156 0.649365 0.739713 0.176493 -0.328776 0.767988 0.549638 -0.31779 0.783928 0.533355 -0.141595 0.617758 0.773515 -0.13472 0.717324 0.683591 0.0762214 0.517204 0.852462 0.0543553 0.648022 0.75968 0.26773 0.444322 0.854926 0.222876 0.59309 0.773674 0.359564 0.470918 0.805574 0.336414 0.365179 0.868026 0.410218 0.294669 0.863071 0.389231 0.138351 0.910691 0.551679 -0.028487 0.83357 0.429889 0.258798 0.864997 0.57763 0.13717 0.804691 0.524834 0.848013 0.0736441 0.5259 0.849501 -0.0421586 0.859522 0.115829 -0.497801 0.938728 0.149499 -0.310548 0.897902 0.205132 -0.389478 0.832976 0.430753 -0.347278 0.73554 0.650946 0.187751 0.889346 0.37785 0.257475 0.861591 0.422167 0.281844 0.941589 0.0892719 0.324717 0.922446 0.152535 0.354721 0.982199 0.138725 0.126652 0.513691 0.848659 -0.126092 0.55502 0.831223 0.0319535 0.705555 0.672022 -0.224897 0.869422 0.375511 -0.321087 0.704461 0.457046 -0.542995 0.76339 0.161064 -0.625535 0.717551 0.131047 -0.684067 0.513691 0.848573 -0.126667 0.662583 0.705936 -0.250279 0.608972 0.68064 -0.407286 0.704173 0.457306 -0.54315 0.602084 0.441231 -0.66544 0.636763 0.165827 -0.753017 0.567426 0.13527 -0.812238 0.552768 0.832638 0.0340766 0.711983 0.69955 0.0609114 0.759958 0.649544 -0.023579 0.915806 0.400316 -0.0323421 0.91775 0.395457 -0.0367207 0.984546 0.170278 -0.0409105 0.989449 0.121136 -0.0794836 0.300785 0 -0.953692 0.321228 0.00402395 -0.946993 0.0677581 -0.00129657 -0.997701 -0.0672042 -0.00934597 -0.997696 -0.122361 -0.00109563 -0.992485 -0.533671 -0.00388752 -0.845684 -0.447699 -0.0158025 -0.894045 -0.484837 -0.0106804 -0.874539 -0.367373 -0.000192869 -0.930074 -0.277942 1.67448e-05 -0.960598 -0.846314 0 -0.532685 -0.783621 -0.00748866 -0.621195 -0.786561 -0.0070197 -0.617473 -0.715544 -5.53307e-05 -0.698567 -0.639989 3.8175e-05 -0.768384 0.576849 0.791628 -0.20142 0.532094 0.838702 -0.115992 0.624117 0.62991 -0.462267 0.607179 0.681589 -0.408375 0.617428 0.463694 -0.635429 0.616558 0.434157 -0.656783 0.593204 0.337319 -0.730975 0.558407 0.201922 -0.804617 0.544162 0.146215 -0.826141 0.509266 0.0671827 -0.857983 0.748324 0.659974 0.0666669 -0.237528 0.621356 0.746657 0.32504 0.86321 0.386287 0.0671262 0.871668 0.485479 0.026942 0.851219 0.524118 0.0400228 0.853095 0.520219 0.83863 0.544696 -0.00256868 0.697645 0.701425 0.145924 0.588083 0.76421 0.264842 0.270669 0.924545 0.268246 0.208895 0.937827 0.277207 0.525461 0.841699 0.124231 0.464432 0.874012 0.142848 0.718774 0.695244 0.000667228 0.63953 0.76817 0.0302762 -0.833638 0.131836 0.536346 -0.858812 0.0923038 0.503908 -0.708278 0.33449 0.621658 -0.732392 0.310838 0.60579 -0.488445 0.561332 0.668078 -0.535273 0.537043 0.651972 -0.252979 0.706728 0.660709 -0.908353 0.102471 0.405455 0.606949 0.753581 0.252445 0.449147 0.820569 0.353459 0.103618 0.793022 0.600316 0.297858 0.795096 0.528302 0.136299 0.774245 0.618035 0.143601 0.773037 0.617894 -0.0961533 0.729322 0.67738 -0.900833 0.140685 0.410739 -0.83108 0.315621 0.457919 -0.798796 0.386264 0.461222 -0.764141 0.437961 0.473581 -0.609222 0.620887 0.493303 -0.615765 0.61592 0.491402 -0.350085 0.818773 0.455029 -0.369485 0.810682 0.454175 -0.0358207 0.92132 0.387152 -0.166947 0.906024 0.388907 -0.00787382 0.932635 0.360735 -0.961475 4.63323e-05 -0.274892 -0.99718 -0.00336416 -0.0749736 -0.942784 0 0.333404 -0.877537 -0.0163037 0.479232 -0.903915 -0.0111365 0.427568 -0.940994 -0.0044613 0.338395 -0.989848 0.00279109 0.142105 -0.992505 -0.00859448 -0.121902 -0.543995 0 -0.839088 -0.575995 -0.0033154 -0.817446 -0.919604 -0.000144263 -0.392848 -0.833499 -0.00977144 -0.552435 -0.859235 -0.00471493 -0.51156 -0.748994 3.09457e-05 -0.662577 -0.690793 -3.51185e-05 -0.723052 0.826012 0.121226 0.550462 0.830422 0.15134 0.536186 0.810009 0.389359 0.438503 0.804777 0.427752 0.411536 0.722653 0.629266 0.286001 0.701351 0.669591 0.244448 0.575262 0.81022 0.112329 0.534527 0.843132 0.0583827 0.784295 0.100479 0.612198 0.796564 0.13965 0.588204 0.809776 0.337786 0.479754 0.811861 0.388185 0.436114 0.773584 0.553542 0.308478 0.756123 0.607742 0.242749 0.680312 0.723412 0.117685 0.63674 0.770363 0.0332266 0.481028 -0.00660713 -0.87668 0.481081 0.00240515 -0.876673 0.481077 0.00188339 -0.876676 0.481039 0 -0.876699 0.481039 0 -0.876699 0.481054 0.000221434 -0.876691 0.481035 -0.00020962 -0.876701 0.786592 0 0.617473 0.800134 -0.0594395 0.596869 0.757959 0 0.652302 0.948423 -0.000692384 -0.317006 0.923702 0.00767382 0.383035 0.932076 0 0.362262 0.999822 0.00223214 -0.0187511 0.996498 -0.0215065 -0.0808023 0.991637 -0.00208117 0.129041 0.862776 -0.0248826 -0.504974 0.890749 -0.00490596 -0.45447 0.719766 0.0019335 -0.694215 0.63429 -0.0139606 -0.772969 0.566718 0 -0.823912 -0.888097 0 0.459657 -0.923965 0.0304674 0.381261 -0.910763 0 0.412929 -0.882147 0.220638 0.416096 -0.870535 0.267521 0.41304 -0.831871 0.387015 0.397757 -0.770112 0.520204 0.369209 -0.583056 0.762079 0.28157 -0.887615 0 0.460587 -0.876293 -0.0028505 0.481769 -0.758661 0.00105288 0.651485 -0.617926 -0.00749708 0.786201 0.103783 -0.00134256 0.994599 -0.138098 0.00367616 0.990412 -0.210989 -0.00694444 0.977464 -0.36948 -0.000497235 0.929238 -0.562584 0.00176056 0.826738 0.59955 0 0.800337 0.67314 -0.0142903 0.739377 0.570271 -0.00346576 0.82145 0.238606 0.00951703 0.97107 0.411533 -0.0317268 0.910842 0.221082 -0.00770578 0.975225 0.316376 0.173201 -0.932689 -0.774714 0.173047 -0.608172 -0.774713 0.173068 -0.608167 -0.714212 0.418984 -0.560673 -0.671199 0.532215 -0.515983 -0.62776 0.602542 -0.492808 -0.428952 0.838217 -0.336739 -0.490689 0.78965 -0.368344 -0.128042 0.984312 -0.121388 -0.206684 0.964861 -0.162252 -0.0222612 0.988082 -0.152313 -0.0211184 0.983989 -0.176974 -0.0452267 0.837029 -0.545287 0.217954 0.537901 -0.814346 0.208587 0.582302 -0.785758 0.187009 0.538157 -0.821836 0.10585 0.779254 -0.617704 0.163553 0.771435 -0.614929 -0.0333526 0.868171 -0.495143 -0.0569973 0.529866 -0.846164 -0.0569974 0.529867 -0.846163 -0.0662094 0.171707 -0.982921 -0.066209 0.171704 -0.982921 -0.0872663 0.98367 -0.15741 -0.0872667 0.98367 -0.157411 -0.265916 0.836193 -0.479657 -0.265915 0.836195 -0.479653 -0.411205 0.529862 -0.741725 -0.411205 0.529862 -0.741725 -0.477663 0.171711 -0.8616 -0.477663 0.171717 -0.861598 -0.547791 0.173471 -0.818433 -0.443505 0.60352 -0.662621 -0.406468 0.703306 -0.583219 -0.341519 0.789311 -0.510249 -0.238825 0.90313 -0.356818 -0.155015 0.965475 -0.209352 -0.0990886 0.984004 -0.148044 -0.783438 0.173473 -0.596768 -0.762072 0.255988 -0.594741 -0.547073 0.255986 -0.796983 -0.504828 0.419844 -0.754241 -0.721985 0.419861 -0.549958 -0.634292 0.603516 -0.48316 -0.557298 0.703306 -0.441339 -0.488433 0.789309 -0.372055 -0.208533 0.96503 -0.158846 -0.208534 0.965029 -0.158847 -0.561933 0.8084 0.175272 -0.849201 0.434364 0.30031 -0.568788 0.815674 0.105625 -0.724127 0.670706 0.1606 -0.811708 0.536295 0.23134 -0.943952 0.174292 0.280314 -0.149809 0.988515 -0.0198753 -0.314504 0.837774 -0.446342 -0.343415 0.789136 -0.509244 -0.248182 0.902413 -0.352216 -0.567338 0.172757 -0.80516 -0.567338 0.172751 -0.805161 -0.487624 0.532273 -0.692032 -0.506171 0.419743 -0.753397 -0.459987 0.601874 -0.652809 -0.472111 0.835527 -0.28108 -0.472109 0.835529 -0.281078 -0.729247 0.528862 -0.43417 -0.729246 0.528865 -0.434169 -0.84655 0.171262 -0.504007 -0.84655 0.171262 -0.504007 -0.982452 0.171264 -0.0738663 -0.982453 0.171259 -0.0738669 -0.846322 0.528858 -0.0636317 -0.846317 0.528866 -0.0636299 -0.555474 0.830485 -0.0417631 -0.548135 0.835422 -0.0402284 -0.178316 0.983794 -0.0187711 -0.155043 0.983586 -0.0923077 -0.155042 0.983586 -0.0923072 -0.103037 0.98387 -0.146229 -0.103038 0.98387 -0.146231 -0.129355 -0.705332 -0.696975 -0.159177 -0.186226 -0.969527 0.0381704 -0.479656 -0.876626 0.0733776 0.366071 -0.927689 -0.015547 -0.69962 -0.714346 -0.0273997 -0.707106 -0.706577 -0.0442954 -0.707031 -0.705794 0.29568 -0.70709 -0.642337 0.292268 -0.65358 -0.698149 0.324188 0.0343261 -0.94537 0.299913 0.306995 -0.90322 0.171233 -0.706751 -0.686427 0.103884 -0.706618 -0.699928 0.511033 -0.704513 -0.492449 0.399607 -0.705864 -0.584867 0.521876 0.204082 -0.828249 0.400797 -0.552991 -0.730454 0.316936 -0.707012 -0.632207 0.821137 0.0810156 -0.564952 0.739414 -0.551274 -0.386476 0.807539 -0.402259 -0.431358 0.721094 0.552627 -0.417884 0.586421 -0.706628 -0.395964 0.51103 -0.704518 -0.492446 0.646235 -0.707075 -0.287097 0.681347 -0.704516 -0.198552 0.681347 -0.704516 -0.198552 0.832697 0.552628 -0.0349085 0.912858 -0.402235 -0.0699821 0.831272 -0.551282 -0.0712415 0.699298 -0.707075 -0.105005 0.663732 -0.706927 0.244367 0.695573 -0.704518 0.140828 0.695575 -0.704516 0.140829 0.705414 -0.707092 0.0491044 0.775225 -0.631511 0.0148617 0.993164 -0.113813 0.0259054 0.905231 0.0474585 0.422261 0.885115 0.204084 0.418236 0.730452 -0.552997 0.400793 0.781293 0.0343225 0.62322 0.738174 0.307001 0.600708 0.621566 -0.653575 0.431852 0.59446 -0.707087 0.382942 0.606947 -0.707009 0.362979 0.370633 -0.699623 0.610867 0.503121 -0.479658 0.718887 0.560249 0.366066 0.743045 0.463623 -0.706621 0.534547 0.513175 -0.706754 0.486981 0.356467 -0.707107 0.610681 0.279232 -0.704517 0.652446 0.279233 -0.704515 0.652448 0.486394 0 0.873739 0.517818 0.0590904 0.853447 0.695964 0 0.718077 0.8383 0 0.54521 0.872448 0.098361 0.478706 0.950846 0 0.309664 0.999763 0 -0.0217577 0.9754 0.201917 0.0884575 -0.0591257 0 -0.998251 -0.0217197 0.059091 -0.998016 0.201261 0 -0.979538 0.294446 0 -0.955668 0.413586 -0.053399 -0.908898 0.48099 0.0145058 -0.876606 0.635627 -0.00667511 -0.771967 0.647877 0 -0.761745 0.791488 0 -0.611185 0.84898 0.11789 -0.515107 0.922704 0 -0.38551 0.985354 0 -0.170522 0.986379 0 0.164488 0.817327 0 0.576174 0.817327 0 0.576174 0.486394 0 0.873739 0.486394 0 0.873739 0.958071 -0.0644439 -0.279191 0.97362 0 -0.228175 0.986379 0 0.164488 0.67305 -0.142021 -0.725833 0.82606 0 -0.563582 0.898438 0 -0.439101 0.7436 0 -0.668625 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591246 0 -0.998251 -0.0591246 0 -0.998251 0.518724 0 0.854942 0.485245 -0.0686876 0.871676 0.836835 0.0590877 0.544257 0.817328 0 0.576172 0.967412 0 0.253208 0.949372 0.0556624 0.309183 0.997576 -0.0634961 0.0284719 0.995913 0 0.0903194 0.993677 0 -0.112279 0.985108 -0.0223083 -0.170482 0.942745 0.0467916 -0.330215 0.922705 0 -0.385507 0.791487 0 -0.611186 0.741276 0.0789913 -0.666536 0.63564 0 -0.771985 0.414178 0 -0.910196 0.379392 0.0493941 -0.923917 -0.0217198 -0.0590896 -0.998016 -0.0591249 0 -0.998251 0.486393 0 0.87374 0.865316 -0.160627 0.474791 0.736988 0 0.675906 0.486393 0 0.87374 0.81703 0.027012 0.575962 0.986107 -0.023482 0.164445 0.988877 0 0.148732 0.960066 0 -0.279775 0.960066 0 -0.279775 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591246 0 -0.998251 -0.0591246 0 -0.998251 0.335751 0 0.941951 0.516888 -0.0840337 0.851919 0.516889 -0.0840358 0.851918 0.652453 -0.0156396 0.757668 0.836835 0.0590899 0.544257 0.817328 0 0.576173 0.950846 0 0.309664 0.983297 0.0789904 0.163976 0.995913 0 0.0903178 0.985354 0 -0.170523 0.95627 0.0888317 -0.278669 0.922705 0 -0.385508 0.791487 0 -0.611186 0.741276 0.0789907 -0.666536 0.635641 0 -0.771985 0.414178 0 -0.910196 0.379392 0.0493945 -0.923917 -0.0217197 -0.0590892 -0.998016 -0.0591246 0 -0.998251 -0.0591235 0 -0.998251 -0.0217197 0.0590874 -0.998017 0.478706 0.0983587 -0.872448 0.414179 0 -0.910195 0.201248 0 -0.97954 0.985354 0 -0.170522 0.922705 0 -0.385508 0.84898 0.117891 -0.515107 0.791487 0 -0.611186 0.635639 0 -0.771987 0.9754 0.201915 0.0884567 0.999763 0 -0.0217578 0.950846 0 0.309664 0.872448 0.0983605 0.478706 0.8383 0 0.545209 0.695966 0 0.718075 0.517819 0.0590914 0.853447 0.486394 0 0.873739 0.379391 0.0493944 -0.923917 -0.0217197 -0.0590892 -0.998016 -0.0591246 0 -0.998251 0.922705 0 -0.385508 0.791487 0 -0.611186 0.741276 0.0789907 -0.666536 0.635641 0 -0.771985 0.414178 0 -0.910196 0.970231 0.174528 -0.167904 0.960066 0 -0.279774 0.995913 0 0.0903171 0.983297 0.0789912 0.163976 0.950846 0 0.309665 0.817328 0 0.576173 0.836835 0.0590908 0.544256 0.485247 -0.0686846 0.871675 0.518725 0 0.854941 -0.0217578 0 -0.999763 -0.120057 -0.18191 -0.975959 0.13895 0 -0.990299 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217578 0.999763 0 -0.0217578 0.876699 0 0.481039 0.876699 0 0.481039 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591249 0 -0.998251 -0.0591249 0 -0.998251 0.379854 0 -0.925046 0.379854 0 -0.925046 0.743601 0 -0.668624 0.743601 0 -0.668624 0.960066 0 -0.279775 0.960066 0 -0.279775 0.986379 0 0.164488 0.986379 0 0.164488 0.817327 0 0.576174 0.817327 0 0.576174 0.486394 0 0.873739 0.486394 0 0.873739 -0.0217578 0 -0.999763 -0.0217578 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217578 0.999763 0 -0.0217578 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 -0.0217578 0 -0.999763 -0.0217578 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217578 0.999763 0 -0.0217578 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 0.143314 0 -0.989677 0.379855 0 -0.925046 0.379855 0 -0.925046 0.7436 0 -0.668624 0.7436 0 -0.668624 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164489 0.986379 0 0.164489 0.817327 0 0.576173 0.817327 0 0.576173 0.486394 0 0.873739 0.486394 0 0.873739 -0.0217519 -0.025134 -0.999447 -0.0589834 -0.0687868 -0.995886 -0.222826 0 -0.974858 -0.0423355 -0.698074 -0.714774 -0.0423349 -0.698076 -0.714772 0.142363 -0.706861 -0.692878 0.239089 -0.777063 -0.582246 0.295431 -0.700863 -0.64924 0.450095 -0.706117 -0.546639 0.434068 -0.811942 -0.390302 0.5628 -0.703125 -0.434593 0.687432 -0.698074 -0.200326 0.434314 -0.882295 -0.181458 0.698945 -0.704872 -0.120957 0.706273 -0.698073 0.117779 0.533415 -0.844469 0.0483746 0.67329 -0.706117 0.219271 0.585227 -0.698075 0.412554 0.516924 -0.78725 0.336195 0.492291 -0.706861 0.507933 0.34827 -0.698076 0.625618 0.348271 -0.698074 0.62562 -0.317839 -0.701415 -0.637962 -0.317839 -0.701415 -0.637962 -0.711928 -0.697265 -0.0835427 -0.711929 -0.697265 -0.0835428 -0.597623 -0.697265 -0.395814 -0.597623 -0.697265 -0.395813 -0.354703 -0.697265 -0.622902 -0.354703 -0.697267 -0.6229 -0.289574 -0.703804 -0.648696 -0.289574 -0.703805 -0.648695 -0.703144 -0.698432 -0.133348 -0.703142 -0.698434 -0.133347 -0.579402 -0.698433 -0.4201 -0.579402 -0.698433 -0.4201 -0.345323 -0.698433 -0.626852 -0.345323 -0.698434 -0.626851 -0.334404 -0.699696 -0.631348 -0.334404 -0.699696 -0.631348 -0.526143 -0.701185 -0.481159 -0.526143 -0.701184 -0.48116 -0.320171 -0.701184 -0.637048 -0.320171 -0.701185 -0.637048 -0.0156496 -0.694746 -0.719085 -0.01565 -0.694747 -0.719084 0.34599 -0.694747 -0.63057 0.34599 -0.694747 -0.63057 0.61492 -0.694747 -0.373095 0.614921 -0.694747 -0.373095 0.719085 -0.694746 -0.0156496 0.719084 -0.694747 -0.01565 0.63057 -0.694747 0.34599 0.63057 -0.694747 0.34599 0.373095 -0.694747 0.61492 0.373095 -0.694747 0.614921 -0.0156496 -0.694747 -0.719084 -0.0156494 -0.694747 -0.719084 0.34599 -0.694747 -0.63057 0.345989 -0.694747 -0.63057 0.61492 -0.694747 -0.373095 0.614922 -0.694745 -0.373094 0.719086 -0.694745 -0.015648 0.719083 -0.694748 -0.0156511 0.630569 -0.694748 0.345988 0.63057 -0.694745 0.345991 0.373095 -0.694746 0.614922 0.373095 -0.694747 0.61492 -0.0156495 -0.694748 -0.719083 -0.0156488 -0.694747 -0.719084 0.34599 -0.694747 -0.63057 0.345988 -0.694748 -0.63057 0.61492 -0.694748 -0.373094 0.61492 -0.694747 -0.373094 0.719083 -0.694748 -0.0156495 0.719084 -0.694747 -0.0156488 0.63057 -0.694747 0.34599 0.63057 -0.694747 0.345989 0.373095 -0.694747 0.614921 0.373095 -0.694747 0.61492 -0.0156511 -0.694748 -0.719083 -0.0156488 -0.694745 -0.719085 0.345991 -0.694745 -0.63057 0.345989 -0.694747 -0.63057 0.614919 -0.694747 -0.373096 0.614921 -0.694746 -0.373095 0.719084 -0.694747 -0.0156495 0.719084 -0.694747 -0.0156494 0.63057 -0.694747 0.34599 0.63057 -0.694746 0.345991 0.373094 -0.694745 0.614923 0.373095 -0.694747 0.61492 -0.0156511 -0.694748 -0.719083 -0.0156488 -0.694746 -0.719085 0.345991 -0.694745 -0.63057 0.345988 -0.694747 -0.63057 0.614919 -0.694747 -0.373096 0.614922 -0.694746 -0.373095 0.719084 -0.694746 -0.0156491 0.719084 -0.694747 -0.0156494 0.63057 -0.694747 0.34599 0.63057 -0.694747 0.345989 0.373095 -0.694747 0.61492 0.373095 -0.694745 0.614922 -0.0156496 -0.694747 -0.719084 -0.0156491 -0.694746 -0.719085 0.34599 -0.694746 -0.63057 0.345989 -0.694747 -0.63057 0.61492 -0.694747 -0.373095 0.614922 -0.694745 -0.373095 0.719086 -0.694745 -0.015648 0.719083 -0.694748 -0.0156511 0.630569 -0.694748 0.345988 0.63057 -0.694745 0.345991 0.373095 -0.694746 0.614922 0.373096 -0.694747 0.61492 0.348271 -0.698073 0.625621 0.348271 -0.698073 0.62562 0.492298 -0.706859 0.507931 0.597545 -0.682274 0.421239 0.597956 -0.700861 0.3889 0.673292 -0.706115 0.219269 0.730222 -0.672271 0.121771 0.708161 -0.703124 0.0642198 0.698946 -0.704873 -0.120952 0.713716 -0.668844 -0.207985 0.654505 -0.704872 -0.273457 0.532438 -0.698073 -0.478753 0.601342 -0.650201 -0.464356 0.450093 -0.706116 -0.546641 0.271987 -0.698074 -0.662357 -0.0423356 -0.698074 -0.714773 -0.0423353 -0.698074 -0.714773 0.142361 -0.706859 -0.69288 0.305415 -0.675459 -0.671176 0.348271 -0.698074 0.625619 0.348271 -0.698073 0.625621 0.492292 -0.706859 0.507935 0.597546 -0.682274 0.421238 0.597957 -0.700862 0.388896 0.673289 -0.706116 0.219274 0.730221 -0.672271 0.121772 0.708161 -0.703124 0.0642224 0.687433 -0.698073 -0.200325 0.771535 -0.622018 -0.133521 0.654505 -0.704873 -0.273453 0.532437 -0.698074 -0.478753 0.601341 -0.650203 -0.464355 0.450093 -0.706117 -0.54664 0.271985 -0.698074 -0.662357 -0.0423348 -0.698075 -0.714773 -0.0423339 -0.698074 -0.714773 0.142358 -0.706859 -0.692881 0.305414 -0.675459 -0.671176 -0.015648 -0.694745 -0.719086 -0.0156488 -0.694745 -0.719085 0.345989 -0.694746 -0.630571 0.34599 -0.694745 -0.630571 0.614922 -0.694746 -0.373095 0.61492 -0.694747 -0.373096 0.719084 -0.694747 -0.0156496 0.719084 -0.694747 -0.0156494 0.63057 -0.694747 0.345988 0.630571 -0.694745 0.34599 0.373094 -0.694745 0.614923 0.373095 -0.694747 0.61492 -0.0423345 -0.698077 -0.71477 -0.0423349 -0.698076 -0.714772 0.271985 -0.698076 -0.662355 0.271986 -0.698075 -0.662356 0.532436 -0.698074 -0.478752 0.532435 -0.698076 -0.478751 0.687429 -0.698077 -0.200324 0.687433 -0.698073 -0.200326 0.706273 -0.698073 0.117778 0.706272 -0.698074 0.117778 0.585226 -0.698075 0.412555 0.58523 -0.698071 0.412556 0.348271 -0.698073 0.625621 0.348272 -0.698073 0.625621 0.34599 -0.694745 -0.630571 -0.0156494 -0.694748 -0.719083 -0.0156494 -0.694748 -0.719083 0.213128 -0.857442 -0.468369 0.450093 -0.706119 -0.546638 0.614918 -0.69475 -0.373093 0.352099 -0.895601 -0.271891 0.654506 -0.704873 -0.273453 0.698944 -0.704873 -0.120959 0.532451 -0.846381 -0.0115873 0.708158 -0.703127 0.064223 0.673289 -0.706118 0.219271 0.489727 -0.829436 0.268709 0.597959 -0.70086 0.388898 0.373095 -0.694745 0.614922 0.373095 -0.694746 0.614921 -0.0423346 -0.698075 -0.714772 -0.042335 -0.698074 -0.714773 0.271986 -0.698074 -0.662357 0.271986 -0.698075 -0.662356 0.532436 -0.698074 -0.478753 0.532435 -0.698076 -0.478751 0.687429 -0.698077 -0.200325 0.687427 -0.698079 -0.200324 0.706267 -0.69808 0.117778 0.706272 -0.698074 0.117778 0.585227 -0.698075 0.412554 0.585224 -0.698078 0.412553 0.348269 -0.698077 0.625617 0.348272 -0.698072 0.625621 0.345989 -0.694748 -0.630569 -0.0156488 -0.694749 -0.719082 -0.0156494 -0.694746 -0.719085 0.213128 -0.857442 -0.468369 0.450095 -0.706117 -0.546639 0.61492 -0.694747 -0.373095 0.3521 -0.895601 -0.271892 0.654506 -0.704872 -0.273454 0.698945 -0.704873 -0.120958 0.532454 -0.846379 -0.0115879 0.708162 -0.703123 0.0642221 0.673292 -0.706115 0.219272 0.489727 -0.829435 0.26871 0.597955 -0.700864 0.388895 0.373093 -0.69475 0.614918 0.373096 -0.694745 0.614921 -0.042334 -0.698073 -0.714774 -0.0423353 -0.698069 -0.714778 0.142354 -0.706855 -0.692886 0.23909 -0.777063 -0.582244 0.295433 -0.700863 -0.649239 0.450093 -0.706117 -0.54664 0.434067 -0.811943 -0.390302 0.5628 -0.703125 -0.434594 0.654505 -0.704873 -0.273454 0.54681 -0.821954 -0.159346 0.698943 -0.704874 -0.120957 0.706273 -0.698073 0.117779 0.533415 -0.84447 0.0483741 0.67329 -0.706116 0.219272 0.585229 -0.698073 0.412555 0.516925 -0.78725 0.336195 0.492293 -0.706861 0.507932 0.34827 -0.698076 0.625618 0.348267 -0.69808 0.625615 0.345989 -0.694748 -0.630569 -0.0156496 -0.694749 -0.719082 -0.0156493 -0.69475 -0.719081 0.213128 -0.857442 -0.468369 0.450095 -0.706117 -0.546639 0.61492 -0.694747 -0.373095 0.3521 -0.895601 -0.271891 0.654505 -0.704874 -0.273453 0.698943 -0.704874 -0.120956 0.532454 -0.846379 -0.0115879 0.708161 -0.703125 0.0642215 0.673291 -0.706115 0.219273 0.489729 -0.829434 0.268711 0.597958 -0.70086 0.388897 0.373097 -0.694744 0.614922 0.373091 -0.694753 0.614916 -0.0156494 -0.694746 -0.719085 -0.0156492 -0.694747 -0.719084 0.345989 -0.694746 -0.63057 0.345989 -0.694747 -0.63057 0.61492 -0.694747 -0.373095 0.614919 -0.694749 -0.373094 0.719081 -0.69475 -0.0156493 0.719082 -0.694749 -0.0156496 0.630569 -0.694748 0.345989 0.63057 -0.694747 0.345989 0.373095 -0.694747 0.61492 0.373093 -0.69475 0.614918 -0.0423349 -0.698074 -0.714773 -0.0423349 -0.698074 -0.714773 0.271985 -0.698074 -0.662356 0.271985 -0.698077 -0.662354 0.532434 -0.698079 -0.478749 0.532438 -0.698072 -0.478755 0.687434 -0.698071 -0.200327 0.687433 -0.698073 -0.200326 0.706273 -0.698073 0.117778 0.706266 -0.698081 0.117779 0.585223 -0.69808 0.412552 0.585225 -0.698077 0.412553 0.34827 -0.698076 0.625618 0.348272 -0.698073 0.62562 -0.0156494 -0.694746 -0.719085 -0.0156488 -0.694749 -0.719082 0.345989 -0.694748 -0.630569 0.345989 -0.694747 -0.63057 0.614921 -0.694747 -0.373094 0.614922 -0.694745 -0.373095 0.719085 -0.694746 -0.0156494 0.719086 -0.694745 -0.0156496 0.63057 -0.694747 0.34599 0.630569 -0.694747 0.345989 0.373095 -0.694747 0.61492 0.373094 -0.694749 0.614919 -0.0156494 -0.694746 -0.719085 -0.0156488 -0.694749 -0.719082 0.345989 -0.694748 -0.630569 0.34599 -0.694744 -0.630573 0.614922 -0.694745 -0.373096 0.61492 -0.694747 -0.373094 0.719085 -0.694746 -0.0156494 0.719084 -0.694747 -0.0156492 0.63057 -0.694746 0.34599 0.630569 -0.694747 0.345989 0.373095 -0.694747 0.61492 0.373095 -0.694747 0.61492 -0.0423336 -0.69808 -0.714767 -0.0423349 -0.698076 -0.714772 0.271985 -0.698076 -0.662355 0.271986 -0.698075 -0.662356 0.532437 -0.698074 -0.478752 0.532437 -0.698074 -0.478752 0.687432 -0.698074 -0.200326 0.687432 -0.698074 -0.200326 0.706272 -0.698075 0.117778 0.706272 -0.698075 0.117778 0.585225 -0.698077 0.412553 0.585227 -0.698075 0.412554 0.34827 -0.698076 0.625618 0.348272 -0.698073 0.62562 -0.445932 0 -0.895067 -0.445932 0 -0.895067 -0.25989 0 0.965638 -0.253 0.00100166 0.967466 0.10123 -0.00096287 0.994863 0.108318 0 0.994116 -0.993185 0 -0.116547 -0.993185 0 -0.116547 -0.833722 0 -0.552185 -0.833722 0 -0.552185 -0.494834 0 -0.868988 -0.494834 0 -0.868988 0.0657166 0 0.997838 0.0799341 -0.00208073 0.996798 0.26606 0 0.963956 -0.407624 0 -0.91315 -0.407624 0 -0.91315 -0.982488 0 -0.186324 -0.982488 0 -0.186324 -0.809588 0 -0.586999 -0.809588 0 -0.586999 -0.482514 0 -0.875888 -0.482514 0 -0.875888 -0.0591247 0 -0.998251 -0.0217579 0.00363663 -0.999757 0.201255 0 -0.979539 0.414178 0 -0.910196 0.48103 0.00607244 -0.876683 0.635643 0 -0.771983 0.791486 0 -0.611187 0.854919 0.00729373 -0.518711 0.922705 0 -0.385507 0.985354 0 -0.17052 0.999737 0.00729353 -0.0217575 0.995913 0 0.0903148 0.950845 0 0.309667 0.876683 0.0060723 0.48103 0.8383 0 0.545209 0.695955 0 0.718085 0.518721 0.00363657 0.854936 0.486396 0 0.873739 -0.0217581 0 -0.999763 -0.0217581 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217559 0.999763 0 -0.0217559 0.8767 0 0.481037 0.8767 0 0.481037 0.518724 0 0.854942 0.518724 0 0.854942 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.021758 0.999763 0 -0.021758 0.876699 0 0.481039 0.876699 0 0.481039 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591272 0 -0.99825 -0.0217601 0.00363666 -0.999757 0.201253 0 -0.979539 0.414179 0 -0.910196 0.481032 0.00607253 -0.876682 0.635646 0 -0.771981 0.791484 0 -0.611189 0.854918 0.0072938 -0.518712 0.922705 0 -0.385507 0.985354 0 -0.170521 0.999737 0.00729365 -0.0217574 0.995913 0 0.0903164 0.950845 0 0.309666 0.876683 0.00607229 0.48103 0.838301 0 0.545208 0.695963 0 0.718078 0.518719 0.00363675 0.854937 0.486391 0 0.873741 -0.0217602 0 -0.999763 -0.0217602 0 -0.999763 0.481041 0 -0.876698 0.481041 0 -0.876698 0.854941 0 -0.518726 0.854941 0 -0.518726 0.999763 0 -0.0217574 0.999763 0 -0.0217574 0.876699 0 0.481039 0.876699 0 0.481039 0.518726 0 0.854941 0.518726 0 0.854941 -0.0217581 0 -0.999763 -0.0217581 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217559 0.999763 0 -0.0217559 0.8767 0 0.481037 0.8767 0 0.481037 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591258 0 -0.998251 -0.0217578 -0.00363675 -0.999757 0.201259 0 -0.979538 0.414179 0 -0.910195 0.48103 -0.00607231 -0.876683 0.635638 0 -0.771987 0.791487 0 -0.611185 0.854918 -0.00729355 -0.518712 0.922703 0 -0.385512 0.985355 0 -0.170515 0.999737 -0.00729339 -0.0217553 0.995913 0 0.0903147 0.950847 0 0.30966 0.876682 -0.0060726 0.481032 0.486395 0 0.873739 0.518722 -0.0036368 0.854935 0.69597 0 0.71807 0.838297 0 0.545213 -0.0591247 0 -0.998251 -0.0217579 -0.00363663 -0.999757 0.201255 0 -0.979539 0.414178 0 -0.910196 0.481029 -0.00607235 -0.876683 0.635639 0 -0.771986 0.791487 0 -0.611186 0.854919 -0.00729369 -0.51871 0.922705 0 -0.385507 0.985353 0 -0.170525 0.999737 -0.00729377 -0.0217574 0.995913 0 0.0903182 0.950845 0 0.309667 0.876683 -0.0060723 0.48103 0.486394 0 0.87374 0.518721 -0.00363671 0.854936 0.695963 0 0.718078 0.8383 0 0.545209 -0.0591222 0 -0.998251 -0.0217557 0.00363659 -0.999757 0.201253 0 -0.979539 0.414179 0 -0.910196 0.481029 0.00607222 -0.876684 0.635637 0 -0.771988 0.791487 0 -0.611186 0.854919 0.00729369 -0.51871 0.922705 0 -0.385507 0.985354 0 -0.170521 0.999737 0.00729364 -0.0217575 0.995913 0 0.090317 0.950847 0 0.309662 0.876684 0.00607246 0.481028 0.838301 0 0.545208 0.695963 0 0.718078 0.518719 0.00363675 0.854937 0.486391 0 0.873741 -0.0156496 -0.694746 -0.719085 -0.0156496 -0.694746 -0.719085 0.34599 -0.694746 -0.630571 0.345989 -0.694746 -0.630571 0.614921 -0.694746 -0.373095 0.614921 -0.694746 -0.373095 0.719085 -0.694746 -0.0156496 0.719085 -0.694746 -0.0156492 0.630571 -0.694745 0.345991 0.63057 -0.694746 0.345989 0.373095 -0.694747 0.61492 0.373095 -0.694747 0.61492 -0.031021 -0.851306 -0.523752 0.216079 -0.853126 -0.474853 0.411013 -0.854596 -0.317385 0.509848 -0.855728 -0.0882314 0.490729 -0.85653 0.159819 0.255197 -0.851306 0.458425 0.358628 -0.857008 0.370031 0.437345 -0.853126 0.284438 0.517171 -0.854596 0.0468998 0.477432 -0.855728 -0.199471 0.328054 -0.85653 -0.398419 0.103707 -0.857008 -0.504759 0.45158 -0.84912 -0.273991 0.254085 -0.84912 -0.463073 -0.0114926 -0.84912 -0.528075 0.27399 -0.84912 0.45158 0.463073 -0.84912 0.254084 0.528075 -0.84912 -0.0114915 0.451581 -0.84912 -0.27399 0.254085 -0.84912 -0.463073 -0.0114926 -0.84912 -0.528075 0.27399 -0.84912 0.45158 0.463073 -0.84912 0.254085 0.528075 -0.84912 -0.0114926 -0.0310223 -0.851305 -0.523753 0.216079 -0.853126 -0.474853 0.411012 -0.854596 -0.317386 0.509848 -0.855728 -0.0882322 0.490729 -0.85653 0.159818 0.255195 -0.851306 0.458426 0.358631 -0.857009 0.370027 0.437345 -0.853126 0.284438 0.517171 -0.854596 0.0469006 0.477432 -0.855728 -0.199472 0.328055 -0.856529 -0.398418 0.103706 -0.857008 -0.504759 0.45158 -0.84912 -0.273991 0.254086 -0.84912 -0.463072 -0.0114937 -0.84912 -0.528075 0.273991 -0.84912 0.45158 0.463073 -0.84912 0.254085 0.528075 -0.84912 -0.0114923 0.45158 -0.84912 -0.273991 0.254085 -0.84912 -0.463073 -0.0114926 -0.84912 -0.528075 0.27399 -0.84912 0.45158 0.463073 -0.84912 0.254084 0.528075 -0.84912 -0.0114915 0.45158 -0.84912 -0.273991 0.254085 -0.84912 -0.463073 -0.0114926 -0.84912 -0.528075 0.273991 -0.84912 0.45158 0.463072 -0.84912 0.254086 0.528075 -0.84912 -0.0114915 0.45158 -0.84912 -0.27399 0.254085 -0.84912 -0.463073 -0.0114926 -0.84912 -0.528075 0.27399 -0.84912 0.45158 0.463072 -0.84912 0.254085 0.528075 -0.84912 -0.0114926 -0.0310197 -0.851306 -0.523752 0.216079 -0.853126 -0.474853 0.411014 -0.854596 -0.317384 0.509848 -0.855728 -0.0882322 0.49073 -0.85653 0.159816 0.255195 -0.851306 0.458426 0.358631 -0.857009 0.370027 0.437345 -0.853126 0.284438 0.517171 -0.854596 0.046901 0.477432 -0.855728 -0.199472 0.328051 -0.85653 -0.398422 0.103706 -0.857008 -0.504759 -0.0156496 -0.694746 -0.719085 -0.0156496 -0.694746 -0.719085 0.34599 -0.694746 -0.63057 0.34599 -0.694746 -0.63057 0.614922 -0.694746 -0.373095 0.614921 -0.694747 -0.373095 0.719085 -0.694746 -0.0156496 0.719085 -0.694746 -0.0156496 0.63057 -0.694746 0.345989 0.630571 -0.694746 0.34599 0.373095 -0.694746 0.614922 0.373095 -0.694746 0.614921 -0.0423349 -0.698073 -0.714774 -0.0423349 -0.698073 -0.714774 0.271987 -0.698073 -0.662357 0.271987 -0.698073 -0.662357 0.532438 -0.698073 -0.478753 0.532436 -0.698074 -0.478753 0.687431 -0.698074 -0.200326 0.687431 -0.698074 -0.200326 0.706272 -0.698074 0.117777 0.706274 -0.698073 0.117779 0.585228 -0.698073 0.412557 0.585227 -0.698074 0.412555 0.348272 -0.698074 0.625619 0.348271 -0.698072 0.625621 -0.0156484 -0.694745 -0.719086 -0.0156496 -0.694746 -0.719085 0.345989 -0.694746 -0.63057 0.34599 -0.694746 -0.630571 0.614921 -0.694746 -0.373096 0.61492 -0.694746 -0.373096 0.719085 -0.694746 -0.0156496 0.719085 -0.694746 -0.0156496 0.63057 -0.694746 0.34599 0.63057 -0.694746 0.34599 0.373095 -0.694746 0.614921 0.373095 -0.694746 0.61492 0.373096 -0.694746 0.614921 0.363728 -0.663921 0.653385 0.492291 -0.706859 0.507938 0.630571 -0.694746 0.34599 0.651893 -0.628713 0.423975 0.673291 -0.706116 0.219271 0.719085 -0.694746 -0.0156496 0.805144 -0.588567 0.0730173 0.698945 -0.704873 -0.120958 0.654505 -0.704873 -0.273455 0.651699 -0.647256 -0.39541 0.562802 -0.703123 -0.434593 0.450093 -0.706114 -0.546643 0.363155 -0.655795 -0.661855 -0.0423348 -0.698075 -0.714773 -0.016109 -0.672101 -0.740284 0.142357 -0.706858 -0.692883 0.295434 -0.70086 -0.649241 -0.0156496 -0.694747 -0.719084 -0.0156495 -0.694747 -0.719083 0.345989 -0.694747 -0.630569 0.345989 -0.694747 -0.63057 0.614921 -0.694747 -0.373095 0.614921 -0.694746 -0.373095 0.719085 -0.694746 -0.0156494 0.719085 -0.694746 -0.0156493 0.63057 -0.694746 0.34599 0.630571 -0.694745 0.34599 0.373096 -0.694745 0.614922 0.373096 -0.694745 0.614922 -0.0423347 -0.698074 -0.714773 -0.0423348 -0.698074 -0.714773 0.271984 -0.698074 -0.662357 0.271988 -0.698072 -0.662358 0.532438 -0.698072 -0.478754 0.532438 -0.698073 -0.478754 0.687433 -0.698073 -0.200326 0.687433 -0.698073 -0.200326 0.706273 -0.698073 0.117779 0.706274 -0.698073 0.117779 0.585228 -0.698073 0.412555 0.585228 -0.698073 0.412556 0.34827 -0.698073 0.625622 0.348271 -0.698074 0.62562 -0.0156496 -0.694746 -0.719085 -0.0156496 -0.694746 -0.719085 0.345989 -0.694746 -0.630571 0.34599 -0.694745 -0.630571 0.614923 -0.694745 -0.373094 0.61492 -0.694747 -0.373095 0.719084 -0.694747 -0.0156496 0.719083 -0.694747 -0.0156496 0.63057 -0.694747 0.345989 0.63057 -0.694747 0.345989 0.373095 -0.694747 0.61492 0.373095 -0.694746 0.614921 -0.0156493 -0.694746 -0.719085 -0.0156493 -0.694746 -0.719085 0.345989 -0.694746 -0.63057 0.345991 -0.694745 -0.630571 0.614922 -0.694745 -0.373096 0.614921 -0.694745 -0.373096 0.719086 -0.694745 -0.0156472 0.719083 -0.694747 -0.0156495 0.630569 -0.694747 0.345989 0.63057 -0.694747 0.345989 0.373095 -0.694747 0.614921 0.373095 -0.694746 0.614921 -0.0156496 -0.694746 -0.719085 -0.0156491 -0.694746 -0.719085 0.34599 -0.694746 -0.630571 0.34599 -0.694745 -0.630571 0.614922 -0.694745 -0.373096 0.614921 -0.694745 -0.373096 0.719086 -0.694745 -0.0156472 0.719084 -0.694747 -0.0156495 0.63057 -0.694747 0.345989 0.63057 -0.694747 0.345989 0.373094 -0.694746 0.614921 0.373094 -0.694747 0.614921 -0.0423348 -0.698073 -0.714774 -0.0423349 -0.698073 -0.714774 0.271987 -0.698073 -0.662357 0.271986 -0.698074 -0.662357 0.532436 -0.698074 -0.478753 0.532438 -0.698073 -0.478753 0.687433 -0.698073 -0.200325 0.687433 -0.698073 -0.200325 0.706273 -0.698073 0.117779 0.706274 -0.698073 0.117779 0.585228 -0.698073 0.412555 0.585228 -0.698073 0.412555 0.348271 -0.698073 0.625621 0.348272 -0.698074 0.625619 -0.0156496 -0.694745 -0.719086 -0.0156496 -0.694745 -0.719086 0.345992 -0.694745 -0.63057 0.345989 -0.694747 -0.63057 0.614921 -0.694747 -0.373095 0.614921 -0.694746 -0.373095 0.719085 -0.694746 -0.0156494 0.719085 -0.694746 -0.0156493 0.63057 -0.694746 0.34599 0.630571 -0.694745 0.34599 0.373094 -0.694745 0.614923 0.373095 -0.694747 0.61492 -0.0591267 0 -0.99825 -0.0217579 0.00371772 -0.999756 0.201264 0 -0.979537 0.414178 0 -0.910196 0.481029 0.00620744 -0.876683 0.63564 0 -0.771986 0.791487 0 -0.611186 0.854918 0.0074559 -0.51871 0.922705 0 -0.385508 0.985354 0 -0.170522 0.999735 0.00745585 -0.0217574 0.995913 0 0.0903161 0.950845 0 0.309666 0.876682 0.00620745 0.48103 0.838299 0 0.54521 0.695963 0 0.718077 0.518721 0.00371761 0.854936 0.486394 0 0.87374 -0.0591247 0 -0.998251 -0.0217579 0.00371752 -0.999756 0.201252 0 -0.979539 0.41418 0 -0.910195 0.48103 0.0062074 -0.876682 0.63564 0 -0.771986 0.791488 0 -0.611185 0.854918 0.00745587 -0.518709 0.922705 0 -0.385508 0.985354 0 -0.170524 0.999735 0.00745595 -0.0217574 0.995913 0 0.0903176 0.950846 0 0.309663 0.876683 0.00620749 0.481029 0.8383 0 0.545209 0.695954 0 0.718086 0.51872 0.00371741 0.854936 0.486395 0 0.873739 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.743601 0 -0.668624 0.743601 0 -0.668624 0.960066 0 -0.279775 0.960066 0 -0.279775 0.986379 0 0.164487 0.986379 0 0.164487 0.817326 0 0.576175 0.817326 0 0.576175 0.486396 0 0.873739 0.486396 0 0.873739 -0.0217563 0 -0.999763 -0.0217563 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.021758 0.999763 0 -0.021758 0.876699 0 0.48104 0.876699 0 0.48104 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 0.201252 0 -0.979539 0.201252 0 -0.979539 0.41418 0 -0.910195 0.41418 0 -0.910195 0.635637 0 -0.771989 0.635637 0 -0.771989 0.791489 0 -0.611184 0.791489 0 -0.611184 0.922704 0 -0.385509 0.922704 0 -0.385509 0.985354 0 -0.170523 0.985354 0 -0.170523 0.995913 0 0.0903179 0.995913 0 0.0903179 0.950846 0 0.309663 0.950846 0 0.309663 0.8383 0 0.545209 0.8383 0 0.545209 0.69596 0 0.71808 0.69596 0 0.71808 0.486395 0 0.873739 0.486395 0 0.873739 -0.0591247 0 -0.998251 -0.0217579 0.00371752 -0.999756 0.201253 0 -0.979539 0.414176 0 -0.910197 0.481029 0.00620764 -0.876683 0.635644 0 -0.771982 0.791487 0 -0.611186 0.854918 0.00745592 -0.51871 0.922705 0 -0.385508 0.985354 0 -0.170522 0.999735 0.00745589 -0.0217571 0.995913 0 0.0903171 0.950845 0 0.309666 0.876683 0.00620737 0.481029 0.838301 0 0.545208 0.695963 0 0.718078 0.518721 0.0037176 0.854935 0.486395 0 0.873739 -0.0591246 0 -0.998251 -0.0591246 0 -0.998251 0.379853 0 -0.925047 0.379853 0 -0.925047 0.7436 0 -0.668625 0.7436 0 -0.668625 0.960066 0 -0.279775 0.960066 0 -0.279775 0.986379 0 0.164489 0.986379 0 0.164489 0.817328 0 0.576173 0.817328 0 0.576173 0.486393 0 0.87374 0.486393 0 0.87374 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854943 0 -0.518722 0.854943 0 -0.518722 0.999763 0 -0.021758 0.999763 0 -0.021758 0.8767 0 0.481038 0.8767 0 0.481038 0.518725 0 0.854941 0.518725 0 0.854941 -0.0591249 0 -0.998251 -0.0217575 0.00371758 -0.999756 0.201259 0 -0.979538 0.414178 0 -0.910196 0.481029 0.00620746 -0.876683 0.635641 0 -0.771985 0.791488 0 -0.611184 0.854918 0.00745573 -0.51871 0.922703 0 -0.385512 0.985354 0 -0.170519 0.999736 0.00745592 -0.021754 0.995913 0 0.0903207 0.950846 0 0.309663 0.876683 0.00620749 0.481029 0.8383 0 0.545209 0.695965 0 0.718076 0.518721 0.00371763 0.854936 0.486394 0 0.87374 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217546 0.999763 0 -0.0217546 0.8767 0 0.481038 0.8767 0 0.481038 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591246 0 -0.998251 -0.0217579 -0.00371752 -0.999756 0.379855 0.00310598 -0.925041 0.41418 0 -0.910195 0.63564 0 -0.771986 0.74359 0.00497647 -0.668618 0.791486 0 -0.611187 0.922705 0 -0.385508 0.960051 0.00560116 -0.279769 0.985354 0 -0.17052 0.995913 0 0.0903176 0.986367 0.00497643 0.164487 0.950846 0 0.309663 0.817328 0 0.576173 0.838294 0.00371743 0.545206 0.48639 -0.00432407 0.873731 0.518725 0 0.854941 -0.0591247 0 -0.998251 -0.0217579 0.00371752 -0.999756 0.201253 0 -0.979539 0.41418 0 -0.910195 0.481032 0.00620754 -0.876681 0.635644 0 -0.771982 0.791487 0 -0.611187 0.854918 0.00745593 -0.51871 0.922705 0 -0.385507 0.985354 0 -0.170522 0.999735 0.00745589 -0.0217572 0.995913 0 0.0903169 0.950845 0 0.309666 0.876682 0.00620736 0.481029 0.838301 0 0.545208 0.69595 0 0.71809 0.518719 0.0037173 0.854937 0.486395 0 0.873739 0.607576 0 -0.794262 0.999313 0 0.0370677 0.980114 0 0.198437 0.361751 0 0.932275 0.289356 -0.677613 0.676102 0.536898 -0.219455 0.814604 0.427562 -0.704008 0.567065 0.518704 -0.00912181 0.854905 0.502771 0 0.86442 0.471486 0 0.881874 0.839783 0 0.542923 0.817578 -0.111032 0.565012 0.620055 -0.609058 0.49455 0.545028 -0.711494 0.443531 0.722559 0 0.691309 0.632683 0 0.774411 0.980114 0 0.198437 0.919995 0 0.391929 0.643263 -0.702726 0.303955 0.84819 -0.252943 0.465396 0.857433 0 0.514595 0.793783 -0.607956 -0.0172753 0.660913 -0.74995 -0.0277072 0.966417 -0.242499 -0.0850399 0.960066 0 -0.279774 0.960066 0 -0.279774 0.988806 0 -0.149206 0.823488 -0.091236 -0.55995 0.678791 -0.607969 -0.411846 0.572336 -0.749948 -0.331677 0.860812 -0.242492 -0.447436 0.914165 0 -0.405343 0.720079 0 -0.693893 0.720079 0 -0.693893 0.802682 0 -0.596407 0.428585 -0.60904 -0.667372 0.379274 -0.70273 -0.601932 0.465395 -0.252948 -0.848189 -0.0217544 -0.0091277 -0.999722 0.0152409 -0.219459 -0.975503 0.0500503 -0.634154 -0.771585 0.05257 -0.745324 -0.664626 0.146121 0 -0.989267 0.31513 0 -0.949049 0.31513 0 -0.949049 0.446762 0 -0.894653 -0.162011 0 -0.986789 -0.162011 0 -0.986789 -0.040316 0 -0.999187 -0.0423348 0.698074 -0.714773 -0.0423348 0.698075 -0.714772 0.142358 0.706861 -0.69288 0.309106 0.581219 -0.752754 0.295432 0.700862 -0.64924 0.450096 0.706116 -0.546639 0.649554 0.486779 -0.58406 0.562798 0.703128 -0.434591 0.66872 0.702602 -0.243235 0.755806 0.57362 -0.315781 0.65804 0.744322 -0.113878 0.805545 0.592275 -0.0175313 0.644295 0.762542 0.0584302 0.730694 0.652567 0.200606 0.673289 0.706117 0.219274 0.585228 0.698074 0.412554 0.348269 0.698077 0.625618 0.34827 0.698076 0.625618 0.492288 0.706862 0.507935 0.701608 0.547292 0.456308 0.373092 0.694752 0.614916 0.719082 0.694749 -0.0156502 0.719078 0.694753 -0.0156492 0.614915 0.694753 -0.373091 0.614922 0.694744 -0.373097 0.34599 0.694745 -0.630571 0.345989 0.694748 -0.630569 -0.0156492 0.694747 -0.719084 -0.0156494 0.694746 -0.719085 0.373094 0.694749 0.614919 0.53342 0.70672 0.464768 0.519137 0.805828 0.284847 0.519139 0.805827 0.284848 0.678566 0.706719 0.200241 0.467776 0.707093 0.530288 -0.0423346 0.698073 -0.714774 -0.0423349 0.698072 -0.714775 0.142362 0.706858 -0.692882 0.309106 0.581219 -0.752754 0.85705 0.450652 -0.249755 0.295432 0.700863 -0.64924 0.450095 0.706117 -0.546639 0.649554 0.486778 -0.584061 0.5628 0.703125 -0.434594 0.654504 0.704874 -0.273455 0.698945 0.704872 -0.120957 0.708161 0.703124 0.0642222 0.861628 0.486777 0.143686 0.673291 0.706116 0.219272 0.585228 0.698073 0.412555 0.701613 0.547284 0.456311 0.492285 0.706861 0.50794 0.357948 0.723759 0.589955 0.296283 0.793062 0.532231 0.229566 0.706718 0.669215 -0.0156494 0.694743 -0.719088 -0.0508619 0.509849 -0.858759 0.809398 0.322032 -0.491091 0.142357 0.706858 -0.692882 0.295433 0.70086 -0.649241 0.439497 0.406517 -0.800991 0.450093 0.706119 -0.546638 0.562798 0.703127 -0.434592 0.654505 0.704873 -0.273455 0.698944 0.704873 -0.120957 0.946506 0.322028 -0.0205987 0.70816 0.703125 0.0642214 0.673291 0.706116 0.219272 0.800994 0.406508 0.4395 0.34827 0.698074 0.625621 0.434145 0.547283 0.715541 0.492293 0.706857 0.507937 0.597958 0.70086 0.388897 -0.0156493 0.69475 -0.719081 -0.0508627 0.509854 -0.858756 0.809399 0.322029 -0.491092 0.142356 0.706861 -0.69288 0.295432 0.700863 -0.649239 0.439498 0.406514 -0.800991 0.450094 0.706116 -0.54664 0.5628 0.703125 -0.434593 0.654505 0.704874 -0.273454 0.698944 0.704873 -0.120957 0.946507 0.322026 -0.0205987 0.708161 0.703125 0.0642215 0.673291 0.706115 0.219273 0.800994 0.406508 0.4395 0.348271 0.698073 0.625621 0.434145 0.547282 0.715542 0.492294 0.706858 0.507936 0.597958 0.70086 0.388897 -0.0156493 0.694748 -0.719083 -0.0508633 0.509848 -0.85876 0.8094 0.322026 -0.491092 0.14236 0.70686 -0.692881 0.295432 0.700862 -0.64924 0.439499 0.406511 -0.800993 0.450094 0.706117 -0.546639 0.5628 0.703125 -0.434594 0.654506 0.704872 -0.273454 0.698945 0.704873 -0.120957 0.946507 0.322026 -0.0205987 0.708162 0.703123 0.0642211 0.673292 0.706114 0.219273 0.800994 0.406508 0.4395 0.348271 0.698073 0.625621 0.434144 0.547286 0.71554 0.492293 0.70686 0.507934 0.597956 0.700862 0.388896 0.348271 0.698073 0.62562 0.348272 0.698073 0.625621 0.58523 0.698072 0.412556 0.585227 0.698074 0.412555 0.706273 0.698074 0.117778 0.706273 0.698073 0.117778 0.687433 0.698073 -0.200326 0.687435 0.698071 -0.200327 0.532438 0.698072 -0.478754 0.532437 0.698074 -0.478752 0.271986 0.698074 -0.662357 0.271986 0.698074 -0.662356 -0.0423349 0.698074 -0.714773 -0.042335 0.698074 -0.714773 -0.0423344 0.698077 -0.714771 -0.0423357 0.698072 -0.714775 0.142361 0.706858 -0.692882 0.309106 0.581217 -0.752755 0.295432 0.700863 -0.649239 0.450094 0.706117 -0.54664 0.649555 0.486775 -0.584062 0.5628 0.703125 -0.434594 0.654505 0.704873 -0.273453 0.857048 0.450657 -0.249753 0.698945 0.704872 -0.120957 0.708161 0.703124 0.0642222 0.861625 0.486782 0.143685 0.67329 0.706117 0.21927 0.585226 0.698075 0.412555 0.348272 0.698072 0.625621 0.348271 0.698074 0.62562 0.492289 0.70686 0.507937 0.70161 0.547288 0.45631 0.373096 0.694745 0.614921 0.373093 0.69475 0.614918 0.630568 0.694749 0.345989 0.630569 0.694748 0.345989 0.719084 0.694747 -0.0156496 0.719083 0.694748 -0.0156493 0.614919 0.694749 -0.373094 0.614922 0.694745 -0.373096 0.34599 0.694744 -0.630573 0.345989 0.694748 -0.630569 -0.0156488 0.694749 -0.719082 -0.0156494 0.694746 -0.719085 -0.0128846 0.805826 -0.592012 -0.0128822 0.805833 -0.592003 -0.16588 0.706717 -0.687775 0.373097 0.694743 0.614923 0.373093 0.69475 0.614918 0.630568 0.694749 0.345989 0.630568 0.694748 0.345989 0.719084 0.694747 -0.0156493 0.719084 0.694747 -0.0156494 0.614921 0.694746 -0.373095 0.614922 0.694745 -0.373095 0.345991 0.694744 -0.630572 0.345991 0.694742 -0.630574 0.135796 0.706713 -0.694346 -0.0423355 0.698075 -0.714772 -0.0114175 0.796865 -0.60405 -0.170422 0.70682 -0.686558 0.34827 0.698076 0.625618 0.348272 0.698073 0.62562 0.585228 0.698073 0.412556 0.585228 0.698073 0.412556 0.706273 0.698074 0.117778 0.706273 0.698074 0.117778 0.687433 0.698073 -0.200326 0.687432 0.698074 -0.200325 0.532437 0.698074 -0.478753 0.484567 0.771732 -0.411855 0.311205 0.573403 -0.757865 0.236201 0.871147 -0.430479 0.17494 0.70585 -0.68642 0.506252 0.805829 -0.307161 -0.0156494 0.694746 -0.719085 -0.0156496 0.694745 -0.719086 0.34599 0.694747 -0.63057 0.34599 0.694745 -0.630571 0.512692 0.706716 -0.487545 0.50625 0.805831 -0.307159 0.373094 0.694749 0.614919 0.373096 0.694745 0.614922 0.630572 0.694744 0.345991 0.630573 0.694744 0.345991 0.719089 0.694741 -0.0156504 0.719085 0.694746 -0.0156494 0.669215 0.706718 -0.229567 0.34827 0.698075 0.625619 0.348271 0.698074 0.625619 0.585227 0.698074 0.412555 0.585227 0.698074 0.412555 0.706272 0.698074 0.117778 0.706272 0.698075 0.117778 0.687431 0.698075 -0.200325 0.687432 0.698074 -0.200325 0.532436 0.698074 -0.478752 0.532436 0.698075 -0.478752 0.271986 0.698075 -0.662356 0.271986 0.698074 -0.662357 -0.0423349 0.698074 -0.714773 -0.0423349 0.698073 -0.714774 0.10424 0.703803 0.702705 0.104239 0.703805 0.702704 -0.521434 0.698432 0.490203 -0.521434 0.698433 0.490203 -0.263019 0.698433 0.665591 -0.263019 0.698433 0.665592 0.0454829 0.698432 0.714229 0.0454822 0.698435 0.714227 0.0571084 0.699695 0.712155 0.0571086 0.699695 0.712156 -0.185296 0.701184 0.688481 -0.185296 0.701184 0.688481 0.0721748 0.701184 0.709318 0.0721748 0.701184 0.709318 0.0746331 0.701412 0.708838 0.0746331 0.701412 0.708838 -0.555599 0.697265 0.452915 -0.555598 0.697266 0.452914 -0.291434 0.697266 0.654894 -0.291435 0.697263 0.654897 0.0354492 0.697263 0.715939 0.0354489 0.697264 0.715937 -0.0217608 0 -0.999763 -0.0217608 0 -0.999763 0.481041 0 -0.876698 0.481041 0 -0.876698 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217575 0.999763 0 -0.0217575 0.876699 0 0.48104 0.876699 0 0.48104 0.518725 0 0.854941 0.518725 0 0.854941 -0.059124 0 -0.998251 -0.059124 0 -0.998251 0.379854 0 -0.925046 0.379854 0 -0.925046 0.7436 0 -0.668625 0.7436 0 -0.668625 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164489 0.986379 0 0.164489 0.817328 0 0.576173 0.817328 0 0.576173 0.486394 0 0.87374 0.486394 0 0.87374 -0.0217575 0 -0.999763 -0.0217575 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217575 0.999763 0 -0.0217575 0.876698 0 0.481041 0.876698 0 0.481041 0.518725 0 0.854941 0.518725 0 0.854941 -0.059126 0 -0.998251 -0.059126 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.7436 0 -0.668625 0.7436 0 -0.668625 0.960066 0 -0.279775 0.960066 0 -0.279775 0.986379 0 0.164489 0.986379 0 0.164489 0.817327 0 0.576174 0.817327 0 0.576174 0.486395 0 0.873739 0.486395 0 0.873739 -0.0217575 0 -0.999763 -0.0217575 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217575 0.999763 0 -0.0217575 0.876699 0 0.481039 0.876699 0 0.481039 0.518723 0 0.854943 0.518723 0 0.854943 -0.0217575 0 -0.999763 -0.0217575 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217575 0.999763 0 -0.0217575 0.876699 0 0.481039 0.876699 0 0.481039 0.518723 0 0.854943 0.518723 0 0.854943 -0.0217579 0 -0.999763 -0.0217579 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217575 0.999763 0 -0.0217575 0.876698 0 0.481041 0.876698 0 0.481041 0.518726 0 0.854941 0.518726 0 0.854941 -0.0217575 0 -0.999763 -0.0587116 0.118066 -0.991269 0.412031 -0.101692 -0.905477 0.379855 0 -0.925046 0.635639 0 -0.771987 0.736734 -0.135578 -0.662451 0.791489 0 -0.611184 0.960066 0 -0.279774 0.882299 -0.292685 -0.368626 0.985354 0 -0.170523 0.986379 0 0.164489 0.975759 -0.20016 0.0884909 0.950847 0 0.309661 0.8383 0 0.54521 0.814363 -0.0850932 0.574083 0.516035 0.101692 0.85051 0.486394 0 0.87374 -0.0217575 0 -0.999763 -0.0587124 0.118068 -0.991268 0.412031 -0.101688 -0.905478 0.379857 0 -0.925045 0.63564 0 -0.771986 0.736734 -0.135574 -0.662452 0.791486 0 -0.611187 0.960066 0 -0.279773 0.882298 -0.292688 -0.368625 0.985354 0 -0.17052 0.986379 0 0.164489 0.975758 -0.200168 0.0884878 0.950845 0 0.309666 0.8383 0 0.54521 0.814362 -0.0850957 0.574084 0.516035 0.101687 0.85051 0.486395 0 0.873739 0.486394 0 0.873739 0.486394 0 0.873739 0.69596 0 0.71808 0.69596 0 0.71808 0.8383 0 0.545209 0.8383 0 0.545209 0.950845 0 0.309667 0.950845 0 0.309667 0.995913 0 0.0903181 0.995913 0 0.0903181 0.985354 0 -0.170522 0.985354 0 -0.170522 0.922703 0 -0.385512 0.922703 0 -0.385512 0.791488 0 -0.611185 0.791488 0 -0.611185 0.635642 0 -0.771984 0.635642 0 -0.771984 0.414178 0 -0.910196 0.414178 0 -0.910196 0.201255 0 -0.979539 0.201255 0 -0.979539 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 -0.0217576 0 -0.999763 -0.0217576 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.021759 0.999763 0 -0.021759 0.876699 0 0.481039 0.876699 0 0.481039 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591247 0 -0.998251 -0.0217508 0.0239943 -0.999475 0.20126 0 -0.979538 0.414178 0 -0.910196 0.480653 0.0400444 -0.875996 0.635641 0 -0.771985 0.791487 0 -0.611186 0.853952 0.0480808 -0.518125 0.922704 0 -0.38551 0.985354 0 -0.170521 0.998607 0.0480814 -0.0217319 0.995913 0 0.090318 0.950846 0 0.309664 0.875996 0.0400443 0.480652 0.8383 0 0.545209 0.695955 0 0.718086 0.518574 0.023993 0.854696 0.486395 0 0.873739 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.201253 0 -0.979539 0.201253 0 -0.979539 0.414179 0 -0.910195 0.414179 0 -0.910195 0.63564 0 -0.771985 0.63564 0 -0.771985 0.791487 0 -0.611186 0.791487 0 -0.611186 0.922704 0 -0.38551 0.922704 0 -0.38551 0.985354 0 -0.170521 0.985354 0 -0.170521 0.995913 0 0.0903171 0.995913 0 0.0903171 0.950846 0 0.309664 0.950846 0 0.309664 0.8383 0 0.545209 0.8383 0 0.545209 0.695962 0 0.718078 0.695962 0 0.718078 0.486393 0 0.87374 0.486393 0 0.87374 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 0.201252 0 -0.97954 0.201252 0 -0.97954 0.414178 0 -0.910196 0.414178 0 -0.910196 0.63564 0 -0.771986 0.63564 0 -0.771986 0.791488 0 -0.611185 0.791488 0 -0.611185 0.922704 0 -0.385509 0.922704 0 -0.385509 0.985354 0 -0.170522 0.985354 0 -0.170522 0.995913 0 0.0903171 0.995913 0 0.0903171 0.950846 0 0.309665 0.950846 0 0.309665 0.8383 0 0.545209 0.8383 0 0.545209 0.695963 0 0.718078 0.695963 0 0.718078 0.486393 0 0.87374 0.486393 0 0.87374 -0.0591252 0 -0.998251 -0.0591252 0 -0.998251 0.201257 0 -0.979539 0.201257 0 -0.979539 0.414178 0 -0.910196 0.414178 0 -0.910196 0.635641 0 -0.771985 0.635641 0 -0.771985 0.791487 0 -0.611186 0.791487 0 -0.611186 0.922704 0 -0.385508 0.922704 0 -0.385508 0.985354 0 -0.170521 0.985354 0 -0.170521 0.995913 0 0.0903164 0.995913 0 0.0903164 0.950846 0 0.309665 0.950846 0 0.309665 0.8383 0 0.54521 0.8383 0 0.54521 0.695965 0 0.718076 0.695965 0 0.718076 0.486394 0 0.87374 0.486394 0 0.87374 -0.0591249 0 -0.998251 -0.0591249 0 -0.998251 0.379855 0 -0.925046 0.379855 0 -0.925046 0.7436 0 -0.668625 0.7436 0 -0.668625 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164489 0.986379 0 0.164489 0.817328 0 0.576173 0.817328 0 0.576173 0.486394 0 0.873739 0.486394 0 0.873739 -0.0591258 0 -0.998251 -0.0217518 0.0239945 -0.999475 0.201258 0 -0.979538 0.414178 0 -0.910196 0.480653 0.040044 -0.875996 0.63564 0 -0.771986 0.791487 0 -0.611186 0.853953 0.0480813 -0.518124 0.922705 0 -0.385508 0.985354 0 -0.170522 0.998607 0.0480814 -0.0217319 0.995913 0 0.090318 0.950847 0 0.309661 0.875996 0.0400448 0.480653 0.8383 0 0.54521 0.69596 0 0.718081 0.518575 0.0239938 0.854695 0.486395 0 0.873739 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217581 0.999763 0 -0.0217581 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 -0.021759 0 -0.999763 -0.021759 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217577 0.999763 0 -0.0217577 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 -0.0591258 0 -0.998251 -0.0591258 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.7436 0 -0.668625 0.7436 0 -0.668625 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164489 0.986379 0 0.164489 0.817327 0 0.576174 0.817327 0 0.576174 0.486394 0 0.873739 0.486394 0 0.873739 -0.0217581 0 -0.999763 -0.0217581 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.021759 0.999763 0 -0.021759 0.876699 0 0.481039 0.876699 0 0.481039 0.518724 0 0.854942 0.518724 0 0.854942 -0.0591248 0 -0.998251 -0.0591248 0 -0.998251 0.379855 0 -0.925046 0.379855 0 -0.925046 0.7436 0 -0.668625 0.7436 0 -0.668625 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164489 0.986379 0 0.164489 0.817327 0 0.576173 0.817327 0 0.576173 0.486394 0 0.873739 0.486394 0 0.873739 -0.480613 0 -0.876933 -0.468052 0.00686625 -0.883674 -0.293432 0 -0.95598 0.146735 0 0.989176 0.146735 0 0.989176 -0.728589 0 0.684951 -0.7356 -0.00793093 0.677369 -0.367499 0.00829711 0.929987 -0.39609 -0.0165918 0.918062 0.011959 0.0136553 0.999835 0.063539 -0.0204793 0.997769 0.249904 0 0.968271 0.104711 0 0.994503 0.104711 0 0.994503 -0.790152 -0.0199553 0.612586 -0.775095 0 0.631845 -0.472366 0.0158423 0.88126 -0.406366 -0.0316634 0.913162 -0.231391 0 0.972861 -0.0238684 0 0.999715 0.0494116 -0.0412482 0.997926 0.20867 0 0.977986 -0.737949 0 -0.674857 -0.733115 -0.00330572 -0.680096 -0.449059 0.00317724 -0.893497 -0.442681 0 -0.896679 -0.0156516 -0.694747 -0.719084 -0.0156496 -0.694746 -0.719085 0.345991 -0.694746 -0.63057 0.345989 -0.694747 -0.63057 0.614921 -0.694747 -0.373095 0.614921 -0.694747 -0.373095 0.719084 -0.694746 -0.0156492 0.719084 -0.694746 -0.0156493 0.63057 -0.694746 0.34599 0.63057 -0.694747 0.345989 0.373095 -0.694747 0.61492 0.373095 -0.694747 0.614921 0.385508 0 0.922704 0.385508 0 0.922704 0.581164 0 0.813787 0.581164 0 0.813787 0.747677 0 0.664062 0.747677 0 0.664062 0.876699 0 0.481039 0.876699 0 0.481039 0.96176 0 0.273894 0.96176 0 0.273894 0.998594 0 0.0530155 0.998594 0 0.0530155 0.985354 0 -0.170522 0.985354 0 -0.170522 0.922704 0 -0.385508 0.922704 0 -0.385508 0.813787 0 -0.581164 0.813787 0 -0.581164 0.664062 0 -0.747677 0.664062 0 -0.747677 0.481039 0 -0.876699 0.481039 0 -0.876699 0.273894 0 -0.96176 0.273894 0 -0.96176 0.0530155 0 -0.998594 0.0530155 0 -0.998594 -0.170522 0 -0.985354 -0.170522 0 -0.985354 -0.156979 -0.706467 -0.690117 -0.169232 -0.122774 -0.977899 0.302879 -0.706616 -0.639498 0.194282 -0.704874 -0.682208 0.194284 -0.704868 -0.682213 0.0376059 -0.704868 -0.708341 0.0376059 -0.704868 -0.708341 -0.0450241 -0.707098 -0.705681 -0.0846636 -0.681905 -0.726525 0.471805 -0.16525 -0.866079 0.477626 -0.118907 -0.870479 0.475057 -0.219929 -0.852028 0.577248 -0.704871 -0.41224 0.471043 -0.70487 -0.530355 0.471043 -0.704871 -0.530354 0.381928 -0.706767 -0.595493 0.463151 -0.364598 -0.807812 0.915722 -0.122788 -0.382591 0.635398 -0.706622 -0.311377 0.577247 -0.704872 -0.41224 0.682209 -0.704873 0.194282 0.708336 -0.704873 0.0376057 0.708336 -0.704873 0.0376057 0.7032 -0.706622 -0.0787057 0.977898 -0.122786 -0.169231 0.690117 -0.706467 -0.156978 0.66641 -0.706468 -0.23833 0.824601 -0.364611 0.432542 0.642038 -0.706768 0.297096 0.682208 -0.704874 0.194282 0.858391 -0.219987 0.463434 0.87048 -0.118903 0.477626 0.863188 -0.16535 0.47704 0.599006 -0.706614 0.37668 0.530354 -0.704872 0.471043 0.530353 -0.704872 0.471042 0.41224 -0.704872 0.577247 0.41224 -0.704872 0.577247 0.238328 -0.706472 0.666407 0.382592 -0.122782 0.915723 0.318882 -0.681904 0.658272 0.341122 -0.707102 0.619389 -0.0423344 -0.698074 -0.714774 -0.0423348 -0.698074 -0.714773 0.271985 -0.698074 -0.662357 0.271986 -0.698074 -0.662357 0.532437 -0.698074 -0.478753 0.532437 -0.698074 -0.478753 0.687432 -0.698074 -0.200326 0.687432 -0.698074 -0.200326 0.706273 -0.698074 0.117779 0.706273 -0.698074 0.117779 0.585228 -0.698074 0.412555 0.585228 -0.698074 0.412555 0.348271 -0.698074 0.62562 0.348271 -0.698074 0.62562 -0.0156492 -0.694746 -0.719084 -0.0156496 -0.694747 -0.719084 0.345989 -0.694747 -0.63057 0.345989 -0.694747 -0.63057 0.61492 -0.694747 -0.373095 0.614921 -0.694746 -0.373095 0.719085 -0.694746 -0.0156492 0.719085 -0.694746 -0.0156496 0.63057 -0.694746 0.345991 0.63057 -0.694747 0.345989 0.373095 -0.694747 0.61492 0.373095 -0.694746 0.614921 -0.0423357 -0.698074 -0.714773 -0.0423354 -0.698074 -0.714773 0.271987 -0.698074 -0.662357 0.271987 -0.698074 -0.662357 0.532437 -0.698074 -0.478753 0.532437 -0.698074 -0.478753 0.687432 -0.698074 -0.200326 0.687432 -0.698074 -0.200326 0.706273 -0.698074 0.117778 0.706273 -0.698074 0.117779 0.585228 -0.698073 0.412556 0.585228 -0.698074 0.412555 0.348271 -0.698074 0.62562 0.348271 -0.698074 0.62562 -0.0156492 -0.694747 -0.719084 -0.0156496 -0.694747 -0.719084 0.345989 -0.694747 -0.63057 0.34599 -0.694747 -0.63057 0.614921 -0.694746 -0.373095 0.61492 -0.694747 -0.373095 0.719084 -0.694746 -0.0156492 0.719084 -0.694746 -0.0156493 0.63057 -0.694746 0.345989 0.63057 -0.694746 0.34599 0.373094 -0.694746 0.614922 0.373095 -0.694747 0.61492 -0.0156492 -0.694747 -0.719084 -0.0156491 -0.694747 -0.719084 0.345989 -0.694747 -0.63057 0.345989 -0.694747 -0.63057 0.614921 -0.694747 -0.373095 0.61492 -0.694747 -0.373095 0.719084 -0.694747 -0.0156492 0.719084 -0.694747 -0.0156494 0.63057 -0.694747 0.345989 0.63057 -0.694747 0.345989 0.373094 -0.694746 0.614922 0.373094 -0.694747 0.614921 -0.0156495 -0.694747 -0.719084 -0.0156494 -0.694747 -0.719084 0.345989 -0.694747 -0.63057 0.345989 -0.694746 -0.63057 0.61492 -0.694746 -0.373096 0.614921 -0.694746 -0.373095 0.719085 -0.694746 -0.0156492 0.719085 -0.694746 -0.0156496 0.63057 -0.694746 0.345991 0.63057 -0.694747 0.34599 0.373096 -0.694747 0.61492 0.373095 -0.694746 0.614921 0.219008 -0.706934 0.672518 0.63057 -0.694747 0.34599 0.445112 -0.70412 0.553254 0.36176 -0.716679 0.596239 0.327674 -0.71162 0.621471 0.264753 -0.708092 0.654608 0.61924 -0.67405 0.402739 0.673291 -0.706116 0.21927 0.719084 -0.694747 -0.0156496 0.746218 -0.662253 0.0676739 0.698944 -0.704873 -0.120958 0.654505 -0.704873 -0.273453 0.623292 -0.684464 -0.378174 -0.176556 -0.706934 -0.684889 0.562801 -0.703124 -0.434593 0.450093 -0.706116 -0.546641 0.349907 -0.686215 -0.63771 0.295432 -0.700862 -0.64924 0.0782213 -0.70412 -0.705759 -0.0151737 -0.716679 -0.697238 -0.0574789 -0.71162 -0.700209 -0.12835 -0.708092 -0.694358 0.373095 -0.694746 0.614921 0.373095 -0.694746 0.614921 0.63057 -0.694747 0.34599 0.61924 -0.67405 0.402739 0.67329 -0.706116 0.219273 0.719084 -0.694747 -0.0156496 0.746218 -0.662253 0.0676718 0.698945 -0.704873 -0.120955 0.654505 -0.704873 -0.273453 0.623292 -0.684464 -0.378175 -0.0156492 -0.694746 -0.719085 -0.0156496 -0.694747 -0.719084 0.295432 -0.700862 -0.64924 0.349907 -0.686215 -0.63771 0.450094 -0.706116 -0.54664 0.5628 -0.703125 -0.434594 -0.703145 -0.698431 -0.133348 -0.703145 -0.69843 -0.133348 -0.579404 -0.69843 -0.420102 -0.579404 -0.698431 -0.420101 -0.345324 -0.698431 -0.626854 -0.345324 -0.698431 -0.626853 -0.334405 -0.699693 -0.631351 -0.334405 -0.699693 -0.63135 -0.526144 -0.701182 -0.481161 -0.526144 -0.701182 -0.481161 -0.320172 -0.701182 -0.63705 -0.320172 -0.701183 -0.63705 -0.317841 -0.701411 -0.637965 -0.317841 -0.701411 -0.637965 -0.711931 -0.697263 -0.083543 -0.711931 -0.697262 -0.0835431 -0.597625 -0.697262 -0.395815 -0.597625 -0.697263 -0.395814 -0.396535 -0.702504 -0.590973 -0.41892 -0.53225 -0.735674 -0.247377 -0.706154 -0.663439 -0.289575 -0.703802 -0.648698 -0.289575 -0.703803 -0.648697 0.373097 -0.694742 0.614924 0.41843 -0.509841 0.751651 0.946508 -0.322023 -0.0205988 0.492295 -0.706857 0.507936 0.597959 -0.700859 0.388898 0.800995 -0.406505 0.4395 0.673295 -0.706111 0.219274 0.708165 -0.70312 0.0642214 0.698948 -0.704869 -0.120957 0.654509 -0.704869 -0.273456 0.8094 -0.322023 -0.491093 0.562802 -0.703122 -0.434596 0.450096 -0.706113 -0.546642 0.4395 -0.406508 -0.800994 -0.0423353 -0.698072 -0.714775 -0.0182101 -0.547285 -0.836748 0.14236 -0.706856 -0.692884 0.295434 -0.700858 -0.649243 0.373097 -0.694742 0.614924 0.41843 -0.509836 0.751654 0.946508 -0.322023 -0.0205988 0.492296 -0.706854 0.507939 0.597961 -0.700857 0.388899 0.800995 -0.406505 0.439501 0.673294 -0.706112 0.219274 0.708164 -0.703121 0.0642218 0.698948 -0.70487 -0.120957 0.654508 -0.70487 -0.273455 0.809399 -0.322027 -0.491092 0.562803 -0.703122 -0.434595 0.450096 -0.706113 -0.546642 0.439499 -0.406511 -0.800993 -0.0423349 -0.698073 -0.714774 -0.01821 -0.547291 -0.836744 0.142357 -0.706858 -0.692883 0.295433 -0.70086 -0.649242 0.373097 -0.694743 0.614924 0.41843 -0.509837 0.751654 0.946507 -0.322025 -0.0205987 0.492296 -0.706854 0.50794 0.597961 -0.700857 0.388899 0.800995 -0.406504 0.439501 0.673294 -0.706113 0.219273 0.708163 -0.703122 0.0642217 0.698947 -0.70487 -0.120957 0.654508 -0.70487 -0.273456 0.809398 -0.32203 -0.491092 0.562801 -0.703124 -0.434594 0.450095 -0.706116 -0.54664 0.439498 -0.406514 -0.800992 -0.0423344 -0.698066 -0.71478 -0.0182101 -0.547285 -0.836748 0.142358 -0.706855 -0.692886 0.295435 -0.700857 -0.649244 -0.015649 -0.694743 -0.719088 -0.0156494 -0.694745 -0.719086 0.345989 -0.694746 -0.63057 0.34599 -0.694745 -0.630571 0.61492 -0.694747 -0.373095 0.614924 -0.694742 -0.373097 0.719088 -0.694743 -0.015649 0.719086 -0.694745 -0.0156494 0.630572 -0.694745 0.34599 0.630574 -0.694742 0.345992 0.373097 -0.694741 0.614926 0.373096 -0.694744 0.614923 -0.0156493 -0.694743 -0.719088 -0.0156494 -0.694743 -0.719087 0.34599 -0.694745 -0.630571 0.345992 -0.694742 -0.630573 0.614926 -0.694741 -0.373097 0.614918 -0.69475 -0.373094 0.719081 -0.69475 -0.0156502 0.719086 -0.694745 -0.0156494 0.630571 -0.694745 0.345991 0.63057 -0.694747 0.345989 0.373095 -0.694745 0.614922 0.373094 -0.694749 0.614919 0.348271 -0.698073 0.62562 0.348271 -0.698073 0.625621 0.492291 -0.706859 0.507937 0.6651 -0.581217 0.46886 0.857051 -0.45065 -0.249755 0.597959 -0.700859 0.388898 0.673292 -0.706113 0.219275 0.861632 -0.48677 0.143688 0.708164 -0.703121 0.0642225 0.698948 -0.704869 -0.120957 0.654504 -0.704874 -0.273456 0.562801 -0.703125 -0.434593 0.649555 -0.486775 -0.584062 0.450098 -0.706113 -0.546641 0.271987 -0.69807 -0.66236 -0.042335 -0.698071 -0.714776 -0.042335 -0.698071 -0.714776 0.142359 -0.706857 -0.692883 0.346644 -0.547287 -0.761784 -0.0156497 -0.694743 -0.719088 -0.0156494 -0.694742 -0.719089 0.345991 -0.694743 -0.630573 0.345992 -0.694742 -0.630574 0.614926 -0.694741 -0.373098 0.614923 -0.694744 -0.373096 0.719088 -0.694743 -0.0156503 0.719092 -0.694738 -0.0156495 0.630575 -0.69474 0.345993 0.630575 -0.694741 0.345992 0.373097 -0.694742 0.614925 0.373096 -0.694745 0.614922 -0.0423358 -0.69807 -0.714777 -0.0423362 -0.698072 -0.714775 0.271987 -0.698072 -0.662358 0.271988 -0.698071 -0.662359 0.532439 -0.698071 -0.478755 0.532439 -0.69807 -0.478755 0.687435 -0.698071 -0.200326 0.687436 -0.698069 -0.200326 0.706276 -0.69807 0.117779 0.706276 -0.69807 0.117779 0.585231 -0.69807 0.412558 0.58523 -0.69807 0.412558 0.348273 -0.69807 0.625624 0.348272 -0.698072 0.625621 -0.0156503 -0.694743 -0.719088 -0.0156495 -0.694738 -0.719092 0.345993 -0.694739 -0.630576 0.345992 -0.694741 -0.630575 0.614925 -0.694742 -0.373097 0.614924 -0.694743 -0.373097 0.719087 -0.694744 -0.0156494 0.719087 -0.694744 -0.0156494 0.630571 -0.694745 0.34599 0.630571 -0.694745 0.34599 0.373095 -0.694747 0.61492 0.373098 -0.69474 0.614926 -0.015649 -0.694743 -0.719088 -0.0156494 -0.694745 -0.719086 0.34599 -0.694745 -0.630572 0.345992 -0.694741 -0.630575 0.614925 -0.694742 -0.373097 0.614922 -0.694745 -0.373096 0.719086 -0.694745 -0.0156496 0.719087 -0.694743 -0.0156494 0.630572 -0.694745 0.34599 0.630571 -0.694745 0.34599 0.373095 -0.694747 0.61492 0.373097 -0.694742 0.614925 -0.0156496 -0.694746 -0.719085 -0.0156494 -0.694745 -0.719086 0.34599 -0.694745 -0.630572 0.345991 -0.694744 -0.630572 0.614923 -0.694744 -0.373096 0.614923 -0.694744 -0.373096 0.719088 -0.694743 -0.015649 0.719086 -0.694745 -0.0156494 0.630572 -0.694745 0.34599 0.630573 -0.694744 0.345991 0.373096 -0.694744 0.614923 0.373097 -0.694742 0.614924 -0.0423351 -0.698071 -0.714776 -0.0423351 -0.698071 -0.714776 0.271987 -0.698071 -0.662359 0.271987 -0.698071 -0.66236 0.532439 -0.698071 -0.478755 0.532441 -0.698068 -0.478756 0.687438 -0.698067 -0.200327 0.687436 -0.69807 -0.200327 0.706277 -0.69807 0.117779 0.706276 -0.698071 0.117779 0.58523 -0.698071 0.412557 0.585232 -0.698068 0.412559 0.348273 -0.698069 0.625624 0.348273 -0.69807 0.625623 0.264055 0.705394 0.657795 0.264056 0.705392 0.657797 0.387312 0.705392 0.593643 0.387308 0.705399 0.593637 0.495679 0.705399 0.50667 0.495682 0.705394 0.506674 0.585005 0.705394 0.400235 0.585006 0.705393 0.400236 0.651848 0.705393 0.278417 0.651847 0.705393 0.278417 0.693638 0.705393 0.145898 0.693635 0.705397 0.145897 0.708769 0.705398 0.00777239 0.708765 0.705402 0.00777221 0.696663 0.705402 -0.13065 0.696669 0.705395 -0.130651 0.657794 0.705395 -0.264054 0.65779 0.705399 -0.264053 0.593636 0.7054 -0.387308 0.593645 0.70539 -0.387313 0.506677 0.70539 -0.495685 0.506671 0.705398 -0.495679 0.400233 0.705398 -0.585002 0.400233 0.705398 -0.585002 0.278414 0.705399 -0.651842 0.278417 0.705393 -0.651847 0.145898 0.705393 -0.693638 0.145898 0.705391 -0.69364 0.00777246 0.705391 -0.708776 0.00777228 0.705395 -0.708772 -0.130652 0.705395 -0.696669 -0.130652 0.705394 -0.69667 0.37253 0 0.92802 0.37253 0 0.92802 0.54642 0 0.837512 0.54642 0 0.837512 0.699311 0 0.714818 0.699311 0 0.714818 0.825328 0 0.564654 0.825328 0 0.564654 0.919628 0 0.392791 0.919628 0 0.392791 0.978587 0 0.205833 0.978587 0 0.205833 0.99994 0 0.0109654 0.99994 0 0.0109654 0.982866 0 -0.184324 0.982866 0 -0.184324 0.92802 0 -0.37253 0.92802 0 -0.37253 0.837511 0 -0.54642 0.837511 0 -0.54642 0.714818 0 -0.699311 0.714818 0 -0.699311 0.564654 0 -0.825328 0.564654 0 -0.825328 0.392791 0 -0.919628 0.392791 0 -0.919628 0.205833 0 -0.978587 0.205833 0 -0.978587 0.0109654 0 -0.99994 0.0109654 0 -0.99994 -0.184324 0 -0.982866 -0.184324 0 -0.982866 -0.108173 -0.809687 -0.576807 -0.108173 -0.809687 -0.576807 0.00643517 -0.809687 -0.586827 0.00643515 -0.809687 -0.586827 0.120796 -0.809687 -0.574296 0.120796 -0.809687 -0.574296 0.230514 -0.809687 -0.539695 0.230514 -0.809687 -0.539695 0.331374 -0.809687 -0.484353 0.331374 -0.809687 -0.484354 0.4195 -0.809687 -0.410399 0.4195 -0.809686 -0.410399 0.491504 -0.809687 -0.320673 0.491504 -0.809687 -0.320673 0.54462 -0.809687 -0.218624 0.54462 -0.809687 -0.218624 0.576807 -0.809687 -0.108173 0.576807 -0.809687 -0.108173 0.586827 -0.809687 0.00643517 0.586827 -0.809687 0.00643515 0.574296 -0.809687 0.120796 0.574296 -0.809687 0.120796 0.539695 -0.809687 0.230514 0.539695 -0.809687 0.230514 0.484354 -0.809687 0.331374 0.484354 -0.809687 0.331374 0.410399 -0.809687 0.4195 0.410399 -0.809687 0.4195 0.320673 -0.809687 0.491504 0.320673 -0.809687 0.491504 0.218624 -0.809687 0.54462 0.218624 -0.809687 0.54462 0.37253 0 0.92802 0.37253 0 0.92802 0.54642 0 0.837512 0.54642 0 0.837512 0.699311 0 0.714818 0.699311 0 0.714818 0.825328 0 0.564654 0.825328 0 0.564654 0.919628 0 0.392791 0.919628 0 0.392791 0.978587 0 0.205833 0.978587 0 0.205833 0.99994 0 0.0109653 0.99994 0 0.0109653 0.982866 0 -0.184324 0.982866 0 -0.184324 0.92802 0 -0.37253 0.92802 0 -0.37253 0.837512 0 -0.54642 0.837512 0 -0.54642 0.714818 0 -0.699311 0.714818 0 -0.699311 0.564654 0 -0.825328 0.564654 0 -0.825328 0.392791 0 -0.919628 0.392791 0 -0.919628 0.205833 0 -0.978587 0.205833 0 -0.978587 0.010965 0 -0.99994 0.010965 0 -0.99994 -0.184324 0 -0.982866 -0.184324 0 -0.982866 -0.55514 0.705637 0.440337 -0.55514 0.705637 0.440337 -0.466207 0.705637 0.533599 -0.466208 0.705636 0.533599 -0.361856 0.705636 0.609211 -0.361855 0.705637 0.609211 -0.245535 0.705637 0.664673 -0.245534 0.705637 0.664672 -0.121092 0.705637 0.69815 -0.121092 0.705636 0.69815 0.00735516 0.705636 0.708536 0.0073552 0.705636 0.708536 0.135559 0.705636 0.695486 0.135559 0.705636 0.695486 -0.141334 -0.705903 -0.694065 -0.141336 -0.705894 -0.694073 -0.025167 -0.705894 -0.70787 -0.0251674 -0.705887 -0.707877 0.0916884 -0.705887 -0.702365 0.0916873 -0.705899 -0.702353 0.20604 -0.705899 -0.677683 0.206038 -0.705906 -0.677676 0.31477 -0.705905 -0.634522 0.314778 -0.705887 -0.634538 0.414926 -0.705888 -0.574072 0.414926 -0.705887 -0.574072 0.503756 -0.705889 -0.497947 0.503754 -0.705891 -0.497945 0.578842 -0.705892 -0.408238 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680026 -0.7059 -0.198167 0.703368 -0.7059 -0.0835358 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692382 -0.7059 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.658359 -0.705893 0.261301 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454644 -0.705893 0.543152 0.359044 -0.705891 0.610578 0.359041 -0.705897 0.610573 0.253647 -0.705897 0.661341 0.25365 -0.70589 0.661348 0.359042 0.705896 0.610573 0.253648 0.705896 0.661342 0.253648 0.705896 0.661343 0.537842 0.705895 0.460911 0.478806 0.706876 0.520645 0.589836 0.394392 0.704662 0.434271 0.70672 0.558529 0.359043 0.705894 0.610575 0.641383 0.645803 0.414206 0.789363 0.387009 0.476582 0.577964 0.706746 0.408005 0.573188 0.707109 0.414068 0.537839 0.705898 0.460909 0.766427 0.557275 0.319429 0.856665 0.387968 0.340009 0.643903 0.703556 0.300662 0.633846 0.707105 0.313434 0.620252 0.706806 0.340164 0.700716 0.707106 0.0948578 0.728634 0.669694 0.14354 0.861297 0.472907 0.185815 0.681116 0.707016 0.190288 0.668155 0.706832 0.232289 0.703912 0.706928 0.0690017 0.9114 0.409271 0.0429905 0.850755 0.5246 0.0317986 0.638136 0.705898 -0.307394 0.680027 0.705898 -0.198168 0.680032 0.705893 -0.198169 0.703375 0.705894 -0.0835366 0.703375 0.705893 -0.0835367 0.706696 0.707103 -0.0242091 0.710578 0.703568 -0.00848501 0.540065 0.7071 -0.456443 0.556653 0.706922 -0.436347 0.745632 0.409261 -0.52587 0.591011 0.706651 -0.389037 0.63814 0.705893 -0.307396 0.53746 0.669691 -0.512495 0.626646 0.472899 -0.619421 0.480028 0.697893 -0.531525 0.381585 0.703557 -0.5995 0.474844 0.557279 -0.681148 0.539905 0.387962 -0.746986 0.438772 0.706829 -0.554861 0.461892 0.707102 -0.535408 0.268305 0.706745 -0.654617 0.318461 0.645808 -0.693913 0.40977 0.387006 -0.826024 0.340418 0.706803 -0.620117 0.366258 0.707102 -0.604865 0.0916871 0.705897 -0.702355 0.162224 0.707044 -0.688311 0.250692 0.507221 -0.824548 0.218712 0.70639 -0.673185 0.261019 0.707108 -0.657166 -0.0268981 0.689408 -0.723874 0.0321883 0.707104 -0.706377 0.0916879 0.705894 -0.702359 -0.0251669 0.705898 -0.707866 -0.141335 0.705898 -0.69407 -0.141335 0.705896 -0.694072 -0.141332 -0.705909 -0.694059 -0.141334 -0.705901 -0.694067 -0.0251668 -0.705901 -0.707864 -0.0251672 -0.705894 -0.707871 0.0916876 -0.705894 -0.702358 0.0916864 -0.705905 -0.702347 0.206038 -0.705905 -0.677677 0.206036 -0.705913 -0.67767 0.314768 -0.705912 -0.634516 0.314775 -0.705893 -0.634532 0.414922 -0.705894 -0.574067 0.414922 -0.705894 -0.574067 0.503751 -0.705895 -0.497943 0.503749 -0.705898 -0.497941 0.578836 -0.705899 -0.408235 0.578838 -0.705897 -0.408236 0.638136 -0.705897 -0.307395 0.638125 -0.70591 -0.307389 0.680015 -0.705911 -0.198164 0.680019 -0.705907 -0.198165 0.703362 -0.705907 -0.083535 0.703373 -0.705896 -0.0835367 0.707529 -0.705895 0.033374 0.707518 -0.705907 0.0333738 0.692375 -0.705907 0.149372 0.692376 -0.705907 0.149372 0.658347 -0.705907 0.261296 0.658353 -0.7059 0.261299 0.606366 -0.705899 0.366096 0.606361 -0.705905 0.366093 0.537834 -0.705905 0.460904 0.537835 -0.705904 0.460905 0.454637 -0.705904 0.543143 0.45464 -0.7059 0.543147 0.359041 -0.705898 0.610572 0.359038 -0.705903 0.610567 0.253645 -0.705904 0.661335 0.253648 -0.705897 0.661342 0.253652 0.705884 0.661354 0.25365 0.70589 0.661348 0.359045 0.70589 0.610578 0.359048 0.705884 0.610584 0.454649 0.705886 0.543157 0.454645 0.705892 0.543153 0.537844 0.705891 0.460913 0.537844 0.705892 0.460913 0.606372 0.705892 0.3661 0.606378 0.705886 0.366104 0.658365 0.705886 0.261304 0.658358 0.705894 0.261301 0.692388 0.705893 0.149375 0.692388 0.705894 0.149375 0.707531 0.705894 0.0333741 0.707542 0.705882 0.0333749 0.703386 0.705882 -0.0835379 0.703375 0.705894 -0.0835369 0.680032 0.705893 -0.198169 0.680028 0.705898 -0.198168 0.638137 0.705897 -0.307395 0.638148 0.705884 -0.3074 0.578849 0.705884 -0.408243 0.578847 0.705886 -0.408242 0.503758 0.705885 -0.49795 0.50376 0.705883 -0.497951 0.41493 0.70588 -0.574078 0.41493 0.705882 -0.574077 0.314782 0.70588 -0.634544 0.314773 0.705899 -0.634528 0.20604 0.705899 -0.677682 0.206042 0.705892 -0.677689 0.0916878 0.705892 -0.70236 0.0916897 0.70588 -0.702372 -0.0251675 0.70588 -0.707884 -0.0251674 0.705887 -0.707877 -0.141337 0.705888 -0.69408 -0.141335 0.705896 -0.694072 -0.141334 -0.705903 -0.694065 -0.141336 -0.705894 -0.694073 -0.025167 -0.705894 -0.70787 -0.0251674 -0.705887 -0.707877 0.0916884 -0.705887 -0.702365 0.0916873 -0.705899 -0.702353 0.20604 -0.705899 -0.677683 0.206038 -0.705906 -0.677676 0.31477 -0.705905 -0.634522 0.314778 -0.705887 -0.634538 0.414926 -0.705888 -0.574072 0.414926 -0.705887 -0.574072 0.503756 -0.705889 -0.497947 0.503754 -0.705891 -0.497945 0.578842 -0.705892 -0.408238 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680026 -0.7059 -0.198167 0.703368 -0.7059 -0.0835358 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692382 -0.7059 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.658359 -0.705893 0.261301 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454644 -0.705893 0.543152 0.359044 -0.705891 0.610578 0.359041 -0.705897 0.610573 0.253647 -0.705897 0.661341 0.25365 -0.70589 0.661348 0.25365 0.70589 0.661348 0.253648 0.705897 0.661342 0.359042 0.705897 0.610573 0.359045 0.70589 0.610578 0.454644 0.705892 0.543152 0.45464 0.705899 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261302 0.658352 0.7059 0.261299 0.692382 0.7059 0.149373 0.692382 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680026 0.7059 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.40824 0.578842 0.705892 -0.408238 0.503753 0.705892 -0.497945 0.503755 0.705889 -0.497947 0.414927 0.705887 -0.574073 0.414926 0.705888 -0.574072 0.314779 0.705886 -0.634538 0.31477 0.705905 -0.634522 0.206038 0.705906 -0.677676 0.20604 0.705899 -0.677683 0.0916869 0.705899 -0.702354 0.0916888 0.705887 -0.702365 -0.0251672 0.705887 -0.707877 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141334 0.705902 -0.694065 -0.141334 -0.705903 -0.694065 -0.141336 -0.705894 -0.694073 -0.025167 -0.705894 -0.70787 -0.0251674 -0.705887 -0.707877 0.0916884 -0.705887 -0.702365 0.0916873 -0.705899 -0.702353 0.20604 -0.705899 -0.677683 0.206038 -0.705906 -0.677676 0.31477 -0.705905 -0.634522 0.314778 -0.705887 -0.634538 0.414926 -0.705888 -0.574072 0.414926 -0.705887 -0.574072 0.503756 -0.705889 -0.497947 0.503754 -0.705891 -0.497945 0.578842 -0.705892 -0.408238 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680026 -0.7059 -0.198167 0.703368 -0.7059 -0.0835358 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692382 -0.7059 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.658359 -0.705893 0.261301 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454644 -0.705893 0.543152 0.359044 -0.705891 0.610578 0.359041 -0.705897 0.610573 0.253647 -0.705897 0.661341 0.25365 -0.70589 0.661348 0.25365 0.70589 0.661348 0.253648 0.705897 0.661342 0.359042 0.705897 0.610573 0.359045 0.70589 0.610578 0.454644 0.705892 0.543152 0.45464 0.705899 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261302 0.658352 0.7059 0.261299 0.692382 0.7059 0.149373 0.692382 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680026 0.7059 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.40824 0.578842 0.705892 -0.408238 0.503753 0.705892 -0.497945 0.503755 0.705889 -0.497947 0.414927 0.705887 -0.574073 0.414926 0.705888 -0.574072 0.314779 0.705886 -0.634538 0.31477 0.705905 -0.634522 0.206038 0.705906 -0.677676 0.20604 0.705899 -0.677683 0.0916869 0.705899 -0.702354 0.0916888 0.705887 -0.702365 -0.0251672 0.705887 -0.707877 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141334 0.705902 -0.694065 -0.141334 -0.705903 -0.694065 -0.141336 -0.705894 -0.694073 -0.025167 -0.705894 -0.70787 -0.0251674 -0.705887 -0.707877 0.0916884 -0.705887 -0.702365 0.0916873 -0.705899 -0.702353 0.20604 -0.705899 -0.677683 0.206038 -0.705906 -0.677676 0.31477 -0.705905 -0.634522 0.314778 -0.705887 -0.634538 0.414926 -0.705888 -0.574072 0.414926 -0.705887 -0.574072 0.503756 -0.705889 -0.497947 0.503754 -0.705891 -0.497945 0.578842 -0.705892 -0.408238 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680026 -0.7059 -0.198167 0.703368 -0.7059 -0.0835358 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692382 -0.7059 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.658359 -0.705893 0.261301 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454644 -0.705893 0.543152 0.359044 -0.705891 0.610578 0.359041 -0.705897 0.610573 0.253647 -0.705897 0.661341 0.25365 -0.70589 0.661348 0.25365 0.70589 0.661348 0.253648 0.705897 0.661342 0.359042 0.705897 0.610573 0.359045 0.70589 0.610578 0.454644 0.705892 0.543152 0.45464 0.705899 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261302 0.658352 0.7059 0.261299 0.692382 0.7059 0.149373 0.692382 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680026 0.7059 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.40824 0.578842 0.705892 -0.408238 0.503753 0.705892 -0.497945 0.503755 0.705889 -0.497947 0.414927 0.705887 -0.574073 0.414926 0.705888 -0.574072 0.314779 0.705886 -0.634538 0.31477 0.705905 -0.634522 0.206038 0.705906 -0.677676 0.20604 0.705899 -0.677683 0.0916869 0.705899 -0.702354 0.0916888 0.705887 -0.702365 -0.0251672 0.705887 -0.707877 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141334 0.705902 -0.694065 -0.141334 -0.705903 -0.694065 -0.141336 -0.705894 -0.694073 -0.025167 -0.705894 -0.70787 -0.0251674 -0.705887 -0.707877 0.0916884 -0.705887 -0.702365 0.0916873 -0.705899 -0.702353 0.20604 -0.705899 -0.677683 0.206038 -0.705906 -0.677676 0.31477 -0.705905 -0.634522 0.314778 -0.705887 -0.634538 0.414926 -0.705888 -0.574072 0.414926 -0.705887 -0.574072 0.503756 -0.705889 -0.497947 0.503754 -0.705891 -0.497945 0.578842 -0.705892 -0.408238 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680026 -0.7059 -0.198167 0.703368 -0.7059 -0.0835358 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692382 -0.7059 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.658359 -0.705893 0.261301 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454644 -0.705893 0.543152 0.359044 -0.705891 0.610578 0.359041 -0.705897 0.610573 0.253647 -0.705897 0.661341 0.25365 -0.70589 0.661348 0.25365 0.70589 0.661348 0.253648 0.705897 0.661342 0.359042 0.705897 0.610573 0.359045 0.70589 0.610578 0.454644 0.705892 0.543152 0.45464 0.705899 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261302 0.658352 0.7059 0.261299 0.692382 0.7059 0.149373 0.692382 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680026 0.7059 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.40824 0.578842 0.705892 -0.408238 0.503753 0.705892 -0.497945 0.503755 0.705889 -0.497947 0.414927 0.705887 -0.574073 0.414926 0.705888 -0.574072 0.314779 0.705886 -0.634538 0.31477 0.705905 -0.634522 0.206038 0.705906 -0.677676 0.20604 0.705899 -0.677683 0.0916869 0.705899 -0.702354 0.0916888 0.705887 -0.702365 -0.0251672 0.705887 -0.707877 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141334 0.705902 -0.694065 -0.141334 -0.705903 -0.694065 -0.141336 -0.705894 -0.694073 -0.025167 -0.705894 -0.70787 -0.0251674 -0.705887 -0.707877 0.0916884 -0.705887 -0.702365 0.0916873 -0.705899 -0.702353 0.20604 -0.705899 -0.677683 0.206038 -0.705906 -0.677676 0.31477 -0.705905 -0.634522 0.314778 -0.705887 -0.634538 0.414926 -0.705888 -0.574072 0.414926 -0.705887 -0.574072 0.503756 -0.705889 -0.497947 0.503754 -0.705891 -0.497945 0.578842 -0.705892 -0.408238 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680026 -0.7059 -0.198167 0.703368 -0.7059 -0.0835358 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692382 -0.7059 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.658359 -0.705893 0.261301 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454644 -0.705893 0.543152 0.359044 -0.705891 0.610578 0.359041 -0.705897 0.610573 0.253647 -0.705897 0.661341 0.25365 -0.70589 0.661348 0.25365 0.70589 0.661348 0.253648 0.705897 0.661342 0.359042 0.705897 0.610573 0.359045 0.70589 0.610578 0.454644 0.705892 0.543152 0.45464 0.705899 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261302 0.658352 0.7059 0.261299 0.692382 0.7059 0.149373 0.692382 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680026 0.7059 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.40824 0.578842 0.705892 -0.408238 0.503753 0.705892 -0.497945 0.503755 0.705889 -0.497947 0.414927 0.705887 -0.574073 0.414926 0.705888 -0.574072 0.314779 0.705886 -0.634538 0.31477 0.705905 -0.634522 0.206038 0.705906 -0.677676 0.20604 0.705899 -0.677683 0.0916869 0.705899 -0.702354 0.0916888 0.705887 -0.702365 -0.0251672 0.705887 -0.707877 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141334 0.705902 -0.694065 -0.141334 -0.705903 -0.694065 -0.141336 -0.705894 -0.694073 -0.025167 -0.705894 -0.70787 -0.0251674 -0.705887 -0.707877 0.0916884 -0.705887 -0.702365 0.0916873 -0.705899 -0.702353 0.20604 -0.705899 -0.677683 0.206038 -0.705906 -0.677676 0.31477 -0.705905 -0.634522 0.314778 -0.705887 -0.634538 0.414926 -0.705888 -0.574072 0.414926 -0.705887 -0.574072 0.503756 -0.705889 -0.497947 0.503754 -0.705891 -0.497945 0.578842 -0.705892 -0.408238 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680026 -0.7059 -0.198167 0.703368 -0.7059 -0.0835358 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692382 -0.7059 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.658359 -0.705893 0.261301 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454644 -0.705893 0.543152 0.359044 -0.705891 0.610578 0.359041 -0.705897 0.610573 0.253647 -0.705897 0.661341 0.25365 -0.70589 0.661348 0.25365 0.70589 0.661348 0.253648 0.705897 0.661342 0.359042 0.705897 0.610573 0.359045 0.70589 0.610578 0.454644 0.705892 0.543152 0.45464 0.705899 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261302 0.658352 0.7059 0.261299 0.692382 0.7059 0.149373 0.692382 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680026 0.7059 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.40824 0.578842 0.705892 -0.408238 0.503753 0.705892 -0.497945 0.503755 0.705889 -0.497947 0.414927 0.705887 -0.574073 0.414926 0.705888 -0.574072 0.314779 0.705886 -0.634538 0.31477 0.705905 -0.634522 0.206038 0.705906 -0.677676 0.20604 0.705899 -0.677683 0.0916869 0.705899 -0.702354 0.0916888 0.705887 -0.702365 -0.0251672 0.705887 -0.707877 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141334 0.705902 -0.694065 -0.141334 -0.705903 -0.694065 -0.141336 -0.705894 -0.694073 -0.025167 -0.705894 -0.70787 -0.0251674 -0.705887 -0.707877 0.0916884 -0.705887 -0.702365 0.0916873 -0.705899 -0.702353 0.20604 -0.705899 -0.677683 0.206038 -0.705906 -0.677676 0.31477 -0.705905 -0.634522 0.314778 -0.705887 -0.634538 0.414926 -0.705888 -0.574072 0.414926 -0.705887 -0.574072 0.503756 -0.705889 -0.497947 0.503754 -0.705891 -0.497945 0.578842 -0.705892 -0.408238 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680026 -0.7059 -0.198167 0.703368 -0.7059 -0.0835358 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692382 -0.7059 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.658359 -0.705893 0.261301 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454644 -0.705893 0.543152 0.359044 -0.705891 0.610578 0.359041 -0.705897 0.610573 0.253647 -0.705897 0.661341 0.25365 -0.70589 0.661348 0.25365 0.70589 0.661348 0.253648 0.705897 0.661342 0.359042 0.705897 0.610573 0.359045 0.70589 0.610578 0.454644 0.705892 0.543152 0.45464 0.705899 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261302 0.658352 0.7059 0.261299 0.692382 0.7059 0.149373 0.692382 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680026 0.7059 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.40824 0.578842 0.705892 -0.408238 0.503753 0.705892 -0.497945 0.503755 0.705889 -0.497947 0.414927 0.705887 -0.574073 0.414926 0.705888 -0.574072 0.314779 0.705886 -0.634538 0.31477 0.705905 -0.634522 0.206038 0.705906 -0.677676 0.20604 0.705899 -0.677683 0.0916869 0.705899 -0.702354 0.0916888 0.705887 -0.702365 -0.0251672 0.705887 -0.707877 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141334 0.705902 -0.694065 0.3581 0 0.933683 0.3581 0 0.933683 0.506895 0 0.862008 0.506895 0 0.862008 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856071 0 0.516858 0.856071 0 0.516858 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210886 0.977511 0 0.210886 0.998889 0 0.047118 0.998889 0 0.047118 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900923 0 -0.43398 0.900923 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444398 0 -0.895829 0.444398 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129445 0 -0.991587 0.129445 0 -0.991587 -0.0355311 0 -0.999369 -0.0355311 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506895 0 0.862008 0.506895 0 0.862008 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856071 0 0.516858 0.856071 0 0.516858 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210886 0.977511 0 0.210886 0.998889 0 0.047118 0.998889 0 0.047118 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900923 0 -0.43398 0.900923 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444398 0 -0.895829 0.444398 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129445 0 -0.991587 0.129445 0 -0.991587 -0.0355311 0 -0.999369 -0.0355311 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506895 0 0.862008 0.506895 0 0.862008 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856071 0 0.516858 0.856071 0 0.516858 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210886 0.977511 0 0.210886 0.998889 0 0.047118 0.998889 0 0.047118 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900923 0 -0.43398 0.900923 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444398 0 -0.895829 0.444398 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129445 0 -0.991587 0.129445 0 -0.991587 -0.0355311 0 -0.999369 -0.0355311 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506895 0 0.862008 0.506895 0 0.862008 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856071 0 0.516858 0.856071 0 0.516858 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210886 0.977511 0 0.210886 0.998889 0 0.047118 0.998889 0 0.047118 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900923 0 -0.43398 0.900923 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444398 0 -0.895829 0.444398 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129445 0 -0.991587 0.129445 0 -0.991587 -0.0355311 0 -0.999369 -0.0355311 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506895 0 0.862008 0.506895 0 0.862008 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856071 0 0.516858 0.856071 0 0.516858 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210886 0.977511 0 0.210886 0.998889 0 0.047118 0.998889 0 0.047118 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900923 0 -0.43398 0.900923 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444398 0 -0.895829 0.444398 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129445 0 -0.991587 0.129445 0 -0.991587 -0.0355311 0 -0.999369 -0.0355311 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506895 0 0.862008 0.506895 0 0.862008 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856071 0 0.516858 0.856071 0 0.516858 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210886 0.977511 0 0.210886 0.998889 0 0.047118 0.998889 0 0.047118 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900923 0 -0.43398 0.900923 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444398 0 -0.895829 0.444398 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129445 0 -0.991587 0.129445 0 -0.991587 -0.0355311 0 -0.999369 -0.0355311 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506895 0 0.862008 0.506895 0 0.862008 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856071 0 0.516858 0.856071 0 0.516858 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210886 0.977511 0 0.210886 0.998889 0 0.047118 0.998889 0 0.047118 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900923 0 -0.43398 0.900923 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444398 0 -0.895829 0.444398 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129445 0 -0.991587 0.129445 0 -0.991587 -0.0355311 0 -0.999369 -0.0355311 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506895 0 0.862008 0.506895 0 0.862008 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856071 0 0.516858 0.856071 0 0.516858 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210886 0.977511 0 0.210886 0.998889 0 0.047118 0.998889 0 0.047118 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900923 0 -0.43398 0.900923 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444398 0 -0.895829 0.444398 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129445 0 -0.991587 0.129445 0 -0.991587 -0.0355311 0 -0.999369 -0.0355311 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.141334 -0.705903 -0.694065 -0.141336 -0.705894 -0.694073 -0.025167 -0.705894 -0.70787 -0.0251674 -0.705887 -0.707877 0.0916884 -0.705887 -0.702365 0.0916873 -0.705899 -0.702353 0.20604 -0.705899 -0.677683 0.206038 -0.705906 -0.677676 0.31477 -0.705905 -0.634522 0.314778 -0.705887 -0.634538 0.414926 -0.705888 -0.574072 0.414926 -0.705887 -0.574072 0.503756 -0.705889 -0.497947 0.503754 -0.705891 -0.497945 0.578842 -0.705892 -0.408238 0.578843 -0.70589 -0.40824 0.638142 -0.705891 -0.307397 0.638131 -0.705903 -0.307392 0.680022 -0.705904 -0.198166 0.680026 -0.7059 -0.198167 0.703368 -0.7059 -0.0835358 0.703379 -0.705889 -0.0835374 0.707536 -0.705889 0.0333743 0.707524 -0.705901 0.0333741 0.692382 -0.7059 0.149373 0.692382 -0.7059 0.149373 0.658353 -0.7059 0.261299 0.658359 -0.705893 0.261301 0.606372 -0.705893 0.3661 0.606366 -0.705899 0.366097 0.537839 -0.705898 0.460909 0.53784 -0.705898 0.460909 0.454641 -0.705898 0.543148 0.454644 -0.705893 0.543152 0.359044 -0.705891 0.610578 0.359041 -0.705897 0.610573 0.253647 -0.705897 0.661341 0.25365 -0.70589 0.661348 0.25365 0.70589 0.661348 0.253648 0.705897 0.661342 0.359042 0.705897 0.610573 0.359045 0.70589 0.610578 0.454644 0.705892 0.543152 0.45464 0.705899 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261302 0.658352 0.7059 0.261299 0.692382 0.7059 0.149373 0.692382 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680026 0.7059 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.40824 0.578842 0.705892 -0.408238 0.503753 0.705892 -0.497945 0.503755 0.705889 -0.497947 0.414927 0.705887 -0.574073 0.414926 0.705888 -0.574072 0.314779 0.705886 -0.634538 0.31477 0.705905 -0.634522 0.206038 0.705906 -0.677676 0.20604 0.705899 -0.677683 0.0916869 0.705899 -0.702354 0.0916888 0.705887 -0.702365 -0.0251672 0.705887 -0.707877 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141334 0.705902 -0.694065 0.3581 0 0.933683 0.3581 0 0.933683 0.506895 0 0.862008 0.506895 0 0.862008 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856071 0 0.516858 0.856071 0 0.516858 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210886 0.977511 0 0.210886 0.998889 0 0.047118 0.998889 0 0.047118 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900923 0 -0.43398 0.900923 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444398 0 -0.895829 0.444398 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129445 0 -0.991587 0.129445 0 -0.991587 -0.0355311 0 -0.999369 -0.0355311 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.270241 0.258821 0.927352 0.270241 0.258819 0.927352 0.19783 0.707106 0.67887 0.19783 0.707107 0.678869 0.0724103 0.965926 0.248481 0.0724103 0.965926 0.248481 -0.0724103 0.965926 -0.248481 -0.0724103 0.965926 -0.248481 -0.19783 0.707107 -0.678869 -0.19783 0.707106 -0.67887 -0.270241 0.258819 -0.927352 -0.270241 0.258821 -0.927352 -0.776964 0.510203 0.368808 -0.710717 0.373494 0.59614 -0.672469 0.136705 0.727391 -0.957953 0.136708 -0.252265 -0.919704 0.373497 -0.121015 -0.853458 0.510203 0.106312 0.270241 0.258818 0.927353 0.270241 0.258818 0.927353 0.19783 0.707107 0.678869 0.19783 0.707107 0.678869 0.0724103 0.965926 0.248481 0.0724104 0.965926 0.248482 -0.0724102 0.965926 -0.248481 -0.0724101 0.965927 -0.248481 -0.197831 0.707106 -0.67887 -0.197831 0.707105 -0.67887 -0.270241 0.258821 -0.927352 -0.270241 0.258821 -0.927352 -0.776962 0.510203 0.368813 -0.710717 0.373496 0.59614 -0.672469 0.136708 0.72739 -0.957952 0.136709 -0.252268 -0.919705 0.373493 -0.121019 -0.853458 0.510203 0.106312 -0.270241 0.258818 -0.927353 -0.270241 0.258818 -0.927353 -0.19783 0.707108 -0.678868 -0.19783 0.707106 -0.67887 -0.0724104 0.965926 -0.248482 -0.0724102 0.965926 -0.248481 0.0724102 0.965926 0.248481 0.0724102 0.965926 0.248481 0.19783 0.707106 0.67887 0.19783 0.707106 0.67887 0.270241 0.258818 0.927353 0.270241 0.258818 0.927353 0.776964 0.510203 -0.368809 0.710716 0.373492 -0.596142 0.672469 0.136708 -0.72739 0.957953 0.136708 0.252266 0.919704 0.373497 0.121015 0.853458 0.510203 -0.106312 -0.270241 0.258819 -0.927352 -0.270241 0.258819 -0.927352 -0.19783 0.707106 -0.67887 -0.19783 0.707106 -0.67887 -0.0724102 0.965927 -0.248481 -0.0724102 0.965926 -0.248481 0.0724103 0.965926 0.248481 0.0724102 0.965927 0.248481 0.19783 0.707106 0.67887 0.19783 0.707106 0.67887 0.270241 0.258819 0.927352 0.270241 0.258819 0.927352 0.776962 0.510203 -0.368812 0.710716 0.373495 -0.596141 0.672469 0.136709 -0.72739 0.957952 0.136708 0.252268 0.919705 0.373494 0.121019 0.853458 0.510203 -0.106312 -0.0156491 -0.694746 -0.719085 -0.0156494 -0.694746 -0.719085 0.34599 -0.694746 -0.63057 0.345991 -0.694746 -0.63057 0.614921 -0.694746 -0.373097 0.614922 -0.694745 -0.373096 0.719087 -0.694744 -0.0156448 0.719085 -0.694746 -0.0156479 0.630571 -0.694745 0.34599 0.630571 -0.694747 0.345987 0.373097 -0.694747 0.614919 0.373096 -0.694746 0.614921 -0.0217574 0 -0.999763 -0.0217574 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.85494 0 -0.518726 0.85494 0 -0.518726 0.999763 0 -0.0217513 0.999763 0 -0.0217513 0.876699 0 0.481039 0.876699 0 0.481039 0.518727 0 0.85494 0.518727 0 0.85494 0.373098 0.694746 0.61492 0.373095 0.694747 0.61492 0.630569 0.694747 0.345989 0.630572 0.694746 0.345988 0.719085 0.694746 -0.0156448 0.719087 0.694744 -0.0156479 0.614922 0.694744 -0.373097 0.614922 0.694745 -0.373096 0.34599 0.694746 -0.63057 0.345991 0.694746 -0.63057 -0.0156491 0.694746 -0.719085 -0.0156494 0.694746 -0.719085 0.373093 -0.694747 0.614922 0.35736 -0.678374 0.641953 0.492291 -0.70686 0.507937 0.630571 -0.694747 0.345987 0.629508 -0.660378 0.409416 0.673291 -0.706115 0.219272 0.719085 -0.694746 -0.0156479 0.764727 -0.64061 0.0693546 0.69894 -0.704875 -0.120969 0.654505 -0.704875 -0.273451 0.632224 -0.673164 -0.383592 0.562805 -0.703124 -0.434589 0.450093 -0.706116 -0.546641 0.354078 -0.676903 -0.645314 -0.0423341 -0.698073 -0.714774 -0.0158688 -0.68421 -0.729112 0.142354 -0.706859 -0.692882 0.295434 -0.700861 -0.64924 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.201248 0 -0.97954 0.201248 0 -0.97954 0.41418 0 -0.910195 0.41418 0 -0.910195 0.635639 0 -0.771987 0.635639 0 -0.771987 0.791493 0 -0.611179 0.791493 0 -0.611179 0.922706 0 -0.385505 0.922706 0 -0.385505 0.985351 0 -0.17054 0.985351 0 -0.17054 0.995913 0 0.0903212 0.995913 0 0.0903212 0.950846 0 0.309664 0.950846 0 0.309664 0.8383 0 0.545209 0.8383 0 0.545209 0.695961 0 0.71808 0.695961 0 0.71808 0.486391 0 0.873741 0.486391 0 0.873741 -0.0156505 0.694746 -0.719084 -0.043439 0.678375 -0.73343 0.142354 0.706859 -0.692882 0.345989 0.694746 -0.630571 0.311021 0.66038 -0.683494 0.450093 0.706116 -0.546641 0.614921 0.694746 -0.373094 0.607756 0.640617 -0.4693 0.654505 0.704875 -0.273451 0.69894 0.704875 -0.120969 0.739321 0.673161 -0.0160882 0.708161 0.703124 0.0642245 0.673291 0.706115 0.219272 0.645315 0.676903 0.354077 0.348269 0.698074 0.625621 0.378296 0.684209 0.623498 0.492291 0.706859 0.507937 0.597957 0.700862 0.388896 -0.015653 -0.694745 -0.719086 -0.0156531 -0.694745 -0.719086 0.345991 -0.694745 -0.630571 0.345993 -0.694744 -0.630571 0.614922 -0.694744 -0.373096 0.614922 -0.694745 -0.373096 0.719087 -0.694744 -0.0156489 0.719086 -0.694745 -0.0156504 0.63057 -0.694746 0.345991 0.63057 -0.694746 0.345991 0.373097 -0.694746 0.61492 0.373096 -0.694745 0.614922 -0.0217628 0 -0.999763 -0.0217628 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.021757 0.999763 0 -0.021757 0.876699 0 0.48104 0.876699 0 0.48104 0.518727 0 0.85494 0.518727 0 0.85494 0.373098 0.694744 0.614921 0.373096 0.694745 0.614921 0.63057 0.694746 0.345991 0.63057 0.694746 0.345991 0.719085 0.694745 -0.0156489 0.719086 0.694745 -0.0156504 0.614922 0.694745 -0.373096 0.614922 0.694744 -0.373096 0.345992 0.694744 -0.630572 0.345992 0.694745 -0.630571 -0.015653 0.694745 -0.719086 -0.0156531 0.694745 -0.719086 0.373094 0.694748 0.614919 0.373092 0.694751 0.614917 0.630565 0.694753 0.345987 0.630567 0.694751 0.345987 0.71908 0.694751 -0.0156488 0.719085 0.694746 -0.0156508 0.614921 0.694747 -0.373093 0.614923 0.694744 -0.373096 0.345988 0.694746 -0.630571 0.345988 0.69475 -0.630567 -0.0156494 0.694749 -0.719082 -0.0156492 0.69475 -0.719082 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854943 0 -0.518722 0.854943 0 -0.518722 0.481037 0 -0.8767 0.481037 0 -0.8767 -0.0217579 0 -0.999763 -0.0217579 0 -0.999763 0.348273 0.698073 0.62562 0.348269 0.698077 0.625617 0.585222 0.69808 0.412553 0.585228 0.698075 0.412554 0.706273 0.698074 0.117777 0.706269 0.698078 0.117778 0.687429 0.698077 -0.200325 0.687425 0.698082 -0.200321 0.532433 0.698082 -0.478745 0.532434 0.698078 -0.478749 0.271984 0.698078 -0.662354 0.271984 0.698077 -0.662354 -0.0423338 0.698078 -0.714769 -0.0423337 0.698078 -0.714769 0.486397 0 0.873738 0.486397 0 0.873738 0.817326 0 0.576175 0.817326 0 0.576175 0.986379 0 0.164486 0.986379 0 0.164486 0.960066 0 -0.279775 0.960066 0 -0.279775 0.743603 0 -0.668622 0.743603 0 -0.668622 0.379854 0 -0.925046 0.379854 0 -0.925046 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 -0.0423315 0.698082 -0.714765 -0.0423338 0.698078 -0.714769 0.142356 0.706863 -0.692878 0.288131 0.651636 -0.701677 0.295431 0.700866 -0.649237 0.450085 0.706121 -0.546641 0.583691 0.619556 -0.524838 0.562803 0.70312 -0.434598 0.654511 0.70487 -0.27345 0.76216 0.608097 -0.222102 0.698945 0.704871 -0.120961 0.706272 0.698074 0.117778 0.824145 0.561425 0.0747433 0.673292 0.706116 0.219265 0.585226 0.698074 0.412556 0.348271 0.698075 0.625619 0.348271 0.698075 0.625619 0.49229 0.706861 0.507935 0.645924 0.637418 0.420096 0.486395 0 0.873739 0.518723 0.00303665 0.854937 0.695962 0 0.718079 0.838298 0 0.545213 0.876689 0.00507072 0.481032 0.950849 0 0.309655 0.995913 0 0.0903212 0.999745 0.0060904 -0.0217567 0.985353 0 -0.170527 0.922708 0 -0.385501 0.854927 0.00609048 -0.518713 0.791485 0 -0.611188 0.635632 0 -0.771992 0.48103 0.00507017 -0.87669 -0.0591236 0 -0.998251 -0.021757 0.00303655 -0.999759 0.201252 0 -0.97954 0.414178 0 -0.910196 0.348271 0.698076 0.625618 0.348268 0.698079 0.625616 0.585221 0.698081 0.412552 0.585228 0.698075 0.412553 0.706273 0.698074 0.117777 0.706269 0.698078 0.117778 0.687429 0.698077 -0.200324 0.687425 0.698082 -0.200321 0.532433 0.698081 -0.478746 0.532434 0.698078 -0.47875 0.271984 0.698077 -0.662355 0.271984 0.698079 -0.662352 -0.0423348 0.698076 -0.714771 -0.0423346 0.698077 -0.714771 -0.0423349 0.698075 -0.714772 -0.0423351 0.698075 -0.714772 0.14236 0.706863 -0.692877 0.288132 0.651638 -0.701675 0.29543 0.700864 -0.649239 0.450097 0.706118 -0.546635 0.583686 0.619565 -0.524834 0.562795 0.703133 -0.434587 0.687425 0.698082 -0.200321 0.815741 0.467337 -0.340827 0.698942 0.704877 -0.12095 0.706269 0.698078 0.117778 0.824157 0.561409 0.0747361 0.673289 0.706117 0.219274 0.585228 0.698075 0.412554 0.348273 0.698073 0.62562 0.348269 0.698077 0.625617 0.492281 0.706864 0.50794 0.645926 0.637418 0.420093 0.348271 0.698077 0.625617 0.348267 0.698081 0.625614 0.58522 0.698082 0.412551 0.585228 0.698075 0.412552 0.706273 0.698074 0.117777 0.70627 0.698077 0.117778 0.687428 0.698078 -0.200324 0.687425 0.698082 -0.200321 0.532432 0.698082 -0.478746 0.532433 0.698078 -0.47875 0.271985 0.698078 -0.662353 0.271985 0.69808 -0.662351 -0.0423338 0.698077 -0.71477 -0.0423361 0.698073 -0.714774 0.373088 0.694756 0.614914 0.373092 0.694752 0.614917 0.630568 0.69475 0.345987 0.63057 0.694748 0.345987 0.71908 0.694751 -0.0156487 0.71908 0.694751 -0.0156489 0.614918 0.69475 -0.373094 0.614915 0.694754 -0.37309 0.345987 0.694754 -0.630563 0.345987 0.69475 -0.630568 -0.0156488 0.694751 -0.71908 -0.0156508 0.694746 -0.719085 0.373096 -0.694744 0.614923 0.373095 -0.694747 0.61492 0.630569 -0.694748 0.345989 0.711986 -0.527877 0.463057 0.67329 -0.706116 0.219274 0.719085 -0.694746 -0.0156508 0.908902 -0.408783 0.0824211 0.69895 -0.704868 -0.120951 0.654507 -0.704868 -0.273461 0.704407 -0.5667 -0.427389 -0.0156494 -0.694745 -0.719086 -0.0156493 -0.694745 -0.719086 0.295432 -0.700861 -0.649241 0.387721 -0.591906 -0.706625 0.450098 -0.706117 -0.546636 0.5628 -0.703125 -0.434593 -0.0217577 0 -0.999763 -0.0591247 0.0018828 -0.998249 0.414177 -0.00161882 -0.910195 0.379853 0 -0.925047 0.635646 0 -0.771981 0.7436 -0.00216686 -0.668621 0.791488 0 -0.611185 0.922701 0 -0.385516 0.960063 -0.00243909 -0.279773 0.985355 0 -0.170513 0.995914 0 0.0903115 0.986377 -0.002167 0.164486 0.950845 0 0.309667 0.8383 0 0.545209 0.817326 -0.0013525 0.576174 0.518724 0.00161868 0.85494 0.486396 0 0.873738 -0.0156489 -0.694744 -0.719087 -0.0156498 -0.694746 -0.719085 0.345989 -0.694747 -0.630569 0.345991 -0.694746 -0.63057 0.614919 -0.694747 -0.373096 0.614925 -0.694741 -0.373097 0.719089 -0.694742 -0.015649 0.719085 -0.694746 -0.0156508 0.630571 -0.694745 0.34599 0.63057 -0.694747 0.345988 0.373096 -0.694746 0.614921 0.373096 -0.694741 0.614926 -0.0591253 0 -0.998251 -0.021757 0.00161879 -0.999762 0.201258 0 -0.979538 0.414177 0 -0.910196 0.481037 0.00270301 -0.876696 0.635646 0 -0.771981 0.791489 0 -0.611184 0.854936 0.00324642 -0.518724 0.922701 0 -0.385517 0.985355 0 -0.170513 0.999758 0.00324639 -0.021757 0.995914 0 0.0903113 0.950845 0 0.309667 0.876696 0.00270291 0.481037 0.8383 0 0.545209 0.695951 0 0.718089 0.518724 0.00161865 0.85494 0.486397 0 0.873738 -0.0423343 -0.698069 -0.714778 -0.0423361 -0.698073 -0.714774 0.271985 -0.698076 -0.662355 0.271987 -0.698073 -0.662357 0.532438 -0.698074 -0.478752 0.532434 -0.698077 -0.478751 0.687428 -0.698078 -0.200324 0.687432 -0.698074 -0.200323 0.706274 -0.698073 0.117777 0.706277 -0.69807 0.117779 0.58523 -0.69807 0.412558 0.585226 -0.698077 0.412551 0.348271 -0.698077 0.625617 0.348271 -0.698072 0.625621 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379855 0 -0.925046 0.379855 0 -0.925046 0.743601 0 -0.668623 0.743601 0 -0.668623 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164487 0.986379 0 0.164487 0.817326 0 0.576175 0.817326 0 0.576175 0.486397 0 0.873738 0.486397 0 0.873738 -0.015649 -0.694742 -0.719089 -0.0156508 -0.694746 -0.719085 0.345991 -0.694745 -0.630571 0.345987 -0.694749 -0.630568 0.614918 -0.69475 -0.373094 0.614922 -0.694745 -0.373094 0.719085 -0.694746 -0.0156488 0.719084 -0.694747 -0.015649 0.630573 -0.694743 0.34599 0.630572 -0.694745 0.345989 0.373093 -0.694747 0.614922 0.373092 -0.694752 0.614917 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.021757 0.999763 0 -0.021757 0.8767 0 0.481038 0.8767 0 0.481038 0.518722 0 0.854943 0.518722 0 0.854943 -0.0156488 -0.694746 -0.719085 -0.0156478 -0.694746 -0.719085 0.345991 -0.694746 -0.63057 0.345991 -0.694746 -0.63057 0.61492 -0.694746 -0.373097 0.614922 -0.694745 -0.373096 0.719086 -0.694745 -0.0156531 0.719086 -0.694745 -0.0156531 0.630571 -0.694746 0.345989 0.630571 -0.694744 0.345993 0.373093 -0.694744 0.614925 0.373096 -0.694746 0.614921 -0.021757 0 -0.999763 -0.021757 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.85494 0 -0.518727 0.85494 0 -0.518727 0.999763 0 -0.0217629 0.999763 0 -0.0217629 0.8767 0 0.481038 0.8767 0 0.481038 0.51872 0 0.854944 0.51872 0 0.854944 0.373092 0.694747 0.614922 0.373096 0.694744 0.614922 0.630573 0.694744 0.34599 0.63057 0.694745 0.345992 0.719086 0.694745 -0.0156531 0.719086 0.694745 -0.0156531 0.614921 0.694744 -0.373098 0.614921 0.694745 -0.373096 0.345991 0.694746 -0.63057 0.345991 0.694746 -0.63057 -0.0156489 0.694745 -0.719085 -0.0156478 0.694746 -0.719085 -0.0156448 -0.694744 -0.719087 -0.0156479 -0.694746 -0.719085 0.345991 -0.694745 -0.630571 0.345987 -0.694747 -0.630571 0.61492 -0.694746 -0.373096 0.614921 -0.694746 -0.373096 0.719084 -0.694747 -0.015653 0.719086 -0.694745 -0.0156504 0.63057 -0.694746 0.345991 0.63057 -0.694746 0.345991 0.373096 -0.694745 0.614922 0.373095 -0.694745 0.614923 -0.0591169 0 -0.998251 -0.0217512 0.00192592 -0.999762 0.201248 0 -0.97954 0.414177 0 -0.910196 0.481038 0.00321613 -0.876694 0.635649 0 -0.771979 0.791484 0 -0.61119 0.854935 0.0038629 -0.518722 0.922706 0 -0.385505 0.985353 0 -0.170525 0.999756 0.00386279 -0.0217626 0.995914 0 0.0903113 0.950846 0 0.309664 0.876694 0.00321607 0.481038 0.838298 0 0.545213 0.695962 0 0.718079 0.518724 0.00192604 0.85494 0.486394 0 0.87374 -0.0423389 0.698072 -0.714775 -0.0423291 0.698077 -0.714771 0.142353 0.706862 -0.692879 0.275155 0.689419 -0.670068 0.295431 0.700861 -0.649241 0.450101 0.706115 -0.546636 0.542402 0.684059 -0.487713 0.562799 0.703124 -0.434597 0.654507 0.704872 -0.273452 0.701928 0.682244 -0.204552 0.698944 0.704874 -0.120959 0.706273 0.698074 0.11778 0.740207 0.66902 0.0671233 0.673292 0.706114 0.219272 0.58523 0.698071 0.412556 0.348272 0.698072 0.625622 0.348271 0.698072 0.625622 0.492292 0.706858 0.507937 0.611359 0.684209 0.397616 -0.0423294 -0.698071 -0.714776 -0.0423329 -0.698073 -0.714774 0.271986 -0.698073 -0.662358 0.271984 -0.698073 -0.662358 0.532436 -0.698074 -0.478754 0.532437 -0.698073 -0.478754 0.687433 -0.698073 -0.200326 0.687434 -0.698072 -0.200325 0.706273 -0.698073 0.117778 0.706274 -0.698073 0.117779 0.585228 -0.698072 0.412558 0.585228 -0.698073 0.412556 0.348272 -0.698072 0.625621 0.348275 -0.698074 0.625617 -0.0591169 0 -0.998251 -0.0217513 -0.00192592 -0.999762 0.379853 0.00160914 -0.925045 0.414177 0 -0.910196 0.635644 0 -0.771982 0.743595 0.00257811 -0.668625 0.791484 0 -0.61119 0.922704 0 -0.38551 0.960062 0.00290188 -0.279773 0.985354 0 -0.170521 0.995913 0 0.0903169 0.986376 0.0025782 0.164488 0.950847 0 0.309661 0.817326 0 0.576175 0.838296 0.00192589 0.545212 0.486394 -0.00224028 0.873737 0.518727 0 0.85494 -0.0156479 0.694744 -0.719087 -0.0156447 0.694746 -0.719085 0.345988 0.694746 -0.630572 0.311019 0.660379 -0.683496 0.450097 0.706117 -0.546637 0.61492 0.694747 -0.373095 0.607753 0.640611 -0.469312 0.654505 0.704872 -0.273455 0.698945 0.704872 -0.120956 0.73932 0.673162 -0.0160896 0.373096 0.694748 0.614919 0.373099 0.694746 0.614919 0.597956 0.700861 0.388899 0.645314 0.676902 0.354081 0.673292 0.706116 0.21927 0.708161 0.703124 0.0642214 0.373089 0.694755 0.614915 0.373097 0.694745 0.61492 0.630572 0.694744 0.345991 0.630572 0.694744 0.345991 0.71909 0.694741 -0.0156531 0.719076 0.694755 -0.0156469 0.614915 0.694754 -0.37309 0.614917 0.694752 -0.373092 0.345989 0.69475 -0.630566 0.345989 0.694747 -0.630569 -0.0156487 0.694751 -0.71908 -0.0156508 0.694746 -0.719085 0.518722 0 0.854943 0.518722 0 0.854943 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217628 0.999763 0 -0.0217628 0.854943 0 -0.518723 0.854943 0 -0.518723 0.48104 0 -0.876699 0.48104 0 -0.876699 -0.021757 0 -0.999763 -0.021757 0 -0.999763 0.373089 0.694754 0.614916 0.373098 0.694744 0.614922 0.630573 0.694745 0.345988 0.630566 0.694752 0.345987 0.71908 0.694751 -0.0156488 0.71908 0.694751 -0.0156489 0.614918 0.69475 -0.373094 0.614918 0.69475 -0.373093 0.345987 0.694752 -0.630566 0.345987 0.694752 -0.630566 -0.0156488 0.694751 -0.71908 -0.0156508 0.694746 -0.719085 0.518722 0 0.854943 0.518722 0 0.854943 0.876701 0 0.481036 0.876701 0 0.481036 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.373089 0.694755 0.614915 0.373092 0.694752 0.614916 0.630566 0.694751 0.345988 0.630571 0.694747 0.345988 0.719081 0.69475 -0.015649 0.719082 0.694749 -0.0156494 0.614919 0.694748 -0.373095 0.614917 0.694751 -0.373092 0.345987 0.694753 -0.630565 0.345987 0.694751 -0.630567 -0.0156488 0.694751 -0.71908 -0.0156508 0.694746 -0.719085 0.518722 0 0.854943 0.518722 0 0.854943 0.876699 0 0.48104 0.876699 0 0.48104 0.999763 0 -0.0217574 0.999763 0 -0.0217574 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.348269 0.698077 0.625618 0.348269 0.698076 0.625618 0.585229 0.698074 0.412553 0.585221 0.698082 0.412551 0.706263 0.698083 0.11778 0.70627 0.698077 0.117778 0.687428 0.698078 -0.200324 0.687431 0.698074 -0.200327 0.532435 0.698075 -0.478754 0.532433 0.698078 -0.47875 0.271986 0.698078 -0.662353 0.271986 0.698077 -0.662354 -0.0423338 0.698078 -0.714769 -0.0423364 0.698073 -0.714774 -0.0156469 0.694755 -0.719076 -0.0156488 0.694751 -0.71908 0.345987 0.694752 -0.630566 0.351769 0.527877 -0.773049 0.450094 0.706121 -0.546634 0.614918 0.69475 -0.373093 0.722338 0.408779 -0.557788 0.654501 0.704876 -0.273455 0.698941 0.704877 -0.120955 0.823726 0.566704 -0.0179262 0.373094 0.694746 0.614922 0.373096 0.694744 0.614923 0.597958 0.70086 0.388897 0.706621 0.591911 0.387721 0.673286 0.706121 0.21927 0.708156 0.703129 0.0642205 -0.0156469 0.694755 -0.719076 -0.0462964 0.621967 -0.781674 0.142358 0.706864 -0.692876 0.345987 0.694752 -0.630566 0.351769 0.527878 -0.773048 0.450093 0.706122 -0.546633 0.614917 0.694752 -0.373092 0.72234 0.408772 -0.557791 0.654502 0.704877 -0.273453 0.69894 0.704877 -0.120958 0.823729 0.566701 -0.0179263 0.708159 0.703127 0.0642207 0.673288 0.706119 0.219271 0.706623 0.59191 0.387719 0.348272 0.698073 0.625621 0.399686 0.637418 0.658749 0.492284 0.706859 0.507944 0.597957 0.700862 0.388896 0.373093 0.694747 0.614921 0.373096 0.694744 0.614923 0.630571 0.694746 0.345988 0.630566 0.694751 0.345988 0.719082 0.694749 -0.0156493 0.719082 0.694749 -0.0156493 0.614919 0.694748 -0.373095 0.614917 0.694751 -0.373092 0.345987 0.694753 -0.630565 0.345987 0.694751 -0.630567 -0.0156488 0.694751 -0.71908 -0.0156469 0.694755 -0.719076 -0.0423343 -0.698069 -0.714778 -0.0423364 -0.698073 -0.714774 0.271988 -0.698072 -0.662358 0.271987 -0.698073 -0.662357 0.532435 -0.698074 -0.478754 0.532439 -0.69807 -0.478755 0.687437 -0.698069 -0.200327 0.687431 -0.698074 -0.200327 0.706274 -0.698072 0.117782 0.706268 -0.698079 0.117778 0.585226 -0.698078 0.412551 0.58523 -0.69807 0.412558 0.348271 -0.698072 0.625622 0.348271 -0.698072 0.625621 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379857 0 -0.925045 0.379857 0 -0.925045 0.743598 0 -0.668627 0.743598 0 -0.668627 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986378 0 0.164493 0.986378 0 0.164493 0.81733 0 0.57617 0.81733 0 0.57617 0.486394 0 0.87374 0.486394 0 0.87374 -0.0423338 -0.698078 -0.714769 -0.042332 -0.698074 -0.714774 0.271984 -0.698074 -0.662357 0.271986 -0.698073 -0.662358 0.532438 -0.698074 -0.478752 0.532437 -0.698074 -0.478752 0.687432 -0.698074 -0.200327 0.687434 -0.698071 -0.200326 0.706272 -0.698074 0.117778 0.706272 -0.698074 0.117778 0.585227 -0.698074 0.412556 0.585228 -0.698072 0.412558 0.348273 -0.69807 0.625623 0.348273 -0.698068 0.625625 -0.0591236 0 -0.998251 -0.021757 -0.00161871 -0.999762 0.379853 0.00135244 -0.925046 0.414177 0 -0.910196 0.635644 0 -0.771983 0.743599 0.0021669 -0.668622 0.791488 0 -0.611185 0.922703 0 -0.385511 0.960063 0.00243894 -0.279775 0.985354 0 -0.170521 0.995913 0 0.0903162 0.986377 0.00216694 0.164489 0.950846 0 0.309664 0.817327 0 0.576174 0.838299 0.00161881 0.545208 0.486394 -0.00188264 0.873737 0.518723 0 0.854943 0.373096 -0.694741 0.614926 0.380871 -0.621958 0.684182 0.492287 -0.706854 0.507947 0.630573 -0.694743 0.345991 0.711989 -0.527872 0.463059 0.673292 -0.706114 0.219272 0.719087 -0.694744 -0.015649 0.908907 -0.408771 0.0824259 0.698945 -0.704873 -0.120958 0.654506 -0.704872 -0.273454 0.704409 -0.566698 -0.42739 0.562799 -0.703126 -0.434594 0.450096 -0.706118 -0.546637 0.38772 -0.591909 -0.706624 -0.0423338 -0.698078 -0.714769 -0.0167623 -0.637418 -0.770336 0.142359 -0.70686 -0.692881 0.295431 -0.700863 -0.64924 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.201256 0 -0.979539 0.201256 0 -0.979539 0.414177 0 -0.910196 0.414177 0 -0.910196 0.635644 0 -0.771983 0.635644 0 -0.771983 0.791487 0 -0.611186 0.791487 0 -0.611186 0.922704 0 -0.385508 0.922704 0 -0.385508 0.985354 0 -0.170524 0.985354 0 -0.170524 0.995913 0 0.0903162 0.995913 0 0.0903162 0.950846 0 0.309664 0.950846 0 0.309664 0.8383 0 0.545209 0.8383 0 0.545209 0.695951 0 0.718089 0.695951 0 0.718089 0.486395 0 0.873739 0.486395 0 0.873739 -0.0156488 -0.694751 -0.71908 -0.0156471 -0.694747 -0.719084 0.34599 -0.694746 -0.63057 0.345988 -0.694748 -0.630569 0.61492 -0.694747 -0.373095 0.614923 -0.694744 -0.373096 0.719086 -0.694745 -0.0156494 0.719086 -0.694745 -0.0156494 0.630571 -0.694746 0.345988 0.630574 -0.694742 0.345992 0.373097 -0.694739 0.614928 0.373097 -0.694742 0.614925 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217577 0.999763 0 -0.0217577 0.8767 0 0.481037 0.8767 0 0.481037 0.518722 0 0.854943 0.518722 0 0.854943 0.373096 -0.694746 0.614921 0.357361 -0.678372 0.641954 0.492306 -0.706859 0.507923 0.63057 -0.694745 0.345992 0.629507 -0.660379 0.409415 0.67329 -0.706115 0.219276 0.719085 -0.694746 -0.0156479 0.764727 -0.64061 0.0693546 0.69894 -0.704875 -0.120969 0.654506 -0.704875 -0.273448 0.632225 -0.673163 -0.383593 0.562806 -0.703123 -0.43459 0.450086 -0.706114 -0.546649 0.354078 -0.676903 -0.645314 -0.0423388 -0.698074 -0.714773 -0.0158688 -0.684208 -0.729114 0.142392 -0.706861 -0.692873 0.295428 -0.700863 -0.649241 -0.0591303 0 -0.99825 -0.0591303 0 -0.99825 0.201302 0 -0.979529 0.201302 0 -0.979529 0.414174 0 -0.910198 0.414174 0 -0.910198 0.635627 0 -0.771996 0.635627 0 -0.771996 0.791493 0 -0.611179 0.791493 0 -0.611179 0.922708 0 -0.385501 0.922708 0 -0.385501 0.985351 0 -0.17054 0.985351 0 -0.17054 0.995913 0 0.0903212 0.995913 0 0.0903212 0.950844 0 0.30967 0.950844 0 0.30967 0.8383 0 0.545209 0.8383 0 0.545209 0.695982 0 0.71806 0.695982 0 0.71806 0.486391 0 0.873741 0.486391 0 0.873741 -0.0156505 0.694746 -0.719084 -0.0434441 0.678372 -0.733433 0.142391 0.706861 -0.692873 0.345988 0.694748 -0.63057 0.311017 0.660378 -0.683498 0.450086 0.706114 -0.546649 0.614922 0.694745 -0.373095 0.607757 0.640615 -0.469301 0.654506 0.704875 -0.273448 0.69894 0.704875 -0.120969 0.739321 0.673161 -0.0160882 0.708161 0.703124 0.0642245 0.67329 0.706115 0.219276 0.645313 0.676902 0.354082 0.348269 0.698074 0.625621 0.378299 0.684208 0.623498 0.492306 0.706859 0.507923 0.597959 0.70086 0.388897 -0.0423387 -0.698076 -0.714771 -0.0423329 -0.698073 -0.714774 0.271986 -0.698072 -0.662358 0.271985 -0.698073 -0.662358 0.532439 -0.698073 -0.478751 0.532435 -0.698075 -0.478753 0.687431 -0.698074 -0.200328 0.687435 -0.698072 -0.200324 0.706274 -0.698073 0.117776 0.706274 -0.698072 0.117777 0.585227 -0.698073 0.412558 0.585227 -0.698075 0.412554 0.34827 -0.698075 0.625619 0.348269 -0.698075 0.62562 -0.0591303 0 -0.99825 -0.0591303 0 -0.99825 0.379854 0 -0.925046 0.379854 0 -0.925046 0.743602 0 -0.668622 0.743602 0 -0.668622 0.960065 0 -0.279777 0.960065 0 -0.279777 0.986379 0 0.164486 0.986379 0 0.164486 0.817325 0 0.576176 0.817325 0 0.576176 0.486394 0 0.87374 0.486394 0 0.87374 0.34827 0.698075 0.625619 0.348269 0.698075 0.625619 0.585225 0.698075 0.412557 0.585228 0.698074 0.412555 0.706275 0.698072 0.117776 0.706274 0.698073 0.117777 0.687434 0.698071 -0.200328 0.687433 0.698074 -0.200323 0.532437 0.698076 -0.47875 0.532436 0.698073 -0.478754 0.271986 0.698073 -0.662358 0.271985 0.698073 -0.662359 -0.0423389 0.698072 -0.714775 -0.0423328 0.698075 -0.714772 -0.0423294 -0.698071 -0.714776 -0.0423329 -0.698073 -0.714774 0.271986 -0.698073 -0.662358 0.271984 -0.698073 -0.662358 0.532435 -0.698074 -0.478755 0.532437 -0.698073 -0.478754 0.687433 -0.698073 -0.200326 0.687432 -0.698073 -0.200326 0.706274 -0.698073 0.117778 0.706274 -0.698073 0.117778 0.585228 -0.698072 0.412557 0.585229 -0.698073 0.412556 0.348272 -0.698072 0.625621 0.348271 -0.698072 0.625622 -0.0591169 0 -0.998251 -0.0217513 -0.00192592 -0.999762 0.379853 0.00160914 -0.925045 0.414177 0 -0.910196 0.635644 0 -0.771982 0.743595 0.0025781 -0.668625 0.791483 0 -0.611191 0.922704 0 -0.385509 0.960062 0.00290188 -0.279773 0.985354 0 -0.170521 0.995913 0 0.0903169 0.986376 0.0025782 0.164488 0.950847 0 0.309661 0.817326 0 0.576175 0.838296 0.00192589 0.545212 0.486394 -0.00224028 0.873737 0.518726 0 0.85494 -0.0156479 0.694744 -0.719087 -0.0156447 0.694746 -0.719085 0.345988 0.694746 -0.630572 0.311019 0.660379 -0.683496 0.450097 0.706117 -0.546637 0.61492 0.694747 -0.373095 0.607753 0.64061 -0.469313 0.654505 0.704872 -0.273455 0.698945 0.704872 -0.120956 0.73932 0.673162 -0.0160897 0.373097 0.694744 0.614922 0.373096 0.694745 0.614922 0.597956 0.700861 0.388899 0.645314 0.676902 0.354081 0.673292 0.706116 0.21927 0.708161 0.703124 0.0642214 0.373096 0.694746 0.614921 0.373096 0.694745 0.614921 0.630572 0.694744 0.345991 0.630567 0.694749 0.34599 0.71908 0.694751 -0.0156488 0.719085 0.694746 -0.0156508 0.61492 0.694745 -0.373097 0.614915 0.694754 -0.37309 0.345987 0.694754 -0.630563 0.345987 0.694748 -0.63057 -0.0156487 0.694751 -0.71908 -0.0156489 0.694751 -0.71908 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.85494 0 -0.518727 0.85494 0 -0.518727 0.48104 0 -0.876699 0.48104 0 -0.876699 -0.021757 0 -0.999763 -0.021757 0 -0.999763 0.373097 0.694745 0.61492 0.37309 0.694754 0.614915 0.630563 0.694754 0.345987 0.63057 0.694748 0.345987 0.71908 0.694751 -0.0156487 0.71908 0.694751 -0.0156489 0.614918 0.69475 -0.373094 0.614918 0.69475 -0.373093 0.345987 0.694752 -0.630566 0.345987 0.694752 -0.630566 -0.0156488 0.694751 -0.71908 -0.0156508 0.694746 -0.719085 0.518727 0 0.85494 0.518727 0 0.85494 0.876699 0 0.48104 0.876699 0 0.48104 0.999763 0 -0.021757 0.999763 0 -0.021757 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 -0.0156508 0.694746 -0.719085 -0.0156488 0.694751 -0.71908 0.345987 0.694751 -0.630567 0.351769 0.527878 -0.773048 0.450094 0.706122 -0.546633 0.614917 0.694751 -0.373092 0.72234 0.408772 -0.557791 0.654503 0.704875 -0.273454 0.698942 0.704876 -0.120956 0.823729 0.566701 -0.0179267 0.373089 0.694755 0.614915 0.373098 0.694745 0.614921 0.597957 0.700861 0.388896 0.706624 0.591909 0.38772 0.673288 0.70612 0.219268 0.708158 0.703128 0.0642217 0.518722 0 0.854943 0.486392 -0.00353163 0.873734 0.838296 0.00303679 0.545207 0.817326 0 0.576175 0.950847 0 0.309661 0.986371 0.00406485 0.164488 0.995913 0 0.0903178 0.985354 0 -0.170521 0.960056 0.0045752 -0.279771 0.922704 0 -0.385509 0.791487 0 -0.611186 0.743595 0.00406484 -0.668618 0.635644 0 -0.771982 0.414177 0 -0.910196 0.379852 0.00253704 -0.925044 -0.021757 -0.00303655 -0.999759 -0.0591236 0 -0.998251 0.373096 0.694746 0.614921 0.373092 0.69475 0.614919 0.630566 0.694752 0.345987 0.630568 0.69475 0.345987 0.71908 0.694751 -0.0156488 0.719085 0.694746 -0.0156508 0.614922 0.694746 -0.373094 0.614922 0.694746 -0.373094 0.345987 0.694749 -0.630568 0.345987 0.694752 -0.630566 -0.0156488 0.694751 -0.71908 -0.0156489 0.694751 -0.71908 -0.0423362 0.698074 -0.714773 -0.0423338 0.698078 -0.714769 0.142356 0.706863 -0.692878 0.288136 0.651634 -0.701677 0.295434 0.700858 -0.649244 0.450098 0.706113 -0.54664 0.583688 0.619559 -0.524839 0.562798 0.703125 -0.434595 0.654506 0.704873 -0.273452 0.76216 0.608097 -0.222102 0.698944 0.704873 -0.120959 0.706274 0.698073 0.117779 0.824146 0.561424 0.0747434 0.673291 0.706117 0.219269 0.585227 0.698075 0.412554 0.348271 0.698075 0.625619 0.348271 0.698075 0.625619 0.49229 0.706861 0.507935 0.645927 0.637416 0.420094 0.348272 0.698073 0.625621 0.34827 0.698075 0.625619 0.585226 0.698076 0.412554 0.585227 0.698075 0.412554 0.706273 0.698074 0.117777 0.70627 0.698077 0.117778 0.687428 0.698078 -0.200324 0.687428 0.698078 -0.200324 0.532434 0.698078 -0.478749 0.532437 0.698072 -0.478755 0.271986 0.698069 -0.662362 0.271987 0.698078 -0.662352 -0.0423338 0.698078 -0.714769 -0.0423362 0.698073 -0.714774 0.348272 0.698074 0.62562 0.348271 0.698074 0.625619 0.585227 0.698075 0.412553 0.585225 0.698077 0.412553 0.70627 0.698077 0.117778 0.706271 0.698076 0.117778 0.687429 0.698077 -0.200325 0.687429 0.698077 -0.200324 0.532434 0.698078 -0.478749 0.532437 0.698071 -0.478756 0.271987 0.698068 -0.662362 0.271988 0.698077 -0.662352 -0.0423338 0.698078 -0.714769 -0.0423362 0.698073 -0.714774 -0.0156489 -0.694746 -0.719085 -0.015649 -0.694746 -0.719085 0.345988 -0.694748 -0.63057 0.34599 -0.694745 -0.630571 0.614926 -0.694741 -0.373096 0.614926 -0.694741 -0.373096 0.719089 -0.694742 -0.015649 0.719085 -0.694746 -0.0156508 0.630571 -0.694745 0.34599 0.63057 -0.694747 0.345988 0.373096 -0.694746 0.614921 0.373096 -0.694741 0.614926 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854943 0 -0.518723 0.854943 0 -0.518723 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 -0.015649 -0.694742 -0.719089 -0.0156508 -0.694746 -0.719085 0.345991 -0.694745 -0.630571 0.345994 -0.694742 -0.630573 0.614922 -0.694745 -0.373096 0.614922 -0.694745 -0.373096 0.719085 -0.694746 -0.0156488 0.719085 -0.694746 -0.0156489 0.63057 -0.694748 0.345988 0.630571 -0.694746 0.34599 0.373096 -0.694747 0.614919 0.373096 -0.694744 0.614923 -0.0591236 0 -0.998251 -0.021757 0.00161871 -0.999762 0.201252 0 -0.97954 0.414178 0 -0.910196 0.481038 0.00270298 -0.876695 0.635644 0 -0.771983 0.791485 0 -0.611188 0.854937 0.00324663 -0.518722 0.922706 0 -0.385505 0.985353 0 -0.170525 0.999758 0.00324667 -0.0217569 0.995913 0 0.0903212 0.950847 0 0.309661 0.876697 0.00270295 0.481036 0.8383 0 0.545209 0.695962 0 0.718079 0.518725 0.00161876 0.85494 0.486395 0 0.873739 -0.0423343 -0.698069 -0.714778 -0.0423363 -0.698073 -0.714774 0.271984 -0.698074 -0.662357 0.271992 -0.698065 -0.662364 0.532442 -0.698067 -0.478756 0.532436 -0.698074 -0.478754 0.687432 -0.698073 -0.200325 0.687432 -0.698074 -0.200325 0.706274 -0.698073 0.117777 0.706277 -0.69807 0.117779 0.585231 -0.69807 0.412557 0.58523 -0.698071 0.412556 0.348273 -0.69807 0.625623 0.348273 -0.698068 0.625625 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379853 0 -0.925047 0.379853 0 -0.925047 0.743601 0 -0.668624 0.743601 0 -0.668624 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164487 0.986379 0 0.164487 0.817328 0 0.576173 0.817328 0 0.576173 0.486395 0 0.873739 0.486395 0 0.873739 0.373097 -0.694742 0.614925 0.373096 -0.694748 0.614919 0.63057 -0.694747 0.34599 0.711985 -0.527878 0.463057 0.67329 -0.706115 0.219274 0.719086 -0.694745 -0.0156494 0.908909 -0.408767 0.0824266 0.698946 -0.704871 -0.120957 0.654507 -0.704871 -0.273456 0.704409 -0.566694 -0.427393 -0.015649 -0.694742 -0.719089 -0.0156508 -0.694746 -0.719085 0.295431 -0.700862 -0.649241 0.387726 -0.591899 -0.706628 0.450101 -0.70611 -0.546642 0.562804 -0.703119 -0.434597 -0.0217571 0 -0.999763 -0.0591235 0.00188276 -0.998249 0.414176 -0.00161875 -0.910195 0.379854 0 -0.925047 0.635644 0 -0.771982 0.743599 -0.00216688 -0.668622 0.791487 0 -0.611186 0.922704 0 -0.38551 0.960063 -0.00243894 -0.279773 0.985354 0 -0.170521 0.995913 0 0.0903169 0.986377 -0.00216693 0.164489 0.950845 0 0.309667 0.8383 0 0.54521 0.817328 -0.00135237 0.576172 0.518726 0.00161881 0.854939 0.486395 0 0.873739 -0.0156493 -0.694746 -0.719085 -0.0156493 -0.694746 -0.719085 0.34599 -0.694746 -0.63057 0.345991 -0.694746 -0.63057 0.61492 -0.694746 -0.373097 0.614922 -0.694745 -0.373096 0.719087 -0.694744 -0.0156448 0.719085 -0.694746 -0.0156479 0.630571 -0.694745 0.34599 0.630571 -0.694747 0.345987 0.373097 -0.694747 0.614919 0.373096 -0.694746 0.614921 -0.0217576 0 -0.999763 -0.0217576 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.85494 0 -0.518727 0.85494 0 -0.518727 0.999763 0 -0.0217513 0.999763 0 -0.0217513 0.876699 0 0.481039 0.876699 0 0.481039 0.518727 0 0.85494 0.518727 0 0.85494 0.373098 0.694745 0.61492 0.373095 0.694747 0.61492 0.630569 0.694747 0.345989 0.630572 0.694746 0.345988 0.719085 0.694746 -0.0156448 0.719087 0.694744 -0.0156479 0.614922 0.694744 -0.373098 0.614922 0.694745 -0.373096 0.34599 0.694746 -0.63057 0.345991 0.694746 -0.63057 -0.0156493 0.694746 -0.719085 -0.0156493 0.694746 -0.719085 0.373096 -0.694746 0.614921 0.357363 -0.678375 0.641949 0.492265 -0.706856 0.507966 0.630571 -0.694744 0.345993 0.629508 -0.660378 0.409416 0.673295 -0.70612 0.219245 0.719082 -0.694749 -0.015653 0.764728 -0.64061 0.0693553 0.698948 -0.704871 -0.12095 0.654508 -0.704871 -0.273452 0.632226 -0.67316 -0.383595 0.562798 -0.703124 -0.434598 0.450094 -0.706115 -0.546642 0.354081 -0.676902 -0.645314 -0.0423341 -0.698073 -0.714774 -0.0158661 -0.684209 -0.729114 0.142354 -0.706858 -0.692883 0.295434 -0.700861 -0.64924 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.201248 0 -0.97954 0.201248 0 -0.97954 0.41418 0 -0.910195 0.41418 0 -0.910195 0.635639 0 -0.771987 0.635639 0 -0.771987 0.791483 0 -0.611191 0.791483 0 -0.611191 0.922706 0 -0.385505 0.922706 0 -0.385505 0.985356 0 -0.170512 0.985356 0 -0.170512 0.995913 0 0.0903221 0.995913 0 0.0903221 0.950858 0 0.309628 0.950858 0 0.309628 0.8383 0 0.545209 0.8383 0 0.545209 0.695921 0 0.718118 0.695921 0 0.718118 0.486397 0 0.873738 0.486397 0 0.873738 -0.0156478 0.694746 -0.719085 -0.0434391 0.678373 -0.733432 0.142354 0.706858 -0.692883 0.345991 0.694746 -0.63057 0.311021 0.660378 -0.683496 0.450094 0.706115 -0.546642 0.614921 0.694745 -0.373096 0.607755 0.640608 -0.469314 0.654508 0.704871 -0.273453 0.698948 0.704871 -0.12095 0.739319 0.673163 -0.0160935 0.708158 0.703127 0.0642248 0.673295 0.70612 0.219245 0.645314 0.676901 0.354082 0.348273 0.698073 0.62562 0.378298 0.68421 0.623496 0.492265 0.706856 0.507966 0.597959 0.700859 0.388897 0.348269 -0.698075 0.62562 0.348264 -0.698071 0.625626 0.492307 -0.706858 0.507924 0.592042 -0.689418 0.417359 0.597957 -0.700863 0.388892 0.673286 -0.706117 0.21928 0.719492 -0.684058 0.119982 0.708162 -0.703123 0.0642245 0.698945 -0.704872 -0.120959 0.701929 -0.682243 -0.204549 0.654507 -0.704872 -0.273452 0.532439 -0.698073 -0.478751 0.588271 -0.669021 -0.454256 0.450094 -0.706116 -0.546641 0.271985 -0.698073 -0.662358 -0.0423387 -0.698076 -0.714771 -0.0423329 -0.698073 -0.714774 0.142359 -0.706858 -0.692882 0.302053 -0.684209 -0.663794 0.486384 0 0.873745 0.486384 0 0.873745 0.695982 0 0.71806 0.695982 0 0.71806 0.838303 0 0.545205 0.838303 0 0.545205 0.950842 0 0.309676 0.950842 0 0.309676 0.995913 0 0.0903212 0.995913 0 0.0903212 0.985353 0 -0.170525 0.985353 0 -0.170525 0.922706 0 -0.385505 0.922706 0 -0.385505 0.791492 0 -0.61118 0.791492 0 -0.61118 0.635639 0 -0.771987 0.635639 0 -0.771987 0.414177 0 -0.910196 0.414177 0 -0.910196 0.201256 0 -0.979539 0.201256 0 -0.979539 -0.0591303 0 -0.99825 -0.0591303 0 -0.99825 -0.0423328 0.698075 -0.714772 -0.0423389 0.698072 -0.714775 0.142359 0.706858 -0.692882 0.275152 0.689417 -0.670071 0.295431 0.700861 -0.649241 0.450094 0.706116 -0.546641 0.542405 0.684057 -0.487713 0.562804 0.703124 -0.43459 0.654507 0.704872 -0.273452 0.701929 0.682243 -0.204549 0.698945 0.704872 -0.120959 0.706275 0.698072 0.117777 0.740203 0.669024 0.0671304 0.673286 0.706117 0.21928 0.585227 0.698075 0.412554 0.348262 0.698076 0.625622 0.348271 0.698072 0.625622 0.492306 0.706858 0.507924 0.611362 0.684209 0.397611 -0.0423346 0.698077 -0.71477 -0.0423348 0.698077 -0.71477 0.142361 0.706862 -0.692878 0.288131 0.651638 -0.701676 0.29543 0.700865 -0.649237 0.450096 0.70612 -0.546634 0.583685 0.619566 -0.524833 0.562797 0.703124 -0.434598 0.654507 0.704873 -0.273451 0.762157 0.608101 -0.222104 0.69894 0.704877 -0.120959 0.706269 0.698078 0.117778 0.824141 0.561432 0.074743 0.673281 0.706125 0.219272 0.58522 0.698082 0.412552 0.348269 0.698075 0.625619 0.34827 0.698075 0.625619 0.4923 0.70686 0.507928 0.645924 0.637421 0.420092 0.486393 0 0.87374 0.518723 0.00303677 0.854937 0.695974 0 0.718067 0.8383 0 0.545209 0.876688 0.00507037 0.481033 0.950845 0 0.309668 0.995913 0 0.0903214 0.999745 0.0060904 -0.0217567 0.985353 0 -0.170526 0.922706 0 -0.385504 0.854924 0.00609045 -0.518717 0.791483 0 -0.611191 0.635645 0 -0.771981 0.481034 0.00507053 -0.876688 -0.0591249 0 -0.998251 -0.0217577 0.0030366 -0.999759 0.201259 0 -0.979538 0.414178 0 -0.910196 0.373094 0.69475 0.614918 0.373093 0.69475 0.614918 0.630566 0.694752 0.345987 0.630566 0.694752 0.345987 0.71908 0.694751 -0.0156488 0.719076 0.694755 -0.0156469 0.614915 0.694754 -0.37309 0.614921 0.694744 -0.373099 0.345989 0.694745 -0.630571 0.345989 0.694752 -0.630565 -0.0156488 0.694751 -0.71908 -0.0156508 0.694746 -0.719085 0.518725 0 0.854941 0.518725 0 0.854941 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.854943 0 -0.518723 0.854943 0 -0.518723 0.481038 0 -0.8767 0.481038 0 -0.8767 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 -0.0156471 0.694746 -0.719085 -0.015649 0.694742 -0.719089 0.345991 0.694744 -0.630572 0.351773 0.527884 -0.773042 0.45009 0.706114 -0.546647 0.61492 0.694745 -0.373097 0.722338 0.408779 -0.557788 0.654499 0.70488 -0.27345 0.698939 0.704878 -0.120955 0.823726 0.566705 -0.0179261 0.373097 0.694745 0.61492 0.373092 0.694752 0.614917 0.597954 0.700865 0.388894 0.706617 0.591918 0.387718 0.673285 0.706121 0.219275 0.708156 0.703129 0.0642205 0.518727 0 0.85494 0.486392 -0.00353213 0.873733 0.838296 0.00303644 0.545206 0.817329 0 0.576171 0.950844 0 0.30967 0.986371 0.00406502 0.164489 0.995913 0 0.0903162 0.985354 0 -0.170521 0.960056 0.00457513 -0.279771 0.922705 0 -0.385506 0.791488 0 -0.611185 0.743592 0.00406513 -0.668621 0.635632 0 -0.771992 0.414183 0 -0.910194 0.379858 0.00253714 -0.925041 -0.021757 -0.00303655 -0.999759 -0.0591236 0 -0.998251 0.518725 0 0.854941 0.518725 0 0.854941 0.876696 0 0.481044 0.876696 0 0.481044 0.999763 0 -0.0217646 0.999763 0 -0.0217646 0.854943 0 -0.518722 0.854943 0 -0.518722 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.518723 0 0.854942 0.518723 0 0.854942 0.876701 0 0.481037 0.876701 0 0.481037 0.999763 0 -0.0217559 0.999763 0 -0.0217559 0.854939 0 -0.518728 0.854939 0 -0.518728 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.0217582 0 -0.999763 -0.0217582 0 -0.999763 0.518725 0 0.854941 0.518725 0 0.854941 0.8767 0 0.481037 0.8767 0 0.481037 0.999763 0 -0.0217559 0.999763 0 -0.0217559 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481037 0 -0.8767 0.481037 0 -0.8767 -0.0217559 0 -0.999763 -0.0217559 0 -0.999763 0.486392 0 0.873741 0.486392 0 0.873741 0.817328 0 0.576173 0.817328 0 0.576173 0.986379 0 0.164489 0.986379 0 0.164489 0.960066 0 -0.279774 0.960066 0 -0.279774 0.743599 0 -0.668626 0.743599 0 -0.668626 0.379855 0 -0.925046 0.379855 0 -0.925046 -0.0591222 0 -0.998251 -0.0591222 0 -0.998251 0.518727 0 0.85494 0.518727 0 0.85494 0.876698 0 0.481041 0.876698 0 0.481041 0.999763 0 -0.0217602 0.999763 0 -0.0217602 0.854943 0 -0.518722 0.854943 0 -0.518722 0.481036 0 -0.876701 0.481036 0 -0.876701 -0.0217559 0 -0.999763 -0.0217559 0 -0.999763 0.486396 0 0.873739 0.486396 0 0.873739 0.817329 0 0.576172 0.817329 0 0.576172 0.986379 0 0.16449 0.986379 0 0.16449 0.960066 0 -0.279773 0.960066 0 -0.279773 0.7436 0 -0.668625 0.7436 0 -0.668625 0.379856 0 -0.925046 0.379856 0 -0.925046 -0.0591271 0 -0.99825 -0.0591271 0 -0.99825 0.486394 0 0.87374 0.486394 0 0.87374 0.817327 0 0.576174 0.817327 0 0.576174 0.98638 0 0.164481 0.98638 0 0.164481 0.960066 0 -0.279773 0.960066 0 -0.279773 0.743599 0 -0.668626 0.743599 0 -0.668626 0.379856 0 -0.925046 0.379856 0 -0.925046 -0.0591248 0 -0.998251 -0.0591248 0 -0.998251 0.518725 0 0.854941 0.518725 0 0.854941 0.876696 0 0.481044 0.876696 0 0.481044 0.999763 0 -0.0217646 0.999763 0 -0.0217646 0.854943 0 -0.518722 0.854943 0 -0.518722 0.481039 0 -0.876699 0.481039 0 -0.876699 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.518725 0 0.854941 0.518725 0 0.854941 0.8767 0 0.481037 0.8767 0 0.481037 0.999763 0 -0.0217559 0.999763 0 -0.0217559 0.854941 0 -0.518725 0.854941 0 -0.518725 0.481041 0 -0.876698 0.481041 0 -0.876698 -0.0217602 0 -0.999763 -0.0217602 0 -0.999763 0.518723 0 0.854943 0.518723 0 0.854943 0.876699 0 0.481039 0.876699 0 0.481039 0.999763 0 -0.021758 0.999763 0 -0.021758 0.854942 0 -0.518723 0.854942 0 -0.518723 0.481037 0 -0.876701 0.481037 0 -0.876701 -0.0217559 0 -0.999763 -0.0217559 0 -0.999763 0.348267 0.69808 0.625615 0.348272 0.698075 0.625618 0.585227 0.698074 0.412556 0.585226 0.698074 0.412556 0.706273 0.698074 0.117777 0.706269 0.698078 0.117778 0.687428 0.698078 -0.200324 0.687432 0.698073 -0.200328 0.532436 0.698074 -0.478754 0.532434 0.698078 -0.47875 0.271985 0.698077 -0.662354 0.271985 0.698076 -0.662355 -0.0423347 0.698077 -0.71477 -0.0423351 0.698077 -0.71477 0.37309 0.694753 0.614916 0.373097 0.694745 0.614921 0.630575 0.694743 0.345988 0.630566 0.694752 0.345987 0.71908 0.694751 -0.0156488 0.719076 0.694755 -0.0156469 0.614915 0.694754 -0.37309 0.614921 0.694744 -0.373099 0.345989 0.694745 -0.630571 0.345989 0.694752 -0.630565 -0.0156488 0.694751 -0.71908 -0.0156508 0.694746 -0.719085 -0.0156489 0.694751 -0.71908 -0.0462964 0.621967 -0.781674 0.142358 0.706864 -0.692876 0.345987 0.694752 -0.630566 0.351769 0.527877 -0.773049 0.450092 0.706118 -0.54664 0.61492 0.694746 -0.373097 0.722338 0.408779 -0.557788 0.654499 0.704881 -0.273449 0.698936 0.704882 -0.120958 0.823728 0.566701 -0.0179242 0.708156 0.703129 0.064224 0.67329 0.70612 0.21926 0.706628 0.591903 0.387721 0.348269 0.698077 0.625617 0.399687 0.637417 0.658748 0.492285 0.706857 0.507945 0.597959 0.700859 0.388897 -0.0156508 0.694746 -0.719085 -0.0156488 0.694751 -0.71908 0.345987 0.694752 -0.630566 0.351769 0.527877 -0.773049 0.450094 0.706121 -0.546634 0.614918 0.69475 -0.373093 0.722338 0.408779 -0.557788 0.654501 0.704876 -0.273455 0.698941 0.704877 -0.120954 0.823726 0.566705 -0.0179262 0.37309 0.694754 0.614915 0.373099 0.694744 0.614921 0.597958 0.70086 0.388897 0.706621 0.591911 0.387721 0.673286 0.706121 0.21927 0.708156 0.703129 0.0642211 -0.042335 -0.698072 -0.714775 -0.0423353 -0.698073 -0.714774 0.271987 -0.698072 -0.662358 0.271986 -0.698073 -0.662358 0.532436 -0.698073 -0.478754 0.53244 -0.698069 -0.478755 0.687437 -0.698069 -0.200327 0.687432 -0.698073 -0.200328 0.706274 -0.698073 0.117777 0.706277 -0.69807 0.117779 0.58523 -0.69807 0.412558 0.58523 -0.698069 0.412559 0.348272 -0.69807 0.625623 0.348272 -0.698075 0.625618 -0.0591249 0 -0.998251 -0.0591249 0 -0.998251 0.379855 0 -0.925046 0.379855 0 -0.925046 0.743599 0 -0.668626 0.743599 0 -0.668626 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164487 0.986379 0 0.164487 0.817327 0 0.576175 0.817327 0 0.576175 0.486393 0 0.87374 0.486393 0 0.87374 -0.015649 -0.694742 -0.719089 -0.0156508 -0.694746 -0.719085 0.345988 -0.694748 -0.63057 0.345993 -0.694741 -0.630574 0.614928 -0.694739 -0.373098 0.614917 -0.694749 -0.373096 0.71908 -0.694751 -0.0156488 0.719084 -0.694747 -0.0156471 0.630571 -0.694748 0.345986 0.630576 -0.694739 0.345993 0.373097 -0.694741 0.614927 0.373095 -0.694748 0.614919 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854943 0 -0.518723 0.854943 0 -0.518723 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876702 0 0.481035 0.876702 0 0.481035 0.518722 0 0.854943 0.518722 0 0.854943 0.373096 -0.694746 0.614921 0.380872 -0.621956 0.684183 0.492289 -0.706853 0.507948 0.630577 -0.694739 0.345992 0.711994 -0.527862 0.463062 0.673294 -0.706116 0.219261 0.719084 -0.694747 -0.0156471 0.908909 -0.408767 0.0824306 0.69894 -0.704877 -0.120959 0.654503 -0.704876 -0.273451 0.704408 -0.566697 -0.427393 0.562804 -0.70312 -0.434596 0.450095 -0.706113 -0.546643 0.38772 -0.591907 -0.706625 -0.0423341 -0.698073 -0.714774 -0.0167644 -0.637417 -0.770337 0.142359 -0.70686 -0.692881 0.295431 -0.700863 -0.64924 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.201256 0 -0.979539 0.201256 0 -0.979539 0.414177 0 -0.910196 0.414177 0 -0.910196 0.635639 0 -0.771987 0.635639 0 -0.771987 0.791488 0 -0.611185 0.791488 0 -0.611185 0.922706 0 -0.385505 0.922706 0 -0.385505 0.985353 0 -0.170526 0.985353 0 -0.170526 0.995913 0 0.0903212 0.995913 0 0.0903212 0.950851 0 0.309649 0.950851 0 0.309649 0.8383 0 0.545209 0.8383 0 0.545209 0.695951 0 0.718089 0.695951 0 0.718089 0.486394 0 0.87374 0.486394 0 0.87374 -0.0423343 -0.698069 -0.714778 -0.0423363 -0.698073 -0.714774 0.271984 -0.698074 -0.662357 0.271986 -0.698073 -0.662358 0.532438 -0.698074 -0.478752 0.532437 -0.698074 -0.478752 0.687432 -0.698073 -0.200325 0.687432 -0.698074 -0.200325 0.706274 -0.698073 0.117779 0.706272 -0.698074 0.117778 0.585227 -0.698074 0.412556 0.585226 -0.698077 0.412553 0.348269 -0.698078 0.625616 0.34827 -0.698076 0.625618 -0.0591236 0 -0.998251 -0.021757 -0.00161871 -0.999762 0.379853 0.00135244 -0.925046 0.414177 0 -0.910196 0.635644 0 -0.771983 0.743599 0.0021669 -0.668622 0.791488 0 -0.611185 0.922703 0 -0.385511 0.960063 0.00243898 -0.279773 0.985354 0 -0.170519 0.995913 0 0.0903171 0.986376 0.00216692 0.16449 0.950846 0 0.309664 0.817327 0 0.576174 0.838299 0.00161881 0.545208 0.486394 -0.00188264 0.873737 0.518723 0 0.854943 -0.783461 0 0.621441 -0.783461 0 0.621441 -0.657952 0 0.75306 -0.657952 0 0.75306 -0.510681 0 0.85977 -0.510681 0 0.85977 -0.346519 0 0.938043 -0.346519 0 0.938043 -0.170896 0 0.985289 -0.170896 0 0.985289 0.0103802 0 0.999946 0.0103802 0 0.999946 0.191313 0 0.981529 0.191313 0 0.981529 0.3581 0 0.933683 0.3581 0 0.933683 0.506896 0 0.862008 0.506896 0 0.862008 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856072 0 0.516857 0.856072 0 0.516857 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210887 0.977511 0 0.210887 0.998889 0 0.0471174 0.998889 0 0.0471174 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900922 0 -0.43398 0.900922 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444399 0 -0.895829 0.444399 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129444 0 -0.991587 0.129444 0 -0.991587 -0.0355307 0 -0.999369 -0.0355307 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506896 0 0.862007 0.506896 0 0.862007 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856072 0 0.516857 0.856072 0 0.516857 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210887 0.977511 0 0.210887 0.998889 0 0.0471174 0.998889 0 0.0471174 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900922 0 -0.43398 0.900922 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444399 0 -0.895829 0.444399 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129444 0 -0.991587 0.129444 0 -0.991587 -0.0355307 0 -0.999369 -0.0355307 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506896 0 0.862007 0.506896 0 0.862007 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856072 0 0.516857 0.856072 0 0.516857 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210887 0.977511 0 0.210887 0.998889 0 0.0471174 0.998889 0 0.0471174 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900922 0 -0.43398 0.900922 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444399 0 -0.895829 0.444399 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129444 0 -0.991587 0.129444 0 -0.991587 -0.0355307 0 -0.999369 -0.0355307 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506896 0 0.862007 0.506896 0 0.862007 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856072 0 0.516857 0.856072 0 0.516857 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210887 0.977511 0 0.210887 0.998889 0 0.0471174 0.998889 0 0.0471174 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900922 0 -0.43398 0.900922 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444399 0 -0.895829 0.444399 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129444 0 -0.991587 0.129444 0 -0.991587 -0.0355307 0 -0.999369 -0.0355307 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506896 0 0.862007 0.506896 0 0.862007 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856072 0 0.516857 0.856072 0 0.516857 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210887 0.977511 0 0.210887 0.998889 0 0.0471174 0.998889 0 0.0471174 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900922 0 -0.43398 0.900922 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444399 0 -0.895829 0.444399 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129444 0 -0.991587 0.129444 0 -0.991587 -0.0355307 0 -0.999369 -0.0355307 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506896 0 0.862007 0.506896 0 0.862007 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856072 0 0.516857 0.856072 0 0.516857 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210887 0.977511 0 0.210887 0.998889 0 0.0471174 0.998889 0 0.0471174 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900922 0 -0.43398 0.900922 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444399 0 -0.895829 0.444399 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129444 0 -0.991587 0.129444 0 -0.991587 -0.0355307 0 -0.999369 -0.0355307 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506896 0 0.862007 0.506896 0 0.862007 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856072 0 0.516857 0.856072 0 0.516857 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210887 0.977511 0 0.210887 0.998889 0 0.0471174 0.998889 0 0.0471174 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900922 0 -0.43398 0.900922 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444399 0 -0.895829 0.444399 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129444 0 -0.991587 0.129444 0 -0.991587 -0.0355307 0 -0.999369 -0.0355307 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506896 0 0.862007 0.506896 0 0.862007 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856072 0 0.516857 0.856072 0 0.516857 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210887 0.977511 0 0.210887 0.998889 0 0.0471174 0.998889 0 0.0471174 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900922 0 -0.43398 0.900922 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444399 0 -0.895829 0.444399 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129444 0 -0.991587 0.129444 0 -0.991587 -0.0355307 0 -0.999369 -0.0355307 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506896 0 0.862007 0.506896 0 0.862007 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856071 0 0.516857 0.856071 0 0.516857 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210887 0.977511 0 0.210887 0.998889 0 0.0471174 0.998889 0 0.0471174 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900922 0 -0.43398 0.900922 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444399 0 -0.895829 0.444399 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129444 0 -0.991587 0.129444 0 -0.991587 -0.0355307 0 -0.999369 -0.0355307 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.3581 0 0.933683 0.3581 0 0.933683 0.506896 0 0.862008 0.506896 0 0.862008 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856072 0 0.516857 0.856072 0 0.516857 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210887 0.977511 0 0.210887 0.998889 0 0.0471174 0.998889 0 0.0471174 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900922 0 -0.43398 0.900922 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444399 0 -0.895829 0.444399 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129444 0 -0.991587 0.129444 0 -0.991587 -0.0355307 0 -0.999369 -0.0355307 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 0.25365 0.70589 0.661348 0.253648 0.705897 0.661342 0.359042 0.705897 0.610573 0.359045 0.70589 0.610578 0.454644 0.705892 0.543152 0.45464 0.705899 0.543148 0.537839 0.705898 0.460909 0.537839 0.705899 0.460908 0.606366 0.705899 0.366097 0.606372 0.705892 0.3661 0.658359 0.705893 0.261302 0.658352 0.7059 0.261299 0.692382 0.7059 0.149373 0.692382 0.7059 0.149373 0.707524 0.705901 0.0333738 0.707536 0.705889 0.0333746 0.703379 0.705889 -0.0835371 0.703368 0.7059 -0.0835361 0.680026 0.7059 -0.198167 0.680022 0.705904 -0.198166 0.638131 0.705903 -0.307392 0.638143 0.70589 -0.307397 0.578843 0.70589 -0.40824 0.578842 0.705892 -0.408238 0.503753 0.705892 -0.497945 0.503755 0.705889 -0.497947 0.414927 0.705887 -0.574073 0.414926 0.705888 -0.574072 0.314779 0.705886 -0.634538 0.31477 0.705905 -0.634522 0.206038 0.705906 -0.677676 0.20604 0.705899 -0.677683 0.0916869 0.705899 -0.702354 0.0916888 0.705887 -0.702365 -0.0251672 0.705887 -0.707877 -0.0251672 0.705894 -0.70787 -0.141335 0.705894 -0.694073 -0.141334 0.705902 -0.694065 -0.0591248 0 -0.998251 -0.0591248 0 -0.998251 0.379853 0 -0.925047 0.379853 0 -0.925047 0.743599 0 -0.668626 0.743599 0 -0.668626 0.960066 0 -0.279773 0.960066 0 -0.279773 0.986379 0 0.164491 0.986379 0 0.164491 0.817326 0 0.576175 0.817326 0 0.576175 0.486394 0 0.87374 0.486394 0 0.87374 -0.0217582 0 -0.999763 -0.0217582 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854939 0 -0.518728 0.854939 0 -0.518728 0.999763 0 -0.0217559 0.999763 0 -0.0217559 0.876701 0 0.481037 0.876701 0 0.481037 0.518723 0 0.854942 0.518723 0 0.854942 -0.0591223 0 -0.998251 -0.0591223 0 -0.998251 0.379854 0 -0.925046 0.379854 0 -0.925046 0.7436 0 -0.668624 0.7436 0 -0.668624 0.960065 0 -0.279777 0.960065 0 -0.279777 0.986379 0 0.164491 0.986379 0 0.164491 0.817326 0 0.576175 0.817326 0 0.576175 0.486396 0 0.873739 0.486396 0 0.873739 -0.0217558 0 -0.999763 -0.0217558 0 -0.999763 0.481037 0 -0.8767 0.481037 0 -0.8767 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217558 0.999763 0 -0.0217558 0.876699 0 0.481039 0.876699 0 0.481039 0.518723 0 0.854943 0.518723 0 0.854943 -0.059122 0 -0.998251 -0.059122 0 -0.998251 0.379856 0 -0.925046 0.379856 0 -0.925046 0.743598 0 -0.668627 0.743598 0 -0.668627 0.960066 0 -0.279772 0.960066 0 -0.279772 0.986379 0 0.164491 0.986379 0 0.164491 0.817329 0 0.576172 0.817329 0 0.576172 0.486396 0 0.873739 0.486396 0 0.873739 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854943 0 -0.518722 0.854943 0 -0.518722 0.999763 0 -0.0217646 0.999763 0 -0.0217646 0.876696 0 0.481044 0.876696 0 0.481044 0.518725 0 0.854941 0.518725 0 0.854941 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854943 0 -0.518723 0.854943 0 -0.518723 0.999763 0 -0.0217558 0.999763 0 -0.0217558 0.8767 0 0.481037 0.8767 0 0.481037 0.518725 0 0.854941 0.518725 0 0.854941 -0.0217602 0 -0.999763 -0.0217602 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854943 0 -0.518722 0.854943 0 -0.518722 0.999763 0 -0.0217602 0.999763 0 -0.0217602 0.876698 0 0.481041 0.876698 0 0.481041 0.518727 0 0.85494 0.518727 0 0.85494 -0.0217559 0 -0.999763 -0.0217559 0 -0.999763 0.481037 0 -0.876701 0.481037 0 -0.876701 0.854942 0 -0.518723 0.854942 0 -0.518723 0.999763 0 -0.021758 0.999763 0 -0.021758 0.876699 0 0.481039 0.876699 0 0.481039 0.518723 0 0.854943 0.518723 0 0.854943 -0.0591274 0 -0.99825 -0.0217599 -0.00572012 -0.999747 0.37985 0.00477919 -0.925036 0.414178 0 -0.910196 0.635647 0 -0.77198 0.743581 0.0076569 -0.668602 0.791488 0 -0.611184 0.922703 0 -0.385512 0.960029 0.00861819 -0.279768 0.985353 0 -0.170525 0.995913 0 0.090322 0.98635 0.00765675 0.164485 0.950848 0 0.309658 0.817326 0 0.576175 0.838286 0.00572038 0.545201 0.486385 -0.00665299 0.873719 0.518725 0 0.854941 -0.130651 -0.705398 -0.696667 -0.130651 -0.705398 -0.696666 0.00777238 -0.705398 -0.708768 0.00777229 -0.705394 -0.708772 0.145898 -0.705394 -0.693637 0.145897 -0.705397 -0.693635 0.278415 -0.705397 -0.651844 0.278413 -0.705402 -0.651839 0.400231 -0.705402 -0.584999 0.400231 -0.705401 -0.584999 0.506669 -0.705401 -0.495677 0.506675 -0.705392 -0.495683 0.593642 -0.705393 -0.387311 0.593634 -0.705403 -0.387305 0.657787 -0.705403 -0.264052 0.657791 -0.705399 -0.264053 0.696666 -0.705398 -0.130651 0.696659 -0.705405 -0.13065 0.708762 -0.705405 0.00777231 0.708766 -0.705401 0.00777222 0.693631 -0.705401 0.145896 0.693635 -0.705396 0.145897 0.651844 -0.705397 0.278415 0.651845 -0.705396 0.278416 0.585003 -0.705396 0.400234 0.585003 -0.705397 0.400234 0.495681 -0.705397 0.506672 0.495676 -0.705403 0.506668 0.387306 -0.705402 0.593634 0.38731 -0.705396 0.593639 0.264054 -0.705395 0.657794 0.264054 -0.705397 0.657792 0.454642 -0.705896 0.543149 -0.141335 -0.705898 -0.69407 0.149433 -0.707109 -0.691134 0.0916872 -0.705899 -0.702354 0.0916873 -0.705896 -0.702356 0.0207681 -0.707051 -0.706858 -0.0294817 -0.558131 -0.829229 -0.0377113 -0.706363 -0.706844 -0.141335 -0.705898 -0.694069 0.260512 -0.707109 -0.657366 0.232683 -0.704459 -0.67052 0.258347 -0.459591 -0.849725 0.208372 -0.623996 -0.753133 0.162097 -0.706205 -0.689201 0.283576 -0.706896 -0.647984 0.392846 -0.467496 -0.791909 0.377441 -0.554116 -0.741952 0.461691 -0.707104 -0.53558 0.414922 -0.705894 -0.574067 0.414923 -0.705894 -0.574067 0.355456 -0.707056 -0.611329 0.36038 -0.662734 -0.656438 0.536576 -0.686582 -0.490603 0.631411 -0.460197 -0.624131 0.572962 -0.57552 -0.583516 0.479046 -0.699964 -0.529685 0.600931 -0.707007 -0.372857 0.683326 -0.557271 -0.471715 0.721352 -0.469924 -0.508746 0.557413 -0.706903 -0.435405 0.539936 -0.707101 -0.456593 0.632599 -0.706331 -0.317671 0.741466 -0.568031 -0.357169 0.655997 -0.707059 -0.264075 0.680029 -0.705896 -0.198168 0.68003 -0.705896 -0.198168 0.695165 -0.707059 -0.129669 0.817262 -0.568034 -0.0970624 0.704224 -0.706328 -0.0718949 0.707469 -0.706681 0.00943152 0.881724 -0.469929 0.0415907 0.704052 -0.706905 0.0677993 0.688595 -0.699969 0.189419 0.796733 -0.57552 0.18437 0.867847 -0.460204 0.187228 0.716129 -0.686584 0.12555 0.700692 -0.707102 0.0950597 0.677124 -0.707109 0.203714 0.658353 -0.7059 0.261299 0.658355 -0.705898 0.2613 0.596662 -0.706513 0.380571 0.735631 -0.511455 0.444141 0.656605 -0.662731 0.360079 0.628215 -0.70706 0.324672 0.506128 -0.707049 0.493878 0.580338 -0.623996 0.523294 0.674378 -0.459592 0.577918 0.556463 -0.704458 0.440555 0.572879 -0.707109 0.414495 0.400271 -0.69323 0.599345 0.4032 -0.707098 0.580897 0.454641 -0.705898 0.543148 0.413494 -0.619844 0.666946 0.450384 -0.458849 0.765906 0.333076 -0.706806 0.624088 0.253647 -0.705898 0.661341 0.253647 -0.705898 0.66134 -0.0156493 -0.69475 -0.719082 -0.0156492 -0.694749 -0.719082 0.345988 -0.69475 -0.630566 0.345988 -0.694751 -0.630566 0.614915 -0.694752 -0.373093 0.614921 -0.694747 -0.373094 0.719085 -0.694746 -0.0156489 0.71908 -0.694751 -0.0156507 0.630566 -0.694751 0.345988 0.630565 -0.694752 0.345986 0.373093 -0.694751 0.614917 0.373093 -0.694749 0.614919 -0.0591249 0 -0.998251 -0.0217572 0.0071725 -0.999738 0.201251 0 -0.97954 0.414178 0 -0.910196 0.481005 0.0119762 -0.876636 0.635646 0 -0.771981 0.791488 0 -0.611185 0.854852 0.0143838 -0.518673 0.922701 0 -0.385516 0.985355 0 -0.170513 0.99966 0.0143834 -0.0217548 0.995914 0 0.0903114 0.950845 0 0.309667 0.876636 0.0119759 0.481005 0.8383 0 0.545209 0.695954 0 0.718087 0.518712 0.00717224 0.854919 0.486396 0 0.873738 -0.0423347 0.698074 -0.714773 -0.0423349 0.698074 -0.714773 0.142355 0.706861 -0.692879 0.296453 0.625237 -0.721938 0.295433 0.700859 -0.649242 0.450101 0.706112 -0.54664 0.610185 0.571525 -0.548665 0.562794 0.703133 -0.434588 0.654494 0.704883 -0.273455 0.800719 0.551728 -0.233337 0.698939 0.704879 -0.12095 0.706267 0.69808 0.11778 0.876379 0.47502 0.0794718 0.673295 0.70611 0.219276 0.585234 0.698069 0.412555 0.348272 0.698074 0.625619 0.348268 0.698079 0.625616 0.492281 0.706867 0.507936 0.668089 0.604037 0.434508 0.373094 -0.694746 0.614922 0.380869 -0.621968 0.684174 0.492281 -0.706863 0.50794 0.630566 -0.694752 0.345986 0.711984 -0.52788 0.463056 0.673286 -0.706119 0.219273 0.71908 -0.694751 -0.0156507 0.9089 -0.408787 0.0824207 0.698946 -0.704872 -0.120951 0.654504 -0.704872 -0.27346 0.704404 -0.566706 -0.427387 0.562798 -0.703129 -0.43459 0.450096 -0.70612 -0.546634 0.38772 -0.59191 -0.706623 -0.0423351 -0.698075 -0.714772 -0.0167653 -0.637418 -0.770336 0.14236 -0.706864 -0.692876 0.295429 -0.700867 -0.649236 -0.0591253 0 -0.998251 -0.0591253 0 -0.998251 0.201258 0 -0.979538 0.201258 0 -0.979538 0.414177 0 -0.910196 0.414177 0 -0.910196 0.635646 0 -0.771981 0.635646 0 -0.771981 0.791489 0 -0.611184 0.791489 0 -0.611184 0.922701 0 -0.385517 0.922701 0 -0.385517 0.985355 0 -0.170513 0.985355 0 -0.170513 0.995914 0 0.0903113 0.995914 0 0.0903113 0.950845 0 0.309667 0.950845 0 0.309667 0.8383 0 0.545209 0.8383 0 0.545209 0.695951 0 0.718089 0.695951 0 0.718089 0.486397 0 0.873738 0.486397 0 0.873738 -0.0156495 0.694746 -0.719085 -0.0481271 0.580885 -0.812562 0.14236 0.706862 -0.692878 0.345988 0.69475 -0.630567 0.376227 0.418159 -0.826799 0.450096 0.706119 -0.546635 0.562799 0.703128 -0.434591 0.749509 0.481078 -0.454753 0.654509 0.704866 -0.273463 0.698953 0.704866 -0.120952 0.876469 0.481079 -0.0190771 0.708159 0.703126 0.0642172 0.673287 0.706119 0.219273 0.745574 0.526084 0.409092 0.348273 0.698072 0.62562 0.413402 0.604035 0.681352 0.492284 0.70686 0.507943 0.597956 0.700863 0.388895 -0.0156488 -0.694746 -0.719085 -0.0156507 -0.694751 -0.71908 0.345988 -0.694752 -0.630565 0.345989 -0.69475 -0.630566 0.614915 -0.694752 -0.373094 0.614922 -0.694746 -0.373095 0.719085 -0.694746 -0.0156489 0.719081 -0.694751 -0.0156507 0.630566 -0.694752 0.345987 0.630566 -0.694752 0.345987 0.373094 -0.69475 0.614918 0.373094 -0.69475 0.614918 -0.0591236 0 -0.998251 -0.0217565 0.0071724 -0.999738 0.201248 0 -0.97954 0.41418 0 -0.910195 0.481006 0.0119759 -0.876636 0.635643 0 -0.771984 0.791488 0 -0.611185 0.854851 0.0143837 -0.518673 0.922701 0 -0.385517 0.985356 0 -0.170512 0.99966 0.0143834 -0.0217548 0.995914 0 0.0903117 0.950845 0 0.309667 0.876636 0.0119759 0.481004 0.8383 0 0.545209 0.695951 0 0.718089 0.518712 0.0071721 0.854919 0.486397 0 0.873738 -0.0423348 0.698073 -0.714774 -0.0423339 0.698075 -0.714772 0.142353 0.706863 -0.692879 0.296454 0.625237 -0.721938 0.295434 0.70086 -0.649241 0.450098 0.706113 -0.546641 0.610186 0.571522 -0.548667 0.562794 0.703133 -0.434588 0.654494 0.704883 -0.273456 0.800719 0.551727 -0.233337 0.698938 0.70488 -0.120949 0.706268 0.698079 0.11778 0.876379 0.47502 0.0794721 0.673296 0.70611 0.219276 0.585235 0.698068 0.412555 0.348273 0.698072 0.62562 0.348267 0.698081 0.625615 0.492278 0.706868 0.507937 0.668089 0.604037 0.434508 -0.0156489 -0.694746 -0.719085 -0.0156507 -0.694751 -0.71908 0.345989 -0.694749 -0.630567 0.345985 -0.694754 -0.630564 0.614914 -0.694754 -0.373092 0.614919 -0.69475 -0.373092 0.71908 -0.694751 -0.0156487 0.71908 -0.694751 -0.0156489 0.63057 -0.694748 0.345988 0.630568 -0.69475 0.345986 0.373091 -0.694751 0.614918 0.37309 -0.694756 0.614913 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.021757 0.999763 0 -0.021757 0.8767 0 0.481038 0.8767 0 0.481038 0.518722 0 0.854943 0.518722 0 0.854943 0.37309 0.694752 0.614918 0.373093 0.694748 0.61492 0.630571 0.694746 0.345989 0.630574 0.694743 0.34599 0.719082 0.694749 -0.0156488 0.719085 0.694746 -0.0156496 0.614921 0.694745 -0.373096 0.614917 0.694752 -0.373091 0.345988 0.694752 -0.630565 0.345989 0.694746 -0.63057 -0.0156488 0.694749 -0.719082 -0.0156516 0.69474 -0.719091 -0.0156493 -0.694747 -0.719084 -0.0156492 -0.694747 -0.719084 0.345989 -0.694748 -0.630569 0.345989 -0.694749 -0.630568 0.614918 -0.69475 -0.373093 0.614916 -0.694752 -0.373093 0.719078 -0.694753 -0.0156494 0.719082 -0.694749 -0.0156485 0.630569 -0.694748 0.345988 0.630576 -0.694738 0.345995 0.373096 -0.694742 0.614925 0.373095 -0.694746 0.614921 0.373096 -0.694745 0.614921 0.373094 -0.694752 0.614915 0.613884 -0.698178 0.368366 0.550511 -0.778264 0.302064 -0.0156496 -0.694746 -0.719085 -0.0156486 -0.694742 -0.719089 0.34599 -0.694744 -0.630573 0.345989 -0.694745 -0.630572 0.614926 -0.69474 -0.373099 0.614926 -0.694739 -0.373099 0.719091 -0.694739 -0.0156497 0.719083 -0.694748 -0.0156517 0.680078 -0.706845 0.194585 -0.0156494 -0.694753 -0.719078 -0.0156485 -0.694749 -0.719082 0.345989 -0.694746 -0.63057 0.345986 -0.694752 -0.630567 0.614916 -0.694752 -0.373093 0.614922 -0.694746 -0.373095 0.719085 -0.694746 -0.0156495 0.719083 -0.694748 -0.01565 0.630567 -0.694749 0.345989 0.630565 -0.694752 0.345987 0.373093 -0.694752 0.614916 0.373096 -0.69474 0.614927 -0.0156494 -0.694746 -0.719085 -0.0156494 -0.694746 -0.719085 0.345991 -0.694744 -0.630572 0.345993 -0.694742 -0.630573 0.614928 -0.694739 -0.373097 0.614915 -0.69475 -0.373096 0.719079 -0.694752 -0.0156489 0.719078 -0.694753 -0.0156495 0.630566 -0.694752 0.345986 0.63057 -0.694744 0.345993 0.373096 -0.694745 0.614922 0.373096 -0.694748 0.614919 -0.0217578 0 -0.999763 -0.0217578 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854943 0 -0.518721 0.854943 0 -0.518721 0.999763 0 -0.0217573 0.999763 0 -0.0217573 0.8767 0 0.481038 0.8767 0 0.481038 0.518725 0 0.854941 0.518725 0 0.854941 0.373092 0.694753 0.614915 0.373097 0.694747 0.614919 0.630572 0.694744 0.34599 0.630558 0.694758 0.345987 0.719071 0.69476 -0.0156487 0.719076 0.694756 -0.0156504 0.614915 0.694755 -0.373089 0.614927 0.694737 -0.373103 0.345992 0.694742 -0.630574 0.345991 0.694746 -0.63057 -0.0156493 0.694749 -0.719082 -0.0156491 0.69475 -0.719081 -0.0156491 -0.694746 -0.719085 -0.0156495 -0.694747 -0.719084 0.345987 -0.694751 -0.630567 0.345992 -0.694746 -0.63057 0.614918 -0.694748 -0.373097 0.614926 -0.694741 -0.373097 0.71909 -0.694741 -0.0156491 0.719089 -0.694742 -0.0156497 0.630575 -0.694741 0.345992 0.630574 -0.694743 0.34599 0.373097 -0.694743 0.614924 0.373097 -0.694742 0.614924 -0.0217574 0 -0.999763 -0.0217574 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854939 0 -0.518728 0.854939 0 -0.518728 0.999763 0 -0.0217572 0.999763 0 -0.0217572 0.8767 0 0.481038 0.8767 0 0.481038 0.518725 0 0.854941 0.518725 0 0.854941 0.373098 0.694741 0.614925 0.373098 0.694741 0.614925 0.630575 0.694741 0.345991 0.630577 0.694739 0.345992 0.719089 0.694742 -0.0156491 0.719094 0.694737 -0.0156508 0.614927 0.694737 -0.373102 0.614919 0.694749 -0.373093 0.345989 0.694746 -0.630571 0.345988 0.694756 -0.630561 -0.015649 0.694751 -0.719081 -0.0156505 0.694746 -0.719084 -0.0156489 -0.694752 -0.719079 -0.0156495 -0.694753 -0.719078 0.345986 -0.694753 -0.630565 0.345993 -0.694746 -0.630569 0.61492 -0.694748 -0.373095 0.614919 -0.694748 -0.373095 0.719085 -0.694746 -0.0156491 0.719084 -0.694747 -0.0156495 0.630568 -0.694751 0.345984 0.630574 -0.694741 0.345994 0.373097 -0.694738 0.614929 0.373097 -0.694741 0.614926 -0.0217573 0 -0.999763 -0.0217573 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217574 0.999763 0 -0.0217574 0.876702 0 0.481034 0.876702 0 0.481034 0.518722 0 0.854943 0.518722 0 0.854943 0.373089 0.694754 0.614916 0.373101 0.694739 0.614926 0.630574 0.694745 0.345987 0.630562 0.694756 0.345985 0.719081 0.694751 -0.015649 0.719076 0.694755 -0.0156473 0.614911 0.694758 -0.373089 0.61491 0.694759 -0.373089 0.345982 0.694762 -0.630557 0.345982 0.69476 -0.630559 -0.0156488 0.69476 -0.719071 -0.0156504 0.694756 -0.719076 -0.0217577 0 -0.999763 -0.0217577 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.021758 0.999763 0 -0.021758 0.8767 0 0.481038 0.8767 0 0.481038 0.518723 0 0.854942 0.518723 0 0.854942 -0.0217581 0 -0.999763 -0.0217581 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.021758 0.999763 0 -0.021758 0.876698 0 0.481042 0.876698 0 0.481042 0.518727 0 0.85494 0.518727 0 0.85494 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.021758 0.999763 0 -0.021758 0.876699 0 0.48104 0.876699 0 0.48104 0.518725 0 0.854941 0.518725 0 0.854941 -0.0156488 -0.694751 -0.71908 -0.0156489 -0.694751 -0.71908 0.345986 -0.694752 -0.630566 0.345988 -0.69475 -0.630567 0.614922 -0.694746 -0.373094 0.614922 -0.694746 -0.373094 0.719085 -0.694746 -0.0156489 0.71908 -0.694751 -0.0156507 0.630567 -0.69475 0.345988 0.630566 -0.694752 0.345986 0.373094 -0.69475 0.614918 0.373094 -0.694746 0.614922 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854942 0 -0.518723 0.854942 0 -0.518723 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 0.373096 0.694745 0.614921 0.373096 0.694746 0.614921 0.630568 0.694749 0.345989 0.63057 0.694746 0.345989 0.719082 0.694749 -0.0156488 0.719078 0.694753 -0.0156476 0.614917 0.694752 -0.373091 0.614925 0.69474 -0.3731 0.345989 0.694745 -0.630572 0.345988 0.69475 -0.630567 -0.0156489 0.694749 -0.719082 -0.0156496 0.694746 -0.719085 -0.0156489 -0.694746 -0.719085 -0.0156507 -0.694751 -0.71908 0.345989 -0.694749 -0.630567 0.345992 -0.694746 -0.630569 0.614918 -0.694749 -0.373094 0.614918 -0.69475 -0.373094 0.71908 -0.694751 -0.0156487 0.71908 -0.694751 -0.0156488 0.630566 -0.694752 0.345986 0.630567 -0.69475 0.345988 0.373093 -0.694752 0.614916 0.373094 -0.694748 0.61492 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.48104 0 -0.876699 0.48104 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.021757 0.999763 0 -0.021757 0.8767 0 0.481038 0.8767 0 0.481038 0.518726 0 0.854941 0.518726 0 0.854941 0.3731 0.694739 0.614926 0.373093 0.694748 0.61492 0.630571 0.694746 0.345989 0.630567 0.69475 0.345988 0.719082 0.694749 -0.0156488 0.719085 0.694746 -0.0156495 0.614921 0.694745 -0.373096 0.614917 0.694752 -0.373091 0.345988 0.694752 -0.630565 0.345989 0.694746 -0.63057 -0.0156488 0.694749 -0.719082 -0.0156516 0.69474 -0.719091 -0.0423341 -0.698073 -0.714774 -0.042336 -0.698077 -0.71477 0.271983 -0.698079 -0.662353 0.271991 -0.69807 -0.662359 0.532439 -0.698072 -0.478753 0.532432 -0.698078 -0.478751 0.687428 -0.698078 -0.200324 0.687428 -0.698078 -0.200324 0.70627 -0.698077 0.117776 0.706272 -0.698074 0.117778 0.585227 -0.698075 0.412555 0.585226 -0.698076 0.412553 0.348271 -0.698075 0.625619 0.348271 -0.698073 0.625621 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379853 0 -0.925047 0.379853 0 -0.925047 0.743601 0 -0.668624 0.743601 0 -0.668624 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164487 0.986379 0 0.164487 0.817328 0 0.576173 0.817328 0 0.576173 0.486395 0 0.873739 0.486395 0 0.873739 0.348275 0.698067 0.625626 0.348267 0.698077 0.625618 0.585224 0.698078 0.412553 0.585225 0.698077 0.412553 0.706272 0.698075 0.117777 0.706273 0.698074 0.117777 0.687433 0.698073 -0.200325 0.687431 0.698075 -0.200324 0.532439 0.698072 -0.478753 0.532442 0.698065 -0.478759 0.271989 0.698062 -0.662368 0.271988 0.698075 -0.662354 -0.0423339 0.698076 -0.714771 -0.0423375 0.698067 -0.71478 -0.0156489 -0.694746 -0.719085 -0.0156507 -0.694751 -0.71908 0.345988 -0.694751 -0.630566 0.345993 -0.694745 -0.63057 0.614921 -0.694746 -0.373095 0.614918 -0.694748 -0.373095 0.719082 -0.69475 -0.0156493 0.719081 -0.69475 -0.0156493 0.630566 -0.694751 0.345988 0.630566 -0.694751 0.345988 0.373094 -0.694752 0.614915 0.373094 -0.694747 0.614921 -0.0591236 0 -0.998251 -0.0217565 0.00717239 -0.999738 0.201253 0 -0.979539 0.414177 0 -0.910196 0.481005 0.0119763 -0.876636 0.635644 0 -0.771982 0.791487 0 -0.611186 0.854853 0.0143841 -0.518671 0.922704 0 -0.38551 0.985354 0 -0.170521 0.99966 0.0143842 -0.0217555 0.995913 0 0.0903169 0.950845 0 0.309667 0.876636 0.0119758 0.481005 0.8383 0 0.54521 0.695969 0 0.718072 0.518713 0.00717284 0.854918 0.486395 0 0.873739 -0.0423374 0.698067 -0.71478 -0.0423339 0.698076 -0.714771 0.142357 0.706861 -0.692879 0.296451 0.62524 -0.721937 0.295431 0.700863 -0.64924 0.450097 0.706117 -0.546637 0.61019 0.571523 -0.548662 0.562803 0.703121 -0.434596 0.654506 0.704872 -0.273455 0.800719 0.551726 -0.233339 0.698944 0.704873 -0.120956 0.706272 0.698074 0.117778 0.876365 0.475045 0.0794754 0.673288 0.706118 0.219273 0.585226 0.698077 0.412553 0.348274 0.698067 0.625625 0.348268 0.698076 0.625619 0.492295 0.706862 0.507929 0.668088 0.604038 0.434508 -0.0156496 -0.694746 -0.719085 -0.0156501 -0.694748 -0.719083 0.345987 -0.69475 -0.630568 0.345991 -0.694745 -0.630571 0.614926 -0.69474 -0.373099 0.614926 -0.694739 -0.373099 0.719092 -0.694739 -0.0156463 0.719082 -0.694749 -0.0156484 0.630568 -0.69475 0.345988 0.630566 -0.694752 0.345986 0.373093 -0.694752 0.614916 0.373093 -0.694751 0.614917 -0.0423352 -0.698067 -0.71478 -0.0423371 -0.698075 -0.714772 0.271985 -0.698076 -0.662355 0.271986 -0.698075 -0.662356 0.532438 -0.698074 -0.478751 0.532436 -0.698076 -0.47875 0.687433 -0.698072 -0.200325 0.687433 -0.698073 -0.200325 0.706273 -0.698074 0.117778 0.706274 -0.698073 0.117779 0.585231 -0.698069 0.412558 0.585225 -0.698078 0.412551 0.348271 -0.698078 0.625616 0.348273 -0.698067 0.625627 0.373093 -0.694752 0.614916 0.373093 -0.69475 0.614918 0.630568 -0.694749 0.345989 0.787831 -0.341732 0.512389 0.67329 -0.706117 0.21927 0.70816 -0.703125 0.0642214 0.906442 -0.42187 -0.0197268 0.698944 -0.704873 -0.120957 0.654506 -0.704873 -0.273452 0.775143 -0.421859 -0.470307 -0.0156497 -0.694739 -0.719091 -0.0156517 -0.694748 -0.719083 0.295431 -0.700864 -0.649238 0.421652 -0.481327 -0.768462 0.450098 -0.706109 -0.546646 0.562804 -0.703119 -0.434597 -0.015649 -0.694746 -0.719085 -0.0156496 -0.694747 -0.719084 0.345989 -0.694746 -0.630571 0.345989 -0.694746 -0.630571 0.614918 -0.694748 -0.373097 0.614926 -0.694741 -0.373097 0.71909 -0.694741 -0.0156491 0.719089 -0.694742 -0.0156497 0.630575 -0.694741 0.345992 0.630574 -0.694743 0.34599 0.373094 -0.694742 0.614926 0.373094 -0.694748 0.614919 -0.0217572 0 -0.999763 -0.0217572 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854939 0 -0.518728 0.854939 0 -0.518728 0.999763 0 -0.0217572 0.999763 0 -0.0217572 0.8767 0 0.481038 0.8767 0 0.481038 0.518721 0 0.854944 0.518721 0 0.854944 0.37309 0.694751 0.614919 0.373098 0.694741 0.614925 0.630575 0.694741 0.345991 0.630577 0.694739 0.345992 0.719089 0.694742 -0.0156491 0.719094 0.694737 -0.0156508 0.614927 0.694737 -0.373102 0.614919 0.694749 -0.373093 0.345989 0.694746 -0.630571 0.345989 0.694747 -0.630569 -0.0156489 0.694751 -0.71908 -0.0156507 0.694746 -0.719085 -0.0423347 -0.698068 -0.714779 -0.0423351 -0.698069 -0.714778 0.271987 -0.69807 -0.662361 0.271984 -0.698072 -0.662359 0.53244 -0.698072 -0.478753 0.532438 -0.698073 -0.478752 0.687435 -0.69807 -0.200327 0.687435 -0.698071 -0.200327 0.706276 -0.69807 0.117781 0.706272 -0.698074 0.117778 0.585228 -0.698075 0.412551 0.585231 -0.69807 0.412558 0.348272 -0.698071 0.625623 0.348272 -0.698068 0.625626 -0.0591241 0 -0.998251 -0.0591241 0 -0.998251 0.379854 0 -0.925047 0.379854 0 -0.925047 0.743602 0 -0.668623 0.743602 0 -0.668623 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986378 0 0.164492 0.986378 0 0.164492 0.81733 0 0.57617 0.81733 0 0.57617 0.486394 0 0.873739 0.486394 0 0.873739 0.348275 0.698065 0.625628 0.348275 0.698065 0.625628 0.585235 0.698066 0.412556 0.585222 0.69808 0.412553 0.706271 0.698076 0.11778 0.706271 0.698075 0.11778 0.687425 0.698081 -0.200324 0.687429 0.698076 -0.200327 0.532433 0.698081 -0.478746 0.532434 0.698078 -0.478749 0.271984 0.698077 -0.662354 0.271984 0.698072 -0.662359 -0.0423347 0.698068 -0.714779 -0.0423363 0.698065 -0.714782 -0.0423345 -0.698068 -0.714779 -0.0423351 -0.698069 -0.714778 0.271988 -0.698069 -0.662361 0.271984 -0.698073 -0.662359 0.532435 -0.698074 -0.478755 0.532442 -0.698068 -0.478756 0.687435 -0.698071 -0.200326 0.687435 -0.69807 -0.200326 0.706272 -0.698075 0.117777 0.706273 -0.698073 0.117779 0.585226 -0.698074 0.412557 0.585227 -0.698073 0.412558 0.348272 -0.698072 0.625621 0.348272 -0.698078 0.625615 -0.0591238 0 -0.998251 -0.0591238 0 -0.998251 0.379855 0 -0.925046 0.379855 0 -0.925046 0.743598 0 -0.668627 0.743598 0 -0.668627 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986379 0 0.164488 0.986379 0 0.164488 0.817325 0 0.576176 0.817325 0 0.576176 0.486394 0 0.873739 0.486394 0 0.873739 0.348267 0.698082 0.625613 0.348267 0.698082 0.625613 0.585221 0.698081 0.412553 0.58523 0.698071 0.412555 0.706272 0.698075 0.117777 0.706269 0.698078 0.117778 0.687431 0.698075 -0.200325 0.687431 0.698075 -0.200326 0.532437 0.698071 -0.478756 0.532434 0.698077 -0.478751 0.271985 0.698077 -0.662354 0.271985 0.698086 -0.662345 -0.0423334 0.698087 -0.71476 -0.0423355 0.698083 -0.714765 -0.0217581 0 -0.999763 -0.0217581 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217532 0.999763 0 -0.0217532 0.8767 0 0.481038 0.8767 0 0.481038 0.518725 0 0.854941 0.518725 0 0.854941 -0.0591247 0 -0.998251 -0.0591247 0 -0.998251 0.379855 0 -0.925046 0.379855 0 -0.925046 0.743602 0 -0.668623 0.743602 0 -0.668623 0.960066 0 -0.279773 0.960066 0 -0.279773 0.986379 0 0.164489 0.986379 0 0.164489 0.817327 0 0.576174 0.817327 0 0.576174 0.486397 0 0.873738 0.486397 0 0.873738 -0.021758 0 -0.999763 -0.059112 0.0207329 -0.998036 0.414112 -0.0178267 -0.910051 0.379855 0 -0.925046 0.635638 0 -0.771987 0.743388 -0.0238606 -0.668435 0.791487 0 -0.611186 0.922706 0 -0.385505 0.95972 -0.026853 -0.279672 0.985354 0 -0.170522 0.995913 0 0.0903171 0.986098 -0.0238601 0.164442 0.950847 0 0.309662 0.838298 0 0.545212 0.817237 -0.0148933 0.57611 0.518642 0.0178279 0.854806 0.486392 0 0.873741 -0.0423341 -0.698073 -0.714774 -0.0423361 -0.698078 -0.714769 0.271987 -0.698077 -0.662354 0.271986 -0.698078 -0.662353 0.532432 -0.698078 -0.478751 0.532436 -0.698075 -0.478752 0.687432 -0.698074 -0.200325 0.687427 -0.698078 -0.200326 0.706269 -0.698077 0.117781 0.706264 -0.698083 0.117777 0.585222 -0.698082 0.412548 0.585226 -0.698075 0.412555 0.348269 -0.698076 0.625618 0.348269 -0.698077 0.625618 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379857 0 -0.925045 0.379857 0 -0.925045 0.743598 0 -0.668627 0.743598 0 -0.668627 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986378 0 0.164493 0.986378 0 0.164493 0.81733 0 0.57617 0.81733 0 0.57617 0.486394 0 0.87374 0.486394 0 0.87374 0.348271 0.698073 0.625621 0.34827 0.698074 0.62562 0.58523 0.698072 0.412554 0.585224 0.698079 0.412552 0.706266 0.698081 0.11778 0.706281 0.698066 0.117778 0.687437 0.698068 -0.200327 0.687435 0.698071 -0.200325 0.532437 0.698071 -0.478756 0.532433 0.698079 -0.478749 0.271986 0.698077 -0.662353 0.271987 0.698073 -0.662357 -0.0423339 0.698076 -0.714771 -0.042335 0.698073 -0.714774 -0.0423335 -0.698082 -0.714765 -0.0423317 -0.698078 -0.714769 0.271983 -0.698079 -0.662353 0.271984 -0.698077 -0.662354 0.532435 -0.698078 -0.478749 0.532434 -0.698078 -0.478749 0.687428 -0.698078 -0.200325 0.68743 -0.698076 -0.200325 0.706268 -0.698079 0.117778 0.706268 -0.698079 0.117778 0.585224 -0.698078 0.412553 0.585225 -0.698076 0.412555 0.348271 -0.698075 0.625619 0.348271 -0.698073 0.625621 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379853 0 -0.925047 0.379853 0 -0.925047 0.743601 0 -0.668624 0.743601 0 -0.668624 0.960065 0 -0.279776 0.960065 0 -0.279776 0.986379 0 0.164489 0.986379 0 0.164489 0.817327 0 0.576174 0.817327 0 0.576174 0.486395 0 0.873739 0.486395 0 0.873739 0.348269 0.698078 0.625616 0.348272 0.698074 0.625618 0.585228 0.698073 0.412556 0.585232 0.698069 0.412557 0.706274 0.698073 0.117779 0.706273 0.698073 0.117779 0.687433 0.698073 -0.200327 0.687427 0.698079 -0.200323 0.532432 0.698081 -0.478747 0.532436 0.698074 -0.478753 0.271985 0.698074 -0.662357 0.271984 0.698076 -0.662355 -0.0423339 0.698076 -0.714771 -0.0423323 0.69808 -0.714768 -0.0423335 -0.698082 -0.714765 -0.0423317 -0.698078 -0.714769 0.271984 -0.698077 -0.662354 0.271984 -0.698077 -0.662354 0.532434 -0.698078 -0.47875 0.532435 -0.698077 -0.47875 0.68743 -0.698076 -0.200326 0.687432 -0.698074 -0.200325 0.70627 -0.698076 0.117778 0.70627 -0.698076 0.117778 0.585225 -0.698076 0.412554 0.585226 -0.698074 0.412556 0.348271 -0.698074 0.62562 0.348271 -0.698073 0.625621 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379854 0 -0.925046 0.379854 0 -0.925046 0.7436 0 -0.668624 0.7436 0 -0.668624 0.960065 0 -0.279776 0.960065 0 -0.279776 0.986379 0 0.164489 0.986379 0 0.164489 0.817327 0 0.576174 0.817327 0 0.576174 0.486395 0 0.873739 0.486395 0 0.873739 0.348269 0.698079 0.625616 0.348271 0.698076 0.625618 0.585226 0.698075 0.412555 0.585232 0.698069 0.412557 0.706274 0.698073 0.117779 0.706273 0.698073 0.117779 0.687433 0.698073 -0.200327 0.68743 0.698076 -0.200325 0.532434 0.698078 -0.478749 0.532434 0.698077 -0.478751 0.271985 0.698076 -0.662355 0.271985 0.698076 -0.662355 -0.0423339 0.698076 -0.714771 -0.0423321 0.69808 -0.714767 -0.0156487 -0.694755 -0.719076 -0.015647 -0.694751 -0.71908 0.345988 -0.69475 -0.630567 0.345986 -0.694752 -0.630565 0.614916 -0.694751 -0.373093 0.614919 -0.694749 -0.373093 0.719082 -0.694749 -0.0156493 0.719082 -0.694749 -0.0156493 0.630567 -0.694751 0.345986 0.63057 -0.694746 0.34599 0.373095 -0.694744 0.614924 0.373094 -0.694747 0.614921 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217577 0.999763 0 -0.0217577 0.8767 0 0.481037 0.8767 0 0.481037 0.518722 0 0.854943 0.518722 0 0.854943 0.37309 0.694753 0.614917 0.373101 0.694738 0.614926 0.630575 0.694742 0.34599 0.630568 0.694748 0.345989 0.719084 0.694747 -0.0156493 0.719084 0.694747 -0.0156494 0.614921 0.694746 -0.373096 0.614919 0.694749 -0.373093 0.345988 0.69475 -0.630567 0.345988 0.694748 -0.630569 -0.0156488 0.694749 -0.719082 -0.0156475 0.694753 -0.719078 -0.0156495 -0.694753 -0.719078 -0.0156485 -0.694749 -0.719082 0.345988 -0.69475 -0.630568 0.34599 -0.694746 -0.63057 0.61492 -0.694748 -0.373094 0.614917 -0.694751 -0.373093 0.719078 -0.694753 -0.0156495 0.719082 -0.694749 -0.0156485 0.630568 -0.69475 0.345987 0.630569 -0.694748 0.345988 0.373096 -0.694746 0.614921 0.373096 -0.694745 0.614921 -0.0156494 -0.694753 -0.719078 -0.0156485 -0.694749 -0.719082 0.345989 -0.694746 -0.63057 0.345996 -0.694737 -0.630578 0.614928 -0.694738 -0.373098 0.614915 -0.694752 -0.373094 0.719084 -0.694747 -0.0156496 0.719083 -0.694748 -0.01565 0.630567 -0.694749 0.345989 0.630565 -0.694752 0.345987 0.373093 -0.694752 0.614916 0.373093 -0.694751 0.614917 0.348267 -0.69808 0.625616 0.348268 -0.698076 0.625619 0.492298 -0.706861 0.507927 0.648721 -0.608298 0.457312 0.59796 -0.700857 0.3889 0.673293 -0.706114 0.219271 0.8305 -0.539526 0.138495 0.70816 -0.703125 0.0642217 0.698944 -0.704873 -0.120957 0.823667 -0.51377 -0.240026 0.654502 -0.704876 -0.273453 0.532434 -0.698078 -0.478749 0.719952 -0.415442 -0.555947 0.4501 -0.706117 -0.546635 0.271986 -0.698075 -0.662356 -0.0423352 -0.698066 -0.71478 -0.0423372 -0.698075 -0.714772 0.142357 -0.706861 -0.692879 0.336707 -0.582331 -0.739945 -0.015649 -0.694746 -0.719085 -0.0156496 -0.694747 -0.719084 0.345992 -0.694745 -0.63057 0.345987 -0.69475 -0.630567 0.614919 -0.69475 -0.373091 0.614916 -0.694753 -0.373091 0.719079 -0.694752 -0.0156489 0.719078 -0.694753 -0.0156495 0.630567 -0.694751 0.345987 0.63057 -0.694746 0.345991 0.373095 -0.694748 0.61492 0.373095 -0.694748 0.614919 -0.0217572 0 -0.999763 -0.0217572 0 -0.999763 0.481042 0 -0.876698 0.481042 0 -0.876698 0.854943 0 -0.518722 0.854943 0 -0.518722 0.999763 0 -0.0217573 0.999763 0 -0.0217573 0.8767 0 0.481038 0.8767 0 0.481038 0.518725 0 0.854941 0.518725 0 0.854941 0.373093 0.69475 0.614917 0.373087 0.694758 0.614912 0.630557 0.694762 0.345982 0.630559 0.69476 0.345982 0.719071 0.69476 -0.0156488 0.719076 0.694756 -0.0156504 0.614912 0.694759 -0.373087 0.614915 0.694754 -0.373091 0.345988 0.694754 -0.630562 0.345989 0.694747 -0.630569 -0.0156489 0.694751 -0.71908 -0.0156507 0.694746 -0.719085 0.348273 -0.698077 0.625616 0.348272 -0.698071 0.625623 0.492284 -0.706856 0.507948 0.610931 -0.66429 0.430675 0.597961 -0.700857 0.388898 0.673293 -0.706114 0.219273 0.756461 -0.641758 0.126147 0.708164 -0.703121 0.0642232 0.698947 -0.70487 -0.12096 0.742577 -0.63384 -0.216394 0.654508 -0.704871 -0.273452 0.532439 -0.698069 -0.478757 0.633378 -0.599679 -0.489099 0.450094 -0.706115 -0.546642 0.27199 -0.698073 -0.662356 -0.0423338 -0.698079 -0.714768 -0.0423344 -0.69808 -0.714767 0.142358 -0.706864 -0.692876 0.313595 -0.653242 -0.689154 -0.0591238 0 -0.998251 -0.0217564 -0.00889363 -0.999724 0.201256 0 -0.979539 0.414178 0 -0.910196 0.480985 -0.0148494 -0.876603 0.635638 0 -0.771987 0.791484 0 -0.61119 0.854805 -0.0178362 -0.518642 0.922706 0 -0.385504 0.985353 0 -0.170526 0.999604 -0.0178359 -0.0217537 0.995913 0 0.0903191 0.950846 0 0.309664 0.876603 -0.0148496 0.480985 0.486394 0 0.873739 0.518701 -0.008893 0.854909 0.695948 0 0.718092 0.8383 0 0.545209 0.373089 0.694754 0.614916 0.373089 0.694754 0.614916 0.630564 0.694754 0.345985 0.63057 0.694748 0.345986 0.71908 0.694751 -0.0156489 0.719076 0.694755 -0.0156473 0.614911 0.694758 -0.373089 0.614916 0.69475 -0.373096 0.345989 0.694746 -0.630571 0.345987 0.694759 -0.630557 -0.0156488 0.69476 -0.719071 -0.0156504 0.694756 -0.719076 0.373092 -0.694751 0.614917 0.373092 -0.694748 0.614921 0.63057 -0.694747 0.345988 0.685458 -0.575678 0.445806 0.673292 -0.706114 0.219272 0.719085 -0.694746 -0.0156495 0.864654 -0.49621 0.0784139 0.698947 -0.704871 -0.120956 0.654507 -0.70487 -0.273459 0.680999 -0.60458 -0.413186 -0.0156491 -0.694741 -0.71909 -0.0156497 -0.694742 -0.719089 0.295434 -0.700857 -0.649244 0.376792 -0.621656 -0.686711 0.450094 -0.706114 -0.546643 0.562805 -0.703122 -0.434591 -0.0217573 0 -0.999763 -0.0591206 0.0103442 -0.998197 0.414162 -0.00889392 -0.91016 0.379855 0 -0.925046 0.635638 0 -0.771988 0.74355 -0.0119059 -0.668575 0.791491 0 -0.61118 0.922702 0 -0.385514 0.95998 -0.0133999 -0.279749 0.985354 0 -0.17052 0.995913 0 0.0903176 0.986309 -0.0119052 0.164478 0.950846 0 0.309664 0.838299 0 0.54521 0.817303 -0.00743116 0.57616 0.518701 0.00889297 0.85491 0.486394 0 0.873739 0.348267 0.698082 0.625613 0.348267 0.698082 0.625613 0.585221 0.69808 0.412553 0.58523 0.698072 0.412555 0.706271 0.698075 0.117779 0.706272 0.698074 0.117778 0.687426 0.69808 -0.200324 0.687427 0.698079 -0.200324 0.532431 0.698084 -0.478744 0.532434 0.698077 -0.478751 0.271985 0.698077 -0.662354 0.271985 0.69807 -0.662362 -0.0423345 0.698069 -0.714778 -0.0423285 0.698082 -0.714766 -0.0217581 0 -0.999763 -0.0217581 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217581 0.999763 0 -0.0217581 0.8767 0 0.481037 0.8767 0 0.481037 0.518725 0 0.854941 0.518725 0 0.854941 -0.021758 0 -0.999763 -0.021758 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854943 0 -0.518723 0.854943 0 -0.518723 0.999763 0 -0.0217581 0.999763 0 -0.0217581 0.876699 0 0.48104 0.876699 0 0.48104 0.518725 0 0.854941 0.518725 0 0.854941 -0.0591247 0 -0.998251 -0.0217546 -0.0178262 -0.999604 0.201253 0 -0.979539 0.414178 0 -0.910196 0.480829 -0.0297591 -0.87631 0.635648 0 -0.771979 0.791487 0 -0.611186 0.854395 -0.0357358 -0.518394 0.922704 0 -0.385509 0.985354 0 -0.170522 0.999125 -0.0357361 -0.0217439 0.995913 0 0.0903175 0.950847 0 0.309661 0.876311 -0.0297587 0.480826 0.486392 0 0.873741 0.518642 -0.0178279 0.854806 0.695973 0 0.718068 0.838298 0 0.545212 -0.0156494 -0.69475 -0.719081 -0.0156494 -0.69475 -0.719081 0.345986 -0.694751 -0.630567 0.34599 -0.694747 -0.63057 0.614924 -0.694744 -0.373095 0.614913 -0.694754 -0.373093 0.719076 -0.694755 -0.0156487 0.71908 -0.694751 -0.015647 0.630568 -0.694751 0.345984 0.630572 -0.694744 0.34599 0.373094 -0.694746 0.614922 0.373093 -0.694753 0.614915 -0.0591249 0 -0.998251 -0.0217573 0.00717248 -0.999738 0.201258 0 -0.979538 0.414178 0 -0.910196 0.481003 0.0119758 -0.876637 0.635636 0 -0.771989 0.791488 0 -0.611185 0.854854 0.0143844 -0.518669 0.922706 0 -0.385504 0.985353 0 -0.170526 0.99966 0.0143847 -0.0217548 0.995913 0 0.0903214 0.950851 0 0.309649 0.876639 0.0119767 0.481 0.8383 0 0.545209 0.695954 0 0.718087 0.518709 0.00717233 0.854921 0.486393 0 0.87374 -0.0423347 0.698075 -0.714772 -0.0423349 0.698074 -0.714773 0.14236 0.706862 -0.692878 0.29645 0.625245 -0.721932 0.295431 0.700865 -0.649238 0.450088 0.70612 -0.546639 0.610191 0.571519 -0.548665 0.562802 0.703123 -0.434594 0.654509 0.70487 -0.273452 0.800711 0.551738 -0.23334 0.698938 0.704879 -0.120959 0.706267 0.69808 0.11778 0.876357 0.47506 0.0794787 0.6733 0.70611 0.219263 0.585232 0.698069 0.412558 0.34827 0.698073 0.625621 0.348271 0.698073 0.625621 0.492287 0.706858 0.507942 0.668098 0.604021 0.434514 -0.0156489 -0.694746 -0.719085 -0.0156508 -0.694751 -0.719081 0.345986 -0.694752 -0.630566 0.345991 -0.694746 -0.63057 0.614924 -0.694744 -0.373095 0.614914 -0.694753 -0.373094 0.719076 -0.694755 -0.0156487 0.71908 -0.694751 -0.015647 0.630567 -0.694752 0.345984 0.630572 -0.694744 0.345991 0.373094 -0.694745 0.614923 0.373093 -0.694752 0.614915 -0.0217571 0 -0.999763 -0.0217571 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854942 0 -0.518723 0.854942 0 -0.518723 0.999763 0 -0.0217571 0.999763 0 -0.0217571 0.876702 0 0.481035 0.876702 0 0.481035 0.518722 0 0.854943 0.518722 0 0.854943 0.373094 0.694746 0.614922 0.373097 0.694742 0.614925 0.630579 0.694738 0.345991 0.630567 0.69475 0.345988 0.719082 0.694749 -0.0156488 0.719078 0.694753 -0.0156475 0.614917 0.694752 -0.373091 0.614917 0.694752 -0.373091 0.345986 0.694752 -0.630566 0.345987 0.69475 -0.630568 -0.0156489 0.694749 -0.719082 -0.0156496 0.694746 -0.719085 -0.0423338 -0.698078 -0.71477 -0.042334 -0.698078 -0.714769 0.271984 -0.698077 -0.662354 0.271984 -0.698077 -0.662354 0.532433 -0.698078 -0.47875 0.532437 -0.698075 -0.478751 0.687432 -0.698074 -0.200326 0.687428 -0.698077 -0.200327 0.706269 -0.698078 0.117776 0.706272 -0.698074 0.117778 0.585226 -0.698074 0.412556 0.585227 -0.698072 0.412558 0.348271 -0.698072 0.625621 0.348271 -0.698077 0.625616 -0.0591236 0 -0.998251 -0.0591236 0 -0.998251 0.379854 0 -0.925046 0.379854 0 -0.925046 0.743599 0 -0.668625 0.743599 0 -0.668625 0.960066 0 -0.279775 0.960066 0 -0.279775 0.986379 0 0.164486 0.986379 0 0.164486 0.817326 0 0.576175 0.817326 0 0.576175 0.486394 0 0.87374 0.486394 0 0.87374 0.348271 0.698073 0.625621 0.348274 0.698068 0.625624 0.585231 0.698069 0.412559 0.585232 0.698067 0.412559 0.70628 0.698067 0.117778 0.706267 0.69808 0.11778 0.687427 0.698079 -0.200324 0.687432 0.698073 -0.200328 0.532435 0.698076 -0.478752 0.532433 0.698079 -0.478749 0.271984 0.698077 -0.662354 0.271984 0.698078 -0.662353 -0.0423339 0.698075 -0.714772 -0.0423348 0.698073 -0.714774 -0.0156489 -0.694746 -0.719085 -0.0156507 -0.694751 -0.719081 0.345987 -0.694752 -0.630566 0.345987 -0.694752 -0.630566 0.614918 -0.69475 -0.373094 0.614918 -0.69475 -0.373094 0.71908 -0.694751 -0.0156488 0.71908 -0.694751 -0.0156489 0.630566 -0.694752 0.345986 0.63057 -0.694746 0.345991 0.373095 -0.694744 0.614924 0.373094 -0.694753 0.614914 -0.0591236 0 -0.998251 -0.0217565 0.00717239 -0.999738 0.201252 0 -0.97954 0.414177 0 -0.910196 0.481004 0.0119763 -0.876636 0.635644 0 -0.771983 0.791488 0 -0.611185 0.854853 0.014384 -0.518671 0.922703 0 -0.385511 0.985354 0 -0.170519 0.99966 0.0143841 -0.0217549 0.995913 0 0.0903171 0.950846 0 0.309664 0.876637 0.0119761 0.481003 0.8383 0 0.545209 0.695951 0 0.718089 0.518709 0.00717196 0.854921 0.486395 0 0.873739 -0.0423323 0.69808 -0.714768 -0.0423339 0.698076 -0.714771 0.142356 0.706861 -0.692879 0.296451 0.625239 -0.721937 0.295431 0.700863 -0.64924 0.450096 0.706117 -0.546637 0.610185 0.571527 -0.548663 0.562795 0.703131 -0.434589 0.654499 0.704879 -0.273454 0.80072 0.551727 -0.233336 0.698945 0.704873 -0.120955 0.706273 0.698073 0.117779 0.876366 0.475043 0.0794757 0.673289 0.706118 0.219271 0.585224 0.698077 0.412555 0.348269 0.698078 0.625616 0.348272 0.698074 0.625618 0.492284 0.706859 0.507944 0.668097 0.604024 0.434513 -0.0156493 -0.694747 -0.719084 -0.0156493 -0.694748 -0.719083 0.345992 -0.694742 -0.630574 0.345987 -0.694749 -0.630569 0.614918 -0.69475 -0.373093 0.614927 -0.694741 -0.373096 0.719091 -0.694739 -0.0156497 0.719083 -0.694748 -0.0156517 0.630569 -0.694749 0.345988 0.630576 -0.694738 0.345995 0.373096 -0.694742 0.614925 0.373095 -0.694747 0.61492 -0.0156479 -0.694746 -0.719085 -0.0156485 -0.694749 -0.719082 0.345988 -0.69475 -0.630568 0.34599 -0.694746 -0.63057 0.61492 -0.694748 -0.373094 0.614913 -0.694755 -0.373092 0.719078 -0.694753 -0.0156495 0.719082 -0.694749 -0.0156484 0.630568 -0.69475 0.345987 0.630569 -0.694748 0.345988 0.373096 -0.694746 0.614921 0.373096 -0.694745 0.614921 -0.0156495 -0.694753 -0.719078 -0.0156484 -0.694749 -0.719082 0.345987 -0.69475 -0.630568 0.345988 -0.694748 -0.630569 0.614921 -0.694746 -0.373096 0.614921 -0.694745 -0.373096 0.719085 -0.694746 -0.0156496 0.719089 -0.694742 -0.0156486 0.630573 -0.694744 0.34599 0.630576 -0.694739 0.345993 0.3731 -0.694736 0.614929 0.373098 -0.694743 0.614923 -0.0156495 -0.694746 -0.719085 -0.0156493 -0.694746 -0.719085 0.345985 -0.69475 -0.630568 0.345993 -0.694742 -0.630573 0.614928 -0.694739 -0.373097 0.614925 -0.694742 -0.373097 0.71909 -0.694741 -0.0156491 0.719089 -0.694742 -0.0156497 0.630574 -0.694742 0.345991 0.630573 -0.694744 0.345989 0.373096 -0.694745 0.614922 0.373096 -0.694742 0.614925 -0.0217579 0 -0.999763 -0.0217579 0 -0.999763 0.481035 0 -0.876701 0.481035 0 -0.876701 0.854943 0 -0.518721 0.854943 0 -0.518721 0.999763 0 -0.0217573 0.999763 0 -0.0217573 0.8767 0 0.481038 0.8767 0 0.481038 0.518724 0 0.854941 0.518724 0 0.854941 0.373096 0.694744 0.614923 0.373095 0.694746 0.614921 0.630573 0.694744 0.34599 0.630574 0.694743 0.34599 0.719089 0.694742 -0.0156491 0.719077 0.694755 -0.0156443 0.614915 0.694755 -0.373089 0.614927 0.694737 -0.373103 0.345989 0.694742 -0.630576 0.345987 0.694755 -0.630562 -0.0156494 0.694749 -0.719082 -0.0156492 0.69475 -0.719081 0.348271 -0.698075 0.625618 0.348271 -0.69807 0.625624 0.492308 -0.706855 0.507926 0.610927 -0.664298 0.430669 0.59796 -0.700855 0.388903 0.673299 -0.70611 0.219264 0.756458 -0.641762 0.12615 0.708159 -0.703127 0.0642233 0.698942 -0.704875 -0.120959 0.742573 -0.633844 -0.216396 0.654506 -0.704873 -0.273451 0.532437 -0.698073 -0.478754 0.633391 -0.599666 -0.489098 0.450088 -0.706115 -0.546646 0.271988 -0.698073 -0.662357 -0.0423339 -0.698073 -0.714774 -0.0423345 -0.698074 -0.714773 0.142359 -0.706859 -0.692881 0.313599 -0.653235 -0.689158 -0.0591234 0 -0.998251 -0.0217563 -0.00889363 -0.999724 0.201256 0 -0.979539 0.414181 0 -0.910195 0.480985 -0.0148488 -0.876603 0.635631 0 -0.771993 0.791491 0 -0.611181 0.854809 -0.0178354 -0.518637 0.922706 0 -0.385504 0.985353 0 -0.170526 0.999604 -0.0178359 -0.0217538 0.995913 0 0.0903198 0.950851 0 0.30965 0.876603 -0.0148508 0.480985 0.486392 0 0.873741 0.518704 -0.00889461 0.854907 0.695981 0 0.71806 0.838297 0 0.545213 0.373093 0.69475 0.614917 0.373094 0.694749 0.614918 0.630571 0.694746 0.345989 0.630557 0.694759 0.345987 0.719071 0.69476 -0.0156488 0.719076 0.694756 -0.0156504 0.614913 0.694759 -0.373085 0.614919 0.694749 -0.373093 0.345989 0.694746 -0.630571 0.345989 0.694747 -0.630569 -0.0156489 0.694751 -0.71908 -0.0156505 0.694746 -0.719084 -0.0423347 -0.698068 -0.714779 -0.0423351 -0.698069 -0.714778 0.271987 -0.69807 -0.662361 0.271984 -0.698072 -0.662359 0.53244 -0.698072 -0.478753 0.532438 -0.698073 -0.478752 0.687435 -0.69807 -0.200327 0.687435 -0.698071 -0.200327 0.706276 -0.69807 0.117781 0.706272 -0.698074 0.117778 0.585228 -0.698075 0.412551 0.585231 -0.69807 0.412558 0.348272 -0.698071 0.625623 0.348272 -0.698068 0.625626 -0.0591241 0 -0.998251 -0.0591241 0 -0.998251 0.379854 0 -0.925047 0.379854 0 -0.925047 0.743602 0 -0.668623 0.743602 0 -0.668623 0.960066 0 -0.279774 0.960066 0 -0.279774 0.986378 0 0.164492 0.986378 0 0.164492 0.81733 0 0.57617 0.81733 0 0.57617 0.486394 0 0.873739 0.486394 0 0.873739 0.348275 0.698065 0.625628 0.348275 0.698065 0.625628 0.585235 0.698066 0.412556 0.585222 0.69808 0.412553 0.706271 0.698076 0.11778 0.706277 0.69807 0.117779 0.687438 0.698067 -0.200328 0.687431 0.698076 -0.200322 0.532433 0.698081 -0.478746 0.532434 0.698078 -0.478749 0.271984 0.698077 -0.662354 0.271984 0.698072 -0.662359 -0.0423347 0.698068 -0.714779 -0.0423363 0.698065 -0.714782 -0.0217577 0 -0.999763 -0.0217577 0 -0.999763 0.481039 0 -0.876699 0.481039 0 -0.876699 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.021758 0.999763 0 -0.021758 0.8767 0 0.481038 0.8767 0 0.481038 0.518723 0 0.854943 0.518723 0 0.854943 -0.0217557 0 -0.999763 -0.0217557 0 -0.999763 0.481038 0 -0.8767 0.481038 0 -0.8767 0.854942 0 -0.518724 0.854942 0 -0.518724 0.999763 0 -0.0217581 0.999763 0 -0.0217581 0.8767 0 0.481037 0.8767 0 0.481037 0.518725 0 0.854941 0.518725 0 0.854941 -0.0217581 0 -0.999763 -0.0217581 0 -0.999763 0.481037 0 -0.8767 0.481037 0 -0.8767 0.854941 0 -0.518725 0.854941 0 -0.518725 0.999763 0 -0.0217581 0.999763 0 -0.0217581 0.8767 0 0.481038 0.8767 0 0.481038 0.518724 0 0.854942 0.518724 0 0.854942 0.37253 0 0.92802 0.37253 0 0.92802 0.54642 0 0.837512 0.54642 0 0.837512 0.699311 0 0.714818 0.699311 0 0.714818 0.825328 0 0.564654 0.825328 0 0.564654 0.919628 0 0.392791 0.919628 0 0.392791 0.978587 0 0.205833 0.978587 0 0.205833 0.99994 0 0.0109654 0.99994 0 0.0109654 0.982866 0 -0.184324 0.982866 0 -0.184324 0.92802 0 -0.37253 0.92802 0 -0.37253 0.837511 0 -0.54642 0.837511 0 -0.54642 0.714818 0 -0.699311 0.714818 0 -0.699311 0.564654 0 -0.825328 0.564654 0 -0.825328 0.392791 0 -0.919628 0.392791 0 -0.919628 0.205833 0 -0.978587 0.205833 0 -0.978587 0.0109654 0 -0.99994 0.0109654 0 -0.99994 -0.184324 0 -0.982866 -0.184324 0 -0.982866 0.3581 0 0.933683 0.3581 0 0.933683 0.506896 0 0.862007 0.506896 0 0.862007 0.641864 0 0.766819 0.641864 0 0.766819 0.759324 0 0.650713 0.759324 0 0.650713 0.856072 0 0.516857 0.856072 0 0.516857 0.929468 0 0.368904 0.929468 0 0.368904 0.977511 0 0.210887 0.977511 0 0.210887 0.998889 0 0.0471174 0.998889 0 0.0471174 0.993021 0 -0.117937 0.993021 0 -0.117937 0.960066 0 -0.279774 0.960066 0 -0.279774 0.900922 0 -0.43398 0.900922 0 -0.43398 0.817204 0 -0.576348 0.817204 0 -0.576348 0.711195 0 -0.702995 0.711195 0 -0.702995 0.585786 0 -0.810466 0.585786 0 -0.810466 0.444399 0 -0.895829 0.444399 0 -0.895829 0.290889 0 -0.956757 0.290889 0 -0.956757 0.129444 0 -0.991587 0.129444 0 -0.991587 -0.0355307 0 -0.999369 -0.0355307 0 -0.999369 -0.199537 0 -0.97989 -0.199537 0 -0.97989 -0.0310211 -0.851308 -0.523749 -0.0310208 -0.851308 -0.523749 0.199298 -0.851306 -0.485343 0.199297 -0.851307 -0.485343 0.390143 -0.851307 -0.350806 0.390142 -0.851308 -0.350806 0.503715 -0.851308 -0.146786 0.503713 -0.851309 -0.146787 0.517518 -0.851309 0.0863001 0.51752 -0.851308 0.0863028 0.428826 -0.851308 0.302296 0.428826 -0.851306 0.302302 0.255194 -0.851306 0.458426 0.255195 -0.851307 0.458423 -0.0114925 -0.849122 -0.528072 -0.0114926 -0.849122 -0.528072 0.254086 -0.84912 -0.463071 0.254083 -0.849122 -0.46307 0.451577 -0.849122 -0.27399 0.451576 -0.849122 -0.27399 0.528071 -0.849122 -0.0114892 0.528069 -0.849124 -0.0114913 0.463069 -0.849124 0.254078 0.463071 -0.849122 0.254082 0.273986 -0.849121 0.45158 0.273987 -0.849123 0.451576 -0.0310175 -0.851306 -0.523751 -0.0310195 -0.851308 -0.523749 0.199296 -0.851307 -0.485343 0.199298 -0.851306 -0.485343 0.390144 -0.851306 -0.350806 0.390144 -0.851307 -0.350806 0.503716 -0.851307 -0.14679 0.503715 -0.851307 -0.14679 0.517521 -0.851307 0.0863044 0.51752 -0.851308 0.086303 0.428826 -0.851308 0.302298 0.428826 -0.851306 0.302302 0.255196 -0.851306 0.458425 0.255196 -0.851307 0.458423 -0.0114892 -0.849122 -0.528071 -0.0114913 -0.849124 -0.528069 0.254078 -0.849124 -0.463069 0.254083 -0.849122 -0.463071 0.451579 -0.849122 -0.273987 0.451576 -0.849123 -0.273988 0.528072 -0.849122 -0.0114926 0.528073 -0.849121 -0.0114914 0.463071 -0.849122 0.254083 0.463071 -0.849121 0.254084 0.27399 -0.849121 0.451577 0.273989 -0.84912 0.451581 -0.0310211 -0.851309 -0.523748 -0.0310194 -0.851308 -0.523749 0.199295 -0.851308 -0.485342 0.199299 -0.851306 -0.485343 0.390144 -0.851306 -0.350806 0.390141 -0.851308 -0.350806 0.503713 -0.851308 -0.146789 0.503716 -0.851307 -0.146787 0.517521 -0.851308 0.0863006 0.517523 -0.851306 0.0863035 0.428826 -0.851306 0.302302 0.428826 -0.851307 0.302299 0.255196 -0.851307 0.458422 0.255196 -0.851307 0.458423 -0.0114926 -0.849122 -0.528072 -0.0114925 -0.849122 -0.528072 0.254082 -0.849123 -0.463069 0.254083 -0.849122 -0.46307 0.451576 -0.849122 -0.27399 0.451582 -0.849119 -0.273989 0.528077 -0.849119 -0.0114893 0.52807 -0.849123 -0.0114959 0.463067 -0.849124 0.254083 0.463069 -0.849122 0.254086 0.27399 -0.849121 0.451579 0.27399 -0.849121 0.451579 -0.0114909 -0.849121 -0.528074 -0.0114925 -0.849122 -0.528072 0.254082 -0.849123 -0.463069 0.254083 -0.849122 -0.46307 0.45158 -0.849121 -0.273986 0.451577 -0.849123 -0.273987 0.52807 -0.849123 -0.0114958 0.528075 -0.84912 -0.0114914 0.463072 -0.84912 0.254086 0.463071 -0.849122 0.254083 0.27399 -0.849122 0.451577 0.27399 -0.849121 0.451579 -0.0114926 -0.849121 -0.528073 -0.0114937 -0.849122 -0.528072 0.254084 -0.849121 -0.46307 0.254083 -0.849122 -0.46307 0.451579 -0.849122 -0.273988 0.451579 -0.849121 -0.273988 0.528073 -0.849121 -0.0114926 0.528072 -0.849122 -0.0114937 0.463069 -0.849122 0.254083 0.463069 -0.849122 0.254084 0.273989 -0.849122 0.451577 0.273989 -0.849123 0.451576 -0.0114958 -0.849123 -0.52807 -0.0114914 -0.84912 -0.528075 0.254086 -0.84912 -0.463072 0.254082 -0.849122 -0.463071 0.451577 -0.849122 -0.273989 0.451579 -0.849121 -0.273989 0.528072 -0.849122 -0.0114925 0.528072 -0.849122 -0.0114925 0.463069 -0.849123 0.254082 0.46307 -0.849122 0.254083 0.273986 -0.849121 0.45158 0.273987 -0.849123 0.451577 -0.0114926 -0.849121 -0.528073 0.273988 -0.849123 0.451576 0.273988 -0.849122 0.451579 0.437342 -0.853128 0.284437 0.433021 -0.869506 0.237596 0.487359 -0.873137 -0.0106066 0.517169 -0.854597 0.0469035 0.490729 -0.856531 0.159813 0.416762 -0.873137 -0.252866 0.477429 -0.855729 -0.199473 0.509846 -0.855729 -0.088234 -0.0114937 -0.849122 -0.528072 0.216077 -0.853128 -0.474851 0.237597 -0.869507 -0.433019 0.328054 -0.856532 -0.398414 0.411012 -0.854598 -0.317382 -0.0310175 -0.851305 -0.523754 0.255197 -0.851305 0.458426 0.255194 -0.851305 0.458428 0.358632 -0.857008 0.370028 0.424209 -0.854762 0.299045 0.508643 -0.856791 0.0848053 0.49073 -0.856529 0.159818 0.437346 -0.853126 0.284439 0.494003 -0.85746 -0.143955 0.509849 -0.855727 -0.0882324 0.517171 -0.854596 0.0469007 0.38344 -0.856792 -0.344792 0.411014 -0.854596 -0.317385 0.477432 -0.855727 -0.199472 -0.0310221 -0.851305 -0.523753 0.103712 -0.857008 -0.504759 0.197157 -0.854762 -0.480115 0.216079 -0.853126 -0.474854 0.328053 -0.856529 -0.39842 -0.0310398 -0.851307 -0.523749 0.255197 -0.851305 0.458426 0.255209 -0.851307 0.458416 0.358627 -0.857008 0.370032 0.4242 -0.854764 0.299054 0.508638 -0.856792 0.0848255 0.49073 -0.856529 0.159817 0.437346 -0.853126 0.284439 0.493997 -0.85746 -0.143974 0.509849 -0.855727 -0.0882335 0.517172 -0.854596 0.0469013 0.38345 -0.856791 -0.344782 0.411015 -0.854596 -0.317385 0.477432 -0.855727 -0.199472 -0.031021 -0.851305 -0.523753 0.103706 -0.857008 -0.50476 0.197157 -0.854762 -0.480115 0.21608 -0.853126 -0.474854 0.328053 -0.856529 -0.398421 -0.031022 -0.851305 -0.523753 -0.031021 -0.851305 -0.523753 0.199309 -0.851304 -0.485342 0.199299 -0.851305 -0.485345 0.390134 -0.851307 -0.350817 0.390146 -0.851305 -0.350808 0.50372 -0.851305 -0.146787 0.503719 -0.851305 -0.14679 0.517525 -0.851307 0.0862872 0.517525 -0.851305 0.0863018 0.428819 -0.851303 0.30232 0.428827 -0.851305 0.302302 0.2552 -0.851305 0.458424 0.255198 -0.851305 0.458425 -0.0114928 -0.84912 -0.528076 -0.0114916 -0.849119 -0.528076 0.25408 -0.84912 -0.463075 0.254085 -0.849119 -0.463074 0.451577 -0.84912 -0.273995 0.451581 -0.849119 -0.273991 0.528076 -0.849119 -0.0114928 0.528076 -0.849119 -0.0114926 0.46307 -0.849118 0.254096 0.463073 -0.849119 0.254086 0.273983 -0.849118 0.451588 0.273991 -0.849119 0.451581 0.255197 -0.851305 0.458425 0.270442 -0.853328 0.44575 0.358631 -0.857008 0.370029 0.437346 -0.853126 0.284439 0.453152 -0.856057 0.248635 0.49073 -0.856529 0.159817 0.517171 -0.854596 0.0469015 0.514531 -0.857399 -0.0111989 0.509849 -0.855727 -0.0882332 0.477432 -0.855727 -0.199473 0.439996 -0.857398 -0.266968 0.411015 -0.854596 -0.317384 0.328051 -0.856529 -0.398422 0.248643 -0.856057 -0.453149 0.21608 -0.853126 -0.474854 0.103706 -0.857008 -0.50476 -0.0113433 -0.853328 -0.521251 -0.031021 -0.851305 -0.523753 -0.0310392 -0.851307 -0.523749 0.255197 -0.851305 0.458425 0.255193 -0.851304 0.458429 0.358632 -0.857008 0.370028 0.424209 -0.854763 0.299044 0.508639 -0.856791 0.0848232 0.49073 -0.856529 0.159818 0.437346 -0.853126 0.284438 0.494002 -0.85746 -0.143958 0.509849 -0.855727 -0.0882329 0.517172 -0.854596 0.0469013 0.38345 -0.856791 -0.344783 0.411014 -0.854596 -0.317385 0.477432 -0.855727 -0.199472 -0.031021 -0.851305 -0.523754 0.103706 -0.857008 -0.50476 0.197155 -0.854762 -0.480116 0.216078 -0.853126 -0.474855 0.328055 -0.856529 -0.398419 -0.0310175 -0.851305 -0.523754 -0.031021 -0.851305 -0.523753 0.199284 -0.851307 -0.485348 0.199298 -0.851305 -0.485345 0.390149 -0.851305 -0.350805 0.390145 -0.851305 -0.350808 0.50372 -0.851305 -0.146787 0.503718 -0.851305 -0.14679 0.517524 -0.851307 0.086286 0.517524 -0.851305 0.0863027 0.428828 -0.851305 0.302302 0.428828 -0.851305 0.302301 0.255186 -0.851304 0.458434 0.255196 -0.851305 0.458426 -0.0114928 -0.849119 -0.528076 -0.0114926 -0.849119 -0.528076 0.25408 -0.84912 -0.463075 0.254085 -0.849119 -0.463074 0.451588 -0.849118 -0.273983 0.451582 -0.849119 -0.27399 0.528076 -0.849119 -0.0114928 0.528076 -0.849119 -0.0114926 0.463075 -0.84912 0.25408 0.463074 -0.849119 0.254085 0.273983 -0.849118 0.451588 0.273991 -0.849119 0.451581 -0.0310189 -0.851305 -0.523754 0.255197 -0.851305 0.458426 0.255198 -0.851306 0.458424 0.358633 -0.857008 0.370027 0.424219 -0.854762 0.299033 0.508634 -0.856792 0.0848469 0.49073 -0.856529 0.159817 0.437346 -0.853126 0.284439 0.494003 -0.85746 -0.143955 0.509849 -0.855727 -0.0882313 0.517172 -0.854596 0.0469029 0.383437 -0.856792 -0.344795 0.411015 -0.854596 -0.317384 0.477432 -0.855727 -0.199474 -0.0310211 -0.851305 -0.523753 0.10371 -0.857008 -0.504759 0.197162 -0.854762 -0.480114 0.216079 -0.853126 -0.474854 0.328053 -0.856529 -0.39842 -0.0114932 -0.849119 -0.528076 -0.0114926 -0.849119 -0.528076 0.25408 -0.84912 -0.463075 0.254085 -0.849119 -0.463073 0.451577 -0.84912 -0.273995 0.451581 -0.849119 -0.273991 0.528076 -0.84912 -0.0114928 0.528076 -0.849119 -0.0114908 0.463071 -0.849118 0.254096 0.463074 -0.849119 0.254085 0.27399 -0.849119 0.451582 0.27399 -0.849119 0.451581 -0.0114928 -0.84912 -0.528076 0.273991 -0.849119 0.451581 0.273995 -0.84912 0.451578 0.437345 -0.853126 0.284439 0.453152 -0.856057 0.248635 0.514531 -0.857399 -0.0111984 0.517171 -0.854596 0.0469014 0.49073 -0.856529 0.159817 0.440003 -0.857399 -0.266954 0.477432 -0.855727 -0.199472 0.509849 -0.855727 -0.0882316 -0.0114926 -0.84912 -0.528076 0.21608 -0.853126 -0.474854 0.248636 -0.856056 -0.453153 0.328053 -0.856529 -0.398421 0.411014 -0.854596 -0.317386 -0.0309972 -0.851303 -0.523759 0.255197 -0.851305 0.458426 0.255192 -0.851305 0.45843 0.358625 -0.857008 0.370034 0.424209 -0.854763 0.299044 0.508639 -0.856791 0.0848232 0.49073 -0.856529 0.159818 0.437346 -0.853126 0.284438 0.494002 -0.85746 -0.143958 0.509849 -0.855727 -0.0882329 0.517172 -0.854596 0.0469011 0.383449 -0.856791 -0.344783 0.411014 -0.854596 -0.317385 0.477432 -0.855727 -0.199472 -0.031021 -0.851305 -0.523753 0.103707 -0.857008 -0.50476 0.197154 -0.854763 -0.480116 0.21608 -0.853126 -0.474854 0.328055 -0.856529 -0.398419 0.0114928 -0.849119 0.528076 -0.273991 -0.849119 -0.451581 -0.274008 -0.849122 -0.451565 -0.437346 -0.853126 -0.284438 -0.453151 -0.856057 -0.24864 -0.514531 -0.857399 0.0111974 -0.517172 -0.854596 -0.046901 -0.49073 -0.856529 -0.159818 -0.439999 -0.857399 0.266962 -0.477432 -0.855727 0.199472 -0.509849 -0.855727 0.0882331 0.0114926 -0.849119 0.528076 -0.216078 -0.853126 0.474855 -0.248624 -0.856056 0.453161 -0.328055 -0.856529 0.398419 -0.411014 -0.854596 0.317385 0.0114928 -0.849119 0.528076 0.0114926 -0.849119 0.528076 -0.254088 -0.849119 0.463073 -0.254085 -0.849119 0.463074 -0.451577 -0.84912 0.273995 -0.451581 -0.849119 0.27399 -0.528076 -0.849119 0.0114928 -0.528076 -0.849119 0.0114926 -0.463075 -0.84912 -0.25408 -0.463074 -0.849119 -0.254085 -0.273983 -0.849118 -0.451588 -0.273991 -0.849119 -0.451581 0.0310175 -0.851305 0.523754 0.0310221 -0.851305 0.523753 -0.199304 -0.851305 0.485344 -0.199299 -0.851305 0.485344 -0.390138 -0.851306 0.350814 -0.390145 -0.851305 0.350808 -0.50372 -0.851305 0.146787 -0.503718 -0.851305 0.14679 -0.517524 -0.851307 -0.086286 -0.517524 -0.851305 -0.0863027 -0.428828 -0.851305 -0.302302 -0.428828 -0.851305 -0.302302 -0.255186 -0.851304 -0.458434 -0.255197 -0.851305 -0.458426 0.0114928 -0.849119 0.528076 -0.273991 -0.849119 -0.451581 -0.27399 -0.849119 -0.451583 -0.437346 -0.853125 -0.284439 -0.453158 -0.856058 -0.248623 -0.514531 -0.857399 0.011198 -0.517171 -0.854596 -0.046903 -0.49073 -0.856529 -0.159817 -0.440002 -0.857399 0.266956 -0.477433 -0.855727 0.199471 -0.509848 -0.855727 0.0882353 0.0114925 -0.849119 0.528076 -0.216079 -0.853126 0.474854 -0.248639 -0.856057 0.45315 -0.328053 -0.856529 0.39842 -0.411015 -0.854596 0.317384 0.0310398 -0.851307 0.523749 0.031021 -0.851305 0.523753 -0.199304 -0.851305 0.485344 -0.199299 -0.851305 0.485345 -0.390136 -0.851306 0.350815 -0.390145 -0.851305 0.350808 -0.50372 -0.851305 0.146787 -0.503719 -0.851305 0.14679 -0.517524 -0.851305 -0.0863074 -0.517524 -0.851305 -0.0863027 -0.428828 -0.851305 -0.302302 -0.428828 -0.851305 -0.302302 -0.255195 -0.851305 -0.458428 -0.255197 -0.851305 -0.458426 0.0114932 -0.849119 0.528076 0.0114926 -0.849119 0.528076 -0.25408 -0.84912 0.463075 -0.254085 -0.849119 0.463074 -0.451577 -0.84912 0.273995 -0.451581 -0.849119 0.273991 -0.528076 -0.849119 0.0114928 -0.528076 -0.849119 0.0114926 -0.46307 -0.849118 -0.254096 -0.463073 -0.849119 -0.254086 -0.27399 -0.849119 -0.451582 -0.273991 -0.849119 -0.451581 0.0114928 -0.84912 0.528075 0.0114926 -0.84912 0.528075 -0.254065 -0.849122 0.463079 -0.254086 -0.849119 0.463073 -0.451582 -0.849119 0.27399 -0.451581 -0.849119 0.273991 -0.528076 -0.849119 0.0114922 -0.528076 -0.849119 0.0114924 -0.463074 -0.84912 -0.254084 -0.463073 -0.849119 -0.254085 -0.273984 -0.849118 -0.451587 -0.27399 -0.849119 -0.451582 0.0310175 -0.851305 0.523754 -0.255197 -0.851305 -0.458426 -0.255186 -0.851304 -0.458435 -0.358634 -0.857008 -0.370026 -0.424221 -0.854761 -0.299032 -0.508638 -0.856792 -0.0848255 -0.490729 -0.856529 -0.159819 -0.437345 -0.853126 -0.284439 -0.494003 -0.85746 0.143955 -0.509849 -0.855727 0.0882314 -0.517172 -0.854596 -0.0468999 -0.38345 -0.856791 0.344782 -0.411014 -0.854596 0.317386 -0.477432 -0.855727 0.199472 0.031021 -0.851305 0.523753 -0.103707 -0.857008 0.504759 -0.197138 -0.854764 0.480121 -0.21608 -0.853126 0.474854 -0.328053 -0.856529 0.398421 0.0310187 -0.851305 0.523754 0.031021 -0.851305 0.523753 -0.199304 -0.851305 0.485344 -0.199299 -0.851305 0.485345 -0.390138 -0.851306 0.350814 -0.390144 -0.851305 0.350809 -0.503711 -0.851307 0.146805 -0.503719 -0.851305 0.146788 -0.517525 -0.851304 -0.0863075 -0.517525 -0.851305 -0.0863017 -0.428828 -0.851305 -0.302302 -0.428828 -0.851305 -0.302302 -0.255195 -0.851305 -0.458428 -0.255198 -0.851305 -0.458425 0.0114922 -0.849119 0.528076 0.0114925 -0.849119 0.528076 -0.254084 -0.849119 0.463074 -0.254085 -0.849119 0.463074 -0.451587 -0.849118 0.273984 -0.451581 -0.849119 0.273991 -0.528076 -0.849119 0.0114928 -0.528076 -0.849119 0.0114926 -0.46307 -0.849118 -0.254097 -0.463073 -0.849119 -0.254085 -0.273989 -0.849119 -0.451582 -0.273991 -0.849119 -0.451581 0.0114928 -0.849119 0.528076 -0.273991 -0.849119 -0.451581 -0.273983 -0.849119 -0.451587 -0.437346 -0.853126 -0.284438 -0.453152 -0.856057 -0.248635 -0.514531 -0.857399 0.011198 -0.517171 -0.854596 -0.0469 -0.49073 -0.856529 -0.159817 -0.440003 -0.857399 0.266955 -0.477431 -0.855727 0.199475 -0.509849 -0.855727 0.0882313 0.0114926 -0.849119 0.528076 -0.216079 -0.853126 0.474854 -0.248636 -0.856056 0.453153 -0.328053 -0.856529 0.398421 -0.411015 -0.854596 0.317384 0.0114928 -0.849119 0.528076 0.0114926 -0.849119 0.528076 -0.25408 -0.84912 0.463075 -0.254085 -0.849119 0.463074 -0.451577 -0.84912 0.273995 -0.451581 -0.849119 0.273991 -0.528076 -0.849119 0.0114928 -0.528076 -0.849119 0.0114926 -0.46307 -0.849118 -0.254096 -0.463073 -0.849119 -0.254086 -0.27399 -0.849119 -0.451582 -0.27399 -0.849119 -0.451581 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0114925 -0.849123 0.52807 0.0114914 -0.849122 0.528072 -0.254083 -0.849122 0.463071 -0.254083 -0.849122 0.463071 -0.451577 -0.849122 0.27399 -0.451578 -0.849121 0.273989 -0.528074 -0.849121 0.0114893 -0.528072 -0.849122 0.0114914 -0.463071 -0.849122 -0.254083 -0.463071 -0.849122 -0.254083 -0.27399 -0.849122 -0.451577 -0.273989 -0.849121 -0.451578 0.0114958 -0.849123 0.52807 0.0114914 -0.84912 0.528075 -0.254086 -0.84912 0.463072 -0.254083 -0.849122 0.463071 -0.451577 -0.849122 0.27399 -0.451579 -0.849121 0.27399 -0.528072 -0.849122 0.0114925 -0.528073 -0.849121 0.0114915 -0.463073 -0.84912 -0.254084 -0.463073 -0.849121 -0.254082 -0.273986 -0.849121 -0.451581 -0.273987 -0.849123 -0.451577 0.0114925 -0.849123 0.52807 0.0114913 -0.849122 0.528072 -0.254081 -0.849123 0.46307 -0.254083 -0.849122 0.463071 -0.451579 -0.849122 0.273988 -0.451576 -0.849123 0.273988 -0.52807 -0.849123 0.0114925 -0.528072 -0.849122 0.0114914 -0.463071 -0.849122 -0.254083 -0.463072 -0.84912 -0.254086 -0.273991 -0.849121 -0.451578 -0.273991 -0.849121 -0.451578 0.0310212 -0.851308 0.523749 0.0310209 -0.851307 0.523749 -0.199299 -0.851308 0.485341 -0.199298 -0.851308 0.48534 -0.390142 -0.851308 0.350805 -0.390141 -0.851308 0.350805 -0.503711 -0.851309 0.146792 -0.503718 -0.851306 0.146788 -0.517524 -0.851305 -0.0863014 -0.517526 -0.851304 -0.0863037 -0.428827 -0.851305 -0.302305 -0.428825 -0.851309 -0.302295 -0.255197 -0.851309 -0.458419 -0.255195 -0.851306 -0.458425 0.0310212 -0.851308 0.523749 -0.255196 -0.851308 -0.45842 -0.255194 -0.851306 -0.458426 -0.358619 -0.857009 -0.370038 -0.414578 -0.861809 -0.292252 -0.490417 -0.867642 -0.0817811 -0.490725 -0.856532 -0.15982 -0.437343 -0.853129 -0.284434 -0.474185 -0.869514 0.13818 -0.509843 -0.855731 0.0882278 -0.517165 -0.8546 -0.0468993 -0.369711 -0.867641 0.332435 -0.41101 -0.854599 0.317384 -0.477427 -0.85573 0.199472 0.0310209 -0.851307 0.523749 -0.103708 -0.85701 0.504756 -0.192677 -0.861808 0.469215 -0.216077 -0.853128 0.47485 -0.328052 -0.856532 0.398416 0.0114926 -0.849121 0.528073 0.0114914 -0.84912 0.528075 -0.254085 -0.849121 0.463071 -0.254083 -0.849122 0.463071 -0.451579 -0.849122 0.273988 -0.451576 -0.849123 0.273988 -0.52807 -0.849123 0.0114925 -0.528072 -0.849122 0.0114914 -0.463071 -0.849122 -0.254083 -0.463072 -0.84912 -0.254086 -0.273988 -0.849121 -0.45158 -0.273989 -0.849123 -0.451576 0.0310215 -0.851305 0.523753 0.0310248 -0.851307 0.52375 -0.199301 -0.851307 0.48534 -0.199296 -0.851309 0.485338 -0.390139 -0.851309 0.350805 -0.390146 -0.851306 0.350805 -0.503715 -0.851307 0.14679 -0.503715 -0.851307 0.14679 -0.517521 -0.851307 -0.0863025 -0.517521 -0.851307 -0.0863032 -0.428827 -0.851307 -0.302297 -0.428828 -0.851306 -0.302299 -0.255195 -0.851305 -0.458427 -0.255197 -0.851308 -0.45842 0.0114926 -0.849121 0.528073 0.0114914 -0.84912 0.528075 -0.254087 -0.84912 0.463072 -0.254083 -0.849122 0.463071 -0.451577 -0.849122 0.27399 -0.451578 -0.849121 0.273989 -0.528073 -0.849121 0.0114926 -0.528075 -0.84912 0.0114914 -0.463072 -0.84912 -0.254087 -0.463071 -0.849122 -0.254083 -0.27399 -0.849122 -0.451577 -0.273989 -0.849121 -0.451578 0.0310211 -0.851308 0.523749 0.0310208 -0.851308 0.523749 -0.199298 -0.851306 0.485343 -0.199297 -0.851307 0.485343 -0.390143 -0.851307 0.350806 -0.390147 -0.851305 0.350805 -0.50372 -0.851305 0.146787 -0.503712 -0.851308 0.146792 -0.517518 -0.851309 -0.0863001 -0.51752 -0.851308 -0.086303 -0.428826 -0.851308 -0.302297 -0.428827 -0.851306 -0.302301 -0.255194 -0.851306 -0.458426 -0.255195 -0.851307 -0.458423 0.0114926 -0.849122 0.528072 0.0114926 -0.849122 0.528072 -0.254082 -0.849123 0.463069 -0.254083 -0.849122 0.46307 -0.451577 -0.849122 0.27399 -0.451576 -0.849122 0.27399 -0.528071 -0.849122 0.0114892 -0.528069 -0.849124 0.0114913 -0.463069 -0.849124 -0.254077 -0.463071 -0.849121 -0.254083 -0.273987 -0.849121 -0.451581 -0.273988 -0.849123 -0.451576 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.3581 0 -0.933683 -0.3581 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817205 0 0.576348 -0.817205 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129445 0 0.991587 -0.129445 0 0.991587 0.0355312 0 0.999369 0.0355312 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 -0.37253 0 -0.92802 -0.37253 0 -0.92802 -0.546419 0 -0.837512 -0.546419 0 -0.837512 -0.699311 0 -0.714818 -0.699311 0 -0.714818 -0.825328 0 -0.564654 -0.825328 0 -0.564654 -0.919628 0 -0.392791 -0.919628 0 -0.392791 -0.978587 0 -0.205833 -0.978587 0 -0.205833 -0.99994 0 -0.0109654 -0.99994 0 -0.0109654 -0.982866 0 0.184324 -0.982866 0 0.184324 -0.92802 0 0.37253 -0.92802 0 0.37253 -0.837512 0 0.54642 -0.837512 0 0.54642 -0.714818 0 0.699311 -0.714818 0 0.699311 -0.564654 0 0.825328 -0.564654 0 0.825328 -0.392791 0 0.919628 -0.392791 0 0.919628 -0.205833 0 0.978587 -0.205833 0 0.978587 -0.0109654 0 0.99994 -0.0109654 0 0.99994 0.184324 0 0.982866 0.184324 0 0.982866 0.0591247 0 0.998251 0.0217546 -0.0178262 0.999604 -0.201255 0 0.979539 -0.414177 0 0.910196 -0.480828 -0.0297593 0.87631 -0.635648 0 0.771979 -0.791489 0 0.611184 -0.854395 -0.0357349 0.518394 -0.922702 0 0.385513 -0.985354 0 0.17052 -0.999125 -0.0357359 0.0217418 -0.995913 0 -0.090319 -0.950848 0 -0.309658 -0.876311 -0.0297591 -0.480825 -0.486391 0 -0.873741 -0.518641 -0.0178278 -0.854806 -0.69597 0 -0.718071 -0.838298 0 -0.545212 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.021758 0 0.999763 0.059112 0.020733 0.998036 -0.414114 -0.0178277 0.91005 -0.379855 0 0.925046 -0.635639 0 0.771986 -0.743389 -0.0238609 0.668434 -0.791489 0 0.611184 -0.922703 0 0.385511 -0.959719 -0.0268539 0.279674 -0.985354 0 0.17052 -0.995913 0 -0.0903149 -0.986098 -0.0238608 -0.164442 -0.950845 0 -0.309667 -0.838302 0 -0.545206 -0.817236 -0.0148962 -0.57611 -0.51864 0.0178249 -0.854807 -0.486396 0 -0.873739 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0217578 0 0.999763 0.0591124 0.0207332 0.998036 -0.414111 -0.017826 0.910052 -0.379855 0 0.925046 -0.635646 0 0.771981 -0.743388 -0.0238591 0.668435 -0.791485 0 0.611189 -0.922707 0 0.385502 -0.959721 -0.0268528 0.279669 -0.985354 0 0.170519 -0.995913 0 -0.0903148 -0.986098 -0.0238609 -0.164442 -0.950845 0 -0.309667 -0.838301 0 -0.545207 -0.817239 -0.0148939 -0.576106 -0.518643 0.0178269 -0.854805 -0.486394 0 -0.873739 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.373098 0.694742 -0.614923 -0.373093 0.694749 -0.614919 -0.630571 0.694746 -0.345989 -0.630569 0.694747 -0.345989 -0.71908 0.694751 0.0156489 -0.719085 0.694746 0.0156507 -0.614925 0.694741 0.373098 -0.61492 0.694749 0.373092 -0.345989 0.694746 0.630571 -0.34599 0.69474 0.630577 0.0156491 0.694742 0.719089 0.0156508 0.694737 0.719094 0.0217572 0 0.999763 0.0217572 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217572 -0.999763 0 0.0217572 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518726 0 -0.85494 -0.518726 0 -0.85494 0.0156491 -0.694741 0.71909 0.0156497 -0.694742 0.719089 -0.345991 -0.694741 0.630575 -0.34599 -0.694743 0.630574 -0.614924 -0.694743 0.373097 -0.614924 -0.694742 0.373097 -0.719085 -0.694746 0.015649 -0.719084 -0.694747 0.0156496 -0.630571 -0.694746 -0.345989 -0.630571 -0.694746 -0.345989 -0.373096 -0.694748 -0.614919 -0.373096 -0.694744 -0.614924 -0.373093 0.69475 -0.614917 -0.373094 0.694749 -0.614918 -0.630571 0.694746 -0.345989 -0.630562 0.694755 -0.345988 -0.719071 0.69476 0.0156487 -0.719076 0.694756 0.0156504 -0.614916 0.694754 0.373089 -0.614929 0.694734 0.373105 -0.345993 0.694737 0.630579 -0.345992 0.694747 0.630568 0.0156489 0.694751 0.71908 0.0156505 0.694746 0.719084 0.0217572 0 0.999763 0.0217572 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854943 0 0.518722 -0.854943 0 0.518722 -0.999763 0 0.0217572 -0.999763 0 0.0217572 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.015649 -0.694746 0.719085 0.0156495 -0.694747 0.719084 -0.345989 -0.694746 0.630571 -0.345994 -0.694741 0.630574 -0.614929 -0.694738 0.373097 -0.614916 -0.694749 0.373097 -0.719079 -0.694752 0.0156489 -0.719078 -0.694753 0.0156495 -0.630567 -0.694751 -0.345987 -0.630571 -0.694743 -0.345994 -0.373097 -0.694743 -0.614924 -0.373097 -0.694748 -0.614918 -0.348266 0.69808 -0.625615 -0.348271 0.698075 -0.625619 -0.585229 0.698073 -0.412554 -0.58522 0.698082 -0.412552 -0.706264 0.698083 -0.117775 -0.706261 0.698087 -0.117776 -0.68742 0.698086 0.200322 -0.687424 0.698082 0.200325 -0.532432 0.69808 0.478749 -0.532433 0.698078 0.478751 -0.271987 0.698077 0.662353 -0.271987 0.698072 0.662358 0.0423344 0.698077 0.71477 0.042335 0.698076 0.714771 0.0591244 0 0.998251 0.0591244 0 0.998251 -0.379858 0 0.925045 -0.379858 0 0.925045 -0.743599 0 0.668625 -0.743599 0 0.668625 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164486 -0.986379 0 -0.164486 -0.817329 0 -0.576172 -0.817329 0 -0.576172 -0.486392 0 -0.873741 -0.486392 0 -0.873741 0.0423347 -0.698073 0.714774 0.0423352 -0.698073 0.714774 -0.271989 -0.698072 0.662358 -0.271984 -0.698076 0.662355 -0.532432 -0.69808 0.478749 -0.532438 -0.698075 0.47875 -0.687431 -0.698075 0.200325 -0.68743 -0.698076 0.200326 -0.706271 -0.698076 -0.117776 -0.706277 -0.698069 -0.117782 -0.585232 -0.69807 -0.412556 -0.585232 -0.69807 -0.412556 -0.348271 -0.698071 -0.625623 -0.348271 -0.698075 -0.625619 -0.348266 -0.698082 -0.625614 -0.348267 -0.698077 -0.625618 -0.492294 -0.706863 -0.507927 -0.553018 -0.673 -0.491164 -0.50705 -0.815779 -0.278217 -0.59796 -0.700857 -0.3889 -0.673294 -0.706114 -0.219268 -0.830497 -0.539531 -0.138494 -0.708161 -0.703124 -0.0642229 -0.698945 -0.704872 0.120955 -0.823671 -0.513764 0.240026 -0.654498 -0.704879 0.273455 -0.532432 -0.698081 0.478747 -0.719956 -0.415436 0.555946 -0.4501 -0.706116 0.546635 -0.271986 -0.698075 0.662356 0.0423352 -0.698067 0.71478 0.0423371 -0.698075 0.714772 -0.142358 -0.706861 0.692879 -0.336705 -0.582334 0.739944 -0.373096 -0.694745 -0.614921 -0.373098 -0.694738 -0.614928 -0.630578 -0.694737 -0.345996 -0.787825 -0.341763 -0.512378 -0.673287 -0.706119 -0.219274 -0.708159 -0.703127 -0.0642197 -0.906435 -0.421885 0.0197255 -0.698938 -0.70488 0.120954 -0.654497 -0.704881 0.273453 -0.77513 -0.42189 0.4703 0.0156495 -0.694746 0.719085 0.0156485 -0.694742 0.719089 -0.295435 -0.700858 0.649243 -0.421646 -0.481341 0.768457 -0.450091 -0.706121 0.546636 -0.562797 -0.70313 0.434589 -0.373095 -0.694746 -0.614921 -0.373094 -0.694749 -0.614918 -0.630568 -0.69475 -0.345987 -0.787826 -0.341757 -0.512379 -0.673288 -0.706118 -0.219274 -0.708159 -0.703126 -0.0642197 -0.906435 -0.421885 0.0197256 -0.698939 -0.704879 0.120954 -0.654501 -0.704879 0.273447 -0.77514 -0.421864 0.470307 0.0156494 -0.694748 0.719083 0.0156493 -0.694748 0.719083 -0.29543 -0.700864 0.649239 -0.42165 -0.481331 0.768461 -0.450096 -0.706119 0.546635 -0.562796 -0.703128 0.434594 0.0156475 0.694753 0.719078 0.0156488 0.694749 0.719082 -0.345988 0.69475 0.630567 -0.376227 0.418159 0.826799 -0.450094 0.706106 0.546652 -0.562807 0.703116 0.434598 -0.749516 0.48106 0.45476 -0.654506 0.704872 0.273453 -0.698945 0.704873 0.120956 -0.876473 0.481074 0.0190749 -0.373095 0.694751 -0.614916 -0.373094 0.694752 -0.614915 -0.597953 0.700867 -0.388893 -0.745571 0.526089 -0.40909 -0.673287 0.706119 -0.219275 -0.708159 0.703127 -0.0642207 0.0591303 0 0.99825 0.0217565 -0.00717367 0.999738 -0.379852 0.00599163 0.925028 -0.414177 0 0.910196 -0.635632 0 0.771992 -0.743564 0.00960175 0.668596 -0.791488 0 0.611185 -0.922705 0 0.385506 -0.96001 0.0108063 0.279757 -0.985354 0 0.170521 -0.995913 0 -0.0903162 -0.986333 0.00960149 -0.164483 -0.950844 0 -0.30967 -0.817329 0 -0.576171 -0.838279 0.00717213 -0.545195 -0.486378 -0.0083429 -0.873708 -0.518727 0 -0.85494 0.0423383 -0.698083 0.714764 0.0423322 -0.698069 0.714778 -0.27199 -0.69807 0.662359 -0.271984 -0.698077 0.662354 -0.532432 -0.698078 0.478751 -0.532439 -0.698072 0.478753 -0.687431 -0.698075 0.200325 -0.68743 -0.698076 0.200325 -0.706268 -0.698079 -0.117778 -0.706268 -0.698079 -0.117778 -0.585225 -0.698079 -0.412551 -0.585226 -0.698076 -0.412553 -0.348271 -0.698075 -0.625619 -0.348271 -0.698073 -0.625621 -0.373096 0.694745 -0.614921 -0.373091 0.694752 -0.614917 -0.630566 0.694752 -0.345987 -0.630568 0.69475 -0.345988 -0.719082 0.694749 0.0156489 -0.719078 0.694753 0.0156475 -0.614913 0.694755 0.373092 -0.614918 0.694749 0.373096 -0.345991 0.694746 0.63057 -0.34599 0.694749 0.630567 0.0156489 0.694749 0.719082 0.0156496 0.694746 0.719085 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.854941 0 0.518726 -0.854941 0 0.518726 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0156489 -0.694746 0.719085 0.0156489 -0.694746 0.719085 -0.34599 -0.694748 0.630569 -0.345988 -0.69475 0.630567 -0.614916 -0.694752 0.373093 -0.61492 -0.694748 0.373094 -0.719085 -0.694746 0.0156489 -0.719081 -0.694751 0.0156507 -0.630566 -0.694752 -0.345987 -0.630566 -0.694752 -0.345987 -0.373094 -0.69475 -0.614918 -0.373094 -0.69475 -0.614918 -0.373096 0.694745 -0.614921 -0.373096 0.694746 -0.614921 -0.630568 0.694749 -0.345989 -0.630567 0.69475 -0.345988 -0.719082 0.694749 0.0156488 -0.719078 0.694753 0.0156475 -0.614916 0.694751 0.373094 -0.614917 0.69475 0.373095 -0.345989 0.694749 0.630568 -0.345988 0.69475 0.630567 0.0156489 0.694749 0.719082 0.0156496 0.694746 0.719085 0.0591236 0 0.998251 0.0217566 -0.00717238 0.999738 -0.201256 0 0.979539 -0.414178 0 0.910196 -0.481005 -0.011976 0.876636 -0.635643 0 0.771984 -0.791484 0 0.61119 -0.854852 -0.0143847 0.518673 -0.922706 0 0.385505 -0.985353 0 0.170526 -0.99966 -0.0143847 0.0217548 -0.995913 0 -0.0903212 -0.950845 0 -0.309667 -0.876636 -0.0119759 -0.481004 -0.486394 0 -0.87374 -0.518712 -0.00717277 -0.854919 -0.695971 0 -0.71807 -0.8383 0 -0.545209 -0.348269 -0.698073 -0.625622 -0.348269 -0.698076 -0.625618 -0.492297 -0.706861 -0.507928 -0.619965 -0.65164 -0.437045 -0.59795 -0.70087 -0.388891 -0.673281 -0.706125 -0.219271 -0.774255 -0.619564 -0.129111 -0.708165 -0.70312 -0.0642248 -0.687437 -0.698069 0.200325 -0.871116 -0.467365 0.150756 -0.654506 -0.704873 0.273452 -0.532436 -0.698075 0.478752 -0.654972 -0.56143 0.505774 -0.450093 -0.70612 0.546635 -0.271985 -0.698078 0.662353 0.0423339 -0.698076 0.714771 0.0423348 -0.698078 0.714769 -0.142359 -0.706863 0.692877 -0.319131 -0.63742 0.701321 -0.373095 0.694747 -0.61492 -0.373094 0.694749 -0.614919 -0.630567 0.69475 -0.345988 -0.630569 0.694748 -0.345989 -0.719082 0.694749 0.0156488 -0.719078 0.694753 0.0156475 -0.614915 0.694752 0.373094 -0.614916 0.69475 0.373095 -0.345989 0.694749 0.630568 -0.345989 0.694748 0.630568 0.0156493 0.694747 0.719084 0.0156494 0.694747 0.719084 0.0217577 0 0.999763 0.0217577 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0156493 -0.694749 0.719082 0.0156492 -0.694749 0.719082 -0.345988 -0.69475 0.630566 -0.345988 -0.694751 0.630566 -0.614915 -0.694752 0.373094 -0.614921 -0.694747 0.373094 -0.719085 -0.694746 0.0156489 -0.71908 -0.694751 0.0156507 -0.630567 -0.69475 -0.345988 -0.630565 -0.694753 -0.345986 -0.373093 -0.694752 -0.614916 -0.373093 -0.694749 -0.614919 0.021758 0 0.999763 0.059112 0.0207329 0.998036 -0.414112 -0.0178267 0.910051 -0.379855 0 0.925046 -0.635638 0 0.771987 -0.743388 -0.0238606 0.668435 -0.791487 0 0.611186 -0.922704 0 0.385509 -0.959719 -0.0268533 0.279674 -0.985354 0 0.170522 -0.995913 0 -0.0903165 -0.986098 -0.0238605 -0.164442 -0.950845 0 -0.309667 -0.8383 0 -0.545209 -0.817237 -0.0148949 -0.57611 -0.518642 0.0178257 -0.854806 -0.486396 0 -0.873739 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.021758 0 0.999763 0.021758 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854943 0 0.518723 -0.854943 0 0.518723 -0.999763 0 0.0217581 -0.999763 0 0.0217581 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0591247 0 0.998251 0.0591247 0 0.998251 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.7436 0 0.668624 -0.7436 0 0.668624 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.373094 0.694754 -0.614913 -0.373095 0.694753 -0.614914 -0.630566 0.694751 -0.345988 -0.630562 0.694755 -0.345987 -0.719082 0.694749 0.0156494 -0.719081 0.69475 0.0156492 -0.614915 0.694753 0.373092 -0.614913 0.694756 0.37309 -0.345987 0.694761 0.630555 -0.34599 0.694743 0.630574 0.0156558 0.694741 0.71909 0.0156504 0.694756 0.719076 0.0591346 0 0.99825 0.0217657 -0.008894 0.999724 -0.201253 0 0.979539 -0.414178 0 0.910196 -0.480992 -0.014851 0.876599 -0.635657 0 0.771972 -0.791485 0 0.611188 -0.854805 -0.0178358 0.518642 -0.922705 0 0.385506 -0.985354 0 0.170523 -0.999604 -0.0178355 0.0217544 -0.995913 0 -0.0903175 -0.950846 0 -0.309664 -0.876602 -0.0148498 -0.480986 -0.486394 0 -0.873739 -0.518708 -0.00889484 -0.854905 -0.69598 0 -0.718061 -0.838299 0 -0.54521 -0.348271 -0.698069 -0.625625 -0.348272 -0.698072 -0.625621 -0.492305 -0.706858 -0.507925 -0.610925 -0.6643 -0.43067 -0.597956 -0.700862 -0.388897 -0.673291 -0.706116 -0.219272 -0.75646 -0.64176 -0.126148 -0.708161 -0.703124 -0.0642218 -0.687432 -0.698073 0.200325 -0.831838 -0.536024 0.143956 -0.654505 -0.704874 0.273452 -0.532436 -0.698075 0.478751 -0.633374 -0.599688 0.489094 -0.450106 -0.706115 0.546631 -0.271984 -0.698073 0.662359 0.0423415 -0.69808 0.714767 0.0423351 -0.698069 0.714778 -0.142358 -0.706855 0.692886 -0.313599 -0.653231 0.689163 0.0423355 0.698082 0.714765 0.0423334 0.698087 0.71476 -0.142357 0.706872 0.692869 -0.292109 0.639258 0.711352 -0.295431 0.700866 0.649236 -0.450085 0.706121 0.546642 -0.596382 0.597295 0.536253 -0.562799 0.703127 0.434592 -0.654499 0.704878 0.273455 -0.780662 0.582078 0.227492 -0.698942 0.704876 0.120952 -0.706268 0.698079 -0.117777 -0.8495 0.521935 -0.0770341 -0.673292 0.706114 -0.219273 -0.585232 0.69807 -0.412556 -0.348268 0.698081 -0.625614 -0.348264 0.698085 -0.625612 -0.492274 0.706871 -0.507937 -0.656519 0.621823 -0.426988 0.0591238 0 0.998251 0.0217564 0.00889363 0.999724 -0.201256 0 0.979539 -0.414178 0 0.910196 -0.480983 0.014849 0.876604 -0.635631 0 0.771993 -0.791488 0 0.611185 -0.854805 0.0178351 0.518642 -0.922702 0 0.385513 -0.985355 0 0.170515 -0.999604 0.0178346 0.0217537 -0.995914 0 -0.0903111 -0.950846 0 -0.309664 -0.876601 0.01485 -0.480989 -0.838297 0 -0.545213 -0.695948 0 -0.718092 -0.518701 0.008893 -0.854909 -0.486394 0 -0.873739 0.0156489 -0.694752 0.719079 0.0156495 -0.694753 0.719078 -0.345984 -0.694753 0.630565 -0.345994 -0.694743 0.630571 -0.614924 -0.694743 0.373097 -0.614923 -0.694743 0.373097 -0.71909 -0.694741 0.0156491 -0.719089 -0.694742 0.0156496 -0.630574 -0.69474 -0.345994 -0.630571 -0.694745 -0.34599 -0.373096 -0.694741 -0.614927 -0.373096 -0.694752 -0.614914 -0.348275 0.698068 -0.625624 -0.348272 0.698073 -0.625621 -0.585231 0.698072 -0.412553 -0.585221 0.698082 -0.412551 -0.706262 0.698084 -0.117783 -0.706278 0.698068 -0.117779 -0.687436 0.69807 0.200327 -0.68744 0.698065 0.20033 -0.532441 0.698068 0.478757 -0.532436 0.698078 0.478748 -0.271984 0.698077 0.662354 -0.271984 0.69808 0.662351 0.0423342 0.698077 0.71477 0.0423358 0.698074 0.714773 0.0591241 0 0.998251 0.0591241 0 0.998251 -0.379854 0 0.925047 -0.379854 0 0.925047 -0.743599 0 0.668625 -0.743599 0 0.668625 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986378 0 -0.164497 -0.986378 0 -0.164497 -0.81733 0 -0.57617 -0.81733 0 -0.57617 -0.486397 0 -0.873738 -0.486397 0 -0.873738 0.0423344 -0.698074 0.714774 0.0423346 -0.698074 0.714773 -0.271984 -0.698077 0.662354 -0.271988 -0.698073 0.662357 -0.532438 -0.698072 0.478754 -0.532433 -0.698076 0.478754 -0.68743 -0.698076 0.200325 -0.68743 -0.698076 0.200325 -0.706271 -0.698075 -0.117784 -0.706266 -0.69808 -0.11778 -0.585225 -0.69808 -0.412549 -0.585225 -0.698078 -0.412551 -0.348271 -0.698076 -0.625617 -0.348271 -0.69807 -0.625624 -0.373096 -0.694741 -0.614927 -0.373093 -0.69475 -0.614918 -0.630569 -0.694749 -0.345987 -0.78783 -0.34174 -0.512384 -0.673292 -0.706113 -0.219275 -0.708161 -0.703124 -0.0642211 -0.906442 -0.42187 0.0197268 -0.698944 -0.704874 0.120957 -0.654505 -0.704873 0.273455 -0.775137 -0.421873 0.470304 0.0156494 -0.694753 0.719078 0.0156485 -0.694749 0.719082 -0.295431 -0.700864 0.649238 -0.421645 -0.481343 0.768456 -0.450091 -0.706119 0.546639 -0.562798 -0.703127 0.434592 0.0156494 -0.694753 0.719078 0.0156485 -0.694749 0.719082 -0.345989 -0.694746 0.63057 -0.345994 -0.69474 0.630575 -0.614923 -0.694744 0.373095 -0.614915 -0.694753 0.373093 -0.719084 -0.694747 0.0156496 -0.719083 -0.694748 0.01565 -0.630568 -0.69475 -0.345988 -0.63057 -0.694746 -0.34599 -0.373094 -0.694748 -0.61492 -0.373093 -0.694751 -0.614917 0.0423349 -0.698073 0.714774 0.0423353 -0.698075 0.714772 -0.271984 -0.698078 0.662353 -0.271985 -0.698077 0.662354 -0.532433 -0.698079 0.478749 -0.53244 -0.698071 0.478752 -0.687435 -0.698071 0.200327 -0.687424 -0.698081 0.200327 -0.706268 -0.698079 -0.117778 -0.706278 -0.698067 -0.117783 -0.585232 -0.698067 -0.412559 -0.585229 -0.698072 -0.412555 -0.34827 -0.698074 -0.62562 -0.348269 -0.698079 -0.625616 0.0423323 0.69808 0.714767 0.0423339 0.698076 0.714771 -0.142357 0.706861 0.692879 -0.296451 0.625239 0.721937 -0.295431 0.700863 0.649239 -0.450097 0.706117 0.546637 -0.610185 0.571527 0.548662 -0.562797 0.703129 0.434591 -0.654502 0.704876 0.273453 -0.800716 0.551732 0.233338 -0.698942 0.704876 0.120956 -0.706275 0.698072 -0.117779 -0.876364 0.475046 -0.0794761 -0.673293 0.706114 -0.21927 -0.585232 0.698069 -0.412557 -0.348269 0.698079 -0.625615 -0.348271 0.698076 -0.625617 -0.492281 0.706861 -0.507944 -0.668095 0.604026 -0.434512 0.0591236 0 0.998251 0.0217565 0.00717239 0.999738 -0.201253 0 0.979539 -0.414177 0 0.910196 -0.481005 0.0119763 0.876636 -0.635644 0 0.771982 -0.791487 0 0.611186 -0.854853 0.0143842 0.518671 -0.922704 0 0.385509 -0.985354 0 0.170521 -0.99966 0.0143842 0.0217556 -0.995913 0 -0.0903178 -0.950847 0 -0.309661 -0.876637 0.0119763 -0.481003 -0.8383 0 -0.545209 -0.695949 0 -0.718092 -0.518709 0.00717191 -0.854921 -0.486395 0 -0.873739 0.0156489 -0.694746 0.719085 0.0156507 -0.694751 0.71908 -0.345988 -0.69475 0.630567 -0.345986 -0.694753 0.630565 -0.614916 -0.694752 0.373093 -0.614919 -0.694749 0.373093 -0.719081 -0.69475 0.0156494 -0.719081 -0.69475 0.0156494 -0.630567 -0.694751 -0.345986 -0.63057 -0.694747 -0.34599 -0.373095 -0.694744 -0.614924 -0.373093 -0.694754 -0.614913 -0.373089 0.694755 -0.614915 -0.373094 0.694748 -0.61492 -0.630571 0.694746 -0.345989 -0.630567 0.69475 -0.345988 -0.719083 0.694748 0.015651 -0.719078 0.694753 0.0156495 -0.614917 0.694751 0.373093 -0.614916 0.694752 0.373093 -0.345988 0.694752 0.630565 -0.345989 0.694746 0.63057 0.0156488 0.694749 0.719082 0.0156476 0.694753 0.719078 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.02176 -0.999763 0 0.02176 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518722 0 -0.854943 -0.518722 0 -0.854943 0.0156489 -0.694746 0.719085 0.0156507 -0.694751 0.71908 -0.345989 -0.694749 0.630567 -0.345985 -0.694754 0.630564 -0.614914 -0.694754 0.373092 -0.614919 -0.69475 0.373092 -0.71908 -0.694751 0.0156509 -0.719085 -0.694746 0.015649 -0.630569 -0.694748 -0.345988 -0.630571 -0.694746 -0.34599 -0.373095 -0.694743 -0.614925 -0.373093 -0.694756 -0.614912 -0.373091 0.694752 -0.614917 -0.3731 0.69474 -0.614925 -0.630572 0.694745 -0.345989 -0.630567 0.69475 -0.345988 -0.719082 0.694749 0.0156489 -0.719085 0.694746 0.0156496 -0.614921 0.694745 0.373096 -0.614921 0.694746 0.373096 -0.345989 0.694748 0.630568 -0.345988 0.69475 0.630567 0.0156488 0.694749 0.719082 0.0156475 0.694753 0.719078 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518723 0 -0.854942 -0.518723 0 -0.854942 0.0156489 -0.694746 0.719085 0.0156507 -0.694751 0.719081 -0.345987 -0.694752 0.630566 -0.345987 -0.694752 0.630566 -0.614918 -0.69475 0.373094 -0.614922 -0.694746 0.373094 -0.719085 -0.694746 0.0156489 -0.71908 -0.694751 0.0156507 -0.630566 -0.694752 -0.345986 -0.63057 -0.694746 -0.345991 -0.373095 -0.694744 -0.614924 -0.373094 -0.694753 -0.614914 -0.373094 0.694746 -0.614922 -0.373099 0.694739 -0.614927 -0.630581 0.694736 -0.345991 -0.630567 0.69475 -0.345988 -0.719082 0.694749 0.0156488 -0.719078 0.694753 0.0156475 -0.614917 0.694752 0.373091 -0.614917 0.694752 0.373091 -0.345986 0.694752 0.630566 -0.345987 0.69475 0.630568 0.0156489 0.694749 0.719082 0.0156496 0.694746 0.719085 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854942 0 0.518723 -0.854942 0 0.518723 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876702 0 -0.481035 -0.876702 0 -0.481035 -0.518722 0 -0.854943 -0.518722 0 -0.854943 0.0156488 -0.694751 0.71908 0.0156489 -0.694751 0.71908 -0.345986 -0.694752 0.630566 -0.345988 -0.69475 0.630567 -0.614922 -0.694746 0.373094 -0.614914 -0.694753 0.373093 -0.719076 -0.694755 0.0156487 -0.71908 -0.694751 0.015647 -0.630569 -0.69475 -0.345985 -0.630573 -0.694744 -0.34599 -0.373094 -0.694745 -0.614923 -0.373094 -0.694746 -0.614922 0.021758 0 0.999763 0.021758 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217577 -0.999763 0 0.0217577 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0217532 0 0.999763 0.0217532 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.999763 0 0.0217557 -0.999763 0 0.0217557 -0.876701 0 -0.481036 -0.876701 0 -0.481036 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.0591247 0 0.998251 0.0217546 -0.0178262 0.999604 -0.201255 0 0.979539 -0.414177 0 0.910196 -0.480823 -0.0297571 0.876312 -0.635634 0 0.77199 -0.791489 0 0.611184 -0.854396 -0.0357353 0.518393 -0.922703 0 0.385511 -0.985354 0 0.17052 -0.999125 -0.0357353 0.0217442 -0.995913 0 -0.0903149 -0.950845 0 -0.309667 -0.87631 -0.0297578 -0.480828 -0.486394 0 -0.87374 -0.518643 -0.0178272 -0.854805 -0.69597 0 -0.718071 -0.838299 0 -0.545211 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.373089 0.694755 -0.614915 -0.373103 0.694737 -0.614927 -0.630575 0.694742 -0.345989 -0.630562 0.694755 -0.345987 -0.719082 0.694749 0.0156495 -0.719081 0.69475 0.0156491 -0.614915 0.694753 0.373092 -0.614913 0.694756 0.373089 -0.345982 0.694761 0.630559 -0.345982 0.694759 0.63056 0.0156487 0.69476 0.719071 0.0156504 0.694756 0.719076 0.0217573 0 0.999763 0.0217573 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.876701 0 -0.481035 -0.876701 0 -0.481035 -0.518721 0 -0.854943 -0.518721 0 -0.854943 0.0156489 -0.694752 0.719079 0.0156495 -0.694753 0.719078 -0.345986 -0.694752 0.630566 -0.345993 -0.694744 0.63057 -0.614922 -0.694745 0.373096 -0.614919 -0.694748 0.373096 -0.719085 -0.694746 0.0156495 -0.719085 -0.694746 0.0156494 -0.630568 -0.69475 -0.345985 -0.630573 -0.694742 -0.345993 -0.373097 -0.694739 -0.614928 -0.373097 -0.694742 -0.614925 -0.3731 0.694742 -0.614923 -0.373091 0.694754 -0.614915 -0.630562 0.694754 -0.345988 -0.630561 0.694756 -0.345988 -0.719081 0.694751 0.015649 -0.719084 0.694746 0.0156505 -0.614919 0.694751 0.37309 -0.614925 0.694741 0.373098 -0.345991 0.694741 0.630575 -0.345992 0.694739 0.630577 0.0156491 0.694742 0.719089 0.0156508 0.694737 0.719094 0.0217572 0 0.999763 0.0217572 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854944 0 0.518721 -0.854944 0 0.518721 -0.999763 0 0.0217574 -0.999763 0 0.0217574 -0.876698 0 -0.481042 -0.876698 0 -0.481042 -0.518728 0 -0.854939 -0.518728 0 -0.854939 0.0156491 -0.694741 0.71909 0.0156497 -0.694742 0.719089 -0.345991 -0.694741 0.630575 -0.34599 -0.694743 0.630574 -0.614926 -0.694742 0.373094 -0.614919 -0.694748 0.373094 -0.719085 -0.694746 0.0156491 -0.719084 -0.694747 0.0156496 -0.63057 -0.694745 -0.345992 -0.630567 -0.69475 -0.345987 -0.373096 -0.694751 -0.614915 -0.373096 -0.694744 -0.614924 -0.348275 0.698068 -0.625624 -0.348272 0.698073 -0.625621 -0.58523 0.698072 -0.412555 -0.58522 0.698082 -0.412553 -0.706262 0.698084 -0.117782 -0.706277 0.69807 -0.117779 -0.687438 0.698067 0.200328 -0.68744 0.698065 0.200329 -0.532441 0.698068 0.478757 -0.532436 0.698078 0.478748 -0.271984 0.698077 0.662354 -0.271984 0.69808 0.662351 0.0423342 0.698077 0.71477 0.0423358 0.698074 0.714773 0.0591241 0 0.998251 0.0591241 0 0.998251 -0.379854 0 0.925047 -0.379854 0 0.925047 -0.743599 0 0.668625 -0.743599 0 0.668625 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986378 0 -0.164496 -0.986378 0 -0.164496 -0.817328 0 -0.576172 -0.817328 0 -0.576172 -0.486397 0 -0.873738 -0.486397 0 -0.873738 0.0423344 -0.698074 0.714774 0.0423349 -0.698074 0.714773 -0.271986 -0.698073 0.662358 -0.271986 -0.698073 0.662358 -0.532438 -0.698072 0.478754 -0.532445 -0.698065 0.478755 -0.687441 -0.698064 0.200328 -0.687441 -0.698064 0.200329 -0.70628 -0.698065 -0.117785 -0.706268 -0.698079 -0.117774 -0.585224 -0.69808 -0.412551 -0.585228 -0.69807 -0.412561 -0.348274 -0.698071 -0.625622 -0.348274 -0.69807 -0.625623 0.0156494 -0.694753 0.719078 0.0156485 -0.694749 0.719082 -0.345988 -0.694749 0.630569 -0.345987 -0.69475 0.630568 -0.614918 -0.694749 0.373094 -0.614921 -0.694746 0.373095 -0.719084 -0.694747 0.0156493 -0.719084 -0.694747 0.0156493 -0.630574 -0.694741 -0.345992 -0.630569 -0.694749 -0.345987 -0.373093 -0.69475 -0.614918 -0.373096 -0.694741 -0.614927 0.0156463 -0.694739 0.719092 0.0156484 -0.694749 0.719082 -0.345988 -0.69475 0.630568 -0.345986 -0.694752 0.630566 -0.614915 -0.694752 0.373094 -0.614921 -0.694745 0.373096 -0.719085 -0.694746 0.0156479 -0.719082 -0.694749 0.0156485 -0.630568 -0.69475 -0.345986 -0.630576 -0.694739 -0.345993 -0.3731 -0.694736 -0.614929 -0.373098 -0.694743 -0.614923 -0.348272 -0.698073 -0.625621 -0.348273 -0.698068 -0.625625 -0.492301 -0.706854 -0.507934 -0.648725 -0.60829 -0.457317 -0.597958 -0.700859 -0.388899 -0.673294 -0.706112 -0.219276 -0.830511 -0.53951 -0.138496 -0.708168 -0.703118 -0.0642205 -0.698952 -0.704866 0.120957 -0.823677 -0.513753 0.240028 -0.654507 -0.70487 0.273457 -0.532439 -0.698071 0.478753 -0.719962 -0.415419 0.555951 -0.450087 -0.706121 0.546639 -0.271985 -0.698077 0.662354 0.0423345 -0.69808 0.714767 0.0423334 -0.698075 0.714772 -0.142358 -0.706863 0.692878 -0.336704 -0.582338 0.739941 0.0156516 0.69474 0.719091 0.0156488 0.694749 0.719082 -0.345988 0.694748 0.630569 -0.376227 0.418162 0.826797 -0.450095 0.706119 0.546635 -0.562798 0.703127 0.434592 -0.749511 0.481073 0.454755 -0.654505 0.704873 0.273455 -0.698944 0.704873 0.120956 -0.876474 0.481071 0.0190747 -0.3731 0.69474 -0.614925 -0.373092 0.69475 -0.614919 -0.597955 0.700864 -0.388895 -0.745574 0.526083 -0.409092 -0.673289 0.706117 -0.219273 -0.70816 0.703125 -0.0642212 0.0591236 0 0.998251 0.0217565 -0.00717238 0.999738 -0.379847 0.00599258 0.92503 -0.414177 0 0.910196 -0.635644 0 0.771982 -0.743567 0.00960109 0.668593 -0.791487 0 0.611186 -0.922704 0 0.385509 -0.96001 0.0108064 0.279758 -0.985354 0 0.170521 -0.995913 0 -0.0903169 -0.986333 0.0096013 -0.164482 -0.950845 0 -0.309667 -0.817328 0 -0.576172 -0.838278 0.00717225 -0.545195 -0.486378 -0.00834283 -0.873709 -0.518726 0 -0.85494 0.042334 -0.698073 0.714774 0.042336 -0.698078 0.714769 -0.271984 -0.698078 0.662354 -0.271984 -0.698077 0.662354 -0.532435 -0.698077 0.47875 -0.532434 -0.698078 0.47875 -0.687429 -0.698077 0.200324 -0.687429 -0.698077 0.200325 -0.706271 -0.698076 -0.117778 -0.70627 -0.698076 -0.117778 -0.585226 -0.698077 -0.412553 -0.585227 -0.698075 -0.412554 -0.348271 -0.698074 -0.625619 -0.348271 -0.698074 -0.62562 -0.373101 0.694739 -0.614926 -0.373093 0.69475 -0.614918 -0.630567 0.694749 -0.345989 -0.63057 0.694746 -0.34599 -0.719086 0.694745 0.0156499 -0.719082 0.69475 0.0156485 -0.614919 0.694748 0.373094 -0.614919 0.694749 0.373094 -0.345988 0.69475 0.630567 -0.345988 0.69475 0.630567 0.0156488 0.694749 0.719082 0.0156516 0.69474 0.719091 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217585 -0.999763 0 0.0217585 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.518727 0 -0.85494 -0.518727 0 -0.85494 0.0156489 -0.694746 0.719085 0.0156507 -0.694751 0.71908 -0.345989 -0.69475 0.630567 -0.345986 -0.694753 0.630565 -0.614916 -0.694752 0.373093 -0.614918 -0.69475 0.373093 -0.71908 -0.694751 0.0156498 -0.719082 -0.694749 0.0156489 -0.630571 -0.694745 -0.345991 -0.630566 -0.694752 -0.345986 -0.373094 -0.694753 -0.614914 -0.373095 -0.694746 -0.614922 0.0423375 0.698067 0.71478 0.0423339 0.698076 0.714771 -0.142356 0.706861 0.692879 -0.296451 0.625239 0.721937 -0.295431 0.700865 0.649237 -0.450094 0.706121 0.546634 -0.610189 0.571527 0.548659 -0.562804 0.703118 0.4346 -0.654511 0.704868 0.273454 -0.800717 0.551729 0.233339 -0.698945 0.704872 0.120959 -0.706273 0.698073 -0.117779 -0.876368 0.475039 -0.0794751 -0.673287 0.706118 -0.219275 -0.585225 0.698077 -0.412553 -0.348272 0.69807 -0.625623 -0.348269 0.698074 -0.625621 -0.492299 0.706859 -0.50793 -0.66809 0.604034 -0.434509 0.0591236 0 0.998251 0.0217565 0.00717239 0.999738 -0.201252 0 0.97954 -0.414178 0 0.910196 -0.481006 0.0119762 0.876636 -0.635644 0 0.771983 -0.791485 0 0.611188 -0.854853 0.0143845 0.518671 -0.922706 0 0.385505 -0.985353 0 0.170525 -0.99966 0.0143844 0.0217576 -0.995913 0 -0.0903162 -0.950844 0 -0.30967 -0.876636 0.0119757 -0.481006 -0.8383 0 -0.545209 -0.695972 0 -0.718069 -0.518712 0.00717296 -0.854919 -0.486394 0 -0.87374 0.0156489 -0.694746 0.719085 0.0156507 -0.694751 0.71908 -0.345989 -0.694749 0.630567 -0.345985 -0.694754 0.630564 -0.614914 -0.694754 0.373092 -0.614919 -0.69475 0.373092 -0.71908 -0.694751 0.0156508 -0.719085 -0.694746 0.015649 -0.630572 -0.694743 -0.345992 -0.630568 -0.69475 -0.345986 -0.373093 -0.694752 -0.614916 -0.373094 -0.694748 -0.61492 0.042335 0.698073 0.714774 0.0423339 0.698076 0.714771 -0.142359 0.70686 0.69288 -0.296452 0.625238 0.721937 -0.295432 0.700866 0.649236 -0.450086 0.706121 0.54664 -0.610191 0.571517 0.548666 -0.562803 0.703122 0.434595 -0.654509 0.70487 0.273451 -0.800709 0.55174 0.23334 -0.698937 0.70488 0.120959 -0.706268 0.698079 -0.11778 -0.876357 0.47506 -0.0794789 -0.6733 0.706109 -0.219263 -0.585233 0.698067 -0.412558 -0.348271 0.698073 -0.625621 -0.34827 0.698074 -0.62562 -0.492299 0.706859 -0.50793 -0.668083 0.604041 -0.434511 0.0591236 0 0.998251 0.0217566 0.00717238 0.999738 -0.201256 0 0.979539 -0.41418 0 0.910195 -0.481003 0.0119755 0.876637 -0.635633 0 0.771992 -0.791488 0 0.611185 -0.854855 0.0143845 0.518668 -0.922707 0 0.385503 -0.985353 0 0.170526 -0.99966 0.0143847 0.0217549 -0.995913 0 -0.0903217 -0.950851 0 -0.309649 -0.876636 0.011977 -0.481004 -0.838297 0 -0.545215 -0.695971 0 -0.71807 -0.518712 0.00717277 -0.854919 -0.486394 0 -0.87374 0.0156489 -0.694746 0.719085 0.015649 -0.694746 0.719085 -0.345988 -0.694748 0.630569 -0.34599 -0.694746 0.630571 -0.614925 -0.694743 0.373095 -0.614912 -0.694756 0.373093 -0.719076 -0.694755 0.0156487 -0.71908 -0.694751 0.015647 -0.630566 -0.694752 -0.345987 -0.630566 -0.694752 -0.345987 -0.373094 -0.69475 -0.614918 -0.373094 -0.69475 -0.614918 0.0591247 0 0.998251 0.0217546 -0.0178262 0.999604 -0.201251 0 0.97954 -0.414179 0 0.910196 -0.480825 -0.0297574 0.876311 -0.635639 0 0.771987 -0.791487 0 0.611186 -0.854396 -0.0357368 0.518391 -0.922706 0 0.385504 -0.985353 0 0.170525 -0.999125 -0.0357367 0.0217442 -0.995913 0 -0.090319 -0.950847 0 -0.309662 -0.876311 -0.0297579 -0.480825 -0.486391 0 -0.873741 -0.518641 -0.0178278 -0.854806 -0.69597 0 -0.718071 -0.8383 0 -0.545209 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0591247 0 0.998251 0.0591247 0 0.998251 -0.379857 0 0.925045 -0.379857 0 0.925045 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486396 0 -0.873739 -0.486396 0 -0.873739 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0591249 0 0.998251 0.0591249 0 0.998251 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.960067 0 0.27977 -0.960067 0 0.27977 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486397 0 -0.873738 -0.486397 0 -0.873738 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.373089 0.694754 -0.614916 -0.373089 0.694754 -0.614916 -0.630562 0.694754 -0.345988 -0.630577 0.69474 -0.34599 -0.719089 0.694741 0.0156524 -0.719076 0.694755 0.0156475 -0.61492 0.694749 0.373092 -0.614925 0.694741 0.373098 -0.34599 0.694741 0.630576 -0.345987 0.694759 0.630557 0.0156488 0.69476 0.719071 0.0156504 0.694756 0.719076 0.0591238 0 0.998251 0.0217564 -0.00889363 0.999724 -0.201256 0 0.979539 -0.414178 0 0.910196 -0.480983 -0.014849 0.876604 -0.635631 0 0.771993 -0.791488 0 0.611185 -0.854807 -0.0178357 0.518639 -0.922706 0 0.385504 -0.985353 0 0.170526 -0.999604 -0.0178354 0.0217584 -0.995914 0 -0.0903111 -0.950846 0 -0.309664 -0.876601 -0.01485 -0.480989 -0.486394 0 -0.873739 -0.518701 -0.008893 -0.854909 -0.695948 0 -0.718092 -0.838297 0 -0.545213 -0.348272 -0.698077 -0.625616 -0.348271 -0.698073 -0.625621 -0.492282 -0.70686 -0.507945 -0.610927 -0.664296 -0.430673 -0.597958 -0.700858 -0.388901 -0.673294 -0.706112 -0.219273 -0.756462 -0.641756 -0.126151 -0.708158 -0.703128 -0.0642169 -0.698944 -0.704874 0.12096 -0.742575 -0.633842 0.216395 -0.654508 -0.704871 0.273452 -0.532441 -0.698069 0.478755 -0.633383 -0.599675 0.489097 -0.450086 -0.706118 0.546644 -0.271989 -0.698075 0.662354 0.0423345 -0.698068 0.714779 0.0423411 -0.698079 0.714768 -0.142358 -0.706865 0.692875 -0.313594 -0.653245 0.689152 -0.348267 0.698077 -0.625618 -0.348272 0.698073 -0.625621 -0.58523 0.698072 -0.412555 -0.58522 0.698082 -0.412553 -0.706264 0.698083 -0.117775 -0.706259 0.698088 -0.117776 -0.687422 0.698085 0.200323 -0.687424 0.698082 0.200324 -0.532434 0.698082 0.478743 -0.532442 0.698065 0.47876 -0.271986 0.698071 0.66236 -0.271986 0.698074 0.662357 0.0423336 0.698079 0.714769 0.0423363 0.698073 0.714774 0.0591234 0 0.998251 0.0591234 0 0.998251 -0.379854 0 0.925047 -0.379854 0 0.925047 -0.743605 0 0.668619 -0.743605 0 0.668619 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.98638 0 -0.164486 -0.98638 0 -0.164486 -0.817328 0 -0.576172 -0.817328 0 -0.576172 -0.486392 0 -0.873741 -0.486392 0 -0.873741 0.042334 -0.698073 0.714774 0.0423349 -0.698074 0.714773 -0.271986 -0.698073 0.662358 -0.271986 -0.698073 0.662358 -0.532442 -0.698071 0.47875 -0.53244 -0.698073 0.47875 -0.687432 -0.698074 0.200326 -0.68743 -0.698076 0.200326 -0.706271 -0.698076 -0.117776 -0.706269 -0.698078 -0.117774 -0.585226 -0.698076 -0.412553 -0.585229 -0.69807 -0.41256 -0.348271 -0.69807 -0.625624 -0.348271 -0.698075 -0.625618 -0.348266 0.69808 -0.625615 -0.348271 0.698075 -0.625619 -0.585229 0.698073 -0.412554 -0.585235 0.698068 -0.412555 -0.706282 0.698065 -0.117778 -0.70626 0.698086 -0.117783 -0.68742 0.698086 0.200322 -0.687424 0.698082 0.200325 -0.532431 0.69808 0.478749 -0.532433 0.698078 0.478751 -0.271984 0.698077 0.662354 -0.271984 0.698079 0.662352 0.042335 0.698076 0.714771 0.0423346 0.698077 0.71477 0.0591251 0 0.998251 0.0591251 0 0.998251 -0.379854 0 0.925046 -0.379854 0 0.925046 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164486 -0.986379 0 -0.164486 -0.817329 0 -0.576172 -0.817329 0 -0.576172 -0.486392 0 -0.873741 -0.486392 0 -0.873741 0.0423352 -0.698073 0.714774 0.0423348 -0.698073 0.714774 -0.271985 -0.698076 0.662355 -0.271988 -0.698072 0.662358 -0.532438 -0.698072 0.478755 -0.532435 -0.698074 0.478754 -0.687431 -0.698075 0.200325 -0.68743 -0.698076 0.200326 -0.706271 -0.698076 -0.117776 -0.706277 -0.698069 -0.117782 -0.585232 -0.69807 -0.412556 -0.585232 -0.69807 -0.412556 -0.348271 -0.698071 -0.625623 -0.348271 -0.698075 -0.625619 -0.348271 -0.698078 -0.625615 -0.348274 -0.698062 -0.625631 -0.492304 -0.706849 -0.507938 -0.648727 -0.608284 -0.457322 -0.597955 -0.700865 -0.388894 -0.673289 -0.706118 -0.21927 -0.830497 -0.539531 -0.138494 -0.708161 -0.703124 -0.0642229 -0.698945 -0.704872 0.120959 -0.823667 -0.51377 0.240027 -0.654511 -0.704868 0.273453 -0.532443 -0.698067 0.478756 -0.719958 -0.415425 0.555952 -0.450093 -0.706117 0.54664 -0.271986 -0.698075 0.662356 0.0423353 -0.698066 0.714781 0.0423372 -0.698075 0.714772 -0.142356 -0.706861 0.692879 -0.336708 -0.582329 0.739946 0.0423349 -0.698073 0.714774 0.042334 -0.698069 0.714778 -0.27199 -0.698067 0.662363 -0.271987 -0.698072 0.662359 -0.532439 -0.698069 0.478756 -0.532438 -0.698071 0.478756 -0.687435 -0.698071 0.200327 -0.687439 -0.698066 0.200327 -0.70628 -0.698067 -0.11778 -0.706278 -0.698068 -0.117779 -0.585229 -0.698071 -0.412557 -0.585228 -0.698073 -0.412556 -0.348272 -0.698074 -0.625619 -0.348272 -0.698072 -0.625621 0.0423349 -0.698074 0.714773 0.0423351 -0.698075 0.714772 -0.271987 -0.698072 0.662359 -0.271987 -0.698072 0.662359 -0.53244 -0.698069 0.478756 -0.532438 -0.698072 0.478755 -0.687436 -0.69807 0.200323 -0.687427 -0.69808 0.200323 -0.706267 -0.69808 -0.117777 -0.706266 -0.698081 -0.117777 -0.585223 -0.69808 -0.412552 -0.585221 -0.698083 -0.41255 -0.34827 -0.69808 -0.625614 -0.348271 -0.698073 -0.62562 0.0423367 0.69808 0.714767 0.0423387 0.698075 0.714772 -0.142356 0.706861 0.692879 -0.296456 0.625236 0.721938 -0.295435 0.700866 0.649234 -0.450085 0.706121 0.546641 -0.610191 0.571518 0.548666 -0.562804 0.703118 0.4346 -0.654513 0.704867 0.273451 -0.800713 0.551735 0.233338 -0.698945 0.704872 0.120961 -0.706273 0.698073 -0.117779 -0.876368 0.475039 -0.0794751 -0.673287 0.706118 -0.219275 -0.585225 0.698077 -0.412553 -0.348272 0.69807 -0.625623 -0.348269 0.698074 -0.625621 -0.492299 0.706859 -0.50793 -0.66809 0.604034 -0.434509 0.0591303 0 0.99825 0.0591303 0 0.99825 -0.201252 0 0.97954 -0.201252 0 0.97954 -0.414185 0 0.910193 -0.414185 0 0.910193 -0.635632 0 0.771992 -0.635632 0 0.771992 -0.791485 0 0.611188 -0.791485 0 0.611188 -0.922708 0 0.385501 -0.922708 0 0.385501 -0.985353 0 0.170527 -0.985353 0 0.170527 -0.995913 0 -0.0903162 -0.995913 0 -0.0903162 -0.950844 0 -0.30967 -0.950844 0 -0.30967 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.695972 0 -0.718069 -0.695972 0 -0.718069 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.348271 -0.698075 -0.625619 -0.348271 -0.698072 -0.625621 -0.492299 -0.706858 -0.50793 -0.61997 -0.651635 -0.437046 -0.597956 -0.700863 -0.388895 -0.673288 -0.706117 -0.219276 -0.774261 -0.619556 -0.129117 -0.708161 -0.703125 -0.0642209 -0.687434 -0.698071 0.200326 -0.871115 -0.467367 0.150757 -0.654511 -0.70487 0.27345 -0.532441 -0.698069 0.478755 -0.65498 -0.561418 0.505778 -0.450085 -0.706121 0.546641 -0.271984 -0.698078 0.662354 0.0423383 -0.698083 0.714764 0.0423322 -0.698069 0.714778 -0.142357 -0.706855 0.692886 -0.319142 -0.637404 0.70133 0.0156495 0.694746 0.719085 0.0156488 0.694749 0.719082 -0.345988 0.69475 0.630567 -0.376227 0.418159 0.826799 -0.450097 0.706122 0.546631 -0.562797 0.70313 0.43459 -0.749509 0.481078 0.454753 -0.654509 0.704866 0.273463 -0.698953 0.704866 0.120952 -0.876469 0.481079 0.0190771 -0.373096 0.694745 -0.614921 -0.373096 0.694746 -0.614921 -0.597956 0.700863 -0.388895 -0.745574 0.526084 -0.409092 -0.673287 0.706119 -0.219273 -0.708159 0.703126 -0.0642172 0.0591236 0 0.998251 0.0217565 -0.0071724 0.999738 -0.379845 0.00599282 0.925031 -0.414177 0 0.910196 -0.635649 0 0.771979 -0.743569 0.00960086 0.668591 -0.791488 0 0.611185 -0.922701 0 0.385517 -0.96001 0.0108071 0.279758 -0.985355 0 0.170513 -0.995914 0 -0.0903113 -0.986334 0.00960163 -0.164479 -0.950845 0 -0.309667 -0.817326 0 -0.576175 -0.838279 0.00717302 -0.545195 -0.48638 -0.00834197 -0.873708 -0.518725 0 -0.854941 0.0423338 -0.698078 0.71477 0.0423337 -0.698077 0.71477 -0.271981 -0.698081 0.662352 -0.271987 -0.698074 0.662356 -0.532441 -0.698071 0.478752 -0.53243 -0.698081 0.478749 -0.687424 -0.698082 0.200324 -0.687429 -0.698077 0.200323 -0.706269 -0.698078 -0.117776 -0.706272 -0.698074 -0.117778 -0.585226 -0.698074 -0.412556 -0.585224 -0.698079 -0.412551 -0.348271 -0.698077 -0.625616 -0.348271 -0.698073 -0.625621 -0.373096 0.694745 -0.614921 -0.373093 0.694749 -0.614919 -0.630567 0.69475 -0.345988 -0.630567 0.69475 -0.345988 -0.719082 0.694749 0.0156488 -0.719091 0.69474 0.0156516 -0.614926 0.694739 0.373101 -0.614917 0.694752 0.373091 -0.345988 0.694752 0.630565 -0.345988 0.69475 0.630567 0.0156488 0.694749 0.719082 0.0156495 0.694746 0.719085 0.0591236 0 0.998251 0.0217565 -0.0071724 0.999738 -0.201248 0 0.97954 -0.414177 0 0.910196 -0.481006 -0.0119765 0.876636 -0.635649 0 0.771979 -0.791488 0 0.611185 -0.854851 -0.0143837 0.518673 -0.922701 0 0.385517 -0.985356 0 0.170512 -0.99966 -0.0143834 0.0217548 -0.995914 0 -0.0903117 -0.950845 0 -0.309667 -0.876636 -0.0119759 -0.481004 -0.486397 0 -0.873738 -0.518712 -0.0071721 -0.854919 -0.695951 0 -0.718089 -0.8383 0 -0.545209 -0.34827 -0.698075 -0.625619 -0.34827 -0.698079 -0.625615 -0.492279 -0.706866 -0.507939 -0.619969 -0.651637 -0.437044 -0.597956 -0.700863 -0.388895 -0.673289 -0.706117 -0.219274 -0.774261 -0.619556 -0.129116 -0.708157 -0.703129 -0.0642173 -0.687428 -0.698079 0.200322 -0.871129 -0.467344 0.150746 -0.654494 -0.704882 0.273457 -0.532429 -0.698081 0.47875 -0.654984 -0.561413 0.505777 -0.450103 -0.706111 0.546639 -0.27199 -0.69807 0.662359 0.0423341 -0.698073 0.714774 0.0423359 -0.698077 0.71477 -0.142353 -0.706865 0.692876 -0.31913 -0.637421 0.701321 0.015649 0.694748 0.719083 0.0156493 0.694747 0.719084 -0.345989 0.694748 0.630569 -0.376228 0.418162 0.826797 -0.450096 0.706119 0.546635 -0.562798 0.703128 0.434591 -0.74951 0.481076 0.454754 -0.654509 0.704866 0.273462 -0.698953 0.704866 0.120952 -0.876469 0.48108 0.0190771 -0.373095 0.694746 -0.61492 -0.373093 0.694749 -0.614919 -0.597954 0.700865 -0.388894 -0.745574 0.526083 -0.409091 -0.673288 0.706118 -0.219274 -0.708159 0.703126 -0.0642173 0.0591249 0 0.998251 0.0217572 -0.0071725 0.999738 -0.379847 0.0059928 0.92503 -0.414178 0 0.910196 -0.635646 0 0.771981 -0.743568 0.009601 0.668592 -0.791488 0 0.611185 -0.922701 0 0.385516 -0.96001 0.0108071 0.279758 -0.985355 0 0.170513 -0.995914 0 -0.0903114 -0.986334 0.00960162 -0.164479 -0.950845 0 -0.309667 -0.817327 0 -0.576175 -0.838278 0.00717293 -0.545195 -0.486379 -0.00834214 -0.873708 -0.518725 0 -0.854941 0.0423348 -0.698077 0.714771 0.0423344 -0.698076 0.714771 -0.271983 -0.698079 0.662353 -0.271987 -0.698074 0.662356 -0.53244 -0.698071 0.478753 -0.53243 -0.698081 0.47875 -0.687424 -0.698082 0.200323 -0.687429 -0.698078 0.200322 -0.706269 -0.698078 -0.117776 -0.706273 -0.698074 -0.117779 -0.585227 -0.698074 -0.412556 -0.585223 -0.698081 -0.412549 -0.34827 -0.698079 -0.625615 -0.34827 -0.698076 -0.625618 0.141335 -0.705898 0.69407 -0.161583 -0.707047 0.688458 -0.0916878 -0.705894 0.702358 -0.0916877 -0.705896 0.702356 -0.0271457 -0.707093 0.706599 0.0275408 -0.631819 0.774626 0.0313399 -0.706137 0.707382 0.141336 -0.705894 0.694073 -0.208372 -0.623996 0.753133 -0.258347 -0.459591 0.849725 -0.232682 -0.704459 0.670519 -0.36038 -0.662727 0.656444 -0.374447 -0.577958 0.725089 -0.39484 -0.45891 0.795929 -0.287558 -0.706811 0.646319 -0.260463 -0.707105 0.65739 -0.355455 -0.70706 0.611325 -0.414921 -0.705897 0.574064 -0.414921 -0.705896 0.574065 -0.534392 -0.674973 0.50876 -0.609055 -0.516341 0.602033 -0.479044 -0.699966 0.529684 -0.46169 -0.707106 0.535579 -0.707156 -0.707009 0.00833473 -0.703371 -0.705898 0.0835363 -0.703368 -0.7059 0.0835358 -0.680025 -0.7059 0.198167 -0.680029 -0.705896 0.198169 -0.638137 -0.705896 0.307395 -0.638137 -0.705897 0.307394 -0.591648 -0.706685 0.388007 -0.721351 -0.469925 0.508746 -0.557409 -0.706908 0.435403 -0.539936 -0.707106 0.456586 -0.829756 -0.557276 -0.0307841 -0.881727 -0.469924 -0.0415913 -0.704052 -0.706905 -0.0678002 -0.837122 -0.516344 -0.180599 -0.724046 -0.674968 -0.14204 -0.700693 -0.707103 -0.0950535 -0.628215 -0.70706 -0.324672 -0.658355 -0.705898 -0.2613 -0.658357 -0.705895 -0.2613 -0.677129 -0.707105 -0.203715 -0.688601 -0.699964 -0.189419 -0.587282 -0.706897 -0.394205 -0.731018 -0.514199 -0.448566 -0.760605 -0.458911 -0.459219 -0.705349 -0.577957 -0.410425 -0.656605 -0.662731 -0.360079 -0.506964 -0.706204 -0.494231 -0.580336 -0.623998 -0.523294 -0.674379 -0.45959 -0.577919 -0.55646 -0.704461 -0.440552 -0.572851 -0.707109 -0.414534 -0.497328 -0.707107 -0.502658 -0.454642 -0.705896 -0.543149 -0.454642 -0.705897 -0.543149 -0.359041 -0.705896 -0.610573 -0.359041 -0.705897 -0.610573 -0.253648 -0.705897 -0.661341 -0.253647 -0.705898 -0.66134 0.130651 -0.705398 0.696667 0.130651 -0.705398 0.696666 -0.00777238 -0.705398 0.708768 -0.00777229 -0.705394 0.708772 -0.145898 -0.705394 0.693637 -0.145897 -0.705397 0.693635 -0.278415 -0.705397 0.651844 -0.278413 -0.705402 0.651839 -0.400231 -0.705402 0.584999 -0.400231 -0.705401 0.584999 -0.506669 -0.705401 0.495677 -0.506671 -0.705398 0.495679 -0.593637 -0.705398 0.387308 -0.593638 -0.705397 0.387309 -0.657793 -0.705397 0.264054 -0.657791 -0.705399 0.264053 -0.696666 -0.705398 0.130651 -0.696666 -0.705399 0.130651 -0.708768 -0.705398 -0.00777238 -0.708772 -0.705394 -0.00777229 -0.693637 -0.705394 -0.145897 -0.693629 -0.705403 -0.145896 -0.651838 -0.705403 -0.278413 -0.651839 -0.705402 -0.278413 -0.584999 -0.705402 -0.400231 -0.585003 -0.705397 -0.400234 -0.495681 -0.705397 -0.506672 -0.495676 -0.705403 -0.506668 -0.387306 -0.705402 -0.593634 -0.38731 -0.705395 -0.59364 -0.264054 -0.705395 -0.657794 -0.264054 -0.705397 -0.657792 0.0217559 0 0.999763 0.0217559 0 0.999763 -0.481037 0 0.8767 -0.481037 0 0.8767 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.8767 0 -0.481037 -0.8767 0 -0.481037 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0217558 0 0.999763 0.0217558 0 0.999763 -0.481037 0 0.8767 -0.481037 0 0.8767 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.021756 -0.999763 0 0.021756 -0.876701 0 -0.481035 -0.876701 0 -0.481035 -0.518723 0 -0.854943 -0.518723 0 -0.854943 0.0217558 0 0.999763 0.0217558 0 0.999763 -0.481037 0 0.8767 -0.481037 0 0.8767 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.876698 0 -0.481041 -0.876698 0 -0.481041 -0.518727 0 -0.85494 -0.518727 0 -0.85494 0.0591248 0 0.998251 0.0591248 0 0.998251 -0.379856 0 0.925046 -0.379856 0 0.925046 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.960066 0 0.279773 -0.960066 0 0.279773 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.817332 0 -0.576167 -0.817332 0 -0.576167 -0.486392 0 -0.873741 -0.486392 0 -0.873741 0.0591248 0 0.998251 0.0217578 0.00572005 0.999747 -0.201258 0 0.979538 -0.414178 0 0.910196 -0.481017 0.00955118 0.876659 -0.635643 0 0.771983 -0.791485 0 0.611189 -0.854883 0.0114719 0.518694 -0.922703 0 0.385512 -0.985355 0 0.170515 -0.999698 0.0114714 0.0217545 -0.995913 0 -0.0903148 -0.950844 0 -0.309672 -0.87666 0.00955071 -0.481016 -0.838302 0 -0.545206 -0.69594 0 -0.7181 -0.518716 0.00571956 -0.854927 -0.486398 0 -0.873737 0.0217558 0 0.999763 0.0217558 0 0.999763 -0.481037 0 0.8767 -0.481037 0 0.8767 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.876698 0 -0.481041 -0.876698 0 -0.481041 -0.518727 0 -0.85494 -0.518727 0 -0.85494 0.0591323 0 0.99825 0.0591323 0 0.99825 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.743604 0 0.668621 -0.743604 0 0.668621 -0.960065 0 0.279777 -0.960065 0 0.279777 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.817329 0 -0.576171 -0.817329 0 -0.576171 -0.4864 0 -0.873737 -0.4864 0 -0.873737 0.0217559 0 0.999763 0.0217559 0 0.999763 -0.481037 0 0.8767 -0.481037 0 0.8767 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.8767 0 -0.481037 -0.8767 0 -0.481037 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0591248 0 0.998251 0.0591248 0 0.998251 -0.379853 0 0.925047 -0.379853 0 0.925047 -0.743604 0 0.66862 -0.743604 0 0.66862 -0.960064 0 0.279782 -0.960064 0 0.279782 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0.0217582 0 0.999763 0.0217582 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854939 0 0.518728 -0.854939 0 0.518728 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.8767 0 -0.481037 -0.8767 0 -0.481037 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.253646 0.705903 -0.661336 -0.253647 0.705898 -0.661341 -0.359041 0.705897 -0.610573 -0.35904 0.705899 -0.610571 -0.454641 0.705898 -0.543148 -0.454644 0.705893 -0.543152 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658364 0.705887 -0.261303 -0.692395 0.705887 -0.149376 -0.692394 0.705888 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503752 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314774 0.705897 0.634529 -0.206041 0.705895 0.677686 -0.206044 0.705886 0.677695 -0.091689 0.705886 0.702366 -0.0916867 0.7059 0.702352 0.0251672 0.7059 0.707864 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141336 0.705889 0.694078 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.3581 0 -0.933683 -0.3581 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817205 0 0.576348 -0.817205 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129445 0 0.991587 -0.129445 0 0.991587 0.0355312 0 0.999369 0.0355312 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 -0.3581 0 -0.933683 -0.3581 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856071 0 -0.516857 -0.856071 0 -0.516857 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817205 0 0.576348 -0.817205 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129445 0 0.991587 -0.129445 0 0.991587 0.0355312 0 0.999369 0.0355312 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 -0.3581 0 -0.933683 -0.3581 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129445 0 0.991587 -0.129445 0 0.991587 0.0355312 0 0.999369 0.0355312 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 -0.3581 0 -0.933683 -0.3581 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129445 0 0.991587 -0.129445 0 0.991587 0.0355312 0 0.999369 0.0355312 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 -0.3581 0 -0.933683 -0.3581 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129445 0 0.991587 -0.129445 0 0.991587 0.0355312 0 0.999369 0.0355312 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 -0.3581 0 -0.933683 -0.3581 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129445 0 0.991587 -0.129445 0 0.991587 0.0355312 0 0.999369 0.0355312 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 -0.3581 0 -0.933683 -0.3581 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129445 0 0.991587 -0.129445 0 0.991587 0.0355312 0 0.999369 0.0355312 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 -0.3581 0 -0.933683 -0.3581 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129445 0 0.991587 -0.129445 0 0.991587 0.0355312 0 0.999369 0.0355312 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 -0.3581 0 -0.933683 -0.3581 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129445 0 0.991587 -0.129445 0 0.991587 0.0355312 0 0.999369 0.0355312 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 -0.3581 0 -0.933683 -0.3581 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856072 0 -0.516857 -0.856072 0 -0.516857 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.0471179 -0.998889 0 -0.0471179 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444398 0 0.895829 -0.444398 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129445 0 0.991587 -0.129445 0 0.991587 0.0355312 0 0.999369 0.0355312 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 0.365917 0 0.930647 0.365917 0 0.930647 0.528419 0 0.848984 0.528419 0 0.848984 0.673443 0 0.739239 0.673443 0 0.739239 0.796192 0 0.605044 0.796192 0 0.605044 0.892607 0 0.450836 0.892607 0 0.450836 0.959498 0 0.281717 0.959498 0 0.281717 0.994652 0 0.103279 0.994652 0 0.103279 0.779088 0 -0.626914 0.779088 0 -0.626914 0.641984 0 -0.766718 0.641984 0 -0.766718 0.480262 0 -0.877125 0.480262 0 -0.877125 0.300127 0 -0.953899 0.300127 0 -0.953899 0.108484 0 -0.994098 0.108484 0 -0.994098 -0.0873196 0 -0.99618 -0.0873196 0 -0.99618 -0.279774 0 -0.960066 -0.279774 0 -0.960066 -0.461501 0 -0.887139 -0.461501 0 -0.887139 -0.625534 0 -0.780197 -0.625534 0 -0.780197 -0.765581 0 -0.64334 -0.765581 0 -0.64334 -0.876273 0 -0.481815 -0.876273 0 -0.481815 -0.953366 0 -0.301816 -0.953366 0 -0.301816 -0.993905 0 -0.110244 -0.993905 0 -0.110244 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0.279774 0 0.960066 0.279774 0 0.960066 0 1 0 0 1 0 -0.279774 0 -0.960066 -0.279774 0 -0.960066 -0.279774 0 -0.960066 -0.279774 0 -0.960066 0 1 0 0 1 0 0.279774 0 0.960066 0.279774 0 0.960066 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0591303 0 0.99825 0.021757 0.001619 0.999762 -0.20129 0 0.979532 -0.414177 0 0.910196 -0.481033 0.00270282 0.876698 -0.635632 0 0.771992 -0.791488 0 0.611185 -0.854938 0.00324659 0.51872 -0.922705 0 0.385506 -0.985354 0 0.170521 -0.999758 0.00324653 0.021757 -0.995913 0 -0.0903162 -0.950844 0 -0.30967 -0.876695 0.00270286 -0.481038 -0.8383 0 -0.545209 -0.695972 0 -0.718069 -0.518726 0.00161883 -0.854939 -0.486395 0 -0.873739 0.0156488 -0.694751 0.71908 0.0156471 -0.694747 0.719084 -0.345986 -0.694748 0.630571 -0.345993 -0.694739 0.630576 -0.614927 -0.694741 0.373097 -0.614921 -0.694746 0.373096 -0.719089 -0.694742 0.015649 -0.719085 -0.694746 0.0156508 -0.630569 -0.694747 -0.34599 -0.63057 -0.694746 -0.345991 -0.373096 -0.694747 -0.614919 -0.373097 -0.694741 -0.614925 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.854941 0 0.518726 -0.854941 0 0.518726 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.015649 -0.694742 0.719089 0.015649 -0.694742 0.719089 -0.345992 -0.694743 0.630572 -0.34599 -0.694746 0.630571 -0.614919 -0.694747 0.373096 -0.614923 -0.694744 0.373096 -0.719089 -0.694742 0.015649 -0.719085 -0.694746 0.0156508 -0.630569 -0.694747 -0.345989 -0.630569 -0.694747 -0.345989 -0.373096 -0.694746 -0.614921 -0.373096 -0.694745 -0.614922 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.201256 0 0.979539 -0.201256 0 0.979539 -0.414178 0 0.910196 -0.414178 0 0.910196 -0.635643 0 0.771984 -0.635643 0 0.771984 -0.791484 0 0.61119 -0.791484 0 0.61119 -0.922706 0 0.385505 -0.922706 0 0.385505 -0.985353 0 0.170526 -0.985353 0 0.170526 -0.995913 0 -0.0903212 -0.995913 0 -0.0903212 -0.950845 0 -0.309667 -0.950845 0 -0.309667 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.695971 0 -0.71807 -0.695971 0 -0.71807 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.348272 -0.698069 -0.625625 -0.348271 -0.698072 -0.625622 -0.4923 -0.706857 -0.507932 -0.619969 -0.651635 -0.437047 -0.597954 -0.700866 -0.388894 -0.673285 -0.706121 -0.219273 -0.774259 -0.619559 -0.129111 -0.70817 -0.703115 -0.0642252 -0.687442 -0.698064 0.200326 -0.871118 -0.467361 0.150757 -0.65451 -0.704869 0.273454 -0.532439 -0.698071 0.478755 -0.654975 -0.561425 0.505777 -0.450096 -0.706116 0.546639 -0.271987 -0.698073 0.662357 0.0423342 -0.698071 0.714776 0.042335 -0.698074 0.714774 -0.142359 -0.706859 0.692881 -0.319133 -0.637415 0.701325 0.0217577 0 0.999763 0.0217577 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0156493 -0.694745 0.719086 0.0156493 -0.694745 0.719086 -0.34599 -0.694746 0.63057 -0.34599 -0.694747 0.63057 -0.614919 -0.694748 0.373096 -0.614925 -0.694742 0.373097 -0.719089 -0.694742 0.015649 -0.719085 -0.694746 0.0156508 -0.63057 -0.694746 -0.34599 -0.630569 -0.694748 -0.345988 -0.373095 -0.694747 -0.61492 -0.373095 -0.694744 -0.614923 0.0423315 0.698082 0.714766 0.0423391 0.698068 0.714779 -0.142384 0.706855 0.69288 -0.288131 0.651639 0.701675 -0.295429 0.700866 0.649237 -0.450085 0.706121 0.546641 -0.583691 0.619556 0.524838 -0.562801 0.703124 0.434594 -0.687431 0.698075 0.200325 -0.815733 0.467361 0.340813 -0.698942 0.704876 0.120956 -0.706268 0.698079 -0.117778 -0.824149 0.56142 -0.0747395 -0.673284 0.706121 -0.219275 -0.585224 0.698078 -0.412552 -0.348272 0.698073 -0.625621 -0.34827 0.698075 -0.625619 -0.492297 0.706861 -0.507928 -0.645923 0.637421 -0.420092 -0.373094 0.69475 -0.614918 -0.373093 0.69475 -0.614918 -0.630566 0.694752 -0.345987 -0.630566 0.694752 -0.345987 -0.71908 0.694751 0.0156488 -0.719085 0.694746 0.0156508 -0.614919 0.694748 0.373095 -0.614917 0.694752 0.373092 -0.345989 0.69475 0.630566 -0.345989 0.694748 0.630569 0.0156489 0.694746 0.719085 0.0156489 0.694746 0.719085 0.0423349 0.698076 0.714771 0.0423338 0.698078 0.714769 -0.142358 0.706863 0.692877 -0.288132 0.651638 0.701675 -0.295431 0.700866 0.649236 -0.450093 0.70612 0.546635 -0.583686 0.619565 0.524834 -0.562797 0.703125 0.434596 -0.654506 0.704873 0.273452 -0.762163 0.608094 0.222101 -0.698949 0.704868 0.120961 -0.706278 0.698069 -0.117775 -0.824141 0.561431 -0.0747429 -0.673281 0.706125 -0.219271 -0.585221 0.698082 -0.412551 -0.348271 0.698073 -0.625621 -0.348268 0.698076 -0.625619 -0.492297 0.706861 -0.507928 -0.645923 0.637421 -0.420092 -0.373094 0.694749 -0.614919 -0.373092 0.694751 -0.614917 -0.630565 0.694753 -0.345987 -0.630567 0.694751 -0.345987 -0.71908 0.694751 0.0156488 -0.719085 0.694746 0.0156508 -0.61492 0.694746 0.373097 -0.614916 0.694752 0.373092 -0.345988 0.694751 0.630566 -0.345988 0.694751 0.630566 0.0156493 0.694749 0.719082 0.0156492 0.69475 0.719082 -0.486392 0 -0.873741 -0.486392 0 -0.873741 -0.817328 0 -0.576173 -0.817328 0 -0.576173 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.379855 0 0.925046 -0.379855 0 0.925046 0.0591222 0 0.998251 0.0591222 0 0.998251 -0.486396 0 -0.873739 -0.486396 0 -0.873739 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.960065 0 0.279777 -0.960065 0 0.279777 -0.7436 0 0.668624 -0.7436 0 0.668624 -0.379854 0 0.925046 -0.379854 0 0.925046 0.0591223 0 0.998251 0.0591223 0 0.998251 -0.486398 0 -0.873737 -0.486398 0 -0.873737 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.960066 0 0.279773 -0.960066 0 0.279773 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591248 0 0.998251 0.0591248 0 0.998251 -0.518723 0 -0.854942 -0.518723 0 -0.854942 -0.876701 0 -0.481037 -0.876701 0 -0.481037 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.854943 0 0.518723 -0.854943 0 0.518723 -0.481036 0 0.876701 -0.481036 0 0.876701 0.021756 0 0.999763 0.021756 0 0.999763 -0.518727 0 -0.85494 -0.518727 0 -0.85494 -0.876698 0 -0.481041 -0.876698 0 -0.481041 -0.999763 0 0.0217559 -0.999763 0 0.0217559 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481037 0 0.8767 -0.481037 0 0.8767 0.0217558 0 0.999763 0.0217558 0 0.999763 -0.486396 0 -0.873739 -0.486396 0 -0.873739 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.98638 0 -0.164485 -0.98638 0 -0.164485 -0.960066 0 0.279773 -0.960066 0 0.279773 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591271 0 0.99825 0.0591271 0 0.99825 -0.518729 0 -0.854939 -0.518729 0 -0.854939 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217582 -0.999763 0 0.0217582 -0.854942 0 0.518723 -0.854942 0 0.518723 -0.481043 0 0.876697 -0.481043 0 0.876697 0.0217646 0 0.999763 0.0217646 0 0.999763 -0.486396 0 -0.873739 -0.486396 0 -0.873739 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.960065 0 0.279778 -0.960065 0 0.279778 -0.743603 0 0.668622 -0.743603 0 0.668622 -0.379854 0 0.925046 -0.379854 0 0.925046 0.0591274 0 0.99825 0.0591274 0 0.99825 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.960064 0 0.279782 -0.960064 0 0.279782 -0.743604 0 0.66862 -0.743604 0 0.66862 -0.379853 0 0.925047 -0.379853 0 0.925047 0.0591248 0 0.998251 0.0591248 0 0.998251 -0.486398 0 -0.873737 -0.486398 0 -0.873737 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.960066 0 0.279773 -0.960066 0 0.279773 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.379856 0 0.925046 -0.379856 0 0.925046 0.0591248 0 0.998251 0.0591248 0 0.998251 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.486395 0 -0.873739 -0.518725 0.00303677 -0.854936 -0.695972 0 -0.718069 -0.8383 0 -0.545209 -0.876687 0.00507028 -0.481034 -0.950844 0 -0.30967 -0.995913 0 -0.0903162 -0.999745 0.00609012 0.0217566 -0.985354 0 0.170519 -0.922703 0 0.385511 -0.854925 0.00609008 0.518715 -0.791488 0 0.611185 -0.635644 0 0.771983 -0.481033 0.00507054 0.876688 0.0591236 0 0.998251 0.021757 0.00303655 0.999759 -0.201252 0 0.97954 -0.414177 0 0.910197 0.0423362 0.698073 0.714774 0.0423338 0.698078 0.714769 -0.142356 0.706864 0.692877 -0.288131 0.651639 0.701675 -0.295429 0.700866 0.649237 -0.450094 0.70612 0.546635 -0.583687 0.619564 0.524834 -0.562797 0.703129 0.43459 -0.6545 0.704878 0.273454 -0.76216 0.608097 0.222102 -0.69894 0.704878 0.120954 -0.70627 0.698077 -0.117778 -0.824149 0.56142 -0.0747395 -0.673284 0.706121 -0.219275 -0.585224 0.698078 -0.412552 -0.348272 0.698073 -0.625621 -0.34827 0.698075 -0.625619 -0.492297 0.706861 -0.507928 -0.645923 0.637421 -0.420092 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.81733 0 -0.57617 -0.81733 0 -0.57617 -0.986378 0 -0.164493 -0.986378 0 -0.164493 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.743599 0 0.668625 -0.743599 0 0.668625 -0.379854 0 0.925046 -0.379854 0 0.925046 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.348271 0.698073 -0.625621 -0.348268 0.698076 -0.625619 -0.585229 0.698074 -0.412553 -0.585221 0.698082 -0.412551 -0.706263 0.698083 -0.11778 -0.706269 0.698078 -0.117778 -0.687429 0.698077 0.200325 -0.687431 0.698074 0.200327 -0.532436 0.698075 0.478752 -0.532434 0.698078 0.478749 -0.271984 0.698078 0.662354 -0.271984 0.698077 0.662354 0.0423338 0.698078 0.714769 0.042334 0.698078 0.71477 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518722 0 -0.854943 -0.48639 -0.00353185 -0.873735 -0.838296 0.00303678 -0.545207 -0.817327 0 -0.576175 -0.950851 0 -0.309649 -0.986371 0.00406454 -0.164485 -0.995913 0 -0.0903214 -0.985353 0 0.170526 -0.960056 0.00457498 0.279771 -0.922706 0 0.385504 -0.791488 0 0.611185 -0.743593 0.00406508 0.668621 -0.635636 0 0.771989 -0.414178 0 0.910196 -0.379855 0.00253693 0.925043 0.0217574 -0.00303662 0.999759 0.0591249 0 0.998251 0.0156494 0.694749 0.719082 0.0156491 0.69475 0.719081 -0.345988 0.694751 0.630566 -0.35177 0.527876 0.773049 -0.450092 0.706115 0.546643 -0.614921 0.694745 0.373098 -0.722339 0.408778 0.557788 -0.654499 0.704881 0.273448 -0.698935 0.704882 0.120958 -0.823728 0.566701 0.0179241 -0.37309 0.694753 -0.614916 -0.373096 0.694747 -0.61492 -0.597959 0.70086 -0.388897 -0.706627 0.591904 -0.387721 -0.673289 0.706121 -0.21926 -0.708156 0.703129 -0.0642241 -0.373096 0.694748 -0.614919 -0.373094 0.694749 -0.614919 -0.630569 0.694747 -0.34599 -0.630571 0.694746 -0.345989 -0.719086 0.694745 0.015649 -0.719085 0.694746 0.0156479 -0.614922 0.694747 0.373092 -0.614922 0.694746 0.373093 -0.345988 0.694747 0.63057 -0.345988 0.694746 0.630572 0.0156531 0.694745 0.719086 0.0156478 0.694748 0.719083 0.0217629 0 0.999763 0.0217629 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854944 0 0.51872 -0.854944 0 0.51872 -0.999763 0 0.0217573 -0.999763 0 0.0217573 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.518727 0 -0.85494 -0.518727 0 -0.85494 0.015653 -0.694749 0.719082 0.0156479 -0.694746 0.719085 -0.345989 -0.694746 0.630571 -0.345987 -0.694747 0.630571 -0.614923 -0.694746 0.373092 -0.614922 -0.694747 0.373093 -0.719085 -0.694746 0.015649 -0.719085 -0.694746 0.015648 -0.63057 -0.694746 -0.345991 -0.63057 -0.694747 -0.345988 -0.373096 -0.694749 -0.614918 -0.373095 -0.694748 -0.614919 -0.373096 0.694746 -0.614921 -0.373095 0.694746 -0.614921 -0.63057 0.694747 -0.345988 -0.630572 0.694746 -0.345988 -0.719085 0.694746 0.0156448 -0.719087 0.694744 0.0156479 -0.614921 0.694744 0.373098 -0.614921 0.694746 0.373094 -0.34599 0.694747 0.630569 -0.34599 0.694747 0.630569 0.0156488 0.694747 0.719084 0.0156504 0.694746 0.719085 0.021757 0 0.999763 0.021757 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.999763 0 0.0217514 -0.999763 0 0.0217514 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0156488 -0.694746 0.719085 0.0156504 -0.694747 0.719084 -0.34599 -0.694747 0.630569 -0.34599 -0.694747 0.630569 -0.614919 -0.694747 0.373097 -0.614923 -0.694745 0.373095 -0.719087 -0.694744 0.0156448 -0.719085 -0.694746 0.0156479 -0.630571 -0.694746 -0.345989 -0.630571 -0.694747 -0.345987 -0.373096 -0.694746 -0.61492 -0.373096 -0.694746 -0.614921 -0.348273 0.698073 -0.62562 -0.348272 0.698073 -0.62562 -0.585225 0.698074 -0.412559 -0.585228 0.698072 -0.412558 -0.706276 0.698072 -0.117772 -0.706271 0.698076 -0.11778 -0.687431 0.698076 0.20032 -0.687433 0.698072 0.20033 -0.53244 0.698072 0.478752 -0.532439 0.698071 0.478753 -0.271984 0.698072 0.66236 -0.271986 0.698073 0.662358 0.042335 0.698073 0.714774 0.0423351 0.698073 0.714774 0.0591249 0 0.998251 0.0591249 0 0.998251 -0.379851 0 0.925048 -0.379851 0 0.925048 -0.743602 0 0.668623 -0.743602 0 0.668623 -0.960068 0 0.279768 -0.960068 0 0.279768 -0.98638 0 -0.16448 -0.98638 0 -0.16448 -0.817323 0 -0.576179 -0.817323 0 -0.576179 -0.486396 0 -0.873738 -0.486396 0 -0.873738 0.042335 -0.698073 0.714774 0.0423352 -0.698073 0.714774 -0.271983 -0.698073 0.662358 -0.271986 -0.698072 0.662359 -0.53244 -0.698071 0.478753 -0.532439 -0.698072 0.478753 -0.687436 -0.698071 0.200322 -0.687429 -0.698075 0.200329 -0.706271 -0.698077 -0.117772 -0.706274 -0.698072 -0.11778 -0.585226 -0.698072 -0.41256 -0.585227 -0.698073 -0.412557 -0.348273 -0.698073 -0.62562 -0.348272 -0.698073 -0.62562 0.0591236 0 0.998251 0.0217571 -0.00161871 0.999762 -0.201253 0 0.979539 -0.414177 0 0.910196 -0.481038 -0.002703 0.876696 -0.635644 0 0.771982 -0.791487 0 0.611186 -0.854937 -0.00324655 0.518722 -0.922704 0 0.385509 -0.985354 0 0.170521 -0.999758 -0.00324657 0.0217576 -0.995913 0 -0.0903169 -0.950845 0 -0.309667 -0.876696 -0.0027029 -0.481038 -0.486395 0 -0.873739 -0.518726 -0.00161881 -0.854939 -0.695969 0 -0.718072 -0.8383 0 -0.545209 -0.348273 -0.698069 -0.625624 -0.348273 -0.69807 -0.625623 -0.492299 -0.706856 -0.507933 -0.619972 -0.651633 -0.437047 -0.597958 -0.70086 -0.388897 -0.673291 -0.706114 -0.219274 -0.774261 -0.619555 -0.129116 -0.708162 -0.703123 -0.0642215 -0.687433 -0.698073 0.200326 -0.871122 -0.467354 0.150753 -0.654505 -0.704872 0.273455 -0.532437 -0.698073 0.478753 -0.654981 -0.561418 0.505776 -0.450098 -0.706115 0.546639 -0.271986 -0.698072 0.662358 0.0423343 -0.698069 0.714778 0.0423363 -0.698073 0.714774 -0.142357 -0.706859 0.692882 -0.319132 -0.637415 0.701325 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217585 -0.999763 0 0.0217585 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.518727 0 -0.85494 -0.518727 0 -0.85494 0.015649 -0.694742 0.719089 0.0156508 -0.694746 0.719085 -0.345991 -0.694745 0.630571 -0.345988 -0.694748 0.630569 -0.61492 -0.694748 0.373095 -0.614922 -0.694745 0.373095 -0.719085 -0.694746 0.0156499 -0.719087 -0.694744 0.015649 -0.630574 -0.694741 -0.345993 -0.63057 -0.694747 -0.345988 -0.373096 -0.694749 -0.614918 -0.373097 -0.694741 -0.614925 0.0591236 0 0.998251 0.021757 -0.00161871 0.999762 -0.379854 0.00135245 0.925045 -0.414178 0 0.910196 -0.635644 0 0.771983 -0.743598 0.00216686 0.668624 -0.791485 0 0.611188 -0.922706 0 0.385505 -0.960063 0.00243884 0.279773 -0.985353 0 0.170525 -0.995913 0 -0.0903162 -0.986376 0.00216697 -0.16449 -0.950844 0 -0.30967 -0.817329 0 -0.576171 -0.838299 0.00161865 -0.545208 -0.486393 -0.00188291 -0.873738 -0.518726 0 -0.854941 0.0423343 -0.698069 0.714778 0.0423362 -0.698073 0.714774 -0.271986 -0.698073 0.662358 -0.271986 -0.698073 0.662358 -0.532436 -0.698074 0.478753 -0.53244 -0.698071 0.478754 -0.687437 -0.698069 0.200327 -0.687436 -0.69807 0.200327 -0.706278 -0.698068 -0.11778 -0.706277 -0.69807 -0.117779 -0.585232 -0.69807 -0.412555 -0.585233 -0.698068 -0.412558 -0.348273 -0.698068 -0.625625 -0.348273 -0.698071 -0.625622 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.201256 0 0.979539 -0.201256 0 0.979539 -0.41418 0 0.910195 -0.41418 0 0.910195 -0.635633 0 0.771992 -0.635633 0 0.771992 -0.791488 0 0.611185 -0.791488 0 0.611185 -0.922707 0 0.385503 -0.922707 0 0.385503 -0.985353 0 0.170526 -0.985353 0 0.170526 -0.995913 0 -0.0903217 -0.995913 0 -0.0903217 -0.950851 0 -0.309649 -0.950851 0 -0.309649 -0.838297 0 -0.545215 -0.838297 0 -0.545215 -0.695971 0 -0.71807 -0.695971 0 -0.71807 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.348271 -0.698072 -0.625621 -0.348271 -0.698072 -0.625622 -0.4923 -0.706857 -0.507932 -0.619969 -0.651635 -0.437047 -0.597958 -0.700858 -0.388902 -0.673298 -0.706112 -0.219263 -0.774255 -0.619563 -0.129115 -0.708161 -0.703124 -0.0642248 -0.687431 -0.698074 0.200327 -0.871117 -0.467362 0.150756 -0.654511 -0.704869 0.273452 -0.532439 -0.69807 0.478755 -0.654987 -0.561408 0.505779 -0.450089 -0.706116 0.546644 -0.271987 -0.698073 0.662357 0.0423343 -0.698069 0.714778 0.0423364 -0.698073 0.714774 -0.142359 -0.706859 0.692881 -0.319134 -0.637415 0.701324 -0.373096 0.694746 -0.61492 -0.373092 0.694752 -0.614916 -0.630566 0.694751 -0.345988 -0.630571 0.694746 -0.345988 -0.719082 0.69475 0.0156493 -0.719081 0.69475 0.0156493 -0.614919 0.694749 0.373094 -0.614917 0.694751 0.373092 -0.345987 0.694753 0.630565 -0.345987 0.694751 0.630567 0.0156488 0.694751 0.71908 0.0156508 0.694746 0.719085 -0.373097 0.694745 -0.61492 -0.373091 0.694753 -0.614916 -0.630565 0.694752 -0.345988 -0.630572 0.694746 -0.345988 -0.719082 0.694749 0.0156498 -0.71908 0.694751 0.0156489 -0.614918 0.69475 0.373094 -0.614917 0.694752 0.373092 -0.345987 0.694753 0.630564 -0.345987 0.69475 0.630568 0.0156488 0.694751 0.71908 0.0156508 0.694746 0.719085 0.0156508 0.694746 0.719085 0.0156488 0.694751 0.71908 -0.345987 0.69475 0.630568 -0.351769 0.527882 0.773046 -0.450092 0.706123 0.546632 -0.614915 0.694754 0.37309 -0.722341 0.408765 0.557795 -0.654503 0.704877 0.273451 -0.69894 0.704877 0.120958 -0.823731 0.566698 0.0179263 -0.373095 0.694748 -0.614919 -0.373092 0.694752 -0.614917 -0.597954 0.700865 -0.388894 -0.706625 0.591909 -0.387718 -0.673291 0.706114 -0.219277 -0.708162 0.703124 -0.064221 0.0423364 0.698073 0.714774 0.0423338 0.698078 0.714769 -0.142358 0.706863 0.692877 -0.288133 0.651637 0.701675 -0.295432 0.700866 0.649236 -0.450086 0.706121 0.546641 -0.58369 0.619557 0.524839 -0.5628 0.703126 0.434593 -0.687431 0.698074 0.200327 -0.815726 0.467378 0.340807 -0.69894 0.704877 0.120959 -0.70627 0.698077 -0.117778 -0.824141 0.561432 -0.0747432 -0.673294 0.706116 -0.219261 -0.585227 0.698074 -0.412556 -0.348269 0.698077 -0.625618 -0.348269 0.698076 -0.625618 -0.492297 0.706861 -0.507928 -0.645919 0.637424 -0.420095 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518726 0 -0.85494 -0.518726 0 -0.85494 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.999763 0 0.0217579 -0.999763 0 0.0217579 -0.854943 0 0.518722 -0.854943 0 0.518722 -0.481035 0 0.876702 -0.481035 0 0.876702 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373096 0.694746 -0.61492 -0.373092 0.694752 -0.614916 -0.630566 0.694751 -0.345988 -0.630567 0.69475 -0.345988 -0.719082 0.694749 0.0156494 -0.719082 0.69475 0.0156492 -0.61492 0.694749 0.373092 -0.614921 0.694746 0.373094 -0.345988 0.694744 0.630574 -0.345987 0.694751 0.630567 0.0156488 0.694751 0.71908 0.0156469 0.694755 0.719076 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.486395 0 -0.873739 -0.486395 0 -0.873739 -0.817329 0 -0.576171 -0.817329 0 -0.576171 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743601 0 0.668624 -0.743601 0 0.668624 -0.379853 0 0.925047 -0.379853 0 0.925047 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.348272 0.698073 -0.625621 -0.34827 0.698075 -0.625619 -0.585227 0.698076 -0.412552 -0.585224 0.698078 -0.412552 -0.706268 0.698079 -0.117778 -0.70627 0.698077 -0.117778 -0.687428 0.698078 0.200324 -0.687428 0.698078 0.200324 -0.532434 0.698078 0.478749 -0.532436 0.698075 0.478752 -0.271984 0.698076 0.662356 -0.271984 0.698079 0.662352 0.0423338 0.698078 0.714769 0.0423362 0.698073 0.714774 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.48104 0 0.876699 -0.48104 0 0.876699 0.021757 0 0.999763 0.021757 0 0.999763 -0.373094 0.69475 -0.614918 -0.373093 0.69475 -0.614918 -0.630566 0.694752 -0.345987 -0.630566 0.694752 -0.345987 -0.71908 0.694751 0.0156488 -0.719085 0.694746 0.0156508 -0.61492 0.694745 0.373097 -0.614917 0.694752 0.373092 -0.345989 0.69475 0.630566 -0.345989 0.694748 0.630569 0.0156488 0.694746 0.719085 0.0156489 0.694746 0.719085 0.0423389 0.698072 0.714775 0.0423389 0.698072 0.714775 -0.142357 0.706858 0.692882 -0.275157 0.689416 0.67007 -0.29544 0.700862 0.649236 -0.450081 0.706116 0.546651 -0.542403 0.684056 0.487715 -0.562803 0.703124 0.434591 -0.654505 0.704872 0.273455 -0.701929 0.682242 0.204551 -0.698945 0.704873 0.120956 -0.706274 0.698073 -0.117779 -0.740205 0.669023 -0.0671273 -0.673288 0.706116 -0.219278 -0.585227 0.698074 -0.412555 -0.348272 0.698072 -0.625622 -0.348271 0.698072 -0.625622 -0.492298 0.706858 -0.507932 -0.611363 0.684208 -0.397611 0.0591303 0 0.99825 0.0217628 0.00192601 0.999761 -0.201253 0 0.979539 -0.41419 0 0.91019 -0.481037 0.00321547 0.876694 -0.635621 0 0.772001 -0.791491 0 0.611181 -0.854936 0.0038627 0.518719 -0.922704 0 0.38551 -0.985354 0 0.17052 -0.999756 0.00386279 0.0217572 -0.995913 0 -0.0903169 -0.950843 0 -0.309672 -0.876694 0.00321578 -0.481037 -0.838302 0 -0.545206 -0.695969 0 -0.718072 -0.518726 0.00192609 -0.854939 -0.486395 0 -0.873739 0.0156531 -0.694745 0.719086 0.0156531 -0.694745 0.719086 -0.34599 -0.694745 0.630571 -0.345992 -0.694744 0.630571 -0.614923 -0.694745 0.373095 -0.614921 -0.694746 0.373096 -0.719085 -0.694746 0.0156491 -0.719085 -0.694746 0.0156493 -0.63057 -0.694746 -0.34599 -0.63057 -0.694746 -0.345991 -0.373097 -0.694746 -0.614921 -0.373096 -0.694745 -0.614922 -0.37309 0.694748 -0.614922 -0.373096 0.694745 -0.614921 -0.630573 0.694745 -0.345988 -0.630571 0.694746 -0.345989 -0.719086 0.694745 0.015649 -0.719085 0.694746 0.0156479 -0.614922 0.694747 0.373092 -0.614922 0.694744 0.373096 -0.34599 0.694744 0.630573 -0.345992 0.694745 0.63057 0.0156531 0.694745 0.719086 0.0156478 0.694748 0.719083 0.0217629 0 0.999763 0.0217629 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854944 0 0.51872 -0.854944 0 0.51872 -0.999763 0 0.0217573 -0.999763 0 0.0217573 -0.876701 0 -0.481035 -0.876701 0 -0.481035 -0.518719 0 -0.854945 -0.518719 0 -0.854945 0.015653 -0.694749 0.719082 0.0156479 -0.694746 0.719085 -0.345989 -0.694746 0.630571 -0.345993 -0.694744 0.630571 -0.614925 -0.694744 0.373093 -0.614921 -0.694746 0.373096 -0.719085 -0.694746 0.015649 -0.719085 -0.694746 0.015648 -0.630572 -0.694746 -0.345987 -0.630572 -0.694745 -0.345989 -0.373092 -0.694745 -0.614925 -0.373095 -0.694748 -0.614919 0.0423329 0.698073 0.714774 0.0423341 0.698073 0.714775 -0.142365 0.706858 0.692881 -0.275153 0.689418 0.67007 -0.295429 0.70086 0.649243 -0.450094 0.706115 0.546642 -0.542402 0.684056 0.487716 -0.562803 0.703126 0.434588 -0.654505 0.704874 0.273452 -0.701928 0.682244 0.204549 -0.698944 0.704871 0.120969 -0.706274 0.698072 -0.11778 -0.740204 0.669022 -0.0671305 -0.67329 0.706115 -0.219276 -0.58523 0.698073 -0.412553 -0.348269 0.698074 -0.625621 -0.348269 0.698074 -0.625621 -0.492291 0.70686 -0.507937 -0.61136 0.68421 -0.397613 -0.486391 0 -0.873741 -0.486391 0 -0.873741 -0.695961 0 -0.71808 -0.695961 0 -0.71808 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.950844 0 -0.30967 -0.950844 0 -0.30967 -0.995913 0 -0.0903212 -0.995913 0 -0.0903212 -0.985351 0 0.170538 -0.985351 0 0.170538 -0.922706 0 0.385505 -0.922706 0 0.385505 -0.791493 0 0.611179 -0.791493 0 0.611179 -0.635639 0 0.771987 -0.635639 0 0.771987 -0.414174 0 0.910198 -0.414174 0 0.910198 -0.201264 0 0.979537 -0.201264 0 0.979537 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.348269 -0.698074 -0.625621 -0.348269 -0.698074 -0.625621 -0.492291 -0.70686 -0.507937 -0.592044 -0.689418 -0.417357 -0.597958 -0.700861 -0.388897 -0.67329 -0.706115 -0.219276 -0.719493 -0.684057 -0.119985 -0.708162 -0.703123 -0.0642245 -0.687433 -0.698073 0.200325 -0.746764 -0.65241 0.129245 -0.654505 -0.704874 0.273452 -0.532435 -0.698074 0.478754 -0.588274 -0.669019 0.454256 -0.450094 -0.706115 0.546642 -0.271986 -0.698073 0.662358 0.0423341 -0.698073 0.714774 0.0423329 -0.698073 0.714774 -0.142365 -0.706858 0.692881 -0.302051 -0.68421 0.663794 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.201253 0 0.979539 -0.201253 0 0.979539 -0.414177 0 0.910196 -0.414177 0 0.910196 -0.635644 0 0.771982 -0.635644 0 0.771982 -0.791487 0 0.611186 -0.791487 0 0.611186 -0.922704 0 0.385509 -0.922704 0 0.385509 -0.985354 0 0.170521 -0.985354 0 0.170521 -0.995913 0 -0.0903178 -0.995913 0 -0.0903178 -0.950847 0 -0.309661 -0.950847 0 -0.309661 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.695948 0 -0.718092 -0.695948 0 -0.718092 -0.486395 0 -0.873739 -0.486395 0 -0.873739 -0.373095 -0.69475 -0.614917 -0.380872 -0.621958 -0.684182 -0.492286 -0.706853 -0.507949 -0.630574 -0.694742 -0.345992 -0.711989 -0.527871 -0.46306 -0.673292 -0.706116 -0.21927 -0.719086 -0.694745 0.0156495 -0.908909 -0.408766 -0.0824275 -0.698946 -0.704871 0.120957 -0.654507 -0.704871 0.273455 -0.704409 -0.566697 0.42739 -0.5628 -0.703125 0.434594 -0.450096 -0.706117 0.546637 -0.38772 -0.591908 0.706625 0.0423343 -0.698069 0.714778 0.0167663 -0.637416 0.770338 -0.142357 -0.706859 0.692882 -0.295432 -0.700861 0.649241 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.201252 0 0.97954 -0.201252 0 0.97954 -0.414177 0 0.910196 -0.414177 0 0.910196 -0.635649 0 0.771979 -0.635649 0 0.771979 -0.791485 0 0.611188 -0.791485 0 0.611188 -0.922706 0 0.385505 -0.922706 0 0.385505 -0.985353 0 0.170525 -0.985353 0 0.170525 -0.995913 0 -0.0903171 -0.995913 0 -0.0903171 -0.950846 0 -0.309664 -0.950846 0 -0.309664 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.695951 0 -0.718089 -0.695951 0 -0.718089 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.348269 -0.698078 -0.625616 -0.34827 -0.698076 -0.625618 -0.492283 -0.70686 -0.507943 -0.619972 -0.651631 -0.437049 -0.597957 -0.700862 -0.388896 -0.67329 -0.706116 -0.219272 -0.774259 -0.619558 -0.129116 -0.708161 -0.703124 -0.0642216 -0.687432 -0.698074 0.200325 -0.871115 -0.467367 0.150755 -0.654506 -0.704873 0.273452 -0.532436 -0.698074 0.478753 -0.654978 -0.561422 0.505776 -0.450102 -0.706113 0.546638 -0.271986 -0.698071 0.662359 0.0423343 -0.698069 0.714778 0.0423364 -0.698073 0.714774 -0.142357 -0.706859 0.692882 -0.319132 -0.637414 0.701326 0.0591236 0 0.998251 0.021757 0.00161871 0.999762 -0.201252 0 0.97954 -0.414177 0 0.910196 -0.481037 0.002703 0.876696 -0.635644 0 0.771983 -0.791488 0 0.611185 -0.854937 0.00324651 0.518722 -0.922703 0 0.385511 -0.985354 0 0.170519 -0.999758 0.00324653 0.021757 -0.995913 0 -0.0903171 -0.950846 0 -0.309664 -0.876697 0.00270296 -0.481036 -0.8383 0 -0.545209 -0.695951 0 -0.718089 -0.518722 0.00161862 -0.854941 -0.486395 0 -0.873739 0.015649 -0.694742 0.719089 0.0156508 -0.694746 0.719085 -0.345989 -0.694747 0.630569 -0.345989 -0.694747 0.630569 -0.614921 -0.694746 0.373096 -0.614926 -0.694741 0.373096 -0.719089 -0.694742 0.015649 -0.719085 -0.694746 0.0156508 -0.63057 -0.694748 -0.345988 -0.630574 -0.694741 -0.345993 -0.373098 -0.694739 -0.614928 -0.373096 -0.694749 -0.614917 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854943 0 0.518723 -0.854943 0 0.518723 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876702 0 -0.481035 -0.876702 0 -0.481035 -0.518722 0 -0.854943 -0.518722 0 -0.854943 0.0156489 -0.694746 0.719085 0.015649 -0.694746 0.719085 -0.345988 -0.694748 0.63057 -0.34599 -0.694745 0.630571 -0.614926 -0.694741 0.373096 -0.614918 -0.694749 0.373095 -0.71908 -0.694751 0.0156488 -0.719084 -0.694747 0.0156471 -0.630572 -0.694746 -0.345987 -0.630577 -0.694739 -0.345992 -0.373097 -0.694741 -0.614927 -0.373096 -0.694741 -0.614926 0.0156508 0.694746 0.719085 0.0462964 0.621967 0.781674 -0.142356 0.706863 0.692877 -0.345987 0.694751 0.630567 -0.351769 0.527878 0.773048 -0.450094 0.706122 0.546633 -0.614917 0.694751 0.373092 -0.72234 0.408771 0.557791 -0.654503 0.704875 0.273454 -0.698942 0.704876 0.120956 -0.823729 0.566701 0.0179268 -0.708157 0.703128 -0.0642217 -0.673287 0.70612 -0.219268 -0.706623 0.591909 -0.38772 -0.348268 0.698082 -0.625613 -0.399688 0.63742 -0.658745 -0.492283 0.706858 -0.507946 -0.597957 0.700861 -0.388896 0.0423364 0.698073 0.714774 0.0423338 0.698078 0.714769 -0.142356 0.706863 0.692878 -0.288131 0.651636 0.701677 -0.29543 0.700864 0.649239 -0.4501 0.706117 0.546634 -0.583685 0.619565 0.524834 -0.562796 0.703129 0.434593 -0.654502 0.704877 0.27345 -0.762156 0.608103 0.222101 -0.69894 0.704877 0.120958 -0.70627 0.698077 -0.117778 -0.824148 0.561422 -0.0747401 -0.673286 0.706121 -0.21927 -0.585223 0.698078 -0.412553 -0.348266 0.698083 -0.625612 -0.348268 0.698081 -0.625614 -0.49228 0.706865 -0.50794 -0.645927 0.637416 -0.420094 0.0423362 0.698073 0.714774 0.0423338 0.698078 0.714769 -0.142356 0.706864 0.692877 -0.288131 0.651639 0.701675 -0.295429 0.700866 0.649237 -0.450094 0.70612 0.546635 -0.583687 0.619564 0.524834 -0.562797 0.703129 0.43459 -0.687428 0.698078 0.200324 -0.815735 0.467354 0.340819 -0.69894 0.704878 0.120954 -0.70627 0.698077 -0.117778 -0.824148 0.561422 -0.0747401 -0.673286 0.706121 -0.21927 -0.585224 0.698078 -0.412552 -0.348268 0.698081 -0.625614 -0.348267 0.698083 -0.625613 -0.492278 0.706868 -0.507937 -0.645923 0.637421 -0.420092 -0.373094 0.694746 -0.614922 -0.373095 0.694745 -0.614923 -0.630575 0.694743 -0.345988 -0.630568 0.69475 -0.345987 -0.71908 0.694751 0.0156488 -0.719076 0.694755 0.015647 -0.614915 0.694754 0.37309 -0.61492 0.694746 0.373097 -0.345987 0.694749 0.630568 -0.345987 0.694752 0.630566 0.0156488 0.694751 0.71908 0.0156489 0.694751 0.71908 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.486395 0 -0.873739 -0.486395 0 -0.873739 -0.817329 0 -0.576172 -0.817329 0 -0.576172 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.743598 0 0.668627 -0.743598 0 0.668627 -0.379859 0 0.925044 -0.379859 0 0.925044 0.0591303 0 0.99825 0.0591303 0 0.99825 -0.348271 0.698074 -0.62562 -0.348271 0.698074 -0.62562 -0.585228 0.698075 -0.412553 -0.585226 0.698077 -0.412553 -0.70627 0.698077 -0.117778 -0.706269 0.698077 -0.117779 -0.687431 0.698075 0.200325 -0.687431 0.698074 0.200325 -0.532437 0.698071 0.478756 -0.532435 0.698077 0.47875 -0.271988 0.698077 0.662352 -0.271987 0.698069 0.662361 0.0423391 0.698068 0.714778 0.0423315 0.698082 0.714765 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.960065 0 0.279776 -0.960065 0 0.279776 -0.743601 0 0.668624 -0.743601 0 0.668624 -0.379853 0 0.925047 -0.379853 0 0.925047 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.34827 0.698075 -0.625619 -0.348265 0.69808 -0.625616 -0.585224 0.698077 -0.412554 -0.585223 0.698078 -0.412553 -0.706268 0.698079 -0.117778 -0.706268 0.698079 -0.117778 -0.68743 0.698076 0.200326 -0.687428 0.698078 0.200324 -0.532434 0.698078 0.478749 -0.532436 0.698075 0.478752 -0.271984 0.698076 0.662356 -0.271984 0.698077 0.662354 0.0423338 0.698078 0.714769 0.0423316 0.698082 0.714765 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.486397 0 -0.873738 -0.486397 0 -0.873738 -0.817326 0 -0.576175 -0.817326 0 -0.576175 -0.986378 0 -0.164493 -0.986378 0 -0.164493 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.743599 0 0.668625 -0.743599 0 0.668625 -0.379854 0 0.925046 -0.379854 0 0.925046 0.0591236 0 0.998251 0.0591236 0 0.998251 -0.348273 0.698073 -0.62562 -0.348269 0.698077 -0.625617 -0.585222 0.69808 -0.412553 -0.585228 0.698075 -0.412554 -0.706272 0.698074 -0.117781 -0.706277 0.698069 -0.117779 -0.687437 0.698068 0.200327 -0.687433 0.698073 0.200324 -0.532436 0.698075 0.478752 -0.532434 0.698078 0.478749 -0.271984 0.698078 0.662354 -0.271984 0.698077 0.662354 0.0423338 0.698078 0.714769 0.0423337 0.698078 0.714769 -0.373097 0.694744 -0.614922 -0.373096 0.694745 -0.614922 -0.63057 0.694746 -0.34599 -0.630572 0.694745 -0.345989 -0.719085 0.694746 0.0156493 -0.719085 0.694746 0.0156495 -0.614922 0.694746 0.373094 -0.614922 0.694745 0.373096 -0.345991 0.694744 0.630572 -0.345992 0.694745 0.63057 0.0156531 0.694745 0.719086 0.0156478 0.694748 0.719083 0.0217628 0 0.999763 0.0217628 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854943 0 0.518722 -0.854943 0 0.518722 -0.999763 0 0.0217576 -0.999763 0 0.0217576 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.518726 0 -0.85494 -0.518726 0 -0.85494 0.015653 -0.694749 0.719082 0.0156479 -0.694746 0.719085 -0.34599 -0.694745 0.630571 -0.345992 -0.694744 0.630571 -0.614923 -0.694745 0.373094 -0.614921 -0.694746 0.373096 -0.719085 -0.694746 0.0156493 -0.719085 -0.694746 0.0156494 -0.630572 -0.694744 -0.345991 -0.630572 -0.694745 -0.345989 -0.373097 -0.694746 -0.614921 -0.373096 -0.694745 -0.614922 0.0156531 0.694745 0.719086 0.0156447 0.69475 0.719081 -0.34599 0.694749 0.630567 -0.311019 0.660379 0.683496 -0.450099 0.706118 0.546634 -0.614919 0.694748 0.373095 -0.607753 0.640612 0.469311 -0.654503 0.704872 0.27346 -0.698946 0.704872 0.12095 -0.739319 0.673163 0.0160881 -0.373098 0.694744 -0.614921 -0.373096 0.694745 -0.614921 -0.597956 0.700861 -0.388899 -0.645314 0.676902 -0.354081 -0.673291 0.706115 -0.219272 -0.708162 0.703123 -0.0642175 0.0591169 0 0.998251 0.0217513 -0.00192591 0.999762 -0.379854 0.0016091 0.925045 -0.414177 0 0.910196 -0.635649 0 0.771979 -0.743597 0.00257804 0.668623 -0.791484 0 0.61119 -0.922701 0 0.385517 -0.960062 0.0029021 0.279773 -0.985356 0 0.170512 -0.995914 0 -0.0903113 -0.986376 0.00257831 -0.164485 -0.950846 0 -0.309664 -0.817325 0 -0.576176 -0.838296 0.001926 -0.545212 -0.486395 -0.0022402 -0.873736 -0.518727 0 -0.85494 0.0423294 -0.698071 0.714776 0.0423387 -0.698076 0.714771 -0.271985 -0.698076 0.662355 -0.271989 -0.698074 0.662355 -0.532437 -0.698073 0.478753 -0.532438 -0.698073 0.478753 -0.687433 -0.698073 0.200325 -0.687431 -0.698074 0.200327 -0.706273 -0.698074 -0.117776 -0.706274 -0.698072 -0.11778 -0.585228 -0.698071 -0.412559 -0.585229 -0.698073 -0.412556 -0.348273 -0.698073 -0.62562 -0.348272 -0.698072 -0.625622 0.0423358 0.698073 0.714774 0.0423389 0.698072 0.714775 -0.142381 0.706858 0.692878 -0.275153 0.689418 0.67007 -0.295433 0.700862 0.649239 -0.450084 0.706117 0.546647 -0.542403 0.684057 0.487714 -0.562803 0.703126 0.434588 -0.687432 0.698075 0.200324 -0.699293 0.652395 0.29218 -0.698947 0.704872 0.120952 -0.706274 0.698072 -0.117781 -0.740204 0.669022 -0.0671305 -0.673292 0.706114 -0.219272 -0.585232 0.698072 -0.412553 -0.348273 0.698073 -0.62562 -0.348271 0.698074 -0.62562 -0.492306 0.706859 -0.507923 -0.611357 0.684211 -0.397615 -0.486397 0 -0.873738 -0.486397 0 -0.873738 -0.695982 0 -0.71806 -0.695982 0 -0.71806 -0.838298 0 -0.545213 -0.838298 0 -0.545213 -0.950846 0 -0.309664 -0.950846 0 -0.309664 -0.995913 0 -0.0903212 -0.995913 0 -0.0903212 -0.985355 0 0.170514 -0.985355 0 0.170514 -0.922698 0 0.385523 -0.922698 0 0.385523 -0.791493 0 0.611179 -0.791493 0 0.611179 -0.635627 0 0.771996 -0.635627 0 0.771996 -0.41418 0 0.910195 -0.41418 0 0.910195 -0.201286 0 0.979532 -0.201286 0 0.979532 0.0591303 0 0.99825 0.0591303 0 0.99825 -0.348271 -0.698073 -0.62562 -0.348272 -0.698074 -0.625619 -0.492305 -0.706859 -0.507923 -0.592045 -0.689418 -0.417355 -0.597957 -0.700859 -0.3889 -0.673292 -0.706114 -0.219272 -0.719493 -0.684057 -0.119985 -0.708162 -0.703123 -0.0642245 -0.687434 -0.698072 0.200324 -0.746777 -0.652399 0.129229 -0.654499 -0.704875 0.273464 -0.532437 -0.698074 0.478752 -0.588272 -0.669021 0.454255 -0.450084 -0.706117 0.546647 -0.271986 -0.698074 0.662357 0.0423388 -0.698074 0.714773 0.0423359 -0.698072 0.714775 -0.142381 -0.706858 0.692878 -0.302055 -0.684209 0.663793 0.0591303 0 0.99825 0.0591303 0 0.99825 -0.37986 0 0.925044 -0.37986 0 0.925044 -0.743596 0 0.668629 -0.743596 0 0.668629 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.817329 0 -0.576171 -0.817329 0 -0.576171 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0.0423385 -0.698079 0.714768 0.0423325 -0.698065 0.714782 -0.271993 -0.698064 0.662365 -0.271986 -0.698073 0.662358 -0.532434 -0.698074 0.478755 -0.532444 -0.698065 0.478758 -0.687439 -0.698066 0.200327 -0.687438 -0.698067 0.200327 -0.706277 -0.69807 -0.11778 -0.706277 -0.69807 -0.11778 -0.585232 -0.69807 -0.412555 -0.585233 -0.698068 -0.412558 -0.348273 -0.698068 -0.625625 -0.348273 -0.698071 -0.625622 0.021757 0 0.999763 0.021757 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0156488 -0.694746 0.719085 0.015649 -0.694747 0.719084 -0.345992 -0.694743 0.630573 -0.345987 -0.694749 0.630569 -0.614917 -0.69475 0.373095 -0.614926 -0.694741 0.373096 -0.719089 -0.694742 0.015649 -0.719085 -0.694746 0.0156508 -0.630571 -0.694745 -0.34599 -0.630575 -0.69474 -0.345995 -0.373098 -0.694741 -0.614925 -0.373098 -0.694741 -0.614925 0.0591236 0 0.998251 0.021757 -0.00161871 0.999762 -0.201248 0 0.97954 -0.414177 0 0.910196 -0.481038 -0.00270305 0.876695 -0.635649 0 0.771979 -0.791488 0 0.611185 -0.854935 -0.00324644 0.518724 -0.922701 0 0.385517 -0.985356 0 0.170512 -0.999758 -0.00324638 0.021757 -0.995914 0 -0.0903117 -0.950845 0 -0.309667 -0.876696 -0.00270291 -0.481037 -0.486397 0 -0.873738 -0.518724 -0.00161865 -0.85494 -0.695951 0 -0.718089 -0.8383 0 -0.545209 -0.348272 -0.69807 -0.625623 -0.348272 -0.698075 -0.625618 -0.492283 -0.706862 -0.507942 -0.619973 -0.651632 -0.437046 -0.59796 -0.700858 -0.388898 -0.673293 -0.706112 -0.219275 -0.774264 -0.619551 -0.129117 -0.708161 -0.703124 -0.0642177 -0.687432 -0.698074 0.200323 -0.871131 -0.46734 0.150746 -0.654499 -0.704878 0.273458 -0.532432 -0.698077 0.478753 -0.654987 -0.561408 0.505779 -0.450106 -0.706107 0.546642 -0.271992 -0.698066 0.662363 0.0423343 -0.698069 0.714778 0.0423361 -0.698073 0.714774 -0.142353 -0.706861 0.692881 -0.319131 -0.637416 0.701325 0.0591249 0 0.998251 0.0217577 -0.00161874 0.999762 -0.201251 0 0.97954 -0.414178 0 0.910196 -0.481038 -0.00270299 0.876696 -0.635646 0 0.771981 -0.791488 0 0.611185 -0.854936 -0.00324645 0.518724 -0.922701 0 0.385516 -0.985355 0 0.170513 -0.999758 -0.00324639 0.021757 -0.995914 0 -0.0903115 -0.950845 0 -0.309667 -0.876696 -0.00270291 -0.481038 -0.486396 0 -0.873738 -0.518724 -0.00161868 -0.85494 -0.695954 0 -0.718086 -0.8383 0 -0.545209 -0.348272 -0.698071 -0.625622 -0.348272 -0.698075 -0.625618 -0.492284 -0.706862 -0.50794 -0.619972 -0.651633 -0.437045 -0.59796 -0.700858 -0.388898 -0.673293 -0.706112 -0.219275 -0.774264 -0.619551 -0.129117 -0.708161 -0.703124 -0.0642175 -0.698946 -0.704873 0.120951 -0.762167 -0.60809 0.222102 -0.654499 -0.704877 0.273458 -0.532433 -0.698076 0.478753 -0.654986 -0.56141 0.505779 -0.450102 -0.70611 0.546642 -0.271989 -0.698069 0.66236 0.042335 -0.698072 0.714775 0.0423346 -0.698071 0.714776 -0.142355 -0.706859 0.692882 -0.319133 -0.637414 0.701325 -0.34827 0.698075 -0.625619 -0.348272 0.698073 -0.625621 -0.58523 0.698072 -0.412554 -0.585227 0.698075 -0.412554 -0.706272 0.698074 -0.117779 -0.706272 0.698074 -0.117779 -0.687434 0.698072 0.200326 -0.687435 0.698071 0.200326 -0.532438 0.698068 0.478759 -0.532434 0.698078 0.478749 -0.271988 0.698078 0.662351 -0.271987 0.698069 0.662362 0.0423391 0.698068 0.714778 0.0423315 0.698082 0.714765 -0.373096 0.694746 -0.614921 -0.373096 0.694745 -0.614921 -0.630572 0.694744 -0.345991 -0.630567 0.694749 -0.34599 -0.71908 0.694751 0.0156488 -0.719085 0.694746 0.0156508 -0.61492 0.694745 0.373097 -0.614915 0.694754 0.37309 -0.345987 0.694754 0.630563 -0.345987 0.694748 0.63057 0.0156487 0.694751 0.71908 0.0156489 0.694751 0.71908 -0.373095 0.694748 -0.61492 -0.373097 0.694745 -0.614921 -0.630572 0.694744 -0.345991 -0.630564 0.694751 -0.34599 -0.71908 0.694751 0.0156488 -0.719085 0.694746 0.0156508 -0.61492 0.694745 0.373097 -0.614917 0.694752 0.373092 -0.345989 0.69475 0.630566 -0.345989 0.694747 0.630569 0.0156487 0.694751 0.71908 0.0156508 0.694746 0.719085 -0.373094 0.694749 -0.614919 -0.373096 0.694747 -0.61492 -0.630572 0.694744 -0.345991 -0.630565 0.69475 -0.34599 -0.71908 0.694751 0.0156488 -0.719085 0.694746 0.0156508 -0.61492 0.694746 0.373097 -0.614916 0.694752 0.373092 -0.345988 0.694751 0.630566 -0.345989 0.694747 0.630571 0.0156493 0.69475 0.719081 0.0156494 0.69475 0.719081 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518722 0 -0.854943 -0.518722 0 -0.854943 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.999763 0 0.02176 -0.999763 0 0.02176 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.48104 0 0.876699 -0.48104 0 0.876699 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.373088 0.694756 -0.614914 -0.373099 0.694744 -0.614921 -0.630571 0.694745 -0.345989 -0.630569 0.694748 -0.345989 -0.719085 0.694746 0.015651 -0.71908 0.694751 0.0156489 -0.614918 0.69475 0.373094 -0.614915 0.694754 0.37309 -0.345987 0.694754 0.630563 -0.345987 0.69475 0.630568 0.0156488 0.694751 0.71908 0.0156508 0.694746 0.719085 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518722 0 -0.854943 -0.518722 0 -0.854943 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.48104 0 0.876699 -0.48104 0 0.876699 0.021757 0 0.999763 0.021757 0 0.999763 -0.373089 0.694755 -0.614915 -0.373097 0.694745 -0.61492 -0.630572 0.694744 -0.345991 -0.630572 0.694744 -0.345991 -0.719089 0.694742 0.015649 -0.719085 0.694746 0.0156471 -0.61492 0.694745 0.373097 -0.614917 0.694752 0.373092 -0.345989 0.69475 0.630566 -0.345989 0.694747 0.630569 0.0156487 0.694751 0.71908 0.0156508 0.694746 0.719085 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.854943 0 0.518722 -0.854943 0 0.518722 -0.481037 0 0.8767 -0.481037 0 0.8767 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.373094 0.694749 -0.614919 -0.373092 0.694751 -0.614917 -0.630565 0.694753 -0.345987 -0.630567 0.694751 -0.345987 -0.71908 0.694751 0.0156488 -0.719076 0.694755 0.0156469 -0.614915 0.694755 0.373089 -0.614921 0.694745 0.373098 -0.345988 0.694746 0.630571 -0.345988 0.694751 0.630566 0.0156493 0.694749 0.719082 0.0156493 0.694749 0.719082 0.0423328 0.698071 0.714776 0.0423293 0.698073 0.714774 -0.142354 0.706859 0.692883 -0.275152 0.689417 0.670071 -0.295431 0.700861 0.649241 -0.450101 0.706115 0.546636 -0.542402 0.684059 0.487713 -0.562799 0.703124 0.434597 -0.687432 0.698073 0.200328 -0.699292 0.6524 0.292174 -0.698945 0.704874 0.12095 -0.706273 0.698074 -0.11778 -0.740207 0.66902 -0.0671233 -0.673292 0.706114 -0.219272 -0.58523 0.698071 -0.412556 -0.348274 0.698072 -0.625621 -0.348272 0.698072 -0.625621 -0.492292 0.706858 -0.507937 -0.611359 0.684209 -0.397616 -0.486397 0 -0.873738 -0.486397 0 -0.873738 -0.695962 0 -0.718079 -0.695962 0 -0.718079 -0.838298 0 -0.545213 -0.838298 0 -0.545213 -0.950846 0 -0.309664 -0.950846 0 -0.309664 -0.995914 0 -0.0903113 -0.995914 0 -0.0903113 -0.985356 0 0.170512 -0.985356 0 0.170512 -0.922701 0 0.385517 -0.922701 0 0.385517 -0.791484 0 0.61119 -0.791484 0 0.61119 -0.635649 0 0.771979 -0.635649 0 0.771979 -0.414177 0 0.910196 -0.414177 0 0.910196 -0.201248 0 0.97954 -0.201248 0 0.97954 0.0591169 0 0.998251 0.0591169 0 0.998251 -0.348272 -0.698072 -0.625622 -0.348273 -0.698073 -0.62562 -0.492292 -0.706858 -0.507937 -0.592044 -0.689417 -0.41736 -0.597957 -0.700859 -0.3889 -0.673292 -0.706114 -0.219272 -0.719493 -0.684057 -0.119985 -0.70816 -0.703125 -0.0642173 -0.698945 -0.704874 0.12095 -0.701929 -0.682242 0.204552 -0.654503 -0.704873 0.27346 -0.532438 -0.698073 0.478753 -0.588263 -0.669025 0.454261 -0.450101 -0.706115 0.546636 -0.271985 -0.698073 0.662358 0.0423294 -0.698071 0.714776 0.0423328 -0.698073 0.714775 -0.142354 -0.706859 0.692883 -0.302053 -0.684209 0.663794 -0.373092 0.694747 -0.614922 -0.373096 0.694744 -0.614922 -0.630573 0.694744 -0.34599 -0.63057 0.694745 -0.345992 -0.719086 0.694745 0.0156531 -0.719083 0.694748 0.0156478 -0.614919 0.694748 0.373096 -0.614919 0.694749 0.373094 -0.34599 0.694747 0.630569 -0.345989 0.694746 0.630571 0.015649 0.694745 0.719085 0.0156479 0.694746 0.719085 0.0217573 0 0.999763 0.0217573 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.85494 0 0.518727 -0.85494 0 0.518727 -0.999763 0 0.0217629 -0.999763 0 0.0217629 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.51872 0 -0.854944 -0.51872 0 -0.854944 0.015649 -0.694746 0.719085 0.015648 -0.694746 0.719085 -0.345991 -0.694746 0.63057 -0.345988 -0.694747 0.63057 -0.614918 -0.694749 0.373096 -0.614919 -0.694748 0.373095 -0.719082 -0.694749 0.015653 -0.719085 -0.694746 0.0156479 -0.630571 -0.694746 -0.345989 -0.630571 -0.694744 -0.345993 -0.373093 -0.694744 -0.614925 -0.373096 -0.694746 -0.614921 0.0156493 0.694746 0.719085 0.0156494 0.694746 0.719085 -0.345991 0.694746 0.63057 -0.311022 0.660379 0.683495 -0.450092 0.706115 0.546643 -0.614922 0.694745 0.373095 -0.607755 0.640608 0.469314 -0.654508 0.704871 0.273452 -0.698948 0.704871 0.120951 -0.739319 0.673163 0.0160935 -0.373094 0.694746 -0.614922 -0.373096 0.694745 -0.614922 -0.597959 0.700859 -0.388897 -0.645314 0.676902 -0.354082 -0.673295 0.706119 -0.219248 -0.708158 0.703127 -0.0642243 0.059125 0 0.998251 0.0217577 -0.001926 0.999761 -0.379855 0.00160922 0.925045 -0.414181 0 0.910195 -0.635636 0 0.771989 -0.743593 0.00257824 0.668628 -0.791483 0 0.611191 -0.922706 0 0.385504 -0.960064 0.0029019 0.279767 -0.985355 0 0.170513 -0.995913 0 -0.0903214 -0.986377 0.00257776 -0.16448 -0.950857 0 -0.309631 -0.817323 0 -0.576179 -0.838299 0.00192641 -0.545208 -0.486395 -0.0022399 -0.873736 -0.518722 0 -0.854943 0.042335 -0.698073 0.714774 0.042335 -0.698073 0.714774 -0.271987 -0.698073 0.662358 -0.271985 -0.698074 0.662357 -0.532433 -0.698075 0.478756 -0.532439 -0.698072 0.478753 -0.687436 -0.698071 0.200322 -0.687434 -0.698072 0.200325 -0.706275 -0.698073 -0.117772 -0.706275 -0.698072 -0.117775 -0.585226 -0.698072 -0.41256 -0.585227 -0.698073 -0.412557 -0.348273 -0.698073 -0.62562 -0.348272 -0.698073 -0.62562 0.960066 -8.15244e-08 -0.279774 0.960066 3.7572e-07 -0.279772 0.960066 -8.00766e-07 -0.279775 0.960066 2.35117e-07 -0.279773 0.960066 1.14172e-07 -0.279774 0.960065 0 -0.279776 0.960066 -1.30952e-07 -0.279774 0.960065 -2.2651e-06 -0.279779 0.960066 3.78401e-07 -0.279772 0.960066 -3.08925e-07 -0.279772 0.960065 1.75767e-06 -0.279778 0.960066 -1.02199e-06 -0.279774 0.960066 -2.53895e-07 -0.279774 0.960066 2.33666e-06 -0.279772 0.960066 5.0954e-07 -0.279773 0.960066 5.1671e-07 -0.279773 0.960066 -7.72858e-08 -0.279773 0.960066 3.04106e-07 -0.279773 0.960066 2.30724e-07 -0.279773 0.960065 0 -0.279776 0.960066 -2.01159e-07 -0.279773 0.960066 -2.55127e-07 -0.279773 0.960066 4.62295e-06 -0.279775 0.960066 -1.54808e-06 -0.279774 0.960066 -7.23093e-07 -0.279774 0.960066 -6.32199e-07 -0.279774 0.960066 9.29077e-07 -0.279774 0.960066 5.01327e-07 -0.279775 0.960066 -9.60027e-07 -0.279774 0.960066 -2.80255e-07 -0.279773 0.960066 -4.60218e-07 -0.279772 0.960066 2.82947e-07 -0.279774 0.960066 1.03179e-06 -0.279772 0.960066 3.81515e-07 -0.279775 0.960065 -4.16125e-06 -0.279776 0.960066 2.75204e-07 -0.279773 0.960066 -2.70501e-07 -0.279773 0.960066 0 -0.279773 0.960066 2.705e-07 -0.279773 0.960066 8.57285e-07 -0.279773 0.960063 -6.04768e-06 -0.279786 0.960066 4.39418e-07 -0.279772 0.960066 3.25893e-07 -0.279774 0.960066 3.8818e-07 -0.279774 0.960066 -8.67454e-07 -0.279773 0.960067 -3.25604e-06 -0.279771 0.960066 -7.9281e-08 -0.279773 0.960066 -5.65322e-07 -0.279773 0.960066 0 -0.279773 0.960066 8.3269e-07 -0.279774 0.960066 7.74036e-07 -0.279774 0.960066 4.40935e-06 -0.279774 0.960066 -4.99614e-06 -0.279775 0.960066 9.60027e-07 -0.279774 0.853458 -0.510203 -0.106312 0.919705 -0.373494 0.121019 0.957952 -0.136708 0.252268 0.672469 -0.136709 -0.72739 0.710716 -0.373495 -0.596141 0.776962 -0.510203 -0.368813 0.270241 -0.258819 0.927352 0.270241 -0.258819 0.927352 0.19783 -0.707106 0.67887 0.19783 -0.707106 0.67887 0.0724103 -0.965926 0.248481 0.0724102 -0.965927 0.248481 -0.0724102 -0.965927 -0.248481 -0.0724103 -0.965926 -0.248481 -0.19783 -0.707106 -0.67887 -0.19783 -0.707106 -0.67887 -0.270241 -0.258819 -0.927352 -0.270241 -0.258819 -0.927352 0.853458 -0.510203 -0.106312 0.919704 -0.373497 0.121015 0.957953 -0.136708 0.252266 0.672469 -0.136708 -0.72739 0.710716 -0.373492 -0.596142 0.776964 -0.510203 -0.368809 0.270241 -0.258818 0.927353 0.270241 -0.258818 0.927353 0.19783 -0.707106 0.67887 0.197831 -0.707106 0.67887 0.0724102 -0.965926 0.248481 0.0724102 -0.965926 0.248481 -0.0724104 -0.965926 -0.248482 -0.0724102 -0.965926 -0.248481 -0.19783 -0.707108 -0.678868 -0.19783 -0.707106 -0.678869 -0.270241 -0.258818 -0.927353 -0.270241 -0.258818 -0.927353 -0.960065 -7.09692e-07 0.279777 -0.960066 2.35117e-07 0.279773 -0.960066 3.47949e-07 0.279772 -0.960065 0 0.279777 -0.960066 -3.99088e-07 0.279772 -0.960066 -1.72107e-07 0.279775 -0.960066 1.21142e-06 0.279774 -0.960065 3.86658e-06 0.279779 -0.960063 1.09384e-05 0.279786 -0.960067 2.62322e-07 0.279772 -0.960068 0 0.279768 -0.960067 -3.00876e-07 0.279771 -0.960065 -1.25816e-06 0.279779 -0.960064 1.05552e-06 0.279779 -0.960066 -2.92227e-07 0.279772 -0.960066 -3.19577e-07 0.279772 -0.960066 1.60266e-06 0.279774 -0.960066 2.32737e-07 0.279774 -0.960065 -2.43107e-06 0.279776 -0.960066 1.69847e-06 0.279774 -0.960066 1.68492e-08 0.279775 -0.960066 -5.44865e-06 0.279773 -0.960066 0 0.279773 -0.960066 -7.8905e-07 0.279773 -0.960066 -5.12117e-07 0.279774 -0.960066 4.09511e-07 0.279772 -0.960066 3.57947e-07 0.279773 -0.960066 2.92326e-07 0.279775 -0.960066 2.76587e-07 0.279774 -0.960066 7.7404e-07 0.279774 -0.960066 1.44619e-06 0.279774 -0.960066 1.2644e-06 0.279774 -0.960066 -1.30071e-06 0.279775 -0.960066 -2.80255e-07 0.279773 -0.960065 8.79526e-07 0.279777 -0.960066 -6.144e-07 0.279774 -0.960066 -1.01156e-07 0.279773 -0.960066 -2.3146e-07 0.279773 -0.960066 1.06288e-06 0.279773 -0.960066 -1.48388e-06 0.279775 -0.960065 5.41001e-07 0.279776 -0.960065 0 0.279776 -0.960065 -5.41e-07 0.279776 -0.960065 -7.81082e-07 0.279776 -0.960067 2.59186e-06 0.279769 -0.960066 9.58733e-07 0.279773 -0.960066 7.48885e-07 0.279775 -0.960066 -6.19229e-06 0.279774 -0.960066 -2.20468e-06 0.279774 -0.960066 1.23953e-06 0.279774 -0.960066 -3.87204e-07 0.279774 -0.960066 -1.35638e-06 0.279774 -0.853458 -0.510203 0.106312 -0.919705 -0.373493 -0.121019 -0.957952 -0.136709 -0.252268 -0.672469 -0.136708 0.72739 -0.710717 -0.373496 0.59614 -0.776962 -0.510202 0.368813 -0.270241 -0.258821 -0.927352 -0.270241 -0.258821 -0.927352 -0.197831 -0.707106 -0.67887 -0.197831 -0.707106 -0.67887 -0.0724102 -0.965926 -0.248481 -0.0724101 -0.965927 -0.248481 0.0724103 -0.965926 0.248481 0.0724104 -0.965926 0.248482 0.19783 -0.707107 0.678869 0.19783 -0.707107 0.678869 0.270241 -0.258818 0.927353 0.270241 -0.258818 0.927353 -0.853458 -0.510203 0.106312 -0.919704 -0.373497 -0.121015 -0.957953 -0.136708 -0.252265 -0.672469 -0.136705 0.727391 -0.710717 -0.373494 0.59614 -0.776964 -0.510203 0.368808 -0.270241 -0.258819 -0.927352 -0.270241 -0.258821 -0.927352 -0.19783 -0.707107 -0.678869 -0.19783 -0.707106 -0.67887 -0.0724103 -0.965926 -0.248481 -0.0724103 -0.965926 -0.248481 0.0724103 -0.965926 0.248481 0.0724103 -0.965926 0.248481 0.19783 -0.707106 0.67887 0.19783 -0.707107 0.678869 0.270241 -0.258821 0.927352 0.270241 -0.258819 0.927352 -0.908323 0 0.41827 -0.908323 0 0.41827 -0.990823 0 0.135163 -0.990823 0 0.135163 0.990823 0 -0.135163 0.990823 0 -0.135163 0.908323 0 -0.41827 0.908323 0 -0.41827 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.358101 0 -0.933683 -0.358101 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.97751 0 -0.210887 -0.97751 0 -0.210887 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444399 0 0.895829 -0.444399 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129444 0 0.991587 -0.129444 0 0.991587 0.0355306 0 0.999369 0.0355306 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.253646 0.705903 -0.661336 -0.253647 0.705898 -0.661341 -0.359041 0.705897 -0.610573 -0.35904 0.705899 -0.610571 -0.454641 0.705898 -0.543148 -0.454644 0.705893 -0.543152 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658364 0.705887 -0.261303 -0.692395 0.705887 -0.149376 -0.692394 0.705888 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503752 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314774 0.705897 0.634529 -0.206041 0.705895 0.677686 -0.206044 0.705886 0.677695 -0.091689 0.705886 0.702366 -0.0916867 0.7059 0.702352 0.0251672 0.7059 0.707864 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141336 0.705889 0.694078 0.141336 -0.70589 0.694078 0.141335 -0.705894 0.694073 0.0251674 -0.705894 0.70787 0.025167 -0.7059 0.707864 -0.0916871 -0.7059 0.702352 -0.0916886 -0.705886 0.702366 -0.206044 -0.705886 0.677695 -0.206041 -0.705895 0.677686 -0.314774 -0.705896 0.63453 -0.314774 -0.705896 0.63453 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.50375 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658364 -0.705888 -0.261303 -0.65836 -0.705892 -0.261302 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.45464 -0.705899 -0.543148 -0.35904 -0.705899 -0.610571 -0.359041 -0.705897 -0.610573 -0.253648 -0.705897 -0.661341 -0.253646 -0.705902 -0.661336 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.358101 0 -0.933683 -0.358101 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444399 0 0.895829 -0.444399 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129444 0 0.991587 -0.129444 0 0.991587 0.0355306 0 0.999369 0.0355306 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.358101 0 -0.933683 -0.358101 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444399 0 0.895829 -0.444399 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129444 0 0.991587 -0.129444 0 0.991587 0.0355306 0 0.999369 0.0355306 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.358101 0 -0.933683 -0.358101 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.97751 0 -0.210887 -0.97751 0 -0.210887 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444399 0 0.895829 -0.444399 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129444 0 0.991587 -0.129444 0 0.991587 0.0355306 0 0.999369 0.0355306 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.358101 0 -0.933683 -0.358101 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444399 0 0.895829 -0.444399 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129444 0 0.991587 -0.129444 0 0.991587 0.0355306 0 0.999369 0.0355306 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.358101 0 -0.933683 -0.358101 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444399 0 0.895829 -0.444399 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129444 0 0.991587 -0.129444 0 0.991587 0.0355306 0 0.999369 0.0355306 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.358101 0 -0.933683 -0.358101 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.97751 0 -0.210887 -0.97751 0 -0.210887 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444399 0 0.895829 -0.444399 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129444 0 0.991587 -0.129444 0 0.991587 0.0355306 0 0.999369 0.0355306 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.358101 0 -0.933683 -0.358101 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444399 0 0.895829 -0.444399 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129444 0 0.991587 -0.129444 0 0.991587 0.0355306 0 0.999369 0.0355306 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.358101 0 -0.933683 -0.358101 0 -0.933683 -0.506895 0 -0.862008 -0.506895 0 -0.862008 -0.641864 0 -0.766819 -0.641864 0 -0.766819 -0.759324 0 -0.650713 -0.759324 0 -0.650713 -0.856071 0 -0.516858 -0.856071 0 -0.516858 -0.929468 0 -0.368903 -0.929468 0 -0.368903 -0.977511 0 -0.210887 -0.977511 0 -0.210887 -0.998889 0 -0.047118 -0.998889 0 -0.047118 -0.993021 0 0.117937 -0.993021 0 0.117937 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.900923 0 0.43398 -0.900923 0 0.43398 -0.817204 0 0.576348 -0.817204 0 0.576348 -0.711195 0 0.702995 -0.711195 0 0.702995 -0.585786 0 0.810466 -0.585786 0 0.810466 -0.444399 0 0.895829 -0.444399 0 0.895829 -0.290889 0 0.956757 -0.290889 0 0.956757 -0.129444 0 0.991587 -0.129444 0 0.991587 0.0355306 0 0.999369 0.0355306 0 0.999369 0.199537 0 0.97989 0.199537 0 0.97989 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.253646 0.705903 -0.661336 -0.253647 0.705898 -0.661341 -0.359041 0.705897 -0.610573 -0.35904 0.705899 -0.610571 -0.454641 0.705898 -0.543148 -0.454644 0.705893 -0.543152 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658364 0.705887 -0.261303 -0.692395 0.705887 -0.149376 -0.692394 0.705888 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503752 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314774 0.705897 0.634529 -0.206041 0.705895 0.677686 -0.206044 0.705886 0.677695 -0.091689 0.705886 0.702366 -0.0916867 0.7059 0.702352 0.0251672 0.7059 0.707864 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141336 0.705889 0.694078 0.141336 -0.70589 0.694078 0.141335 -0.705894 0.694073 0.0251674 -0.705894 0.70787 0.025167 -0.7059 0.707864 -0.0916871 -0.7059 0.702352 -0.0916886 -0.705886 0.702366 -0.206044 -0.705886 0.677695 -0.206041 -0.705895 0.677686 -0.314774 -0.705896 0.63453 -0.314774 -0.705896 0.63453 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.50375 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658364 -0.705888 -0.261303 -0.65836 -0.705892 -0.261302 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.45464 -0.705899 -0.543148 -0.35904 -0.705899 -0.610571 -0.359041 -0.705897 -0.610573 -0.253648 -0.705897 -0.661341 -0.253646 -0.705902 -0.661336 -0.253646 0.705903 -0.661336 -0.253647 0.705898 -0.661341 -0.359041 0.705897 -0.610573 -0.35904 0.705899 -0.610571 -0.454641 0.705898 -0.543148 -0.454644 0.705893 -0.543152 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658364 0.705887 -0.261303 -0.692395 0.705887 -0.149376 -0.692394 0.705888 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503752 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314774 0.705897 0.634529 -0.206041 0.705895 0.677686 -0.206044 0.705886 0.677695 -0.091689 0.705886 0.702366 -0.0916867 0.7059 0.702352 0.0251672 0.7059 0.707864 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141336 0.705889 0.694078 0.141336 -0.70589 0.694078 0.141335 -0.705894 0.694073 0.0251674 -0.705894 0.70787 0.025167 -0.7059 0.707864 -0.0916871 -0.7059 0.702352 -0.0916886 -0.705886 0.702366 -0.206044 -0.705886 0.677695 -0.206041 -0.705895 0.677686 -0.314774 -0.705896 0.63453 -0.314774 -0.705896 0.63453 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.50375 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658364 -0.705888 -0.261303 -0.65836 -0.705892 -0.261302 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.45464 -0.705899 -0.543148 -0.35904 -0.705899 -0.610571 -0.359041 -0.705897 -0.610573 -0.253648 -0.705897 -0.661341 -0.253646 -0.705902 -0.661336 -0.253646 0.705903 -0.661336 -0.253647 0.705898 -0.661341 -0.359041 0.705897 -0.610573 -0.35904 0.705899 -0.610571 -0.454641 0.705898 -0.543148 -0.454644 0.705893 -0.543152 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658364 0.705887 -0.261303 -0.692395 0.705887 -0.149376 -0.692394 0.705888 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503752 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314774 0.705897 0.634529 -0.206041 0.705895 0.677686 -0.206044 0.705886 0.677695 -0.091689 0.705886 0.702366 -0.0916867 0.7059 0.702352 0.0251672 0.7059 0.707864 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141336 0.705889 0.694078 0.141336 -0.70589 0.694078 0.141335 -0.705894 0.694073 0.0251674 -0.705894 0.70787 0.025167 -0.7059 0.707864 -0.0916871 -0.7059 0.702352 -0.0916886 -0.705886 0.702366 -0.206044 -0.705886 0.677695 -0.206041 -0.705895 0.677686 -0.314774 -0.705896 0.63453 -0.314774 -0.705896 0.63453 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.50375 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658364 -0.705888 -0.261303 -0.65836 -0.705892 -0.261302 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.45464 -0.705899 -0.543148 -0.35904 -0.705899 -0.610571 -0.359041 -0.705897 -0.610573 -0.253648 -0.705897 -0.661341 -0.253646 -0.705902 -0.661336 -0.253646 0.705903 -0.661336 -0.253647 0.705898 -0.661341 -0.359041 0.705897 -0.610573 -0.35904 0.705899 -0.610571 -0.454641 0.705898 -0.543148 -0.454644 0.705893 -0.543152 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658364 0.705887 -0.261303 -0.692395 0.705887 -0.149376 -0.692394 0.705888 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503752 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314774 0.705897 0.634529 -0.206041 0.705895 0.677686 -0.206044 0.705886 0.677695 -0.091689 0.705886 0.702366 -0.0916867 0.7059 0.702352 0.0251672 0.7059 0.707864 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141336 0.705889 0.694078 0.141336 -0.70589 0.694078 0.141335 -0.705894 0.694073 0.0251674 -0.705894 0.70787 0.025167 -0.7059 0.707864 -0.0916871 -0.7059 0.702352 -0.0916886 -0.705886 0.702366 -0.206044 -0.705886 0.677695 -0.206041 -0.705895 0.677686 -0.314774 -0.705896 0.63453 -0.314774 -0.705896 0.63453 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.50375 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658364 -0.705888 -0.261303 -0.65836 -0.705892 -0.261302 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.45464 -0.705899 -0.543148 -0.35904 -0.705899 -0.610571 -0.359041 -0.705897 -0.610573 -0.253648 -0.705897 -0.661341 -0.253646 -0.705902 -0.661336 -0.253646 0.705903 -0.661336 -0.253647 0.705898 -0.661341 -0.359041 0.705897 -0.610573 -0.35904 0.705899 -0.610571 -0.454641 0.705898 -0.543148 -0.454644 0.705893 -0.543152 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658364 0.705887 -0.261303 -0.692395 0.705887 -0.149376 -0.692394 0.705888 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503752 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314774 0.705897 0.634529 -0.206041 0.705895 0.677686 -0.206044 0.705886 0.677695 -0.091689 0.705886 0.702366 -0.0916867 0.7059 0.702352 0.0251672 0.7059 0.707864 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141336 0.705889 0.694078 0.141336 -0.70589 0.694078 0.141335 -0.705894 0.694073 0.0251674 -0.705894 0.70787 0.025167 -0.7059 0.707864 -0.0916871 -0.7059 0.702352 -0.0916886 -0.705886 0.702366 -0.206044 -0.705886 0.677695 -0.206041 -0.705895 0.677686 -0.314774 -0.705896 0.63453 -0.314774 -0.705896 0.63453 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.50375 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658364 -0.705888 -0.261303 -0.65836 -0.705892 -0.261302 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.45464 -0.705899 -0.543148 -0.35904 -0.705899 -0.610571 -0.359041 -0.705897 -0.610573 -0.253648 -0.705897 -0.661341 -0.253646 -0.705902 -0.661336 -0.253646 0.705903 -0.661336 -0.253647 0.705898 -0.661341 -0.359041 0.705897 -0.610573 -0.35904 0.705899 -0.610571 -0.454641 0.705898 -0.543148 -0.454644 0.705893 -0.543152 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658364 0.705887 -0.261303 -0.692395 0.705887 -0.149376 -0.692394 0.705888 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503752 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314774 0.705897 0.634529 -0.206041 0.705895 0.677686 -0.206044 0.705886 0.677695 -0.091689 0.705886 0.702366 -0.0916867 0.7059 0.702352 0.0251672 0.7059 0.707864 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141336 0.705889 0.694078 0.141336 -0.70589 0.694078 0.141335 -0.705894 0.694073 0.0251674 -0.705894 0.70787 0.025167 -0.7059 0.707864 -0.0916871 -0.7059 0.702352 -0.0916886 -0.705886 0.702366 -0.206044 -0.705886 0.677695 -0.206041 -0.705895 0.677686 -0.314774 -0.705896 0.63453 -0.314774 -0.705896 0.63453 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.50375 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658364 -0.705888 -0.261303 -0.65836 -0.705892 -0.261302 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.45464 -0.705899 -0.543148 -0.35904 -0.705899 -0.610571 -0.359041 -0.705897 -0.610573 -0.253648 -0.705897 -0.661341 -0.253646 -0.705902 -0.661336 -0.253646 0.705903 -0.661336 -0.253647 0.705898 -0.661341 -0.359041 0.705897 -0.610573 -0.35904 0.705899 -0.610571 -0.454641 0.705898 -0.543148 -0.454644 0.705893 -0.543152 -0.537843 0.705893 -0.460912 -0.537839 0.705899 -0.460908 -0.606366 0.705899 -0.366097 -0.606372 0.705892 -0.3661 -0.658359 0.705893 -0.261301 -0.658364 0.705887 -0.261303 -0.692395 0.705887 -0.149376 -0.692394 0.705888 -0.149376 -0.707537 0.705887 -0.0333747 -0.707523 0.705902 -0.0333736 -0.703366 0.705902 0.0835356 -0.703368 0.7059 0.0835357 -0.680025 0.705901 0.198167 -0.680034 0.705891 0.19817 -0.638142 0.705891 0.307397 -0.638143 0.70589 0.307397 -0.578843 0.70589 0.408239 -0.578839 0.705896 0.408236 -0.50375 0.705896 0.497942 -0.503752 0.705893 0.497944 -0.414923 0.705894 0.574067 -0.414923 0.705894 0.574067 -0.314775 0.705895 0.634531 -0.314774 0.705897 0.634529 -0.206041 0.705895 0.677686 -0.206044 0.705886 0.677695 -0.091689 0.705886 0.702366 -0.0916867 0.7059 0.702352 0.0251672 0.7059 0.707864 0.0251672 0.705894 0.70787 0.141335 0.705894 0.694073 0.141336 0.705889 0.694078 0.141336 -0.70589 0.694078 0.141335 -0.705894 0.694073 0.0251674 -0.705894 0.70787 0.025167 -0.7059 0.707864 -0.0916871 -0.7059 0.702352 -0.0916886 -0.705886 0.702366 -0.206044 -0.705886 0.677695 -0.206041 -0.705895 0.677686 -0.314774 -0.705896 0.63453 -0.314774 -0.705896 0.63453 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.50375 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658364 -0.705888 -0.261303 -0.65836 -0.705892 -0.261302 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.45464 -0.705899 -0.543148 -0.35904 -0.705899 -0.610571 -0.359041 -0.705897 -0.610573 -0.253648 -0.705897 -0.661341 -0.253646 -0.705902 -0.661336 -0.253648 0.705896 -0.661342 -0.25365 0.705891 -0.661347 -0.359045 0.70589 -0.610578 -0.359044 0.705892 -0.610577 -0.454645 0.705892 -0.543153 -0.454648 0.705886 -0.543157 -0.537848 0.705886 -0.460916 -0.537844 0.705892 -0.460913 -0.606372 0.705892 -0.3661 -0.606378 0.705886 -0.366104 -0.658366 0.705886 -0.261304 -0.65837 0.705881 -0.261306 -0.692401 0.705881 -0.149378 -0.692401 0.705881 -0.149377 -0.707544 0.705881 -0.0333751 -0.707529 0.705896 -0.033374 -0.703373 0.705895 0.0835364 -0.703374 0.705894 0.0835365 -0.680031 0.705894 0.198169 -0.68004 0.705885 0.198172 -0.638148 0.705885 0.3074 -0.638148 0.705884 0.3074 -0.578849 0.705884 0.408243 -0.578844 0.705889 0.40824 -0.503755 0.70589 0.497947 -0.503757 0.705887 0.497949 -0.414926 0.705887 0.574072 -0.414926 0.705887 0.574072 -0.314778 0.705889 0.634536 -0.314777 0.70589 0.634535 -0.206043 0.705889 0.677693 -0.206046 0.70588 0.677701 -0.0916898 0.705879 0.702373 -0.0916876 0.705894 0.702359 0.0251674 0.705894 0.707871 0.0251674 0.705887 0.707877 0.141337 0.705888 0.69408 0.141338 0.705883 0.694084 0.141335 -0.705896 0.694071 0.141334 -0.705901 0.694067 0.0251671 -0.705901 0.707864 0.0251667 -0.705907 0.707857 -0.0916863 -0.705907 0.702345 -0.0916877 -0.705892 0.70236 -0.206042 -0.705893 0.677689 -0.206039 -0.705902 0.67768 -0.314771 -0.705903 0.634524 -0.314771 -0.705902 0.634524 -0.414918 -0.705901 0.574061 -0.414919 -0.705901 0.574062 -0.503748 -0.7059 0.49794 -0.503746 -0.705902 0.497938 -0.578833 -0.705903 0.408232 -0.578838 -0.705897 0.408236 -0.638136 -0.705897 0.307394 -0.638136 -0.705898 0.307394 -0.680028 -0.705898 0.198168 -0.680019 -0.705908 0.198165 -0.703361 -0.705907 0.083535 -0.703359 -0.705909 0.0835347 -0.707516 -0.705909 -0.0333738 -0.707531 -0.705894 -0.033374 -0.692388 -0.705894 -0.149375 -0.692388 -0.705894 -0.149375 -0.658358 -0.705894 -0.261301 -0.658354 -0.705899 -0.261299 -0.606366 -0.705899 -0.366096 -0.606361 -0.705905 -0.366093 -0.537834 -0.705905 -0.460904 -0.537838 -0.7059 -0.460908 -0.454639 -0.7059 -0.543146 -0.454636 -0.705905 -0.543143 -0.359037 -0.705906 -0.610565 -0.359038 -0.705903 -0.610567 -0.253645 -0.705904 -0.661335 -0.253643 -0.705909 -0.66133 0.270241 0.258819 0.927353 0.288444 0.195069 0.937416 0.211337 0.608723 0.764718 0.232624 0.55557 0.798266 0.170315 0.793354 0.58445 0.148332 0.831446 0.535439 0.0830167 0.965867 0.245376 0.0545803 0.980786 0.187296 0.0545816 -0.980785 0.187301 0.0617967 -0.965867 0.251559 0.12374 -0.896875 0.424622 0.170317 -0.793351 0.584454 0.183643 -0.70703 0.682924 0.274398 -0.19509 0.941619 0.259615 -0.258803 0.930388 0.250922 -0.442289 0.861057 0.221959 -0.608763 0.76167 -0.274398 -0.195089 -0.941619 -0.274399 -0.195089 -0.941619 -0.232624 -0.555571 -0.798265 -0.232623 -0.555572 -0.798264 -0.155434 -0.831469 -0.533385 -0.155434 -0.831469 -0.533385 -0.0545816 -0.980785 -0.187301 -0.0545817 -0.980785 -0.187301 -0.0724107 0.965926 -0.248483 -0.0724108 0.965926 -0.248483 -0.19783 0.707106 -0.678869 -0.19783 0.707106 -0.678869 -0.270241 0.258818 -0.927353 -0.270241 0.258819 -0.927352 0.274398 0.19509 0.941619 0.282101 0.2588 0.923819 0.250921 0.442291 0.861056 0.22196 0.60876 0.761673 0.213666 0.70701 0.674155 0.170315 0.793354 0.58445 0.123743 0.89687 0.424632 0.0842859 0.965852 0.245002 0.0545804 0.980786 0.187297 0.0545817 -0.980785 0.187301 0.084285 -0.965852 0.245002 0.12374 -0.896875 0.424621 0.170317 -0.793351 0.584454 0.213665 -0.70701 0.674155 0.221959 -0.608763 0.76167 0.250921 -0.442291 0.861056 0.282101 -0.2588 0.923819 0.274398 -0.19509 0.941619 -0.274398 -0.19509 -0.941619 -0.25834 -0.258799 -0.930743 -0.250922 -0.442289 -0.861057 -0.221959 -0.608763 -0.76167 -0.181942 -0.70701 -0.683399 -0.170317 -0.793351 -0.584455 -0.123739 -0.896875 -0.424621 -0.0605254 -0.965852 -0.251926 -0.0545816 -0.980785 -0.187301 -0.0545803 0.980786 -0.187297 -0.0605245 0.965852 -0.251926 -0.123743 0.89687 -0.424632 -0.170315 0.793354 -0.58445 -0.181941 0.70701 -0.683399 -0.22196 0.60876 -0.761673 -0.250922 0.442289 -0.861057 -0.25834 0.258799 -0.930743 -0.274398 0.19509 -0.941618 -0.253648 0.705896 -0.661343 -0.253648 0.705896 -0.661342 -0.347033 0.706393 -0.616909 -0.437382 0.505435 -0.743796 -0.397553 0.703333 -0.5893 -0.589834 0.394398 -0.70466 -0.43427 0.706723 -0.558527 -0.406614 0.707107 -0.578502 -0.699698 0.388437 -0.599616 -0.516525 0.706836 -0.483306 -0.478806 0.706876 -0.520646 -0.633856 0.707105 -0.313415 -0.620252 0.706806 -0.340165 -0.789359 0.38702 -0.476579 -0.590046 0.706804 -0.390224 -0.554722 0.706771 -0.439041 -0.677202 0.707105 -0.20347 -0.663507 0.706463 -0.24631 -0.81744 0.475953 -0.32444 -0.647661 0.699808 -0.301338 -0.63504 0.706701 -0.311927 -0.718167 0.684611 -0.124671 -0.899586 0.391253 -0.194075 -0.817034 0.544807 -0.188788 -0.690422 0.697889 -0.190444 -0.911403 0.409264 -0.0429911 -0.703917 0.706923 -0.0690022 -0.700721 0.707101 -0.0948584 -0.680027 0.705899 0.198168 -0.695315 0.707055 0.128884 -0.847789 0.520689 0.100688 -0.704279 0.706354 0.0710942 -0.707482 0.706651 -0.0106416 -0.601458 0.707016 0.37199 -0.632218 0.706355 0.318376 -0.76916 0.520687 0.370509 -0.655707 0.707049 0.264822 -0.680032 0.705893 0.198169 -0.700489 0.524601 0.483849 -0.745628 0.409272 0.525867 -0.556649 0.706928 0.436343 -0.587707 0.544816 0.598144 -0.6545 0.391255 0.646954 -0.538763 0.684617 0.490952 -0.540064 0.707106 0.456435 -0.366244 0.707105 0.60487 -0.368072 0.706694 0.604241 -0.384393 0.699806 0.602091 -0.515182 0.475951 0.712782 -0.427319 0.706461 0.564191 -0.472268 0.707013 0.526399 -0.340416 0.706806 0.620114 -0.409768 0.387012 0.826021 -0.288749 0.705491 0.64723 -0.261021 0.707104 0.65717 -0.206042 0.705893 0.677689 -0.206042 0.705893 0.677689 -0.124158 0.706873 0.696358 -0.118952 0.394392 0.911211 -0.0662429 0.706725 0.70438 -0.01978 0.707045 0.706892 0.0306587 0.505433 0.862321 0.0386997 0.706389 0.706765 0.141336 0.705893 0.694075 0.141335 0.705896 0.694072 0.141336 -0.70589 0.694078 0.141335 -0.705894 0.694073 0.0251674 -0.705894 0.70787 0.025167 -0.7059 0.707864 -0.0916871 -0.7059 0.702352 -0.0916886 -0.705886 0.702366 -0.206044 -0.705886 0.677695 -0.206041 -0.705895 0.677686 -0.314774 -0.705896 0.63453 -0.314774 -0.705896 0.63453 -0.414922 -0.705895 0.574067 -0.414923 -0.705894 0.574067 -0.503752 -0.705893 0.497944 -0.50375 -0.705896 0.497942 -0.578839 -0.705896 0.408236 -0.578843 -0.70589 0.40824 -0.638142 -0.705891 0.307397 -0.638142 -0.705891 0.307397 -0.680034 -0.705891 0.19817 -0.680025 -0.705901 0.198167 -0.703368 -0.705901 0.0835357 -0.703366 -0.705902 0.0835355 -0.707523 -0.705902 -0.0333741 -0.707537 -0.705887 -0.0333743 -0.692394 -0.705888 -0.149376 -0.692395 -0.705887 -0.149376 -0.658364 -0.705888 -0.261303 -0.65836 -0.705892 -0.261302 -0.606372 -0.705893 -0.3661 -0.606366 -0.705899 -0.366097 -0.537839 -0.705898 -0.460909 -0.537843 -0.705893 -0.460912 -0.454644 -0.705894 -0.543151 -0.45464 -0.705899 -0.543148 -0.35904 -0.705899 -0.610571 -0.359041 -0.705897 -0.610573 -0.253648 -0.705897 -0.661341 -0.253646 -0.705902 -0.661336 0.328364 -0.939692 -0.0956889 0.328363 -0.939692 -0.0956888 0.0643458 -0.183734 -0.980868 0.0643459 -0.183734 -0.980868 0.0918929 -0.41572 -0.904839 0.0665999 -0.529899 -0.845442 0.117097 -0.572621 -0.811415 0.176386 -0.78307 -0.596397 0.271369 -0.923694 -0.270458 0.271369 -0.923694 -0.270458 0.211436 -0.842998 -0.494621 0.102815 -0.762187 -0.63914 0.374177 -0.923695 0.0823384 0.374178 -0.923694 0.0823386 0.444048 -0.842998 0.303605 0.436725 -0.793047 0.424674 0.486084 -0.746249 0.454791 0.541855 -0.523232 0.657739 0.581198 -0.183734 0.792749 0.581198 -0.183735 0.792749 0.563589 -0.415722 0.713823 0.479684 -0.58485 0.654106 0.0654602 0 -0.997855 0.0654602 0 -0.997855 0.591264 0 0.806478 0.591264 0 0.806478 0.271369 0.923694 -0.270458 0.271366 0.923697 -0.270453 0.211429 0.842994 -0.494631 0.140223 0.793049 -0.592799 0.165674 0.746253 -0.644716 0.103689 0.52323 -0.84586 0.0643458 0.183734 -0.980868 0.0643459 0.183734 -0.980868 0.0918929 0.41572 -0.904839 0.0532035 0.584846 -0.809398 0.581198 0.183735 0.792749 0.581198 0.183734 0.792749 0.563589 0.415722 0.713823 0.510349 0.529897 0.677313 0.53466 0.572618 0.621488 0.469159 0.783072 0.408276 0.374177 0.923695 0.0823345 0.374174 0.923696 0.0823396 0.444048 0.842993 0.303617 0.430068 0.762189 0.483848 0.328363 0.939692 -0.0956887 0.328364 0.939692 -0.095689 -0.328363 0.939692 0.0956887 -0.328363 0.939692 0.0956887 -0.386737 0.91125 -0.141625 -0.386737 0.91125 -0.141625 -0.505057 0.667081 -0.547649 -0.505057 0.667081 -0.547649 -0.573368 0.244168 -0.782068 -0.573368 0.244168 -0.782069 -0.250113 0.91125 0.32721 -0.250113 0.91125 0.32721 -0.131792 0.667081 0.733235 -0.0634789 0.244169 0.967653 -0.0634795 0.244168 0.967653 -0.117097 0.572617 0.811417 0.00674831 0.782098 0.623119 -0.591264 0 -0.806478 -0.591264 0 -0.806478 -0.0654602 0 0.997855 -0.0654602 0 0.997855 -0.581198 -0.183733 -0.792749 -0.581197 -0.183734 -0.792749 -0.541854 -0.523233 -0.657739 -0.541855 -0.523232 -0.657739 -0.469159 -0.78307 -0.408277 -0.46916 -0.78307 -0.408277 -0.374178 -0.923694 -0.0823386 -0.374177 -0.923695 -0.0823384 -0.0643458 -0.183734 0.980868 -0.0643461 -0.183734 0.980868 -0.0918931 -0.41572 0.904839 -0.0666 -0.529899 0.845442 -0.117096 -0.572621 0.811415 -0.176386 -0.78307 0.596397 -0.271369 -0.923695 0.270458 -0.271369 -0.923695 0.270458 -0.211436 -0.842997 0.494621 -0.102815 -0.762187 0.63914 -0.328363 -0.939692 0.0956887 -0.328363 -0.939692 0.0956887 0.552224 0.705401 -0.444362 0.552224 0.705402 -0.444362 0.455043 0.705402 -0.543456 0.455043 0.705402 -0.543456 0.340414 0.705402 -0.621713 0.340414 0.705402 -0.621713 0.212732 0.705402 -0.676131 0.212733 0.705401 -0.676132 0.0768942 0.705401 -0.704625 0.076894 0.705402 -0.704624 -0.0618928 0.705402 -0.7061 -0.0618925 0.705401 -0.706101 -0.198306 0.705401 -0.680503 -0.198306 0.705401 -0.680503 -0.327116 0.705401 -0.628812 -0.327116 0.705402 -0.628811 -0.443383 0.705401 -0.55301 -0.443383 0.705402 -0.55301 -0.54265 0.705401 -0.456005 -0.54265 0.705402 -0.456004 -0.621109 0.705402 -0.341514 -0.62111 0.705401 -0.341514 -0.675754 0.705401 -0.213929 -0.675754 0.705401 -0.213929 -0.704488 0.705401 -0.0781415 -0.704488 0.705401 -0.0781416 -0.704458 0.70321 0.0960984 -0.704458 0.70321 0.096098 0.645801 0.703211 -0.297382 0.645801 0.70321 -0.297382 -0.67887 0.707106 0.19783 -0.67887 0.707106 0.197831 0.678869 0.707106 -0.19783 0.678869 0.707106 -0.19783 -0.645802 0.70321 0.297383 -0.645801 0.70321 0.297383 0.704458 0.70321 -0.0960984 0.704457 0.703211 -0.0960992 0.25928 0.705636 0.659433 0.25928 0.705637 0.659432 0.374424 0.705637 0.601567 0.374424 0.705637 0.601568 0.477184 0.705637 0.523806 0.477184 0.705637 0.523805 0.564161 0.705637 0.428718 0.564161 0.705637 0.428718 0.632478 0.705637 0.31945 0.632478 0.705637 0.319451 0.679875 0.705637 0.199617 0.679875 0.705637 0.199617 0.704785 0.705637 0.0731809 0.704785 0.705637 0.0731809 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.960066 2.37977e-06 -0.279773 0.960066 0 -0.279774 0.960066 -2.04691e-07 -0.279774 0.960066 1.02348e-06 -0.279774 0.960066 3.43116e-07 -0.279774 0.960066 7.05741e-07 -0.279774 0.960066 0 -0.279775 0.960066 3.59784e-07 -0.279774 0.960066 -1.16402e-06 -0.279774 0.960066 6.05953e-07 -0.279773 0.960066 -7.16702e-08 -0.279774 0.960066 -6.03121e-07 -0.279774 0.960066 -1.2119e-06 -0.279774 0.960065 -5.17342e-08 -0.279776 -0.960066 1.76901e-06 0.279774 -0.960066 2.14122e-06 0.279774 -0.960066 2.37977e-06 0.279773 -0.960066 -1.10046e-06 0.279774 -0.960066 -1.83814e-06 0.279774 -0.960066 -6.61063e-07 0.279774 -0.960066 -1.59361e-07 0.279774 -0.960066 0 0.279774 -0.960065 -1.72318e-06 0.279776 -0.960066 2.48323e-06 0.279773 -0.960066 -5.35354e-07 0.279775 -0.960066 -1.67102e-06 0.279774 -0.960066 -6.24337e-07 0.279774 -0.960066 -1.13829e-07 0.279774 -0.960066 0 0.279774 -0.960065 -1.51488e-06 0.279775 -0.37253 0 -0.92802 -0.37253 0 -0.92802 -0.54642 0 -0.837512 -0.54642 0 -0.837512 -0.699311 0 -0.714818 -0.699311 0 -0.714818 -0.825328 0 -0.564654 -0.825328 0 -0.564654 -0.919628 0 -0.392791 -0.919628 0 -0.392791 -0.978587 0 -0.205833 -0.978587 0 -0.205833 -0.99994 0 -0.0109653 -0.99994 0 -0.0109653 -0.982865 0 0.184324 -0.982865 0 0.184324 -0.92802 0 0.37253 -0.92802 0 0.37253 -0.837512 0 0.54642 -0.837512 0 0.54642 -0.714818 0 0.699311 -0.714818 0 0.699311 -0.564654 0 0.825328 -0.564654 0 0.825328 -0.392791 0 0.919628 -0.392791 0 0.919628 -0.205833 0 0.978587 -0.205833 0 0.978587 -0.010965 0 0.99994 -0.010965 0 0.99994 0.184324 0 0.982866 0.184324 0 0.982866 0.108173 -0.809687 0.576807 0.108173 -0.809687 0.576807 -0.00643517 -0.809687 0.586827 -0.00643515 -0.809687 0.586827 -0.120796 -0.809687 0.574296 -0.120796 -0.809687 0.574296 -0.230514 -0.809687 0.539695 -0.230514 -0.809687 0.539695 -0.331374 -0.809687 0.484354 -0.331374 -0.809687 0.484354 -0.4195 -0.809687 0.410399 -0.4195 -0.809687 0.410399 -0.491504 -0.809687 0.320673 -0.491504 -0.809687 0.320673 -0.54462 -0.809687 0.218624 -0.54462 -0.809686 0.218624 -0.576807 -0.809686 0.108173 -0.576807 -0.809687 0.108173 -0.586827 -0.809687 -0.00643517 -0.586827 -0.809687 -0.00643496 -0.574296 -0.809687 -0.120796 -0.574296 -0.809687 -0.120796 -0.539695 -0.809687 -0.230514 -0.539695 -0.809687 -0.230514 -0.484354 -0.809687 -0.331374 -0.484354 -0.809687 -0.331374 -0.410399 -0.809687 -0.4195 -0.410399 -0.809687 -0.419499 -0.320673 -0.809687 -0.491504 -0.320673 -0.809687 -0.491504 -0.218624 -0.809687 -0.54462 -0.218624 -0.809687 -0.54462 -0.37253 0 -0.92802 -0.37253 0 -0.92802 -0.546419 0 -0.837512 -0.546419 0 -0.837512 -0.699311 0 -0.714818 -0.699311 0 -0.714818 -0.825328 0 -0.564654 -0.825328 0 -0.564654 -0.919628 0 -0.392791 -0.919628 0 -0.392791 -0.978587 0 -0.205833 -0.978587 0 -0.205833 -0.99994 0 -0.0109654 -0.99994 0 -0.0109654 -0.982866 0 0.184324 -0.982866 0 0.184324 -0.92802 0 0.37253 -0.92802 0 0.37253 -0.837512 0 0.54642 -0.837512 0 0.54642 -0.714818 0 0.699311 -0.714818 0 0.699311 -0.564654 0 0.825328 -0.564654 0 0.825328 -0.392791 0 0.919628 -0.392791 0 0.919628 -0.205833 0 0.978587 -0.205833 0 0.978587 -0.0109654 0 0.99994 -0.0109654 0 0.99994 0.184324 0 0.982866 0.184324 0 0.982866 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.264055 0.705394 -0.657795 -0.264056 0.705392 -0.657797 -0.387311 0.705392 -0.593643 -0.387308 0.705398 -0.593638 -0.495679 0.705399 -0.50667 -0.495683 0.705393 -0.506675 -0.585005 0.705394 -0.400236 -0.585001 0.705399 -0.400233 -0.651842 0.705399 -0.278415 -0.651842 0.705399 -0.278414 -0.693632 0.7054 -0.145896 -0.693641 0.705391 -0.145899 -0.708776 0.705391 -0.00777246 -0.708772 0.705395 -0.00777228 -0.696669 0.705395 0.130652 -0.696669 0.705395 0.130652 -0.657794 0.705395 0.264054 -0.657796 0.705393 0.264055 -0.593641 0.705394 0.387311 -0.59364 0.705395 0.38731 -0.506674 0.705394 0.495682 -0.506672 0.705397 0.49568 -0.400233 0.705398 0.585002 -0.400233 0.705399 0.585001 -0.278414 0.705399 0.651842 -0.278417 0.705393 0.651847 -0.145898 0.705393 0.693638 -0.145898 0.705391 0.69364 -0.00777246 0.705391 0.708776 -0.00777228 0.705395 0.708772 0.130652 0.705395 0.696669 0.130652 0.705394 0.69667 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0156493 -0.694744 0.719087 0.0156494 -0.694744 0.719087 -0.345989 -0.694746 0.630571 -0.345992 -0.694742 0.630574 -0.614926 -0.694741 0.373097 -0.614924 -0.694743 0.373097 -0.719088 -0.694743 0.015649 -0.719086 -0.694745 0.0156494 -0.630572 -0.694745 -0.345989 -0.630575 -0.694741 -0.345992 -0.373097 -0.694742 -0.614924 -0.373097 -0.694743 -0.614924 0.0156493 -0.694743 0.719088 0.0156494 -0.694743 0.719087 -0.34599 -0.694745 0.630571 -0.34599 -0.694745 0.630571 -0.61492 -0.694747 0.373095 -0.614923 -0.694744 0.373096 -0.719088 -0.694743 0.015649 -0.719086 -0.694745 0.0156494 -0.630571 -0.694746 -0.345989 -0.630575 -0.694741 -0.345992 -0.373097 -0.694742 -0.614925 -0.373096 -0.694745 -0.614922 0.015649 -0.694743 0.719088 0.0156494 -0.694745 0.719086 -0.345989 -0.694746 0.63057 -0.345991 -0.694744 0.630572 -0.614923 -0.694744 0.373096 -0.614923 -0.694744 0.373096 -0.719088 -0.694743 0.015649 -0.719086 -0.694745 0.0156494 -0.630572 -0.694745 -0.34599 -0.630574 -0.694742 -0.345992 -0.373097 -0.694741 -0.614926 -0.373096 -0.694744 -0.614923 -0.373097 -0.694743 -0.614924 -0.946507 -0.322025 0.0205987 -0.373097 -0.694741 -0.614926 -0.597961 -0.700857 -0.388899 -0.800995 -0.406505 -0.439501 -0.673294 -0.706112 -0.219274 -0.708164 -0.703121 -0.0642215 -0.698946 -0.704871 0.120957 -0.654506 -0.704872 0.273454 -0.809398 -0.32203 0.491092 0.015649 -0.694739 0.719091 0.0156495 -0.694742 0.719089 -0.295435 -0.700857 0.649244 -0.439498 -0.406514 0.800992 -0.450095 -0.706116 0.54664 -0.562801 -0.703124 0.434594 0.0156496 -0.694746 0.719085 0.0156494 -0.694745 0.719086 -0.34599 -0.694745 0.630572 -0.345991 -0.694744 0.630572 -0.614923 -0.694744 0.373096 -0.614923 -0.694744 0.373096 -0.719088 -0.694743 0.0156493 -0.719087 -0.694744 0.0156494 -0.630574 -0.694741 -0.345992 -0.630574 -0.694742 -0.345992 -0.373098 -0.694741 -0.614926 -0.373097 -0.694742 -0.614924 -0.348272 -0.698071 -0.625623 -0.348273 -0.69807 -0.625624 -0.492296 -0.706856 -0.507937 -0.665099 -0.581217 -0.46886 -0.857048 -0.450657 0.249754 -0.597959 -0.70086 -0.388898 -0.673293 -0.706114 -0.219273 -0.861629 -0.486774 -0.143686 -0.708161 -0.703124 -0.064221 -0.698945 -0.704872 0.120957 -0.654508 -0.70487 0.273455 -0.562803 -0.703121 0.434596 -0.649555 -0.486774 0.584062 -0.450098 -0.706112 0.546642 -0.271988 -0.69807 0.662361 0.0423349 -0.698072 0.714775 0.042335 -0.698072 0.714775 -0.142358 -0.706858 0.692882 -0.346644 -0.547287 0.761784 0.0156494 -0.694744 0.719087 0.0156494 -0.694744 0.719087 -0.345992 -0.694742 0.630574 -0.345992 -0.694742 0.630574 -0.614926 -0.69474 0.373097 -0.614921 -0.694746 0.373096 -0.719085 -0.694746 0.0156503 -0.719089 -0.694742 0.0156495 -0.630574 -0.694742 -0.345992 -0.630574 -0.694741 -0.345993 -0.373097 -0.694742 -0.614924 -0.373096 -0.694746 -0.614921 0.0423349 -0.698074 0.714773 0.0423346 -0.698072 0.714775 -0.271986 -0.698072 0.662358 -0.271987 -0.698071 0.662359 -0.532439 -0.698071 0.478755 -0.532439 -0.69807 0.478755 -0.687435 -0.698071 0.200326 -0.687435 -0.69807 0.200326 -0.706277 -0.69807 -0.117779 -0.706276 -0.698071 -0.117779 -0.58523 -0.69807 -0.412557 -0.58523 -0.698071 -0.412557 -0.348273 -0.698071 -0.625622 -0.348273 -0.698069 -0.625624 0.015649 -0.694743 0.719088 0.0156494 -0.694745 0.719086 -0.34599 -0.694745 0.630572 -0.345992 -0.694741 0.630575 -0.614925 -0.694742 0.373097 -0.614923 -0.694744 0.373096 -0.719086 -0.694745 0.0156496 -0.719087 -0.694743 0.0156494 -0.630572 -0.694745 -0.34599 -0.630572 -0.694744 -0.345991 -0.373096 -0.694744 -0.614923 -0.373096 -0.694744 -0.614923 -0.348273 -0.698067 -0.625626 -0.348272 -0.698073 -0.625621 -0.492293 -0.706858 -0.507937 -0.665099 -0.581218 -0.46886 -0.857049 -0.450655 0.249754 -0.597957 -0.700861 -0.388896 -0.673292 -0.706115 -0.219273 -0.861629 -0.486774 -0.143686 -0.708163 -0.703122 -0.0642218 -0.698946 -0.704871 0.120957 -0.654508 -0.70487 0.273455 -0.562803 -0.703121 0.434596 -0.649556 -0.486773 0.584063 -0.450096 -0.706114 0.546641 -0.271987 -0.698071 0.662359 0.0423358 -0.69807 0.714777 0.0423362 -0.698072 0.714775 -0.142357 -0.706858 0.692882 -0.346646 -0.547284 0.761785 -0.348272 -0.698072 -0.625621 -0.348273 -0.69807 -0.625624 -0.492294 -0.706856 -0.507939 -0.6651 -0.581214 -0.468862 -0.85705 -0.450654 0.249754 -0.59796 -0.700858 -0.388899 -0.673294 -0.706113 -0.219273 -0.861631 -0.486772 -0.143686 -0.708164 -0.703121 -0.0642213 -0.698948 -0.704869 0.120958 -0.654508 -0.70487 0.273455 -0.562803 -0.703121 0.434596 -0.649556 -0.486771 0.584064 -0.450096 -0.706113 0.546642 -0.271988 -0.698071 0.662359 0.0423358 -0.69807 0.714777 0.0423362 -0.698072 0.714775 -0.142357 -0.706858 0.692883 -0.346647 -0.547283 0.761786 -0.348272 -0.698071 -0.625623 -0.348273 -0.698069 -0.625624 -0.492299 -0.706854 -0.507935 -0.665097 -0.58122 -0.46886 -0.597958 -0.700859 -0.388899 -0.673293 -0.706114 -0.219271 -0.861628 -0.486778 -0.143685 -0.708165 -0.703121 -0.0642225 -0.698948 -0.70487 0.120957 -0.857051 -0.450651 0.249755 -0.654509 -0.704868 0.273456 -0.562803 -0.703121 0.434597 -0.649554 -0.486778 0.584061 -0.450098 -0.706113 0.54664 -0.271987 -0.698071 0.662359 0.042335 -0.69807 0.714777 0.0423354 -0.698072 0.714775 -0.142358 -0.706858 0.692882 -0.346644 -0.547287 0.761784 0.657712 -0.70622 -0.262046 0.657712 -0.70622 -0.262046 0.688079 -0.70622 -0.166737 0.688078 -0.70622 -0.166737 0.555601 -0.697262 -0.452916 0.5556 -0.697264 -0.452916 0.291435 -0.697264 -0.654896 0.291436 -0.697262 -0.654898 -0.0354492 -0.697262 -0.71594 0.0217291 -0.413787 -0.910114 -0.147751 -0.706152 -0.692473 -0.570195 -0.704307 -0.422882 -0.570195 -0.704307 -0.422882 -0.447288 -0.704308 -0.551257 -0.447288 -0.704306 -0.551259 -0.413024 -0.699237 0.583506 -0.413024 -0.699237 0.583505 -0.614794 -0.699237 0.364824 -0.614795 -0.699235 0.364825 -0.710063 -0.699235 0.0829447 -0.710063 -0.699236 0.0829448 -0.682327 -0.699236 -0.213305 -0.682327 -0.699235 -0.213305 -0.136644 -0.706221 0.694681 -0.136644 -0.70622 0.694681 -0.233184 -0.706221 0.668489 -0.233184 -0.706221 0.668489 0.523045 -0.700705 0.485218 0.523045 -0.700705 0.485218 0.30668 -0.700705 0.644174 0.30668 -0.700704 0.644174 0.0468856 -0.700705 0.711909 0.0468858 -0.700705 0.711909 0.516138 -0.699582 0.494152 0.516138 -0.699583 0.494151 0.713275 -0.700705 0.0158696 0.713275 -0.700705 0.0158697 0.656906 -0.700705 0.278365 0.656906 -0.700705 0.278364 0.507514 -0.700705 0.50144 0.507514 -0.700705 0.50144 0.555794 -0.706221 0.438572 0.555794 -0.70622 0.438572 0.488437 -0.706221 0.512525 0.488438 -0.70622 0.512525 0.460923 -0.699236 -0.54646 0.460923 -0.699236 -0.54646 0.643462 -0.699237 -0.311488 0.643463 -0.699235 -0.311488 0.714535 -0.699236 -0.0225574 0.714535 -0.699236 -0.0225573 0.661829 -0.699235 0.270282 0.661828 -0.699237 0.270281 0.0811289 -0.704307 -0.705245 0.0811288 -0.704307 -0.705245 0.253759 -0.704307 -0.662992 0.253759 -0.704308 -0.662991 -0.10424 -0.703805 -0.702704 -0.104239 -0.703802 -0.702707 -0.669933 -0.70622 0.229003 -0.669933 -0.706221 0.229003 -0.695521 -0.706221 0.132302 -0.695521 -0.70622 0.132302 -0.158689 -0.700705 0.695579 -0.158689 -0.700705 0.695579 -0.404531 -0.700705 0.58768 -0.404531 -0.700705 0.587679 -0.593088 -0.700705 0.396558 -0.593088 -0.700705 0.396558 -0.169878 -0.699583 0.694064 -0.169879 -0.699582 0.694065 0.342894 -0.700705 0.625649 0.342894 -0.700705 0.625649 0.0873826 -0.700705 0.70808 0.0873823 -0.700705 0.70808 -0.180503 -0.700704 0.690241 -0.180503 -0.700705 0.69024 -0.101918 -0.70622 0.700618 -0.101918 -0.706221 0.700618 -0.199641 -0.706221 0.679261 -0.199641 -0.70622 0.679262 0.0968434 -0.699236 0.708301 0.70371 -0.699236 0.125941 0.703711 -0.699235 0.125941 0.591489 -0.699235 0.401511 0.591488 -0.699236 0.40151 0.376802 -0.699236 0.607527 0.376803 -0.699236 0.607527 0.218816 -0.706935 0.672579 0.0824805 -0.616059 0.78337 0.651323 -0.704308 -0.282362 0.651323 -0.704309 -0.282362 0.701045 -0.704309 -0.111734 0.701046 -0.704308 -0.111734 -0.0454829 -0.698432 -0.71423 -0.045483 -0.698433 -0.714229 0.26302 -0.698432 -0.665593 0.26302 -0.698432 -0.665593 0.521435 -0.698431 -0.490204 0.521435 -0.698431 -0.490204 -0.533289 -0.70622 -0.465678 -0.53329 -0.70622 -0.465678 -0.462337 -0.70622 -0.536188 -0.462336 -0.706221 -0.536187 -0.681734 -0.700705 0.210361 -0.681733 -0.700706 0.210361 -0.71121 -0.700706 -0.0564942 -0.711211 -0.700705 -0.056495 -0.639974 -0.700705 -0.31535 -0.639974 -0.700705 -0.31535 -0.686016 -0.699583 0.199913 -0.686016 -0.699583 0.199913 -0.370381 -0.700705 0.609779 -0.37038 -0.700705 0.609779 -0.569523 -0.700705 0.429715 -0.569524 -0.700705 0.429715 -0.688017 -0.700705 0.1888 -0.688016 -0.700705 0.1888 -0.657712 -0.70622 0.262046 -0.657712 -0.70622 0.262046 -0.688078 -0.70622 0.166737 -0.688078 -0.70622 0.166737 -0.564986 -0.699235 0.43802 -0.564984 -0.699237 0.438019 -0.337731 -0.699238 0.630083 -0.337733 -0.699236 0.630084 -0.163717 -0.706682 0.68833 -0.0582005 -0.599301 0.798405 0.289575 -0.703804 0.648696 0.280047 -0.565715 0.77559 0.147751 -0.706153 0.692473 -0.0169867 -0.702503 0.711478 0.570195 -0.704307 0.422882 0.570195 -0.704307 0.422882 0.447287 -0.704308 0.551257 0.447287 -0.704308 0.551257 0.413024 -0.699237 -0.583506 0.413024 -0.699237 -0.583505 0.614794 -0.699237 -0.364824 0.614795 -0.699235 -0.364825 0.710063 -0.699235 -0.0829447 0.710063 -0.699236 -0.0829448 0.682327 -0.699236 0.213305 0.682327 -0.699235 0.213305 0.136644 -0.706221 -0.694681 0.136644 -0.70622 -0.694681 0.233184 -0.706221 -0.668489 0.233184 -0.706221 -0.668489 -0.0571086 -0.699693 -0.712158 -0.0571086 -0.699693 -0.712158 -0.516138 -0.699582 -0.494152 -0.516138 -0.699583 -0.494151 -0.713275 -0.700705 -0.0158696 -0.713274 -0.700705 -0.0158694 -0.656906 -0.700705 -0.278364 -0.656906 -0.700705 -0.278365 -0.507514 -0.700705 -0.50144 -0.507514 -0.700705 -0.50144 -0.555794 -0.706221 -0.438572 -0.555794 -0.70622 -0.438572 -0.488437 -0.706221 -0.512525 -0.488438 -0.70622 -0.512525 -0.460923 -0.699235 0.546461 -0.460922 -0.699236 0.54646 -0.643462 -0.699237 0.311488 -0.643461 -0.699237 0.311488 -0.714533 -0.699238 0.0225573 -0.714535 -0.699236 0.0225566 -0.661829 -0.699235 -0.270282 -0.661828 -0.699237 -0.270281 -0.0811289 -0.704306 0.705245 -0.0811288 -0.704307 0.705245 -0.253759 -0.704307 0.662992 -0.25376 -0.704307 0.662992 0.156436 -0.699235 0.697566 0.130563 -0.456378 0.880155 0.247377 -0.706154 0.663439 0.426863 -0.699237 0.57346 0.711844 -0.699236 0.065937 0.711843 -0.699236 0.0659368 0.623344 -0.699237 0.350015 0.623344 -0.699237 0.350015 0.50786 -0.706683 0.492624 0.463232 -0.555697 0.690374 0.669933 -0.706221 -0.229003 0.669933 -0.70622 -0.229003 0.695521 -0.70622 -0.132302 0.695521 -0.70622 -0.132302 0.158689 -0.700705 -0.695579 0.158688 -0.700706 -0.695578 0.404531 -0.700706 -0.587679 0.404531 -0.700705 -0.587679 0.593088 -0.700705 -0.396558 0.593088 -0.700705 -0.396558 0.169878 -0.699583 -0.694064 0.169879 -0.699582 -0.694065 -0.0721749 -0.701183 -0.709319 -0.0721749 -0.701183 -0.709319 0.185296 -0.701183 -0.688482 0.185297 -0.701182 -0.688483 0.101918 -0.70622 -0.700618 0.101918 -0.70622 -0.700618 0.199641 -0.70622 -0.679262 0.199641 -0.706221 -0.679262 -0.0746334 -0.70141 -0.708839 -0.0746333 -0.70141 -0.70884 -0.651323 -0.704308 0.282362 -0.651322 -0.704309 0.282362 -0.701045 -0.704309 0.111734 -0.701046 -0.704308 0.111734 -0.52589 -0.699236 0.48426 -0.525891 -0.699236 0.48426 -0.2832 -0.699236 0.656404 -0.283199 -0.699237 0.656404 0.00855035 -0.699237 0.714839 0.317841 -0.701411 0.637965 0.323753 -0.63252 0.703635 0.176751 -0.706935 0.684837 0.00855018 -0.699236 0.71484 0.533289 -0.706221 0.465677 0.53329 -0.70622 0.465678 0.462337 -0.70622 0.536188 0.462336 -0.706221 0.536187 0.681733 -0.700705 -0.210361 0.681734 -0.700705 -0.210361 0.711211 -0.700705 0.0564943 0.711211 -0.700705 0.0564946 0.639974 -0.700704 0.315351 0.639974 -0.700706 0.31535 0.686016 -0.699583 -0.199913 0.686016 -0.699583 -0.199913 0.37038 -0.700706 -0.609779 0.370381 -0.700705 -0.609779 0.569523 -0.700705 -0.429715 0.569524 -0.700705 -0.429715 0.688017 -0.700705 -0.1888 0.688016 -0.700705 -0.1888 -0.348271 -0.698074 -0.62562 -0.34827 -0.698073 -0.625621 -0.492292 -0.706859 -0.507936 -0.588536 -0.693898 -0.414887 -0.597957 -0.700862 -0.388896 -0.673291 -0.706116 -0.21927 -0.71268 -0.691348 -0.118847 -0.708161 -0.703125 -0.0642224 -0.687432 -0.698074 0.200326 -0.731149 -0.670381 0.126531 -0.654505 -0.704873 0.273453 -0.532437 -0.698074 0.478753 -0.579992 -0.680458 0.447868 -0.450094 -0.706116 0.54664 -0.271987 -0.698074 0.662357 0.0423344 -0.698074 0.714774 0.0423354 -0.698074 0.714773 -0.142357 -0.70686 0.692881 -0.299915 -0.689672 0.659093 0.0156492 -0.694747 0.719084 0.0156494 -0.694747 0.719084 -0.34599 -0.694746 0.63057 -0.34599 -0.694747 0.63057 -0.61492 -0.694747 0.373095 -0.61492 -0.694747 0.373095 -0.719084 -0.694747 0.0156492 -0.719084 -0.694747 0.0156496 -0.63057 -0.694747 -0.345989 -0.63057 -0.694746 -0.34599 -0.373095 -0.694746 -0.614921 -0.373095 -0.694747 -0.61492 -0.348271 -0.698074 -0.62562 -0.348271 -0.698074 -0.62562 -0.49229 -0.706859 -0.507937 -0.588536 -0.693898 -0.414887 -0.597957 -0.700862 -0.388896 -0.673291 -0.706116 -0.21927 -0.71268 -0.691348 -0.118847 -0.708161 -0.703124 -0.0642226 -0.698945 -0.704873 0.120958 -0.694455 -0.690491 0.202372 -0.654505 -0.704873 0.273453 -0.532437 -0.698074 0.478753 -0.57999 -0.680459 0.44787 -0.450098 -0.706116 0.546637 -0.271986 -0.698074 0.662357 0.0423343 -0.698074 0.714774 0.0423351 -0.698074 0.714773 -0.142359 -0.70686 0.692881 -0.299914 -0.689672 0.659093 -0.348271 -0.698074 -0.62562 -0.348271 -0.698073 -0.625621 -0.492297 -0.706859 -0.507932 -0.588536 -0.693898 -0.414888 -0.597957 -0.700862 -0.388896 -0.67329 -0.706116 -0.219274 -0.71268 -0.691348 -0.118847 -0.708161 -0.703125 -0.0642213 -0.698944 -0.704873 0.120957 -0.694455 -0.690491 0.202372 -0.654505 -0.704873 0.273454 -0.532437 -0.698074 0.478753 -0.579992 -0.680458 0.447868 -0.450097 -0.706116 0.546638 -0.271986 -0.698074 0.662357 0.0423371 -0.698074 0.714773 0.0423348 -0.698073 0.714774 -0.142373 -0.706859 0.692878 -0.299913 -0.689672 0.659093 -0.373095 -0.694747 -0.614921 -0.373094 -0.694746 -0.614922 -0.63057 -0.694746 -0.345989 -0.61924 -0.67405 -0.402739 -0.673291 -0.706116 -0.219271 -0.719084 -0.694747 0.0156494 -0.746218 -0.662253 -0.0676726 -0.698944 -0.704873 0.120958 -0.654505 -0.704873 0.273454 -0.623292 -0.684464 0.378175 0.0156492 -0.694747 0.719084 0.0156496 -0.694747 0.719084 -0.29543 -0.700862 0.64924 -0.349908 -0.686215 0.63771 -0.450097 -0.706116 0.546638 -0.562801 -0.703124 0.434593 -0.373095 -0.694747 -0.614921 -0.373094 -0.694746 -0.614921 -0.63057 -0.694746 -0.34599 -0.63057 -0.694747 -0.345989 -0.708082 -0.70316 -0.0646908 -0.697647 -0.716281 0.0151826 0.0156492 -0.694746 0.719085 0.0156496 -0.694747 0.719084 -0.345989 -0.694747 0.63057 -0.34599 -0.694746 0.63057 -0.614921 -0.694746 0.373095 -0.614921 -0.694746 0.373095 -0.699051 -0.704846 0.120496 -0.348271 -0.698074 -0.62562 -0.348271 -0.698074 -0.62562 -0.492292 -0.706859 -0.507936 -0.588536 -0.693898 -0.414888 -0.597957 -0.700862 -0.388896 -0.673291 -0.706116 -0.21927 -0.71268 -0.691348 -0.118847 -0.708161 -0.703124 -0.0642225 -0.687432 -0.698074 0.200326 -0.731149 -0.670381 0.126531 -0.654506 -0.704873 0.273453 -0.532437 -0.698074 0.478753 -0.57999 -0.680459 0.44787 -0.450098 -0.706116 0.546637 -0.271986 -0.698074 0.662357 0.042335 -0.698074 0.714773 0.042335 -0.698074 0.714773 -0.142363 -0.706859 0.69288 -0.299914 -0.689672 0.659093 -0.373095 -0.694746 -0.614921 -0.373096 -0.694747 -0.61492 -0.63057 -0.694747 -0.34599 -0.63057 -0.694746 -0.34599 -0.719084 -0.694747 0.0156496 -0.719085 -0.694746 0.0156492 -0.614921 -0.694747 0.373095 -0.61492 -0.694747 0.373095 -0.345989 -0.694747 0.63057 -0.34599 -0.694746 0.63057 -0.0340659 -0.7005 0.712839 0.0152786 -0.712009 0.702004 0.150382 -0.706252 0.691805 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.120957 -0.704873 0.698945 0.120958 -0.704868 0.698949 0.00808457 -0.706699 0.707468 -0.0525094 -0.13784 0.989062 -0.0712106 -0.706366 0.704255 -0.173647 -0.705898 0.686698 -0.261423 -0.298315 0.917969 -0.249071 -0.706951 0.661955 -0.309234 -0.706416 0.636672 -0.476957 -0.130002 0.869259 -0.378439 -0.706668 0.597832 -0.471043 -0.704872 0.530354 -0.471043 -0.70487 0.530355 -0.577248 -0.704871 0.41224 -0.577247 -0.704872 0.41224 -0.654506 -0.704872 0.273454 -0.654505 -0.704873 0.273454 -0.698945 -0.704873 0.120957 -0.698945 -0.704873 0.120957 -0.708264 -0.705438 -0.0268286 -0.861951 -0.504923 -0.0457611 -0.699201 -0.707066 -0.105716 -0.682209 -0.704873 -0.194283 -0.682212 -0.704869 -0.194283 -0.638633 -0.706554 -0.304842 -0.87048 -0.118906 -0.477626 -0.600497 -0.706542 -0.374436 -0.541594 -0.705781 -0.456671 -0.699743 -0.352296 -0.621488 -0.486228 -0.70699 -0.513563 -0.412239 -0.704874 -0.577246 -0.41224 -0.704872 -0.577247 -0.273454 -0.704872 -0.654506 -0.273456 -0.704869 -0.654509 -0.385508 0 -0.922705 -0.385508 0 -0.922705 -0.581164 0 -0.813787 -0.581164 0 -0.813787 -0.747677 0 -0.664062 -0.747677 0 -0.664062 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.96176 0 -0.273895 -0.96176 0 -0.273895 -0.998594 0 -0.0530155 -0.998594 0 -0.0530155 -0.985354 0 0.170522 -0.985354 0 0.170522 -0.922704 0 0.385508 -0.922704 0 0.385508 -0.813787 0 0.581164 -0.813787 0 0.581164 -0.664062 0 0.747677 -0.664062 0 0.747677 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.273894 0 0.96176 -0.273894 0 0.96176 -0.0530155 0 0.998594 -0.0530155 0 0.998594 0.170521 0 0.985354 0.170521 0 0.985354 -0.348271 -0.698074 -0.62562 -0.34827 -0.698074 -0.62562 -0.492286 -0.70686 -0.507941 -0.588536 -0.693898 -0.414887 -0.597957 -0.700862 -0.388897 -0.673291 -0.706116 -0.219271 -0.71268 -0.691348 -0.118847 -0.708161 -0.703125 -0.0642217 -0.698944 -0.704873 0.120957 -0.694455 -0.690491 0.202372 -0.654505 -0.704873 0.273454 -0.532437 -0.698074 0.478753 -0.579992 -0.680458 0.447869 -0.450097 -0.706116 0.546638 -0.271986 -0.698074 0.662357 0.0423343 -0.698074 0.714773 0.0423348 -0.698074 0.714773 -0.142357 -0.70686 0.692881 -0.299914 -0.689672 0.659093 -0.722324 0 -0.691554 -0.722324 0 -0.691554 -0.26606 0 -0.963956 -0.0799324 0.00686626 -0.996777 -0.0657166 0 -0.997838 0.193002 0 -0.981198 0.193002 0 -0.981198 0.329359 0 -0.944205 0.329359 0 -0.944205 0.954449 0 0.298374 0.954449 0 0.298374 0.993246 0 -0.116024 0.993246 0 -0.116024 0.859983 0 -0.510322 0.859983 0 -0.510322 0.577745 0 -0.816217 0.577745 0 -0.816217 0.80321 0 0.595696 0.80321 0 0.595696 0.630076 0 0.776534 0.630076 0 0.776534 0.407626 0 0.913149 0.407626 0 0.913149 -0.928982 0 0.370125 -0.928982 0 0.370125 -0.971873 0 0.235507 -0.971873 0 0.235507 -0.999753 0 -0.0222434 -0.999753 0 -0.0222434 -0.920745 0 -0.390166 -0.920745 0 -0.390166 -0.711351 0 -0.702837 -0.711351 0 -0.702837 -0.753241 0 -0.657744 -0.753241 0 -0.657744 -0.653026 0 -0.757336 -0.653026 0 -0.757336 0.735623 0 -0.677391 0.728568 0.00756422 -0.684931 0.396134 -0.00719696 -0.918165 0.367474 0.0143921 -0.929923 -0.011959 -0.0136553 -0.999835 -0.063539 0.0204793 -0.997769 -0.417914 -0.0193724 -0.90828 -0.445932 0 -0.895067 0.917493 0 -0.397752 0.917493 0 -0.397752 0.987536 0 -0.157395 0.987536 0 -0.157395 0.309378 0 0.950939 0.482413 -0.0204792 0.875705 0.527028 0.0136553 0.849738 0.809504 -0.0143922 0.586938 0.827361 0.0071967 0.561625 0.98246 -0.00756464 0.186318 0.98436 0 0.176168 -0.143953 0 0.989585 -0.143953 0 0.989585 -0.281981 0 0.95942 -0.281981 0 0.95942 -0.519139 0 0.85469 -0.519139 0 0.85469 -0.798266 0 0.602305 -0.798266 0 0.602305 -0.96435 0 0.264629 -0.96435 0 0.264629 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.955544 0 0.294849 -0.955544 0 0.294849 -0.99686 0 -0.0791846 -0.99686 0 -0.0791846 -0.897012 0 -0.442007 -0.897012 0 -0.442007 -0.946244 0 0.323454 -0.946244 0 0.323454 -0.982385 0 0.186869 -0.982385 0 0.186869 -0.146735 0 -0.989176 -0.218692 -0.035025 -0.975165 -0.349374 0 -0.936983 -0.597103 0 -0.802165 -0.556825 -0.0357808 -0.829859 -0.871101 0.0439432 -0.489134 -0.83352 -0.021994 -0.552051 -0.995539 0.0199554 -0.092215 -0.993185 0 -0.116547 0.114283 0 -0.993448 0.114283 0 -0.993448 0.35746 0 -0.933928 0.35746 0 -0.933928 0.925775 0 0.378074 0.925775 0 0.378074 0.999502 0 -0.0315536 0.999502 0 -0.0315536 0.900085 0 -0.435715 0.900085 0 -0.435715 0.644746 0 -0.764397 0.644746 0 -0.764397 0.785029 0 0.619459 0.785029 0 0.619459 0.689891 0 0.723913 0.689891 0 0.723913 0.480613 0 0.876933 0.468052 -0.00686625 0.883674 0.122476 0.00635469 0.992451 0.101229 -0.00317746 0.994858 -0.252999 0.00330544 0.967461 -0.25989 0 0.965638 -0.237741 0 0.971328 -0.237741 0 0.971328 -0.222424 0 0.97495 -0.222424 0 0.97495 -0.567006 0 0.823714 -0.567006 0 0.823714 -0.831295 0 0.555831 -0.831295 0 0.555831 -0.193002 0 0.981198 -0.193002 0 0.981198 -0.329359 0 0.944205 -0.329359 0 0.944205 -0.954449 0 -0.298374 -0.954449 0 -0.298374 -0.993246 0 0.116024 -0.993246 0 0.116024 -0.859983 0 0.510322 -0.859983 0 0.510322 -0.577745 0 0.816217 -0.577745 0 0.816217 -0.80321 0 -0.595696 -0.80321 0 -0.595696 -0.630076 0 -0.776534 -0.630076 0 -0.776534 0.79031 0 -0.612708 0.774971 0.0179047 -0.631744 0.472365 -0.0158418 -0.88126 0.406366 0.0316634 -0.913162 0.0726751 -0.0275254 -0.996976 0.0238684 0 -0.999715 -0.20867 0 -0.977986 -0.339406 -0.035025 -0.939988 -0.407624 0 -0.91315 0.928982 0 -0.370125 0.928982 0 -0.370125 0.971873 0 -0.235507 0.971873 0 -0.235507 0.999753 0 0.0222434 0.999753 0 0.0222434 0.920745 0 0.390166 0.920745 0 0.390166 0.711351 0 0.702837 0.711351 0 0.702837 0.722324 0 0.691554 0.722324 0 0.691554 0.733119 0 0.6801 0.737944 0.00343312 0.674854 0.429851 -0.00356103 0.902893 0.44905 0.00712152 0.893478 0.0657148 -0.00737645 0.997811 0.0799343 0 0.9968 0.753242 0 0.657744 0.753242 0 0.657744 0.653026 0 0.757336 0.653026 0 0.757336 0.445932 0 0.895067 0.445932 0 0.895067 -0.917493 0 0.397752 -0.917493 0 0.397752 -0.987536 0 0.157395 -0.987536 0 0.157395 -0.135466 0 -0.990782 -0.104684 -0.0226848 -0.994247 -0.526899 0.0259748 -0.849531 -0.482442 -0.017321 -0.875757 -0.827269 0.0165917 -0.561562 -0.80956 -0.00829689 -0.586978 -0.984329 0.00793137 -0.176162 -0.982488 0 -0.186324 0.143953 0 -0.989585 0.143953 0 -0.989585 0.281981 0 -0.95942 0.281981 0 -0.95942 0.519139 0 -0.85469 0.519139 0 -0.85469 0.798266 0 -0.602305 0.798266 0 -0.602305 0.96435 0 -0.264629 0.96435 0 -0.264629 0.960066 0 -0.279774 0.960066 0 -0.279774 0.955544 0 -0.29485 0.955544 0 -0.29485 0.99686 0 0.0791846 0.99686 0 0.0791846 0.897012 0 0.442007 0.897012 0 0.442007 0.946244 0 -0.323454 0.946244 0 -0.323454 0.982385 0 -0.186869 0.982385 0 -0.186869 0.349374 0 0.936983 0.494412 -0.0412481 0.868248 0.557181 0 0.830391 0.717792 0 0.696258 0.833304 -0.0316633 0.551908 0.871834 0.0158423 0.489545 0.993026 -0.0179043 0.116529 0.995737 0 0.0922336 -0.114283 0 0.993448 -0.114283 0 0.993448 -0.35746 0 0.933928 -0.35746 0 0.933928 -0.925775 0 -0.378074 -0.925775 0 -0.378074 -0.999502 0 0.0315536 -0.999502 0 0.0315536 -0.900085 0 0.435715 -0.900085 0 0.435715 -0.644746 0 0.764397 -0.644746 0 0.764397 -0.785029 0 -0.619459 -0.785029 0 -0.619459 -0.689891 0 -0.723913 -0.689891 0 -0.723913 -0.10123 0 -0.994863 -0.108318 0.00330545 -0.994111 0.259888 -0.00343326 -0.965633 0.253 0 -0.967466 0.237741 0 -0.971328 0.237741 0 -0.971328 0.222424 0 -0.97495 0.222424 0 -0.97495 0.567006 0 -0.823714 0.567006 0 -0.823714 0.831295 0 -0.555831 0.831295 0 -0.555831 0.059125 0 0.998251 0.059125 0 0.998251 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817327 0 -0.576173 -0.817327 0 -0.576173 -0.486394 0 -0.873739 -0.486394 0 -0.873739 0.0591247 0 0.998251 0.0217518 -0.0239937 0.999475 -0.201253 0 0.979539 -0.414178 0 0.910196 -0.480653 -0.0400446 0.875996 -0.635642 0 0.771984 -0.791487 0 0.611186 -0.853953 -0.0480813 0.518124 -0.922705 0 0.385508 -0.985354 0 0.170522 -0.998607 -0.0480811 0.0217329 -0.995913 0 -0.0903164 -0.950846 0 -0.309665 -0.875996 -0.0400443 -0.480654 -0.486394 0 -0.87374 -0.518575 -0.0239945 -0.854695 -0.695965 0 -0.718076 -0.8383 0 -0.54521 0.021758 0 0.999763 0.021758 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.0217576 -0.999763 0 0.0217576 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.0217571 0 0.999763 0.0591006 0.0279047 0.997862 -0.41406 -0.0239945 0.909933 -0.379856 0 0.925046 -0.635641 0 0.771985 -0.743216 -0.0321123 0.66828 -0.791487 0 0.611186 -0.922704 0 0.385508 -0.959439 -0.0361379 0.279592 -0.985354 0 0.170522 -0.995913 0 -0.0903167 -0.98587 -0.0321123 -0.164404 -0.950846 0 -0.309665 -0.8383 0 -0.545209 -0.817163 -0.0200482 -0.576057 -0.518574 0.0239943 -0.854696 -0.486393 0 -0.87374 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518723 0 -0.854942 -0.518723 0 -0.854942 0.0591247 0 0.998251 0.0217513 0.023994 0.999475 -0.201257 0 0.979539 -0.414178 0 0.910196 -0.480653 0.0400446 0.875996 -0.635642 0 0.771984 -0.791486 0 0.611187 -0.853952 0.0480815 0.518125 -0.922705 0 0.385508 -0.985354 0 0.170522 -0.998607 0.0480814 0.0217319 -0.995913 0 -0.090318 -0.950847 0 -0.309661 -0.875997 0.0400449 -0.480652 -0.8383 0 -0.54521 -0.695961 0 -0.718079 -0.518575 0.0239941 -0.854696 -0.486394 0 -0.87374 0.0217576 0 0.999763 0.0217576 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.0217571 -0.999763 0 0.0217571 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.0591247 0 0.998251 0.0591247 0 0.998251 -0.201253 0 0.979539 -0.201253 0 0.979539 -0.414178 0 0.910196 -0.414178 0 0.910196 -0.635643 0 0.771983 -0.635643 0 0.771983 -0.791486 0 0.611187 -0.791486 0 0.611187 -0.922704 0 0.385508 -0.922704 0 0.385508 -0.985354 0 0.170521 -0.985354 0 0.170521 -0.995913 0 -0.090318 -0.995913 0 -0.090318 -0.950847 0 -0.309662 -0.950847 0 -0.309662 -0.838299 0 -0.545211 -0.838299 0 -0.545211 -0.695968 0 -0.718073 -0.695968 0 -0.718073 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0.0591258 0 0.998251 0.0591258 0 0.998251 -0.201252 0 0.97954 -0.201252 0 0.97954 -0.414179 0 0.910195 -0.414179 0 0.910195 -0.63564 0 0.771986 -0.63564 0 0.771986 -0.791487 0 0.611186 -0.791487 0 0.611186 -0.922705 0 0.385508 -0.922705 0 0.385508 -0.985354 0 0.170522 -0.985354 0 0.170522 -0.995913 0 -0.0903164 -0.995913 0 -0.0903164 -0.950846 0 -0.309664 -0.950846 0 -0.309664 -0.838299 0 -0.54521 -0.838299 0 -0.54521 -0.695961 0 -0.718079 -0.695961 0 -0.718079 -0.486394 0 -0.873739 -0.486394 0 -0.873739 0.0591258 0 0.998251 0.0591258 0 0.998251 -0.201253 0 0.979539 -0.201253 0 0.979539 -0.414179 0 0.910195 -0.414179 0 0.910195 -0.63564 0 0.771985 -0.63564 0 0.771985 -0.791487 0 0.611186 -0.791487 0 0.611186 -0.922705 0 0.385508 -0.922705 0 0.385508 -0.985354 0 0.170521 -0.985354 0 0.170521 -0.995913 0 -0.0903172 -0.995913 0 -0.0903172 -0.950846 0 -0.309665 -0.950846 0 -0.309665 -0.8383 0 -0.545209 -0.8383 0 -0.545209 -0.695962 0 -0.718078 -0.695962 0 -0.718078 -0.486395 0 -0.873739 -0.486395 0 -0.873739 0.0217571 0 0.999763 0.0217571 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.0217581 -0.999763 0 0.0217581 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.0591248 0 0.998251 0.0591248 0 0.998251 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486395 0 -0.873739 -0.486395 0 -0.873739 0.0217577 0 0.999763 0.0217577 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.021759 -0.999763 0 0.021759 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.059124 0 0.998251 0.0216447 -0.10169 0.994581 -0.201253 0 0.979539 -0.481038 0 0.8767 -0.402957 -0.231186 0.885539 -0.63564 0 0.771986 -0.854942 0 0.518724 -0.745642 -0.335399 0.575783 -0.922705 0 0.385507 -0.985354 0 0.170523 -0.979392 -0.200842 0.0213142 -0.995913 0 -0.0903185 -0.950847 0 -0.309661 -0.864201 -0.168256 -0.47418 -0.486393 0 -0.87374 -0.516034 -0.101692 -0.85051 -0.695963 0 -0.718078 -0.8383 0 -0.54521 0.0217575 0 0.999763 0.0217575 0 0.999763 -0.48104 0 0.876699 -0.48104 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217575 -0.999763 0 0.0217575 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.0591239 0 0.998251 0.0216447 -0.101689 0.994581 -0.201255 0 0.979539 -0.481039 0 0.876699 -0.402956 -0.231191 0.885538 -0.635645 0 0.771982 -0.854941 0 0.518725 -0.745639 -0.335403 0.575784 -0.922705 0 0.385507 -0.985354 0 0.170523 -0.979392 -0.200842 0.0213142 -0.995913 0 -0.0903186 -0.950847 0 -0.309661 -0.864201 -0.168256 -0.47418 -0.486394 0 -0.873739 -0.516035 -0.10169 -0.85051 -0.69596 0 -0.718081 -0.8383 0 -0.54521 0.0591279 0 0.99825 0.0216447 -0.1017 0.99458 -0.201275 0 0.979535 -0.481038 0 0.8767 -0.402955 -0.231192 0.885538 -0.635643 0 0.771983 -0.854942 0 0.518724 -0.745642 -0.335397 0.575783 -0.922704 0 0.385509 -0.985354 0 0.170522 -0.979392 -0.200839 0.0213142 -0.995913 0 -0.0903168 -0.950845 0 -0.309667 -0.864201 -0.168251 -0.474183 -0.486394 0 -0.87374 -0.516036 -0.101696 -0.850509 -0.695969 0 -0.718072 -0.8383 0 -0.54521 0.0217575 0 0.999763 0.0587105 0.118062 0.991269 -0.412028 -0.101691 0.905479 -0.379853 0 0.925047 -0.635643 0 0.771983 -0.736736 -0.135573 0.66245 -0.791488 0 0.611185 -0.960066 0 0.279775 -0.882298 -0.292684 0.368627 -0.985354 0 0.170523 -0.986379 0 -0.164489 -0.975758 -0.200164 -0.088489 -0.950846 0 -0.309664 -0.8383 0 -0.54521 -0.814362 -0.0850957 -0.574084 -0.516034 0.101688 -0.850511 -0.486394 0 -0.87374 0.0217575 0 0.999763 0.0217575 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.0217575 -0.999763 0 0.0217575 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.0591249 0 0.998251 0.0216447 -0.101692 0.99458 -0.201261 0 0.979538 -0.481038 0 0.8767 -0.402955 -0.231192 0.885538 -0.635645 0 0.771982 -0.854941 0 0.518725 -0.745639 -0.335404 0.575784 -0.922705 0 0.385507 -0.985354 0 0.170523 -0.979392 -0.200842 0.0213142 -0.995913 0 -0.0903186 -0.950847 0 -0.309661 -0.864201 -0.168256 -0.47418 -0.486394 0 -0.87374 -0.516035 -0.101692 -0.85051 -0.695963 0 -0.718078 -0.8383 0 -0.54521 0.0217592 0 0.999763 0.0217592 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217575 -0.999763 0 0.0217575 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.518726 0 -0.854941 -0.518726 0 -0.854941 0.059124 0 0.998251 0.0216447 -0.10169 0.994581 -0.201253 0 0.979539 -0.481038 0 0.8767 -0.402955 -0.231192 0.885538 -0.635643 0 0.771983 -0.854942 0 0.518724 -0.745642 -0.335399 0.575783 -0.922704 0 0.385508 -0.985354 0 0.170522 -0.979392 -0.20084 0.0213146 -0.995913 0 -0.0903173 -0.950846 0 -0.309664 -0.864201 -0.168255 -0.474181 -0.486394 0 -0.87374 -0.516034 -0.101688 -0.850511 -0.695955 0 -0.718085 -0.8383 0 -0.54521 -0.516137 0.699585 -0.49415 -0.516137 0.699585 -0.49415 -0.523044 0.700707 -0.485217 -0.523043 0.700707 -0.485216 -0.306679 0.700708 -0.644172 -0.0468854 0.700708 -0.711906 -0.0468856 0.700707 -0.711907 -0.188143 0.707071 -0.681654 -0.330102 0.666294 -0.668644 0.233183 0.706223 -0.668487 0.233183 0.706223 -0.668487 0.136644 0.706223 -0.694678 0.136644 0.706223 -0.694678 0.682326 0.699237 0.213304 0.682327 0.699236 0.213304 0.710063 0.699236 -0.0829446 0.710059 0.69924 -0.0829434 0.614791 0.69924 -0.364823 0.614792 0.699239 -0.364824 0.413023 0.699239 -0.583504 0.413023 0.699239 -0.583504 0.570193 0.704309 0.42288 0.570193 0.70431 0.42288 0.487599 0.70672 0.512634 0.273712 0.900715 0.337335 0.420013 0.706011 0.570208 0.289575 0.703805 0.648695 0.289573 0.703807 0.648693 -0.688076 0.706222 0.166737 -0.688076 0.706223 0.166736 -0.65771 0.706223 0.262045 -0.65771 0.706222 0.262045 -0.507513 0.700707 -0.501439 -0.507512 0.700707 -0.501439 -0.656904 0.700707 -0.278364 -0.656904 0.700708 -0.278364 -0.713272 0.700708 -0.0158695 -0.713272 0.700708 -0.0158695 -0.462334 0.706225 -0.536184 -0.462336 0.706222 -0.536187 -0.533288 0.706222 -0.465677 -0.533288 0.706222 -0.465676 0.525889 0.699239 -0.484259 0.525888 0.699239 -0.484258 0.283198 0.69924 -0.656401 0.283199 0.699238 -0.656403 -0.00855017 0.699238 -0.714838 -0.0085498 0.69924 -0.714836 -0.298817 0.69924 -0.649439 -0.298817 0.699241 -0.649439 0.701045 0.704309 -0.111734 0.701045 0.704309 -0.111734 0.651322 0.704309 -0.282362 0.651321 0.70431 -0.282361 0.345324 0.698432 0.626853 0.345323 0.698433 0.626852 0.579402 0.698433 0.4201 0.579402 0.698433 0.4201 0.703142 0.698434 0.133347 0.703144 0.698432 0.133347 -0.19964 0.706223 0.679259 -0.19964 0.706223 0.679259 -0.101917 0.706223 0.700616 -0.101917 0.706222 0.700616 -0.688015 0.700707 0.188799 -0.688015 0.700707 0.188799 -0.569522 0.700707 0.429714 -0.569522 0.700708 0.429714 -0.370379 0.700708 0.609777 -0.370379 0.700709 0.609776 -0.686015 0.699584 0.199913 -0.686015 0.699584 0.199913 -0.639972 0.700707 -0.315349 -0.639972 0.700707 -0.315349 -0.711209 0.700707 -0.0564942 -0.711207 0.700709 -0.0564945 -0.68173 0.700709 0.21036 -0.681732 0.700706 0.210361 -0.695519 0.706223 0.132301 -0.695518 0.706223 0.132301 -0.669931 0.706223 0.229002 -0.669931 0.706223 0.229002 -0.156437 0.699236 -0.697565 -0.156435 0.69924 -0.697561 -0.426861 0.69924 -0.573457 -0.426862 0.699239 -0.573458 -0.623342 0.699239 -0.350014 -0.623343 0.699238 -0.350014 -0.711842 0.699238 -0.0659366 -0.711841 0.699239 -0.0659366 0.0479438 0.706008 -0.70658 0.0496458 0.900714 -0.431566 0.122791 0.744132 -0.656651 0.253759 0.704309 -0.66299 0.253759 0.704308 -0.66299 0.162339 0.707093 -0.688234 0.661826 0.699238 0.270281 0.661827 0.699238 0.270281 0.714533 0.699238 -0.0225573 0.714533 0.699238 -0.0225573 0.643462 0.699237 -0.311488 0.643461 0.699238 -0.311488 0.460922 0.699237 -0.54646 0.460922 0.699237 -0.546459 0.488436 0.706223 0.512523 0.488437 0.706222 0.512524 0.555793 0.706222 0.438571 0.555793 0.706222 0.438571 0.334405 0.699694 0.631349 0.334403 0.699696 0.631348 -0.169878 0.699585 0.694063 -0.169878 0.699584 0.694063 -0.593086 0.700708 0.396557 -0.593087 0.700707 0.396558 -0.40453 0.700707 0.587678 -0.40453 0.700707 0.587678 -0.158689 0.700707 0.695577 -0.158688 0.700706 0.695578 -0.233183 0.706223 0.668487 -0.233183 0.706223 0.668487 -0.136644 0.706223 0.694678 -0.136644 0.706223 0.694678 -0.682326 0.699237 -0.213304 -0.682327 0.699236 -0.213304 -0.710063 0.699236 0.0829446 -0.710059 0.69924 0.0829434 -0.614791 0.69924 0.364823 -0.614793 0.699238 0.364824 -0.413024 0.699238 0.583505 -0.413023 0.699239 0.583503 -0.586881 0.705928 -0.396531 -0.352949 0.89828 -0.261763 -0.531999 0.706766 -0.466325 -0.487599 0.70672 -0.512634 -0.273712 0.900714 -0.337335 -0.420015 0.706008 -0.57021 0.564983 0.699238 -0.438018 0.564983 0.699238 -0.438018 0.337731 0.699238 -0.630083 0.337731 0.699239 -0.630082 0.0519743 0.699239 -0.712996 0.0519742 0.699238 -0.712997 -0.242786 0.699238 -0.672399 -0.242787 0.699237 -0.672401 0.688076 0.706223 -0.166736 0.688077 0.706222 -0.166737 0.657711 0.706222 -0.262045 0.65771 0.706222 -0.262045 0.507513 0.700707 0.501439 0.507512 0.700707 0.501439 0.656904 0.700707 0.278364 0.656905 0.700707 0.278364 0.713273 0.700707 0.0158695 0.713272 0.700707 0.0158698 0.516137 0.699585 0.49415 0.516137 0.699584 0.49415 0.320172 0.701185 0.637048 0.320171 0.701185 0.637048 0.526141 0.701186 0.481159 0.526143 0.701184 0.48116 0.462335 0.706223 0.536186 0.462336 0.706222 0.536187 0.533288 0.706222 0.465677 0.533287 0.706224 0.465676 0.31784 0.701414 0.637963 0.31784 0.701413 0.637963 -0.701045 0.704309 0.111734 -0.701042 0.704312 0.111733 -0.651319 0.704312 0.282361 -0.651322 0.70431 0.282362 -0.096843 0.699238 -0.708299 -0.0968431 0.699238 -0.708299 -0.376802 0.699238 -0.607525 -0.376802 0.699237 -0.607526 -0.591488 0.699237 -0.40151 -0.591487 0.699237 -0.40151 -0.703709 0.699237 -0.12594 -0.703709 0.699237 -0.12594 0.19964 0.706223 -0.679259 0.19964 0.706223 -0.679259 0.101917 0.706223 -0.700616 0.101917 0.706222 -0.700616 0.688015 0.700707 -0.188799 0.688015 0.700707 -0.188799 0.569522 0.700707 -0.429714 0.569522 0.700708 -0.429714 0.370379 0.700708 -0.609777 0.370379 0.700708 -0.609776 0.686015 0.699584 -0.199913 0.686014 0.699586 -0.199912 0.639971 0.700708 0.315349 0.639972 0.700707 0.315349 0.711209 0.700707 0.0564941 0.711209 0.700707 0.0564941 0.681732 0.700707 -0.210361 0.681731 0.700708 -0.21036 0.695519 0.706223 -0.132301 0.695518 0.706223 -0.132301 0.66993 0.706223 -0.229002 0.669931 0.706223 -0.229002 0.354704 0.697264 0.622903 0.354703 0.697265 0.622902 0.597623 0.697265 0.395813 0.597623 0.697265 0.395813 0.711929 0.697265 0.0835429 0.711928 0.697265 0.0835429 -0.253759 0.704309 0.66299 -0.253759 0.704308 0.662991 -0.0811287 0.704308 0.705244 -0.0811287 0.704308 0.705244 -0.661825 0.69924 -0.270281 -0.661827 0.699238 -0.270281 -0.714533 0.699238 0.0225573 -0.714533 0.699238 0.0225573 -0.643462 0.699237 0.311488 -0.643461 0.699238 0.311488 -0.460922 0.699237 0.54646 -0.460922 0.699237 0.546459 -0.488436 0.706223 -0.512523 -0.488437 0.706222 -0.512524 -0.555793 0.706222 -0.438571 -0.555791 0.706224 -0.43857 -0.342892 0.700708 -0.625646 0.180503 0.700707 -0.690238 0.180503 0.700708 -0.690237 -0.0771798 0.701644 -0.708336 -0.0909154 0.670074 -0.736706 -0.207498 0.707071 -0.676014 -0.342893 0.700707 -0.625647 0.169878 0.699584 -0.694063 0.169878 0.699586 -0.694062 0.593086 0.700708 -0.396557 0.593087 0.700707 -0.396558 0.40453 0.700707 -0.587678 0.40453 0.700708 -0.587676 0.158688 0.700709 -0.695576 0.158688 0.700708 -0.695577 -0.348271 0.698073 -0.62562 -0.348271 0.698074 -0.62562 -0.585227 0.698074 -0.412555 -0.585228 0.698074 -0.412555 -0.706273 0.698074 -0.117778 -0.706273 0.698073 -0.117779 -0.687433 0.698073 0.200326 -0.687432 0.698074 0.200325 -0.532436 0.698074 0.478752 -0.532437 0.698074 0.478753 -0.271986 0.698073 0.662357 -0.271986 0.698074 0.662357 0.042335 0.698074 0.714773 0.0423348 0.698075 0.714772 -0.373095 0.694747 -0.61492 -0.373095 0.694747 -0.61492 -0.630569 0.694747 -0.34599 -0.630571 0.694745 -0.34599 -0.719086 0.694745 0.0156496 -0.719085 0.694746 0.0156494 -0.61492 0.694747 0.373094 -0.61492 0.694747 0.373095 -0.345989 0.694747 0.63057 -0.345989 0.694746 0.63057 0.0156496 0.694747 0.719084 0.0156493 0.694748 0.719083 -0.373095 0.694746 -0.614922 -0.373096 0.694744 -0.614923 -0.630571 0.694745 -0.34599 -0.630572 0.694745 -0.34599 -0.719084 0.694747 0.0156492 -0.719085 0.694746 0.0156494 -0.61492 0.694747 0.373094 -0.61492 0.694747 0.373095 -0.345989 0.694747 0.63057 -0.345989 0.694748 0.630569 0.0156495 0.694749 0.719082 0.0156493 0.69475 0.719081 -0.34827 0.698074 -0.625621 -0.348273 0.69807 -0.625623 -0.58523 0.698071 -0.412556 -0.585228 0.698073 -0.412556 -0.706273 0.698074 -0.117778 -0.706272 0.698074 -0.117778 -0.687432 0.698074 0.200326 -0.687431 0.698075 0.200325 -0.532436 0.698074 0.478752 -0.532436 0.698075 0.478752 -0.271986 0.698075 0.662356 -0.271986 0.698075 0.662355 0.0423339 0.698076 0.714771 0.0423355 0.69807 0.714777 0.0156494 0.694746 0.719085 0.0156488 0.694749 0.719082 -0.345988 0.69475 0.630567 -0.345989 0.694747 0.63057 -0.61492 0.694747 0.373095 -0.61492 0.694747 0.373094 -0.719085 0.694746 0.0156494 -0.719082 0.694749 0.0156488 -0.630569 0.694748 -0.345989 -0.630571 0.694745 -0.34599 -0.487539 0.706716 -0.512697 -0.307165 0.805826 -0.506256 -0.307161 0.80583 -0.506252 -0.229566 0.706718 -0.669215 0.042335 0.698073 0.714774 0.0423348 0.698074 0.714773 -0.14236 0.70686 0.69288 -0.309106 0.581219 0.752754 -0.295432 0.700863 0.64924 -0.450095 0.706117 0.546638 -0.649553 0.48678 0.58406 -0.562801 0.703123 0.434596 -0.654507 0.704871 0.273455 -0.857049 0.450654 0.249754 -0.698945 0.704872 0.120957 -0.70722 0.700203 -0.0977468 -0.34827 0.698076 -0.625619 -0.348273 0.698071 -0.625622 -0.492293 0.706857 -0.507938 -0.533539 0.681288 -0.501182 -0.525943 0.778703 -0.342061 -0.671339 0.64313 -0.368359 -0.656128 0.723766 -0.21368 -0.843675 0.531374 -0.0765118 -0.614921 0.694746 0.373094 -0.614923 0.694744 0.373096 -0.345989 0.694745 0.630571 -0.345988 0.694749 0.630568 0.0156492 0.694748 0.719083 0.0156494 0.694747 0.719084 -0.592007 0.80583 0.0128834 -0.59201 0.805828 0.0128841 -0.687777 0.706717 0.165874 -0.373095 0.694746 -0.614921 -0.373095 0.694746 -0.614922 -0.630572 0.694744 -0.34599 -0.630568 0.694748 -0.345989 -0.694339 0.70672 -0.135795 0.0423354 0.698073 0.714774 0.0423347 0.698076 0.714772 -0.142357 0.706861 0.692879 -0.309106 0.581219 0.752754 -0.295432 0.700863 0.649239 -0.476324 0.704478 0.526143 -0.503059 0.611276 0.610961 -0.50625 0.80583 0.307161 -0.72467 0.402133 0.559591 -0.6162 0.744323 0.25745 -0.765874 0.620147 0.169867 -0.698945 0.704873 0.120957 -0.708161 0.703124 -0.0642222 -0.861626 0.486781 -0.143685 -0.67329 0.706117 -0.21927 -0.585226 0.698075 -0.412555 -0.34827 0.698074 -0.62562 -0.348271 0.698073 -0.625621 -0.492297 0.706858 -0.507933 -0.701605 0.547296 -0.456309 0.0423361 0.698073 0.714774 0.0423355 0.698075 0.714772 -0.142356 0.706861 0.692879 -0.180781 0.681288 0.709341 -0.284848 0.805827 0.519139 -0.331722 0.598778 0.728989 -0.438621 0.723764 0.532707 -0.618737 0.583612 0.525892 -0.5628 0.703125 0.434594 -0.654505 0.704873 0.273453 -0.857048 0.450657 0.249753 -0.698945 0.704872 0.120957 -0.708161 0.703124 -0.064221 -0.861629 0.486775 -0.143685 -0.673291 0.706116 -0.219272 -0.585228 0.698073 -0.412556 -0.34827 0.698076 -0.625618 -0.348272 0.698073 -0.62562 -0.492291 0.706859 -0.507937 -0.701609 0.547289 -0.456311 0.16588 0.706717 0.687775 0.0128822 0.805833 0.592003 0.0406755 0.72576 0.686744 -0.109654 0.707092 0.698567 -0.142357 0.706861 0.692879 -0.309107 0.581218 0.752754 -0.295432 0.700863 0.649239 -0.450094 0.706117 0.546639 -0.649554 0.486777 0.584062 -0.5628 0.703125 0.434594 -0.654505 0.704873 0.273454 -0.857047 0.450659 0.249754 -0.698943 0.704875 0.120956 -0.70816 0.703125 -0.0642215 -0.861627 0.486778 -0.143685 -0.673289 0.706118 -0.219272 -0.585225 0.698077 -0.412553 -0.348273 0.69807 -0.625623 -0.348269 0.698076 -0.625619 -0.49229 0.706861 -0.507934 -0.701608 0.547292 -0.456309 -0.373095 0.694747 -0.61492 -0.373095 0.694747 -0.61492 -0.63057 0.694747 -0.345989 -0.630569 0.694748 -0.345989 -0.719084 0.694747 0.0156496 -0.719083 0.694748 0.0156493 -0.61492 0.694747 0.373095 -0.614922 0.694745 0.373096 -0.34599 0.694744 0.630573 -0.345989 0.694748 0.630569 0.0156488 0.694749 0.719082 0.0156494 0.694746 0.719085 -0.348272 0.698072 -0.625621 -0.348271 0.698074 -0.62562 -0.585227 0.698074 -0.412555 -0.585227 0.698074 -0.412555 -0.706273 0.698074 -0.117778 -0.706274 0.698073 -0.117778 -0.687432 0.698074 0.200325 -0.687432 0.698074 0.200325 -0.532437 0.698074 0.478753 -0.532436 0.698074 0.478753 -0.271985 0.698074 0.662356 -0.271985 0.698076 0.662355 0.0423348 0.698076 0.714772 0.0423344 0.698077 0.71477 -0.373093 0.69475 -0.614918 -0.373096 0.694746 -0.614921 -0.630572 0.694744 -0.345991 -0.630571 0.694745 -0.345991 -0.719086 0.694745 0.0156503 -0.719081 0.69475 0.0156493 -0.614919 0.694749 0.373093 -0.614923 0.694744 0.373097 -0.34599 0.694745 0.630571 -0.34599 0.694745 0.630571 0.0156493 0.694747 0.719084 0.0156494 0.694747 0.719084 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.416658 0 0.909063 -0.914165 0 0.405343 -0.536898 -0.219455 -0.814604 -0.427562 -0.704008 -0.567066 -0.632682 0 -0.774411 -0.393457 0 -0.919343 -0.393457 0 -0.919343 -0.502771 0 -0.86442 -0.518704 -0.00912185 -0.854905 -0.72395 0 -0.689853 -0.538655 -0.719518 -0.438344 -0.801824 0 -0.597561 -0.939142 0 -0.343531 -0.720006 -0.609039 -0.33266 -0.643257 -0.702733 -0.303953 -0.848188 -0.252951 -0.465396 -0.857433 0 -0.514596 -0.954517 0 -0.298156 -0.851277 -0.495603 -0.172352 -0.983497 0 -0.180926 -0.966421 -0.242485 0.0850402 -0.660916 -0.749948 0.027707 -0.793783 -0.607956 0.0172753 -0.999313 0 -0.0370677 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.988807 0 0.149203 -0.860813 -0.242491 0.447436 -0.572333 -0.749951 0.331675 -0.678802 -0.60795 0.411855 -0.446762 0 0.894653 -0.465395 -0.252948 0.848189 -0.379274 -0.70273 0.601932 -0.565428 0 0.824798 -0.720079 0 0.693893 -0.720079 0 0.693893 -0.82296 0 0.568099 -0.24587 -0.474001 0.8455 -0.218849 -0.719521 0.659087 -0.261229 -0.599336 0.756674 -0.386063 -0.111033 0.915766 0.0217544 -0.00912769 0.999722 -0.0152409 -0.219459 0.975503 -0.0559995 -0.704005 0.707984 -0.117622 0 0.993059 -0.238071 0 0.971248 0.162011 0 0.986789 0.162011 0 0.986789 0.040316 0 0.999187 0.0591247 0 0.998251 0.0217579 -0.00371752 0.999756 -0.379851 0.00310596 0.925043 -0.414176 0 0.910197 -0.635644 0 0.771982 -0.743591 0.00497638 0.668616 -0.791487 0 0.611186 -0.922705 0 0.385508 -0.960051 0.0056011 0.27977 -0.985354 0 0.170522 -0.995913 0 -0.0903169 -0.986367 0.0049765 -0.164487 -0.950845 0 -0.309666 -0.817328 0 -0.576172 -0.838295 0.00371756 -0.545205 -0.48639 -0.00432401 -0.873731 -0.518725 0 -0.854941 0.021758 0 0.999763 0.021758 0 0.999763 -0.481038 0 0.8767 -0.481038 0 0.8767 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0591267 0 0.99825 0.0591267 0 0.99825 -0.379856 0 0.925045 -0.379856 0 0.925045 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.960065 0 0.279776 -0.960065 0 0.279776 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0.059125 0 0.998251 0.0217576 -0.00371757 0.999756 -0.379852 0.00310604 0.925042 -0.414178 0 0.910196 -0.635641 0 0.771985 -0.743591 0.00497652 0.668616 -0.791488 0 0.611185 -0.922706 0 0.385505 -0.960051 0.0056009 0.279771 -0.985353 0 0.170527 -0.995913 0 -0.0903207 -0.986366 0.00497636 -0.164489 -0.950846 0 -0.309663 -0.817328 0 -0.576172 -0.838294 0.00371748 -0.545206 -0.486389 -0.00432403 -0.873731 -0.518724 0 -0.854942 0.0591247 0 0.998251 0.0591247 0 0.998251 -0.379856 0 0.925046 -0.379856 0 0.925046 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.960066 0 0.279775 -0.960066 0 0.279775 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486395 0 -0.873739 -0.486395 0 -0.873739 0.021758 0 0.999763 0.021758 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.876699 0 -0.48104 -0.876699 0 -0.48104 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0.0591247 0 0.998251 0.0217579 -0.00371752 0.999756 -0.201253 0 0.979539 -0.41418 0 0.910195 -0.481032 -0.00620753 0.876681 -0.635644 0 0.771982 -0.791487 0 0.611186 -0.854918 -0.00745591 0.51871 -0.922705 0 0.385508 -0.985354 0 0.170522 -0.999735 -0.0074559 0.021757 -0.995913 0 -0.0903173 -0.950846 0 -0.309666 -0.876682 -0.00620739 -0.48103 -0.486395 0 -0.873739 -0.518719 -0.00371731 -0.854937 -0.695951 0 -0.718089 -0.838301 0 -0.545208 -0.486394 0 -0.87374 -0.486394 0 -0.87374 -0.695966 0 -0.718075 -0.695966 0 -0.718075 -0.838299 0 -0.54521 -0.838299 0 -0.54521 -0.950845 0 -0.309669 -0.950845 0 -0.309669 -0.995913 0 -0.0903147 -0.995913 0 -0.0903147 -0.985354 0 0.17052 -0.985354 0 0.17052 -0.922705 0 0.385508 -0.922705 0 0.385508 -0.791486 0 0.611187 -0.791486 0 0.611187 -0.63564 0 0.771986 -0.63564 0 0.771986 -0.41418 0 0.910195 -0.41418 0 0.910195 -0.201255 0 0.979539 -0.201255 0 0.979539 0.0591246 0 0.998251 0.0591246 0 0.998251 0.0591247 0 0.998251 0.0591247 0 0.998251 -0.379856 0 0.925046 -0.379856 0 0.925046 -0.743598 0 0.668627 -0.743598 0 0.668627 -0.960067 0 0.279771 -0.960067 0 0.279771 -0.986379 0 -0.164487 -0.986379 0 -0.164487 -0.817327 0 -0.576175 -0.817327 0 -0.576175 -0.486396 0 -0.873739 -0.486396 0 -0.873739 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.021758 -0.999763 0 0.021758 -0.8767 0 -0.481038 -0.8767 0 -0.481038 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.0591246 0 0.998251 0.0217579 -0.00371752 0.999756 -0.379853 0.00310595 0.925042 -0.414178 0 0.910196 -0.63564 0 0.771986 -0.743592 0.00497656 0.668615 -0.791489 0 0.611184 -0.922703 0 0.385513 -0.960051 0.00560131 0.279771 -0.985354 0 0.170519 -0.995913 0 -0.0903149 -0.986367 0.00497649 -0.164486 -0.950846 0 -0.309663 -0.817327 0 -0.576175 -0.838294 0.00371779 -0.545205 -0.48639 -0.00432387 -0.873731 -0.518724 0 -0.854942 0.0591247 0 0.998251 0.0217579 -0.00371752 0.999756 -0.201252 0 0.979539 -0.414176 0 0.910197 -0.48103 -0.00620769 0.876682 -0.635647 0 0.77198 -0.791486 0 0.611187 -0.854918 -0.00745594 0.51871 -0.922705 0 0.385508 -0.985354 0 0.170524 -0.999735 -0.00745595 0.0217574 -0.995913 0 -0.0903176 -0.950846 0 -0.309663 -0.876682 -0.00620753 -0.48103 -0.486393 0 -0.87374 -0.51872 -0.00371768 -0.854936 -0.695966 0 -0.718075 -0.838299 0 -0.545211 0.0423348 -0.698074 0.714773 0.0423348 -0.698074 0.714773 -0.271984 -0.698075 0.662357 -0.271988 -0.698072 0.662358 -0.532439 -0.698072 0.478754 -0.532437 -0.698073 0.478754 -0.687433 -0.698073 0.200326 -0.687432 -0.698073 0.200326 -0.706273 -0.698073 -0.117779 -0.706273 -0.698073 -0.117779 -0.585229 -0.698073 -0.412554 -0.585229 -0.698073 -0.412555 -0.348272 -0.698073 -0.625621 -0.348271 -0.698072 -0.625621 0.0156496 -0.694747 0.719083 0.0156477 -0.694745 0.719086 -0.34599 -0.694745 0.630571 -0.34599 -0.694745 0.630571 -0.614922 -0.694745 0.373095 -0.614921 -0.694746 0.373095 -0.719085 -0.694746 0.0156496 -0.719085 -0.694746 0.0156496 -0.63057 -0.694746 -0.345989 -0.630571 -0.694746 -0.34599 -0.373096 -0.694746 -0.614921 -0.373096 -0.694746 -0.614921 0.0423363 -0.698074 0.714773 0.0423349 -0.698072 0.714775 -0.271988 -0.698072 0.662358 -0.271985 -0.698074 0.662357 -0.532437 -0.698074 0.478753 -0.532437 -0.698073 0.478752 -0.687432 -0.698073 0.200327 -0.687433 -0.698073 0.200326 -0.706273 -0.698073 -0.117779 -0.706274 -0.698073 -0.117779 -0.585228 -0.698073 -0.412556 -0.585228 -0.698073 -0.412555 -0.348271 -0.698073 -0.625621 -0.348271 -0.698074 -0.62562 0.042335 -0.698073 0.714774 0.042335 -0.698073 0.714774 -0.271985 -0.698073 0.662358 -0.271986 -0.698073 0.662358 -0.532438 -0.698073 0.478753 -0.532436 -0.698074 0.478753 -0.687431 -0.698074 0.200326 -0.687434 -0.698072 0.200325 -0.706274 -0.698072 -0.11778 -0.706273 -0.698073 -0.117779 -0.585229 -0.698073 -0.412555 -0.585229 -0.698072 -0.412556 -0.348271 -0.698073 -0.625621 -0.348272 -0.698073 -0.62562 0.0423349 -0.698073 0.714774 0.0423348 -0.698073 0.714774 -0.271987 -0.698073 0.662358 -0.271986 -0.698073 0.662357 -0.532437 -0.698073 0.478753 -0.532438 -0.698073 0.478753 -0.687433 -0.698073 0.200326 -0.687433 -0.698073 0.200326 -0.706273 -0.698073 -0.117779 -0.706274 -0.698073 -0.117779 -0.585228 -0.698073 -0.412556 -0.585228 -0.698074 -0.412555 -0.348271 -0.698074 -0.62562 -0.348271 -0.698073 -0.625621 0.0156496 -0.694746 0.719085 0.0156496 -0.694746 0.719085 -0.34599 -0.694746 0.630571 -0.345989 -0.694746 0.630571 -0.614921 -0.694746 0.373095 -0.614921 -0.694746 0.373095 -0.719085 -0.694746 0.0156496 -0.719085 -0.694746 0.0156491 -0.63057 -0.694746 -0.34599 -0.63057 -0.694747 -0.34599 -0.373095 -0.694747 -0.61492 -0.373095 -0.694747 -0.61492 -0.34827 -0.698074 -0.62562 -0.348271 -0.698075 -0.625619 -0.492283 -0.70686 -0.507943 -0.599622 -0.679542 -0.422701 -0.597958 -0.700861 -0.388896 -0.67329 -0.706116 -0.219273 -0.734278 -0.667714 -0.122449 -0.708161 -0.703124 -0.0642216 -0.687432 -0.698073 0.200326 -0.78092 -0.609836 0.135144 -0.654506 -0.704873 0.273454 -0.532438 -0.698073 0.478752 -0.606293 -0.64282 0.468179 -0.450097 -0.706116 0.546638 -0.271985 -0.698074 0.662357 0.0423349 -0.698072 0.714775 0.0423349 -0.698072 0.714775 -0.142357 -0.706858 0.692882 -0.306684 -0.6721 0.673964 -0.348272 -0.698074 -0.625619 -0.348271 -0.698073 -0.625621 -0.492295 -0.706858 -0.507934 -0.59962 -0.679543 -0.422702 -0.597956 -0.700862 -0.388897 -0.673289 -0.706117 -0.219275 -0.734279 -0.667714 -0.122448 -0.708161 -0.703124 -0.0642198 -0.698945 -0.704873 0.120955 -0.718174 -0.663647 0.209284 -0.654506 -0.704872 0.273454 -0.532438 -0.698073 0.478753 -0.606292 -0.64282 0.46818 -0.450094 -0.706116 0.54664 -0.271986 -0.698074 0.662357 0.0423348 -0.698073 0.714774 0.0423349 -0.698073 0.714774 -0.142358 -0.706859 0.692881 -0.306683 -0.672101 0.673963 0.0423349 -0.698073 0.714774 0.0423348 -0.698073 0.714774 -0.271987 -0.698073 0.662357 -0.271986 -0.698074 0.662357 -0.532435 -0.698075 0.478754 -0.532439 -0.698072 0.478753 -0.687435 -0.698071 0.200324 -0.687432 -0.698074 0.200326 -0.706272 -0.698075 -0.117777 -0.706274 -0.698073 -0.117779 -0.585228 -0.698073 -0.412556 -0.585227 -0.698074 -0.412555 -0.348272 -0.698074 -0.62562 -0.348272 -0.698073 -0.625621 0.0156494 -0.694746 0.719085 0.0156494 -0.694746 0.719085 -0.34599 -0.694746 0.63057 -0.345989 -0.694746 0.63057 -0.61492 -0.694747 0.373095 -0.61492 -0.694747 0.373095 -0.719084 -0.694747 0.0156496 -0.719086 -0.694745 0.0156477 -0.630571 -0.694745 -0.34599 -0.630571 -0.694745 -0.34599 -0.373095 -0.694746 -0.614922 -0.373096 -0.694746 -0.614921 0.0423348 -0.698073 0.714774 0.0423349 -0.698073 0.714774 -0.271986 -0.698073 0.662358 -0.271987 -0.698072 0.662358 -0.532439 -0.698072 0.478753 -0.532436 -0.698074 0.478753 -0.687431 -0.698074 0.200326 -0.687431 -0.698074 0.200326 -0.706272 -0.698074 -0.117777 -0.706274 -0.698073 -0.117779 -0.585228 -0.698073 -0.412556 -0.585227 -0.698074 -0.412555 -0.348272 -0.698073 -0.62562 -0.348271 -0.698073 -0.625621 0.0114938 -0.84912 0.528075 -0.328054 -0.85653 0.398418 -0.477432 -0.855728 0.199471 -0.51717 -0.854596 -0.0469006 -0.273991 -0.84912 -0.45158 -0.437346 -0.853126 -0.284438 -0.490729 -0.85653 -0.159819 -0.509848 -0.855728 0.088233 -0.411014 -0.854596 0.317384 -0.216079 -0.853127 0.474853 -0.45158 -0.84912 0.273991 -0.254085 -0.84912 0.463073 0.0114926 -0.84912 0.528075 -0.27399 -0.84912 -0.451581 -0.463073 -0.84912 -0.254085 -0.528075 -0.84912 0.0114914 0.0310209 -0.851306 0.523752 -0.503718 -0.851306 0.146788 -0.390144 -0.851306 0.350808 -0.199299 -0.851306 0.485344 -0.255197 -0.851306 -0.458425 -0.428828 -0.851306 -0.3023 -0.517523 -0.851306 -0.0863034 0.0310209 -0.851306 0.523752 -0.503718 -0.851306 0.146788 -0.390144 -0.851306 0.350808 -0.199299 -0.851306 0.485344 -0.255196 -0.851306 -0.458425 -0.428828 -0.851306 -0.3023 -0.517523 -0.851306 -0.0863034 0.0310197 -0.851306 0.523752 -0.503718 -0.851306 0.146789 -0.390144 -0.851306 0.350808 -0.199299 -0.851305 0.485344 -0.255195 -0.851306 -0.458426 -0.428828 -0.851306 -0.3023 -0.517524 -0.851306 -0.0863023 0.0114938 -0.84912 0.528075 -0.328055 -0.85653 0.398417 -0.477431 -0.855728 0.199471 -0.51717 -0.854596 -0.0469006 -0.273989 -0.84912 -0.451581 -0.437346 -0.853126 -0.284437 -0.490728 -0.85653 -0.15982 -0.509848 -0.855728 0.0882321 -0.411012 -0.854597 0.317386 -0.216079 -0.853127 0.474853 0.031021 -0.851306 0.523752 -0.503718 -0.851306 0.146789 -0.390144 -0.851306 0.350808 -0.199299 -0.851306 0.485344 -0.255196 -0.851306 -0.458425 -0.428828 -0.851306 -0.3023 -0.517523 -0.851306 -0.0863035 0.0310209 -0.851306 0.523752 -0.503718 -0.851306 0.146788 -0.390144 -0.851306 0.350808 -0.199299 -0.851306 0.485344 -0.255196 -0.851306 -0.458425 -0.428828 -0.851306 -0.3023 -0.517523 -0.851306 -0.0863034 -0.45158 -0.84912 0.27399 -0.254085 -0.84912 0.463073 0.0114915 -0.84912 0.528075 -0.27399 -0.84912 -0.451581 -0.463073 -0.84912 -0.254084 -0.528075 -0.84912 0.0114926 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.348271 -0.698074 -0.62562 -0.34827 -0.698073 -0.625622 -0.492295 -0.706858 -0.507934 -0.599621 -0.679543 -0.422702 -0.597957 -0.700861 -0.388898 -0.673291 -0.706115 -0.219271 -0.734278 -0.667714 -0.122449 -0.708161 -0.703124 -0.0642219 -0.698945 -0.704872 0.120958 -0.718173 -0.663647 0.209285 -0.654506 -0.704872 0.273454 -0.532438 -0.698073 0.478754 -0.606293 -0.642819 0.46818 -0.4501 -0.706114 0.546638 -0.271988 -0.698071 0.662358 0.0423348 -0.698075 0.714773 0.0423347 -0.698074 0.714773 -0.142357 -0.70686 0.69288 -0.30668 -0.672103 0.673962 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0591272 0 0.99825 0.0217601 -0.00363666 0.999757 -0.379853 0.00303842 0.925042 -0.414179 0 0.910196 -0.635645 0 0.771982 -0.743593 0.00486812 0.668615 -0.791488 0 0.611185 -0.922705 0 0.385507 -0.960051 0.00547917 0.27977 -0.985354 0 0.170523 -0.995913 0 -0.0903164 -0.986367 0.00486825 -0.164487 -0.950845 0 -0.309668 -0.817329 0 -0.576172 -0.838295 0.00363672 -0.545204 -0.486391 -0.00422987 -0.873731 -0.518725 0 -0.854941 0.021758 0 0.999763 0.021758 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854941 0 0.518726 -0.854941 0 0.518726 -0.999763 0 0.0217558 -0.999763 0 0.0217558 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518724 0 -0.854942 -0.518724 0 -0.854942 0.0217575 0 0.999763 0.059124 0.00422987 0.998242 -0.414175 -0.0036365 0.91019 -0.379856 0 0.925046 -0.635637 0 0.771988 -0.74359 -0.00486835 0.668618 -0.791487 0 0.611185 -0.922706 0 0.385503 -0.960052 -0.00547906 0.279768 -0.985354 0 0.170524 -0.995913 0 -0.0903148 -0.986367 -0.00486844 -0.164489 -0.950843 0 -0.309673 -0.8383 0 -0.545209 -0.817325 -0.00303825 -0.576169 -0.518722 0.00363671 -0.854935 -0.486395 0 -0.873739 0.0591245 0 0.998251 0.0591245 0 0.998251 -0.379856 0 0.925046 -0.379856 0 0.925046 -0.743598 0 0.668627 -0.743598 0 0.668627 -0.960066 0 0.279772 -0.960066 0 0.279772 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.817329 0 -0.576171 -0.817329 0 -0.576171 -0.486393 0 -0.87374 -0.486393 0 -0.87374 0.0591222 0 0.998251 0.0591222 0 0.998251 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.960066 0 0.279773 -0.960066 0 0.279773 -0.986379 0 -0.164489 -0.986379 0 -0.164489 -0.817329 0 -0.576172 -0.817329 0 -0.576172 -0.486391 0 -0.873741 -0.486391 0 -0.873741 0.0591272 0 0.99825 0.0217601 -0.00363666 0.999757 -0.379853 0.00303842 0.925042 -0.414179 0 0.910196 -0.635646 0 0.771981 -0.74359 0.00486797 0.668618 -0.791484 0 0.611189 -0.922705 0 0.385507 -0.960052 0.00547924 0.279769 -0.985354 0 0.170521 -0.995913 0 -0.0903164 -0.986367 0.00486829 -0.164488 -0.950844 0 -0.309669 -0.817329 0 -0.576171 -0.838296 0.00363668 -0.545204 -0.486387 -0.00422997 -0.873733 -0.518722 0 -0.854943 0.0591247 0 0.998251 0.0591247 0 0.998251 -0.379855 0 0.925046 -0.379855 0 0.925046 -0.743599 0 0.668626 -0.743599 0 0.668626 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.817328 0 -0.576172 -0.817328 0 -0.576172 -0.486394 0 -0.87374 -0.486394 0 -0.87374 0.0591245 0 0.998251 0.0591245 0 0.998251 -0.379856 0 0.925046 -0.379856 0 0.925046 -0.743598 0 0.668627 -0.743598 0 0.668627 -0.960066 0 0.279772 -0.960066 0 0.279772 -0.986379 0 -0.164491 -0.986379 0 -0.164491 -0.817329 0 -0.576171 -0.817329 0 -0.576171 -0.486393 0 -0.87374 -0.486393 0 -0.87374 0.0591247 0 0.998251 0.0217557 -0.00363684 0.999757 -0.201269 0 0.979536 -0.414176 0 0.910197 -0.481029 -0.00607257 0.876683 -0.635644 0 0.771983 -0.791487 0 0.611186 -0.854919 -0.00729369 0.51871 -0.922705 0 0.385507 -0.985354 0 0.17052 -0.999737 -0.00729353 0.0217575 -0.995913 0 -0.0903148 -0.950846 0 -0.309665 -0.876683 -0.00607238 -0.481029 -0.486393 0 -0.87374 -0.51872 -0.00363673 -0.854937 -0.695963 0 -0.718078 -0.8383 0 -0.545209 -0.971873 0 0.235507 -0.971873 0 0.235507 -0.928982 0 0.370125 -0.928982 0 0.370125 0.339615 0 0.940564 0.339615 0 0.940564 -0.0727027 0 0.997354 -0.0727027 0 0.997354 -0.472426 0 0.881371 -0.472426 0 0.881371 -0.790309 0 0.612708 -0.790309 0 0.612708 0.630076 0 0.776534 0.630076 0 0.776534 0.80321 0 0.595696 0.80321 0 0.595696 0.577745 0 -0.816217 0.577745 0 -0.816217 0.859983 0 -0.510322 0.859983 0 -0.510322 0.993246 0 -0.116024 0.993246 0 -0.116024 0.954449 0 0.298374 0.954449 0 0.298374 0.329359 0 -0.944205 0.329359 0 -0.944205 0.193002 0 -0.981198 0.193002 0 -0.981198 -0.0657166 0 -0.997838 -0.0799341 0.00208073 -0.996798 -0.429853 -0.00192568 -0.902897 -0.449061 0.000962801 -0.893501 -0.733119 -0.00100173 -0.6801 -0.737949 0 -0.674857 -0.722324 0 -0.691554 -0.722324 0 -0.691554 -0.711351 0 -0.702837 -0.711351 0 -0.702837 -0.920745 0 -0.390166 -0.920745 0 -0.390166 -0.999753 0 -0.0222434 -0.999753 0 -0.0222434 -0.689891 0 -0.723913 -0.689891 0 -0.723913 -0.785029 0 -0.619459 -0.785029 0 -0.619459 -0.644746 0 0.764397 -0.644746 0 0.764397 -0.900085 0 0.435715 -0.900085 0 0.435715 -0.999502 0 0.0315536 -0.999502 0 0.0315536 -0.925775 0 -0.378074 -0.925775 0 -0.378074 -0.35746 0 0.933928 -0.35746 0 0.933928 -0.114283 0 0.993448 -0.114283 0 0.993448 0.995737 0 0.0922336 0.995737 0 0.0922336 0.871944 0 0.489606 0.871944 0 0.489606 0.597103 0 0.802165 0.597103 0 0.802165 0.218826 0 0.975764 0.218826 0 0.975764 0.982385 0 -0.186869 0.982385 0 -0.186869 0.946244 0 -0.323454 0.946244 0 -0.323454 0.831295 0 -0.555831 0.831295 0 -0.555831 0.567006 0 -0.823714 0.567006 0 -0.823714 0.222424 0 -0.97495 0.222424 0 -0.97495 0.237741 0 -0.971328 0.237741 0 -0.971328 0.253 0 -0.967466 0.259889 -0.00104039 -0.965638 -0.122479 0.00107907 -0.992471 -0.101229 -0.0021581 -0.994861 -0.480612 0.00223534 -0.876931 -0.468063 0 -0.883695 0.281981 0 -0.95942 0.281981 0 -0.95942 0.143953 0 -0.989585 0.143953 0 -0.989585 -0.104711 0 -0.994503 -0.104711 0 -0.994503 -0.987536 0 0.157395 -0.987536 0 0.157395 -0.917493 0 0.397752 -0.917493 0 0.397752 0.417992 0 0.908451 0.417992 0 0.908451 0.0119601 0 0.999928 0.0119601 0 0.999928 -0.396144 0 0.918188 -0.396144 0 0.918188 -0.735623 0 0.677391 -0.735623 0 0.677391 0.653026 0 0.757336 0.653026 0 0.757336 0.753242 0 0.657744 0.753242 0 0.657744 0.897011 0 0.442007 0.897011 0 0.442007 0.99686 0 0.0791846 0.99686 0 0.0791846 0.955544 0 -0.29485 0.955544 0 -0.29485 0.960066 0 -0.279774 0.960066 0 -0.279774 0.96435 0 -0.264629 0.96435 0 -0.264629 0.798266 0 -0.602305 0.798266 0 -0.602305 0.519139 0 -0.854689 0.519139 0 -0.854689 0.971873 0 -0.235507 0.971873 0 -0.235507 0.928982 0 -0.370125 0.928982 0 -0.370125 -0.0494537 0 -0.998776 -0.0494537 0 -0.998776 0.40657 0 -0.91362 0.40657 0 -0.91362 0.775095 0 -0.631845 0.775095 0 -0.631845 -0.630076 0 -0.776534 -0.630076 0 -0.776534 -0.80321 0 -0.595696 -0.80321 0 -0.595696 -0.577745 0 0.816217 -0.577745 0 0.816217 -0.859983 0 0.510322 -0.859983 0 0.510322 -0.993246 0 0.116024 -0.993246 0 0.116024 -0.954449 0 -0.298374 -0.954449 0 -0.298374 -0.329359 0 0.944205 -0.329359 0 0.944205 -0.193002 0 0.981198 -0.193002 0 0.981198 0.449062 0 0.893501 0.442681 -0.00100169 0.896679 0.737948 0.00104035 0.674857 0.733119 0 0.6801 0.722324 0 0.691554 0.722324 0 0.691554 0.711351 0 0.702837 0.711351 0 0.702837 0.920745 0 0.390166 0.920745 0 0.390166 0.999753 0 0.0222434 0.999753 0 0.0222434 0.689891 0 0.723913 0.689891 0 0.723913 0.785029 0 0.619459 0.785029 0 0.619459 0.644746 0 -0.764397 0.644746 0 -0.764397 0.900085 0 -0.435715 0.900085 0 -0.435715 0.999502 0 -0.0315536 0.999502 0 -0.0315536 0.925775 0 0.378074 0.925775 0 0.378074 0.35746 0 -0.933928 0.35746 0 -0.933928 0.114283 0 -0.993448 0.114283 0 -0.993448 -0.146735 0 -0.989176 -0.146735 0 -0.989176 -0.982385 0 0.186869 -0.982385 0 0.186869 -0.946244 0 0.323454 -0.946244 0 0.323454 -0.831295 0 0.555831 -0.831295 0 0.555831 -0.567006 0 0.823714 -0.567006 0 0.823714 -0.222424 0 0.97495 -0.222424 0 0.97495 -0.237741 0 0.971328 -0.237741 0 0.971328 0.293432 0 0.95598 0.468062 -0.00208073 0.883693 0.480613 0 0.876933 -0.281981 0 0.95942 -0.281981 0 0.95942 -0.143953 0 0.989585 -0.143953 0 0.989585 0.98436 0 0.176168 0.98436 0 0.176168 0.827382 0 0.561639 0.827382 0 0.561639 0.527077 0 0.849818 0.527077 0 0.849818 0.135466 0 0.990782 0.135466 0 0.990782 0.987536 0 -0.157395 0.987536 0 -0.157395 0.917493 0 -0.397752 0.917493 0 -0.397752 -0.0635524 0 -0.997979 -0.0635524 0 -0.997979 0.367512 0 -0.930019 0.367512 0 -0.930019 0.728589 0 -0.684951 0.728589 0 -0.684951 -0.653026 0 -0.757336 -0.653026 0 -0.757336 -0.753241 0 -0.657744 -0.753241 0 -0.657744 -0.897012 0 -0.442007 -0.897012 0 -0.442007 -0.99686 0 -0.0791846 -0.99686 0 -0.0791846 -0.955544 0 0.294849 -0.955544 0 0.294849 -0.960066 0 0.279774 -0.960066 0 0.279774 -0.96435 0 0.264629 -0.96435 0 0.264629 -0.798266 0 0.602305 -0.798266 0 0.602305 -0.519139 0 0.854689 -0.519139 0 0.854689 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0156494 -0.694746 0.719085 0.0156488 -0.694749 0.719082 -0.345989 -0.694748 0.630568 -0.345988 -0.69475 0.630567 -0.614919 -0.694749 0.373094 -0.614921 -0.694746 0.373096 -0.719084 -0.694747 0.0156494 -0.719083 -0.694748 0.0156492 -0.630571 -0.694746 -0.34599 -0.630571 -0.694745 -0.34599 -0.373097 -0.694744 -0.614922 -0.373091 -0.694752 -0.614916 -0.345991 -0.694745 0.630571 0.0156496 -0.694745 0.719086 0.0156494 -0.694746 0.719085 -0.213128 -0.857442 0.468369 -0.450095 -0.706117 0.546639 -0.61492 -0.694747 0.373095 -0.3521 -0.895601 0.271892 -0.654506 -0.704872 0.273454 -0.698945 -0.704873 0.120958 -0.532453 -0.84638 0.0115874 -0.708159 -0.703126 -0.0642218 -0.673289 -0.706118 -0.219271 -0.489726 -0.829436 -0.268709 -0.597955 -0.700864 -0.388895 -0.373093 -0.69475 -0.614918 -0.373096 -0.694745 -0.614921 0.0156493 -0.694748 0.719083 0.0156496 -0.694747 0.719084 -0.345989 -0.694748 0.630569 -0.34599 -0.694745 0.630571 -0.614922 -0.694744 0.373097 -0.614921 -0.694745 0.373096 -0.719085 -0.694746 0.0156494 -0.719082 -0.694749 0.0156488 -0.630567 -0.69475 -0.345988 -0.630567 -0.69475 -0.345988 -0.373094 -0.694749 -0.614919 -0.373096 -0.694745 -0.614921 -0.345988 -0.694749 0.630568 0.0156492 -0.694748 0.719083 0.0156493 -0.694747 0.719084 -0.213128 -0.857442 0.468369 -0.450098 -0.706115 0.546639 -0.614923 -0.694744 0.373096 -0.352101 -0.8956 0.271892 -0.654505 -0.704873 0.273455 -0.698945 -0.704873 0.120956 -0.532456 -0.846379 0.0115874 -0.708159 -0.703126 -0.0642206 -0.673289 -0.706118 -0.219271 -0.489725 -0.829436 -0.268709 -0.597954 -0.700865 -0.388895 -0.373094 -0.694749 -0.614919 -0.373095 -0.694746 -0.614921 0.0156493 -0.69475 0.719081 0.0156496 -0.694749 0.719082 -0.345989 -0.694748 0.630569 -0.34599 -0.694745 0.630571 -0.614922 -0.694744 0.373097 -0.614916 -0.694753 0.37309 -0.719078 -0.694753 0.0156492 -0.719083 -0.694748 0.0156503 -0.630568 -0.694748 -0.34599 -0.630571 -0.694745 -0.345991 -0.373095 -0.694747 -0.614921 -0.373096 -0.694745 -0.614921 0.0423335 -0.69808 0.714767 0.0423349 -0.698076 0.714772 -0.142363 -0.706861 0.692878 -0.239089 -0.777063 0.582246 -0.295431 -0.700863 0.64924 -0.450095 -0.706117 0.546639 -0.434068 -0.811942 0.390302 -0.5628 -0.703125 0.434593 -0.654504 -0.704873 0.273455 -0.54681 -0.821953 0.159347 -0.698945 -0.704873 0.120957 -0.706274 -0.698073 -0.117779 -0.533415 -0.844469 -0.0483745 -0.67329 -0.706117 -0.219271 -0.585227 -0.698075 -0.412554 -0.516924 -0.78725 -0.336195 -0.492291 -0.706861 -0.507933 -0.34827 -0.698076 -0.625618 -0.348269 -0.698077 -0.625617 -0.345989 -0.694749 0.630568 0.0156503 -0.694748 0.719083 0.0156492 -0.694753 0.719078 -0.213129 -0.857441 0.46837 -0.450097 -0.706114 0.54664 -0.614922 -0.694745 0.373095 -0.3521 -0.895601 0.271891 -0.654503 -0.704876 0.273454 -0.698943 -0.704875 0.120956 -0.532454 -0.846379 0.0115877 -0.70816 -0.703126 -0.0642214 -0.673289 -0.706118 -0.219271 -0.489726 -0.829436 -0.268709 -0.597957 -0.700861 -0.388898 -0.373097 -0.694744 -0.614922 -0.373095 -0.694746 -0.614921 0.0156494 -0.694746 0.719085 0.0156504 -0.694742 0.719089 -0.345991 -0.694742 0.630574 -0.345991 -0.694744 0.630572 -0.614922 -0.694745 0.373096 -0.61492 -0.694747 0.373094 -0.719085 -0.694746 0.0156494 -0.719084 -0.694747 0.0156492 -0.63057 -0.694746 -0.34599 -0.630569 -0.694747 -0.345989 -0.373095 -0.694747 -0.61492 -0.373095 -0.694747 -0.61492 -0.345989 -0.694748 0.630569 0.0156488 -0.694749 0.719082 0.0156494 -0.694746 0.719085 -0.213128 -0.857442 0.468369 -0.450092 -0.706119 0.546638 -0.614918 -0.69475 0.373093 -0.352101 -0.8956 0.271892 -0.654506 -0.704872 0.273454 -0.698945 -0.704873 0.120957 -0.532454 -0.846379 0.0115879 -0.708162 -0.703124 -0.0642221 -0.673291 -0.706116 -0.219272 -0.489727 -0.829435 -0.26871 -0.597956 -0.700862 -0.388896 -0.373095 -0.694747 -0.61492 -0.373094 -0.694749 -0.614919 0.0423349 -0.698074 0.714773 0.0423349 -0.698074 0.714773 -0.142359 -0.70686 0.69288 -0.239089 -0.777063 0.582245 -0.295432 -0.700862 0.64924 -0.450094 -0.706116 0.54664 -0.434068 -0.811942 0.390302 -0.562798 -0.703128 0.434592 -0.687429 -0.698077 0.200324 -0.434316 -0.882294 0.181457 -0.698945 -0.704873 0.120956 -0.706273 -0.698073 -0.117778 -0.533415 -0.84447 -0.0483736 -0.67329 -0.706116 -0.219271 -0.585227 -0.698074 -0.412555 -0.516924 -0.78725 -0.336195 -0.49229 -0.706858 -0.50794 -0.348272 -0.698072 -0.625621 -0.348271 -0.698074 -0.62562 0.0156494 -0.694746 0.719085 0.0156492 -0.694747 0.719084 -0.345989 -0.694746 0.63057 -0.345989 -0.694747 0.63057 -0.61492 -0.694747 0.373095 -0.614918 -0.69475 0.373093 -0.719081 -0.69475 0.0156493 -0.719082 -0.694749 0.0156496 -0.630569 -0.694748 -0.345989 -0.630569 -0.694747 -0.345989 -0.373095 -0.694747 -0.61492 -0.373093 -0.69475 -0.614918 0.0423366 -0.698075 0.714772 0.042334 -0.698073 0.714774 -0.271987 -0.698072 0.662358 -0.271984 -0.698074 0.662357 -0.532438 -0.698074 0.478752 -0.532438 -0.698074 0.478752 -0.687432 -0.698074 0.200326 -0.687432 -0.698074 0.200326 -0.706273 -0.698074 -0.117779 -0.706273 -0.698074 -0.117778 -0.585228 -0.698075 -0.412554 -0.585228 -0.698074 -0.412555 -0.348271 -0.698074 -0.625619 -0.34827 -0.698073 -0.625622 0.0156495 -0.694748 0.719083 0.0156488 -0.694747 0.719084 -0.34599 -0.694747 0.63057 -0.34599 -0.694747 0.63057 -0.61492 -0.694747 0.373096 -0.614921 -0.694746 0.373095 -0.719085 -0.694746 0.015648 -0.719084 -0.694747 0.0156488 -0.63057 -0.694747 -0.34599 -0.63057 -0.694747 -0.345989 -0.373095 -0.694747 -0.614921 -0.373095 -0.694747 -0.61492 -0.373095 -0.694746 -0.614922 -0.373095 -0.694747 -0.61492 -0.63057 -0.694747 -0.345988 -0.645743 -0.637682 -0.419974 -0.67329 -0.706115 -0.219279 -0.719085 -0.694746 0.0156488 -0.794053 -0.603569 -0.072009 -0.698943 -0.704874 0.120958 -0.654506 -0.704874 0.27345 -0.646347 -0.654556 0.392163 0.0156492 -0.694746 0.719084 0.0156494 -0.694747 0.719084 -0.295431 -0.700862 0.64924 -0.360663 -0.661712 0.657313 -0.450093 -0.706115 0.546643 -0.562801 -0.703123 0.434594 0.0423347 -0.698074 0.714773 0.0423345 -0.698074 0.714773 -0.271987 -0.698074 0.662357 -0.271986 -0.698074 0.662357 -0.532435 -0.698074 0.478754 -0.532438 -0.698073 0.478753 -0.687434 -0.698072 0.200325 -0.687433 -0.698073 0.200325 -0.706273 -0.698073 -0.11778 -0.706272 -0.698075 -0.117777 -0.585228 -0.698075 -0.412553 -0.585228 -0.698073 -0.412556 -0.34827 -0.698073 -0.625621 -0.348271 -0.698074 -0.62562 0.0423331 -0.698072 0.714775 0.0423366 -0.698075 0.714772 -0.271986 -0.698075 0.662356 -0.271987 -0.698074 0.662356 -0.532436 -0.698074 0.478753 -0.532437 -0.698074 0.478753 -0.687432 -0.698074 0.200325 -0.687432 -0.698074 0.200325 -0.706273 -0.698074 -0.117778 -0.706273 -0.698074 -0.117778 -0.585228 -0.698074 -0.412554 -0.585228 -0.698072 -0.412557 -0.34827 -0.698072 -0.625623 -0.348272 -0.698074 -0.625619 0.0423366 -0.698075 0.714772 0.042334 -0.698073 0.714774 -0.271987 -0.698072 0.662358 -0.271984 -0.698074 0.662357 -0.532436 -0.698074 0.478753 -0.532437 -0.698074 0.478753 -0.687432 -0.698074 0.200325 -0.687432 -0.698074 0.200325 -0.706273 -0.698074 -0.117779 -0.706272 -0.698074 -0.117778 -0.585228 -0.698075 -0.412553 -0.585228 -0.698072 -0.412557 -0.34827 -0.698072 -0.625623 -0.348272 -0.698074 -0.625619 0.0423348 -0.698075 0.714773 0.0423339 -0.698074 0.714773 -0.271986 -0.698074 0.662357 -0.271985 -0.698074 0.662357 -0.532436 -0.698074 0.478753 -0.532437 -0.698074 0.478753 -0.687432 -0.698074 0.200326 -0.687432 -0.698073 0.200325 -0.706273 -0.698073 -0.11778 -0.706273 -0.698074 -0.117778 -0.585228 -0.698074 -0.412554 -0.585228 -0.698074 -0.412555 -0.348271 -0.698073 -0.625621 -0.348271 -0.698074 -0.625619 0.0423347 -0.698074 0.714773 0.0423348 -0.698074 0.714773 -0.271987 -0.698074 0.662357 -0.271987 -0.698074 0.662357 -0.532436 -0.698074 0.478754 -0.532437 -0.698073 0.478754 -0.687434 -0.698072 0.200325 -0.687433 -0.698073 0.200325 -0.706273 -0.698073 -0.11778 -0.706272 -0.698075 -0.117777 -0.585228 -0.698075 -0.412553 -0.585228 -0.698073 -0.412556 -0.34827 -0.698073 -0.625621 -0.348271 -0.698074 -0.62562 -0.348271 -0.698074 -0.62562 -0.34827 -0.698072 -0.625622 -0.492293 -0.706858 -0.507936 -0.597546 -0.682273 -0.42124 -0.597957 -0.700862 -0.388896 -0.67329 -0.706116 -0.219272 -0.730221 -0.672271 -0.121772 -0.70816 -0.703125 -0.0642198 -0.687432 -0.698074 0.200325 -0.771537 -0.622016 0.133518 -0.654505 -0.704873 0.273453 -0.532437 -0.698074 0.478753 -0.601341 -0.650203 0.464355 -0.450097 -0.706116 0.546638 -0.271987 -0.698073 0.662357 0.0423348 -0.698073 0.714774 0.0423352 -0.698074 0.714773 -0.142369 -0.706859 0.692879 -0.305411 -0.675461 0.671176 -0.65771 -0.706222 0.262045 -0.65771 -0.706223 0.262045 -0.688076 -0.706223 0.166736 -0.688076 -0.706222 0.166736 0.242787 -0.69924 0.672397 0.242787 -0.699238 0.672399 -0.0519743 -0.699238 0.712997 -0.0519742 -0.699239 0.712996 -0.337731 -0.699239 0.630081 -0.33773 -0.699241 0.63008 -0.564982 -0.69924 0.438017 -0.564983 -0.699238 0.438018 0.570193 -0.704309 0.422881 0.570193 -0.70431 0.42288 0.447286 -0.70431 0.551256 0.447285 -0.704311 0.551255 0.413023 -0.699239 -0.583504 0.413023 -0.699239 -0.583504 0.614792 -0.699238 -0.364823 0.614791 -0.69924 -0.364823 0.710059 -0.69924 -0.0829442 0.710063 -0.699236 -0.0829438 0.682327 -0.699236 0.213305 0.682326 -0.699237 0.213304 0.136644 -0.706223 -0.694678 0.136644 -0.706223 -0.694678 0.233183 -0.706223 -0.668487 0.233183 -0.706223 -0.668487 -0.0571084 -0.699695 -0.712156 -0.0571085 -0.699695 -0.712155 -0.516137 -0.699585 -0.49415 -0.516137 -0.699585 -0.49415 -0.713272 -0.700708 -0.0158695 -0.713272 -0.700708 -0.0158695 -0.656904 -0.700708 -0.278363 -0.656904 -0.700707 -0.278364 -0.507512 -0.700707 -0.501438 -0.507512 -0.700707 -0.501439 -0.555791 -0.706224 -0.43857 -0.555793 -0.706222 -0.438572 -0.488437 -0.706222 -0.512524 -0.488436 -0.706223 -0.512523 -0.460922 -0.699237 0.546459 -0.460923 -0.699237 0.54646 -0.643461 -0.699238 0.311488 -0.643462 -0.699237 0.311488 -0.714533 -0.699238 0.0225573 -0.714533 -0.699238 0.0225573 -0.661827 -0.699238 -0.270281 -0.661825 -0.69924 -0.27028 -0.0811288 -0.704308 0.705244 -0.0811287 -0.704308 0.705244 -0.253759 -0.704308 0.662991 -0.253759 -0.704309 0.66299 0.711841 -0.699239 0.0659367 0.711841 -0.699238 0.0659368 0.623343 -0.699238 0.350015 0.623342 -0.699239 0.350014 0.426861 -0.699239 0.573458 0.426862 -0.699237 0.57346 0.156436 -0.699237 0.697564 0.156436 -0.699236 0.697565 0.669931 -0.706223 -0.229002 0.66993 -0.706223 -0.229002 0.695518 -0.706223 -0.132301 0.695519 -0.706223 -0.132301 0.158688 -0.700708 -0.695576 0.158688 -0.700709 -0.695576 0.404529 -0.700708 -0.587677 0.40453 -0.700707 -0.587678 0.593087 -0.700707 -0.396557 0.593086 -0.700708 -0.396557 0.169878 -0.699586 -0.694062 0.169878 -0.699584 -0.694063 -0.0721747 -0.701186 -0.709316 -0.0721743 -0.701184 -0.709318 0.185296 -0.701184 -0.688481 0.185296 -0.701184 -0.688481 0.101917 -0.706222 -0.700616 0.101917 -0.706223 -0.700616 0.19964 -0.706223 -0.679259 0.19964 -0.706223 -0.679259 -0.0746331 -0.701413 -0.708837 -0.074633 -0.701412 -0.708838 -0.651322 -0.70431 0.282362 -0.651319 -0.704312 0.282361 -0.701042 -0.704312 0.111733 -0.701045 -0.704309 0.111733 0.298818 -0.699239 0.64944 0.298818 -0.699239 0.649441 0.00855015 -0.69924 0.714836 0.00854982 -0.699238 0.714838 -0.283199 -0.699237 0.656403 -0.2832 -0.699237 0.656404 -0.52589 -0.699237 0.48426 -0.525889 -0.699238 0.48426 0.533287 -0.706223 0.465675 0.533288 -0.706222 0.465677 0.462336 -0.706222 0.536187 0.462335 -0.706223 0.536186 0.681731 -0.700708 -0.21036 0.681732 -0.700707 -0.21036 0.711209 -0.700707 0.0564941 0.711209 -0.700707 0.0564941 0.639972 -0.700707 0.31535 0.639971 -0.700708 0.315349 0.686014 -0.699586 -0.199912 0.686015 -0.699585 -0.199913 0.370379 -0.700709 -0.609776 0.37038 -0.700708 -0.609777 0.569522 -0.700708 -0.429714 0.569522 -0.700707 -0.429714 0.688015 -0.700707 -0.188799 0.688015 -0.700707 -0.188799 0.65771 -0.706222 -0.262045 0.657711 -0.706222 -0.262045 0.688077 -0.706222 -0.166737 0.688076 -0.706223 -0.166736 -0.0354491 -0.697264 -0.715937 -0.035449 -0.697263 -0.715939 0.291436 -0.697263 -0.654897 0.291434 -0.697266 -0.654894 0.555598 -0.697266 -0.452914 0.555599 -0.697265 -0.452915 -0.570193 -0.704309 -0.422881 -0.570193 -0.70431 -0.42288 -0.447286 -0.70431 -0.551256 -0.447287 -0.704309 -0.551257 -0.413023 -0.699239 0.583504 -0.413024 -0.699238 0.583505 -0.614793 -0.699238 0.364824 -0.614791 -0.69924 0.364823 -0.710059 -0.69924 0.0829442 -0.710063 -0.699236 0.0829438 -0.682327 -0.699236 -0.213305 -0.682326 -0.699237 -0.213304 -0.136644 -0.706223 0.694678 -0.136644 -0.706223 0.694678 -0.233183 -0.706223 0.668487 -0.233183 -0.706223 0.668487 0.0468855 -0.700708 0.711906 0.523044 -0.700706 0.485217 0.523044 -0.700707 0.485217 0.315423 -0.701643 0.63891 0.319078 -0.670074 0.670217 0.188143 -0.707071 0.681654 0.0468854 -0.700707 0.711907 0.516137 -0.699584 0.49415 0.516137 -0.699585 0.49415 0.713272 -0.700707 0.0158695 0.713273 -0.700707 0.0158698 0.656905 -0.700707 0.278364 0.656904 -0.700707 0.278363 0.507512 -0.700707 0.501438 0.507512 -0.700707 0.501439 0.555793 -0.706222 0.438571 0.555793 -0.706222 0.438571 0.488437 -0.706222 0.512524 0.488436 -0.706223 0.512523 0.460922 -0.699237 -0.546459 0.460923 -0.699237 -0.54646 0.643461 -0.699238 -0.311488 0.643462 -0.699237 -0.311488 0.714533 -0.699238 -0.0225573 0.714533 -0.699238 -0.0225573 0.661827 -0.699238 0.270281 0.661826 -0.699238 0.270281 0.0811288 -0.704308 -0.705244 0.0811287 -0.704308 -0.705243 0.253759 -0.704308 -0.66299 0.253759 -0.704309 -0.66299 -0.104239 -0.703808 -0.702701 -0.104239 -0.703803 -0.702705 -0.669931 -0.706223 0.229002 -0.669931 -0.706223 0.229002 -0.695518 -0.706223 0.132301 -0.695519 -0.706223 0.132301 -0.158689 -0.700706 0.695578 -0.158688 -0.700707 0.695577 -0.40453 -0.700707 0.587678 -0.40453 -0.700707 0.587678 -0.593087 -0.700707 0.396557 -0.593086 -0.700708 0.396557 -0.169878 -0.699584 0.694063 -0.169878 -0.699585 0.694062 -0.180502 -0.700707 0.690238 -0.180503 -0.700706 0.690239 0.0873821 -0.700706 0.708079 0.342893 -0.700708 0.625646 0.342893 -0.700707 0.625647 0.207498 -0.707071 0.676014 0.0807718 -0.666294 0.741302 -0.101917 -0.706222 0.700616 -0.101917 -0.706223 0.700616 -0.19964 -0.706223 0.679259 -0.19964 -0.706223 0.679259 0.703709 -0.699237 0.12594 0.703709 -0.699237 0.12594 0.591487 -0.699237 0.40151 0.591488 -0.699237 0.401511 0.376802 -0.699237 0.607526 0.376802 -0.699238 0.607525 0.096843 -0.699238 0.708299 0.096843 -0.699238 0.708299 0.651321 -0.70431 -0.282361 0.651322 -0.704309 -0.282362 0.701045 -0.704309 -0.111734 0.701045 -0.704309 -0.111734 -0.0454827 -0.698435 -0.714226 -0.0454823 -0.698432 -0.714229 0.263019 -0.698433 -0.665592 0.263019 -0.698433 -0.665591 0.521434 -0.698433 -0.490203 0.521433 -0.698433 -0.490203 -0.533288 -0.706222 -0.465676 -0.533288 -0.706222 -0.465677 -0.462336 -0.706222 -0.536187 -0.462334 -0.706225 -0.536184 -0.681733 -0.700706 0.21036 -0.68173 -0.700709 0.21036 -0.711207 -0.700709 -0.056494 -0.711209 -0.700707 -0.0564946 -0.639972 -0.700707 -0.315349 -0.639972 -0.700707 -0.315349 -0.686015 -0.699584 0.199913 -0.686015 -0.699585 0.199913 -0.370379 -0.700709 0.609776 -0.37038 -0.700708 0.609777 -0.569522 -0.700708 0.429714 -0.569522 -0.700707 0.429714 -0.688015 -0.700707 0.188799 -0.688015 -0.700707 0.188799 0.0156494 -0.694746 0.719085 0.0156488 -0.694749 0.719082 -0.345989 -0.694748 0.630569 -0.345989 -0.694747 0.63057 -0.61492 -0.694747 0.373095 -0.61492 -0.694747 0.373095 -0.719083 -0.694748 0.0156494 -0.719082 -0.694749 0.0156492 -0.63057 -0.694746 -0.34599 -0.630571 -0.694745 -0.34599 -0.373096 -0.694744 -0.614923 -0.373094 -0.694747 -0.61492 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.335751 0 -0.941951 -0.516888 -0.0840337 -0.851919 -0.516889 -0.0840358 -0.851918 -0.652453 -0.0156396 -0.757668 -0.836835 0.0590899 -0.544257 -0.817328 0 -0.576173 -0.950846 0 -0.309664 -0.983297 0.0789904 -0.163976 -0.995913 0 -0.0903178 -0.985354 0 0.170523 -0.95627 0.0888317 0.278669 -0.922705 0 0.385508 -0.791487 0 0.611186 -0.741276 0.0789907 0.666536 -0.635641 0 0.771985 -0.414178 0 0.910196 -0.379391 0.049395 0.923917 0.0217197 -0.0590892 0.998016 0.0591246 0 0.998251 -0.761747 0 -0.647874 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.873598 -0.0840317 -0.479339 -0.873598 -0.0840338 -0.479338 -0.955665 0 -0.294455 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217577 0 0.999763 0.0217577 0 0.999763 -0.518724 0 -0.854942 -0.485246 -0.0686855 -0.871676 -0.836835 0.0590907 -0.544257 -0.817327 0 -0.576174 -0.967412 0 -0.253208 -0.949372 0.0556624 -0.309183 -0.997576 -0.0634984 -0.0284663 -0.995913 0 -0.0903161 -0.993677 0 0.112279 -0.985109 -0.0223067 0.170478 -0.942745 0.0467949 0.330215 -0.922704 0 0.38551 -0.791487 0 0.611186 -0.741277 0.0789895 0.666535 -0.635644 0 0.771983 -0.414178 0 0.910196 -0.379391 0.0493952 0.923917 0.0217197 -0.0590897 0.998016 0.0591249 0 0.998251 -0.941951 0 0.335751 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.876698 0 -0.48104 -0.876698 0 -0.48104 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.851917 -0.0840349 0.51689 -0.851917 -0.0840352 0.51689 -0.732836 0 0.680405 -0.481039 0 0.876699 -0.481039 0 0.876699 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.486394 0 -0.873739 -0.517818 0.0590904 -0.853447 -0.695964 0 -0.718077 -0.8383 0 -0.54521 -0.872448 0.098361 -0.478706 -0.950846 0 -0.309664 -0.999763 0 0.0217577 -0.9754 0.201916 -0.0884573 0.0591234 0 0.998251 0.0217178 0.0590905 0.998016 -0.201261 0 0.979538 -0.294448 0 0.955668 -0.413586 -0.0533983 0.908898 -0.48099 0.0145059 0.876606 -0.635627 -0.00667511 0.771967 -0.647877 0 0.761745 -0.791488 0 0.611185 -0.84898 0.11789 0.515107 -0.922704 0 0.38551 -0.985354 0 0.170523 -0.970231 0.174528 0.167904 -0.960066 0 0.279774 -0.995913 0 -0.0903171 -0.983297 0.0789908 -0.163975 -0.950846 0 -0.309664 -0.817327 0 -0.576173 -0.836834 0.059088 -0.544258 -0.485245 -0.0686884 -0.871676 -0.518725 0 -0.854941 -0.922704 0 0.385509 -0.791487 0 0.611186 -0.741277 0.0789903 0.666535 -0.635643 0 0.771984 -0.414179 0 0.910195 0.222826 0 0.974858 0.0216818 -0.0840328 0.996227 0.0216808 -0.0840343 0.996227 -0.143297 -0.0156364 0.989556 -0.379391 0.0493963 0.923917 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 -0.379392 0.0493945 0.923917 0.0217198 -0.0590892 0.998016 0.0591246 0 0.998251 -0.922705 0 0.385508 -0.791488 0 0.611185 -0.741276 0.078992 0.666536 -0.63564 0 0.771986 -0.414178 0 0.910196 -0.970231 0.174527 0.167905 -0.960066 0 0.279775 -0.995913 0 -0.0903178 -0.983297 0.0789905 -0.163976 -0.950846 0 -0.309664 -0.817328 0 -0.576173 -0.836835 0.0590893 -0.544257 -0.485246 -0.0686862 -0.871676 -0.518725 0 -0.854941 0.0591249 0 0.998251 0.0217198 0.0590896 0.998016 -0.478706 0.0983604 0.872448 -0.414178 0 0.910196 -0.201256 0 0.979539 -0.985354 0 0.170521 -0.922705 0 0.385507 -0.84898 0.117892 0.515107 -0.791487 0 0.611186 -0.63564 0 0.771985 -0.975401 0.201914 -0.0884559 -0.999763 0 0.0217578 -0.950846 0 -0.309664 -0.872448 0.098361 -0.478706 -0.8383 0 -0.54521 -0.695959 0 -0.718082 -0.517818 0.0590889 -0.853448 -0.486395 0 -0.873739 0.0217578 0 0.999763 0.120057 -0.18191 0.975959 -0.13895 0 0.990299 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854941 0 0.518725 -0.854941 0 0.518725 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518725 0 -0.854941 -0.518725 0 -0.854941 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0217578 0 0.999763 0.0217578 0 0.999763 -0.481039 0 0.876699 -0.481039 0 0.876699 -0.854942 0 0.518724 -0.854942 0 0.518724 -0.999763 0 0.0217578 -0.999763 0 0.0217578 -0.876699 0 -0.481039 -0.876699 0 -0.481039 -0.518724 0 -0.854942 -0.518724 0 -0.854942 -0.681347 -0.704517 0.198552 0.0273998 -0.707106 0.706577 0.114977 -0.704516 0.700313 0.114978 -0.704514 0.700314 -0.103884 -0.706618 0.699928 -0.0733776 0.366071 0.927689 -0.0381704 -0.479656 0.876626 0.015547 -0.69962 0.714346 -0.171232 -0.706751 0.686427 -0.299911 0.30701 0.903216 -0.252962 -0.706082 0.661407 -0.399606 -0.705866 0.584865 -0.521876 0.204082 0.828249 -0.400794 -0.552998 0.73045 -0.316936 -0.707012 0.632207 -0.458611 -0.707018 0.538332 -0.713373 -0.136153 0.687431 -0.521348 -0.705394 0.480225 -0.646235 -0.707076 0.287097 -0.739413 -0.551276 0.386475 -0.799324 0.382765 0.463219 -0.854464 -0.033401 0.518436 -0.58282 -0.706774 0.400987 -0.996079 0.0810782 -0.0353926 -0.831281 -0.551268 0.0712415 -0.699298 -0.707075 0.105008 -0.681347 -0.704517 0.198552 -0.912858 -0.402235 0.0699821 -0.832702 0.55262 0.034909 -0.707333 -0.706627 -0.0189495 -0.695575 -0.704516 -0.140828 -0.695573 -0.704518 -0.140828 -0.651238 -0.705869 -0.278635 -0.885115 0.204084 -0.418236 -0.730436 -0.553022 -0.400787 -0.738173 0.307002 -0.600708 -0.56867 -0.706084 -0.421972 -0.606942 -0.707015 -0.362976 -0.356467 -0.707107 -0.610681 -0.370633 -0.699623 -0.610867 -0.503121 -0.479658 -0.718887 -0.560249 0.366069 -0.743044 -0.463623 -0.706621 -0.534547 -0.513175 -0.706754 -0.486981 -0.341793 -0.707033 -0.619098 -0.386574 -0.186233 -0.903259 -0.265312 -0.705332 -0.657356 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0310205 -0.851306 0.523751 -0.503716 -0.851307 0.146789 -0.390143 -0.851307 0.350806 -0.199298 -0.851307 0.485343 -0.255196 -0.851307 -0.458423 -0.428825 -0.851307 -0.302301 -0.517521 -0.851307 -0.0863018 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.451579 -0.849121 -0.27399 0.254084 -0.849121 -0.463071 -0.0114917 -0.849121 -0.528073 0.273989 -0.849121 0.45158 0.463071 -0.849121 0.254084 0.528073 -0.849121 -0.0114943 0.031022 -0.851307 0.52375 -0.503717 -0.851307 0.146787 -0.390144 -0.851307 0.350806 -0.199299 -0.851307 0.485342 -0.255194 -0.851307 -0.458424 -0.428828 -0.851307 -0.302297 -0.517522 -0.851307 -0.0863017 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.451579 -0.849121 -0.273989 0.254084 -0.849121 -0.463071 -0.011493 -0.849121 -0.528073 0.273988 -0.849121 0.451579 0.463071 -0.849121 0.254084 0.528074 -0.849121 -0.0114943 0 1 0 0 1 0 -0.676286 0 0.73664 -0.676286 0 0.73664 -0.906605 0 0.421981 -0.906605 0 0.421981 0 -1 0 0 -1 0 0.812891 0 -0.582416 0.812891 0 -0.582416 0.800888 0 -0.598814 0.800888 0 -0.598814 0 -1 0 0 -1 0 0.406695 0 -0.913564 0.406695 0 -0.913564 0 1 0 0 1 0 -0.246176 0 0.969225 -0.246176 0 0.969225 -0.356697 0 0.93422 -0.356697 0 0.93422 -0.613205 0 0.789924 -0.613205 0 0.789924 0 -1 0 0 -1 0 0.552071 0 -0.833797 0.552071 0 -0.833797 0 1 0 0 1 0 -0.336847 0 0.941559 -0.336847 0 0.941559 -0.596355 0 0.802721 -0.596355 0 0.802721 -0.685248 0 0.728309 -0.685248 0 0.728309 0 -1 0 0 -1 0 0.0748301 0 -0.997196 0.0748301 0 -0.997196 0.054557 0 -0.998511 0.054557 0 -0.998511 0 1 0 0 1 0 0.131109 0 0.991368 0.131109 0 0.991368 -0.25802 0 0.96614 -0.25802 0 0.96614 0.73664 0 0.676286 0.73664 0 0.676286 0.421981 0 0.906605 0.421981 0 0.906605 0 -1 0 0 -1 0 -0.582416 0 -0.812891 -0.582416 0 -0.812891 -0.598814 0 -0.800888 -0.598814 0 -0.800888 0 1 0 0 1 0 0.969224 0 0.246181 0.969224 0 0.246181 0.93422 0 0.356697 0.93422 0 0.356697 0.789927 0 0.613201 0.789927 0 0.613201 0 -1 0 0 -1 0 -0.913564 0 -0.406695 -0.913564 0 -0.406695 0 1 0 0 1 0 0.941557 0 0.336853 0.941557 0 0.336853 0.802724 0 0.596351 0.802724 0 0.596351 0.728311 0 0.685247 0.728311 0 0.685247 0 -1 0 0 -1 0 -0.833797 0 -0.552071 -0.833797 0 -0.552071 0 1 0 0 1 0 0.991367 0 -0.131114 0.991367 0 -0.131114 0.96614 0 0.25802 0.96614 0 0.25802 0 -1 0 0 -1 0 0 1 0 0 1 0 -0.997196 0 -0.07483 -0.997196 0 -0.07483 -0.998511 0 -0.0545523 -0.998511 0 -0.0545523 -0.255197 0.851305 -0.458426 -0.503718 0.851305 0.14679 -0.517524 0.851305 -0.086304 -0.428828 0.851305 -0.302301 0.0310212 0.851305 0.523753 -0.199299 0.851305 0.485344 -0.390145 0.851305 0.350808 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.528076 0.849119 -0.0114919 0.463073 0.849119 0.254085 0.273991 0.849119 0.451581 -0.0114927 0.849119 -0.528076 0.254085 0.849119 -0.463073 0.451581 0.849119 -0.273991 -0.255197 0.851305 -0.458425 -0.503719 0.851305 0.146789 -0.517524 0.851305 -0.0863025 -0.428828 0.851305 -0.302302 0.0310207 0.851305 0.523753 -0.199299 0.851305 0.485345 -0.390145 0.851305 0.350809 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.528076 0.84912 -0.0114933 0.463073 0.84912 0.254085 0.27399 0.84912 0.451581 -0.0114933 0.84912 -0.528076 0.254086 0.84912 -0.463073 0.451581 0.84912 -0.27399 0.976913 0.0039234 -0.213603 0.987239 0 -0.159247 0.970713 0 -0.240242 0.963606 0 -0.267328 0.976913 0.00392473 -0.213603 0.937649 0.280682 -0.205018 0.982396 0 -0.186808 -0.971773 0 -0.235917 -0.621881 0 0.783112 -0.777778 0.0628557 0.625389 -0.784636 0 0.619957 -0.891969 0 -0.452096 -0.967808 0.062853 -0.243714 -0.971773 0 -0.235917 -0.97692 0 0.213605 -0.97692 0 0.213605 -0.784635 0 0.619957 0 1 0 0 1 0 0 1 0 -0.820902 0 0.57107 -0.820902 0 0.57107 -0.984329 0 -0.176341 -0.984329 0 -0.176341 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0.999533 0 0.0305622 0.958192 0.280682 0.0555588 0.996367 0 0.0851661 0.999997 0 0.00260078 0.998316 0.00392204 0.0578858 0.998316 0.00392488 0.0578853 0.993591 0 0.113034 -0.872088 0 -0.489349 -0.810086 0 0.58631 -0.917663 0.0628647 0.392357 -0.922802 0 0.385275 -0.7369 0 -0.676002 -0.866166 0.0628616 -0.495788 -0.872088 0 -0.489349 -0.998323 0 -0.0578863 -0.998323 0 -0.0578863 -0.922802 0 0.385275 0 1 0 0 1 0 0 1 0 -0.944532 0 0.328419 -0.944532 0 0.328419 -0.900239 0 -0.435396 -0.900239 0 -0.435396 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 -0.749392 0 -0.662126 -0.749392 0 -0.662126 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0.954222 0 0.299099 0.907667 0.280689 0.312015 0.936441 0 0.350825 0.962217 0 0.272283 0.945678 0.00392331 0.325082 0.945678 0.00392498 0.325081 0.926249 0 0.376912 -0.707724 0 -0.706489 -0.938233 0 0.346004 -0.98949 0.0628629 0.130223 -0.992528 0 0.122018 -0.527197 0 -0.849743 -0.700284 0.0628582 -0.711091 -0.707724 0 -0.706489 -0.945685 0 -0.325084 -0.945685 0 -0.325084 -0.992528 0 0.122018 0 1 0 0 1 0 0 1 0 -0.998112 0 0.0614136 -0.998112 0 0.0614136 0.822904 0.00392392 0.568167 0.790221 0 0.612822 0.838141 0 0.545454 0.853069 0 0.521799 0.822904 0.00392251 0.568167 0.789828 0.280688 0.545331 0.807064 0 0.590464 -0.490872 0 -0.871232 -0.996792 0 0.0800322 -0.987931 0.0628593 -0.141566 -0.988643 0 -0.150285 -0.278373 0 -0.960473 -0.482466 0.0628636 -0.873656 -0.490872 0 -0.871232 -0.82291 0 -0.568172 -0.82291 0 -0.568172 -0.988643 0 -0.150285 0 1 0 0 1 0 0 1 0 -0.977666 0 -0.210166 -0.977666 0 -0.210166 -0.542962 0 -0.839757 -0.542962 0 -0.839757 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0.659899 0 0.751354 0.613411 0.280688 0.738201 0.61783 0 0.786311 0.680647 0 0.732612 0.639099 0.00392174 0.769115 0.639099 0.00392363 0.769115 0.595582 0 0.803295 -0.237612 0 -0.97136 -0.981423 0 -0.191857 -0.913102 0.062863 -0.402856 -0.911435 0 -0.411445 -0.00896006 0 -0.99996 -0.228865 0.0628523 -0.971427 -0.237612 0 -0.97136 -0.639102 0 -0.769122 -0.639102 0 -0.769122 -0.911435 0 -0.411445 0 1 0 0 1 0 0 1 0 -0.884711 0 -0.466141 -0.884711 0 -0.466141 -0.296282 0 -0.955101 -0.296282 0 -0.955101 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0.407894 0.00392498 0.913021 0.356754 0 0.934198 0.432715 0 0.901531 0.457785 0 0.889063 0.407894 0.00392451 0.913021 0.3915 0.280685 0.876324 0.382775 0 0.923841 0.033267 0 -0.999447 -0.893267 0 -0.449526 -0.770551 0.0628631 -0.63427 -0.766629 0 -0.642091 0.261194 0 -0.965286 0.0417093 0.0628617 -0.99715 0.033267 0 -0.999447 -0.407897 0 -0.913028 -0.407897 0 -0.913028 -0.766629 0 -0.642091 0 1 0 0 1 0 0 1 0 -0.726153 0 -0.687534 -0.726153 0 -0.687534 -0.0275885 0 -0.999619 -0.0275885 0 -0.999619 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0.146438 0.00392168 0.989212 0.0915272 0 0.995803 0.173439 0 0.984845 0.200911 0 0.979609 0.146438 0.00392217 0.989212 0.140552 0.280691 0.949451 0.119331 0 0.992855 0.301682 0 -0.953409 -0.738851 0 -0.673869 -0.570853 0.0628592 -0.818642 -0.564966 0 -0.825114 0.511937 0 -0.859023 0.309192 0.0628621 -0.94892 0.301682 0 -0.953409 -0.14644 0 -0.98922 -0.14644 0 -0.98922 -0.564966 0 -0.825114 0 1 0 0 1 0 0 1 0 -0.513712 0 -0.857962 -0.513712 0 -0.857962 0.243111 0 -0.969998 0.243111 0 -0.969998 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0.495789 0 -0.868443 0.495789 0 -0.868443 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 -0.125878 0.00392326 0.992038 -0.180553 0 0.983565 -0.0987018 0 0.995117 -0.070821 0 0.997489 -0.125878 0.00392316 0.992038 -0.120819 0.28068 0.952167 -0.152962 0 0.988232 0.547722 0 -0.83666 -0.529646 0 -0.848219 -0.328818 0.0628587 -0.942299 -0.321404 0 -0.946942 0.724694 0 -0.689071 0.553741 0.0628521 -0.830313 0.547722 0 -0.83666 0.12588 0 -0.992046 0.12588 0 -0.992046 -0.321404 0 -0.946942 0 1 0 0 1 0 0 1 0 -0.263191 0 -0.964744 -0.263191 0 -0.964744 -0.36352 0 0.931586 -0.373229 0.280687 0.884259 -0.413912 0 0.910317 -0.337306 0 0.941395 -0.388859 0.00392372 0.921289 -0.388859 0.00392417 0.921289 -0.439233 0 0.898373 0.753139 0 -0.657862 -0.281155 0 -0.959662 -0.0623949 0.0628579 -0.99607 -0.0540026 0 -0.998541 0.883745 0 -0.46797 0.757223 0.0628619 -0.650125 0.753139 0 -0.657862 0.388862 0 -0.921296 0.388862 0 -0.921296 -0.0540026 0 -0.998541 0 1 0 0 1 0 0 1 0 0.00684823 0 -0.999977 0.00684823 0 -0.999977 0.711726 0 -0.702457 0.711726 0 -0.702457 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0.276375 0 -0.96105 0.276375 0 -0.96105 0.874854 0 -0.484386 0.874854 0 -0.484386 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 -0.623 0.00392709 0.782212 -0.665354 0 0.746528 -0.601379 0 0.798964 -0.578771 0 0.81549 -0.623 0.00392485 0.782212 -0.597959 0.280686 0.750773 -0.644164 0 0.764888 0.902699 0 -0.430272 -0.0118309 0 -0.99993 0.208655 0.0628614 -0.975967 0.217403 0 -0.976082 0.977223 0 -0.212217 0.904545 0.0628528 -0.421721 0.902699 0 -0.430272 0.623005 0 -0.782218 0.623005 0 -0.782218 0.217403 0 -0.976082 0 1 0 0 1 0 0 1 0 -0.810936 0.00392604 0.585122 -0.842082 0 0.539349 -0.794637 0 0.607085 -0.777333 0 0.629089 -0.810935 0.00392388 0.585123 -0.778343 0.280679 0.561606 -0.82664 0 0.562731 0.985311 0 -0.170772 0.258407 0 -0.966036 0.464232 0.0628565 -0.883481 0.472686 0 -0.881231 0.998239 0 0.0593289 0.98478 0.0628592 -0.16204 0.985311 0 -0.170772 0.810942 0 -0.585126 0.810942 0 -0.585126 0.472686 0 -0.881231 0 1 0 0 1 0 0 1 0 0.525427 0 -0.850839 0.525427 0 -0.850839 0.973098 0 -0.230391 0.973098 0 -0.230391 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 -0.928959 0 0.370182 -0.900998 0.280685 0.330784 -0.94781 0 0.318837 -0.918222 0 0.396067 -0.938728 0.00392613 0.344636 -0.938728 0.00392363 0.344636 -0.956361 0 0.292187 0.994846 0 0.101396 0.509472 0 -0.860487 0.685377 0.0628509 -0.725471 0.69291 0 -0.721024 0.945207 0 0.326472 0.991979 0.0628669 0.109662 0.994846 0 0.101396 0.938735 0 -0.34464 0.938735 0 -0.34464 0.69291 0 -0.721024 0 1 0 0 1 0 0 1 0 0.735495 0 -0.67753 0.735495 0 -0.67753 0.999171 0 0.0406977 0.999171 0 0.0406977 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 -0.031022 -0.851307 -0.52375 0.503716 -0.851307 -0.146786 0.390141 -0.851307 -0.350809 0.199299 -0.851307 -0.485342 0.255195 -0.851307 0.458423 0.428825 -0.851307 0.302301 0.517521 -0.851307 0.0863016 -0.451578 -0.849121 0.273991 -0.254085 -0.849121 0.463071 0.011493 -0.849121 0.528073 -0.273988 -0.849121 -0.451579 -0.463071 -0.849121 -0.254084 -0.528073 -0.849121 0.0114917 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0310205 -0.851307 0.52375 -0.503717 -0.851307 0.146787 -0.390141 -0.851307 0.350808 -0.199298 -0.851307 0.485342 -0.255196 -0.851306 -0.458424 -0.428826 -0.851307 -0.3023 -0.517522 -0.851307 -0.0863015 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.451579 -0.849121 -0.273988 0.254083 -0.849121 -0.463071 -0.0114943 -0.849121 -0.528073 0.273989 -0.849121 0.451578 0.463071 -0.849121 0.254083 0.528073 -0.849121 -0.0114917 0.0591254 0 0.998251 0.0591254 0 0.998251 -0.379856 0 0.925046 -0.379856 0 0.925046 -0.7436 0 0.668625 -0.7436 0 0.668625 -0.960066 0 0.279773 -0.960066 0 0.279773 -0.986379 0 -0.16449 -0.986379 0 -0.16449 -0.817327 0 -0.576174 -0.817327 0 -0.576174 -0.486396 0 -0.873739 -0.486396 0 -0.873739 0.0310212 -0.851307 0.523751 -0.503717 -0.851306 0.146788 -0.390144 -0.851306 0.350807 -0.199298 -0.851307 0.485342 -0.255197 -0.851306 -0.458425 -0.428827 -0.851306 -0.302301 -0.517523 -0.851306 -0.0863029 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.451581 -0.84912 -0.273988 0.254083 -0.84912 -0.463073 -0.0114929 -0.84912 -0.528075 0.27399 -0.849121 0.451579 0.463072 -0.849121 0.254084 0.528074 -0.84912 -0.0114925 -0.0217586 0 -0.999763 -0.0217586 0 -0.999763 0.481036 0 -0.876701 0.481036 0 -0.876701 0.854943 0 -0.518722 0.854943 0 -0.518722 0.999763 0 -0.0217578 0.999763 0 -0.0217578 0.876699 0 0.481039 0.876699 0 0.481039 0.518725 0 0.854941 0.518725 0 0.854941 -0.379541 0.0406826 0.92428 0.0217328 -0.0486753 0.998578 0.0591253 0 0.998251 -0.922704 0 0.385508 -0.791486 0 0.611187 -0.742024 0.0650959 0.667206 -0.635647 0 0.77198 -0.414179 0 0.910196 -0.975027 0.144398 0.168736 -0.960066 0 0.279775 -0.995913 0 -0.0903175 -0.984286 0.0650985 -0.164141 -0.950846 0 -0.309666 -0.817329 0 -0.576171 -0.837307 0.0486733 -0.544562 -0.485611 -0.0565997 -0.872341 -0.518725 0 -0.854941 0.0114929 -0.849121 0.528073 -0.328055 -0.85653 0.398416 -0.47743 -0.855728 0.199472 -0.51717 -0.854597 -0.0469012 -0.27399 -0.84912 -0.45158 -0.437345 -0.853127 -0.284438 -0.490728 -0.85653 -0.159817 -0.509847 -0.855729 0.0882329 -0.411012 -0.854597 0.317385 -0.216078 -0.853127 0.474852 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0310213 -0.851306 -0.523752 0.216079 -0.853126 -0.474853 0.411015 -0.854597 -0.317382 0.509847 -0.855729 -0.0882329 0.490728 -0.85653 0.159817 0.255197 -0.851306 0.458423 0.358625 -0.857009 0.370032 0.437344 -0.853127 0.284437 0.51717 -0.854597 0.0469006 0.477429 -0.855728 -0.199475 0.328048 -0.85653 -0.398423 0.103707 -0.857009 -0.504759 -0.0591253 0 -0.998251 -0.0217328 0.0486753 -0.998578 0.479451 0.081102 -0.873813 0.414179 0 -0.910196 0.201254 0 -0.979539 0.985354 0 -0.170523 0.922702 0 -0.385514 0.850887 0.0972728 -0.516265 0.791491 0 -0.611181 0.635632 0 -0.771992 0.98187 0.16734 0.0890429 0.999763 0 -0.0217586 0.950846 0 0.309666 0.873811 0.0811058 0.479454 0.8383 0 0.545209 0.695952 0 0.718089 0.51811 0.0486729 0.853928 0.486397 0 0.873738 -0.258509 0 -0.966009 -0.258509 0 -0.966009 0 -1 0 0 -1 0 0.590646 0 0.806931 0.590646 0 0.806931 0 1 0 0 1 0 -0.744062 0 -0.66811 -0.744062 0 -0.66811 -0.451769 0 -0.892135 -0.451769 0 -0.892135 -0.969224 0 -0.246181 -0.969224 0 -0.246181 -0.934222 0 -0.356692 -0.934222 0 -0.356692 -0.789924 0 -0.613205 -0.789924 0 -0.613205 0 -1 0 0 -1 0 0.913564 0 0.406695 0.913564 0 0.406695 0 1 0 0 1 0 -0.941559 0 -0.336847 -0.941559 0 -0.336847 -0.802721 0 -0.596355 -0.802721 0 -0.596355 -0.728311 0 -0.685247 -0.728311 0 -0.685247 0 -1 0 0 -1 0 0.833797 0 0.552071 0.833797 0 0.552071 0 1 0 0 1 0 -0.991368 0 0.131109 -0.991368 0 0.131109 -0.96614 0 -0.25802 -0.96614 0 -0.25802 0 -1 0 0 -1 0 0.997196 0 0.0748301 0.997196 0 0.0748301 0.998511 0 0.054557 0.998511 0 0.054557 0 1 0 0 1 0 0 -1 0 0 -1 0 -0.812889 0 0.582419 -0.812889 0 0.582419 -0.800889 0 0.598812 -0.800889 0 0.598812 0 1 0 0 1 0 0.676284 0 -0.736641 0.676284 0 -0.736641 0.906605 0 -0.421981 0.906605 0 -0.421981 0 -1 0 0 -1 0 -0.406695 0 0.913564 -0.406695 0 0.913564 0 1 0 0 1 0 0.24618 0 -0.969224 0.24618 0 -0.969224 0.356697 0 -0.93422 0.356697 0 -0.93422 0.613201 0 -0.789927 0.613201 0 -0.789927 0 -1 0 0 -1 0 -0.552071 0 0.833797 -0.552071 0 0.833797 0 1 0 0 1 0 0.336852 0 -0.941558 0.336852 0 -0.941558 0.596351 0 -0.802724 0.596351 0 -0.802724 0.685248 0 -0.728309 0.685248 0 -0.728309 -0.0982117 0 -0.995166 -0.0982117 0 -0.995166 0.268669 0 -0.963232 0.268669 0 -0.963232 -0.300917 0 -0.95365 -0.300917 0 -0.95365 0 -1 0 0 -1 0 -0.0646945 0 0.997905 -0.0646945 0 0.997905 0 1 0 0 1 0 -0.528076 0.849119 0.0114927 -0.463073 0.849119 -0.254085 -0.273991 0.849119 -0.451581 0.0114933 0.84912 0.528076 -0.254085 0.84912 0.463073 -0.451581 0.84912 0.27399 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.528076 0.849119 -0.0114927 0.463073 0.84912 0.254085 0.27399 0.84912 0.451581 -0.0114919 0.849119 -0.528076 0.254086 0.849119 -0.463073 0.451581 0.849119 -0.273991 -0.0103769 0 -0.999946 -0.0103769 0 -0.999946 -0.0656696 0 -0.997841 -0.0103766 0.00392361 -0.999938 -0.0103768 0.00392472 -0.999938 0.0449634 0 -0.998989 0.640211 0 0.768199 0.472882 0.0570008 0.87928 0.466123 0 0.88472 0.466123 0 0.88472 0 1 0 0 1 0 0.392108 0 0.919919 0.392108 0 0.919919 -0.372933 0 0.927858 -0.372933 0 0.927858 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 -0.419138 0 0.907923 0.0420178 0 0.999117 0.0420178 0 0.999117 -0.419138 0 0.907923 -0.425943 0.0657716 0.902356 -0.624122 0 0.781327 -0.609438 0 0.792834 -0.609438 0 0.792834 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 -0.674773 0 0.738025 0.0769341 0 0.997036 0.0769341 0 0.997036 -0.329798 0 0.944052 -0.329798 0 0.944052 -0.674773 0 0.738025 -0.679973 0.0560794 0.731089 -0.811794 0 0.583944 0.259791 0 -0.965665 0.259791 0 -0.965665 0.205963 0 -0.97856 0.259788 0.00392483 -0.965658 0.259789 0.00392255 -0.965658 0.31279 0 -0.949822 0.409207 0 0.912441 0.349257 0.0184677 0.936845 0.341312 0 0.93995 0.341312 0 0.93995 0 1 0 0 1 0 0 1 0 0.129382 0 0.991595 0.129382 0 0.991595 0.486986 0 -0.87341 0.49016 0.280684 -0.825203 0.534012 0 -0.845477 0.462334 0 -0.886706 0.510686 0.00392518 -0.859759 0.510686 0.00392228 -0.859758 0.557444 0 -0.830215 -0.835703 0 0.549182 0.147843 0 0.989011 -0.0738183 0.062852 0.995289 -0.082468 0 0.996594 -0.939238 0 0.343265 -0.838695 0.062865 0.54096 -0.835703 0 0.549182 -0.51069 0 0.859765 -0.51069 0 0.859765 -0.082468 0 0.996594 0 1 0 0 1 0 0 1 0 -0.142955 0 0.989729 -0.142955 0 0.989729 -0.800739 0 0.599013 -0.800739 0 0.599013 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0.70457 0 -0.709634 0.69462 0.280687 -0.662358 0.742316 0 -0.67005 0.684448 0 -0.729061 0.723709 0.0039224 -0.690095 0.723708 0.00392471 -0.690095 0.760787 0 -0.649002 -0.95288 0 0.303347 -0.124442 0 0.992227 -0.339606 0.0628604 0.938465 -0.348288 0 0.937388 -0.997019 0 0.0771622 -0.953544 0.062856 0.294624 -0.95288 0 0.303347 -0.723715 0 0.690099 -0.723715 0 0.690099 -0.348288 0 0.937388 0 1 0 0 1 0 0 1 0 -0.404681 0 0.914458 -0.404681 0 0.914458 -0.93266 0 0.360757 -0.93266 0 0.360757 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0.8699 0 -0.493228 0.847565 0.280682 -0.45039 0.895566 0 -0.444928 0.855767 0 -0.517361 0.883057 0.00392212 -0.46925 0.883057 0.00392471 -0.46925 0.907674 0 -0.419677 -0.999387 0 0.0350128 -0.387513 0 0.921864 -0.580207 0.0628663 0.812039 -0.588277 0 0.808659 -0.980866 0 -0.194686 -0.997673 0.0628549 0.0264345 -0.999387 0 0.0350128 -0.883063 0 0.469254 -0.883063 0 0.469254 -0.588277 0 0.808659 0 1 0 0 1 0 0 1 0 -0.63638 0 0.771375 -0.63638 0 0.771375 -0.995405 0 0.095752 -0.995405 0 0.095752 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0.951142 0 0.308755 0.951142 0 0.308755 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 -0.994385 0 0.105826 -0.956829 0.280691 0.0754318 -0.998683 0 0.0512978 -0.991037 0 0.13359 -0.996899 0.00392207 0.0785902 -0.996899 0.00392525 0.0785908 -0.999728 0 0.023307 0.930598 0 0.366042 0.722717 0 -0.691144 0.855691 0.0628596 -0.513656 0.861745 0 -0.507341 0.822091 0 0.569356 0.925608 0.0628583 0.373227 0.930598 0 0.366042 0.996907 0 -0.0785918 0.996907 0 -0.0785918 0.861745 0 -0.507341 0 1 0 0 1 0 0 1 0 0.89102 0 -0.453963 0.89102 0 -0.453963 -0.981135 0.00392458 -0.193284 -0.968946 0 -0.247272 -0.986062 0 -0.16638 -0.990329 0 -0.138741 -0.981135 0.0039222 -0.193284 -0.9417 0.280689 -0.185515 -0.975489 0 -0.220046 0.797333 0 0.60354 0.882382 0 -0.470534 0.962542 0.0628613 -0.263746 0.966668 0 -0.256032 0.637991 0 0.770044 0.790589 0.06286 0.609113 0.797333 0 0.60354 0.981142 0 0.193287 0.981142 0 0.193287 0.966668 0 -0.256032 0 1 0 0 1 0 0 1 0 0.980456 0 -0.196739 0.980456 0 -0.196739 0.832571 0 0.553918 0.832571 0 0.553918 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 -0.892605 0.00392287 -0.450823 -0.866313 0 -0.499502 -0.904607 0 -0.426246 -0.916182 0 -0.400762 -0.892605 0.00392387 -0.450823 -0.856726 0.280693 -0.432703 -0.879948 0 -0.47507 0.604932 0 0.796277 0.976605 0 -0.215042 0.998006 0.0628669 0.00572461 0.999898 0 0.0142672 0.40659 0 0.913611 0.596935 0.0628568 0.799824 0.604932 0 0.796277 0.892611 0 0.450828 0.892611 0 0.450828 0.999898 0 0.0142672 0 1 0 0 1 0 0 1 0 0.997179 0 0.0750608 0.997179 0 0.0750608 0.652263 0 0.757993 0.652263 0 0.757993 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 -0.737879 0 -0.674933 -0.737879 0 -0.674933 -0.77408 0 -0.633088 -0.737874 0.00392344 -0.674927 -0.737874 0.0039239 -0.674927 -0.699413 0 -0.714718 0.998405 0 0.0564577 0.966269 0.0560709 0.251355 0.965609 0 0.259997 0.470721 0 0.882282 0.470721 0 0.882282 0.785316 0 0.619095 0.785316 0 0.619095 0.965609 0 0.259997 0 1 0 0 1 0 0 1 0 0.939942 0 0.341335 0.939942 0 0.341335 0.42356 0 0.905868 0.42356 0 0.905868 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0.217065 0 0.976157 0.217065 0 0.976157 0.143224 0.156597 0.977223 0.20873 0 0.977973 -0.528422 0 -0.848982 -0.528422 0 -0.848982 -0.574553 0 -0.818468 -0.528418 0.0039221 -0.848975 -0.528418 0.00392444 -0.848975 -0.480645 0 -0.876915 0.946162 0 0.323695 0.844012 0.0657823 0.532275 0.841262 0 0.540628 0.50129 0 0.86528 0.50129 0 0.86528 0.841262 0 0.540628 0 1 0 0 1 0 0.812999 0 0.582265 0.812999 0 0.582265 0.163451 0 0.986551 0.163451 0 0.986551 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 -0.12731 0 0.991863 0.0821213 0 0.996622 0.0821213 0 0.996622 0.0734969 0.0570016 0.995665 0 1 0 -0.22565 0 0.974209 0.110103 0 0.99392 0.110103 0 0.99392 -0.22565 0 0.974209 -0.233696 0.0467589 0.971185 -0.390197 0 0.920731 -0.279774 0 -0.960066 -0.279774 0 -0.960066 -0.332446 0 -0.943122 -0.279772 0.00392346 -0.960059 -0.279772 0.00392525 -0.960059 -0.22622 0 -0.974076 0.823725 0 0.56699 0.718834 0.0467549 0.693607 0.713672 0 0.70048 0.441072 0 0.897472 0.441072 0 0.897472 0.713672 0 0.70048 0 1 0 0 1 0 0 1 0 0.625753 0 0.780021 0.625753 0 0.780021 -0.108789 0 0.994065 -0.108789 0 0.994065 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + + + + + + + + + + + + + + +

2 0 0 0 1 0 2 1 1 1 4 1 4 2 1 2 3 2 4 3 3 3 1878 3 2659 4 2658 4 5 4 5 5 2658 5 6 5 5 6 6 6 7 6 7 7 6 7 8 7 8 8 6 8 9 8 8 9 9 9 1909 9 2661 10 2659 10 1848 10 1848 11 2659 11 5 11 1848 12 5 12 10 12 10 13 5 13 7 13 2661 14 1846 14 2662 14 2662 15 1846 15 1845 15 2662 16 1845 16 1844 16 1874 17 11 17 2676 17 2676 18 11 18 1878 18 12 19 776 19 739 19 17 20 14 20 13 20 13 21 14 21 2663 21 13 22 2663 22 739 22 739 23 2663 23 2664 23 739 24 2664 24 12 24 2670 25 2669 25 15 25 15 26 2669 26 2666 26 15 27 2666 27 17 27 17 28 2666 28 2665 28 17 29 2665 29 14 29 22 30 2670 30 20 30 20 31 2670 31 15 31 20 32 15 32 16 32 739 33 738 33 13 33 13 34 738 34 18 34 16 35 15 35 18 35 18 36 15 36 17 36 18 37 17 37 13 37 738 38 19 38 18 38 18 39 19 39 25 39 18 40 25 40 16 40 16 41 25 41 27 41 16 42 27 42 20 42 20 43 27 43 21 43 20 44 21 44 22 44 22 45 21 45 1889 45 19 46 28 46 23 46 19 47 23 47 25 47 1894 48 1889 48 33 48 33 49 1889 49 21 49 27 50 24 50 21 50 21 51 24 51 31 51 21 52 31 52 33 52 23 53 48 53 25 53 25 54 48 54 26 54 25 55 26 55 27 55 27 56 26 56 34 56 27 57 34 57 24 57 26 58 48 58 47 58 23 59 28 59 29 59 2033 60 2035 60 30 60 2034 61 2033 61 2600 61 2600 62 2033 62 30 62 2600 63 30 63 2597 63 32 64 565 64 564 64 24 65 42 65 31 65 31 66 42 66 32 66 31 67 32 67 33 67 33 68 32 68 564 68 33 69 564 69 1894 69 39 70 34 70 26 70 562 71 567 71 35 71 35 72 567 72 36 72 35 73 36 73 2035 73 2035 74 36 74 43 74 2035 75 43 75 30 75 30 76 43 76 45 76 30 77 45 77 2597 77 2597 78 45 78 38 78 2597 79 38 79 37 79 37 80 38 80 29 80 26 81 47 81 39 81 39 82 47 82 46 82 39 83 46 83 41 83 41 84 46 84 40 84 41 85 40 85 44 85 34 86 39 86 24 86 24 87 39 87 41 87 24 88 41 88 42 88 42 89 41 89 44 89 42 90 44 90 32 90 32 91 44 91 566 91 32 92 566 92 565 92 567 93 566 93 36 93 36 94 566 94 44 94 36 95 44 95 43 95 43 96 44 96 40 96 43 97 40 97 45 97 45 98 40 98 46 98 45 99 46 99 38 99 38 100 46 100 47 100 38 101 47 101 29 101 29 102 47 102 48 102 29 103 48 103 23 103 2015 104 2673 104 49 104 49 105 2673 105 50 105 49 106 50 106 65 106 65 107 50 107 60 107 60 108 50 108 2672 108 60 109 2672 109 62 109 62 110 2672 110 63 110 63 111 2672 111 51 111 63 112 51 112 64 112 64 113 51 113 52 113 52 114 51 114 2674 114 52 115 2674 115 535 115 2015 116 49 116 54 116 53 117 54 117 67 117 67 118 54 118 49 118 67 119 49 119 55 119 55 120 49 120 65 120 66 121 56 121 68 121 69 122 68 122 57 122 72 123 1752 123 1751 123 65 124 60 124 66 124 56 125 61 125 68 125 68 126 61 126 73 126 68 127 73 127 57 127 52 128 535 128 58 128 58 129 535 129 59 129 58 130 59 130 70 130 72 131 71 131 538 131 538 132 71 132 70 132 538 133 70 133 537 133 537 134 70 134 59 134 66 135 60 135 56 135 56 136 60 136 62 136 56 137 62 137 61 137 61 138 62 138 63 138 61 139 63 139 64 139 65 140 66 140 55 140 55 141 66 141 68 141 55 142 68 142 67 142 67 143 68 143 69 143 67 144 69 144 53 144 52 145 58 145 64 145 64 146 58 146 70 146 64 147 70 147 61 147 61 148 70 148 71 148 61 149 71 149 73 149 73 150 71 150 72 150 73 151 72 151 57 151 57 152 72 152 1751 152 57 153 1751 153 69 153 53 154 1082 154 54 154 54 155 1082 155 74 155 54 156 74 156 2015 156 74 157 1082 157 75 157 75 158 76 158 575 158 74 159 75 159 77 159 77 160 75 160 575 160 77 161 575 161 78 161 122 162 79 162 120 162 94 163 2605 163 1673 163 83 164 1622 164 80 164 80 165 1622 165 1621 165 80 166 1621 166 81 166 80 167 82 167 83 167 83 168 82 168 84 168 83 169 84 169 1614 169 1614 170 84 170 85 170 1614 171 85 171 86 171 86 172 85 172 92 172 1673 173 1672 173 94 173 94 174 1672 174 1613 174 94 175 1613 175 93 175 93 176 1613 176 87 176 93 177 87 177 92 177 92 178 87 178 1615 178 92 179 1615 179 86 179 81 180 114 180 80 180 80 181 114 181 115 181 80 182 115 182 82 182 82 183 115 183 88 183 82 184 88 184 84 184 84 185 88 185 89 185 84 186 89 186 85 186 85 187 89 187 90 187 85 188 90 188 92 188 92 189 90 189 91 189 92 190 91 190 93 190 93 191 91 191 117 191 93 192 117 192 94 192 94 193 117 193 118 193 94 194 118 194 2605 194 95 195 2062 195 96 195 110 196 99 196 102 196 95 197 96 197 102 197 102 198 96 198 2066 198 102 199 2066 199 110 199 2062 200 95 200 2064 200 2064 201 95 201 97 201 2064 202 97 202 98 202 98 203 97 203 104 203 98 204 104 204 2065 204 99 205 100 205 102 205 102 206 100 206 101 206 102 207 101 207 95 207 95 208 101 208 103 208 95 209 103 209 97 209 97 210 103 210 116 210 97 211 116 211 104 211 105 212 106 212 107 212 107 213 106 213 112 213 105 214 108 214 106 214 106 215 108 215 109 215 106 216 109 216 119 216 119 217 109 217 2071 217 119 218 2071 218 121 218 120 219 2639 219 118 219 118 220 2639 220 2638 220 118 221 2638 221 2605 221 110 222 111 222 99 222 99 223 111 223 2069 223 99 224 2069 224 112 224 112 225 2069 225 113 225 112 226 113 226 107 226 114 227 116 227 115 227 115 228 116 228 103 228 115 229 103 229 88 229 88 230 103 230 101 230 88 231 101 231 89 231 89 232 101 232 100 232 89 233 100 233 90 233 90 234 100 234 99 234 90 235 99 235 91 235 91 236 99 236 112 236 91 237 112 237 117 237 117 238 112 238 106 238 117 239 106 239 118 239 118 240 106 240 119 240 118 241 119 241 120 241 120 242 119 242 121 242 120 243 121 243 122 243 123 244 1040 244 124 244 125 245 134 245 126 245 126 246 134 246 133 246 1038 247 127 247 129 247 129 248 127 248 1047 248 129 249 1047 249 133 249 133 250 1047 250 128 250 133 251 128 251 126 251 129 252 131 252 130 252 1038 253 129 253 124 253 124 254 129 254 130 254 124 255 130 255 123 255 123 256 130 256 182 256 123 257 182 257 1051 257 131 258 129 258 132 258 132 259 129 259 133 259 132 260 133 260 138 260 138 261 133 261 134 261 138 262 134 262 135 262 1059 263 1063 263 154 263 169 264 136 264 163 264 137 265 132 265 138 265 139 266 168 266 1428 266 1428 267 168 267 140 267 1428 268 140 268 1430 268 1430 269 140 269 141 269 1430 270 141 270 142 270 163 271 136 271 143 271 143 272 136 272 144 272 143 273 144 273 178 273 178 274 144 274 172 274 178 275 172 275 145 275 145 276 172 276 141 276 145 277 141 277 177 277 177 278 141 278 140 278 177 279 140 279 175 279 175 280 140 280 168 280 175 281 168 281 174 281 146 282 147 282 149 282 149 283 147 283 1057 283 149 284 1057 284 155 284 155 285 1057 285 148 285 155 286 148 286 1060 286 146 287 149 287 150 287 150 288 149 288 152 288 150 289 152 289 151 289 151 290 152 290 1054 290 1054 291 152 291 158 291 1054 292 158 292 153 292 1059 293 154 293 1060 293 1060 294 154 294 179 294 1060 295 179 295 155 295 155 296 179 296 156 296 155 297 156 297 149 297 149 298 156 298 176 298 149 299 176 299 152 299 152 300 176 300 157 300 152 301 157 301 158 301 159 302 1065 302 160 302 160 303 1065 303 1064 303 160 304 1064 304 164 304 164 305 1064 305 1066 305 164 306 1066 306 1051 306 159 307 160 307 161 307 161 308 160 308 166 308 161 309 166 309 1061 309 132 310 137 310 131 310 131 311 137 311 162 311 131 312 162 312 130 312 138 313 169 313 137 313 137 314 169 314 163 314 137 315 163 315 162 315 162 316 163 316 181 316 162 317 181 317 130 317 130 318 181 318 182 318 1063 319 1062 319 154 319 154 320 1062 320 167 320 154 321 167 321 180 321 164 322 165 322 160 322 160 323 165 323 180 323 160 324 180 324 166 324 166 325 180 325 167 325 166 326 167 326 1061 326 139 327 1455 327 168 327 168 328 1455 328 186 328 168 329 186 329 174 329 138 330 135 330 169 330 169 331 135 331 170 331 169 332 170 332 136 332 136 333 170 333 1393 333 136 334 1393 334 144 334 144 335 1393 335 171 335 144 336 171 336 172 336 172 337 171 337 1496 337 172 338 1496 338 141 338 141 339 1496 339 173 339 141 340 173 340 142 340 174 341 157 341 175 341 175 342 157 342 176 342 175 343 176 343 177 343 177 344 176 344 156 344 177 345 156 345 145 345 145 346 156 346 179 346 145 347 179 347 178 347 178 348 179 348 154 348 178 349 154 349 143 349 143 350 154 350 180 350 143 351 180 351 163 351 163 352 180 352 165 352 163 353 165 353 181 353 181 354 165 354 164 354 181 355 164 355 182 355 182 356 164 356 1051 356 157 357 183 357 158 357 158 358 183 358 153 358 1048 359 183 359 1049 359 1049 360 183 360 157 360 1049 361 157 361 1050 361 1050 362 157 362 174 362 186 363 1455 363 184 363 1433 364 1036 364 184 364 184 365 1036 365 185 365 184 366 185 366 186 366 186 367 185 367 187 367 186 368 187 368 174 368 174 369 187 369 188 369 174 370 188 370 1050 370 189 371 1610 371 192 371 1608 372 190 372 200 372 968 373 967 373 195 373 197 374 971 374 970 374 971 375 191 375 972 375 972 376 191 376 196 376 972 377 196 377 983 377 963 378 189 378 193 378 193 379 189 379 192 379 193 380 192 380 1612 380 963 381 193 381 964 381 964 382 193 382 198 382 964 383 198 383 965 383 965 384 198 384 194 384 194 385 198 385 197 385 194 386 197 386 195 386 195 387 197 387 970 387 195 388 970 388 968 388 200 389 190 389 199 389 199 390 190 390 242 390 199 391 242 391 191 391 191 392 242 392 226 392 191 393 226 393 196 393 971 394 197 394 191 394 191 395 197 395 198 395 191 396 198 396 199 396 199 397 198 397 193 397 199 398 193 398 200 398 200 399 193 399 1612 399 200 400 1612 400 1608 400 201 401 202 401 213 401 190 402 1608 402 203 402 203 403 1608 403 1607 403 203 404 1607 404 210 404 210 405 1607 405 204 405 210 406 204 406 205 406 250 407 246 407 230 407 230 408 246 408 206 408 230 409 206 409 229 409 229 410 206 410 207 410 229 411 207 411 208 411 208 412 207 412 235 412 208 413 235 413 232 413 232 414 235 414 209 414 232 415 209 415 205 415 205 416 209 416 237 416 205 417 237 417 210 417 210 418 237 418 238 418 210 419 238 419 203 419 203 420 238 420 240 420 203 421 240 421 190 421 190 422 240 422 242 422 978 423 211 423 979 423 979 424 211 424 236 424 979 425 236 425 975 425 216 426 212 426 976 426 212 427 216 427 213 427 213 428 216 428 214 428 213 429 214 429 201 429 975 430 236 430 976 430 976 431 236 431 215 431 976 432 215 432 216 432 216 433 215 433 217 433 216 434 217 434 214 434 214 435 217 435 234 435 214 436 234 436 201 436 983 437 196 437 984 437 984 438 196 438 225 438 984 439 225 439 218 439 218 440 225 440 985 440 985 441 225 441 221 441 985 442 221 442 986 442 982 443 219 443 223 443 223 444 219 444 220 444 223 445 220 445 221 445 221 446 220 446 222 446 221 447 222 447 986 447 978 448 982 448 211 448 211 449 982 449 223 449 211 450 223 450 224 450 224 451 223 451 221 451 224 452 221 452 239 452 239 453 221 453 225 453 239 454 225 454 241 454 241 455 225 455 196 455 241 456 196 456 226 456 232 457 227 457 208 457 208 458 227 458 228 458 208 459 228 459 229 459 229 460 228 460 1604 460 229 461 1604 461 230 461 230 462 1604 462 1624 462 230 463 1624 463 250 463 204 464 231 464 205 464 205 465 231 465 1606 465 205 466 1606 466 232 466 232 467 1606 467 233 467 232 468 233 468 227 468 246 469 234 469 206 469 206 470 234 470 217 470 206 471 217 471 207 471 207 472 217 472 215 472 207 473 215 473 235 473 235 474 215 474 236 474 235 475 236 475 209 475 209 476 236 476 211 476 209 477 211 477 237 477 237 478 211 478 224 478 237 479 224 479 238 479 238 480 224 480 239 480 238 481 239 481 240 481 240 482 239 482 241 482 240 483 241 483 242 483 242 484 241 484 226 484 256 485 966 485 257 485 957 486 966 486 243 486 243 487 966 487 256 487 243 488 256 488 244 488 244 489 256 489 254 489 244 490 254 490 245 490 245 491 254 491 253 491 245 492 253 492 251 492 250 493 252 493 246 493 246 494 252 494 255 494 246 495 255 495 234 495 234 496 255 496 247 496 234 497 247 497 201 497 248 498 252 498 249 498 249 499 252 499 250 499 249 500 250 500 1624 500 954 501 251 501 248 501 248 502 251 502 253 502 248 503 253 503 252 503 252 504 253 504 254 504 252 505 254 505 255 505 255 506 254 506 256 506 255 507 256 507 247 507 247 508 256 508 257 508 247 509 257 509 201 509 201 510 257 510 202 510 1395 511 1419 511 289 511 2083 512 1035 512 312 512 312 513 1035 513 288 513 258 514 259 514 1019 514 1019 515 259 515 260 515 1395 516 289 516 1493 516 259 517 1493 517 260 517 260 518 1493 518 289 518 260 519 289 519 261 519 261 520 289 520 262 520 261 521 262 521 1021 521 1021 522 262 522 263 522 1021 523 263 523 1022 523 1022 524 263 524 288 524 1022 525 288 525 1016 525 1016 526 288 526 1035 526 1016 527 1035 527 1015 527 264 528 1423 528 319 528 2085 529 2086 529 280 529 265 530 262 530 289 530 273 531 266 531 267 531 267 532 266 532 296 532 267 533 296 533 268 533 307 534 308 534 269 534 269 535 308 535 309 535 269 536 309 536 295 536 295 537 309 537 270 537 295 538 270 538 294 538 294 539 270 539 271 539 294 540 271 540 268 540 268 541 271 541 272 541 268 542 272 542 267 542 267 543 272 543 310 543 267 544 310 544 273 544 2072 545 274 545 281 545 281 546 274 546 275 546 281 547 275 547 305 547 276 548 306 548 278 548 303 549 276 549 277 549 277 550 276 550 278 550 277 551 278 551 291 551 291 552 278 552 279 552 291 553 279 553 290 553 2086 554 2072 554 280 554 280 555 2072 555 281 555 280 556 281 556 304 556 304 557 301 557 280 557 280 558 301 558 315 558 280 559 315 559 2085 559 2085 560 315 560 2084 560 284 561 2080 561 2079 561 285 562 2082 562 286 562 283 563 293 563 2076 563 2082 564 285 564 282 564 2076 565 282 565 283 565 283 566 282 566 285 566 283 567 285 567 284 567 284 568 285 568 286 568 284 569 286 569 2080 569 262 570 265 570 263 570 263 571 265 571 287 571 263 572 287 572 288 572 312 573 288 573 311 573 311 574 288 574 287 574 311 575 287 575 310 575 310 576 287 576 265 576 310 577 265 577 273 577 273 578 265 578 289 578 273 579 289 579 1419 579 290 580 292 580 291 580 291 581 292 581 2078 581 291 582 2078 582 293 582 293 583 2078 583 2077 583 293 584 2077 584 2076 584 294 585 299 585 295 585 295 586 299 586 1420 586 295 587 1420 587 269 587 269 588 1420 588 1481 588 269 589 1481 589 307 589 307 590 1481 590 1480 590 307 591 1480 591 264 591 296 592 297 592 268 592 268 593 297 593 298 593 268 594 298 594 294 594 294 595 298 595 1421 595 294 596 1421 596 299 596 300 597 301 597 302 597 302 598 301 598 304 598 302 599 304 599 303 599 303 600 304 600 281 600 303 601 281 601 276 601 276 602 281 602 305 602 276 603 305 603 306 603 264 604 319 604 307 604 307 605 319 605 300 605 307 606 300 606 308 606 308 607 300 607 302 607 308 608 302 608 309 608 309 609 302 609 303 609 309 610 303 610 270 610 270 611 303 611 277 611 270 612 277 612 271 612 271 613 277 613 291 613 271 614 291 614 272 614 272 615 291 615 293 615 272 616 293 616 310 616 310 617 293 617 283 617 310 618 283 618 311 618 311 619 283 619 284 619 311 620 284 620 312 620 312 621 284 621 2079 621 312 622 2079 622 2083 622 1031 623 1034 623 313 623 314 624 316 624 1032 624 2084 625 315 625 313 625 313 626 315 626 301 626 313 627 301 627 1031 627 1031 628 301 628 314 628 1031 629 314 629 1023 629 1023 630 314 630 1032 630 316 631 314 631 318 631 318 632 314 632 317 632 318 633 317 633 1033 633 1033 634 317 634 1010 634 1010 635 317 635 1424 635 1010 636 1424 636 1503 636 301 637 300 637 314 637 314 638 300 638 319 638 314 639 319 639 317 639 317 640 319 640 1423 640 317 641 1423 641 1424 641 330 642 329 642 320 642 321 643 322 643 329 643 1009 644 322 644 367 644 367 645 322 645 321 645 367 646 321 646 368 646 323 647 332 647 324 647 324 648 332 648 992 648 324 649 992 649 1736 649 320 650 989 650 330 650 330 651 989 651 994 651 330 652 994 652 331 652 331 653 994 653 325 653 331 654 325 654 332 654 332 655 325 655 993 655 332 656 993 656 992 656 368 657 321 657 326 657 326 658 321 658 327 658 326 659 327 659 328 659 328 660 327 660 333 660 328 661 333 661 337 661 329 662 330 662 321 662 321 663 330 663 331 663 321 664 331 664 327 664 327 665 331 665 332 665 327 666 332 666 333 666 333 667 332 667 323 667 333 668 323 668 337 668 334 669 2090 669 2091 669 335 670 354 670 2087 670 2087 671 354 671 2093 671 352 672 2094 672 355 672 328 673 337 673 336 673 336 674 337 674 1626 674 336 675 1626 675 338 675 338 676 1626 676 1625 676 338 677 1625 677 371 677 349 678 339 678 1585 678 349 679 1585 679 340 679 370 680 341 680 342 680 342 681 341 681 343 681 342 682 343 682 344 682 344 683 343 683 340 683 344 684 340 684 1583 684 1583 685 340 685 1585 685 383 686 345 686 341 686 341 687 345 687 346 687 341 688 346 688 343 688 343 689 346 689 347 689 343 690 347 690 340 690 340 691 347 691 348 691 340 692 348 692 349 692 349 693 348 693 374 693 349 694 374 694 371 694 371 695 374 695 375 695 371 696 375 696 338 696 338 697 375 697 350 697 338 698 350 698 336 698 336 699 350 699 351 699 336 700 351 700 328 700 328 701 351 701 326 701 2094 702 352 702 2095 702 2095 703 352 703 353 703 2095 704 353 704 2092 704 2092 705 353 705 2091 705 2091 706 353 706 357 706 2091 707 357 707 334 707 2093 708 354 708 355 708 355 709 354 709 356 709 355 710 356 710 352 710 352 711 356 711 373 711 352 712 373 712 353 712 353 713 373 713 372 713 353 714 372 714 357 714 357 715 372 715 358 715 357 716 358 716 334 716 359 717 2088 717 365 717 365 718 2088 718 360 718 365 719 360 719 361 719 361 720 360 720 1009 720 361 721 1009 721 367 721 2087 722 362 722 335 722 335 723 362 723 363 723 335 724 363 724 364 724 364 725 363 725 359 725 359 726 365 726 364 726 364 727 365 727 361 727 364 728 361 728 366 728 366 729 361 729 367 729 366 730 367 730 368 730 1586 731 383 731 1588 731 1588 732 383 732 341 732 1588 733 341 733 369 733 369 734 341 734 370 734 1625 735 1592 735 371 735 371 736 1592 736 1591 736 371 737 1591 737 349 737 349 738 1591 738 1590 738 349 739 1590 739 339 739 345 740 358 740 346 740 346 741 358 741 372 741 346 742 372 742 347 742 347 743 372 743 373 743 347 744 373 744 348 744 348 745 373 745 356 745 348 746 356 746 374 746 374 747 356 747 354 747 374 748 354 748 375 748 375 749 354 749 335 749 375 750 335 750 350 750 350 751 335 751 364 751 350 752 364 752 351 752 351 753 364 753 366 753 351 754 366 754 326 754 326 755 366 755 368 755 376 756 358 756 345 756 381 757 1582 757 991 757 358 758 376 758 334 758 334 759 376 759 377 759 334 760 377 760 2090 760 991 761 990 761 381 761 381 762 990 762 1006 762 381 763 1006 763 378 763 378 764 1006 764 379 764 378 765 379 765 380 765 382 766 1582 766 384 766 384 767 1582 767 381 767 384 768 381 768 385 768 385 769 381 769 378 769 385 770 378 770 386 770 386 771 378 771 380 771 386 772 380 772 1005 772 1586 773 382 773 383 773 383 774 382 774 384 774 383 775 384 775 345 775 345 776 384 776 385 776 345 777 385 777 376 777 376 778 385 778 386 778 376 779 386 779 377 779 377 780 386 780 1005 780 377 781 1005 781 1004 781 407 782 548 782 405 782 437 783 476 783 456 783 1398 784 1397 784 419 784 1403 785 387 785 1404 785 1404 786 387 786 389 786 1404 787 389 787 388 787 388 788 389 788 433 788 388 789 433 789 390 789 390 790 433 790 392 790 400 791 1427 791 391 791 391 792 1427 792 1426 792 391 793 1426 793 392 793 392 794 1426 794 393 794 392 795 393 795 390 795 421 796 394 796 422 796 422 797 394 797 395 797 422 798 395 798 424 798 424 799 395 799 396 799 424 800 396 800 426 800 426 801 396 801 397 801 426 802 397 802 428 802 428 803 397 803 398 803 428 804 398 804 429 804 429 805 398 805 1401 805 429 806 1401 806 400 806 400 807 1401 807 399 807 400 808 399 808 1427 808 419 809 1397 809 420 809 420 810 1397 810 1516 810 420 811 1516 811 421 811 421 812 1516 812 401 812 421 813 401 813 394 813 402 814 1536 814 1557 814 403 815 1400 815 405 815 403 816 405 816 404 816 402 817 1557 817 405 817 405 818 1557 818 406 818 405 819 406 819 404 819 1400 820 1398 820 405 820 405 821 1398 821 419 821 405 822 419 822 407 822 408 823 1877 823 450 823 450 824 409 824 408 824 408 825 409 825 449 825 408 826 449 826 1873 826 1873 827 449 827 446 827 1873 828 446 828 411 828 411 829 446 829 410 829 411 830 410 830 1872 830 1872 831 410 831 444 831 1872 832 444 832 412 832 412 833 444 833 443 833 412 834 443 834 1871 834 1871 835 443 835 413 835 1871 836 413 836 414 836 414 837 413 837 442 837 414 838 442 838 415 838 415 839 442 839 416 839 415 840 416 840 1864 840 1864 841 416 841 440 841 1864 842 440 842 1863 842 417 843 407 843 418 843 418 844 407 844 419 844 418 845 419 845 448 845 448 846 419 846 420 846 448 847 420 847 447 847 447 848 420 848 421 848 447 849 421 849 445 849 445 850 421 850 422 850 445 851 422 851 423 851 423 852 422 852 424 852 423 853 424 853 425 853 425 854 424 854 426 854 425 855 426 855 427 855 427 856 426 856 428 856 427 857 428 857 441 857 441 858 428 858 429 858 441 859 429 859 430 859 430 860 429 860 400 860 430 861 400 861 431 861 431 862 400 862 391 862 431 863 391 863 439 863 439 864 391 864 392 864 439 865 392 865 432 865 432 866 392 866 433 866 432 867 433 867 438 867 438 868 433 868 389 868 438 869 389 869 434 869 434 870 389 870 387 870 434 871 387 871 435 871 435 872 387 872 1403 872 435 873 1403 873 436 873 435 874 437 874 434 874 434 875 437 875 456 875 434 876 456 876 438 876 438 877 456 877 454 877 438 878 454 878 432 878 432 879 454 879 453 879 432 880 453 880 439 880 439 881 453 881 452 881 439 882 452 882 431 882 431 883 452 883 440 883 431 884 440 884 430 884 430 885 440 885 416 885 430 886 416 886 441 886 441 887 416 887 442 887 441 888 442 888 427 888 427 889 442 889 413 889 427 890 413 890 425 890 425 891 413 891 443 891 425 892 443 892 423 892 423 893 443 893 444 893 423 894 444 894 445 894 445 895 444 895 410 895 445 896 410 896 447 896 447 897 410 897 446 897 447 898 446 898 448 898 448 899 446 899 449 899 448 900 449 900 418 900 418 901 449 901 409 901 418 902 409 902 417 902 417 903 409 903 450 903 1863 904 440 904 451 904 451 905 440 905 452 905 451 906 452 906 1862 906 1862 907 452 907 453 907 1862 908 453 908 455 908 455 909 453 909 454 909 455 910 454 910 457 910 457 911 454 911 456 911 457 912 456 912 458 912 458 913 456 913 476 913 458 914 476 914 1860 914 459 915 495 915 485 915 492 916 460 916 461 916 461 917 460 917 462 917 461 918 462 918 463 918 463 919 462 919 464 919 463 920 464 920 1921 920 1921 921 464 921 465 921 1921 922 465 922 466 922 466 923 465 923 467 923 466 924 467 924 468 924 468 925 467 925 487 925 468 926 487 926 1852 926 1852 927 487 927 485 927 1852 928 485 928 469 928 469 929 485 929 495 929 469 930 495 930 1858 930 435 931 436 931 1412 931 437 932 435 932 470 932 435 933 1412 933 470 933 470 934 1412 934 1409 934 470 935 1409 935 471 935 471 936 1409 936 472 936 471 937 472 937 477 937 477 938 472 938 473 938 477 939 473 939 478 939 478 940 473 940 474 940 478 941 474 941 479 941 479 942 474 942 475 942 479 943 475 943 481 943 475 944 1435 944 481 944 481 945 1435 945 1416 945 481 946 1416 946 483 946 483 947 1416 947 1415 947 476 948 437 948 491 948 491 949 437 949 470 949 491 950 470 950 490 950 490 951 470 951 471 951 490 952 471 952 489 952 489 953 471 953 477 953 489 954 477 954 488 954 488 955 477 955 478 955 488 956 478 956 486 956 486 957 478 957 479 957 486 958 479 958 480 958 480 959 479 959 481 959 480 960 481 960 482 960 482 961 481 961 483 961 482 962 483 962 484 962 484 963 483 963 1415 963 484 964 1415 964 1413 964 484 965 459 965 482 965 482 966 459 966 485 966 482 967 485 967 480 967 480 968 485 968 487 968 480 969 487 969 486 969 486 970 487 970 467 970 486 971 467 971 488 971 488 972 467 972 465 972 488 973 465 973 489 973 489 974 465 974 464 974 489 975 464 975 490 975 490 976 464 976 462 976 490 977 462 977 491 977 491 978 462 978 460 978 491 979 460 979 476 979 476 980 460 980 492 980 476 981 492 981 1860 981 484 982 1413 982 493 982 459 983 484 983 504 983 459 984 504 984 494 984 494 985 504 985 496 985 494 986 496 986 501 986 1858 987 495 987 1857 987 1857 988 495 988 503 988 1857 989 503 989 1908 989 1908 990 503 990 502 990 1908 991 502 991 1850 991 1850 992 502 992 500 992 1850 993 500 993 1849 993 1849 994 500 994 1756 994 496 995 497 995 501 995 501 996 497 996 510 996 501 997 510 997 498 997 498 998 510 998 509 998 498 999 509 999 499 999 499 1000 1756 1000 498 1000 498 1001 1756 1001 500 1001 498 1002 500 1002 501 1002 501 1003 500 1003 502 1003 501 1004 502 1004 494 1004 494 1005 502 1005 503 1005 494 1006 503 1006 459 1006 459 1007 503 1007 495 1007 484 1008 493 1008 504 1008 504 1009 493 1009 505 1009 504 1010 505 1010 496 1010 496 1011 505 1011 1439 1011 496 1012 1439 1012 497 1012 497 1013 1439 1013 506 1013 497 1014 506 1014 1436 1014 1456 1015 1570 1015 507 1015 507 1016 1570 1016 508 1016 507 1017 508 1017 1548 1017 512 1018 1847 1018 509 1018 509 1019 1847 1019 1755 1019 509 1020 1755 1020 499 1020 1436 1021 1456 1021 497 1021 497 1022 1456 1022 507 1022 497 1023 507 1023 510 1023 510 1024 507 1024 516 1024 510 1025 516 1025 509 1025 509 1026 516 1026 511 1026 509 1027 511 1027 512 1027 512 1028 511 1028 1843 1028 513 1029 532 1029 514 1029 1548 1030 524 1030 507 1030 507 1031 524 1031 515 1031 507 1032 515 1032 516 1032 516 1033 515 1033 518 1033 516 1034 518 1034 511 1034 517 1035 1843 1035 511 1035 1838 1036 1837 1036 518 1036 518 1037 1837 1037 1836 1037 518 1038 1836 1038 511 1038 511 1039 1836 1039 519 1039 511 1040 519 1040 517 1040 530 1041 1822 1041 531 1041 531 1042 1822 1042 1934 1042 531 1043 1934 1043 1758 1043 520 1044 526 1044 1757 1044 1757 1045 1835 1045 520 1045 520 1046 1835 1046 521 1046 520 1047 521 1047 1840 1047 1548 1048 522 1048 524 1048 524 1049 522 1049 1687 1049 524 1050 1687 1050 1686 1050 1686 1051 523 1051 524 1051 524 1052 523 1052 528 1052 524 1053 528 1053 515 1053 515 1054 528 1054 520 1054 515 1055 520 1055 518 1055 518 1056 520 1056 1840 1056 518 1057 1840 1057 1838 1057 513 1058 514 1058 1710 1058 1686 1059 1575 1059 523 1059 523 1060 1575 1060 525 1060 523 1061 525 1061 1652 1061 1758 1062 526 1062 531 1062 531 1063 526 1063 520 1063 531 1064 520 1064 527 1064 527 1065 520 1065 528 1065 527 1066 528 1066 514 1066 514 1067 528 1067 523 1067 514 1068 523 1068 1710 1068 1710 1069 523 1069 1652 1069 529 1070 530 1070 531 1070 536 1071 1813 1071 1826 1071 514 1072 532 1072 1315 1072 1826 1073 529 1073 536 1073 536 1074 529 1074 531 1074 536 1075 531 1075 539 1075 539 1076 531 1076 527 1076 539 1077 527 1077 540 1077 540 1078 527 1078 514 1078 540 1079 514 1079 533 1079 533 1080 514 1080 1315 1080 533 1081 1315 1081 534 1081 535 1082 1813 1082 59 1082 59 1083 1813 1083 536 1083 59 1084 536 1084 537 1084 537 1085 536 1085 539 1085 537 1086 539 1086 538 1086 538 1087 539 1087 540 1087 538 1088 540 1088 72 1088 1753 1089 1752 1089 72 1089 72 1090 540 1090 1753 1090 1753 1091 540 1091 533 1091 1753 1092 533 1092 534 1092 1802 1093 1805 1093 554 1093 541 1094 1536 1094 547 1094 450 1095 1877 1095 542 1095 450 1096 542 1096 417 1096 417 1097 542 1097 1774 1097 417 1098 1774 1098 543 1098 543 1099 1879 1099 559 1099 543 1100 559 1100 417 1100 417 1101 559 1101 544 1101 417 1102 544 1102 407 1102 547 1103 405 1103 545 1103 545 1104 405 1104 548 1104 541 1105 547 1105 1580 1105 555 1106 1580 1106 546 1106 546 1107 1580 1107 547 1107 546 1108 547 1108 558 1108 558 1109 547 1109 545 1109 558 1110 545 1110 544 1110 544 1111 545 1111 548 1111 544 1112 548 1112 407 1112 549 1113 556 1113 1576 1113 1576 1114 556 1114 560 1114 1576 1115 560 1115 1304 1115 556 1116 557 1116 560 1116 560 1117 557 1117 550 1117 560 1118 550 1118 570 1118 570 1119 550 1119 551 1119 570 1120 551 1120 554 1120 552 1121 553 1121 551 1121 551 1122 553 1122 1886 1122 551 1123 1886 1123 554 1123 554 1124 1886 1124 1884 1124 554 1125 1884 1125 1802 1125 1783 1126 1881 1126 551 1126 551 1127 1881 1127 1789 1127 551 1128 1789 1128 552 1128 549 1129 555 1129 556 1129 556 1130 555 1130 546 1130 556 1131 546 1131 557 1131 557 1132 546 1132 558 1132 557 1133 558 1133 550 1133 550 1134 558 1134 544 1134 550 1135 544 1135 551 1135 551 1136 544 1136 559 1136 551 1137 559 1137 1783 1137 1783 1138 559 1138 1879 1138 1302 1139 1304 1139 560 1139 561 1140 1303 1140 572 1140 563 1141 1890 1141 1894 1141 567 1142 562 1142 2037 1142 1894 1143 564 1143 563 1143 563 1144 564 1144 565 1144 563 1145 565 1145 566 1145 2037 1146 561 1146 567 1146 567 1147 561 1147 572 1147 567 1148 572 1148 566 1148 566 1149 572 1149 571 1149 566 1150 571 1150 563 1150 563 1151 571 1151 568 1151 563 1152 568 1152 1890 1152 1890 1153 568 1153 1800 1153 1302 1154 560 1154 569 1154 1805 1155 1800 1155 554 1155 554 1156 1800 1156 568 1156 554 1157 568 1157 570 1157 570 1158 568 1158 571 1158 570 1159 571 1159 560 1159 560 1160 571 1160 572 1160 560 1161 572 1161 569 1161 569 1162 572 1162 1303 1162 576 1163 2016 1163 578 1163 573 1164 574 1164 579 1164 575 1165 76 1165 1079 1165 579 1166 574 1166 1079 1166 1079 1167 574 1167 78 1167 1079 1168 78 1168 575 1168 611 1169 576 1169 577 1169 577 1170 576 1170 578 1170 577 1171 578 1171 620 1171 620 1172 578 1172 2017 1172 620 1173 2017 1173 579 1173 579 1174 2017 1174 580 1174 579 1175 580 1175 573 1175 695 1176 698 1176 602 1176 695 1177 602 1177 694 1177 602 1178 581 1178 582 1178 583 1179 584 1179 604 1179 583 1180 604 1180 585 1180 584 1181 583 1181 602 1181 602 1182 583 1182 585 1182 602 1183 585 1183 581 1183 581 1184 585 1184 604 1184 581 1185 604 1185 582 1185 604 1186 683 1186 586 1186 587 1187 655 1187 664 1187 587 1188 664 1188 2002 1188 643 1189 641 1189 639 1189 622 1190 588 1190 621 1190 589 1191 614 1191 590 1191 618 1192 592 1192 591 1192 616 1193 615 1193 618 1193 618 1194 615 1194 936 1194 592 1195 618 1195 949 1195 594 1196 932 1196 640 1196 640 1197 932 1197 935 1197 645 1198 593 1198 644 1198 644 1199 593 1199 594 1199 644 1200 594 1200 642 1200 642 1201 594 1201 640 1201 666 1202 595 1202 665 1202 595 1203 666 1203 929 1203 929 1204 666 1204 668 1204 929 1205 668 1205 596 1205 596 1206 668 1206 669 1206 596 1207 669 1207 670 1207 688 1208 598 1208 597 1208 597 1209 598 1209 687 1209 599 1210 600 1210 687 1210 687 1211 600 1211 927 1211 687 1212 927 1212 597 1212 698 1213 601 1213 602 1213 602 1214 601 1214 940 1214 602 1215 940 1215 584 1215 584 1216 940 1216 603 1216 584 1217 603 1217 604 1217 604 1218 603 1218 605 1218 604 1219 605 1219 685 1219 685 1220 605 1220 606 1220 685 1221 606 1221 599 1221 599 1222 606 1222 931 1222 599 1223 931 1223 600 1223 607 1224 608 1224 941 1224 941 1225 697 1225 607 1225 607 1226 697 1226 696 1226 607 1227 696 1227 702 1227 702 1228 696 1228 693 1228 702 1229 693 1229 703 1229 703 1230 693 1230 704 1230 704 1231 693 1231 692 1231 704 1232 692 1232 705 1232 1079 1233 609 1233 579 1233 579 1234 609 1234 610 1234 579 1235 610 1235 620 1235 949 1236 611 1236 592 1236 592 1237 611 1237 577 1237 592 1238 577 1238 591 1238 591 1239 577 1239 620 1239 634 1240 629 1240 612 1240 636 1241 933 1241 635 1241 635 1242 933 1242 613 1242 635 1243 613 1243 589 1243 589 1244 613 1244 939 1244 589 1245 939 1245 614 1245 614 1246 939 1246 615 1246 614 1247 615 1247 590 1247 590 1248 615 1248 616 1248 590 1249 616 1249 617 1249 617 1250 616 1250 618 1250 617 1251 618 1251 633 1251 633 1252 618 1252 591 1252 633 1253 591 1253 619 1253 619 1254 591 1254 620 1254 612 1255 629 1255 621 1255 621 1256 629 1256 630 1256 621 1257 630 1257 622 1257 622 1258 640 1258 588 1258 588 1259 640 1259 623 1259 588 1260 623 1260 621 1260 621 1261 623 1261 624 1261 621 1262 624 1262 612 1262 609 1263 625 1263 610 1263 610 1264 625 1264 626 1264 610 1265 626 1265 627 1265 627 1266 626 1266 628 1266 627 1267 628 1267 634 1267 634 1268 628 1268 1985 1268 634 1269 1985 1269 629 1269 629 1270 1985 1270 1988 1270 629 1271 1988 1271 630 1271 630 1272 1988 1272 631 1272 630 1273 631 1273 622 1273 622 1274 631 1274 632 1274 622 1275 632 1275 640 1275 620 1276 610 1276 619 1276 619 1277 610 1277 627 1277 619 1278 627 1278 633 1278 633 1279 627 1279 634 1279 633 1280 634 1280 617 1280 617 1281 634 1281 612 1281 617 1282 612 1282 590 1282 590 1283 612 1283 624 1283 590 1284 624 1284 589 1284 589 1285 624 1285 623 1285 589 1286 623 1286 635 1286 635 1287 623 1287 640 1287 635 1288 640 1288 636 1288 636 1289 640 1289 935 1289 636 1290 935 1290 933 1290 1993 1291 656 1291 637 1291 637 1292 656 1292 640 1292 1996 1293 638 1293 649 1293 649 1294 638 1294 662 1294 649 1295 662 1295 647 1295 656 1296 639 1296 640 1296 640 1297 639 1297 641 1297 640 1298 641 1298 642 1298 642 1299 641 1299 643 1299 642 1300 643 1300 644 1300 644 1301 643 1301 658 1301 644 1302 658 1302 645 1302 645 1303 658 1303 660 1303 661 1304 646 1304 662 1304 662 1305 646 1305 659 1305 662 1306 659 1306 647 1306 647 1307 659 1307 648 1307 647 1308 648 1308 649 1308 649 1309 648 1309 657 1309 649 1310 657 1310 1996 1310 1996 1311 657 1311 1994 1311 654 1312 655 1312 650 1312 650 1313 655 1313 587 1313 650 1314 587 1314 651 1314 651 1315 587 1315 2002 1315 651 1316 2006 1316 650 1316 650 1317 2006 1317 652 1317 650 1318 652 1318 654 1318 654 1319 652 1319 653 1319 654 1320 653 1320 655 1320 655 1321 653 1321 667 1321 655 1322 667 1322 664 1322 1993 1323 1994 1323 656 1323 656 1324 1994 1324 657 1324 656 1325 657 1325 639 1325 639 1326 657 1326 648 1326 639 1327 648 1327 643 1327 643 1328 648 1328 659 1328 643 1329 659 1329 658 1329 658 1330 659 1330 646 1330 658 1331 646 1331 660 1331 660 1332 646 1332 661 1332 660 1333 661 1333 947 1333 947 1334 661 1334 662 1334 947 1335 662 1335 946 1335 946 1336 662 1336 663 1336 946 1337 663 1337 665 1337 665 1338 663 1338 664 1338 665 1339 664 1339 666 1339 666 1340 664 1340 667 1340 666 1341 667 1341 668 1341 668 1342 667 1342 653 1342 668 1343 653 1343 669 1343 669 1344 653 1344 652 1344 669 1345 652 1345 670 1345 670 1346 652 1346 689 1346 670 1347 689 1347 596 1347 671 1348 652 1348 2008 1348 652 1349 671 1349 672 1349 672 1350 671 1350 675 1350 672 1351 675 1351 680 1351 2008 1352 673 1352 671 1352 671 1353 673 1353 674 1353 671 1354 674 1354 675 1354 675 1355 674 1355 682 1355 675 1356 682 1356 677 1356 680 1357 675 1357 676 1357 676 1358 675 1358 677 1358 676 1359 677 1359 678 1359 678 1360 684 1360 676 1360 676 1361 684 1361 679 1361 676 1362 679 1362 680 1362 680 1363 679 1363 686 1363 680 1364 686 1364 672 1364 672 1365 686 1365 681 1365 672 1366 681 1366 652 1366 682 1367 586 1367 677 1367 677 1368 586 1368 683 1368 677 1369 683 1369 678 1369 678 1370 683 1370 604 1370 678 1371 604 1371 684 1371 684 1372 604 1372 685 1372 684 1373 685 1373 679 1373 679 1374 685 1374 599 1374 679 1375 599 1375 686 1375 686 1376 599 1376 687 1376 686 1377 687 1377 681 1377 681 1378 687 1378 598 1378 681 1379 598 1379 652 1379 652 1380 598 1380 688 1380 652 1381 688 1381 689 1381 694 1382 602 1382 690 1382 690 1383 602 1383 2014 1383 690 1384 2014 1384 691 1384 700 1385 705 1385 691 1385 691 1386 705 1386 692 1386 691 1387 692 1387 690 1387 690 1388 692 1388 693 1388 690 1389 693 1389 694 1389 694 1390 693 1390 696 1390 694 1391 696 1391 695 1391 695 1392 696 1392 697 1392 695 1393 697 1393 698 1393 698 1394 697 1394 941 1394 698 1395 941 1395 601 1395 706 1396 699 1396 1117 1396 1117 1397 699 1397 705 1397 1117 1398 705 1398 700 1398 709 1399 608 1399 701 1399 701 1400 608 1400 607 1400 701 1401 607 1401 711 1401 607 1402 702 1402 711 1402 711 1403 702 1403 703 1403 711 1404 703 1404 699 1404 699 1405 703 1405 704 1405 699 1406 704 1406 705 1406 706 1407 2032 1407 707 1407 923 1408 709 1408 708 1408 708 1409 709 1409 701 1409 708 1410 701 1410 710 1410 710 1411 701 1411 711 1411 710 1412 711 1412 707 1412 707 1413 711 1413 699 1413 707 1414 699 1414 706 1414 725 1415 724 1415 729 1415 710 1416 707 1416 716 1416 716 1417 707 1417 2032 1417 713 1418 2040 1418 712 1418 729 1419 728 1419 713 1419 725 1420 729 1420 2039 1420 715 1421 714 1421 722 1421 722 1422 714 1422 2040 1422 722 1423 2040 1423 727 1423 2041 1424 714 1424 2042 1424 2042 1425 714 1425 715 1425 2042 1426 715 1426 716 1426 716 1427 715 1427 721 1427 716 1428 721 1428 710 1428 710 1429 721 1429 708 1429 717 1430 719 1430 718 1430 718 1431 719 1431 720 1431 718 1432 720 1432 732 1432 923 1433 708 1433 717 1433 717 1434 708 1434 721 1434 717 1435 721 1435 719 1435 719 1436 721 1436 715 1436 719 1437 715 1437 720 1437 720 1438 715 1438 722 1438 720 1439 722 1439 733 1439 733 1440 722 1440 727 1440 733 1441 727 1441 723 1441 2598 1442 724 1442 2599 1442 2599 1443 724 1443 725 1443 2599 1444 725 1444 726 1444 726 1445 725 1445 2039 1445 2040 1446 713 1446 727 1446 727 1447 713 1447 728 1447 727 1448 728 1448 723 1448 723 1449 728 1449 729 1449 723 1450 729 1450 730 1450 730 1451 729 1451 724 1451 730 1452 724 1452 731 1452 731 1453 724 1453 2598 1453 731 1454 2598 1454 735 1454 732 1455 720 1455 926 1455 926 1456 720 1456 733 1456 926 1457 733 1457 734 1457 734 1458 733 1458 723 1458 734 1459 723 1459 921 1459 921 1460 723 1460 730 1460 921 1461 730 1461 918 1461 918 1462 730 1462 731 1462 918 1463 731 1463 917 1463 917 1464 731 1464 735 1464 917 1465 735 1465 736 1465 746 1466 19 1466 738 1466 746 1467 738 1467 737 1467 737 1468 738 1468 739 1468 737 1469 739 1469 777 1469 777 1470 775 1470 753 1470 750 1471 749 1471 757 1471 753 1472 775 1472 755 1472 755 1473 775 1473 779 1473 755 1474 779 1474 751 1474 740 1475 742 1475 741 1475 741 1476 742 1476 743 1476 741 1477 743 1477 754 1477 754 1478 743 1478 744 1478 754 1479 744 1479 752 1479 752 1480 744 1480 920 1480 752 1481 920 1481 919 1481 777 1482 753 1482 737 1482 737 1483 753 1483 745 1483 737 1484 745 1484 746 1484 747 1485 757 1485 748 1485 748 1486 757 1486 749 1486 748 1487 749 1487 751 1487 751 1488 749 1488 750 1488 751 1489 750 1489 755 1489 742 1490 766 1490 743 1490 743 1491 766 1491 761 1491 743 1492 761 1492 744 1492 744 1493 761 1493 762 1493 744 1494 762 1494 920 1494 919 1495 745 1495 752 1495 752 1496 745 1496 753 1496 752 1497 753 1497 754 1497 754 1498 753 1498 755 1498 754 1499 755 1499 741 1499 741 1500 755 1500 750 1500 741 1501 750 1501 740 1501 740 1502 750 1502 757 1502 774 1503 924 1503 769 1503 756 1504 928 1504 922 1504 757 1505 747 1505 764 1505 758 1506 772 1506 759 1506 759 1507 772 1507 770 1507 759 1508 770 1508 942 1508 766 1509 742 1509 764 1509 764 1510 742 1510 740 1510 764 1511 740 1511 757 1511 765 1512 760 1512 761 1512 761 1513 760 1513 925 1513 761 1514 925 1514 762 1514 763 1515 953 1515 764 1515 764 1516 953 1516 765 1516 764 1517 765 1517 766 1517 766 1518 765 1518 761 1518 767 1519 768 1519 953 1519 953 1520 768 1520 771 1520 953 1521 771 1521 765 1521 765 1522 771 1522 774 1522 765 1523 774 1523 760 1523 760 1524 774 1524 769 1524 760 1525 769 1525 925 1525 773 1526 772 1526 922 1526 922 1527 772 1527 758 1527 922 1528 758 1528 756 1528 767 1529 942 1529 768 1529 768 1530 942 1530 770 1530 768 1531 770 1531 771 1531 771 1532 770 1532 772 1532 771 1533 772 1533 774 1533 774 1534 772 1534 773 1534 774 1535 773 1535 924 1535 775 1536 777 1536 778 1536 950 1537 778 1537 776 1537 776 1538 778 1538 777 1538 776 1539 777 1539 739 1539 952 1540 943 1540 747 1540 747 1541 748 1541 952 1541 952 1542 748 1542 751 1542 952 1543 751 1543 778 1543 778 1544 751 1544 779 1544 778 1545 779 1545 775 1545 2397 1546 792 1546 780 1546 780 1547 792 1547 781 1547 780 1548 781 1548 782 1548 782 1549 781 1549 2529 1549 782 1550 2529 1550 2399 1550 2399 1551 2529 1551 2528 1551 2399 1552 2528 1552 783 1552 783 1553 2528 1553 784 1553 783 1554 784 1554 785 1554 785 1555 784 1555 2526 1555 785 1556 2526 1556 786 1556 786 1557 2526 1557 787 1557 786 1558 787 1558 2390 1558 2390 1559 787 1559 2524 1559 2390 1560 2524 1560 2391 1560 2391 1561 2524 1561 788 1561 2391 1562 788 1562 789 1562 789 1563 788 1563 2533 1563 789 1564 2533 1564 2393 1564 2393 1565 2533 1565 2532 1565 2393 1566 2532 1566 790 1566 790 1567 2532 1567 791 1567 790 1568 791 1568 2397 1568 2397 1569 791 1569 792 1569 2379 1570 793 1570 2380 1570 2380 1571 793 1571 2521 1571 2380 1572 2521 1572 2381 1572 2381 1573 2521 1573 2519 1573 2381 1574 2519 1574 2382 1574 2382 1575 2519 1575 2517 1575 2382 1576 2517 1576 794 1576 794 1577 2517 1577 795 1577 794 1578 795 1578 2370 1578 2370 1579 795 1579 2515 1579 2370 1580 2515 1580 2371 1580 2371 1581 2515 1581 2513 1581 2371 1582 2513 1582 796 1582 796 1583 2513 1583 2512 1583 796 1584 2512 1584 2375 1584 2375 1585 2512 1585 797 1585 2375 1586 797 1586 798 1586 798 1587 797 1587 799 1587 798 1588 799 1588 2376 1588 2376 1589 799 1589 800 1589 2376 1590 800 1590 2377 1590 2377 1591 800 1591 2522 1591 2377 1592 2522 1592 2379 1592 2379 1593 2522 1593 793 1593 2343 1594 801 1594 2333 1594 2333 1595 801 1595 802 1595 2333 1596 802 1596 2335 1596 2335 1597 802 1597 2547 1597 2335 1598 2547 1598 2336 1598 2336 1599 2547 1599 804 1599 2336 1600 804 1600 803 1600 803 1601 804 1601 805 1601 803 1602 805 1602 806 1602 806 1603 805 1603 807 1603 806 1604 807 1604 2338 1604 2338 1605 807 1605 808 1605 2338 1606 808 1606 809 1606 809 1607 808 1607 2549 1607 809 1608 2549 1608 2340 1608 2340 1609 2549 1609 811 1609 2340 1610 811 1610 810 1610 810 1611 811 1611 812 1611 810 1612 812 1612 813 1612 813 1613 812 1613 814 1613 813 1614 814 1614 816 1614 816 1615 814 1615 815 1615 816 1616 815 1616 2343 1616 2343 1617 815 1617 801 1617 817 1618 2539 1618 2360 1618 2360 1619 2539 1619 818 1619 2360 1620 818 1620 819 1620 819 1621 818 1621 2537 1621 819 1622 2537 1622 820 1622 820 1623 2537 1623 2535 1623 820 1624 2535 1624 2351 1624 2351 1625 2535 1625 821 1625 2351 1626 821 1626 2352 1626 2352 1627 821 1627 822 1627 2352 1628 822 1628 823 1628 823 1629 822 1629 824 1629 823 1630 824 1630 825 1630 825 1631 824 1631 826 1631 825 1632 826 1632 2356 1632 2356 1633 826 1633 827 1633 2356 1634 827 1634 828 1634 828 1635 827 1635 2543 1635 828 1636 2543 1636 829 1636 829 1637 2543 1637 2541 1637 829 1638 2541 1638 830 1638 830 1639 2541 1639 2540 1639 830 1640 2540 1640 817 1640 817 1641 2540 1641 2539 1641 844 1642 2553 1642 831 1642 831 1643 2553 1643 832 1643 831 1644 832 1644 833 1644 833 1645 832 1645 834 1645 833 1646 834 1646 835 1646 835 1647 834 1647 836 1647 835 1648 836 1648 2299 1648 2299 1649 836 1649 837 1649 2299 1650 837 1650 2300 1650 2300 1651 837 1651 838 1651 2300 1652 838 1652 2301 1652 2301 1653 838 1653 2561 1653 2301 1654 2561 1654 2303 1654 2303 1655 2561 1655 2560 1655 2303 1656 2560 1656 839 1656 839 1657 2560 1657 2559 1657 839 1658 2559 1658 840 1658 840 1659 2559 1659 841 1659 840 1660 841 1660 842 1660 842 1661 841 1661 843 1661 842 1662 843 1662 2306 1662 2306 1663 843 1663 2555 1663 2306 1664 2555 1664 844 1664 844 1665 2555 1665 2553 1665 845 1666 2574 1666 2254 1666 2254 1667 2574 1667 846 1667 2254 1668 846 1668 847 1668 847 1669 846 1669 2572 1669 847 1670 2572 1670 2258 1670 2258 1671 2572 1671 848 1671 2258 1672 848 1672 849 1672 849 1673 848 1673 2571 1673 849 1674 2571 1674 850 1674 850 1675 2571 1675 851 1675 850 1676 851 1676 2261 1676 2261 1677 851 1677 852 1677 2261 1678 852 1678 853 1678 853 1679 852 1679 2579 1679 853 1680 2579 1680 2265 1680 2265 1681 2579 1681 854 1681 2265 1682 854 1682 2266 1682 2266 1683 854 1683 2578 1683 2266 1684 2578 1684 855 1684 855 1685 2578 1685 2576 1685 855 1686 2576 1686 2253 1686 2253 1687 2576 1687 856 1687 2253 1688 856 1688 845 1688 845 1689 856 1689 2574 1689 857 1690 2588 1690 858 1690 858 1691 2588 1691 2586 1691 858 1692 2586 1692 2282 1692 2282 1693 2586 1693 2584 1693 2282 1694 2584 1694 2284 1694 2284 1695 2584 1695 859 1695 2284 1696 859 1696 860 1696 860 1697 859 1697 2583 1697 860 1698 2583 1698 861 1698 861 1699 2583 1699 862 1699 861 1700 862 1700 2287 1700 2287 1701 862 1701 863 1701 2287 1702 863 1702 2288 1702 2288 1703 863 1703 864 1703 2288 1704 864 1704 2273 1704 2273 1705 864 1705 865 1705 2273 1706 865 1706 2275 1706 2275 1707 865 1707 866 1707 2275 1708 866 1708 2277 1708 2277 1709 866 1709 867 1709 2277 1710 867 1710 2279 1710 2279 1711 867 1711 868 1711 2279 1712 868 1712 857 1712 857 1713 868 1713 2588 1713 869 1714 2131 1714 870 1714 870 1715 2131 1715 871 1715 870 1716 871 1716 2415 1716 2415 1717 871 1717 2133 1717 2415 1718 2133 1718 2417 1718 2417 1719 2133 1719 2134 1719 2417 1720 2134 1720 872 1720 872 1721 2134 1721 2136 1721 872 1722 2136 1722 2419 1722 2419 1723 2136 1723 873 1723 2419 1724 873 1724 874 1724 874 1725 873 1725 2138 1725 874 1726 2138 1726 2420 1726 2420 1727 2138 1727 2139 1727 2420 1728 2139 1728 875 1728 875 1729 2139 1729 2140 1729 875 1730 2140 1730 2421 1730 2421 1731 2140 1731 876 1731 2421 1732 876 1732 877 1732 877 1733 876 1733 878 1733 877 1734 878 1734 879 1734 879 1735 878 1735 880 1735 879 1736 880 1736 869 1736 869 1737 880 1737 2131 1737 881 1738 2118 1738 2424 1738 2424 1739 2118 1739 882 1739 2424 1740 882 1740 2425 1740 2425 1741 882 1741 2120 1741 2425 1742 2120 1742 883 1742 883 1743 2120 1743 2122 1743 883 1744 2122 1744 2427 1744 2427 1745 2122 1745 2123 1745 2427 1746 2123 1746 884 1746 884 1747 2123 1747 2124 1747 884 1748 2124 1748 2429 1748 2429 1749 2124 1749 2126 1749 2429 1750 2126 1750 2432 1750 2432 1751 2126 1751 2127 1751 2432 1752 2127 1752 885 1752 885 1753 2127 1753 2128 1753 885 1754 2128 1754 2434 1754 2434 1755 2128 1755 886 1755 2434 1756 886 1756 887 1756 887 1757 886 1757 2129 1757 887 1758 2129 1758 888 1758 888 1759 2129 1759 889 1759 888 1760 889 1760 881 1760 881 1761 889 1761 2118 1761 2441 1762 890 1762 2443 1762 2443 1763 890 1763 2112 1763 2443 1764 2112 1764 891 1764 891 1765 2112 1765 2115 1765 891 1766 2115 1766 2445 1766 2445 1767 2115 1767 892 1767 2445 1768 892 1768 894 1768 894 1769 892 1769 893 1769 894 1770 893 1770 895 1770 895 1771 893 1771 2117 1771 895 1772 2117 1772 896 1772 896 1773 2117 1773 897 1773 896 1774 897 1774 898 1774 898 1775 897 1775 2107 1775 898 1776 2107 1776 899 1776 899 1777 2107 1777 2108 1777 899 1778 2108 1778 900 1778 900 1779 2108 1779 902 1779 900 1780 902 1780 901 1780 901 1781 902 1781 903 1781 901 1782 903 1782 904 1782 904 1783 903 1783 905 1783 904 1784 905 1784 2441 1784 2441 1785 905 1785 890 1785 916 1786 2096 1786 2449 1786 2449 1787 2096 1787 906 1787 2449 1788 906 1788 907 1788 907 1789 906 1789 909 1789 907 1790 909 1790 908 1790 908 1791 909 1791 2098 1791 908 1792 2098 1792 910 1792 910 1793 2098 1793 2099 1793 910 1794 2099 1794 2451 1794 2451 1795 2099 1795 2101 1795 2451 1796 2101 1796 2452 1796 2452 1797 2101 1797 911 1797 2452 1798 911 1798 2453 1798 2453 1799 911 1799 912 1799 2453 1800 912 1800 2455 1800 2455 1801 912 1801 2103 1801 2455 1802 2103 1802 913 1802 913 1803 2103 1803 2104 1803 913 1804 2104 1804 2457 1804 2457 1805 2104 1805 914 1805 2457 1806 914 1806 915 1806 915 1807 914 1807 2106 1807 915 1808 2106 1808 916 1808 916 1809 2106 1809 2096 1809 917 1810 736 1810 746 1810 746 1811 745 1811 917 1811 917 1812 745 1812 919 1812 917 1813 919 1813 918 1813 918 1814 919 1814 920 1814 918 1815 920 1815 921 1815 921 1816 920 1816 762 1816 921 1817 762 1817 734 1817 734 1818 762 1818 925 1818 928 1819 709 1819 922 1819 922 1820 709 1820 923 1820 922 1821 923 1821 773 1821 773 1822 923 1822 717 1822 773 1823 717 1823 924 1823 924 1824 717 1824 718 1824 924 1825 718 1825 769 1825 769 1826 718 1826 732 1826 769 1827 732 1827 925 1827 925 1828 732 1828 926 1828 925 1829 926 1829 734 1829 736 1830 28 1830 746 1830 746 1831 28 1831 19 1831 608 1832 709 1832 928 1832 688 1833 597 1833 927 1833 951 1834 949 1834 937 1834 937 1835 949 1835 618 1835 928 1836 931 1836 606 1836 600 1837 665 1837 927 1837 927 1838 665 1838 595 1838 927 1839 595 1839 929 1839 929 1840 596 1840 927 1840 927 1841 596 1841 689 1841 927 1842 689 1842 688 1842 611 1843 950 1843 576 1843 576 1844 950 1844 930 1844 576 1845 930 1845 2016 1845 948 1846 2411 1846 928 1846 606 1847 605 1847 928 1847 928 1848 605 1848 603 1848 928 1849 603 1849 940 1849 759 1850 942 1850 951 1850 759 1851 951 1851 758 1851 2411 1852 2401 1852 928 1852 928 1853 2401 1853 665 1853 928 1854 665 1854 931 1854 931 1855 665 1855 600 1855 593 1856 645 1856 2405 1856 2405 1857 645 1857 660 1857 2405 1858 660 1858 2403 1858 593 1859 2405 1859 594 1859 594 1860 2405 1860 934 1860 594 1861 934 1861 932 1861 938 1862 933 1862 934 1862 934 1863 933 1863 935 1863 934 1864 935 1864 932 1864 618 1865 936 1865 937 1865 937 1866 936 1866 615 1866 937 1867 615 1867 2408 1867 2408 1868 615 1868 939 1868 2408 1869 939 1869 938 1869 938 1870 939 1870 613 1870 938 1871 613 1871 933 1871 940 1872 601 1872 928 1872 928 1873 601 1873 941 1873 928 1874 941 1874 608 1874 942 1875 767 1875 951 1875 951 1876 767 1876 943 1876 951 1877 943 1877 952 1877 2401 1878 944 1878 665 1878 665 1879 944 1879 945 1879 665 1880 945 1880 946 1880 946 1881 945 1881 2403 1881 946 1882 2403 1882 947 1882 947 1883 2403 1883 660 1883 948 1884 928 1884 951 1884 951 1885 928 1885 756 1885 951 1886 756 1886 758 1886 611 1887 949 1887 950 1887 950 1888 949 1888 951 1888 950 1889 951 1889 778 1889 778 1890 951 1890 952 1890 943 1891 767 1891 953 1891 953 1892 763 1892 943 1892 943 1893 763 1893 764 1893 943 1894 764 1894 747 1894 251 1895 954 1895 956 1895 955 1896 2437 1896 956 1896 243 1897 244 1897 956 1897 956 1898 244 1898 245 1898 956 1899 245 1899 251 1899 243 1900 956 1900 957 1900 957 1901 956 1901 2437 1901 957 1902 2437 1902 958 1902 958 1903 2437 1903 959 1903 958 1904 959 1904 973 1904 973 1905 959 1905 2438 1905 973 1906 2438 1906 974 1906 974 1907 2438 1907 2439 1907 974 1908 2439 1908 977 1908 977 1909 2439 1909 2440 1909 977 1910 2440 1910 981 1910 981 1911 2440 1911 2442 1911 981 1912 2442 1912 980 1912 980 1913 2442 1913 960 1913 980 1914 960 1914 961 1914 961 1915 960 1915 962 1915 961 1916 962 1916 969 1916 969 1917 962 1917 2444 1917 969 1918 2444 1918 967 1918 967 1919 2444 1919 195 1919 195 1920 2444 1920 2446 1920 195 1921 2446 1921 194 1921 1610 1922 189 1922 956 1922 956 1923 189 1923 963 1923 956 1924 963 1924 964 1924 955 1925 956 1925 2436 1925 2436 1926 956 1926 964 1926 2436 1927 964 1927 2446 1927 2446 1928 964 1928 965 1928 2446 1929 965 1929 194 1929 202 1930 257 1930 958 1930 958 1931 257 1931 966 1931 958 1932 966 1932 957 1932 967 1933 968 1933 969 1933 969 1934 968 1934 970 1934 970 1935 971 1935 969 1935 969 1936 971 1936 972 1936 969 1937 972 1937 983 1937 202 1938 958 1938 973 1938 974 1939 212 1939 973 1939 973 1940 212 1940 213 1940 973 1941 213 1941 202 1941 977 1942 975 1942 974 1942 974 1943 975 1943 976 1943 974 1944 976 1944 212 1944 981 1945 978 1945 977 1945 977 1946 978 1946 979 1946 977 1947 979 1947 975 1947 980 1948 222 1948 981 1948 981 1949 222 1949 220 1949 220 1950 219 1950 981 1950 981 1951 219 1951 982 1951 981 1952 982 1952 978 1952 969 1953 983 1953 961 1953 961 1954 983 1954 984 1954 984 1955 218 1955 961 1955 961 1956 218 1956 985 1956 961 1957 985 1957 980 1957 980 1958 985 1958 986 1958 980 1959 986 1959 222 1959 2448 1960 987 1960 1008 1960 1008 1961 987 1961 320 1961 320 1962 987 1962 988 1962 320 1963 988 1963 989 1963 989 1964 988 1964 2450 1964 989 1965 2450 1965 994 1965 990 1966 991 1966 1581 1966 1736 1967 992 1967 1581 1967 1581 1968 992 1968 993 1968 1581 1969 993 1969 325 1969 994 1970 2450 1970 325 1970 325 1971 2450 1971 995 1971 325 1972 995 1972 1581 1972 1581 1973 995 1973 996 1973 1581 1974 996 1974 990 1974 1008 1975 2089 1975 2448 1975 2448 1976 2089 1976 997 1976 2448 1977 997 1977 2447 1977 2447 1978 997 1978 998 1978 2447 1979 998 1979 2458 1979 2458 1980 998 1980 999 1980 2458 1981 999 1981 2456 1981 2456 1982 999 1982 1000 1982 2456 1983 1000 1983 1001 1983 1001 1984 1000 1984 1002 1984 1001 1985 1002 1985 2454 1985 2454 1986 1002 1986 1007 1986 2454 1987 1007 1987 1003 1987 1003 1988 1007 1988 1004 1988 1003 1989 1004 1989 996 1989 996 1990 1004 1990 1005 1990 996 1991 1005 1991 380 1991 380 1992 379 1992 996 1992 996 1993 379 1993 1006 1993 996 1994 1006 1994 990 1994 1004 1995 1007 1995 377 1995 377 1996 1007 1996 2090 1996 320 1997 329 1997 1008 1997 1008 1998 329 1998 322 1998 1008 1999 322 1999 1009 1999 2414 2000 1014 2000 1012 2000 1022 2001 1016 2001 1020 2001 1010 2002 1503 2002 1020 2002 1011 2003 258 2003 1019 2003 1012 2004 1014 2004 1013 2004 1013 2005 1014 2005 2416 2005 1013 2006 2416 2006 1015 2006 1015 2007 2416 2007 2418 2007 1015 2008 2418 2008 1016 2008 1016 2009 2418 2009 1017 2009 1016 2010 1017 2010 1020 2010 1033 2011 1010 2011 1030 2011 1030 2012 1010 2012 1020 2012 1030 2013 1020 2013 1018 2013 1018 2014 1020 2014 1017 2014 1019 2015 260 2015 1011 2015 1011 2016 260 2016 261 2016 1011 2017 261 2017 1020 2017 1020 2018 261 2018 1021 2018 1020 2019 1021 2019 1022 2019 1023 2020 1032 2020 1030 2020 1012 2021 2081 2021 2414 2021 2414 2022 2081 2022 2075 2022 2414 2023 2075 2023 1024 2023 1024 2024 2075 2024 1025 2024 1024 2025 1025 2025 2413 2025 2413 2026 1025 2026 2074 2026 2413 2027 2074 2027 1026 2027 1026 2028 2074 2028 2073 2028 1026 2029 2073 2029 1027 2029 1027 2030 2073 2030 1028 2030 1027 2031 1028 2031 1029 2031 1029 2032 1028 2032 1034 2032 1029 2033 1034 2033 1030 2033 1030 2034 1034 2034 1031 2034 1030 2035 1031 2035 1023 2035 1032 2036 316 2036 1030 2036 1030 2037 316 2037 318 2037 1030 2038 318 2038 1033 2038 1034 2039 1028 2039 313 2039 313 2040 1028 2040 2084 2040 2083 2041 1013 2041 1035 2041 1035 2042 1013 2042 1015 2042 1036 2043 1433 2043 1037 2043 1036 2044 1037 2044 185 2044 125 2045 126 2045 1037 2045 1037 2046 126 2046 128 2046 1037 2047 128 2047 1047 2047 1038 2048 124 2048 1039 2048 1039 2049 124 2049 1040 2049 1039 2050 1040 2050 2431 2050 2431 2051 1040 2051 1052 2051 2431 2052 1052 2052 2430 2052 2430 2053 1052 2053 1041 2053 2430 2054 1041 2054 2428 2054 2428 2055 1041 2055 1042 2055 2428 2056 1042 2056 1043 2056 1043 2057 1042 2057 1044 2057 1043 2058 1044 2058 1045 2058 1045 2059 1044 2059 1058 2059 1045 2060 1058 2060 2426 2060 2426 2061 1058 2061 1055 2061 2426 2062 1055 2062 2423 2062 2435 2063 185 2063 1046 2063 1046 2064 185 2064 1037 2064 1046 2065 1037 2065 2433 2065 2433 2066 1037 2066 1047 2066 2433 2067 1047 2067 1039 2067 1039 2068 1047 2068 127 2068 1039 2069 127 2069 1038 2069 1055 2070 1056 2070 2423 2070 2423 2071 1056 2071 1053 2071 2423 2072 1053 2072 2422 2072 2422 2073 1053 2073 1048 2073 2422 2074 1048 2074 2435 2074 2435 2075 1048 2075 1049 2075 2435 2076 1049 2076 1050 2076 1050 2077 188 2077 2435 2077 2435 2078 188 2078 187 2078 2435 2079 187 2079 185 2079 1048 2080 1053 2080 183 2080 183 2081 1053 2081 153 2081 1051 2082 1052 2082 123 2082 123 2083 1052 2083 1040 2083 153 2084 1053 2084 1054 2084 1054 2085 1053 2085 1056 2085 147 2086 146 2086 1055 2086 1055 2087 146 2087 150 2087 1055 2088 150 2088 1056 2088 1056 2089 150 2089 151 2089 1056 2090 151 2090 1054 2090 147 2091 1055 2091 1057 2091 1057 2092 1055 2092 1058 2092 1057 2093 1058 2093 148 2093 1063 2094 1059 2094 1058 2094 1058 2095 1059 2095 1060 2095 1058 2096 1060 2096 148 2096 1042 2097 159 2097 1044 2097 1044 2098 159 2098 161 2098 161 2099 1061 2099 1044 2099 1044 2100 1061 2100 167 2100 1044 2101 167 2101 1058 2101 1058 2102 167 2102 1062 2102 1058 2103 1062 2103 1063 2103 1066 2104 1064 2104 1042 2104 1042 2105 1064 2105 1065 2105 1042 2106 1065 2106 159 2106 1042 2107 1041 2107 1066 2107 1066 2108 1041 2108 1052 2108 1066 2109 1052 2109 1051 2109 1067 2110 1068 2110 2652 2110 2652 2111 1068 2111 2068 2111 2652 2112 2068 2112 2654 2112 2654 2113 2068 2113 2067 2113 2654 2114 2067 2114 1069 2114 1069 2115 2067 2115 2063 2115 1069 2116 2063 2116 2655 2116 2655 2117 2063 2117 1070 2117 2655 2118 1070 2118 2644 2118 2644 2119 1070 2119 1071 2119 2644 2120 1071 2120 2645 2120 2645 2121 1071 2121 1072 2121 2645 2122 1072 2122 2646 2122 2646 2123 1072 2123 2057 2123 2646 2124 2057 2124 2647 2124 2647 2125 2057 2125 1073 2125 2647 2126 1073 2126 1075 2126 1075 2127 1073 2127 1074 2127 1075 2128 1074 2128 2648 2128 2648 2129 1074 2129 1077 2129 2648 2130 1077 2130 1076 2130 1076 2131 1077 2131 2070 2131 1076 2132 2070 2132 1067 2132 1067 2133 2070 2133 1068 2133 1341 2134 1078 2134 1229 2134 2007 2135 1102 2135 1107 2135 1084 2136 1079 2136 1080 2136 1080 2137 1079 2137 76 2137 1080 2138 76 2138 1081 2138 1081 2139 76 2139 75 2139 75 2140 1082 2140 1081 2140 1081 2141 1082 2141 1754 2141 1081 2142 1754 2142 1324 2142 1088 2143 1984 2143 1084 2143 1084 2144 1984 2144 1083 2144 1084 2145 1083 2145 1079 2145 1085 2146 1086 2146 1087 2146 1087 2147 1086 2147 1088 2147 1087 2148 1088 2148 1089 2148 1089 2149 1088 2149 1084 2149 1987 2150 1986 2150 1206 2150 1206 2151 1986 2151 1090 2151 1206 2152 1090 2152 1085 2152 1085 2153 1090 2153 1091 2153 1085 2154 1091 2154 1086 2154 1094 2155 1093 2155 1211 2155 1211 2156 1093 2156 1092 2156 1211 2157 1092 2157 1209 2157 1209 2158 1092 2158 1987 2158 1209 2159 1987 2159 1207 2159 1207 2160 1987 2160 1206 2160 1096 2161 1990 2161 1094 2161 1094 2162 1990 2162 1989 2162 1094 2163 1989 2163 1093 2163 1094 2164 1095 2164 1096 2164 1096 2165 1095 2165 1097 2165 1096 2166 1097 2166 1991 2166 1991 2167 1097 2167 1098 2167 1991 2168 1098 2168 1992 2168 1992 2169 1098 2169 1214 2169 1992 2170 1214 2170 1995 2170 1995 2171 1214 2171 1099 2171 1995 2172 1099 2172 1997 2172 1997 2173 1099 2173 1100 2173 1997 2174 1100 2174 1998 2174 1998 2175 1100 2175 1101 2175 1998 2176 1101 2176 1999 2176 1999 2177 1101 2177 1215 2177 1999 2178 1215 2178 2000 2178 2000 2179 1215 2179 1216 2179 2000 2180 1216 2180 2001 2180 2001 2181 1216 2181 1217 2181 2001 2182 1217 2182 2003 2182 2003 2183 1217 2183 2004 2183 2004 2184 1217 2184 1219 2184 2004 2185 1219 2185 2005 2185 2005 2186 1219 2186 1104 2186 2005 2187 1104 2187 1105 2187 1102 2188 2007 2188 1104 2188 1104 2189 2007 2189 1103 2189 1104 2190 1103 2190 1105 2190 1110 2191 1106 2191 1107 2191 1107 2192 1106 2192 2009 2192 1107 2193 2009 2193 2007 2193 1111 2194 1108 2194 1226 2194 1226 2195 1108 2195 1109 2195 1226 2196 1109 2196 1225 2196 1225 2197 1109 2197 1110 2197 1225 2198 1110 2198 1224 2198 1224 2199 1110 2199 1107 2199 1242 2200 2011 2200 1243 2200 1243 2201 2011 2201 2010 2201 1243 2202 2010 2202 1111 2202 1111 2203 2010 2203 1112 2203 1111 2204 1112 2204 1108 2204 2012 2205 1113 2205 1242 2205 1242 2206 1113 2206 1114 2206 1242 2207 1114 2207 2011 2207 2013 2208 1201 2208 1115 2208 1115 2209 1201 2209 1200 2209 1115 2210 1200 2210 1118 2210 1118 2211 1200 2211 1116 2211 706 2212 1117 2212 1116 2212 1116 2213 1117 2213 700 2213 1116 2214 700 2214 1118 2214 706 2215 1116 2215 2032 2215 2032 2216 1116 2216 1198 2216 2032 2217 1198 2217 2038 2217 2038 2218 1198 2218 1196 2218 2038 2219 1196 2219 1313 2219 1121 2220 1342 2220 1341 2220 1119 2221 1342 2221 1281 2221 1281 2222 1342 2222 1121 2222 1281 2223 1121 2223 1120 2223 1120 2224 1121 2224 1123 2224 1341 2225 1229 2225 1121 2225 1121 2226 1229 2226 1122 2226 1121 2227 1122 2227 1123 2227 1123 2228 1122 2228 1230 2228 1123 2229 1230 2229 1124 2229 1124 2230 1230 2230 1232 2230 1124 2231 1232 2231 1125 2231 1272 2232 1126 2232 1273 2232 1273 2233 1126 2233 1127 2233 1273 2234 1127 2234 1274 2234 1274 2235 1127 2235 1275 2235 1239 2236 1240 2236 1272 2236 1272 2237 1240 2237 1128 2237 1272 2238 1128 2238 1126 2238 1129 2239 1168 2239 1130 2239 1130 2240 1168 2240 1131 2240 1130 2241 1131 2241 1132 2241 1132 2242 1131 2242 1134 2242 1132 2243 1134 2243 1133 2243 1133 2244 1134 2244 1136 2244 1138 2245 1135 2245 1136 2245 1136 2246 1134 2246 1138 2246 1138 2247 1134 2247 1137 2247 1138 2248 1137 2248 1139 2248 1254 2249 1172 2249 1298 2249 1254 2250 1298 2250 1141 2250 1141 2251 1298 2251 1140 2251 1141 2252 1140 2252 1142 2252 1142 2253 1140 2253 1143 2253 1142 2254 1143 2254 1144 2254 1144 2255 1143 2255 1146 2255 1144 2256 1146 2256 1145 2256 1146 2257 1292 2257 1145 2257 1145 2258 1292 2258 1295 2258 1145 2259 1295 2259 1147 2259 1147 2260 1295 2260 1294 2260 1147 2261 1294 2261 1259 2261 1259 2262 1294 2262 1293 2262 1259 2263 1293 2263 1261 2263 1261 2264 1293 2264 1148 2264 1261 2265 1148 2265 1149 2265 1149 2266 1148 2266 1150 2266 1149 2267 1150 2267 1151 2267 1151 2268 1150 2268 1152 2268 1151 2269 1152 2269 1153 2269 1153 2270 1152 2270 1284 2270 1153 2271 1284 2271 1266 2271 1266 2272 1284 2272 1154 2272 1266 2273 1154 2273 1267 2273 1267 2274 1154 2274 1279 2274 1267 2275 1279 2275 1155 2275 1155 2276 1279 2276 1278 2276 1155 2277 1278 2277 1268 2277 1171 2278 1156 2278 1157 2278 1157 2279 1156 2279 1166 2279 1157 2280 1166 2280 1159 2280 1159 2281 1166 2281 1158 2281 1159 2282 1158 2282 1168 2282 1168 2283 1158 2283 1160 2283 1168 2284 1160 2284 1131 2284 1131 2285 1160 2285 1161 2285 1131 2286 1161 2286 1134 2286 1134 2287 1161 2287 1162 2287 1134 2288 1162 2288 1137 2288 1163 2289 1139 2289 1181 2289 1181 2290 1139 2290 1137 2290 1181 2291 1137 2291 1178 2291 1178 2292 1137 2292 1162 2292 1178 2293 1162 2293 1164 2293 1164 2294 1162 2294 1161 2294 1164 2295 1161 2295 1177 2295 1177 2296 1161 2296 1160 2296 1177 2297 1160 2297 1165 2297 1165 2298 1160 2298 1158 2298 1165 2299 1158 2299 1173 2299 1173 2300 1158 2300 1166 2300 1173 2301 1166 2301 1167 2301 1167 2302 1166 2302 1156 2302 1129 2303 1169 2303 1168 2303 1168 2304 1169 2304 1290 2304 1168 2305 1290 2305 1159 2305 1159 2306 1290 2306 1299 2306 1159 2307 1299 2307 1157 2307 1157 2308 1299 2308 1170 2308 1157 2309 1170 2309 1171 2309 1171 2310 1170 2310 1172 2310 1171 2311 1172 2311 1156 2311 1156 2312 1172 2312 1254 2312 1156 2313 1254 2313 1167 2313 1167 2314 1254 2314 1253 2314 1167 2315 1253 2315 1173 2315 1173 2316 1253 2316 1174 2316 1173 2317 1174 2317 1165 2317 1165 2318 1174 2318 1175 2318 1165 2319 1175 2319 1177 2319 1177 2320 1175 2320 1176 2320 1177 2321 1176 2321 1164 2321 1164 2322 1176 2322 1179 2322 1164 2323 1179 2323 1178 2323 1178 2324 1179 2324 1180 2324 1178 2325 1180 2325 1181 2325 1181 2326 1180 2326 1182 2326 1181 2327 1182 2327 1163 2327 1163 2328 1182 2328 1249 2328 1081 2329 1328 2329 1080 2329 1080 2330 1328 2330 1183 2330 1080 2331 1183 2331 1084 2331 1084 2332 1183 2332 1184 2332 1084 2333 1184 2333 1089 2333 1244 2334 1185 2334 1193 2334 1193 2335 1185 2335 1186 2335 1193 2336 1186 2336 1187 2336 1187 2337 1186 2337 1189 2337 1187 2338 1189 2338 1188 2338 1188 2339 1189 2339 1190 2339 1188 2340 1190 2340 1195 2340 1195 2341 1190 2341 1248 2341 1195 2342 1248 2342 1191 2342 1241 2343 1244 2343 1192 2343 1192 2344 1244 2344 1193 2344 1192 2345 1193 2345 1199 2345 1199 2346 1193 2346 1187 2346 1199 2347 1187 2347 1194 2347 1194 2348 1187 2348 1188 2348 1194 2349 1188 2349 1197 2349 1197 2350 1188 2350 1195 2350 1197 2351 1195 2351 1323 2351 1323 2352 1195 2352 1191 2352 1323 2353 1196 2353 1197 2353 1197 2354 1196 2354 1198 2354 1197 2355 1198 2355 1194 2355 1194 2356 1198 2356 1116 2356 1194 2357 1116 2357 1199 2357 1199 2358 1116 2358 1200 2358 1199 2359 1200 2359 1192 2359 1192 2360 1200 2360 1201 2360 1192 2361 1201 2361 1241 2361 1328 2362 1202 2362 1183 2362 1183 2363 1202 2363 1250 2363 1183 2364 1250 2364 1184 2364 1184 2365 1250 2365 1203 2365 1184 2366 1203 2366 1089 2366 1089 2367 1203 2367 1204 2367 1089 2368 1204 2368 1087 2368 1087 2369 1204 2369 1251 2369 1087 2370 1251 2370 1085 2370 1085 2371 1251 2371 1205 2371 1085 2372 1205 2372 1206 2372 1206 2373 1205 2373 1252 2373 1206 2374 1252 2374 1207 2374 1207 2375 1252 2375 1208 2375 1207 2376 1208 2376 1209 2376 1209 2377 1208 2377 1210 2377 1209 2378 1210 2378 1211 2378 1211 2379 1210 2379 1212 2379 1211 2380 1212 2380 1094 2380 1094 2381 1212 2381 1213 2381 1094 2382 1213 2382 1095 2382 1095 2383 1213 2383 1255 2383 1095 2384 1255 2384 1097 2384 1097 2385 1255 2385 1256 2385 1097 2386 1256 2386 1098 2386 1098 2387 1256 2387 1257 2387 1098 2388 1257 2388 1214 2388 1214 2389 1257 2389 1258 2389 1214 2390 1258 2390 1099 2390 1099 2391 1258 2391 1260 2391 1099 2392 1260 2392 1100 2392 1100 2393 1260 2393 1262 2393 1100 2394 1262 2394 1101 2394 1101 2395 1262 2395 1263 2395 1101 2396 1263 2396 1215 2396 1215 2397 1263 2397 1264 2397 1215 2398 1264 2398 1216 2398 1216 2399 1264 2399 1265 2399 1216 2400 1265 2400 1217 2400 1217 2401 1265 2401 1218 2401 1217 2402 1218 2402 1219 2402 1219 2403 1218 2403 1220 2403 1219 2404 1220 2404 1104 2404 1104 2405 1220 2405 1221 2405 1104 2406 1221 2406 1102 2406 1102 2407 1221 2407 1222 2407 1102 2408 1222 2408 1107 2408 1107 2409 1222 2409 1223 2409 1107 2410 1223 2410 1224 2410 1224 2411 1223 2411 1270 2411 1224 2412 1270 2412 1225 2412 1225 2413 1270 2413 1271 2413 1225 2414 1271 2414 1226 2414 1226 2415 1271 2415 1227 2415 1226 2416 1227 2416 1111 2416 1111 2417 1227 2417 1228 2417 1111 2418 1228 2418 1243 2418 1243 2419 1228 2419 1234 2419 1078 2420 1376 2420 1229 2420 1229 2421 1376 2421 1247 2421 1229 2422 1247 2422 1122 2422 1122 2423 1247 2423 1231 2423 1122 2424 1231 2424 1230 2424 1230 2425 1231 2425 1233 2425 1230 2426 1233 2426 1232 2426 1232 2427 1233 2427 1246 2427 1232 2428 1246 2428 1276 2428 1276 2429 1246 2429 1245 2429 1276 2430 1245 2430 1234 2430 1268 2431 1278 2431 1235 2431 1235 2432 1278 2432 1236 2432 1235 2433 1236 2433 1269 2433 1269 2434 1236 2434 1237 2434 1269 2435 1237 2435 1238 2435 1238 2436 1237 2436 1288 2436 1238 2437 1288 2437 1239 2437 1239 2438 1288 2438 1287 2438 1239 2439 1287 2439 1240 2439 2013 2440 2012 2440 1201 2440 1201 2441 2012 2441 1242 2441 1201 2442 1242 2442 1241 2442 1241 2443 1242 2443 1243 2443 1241 2444 1243 2444 1244 2444 1244 2445 1243 2445 1234 2445 1244 2446 1234 2446 1185 2446 1185 2447 1234 2447 1245 2447 1185 2448 1245 2448 1186 2448 1186 2449 1245 2449 1246 2449 1186 2450 1246 2450 1189 2450 1189 2451 1246 2451 1233 2451 1189 2452 1233 2452 1190 2452 1190 2453 1233 2453 1231 2453 1190 2454 1231 2454 1248 2454 1248 2455 1231 2455 1247 2455 1248 2456 1247 2456 1191 2456 1191 2457 1247 2457 1376 2457 1202 2458 1249 2458 1250 2458 1250 2459 1249 2459 1182 2459 1250 2460 1182 2460 1203 2460 1203 2461 1182 2461 1180 2461 1203 2462 1180 2462 1204 2462 1204 2463 1180 2463 1179 2463 1204 2464 1179 2464 1251 2464 1251 2465 1179 2465 1176 2465 1251 2466 1176 2466 1205 2466 1205 2467 1176 2467 1175 2467 1205 2468 1175 2468 1252 2468 1252 2469 1175 2469 1174 2469 1252 2470 1174 2470 1208 2470 1208 2471 1174 2471 1253 2471 1208 2472 1253 2472 1210 2472 1210 2473 1253 2473 1254 2473 1210 2474 1254 2474 1212 2474 1212 2475 1254 2475 1141 2475 1212 2476 1141 2476 1213 2476 1213 2477 1141 2477 1142 2477 1213 2478 1142 2478 1255 2478 1255 2479 1142 2479 1144 2479 1255 2480 1144 2480 1256 2480 1256 2481 1144 2481 1145 2481 1256 2482 1145 2482 1257 2482 1257 2483 1145 2483 1147 2483 1257 2484 1147 2484 1258 2484 1258 2485 1147 2485 1259 2485 1258 2486 1259 2486 1260 2486 1260 2487 1259 2487 1261 2487 1260 2488 1261 2488 1262 2488 1262 2489 1261 2489 1149 2489 1262 2490 1149 2490 1263 2490 1263 2491 1149 2491 1151 2491 1263 2492 1151 2492 1264 2492 1264 2493 1151 2493 1153 2493 1264 2494 1153 2494 1265 2494 1265 2495 1153 2495 1266 2495 1265 2496 1266 2496 1218 2496 1218 2497 1266 2497 1267 2497 1218 2498 1267 2498 1220 2498 1220 2499 1267 2499 1155 2499 1220 2500 1155 2500 1221 2500 1221 2501 1155 2501 1268 2501 1221 2502 1268 2502 1222 2502 1222 2503 1268 2503 1235 2503 1222 2504 1235 2504 1223 2504 1223 2505 1235 2505 1269 2505 1223 2506 1269 2506 1270 2506 1270 2507 1269 2507 1238 2507 1270 2508 1238 2508 1271 2508 1271 2509 1238 2509 1239 2509 1271 2510 1239 2510 1227 2510 1227 2511 1239 2511 1272 2511 1227 2512 1272 2512 1228 2512 1228 2513 1272 2513 1273 2513 1228 2514 1273 2514 1234 2514 1234 2515 1273 2515 1274 2515 1234 2516 1274 2516 1276 2516 1276 2517 1274 2517 1275 2517 1276 2518 1275 2518 1232 2518 1232 2519 1275 2519 1296 2519 1232 2520 1296 2520 1125 2520 1277 2521 1119 2521 1281 2521 1279 2522 1280 2522 1278 2522 1278 2523 1280 2523 1286 2523 1278 2524 1286 2524 1236 2524 1236 2525 1286 2525 1237 2525 1279 2526 1154 2526 1280 2526 1280 2527 1154 2527 1284 2527 1280 2528 1284 2528 1283 2528 1281 2529 1120 2529 1291 2529 1291 2530 1120 2530 1123 2530 1148 2531 1282 2531 1150 2531 1150 2532 1282 2532 1283 2532 1150 2533 1283 2533 1152 2533 1152 2534 1283 2534 1284 2534 2595 2535 1240 2535 1285 2535 1285 2536 1240 2536 1287 2536 1285 2537 1287 2537 1286 2537 1286 2538 1287 2538 1288 2538 1286 2539 1288 2539 1237 2539 1289 2540 1290 2540 1291 2540 1291 2541 1290 2541 1169 2541 1291 2542 1169 2542 1281 2542 1281 2543 1169 2543 1129 2543 1281 2544 1129 2544 1130 2544 1277 2545 1281 2545 1356 2545 1292 2546 1146 2546 2592 2546 2592 2547 1146 2547 1143 2547 1148 2548 1293 2548 1282 2548 1282 2549 1293 2549 1294 2549 1282 2550 1294 2550 2592 2550 2592 2551 1294 2551 1295 2551 2592 2552 1295 2552 1292 2552 1123 2553 1124 2553 1291 2553 1291 2554 1124 2554 1125 2554 1291 2555 1125 2555 1296 2555 1143 2556 1140 2556 2592 2556 2592 2557 1140 2557 1298 2557 2592 2558 1298 2558 1297 2558 1297 2559 1298 2559 1172 2559 1297 2560 1172 2560 2593 2560 2593 2561 1172 2561 1170 2561 2593 2562 1170 2562 1289 2562 1289 2563 1170 2563 1299 2563 1289 2564 1299 2564 1290 2564 1296 2565 1275 2565 1291 2565 1291 2566 1275 2566 1127 2566 1291 2567 1127 2567 1300 2567 1300 2568 1127 2568 1126 2568 1300 2569 1126 2569 2595 2569 2595 2570 1126 2570 1128 2570 2595 2571 1128 2571 1240 2571 1130 2572 1132 2572 1281 2572 1281 2573 1132 2573 1133 2573 1281 2574 1133 2574 1356 2574 1356 2575 1133 2575 1136 2575 1356 2576 1136 2576 1135 2576 1307 2577 1301 2577 1311 2577 1302 2578 569 2578 1301 2578 1301 2579 569 2579 1311 2579 1311 2580 569 2580 1303 2580 1311 2581 1303 2581 561 2581 1628 2582 1304 2582 1302 2582 1628 2583 1302 2583 1632 2583 1632 2584 1302 2584 1301 2584 1632 2585 1301 2585 1305 2585 1305 2586 1301 2586 1307 2586 1305 2587 1307 2587 1306 2587 1306 2588 1307 2588 1321 2588 1306 2589 1321 2589 1320 2589 1309 2590 1374 2590 1307 2590 1307 2591 1374 2591 1308 2591 1307 2592 1308 2592 1321 2592 1309 2593 1307 2593 1310 2593 1310 2594 1307 2594 1311 2594 1310 2595 1311 2595 1312 2595 1312 2596 1311 2596 561 2596 1312 2597 561 2597 1313 2597 1315 2598 532 2598 1669 2598 1324 2599 534 2599 1325 2599 1325 2600 534 2600 1314 2600 1315 2601 1669 2601 1316 2601 1316 2602 1669 2602 1668 2602 1316 2603 1668 2603 1319 2603 1319 2604 1668 2604 1317 2604 1319 2605 1317 2605 1318 2605 1318 2606 1339 2606 1319 2606 1319 2607 1339 2607 1329 2607 1319 2608 1329 2608 1390 2608 534 2609 1315 2609 1314 2609 1314 2610 1315 2610 1316 2610 1314 2611 1316 2611 1325 2611 1325 2612 1316 2612 1319 2612 1325 2613 1319 2613 1358 2613 1358 2614 1319 2614 1390 2614 1643 2615 1320 2615 1321 2615 1350 2616 1322 2616 1353 2616 1323 2617 1191 2617 1352 2617 1377 2618 1376 2618 1078 2618 1377 2619 1078 2619 1347 2619 1324 2620 1325 2620 1081 2620 1081 2621 1325 2621 1326 2621 1359 2622 1249 2622 1327 2622 1327 2623 1249 2623 1202 2623 1327 2624 1202 2624 1326 2624 1326 2625 1202 2625 1328 2625 1326 2626 1328 2626 1081 2626 1330 2627 1329 2627 1339 2627 1390 2628 1329 2628 1387 2628 1387 2629 1329 2629 1330 2629 1387 2630 1330 2630 1386 2630 1386 2631 1330 2631 1338 2631 1386 2632 1338 2632 1331 2632 1331 2633 1338 2633 1336 2633 1331 2634 1336 2634 1383 2634 1383 2635 1336 2635 1332 2635 1383 2636 1332 2636 1380 2636 1380 2637 1332 2637 1364 2637 1380 2638 1364 2638 1333 2638 1333 2639 1364 2639 1366 2639 1661 2640 1364 2640 1571 2640 1571 2641 1364 2641 1332 2641 1571 2642 1332 2642 1334 2642 1334 2643 1332 2643 1336 2643 1334 2644 1336 2644 1335 2644 1335 2645 1336 2645 1338 2645 1335 2646 1338 2646 1337 2646 1337 2647 1338 2647 1330 2647 1337 2648 1330 2648 1662 2648 1662 2649 1330 2649 1339 2649 1365 2650 1348 2650 1379 2650 1379 2651 1348 2651 1349 2651 1355 2652 1322 2652 1369 2652 1369 2653 1322 2653 1350 2653 1369 2654 1350 2654 1340 2654 1078 2655 1341 2655 1347 2655 1347 2656 1341 2656 1342 2656 1347 2657 1342 2657 1344 2657 1344 2658 1342 2658 1119 2658 1344 2659 1119 2659 1343 2659 1343 2660 1119 2660 1277 2660 1343 2661 1277 2661 1356 2661 1360 2662 1361 2662 1356 2662 1356 2663 1361 2663 1362 2663 1356 2664 1362 2664 1343 2664 1343 2665 1362 2665 1345 2665 1343 2666 1345 2666 1344 2666 1344 2667 1345 2667 1346 2667 1344 2668 1346 2668 1347 2668 1347 2669 1346 2669 1378 2669 1347 2670 1378 2670 1377 2670 1348 2671 1340 2671 1349 2671 1349 2672 1340 2672 1350 2672 1349 2673 1350 2673 1351 2673 1351 2674 1350 2674 1353 2674 1351 2675 1353 2675 1352 2675 1352 2676 1353 2676 1354 2676 1352 2677 1354 2677 1323 2677 1323 2678 1354 2678 1196 2678 1313 2679 1196 2679 1312 2679 1312 2680 1196 2680 1354 2680 1312 2681 1354 2681 1375 2681 1375 2682 1354 2682 1353 2682 1375 2683 1353 2683 1373 2683 1373 2684 1353 2684 1322 2684 1373 2685 1322 2685 1372 2685 1372 2686 1322 2686 1355 2686 1372 2687 1355 2687 1371 2687 1356 2688 1135 2688 1360 2688 1360 2689 1135 2689 1138 2689 1360 2690 1138 2690 1357 2690 1357 2691 1138 2691 1139 2691 1357 2692 1139 2692 1359 2692 1359 2693 1139 2693 1163 2693 1359 2694 1163 2694 1249 2694 1325 2695 1358 2695 1326 2695 1326 2696 1358 2696 1389 2696 1326 2697 1389 2697 1327 2697 1327 2698 1389 2698 1388 2698 1327 2699 1388 2699 1359 2699 1359 2700 1388 2700 1385 2700 1359 2701 1385 2701 1357 2701 1357 2702 1385 2702 1384 2702 1357 2703 1384 2703 1360 2703 1360 2704 1384 2704 1382 2704 1360 2705 1382 2705 1361 2705 1361 2706 1382 2706 1381 2706 1361 2707 1381 2707 1362 2707 1362 2708 1381 2708 1363 2708 1362 2709 1363 2709 1345 2709 1661 2710 1660 2710 1364 2710 1364 2711 1660 2711 1365 2711 1364 2712 1365 2712 1366 2712 1366 2713 1365 2713 1379 2713 1660 2714 1735 2714 1365 2714 1365 2715 1735 2715 1367 2715 1365 2716 1367 2716 1348 2716 1348 2717 1367 2717 1368 2717 1348 2718 1368 2718 1340 2718 1340 2719 1368 2719 1647 2719 1340 2720 1647 2720 1369 2720 1369 2721 1647 2721 1646 2721 1369 2722 1646 2722 1355 2722 1355 2723 1646 2723 1645 2723 1355 2724 1645 2724 1371 2724 1371 2725 1645 2725 1370 2725 1371 2726 1370 2726 1643 2726 1643 2727 1321 2727 1371 2727 1371 2728 1321 2728 1308 2728 1371 2729 1308 2729 1372 2729 1372 2730 1308 2730 1374 2730 1372 2731 1374 2731 1373 2731 1373 2732 1374 2732 1309 2732 1373 2733 1309 2733 1375 2733 1375 2734 1309 2734 1310 2734 1375 2735 1310 2735 1312 2735 1191 2736 1376 2736 1352 2736 1352 2737 1376 2737 1377 2737 1352 2738 1377 2738 1351 2738 1351 2739 1377 2739 1378 2739 1351 2740 1378 2740 1349 2740 1349 2741 1378 2741 1346 2741 1349 2742 1346 2742 1379 2742 1379 2743 1346 2743 1345 2743 1379 2744 1345 2744 1366 2744 1366 2745 1345 2745 1363 2745 1366 2746 1363 2746 1333 2746 1333 2747 1363 2747 1381 2747 1333 2748 1381 2748 1380 2748 1380 2749 1381 2749 1382 2749 1380 2750 1382 2750 1383 2750 1383 2751 1382 2751 1384 2751 1383 2752 1384 2752 1331 2752 1331 2753 1384 2753 1385 2753 1331 2754 1385 2754 1386 2754 1386 2755 1385 2755 1388 2755 1386 2756 1388 2756 1387 2756 1387 2757 1388 2757 1389 2757 1387 2758 1389 2758 1390 2758 1390 2759 1389 2759 1358 2759 1559 2760 1391 2760 1392 2760 1476 2761 1466 2761 1497 2761 171 2762 1393 2762 1394 2762 1420 2763 1483 2763 1481 2763 1493 2764 1418 2764 1395 2764 474 2765 473 2765 1407 2765 396 2766 395 2766 1523 2766 1522 2767 404 2767 1396 2767 1396 2768 404 2768 406 2768 1396 2769 406 2769 1556 2769 1397 2770 1398 2770 1399 2770 1399 2771 1398 2771 1400 2771 1399 2772 1400 2772 1522 2772 1522 2773 1400 2773 403 2773 1522 2774 403 2774 404 2774 1524 2775 397 2775 396 2775 1427 2776 399 2776 1425 2776 1425 2777 399 2777 1401 2777 1425 2778 1401 2778 1524 2778 1524 2779 1401 2779 398 2779 1524 2780 398 2780 397 2780 1411 2781 436 2781 1506 2781 1506 2782 436 2782 1403 2782 1506 2783 1403 2783 1402 2783 1402 2784 1403 2784 1404 2784 1402 2785 1404 2785 1504 2785 1504 2786 1404 2786 388 2786 1504 2787 388 2787 1405 2787 1405 2788 388 2788 390 2788 1405 2789 390 2789 1406 2789 1406 2790 390 2790 393 2790 1406 2791 393 2791 1426 2791 1407 2792 473 2792 1408 2792 1408 2793 473 2793 472 2793 1408 2794 472 2794 1410 2794 1410 2795 472 2795 1409 2795 1410 2796 1409 2796 1411 2796 1411 2797 1409 2797 1412 2797 1411 2798 1412 2798 436 2798 1435 2799 475 2799 1468 2799 1468 2800 475 2800 474 2800 1413 2801 1415 2801 1414 2801 1414 2802 1415 2802 1416 2802 1439 2803 505 2803 1451 2803 1446 2804 1436 2804 506 2804 296 2805 266 2805 1417 2805 1417 2806 266 2806 273 2806 1417 2807 273 2807 1418 2807 1418 2808 273 2808 1419 2808 1418 2809 1419 2809 1395 2809 1483 2810 1420 2810 1478 2810 1478 2811 1420 2811 299 2811 1478 2812 299 2812 1421 2812 1479 2813 298 2813 297 2813 264 2814 1502 2814 1423 2814 1423 2815 1502 2815 1422 2815 1423 2816 1422 2816 1424 2816 1424 2817 1422 2817 1503 2817 1020 2818 1406 2818 1425 2818 1425 2819 1406 2819 1426 2819 1425 2820 1426 2820 1427 2820 1468 2821 125 2821 1037 2821 1431 2822 173 2822 1496 2822 1431 2823 1496 2823 1497 2823 139 2824 1428 2824 1429 2824 1429 2825 1428 2825 1430 2825 1429 2826 1430 2826 1431 2826 1431 2827 1430 2827 142 2827 1431 2828 142 2828 173 2828 1450 2829 1432 2829 1455 2829 1455 2830 1432 2830 184 2830 184 2831 1432 2831 1433 2831 1433 2832 1432 2832 1434 2832 1433 2833 1434 2833 1037 2833 1037 2834 1434 2834 1414 2834 1037 2835 1414 2835 1468 2835 1468 2836 1414 2836 1416 2836 1468 2837 1416 2837 1435 2837 1456 2838 1436 2838 1437 2838 1437 2839 1436 2839 1446 2839 1437 2840 1446 2840 1438 2840 1438 2841 1446 2841 1444 2841 1438 2842 1444 2842 1459 2842 1459 2843 1444 2843 1460 2843 1439 2844 1451 2844 1440 2844 1440 2845 1451 2845 1452 2845 1440 2846 1452 2846 1445 2846 1431 2847 1441 2847 1429 2847 1429 2848 1441 2848 1442 2848 1429 2849 1442 2849 1453 2849 1453 2850 1442 2850 1460 2850 1453 2851 1460 2851 1443 2851 1443 2852 1460 2852 1444 2852 1443 2853 1444 2853 1445 2853 1445 2854 1444 2854 1446 2854 1445 2855 1446 2855 1440 2855 1440 2856 1446 2856 506 2856 1440 2857 506 2857 1439 2857 493 2858 1413 2858 1447 2858 1447 2859 1413 2859 1414 2859 1447 2860 1414 2860 1448 2860 1448 2861 1414 2861 1434 2861 1448 2862 1434 2862 1449 2862 1449 2863 1434 2863 1432 2863 1449 2864 1432 2864 1454 2864 1454 2865 1432 2865 1450 2865 505 2866 493 2866 1451 2866 1451 2867 493 2867 1447 2867 1451 2868 1447 2868 1452 2868 1452 2869 1447 2869 1448 2869 1452 2870 1448 2870 1445 2870 1445 2871 1448 2871 1449 2871 1445 2872 1449 2872 1443 2872 1443 2873 1449 2873 1454 2873 1443 2874 1454 2874 1453 2874 1453 2875 1454 2875 1450 2875 1453 2876 1450 2876 1429 2876 1429 2877 1450 2877 1455 2877 1429 2878 1455 2878 139 2878 1570 2879 1456 2879 1457 2879 1457 2880 1456 2880 1437 2880 1457 2881 1437 2881 1458 2881 1458 2882 1437 2882 1438 2882 1458 2883 1438 2883 1567 2883 1567 2884 1438 2884 1459 2884 1567 2885 1459 2885 1566 2885 1566 2886 1459 2886 1460 2886 1566 2887 1460 2887 1461 2887 1461 2888 1460 2888 1442 2888 1461 2889 1442 2889 1462 2889 1462 2890 1442 2890 1441 2890 1462 2891 1441 2891 1463 2891 1463 2892 1441 2892 1431 2892 1463 2893 1431 2893 1464 2893 1464 2894 1431 2894 1497 2894 1464 2895 1497 2895 1465 2895 1465 2896 1497 2896 1466 2896 1465 2897 1466 2897 1467 2897 474 2898 1407 2898 1468 2898 1468 2899 1407 2899 1511 2899 1468 2900 1511 2900 125 2900 170 2901 135 2901 1472 2901 1472 2902 135 2902 1469 2902 1472 2903 1469 2903 1471 2903 135 2904 134 2904 1469 2904 1469 2905 134 2905 1470 2905 1469 2906 1470 2906 1471 2906 1471 2907 1470 2907 1510 2907 1471 2908 1510 2908 1509 2908 1393 2909 170 2909 1394 2909 1394 2910 170 2910 1472 2910 1394 2911 1472 2911 1498 2911 1498 2912 1472 2912 1471 2912 1498 2913 1471 2913 1473 2913 1473 2914 1471 2914 1509 2914 1473 2915 1509 2915 1508 2915 1474 2916 1467 2916 1475 2916 1475 2917 1467 2917 1466 2917 1475 2918 1466 2918 1477 2918 1477 2919 1466 2919 1476 2919 1477 2920 1476 2920 1499 2920 1499 2921 1500 2921 1477 2921 1477 2922 1500 2922 1482 2922 1477 2923 1482 2923 1475 2923 1475 2924 1482 2924 1484 2924 1475 2925 1484 2925 1474 2925 1474 2926 1484 2926 1485 2926 1421 2927 298 2927 1478 2927 1478 2928 298 2928 1479 2928 1478 2929 1479 2929 1528 2929 264 2930 1480 2930 1502 2930 1502 2931 1480 2931 1481 2931 1502 2932 1481 2932 1500 2932 1500 2933 1481 2933 1483 2933 1500 2934 1483 2934 1482 2934 1482 2935 1483 2935 1478 2935 1482 2936 1478 2936 1484 2936 1484 2937 1478 2937 1528 2937 1484 2938 1528 2938 1485 2938 1486 2939 1487 2939 1512 2939 1486 2940 1512 2940 1391 2940 1556 2941 1558 2941 1520 2941 1521 2942 1559 2942 1491 2942 1513 2943 1512 2943 1527 2943 1527 2944 1512 2944 1487 2944 1527 2945 1487 2945 1488 2945 1488 2946 1487 2946 1486 2946 1488 2947 1486 2947 1489 2947 1559 2948 1392 2948 1491 2948 1491 2949 1392 2949 1490 2949 1491 2950 1490 2950 1514 2950 297 2951 296 2951 1479 2951 1479 2952 296 2952 1417 2952 1479 2953 1417 2953 1492 2953 1492 2954 1417 2954 1418 2954 1492 2955 1418 2955 1526 2955 1526 2956 1418 2956 1493 2956 1526 2957 1493 2957 1525 2957 1525 2958 1493 2958 259 2958 1525 2959 259 2959 1524 2959 1524 2960 259 2960 258 2960 1524 2961 258 2961 1425 2961 1425 2962 258 2962 1011 2962 1425 2963 1011 2963 1020 2963 1508 2964 1507 2964 1473 2964 1473 2965 1507 2965 1505 2965 1473 2966 1505 2966 1501 2966 1501 2967 1505 2967 1494 2967 1501 2968 1494 2968 1495 2968 1496 2969 171 2969 1497 2969 1497 2970 171 2970 1394 2970 1497 2971 1394 2971 1476 2971 1476 2972 1394 2972 1498 2972 1476 2973 1498 2973 1499 2973 1499 2974 1498 2974 1473 2974 1499 2975 1473 2975 1500 2975 1500 2976 1473 2976 1501 2976 1500 2977 1501 2977 1502 2977 1502 2978 1501 2978 1495 2978 1502 2979 1495 2979 1422 2979 1020 2980 1503 2980 1406 2980 1406 2981 1503 2981 1422 2981 1406 2982 1422 2982 1405 2982 1405 2983 1422 2983 1495 2983 1405 2984 1495 2984 1504 2984 1504 2985 1495 2985 1494 2985 1504 2986 1494 2986 1402 2986 1402 2987 1494 2987 1505 2987 1402 2988 1505 2988 1506 2988 1506 2989 1505 2989 1507 2989 1506 2990 1507 2990 1411 2990 1411 2991 1507 2991 1508 2991 1411 2992 1508 2992 1410 2992 1410 2993 1508 2993 1509 2993 1410 2994 1509 2994 1408 2994 1408 2995 1509 2995 1510 2995 1408 2996 1510 2996 1407 2996 1407 2997 1510 2997 1470 2997 1407 2998 1470 2998 1511 2998 1511 2999 1470 2999 134 2999 1511 3000 134 3000 125 3000 1391 3001 1512 3001 1392 3001 1392 3002 1512 3002 1513 3002 1392 3003 1513 3003 1490 3003 1490 3004 1513 3004 1531 3004 1490 3005 1531 3005 1514 3005 394 3006 401 3006 1515 3006 1515 3007 401 3007 1516 3007 1515 3008 1516 3008 1532 3008 1532 3009 1516 3009 1517 3009 1532 3010 1517 3010 1518 3010 1518 3011 1517 3011 1519 3011 1518 3012 1519 3012 1530 3012 1530 3013 1519 3013 1520 3013 1530 3014 1520 3014 1529 3014 1529 3015 1520 3015 1558 3015 1529 3016 1558 3016 1521 3016 1556 3017 1520 3017 1396 3017 1396 3018 1520 3018 1519 3018 1396 3019 1519 3019 1522 3019 1522 3020 1519 3020 1517 3020 1522 3021 1517 3021 1399 3021 1399 3022 1517 3022 1516 3022 1399 3023 1516 3023 1397 3023 396 3024 1523 3024 1524 3024 1524 3025 1523 3025 1533 3025 1524 3026 1533 3026 1525 3026 1525 3027 1533 3027 1531 3027 1525 3028 1531 3028 1526 3028 1526 3029 1531 3029 1513 3029 1526 3030 1513 3030 1492 3030 1492 3031 1513 3031 1527 3031 1492 3032 1527 3032 1479 3032 1479 3033 1527 3033 1488 3033 1479 3034 1488 3034 1528 3034 1528 3035 1488 3035 1489 3035 1528 3036 1489 3036 1485 3036 1521 3037 1491 3037 1529 3037 1529 3038 1491 3038 1514 3038 1529 3039 1514 3039 1530 3039 1530 3040 1514 3040 1531 3040 1530 3041 1531 3041 1518 3041 1518 3042 1531 3042 1533 3042 1518 3043 1533 3043 1532 3043 1532 3044 1533 3044 1523 3044 1532 3045 1523 3045 1515 3045 1515 3046 1523 3046 395 3046 1515 3047 395 3047 394 3047 1594 3048 1534 3048 1562 3048 1594 3049 1593 3049 1534 3049 1534 3050 1593 3050 1535 3050 1534 3051 1535 3051 1563 3051 1563 3052 1535 3052 1599 3052 1563 3053 1599 3053 1554 3053 1557 3054 1536 3054 1537 3054 1537 3055 1536 3055 1538 3055 1537 3056 1538 3056 1539 3056 1539 3057 1538 3057 1540 3057 1539 3058 1540 3058 1541 3058 1541 3059 1540 3059 1587 3059 1541 3060 1587 3060 1560 3060 1560 3061 1587 3061 1589 3061 1560 3062 1589 3062 1561 3062 1561 3063 1589 3063 1584 3063 1561 3064 1584 3064 1542 3064 1542 3065 1584 3065 1596 3065 1542 3066 1596 3066 1562 3066 1562 3067 1596 3067 1543 3067 1562 3068 1543 3068 1594 3068 1564 3069 1555 3069 1544 3069 1544 3070 1601 3070 1564 3070 1564 3071 1601 3071 1685 3071 1564 3072 1685 3072 1546 3072 1546 3073 1685 3073 1545 3073 1546 3074 1545 3074 1547 3074 1547 3075 1545 3075 1602 3075 1547 3076 1602 3076 1565 3076 1548 3077 508 3077 1549 3077 1549 3078 508 3078 1550 3078 1549 3079 1550 3079 1611 3079 1611 3080 1550 3080 1551 3080 1611 3081 1551 3081 1609 3081 1609 3082 1551 3082 1569 3082 1609 3083 1569 3083 1552 3083 1552 3084 1569 3084 1568 3084 1552 3085 1568 3085 1605 3085 1605 3086 1568 3086 1565 3086 1605 3087 1565 3087 1603 3087 1603 3088 1565 3088 1602 3088 1599 3089 1598 3089 1554 3089 1554 3090 1598 3090 1553 3090 1554 3091 1553 3091 1555 3091 1555 3092 1553 3092 1696 3092 1555 3093 1696 3093 1544 3093 406 3094 1557 3094 1556 3094 1556 3095 1557 3095 1537 3095 1556 3096 1537 3096 1558 3096 1558 3097 1537 3097 1539 3097 1558 3098 1539 3098 1521 3098 1521 3099 1539 3099 1541 3099 1521 3100 1541 3100 1559 3100 1559 3101 1541 3101 1560 3101 1559 3102 1560 3102 1391 3102 1391 3103 1560 3103 1561 3103 1391 3104 1561 3104 1486 3104 1486 3105 1561 3105 1542 3105 1486 3106 1542 3106 1489 3106 1489 3107 1542 3107 1562 3107 1489 3108 1562 3108 1485 3108 1485 3109 1562 3109 1534 3109 1485 3110 1534 3110 1474 3110 1474 3111 1534 3111 1563 3111 1474 3112 1563 3112 1467 3112 1467 3113 1563 3113 1554 3113 1467 3114 1554 3114 1465 3114 1465 3115 1554 3115 1555 3115 1465 3116 1555 3116 1464 3116 1464 3117 1555 3117 1564 3117 1464 3118 1564 3118 1463 3118 1463 3119 1564 3119 1546 3119 1463 3120 1546 3120 1462 3120 1462 3121 1546 3121 1547 3121 1462 3122 1547 3122 1461 3122 1461 3123 1547 3123 1565 3123 1461 3124 1565 3124 1566 3124 1566 3125 1565 3125 1568 3125 1566 3126 1568 3126 1567 3126 1567 3127 1568 3127 1569 3127 1567 3128 1569 3128 1458 3128 1458 3129 1569 3129 1551 3129 1458 3130 1551 3130 1457 3130 1457 3131 1551 3131 1550 3131 1457 3132 1550 3132 1570 3132 1570 3133 1550 3133 508 3133 1733 3134 1368 3134 1367 3134 1750 3135 1661 3135 1571 3135 1636 3136 1572 3136 1634 3136 1743 3137 1741 3137 1637 3137 1739 3138 1737 3138 1578 3138 324 3139 1709 3139 1708 3139 1584 3140 1573 3140 1595 3140 1677 3141 522 3141 1548 3141 1648 3142 1652 3142 1574 3142 1574 3143 1652 3143 525 3143 1574 3144 525 3144 1575 3144 1669 3145 532 3145 1667 3145 1667 3146 532 3146 513 3146 1631 3147 1577 3147 1576 3147 1576 3148 1577 3148 1578 3148 1576 3149 1578 3149 549 3149 549 3150 1578 3150 1737 3150 549 3151 1737 3151 555 3151 555 3152 1579 3152 1580 3152 1580 3153 1579 3153 1736 3153 1580 3154 1736 3154 541 3154 1736 3155 1581 3155 541 3155 541 3156 1581 3156 991 3156 541 3157 991 3157 1536 3157 1536 3158 991 3158 1538 3158 1538 3159 991 3159 1582 3159 1538 3160 1582 3160 1540 3160 342 3161 344 3161 1584 3161 1584 3162 344 3162 1583 3162 1584 3163 1583 3163 1585 3163 1582 3164 382 3164 1540 3164 1540 3165 382 3165 1586 3165 1540 3166 1586 3166 1587 3166 1587 3167 1586 3167 1588 3167 1587 3168 1588 3168 1589 3168 1589 3169 1588 3169 369 3169 1589 3170 369 3170 1584 3170 1584 3171 369 3171 370 3171 1584 3172 370 3172 342 3172 1585 3173 339 3173 1584 3173 1584 3174 339 3174 1590 3174 1584 3175 1590 3175 1573 3175 1573 3176 1590 3176 1591 3176 1591 3177 1592 3177 1573 3177 1573 3178 1592 3178 1625 3178 1573 3179 1625 3179 1706 3179 1593 3180 1594 3180 1600 3180 1600 3181 1594 3181 1543 3181 1600 3182 1543 3182 1595 3182 1595 3183 1543 3183 1596 3183 1595 3184 1596 3184 1584 3184 1553 3185 1598 3185 1597 3185 1597 3186 1598 3186 1599 3186 1597 3187 1599 3187 1600 3187 1600 3188 1599 3188 1535 3188 1600 3189 1535 3189 1593 3189 1685 3190 1601 3190 1695 3190 1695 3191 1601 3191 1544 3191 1695 3192 1544 3192 1696 3192 1684 3193 1602 3193 1545 3193 1602 3194 1684 3194 1603 3194 1603 3195 1684 3195 1682 3195 1603 3196 1682 3196 1605 3196 1624 3197 1604 3197 1682 3197 1604 3198 228 3198 1682 3198 1682 3199 228 3199 227 3199 1682 3200 227 3200 1605 3200 1605 3201 227 3201 233 3201 1605 3202 233 3202 1606 3202 1606 3203 231 3203 1605 3203 1605 3204 231 3204 204 3204 1605 3205 204 3205 1552 3205 204 3206 1607 3206 1552 3206 1552 3207 1607 3207 1608 3207 1552 3208 1608 3208 1609 3208 1609 3209 1608 3209 1612 3209 1609 3210 1612 3210 1611 3210 1548 3211 1549 3211 1610 3211 1610 3212 1549 3212 1611 3212 1610 3213 1611 3213 192 3213 192 3214 1611 3214 1612 3214 1613 3215 1672 3215 1597 3215 1600 3216 1614 3216 86 3216 1613 3217 1597 3217 87 3217 1600 3218 86 3218 1597 3218 1597 3219 86 3219 1615 3219 1597 3220 1615 3220 87 3220 1673 3221 1616 3221 1674 3221 1616 3222 2602 3222 1674 3222 1674 3223 2602 3223 1617 3223 1674 3224 1617 3224 1618 3224 1617 3225 2604 3225 1618 3225 1618 3226 2604 3226 1619 3226 1618 3227 1619 3227 1620 3227 1704 3228 1621 3228 1595 3228 1595 3229 1621 3229 1622 3229 1595 3230 1622 3230 1600 3230 1600 3231 1622 3231 83 3231 1600 3232 83 3232 1614 3232 1610 3233 956 3233 1548 3233 1548 3234 956 3234 954 3234 1548 3235 954 3235 1677 3235 1677 3236 954 3236 248 3236 1677 3237 248 3237 1623 3237 1623 3238 248 3238 249 3238 1623 3239 249 3239 1679 3239 1679 3240 249 3240 1624 3240 1679 3241 1624 3241 1681 3241 1681 3242 1624 3242 1682 3242 1625 3243 1626 3243 1706 3243 1706 3244 1626 3244 337 3244 1706 3245 337 3245 1708 3245 1708 3246 337 3246 323 3246 1708 3247 323 3247 324 3247 1741 3248 1739 3248 1629 3248 1744 3249 1743 3249 1627 3249 1743 3250 1637 3250 1627 3250 1627 3251 1637 3251 1638 3251 1627 3252 1638 3252 1640 3252 1320 3253 1639 3253 1306 3253 1306 3254 1639 3254 1633 3254 1306 3255 1633 3255 1305 3255 1576 3256 1304 3256 1631 3256 1631 3257 1304 3257 1628 3257 1631 3258 1628 3258 1632 3258 1739 3259 1578 3259 1629 3259 1629 3260 1578 3260 1577 3260 1629 3261 1577 3261 1630 3261 1630 3262 1577 3262 1631 3262 1630 3263 1631 3263 1633 3263 1633 3264 1631 3264 1632 3264 1633 3265 1632 3265 1305 3265 1744 3266 1635 3266 1634 3266 1634 3267 1635 3267 1729 3267 1634 3268 1729 3268 1636 3268 1636 3269 1729 3269 1731 3269 1741 3270 1629 3270 1637 3270 1637 3271 1629 3271 1630 3271 1637 3272 1630 3272 1638 3272 1638 3273 1630 3273 1633 3273 1638 3274 1633 3274 1640 3274 1640 3275 1633 3275 1639 3275 1640 3276 1639 3276 1730 3276 1730 3277 1639 3277 1641 3277 1730 3278 1641 3278 1644 3278 1642 3279 1572 3279 1746 3279 1746 3280 1572 3280 1636 3280 1746 3281 1636 3281 1747 3281 1747 3282 1636 3282 1731 3282 1747 3283 1731 3283 1748 3283 1320 3284 1643 3284 1639 3284 1639 3285 1643 3285 1370 3285 1639 3286 1370 3286 1641 3286 1641 3287 1370 3287 1645 3287 1641 3288 1645 3288 1644 3288 1644 3289 1645 3289 1646 3289 1644 3290 1646 3290 1733 3290 1733 3291 1646 3291 1647 3291 1733 3292 1647 3292 1368 3292 1648 3293 1574 3293 1654 3293 1654 3294 1574 3294 1697 3294 1654 3295 1697 3295 1651 3295 1718 3296 1716 3296 1702 3296 1702 3297 1716 3297 1659 3297 1702 3298 1659 3298 1701 3298 1701 3299 1659 3299 1649 3299 1701 3300 1649 3300 1700 3300 1700 3301 1649 3301 1657 3301 1700 3302 1657 3302 1650 3302 1650 3303 1657 3303 1651 3303 1650 3304 1651 3304 1698 3304 1698 3305 1651 3305 1697 3305 1710 3306 1652 3306 1653 3306 1653 3307 1652 3307 1648 3307 1653 3308 1648 3308 1712 3308 1712 3309 1648 3309 1654 3309 1712 3310 1654 3310 1655 3310 1655 3311 1654 3311 1651 3311 1655 3312 1651 3312 1656 3312 1656 3313 1651 3313 1657 3313 1656 3314 1657 3314 1658 3314 1658 3315 1657 3315 1649 3315 1658 3316 1649 3316 1713 3316 1713 3317 1649 3317 1659 3317 1713 3318 1659 3318 1714 3318 1714 3319 1659 3319 1716 3319 1734 3320 1735 3320 1660 3320 1731 3321 1732 3321 1748 3321 1748 3322 1732 3322 1734 3322 1748 3323 1734 3323 1750 3323 1750 3324 1734 3324 1660 3324 1750 3325 1660 3325 1661 3325 1662 3326 1663 3326 1337 3326 1337 3327 1663 3327 1671 3327 513 3328 1664 3328 1667 3328 1667 3329 1664 3329 1711 3329 1667 3330 1711 3330 1666 3330 1666 3331 1711 3331 1665 3331 1666 3332 1665 3332 1663 3332 1662 3333 1339 3333 1663 3333 1663 3334 1339 3334 1318 3334 1663 3335 1318 3335 1666 3335 1666 3336 1318 3336 1317 3336 1666 3337 1317 3337 1667 3337 1667 3338 1317 3338 1668 3338 1667 3339 1668 3339 1669 3339 1670 3340 1334 3340 1671 3340 1671 3341 1334 3341 1335 3341 1671 3342 1335 3342 1337 3342 1672 3343 1673 3343 1597 3343 1597 3344 1673 3344 1674 3344 1597 3345 1674 3345 1694 3345 1694 3346 1674 3346 1720 3346 1694 3347 1720 3347 1693 3347 1687 3348 522 3348 1675 3348 1675 3349 522 3349 1677 3349 1675 3350 1677 3350 1676 3350 1676 3351 1677 3351 1623 3351 1676 3352 1623 3352 1691 3352 1691 3353 1623 3353 1679 3353 1691 3354 1679 3354 1678 3354 1678 3355 1679 3355 1681 3355 1678 3356 1681 3356 1680 3356 1680 3357 1681 3357 1682 3357 1680 3358 1682 3358 1683 3358 1683 3359 1682 3359 1684 3359 1683 3360 1684 3360 1695 3360 1695 3361 1684 3361 1545 3361 1695 3362 1545 3362 1685 3362 1686 3363 1687 3363 1688 3363 1688 3364 1687 3364 1675 3364 1688 3365 1675 3365 1689 3365 1689 3366 1675 3366 1676 3366 1689 3367 1676 3367 1690 3367 1690 3368 1676 3368 1691 3368 1690 3369 1691 3369 1692 3369 1692 3370 1691 3370 1678 3370 1692 3371 1678 3371 1699 3371 1699 3372 1678 3372 1680 3372 1699 3373 1680 3373 1693 3373 1693 3374 1680 3374 1683 3374 1693 3375 1683 3375 1694 3375 1694 3376 1683 3376 1695 3376 1694 3377 1695 3377 1597 3377 1597 3378 1695 3378 1696 3378 1597 3379 1696 3379 1553 3379 1575 3380 1686 3380 1574 3380 1574 3381 1686 3381 1688 3381 1574 3382 1688 3382 1697 3382 1697 3383 1688 3383 1689 3383 1697 3384 1689 3384 1698 3384 1698 3385 1689 3385 1690 3385 1698 3386 1690 3386 1650 3386 1650 3387 1690 3387 1692 3387 1650 3388 1692 3388 1700 3388 1700 3389 1692 3389 1699 3389 1700 3390 1699 3390 1701 3390 1701 3391 1699 3391 1693 3391 1701 3392 1693 3392 1702 3392 1702 3393 1693 3393 1720 3393 1702 3394 1720 3394 1718 3394 1620 3395 1703 3395 1618 3395 1618 3396 1703 3396 1704 3396 1618 3397 1704 3397 1724 3397 1724 3398 1704 3398 1595 3398 1724 3399 1595 3399 1725 3399 1725 3400 1595 3400 1573 3400 1725 3401 1573 3401 1705 3401 1705 3402 1573 3402 1706 3402 1705 3403 1706 3403 1707 3403 1707 3404 1706 3404 1708 3404 1707 3405 1708 3405 1727 3405 1727 3406 1708 3406 1709 3406 1727 3407 1709 3407 1728 3407 513 3408 1710 3408 1664 3408 1664 3409 1710 3409 1653 3409 1664 3410 1653 3410 1711 3410 1711 3411 1653 3411 1712 3411 1711 3412 1712 3412 1665 3412 1665 3413 1712 3413 1655 3413 1665 3414 1655 3414 1663 3414 1663 3415 1655 3415 1656 3415 1663 3416 1656 3416 1671 3416 1671 3417 1656 3417 1658 3417 1671 3418 1658 3418 1670 3418 1670 3419 1658 3419 1713 3419 1670 3420 1713 3420 1749 3420 1749 3421 1713 3421 1714 3421 1749 3422 1714 3422 1715 3422 1715 3423 1714 3423 1716 3423 1715 3424 1716 3424 1717 3424 1717 3425 1716 3425 1718 3425 1717 3426 1718 3426 1719 3426 1719 3427 1718 3427 1720 3427 1719 3428 1720 3428 1745 3428 1745 3429 1720 3429 1674 3429 1745 3430 1674 3430 1721 3430 1721 3431 1674 3431 1618 3431 1721 3432 1618 3432 1722 3432 1722 3433 1618 3433 1724 3433 1722 3434 1724 3434 1723 3434 1723 3435 1724 3435 1725 3435 1723 3436 1725 3436 1742 3436 1742 3437 1725 3437 1705 3437 1742 3438 1705 3438 1740 3438 1740 3439 1705 3439 1707 3439 1740 3440 1707 3440 1738 3440 1738 3441 1707 3441 1727 3441 1738 3442 1727 3442 1726 3442 1726 3443 1727 3443 1728 3443 1744 3444 1627 3444 1635 3444 1635 3445 1627 3445 1640 3445 1635 3446 1640 3446 1729 3446 1729 3447 1640 3447 1730 3447 1729 3448 1730 3448 1731 3448 1731 3449 1730 3449 1644 3449 1731 3450 1644 3450 1732 3450 1732 3451 1644 3451 1733 3451 1732 3452 1733 3452 1734 3452 1734 3453 1733 3453 1367 3453 1734 3454 1367 3454 1735 3454 324 3455 1736 3455 1709 3455 1709 3456 1736 3456 1579 3456 1709 3457 1579 3457 1728 3457 1728 3458 1579 3458 555 3458 1728 3459 555 3459 1726 3459 1726 3460 555 3460 1737 3460 1726 3461 1737 3461 1738 3461 1738 3462 1737 3462 1739 3462 1738 3463 1739 3463 1740 3463 1740 3464 1739 3464 1741 3464 1740 3465 1741 3465 1742 3465 1742 3466 1741 3466 1743 3466 1742 3467 1743 3467 1723 3467 1723 3468 1743 3468 1744 3468 1723 3469 1744 3469 1722 3469 1722 3470 1744 3470 1634 3470 1722 3471 1634 3471 1721 3471 1721 3472 1634 3472 1572 3472 1721 3473 1572 3473 1745 3473 1745 3474 1572 3474 1642 3474 1745 3475 1642 3475 1719 3475 1719 3476 1642 3476 1746 3476 1719 3477 1746 3477 1717 3477 1717 3478 1746 3478 1747 3478 1717 3479 1747 3479 1715 3479 1715 3480 1747 3480 1748 3480 1715 3481 1748 3481 1749 3481 1749 3482 1748 3482 1750 3482 1749 3483 1750 3483 1670 3483 1670 3484 1750 3484 1571 3484 1670 3485 1571 3485 1334 3485 1082 3486 53 3486 69 3486 69 3487 1751 3487 1082 3487 1082 3488 1751 3488 1752 3488 1082 3489 1752 3489 1754 3489 1752 3490 1753 3490 1754 3490 1754 3491 1753 3491 534 3491 1754 3492 534 3492 1324 3492 1789 3493 1791 3493 552 3493 1879 3494 1880 3494 1783 3494 1774 3495 1777 3495 543 3495 458 3496 1860 3496 1861 3496 1755 3497 1756 3497 499 3497 1757 3498 1925 3498 1835 3498 1934 3499 1827 3499 1758 3499 2508 3500 1759 3500 1896 3500 1773 3501 1760 3501 1961 3501 2046 3502 2048 3502 1966 3502 1762 3503 1761 3503 2051 3503 2051 3504 1761 3504 1938 3504 2051 3505 1938 3505 2050 3505 2050 3506 1938 3506 2048 3506 1762 3507 1763 3507 1902 3507 1902 3508 1763 3508 2053 3508 1764 3509 2045 3509 1782 3509 2046 3510 1966 3510 2045 3510 2053 3511 2055 3511 1765 3511 1765 3512 2055 3512 1766 3512 1765 3513 1766 3513 1782 3513 1782 3514 1766 3514 1767 3514 1782 3515 1767 3515 1764 3515 1905 3516 1768 3516 1769 3516 1768 3517 1770 3517 1769 3517 1769 3518 1770 3518 1771 3518 1769 3519 1771 3519 1839 3519 1839 3520 1771 3520 2465 3520 2465 3521 2463 3521 1839 3521 1839 3522 2463 3522 2462 3522 1839 3523 2462 3523 1836 3523 1772 3524 2469 3524 1842 3524 1772 3525 1842 3525 2471 3525 2462 3526 2461 3526 1836 3526 1836 3527 2461 3527 2460 3527 1836 3528 2460 3528 519 3528 1773 3529 1961 3529 1779 3529 2505 3530 2503 3530 542 3530 542 3531 2503 3531 1774 3531 1774 3532 2503 3532 1775 3532 1774 3533 1775 3533 1777 3533 1777 3534 1775 3534 1776 3534 1777 3535 1776 3535 1784 3535 1784 3536 1776 3536 1778 3536 1784 3537 1778 3537 1779 3537 2508 3538 1898 3538 1780 3538 1780 3539 1898 3539 1765 3539 1780 3540 1765 3540 1781 3540 1781 3541 1765 3541 1782 3541 1781 3542 1782 3542 1760 3542 1783 3543 1880 3543 1881 3543 1784 3544 1786 3544 2246 3544 1779 3545 1961 3545 1784 3545 1784 3546 1961 3546 1785 3546 1784 3547 1785 3547 1786 3547 1951 3548 1787 3548 1962 3548 1787 3549 2242 3549 1962 3549 1962 3550 2242 3550 2243 3550 1962 3551 2243 3551 1961 3551 1961 3552 2243 3552 1788 3552 1961 3553 1788 3553 1785 3553 1881 3554 1883 3554 1789 3554 1789 3555 1883 3555 1790 3555 1789 3556 1790 3556 1791 3556 1791 3557 1790 3557 1792 3557 1791 3558 1792 3558 1793 3558 1793 3559 1792 3559 1951 3559 1793 3560 1951 3560 1922 3560 553 3561 1924 3561 2203 3561 2203 3562 2205 3562 553 3562 553 3563 2205 3563 1794 3563 553 3564 1794 3564 1886 3564 1886 3565 1794 3565 2193 3565 1795 3566 1796 3566 1954 3566 1954 3567 1796 3567 2198 3567 1954 3568 2198 3568 1953 3568 1953 3569 2198 3569 1797 3569 1953 3570 1797 3570 1923 3570 1923 3571 1797 3571 1798 3571 1923 3572 1798 3572 1924 3572 1924 3573 1798 3573 2201 3573 1924 3574 2201 3574 2203 3574 10288 3575 2194 3575 2196 3575 2169 3576 1800 3576 2183 3576 2183 3577 1800 3577 1805 3577 2169 3578 1799 3578 1800 3578 1800 3579 1799 3579 2172 3579 1800 3580 2172 3580 10300 3580 10300 3581 2172 3581 1801 3581 2177 3582 2179 3582 1885 3582 1885 3583 2179 3583 1803 3583 1885 3584 1803 3584 1802 3584 1802 3585 1803 3585 1804 3585 1802 3586 1804 3586 1805 3586 1805 3587 1804 3587 1806 3587 1805 3588 1806 3588 2183 3588 2177 3589 1931 3589 2175 3589 2175 3590 1931 3590 1942 3590 2175 3591 1942 3591 2173 3591 2173 3592 1942 3592 1801 3592 2675 3593 1807 3593 2158 3593 2158 3594 1808 3594 2675 3594 2675 3595 1808 3595 1809 3595 2675 3596 1809 3596 2674 3596 2674 3597 1809 3597 1810 3597 2674 3598 1810 3598 535 3598 1810 3599 1811 3599 535 3599 535 3600 1811 3600 2162 3600 535 3601 2162 3601 1813 3601 1813 3602 2162 3602 1812 3602 1813 3603 1812 3603 1826 3603 1812 3604 2164 3604 1826 3604 1826 3605 2164 3605 1815 3605 1826 3606 1815 3606 1814 3606 1815 3607 1816 3607 1814 3607 1814 3608 1816 3608 1817 3608 1814 3609 1817 3609 1807 3609 1807 3610 1817 3610 1818 3610 1807 3611 1818 3611 2158 3611 1933 3612 1819 3612 1982 3612 1819 3613 2191 3613 1982 3613 1982 3614 2191 3614 2184 3614 1982 3615 2184 3615 1814 3615 529 3616 1820 3616 530 3616 530 3617 1820 3617 1821 3617 530 3618 1821 3618 1822 3618 1822 3619 1821 3619 2188 3619 1822 3620 2188 3620 1932 3620 2184 3621 1823 3621 1814 3621 1814 3622 1823 3622 1824 3622 1814 3623 1824 3623 1826 3623 1826 3624 1824 3624 1825 3624 1826 3625 1825 3625 529 3625 529 3626 1825 3626 2187 3626 529 3627 2187 3627 1820 3627 1827 3628 1829 3628 2221 3628 2218 3629 1828 3629 1829 3629 1829 3630 1828 3630 2220 3630 1829 3631 2220 3631 2221 3631 2221 3632 2207 3632 1827 3632 1827 3633 2207 3633 1830 3633 1827 3634 1830 3634 1758 3634 1758 3635 1830 3635 2209 3635 526 3636 1831 3636 1832 3636 2209 3637 1833 3637 1758 3637 1758 3638 1833 3638 2212 3638 1758 3639 2212 3639 526 3639 526 3640 2212 3640 2213 3640 526 3641 2213 3641 1831 3641 2233 3642 1834 3642 1914 3642 1841 3643 2230 3643 1915 3643 1915 3644 2230 3644 2231 3644 1915 3645 2231 3645 2233 3645 1834 3646 2236 3646 1914 3646 1914 3647 2236 3647 2237 3647 1914 3648 2237 3648 1925 3648 2228 3649 1840 3649 2227 3649 2227 3650 1840 3650 521 3650 2227 3651 521 3651 2226 3651 2226 3652 521 3652 1835 3652 2226 3653 1835 3653 2225 3653 2225 3654 1835 3654 1925 3654 2225 3655 1925 3655 2224 3655 2224 3656 1925 3656 2237 3656 1836 3657 1837 3657 1839 3657 1839 3658 1837 3658 1838 3658 1839 3659 1838 3659 1915 3659 1915 3660 1838 3660 1840 3660 1915 3661 1840 3661 1841 3661 1841 3662 1840 3662 2228 3662 1844 3663 1842 3663 2660 3663 2660 3664 1842 3664 1911 3664 2660 3665 1911 3665 2661 3665 2460 3666 2471 3666 519 3666 519 3667 2471 3667 1842 3667 519 3668 1842 3668 517 3668 517 3669 1842 3669 1844 3669 517 3670 1844 3670 1843 3670 1843 3671 1844 3671 512 3671 1844 3672 1845 3672 512 3672 512 3673 1845 3673 1846 3673 512 3674 1846 3674 1847 3674 1847 3675 1846 3675 2661 3675 1847 3676 2661 3676 1755 3676 1755 3677 2661 3677 1848 3677 1755 3678 1848 3678 1756 3678 1756 3679 1848 3679 10 3679 1756 3680 10 3680 1849 3680 1849 3681 10 3681 7 3681 1849 3682 7 3682 1850 3682 1851 3683 2478 3683 1920 3683 1852 3684 1851 3684 468 3684 468 3685 1851 3685 1920 3685 468 3686 1920 3686 466 3686 1906 3687 2474 3687 2473 3687 1858 3688 2484 3688 469 3688 469 3689 2484 3689 2482 3689 469 3690 2482 3690 1852 3690 1852 3691 2482 3691 2481 3691 1852 3692 2481 3692 1851 3692 2478 3693 1853 3693 1920 3693 1920 3694 1853 3694 1854 3694 1920 3695 1854 3695 1906 3695 1906 3696 1854 3696 1855 3696 1906 3697 1855 3697 2474 3697 1908 3698 1856 3698 1857 3698 1857 3699 1856 3699 1907 3699 1857 3700 1907 3700 1858 3700 1858 3701 1907 3701 1859 3701 1858 3702 1859 3702 2484 3702 10225 3703 463 3703 1921 3703 1860 3704 492 3704 1861 3704 1861 3705 492 3705 461 3705 1861 3706 461 3706 10324 3706 451 3707 1862 3707 1869 3707 1869 3708 1862 3708 455 3708 1863 3709 2494 3709 1864 3709 1864 3710 2494 3710 2493 3710 1864 3711 2493 3711 415 3711 1867 3712 2487 3712 1865 3712 10244 3713 414 3713 415 3713 1901 3714 10244 3714 2490 3714 2490 3715 10244 3715 415 3715 2490 3716 415 3716 2491 3716 2491 3717 415 3717 2493 3717 1865 3718 1866 3718 1867 3718 1867 3719 1866 3719 1868 3719 1867 3720 1868 3720 1869 3720 1869 3721 1868 3721 2498 3721 1869 3722 2498 3722 451 3722 451 3723 2498 3723 2497 3723 451 3724 2497 3724 1863 3724 1863 3725 2497 3725 1870 3725 1863 3726 1870 3726 2494 3726 1899 3727 412 3727 10244 3727 10244 3728 412 3728 1871 3728 10244 3729 1871 3729 414 3729 1872 3730 1876 3730 411 3730 411 3731 1876 3731 1873 3731 1759 3732 2505 3732 1896 3732 1896 3733 2505 3733 542 3733 1896 3734 542 3734 1874 3734 1874 3735 542 3735 1877 3735 1874 3736 1877 3736 11 3736 1874 3737 1875 3737 1896 3737 1896 3738 1875 3738 1878 3738 1896 3739 1878 3739 1876 3739 1876 3740 1878 3740 2678 3740 0 3741 2 3741 408 3741 408 3742 2 3742 4 3742 408 3743 4 3743 1877 3743 1877 3744 4 3744 1878 3744 1877 3745 1878 3745 11 3745 2678 3746 2677 3746 1876 3746 1876 3747 2677 3747 0 3747 1876 3748 0 3748 1873 3748 1873 3749 0 3749 408 3749 543 3750 1777 3750 1879 3750 1879 3751 1777 3751 1784 3751 1879 3752 1784 3752 1880 3752 1880 3753 1784 3753 2246 3753 1880 3754 2246 3754 1881 3754 1881 3755 2246 3755 1882 3755 1881 3756 1882 3756 1883 3756 1802 3757 1884 3757 1885 3757 1885 3758 1884 3758 1886 3758 1885 3759 1886 3759 10288 3759 10288 3760 1886 3760 2193 3760 10288 3761 2193 3761 2194 3761 1890 3762 1887 3762 1892 3762 2146 3763 2668 3763 1888 3763 1888 3764 2668 3764 1889 3764 1888 3765 1889 3765 1895 3765 1895 3766 1889 3766 1894 3766 10300 3767 1944 3767 1800 3767 1800 3768 1944 3768 1945 3768 1800 3769 1945 3769 1890 3769 1890 3770 1945 3770 1891 3770 1890 3771 1891 3771 1887 3771 2146 3772 2149 3772 2668 3772 2668 3773 2149 3773 2150 3773 2668 3774 2150 3774 1945 3774 1945 3775 2150 3775 2152 3775 1945 3776 2152 3776 1891 3776 1892 3777 2156 3777 1890 3777 1890 3778 2156 3778 1893 3778 1890 3779 1893 3779 1894 3779 1894 3780 1893 3780 2144 3780 1894 3781 2144 3781 1895 3781 2661 3782 1911 3782 2657 3782 2657 3783 1911 3783 1910 3783 2657 3784 1910 3784 1909 3784 2508 3785 1896 3785 1898 3785 1898 3786 1896 3786 1876 3786 1898 3787 1876 3787 1899 3787 1899 3788 1876 3788 1872 3788 1899 3789 1872 3789 412 3789 2053 3790 1765 3790 1902 3790 1902 3791 1765 3791 1898 3791 1902 3792 1898 3792 1897 3792 1897 3793 1898 3793 1899 3793 1897 3794 1899 3794 1900 3794 1900 3795 1899 3795 10244 3795 1900 3796 10244 3796 1867 3796 1867 3797 10244 3797 1901 3797 1867 3798 1901 3798 2487 3798 1762 3799 1902 3799 1761 3799 1761 3800 1902 3800 1897 3800 1761 3801 1897 3801 1903 3801 1903 3802 1897 3802 1900 3802 1903 3803 1900 3803 1940 3803 1940 3804 1900 3804 1867 3804 1940 3805 1867 3805 1904 3805 1904 3806 1867 3806 1869 3806 1904 3807 1869 3807 1941 3807 1941 3808 1869 3808 455 3808 1941 3809 455 3809 457 3809 1905 3810 1769 3810 1913 3810 1913 3811 1769 3811 1918 3811 1913 3812 1918 3812 1912 3812 1912 3813 1918 3813 1906 3813 1912 3814 1906 3814 1856 3814 1856 3815 1906 3815 2473 3815 1856 3816 2473 3816 1907 3816 7 3817 8 3817 1850 3817 1850 3818 8 3818 1909 3818 1850 3819 1909 3819 1908 3819 1908 3820 1909 3820 1910 3820 1908 3821 1910 3821 1856 3821 1856 3822 1910 3822 1911 3822 1856 3823 1911 3823 1912 3823 1912 3824 1911 3824 1842 3824 1912 3825 1842 3825 1913 3825 1913 3826 1842 3826 2469 3826 1913 3827 2469 3827 1905 3827 2233 3828 1914 3828 1915 3828 1915 3829 1914 3829 1916 3829 1915 3830 1916 3830 1839 3830 1839 3831 1916 3831 1917 3831 1839 3832 1917 3832 1769 3832 1769 3833 1917 3833 1930 3833 1769 3834 1930 3834 1918 3834 1918 3835 1930 3835 1919 3835 1918 3836 1919 3836 1906 3836 1906 3837 1919 3837 10225 3837 1906 3838 10225 3838 1920 3838 1920 3839 10225 3839 1921 3839 1920 3840 1921 3840 466 3840 1922 3841 1953 3841 1793 3841 1793 3842 1953 3842 1923 3842 1793 3843 1923 3843 1791 3843 1791 3844 1923 3844 1924 3844 1791 3845 1924 3845 552 3845 552 3846 1924 3846 553 3846 1832 3847 2218 3847 526 3847 526 3848 2218 3848 1829 3848 526 3849 1829 3849 1757 3849 1757 3850 1829 3850 1937 3850 1757 3851 1937 3851 1925 3851 1925 3852 1937 3852 1926 3852 1925 3853 1926 3853 1914 3853 1914 3854 1926 3854 1927 3854 1914 3855 1927 3855 1916 3855 1916 3856 1927 3856 1939 3856 1916 3857 1939 3857 1917 3857 1917 3858 1939 3858 1928 3858 1917 3859 1928 3859 1930 3859 1930 3860 1928 3860 1929 3860 1930 3861 1929 3861 1919 3861 1919 3862 1929 3862 10324 3862 1919 3863 10324 3863 10225 3863 10225 3864 10324 3864 461 3864 10225 3865 461 3865 463 3865 2177 3866 1885 3866 1931 3866 1931 3867 1885 3867 10288 3867 1931 3868 10288 3868 1946 3868 1946 3869 10288 3869 2196 3869 1946 3870 2196 3870 1795 3870 1932 3871 1933 3871 1822 3871 1822 3872 1933 3872 1982 3872 1822 3873 1982 3873 1934 3873 1934 3874 1982 3874 1981 3874 1934 3875 1981 3875 1827 3875 1827 3876 1981 3876 1935 3876 1827 3877 1935 3877 1829 3877 1829 3878 1935 3878 1936 3878 1829 3879 1936 3879 1937 3879 1937 3880 1936 3880 1980 3880 1937 3881 1980 3881 1926 3881 1926 3882 1980 3882 1938 3882 1926 3883 1938 3883 1927 3883 1927 3884 1938 3884 1761 3884 1927 3885 1761 3885 1939 3885 1939 3886 1761 3886 1903 3886 1939 3887 1903 3887 1928 3887 1928 3888 1903 3888 1940 3888 1928 3889 1940 3889 1929 3889 1929 3890 1940 3890 1904 3890 1929 3891 1904 3891 10324 3891 10324 3892 1904 3892 1941 3892 10324 3893 1941 3893 1861 3893 1861 3894 1941 3894 457 3894 1861 3895 457 3895 458 3895 1801 3896 1942 3896 10300 3896 10300 3897 1942 3897 1950 3897 10300 3898 1950 3898 1944 3898 1944 3899 1950 3899 1943 3899 1944 3900 1943 3900 1945 3900 1945 3901 1943 3901 2667 3901 1945 3902 2667 3902 2668 3902 1795 3903 1954 3903 1946 3903 1946 3904 1954 3904 1947 3904 1946 3905 1947 3905 1931 3905 1931 3906 1947 3906 1948 3906 1931 3907 1948 3907 1942 3907 1942 3908 1948 3908 1949 3908 1942 3909 1949 3909 1950 3909 1950 3910 1949 3910 1958 3910 1950 3911 1958 3911 1943 3911 1943 3912 1958 3912 1959 3912 1943 3913 1959 3913 2667 3913 1951 3914 1962 3914 1922 3914 1922 3915 1962 3915 1952 3915 1922 3916 1952 3916 1953 3916 1953 3917 1952 3917 1963 3917 1953 3918 1963 3918 1954 3918 1954 3919 1963 3919 1955 3919 1954 3920 1955 3920 1947 3920 1947 3921 1955 3921 1956 3921 1947 3922 1956 3922 1948 3922 1948 3923 1956 3923 1957 3923 1948 3924 1957 3924 1949 3924 1949 3925 1957 3925 1964 3925 1949 3926 1964 3926 1958 3926 1958 3927 1964 3927 1965 3927 1958 3928 1965 3928 1959 3928 1760 3929 1782 3929 1961 3929 1961 3930 1782 3930 1960 3930 1961 3931 1960 3931 1962 3931 1962 3932 1960 3932 1968 3932 1962 3933 1968 3933 1952 3933 1952 3934 1968 3934 1971 3934 1952 3935 1971 3935 1963 3935 1963 3936 1971 3936 1972 3936 1963 3937 1972 3937 1955 3937 1955 3938 1972 3938 1974 3938 1955 3939 1974 3939 1956 3939 1956 3940 1974 3940 1976 3940 1956 3941 1976 3941 1957 3941 1957 3942 1976 3942 1979 3942 1957 3943 1979 3943 1964 3943 1964 3944 1979 3944 2671 3944 1964 3945 2671 3945 1965 3945 2045 3946 1966 3946 1782 3946 1782 3947 1966 3947 1967 3947 1782 3948 1967 3948 1960 3948 1960 3949 1967 3949 1969 3949 1960 3950 1969 3950 1968 3950 1968 3951 1969 3951 1970 3951 1968 3952 1970 3952 1971 3952 1971 3953 1970 3953 1983 3953 1971 3954 1983 3954 1972 3954 1972 3955 1983 3955 1973 3955 1972 3956 1973 3956 1974 3956 1974 3957 1973 3957 1975 3957 1974 3958 1975 3958 1976 3958 1976 3959 1975 3959 1977 3959 1976 3960 1977 3960 1979 3960 1979 3961 1977 3961 1978 3961 1979 3962 1978 3962 2671 3962 2048 3963 1938 3963 1966 3963 1966 3964 1938 3964 1980 3964 1966 3965 1980 3965 1967 3965 1967 3966 1980 3966 1936 3966 1967 3967 1936 3967 1969 3967 1969 3968 1936 3968 1935 3968 1969 3969 1935 3969 1970 3969 1970 3970 1935 3970 1981 3970 1970 3971 1981 3971 1983 3971 1983 3972 1981 3972 1982 3972 1983 3973 1982 3973 1973 3973 1973 3974 1982 3974 1814 3974 1973 3975 1814 3975 1975 3975 1975 3976 1814 3976 1807 3976 1975 3977 1807 3977 1977 3977 1977 3978 1807 3978 2675 3978 1977 3979 2675 3979 1978 3979 1086 3980 1091 3980 1985 3980 1984 3981 1088 3981 626 3981 1079 3982 1083 3982 609 3982 1984 3983 626 3983 1083 3983 1083 3984 626 3984 625 3984 1083 3985 625 3985 609 3985 1086 3986 1985 3986 1088 3986 1088 3987 1985 3987 628 3987 1088 3988 628 3988 626 3988 1091 3989 1090 3989 1985 3989 1985 3990 1090 3990 1986 3990 1985 3991 1986 3991 1988 3991 1988 3992 1986 3992 1987 3992 1987 3993 1092 3993 1988 3993 1988 3994 1092 3994 1093 3994 1988 3995 1093 3995 631 3995 631 3996 1093 3996 1989 3996 631 3997 1989 3997 632 3997 632 3998 1989 3998 1990 3998 632 3999 1990 3999 640 3999 640 4000 1990 4000 1096 4000 640 4001 1096 4001 637 4001 637 4002 1096 4002 1991 4002 637 4003 1991 4003 1993 4003 1993 4004 1991 4004 1992 4004 1993 4005 1992 4005 1994 4005 1994 4006 1992 4006 1995 4006 1994 4007 1995 4007 1996 4007 1996 4008 1995 4008 1997 4008 1996 4009 1997 4009 638 4009 638 4010 1997 4010 1998 4010 638 4011 1998 4011 662 4011 662 4012 1998 4012 1999 4012 662 4013 1999 4013 663 4013 1999 4014 2000 4014 663 4014 663 4015 2000 4015 2001 4015 663 4016 2001 4016 664 4016 664 4017 2001 4017 2003 4017 664 4018 2003 4018 2002 4018 2002 4019 2003 4019 2004 4019 2002 4020 2004 4020 651 4020 651 4021 2004 4021 2005 4021 2005 4022 1105 4022 651 4022 651 4023 1105 4023 1103 4023 651 4024 1103 4024 2006 4024 2006 4025 1103 4025 2007 4025 2006 4026 2007 4026 652 4026 652 4027 2007 4027 2009 4027 652 4028 2009 4028 2008 4028 2008 4029 2009 4029 1106 4029 2008 4030 1106 4030 673 4030 673 4031 1106 4031 1110 4031 673 4032 1110 4032 674 4032 674 4033 1110 4033 1109 4033 674 4034 1109 4034 682 4034 1109 4035 1108 4035 682 4035 682 4036 1108 4036 1112 4036 682 4037 1112 4037 586 4037 586 4038 1112 4038 2010 4038 586 4039 2010 4039 604 4039 604 4040 2010 4040 2011 4040 604 4041 2011 4041 582 4041 2011 4042 1114 4042 582 4042 582 4043 1114 4043 1113 4043 582 4044 1113 4044 602 4044 2014 4045 1118 4045 691 4045 691 4046 1118 4046 700 4046 1113 4047 2012 4047 602 4047 602 4048 2012 4048 2013 4048 602 4049 2013 4049 2014 4049 2014 4050 2013 4050 1115 4050 2014 4051 1115 4051 1118 4051 78 4052 574 4052 77 4052 77 4053 574 4053 573 4053 77 4054 573 4054 74 4054 74 4055 573 4055 580 4055 74 4056 580 4056 2015 4056 2015 4057 580 4057 2017 4057 930 4058 2673 4058 2016 4058 2016 4059 2673 4059 2015 4059 2016 4060 2015 4060 578 4060 578 4061 2015 4061 2017 4061 2324 4062 2018 4062 2019 4062 2019 4063 2018 4063 2020 4063 2019 4064 2020 4064 2315 4064 2315 4065 2020 4065 2566 4065 2315 4066 2566 4066 2316 4066 2316 4067 2566 4067 2564 4067 2316 4068 2564 4068 2021 4068 2021 4069 2564 4069 2023 4069 2021 4070 2023 4070 2022 4070 2022 4071 2023 4071 2563 4071 2022 4072 2563 4072 2024 4072 2024 4073 2563 4073 2562 4073 2024 4074 2562 4074 2319 4074 2319 4075 2562 4075 2025 4075 2319 4076 2025 4076 2026 4076 2026 4077 2025 4077 2028 4077 2026 4078 2028 4078 2027 4078 2027 4079 2028 4079 2029 4079 2027 4080 2029 4080 2030 4080 2030 4081 2029 4081 2031 4081 2030 4082 2031 4082 2322 4082 2322 4083 2031 4083 2568 4083 2322 4084 2568 4084 2324 4084 2324 4085 2568 4085 2018 4085 716 4086 2032 4086 2038 4086 561 4087 2037 4087 1313 4087 1313 4088 2037 4088 2038 4088 2033 4089 2034 4089 2036 4089 2036 4090 2034 4090 2037 4090 2036 4091 2037 4091 562 4091 562 4092 35 4092 2036 4092 2036 4093 35 4093 2035 4093 2036 4094 2035 4094 2033 4094 2034 4095 726 4095 2037 4095 2037 4096 726 4096 2039 4096 2037 4097 2039 4097 2038 4097 2038 4098 2039 4098 729 4098 2038 4099 729 4099 713 4099 713 4100 712 4100 2038 4100 2038 4101 712 4101 2040 4101 2038 4102 2040 4102 714 4102 714 4103 2041 4103 2038 4103 2038 4104 2041 4104 2042 4104 2038 4105 2042 4105 716 4105 1767 4106 2043 4106 1764 4106 1764 4107 2043 4107 2656 4107 1764 4108 2656 4108 2045 4108 2045 4109 2656 4109 2044 4109 2045 4110 2044 4110 2046 4110 2046 4111 2044 4111 2047 4111 2046 4112 2047 4112 2048 4112 2048 4113 2047 4113 2049 4113 2048 4114 2049 4114 2050 4114 2050 4115 2049 4115 2052 4115 2050 4116 2052 4116 2051 4116 2051 4117 2052 4117 2649 4117 2051 4118 2649 4118 1762 4118 1762 4119 2649 4119 2650 4119 1762 4120 2650 4120 1763 4120 1763 4121 2650 4121 2651 4121 1763 4122 2651 4122 2053 4122 2053 4123 2651 4123 2054 4123 2053 4124 2054 4124 2055 4124 2055 4125 2054 4125 2653 4125 2055 4126 2653 4126 1766 4126 1766 4127 2653 4127 2056 4127 1766 4128 2056 4128 1767 4128 1767 4129 2056 4129 2043 4129 96 4130 2062 4130 2067 4130 122 4131 1077 4131 79 4131 79 4132 1077 4132 1074 4132 79 4133 1074 4133 2630 4133 2630 4134 1074 4134 2621 4134 2621 4135 1074 4135 1073 4135 2621 4136 1073 4136 2620 4136 2057 4137 2060 4137 1073 4137 1073 4138 2060 4138 2619 4138 1073 4139 2619 4139 2620 4139 1072 4140 2061 4140 2057 4140 2057 4141 2061 4141 2626 4141 2626 4142 2058 4142 2057 4142 2057 4143 2058 4143 2059 4143 2057 4144 2059 4144 2060 4144 2625 4145 2624 4145 1070 4145 1070 4146 2624 4146 2623 4146 1070 4147 2623 4147 1071 4147 1071 4148 2623 4148 2629 4148 1071 4149 2629 4149 1072 4149 1072 4150 2629 4150 2627 4150 1072 4151 2627 4151 2061 4151 2067 4152 2062 4152 2063 4152 2062 4153 2064 4153 2063 4153 2063 4154 2064 4154 98 4154 2063 4155 98 4155 1070 4155 1070 4156 98 4156 2065 4156 1070 4157 2065 4157 2625 4157 96 4158 2067 4158 2066 4158 2066 4159 2067 4159 2068 4159 2066 4160 2068 4160 110 4160 1068 4161 2069 4161 2068 4161 2068 4162 2069 4162 111 4162 2068 4163 111 4163 110 4163 108 4164 105 4164 2070 4164 2070 4165 105 4165 107 4165 2070 4166 107 4166 1068 4166 1068 4167 107 4167 113 4167 1068 4168 113 4168 2069 4168 122 4169 121 4169 1077 4169 1077 4170 121 4170 2071 4170 1077 4171 2071 4171 2070 4171 2070 4172 2071 4172 109 4172 2070 4173 109 4173 108 4173 2072 4174 2073 4174 274 4174 274 4175 2073 4175 2074 4175 274 4176 2074 4176 275 4176 275 4177 2074 4177 305 4177 305 4178 2074 4178 1025 4178 305 4179 1025 4179 306 4179 292 4180 290 4180 2075 4180 2075 4181 290 4181 279 4181 2075 4182 279 4182 1025 4182 1025 4183 279 4183 278 4183 1025 4184 278 4184 306 4184 2081 4185 282 4185 2075 4185 2075 4186 282 4186 2076 4186 2076 4187 2077 4187 2075 4187 2075 4188 2077 4188 2078 4188 2075 4189 2078 4189 292 4189 2079 4190 2080 4190 2081 4190 2080 4191 286 4191 2081 4191 2081 4192 286 4192 2082 4192 2081 4193 2082 4193 282 4193 2081 4194 1012 4194 2079 4194 2079 4195 1012 4195 1013 4195 2079 4196 1013 4196 2083 4196 2084 4197 1028 4197 2085 4197 2085 4198 1028 4198 2073 4198 2085 4199 2073 4199 2086 4199 2086 4200 2073 4200 2072 4200 998 4201 2087 4201 2093 4201 998 4202 2093 4202 999 4202 997 4203 363 4203 998 4203 998 4204 363 4204 362 4204 998 4205 362 4205 2087 4205 360 4206 2088 4206 997 4206 997 4207 2088 4207 359 4207 997 4208 359 4208 363 4208 997 4209 2089 4209 360 4209 360 4210 2089 4210 1008 4210 360 4211 1008 4211 1009 4211 2090 4212 1007 4212 2091 4212 2091 4213 1007 4213 1002 4213 2091 4214 1002 4214 2092 4214 2092 4215 1002 4215 1000 4215 2093 4216 355 4216 999 4216 999 4217 355 4217 2094 4217 999 4218 2094 4218 1000 4218 1000 4219 2094 4219 2095 4219 1000 4220 2095 4220 2092 4220 2106 4221 2507 4221 2096 4221 2096 4222 2507 4222 2509 4222 2096 4223 2509 4223 906 4223 906 4224 2509 4224 2097 4224 906 4225 2097 4225 909 4225 909 4226 2097 4226 2499 4226 909 4227 2499 4227 2098 4227 2098 4228 2499 4228 2500 4228 2098 4229 2500 4229 2099 4229 2099 4230 2500 4230 2100 4230 2099 4231 2100 4231 2101 4231 2101 4232 2100 4232 2501 4232 2101 4233 2501 4233 911 4233 911 4234 2501 4234 2502 4234 911 4235 2502 4235 912 4235 912 4236 2502 4236 2102 4236 912 4237 2102 4237 2103 4237 2103 4238 2102 4238 2504 4238 2103 4239 2504 4239 2104 4239 2104 4240 2504 4240 2105 4240 2104 4241 2105 4241 914 4241 914 4242 2105 4242 2506 4242 914 4243 2506 4243 2106 4243 2106 4244 2506 4244 2507 4244 897 4245 2470 4245 2107 4245 2107 4246 2470 4246 2459 4246 2107 4247 2459 4247 2108 4247 2108 4248 2459 4248 2109 4248 2108 4249 2109 4249 902 4249 902 4250 2109 4250 2110 4250 902 4251 2110 4251 903 4251 903 4252 2110 4252 2111 4252 903 4253 2111 4253 905 4253 905 4254 2111 4254 2464 4254 905 4255 2464 4255 890 4255 890 4256 2464 4256 2113 4256 890 4257 2113 4257 2112 4257 2112 4258 2113 4258 2114 4258 2112 4259 2114 4259 2115 4259 2115 4260 2114 4260 2466 4260 2115 4261 2466 4261 892 4261 892 4262 2466 4262 2116 4262 892 4263 2116 4263 893 4263 893 4264 2116 4264 2467 4264 893 4265 2467 4265 2117 4265 2117 4266 2467 4266 2468 4266 2117 4267 2468 4267 897 4267 897 4268 2468 4268 2470 4268 889 4269 2483 4269 2118 4269 2118 4270 2483 4270 2485 4270 2118 4271 2485 4271 882 4271 882 4272 2485 4272 2119 4272 882 4273 2119 4273 2120 4273 2120 4274 2119 4274 2472 4274 2120 4275 2472 4275 2122 4275 2122 4276 2472 4276 2121 4276 2122 4277 2121 4277 2123 4277 2123 4278 2121 4278 2475 4278 2123 4279 2475 4279 2124 4279 2124 4280 2475 4280 2125 4280 2124 4281 2125 4281 2126 4281 2126 4282 2125 4282 2476 4282 2126 4283 2476 4283 2127 4283 2127 4284 2476 4284 2477 4284 2127 4285 2477 4285 2128 4285 2128 4286 2477 4286 2479 4286 2128 4287 2479 4287 886 4287 886 4288 2479 4288 2480 4288 886 4289 2480 4289 2129 4289 2129 4290 2480 4290 2130 4290 2129 4291 2130 4291 889 4291 889 4292 2130 4292 2483 4292 880 4293 2143 4293 2131 4293 2131 4294 2143 4294 2132 4294 2131 4295 2132 4295 871 4295 871 4296 2132 4296 2486 4296 871 4297 2486 4297 2133 4297 2133 4298 2486 4298 2488 4298 2133 4299 2488 4299 2134 4299 2134 4300 2488 4300 2135 4300 2134 4301 2135 4301 2136 4301 2136 4302 2135 4302 2489 4302 2136 4303 2489 4303 873 4303 873 4304 2489 4304 2137 4304 873 4305 2137 4305 2138 4305 2138 4306 2137 4306 2492 4306 2138 4307 2492 4307 2139 4307 2139 4308 2492 4308 2141 4308 2139 4309 2141 4309 2140 4309 2140 4310 2141 4310 2495 4310 2140 4311 2495 4311 876 4311 876 4312 2495 4312 2496 4312 876 4313 2496 4313 878 4313 878 4314 2496 4314 2142 4314 878 4315 2142 4315 880 4315 880 4316 2142 4316 2143 4316 1893 4317 2157 4317 2144 4317 2144 4318 2157 4318 2581 4318 2144 4319 2581 4319 1895 4319 1895 4320 2581 4320 2145 4320 1895 4321 2145 4321 1888 4321 1888 4322 2145 4322 2147 4322 1888 4323 2147 4323 2146 4323 2146 4324 2147 4324 2148 4324 2146 4325 2148 4325 2149 4325 2149 4326 2148 4326 2582 4326 2149 4327 2582 4327 2150 4327 2150 4328 2582 4328 2151 4328 2150 4329 2151 4329 2152 4329 2152 4330 2151 4330 2153 4330 2152 4331 2153 4331 1891 4331 1891 4332 2153 4332 2154 4332 1891 4333 2154 4333 1887 4333 1887 4334 2154 4334 2585 4334 1887 4335 2585 4335 1892 4335 1892 4336 2585 4336 2587 4336 1892 4337 2587 4337 2156 4337 2156 4338 2587 4338 2155 4338 2156 4339 2155 4339 1893 4339 1893 4340 2155 4340 2157 4340 2158 4341 2570 4341 1808 4341 1808 4342 2570 4342 2159 4342 1808 4343 2159 4343 1809 4343 1809 4344 2159 4344 2573 4344 1809 4345 2573 4345 1810 4345 1810 4346 2573 4346 2160 4346 1810 4347 2160 4347 1811 4347 1811 4348 2160 4348 2161 4348 1811 4349 2161 4349 2162 4349 2162 4350 2161 4350 2575 4350 2162 4351 2575 4351 1812 4351 1812 4352 2575 4352 2163 4352 1812 4353 2163 4353 2164 4353 2164 4354 2163 4354 2577 4354 2164 4355 2577 4355 1815 4355 1815 4356 2577 4356 2165 4356 1815 4357 2165 4357 1816 4357 1816 4358 2165 4358 2580 4358 1816 4359 2580 4359 1817 4359 1817 4360 2580 4360 2166 4360 1817 4361 2166 4361 1818 4361 1818 4362 2166 4362 2167 4362 1818 4363 2167 4363 2158 4363 2158 4364 2167 4364 2570 4364 2183 4365 2168 4365 2169 4365 2169 4366 2168 4366 2170 4366 2169 4367 2170 4367 1799 4367 1799 4368 2170 4368 2171 4368 1799 4369 2171 4369 2172 4369 2172 4370 2171 4370 2565 4370 2172 4371 2565 4371 1801 4371 1801 4372 2565 4372 2567 4372 1801 4373 2567 4373 2173 4373 2173 4374 2567 4374 2174 4374 2173 4375 2174 4375 2175 4375 2175 4376 2174 4376 2176 4376 2175 4377 2176 4377 2177 4377 2177 4378 2176 4378 2178 4378 2177 4379 2178 4379 2179 4379 2179 4380 2178 4380 2180 4380 2179 4381 2180 4381 1803 4381 1803 4382 2180 4382 2181 4382 1803 4383 2181 4383 1804 4383 1804 4384 2181 4384 2569 4384 1804 4385 2569 4385 1806 4385 1806 4386 2569 4386 2182 4386 1806 4387 2182 4387 2183 4387 2183 4388 2182 4388 2168 4388 2184 4389 2185 4389 1823 4389 1823 4390 2185 4390 2186 4390 1823 4391 2186 4391 1824 4391 1824 4392 2186 4392 2550 4392 1824 4393 2550 4393 1825 4393 1825 4394 2550 4394 2551 4394 1825 4395 2551 4395 2187 4395 2187 4396 2551 4396 2552 4396 2187 4397 2552 4397 1820 4397 1820 4398 2552 4398 2554 4398 1820 4399 2554 4399 1821 4399 1821 4400 2554 4400 2556 4400 1821 4401 2556 4401 2188 4401 2188 4402 2556 4402 2557 4402 2188 4403 2557 4403 1932 4403 1932 4404 2557 4404 2189 4404 1932 4405 2189 4405 1933 4405 1933 4406 2189 4406 2558 4406 1933 4407 2558 4407 1819 4407 1819 4408 2558 4408 2190 4408 1819 4409 2190 4409 2191 4409 2191 4410 2190 4410 2192 4410 2191 4411 2192 4411 2184 4411 2184 4412 2192 4412 2185 4412 1794 4413 2206 4413 2193 4413 2193 4414 2206 4414 2195 4414 2193 4415 2195 4415 2194 4415 2194 4416 2195 4416 2534 4416 2194 4417 2534 4417 2196 4417 2196 4418 2534 4418 2536 4418 2196 4419 2536 4419 1795 4419 1795 4420 2536 4420 2538 4420 1795 4421 2538 4421 1796 4421 1796 4422 2538 4422 2197 4422 1796 4423 2197 4423 2198 4423 2198 4424 2197 4424 2199 4424 2198 4425 2199 4425 1797 4425 1797 4426 2199 4426 2200 4426 1797 4427 2200 4427 1798 4427 1798 4428 2200 4428 2202 4428 1798 4429 2202 4429 2201 4429 2201 4430 2202 4430 2542 4430 2201 4431 2542 4431 2203 4431 2203 4432 2542 4432 2204 4432 2203 4433 2204 4433 2205 4433 2205 4434 2204 4434 2544 4434 2205 4435 2544 4435 1794 4435 1794 4436 2544 4436 2206 4436 2221 4437 2545 4437 2207 4437 2207 4438 2545 4438 2208 4438 2207 4439 2208 4439 1830 4439 1830 4440 2208 4440 2210 4440 1830 4441 2210 4441 2209 4441 2209 4442 2210 4442 2546 4442 2209 4443 2546 4443 1833 4443 1833 4444 2546 4444 2211 4444 1833 4445 2211 4445 2212 4445 2212 4446 2211 4446 2214 4446 2212 4447 2214 4447 2213 4447 2213 4448 2214 4448 2215 4448 2213 4449 2215 4449 1831 4449 1831 4450 2215 4450 2216 4450 1831 4451 2216 4451 1832 4451 1832 4452 2216 4452 2217 4452 1832 4453 2217 4453 2218 4453 2218 4454 2217 4454 2219 4454 2218 4455 2219 4455 1828 4455 1828 4456 2219 4456 2548 4456 1828 4457 2548 4457 2220 4457 2220 4458 2548 4458 2222 4458 2220 4459 2222 4459 2221 4459 2221 4460 2222 4460 2545 4460 2237 4461 2223 4461 2224 4461 2224 4462 2223 4462 2510 4462 2224 4463 2510 4463 2225 4463 2225 4464 2510 4464 2511 4464 2225 4465 2511 4465 2226 4465 2226 4466 2511 4466 2514 4466 2226 4467 2514 4467 2227 4467 2227 4468 2514 4468 2516 4468 2227 4469 2516 4469 2228 4469 2228 4470 2516 4470 2229 4470 2228 4471 2229 4471 1841 4471 1841 4472 2229 4472 2518 4472 1841 4473 2518 4473 2230 4473 2230 4474 2518 4474 2520 4474 2230 4475 2520 4475 2231 4475 2231 4476 2520 4476 2232 4476 2231 4477 2232 4477 2233 4477 2233 4478 2232 4478 2234 4478 2233 4479 2234 4479 1834 4479 1834 4480 2234 4480 2235 4480 1834 4481 2235 4481 2236 4481 2236 4482 2235 4482 2523 4482 2236 4483 2523 4483 2237 4483 2237 4484 2523 4484 2223 4484 1883 4485 2238 4485 1790 4485 1790 4486 2238 4486 2239 4486 1790 4487 2239 4487 1792 4487 1792 4488 2239 4488 2525 4488 1792 4489 2525 4489 1951 4489 1951 4490 2525 4490 2240 4490 1951 4491 2240 4491 1787 4491 1787 4492 2240 4492 2241 4492 1787 4493 2241 4493 2242 4493 2242 4494 2241 4494 2527 4494 2242 4495 2527 4495 2243 4495 2243 4496 2527 4496 2530 4496 2243 4497 2530 4497 1788 4497 1788 4498 2530 4498 2244 4498 1788 4499 2244 4499 1785 4499 1785 4500 2244 4500 2531 4500 1785 4501 2531 4501 1786 4501 1786 4502 2531 4502 2245 4502 1786 4503 2245 4503 2246 4503 2246 4504 2245 4504 2247 4504 2246 4505 2247 4505 1882 4505 1882 4506 2247 4506 2248 4506 1882 4507 2248 4507 1883 4507 1883 4508 2248 4508 2238 4508 2249 4509 2252 4509 2255 4509 2251 4510 2252 4510 2249 4510 2249 4511 2257 4511 2259 4511 2256 4512 2257 4512 2249 4512 2255 4513 2256 4513 2249 4513 2249 4514 2260 4514 2262 4514 2250 4515 2260 4515 2249 4515 2259 4516 2250 4516 2249 4516 2249 4517 2264 4517 2267 4517 2263 4518 2264 4518 2249 4518 2262 4519 2263 4519 2249 4519 2267 4520 2251 4520 2249 4520 2251 4521 2253 4521 2252 4521 2252 4522 2253 4522 845 4522 2252 4523 845 4523 2255 4523 2255 4524 845 4524 2254 4524 2255 4525 2254 4525 2256 4525 2256 4526 2254 4526 847 4526 2256 4527 847 4527 2257 4527 2257 4528 847 4528 2258 4528 2257 4529 2258 4529 2259 4529 2259 4530 2258 4530 849 4530 2259 4531 849 4531 2250 4531 2250 4532 849 4532 850 4532 2250 4533 850 4533 2260 4533 2260 4534 850 4534 2261 4534 2260 4535 2261 4535 2262 4535 2262 4536 2261 4536 853 4536 2262 4537 853 4537 2263 4537 2263 4538 853 4538 2265 4538 2263 4539 2265 4539 2264 4539 2264 4540 2265 4540 2266 4540 2264 4541 2266 4541 2267 4541 2267 4542 2266 4542 855 4542 2267 4543 855 4543 2251 4543 2251 4544 855 4544 2253 4544 2270 4545 2268 4545 2274 4545 2269 4546 2268 4546 2270 4546 2270 4547 2278 4547 2271 4547 2276 4548 2278 4548 2270 4548 2274 4549 2276 4549 2270 4549 2270 4550 2281 4550 2283 4550 2280 4551 2281 4551 2270 4551 2271 4552 2280 4552 2270 4552 2270 4553 2285 4553 2286 4553 2272 4554 2285 4554 2270 4554 2283 4555 2272 4555 2270 4555 2286 4556 2269 4556 2270 4556 2269 4557 2288 4557 2268 4557 2268 4558 2288 4558 2273 4558 2268 4559 2273 4559 2274 4559 2274 4560 2273 4560 2275 4560 2274 4561 2275 4561 2276 4561 2276 4562 2275 4562 2277 4562 2276 4563 2277 4563 2278 4563 2278 4564 2277 4564 2279 4564 2278 4565 2279 4565 2271 4565 2271 4566 2279 4566 857 4566 2271 4567 857 4567 2280 4567 2280 4568 857 4568 858 4568 2280 4569 858 4569 2281 4569 2281 4570 858 4570 2282 4570 2281 4571 2282 4571 2283 4571 2283 4572 2282 4572 2284 4572 2283 4573 2284 4573 2272 4573 2272 4574 2284 4574 860 4574 2272 4575 860 4575 2285 4575 2285 4576 860 4576 861 4576 2285 4577 861 4577 2286 4577 2286 4578 861 4578 2287 4578 2286 4579 2287 4579 2269 4579 2269 4580 2287 4580 2288 4580 2290 4581 2289 4581 2294 4581 2305 4582 2289 4582 2290 4582 2290 4583 2293 4583 2291 4583 2292 4584 2293 4584 2290 4584 2294 4585 2292 4585 2290 4585 2290 4586 2302 4586 2297 4586 2295 4587 2302 4587 2290 4587 2291 4588 2295 4588 2290 4588 2290 4589 2296 4589 2298 4589 2304 4590 2296 4590 2290 4590 2297 4591 2304 4591 2290 4591 2298 4592 2305 4592 2290 4592 2305 4593 844 4593 2289 4593 2289 4594 844 4594 831 4594 2289 4595 831 4595 2294 4595 2294 4596 831 4596 833 4596 2294 4597 833 4597 2292 4597 2292 4598 833 4598 835 4598 2292 4599 835 4599 2293 4599 2293 4600 835 4600 2299 4600 2293 4601 2299 4601 2291 4601 2291 4602 2299 4602 2300 4602 2291 4603 2300 4603 2295 4603 2295 4604 2300 4604 2301 4604 2295 4605 2301 4605 2302 4605 2302 4606 2301 4606 2303 4606 2302 4607 2303 4607 2297 4607 2297 4608 2303 4608 839 4608 2297 4609 839 4609 2304 4609 2304 4610 839 4610 840 4610 2304 4611 840 4611 2296 4611 2296 4612 840 4612 842 4612 2296 4613 842 4613 2298 4613 2298 4614 842 4614 2306 4614 2298 4615 2306 4615 2305 4615 2305 4616 2306 4616 844 4616 2309 4617 2314 4617 2307 4617 2313 4618 2314 4618 2309 4618 2309 4619 2317 4619 2318 4619 2308 4620 2317 4620 2309 4620 2307 4621 2308 4621 2309 4621 2309 4622 2310 4622 2311 4622 2312 4623 2310 4623 2309 4623 2318 4624 2312 4624 2309 4624 2309 4625 2321 4625 2323 4625 2320 4626 2321 4626 2309 4626 2311 4627 2320 4627 2309 4627 2323 4628 2313 4628 2309 4628 2313 4629 2019 4629 2314 4629 2314 4630 2019 4630 2315 4630 2314 4631 2315 4631 2307 4631 2307 4632 2315 4632 2316 4632 2307 4633 2316 4633 2308 4633 2308 4634 2316 4634 2021 4634 2308 4635 2021 4635 2317 4635 2317 4636 2021 4636 2022 4636 2317 4637 2022 4637 2318 4637 2318 4638 2022 4638 2024 4638 2318 4639 2024 4639 2312 4639 2312 4640 2024 4640 2319 4640 2312 4641 2319 4641 2310 4641 2310 4642 2319 4642 2026 4642 2310 4643 2026 4643 2311 4643 2311 4644 2026 4644 2027 4644 2311 4645 2027 4645 2320 4645 2320 4646 2027 4646 2030 4646 2320 4647 2030 4647 2321 4647 2321 4648 2030 4648 2322 4648 2321 4649 2322 4649 2323 4649 2323 4650 2322 4650 2324 4650 2323 4651 2324 4651 2313 4651 2313 4652 2324 4652 2019 4652 2331 4653 2332 4653 2334 4653 2330 4654 2332 4654 2331 4654 2331 4655 2326 4655 2325 4655 2337 4656 2326 4656 2331 4656 2334 4657 2337 4657 2331 4657 2331 4658 2327 4658 2339 4658 2328 4659 2327 4659 2331 4659 2325 4660 2328 4660 2331 4660 2331 4661 2342 4661 2329 4661 2341 4662 2342 4662 2331 4662 2339 4663 2341 4663 2331 4663 2329 4664 2330 4664 2331 4664 2330 4665 2333 4665 2332 4665 2332 4666 2333 4666 2335 4666 2332 4667 2335 4667 2334 4667 2334 4668 2335 4668 2336 4668 2334 4669 2336 4669 2337 4669 2337 4670 2336 4670 803 4670 2337 4671 803 4671 2326 4671 2326 4672 803 4672 806 4672 2326 4673 806 4673 2325 4673 2325 4674 806 4674 2338 4674 2325 4675 2338 4675 2328 4675 2328 4676 2338 4676 809 4676 2328 4677 809 4677 2327 4677 2327 4678 809 4678 2340 4678 2327 4679 2340 4679 2339 4679 2339 4680 2340 4680 810 4680 2339 4681 810 4681 2341 4681 2341 4682 810 4682 813 4682 2341 4683 813 4683 2342 4683 2342 4684 813 4684 816 4684 2342 4685 816 4685 2329 4685 2329 4686 816 4686 2343 4686 2329 4687 2343 4687 2330 4687 2330 4688 2343 4688 2333 4688 2347 4689 2349 4689 2344 4689 2345 4690 2349 4690 2347 4690 2347 4691 2350 4691 2353 4691 2346 4692 2350 4692 2347 4692 2344 4693 2346 4693 2347 4693 2347 4694 2355 4694 2357 4694 2354 4695 2355 4695 2347 4695 2353 4696 2354 4696 2347 4696 2347 4697 2358 4697 2359 4697 2348 4698 2358 4698 2347 4698 2357 4699 2348 4699 2347 4699 2359 4700 2345 4700 2347 4700 2345 4701 2360 4701 2349 4701 2349 4702 2360 4702 819 4702 2349 4703 819 4703 2344 4703 2344 4704 819 4704 820 4704 2344 4705 820 4705 2346 4705 2346 4706 820 4706 2351 4706 2346 4707 2351 4707 2350 4707 2350 4708 2351 4708 2352 4708 2350 4709 2352 4709 2353 4709 2353 4710 2352 4710 823 4710 2353 4711 823 4711 2354 4711 2354 4712 823 4712 825 4712 2354 4713 825 4713 2355 4713 2355 4714 825 4714 2356 4714 2355 4715 2356 4715 2357 4715 2357 4716 2356 4716 828 4716 2357 4717 828 4717 2348 4717 2348 4718 828 4718 829 4718 2348 4719 829 4719 2358 4719 2358 4720 829 4720 830 4720 2358 4721 830 4721 2359 4721 2359 4722 830 4722 817 4722 2359 4723 817 4723 2345 4723 2345 4724 817 4724 2360 4724 2366 4725 2361 4725 2372 4725 2362 4726 2361 4726 2366 4726 2366 4727 2374 4727 2363 4727 2373 4728 2374 4728 2366 4728 2372 4729 2373 4729 2366 4729 2366 4730 2378 4730 2364 4730 2365 4731 2378 4731 2366 4731 2363 4732 2365 4732 2366 4732 2366 4733 2367 4733 2369 4733 2368 4734 2367 4734 2366 4734 2364 4735 2368 4735 2366 4735 2369 4736 2362 4736 2366 4736 2362 4737 794 4737 2361 4737 2361 4738 794 4738 2370 4738 2361 4739 2370 4739 2372 4739 2372 4740 2370 4740 2371 4740 2372 4741 2371 4741 2373 4741 2373 4742 2371 4742 796 4742 2373 4743 796 4743 2374 4743 2374 4744 796 4744 2375 4744 2374 4745 2375 4745 2363 4745 2363 4746 2375 4746 798 4746 2363 4747 798 4747 2365 4747 2365 4748 798 4748 2376 4748 2365 4749 2376 4749 2378 4749 2378 4750 2376 4750 2377 4750 2378 4751 2377 4751 2364 4751 2364 4752 2377 4752 2379 4752 2364 4753 2379 4753 2368 4753 2368 4754 2379 4754 2380 4754 2368 4755 2380 4755 2367 4755 2367 4756 2380 4756 2381 4756 2367 4757 2381 4757 2369 4757 2369 4758 2381 4758 2382 4758 2369 4759 2382 4759 2362 4759 2362 4760 2382 4760 794 4760 2384 4761 2383 4761 2386 4761 2400 4762 2383 4762 2384 4762 2384 4763 2385 4763 2387 4763 2389 4764 2385 4764 2384 4764 2386 4765 2389 4765 2384 4765 2384 4766 2394 4766 2395 4766 2392 4767 2394 4767 2384 4767 2387 4768 2392 4768 2384 4768 2384 4769 2398 4769 2388 4769 2396 4770 2398 4770 2384 4770 2395 4771 2396 4771 2384 4771 2388 4772 2400 4772 2384 4772 2400 4773 783 4773 2383 4773 2383 4774 783 4774 785 4774 2383 4775 785 4775 2386 4775 2386 4776 785 4776 786 4776 2386 4777 786 4777 2389 4777 2389 4778 786 4778 2390 4778 2389 4779 2390 4779 2385 4779 2385 4780 2390 4780 2391 4780 2385 4781 2391 4781 2387 4781 2387 4782 2391 4782 789 4782 2387 4783 789 4783 2392 4783 2392 4784 789 4784 2393 4784 2392 4785 2393 4785 2394 4785 2394 4786 2393 4786 790 4786 2394 4787 790 4787 2395 4787 2395 4788 790 4788 2397 4788 2395 4789 2397 4789 2396 4789 2396 4790 2397 4790 780 4790 2396 4791 780 4791 2398 4791 2398 4792 780 4792 782 4792 2398 4793 782 4793 2388 4793 2388 4794 782 4794 2399 4794 2388 4795 2399 4795 2400 4795 2400 4796 2399 4796 783 4796 2411 4797 2594 4797 2401 4797 2401 4798 2594 4798 2596 4798 2401 4799 2596 4799 944 4799 944 4800 2596 4800 2402 4800 944 4801 2402 4801 945 4801 945 4802 2402 4802 2589 4802 945 4803 2589 4803 2403 4803 2403 4804 2589 4804 2404 4804 2403 4805 2404 4805 2405 4805 2405 4806 2404 4806 2590 4806 2405 4807 2590 4807 934 4807 934 4808 2590 4808 2406 4808 934 4809 2406 4809 938 4809 938 4810 2406 4810 2591 4810 938 4811 2591 4811 2408 4811 2408 4812 2591 4812 2407 4812 2408 4813 2407 4813 937 4813 937 4814 2407 4814 2409 4814 937 4815 2409 4815 951 4815 951 4816 2409 4816 2410 4816 951 4817 2410 4817 948 4817 948 4818 2410 4818 2412 4818 948 4819 2412 4819 2411 4819 2411 4820 2412 4820 2594 4820 1026 4821 879 4821 2413 4821 2413 4822 879 4822 869 4822 2413 4823 869 4823 1024 4823 1024 4824 869 4824 870 4824 1024 4825 870 4825 2414 4825 2414 4826 870 4826 2415 4826 2414 4827 2415 4827 1014 4827 1014 4828 2415 4828 2417 4828 1014 4829 2417 4829 2416 4829 2416 4830 2417 4830 872 4830 2416 4831 872 4831 2418 4831 2418 4832 872 4832 2419 4832 2418 4833 2419 4833 1017 4833 1017 4834 2419 4834 874 4834 1017 4835 874 4835 1018 4835 1018 4836 874 4836 2420 4836 1018 4837 2420 4837 1030 4837 1030 4838 2420 4838 875 4838 1030 4839 875 4839 1029 4839 1029 4840 875 4840 2421 4840 1029 4841 2421 4841 1027 4841 1027 4842 2421 4842 877 4842 1027 4843 877 4843 1026 4843 1026 4844 877 4844 879 4844 2435 4845 888 4845 2422 4845 2422 4846 888 4846 881 4846 2422 4847 881 4847 2423 4847 2423 4848 881 4848 2424 4848 2423 4849 2424 4849 2426 4849 2426 4850 2424 4850 2425 4850 2426 4851 2425 4851 1045 4851 1045 4852 2425 4852 883 4852 1045 4853 883 4853 1043 4853 1043 4854 883 4854 2427 4854 1043 4855 2427 4855 2428 4855 2428 4856 2427 4856 884 4856 2428 4857 884 4857 2430 4857 2430 4858 884 4858 2429 4858 2430 4859 2429 4859 2431 4859 2431 4860 2429 4860 2432 4860 2431 4861 2432 4861 1039 4861 1039 4862 2432 4862 885 4862 1039 4863 885 4863 2433 4863 2433 4864 885 4864 2434 4864 2433 4865 2434 4865 1046 4865 1046 4866 2434 4866 887 4866 1046 4867 887 4867 2435 4867 2435 4868 887 4868 888 4868 2436 4869 896 4869 955 4869 955 4870 896 4870 898 4870 955 4871 898 4871 2437 4871 2437 4872 898 4872 899 4872 2437 4873 899 4873 959 4873 959 4874 899 4874 900 4874 959 4875 900 4875 2438 4875 2438 4876 900 4876 901 4876 2438 4877 901 4877 2439 4877 2439 4878 901 4878 904 4878 2439 4879 904 4879 2440 4879 2440 4880 904 4880 2441 4880 2440 4881 2441 4881 2442 4881 2442 4882 2441 4882 2443 4882 2442 4883 2443 4883 960 4883 960 4884 2443 4884 891 4884 960 4885 891 4885 962 4885 962 4886 891 4886 2445 4886 962 4887 2445 4887 2444 4887 2444 4888 2445 4888 894 4888 2444 4889 894 4889 2446 4889 2446 4890 894 4890 895 4890 2446 4891 895 4891 2436 4891 2436 4892 895 4892 896 4892 2458 4893 915 4893 2447 4893 2447 4894 915 4894 916 4894 2447 4895 916 4895 2448 4895 2448 4896 916 4896 2449 4896 2448 4897 2449 4897 987 4897 987 4898 2449 4898 907 4898 987 4899 907 4899 988 4899 988 4900 907 4900 908 4900 988 4901 908 4901 2450 4901 2450 4902 908 4902 910 4902 2450 4903 910 4903 995 4903 995 4904 910 4904 2451 4904 995 4905 2451 4905 996 4905 996 4906 2451 4906 2452 4906 996 4907 2452 4907 1003 4907 1003 4908 2452 4908 2453 4908 1003 4909 2453 4909 2454 4909 2454 4910 2453 4910 2455 4910 2454 4911 2455 4911 1001 4911 1001 4912 2455 4912 913 4912 1001 4913 913 4913 2456 4913 2456 4914 913 4914 2457 4914 2456 4915 2457 4915 2458 4915 2458 4916 2457 4916 915 4916 2459 4917 2460 4917 2109 4917 2109 4918 2460 4918 2461 4918 2109 4919 2461 4919 2110 4919 2110 4920 2461 4920 2462 4920 2110 4921 2462 4921 2111 4921 2111 4922 2462 4922 2463 4922 2111 4923 2463 4923 2464 4923 2464 4924 2463 4924 2465 4924 2464 4925 2465 4925 2113 4925 2113 4926 2465 4926 1771 4926 2113 4927 1771 4927 2114 4927 2114 4928 1771 4928 1770 4928 2114 4929 1770 4929 2466 4929 2466 4930 1770 4930 1768 4930 2466 4931 1768 4931 2116 4931 2116 4932 1768 4932 1905 4932 2116 4933 1905 4933 2467 4933 2467 4934 1905 4934 2469 4934 2467 4935 2469 4935 2468 4935 2468 4936 2469 4936 1772 4936 2468 4937 1772 4937 2470 4937 2470 4938 1772 4938 2471 4938 2470 4939 2471 4939 2459 4939 2459 4940 2471 4940 2460 4940 2485 4941 1859 4941 2119 4941 2119 4942 1859 4942 1907 4942 2119 4943 1907 4943 2472 4943 2472 4944 1907 4944 2473 4944 2472 4945 2473 4945 2121 4945 2121 4946 2473 4946 2474 4946 2121 4947 2474 4947 2475 4947 2475 4948 2474 4948 1855 4948 2475 4949 1855 4949 2125 4949 2125 4950 1855 4950 1854 4950 2125 4951 1854 4951 2476 4951 2476 4952 1854 4952 1853 4952 2476 4953 1853 4953 2477 4953 2477 4954 1853 4954 2478 4954 2477 4955 2478 4955 2479 4955 2479 4956 2478 4956 1851 4956 2479 4957 1851 4957 2480 4957 2480 4958 1851 4958 2481 4958 2480 4959 2481 4959 2130 4959 2130 4960 2481 4960 2482 4960 2130 4961 2482 4961 2483 4961 2483 4962 2482 4962 2484 4962 2483 4963 2484 4963 2485 4963 2485 4964 2484 4964 1859 4964 2132 4965 1866 4965 2486 4965 2486 4966 1866 4966 1865 4966 2486 4967 1865 4967 2488 4967 2488 4968 1865 4968 2487 4968 2488 4969 2487 4969 2135 4969 2135 4970 2487 4970 1901 4970 2135 4971 1901 4971 2489 4971 2489 4972 1901 4972 2490 4972 2489 4973 2490 4973 2137 4973 2137 4974 2490 4974 2491 4974 2137 4975 2491 4975 2492 4975 2492 4976 2491 4976 2493 4976 2492 4977 2493 4977 2141 4977 2141 4978 2493 4978 2494 4978 2141 4979 2494 4979 2495 4979 2495 4980 2494 4980 1870 4980 2495 4981 1870 4981 2496 4981 2496 4982 1870 4982 2497 4982 2496 4983 2497 4983 2142 4983 2142 4984 2497 4984 2498 4984 2142 4985 2498 4985 2143 4985 2143 4986 2498 4986 1868 4986 2143 4987 1868 4987 2132 4987 2132 4988 1868 4988 1866 4988 2509 4989 1781 4989 2097 4989 2097 4990 1781 4990 1760 4990 2097 4991 1760 4991 2499 4991 2499 4992 1760 4992 1773 4992 2499 4993 1773 4993 2500 4993 2500 4994 1773 4994 1779 4994 2500 4995 1779 4995 2100 4995 2100 4996 1779 4996 1778 4996 2100 4997 1778 4997 2501 4997 2501 4998 1778 4998 1776 4998 2501 4999 1776 4999 2502 4999 2502 5000 1776 5000 1775 5000 2502 5001 1775 5001 2102 5001 2102 5002 1775 5002 2503 5002 2102 5003 2503 5003 2504 5003 2504 5004 2503 5004 2505 5004 2504 5005 2505 5005 2105 5005 2105 5006 2505 5006 1759 5006 2105 5007 1759 5007 2506 5007 2506 5008 1759 5008 2508 5008 2506 5009 2508 5009 2507 5009 2507 5010 2508 5010 1780 5010 2507 5011 1780 5011 2509 5011 2509 5012 1780 5012 1781 5012 2523 5013 799 5013 2223 5013 2223 5014 799 5014 797 5014 2223 5015 797 5015 2510 5015 2510 5016 797 5016 2512 5016 2510 5017 2512 5017 2511 5017 2511 5018 2512 5018 2513 5018 2511 5019 2513 5019 2514 5019 2514 5020 2513 5020 2515 5020 2514 5021 2515 5021 2516 5021 2516 5022 2515 5022 795 5022 2516 5023 795 5023 2229 5023 2229 5024 795 5024 2517 5024 2229 5025 2517 5025 2518 5025 2518 5026 2517 5026 2519 5026 2518 5027 2519 5027 2520 5027 2520 5028 2519 5028 2521 5028 2520 5029 2521 5029 2232 5029 2232 5030 2521 5030 793 5030 2232 5031 793 5031 2234 5031 2234 5032 793 5032 2522 5032 2234 5033 2522 5033 2235 5033 2235 5034 2522 5034 800 5034 2235 5035 800 5035 2523 5035 2523 5036 800 5036 799 5036 2248 5037 2533 5037 2238 5037 2238 5038 2533 5038 788 5038 2238 5039 788 5039 2239 5039 2239 5040 788 5040 2524 5040 2239 5041 2524 5041 2525 5041 2525 5042 2524 5042 787 5042 2525 5043 787 5043 2240 5043 2240 5044 787 5044 2526 5044 2240 5045 2526 5045 2241 5045 2241 5046 2526 5046 784 5046 2241 5047 784 5047 2527 5047 2527 5048 784 5048 2528 5048 2527 5049 2528 5049 2530 5049 2530 5050 2528 5050 2529 5050 2530 5051 2529 5051 2244 5051 2244 5052 2529 5052 781 5052 2244 5053 781 5053 2531 5053 2531 5054 781 5054 792 5054 2531 5055 792 5055 2245 5055 2245 5056 792 5056 791 5056 2245 5057 791 5057 2247 5057 2247 5058 791 5058 2532 5058 2247 5059 2532 5059 2248 5059 2248 5060 2532 5060 2533 5060 2544 5061 824 5061 2206 5061 2206 5062 824 5062 822 5062 2206 5063 822 5063 2195 5063 2195 5064 822 5064 821 5064 2195 5065 821 5065 2534 5065 2534 5066 821 5066 2535 5066 2534 5067 2535 5067 2536 5067 2536 5068 2535 5068 2537 5068 2536 5069 2537 5069 2538 5069 2538 5070 2537 5070 818 5070 2538 5071 818 5071 2197 5071 2197 5072 818 5072 2539 5072 2197 5073 2539 5073 2199 5073 2199 5074 2539 5074 2540 5074 2199 5075 2540 5075 2200 5075 2200 5076 2540 5076 2541 5076 2200 5077 2541 5077 2202 5077 2202 5078 2541 5078 2543 5078 2202 5079 2543 5079 2542 5079 2542 5080 2543 5080 827 5080 2542 5081 827 5081 2204 5081 2204 5082 827 5082 826 5082 2204 5083 826 5083 2544 5083 2544 5084 826 5084 824 5084 2222 5085 808 5085 2545 5085 2545 5086 808 5086 807 5086 2545 5087 807 5087 2208 5087 2208 5088 807 5088 805 5088 2208 5089 805 5089 2210 5089 2210 5090 805 5090 804 5090 2210 5091 804 5091 2546 5091 2546 5092 804 5092 2547 5092 2546 5093 2547 5093 2211 5093 2211 5094 2547 5094 802 5094 2211 5095 802 5095 2214 5095 2214 5096 802 5096 801 5096 2214 5097 801 5097 2215 5097 2215 5098 801 5098 815 5098 2215 5099 815 5099 2216 5099 2216 5100 815 5100 814 5100 2216 5101 814 5101 2217 5101 2217 5102 814 5102 812 5102 2217 5103 812 5103 2219 5103 2219 5104 812 5104 811 5104 2219 5105 811 5105 2548 5105 2548 5106 811 5106 2549 5106 2548 5107 2549 5107 2222 5107 2222 5108 2549 5108 808 5108 2192 5109 838 5109 2185 5109 2185 5110 838 5110 837 5110 2185 5111 837 5111 2186 5111 2186 5112 837 5112 836 5112 2186 5113 836 5113 2550 5113 2550 5114 836 5114 834 5114 2550 5115 834 5115 2551 5115 2551 5116 834 5116 832 5116 2551 5117 832 5117 2552 5117 2552 5118 832 5118 2553 5118 2552 5119 2553 5119 2554 5119 2554 5120 2553 5120 2555 5120 2554 5121 2555 5121 2556 5121 2556 5122 2555 5122 843 5122 2556 5123 843 5123 2557 5123 2557 5124 843 5124 841 5124 2557 5125 841 5125 2189 5125 2189 5126 841 5126 2559 5126 2189 5127 2559 5127 2558 5127 2558 5128 2559 5128 2560 5128 2558 5129 2560 5129 2190 5129 2190 5130 2560 5130 2561 5130 2190 5131 2561 5131 2192 5131 2192 5132 2561 5132 838 5132 2182 5133 2562 5133 2168 5133 2168 5134 2562 5134 2563 5134 2168 5135 2563 5135 2170 5135 2170 5136 2563 5136 2023 5136 2170 5137 2023 5137 2171 5137 2171 5138 2023 5138 2564 5138 2171 5139 2564 5139 2565 5139 2565 5140 2564 5140 2566 5140 2565 5141 2566 5141 2567 5141 2567 5142 2566 5142 2020 5142 2567 5143 2020 5143 2174 5143 2174 5144 2020 5144 2018 5144 2174 5145 2018 5145 2176 5145 2176 5146 2018 5146 2568 5146 2176 5147 2568 5147 2178 5147 2178 5148 2568 5148 2031 5148 2178 5149 2031 5149 2180 5149 2180 5150 2031 5150 2029 5150 2180 5151 2029 5151 2181 5151 2181 5152 2029 5152 2028 5152 2181 5153 2028 5153 2569 5153 2569 5154 2028 5154 2025 5154 2569 5155 2025 5155 2182 5155 2182 5156 2025 5156 2562 5156 2167 5157 2571 5157 2570 5157 2570 5158 2571 5158 848 5158 2570 5159 848 5159 2159 5159 2159 5160 848 5160 2572 5160 2159 5161 2572 5161 2573 5161 2573 5162 2572 5162 846 5162 2573 5163 846 5163 2160 5163 2160 5164 846 5164 2574 5164 2160 5165 2574 5165 2161 5165 2161 5166 2574 5166 856 5166 2161 5167 856 5167 2575 5167 2575 5168 856 5168 2576 5168 2575 5169 2576 5169 2163 5169 2163 5170 2576 5170 2578 5170 2163 5171 2578 5171 2577 5171 2577 5172 2578 5172 854 5172 2577 5173 854 5173 2165 5173 2165 5174 854 5174 2579 5174 2165 5175 2579 5175 2580 5175 2580 5176 2579 5176 852 5176 2580 5177 852 5177 2166 5177 2166 5178 852 5178 851 5178 2166 5179 851 5179 2167 5179 2167 5180 851 5180 2571 5180 2155 5181 2588 5181 2157 5181 2157 5182 2588 5182 868 5182 2157 5183 868 5183 2581 5183 2581 5184 868 5184 867 5184 2581 5185 867 5185 2145 5185 2145 5186 867 5186 866 5186 2145 5187 866 5187 2147 5187 2147 5188 866 5188 865 5188 2147 5189 865 5189 2148 5189 2148 5190 865 5190 864 5190 2148 5191 864 5191 2582 5191 2582 5192 864 5192 863 5192 2582 5193 863 5193 2151 5193 2151 5194 863 5194 862 5194 2151 5195 862 5195 2153 5195 2153 5196 862 5196 2583 5196 2153 5197 2583 5197 2154 5197 2154 5198 2583 5198 859 5198 2154 5199 859 5199 2585 5199 2585 5200 859 5200 2584 5200 2585 5201 2584 5201 2587 5201 2587 5202 2584 5202 2586 5202 2587 5203 2586 5203 2155 5203 2155 5204 2586 5204 2588 5204 2596 5205 1285 5205 2402 5205 2402 5206 1285 5206 1286 5206 2402 5207 1286 5207 2589 5207 2589 5208 1286 5208 1280 5208 2589 5209 1280 5209 2404 5209 2404 5210 1280 5210 1283 5210 2404 5211 1283 5211 2590 5211 2590 5212 1283 5212 1282 5212 2590 5213 1282 5213 2406 5213 2406 5214 1282 5214 2592 5214 2406 5215 2592 5215 2591 5215 2591 5216 2592 5216 1297 5216 2591 5217 1297 5217 2407 5217 2407 5218 1297 5218 2593 5218 2407 5219 2593 5219 2409 5219 2409 5220 2593 5220 1289 5220 2409 5221 1289 5221 2410 5221 2410 5222 1289 5222 1291 5222 2410 5223 1291 5223 2412 5223 2412 5224 1291 5224 1300 5224 2412 5225 1300 5225 2594 5225 2594 5226 1300 5226 2595 5226 2594 5227 2595 5227 2596 5227 2596 5228 2595 5228 1285 5228 28 5229 736 5229 29 5229 29 5230 736 5230 735 5230 29 5231 735 5231 37 5231 37 5232 735 5232 2598 5232 37 5233 2598 5233 2597 5233 2597 5234 2598 5234 2599 5234 2597 5235 2599 5235 2600 5235 2600 5236 2599 5236 726 5236 2600 5237 726 5237 2034 5237 2617 5238 81 5238 1621 5238 2602 5239 1616 5239 2607 5239 2607 5240 1616 5240 1673 5240 2607 5241 1673 5241 2605 5241 2607 5242 2601 5242 2602 5242 2602 5243 2601 5243 2610 5243 2602 5244 2610 5244 1617 5244 1617 5245 2610 5245 2611 5245 1617 5246 2611 5246 2604 5246 2604 5247 2611 5247 2603 5247 1621 5248 1704 5248 2617 5248 2617 5249 1704 5249 1703 5249 2617 5250 1703 5250 2614 5250 2614 5251 1703 5251 1620 5251 2614 5252 1620 5252 2603 5252 2603 5253 1620 5253 1619 5253 2603 5254 1619 5254 2604 5254 2605 5255 2638 5255 2607 5255 2607 5256 2638 5256 2606 5256 2607 5257 2606 5257 2601 5257 2601 5258 2606 5258 2608 5258 2601 5259 2608 5259 2610 5259 2610 5260 2608 5260 2609 5260 2610 5261 2609 5261 2611 5261 2611 5262 2609 5262 2612 5262 2611 5263 2612 5263 2603 5263 2603 5264 2612 5264 2613 5264 2603 5265 2613 5265 2614 5265 2614 5266 2613 5266 2615 5266 2614 5267 2615 5267 2617 5267 2617 5268 2615 5268 2616 5268 2617 5269 2616 5269 81 5269 81 5270 2616 5270 114 5270 2058 5271 2618 5271 2059 5271 2059 5272 2618 5272 2634 5272 2059 5273 2634 5273 2060 5273 2060 5274 2634 5274 2619 5274 2619 5275 2634 5275 2632 5275 2619 5276 2632 5276 2620 5276 2620 5277 2632 5277 2621 5277 2621 5278 2632 5278 2631 5278 2621 5279 2631 5279 2630 5279 2639 5280 120 5280 2640 5280 2640 5281 120 5281 79 5281 2640 5282 79 5282 2630 5282 2628 5283 2629 5283 2622 5283 2622 5284 2629 5284 2623 5284 2622 5285 2623 5285 2637 5285 2637 5286 2623 5286 2624 5286 2637 5287 2624 5287 104 5287 104 5288 2624 5288 2625 5288 104 5289 2625 5289 2065 5289 2058 5290 2626 5290 2618 5290 2618 5291 2626 5291 2061 5291 2618 5292 2061 5292 2628 5292 2628 5293 2061 5293 2627 5293 2628 5294 2627 5294 2629 5294 2630 5295 2631 5295 2640 5295 2640 5296 2631 5296 2632 5296 2640 5297 2632 5297 2633 5297 2633 5298 2632 5298 2634 5298 2633 5299 2634 5299 2641 5299 2641 5300 2634 5300 2618 5300 2641 5301 2618 5301 2635 5301 2635 5302 2618 5302 2628 5302 2635 5303 2628 5303 2636 5303 2636 5304 2628 5304 2622 5304 2636 5305 2622 5305 2642 5305 2642 5306 2622 5306 2637 5306 2642 5307 2637 5307 2643 5307 2643 5308 2637 5308 104 5308 2643 5309 104 5309 116 5309 2638 5310 2639 5310 2606 5310 2606 5311 2639 5311 2640 5311 2606 5312 2640 5312 2608 5312 2608 5313 2640 5313 2633 5313 2608 5314 2633 5314 2609 5314 2609 5315 2633 5315 2641 5315 2609 5316 2641 5316 2612 5316 2612 5317 2641 5317 2635 5317 2612 5318 2635 5318 2613 5318 2613 5319 2635 5319 2636 5319 2613 5320 2636 5320 2615 5320 2615 5321 2636 5321 2642 5321 2615 5322 2642 5322 2616 5322 2616 5323 2642 5323 2643 5323 2616 5324 2643 5324 114 5324 114 5325 2643 5325 116 5325 2656 5326 2644 5326 2044 5326 2044 5327 2644 5327 2645 5327 2044 5328 2645 5328 2047 5328 2047 5329 2645 5329 2646 5329 2047 5330 2646 5330 2049 5330 2049 5331 2646 5331 2647 5331 2049 5332 2647 5332 2052 5332 2052 5333 2647 5333 1075 5333 2052 5334 1075 5334 2649 5334 2649 5335 1075 5335 2648 5335 2649 5336 2648 5336 2650 5336 2650 5337 2648 5337 1076 5337 2650 5338 1076 5338 2651 5338 2651 5339 1076 5339 1067 5339 2651 5340 1067 5340 2054 5340 2054 5341 1067 5341 2652 5341 2054 5342 2652 5342 2653 5342 2653 5343 2652 5343 2654 5343 2653 5344 2654 5344 2056 5344 2056 5345 2654 5345 1069 5345 2056 5346 1069 5346 2043 5346 2043 5347 1069 5347 2655 5347 2043 5348 2655 5348 2656 5348 2656 5349 2655 5349 2644 5349 2659 5350 2661 5350 2657 5350 2657 5351 1909 5351 9 5351 9 5352 6 5352 2657 5352 2657 5353 6 5353 2658 5353 2657 5354 2658 5354 2659 5354 2662 5355 2660 5355 2661 5355 2660 5356 2662 5356 1844 5356 14 5357 2668 5357 2663 5357 2663 5358 2668 5358 2664 5358 14 5359 2665 5359 2668 5359 2668 5360 2665 5360 2666 5360 2668 5361 2666 5361 2669 5361 1959 5362 950 5362 2667 5362 2667 5363 950 5363 776 5363 2667 5364 776 5364 2668 5364 2668 5365 776 5365 12 5365 2668 5366 12 5366 2664 5366 2669 5367 2670 5367 2668 5367 2668 5368 2670 5368 22 5368 2668 5369 22 5369 1889 5369 1959 5370 1965 5370 950 5370 950 5371 1965 5371 2671 5371 950 5372 2671 5372 930 5372 930 5373 2671 5373 1978 5373 2672 5374 50 5374 51 5374 51 5375 50 5375 2673 5375 51 5376 2673 5376 2674 5376 2674 5377 2673 5377 930 5377 2674 5378 930 5378 2675 5378 2675 5379 930 5379 1978 5379 1878 5380 1875 5380 2676 5380 2676 5381 1875 5381 1874 5381 0 5382 2677 5382 1 5382 1 5383 2677 5383 2678 5383 1 5384 2678 5384 3 5384 3 5385 2678 5385 1878 5385 4464 5386 2679 5386 4466 5386 4466 5387 2679 5387 6314 5387 4466 5388 6314 5388 2680 5388 2680 5389 6314 5389 2682 5389 2680 5390 2682 5390 2681 5390 2681 5391 2682 5391 2683 5391 2681 5392 2683 5392 4468 5392 4468 5393 2683 5393 6313 5393 4468 5394 6313 5394 4460 5394 4460 5395 6313 5395 2684 5395 4460 5396 2684 5396 4462 5396 4462 5397 2684 5397 6315 5397 2685 5398 2686 5398 4454 5398 4454 5399 2686 5399 6311 5399 4454 5400 6311 5400 2687 5400 2687 5401 6311 5401 2688 5401 2687 5402 2688 5402 4450 5402 4450 5403 2688 5403 2690 5403 4450 5404 2690 5404 2689 5404 2689 5405 2690 5405 2691 5405 2689 5406 2691 5406 4456 5406 4456 5407 2691 5407 6309 5407 4456 5408 6309 5408 2692 5408 2692 5409 6309 5409 6308 5409 2692 5410 6308 5410 4457 5410 4457 5411 6308 5411 2782 5411 2794 5412 6304 5412 4447 5412 4447 5413 6304 5413 6306 5413 4447 5414 6306 5414 2693 5414 2693 5415 6306 5415 2694 5415 2693 5416 2694 5416 2695 5416 2695 5417 2694 5417 2696 5417 2695 5418 2696 5418 2697 5418 2697 5419 2696 5419 6301 5419 2697 5420 6301 5420 2698 5420 2698 5421 6301 5421 6305 5421 2698 5422 6305 5422 4455 5422 4455 5423 6305 5423 2787 5423 2802 5424 2700 5424 2699 5424 2699 5425 2700 5425 2701 5425 2699 5426 2701 5426 2702 5426 2702 5427 2701 5427 6299 5427 2702 5428 6299 5428 4434 5428 4434 5429 6299 5429 2704 5429 4434 5430 2704 5430 2703 5430 2703 5431 2704 5431 6295 5431 2703 5432 6295 5432 2705 5432 2705 5433 6295 5433 2706 5433 2705 5434 2706 5434 2707 5434 2707 5435 2706 5435 6296 5435 2707 5436 6296 5436 2708 5436 2708 5437 6296 5437 6300 5437 2809 5438 2710 5438 2709 5438 2709 5439 2710 5439 6294 5439 2709 5440 6294 5440 4490 5440 4490 5441 6294 5441 2711 5441 4490 5442 2711 5442 2712 5442 2712 5443 2711 5443 6290 5443 2712 5444 6290 5444 2713 5444 2713 5445 6290 5445 2714 5445 2713 5446 2714 5446 2715 5446 2715 5447 2714 5447 2716 5447 2715 5448 2716 5448 2717 5448 2717 5449 2716 5449 6289 5449 2717 5450 6289 5450 2803 5450 2803 5451 6289 5451 2805 5451 4525 5452 6288 5452 2718 5452 2718 5453 6288 5453 2719 5453 2718 5454 2719 5454 4526 5454 4526 5455 2719 5455 6285 5455 4526 5456 6285 5456 2720 5456 2720 5457 6285 5457 2721 5457 2720 5458 2721 5458 4527 5458 4527 5459 2721 5459 2722 5459 4527 5460 2722 5460 4528 5460 4528 5461 2722 5461 2724 5461 4528 5462 2724 5462 2723 5462 2723 5463 2724 5463 2726 5463 2723 5464 2726 5464 2725 5464 2725 5465 2726 5465 2727 5465 4516 5466 6284 5466 2728 5466 2728 5467 6284 5467 2730 5467 2728 5468 2730 5468 2729 5468 2729 5469 2730 5469 6280 5469 2729 5470 6280 5470 4518 5470 4518 5471 6280 5471 6279 5471 4518 5472 6279 5472 4519 5472 4519 5473 6279 5473 6282 5473 4519 5474 6282 5474 4520 5474 4520 5475 6282 5475 2732 5475 4520 5476 2732 5476 2731 5476 2731 5477 2732 5477 6281 5477 2731 5478 6281 5478 4522 5478 4522 5479 6281 5479 2815 5479 4476 5480 2733 5480 2734 5480 2734 5481 2733 5481 2735 5481 2734 5482 2735 5482 4539 5482 4539 5483 2735 5483 6274 5483 4539 5484 6274 5484 2736 5484 2736 5485 6274 5485 2737 5485 2736 5486 2737 5486 4474 5486 4474 5487 2737 5487 2738 5487 4474 5488 2738 5488 2739 5488 2739 5489 2738 5489 6276 5489 2739 5490 6276 5490 2740 5490 2740 5491 6276 5491 6277 5491 2740 5492 6277 5492 4511 5492 4511 5493 6277 5493 2821 5493 4508 5494 2741 5494 2742 5494 2742 5495 2741 5495 6270 5495 2742 5496 6270 5496 4505 5496 4505 5497 6270 5497 2743 5497 4505 5498 2743 5498 4506 5498 4506 5499 2743 5499 2744 5499 4506 5500 2744 5500 4507 5500 4507 5501 2744 5501 6269 5501 4507 5502 6269 5502 4417 5502 4417 5503 6269 5503 2745 5503 4417 5504 2745 5504 2746 5504 2746 5505 2745 5505 6272 5505 4472 5506 2842 5506 4469 5506 4469 5507 2842 5507 6267 5507 4469 5508 6267 5508 4498 5508 4498 5509 6267 5509 6268 5509 4498 5510 6268 5510 2747 5510 2747 5511 6268 5511 2748 5511 2747 5512 2748 5512 2749 5512 2749 5513 2748 5513 6266 5513 2749 5514 6266 5514 4500 5514 4500 5515 6266 5515 2750 5515 4500 5516 2750 5516 4502 5516 4502 5517 2750 5517 2835 5517 2851 5518 2751 5518 2752 5518 2752 5519 2751 5519 2753 5519 2752 5520 2753 5520 2754 5520 2754 5521 2753 5521 2755 5521 2754 5522 2755 5522 4423 5522 4423 5523 2755 5523 6259 5523 4423 5524 6259 5524 4424 5524 4424 5525 6259 5525 2756 5525 4424 5526 2756 5526 2757 5526 2757 5527 2756 5527 6260 5527 2757 5528 6260 5528 2758 5528 2758 5529 6260 5529 2760 5529 2758 5530 2760 5530 2759 5530 2759 5531 2760 5531 2761 5531 2858 5532 2762 5532 2763 5532 2763 5533 2762 5533 2764 5533 2763 5534 2764 5534 2765 5534 2765 5535 2764 5535 2766 5535 2765 5536 2766 5536 4440 5536 4440 5537 2766 5537 2767 5537 4440 5538 2767 5538 4439 5538 4439 5539 2767 5539 2769 5539 4439 5540 2769 5540 2768 5540 2768 5541 2769 5541 6255 5541 2768 5542 6255 5542 2852 5542 2852 5543 6255 5543 2853 5543 2772 5544 2770 5544 2774 5544 4615 5545 2771 5545 2772 5545 2980 5546 4615 5546 2773 5546 2773 5547 4615 5547 2772 5547 2773 5548 2772 5548 3210 5548 3210 5549 2772 5549 2774 5549 4462 5550 6315 5550 2775 5550 2775 5551 6315 5551 2776 5551 2775 5552 2776 5552 2777 5552 2777 5553 2776 5553 2778 5553 2777 5554 2778 5554 2779 5554 2779 5555 2778 5555 6312 5555 2779 5556 6312 5556 4463 5556 4463 5557 6312 5557 2781 5557 4463 5558 2781 5558 2780 5558 2780 5559 2781 5559 6316 5559 2780 5560 6316 5560 4464 5560 4464 5561 6316 5561 2679 5561 4457 5562 2782 5562 4426 5562 4426 5563 2782 5563 2783 5563 4426 5564 2783 5564 2784 5564 2784 5565 2783 5565 2785 5565 2784 5566 2785 5566 4428 5566 4428 5567 2785 5567 6307 5567 4428 5568 6307 5568 4429 5568 4429 5569 6307 5569 6310 5569 4429 5570 6310 5570 4451 5570 4451 5571 6310 5571 2786 5571 4451 5572 2786 5572 2685 5572 2685 5573 2786 5573 2686 5573 4455 5574 2787 5574 4540 5574 4540 5575 2787 5575 2788 5575 4540 5576 2788 5576 2789 5576 2789 5577 2788 5577 6303 5577 2789 5578 6303 5578 2790 5578 2790 5579 6303 5579 6302 5579 2790 5580 6302 5580 2792 5580 2792 5581 6302 5581 2791 5581 2792 5582 2791 5582 4446 5582 4446 5583 2791 5583 2793 5583 4446 5584 2793 5584 2794 5584 2794 5585 2793 5585 6304 5585 2708 5586 6300 5586 2795 5586 2795 5587 6300 5587 2796 5587 2795 5588 2796 5588 2797 5588 2797 5589 2796 5589 2798 5589 2797 5590 2798 5590 2799 5590 2799 5591 2798 5591 6298 5591 2799 5592 6298 5592 2800 5592 2800 5593 6298 5593 6297 5593 2800 5594 6297 5594 4433 5594 4433 5595 6297 5595 2801 5595 4433 5596 2801 5596 2802 5596 2802 5597 2801 5597 2700 5597 2803 5598 2805 5598 2804 5598 2804 5599 2805 5599 6293 5599 2804 5600 6293 5600 2806 5600 2806 5601 6293 5601 2807 5601 2806 5602 2807 5602 4485 5602 4485 5603 2807 5603 6292 5603 4485 5604 6292 5604 4436 5604 4436 5605 6292 5605 6291 5605 4436 5606 6291 5606 4486 5606 4486 5607 6291 5607 2808 5607 4486 5608 2808 5608 2809 5608 2809 5609 2808 5609 2710 5609 2725 5610 2727 5610 4530 5610 4530 5611 2727 5611 2811 5611 4530 5612 2811 5612 2810 5612 2810 5613 2811 5613 6286 5613 2810 5614 6286 5614 2813 5614 2813 5615 6286 5615 2812 5615 2813 5616 2812 5616 4482 5616 4482 5617 2812 5617 6287 5617 4482 5618 6287 5618 4524 5618 4524 5619 6287 5619 2814 5619 4524 5620 2814 5620 4525 5620 4525 5621 2814 5621 6288 5621 4522 5622 2815 5622 2816 5622 2816 5623 2815 5623 2817 5623 2816 5624 2817 5624 4477 5624 4477 5625 2817 5625 2818 5625 4477 5626 2818 5626 4478 5626 4478 5627 2818 5627 2819 5627 4478 5628 2819 5628 4480 5628 4480 5629 2819 5629 6283 5629 4480 5630 6283 5630 4515 5630 4515 5631 6283 5631 2820 5631 4515 5632 2820 5632 4516 5632 4516 5633 2820 5633 6284 5633 4511 5634 2821 5634 2822 5634 2822 5635 2821 5635 2824 5635 2822 5636 2824 5636 2823 5636 2823 5637 2824 5637 2825 5637 2823 5638 2825 5638 4513 5638 4513 5639 2825 5639 6275 5639 4513 5640 6275 5640 2826 5640 2826 5641 6275 5641 2828 5641 2826 5642 2828 5642 2827 5642 2827 5643 2828 5643 6278 5643 2827 5644 6278 5644 4476 5644 4476 5645 6278 5645 2733 5645 2746 5646 6272 5646 2829 5646 2829 5647 6272 5647 6273 5647 2829 5648 6273 5648 4509 5648 4509 5649 6273 5649 2830 5649 4509 5650 2830 5650 2831 5650 2831 5651 2830 5651 2832 5651 2831 5652 2832 5652 2833 5652 2833 5653 2832 5653 6271 5653 2833 5654 6271 5654 4510 5654 4510 5655 6271 5655 2834 5655 4510 5656 2834 5656 4508 5656 4508 5657 2834 5657 2741 5657 4502 5658 2835 5658 4504 5658 4504 5659 2835 5659 6263 5659 4504 5660 6263 5660 2836 5660 2836 5661 6263 5661 2838 5661 2836 5662 2838 5662 2837 5662 2837 5663 2838 5663 6262 5663 2837 5664 6262 5664 2839 5664 2839 5665 6262 5665 2840 5665 2839 5666 2840 5666 4471 5666 4471 5667 2840 5667 6264 5667 4471 5668 6264 5668 2841 5668 2841 5669 6264 5669 6265 5669 2841 5670 6265 5670 4472 5670 4472 5671 6265 5671 2842 5671 2759 5672 2761 5672 2844 5672 2844 5673 2761 5673 2843 5673 2844 5674 2843 5674 2845 5674 2845 5675 2843 5675 2846 5675 2845 5676 2846 5676 4421 5676 4421 5677 2846 5677 6261 5677 4421 5678 6261 5678 2847 5678 2847 5679 6261 5679 2848 5679 2847 5680 2848 5680 2850 5680 2850 5681 2848 5681 2849 5681 2850 5682 2849 5682 2851 5682 2851 5683 2849 5683 2751 5683 2852 5684 2853 5684 4493 5684 4493 5685 2853 5685 2854 5685 4493 5686 2854 5686 2855 5686 2855 5687 2854 5687 6258 5687 2855 5688 6258 5688 4496 5688 4496 5689 6258 5689 2857 5689 4496 5690 2857 5690 2856 5690 2856 5691 2857 5691 6257 5691 2856 5692 6257 5692 4497 5692 4497 5693 6257 5693 6256 5693 4497 5694 6256 5694 2858 5694 2858 5695 6256 5695 2762 5695 3159 5696 2859 5696 3157 5696 3157 5697 2859 5697 2860 5697 6150 5698 6151 5698 2860 5698 2860 5699 6151 5699 2861 5699 2860 5700 2861 5700 3157 5700 5051 5701 2860 5701 2864 5701 2864 5702 2860 5702 2859 5702 2860 5703 5051 5703 2862 5703 2862 5704 5051 5704 2863 5704 2859 5705 2865 5705 2864 5705 2864 5706 2865 5706 2866 5706 2864 5707 2866 5707 5051 5707 4805 5708 2869 5708 2867 5708 2867 5709 2869 5709 3188 5709 2867 5710 3188 5710 2868 5710 2868 5711 3188 5711 4810 5711 4810 5712 3188 5712 3182 5712 4810 5713 3182 5713 4809 5713 4809 5714 3182 5714 3184 5714 4809 5715 3184 5715 4806 5715 4806 5716 3184 5716 2862 5716 4806 5717 2862 5717 2863 5717 2869 5718 4805 5718 2870 5718 2870 5719 4805 5719 6194 5719 2870 5720 6194 5720 3197 5720 3197 5721 6194 5721 2871 5721 3197 5722 2871 5722 3200 5722 3200 5723 2871 5723 5056 5723 3200 5724 5056 5724 3199 5724 3199 5725 5056 5725 5055 5725 3199 5726 5055 5726 2872 5726 2872 5727 5055 5727 5057 5727 2874 5728 3203 5728 5279 5728 2874 5729 5279 5729 2873 5729 2873 5730 5279 5730 2872 5730 2873 5731 2872 5731 5057 5731 3203 5732 2874 5732 3204 5732 3204 5733 2874 5733 2875 5733 3204 5734 2875 5734 3207 5734 3207 5735 2875 5735 5054 5735 3207 5736 5054 5736 3208 5736 3208 5737 5054 5737 5052 5737 3208 5738 5052 5738 2876 5738 2876 5739 5052 5739 6206 5739 2876 5740 6206 5740 2880 5740 2880 5741 6206 5741 6209 5741 5062 5742 2881 5742 4800 5742 4800 5743 2881 5743 3194 5743 4800 5744 3194 5744 2877 5744 2877 5745 3194 5745 2878 5745 2877 5746 2878 5746 2879 5746 2879 5747 2878 5747 3191 5747 2879 5748 3191 5748 4804 5748 4804 5749 3191 5749 2880 5749 4804 5750 2880 5750 6209 5750 2881 5751 5062 5751 2882 5751 2882 5752 5062 5752 2893 5752 6234 5753 5059 5753 2883 5753 2883 5754 5059 5754 2885 5754 2883 5755 2885 5755 2884 5755 2884 5756 2885 5756 6232 5756 2886 5757 6240 5757 2889 5757 2889 5758 6240 5758 6241 5758 2889 5759 6241 5759 2887 5759 2887 5760 6241 5760 2888 5760 2887 5761 5470 5761 2889 5761 2889 5762 5470 5762 2890 5762 2889 5763 2890 5763 5058 5763 5058 5764 2890 5764 2891 5764 5058 5765 2891 5765 5059 5765 5059 5766 2891 5766 5473 5766 5059 5767 5473 5767 2885 5767 2895 5768 2882 5768 2892 5768 2892 5769 2882 5769 2893 5769 2895 5770 3167 5770 2882 5770 2882 5771 3167 5771 3165 5771 2882 5772 3165 5772 3164 5772 2893 5773 5061 5773 2892 5773 2892 5774 5061 5774 2894 5774 2892 5775 2894 5775 2895 5775 5025 5776 2897 5776 2896 5776 2896 5777 2897 5777 3220 5777 2896 5778 3220 5778 3222 5778 2900 5779 3220 5779 2898 5779 2898 5780 3220 5780 2897 5780 3220 5781 2900 5781 2899 5781 2899 5782 2900 5782 2906 5782 2897 5783 5027 5783 2898 5783 2898 5784 5027 5784 6211 5784 2898 5785 6211 5785 2900 5785 2908 5786 3218 5786 2901 5786 2901 5787 3218 5787 2903 5787 2901 5788 2903 5788 2902 5788 2902 5789 2903 5789 2904 5789 2904 5790 2903 5790 3215 5790 2904 5791 3215 5791 4798 5791 4798 5792 3215 5792 3216 5792 4798 5793 3216 5793 2905 5793 2905 5794 3216 5794 2899 5794 2905 5795 2899 5795 2906 5795 3218 5796 2908 5796 2907 5796 2907 5797 2908 5797 2909 5797 2907 5798 2909 5798 3226 5798 3226 5799 2909 5799 5041 5799 3226 5800 5041 5800 3228 5800 3228 5801 5041 5801 2910 5801 3228 5802 2910 5802 3232 5802 3232 5803 2910 5803 5043 5803 3232 5804 5043 5804 2911 5804 2911 5805 5043 5805 5044 5805 5047 5806 3223 5806 5280 5806 5047 5807 5280 5807 5045 5807 5045 5808 5280 5808 2911 5808 5045 5809 2911 5809 5044 5809 3223 5810 5047 5810 2912 5810 2912 5811 5047 5811 2913 5811 2912 5812 2913 5812 2914 5812 2914 5813 2913 5813 2915 5813 2914 5814 2915 5814 2916 5814 2916 5815 2915 5815 2917 5815 2916 5816 2917 5816 3224 5816 3224 5817 2917 5817 2918 5817 3224 5818 2918 5818 3211 5818 3211 5819 2918 5819 6198 5819 2925 5820 3212 5820 2919 5820 2919 5821 3212 5821 2921 5821 2919 5822 2921 5822 2920 5822 2920 5823 2921 5823 3209 5823 2920 5824 3209 5824 2922 5824 2922 5825 3209 5825 2923 5825 2922 5826 2923 5826 2924 5826 2924 5827 2923 5827 3211 5827 2924 5828 3211 5828 6198 5828 3212 5829 2925 5829 2934 5829 2934 5830 2925 5830 5050 5830 5042 5831 6224 5831 5464 5831 5464 5832 6224 5832 6225 5832 5464 5833 6225 5833 5461 5833 5468 5834 2926 5834 6228 5834 6228 5835 2927 5835 5468 5835 5468 5836 2927 5836 5048 5836 5468 5837 5048 5837 2928 5837 5042 5838 5464 5838 5046 5838 5046 5839 5464 5839 5463 5839 5046 5840 5463 5840 2929 5840 5463 5841 2930 5841 2929 5841 2929 5842 2930 5842 2931 5842 2929 5843 2931 5843 2928 5843 2928 5844 2931 5844 2932 5844 2928 5845 2932 5845 5468 5845 2933 5846 2934 5846 2937 5846 2937 5847 2934 5847 5050 5847 2933 5848 5005 5848 2934 5848 2934 5849 5005 5849 6155 5849 6155 5850 2935 5850 2934 5850 2934 5851 2935 5851 2936 5851 2934 5852 2936 5852 3213 5852 5050 5853 5049 5853 2937 5853 2937 5854 5049 5854 2938 5854 2937 5855 2938 5855 2933 5855 2939 5856 3217 5856 2940 5856 2940 5857 3217 5857 2942 5857 2942 5858 4616 5858 2940 5858 2940 5859 4616 5859 2941 5859 2940 5860 2941 5860 5063 5860 4617 5861 4616 5861 2950 5861 2950 5862 4616 5862 2942 5862 2950 5863 2942 5863 2943 5863 2943 5864 2942 5864 3217 5864 2952 5865 3221 5865 2944 5865 2944 5866 3221 5866 3219 5866 2944 5867 3219 5867 4650 5867 4650 5868 3219 5868 4649 5868 4649 5869 3219 5869 2945 5869 4649 5870 2945 5870 2947 5870 2947 5871 2945 5871 2946 5871 2947 5872 2946 5872 4648 5872 4648 5873 2946 5873 2939 5873 4648 5874 2939 5874 2940 5874 2951 5875 4617 5875 2950 5875 6220 5876 2948 5876 2953 5876 2953 5877 2948 5877 2943 5877 2943 5878 2948 5878 2950 5878 2950 5879 2948 5879 2949 5879 2950 5880 2949 5880 2951 5880 3221 5881 2952 5881 2960 5881 2960 5882 2952 5882 2961 5882 6220 5883 2953 5883 4925 5883 4925 5884 2953 5884 3227 5884 4925 5885 3227 5885 4924 5885 4924 5886 3227 5886 4836 5886 4836 5887 3227 5887 3229 5887 4836 5888 3229 5888 2966 5888 2954 5889 3169 5889 3171 5889 2954 5890 3171 5890 2955 5890 2955 5891 3171 5891 2956 5891 2955 5892 2956 5892 2957 5892 2957 5893 2956 5893 2959 5893 2957 5894 2959 5894 2958 5894 2958 5895 2959 5895 2960 5895 2958 5896 2960 5896 2961 5896 2962 5897 3231 5897 2963 5897 2963 5898 3231 5898 3230 5898 2963 5899 3230 5899 4832 5899 4832 5900 3230 5900 2964 5900 4832 5901 2964 5901 2965 5901 2965 5902 2964 5902 2967 5902 2965 5903 2967 5903 4833 5903 2962 5904 4837 5904 3231 5904 3231 5905 4837 5905 4836 5905 3231 5906 4836 5906 2966 5906 4833 5907 2967 5907 2968 5907 2968 5908 2967 5908 2969 5908 2968 5909 2969 5909 4835 5909 4835 5910 2969 5910 4831 5910 4831 5911 2969 5911 2970 5911 4831 5912 2970 5912 4829 5912 2971 5913 2977 5913 4548 5913 2971 5914 4548 5914 2973 5914 4548 5915 4824 5915 2973 5915 2973 5916 4824 5916 4897 5916 2973 5917 4897 5917 4828 5917 4829 5918 2970 5918 4830 5918 4830 5919 2970 5919 2972 5919 4830 5920 2972 5920 2974 5920 2974 5921 2972 5921 2973 5921 2974 5922 2973 5922 4826 5922 4826 5923 2973 5923 4828 5923 3225 5924 2774 5924 2770 5924 2770 5925 2975 5925 3225 5925 3225 5926 2975 5926 4546 5926 3225 5927 4546 5927 2976 5927 2976 5928 4546 5928 4548 5928 2976 5929 4548 5929 2977 5929 3210 5930 2978 5930 2773 5930 2773 5931 2978 5931 2979 5931 2773 5932 2979 5932 2980 5932 2980 5933 2979 5933 2981 5933 4613 5934 2981 5934 2979 5934 4612 5935 4613 5935 2982 5935 2982 5936 4613 5936 2979 5936 2982 5937 2979 5937 2983 5937 2983 5938 2979 5938 2978 5938 2982 5939 2983 5939 2984 5939 2984 5940 2983 5940 2986 5940 2984 5941 2986 5941 2985 5941 2985 5942 2986 5942 3214 5942 2985 5943 3214 5943 4639 5943 4639 5944 3214 5944 2987 5944 4639 5945 2987 5945 2989 5945 2989 5946 2987 5946 2988 5946 2989 5947 2988 5947 5071 5947 5071 5948 2988 5948 5070 5948 5070 5949 2988 5949 3173 5949 5070 5950 3173 5950 3174 5950 5070 5951 3174 5951 2991 5951 2991 5952 3174 5952 2990 5952 2991 5953 2990 5953 5076 5953 5076 5954 2990 5954 2992 5954 5076 5955 2992 5955 5075 5955 5075 5956 2992 5956 5066 5956 5075 5957 5066 5957 5064 5957 2995 5958 2993 5958 2994 5958 6204 5959 6205 5959 3196 5959 3196 5960 6205 5960 3183 5960 3183 5961 6205 5961 2994 5961 2994 5962 6205 5962 4555 5962 2994 5963 4555 5963 2995 5963 6204 5964 3196 5964 2996 5964 2996 5965 3196 5965 2997 5965 2996 5966 2997 5966 2998 5966 2998 5967 2997 5967 3005 5967 3005 5968 2997 5968 3202 5968 3005 5969 3202 5969 3201 5969 2993 5970 2999 5970 2994 5970 2994 5971 2999 5971 3007 5971 2994 5972 3007 5972 3183 5972 3183 5973 3007 5973 3185 5973 3000 5974 3001 5974 5558 5974 5558 5975 3001 5975 3198 5975 5558 5976 3198 5976 5559 5976 5559 5977 3198 5977 3003 5977 5559 5978 3003 5978 3002 5978 3002 5979 3003 5979 3004 5979 3002 5980 3004 5980 5561 5980 3000 5981 5562 5981 3001 5981 3001 5982 5562 5982 3005 5982 3001 5983 3005 5983 3201 5983 3006 5984 3185 5984 3008 5984 3008 5985 3185 5985 3007 5985 3007 5986 2999 5986 3008 5986 3008 5987 2999 5987 3009 5987 3008 5988 3009 5988 4619 5988 5561 5989 3004 5989 3011 5989 3011 5990 3004 5990 3010 5990 3011 5991 3010 5991 5557 5991 5557 5992 3010 5992 3012 5992 3012 5993 3010 5993 3019 5993 3012 5994 3019 5994 5551 5994 4657 5995 4660 5995 3189 5995 3189 5996 4660 5996 5089 5996 3189 5997 5089 5997 3020 5997 4657 5998 3189 5998 4659 5998 4659 5999 3189 5999 3187 5999 4659 6000 3187 6000 3013 6000 3013 6001 3187 6001 3186 6001 3013 6002 3186 6002 3014 6002 3014 6003 3186 6003 3006 6003 3014 6004 3006 6004 3008 6004 3206 6005 3015 6005 3017 6005 3206 6006 3017 6006 3016 6006 3017 6007 3018 6007 3016 6007 3016 6008 3018 6008 5610 6008 3016 6009 5610 6009 5549 6009 5551 6010 3019 6010 5552 6010 5552 6011 3019 6011 3205 6011 5552 6012 3205 6012 5553 6012 5553 6013 3205 6013 3016 6013 5553 6014 3016 6014 5555 6014 5555 6015 3016 6015 5549 6015 3020 6016 5089 6016 3027 6016 3027 6017 5089 6017 5086 6017 3022 6018 3021 6018 6217 6018 6217 6019 6218 6019 3022 6019 3022 6020 6218 6020 4920 6020 3022 6021 4920 6021 3023 6021 3023 6022 4920 6022 3017 6022 3023 6023 3017 6023 3015 6023 5271 6024 3175 6024 3024 6024 5271 6025 3024 6025 5088 6025 5088 6026 3024 6026 3025 6026 5088 6027 3025 6027 5087 6027 5087 6028 3025 6028 3177 6028 5087 6029 3177 6029 3026 6029 3026 6030 3177 6030 3027 6030 3026 6031 3027 6031 5086 6031 3029 6032 6217 6032 3021 6032 5678 6033 4938 6033 3029 6033 3031 6034 5678 6034 3028 6034 3028 6035 5678 6035 3029 6035 3028 6036 3029 6036 3192 6036 3192 6037 3029 6037 3021 6037 3192 6038 3030 6038 3028 6038 3028 6039 3030 6039 5676 6039 3028 6040 5676 6040 3031 6040 5676 6041 3030 6041 5677 6041 5677 6042 3030 6042 3193 6042 5677 6043 3193 6043 5528 6043 5528 6044 3193 6044 4752 6044 4752 6045 3193 6045 3033 6045 4752 6046 3033 6046 3032 6046 3032 6047 3033 6047 4766 6047 4766 6048 3033 6048 3034 6048 4766 6049 3034 6049 3035 6049 3035 6050 3034 6050 3195 6050 3035 6051 3195 6051 3036 6051 3036 6052 3195 6052 3038 6052 3036 6053 3038 6053 4750 6053 4750 6054 3038 6054 3037 6054 3037 6055 3038 6055 3039 6055 3040 6056 5278 6056 3041 6056 3041 6057 5147 6057 3040 6057 3040 6058 5147 6058 5148 6058 3040 6059 5148 6059 3181 6059 3181 6060 5148 6060 3037 6060 3181 6061 3037 6061 3039 6061 6191 6062 6192 6062 6248 6062 6248 6063 6192 6063 4449 6063 6248 6064 4449 6064 3042 6064 3042 6065 4449 6065 3044 6065 3042 6066 3044 6066 3043 6066 3043 6067 3044 6067 4448 6067 3043 6068 4448 6068 6249 6068 6249 6069 4448 6069 3045 6069 6249 6070 3045 6070 6242 6070 6242 6071 3045 6071 3047 6071 6242 6072 3047 6072 3046 6072 3046 6073 3047 6073 4459 6073 3046 6074 4459 6074 3048 6074 3048 6075 4459 6075 3049 6075 3048 6076 3049 6076 6243 6076 6243 6077 3049 6077 4465 6077 6243 6078 4465 6078 6245 6078 6245 6079 4465 6079 4467 6079 6245 6080 4467 6080 6246 6080 6246 6081 4467 6081 3050 6081 6246 6082 3050 6082 6251 6082 6251 6083 3050 6083 3051 6083 6251 6084 3051 6084 6179 6084 6179 6085 3051 6085 6180 6085 5423 6086 6176 6086 3052 6086 5211 6087 5409 6087 5411 6087 5423 6088 3052 6088 5411 6088 5411 6089 3052 6089 5224 6089 5411 6090 5224 6090 5211 6090 3061 6091 5399 6091 3053 6091 3053 6092 5399 6092 5406 6092 5211 6093 5214 6093 5409 6093 5409 6094 5214 6094 3054 6094 5409 6095 3054 6095 3055 6095 3055 6096 3054 6096 5207 6096 3055 6097 5207 6097 3056 6097 3056 6098 5207 6098 3057 6098 3056 6099 3057 6099 5406 6099 5406 6100 3057 6100 5209 6100 5406 6101 5209 6101 3053 6101 3063 6102 3064 6102 3058 6102 3058 6103 3064 6103 5378 6103 3058 6104 5378 6104 5191 6104 5191 6105 5378 6105 3059 6105 5191 6106 3059 6106 5195 6106 5195 6107 3059 6107 5395 6107 5195 6108 5395 6108 3060 6108 3060 6109 5395 6109 5388 6109 3060 6110 5388 6110 3061 6110 3061 6111 5388 6111 3062 6111 3061 6112 3062 6112 5399 6112 3063 6113 5193 6113 3064 6113 3064 6114 5193 6114 5188 6114 3064 6115 5188 6115 3072 6115 3065 6116 3178 6116 3067 6116 3065 6117 3067 6117 3066 6117 3066 6118 3067 6118 3068 6118 3066 6119 3068 6119 3069 6119 3069 6120 3068 6120 3176 6120 3069 6121 3176 6121 3070 6121 3070 6122 3176 6122 3071 6122 3070 6123 3071 6123 5458 6123 3072 6124 5188 6124 3074 6124 3072 6125 3074 6125 3073 6125 3073 6126 3074 6126 3075 6126 3073 6127 3075 6127 3076 6127 3076 6128 3075 6128 3172 6128 3076 6129 3172 6129 3077 6129 3077 6130 3172 6130 3080 6130 3077 6131 3080 6131 3078 6131 3178 6132 3065 6132 6152 6132 6152 6133 3065 6133 3079 6133 3078 6134 3080 6134 5376 6134 5376 6135 3080 6135 3151 6135 6152 6136 3079 6136 3081 6136 3081 6137 3079 6137 3082 6137 3081 6138 3082 6138 3158 6138 3158 6139 3082 6139 5459 6139 3158 6140 5459 6140 3160 6140 3160 6141 5459 6141 3083 6141 3160 6142 3083 6142 3084 6142 5376 6143 3151 6143 3085 6143 5376 6144 3085 6144 5375 6144 3085 6145 6153 6145 5375 6145 5375 6146 6153 6146 3086 6146 5375 6147 3086 6147 3087 6147 3087 6148 3086 6148 6154 6148 3087 6149 6154 6149 5377 6149 3101 6150 3084 6150 3083 6150 4989 6151 3088 6151 3089 6151 5377 6152 6154 6152 5386 6152 5386 6153 6154 6153 3090 6153 3089 6154 5404 6154 4989 6154 4989 6155 5404 6155 5400 6155 4989 6156 5400 6156 4990 6156 4990 6157 5400 6157 5392 6157 4990 6158 5392 6158 3090 6158 3090 6159 5392 6159 5370 6159 3090 6160 5370 6160 5386 6160 3096 6161 5422 6161 3091 6161 3091 6162 5422 6162 3092 6162 3091 6163 3092 6163 4987 6163 4987 6164 3092 6164 5412 6164 4987 6165 5412 6165 4988 6165 4988 6166 5412 6166 5371 6166 4988 6167 5371 6167 3088 6167 3088 6168 5371 6168 3093 6168 3088 6169 3093 6169 3089 6169 3099 6170 5421 6170 3094 6170 3094 6171 5421 6171 3095 6171 3094 6172 3095 6172 3096 6172 3096 6173 3095 6173 3097 6173 3096 6174 3097 6174 5422 6174 3105 6175 5428 6175 3098 6175 3098 6176 5428 6176 5431 6176 3098 6177 5431 6177 3099 6177 3099 6178 5431 6178 3100 6178 3099 6179 3100 6179 5421 6179 3083 6180 5448 6180 3101 6180 3101 6181 5448 6181 3102 6181 3101 6182 3102 6182 3104 6182 3104 6183 3102 6183 3103 6183 3104 6184 3103 6184 3105 6184 3105 6185 3103 6185 5444 6185 3105 6186 5444 6186 5428 6186 5269 6187 5270 6187 3132 6187 3132 6188 5270 6188 5363 6188 5363 6189 5270 6189 5284 6189 5284 6190 5270 6190 3106 6190 5284 6191 3106 6191 5282 6191 3106 6192 3107 6192 5282 6192 5282 6193 3107 6193 5262 6193 5282 6194 5262 6194 5351 6194 5351 6195 5262 6195 5259 6195 5351 6196 5259 6196 3108 6196 3108 6197 5259 6197 3109 6197 3108 6198 3109 6198 3110 6198 3113 6199 5335 6199 5336 6199 3110 6200 3109 6200 3111 6200 3111 6201 3109 6201 5253 6201 3111 6202 5253 6202 5346 6202 5346 6203 5253 6203 5248 6203 5346 6204 5248 6204 5336 6204 5336 6205 5248 6205 5249 6205 5336 6206 5249 6206 3113 6206 5244 6207 3112 6207 5328 6207 3113 6208 5246 6208 5335 6208 5335 6209 5246 6209 3114 6209 5335 6210 3114 6210 5328 6210 5328 6211 3114 6211 3115 6211 5328 6212 3115 6212 5244 6212 5244 6213 3116 6213 3112 6213 3112 6214 3116 6214 5515 6214 3112 6215 5515 6215 3117 6215 5515 6216 5517 6216 3117 6216 3117 6217 5517 6217 3118 6217 3117 6218 3118 6218 5324 6218 3118 6219 3119 6219 5324 6219 5324 6220 3119 6220 5507 6220 5324 6221 5507 6221 5318 6221 5507 6222 5508 6222 5318 6222 5318 6223 5508 6223 5512 6223 5318 6224 5512 6224 5287 6224 5287 6225 5512 6225 5513 6225 5287 6226 5513 6226 5286 6226 5286 6227 5513 6227 3120 6227 5286 6228 3120 6228 3121 6228 3121 6229 3120 6229 5503 6229 3121 6230 5503 6230 5311 6230 5311 6231 5503 6231 5504 6231 5311 6232 5504 6232 3122 6232 3122 6233 5504 6233 5506 6233 3122 6234 5506 6234 3123 6234 3123 6235 5506 6235 5501 6235 3123 6236 5501 6236 5306 6236 5306 6237 5501 6237 3124 6237 5306 6238 3124 6238 3125 6238 3125 6239 3124 6239 3126 6239 3125 6240 3126 6240 5295 6240 5295 6241 3126 6241 5497 6241 5295 6242 5497 6242 3128 6242 3128 6243 5497 6243 3127 6243 3128 6244 3127 6244 3129 6244 5369 6245 3130 6245 3131 6245 5369 6246 3131 6246 5358 6246 5358 6247 3131 6247 3170 6247 5358 6248 3170 6248 5356 6248 5356 6249 3170 6249 3168 6249 5356 6250 3168 6250 5355 6250 5355 6251 3168 6251 5269 6251 5355 6252 5269 6252 3132 6252 3129 6253 3127 6253 3133 6253 3129 6254 3133 6254 5288 6254 5288 6255 3133 6255 3180 6255 5288 6256 3180 6256 3135 6256 3135 6257 3180 6257 3134 6257 3135 6258 3134 6258 5289 6258 5289 6259 3134 6259 3190 6259 5289 6260 3190 6260 5292 6260 3130 6261 5369 6261 3152 6261 3152 6262 5369 6262 5368 6262 5292 6263 3190 6263 3136 6263 3136 6264 3190 6264 6166 6264 3153 6265 3152 6265 3137 6265 3137 6266 3152 6266 5368 6266 3138 6267 6167 6267 3166 6267 3138 6268 3166 6268 5290 6268 5290 6269 3166 6269 3139 6269 5290 6270 3139 6270 3140 6270 3140 6271 3139 6271 3141 6271 3140 6272 3141 6272 5297 6272 5297 6273 3141 6273 5298 6273 5298 6274 3141 6274 3144 6274 3142 6275 5310 6275 4999 6275 4999 6276 5310 6276 5304 6276 4999 6277 5304 6277 3144 6277 3144 6278 5304 6278 3143 6278 3144 6279 3143 6279 5298 6279 3150 6280 3145 6280 4997 6280 4997 6281 3145 6281 5316 6281 4997 6282 5316 6282 3142 6282 3142 6283 5316 6283 5314 6283 3142 6284 5314 6284 5310 6284 4991 6285 5322 6285 3146 6285 3146 6286 5322 6286 3147 6286 3146 6287 3147 6287 3149 6287 3149 6288 3147 6288 3148 6288 3149 6289 3148 6289 3150 6289 3150 6290 3148 6290 5320 6290 3150 6291 5320 6291 3145 6291 2935 6292 3085 6292 2936 6292 2936 6293 3085 6293 3151 6293 2936 6294 3151 6294 3213 6294 3222 6295 3152 6295 3153 6295 3222 6296 3153 6296 2896 6296 2896 6297 3153 6297 3154 6297 2896 6298 3154 6298 5025 6298 5025 6299 3154 6299 5026 6299 5026 6300 3154 6300 3155 6300 5026 6301 3155 6301 3156 6301 3156 6302 3155 6302 6168 6302 3156 6303 6168 6303 5518 6303 2861 6304 3081 6304 3157 6304 3157 6305 3081 6305 3158 6305 3157 6306 3158 6306 3159 6306 3159 6307 3158 6307 5002 6307 5002 6308 3158 6308 3160 6308 5002 6309 3160 6309 3161 6309 3161 6310 3160 6310 3084 6310 3161 6311 3084 6311 5022 6311 5001 6312 3141 6312 3139 6312 5001 6313 3139 6313 3162 6313 3162 6314 3139 6314 3166 6314 3162 6315 3166 6315 3163 6315 6166 6316 3164 6316 6167 6316 6167 6317 3164 6317 3165 6317 6167 6318 3165 6318 3166 6318 3166 6319 3165 6319 3167 6319 3166 6320 3167 6320 3163 6320 3169 6321 5269 6321 3168 6321 3169 6322 3168 6322 3171 6322 3171 6323 3168 6323 3170 6323 3171 6324 3170 6324 2956 6324 2956 6325 3170 6325 3131 6325 2956 6326 3131 6326 2959 6326 2959 6327 3131 6327 3130 6327 2959 6328 3130 6328 2960 6328 3173 6329 3080 6329 3172 6329 3173 6330 3172 6330 3174 6330 3174 6331 3172 6331 3075 6331 3174 6332 3075 6332 2990 6332 2990 6333 3075 6333 3074 6333 2990 6334 3074 6334 2992 6334 2992 6335 3074 6335 5188 6335 2992 6336 5188 6336 5066 6336 3175 6337 3071 6337 3176 6337 3175 6338 3176 6338 3024 6338 3024 6339 3176 6339 3068 6339 3024 6340 3068 6340 3025 6340 3025 6341 3068 6341 3067 6341 3025 6342 3067 6342 3177 6342 3177 6343 3067 6343 3178 6343 3177 6344 3178 6344 3027 6344 3180 6345 3133 6345 5278 6345 3127 6346 3179 6346 3133 6346 3133 6347 3179 6347 5277 6347 3133 6348 5277 6348 5278 6348 5278 6349 3040 6349 3180 6349 3180 6350 3040 6350 3181 6350 3180 6351 3181 6351 3134 6351 3134 6352 3181 6352 3039 6352 3134 6353 3039 6353 3190 6353 3182 6354 3183 6354 3184 6354 3184 6355 3183 6355 3185 6355 3184 6356 3185 6356 2862 6356 2862 6357 3185 6357 3006 6357 2862 6358 3006 6358 2860 6358 2860 6359 3006 6359 3186 6359 2860 6360 3186 6360 3187 6360 2870 6361 3196 6361 2869 6361 2869 6362 3196 6362 3183 6362 2869 6363 3183 6363 3188 6363 3188 6364 3183 6364 3182 6364 3187 6365 3189 6365 2860 6365 2860 6366 3189 6366 3020 6366 2860 6367 3020 6367 6150 6367 6150 6368 3020 6368 3027 6368 6150 6369 3027 6369 6152 6369 6152 6370 3027 6370 3178 6370 3164 6371 6166 6371 3190 6371 3191 6372 2878 6372 3192 6372 3192 6373 2878 6373 3030 6373 3191 6374 3192 6374 2880 6374 2880 6375 3192 6375 3021 6375 2880 6376 3021 6376 2876 6376 3034 6377 3033 6377 2882 6377 2882 6378 3033 6378 3193 6378 2882 6379 3193 6379 2881 6379 2881 6380 3193 6380 3030 6380 2881 6381 3030 6381 3194 6381 3194 6382 3030 6382 2878 6382 3190 6383 3039 6383 3164 6383 3164 6384 3039 6384 3038 6384 3164 6385 3038 6385 2882 6385 2882 6386 3038 6386 3195 6386 2882 6387 3195 6387 3034 6387 3196 6388 2870 6388 3197 6388 3196 6389 3197 6389 2997 6389 2997 6390 3197 6390 3200 6390 2997 6391 3200 6391 3202 6391 3004 6392 3003 6392 2872 6392 2872 6393 3003 6393 3198 6393 2872 6394 3198 6394 3199 6394 3199 6395 3198 6395 3001 6395 3199 6396 3001 6396 3200 6396 3200 6397 3001 6397 3201 6397 3200 6398 3201 6398 3202 6398 3019 6399 3203 6399 3205 6399 3205 6400 3203 6400 3204 6400 3205 6401 3204 6401 3016 6401 3016 6402 3204 6402 3206 6402 3206 6403 3204 6403 3015 6403 3015 6404 3204 6404 3207 6404 3015 6405 3207 6405 3023 6405 3023 6406 3207 6406 3208 6406 3023 6407 3208 6407 3022 6407 3022 6408 3208 6408 2876 6408 3022 6409 2876 6409 3021 6409 3213 6410 3151 6410 3080 6410 2923 6411 3209 6411 3210 6411 3210 6412 3209 6412 2978 6412 2923 6413 3210 6413 3211 6413 3211 6414 3210 6414 2774 6414 3211 6415 2774 6415 3224 6415 3209 6416 2921 6416 2978 6416 2978 6417 2921 6417 3212 6417 2978 6418 3212 6418 2983 6418 2983 6419 3212 6419 2934 6419 2983 6420 2934 6420 2986 6420 2986 6421 2934 6421 3214 6421 3080 6422 3173 6422 3213 6422 3213 6423 3173 6423 2988 6423 3213 6424 2988 6424 2934 6424 2934 6425 2988 6425 2987 6425 2934 6426 2987 6426 3214 6426 3215 6427 2943 6427 3216 6427 3216 6428 2943 6428 3217 6428 3216 6429 3217 6429 2899 6429 2899 6430 3217 6430 2939 6430 2899 6431 2939 6431 3220 6431 3220 6432 2939 6432 2946 6432 3220 6433 2946 6433 2945 6433 2907 6434 2953 6434 3218 6434 3218 6435 2953 6435 2943 6435 3218 6436 2943 6436 2903 6436 2903 6437 2943 6437 3215 6437 2945 6438 3219 6438 3220 6438 3220 6439 3219 6439 3221 6439 3220 6440 3221 6440 3222 6440 3222 6441 3221 6441 2960 6441 3222 6442 2960 6442 3152 6442 3152 6443 2960 6443 3130 6443 2970 6444 3223 6444 2972 6444 2972 6445 3223 6445 2912 6445 2972 6446 2912 6446 2973 6446 2973 6447 2912 6447 2971 6447 2971 6448 2912 6448 2977 6448 2977 6449 2912 6449 2914 6449 2977 6450 2914 6450 2976 6450 2976 6451 2914 6451 2916 6451 2976 6452 2916 6452 3225 6452 3225 6453 2916 6453 3224 6453 3225 6454 3224 6454 2774 6454 2953 6455 2907 6455 3226 6455 2953 6456 3226 6456 3227 6456 3227 6457 3226 6457 3228 6457 3227 6458 3228 6458 3229 6458 2967 6459 2964 6459 2911 6459 2911 6460 2964 6460 3230 6460 2911 6461 3230 6461 3232 6461 3232 6462 3230 6462 3231 6462 3232 6463 3231 6463 3228 6463 3228 6464 3231 6464 2966 6464 3228 6465 2966 6465 3229 6465 3233 6466 3483 6466 6143 6466 6143 6467 3243 6467 3233 6467 3233 6468 3243 6468 3235 6468 3233 6469 3235 6469 3234 6469 3235 6470 3236 6470 3234 6470 3234 6471 3236 6471 3246 6471 3234 6472 3246 6472 3237 6472 3246 6473 3247 6473 3237 6473 3237 6474 3247 6474 3249 6474 3237 6475 3249 6475 3481 6475 3481 6476 3249 6476 3250 6476 3481 6477 3250 6477 3239 6477 3250 6478 3238 6478 3239 6478 3239 6479 3238 6479 3252 6479 3239 6480 3252 6480 3241 6480 6149 6481 3478 6481 3240 6481 3240 6482 3478 6482 3241 6482 3240 6483 3241 6483 3253 6483 3253 6484 3241 6484 3252 6484 6143 6485 3242 6485 3243 6485 3243 6486 3242 6486 3267 6486 3243 6487 3267 6487 3235 6487 3235 6488 3267 6488 3244 6488 3235 6489 3244 6489 3236 6489 3236 6490 3244 6490 3245 6490 3236 6491 3245 6491 3246 6491 3246 6492 3245 6492 3264 6492 3246 6493 3264 6493 3247 6493 3247 6494 3264 6494 3263 6494 3247 6495 3263 6495 3249 6495 3249 6496 3263 6496 3248 6496 3249 6497 3248 6497 3250 6497 3250 6498 3248 6498 3260 6498 3250 6499 3260 6499 3238 6499 3238 6500 3260 6500 3251 6500 3238 6501 3251 6501 3252 6501 3252 6502 3251 6502 3258 6502 3252 6503 3258 6503 3253 6503 3253 6504 3258 6504 3257 6504 3253 6505 3257 6505 3240 6505 3240 6506 3257 6506 3256 6506 3240 6507 3256 6507 6149 6507 6149 6508 3256 6508 3254 6508 3255 6509 5420 6509 3254 6509 3254 6510 3256 6510 3255 6510 3255 6511 3256 6511 3257 6511 3255 6512 3257 6512 3259 6512 3257 6513 3258 6513 3259 6513 3259 6514 3258 6514 3251 6514 3259 6515 3251 6515 3261 6515 3251 6516 3260 6516 3261 6516 3261 6517 3260 6517 3248 6517 3261 6518 3248 6518 3262 6518 3262 6519 3248 6519 3263 6519 3262 6520 3263 6520 3265 6520 3263 6521 3264 6521 3265 6521 3265 6522 3264 6522 3245 6522 3265 6523 3245 6523 3266 6523 3242 6524 3268 6524 3267 6524 3267 6525 3268 6525 3266 6525 3267 6526 3266 6526 3244 6526 3244 6527 3266 6527 3245 6527 3269 6528 3444 6528 3270 6528 3270 6529 3444 6529 3443 6529 3270 6530 3443 6530 3276 6530 3276 6531 3443 6531 3442 6531 3276 6532 3442 6532 3277 6532 3277 6533 3442 6533 3271 6533 3277 6534 3271 6534 3272 6534 3272 6535 3271 6535 3273 6535 3272 6536 3273 6536 3280 6536 3280 6537 3273 6537 3274 6537 3280 6538 3274 6538 3282 6538 3282 6539 3274 6539 3440 6539 3282 6540 3440 6540 6121 6540 6121 6541 3440 6541 3275 6541 6129 6542 3269 6542 3286 6542 3286 6543 3269 6543 3270 6543 3286 6544 3270 6544 3285 6544 3285 6545 3270 6545 3276 6545 3285 6546 3276 6546 3284 6546 3284 6547 3276 6547 3277 6547 3284 6548 3277 6548 3278 6548 3278 6549 3277 6549 3272 6549 3278 6550 3272 6550 3279 6550 3279 6551 3272 6551 3280 6551 3279 6552 3280 6552 3281 6552 3281 6553 3280 6553 3282 6553 3281 6554 3282 6554 3283 6554 3283 6555 3282 6555 6121 6555 3283 6556 6120 6556 3281 6556 3281 6557 6120 6557 5435 6557 3281 6558 5435 6558 3279 6558 3279 6559 5435 6559 5434 6559 3279 6560 5434 6560 3278 6560 3278 6561 5434 6561 5432 6561 3278 6562 5432 6562 3284 6562 3284 6563 5432 6563 5430 6563 3284 6564 5430 6564 3285 6564 3285 6565 5430 6565 5429 6565 3285 6566 5429 6566 3286 6566 3286 6567 5429 6567 5438 6567 3286 6568 5438 6568 6129 6568 6129 6569 5438 6569 6115 6569 3287 6570 3460 6570 3291 6570 3291 6571 3460 6571 3458 6571 3291 6572 3458 6572 3292 6572 3292 6573 3458 6573 3288 6573 3292 6574 3288 6574 3290 6574 3290 6575 3288 6575 3289 6575 3290 6576 3289 6576 3294 6576 3294 6577 3289 6577 3456 6577 3294 6578 3456 6578 3296 6578 3296 6579 3456 6579 3455 6579 3296 6580 3455 6580 6106 6580 6106 6581 3455 6581 3454 6581 6096 6582 3287 6582 3302 6582 3302 6583 3287 6583 3291 6583 3302 6584 3291 6584 3300 6584 3300 6585 3291 6585 3292 6585 3300 6586 3292 6586 3299 6586 3299 6587 3292 6587 3290 6587 3299 6588 3290 6588 3293 6588 3293 6589 3290 6589 3294 6589 3293 6590 3294 6590 3295 6590 3295 6591 3294 6591 3296 6591 3295 6592 3296 6592 3297 6592 3297 6593 3296 6593 6106 6593 3297 6594 6105 6594 3295 6594 3295 6595 6105 6595 3298 6595 3295 6596 3298 6596 3293 6596 3293 6597 3298 6597 5447 6597 3293 6598 5447 6598 3299 6598 3299 6599 5447 6599 5446 6599 3299 6600 5446 6600 3300 6600 3300 6601 5446 6601 5445 6601 3300 6602 5445 6602 3302 6602 3302 6603 5445 6603 3301 6603 3302 6604 3301 6604 6096 6604 6096 6605 3301 6605 5443 6605 3303 6606 3425 6606 6086 6606 6086 6607 3304 6607 3303 6607 3303 6608 3304 6608 3325 6608 3303 6609 3325 6609 3427 6609 3325 6610 3305 6610 3427 6610 3427 6611 3305 6611 3306 6611 3427 6612 3306 6612 3307 6612 3306 6613 3322 6613 3307 6613 3307 6614 3322 6614 3308 6614 3307 6615 3308 6615 3309 6615 3309 6616 3308 6616 3321 6616 3309 6617 3321 6617 3311 6617 3321 6618 3310 6618 3311 6618 3311 6619 3310 6619 3312 6619 3311 6620 3312 6620 3315 6620 3313 6621 3314 6621 3316 6621 3316 6622 3314 6622 3315 6622 3316 6623 3315 6623 3318 6623 3318 6624 3315 6624 3312 6624 3313 6625 3316 6625 3317 6625 3317 6626 3316 6626 3319 6626 3316 6627 3318 6627 3319 6627 3319 6628 3318 6628 3312 6628 3319 6629 3312 6629 3328 6629 3312 6630 3310 6630 3328 6630 3328 6631 3310 6631 3321 6631 3328 6632 3321 6632 3320 6632 3321 6633 3308 6633 3320 6633 3320 6634 3308 6634 3322 6634 3320 6635 3322 6635 3323 6635 3322 6636 3306 6636 3323 6636 3323 6637 3306 6637 3305 6637 3323 6638 3305 6638 3324 6638 6086 6639 6085 6639 3304 6639 3304 6640 6085 6640 3324 6640 3304 6641 3324 6641 3325 6641 3325 6642 3324 6642 3305 6642 6085 6643 3326 6643 3324 6643 3324 6644 3326 6644 3327 6644 3324 6645 3327 6645 3323 6645 3323 6646 3327 6646 5451 6646 3323 6647 5451 6647 3320 6647 3320 6648 5451 6648 3329 6648 3320 6649 3329 6649 3328 6649 3328 6650 3329 6650 3330 6650 3328 6651 3330 6651 3319 6651 3319 6652 3330 6652 3331 6652 3319 6653 3331 6653 3317 6653 3317 6654 3331 6654 6080 6654 5215 6655 3400 6655 5216 6655 5216 6656 3400 6656 3397 6656 3397 6657 3332 6657 5216 6657 5216 6658 3332 6658 3333 6658 5216 6659 3333 6659 3334 6659 5231 6660 3335 6660 3336 6660 3336 6661 3335 6661 3437 6661 3437 6662 3337 6662 3336 6662 3336 6663 3337 6663 3380 6663 3336 6664 3380 6664 3338 6664 3417 6665 5233 6665 5235 6665 5235 6666 3339 6666 3340 6666 3340 6667 3407 6667 5235 6667 5235 6668 3407 6668 3341 6668 5235 6669 3341 6669 3417 6669 3345 6670 3342 6670 5241 6670 5241 6671 3361 6671 3343 6671 3343 6672 3344 6672 5241 6672 5241 6673 3344 6673 3423 6673 5241 6674 3423 6674 3345 6674 3342 6675 3345 6675 3346 6675 3346 6676 3345 6676 3423 6676 3346 6677 3423 6677 4610 6677 4610 6678 3423 6678 3424 6678 4610 6679 3424 6679 3347 6679 3347 6680 3424 6680 3348 6680 3347 6681 3348 6681 4611 6681 4611 6682 3348 6682 6071 6682 4611 6683 6071 6683 3349 6683 3349 6684 6071 6684 3350 6684 3350 6685 6071 6685 5124 6685 5124 6686 6071 6686 3351 6686 5124 6687 3351 6687 3352 6687 3351 6688 3353 6688 3352 6688 3352 6689 3353 6689 6072 6689 3352 6690 6072 6690 3354 6690 3354 6691 6072 6691 6074 6691 6074 6692 6075 6692 3354 6692 3354 6693 6075 6693 6076 6693 3354 6694 6076 6694 3355 6694 6076 6695 6078 6695 3355 6695 3355 6696 6078 6696 6079 6696 3355 6697 6079 6697 5084 6697 3359 6698 5085 6698 3356 6698 3356 6699 5085 6699 5084 6699 3356 6700 5084 6700 3357 6700 3357 6701 5084 6701 6079 6701 3358 6702 5085 6702 5272 6702 5272 6703 5085 6703 3359 6703 5272 6704 3359 6704 3363 6704 3363 6705 3359 6705 3360 6705 3343 6706 3361 6706 3362 6706 3363 6707 3360 6707 3364 6707 3364 6708 3360 6708 3421 6708 3364 6709 3421 6709 3362 6709 3362 6710 3421 6710 3344 6710 3362 6711 3344 6711 3343 6711 3435 6712 3439 6712 3366 6712 3366 6713 3439 6713 3437 6713 3366 6714 3437 6714 5230 6714 5230 6715 3437 6715 3335 6715 5230 6716 3335 6716 5231 6716 3365 6717 3436 6717 3366 6717 3366 6718 3436 6718 3435 6718 5130 6719 3367 6719 3368 6719 3368 6720 3367 6720 3436 6720 3368 6721 3436 6721 3365 6721 5128 6722 3369 6722 3370 6722 3370 6723 3369 6723 3371 6723 3370 6724 3371 6724 5135 6724 5135 6725 3371 6725 6066 6725 5135 6726 6066 6726 5134 6726 5134 6727 6066 6727 3372 6727 5134 6728 3372 6728 3374 6728 3374 6729 3372 6729 3373 6729 3374 6730 3373 6730 5133 6730 3367 6731 5130 6731 3375 6731 3375 6732 5130 6732 3376 6732 3375 6733 3376 6733 3377 6733 3377 6734 3376 6734 5133 6734 3377 6735 5133 6735 6069 6735 6069 6736 5133 6736 3373 6736 3378 6737 3379 6737 5119 6737 5119 6738 3379 6738 3369 6738 5119 6739 3369 6739 5128 6739 3381 6740 3383 6740 3378 6740 3378 6741 3383 6741 3379 6741 3338 6742 3380 6742 4605 6742 4605 6743 3380 6743 3337 6743 4605 6744 3337 6744 3381 6744 3381 6745 3337 6745 3382 6745 3381 6746 3382 6746 3383 6746 3334 6747 3333 6747 4602 6747 4602 6748 3333 6748 3332 6748 4602 6749 3332 6749 3385 6749 3385 6750 3332 6750 3482 6750 3385 6751 3482 6751 3466 6751 3384 6752 3385 6752 3467 6752 3467 6753 3385 6753 3466 6753 3384 6754 3467 6754 5104 6754 5104 6755 3467 6755 3468 6755 5104 6756 3468 6756 3386 6756 3386 6757 3468 6757 5102 6757 5102 6758 3468 6758 3387 6758 5102 6759 3387 6759 5115 6759 5115 6760 3387 6760 3388 6760 5115 6761 3388 6761 5116 6761 3388 6762 6056 6762 5116 6762 5116 6763 6056 6763 6057 6763 5116 6764 6057 6764 3393 6764 3470 6765 5127 6765 3389 6765 3389 6766 5127 6766 5129 6766 3389 6767 5129 6767 3390 6767 3390 6768 5129 6768 3391 6768 3390 6769 3391 6769 3392 6769 3392 6770 3391 6770 3393 6770 3392 6771 3393 6771 3394 6771 3394 6772 3393 6772 6057 6772 5127 6773 3470 6773 5126 6773 5126 6774 3470 6774 3395 6774 5126 6775 3395 6775 4606 6775 3398 6776 4606 6776 3396 6776 3396 6777 4606 6777 3395 6777 3396 6778 3475 6778 3398 6778 3398 6779 3475 6779 3397 6779 3398 6780 3397 6780 3399 6780 3399 6781 3397 6781 3400 6781 3399 6782 3400 6782 5215 6782 3401 6783 3402 6783 3449 6783 3449 6784 3402 6784 3404 6784 3412 6785 3403 6785 3405 6785 3405 6786 3403 6786 3404 6786 3405 6787 3404 6787 3402 6787 3449 6788 3462 6788 3401 6788 3401 6789 3462 6789 3407 6789 3401 6790 3407 6790 3406 6790 3406 6791 3407 6791 3340 6791 3406 6792 3340 6792 3339 6792 5131 6793 3415 6793 5132 6793 5132 6794 3415 6794 3408 6794 5132 6795 3408 6795 5120 6795 3408 6796 6058 6796 5120 6796 5120 6797 6058 6797 3409 6797 5120 6798 3409 6798 5121 6798 3409 6799 6060 6799 5121 6799 5121 6800 6060 6800 6061 6800 5121 6801 6061 6801 5122 6801 6061 6802 3410 6802 5122 6802 5122 6803 3410 6803 3411 6803 5122 6804 3411 6804 5125 6804 3403 6805 3412 6805 3452 6805 3452 6806 3412 6806 3413 6806 3452 6807 3413 6807 3450 6807 3450 6808 3413 6808 5125 6808 3450 6809 5125 6809 6064 6809 6064 6810 5125 6810 3411 6810 4608 6811 3414 6811 4609 6811 4609 6812 3414 6812 3415 6812 4609 6813 3415 6813 5131 6813 3416 6814 3447 6814 4608 6814 4608 6815 3447 6815 3414 6815 5233 6816 3417 6816 4607 6816 4607 6817 3417 6817 3341 6817 4607 6818 3341 6818 3416 6818 3416 6819 3341 6819 3463 6819 3416 6820 3463 6820 3447 6820 6071 6821 3348 6821 3418 6821 3418 6822 3348 6822 3424 6822 3419 6823 3421 6823 3359 6823 3359 6824 3421 6824 3360 6824 3356 6825 3430 6825 3359 6825 3359 6826 3430 6826 3419 6826 3423 6827 3344 6827 3421 6827 3420 6828 3422 6828 3421 6828 3421 6829 3422 6829 3424 6829 3421 6830 3424 6830 3423 6830 3422 6831 6094 6831 3424 6831 3424 6832 6094 6832 3425 6832 3424 6833 3425 6833 3418 6833 3418 6834 3425 6834 3303 6834 3418 6835 3303 6835 3426 6835 3426 6836 3303 6836 3427 6836 3426 6837 3427 6837 6073 6837 6073 6838 3427 6838 3307 6838 6073 6839 3307 6839 3428 6839 3428 6840 3307 6840 3309 6840 3428 6841 3309 6841 6077 6841 6077 6842 3309 6842 3311 6842 6077 6843 3311 6843 3429 6843 3429 6844 3311 6844 3315 6844 3429 6845 3315 6845 3430 6845 3430 6846 3315 6846 3314 6846 3430 6847 3314 6847 3419 6847 3419 6848 3314 6848 3431 6848 3419 6849 3431 6849 3421 6849 3421 6850 3431 6850 3432 6850 3421 6851 3432 6851 3420 6851 3383 6852 3382 6852 3379 6852 3379 6853 3382 6853 3433 6853 3379 6854 3433 6854 3369 6854 3439 6855 3435 6855 3434 6855 3434 6856 3435 6856 3436 6856 3434 6857 3436 6857 3367 6857 3377 6858 6070 6858 3445 6858 3377 6859 3445 6859 3375 6859 3375 6860 3445 6860 3434 6860 3375 6861 3434 6861 3367 6861 3337 6862 3437 6862 3382 6862 3382 6863 3437 6863 3439 6863 3382 6864 3439 6864 3438 6864 3438 6865 3439 6865 6131 6865 3438 6866 3275 6866 3382 6866 3382 6867 3275 6867 3440 6867 3382 6868 3440 6868 3433 6868 3433 6869 3440 6869 3274 6869 3433 6870 3274 6870 6065 6870 6065 6871 3274 6871 3273 6871 6065 6872 3273 6872 3441 6872 3441 6873 3273 6873 3271 6873 3441 6874 3271 6874 6067 6874 6067 6875 3271 6875 3442 6875 6067 6876 3442 6876 6068 6876 6068 6877 3442 6877 3443 6877 6068 6878 3443 6878 6070 6878 6070 6879 3443 6879 3444 6879 6070 6880 3444 6880 3445 6880 3445 6881 3444 6881 6133 6881 3445 6882 6133 6882 3434 6882 3434 6883 6133 6883 3446 6883 3434 6884 3446 6884 3439 6884 3439 6885 3446 6885 6132 6885 3439 6886 6132 6886 6131 6886 3447 6887 3463 6887 3414 6887 3414 6888 3463 6888 3453 6888 3414 6889 3453 6889 3415 6889 3462 6890 3449 6890 3448 6890 3448 6891 3449 6891 3404 6891 3448 6892 3404 6892 3403 6892 3450 6893 3459 6893 3451 6893 3450 6894 3451 6894 3452 6894 3452 6895 3451 6895 3448 6895 3452 6896 3448 6896 3403 6896 3341 6897 3407 6897 3463 6897 3463 6898 3407 6898 3462 6898 3463 6899 3454 6899 3453 6899 3453 6900 3454 6900 3455 6900 3453 6901 3455 6901 3457 6901 3457 6902 3455 6902 3456 6902 3457 6903 3456 6903 6059 6903 6059 6904 3456 6904 3289 6904 6059 6905 3289 6905 6062 6905 6062 6906 3289 6906 3288 6906 6062 6907 3288 6907 6063 6907 6063 6908 3288 6908 3458 6908 6063 6909 3458 6909 3459 6909 3459 6910 3458 6910 3460 6910 3459 6911 3460 6911 3451 6911 3451 6912 3460 6912 3461 6912 3451 6913 3461 6913 3448 6913 3448 6914 3461 6914 6114 6914 3448 6915 6114 6915 3462 6915 6114 6916 6112 6916 3462 6916 3462 6917 6112 6917 3464 6917 3462 6918 3464 6918 3463 6918 3463 6919 3464 6919 3465 6919 3463 6920 3465 6920 3454 6920 3466 6921 3482 6921 3467 6921 3467 6922 3482 6922 6054 6922 3467 6923 6054 6923 3468 6923 3475 6924 3396 6924 3469 6924 3469 6925 3396 6925 3395 6925 3469 6926 3395 6926 3470 6926 3392 6927 3471 6927 3472 6927 3392 6928 3472 6928 3390 6928 3390 6929 3472 6929 3476 6929 3390 6930 3476 6930 3389 6930 3389 6931 3476 6931 3469 6931 3389 6932 3469 6932 3470 6932 3482 6933 3332 6933 3475 6933 3475 6934 3332 6934 3397 6934 3473 6935 3474 6935 3475 6935 3483 6936 3482 6936 6145 6936 6145 6937 3482 6937 3475 6937 6145 6938 3475 6938 6147 6938 6147 6939 3475 6939 3474 6939 3475 6940 3469 6940 3473 6940 3473 6941 3469 6941 3476 6941 3473 6942 3476 6942 3477 6942 3477 6943 3476 6943 3472 6943 3477 6944 3472 6944 3478 6944 3478 6945 3472 6945 3471 6945 3478 6946 3471 6946 3241 6946 3241 6947 3471 6947 3479 6947 3241 6948 3479 6948 3239 6948 3239 6949 3479 6949 3480 6949 3239 6950 3480 6950 3481 6950 3481 6951 3480 6951 6055 6951 3481 6952 6055 6952 3237 6952 3237 6953 6055 6953 6054 6953 3237 6954 6054 6954 3234 6954 3234 6955 6054 6955 3482 6955 3234 6956 3482 6956 3233 6956 3233 6957 3482 6957 3483 6957 3484 6958 6051 6958 6041 6958 6041 6959 3506 6959 3484 6959 3484 6960 3506 6960 3486 6960 3484 6961 3486 6961 3485 6961 3485 6962 3486 6962 3487 6962 3487 6963 3503 6963 3485 6963 3485 6964 3503 6964 3501 6964 3485 6965 3501 6965 3727 6965 3501 6966 3499 6966 3727 6966 3727 6967 3499 6967 3498 6967 3727 6968 3498 6968 3729 6968 3498 6969 3496 6969 3729 6969 3729 6970 3496 6970 3495 6970 3729 6971 3495 6971 3488 6971 3489 6972 3490 6972 3493 6972 3493 6973 3490 6973 3488 6973 3493 6974 3488 6974 3491 6974 3491 6975 3488 6975 3495 6975 3508 6976 3489 6976 3492 6976 3492 6977 3489 6977 3493 6977 3492 6978 3493 6978 3494 6978 3494 6979 3493 6979 3491 6979 3494 6980 3491 6980 3509 6980 3509 6981 3491 6981 3495 6981 3509 6982 3495 6982 3511 6982 3511 6983 3495 6983 3496 6983 3511 6984 3496 6984 3512 6984 3512 6985 3496 6985 3498 6985 3512 6986 3498 6986 3497 6986 3497 6987 3498 6987 3499 6987 3497 6988 3499 6988 3500 6988 3500 6989 3499 6989 3501 6989 3500 6990 3501 6990 3502 6990 3502 6991 3501 6991 3503 6991 3502 6992 3503 6992 3515 6992 3515 6993 3503 6993 3487 6993 3515 6994 3487 6994 3504 6994 3504 6995 3487 6995 3486 6995 3504 6996 3486 6996 3505 6996 3505 6997 3486 6997 3506 6997 3505 6998 3506 6998 3507 6998 3507 6999 3506 6999 6041 6999 5408 7000 5414 7000 3508 7000 3508 7001 3492 7001 5408 7001 5408 7002 3492 7002 3494 7002 5408 7003 3494 7003 3510 7003 3510 7004 3494 7004 3509 7004 3509 7005 3511 7005 3510 7005 3510 7006 3511 7006 3512 7006 3510 7007 3512 7007 3513 7007 3512 7008 3497 7008 3513 7008 3513 7009 3497 7009 3500 7009 3513 7010 3500 7010 3514 7010 3500 7011 3502 7011 3514 7011 3514 7012 3502 7012 3515 7012 3514 7013 3515 7013 5373 7013 3507 7014 5410 7014 3505 7014 3505 7015 5410 7015 5373 7015 3505 7016 5373 7016 3504 7016 3504 7017 5373 7017 3515 7017 3516 7018 6027 7018 6026 7018 6026 7019 3538 7019 3516 7019 3516 7020 3538 7020 3536 7020 3516 7021 3536 7021 3517 7021 3517 7022 3536 7022 3535 7022 3535 7023 3518 7023 3517 7023 3517 7024 3518 7024 3533 7024 3517 7025 3533 7025 3519 7025 3533 7026 3532 7026 3519 7026 3519 7027 3532 7027 3530 7027 3519 7028 3530 7028 3520 7028 3530 7029 3529 7029 3520 7029 3520 7030 3529 7030 3526 7030 3520 7031 3526 7031 3685 7031 6022 7032 3521 7032 3524 7032 3524 7033 3521 7033 3685 7033 3524 7034 3685 7034 3522 7034 3522 7035 3685 7035 3526 7035 6004 7036 6022 7036 3523 7036 3523 7037 6022 7037 3524 7037 3523 7038 3524 7038 3541 7038 3541 7039 3524 7039 3522 7039 3541 7040 3522 7040 3525 7040 3525 7041 3522 7041 3526 7041 3525 7042 3526 7042 3527 7042 3527 7043 3526 7043 3529 7043 3527 7044 3529 7044 3528 7044 3528 7045 3529 7045 3530 7045 3528 7046 3530 7046 3542 7046 3542 7047 3530 7047 3532 7047 3542 7048 3532 7048 3531 7048 3531 7049 3532 7049 3533 7049 3531 7050 3533 7050 3534 7050 3534 7051 3533 7051 3518 7051 3534 7052 3518 7052 3544 7052 3544 7053 3518 7053 3535 7053 3544 7054 3535 7054 3545 7054 3545 7055 3535 7055 3536 7055 3545 7056 3536 7056 3537 7056 3537 7057 3536 7057 3538 7057 3537 7058 3538 7058 3539 7058 3539 7059 3538 7059 6026 7059 5396 7060 3540 7060 6004 7060 6004 7061 3523 7061 5396 7061 5396 7062 3523 7062 3541 7062 5396 7063 3541 7063 5397 7063 5397 7064 3541 7064 3525 7064 3525 7065 3527 7065 5397 7065 5397 7066 3527 7066 3528 7066 5397 7067 3528 7067 3543 7067 3528 7068 3542 7068 3543 7068 3543 7069 3542 7069 3531 7069 3543 7070 3531 7070 5398 7070 3531 7071 3534 7071 5398 7071 5398 7072 3534 7072 3544 7072 5398 7073 3544 7073 3546 7073 3539 7074 5998 7074 3537 7074 3537 7075 5998 7075 3546 7075 3537 7076 3546 7076 3545 7076 3545 7077 3546 7077 3544 7077 5996 7078 5975 7078 3717 7078 3717 7079 5975 7079 3547 7079 3717 7080 3547 7080 3708 7080 3708 7081 3547 7081 3561 7081 3561 7082 3548 7082 3708 7082 3708 7083 3548 7083 3559 7083 3708 7084 3559 7084 3549 7084 3559 7085 3550 7085 3549 7085 3549 7086 3550 7086 3553 7086 3549 7087 3553 7087 3552 7087 5987 7088 5989 7088 3555 7088 3555 7089 5989 7089 3713 7089 3555 7090 3713 7090 3551 7090 3551 7091 3713 7091 3552 7091 3551 7092 3552 7092 3557 7092 3557 7093 3552 7093 3553 7093 3554 7094 5987 7094 3555 7094 3554 7095 3555 7095 3568 7095 3568 7096 3555 7096 3551 7096 3568 7097 3551 7097 3556 7097 3556 7098 3551 7098 3557 7098 3556 7099 3557 7099 3558 7099 3557 7100 3553 7100 3558 7100 3558 7101 3553 7101 3550 7101 3558 7102 3550 7102 3560 7102 3550 7103 3559 7103 3560 7103 3560 7104 3559 7104 3548 7104 3560 7105 3548 7105 3562 7105 3548 7106 3561 7106 3562 7106 3562 7107 3561 7107 3547 7107 3562 7108 3547 7108 3563 7108 3563 7109 3547 7109 5975 7109 3563 7110 5975 7110 5976 7110 5976 7111 5389 7111 3563 7111 3563 7112 5389 7112 3564 7112 3563 7113 3564 7113 3562 7113 3562 7114 3564 7114 3565 7114 3562 7115 3565 7115 3560 7115 3560 7116 3565 7116 3566 7116 3560 7117 3566 7117 3558 7117 3558 7118 3566 7118 5394 7118 3558 7119 5394 7119 3556 7119 3556 7120 5394 7120 3567 7120 3556 7121 3567 7121 3568 7121 3568 7122 3567 7122 5393 7122 3568 7123 5393 7123 3554 7123 3554 7124 5393 7124 3569 7124 3574 7125 3744 7125 3576 7125 3576 7126 3744 7126 3745 7126 3576 7127 3745 7127 3577 7127 3577 7128 3745 7128 3746 7128 3577 7129 3746 7129 3570 7129 3570 7130 3746 7130 3571 7130 3570 7131 3571 7131 3572 7131 3572 7132 3571 7132 3749 7132 3572 7133 3749 7133 3580 7133 3580 7134 3749 7134 3573 7134 3580 7135 3573 7135 5959 7135 5959 7136 3573 7136 5966 7136 5952 7137 3574 7137 3575 7137 3575 7138 3574 7138 3576 7138 3575 7139 3576 7139 3584 7139 3584 7140 3576 7140 3577 7140 3584 7141 3577 7141 3583 7141 3583 7142 3577 7142 3570 7142 3583 7143 3570 7143 3578 7143 3578 7144 3570 7144 3572 7144 3578 7145 3572 7145 3579 7145 3579 7146 3572 7146 3580 7146 3579 7147 3580 7147 5958 7147 5958 7148 3580 7148 5959 7148 5958 7149 3581 7149 3579 7149 3579 7150 3581 7150 5379 7150 3579 7151 5379 7151 3578 7151 3578 7152 5379 7152 5381 7152 3578 7153 5381 7153 3583 7153 3583 7154 5381 7154 3582 7154 3583 7155 3582 7155 3584 7155 3584 7156 3582 7156 5380 7156 3584 7157 5380 7157 3575 7157 3575 7158 5380 7158 3585 7158 3575 7159 3585 7159 5952 7159 5952 7160 3585 7160 3586 7160 3588 7161 3587 7161 5212 7161 5212 7162 5213 7162 3639 7162 3639 7163 3637 7163 5212 7163 5212 7164 3637 7164 3655 7164 5212 7165 3655 7165 3588 7165 3591 7166 3589 7166 3590 7166 3590 7167 5205 7167 3636 7167 3636 7168 3635 7168 3590 7168 3590 7169 3635 7169 3618 7169 3590 7170 3618 7170 3591 7170 3673 7171 3592 7171 5206 7171 5206 7172 3592 7172 3671 7172 3671 7173 3707 7173 5206 7173 5206 7174 3707 7174 3593 7174 5206 7175 3593 7175 5198 7175 3614 7176 5187 7176 3594 7176 3616 7177 3614 7177 3595 7177 3595 7178 3614 7178 3594 7178 3595 7179 3594 7179 3597 7179 3597 7180 3594 7180 5194 7180 3734 7181 3748 7181 4592 7181 4592 7182 3748 7182 3595 7182 4592 7183 3595 7183 3596 7183 3596 7184 3595 7184 3597 7184 3596 7185 3597 7185 5194 7185 4593 7186 3600 7186 4592 7186 4592 7187 3600 7187 3734 7187 3607 7188 3598 7188 3599 7188 3599 7189 3598 7189 3600 7189 3599 7190 3600 7190 4593 7190 3601 7191 3602 7191 5072 7191 5072 7192 3602 7192 3603 7192 3603 7193 3750 7193 5072 7193 5072 7194 3750 7194 3604 7194 5072 7195 3604 7195 5073 7195 3604 7196 3751 7196 5073 7196 5073 7197 3751 7197 3752 7197 5073 7198 3752 7198 3605 7198 3752 7199 3754 7199 3605 7199 3605 7200 3754 7200 3755 7200 3605 7201 3755 7201 3610 7201 3598 7202 3607 7202 3606 7202 3606 7203 3607 7203 3608 7203 3606 7204 3608 7204 3609 7204 3609 7205 3608 7205 3610 7205 3609 7206 3610 7206 3756 7206 3756 7207 3610 7207 3755 7207 5065 7208 3611 7208 3612 7208 3612 7209 3611 7209 3602 7209 3612 7210 3602 7210 3601 7210 3613 7211 3617 7211 5065 7211 5065 7212 3617 7212 3611 7212 5187 7213 3614 7213 3615 7213 3615 7214 3614 7214 3616 7214 3615 7215 3616 7215 3613 7215 3613 7216 3616 7216 3747 7216 3613 7217 3747 7217 3617 7217 3589 7218 3591 7218 5204 7218 5204 7219 3591 7219 3618 7219 5204 7220 3618 7220 3619 7220 3619 7221 3618 7221 3620 7221 3619 7222 3620 7222 3621 7222 4595 7223 3619 7223 3674 7223 3674 7224 3619 7224 3621 7224 4595 7225 3674 7225 3622 7225 3622 7226 3674 7226 3676 7226 3622 7227 3676 7227 5099 7227 5099 7228 3676 7228 3623 7228 3623 7229 3676 7229 5951 7229 3623 7230 5951 7230 3628 7230 3630 7231 5111 7231 3624 7231 3624 7232 5111 7232 3625 7232 3624 7233 3625 7233 3683 7233 3683 7234 3625 7234 5114 7234 3683 7235 5114 7235 3681 7235 3681 7236 5114 7236 3626 7236 3681 7237 3626 7237 3679 7237 3679 7238 3626 7238 3627 7238 3679 7239 3627 7239 3678 7239 3678 7240 3627 7240 3628 7240 3678 7241 3628 7241 3629 7241 3629 7242 3628 7242 5951 7242 5111 7243 3630 7243 3631 7243 3631 7244 3630 7244 3633 7244 3631 7245 3633 7245 4598 7245 4597 7246 4598 7246 3632 7246 3632 7247 4598 7247 3633 7247 3632 7248 3634 7248 4597 7248 4597 7249 3634 7249 3635 7249 4597 7250 3635 7250 5210 7250 5210 7251 3635 7251 3636 7251 5210 7252 3636 7252 5205 7252 3719 7253 3725 7253 4603 7253 4603 7254 3725 7254 3637 7254 4603 7255 3637 7255 3638 7255 3638 7256 3637 7256 3639 7256 3638 7257 3639 7257 5213 7257 3640 7258 3642 7258 4603 7258 4603 7259 3642 7259 3719 7259 5108 7260 3641 7260 5106 7260 5106 7261 3641 7261 3642 7261 5106 7262 3642 7262 3640 7262 5113 7263 5112 7263 3718 7263 3718 7264 5947 7264 5113 7264 5113 7265 5947 7265 3643 7265 5113 7266 3643 7266 5094 7266 3643 7267 3644 7267 5094 7267 5094 7268 3644 7268 3645 7268 5094 7269 3645 7269 3646 7269 3645 7270 3647 7270 3646 7270 3646 7271 3647 7271 3651 7271 3646 7272 3651 7272 5096 7272 3641 7273 5108 7273 3648 7273 3648 7274 5108 7274 3650 7274 3648 7275 3650 7275 3649 7275 3649 7276 3650 7276 5096 7276 3649 7277 5096 7277 3722 7277 3722 7278 5096 7278 3651 7278 3653 7279 3652 7279 5101 7279 5101 7280 3652 7280 3718 7280 5101 7281 3718 7281 5112 7281 4599 7282 3656 7282 3653 7282 3653 7283 3656 7283 3652 7283 3587 7284 3588 7284 3654 7284 3654 7285 3588 7285 3655 7285 3654 7286 3655 7286 4599 7286 4599 7287 3655 7287 3726 7287 4599 7288 3726 7288 3656 7288 3660 7289 3693 7289 3657 7289 3657 7290 3693 7290 3658 7290 3657 7291 3658 7291 5091 7291 5091 7292 3658 7292 3659 7292 5091 7293 3659 7293 5092 7293 5198 7294 3593 7294 5196 7294 5196 7295 3593 7295 3707 7295 5196 7296 3707 7296 3660 7296 3660 7297 3707 7297 3661 7297 3660 7298 3661 7298 3693 7298 5092 7299 3659 7299 5097 7299 5097 7300 3659 7300 3662 7300 5097 7301 3662 7301 3663 7301 3662 7302 3699 7302 3663 7302 3663 7303 3699 7303 3700 7303 3663 7304 3700 7304 3665 7304 3700 7305 3664 7305 3665 7305 3665 7306 3664 7306 3666 7306 3665 7307 3666 7307 3667 7307 3666 7308 3702 7308 3667 7308 3667 7309 3702 7309 3703 7309 3667 7310 3703 7310 3668 7310 3698 7311 3669 7311 3706 7311 3706 7312 3669 7312 5100 7312 3706 7313 5100 7313 3705 7313 3705 7314 5100 7314 3668 7314 3705 7315 3668 7315 3704 7315 3704 7316 3668 7316 3703 7316 3669 7317 3698 7317 4596 7317 4596 7318 3698 7318 3697 7318 4596 7319 3697 7319 3670 7319 4594 7320 3670 7320 3695 7320 3695 7321 3670 7321 3697 7321 3695 7322 3716 7322 4594 7322 4594 7323 3716 7323 3671 7323 4594 7324 3671 7324 3672 7324 3672 7325 3671 7325 3592 7325 3672 7326 3592 7326 3673 7326 3621 7327 3620 7327 3674 7327 3674 7328 3620 7328 3675 7328 3674 7329 3675 7329 3676 7329 3634 7330 3632 7330 3691 7330 3691 7331 3632 7331 3633 7331 3691 7332 3633 7332 3630 7332 3629 7333 3686 7333 3678 7333 3678 7334 3686 7334 3677 7334 3678 7335 3677 7335 3679 7335 3679 7336 3677 7336 3680 7336 3679 7337 3680 7337 3681 7337 3681 7338 3680 7338 3682 7338 3681 7339 3682 7339 3683 7339 3683 7340 3682 7340 3684 7340 3683 7341 3684 7341 3624 7341 3624 7342 3684 7342 3691 7342 3624 7343 3691 7343 3630 7343 6027 7344 3516 7344 3634 7344 3516 7345 3620 7345 3634 7345 3634 7346 3620 7346 3618 7346 3634 7347 3618 7347 3635 7347 3516 7348 3517 7348 3620 7348 3620 7349 3517 7349 3519 7349 3620 7350 3519 7350 3675 7350 3675 7351 3519 7351 3520 7351 3675 7352 3520 7352 5950 7352 5950 7353 3520 7353 3685 7353 5950 7354 3685 7354 3686 7354 3686 7355 3685 7355 3521 7355 3686 7356 3521 7356 3677 7356 3677 7357 3521 7357 3687 7357 3677 7358 3687 7358 3680 7358 3680 7359 3687 7359 6025 7359 3680 7360 6025 7360 3682 7360 3682 7361 6025 7361 3688 7361 3682 7362 3688 7362 3684 7362 3684 7363 3688 7363 3689 7363 3684 7364 3689 7364 3691 7364 3691 7365 3689 7365 3690 7365 3691 7366 3690 7366 3634 7366 3634 7367 3690 7367 3692 7367 3634 7368 3692 7368 6027 7368 3693 7369 3661 7369 3658 7369 3658 7370 3661 7370 3694 7370 3658 7371 3694 7371 3659 7371 3716 7372 3695 7372 3696 7372 3696 7373 3695 7373 3697 7373 3696 7374 3697 7374 3698 7374 3699 7375 3714 7375 3700 7375 3700 7376 3714 7376 3701 7376 3700 7377 3701 7377 3664 7377 3664 7378 3701 7378 3666 7378 3666 7379 3701 7379 3712 7379 3666 7380 3712 7380 3702 7380 3702 7381 3712 7381 3703 7381 3703 7382 3712 7382 3711 7382 3703 7383 3711 7383 3704 7383 3704 7384 3711 7384 3705 7384 3705 7385 3711 7385 3709 7385 3705 7386 3709 7386 3706 7386 3706 7387 3709 7387 3696 7387 3706 7388 3696 7388 3698 7388 3661 7389 3707 7389 3716 7389 3716 7390 3707 7390 3671 7390 3661 7391 3549 7391 3552 7391 3549 7392 3661 7392 3708 7392 3708 7393 3661 7393 3716 7393 3708 7394 3716 7394 3717 7394 3696 7395 3709 7395 5993 7395 5993 7396 3709 7396 5992 7396 5992 7397 3709 7397 3711 7397 5992 7398 3711 7398 3710 7398 3710 7399 3711 7399 3712 7399 3710 7400 3712 7400 5990 7400 5990 7401 3712 7401 3701 7401 5990 7402 3701 7402 5989 7402 5989 7403 3701 7403 3714 7403 5989 7404 3714 7404 3713 7404 3713 7405 3714 7405 5949 7405 3713 7406 5949 7406 3552 7406 3552 7407 5949 7407 3694 7407 3552 7408 3694 7408 3661 7408 5993 7409 5994 7409 3696 7409 3696 7410 5994 7410 3715 7410 3696 7411 3715 7411 3716 7411 3716 7412 3715 7412 5996 7412 3716 7413 5996 7413 3717 7413 3656 7414 3726 7414 3652 7414 3652 7415 3726 7415 3728 7415 3652 7416 3728 7416 3718 7416 3725 7417 3719 7417 3720 7417 3720 7418 3719 7418 3642 7418 3720 7419 3642 7419 3641 7419 3645 7420 5948 7420 3647 7420 3647 7421 5948 7421 3721 7421 3647 7422 3721 7422 3651 7422 3651 7423 3721 7423 3722 7423 3722 7424 3721 7424 3723 7424 3722 7425 3723 7425 3649 7425 3649 7426 3723 7426 3724 7426 3649 7427 3724 7427 3648 7427 3648 7428 3724 7428 3720 7428 3648 7429 3720 7429 3641 7429 3655 7430 3637 7430 3725 7430 6052 7431 6051 7431 3725 7431 6051 7432 3484 7432 3725 7432 3725 7433 3484 7433 3726 7433 3725 7434 3726 7434 3655 7434 3484 7435 3485 7435 3726 7435 3726 7436 3485 7436 3727 7436 3726 7437 3727 7437 3728 7437 3728 7438 3727 7438 3729 7438 3728 7439 3729 7439 5945 7439 5945 7440 3729 7440 3488 7440 6052 7441 3725 7441 3730 7441 3730 7442 3725 7442 3720 7442 3730 7443 3720 7443 3731 7443 3731 7444 3720 7444 3724 7444 3731 7445 3724 7445 6053 7445 6053 7446 3724 7446 3723 7446 6053 7447 3723 7447 3732 7447 3732 7448 3723 7448 3721 7448 3732 7449 3721 7449 3490 7449 3490 7450 3721 7450 5948 7450 3490 7451 5948 7451 3488 7451 3488 7452 5948 7452 5946 7452 3488 7453 5946 7453 5945 7453 3617 7454 3747 7454 3611 7454 3611 7455 3747 7455 3733 7455 3611 7456 3733 7456 3602 7456 3748 7457 3734 7457 3736 7457 3736 7458 3734 7458 3600 7458 3736 7459 3600 7459 3598 7459 3747 7460 3616 7460 3748 7460 3748 7461 3616 7461 3595 7461 5966 7462 3748 7462 3735 7462 3735 7463 3748 7463 3736 7463 3735 7464 3736 7464 3737 7464 3737 7465 3736 7465 3738 7465 3737 7466 3738 7466 3739 7466 3739 7467 3738 7467 3757 7467 3739 7468 3757 7468 3741 7468 3741 7469 3757 7469 3740 7469 3741 7470 3740 7470 3742 7470 3742 7471 3740 7471 3753 7471 3742 7472 3753 7472 5970 7472 5970 7473 3753 7473 3743 7473 5970 7474 3743 7474 3744 7474 3744 7475 3743 7475 5944 7475 3744 7476 5944 7476 3745 7476 3745 7477 5944 7477 3733 7477 3745 7478 3733 7478 3746 7478 3746 7479 3733 7479 3747 7479 5966 7480 3573 7480 3748 7480 3748 7481 3573 7481 3749 7481 3748 7482 3749 7482 3747 7482 3747 7483 3749 7483 3571 7483 3747 7484 3571 7484 3746 7484 3603 7485 5944 7485 3750 7485 3750 7486 5944 7486 3743 7486 3750 7487 3743 7487 3604 7487 3604 7488 3743 7488 3751 7488 3751 7489 3743 7489 3753 7489 3751 7490 3753 7490 3752 7490 3752 7491 3753 7491 3754 7491 3754 7492 3753 7492 3740 7492 3754 7493 3740 7493 3755 7493 3755 7494 3740 7494 3756 7494 3756 7495 3740 7495 3757 7495 3756 7496 3757 7496 3609 7496 3609 7497 3757 7497 3738 7497 3609 7498 3738 7498 3606 7498 3606 7499 3738 7499 3736 7499 3606 7500 3736 7500 3598 7500 3758 7501 4000 7501 3759 7501 3759 7502 3775 7502 3758 7502 3758 7503 3775 7503 3777 7503 3758 7504 3777 7504 3760 7504 3777 7505 3761 7505 3760 7505 3760 7506 3761 7506 3762 7506 3760 7507 3762 7507 3763 7507 3762 7508 3772 7508 3763 7508 3763 7509 3772 7509 3764 7509 3763 7510 3764 7510 3993 7510 3993 7511 3764 7511 3765 7511 3993 7512 3765 7512 3994 7512 3765 7513 3771 7513 3994 7513 3994 7514 3771 7514 3769 7514 3994 7515 3769 7515 3766 7515 5939 7516 3767 7516 3770 7516 3770 7517 3767 7517 3766 7517 3770 7518 3766 7518 3768 7518 3768 7519 3766 7519 3769 7519 5939 7520 3770 7520 5925 7520 5925 7521 3770 7521 3783 7521 3770 7522 3768 7522 3783 7522 3783 7523 3768 7523 3769 7523 3783 7524 3769 7524 3782 7524 3769 7525 3771 7525 3782 7525 3782 7526 3771 7526 3765 7526 3782 7527 3765 7527 3780 7527 3765 7528 3764 7528 3780 7528 3780 7529 3764 7529 3772 7529 3780 7530 3772 7530 3773 7530 3772 7531 3762 7531 3773 7531 3773 7532 3762 7532 3761 7532 3773 7533 3761 7533 3776 7533 3759 7534 3774 7534 3775 7534 3775 7535 3774 7535 3776 7535 3775 7536 3776 7536 3777 7536 3777 7537 3776 7537 3761 7537 3774 7538 5321 7538 3776 7538 3776 7539 5321 7539 3778 7539 3776 7540 3778 7540 3773 7540 3773 7541 3778 7541 3779 7541 3773 7542 3779 7542 3780 7542 3780 7543 3779 7543 3781 7543 3780 7544 3781 7544 3782 7544 3782 7545 3781 7545 5317 7545 3782 7546 5317 7546 3783 7546 3783 7547 5317 7547 3784 7547 3783 7548 3784 7548 5925 7548 5925 7549 3784 7549 3785 7549 3796 7550 3786 7550 3797 7550 3797 7551 3786 7551 3787 7551 3797 7552 3787 7552 3798 7552 3798 7553 3787 7553 3949 7553 3798 7554 3949 7554 3799 7554 3799 7555 3949 7555 3788 7555 3799 7556 3788 7556 3800 7556 3800 7557 3788 7557 3789 7557 3800 7558 3789 7558 3791 7558 3791 7559 3789 7559 3790 7559 3791 7560 3790 7560 3792 7560 3792 7561 3790 7561 3794 7561 3792 7562 3794 7562 3793 7562 3793 7563 3794 7563 3795 7563 5903 7564 3796 7564 3810 7564 3810 7565 3796 7565 3797 7565 3810 7566 3797 7566 3808 7566 3808 7567 3797 7567 3798 7567 3808 7568 3798 7568 3806 7568 3806 7569 3798 7569 3799 7569 3806 7570 3799 7570 3804 7570 3804 7571 3799 7571 3800 7571 3804 7572 3800 7572 3801 7572 3801 7573 3800 7573 3791 7573 3801 7574 3791 7574 3802 7574 3802 7575 3791 7575 3792 7575 3802 7576 3792 7576 5911 7576 5911 7577 3792 7577 3793 7577 5911 7578 5910 7578 3802 7578 3802 7579 5910 7579 3803 7579 3802 7580 3803 7580 3801 7580 3801 7581 3803 7581 5315 7581 3801 7582 5315 7582 3804 7582 3804 7583 5315 7583 3805 7583 3804 7584 3805 7584 3806 7584 3806 7585 3805 7585 3807 7585 3806 7586 3807 7586 3808 7586 3808 7587 3807 7587 3809 7587 3808 7588 3809 7588 3810 7588 3810 7589 3809 7589 3811 7589 3810 7590 3811 7590 5903 7590 5903 7591 3811 7591 5905 7591 3977 7592 3828 7592 3812 7592 3812 7593 3828 7593 3827 7593 3812 7594 3827 7594 3978 7594 3978 7595 3827 7595 3813 7595 3813 7596 3814 7596 3978 7596 3978 7597 3814 7597 3816 7597 3978 7598 3816 7598 3815 7598 3816 7599 3817 7599 3815 7599 3815 7600 3817 7600 3818 7600 3815 7601 3818 7601 3819 7601 5898 7602 3820 7602 3821 7602 3821 7603 3820 7603 3973 7603 3821 7604 3973 7604 3822 7604 3822 7605 3973 7605 3819 7605 3822 7606 3819 7606 3823 7606 3823 7607 3819 7607 3818 7607 5897 7608 5898 7608 3821 7608 5897 7609 3821 7609 3834 7609 3834 7610 3821 7610 3822 7610 3834 7611 3822 7611 3824 7611 3824 7612 3822 7612 3823 7612 3824 7613 3823 7613 3825 7613 3823 7614 3818 7614 3825 7614 3825 7615 3818 7615 3817 7615 3825 7616 3817 7616 3831 7616 3817 7617 3816 7617 3831 7617 3831 7618 3816 7618 3814 7618 3831 7619 3814 7619 3826 7619 3814 7620 3813 7620 3826 7620 3826 7621 3813 7621 3827 7621 3826 7622 3827 7622 3829 7622 3829 7623 3827 7623 3828 7623 3829 7624 3828 7624 5889 7624 5889 7625 5305 7625 3829 7625 3829 7626 5305 7626 5303 7626 3829 7627 5303 7627 3826 7627 3826 7628 5303 7628 3830 7628 3826 7629 3830 7629 3831 7629 3831 7630 3830 7630 3832 7630 3831 7631 3832 7631 3825 7631 3825 7632 3832 7632 3833 7632 3825 7633 3833 7633 3824 7633 3824 7634 3833 7634 3835 7634 3824 7635 3835 7635 3834 7635 3834 7636 3835 7636 5309 7636 3834 7637 5309 7637 5897 7637 5897 7638 5309 7638 5308 7638 3836 7639 3926 7639 3843 7639 3843 7640 3926 7640 3837 7640 3843 7641 3837 7641 3844 7641 3844 7642 3837 7642 3928 7642 3844 7643 3928 7643 3846 7643 3846 7644 3928 7644 3838 7644 3846 7645 3838 7645 3839 7645 3839 7646 3838 7646 3931 7646 3839 7647 3931 7647 3840 7647 3840 7648 3931 7648 3932 7648 3840 7649 3932 7649 3849 7649 3849 7650 3932 7650 3934 7650 3849 7651 3934 7651 3841 7651 3841 7652 3934 7652 3936 7652 3856 7653 3836 7653 3842 7653 3842 7654 3836 7654 3843 7654 3842 7655 3843 7655 3854 7655 3854 7656 3843 7656 3844 7656 3854 7657 3844 7657 3845 7657 3845 7658 3844 7658 3846 7658 3845 7659 3846 7659 3847 7659 3847 7660 3846 7660 3839 7660 3847 7661 3839 7661 3851 7661 3851 7662 3839 7662 3840 7662 3851 7663 3840 7663 3848 7663 3848 7664 3840 7664 3849 7664 3848 7665 3849 7665 5873 7665 5873 7666 3849 7666 3841 7666 5873 7667 3850 7667 3848 7667 3848 7668 3850 7668 5296 7668 3848 7669 5296 7669 3851 7669 3851 7670 5296 7670 3852 7670 3851 7671 3852 7671 3847 7671 3847 7672 3852 7672 3853 7672 3847 7673 3853 7673 3845 7673 3845 7674 3853 7674 5299 7674 3845 7675 5299 7675 3854 7675 3854 7676 5299 7676 3855 7676 3854 7677 3855 7677 3842 7677 3842 7678 3855 7678 5300 7678 3842 7679 5300 7679 3856 7679 3856 7680 5300 7680 3857 7680 3858 7681 5510 7681 5509 7681 3996 7682 3858 7682 3995 7682 3995 7683 3858 7683 5509 7683 3995 7684 5509 7684 3898 7684 3898 7685 5509 7685 3859 7685 3878 7686 5505 7686 3861 7686 3861 7687 3894 7687 3860 7687 3860 7688 3892 7688 3861 7688 3861 7689 3892 7689 3879 7689 3861 7690 3879 7690 3878 7690 3865 7691 3862 7691 3863 7691 3863 7692 3916 7692 3915 7692 3915 7693 3974 7693 3863 7693 3863 7694 3974 7694 3864 7694 3863 7695 3864 7695 3865 7695 5498 7696 3871 7696 5496 7696 5496 7697 3871 7697 3870 7697 3870 7698 3876 7698 5496 7698 5496 7699 3876 7699 3866 7699 5496 7700 3866 7700 3875 7700 3871 7701 5498 7701 5499 7701 4587 7702 3867 7702 3868 7702 3868 7703 3867 7703 3869 7703 3868 7704 3869 7704 5499 7704 5499 7705 3869 7705 3870 7705 5499 7706 3870 7706 3871 7706 5149 7707 5863 7707 4586 7707 4586 7708 5863 7708 3920 7708 4586 7709 3920 7709 4587 7709 4587 7710 3920 7710 3867 7710 3922 7711 5868 7711 3872 7711 3872 7712 5868 7712 3874 7712 3877 7713 3873 7713 5275 7713 5275 7714 3873 7714 3872 7714 5275 7715 3872 7715 5276 7715 5276 7716 3872 7716 3874 7716 3875 7717 3866 7717 5274 7717 5274 7718 3866 7718 3876 7718 5274 7719 3876 7719 5273 7719 5273 7720 3876 7720 3918 7720 5273 7721 3918 7721 3877 7721 3877 7722 3918 7722 3873 7722 5505 7723 3878 7723 4581 7723 4581 7724 3878 7724 3879 7724 4581 7725 3879 7725 3881 7725 3881 7726 3879 7726 3880 7726 3881 7727 3880 7727 3884 7727 3882 7728 3881 7728 3883 7728 3883 7729 3881 7729 3884 7729 3882 7730 3883 7730 5141 7730 5141 7731 3883 7731 3941 7731 5141 7732 3941 7732 5154 7732 3885 7733 3886 7733 3887 7733 3887 7734 3886 7734 3888 7734 3887 7735 3888 7735 3941 7735 3941 7736 3888 7736 5154 7736 5859 7737 5858 7737 3889 7737 3889 7738 5858 7738 3890 7738 3889 7739 3890 7739 4582 7739 3891 7740 4582 7740 3940 7740 3940 7741 4582 7741 3890 7741 3940 7742 3950 7742 3891 7742 3891 7743 3950 7743 3892 7743 3891 7744 3892 7744 3893 7744 3893 7745 3892 7745 3860 7745 3893 7746 3860 7746 3894 7746 3983 7747 3895 7747 3896 7747 3896 7748 3895 7748 3995 7748 3896 7749 3995 7749 3897 7749 3897 7750 3995 7750 3898 7750 3897 7751 3898 7751 3859 7751 3899 7752 3984 7752 3896 7752 3896 7753 3984 7753 3983 7753 5853 7754 3985 7754 5163 7754 5163 7755 3985 7755 3984 7755 5163 7756 3984 7756 3899 7756 5857 7757 3901 7757 3900 7757 3900 7758 3901 7758 3902 7758 3900 7759 3902 7759 3903 7759 3903 7760 3902 7760 5186 7760 3903 7761 5186 7761 3986 7761 3986 7762 5186 7762 5184 7762 3904 7763 3981 7763 4583 7763 4583 7764 3981 7764 3986 7764 4583 7765 3986 7765 5184 7765 3906 7766 3980 7766 3904 7766 3904 7767 3980 7767 3981 7767 5510 7768 3858 7768 3905 7768 3905 7769 3858 7769 3996 7769 3905 7770 3996 7770 3906 7770 3906 7771 3996 7771 3997 7771 3906 7772 3997 7772 3980 7772 4591 7773 3907 7773 4589 7773 4589 7774 3907 7774 3955 7774 4589 7775 3955 7775 5145 7775 5145 7776 3955 7776 3908 7776 5145 7777 3908 7777 5146 7777 3862 7778 3865 7778 5502 7778 5502 7779 3865 7779 3864 7779 5502 7780 3864 7780 4591 7780 4591 7781 3864 7781 3972 7781 4591 7782 3972 7782 3907 7782 5150 7783 5146 7783 3908 7783 3960 7784 5848 7784 3909 7784 3909 7785 5848 7785 5150 7785 3909 7786 5150 7786 3958 7786 3958 7787 5150 7787 3908 7787 5851 7788 3910 7788 5140 7788 5140 7789 3910 7789 3911 7789 5140 7790 3911 7790 3912 7790 3914 7791 3912 7791 3913 7791 3913 7792 3912 7792 3911 7792 3913 7793 3957 7793 3914 7793 3914 7794 3957 7794 3974 7794 3914 7795 3974 7795 5500 7795 5500 7796 3974 7796 3915 7796 5500 7797 3915 7797 3916 7797 3872 7798 3873 7798 3917 7798 3917 7799 3873 7799 3918 7799 3919 7800 3869 7800 3920 7800 3920 7801 3869 7801 3867 7801 3872 7802 3917 7802 3935 7802 3872 7803 3935 7803 3922 7803 3922 7804 3935 7804 3921 7804 3922 7805 3921 7805 5866 7805 5866 7806 3921 7806 3933 7806 5866 7807 3933 7807 3923 7807 3923 7808 3933 7808 3930 7808 3923 7809 3930 7809 5864 7809 5864 7810 3930 7810 3924 7810 5864 7811 3924 7811 3925 7811 3925 7812 3924 7812 3929 7812 3925 7813 3929 7813 5862 7813 5862 7814 3929 7814 3919 7814 5862 7815 3919 7815 3920 7815 3918 7816 3876 7816 3870 7816 3869 7817 3928 7817 3837 7817 3837 7818 3926 7818 3869 7818 3869 7819 3926 7819 3927 7819 3869 7820 3927 7820 3870 7820 3870 7821 3927 7821 3938 7821 3870 7822 3938 7822 3918 7822 3869 7823 3919 7823 3928 7823 3928 7824 3919 7824 3929 7824 3928 7825 3929 7825 3838 7825 3838 7826 3929 7826 3924 7826 3838 7827 3924 7827 3931 7827 3931 7828 3924 7828 3930 7828 3931 7829 3930 7829 3932 7829 3932 7830 3930 7830 3933 7830 3932 7831 3933 7831 3934 7831 3934 7832 3933 7832 3921 7832 3934 7833 3921 7833 3936 7833 3936 7834 3921 7834 3935 7834 3936 7835 3935 7835 5878 7835 5878 7836 3935 7836 3917 7836 5878 7837 3917 7837 3937 7837 3937 7838 3917 7838 3918 7838 3937 7839 3918 7839 5882 7839 5882 7840 3918 7840 3938 7840 3884 7841 3880 7841 3883 7841 3883 7842 3880 7842 3939 7842 3883 7843 3939 7843 3941 7843 3950 7844 3940 7844 3948 7844 3948 7845 3940 7845 3890 7845 3948 7846 3890 7846 5858 7846 3941 7847 3939 7847 3942 7847 3941 7848 3942 7848 3887 7848 3887 7849 3942 7849 3952 7849 3887 7850 3952 7850 3885 7850 3885 7851 3952 7851 3953 7851 3885 7852 3953 7852 3943 7852 3943 7853 3953 7853 3954 7853 3943 7854 3954 7854 5860 7854 5860 7855 3954 7855 3944 7855 5860 7856 3944 7856 3945 7856 3945 7857 3944 7857 3946 7857 3945 7858 3946 7858 3947 7858 3947 7859 3946 7859 3948 7859 3947 7860 3948 7860 5858 7860 3880 7861 3879 7861 3892 7861 3950 7862 3788 7862 3949 7862 3949 7863 3787 7863 3950 7863 3950 7864 3787 7864 3786 7864 3950 7865 3786 7865 3892 7865 3892 7866 3786 7866 5924 7866 3892 7867 5924 7867 3880 7867 5924 7868 5923 7868 3880 7868 3880 7869 5923 7869 3951 7869 3880 7870 3951 7870 3939 7870 3939 7871 3951 7871 5922 7871 3939 7872 5922 7872 3942 7872 3942 7873 5922 7873 5921 7873 3942 7874 5921 7874 3952 7874 3952 7875 5921 7875 3795 7875 3952 7876 3795 7876 3953 7876 3953 7877 3795 7877 3794 7877 3953 7878 3794 7878 3954 7878 3954 7879 3794 7879 3790 7879 3954 7880 3790 7880 3944 7880 3944 7881 3790 7881 3789 7881 3944 7882 3789 7882 3946 7882 3946 7883 3789 7883 3788 7883 3946 7884 3788 7884 3948 7884 3948 7885 3788 7885 3950 7885 3907 7886 3972 7886 3955 7886 3955 7887 3972 7887 3956 7887 3955 7888 3956 7888 3908 7888 3957 7889 3913 7889 3970 7889 3970 7890 3913 7890 3911 7890 3970 7891 3911 7891 3910 7891 3908 7892 3956 7892 3958 7892 3958 7893 3956 7893 3959 7893 3958 7894 3959 7894 3909 7894 3909 7895 3959 7895 3960 7895 3960 7896 3959 7896 3979 7896 3960 7897 3979 7897 3961 7897 3961 7898 3979 7898 5849 7898 5849 7899 3979 7899 3963 7899 5849 7900 3963 7900 3962 7900 3962 7901 3963 7901 3964 7901 3964 7902 3963 7902 3965 7902 3964 7903 3965 7903 3966 7903 3966 7904 3965 7904 3967 7904 3966 7905 3967 7905 3968 7905 3968 7906 3967 7906 3969 7906 3968 7907 3969 7907 3971 7907 3971 7908 3969 7908 3970 7908 3971 7909 3970 7909 3910 7909 3972 7910 3864 7910 3974 7910 3972 7911 3974 7911 3976 7911 3819 7912 3973 7912 3957 7912 3957 7913 3973 7913 3820 7913 3957 7914 3820 7914 3974 7914 3974 7915 3820 7915 3975 7915 3974 7916 3975 7916 3976 7916 3976 7917 5902 7917 3972 7917 3972 7918 5902 7918 5901 7918 3972 7919 5901 7919 3956 7919 3956 7920 5901 7920 5900 7920 3956 7921 5900 7921 3959 7921 3959 7922 5900 7922 3977 7922 3957 7923 3970 7923 3819 7923 3819 7924 3970 7924 3969 7924 3819 7925 3969 7925 3815 7925 3815 7926 3969 7926 3967 7926 3815 7927 3967 7927 3978 7927 3978 7928 3967 7928 3965 7928 3978 7929 3965 7929 3812 7929 3812 7930 3965 7930 3963 7930 3812 7931 3963 7931 3977 7931 3977 7932 3963 7932 3979 7932 3977 7933 3979 7933 3959 7933 3980 7934 3997 7934 3981 7934 3981 7935 3997 7935 3982 7935 3981 7936 3982 7936 3986 7936 3895 7937 3983 7937 3991 7937 3991 7938 3983 7938 3984 7938 3991 7939 3984 7939 3985 7939 3986 7940 3982 7940 4002 7940 3986 7941 4002 7941 3903 7941 3903 7942 4002 7942 3987 7942 3903 7943 3987 7943 3900 7943 3900 7944 3987 7944 5857 7944 5857 7945 3987 7945 4001 7945 5857 7946 4001 7946 3988 7946 3988 7947 4001 7947 3989 7947 3988 7948 3989 7948 5855 7948 5855 7949 3989 7949 3999 7949 5855 7950 3999 7950 5854 7950 5854 7951 3999 7951 3990 7951 5854 7952 3990 7952 3992 7952 3992 7953 3990 7953 3991 7953 3992 7954 3991 7954 3985 7954 3982 7955 3997 7955 4003 7955 3895 7956 3763 7956 3993 7956 3993 7957 3994 7957 3895 7957 3895 7958 3994 7958 3766 7958 3895 7959 3766 7959 3995 7959 3766 7960 3767 7960 3995 7960 3995 7961 3767 7961 5943 7961 3995 7962 5943 7962 3996 7962 3996 7963 5943 7963 3998 7963 3996 7964 3998 7964 3997 7964 3997 7965 3998 7965 5942 7965 3997 7966 5942 7966 4003 7966 3895 7967 3991 7967 3763 7967 3763 7968 3991 7968 3990 7968 3763 7969 3990 7969 3760 7969 3760 7970 3990 7970 3999 7970 3760 7971 3999 7971 3758 7971 3758 7972 3999 7972 3989 7972 3758 7973 3989 7973 4000 7973 4000 7974 3989 7974 4001 7974 4000 7975 4001 7975 5940 7975 5940 7976 4001 7976 3987 7976 5940 7977 3987 7977 4003 7977 4003 7978 3987 7978 4002 7978 4003 7979 4002 7979 3982 7979 5841 7980 4248 7980 4004 7980 4004 7981 4248 7981 4005 7981 4004 7982 4005 7982 4006 7982 4006 7983 4005 7983 4007 7983 4006 7984 4007 7984 4015 7984 4015 7985 4007 7985 4008 7985 4015 7986 4008 7986 4016 7986 4016 7987 4008 7987 4009 7987 4016 7988 4009 7988 4011 7988 4011 7989 4009 7989 4010 7989 4011 7990 4010 7990 4018 7990 4018 7991 4010 7991 4251 7991 4018 7992 4251 7992 4019 7992 4019 7993 4251 7993 4252 7993 4025 7994 5841 7994 4012 7994 4012 7995 5841 7995 4004 7995 4012 7996 4004 7996 4013 7996 4013 7997 4004 7997 4006 7997 4013 7998 4006 7998 4014 7998 4014 7999 4006 7999 4015 7999 4014 8000 4015 8000 4021 8000 4021 8001 4015 8001 4016 8001 4021 8002 4016 8002 4017 8002 4017 8003 4016 8003 4011 8003 4017 8004 4011 8004 4020 8004 4020 8005 4011 8005 4018 8005 4020 8006 4018 8006 5835 8006 5835 8007 4018 8007 4019 8007 5835 8008 5332 8008 4020 8008 4020 8009 5332 8009 5331 8009 4020 8010 5331 8010 4017 8010 4017 8011 5331 8011 5337 8011 4017 8012 5337 8012 4021 8012 4021 8013 5337 8013 4022 8013 4021 8014 4022 8014 4014 8014 4014 8015 4022 8015 4023 8015 4014 8016 4023 8016 4013 8016 4013 8017 4023 8017 4024 8017 4013 8018 4024 8018 4012 8018 4012 8019 4024 8019 5334 8019 4012 8020 5334 8020 4025 8020 4025 8021 5334 8021 5831 8021 4027 8022 4026 8022 5812 8022 5812 8023 4042 8023 4027 8023 4027 8024 4042 8024 4043 8024 4027 8025 4043 8025 4210 8025 4043 8026 4041 8026 4210 8026 4210 8027 4041 8027 4040 8027 4210 8028 4040 8028 4028 8028 4040 8029 4039 8029 4028 8029 4028 8030 4039 8030 4038 8030 4028 8031 4038 8031 4211 8031 4211 8032 4038 8032 4037 8032 4211 8033 4037 8033 4203 8033 4037 8034 4035 8034 4203 8034 4203 8035 4035 8035 4031 8035 4203 8036 4031 8036 4030 8036 5820 8037 4205 8037 4029 8037 4029 8038 4205 8038 4030 8038 4029 8039 4030 8039 4034 8039 4034 8040 4030 8040 4031 8040 5820 8041 4029 8041 4032 8041 4032 8042 4029 8042 4033 8042 4029 8043 4034 8043 4033 8043 4033 8044 4034 8044 4031 8044 4033 8045 4031 8045 4048 8045 4031 8046 4035 8046 4048 8046 4048 8047 4035 8047 4037 8047 4048 8048 4037 8048 4036 8048 4037 8049 4038 8049 4036 8049 4036 8050 4038 8050 4039 8050 4036 8051 4039 8051 4046 8051 4039 8052 4040 8052 4046 8052 4046 8053 4040 8053 4041 8053 4046 8054 4041 8054 4045 8054 5812 8055 4044 8055 4042 8055 4042 8056 4044 8056 4045 8056 4042 8057 4045 8057 4043 8057 4043 8058 4045 8058 4041 8058 4044 8059 5339 8059 4045 8059 4045 8060 5339 8060 5341 8060 4045 8061 5341 8061 4046 8061 4046 8062 5341 8062 4047 8062 4046 8063 4047 8063 4036 8063 4036 8064 4047 8064 5340 8064 4036 8065 5340 8065 4048 8065 4048 8066 5340 8066 4049 8066 4048 8067 4049 8067 4033 8067 4033 8068 4049 8068 4050 8068 4033 8069 4050 8069 4032 8069 4032 8070 4050 8070 5338 8070 4230 8071 5801 8071 5794 8071 5794 8072 4051 8072 4230 8072 4230 8073 4051 8073 4074 8073 4230 8074 4074 8074 4052 8074 4052 8075 4074 8075 4072 8075 4072 8076 4071 8076 4052 8076 4052 8077 4071 8077 4053 8077 4052 8078 4053 8078 4054 8078 4053 8079 4068 8079 4054 8079 4054 8080 4068 8080 4067 8080 4054 8081 4067 8081 4055 8081 4067 8082 4056 8082 4055 8082 4055 8083 4056 8083 4063 8083 4055 8084 4063 8084 4224 8084 5800 8085 4057 8085 4058 8085 4058 8086 4057 8086 4224 8086 4058 8087 4224 8087 4060 8087 4060 8088 4224 8088 4063 8088 4059 8089 5800 8089 4076 8089 4076 8090 5800 8090 4058 8090 4076 8091 4058 8091 4061 8091 4061 8092 4058 8092 4060 8092 4061 8093 4060 8093 4062 8093 4062 8094 4060 8094 4063 8094 4062 8095 4063 8095 4064 8095 4064 8096 4063 8096 4056 8096 4064 8097 4056 8097 4065 8097 4065 8098 4056 8098 4067 8098 4065 8099 4067 8099 4066 8099 4066 8100 4067 8100 4068 8100 4066 8101 4068 8101 4069 8101 4069 8102 4068 8102 4053 8102 4069 8103 4053 8103 4070 8103 4070 8104 4053 8104 4071 8104 4070 8105 4071 8105 4081 8105 4081 8106 4071 8106 4072 8106 4081 8107 4072 8107 4073 8107 4073 8108 4072 8108 4074 8108 4073 8109 4074 8109 4075 8109 4075 8110 4074 8110 4051 8110 4075 8111 4051 8111 5792 8111 5792 8112 4051 8112 5794 8112 4077 8113 5352 8113 4059 8113 4059 8114 4076 8114 4077 8114 4077 8115 4076 8115 4061 8115 4077 8116 4061 8116 5349 8116 5349 8117 4061 8117 4062 8117 4062 8118 4064 8118 5349 8118 5349 8119 4064 8119 4065 8119 5349 8120 4065 8120 4078 8120 4065 8121 4066 8121 4078 8121 4078 8122 4066 8122 4069 8122 4078 8123 4069 8123 4079 8123 4069 8124 4070 8124 4079 8124 4079 8125 4070 8125 4081 8125 4079 8126 4081 8126 4080 8126 5792 8127 5350 8127 4075 8127 4075 8128 5350 8128 4080 8128 4075 8129 4080 8129 4073 8129 4073 8130 4080 8130 4081 8130 4259 8131 4082 8131 4099 8131 4099 8132 4101 8132 4259 8132 4259 8133 4101 8133 4103 8133 4259 8134 4103 8134 4263 8134 4103 8135 4097 8135 4263 8135 4263 8136 4097 8136 4083 8136 4263 8137 4083 8137 4084 8137 4083 8138 4096 8138 4084 8138 4084 8139 4096 8139 4085 8139 4084 8140 4085 8140 4264 8140 4264 8141 4085 8141 4086 8141 4264 8142 4086 8142 4087 8142 4086 8143 4095 8143 4087 8143 4087 8144 4095 8144 4089 8144 4087 8145 4089 8145 4265 8145 4088 8146 5776 8146 4092 8146 4092 8147 5776 8147 4265 8147 4092 8148 4265 8148 4093 8148 4093 8149 4265 8149 4089 8149 4088 8150 4092 8150 4090 8150 4090 8151 4092 8151 4091 8151 4092 8152 4093 8152 4091 8152 4091 8153 4093 8153 4089 8153 4091 8154 4089 8154 4094 8154 4089 8155 4095 8155 4094 8155 4094 8156 4095 8156 4086 8156 4094 8157 4086 8157 4105 8157 4086 8158 4085 8158 4105 8158 4105 8159 4085 8159 4096 8159 4105 8160 4096 8160 4098 8160 4096 8161 4083 8161 4098 8161 4098 8162 4083 8162 4097 8162 4098 8163 4097 8163 4102 8163 4099 8164 4100 8164 4101 8164 4101 8165 4100 8165 4102 8165 4101 8166 4102 8166 4103 8166 4103 8167 4102 8167 4097 8167 4100 8168 5367 8168 4102 8168 4102 8169 5367 8169 5357 8169 4102 8170 5357 8170 4098 8170 4098 8171 5357 8171 4104 8171 4098 8172 4104 8172 4105 8172 4105 8173 4104 8173 4106 8173 4105 8174 4106 8174 4094 8174 4094 8175 4106 8175 5359 8175 4094 8176 5359 8176 4091 8176 4091 8177 5359 8177 5364 8177 4091 8178 5364 8178 4090 8178 4090 8179 5364 8179 4107 8179 4156 8180 4155 8180 4108 8180 4108 8181 5245 8181 4109 8181 4109 8182 4172 8182 4108 8182 4108 8183 4172 8183 4110 8183 4108 8184 4110 8184 4156 8184 4111 8185 4141 8185 4114 8185 4114 8186 4141 8186 4112 8186 4112 8187 4204 8187 4114 8187 4114 8188 4204 8188 4113 8188 4114 8189 4113 8189 5247 8189 5255 8190 4178 8190 5261 8190 5261 8191 4178 8191 4177 8191 4177 8192 4189 8192 5261 8192 5261 8193 4189 8193 4115 8193 5261 8194 4115 8194 5260 8194 4120 8195 5264 8195 4117 8195 4117 8196 4138 8196 4116 8196 4116 8197 4137 8197 4117 8197 4117 8198 4137 8198 4118 8198 4117 8199 4118 8199 4120 8199 5264 8200 4120 8200 4119 8200 4119 8201 4120 8201 4118 8201 4119 8202 4118 8202 4121 8202 4121 8203 4118 8203 4122 8203 4121 8204 4122 8204 4125 8204 4123 8205 4121 8205 4124 8205 4124 8206 4121 8206 4125 8206 4123 8207 4124 8207 4126 8207 4126 8208 4124 8208 4127 8208 4126 8209 4127 8209 4129 8209 4128 8210 4129 8210 4127 8210 4127 8211 4267 8211 4128 8211 4128 8212 4267 8212 4268 8212 4128 8213 4268 8213 4130 8213 4268 8214 4269 8214 4130 8214 4130 8215 4269 8215 4271 8215 4130 8216 4271 8216 4131 8216 4271 8217 4272 8217 4131 8217 4131 8218 4272 8218 4132 8218 4131 8219 4132 8219 5079 8219 4132 8220 4274 8220 5079 8220 5079 8221 4274 8221 4276 8221 5079 8222 4276 8222 5082 8222 5082 8223 4276 8223 4133 8223 5082 8224 4133 8224 4134 8224 4134 8225 4133 8225 4277 8225 4134 8226 4277 8226 5763 8226 5083 8227 4257 8227 5069 8227 5069 8228 4257 8228 4256 8228 5069 8229 4256 8229 5068 8229 4135 8230 5068 8230 4136 8230 4136 8231 5068 8231 4256 8231 4136 8232 4258 8232 4135 8232 4135 8233 4258 8233 4137 8233 4135 8234 4137 8234 5067 8234 5067 8235 4137 8235 4116 8235 5067 8236 4116 8236 4138 8236 4193 8237 4192 8237 4139 8237 4139 8238 4192 8238 4112 8238 4139 8239 4112 8239 4140 8239 4140 8240 4112 8240 4141 8240 4140 8241 4141 8241 4111 8241 4143 8242 4142 8242 4139 8242 4139 8243 4142 8243 4193 8243 5178 8244 4202 8244 4577 8244 4577 8245 4202 8245 4142 8245 4577 8246 4142 8246 4143 8246 5169 8247 5168 8247 4152 8247 4152 8248 4194 8248 5169 8248 5169 8249 4194 8249 4144 8249 5169 8250 4144 8250 5160 8250 4144 8251 4145 8251 5160 8251 5160 8252 4145 8252 4146 8252 5160 8253 4146 8253 4148 8253 4146 8254 4147 8254 4148 8254 4148 8255 4147 8255 4197 8255 4148 8256 4197 8256 5171 8256 5171 8257 4197 8257 4198 8257 5171 8258 4198 8258 5173 8258 5173 8259 4198 8259 4149 8259 5173 8260 4149 8260 4199 8260 4150 8261 4151 8261 5161 8261 5161 8262 4151 8262 4152 8262 5161 8263 4152 8263 5168 8263 4154 8264 4153 8264 4150 8264 4150 8265 4153 8265 4151 8265 5247 8266 4113 8266 5243 8266 5243 8267 4113 8267 4204 8267 5243 8268 4204 8268 4154 8268 4154 8269 4204 8269 4190 8269 4154 8270 4190 8270 4153 8270 4155 8271 4156 8271 4157 8271 4157 8272 4156 8272 4110 8272 4157 8273 4110 8273 4158 8273 4158 8274 4110 8274 4234 8274 4158 8275 4234 8275 4159 8275 4578 8276 4158 8276 4233 8276 4233 8277 4158 8277 4159 8277 4578 8278 4233 8278 4160 8278 4160 8279 4233 8279 4235 8279 4160 8280 4235 8280 4161 8280 4161 8281 4235 8281 4162 8281 4162 8282 4235 8282 4163 8282 4162 8283 4163 8283 4164 8283 4164 8284 4163 8284 4165 8284 4164 8285 4165 8285 4166 8285 4166 8286 4165 8286 4241 8286 4166 8287 4241 8287 4167 8287 4167 8288 4241 8288 4168 8288 4167 8289 4168 8289 4242 8289 4169 8290 4170 8290 4576 8290 4576 8291 4170 8291 4237 8291 4576 8292 4237 8292 4574 8292 4171 8293 4574 8293 4236 8293 4236 8294 4574 8294 4237 8294 4236 8295 4250 8295 4171 8295 4171 8296 4250 8296 4172 8296 4171 8297 4172 8297 5252 8297 5252 8298 4172 8298 4109 8298 5252 8299 4109 8299 5245 8299 4173 8300 4571 8300 4174 8300 4174 8301 4571 8301 4176 8301 5758 8302 4175 8302 4310 8302 4310 8303 4175 8303 4176 8303 4310 8304 4176 8304 4571 8304 4174 8305 4232 8305 4173 8305 4173 8306 4232 8306 4177 8306 4173 8307 4177 8307 5254 8307 5254 8308 4177 8308 4178 8308 5254 8309 4178 8309 5255 8309 5175 8310 5176 8310 4213 8310 4213 8311 4179 8311 5175 8311 5175 8312 4179 8312 4215 8312 5175 8313 4215 8313 4182 8313 4215 8314 4180 8314 4182 8314 4182 8315 4180 8315 4181 8315 4182 8316 4181 8316 4183 8316 4181 8317 4217 8317 4183 8317 4183 8318 4217 8318 4219 8318 4183 8319 4219 8319 4184 8319 4223 8320 5138 8320 4221 8320 4221 8321 5138 8321 4184 8321 4221 8322 4184 8322 4220 8322 4220 8323 4184 8323 4219 8323 4187 8324 4212 8324 5177 8324 5177 8325 4212 8325 4213 8325 5177 8326 4213 8326 5176 8326 4185 8327 4186 8327 4187 8327 4187 8328 4186 8328 4212 8328 5260 8329 4115 8329 4188 8329 4188 8330 4115 8330 4189 8330 4188 8331 4189 8331 4185 8331 4185 8332 4189 8332 4225 8332 4185 8333 4225 8333 4186 8333 4153 8334 4190 8334 4151 8334 4151 8335 4190 8335 4191 8335 4151 8336 4191 8336 4152 8336 4192 8337 4193 8337 4201 8337 4201 8338 4193 8338 4142 8338 4201 8339 4142 8339 4202 8339 4152 8340 4191 8340 4194 8340 4194 8341 4191 8341 4195 8341 4194 8342 4195 8342 4144 8342 4144 8343 4195 8343 4145 8343 4145 8344 4195 8344 4196 8344 4145 8345 4196 8345 4146 8345 4146 8346 4196 8346 4147 8346 4147 8347 4196 8347 4207 8347 4147 8348 4207 8348 4197 8348 4197 8349 4207 8349 4198 8349 4198 8350 4207 8350 4208 8350 4198 8351 4208 8351 4149 8351 4149 8352 4208 8352 4199 8352 4199 8353 4208 8353 4209 8353 4199 8354 4209 8354 5762 8354 5762 8355 4209 8355 4200 8355 4200 8356 4209 8356 4201 8356 4200 8357 4201 8357 4202 8357 4211 8358 4203 8358 4192 8358 4192 8359 4203 8359 4204 8359 4192 8360 4204 8360 4112 8360 4203 8361 4030 8361 4204 8361 4204 8362 4030 8362 4205 8362 4204 8363 4205 8363 4190 8363 4190 8364 4205 8364 4206 8364 4190 8365 4206 8365 4191 8365 4191 8366 4206 8366 5823 8366 4191 8367 5823 8367 4195 8367 4195 8368 5823 8368 5825 8368 4195 8369 5825 8369 4196 8369 4196 8370 5825 8370 5829 8370 4196 8371 5829 8371 4207 8371 4207 8372 5829 8372 5827 8372 4207 8373 5827 8373 4208 8373 4208 8374 5827 8374 4026 8374 4208 8375 4026 8375 4209 8375 4209 8376 4026 8376 4027 8376 4209 8377 4027 8377 4201 8377 4201 8378 4027 8378 4210 8378 4201 8379 4210 8379 4192 8379 4192 8380 4210 8380 4028 8380 4192 8381 4028 8381 4211 8381 4186 8382 4225 8382 4212 8382 4212 8383 4225 8383 4226 8383 4212 8384 4226 8384 4213 8384 4232 8385 4174 8385 4231 8385 4231 8386 4174 8386 4176 8386 4231 8387 4176 8387 4175 8387 4213 8388 4226 8388 4179 8388 4179 8389 4226 8389 4214 8389 4179 8390 4214 8390 4215 8390 4215 8391 4214 8391 4180 8391 4180 8392 4214 8392 4216 8392 4180 8393 4216 8393 4181 8393 4181 8394 4216 8394 4217 8394 4217 8395 4216 8395 4218 8395 4217 8396 4218 8396 4219 8396 4219 8397 4218 8397 4220 8397 4220 8398 4218 8398 4222 8398 4220 8399 4222 8399 4221 8399 4221 8400 4222 8400 4223 8400 4223 8401 4222 8401 4229 8401 4223 8402 4229 8402 5759 8402 5759 8403 4229 8403 5757 8403 5757 8404 4229 8404 4231 8404 5757 8405 4231 8405 4175 8405 4232 8406 4054 8406 4055 8406 4055 8407 4225 8407 4232 8407 4232 8408 4225 8408 4189 8408 4232 8409 4189 8409 4177 8409 4055 8410 4224 8410 4225 8410 4225 8411 4224 8411 4057 8411 4225 8412 4057 8412 4226 8412 4226 8413 4057 8413 5806 8413 4226 8414 5806 8414 4214 8414 4214 8415 5806 8415 4227 8415 4214 8416 4227 8416 4216 8416 4216 8417 4227 8417 4228 8417 4216 8418 4228 8418 4218 8418 4218 8419 4228 8419 5805 8419 4218 8420 5805 8420 4222 8420 4222 8421 5805 8421 5803 8421 4222 8422 5803 8422 4229 8422 4229 8423 5803 8423 5801 8423 4229 8424 5801 8424 4231 8424 4231 8425 5801 8425 4230 8425 4231 8426 4230 8426 4232 8426 4232 8427 4230 8427 4052 8427 4232 8428 4052 8428 4054 8428 4159 8429 4234 8429 4233 8429 4233 8430 4234 8430 4238 8430 4233 8431 4238 8431 4235 8431 4250 8432 4236 8432 4247 8432 4247 8433 4236 8433 4237 8433 4247 8434 4237 8434 4170 8434 4235 8435 4238 8435 4239 8435 4235 8436 4239 8436 4163 8436 4163 8437 4239 8437 4254 8437 4163 8438 4254 8438 4165 8438 4165 8439 4254 8439 4240 8439 4165 8440 4240 8440 4241 8440 4241 8441 4240 8441 4253 8441 4241 8442 4253 8442 4168 8442 4168 8443 4253 8443 4242 8443 4242 8444 4253 8444 4243 8444 4242 8445 4243 8445 4244 8445 4244 8446 4243 8446 4245 8446 4244 8447 4245 8447 4246 8447 4246 8448 4245 8448 4247 8448 4246 8449 4247 8449 4170 8449 4247 8450 4245 8450 4243 8450 4250 8451 4251 8451 4010 8451 4110 8452 4172 8452 4005 8452 4005 8453 4248 8453 4110 8453 4110 8454 4248 8454 4249 8454 4110 8455 4249 8455 4234 8455 4234 8456 4249 8456 5846 8456 4234 8457 5846 8457 4238 8457 4238 8458 5846 8458 4255 8458 4010 8459 4009 8459 4250 8459 4250 8460 4009 8460 4008 8460 4250 8461 4008 8461 4172 8461 4172 8462 4008 8462 4007 8462 4172 8463 4007 8463 4005 8463 4250 8464 4247 8464 4251 8464 4251 8465 4247 8465 4243 8465 4251 8466 4243 8466 4252 8466 4252 8467 4243 8467 4253 8467 4252 8468 4253 8468 5842 8468 5842 8469 4253 8469 4240 8469 5842 8470 4240 8470 5843 8470 5843 8471 4240 8471 4254 8471 5843 8472 4254 8472 4255 8472 4255 8473 4254 8473 4239 8473 4255 8474 4239 8474 4238 8474 4125 8475 4122 8475 4124 8475 4124 8476 4122 8476 4266 8476 4124 8477 4266 8477 4127 8477 4258 8478 4136 8478 4278 8478 4278 8479 4136 8479 4256 8479 4278 8480 4256 8480 4257 8480 4122 8481 4118 8481 4258 8481 4258 8482 4118 8482 4137 8482 4263 8483 4258 8483 4259 8483 4259 8484 4258 8484 4278 8484 4259 8485 4278 8485 4082 8485 4082 8486 4278 8486 4260 8486 4082 8487 4260 8487 5784 8487 5784 8488 4260 8488 4275 8488 5784 8489 4275 8489 5785 8489 5785 8490 4275 8490 4273 8490 5785 8491 4273 8491 5782 8491 5782 8492 4273 8492 4270 8492 5782 8493 4270 8493 5778 8493 5778 8494 4270 8494 4261 8494 5778 8495 4261 8495 4262 8495 4262 8496 4261 8496 4266 8496 4262 8497 4266 8497 5776 8497 5776 8498 4266 8498 4122 8498 5776 8499 4122 8499 4265 8499 4263 8500 4084 8500 4258 8500 4258 8501 4084 8501 4264 8501 4258 8502 4264 8502 4122 8502 4122 8503 4264 8503 4087 8503 4122 8504 4087 8504 4265 8504 4127 8505 4266 8505 4267 8505 4267 8506 4266 8506 4261 8506 4267 8507 4261 8507 4268 8507 4268 8508 4261 8508 4269 8508 4269 8509 4261 8509 4270 8509 4269 8510 4270 8510 4271 8510 4271 8511 4270 8511 4272 8511 4272 8512 4270 8512 4273 8512 4272 8513 4273 8513 4132 8513 4132 8514 4273 8514 4274 8514 4274 8515 4273 8515 4275 8515 4274 8516 4275 8516 4276 8516 4276 8517 4275 8517 4133 8517 4133 8518 4275 8518 4260 8518 4133 8519 4260 8519 4277 8519 4277 8520 4260 8520 5763 8520 5763 8521 4260 8521 4278 8521 5763 8522 4278 8522 4257 8522 4279 8523 4553 8523 5201 8523 5201 8524 4553 8524 4283 8524 5201 8525 4283 8525 4280 8525 4280 8526 4283 8526 4412 8526 4553 8527 4279 8527 4285 8527 4280 8528 4412 8528 4281 8528 4281 8529 4412 8529 4411 8529 4412 8530 4283 8530 4282 8530 4282 8531 4283 8531 4284 8531 4553 8532 4285 8532 4286 8532 4286 8533 4285 8533 4410 8533 4285 8534 4279 8534 4297 8534 4297 8535 4279 8535 5202 8535 4364 8536 4363 8536 5192 8536 5192 8537 4363 8537 4287 8537 5192 8538 4287 8538 4288 8538 4288 8539 4287 8539 4367 8539 4288 8540 4367 8540 4366 8540 4361 8541 4289 8541 5189 8541 5189 8542 4289 8542 4364 8542 5189 8543 4364 8543 5190 8543 5190 8544 4364 8544 5192 8544 4361 8545 5189 8545 4411 8545 4411 8546 5189 8546 4290 8546 4411 8547 4290 8547 4281 8547 4282 8548 4284 8548 4291 8548 4291 8549 4284 8549 4568 8549 4291 8550 4568 8550 4369 8550 4369 8551 4568 8551 4614 8551 4286 8552 4410 8552 4554 8552 4554 8553 4410 8553 4292 8553 4554 8554 4292 8554 4295 8554 4618 8555 4293 8555 4398 8555 4398 8556 4293 8556 4294 8556 4398 8557 4294 8557 4395 8557 4395 8558 4294 8558 4295 8558 4395 8559 4295 8559 4296 8559 4296 8560 4295 8560 4292 8560 5197 8561 5091 8561 4302 8561 4297 8562 5202 8562 4298 8562 4298 8563 5202 8563 5203 8563 4298 8564 5203 8564 4299 8564 4299 8565 5203 8565 4300 8565 4299 8566 4300 8566 4301 8566 4301 8567 4300 8567 5200 8567 4301 8568 5200 8568 4302 8568 4302 8569 5200 8569 5199 8569 4302 8570 5199 8570 5197 8570 4407 8571 5268 8571 4328 8571 4328 8572 5268 8572 4303 8572 4328 8573 4303 8573 4327 8573 4327 8574 4303 8574 4304 8574 4327 8575 4304 8575 4325 8575 4304 8576 5266 8576 4325 8576 4325 8577 5266 8577 4305 8577 4325 8578 4305 8578 4324 8578 4305 8579 5265 8579 4324 8579 4324 8580 5265 8580 4306 8580 4324 8581 4306 8581 5077 8581 4373 8582 4922 8582 4374 8582 4374 8583 4922 8583 4921 8583 4374 8584 4921 8584 4307 8584 4307 8585 4921 8585 4934 8585 4936 8586 4638 8586 4406 8586 4406 8587 4404 8587 4936 8587 4936 8588 4404 8588 4308 8588 4936 8589 4308 8589 4935 8589 4935 8590 4308 8590 4309 8590 4935 8591 4309 8591 5755 8591 4310 8592 4572 8592 4311 8592 4311 8593 4572 8593 5263 8593 4311 8594 5263 8594 4312 8594 4312 8595 5263 8595 4314 8595 4312 8596 4314 8596 4313 8596 4313 8597 4314 8597 5258 8597 4313 8598 5258 8598 4315 8598 4315 8599 5258 8599 5257 8599 4315 8600 5257 8600 4408 8600 4408 8601 5257 8601 5256 8601 5268 8602 4407 8602 4320 8602 4320 8603 4407 8603 4316 8603 4307 8604 4934 8604 4316 8604 4316 8605 4934 8605 4933 8605 4317 8606 4319 8606 4318 8606 4318 8607 4319 8607 4409 8607 4408 8608 5256 8608 4409 8608 4409 8609 5256 8609 4321 8609 4316 8610 4933 8610 4320 8610 4409 8611 4321 8611 4318 8611 4318 8612 4321 8612 4933 8612 4933 8613 4321 8613 5267 8613 4933 8614 5267 8614 4320 8614 5077 8615 4322 8615 4323 8615 5077 8616 4323 8616 4324 8616 4324 8617 4323 8617 4337 8617 4324 8618 4337 8618 4325 8618 4325 8619 4337 8619 4326 8619 4325 8620 4326 8620 4327 8620 4327 8621 4326 8621 4330 8621 4327 8622 4330 8622 4328 8622 4328 8623 4330 8623 4371 8623 4328 8624 4371 8624 4407 8624 4329 8625 4344 8625 4341 8625 4330 8626 4326 8626 4339 8626 4337 8627 4323 8627 4331 8627 4323 8628 4322 8628 4331 8628 4331 8629 4322 8629 5078 8629 4331 8630 5078 8630 4332 8630 4332 8631 5078 8631 4333 8631 4332 8632 4333 8632 4334 8632 4334 8633 4333 8633 4335 8633 4334 8634 4335 8634 4336 8634 4336 8635 4335 8635 5081 8635 4336 8636 4329 8636 4334 8636 4334 8637 4329 8637 4341 8637 4334 8638 4341 8638 4332 8638 4332 8639 4341 8639 4340 8639 4332 8640 4340 8640 4331 8640 4331 8641 4340 8641 4339 8641 4331 8642 4339 8642 4337 8642 4337 8643 4339 8643 4326 8643 4371 8644 4330 8644 4372 8644 4372 8645 4330 8645 4339 8645 4372 8646 4339 8646 4338 8646 4338 8647 4339 8647 4340 8647 4338 8648 4340 8648 4342 8648 4342 8649 4340 8649 4341 8649 4342 8650 4341 8650 4343 8650 4343 8651 4341 8651 4344 8651 4644 8652 4345 8652 4354 8652 4346 8653 4348 8653 4349 8653 4347 8654 5074 8654 4350 8654 4348 8655 4347 8655 4349 8655 4349 8656 4347 8656 4350 8656 4349 8657 4350 8657 4356 8657 4356 8658 4350 8658 4352 8658 4356 8659 4352 8659 4351 8659 4351 8660 4352 8660 4353 8660 4351 8661 4353 8661 4358 8661 4358 8662 4353 8662 4365 8662 4345 8663 4346 8663 4354 8663 4354 8664 4346 8664 4349 8664 4354 8665 4349 8665 4355 8665 4355 8666 4349 8666 4356 8666 4355 8667 4356 8667 4357 8667 4357 8668 4356 8668 4351 8668 4357 8669 4351 8669 4362 8669 4362 8670 4351 8670 4358 8670 4368 8671 4644 8671 4359 8671 4359 8672 4644 8672 4354 8672 4359 8673 4354 8673 4360 8673 4360 8674 4354 8674 4355 8674 4360 8675 4355 8675 4370 8675 4370 8676 4355 8676 4357 8676 4370 8677 4357 8677 4413 8677 4413 8678 4357 8678 4362 8678 4287 8679 4363 8679 4358 8679 4411 8680 4413 8680 4361 8680 4361 8681 4413 8681 4362 8681 4361 8682 4362 8682 4289 8682 4358 8683 4363 8683 4362 8683 4362 8684 4363 8684 4364 8684 4362 8685 4364 8685 4289 8685 4365 8686 4366 8686 4358 8686 4358 8687 4366 8687 4367 8687 4358 8688 4367 8688 4287 8688 4369 8689 4368 8689 4359 8689 4369 8690 4359 8690 4291 8690 4413 8691 4282 8691 4370 8691 4370 8692 4282 8692 4291 8692 4370 8693 4291 8693 4360 8693 4360 8694 4291 8694 4359 8694 4307 8695 4371 8695 4372 8695 4307 8696 4372 8696 4374 8696 4343 8697 4373 8697 4342 8697 4342 8698 4373 8698 4374 8698 4342 8699 4374 8699 4338 8699 4338 8700 4374 8700 4372 8700 5091 8701 5753 8701 5751 8701 5091 8702 5751 8702 4302 8702 4302 8703 5751 8703 4375 8703 4302 8704 4375 8704 4301 8704 4301 8705 4375 8705 4377 8705 4301 8706 4377 8706 4299 8706 4376 8707 4297 8707 4377 8707 4377 8708 4297 8708 4298 8708 4377 8709 4298 8709 4299 8709 4397 8710 4396 8710 4378 8710 4397 8711 4382 8711 4946 8711 4946 8712 4382 8712 4379 8712 4379 8713 4382 8713 4695 8713 4695 8714 4382 8714 4383 8714 4695 8715 4383 8715 4380 8715 4380 8716 4383 8716 4381 8716 4380 8717 4381 8717 4655 8717 4397 8718 4378 8718 4382 8718 4382 8719 4378 8719 5750 8719 4382 8720 5750 8720 4383 8720 4383 8721 5750 8721 5105 8721 4383 8722 5105 8722 4381 8722 4389 8723 4401 8723 4390 8723 4384 8724 4385 8724 4391 8724 4391 8725 4385 8725 4399 8725 4391 8726 4399 8726 4389 8726 4384 8727 4391 8727 4386 8727 4386 8728 4391 8728 4387 8728 4386 8729 4387 8729 4393 8729 4393 8730 4387 8730 4394 8730 4394 8731 4387 8731 4388 8731 4394 8732 4388 8732 5139 8732 4389 8733 4390 8733 4391 8733 4391 8734 4390 8734 5748 8734 4391 8735 5748 8735 4387 8735 4387 8736 5748 8736 4392 8736 4387 8737 4392 8737 4388 8737 4408 8738 4385 8738 4384 8738 4408 8739 4384 8739 4315 8739 4315 8740 4384 8740 4386 8740 4315 8741 4386 8741 4313 8741 4313 8742 4386 8742 4393 8742 4313 8743 4393 8743 4312 8743 4312 8744 4393 8744 4394 8744 4312 8745 4394 8745 4311 8745 4311 8746 4394 8746 5139 8746 4311 8747 5139 8747 4310 8747 4296 8748 4396 8748 4395 8748 4395 8749 4396 8749 4397 8749 4395 8750 4397 8750 4398 8750 4398 8751 4397 8751 4946 8751 4398 8752 4946 8752 4618 8752 4385 8753 4319 8753 4399 8753 4399 8754 4319 8754 4400 8754 4399 8755 4400 8755 4389 8755 4389 8756 4400 8756 5756 8756 4389 8757 5756 8757 4401 8757 4401 8758 5756 8758 5755 8758 4401 8759 5755 8759 5741 8759 5741 8760 5755 8760 4309 8760 5741 8761 4309 8761 4402 8761 4402 8762 4309 8762 4308 8762 4402 8763 4308 8763 4403 8763 4403 8764 4308 8764 4404 8764 4403 8765 4404 8765 4405 8765 4405 8766 4404 8766 4406 8766 4371 8767 4307 8767 4407 8767 4407 8768 4307 8768 4316 8768 4408 8769 4409 8769 4385 8769 4385 8770 4409 8770 4319 8770 4376 8771 4410 8771 4297 8771 4297 8772 4410 8772 4285 8772 4411 8773 4412 8773 4413 8773 4413 8774 4412 8774 4282 8774 6188 8775 4544 8775 4491 8775 6180 8776 3051 8776 4499 8776 4536 8777 4414 8777 4532 8777 5478 8778 4438 8778 5476 8778 5490 8779 4501 8779 4503 8779 4415 8780 4417 8780 4416 8780 4416 8781 4417 8781 2746 8781 4416 8782 2746 8782 5490 8782 4461 8783 5486 8783 4418 8783 4418 8784 5486 8784 4419 8784 4418 8785 4419 8785 4420 8785 4420 8786 4419 8786 5489 8786 4420 8787 5489 8787 4535 8787 2847 8788 4427 8788 4421 8788 4421 8789 4427 8789 5467 8789 4421 8790 5467 8790 2845 8790 2845 8791 5467 8791 5466 8791 2845 8792 5466 8792 2844 8792 2850 8793 2851 8793 4425 8793 4425 8794 2851 8794 2752 8794 2757 8795 2758 8795 4422 8795 4422 8796 2758 8796 2759 8796 2752 8797 2754 8797 4425 8797 4425 8798 2754 8798 4423 8798 4425 8799 4423 8799 4422 8799 4422 8800 4423 8800 4424 8800 4422 8801 4424 8801 2757 8801 4457 8802 4426 8802 4425 8802 4425 8803 4426 8803 4427 8803 4425 8804 4427 8804 2850 8804 2850 8805 4427 8805 2847 8805 4426 8806 2784 8806 4427 8806 4427 8807 2784 8807 4428 8807 4427 8808 4428 8808 5469 8808 5469 8809 4428 8809 4429 8809 5469 8810 4429 8810 4452 8810 5485 8811 4430 8811 5483 8811 5483 8812 4430 8812 4444 8812 5483 8813 4444 8813 5482 8813 2693 8814 4435 8814 4447 8814 4447 8815 4435 8815 4445 8815 2797 8816 2799 8816 4435 8816 4435 8817 2799 8817 4445 8817 4445 8818 2799 8818 2800 8818 4445 8819 2800 8819 4432 8819 2702 8820 4487 8820 2699 8820 2699 8821 4487 8821 4431 8821 2699 8822 4431 8822 2802 8822 2802 8823 4431 8823 4432 8823 2802 8824 4432 8824 4433 8824 4433 8825 4432 8825 2800 8825 4434 8826 2703 8826 4437 8826 4437 8827 2703 8827 2705 8827 2705 8828 2707 8828 4437 8828 4437 8829 2707 8829 2708 8829 4437 8830 2708 8830 4435 8830 4435 8831 2708 8831 2795 8831 4435 8832 2795 8832 2797 8832 4485 8833 4436 8833 4437 8833 4437 8834 4436 8834 4487 8834 4437 8835 4487 8835 4434 8835 4434 8836 4487 8836 2702 8836 4438 8837 5478 8837 4543 8837 4543 8838 5478 8838 4488 8838 4543 8839 4488 8839 4489 8839 4439 8840 5472 8840 4440 8840 4440 8841 5472 8841 5471 8841 4440 8842 5471 8842 2765 8842 2765 8843 5471 8843 4495 8843 4514 8844 4537 8844 5474 8844 4536 8845 4532 8845 5493 8845 5493 8846 4532 8846 4441 8846 5493 8847 4441 8847 4442 8847 4442 8848 4441 8848 4443 8848 4442 8849 4443 8849 4415 8849 2789 8850 2790 8850 4444 8850 4444 8851 2790 8851 2792 8851 4444 8852 2792 8852 5482 8852 5482 8853 2792 8853 4446 8853 5482 8854 4446 8854 4445 8854 4445 8855 4446 8855 2794 8855 4445 8856 2794 8856 4447 8856 4455 8857 4448 8857 2698 8857 2698 8858 4448 8858 3044 8858 2698 8859 3044 8859 2697 8859 2697 8860 3044 8860 4449 8860 2697 8861 4449 8861 2695 8861 4453 8862 2687 8862 4450 8862 4429 8863 4451 8863 4452 8863 4452 8864 4451 8864 2685 8864 4452 8865 2685 8865 4453 8865 4453 8866 2685 8866 4454 8866 4453 8867 4454 8867 2687 8867 4455 8868 4540 8868 4448 8868 4448 8869 4540 8869 4453 8869 4448 8870 4453 8870 3045 8870 3045 8871 4453 8871 4450 8871 2692 8872 3047 8872 4456 8872 4456 8873 3047 8873 3045 8873 4456 8874 3045 8874 2689 8874 2689 8875 3045 8875 4450 8875 2692 8876 4457 8876 3047 8876 3047 8877 4457 8877 4425 8877 3047 8878 4425 8878 4459 8878 4459 8879 4425 8879 4422 8879 3049 8880 4459 8880 4458 8880 4458 8881 4459 8881 4422 8881 4458 8882 4422 8882 5466 8882 5466 8883 4422 8883 2759 8883 5466 8884 2759 8884 2844 8884 3050 8885 4467 8885 4534 8885 4534 8886 4467 8886 4468 8886 4534 8887 4468 8887 4460 8887 4460 8888 4462 8888 4461 8888 4461 8889 4462 8889 2775 8889 4461 8890 2775 8890 5486 8890 5486 8891 2775 8891 2777 8891 5486 8892 2777 8892 5465 8892 5465 8893 2777 8893 2779 8893 5465 8894 2779 8894 5466 8894 5466 8895 2779 8895 4463 8895 5466 8896 4463 8896 4458 8896 4458 8897 4463 8897 2780 8897 4458 8898 2780 8898 3049 8898 2780 8899 4464 8899 3049 8899 3049 8900 4464 8900 4466 8900 3049 8901 4466 8901 4465 8901 4465 8902 4466 8902 2680 8902 4465 8903 2680 8903 4467 8903 4467 8904 2680 8904 2681 8904 4467 8905 2681 8905 4468 8905 3051 8906 3050 8906 4469 8906 2837 8907 2839 8907 4470 8907 4470 8908 2839 8908 4534 8908 2839 8909 4471 8909 4534 8909 4534 8910 4471 8910 2841 8910 4534 8911 2841 8911 3050 8911 3050 8912 2841 8912 4472 8912 3050 8913 4472 8913 4469 8913 6181 8914 2826 8914 4473 8914 4473 8915 2826 8915 2827 8915 4473 8916 2827 8916 6183 8916 6183 8917 2827 8917 4476 8917 2736 8918 4474 8918 4533 8918 2736 8919 4533 8919 4539 8919 4521 8920 4522 8920 4475 8920 4475 8921 4522 8921 2816 8921 4475 8922 2816 8922 4477 8922 4476 8923 2734 8923 6183 8923 6183 8924 2734 8924 4475 8924 6183 8925 4475 8925 4479 8925 4479 8926 4475 8926 4477 8926 4477 8927 4478 8927 4479 8927 4479 8928 4478 8928 4480 8928 4479 8929 4480 8929 6184 8929 4492 8930 4529 8930 4481 8930 4481 8931 4529 8931 6185 8931 6188 8932 4482 8932 4544 8932 4544 8933 4482 8933 4524 8933 4544 8934 4524 8934 4542 8934 6185 8935 4530 8935 4483 8935 4483 8936 4530 8936 2810 8936 4483 8937 2810 8937 6188 8937 6188 8938 2810 8938 2813 8938 6188 8939 2813 8939 4482 8939 2806 8940 4484 8940 2804 8940 2804 8941 4484 8941 4491 8941 2806 8942 4485 8942 4484 8942 4484 8943 4485 8943 4437 8943 4484 8944 4437 8944 6192 8944 6192 8945 4437 8945 4435 8945 6192 8946 4435 8946 4449 8946 4449 8947 4435 8947 2693 8947 4449 8948 2693 8948 2695 8948 4436 8949 4486 8949 4487 8949 4487 8950 4486 8950 2809 8950 4487 8951 2809 8951 4488 8951 4488 8952 2809 8952 2709 8952 4488 8953 2709 8953 4489 8953 4489 8954 2709 8954 4490 8954 4489 8955 4490 8955 2712 8955 2713 8956 2715 8956 4544 8956 4544 8957 2715 8957 2717 8957 4544 8958 2717 8958 4491 8958 4491 8959 2717 8959 2803 8959 4491 8960 2803 8960 2804 8960 4481 8961 6184 8961 4492 8961 4492 8962 6184 8962 4494 8962 4492 8963 4494 8963 4493 8963 4493 8964 4494 8964 4517 8964 4493 8965 4517 8965 2852 8965 2852 8966 4517 8966 5472 8966 2852 8967 5472 8967 2768 8967 2768 8968 5472 8968 4439 8968 4529 8969 4497 8969 4523 8969 4523 8970 4497 8970 2858 8970 4523 8971 2858 8971 4495 8971 4495 8972 2858 8972 2763 8972 4495 8973 2763 8973 2765 8973 4493 8974 2855 8974 4492 8974 4492 8975 2855 8975 4496 8975 4492 8976 4496 8976 4529 8976 4529 8977 4496 8977 2856 8977 4529 8978 2856 8978 4497 8978 4469 8979 4498 8979 3051 8979 3051 8980 4498 8980 2747 8980 3051 8981 2747 8981 4499 8981 4499 8982 2747 8982 2749 8982 4499 8983 2749 8983 4501 8983 2749 8984 4500 8984 4501 8984 4501 8985 4500 8985 4502 8985 4501 8986 4502 8986 4503 8986 4503 8987 4502 8987 4504 8987 4503 8988 4504 8988 4470 8988 4470 8989 4504 8989 2836 8989 4470 8990 2836 8990 2837 8990 4508 8991 2742 8991 4512 8991 4512 8992 2742 8992 4505 8992 4512 8993 4505 8993 4443 8993 4443 8994 4505 8994 4506 8994 4443 8995 4506 8995 4415 8995 4415 8996 4506 8996 4507 8996 4415 8997 4507 8997 4417 8997 6181 8998 6180 8998 4512 8998 4512 8999 6180 8999 4499 8999 4512 9000 4499 9000 4508 9000 4508 9001 4499 9001 4510 9001 2746 9002 2829 9002 5490 9002 5490 9003 2829 9003 4509 9003 5490 9004 4509 9004 4501 9004 4501 9005 4509 9005 2831 9005 4501 9006 2831 9006 4499 9006 4499 9007 2831 9007 2833 9007 4499 9008 2833 9008 4510 9008 2739 9009 2740 9009 4441 9009 4441 9010 2740 9010 4511 9010 4441 9011 4511 9011 4443 9011 4443 9012 4511 9012 2822 9012 4443 9013 2822 9013 4512 9013 4512 9014 2822 9014 2823 9014 4512 9015 2823 9015 6181 9015 6181 9016 2823 9016 4513 9016 6181 9017 4513 9017 2826 9017 4518 9018 4514 9018 4517 9018 4517 9019 4514 9019 5474 9019 4517 9020 5474 9020 5472 9020 4480 9021 4515 9021 6184 9021 6184 9022 4515 9022 4516 9022 6184 9023 4516 9023 4494 9023 4494 9024 4516 9024 2728 9024 4494 9025 2728 9025 4517 9025 4517 9026 2728 9026 2729 9026 4517 9027 2729 9027 4518 9027 4518 9028 4519 9028 4514 9028 4514 9029 4519 9029 4520 9029 4514 9030 4520 9030 4521 9030 4521 9031 4520 9031 2731 9031 4521 9032 2731 9032 4522 9032 4495 9033 5475 9033 4523 9033 4523 9034 5475 9034 4541 9034 4523 9035 4541 9035 2720 9035 4524 9036 4525 9036 4542 9036 4542 9037 4525 9037 2718 9037 4542 9038 2718 9038 4541 9038 4541 9039 2718 9039 4526 9039 4541 9040 4526 9040 2720 9040 2720 9041 4527 9041 4523 9041 4523 9042 4527 9042 4528 9042 4523 9043 4528 9043 4529 9043 4529 9044 4528 9044 2723 9044 4529 9045 2723 9045 6185 9045 6185 9046 2723 9046 2725 9046 6185 9047 2725 9047 4530 9047 4414 9048 4538 9048 4532 9048 4532 9049 4538 9049 4531 9049 4532 9050 4531 9050 4441 9050 4441 9051 4531 9051 4533 9051 4441 9052 4533 9052 2739 9052 2739 9053 4533 9053 4474 9053 4460 9054 4461 9054 4534 9054 4534 9055 4461 9055 4418 9055 4534 9056 4418 9056 4470 9056 4470 9057 4418 9057 4420 9057 4470 9058 4420 9058 4503 9058 4503 9059 4420 9059 4535 9059 4503 9060 4535 9060 5490 9060 4536 9061 5495 9061 4414 9061 4414 9062 5495 9062 4537 9062 4414 9063 4537 9063 4538 9063 4538 9064 4537 9064 4514 9064 4538 9065 4514 9065 4531 9065 4531 9066 4514 9066 4521 9066 4531 9067 4521 9067 4533 9067 4533 9068 4521 9068 4475 9068 4533 9069 4475 9069 4539 9069 4539 9070 4475 9070 2734 9070 4540 9071 2789 9071 4453 9071 4453 9072 2789 9072 4444 9072 4453 9073 4444 9073 4452 9073 4452 9074 4444 9074 4430 9074 4452 9075 4430 9075 5469 9075 5469 9076 4430 9076 5485 9076 5475 9077 5476 9077 4541 9077 4541 9078 5476 9078 4438 9078 4541 9079 4438 9079 4542 9079 4542 9080 4438 9080 4543 9080 4542 9081 4543 9081 4544 9081 4544 9082 4543 9082 4489 9082 4544 9083 4489 9083 2713 9083 2713 9084 4489 9084 2712 9084 4545 9085 4546 9085 2975 9085 4545 9086 4547 9086 4546 9086 4546 9087 4547 9087 4825 9087 4546 9088 4825 9088 4548 9088 4550 9089 4555 9089 4551 9089 2975 9090 4549 9090 4545 9090 4545 9091 4549 9091 2771 9091 4545 9092 2771 9092 4552 9092 4552 9093 2771 9093 4615 9093 3005 9094 5546 9094 2998 9094 2998 9095 5546 9095 4550 9095 2998 9096 4550 9096 2996 9096 2996 9097 4550 9097 4551 9097 4615 9098 4614 9098 4552 9098 4552 9099 4614 9099 4568 9099 4552 9100 4568 9100 4823 9100 4284 9101 4283 9101 4553 9101 4553 9102 4286 9102 4284 9102 4284 9103 4286 9103 4554 9103 4284 9104 4554 9104 4568 9104 4568 9105 4554 9105 4295 9105 4568 9106 4295 9106 4294 9106 2995 9107 4555 9107 4634 9107 4634 9108 4555 9108 4550 9108 4634 9109 4550 9109 4632 9109 4632 9110 4550 9110 4557 9110 4632 9111 4557 9111 4556 9111 4556 9112 4557 9112 4558 9112 4556 9113 4558 9113 4630 9113 4558 9114 4559 9114 4630 9114 4630 9115 4559 9115 4560 9115 4630 9116 4560 9116 4629 9116 4629 9117 4560 9117 4561 9117 4629 9118 4561 9118 4628 9118 4628 9119 4561 9119 4563 9119 4628 9120 4563 9120 4562 9120 4562 9121 4563 9121 4564 9121 4562 9122 4564 9122 4626 9122 4564 9123 4565 9123 4626 9123 4626 9124 4565 9124 4566 9124 4626 9125 4566 9125 4624 9125 4624 9126 4566 9126 4819 9126 4624 9127 4819 9127 4622 9127 4622 9128 4819 9128 4569 9128 4622 9129 4569 9129 4567 9129 4567 9130 4569 9130 4570 9130 4823 9131 4568 9131 4821 9131 4821 9132 4568 9132 4294 9132 4821 9133 4294 9133 4569 9133 4569 9134 4294 9134 4293 9134 4569 9135 4293 9135 4570 9135 4126 9136 5077 9136 4123 9136 4123 9137 5077 9137 4306 9137 4123 9138 4306 9138 4121 9138 4121 9139 4306 9139 4119 9139 3657 9140 5091 9140 5197 9140 3657 9141 5197 9141 3660 9141 3660 9142 5197 9142 5196 9142 4173 9143 5254 9143 4571 9143 4571 9144 5254 9144 4572 9144 4571 9145 4572 9145 4310 9145 4573 9146 5243 9146 4154 9146 4171 9147 5252 9147 4574 9147 4574 9148 5252 9148 5251 9148 4154 9149 4150 9149 4573 9149 4573 9150 4150 9150 5161 9150 4573 9151 5161 9151 5250 9151 5250 9152 5161 9152 4575 9152 5250 9153 4575 9153 5251 9153 5251 9154 4575 9154 4576 9154 5251 9155 4576 9155 4574 9155 4140 9156 4188 9156 4139 9156 4139 9157 4188 9157 4185 9157 4139 9158 4185 9158 4143 9158 4143 9159 4185 9159 4187 9159 4143 9160 4187 9160 4577 9160 4577 9161 4187 9161 5177 9161 4578 9162 4160 9162 5180 9162 4579 9163 4157 9163 4158 9163 4158 9164 4578 9164 4579 9164 4579 9165 4578 9165 5180 9165 4579 9166 5180 9166 4580 9166 4580 9167 5180 9167 5179 9167 4580 9168 5179 9168 5516 9168 5500 9169 4581 9169 3914 9169 3914 9170 4581 9170 3881 9170 3914 9171 3881 9171 3912 9171 3912 9172 3881 9172 3882 9172 3912 9173 3882 9173 5140 9173 5140 9174 3882 9174 5141 9174 3891 9175 3893 9175 4582 9175 4582 9176 3893 9176 4585 9176 5511 9177 3905 9177 3906 9177 3906 9178 3904 9178 5511 9178 5511 9179 3904 9179 4583 9179 5511 9180 4583 9180 5514 9180 5514 9181 4583 9181 4584 9181 5514 9182 4584 9182 4585 9182 4585 9183 4584 9183 3889 9183 4585 9184 3889 9184 4582 9184 4588 9185 5149 9185 4590 9185 4590 9186 5149 9186 4586 9186 4586 9187 4587 9187 4590 9187 4590 9188 4587 9188 3868 9188 4590 9189 3868 9189 5499 9189 5145 9190 4588 9190 4589 9190 4589 9191 4588 9191 4590 9191 4589 9192 4590 9192 4591 9192 4591 9193 4590 9193 5502 9193 4592 9194 3596 9194 4593 9194 4593 9195 3596 9195 4288 9195 4593 9196 4288 9196 3599 9196 3599 9197 4288 9197 4366 9197 3672 9198 5204 9198 4594 9198 4594 9199 5204 9199 3619 9199 4594 9200 3619 9200 3670 9200 3670 9201 3619 9201 4595 9201 3670 9202 4595 9202 4596 9202 4596 9203 4595 9203 3622 9203 3653 9204 5101 9204 4600 9204 4597 9205 5210 9205 4598 9205 4598 9206 5210 9206 4601 9206 5208 9207 3654 9207 4599 9207 4599 9208 3653 9208 5208 9208 5208 9209 3653 9209 4600 9209 5208 9210 4600 9210 4601 9210 4601 9211 4600 9211 3631 9211 4601 9212 3631 9212 4598 9212 5218 9213 4602 9213 3385 9213 4603 9214 3638 9214 3640 9214 3640 9215 3638 9215 5225 9215 3640 9216 5225 9216 5106 9216 5106 9217 5225 9217 5107 9217 5225 9218 4604 9218 5107 9218 5107 9219 4604 9219 5223 9219 5107 9220 5223 9220 5109 9220 5223 9221 5222 9221 5109 9221 5109 9222 5222 9222 5221 9222 5109 9223 5221 9223 5103 9223 5103 9224 5221 9224 5220 9224 5103 9225 5220 9225 5104 9225 5104 9226 5220 9226 5218 9226 5104 9227 5218 9227 3384 9227 3384 9228 5218 9228 3385 9228 5118 9229 5228 9229 5227 9229 5118 9230 5227 9230 5119 9230 4605 9231 3381 9231 5227 9231 5227 9232 3381 9232 3378 9232 5227 9233 3378 9233 5119 9233 3398 9234 3399 9234 4606 9234 4606 9235 3399 9235 5228 9235 4606 9236 5228 9236 5126 9236 5126 9237 5228 9237 5118 9237 5230 9238 4607 9238 3366 9238 3366 9239 4607 9239 3416 9239 3366 9240 3416 9240 3365 9240 3365 9241 3416 9241 4608 9241 3365 9242 4608 9242 3368 9242 3368 9243 4608 9243 4609 9243 5238 9244 5237 9244 5090 9244 4610 9245 3347 9245 4611 9245 3349 9246 5090 9246 4611 9246 4611 9247 5090 9247 5237 9247 4611 9248 5237 9248 4610 9248 4610 9249 5237 9249 3346 9249 3401 9250 3406 9250 3402 9250 3402 9251 3406 9251 5238 9251 3402 9252 5238 9252 3405 9252 3405 9253 5238 9253 5090 9253 2980 9254 2981 9254 4613 9254 4612 9255 4369 9255 4613 9255 4613 9256 4369 9256 4614 9256 4613 9257 4614 9257 2980 9257 2980 9258 4614 9258 4615 9258 4373 9259 5063 9259 4922 9259 4922 9260 5063 9260 2941 9260 2941 9261 4616 9261 4922 9261 4922 9262 4616 9262 4617 9262 4922 9263 4617 9263 2951 9263 4293 9264 4618 9264 4620 9264 4970 9265 4619 9265 4634 9265 4634 9266 4619 9266 3009 9266 3009 9267 2999 9267 4634 9267 4634 9268 2999 9268 2993 9268 4634 9269 2993 9269 2995 9269 4293 9270 4620 9270 4570 9270 4570 9271 4620 9271 4948 9271 4570 9272 4948 9272 4567 9272 4567 9273 4948 9273 4621 9273 4567 9274 4621 9274 4622 9274 4622 9275 4621 9275 4623 9275 4622 9276 4623 9276 4624 9276 4623 9277 4950 9277 4624 9277 4624 9278 4950 9278 4625 9278 4624 9279 4625 9279 4626 9279 4625 9280 4954 9280 4626 9280 4626 9281 4954 9281 4955 9281 4626 9282 4955 9282 4562 9282 4955 9283 4956 9283 4562 9283 4562 9284 4956 9284 4627 9284 4562 9285 4627 9285 4628 9285 4627 9286 4959 9286 4628 9286 4628 9287 4959 9287 4961 9287 4628 9288 4961 9288 4629 9288 4629 9289 4961 9289 4963 9289 4629 9290 4963 9290 4630 9290 4963 9291 4964 9291 4630 9291 4630 9292 4964 9292 4965 9292 4630 9293 4965 9293 4556 9293 4965 9294 4966 9294 4556 9294 4556 9295 4966 9295 4631 9295 4556 9296 4631 9296 4632 9296 4631 9297 4967 9297 4632 9297 4632 9298 4967 9298 4633 9298 4632 9299 4633 9299 4634 9299 4634 9300 4633 9300 4635 9300 4634 9301 4635 9301 4970 9301 4931 9302 5539 9302 4971 9302 4931 9303 4971 9303 4636 9303 4636 9304 4971 9304 4973 9304 4636 9305 4973 9305 4930 9305 4930 9306 4973 9306 4976 9306 4930 9307 4976 9307 4928 9307 4928 9308 4976 9308 4978 9308 4928 9309 4978 9309 4637 9309 4637 9310 4978 9310 4981 9310 4637 9311 4981 9311 4927 9311 4927 9312 4981 9312 4406 9312 4927 9313 4406 9313 4638 9313 4641 9314 5074 9314 4347 9314 4643 9315 4639 9315 4642 9315 4642 9316 4639 9316 2989 9316 4642 9317 2989 9317 4640 9317 4640 9318 2989 9318 5071 9318 4640 9319 5071 9319 4641 9319 2982 9320 2984 9320 4643 9320 4643 9321 2984 9321 2985 9321 4643 9322 2985 9322 4639 9322 4641 9323 4347 9323 4640 9323 4640 9324 4347 9324 4348 9324 4640 9325 4348 9325 4642 9325 4642 9326 4348 9326 4346 9326 4642 9327 4346 9327 4643 9327 4643 9328 4346 9328 4345 9328 4643 9329 4345 9329 4644 9329 4644 9330 4368 9330 4643 9330 4643 9331 4368 9331 4645 9331 4643 9332 4645 9332 2982 9332 5081 9333 5080 9333 4651 9333 2940 9334 4646 9334 4647 9334 2940 9335 4647 9335 4648 9335 4648 9336 4647 9336 4652 9336 4648 9337 4652 9337 2947 9337 2947 9338 4652 9338 4649 9338 4649 9339 4652 9339 4651 9339 4649 9340 4651 9340 4650 9340 4650 9341 4651 9341 2944 9341 2944 9342 4651 9342 5080 9342 2944 9343 5080 9343 2952 9343 5081 9344 4651 9344 4336 9344 4336 9345 4651 9345 4652 9345 4336 9346 4652 9346 4329 9346 4329 9347 4652 9347 4647 9347 4329 9348 4647 9348 4344 9348 4344 9349 4647 9349 4646 9349 4344 9350 4646 9350 4343 9350 4653 9351 4711 9351 4654 9351 4663 9352 4658 9352 4665 9352 4655 9353 4697 9353 4656 9353 3008 9354 4969 9354 4742 9354 4660 9355 4657 9355 4658 9355 4658 9356 4657 9356 4659 9356 4658 9357 4659 9357 4665 9357 4665 9358 4659 9358 3013 9358 4665 9359 3013 9359 3014 9359 5089 9360 4660 9360 4661 9360 4661 9361 4660 9361 4658 9361 4661 9362 4658 9362 4662 9362 4662 9363 4658 9363 4663 9363 4662 9364 4663 9364 5123 9364 4664 9365 5123 9365 4739 9365 4739 9366 5123 9366 4663 9366 4739 9367 4663 9367 4740 9367 4740 9368 4663 9368 4665 9368 4740 9369 4665 9369 4742 9369 4742 9370 4665 9370 3014 9370 4742 9371 3014 9371 3008 9371 4668 9372 4699 9372 4669 9372 4949 9373 4666 9373 4667 9373 4667 9374 4666 9374 4668 9374 4667 9375 4668 9375 4706 9375 4706 9376 4668 9376 4669 9376 4706 9377 4669 9377 4705 9377 4670 9378 5093 9378 4704 9378 4704 9379 5093 9379 4671 9379 4704 9380 4671 9380 4672 9380 4672 9381 4671 9381 4674 9381 4672 9382 4674 9382 4707 9382 4707 9383 4674 9383 4676 9383 5093 9384 4709 9384 4671 9384 4671 9385 4709 9385 4673 9385 4671 9386 4673 9386 4674 9386 4674 9387 4673 9387 4675 9387 4674 9388 4675 9388 4676 9388 4676 9389 4675 9389 4678 9389 4676 9390 4678 9390 4677 9390 4677 9391 4678 9391 4953 9391 4679 9392 4717 9392 4680 9392 4680 9393 4717 9393 4716 9393 4680 9394 4716 9394 4681 9394 4681 9395 4716 9395 4714 9395 4681 9396 4714 9396 4719 9396 4719 9397 4714 9397 4718 9397 4720 9398 4682 9398 4683 9398 4683 9399 4682 9399 4684 9399 4683 9400 4684 9400 4722 9400 4722 9401 4684 9401 4685 9401 4722 9402 4685 9402 4727 9402 4727 9403 4685 9403 4724 9403 4686 9404 5136 9404 4731 9404 4731 9405 5136 9405 4689 9405 4731 9406 4689 9406 4733 9406 4733 9407 4689 9407 4691 9407 4733 9408 4691 9408 4687 9408 4687 9409 4691 9409 4736 9409 5136 9410 4688 9410 4689 9410 4689 9411 4688 9411 4690 9411 4689 9412 4690 9412 4691 9412 4691 9413 4690 9413 4692 9413 4691 9414 4692 9414 4736 9414 4736 9415 4692 9415 4693 9415 4736 9416 4693 9416 4694 9416 4694 9417 4693 9417 4741 9417 4655 9418 4656 9418 4380 9418 4380 9419 4656 9419 4698 9419 4380 9420 4698 9420 4695 9420 4695 9421 4698 9421 4696 9421 4695 9422 4696 9422 4379 9422 4379 9423 4696 9423 4947 9423 4379 9424 4947 9424 4946 9424 4697 9425 4705 9425 4656 9425 4656 9426 4705 9426 4669 9426 4656 9427 4669 9427 4698 9427 4698 9428 4669 9428 4699 9428 4698 9429 4699 9429 4696 9429 4696 9430 4699 9430 4703 9430 4696 9431 4703 9431 4947 9431 4666 9432 4700 9432 4668 9432 4668 9433 4700 9433 4701 9433 4668 9434 4701 9434 4699 9434 4699 9435 4701 9435 4702 9435 4699 9436 4702 9436 4703 9436 4697 9437 4670 9437 4705 9437 4705 9438 4670 9438 4704 9438 4705 9439 4704 9439 4706 9439 4706 9440 4704 9440 4672 9440 4706 9441 4672 9441 4667 9441 4667 9442 4672 9442 4707 9442 4667 9443 4707 9443 4949 9443 4677 9444 4952 9444 4676 9444 4676 9445 4952 9445 4951 9445 4676 9446 4951 9446 4707 9446 4707 9447 4951 9447 4708 9447 4707 9448 4708 9448 4949 9448 4709 9449 5095 9449 4673 9449 4673 9450 5095 9450 4710 9450 4673 9451 4710 9451 4675 9451 4675 9452 4710 9452 4712 9452 4675 9453 4712 9453 4678 9453 4678 9454 4712 9454 4654 9454 4678 9455 4654 9455 4953 9455 4953 9456 4654 9456 4711 9456 5095 9457 4679 9457 4710 9457 4710 9458 4679 9458 4680 9458 4710 9459 4680 9459 4712 9459 4712 9460 4680 9460 4681 9460 4712 9461 4681 9461 4654 9461 4654 9462 4681 9462 4719 9462 4654 9463 4719 9463 4653 9463 4729 9464 4962 9464 4713 9464 4713 9465 4962 9465 4718 9465 4713 9466 4718 9466 4721 9466 4721 9467 4718 9467 4714 9467 4721 9468 4714 9468 4715 9468 4715 9469 4714 9469 4716 9469 4715 9470 4716 9470 5110 9470 5110 9471 4716 9471 4717 9471 4962 9472 4960 9472 4718 9472 4718 9473 4960 9473 4958 9473 4718 9474 4958 9474 4719 9474 4719 9475 4958 9475 4957 9475 4719 9476 4957 9476 4653 9476 5110 9477 4720 9477 4715 9477 4715 9478 4720 9478 4683 9478 4715 9479 4683 9479 4721 9479 4721 9480 4683 9480 4722 9480 4721 9481 4722 9481 4713 9481 4713 9482 4722 9482 4727 9482 4713 9483 4727 9483 4729 9483 4738 9484 4723 9484 4734 9484 4734 9485 4723 9485 4724 9485 4734 9486 4724 9486 4732 9486 4732 9487 4724 9487 4685 9487 4732 9488 4685 9488 4730 9488 4730 9489 4685 9489 4684 9489 4730 9490 4684 9490 5117 9490 5117 9491 4684 9491 4682 9491 4723 9492 4725 9492 4724 9492 4724 9493 4725 9493 4726 9493 4724 9494 4726 9494 4727 9494 4727 9495 4726 9495 4728 9495 4727 9496 4728 9496 4729 9496 5117 9497 4686 9497 4730 9497 4730 9498 4686 9498 4731 9498 4730 9499 4731 9499 4732 9499 4732 9500 4731 9500 4733 9500 4732 9501 4733 9501 4734 9501 4734 9502 4733 9502 4687 9502 4734 9503 4687 9503 4738 9503 4694 9504 4735 9504 4736 9504 4736 9505 4735 9505 4737 9505 4736 9506 4737 9506 4687 9506 4687 9507 4737 9507 4968 9507 4687 9508 4968 9508 4738 9508 4688 9509 4664 9509 4690 9509 4690 9510 4664 9510 4739 9510 4690 9511 4739 9511 4692 9511 4692 9512 4739 9512 4740 9512 4692 9513 4740 9513 4693 9513 4693 9514 4740 9514 4742 9514 4693 9515 4742 9515 4741 9515 4741 9516 4742 9516 4969 9516 5533 9517 5532 9517 4743 9517 4763 9518 4744 9518 4751 9518 4745 9519 4757 9519 4746 9519 5183 9520 5182 9520 4747 9520 4760 9521 5183 9521 4789 9521 5156 9522 4748 9522 4749 9522 5155 9523 5156 9523 4770 9523 4756 9524 5155 9524 4771 9524 4766 9525 3035 9525 4765 9525 4765 9526 3035 9526 3036 9526 4765 9527 3036 9527 4754 9527 4754 9528 3036 9528 4750 9528 4754 9529 4750 9529 5143 9529 4744 9530 5528 9530 4751 9530 4751 9531 5528 9531 4752 9531 4751 9532 4752 9532 3032 9532 4759 9533 4757 9533 4753 9533 4753 9534 4757 9534 4745 9534 4753 9535 4745 9535 5157 9535 4764 9536 4765 9536 4767 9536 4767 9537 4765 9537 4754 9537 4767 9538 4754 9538 4755 9538 4755 9539 4754 9539 5143 9539 4755 9540 5143 9540 4756 9540 4784 9541 4746 9541 4758 9541 4758 9542 4746 9542 4757 9542 4758 9543 4757 9543 4788 9543 4788 9544 4757 9544 4759 9544 4788 9545 4759 9545 4760 9545 4779 9546 4776 9546 4761 9546 4785 9547 5538 9547 4783 9547 4783 9548 5538 9548 4779 9548 4783 9549 4779 9549 4782 9549 4782 9550 4779 9550 4761 9550 4782 9551 4761 9551 4762 9551 4769 9552 4763 9552 4764 9552 4764 9553 4763 9553 4751 9553 4764 9554 4751 9554 4765 9554 4765 9555 4751 9555 3032 9555 4765 9556 3032 9556 4766 9556 4774 9557 5530 9557 4768 9557 4756 9558 4771 9558 4755 9558 4755 9559 4771 9559 4773 9559 4755 9560 4773 9560 4767 9560 4767 9561 4773 9561 4774 9561 4767 9562 4774 9562 4764 9562 4764 9563 4774 9563 4768 9563 4764 9564 4768 9564 4769 9564 5155 9565 4770 9565 4771 9565 4771 9566 4770 9566 4772 9566 4771 9567 4772 9567 4773 9567 4773 9568 4772 9568 4743 9568 4773 9569 4743 9569 4774 9569 4774 9570 4743 9570 5532 9570 4774 9571 5532 9571 5530 9571 5156 9572 4749 9572 4770 9572 4770 9573 4749 9573 4775 9573 4770 9574 4775 9574 4772 9574 4772 9575 4775 9575 4777 9575 4772 9576 4777 9576 4743 9576 4743 9577 4777 9577 5534 9577 4743 9578 5534 9578 5533 9578 4748 9579 4762 9579 4749 9579 4749 9580 4762 9580 4761 9580 4749 9581 4761 9581 4775 9581 4775 9582 4761 9582 4776 9582 4775 9583 4776 9583 4777 9583 4777 9584 4776 9584 4781 9584 4777 9585 4781 9585 5534 9585 5538 9586 4778 9586 4779 9586 4779 9587 4778 9587 4780 9587 4779 9588 4780 9588 4776 9588 4776 9589 4780 9589 5536 9589 4776 9590 5536 9590 4781 9590 4748 9591 5157 9591 4762 9591 4762 9592 5157 9592 4745 9592 4762 9593 4745 9593 4782 9593 4782 9594 4745 9594 4746 9594 4782 9595 4746 9595 4783 9595 4783 9596 4746 9596 4784 9596 4783 9597 4784 9597 4785 9597 4785 9598 4784 9598 4786 9598 4792 9599 4794 9599 4787 9599 4760 9600 4789 9600 4788 9600 4788 9601 4789 9601 4791 9601 4788 9602 4791 9602 4758 9602 4758 9603 4791 9603 4792 9603 4758 9604 4792 9604 4784 9604 4784 9605 4792 9605 4787 9605 4784 9606 4787 9606 4786 9606 5183 9607 4747 9607 4789 9607 4789 9608 4747 9608 4790 9608 4789 9609 4790 9609 4791 9609 4791 9610 4790 9610 4793 9610 4791 9611 4793 9611 4792 9611 4792 9612 4793 9612 4972 9612 4792 9613 4972 9613 4794 9613 6199 9614 2925 9614 4795 9614 4795 9615 2925 9615 2919 9615 4795 9616 2919 9616 6201 9616 6201 9617 2919 9617 2920 9617 6201 9618 2920 9618 6203 9618 6203 9619 2920 9619 4796 9619 2920 9620 2922 9620 4796 9620 4796 9621 2922 9621 2924 9621 4796 9622 2924 9622 6202 9622 6202 9623 2924 9623 6198 9623 2902 9624 6212 9624 2901 9624 2901 9625 6212 9625 2908 9625 2905 9626 2906 9626 6214 9626 6214 9627 6215 9627 2905 9627 2905 9628 6215 9628 6216 9628 2905 9629 6216 9629 4798 9629 4798 9630 6216 9630 4797 9630 4798 9631 4797 9631 2904 9631 2904 9632 4797 9632 4799 9632 2904 9633 4799 9633 2902 9633 2902 9634 4799 9634 6213 9634 2902 9635 6213 9635 6212 9635 5060 9636 5062 9636 6208 9636 6208 9637 5062 9637 4800 9637 6208 9638 4800 9638 4801 9638 4801 9639 4800 9639 2877 9639 4801 9640 2877 9640 4802 9640 4802 9641 2877 9641 4803 9641 2877 9642 2879 9642 4803 9642 4803 9643 2879 9643 4804 9643 4803 9644 4804 9644 6210 9644 6210 9645 4804 9645 6209 9645 2868 9646 4812 9646 2867 9646 2867 9647 4812 9647 4805 9647 4806 9648 2863 9648 4807 9648 4807 9649 4808 9649 4806 9649 4806 9650 4808 9650 6197 9650 4806 9651 6197 9651 4809 9651 4809 9652 6197 9652 6196 9652 4809 9653 6196 9653 4810 9653 4810 9654 6196 9654 4811 9654 4810 9655 4811 9655 2868 9655 2868 9656 4811 9656 6195 9656 2868 9657 6195 9657 4812 9657 4913 9658 4813 9658 4814 9658 4815 9659 4816 9659 4891 9659 4840 9660 4846 9660 4905 9660 4817 9661 4841 9661 4882 9661 4566 9662 4565 9662 5581 9662 4819 9663 4566 9663 4818 9663 4569 9664 4819 9664 4820 9664 4821 9665 4569 9665 4822 9665 4823 9666 4821 9666 4906 9666 4843 9667 4923 9667 4838 9667 4866 9668 4932 9668 4869 9668 4824 9669 4548 9669 4825 9669 4824 9670 4825 9670 4897 9670 4826 9671 4828 9671 4827 9671 4827 9672 4828 9672 4897 9672 4893 9673 4829 9673 4898 9673 4898 9674 4829 9674 4830 9674 4898 9675 4830 9675 4827 9675 4827 9676 4830 9676 2974 9676 4827 9677 2974 9677 4826 9677 4834 9678 4835 9678 4893 9678 4893 9679 4835 9679 4831 9679 4893 9680 4831 9680 4829 9680 4832 9681 4891 9681 2963 9681 2963 9682 4891 9682 4888 9682 2963 9683 4888 9683 2962 9683 4832 9684 2965 9684 4891 9684 4891 9685 2965 9685 4833 9685 4891 9686 4833 9686 4834 9686 4834 9687 4833 9687 2968 9687 4834 9688 2968 9688 4835 9688 4885 9689 4838 9689 2962 9689 4923 9690 4836 9690 4838 9690 4838 9691 4836 9691 4837 9691 4838 9692 4837 9692 2962 9692 4839 9693 4841 9693 4926 9693 4926 9694 4841 9694 4817 9694 4926 9695 4817 9695 4881 9695 4552 9696 4846 9696 4545 9696 4545 9697 4846 9697 4840 9697 4545 9698 4840 9698 4547 9698 4886 9699 4882 9699 4884 9699 4884 9700 4882 9700 4841 9700 4884 9701 4841 9701 4842 9701 4842 9702 4841 9702 4839 9702 4842 9703 4839 9703 4843 9703 4844 9704 4905 9704 4845 9704 4845 9705 4905 9705 4846 9705 4845 9706 4846 9706 4847 9706 4847 9707 4846 9707 4552 9707 4847 9708 4552 9708 4823 9708 4872 9709 4848 9709 4852 9709 4849 9710 4851 9710 4850 9710 4850 9711 4851 9711 4872 9711 4850 9712 4872 9712 4874 9712 4874 9713 4872 9713 4852 9713 4874 9714 4852 9714 4868 9714 4929 9715 4856 9715 4853 9715 4853 9716 4856 9716 4857 9716 4853 9717 4857 9717 4855 9717 4855 9718 4857 9718 4854 9718 4855 9719 4854 9719 4875 9719 4875 9720 4854 9720 4859 9720 4856 9721 4879 9721 4857 9721 4857 9722 4879 9722 4880 9722 4857 9723 4880 9723 4854 9723 4854 9724 4880 9724 4858 9724 4854 9725 4858 9725 4859 9725 4859 9726 4858 9726 4860 9726 4859 9727 4860 9727 5695 9727 5695 9728 4860 9728 4883 9728 4864 9729 4901 9729 4861 9729 5708 9730 4862 9730 4863 9730 4863 9731 4862 9731 4864 9731 4863 9732 4864 9732 4865 9732 4865 9733 4864 9733 4861 9733 4865 9734 4861 9734 4904 9734 4866 9735 4869 9735 5545 9735 5545 9736 4869 9736 4870 9736 5545 9737 4870 9737 5642 9737 5642 9738 4870 9738 4871 9738 5642 9739 4871 9739 4867 9739 4867 9740 4871 9740 5691 9740 4867 9741 5691 9741 5643 9741 4932 9742 4868 9742 4869 9742 4869 9743 4868 9743 4852 9743 4869 9744 4852 9744 4870 9744 4870 9745 4852 9745 4848 9745 4870 9746 4848 9746 4871 9746 4871 9747 4848 9747 4873 9747 4871 9748 4873 9748 5691 9748 4851 9749 5692 9749 4872 9749 4872 9750 5692 9750 5688 9750 4872 9751 5688 9751 4848 9751 4848 9752 5688 9752 5689 9752 4848 9753 5689 9753 4873 9753 4932 9754 4929 9754 4868 9754 4868 9755 4929 9755 4853 9755 4868 9756 4853 9756 4874 9756 4874 9757 4853 9757 4855 9757 4874 9758 4855 9758 4850 9758 4850 9759 4855 9759 4875 9759 4850 9760 4875 9760 4849 9760 5695 9761 4876 9761 4859 9761 4859 9762 4876 9762 4877 9762 4859 9763 4877 9763 4875 9763 4875 9764 4877 9764 4878 9764 4875 9765 4878 9765 4849 9765 4879 9766 4881 9766 4880 9766 4880 9767 4881 9767 4817 9767 4880 9768 4817 9768 4858 9768 4858 9769 4817 9769 4882 9769 4858 9770 4882 9770 4860 9770 4860 9771 4882 9771 4886 9771 4860 9772 4886 9772 4883 9772 4883 9773 4886 9773 5697 9773 4889 9774 4890 9774 4887 9774 4843 9775 4838 9775 4842 9775 4842 9776 4838 9776 4885 9776 4842 9777 4885 9777 4884 9777 4884 9778 4885 9778 4889 9778 4884 9779 4889 9779 4886 9779 4886 9780 4889 9780 4887 9780 4886 9781 4887 9781 5697 9781 2962 9782 4888 9782 4885 9782 4885 9783 4888 9783 4891 9783 4885 9784 4891 9784 4889 9784 4889 9785 4891 9785 4816 9785 4889 9786 4816 9786 4890 9786 4815 9787 4891 9787 4892 9787 4892 9788 4891 9788 4834 9788 4892 9789 4834 9789 5701 9789 5701 9790 4834 9790 4893 9790 5701 9791 4893 9791 5698 9791 5698 9792 4893 9792 4894 9792 4894 9793 4893 9793 4898 9793 4894 9794 4898 9794 5702 9794 4825 9795 4895 9795 4897 9795 4897 9796 4895 9796 4896 9796 4897 9797 4896 9797 4827 9797 4827 9798 4896 9798 4900 9798 4827 9799 4900 9799 4898 9799 4898 9800 4900 9800 4899 9800 4898 9801 4899 9801 5702 9801 4825 9802 4904 9802 4895 9802 4895 9803 4904 9803 4861 9803 4895 9804 4861 9804 4896 9804 4896 9805 4861 9805 4901 9805 4896 9806 4901 9806 4900 9806 4900 9807 4901 9807 4903 9807 4900 9808 4903 9808 4899 9808 4862 9809 5706 9809 4864 9809 4864 9810 5706 9810 4902 9810 4864 9811 4902 9811 4901 9811 4901 9812 4902 9812 5704 9812 4901 9813 5704 9813 4903 9813 4825 9814 4547 9814 4904 9814 4904 9815 4547 9815 4840 9815 4904 9816 4840 9816 4865 9816 4865 9817 4840 9817 4905 9817 4865 9818 4905 9818 4863 9818 4863 9819 4905 9819 4844 9819 4863 9820 4844 9820 5708 9820 5708 9821 4844 9821 5709 9821 4909 9822 4910 9822 4908 9822 4823 9823 4906 9823 4847 9823 4847 9824 4906 9824 4907 9824 4847 9825 4907 9825 4845 9825 4845 9826 4907 9826 4909 9826 4845 9827 4909 9827 4844 9827 4844 9828 4909 9828 4908 9828 4844 9829 4908 9829 5709 9829 4821 9830 4822 9830 4906 9830 4906 9831 4822 9831 4911 9831 4906 9832 4911 9832 4907 9832 4907 9833 4911 9833 4814 9833 4907 9834 4814 9834 4909 9834 4909 9835 4814 9835 4813 9835 4909 9836 4813 9836 4910 9836 4569 9837 4820 9837 4822 9837 4822 9838 4820 9838 4912 9838 4822 9839 4912 9839 4911 9839 4911 9840 4912 9840 4917 9840 4911 9841 4917 9841 4814 9841 4814 9842 4917 9842 5711 9842 4814 9843 5711 9843 4913 9843 4916 9844 5712 9844 4914 9844 4819 9845 4818 9845 4820 9845 4820 9846 4818 9846 4915 9846 4820 9847 4915 9847 4912 9847 4912 9848 4915 9848 4916 9848 4912 9849 4916 9849 4917 9849 4917 9850 4916 9850 4914 9850 4917 9851 4914 9851 5711 9851 4566 9852 5581 9852 4818 9852 4818 9853 5581 9853 4918 9853 4818 9854 4918 9854 4915 9854 4915 9855 4918 9855 4919 9855 4915 9856 4919 9856 4916 9856 4916 9857 4919 9857 5582 9857 4916 9858 5582 9858 5712 9858 5563 9859 4920 9859 6218 9859 5563 9860 5621 9860 4920 9860 4920 9861 5621 9861 5548 9861 4920 9862 5548 9862 3017 9862 4843 9863 4921 9863 4922 9863 4836 9864 4923 9864 4924 9864 4924 9865 4923 9865 4843 9865 4924 9866 4843 9866 4925 9866 4925 9867 4843 9867 6219 9867 6219 9868 4843 9868 2949 9868 2949 9869 4843 9869 4922 9869 2949 9870 4922 9870 2951 9870 4928 9871 4637 9871 4881 9871 4881 9872 4637 9872 4926 9872 4926 9873 4637 9873 4927 9873 4926 9874 4927 9874 4839 9874 4839 9875 4927 9875 4638 9875 4839 9876 4638 9876 4843 9876 4881 9877 4879 9877 4928 9877 4928 9878 4879 9878 4856 9878 4928 9879 4856 9879 4930 9879 4930 9880 4856 9880 4929 9880 4930 9881 4929 9881 4636 9881 4636 9882 4929 9882 4932 9882 4636 9883 4932 9883 4931 9883 4931 9884 4932 9884 4866 9884 4931 9885 4866 9885 5685 9885 5685 9886 4866 9886 4941 9886 5685 9887 4941 9887 4943 9887 4318 9888 4933 9888 4317 9888 4317 9889 4933 9889 4934 9889 4317 9890 4934 9890 5754 9890 5754 9891 4934 9891 4921 9891 5754 9892 4921 9892 4935 9892 4935 9893 4921 9893 4843 9893 4935 9894 4843 9894 4936 9894 4936 9895 4843 9895 4638 9895 6218 9896 4937 9896 5563 9896 5563 9897 4937 9897 4938 9897 5563 9898 4938 9898 4939 9898 4939 9899 4938 9899 5678 9899 4939 9900 5678 9900 4940 9900 4941 9901 4942 9901 4943 9901 4943 9902 4942 9902 4944 9902 4943 9903 4944 9903 5683 9903 5683 9904 4944 9904 4945 9904 5683 9905 4945 9905 5682 9905 5682 9906 4945 9906 5569 9906 5682 9907 5569 9907 5681 9907 5681 9908 5569 9908 4939 9908 5681 9909 4939 9909 5680 9909 5680 9910 4939 9910 4940 9910 4946 9911 4947 9911 4618 9911 4618 9912 4947 9912 4620 9912 4701 9913 4948 9913 4702 9913 4702 9914 4948 9914 4620 9914 4702 9915 4620 9915 4703 9915 4703 9916 4620 9916 4947 9916 4701 9917 4700 9917 4948 9917 4948 9918 4700 9918 4666 9918 4948 9919 4666 9919 4621 9919 4666 9920 4949 9920 4621 9920 4621 9921 4949 9921 4708 9921 4621 9922 4708 9922 4623 9922 4623 9923 4708 9923 4951 9923 4623 9924 4951 9924 4950 9924 4951 9925 4952 9925 4950 9925 4950 9926 4952 9926 4677 9926 4950 9927 4677 9927 4625 9927 4625 9928 4677 9928 4953 9928 4625 9929 4953 9929 4954 9929 4954 9930 4953 9930 4955 9930 4953 9931 4711 9931 4955 9931 4955 9932 4711 9932 4653 9932 4955 9933 4653 9933 4956 9933 4956 9934 4653 9934 4957 9934 4956 9935 4957 9935 4627 9935 4957 9936 4958 9936 4627 9936 4627 9937 4958 9937 4960 9937 4627 9938 4960 9938 4959 9938 4959 9939 4960 9939 4961 9939 4960 9940 4962 9940 4961 9940 4961 9941 4962 9941 4729 9941 4961 9942 4729 9942 4963 9942 4963 9943 4729 9943 4728 9943 4963 9944 4728 9944 4964 9944 4728 9945 4726 9945 4964 9945 4964 9946 4726 9946 4725 9946 4964 9947 4725 9947 4965 9947 4965 9948 4725 9948 4966 9948 4725 9949 4723 9949 4966 9949 4966 9950 4723 9950 4738 9950 4966 9951 4738 9951 4631 9951 4631 9952 4738 9952 4968 9952 4631 9953 4968 9953 4967 9953 4967 9954 4968 9954 4737 9954 4967 9955 4737 9955 4633 9955 3008 9956 4619 9956 4969 9956 4969 9957 4619 9957 4970 9957 4969 9958 4970 9958 4741 9958 4741 9959 4970 9959 4635 9959 4741 9960 4635 9960 4694 9960 4694 9961 4635 9961 4633 9961 4694 9962 4633 9962 4735 9962 4735 9963 4633 9963 4737 9963 5661 9964 4973 9964 5662 9964 5662 9965 4973 9965 4971 9965 5662 9966 4971 9966 5660 9966 5660 9967 4971 9967 5539 9967 5660 9968 5539 9968 4972 9968 5661 9969 4974 9969 4973 9969 4973 9970 4974 9970 4975 9970 4973 9971 4975 9971 4976 9971 4975 9972 5668 9972 4976 9972 4976 9973 5668 9973 4977 9973 4976 9974 4977 9974 4978 9974 4978 9975 4977 9975 4979 9975 4978 9976 4979 9976 4981 9976 4981 9977 4979 9977 4980 9977 4405 9978 4406 9978 5673 9978 5673 9979 4406 9979 4981 9979 5673 9980 4981 9980 5675 9980 5675 9981 4981 9981 4980 9981 5022 9982 3084 9982 4982 9982 4982 9983 3084 9983 3101 9983 4982 9984 3101 9984 5023 9984 5023 9985 3101 9985 3104 9985 5023 9986 3104 9986 5024 9986 5024 9987 3104 9987 3105 9987 5024 9988 3105 9988 4983 9988 4983 9989 3105 9989 3098 9989 4983 9990 3098 9990 4984 9990 4984 9991 3098 9991 3099 9991 4984 9992 3099 9992 5016 9992 5016 9993 3099 9993 3094 9993 5016 9994 3094 9994 4985 9994 4985 9995 3094 9995 3096 9995 4985 9996 3096 9996 4986 9996 4986 9997 3096 9997 3091 9997 4986 9998 3091 9998 5019 9998 5019 9999 3091 9999 4987 9999 5019 10000 4987 10000 5020 10000 5020 10001 4987 10001 4988 10001 5020 10002 4988 10002 5012 10002 5012 10003 4988 10003 3088 10003 5012 10004 3088 10004 5011 10004 5011 10005 3088 10005 4989 10005 5011 10006 4989 10006 5009 10006 5009 10007 4989 10007 4990 10007 5009 10008 4990 10008 5008 10008 5008 10009 4990 10009 3090 10009 5008 10010 3090 10010 5006 10010 5006 10011 3090 10011 6154 10011 5035 10012 4991 10012 4992 10012 4992 10013 4991 10013 3146 10013 4992 10014 3146 10014 4993 10014 4993 10015 3146 10015 3149 10015 4993 10016 3149 10016 4994 10016 4994 10017 3149 10017 3150 10017 4994 10018 3150 10018 4995 10018 4995 10019 3150 10019 4997 10019 4995 10020 4997 10020 4996 10020 4996 10021 4997 10021 3142 10021 4996 10022 3142 10022 4998 10022 4998 10023 3142 10023 4999 10023 4998 10024 4999 10024 5000 10024 5000 10025 4999 10025 3144 10025 5000 10026 3144 10026 5001 10026 5001 10027 3144 10027 3141 10027 3159 10028 5002 10028 2859 10028 2859 10029 5002 10029 3161 10029 2859 10030 3161 10030 2865 10030 2865 10031 3161 10031 5022 10031 2865 10032 5022 10032 6193 10032 5006 10033 5003 10033 2933 10033 2933 10034 5003 10034 5004 10034 2933 10035 5004 10035 5005 10035 6230 10036 6229 10036 6200 10036 6200 10037 6229 10037 6227 10037 6200 10038 6227 10038 2938 10038 2933 10039 2938 10039 5006 10039 5006 10040 2938 10040 6227 10040 5006 10041 6227 10041 5008 10041 5008 10042 6227 10042 5007 10042 5008 10043 5007 10043 5009 10043 5009 10044 5007 10044 5010 10044 5009 10045 5010 10045 5011 10045 5011 10046 5010 10046 5484 10046 5011 10047 5484 10047 5012 10047 5012 10048 5484 10048 5013 10048 5480 10049 4983 10049 5014 10049 5014 10050 4983 10050 4984 10050 5014 10051 4984 10051 5481 10051 5481 10052 4984 10052 5016 10052 5481 10053 5016 10053 5015 10053 5015 10054 5016 10054 4985 10054 5015 10055 4985 10055 5017 10055 5017 10056 4985 10056 4986 10056 5017 10057 4986 10057 5018 10057 5018 10058 4986 10058 5019 10058 5018 10059 5019 10059 5013 10059 5013 10060 5019 10060 5020 10060 5013 10061 5020 10061 5012 10061 5460 10062 6239 10062 5021 10062 5021 10063 6193 10063 5460 10063 5460 10064 6193 10064 5022 10064 5460 10065 5022 10065 5477 10065 5477 10066 5022 10066 4982 10066 5477 10067 4982 10067 5479 10067 5479 10068 4982 10068 5023 10068 5479 10069 5023 10069 5480 10069 5480 10070 5023 10070 5024 10070 5480 10071 5024 10071 4983 10071 3163 10072 3167 10072 2895 10072 5025 10073 5026 10073 2897 10073 2897 10074 5026 10074 3156 10074 2897 10075 3156 10075 5027 10075 5027 10076 3156 10076 5518 10076 5027 10077 5518 10077 5028 10077 5031 10078 5000 10078 5029 10078 5029 10079 5000 10079 5001 10079 5029 10080 5001 10080 5032 10080 5036 10081 4993 10081 5492 10081 5492 10082 4993 10082 4994 10082 5492 10083 4994 10083 5494 10083 5494 10084 4994 10084 4995 10084 5494 10085 4995 10085 5030 10085 5030 10086 4995 10086 4996 10086 5030 10087 4996 10087 5031 10087 5031 10088 4996 10088 4998 10088 5031 10089 4998 10089 5000 10089 6235 10090 6233 10090 6236 10090 6236 10091 6233 10091 5032 10091 6236 10092 5032 10092 2894 10092 2894 10093 5032 10093 5001 10093 2894 10094 5001 10094 2895 10094 2895 10095 5001 10095 3162 10095 2895 10096 3162 10096 3163 10096 5038 10097 5033 10097 5491 10097 5491 10098 5033 10098 5526 10098 5491 10099 5526 10099 5034 10099 5034 10100 5526 10100 5035 10100 5034 10101 5035 10101 5036 10101 5036 10102 5035 10102 4992 10102 5036 10103 4992 10103 4993 10103 6226 10104 6223 10104 6222 10104 6222 10105 5028 10105 6226 10105 6226 10106 5028 10106 5518 10106 6226 10107 5518 10107 5462 10107 5462 10108 5518 10108 5520 10108 5462 10109 5520 10109 5487 10109 5487 10110 5520 10110 5521 10110 5487 10111 5521 10111 5488 10111 5488 10112 5521 10112 5522 10112 5488 10113 5522 10113 5037 10113 5037 10114 5522 10114 5523 10114 5037 10115 5523 10115 5038 10115 5038 10116 5523 10116 5525 10116 5038 10117 5525 10117 5033 10117 2906 10118 2900 10118 6214 10118 6214 10119 2900 10119 6211 10119 2918 10120 2917 10120 5039 10120 5039 10121 2917 10121 2915 10121 5039 10122 2915 10122 6231 10122 6231 10123 2915 10123 2913 10123 5043 10124 2910 10124 5040 10124 5040 10125 2910 10125 5041 10125 5040 10126 5041 10126 2909 10126 5040 10127 6221 10127 5043 10127 5043 10128 6221 10128 5042 10128 5043 10129 5042 10129 5044 10129 5044 10130 5042 10130 5046 10130 5044 10131 5046 10131 5045 10131 5045 10132 5046 10132 2929 10132 5045 10133 2929 10133 5047 10133 5047 10134 2929 10134 2928 10134 5047 10135 2928 10135 2913 10135 2913 10136 2928 10136 5048 10136 2913 10137 5048 10137 6231 10137 6199 10138 5049 10138 2925 10138 2925 10139 5049 10139 5050 10139 2863 10140 5051 10140 4807 10140 4807 10141 5051 10141 2866 10141 6206 10142 5052 10142 6207 10142 6207 10143 5052 10143 5054 10143 6207 10144 5054 10144 5053 10144 5053 10145 5054 10145 2875 10145 5055 10146 5056 10146 6237 10146 6237 10147 5056 10147 2871 10147 6237 10148 2871 10148 6194 10148 6237 10149 6238 10149 5055 10149 5055 10150 6238 10150 2886 10150 5055 10151 2886 10151 5057 10151 5057 10152 2886 10152 2889 10152 5057 10153 2889 10153 2873 10153 2873 10154 2889 10154 5058 10154 2873 10155 5058 10155 2874 10155 2874 10156 5058 10156 5059 10156 2874 10157 5059 10157 2875 10157 2875 10158 5059 10158 6234 10158 2875 10159 6234 10159 5053 10159 5060 10160 5061 10160 5062 10160 5062 10161 5061 10161 2893 10161 4368 10162 4369 10162 4645 10162 4645 10163 4369 10163 4612 10163 4645 10164 4612 10164 2982 10164 4373 10165 4343 10165 5063 10165 5063 10166 4343 10166 4646 10166 5063 10167 4646 10167 2940 10167 3612 10168 5064 10168 5065 10168 5065 10169 5064 10169 5066 10169 5065 10170 5066 10170 3613 10170 3613 10171 5066 10171 3615 10171 4135 10172 5067 10172 5068 10172 5068 10173 5067 10173 3169 10173 5068 10174 3169 10174 5069 10174 5069 10175 3169 10175 2954 10175 3607 10176 3599 10176 4366 10176 3605 10177 5074 10177 4641 10177 5064 10178 3612 10178 3601 10178 5070 10179 3601 10179 5071 10179 5071 10180 3601 10180 5072 10180 5071 10181 5072 10181 4641 10181 4641 10182 5072 10182 5073 10182 4641 10183 5073 10183 3605 10183 5074 10184 3605 10184 4350 10184 4350 10185 3605 10185 3610 10185 4350 10186 3610 10186 4352 10186 5075 10187 5064 10187 5076 10187 5076 10188 5064 10188 3601 10188 5076 10189 3601 10189 2991 10189 2991 10190 3601 10190 5070 10190 3607 10191 4366 10191 3608 10191 3608 10192 4366 10192 4365 10192 3608 10193 4365 10193 3610 10193 3610 10194 4365 10194 4353 10194 3610 10195 4353 10195 4352 10195 4128 10196 5077 10196 4129 10196 4129 10197 5077 10197 4126 10197 4333 10198 5078 10198 4130 10198 2952 10199 5080 10199 5079 10199 4130 10200 5078 10200 4128 10200 4128 10201 5078 10201 4322 10201 4128 10202 4322 10202 5077 10202 5079 10203 5080 10203 4131 10203 4131 10204 5080 10204 5081 10204 4131 10205 5081 10205 4130 10205 4130 10206 5081 10206 4335 10206 4130 10207 4335 10207 4333 10207 5069 10208 2954 10208 5083 10208 5083 10209 2954 10209 2955 10209 5083 10210 2955 10210 2957 10210 5079 10211 5082 10211 2952 10211 2952 10212 5082 10212 4134 10212 2952 10213 4134 10213 2961 10213 2961 10214 4134 10214 5083 10214 2961 10215 5083 10215 2958 10215 2958 10216 5083 10216 2957 10216 5089 10217 5084 10217 5086 10217 5086 10218 5084 10218 5085 10218 5085 10219 3358 10219 5271 10219 3026 10220 5086 10220 5087 10220 5087 10221 5086 10221 5085 10221 5087 10222 5085 10222 5088 10222 5088 10223 5085 10223 5271 10223 5123 10224 5124 10224 4662 10224 4662 10225 5124 10225 3352 10225 4662 10226 3352 10226 4661 10226 4661 10227 3352 10227 3354 10227 4661 10228 3354 10228 5089 10228 5089 10229 3354 10229 3355 10229 5089 10230 3355 10230 5084 10230 5090 10231 3349 10231 3350 10231 5753 10232 5091 10232 5092 10232 5093 10233 5113 10233 4709 10233 4709 10234 5113 10234 5094 10234 4709 10235 5094 10235 5095 10235 5095 10236 5094 10236 3646 10236 5095 10237 3646 10237 4679 10237 4679 10238 3646 10238 5096 10238 4679 10239 5096 10239 4717 10239 4717 10240 5096 10240 3650 10240 4717 10241 3650 10241 5110 10241 5110 10242 3650 10242 5108 10242 5090 10243 3350 10243 3405 10243 5092 10244 5097 10244 5753 10244 5753 10245 5097 10245 3663 10245 5753 10246 3663 10246 5098 10246 5098 10247 3663 10247 5105 10247 4596 10248 3622 10248 3669 10248 3669 10249 3622 10249 5099 10249 3669 10250 5099 10250 5100 10250 5100 10251 5099 10251 3623 10251 5100 10252 3623 10252 3668 10252 4600 10253 5101 10253 5112 10253 5102 10254 5109 10254 3386 10254 3386 10255 5109 10255 5103 10255 3386 10256 5103 10256 5104 10256 3623 10257 3628 10257 3668 10257 3668 10258 3628 10258 4670 10258 3668 10259 4670 10259 3667 10259 3667 10260 4670 10260 4697 10260 3667 10261 4697 10261 3665 10261 3665 10262 4697 10262 4655 10262 3665 10263 4655 10263 3663 10263 3663 10264 4655 10264 4381 10264 3663 10265 4381 10265 5105 10265 5106 10266 5107 10266 5108 10266 5108 10267 5107 10267 5109 10267 5108 10268 5109 10268 5110 10268 5110 10269 5109 10269 5102 10269 5110 10270 5102 10270 4720 10270 4720 10271 5102 10271 4682 10271 3631 10272 4600 10272 5111 10272 5111 10273 4600 10273 5112 10273 5111 10274 5112 10274 3625 10274 3625 10275 5112 10275 5113 10275 3625 10276 5113 10276 5114 10276 5114 10277 5113 10277 5093 10277 5114 10278 5093 10278 3626 10278 3626 10279 5093 10279 4670 10279 3626 10280 4670 10280 3627 10280 3627 10281 4670 10281 3628 10281 5102 10282 5115 10282 4682 10282 4682 10283 5115 10283 5116 10283 4682 10284 5116 10284 5117 10284 5117 10285 5116 10285 3393 10285 5117 10286 3393 10286 4686 10286 5118 10287 5119 10287 5128 10287 4664 10288 4688 10288 5120 10288 3393 10289 3391 10289 4686 10289 4686 10290 3391 10290 5129 10290 4686 10291 5129 10291 5136 10291 5120 10292 5121 10292 4664 10292 4664 10293 5121 10293 5122 10293 4664 10294 5122 10294 5123 10294 5123 10295 5122 10295 5125 10295 5123 10296 5125 10296 5124 10296 5124 10297 5125 10297 3413 10297 5124 10298 3413 10298 3350 10298 3350 10299 3413 10299 3412 10299 3350 10300 3412 10300 3405 10300 5126 10301 5118 10301 5127 10301 5127 10302 5118 10302 5128 10302 5127 10303 5128 10303 5129 10303 5129 10304 5128 10304 3370 10304 5129 10305 3370 10305 5136 10305 3368 10306 4609 10306 5130 10306 5130 10307 4609 10307 5131 10307 5130 10308 5131 10308 3376 10308 3376 10309 5131 10309 5132 10309 3376 10310 5132 10310 5133 10310 5133 10311 5132 10311 5120 10311 5133 10312 5120 10312 3374 10312 3374 10313 5120 10313 4688 10313 3374 10314 4688 10314 5134 10314 5134 10315 4688 10315 5136 10315 5134 10316 5136 10316 5135 10316 5135 10317 5136 10317 3370 10317 4392 10318 5747 10318 5137 10318 5138 10319 5139 10319 4184 10319 4184 10320 5139 10320 4388 10320 5758 10321 4310 10321 5139 10321 5758 10322 5139 10322 5760 10322 5760 10323 5139 10323 5138 10323 4756 10324 5143 10324 5142 10324 4388 10325 4392 10325 4184 10325 4184 10326 4392 10326 5137 10326 4184 10327 5137 10327 4183 10327 4183 10328 5137 10328 5644 10328 4183 10329 5644 10329 4182 10329 4182 10330 5644 10330 5172 10330 4182 10331 5172 10331 5175 10331 5140 10332 5141 10332 5851 10332 5851 10333 5141 10333 5154 10333 5851 10334 5154 10334 5153 10334 5142 10335 5143 10335 5865 10335 5865 10336 5143 10336 4750 10336 5865 10337 4750 10337 5867 10337 5142 10338 5144 10338 4756 10338 4756 10339 5144 10339 5151 10339 4756 10340 5151 10340 5155 10340 4588 10341 5145 10341 5146 10341 3037 10342 3874 10342 4750 10342 4750 10343 3874 10343 5868 10343 4750 10344 5868 10344 5867 10344 5159 10345 5167 10345 5169 10345 3041 10346 5276 10346 5147 10346 5147 10347 5276 10347 3874 10347 5147 10348 3874 10348 5148 10348 5148 10349 3874 10349 3037 10349 5149 10350 4588 10350 5863 10350 5863 10351 4588 10351 5146 10351 5863 10352 5146 10352 5151 10352 5151 10353 5146 10353 5150 10353 5151 10354 5150 10354 5155 10354 5181 10355 4760 10355 5856 10355 5856 10356 4760 10356 4759 10356 5856 10357 4759 10357 3901 10357 5152 10358 5158 10358 3886 10358 3886 10359 5158 10359 5153 10359 3886 10360 5153 10360 3888 10360 3888 10361 5153 10361 5154 10361 5150 10362 5848 10362 5155 10362 5155 10363 5848 10363 5850 10363 5155 10364 5850 10364 5156 10364 5156 10365 5850 10365 5852 10365 5156 10366 5852 10366 4748 10366 4748 10367 5852 10367 5158 10367 4748 10368 5158 10368 5157 10368 5157 10369 5158 10369 5152 10369 5159 10370 5169 10370 5647 10370 5169 10371 5160 10371 5647 10371 5647 10372 5160 10372 4148 10372 5647 10373 4148 10373 5172 10373 4575 10374 5161 10374 5168 10374 4584 10375 4583 10375 5184 10375 5152 10376 5162 10376 5157 10376 5157 10377 5162 10377 5861 10377 5157 10378 5861 10378 4753 10378 4753 10379 5861 10379 5185 10379 4753 10380 5185 10380 4759 10380 4759 10381 5185 10381 3902 10381 4759 10382 3902 10382 3901 10382 5163 10383 5164 10383 5853 10383 5853 10384 5164 10384 5179 10384 5853 10385 5179 10385 5165 10385 4162 10386 4164 10386 5166 10386 5166 10387 4164 10387 4166 10387 5166 10388 4166 10388 5167 10388 5167 10389 4166 10389 4167 10389 5167 10390 4167 10390 5169 10390 4576 10391 4575 10391 4169 10391 4169 10392 4575 10392 5168 10392 4169 10393 5168 10393 5761 10393 5761 10394 5168 10394 5169 10394 5761 10395 5169 10395 5170 10395 5170 10396 5169 10396 4167 10396 4148 10397 5171 10397 5172 10397 5172 10398 5171 10398 5173 10398 5172 10399 5173 10399 5175 10399 5175 10400 5173 10400 5174 10400 5175 10401 5174 10401 5176 10401 5176 10402 5174 10402 5178 10402 5176 10403 5178 10403 5177 10403 5177 10404 5178 10404 4577 10404 5181 10405 5165 10405 4162 10405 4162 10406 5165 10406 5179 10406 4162 10407 5179 10407 4161 10407 4161 10408 5179 10408 5180 10408 4161 10409 5180 10409 4160 10409 5166 10410 5653 10410 4162 10410 4162 10411 5653 10411 5182 10411 4162 10412 5182 10412 5181 10412 5181 10413 5182 10413 5183 10413 5181 10414 5183 10414 4760 10414 3889 10415 4584 10415 5859 10415 5859 10416 4584 10416 5184 10416 5859 10417 5184 10417 5185 10417 5185 10418 5184 10418 5186 10418 5185 10419 5186 10419 3902 10419 3334 10420 4602 10420 5218 10420 3615 10421 5066 10421 5187 10421 5187 10422 5066 10422 5188 10422 5187 10423 5188 10423 3594 10423 4288 10424 3596 10424 5194 10424 4290 10425 5191 10425 4281 10425 4281 10426 5191 10426 5201 10426 4281 10427 5201 10427 4280 10427 4290 10428 5189 10428 5191 10428 5191 10429 5189 10429 5190 10429 5191 10430 5190 10430 3058 10430 3058 10431 5190 10431 5192 10431 5188 10432 5193 10432 3594 10432 3594 10433 5193 10433 3063 10433 3594 10434 3063 10434 5194 10434 5194 10435 3063 10435 3058 10435 5194 10436 3058 10436 4288 10436 4288 10437 3058 10437 5192 10437 3060 10438 5206 10438 5195 10438 5195 10439 5206 10439 5198 10439 5195 10440 5198 10440 5191 10440 5196 10441 5197 10441 5198 10441 5198 10442 5197 10442 5199 10442 5198 10443 5199 10443 5191 10443 5191 10444 5199 10444 5200 10444 5191 10445 5200 10445 4300 10445 4279 10446 5201 10446 5202 10446 5202 10447 5201 10447 5191 10447 5202 10448 5191 10448 5203 10448 5203 10449 5191 10449 4300 10449 5204 10450 3672 10450 3589 10450 3589 10451 3672 10451 3673 10451 5209 10452 5205 10452 3053 10452 3053 10453 5205 10453 3590 10453 3053 10454 3590 10454 3061 10454 3061 10455 3590 10455 3589 10455 3061 10456 3589 10456 3060 10456 3060 10457 3589 10457 3673 10457 3060 10458 3673 10458 5206 10458 3587 10459 3654 10459 5207 10459 5207 10460 3654 10460 5208 10460 5207 10461 5208 10461 3057 10461 3057 10462 5208 10462 4601 10462 3057 10463 4601 10463 5209 10463 5209 10464 4601 10464 5210 10464 5209 10465 5210 10465 5205 10465 3638 10466 5213 10466 5211 10466 3587 10467 5207 10467 5212 10467 5212 10468 5207 10468 3054 10468 5212 10469 3054 10469 5213 10469 5213 10470 3054 10470 5214 10470 5213 10471 5214 10471 5211 10471 5229 10472 5215 10472 6175 10472 6175 10473 5215 10473 5216 10473 6175 10474 5216 10474 5217 10474 5217 10475 5216 10475 3334 10475 5217 10476 3334 10476 6178 10476 6178 10477 3334 10477 5218 10477 6178 10478 5218 10478 5219 10478 5219 10479 5218 10479 5220 10479 5219 10480 5220 10480 6177 10480 6177 10481 5220 10481 5221 10481 6177 10482 5221 10482 6176 10482 6176 10483 5221 10483 5222 10483 6176 10484 5222 10484 3052 10484 3052 10485 5222 10485 5223 10485 3052 10486 5223 10486 5224 10486 5224 10487 5223 10487 4604 10487 5224 10488 4604 10488 5211 10488 5211 10489 4604 10489 5225 10489 5211 10490 5225 10490 3638 10490 3338 10491 4605 10491 5226 10491 5226 10492 4605 10492 5227 10492 5226 10493 5227 10493 6174 10493 6174 10494 5227 10494 5228 10494 6174 10495 5228 10495 5229 10495 5229 10496 5228 10496 3399 10496 5229 10497 3399 10497 5215 10497 4607 10498 5230 10498 5233 10498 5233 10499 5230 10499 5231 10499 3338 10500 5226 10500 3336 10500 3336 10501 5226 10501 5232 10501 3336 10502 5232 10502 5231 10502 5231 10503 5232 10503 5234 10503 5231 10504 5234 10504 5233 10504 5233 10505 5234 10505 6170 10505 5233 10506 6170 10506 5235 10506 5235 10507 6170 10507 6171 10507 5235 10508 6171 10508 3339 10508 3339 10509 6171 10509 5236 10509 3339 10510 5236 10510 3406 10510 5242 10511 5237 10511 5236 10511 5236 10512 5237 10512 5238 10512 5236 10513 5238 10513 3406 10513 3175 10514 3362 10514 3071 10514 3071 10515 3362 10515 3361 10515 3071 10516 3361 10516 5239 10516 5239 10517 3361 10517 5241 10517 5239 10518 5241 10518 5240 10518 5240 10519 5241 10519 3342 10519 5240 10520 3342 10520 5242 10520 5242 10521 3342 10521 3346 10521 5242 10522 3346 10522 5237 10522 5247 10523 5243 10523 4573 10523 4580 10524 5516 10524 5515 10524 4155 10525 4157 10525 3115 10525 3115 10526 4157 10526 4579 10526 3115 10527 4579 10527 5244 10527 5244 10528 4579 10528 4580 10528 5244 10529 4580 10529 3116 10529 3116 10530 4580 10530 5515 10530 5252 10531 5245 10531 3113 10531 4155 10532 3115 10532 4108 10532 4108 10533 3115 10533 3114 10533 4108 10534 3114 10534 5245 10534 5245 10535 3114 10535 5246 10535 5245 10536 5246 10536 3113 10536 4114 10537 5247 10537 5248 10537 5248 10538 5247 10538 4573 10538 5248 10539 4573 10539 5249 10539 5249 10540 4573 10540 5250 10540 5249 10541 5250 10541 3113 10541 3113 10542 5250 10542 5251 10542 3113 10543 5251 10543 5252 10543 5260 10544 4188 10544 4140 10544 5248 10545 5253 10545 4114 10545 4114 10546 5253 10546 3109 10546 4114 10547 3109 10547 4111 10547 4111 10548 3109 10548 5259 10548 4572 10549 5254 10549 5255 10549 5267 10550 4321 10550 3106 10550 3106 10551 4321 10551 5256 10551 5256 10552 5257 10552 3106 10552 3106 10553 5257 10553 5258 10553 3106 10554 5258 10554 3107 10554 3107 10555 5258 10555 4314 10555 4572 10556 5255 10556 5263 10556 4140 10557 4111 10557 5260 10557 5260 10558 4111 10558 5259 10558 5260 10559 5259 10559 5261 10559 5261 10560 5259 10560 5262 10560 5261 10561 5262 10561 5255 10561 5255 10562 5262 10562 3107 10562 5255 10563 3107 10563 5263 10563 5263 10564 3107 10564 4314 10564 5264 10565 3106 10565 5270 10565 5264 10566 4119 10566 3106 10566 3106 10567 4119 10567 4306 10567 3106 10568 4306 10568 5265 10568 5265 10569 4305 10569 3106 10569 3106 10570 4305 10570 5266 10570 3106 10571 5266 10571 4304 10571 4320 10572 5267 10572 5268 10572 5268 10573 5267 10573 3106 10573 5268 10574 3106 10574 4303 10574 4303 10575 3106 10575 4304 10575 3169 10576 5067 10576 5269 10576 5269 10577 5067 10577 4138 10577 5269 10578 4138 10578 5270 10578 5270 10579 4138 10579 4117 10579 5270 10580 4117 10580 5264 10580 5271 10581 3358 10581 3175 10581 3175 10582 3358 10582 5272 10582 5272 10583 3363 10583 3175 10583 3175 10584 3363 10584 3364 10584 3175 10585 3364 10585 3362 10585 3877 10586 5275 10586 5273 10586 5273 10587 5275 10587 3179 10587 5273 10588 3179 10588 5274 10588 5275 10589 5276 10589 3179 10589 3179 10590 5276 10590 3041 10590 3179 10591 3041 10591 5277 10591 5277 10592 3041 10592 5278 10592 3004 10593 2872 10593 5279 10593 3004 10594 5279 10594 3010 10594 3010 10595 5279 10595 3203 10595 3010 10596 3203 10596 3019 10596 2967 10597 2911 10597 5280 10597 2967 10598 5280 10598 2969 10598 2969 10599 5280 10599 3223 10599 2969 10600 3223 10600 2970 10600 5320 10601 5319 10601 3145 10601 6158 10602 5330 10602 6159 10602 5281 10603 5283 10603 6161 10603 5282 10604 5283 10604 5284 10604 3110 10605 5285 10605 3108 10605 5336 10606 5330 10606 5346 10606 5286 10607 5319 10607 5287 10607 3122 10608 5313 10608 5311 10608 5292 10609 3128 10609 3129 10609 5288 10610 3135 10610 3129 10610 3129 10611 3135 10611 5289 10611 3129 10612 5289 10612 5292 10612 3138 10613 5290 10613 3140 10613 5293 10614 3128 10614 5291 10614 5291 10615 3128 10615 5292 10615 5291 10616 5292 10616 3850 10616 3850 10617 5292 10617 3136 10617 3850 10618 3136 10618 5296 10618 5293 10619 5871 10619 3128 10619 3128 10620 5871 10620 5294 10620 3128 10621 5294 10621 5295 10621 5295 10622 5294 10622 5870 10622 5295 10623 5870 10623 3125 10623 3136 10624 3138 10624 5296 10624 5296 10625 3138 10625 3140 10625 5296 10626 3140 10626 3852 10626 3852 10627 3140 10627 5297 10627 3852 10628 5297 10628 3853 10628 3853 10629 5297 10629 5298 10629 3853 10630 5298 10630 5299 10630 3857 10631 5300 10631 5302 10631 5302 10632 5300 10632 3855 10632 5305 10633 5301 10633 5302 10633 5870 10634 3857 10634 3125 10634 3125 10635 3857 10635 5302 10635 3125 10636 5302 10636 5306 10636 5306 10637 5302 10637 5301 10637 5306 10638 5301 10638 5887 10638 5310 10639 5303 10639 5304 10639 5304 10640 5303 10640 5305 10640 5304 10641 5305 10641 3143 10641 3143 10642 5305 10642 5302 10642 3143 10643 5302 10643 5298 10643 5298 10644 5302 10644 3855 10644 5298 10645 3855 10645 5299 10645 5887 10646 5885 10646 5306 10646 5306 10647 5885 10647 5884 10647 5306 10648 5884 10648 3123 10648 3123 10649 5884 10649 5307 10649 3123 10650 5307 10650 3122 10650 3122 10651 5307 10651 5308 10651 3122 10652 5308 10652 5313 10652 5308 10653 5309 10653 5313 10653 5313 10654 5309 10654 3835 10654 5313 10655 3835 10655 3833 10655 3833 10656 3832 10656 5310 10656 5310 10657 3832 10657 3830 10657 5310 10658 3830 10658 5303 10658 5286 10659 3121 10659 5906 10659 5910 10660 5909 10660 5313 10660 5313 10661 5909 10661 5908 10661 5313 10662 5908 10662 5311 10662 5311 10663 5908 10663 5312 10663 5311 10664 5312 10664 3121 10664 3121 10665 5312 10665 5907 10665 3121 10666 5907 10666 5906 10666 3833 10667 5310 10667 5313 10667 5313 10668 5310 10668 5314 10668 5313 10669 5314 10669 5910 10669 5316 10670 5315 10670 5314 10670 5314 10671 5315 10671 3803 10671 5314 10672 3803 10672 5910 10672 5906 10673 5905 10673 5286 10673 5286 10674 5905 10674 3811 10674 5286 10675 3811 10675 5319 10675 5319 10676 3811 10676 3809 10676 5319 10677 3809 10677 3145 10677 3145 10678 3809 10678 3807 10678 3145 10679 3807 10679 5316 10679 5316 10680 3807 10680 3805 10680 5316 10681 3805 10681 5315 10681 5324 10682 5317 10682 3781 10682 5323 10683 5318 10683 5930 10683 5930 10684 5318 10684 5287 10684 5930 10685 5287 10685 5931 10685 5931 10686 5287 10686 5319 10686 5931 10687 5319 10687 5932 10687 5932 10688 5319 10688 5320 10688 5932 10689 5320 10689 5321 10689 5321 10690 5320 10690 3778 10690 3778 10691 5320 10691 3148 10691 3778 10692 3148 10692 3779 10692 3779 10693 3148 10693 3147 10693 3779 10694 3147 10694 3781 10694 3781 10695 3147 10695 5322 10695 3781 10696 5322 10696 5324 10696 5323 10697 5927 10697 5318 10697 5318 10698 5927 10698 3785 10698 5318 10699 3785 10699 5324 10699 5324 10700 3785 10700 3784 10700 5324 10701 3784 10701 5317 10701 5328 10702 3112 10702 5325 10702 5325 10703 3112 10703 3117 10703 5326 10704 5832 10704 5328 10704 5329 10705 5322 10705 5327 10705 3117 10706 5324 10706 5325 10706 5325 10707 5324 10707 5322 10707 5325 10708 5322 10708 5328 10708 5328 10709 5322 10709 5329 10709 5328 10710 5329 10710 5326 10710 5330 10711 5331 10711 6159 10711 6159 10712 5331 10712 5332 10712 6159 10713 5332 10713 6160 10713 6160 10714 5332 10714 5333 10714 6160 10715 5333 10715 5327 10715 5327 10716 5333 10716 5834 10716 5327 10717 5834 10717 5329 10717 5832 10718 5831 10718 5328 10718 5328 10719 5831 10719 5334 10719 5328 10720 5334 10720 5335 10720 5334 10721 4024 10721 5335 10721 5335 10722 4024 10722 4023 10722 5335 10723 4023 10723 5336 10723 5336 10724 4023 10724 4022 10724 5336 10725 4022 10725 5330 10725 5330 10726 4022 10726 5337 10726 5330 10727 5337 10727 5331 10727 3111 10728 5346 10728 5338 10728 5341 10729 5339 10729 5285 10729 5285 10730 5339 10730 5343 10730 5285 10731 5343 10731 6164 10731 5338 10732 4050 10732 3111 10732 3111 10733 4050 10733 4049 10733 3111 10734 4049 10734 3110 10734 3110 10735 4049 10735 5340 10735 3110 10736 5340 10736 5285 10736 5285 10737 5340 10737 4047 10737 5285 10738 4047 10738 5341 10738 5339 10739 5811 10739 5343 10739 5343 10740 5811 10740 5342 10740 5343 10741 5342 10741 5344 10741 5344 10742 5342 10742 5345 10742 5344 10743 5345 10743 6158 10743 6158 10744 5345 10744 5807 10744 6158 10745 5807 10745 5330 10745 5330 10746 5807 10746 5347 10746 5330 10747 5347 10747 5346 10747 5346 10748 5347 10748 5348 10748 5346 10749 5348 10749 5338 10749 5282 10750 5351 10750 5349 10750 5349 10751 4078 10751 5282 10751 5282 10752 4078 10752 4079 10752 5282 10753 4079 10753 5283 10753 5283 10754 4079 10754 4080 10754 5283 10755 4080 10755 6161 10755 6161 10756 4080 10756 5350 10756 6161 10757 5350 10757 6163 10757 6163 10758 5350 10758 5353 10758 6163 10759 5353 10759 6164 10759 5285 10760 5787 10760 3108 10760 3108 10761 5787 10761 5352 10761 3108 10762 5352 10762 5351 10762 5351 10763 5352 10763 4077 10763 5351 10764 4077 10764 5349 10764 5353 10765 5790 10765 6164 10765 6164 10766 5790 10766 5354 10766 6164 10767 5354 10767 5285 10767 5285 10768 5354 10768 5789 10768 5285 10769 5789 10769 5787 10769 5358 10770 5357 10770 5369 10770 5369 10771 5357 10771 5367 10771 3132 10772 4104 10772 5355 10772 5355 10773 4104 10773 5357 10773 5355 10774 5357 10774 5356 10774 5356 10775 5357 10775 5358 10775 5363 10776 5359 10776 3132 10776 3132 10777 5359 10777 4106 10777 3132 10778 4106 10778 4104 10778 6169 10779 5365 10779 5360 10779 5360 10780 5365 10780 5771 10780 5360 10781 5771 10781 5281 10781 5281 10782 5771 10782 5768 10782 5768 10783 5361 10783 5281 10783 5281 10784 5361 10784 5765 10784 5281 10785 5765 10785 5283 10785 5283 10786 5765 10786 5362 10786 5283 10787 5362 10787 5284 10787 5284 10788 5362 10788 4107 10788 5284 10789 4107 10789 5363 10789 5363 10790 4107 10790 5364 10790 5363 10791 5364 10791 5359 10791 6169 10792 5366 10792 5365 10792 5365 10793 5366 10793 3137 10793 5365 10794 3137 10794 5367 10794 5367 10795 3137 10795 5368 10795 5367 10796 5368 10796 5369 10796 5370 10797 5374 10797 5386 10797 5371 10798 5407 10798 3093 10798 3100 10799 5433 10799 5421 10799 5444 10800 5440 10800 5428 10800 5448 10801 5449 10801 3102 10801 5372 10802 5449 10802 5450 10802 3514 10803 5373 10803 3055 10803 5388 10804 5401 10804 3062 10804 5378 10805 5374 10805 3059 10805 3077 10806 3078 10806 3076 10806 3076 10807 3078 10807 3072 10807 3076 10808 3072 10808 3073 10808 5375 10809 3087 10809 5376 10809 5376 10810 3087 10810 5377 10810 5376 10811 5377 10811 3078 10811 3586 10812 3585 10812 3072 10812 3064 10813 5379 10813 5378 10813 5378 10814 5379 10814 3581 10814 5378 10815 3581 10815 5374 10815 3585 10816 5380 10816 3072 10816 3072 10817 5380 10817 3582 10817 3072 10818 3582 10818 3064 10818 3064 10819 3582 10819 5381 10819 3064 10820 5381 10820 5379 10820 3581 10821 5957 10821 5374 10821 5374 10822 5957 10822 5382 10822 5374 10823 5382 10823 5386 10823 3078 10824 5377 10824 3072 10824 3072 10825 5377 10825 5383 10825 3072 10826 5383 10826 3586 10826 5382 10827 5384 10827 5386 10827 5386 10828 5384 10828 5385 10828 5386 10829 5385 10829 5377 10829 5377 10830 5385 10830 5955 10830 5377 10831 5955 10831 5383 10831 5401 10832 5387 10832 5972 10832 5388 10833 5389 10833 5401 10833 5401 10834 5389 10834 5974 10834 5401 10835 5974 10835 5387 10835 5972 10836 5390 10836 5400 10836 5400 10837 5390 10837 5391 10837 5400 10838 5391 10838 5392 10838 5392 10839 5391 10839 3569 10839 5392 10840 3569 10840 5370 10840 5395 10841 3565 10841 5388 10841 5388 10842 3565 10842 3564 10842 5388 10843 3564 10843 5389 10843 5370 10844 3569 10844 5374 10844 5374 10845 3569 10845 5393 10845 5374 10846 5393 10846 3059 10846 5393 10847 3567 10847 3059 10847 3059 10848 3567 10848 5394 10848 3059 10849 5394 10849 5395 10849 5395 10850 5394 10850 3566 10850 5395 10851 3566 10851 3565 10851 3540 10852 5396 10852 5401 10852 5401 10853 5396 10853 5397 10853 5401 10854 5397 10854 3062 10854 3062 10855 5397 10855 3543 10855 3062 10856 3543 10856 5399 10856 3543 10857 5398 10857 5399 10857 5399 10858 5398 10858 3546 10858 5399 10859 3546 10859 5406 10859 5406 10860 3546 10860 5998 10860 5999 10861 6000 10861 5407 10861 5972 10862 5400 10862 5401 10862 5401 10863 5400 10863 5404 10863 5401 10864 5404 10864 3540 10864 5407 10865 6000 10865 3093 10865 3093 10866 6000 10866 5402 10866 3093 10867 5402 10867 3089 10867 5402 10868 6002 10868 3089 10868 3089 10869 6002 10869 5403 10869 3089 10870 5403 10870 5404 10870 5404 10871 5403 10871 5405 10871 5404 10872 5405 10872 3540 10872 5998 10873 5999 10873 5406 10873 5406 10874 5999 10874 5407 10874 5406 10875 5407 10875 3056 10875 3056 10876 5407 10876 3055 10876 3055 10877 5373 10877 5409 10877 3092 10878 5422 10878 5423 10878 5371 10879 5408 10879 5407 10879 5407 10880 5408 10880 3510 10880 5407 10881 3510 10881 3055 10881 3055 10882 3510 10882 3513 10882 3055 10883 3513 10883 3514 10883 5373 10884 5410 10884 5409 10884 5409 10885 5410 10885 6030 10885 5409 10886 6030 10886 5411 10886 5411 10887 6030 10887 6032 10887 5411 10888 6032 10888 5423 10888 5423 10889 6032 10889 6034 10889 5423 10890 6034 10890 3092 10890 3092 10891 6034 10891 6036 10891 3092 10892 6036 10892 5412 10892 6036 10893 6039 10893 5412 10893 5412 10894 6039 10894 5413 10894 5412 10895 5413 10895 5371 10895 5371 10896 5413 10896 5414 10896 5371 10897 5414 10897 5408 10897 5425 10898 6173 10898 5433 10898 5433 10899 6173 10899 5418 10899 6137 10900 5418 10900 5415 10900 5415 10901 5418 10901 5416 10901 5415 10902 5416 10902 3268 10902 6137 10903 5417 10903 5418 10903 5418 10904 5417 10904 6136 10904 5418 10905 6136 10905 5433 10905 5433 10906 6136 10906 5419 10906 5433 10907 5419 10907 5421 10907 5419 10908 5420 10908 5421 10908 5421 10909 5420 10909 3255 10909 5421 10910 3255 10910 3095 10910 3095 10911 3255 10911 3259 10911 3095 10912 3259 10912 3097 10912 3097 10913 3259 10913 3261 10913 3097 10914 3261 10914 3262 10914 5422 10915 3097 10915 5423 10915 5423 10916 3097 10916 3262 10916 5423 10917 3262 10917 5424 10917 5424 10918 3262 10918 3265 10918 5424 10919 3265 10919 5416 10919 5416 10920 3265 10920 3266 10920 5416 10921 3266 10921 3268 10921 6120 10922 5426 10922 5425 10922 6118 10923 5436 10923 5440 10923 5425 10924 5426 10924 5427 10924 5427 10925 5426 10925 6119 10925 5427 10926 6119 10926 5439 10926 5428 10927 5429 10927 5431 10927 5431 10928 5429 10928 5430 10928 5431 10929 5430 10929 3100 10929 3100 10930 5430 10930 5432 10930 3100 10931 5432 10931 5433 10931 5433 10932 5432 10932 5434 10932 5433 10933 5434 10933 5425 10933 5425 10934 5434 10934 5435 10934 5425 10935 5435 10935 6120 10935 5436 10936 5437 10936 5440 10936 5440 10937 5437 10937 6115 10937 5440 10938 6115 10938 5428 10938 5428 10939 6115 10939 5438 10939 5428 10940 5438 10940 5429 10940 6119 10941 6118 10941 5439 10941 5439 10942 6118 10942 5440 10942 5439 10943 5440 10943 5441 10943 5441 10944 5440 10944 3298 10944 3298 10945 6105 10945 5441 10945 5441 10946 6105 10946 6103 10946 5441 10947 6103 10947 6172 10947 6172 10948 6103 10948 6102 10948 6172 10949 6102 10949 5372 10949 6102 10950 6100 10950 5372 10950 5372 10951 6100 10951 5442 10951 5372 10952 5442 10952 5449 10952 5449 10953 5442 10953 6098 10953 5449 10954 6098 10954 3102 10954 3102 10955 6098 10955 5443 10955 3102 10956 5443 10956 3103 10956 3103 10957 5443 10957 3301 10957 3103 10958 3301 10958 5444 10958 3301 10959 5445 10959 5444 10959 5444 10960 5445 10960 5446 10960 5444 10961 5446 10961 5440 10961 5440 10962 5446 10962 5447 10962 5440 10963 5447 10963 3298 10963 6081 10964 6080 10964 5456 10964 5448 10965 5451 10965 5449 10965 5449 10966 5451 10966 3327 10966 5449 10967 3327 10967 5450 10967 5450 10968 3327 10968 3326 10968 5450 10969 3326 10969 5452 10969 6080 10970 3331 10970 3083 10970 3083 10971 3331 10971 3330 10971 3083 10972 3330 10972 5448 10972 5448 10973 3330 10973 3329 10973 5448 10974 3329 10974 5451 10974 5454 10975 5457 10975 6084 10975 6084 10976 5457 10976 5452 10976 6084 10977 5452 10977 5453 10977 5453 10978 5452 10978 3326 10978 6081 10979 5456 10979 5455 10979 5456 10980 3066 10980 3069 10980 5454 10981 5455 10981 5457 10981 5457 10982 5455 10982 5456 10982 5457 10983 5456 10983 5458 10983 5458 10984 5456 10984 3069 10984 5458 10985 3069 10985 3070 10985 3082 10986 3079 10986 5456 10986 5456 10987 3079 10987 3065 10987 5456 10988 3065 10988 3066 10988 6080 10989 3083 10989 5456 10989 5456 10990 3083 10990 5459 10990 5456 10991 5459 10991 3082 10991 2888 10992 5460 10992 5477 10992 5461 10993 6226 10993 5462 10993 5466 10994 5463 10994 5464 10994 5466 10995 5464 10995 5465 10995 5463 10996 5466 10996 2930 10996 2930 10997 5466 10997 5467 10997 2930 10998 5467 10998 2931 10998 2931 10999 5467 10999 2932 10999 2932 11000 5467 11000 4427 11000 2932 11001 4427 11001 5468 11001 5468 11002 4427 11002 2926 11002 2926 11003 4427 11003 5469 11003 2926 11004 5469 11004 6227 11004 4495 11005 5471 11005 5470 11005 5470 11006 5471 11006 2890 11006 5032 11007 6232 11007 5474 11007 5474 11008 6232 11008 5472 11008 6232 11009 2885 11009 5472 11009 5472 11010 2885 11010 5473 11010 5472 11011 5473 11011 5471 11011 5471 11012 5473 11012 2891 11012 5471 11013 2891 11013 2890 11013 5030 11014 5031 11014 4537 11014 4537 11015 5031 11015 5474 11015 5474 11016 5031 11016 5029 11016 5474 11017 5029 11017 5032 11017 5470 11018 2887 11018 4495 11018 4495 11019 2887 11019 2888 11019 4495 11020 2888 11020 5475 11020 5475 11021 2888 11021 5477 11021 5475 11022 5477 11022 5476 11022 5476 11023 5477 11023 5479 11023 5476 11024 5479 11024 5478 11024 5478 11025 5479 11025 5480 11025 5478 11026 5480 11026 4488 11026 4488 11027 5480 11027 5014 11027 4488 11028 5014 11028 4487 11028 4487 11029 5014 11029 5481 11029 4487 11030 5481 11030 4431 11030 4431 11031 5481 11031 5015 11031 4431 11032 5015 11032 4432 11032 4432 11033 5015 11033 5017 11033 4432 11034 5017 11034 4445 11034 4445 11035 5017 11035 5018 11035 4445 11036 5018 11036 5482 11036 5482 11037 5018 11037 5013 11037 5482 11038 5013 11038 5483 11038 5483 11039 5013 11039 5484 11039 5483 11040 5484 11040 5485 11040 5485 11041 5484 11041 5010 11041 5485 11042 5010 11042 5469 11042 5469 11043 5010 11043 5007 11043 5469 11044 5007 11044 6227 11044 5464 11045 5461 11045 5465 11045 5465 11046 5461 11046 5462 11046 5465 11047 5462 11047 5486 11047 5486 11048 5462 11048 5487 11048 5486 11049 5487 11049 4419 11049 4419 11050 5487 11050 5488 11050 4419 11051 5488 11051 5489 11051 5489 11052 5488 11052 5037 11052 5489 11053 5037 11053 4535 11053 4535 11054 5037 11054 5038 11054 4535 11055 5038 11055 5490 11055 5490 11056 5038 11056 5491 11056 5490 11057 5491 11057 4416 11057 4416 11058 5491 11058 5034 11058 4416 11059 5034 11059 4415 11059 4415 11060 5034 11060 5036 11060 4415 11061 5036 11061 4442 11061 4442 11062 5036 11062 5492 11062 4442 11063 5492 11063 5493 11063 5493 11064 5492 11064 5494 11064 5493 11065 5494 11065 4536 11065 4536 11066 5494 11066 5030 11066 4536 11067 5030 11067 5495 11067 5495 11068 5030 11068 4537 11068 5510 11069 3905 11069 5511 11069 5274 11070 3179 11070 3875 11070 3875 11071 3179 11071 3127 11071 3875 11072 3127 11072 5496 11072 5496 11073 3127 11073 5497 11073 5496 11074 5497 11074 5498 11074 5498 11075 5497 11075 3126 11075 3124 11076 4590 11076 3126 11076 3126 11077 4590 11077 5499 11077 3126 11078 5499 11078 5498 11078 4581 11079 5500 11079 5505 11079 5505 11080 5500 11080 3916 11080 5506 11081 3863 11081 5501 11081 5501 11082 3863 11082 3862 11082 5501 11083 3862 11083 3124 11083 3124 11084 3862 11084 5502 11084 3124 11085 5502 11085 4590 11085 3893 11086 3894 11086 3120 11086 3120 11087 3894 11087 5503 11087 5503 11088 3894 11088 3861 11088 5503 11089 3861 11089 5504 11089 5504 11090 3861 11090 5505 11090 5504 11091 5505 11091 5506 11091 5506 11092 5505 11092 3916 11092 5506 11093 3916 11093 3863 11093 5686 11094 3897 11094 3119 11094 3119 11095 3897 11095 3859 11095 3119 11096 3859 11096 5507 11096 5507 11097 3859 11097 5509 11097 5507 11098 5509 11098 5508 11098 5508 11099 5509 11099 5510 11099 5508 11100 5510 11100 5512 11100 5512 11101 5510 11101 5511 11101 5512 11102 5511 11102 5513 11102 5513 11103 5511 11103 5514 11103 5513 11104 5514 11104 3120 11104 3120 11105 5514 11105 4585 11105 3120 11106 4585 11106 3893 11106 5515 11107 5516 11107 5517 11107 5517 11108 5516 11108 5686 11108 5517 11109 5686 11109 3118 11109 3118 11110 5686 11110 3119 11110 5518 11111 6168 11111 5520 11111 5520 11112 6168 11112 5519 11112 5520 11113 5519 11113 5521 11113 5521 11114 5519 11114 6162 11114 5521 11115 6162 11115 5522 11115 5522 11116 6162 11116 6165 11116 5522 11117 6165 11117 5523 11117 5523 11118 6165 11118 5524 11118 5523 11119 5524 11119 5525 11119 5525 11120 5524 11120 6157 11120 5525 11121 6157 11121 5033 11121 5033 11122 6157 11122 5527 11122 5033 11123 5527 11123 5526 11123 5526 11124 5527 11124 6156 11124 5526 11125 6156 11125 5035 11125 5035 11126 6156 11126 4991 11126 5528 11127 4744 11127 5677 11127 5677 11128 4744 11128 5529 11128 4744 11129 4763 11129 5529 11129 5529 11130 4763 11130 4769 11130 5529 11131 4769 11131 5679 11131 4769 11132 4768 11132 5679 11132 5679 11133 4768 11133 5530 11133 5679 11134 5530 11134 5531 11134 5530 11135 5532 11135 5531 11135 5531 11136 5532 11136 5533 11136 5531 11137 5533 11137 5537 11137 5537 11138 5533 11138 5534 11138 4780 11139 5535 11139 5536 11139 5536 11140 5535 11140 5537 11140 5536 11141 5537 11141 4781 11141 4781 11142 5537 11142 5534 11142 4780 11143 4778 11143 5535 11143 5535 11144 4778 11144 5538 11144 5535 11145 5538 11145 5684 11145 5684 11146 5538 11146 4785 11146 5684 11147 4785 11147 5540 11147 5540 11148 4785 11148 4786 11148 4972 11149 5539 11149 4794 11149 4794 11150 5539 11150 5540 11150 4794 11151 5540 11151 4787 11151 4787 11152 5540 11152 4786 11152 5635 11153 5735 11153 5633 11153 5541 11154 5726 11154 5560 11154 5542 11155 5543 11155 5544 11155 5599 11156 5566 11156 5600 11156 4941 11157 4866 11157 5545 11157 4942 11158 4941 11158 5637 11158 4944 11159 4942 11159 5636 11159 4945 11160 4944 11160 5628 11160 5569 11161 4945 11161 5626 11161 4550 11162 5546 11162 5547 11162 4565 11163 4564 11163 5580 11163 3018 11164 3017 11164 5548 11164 3018 11165 5548 11165 5610 11165 5555 11166 5549 11166 5554 11166 5554 11167 5549 11167 5610 11167 5550 11168 5551 11168 5612 11168 5612 11169 5551 11169 5552 11169 5612 11170 5552 11170 5554 11170 5554 11171 5552 11171 5553 11171 5554 11172 5553 11172 5555 11172 5556 11173 5557 11173 5550 11173 5550 11174 5557 11174 3012 11174 5550 11175 3012 11175 5551 11175 5559 11176 5560 11176 5558 11176 5558 11177 5560 11177 5606 11177 5558 11178 5606 11178 3000 11178 5559 11179 3002 11179 5560 11179 5560 11180 3002 11180 5561 11180 5560 11181 5561 11181 5556 11181 5556 11182 5561 11182 3011 11182 5556 11183 3011 11183 5557 11183 5605 11184 5547 11184 3000 11184 5546 11185 3005 11185 5547 11185 5547 11186 3005 11186 5562 11186 5547 11187 5562 11187 3000 11187 4557 11188 5566 11188 4558 11188 4558 11189 5566 11189 5599 11189 4558 11190 5599 11190 4559 11190 4939 11191 5543 11191 5563 11191 5563 11192 5543 11192 5542 11192 5563 11193 5542 11193 5621 11193 5602 11194 5600 11194 5564 11194 5564 11195 5600 11195 5566 11195 5564 11196 5566 11196 5565 11196 5565 11197 5566 11197 4557 11197 5565 11198 4557 11198 4550 11198 5627 11199 5544 11199 5567 11199 5567 11200 5544 11200 5543 11200 5567 11201 5543 11201 5568 11201 5568 11202 5543 11202 4939 11202 5568 11203 4939 11203 5569 11203 5570 11204 5590 11204 5584 11204 5717 11205 5716 11205 5595 11205 5595 11206 5716 11206 5570 11206 5595 11207 5570 11207 5571 11207 5571 11208 5570 11208 5584 11208 5571 11209 5584 11209 5583 11209 4563 11210 4561 11210 5592 11210 5592 11211 4561 11211 5573 11211 5592 11212 5573 11212 5593 11212 5593 11213 5573 11213 5574 11213 5593 11214 5574 11214 5594 11214 5594 11215 5574 11215 5572 11215 4561 11216 4560 11216 5573 11216 5573 11217 4560 11217 5598 11217 5573 11218 5598 11218 5574 11218 5574 11219 5598 11219 5575 11219 5574 11220 5575 11220 5572 11220 5572 11221 5575 11221 5601 11221 5572 11222 5601 11222 5719 11222 5719 11223 5601 11223 5576 11223 5577 11224 5618 11224 5579 11224 5733 11225 5616 11225 5623 11225 5623 11226 5616 11226 5577 11226 5623 11227 5577 11227 5578 11227 5578 11228 5577 11228 5579 11228 5578 11229 5579 11229 5622 11229 4565 11230 5580 11230 5581 11230 5581 11231 5580 11231 5585 11231 5581 11232 5585 11232 4918 11232 4918 11233 5585 11233 5586 11233 4918 11234 5586 11234 4919 11234 4919 11235 5586 11235 5714 11235 4919 11236 5714 11236 5582 11236 4564 11237 5583 11237 5580 11237 5580 11238 5583 11238 5584 11238 5580 11239 5584 11239 5585 11239 5585 11240 5584 11240 5590 11240 5585 11241 5590 11241 5586 11241 5586 11242 5590 11242 5587 11242 5586 11243 5587 11243 5714 11243 5716 11244 5588 11244 5570 11244 5570 11245 5588 11245 5589 11245 5570 11246 5589 11246 5590 11246 5590 11247 5589 11247 5591 11247 5590 11248 5591 11248 5587 11248 4564 11249 4563 11249 5583 11249 5583 11250 4563 11250 5592 11250 5583 11251 5592 11251 5571 11251 5571 11252 5592 11252 5593 11252 5571 11253 5593 11253 5595 11253 5595 11254 5593 11254 5594 11254 5595 11255 5594 11255 5717 11255 5719 11256 5596 11256 5572 11256 5572 11257 5596 11257 5721 11257 5572 11258 5721 11258 5594 11258 5594 11259 5721 11259 5597 11259 5594 11260 5597 11260 5717 11260 4560 11261 4559 11261 5598 11261 5598 11262 4559 11262 5599 11262 5598 11263 5599 11263 5575 11263 5575 11264 5599 11264 5600 11264 5575 11265 5600 11265 5601 11265 5601 11266 5600 11266 5602 11266 5601 11267 5602 11267 5576 11267 5576 11268 5602 11268 5603 11268 5604 11269 5722 11269 5725 11269 4550 11270 5547 11270 5565 11270 5565 11271 5547 11271 5605 11271 5565 11272 5605 11272 5564 11272 5564 11273 5605 11273 5604 11273 5564 11274 5604 11274 5602 11274 5602 11275 5604 11275 5725 11275 5602 11276 5725 11276 5603 11276 3000 11277 5606 11277 5605 11277 5605 11278 5606 11278 5560 11278 5605 11279 5560 11279 5604 11279 5604 11280 5560 11280 5726 11280 5604 11281 5726 11281 5722 11281 5541 11282 5560 11282 5727 11282 5727 11283 5560 11283 5556 11283 5727 11284 5556 11284 5607 11284 5607 11285 5556 11285 5550 11285 5607 11286 5550 11286 5728 11286 5728 11287 5550 11287 5608 11287 5608 11288 5550 11288 5612 11288 5608 11289 5612 11289 5609 11289 5548 11290 5614 11290 5610 11290 5610 11291 5614 11291 5615 11291 5610 11292 5615 11292 5554 11292 5554 11293 5615 11293 5611 11293 5554 11294 5611 11294 5612 11294 5612 11295 5611 11295 5613 11295 5612 11296 5613 11296 5609 11296 5548 11297 5622 11297 5614 11297 5614 11298 5622 11298 5579 11298 5614 11299 5579 11299 5615 11299 5615 11300 5579 11300 5618 11300 5615 11301 5618 11301 5611 11301 5611 11302 5618 11302 5620 11302 5611 11303 5620 11303 5613 11303 5616 11304 5617 11304 5577 11304 5577 11305 5617 11305 5732 11305 5577 11306 5732 11306 5618 11306 5618 11307 5732 11307 5619 11307 5618 11308 5619 11308 5620 11308 5548 11309 5621 11309 5622 11309 5622 11310 5621 11310 5542 11310 5622 11311 5542 11311 5578 11311 5578 11312 5542 11312 5544 11312 5578 11313 5544 11313 5623 11313 5623 11314 5544 11314 5627 11314 5623 11315 5627 11315 5733 11315 5733 11316 5627 11316 5624 11316 5631 11317 5736 11317 5625 11317 5569 11318 5626 11318 5568 11318 5568 11319 5626 11319 5630 11319 5568 11320 5630 11320 5567 11320 5567 11321 5630 11321 5631 11321 5567 11322 5631 11322 5627 11322 5627 11323 5631 11323 5625 11323 5627 11324 5625 11324 5624 11324 4945 11325 5628 11325 5626 11325 5626 11326 5628 11326 5629 11326 5626 11327 5629 11327 5630 11327 5630 11328 5629 11328 5633 11328 5630 11329 5633 11329 5631 11329 5631 11330 5633 11330 5735 11330 5631 11331 5735 11331 5736 11331 4944 11332 5636 11332 5628 11332 5628 11333 5636 11333 5632 11333 5628 11334 5632 11334 5629 11334 5629 11335 5632 11335 5640 11335 5629 11336 5640 11336 5633 11336 5633 11337 5640 11337 5634 11337 5633 11338 5634 11338 5635 11338 5639 11339 5739 11339 5641 11339 4942 11340 5637 11340 5636 11340 5636 11341 5637 11341 5638 11341 5636 11342 5638 11342 5632 11342 5632 11343 5638 11343 5639 11343 5632 11344 5639 11344 5640 11344 5640 11345 5639 11345 5641 11345 5640 11346 5641 11346 5634 11346 4941 11347 5545 11347 5637 11347 5637 11348 5545 11348 5642 11348 5637 11349 5642 11349 5638 11349 5638 11350 5642 11350 4867 11350 5638 11351 4867 11351 5639 11351 5639 11352 4867 11352 5643 11352 5639 11353 5643 11353 5739 11353 5644 11354 5137 11354 5645 11354 5172 11355 5644 11355 5646 11355 5647 11356 5172 11356 5656 11356 5159 11357 5647 11357 5648 11357 5167 11358 5159 11358 5666 11358 5166 11359 5167 11359 5649 11359 5663 11360 4747 11360 5652 11360 5652 11361 4747 11361 5182 11361 5652 11362 5182 11362 5653 11362 5650 11363 5663 11363 5651 11363 5651 11364 5663 11364 5652 11364 5651 11365 5652 11365 5654 11365 5654 11366 5652 11366 5653 11366 5654 11367 5653 11367 5166 11367 5644 11368 5645 11368 5646 11368 5646 11369 5645 11369 5658 11369 5646 11370 5658 11370 5657 11370 5655 11371 4793 11371 4790 11371 5172 11372 5646 11372 5656 11372 5656 11373 5646 11373 5657 11373 5656 11374 5657 11374 5672 11374 5672 11375 5657 11375 5659 11375 5672 11376 5659 11376 5674 11376 5658 11377 5745 11377 5657 11377 5657 11378 5745 11378 5744 11378 5657 11379 5744 11379 5659 11379 5659 11380 5744 11380 5742 11380 5659 11381 5742 11381 4405 11381 4972 11382 4793 11382 5660 11382 5660 11383 4793 11383 5655 11383 5660 11384 5655 11384 5662 11384 5661 11385 5662 11385 5650 11385 5650 11386 5662 11386 5655 11386 5650 11387 5655 11387 5663 11387 5663 11388 5655 11388 4790 11388 5663 11389 4790 11389 4747 11389 5665 11390 4975 11390 4974 11390 5166 11391 5649 11391 5654 11391 5654 11392 5649 11392 5664 11392 5654 11393 5664 11393 5651 11393 5651 11394 5664 11394 5665 11394 5651 11395 5665 11395 5650 11395 5650 11396 5665 11396 4974 11396 5650 11397 4974 11397 5661 11397 5167 11398 5666 11398 5649 11398 5649 11399 5666 11399 5671 11399 5649 11400 5671 11400 5664 11400 5664 11401 5671 11401 5667 11401 5664 11402 5667 11402 5665 11402 5665 11403 5667 11403 5668 11403 5665 11404 5668 11404 4975 11404 5159 11405 5648 11405 5666 11405 5666 11406 5648 11406 5669 11406 5666 11407 5669 11407 5671 11407 5671 11408 5669 11408 5670 11408 5671 11409 5670 11409 5667 11409 5667 11410 5670 11410 4977 11410 5667 11411 4977 11411 5668 11411 5647 11412 5656 11412 5648 11412 5648 11413 5656 11413 5672 11413 5648 11414 5672 11414 5669 11414 5669 11415 5672 11415 5674 11415 5669 11416 5674 11416 5670 11416 5670 11417 5674 11417 4979 11417 5670 11418 4979 11418 4977 11418 4405 11419 5673 11419 5659 11419 5659 11420 5673 11420 5675 11420 5659 11421 5675 11421 5674 11421 5674 11422 5675 11422 4980 11422 5674 11423 4980 11423 4979 11423 5676 11424 5677 11424 3031 11424 3031 11425 5677 11425 5529 11425 3031 11426 5529 11426 5678 11426 5678 11427 5529 11427 4940 11427 4940 11428 5529 11428 5679 11428 4940 11429 5679 11429 5680 11429 5680 11430 5679 11430 5531 11430 5680 11431 5531 11431 5681 11431 5681 11432 5531 11432 5537 11432 5681 11433 5537 11433 5682 11433 5682 11434 5537 11434 5535 11434 5682 11435 5535 11435 5683 11435 5683 11436 5535 11436 5684 11436 5683 11437 5684 11437 4943 11437 4943 11438 5684 11438 5540 11438 4943 11439 5540 11439 5685 11439 5685 11440 5540 11440 5539 11440 5685 11441 5539 11441 4931 11441 3896 11442 3897 11442 3899 11442 3899 11443 3897 11443 5686 11443 3899 11444 5686 11444 5163 11444 5163 11445 5686 11445 5164 11445 5164 11446 5686 11446 5516 11446 5164 11447 5516 11447 5179 11447 5691 11448 5690 11448 5687 11448 5688 11449 5693 11449 5689 11449 5689 11450 5693 11450 5690 11450 5689 11451 5690 11451 4873 11451 4873 11452 5690 11452 5691 11452 5688 11453 5692 11453 5693 11453 5693 11454 5692 11454 4851 11454 5693 11455 4851 11455 6322 11455 4877 11456 5694 11456 4878 11456 4878 11457 5694 11457 6322 11457 4878 11458 6322 11458 4849 11458 4849 11459 6322 11459 4851 11459 4877 11460 4876 11460 5694 11460 5694 11461 4876 11461 5695 11461 5694 11462 5695 11462 5696 11462 5695 11463 4883 11463 5696 11463 5696 11464 4883 11464 5697 11464 5696 11465 5697 11465 6320 11465 4816 11466 6321 11466 4890 11466 4890 11467 6321 11467 6320 11467 4890 11468 6320 11468 4887 11468 4887 11469 6320 11469 5697 11469 4816 11470 4815 11470 6321 11470 6321 11471 4815 11471 4892 11471 6321 11472 4892 11472 5700 11472 4894 11473 5699 11473 5698 11473 5698 11474 5699 11474 5700 11474 5698 11475 5700 11475 5701 11475 5701 11476 5700 11476 4892 11476 4894 11477 5702 11477 5699 11477 5699 11478 5702 11478 4899 11478 5699 11479 4899 11479 5705 11479 4902 11480 5703 11480 5704 11480 5704 11481 5703 11481 5705 11481 5704 11482 5705 11482 4903 11482 4903 11483 5705 11483 4899 11483 4902 11484 5706 11484 5703 11484 5703 11485 5706 11485 4862 11485 5703 11486 4862 11486 5707 11486 4862 11487 5708 11487 5707 11487 5707 11488 5708 11488 5709 11488 5707 11489 5709 11489 6319 11489 4813 11490 5710 11490 4910 11490 4910 11491 5710 11491 6319 11491 4910 11492 6319 11492 4908 11492 4908 11493 6319 11493 5709 11493 4813 11494 4913 11494 5710 11494 5710 11495 4913 11495 5711 11495 5710 11496 5711 11496 6318 11496 5711 11497 4914 11497 6318 11497 6318 11498 4914 11498 5712 11498 6318 11499 5712 11499 5713 11499 5712 11500 5582 11500 5713 11500 5713 11501 5582 11501 5714 11501 5713 11502 5714 11502 6317 11502 5589 11503 5715 11503 5591 11503 5591 11504 5715 11504 6317 11504 5591 11505 6317 11505 5587 11505 5587 11506 6317 11506 5714 11506 5589 11507 5588 11507 5715 11507 5715 11508 5588 11508 5716 11508 5715 11509 5716 11509 5718 11509 5716 11510 5717 11510 5718 11510 5718 11511 5717 11511 5597 11511 5718 11512 5597 11512 5720 11512 5719 11513 6326 11513 5596 11513 5596 11514 6326 11514 5720 11514 5596 11515 5720 11515 5721 11515 5721 11516 5720 11516 5597 11516 5719 11517 5576 11517 6326 11517 6326 11518 5576 11518 5603 11518 6326 11519 5603 11519 5724 11519 5726 11520 5723 11520 5722 11520 5722 11521 5723 11521 5724 11521 5722 11522 5724 11522 5725 11522 5725 11523 5724 11523 5603 11523 5726 11524 5541 11524 5723 11524 5723 11525 5541 11525 5727 11525 5723 11526 5727 11526 5729 11526 5608 11527 6325 11527 5728 11527 5728 11528 6325 11528 5729 11528 5728 11529 5729 11529 5607 11529 5607 11530 5729 11530 5727 11530 5608 11531 5609 11531 6325 11531 6325 11532 5609 11532 5613 11532 6325 11533 5613 11533 5730 11533 5613 11534 5620 11534 5730 11534 5730 11535 5620 11535 5619 11535 5730 11536 5619 11536 5731 11536 5616 11537 6324 11537 5617 11537 5617 11538 6324 11538 5731 11538 5617 11539 5731 11539 5732 11539 5732 11540 5731 11540 5619 11540 5616 11541 5733 11541 6324 11541 6324 11542 5733 11542 5624 11542 6324 11543 5624 11543 5734 11543 5735 11544 5737 11544 5736 11544 5736 11545 5737 11545 5734 11545 5736 11546 5734 11546 5625 11546 5625 11547 5734 11547 5624 11547 5735 11548 5635 11548 5737 11548 5737 11549 5635 11549 5634 11549 5737 11550 5634 11550 5738 11550 5634 11551 5641 11551 5738 11551 5738 11552 5641 11552 5739 11552 5738 11553 5739 11553 5687 11553 5687 11554 5739 11554 5643 11554 5687 11555 5643 11555 5691 11555 4410 11556 4376 11556 5740 11556 4410 11557 5740 11557 4292 11557 4292 11558 5740 11558 4396 11558 4292 11559 4396 11559 4296 11559 4390 11560 4401 11560 5741 11560 4405 11561 5742 11561 4403 11561 4403 11562 5742 11562 5743 11562 4403 11563 5743 11563 4402 11563 4402 11564 5743 11564 5741 11564 5742 11565 5744 11565 5743 11565 5743 11566 5744 11566 5745 11566 5743 11567 5745 11567 5746 11567 5741 11568 5743 11568 4390 11568 4390 11569 5743 11569 5746 11569 4390 11570 5746 11570 5748 11570 5748 11571 5746 11571 5747 11571 5748 11572 5747 11572 4392 11572 5137 11573 5747 11573 5645 11573 5645 11574 5747 11574 5746 11574 5645 11575 5746 11575 5658 11575 5658 11576 5746 11576 5745 11576 4396 11577 5740 11577 5749 11577 4396 11578 5749 11578 4378 11578 4378 11579 5749 11579 5752 11579 4378 11580 5752 11580 5750 11580 5751 11581 5752 11581 4375 11581 4375 11582 5752 11582 5749 11582 4375 11583 5749 11583 4377 11583 4377 11584 5749 11584 5740 11584 4377 11585 5740 11585 4376 11585 5751 11586 5753 11586 5752 11586 5752 11587 5753 11587 5098 11587 5752 11588 5098 11588 5750 11588 5750 11589 5098 11589 5105 11589 5754 11590 4935 11590 5755 11590 4319 11591 4317 11591 4400 11591 4400 11592 4317 11592 5754 11592 4400 11593 5754 11593 5756 11593 5756 11594 5754 11594 5755 11594 5760 11595 5138 11595 4223 11595 4175 11596 5758 11596 5757 11596 5757 11597 5758 11597 5760 11597 5757 11598 5760 11598 5759 11598 5759 11599 5760 11599 4223 11599 4170 11600 4169 11600 4246 11600 4246 11601 4169 11601 5761 11601 4246 11602 5761 11602 4244 11602 4244 11603 5761 11603 5170 11603 4244 11604 5170 11604 4242 11604 4242 11605 5170 11605 4167 11605 5174 11606 5173 11606 4199 11606 4202 11607 5178 11607 4200 11607 4200 11608 5178 11608 5174 11608 4200 11609 5174 11609 5762 11609 5762 11610 5174 11610 4199 11610 4257 11611 5083 11611 5763 11611 5763 11612 5083 11612 4134 11612 4090 11613 4107 11613 5775 11613 5775 11614 4107 11614 5362 11614 5775 11615 5362 11615 5764 11615 5764 11616 5362 11616 5765 11616 5764 11617 5765 11617 5766 11617 5766 11618 5765 11618 5361 11618 5766 11619 5361 11619 5767 11619 5767 11620 5361 11620 5768 11620 5767 11621 5768 11621 5769 11621 5769 11622 5768 11622 5771 11622 5769 11623 5771 11623 5770 11623 5770 11624 5771 11624 5365 11624 5770 11625 5365 11625 4100 11625 4100 11626 5365 11626 5367 11626 4100 11627 4099 11627 5783 11627 4100 11628 5783 11628 5770 11628 5770 11629 5783 11629 5772 11629 5770 11630 5772 11630 5769 11630 5769 11631 5772 11631 5773 11631 5769 11632 5773 11632 5767 11632 5773 11633 5786 11633 5767 11633 5767 11634 5786 11634 5774 11634 5767 11635 5774 11635 5766 11635 5774 11636 5781 11636 5766 11636 5766 11637 5781 11637 5780 11637 5766 11638 5780 11638 5764 11638 5780 11639 5779 11639 5764 11639 5764 11640 5779 11640 5777 11640 5764 11641 5777 11641 5775 11641 5775 11642 5777 11642 4088 11642 5775 11643 4088 11643 4090 11643 5776 11644 4088 11644 4262 11644 4262 11645 4088 11645 5777 11645 4262 11646 5777 11646 5778 11646 5778 11647 5777 11647 5779 11647 5779 11648 5780 11648 5778 11648 5778 11649 5780 11649 5781 11649 5778 11650 5781 11650 5782 11650 5781 11651 5774 11651 5782 11651 5782 11652 5774 11652 5786 11652 5782 11653 5786 11653 5785 11653 4099 11654 4082 11654 5783 11654 5783 11655 4082 11655 5784 11655 5783 11656 5784 11656 5772 11656 5772 11657 5784 11657 5785 11657 5772 11658 5785 11658 5773 11658 5773 11659 5785 11659 5786 11659 4059 11660 5352 11660 5788 11660 5788 11661 5352 11661 5787 11661 5788 11662 5787 11662 5797 11662 5797 11663 5787 11663 5789 11663 5797 11664 5789 11664 5796 11664 5796 11665 5789 11665 5354 11665 5796 11666 5354 11666 5791 11666 5791 11667 5354 11667 5790 11667 5791 11668 5790 11668 5793 11668 5793 11669 5790 11669 5353 11669 5793 11670 5353 11670 5792 11670 5792 11671 5353 11671 5350 11671 5792 11672 5794 11672 5793 11672 5793 11673 5794 11673 5802 11673 5793 11674 5802 11674 5791 11674 5791 11675 5802 11675 5795 11675 5791 11676 5795 11676 5796 11676 5796 11677 5795 11677 5804 11677 5796 11678 5804 11678 5797 11678 5797 11679 5804 11679 5798 11679 5797 11680 5798 11680 5788 11680 5788 11681 5798 11681 5799 11681 5788 11682 5799 11682 4059 11682 4059 11683 5799 11683 5800 11683 5794 11684 5801 11684 5802 11684 5802 11685 5801 11685 5803 11685 5802 11686 5803 11686 5795 11686 5795 11687 5803 11687 5805 11687 5795 11688 5805 11688 5804 11688 5804 11689 5805 11689 4228 11689 5804 11690 4228 11690 5798 11690 5798 11691 4228 11691 4227 11691 5798 11692 4227 11692 5799 11692 5799 11693 4227 11693 5806 11693 5799 11694 5806 11694 5800 11694 5800 11695 5806 11695 4057 11695 4032 11696 5338 11696 5818 11696 5818 11697 5338 11697 5348 11697 5818 11698 5348 11698 5817 11698 5817 11699 5348 11699 5347 11699 5817 11700 5347 11700 5816 11700 5816 11701 5347 11701 5807 11701 5816 11702 5807 11702 5808 11702 5808 11703 5807 11703 5345 11703 5808 11704 5345 11704 5809 11704 5809 11705 5345 11705 5342 11705 5809 11706 5342 11706 5810 11706 5810 11707 5342 11707 5811 11707 5810 11708 5811 11708 4044 11708 4044 11709 5811 11709 5339 11709 4044 11710 5812 11710 5813 11710 4044 11711 5813 11711 5810 11711 5810 11712 5813 11712 5814 11712 5810 11713 5814 11713 5809 11713 5809 11714 5814 11714 5828 11714 5809 11715 5828 11715 5808 11715 5828 11716 5826 11716 5808 11716 5808 11717 5826 11717 5815 11717 5808 11718 5815 11718 5816 11718 5815 11719 5824 11719 5816 11719 5816 11720 5824 11720 5822 11720 5816 11721 5822 11721 5817 11721 5822 11722 5821 11722 5817 11722 5817 11723 5821 11723 5819 11723 5817 11724 5819 11724 5818 11724 5818 11725 5819 11725 5820 11725 5818 11726 5820 11726 4032 11726 4205 11727 5820 11727 4206 11727 4206 11728 5820 11728 5819 11728 4206 11729 5819 11729 5823 11729 5823 11730 5819 11730 5821 11730 5821 11731 5822 11731 5823 11731 5823 11732 5822 11732 5824 11732 5823 11733 5824 11733 5825 11733 5824 11734 5815 11734 5825 11734 5825 11735 5815 11735 5826 11735 5825 11736 5826 11736 5829 11736 5812 11737 4026 11737 5813 11737 5813 11738 4026 11738 5827 11738 5813 11739 5827 11739 5814 11739 5814 11740 5827 11740 5829 11740 5814 11741 5829 11741 5828 11741 5828 11742 5829 11742 5826 11742 4025 11743 5831 11743 5830 11743 5830 11744 5831 11744 5832 11744 5830 11745 5832 11745 5833 11745 5833 11746 5832 11746 5326 11746 5833 11747 5326 11747 5840 11747 5840 11748 5326 11748 5329 11748 5840 11749 5329 11749 5838 11749 5838 11750 5329 11750 5834 11750 5838 11751 5834 11751 5836 11751 5836 11752 5834 11752 5333 11752 5836 11753 5333 11753 5835 11753 5835 11754 5333 11754 5332 11754 5835 11755 4019 11755 5836 11755 5836 11756 4019 11756 5837 11756 5836 11757 5837 11757 5838 11757 5838 11758 5837 11758 5839 11758 5838 11759 5839 11759 5840 11759 5840 11760 5839 11760 5844 11760 5840 11761 5844 11761 5833 11761 5833 11762 5844 11762 5845 11762 5833 11763 5845 11763 5830 11763 5830 11764 5845 11764 5847 11764 5830 11765 5847 11765 4025 11765 4025 11766 5847 11766 5841 11766 4019 11767 4252 11767 5837 11767 5837 11768 4252 11768 5842 11768 5837 11769 5842 11769 5839 11769 5839 11770 5842 11770 5843 11770 5839 11771 5843 11771 5844 11771 5844 11772 5843 11772 4255 11772 5844 11773 4255 11773 5845 11773 5845 11774 4255 11774 5846 11774 5845 11775 5846 11775 5847 11775 5847 11776 5846 11776 4249 11776 5847 11777 4249 11777 5841 11777 5841 11778 4249 11778 4248 11778 5848 11779 3960 11779 3961 11779 5848 11780 3961 11780 5850 11780 3961 11781 5849 11781 5850 11781 5850 11782 5849 11782 3962 11782 5850 11783 3962 11783 5852 11783 3910 11784 5851 11784 3971 11784 3971 11785 5851 11785 5153 11785 3971 11786 5153 11786 3968 11786 3968 11787 5153 11787 5158 11787 3968 11788 5158 11788 3966 11788 3966 11789 5158 11789 5852 11789 3966 11790 5852 11790 3964 11790 3964 11791 5852 11791 3962 11791 3985 11792 5853 11792 3992 11792 3992 11793 5853 11793 5165 11793 3992 11794 5165 11794 5854 11794 5854 11795 5165 11795 5181 11795 5854 11796 5181 11796 5855 11796 5855 11797 5181 11797 5856 11797 5855 11798 5856 11798 3988 11798 3988 11799 5856 11799 3901 11799 3988 11800 3901 11800 5857 11800 5858 11801 5859 11801 3947 11801 3947 11802 5859 11802 5185 11802 3947 11803 5185 11803 3945 11803 3945 11804 5185 11804 5861 11804 3945 11805 5861 11805 5860 11805 5860 11806 5861 11806 5162 11806 5860 11807 5162 11807 3943 11807 3943 11808 5162 11808 5152 11808 3943 11809 5152 11809 3885 11809 3885 11810 5152 11810 3886 11810 3920 11811 5863 11811 5862 11811 5862 11812 5863 11812 5151 11812 5862 11813 5151 11813 3925 11813 3925 11814 5151 11814 5144 11814 3925 11815 5144 11815 5864 11815 5864 11816 5144 11816 5142 11816 5864 11817 5142 11817 3923 11817 3923 11818 5142 11818 5865 11818 3923 11819 5865 11819 5866 11819 5866 11820 5865 11820 5867 11820 5866 11821 5867 11821 3922 11821 3922 11822 5867 11822 5868 11822 3856 11823 3857 11823 5869 11823 5869 11824 3857 11824 5870 11824 5869 11825 5870 11825 5876 11825 5876 11826 5870 11826 5294 11826 5876 11827 5294 11827 5875 11827 5875 11828 5294 11828 5871 11828 5875 11829 5871 11829 5874 11829 5874 11830 5871 11830 5293 11830 5874 11831 5293 11831 5872 11831 5872 11832 5293 11832 5291 11832 5872 11833 5291 11833 5873 11833 5873 11834 5291 11834 3850 11834 5873 11835 3841 11835 5872 11835 5872 11836 3841 11836 5879 11836 5872 11837 5879 11837 5874 11837 5874 11838 5879 11838 5880 11838 5874 11839 5880 11839 5875 11839 5875 11840 5880 11840 5881 11840 5875 11841 5881 11841 5876 11841 5876 11842 5881 11842 5877 11842 5876 11843 5877 11843 5869 11843 5869 11844 5877 11844 5883 11844 5869 11845 5883 11845 3856 11845 3856 11846 5883 11846 3836 11846 3841 11847 3936 11847 5879 11847 5879 11848 3936 11848 5878 11848 5879 11849 5878 11849 5880 11849 5880 11850 5878 11850 3937 11850 5880 11851 3937 11851 5881 11851 5881 11852 3937 11852 5882 11852 5881 11853 5882 11853 5877 11853 5877 11854 5882 11854 3938 11854 5877 11855 3938 11855 5883 11855 5883 11856 3938 11856 3927 11856 5883 11857 3927 11857 3836 11857 3836 11858 3927 11858 3926 11858 5897 11859 5308 11859 5895 11859 5895 11860 5308 11860 5307 11860 5895 11861 5307 11861 5893 11861 5893 11862 5307 11862 5884 11862 5893 11863 5884 11863 5891 11863 5891 11864 5884 11864 5885 11864 5891 11865 5885 11865 5886 11865 5886 11866 5885 11866 5887 11866 5886 11867 5887 11867 5888 11867 5888 11868 5887 11868 5301 11868 5888 11869 5301 11869 5889 11869 5889 11870 5301 11870 5305 11870 5889 11871 3828 11871 5888 11871 5888 11872 3828 11872 5899 11872 5888 11873 5899 11873 5886 11873 5886 11874 5899 11874 5890 11874 5886 11875 5890 11875 5891 11875 5891 11876 5890 11876 5892 11876 5891 11877 5892 11877 5893 11877 5893 11878 5892 11878 5894 11878 5893 11879 5894 11879 5895 11879 5895 11880 5894 11880 5896 11880 5895 11881 5896 11881 5897 11881 5897 11882 5896 11882 5898 11882 3828 11883 3977 11883 5899 11883 5899 11884 3977 11884 5900 11884 5899 11885 5900 11885 5890 11885 5890 11886 5900 11886 5901 11886 5890 11887 5901 11887 5892 11887 5892 11888 5901 11888 5902 11888 5892 11889 5902 11889 5894 11889 5894 11890 5902 11890 3976 11890 5894 11891 3976 11891 5896 11891 5896 11892 3976 11892 3975 11892 5896 11893 3975 11893 5898 11893 5898 11894 3975 11894 3820 11894 5903 11895 5905 11895 5904 11895 5904 11896 5905 11896 5906 11896 5904 11897 5906 11897 5917 11897 5917 11898 5906 11898 5907 11898 5917 11899 5907 11899 5914 11899 5914 11900 5907 11900 5312 11900 5914 11901 5312 11901 5913 11901 5913 11902 5312 11902 5908 11902 5913 11903 5908 11903 5912 11903 5912 11904 5908 11904 5909 11904 5912 11905 5909 11905 5911 11905 5911 11906 5909 11906 5910 11906 5911 11907 3793 11907 5912 11907 5912 11908 3793 11908 5919 11908 5912 11909 5919 11909 5913 11909 5913 11910 5919 11910 5920 11910 5913 11911 5920 11911 5914 11911 5914 11912 5920 11912 5915 11912 5914 11913 5915 11913 5917 11913 5917 11914 5915 11914 5916 11914 5917 11915 5916 11915 5904 11915 5904 11916 5916 11916 5918 11916 5904 11917 5918 11917 5903 11917 5903 11918 5918 11918 3796 11918 3793 11919 3795 11919 5919 11919 5919 11920 3795 11920 5921 11920 5919 11921 5921 11921 5920 11921 5920 11922 5921 11922 5922 11922 5920 11923 5922 11923 5915 11923 5915 11924 5922 11924 3951 11924 5915 11925 3951 11925 5916 11925 5916 11926 3951 11926 5923 11926 5916 11927 5923 11927 5918 11927 5918 11928 5923 11928 5924 11928 5918 11929 5924 11929 3796 11929 3796 11930 5924 11930 3786 11930 5925 11931 3785 11931 5926 11931 5926 11932 3785 11932 5927 11932 5926 11933 5927 11933 5928 11933 5928 11934 5927 11934 5323 11934 5928 11935 5323 11935 5929 11935 5929 11936 5323 11936 5930 11936 5929 11937 5930 11937 5934 11937 5934 11938 5930 11938 5931 11938 5934 11939 5931 11939 5933 11939 5933 11940 5931 11940 5932 11940 5933 11941 5932 11941 3774 11941 3774 11942 5932 11942 5321 11942 3774 11943 3759 11943 5933 11943 5933 11944 3759 11944 5941 11944 5933 11945 5941 11945 5934 11945 5934 11946 5941 11946 5935 11946 5934 11947 5935 11947 5929 11947 5929 11948 5935 11948 5936 11948 5929 11949 5936 11949 5928 11949 5928 11950 5936 11950 5937 11950 5928 11951 5937 11951 5926 11951 5926 11952 5937 11952 5938 11952 5926 11953 5938 11953 5925 11953 5925 11954 5938 11954 5939 11954 3759 11955 4000 11955 5941 11955 5941 11956 4000 11956 5940 11956 5941 11957 5940 11957 5935 11957 5935 11958 5940 11958 4003 11958 5935 11959 4003 11959 5936 11959 5936 11960 4003 11960 5942 11960 5936 11961 5942 11961 5937 11961 5937 11962 5942 11962 3998 11962 5937 11963 3998 11963 5938 11963 5938 11964 3998 11964 5943 11964 5938 11965 5943 11965 5939 11965 5939 11966 5943 11966 3767 11966 3602 11967 3733 11967 3603 11967 3603 11968 3733 11968 5944 11968 3718 11969 3728 11969 5945 11969 3718 11970 5945 11970 5947 11970 5947 11971 5945 11971 5946 11971 5947 11972 5946 11972 3643 11972 3643 11973 5946 11973 3644 11973 3644 11974 5946 11974 5948 11974 3644 11975 5948 11975 3645 11975 3659 11976 3694 11976 5949 11976 3659 11977 5949 11977 3662 11977 3662 11978 5949 11978 3714 11978 3662 11979 3714 11979 3699 11979 3676 11980 3675 11980 5950 11980 3676 11981 5950 11981 5951 11981 5951 11982 5950 11982 3686 11982 5951 11983 3686 11983 3629 11983 5952 11984 3586 11984 5964 11984 5964 11985 3586 11985 5383 11985 5964 11986 5383 11986 5953 11986 5953 11987 5383 11987 5955 11987 5953 11988 5955 11988 5954 11988 5954 11989 5955 11989 5385 11989 5954 11990 5385 11990 5962 11990 5962 11991 5385 11991 5384 11991 5962 11992 5384 11992 5956 11992 5956 11993 5384 11993 5382 11993 5956 11994 5382 11994 5960 11994 5960 11995 5382 11995 5957 11995 5960 11996 5957 11996 5958 11996 5958 11997 5957 11997 3581 11997 5958 11998 5959 11998 5960 11998 5960 11999 5959 11999 5967 11999 5960 12000 5967 12000 5956 12000 5956 12001 5967 12001 5968 12001 5956 12002 5968 12002 5962 12002 5962 12003 5968 12003 5961 12003 5962 12004 5961 12004 5954 12004 5954 12005 5961 12005 5963 12005 5954 12006 5963 12006 5953 12006 5953 12007 5963 12007 5965 12007 5953 12008 5965 12008 5964 12008 5964 12009 5965 12009 5969 12009 5964 12010 5969 12010 5952 12010 5952 12011 5969 12011 3574 12011 5959 12012 5966 12012 5967 12012 5967 12013 5966 12013 3735 12013 5967 12014 3735 12014 5968 12014 5968 12015 3735 12015 3737 12015 5968 12016 3737 12016 5961 12016 5961 12017 3737 12017 3739 12017 5961 12018 3739 12018 5963 12018 5963 12019 3739 12019 3741 12019 5963 12020 3741 12020 5965 12020 5965 12021 3741 12021 3742 12021 5965 12022 3742 12022 5969 12022 5969 12023 3742 12023 5970 12023 5969 12024 5970 12024 3574 12024 3574 12025 5970 12025 3744 12025 3554 12026 3569 12026 5971 12026 5971 12027 3569 12027 5391 12027 5971 12028 5391 12028 5984 12028 5984 12029 5391 12029 5390 12029 5984 12030 5390 12030 5982 12030 5982 12031 5390 12031 5972 12031 5982 12032 5972 12032 5980 12032 5980 12033 5972 12033 5387 12033 5980 12034 5387 12034 5973 12034 5973 12035 5387 12035 5974 12035 5973 12036 5974 12036 5976 12036 5976 12037 5974 12037 5389 12037 5975 12038 5977 12038 5976 12038 5976 12039 5977 12039 5973 12039 5977 12040 5997 12040 5973 12040 5973 12041 5997 12041 5978 12041 5973 12042 5978 12042 5980 12042 5978 12043 5979 12043 5980 12043 5980 12044 5979 12044 5995 12044 5980 12045 5995 12045 5982 12045 5995 12046 5981 12046 5982 12046 5982 12047 5981 12047 5983 12047 5982 12048 5983 12048 5984 12048 5983 12049 5985 12049 5984 12049 5984 12050 5985 12050 5986 12050 5984 12051 5986 12051 5971 12051 5987 12052 3554 12052 5988 12052 5988 12053 3554 12053 5971 12053 5988 12054 5971 12054 5991 12054 5991 12055 5971 12055 5986 12055 5990 12056 5989 12056 5987 12056 5987 12057 5988 12057 5990 12057 5990 12058 5988 12058 5991 12058 5990 12059 5991 12059 3710 12059 5991 12060 5986 12060 3710 12060 3710 12061 5986 12061 5985 12061 3710 12062 5985 12062 5992 12062 5985 12063 5983 12063 5992 12063 5992 12064 5983 12064 5981 12064 5992 12065 5981 12065 5993 12065 5993 12066 5981 12066 5995 12066 5993 12067 5995 12067 5994 12067 5995 12068 5979 12068 5994 12068 5994 12069 5979 12069 5978 12069 5994 12070 5978 12070 3715 12070 5975 12071 5996 12071 5977 12071 5977 12072 5996 12072 3715 12072 5977 12073 3715 12073 5997 12073 5997 12074 3715 12074 5978 12074 5999 12075 5998 12075 3539 12075 3539 12076 6005 12076 5999 12076 5999 12077 6005 12077 6007 12077 5999 12078 6007 12078 6000 12078 6007 12079 6009 12079 6000 12079 6000 12080 6009 12080 6010 12080 6000 12081 6010 12081 5402 12081 6010 12082 6011 12082 5402 12082 5402 12083 6011 12083 6001 12083 5402 12084 6001 12084 6002 12084 6002 12085 6001 12085 6015 12085 6002 12086 6015 12086 5403 12086 6015 12087 6017 12087 5403 12087 5403 12088 6017 12088 6003 12088 5403 12089 6003 12089 5405 12089 6004 12090 3540 12090 6021 12090 6021 12091 3540 12091 5405 12091 6021 12092 5405 12092 6020 12092 6020 12093 5405 12093 6003 12093 3539 12094 6026 12094 6005 12094 6005 12095 6026 12095 6006 12095 6005 12096 6006 12096 6007 12096 6007 12097 6006 12097 6008 12097 6007 12098 6008 12098 6009 12098 6009 12099 6008 12099 6028 12099 6009 12100 6028 12100 6010 12100 6010 12101 6028 12101 6012 12101 6010 12102 6012 12102 6011 12102 6011 12103 6012 12103 6013 12103 6011 12104 6013 12104 6001 12104 6001 12105 6013 12105 6014 12105 6001 12106 6014 12106 6015 12106 6015 12107 6014 12107 6016 12107 6015 12108 6016 12108 6017 12108 6017 12109 6016 12109 6018 12109 6017 12110 6018 12110 6003 12110 6003 12111 6018 12111 6019 12111 6003 12112 6019 12112 6020 12112 6020 12113 6019 12113 6024 12113 6020 12114 6024 12114 6021 12114 6021 12115 6024 12115 6023 12115 6021 12116 6023 12116 6004 12116 6004 12117 6023 12117 6022 12117 3687 12118 3521 12118 6022 12118 6022 12119 6023 12119 3687 12119 3687 12120 6023 12120 6024 12120 3687 12121 6024 12121 6025 12121 6024 12122 6019 12122 6025 12122 6025 12123 6019 12123 6018 12123 6025 12124 6018 12124 3688 12124 6018 12125 6016 12125 3688 12125 3688 12126 6016 12126 6014 12126 3688 12127 6014 12127 3689 12127 3689 12128 6014 12128 6013 12128 3689 12129 6013 12129 3690 12129 6013 12130 6012 12130 3690 12130 3690 12131 6012 12131 6028 12131 3690 12132 6028 12132 3692 12132 6026 12133 6027 12133 6006 12133 6006 12134 6027 12134 3692 12134 6006 12135 3692 12135 6008 12135 6008 12136 3692 12136 6028 12136 6030 12137 5410 12137 3507 12137 3507 12138 6043 12138 6030 12138 6030 12139 6043 12139 6029 12139 6030 12140 6029 12140 6032 12140 6029 12141 6031 12141 6032 12141 6032 12142 6031 12142 6033 12142 6032 12143 6033 12143 6034 12143 6033 12144 6035 12144 6034 12144 6034 12145 6035 12145 6046 12145 6034 12146 6046 12146 6036 12146 6036 12147 6046 12147 6037 12147 6036 12148 6037 12148 6039 12148 6037 12149 6038 12149 6039 12149 6039 12150 6038 12150 6049 12150 6039 12151 6049 12151 5413 12151 3508 12152 5414 12152 6050 12152 6050 12153 5414 12153 5413 12153 6050 12154 5413 12154 6040 12154 6040 12155 5413 12155 6049 12155 3507 12156 6041 12156 6043 12156 6043 12157 6041 12157 6042 12157 6043 12158 6042 12158 6029 12158 6029 12159 6042 12159 6031 12159 6031 12160 6042 12160 6044 12160 6031 12161 6044 12161 6033 12161 6033 12162 6044 12162 6035 12162 6035 12163 6044 12163 6045 12163 6035 12164 6045 12164 6046 12164 6046 12165 6045 12165 6037 12165 6037 12166 6045 12166 6047 12166 6037 12167 6047 12167 6038 12167 6038 12168 6047 12168 6049 12168 6049 12169 6047 12169 6048 12169 6049 12170 6048 12170 6040 12170 6040 12171 6048 12171 6050 12171 6050 12172 6048 12172 3489 12172 6050 12173 3489 12173 3508 12173 6041 12174 6051 12174 6042 12174 6042 12175 6051 12175 6052 12175 6042 12176 6052 12176 6044 12176 6044 12177 6052 12177 3730 12177 6044 12178 3730 12178 6045 12178 6045 12179 3730 12179 3731 12179 6045 12180 3731 12180 6047 12180 6047 12181 3731 12181 6053 12181 6047 12182 6053 12182 6048 12182 6048 12183 6053 12183 3732 12183 6048 12184 3732 12184 3489 12184 3489 12185 3732 12185 3490 12185 3468 12186 6054 12186 6055 12186 3468 12187 6055 12187 3387 12187 3387 12188 6055 12188 3480 12188 3387 12189 3480 12189 3388 12189 3388 12190 3480 12190 6056 12190 6056 12191 3480 12191 3479 12191 6056 12192 3479 12192 6057 12192 6057 12193 3479 12193 3394 12193 3394 12194 3479 12194 3471 12194 3394 12195 3471 12195 3392 12195 3408 12196 3415 12196 3457 12196 3457 12197 3415 12197 3453 12197 3408 12198 3457 12198 6058 12198 6058 12199 3457 12199 6059 12199 6058 12200 6059 12200 3409 12200 3409 12201 6059 12201 6060 12201 6060 12202 6059 12202 6062 12202 6060 12203 6062 12203 6061 12203 6061 12204 6062 12204 3410 12204 3410 12205 6062 12205 6063 12205 3410 12206 6063 12206 3411 12206 3411 12207 6063 12207 6064 12207 6064 12208 6063 12208 3459 12208 6064 12209 3459 12209 3450 12209 3369 12210 3433 12210 6065 12210 3369 12211 6065 12211 3371 12211 3371 12212 6065 12212 3441 12212 3371 12213 3441 12213 6066 12213 6066 12214 3441 12214 6067 12214 6066 12215 6067 12215 3372 12215 3372 12216 6067 12216 6068 12216 3372 12217 6068 12217 3373 12217 3373 12218 6068 12218 6069 12218 6069 12219 6068 12219 6070 12219 6069 12220 6070 12220 3377 12220 6071 12221 3418 12221 3426 12221 6071 12222 3426 12222 3351 12222 3351 12223 3426 12223 6073 12223 3351 12224 6073 12224 3353 12224 3353 12225 6073 12225 6072 12225 6072 12226 6073 12226 3428 12226 6072 12227 3428 12227 6074 12227 6074 12228 3428 12228 6075 12228 6075 12229 3428 12229 6077 12229 6075 12230 6077 12230 6076 12230 6076 12231 6077 12231 6078 12231 6078 12232 6077 12232 3429 12232 6078 12233 3429 12233 6079 12233 6079 12234 3429 12234 3357 12234 3357 12235 3429 12235 3430 12235 3357 12236 3430 12236 3356 12236 3317 12237 6080 12237 6092 12237 6092 12238 6080 12238 6081 12238 6092 12239 6081 12239 6082 12239 6082 12240 6081 12240 5455 12240 6082 12241 5455 12241 6083 12241 6083 12242 5455 12242 5454 12242 6083 12243 5454 12243 6088 12243 6088 12244 5454 12244 6084 12244 6088 12245 6084 12245 6087 12245 6087 12246 6084 12246 5453 12246 6087 12247 5453 12247 6085 12247 6085 12248 5453 12248 3326 12248 6085 12249 6086 12249 6087 12249 6087 12250 6086 12250 6093 12250 6087 12251 6093 12251 6088 12251 6088 12252 6093 12252 6089 12252 6088 12253 6089 12253 6083 12253 6083 12254 6089 12254 6090 12254 6083 12255 6090 12255 6082 12255 6082 12256 6090 12256 6091 12256 6082 12257 6091 12257 6092 12257 6092 12258 6091 12258 6095 12258 6092 12259 6095 12259 3317 12259 3317 12260 6095 12260 3313 12260 6086 12261 3425 12261 6093 12261 6093 12262 3425 12262 6094 12262 6093 12263 6094 12263 6089 12263 6089 12264 6094 12264 3422 12264 6089 12265 3422 12265 6090 12265 6090 12266 3422 12266 3420 12266 6090 12267 3420 12267 6091 12267 6091 12268 3420 12268 3432 12268 6091 12269 3432 12269 6095 12269 6095 12270 3432 12270 3431 12270 6095 12271 3431 12271 3313 12271 3313 12272 3431 12272 3314 12272 6096 12273 5443 12273 6111 12273 6111 12274 5443 12274 6098 12274 6111 12275 6098 12275 6097 12275 6097 12276 6098 12276 5442 12276 6097 12277 5442 12277 6099 12277 6099 12278 5442 12278 6100 12278 6099 12279 6100 12279 6101 12279 6101 12280 6100 12280 6102 12280 6101 12281 6102 12281 6104 12281 6104 12282 6102 12282 6103 12282 6104 12283 6103 12283 3297 12283 3297 12284 6103 12284 6105 12284 3297 12285 6106 12285 6104 12285 6104 12286 6106 12286 6107 12286 6104 12287 6107 12287 6101 12287 6101 12288 6107 12288 6108 12288 6101 12289 6108 12289 6099 12289 6099 12290 6108 12290 6109 12290 6099 12291 6109 12291 6097 12291 6097 12292 6109 12292 6113 12292 6097 12293 6113 12293 6111 12293 6111 12294 6113 12294 6110 12294 6111 12295 6110 12295 6096 12295 6096 12296 6110 12296 3287 12296 6106 12297 3454 12297 6107 12297 6107 12298 3454 12298 3465 12298 6107 12299 3465 12299 6108 12299 6108 12300 3465 12300 3464 12300 6108 12301 3464 12301 6109 12301 6109 12302 3464 12302 6112 12302 6109 12303 6112 12303 6113 12303 6113 12304 6112 12304 6114 12304 6113 12305 6114 12305 6110 12305 6110 12306 6114 12306 3461 12306 6110 12307 3461 12307 3287 12307 3287 12308 3461 12308 3460 12308 6129 12309 6115 12309 6116 12309 6116 12310 6115 12310 5437 12310 6116 12311 5437 12311 6127 12311 6127 12312 5437 12312 5436 12312 6127 12313 5436 12313 6117 12313 6117 12314 5436 12314 6118 12314 6117 12315 6118 12315 6123 12315 6123 12316 6118 12316 6119 12316 6123 12317 6119 12317 6122 12317 6122 12318 6119 12318 5426 12318 6122 12319 5426 12319 3283 12319 3283 12320 5426 12320 6120 12320 3283 12321 6121 12321 6122 12321 6122 12322 6121 12322 6124 12322 6122 12323 6124 12323 6123 12323 6123 12324 6124 12324 6125 12324 6123 12325 6125 12325 6117 12325 6117 12326 6125 12326 6126 12326 6117 12327 6126 12327 6127 12327 6127 12328 6126 12328 6128 12328 6127 12329 6128 12329 6116 12329 6116 12330 6128 12330 6130 12330 6116 12331 6130 12331 6129 12331 6129 12332 6130 12332 3269 12332 6121 12333 3275 12333 6124 12333 6124 12334 3275 12334 3438 12334 6124 12335 3438 12335 6125 12335 6125 12336 3438 12336 6131 12336 6125 12337 6131 12337 6126 12337 6126 12338 6131 12338 6132 12338 6126 12339 6132 12339 6128 12339 6128 12340 6132 12340 3446 12340 6128 12341 3446 12341 6130 12341 6130 12342 3446 12342 6133 12342 6130 12343 6133 12343 3269 12343 3269 12344 6133 12344 3444 12344 3254 12345 5420 12345 6141 12345 6141 12346 5420 12346 5419 12346 6141 12347 5419 12347 6134 12347 6134 12348 5419 12348 6136 12348 6134 12349 6136 12349 6135 12349 6135 12350 6136 12350 5417 12350 6135 12351 5417 12351 6139 12351 6139 12352 5417 12352 6137 12352 6139 12353 6137 12353 6138 12353 6138 12354 6137 12354 5415 12354 6138 12355 5415 12355 3242 12355 3242 12356 5415 12356 3268 12356 3242 12357 6143 12357 6138 12357 6138 12358 6143 12358 6144 12358 6138 12359 6144 12359 6139 12359 6139 12360 6144 12360 6146 12360 6139 12361 6146 12361 6135 12361 6135 12362 6146 12362 6140 12362 6135 12363 6140 12363 6134 12363 6134 12364 6140 12364 6148 12364 6134 12365 6148 12365 6141 12365 6141 12366 6148 12366 6142 12366 6141 12367 6142 12367 3254 12367 3254 12368 6142 12368 6149 12368 6143 12369 3483 12369 6144 12369 6144 12370 3483 12370 6145 12370 6144 12371 6145 12371 6146 12371 6146 12372 6145 12372 6147 12372 6146 12373 6147 12373 6140 12373 6140 12374 6147 12374 3474 12374 6140 12375 3474 12375 6148 12375 6148 12376 3474 12376 3473 12376 6148 12377 3473 12377 6142 12377 6142 12378 3473 12378 3477 12378 6142 12379 3477 12379 6149 12379 6149 12380 3477 12380 3478 12380 6150 12381 6152 12381 6151 12381 6151 12382 6152 12382 3081 12382 6151 12383 3081 12383 2861 12383 5005 12384 5004 12384 6153 12384 6153 12385 5004 12385 5003 12385 6153 12386 5003 12386 3086 12386 3086 12387 5003 12387 5006 12387 3086 12388 5006 12388 6154 12388 5005 12389 6153 12389 6155 12389 6155 12390 6153 12390 3085 12390 6155 12391 3085 12391 2935 12391 5519 12392 6168 12392 5360 12392 5527 12393 6160 12393 6156 12393 6156 12394 6160 12394 5327 12394 6156 12395 5327 12395 4991 12395 4991 12396 5327 12396 5322 12396 6165 12397 5343 12397 5524 12397 5524 12398 5343 12398 5344 12398 5524 12399 5344 12399 6157 12399 6157 12400 5344 12400 6158 12400 6157 12401 6158 12401 5527 12401 5527 12402 6158 12402 6159 12402 5527 12403 6159 12403 6160 12403 5360 12404 5281 12404 5519 12404 5519 12405 5281 12405 6161 12405 5519 12406 6161 12406 6162 12406 6162 12407 6161 12407 6163 12407 6162 12408 6163 12408 6165 12408 6165 12409 6163 12409 6164 12409 6165 12410 6164 12410 5343 12410 6166 12411 6167 12411 3136 12411 3136 12412 6167 12412 3138 12412 5360 12413 6168 12413 3155 12413 5360 12414 3155 12414 6169 12414 6169 12415 3155 12415 3154 12415 6169 12416 3154 12416 5366 12416 5366 12417 3154 12417 3153 12417 5366 12418 3153 12418 3137 12418 6172 12419 6170 12419 5441 12419 5441 12420 6170 12420 5234 12420 5441 12421 5234 12421 5439 12421 5458 12422 3071 12422 5457 12422 5457 12423 3071 12423 5239 12423 5457 12424 5239 12424 5452 12424 5452 12425 5239 12425 5240 12425 5452 12426 5240 12426 5450 12426 5450 12427 5240 12427 5242 12427 5450 12428 5242 12428 5372 12428 5372 12429 5242 12429 5236 12429 5372 12430 5236 12430 6172 12430 6172 12431 5236 12431 6171 12431 6172 12432 6171 12432 6170 12432 5439 12433 5234 12433 5427 12433 5427 12434 5234 12434 5232 12434 5427 12435 5232 12435 5425 12435 5425 12436 5232 12436 5226 12436 5425 12437 5226 12437 6173 12437 6173 12438 5226 12438 6174 12438 6173 12439 6174 12439 5418 12439 6174 12440 5229 12440 5418 12440 5418 12441 5229 12441 6175 12441 5418 12442 6175 12442 5416 12442 6175 12443 5217 12443 5416 12443 5416 12444 5217 12444 6178 12444 5416 12445 6178 12445 5424 12445 6176 12446 5423 12446 6177 12446 6177 12447 5423 12447 5424 12447 6177 12448 5424 12448 5219 12448 5219 12449 5424 12449 6178 12449 6179 12450 6180 12450 6253 12450 6253 12451 6180 12451 6181 12451 6253 12452 6181 12452 6182 12452 6182 12453 6181 12453 4473 12453 6182 12454 4473 12454 6254 12454 6254 12455 4473 12455 6183 12455 6254 12456 6183 12456 6250 12456 6250 12457 6183 12457 4479 12457 6250 12458 4479 12458 6252 12458 6252 12459 4479 12459 6184 12459 6252 12460 6184 12460 6247 12460 6247 12461 6184 12461 4481 12461 6247 12462 4481 12462 6244 12462 6244 12463 4481 12463 6185 12463 6244 12464 6185 12464 6186 12464 6186 12465 6185 12465 4483 12465 6186 12466 4483 12466 6187 12466 6187 12467 4483 12467 6188 12467 6187 12468 6188 12468 6189 12468 6189 12469 6188 12469 4491 12469 6189 12470 4491 12470 6190 12470 6190 12471 4491 12471 4484 12471 6190 12472 4484 12472 6191 12472 6191 12473 4484 12473 6192 12473 2866 12474 2865 12474 6193 12474 4812 12475 6195 12475 4807 12475 6193 12476 6237 12476 2866 12476 2866 12477 6237 12477 6194 12477 2866 12478 6194 12478 4807 12478 4807 12479 6194 12479 4805 12479 4807 12480 4805 12480 4812 12480 6195 12481 4811 12481 4807 12481 4807 12482 4811 12482 6196 12482 4807 12483 6196 12483 4808 12483 4808 12484 6196 12484 6197 12484 2918 12485 5039 12485 6200 12485 4795 12486 6198 12486 6199 12486 6199 12487 6198 12487 2918 12487 6199 12488 2918 12488 5049 12488 5049 12489 2918 12489 6200 12489 5049 12490 6200 12490 2938 12490 4795 12491 6201 12491 6198 12491 6198 12492 6201 12492 6203 12492 6198 12493 6203 12493 6202 12493 6202 12494 6203 12494 4796 12494 2996 12495 4551 12495 6204 12495 6204 12496 4551 12496 6205 12496 6205 12497 4551 12497 4555 12497 2772 12498 4549 12498 2770 12498 2770 12499 4549 12499 2975 12499 2771 12500 4549 12500 2772 12500 6206 12501 6207 12501 6236 12501 6208 12502 6209 12502 5060 12502 5060 12503 6209 12503 6206 12503 5060 12504 6206 12504 5061 12504 5061 12505 6206 12505 6236 12505 5061 12506 6236 12506 2894 12506 6208 12507 4801 12507 6209 12507 6209 12508 4801 12508 4802 12508 6209 12509 4802 12509 6210 12509 6210 12510 4802 12510 4803 12510 6211 12511 5027 12511 5028 12511 6212 12512 6213 12512 6214 12512 5028 12513 5040 12513 6211 12513 6211 12514 5040 12514 2909 12514 6211 12515 2909 12515 6214 12515 6214 12516 2909 12516 2908 12516 6214 12517 2908 12517 6212 12517 6213 12518 4799 12518 6214 12518 6214 12519 4799 12519 4797 12519 6214 12520 4797 12520 6215 12520 6215 12521 4797 12521 6216 12521 4938 12522 4937 12522 3029 12522 3029 12523 4937 12523 6217 12523 6217 12524 4937 12524 6218 12524 2948 12525 6219 12525 2949 12525 4925 12526 6219 12526 6220 12526 6220 12527 6219 12527 2948 12527 5028 12528 6222 12528 5040 12528 5040 12529 6222 12529 6221 12529 6221 12530 6222 12530 5042 12530 5042 12531 6222 12531 6223 12531 5042 12532 6223 12532 6224 12532 6224 12533 6223 12533 6225 12533 6225 12534 6223 12534 6226 12534 6225 12535 6226 12535 5461 12535 2926 12536 6227 12536 6228 12536 6228 12537 6227 12537 6229 12537 6231 12538 5048 12538 6229 12538 6229 12539 5048 12539 2927 12539 6229 12540 2927 12540 6228 12540 6229 12541 6230 12541 6231 12541 6231 12542 6230 12542 6200 12542 6231 12543 6200 12543 5039 12543 6232 12544 5032 12544 2884 12544 2884 12545 5032 12545 6233 12545 5053 12546 6234 12546 6233 12546 6233 12547 6234 12547 2883 12547 6233 12548 2883 12548 2884 12548 6233 12549 6235 12549 5053 12549 5053 12550 6235 12550 6236 12550 5053 12551 6236 12551 6207 12551 6193 12552 5021 12552 6237 12552 6237 12553 5021 12553 6238 12553 6238 12554 5021 12554 2886 12554 2886 12555 5021 12555 6239 12555 2886 12556 6239 12556 6240 12556 6240 12557 6239 12557 6241 12557 6241 12558 6239 12558 5460 12558 6241 12559 5460 12559 2888 12559 6242 12560 3046 12560 6247 12560 6247 12561 3046 12561 3048 12561 6247 12562 3048 12562 6243 12562 6247 12563 6244 12563 6186 12563 6243 12564 6245 12564 6247 12564 6247 12565 6245 12565 6246 12565 6247 12566 6246 12566 6251 12566 6186 12567 6187 12567 6247 12567 6247 12568 6187 12568 6189 12568 6247 12569 6189 12569 6190 12569 6190 12570 6191 12570 6247 12570 6247 12571 6191 12571 6248 12571 6247 12572 6248 12572 3042 12572 3042 12573 3043 12573 6247 12573 6247 12574 3043 12574 6249 12574 6247 12575 6249 12575 6242 12575 6179 12576 6250 12576 6251 12576 6251 12577 6250 12577 6252 12577 6251 12578 6252 12578 6247 12578 6179 12579 6253 12579 6250 12579 6250 12580 6253 12580 6182 12580 6250 12581 6182 12581 6254 12581 6257 12582 2857 12582 6258 12582 2764 12583 2762 12583 2766 12583 2766 12584 2762 12584 6256 12584 2854 12585 2853 12585 6258 12585 6258 12586 2853 12586 6255 12586 6256 12587 6257 12587 2766 12587 2766 12588 6257 12588 6258 12588 2766 12589 6258 12589 2767 12589 2767 12590 6258 12590 6255 12590 2767 12591 6255 12591 2769 12591 6261 12592 6259 12592 2755 12592 2846 12593 2843 12593 6261 12593 6261 12594 2843 12594 2761 12594 2756 12595 6259 12595 6260 12595 6260 12596 6259 12596 6261 12596 6260 12597 6261 12597 2760 12597 2760 12598 6261 12598 2761 12598 2849 12599 2848 12599 2751 12599 2751 12600 2848 12600 6261 12600 2751 12601 6261 12601 2753 12601 2753 12602 6261 12602 2755 12602 2842 12603 6265 12603 6263 12603 6262 12604 2838 12604 2840 12604 2840 12605 2838 12605 6263 12605 2840 12606 6263 12606 6264 12606 6264 12607 6263 12607 6265 12607 2835 12608 2750 12608 6266 12608 2842 12609 6263 12609 6267 12609 6267 12610 6263 12610 2835 12610 6267 12611 2835 12611 6268 12611 6268 12612 2835 12612 6266 12612 6268 12613 6266 12613 2748 12613 6271 12614 6269 12614 2744 12614 6271 12615 2832 12615 2830 12615 2741 12616 2834 12616 6270 12616 6270 12617 2834 12617 6271 12617 6270 12618 6271 12618 2743 12618 2743 12619 6271 12619 2744 12619 2745 12620 6269 12620 6272 12620 6272 12621 6269 12621 6271 12621 6272 12622 6271 12622 6273 12622 6273 12623 6271 12623 2830 12623 6275 12624 2737 12624 6274 12624 2825 12625 2824 12625 6275 12625 6275 12626 2824 12626 2821 12626 2738 12627 2737 12627 6276 12627 6276 12628 2737 12628 6275 12628 6276 12629 6275 12629 6277 12629 6277 12630 6275 12630 2821 12630 6278 12631 2828 12631 2733 12631 2733 12632 2828 12632 6275 12632 2733 12633 6275 12633 2735 12633 2735 12634 6275 12634 6274 12634 2819 12635 2818 12635 2817 12635 6282 12636 6279 12636 2819 12636 2819 12637 6279 12637 6280 12637 2732 12638 6282 12638 6281 12638 6281 12639 6282 12639 2819 12639 6281 12640 2819 12640 2815 12640 2815 12641 2819 12641 2817 12641 2820 12642 6283 12642 6284 12642 6284 12643 6283 12643 2819 12643 6284 12644 2819 12644 2730 12644 2730 12645 2819 12645 6280 12645 2721 12646 6285 12646 2722 12646 2722 12647 6285 12647 6286 12647 2724 12648 2722 12648 2726 12648 2726 12649 2722 12649 6286 12649 2726 12650 6286 12650 2727 12650 2727 12651 6286 12651 2811 12651 6288 12652 2814 12652 6287 12652 6285 12653 2719 12653 6286 12653 6286 12654 2719 12654 6288 12654 6286 12655 6288 12655 2812 12655 2812 12656 6288 12656 6287 12656 6292 12657 2807 12657 6293 12657 6289 12658 2716 12658 6294 12658 2710 12659 2808 12659 6291 12659 2716 12660 2714 12660 6294 12660 6294 12661 2714 12661 6290 12661 6294 12662 6290 12662 2711 12662 6291 12663 6292 12663 2710 12663 2710 12664 6292 12664 6293 12664 2710 12665 6293 12665 6294 12665 6294 12666 6293 12666 2805 12666 6294 12667 2805 12667 6289 12667 6298 12668 2704 12668 6299 12668 6295 12669 2704 12669 2706 12669 2706 12670 2704 12670 6298 12670 2706 12671 6298 12671 6296 12671 2801 12672 6297 12672 2700 12672 2700 12673 6297 12673 6298 12673 2700 12674 6298 12674 2701 12674 2701 12675 6298 12675 6299 12675 2798 12676 2796 12676 6298 12676 6298 12677 2796 12677 6300 12677 6298 12678 6300 12678 6296 12678 6303 12679 2788 12679 2787 12679 6301 12680 2696 12680 2694 12680 2791 12681 6302 12681 2793 12681 2793 12682 6302 12682 6303 12682 2793 12683 6303 12683 6304 12683 6304 12684 6303 12684 2787 12684 2787 12685 6305 12685 6304 12685 6304 12686 6305 12686 6301 12686 6304 12687 6301 12687 6306 12687 6306 12688 6301 12688 2694 12688 6307 12689 2690 12689 2688 12689 2785 12690 2783 12690 6307 12690 6307 12691 2783 12691 2782 12691 6307 12692 2782 12692 6308 12692 6308 12693 6309 12693 6307 12693 6307 12694 6309 12694 2691 12694 6307 12695 2691 12695 2690 12695 2786 12696 6310 12696 2686 12696 2686 12697 6310 12697 6307 12697 2686 12698 6307 12698 6311 12698 6311 12699 6307 12699 2688 12699 6312 12700 2778 12700 2776 12700 2683 12701 2682 12701 6313 12701 6313 12702 2682 12702 6314 12702 6313 12703 6314 12703 2684 12703 2684 12704 6314 12704 6315 12704 6316 12705 2781 12705 2679 12705 2679 12706 2781 12706 6312 12706 2679 12707 6312 12707 6314 12707 6314 12708 6312 12708 2776 12708 6314 12709 2776 12709 6315 12709 5713 12710 6317 12710 6323 12710 5713 12711 6323 12711 6318 12711 5707 12712 6319 12712 6323 12712 6323 12713 6319 12713 5710 12713 6323 12714 5710 12714 6318 12714 5699 12715 5705 12715 6323 12715 6323 12716 5705 12716 5703 12716 6323 12717 5703 12717 5707 12717 6320 12718 6321 12718 6323 12718 6323 12719 6321 12719 5700 12719 6323 12720 5700 12720 5699 12720 6322 12721 5694 12721 6323 12721 6323 12722 5694 12722 5696 12722 6323 12723 5696 12723 6320 12723 5687 12724 5690 12724 6323 12724 6323 12725 5690 12725 5693 12725 6323 12726 5693 12726 6322 12726 5734 12727 5737 12727 6323 12727 6323 12728 5737 12728 5738 12728 6323 12729 5738 12729 5687 12729 5730 12730 5731 12730 6323 12730 6323 12731 5731 12731 6324 12731 6323 12732 6324 12732 5734 12732 5723 12733 5729 12733 6323 12733 6323 12734 5729 12734 6325 12734 6323 12735 6325 12735 5730 12735 5720 12736 6326 12736 6323 12736 6323 12737 6326 12737 5724 12737 6323 12738 5724 12738 5723 12738 6317 12739 5715 12739 6323 12739 6323 12740 5715 12740 5718 12740 6323 12741 5718 12741 5720 12741 6333 12742 6327 12742 6343 12742 6345 12743 6339 12743 6344 12743 6328 12744 6329 12744 6337 12744 6337 12745 6329 12745 8262 12745 6337 12746 8262 12746 6346 12746 6330 12747 6345 12747 8259 12747 8259 12748 6345 12748 8261 12748 6342 12749 6331 12749 6343 12749 6343 12750 6331 12750 6332 12750 6343 12751 6332 12751 6333 12751 6333 12752 6332 12752 8170 12752 6335 12753 8267 12753 6336 12753 6336 12754 8267 12754 8268 12754 6336 12755 8268 12755 6334 12755 6334 12756 8268 12756 8269 12756 6334 12757 8269 12757 6338 12757 8170 12758 6335 12758 6333 12758 6333 12759 6335 12759 6336 12759 6333 12760 6336 12760 6327 12760 6327 12761 6336 12761 6334 12761 6327 12762 6334 12762 6337 12762 6337 12763 6334 12763 6338 12763 6337 12764 6338 12764 6328 12764 6339 12765 8638 12765 6340 12765 6344 12766 6339 12766 6341 12766 6341 12767 6339 12767 6340 12767 6341 12768 6340 12768 6342 12768 6342 12769 6343 12769 6341 12769 6341 12770 6343 12770 6327 12770 6341 12771 6327 12771 6344 12771 6344 12772 6327 12772 6337 12772 6344 12773 6337 12773 6345 12773 6345 12774 6337 12774 6346 12774 6345 12775 6346 12775 8261 12775 6347 12776 6360 12776 6348 12776 6348 12777 6360 12777 10364 12777 6348 12778 10364 12778 6350 12778 6350 12779 10364 12779 6349 12779 6350 12780 6349 12780 6351 12780 6351 12781 6349 12781 10396 12781 6351 12782 10396 12782 11783 12782 11783 12783 10396 12783 6352 12783 11783 12784 6352 12784 6353 12784 6353 12785 6352 12785 10376 12785 6353 12786 10376 12786 11785 12786 11785 12787 10376 12787 10360 12787 11785 12788 10360 12788 11786 12788 11786 12789 10360 12789 10355 12789 11786 12790 10355 12790 11787 12790 11787 12791 10355 12791 6354 12791 11787 12792 6354 12792 6355 12792 6355 12793 6354 12793 6356 12793 6355 12794 6356 12794 6357 12794 6357 12795 6356 12795 10385 12795 6357 12796 10385 12796 6358 12796 6358 12797 10385 12797 6359 12797 6358 12798 6359 12798 6347 12798 6347 12799 6359 12799 6360 12799 10411 12800 6361 12800 6363 12800 6362 12801 8246 12801 10411 12801 10411 12802 6363 12802 6362 12802 6362 12803 6363 12803 6364 12803 6362 12804 6364 12804 8258 12804 11621 12805 11618 12805 6365 12805 6365 12806 10368 12806 11621 12806 11621 12807 10368 12807 6366 12807 11621 12808 6366 12808 11622 12808 11622 12809 6366 12809 6367 12809 11622 12810 6367 12810 6368 12810 6368 12811 6367 12811 10366 12811 6368 12812 10366 12812 6369 12812 6369 12813 10366 12813 10365 12813 6369 12814 10365 12814 6370 12814 6370 12815 10365 12815 10379 12815 6370 12816 10379 12816 11626 12816 11626 12817 10379 12817 10415 12817 11626 12818 10415 12818 7601 12818 10560 12819 10563 12819 10386 12819 10557 12820 10560 12820 6371 12820 6371 12821 10560 12821 10386 12821 6371 12822 10386 12822 6372 12822 6372 12823 10386 12823 6373 12823 6374 12824 10557 12824 6375 12824 6375 12825 10557 12825 6371 12825 6375 12826 6371 12826 6376 12826 6376 12827 6371 12827 7596 12827 6376 12828 7596 12828 6377 12828 6377 12829 7596 12829 7598 12829 6377 12830 7598 12830 10415 12830 10415 12831 7598 12831 7601 12831 8291 12832 6378 12832 6389 12832 6389 12833 6378 12833 6380 12833 6389 12834 6380 12834 6402 12834 6402 12835 6380 12835 6379 12835 6402 12836 6379 12836 6396 12836 6396 12837 6379 12837 6383 12837 6396 12838 6383 12838 8966 12838 8966 12839 6383 12839 8967 12839 6378 12840 8331 12840 6380 12840 6380 12841 8331 12841 6381 12841 6380 12842 6381 12842 6379 12842 6379 12843 6381 12843 6382 12843 6379 12844 6382 12844 6383 12844 6383 12845 6382 12845 6384 12845 6383 12846 6384 12846 8967 12846 8967 12847 6384 12847 6385 12847 6401 12848 6386 12848 6403 12848 9489 12849 9491 12849 6454 12849 6396 12850 8966 12850 6388 12850 6406 12851 6387 12851 9534 12851 9534 12852 6387 12852 6400 12852 9534 12853 6400 12853 6388 12853 6388 12854 6400 12854 6397 12854 6388 12855 6397 12855 6396 12855 6386 12856 6401 12856 6389 12856 6389 12857 6401 12857 8292 12857 6389 12858 8292 12858 8291 12858 6394 12859 6393 12859 6390 12859 6391 12860 6393 12860 6392 12860 6392 12861 6393 12861 6394 12861 6392 12862 6394 12862 6395 12862 6395 12863 6394 12863 6448 12863 6402 12864 6396 12864 6398 12864 6398 12865 6396 12865 6397 12865 6398 12866 6397 12866 6404 12866 6404 12867 6397 12867 6400 12867 6404 12868 6400 12868 6399 12868 6399 12869 6400 12869 6387 12869 6453 12870 6448 12870 6405 12870 6405 12871 6448 12871 6394 12871 6405 12872 6394 12872 6403 12872 6403 12873 6394 12873 6390 12873 6403 12874 6390 12874 6401 12874 6389 12875 6402 12875 6386 12875 6386 12876 6402 12876 6398 12876 6386 12877 6398 12877 6403 12877 6403 12878 6398 12878 6404 12878 6403 12879 6404 12879 6405 12879 6405 12880 6404 12880 6399 12880 6405 12881 6399 12881 6453 12881 6453 12882 6399 12882 6387 12882 6453 12883 6387 12883 6454 12883 6454 12884 6387 12884 6406 12884 6454 12885 6406 12885 9489 12885 6491 12886 8968 12886 6412 12886 6502 12887 6416 12887 6407 12887 6413 12888 6414 12888 6408 12888 6408 12889 6414 12889 6411 12889 6381 12890 8331 12890 6410 12890 6410 12891 8331 12891 8294 12891 11412 12892 6502 12892 8295 12892 8295 12893 6502 12893 6407 12893 8295 12894 6407 12894 8294 12894 8294 12895 6407 12895 6409 12895 8294 12896 6409 12896 6410 12896 6382 12897 6413 12897 6384 12897 6384 12898 6413 12898 6408 12898 6384 12899 6408 12899 6385 12899 6415 12900 6503 12900 6411 12900 6411 12901 6503 12901 6491 12901 6411 12902 6491 12902 6408 12902 6408 12903 6491 12903 6412 12903 6408 12904 6412 12904 6385 12904 6382 12905 6381 12905 6413 12905 6413 12906 6381 12906 6410 12906 6413 12907 6410 12907 6414 12907 6414 12908 6410 12908 6409 12908 6414 12909 6409 12909 6411 12909 6411 12910 6409 12910 6407 12910 6411 12911 6407 12911 6415 12911 6415 12912 6407 12912 6416 12912 6417 12913 6418 12913 6445 12913 11417 12914 6391 12914 6392 12914 11413 12915 11415 12915 6429 12915 6440 12916 6520 12916 6422 12916 6440 12917 6422 12917 6423 12917 11413 12918 6429 12918 6419 12918 11415 12919 6420 12919 6429 12919 6429 12920 6420 12920 6421 12920 6429 12921 6421 12921 6427 12921 6427 12922 6421 12922 6434 12922 6427 12923 6434 12923 6433 12923 6422 12924 6519 12924 6423 12924 6423 12925 6519 12925 6441 12925 6423 12926 6441 12926 6431 12926 6431 12927 6441 12927 6424 12927 6431 12928 6424 12928 6426 12928 6426 12929 6424 12929 6425 12929 6535 12930 6427 12930 6425 12930 6425 12931 6427 12931 6433 12931 6425 12932 6433 12932 6426 12932 6535 12933 6537 12933 6427 12933 6427 12934 6537 12934 6428 12934 6427 12935 6428 12935 6429 12935 6429 12936 6428 12936 6539 12936 6429 12937 6539 12937 6419 12937 6438 12938 6440 12938 6430 12938 6430 12939 6440 12939 6423 12939 6430 12940 6423 12940 6452 12940 6452 12941 6423 12941 6431 12941 6452 12942 6431 12942 6451 12942 6451 12943 6431 12943 6426 12943 6451 12944 6426 12944 6432 12944 6432 12945 6426 12945 6433 12945 6432 12946 6433 12946 6450 12946 6450 12947 6433 12947 6434 12947 6450 12948 6434 12948 6435 12948 6435 12949 6434 12949 6421 12949 6435 12950 6421 12950 6436 12950 6436 12951 6421 12951 6420 12951 6418 12952 11417 12952 6445 12952 6445 12953 11417 12953 6392 12953 6445 12954 6392 12954 6437 12954 6437 12955 6392 12955 6395 12955 6437 12956 6395 12956 6448 12956 6430 12957 9492 12957 6438 12957 6438 12958 9492 12958 6439 12958 6438 12959 6439 12959 6440 12959 6440 12960 6439 12960 9493 12960 6440 12961 9493 12961 6520 12961 6519 12962 6442 12962 6441 12962 6441 12963 6442 12963 6443 12963 6441 12964 6443 12964 6424 12964 6424 12965 6443 12965 6545 12965 6424 12966 6545 12966 6425 12966 6425 12967 6545 12967 6534 12967 6425 12968 6534 12968 6535 12968 6444 12969 6417 12969 6449 12969 6449 12970 6417 12970 6445 12970 6449 12971 6445 12971 6446 12971 6446 12972 6445 12972 6437 12972 6446 12973 6437 12973 6447 12973 6447 12974 6437 12974 6448 12974 6447 12975 6448 12975 6453 12975 6436 12976 6444 12976 6435 12976 6435 12977 6444 12977 6449 12977 6435 12978 6449 12978 6450 12978 6450 12979 6449 12979 6446 12979 6450 12980 6446 12980 6432 12980 6432 12981 6446 12981 6447 12981 6432 12982 6447 12982 6451 12982 6451 12983 6447 12983 6453 12983 6451 12984 6453 12984 6452 12984 6452 12985 6453 12985 6454 12985 6452 12986 6454 12986 6430 12986 6430 12987 6454 12987 9491 12987 6430 12988 9491 12988 9492 12988 9037 12989 8968 12989 6491 12989 6455 12990 6494 12990 6456 12990 6496 12991 6455 12991 6457 12991 6457 12992 6455 12992 6456 12992 6457 12993 6456 12993 6498 12993 6498 12994 6456 12994 6458 12994 6498 12995 6458 12995 6459 12995 6459 12996 6458 12996 6506 12996 6459 12997 6506 12997 6499 12997 6499 12998 6506 12998 6460 12998 6499 12999 6460 12999 6508 12999 6491 13000 6503 13000 6492 13000 11411 13001 6461 13001 6462 13001 6462 13002 6461 13002 6487 13002 6462 13003 6487 13003 6486 13003 6556 13004 6490 13004 11408 13004 11408 13005 6490 13005 6464 13005 6467 13006 6463 13006 6464 13006 6464 13007 6463 13007 6465 13007 6464 13008 6465 13008 11408 13008 6466 13009 11405 13009 6467 13009 6467 13010 11405 13010 6468 13010 6467 13011 6468 13011 6463 13011 6473 13012 6476 13012 6466 13012 6466 13013 6476 13013 6469 13013 6466 13014 6469 13014 11405 13014 6461 13015 6470 13015 6487 13015 6487 13016 6470 13016 6472 13016 6487 13017 6472 13017 6471 13017 6471 13018 6472 13018 6474 13018 6471 13019 6474 13019 6473 13019 6473 13020 6474 13020 6475 13020 6473 13021 6475 13021 6476 13021 6558 13022 6477 13022 6478 13022 6478 13023 6477 13023 6560 13023 6478 13024 6560 13024 6509 13024 6558 13025 6478 13025 6479 13025 6479 13026 6478 13026 6507 13026 6479 13027 6507 13027 6489 13027 6489 13028 6507 13028 6480 13028 6489 13029 6480 13029 6481 13029 6481 13030 6480 13030 6505 13030 6481 13031 6505 13031 6482 13031 6482 13032 6505 13032 6504 13032 6482 13033 6504 13033 6488 13033 6488 13034 6504 13034 6484 13034 6488 13035 6484 13035 6483 13035 6483 13036 6484 13036 6485 13036 6483 13037 6485 13037 6486 13037 6486 13038 6487 13038 6483 13038 6483 13039 6487 13039 6471 13039 6483 13040 6471 13040 6488 13040 6488 13041 6471 13041 6473 13041 6488 13042 6473 13042 6482 13042 6482 13043 6473 13043 6466 13043 6482 13044 6466 13044 6481 13044 6481 13045 6466 13045 6467 13045 6481 13046 6467 13046 6489 13046 6489 13047 6467 13047 6464 13047 6489 13048 6464 13048 6479 13048 6479 13049 6464 13049 6490 13049 6479 13050 6490 13050 6558 13050 9036 13051 9037 13051 6495 13051 6495 13052 9037 13052 6491 13052 6495 13053 6491 13053 6493 13053 6493 13054 6491 13054 6492 13054 6492 13055 6494 13055 6493 13055 6493 13056 6494 13056 6455 13056 6493 13057 6455 13057 6495 13057 6495 13058 6455 13058 6496 13058 6495 13059 6496 13059 9036 13059 9036 13060 6496 13060 6457 13060 9036 13061 6457 13061 6497 13061 6497 13062 6457 13062 6498 13062 6497 13063 6498 13063 9022 13063 9022 13064 6498 13064 6459 13064 9022 13065 6459 13065 6500 13065 6500 13066 6459 13066 6499 13066 6500 13067 6499 13067 6501 13067 6501 13068 6499 13068 6508 13068 6501 13069 6508 13069 6510 13069 11412 13070 11411 13070 6502 13070 6502 13071 11411 13071 6462 13071 6502 13072 6462 13072 6416 13072 6416 13073 6462 13073 6486 13073 6416 13074 6486 13074 6415 13074 6415 13075 6486 13075 6485 13075 6415 13076 6485 13076 6503 13076 6503 13077 6485 13077 6492 13077 6492 13078 6485 13078 6484 13078 6492 13079 6484 13079 6494 13079 6494 13080 6484 13080 6504 13080 6494 13081 6504 13081 6456 13081 6456 13082 6504 13082 6505 13082 6456 13083 6505 13083 6458 13083 6458 13084 6505 13084 6480 13084 6458 13085 6480 13085 6506 13085 6506 13086 6480 13086 6507 13086 6506 13087 6507 13087 6460 13087 6460 13088 6507 13088 6478 13088 6460 13089 6478 13089 6508 13089 6508 13090 6478 13090 6509 13090 6508 13091 6509 13091 6510 13091 6540 13092 8286 13092 6419 13092 6553 13093 6511 13093 6512 13093 6512 13094 6511 13094 6513 13094 6555 13095 6514 13095 6515 13095 9497 13096 6546 13096 6516 13096 6443 13097 6442 13097 6549 13097 6549 13098 6517 13098 6544 13098 6544 13099 6517 13099 6551 13099 6544 13100 6551 13100 6552 13100 6550 13101 6519 13101 6518 13101 6518 13102 6519 13102 6422 13102 6518 13103 6422 13103 6520 13103 6521 13104 6550 13104 9496 13104 9496 13105 6550 13105 6518 13105 9496 13106 6518 13106 9495 13106 9495 13107 6518 13107 6520 13107 9495 13108 6520 13108 9493 13108 6521 13109 9496 13109 6522 13109 6522 13110 9496 13110 6523 13110 6522 13111 6523 13111 6527 13111 6527 13112 6524 13112 6516 13112 6516 13113 6524 13113 6525 13113 6516 13114 6525 13114 9497 13114 6526 13115 6569 13115 6529 13115 6553 13116 6522 13116 6511 13116 6511 13117 6522 13117 6527 13117 6511 13118 6527 13118 6513 13118 6513 13119 6527 13119 6516 13119 6513 13120 6516 13120 6528 13120 6528 13121 6516 13121 6546 13121 6528 13122 6546 13122 6529 13122 6548 13123 6530 13123 6515 13123 6515 13124 6530 13124 6531 13124 6515 13125 6531 13125 6555 13125 8286 13126 6540 13126 8288 13126 8290 13127 8288 13127 6554 13127 6554 13128 8288 13128 6540 13128 6554 13129 6540 13129 6532 13129 6545 13130 6533 13130 6534 13130 6534 13131 6533 13131 6543 13131 6534 13132 6543 13132 6535 13132 6535 13133 6543 13133 6536 13133 6535 13134 6536 13134 6537 13134 6537 13135 6536 13135 6541 13135 6537 13136 6541 13136 6428 13136 6428 13137 6541 13137 6538 13137 6428 13138 6538 13138 6539 13138 6419 13139 6539 13139 6540 13139 6540 13140 6539 13140 6538 13140 6540 13141 6538 13141 6532 13141 6532 13142 6538 13142 6541 13142 6532 13143 6541 13143 6542 13143 6542 13144 6541 13144 6536 13144 6542 13145 6536 13145 6552 13145 6552 13146 6536 13146 6543 13146 6552 13147 6543 13147 6544 13147 6544 13148 6543 13148 6533 13148 6544 13149 6533 13149 6549 13149 6549 13150 6533 13150 6545 13150 6549 13151 6545 13151 6443 13151 6529 13152 6546 13152 6526 13152 6526 13153 6546 13153 6547 13153 6526 13154 6547 13154 9572 13154 6569 13155 8335 13155 6529 13155 6529 13156 8335 13156 6548 13156 6529 13157 6548 13157 6528 13157 6528 13158 6548 13158 6515 13158 6528 13159 6515 13159 6513 13159 6513 13160 6515 13160 6514 13160 6513 13161 6514 13161 6512 13161 6442 13162 6519 13162 6549 13162 6549 13163 6519 13163 6550 13163 6549 13164 6550 13164 6517 13164 6517 13165 6550 13165 6521 13165 6517 13166 6521 13166 6551 13166 6551 13167 6521 13167 6522 13167 6551 13168 6522 13168 6552 13168 6552 13169 6522 13169 6553 13169 6552 13170 6553 13170 6542 13170 6542 13171 6553 13171 6512 13171 6542 13172 6512 13172 6532 13172 6532 13173 6512 13173 6514 13173 6532 13174 6514 13174 6554 13174 6554 13175 6514 13175 6555 13175 6554 13176 6555 13176 8290 13176 8290 13177 6555 13177 6531 13177 6477 13178 6558 13178 6559 13178 6490 13179 6556 13179 8296 13179 6563 13180 6564 13180 6557 13180 6562 13181 6590 13181 6561 13181 6558 13182 6490 13182 6559 13182 6559 13183 6490 13183 8296 13183 6559 13184 8296 13184 6565 13184 6565 13185 8296 13185 8298 13185 6565 13186 8298 13186 6566 13186 6566 13187 8298 13187 8299 13187 6566 13188 8299 13188 6567 13188 6567 13189 8299 13189 8300 13189 9021 13190 6510 13190 6557 13190 6557 13191 6510 13191 6509 13191 6557 13192 6509 13192 6563 13192 6563 13193 6509 13193 6560 13193 6582 13194 9021 13194 6561 13194 6561 13195 9021 13195 6557 13195 6561 13196 6557 13196 6562 13196 6562 13197 6557 13197 6564 13197 6560 13198 6477 13198 6563 13198 6563 13199 6477 13199 6559 13199 6563 13200 6559 13200 6564 13200 6564 13201 6559 13201 6565 13201 6564 13202 6565 13202 6562 13202 6562 13203 6565 13203 6566 13203 6562 13204 6566 13204 6590 13204 6590 13205 6566 13205 6567 13205 6568 13206 6618 13206 6580 13206 8336 13207 8335 13207 6569 13207 8336 13208 6569 13208 6570 13208 6570 13209 6569 13209 6526 13209 6570 13210 6526 13210 9572 13210 6570 13211 6571 13211 8336 13211 8336 13212 6571 13212 6573 13212 8336 13213 6573 13213 6572 13213 6572 13214 6573 13214 6574 13214 6572 13215 6574 13215 8338 13215 8338 13216 6574 13216 6575 13216 8338 13217 6575 13217 6576 13217 6576 13218 6575 13218 6577 13218 6576 13219 6577 13219 6578 13219 6578 13220 6577 13220 9603 13220 6578 13221 9603 13221 6579 13221 6579 13222 9603 13222 9602 13222 6579 13223 9602 13223 6580 13223 6580 13224 9602 13224 9601 13224 9601 13225 9488 13225 6581 13225 9601 13226 6581 13226 6580 13226 6580 13227 6581 13227 6598 13227 6580 13228 6598 13228 6568 13228 6591 13229 6582 13229 6561 13229 6588 13230 9019 13230 6585 13230 10564 13231 8308 13231 6589 13231 6589 13232 8308 13232 6583 13232 6589 13233 6583 13233 6584 13233 6584 13234 6583 13234 6586 13234 6584 13235 6586 13235 6585 13235 6585 13236 6586 13236 6587 13236 6585 13237 6587 13237 6588 13237 6588 13238 6587 13238 6619 13238 8300 13239 10564 13239 6567 13239 6567 13240 10564 13240 6589 13240 6567 13241 6589 13241 6590 13241 6590 13242 6589 13242 6584 13242 6590 13243 6584 13243 6561 13243 6561 13244 6584 13244 6585 13244 6561 13245 6585 13245 6591 13245 6591 13246 6585 13246 9019 13246 6596 13247 6592 13247 8271 13247 6614 13248 6593 13248 6607 13248 6607 13249 6593 13249 6594 13249 6607 13250 6594 13250 6606 13250 6606 13251 6594 13251 9487 13251 6606 13252 9487 13252 9504 13252 6608 13253 9598 13253 6607 13253 6607 13254 9598 13254 6595 13254 6607 13255 6595 13255 6614 13255 6614 13256 6595 13256 6611 13256 6611 13257 6595 13257 6610 13257 6610 13258 6595 13258 6604 13258 6610 13259 6604 13259 6643 13259 6596 13260 8271 13260 6597 13260 9488 13261 9487 13261 6581 13261 6581 13262 9487 13262 6594 13262 6581 13263 6594 13263 6598 13263 6598 13264 6594 13264 6599 13264 6598 13265 6599 13265 6568 13265 6609 13266 6597 13266 6612 13266 6612 13267 6597 13267 8271 13267 6612 13268 8271 13268 6613 13268 6613 13269 8271 13269 8272 13269 6613 13270 8272 13270 6615 13270 6615 13271 8272 13271 6600 13271 6615 13272 6600 13272 6616 13272 6616 13273 6600 13273 6601 13273 6616 13274 6601 13274 6602 13274 6602 13275 6601 13275 6603 13275 6602 13276 6603 13276 6617 13276 6641 13277 6604 13277 6605 13277 6605 13278 6604 13278 6595 13278 6605 13279 6595 13279 9554 13279 9554 13280 6595 13280 9598 13280 9504 13281 9502 13281 6606 13281 6606 13282 9502 13282 9588 13282 6606 13283 9588 13283 6607 13283 6607 13284 9588 13284 9486 13284 6607 13285 9486 13285 6608 13285 6643 13286 6609 13286 6610 13286 6610 13287 6609 13287 6612 13287 6610 13288 6612 13288 6611 13288 6611 13289 6612 13289 6613 13289 6611 13290 6613 13290 6614 13290 6614 13291 6613 13291 6615 13291 6614 13292 6615 13292 6593 13292 6593 13293 6615 13293 6616 13293 6593 13294 6616 13294 6594 13294 6594 13295 6616 13295 6602 13295 6594 13296 6602 13296 6599 13296 6599 13297 6602 13297 6617 13297 6599 13298 6617 13298 6568 13298 6568 13299 6617 13299 6618 13299 6619 13300 6587 13300 9079 13300 9079 13301 6587 13301 6623 13301 6697 13302 9016 13302 6620 13302 6623 13303 6621 13303 6622 13303 6700 13304 6699 13304 6622 13304 6622 13305 6699 13305 6697 13305 6622 13306 6697 13306 6623 13306 6623 13307 6697 13307 6620 13307 6623 13308 6620 13308 9079 13308 6621 13309 6623 13309 6629 13309 6629 13310 6623 13310 6587 13310 6629 13311 6587 13311 6586 13311 6583 13312 8308 13312 6630 13312 6630 13313 8308 13313 6624 13313 6630 13314 6624 13314 6625 13314 6626 13315 6701 13315 6627 13315 6627 13316 6701 13316 6631 13316 6627 13317 6631 13317 6628 13317 6628 13318 6631 13318 6625 13318 6628 13319 6625 13319 8310 13319 8310 13320 6625 13320 6624 13320 6586 13321 6583 13321 6629 13321 6629 13322 6583 13322 6630 13322 6629 13323 6630 13323 6621 13323 6621 13324 6630 13324 6625 13324 6621 13325 6625 13325 6622 13325 6622 13326 6625 13326 6631 13326 6622 13327 6631 13327 6700 13327 6700 13328 6631 13328 6701 13328 6654 13329 6653 13329 6636 13329 6636 13330 6653 13330 6632 13330 6636 13331 6632 13331 6649 13331 6649 13332 6632 13332 6633 13332 6633 13333 6632 13333 6647 13333 6633 13334 6647 13334 6718 13334 6639 13335 8278 13335 6640 13335 6634 13336 6655 13336 6636 13336 6636 13337 6655 13337 6635 13337 6636 13338 6635 13338 6654 13338 6725 13339 6637 13339 6648 13339 6648 13340 6637 13340 8276 13340 6648 13341 8276 13341 6638 13341 6638 13342 8276 13342 6639 13342 6638 13343 6639 13343 6650 13343 6650 13344 6639 13344 6640 13344 6641 13345 6642 13345 6604 13345 6604 13346 6642 13346 6652 13346 6604 13347 6652 13347 6643 13347 6643 13348 6652 13348 6644 13348 6643 13349 6644 13349 6609 13349 6609 13350 6644 13350 6645 13350 6609 13351 6645 13351 6597 13351 6597 13352 6645 13352 6656 13352 6597 13353 6656 13353 6596 13353 6596 13354 6656 13354 6646 13354 6596 13355 6646 13355 6592 13355 6592 13356 6646 13356 8280 13356 9505 13357 6647 13357 9506 13357 9506 13358 6647 13358 6632 13358 9506 13359 6632 13359 9507 13359 9507 13360 6632 13360 6653 13360 9507 13361 6653 13361 6651 13361 6718 13362 6725 13362 6633 13362 6633 13363 6725 13363 6648 13363 6633 13364 6648 13364 6649 13364 6649 13365 6648 13365 6638 13365 6649 13366 6638 13366 6636 13366 6636 13367 6638 13367 6650 13367 6636 13368 6650 13368 6634 13368 6634 13369 6650 13369 6640 13369 6641 13370 6651 13370 6642 13370 6642 13371 6651 13371 6653 13371 6642 13372 6653 13372 6652 13372 6652 13373 6653 13373 6654 13373 6652 13374 6654 13374 6644 13374 6644 13375 6654 13375 6635 13375 6644 13376 6635 13376 6645 13376 6645 13377 6635 13377 6655 13377 6645 13378 6655 13378 6656 13378 6656 13379 6655 13379 6634 13379 6656 13380 6634 13380 6646 13380 6646 13381 6634 13381 6640 13381 6646 13382 6640 13382 8280 13382 8280 13383 6640 13383 8278 13383 6702 13384 6657 13384 6704 13384 6658 13385 6685 13385 6659 13385 6667 13386 9017 13386 6698 13386 6660 13387 9012 13387 6671 13387 6671 13388 9012 13388 6661 13388 6671 13389 6661 13389 6662 13389 6662 13390 6661 13390 9014 13390 6662 13391 9014 13391 6663 13391 6663 13392 9014 13392 9015 13392 6663 13393 9015 13393 6664 13393 6664 13394 9015 13394 6666 13394 6664 13395 6666 13395 6665 13395 6665 13396 6666 13396 6667 13396 6665 13397 6667 13397 6676 13397 6676 13398 6678 13398 6665 13398 6665 13399 6678 13399 6668 13399 6665 13400 6668 13400 6664 13400 6664 13401 6668 13401 6669 13401 6664 13402 6669 13402 6663 13402 6663 13403 6669 13403 6670 13403 6663 13404 6670 13404 6662 13404 6662 13405 6670 13405 6709 13405 6662 13406 6709 13406 6671 13406 6671 13407 6709 13407 6710 13407 6671 13408 6710 13408 6660 13408 6660 13409 6710 13409 6712 13409 6657 13410 6658 13410 6704 13410 6704 13411 6658 13411 6659 13411 6704 13412 6659 13412 6705 13412 8302 13413 6673 13413 6672 13413 6672 13414 6673 13414 6674 13414 6672 13415 6674 13415 6675 13415 6667 13416 6698 13416 6676 13416 6676 13417 6698 13417 6677 13417 6676 13418 6677 13418 6678 13418 6678 13419 6677 13419 6679 13419 6678 13420 6679 13420 6703 13420 6626 13421 6675 13421 6701 13421 6701 13422 6675 13422 6674 13422 6701 13423 6674 13423 6679 13423 6679 13424 6674 13424 6673 13424 6679 13425 6673 13425 6703 13425 6695 13426 6681 13426 6680 13426 6680 13427 6681 13427 11401 13427 6680 13428 11401 13428 6682 13428 6688 13429 6683 13429 6695 13429 6695 13430 6683 13430 6684 13430 6695 13431 6684 13431 6681 13431 6685 13432 6686 13432 6659 13432 6659 13433 6686 13433 6687 13433 6659 13434 6687 13434 6688 13434 6688 13435 6687 13435 6689 13435 6688 13436 6689 13436 6683 13436 6732 13437 6711 13437 6690 13437 6732 13438 6690 13438 6691 13438 6691 13439 6690 13439 6692 13439 6691 13440 6692 13440 6696 13440 6696 13441 6692 13441 6708 13441 6696 13442 6708 13442 6694 13442 6694 13443 6708 13443 6707 13443 6694 13444 6707 13444 6693 13444 6693 13445 6707 13445 6706 13445 6693 13446 6706 13446 6705 13446 6705 13447 6659 13447 6693 13447 6693 13448 6659 13448 6688 13448 6693 13449 6688 13449 6694 13449 6694 13450 6688 13450 6695 13450 6694 13451 6695 13451 6696 13451 6696 13452 6695 13452 6680 13452 6696 13453 6680 13453 6691 13453 6691 13454 6680 13454 6682 13454 6691 13455 6682 13455 6732 13455 9017 13456 9016 13456 6698 13456 6698 13457 9016 13457 6697 13457 6698 13458 6697 13458 6677 13458 6677 13459 6697 13459 6699 13459 6677 13460 6699 13460 6679 13460 6679 13461 6699 13461 6700 13461 6679 13462 6700 13462 6701 13462 8302 13463 6702 13463 6673 13463 6673 13464 6702 13464 6704 13464 6673 13465 6704 13465 6703 13465 6703 13466 6704 13466 6705 13466 6703 13467 6705 13467 6678 13467 6678 13468 6705 13468 6706 13468 6678 13469 6706 13469 6668 13469 6668 13470 6706 13470 6707 13470 6668 13471 6707 13471 6669 13471 6669 13472 6707 13472 6708 13472 6669 13473 6708 13473 6670 13473 6670 13474 6708 13474 6692 13474 6670 13475 6692 13475 6709 13475 6709 13476 6692 13476 6690 13476 6709 13477 6690 13477 6710 13477 6710 13478 6690 13478 6711 13478 6710 13479 6711 13479 6712 13479 6723 13480 6713 13480 6721 13480 6721 13481 6713 13481 6714 13481 6721 13482 6714 13482 6719 13482 6719 13483 6714 13483 6739 13483 6715 13484 6735 13484 6720 13484 6720 13485 6735 13485 8281 13485 6720 13486 8281 13486 6722 13486 6722 13487 8281 13487 8283 13487 6722 13488 8283 13488 6724 13488 6724 13489 8283 13489 8284 13489 6724 13490 8284 13490 6725 13490 6725 13491 8284 13491 6637 13491 6717 13492 6738 13492 6714 13492 6714 13493 6738 13493 6716 13493 6714 13494 6716 13494 6739 13494 6717 13495 6714 13495 9505 13495 9505 13496 6714 13496 6713 13496 9505 13497 6713 13497 6647 13497 6647 13498 6713 13498 6723 13498 6647 13499 6723 13499 6718 13499 6739 13500 6715 13500 6719 13500 6719 13501 6715 13501 6720 13501 6719 13502 6720 13502 6721 13502 6721 13503 6720 13503 6722 13503 6721 13504 6722 13504 6723 13504 6723 13505 6722 13505 6724 13505 6723 13506 6724 13506 6718 13506 6718 13507 6724 13507 6725 13507 6731 13508 6734 13508 6743 13508 6730 13509 6728 13509 6727 13509 9012 13510 6727 13510 6726 13510 6726 13511 6727 13511 6728 13511 6726 13512 6728 13512 6729 13512 9012 13513 6660 13513 6727 13513 6727 13514 6660 13514 6731 13514 6727 13515 6731 13515 6730 13515 6730 13516 6731 13516 6743 13516 6660 13517 6712 13517 6731 13517 6731 13518 6712 13518 6711 13518 6731 13519 6711 13519 6734 13519 6734 13520 6711 13520 6732 13520 6734 13521 6732 13521 6682 13521 11403 13522 6743 13522 6733 13522 6733 13523 6743 13523 6734 13523 6733 13524 6734 13524 11402 13524 11402 13525 6734 13525 6682 13525 11402 13526 6682 13526 11401 13526 6736 13527 6735 13527 6715 13527 6736 13528 6715 13528 6737 13528 6738 13529 9508 13529 6716 13529 6716 13530 9508 13530 6740 13530 6716 13531 6740 13531 6739 13531 6739 13532 6740 13532 6741 13532 6739 13533 6741 13533 6715 13533 6715 13534 6741 13534 6744 13534 6715 13535 6744 13535 6737 13535 6742 13536 6737 13536 6744 13536 6740 13537 9508 13537 6729 13537 6743 13538 6741 13538 6730 13538 6730 13539 6741 13539 6740 13539 6730 13540 6740 13540 6728 13540 6728 13541 6740 13541 6729 13541 11403 13542 6742 13542 6743 13542 6743 13543 6742 13543 6744 13543 6743 13544 6744 13544 6741 13544 9336 13545 9335 13545 6749 13545 10542 13546 6745 13546 9336 13546 10542 13547 9336 13547 10541 13547 9336 13548 6749 13548 10541 13548 10541 13549 6749 13549 6746 13549 10541 13550 6746 13550 10543 13550 10543 13551 6746 13551 6747 13551 10543 13552 6747 13552 10544 13552 6748 13553 10545 13553 10544 13553 10544 13554 6747 13554 6748 13554 6748 13555 6747 13555 6775 13555 6748 13556 6775 13556 6773 13556 9335 13557 9334 13557 6749 13557 6749 13558 9334 13558 6758 13558 6749 13559 6758 13559 6746 13559 6746 13560 6758 13560 6792 13560 6746 13561 6792 13561 6747 13561 6747 13562 6792 13562 6776 13562 6747 13563 6776 13563 6775 13563 6800 13564 6802 13564 6785 13564 6785 13565 6802 13565 6750 13565 6785 13566 6750 13566 6751 13566 6751 13567 6750 13567 6753 13567 6751 13568 6753 13568 6752 13568 6752 13569 6753 13569 6788 13569 6752 13570 6788 13570 6754 13570 6754 13571 6788 13571 6789 13571 6754 13572 6789 13572 6755 13572 6755 13573 6789 13573 6756 13573 6755 13574 6756 13574 6781 13574 6781 13575 6756 13575 6790 13575 6781 13576 6790 13576 6757 13576 6757 13577 6790 13577 6759 13577 6757 13578 6759 13578 6758 13578 6758 13579 6759 13579 6792 13579 6761 13580 8493 13580 6760 13580 6761 13581 6760 13581 6778 13581 6766 13582 6762 13582 8491 13582 8493 13583 6761 13583 8492 13583 8492 13584 6761 13584 6787 13584 8492 13585 6787 13585 8491 13585 6762 13586 6766 13586 6764 13586 6764 13587 6766 13587 6763 13587 6764 13588 6763 13588 8490 13588 8490 13589 6763 13589 6765 13589 8490 13590 6765 13590 6806 13590 8491 13591 6787 13591 6766 13591 6766 13592 6787 13592 6786 13592 6766 13593 6786 13593 6763 13593 6763 13594 6786 13594 6767 13594 6763 13595 6767 13595 6765 13595 6768 13596 6769 13596 6791 13596 6791 13597 6769 13597 8495 13597 8495 13598 6770 13598 6771 13598 6771 13599 6770 13599 8497 13599 6771 13600 8497 13600 6772 13600 6772 13601 8497 13601 6773 13601 6772 13602 6773 13602 6775 13602 8495 13603 6771 13603 6791 13603 6791 13604 6771 13604 6772 13604 6791 13605 6772 13605 6774 13605 6774 13606 6772 13606 6775 13606 6774 13607 6775 13607 6776 13607 6760 13608 6777 13608 6778 13608 6778 13609 6777 13609 6779 13609 6778 13610 6779 13610 6768 13610 6768 13611 6779 13611 6780 13611 6768 13612 6780 13612 6769 13612 6758 13613 9334 13613 6757 13613 6757 13614 9334 13614 9331 13614 6757 13615 9331 13615 6781 13615 6781 13616 9331 13616 9330 13616 6781 13617 9330 13617 6755 13617 6755 13618 9330 13618 6782 13618 6755 13619 6782 13619 6754 13619 6754 13620 6782 13620 9328 13620 6754 13621 9328 13621 6752 13621 6752 13622 9328 13622 6783 13622 6752 13623 6783 13623 6751 13623 6751 13624 6783 13624 6784 13624 6751 13625 6784 13625 6785 13625 6785 13626 6784 13626 9447 13626 6785 13627 9447 13627 6800 13627 6802 13628 6767 13628 6750 13628 6750 13629 6767 13629 6786 13629 6750 13630 6786 13630 6753 13630 6753 13631 6786 13631 6787 13631 6753 13632 6787 13632 6788 13632 6788 13633 6787 13633 6761 13633 6788 13634 6761 13634 6789 13634 6789 13635 6761 13635 6778 13635 6789 13636 6778 13636 6756 13636 6756 13637 6778 13637 6768 13637 6756 13638 6768 13638 6790 13638 6790 13639 6768 13639 6791 13639 6790 13640 6791 13640 6759 13640 6759 13641 6791 13641 6774 13641 6759 13642 6774 13642 6792 13642 6792 13643 6774 13643 6776 13643 6793 13644 6805 13644 6794 13644 6794 13645 6805 13645 6804 13645 6794 13646 6804 13646 6795 13646 6795 13647 6804 13647 6803 13647 6795 13648 6803 13648 6796 13648 6796 13649 6803 13649 6797 13649 6797 13650 6803 13650 6798 13650 6797 13651 6798 13651 6799 13651 6799 13652 6798 13652 6801 13652 6799 13653 6801 13653 9379 13653 9447 13654 6801 13654 6800 13654 6800 13655 6801 13655 6798 13655 6800 13656 6798 13656 6802 13656 6802 13657 6798 13657 6803 13657 6802 13658 6803 13658 6767 13658 6767 13659 6803 13659 6804 13659 6767 13660 6804 13660 6765 13660 6765 13661 6804 13661 6805 13661 6765 13662 6805 13662 6806 13662 9027 13663 6844 13663 6843 13663 9023 13664 9026 13664 6807 13664 6807 13665 9026 13665 6812 13665 6807 13666 6812 13666 8518 13666 8518 13667 6812 13667 8517 13667 8517 13668 6812 13668 6809 13668 8517 13669 6809 13669 6808 13669 6808 13670 6809 13670 6811 13670 6808 13671 6811 13671 6810 13671 8533 13672 8534 13672 6810 13672 6810 13673 6811 13673 8533 13673 8533 13674 6811 13674 6834 13674 8533 13675 6834 13675 8543 13675 9026 13676 9027 13676 6812 13676 6812 13677 9027 13677 6843 13677 6812 13678 6843 13678 6809 13678 6809 13679 6843 13679 6813 13679 6809 13680 6813 13680 6811 13680 6811 13681 6813 13681 6814 13681 6811 13682 6814 13682 6834 13682 6815 13683 6816 13683 6818 13683 6818 13684 6816 13684 6817 13684 6818 13685 6817 13685 6849 13685 6849 13686 6817 13686 6819 13686 6849 13687 6819 13687 6821 13687 6821 13688 6819 13688 6820 13688 6821 13689 6820 13689 6822 13689 6822 13690 6820 13690 6854 13690 6822 13691 6854 13691 6847 13691 6847 13692 6854 13692 6823 13692 6847 13693 6823 13693 6846 13693 6846 13694 6823 13694 6855 13694 6846 13695 6855 13695 6824 13695 6824 13696 6855 13696 6859 13696 6824 13697 6859 13697 6843 13697 6843 13698 6859 13698 6813 13698 6826 13699 6841 13699 6830 13699 8536 13700 8537 13700 6831 13700 6831 13701 8537 13701 8539 13701 6831 13702 8539 13702 6830 13702 6830 13703 8539 13703 6825 13703 6830 13704 6825 13704 6826 13704 8536 13705 6831 13705 6828 13705 6828 13706 6831 13706 6827 13706 6828 13707 6827 13707 8535 13707 8535 13708 6827 13708 6869 13708 8535 13709 6869 13709 6829 13709 6841 13710 6853 13710 6830 13710 6830 13711 6853 13711 6832 13711 6830 13712 6832 13712 6831 13712 6831 13713 6832 13713 6852 13713 6831 13714 6852 13714 6827 13714 6827 13715 6852 13715 6833 13715 6827 13716 6833 13716 6869 13716 8543 13717 6834 13717 6839 13717 6839 13718 6834 13718 6835 13718 8541 13719 6857 13719 6836 13719 6836 13720 6857 13720 6856 13720 8541 13721 8546 13721 6840 13721 6840 13722 8546 13722 6837 13722 6840 13723 6837 13723 6835 13723 6835 13724 6837 13724 6838 13724 6835 13725 6838 13725 6839 13725 8541 13726 6840 13726 6857 13726 6857 13727 6840 13727 6835 13727 6857 13728 6835 13728 6858 13728 6858 13729 6835 13729 6834 13729 6858 13730 6834 13730 6814 13730 6826 13731 8540 13731 6841 13731 6841 13732 8540 13732 6842 13732 6841 13733 6842 13733 6856 13733 6856 13734 6842 13734 8542 13734 6856 13735 8542 13735 6836 13735 6843 13736 6844 13736 6824 13736 6824 13737 6844 13737 6845 13737 6824 13738 6845 13738 6846 13738 6846 13739 6845 13739 9035 13739 6846 13740 9035 13740 6847 13740 6847 13741 9035 13741 9034 13741 6847 13742 9034 13742 6822 13742 6822 13743 9034 13743 6848 13743 6822 13744 6848 13744 6821 13744 6821 13745 6848 13745 9085 13745 6821 13746 9085 13746 6849 13746 6849 13747 9085 13747 9040 13747 6849 13748 9040 13748 6818 13748 6818 13749 9040 13749 6850 13749 6818 13750 6850 13750 6815 13750 6815 13751 6850 13751 6851 13751 6815 13752 6851 13752 6867 13752 6816 13753 6833 13753 6817 13753 6817 13754 6833 13754 6852 13754 6817 13755 6852 13755 6819 13755 6819 13756 6852 13756 6832 13756 6819 13757 6832 13757 6820 13757 6820 13758 6832 13758 6853 13758 6820 13759 6853 13759 6854 13759 6854 13760 6853 13760 6841 13760 6854 13761 6841 13761 6823 13761 6823 13762 6841 13762 6856 13762 6823 13763 6856 13763 6855 13763 6855 13764 6856 13764 6857 13764 6855 13765 6857 13765 6859 13765 6859 13766 6857 13766 6858 13766 6859 13767 6858 13767 6813 13767 6813 13768 6858 13768 6814 13768 8532 13769 6860 13769 8524 13769 8524 13770 6860 13770 6870 13770 8524 13771 6870 13771 6861 13771 6861 13772 6870 13772 6862 13772 6862 13773 6870 13773 6868 13773 6862 13774 6868 13774 6863 13774 6863 13775 6868 13775 6864 13775 6863 13776 6864 13776 6865 13776 6865 13777 6864 13777 6866 13777 6865 13778 6866 13778 8515 13778 6867 13779 6866 13779 6815 13779 6815 13780 6866 13780 6864 13780 6815 13781 6864 13781 6816 13781 6816 13782 6864 13782 6868 13782 6816 13783 6868 13783 6833 13783 6833 13784 6868 13784 6870 13784 6833 13785 6870 13785 6869 13785 6869 13786 6870 13786 6860 13786 6869 13787 6860 13787 6829 13787 6880 13788 8973 13788 6871 13788 6872 13789 8503 13789 10509 13789 6875 13790 10507 13790 6873 13790 6873 13791 10507 13791 10500 13791 6873 13792 10500 13792 6880 13792 6880 13793 10500 13793 10501 13793 6880 13794 10501 13794 8973 13794 6874 13795 6872 13795 6875 13795 6875 13796 6872 13796 10509 13796 6875 13797 10509 13797 10507 13797 8509 13798 6874 13798 6883 13798 6883 13799 6874 13799 6879 13799 6883 13800 6879 13800 6884 13800 6884 13801 6879 13801 6876 13801 6884 13802 6876 13802 6877 13802 6877 13803 6876 13803 6878 13803 6877 13804 6878 13804 6881 13804 6874 13805 6875 13805 6879 13805 6879 13806 6875 13806 6873 13806 6879 13807 6873 13807 6876 13807 6876 13808 6873 13808 6880 13808 6876 13809 6880 13809 6878 13809 6878 13810 6880 13810 6871 13810 6878 13811 6871 13811 6881 13811 8510 13812 8509 13812 6882 13812 6882 13813 8509 13813 6883 13813 6882 13814 6883 13814 6894 13814 6894 13815 6883 13815 6884 13815 6894 13816 6884 13816 6887 13816 6887 13817 6884 13817 6877 13817 6887 13818 6877 13818 9533 13818 9533 13819 6877 13819 6881 13819 6885 13820 6882 13820 6894 13820 9538 13821 6886 13821 6904 13821 9538 13822 6893 13822 9539 13822 9539 13823 6893 13823 9540 13823 6886 13824 9537 13824 6904 13824 6904 13825 9537 13825 9536 13825 6904 13826 9536 13826 8969 13826 6887 13827 9533 13827 9532 13827 9532 13828 9531 13828 6887 13828 6887 13829 9531 13829 9546 13829 6887 13830 9546 13830 9545 13830 9545 13831 9544 13831 6887 13831 6887 13832 9544 13832 9543 13832 6887 13833 9543 13833 6888 13833 9542 13834 6889 13834 6893 13834 6893 13835 6889 13835 9541 13835 6893 13836 9541 13836 9540 13836 6885 13837 8512 13837 6882 13837 6882 13838 8512 13838 8511 13838 6882 13839 8511 13839 8510 13839 6891 13840 8514 13840 6890 13840 9538 13841 6904 13841 6893 13841 6893 13842 6904 13842 6908 13842 6893 13843 6908 13843 6895 13843 6895 13844 6908 13844 6891 13844 6895 13845 6891 13845 6896 13845 6896 13846 6891 13846 6890 13846 6896 13847 6890 13847 6892 13847 6888 13848 9542 13848 6887 13848 6887 13849 9542 13849 6893 13849 6887 13850 6893 13850 6894 13850 6894 13851 6893 13851 6895 13851 6894 13852 6895 13852 6885 13852 6885 13853 6895 13853 6896 13853 6885 13854 6896 13854 8512 13854 8512 13855 6896 13855 6892 13855 6897 13856 6928 13856 6898 13856 6897 13857 6898 13857 6899 13857 6899 13858 6898 13858 6901 13858 6899 13859 6901 13859 6900 13859 6900 13860 6901 13860 6905 13860 6900 13861 6905 13861 8972 13861 8972 13862 6905 13862 6904 13862 8972 13863 6904 13863 8969 13863 8514 13864 6891 13864 8507 13864 8507 13865 6891 13865 6902 13865 8507 13866 6902 13866 8508 13866 8508 13867 6902 13867 6919 13867 8508 13868 6919 13868 6903 13868 6908 13869 6904 13869 6909 13869 6909 13870 6904 13870 6905 13870 6909 13871 6905 13871 6906 13871 6906 13872 6905 13872 6901 13872 6906 13873 6901 13873 6907 13873 6907 13874 6901 13874 6898 13874 6907 13875 6898 13875 6911 13875 6911 13876 6898 13876 6928 13876 6911 13877 6928 13877 6927 13877 6891 13878 6908 13878 6902 13878 6902 13879 6908 13879 6909 13879 6902 13880 6909 13880 6919 13880 6919 13881 6909 13881 6906 13881 6919 13882 6906 13882 6917 13882 6917 13883 6906 13883 6907 13883 6917 13884 6907 13884 6910 13884 6910 13885 6907 13885 6911 13885 6910 13886 6911 13886 6915 13886 6915 13887 6911 13887 6927 13887 6915 13888 6927 13888 6912 13888 6925 13889 6913 13889 6912 13889 6912 13890 6913 13890 6914 13890 6912 13891 6914 13891 6915 13891 6915 13892 6914 13892 6916 13892 6915 13893 6916 13893 6910 13893 6910 13894 6916 13894 6918 13894 6910 13895 6918 13895 6917 13895 6917 13896 6918 13896 8506 13896 6917 13897 8506 13897 6919 13897 6919 13898 8506 13898 6920 13898 6919 13899 6920 13899 6903 13899 8965 13900 6921 13900 6924 13900 6924 13901 6921 13901 6922 13901 6924 13902 6922 13902 6931 13902 8971 13903 8965 13903 6929 13903 6929 13904 8965 13904 6924 13904 6929 13905 6924 13905 6923 13905 6923 13906 6924 13906 6931 13906 6923 13907 6931 13907 6926 13907 8504 13908 6925 13908 6926 13908 6926 13909 6925 13909 6912 13909 6926 13910 6912 13910 6923 13910 6923 13911 6912 13911 6927 13911 6923 13912 6927 13912 6929 13912 6929 13913 6927 13913 6928 13913 6929 13914 6928 13914 8971 13914 8971 13915 6928 13915 6897 13915 6939 13916 8504 13916 6930 13916 6930 13917 8504 13917 6926 13917 6930 13918 6926 13918 6938 13918 6938 13919 6926 13919 6931 13919 6938 13920 6931 13920 6932 13920 6932 13921 6931 13921 6922 13921 6932 13922 6922 13922 6933 13922 6933 13923 6922 13923 6921 13923 6935 13924 8502 13924 8501 13924 10520 13925 8502 13925 6934 13925 6934 13926 8502 13926 6935 13926 6934 13927 6935 13927 10521 13927 10521 13928 6935 13928 6936 13928 6936 13929 6935 13929 6943 13929 6936 13930 6943 13930 10505 13930 10505 13931 6943 13931 6937 13931 10505 13932 6937 13932 6941 13932 6932 13933 6942 13933 6938 13933 6938 13934 6942 13934 6944 13934 6938 13935 6944 13935 6930 13935 6930 13936 6944 13936 6945 13936 6930 13937 6945 13937 6939 13937 9031 13938 6942 13938 6940 13938 6940 13939 6942 13939 6932 13939 6940 13940 6932 13940 6933 13940 9032 13941 6941 13941 9031 13941 9031 13942 6941 13942 6937 13942 9031 13943 6937 13943 6942 13943 6942 13944 6937 13944 6943 13944 6942 13945 6943 13945 6944 13945 6944 13946 6943 13946 6935 13946 6944 13947 6935 13947 6945 13947 6945 13948 6935 13948 8501 13948 6945 13949 8501 13949 6939 13949 6949 13950 6950 13950 6961 13950 6946 13951 8590 13951 6947 13951 6954 13952 8576 13952 6948 13952 6948 13953 8576 13953 8577 13953 6948 13954 8577 13954 6949 13954 6949 13955 8577 13955 6951 13955 6949 13956 6951 13956 6950 13956 6950 13957 6951 13957 6952 13957 6953 13958 6946 13958 6954 13958 6954 13959 6946 13959 6947 13959 6954 13960 6947 13960 8576 13960 8591 13961 6953 13961 6963 13961 6963 13962 6953 13962 6955 13962 6963 13963 6955 13963 6956 13963 6956 13964 6955 13964 6957 13964 6957 13965 6955 13965 6958 13965 6957 13966 6958 13966 6959 13966 6959 13967 6958 13967 6960 13967 6959 13968 6960 13968 6962 13968 6953 13969 6954 13969 6955 13969 6955 13970 6954 13970 6948 13970 6955 13971 6948 13971 6958 13971 6958 13972 6948 13972 6949 13972 6958 13973 6949 13973 6960 13973 6960 13974 6949 13974 6961 13974 6960 13975 6961 13975 6962 13975 6963 13976 6956 13976 7004 13976 10734 13977 10738 13977 6972 13977 6957 13978 6959 13978 6964 13978 6964 13979 6959 13979 6966 13979 6964 13980 6966 13980 6965 13980 6965 13981 6966 13981 6986 13981 6965 13982 6986 13982 6967 13982 6967 13983 6986 13983 6988 13983 6967 13984 6988 13984 7002 13984 7002 13985 6988 13985 6990 13985 7002 13986 6990 13986 7000 13986 7000 13987 6990 13987 6991 13987 7000 13988 6991 13988 6999 13988 6999 13989 6991 13989 6968 13989 6999 13990 6968 13990 6969 13990 6969 13991 6968 13991 6970 13991 6969 13992 6970 13992 6996 13992 6972 13993 6973 13993 10734 13993 10734 13994 6973 13994 7015 13994 10734 13995 7015 13995 7013 13995 6971 13996 6981 13996 10738 13996 10738 13997 6981 13997 7001 13997 10738 13998 7001 13998 6972 13998 6972 13999 7001 13999 6998 13999 6972 14000 6998 14000 6973 14000 6973 14001 6998 14001 6997 14001 6973 14002 6997 14002 7015 14002 8591 14003 6963 14003 6982 14003 8591 14004 6982 14004 6974 14004 6974 14005 6982 14005 6975 14005 6974 14006 6975 14006 10733 14006 10733 14007 6975 14007 6977 14007 6977 14008 6975 14008 6976 14008 6977 14009 6976 14009 6978 14009 6984 14010 7003 14010 6979 14010 6971 14011 6980 14011 6981 14011 6981 14012 6980 14012 10736 14012 6981 14013 10736 14013 6979 14013 6979 14014 10736 14014 10731 14014 6979 14015 10731 14015 6984 14015 6963 14016 7004 14016 6982 14016 6982 14017 7004 14017 6983 14017 6982 14018 6983 14018 6975 14018 6975 14019 6983 14019 7003 14019 6975 14020 7003 14020 6976 14020 6976 14021 7003 14021 6984 14021 6976 14022 6984 14022 6978 14022 6996 14023 6970 14023 6985 14023 6985 14024 6970 14024 6995 14024 6985 14025 6995 14025 9008 14025 6959 14026 6962 14026 6966 14026 6966 14027 6962 14027 9058 14027 6966 14028 9058 14028 6986 14028 6986 14029 9058 14029 6987 14029 6986 14030 6987 14030 6988 14030 6988 14031 6987 14031 6989 14031 6988 14032 6989 14032 6990 14032 6990 14033 6989 14033 9011 14033 6990 14034 9011 14034 6991 14034 6991 14035 9011 14035 6992 14035 6991 14036 6992 14036 6968 14036 6968 14037 6992 14037 6993 14037 6968 14038 6993 14038 6970 14038 6970 14039 6993 14039 6994 14039 6970 14040 6994 14040 6995 14040 6996 14041 6997 14041 6969 14041 6969 14042 6997 14042 6998 14042 6969 14043 6998 14043 6999 14043 6999 14044 6998 14044 7001 14044 6999 14045 7001 14045 7000 14045 7000 14046 7001 14046 6981 14046 7000 14047 6981 14047 7002 14047 7002 14048 6981 14048 6979 14048 7002 14049 6979 14049 6967 14049 6967 14050 6979 14050 7003 14050 6967 14051 7003 14051 6965 14051 6965 14052 7003 14052 6983 14052 6965 14053 6983 14053 6964 14053 6964 14054 6983 14054 7004 14054 6964 14055 7004 14055 6957 14055 6957 14056 7004 14056 6956 14056 7018 14057 8574 14057 7005 14057 7005 14058 8574 14058 7006 14058 7014 14059 7016 14059 8588 14059 8588 14060 7016 14060 7005 14060 8588 14061 7005 14061 8589 14061 8589 14062 7005 14062 7006 14062 8589 14063 7006 14063 8579 14063 6996 14064 6985 14064 7009 14064 8573 14065 7012 14065 9006 14065 9006 14066 7012 14066 7011 14066 9006 14067 7011 14067 7007 14067 7007 14068 7011 14068 7009 14068 7007 14069 7009 14069 7008 14069 7008 14070 7009 14070 6985 14070 7008 14071 6985 14071 9008 14071 6997 14072 6996 14072 7017 14072 7017 14073 6996 14073 7009 14073 7017 14074 7009 14074 7010 14074 7010 14075 7009 14075 7011 14075 7010 14076 7011 14076 7019 14076 7019 14077 7011 14077 7012 14077 7013 14078 7015 14078 7014 14078 7014 14079 7015 14079 6997 14079 7014 14080 6997 14080 7016 14080 7016 14081 6997 14081 7017 14081 7016 14082 7017 14082 7005 14082 7005 14083 7017 14083 7010 14083 7005 14084 7010 14084 7018 14084 7018 14085 7010 14085 7019 14085 7029 14086 7020 14086 7031 14086 7027 14087 7021 14087 7028 14087 7030 14088 7022 14088 7027 14088 7022 14089 7030 14089 7023 14089 7023 14090 7030 14090 7032 14090 7023 14091 7032 14091 10489 14091 10489 14092 7032 14092 7024 14092 10489 14093 7024 14093 7025 14093 7026 14094 10492 14094 7025 14094 7025 14095 7024 14095 7026 14095 7026 14096 7024 14096 7064 14096 7026 14097 7064 14097 10744 14097 9049 14098 7020 14098 9046 14098 9046 14099 7020 14099 7029 14099 9046 14100 7029 14100 7028 14100 7027 14101 7028 14101 7030 14101 7030 14102 7028 14102 7029 14102 7030 14103 7029 14103 7032 14103 7032 14104 7029 14104 7031 14104 7032 14105 7031 14105 7024 14105 7024 14106 7031 14106 7065 14106 7024 14107 7065 14107 7064 14107 10745 14108 10744 14108 7064 14108 10745 14109 7064 14109 7033 14109 7064 14110 7063 14110 7033 14110 7033 14111 7063 14111 7034 14111 7033 14112 7034 14112 10742 14112 7035 14113 7036 14113 7037 14113 7037 14114 7036 14114 7038 14114 7037 14115 7038 14115 7034 14115 7034 14116 7038 14116 10740 14116 7034 14117 10740 14117 10742 14117 7020 14118 9049 14118 7040 14118 7040 14119 9049 14119 7039 14119 7040 14120 7039 14120 7043 14120 7039 14121 7041 14121 7043 14121 7043 14122 7041 14122 7042 14122 7043 14123 7042 14123 7051 14123 7051 14124 7042 14124 9065 14124 7051 14125 9065 14125 7044 14125 7044 14126 9065 14126 7045 14126 7044 14127 7045 14127 7046 14127 7046 14128 7045 14128 9055 14128 7046 14129 9055 14129 7049 14129 7066 14130 7081 14130 7047 14130 7047 14131 7081 14131 7069 14131 7047 14132 7069 14132 7049 14132 7049 14133 7069 14133 7048 14133 7049 14134 7048 14134 7046 14134 7046 14135 7048 14135 7050 14135 7046 14136 7050 14136 7044 14136 7044 14137 7050 14137 7070 14137 7044 14138 7070 14138 7051 14138 7051 14139 7070 14139 7052 14139 7051 14140 7052 14140 7043 14140 7043 14141 7052 14141 7071 14141 7043 14142 7071 14142 7040 14142 7040 14143 7071 14143 7072 14143 7040 14144 7072 14144 7020 14144 7020 14145 7072 14145 7031 14145 10748 14146 7061 14146 10749 14146 10749 14147 7061 14147 7055 14147 10749 14148 7055 14148 7053 14148 7056 14149 7058 14149 7059 14149 7056 14150 7059 14150 7054 14150 7054 14151 7059 14151 7082 14151 7054 14152 7082 14152 8569 14152 7053 14153 7055 14153 7056 14153 7056 14154 7055 14154 7057 14154 7056 14155 7057 14155 7058 14155 7058 14156 7057 14156 7068 14156 7058 14157 7068 14157 7059 14157 7059 14158 7068 14158 7060 14158 7059 14159 7060 14159 7082 14159 10748 14160 7035 14160 7061 14160 7061 14161 7035 14161 7037 14161 7061 14162 7037 14162 7062 14162 7062 14163 7037 14163 7034 14163 7062 14164 7034 14164 7073 14164 7073 14165 7034 14165 7063 14165 7073 14166 7063 14166 7074 14166 7074 14167 7063 14167 7064 14167 7074 14168 7064 14168 7065 14168 7084 14169 7066 14169 9052 14169 9052 14170 7066 14170 7047 14170 9052 14171 7047 14171 7067 14171 7067 14172 7047 14172 7049 14172 7067 14173 7049 14173 9053 14173 9053 14174 7049 14174 9055 14174 7081 14175 7060 14175 7069 14175 7069 14176 7060 14176 7068 14176 7069 14177 7068 14177 7048 14177 7048 14178 7068 14178 7057 14178 7048 14179 7057 14179 7050 14179 7050 14180 7057 14180 7055 14180 7050 14181 7055 14181 7070 14181 7070 14182 7055 14182 7061 14182 7070 14183 7061 14183 7052 14183 7052 14184 7061 14184 7062 14184 7052 14185 7062 14185 7071 14185 7071 14186 7062 14186 7073 14186 7071 14187 7073 14187 7072 14187 7072 14188 7073 14188 7074 14188 7072 14189 7074 14189 7031 14189 7031 14190 7074 14190 7065 14190 7076 14191 8570 14191 7085 14191 7075 14192 8570 14192 10491 14192 10491 14193 8570 14193 7076 14193 10491 14194 7076 14194 10487 14194 10487 14195 7076 14195 10488 14195 10488 14196 7076 14196 7077 14196 10488 14197 7077 14197 7078 14197 7078 14198 7077 14198 7089 14198 7078 14199 7089 14199 7079 14199 7079 14200 7089 14200 9045 14200 7079 14201 9045 14201 7080 14201 7066 14202 7088 14202 7081 14202 7081 14203 7088 14203 7087 14203 7081 14204 7087 14204 7060 14204 7060 14205 7087 14205 7086 14205 7060 14206 7086 14206 7082 14206 7083 14207 7088 14207 9056 14207 9056 14208 7088 14208 7066 14208 9056 14209 7066 14209 7084 14209 8569 14210 7082 14210 7085 14210 7085 14211 7082 14211 7086 14211 7085 14212 7086 14212 7076 14212 7076 14213 7086 14213 7087 14213 7076 14214 7087 14214 7077 14214 7077 14215 7087 14215 7088 14215 7077 14216 7088 14216 7089 14216 7089 14217 7088 14217 7083 14217 7089 14218 7083 14218 9045 14218 10752 14219 7101 14219 7102 14219 7091 14220 7090 14220 7111 14220 7091 14221 7111 14221 9126 14221 8567 14222 8566 14222 7099 14222 7099 14223 8566 14223 7093 14223 8564 14224 7105 14224 8565 14224 8565 14225 7105 14225 7092 14225 8565 14226 7092 14226 7093 14226 7093 14227 7092 14227 7103 14227 7093 14228 7103 14228 7099 14228 7098 14229 8568 14229 8567 14229 7094 14230 8568 14230 10754 14230 10754 14231 8568 14231 7098 14231 10754 14232 7098 14232 7095 14232 7095 14233 7098 14233 7096 14233 7095 14234 7096 14234 10755 14234 7120 14235 10752 14235 7118 14235 7118 14236 10752 14236 7102 14236 7118 14237 7102 14237 7128 14237 7128 14238 7102 14238 7097 14238 7128 14239 7097 14239 7111 14239 7111 14240 7097 14240 7104 14240 7111 14241 7104 14241 9126 14241 9126 14242 7104 14242 7106 14242 10750 14243 7100 14243 7103 14243 8567 14244 7099 14244 7098 14244 7098 14245 7099 14245 7103 14245 7098 14246 7103 14246 7096 14246 7096 14247 7103 14247 7100 14247 7096 14248 7100 14248 10755 14248 7101 14249 10750 14249 7102 14249 7102 14250 10750 14250 7103 14250 7102 14251 7103 14251 7097 14251 7097 14252 7103 14252 7092 14252 7097 14253 7092 14253 7104 14253 7104 14254 7092 14254 7105 14254 7104 14255 7105 14255 7106 14255 7106 14256 7105 14256 8564 14256 7112 14257 7114 14257 7123 14257 7107 14258 7109 14258 7110 14258 9003 14259 9001 14259 7122 14259 7122 14260 9001 14260 7134 14260 7122 14261 7134 14261 7133 14261 7107 14262 7110 14262 8999 14262 8999 14263 7110 14263 7111 14263 8999 14264 7111 14264 7090 14264 7117 14265 7108 14265 7119 14265 7108 14266 7117 14266 10762 14266 10762 14267 7117 14267 7115 14267 10762 14268 7115 14268 7113 14268 7124 14269 7125 14269 7109 14269 7109 14270 7125 14270 7126 14270 7109 14271 7126 14271 7110 14271 7110 14272 7126 14272 7128 14272 7110 14273 7128 14273 7111 14273 7112 14274 7113 14274 7114 14274 7114 14275 7113 14275 7115 14275 7114 14276 7115 14276 7116 14276 7116 14277 7115 14277 7117 14277 7116 14278 7117 14278 7127 14278 7127 14279 7117 14279 7119 14279 7127 14280 7119 14280 7118 14280 7118 14281 7119 14281 7120 14281 10757 14282 10759 14282 7132 14282 7132 14283 10759 14283 7121 14283 7132 14284 7121 14284 7133 14284 7133 14285 7121 14285 7124 14285 7133 14286 7124 14286 7122 14286 7122 14287 7124 14287 7109 14287 7122 14288 7109 14288 9003 14288 9003 14289 7109 14289 7107 14289 10759 14290 7112 14290 7121 14290 7121 14291 7112 14291 7123 14291 7121 14292 7123 14292 7124 14292 7124 14293 7123 14293 7114 14293 7124 14294 7114 14294 7125 14294 7125 14295 7114 14295 7116 14295 7125 14296 7116 14296 7126 14296 7126 14297 7116 14297 7127 14297 7126 14298 7127 14298 7128 14298 7128 14299 7127 14299 7118 14299 7130 14300 10757 14300 7132 14300 7129 14301 8563 14301 7130 14301 7134 14302 9001 14302 9000 14302 7129 14303 7130 14303 7131 14303 7131 14304 7130 14304 7132 14304 7131 14305 7132 14305 10465 14305 10465 14306 7132 14306 7133 14306 10465 14307 7133 14307 7135 14307 7135 14308 7133 14308 7134 14308 7135 14309 7134 14309 10466 14309 10466 14310 7134 14310 9000 14310 10466 14311 9000 14311 9005 14311 11707 14312 7142 14312 7136 14312 7136 14313 7142 14313 7137 14313 7136 14314 7137 14314 11703 14314 11703 14315 7137 14315 7144 14315 11703 14316 7144 14316 11702 14316 11702 14317 7144 14317 7138 14317 11702 14318 7138 14318 8500 14318 8499 14319 7148 14319 7139 14319 7139 14320 7148 14320 7162 14320 7139 14321 7162 14321 7165 14321 7141 14322 7142 14322 7140 14322 7140 14323 7142 14323 11707 14323 7140 14324 11707 14324 11706 14324 7141 14325 7146 14325 7142 14325 7142 14326 7146 14326 7143 14326 7142 14327 7143 14327 7137 14327 7137 14328 7143 14328 7148 14328 7137 14329 7148 14329 7144 14329 7144 14330 7148 14330 8499 14330 7144 14331 8499 14331 7138 14331 7141 14332 7145 14332 7146 14332 7146 14333 7145 14333 7156 14333 7146 14334 7156 14334 7143 14334 7143 14335 7156 14335 7147 14335 7143 14336 7147 14336 7148 14336 7148 14337 7147 14337 7161 14337 7148 14338 7161 14338 7162 14338 7164 14339 7163 14339 7169 14339 7149 14340 7168 14340 7150 14340 7151 14341 7181 14341 7152 14341 7151 14342 7152 14342 9480 14342 9480 14343 7152 14343 7157 14343 9480 14344 7157 14344 7153 14344 7154 14345 9478 14345 7153 14345 7158 14346 7180 14346 7155 14346 7145 14347 9478 14347 7156 14347 7156 14348 9478 14348 7154 14348 7156 14349 7154 14349 7147 14349 7153 14350 7157 14350 7154 14350 7154 14351 7157 14351 7170 14351 7154 14352 7170 14352 7147 14352 7181 14353 7180 14353 7152 14353 7152 14354 7180 14354 7158 14354 7152 14355 7158 14355 7157 14355 7157 14356 7158 14356 7159 14356 7157 14357 7159 14357 7170 14357 10764 14358 10767 14358 7167 14358 7167 14359 10767 14359 7160 14359 7161 14360 7163 14360 7162 14360 7162 14361 7163 14361 7164 14361 7162 14362 7164 14362 7165 14362 7150 14363 7166 14363 7149 14363 7149 14364 7166 14364 10764 14364 7149 14365 10764 14365 7169 14365 7169 14366 10764 14366 7167 14366 7169 14367 7167 14367 7164 14367 7164 14368 7167 14368 7160 14368 7164 14369 7160 14369 7165 14369 10765 14370 7150 14370 7155 14370 7155 14371 7150 14371 7168 14371 7155 14372 7168 14372 7158 14372 7158 14373 7168 14373 7149 14373 7158 14374 7149 14374 7159 14374 7159 14375 7149 14375 7169 14375 7159 14376 7169 14376 7170 14376 7170 14377 7169 14377 7163 14377 7170 14378 7163 14378 7147 14378 7147 14379 7163 14379 7161 14379 7183 14380 7213 14380 7171 14380 7172 14381 10765 14381 7155 14381 7173 14382 7210 14382 7212 14382 7173 14383 7212 14383 7184 14383 7195 14384 7197 14384 7180 14384 7180 14385 7197 14385 7155 14385 7187 14386 7174 14386 7188 14386 7188 14387 7174 14387 10769 14387 7188 14388 10769 14388 7175 14388 7187 14389 7177 14389 7176 14389 7176 14390 7177 14390 7189 14390 7176 14391 7189 14391 10768 14391 7185 14392 7178 14392 10768 14392 7191 14393 7178 14393 7179 14393 7179 14394 7178 14394 7185 14394 7179 14395 7185 14395 7193 14395 7180 14396 7181 14396 7195 14396 7195 14397 7181 14397 7182 14397 7195 14398 7182 14398 7194 14398 7213 14399 7183 14399 7212 14399 7212 14400 7183 14400 7192 14400 7212 14401 7192 14401 7184 14401 7184 14402 7192 14402 7194 14402 7184 14403 7194 14403 9117 14403 9117 14404 7194 14404 7182 14404 9117 14405 7182 14405 9119 14405 9119 14406 7182 14406 7181 14406 9119 14407 7181 14407 7151 14407 10768 14408 7189 14408 7185 14408 7185 14409 7189 14409 7186 14409 7185 14410 7186 14410 7193 14410 7187 14411 7188 14411 7177 14411 7177 14412 7188 14412 7198 14412 7177 14413 7198 14413 7189 14413 7189 14414 7198 14414 7196 14414 7189 14415 7196 14415 7186 14415 7190 14416 7191 14416 7171 14416 7171 14417 7191 14417 7179 14417 7171 14418 7179 14418 7183 14418 7183 14419 7179 14419 7193 14419 7183 14420 7193 14420 7192 14420 7192 14421 7193 14421 7186 14421 7192 14422 7186 14422 7194 14422 7194 14423 7186 14423 7196 14423 7194 14424 7196 14424 7195 14424 7195 14425 7196 14425 7198 14425 7195 14426 7198 14426 7197 14426 7197 14427 7198 14427 7188 14427 7197 14428 7188 14428 7155 14428 7155 14429 7188 14429 7175 14429 7155 14430 7175 14430 7172 14430 9122 14431 9121 14431 7207 14431 10523 14432 7199 14432 7204 14432 7200 14433 7201 14433 7214 14433 7211 14434 7206 14434 7200 14434 7200 14435 7206 14435 7204 14435 10525 14436 7201 14436 10526 14436 10526 14437 7201 14437 7200 14437 10526 14438 7200 14438 7202 14438 7202 14439 7200 14439 7204 14439 7202 14440 7204 14440 7203 14440 7203 14441 7204 14441 7199 14441 7211 14442 7205 14442 7206 14442 7206 14443 7205 14443 7209 14443 7206 14444 7209 14444 7204 14444 7204 14445 7209 14445 7208 14445 7204 14446 7208 14446 10523 14446 10523 14447 7208 14447 7207 14447 9122 14448 7207 14448 9124 14448 9124 14449 7207 14449 7208 14449 9124 14450 7208 14450 9125 14450 9125 14451 7208 14451 7209 14451 9125 14452 7209 14452 9120 14452 9120 14453 7209 14453 7205 14453 9120 14454 7205 14454 7210 14454 7210 14455 7205 14455 7212 14455 7212 14456 7205 14456 7211 14456 7212 14457 7211 14457 7213 14457 7213 14458 7211 14458 7200 14458 7213 14459 7200 14459 7171 14459 7171 14460 7200 14460 7214 14460 7171 14461 7214 14461 7190 14461 7215 14462 9204 14462 7216 14462 7225 14463 7226 14463 7217 14463 7217 14464 7226 14464 7236 14464 7217 14465 7236 14465 7216 14465 7216 14466 7236 14466 7218 14466 7216 14467 7218 14467 7215 14467 7245 14468 8547 14468 8550 14468 7225 14469 7217 14469 7223 14469 7223 14470 7217 14470 7245 14470 7223 14471 7245 14471 7219 14471 7219 14472 7245 14472 8550 14472 7219 14473 8550 14473 7220 14473 7219 14474 7220 14474 7222 14474 8557 14475 7221 14475 7230 14475 8556 14476 7234 14476 8555 14476 8555 14477 7234 14477 8553 14477 7224 14478 7222 14478 7241 14478 7219 14479 7222 14479 7223 14479 7223 14480 7222 14480 7224 14480 7223 14481 7224 14481 7225 14481 7225 14482 7224 14482 7239 14482 7225 14483 7239 14483 7226 14483 7226 14484 7239 14484 7227 14484 7226 14485 7227 14485 7236 14485 7238 14486 9110 14486 7237 14486 7233 14487 7228 14487 9110 14487 7229 14488 8557 14488 7235 14488 7235 14489 8557 14489 7230 14489 7235 14490 7230 14490 7231 14490 7231 14491 7230 14491 7267 14491 7231 14492 7267 14492 7233 14492 7233 14493 7267 14493 7251 14493 7233 14494 7251 14494 7228 14494 7228 14495 7251 14495 7232 14495 9110 14496 7238 14496 7233 14496 7233 14497 7238 14497 7240 14497 7233 14498 7240 14498 7231 14498 7231 14499 7240 14499 7234 14499 7231 14500 7234 14500 7235 14500 7235 14501 7234 14501 8556 14501 7235 14502 8556 14502 7229 14502 7218 14503 7236 14503 7237 14503 7237 14504 7236 14504 7227 14504 7237 14505 7227 14505 7238 14505 7238 14506 7227 14506 7239 14506 7238 14507 7239 14507 7240 14507 7240 14508 7239 14508 7224 14508 7240 14509 7224 14509 7234 14509 7234 14510 7224 14510 7241 14510 7234 14511 7241 14511 8553 14511 7242 14512 8547 14512 7245 14512 7243 14513 7242 14513 7244 14513 7244 14514 7242 14514 7245 14514 7244 14515 7245 14515 10486 14515 10486 14516 7245 14516 7217 14516 10486 14517 7217 14517 10472 14517 10472 14518 7217 14518 7216 14518 10472 14519 7216 14519 10469 14519 10469 14520 7216 14520 9204 14520 10469 14521 9204 14521 9210 14521 7259 14522 8560 14522 8562 14522 7246 14523 7261 14523 8561 14523 8561 14524 7261 14524 7247 14524 8561 14525 7247 14525 8558 14525 8558 14526 7247 14526 7248 14526 7248 14527 7247 14527 7230 14527 7248 14528 7230 14528 7221 14528 7249 14529 8985 14529 7266 14529 7266 14530 8985 14530 8986 14530 7266 14531 8986 14531 7250 14531 7250 14532 8986 14532 7252 14532 7250 14533 7252 14533 7251 14533 7251 14534 7252 14534 7232 14534 7253 14535 8982 14535 7268 14535 7268 14536 8982 14536 7257 14536 7268 14537 7257 14537 7254 14537 7263 14538 7255 14538 7256 14538 7256 14539 7255 14539 7254 14539 7256 14540 7254 14540 7265 14540 7265 14541 7254 14541 7257 14541 7265 14542 7257 14542 7266 14542 7266 14543 7257 14543 8982 14543 7266 14544 8982 14544 7249 14544 8561 14545 8560 14545 7246 14545 7246 14546 8560 14546 7259 14546 7246 14547 7259 14547 7258 14547 7258 14548 7259 14548 8562 14548 7258 14549 8562 14549 7260 14549 7246 14550 7264 14550 7261 14550 7261 14551 7264 14551 7262 14551 7261 14552 7262 14552 7247 14552 7247 14553 7262 14553 7267 14553 7247 14554 7267 14554 7230 14554 7260 14555 7263 14555 7258 14555 7258 14556 7263 14556 7256 14556 7258 14557 7256 14557 7246 14557 7246 14558 7256 14558 7265 14558 7246 14559 7265 14559 7264 14559 7264 14560 7265 14560 7266 14560 7264 14561 7266 14561 7262 14561 7262 14562 7266 14562 7250 14562 7262 14563 7250 14563 7267 14563 7267 14564 7250 14564 7251 14564 8984 14565 7253 14565 7268 14565 8548 14566 10476 14566 7269 14566 7260 14567 8548 14567 7263 14567 7263 14568 8548 14568 7269 14568 7263 14569 7269 14569 7255 14569 7255 14570 7269 14570 7270 14570 7255 14571 7270 14571 7254 14571 7254 14572 7270 14572 10470 14572 7254 14573 10470 14573 7268 14573 7268 14574 10470 14574 10485 14574 7268 14575 10485 14575 8984 14575 8984 14576 10485 14576 10484 14576 8984 14577 10484 14577 10483 14577 7398 14578 9219 14578 9215 14578 7399 14579 7271 14579 7395 14579 7395 14580 7271 14580 7272 14580 7341 14581 7340 14581 9244 14581 7341 14582 9244 14582 9239 14582 7326 14583 7273 14583 7329 14583 7316 14584 7317 14584 7274 14584 7329 14585 7276 14585 7275 14585 7275 14586 7276 14586 7274 14586 7274 14587 7318 14587 7315 14587 7400 14588 7277 14588 7310 14588 7310 14589 7277 14589 7312 14589 9215 14590 8639 14590 7278 14590 7279 14591 7280 14591 7281 14591 10589 14592 10588 14592 7282 14592 7285 14593 10576 14593 10575 14593 7283 14594 10576 14594 7284 14594 7284 14595 10576 14595 7285 14595 7284 14596 7285 14596 7286 14596 7283 14597 7284 14597 7287 14597 7287 14598 7284 14598 7288 14598 7287 14599 7288 14599 7289 14599 7290 14600 7291 14600 7292 14600 7292 14601 7291 14601 7293 14601 7292 14602 7293 14602 7294 14602 7294 14603 7293 14603 7349 14603 7294 14604 7349 14604 7295 14604 7379 14605 7381 14605 7296 14605 7296 14606 7381 14606 10583 14606 7296 14607 10583 14607 7365 14607 7365 14608 10583 14608 7364 14608 10586 14609 7377 14609 7297 14609 7297 14610 7377 14610 7376 14610 7297 14611 7376 14611 7298 14611 7298 14612 7376 14612 7300 14612 7279 14613 7299 14613 7300 14613 7300 14614 7299 14614 10597 14614 7300 14615 10597 14615 7298 14615 7399 14616 10592 14616 7271 14616 7271 14617 10592 14617 7301 14617 7271 14618 7301 14618 7272 14618 8642 14619 10578 14619 7302 14619 7302 14620 10578 14620 10577 14620 8642 14621 7302 14621 7303 14621 7303 14622 7302 14622 7304 14622 7303 14623 7304 14623 7305 14623 7305 14624 7304 14624 7308 14624 7305 14625 7308 14625 7306 14625 7306 14626 7308 14626 7307 14626 7307 14627 7308 14627 7397 14627 7307 14628 7397 14628 7396 14628 7312 14629 9254 14629 7313 14629 7313 14630 9254 14630 7309 14630 7313 14631 7309 14631 7274 14631 7400 14632 7310 14632 7311 14632 7311 14633 7310 14633 7314 14633 7311 14634 7314 14634 7320 14634 7312 14635 7313 14635 7310 14635 7310 14636 7313 14636 7274 14636 7310 14637 7274 14637 7314 14637 7314 14638 7274 14638 7315 14638 7314 14639 7315 14639 7320 14639 7274 14640 7276 14640 7316 14640 7316 14641 7276 14641 7329 14641 7316 14642 7329 14642 7317 14642 7317 14643 7329 14643 7330 14643 7317 14644 7330 14644 7274 14644 7274 14645 7330 14645 7319 14645 7274 14646 7319 14646 7318 14646 7318 14647 7319 14647 10593 14647 7318 14648 10593 14648 7315 14648 7315 14649 10593 14649 7433 14649 7315 14650 7433 14650 7320 14650 7327 14651 7321 14651 7322 14651 7322 14652 7321 14652 7323 14652 7322 14653 7323 14653 7325 14653 7273 14654 7326 14654 7328 14654 7324 14655 7328 14655 7325 14655 7325 14656 7328 14656 7326 14656 7325 14657 7326 14657 7322 14657 7322 14658 7326 14658 7329 14658 7322 14659 7329 14659 7327 14659 7327 14660 7329 14660 9251 14660 7327 14661 9251 14661 7321 14661 7323 14662 7286 14662 7325 14662 7325 14663 7286 14663 7285 14663 7325 14664 7285 14664 7324 14664 7324 14665 7285 14665 10575 14665 7324 14666 10575 14666 7328 14666 7328 14667 10575 14667 10574 14667 7328 14668 10574 14668 7273 14668 7273 14669 10574 14669 10589 14669 7273 14670 10589 14670 7329 14670 7329 14671 10589 14671 7282 14671 7329 14672 7282 14672 7330 14672 7330 14673 7282 14673 10588 14673 7330 14674 10588 14674 7319 14674 9241 14675 7331 14675 9247 14675 9247 14676 7331 14676 7333 14676 9247 14677 7333 14677 9248 14677 9248 14678 7333 14678 7332 14678 9248 14679 7332 14679 9250 14679 7336 14680 7332 14680 7335 14680 7335 14681 7332 14681 7333 14681 7335 14682 7333 14682 7334 14682 7334 14683 7333 14683 7331 14683 9241 14684 9243 14684 7331 14684 7331 14685 9243 14685 9244 14685 7331 14686 9244 14686 7334 14686 7334 14687 9244 14687 7338 14687 7334 14688 7338 14688 7335 14688 7335 14689 7338 14689 7337 14689 7335 14690 7337 14690 7336 14690 9251 14691 9250 14691 7321 14691 7321 14692 9250 14692 7332 14692 7321 14693 7332 14693 7323 14693 7323 14694 7332 14694 7336 14694 7323 14695 7336 14695 7286 14695 7286 14696 7336 14696 7337 14696 7286 14697 7337 14697 7284 14697 7284 14698 7337 14698 7338 14698 7284 14699 7338 14699 7288 14699 7288 14700 7338 14700 9244 14700 7288 14701 9244 14701 7348 14701 7339 14702 7340 14702 7343 14702 7343 14703 7340 14703 7341 14703 7343 14704 7341 14704 7342 14704 7342 14705 7341 14705 9239 14705 7342 14706 9236 14706 7343 14706 7343 14707 9236 14707 7344 14707 7343 14708 7344 14708 7339 14708 7339 14709 7344 14709 7345 14709 7339 14710 7345 14710 7340 14710 7340 14711 7345 14711 7346 14711 7340 14712 7346 14712 9244 14712 7289 14713 7288 14713 7347 14713 7347 14714 7288 14714 7348 14714 7347 14715 7348 14715 7290 14715 7290 14716 7348 14716 9244 14716 7290 14717 9244 14717 7291 14717 7291 14718 9244 14718 7346 14718 7291 14719 7346 14719 7293 14719 7293 14720 7346 14720 7345 14720 7293 14721 7345 14721 7349 14721 7349 14722 7345 14722 7344 14722 7349 14723 7344 14723 7360 14723 7351 14724 7363 14724 7350 14724 7350 14725 9232 14725 7351 14725 7351 14726 9232 14726 7352 14726 7351 14727 7352 14727 7353 14727 7353 14728 7354 14728 7351 14728 7351 14729 7354 14729 7356 14729 7351 14730 7356 14730 7363 14730 7352 14731 9235 14731 7353 14731 7353 14732 9235 14732 7355 14732 7353 14733 7355 14733 7354 14733 7354 14734 7355 14734 7357 14734 7354 14735 7357 14735 7356 14735 7356 14736 7357 14736 7358 14736 7356 14737 7358 14737 7363 14737 7295 14738 7349 14738 7359 14738 7359 14739 7349 14739 7360 14739 7359 14740 7360 14740 7361 14740 7361 14741 7360 14741 7344 14741 7361 14742 7344 14742 7362 14742 7362 14743 7344 14743 9238 14743 7362 14744 9238 14744 7364 14744 7364 14745 9238 14745 7363 14745 7364 14746 7363 14746 7365 14746 7365 14747 7363 14747 7358 14747 7365 14748 7358 14748 7296 14748 7296 14749 7358 14749 7357 14749 7296 14750 7357 14750 7379 14750 7379 14751 7357 14751 7355 14751 7379 14752 7355 14752 7378 14752 7366 14753 9226 14753 9225 14753 9225 14754 9223 14754 7366 14754 7366 14755 9223 14755 7367 14755 7366 14756 7367 14756 7370 14756 7370 14757 7367 14757 7392 14757 7368 14758 9226 14758 7371 14758 7371 14759 9226 14759 7366 14759 7371 14760 7366 14760 7369 14760 7369 14761 7366 14761 7370 14761 7369 14762 7370 14762 7373 14762 7368 14763 7371 14763 7372 14763 7372 14764 7371 14764 7369 14764 7372 14765 7369 14765 7375 14765 7375 14766 7369 14766 7373 14766 7375 14767 7373 14767 7374 14767 7272 14768 7280 14768 7374 14768 7374 14769 7280 14769 7279 14769 7374 14770 7279 14770 7375 14770 7375 14771 7279 14771 7300 14771 7375 14772 7300 14772 7372 14772 7372 14773 7300 14773 7376 14773 7372 14774 7376 14774 7368 14774 7368 14775 7376 14775 7377 14775 7368 14776 7377 14776 9226 14776 9226 14777 7377 14777 10586 14777 9226 14778 10586 14778 9228 14778 9228 14779 10586 14779 10585 14779 9228 14780 10585 14780 7355 14780 7355 14781 10585 14781 10580 14781 7355 14782 10580 14782 7378 14782 7378 14783 10580 14783 10579 14783 7378 14784 10579 14784 7379 14784 7379 14785 10579 14785 7380 14785 7379 14786 7380 14786 7381 14786 7387 14787 7384 14787 9218 14787 7387 14788 9218 14788 7382 14788 7382 14789 9218 14789 7383 14789 7382 14790 7383 14790 7388 14790 7393 14791 7384 14791 7385 14791 7385 14792 7384 14792 7387 14792 7385 14793 7387 14793 7386 14793 7386 14794 7387 14794 7382 14794 7386 14795 7382 14795 7394 14795 7394 14796 7382 14796 7388 14796 7394 14797 7388 14797 7389 14797 7383 14798 9219 14798 7388 14798 7388 14799 9219 14799 7398 14799 7388 14800 7398 14800 7389 14800 7389 14801 7398 14801 7390 14801 7389 14802 7390 14802 7391 14802 7392 14803 7393 14803 7370 14803 7370 14804 7393 14804 7385 14804 7370 14805 7385 14805 7373 14805 7373 14806 7385 14806 7386 14806 7373 14807 7386 14807 7374 14807 7374 14808 7386 14808 7394 14808 7374 14809 7394 14809 7272 14809 7272 14810 7394 14810 7389 14810 7272 14811 7389 14811 7395 14811 7395 14812 7389 14812 7391 14812 7395 14813 7391 14813 7399 14813 7278 14814 7396 14814 9215 14814 9215 14815 7396 14815 7397 14815 9215 14816 7397 14816 7398 14816 7398 14817 7397 14817 7308 14817 7398 14818 7308 14818 7390 14818 7390 14819 7308 14819 7304 14819 7390 14820 7304 14820 7391 14820 7391 14821 7304 14821 7302 14821 7391 14822 7302 14822 7399 14822 7399 14823 7302 14823 10577 14823 7399 14824 10577 14824 10592 14824 7311 14825 7320 14825 7419 14825 7277 14826 7400 14826 7417 14826 7402 14827 7434 14827 7401 14827 7416 14828 7402 14828 7403 14828 7402 14829 7401 14829 7403 14829 7403 14830 7401 14830 7405 14830 7403 14831 7405 14831 7404 14831 7404 14832 7405 14832 9260 14832 7404 14833 9260 14833 7406 14833 7406 14834 9260 14834 7407 14834 7406 14835 7407 14835 7412 14835 7412 14836 7407 14836 7408 14836 7412 14837 7408 14837 7411 14837 7411 14838 7408 14838 9259 14838 7411 14839 9259 14839 7410 14839 7410 14840 9259 14840 9257 14840 7410 14841 9257 14841 7409 14841 7409 14842 9257 14842 9254 14842 7409 14843 9254 14843 7312 14843 7312 14844 7277 14844 7409 14844 7409 14845 7277 14845 7417 14845 7409 14846 7417 14846 7410 14846 7410 14847 7417 14847 7418 14847 7410 14848 7418 14848 7411 14848 7411 14849 7418 14849 7413 14849 7411 14850 7413 14850 7412 14850 7412 14851 7413 14851 7414 14851 7412 14852 7414 14852 7406 14852 7406 14853 7414 14853 7420 14853 7406 14854 7420 14854 7404 14854 7404 14855 7420 14855 7415 14855 7404 14856 7415 14856 7403 14856 7403 14857 7415 14857 7424 14857 7403 14858 7424 14858 7416 14858 7416 14859 7424 14859 7436 14859 7400 14860 7311 14860 7417 14860 7417 14861 7311 14861 7419 14861 7417 14862 7419 14862 7418 14862 7418 14863 7419 14863 7431 14863 7418 14864 7431 14864 7413 14864 7413 14865 7431 14865 7430 14865 7413 14866 7430 14866 7414 14866 7414 14867 7430 14867 7427 14867 7414 14868 7427 14868 7420 14868 7420 14869 7427 14869 7421 14869 7420 14870 7421 14870 7415 14870 7415 14871 7421 14871 7422 14871 7415 14872 7422 14872 7424 14872 7424 14873 7422 14873 7423 14873 7424 14874 7423 14874 7436 14874 7436 14875 7423 14875 7425 14875 7425 14876 7423 14876 7426 14876 7426 14877 7423 14877 7422 14877 7426 14878 7422 14878 8637 14878 8637 14879 7422 14879 7421 14879 8637 14880 7421 14880 8636 14880 8636 14881 7421 14881 7427 14881 8636 14882 7427 14882 7428 14882 7428 14883 7427 14883 7430 14883 7428 14884 7430 14884 7429 14884 7429 14885 7430 14885 7431 14885 7429 14886 7431 14886 7432 14886 7432 14887 7431 14887 7419 14887 7432 14888 7419 14888 8634 14888 8634 14889 7419 14889 7320 14889 8634 14890 7320 14890 7433 14890 8156 14891 7434 14891 7438 14891 7438 14892 7434 14892 7402 14892 7438 14893 7402 14893 7448 14893 7448 14894 7402 14894 7449 14894 7449 14895 7402 14895 7416 14895 7449 14896 7416 14896 7435 14896 7435 14897 7416 14897 7450 14897 7450 14898 7416 14898 7436 14898 7450 14899 7436 14899 7451 14899 7451 14900 7436 14900 7425 14900 7451 14901 7425 14901 7455 14901 7438 14902 7444 14902 7440 14902 7437 14903 7444 14903 7438 14903 8158 14904 7438 14904 7439 14904 7438 14905 8158 14905 8156 14905 7447 14906 7439 14906 7438 14906 7452 14907 8162 14907 7443 14907 7443 14908 8159 14908 7440 14908 7440 14909 8159 14909 8160 14909 7440 14910 8160 14910 7446 14910 7441 14911 10309 14911 7452 14911 7452 14912 10309 14912 7442 14912 7452 14913 7442 14913 8162 14913 7448 14914 7437 14914 7438 14914 7443 14915 7440 14915 7452 14915 7452 14916 7440 14916 7444 14916 7452 14917 7444 14917 7445 14917 7445 14918 7444 14918 7437 14918 7445 14919 7437 14919 7454 14919 7446 14920 7447 14920 7440 14920 7440 14921 7447 14921 7438 14921 7448 14922 7449 14922 7437 14922 7437 14923 7449 14923 7435 14923 7437 14924 7435 14924 7454 14924 7454 14925 7435 14925 7450 14925 7454 14926 7450 14926 7451 14926 7441 14927 7452 14927 7453 14927 7453 14928 7452 14928 7445 14928 7453 14929 7445 14929 7459 14929 7459 14930 7445 14930 7454 14930 7459 14931 7454 14931 7457 14931 7457 14932 7454 14932 7451 14932 7457 14933 7451 14933 7455 14933 7455 14934 8163 14934 7456 14934 7455 14935 7456 14935 7457 14935 7457 14936 7456 14936 7458 14936 7457 14937 7458 14937 7459 14937 7459 14938 7458 14938 7460 14938 7459 14939 7460 14939 7453 14939 7467 14940 10309 14940 7460 14940 7460 14941 10309 14941 7441 14941 7460 14942 7441 14942 7453 14942 7461 14943 7464 14943 7462 14943 7462 14944 7473 14944 7461 14944 7461 14945 7473 14945 7463 14945 7461 14946 7463 14946 7465 14946 8163 14947 7464 14947 7456 14947 7456 14948 7464 14948 7461 14948 7456 14949 7461 14949 7458 14949 7458 14950 7461 14950 7465 14950 7458 14951 7465 14951 7460 14951 7460 14952 7465 14952 7466 14952 7460 14953 7466 14953 7467 14953 7467 14954 7466 14954 7468 14954 7463 14955 7472 14955 7465 14955 7465 14956 7472 14956 7470 14956 7465 14957 7470 14957 7466 14957 7466 14958 7470 14958 7469 14958 7466 14959 7469 14959 7468 14959 7468 14960 7469 14960 10319 14960 8263 14961 8265 14961 11688 14961 10318 14962 10319 14962 7469 14962 10318 14963 7469 14963 7471 14963 7469 14964 7470 14964 7471 14964 7471 14965 7470 14965 7472 14965 7471 14966 7472 14966 11688 14966 11688 14967 7472 14967 7463 14967 11688 14968 7463 14968 8263 14968 8263 14969 7463 14969 7473 14969 8263 14970 7473 14970 7462 14970 7487 14971 7474 14971 7478 14971 7476 14972 10305 14972 7475 14972 7476 14973 7475 14973 7493 14973 7493 14974 7475 14974 7474 14974 7474 14975 7475 14975 7477 14975 7474 14976 7477 14976 7478 14976 7478 14977 7477 14977 7479 14977 7478 14978 7479 14978 7481 14978 7481 14979 7479 14979 10311 14979 7481 14980 10311 14980 7482 14980 7487 14981 7478 14981 7480 14981 7480 14982 7478 14982 7481 14982 7480 14983 7481 14983 7489 14983 7489 14984 7481 14984 7482 14984 7489 14985 7482 14985 7490 14985 7483 14986 7484 14986 7487 14986 7487 14987 7484 14987 7485 14987 7487 14988 7485 14988 7474 14988 7474 14989 7485 14989 7486 14989 7474 14990 7486 14990 7493 14990 7483 14991 7487 14991 7488 14991 7488 14992 7487 14992 7480 14992 7488 14993 7480 14993 8196 14993 8196 14994 7480 14994 7489 14994 8196 14995 7489 14995 8195 14995 8195 14996 7489 14996 7490 14996 8195 14997 7490 14997 8614 14997 7491 14998 7492 14998 10307 14998 7500 14999 7491 14999 7494 14999 8684 15000 7499 15000 7496 15000 7496 15001 7499 15001 7495 15001 7496 15002 7495 15002 7497 15002 7491 15003 10307 15003 7494 15003 7494 15004 10307 15004 10305 15004 7494 15005 10305 15005 7476 15005 7476 15006 7493 15006 7494 15006 7494 15007 7493 15007 7497 15007 7494 15008 7497 15008 7500 15008 7500 15009 7497 15009 7495 15009 7483 15010 8684 15010 7484 15010 7484 15011 8684 15011 7496 15011 7484 15012 7496 15012 7485 15012 7485 15013 7496 15013 7497 15013 7485 15014 7497 15014 7486 15014 7486 15015 7497 15015 7493 15015 8683 15016 7521 15016 7502 15016 7509 15017 7498 15017 7504 15017 7504 15018 7498 15018 7501 15018 7495 15019 7499 15019 8682 15019 7500 15020 7504 15020 7491 15020 7491 15021 7504 15021 7501 15021 7491 15022 7501 15022 7492 15022 8682 15023 8683 15023 7495 15023 7495 15024 8683 15024 7502 15024 7495 15025 7502 15025 7500 15025 7500 15026 7502 15026 7503 15026 7500 15027 7503 15027 7504 15027 7504 15028 7503 15028 7505 15028 7504 15029 7505 15029 7509 15029 7503 15030 7502 15030 7506 15030 7507 15031 7508 15031 7511 15031 7515 15032 7514 15032 7510 15032 7509 15033 7505 15033 10304 15033 10304 15034 7505 15034 7515 15034 7510 15035 7514 15035 7513 15035 11665 15036 11664 15036 7508 15036 7508 15037 11664 15037 11663 15037 7508 15038 11663 15038 7511 15038 7511 15039 11663 15039 11666 15039 7511 15040 11666 15040 7512 15040 7512 15041 7513 15041 7511 15041 7511 15042 7513 15042 7514 15042 7511 15043 7514 15043 7507 15043 7507 15044 7514 15044 7515 15044 7507 15045 7515 15045 7516 15045 7516 15046 7515 15046 7505 15046 7505 15047 7503 15047 7516 15047 7516 15048 7503 15048 7506 15048 7516 15049 7506 15049 7507 15049 7507 15050 7506 15050 7517 15050 7507 15051 7517 15051 7508 15051 7508 15052 7517 15052 7519 15052 7508 15053 7519 15053 11665 15053 11665 15054 7519 15054 7518 15054 7518 15055 7519 15055 7520 15055 7520 15056 7519 15056 7517 15056 7520 15057 7517 15057 8245 15057 8245 15058 7517 15058 7506 15058 8245 15059 7506 15059 8241 15059 8241 15060 7506 15060 7502 15060 8241 15061 7502 15061 7521 15061 11675 15062 7539 15062 7533 15062 7530 15063 7534 15063 7522 15063 7522 15064 7540 15064 10293 15064 7531 15065 7527 15065 7523 15065 7524 15066 7526 15066 7525 15066 7525 15067 7526 15067 7531 15067 7523 15068 7527 15068 7528 15068 7540 15069 7522 15069 7529 15069 7529 15070 7522 15070 7534 15070 7529 15071 7534 15071 7541 15071 10293 15072 7528 15072 7522 15072 7522 15073 7528 15073 7527 15073 7522 15074 7527 15074 7530 15074 7530 15075 7527 15075 7531 15075 7530 15076 7531 15076 7532 15076 7532 15077 7531 15077 7526 15077 7526 15078 11675 15078 7532 15078 7532 15079 11675 15079 7533 15079 7532 15080 7533 15080 7530 15080 7530 15081 7533 15081 7538 15081 7530 15082 7538 15082 7534 15082 7534 15083 7538 15083 7535 15083 7534 15084 7535 15084 7541 15084 7541 15085 7535 15085 8258 15085 8258 15086 7535 15086 7536 15086 7536 15087 7535 15087 7538 15087 7536 15088 7538 15088 7537 15088 7537 15089 7538 15089 7533 15089 7537 15090 7533 15090 8255 15090 8255 15091 7533 15091 7539 15091 8255 15092 7539 15092 8254 15092 7540 15093 7550 15093 10293 15093 10293 15094 7550 15094 10292 15094 8258 15095 6364 15095 7541 15095 7541 15096 6364 15096 7558 15096 7541 15097 7558 15097 7529 15097 7529 15098 7558 15098 7552 15098 7529 15099 7552 15099 7540 15099 7540 15100 7552 15100 7550 15100 7553 15101 7547 15101 10291 15101 7542 15102 10292 15102 7550 15102 7543 15103 7544 15103 7547 15103 7547 15104 7544 15104 7545 15104 7547 15105 7545 15105 10291 15105 11643 15106 7546 15106 7548 15106 7546 15107 7543 15107 7548 15107 7548 15108 7543 15108 7547 15108 7548 15109 7547 15109 7549 15109 7549 15110 7547 15110 7553 15110 11642 15111 11643 15111 7556 15111 7556 15112 11643 15112 7548 15112 7556 15113 7548 15113 7557 15113 7557 15114 7548 15114 7549 15114 7557 15115 7549 15115 7555 15115 7552 15116 7554 15116 7550 15116 7550 15117 7554 15117 7551 15117 7550 15118 7551 15118 7542 15118 7552 15119 7558 15119 7555 15119 10291 15120 10290 15120 7553 15120 7553 15121 10290 15121 7551 15121 7553 15122 7551 15122 7549 15122 7549 15123 7551 15123 7554 15123 7549 15124 7554 15124 7555 15124 7555 15125 7554 15125 7552 15125 11642 15126 7556 15126 8218 15126 8218 15127 7556 15127 7557 15127 8218 15128 7557 15128 8217 15128 8217 15129 7557 15129 7555 15129 8217 15130 7555 15130 7559 15130 7559 15131 7555 15131 7558 15131 7559 15132 7558 15132 6364 15132 11656 15133 11644 15133 7570 15133 7566 15134 7564 15134 7560 15134 7560 15135 7563 15135 10274 15135 7568 15136 7561 15136 7562 15136 10280 15137 7569 15137 10279 15137 10279 15138 7569 15138 7568 15138 7562 15139 7561 15139 10278 15139 7563 15140 7560 15140 7579 15140 7579 15141 7560 15141 7564 15141 7579 15142 7564 15142 7565 15142 10274 15143 10278 15143 7560 15143 7560 15144 10278 15144 7561 15144 7560 15145 7561 15145 7566 15145 7566 15146 7561 15146 7568 15146 7566 15147 7568 15147 7567 15147 7567 15148 7568 15148 7569 15148 7569 15149 11656 15149 7567 15149 7567 15150 11656 15150 7570 15150 7567 15151 7570 15151 7566 15151 7566 15152 7570 15152 7574 15152 7566 15153 7574 15153 7564 15153 7564 15154 7574 15154 7572 15154 7564 15155 7572 15155 7565 15155 7565 15156 7572 15156 7571 15156 7571 15157 7572 15157 10605 15157 10605 15158 7572 15158 7574 15158 10605 15159 7574 15159 7573 15159 7573 15160 7574 15160 7570 15160 7573 15161 7570 15161 7575 15161 7575 15162 7570 15162 11644 15162 7575 15163 11644 15163 7576 15163 7563 15164 7577 15164 10274 15164 10274 15165 7577 15165 7580 15165 7571 15166 10600 15166 7565 15166 7565 15167 10600 15167 7578 15167 7565 15168 7578 15168 7579 15168 7579 15169 7578 15169 7589 15169 7579 15170 7589 15170 7563 15170 7563 15171 7589 15171 7577 15171 10275 15172 7580 15172 7577 15172 7585 15173 7581 15173 10272 15173 11629 15174 11619 15174 7581 15174 7581 15175 11619 15175 10273 15175 7581 15176 10273 15176 10272 15176 7582 15177 7583 15177 7584 15177 7583 15178 11629 15178 7584 15178 7584 15179 11629 15179 7581 15179 7584 15180 7581 15180 7586 15180 7586 15181 7581 15181 7585 15181 11618 15182 7582 15182 7590 15182 7590 15183 7582 15183 7584 15183 7590 15184 7584 15184 7591 15184 7591 15185 7584 15185 7586 15185 7591 15186 7586 15186 7592 15186 7589 15187 7587 15187 7577 15187 7577 15188 7587 15188 7588 15188 7577 15189 7588 15189 10275 15189 7589 15190 7578 15190 7592 15190 10272 15191 10271 15191 7585 15191 7585 15192 10271 15192 7588 15192 7585 15193 7588 15193 7586 15193 7586 15194 7588 15194 7587 15194 7586 15195 7587 15195 7592 15195 7592 15196 7587 15196 7589 15196 11618 15197 7590 15197 8604 15197 8604 15198 7590 15198 7591 15198 8604 15199 7591 15199 8603 15199 8603 15200 7591 15200 7592 15200 8603 15201 7592 15201 8606 15201 8606 15202 7592 15202 7578 15202 8606 15203 7578 15203 10600 15203 10256 15204 7593 15204 7595 15204 7595 15205 7593 15205 7594 15205 7595 15206 7594 15206 7602 15206 7602 15207 7594 15207 7597 15207 7602 15208 7597 15208 6371 15208 6371 15209 7597 15209 7596 15209 7593 15210 10262 15210 7594 15210 7594 15211 10262 15211 7599 15211 7594 15212 7599 15212 7597 15212 7597 15213 7599 15213 7600 15213 7597 15214 7600 15214 7596 15214 7596 15215 7600 15215 7598 15215 10262 15216 10270 15216 7599 15216 7599 15217 10270 15217 11641 15217 7599 15218 11641 15218 7600 15218 7600 15219 11641 15219 11628 15219 7600 15220 11628 15220 7598 15220 7598 15221 11628 15221 7601 15221 10251 15222 10256 15222 7595 15222 10251 15223 7595 15223 7612 15223 7612 15224 7595 15224 7602 15224 7612 15225 7602 15225 7603 15225 7603 15226 7602 15226 6371 15226 7603 15227 6371 15227 6372 15227 7606 15228 11603 15228 7610 15228 11604 15229 11605 15229 7604 15229 11605 15230 7605 15230 10249 15230 11604 15231 7604 15231 11603 15231 7606 15232 7610 15232 8653 15232 11605 15233 10249 15233 7604 15233 7604 15234 10249 15234 7607 15234 7604 15235 7607 15235 7608 15235 7608 15236 7607 15236 10250 15236 7608 15237 10250 15237 7609 15237 7609 15238 10250 15238 10251 15238 7609 15239 10251 15239 7612 15239 11603 15240 7604 15240 7610 15240 7610 15241 7604 15241 7608 15241 7610 15242 7608 15242 7611 15242 7611 15243 7608 15243 7609 15243 7611 15244 7609 15244 7615 15244 7615 15245 7609 15245 7612 15245 7615 15246 7612 15246 7603 15246 8653 15247 7610 15247 7613 15247 7613 15248 7610 15248 7611 15248 7613 15249 7611 15249 7614 15249 7614 15250 7611 15250 7615 15250 7614 15251 7615 15251 8655 15251 8655 15252 7615 15252 7603 15252 8655 15253 7603 15253 6372 15253 8669 15254 7619 15254 7616 15254 7617 15255 7618 15255 7682 15255 7682 15256 7618 15256 7621 15256 7616 15257 7619 15257 7620 15257 7619 15258 7677 15258 7620 15258 7620 15259 7677 15259 7679 15259 7620 15260 7679 15260 7621 15260 7621 15261 7679 15261 7681 15261 7621 15262 7681 15262 7682 15262 7618 15263 10224 15263 7621 15263 7621 15264 10224 15264 7622 15264 7621 15265 7622 15265 7620 15265 7620 15266 7622 15266 7623 15266 7620 15267 7623 15267 7616 15267 7616 15268 7623 15268 7645 15268 7624 15269 7626 15269 7625 15269 7625 15270 7626 15270 7629 15270 7625 15271 7629 15271 7627 15271 7627 15272 7629 15272 7630 15272 7627 15273 7630 15273 7628 15273 7628 15274 7630 15274 7649 15274 7628 15275 7649 15275 7648 15275 7626 15276 10226 15276 7629 15276 7629 15277 10226 15277 7654 15277 7629 15278 7654 15278 7630 15278 7630 15279 7654 15279 7631 15279 7630 15280 7631 15280 7649 15280 7649 15281 7631 15281 7652 15281 7657 15282 10243 15282 7658 15282 7658 15283 10243 15283 7635 15283 7658 15284 7635 15284 7632 15284 7632 15285 7635 15285 7638 15285 7632 15286 7638 15286 7633 15286 7633 15287 7638 15287 7663 15287 7633 15288 7663 15288 7634 15288 10243 15289 7666 15289 7635 15289 7635 15290 7666 15290 7636 15290 7635 15291 7636 15291 7638 15291 7638 15292 7636 15292 7637 15292 7638 15293 7637 15293 7663 15293 7663 15294 7637 15294 7660 15294 10245 15295 10239 15295 7639 15295 7639 15296 10239 15296 7640 15296 7639 15297 7640 15297 7641 15297 7641 15298 7640 15298 7643 15298 7641 15299 7643 15299 7642 15299 7642 15300 7643 15300 7669 15300 7642 15301 7669 15301 8658 15301 10239 15302 10242 15302 7640 15302 7640 15303 10242 15303 7644 15303 7640 15304 7644 15304 7643 15304 7643 15305 7644 15305 7673 15305 7643 15306 7673 15306 7669 15306 7669 15307 7673 15307 7668 15307 8665 15308 8666 15308 7645 15308 7645 15309 8666 15309 7646 15309 7645 15310 7646 15310 7616 15310 7616 15311 7646 15311 7647 15311 7616 15312 7647 15312 8669 15312 7648 15313 8665 15313 7628 15313 7628 15314 8665 15314 7645 15314 7628 15315 7645 15315 7627 15315 7627 15316 7645 15316 7623 15316 7627 15317 7623 15317 7625 15317 7625 15318 7623 15318 7622 15318 7625 15319 7622 15319 7624 15319 7624 15320 7622 15320 10224 15320 7651 15321 8664 15321 7652 15321 7652 15322 8664 15322 8663 15322 7652 15323 8663 15323 7649 15323 7649 15324 8663 15324 7650 15324 7649 15325 7650 15325 7648 15325 8662 15326 7651 15326 7659 15326 7659 15327 7651 15327 7652 15327 7659 15328 7652 15328 7653 15328 7653 15329 7652 15329 7631 15329 7653 15330 7631 15330 7656 15330 7656 15331 7631 15331 7654 15331 7656 15332 7654 15332 7655 15332 7655 15333 7654 15333 10226 15333 7655 15334 7657 15334 7656 15334 7656 15335 7657 15335 7658 15335 7656 15336 7658 15336 7653 15336 7653 15337 7658 15337 7632 15337 7653 15338 7632 15338 7659 15338 7659 15339 7632 15339 7633 15339 7659 15340 7633 15340 8662 15340 8662 15341 7633 15341 7634 15341 7665 15342 7661 15342 7660 15342 7660 15343 7661 15343 7662 15343 7660 15344 7662 15344 7663 15344 7663 15345 7662 15345 7664 15345 7663 15346 7664 15346 7634 15346 8658 15347 7665 15347 7642 15347 7642 15348 7665 15348 7660 15348 7642 15349 7660 15349 7641 15349 7641 15350 7660 15350 7637 15350 7641 15351 7637 15351 7639 15351 7639 15352 7637 15352 7636 15352 7639 15353 7636 15353 10245 15353 10245 15354 7636 15354 7666 15354 8661 15355 7667 15355 7668 15355 7668 15356 7667 15356 7670 15356 7668 15357 7670 15357 7669 15357 7669 15358 7670 15358 8659 15358 7669 15359 8659 15359 8658 15359 8657 15360 8661 15360 7671 15360 7671 15361 8661 15361 7668 15361 7671 15362 7668 15362 7672 15362 7672 15363 7668 15363 7673 15363 7672 15364 7673 15364 7674 15364 7674 15365 7673 15365 7644 15365 7674 15366 7644 15366 10246 15366 10246 15367 7644 15367 10242 15367 10246 15368 7675 15368 7674 15368 7674 15369 7675 15369 11617 15369 7674 15370 11617 15370 7672 15370 7672 15371 11617 15371 11614 15371 7672 15372 11614 15372 7671 15372 7671 15373 11614 15373 7676 15373 7671 15374 7676 15374 8657 15374 8657 15375 7676 15375 10698 15375 7619 15376 8669 15376 7678 15376 7677 15377 7619 15377 7680 15377 7680 15378 7619 15378 7678 15378 7680 15379 7678 15379 11576 15379 7677 15380 7680 15380 7679 15380 7679 15381 7680 15381 7684 15381 7679 15382 7684 15382 7681 15382 7681 15383 7684 15383 7682 15383 7682 15384 7684 15384 7683 15384 7682 15385 7683 15385 7617 15385 11576 15386 11587 15386 7680 15386 7680 15387 11587 15387 11586 15387 7680 15388 11586 15388 7684 15388 7684 15389 11586 15389 7685 15389 7684 15390 7685 15390 7683 15390 7683 15391 7685 15391 7686 15391 8650 15392 8651 15392 7688 15392 8650 15393 7688 15393 7687 15393 7687 15394 7688 15394 7689 15394 7687 15395 7689 15395 7690 15395 7690 15396 7689 15396 7691 15396 7690 15397 7691 15397 11578 15397 11578 15398 7691 15398 7694 15398 11578 15399 7694 15399 10215 15399 7694 15400 7691 15400 7693 15400 7693 15401 7691 15401 7695 15401 11575 15402 7692 15402 7695 15402 7695 15403 7692 15403 7698 15403 7695 15404 7698 15404 7693 15404 7693 15405 7698 15405 7700 15405 7693 15406 7700 15406 7694 15406 7691 15407 7689 15407 7695 15407 7695 15408 7689 15408 7688 15408 7695 15409 7688 15409 11575 15409 11575 15410 7688 15410 8651 15410 7692 15411 7696 15411 7697 15411 7692 15412 7697 15412 7698 15412 7698 15413 7697 15413 7699 15413 7698 15414 7699 15414 7700 15414 7700 15415 7699 15415 7701 15415 7700 15416 7701 15416 7694 15416 10209 15417 11568 15417 7702 15417 10209 15418 7702 15418 7709 15418 7709 15419 7702 15419 7703 15419 7709 15420 7703 15420 7707 15420 7707 15421 7703 15421 7704 15421 7707 15422 7704 15422 7705 15422 7705 15423 7704 15423 11572 15423 7705 15424 11572 15424 8670 15424 7705 15425 8670 15425 8671 15425 8671 15426 7712 15426 7705 15426 7705 15427 7712 15427 7706 15427 7705 15428 7706 15428 7707 15428 7707 15429 7706 15429 7714 15429 7707 15430 7714 15430 7709 15430 7709 15431 7714 15431 7708 15431 7709 15432 7708 15432 10209 15432 7710 15433 7716 15433 7711 15433 7712 15434 8671 15434 7710 15434 7710 15435 7711 15435 7712 15435 7712 15436 7711 15436 7713 15436 7712 15437 7713 15437 7706 15437 7706 15438 7713 15438 7719 15438 7706 15439 7719 15439 7714 15439 7714 15440 7719 15440 7715 15440 7714 15441 7715 15441 7708 15441 10211 15442 7715 15442 7719 15442 7711 15443 7716 15443 7717 15443 7722 15444 7713 15444 7718 15444 7718 15445 7713 15445 7711 15445 7718 15446 7711 15446 7724 15446 7724 15447 7711 15447 7717 15447 7721 15448 10211 15448 7722 15448 7722 15449 10211 15449 7719 15449 7722 15450 7719 15450 7713 15450 7726 15451 10456 15451 7725 15451 10212 15452 7721 15452 7720 15452 7720 15453 7721 15453 7722 15453 7720 15454 7722 15454 7723 15454 7723 15455 7722 15455 7718 15455 7723 15456 7718 15456 7725 15456 7725 15457 7718 15457 7724 15457 7725 15458 7724 15458 7726 15458 7726 15459 7724 15459 7717 15459 10212 15460 7720 15460 7727 15460 7727 15461 7728 15461 10201 15461 7728 15462 7729 15462 10204 15462 7738 15463 7742 15463 7730 15463 7742 15464 7741 15464 7729 15464 7729 15465 7741 15465 7757 15465 7729 15466 7757 15466 10204 15466 7738 15467 7730 15467 7739 15467 8193 15468 7739 15468 7731 15468 7731 15469 7739 15469 7730 15469 7731 15470 7730 15470 7736 15470 7736 15471 7730 15471 7732 15471 7736 15472 7732 15472 7734 15472 7728 15473 7727 15473 7733 15473 7733 15474 7727 15474 7720 15474 7733 15475 7720 15475 7723 15475 7742 15476 7729 15476 7730 15476 7730 15477 7729 15477 7728 15477 7730 15478 7728 15478 7732 15478 7732 15479 7728 15479 7733 15479 7732 15480 7733 15480 7734 15480 7734 15481 7733 15481 7723 15481 7734 15482 7723 15482 7725 15482 8193 15483 7731 15483 7735 15483 7735 15484 7731 15484 7736 15484 7735 15485 7736 15485 8192 15485 8192 15486 7736 15486 7734 15486 8192 15487 7734 15487 7737 15487 7737 15488 7734 15488 7725 15488 7737 15489 7725 15489 10456 15489 7739 15490 8193 15490 10617 15490 7742 15491 7738 15491 7747 15491 7747 15492 7738 15492 7739 15492 7757 15493 7741 15493 7740 15493 7740 15494 7741 15494 7742 15494 10612 15495 8186 15495 7743 15495 7739 15496 10617 15496 7747 15496 7747 15497 10617 15497 10616 15497 7747 15498 10616 15498 7748 15498 7748 15499 10616 15499 7744 15499 7748 15500 7744 15500 7750 15500 7750 15501 7744 15501 10614 15501 7750 15502 10614 15502 7745 15502 7745 15503 10614 15503 7746 15503 7745 15504 7746 15504 7752 15504 7752 15505 7746 15505 10612 15505 7752 15506 10612 15506 7754 15506 7754 15507 10612 15507 7743 15507 7754 15508 7743 15508 7755 15508 7742 15509 7747 15509 7740 15509 7740 15510 7747 15510 7748 15510 7740 15511 7748 15511 7758 15511 7758 15512 7748 15512 7750 15512 7758 15513 7750 15513 7749 15513 7749 15514 7750 15514 7745 15514 7749 15515 7745 15515 7751 15515 7751 15516 7745 15516 7752 15516 7751 15517 7752 15517 7753 15517 7753 15518 7752 15518 7754 15518 7753 15519 7754 15519 7761 15519 7761 15520 7754 15520 7755 15520 7761 15521 7755 15521 7756 15521 7757 15522 7740 15522 10195 15522 10195 15523 7740 15523 7758 15523 10195 15524 7758 15524 7759 15524 7759 15525 7758 15525 7749 15525 7759 15526 7749 15526 10198 15526 10198 15527 7749 15527 7751 15527 10198 15528 7751 15528 10200 15528 10200 15529 7751 15529 7753 15529 10200 15530 7753 15530 10207 15530 10207 15531 7753 15531 7761 15531 10207 15532 7761 15532 7760 15532 7760 15533 7761 15533 7756 15533 7760 15534 7756 15534 7762 15534 7755 15535 7743 15535 7771 15535 7770 15536 7773 15536 7766 15536 7766 15537 7777 15537 7763 15537 7768 15538 7764 15538 10206 15538 7762 15539 7756 15539 10205 15539 10205 15540 7756 15540 7768 15540 10206 15541 7764 15541 7765 15541 7777 15542 7766 15542 7767 15542 7767 15543 7766 15543 7773 15543 7767 15544 7773 15544 7778 15544 7763 15545 7765 15545 7766 15545 7766 15546 7765 15546 7764 15546 7766 15547 7764 15547 7770 15547 7770 15548 7764 15548 7768 15548 7770 15549 7768 15549 7769 15549 7769 15550 7768 15550 7756 15550 7756 15551 7755 15551 7769 15551 7769 15552 7755 15552 7771 15552 7769 15553 7771 15553 7770 15553 7770 15554 7771 15554 7772 15554 7770 15555 7772 15555 7773 15555 7773 15556 7772 15556 7774 15556 7773 15557 7774 15557 7778 15557 7778 15558 7774 15558 8180 15558 8180 15559 7774 15559 7775 15559 7775 15560 7774 15560 7772 15560 7775 15561 7772 15561 8184 15561 8184 15562 7772 15562 7771 15562 8184 15563 7771 15563 7776 15563 7776 15564 7771 15564 7743 15564 7776 15565 7743 15565 8186 15565 7777 15566 7780 15566 7763 15566 7763 15567 7780 15567 7782 15567 8180 15568 10567 15568 7778 15568 7778 15569 10567 15569 7790 15569 7778 15570 7790 15570 7767 15570 7767 15571 7790 15571 7779 15571 7767 15572 7779 15572 7777 15572 7777 15573 7779 15573 7780 15573 7791 15574 7784 15574 7781 15574 10193 15575 7782 15575 7780 15575 7818 15576 7783 15576 7784 15576 7784 15577 7783 15577 10188 15577 7784 15578 10188 15578 7781 15578 7785 15579 7820 15579 7787 15579 7820 15580 7818 15580 7787 15580 7787 15581 7818 15581 7784 15581 7787 15582 7784 15582 7793 15582 7793 15583 7784 15583 7791 15583 7799 15584 7785 15584 7786 15584 7786 15585 7785 15585 7787 15585 7786 15586 7787 15586 7788 15586 7788 15587 7787 15587 7793 15587 7788 15588 7793 15588 7797 15588 7779 15589 7789 15589 7780 15589 7780 15590 7789 15590 10189 15590 7780 15591 10189 15591 10193 15591 7779 15592 7790 15592 7797 15592 7781 15593 7792 15593 7791 15593 7791 15594 7792 15594 10189 15594 7791 15595 10189 15595 7793 15595 7793 15596 10189 15596 7789 15596 7793 15597 7789 15597 7797 15597 7797 15598 7789 15598 7779 15598 7799 15599 7786 15599 7794 15599 7794 15600 7786 15600 7788 15600 7794 15601 7788 15601 7795 15601 7795 15602 7788 15602 7797 15602 7795 15603 7797 15603 7796 15603 7796 15604 7797 15604 7790 15604 7796 15605 7790 15605 10567 15605 7822 15606 7806 15606 7810 15606 7806 15607 7819 15607 7804 15607 7798 15608 7836 15608 7809 15608 7785 15609 7799 15609 10722 15609 7785 15610 10722 15610 7819 15610 7819 15611 10722 15611 10723 15611 7819 15612 10723 15612 7804 15612 10716 15613 7798 15613 7800 15613 7800 15614 7798 15614 7809 15614 7800 15615 7809 15615 10718 15615 10718 15616 7809 15616 7801 15616 10718 15617 7801 15617 7802 15617 7802 15618 7801 15618 7803 15618 7802 15619 7803 15619 10719 15619 10719 15620 7803 15620 7807 15620 10719 15621 7807 15621 10720 15621 10720 15622 7807 15622 7804 15622 10720 15623 7804 15623 7805 15623 7805 15624 7804 15624 10723 15624 7806 15625 7804 15625 7810 15625 7810 15626 7804 15626 7807 15626 7810 15627 7807 15627 7808 15627 7808 15628 7807 15628 7803 15628 7808 15629 7803 15629 7813 15629 7813 15630 7803 15630 7801 15630 7813 15631 7801 15631 7814 15631 7814 15632 7801 15632 7809 15632 7814 15633 7809 15633 7817 15633 7817 15634 7809 15634 7836 15634 7817 15635 7836 15635 7835 15635 7822 15636 7810 15636 7811 15636 7811 15637 7810 15637 7808 15637 7811 15638 7808 15638 7812 15638 7812 15639 7808 15639 7813 15639 7812 15640 7813 15640 7815 15640 7815 15641 7813 15641 7814 15641 7815 15642 7814 15642 7816 15642 7816 15643 7814 15643 7817 15643 7816 15644 7817 15644 7825 15644 7825 15645 7817 15645 7835 15645 7825 15646 7835 15646 7826 15646 7821 15647 10188 15647 7822 15647 7822 15648 10188 15648 7783 15648 7822 15649 7783 15649 7806 15649 7806 15650 7783 15650 7818 15650 7806 15651 7818 15651 7819 15651 7819 15652 7818 15652 7820 15652 7819 15653 7820 15653 7785 15653 7821 15654 7822 15654 10187 15654 10187 15655 7822 15655 7811 15655 10187 15656 7811 15656 10186 15656 10186 15657 7811 15657 7812 15657 10186 15658 7812 15658 10185 15658 10185 15659 7812 15659 7815 15659 10185 15660 7815 15660 7823 15660 7823 15661 7815 15661 7816 15661 7823 15662 7816 15662 7824 15662 7824 15663 7816 15663 7825 15663 7824 15664 7825 15664 10181 15664 10181 15665 7825 15665 7826 15665 10181 15666 7826 15666 7830 15666 7836 15667 7798 15667 7841 15667 7827 15668 7833 15668 7828 15668 7828 15669 7829 15669 10174 15669 7834 15670 7831 15670 10172 15670 7830 15671 7826 15671 10179 15671 10179 15672 7826 15672 7834 15672 10172 15673 7831 15673 10173 15673 7829 15674 7828 15674 7832 15674 7832 15675 7828 15675 7833 15675 7832 15676 7833 15676 7843 15676 10174 15677 10173 15677 7828 15677 7828 15678 10173 15678 7831 15678 7828 15679 7831 15679 7827 15679 7827 15680 7831 15680 7834 15680 7827 15681 7834 15681 7837 15681 7837 15682 7834 15682 7826 15682 7837 15683 7826 15683 7835 15683 7835 15684 7836 15684 7837 15684 7837 15685 7836 15685 7841 15685 7837 15686 7841 15686 7827 15686 7827 15687 7841 15687 7839 15687 7827 15688 7839 15688 7833 15688 7833 15689 7839 15689 7838 15689 7833 15690 7838 15690 7843 15690 7843 15691 7838 15691 8202 15691 8202 15692 7838 15692 8203 15692 8203 15693 7838 15693 7839 15693 8203 15694 7839 15694 8200 15694 8200 15695 7839 15695 7841 15695 8200 15696 7841 15696 7840 15696 7840 15697 7841 15697 7798 15697 7840 15698 7798 15698 10716 15698 10570 15699 10571 15699 7842 15699 10570 15700 7842 15700 10569 15700 8202 15701 10569 15701 7843 15701 7843 15702 10569 15702 7842 15702 7843 15703 7842 15703 7832 15703 7832 15704 7842 15704 7847 15704 7832 15705 7847 15705 7829 15705 7829 15706 7847 15706 7844 15706 7829 15707 7844 15707 10174 15707 10174 15708 7844 15708 7848 15708 7870 15709 8226 15709 7855 15709 7845 15710 7865 15710 7864 15710 7845 15711 7863 15711 7846 15711 7846 15712 7863 15712 7862 15712 7846 15713 7862 15713 10170 15713 7847 15714 7868 15714 7844 15714 7844 15715 7868 15715 7845 15715 7844 15716 7845 15716 7848 15716 7849 15717 7850 15717 7852 15717 7852 15718 7866 15718 7867 15718 7873 15719 7852 15719 7851 15719 7851 15720 7852 15720 7869 15720 7851 15721 7869 15721 7853 15721 7853 15722 7869 15722 7854 15722 7855 15723 7875 15723 7872 15723 7872 15724 7875 15724 7856 15724 7872 15725 7856 15725 7857 15725 7857 15726 7856 15726 7858 15726 7857 15727 7858 15727 7874 15727 7874 15728 7858 15728 10167 15728 7874 15729 10167 15729 10169 15729 7853 15730 7859 15730 7851 15730 7851 15731 7859 15731 7860 15731 7851 15732 7860 15732 7871 15732 7871 15733 7860 15733 7861 15733 7871 15734 7861 15734 7870 15734 7873 15735 7862 15735 7852 15735 7852 15736 7862 15736 7863 15736 7852 15737 7863 15737 7849 15737 7849 15738 7863 15738 7845 15738 7849 15739 7845 15739 7850 15739 7850 15740 7845 15740 7864 15740 7850 15741 7864 15741 7852 15741 7852 15742 7864 15742 7865 15742 7852 15743 7865 15743 7866 15743 7866 15744 7865 15744 7845 15744 7866 15745 7845 15745 7867 15745 7867 15746 7845 15746 7868 15746 7867 15747 7868 15747 7852 15747 7852 15748 7868 15748 7847 15748 7852 15749 7847 15749 7869 15749 7869 15750 7847 15750 7842 15750 7869 15751 7842 15751 7854 15751 7854 15752 7842 15752 10571 15752 7870 15753 7855 15753 7871 15753 7871 15754 7855 15754 7872 15754 7871 15755 7872 15755 7851 15755 7851 15756 7872 15756 7857 15756 7851 15757 7857 15757 7873 15757 7873 15758 7857 15758 7874 15758 7873 15759 7874 15759 7862 15759 7862 15760 7874 15760 10169 15760 7862 15761 10169 15761 10170 15761 10167 15762 7858 15762 7893 15762 7858 15763 7856 15763 7889 15763 7855 15764 8226 15764 7876 15764 7856 15765 7875 15765 7882 15765 7882 15766 7875 15766 7855 15766 7855 15767 7876 15767 7882 15767 7882 15768 7876 15768 10728 15768 7882 15769 10728 15769 7883 15769 10728 15770 7877 15770 7883 15770 7883 15771 7877 15771 7878 15771 7883 15772 7878 15772 7884 15772 7884 15773 7878 15773 7879 15773 7884 15774 7879 15774 7880 15774 7880 15775 7879 15775 10727 15775 7880 15776 10727 15776 7886 15776 7886 15777 10727 15777 7881 15777 7886 15778 7881 15778 7887 15778 7881 15779 10724 15779 7887 15779 7887 15780 10724 15780 7924 15780 7887 15781 7924 15781 7923 15781 7856 15782 7882 15782 7889 15782 7889 15783 7882 15783 7883 15783 7889 15784 7883 15784 7890 15784 7890 15785 7883 15785 7884 15785 7890 15786 7884 15786 7885 15786 7885 15787 7884 15787 7880 15787 7885 15788 7880 15788 7891 15788 7891 15789 7880 15789 7886 15789 7891 15790 7886 15790 7892 15790 7892 15791 7886 15791 7887 15791 7892 15792 7887 15792 7888 15792 7888 15793 7887 15793 7923 15793 7888 15794 7923 15794 7903 15794 7858 15795 7889 15795 7893 15795 7893 15796 7889 15796 7890 15796 7893 15797 7890 15797 7894 15797 7894 15798 7890 15798 7885 15798 7894 15799 7885 15799 7895 15799 7895 15800 7885 15800 7891 15800 7895 15801 7891 15801 7896 15801 7896 15802 7891 15802 7892 15802 7896 15803 7892 15803 7897 15803 7897 15804 7892 15804 7888 15804 7897 15805 7888 15805 7899 15805 7899 15806 7888 15806 7903 15806 7899 15807 7903 15807 7900 15807 10167 15808 7893 15808 10166 15808 10166 15809 7893 15809 7894 15809 10166 15810 7894 15810 10168 15810 10168 15811 7894 15811 7895 15811 10168 15812 7895 15812 10151 15812 10151 15813 7895 15813 7896 15813 10151 15814 7896 15814 10152 15814 10152 15815 7896 15815 7897 15815 10152 15816 7897 15816 7898 15816 7898 15817 7897 15817 7899 15817 7898 15818 7899 15818 10164 15818 10164 15819 7899 15819 7900 15819 10164 15820 7900 15820 7901 15820 7920 15821 7909 15821 7928 15821 7920 15822 7902 15822 7918 15822 7903 15823 7921 15823 7900 15823 7900 15824 7921 15824 7920 15824 7900 15825 7920 15825 7901 15825 7932 15826 7929 15826 7904 15826 7904 15827 7929 15827 7905 15827 7904 15828 7905 15828 7906 15828 7906 15829 7905 15829 10158 15829 7906 15830 10158 15830 7907 15830 7906 15831 7926 15831 7904 15831 7904 15832 7926 15832 7925 15832 7904 15833 7925 15833 7932 15833 7932 15834 7925 15834 7933 15834 7908 15835 7917 15835 7927 15835 7928 15836 7909 15836 7927 15836 7927 15837 7919 15837 7910 15837 7924 15838 7912 15838 7922 15838 7922 15839 7912 15839 7911 15839 7922 15840 7911 15840 7927 15840 7927 15841 7911 15841 7914 15841 8673 15842 7934 15842 8237 15842 8237 15843 7934 15843 7915 15843 7912 15844 8235 15844 7911 15844 7911 15845 8235 15845 7913 15845 7911 15846 7913 15846 7914 15846 7914 15847 7913 15847 8236 15847 7914 15848 8236 15848 7915 15848 7915 15849 8236 15849 7916 15849 7915 15850 7916 15850 8237 15850 7927 15851 7909 15851 7908 15851 7908 15852 7909 15852 7920 15852 7908 15853 7920 15853 7917 15853 7917 15854 7920 15854 7918 15854 7917 15855 7918 15855 7927 15855 7927 15856 7918 15856 7902 15856 7927 15857 7902 15857 7919 15857 7919 15858 7902 15858 7920 15858 7919 15859 7920 15859 7910 15859 7910 15860 7920 15860 7921 15860 7910 15861 7921 15861 7927 15861 7927 15862 7921 15862 7903 15862 7927 15863 7903 15863 7922 15863 7922 15864 7903 15864 7923 15864 7922 15865 7923 15865 7924 15865 7934 15866 7933 15866 7915 15866 7915 15867 7933 15867 7925 15867 7915 15868 7925 15868 7914 15868 7914 15869 7925 15869 7926 15869 7914 15870 7926 15870 7927 15870 7927 15871 7926 15871 7906 15871 7927 15872 7906 15872 7928 15872 7928 15873 7906 15873 7907 15873 7928 15874 7907 15874 7920 15874 10162 15875 7929 15875 7930 15875 7930 15876 7929 15876 7932 15876 7930 15877 7932 15877 7931 15877 7931 15878 7932 15878 7933 15878 7931 15879 7933 15879 7936 15879 7936 15880 7933 15880 7934 15880 7936 15881 7934 15881 8674 15881 8674 15882 7934 15882 8673 15882 10163 15883 10162 15883 7940 15883 7940 15884 10162 15884 7930 15884 7940 15885 7930 15885 7950 15885 7950 15886 7930 15886 7931 15886 7950 15887 7931 15887 7935 15887 7935 15888 7931 15888 7936 15888 7935 15889 7936 15889 7948 15889 7948 15890 7936 15890 8674 15890 7937 15891 7964 15891 7946 15891 7943 15892 7938 15892 10142 15892 7960 15893 7956 15893 7959 15893 7959 15894 7956 15894 7939 15894 7956 15895 7953 15895 7955 15895 7950 15896 7951 15896 7940 15896 7940 15897 7951 15897 7956 15897 7940 15898 7956 15898 10163 15898 8597 15899 8592 15899 7942 15899 7942 15900 8592 15900 7965 15900 8595 15901 8597 15901 7941 15901 7941 15902 8597 15902 7942 15902 7941 15903 7942 15903 7946 15903 7946 15904 7942 15904 7965 15904 7946 15905 7965 15905 7937 15905 10142 15906 10140 15906 7943 15906 7943 15907 10140 15907 7961 15907 7943 15908 7961 15908 7944 15908 7944 15909 7961 15909 7954 15909 7944 15910 7954 15910 7945 15910 7949 15911 8595 15911 7945 15911 7945 15912 8595 15912 7941 15912 7945 15913 7941 15913 7944 15913 7944 15914 7941 15914 7946 15914 7944 15915 7946 15915 7943 15915 7943 15916 7946 15916 7964 15916 7943 15917 7964 15917 7938 15917 7958 15918 7957 15918 7954 15918 7954 15919 7952 15919 7947 15919 7948 15920 7949 15920 7935 15920 7935 15921 7949 15921 7945 15921 7935 15922 7945 15922 7950 15922 7950 15923 7945 15923 7954 15923 7950 15924 7954 15924 7951 15924 7951 15925 7954 15925 7947 15925 7951 15926 7947 15926 7956 15926 7956 15927 7947 15927 7952 15927 7956 15928 7952 15928 7953 15928 7953 15929 7952 15929 7954 15929 7953 15930 7954 15930 7955 15930 7955 15931 7954 15931 7957 15931 7955 15932 7957 15932 7956 15932 7956 15933 7957 15933 7958 15933 7956 15934 7958 15934 7939 15934 7939 15935 7958 15935 7954 15935 7939 15936 7954 15936 7959 15936 7959 15937 7954 15937 7961 15937 7959 15938 7961 15938 7960 15938 7960 15939 7961 15939 10140 15939 8592 15940 7962 15940 7965 15940 7965 15941 7962 15941 7963 15941 7970 15942 10142 15942 7969 15942 7969 15943 10142 15943 7938 15943 7969 15944 7938 15944 7967 15944 7967 15945 7938 15945 7964 15945 7967 15946 7964 15946 7963 15946 7963 15947 7964 15947 7937 15947 7963 15948 7937 15948 7965 15948 7962 15949 8649 15949 7963 15949 7963 15950 8649 15950 7966 15950 7963 15951 7966 15951 7967 15951 7967 15952 7966 15952 7968 15952 7967 15953 7968 15953 7969 15953 7969 15954 7968 15954 7973 15954 7969 15955 7973 15955 7970 15955 7970 15956 7973 15956 10144 15956 8649 15957 7971 15957 7966 15957 7966 15958 7971 15958 7974 15958 7966 15959 7974 15959 7968 15959 7968 15960 7974 15960 7972 15960 7968 15961 7972 15961 7973 15961 7973 15962 7972 15962 7976 15962 7973 15963 7976 15963 10144 15963 10144 15964 7976 15964 10145 15964 7971 15965 7978 15965 7974 15965 7974 15966 7978 15966 7979 15966 7974 15967 7979 15967 7972 15967 7972 15968 7979 15968 7975 15968 7972 15969 7975 15969 7976 15969 7976 15970 7975 15970 7980 15970 7976 15971 7980 15971 10145 15971 10145 15972 7980 15972 7977 15972 7978 15973 11843 15973 11836 15973 7978 15974 11836 15974 7979 15974 7979 15975 11836 15975 11837 15975 7979 15976 11837 15976 7975 15976 7975 15977 11837 15977 11841 15977 7975 15978 11841 15978 7980 15978 7980 15979 11841 15979 11839 15979 7980 15980 11839 15980 7977 15980 7981 15981 7989 15981 11810 15981 11810 15982 7982 15982 7981 15982 7981 15983 7982 15983 11801 15983 7981 15984 11801 15984 7988 15984 7988 15985 11801 15985 7987 15985 7987 15986 11801 15986 7984 15986 7987 15987 7984 15987 7983 15987 7983 15988 7984 15988 7985 15988 7985 15989 7984 15989 8641 15989 7985 15990 8641 15990 8640 15990 8640 15991 7990 15991 7985 15991 7985 15992 7990 15992 7986 15992 7985 15993 7986 15993 7983 15993 7983 15994 7986 15994 7987 15994 7987 15995 7986 15995 7991 15995 7987 15996 7991 15996 7988 15996 7988 15997 7991 15997 7993 15997 7988 15998 7993 15998 7981 15998 7981 15999 7993 15999 7994 15999 7981 16000 7994 16000 7989 16000 7990 16001 9093 16001 7986 16001 7986 16002 9093 16002 8000 16002 7986 16003 8000 16003 7991 16003 7991 16004 8000 16004 7992 16004 7991 16005 7992 16005 7993 16005 7993 16006 7992 16006 7998 16006 7993 16007 7998 16007 7994 16007 7994 16008 7998 16008 1813 16008 7997 16009 10160 16009 7998 16009 7998 16010 10160 16010 10161 16010 7998 16011 10161 16011 1813 16011 8000 16012 9093 16012 8001 16012 9096 16013 8006 16013 8004 16013 7995 16014 7997 16014 7996 16014 7996 16015 7997 16015 7998 16015 7996 16016 7998 16016 7999 16016 7999 16017 7998 16017 7992 16017 7999 16018 7992 16018 8004 16018 8004 16019 7992 16019 8000 16019 8004 16020 8000 16020 9096 16020 9096 16021 8000 16021 8001 16021 9060 16022 8011 16022 8005 16022 8003 16023 10208 16023 10191 16023 8002 16024 10192 16024 7996 16024 7996 16025 10192 16025 10175 16025 7996 16026 10175 16026 10178 16026 10178 16027 10177 16027 7996 16027 7996 16028 10177 16028 10176 16028 7996 16029 10176 16029 7995 16029 10191 16030 8002 16030 8003 16030 8003 16031 8002 16031 7996 16031 8003 16032 7996 16032 8010 16032 8010 16033 7996 16033 7999 16033 8010 16034 7999 16034 8005 16034 8005 16035 7999 16035 8004 16035 8005 16036 8004 16036 9060 16036 9060 16037 8004 16037 8006 16037 8009 16038 10208 16038 8003 16038 8007 16039 8008 16039 8009 16039 8009 16040 8003 16040 8007 16040 8007 16041 8003 16041 8010 16041 8007 16042 8010 16042 8014 16042 8014 16043 8010 16043 8005 16043 8014 16044 8005 16044 8013 16044 8013 16045 8005 16045 8011 16045 8013 16046 8011 16046 9514 16046 8027 16047 8025 16047 8016 16047 8026 16048 9789 16048 8048 16048 8013 16049 9514 16049 9555 16049 9555 16050 8012 16050 8013 16050 8013 16051 8012 16051 10104 16051 8013 16052 10104 16052 8019 16052 8007 16053 8014 16053 8015 16053 8015 16054 8014 16054 8016 16054 8015 16055 8016 16055 8017 16055 8017 16056 8016 16056 8025 16056 8023 16057 10337 16057 8017 16057 8017 16058 10337 16058 10210 16058 8017 16059 10210 16059 8015 16059 8015 16060 10210 16060 8008 16060 8015 16061 8008 16061 8007 16061 10342 16062 8034 16062 8018 16062 8018 16063 8034 16063 8033 16063 10104 16064 10105 16064 8019 16064 8019 16065 10105 16065 8020 16065 8019 16066 8020 16066 8022 16066 8022 16067 8020 16067 10086 16067 10086 16068 8021 16068 8027 16068 10086 16069 8027 16069 8022 16069 8022 16070 8027 16070 8016 16070 8022 16071 8016 16071 8019 16071 8019 16072 8016 16072 8014 16072 8019 16073 8014 16073 8013 16073 10342 16074 8023 16074 8034 16074 8034 16075 8023 16075 8017 16075 8034 16076 8017 16076 8024 16076 8024 16077 8017 16077 8025 16077 8024 16078 8025 16078 8048 16078 8048 16079 8025 16079 8027 16079 8048 16080 8027 16080 8026 16080 8026 16081 8027 16081 8021 16081 9840 16082 8049 16082 9609 16082 9609 16083 8049 16083 8028 16083 9609 16084 8028 16084 9610 16084 8029 16085 9612 16085 8028 16085 8028 16086 9612 16086 9611 16086 8028 16087 9611 16087 9610 16087 9788 16088 9831 16088 8030 16088 8030 16089 9831 16089 8031 16089 8030 16090 8031 16090 8029 16090 8029 16091 8031 16091 9833 16091 8029 16092 9833 16092 9612 16092 8032 16093 8024 16093 8048 16093 8033 16094 8034 16094 8035 16094 8035 16095 8034 16095 8036 16095 8035 16096 8036 16096 10330 16096 10330 16097 8036 16097 10331 16097 10331 16098 8036 16098 8047 16098 10331 16099 8047 16099 10327 16099 10327 16100 8047 16100 8037 16100 10327 16101 8037 16101 8038 16101 8045 16102 8042 16102 8039 16102 8039 16103 8042 16103 8040 16103 10328 16104 8040 16104 8041 16104 8041 16105 8040 16105 8042 16105 8041 16106 8042 16106 8043 16106 8043 16107 8042 16107 8044 16107 8044 16108 8042 16108 8045 16108 8044 16109 8045 16109 8046 16109 8039 16110 8038 16110 8045 16110 8045 16111 8038 16111 8037 16111 8045 16112 8037 16112 8046 16112 8046 16113 8037 16113 8047 16113 8046 16114 8047 16114 8032 16114 8032 16115 8047 16115 8036 16115 8032 16116 8036 16116 8024 16116 8024 16117 8036 16117 8034 16117 9789 16118 9788 16118 8048 16118 8048 16119 9788 16119 8030 16119 8048 16120 8030 16120 8032 16120 8032 16121 8030 16121 8029 16121 8032 16122 8029 16122 8046 16122 8046 16123 8029 16123 8028 16123 8046 16124 8028 16124 8044 16124 8044 16125 8028 16125 8049 16125 8044 16126 8049 16126 8043 16126 8043 16127 8049 16127 8120 16127 10222 16128 8051 16128 8050 16128 8050 16129 8051 16129 8053 16129 8050 16130 8053 16130 10325 16130 10325 16131 8053 16131 8052 16131 8052 16132 8053 16132 8054 16132 8052 16133 8054 16133 10326 16133 8087 16134 8055 16134 8056 16134 8056 16135 8055 16135 8057 16135 8056 16136 8057 16136 8089 16136 8089 16137 8057 16137 10326 16137 8089 16138 10326 16138 8058 16138 8058 16139 10326 16139 8054 16139 8059 16140 10135 16140 8082 16140 8082 16141 10135 16141 8060 16141 8082 16142 8060 16142 8083 16142 8083 16143 8060 16143 8061 16143 8083 16144 8061 16144 8085 16144 8085 16145 8061 16145 8088 16145 8062 16146 8081 16146 8064 16146 8078 16147 10232 16147 8063 16147 8063 16148 10232 16148 10229 16148 8063 16149 10229 16149 8064 16149 8064 16150 10229 16150 10230 16150 8064 16151 10230 16151 8062 16151 8065 16152 8077 16152 8066 16152 8066 16153 8077 16153 8067 16153 8066 16154 8067 16154 8068 16154 8068 16155 8067 16155 8075 16155 8068 16156 8075 16156 8069 16156 8069 16157 8075 16157 8073 16157 8069 16158 8073 16158 10237 16158 8124 16159 8070 16159 8122 16159 8122 16160 8070 16160 8071 16160 8122 16161 8071 16161 8121 16161 8074 16162 8071 16162 8072 16162 8072 16163 8071 16163 8070 16163 8072 16164 8070 16164 10238 16164 10238 16165 8070 16165 8124 16165 10238 16166 8124 16166 10240 16166 10238 16167 10237 16167 8072 16167 8072 16168 10237 16168 8073 16168 8072 16169 8073 16169 8074 16169 8074 16170 8073 16170 8075 16170 8074 16171 8075 16171 8102 16171 8102 16172 8075 16172 8067 16172 8102 16173 8067 16173 8076 16173 8076 16174 8067 16174 8077 16174 8076 16175 8077 16175 8100 16175 8065 16176 10232 16176 8077 16176 8077 16177 10232 16177 8078 16177 8077 16178 8078 16178 8100 16178 8100 16179 8078 16179 8063 16179 8100 16180 8063 16180 8079 16180 8079 16181 8063 16181 8064 16181 8079 16182 8064 16182 8080 16182 8080 16183 8064 16183 8081 16183 8080 16184 8081 16184 8099 16184 8062 16185 8059 16185 8081 16185 8081 16186 8059 16186 8082 16186 8081 16187 8082 16187 8099 16187 8099 16188 8082 16188 8083 16188 8099 16189 8083 16189 8084 16189 8084 16190 8083 16190 8085 16190 8084 16191 8085 16191 8086 16191 8086 16192 8085 16192 8088 16192 8086 16193 8088 16193 8097 16193 8061 16194 8087 16194 8088 16194 8088 16195 8087 16195 8056 16195 8088 16196 8056 16196 8097 16196 8097 16197 8056 16197 8089 16197 8097 16198 8089 16198 8090 16198 8090 16199 8089 16199 8058 16199 8090 16200 8058 16200 8094 16200 8094 16201 8058 16201 8054 16201 8094 16202 8054 16202 8093 16202 8093 16203 8054 16203 8053 16203 8093 16204 8053 16204 8091 16204 8091 16205 8053 16205 8051 16205 8091 16206 8051 16206 8041 16206 8041 16207 8051 16207 10222 16207 8041 16208 10222 16208 10328 16208 8041 16209 8043 16209 8091 16209 8091 16210 8043 16210 8120 16210 8091 16211 8120 16211 8093 16211 8093 16212 8120 16212 8092 16212 8093 16213 8092 16213 8094 16213 8094 16214 8092 16214 8095 16214 8094 16215 8095 16215 8090 16215 8090 16216 8095 16216 8096 16216 8090 16217 8096 16217 8097 16217 8097 16218 8096 16218 8116 16218 8097 16219 8116 16219 8086 16219 8086 16220 8116 16220 8098 16220 8086 16221 8098 16221 8084 16221 8084 16222 8098 16222 8114 16222 8084 16223 8114 16223 8099 16223 8099 16224 8114 16224 8113 16224 8099 16225 8113 16225 8080 16225 8080 16226 8113 16226 8111 16226 8080 16227 8111 16227 8079 16227 8079 16228 8111 16228 8110 16228 8079 16229 8110 16229 8100 16229 8100 16230 8110 16230 8108 16230 8100 16231 8108 16231 8076 16231 8076 16232 8108 16232 8101 16232 8076 16233 8101 16233 8102 16233 8102 16234 8101 16234 8107 16234 8102 16235 8107 16235 8074 16235 8074 16236 8107 16236 8106 16236 8074 16237 8106 16237 8071 16237 8071 16238 8106 16238 8103 16238 8071 16239 8103 16239 8121 16239 8121 16240 8103 16240 8104 16240 8104 16241 8103 16241 8105 16241 8105 16242 8103 16242 8106 16242 8105 16243 8106 16243 9625 16243 9625 16244 8106 16244 8107 16244 9625 16245 8107 16245 9623 16245 9623 16246 8107 16246 8101 16246 9623 16247 8101 16247 9621 16247 9621 16248 8101 16248 8108 16248 9621 16249 8108 16249 8109 16249 8109 16250 8108 16250 8110 16250 8109 16251 8110 16251 8112 16251 8112 16252 8110 16252 8111 16252 8112 16253 8111 16253 9618 16253 9618 16254 8111 16254 8113 16254 9618 16255 8113 16255 8115 16255 8115 16256 8113 16256 8114 16256 8115 16257 8114 16257 9616 16257 9616 16258 8114 16258 8098 16258 9616 16259 8098 16259 9615 16259 9615 16260 8098 16260 8116 16260 9615 16261 8116 16261 9826 16261 9826 16262 8116 16262 8096 16262 9826 16263 8096 16263 9827 16263 9827 16264 8096 16264 8095 16264 9827 16265 8095 16265 8117 16265 8117 16266 8095 16266 8092 16266 8117 16267 8092 16267 8118 16267 8118 16268 8092 16268 8120 16268 8118 16269 8120 16269 8119 16269 8119 16270 8120 16270 8049 16270 8119 16271 8049 16271 9840 16271 10241 16272 10240 16272 8124 16272 8104 16273 8127 16273 8121 16273 8121 16274 8127 16274 8129 16274 8121 16275 8129 16275 8122 16275 8122 16276 8129 16276 8123 16276 8122 16277 8123 16277 8124 16277 8124 16278 8123 16278 8132 16278 8124 16279 8132 16279 10241 16279 10241 16280 8132 16280 8125 16280 8136 16281 8126 16281 10254 16281 10024 16282 9528 16282 8141 16282 9926 16283 10029 16283 8139 16283 8139 16284 10029 16284 10009 16284 8139 16285 10009 16285 10008 16285 8129 16286 8127 16286 9926 16286 8128 16287 8125 16287 8132 16287 8128 16288 8132 16288 8133 16288 8131 16289 8130 16289 10253 16289 10253 16290 8130 16290 10254 16290 9926 16291 8139 16291 8129 16291 8129 16292 8139 16292 8137 16292 8129 16293 8137 16293 8123 16293 8123 16294 8137 16294 8130 16294 8123 16295 8130 16295 8132 16295 8132 16296 8130 16296 8131 16296 8132 16297 8131 16297 8133 16297 10034 16298 10024 16298 8140 16298 8140 16299 10024 16299 8141 16299 8140 16300 8141 16300 8138 16300 8138 16301 8141 16301 8142 16301 8138 16302 8142 16302 8136 16302 8136 16303 8142 16303 8134 16303 8136 16304 8134 16304 8126 16304 8126 16305 8134 16305 8135 16305 10254 16306 8130 16306 8136 16306 8136 16307 8130 16307 8137 16307 8136 16308 8137 16308 8138 16308 8138 16309 8137 16309 8139 16309 8138 16310 8139 16310 8140 16310 8140 16311 8139 16311 10008 16311 8140 16312 10008 16312 10034 16312 8141 16313 9528 16313 9033 16313 8148 16314 10258 16314 10257 16314 9033 16315 8146 16315 8141 16315 8141 16316 8146 16316 8143 16316 8141 16317 8143 16317 8142 16317 8142 16318 8143 16318 8148 16318 8142 16319 8148 16319 8134 16319 8134 16320 8148 16320 10257 16320 8134 16321 10257 16321 8135 16321 9025 16322 9080 16322 8147 16322 8147 16323 9080 16323 8977 16323 8147 16324 8977 16324 8978 16324 10276 16325 8154 16325 8144 16325 8144 16326 8154 16326 8149 16326 10277 16327 8145 16327 8148 16327 8148 16328 8145 16328 10252 16328 8148 16329 10252 16329 10258 16329 9033 16330 9025 16330 8146 16330 8146 16331 9025 16331 8147 16331 8146 16332 8147 16332 8143 16332 8143 16333 8147 16333 8155 16333 8143 16334 8155 16334 8148 16334 8148 16335 8155 16335 8154 16335 8148 16336 8154 16336 10277 16336 10277 16337 8154 16337 10276 16337 8153 16338 8149 16338 8154 16338 9206 16339 9261 16339 8157 16339 8152 16340 8151 16340 8150 16340 8150 16341 8151 16341 10308 16341 8152 16342 8153 16342 8151 16342 8151 16343 8153 16343 8154 16343 8151 16344 8154 16344 8161 16344 8161 16345 8154 16345 8155 16345 8161 16346 8155 16346 8157 16346 8157 16347 8155 16347 8147 16347 8157 16348 8147 16348 9206 16348 9206 16349 8147 16349 8978 16349 10306 16350 10308 16350 8151 16350 8157 16351 9261 16351 8156 16351 8156 16352 8158 16352 8157 16352 8157 16353 8158 16353 7439 16353 8157 16354 7439 16354 7447 16354 8159 16355 8161 16355 8160 16355 8160 16356 8161 16356 8157 16356 8160 16357 8157 16357 7446 16357 7446 16358 8157 16358 7447 16358 8159 16359 7443 16359 8161 16359 8161 16360 7443 16360 8162 16360 8161 16361 8162 16361 8151 16361 8151 16362 8162 16362 7442 16362 8151 16363 7442 16363 10306 16363 10306 16364 7442 16364 10309 16364 6330 16365 7462 16365 6345 16365 6345 16366 7462 16366 7464 16366 6345 16367 7464 16367 6339 16367 6339 16368 7464 16368 8163 16368 6339 16369 8163 16369 8638 16369 8172 16370 8635 16370 8173 16370 8175 16371 8164 16371 8174 16371 8643 16372 8176 16372 8644 16372 10584 16373 8165 16373 8176 16373 10591 16374 8166 16374 8635 16374 8635 16375 8166 16375 8167 16375 8635 16376 8167 16376 8173 16376 8173 16377 8167 16377 10590 16377 8179 16378 6332 16378 8168 16378 8168 16379 6332 16379 6331 16379 8170 16380 8169 16380 6335 16380 6335 16381 8169 16381 8643 16381 6335 16382 8643 16382 8267 16382 8176 16383 8643 16383 8177 16383 8177 16384 8643 16384 8169 16384 8177 16385 8169 16385 8179 16385 8179 16386 8169 16386 8170 16386 8179 16387 8170 16387 6332 16387 8171 16388 8172 16388 8178 16388 8178 16389 8172 16389 8173 16389 8178 16390 8173 16390 8174 16390 8174 16391 8173 16391 10590 16391 8174 16392 10590 16392 8175 16392 8175 16393 10584 16393 8164 16393 8164 16394 10584 16394 8176 16394 8164 16395 8176 16395 8174 16395 8174 16396 8176 16396 8177 16396 8174 16397 8177 16397 8178 16397 8178 16398 8177 16398 8179 16398 8178 16399 8179 16399 8171 16399 8171 16400 8179 16400 8168 16400 10566 16401 8180 16401 7775 16401 8181 16402 10566 16402 8182 16402 8182 16403 10566 16403 7775 16403 8182 16404 7775 16404 8183 16404 8183 16405 7775 16405 8184 16405 8183 16406 8184 16406 8185 16406 8185 16407 8184 16407 7776 16407 8185 16408 7776 16408 8187 16408 8187 16409 7776 16409 8186 16409 8187 16410 8186 16410 8188 16410 10456 16411 8189 16411 8190 16411 10456 16412 8190 16412 7737 16412 7737 16413 8190 16413 8191 16413 7737 16414 8191 16414 8192 16414 8191 16415 10402 16415 8192 16415 8192 16416 10402 16416 8194 16416 8192 16417 8194 16417 7735 16417 7735 16418 8194 16418 8193 16418 8193 16419 8194 16419 10404 16419 8193 16420 10404 16420 10403 16420 8685 16421 7483 16421 7488 16421 8614 16422 10445 16422 8195 16422 8195 16423 10445 16423 10443 16423 8195 16424 10443 16424 8196 16424 8196 16425 10443 16425 8197 16425 8196 16426 8197 16426 7488 16426 7488 16427 8197 16427 10444 16427 7488 16428 10444 16428 8685 16428 8685 16429 10444 16429 8686 16429 10352 16430 11572 16430 10353 16430 10353 16431 11572 16431 11570 16431 10353 16432 11570 16432 8198 16432 8198 16433 11570 16433 7696 16433 8198 16434 7696 16434 10374 16434 8199 16435 10568 16435 8204 16435 8199 16436 8204 16436 8206 16436 7840 16437 10716 16437 8207 16437 7840 16438 8205 16438 8200 16438 8200 16439 8205 16439 8201 16439 8200 16440 8201 16440 8203 16440 8202 16441 8203 16441 8204 16441 8204 16442 8203 16442 8201 16442 8204 16443 8201 16443 8206 16443 8206 16444 8201 16444 8205 16444 8206 16445 8205 16445 10410 16445 10410 16446 8205 16446 7840 16446 10410 16447 7840 16447 10423 16447 10423 16448 7840 16448 8207 16448 10423 16449 8207 16449 8208 16449 8209 16450 8210 16450 8625 16450 8625 16451 8210 16451 8211 16451 8216 16452 8215 16452 8214 16452 8214 16453 8212 16453 8216 16453 8216 16454 8212 16454 10412 16454 8216 16455 10412 16455 8210 16455 8210 16456 10412 16456 8213 16456 8210 16457 8213 16457 8211 16457 6361 16458 8214 16458 6363 16458 6363 16459 8214 16459 8215 16459 6363 16460 8215 16460 6364 16460 6364 16461 8215 16461 7559 16461 7559 16462 8215 16462 8216 16462 7559 16463 8216 16463 8217 16463 8217 16464 8216 16464 8210 16464 8217 16465 8210 16465 8218 16465 8218 16466 8210 16466 8209 16466 8218 16467 8209 16467 11642 16467 7870 16468 7861 16468 8224 16468 10571 16469 8219 16469 8220 16469 8222 16470 8221 16470 10730 16470 8222 16471 10730 16471 8227 16471 8223 16472 8228 16472 8224 16472 7860 16473 7859 16473 8225 16473 8225 16474 7859 16474 7853 16474 8225 16475 7853 16475 8220 16475 8220 16476 7853 16476 7854 16476 8220 16477 7854 16477 10571 16477 7861 16478 7860 16478 8224 16478 8224 16479 7860 16479 8225 16479 8224 16480 8225 16480 8223 16480 8223 16481 8225 16481 8220 16481 8223 16482 8220 16482 10420 16482 10420 16483 8220 16483 8219 16483 10420 16484 8219 16484 10421 16484 8226 16485 7870 16485 10730 16485 10730 16486 7870 16486 8224 16486 10730 16487 8224 16487 8227 16487 8227 16488 8224 16488 8228 16488 8672 16489 8238 16489 8229 16489 8229 16490 8238 16490 10442 16490 10442 16491 8238 16491 10441 16491 10441 16492 8238 16492 8230 16492 10441 16493 8230 16493 8231 16493 8231 16494 8230 16494 8232 16494 8231 16495 8232 16495 8233 16495 8233 16496 8232 16496 8234 16496 8233 16497 8234 16497 10725 16497 7924 16498 8234 16498 7912 16498 7912 16499 8234 16499 8232 16499 7912 16500 8232 16500 8235 16500 8235 16501 8232 16501 8230 16501 8235 16502 8230 16502 7913 16502 7913 16503 8230 16503 8236 16503 8236 16504 8230 16504 8238 16504 8236 16505 8238 16505 7916 16505 7916 16506 8238 16506 8237 16506 8237 16507 8238 16507 8672 16507 8237 16508 8672 16508 8673 16508 10448 16509 8239 16509 8240 16509 8240 16510 8239 16510 10450 16510 8240 16511 10450 16511 8615 16511 8615 16512 10450 16512 10451 16512 8615 16513 10451 16513 8616 16513 8240 16514 8244 16514 10448 16514 10448 16515 8244 16515 8243 16515 10448 16516 8243 16516 8242 16516 8241 16517 7521 16517 8677 16517 10449 16518 8242 16518 8677 16518 8677 16519 8242 16519 8243 16519 8677 16520 8243 16520 8241 16520 8241 16521 8243 16521 8244 16521 8241 16522 8244 16522 8245 16522 8245 16523 8244 16523 8240 16523 8245 16524 8240 16524 7520 16524 7520 16525 8240 16525 8615 16525 7520 16526 8615 16526 7518 16526 8254 16527 8253 16527 8251 16527 8246 16528 6362 16528 8247 16528 8247 16529 6362 16529 8257 16529 8247 16530 8257 16530 8248 16530 8248 16531 8257 16531 8249 16531 8249 16532 8257 16532 8256 16532 8249 16533 8256 16533 8250 16533 8250 16534 8256 16534 10413 16534 10413 16535 8256 16535 8251 16535 10413 16536 8251 16536 8252 16536 8252 16537 8251 16537 8253 16537 8252 16538 8253 16538 10414 16538 8254 16539 8251 16539 8255 16539 8255 16540 8251 16540 8256 16540 8255 16541 8256 16541 7537 16541 7537 16542 8256 16542 8257 16542 7537 16543 8257 16543 7536 16543 7536 16544 8257 16544 6362 16544 7536 16545 6362 16545 8258 16545 8263 16546 7462 16546 6330 16546 8259 16547 8261 16547 8260 16547 8260 16548 8261 16548 6346 16548 8262 16549 6329 16549 6328 16549 6338 16550 8270 16550 6328 16550 6328 16551 8270 16551 8260 16551 6328 16552 8260 16552 8262 16552 8262 16553 8260 16553 6346 16553 8264 16554 8266 16554 8263 16554 6330 16555 8259 16555 8263 16555 8263 16556 8259 16556 8260 16556 8263 16557 8260 16557 8264 16557 8264 16558 8260 16558 11788 16558 11814 16559 8265 16559 11813 16559 11813 16560 8265 16560 8263 16560 11813 16561 8263 16561 11812 16561 11812 16562 8263 16562 8266 16562 8267 16563 8645 16563 8268 16563 8268 16564 8645 16564 8270 16564 8268 16565 8270 16565 8269 16565 8269 16566 8270 16566 6338 16566 6592 16567 8314 16567 8271 16567 8271 16568 8314 16568 8273 16568 8271 16569 8273 16569 8272 16569 8272 16570 8273 16570 8274 16570 8272 16571 8274 16571 6600 16571 6600 16572 8274 16572 6601 16572 6601 16573 8274 16573 8275 16573 6601 16574 8275 16574 6603 16574 6603 16575 8275 16575 6617 16575 6617 16576 8275 16576 8333 16576 6617 16577 8333 16577 6618 16577 8276 16578 6637 16578 8277 16578 8276 16579 8277 16579 6639 16579 6639 16580 8277 16580 8313 16580 6639 16581 8313 16581 8278 16581 8278 16582 8313 16582 8279 16582 8278 16583 8279 16583 8280 16583 8280 16584 8279 16584 8314 16584 8280 16585 8314 16585 6592 16585 6735 16586 8312 16586 8281 16586 8281 16587 8312 16587 8282 16587 8281 16588 8282 16588 8283 16588 8283 16589 8282 16589 8284 16589 8284 16590 8282 16590 8277 16590 8284 16591 8277 16591 6637 16591 6548 16592 8335 16592 8285 16592 6548 16593 8285 16593 6530 16593 8285 16594 8328 16594 6530 16594 6530 16595 8328 16595 8289 16595 6530 16596 8289 16596 6531 16596 8287 16597 8329 16597 6419 16597 6419 16598 8286 16598 8287 16598 8287 16599 8286 16599 8288 16599 8287 16600 8288 16600 8289 16600 8289 16601 8288 16601 8290 16601 8289 16602 8290 16602 6531 16602 6378 16603 8291 16603 8332 16603 8332 16604 8291 16604 8315 16604 6391 16605 8325 16605 6393 16605 6393 16606 8325 16606 8293 16606 8291 16607 8292 16607 8315 16607 8315 16608 8292 16608 6401 16608 8315 16609 6401 16609 8293 16609 8293 16610 6401 16610 6390 16610 8293 16611 6390 16611 6393 16611 8317 16612 8321 16612 8331 16612 8331 16613 8321 16613 8294 16613 8294 16614 8321 16614 8295 16614 8295 16615 8321 16615 8320 16615 8295 16616 8320 16616 11412 16616 6556 16617 8297 16617 8296 16617 8296 16618 8297 16618 8318 16618 8296 16619 8318 16619 8298 16619 8298 16620 8318 16620 8299 16620 8299 16621 8318 16621 8316 16621 8299 16622 8316 16622 8300 16622 6626 16623 8301 16623 8304 16623 6702 16624 8302 16624 8303 16624 8303 16625 8302 16625 6672 16625 8303 16626 6672 16626 8304 16626 8304 16627 6672 16627 6675 16627 8304 16628 6675 16628 6626 16628 6686 16629 8305 16629 6687 16629 6687 16630 8305 16630 8306 16630 6687 16631 8306 16631 6689 16631 6686 16632 6685 16632 8305 16632 8305 16633 6685 16633 6658 16633 8305 16634 6658 16634 8303 16634 8303 16635 6658 16635 6657 16635 8303 16636 6657 16636 6702 16636 6689 16637 8306 16637 6683 16637 6683 16638 8306 16638 8322 16638 6683 16639 8322 16639 6684 16639 6684 16640 8322 16640 8307 16640 6684 16641 8307 16641 6681 16641 6681 16642 8307 16642 8326 16642 6681 16643 8326 16643 11401 16643 8308 16644 8323 16644 6624 16644 6624 16645 8323 16645 8309 16645 6624 16646 8309 16646 8310 16646 8310 16647 8309 16647 8311 16647 8310 16648 8311 16648 6628 16648 6628 16649 8311 16649 6627 16649 6627 16650 8311 16650 8301 16650 6627 16651 8301 16651 6626 16651 8321 16652 8318 16652 8297 16652 8282 16653 8334 16653 8277 16653 8277 16654 8334 16654 8333 16654 8311 16655 8309 16655 8312 16655 8312 16656 8309 16656 8282 16656 11404 16657 11409 16657 11410 16657 8275 16658 8274 16658 8333 16658 8333 16659 8274 16659 8273 16659 8313 16660 8277 16660 8279 16660 8279 16661 8277 16661 8333 16661 8279 16662 8333 16662 8314 16662 8314 16663 8333 16663 8273 16663 8305 16664 8303 16664 8304 16664 8315 16665 8316 16665 8332 16665 8332 16666 8316 16666 8318 16666 8332 16667 8318 16667 8317 16667 8317 16668 8318 16668 8321 16668 8319 16669 11407 16669 11406 16669 8282 16670 8309 16670 8334 16670 8334 16671 8309 16671 8323 16671 8334 16672 8323 16672 8337 16672 11406 16673 11404 16673 8319 16673 8319 16674 11404 16674 11410 16674 8319 16675 11410 16675 8297 16675 8297 16676 11410 16676 8320 16676 8297 16677 8320 16677 8321 16677 8307 16678 8322 16678 8306 16678 8323 16679 8316 16679 8337 16679 8337 16680 8316 16680 8315 16680 8337 16681 8315 16681 8324 16681 8324 16682 8315 16682 8293 16682 8324 16683 8293 16683 8285 16683 8285 16684 8293 16684 8325 16684 8285 16685 8325 16685 11416 16685 8306 16686 8305 16686 8307 16686 8307 16687 8305 16687 8304 16687 8307 16688 8304 16688 8326 16688 8326 16689 8304 16689 8301 16689 8326 16690 8301 16690 8327 16690 8327 16691 8301 16691 8311 16691 8327 16692 8311 16692 8330 16692 8330 16693 8311 16693 8312 16693 8289 16694 8328 16694 8287 16694 8287 16695 8328 16695 8285 16695 8287 16696 8285 16696 8329 16696 8329 16697 8285 16697 11416 16697 8329 16698 11416 16698 11414 16698 8312 16699 6735 16699 6736 16699 11403 16700 8330 16700 6742 16700 6742 16701 8330 16701 8312 16701 6742 16702 8312 16702 6737 16702 6737 16703 8312 16703 6736 16703 8317 16704 8331 16704 8332 16704 8332 16705 8331 16705 6378 16705 6618 16706 8333 16706 6580 16706 6580 16707 8333 16707 8334 16707 6580 16708 8334 16708 6579 16708 6579 16709 8334 16709 6578 16709 6578 16710 8334 16710 8337 16710 6578 16711 8337 16711 6576 16711 8324 16712 8285 16712 8335 16712 8335 16713 8336 16713 8324 16713 8324 16714 8336 16714 6572 16714 8324 16715 6572 16715 8337 16715 8337 16716 6572 16716 8338 16716 8337 16717 8338 16717 6576 16717 10977 16718 8339 16718 8340 16718 8340 16719 8339 16719 8341 16719 8340 16720 8341 16720 10975 16720 10975 16721 8341 16721 10917 16721 10975 16722 10917 16722 10973 16722 10973 16723 10917 16723 10909 16723 10973 16724 10909 16724 10971 16724 10971 16725 10909 16725 8342 16725 10971 16726 8342 16726 8343 16726 8343 16727 8342 16727 10910 16727 8343 16728 10910 16728 8344 16728 8344 16729 10910 16729 8345 16729 8344 16730 8345 16730 8346 16730 8346 16731 8345 16731 10911 16731 8346 16732 10911 16732 8347 16732 8347 16733 10911 16733 10913 16733 8347 16734 10913 16734 10968 16734 10968 16735 10913 16735 8348 16735 10968 16736 8348 16736 10979 16736 10979 16737 8348 16737 10915 16737 10979 16738 10915 16738 10978 16738 10978 16739 10915 16739 8349 16739 10978 16740 8349 16740 10977 16740 10977 16741 8349 16741 8339 16741 10937 16742 8351 16742 8350 16742 8350 16743 8351 16743 8353 16743 8350 16744 8353 16744 8352 16744 8352 16745 8353 16745 10907 16745 8352 16746 10907 16746 8354 16746 8354 16747 10907 16747 8355 16747 8354 16748 8355 16748 10933 16748 10933 16749 8355 16749 10898 16749 10933 16750 10898 16750 8356 16750 8356 16751 10898 16751 10899 16751 8356 16752 10899 16752 8357 16752 8357 16753 10899 16753 10902 16753 8357 16754 10902 16754 8358 16754 8358 16755 10902 16755 8360 16755 8358 16756 8360 16756 8359 16756 8359 16757 8360 16757 8361 16757 8359 16758 8361 16758 10939 16758 10939 16759 8361 16759 10904 16759 10939 16760 10904 16760 10938 16760 10938 16761 10904 16761 8362 16761 10938 16762 8362 16762 8363 16762 8363 16763 8362 16763 8364 16763 8363 16764 8364 16764 10937 16764 10937 16765 8364 16765 8351 16765 8376 16766 10891 16766 8365 16766 8365 16767 10891 16767 8366 16767 8365 16768 8366 16768 8367 16768 8367 16769 8366 16769 10892 16769 8367 16770 10892 16770 8368 16770 8368 16771 10892 16771 10893 16771 8368 16772 10893 16772 10993 16772 10993 16773 10893 16773 10894 16773 10993 16774 10894 16774 8369 16774 8369 16775 10894 16775 8370 16775 8369 16776 8370 16776 8371 16776 8371 16777 8370 16777 10895 16777 8371 16778 10895 16778 8372 16778 8372 16779 10895 16779 8374 16779 8372 16780 8374 16780 8373 16780 8373 16781 8374 16781 10887 16781 8373 16782 10887 16782 10991 16782 10991 16783 10887 16783 10888 16783 10991 16784 10888 16784 10990 16784 10990 16785 10888 16785 10889 16785 10990 16786 10889 16786 10988 16786 10988 16787 10889 16787 8375 16787 10988 16788 8375 16788 8376 16788 8376 16789 8375 16789 10891 16789 8389 16790 8377 16790 8378 16790 8378 16791 8377 16791 8379 16791 8378 16792 8379 16792 10994 16792 10994 16793 8379 16793 8380 16793 10994 16794 8380 16794 8381 16794 8381 16795 8380 16795 10880 16795 8381 16796 10880 16796 8382 16796 8382 16797 10880 16797 10881 16797 8382 16798 10881 16798 8383 16798 8383 16799 10881 16799 10883 16799 8383 16800 10883 16800 11001 16800 11001 16801 10883 16801 8384 16801 11001 16802 8384 16802 11000 16802 11000 16803 8384 16803 8385 16803 11000 16804 8385 16804 10998 16804 10998 16805 8385 16805 10886 16805 10998 16806 10886 16806 10997 16806 10997 16807 10886 16807 8386 16807 10997 16808 8386 16808 8387 16808 8387 16809 8386 16809 10878 16809 8387 16810 10878 16810 8388 16810 8388 16811 10878 16811 10879 16811 8388 16812 10879 16812 8389 16812 8389 16813 10879 16813 8377 16813 8404 16814 10870 16814 8390 16814 8390 16815 10870 16815 10871 16815 8390 16816 10871 16816 10985 16816 10985 16817 10871 16817 8391 16817 10985 16818 8391 16818 8392 16818 8392 16819 8391 16819 8393 16819 8392 16820 8393 16820 8394 16820 8394 16821 8393 16821 10874 16821 8394 16822 10874 16822 8395 16822 8395 16823 10874 16823 8396 16823 8395 16824 8396 16824 8397 16824 8397 16825 8396 16825 8399 16825 8397 16826 8399 16826 8398 16826 8398 16827 8399 16827 10875 16827 8398 16828 10875 16828 10982 16828 10982 16829 10875 16829 8400 16829 10982 16830 8400 16830 10981 16830 10981 16831 8400 16831 10867 16831 10981 16832 10867 16832 8401 16832 8401 16833 10867 16833 8402 16833 8401 16834 8402 16834 8403 16834 8403 16835 8402 16835 10869 16835 8403 16836 10869 16836 8404 16836 8404 16837 10869 16837 10870 16837 8405 16838 10862 16838 8406 16838 8406 16839 10862 16839 10863 16839 8406 16840 10863 16840 10945 16840 10945 16841 10863 16841 8407 16841 10945 16842 8407 16842 8408 16842 8408 16843 8407 16843 8409 16843 8408 16844 8409 16844 10943 16844 10943 16845 8409 16845 10854 16845 10943 16846 10854 16846 8410 16846 8410 16847 10854 16847 10856 16847 8410 16848 10856 16848 8412 16848 8412 16849 10856 16849 8411 16849 8412 16850 8411 16850 8413 16850 8413 16851 8411 16851 10857 16851 8413 16852 10857 16852 10941 16852 10941 16853 10857 16853 8414 16853 10941 16854 8414 16854 10952 16854 10952 16855 8414 16855 10858 16855 10952 16856 10858 16856 10950 16856 10950 16857 10858 16857 10859 16857 10950 16858 10859 16858 10948 16858 10948 16859 10859 16859 10860 16859 10948 16860 10860 16860 8405 16860 8405 16861 10860 16861 10862 16861 10964 16862 10849 16862 10961 16862 10961 16863 10849 16863 10851 16863 10961 16864 10851 16864 8415 16864 8415 16865 10851 16865 10853 16865 8415 16866 10853 16866 10960 16866 10960 16867 10853 16867 8416 16867 10960 16868 8416 16868 10959 16868 10959 16869 8416 16869 8417 16869 10959 16870 8417 16870 10958 16870 10958 16871 8417 16871 10842 16871 10958 16872 10842 16872 8418 16872 8418 16873 10842 16873 10843 16873 8418 16874 10843 16874 10956 16874 10956 16875 10843 16875 8419 16875 10956 16876 8419 16876 8420 16876 8420 16877 8419 16877 10845 16877 8420 16878 10845 16878 10954 16878 10954 16879 10845 16879 10847 16879 10954 16880 10847 16880 10967 16880 10967 16881 10847 16881 8421 16881 10967 16882 8421 16882 10965 16882 10965 16883 8421 16883 8422 16883 10965 16884 8422 16884 10964 16884 10964 16885 8422 16885 10849 16885 8433 16886 10836 16886 8423 16886 8423 16887 10836 16887 10837 16887 8423 16888 10837 16888 10926 16888 10926 16889 10837 16889 10838 16889 10926 16890 10838 16890 8424 16890 8424 16891 10838 16891 10839 16891 8424 16892 10839 16892 10925 16892 10925 16893 10839 16893 10826 16893 10925 16894 10826 16894 8425 16894 8425 16895 10826 16895 8426 16895 8425 16896 8426 16896 8427 16896 8427 16897 8426 16897 8428 16897 8427 16898 8428 16898 10921 16898 10921 16899 8428 16899 10829 16899 10921 16900 10829 16900 10919 16900 10919 16901 10829 16901 8430 16901 10919 16902 8430 16902 8429 16902 8429 16903 8430 16903 8431 16903 8429 16904 8431 16904 10929 16904 10929 16905 8431 16905 10833 16905 10929 16906 10833 16906 10928 16906 10928 16907 10833 16907 8432 16907 10928 16908 8432 16908 8433 16908 8433 16909 8432 16909 10836 16909 8449 16910 11466 16910 11074 16910 11074 16911 11466 16911 8434 16911 11074 16912 8434 16912 8435 16912 8435 16913 8434 16913 8436 16913 8435 16914 8436 16914 8437 16914 8437 16915 8436 16915 8438 16915 8437 16916 8438 16916 11075 16916 11075 16917 8438 16917 8439 16917 11075 16918 8439 16918 8440 16918 8440 16919 8439 16919 8441 16919 8440 16920 8441 16920 8442 16920 8442 16921 8441 16921 11463 16921 8442 16922 11463 16922 8443 16922 8443 16923 11463 16923 11462 16923 8443 16924 11462 16924 8444 16924 8444 16925 11462 16925 11460 16925 8444 16926 11460 16926 8445 16926 8445 16927 11460 16927 11459 16927 8445 16928 11459 16928 8446 16928 8446 16929 11459 16929 8447 16929 8446 16930 8447 16930 8448 16930 8448 16931 8447 16931 11467 16931 8448 16932 11467 16932 8449 16932 8449 16933 11467 16933 11466 16933 8467 16934 11435 16934 11019 16934 11019 16935 11435 16935 8450 16935 11019 16936 8450 16936 8451 16936 8451 16937 8450 16937 8452 16937 8451 16938 8452 16938 8453 16938 8453 16939 8452 16939 8455 16939 8453 16940 8455 16940 8454 16940 8454 16941 8455 16941 8456 16941 8454 16942 8456 16942 11014 16942 11014 16943 8456 16943 8457 16943 11014 16944 8457 16944 8458 16944 8458 16945 8457 16945 11429 16945 8458 16946 11429 16946 8459 16946 8459 16947 11429 16947 11428 16947 8459 16948 11428 16948 8460 16948 8460 16949 11428 16949 8461 16949 8460 16950 8461 16950 8463 16950 8463 16951 8461 16951 8462 16951 8463 16952 8462 16952 11017 16952 11017 16953 8462 16953 8464 16953 11017 16954 8464 16954 8465 16954 8465 16955 8464 16955 8466 16955 8465 16956 8466 16956 8467 16956 8467 16957 8466 16957 11435 16957 8468 16958 11448 16958 11039 16958 11039 16959 11448 16959 11446 16959 11039 16960 11446 16960 11040 16960 11040 16961 11446 16961 11445 16961 11040 16962 11445 16962 8469 16962 8469 16963 11445 16963 11444 16963 8469 16964 11444 16964 11028 16964 11028 16965 11444 16965 11443 16965 11028 16966 11443 16966 8470 16966 8470 16967 11443 16967 11441 16967 8470 16968 11441 16968 8471 16968 8471 16969 11441 16969 11439 16969 8471 16970 11439 16970 11030 16970 11030 16971 11439 16971 8472 16971 11030 16972 8472 16972 11032 16972 11032 16973 8472 16973 11450 16973 11032 16974 11450 16974 8473 16974 8473 16975 11450 16975 11449 16975 8473 16976 11449 16976 11035 16976 11035 16977 11449 16977 8474 16977 11035 16978 8474 16978 11037 16978 11037 16979 8474 16979 8475 16979 11037 16980 8475 16980 8468 16980 8468 16981 8475 16981 11448 16981 11058 16982 11457 16982 11059 16982 11059 16983 11457 16983 8476 16983 11059 16984 8476 16984 11060 16984 11060 16985 8476 16985 11455 16985 11060 16986 11455 16986 8477 16986 8477 16987 11455 16987 11454 16987 8477 16988 11454 16988 11048 16988 11048 16989 11454 16989 8478 16989 11048 16990 8478 16990 8479 16990 8479 16991 8478 16991 11453 16991 8479 16992 11453 16992 11050 16992 11050 16993 11453 16993 8480 16993 11050 16994 8480 16994 11051 16994 11051 16995 8480 16995 8481 16995 11051 16996 8481 16996 8482 16996 8482 16997 8481 16997 8483 16997 8482 16998 8483 16998 8484 16998 8484 16999 8483 16999 11458 16999 8484 17000 11458 17000 8485 17000 8485 17001 11458 17001 8486 17001 8485 17002 8486 17002 11057 17002 11057 17003 8486 17003 8487 17003 11057 17004 8487 17004 11058 17004 11058 17005 8487 17005 11457 17005 6806 17006 6805 17006 8488 17006 8488 17007 6805 17007 6793 17007 6773 17008 10546 17008 6748 17008 6748 17009 10546 17009 10545 17009 6806 17010 8488 17010 8489 17010 8491 17011 6762 17011 10553 17011 10553 17012 6762 17012 6764 17012 10553 17013 6764 17013 8489 17013 8489 17014 6764 17014 8490 17014 8489 17015 8490 17015 6806 17015 8491 17016 10553 17016 8492 17016 8492 17017 10553 17017 10551 17017 8492 17018 10551 17018 8493 17018 6780 17019 6779 17019 8494 17019 8494 17020 6779 17020 6777 17020 8494 17021 6777 17021 10551 17021 10551 17022 6777 17022 6760 17022 10551 17023 6760 17023 8493 17023 8497 17024 6770 17024 8496 17024 8496 17025 6770 17025 8495 17025 8496 17026 8495 17026 8494 17026 8494 17027 8495 17027 6769 17027 8494 17028 6769 17028 6780 17028 8496 17029 10548 17029 8497 17029 8497 17030 10548 17030 10546 17030 8497 17031 10546 17031 6773 17031 7201 17032 10525 17032 7214 17032 7214 17033 10525 17033 8498 17033 7214 17034 8498 17034 7190 17034 10530 17035 10528 17035 8500 17035 7139 17036 7165 17036 8499 17036 8499 17037 7165 17037 10530 17037 8499 17038 10530 17038 7138 17038 7138 17039 10530 17039 8500 17039 6939 17040 8501 17040 10519 17040 10519 17041 8501 17041 8502 17041 10519 17042 8502 17042 10520 17042 6874 17043 8509 17043 6872 17043 6872 17044 8509 17044 10511 17044 6872 17045 10511 17045 8503 17045 6939 17046 10519 17046 8504 17046 8504 17047 10519 17047 10502 17047 8504 17048 10502 17048 6925 17048 6925 17049 10502 17049 6913 17049 6913 17050 10502 17050 10517 17050 6913 17051 10517 17051 6914 17051 6914 17052 10517 17052 6916 17052 6916 17053 10517 17053 8505 17053 6916 17054 8505 17054 6918 17054 6918 17055 8505 17055 8506 17055 8506 17056 8505 17056 10514 17056 8506 17057 10514 17057 6920 17057 8514 17058 8507 17058 8513 17058 8513 17059 8507 17059 8508 17059 8513 17060 8508 17060 10514 17060 10514 17061 8508 17061 6903 17061 10514 17062 6903 17062 6920 17062 10511 17063 8509 17063 10512 17063 10512 17064 8509 17064 8510 17064 10512 17065 8510 17065 8511 17065 8511 17066 8512 17066 10512 17066 10512 17067 8512 17067 6892 17067 10512 17068 6892 17068 8513 17068 8513 17069 6892 17069 6890 17069 8513 17070 6890 17070 8514 17070 6865 17071 8515 17071 8516 17071 8518 17072 8516 17072 6807 17072 6807 17073 8516 17073 9023 17073 8517 17074 10962 17074 8518 17074 8518 17075 10962 17075 8519 17075 8518 17076 8519 17076 8516 17076 8516 17077 8519 17077 8520 17077 8516 17078 8520 17078 6865 17078 8531 17079 8521 17079 10957 17079 10957 17080 8521 17080 8522 17080 10957 17081 8522 17081 8523 17081 8523 17082 8522 17082 8532 17082 8523 17083 8532 17083 8520 17083 8520 17084 8532 17084 8524 17084 8520 17085 8524 17085 6861 17085 6861 17086 6862 17086 8520 17086 8520 17087 6862 17087 6863 17087 8520 17088 6863 17088 6865 17088 8517 17089 6808 17089 10962 17089 10962 17090 6808 17090 6810 17090 10962 17091 6810 17091 10963 17091 10963 17092 6810 17092 8534 17092 10963 17093 8534 17093 10966 17093 10966 17094 8534 17094 8525 17094 10966 17095 8525 17095 8526 17095 8526 17096 8525 17096 8544 17096 8526 17097 8544 17097 8527 17097 8527 17098 8544 17098 8545 17098 8527 17099 8545 17099 8529 17099 8529 17100 8545 17100 8528 17100 8529 17101 8528 17101 10955 17101 10955 17102 8528 17102 8530 17102 10955 17103 8530 17103 8531 17103 8531 17104 8530 17104 8538 17104 8531 17105 8538 17105 8521 17105 8532 17106 8522 17106 6860 17106 6860 17107 8522 17107 6829 17107 8543 17108 8525 17108 8533 17108 8533 17109 8525 17109 8534 17109 6829 17110 8522 17110 8535 17110 8535 17111 8522 17111 8521 17111 8535 17112 8521 17112 6828 17112 6828 17113 8521 17113 8536 17113 8536 17114 8521 17114 8538 17114 8536 17115 8538 17115 8537 17115 8537 17116 8538 17116 8539 17116 8539 17117 8538 17117 8530 17117 8539 17118 8530 17118 6825 17118 8528 17119 8540 17119 8530 17119 8530 17120 8540 17120 6826 17120 8530 17121 6826 17121 6825 17121 8545 17122 8541 17122 8528 17122 8528 17123 8541 17123 6836 17123 6836 17124 8542 17124 8528 17124 8528 17125 8542 17125 6842 17125 8528 17126 6842 17126 8540 17126 8525 17127 8543 17127 8544 17127 8544 17128 8543 17128 6839 17128 6839 17129 6838 17129 8544 17129 8544 17130 6838 17130 6837 17130 8544 17131 6837 17131 8545 17131 8545 17132 6837 17132 8546 17132 8545 17133 8546 17133 8541 17133 7243 17134 8551 17134 7242 17134 7242 17135 8551 17135 8547 17135 7260 17136 8549 17136 8548 17136 8548 17137 8549 17137 10476 17137 8552 17138 7241 17138 7222 17138 8547 17139 8551 17139 8550 17139 8550 17140 8551 17140 8552 17140 8550 17141 8552 17141 7220 17141 7220 17142 8552 17142 7222 17142 7241 17143 8552 17143 8553 17143 8553 17144 8552 17144 8554 17144 8553 17145 8554 17145 8555 17145 8555 17146 8554 17146 8556 17146 8556 17147 8554 17147 10482 17147 8556 17148 10482 17148 7229 17148 10481 17149 7221 17149 10482 17149 10482 17150 7221 17150 8557 17150 10482 17151 8557 17151 7229 17151 8559 17152 8558 17152 10481 17152 10481 17153 8558 17153 7248 17153 10481 17154 7248 17154 7221 17154 8562 17155 8560 17155 8559 17155 8559 17156 8560 17156 8561 17156 8559 17157 8561 17157 8558 17157 8559 17158 10479 17158 8562 17158 8562 17159 10479 17159 8549 17159 8562 17160 8549 17160 7260 17160 8563 17161 10758 17161 7130 17161 7130 17162 10758 17162 10757 17162 9088 17163 8564 17163 8565 17163 10458 17164 9099 17164 7094 17164 7094 17165 9099 17165 9087 17165 7094 17166 9087 17166 8568 17166 8565 17167 7093 17167 9088 17167 9088 17168 7093 17168 8566 17168 9088 17169 8566 17169 9087 17169 9087 17170 8566 17170 8567 17170 9087 17171 8567 17171 8568 17171 8569 17172 7085 17172 10746 17172 10746 17173 7085 17173 8570 17173 10746 17174 8570 17174 7075 17174 10744 17175 10494 17175 7026 17175 7026 17176 10494 17176 10492 17176 8575 17177 8571 17177 8578 17177 8571 17178 8572 17178 8578 17178 8578 17179 8572 17179 7012 17179 8578 17180 7012 17180 8573 17180 8578 17181 6952 17181 6951 17181 8574 17182 7018 17182 8572 17182 8572 17183 7018 17183 7019 17183 8572 17184 7019 17184 7012 17184 8580 17185 8575 17185 8576 17185 8576 17186 8575 17186 8578 17186 8576 17187 8578 17187 8577 17187 8577 17188 8578 17188 6951 17188 10980 17189 8579 17189 8572 17189 8572 17190 8579 17190 7006 17190 8572 17191 7006 17191 8574 17191 8576 17192 6947 17192 8580 17192 8580 17193 6947 17193 8590 17193 8580 17194 8590 17194 10969 17194 10969 17195 8590 17195 8581 17195 10969 17196 8581 17196 10970 17196 10970 17197 8581 17197 8582 17197 10970 17198 8582 17198 8583 17198 8583 17199 8582 17199 8584 17199 8583 17200 8584 17200 10972 17200 10972 17201 8584 17201 10732 17201 10972 17202 10732 17202 10974 17202 10974 17203 10732 17203 8585 17203 10974 17204 8585 17204 10976 17204 10976 17205 8585 17205 10737 17205 10976 17206 10737 17206 8586 17206 8586 17207 10737 17207 10735 17207 8586 17208 10735 17208 10980 17208 10980 17209 10735 17209 8587 17209 10980 17210 8587 17210 8579 17210 8587 17211 7013 17211 7014 17211 7014 17212 8588 17212 8587 17212 8587 17213 8588 17213 8589 17213 8587 17214 8589 17214 8579 17214 8590 17215 6946 17215 8581 17215 8581 17216 6946 17216 6953 17216 8581 17217 6953 17217 8591 17217 8592 17218 8597 17218 8593 17218 8593 17219 8597 17219 8594 17219 8593 17220 8594 17220 10406 17220 8599 17221 10440 17221 8595 17221 8595 17222 10440 17222 8596 17222 8595 17223 8596 17223 8597 17223 8597 17224 8596 17224 8598 17224 8597 17225 8598 17225 8594 17225 8595 17226 7949 17226 8599 17226 8599 17227 7949 17227 7948 17227 8599 17228 7948 17228 8600 17228 8604 17229 10387 17229 11618 17229 11618 17230 10387 17230 8601 17230 11618 17231 8601 17231 6365 17231 8602 17232 10401 17232 8603 17232 8603 17233 10401 17233 10400 17233 8603 17234 10400 17234 8604 17234 8604 17235 10400 17235 8605 17235 8604 17236 8605 17236 10387 17236 8603 17237 8606 17237 8602 17237 8602 17238 8606 17238 10600 17238 8602 17239 10600 17239 8607 17239 8265 17240 11814 17240 10359 17240 8265 17241 10359 17241 8608 17241 10359 17242 8609 17242 8608 17242 8608 17243 8609 17243 8610 17243 8608 17244 8610 17244 11692 17244 11692 17245 8610 17245 8611 17245 11692 17246 8611 17246 11694 17246 11694 17247 8611 17247 10390 17247 11694 17248 10390 17248 11685 17248 11685 17249 10390 17249 8612 17249 11685 17250 8612 17250 8613 17250 8613 17251 8612 17251 10445 17251 8613 17252 10445 17252 8614 17252 8253 17253 8254 17253 8624 17253 8615 17254 8616 17254 10438 17254 8617 17255 7518 17255 8615 17255 8615 17256 10438 17256 8617 17256 8617 17257 10438 17257 8618 17257 8617 17258 8618 17258 11668 17258 11668 17259 8618 17259 8619 17259 11668 17260 8619 17260 8620 17260 8620 17261 8619 17261 10384 17261 8620 17262 10384 17262 11671 17262 11671 17263 10384 17263 8621 17263 11671 17264 8621 17264 8622 17264 8622 17265 8621 17265 8623 17265 8622 17266 8623 17266 8624 17266 8624 17267 8623 17267 10414 17267 8624 17268 10414 17268 8253 17268 8633 17269 7576 17269 11650 17269 8209 17270 8625 17270 8627 17270 8626 17271 11642 17271 8209 17271 8209 17272 8627 17272 8626 17272 8626 17273 8627 17273 8628 17273 8626 17274 8628 17274 11646 17274 11646 17275 8628 17275 10409 17275 11646 17276 10409 17276 11648 17276 11648 17277 10409 17277 8630 17277 11648 17278 8630 17278 8629 17278 8629 17279 8630 17279 8631 17279 8629 17280 8631 17280 8632 17280 8632 17281 8631 17281 10383 17281 8632 17282 10383 17282 11650 17282 11650 17283 10383 17283 10407 17283 11650 17284 10407 17284 8633 17284 8646 17285 11844 17285 7978 17285 7978 17286 11844 17286 11843 17286 7433 17287 10591 17287 8634 17287 8634 17288 10591 17288 8635 17288 8634 17289 8635 17289 7432 17289 7432 17290 8635 17290 8172 17290 7432 17291 8172 17291 7429 17291 7429 17292 8172 17292 8171 17292 7429 17293 8171 17293 7428 17293 7428 17294 8171 17294 8168 17294 7428 17295 8168 17295 8636 17295 8636 17296 8168 17296 6331 17296 8636 17297 6331 17297 8637 17297 8637 17298 6331 17298 6342 17298 8637 17299 6342 17299 7426 17299 7426 17300 6342 17300 6340 17300 7426 17301 6340 17301 7425 17301 7425 17302 6340 17302 8638 17302 8638 17303 8163 17303 7425 17303 7425 17304 8163 17304 7455 17304 7278 17305 8639 17305 8640 17305 7278 17306 8640 17306 7396 17306 7303 17307 7305 17307 8640 17307 7305 17308 7306 17308 8640 17308 8640 17309 7306 17309 7307 17309 8640 17310 7307 17310 7396 17310 11796 17311 11795 17311 8641 17311 8641 17312 11795 17312 10578 17312 8641 17313 10578 17313 8640 17313 8640 17314 10578 17314 8642 17314 8640 17315 8642 17315 7303 17315 8645 17316 8267 17316 8643 17316 8643 17317 8644 17317 8645 17317 8645 17318 8644 17318 8176 17318 8645 17319 8176 17319 8165 17319 7962 17320 8592 17320 8593 17320 8646 17321 7978 17321 7971 17321 8646 17322 7971 17322 8647 17322 8647 17323 7971 17323 8649 17323 8647 17324 8649 17324 8648 17324 8648 17325 8649 17325 7962 17325 8648 17326 7962 17326 10405 17326 10405 17327 7962 17327 8593 17327 10405 17328 8593 17328 10406 17328 10695 17329 11574 17329 8650 17329 8650 17330 11574 17330 8651 17330 7696 17331 7692 17331 10374 17331 10374 17332 7692 17332 10375 17332 8654 17333 8652 17333 8653 17333 8653 17334 7613 17334 8654 17334 8654 17335 7613 17335 7614 17335 8654 17336 7614 17336 6373 17336 6373 17337 7614 17337 8655 17337 6373 17338 8655 17338 6372 17338 10698 17339 10437 17339 8657 17339 8657 17340 10437 17340 8656 17340 8657 17341 8656 17341 8661 17341 7665 17342 8658 17342 10433 17342 10433 17343 8658 17343 8659 17343 10433 17344 8659 17344 8660 17344 8660 17345 8659 17345 7670 17345 8660 17346 7670 17346 8656 17346 8656 17347 7670 17347 7667 17347 8656 17348 7667 17348 8661 17348 7665 17349 10433 17349 7661 17349 7661 17350 10433 17350 10431 17350 7661 17351 10431 17351 7662 17351 7662 17352 10431 17352 7664 17352 7664 17353 10431 17353 10430 17353 7664 17354 10430 17354 7634 17354 7634 17355 10430 17355 8662 17355 8662 17356 10430 17356 10428 17356 8662 17357 10428 17357 7651 17357 8665 17358 7648 17358 10373 17358 10373 17359 7648 17359 7650 17359 10373 17360 7650 17360 10426 17360 10426 17361 7650 17361 8663 17361 10426 17362 8663 17362 10428 17362 10428 17363 8663 17363 8664 17363 10428 17364 8664 17364 7651 17364 8665 17365 10373 17365 8666 17365 8666 17366 10373 17366 8667 17366 8666 17367 8667 17367 7646 17367 7646 17368 8667 17368 7647 17368 7647 17369 8667 17369 8668 17369 7647 17370 8668 17370 8669 17370 8669 17371 8668 17371 10417 17371 8669 17372 10417 17372 7678 17372 7678 17373 10417 17373 10690 17373 7678 17374 10690 17374 11576 17374 10347 17375 10345 17375 8670 17375 8670 17376 10345 17376 8671 17376 8672 17377 8676 17377 8673 17377 8673 17378 8676 17378 8675 17378 8673 17379 8675 17379 8674 17379 7948 17380 8674 17380 8600 17380 8600 17381 8674 17381 8675 17381 8600 17382 8675 17382 10447 17382 10447 17383 8675 17383 8676 17383 10447 17384 8676 17384 10446 17384 10446 17385 8676 17385 8672 17385 10446 17386 8672 17386 8229 17386 8681 17387 10424 17387 8679 17387 10449 17388 8677 17388 8678 17388 8679 17389 10439 17389 8678 17389 8678 17390 10439 17390 8680 17390 8678 17391 8680 17391 10449 17391 8682 17392 7499 17392 8681 17392 8681 17393 8679 17393 8682 17393 8682 17394 8679 17394 8678 17394 8682 17395 8678 17395 8683 17395 8683 17396 8678 17396 8677 17396 8683 17397 8677 17397 7521 17397 8684 17398 7483 17398 8685 17398 8681 17399 7499 17399 8684 17399 8684 17400 8685 17400 8681 17400 8681 17401 8685 17401 8686 17401 8681 17402 8686 17402 10424 17402 8687 17403 8701 17403 8909 17403 11083 17404 11081 17404 8933 17404 11103 17405 11101 17405 8885 17405 11186 17406 11185 17406 8946 17406 8950 17407 8956 17407 8955 17407 8688 17408 11261 17408 8901 17408 11337 17409 11336 17409 8862 17409 8689 17410 8796 17410 8797 17410 8796 17411 8689 17411 8784 17411 11741 17412 8690 17412 8846 17412 8846 17413 8690 17413 11742 17413 11744 17414 11745 17414 8847 17414 8836 17415 8691 17415 8834 17415 8834 17416 8691 17416 11748 17416 8754 17417 8876 17417 8760 17417 8874 17418 8750 17418 8752 17418 11765 17419 8874 17419 11764 17419 8692 17420 8888 17420 8872 17420 11770 17421 8886 17421 11761 17421 8693 17422 8694 17422 8825 17422 8951 17423 8722 17423 8952 17423 11709 17424 8695 17424 8948 17424 11713 17425 8696 17425 11712 17425 11719 17426 8697 17426 8896 17426 8896 17427 8697 17427 11718 17427 8698 17428 8720 17428 11720 17428 8718 17429 8699 17429 8700 17429 8879 17430 10699 17430 8878 17430 10714 17431 8701 17431 10712 17431 10712 17432 8701 17432 8687 17432 10712 17433 8687 17433 8702 17433 8702 17434 8687 17434 10711 17434 10711 17435 8687 17435 8703 17435 8703 17436 8687 17436 8863 17436 8703 17437 8863 17437 10709 17437 10709 17438 8863 17438 8864 17438 10709 17439 8864 17439 10708 17439 10708 17440 8864 17440 10706 17440 10706 17441 8864 17441 8704 17441 10706 17442 8704 17442 8705 17442 8857 17443 8929 17443 8708 17443 8926 17444 8706 17444 8707 17444 8707 17445 8706 17445 10702 17445 8707 17446 10702 17446 8929 17446 8929 17447 10702 17447 10703 17447 8929 17448 10703 17448 8708 17448 11722 17449 11301 17449 11300 17449 11300 17450 8709 17450 11722 17450 11722 17451 8709 17451 8710 17451 11722 17452 8710 17452 8711 17452 8712 17453 8713 17453 8719 17453 8719 17454 8713 17454 11294 17454 8710 17455 11297 17455 8711 17455 8711 17456 11297 17456 11296 17456 8711 17457 11296 17457 8717 17457 8714 17458 11304 17458 8792 17458 8792 17459 11304 17459 8793 17459 11281 17460 8716 17460 8719 17460 8719 17461 8716 17461 8717 17461 8719 17462 8717 17462 8712 17462 8712 17463 8717 17463 11296 17463 8718 17464 11721 17464 8715 17464 8716 17465 11280 17465 8717 17465 8717 17466 11280 17466 11279 17466 8717 17467 11279 17467 11721 17467 11721 17468 11279 17468 11276 17468 11721 17469 11276 17469 8715 17469 11273 17470 8699 17470 11274 17470 11274 17471 8699 17471 8718 17471 11274 17472 8718 17472 11275 17472 11275 17473 8718 17473 8715 17473 11273 17474 11270 17474 8699 17474 8699 17475 11270 17475 11285 17475 8699 17476 11285 17476 8719 17476 8719 17477 11285 17477 11283 17477 8719 17478 11283 17478 11281 17478 8700 17479 11254 17479 8807 17479 8700 17480 8807 17480 8698 17480 11720 17481 8720 17481 11715 17481 11715 17482 8720 17482 8891 17482 11715 17483 8891 17483 8721 17483 8722 17484 11222 17484 8952 17484 8952 17485 11222 17485 8723 17485 8952 17486 8723 17486 11771 17486 11771 17487 8723 17487 11219 17487 11771 17488 11219 17488 8724 17488 11216 17489 8725 17489 11217 17489 11217 17490 8725 17490 11771 17490 11217 17491 11771 17491 8726 17491 8726 17492 11771 17492 8724 17492 11216 17493 8727 17493 8725 17493 8725 17494 8727 17494 8728 17494 8725 17495 8728 17495 8736 17495 8736 17496 8728 17496 8729 17496 8957 17497 8730 17497 8736 17497 8743 17498 8731 17498 8732 17498 8739 17499 8733 17499 8731 17499 8731 17500 8733 17500 8734 17500 8731 17501 8734 17501 8732 17501 11207 17502 8735 17502 8947 17502 8730 17503 11203 17503 8736 17503 8736 17504 11203 17504 8737 17504 8736 17505 8737 17505 8725 17505 8725 17506 8737 17506 8738 17506 8725 17507 8738 17507 8739 17507 8739 17508 8738 17508 11200 17508 8739 17509 11200 17509 8733 17509 11207 17510 8947 17510 8742 17510 8746 17511 11181 17511 8745 17511 8745 17512 11181 17512 8740 17512 8740 17513 11181 17513 8748 17513 8740 17514 8748 17514 8741 17514 8732 17515 8742 17515 8743 17515 8743 17516 8742 17516 8947 17516 8743 17517 8947 17517 8745 17517 8745 17518 8947 17518 8744 17518 8745 17519 8744 17519 8746 17519 8741 17520 8748 17520 8747 17520 8747 17521 8748 17521 8821 17521 8747 17522 8821 17522 8749 17522 8749 17523 8821 17523 8911 17523 8749 17524 8911 17524 8693 17524 11764 17525 8874 17525 11763 17525 11763 17526 8874 17526 8752 17526 11763 17527 8752 17527 11760 17527 8750 17528 8876 17528 8756 17528 8756 17529 8876 17529 11148 17529 8752 17530 11144 17530 11143 17530 11143 17531 8751 17531 8752 17531 8752 17532 8751 17532 8753 17532 8752 17533 8753 17533 11760 17533 8751 17534 11152 17534 8753 17534 8753 17535 11152 17535 11151 17535 8753 17536 11151 17536 8754 17536 8754 17537 11151 17537 8755 17537 8754 17538 8755 17538 8876 17538 8876 17539 8755 17539 11149 17539 8876 17540 11149 17540 11148 17540 8756 17541 11147 17541 8750 17541 8750 17542 11147 17542 8757 17542 8750 17543 8757 17543 8752 17543 8752 17544 8757 17544 8758 17544 8752 17545 8758 17545 11144 17545 11129 17546 8759 17546 11131 17546 11131 17547 8759 17547 8760 17547 11127 17548 8761 17548 8890 17548 8761 17549 8762 17549 8890 17549 8890 17550 8762 17550 11122 17550 8890 17551 11122 17551 8877 17551 8877 17552 11122 17552 11121 17552 8877 17553 11121 17553 8763 17553 8764 17554 11119 17554 8876 17554 8876 17555 11119 17555 8765 17555 8876 17556 8765 17556 8760 17556 8760 17557 8765 17557 11117 17557 8760 17558 11117 17558 11131 17558 11754 17559 11753 17559 8766 17559 8766 17560 11753 17560 11751 17560 8766 17561 11751 17561 8767 17561 8767 17562 11751 17562 11752 17562 8767 17563 11752 17563 11111 17563 11111 17564 11752 17564 8768 17564 11129 17565 11127 17565 8759 17565 8759 17566 11127 17566 8890 17566 8759 17567 8890 17567 11752 17567 11752 17568 8890 17568 8769 17568 11752 17569 8769 17569 8768 17569 11748 17570 8770 17570 8832 17570 8916 17571 11080 17571 8770 17571 8770 17572 11080 17572 8771 17572 8770 17573 8771 17573 8832 17573 8854 17574 11750 17574 8772 17574 11376 17575 11374 17575 8845 17575 11388 17576 11387 17576 8846 17576 8846 17577 11387 17577 11386 17577 8846 17578 11386 17578 11741 17578 8773 17579 11736 17579 11740 17579 11386 17580 8774 17580 11741 17580 11741 17581 8774 17581 11383 17581 11741 17582 11383 17582 11740 17582 11383 17583 11382 17583 11740 17583 11740 17584 11382 17584 8775 17584 11740 17585 8775 17585 8773 17585 8773 17586 8775 17586 11379 17586 8773 17587 11379 17587 8776 17587 8845 17588 11374 17588 8846 17588 8846 17589 11374 17589 8777 17589 8846 17590 8777 17590 11388 17590 11363 17591 11737 17591 8778 17591 8778 17592 11737 17592 8781 17592 8778 17593 8781 17593 8779 17593 11361 17594 11360 17594 8780 17594 11736 17595 8773 17595 8781 17595 8781 17596 8773 17596 11365 17596 8781 17597 11365 17597 8779 17597 11360 17598 8782 17598 8780 17598 8780 17599 8782 17599 11359 17599 8780 17600 11359 17600 8801 17600 8801 17601 11359 17601 11357 17601 11357 17602 8783 17602 8801 17602 8801 17603 8783 17603 11356 17603 8801 17604 11356 17604 8773 17604 8773 17605 11356 17605 11367 17605 8773 17606 11367 17606 11365 17606 11363 17607 11361 17607 11737 17607 11737 17608 11361 17608 8780 17608 11737 17609 8780 17609 11738 17609 11738 17610 8780 17610 11739 17610 8784 17611 11739 17611 8795 17611 8785 17612 8842 17612 8786 17612 8786 17613 8842 17613 8804 17613 8787 17614 11323 17614 11727 17614 11727 17615 11323 17615 8788 17615 11727 17616 8788 17616 8789 17616 8789 17617 8788 17617 8790 17617 8789 17618 8790 17618 11728 17618 11728 17619 8790 17619 11729 17619 11729 17620 8790 17620 8917 17620 11729 17621 8917 17621 8935 17621 8871 17622 11725 17622 11731 17622 8791 17623 8792 17623 11722 17623 11722 17624 8792 17624 8793 17624 11722 17625 8793 17625 11301 17625 8800 17626 8794 17626 11334 17626 8784 17627 8795 17627 8796 17627 8796 17628 8795 17628 11340 17628 8796 17629 11340 17629 8797 17629 8797 17630 11340 17630 8798 17630 8797 17631 8798 17631 11338 17631 11334 17632 8799 17632 8800 17632 8800 17633 8799 17633 11346 17633 8800 17634 11346 17634 8801 17634 8801 17635 11346 17635 11345 17635 8801 17636 11345 17636 8780 17636 8780 17637 11345 17637 8802 17637 8780 17638 8802 17638 11739 17638 11739 17639 8802 17639 11342 17639 11739 17640 11342 17640 8795 17640 11314 17641 8803 17641 8841 17641 8841 17642 8803 17642 8806 17642 11727 17643 8804 17643 8787 17643 8787 17644 8804 17644 8842 17644 8787 17645 8842 17645 8805 17645 8805 17646 8842 17646 8806 17646 8805 17647 8806 17647 11313 17647 11313 17648 8806 17648 8803 17648 11318 17649 11316 17649 8904 17649 11319 17650 8917 17650 11320 17650 11320 17651 8917 17651 8790 17651 11320 17652 8790 17652 11322 17652 11322 17653 8790 17653 8788 17653 8698 17654 8807 17654 8720 17654 8720 17655 8807 17655 11251 17655 8720 17656 11251 17656 8891 17656 8891 17657 11251 17657 8808 17657 8891 17658 8808 17658 8809 17658 11254 17659 8700 17659 8810 17659 8810 17660 8700 17660 8699 17660 8810 17661 8699 17661 8811 17661 8811 17662 8699 17662 8719 17662 8811 17663 8719 17663 11257 17663 11258 17664 8868 17664 8869 17664 8898 17665 8900 17665 8812 17665 8812 17666 8900 17666 11236 17666 8812 17667 11236 17667 8813 17667 8813 17668 11236 17668 11235 17668 8813 17669 11235 17669 8949 17669 8949 17670 11235 17670 11234 17670 8949 17671 11234 17671 11232 17671 11242 17672 8814 17672 8815 17672 8815 17673 8814 17673 11240 17673 8815 17674 11240 17674 11238 17674 8816 17675 8817 17675 8821 17675 8817 17676 11190 17676 8924 17676 8924 17677 11190 17677 11188 17677 11181 17678 8818 17678 8748 17678 8748 17679 8818 17679 8819 17679 8748 17680 8819 17680 8821 17680 8821 17681 8819 17681 8820 17681 8821 17682 8820 17682 8816 17682 11170 17683 11168 17683 8822 17683 8822 17684 11168 17684 11167 17684 8822 17685 11167 17685 8823 17685 11167 17686 8824 17686 8823 17686 8823 17687 8824 17687 11165 17687 8823 17688 11165 17688 8694 17688 8694 17689 11165 17689 11163 17689 8694 17690 11163 17690 8825 17690 8825 17691 11163 17691 8826 17691 8825 17692 8826 17692 11769 17692 11769 17693 8826 17693 8827 17693 11769 17694 8827 17694 11160 17694 11170 17695 8887 17695 11172 17695 11172 17696 8887 17696 11173 17696 11173 17697 8887 17697 8828 17697 8828 17698 8887 17698 8886 17698 8828 17699 8886 17699 11160 17699 11160 17700 8886 17700 11770 17700 11160 17701 11770 17701 11769 17701 11109 17702 11108 17702 8829 17702 8767 17703 11109 17703 8766 17703 8766 17704 11109 17704 8829 17704 8766 17705 8829 17705 11754 17705 11754 17706 8829 17706 8916 17706 11754 17707 8916 17707 11755 17707 11755 17708 8916 17708 8770 17708 11108 17709 11106 17709 8829 17709 8829 17710 11106 17710 8830 17710 8829 17711 8830 17711 8884 17711 8884 17712 8830 17712 8831 17712 8884 17713 8831 17713 11104 17713 11748 17714 8832 17714 8834 17714 8834 17715 8832 17715 8833 17715 8834 17716 8833 17716 8835 17716 11750 17717 8836 17717 8772 17717 8772 17718 8836 17718 8834 17718 8772 17719 8834 17719 8837 17719 8837 17720 8834 17720 8835 17720 8837 17721 8835 17721 8838 17721 8838 17722 11088 17722 8837 17722 8837 17723 11088 17723 8839 17723 8837 17724 8839 17724 8932 17724 8932 17725 8839 17725 8840 17725 8932 17726 8840 17726 8934 17726 8858 17727 8841 17727 8860 17727 8860 17728 8841 17728 8806 17728 8860 17729 8806 17729 8861 17729 8861 17730 8806 17730 8842 17730 8861 17731 8842 17731 8797 17731 8797 17732 8842 17732 8785 17732 8797 17733 8785 17733 8689 17733 8705 17734 8704 17734 8853 17734 8853 17735 8704 17735 8867 17735 8853 17736 8867 17736 8843 17736 8843 17737 8867 17737 8794 17737 8843 17738 8794 17738 8851 17738 8851 17739 8794 17739 8800 17739 8851 17740 8800 17740 8844 17740 8844 17741 8800 17741 8801 17741 8844 17742 8801 17742 8848 17742 8848 17743 8801 17743 8773 17743 8848 17744 8773 17744 8845 17744 8845 17745 8773 17745 8776 17745 8845 17746 8776 17746 11376 17746 11742 17747 11744 17747 8846 17747 8846 17748 11744 17748 8847 17748 8846 17749 8847 17749 8845 17749 8845 17750 8847 17750 8855 17750 8845 17751 8855 17751 8848 17751 8848 17752 8855 17752 8849 17752 8848 17753 8849 17753 8844 17753 8844 17754 8849 17754 8850 17754 8844 17755 8850 17755 8851 17755 8851 17756 8850 17756 8852 17756 8851 17757 8852 17757 8843 17757 8843 17758 8852 17758 8856 17758 8843 17759 8856 17759 8853 17759 8853 17760 8856 17760 10705 17760 8853 17761 10705 17761 8705 17761 11745 17762 8854 17762 8847 17762 8847 17763 8854 17763 8772 17763 8847 17764 8772 17764 8855 17764 8855 17765 8772 17765 8837 17765 8855 17766 8837 17766 8849 17766 8849 17767 8837 17767 8932 17767 8849 17768 8932 17768 8850 17768 8850 17769 8932 17769 8930 17769 8850 17770 8930 17770 8852 17770 8852 17771 8930 17771 8857 17771 8852 17772 8857 17772 8856 17772 8856 17773 8857 17773 8708 17773 8856 17774 8708 17774 10705 17774 8906 17775 8858 17775 8859 17775 8859 17776 8858 17776 8860 17776 8859 17777 8860 17777 8865 17777 8865 17778 8860 17778 8861 17778 8865 17779 8861 17779 8866 17779 8866 17780 8861 17780 8797 17780 8866 17781 8797 17781 8862 17781 8862 17782 8797 17782 11338 17782 8862 17783 11338 17783 11337 17783 8687 17784 8906 17784 8863 17784 8863 17785 8906 17785 8859 17785 8863 17786 8859 17786 8864 17786 8864 17787 8859 17787 8865 17787 8864 17788 8865 17788 8704 17788 8704 17789 8865 17789 8866 17789 8704 17790 8866 17790 8867 17790 8867 17791 8866 17791 8862 17791 8867 17792 8862 17792 8794 17792 8794 17793 8862 17793 11336 17793 8794 17794 11336 17794 11334 17794 8868 17795 11257 17795 8869 17795 8869 17796 11257 17796 8719 17796 8869 17797 8719 17797 8792 17797 8792 17798 8719 17798 11294 17798 8792 17799 11294 17799 8714 17799 11261 17800 11258 17800 8870 17800 8870 17801 11258 17801 8869 17801 8870 17802 8869 17802 8962 17802 8962 17803 8869 17803 8792 17803 8962 17804 8792 17804 8871 17804 8871 17805 8792 17805 8791 17805 8871 17806 8791 17806 11725 17806 8872 17807 8888 17807 11765 17807 11765 17808 8888 17808 8873 17808 11765 17809 8873 17809 8874 17809 8874 17810 8873 17810 8875 17810 8874 17811 8875 17811 8750 17811 8750 17812 8875 17812 8877 17812 8750 17813 8877 17813 8876 17813 8876 17814 8877 17814 8763 17814 8876 17815 8763 17815 8764 17815 8893 17816 8909 17816 8894 17816 8894 17817 8909 17817 8701 17817 8894 17818 8701 17818 8878 17818 8878 17819 8701 17819 10714 17819 8878 17820 10714 17820 8879 17820 11170 17821 8822 17821 8887 17821 8887 17822 8822 17822 8880 17822 8887 17823 8880 17823 8881 17823 8881 17824 8880 17824 8882 17824 8881 17825 8882 17825 8883 17825 8883 17826 8882 17826 8914 17826 8883 17827 8914 17827 8889 17827 8889 17828 8914 17828 8884 17828 8889 17829 8884 17829 8885 17829 8885 17830 8884 17830 11104 17830 8885 17831 11104 17831 11103 17831 11761 17832 8886 17832 8692 17832 8692 17833 8886 17833 8887 17833 8692 17834 8887 17834 8888 17834 8888 17835 8887 17835 8881 17835 8888 17836 8881 17836 8873 17836 8873 17837 8881 17837 8883 17837 8873 17838 8883 17838 8875 17838 8875 17839 8883 17839 8889 17839 8875 17840 8889 17840 8877 17840 8877 17841 8889 17841 8885 17841 8877 17842 8885 17842 8890 17842 8890 17843 8885 17843 11101 17843 8890 17844 11101 17844 8769 17844 11718 17845 8721 17845 8897 17845 8897 17846 8721 17846 8891 17846 8897 17847 8891 17847 8901 17847 8901 17848 8891 17848 8809 17848 8901 17849 8809 17849 8688 17849 8910 17850 8893 17850 8892 17850 8892 17851 8893 17851 8894 17851 8892 17852 8894 17852 8895 17852 8895 17853 8894 17853 8878 17853 8895 17854 8878 17854 8926 17854 8926 17855 8878 17855 10699 17855 8926 17856 10699 17856 8706 17856 11718 17857 8897 17857 8896 17857 8896 17858 8897 17858 8815 17858 8896 17859 8815 17859 11719 17859 11719 17860 8815 17860 11238 17860 11719 17861 11238 17861 8898 17861 8898 17862 11238 17862 8899 17862 8898 17863 8899 17863 8900 17863 11261 17864 8870 17864 8901 17864 8901 17865 8870 17865 8902 17865 8901 17866 8902 17866 8897 17866 8897 17867 8902 17867 8903 17867 8897 17868 8903 17868 8815 17868 8815 17869 8903 17869 8960 17869 8815 17870 8960 17870 11242 17870 11316 17871 11314 17871 8904 17871 8904 17872 11314 17872 8841 17872 8904 17873 8841 17873 8918 17873 8918 17874 8841 17874 8858 17874 8918 17875 8858 17875 8905 17875 8905 17876 8858 17876 8906 17876 8905 17877 8906 17877 8921 17877 8921 17878 8906 17878 8687 17878 8921 17879 8687 17879 8907 17879 8907 17880 8687 17880 8909 17880 8907 17881 8909 17881 8908 17881 8908 17882 8909 17882 8893 17882 8908 17883 8893 17883 8923 17883 8923 17884 8893 17884 8910 17884 8923 17885 8910 17885 8924 17885 8693 17886 8911 17886 8694 17886 8694 17887 8911 17887 8912 17887 8694 17888 8912 17888 8823 17888 8823 17889 8912 17889 8925 17889 8823 17890 8925 17890 8822 17890 8822 17891 8925 17891 8927 17891 8822 17892 8927 17892 8880 17892 8880 17893 8927 17893 8928 17893 8880 17894 8928 17894 8882 17894 8882 17895 8928 17895 8913 17895 8882 17896 8913 17896 8914 17896 8914 17897 8913 17897 8915 17897 8914 17898 8915 17898 8884 17898 8884 17899 8915 17899 8931 17899 8884 17900 8931 17900 8829 17900 8829 17901 8931 17901 8933 17901 8829 17902 8933 17902 8916 17902 8916 17903 8933 17903 11081 17903 8916 17904 11081 17904 11080 17904 11319 17905 11318 17905 8917 17905 8917 17906 11318 17906 8904 17906 8917 17907 8904 17907 8937 17907 8937 17908 8904 17908 8918 17908 8937 17909 8918 17909 8919 17909 8919 17910 8918 17910 8905 17910 8919 17911 8905 17911 8920 17911 8920 17912 8905 17912 8921 17912 8920 17913 8921 17913 8940 17913 8940 17914 8921 17914 8907 17914 8940 17915 8907 17915 8922 17915 8922 17916 8907 17916 8908 17916 8922 17917 8908 17917 8943 17917 8943 17918 8908 17918 8923 17918 8943 17919 8923 17919 8944 17919 8944 17920 8923 17920 8924 17920 8944 17921 8924 17921 8946 17921 8946 17922 8924 17922 11188 17922 8946 17923 11188 17923 11186 17923 8817 17924 8924 17924 8821 17924 8821 17925 8924 17925 8910 17925 8821 17926 8910 17926 8911 17926 8911 17927 8910 17927 8892 17927 8911 17928 8892 17928 8912 17928 8912 17929 8892 17929 8895 17929 8912 17930 8895 17930 8925 17930 8925 17931 8895 17931 8926 17931 8925 17932 8926 17932 8927 17932 8927 17933 8926 17933 8707 17933 8927 17934 8707 17934 8928 17934 8928 17935 8707 17935 8929 17935 8928 17936 8929 17936 8913 17936 8913 17937 8929 17937 8857 17937 8913 17938 8857 17938 8915 17938 8915 17939 8857 17939 8930 17939 8915 17940 8930 17940 8931 17940 8931 17941 8930 17941 8932 17941 8931 17942 8932 17942 8933 17942 8933 17943 8932 17943 8934 17943 8933 17944 8934 17944 11083 17944 8935 17945 8917 17945 8936 17945 8936 17946 8917 17946 8937 17946 8936 17947 8937 17947 8938 17947 8938 17948 8937 17948 8919 17948 8938 17949 8919 17949 8961 17949 8961 17950 8919 17950 8920 17950 8961 17951 8920 17951 8939 17951 8939 17952 8920 17952 8940 17952 8939 17953 8940 17953 8941 17953 8941 17954 8940 17954 8922 17954 8941 17955 8922 17955 8942 17955 8942 17956 8922 17956 8943 17956 8942 17957 8943 17957 8959 17957 8959 17958 8943 17958 8944 17958 8959 17959 8944 17959 8945 17959 8945 17960 8944 17960 8946 17960 8945 17961 8946 17961 8947 17961 8947 17962 8946 17962 11185 17962 8947 17963 11185 17963 8744 17963 8695 17964 11712 17964 8948 17964 8948 17965 11712 17965 8696 17965 8948 17966 8696 17966 8949 17966 8949 17967 8696 17967 11713 17967 8949 17968 11713 17968 8813 17968 8813 17969 11713 17969 11714 17969 8813 17970 11714 17970 8812 17970 11771 17971 11709 17971 8952 17971 8952 17972 11709 17972 8948 17972 8952 17973 8948 17973 8954 17973 8954 17974 8948 17974 8949 17974 8954 17975 8949 17975 8955 17975 8955 17976 8949 17976 11232 17976 8955 17977 11232 17977 8950 17977 8729 17978 8951 17978 8736 17978 8736 17979 8951 17979 8952 17979 8736 17980 8952 17980 8958 17980 8958 17981 8952 17981 8954 17981 8958 17982 8954 17982 8953 17982 8953 17983 8954 17983 8955 17983 8953 17984 8955 17984 8960 17984 8960 17985 8955 17985 8956 17985 8960 17986 8956 17986 11242 17986 8735 17987 8957 17987 8947 17987 8947 17988 8957 17988 8736 17988 8947 17989 8736 17989 8945 17989 8945 17990 8736 17990 8958 17990 8945 17991 8958 17991 8959 17991 8959 17992 8958 17992 8953 17992 8959 17993 8953 17993 8942 17993 8942 17994 8953 17994 8960 17994 8942 17995 8960 17995 8941 17995 8941 17996 8960 17996 8903 17996 8941 17997 8903 17997 8939 17997 8939 17998 8903 17998 8902 17998 8939 17999 8902 17999 8961 17999 8961 18000 8902 18000 8870 18000 8961 18001 8870 18001 8938 18001 8938 18002 8870 18002 8962 18002 8938 18003 8962 18003 8936 18003 8936 18004 8962 18004 8871 18004 8936 18005 8871 18005 8935 18005 8935 18006 8871 18006 11731 18006 8935 18007 11731 18007 11729 18007 9035 18008 6845 18008 8963 18008 6729 18009 9508 18009 9010 18009 9061 18010 8964 18010 9042 18010 10471 18011 10474 18011 8979 18011 6921 18012 8965 18012 8963 18012 8968 18013 8970 18013 9490 18013 8966 18014 8967 18014 9490 18014 9490 18015 8967 18015 6385 18015 9490 18016 6385 18016 8968 18016 8968 18017 6385 18017 6412 18017 8972 18018 8969 18018 8970 18018 8965 18019 8971 18019 8968 18019 8971 18020 6897 18020 8968 18020 8968 18021 6897 18021 6899 18021 8968 18022 6899 18022 8970 18022 8970 18023 6899 18023 6900 18023 8970 18024 6900 18024 8972 18024 6921 18025 8963 18025 6933 18025 10501 18026 9032 18026 9033 18026 9033 18027 9529 18027 10501 18027 10501 18028 9529 18028 8974 18028 10501 18029 8974 18029 8973 18029 8973 18030 8974 18030 9530 18030 8973 18031 9530 18031 6871 18031 6871 18032 9530 18032 8975 18032 6871 18033 8975 18033 6881 18033 6881 18034 8975 18034 9533 18034 8976 18035 8977 18035 9080 18035 8978 18036 8977 18036 9207 18036 9207 18037 8977 18037 8976 18037 9207 18038 8976 18038 8979 18038 10471 18039 8979 18039 10483 18039 10483 18040 8979 18040 8976 18040 10483 18041 8976 18041 8984 18041 8984 18042 8976 18042 8980 18042 8984 18043 8980 18043 8983 18043 8985 18044 7249 18044 8981 18044 8981 18045 7249 18045 8982 18045 8981 18046 8982 18046 8983 18046 8983 18047 8982 18047 7253 18047 8983 18048 7253 18048 8984 18048 8985 18049 8981 18049 8986 18049 8986 18050 8981 18050 9072 18050 8986 18051 9072 18051 7252 18051 7232 18052 7252 18052 8987 18052 8987 18053 7252 18053 9072 18053 8987 18054 9072 18054 8988 18054 8988 18055 9072 18055 9073 18055 8988 18056 9073 18056 9132 18056 9132 18057 9073 18057 8991 18057 9132 18058 8991 18058 8989 18058 8994 18059 9130 18059 8990 18059 8990 18060 9130 18060 9134 18060 8990 18061 9134 18061 8991 18061 8991 18062 9134 18062 8992 18062 8991 18063 8992 18063 8989 18063 8993 18064 9131 18064 8994 18064 8999 18065 9067 18065 7107 18065 7107 18066 9067 18066 8995 18066 7107 18067 8995 18067 9002 18067 9131 18068 8993 18068 8996 18068 8996 18069 8993 18069 9066 18069 8996 18070 9066 18070 8997 18070 8997 18071 9066 18071 9067 18071 8997 18072 9067 18072 8998 18072 8998 18073 9067 18073 8999 18073 8998 18074 8999 18074 7090 18074 9000 18075 9001 18075 9002 18075 9002 18076 9001 18076 9003 18076 9002 18077 9003 18077 7107 18077 9002 18078 9004 18078 9000 18078 9000 18079 9004 18079 9042 18079 9000 18080 9042 18080 9005 18080 9005 18081 9042 18081 8964 18081 9005 18082 8964 18082 10457 18082 6952 18083 8011 18083 9060 18083 6952 18084 8578 18084 8011 18084 8011 18085 8578 18085 8573 18085 8011 18086 8573 18086 9007 18086 9007 18087 8573 18087 9006 18087 9007 18088 9006 18088 9549 18088 9549 18089 9006 18089 7007 18089 9549 18090 7007 18090 9550 18090 7007 18091 7008 18091 9550 18091 9550 18092 7008 18092 9008 18092 9550 18093 9008 18093 9009 18093 9009 18094 9008 18094 9512 18094 6994 18095 6993 18095 9010 18095 9008 18096 6995 18096 9512 18096 9512 18097 6995 18097 6994 18097 9512 18098 6994 18098 9510 18098 9510 18099 6994 18099 9010 18099 6993 18100 6992 18100 9010 18100 9010 18101 6992 18101 9011 18101 9010 18102 9011 18102 9013 18102 9011 18103 6989 18103 9013 18103 9013 18104 6989 18104 6987 18104 9013 18105 6987 18105 9059 18105 9013 18106 9054 18106 9015 18106 6726 18107 6729 18107 9012 18107 9012 18108 6729 18108 9010 18108 9012 18109 9010 18109 6661 18109 6661 18110 9010 18110 9013 18110 6661 18111 9013 18111 9014 18111 9014 18112 9013 18112 9015 18112 9016 18113 9017 18113 9063 18113 9063 18114 9017 18114 6667 18114 9063 18115 6667 18115 9054 18115 9054 18116 6667 18116 6666 18116 9054 18117 6666 18117 9015 18117 9016 18118 9063 18118 6620 18118 6620 18119 9063 18119 9018 18119 6620 18120 9018 18120 9079 18120 9071 18121 9019 18121 9078 18121 9078 18122 9019 18122 6588 18122 9078 18123 6588 18123 6619 18123 6510 18124 9021 18124 9020 18124 9020 18125 9021 18125 6582 18125 9020 18126 6582 18126 9071 18126 9071 18127 6582 18127 6591 18127 9071 18128 6591 18128 9019 18128 9036 18129 6497 18129 9068 18129 9068 18130 6497 18130 9022 18130 9068 18131 9022 18131 9069 18131 9069 18132 9022 18132 6500 18132 9069 18133 6500 18133 9020 18133 9020 18134 6500 18134 6501 18134 9020 18135 6501 18135 6510 18135 9026 18136 9023 18136 9024 18136 9024 18137 9023 18137 9038 18137 9024 18138 9038 18138 9025 18138 9025 18139 9038 18139 9080 18139 9024 18140 9030 18140 9026 18140 9026 18141 9030 18141 9029 18141 9026 18142 9029 18142 9027 18142 9027 18143 9029 18143 9028 18143 9027 18144 9028 18144 6844 18144 6845 18145 6844 18145 8963 18145 8963 18146 6844 18146 9028 18146 8963 18147 9028 18147 6933 18147 6933 18148 9028 18148 9029 18148 6933 18149 9029 18149 6940 18149 6940 18150 9029 18150 9030 18150 6940 18151 9030 18151 9031 18151 9031 18152 9030 18152 9024 18152 9031 18153 9024 18153 9032 18153 9032 18154 9024 18154 9025 18154 9032 18155 9025 18155 9033 18155 6848 18156 9034 18156 9068 18156 9034 18157 9035 18157 9068 18157 9068 18158 9035 18158 8963 18158 9068 18159 8963 18159 9036 18159 9036 18160 8963 18160 8965 18160 9036 18161 8965 18161 9037 18161 9037 18162 8965 18162 8968 18162 9023 18163 8516 18163 9038 18163 9038 18164 8516 18164 8515 18164 9038 18165 8515 18165 9081 18165 9081 18166 8515 18166 6866 18166 9081 18167 6866 18167 9082 18167 9082 18168 6866 18168 9039 18168 6866 18169 6867 18169 9039 18169 9039 18170 6867 18170 6851 18170 9039 18171 6851 18171 9084 18171 9084 18172 6851 18172 6850 18172 9084 18173 6850 18173 9040 18173 7021 18174 9041 18174 9042 18174 9042 18175 9041 18175 7080 18175 9042 18176 7080 18176 9043 18176 9043 18177 7080 18177 9044 18177 9044 18178 7080 18178 9045 18178 9044 18179 9045 18179 9057 18179 7028 18180 9047 18180 9046 18180 9046 18181 9047 18181 9048 18181 9046 18182 9048 18182 9049 18182 9049 18183 9048 18183 7039 18183 7039 18184 9048 18184 9050 18184 7039 18185 9050 18185 7041 18185 7041 18186 9050 18186 7042 18186 7042 18187 9050 18187 9064 18187 7042 18188 9064 18188 9065 18188 9051 18189 9052 18189 9059 18189 9059 18190 9052 18190 7067 18190 9059 18191 7067 18191 9013 18191 9013 18192 7067 18192 9053 18192 9013 18193 9053 18193 9054 18193 9054 18194 9053 18194 9055 18194 9054 18195 9055 18195 7045 18195 9045 18196 7083 18196 9057 18196 9057 18197 7083 18197 9056 18197 9057 18198 9056 18198 9051 18198 9051 18199 9056 18199 7084 18199 9051 18200 7084 18200 9052 18200 6987 18201 9058 18201 9059 18201 9059 18202 9058 18202 6962 18202 9059 18203 6962 18203 9051 18203 9051 18204 6962 18204 6961 18204 9051 18205 6961 18205 9057 18205 9057 18206 6961 18206 6950 18206 9057 18207 6950 18207 9044 18207 9044 18208 6950 18208 6952 18208 9044 18209 6952 18209 9043 18209 9043 18210 6952 18210 9060 18210 9043 18211 9060 18211 9042 18211 9042 18212 9060 18212 8006 18212 9042 18213 8006 18213 9061 18213 9076 18214 9018 18214 9062 18214 9062 18215 9018 18215 9063 18215 9062 18216 9063 18216 9064 18216 9064 18217 9063 18217 9054 18217 9064 18218 9054 18218 9065 18218 9065 18219 9054 18219 7045 18219 8994 18220 8990 18220 8993 18220 8993 18221 8990 18221 9076 18221 8993 18222 9076 18222 9066 18222 9066 18223 9076 18223 9062 18223 9066 18224 9062 18224 9067 18224 9067 18225 9062 18225 9064 18225 9067 18226 9064 18226 8995 18226 8995 18227 9064 18227 9050 18227 8995 18228 9050 18228 9002 18228 9002 18229 9050 18229 9048 18229 9002 18230 9048 18230 9004 18230 9004 18231 9048 18231 9047 18231 9004 18232 9047 18232 9042 18232 9042 18233 9047 18233 7028 18233 9042 18234 7028 18234 7021 18234 9085 18235 6848 18235 9083 18235 9083 18236 6848 18236 9068 18236 9083 18237 9068 18237 9074 18237 9074 18238 9068 18238 9069 18238 9074 18239 9069 18239 9075 18239 9075 18240 9069 18240 9020 18240 9075 18241 9020 18241 9070 18241 9070 18242 9020 18242 9071 18242 9070 18243 9071 18243 9077 18243 9077 18244 9071 18244 9078 18244 8981 18245 9083 18245 9072 18245 9072 18246 9083 18246 9074 18246 9072 18247 9074 18247 9073 18247 9073 18248 9074 18248 9075 18248 9073 18249 9075 18249 8991 18249 8991 18250 9075 18250 9070 18250 8991 18251 9070 18251 8990 18251 8990 18252 9070 18252 9077 18252 8990 18253 9077 18253 9076 18253 9076 18254 9077 18254 9078 18254 9076 18255 9078 18255 9018 18255 9018 18256 9078 18256 6619 18256 9018 18257 6619 18257 9079 18257 9080 18258 9038 18258 8976 18258 8976 18259 9038 18259 9081 18259 8976 18260 9081 18260 8980 18260 8980 18261 9081 18261 9082 18261 8980 18262 9082 18262 8983 18262 8983 18263 9082 18263 9039 18263 8983 18264 9039 18264 8981 18264 8981 18265 9039 18265 9084 18265 8981 18266 9084 18266 9083 18266 9083 18267 9084 18267 9040 18267 9083 18268 9040 18268 9085 18268 9100 18269 9094 18269 9086 18269 9087 18270 9089 18270 9088 18270 9088 18271 9089 18271 9105 18271 9090 18272 9101 18272 9091 18272 9090 18273 9091 18273 9089 18273 9089 18274 9091 18274 9150 18274 9089 18275 9150 18275 9105 18275 9102 18276 9100 18276 9106 18276 9106 18277 9100 18277 9086 18277 9106 18278 9086 18278 9092 18278 9092 18279 9086 18279 9156 18279 9093 18280 10522 18280 9156 18280 9156 18281 9086 18281 9093 18281 9093 18282 9086 18282 9094 18282 9093 18283 9094 18283 8001 18283 8001 18284 9094 18284 9095 18284 8001 18285 9095 18285 9096 18285 9096 18286 9095 18286 9061 18286 9096 18287 9061 18287 8006 18287 9097 18288 9090 18288 9098 18288 9098 18289 9090 18289 9089 18289 9098 18290 9089 18290 9099 18290 9099 18291 9089 18291 9087 18291 10457 18292 8964 18292 9099 18292 9099 18293 8964 18293 9061 18293 9099 18294 9061 18294 9098 18294 9098 18295 9061 18295 9095 18295 9098 18296 9095 18296 9097 18296 9097 18297 9095 18297 9094 18297 9097 18298 9094 18298 9090 18298 9090 18299 9094 18299 9100 18299 9090 18300 9100 18300 9101 18300 9101 18301 9100 18301 9102 18301 9167 18302 9103 18302 9104 18302 7091 18303 9127 18303 9128 18303 9105 18304 9150 18304 9149 18304 9101 18305 9102 18305 9158 18305 9106 18306 9092 18306 9159 18306 9103 18307 9167 18307 9107 18307 9108 18308 9136 18308 9137 18308 7237 18309 9110 18309 9109 18309 9109 18310 9110 18310 9135 18310 9109 18311 9202 18311 7237 18311 7237 18312 9202 18312 7218 18312 9201 18313 9112 18313 9111 18313 9111 18314 9112 18314 9169 18314 9111 18315 9169 18315 9338 18315 9170 18316 9113 18316 9169 18316 9169 18317 9113 18317 9337 18317 9169 18318 9337 18318 9338 18318 9175 18319 9332 18319 9171 18319 9171 18320 9332 18320 9333 18320 9171 18321 9333 18321 9170 18321 9170 18322 9333 18322 9114 18322 9170 18323 9114 18323 9113 18323 9288 18324 9115 18324 9154 18324 9154 18325 9115 18325 9107 18325 7151 18326 9116 18326 9118 18326 9118 18327 9116 18327 9288 18327 7184 18328 9117 18328 9118 18328 9118 18329 9117 18329 9119 18329 9118 18330 9119 18330 7151 18330 9123 18331 9125 18331 9157 18331 9157 18332 9125 18332 9120 18332 9157 18333 9120 18333 7210 18333 10522 18334 9121 18334 9156 18334 9156 18335 9121 18335 9122 18335 9156 18336 9122 18336 9123 18336 9123 18337 9122 18337 9124 18337 9123 18338 9124 18338 9125 18338 9105 18339 9149 18339 9088 18339 7091 18340 9126 18340 9127 18340 9127 18341 9126 18341 7106 18341 9127 18342 7106 18342 8564 18342 7090 18343 7091 18343 8998 18343 8998 18344 7091 18344 9128 18344 8998 18345 9128 18345 8997 18345 8997 18346 9128 18346 9151 18346 8997 18347 9151 18347 8996 18347 8996 18348 9151 18348 9129 18348 8996 18349 9129 18349 9131 18349 9131 18350 9129 18350 9141 18350 9133 18351 9134 18351 9142 18351 9142 18352 9134 18352 9130 18352 9142 18353 9130 18353 9141 18353 9141 18354 9130 18354 8994 18354 9141 18355 8994 18355 9131 18355 9132 18356 8989 18356 9133 18356 9133 18357 8989 18357 8992 18357 9133 18358 8992 18358 9134 18358 9133 18359 9140 18359 9132 18359 9132 18360 9140 18360 9138 18360 9132 18361 9138 18361 8988 18361 9110 18362 7228 18362 9135 18362 9135 18363 7228 18363 7232 18363 9135 18364 7232 18364 9138 18364 9138 18365 7232 18365 8987 18365 9138 18366 8987 18366 8988 18366 9136 18367 9202 18367 9137 18367 9137 18368 9202 18368 9109 18368 9137 18369 9109 18369 9198 18369 9198 18370 9109 18370 9135 18370 9198 18371 9135 18371 9197 18371 9197 18372 9135 18372 9138 18372 9197 18373 9138 18373 9139 18373 9139 18374 9138 18374 9140 18374 9139 18375 9140 18375 9145 18375 9145 18376 9140 18376 9133 18376 9141 18377 9196 18377 9142 18377 9142 18378 9196 18378 9143 18378 9142 18379 9143 18379 9133 18379 9133 18380 9143 18380 9144 18380 9133 18381 9144 18381 9145 18381 9153 18382 9146 18382 9194 18382 9194 18383 9146 18383 9152 18383 9194 18384 9152 18384 9192 18384 9192 18385 9152 18385 9147 18385 9192 18386 9147 18386 9148 18386 9148 18387 9147 18387 9149 18387 9148 18388 9149 18388 9191 18388 9191 18389 9149 18389 9150 18389 9191 18390 9150 18390 9091 18390 8564 18391 9088 18391 9127 18391 9127 18392 9088 18392 9149 18392 9127 18393 9149 18393 9128 18393 9128 18394 9149 18394 9147 18394 9128 18395 9147 18395 9151 18395 9151 18396 9147 18396 9152 18396 9151 18397 9152 18397 9129 18397 9129 18398 9152 18398 9146 18398 9129 18399 9146 18399 9141 18399 9141 18400 9146 18400 9153 18400 9141 18401 9153 18401 9196 18401 9107 18402 9167 18402 9154 18402 9154 18403 9167 18403 9165 18403 9154 18404 9165 18404 9155 18404 9288 18405 9154 18405 9118 18405 9118 18406 9154 18406 9155 18406 9118 18407 9155 18407 7184 18407 7184 18408 9155 18408 9162 18408 7184 18409 9162 18409 7173 18409 9092 18410 9156 18410 9159 18410 9159 18411 9156 18411 9123 18411 9159 18412 9123 18412 9160 18412 9160 18413 9123 18413 9157 18413 9160 18414 9157 18414 9162 18414 9162 18415 9157 18415 7210 18415 9162 18416 7210 18416 7173 18416 9102 18417 9106 18417 9158 18417 9158 18418 9106 18418 9159 18418 9158 18419 9159 18419 9193 18419 9193 18420 9159 18420 9160 18420 9193 18421 9160 18421 9161 18421 9161 18422 9160 18422 9162 18422 9161 18423 9162 18423 9195 18423 9195 18424 9162 18424 9155 18424 9195 18425 9155 18425 9163 18425 9163 18426 9155 18426 9165 18426 9163 18427 9165 18427 9164 18427 9164 18428 9165 18428 9167 18428 9164 18429 9167 18429 9166 18429 9166 18430 9167 18430 9104 18430 9166 18431 9104 18431 9168 18431 9112 18432 9208 18432 9169 18432 9169 18433 9208 18433 9181 18433 9169 18434 9181 18434 9170 18434 9170 18435 9181 18435 9183 18435 9170 18436 9183 18436 9171 18436 9171 18437 9183 18437 9173 18437 9171 18438 9173 18438 9172 18438 9172 18439 9173 18439 9185 18439 9172 18440 9185 18440 9177 18440 9177 18441 9185 18441 9174 18441 9177 18442 9174 18442 9178 18442 9178 18443 9174 18443 9187 18443 9178 18444 9187 18444 9179 18444 9175 18445 9171 18445 9329 18445 9329 18446 9171 18446 9172 18446 9329 18447 9172 18447 9176 18447 9176 18448 9172 18448 9177 18448 9176 18449 9177 18449 9168 18449 9168 18450 9177 18450 9178 18450 9168 18451 9178 18451 9166 18451 9166 18452 9178 18452 9179 18452 9166 18453 9179 18453 9164 18453 9164 18454 9179 18454 9180 18454 9164 18455 9180 18455 9163 18455 9208 18456 9182 18456 9181 18456 9181 18457 9182 18457 9200 18457 9181 18458 9200 18458 9183 18458 9183 18459 9200 18459 9184 18459 9183 18460 9184 18460 9173 18460 9173 18461 9184 18461 9199 18461 9173 18462 9199 18462 9185 18462 9185 18463 9199 18463 9186 18463 9185 18464 9186 18464 9174 18464 9174 18465 9186 18465 9188 18465 9174 18466 9188 18466 9187 18466 9187 18467 9188 18467 9189 18467 9187 18468 9189 18468 9179 18468 9179 18469 9189 18469 9190 18469 9179 18470 9190 18470 9180 18470 9091 18471 9101 18471 9191 18471 9191 18472 9101 18472 9158 18472 9191 18473 9158 18473 9148 18473 9148 18474 9158 18474 9193 18474 9148 18475 9193 18475 9192 18475 9192 18476 9193 18476 9161 18476 9192 18477 9161 18477 9194 18477 9194 18478 9161 18478 9195 18478 9194 18479 9195 18479 9153 18479 9153 18480 9195 18480 9163 18480 9153 18481 9163 18481 9196 18481 9196 18482 9163 18482 9180 18482 9196 18483 9180 18483 9143 18483 9143 18484 9180 18484 9190 18484 9143 18485 9190 18485 9144 18485 9144 18486 9190 18486 9189 18486 9144 18487 9189 18487 9145 18487 9145 18488 9189 18488 9188 18488 9145 18489 9188 18489 9139 18489 9139 18490 9188 18490 9186 18490 9139 18491 9186 18491 9197 18491 9197 18492 9186 18492 9199 18492 9197 18493 9199 18493 9198 18493 9198 18494 9199 18494 9184 18494 9198 18495 9184 18495 9137 18495 9137 18496 9184 18496 9200 18496 9137 18497 9200 18497 9108 18497 9108 18498 9200 18498 9182 18498 9112 18499 9201 18499 9261 18499 7218 18500 9202 18500 7215 18500 7215 18501 9202 18501 9136 18501 7215 18502 9136 18502 9204 18502 9204 18503 9136 18503 9203 18503 9204 18504 9203 18504 9210 18504 9211 18505 10474 18505 9210 18505 9205 18506 9261 18506 9206 18506 9206 18507 8978 18507 9209 18507 9209 18508 8978 18508 9207 18508 9209 18509 9207 18509 8979 18509 9112 18510 9261 18510 9208 18510 9208 18511 9261 18511 9205 18511 9208 18512 9205 18512 9213 18512 9213 18513 9205 18513 9206 18513 9213 18514 9206 18514 9212 18514 9212 18515 9206 18515 9209 18515 9212 18516 9209 18516 9211 18516 9211 18517 9209 18517 8979 18517 9211 18518 8979 18518 10474 18518 9210 18519 9203 18519 9211 18519 9211 18520 9203 18520 9136 18520 9211 18521 9136 18521 9212 18521 9212 18522 9136 18522 9108 18522 9212 18523 9108 18523 9213 18523 9213 18524 9108 18524 9182 18524 9213 18525 9182 18525 9208 18525 9215 18526 9219 18526 9373 18526 9216 18527 11706 18527 11705 18527 7990 18528 8640 18528 8639 18528 9214 18529 10522 18529 9093 18529 9093 18530 7990 18530 9214 18530 9214 18531 7990 18531 8639 18531 9214 18532 8639 18532 11705 18532 11705 18533 8639 18533 9215 18533 11705 18534 9215 18534 9216 18534 9216 18535 9215 18535 9373 18535 7384 18536 9378 18536 9218 18536 9218 18537 9378 18537 9217 18537 9218 18538 9217 18538 7383 18538 7383 18539 9217 18539 9377 18539 7383 18540 9377 18540 9219 18540 9219 18541 9377 18541 9376 18541 9219 18542 9376 18542 9373 18542 9222 18543 9220 18543 7393 18543 7393 18544 9220 18544 9372 18544 7393 18545 9372 18545 7384 18545 7384 18546 9372 18546 9221 18546 7384 18547 9221 18547 9378 18547 7393 18548 7392 18548 9222 18548 9222 18549 7392 18549 7367 18549 9222 18550 7367 18550 9224 18550 9224 18551 7367 18551 9223 18551 9224 18552 9223 18552 9414 18552 9414 18553 9223 18553 9225 18553 9414 18554 9225 18554 9227 18554 9227 18555 9225 18555 9226 18555 9227 18556 9226 18556 9368 18556 9368 18557 9226 18557 9228 18557 9368 18558 9228 18558 9370 18558 9370 18559 9228 18559 7355 18559 9235 18560 9229 18560 7355 18560 7355 18561 9229 18561 9367 18561 7355 18562 9367 18562 9370 18562 7363 18563 9230 18563 7350 18563 7350 18564 9230 18564 9231 18564 7350 18565 9231 18565 9232 18565 9232 18566 9231 18566 9363 18566 9232 18567 9363 18567 7352 18567 7352 18568 9363 18568 9233 18568 7352 18569 9233 18569 9235 18569 9235 18570 9233 18570 9234 18570 9235 18571 9234 18571 9229 18571 7342 18572 9362 18572 9236 18572 9236 18573 9362 18573 9360 18573 9236 18574 9360 18574 7344 18574 7344 18575 9360 18575 9357 18575 7344 18576 9357 18576 9238 18576 9238 18577 9357 18577 9237 18577 9238 18578 9237 18578 7363 18578 7363 18579 9237 18579 9365 18579 7363 18580 9365 18580 9230 18580 9239 18581 9246 18581 7342 18581 7342 18582 9246 18582 9240 18582 7342 18583 9240 18583 9362 18583 9342 18584 9393 18584 9247 18584 9247 18585 9393 18585 9392 18585 9247 18586 9392 18586 9241 18586 9241 18587 9392 18587 9242 18587 9241 18588 9242 18588 9243 18588 9243 18589 9242 18589 9356 18589 9243 18590 9356 18590 9244 18590 9244 18591 9356 18591 9354 18591 9244 18592 9354 18592 9239 18592 9239 18593 9354 18593 9245 18593 9239 18594 9245 18594 9246 18594 9247 18595 9248 18595 9342 18595 9342 18596 9248 18596 9250 18596 9342 18597 9250 18597 9249 18597 9249 18598 9250 18598 9251 18598 9249 18599 9251 18599 9346 18599 9346 18600 9251 18600 9348 18600 9348 18601 9251 18601 7329 18601 9348 18602 7329 18602 9349 18602 9349 18603 7329 18603 9350 18603 9350 18604 7329 18604 7275 18604 9350 18605 7275 18605 9252 18605 9252 18606 7275 18606 7274 18606 9252 18607 7274 18607 9253 18607 9253 18608 7274 18608 7309 18608 9253 18609 7309 18609 9341 18609 9341 18610 7309 18610 9255 18610 9255 18611 7309 18611 9254 18611 9255 18612 9254 18612 9256 18612 9256 18613 9254 18613 9257 18613 9256 18614 9257 18614 9258 18614 9257 18615 9259 18615 9258 18615 9258 18616 9259 18616 7408 18616 9258 18617 7408 18617 9339 18617 7408 18618 7407 18618 9339 18618 9339 18619 7407 18619 9260 18619 9339 18620 9260 18620 9201 18620 9260 18621 7405 18621 9201 18621 9201 18622 7405 18622 7401 18622 9201 18623 7401 18623 9261 18623 9261 18624 7401 18624 7434 18624 9261 18625 7434 18625 8156 18625 9262 18626 9302 18626 9272 18626 9103 18627 9107 18627 9273 18627 9103 18628 9273 18628 9104 18628 9291 18629 9292 18629 9267 18629 9267 18630 9292 18630 9293 18630 9299 18631 9269 18631 9263 18631 9263 18632 9269 18632 9265 18632 9263 18633 9265 18633 9264 18633 9264 18634 9265 18634 9296 18634 9265 18635 11423 18635 9296 18635 9296 18636 11423 18636 11422 18636 9296 18637 11422 18637 9266 18637 9266 18638 11422 18638 9286 18638 9293 18639 9266 18639 9267 18639 9267 18640 9266 18640 9286 18640 9267 18641 9286 18641 9321 18641 9321 18642 9286 18642 9268 18642 9278 18643 9311 18643 9277 18643 9277 18644 9311 18644 9313 18644 9277 18645 9313 18645 9279 18645 9299 18646 9270 18646 9269 18646 9269 18647 9270 18647 9271 18647 9269 18648 9271 18648 9272 18648 9272 18649 9271 18649 9301 18649 9272 18650 9301 18650 9262 18650 9168 18651 9104 18651 9325 18651 9325 18652 9104 18652 9273 18652 9325 18653 9273 18653 9267 18653 9267 18654 9273 18654 9289 18654 9267 18655 9289 18655 9291 18655 9302 18656 9303 18656 9272 18656 9272 18657 9303 18657 9304 18657 9272 18658 9304 18658 9275 18658 9304 18659 9274 18659 9275 18659 9275 18660 9274 18660 9276 18660 9275 18661 9276 18661 9277 18661 9277 18662 9276 18662 9308 18662 9277 18663 9308 18663 9278 18663 9313 18664 9319 18664 9279 18664 9279 18665 9319 18665 9280 18665 9279 18666 9280 18666 9281 18666 9281 18667 9280 18667 9282 18667 9281 18668 9282 18668 11420 18668 11420 18669 9282 18669 9316 18669 11420 18670 9316 18670 9283 18670 9283 18671 9316 18671 9284 18671 9283 18672 9284 18672 9286 18672 9286 18673 9284 18673 9385 18673 9286 18674 9385 18674 9323 18674 9323 18675 9285 18675 9286 18675 9286 18676 9285 18676 9287 18676 9286 18677 9287 18677 9268 18677 9256 18678 9258 18678 9445 18678 9273 18679 9479 18679 9476 18679 7140 18680 11706 18680 9421 18680 9421 18681 11706 18681 9216 18681 9421 18682 9216 18682 9374 18682 9288 18683 9116 18683 9479 18683 9479 18684 9116 18684 7151 18684 9479 18685 7151 18685 9480 18685 9288 18686 9479 18686 9115 18686 9115 18687 9479 18687 9273 18687 9115 18688 9273 18688 9107 18688 9475 18689 9291 18689 9476 18689 9476 18690 9291 18690 9289 18690 9476 18691 9289 18691 9273 18691 9475 18692 9474 18692 9291 18692 9291 18693 9474 18693 9290 18693 9291 18694 9290 18694 9292 18694 9292 18695 9290 18695 9293 18695 9293 18696 9290 18696 9294 18696 9293 18697 9294 18697 9266 18697 9266 18698 9294 18698 9295 18698 9266 18699 9295 18699 9296 18699 9296 18700 9295 18700 9297 18700 9296 18701 9297 18701 9264 18701 9297 18702 9298 18702 9264 18702 9264 18703 9298 18703 9470 18703 9264 18704 9470 18704 9263 18704 9263 18705 9470 18705 9299 18705 9299 18706 9470 18706 9468 18706 9299 18707 9468 18707 9270 18707 9270 18708 9468 18708 9300 18708 9270 18709 9300 18709 9271 18709 9271 18710 9300 18710 9466 18710 9271 18711 9466 18711 9301 18711 9301 18712 9466 18712 9262 18712 9262 18713 9466 18713 9464 18713 9262 18714 9464 18714 9302 18714 9302 18715 9464 18715 9463 18715 9302 18716 9463 18716 9303 18716 9303 18717 9463 18717 9462 18717 9303 18718 9462 18718 9304 18718 9304 18719 9462 18719 9305 18719 9304 18720 9305 18720 9274 18720 9274 18721 9305 18721 9460 18721 9274 18722 9460 18722 9276 18722 9276 18723 9460 18723 9306 18723 9276 18724 9306 18724 9308 18724 9308 18725 9306 18725 9307 18725 9308 18726 9307 18726 9278 18726 9307 18727 9309 18727 9278 18727 9278 18728 9309 18728 9310 18728 9278 18729 9310 18729 9311 18729 9311 18730 9310 18730 9312 18730 9311 18731 9312 18731 9313 18731 9313 18732 9312 18732 9319 18732 9384 18733 9284 18733 9314 18733 9314 18734 9284 18734 9316 18734 9314 18735 9316 18735 9315 18735 9315 18736 9316 18736 9282 18736 9315 18737 9282 18737 9317 18737 9317 18738 9282 18738 9280 18738 9317 18739 9280 18739 9318 18739 9318 18740 9280 18740 9319 18740 9318 18741 9319 18741 9320 18741 9320 18742 9319 18742 9312 18742 9267 18743 9321 18743 9327 18743 9327 18744 9321 18744 9268 18744 9327 18745 9268 18745 9322 18745 9322 18746 9268 18746 9287 18746 9322 18747 9287 18747 9381 18747 9381 18748 9287 18748 9285 18748 9381 18749 9285 18749 9324 18749 9324 18750 9285 18750 9323 18750 9324 18751 9323 18751 9382 18751 9382 18752 9323 18752 9385 18752 9168 18753 9325 18753 9176 18753 9176 18754 9325 18754 9326 18754 9176 18755 9326 18755 9329 18755 9325 18756 9267 18756 9326 18756 9326 18757 9267 18757 9327 18757 9326 18758 9327 18758 6783 18758 6783 18759 9328 18759 9326 18759 9326 18760 9328 18760 6782 18760 9326 18761 6782 18761 9329 18761 9329 18762 6782 18762 9330 18762 9329 18763 9330 18763 9175 18763 9175 18764 9330 18764 9331 18764 9175 18765 9331 18765 9332 18765 9332 18766 9331 18766 9334 18766 9332 18767 9334 18767 9333 18767 9333 18768 9334 18768 9114 18768 9114 18769 9334 18769 9335 18769 9114 18770 9335 18770 9113 18770 9113 18771 9335 18771 9336 18771 9113 18772 9336 18772 9337 18772 9337 18773 9336 18773 9338 18773 9338 18774 9336 18774 6745 18774 9338 18775 6745 18775 9111 18775 9339 18776 9201 18776 9111 18776 9111 18777 6745 18777 9339 18777 9339 18778 6745 18778 10552 18778 9339 18779 10552 18779 9379 18779 9256 18780 9445 18780 9255 18780 9340 18781 9398 18781 9341 18781 9341 18782 9398 18782 9253 18782 9253 18783 9398 18783 9351 18783 9253 18784 9351 18784 9252 18784 9393 18785 9342 18785 9343 18785 9343 18786 9342 18786 9249 18786 9343 18787 9249 18787 9344 18787 9344 18788 9249 18788 9346 18788 9344 18789 9346 18789 9345 18789 9345 18790 9346 18790 9348 18790 9345 18791 9348 18791 9347 18791 9347 18792 9348 18792 9349 18792 9347 18793 9349 18793 9351 18793 9351 18794 9349 18794 9350 18794 9351 18795 9350 18795 9252 18795 9352 18796 9246 18796 9353 18796 9353 18797 9246 18797 9245 18797 9353 18798 9245 18798 9432 18798 9432 18799 9245 18799 9354 18799 9432 18800 9354 18800 9355 18800 9355 18801 9354 18801 9356 18801 9355 18802 9356 18802 9391 18802 9435 18803 9237 18803 9358 18803 9358 18804 9237 18804 9357 18804 9358 18805 9357 18805 9359 18805 9359 18806 9357 18806 9360 18806 9359 18807 9360 18807 9361 18807 9361 18808 9360 18808 9362 18808 9361 18809 9362 18809 9352 18809 9352 18810 9362 18810 9240 18810 9352 18811 9240 18811 9246 18811 9366 18812 9363 18812 9364 18812 9364 18813 9363 18813 9231 18813 9364 18814 9231 18814 9438 18814 9438 18815 9231 18815 9230 18815 9438 18816 9230 18816 9435 18816 9435 18817 9230 18817 9365 18817 9435 18818 9365 18818 9237 18818 9441 18819 9234 18819 9366 18819 9366 18820 9234 18820 9233 18820 9366 18821 9233 18821 9363 18821 9369 18822 9367 18822 9441 18822 9441 18823 9367 18823 9229 18823 9441 18824 9229 18824 9234 18824 9227 18825 9368 18825 9369 18825 9369 18826 9368 18826 9370 18826 9369 18827 9370 18827 9367 18827 9413 18828 9414 18828 9371 18828 9371 18829 9414 18829 9227 18829 9371 18830 9227 18830 9442 18830 9442 18831 9227 18831 9369 18831 9222 18832 9415 18832 9220 18832 9220 18833 9415 18833 9417 18833 9220 18834 9417 18834 9372 18834 9372 18835 9417 18835 9418 18835 9372 18836 9418 18836 9221 18836 9216 18837 9373 18837 9374 18837 9374 18838 9373 18838 9376 18838 9374 18839 9376 18839 9375 18839 9375 18840 9376 18840 9377 18840 9375 18841 9377 18841 9419 18841 9419 18842 9377 18842 9217 18842 9419 18843 9217 18843 9418 18843 9418 18844 9217 18844 9378 18844 9418 18845 9378 18845 9221 18845 9447 18846 6784 18846 9448 18846 6801 18847 9445 18847 9379 18847 9379 18848 9445 18848 9258 18848 9379 18849 9258 18849 9339 18849 6784 18850 6783 18850 9448 18850 9448 18851 6783 18851 9327 18851 9448 18852 9327 18852 9380 18852 9380 18853 9327 18853 9322 18853 9380 18854 9322 18854 9451 18854 9451 18855 9322 18855 9381 18855 9451 18856 9381 18856 9453 18856 9453 18857 9381 18857 9324 18857 9453 18858 9324 18858 9383 18858 9383 18859 9324 18859 9382 18859 9383 18860 9382 18860 9384 18860 9384 18861 9382 18861 9385 18861 9384 18862 9385 18862 9284 18862 9386 18863 9446 18863 9387 18863 9387 18864 9446 18864 9449 18864 9387 18865 9449 18865 9388 18865 9388 18866 9449 18866 9390 18866 9388 18867 9390 18867 9389 18867 9389 18868 9390 18868 9450 18868 9389 18869 9450 18869 9426 18869 9426 18870 9450 18870 9452 18870 9426 18871 9452 18871 9454 18871 9356 18872 9242 18872 9391 18872 9391 18873 9242 18873 9392 18873 9391 18874 9392 18874 9429 18874 9429 18875 9392 18875 9393 18875 9429 18876 9393 18876 9428 18876 9428 18877 9393 18877 9343 18877 9428 18878 9343 18878 9394 18878 9394 18879 9343 18879 9344 18879 9394 18880 9344 18880 9395 18880 9395 18881 9344 18881 9345 18881 9395 18882 9345 18882 9425 18882 9425 18883 9345 18883 9347 18883 9425 18884 9347 18884 9396 18884 9396 18885 9347 18885 9351 18885 9396 18886 9351 18886 9397 18886 9397 18887 9351 18887 9398 18887 9397 18888 9398 18888 9424 18888 9424 18889 9398 18889 9340 18889 9424 18890 9340 18890 9423 18890 9478 18891 7145 18891 9477 18891 9477 18892 7145 18892 9403 18892 9477 18893 9403 18893 9473 18893 9473 18894 9403 18894 9399 18894 9473 18895 9399 18895 9400 18895 9400 18896 9399 18896 9404 18896 9400 18897 9404 18897 9401 18897 9401 18898 9404 18898 9407 18898 9401 18899 9407 18899 9472 18899 9472 18900 9407 18900 9409 18900 9472 18901 9409 18901 9402 18901 9402 18902 9409 18902 9410 18902 9402 18903 9410 18903 9471 18903 9471 18904 9410 18904 9411 18904 9471 18905 9411 18905 9413 18905 7145 18906 7141 18906 9403 18906 9403 18907 7141 18907 9422 18907 9403 18908 9422 18908 9399 18908 9399 18909 9422 18909 9405 18909 9399 18910 9405 18910 9404 18910 9404 18911 9405 18911 9420 18911 9404 18912 9420 18912 9407 18912 9407 18913 9420 18913 9406 18913 9407 18914 9406 18914 9409 18914 9409 18915 9406 18915 9408 18915 9409 18916 9408 18916 9410 18916 9410 18917 9408 18917 9412 18917 9410 18918 9412 18918 9411 18918 9411 18919 9412 18919 9416 18919 9411 18920 9416 18920 9413 18920 9413 18921 9416 18921 9224 18921 9413 18922 9224 18922 9414 18922 9222 18923 9224 18923 9415 18923 9415 18924 9224 18924 9416 18924 9415 18925 9416 18925 9417 18925 9417 18926 9416 18926 9412 18926 9417 18927 9412 18927 9418 18927 9418 18928 9412 18928 9408 18928 9418 18929 9408 18929 9419 18929 9419 18930 9408 18930 9406 18930 9419 18931 9406 18931 9375 18931 9375 18932 9406 18932 9420 18932 9375 18933 9420 18933 9374 18933 9374 18934 9420 18934 9405 18934 9374 18935 9405 18935 9421 18935 9421 18936 9405 18936 9422 18936 9421 18937 9422 18937 7140 18937 7140 18938 9422 18938 7141 18938 9423 18939 9386 18939 9424 18939 9424 18940 9386 18940 9387 18940 9424 18941 9387 18941 9397 18941 9397 18942 9387 18942 9388 18942 9397 18943 9388 18943 9396 18943 9396 18944 9388 18944 9389 18944 9396 18945 9389 18945 9425 18945 9425 18946 9389 18946 9426 18946 9425 18947 9426 18947 9395 18947 9395 18948 9426 18948 9454 18948 9395 18949 9454 18949 9394 18949 9394 18950 9454 18950 9455 18950 9394 18951 9455 18951 9428 18951 9428 18952 9455 18952 9427 18952 9428 18953 9427 18953 9429 18953 9429 18954 9427 18954 9430 18954 9429 18955 9430 18955 9391 18955 9391 18956 9430 18956 9456 18956 9391 18957 9456 18957 9355 18957 9355 18958 9456 18958 9431 18958 9355 18959 9431 18959 9432 18959 9432 18960 9431 18960 9433 18960 9432 18961 9433 18961 9353 18961 9353 18962 9433 18962 9457 18962 9353 18963 9457 18963 9352 18963 9352 18964 9457 18964 9458 18964 9352 18965 9458 18965 9361 18965 9361 18966 9458 18966 9434 18966 9361 18967 9434 18967 9359 18967 9359 18968 9434 18968 9459 18968 9359 18969 9459 18969 9358 18969 9358 18970 9459 18970 9436 18970 9358 18971 9436 18971 9435 18971 9435 18972 9436 18972 9437 18972 9435 18973 9437 18973 9438 18973 9438 18974 9437 18974 9461 18974 9438 18975 9461 18975 9364 18975 9364 18976 9461 18976 9439 18976 9364 18977 9439 18977 9366 18977 9366 18978 9439 18978 9440 18978 9366 18979 9440 18979 9441 18979 9441 18980 9440 18980 9465 18980 9441 18981 9465 18981 9369 18981 9369 18982 9465 18982 9467 18982 9369 18983 9467 18983 9442 18983 9442 18984 9467 18984 9443 18984 9442 18985 9443 18985 9371 18985 9371 18986 9443 18986 9444 18986 9371 18987 9444 18987 9413 18987 9413 18988 9444 18988 9469 18988 9413 18989 9469 18989 9471 18989 9341 18990 9255 18990 9340 18990 9340 18991 9255 18991 9445 18991 9340 18992 9445 18992 9423 18992 9423 18993 9445 18993 6801 18993 9423 18994 6801 18994 9386 18994 9386 18995 6801 18995 9447 18995 9386 18996 9447 18996 9446 18996 9446 18997 9447 18997 9448 18997 9446 18998 9448 18998 9449 18998 9449 18999 9448 18999 9380 18999 9449 19000 9380 19000 9390 19000 9390 19001 9380 19001 9451 19001 9390 19002 9451 19002 9450 19002 9450 19003 9451 19003 9453 19003 9450 19004 9453 19004 9452 19004 9452 19005 9453 19005 9383 19005 9452 19006 9383 19006 9454 19006 9454 19007 9383 19007 9384 19007 9454 19008 9384 19008 9455 19008 9455 19009 9384 19009 9314 19009 9455 19010 9314 19010 9427 19010 9427 19011 9314 19011 9315 19011 9427 19012 9315 19012 9430 19012 9430 19013 9315 19013 9317 19013 9430 19014 9317 19014 9456 19014 9456 19015 9317 19015 9318 19015 9456 19016 9318 19016 9431 19016 9431 19017 9318 19017 9320 19017 9431 19018 9320 19018 9433 19018 9433 19019 9320 19019 9312 19019 9433 19020 9312 19020 9457 19020 9457 19021 9312 19021 9310 19021 9457 19022 9310 19022 9458 19022 9458 19023 9310 19023 9309 19023 9458 19024 9309 19024 9434 19024 9434 19025 9309 19025 9307 19025 9434 19026 9307 19026 9459 19026 9459 19027 9307 19027 9306 19027 9459 19028 9306 19028 9436 19028 9436 19029 9306 19029 9460 19029 9436 19030 9460 19030 9437 19030 9437 19031 9460 19031 9305 19031 9437 19032 9305 19032 9461 19032 9461 19033 9305 19033 9462 19033 9461 19034 9462 19034 9439 19034 9439 19035 9462 19035 9463 19035 9439 19036 9463 19036 9440 19036 9440 19037 9463 19037 9464 19037 9440 19038 9464 19038 9465 19038 9465 19039 9464 19039 9466 19039 9465 19040 9466 19040 9467 19040 9467 19041 9466 19041 9300 19041 9467 19042 9300 19042 9443 19042 9443 19043 9300 19043 9468 19043 9443 19044 9468 19044 9444 19044 9444 19045 9468 19045 9470 19045 9444 19046 9470 19046 9469 19046 9469 19047 9470 19047 9298 19047 9469 19048 9298 19048 9471 19048 9471 19049 9298 19049 9297 19049 9471 19050 9297 19050 9402 19050 9402 19051 9297 19051 9295 19051 9402 19052 9295 19052 9472 19052 9472 19053 9295 19053 9294 19053 9472 19054 9294 19054 9401 19054 9401 19055 9294 19055 9290 19055 9401 19056 9290 19056 9400 19056 9400 19057 9290 19057 9474 19057 9400 19058 9474 19058 9473 19058 9473 19059 9474 19059 9475 19059 9473 19060 9475 19060 9477 19060 9477 19061 9475 19061 9476 19061 9477 19062 9476 19062 9478 19062 9478 19063 9476 19063 9479 19063 9478 19064 9479 19064 7153 19064 7153 19065 9479 19065 9480 19065 9481 19066 9587 19066 9503 19066 9575 19067 9573 19067 9482 19067 9498 19068 9517 19068 9516 19068 9513 19069 9511 19069 9553 19069 9561 19070 9483 19070 9569 19070 9484 19071 9485 19071 9516 19071 9554 19072 9598 19072 9596 19072 6608 19073 9486 19073 9597 19073 9487 19074 9488 19074 9503 19074 9494 19075 9524 19075 9523 19075 9491 19076 9489 19076 9566 19076 9534 19077 9535 19077 6406 19077 8966 19078 9490 19078 6388 19078 9491 19079 9566 19079 9492 19079 9492 19080 9566 19080 9567 19080 9492 19081 9567 19081 6439 19081 9493 19082 9494 19082 9495 19082 9495 19083 9494 19083 9523 19083 9495 19084 9523 19084 9496 19084 9496 19085 9523 19085 9520 19085 9496 19086 9520 19086 6523 19086 6523 19087 9520 19087 6527 19087 9497 19088 9517 19088 6546 19088 6546 19089 9517 19089 9498 19089 6546 19090 9498 19090 6547 19090 9572 19091 10653 19091 6570 19091 6570 19092 10653 19092 10651 19092 6570 19093 10651 19093 6571 19093 6571 19094 10651 19094 10657 19094 6571 19095 10657 19095 6573 19095 6573 19096 10657 19096 9499 19096 6573 19097 9499 19097 6574 19097 6574 19098 9499 19098 9500 19098 6574 19099 9500 19099 6575 19099 6575 19100 9500 19100 9501 19100 6575 19101 9501 19101 6577 19101 6577 19102 9501 19102 10659 19102 6577 19103 10659 19103 9603 19103 9603 19104 10659 19104 10660 19104 9587 19105 9502 19105 9503 19105 9503 19106 9502 19106 9504 19106 9503 19107 9504 19107 9487 19107 9509 19108 9505 19108 9506 19108 9509 19109 9506 19109 9511 19109 9506 19110 9507 19110 9511 19110 9511 19111 9507 19111 6651 19111 9511 19112 6651 19112 9553 19112 9553 19113 6651 19113 6641 19113 9553 19114 6641 19114 6605 19114 9505 19115 9510 19115 6717 19115 6717 19116 9510 19116 9010 19116 6717 19117 9010 19117 6738 19117 6738 19118 9010 19118 9508 19118 9505 19119 9509 19119 9510 19119 9510 19120 9509 19120 9511 19120 9510 19121 9511 19121 9512 19121 9512 19122 9511 19122 9513 19122 9512 19123 9513 19123 9009 19123 9009 19124 9513 19124 9552 19124 9009 19125 9552 19125 9550 19125 8011 19126 9007 19126 9514 19126 9514 19127 9007 19127 9556 19127 9519 19128 9484 19128 9515 19128 9515 19129 9484 19129 9516 19129 9515 19130 9516 19130 6524 19130 6524 19131 9516 19131 9517 19131 6524 19132 9517 19132 6525 19132 6525 19133 9517 19133 9497 19133 9521 19134 10015 19134 9515 19134 9515 19135 10015 19135 9518 19135 9515 19136 9518 19136 9519 19136 6524 19137 6527 19137 9515 19137 9515 19138 6527 19138 9520 19138 9515 19139 9520 19139 9521 19139 9521 19140 9520 19140 9523 19140 9521 19141 9523 19141 9522 19141 9522 19142 9523 19142 9524 19142 9522 19143 9524 19143 9525 19143 9525 19144 9524 19144 9558 19144 9570 19145 9571 19145 9526 19145 9483 19146 9527 19146 9569 19146 9569 19147 9527 19147 10010 19147 9569 19148 10010 19148 9931 19148 9528 19149 9924 19149 9560 19149 9560 19150 9924 19150 9559 19150 9529 19151 9033 19151 9528 19151 9528 19152 9560 19152 9529 19152 9529 19153 9560 19153 9562 19153 9529 19154 9562 19154 8974 19154 8974 19155 9562 19155 9563 19155 8974 19156 9563 19156 9530 19156 9565 19157 9531 19157 9563 19157 9563 19158 9531 19158 9532 19158 9532 19159 9533 19159 9563 19159 9563 19160 9533 19160 8975 19160 9563 19161 8975 19161 9530 19161 6388 19162 9490 19162 9534 19162 9534 19163 9490 19163 8970 19163 9534 19164 8970 19164 9535 19164 9535 19165 8970 19165 8969 19165 9535 19166 8969 19166 9536 19166 9536 19167 9537 19167 9535 19167 9535 19168 9537 19168 6886 19168 9535 19169 6886 19169 9538 19169 9538 19170 9539 19170 9535 19170 9535 19171 9539 19171 9540 19171 9535 19172 9540 19172 9565 19172 9540 19173 9541 19173 9565 19173 9565 19174 9541 19174 6889 19174 9565 19175 6889 19175 9542 19175 9542 19176 6888 19176 9565 19176 9565 19177 6888 19177 9543 19177 9565 19178 9543 19178 9544 19178 9544 19179 9545 19179 9565 19179 9565 19180 9545 19180 9546 19180 9565 19181 9546 19181 9531 19181 10098 19182 10124 19182 9547 19182 10098 19183 9547 19183 9593 19183 10124 19184 10107 19184 9547 19184 9547 19185 10107 19185 9548 19185 9547 19186 9548 19186 9582 19186 9549 19187 9550 19187 9551 19187 9551 19188 9550 19188 9552 19188 9551 19189 9552 19189 9594 19189 9594 19190 9552 19190 9513 19190 9594 19191 9513 19191 9595 19191 9595 19192 9513 19192 9553 19192 9595 19193 9553 19193 9596 19193 9596 19194 9553 19194 6605 19194 9596 19195 6605 19195 9554 19195 9582 19196 10085 19196 9556 19196 10085 19197 10084 19197 9556 19197 9556 19198 10084 19198 9555 19198 9556 19199 9555 19199 9514 19199 6439 19200 9567 19200 9493 19200 9493 19201 9567 19201 9557 19201 9493 19202 9557 19202 9494 19202 9494 19203 9557 19203 9570 19203 9494 19204 9570 19204 9524 19204 9524 19205 9570 19205 9526 19205 9524 19206 9526 19206 9558 19206 9559 19207 9561 19207 9560 19207 9560 19208 9561 19208 9569 19208 9560 19209 9569 19209 9562 19209 9562 19210 9569 19210 9568 19210 9562 19211 9568 19211 9563 19211 9563 19212 9568 19212 9564 19212 9563 19213 9564 19213 9565 19213 6406 19214 9535 19214 9489 19214 9489 19215 9535 19215 9565 19215 9489 19216 9565 19216 9566 19216 9566 19217 9565 19217 9564 19217 9566 19218 9564 19218 9567 19218 9567 19219 9564 19219 9568 19219 9567 19220 9568 19220 9557 19220 9557 19221 9568 19221 9569 19221 9557 19222 9569 19222 9570 19222 9570 19223 9569 19223 9931 19223 9570 19224 9931 19224 9571 19224 9572 19225 6547 19225 10653 19225 10653 19226 6547 19226 9498 19226 10653 19227 9498 19227 10654 19227 10654 19228 9498 19228 9516 19228 10654 19229 9516 19229 10647 19229 10647 19230 9516 19230 9485 19230 10096 19231 10095 19231 10664 19231 10664 19232 10095 19232 9576 19232 9589 19233 9573 19233 9574 19233 9574 19234 9573 19234 9575 19234 9574 19235 9575 19235 10661 19235 10095 19236 10094 19236 9576 19236 9576 19237 10094 19237 9577 19237 9576 19238 9577 19238 9578 19238 9577 19239 10097 19239 9578 19239 9578 19240 10097 19240 9580 19240 9578 19241 9580 19241 9579 19241 9579 19242 9580 19242 10127 19242 9579 19243 10127 19243 9581 19243 9582 19244 9556 19244 9547 19244 9547 19245 9556 19245 9583 19245 9547 19246 9583 19246 9585 19246 9585 19247 9583 19247 9584 19247 9585 19248 9584 19248 9599 19248 9599 19249 9584 19249 9586 19249 9599 19250 9586 19250 9600 19250 9600 19251 9586 19251 9597 19251 9600 19252 9597 19252 9481 19252 9481 19253 9597 19253 9486 19253 9481 19254 9486 19254 9587 19254 9587 19255 9486 19255 9588 19255 9587 19256 9588 19256 9502 19256 9589 19257 10664 19257 9573 19257 9573 19258 10664 19258 9576 19258 9573 19259 9576 19259 9482 19259 9482 19260 9576 19260 9578 19260 9482 19261 9578 19261 9590 19261 9590 19262 9578 19262 9579 19262 9581 19263 10102 19263 9579 19263 9579 19264 10102 19264 9591 19264 9579 19265 9591 19265 9592 19265 9592 19266 9591 19266 10101 19266 9592 19267 10101 19267 9593 19267 9007 19268 9549 19268 9556 19268 9556 19269 9549 19269 9551 19269 9556 19270 9551 19270 9583 19270 9583 19271 9551 19271 9594 19271 9583 19272 9594 19272 9584 19272 9584 19273 9594 19273 9595 19273 9584 19274 9595 19274 9586 19274 9586 19275 9595 19275 9596 19275 9586 19276 9596 19276 9597 19276 9597 19277 9596 19277 9598 19277 9597 19278 9598 19278 6608 19278 9593 19279 9547 19279 9592 19279 9592 19280 9547 19280 9585 19280 9592 19281 9585 19281 9579 19281 9579 19282 9585 19282 9599 19282 9579 19283 9599 19283 9590 19283 9590 19284 9599 19284 9600 19284 9590 19285 9600 19285 9482 19285 9482 19286 9600 19286 9481 19286 9482 19287 9481 19287 9575 19287 9575 19288 9481 19288 9503 19288 9575 19289 9503 19289 10661 19289 10661 19290 9503 19290 9488 19290 10661 19291 9488 19291 10658 19291 10658 19292 9488 19292 9601 19292 10658 19293 9601 19293 10660 19293 10660 19294 9601 19294 9602 19294 10660 19295 9602 19295 9603 19295 9604 19296 9956 19296 9899 19296 10090 19297 10089 19297 9921 19297 9792 19298 10120 19298 9828 19298 9605 19299 9832 19299 9838 19299 9949 19300 9803 19300 9804 19300 10031 19301 9951 19301 9805 19301 9896 19302 9773 19302 9898 19302 9897 19303 9606 19303 9704 19303 9607 19304 10092 19304 9677 19304 9608 19305 10631 19305 9768 19305 9609 19306 9610 19306 9605 19306 9605 19307 9610 19307 9611 19307 9605 19308 9611 19308 9832 19308 9832 19309 9611 19309 9612 19309 9832 19310 9612 19310 9833 19310 9796 19311 9827 19311 8117 19311 9613 19312 9615 19312 9826 19312 9613 19313 9614 19313 9615 19313 9615 19314 9614 19314 9786 19314 9615 19315 9786 19315 9616 19315 9616 19316 9786 19316 9617 19316 9616 19317 9617 19317 8115 19317 8115 19318 9617 19318 9784 19318 8115 19319 9784 19319 9618 19319 9784 19320 9781 19320 9618 19320 9618 19321 9781 19321 9619 19321 9618 19322 9619 19322 8112 19322 8112 19323 9619 19323 9620 19323 8112 19324 9620 19324 8109 19324 8109 19325 9620 19325 9779 19325 8109 19326 9779 19326 9621 19326 9779 19327 9622 19327 9621 19327 9621 19328 9622 19328 9624 19328 9621 19329 9624 19329 9623 19329 9623 19330 9624 19330 9626 19330 9623 19331 9626 19331 9625 19331 9626 19332 9627 19332 9625 19332 9625 19333 9627 19333 9775 19333 9625 19334 9775 19334 8105 19334 8105 19335 9775 19335 9774 19335 8105 19336 9774 19336 8104 19336 9630 19337 9628 19337 9629 19337 9629 19338 9938 19338 9630 19338 9630 19339 9938 19339 9937 19339 9630 19340 9937 19340 9631 19340 9763 19341 9632 19341 10621 19341 10621 19342 9632 19342 9633 19342 9633 19343 9632 19343 10622 19343 10622 19344 9632 19344 9634 19344 10622 19345 9634 19345 9635 19345 9635 19346 9634 19346 9760 19346 9635 19347 9760 19347 9636 19347 9636 19348 9760 19348 9637 19348 9636 19349 9637 19349 10624 19349 10624 19350 9637 19350 9638 19350 10624 19351 9638 19351 9639 19351 9639 19352 9638 19352 9758 19352 9639 19353 9758 19353 9644 19353 9640 19354 9641 19354 9642 19354 9642 19355 9641 19355 10618 19355 9642 19356 10618 19356 9755 19356 9755 19357 10618 19357 9643 19357 9755 19358 9643 19358 9644 19358 9644 19359 9643 19359 10626 19359 9644 19360 10626 19360 9639 19360 10684 19361 9645 19361 9640 19361 9640 19362 9645 19362 9646 19362 9640 19363 9646 19363 9641 19363 9640 19364 9753 19364 10684 19364 10684 19365 9753 19365 9751 19365 10684 19366 9751 19366 9652 19366 9741 19367 9654 19367 9648 19367 9648 19368 9654 19368 9647 19368 9648 19369 9647 19369 9744 19369 9744 19370 9647 19370 10687 19370 9744 19371 10687 19371 9745 19371 9745 19372 10687 19372 9649 19372 9745 19373 9649 19373 9747 19373 9747 19374 9649 19374 9650 19374 9747 19375 9650 19375 9651 19375 9651 19376 9650 19376 9652 19376 9651 19377 9652 19377 9750 19377 9750 19378 9652 19378 9751 19378 10674 19379 10673 19379 9741 19379 9741 19380 10673 19380 9653 19380 9741 19381 9653 19381 9654 19381 9741 19382 9655 19382 10674 19382 10674 19383 9655 19383 9739 19383 10674 19384 9739 19384 9738 19384 10093 19385 10680 19385 10679 19385 9704 19386 9606 19386 9656 19386 9656 19387 9606 19387 9657 19387 9656 19388 9657 19388 9702 19388 9702 19389 9657 19389 9658 19389 9702 19390 9658 19390 9700 19390 9700 19391 9658 19391 9660 19391 9700 19392 9660 19392 9659 19392 9659 19393 9660 19393 9661 19393 9659 19394 9661 19394 9698 19394 9698 19395 9661 19395 9662 19395 9698 19396 9662 19396 9663 19396 9663 19397 9662 19397 9903 19397 9663 19398 9903 19398 9696 19398 9696 19399 9903 19399 9665 19399 9696 19400 9665 19400 9664 19400 9664 19401 9665 19401 9905 19401 9664 19402 9905 19402 9666 19402 9666 19403 9905 19403 9906 19403 9666 19404 9906 19404 9693 19404 9693 19405 9906 19405 9908 19405 9693 19406 9908 19406 9667 19406 9667 19407 9908 19407 9668 19407 9667 19408 9668 19408 9669 19408 9669 19409 9668 19409 9909 19409 9669 19410 9909 19410 9670 19410 9670 19411 9909 19411 9671 19411 9670 19412 9671 19412 9691 19412 9691 19413 9671 19413 9672 19413 9691 19414 9672 19414 9689 19414 9689 19415 9672 19415 9911 19415 9689 19416 9911 19416 9673 19416 9673 19417 9911 19417 9912 19417 9673 19418 9912 19418 9687 19418 9687 19419 9912 19419 9674 19419 9687 19420 9674 19420 9676 19420 9676 19421 9674 19421 9675 19421 9676 19422 9675 19422 9914 19422 10089 19423 9607 19423 9921 19423 9921 19424 9607 19424 9677 19424 9921 19425 9677 19425 9920 19425 9920 19426 9677 19426 9707 19426 9920 19427 9707 19427 9678 19427 9678 19428 9707 19428 9708 19428 9678 19429 9708 19429 9679 19429 9679 19430 9708 19430 9709 19430 9679 19431 9709 19431 9680 19431 9680 19432 9709 19432 9681 19432 9680 19433 9681 19433 9917 19433 9917 19434 9681 19434 9711 19434 9917 19435 9711 19435 9682 19435 9682 19436 9711 19436 9713 19436 9682 19437 9713 19437 9683 19437 9683 19438 9713 19438 9714 19438 9683 19439 9714 19439 9684 19439 9684 19440 9714 19440 9715 19440 9684 19441 9715 19441 9685 19441 9685 19442 9715 19442 9717 19442 9685 19443 9717 19443 9914 19443 9914 19444 9717 19444 9718 19444 9914 19445 9718 19445 9676 19445 9676 19446 9718 19446 9686 19446 9676 19447 9686 19447 9687 19447 9687 19448 9686 19448 9688 19448 9687 19449 9688 19449 9673 19449 9673 19450 9688 19450 9720 19450 9673 19451 9720 19451 9689 19451 9689 19452 9720 19452 9690 19452 9689 19453 9690 19453 9691 19453 9691 19454 9690 19454 9692 19454 9691 19455 9692 19455 9670 19455 9670 19456 9692 19456 9722 19456 9670 19457 9722 19457 9669 19457 9669 19458 9722 19458 9723 19458 9669 19459 9723 19459 9667 19459 9667 19460 9723 19460 9725 19460 9667 19461 9725 19461 9693 19461 9693 19462 9725 19462 9727 19462 9693 19463 9727 19463 9666 19463 9666 19464 9727 19464 9694 19464 9666 19465 9694 19465 9664 19465 9664 19466 9694 19466 9695 19466 9664 19467 9695 19467 9696 19467 9696 19468 9695 19468 9729 19468 9696 19469 9729 19469 9663 19469 9663 19470 9729 19470 9697 19470 9663 19471 9697 19471 9698 19471 9698 19472 9697 19472 9699 19472 9698 19473 9699 19473 9659 19473 9659 19474 9699 19474 9701 19474 9659 19475 9701 19475 9700 19475 9700 19476 9701 19476 9732 19476 9700 19477 9732 19477 9702 19477 9702 19478 9732 19478 9703 19478 9702 19479 9703 19479 9656 19479 9656 19480 9703 19480 9895 19480 9656 19481 9895 19481 9704 19481 10092 19482 10093 19482 9677 19482 9677 19483 10093 19483 9705 19483 9677 19484 9705 19484 9707 19484 9707 19485 9705 19485 9706 19485 9707 19486 9706 19486 9708 19486 9708 19487 9706 19487 9735 19487 9708 19488 9735 19488 9709 19488 9709 19489 9735 19489 9736 19489 9709 19490 9736 19490 9681 19490 9681 19491 9736 19491 9710 19491 9681 19492 9710 19492 9711 19492 9711 19493 9710 19493 9712 19493 9711 19494 9712 19494 9713 19494 9713 19495 9712 19495 9740 19495 9713 19496 9740 19496 9714 19496 9714 19497 9740 19497 9742 19497 9714 19498 9742 19498 9715 19498 9715 19499 9742 19499 9716 19499 9715 19500 9716 19500 9717 19500 9717 19501 9716 19501 9719 19501 9717 19502 9719 19502 9718 19502 9718 19503 9719 19503 9743 19503 9718 19504 9743 19504 9686 19504 9686 19505 9743 19505 9746 19505 9686 19506 9746 19506 9688 19506 9688 19507 9746 19507 9748 19507 9688 19508 9748 19508 9720 19508 9720 19509 9748 19509 9749 19509 9720 19510 9749 19510 9690 19510 9690 19511 9749 19511 9752 19511 9690 19512 9752 19512 9692 19512 9692 19513 9752 19513 9721 19513 9692 19514 9721 19514 9722 19514 9722 19515 9721 19515 9724 19515 9722 19516 9724 19516 9723 19516 9723 19517 9724 19517 9754 19517 9723 19518 9754 19518 9725 19518 9725 19519 9754 19519 9726 19519 9725 19520 9726 19520 9727 19520 9727 19521 9726 19521 9756 19521 9727 19522 9756 19522 9694 19522 9694 19523 9756 19523 9757 19523 9694 19524 9757 19524 9695 19524 9695 19525 9757 19525 9728 19525 9695 19526 9728 19526 9729 19526 9729 19527 9728 19527 9759 19527 9729 19528 9759 19528 9697 19528 9697 19529 9759 19529 9730 19529 9697 19530 9730 19530 9699 19530 9699 19531 9730 19531 9761 19531 9699 19532 9761 19532 9701 19532 9701 19533 9761 19533 9731 19533 9701 19534 9731 19534 9732 19534 9732 19535 9731 19535 9762 19535 9732 19536 9762 19536 9703 19536 9703 19537 9762 19537 9733 19537 9703 19538 9733 19538 9895 19538 10093 19539 10679 19539 9705 19539 9705 19540 10679 19540 10678 19540 9705 19541 10678 19541 9706 19541 9706 19542 10678 19542 9734 19542 9706 19543 9734 19543 9735 19543 9735 19544 9734 19544 10676 19544 9735 19545 10676 19545 9736 19545 9736 19546 10676 19546 9737 19546 9736 19547 9737 19547 9710 19547 9710 19548 9737 19548 9738 19548 9710 19549 9738 19549 9712 19549 9712 19550 9738 19550 9739 19550 9712 19551 9739 19551 9740 19551 9740 19552 9739 19552 9655 19552 9740 19553 9655 19553 9742 19553 9742 19554 9655 19554 9741 19554 9742 19555 9741 19555 9716 19555 9716 19556 9741 19556 9648 19556 9716 19557 9648 19557 9719 19557 9719 19558 9648 19558 9744 19558 9719 19559 9744 19559 9743 19559 9743 19560 9744 19560 9745 19560 9743 19561 9745 19561 9746 19561 9746 19562 9745 19562 9747 19562 9746 19563 9747 19563 9748 19563 9748 19564 9747 19564 9651 19564 9748 19565 9651 19565 9749 19565 9749 19566 9651 19566 9750 19566 9749 19567 9750 19567 9752 19567 9752 19568 9750 19568 9751 19568 9752 19569 9751 19569 9721 19569 9721 19570 9751 19570 9753 19570 9721 19571 9753 19571 9724 19571 9724 19572 9753 19572 9640 19572 9724 19573 9640 19573 9754 19573 9754 19574 9640 19574 9642 19574 9754 19575 9642 19575 9726 19575 9726 19576 9642 19576 9755 19576 9726 19577 9755 19577 9756 19577 9756 19578 9755 19578 9644 19578 9756 19579 9644 19579 9757 19579 9757 19580 9644 19580 9758 19580 9757 19581 9758 19581 9728 19581 9728 19582 9758 19582 9638 19582 9728 19583 9638 19583 9759 19583 9759 19584 9638 19584 9637 19584 9759 19585 9637 19585 9730 19585 9730 19586 9637 19586 9760 19586 9730 19587 9760 19587 9761 19587 9761 19588 9760 19588 9634 19588 9761 19589 9634 19589 9731 19589 9731 19590 9634 19590 9632 19590 9731 19591 9632 19591 9762 19591 9762 19592 9632 19592 9763 19592 9762 19593 9763 19593 9733 19593 10628 19594 9628 19594 9766 19594 9766 19595 9628 19595 9630 19595 9766 19596 9630 19596 9764 19596 9764 19597 9630 19597 9631 19597 9631 19598 9942 19598 9764 19598 9764 19599 9942 19599 9765 19599 9764 19600 9765 19600 9944 19600 10631 19601 10628 19601 9768 19601 9768 19602 10628 19602 9766 19602 9768 19603 9766 19603 9767 19603 9767 19604 9766 19604 9764 19604 9767 19605 9764 19605 9771 19605 9771 19606 9764 19606 9944 19606 9944 19607 9943 19607 9771 19607 9771 19608 9943 19608 9946 19608 9771 19609 9946 19609 9772 19609 10620 19610 9608 19610 9769 19610 9769 19611 9608 19611 9768 19611 9769 19612 9768 19612 9894 19612 9894 19613 9768 19613 9767 19613 9894 19614 9767 19614 9770 19614 9770 19615 9767 19615 9771 19615 9770 19616 9771 19616 9896 19616 9896 19617 9771 19617 9772 19617 9896 19618 9772 19618 9773 19618 9807 19619 9774 19619 9809 19619 9809 19620 9774 19620 9775 19620 9809 19621 9775 19621 9810 19621 9810 19622 9775 19622 9627 19622 9810 19623 9627 19623 9776 19623 9776 19624 9627 19624 9626 19624 9776 19625 9626 19625 9777 19625 9777 19626 9626 19626 9624 19626 9777 19627 9624 19627 9778 19627 9778 19628 9624 19628 9622 19628 9778 19629 9622 19629 9813 19629 9813 19630 9622 19630 9779 19630 9813 19631 9779 19631 9815 19631 9815 19632 9779 19632 9620 19632 9815 19633 9620 19633 9816 19633 9816 19634 9620 19634 9619 19634 9816 19635 9619 19635 9780 19635 9780 19636 9619 19636 9781 19636 9780 19637 9781 19637 9782 19637 9782 19638 9781 19638 9784 19638 9782 19639 9784 19639 9783 19639 9783 19640 9784 19640 9617 19640 9783 19641 9617 19641 9785 19641 9785 19642 9617 19642 9786 19642 9785 19643 9786 19643 9821 19643 9821 19644 9786 19644 9614 19644 9821 19645 9614 19645 9823 19645 9823 19646 9614 19646 9613 19646 9807 19647 9805 19647 9774 19647 9774 19648 9805 19648 9951 19648 9774 19649 9951 19649 8104 19649 8104 19650 9951 19650 8127 19650 10088 19651 9791 19651 9787 19651 9787 19652 9791 19652 9788 19652 9787 19653 9788 19653 9789 19653 9831 19654 9788 19654 9790 19654 9790 19655 9788 19655 9791 19655 9790 19656 9791 19656 9792 19656 9792 19657 9791 19657 10088 19657 9792 19658 10088 19658 10120 19658 9793 19659 9919 19659 9836 19659 9836 19660 9919 19660 9834 19660 9836 19661 9834 19661 9794 19661 9829 19662 9795 19662 9830 19662 9830 19663 9795 19663 9837 19663 9830 19664 9837 19664 9838 19664 9827 19665 9796 19665 9825 19665 9825 19666 9796 19666 9888 19666 9825 19667 9888 19667 9885 19667 9843 19668 9797 19668 9798 19668 9798 19669 9797 19669 9799 19669 9798 19670 9799 19670 9800 19670 9800 19671 9799 19671 9842 19671 9800 19672 9842 19672 9890 19672 9890 19673 9842 19673 9802 19673 9890 19674 9802 19674 9801 19674 9801 19675 9802 19675 9841 19675 9801 19676 9841 19676 9835 19676 9803 19677 10031 19677 9804 19677 9804 19678 10031 19678 9805 19678 9804 19679 9805 19679 9806 19679 9806 19680 9805 19680 9807 19680 9806 19681 9807 19681 9808 19681 9808 19682 9807 19682 9809 19682 9808 19683 9809 19683 9876 19683 9876 19684 9809 19684 9810 19684 9876 19685 9810 19685 9877 19685 9877 19686 9810 19686 9776 19686 9877 19687 9776 19687 9811 19687 9811 19688 9776 19688 9777 19688 9811 19689 9777 19689 9812 19689 9812 19690 9777 19690 9778 19690 9812 19691 9778 19691 9879 19691 9879 19692 9778 19692 9813 19692 9879 19693 9813 19693 9881 19693 9881 19694 9813 19694 9815 19694 9881 19695 9815 19695 9814 19695 9814 19696 9815 19696 9816 19696 9814 19697 9816 19697 9817 19697 9817 19698 9816 19698 9780 19698 9817 19699 9780 19699 9818 19699 9818 19700 9780 19700 9782 19700 9818 19701 9782 19701 9819 19701 9819 19702 9782 19702 9783 19702 9819 19703 9783 19703 9820 19703 9820 19704 9783 19704 9785 19704 9820 19705 9785 19705 9822 19705 9822 19706 9785 19706 9821 19706 9822 19707 9821 19707 9824 19707 9824 19708 9821 19708 9823 19708 9824 19709 9823 19709 9885 19709 9885 19710 9823 19710 9613 19710 9885 19711 9613 19711 9825 19711 9825 19712 9613 19712 9826 19712 9825 19713 9826 19713 9827 19713 9828 19714 9829 19714 9792 19714 9792 19715 9829 19715 9830 19715 9792 19716 9830 19716 9790 19716 9790 19717 9830 19717 9838 19717 9790 19718 9838 19718 9831 19718 9831 19719 9838 19719 9832 19719 9831 19720 9832 19720 8031 19720 8031 19721 9832 19721 9833 19721 9919 19722 9893 19722 9834 19722 9834 19723 9893 19723 9892 19723 9834 19724 9892 19724 9794 19724 9794 19725 9892 19725 9835 19725 9794 19726 9835 19726 9839 19726 9839 19727 9835 19727 9841 19727 9795 19728 9793 19728 9837 19728 9837 19729 9793 19729 9836 19729 9837 19730 9836 19730 9838 19730 9838 19731 9836 19731 9794 19731 9838 19732 9794 19732 9605 19732 9605 19733 9794 19733 9839 19733 9605 19734 9839 19734 9609 19734 9609 19735 9839 19735 9841 19735 9609 19736 9841 19736 9840 19736 9840 19737 9841 19737 9802 19737 9840 19738 9802 19738 8119 19738 8119 19739 9802 19739 9842 19739 8119 19740 9842 19740 8118 19740 8118 19741 9842 19741 9799 19741 8118 19742 9799 19742 8117 19742 8117 19743 9799 19743 9797 19743 8117 19744 9797 19744 9796 19744 9796 19745 9797 19745 9843 19745 9796 19746 9843 19746 9888 19746 9956 19747 9875 19747 9899 19747 9899 19748 9875 19748 9844 19748 9899 19749 9844 19749 9900 19749 9900 19750 9844 19750 9845 19750 9900 19751 9845 19751 9901 19751 9901 19752 9845 19752 9846 19752 9901 19753 9846 19753 9848 19753 9848 19754 9846 19754 9847 19754 9848 19755 9847 19755 9849 19755 9849 19756 9847 19756 9850 19756 9849 19757 9850 19757 9851 19757 9851 19758 9850 19758 9852 19758 9851 19759 9852 19759 9902 19759 9902 19760 9852 19760 9878 19760 9902 19761 9878 19761 9853 19761 9853 19762 9878 19762 9854 19762 9853 19763 9854 19763 9904 19763 9904 19764 9854 19764 9880 19764 9904 19765 9880 19765 9855 19765 9855 19766 9880 19766 9856 19766 9855 19767 9856 19767 9907 19767 9907 19768 9856 19768 9882 19768 9907 19769 9882 19769 9857 19769 9857 19770 9882 19770 9859 19770 9857 19771 9859 19771 9858 19771 9858 19772 9859 19772 9860 19772 9858 19773 9860 19773 9910 19773 9910 19774 9860 19774 9861 19774 9910 19775 9861 19775 9862 19775 9862 19776 9861 19776 9883 19776 9862 19777 9883 19777 9864 19777 9864 19778 9883 19778 9863 19778 9864 19779 9863 19779 9865 19779 9865 19780 9863 19780 9884 19780 9865 19781 9884 19781 9866 19781 9866 19782 9884 19782 9886 19782 9866 19783 9886 19783 9867 19783 9867 19784 9886 19784 9887 19784 9867 19785 9887 19785 9913 19785 9913 19786 9887 19786 9869 19786 9913 19787 9869 19787 9868 19787 9868 19788 9869 19788 9889 19788 9868 19789 9889 19789 9870 19789 9870 19790 9889 19790 9871 19790 9870 19791 9871 19791 9915 19791 9915 19792 9871 19792 9872 19792 9915 19793 9872 19793 9873 19793 9873 19794 9872 19794 9874 19794 9873 19795 9874 19795 9916 19795 9916 19796 9874 19796 9891 19796 9916 19797 9891 19797 9918 19797 9875 19798 9949 19798 9844 19798 9844 19799 9949 19799 9804 19799 9844 19800 9804 19800 9845 19800 9845 19801 9804 19801 9806 19801 9845 19802 9806 19802 9846 19802 9846 19803 9806 19803 9808 19803 9846 19804 9808 19804 9847 19804 9847 19805 9808 19805 9876 19805 9847 19806 9876 19806 9850 19806 9850 19807 9876 19807 9877 19807 9850 19808 9877 19808 9852 19808 9852 19809 9877 19809 9811 19809 9852 19810 9811 19810 9878 19810 9878 19811 9811 19811 9812 19811 9878 19812 9812 19812 9854 19812 9854 19813 9812 19813 9879 19813 9854 19814 9879 19814 9880 19814 9880 19815 9879 19815 9881 19815 9880 19816 9881 19816 9856 19816 9856 19817 9881 19817 9814 19817 9856 19818 9814 19818 9882 19818 9882 19819 9814 19819 9817 19819 9882 19820 9817 19820 9859 19820 9859 19821 9817 19821 9818 19821 9859 19822 9818 19822 9860 19822 9860 19823 9818 19823 9819 19823 9860 19824 9819 19824 9861 19824 9861 19825 9819 19825 9820 19825 9861 19826 9820 19826 9883 19826 9883 19827 9820 19827 9822 19827 9883 19828 9822 19828 9863 19828 9863 19829 9822 19829 9824 19829 9863 19830 9824 19830 9884 19830 9884 19831 9824 19831 9885 19831 9884 19832 9885 19832 9886 19832 9886 19833 9885 19833 9888 19833 9886 19834 9888 19834 9887 19834 9887 19835 9888 19835 9843 19835 9887 19836 9843 19836 9869 19836 9869 19837 9843 19837 9798 19837 9869 19838 9798 19838 9889 19838 9889 19839 9798 19839 9800 19839 9889 19840 9800 19840 9871 19840 9871 19841 9800 19841 9890 19841 9871 19842 9890 19842 9872 19842 9872 19843 9890 19843 9801 19843 9872 19844 9801 19844 9874 19844 9874 19845 9801 19845 9835 19845 9874 19846 9835 19846 9891 19846 9891 19847 9835 19847 9892 19847 9891 19848 9892 19848 9918 19848 9918 19849 9892 19849 9893 19849 10621 19850 10620 19850 9763 19850 9763 19851 10620 19851 9769 19851 9763 19852 9769 19852 9733 19852 9733 19853 9769 19853 9894 19853 9733 19854 9894 19854 9895 19854 9895 19855 9894 19855 9770 19855 9895 19856 9770 19856 9704 19856 9704 19857 9770 19857 9896 19857 9704 19858 9896 19858 9897 19858 9897 19859 9896 19859 9898 19859 9897 19860 9898 19860 10047 19860 10047 19861 9604 19861 9897 19861 9897 19862 9604 19862 9899 19862 9897 19863 9899 19863 9606 19863 9606 19864 9899 19864 9900 19864 9606 19865 9900 19865 9657 19865 9657 19866 9900 19866 9901 19866 9657 19867 9901 19867 9658 19867 9658 19868 9901 19868 9848 19868 9658 19869 9848 19869 9660 19869 9660 19870 9848 19870 9849 19870 9660 19871 9849 19871 9661 19871 9661 19872 9849 19872 9851 19872 9661 19873 9851 19873 9662 19873 9662 19874 9851 19874 9902 19874 9662 19875 9902 19875 9903 19875 9903 19876 9902 19876 9853 19876 9903 19877 9853 19877 9665 19877 9665 19878 9853 19878 9904 19878 9665 19879 9904 19879 9905 19879 9905 19880 9904 19880 9855 19880 9905 19881 9855 19881 9906 19881 9906 19882 9855 19882 9907 19882 9906 19883 9907 19883 9908 19883 9908 19884 9907 19884 9857 19884 9908 19885 9857 19885 9668 19885 9668 19886 9857 19886 9858 19886 9668 19887 9858 19887 9909 19887 9909 19888 9858 19888 9910 19888 9909 19889 9910 19889 9671 19889 9671 19890 9910 19890 9862 19890 9671 19891 9862 19891 9672 19891 9672 19892 9862 19892 9864 19892 9672 19893 9864 19893 9911 19893 9911 19894 9864 19894 9865 19894 9911 19895 9865 19895 9912 19895 9912 19896 9865 19896 9866 19896 9912 19897 9866 19897 9674 19897 9674 19898 9866 19898 9867 19898 9674 19899 9867 19899 9675 19899 9675 19900 9867 19900 9913 19900 9675 19901 9913 19901 9914 19901 9914 19902 9913 19902 9868 19902 9914 19903 9868 19903 9685 19903 9685 19904 9868 19904 9870 19904 9685 19905 9870 19905 9684 19905 9684 19906 9870 19906 9915 19906 9684 19907 9915 19907 9683 19907 9683 19908 9915 19908 9873 19908 9683 19909 9873 19909 9682 19909 9682 19910 9873 19910 9916 19910 9682 19911 9916 19911 9917 19911 9917 19912 9916 19912 9918 19912 9917 19913 9918 19913 9680 19913 9680 19914 9918 19914 9893 19914 9680 19915 9893 19915 9679 19915 9679 19916 9893 19916 9919 19916 9679 19917 9919 19917 9678 19917 9678 19918 9919 19918 9793 19918 9678 19919 9793 19919 9920 19919 9920 19920 9793 19920 9795 19920 9920 19921 9795 19921 9921 19921 9921 19922 9795 19922 9829 19922 9921 19923 9829 19923 10090 19923 10090 19924 9829 19924 9828 19924 9922 19925 9932 19925 9933 19925 10002 19926 9986 19926 9987 19926 10050 19927 10045 19927 10044 19927 9974 19928 9923 19928 9970 19928 9960 19929 10635 19929 9959 19929 9483 19930 9561 19930 10026 19930 9924 19931 9528 19931 10024 19931 9926 19932 8127 19932 9952 19932 9952 19933 8127 19933 9951 19933 9925 19934 10029 19934 9926 19934 9927 19935 10034 19935 10008 19935 9928 19936 9929 19936 10025 19936 9561 19937 9559 19937 10026 19937 10026 19938 9559 19938 9930 19938 10026 19939 9930 19939 10024 19939 10024 19940 9930 19940 9559 19940 10024 19941 9559 19941 9924 19941 9933 19942 9931 19942 10010 19942 9932 19943 9526 19943 9933 19943 9933 19944 9526 19944 9571 19944 9933 19945 9571 19945 9931 19945 10063 19946 9522 19946 9922 19946 9922 19947 9522 19947 9525 19947 9922 19948 9525 19948 9932 19948 9932 19949 9525 19949 9558 19949 9932 19950 9558 19950 9526 19950 10015 19951 9521 19951 9934 19951 10015 19952 10016 19952 9518 19952 9518 19953 10016 19953 10014 19953 9518 19954 10014 19954 9519 19954 10054 19955 10647 19955 9485 19955 9935 19956 9982 19956 10648 19956 10648 19957 9982 19957 10649 19957 10641 19958 10646 19958 9988 19958 9988 19959 10646 19959 9936 19959 9988 19960 9936 19960 9989 19960 9938 19961 9629 19961 9973 19961 9631 19962 9937 19962 9940 19962 9940 19963 9937 19963 9938 19963 9938 19964 9973 19964 9940 19964 9940 19965 9973 19965 9939 19965 9940 19966 9939 19966 9977 19966 9941 19967 9942 19967 9631 19967 9946 19968 9943 19968 9979 19968 9979 19969 9943 19969 9944 19969 9942 19970 9941 19970 9765 19970 9765 19971 9941 19971 9945 19971 9765 19972 9945 19972 9944 19972 9944 19973 9945 19973 9978 19973 9944 19974 9978 19974 9979 19974 9947 19975 9772 19975 9946 19975 9772 19976 9947 19976 9773 19976 9773 19977 9947 19977 10046 19977 9773 19978 10046 19978 9898 19978 9803 19979 9949 19979 9948 19979 9948 19980 9949 19980 9875 19980 9948 19981 9875 19981 9950 19981 9950 19982 9875 19982 9956 19982 9951 19983 10031 19983 9952 19983 9952 19984 10031 19984 9953 19984 9952 19985 9953 19985 10030 19985 9954 19986 9948 19986 9955 19986 9955 19987 9948 19987 9950 19987 9955 19988 9950 19988 10049 19988 10049 19989 9950 19989 9956 19989 10049 19990 9956 19990 9604 19990 10077 19991 10075 19991 9957 19991 9957 19992 10075 19992 9958 19992 9957 19993 9958 19993 9998 19993 9998 19994 9958 19994 9966 19994 9998 19995 9966 19995 9997 19995 9997 19996 9966 19996 9964 19996 9997 19997 9964 19997 9959 19997 9959 19998 9964 19998 9963 19998 9959 19999 9963 19999 9960 19999 9960 20000 9963 20000 9961 20000 9960 20001 9961 20001 9962 20001 10065 20002 9962 20002 10068 20002 10068 20003 9962 20003 9961 20003 10068 20004 9961 20004 10069 20004 10069 20005 9961 20005 9963 20005 10069 20006 9963 20006 10072 20006 10072 20007 9963 20007 9964 20007 10072 20008 9964 20008 9965 20008 9965 20009 9964 20009 9966 20009 9965 20010 9966 20010 9967 20010 9967 20011 9966 20011 9958 20011 9967 20012 9958 20012 9968 20012 9968 20013 9958 20013 10075 20013 9969 20014 10070 20014 10071 20014 10074 20015 10048 20015 10073 20015 10073 20016 10048 20016 10046 20016 10073 20017 10046 20017 10071 20017 10071 20018 10046 20018 9947 20018 10071 20019 9947 20019 9969 20019 9946 20020 9979 20020 9947 20020 9947 20021 9979 20021 9981 20021 9947 20022 9981 20022 9969 20022 9969 20023 9981 20023 10067 20023 9969 20024 10067 20024 10070 20024 9923 20025 10632 20025 9970 20025 9970 20026 10632 20026 10064 20026 9970 20027 10064 20027 9971 20027 9971 20028 10064 20028 10066 20028 9971 20029 10066 20029 9980 20029 9980 20030 10066 20030 9972 20030 9973 20031 10634 20031 9939 20031 9939 20032 10634 20032 9974 20032 9939 20033 9974 20033 9977 20033 9977 20034 9974 20034 9970 20034 9977 20035 9970 20035 9975 20035 9975 20036 9970 20036 9971 20036 9975 20037 9971 20037 9976 20037 9976 20038 9971 20038 9980 20038 9631 20039 9940 20039 9941 20039 9941 20040 9940 20040 9977 20040 9941 20041 9977 20041 9945 20041 9945 20042 9977 20042 9975 20042 9945 20043 9975 20043 9978 20043 9978 20044 9975 20044 9976 20044 9978 20045 9976 20045 9979 20045 9979 20046 9976 20046 9980 20046 9979 20047 9980 20047 9981 20047 9981 20048 9980 20048 9972 20048 9981 20049 9972 20049 10067 20049 9999 20050 9983 20050 10081 20050 10649 20051 9982 20051 9991 20051 9991 20052 9982 20052 10081 20052 9991 20053 10081 20053 9990 20053 9990 20054 10081 20054 9983 20054 9990 20055 9983 20055 9984 20055 10003 20056 10642 20056 10002 20056 10002 20057 10642 20057 9985 20057 10002 20058 9985 20058 9986 20058 9986 20059 9985 20059 10641 20059 9986 20060 10641 20060 9987 20060 9987 20061 10641 20061 9988 20061 9987 20062 9988 20062 9984 20062 9984 20063 9988 20063 9989 20063 9984 20064 9989 20064 9990 20064 9990 20065 9989 20065 10644 20065 9990 20066 10644 20066 9991 20066 10000 20067 9992 20067 10001 20067 10001 20068 9992 20068 9993 20068 10001 20069 9993 20069 9994 20069 10004 20070 9994 20070 9995 20070 9995 20071 9994 20071 9993 20071 9995 20072 9993 20072 9996 20072 9996 20073 9993 20073 9992 20073 10635 20074 10006 20074 9959 20074 9959 20075 10006 20075 10005 20075 9959 20076 10005 20076 9997 20076 9997 20077 10005 20077 10004 20077 9997 20078 10004 20078 9998 20078 9998 20079 10004 20079 9995 20079 9998 20080 9995 20080 9957 20080 9957 20081 9995 20081 9996 20081 9957 20082 9996 20082 10077 20082 10077 20083 9996 20083 9992 20083 10077 20084 9992 20084 10078 20084 10078 20085 9992 20085 10000 20085 10078 20086 10000 20086 10079 20086 9999 20087 10079 20087 9983 20087 9983 20088 10079 20088 10000 20088 9983 20089 10000 20089 9984 20089 9984 20090 10000 20090 10001 20090 9984 20091 10001 20091 9987 20091 9987 20092 10001 20092 9994 20092 9987 20093 9994 20093 10002 20093 10002 20094 9994 20094 10004 20094 10002 20095 10004 20095 10003 20095 10003 20096 10004 20096 10005 20096 10003 20097 10005 20097 10643 20097 10643 20098 10005 20098 10006 20098 10007 20099 9927 20099 10027 20099 10027 20100 9927 20100 10008 20100 10027 20101 10008 20101 10009 20101 9527 20102 10025 20102 10010 20102 10010 20103 10025 20103 9929 20103 10010 20104 9929 20104 9933 20104 9933 20105 9929 20105 9928 20105 9933 20106 9928 20106 9922 20106 9922 20107 9928 20107 10023 20107 9922 20108 10023 20108 10063 20108 10063 20109 10023 20109 10022 20109 10063 20110 10022 20110 10011 20110 10011 20111 10022 20111 10013 20111 10011 20112 10013 20112 10012 20112 10012 20113 10013 20113 10020 20113 10012 20114 10020 20114 10061 20114 10061 20115 10020 20115 10018 20115 10041 20116 10019 20116 10039 20116 10039 20117 10019 20117 10037 20117 10039 20118 10037 20118 10038 20118 9484 20119 9519 20119 10055 20119 10055 20120 9519 20120 10014 20120 10055 20121 10014 20121 10053 20121 10015 20122 9934 20122 10016 20122 10016 20123 9934 20123 10017 20123 10016 20124 10017 20124 10014 20124 10014 20125 10017 20125 10062 20125 10014 20126 10062 20126 10053 20126 10041 20127 10018 20127 10019 20127 10019 20128 10018 20128 10020 20128 10019 20129 10020 20129 10037 20129 10037 20130 10020 20130 10013 20130 10037 20131 10013 20131 10021 20131 10021 20132 10013 20132 10022 20132 10021 20133 10022 20133 10035 20133 10035 20134 10022 20134 10023 20134 10035 20135 10023 20135 10033 20135 10033 20136 10023 20136 9928 20136 10033 20137 9928 20137 10024 20137 10024 20138 9928 20138 10025 20138 10024 20139 10025 20139 10026 20139 10026 20140 10025 20140 9527 20140 10026 20141 9527 20141 9483 20141 10036 20142 10007 20142 10032 20142 10032 20143 10007 20143 10027 20143 10032 20144 10027 20144 10028 20144 10028 20145 10027 20145 10009 20145 10028 20146 10009 20146 10029 20146 10052 20147 10030 20147 9954 20147 9954 20148 10030 20148 9953 20148 9954 20149 9953 20149 9948 20149 9948 20150 9953 20150 10031 20150 9948 20151 10031 20151 9803 20151 10029 20152 9925 20152 10028 20152 10028 20153 9925 20153 10056 20153 10028 20154 10056 20154 10032 20154 10032 20155 10056 20155 10057 20155 10032 20156 10057 20156 10036 20156 10024 20157 10034 20157 10033 20157 10033 20158 10034 20158 9927 20158 10033 20159 9927 20159 10035 20159 10035 20160 9927 20160 10007 20160 10035 20161 10007 20161 10021 20161 10021 20162 10007 20162 10036 20162 10021 20163 10036 20163 10037 20163 10037 20164 10036 20164 10057 20164 10037 20165 10057 20165 10038 20165 10038 20166 10057 20166 10040 20166 10038 20167 10040 20167 10039 20167 10039 20168 10040 20168 10042 20168 10039 20169 10042 20169 10041 20169 10041 20170 10042 20170 10060 20170 10041 20171 10060 20171 10018 20171 10018 20172 10060 20172 10043 20172 10018 20173 10043 20173 10061 20173 10044 20174 10045 20174 10051 20174 10051 20175 10045 20175 10076 20175 10051 20176 10076 20176 10058 20176 9898 20177 10046 20177 10047 20177 10047 20178 10046 20178 10048 20178 10047 20179 10048 20179 9604 20179 9604 20180 10048 20180 10074 20180 9604 20181 10074 20181 10049 20181 10049 20182 10074 20182 10050 20182 10049 20183 10050 20183 9955 20183 9955 20184 10050 20184 10044 20184 9955 20185 10044 20185 9954 20185 9954 20186 10044 20186 10051 20186 9954 20187 10051 20187 10052 20187 10059 20188 10082 20188 10053 20188 10053 20189 10082 20189 10054 20189 10053 20190 10054 20190 10055 20190 10055 20191 10054 20191 9485 20191 10055 20192 9485 20192 9484 20192 9926 20193 9952 20193 9925 20193 9925 20194 9952 20194 10030 20194 9925 20195 10030 20195 10056 20195 10056 20196 10030 20196 10052 20196 10056 20197 10052 20197 10057 20197 10057 20198 10052 20198 10051 20198 10057 20199 10051 20199 10040 20199 10040 20200 10051 20200 10058 20200 10040 20201 10058 20201 10042 20201 10042 20202 10058 20202 10080 20202 10042 20203 10080 20203 10060 20203 10060 20204 10080 20204 10059 20204 10060 20205 10059 20205 10043 20205 10043 20206 10059 20206 10053 20206 10043 20207 10053 20207 10061 20207 10061 20208 10053 20208 10062 20208 10061 20209 10062 20209 10012 20209 10012 20210 10062 20210 10017 20210 10012 20211 10017 20211 10011 20211 10011 20212 10017 20212 9934 20212 10011 20213 9934 20213 10063 20213 10063 20214 9934 20214 9521 20214 10063 20215 9521 20215 9522 20215 10632 20216 10640 20216 10064 20216 10064 20217 10640 20217 10638 20217 10064 20218 10638 20218 10066 20218 10066 20219 10638 20219 10065 20219 10066 20220 10065 20220 9972 20220 9972 20221 10065 20221 10068 20221 9972 20222 10068 20222 10067 20222 10067 20223 10068 20223 10069 20223 10067 20224 10069 20224 10070 20224 10070 20225 10069 20225 10072 20225 10070 20226 10072 20226 10071 20226 10071 20227 10072 20227 9965 20227 10071 20228 9965 20228 10073 20228 10073 20229 9965 20229 9967 20229 10073 20230 9967 20230 10074 20230 10074 20231 9967 20231 9968 20231 10074 20232 9968 20232 10050 20232 10050 20233 9968 20233 10075 20233 10050 20234 10075 20234 10045 20234 10045 20235 10075 20235 10077 20235 10045 20236 10077 20236 10076 20236 10076 20237 10077 20237 10078 20237 10076 20238 10078 20238 10058 20238 10058 20239 10078 20239 10079 20239 10058 20240 10079 20240 10080 20240 10080 20241 10079 20241 9999 20241 10080 20242 9999 20242 10059 20242 10059 20243 9999 20243 10081 20243 10059 20244 10081 20244 10082 20244 10082 20245 10081 20245 9982 20245 10082 20246 9982 20246 10054 20246 10054 20247 9982 20247 9935 20247 10054 20248 9935 20248 10647 20248 10647 20249 9935 20249 10648 20249 10102 20250 9581 20250 10100 20250 10669 20251 10668 20251 10083 20251 8020 20252 10105 20252 10106 20252 9555 20253 10084 20253 8012 20253 8012 20254 10084 20254 10085 20254 8012 20255 10085 20255 10104 20255 10122 20256 8021 20256 10086 20256 9787 20257 9789 20257 8026 20257 8026 20258 10121 20258 9787 20258 9787 20259 10121 20259 10087 20259 9787 20260 10087 20260 10088 20260 10089 20261 10090 20261 10091 20261 10091 20262 10090 20262 9828 20262 10116 20263 10671 20263 10682 20263 10089 20264 10091 20264 9607 20264 9607 20265 10091 20265 10118 20265 9607 20266 10118 20266 10092 20266 10092 20267 10118 20267 10116 20267 10092 20268 10116 20268 10093 20268 10093 20269 10116 20269 10682 20269 10093 20270 10682 20270 10680 20270 10111 20271 10665 20271 10134 20271 10108 20272 10667 20272 10665 20272 9577 20273 10094 20273 10109 20273 10109 20274 10094 20274 10095 20274 10109 20275 10095 20275 10083 20275 10083 20276 10095 20276 10096 20276 10083 20277 10096 20277 10669 20277 9577 20278 10109 20278 10097 20278 10097 20279 10109 20279 10115 20279 10097 20280 10115 20280 9580 20280 10098 20281 9593 20281 10099 20281 10099 20282 9593 20282 10101 20282 10099 20283 10101 20283 10100 20283 10100 20284 10101 20284 9591 20284 10100 20285 9591 20285 10102 20285 10107 20286 10125 20286 10106 20286 10106 20287 10125 20287 10103 20287 10106 20288 10103 20288 8020 20288 8020 20289 10103 20289 10086 20289 10104 20290 10085 20290 10105 20290 10105 20291 10085 20291 9582 20291 10105 20292 9582 20292 10106 20292 10106 20293 9582 20293 9548 20293 10106 20294 9548 20294 10107 20294 10668 20295 10667 20295 10083 20295 10083 20296 10667 20296 10108 20296 10083 20297 10108 20297 10109 20297 10109 20298 10108 20298 10113 20298 10109 20299 10113 20299 10115 20299 10110 20300 10132 20300 10119 20300 10119 20301 10132 20301 10117 20301 10665 20302 10111 20302 10108 20302 10108 20303 10111 20303 10112 20303 10108 20304 10112 20304 10113 20304 10113 20305 10112 20305 10114 20305 10113 20306 10114 20306 10115 20306 10115 20307 10114 20307 10131 20307 10115 20308 10131 20308 9580 20308 10671 20309 10116 20309 10133 20309 10133 20310 10116 20310 10118 20310 10133 20311 10118 20311 10117 20311 10117 20312 10118 20312 10091 20312 10117 20313 10091 20313 10119 20313 10119 20314 10091 20314 9828 20314 10119 20315 9828 20315 10087 20315 10087 20316 9828 20316 10120 20316 10087 20317 10120 20317 10088 20317 8026 20318 8021 20318 10121 20318 10121 20319 8021 20319 10122 20319 10121 20320 10122 20320 10087 20320 10087 20321 10122 20321 10128 20321 10087 20322 10128 20322 10119 20322 10119 20323 10128 20323 10130 20323 10119 20324 10130 20324 10110 20324 10110 20325 10130 20325 10123 20325 10110 20326 10123 20326 10132 20326 10107 20327 10124 20327 10125 20327 10125 20328 10124 20328 10098 20328 10125 20329 10098 20329 10103 20329 10103 20330 10098 20330 10099 20330 10103 20331 10099 20331 10126 20331 10126 20332 10099 20332 10100 20332 10126 20333 10100 20333 10129 20333 10129 20334 10100 20334 9581 20334 10129 20335 9581 20335 10131 20335 10131 20336 9581 20336 10127 20336 10131 20337 10127 20337 9580 20337 10086 20338 10103 20338 10122 20338 10122 20339 10103 20339 10126 20339 10122 20340 10126 20340 10128 20340 10128 20341 10126 20341 10129 20341 10128 20342 10129 20342 10130 20342 10130 20343 10129 20343 10131 20343 10130 20344 10131 20344 10123 20344 10123 20345 10131 20345 10114 20345 10123 20346 10114 20346 10132 20346 10132 20347 10114 20347 10112 20347 10132 20348 10112 20348 10117 20348 10117 20349 10112 20349 10111 20349 10117 20350 10111 20350 10133 20350 10133 20351 10111 20351 10134 20351 10133 20352 10134 20352 10671 20352 10135 20353 8059 20353 10136 20353 10136 20354 8059 20354 8062 20354 10313 20355 11696 20355 10137 20355 11681 20356 10300 20356 10303 20356 10138 20357 10284 20357 10139 20357 11633 20358 11483 20358 11480 20358 10251 20359 10255 20359 10256 20359 10188 20360 7821 20360 10187 20360 7960 20361 10140 20361 11561 20361 11561 20362 10140 20362 10142 20362 11561 20363 10142 20363 10141 20363 10141 20364 10142 20364 7970 20364 10141 20365 7970 20365 11563 20365 11563 20366 7970 20366 10144 20366 11563 20367 10144 20367 10143 20367 10143 20368 10144 20368 10145 20368 10143 20369 10145 20369 11566 20369 11566 20370 10145 20370 7977 20370 11566 20371 7977 20371 10146 20371 10146 20372 7977 20372 11839 20372 10146 20373 11839 20373 10147 20373 10147 20374 11839 20374 11838 20374 10147 20375 11838 20375 11553 20375 11553 20376 11838 20376 11810 20376 11553 20377 11810 20377 11555 20377 11555 20378 11810 20378 7989 20378 11555 20379 7989 20379 10148 20379 10148 20380 7989 20380 7994 20380 10148 20381 7994 20381 11558 20381 11558 20382 7994 20382 1813 20382 11558 20383 1813 20383 10149 20383 10149 20384 1813 20384 7960 20384 10149 20385 7960 20385 11561 20385 10168 20386 10151 20386 10150 20386 10150 20387 10151 20387 10153 20387 10153 20388 10151 20388 10152 20388 10153 20389 10152 20389 10154 20389 10154 20390 10152 20390 7898 20390 10154 20391 7898 20391 11545 20391 11545 20392 7898 20392 10164 20392 11545 20393 10164 20393 11546 20393 10150 20394 11551 20394 10168 20394 10168 20395 11551 20395 10155 20395 10168 20396 10155 20396 10176 20396 10155 20397 10156 20397 10176 20397 10176 20398 10156 20398 10157 20398 10176 20399 10157 20399 7995 20399 10158 20400 7905 20400 10165 20400 10165 20401 7905 20401 7929 20401 10165 20402 7929 20402 11547 20402 10157 20403 10159 20403 7995 20403 7995 20404 10159 20404 11547 20404 7995 20405 11547 20405 7997 20405 7997 20406 11547 20406 7929 20406 7997 20407 7929 20407 10160 20407 10160 20408 7929 20408 10162 20408 10160 20409 10162 20409 10161 20409 10161 20410 10162 20410 10163 20410 10161 20411 10163 20411 1813 20411 1813 20412 10163 20412 7956 20412 1813 20413 7956 20413 7960 20413 10164 20414 7901 20414 11546 20414 11546 20415 7901 20415 7920 20415 11546 20416 7920 20416 10165 20416 10165 20417 7920 20417 7907 20417 10165 20418 7907 20418 10158 20418 10176 20419 7846 20419 10170 20419 10166 20420 10168 20420 10167 20420 10167 20421 10168 20421 10176 20421 10167 20422 10176 20422 10169 20422 10169 20423 10176 20423 10170 20423 11506 20424 10178 20424 10175 20424 11512 20425 11511 20425 10175 20425 7834 20426 10172 20426 10171 20426 10171 20427 10172 20427 10173 20427 10171 20428 10173 20428 10174 20428 11511 20429 11510 20429 10175 20429 10175 20430 11510 20430 11507 20430 10175 20431 11507 20431 11506 20431 7846 20432 10176 20432 7845 20432 7845 20433 10176 20433 10177 20433 7845 20434 10177 20434 7848 20434 7848 20435 10177 20435 10178 20435 7848 20436 10178 20436 10174 20436 10174 20437 10178 20437 11506 20437 10174 20438 11506 20438 10171 20438 7834 20439 10171 20439 10179 20439 10179 20440 10171 20440 10180 20440 10179 20441 10180 20441 7830 20441 7830 20442 10180 20442 10181 20442 10181 20443 10180 20443 10182 20443 10181 20444 10182 20444 7824 20444 7824 20445 10182 20445 10183 20445 7824 20446 10183 20446 7823 20446 7823 20447 10183 20447 11517 20447 7823 20448 11517 20448 10185 20448 10185 20449 11517 20449 10184 20449 10185 20450 10184 20450 10186 20450 10186 20451 10184 20451 11515 20451 10186 20452 11515 20452 10187 20452 11515 20453 11512 20453 10187 20453 10187 20454 11512 20454 10175 20454 10187 20455 10175 20455 10188 20455 10188 20456 10175 20456 7781 20456 10192 20457 10189 20457 10175 20457 10175 20458 10189 20458 7792 20458 10175 20459 7792 20459 7781 20459 10202 20460 11496 20460 10191 20460 7765 20461 7763 20461 10190 20461 10190 20462 7763 20462 11495 20462 11496 20463 11495 20463 10191 20463 10191 20464 11495 20464 7763 20464 10191 20465 7763 20465 8002 20465 8002 20466 7763 20466 7782 20466 8002 20467 7782 20467 10192 20467 10192 20468 7782 20468 10193 20468 10192 20469 10193 20469 10189 20469 10194 20470 10195 20470 11500 20470 11500 20471 10195 20471 7759 20471 11500 20472 7759 20472 10196 20472 10196 20473 7759 20473 10198 20473 10196 20474 10198 20474 10197 20474 10197 20475 10198 20475 10200 20475 10197 20476 10200 20476 10199 20476 10199 20477 10200 20477 10207 20477 10199 20478 10207 20478 11491 20478 10191 20479 10201 20479 10202 20479 10202 20480 10201 20480 7728 20480 10202 20481 7728 20481 10203 20481 10203 20482 7728 20482 10204 20482 10203 20483 10204 20483 10194 20483 10194 20484 10204 20484 7757 20484 10194 20485 7757 20485 10195 20485 7762 20486 10205 20486 11493 20486 11493 20487 10205 20487 7768 20487 11493 20488 7768 20488 10190 20488 10190 20489 7768 20489 10206 20489 10190 20490 10206 20490 7765 20490 11491 20491 10207 20491 11493 20491 11493 20492 10207 20492 7760 20492 11493 20493 7760 20493 7762 20493 10208 20494 10212 20494 10191 20494 10191 20495 10212 20495 7727 20495 10191 20496 7727 20496 10201 20496 10209 20497 8008 20497 11568 20497 11568 20498 8008 20498 10210 20498 11568 20499 10210 20499 11569 20499 11569 20500 10210 20500 7701 20500 10209 20501 7708 20501 8008 20501 8008 20502 7708 20502 7715 20502 8008 20503 7715 20503 8009 20503 8009 20504 7715 20504 10211 20504 8009 20505 10211 20505 10208 20505 10208 20506 10211 20506 7721 20506 10208 20507 7721 20507 10212 20507 10812 20508 10337 20508 8023 20508 10213 20509 10214 20509 10337 20509 10337 20510 10214 20510 10215 20510 10337 20511 10215 20511 10210 20511 10210 20512 10215 20512 7694 20512 10210 20513 7694 20513 7701 20513 11579 20514 10334 20514 10216 20514 10216 20515 10334 20515 10340 20515 10216 20516 10340 20516 11580 20516 10217 20517 10774 20517 11582 20517 11582 20518 10774 20518 10776 20518 11582 20519 10776 20519 10778 20519 11582 20520 11581 20520 10217 20520 10217 20521 11581 20521 11580 20521 10217 20522 11580 20522 10218 20522 10218 20523 11580 20523 10340 20523 10218 20524 10340 20524 10329 20524 10778 20525 10780 20525 10219 20525 10219 20526 10780 20526 10220 20526 10219 20527 10220 20527 8050 20527 10786 20528 10328 20528 10221 20528 10221 20529 10328 20529 10222 20529 10221 20530 10222 20530 10784 20530 10784 20531 10222 20531 8050 20531 10784 20532 8050 20532 10223 20532 10223 20533 8050 20533 10220 20533 10324 20534 10224 20534 10225 20534 10225 20535 10224 20535 7618 20535 10225 20536 7618 20536 7617 20536 10778 20537 10219 20537 11582 20537 11582 20538 10219 20538 10225 20538 11582 20539 10225 20539 7686 20539 7686 20540 10225 20540 7617 20540 7686 20541 7617 20541 7683 20541 10226 20542 7626 20542 10324 20542 10324 20543 7626 20543 7624 20543 10324 20544 7624 20544 10224 20544 10791 20545 10228 20545 10232 20545 7657 20546 7655 20546 10789 20546 10323 20547 10801 20547 10226 20547 10226 20548 10801 20548 10787 20548 10226 20549 10787 20549 7655 20549 7655 20550 10787 20550 10227 20550 7655 20551 10227 20551 10789 20551 10232 20552 10228 20552 10229 20552 10790 20553 10791 20553 10244 20553 10228 20554 10795 20554 10229 20554 10229 20555 10795 20555 10796 20555 10229 20556 10796 20556 10230 20556 10230 20557 10796 20557 10797 20557 10230 20558 10797 20558 8062 20558 8062 20559 10797 20559 10231 20559 8062 20560 10231 20560 10136 20560 10791 20561 10232 20561 10244 20561 10244 20562 10232 20562 8065 20562 10244 20563 8065 20563 8066 20563 10321 20564 10234 20564 10233 20564 10233 20565 10234 20565 10235 20565 10233 20566 10235 20566 8128 20566 8128 20567 10235 20567 10236 20567 8128 20568 10236 20568 10247 20568 10239 20569 10245 20569 10237 20569 10237 20570 10238 20570 10239 20570 10239 20571 10238 20571 10240 20571 10239 20572 10240 20572 10242 20572 10242 20573 10240 20573 10241 20573 10242 20574 10241 20574 8125 20574 10789 20575 10790 20575 7657 20575 7657 20576 10790 20576 10244 20576 7657 20577 10244 20577 10243 20577 10243 20578 10244 20578 8066 20578 10243 20579 8066 20579 7666 20579 7666 20580 8066 20580 8068 20580 7666 20581 8068 20581 10245 20581 10245 20582 8068 20582 8069 20582 10245 20583 8069 20583 10237 20583 10802 20584 10804 20584 10249 20584 8125 20585 8128 20585 10242 20585 10242 20586 8128 20586 10247 20586 10242 20587 10247 20587 10246 20587 10246 20588 10247 20588 10809 20588 10246 20589 10809 20589 7675 20589 7675 20590 10809 20590 10811 20590 7675 20591 10811 20591 11616 20591 11616 20592 10811 20592 10248 20592 11616 20593 10248 20593 11606 20593 11606 20594 10248 20594 10802 20594 11606 20595 10802 20595 7605 20595 7605 20596 10802 20596 10249 20596 10805 20597 10806 20597 10321 20597 10321 20598 10806 20598 10807 20598 10321 20599 10807 20599 10234 20599 10804 20600 10805 20600 10249 20600 10249 20601 10805 20601 10321 20601 10249 20602 10321 20602 7607 20602 7607 20603 10321 20603 10250 20603 10255 20604 10251 20604 10253 20604 7588 20605 10271 20605 10252 20605 10252 20606 11479 20606 10259 20606 10252 20607 10259 20607 10258 20607 10253 20608 10254 20608 10255 20608 10255 20609 10254 20609 8126 20609 10255 20610 8126 20610 10256 20610 10256 20611 8126 20611 8135 20611 10256 20612 8135 20612 7593 20612 7593 20613 8135 20613 10257 20613 7593 20614 10257 20614 10258 20614 10259 20615 10260 20615 10258 20615 10258 20616 10260 20616 10261 20616 10258 20617 10261 20617 7593 20617 7593 20618 10261 20618 11487 20618 7593 20619 11487 20619 10262 20619 11483 20620 11633 20620 10263 20620 10263 20621 11633 20621 10265 20621 10263 20622 10265 20622 10264 20622 10264 20623 10265 20623 11635 20623 10264 20624 11635 20624 10266 20624 10266 20625 11635 20625 10267 20625 10266 20626 10267 20626 10268 20626 10268 20627 10267 20627 11639 20627 10268 20628 11639 20628 10269 20628 10269 20629 11639 20629 11640 20629 10269 20630 11640 20630 11487 20630 11487 20631 11640 20631 10270 20631 11487 20632 10270 20632 10262 20632 10252 20633 10271 20633 11479 20633 11479 20634 10271 20634 10272 20634 11479 20635 10272 20635 11480 20635 11480 20636 10272 20636 10273 20636 11480 20637 10273 20637 11633 20637 10277 20638 10274 20638 8145 20638 8145 20639 10274 20639 7580 20639 8145 20640 7580 20640 10252 20640 10252 20641 7580 20641 10275 20641 10252 20642 10275 20642 7588 20642 10276 20643 11477 20643 10277 20643 10277 20644 11477 20644 11476 20644 10277 20645 11476 20645 10281 20645 10279 20646 7568 20646 10281 20646 10281 20647 7568 20647 7562 20647 10281 20648 7562 20648 10277 20648 10277 20649 7562 20649 10278 20649 10277 20650 10278 20650 10274 20650 10279 20651 10281 20651 10280 20651 10280 20652 10281 20652 11474 20652 10280 20653 11474 20653 11662 20653 11662 20654 11474 20654 10282 20654 11662 20655 10282 20655 10138 20655 10138 20656 10282 20656 10283 20656 10138 20657 10283 20657 10284 20657 10283 20658 11472 20658 10284 20658 10284 20659 11472 20659 10285 20659 10284 20660 10285 20660 10287 20660 10287 20661 10285 20661 10286 20661 10287 20662 10286 20662 11657 20662 11657 20663 10286 20663 11470 20663 11657 20664 11470 20664 10288 20664 10288 20665 11470 20665 10289 20665 10288 20666 10289 20666 10276 20666 10276 20667 10289 20667 11478 20667 10276 20668 11478 20668 11477 20668 7542 20669 7551 20669 10276 20669 7551 20670 10290 20670 10276 20670 10276 20671 10290 20671 10291 20671 10276 20672 10291 20672 10288 20672 10288 20673 10291 20673 7545 20673 10288 20674 7545 20674 11657 20674 7542 20675 10276 20675 10292 20675 10292 20676 10276 20676 8144 20676 10292 20677 8144 20677 10293 20677 11529 20678 8149 20678 10294 20678 10294 20679 8149 20679 8153 20679 10294 20680 8153 20680 11518 20680 8144 20681 8149 20681 10293 20681 10293 20682 8149 20682 11529 20682 10293 20683 11529 20683 7528 20683 7528 20684 11529 20684 11527 20684 7525 20685 7531 20685 11527 20685 11527 20686 7531 20686 7523 20686 11527 20687 7523 20687 7528 20687 7525 20688 11527 20688 7524 20688 7524 20689 11527 20689 11526 20689 7524 20690 11526 20690 11683 20690 11683 20691 11526 20691 11525 20691 11683 20692 11525 20692 10296 20692 10296 20693 11525 20693 10295 20693 10296 20694 10295 20694 10297 20694 10297 20695 10295 20695 11522 20695 10297 20696 11522 20696 10298 20696 10298 20697 11522 20697 11520 20697 10298 20698 11520 20698 11681 20698 11681 20699 11520 20699 10299 20699 11681 20700 10299 20700 10300 20700 10300 20701 10299 20701 10301 20701 10300 20702 10301 20702 8153 20702 8153 20703 10301 20703 10302 20703 8153 20704 10302 20704 11518 20704 7510 20705 7513 20705 8153 20705 8153 20706 7513 20706 10300 20706 10300 20707 7513 20707 7512 20707 10300 20708 7512 20708 10303 20708 8152 20709 10304 20709 8153 20709 8153 20710 10304 20710 7515 20710 8153 20711 7515 20711 7510 20711 7477 20712 10306 20712 7479 20712 7479 20713 10306 20713 10311 20713 10307 20714 10308 20714 10305 20714 10305 20715 10308 20715 10306 20715 10305 20716 10306 20716 7475 20716 7475 20717 10306 20717 7477 20717 10307 20718 7492 20718 10308 20718 10308 20719 7492 20719 7501 20719 10308 20720 7501 20720 8150 20720 8150 20721 7501 20721 7498 20721 8150 20722 7498 20722 8152 20722 8152 20723 7498 20723 7509 20723 8152 20724 7509 20724 10304 20724 11532 20725 10309 20725 7467 20725 11532 20726 11530 20726 10309 20726 10309 20727 11530 20727 11542 20727 10309 20728 11542 20728 10306 20728 11542 20729 10310 20729 10306 20729 10306 20730 10310 20730 11541 20730 10306 20731 11541 20731 10311 20731 10311 20732 11541 20732 11540 20732 10311 20733 11540 20733 11700 20733 11700 20734 11540 20734 10312 20734 11700 20735 10312 20735 11699 20735 11699 20736 10312 20736 11538 20736 11699 20737 11538 20737 10313 20737 10313 20738 11538 20738 10314 20738 10313 20739 10314 20739 11696 20739 11696 20740 10314 20740 10315 20740 11696 20741 10315 20741 10316 20741 10316 20742 10315 20742 10317 20742 10316 20743 10317 20743 10318 20743 10318 20744 10317 20744 10320 20744 10318 20745 10320 20745 10319 20745 10319 20746 10320 20746 11532 20746 10319 20747 11532 20747 7468 20747 7468 20748 11532 20748 7467 20748 8128 20749 8133 20749 10233 20749 10233 20750 8133 20750 8131 20750 10233 20751 8131 20751 10321 20751 10321 20752 8131 20752 10253 20752 10321 20753 10253 20753 10250 20753 10250 20754 10253 20754 10251 20754 10135 20755 10136 20755 8060 20755 8060 20756 10136 20756 10322 20756 8060 20757 10322 20757 8061 20757 8057 20758 8055 20758 10322 20758 10322 20759 8055 20759 8087 20759 10322 20760 8087 20760 8061 20760 10231 20761 10323 20761 10136 20761 10136 20762 10323 20762 10226 20762 10136 20763 10226 20763 10322 20763 10322 20764 10226 20764 10324 20764 10322 20765 10324 20765 8057 20765 8057 20766 10324 20766 10225 20766 8050 20767 10325 20767 10219 20767 10219 20768 10325 20768 8052 20768 10219 20769 8052 20769 10225 20769 10225 20770 8052 20770 10326 20770 10225 20771 10326 20771 8057 20771 8039 20772 10340 20772 8038 20772 8038 20773 10340 20773 10332 20773 8038 20774 10332 20774 10327 20774 10786 20775 10329 20775 10328 20775 10328 20776 10329 20776 10340 20776 10328 20777 10340 20777 8040 20777 8040 20778 10340 20778 8039 20778 10342 20779 8018 20779 10332 20779 10332 20780 8018 20780 8033 20780 10332 20781 8033 20781 8035 20781 8035 20782 10330 20782 10332 20782 10332 20783 10330 20783 10331 20783 10332 20784 10331 20784 10327 20784 10338 20785 10340 20785 10333 20785 10333 20786 10340 20786 10334 20786 10333 20787 10334 20787 10817 20787 10817 20788 10334 20788 11579 20788 10817 20789 11579 20789 10335 20789 10335 20790 11579 20790 10213 20790 10335 20791 10213 20791 10336 20791 10336 20792 10213 20792 10337 20792 10336 20793 10337 20793 10814 20793 10814 20794 10337 20794 10812 20794 10338 20795 10339 20795 10340 20795 10340 20796 10339 20796 10821 20796 10340 20797 10821 20797 10332 20797 10332 20798 10821 20798 10341 20798 10332 20799 10341 20799 10342 20799 10342 20800 10341 20800 10343 20800 10342 20801 10343 20801 8023 20801 8023 20802 10343 20802 10344 20802 8023 20803 10344 20803 10812 20803 7710 20804 8671 20804 10345 20804 7716 20805 7710 20805 10351 20805 10351 20806 7710 20806 10345 20806 10351 20807 10345 20807 10346 20807 10346 20808 10345 20808 10347 20808 10346 20809 10347 20809 10350 20809 10347 20810 8670 20810 10350 20810 10350 20811 8670 20811 11572 20811 10350 20812 11572 20812 10348 20812 10348 20813 11572 20813 10352 20813 10452 20814 7717 20814 7716 20814 10370 20815 10349 20815 10452 20815 10350 20816 10348 20816 10369 20816 10452 20817 7716 20817 10370 20817 10370 20818 7716 20818 10351 20818 10370 20819 10351 20819 10369 20819 10369 20820 10351 20820 10346 20820 10369 20821 10346 20821 10350 20821 10348 20822 10352 20822 10369 20822 10369 20823 10352 20823 10353 20823 10369 20824 10353 20824 8198 20824 10713 20825 10436 20825 10385 20825 10354 20826 10355 20826 10692 20826 10692 20827 10355 20827 10360 20827 10356 20828 10357 20828 6352 20828 10358 20829 10390 20829 8611 20829 8611 20830 8610 20830 10358 20830 10358 20831 8610 20831 8609 20831 10358 20832 8609 20832 10359 20832 10375 20833 11574 20833 10376 20833 10376 20834 11574 20834 10695 20834 10376 20835 10695 20835 10360 20835 10360 20836 10695 20836 10693 20836 10360 20837 10693 20837 10692 20837 10361 20838 6352 20838 10362 20838 10362 20839 6352 20839 10396 20839 10362 20840 10396 20840 10721 20840 10721 20841 10396 20841 10397 20841 11779 20842 10363 20842 10364 20842 10364 20843 10379 20843 6349 20843 6349 20844 10379 20844 10365 20844 6349 20845 10365 20845 10366 20845 6367 20846 6366 20846 10367 20846 10367 20847 6366 20847 10368 20847 10697 20848 10696 20848 10436 20848 10369 20849 10376 20849 10370 20849 10370 20850 10376 20850 10349 20850 10729 20851 10393 20851 10371 20851 10371 20852 10393 20852 10372 20852 10371 20853 10372 20853 10398 20853 8668 20854 8667 20854 10373 20854 10713 20855 10385 20855 10715 20855 10369 20856 8198 20856 10376 20856 10376 20857 8198 20857 10374 20857 10376 20858 10374 20858 10375 20858 6352 20859 10357 20859 10376 20859 10376 20860 10357 20860 10377 20860 10376 20861 10377 20861 10349 20861 10349 20862 10377 20862 10403 20862 10349 20863 10403 20863 10454 20863 10364 20864 10363 20864 10379 20864 10379 20865 10363 20865 10378 20865 10379 20866 10378 20866 10380 20866 8646 20867 10396 20867 11844 20867 11844 20868 10396 20868 10358 20868 10381 20869 10388 20869 10382 20869 10382 20870 10388 20870 10717 20870 8631 20871 10396 20871 10383 20871 10383 20872 10396 20872 6349 20872 10414 20873 8623 20873 8627 20873 8627 20874 8623 20874 8621 20874 8627 20875 8621 20875 8628 20875 8628 20876 8621 20876 10384 20876 8628 20877 10384 20877 10409 20877 10436 20878 10696 20878 10385 20878 10385 20879 10696 20879 8652 20879 10385 20880 8652 20880 6359 20880 6359 20881 8652 20881 8654 20881 6359 20882 8654 20882 6360 20882 6360 20883 8654 20883 6373 20883 6360 20884 6373 20884 10364 20884 10364 20885 6373 20885 10386 20885 10364 20886 10386 20886 11781 20886 10368 20887 6365 20887 10367 20887 10367 20888 6365 20888 8601 20888 10367 20889 8601 20889 10387 20889 10388 20890 8188 20890 10717 20890 10717 20891 8188 20891 10613 20891 10717 20892 10613 20892 10361 20892 10361 20893 10613 20893 10389 20893 10361 20894 10389 20894 6352 20894 6352 20895 10389 20895 10615 20895 6352 20896 10615 20896 10356 20896 10390 20897 10358 20897 8612 20897 8612 20898 10358 20898 10396 20898 8612 20899 10396 20899 8619 20899 11781 20900 10391 20900 10364 20900 10364 20901 10391 20901 10392 20901 10364 20902 10392 20902 11779 20902 8191 20903 8190 20903 10403 20903 10403 20904 8190 20904 8189 20904 10403 20905 8189 20905 10454 20905 10729 20906 8221 20906 10393 20906 10393 20907 8221 20907 8222 20907 10393 20908 8222 20908 8227 20908 8647 20909 10394 20909 8646 20909 8646 20910 10394 20910 10395 20910 8646 20911 10395 20911 10396 20911 10396 20912 10395 20912 10398 20912 10396 20913 10398 20913 10397 20913 10397 20914 10398 20914 10372 20914 10381 20915 10610 20915 10388 20915 10388 20916 10610 20916 10609 20916 10388 20917 10609 20917 10399 20917 10399 20918 10609 20918 10608 20918 10399 20919 10608 20919 10611 20919 8182 20920 8183 20920 8185 20920 10601 20921 10606 20921 10408 20921 10387 20922 8605 20922 10367 20922 10367 20923 8605 20923 10400 20923 10367 20924 10400 20924 8607 20924 8607 20925 10400 20925 10401 20925 8607 20926 10401 20926 8602 20926 8191 20927 10403 20927 10402 20927 10402 20928 10403 20928 10404 20928 10402 20929 10404 20929 8194 20929 8647 20930 8648 20930 10394 20930 10394 20931 8648 20931 10405 20931 10394 20932 10405 20932 10726 20932 10726 20933 10405 20933 10406 20933 10388 20934 8181 20934 8188 20934 8188 20935 8181 20935 8182 20935 8188 20936 8182 20936 8187 20936 8187 20937 8182 20937 8185 20937 10366 20938 6367 20938 6349 20938 6349 20939 6367 20939 10367 20939 6349 20940 10367 20940 10383 20940 10383 20941 10367 20941 10598 20941 10383 20942 10598 20942 10407 20942 10407 20943 10598 20943 10601 20943 10407 20944 10601 20944 10607 20944 10607 20945 10601 20945 10408 20945 8631 20946 8630 20946 10396 20946 10396 20947 8630 20947 10409 20947 10396 20948 10409 20948 8619 20948 8619 20949 10409 20949 10384 20949 8250 20950 10413 20950 8246 20950 8199 20951 8206 20951 10410 20951 10411 20952 8625 20952 8211 20952 8211 20953 8213 20953 10411 20953 10411 20954 8213 20954 10412 20954 10411 20955 10412 20955 6361 20955 6361 20956 10412 20956 8212 20956 6361 20957 8212 20957 8214 20957 10413 20958 8252 20958 8246 20958 8246 20959 8252 20959 10414 20959 8246 20960 10414 20960 10411 20960 10411 20961 10414 20961 8627 20961 10411 20962 8627 20962 8625 20962 6376 20963 6377 20963 6375 20963 6375 20964 6377 20964 10415 20964 6375 20965 10415 20965 10416 20965 10416 20966 10415 20966 10379 20966 10416 20967 10379 20967 11774 20967 11774 20968 10379 20968 10380 20968 10425 20969 10418 20969 10417 20969 10417 20970 10418 20970 10704 20970 10417 20971 10704 20971 10690 20971 10690 20972 10704 20972 10701 20972 10690 20973 10701 20973 10354 20973 10354 20974 10701 20974 10700 20974 10354 20975 10700 20975 10355 20975 10355 20976 10700 20976 10419 20976 10355 20977 10419 20977 6354 20977 6354 20978 10419 20978 10715 20978 6354 20979 10715 20979 6356 20979 6356 20980 10715 20980 10385 20980 8223 20981 10420 20981 8228 20981 8228 20982 10420 20982 10421 20982 8228 20983 10421 20983 8227 20983 8227 20984 10421 20984 10422 20984 8227 20985 10422 20985 10393 20985 10393 20986 10422 20986 10568 20986 10393 20987 10568 20987 8208 20987 8208 20988 10568 20988 8199 20988 8208 20989 8199 20989 10423 20989 10423 20990 8199 20990 10410 20990 10726 20991 10446 20991 8229 20991 10439 20992 8679 20992 10445 20992 10445 20993 8679 20993 10424 20993 8250 20994 8246 20994 8249 20994 8249 20995 8246 20995 8247 20995 8249 20996 8247 20996 8248 20996 10417 20997 8668 20997 10425 20997 10425 20998 8668 20998 10373 20998 10425 20999 10373 20999 10427 20999 10427 21000 10373 21000 10426 21000 10427 21001 10426 21001 10707 21001 10707 21002 10426 21002 10428 21002 10707 21003 10428 21003 10429 21003 10429 21004 10428 21004 10430 21004 10429 21005 10430 21005 10432 21005 10432 21006 10430 21006 10431 21006 10432 21007 10431 21007 10710 21007 10710 21008 10431 21008 10433 21008 10710 21009 10433 21009 10434 21009 10434 21010 10433 21010 8660 21010 10434 21011 8660 21011 10435 21011 10435 21012 8660 21012 8656 21012 10435 21013 8656 21013 10436 21013 10436 21014 8656 21014 10437 21014 10436 21015 10437 21015 10697 21015 8619 21016 8618 21016 8612 21016 8612 21017 8618 21017 10438 21017 8612 21018 10438 21018 10445 21018 10445 21019 10438 21019 8616 21019 10445 21020 8616 21020 10439 21020 10439 21021 8616 21021 8680 21021 8598 21022 8596 21022 8600 21022 8600 21023 8596 21023 10440 21023 8600 21024 10440 21024 8599 21024 8231 21025 8229 21025 10441 21025 10441 21026 8229 21026 10442 21026 8231 21027 8233 21027 8229 21027 8229 21028 8233 21028 10725 21028 8229 21029 10725 21029 10726 21029 8197 21030 10443 21030 10444 21030 10444 21031 10443 21031 10445 21031 10444 21032 10445 21032 8686 21032 8686 21033 10445 21033 10424 21033 10446 21034 10726 21034 10447 21034 10447 21035 10726 21035 10406 21035 10447 21036 10406 21036 8600 21036 8600 21037 10406 21037 8594 21037 8600 21038 8594 21038 8598 21038 10448 21039 8242 21039 8239 21039 8239 21040 8242 21040 10449 21040 8239 21041 10449 21041 10450 21041 10450 21042 10449 21042 8680 21042 10450 21043 8680 21043 10451 21043 10451 21044 8680 21044 8616 21044 10452 21045 10453 21045 7717 21045 7717 21046 10453 21046 10455 21046 7717 21047 10455 21047 7726 21047 10454 21048 8189 21048 10456 21048 10452 21049 10349 21049 10453 21049 10453 21050 10349 21050 10454 21050 10453 21051 10454 21051 10455 21051 10455 21052 10454 21052 10456 21052 10455 21053 10456 21053 7726 21053 10464 21054 10457 21054 10920 21054 10920 21055 10457 21055 9099 21055 10920 21056 9099 21056 10922 21056 10922 21057 9099 21057 10923 21057 10923 21058 9099 21058 10458 21058 10923 21059 10458 21059 10924 21059 10924 21060 10458 21060 10753 21060 10924 21061 10753 21061 10459 21061 10459 21062 10753 21062 10756 21062 10459 21063 10756 21063 10460 21063 10460 21064 10756 21064 10751 21064 10460 21065 10751 21065 10461 21065 10461 21066 10751 21066 10760 21066 10461 21067 10760 21067 10462 21067 10462 21068 10760 21068 10761 21068 10462 21069 10761 21069 10927 21069 10927 21070 10761 21070 10463 21070 10927 21071 10463 21071 10467 21071 10464 21072 10468 21072 10457 21072 10457 21073 10468 21073 10466 21073 10457 21074 10466 21074 9005 21074 7131 21075 10465 21075 10468 21075 10468 21076 10465 21076 7135 21076 10468 21077 7135 21077 10466 21077 10463 21078 10758 21078 10467 21078 10467 21079 10758 21079 8563 21079 10467 21080 8563 21080 10468 21080 10468 21081 8563 21081 7129 21081 10468 21082 7129 21082 7131 21082 10469 21083 9210 21083 10474 21083 10470 21084 7270 21084 10471 21084 10471 21085 7270 21085 7269 21085 10486 21086 10472 21086 10473 21086 10472 21087 10469 21087 10473 21087 10473 21088 10469 21088 10474 21088 10473 21089 10474 21089 10475 21089 10475 21090 10474 21090 10935 21090 10474 21091 10471 21091 10935 21091 10935 21092 10471 21092 7269 21092 10935 21093 7269 21093 10936 21093 10936 21094 7269 21094 10476 21094 10936 21095 10476 21095 10477 21095 10477 21096 10476 21096 8549 21096 10477 21097 8549 21097 10478 21097 10478 21098 8549 21098 10479 21098 10478 21099 10479 21099 10940 21099 10940 21100 10479 21100 8559 21100 10940 21101 8559 21101 10480 21101 10480 21102 8559 21102 10481 21102 10480 21103 10481 21103 10930 21103 10930 21104 10481 21104 10482 21104 10930 21105 10482 21105 10931 21105 10483 21106 10484 21106 10471 21106 10471 21107 10484 21107 10485 21107 10471 21108 10485 21108 10470 21108 10482 21109 8554 21109 10931 21109 10931 21110 8554 21110 8552 21110 10931 21111 8552 21111 10932 21111 10932 21112 8552 21112 8551 21112 10932 21113 8551 21113 10934 21113 10934 21114 8551 21114 7243 21114 10934 21115 7243 21115 10473 21115 10473 21116 7243 21116 7244 21116 10473 21117 7244 21117 10486 21117 7079 21118 7080 21118 9041 21118 7079 21119 9041 21119 10951 21119 10487 21120 10488 21120 10951 21120 10951 21121 10488 21121 7078 21121 10951 21122 7078 21122 7079 21122 7021 21123 7027 21123 9041 21123 9041 21124 7027 21124 7022 21124 9041 21125 7022 21125 7023 21125 10489 21126 10942 21126 7023 21126 7023 21127 10942 21127 10490 21127 7023 21128 10490 21128 9041 21128 9041 21129 10490 21129 10953 21129 9041 21130 10953 21130 10951 21130 10949 21131 7075 21131 10951 21131 10951 21132 7075 21132 10491 21132 10951 21133 10491 21133 10487 21133 10489 21134 7025 21134 10942 21134 10942 21135 7025 21135 10492 21135 10942 21136 10492 21136 10493 21136 10493 21137 10492 21137 10494 21137 10493 21138 10494 21138 10944 21138 10944 21139 10494 21139 10743 21139 10944 21140 10743 21140 10495 21140 10495 21141 10743 21141 10741 21141 10495 21142 10741 21142 10496 21142 10496 21143 10741 21143 10739 21143 10496 21144 10739 21144 10497 21144 10497 21145 10739 21145 10498 21145 10497 21146 10498 21146 10946 21146 10946 21147 10498 21147 10747 21147 10946 21148 10747 21148 10947 21148 10947 21149 10747 21149 10499 21149 10947 21150 10499 21150 10949 21150 10949 21151 10499 21151 10746 21151 10949 21152 10746 21152 7075 21152 6941 21153 9032 21153 10500 21153 10500 21154 9032 21154 10501 21154 10518 21155 10502 21155 10503 21155 10503 21156 10502 21156 10983 21156 10504 21157 10521 21157 6936 21157 6936 21158 10505 21158 10504 21158 10504 21159 10505 21159 6941 21159 10504 21160 6941 21160 10506 21160 10506 21161 6941 21161 10500 21161 10506 21162 10500 21162 10984 21162 10500 21163 10507 21163 10984 21163 10984 21164 10507 21164 10509 21164 10984 21165 10509 21165 10508 21165 10508 21166 10509 21166 8503 21166 10508 21167 8503 21167 10510 21167 10510 21168 8503 21168 10511 21168 10510 21169 10511 21169 10513 21169 10513 21170 10511 21170 10512 21170 10513 21171 10512 21171 10986 21171 10986 21172 10512 21172 8513 21172 10986 21173 8513 21173 10515 21173 10515 21174 8513 21174 10514 21174 10515 21175 10514 21175 10516 21175 10516 21176 10514 21176 8505 21176 10516 21177 8505 21177 10518 21177 10518 21178 8505 21178 10517 21178 10518 21179 10517 21179 10502 21179 10502 21180 10519 21180 10983 21180 10983 21181 10519 21181 10520 21181 10983 21182 10520 21182 10504 21182 10504 21183 10520 21183 6934 21183 10504 21184 6934 21184 10521 21184 10539 21185 10527 21185 10987 21185 10540 21186 7202 21186 7203 21186 7199 21187 10523 21187 10522 21187 10522 21188 10523 21188 7207 21188 10522 21189 7207 21189 9121 21189 10524 21190 10525 21190 10540 21190 10540 21191 10525 21191 10526 21191 10540 21192 10526 21192 7202 21192 10539 21193 11704 21193 10527 21193 10527 21194 11704 21194 11701 21194 10527 21195 11701 21195 10989 21195 10989 21196 11701 21196 10528 21196 10989 21197 10528 21197 10529 21197 10529 21198 10528 21198 10530 21198 10529 21199 10530 21199 10531 21199 10531 21200 10530 21200 10766 21200 10531 21201 10766 21201 10532 21201 10532 21202 10766 21202 10533 21202 10532 21203 10533 21203 10534 21203 10534 21204 10533 21204 10535 21204 10534 21205 10535 21205 10992 21205 10992 21206 10535 21206 10763 21206 10992 21207 10763 21207 10536 21207 10536 21208 10763 21208 10770 21208 10536 21209 10770 21209 10538 21209 10538 21210 10770 21210 10537 21210 10538 21211 10537 21211 10524 21211 10524 21212 10537 21212 8498 21212 10524 21213 8498 21213 10525 21213 11705 21214 10539 21214 9214 21214 9214 21215 10539 21215 10987 21215 9214 21216 10987 21216 10522 21216 10522 21217 10987 21217 10540 21217 10522 21218 10540 21218 7199 21218 7199 21219 10540 21219 7203 21219 10541 21220 11002 21220 10999 21220 10541 21221 10552 21221 10542 21221 10542 21222 10552 21222 6745 21222 10541 21223 10999 21223 10552 21223 10552 21224 10999 21224 10996 21224 10552 21225 10996 21225 10556 21225 6795 21226 6796 21226 10552 21226 10541 21227 10543 21227 11002 21227 11002 21228 10543 21228 10544 21228 11002 21229 10544 21229 11003 21229 11003 21230 10544 21230 10545 21230 11003 21231 10545 21231 11004 21231 11004 21232 10545 21232 10546 21232 11004 21233 10546 21233 10547 21233 10547 21234 10546 21234 10548 21234 10547 21235 10548 21235 10549 21235 10549 21236 10548 21236 8496 21236 10549 21237 8496 21237 10550 21237 10550 21238 8496 21238 8494 21238 10550 21239 8494 21239 10995 21239 10995 21240 8494 21240 10551 21240 10995 21241 10551 21241 10554 21241 6796 21242 6797 21242 10552 21242 10552 21243 6797 21243 6799 21243 10552 21244 6799 21244 9379 21244 10551 21245 10553 21245 10554 21245 10554 21246 10553 21246 8489 21246 10554 21247 8489 21247 10555 21247 10555 21248 8489 21248 8488 21248 10555 21249 8488 21249 10556 21249 10556 21250 8488 21250 6793 21250 10556 21251 6793 21251 10552 21251 10552 21252 6793 21252 6794 21252 10552 21253 6794 21253 6795 21253 10557 21254 6374 21254 11775 21254 11775 21255 10558 21255 10557 21255 10557 21256 10558 21256 10559 21256 10557 21257 10559 21257 10560 21257 10560 21258 10559 21258 10561 21258 10560 21259 10561 21259 11777 21259 11777 21260 11776 21260 10560 21260 10560 21261 11776 21261 11778 21261 10560 21262 11778 21262 10562 21262 10562 21263 11782 21263 10560 21263 10560 21264 11782 21264 11780 21264 10560 21265 11780 21265 10563 21265 8300 21266 8316 21266 10564 21266 10564 21267 8316 21267 8323 21267 10564 21268 8323 21268 8308 21268 10399 21269 10565 21269 10388 21269 10388 21270 10565 21270 8181 21270 8181 21271 10565 21271 10566 21271 10566 21272 10565 21272 10567 21272 10566 21273 10567 21273 8180 21273 10421 21274 8219 21274 10422 21274 10422 21275 8219 21275 8204 21275 10422 21276 8204 21276 10568 21276 8202 21277 8204 21277 10569 21277 10569 21278 8204 21278 8219 21278 10569 21279 8219 21279 10570 21279 10570 21280 8219 21280 10571 21280 7294 21281 7295 21281 10573 21281 7381 21282 7380 21282 10582 21282 10587 21283 7347 21283 10572 21283 10572 21284 7347 21284 7290 21284 10572 21285 7290 21285 10573 21285 10573 21286 7290 21286 7292 21286 10573 21287 7292 21287 7294 21287 11397 21288 11395 21288 10594 21288 7283 21289 7287 21289 10587 21289 10587 21290 7287 21290 7289 21290 10587 21291 7289 21291 7347 21291 7295 21292 7359 21292 10573 21292 10573 21293 7359 21293 7361 21293 10573 21294 7361 21294 10581 21294 10574 21295 10575 21295 10587 21295 10587 21296 10575 21296 10576 21296 10587 21297 10576 21297 7283 21297 11397 21298 8175 21298 10590 21298 11791 21299 10592 21299 11793 21299 11793 21300 10592 21300 10577 21300 11793 21301 10577 21301 11795 21301 11795 21302 10577 21302 10578 21302 7380 21303 10579 21303 10582 21303 10582 21304 10579 21304 10580 21304 10582 21305 10580 21305 11392 21305 7361 21306 7362 21306 10581 21306 10581 21307 7362 21307 7364 21307 10581 21308 7364 21308 10582 21308 10582 21309 7364 21309 10583 21309 10582 21310 10583 21310 7381 21310 8645 21311 8165 21311 11397 21311 11397 21312 8165 21312 10584 21312 11397 21313 10584 21313 8175 21313 10580 21314 10585 21314 11392 21314 11392 21315 10585 21315 10586 21315 11392 21316 10586 21316 10595 21316 10593 21317 7319 21317 10587 21317 7279 21318 7281 21318 11395 21318 11395 21319 7281 21319 7280 21319 11395 21320 7280 21320 7272 21320 7319 21321 10588 21321 10587 21321 10587 21322 10588 21322 10589 21322 10587 21323 10589 21323 10574 21323 10590 21324 8167 21324 11397 21324 11397 21325 8167 21325 8166 21325 11397 21326 8166 21326 11399 21326 11399 21327 8166 21327 10591 21327 11399 21328 10591 21328 11400 21328 7272 21329 7301 21329 11395 21329 11395 21330 7301 21330 10592 21330 11395 21331 10592 21331 10594 21331 10594 21332 10592 21332 11791 21332 11400 21333 10591 21333 10587 21333 10587 21334 10591 21334 7433 21334 10587 21335 7433 21335 10593 21335 8270 21336 8645 21336 8260 21336 8260 21337 8645 21337 11397 21337 8260 21338 11397 21338 11788 21338 11788 21339 11397 21339 10594 21339 10586 21340 7297 21340 10595 21340 10595 21341 7297 21341 7298 21341 10595 21342 7298 21342 10596 21342 10596 21343 7298 21343 10597 21343 10596 21344 10597 21344 11395 21344 11395 21345 10597 21345 7299 21345 11395 21346 7299 21346 7279 21346 10599 21347 10598 21347 10367 21347 10367 21348 8607 21348 10599 21348 10599 21349 8607 21349 10600 21349 10599 21350 10600 21350 7571 21350 10601 21351 10598 21351 10599 21351 10601 21352 10599 21352 10606 21352 7576 21353 8633 21353 10602 21353 7576 21354 10602 21354 7575 21354 7575 21355 10602 21355 10603 21355 7575 21356 10603 21356 7573 21356 7573 21357 10603 21357 10604 21357 7573 21358 10604 21358 10605 21358 7571 21359 10605 21359 10599 21359 10599 21360 10605 21360 10604 21360 10599 21361 10604 21361 10606 21361 10606 21362 10604 21362 10603 21362 10606 21363 10603 21363 10408 21363 10408 21364 10603 21364 10602 21364 10408 21365 10602 21365 10607 21365 10607 21366 10602 21366 8633 21366 10607 21367 8633 21367 10407 21367 7794 21368 10381 21368 7799 21368 7799 21369 10381 21369 10382 21369 7799 21370 10382 21370 10717 21370 7795 21371 7796 21371 10611 21371 10611 21372 10608 21372 7795 21372 7795 21373 10608 21373 10609 21373 7795 21374 10609 21374 7794 21374 7794 21375 10609 21375 10610 21375 7794 21376 10610 21376 10381 21376 7796 21377 10567 21377 10611 21377 10611 21378 10567 21378 10565 21378 10611 21379 10565 21379 10399 21379 8188 21380 8186 21380 10612 21380 8188 21381 10612 21381 10613 21381 10613 21382 10612 21382 7746 21382 10613 21383 7746 21383 10389 21383 10389 21384 7746 21384 10614 21384 10389 21385 10614 21385 10615 21385 10615 21386 10614 21386 7744 21386 10615 21387 7744 21387 10356 21387 10356 21388 7744 21388 10616 21388 10356 21389 10616 21389 10357 21389 10357 21390 10616 21390 10617 21390 10357 21391 10617 21391 10377 21391 10377 21392 10617 21392 8193 21392 10377 21393 8193 21393 10403 21393 10659 21394 9501 21394 10655 21394 10627 21395 10618 21395 10619 21395 10619 21396 10618 21396 9641 21396 10619 21397 9641 21397 10683 21397 11730 21398 11732 21398 10620 21398 10620 21399 10621 21399 11730 21399 11730 21400 10621 21400 9633 21400 11730 21401 9633 21401 11726 21401 11726 21402 9633 21402 10622 21402 11726 21403 10622 21403 11735 21403 11735 21404 10622 21404 9635 21404 11735 21405 9635 21405 11734 21405 11734 21406 9635 21406 9636 21406 11734 21407 9636 21407 11733 21407 11733 21408 9636 21408 10624 21408 11733 21409 10624 21409 10623 21409 10623 21410 10624 21410 9639 21410 10623 21411 9639 21411 10625 21411 10625 21412 9639 21412 10626 21412 10625 21413 10626 21413 10627 21413 10627 21414 10626 21414 9643 21414 10627 21415 9643 21415 10618 21415 11723 21416 9629 21416 11724 21416 11724 21417 9629 21417 9628 21417 11724 21418 9628 21418 10629 21418 10629 21419 9628 21419 10628 21419 10629 21420 10628 21420 10630 21420 10630 21421 10628 21421 10631 21421 10630 21422 10631 21422 11732 21422 11732 21423 10631 21423 9608 21423 11732 21424 9608 21424 10620 21424 9923 21425 10633 21425 10632 21425 10632 21426 10633 21426 10639 21426 10632 21427 10639 21427 10640 21427 9923 21428 9974 21428 10633 21428 10633 21429 9974 21429 10634 21429 10633 21430 10634 21430 11723 21430 11723 21431 10634 21431 9973 21431 11723 21432 9973 21432 9629 21432 10006 21433 10635 21433 10636 21433 10636 21434 10635 21434 9960 21434 10636 21435 9960 21435 10637 21435 9960 21436 9962 21436 10637 21436 10637 21437 9962 21437 10065 21437 10637 21438 10065 21438 10639 21438 10639 21439 10065 21439 10638 21439 10639 21440 10638 21440 10640 21440 9985 21441 11716 21441 10641 21441 10641 21442 11716 21442 11717 21442 10641 21443 11717 21443 10646 21443 9985 21444 10642 21444 11716 21444 11716 21445 10642 21445 10003 21445 11716 21446 10003 21446 10636 21446 10636 21447 10003 21447 10643 21447 10636 21448 10643 21448 10006 21448 9991 21449 10644 21449 10645 21449 10645 21450 10644 21450 9989 21450 10645 21451 9989 21451 11717 21451 11717 21452 9989 21452 9936 21452 11717 21453 9936 21453 10646 21453 10652 21454 10654 21454 11710 21454 11710 21455 10654 21455 10647 21455 11710 21456 10647 21456 11711 21456 11711 21457 10647 21457 10648 21457 11711 21458 10648 21458 10645 21458 10645 21459 10648 21459 10649 21459 10645 21460 10649 21460 9991 21460 10650 21461 10651 21461 10652 21461 10652 21462 10651 21462 10653 21462 10652 21463 10653 21463 10654 21463 10655 21464 9501 21464 10656 21464 10656 21465 9501 21465 9500 21465 10656 21466 9500 21466 11708 21466 11708 21467 9500 21467 9499 21467 11708 21468 9499 21468 10650 21468 10650 21469 9499 21469 10657 21469 10650 21470 10657 21470 10651 21470 11773 21471 10658 21471 10660 21471 10659 21472 10655 21472 10660 21472 10660 21473 10655 21473 11772 21473 10660 21474 11772 21474 11773 21474 10658 21475 11773 21475 10661 21475 10661 21476 11773 21476 10662 21476 10661 21477 10662 21477 9574 21477 9574 21478 10662 21478 10663 21478 9574 21479 10663 21479 9589 21479 9589 21480 10663 21480 11767 21480 9589 21481 11767 21481 10664 21481 10664 21482 11767 21482 11768 21482 10664 21483 11768 21483 10096 21483 10666 21484 11766 21484 10665 21484 10665 21485 10667 21485 10666 21485 10666 21486 10667 21486 10668 21486 10666 21487 10668 21487 11768 21487 11768 21488 10668 21488 10669 21488 11768 21489 10669 21489 10096 21489 10681 21490 10682 21490 10670 21490 10670 21491 10682 21491 10671 21491 10670 21492 10671 21492 11766 21492 11766 21493 10671 21493 10134 21493 11766 21494 10134 21494 10665 21494 10688 21495 9653 21495 10672 21495 10672 21496 9653 21496 10673 21496 10672 21497 10673 21497 11756 21497 11756 21498 10673 21498 10674 21498 11756 21499 10674 21499 10675 21499 10675 21500 10674 21500 9738 21500 10675 21501 9738 21501 11757 21501 11757 21502 9738 21502 9737 21502 11757 21503 9737 21503 11758 21503 11758 21504 9737 21504 10676 21504 11758 21505 10676 21505 11759 21505 11759 21506 10676 21506 9734 21506 11759 21507 9734 21507 10677 21507 10677 21508 9734 21508 10678 21508 10677 21509 10678 21509 11762 21509 11762 21510 10678 21510 10679 21510 11762 21511 10679 21511 10681 21511 10681 21512 10679 21512 10680 21512 10681 21513 10680 21513 10682 21513 9641 21514 9646 21514 10683 21514 10683 21515 9646 21515 9645 21515 10683 21516 9645 21516 11743 21516 11743 21517 9645 21517 10684 21517 11743 21518 10684 21518 11746 21518 11746 21519 10684 21519 9652 21519 11746 21520 9652 21520 10685 21520 10685 21521 9652 21521 9650 21521 10685 21522 9650 21522 11749 21522 11749 21523 9650 21523 9649 21523 11749 21524 9649 21524 10686 21524 10686 21525 9649 21525 10687 21525 10686 21526 10687 21526 11747 21526 11747 21527 10687 21527 9647 21527 11747 21528 9647 21528 10688 21528 10688 21529 9647 21529 9654 21529 10688 21530 9654 21530 9653 21530 11576 21531 10690 21531 10689 21531 10689 21532 10690 21532 10354 21532 10689 21533 10354 21533 11600 21533 11600 21534 10354 21534 10691 21534 10691 21535 10354 21535 11602 21535 11602 21536 10354 21536 10692 21536 11602 21537 10692 21537 10694 21537 10694 21538 10692 21538 10693 21538 10694 21539 10693 21539 11597 21539 10695 21540 8650 21540 10693 21540 10693 21541 8650 21541 11598 21541 10693 21542 11598 21542 11597 21542 8653 21543 8652 21543 10696 21543 8653 21544 10696 21544 11607 21544 11607 21545 10696 21545 10697 21545 11607 21546 10697 21546 11609 21546 11609 21547 10697 21547 10437 21547 11609 21548 10437 21548 10698 21548 10714 21549 10715 21549 8879 21549 8879 21550 10715 21550 10419 21550 8879 21551 10419 21551 10699 21551 10699 21552 10419 21552 10700 21552 10699 21553 10700 21553 8706 21553 8706 21554 10700 21554 10701 21554 8706 21555 10701 21555 10702 21555 10702 21556 10701 21556 10704 21556 10702 21557 10704 21557 10703 21557 10703 21558 10704 21558 10418 21558 10703 21559 10418 21559 8708 21559 8708 21560 10418 21560 10425 21560 8708 21561 10425 21561 10705 21561 10705 21562 10425 21562 10427 21562 10705 21563 10427 21563 8705 21563 8705 21564 10427 21564 10707 21564 8705 21565 10707 21565 10706 21565 10706 21566 10707 21566 10429 21566 10706 21567 10429 21567 10708 21567 10708 21568 10429 21568 10432 21568 10708 21569 10432 21569 10709 21569 10709 21570 10432 21570 10710 21570 10709 21571 10710 21571 8703 21571 8703 21572 10710 21572 10434 21572 8703 21573 10434 21573 10711 21573 10711 21574 10434 21574 10435 21574 10711 21575 10435 21575 8702 21575 8702 21576 10435 21576 10436 21576 8702 21577 10436 21577 10712 21577 10712 21578 10436 21578 10713 21578 10712 21579 10713 21579 10714 21579 10714 21580 10713 21580 10715 21580 8207 21581 10716 21581 7800 21581 10722 21582 7799 21582 10717 21582 8207 21583 7800 21583 8208 21583 8208 21584 7800 21584 10393 21584 10393 21585 7800 21585 10718 21585 10393 21586 10718 21586 10372 21586 10372 21587 10718 21587 7802 21587 10372 21588 7802 21588 10397 21588 7802 21589 10719 21589 10397 21589 10397 21590 10719 21590 10720 21590 10397 21591 10720 21591 10721 21591 10721 21592 10720 21592 7805 21592 10721 21593 7805 21593 10362 21593 10717 21594 10361 21594 10722 21594 10722 21595 10361 21595 10362 21595 10722 21596 10362 21596 10723 21596 10723 21597 10362 21597 7805 21597 8234 21598 7924 21598 10724 21598 7876 21599 8226 21599 10730 21599 8234 21600 10724 21600 10725 21600 10725 21601 10724 21601 10726 21601 10726 21602 10724 21602 7881 21602 10726 21603 7881 21603 10394 21603 10394 21604 7881 21604 10727 21604 10394 21605 10727 21605 10395 21605 10727 21606 7879 21606 10395 21606 10395 21607 7879 21607 7878 21607 10395 21608 7878 21608 10398 21608 10398 21609 7878 21609 7877 21609 10398 21610 7877 21610 10371 21610 7877 21611 10728 21611 10371 21611 10371 21612 10728 21612 7876 21612 10371 21613 7876 21613 10729 21613 10729 21614 7876 21614 10730 21614 10729 21615 10730 21615 8221 21615 10736 21616 8585 21616 10731 21616 10731 21617 8585 21617 10732 21617 10733 21618 6977 21618 10732 21618 6977 21619 6978 21619 10732 21619 10732 21620 6978 21620 6984 21620 10732 21621 6984 21621 10731 21621 10732 21622 8584 21622 10733 21622 10733 21623 8584 21623 8582 21623 10733 21624 8582 21624 6974 21624 6974 21625 8582 21625 8581 21625 6974 21626 8581 21626 8591 21626 7013 21627 8587 21627 10734 21627 10734 21628 8587 21628 10735 21628 10734 21629 10735 21629 10737 21629 10736 21630 6980 21630 8585 21630 8585 21631 6980 21631 6971 21631 8585 21632 6971 21632 10737 21632 10737 21633 6971 21633 10738 21633 10737 21634 10738 21634 10734 21634 10748 21635 10498 21635 10739 21635 7038 21636 7036 21636 10739 21636 10739 21637 7036 21637 7035 21637 10739 21638 7035 21638 10748 21638 7038 21639 10739 21639 10740 21639 10740 21640 10739 21640 10741 21640 10740 21641 10741 21641 10742 21641 10742 21642 10741 21642 10743 21642 10742 21643 10743 21643 7033 21643 10494 21644 10744 21644 10743 21644 10743 21645 10744 21645 10745 21645 10743 21646 10745 21646 7033 21646 8569 21647 10746 21647 7054 21647 7054 21648 10746 21648 10499 21648 7054 21649 10499 21649 10747 21649 10748 21650 10749 21650 10498 21650 10498 21651 10749 21651 7053 21651 10498 21652 7053 21652 10747 21652 10747 21653 7053 21653 7056 21653 10747 21654 7056 21654 7054 21654 10760 21655 10751 21655 7120 21655 10756 21656 7100 21656 10751 21656 10751 21657 7100 21657 10750 21657 10750 21658 7101 21658 10751 21658 10751 21659 7101 21659 10752 21659 10751 21660 10752 21660 7120 21660 10753 21661 10458 21661 7094 21661 7094 21662 10754 21662 10753 21662 10753 21663 10754 21663 7095 21663 10753 21664 7095 21664 10756 21664 10756 21665 7095 21665 10755 21665 10756 21666 10755 21666 7100 21666 10757 21667 10758 21667 10759 21667 10759 21668 10758 21668 10463 21668 10761 21669 7113 21669 10463 21669 10463 21670 7113 21670 7112 21670 10463 21671 7112 21671 10759 21671 7120 21672 7119 21672 10760 21672 10760 21673 7119 21673 7108 21673 10760 21674 7108 21674 10761 21674 10761 21675 7108 21675 10762 21675 10761 21676 10762 21676 7113 21676 7175 21677 10763 21677 7172 21677 7172 21678 10763 21678 10535 21678 7172 21679 10535 21679 10765 21679 10767 21680 10764 21680 10535 21680 10764 21681 7166 21681 10535 21681 10535 21682 7166 21682 7150 21682 10535 21683 7150 21683 10765 21683 10535 21684 10533 21684 10767 21684 10767 21685 10533 21685 10766 21685 10767 21686 10766 21686 7160 21686 7160 21687 10766 21687 10530 21687 7160 21688 10530 21688 7165 21688 7190 21689 8498 21689 7191 21689 7191 21690 8498 21690 10537 21690 7191 21691 10537 21691 7178 21691 7178 21692 10537 21692 10768 21692 10768 21693 10537 21693 10770 21693 10768 21694 10770 21694 7176 21694 7175 21695 10769 21695 10763 21695 10763 21696 10769 21696 7174 21696 10763 21697 7174 21697 10770 21697 10770 21698 7174 21698 7187 21698 10770 21699 7187 21699 7176 21699 10786 21700 10771 21700 10329 21700 10329 21701 10771 21701 10772 21701 10329 21702 10772 21702 10218 21702 10218 21703 10772 21703 10773 21703 10218 21704 10773 21704 10217 21704 10217 21705 10773 21705 10775 21705 10217 21706 10775 21706 10774 21706 10774 21707 10775 21707 10777 21707 10774 21708 10777 21708 10776 21708 10776 21709 10777 21709 10779 21709 10776 21710 10779 21710 10778 21710 10778 21711 10779 21711 10781 21711 10778 21712 10781 21712 10780 21712 10780 21713 10781 21713 11456 21713 10780 21714 11456 21714 10220 21714 10220 21715 11456 21715 10782 21715 10220 21716 10782 21716 10223 21716 10223 21717 10782 21717 10783 21717 10223 21718 10783 21718 10784 21718 10784 21719 10783 21719 10785 21719 10784 21720 10785 21720 10221 21720 10221 21721 10785 21721 11452 21721 10221 21722 11452 21722 10786 21722 10786 21723 11452 21723 10771 21723 10801 21724 11438 21724 10787 21724 10787 21725 11438 21725 10788 21725 10787 21726 10788 21726 10227 21726 10227 21727 10788 21727 11440 21727 10227 21728 11440 21728 10789 21728 10789 21729 11440 21729 11442 21729 10789 21730 11442 21730 10790 21730 10790 21731 11442 21731 10792 21731 10790 21732 10792 21732 10791 21732 10791 21733 10792 21733 10793 21733 10791 21734 10793 21734 10228 21734 10228 21735 10793 21735 10794 21735 10228 21736 10794 21736 10795 21736 10795 21737 10794 21737 11447 21737 10795 21738 11447 21738 10796 21738 10796 21739 11447 21739 10798 21739 10796 21740 10798 21740 10797 21740 10797 21741 10798 21741 10799 21741 10797 21742 10799 21742 10231 21742 10231 21743 10799 21743 10800 21743 10231 21744 10800 21744 10323 21744 10323 21745 10800 21745 11451 21745 10323 21746 11451 21746 10801 21746 10801 21747 11451 21747 11438 21747 10248 21748 11427 21748 10802 21748 10802 21749 11427 21749 10803 21749 10802 21750 10803 21750 10804 21750 10804 21751 10803 21751 11430 21751 10804 21752 11430 21752 10805 21752 10805 21753 11430 21753 11431 21753 10805 21754 11431 21754 10806 21754 10806 21755 11431 21755 11432 21755 10806 21756 11432 21756 10807 21756 10807 21757 11432 21757 11433 21757 10807 21758 11433 21758 10234 21758 10234 21759 11433 21759 10808 21759 10234 21760 10808 21760 10235 21760 10235 21761 10808 21761 11434 21761 10235 21762 11434 21762 10236 21762 10236 21763 11434 21763 11436 21763 10236 21764 11436 21764 10247 21764 10247 21765 11436 21765 11437 21765 10247 21766 11437 21766 10809 21766 10809 21767 11437 21767 10810 21767 10809 21768 10810 21768 10811 21768 10811 21769 10810 21769 11426 21769 10811 21770 11426 21770 10248 21770 10248 21771 11426 21771 11427 21771 10344 21772 10813 21772 10812 21772 10812 21773 10813 21773 11461 21773 10812 21774 11461 21774 10814 21774 10814 21775 11461 21775 10815 21775 10814 21776 10815 21776 10336 21776 10336 21777 10815 21777 11464 21777 10336 21778 11464 21778 10335 21778 10335 21779 11464 21779 10816 21779 10335 21780 10816 21780 10817 21780 10817 21781 10816 21781 10818 21781 10817 21782 10818 21782 10333 21782 10333 21783 10818 21783 10819 21783 10333 21784 10819 21784 10338 21784 10338 21785 10819 21785 11465 21785 10338 21786 11465 21786 10339 21786 10339 21787 11465 21787 10820 21787 10339 21788 10820 21788 10821 21788 10821 21789 10820 21789 10822 21789 10821 21790 10822 21790 10341 21790 10341 21791 10822 21791 10823 21791 10341 21792 10823 21792 10343 21792 10343 21793 10823 21793 10824 21793 10343 21794 10824 21794 10344 21794 10344 21795 10824 21795 10813 21795 10839 21796 10825 21796 10826 21796 10826 21797 10825 21797 11544 21797 10826 21798 11544 21798 8426 21798 8426 21799 11544 21799 10827 21799 8426 21800 10827 21800 8428 21800 8428 21801 10827 21801 10828 21801 8428 21802 10828 21802 10829 21802 10829 21803 10828 21803 10830 21803 10829 21804 10830 21804 8430 21804 8430 21805 10830 21805 10831 21805 8430 21806 10831 21806 8431 21806 8431 21807 10831 21807 10832 21807 8431 21808 10832 21808 10833 21808 10833 21809 10832 21809 11548 21809 10833 21810 11548 21810 8432 21810 8432 21811 11548 21811 10834 21811 8432 21812 10834 21812 10836 21812 10836 21813 10834 21813 10835 21813 10836 21814 10835 21814 10837 21814 10837 21815 10835 21815 11549 21815 10837 21816 11549 21816 10838 21816 10838 21817 11549 21817 11550 21817 10838 21818 11550 21818 10839 21818 10839 21819 11550 21819 10825 21819 8416 21820 10840 21820 8417 21820 8417 21821 10840 21821 10841 21821 8417 21822 10841 21822 10842 21822 10842 21823 10841 21823 11468 21823 10842 21824 11468 21824 10843 21824 10843 21825 11468 21825 11469 21825 10843 21826 11469 21826 8419 21826 8419 21827 11469 21827 10844 21827 8419 21828 10844 21828 10845 21828 10845 21829 10844 21829 10846 21829 10845 21830 10846 21830 10847 21830 10847 21831 10846 21831 11471 21831 10847 21832 11471 21832 8421 21832 8421 21833 11471 21833 11473 21833 8421 21834 11473 21834 8422 21834 8422 21835 11473 21835 10848 21835 8422 21836 10848 21836 10849 21836 10849 21837 10848 21837 10850 21837 10849 21838 10850 21838 10851 21838 10851 21839 10850 21839 10852 21839 10851 21840 10852 21840 10853 21840 10853 21841 10852 21841 11475 21841 10853 21842 11475 21842 8416 21842 8416 21843 11475 21843 10840 21843 8409 21844 10864 21844 10854 21844 10854 21845 10864 21845 10855 21845 10854 21846 10855 21846 10856 21846 10856 21847 10855 21847 11502 21847 10856 21848 11502 21848 8411 21848 8411 21849 11502 21849 11503 21849 8411 21850 11503 21850 10857 21850 10857 21851 11503 21851 11504 21851 10857 21852 11504 21852 8414 21852 8414 21853 11504 21853 11505 21853 8414 21854 11505 21854 10858 21854 10858 21855 11505 21855 11508 21855 10858 21856 11508 21856 10859 21856 10859 21857 11508 21857 11509 21857 10859 21858 11509 21858 10860 21858 10860 21859 11509 21859 10861 21859 10860 21860 10861 21860 10862 21860 10862 21861 10861 21861 11513 21861 10862 21862 11513 21862 10863 21862 10863 21863 11513 21863 11514 21863 10863 21864 11514 21864 8407 21864 8407 21865 11514 21865 11516 21865 8407 21866 11516 21866 8409 21866 8409 21867 11516 21867 10864 21867 10875 21868 10865 21868 8400 21868 8400 21869 10865 21869 10866 21869 8400 21870 10866 21870 10867 21870 10867 21871 10866 21871 10868 21871 10867 21872 10868 21872 8402 21872 8402 21873 10868 21873 11481 21873 8402 21874 11481 21874 10869 21874 10869 21875 11481 21875 11482 21875 10869 21876 11482 21876 10870 21876 10870 21877 11482 21877 11484 21877 10870 21878 11484 21878 10871 21878 10871 21879 11484 21879 10872 21879 10871 21880 10872 21880 8391 21880 8391 21881 10872 21881 10873 21881 8391 21882 10873 21882 8393 21882 8393 21883 10873 21883 11485 21883 8393 21884 11485 21884 10874 21884 10874 21885 11485 21885 11486 21885 10874 21886 11486 21886 8396 21886 8396 21887 11486 21887 11488 21887 8396 21888 11488 21888 8399 21888 8399 21889 11488 21889 10876 21889 8399 21890 10876 21890 10875 21890 10875 21891 10876 21891 10865 21891 10886 21892 10877 21892 8386 21892 8386 21893 10877 21893 11543 21893 8386 21894 11543 21894 10878 21894 10878 21895 11543 21895 11531 21895 10878 21896 11531 21896 10879 21896 10879 21897 11531 21897 11533 21897 10879 21898 11533 21898 8377 21898 8377 21899 11533 21899 11534 21899 8377 21900 11534 21900 8379 21900 8379 21901 11534 21901 11535 21901 8379 21902 11535 21902 8380 21902 8380 21903 11535 21903 11536 21903 8380 21904 11536 21904 10880 21904 10880 21905 11536 21905 11537 21905 10880 21906 11537 21906 10881 21906 10881 21907 11537 21907 11539 21907 10881 21908 11539 21908 10883 21908 10883 21909 11539 21909 10882 21909 10883 21910 10882 21910 8384 21910 8384 21911 10882 21911 10884 21911 8384 21912 10884 21912 8385 21912 8385 21913 10884 21913 10885 21913 8385 21914 10885 21914 10886 21914 10886 21915 10885 21915 10877 21915 10887 21916 11565 21916 10888 21916 10888 21917 11565 21917 11567 21917 10888 21918 11567 21918 10889 21918 10889 21919 11567 21919 10890 21919 10889 21920 10890 21920 8375 21920 8375 21921 10890 21921 11552 21921 8375 21922 11552 21922 10891 21922 10891 21923 11552 21923 11554 21923 10891 21924 11554 21924 8366 21924 8366 21925 11554 21925 11556 21925 8366 21926 11556 21926 10892 21926 10892 21927 11556 21927 11557 21927 10892 21928 11557 21928 10893 21928 10893 21929 11557 21929 11559 21929 10893 21930 11559 21930 10894 21930 10894 21931 11559 21931 11560 21931 10894 21932 11560 21932 8370 21932 8370 21933 11560 21933 10896 21933 8370 21934 10896 21934 10895 21934 10895 21935 10896 21935 11562 21935 10895 21936 11562 21936 8374 21936 8374 21937 11562 21937 11564 21937 8374 21938 11564 21938 10887 21938 10887 21939 11564 21939 11565 21939 8355 21940 10897 21940 10898 21940 10898 21941 10897 21941 10900 21941 10898 21942 10900 21942 10899 21942 10899 21943 10900 21943 10901 21943 10899 21944 10901 21944 10902 21944 10902 21945 10901 21945 10903 21945 10902 21946 10903 21946 8360 21946 8360 21947 10903 21947 11519 21947 8360 21948 11519 21948 8361 21948 8361 21949 11519 21949 10905 21949 8361 21950 10905 21950 10904 21950 10904 21951 10905 21951 11521 21951 10904 21952 11521 21952 8362 21952 8362 21953 11521 21953 11523 21953 8362 21954 11523 21954 8364 21954 8364 21955 11523 21955 10906 21955 8364 21956 10906 21956 8351 21956 8351 21957 10906 21957 11524 21957 8351 21958 11524 21958 8353 21958 8353 21959 11524 21959 11528 21959 8353 21960 11528 21960 10907 21960 10907 21961 11528 21961 10908 21961 10907 21962 10908 21962 8355 21962 8355 21963 10908 21963 10897 21963 10909 21964 11501 21964 8342 21964 8342 21965 11501 21965 11489 21965 8342 21966 11489 21966 10910 21966 10910 21967 11489 21967 11490 21967 10910 21968 11490 21968 8345 21968 8345 21969 11490 21969 11492 21969 8345 21970 11492 21970 10911 21970 10911 21971 11492 21971 10912 21971 10911 21972 10912 21972 10913 21972 10913 21973 10912 21973 10914 21973 10913 21974 10914 21974 8348 21974 8348 21975 10914 21975 11494 21975 8348 21976 11494 21976 10915 21976 10915 21977 11494 21977 11497 21977 10915 21978 11497 21978 8349 21978 8349 21979 11497 21979 10916 21979 8349 21980 10916 21980 8339 21980 8339 21981 10916 21981 11498 21981 8339 21982 11498 21982 8341 21982 8341 21983 11498 21983 11499 21983 8341 21984 11499 21984 10917 21984 10917 21985 11499 21985 10918 21985 10917 21986 10918 21986 10909 21986 10909 21987 10918 21987 11501 21987 8429 21988 10464 21988 10919 21988 10919 21989 10464 21989 10920 21989 10919 21990 10920 21990 10921 21990 10921 21991 10920 21991 10922 21991 10921 21992 10922 21992 8427 21992 8427 21993 10922 21993 10923 21993 8427 21994 10923 21994 8425 21994 8425 21995 10923 21995 10924 21995 8425 21996 10924 21996 10925 21996 10925 21997 10924 21997 10459 21997 10925 21998 10459 21998 8424 21998 8424 21999 10459 21999 10460 21999 8424 22000 10460 22000 10926 22000 10926 22001 10460 22001 10461 22001 10926 22002 10461 22002 8423 22002 8423 22003 10461 22003 10462 22003 8423 22004 10462 22004 8433 22004 8433 22005 10462 22005 10927 22005 8433 22006 10927 22006 10928 22006 10928 22007 10927 22007 10467 22007 10928 22008 10467 22008 10929 22008 10929 22009 10467 22009 10468 22009 10929 22010 10468 22010 8429 22010 8429 22011 10468 22011 10464 22011 10939 22012 10480 22012 8359 22012 8359 22013 10480 22013 10930 22013 8359 22014 10930 22014 8358 22014 8358 22015 10930 22015 10931 22015 8358 22016 10931 22016 8357 22016 8357 22017 10931 22017 10932 22017 8357 22018 10932 22018 8356 22018 8356 22019 10932 22019 10934 22019 8356 22020 10934 22020 10933 22020 10933 22021 10934 22021 10473 22021 10933 22022 10473 22022 8354 22022 8354 22023 10473 22023 10475 22023 8354 22024 10475 22024 8352 22024 8352 22025 10475 22025 10935 22025 8352 22026 10935 22026 8350 22026 8350 22027 10935 22027 10936 22027 8350 22028 10936 22028 10937 22028 10937 22029 10936 22029 10477 22029 10937 22030 10477 22030 8363 22030 8363 22031 10477 22031 10478 22031 8363 22032 10478 22032 10938 22032 10938 22033 10478 22033 10940 22033 10938 22034 10940 22034 10939 22034 10939 22035 10940 22035 10480 22035 10952 22036 10953 22036 10941 22036 10941 22037 10953 22037 10490 22037 10941 22038 10490 22038 8413 22038 8413 22039 10490 22039 10942 22039 8413 22040 10942 22040 8412 22040 8412 22041 10942 22041 10493 22041 8412 22042 10493 22042 8410 22042 8410 22043 10493 22043 10944 22043 8410 22044 10944 22044 10943 22044 10943 22045 10944 22045 10495 22045 10943 22046 10495 22046 8408 22046 8408 22047 10495 22047 10496 22047 8408 22048 10496 22048 10945 22048 10945 22049 10496 22049 10497 22049 10945 22050 10497 22050 8406 22050 8406 22051 10497 22051 10946 22051 8406 22052 10946 22052 8405 22052 8405 22053 10946 22053 10947 22053 8405 22054 10947 22054 10948 22054 10948 22055 10947 22055 10949 22055 10948 22056 10949 22056 10950 22056 10950 22057 10949 22057 10951 22057 10950 22058 10951 22058 10952 22058 10952 22059 10951 22059 10953 22059 10954 22060 8529 22060 8420 22060 8420 22061 8529 22061 10955 22061 8420 22062 10955 22062 10956 22062 10956 22063 10955 22063 8531 22063 10956 22064 8531 22064 8418 22064 8418 22065 8531 22065 10957 22065 8418 22066 10957 22066 10958 22066 10958 22067 10957 22067 8523 22067 10958 22068 8523 22068 10959 22068 10959 22069 8523 22069 8520 22069 10959 22070 8520 22070 10960 22070 10960 22071 8520 22071 8519 22071 10960 22072 8519 22072 8415 22072 8415 22073 8519 22073 10962 22073 8415 22074 10962 22074 10961 22074 10961 22075 10962 22075 10963 22075 10961 22076 10963 22076 10964 22076 10964 22077 10963 22077 10966 22077 10964 22078 10966 22078 10965 22078 10965 22079 10966 22079 8526 22079 10965 22080 8526 22080 10967 22080 10967 22081 8526 22081 8527 22081 10967 22082 8527 22082 10954 22082 10954 22083 8527 22083 8529 22083 10968 22084 8571 22084 8347 22084 8347 22085 8571 22085 8575 22085 8347 22086 8575 22086 8346 22086 8346 22087 8575 22087 8580 22087 8346 22088 8580 22088 8344 22088 8344 22089 8580 22089 10969 22089 8344 22090 10969 22090 8343 22090 8343 22091 10969 22091 10970 22091 8343 22092 10970 22092 10971 22092 10971 22093 10970 22093 8583 22093 10971 22094 8583 22094 10973 22094 10973 22095 8583 22095 10972 22095 10973 22096 10972 22096 10975 22096 10975 22097 10972 22097 10974 22097 10975 22098 10974 22098 8340 22098 8340 22099 10974 22099 10976 22099 8340 22100 10976 22100 10977 22100 10977 22101 10976 22101 8586 22101 10977 22102 8586 22102 10978 22102 10978 22103 8586 22103 10980 22103 10978 22104 10980 22104 10979 22104 10979 22105 10980 22105 8572 22105 10979 22106 8572 22106 10968 22106 10968 22107 8572 22107 8571 22107 8390 22108 10515 22108 8404 22108 8404 22109 10515 22109 10516 22109 8404 22110 10516 22110 8403 22110 8403 22111 10516 22111 10518 22111 8403 22112 10518 22112 8401 22112 8401 22113 10518 22113 10503 22113 8401 22114 10503 22114 10981 22114 10981 22115 10503 22115 10983 22115 10981 22116 10983 22116 10982 22116 10982 22117 10983 22117 10504 22117 10982 22118 10504 22118 8398 22118 8398 22119 10504 22119 10506 22119 8398 22120 10506 22120 8397 22120 8397 22121 10506 22121 10984 22121 8397 22122 10984 22122 8395 22122 8395 22123 10984 22123 10508 22123 8395 22124 10508 22124 8394 22124 8394 22125 10508 22125 10510 22125 8394 22126 10510 22126 8392 22126 8392 22127 10510 22127 10513 22127 8392 22128 10513 22128 10985 22128 10985 22129 10513 22129 10986 22129 10985 22130 10986 22130 8390 22130 8390 22131 10986 22131 10515 22131 8367 22132 10987 22132 8365 22132 8365 22133 10987 22133 10527 22133 8365 22134 10527 22134 8376 22134 8376 22135 10527 22135 10989 22135 8376 22136 10989 22136 10988 22136 10988 22137 10989 22137 10529 22137 10988 22138 10529 22138 10990 22138 10990 22139 10529 22139 10531 22139 10990 22140 10531 22140 10991 22140 10991 22141 10531 22141 10532 22141 10991 22142 10532 22142 8373 22142 8373 22143 10532 22143 10534 22143 8373 22144 10534 22144 8372 22144 8372 22145 10534 22145 10992 22145 8372 22146 10992 22146 8371 22146 8371 22147 10992 22147 10536 22147 8371 22148 10536 22148 8369 22148 8369 22149 10536 22149 10538 22149 8369 22150 10538 22150 10993 22150 10993 22151 10538 22151 10524 22151 10993 22152 10524 22152 8368 22152 8368 22153 10524 22153 10540 22153 8368 22154 10540 22154 8367 22154 8367 22155 10540 22155 10987 22155 10994 22156 10550 22156 8378 22156 8378 22157 10550 22157 10995 22157 8378 22158 10995 22158 8389 22158 8389 22159 10995 22159 10554 22159 8389 22160 10554 22160 8388 22160 8388 22161 10554 22161 10555 22161 8388 22162 10555 22162 8387 22162 8387 22163 10555 22163 10556 22163 8387 22164 10556 22164 10997 22164 10997 22165 10556 22165 10996 22165 10997 22166 10996 22166 10998 22166 10998 22167 10996 22167 10999 22167 10998 22168 10999 22168 11000 22168 11000 22169 10999 22169 11002 22169 11000 22170 11002 22170 11001 22170 11001 22171 11002 22171 11003 22171 11001 22172 11003 22172 8383 22172 8383 22173 11003 22173 11004 22173 8383 22174 11004 22174 8382 22174 8382 22175 11004 22175 10547 22175 8382 22176 10547 22176 8381 22176 8381 22177 10547 22177 10549 22177 8381 22178 10549 22178 10994 22178 10994 22179 10549 22179 10550 22179 11011 22180 11012 22180 11013 22180 11020 22181 11012 22181 11011 22181 11011 22182 11015 22182 11016 22182 11005 22183 11015 22183 11011 22183 11013 22184 11005 22184 11011 22184 11011 22185 11008 22185 11006 22185 11007 22186 11008 22186 11011 22186 11016 22187 11007 22187 11011 22187 11011 22188 11009 22188 11010 22188 11018 22189 11009 22189 11011 22189 11006 22190 11018 22190 11011 22190 11010 22191 11020 22191 11011 22191 11020 22192 8453 22192 11012 22192 11012 22193 8453 22193 8454 22193 11012 22194 8454 22194 11013 22194 11013 22195 8454 22195 11014 22195 11013 22196 11014 22196 11005 22196 11005 22197 11014 22197 8458 22197 11005 22198 8458 22198 11015 22198 11015 22199 8458 22199 8459 22199 11015 22200 8459 22200 11016 22200 11016 22201 8459 22201 8460 22201 11016 22202 8460 22202 11007 22202 11007 22203 8460 22203 8463 22203 11007 22204 8463 22204 11008 22204 11008 22205 8463 22205 11017 22205 11008 22206 11017 22206 11006 22206 11006 22207 11017 22207 8465 22207 11006 22208 8465 22208 11018 22208 11018 22209 8465 22209 8467 22209 11018 22210 8467 22210 11009 22210 11009 22211 8467 22211 11019 22211 11009 22212 11019 22212 11010 22212 11010 22213 11019 22213 8451 22213 11010 22214 8451 22214 11020 22214 11020 22215 8451 22215 8453 22215 11021 22216 11022 22216 11027 22216 11038 22217 11022 22217 11021 22217 11021 22218 11024 22218 11029 22218 11023 22219 11024 22219 11021 22219 11027 22220 11023 22220 11021 22220 11021 22221 11025 22221 11033 22221 11031 22222 11025 22222 11021 22222 11029 22223 11031 22223 11021 22223 11021 22224 11036 22224 11026 22224 11034 22225 11036 22225 11021 22225 11033 22226 11034 22226 11021 22226 11026 22227 11038 22227 11021 22227 11038 22228 11040 22228 11022 22228 11022 22229 11040 22229 8469 22229 11022 22230 8469 22230 11027 22230 11027 22231 8469 22231 11028 22231 11027 22232 11028 22232 11023 22232 11023 22233 11028 22233 8470 22233 11023 22234 8470 22234 11024 22234 11024 22235 8470 22235 8471 22235 11024 22236 8471 22236 11029 22236 11029 22237 8471 22237 11030 22237 11029 22238 11030 22238 11031 22238 11031 22239 11030 22239 11032 22239 11031 22240 11032 22240 11025 22240 11025 22241 11032 22241 8473 22241 11025 22242 8473 22242 11033 22242 11033 22243 8473 22243 11035 22243 11033 22244 11035 22244 11034 22244 11034 22245 11035 22245 11037 22245 11034 22246 11037 22246 11036 22246 11036 22247 11037 22247 8468 22247 11036 22248 8468 22248 11026 22248 11026 22249 8468 22249 11039 22249 11026 22250 11039 22250 11038 22250 11038 22251 11039 22251 11040 22251 11042 22252 11047 22252 11049 22252 11046 22253 11047 22253 11042 22253 11042 22254 11052 22254 11053 22254 11041 22255 11052 22255 11042 22255 11049 22256 11041 22256 11042 22256 11042 22257 11054 22257 11055 22257 11043 22258 11054 22258 11042 22258 11053 22259 11043 22259 11042 22259 11042 22260 11044 22260 11045 22260 11056 22261 11044 22261 11042 22261 11055 22262 11056 22262 11042 22262 11045 22263 11046 22263 11042 22263 11046 22264 8477 22264 11047 22264 11047 22265 8477 22265 11048 22265 11047 22266 11048 22266 11049 22266 11049 22267 11048 22267 8479 22267 11049 22268 8479 22268 11041 22268 11041 22269 8479 22269 11050 22269 11041 22270 11050 22270 11052 22270 11052 22271 11050 22271 11051 22271 11052 22272 11051 22272 11053 22272 11053 22273 11051 22273 8482 22273 11053 22274 8482 22274 11043 22274 11043 22275 8482 22275 8484 22275 11043 22276 8484 22276 11054 22276 11054 22277 8484 22277 8485 22277 11054 22278 8485 22278 11055 22278 11055 22279 8485 22279 11057 22279 11055 22280 11057 22280 11056 22280 11056 22281 11057 22281 11058 22281 11056 22282 11058 22282 11044 22282 11044 22283 11058 22283 11059 22283 11044 22284 11059 22284 11045 22284 11045 22285 11059 22285 11060 22285 11045 22286 11060 22286 11046 22286 11046 22287 11060 22287 8477 22287 11068 22288 11061 22288 11062 22288 11067 22289 11061 22289 11068 22289 11068 22290 11070 22290 11071 22290 11069 22291 11070 22291 11068 22291 11062 22292 11069 22292 11068 22292 11068 22293 11063 22293 11064 22293 11072 22294 11063 22294 11068 22294 11071 22295 11072 22295 11068 22295 11068 22296 11065 22296 11066 22296 11073 22297 11065 22297 11068 22297 11064 22298 11073 22298 11068 22298 11066 22299 11067 22299 11068 22299 11067 22300 11075 22300 11061 22300 11061 22301 11075 22301 8440 22301 11061 22302 8440 22302 11062 22302 11062 22303 8440 22303 8442 22303 11062 22304 8442 22304 11069 22304 11069 22305 8442 22305 8443 22305 11069 22306 8443 22306 11070 22306 11070 22307 8443 22307 8444 22307 11070 22308 8444 22308 11071 22308 11071 22309 8444 22309 8445 22309 11071 22310 8445 22310 11072 22310 11072 22311 8445 22311 8446 22311 11072 22312 8446 22312 11063 22312 11063 22313 8446 22313 8448 22313 11063 22314 8448 22314 11064 22314 11064 22315 8448 22315 8449 22315 11064 22316 8449 22316 11073 22316 11073 22317 8449 22317 11074 22317 11073 22318 11074 22318 11065 22318 11065 22319 11074 22319 8435 22319 11065 22320 8435 22320 11066 22320 11066 22321 8435 22321 8437 22321 11066 22322 8437 22322 11067 22322 11067 22323 8437 22323 11075 22323 11078 22324 11077 22324 11076 22324 11079 22325 11077 22325 11078 22325 11078 22326 11084 22326 11085 22326 11082 22327 11084 22327 11078 22327 11076 22328 11082 22328 11078 22328 11078 22329 11087 22329 11089 22329 11086 22330 11087 22330 11078 22330 11085 22331 11086 22331 11078 22331 11078 22332 11091 22332 11092 22332 11090 22333 11091 22333 11078 22333 11089 22334 11090 22334 11078 22334 11092 22335 11079 22335 11078 22335 11079 22336 8771 22336 11077 22336 11077 22337 8771 22337 11080 22337 11077 22338 11080 22338 11076 22338 11076 22339 11080 22339 11081 22339 11076 22340 11081 22340 11082 22340 11082 22341 11081 22341 11083 22341 11082 22342 11083 22342 11084 22342 11084 22343 11083 22343 8934 22343 11084 22344 8934 22344 11085 22344 11085 22345 8934 22345 8840 22345 11085 22346 8840 22346 11086 22346 11086 22347 8840 22347 8839 22347 11086 22348 8839 22348 11087 22348 11087 22349 8839 22349 11088 22349 11087 22350 11088 22350 11089 22350 11089 22351 11088 22351 8838 22351 11089 22352 8838 22352 11090 22352 11090 22353 8838 22353 8835 22353 11090 22354 8835 22354 11091 22354 11091 22355 8835 22355 8833 22355 11091 22356 8833 22356 11092 22356 11092 22357 8833 22357 8832 22357 11092 22358 8832 22358 11079 22358 11079 22359 8832 22359 8771 22359 11096 22360 11093 22360 11095 22360 11094 22361 11093 22361 11096 22361 11096 22362 11102 22362 11097 22362 11100 22363 11102 22363 11096 22363 11095 22364 11100 22364 11096 22364 11096 22365 11105 22365 11107 22365 11098 22366 11105 22366 11096 22366 11097 22367 11098 22367 11096 22367 11096 22368 11110 22368 11112 22368 11099 22369 11110 22369 11096 22369 11107 22370 11099 22370 11096 22370 11112 22371 11094 22371 11096 22371 11094 22372 8768 22372 11093 22372 11093 22373 8768 22373 8769 22373 11093 22374 8769 22374 11095 22374 11095 22375 8769 22375 11101 22375 11095 22376 11101 22376 11100 22376 11100 22377 11101 22377 11103 22377 11100 22378 11103 22378 11102 22378 11102 22379 11103 22379 11104 22379 11102 22380 11104 22380 11097 22380 11097 22381 11104 22381 8831 22381 11097 22382 8831 22382 11098 22382 11098 22383 8831 22383 8830 22383 11098 22384 8830 22384 11105 22384 11105 22385 8830 22385 11106 22385 11105 22386 11106 22386 11107 22386 11107 22387 11106 22387 11108 22387 11107 22388 11108 22388 11099 22388 11099 22389 11108 22389 11109 22389 11099 22390 11109 22390 11110 22390 11110 22391 11109 22391 8767 22391 11110 22392 8767 22392 11112 22392 11112 22393 8767 22393 11111 22393 11112 22394 11111 22394 11094 22394 11094 22395 11111 22395 8768 22395 11115 22396 11116 22396 11118 22396 11132 22397 11116 22397 11115 22397 11115 22398 11113 22398 11120 22398 11114 22399 11113 22399 11115 22399 11118 22400 11114 22400 11115 22400 11115 22401 11124 22401 11125 22401 11123 22402 11124 22402 11115 22402 11120 22403 11123 22403 11115 22403 11115 22404 11128 22404 11130 22404 11126 22405 11128 22405 11115 22405 11125 22406 11126 22406 11115 22406 11130 22407 11132 22407 11115 22407 11132 22408 11117 22408 11116 22408 11116 22409 11117 22409 8765 22409 11116 22410 8765 22410 11118 22410 11118 22411 8765 22411 11119 22411 11118 22412 11119 22412 11114 22412 11114 22413 11119 22413 8764 22413 11114 22414 8764 22414 11113 22414 11113 22415 8764 22415 8763 22415 11113 22416 8763 22416 11120 22416 11120 22417 8763 22417 11121 22417 11120 22418 11121 22418 11123 22418 11123 22419 11121 22419 11122 22419 11123 22420 11122 22420 11124 22420 11124 22421 11122 22421 8762 22421 11124 22422 8762 22422 11125 22422 11125 22423 8762 22423 8761 22423 11125 22424 8761 22424 11126 22424 11126 22425 8761 22425 11127 22425 11126 22426 11127 22426 11128 22426 11128 22427 11127 22427 11129 22427 11128 22428 11129 22428 11130 22428 11130 22429 11129 22429 11131 22429 11130 22430 11131 22430 11132 22430 11132 22431 11131 22431 11117 22431 11133 22432 11141 22432 11142 22432 11140 22433 11141 22433 11133 22433 11133 22434 11145 22434 11134 22434 11135 22435 11145 22435 11133 22435 11142 22436 11135 22436 11133 22436 11133 22437 11136 22437 11138 22437 11146 22438 11136 22438 11133 22438 11134 22439 11146 22439 11133 22439 11133 22440 11150 22440 11139 22440 11137 22441 11150 22441 11133 22441 11138 22442 11137 22442 11133 22442 11139 22443 11140 22443 11133 22443 11140 22444 8751 22444 11141 22444 11141 22445 8751 22445 11143 22445 11141 22446 11143 22446 11142 22446 11142 22447 11143 22447 11144 22447 11142 22448 11144 22448 11135 22448 11135 22449 11144 22449 8758 22449 11135 22450 8758 22450 11145 22450 11145 22451 8758 22451 8757 22451 11145 22452 8757 22452 11134 22452 11134 22453 8757 22453 11147 22453 11134 22454 11147 22454 11146 22454 11146 22455 11147 22455 8756 22455 11146 22456 8756 22456 11136 22456 11136 22457 8756 22457 11148 22457 11136 22458 11148 22458 11138 22458 11138 22459 11148 22459 11149 22459 11138 22460 11149 22460 11137 22460 11137 22461 11149 22461 8755 22461 11137 22462 8755 22462 11150 22462 11150 22463 8755 22463 11151 22463 11150 22464 11151 22464 11139 22464 11139 22465 11151 22465 11152 22465 11139 22466 11152 22466 11140 22466 11140 22467 11152 22467 8751 22467 11154 22468 11159 22468 11155 22468 11153 22469 11159 22469 11154 22469 11154 22470 11162 22470 11164 22470 11161 22471 11162 22471 11154 22471 11155 22472 11161 22472 11154 22472 11154 22473 11156 22473 11158 22473 11166 22474 11156 22474 11154 22474 11164 22475 11166 22475 11154 22475 11154 22476 11169 22476 11171 22476 11157 22477 11169 22477 11154 22477 11158 22478 11157 22478 11154 22478 11171 22479 11153 22479 11154 22479 11153 22480 8828 22480 11159 22480 11159 22481 8828 22481 11160 22481 11159 22482 11160 22482 11155 22482 11155 22483 11160 22483 8827 22483 11155 22484 8827 22484 11161 22484 11161 22485 8827 22485 8826 22485 11161 22486 8826 22486 11162 22486 11162 22487 8826 22487 11163 22487 11162 22488 11163 22488 11164 22488 11164 22489 11163 22489 11165 22489 11164 22490 11165 22490 11166 22490 11166 22491 11165 22491 8824 22491 11166 22492 8824 22492 11156 22492 11156 22493 8824 22493 11167 22493 11156 22494 11167 22494 11158 22494 11158 22495 11167 22495 11168 22495 11158 22496 11168 22496 11157 22496 11157 22497 11168 22497 11170 22497 11157 22498 11170 22498 11169 22498 11169 22499 11170 22499 11172 22499 11169 22500 11172 22500 11171 22500 11171 22501 11172 22501 11173 22501 11171 22502 11173 22502 11153 22502 11153 22503 11173 22503 8828 22503 11174 22504 11180 22504 11175 22504 11179 22505 11180 22505 11174 22505 11174 22506 11183 22506 11184 22506 11182 22507 11183 22507 11174 22507 11175 22508 11182 22508 11174 22508 11174 22509 11176 22509 11189 22509 11187 22510 11176 22510 11174 22510 11184 22511 11187 22511 11174 22511 11174 22512 11177 22512 11191 22512 11178 22513 11177 22513 11174 22513 11189 22514 11178 22514 11174 22514 11191 22515 11179 22515 11174 22515 11179 22516 8819 22516 11180 22516 11180 22517 8819 22517 8818 22517 11180 22518 8818 22518 11175 22518 11175 22519 8818 22519 11181 22519 11175 22520 11181 22520 11182 22520 11182 22521 11181 22521 8746 22521 11182 22522 8746 22522 11183 22522 11183 22523 8746 22523 8744 22523 11183 22524 8744 22524 11184 22524 11184 22525 8744 22525 11185 22525 11184 22526 11185 22526 11187 22526 11187 22527 11185 22527 11186 22527 11187 22528 11186 22528 11176 22528 11176 22529 11186 22529 11188 22529 11176 22530 11188 22530 11189 22530 11189 22531 11188 22531 11190 22531 11189 22532 11190 22532 11178 22532 11178 22533 11190 22533 8817 22533 11178 22534 8817 22534 11177 22534 11177 22535 8817 22535 8816 22535 11177 22536 8816 22536 11191 22536 11191 22537 8816 22537 8820 22537 11191 22538 8820 22538 11179 22538 11179 22539 8820 22539 8819 22539 11196 22540 11197 22540 11198 22540 11206 22541 11197 22541 11196 22541 11196 22542 11199 22542 11201 22542 11192 22543 11199 22543 11196 22543 11198 22544 11192 22544 11196 22544 11196 22545 11194 22545 11193 22545 11202 22546 11194 22546 11196 22546 11201 22547 11202 22547 11196 22547 11196 22548 11204 22548 11205 22548 11195 22549 11204 22549 11196 22549 11193 22550 11195 22550 11196 22550 11205 22551 11206 22551 11196 22551 11206 22552 8742 22552 11197 22552 11197 22553 8742 22553 8732 22553 11197 22554 8732 22554 11198 22554 11198 22555 8732 22555 8734 22555 11198 22556 8734 22556 11192 22556 11192 22557 8734 22557 8733 22557 11192 22558 8733 22558 11199 22558 11199 22559 8733 22559 11200 22559 11199 22560 11200 22560 11201 22560 11201 22561 11200 22561 8738 22561 11201 22562 8738 22562 11202 22562 11202 22563 8738 22563 8737 22563 11202 22564 8737 22564 11194 22564 11194 22565 8737 22565 11203 22565 11194 22566 11203 22566 11193 22566 11193 22567 11203 22567 8730 22567 11193 22568 8730 22568 11195 22568 11195 22569 8730 22569 8957 22569 11195 22570 8957 22570 11204 22570 11204 22571 8957 22571 8735 22571 11204 22572 8735 22572 11205 22572 11205 22573 8735 22573 11207 22573 11205 22574 11207 22574 11206 22574 11206 22575 11207 22575 8742 22575 11213 22576 11215 22576 11208 22576 11214 22577 11215 22577 11213 22577 11213 22578 11218 22578 11211 22578 11209 22579 11218 22579 11213 22579 11208 22580 11209 22580 11213 22580 11213 22581 11210 22581 11221 22581 11220 22582 11210 22582 11213 22582 11211 22583 11220 22583 11213 22583 11213 22584 11224 22584 11212 22584 11223 22585 11224 22585 11213 22585 11221 22586 11223 22586 11213 22586 11212 22587 11214 22587 11213 22587 11214 22588 8728 22588 11215 22588 11215 22589 8728 22589 8727 22589 11215 22590 8727 22590 11208 22590 11208 22591 8727 22591 11216 22591 11208 22592 11216 22592 11209 22592 11209 22593 11216 22593 11217 22593 11209 22594 11217 22594 11218 22594 11218 22595 11217 22595 8726 22595 11218 22596 8726 22596 11211 22596 11211 22597 8726 22597 8724 22597 11211 22598 8724 22598 11220 22598 11220 22599 8724 22599 11219 22599 11220 22600 11219 22600 11210 22600 11210 22601 11219 22601 8723 22601 11210 22602 8723 22602 11221 22602 11221 22603 8723 22603 11222 22603 11221 22604 11222 22604 11223 22604 11223 22605 11222 22605 8722 22605 11223 22606 8722 22606 11224 22606 11224 22607 8722 22607 8951 22607 11224 22608 8951 22608 11212 22608 11212 22609 8951 22609 8729 22609 11212 22610 8729 22610 11214 22610 11214 22611 8729 22611 8728 22611 11229 22612 11231 22612 11233 22612 11244 22613 11231 22613 11229 22613 11229 22614 11226 22614 11225 22614 11227 22615 11226 22615 11229 22615 11233 22616 11227 22616 11229 22616 11229 22617 11237 22617 11239 22617 11228 22618 11237 22618 11229 22618 11225 22619 11228 22619 11229 22619 11229 22620 11241 22620 11243 22620 11230 22621 11241 22621 11229 22621 11239 22622 11230 22622 11229 22622 11243 22623 11244 22623 11229 22623 11244 22624 8950 22624 11231 22624 11231 22625 8950 22625 11232 22625 11231 22626 11232 22626 11233 22626 11233 22627 11232 22627 11234 22627 11233 22628 11234 22628 11227 22628 11227 22629 11234 22629 11235 22629 11227 22630 11235 22630 11226 22630 11226 22631 11235 22631 11236 22631 11226 22632 11236 22632 11225 22632 11225 22633 11236 22633 8900 22633 11225 22634 8900 22634 11228 22634 11228 22635 8900 22635 8899 22635 11228 22636 8899 22636 11237 22636 11237 22637 8899 22637 11238 22637 11237 22638 11238 22638 11239 22638 11239 22639 11238 22639 11240 22639 11239 22640 11240 22640 11230 22640 11230 22641 11240 22641 8814 22641 11230 22642 8814 22642 11241 22642 11241 22643 8814 22643 11242 22643 11241 22644 11242 22644 11243 22644 11243 22645 11242 22645 8956 22645 11243 22646 8956 22646 11244 22646 11244 22647 8956 22647 8950 22647 11245 22648 11247 22648 11246 22648 11262 22649 11247 22649 11245 22649 11245 22650 11252 22650 11253 22650 11250 22651 11252 22651 11245 22651 11246 22652 11250 22652 11245 22652 11245 22653 11255 22653 11248 22653 11249 22654 11255 22654 11245 22654 11253 22655 11249 22655 11245 22655 11245 22656 11259 22656 11260 22656 11256 22657 11259 22657 11245 22657 11248 22658 11256 22658 11245 22658 11260 22659 11262 22659 11245 22659 11262 22660 8688 22660 11247 22660 11247 22661 8688 22661 8809 22661 11247 22662 8809 22662 11246 22662 11246 22663 8809 22663 8808 22663 11246 22664 8808 22664 11250 22664 11250 22665 8808 22665 11251 22665 11250 22666 11251 22666 11252 22666 11252 22667 11251 22667 8807 22667 11252 22668 8807 22668 11253 22668 11253 22669 8807 22669 11254 22669 11253 22670 11254 22670 11249 22670 11249 22671 11254 22671 8810 22671 11249 22672 8810 22672 11255 22672 11255 22673 8810 22673 8811 22673 11255 22674 8811 22674 11248 22674 11248 22675 8811 22675 11257 22675 11248 22676 11257 22676 11256 22676 11256 22677 11257 22677 8868 22677 11256 22678 8868 22678 11259 22678 11259 22679 8868 22679 11258 22679 11259 22680 11258 22680 11260 22680 11260 22681 11258 22681 11261 22681 11260 22682 11261 22682 11262 22682 11262 22683 11261 22683 8688 22683 11263 22684 11269 22684 11271 22684 11284 22685 11269 22685 11263 22685 11263 22686 11264 22686 11266 22686 11272 22687 11264 22687 11263 22687 11271 22688 11272 22688 11263 22688 11263 22689 11277 22689 11278 22689 11265 22690 11277 22690 11263 22690 11266 22691 11265 22691 11263 22691 11263 22692 11268 22692 11282 22692 11267 22693 11268 22693 11263 22693 11278 22694 11267 22694 11263 22694 11282 22695 11284 22695 11263 22695 11284 22696 11285 22696 11269 22696 11269 22697 11285 22697 11270 22697 11269 22698 11270 22698 11271 22698 11271 22699 11270 22699 11273 22699 11271 22700 11273 22700 11272 22700 11272 22701 11273 22701 11274 22701 11272 22702 11274 22702 11264 22702 11264 22703 11274 22703 11275 22703 11264 22704 11275 22704 11266 22704 11266 22705 11275 22705 8715 22705 11266 22706 8715 22706 11265 22706 11265 22707 8715 22707 11276 22707 11265 22708 11276 22708 11277 22708 11277 22709 11276 22709 11279 22709 11277 22710 11279 22710 11278 22710 11278 22711 11279 22711 11280 22711 11278 22712 11280 22712 11267 22712 11267 22713 11280 22713 8716 22713 11267 22714 8716 22714 11268 22714 11268 22715 8716 22715 11281 22715 11268 22716 11281 22716 11282 22716 11282 22717 11281 22717 11283 22717 11282 22718 11283 22718 11284 22718 11284 22719 11283 22719 11285 22719 11288 22720 11286 22720 11293 22720 11303 22721 11286 22721 11288 22721 11288 22722 11287 22722 11298 22722 11295 22723 11287 22723 11288 22723 11293 22724 11295 22724 11288 22724 11288 22725 11289 22725 11299 22725 11290 22726 11289 22726 11288 22726 11298 22727 11290 22727 11288 22727 11288 22728 11291 22728 11302 22728 11292 22729 11291 22729 11288 22729 11299 22730 11292 22730 11288 22730 11302 22731 11303 22731 11288 22731 11303 22732 8714 22732 11286 22732 11286 22733 8714 22733 11294 22733 11286 22734 11294 22734 11293 22734 11293 22735 11294 22735 8713 22735 11293 22736 8713 22736 11295 22736 11295 22737 8713 22737 8712 22737 11295 22738 8712 22738 11287 22738 11287 22739 8712 22739 11296 22739 11287 22740 11296 22740 11298 22740 11298 22741 11296 22741 11297 22741 11298 22742 11297 22742 11290 22742 11290 22743 11297 22743 8710 22743 11290 22744 8710 22744 11289 22744 11289 22745 8710 22745 8709 22745 11289 22746 8709 22746 11299 22746 11299 22747 8709 22747 11300 22747 11299 22748 11300 22748 11292 22748 11292 22749 11300 22749 11301 22749 11292 22750 11301 22750 11291 22750 11291 22751 11301 22751 8793 22751 11291 22752 8793 22752 11302 22752 11302 22753 8793 22753 11304 22753 11302 22754 11304 22754 11303 22754 11303 22755 11304 22755 8714 22755 11305 22756 11306 22756 11308 22756 11312 22757 11306 22757 11305 22757 11305 22758 11315 22758 11317 22758 11307 22759 11315 22759 11305 22759 11308 22760 11307 22760 11305 22760 11305 22761 11309 22761 11311 22761 11321 22762 11309 22762 11305 22762 11317 22763 11321 22763 11305 22763 11305 22764 11310 22764 11325 22764 11324 22765 11310 22765 11305 22765 11311 22766 11324 22766 11305 22766 11325 22767 11312 22767 11305 22767 11312 22768 11313 22768 11306 22768 11306 22769 11313 22769 8803 22769 11306 22770 8803 22770 11308 22770 11308 22771 8803 22771 11314 22771 11308 22772 11314 22772 11307 22772 11307 22773 11314 22773 11316 22773 11307 22774 11316 22774 11315 22774 11315 22775 11316 22775 11318 22775 11315 22776 11318 22776 11317 22776 11317 22777 11318 22777 11319 22777 11317 22778 11319 22778 11321 22778 11321 22779 11319 22779 11320 22779 11321 22780 11320 22780 11309 22780 11309 22781 11320 22781 11322 22781 11309 22782 11322 22782 11311 22782 11311 22783 11322 22783 8788 22783 11311 22784 8788 22784 11324 22784 11324 22785 8788 22785 11323 22785 11324 22786 11323 22786 11310 22786 11310 22787 11323 22787 8787 22787 11310 22788 8787 22788 11325 22788 11325 22789 8787 22789 8805 22789 11325 22790 8805 22790 11312 22790 11312 22791 8805 22791 11313 22791 11328 22792 11333 22792 11335 22792 11332 22793 11333 22793 11328 22793 11328 22794 11326 22794 11329 22794 11327 22795 11326 22795 11328 22795 11335 22796 11327 22796 11328 22796 11328 22797 11341 22797 11330 22797 11339 22798 11341 22798 11328 22798 11329 22799 11339 22799 11328 22799 11328 22800 11344 22800 11331 22800 11343 22801 11344 22801 11328 22801 11330 22802 11343 22802 11328 22802 11331 22803 11332 22803 11328 22803 11332 22804 8799 22804 11333 22804 11333 22805 8799 22805 11334 22805 11333 22806 11334 22806 11335 22806 11335 22807 11334 22807 11336 22807 11335 22808 11336 22808 11327 22808 11327 22809 11336 22809 11337 22809 11327 22810 11337 22810 11326 22810 11326 22811 11337 22811 11338 22811 11326 22812 11338 22812 11329 22812 11329 22813 11338 22813 8798 22813 11329 22814 8798 22814 11339 22814 11339 22815 8798 22815 11340 22815 11339 22816 11340 22816 11341 22816 11341 22817 11340 22817 8795 22817 11341 22818 8795 22818 11330 22818 11330 22819 8795 22819 11342 22819 11330 22820 11342 22820 11343 22820 11343 22821 11342 22821 8802 22821 11343 22822 8802 22822 11344 22822 11344 22823 8802 22823 11345 22823 11344 22824 11345 22824 11331 22824 11331 22825 11345 22825 11346 22825 11331 22826 11346 22826 11332 22826 11332 22827 11346 22827 8799 22827 11353 22828 11347 22828 11351 22828 11348 22829 11347 22829 11353 22829 11353 22830 11350 22830 11349 22830 11358 22831 11350 22831 11353 22831 11351 22832 11358 22832 11353 22832 11353 22833 11352 22833 11364 22833 11362 22834 11352 22834 11353 22834 11349 22835 11362 22835 11353 22835 11353 22836 11354 22836 11366 22836 11355 22837 11354 22837 11353 22837 11364 22838 11355 22838 11353 22838 11366 22839 11348 22839 11353 22839 11348 22840 11356 22840 11347 22840 11347 22841 11356 22841 8783 22841 11347 22842 8783 22842 11351 22842 11351 22843 8783 22843 11357 22843 11351 22844 11357 22844 11358 22844 11358 22845 11357 22845 11359 22845 11358 22846 11359 22846 11350 22846 11350 22847 11359 22847 8782 22847 11350 22848 8782 22848 11349 22848 11349 22849 8782 22849 11360 22849 11349 22850 11360 22850 11362 22850 11362 22851 11360 22851 11361 22851 11362 22852 11361 22852 11352 22852 11352 22853 11361 22853 11363 22853 11352 22854 11363 22854 11364 22854 11364 22855 11363 22855 8778 22855 11364 22856 8778 22856 11355 22856 11355 22857 8778 22857 8779 22857 11355 22858 8779 22858 11354 22858 11354 22859 8779 22859 11365 22859 11354 22860 11365 22860 11366 22860 11366 22861 11365 22861 11367 22861 11366 22862 11367 22862 11348 22862 11348 22863 11367 22863 11356 22863 11368 22864 11373 22864 11375 22864 11372 22865 11373 22865 11368 22865 11368 22866 11378 22866 11369 22866 11377 22867 11378 22867 11368 22867 11375 22868 11377 22868 11368 22868 11368 22869 11381 22869 11384 22869 11380 22870 11381 22870 11368 22870 11369 22871 11380 22871 11368 22871 11368 22872 11370 22872 11371 22872 11385 22873 11370 22873 11368 22873 11384 22874 11385 22874 11368 22874 11371 22875 11372 22875 11368 22875 11372 22876 8777 22876 11373 22876 11373 22877 8777 22877 11374 22877 11373 22878 11374 22878 11375 22878 11375 22879 11374 22879 11376 22879 11375 22880 11376 22880 11377 22880 11377 22881 11376 22881 8776 22881 11377 22882 8776 22882 11378 22882 11378 22883 8776 22883 11379 22883 11378 22884 11379 22884 11369 22884 11369 22885 11379 22885 8775 22885 11369 22886 8775 22886 11380 22886 11380 22887 8775 22887 11382 22887 11380 22888 11382 22888 11381 22888 11381 22889 11382 22889 11383 22889 11381 22890 11383 22890 11384 22890 11384 22891 11383 22891 8774 22891 11384 22892 8774 22892 11385 22892 11385 22893 8774 22893 11386 22893 11385 22894 11386 22894 11370 22894 11370 22895 11386 22895 11387 22895 11370 22896 11387 22896 11371 22896 11371 22897 11387 22897 11388 22897 11371 22898 11388 22898 11372 22898 11372 22899 11388 22899 8777 22899 11398 22900 11400 22900 11389 22900 11389 22901 11400 22901 10587 22901 11389 22902 10587 22902 11390 22902 11390 22903 10587 22903 10572 22903 11390 22904 10572 22904 11419 22904 11419 22905 10572 22905 10573 22905 11419 22906 10573 22906 11418 22906 11418 22907 10573 22907 10581 22907 11418 22908 10581 22908 11425 22908 11425 22909 10581 22909 10582 22909 11425 22910 10582 22910 11391 22910 11391 22911 10582 22911 11392 22911 11391 22912 11392 22912 11424 22912 11424 22913 11392 22913 10595 22913 11424 22914 10595 22914 11393 22914 11393 22915 10595 22915 10596 22915 11393 22916 10596 22916 11394 22916 11394 22917 10596 22917 11395 22917 11394 22918 11395 22918 11421 22918 11421 22919 11395 22919 11397 22919 11421 22920 11397 22920 11396 22920 11396 22921 11397 22921 11399 22921 11396 22922 11399 22922 11398 22922 11398 22923 11399 22923 11400 22923 11401 22924 8326 22924 11402 22924 11402 22925 8326 22925 8327 22925 11402 22926 8327 22926 6733 22926 6733 22927 8327 22927 8330 22927 6733 22928 8330 22928 11403 22928 11409 22929 11404 22929 6472 22929 11406 22930 6475 22930 11404 22930 11404 22931 6475 22931 6474 22931 11404 22932 6474 22932 6472 22932 6468 22933 11405 22933 11407 22933 11407 22934 11405 22934 6469 22934 11407 22935 6469 22935 11406 22935 11406 22936 6469 22936 6476 22936 11406 22937 6476 22937 6475 22937 6468 22938 11407 22938 6463 22938 6463 22939 11407 22939 8319 22939 6463 22940 8319 22940 6465 22940 6465 22941 8319 22941 11408 22941 11408 22942 8319 22942 8297 22942 11408 22943 8297 22943 6556 22943 6472 22944 6470 22944 11409 22944 11409 22945 6470 22945 6461 22945 11409 22946 6461 22946 11410 22946 11410 22947 6461 22947 11411 22947 11410 22948 11411 22948 8320 22948 8320 22949 11411 22949 11412 22949 11414 22950 11415 22950 8329 22950 8329 22951 11415 22951 11413 22951 8329 22952 11413 22952 6419 22952 11416 22953 6418 22953 6417 22953 6417 22954 6444 22954 11416 22954 11416 22955 6444 22955 6436 22955 11416 22956 6436 22956 11414 22956 11414 22957 6436 22957 6420 22957 11414 22958 6420 22958 11415 22958 6418 22959 11416 22959 11417 22959 11417 22960 11416 22960 8325 22960 11417 22961 8325 22961 6391 22961 11425 22962 9272 22962 11418 22962 11418 22963 9272 22963 9275 22963 11418 22964 9275 22964 11419 22964 11419 22965 9275 22965 9277 22965 11419 22966 9277 22966 11390 22966 11390 22967 9277 22967 9279 22967 11390 22968 9279 22968 11389 22968 11389 22969 9279 22969 9281 22969 11389 22970 9281 22970 11398 22970 11398 22971 9281 22971 11420 22971 11398 22972 11420 22972 11396 22972 11396 22973 11420 22973 9283 22973 11396 22974 9283 22974 11421 22974 11421 22975 9283 22975 9286 22975 11421 22976 9286 22976 11394 22976 11394 22977 9286 22977 11422 22977 11394 22978 11422 22978 11393 22978 11393 22979 11422 22979 11423 22979 11393 22980 11423 22980 11424 22980 11424 22981 11423 22981 9265 22981 11424 22982 9265 22982 11391 22982 11391 22983 9265 22983 9269 22983 11391 22984 9269 22984 11425 22984 11425 22985 9269 22985 9272 22985 11426 22986 8461 22986 11427 22986 11427 22987 8461 22987 11428 22987 11427 22988 11428 22988 10803 22988 10803 22989 11428 22989 11429 22989 10803 22990 11429 22990 11430 22990 11430 22991 11429 22991 8457 22991 11430 22992 8457 22992 11431 22992 11431 22993 8457 22993 8456 22993 11431 22994 8456 22994 11432 22994 11432 22995 8456 22995 8455 22995 11432 22996 8455 22996 11433 22996 11433 22997 8455 22997 8452 22997 11433 22998 8452 22998 10808 22998 10808 22999 8452 22999 8450 22999 10808 23000 8450 23000 11434 23000 11434 23001 8450 23001 11435 23001 11434 23002 11435 23002 11436 23002 11436 23003 11435 23003 8466 23003 11436 23004 8466 23004 11437 23004 11437 23005 8466 23005 8464 23005 11437 23006 8464 23006 10810 23006 10810 23007 8464 23007 8462 23007 10810 23008 8462 23008 11426 23008 11426 23009 8462 23009 8461 23009 11451 23010 8472 23010 11438 23010 11438 23011 8472 23011 11439 23011 11438 23012 11439 23012 10788 23012 10788 23013 11439 23013 11441 23013 10788 23014 11441 23014 11440 23014 11440 23015 11441 23015 11443 23015 11440 23016 11443 23016 11442 23016 11442 23017 11443 23017 11444 23017 11442 23018 11444 23018 10792 23018 10792 23019 11444 23019 11445 23019 10792 23020 11445 23020 10793 23020 10793 23021 11445 23021 11446 23021 10793 23022 11446 23022 10794 23022 10794 23023 11446 23023 11448 23023 10794 23024 11448 23024 11447 23024 11447 23025 11448 23025 8475 23025 11447 23026 8475 23026 10798 23026 10798 23027 8475 23027 8474 23027 10798 23028 8474 23028 10799 23028 10799 23029 8474 23029 11449 23029 10799 23030 11449 23030 10800 23030 10800 23031 11449 23031 11450 23031 10800 23032 11450 23032 11451 23032 11451 23033 11450 23033 8472 23033 11452 23034 8483 23034 10771 23034 10771 23035 8483 23035 8481 23035 10771 23036 8481 23036 10772 23036 10772 23037 8481 23037 8480 23037 10772 23038 8480 23038 10773 23038 10773 23039 8480 23039 11453 23039 10773 23040 11453 23040 10775 23040 10775 23041 11453 23041 8478 23041 10775 23042 8478 23042 10777 23042 10777 23043 8478 23043 11454 23043 10777 23044 11454 23044 10779 23044 10779 23045 11454 23045 11455 23045 10779 23046 11455 23046 10781 23046 10781 23047 11455 23047 8476 23047 10781 23048 8476 23048 11456 23048 11456 23049 8476 23049 11457 23049 11456 23050 11457 23050 10782 23050 10782 23051 11457 23051 8487 23051 10782 23052 8487 23052 10783 23052 10783 23053 8487 23053 8486 23053 10783 23054 8486 23054 10785 23054 10785 23055 8486 23055 11458 23055 10785 23056 11458 23056 11452 23056 11452 23057 11458 23057 8483 23057 10824 23058 11459 23058 10813 23058 10813 23059 11459 23059 11460 23059 10813 23060 11460 23060 11461 23060 11461 23061 11460 23061 11462 23061 11461 23062 11462 23062 10815 23062 10815 23063 11462 23063 11463 23063 10815 23064 11463 23064 11464 23064 11464 23065 11463 23065 8441 23065 11464 23066 8441 23066 10816 23066 10816 23067 8441 23067 8439 23067 10816 23068 8439 23068 10818 23068 10818 23069 8439 23069 8438 23069 10818 23070 8438 23070 10819 23070 10819 23071 8438 23071 8436 23071 10819 23072 8436 23072 11465 23072 11465 23073 8436 23073 8434 23073 11465 23074 8434 23074 10820 23074 10820 23075 8434 23075 11466 23075 10820 23076 11466 23076 10822 23076 10822 23077 11466 23077 11467 23077 10822 23078 11467 23078 10823 23078 10823 23079 11467 23079 8447 23079 10823 23080 8447 23080 10824 23080 10824 23081 8447 23081 11459 23081 10841 23082 11478 23082 11468 23082 11468 23083 11478 23083 10289 23083 11468 23084 10289 23084 11469 23084 11469 23085 10289 23085 11470 23085 11469 23086 11470 23086 10844 23086 10844 23087 11470 23087 10286 23087 10844 23088 10286 23088 10846 23088 10846 23089 10286 23089 10285 23089 10846 23090 10285 23090 11471 23090 11471 23091 10285 23091 11472 23091 11471 23092 11472 23092 11473 23092 11473 23093 11472 23093 10283 23093 11473 23094 10283 23094 10848 23094 10848 23095 10283 23095 10282 23095 10848 23096 10282 23096 10850 23096 10850 23097 10282 23097 11474 23097 10850 23098 11474 23098 10852 23098 10852 23099 11474 23099 10281 23099 10852 23100 10281 23100 11475 23100 11475 23101 10281 23101 11476 23101 11475 23102 11476 23102 10840 23102 10840 23103 11476 23103 11477 23103 10840 23104 11477 23104 10841 23104 10841 23105 11477 23105 11478 23105 10866 23106 11479 23106 10868 23106 10868 23107 11479 23107 11480 23107 10868 23108 11480 23108 11481 23108 11481 23109 11480 23109 11483 23109 11481 23110 11483 23110 11482 23110 11482 23111 11483 23111 10263 23111 11482 23112 10263 23112 11484 23112 11484 23113 10263 23113 10264 23113 11484 23114 10264 23114 10872 23114 10872 23115 10264 23115 10266 23115 10872 23116 10266 23116 10873 23116 10873 23117 10266 23117 10268 23117 10873 23118 10268 23118 11485 23118 11485 23119 10268 23119 10269 23119 11485 23120 10269 23120 11486 23120 11486 23121 10269 23121 11487 23121 11486 23122 11487 23122 11488 23122 11488 23123 11487 23123 10261 23123 11488 23124 10261 23124 10876 23124 10876 23125 10261 23125 10260 23125 10876 23126 10260 23126 10865 23126 10865 23127 10260 23127 10259 23127 10865 23128 10259 23128 10866 23128 10866 23129 10259 23129 11479 23129 11489 23130 10199 23130 11490 23130 11490 23131 10199 23131 11491 23131 11490 23132 11491 23132 11492 23132 11492 23133 11491 23133 11493 23133 11492 23134 11493 23134 10912 23134 10912 23135 11493 23135 10190 23135 10912 23136 10190 23136 10914 23136 10914 23137 10190 23137 11495 23137 10914 23138 11495 23138 11494 23138 11494 23139 11495 23139 11496 23139 11494 23140 11496 23140 11497 23140 11497 23141 11496 23141 10202 23141 11497 23142 10202 23142 10916 23142 10916 23143 10202 23143 10203 23143 10916 23144 10203 23144 11498 23144 11498 23145 10203 23145 10194 23145 11498 23146 10194 23146 11499 23146 11499 23147 10194 23147 11500 23147 11499 23148 11500 23148 10918 23148 10918 23149 11500 23149 10196 23149 10918 23150 10196 23150 11501 23150 11501 23151 10196 23151 10197 23151 11501 23152 10197 23152 11489 23152 11489 23153 10197 23153 10199 23153 10855 23154 10183 23154 11502 23154 11502 23155 10183 23155 10182 23155 11502 23156 10182 23156 11503 23156 11503 23157 10182 23157 10180 23157 11503 23158 10180 23158 11504 23158 11504 23159 10180 23159 10171 23159 11504 23160 10171 23160 11505 23160 11505 23161 10171 23161 11506 23161 11505 23162 11506 23162 11508 23162 11508 23163 11506 23163 11507 23163 11508 23164 11507 23164 11509 23164 11509 23165 11507 23165 11510 23165 11509 23166 11510 23166 10861 23166 10861 23167 11510 23167 11511 23167 10861 23168 11511 23168 11513 23168 11513 23169 11511 23169 11512 23169 11513 23170 11512 23170 11514 23170 11514 23171 11512 23171 11515 23171 11514 23172 11515 23172 11516 23172 11516 23173 11515 23173 10184 23173 11516 23174 10184 23174 10864 23174 10864 23175 10184 23175 11517 23175 10864 23176 11517 23176 10855 23176 10855 23177 11517 23177 10183 23177 10900 23178 11518 23178 10901 23178 10901 23179 11518 23179 10302 23179 10901 23180 10302 23180 10903 23180 10903 23181 10302 23181 10301 23181 10903 23182 10301 23182 11519 23182 11519 23183 10301 23183 10299 23183 11519 23184 10299 23184 10905 23184 10905 23185 10299 23185 11520 23185 10905 23186 11520 23186 11521 23186 11521 23187 11520 23187 11522 23187 11521 23188 11522 23188 11523 23188 11523 23189 11522 23189 10295 23189 11523 23190 10295 23190 10906 23190 10906 23191 10295 23191 11525 23191 10906 23192 11525 23192 11524 23192 11524 23193 11525 23193 11526 23193 11524 23194 11526 23194 11528 23194 11528 23195 11526 23195 11527 23195 11528 23196 11527 23196 10908 23196 10908 23197 11527 23197 11529 23197 10908 23198 11529 23198 10897 23198 10897 23199 11529 23199 10294 23199 10897 23200 10294 23200 10900 23200 10900 23201 10294 23201 11518 23201 11543 23202 11530 23202 11531 23202 11531 23203 11530 23203 11532 23203 11531 23204 11532 23204 11533 23204 11533 23205 11532 23205 10320 23205 11533 23206 10320 23206 11534 23206 11534 23207 10320 23207 10317 23207 11534 23208 10317 23208 11535 23208 11535 23209 10317 23209 10315 23209 11535 23210 10315 23210 11536 23210 11536 23211 10315 23211 10314 23211 11536 23212 10314 23212 11537 23212 11537 23213 10314 23213 11538 23213 11537 23214 11538 23214 11539 23214 11539 23215 11538 23215 10312 23215 11539 23216 10312 23216 10882 23216 10882 23217 10312 23217 11540 23217 10882 23218 11540 23218 10884 23218 10884 23219 11540 23219 11541 23219 10884 23220 11541 23220 10885 23220 10885 23221 11541 23221 10310 23221 10885 23222 10310 23222 10877 23222 10877 23223 10310 23223 11542 23223 10877 23224 11542 23224 11543 23224 11543 23225 11542 23225 11530 23225 11544 23226 10154 23226 10827 23226 10827 23227 10154 23227 11545 23227 10827 23228 11545 23228 10828 23228 10828 23229 11545 23229 11546 23229 10828 23230 11546 23230 10830 23230 10830 23231 11546 23231 10165 23231 10830 23232 10165 23232 10831 23232 10831 23233 10165 23233 11547 23233 10831 23234 11547 23234 10832 23234 10832 23235 11547 23235 10159 23235 10832 23236 10159 23236 11548 23236 11548 23237 10159 23237 10157 23237 11548 23238 10157 23238 10834 23238 10834 23239 10157 23239 10156 23239 10834 23240 10156 23240 10835 23240 10835 23241 10156 23241 10155 23241 10835 23242 10155 23242 11549 23242 11549 23243 10155 23243 11551 23243 11549 23244 11551 23244 11550 23244 11550 23245 11551 23245 10150 23245 11550 23246 10150 23246 10825 23246 10825 23247 10150 23247 10153 23247 10825 23248 10153 23248 11544 23248 11544 23249 10153 23249 10154 23249 11567 23250 10146 23250 10890 23250 10890 23251 10146 23251 10147 23251 10890 23252 10147 23252 11552 23252 11552 23253 10147 23253 11553 23253 11552 23254 11553 23254 11554 23254 11554 23255 11553 23255 11555 23255 11554 23256 11555 23256 11556 23256 11556 23257 11555 23257 10148 23257 11556 23258 10148 23258 11557 23258 11557 23259 10148 23259 11558 23259 11557 23260 11558 23260 11559 23260 11559 23261 11558 23261 10149 23261 11559 23262 10149 23262 11560 23262 11560 23263 10149 23263 11561 23263 11560 23264 11561 23264 10896 23264 10896 23265 11561 23265 10141 23265 10896 23266 10141 23266 11562 23266 11562 23267 10141 23267 11563 23267 11562 23268 11563 23268 11564 23268 11564 23269 11563 23269 10143 23269 11564 23270 10143 23270 11565 23270 11565 23271 10143 23271 11566 23271 11565 23272 11566 23272 11567 23272 11567 23273 11566 23273 10146 23273 11568 23274 11569 23274 7702 23274 7702 23275 11569 23275 11573 23275 11570 23276 11572 23276 11571 23276 11571 23277 11572 23277 7704 23277 11571 23278 7704 23278 11573 23278 11573 23279 7704 23279 7703 23279 11573 23280 7703 23280 7702 23280 11569 23281 7701 23281 11573 23281 11573 23282 7701 23282 7699 23282 11573 23283 7699 23283 11571 23283 11571 23284 7699 23284 7697 23284 11571 23285 7697 23285 11570 23285 11570 23286 7697 23286 7696 23286 8651 23287 11574 23287 11575 23287 11575 23288 11574 23288 10375 23288 11575 23289 10375 23289 7692 23289 11599 23290 11587 23290 11576 23290 11582 23291 7686 23291 7685 23291 11577 23292 10213 23292 11579 23292 11591 23293 10214 23293 10213 23293 10215 23294 10214 23294 11578 23294 11578 23295 10214 23295 11591 23295 11578 23296 11591 23296 7690 23296 11579 23297 10216 23297 11592 23297 11592 23298 10216 23298 11580 23298 11592 23299 11580 23299 11583 23299 11580 23300 11581 23300 11583 23300 11583 23301 11581 23301 11582 23301 11583 23302 11582 23302 11585 23302 11585 23303 11582 23303 7685 23303 11585 23304 7685 23304 11586 23304 11594 23305 11592 23305 11589 23305 11589 23306 11592 23306 11583 23306 11589 23307 11583 23307 11584 23307 11584 23308 11583 23308 11585 23308 11584 23309 11585 23309 11588 23309 11588 23310 11585 23310 11586 23310 11586 23311 11587 23311 11588 23311 11588 23312 11587 23312 11599 23312 11588 23313 11599 23313 11584 23313 11584 23314 11599 23314 11601 23314 11584 23315 11601 23315 11589 23315 11589 23316 11601 23316 11590 23316 11589 23317 11590 23317 11594 23317 11594 23318 11590 23318 11595 23318 10213 23319 11577 23319 11591 23319 11591 23320 11577 23320 11593 23320 11591 23321 11593 23321 7690 23321 7690 23322 11593 23322 11596 23322 7690 23323 11596 23323 7687 23323 7687 23324 11596 23324 11598 23324 7687 23325 11598 23325 8650 23325 11579 23326 11592 23326 11577 23326 11577 23327 11592 23327 11594 23327 11577 23328 11594 23328 11593 23328 11593 23329 11594 23329 11595 23329 11593 23330 11595 23330 11596 23330 11596 23331 11595 23331 11597 23331 11596 23332 11597 23332 11598 23332 11576 23333 10689 23333 11599 23333 11599 23334 10689 23334 11600 23334 11599 23335 11600 23335 11601 23335 11601 23336 11600 23336 10691 23336 11601 23337 10691 23337 11590 23337 11590 23338 10691 23338 11602 23338 11590 23339 11602 23339 11595 23339 11595 23340 11602 23340 10694 23340 11595 23341 10694 23341 11597 23341 8653 23342 11607 23342 7606 23342 7606 23343 11607 23343 11608 23343 7606 23344 11608 23344 11603 23344 11603 23345 11608 23345 11610 23345 11603 23346 11610 23346 11604 23346 11604 23347 11610 23347 11611 23347 11604 23348 11611 23348 11605 23348 11605 23349 11611 23349 11606 23349 11605 23350 11606 23350 7605 23350 11607 23351 11609 23351 11608 23351 11608 23352 11609 23352 11613 23352 11608 23353 11613 23353 11610 23353 11610 23354 11613 23354 11615 23354 11610 23355 11615 23355 11611 23355 11611 23356 11615 23356 11612 23356 11611 23357 11612 23357 11606 23357 11606 23358 11612 23358 11616 23358 11609 23359 10698 23359 11613 23359 11613 23360 10698 23360 7676 23360 11613 23361 7676 23361 11615 23361 11615 23362 7676 23362 11614 23362 11615 23363 11614 23363 11612 23363 11612 23364 11614 23364 11617 23364 11612 23365 11617 23365 11616 23365 11616 23366 11617 23366 7675 23366 7582 23367 11618 23367 11621 23367 11629 23368 7583 23368 11620 23368 11620 23369 7583 23369 7582 23369 10273 23370 11619 23370 11632 23370 11632 23371 11619 23371 11629 23371 7582 23372 11621 23372 11620 23372 11620 23373 11621 23373 11622 23373 11620 23374 11622 23374 11623 23374 11623 23375 11622 23375 6368 23375 11623 23376 6368 23376 11631 23376 11631 23377 6368 23377 6369 23377 11631 23378 6369 23378 11624 23378 11624 23379 6369 23379 6370 23379 11624 23380 6370 23380 11625 23380 11625 23381 6370 23381 11626 23381 11625 23382 11626 23382 11627 23382 11627 23383 11626 23383 7601 23383 11627 23384 7601 23384 11628 23384 11629 23385 11620 23385 11632 23385 11632 23386 11620 23386 11623 23386 11632 23387 11623 23387 11630 23387 11630 23388 11623 23388 11631 23388 11630 23389 11631 23389 11634 23389 11634 23390 11631 23390 11624 23390 11634 23391 11624 23391 11636 23391 11636 23392 11624 23392 11625 23392 11636 23393 11625 23393 11637 23393 11637 23394 11625 23394 11627 23394 11637 23395 11627 23395 11638 23395 11638 23396 11627 23396 11628 23396 11638 23397 11628 23397 11641 23397 10273 23398 11632 23398 11633 23398 11633 23399 11632 23399 11630 23399 11633 23400 11630 23400 10265 23400 10265 23401 11630 23401 11634 23401 10265 23402 11634 23402 11635 23402 11635 23403 11634 23403 11636 23403 11635 23404 11636 23404 10267 23404 10267 23405 11636 23405 11637 23405 10267 23406 11637 23406 11639 23406 11639 23407 11637 23407 11638 23407 11639 23408 11638 23408 11640 23408 11640 23409 11638 23409 11641 23409 11640 23410 11641 23410 10270 23410 11643 23411 11642 23411 8626 23411 7543 23412 7546 23412 11645 23412 11645 23413 7546 23413 11643 23413 7545 23414 7544 23414 11652 23414 11652 23415 7544 23415 7543 23415 11650 23416 7576 23416 11644 23416 11643 23417 8626 23417 11645 23417 11645 23418 8626 23418 11646 23418 11645 23419 11646 23419 11647 23419 11647 23420 11646 23420 11648 23420 11647 23421 11648 23421 11653 23421 11653 23422 11648 23422 8629 23422 11653 23423 8629 23423 11649 23423 11649 23424 8629 23424 8632 23424 11649 23425 8632 23425 11654 23425 11654 23426 8632 23426 11650 23426 11654 23427 11650 23427 11651 23427 11651 23428 11650 23428 11644 23428 11651 23429 11644 23429 11656 23429 7543 23430 11645 23430 11652 23430 11652 23431 11645 23431 11647 23431 11652 23432 11647 23432 11658 23432 11658 23433 11647 23433 11653 23433 11658 23434 11653 23434 11659 23434 11659 23435 11653 23435 11649 23435 11659 23436 11649 23436 11660 23436 11660 23437 11649 23437 11654 23437 11660 23438 11654 23438 11655 23438 11655 23439 11654 23439 11651 23439 11655 23440 11651 23440 11661 23440 11661 23441 11651 23441 11656 23441 11661 23442 11656 23442 7569 23442 7545 23443 11652 23443 11657 23443 11657 23444 11652 23444 11658 23444 11657 23445 11658 23445 10287 23445 10287 23446 11658 23446 11659 23446 10287 23447 11659 23447 10284 23447 10284 23448 11659 23448 11660 23448 10284 23449 11660 23449 10139 23449 10139 23450 11660 23450 11655 23450 10139 23451 11655 23451 10138 23451 10138 23452 11655 23452 11661 23452 10138 23453 11661 23453 11662 23453 11662 23454 11661 23454 7569 23454 11662 23455 7569 23455 10280 23455 11665 23456 7518 23456 8617 23456 11663 23457 11664 23457 11667 23457 11667 23458 11664 23458 11665 23458 7512 23459 11666 23459 11676 23459 11676 23460 11666 23460 11663 23460 8624 23461 8254 23461 7539 23461 11665 23462 8617 23462 11667 23462 11667 23463 8617 23463 11668 23463 11667 23464 11668 23464 11669 23464 11669 23465 11668 23465 8620 23465 11669 23466 8620 23466 11670 23466 11670 23467 8620 23467 11671 23467 11670 23468 11671 23468 11672 23468 11672 23469 11671 23469 8622 23469 11672 23470 8622 23470 11673 23470 11673 23471 8622 23471 8624 23471 11673 23472 8624 23472 11674 23472 11674 23473 8624 23473 7539 23473 11674 23474 7539 23474 11675 23474 11663 23475 11667 23475 11676 23475 11676 23476 11667 23476 11669 23476 11676 23477 11669 23477 11677 23477 11677 23478 11669 23478 11670 23478 11677 23479 11670 23479 11682 23479 11682 23480 11670 23480 11672 23480 11682 23481 11672 23481 11678 23481 11678 23482 11672 23482 11673 23482 11678 23483 11673 23483 11679 23483 11679 23484 11673 23484 11674 23484 11679 23485 11674 23485 11680 23485 11680 23486 11674 23486 11675 23486 11680 23487 11675 23487 7526 23487 7512 23488 11676 23488 10303 23488 10303 23489 11676 23489 11677 23489 10303 23490 11677 23490 11681 23490 11681 23491 11677 23491 11682 23491 11681 23492 11682 23492 10298 23492 10298 23493 11682 23493 11678 23493 10298 23494 11678 23494 10297 23494 10297 23495 11678 23495 11679 23495 10297 23496 11679 23496 10296 23496 10296 23497 11679 23497 11680 23497 10296 23498 11680 23498 11683 23498 11683 23499 11680 23499 7526 23499 11683 23500 7526 23500 7524 23500 11695 23501 11686 23501 11684 23501 11686 23502 11694 23502 11685 23502 11686 23503 11685 23503 11684 23503 11684 23504 11685 23504 8613 23504 11684 23505 8613 23505 11687 23505 11687 23506 8613 23506 8614 23506 11687 23507 8614 23507 7490 23507 11695 23508 11684 23508 11697 23508 11697 23509 11684 23509 11687 23509 11697 23510 11687 23510 11698 23510 11698 23511 11687 23511 7490 23511 11698 23512 7490 23512 7482 23512 8265 23513 8608 23513 11688 23513 11688 23514 8608 23514 11689 23514 11688 23515 11689 23515 7471 23515 7471 23516 11689 23516 11690 23516 7471 23517 11690 23517 10318 23517 10318 23518 11690 23518 10316 23518 8608 23519 11692 23519 11689 23519 11689 23520 11692 23520 11693 23520 11689 23521 11693 23521 11690 23521 11690 23522 11693 23522 11691 23522 11690 23523 11691 23523 10316 23523 10316 23524 11691 23524 11696 23524 11692 23525 11694 23525 11693 23525 11693 23526 11694 23526 11686 23526 11693 23527 11686 23527 11691 23527 11691 23528 11686 23528 11695 23528 11691 23529 11695 23529 11696 23529 11696 23530 11695 23530 10137 23530 10137 23531 11695 23531 10313 23531 10313 23532 11695 23532 11697 23532 10313 23533 11697 23533 11699 23533 11699 23534 11697 23534 11698 23534 11699 23535 11698 23535 11700 23535 11700 23536 11698 23536 7482 23536 11700 23537 7482 23537 10311 23537 11702 23538 8500 23538 10528 23538 10528 23539 11701 23539 11702 23539 11702 23540 11701 23540 11704 23540 11702 23541 11704 23541 11703 23541 11703 23542 11704 23542 10539 23542 11703 23543 10539 23543 7136 23543 11705 23544 11706 23544 10539 23544 10539 23545 11706 23545 11707 23545 10539 23546 11707 23546 7136 23546 11709 23547 11771 23547 11708 23547 11708 23548 11771 23548 10656 23548 11714 23549 11711 23549 8812 23549 8812 23550 11711 23550 10645 23550 8812 23551 10645 23551 8898 23551 11708 23552 10650 23552 11709 23552 11709 23553 10650 23553 10652 23553 11709 23554 10652 23554 8695 23554 8695 23555 10652 23555 11710 23555 8695 23556 11710 23556 11712 23556 11712 23557 11710 23557 11711 23557 11712 23558 11711 23558 11713 23558 11713 23559 11711 23559 11714 23559 11720 23560 11715 23560 11716 23560 11716 23561 11715 23561 8721 23561 11716 23562 8721 23562 11717 23562 8721 23563 11718 23563 11717 23563 11717 23564 11718 23564 8697 23564 11717 23565 8697 23565 10645 23565 10645 23566 8697 23566 11719 23566 10645 23567 11719 23567 8898 23567 10636 23568 8718 23568 8700 23568 10636 23569 8700 23569 11716 23569 11716 23570 8700 23570 8698 23570 11716 23571 8698 23571 11720 23571 8718 23572 10636 23572 11721 23572 11721 23573 10636 23573 10637 23573 11721 23574 10637 23574 8717 23574 8717 23575 10637 23575 10639 23575 8717 23576 10639 23576 8711 23576 10639 23577 10633 23577 8711 23577 8711 23578 10633 23578 11723 23578 8711 23579 11723 23579 11722 23579 11722 23580 11723 23580 11724 23580 11722 23581 11724 23581 8791 23581 8791 23582 11724 23582 10629 23582 8791 23583 10629 23583 11725 23583 8789 23584 11726 23584 11727 23584 11727 23585 11726 23585 11735 23585 11727 23586 11735 23586 8804 23586 8789 23587 11728 23587 11726 23587 11726 23588 11728 23588 11729 23588 11726 23589 11729 23589 11730 23589 11730 23590 11729 23590 11731 23590 11730 23591 11731 23591 11732 23591 11732 23592 11731 23592 11725 23592 11732 23593 11725 23593 10630 23593 10630 23594 11725 23594 10629 23594 11739 23595 8784 23595 11733 23595 11733 23596 8784 23596 8689 23596 11733 23597 8689 23597 11734 23597 11734 23598 8689 23598 8785 23598 11734 23599 8785 23599 11735 23599 11735 23600 8785 23600 8786 23600 11735 23601 8786 23601 8804 23601 10625 23602 11736 23602 8781 23602 10625 23603 8781 23603 10623 23603 10623 23604 8781 23604 11737 23604 10623 23605 11737 23605 11733 23605 11733 23606 11737 23606 11738 23606 11733 23607 11738 23607 11739 23607 11736 23608 10625 23608 11740 23608 11740 23609 10625 23609 10627 23609 11740 23610 10627 23610 11741 23610 11741 23611 10627 23611 10619 23611 11741 23612 10619 23612 8690 23612 8690 23613 10619 23613 10683 23613 8690 23614 10683 23614 11742 23614 11742 23615 10683 23615 11743 23615 11742 23616 11743 23616 11744 23616 11744 23617 11743 23617 11745 23617 11745 23618 11743 23618 11746 23618 11745 23619 11746 23619 8854 23619 10688 23620 8770 23620 11747 23620 11747 23621 8770 23621 11748 23621 11747 23622 11748 23622 10686 23622 10686 23623 11748 23623 8691 23623 11746 23624 10685 23624 8854 23624 8854 23625 10685 23625 11749 23625 8854 23626 11749 23626 11750 23626 11750 23627 11749 23627 10686 23627 11750 23628 10686 23628 8836 23628 8836 23629 10686 23629 8691 23629 11751 23630 10672 23630 11752 23630 11752 23631 10672 23631 11756 23631 11752 23632 11756 23632 8759 23632 11751 23633 11753 23633 10672 23633 10672 23634 11753 23634 11754 23634 10672 23635 11754 23635 10688 23635 10688 23636 11754 23636 11755 23636 10688 23637 11755 23637 8770 23637 8759 23638 11756 23638 8760 23638 8760 23639 11756 23639 10675 23639 8760 23640 10675 23640 8754 23640 10675 23641 11757 23641 8754 23641 8754 23642 11757 23642 11758 23642 8754 23643 11758 23643 8753 23643 8753 23644 11758 23644 11759 23644 8753 23645 11759 23645 11760 23645 11760 23646 11759 23646 10677 23646 11760 23647 10677 23647 11763 23647 11770 23648 11761 23648 10666 23648 10666 23649 11761 23649 8692 23649 10666 23650 8692 23650 11766 23650 10677 23651 11762 23651 11763 23651 11763 23652 11762 23652 10681 23652 11763 23653 10681 23653 11764 23653 11764 23654 10681 23654 10670 23654 11764 23655 10670 23655 11765 23655 11765 23656 10670 23656 11766 23656 11765 23657 11766 23657 8872 23657 8872 23658 11766 23658 8692 23658 8747 23659 8749 23659 11767 23659 11767 23660 8749 23660 8693 23660 11767 23661 8693 23661 11768 23661 11768 23662 8693 23662 8825 23662 11768 23663 8825 23663 10666 23663 10666 23664 8825 23664 11769 23664 10666 23665 11769 23665 11770 23665 8747 23666 11767 23666 8741 23666 8741 23667 11767 23667 10663 23667 8741 23668 10663 23668 8740 23668 10656 23669 11771 23669 10655 23669 10655 23670 11771 23670 8725 23670 10655 23671 8725 23671 11772 23671 11772 23672 8725 23672 8739 23672 11772 23673 8739 23673 11773 23673 11773 23674 8739 23674 8731 23674 11773 23675 8731 23675 10662 23675 10662 23676 8731 23676 8743 23676 10662 23677 8743 23677 10663 23677 10663 23678 8743 23678 8745 23678 10663 23679 8745 23679 8740 23679 11774 23680 10558 23680 11775 23680 11774 23681 11775 23681 10416 23681 10416 23682 11775 23682 6374 23682 10416 23683 6374 23683 6375 23683 10380 23684 10378 23684 11777 23684 10558 23685 11774 23685 10559 23685 10559 23686 11774 23686 10380 23686 10559 23687 10380 23687 10561 23687 10561 23688 10380 23688 11777 23688 11779 23689 11778 23689 11776 23689 11779 23690 11776 23690 10363 23690 10363 23691 11776 23691 11777 23691 10363 23692 11777 23692 10378 23692 10562 23693 11778 23693 11779 23693 11779 23694 10392 23694 10562 23694 10562 23695 10392 23695 10391 23695 10562 23696 10391 23696 11782 23696 10386 23697 10563 23697 11780 23697 10386 23698 11780 23698 11781 23698 11781 23699 11780 23699 11782 23699 11781 23700 11782 23700 10391 23700 11783 23701 6353 23701 11784 23701 11784 23702 6353 23702 11785 23702 11784 23703 11785 23703 11786 23703 6348 23704 6350 23704 11784 23704 11784 23705 6350 23705 6351 23705 11784 23706 6351 23706 11783 23706 6357 23707 6358 23707 11784 23707 11784 23708 6358 23708 6347 23708 11784 23709 6347 23709 6348 23709 11786 23710 11787 23710 11784 23710 11784 23711 11787 23711 6355 23711 11784 23712 6355 23712 6357 23712 8264 23713 11788 23713 11811 23713 11811 23714 11788 23714 10594 23714 11811 23715 10594 23715 11789 23715 11789 23716 10594 23716 11797 23716 10594 23717 11791 23717 11797 23717 11797 23718 11791 23718 11790 23718 11790 23719 11791 23719 11792 23719 11792 23720 11791 23720 11793 23720 11792 23721 11793 23721 11794 23721 11794 23722 11793 23722 11795 23722 11794 23723 11795 23723 11796 23723 11805 23724 11804 23724 11798 23724 11794 23725 11796 23725 11803 23725 11800 23726 11798 23726 11797 23726 11804 23727 11799 23727 11798 23727 11798 23728 11799 23728 11797 23728 11790 23729 11800 23729 11797 23729 11794 23730 11803 23730 11792 23730 11807 23731 11805 23731 11802 23731 11802 23732 11805 23732 11798 23732 11802 23733 11798 23733 11803 23733 11803 23734 11798 23734 11800 23734 11803 23735 11800 23735 11792 23735 11792 23736 11800 23736 11790 23736 11809 23737 11807 23737 11802 23737 11803 23738 11796 23738 8641 23738 11810 23739 11809 23739 7982 23739 7982 23740 11809 23740 11802 23740 7982 23741 11802 23741 11801 23741 11801 23742 11802 23742 11803 23742 11801 23743 11803 23743 7984 23743 7984 23744 11803 23744 8641 23744 11789 23745 11797 23745 11799 23745 11789 23746 11799 23746 11832 23746 11832 23747 11799 23747 11804 23747 11832 23748 11804 23748 11806 23748 11804 23749 11805 23749 11806 23749 11806 23750 11805 23750 11807 23750 11806 23751 11807 23751 11808 23751 11808 23752 11807 23752 11809 23752 11808 23753 11809 23753 11834 23753 11834 23754 11809 23754 11810 23754 11834 23755 11810 23755 11838 23755 11814 23756 11847 23756 10359 23756 10359 23757 11847 23757 11846 23757 10359 23758 11846 23758 10358 23758 8266 23759 8264 23759 11812 23759 11812 23760 8264 23760 11811 23760 11812 23761 11811 23761 11813 23761 11813 23762 11811 23762 11849 23762 11813 23763 11849 23763 11814 23763 11814 23764 11849 23764 11848 23764 11814 23765 11848 23765 11847 23765 11789 23766 11821 23766 11850 23766 11850 23767 11821 23767 11822 23767 11815 23768 11816 23768 11825 23768 11816 23769 11835 23769 11845 23769 11831 23770 11840 23770 11842 23770 11816 23771 11845 23771 11825 23771 11825 23772 11845 23772 11817 23772 11825 23773 11817 23773 11819 23773 11819 23774 11817 23774 11818 23774 11819 23775 11818 23775 11822 23775 11822 23776 11818 23776 11820 23776 11822 23777 11820 23777 11850 23777 11789 23778 11828 23778 11821 23778 11821 23779 11828 23779 11823 23779 11821 23780 11823 23780 11822 23780 11822 23781 11823 23781 11824 23781 11822 23782 11824 23782 11819 23782 11819 23783 11824 23783 11830 23783 11819 23784 11830 23784 11825 23784 11825 23785 11830 23785 11826 23785 11825 23786 11826 23786 11815 23786 11789 23787 11827 23787 11828 23787 11828 23788 11827 23788 11829 23788 11828 23789 11829 23789 11823 23789 11823 23790 11829 23790 11833 23790 11823 23791 11833 23791 11824 23791 11824 23792 11833 23792 11831 23792 11824 23793 11831 23793 11830 23793 11830 23794 11831 23794 11842 23794 11830 23795 11842 23795 11826 23795 11789 23796 11832 23796 11827 23796 11827 23797 11832 23797 11806 23797 11827 23798 11806 23798 11829 23798 11829 23799 11806 23799 11808 23799 11829 23800 11808 23800 11833 23800 11833 23801 11808 23801 11834 23801 11833 23802 11834 23802 11831 23802 11831 23803 11834 23803 11838 23803 11831 23804 11838 23804 11840 23804 11836 23805 11843 23805 11835 23805 11835 23806 11816 23806 11836 23806 11836 23807 11816 23807 11815 23807 11836 23808 11815 23808 11837 23808 11837 23809 11815 23809 11826 23809 11837 23810 11826 23810 11841 23810 11838 23811 11839 23811 11840 23811 11840 23812 11839 23812 11841 23812 11840 23813 11841 23813 11842 23813 11842 23814 11841 23814 11826 23814 11843 23815 11844 23815 11835 23815 11835 23816 11844 23816 10358 23816 11835 23817 10358 23817 11845 23817 11845 23818 10358 23818 11817 23818 11817 23819 10358 23819 11846 23819 11817 23820 11846 23820 11818 23820 11846 23821 11847 23821 11818 23821 11818 23822 11847 23822 11848 23822 11818 23823 11848 23823 11820 23823 11820 23824 11848 23824 11850 23824 11848 23825 11849 23825 11850 23825 11850 23826 11849 23826 11811 23826 11850 23827 11811 23827 11789 23827 11854 23828 11851 23828 12008 23828 12008 23829 11851 23829 12029 23829 12001 23830 11995 23830 11982 23830 11982 23831 11995 23831 11996 23831 11982 23832 11996 23832 11983 23832 11983 23833 11996 23833 11991 23833 11983 23834 11991 23834 12032 23834 12029 23835 11851 23835 12032 23835 12032 23836 11851 23836 11984 23836 12032 23837 11984 23837 11983 23837 11986 23838 11852 23838 11979 23838 11979 23839 11852 23839 11854 23839 11853 23840 11979 23840 12015 23840 12015 23841 11979 23841 11854 23841 12015 23842 11854 23842 12017 23842 12017 23843 11854 23843 12008 23843 12000 23844 11999 23844 11855 23844 11855 23845 11999 23845 11997 23845 11855 23846 11997 23846 12001 23846 12001 23847 11997 23847 11993 23847 12001 23848 11993 23848 11995 23848 11874 23849 11878 23849 11860 23849 11887 23850 11888 23850 11856 23850 11856 23851 11888 23851 11875 23851 11856 23852 11875 23852 11874 23852 11887 23853 11856 23853 11886 23853 11886 23854 11856 23854 11857 23854 11886 23855 11857 23855 11884 23855 11884 23856 11857 23856 11858 23856 11884 23857 11858 23857 11883 23857 11883 23858 11858 23858 11859 23858 11883 23859 11859 23859 11892 23859 11874 23860 11860 23860 11856 23860 11856 23861 11860 23861 11869 23861 11856 23862 11869 23862 11857 23862 11857 23863 11869 23863 11866 23863 11857 23864 11866 23864 11858 23864 11858 23865 11866 23865 11927 23865 11858 23866 11927 23866 11859 23866 11929 23867 11927 23867 11866 23867 11924 23868 11929 23868 11867 23868 11924 23869 11861 23869 11921 23869 11921 23870 11861 23870 11931 23870 11931 23871 11861 23871 11933 23871 11933 23872 11861 23872 11865 23872 11933 23873 11865 23873 11937 23873 11937 23874 11865 23874 11936 23874 11936 23875 11865 23875 11862 23875 11936 23876 11862 23876 11935 23876 11935 23877 11862 23877 11863 23877 11935 23878 11863 23878 11879 23878 11924 23879 11867 23879 11861 23879 11861 23880 11867 23880 11868 23880 11861 23881 11868 23881 11865 23881 11865 23882 11868 23882 11864 23882 11865 23883 11864 23883 11862 23883 11862 23884 11864 23884 11877 23884 11862 23885 11877 23885 11863 23885 11929 23886 11866 23886 11867 23886 11867 23887 11866 23887 11869 23887 11867 23888 11869 23888 11868 23888 11868 23889 11869 23889 11860 23889 11868 23890 11860 23890 11864 23890 11864 23891 11860 23891 11878 23891 11864 23892 11878 23892 11877 23892 11959 23893 11878 23893 11957 23893 11957 23894 11878 23894 11874 23894 11957 23895 11874 23895 11946 23895 11964 23896 11963 23896 11871 23896 11871 23897 11963 23897 11870 23897 11871 23898 11870 23898 11947 23898 11964 23899 11871 23899 11872 23899 11872 23900 11871 23900 11950 23900 11872 23901 11950 23901 11873 23901 11946 23902 11874 23902 11876 23902 11876 23903 11874 23903 11875 23903 11876 23904 11875 23904 11950 23904 11950 23905 11875 23905 11890 23905 11950 23906 11890 23906 11873 23906 11863 23907 11877 23907 11879 23907 11879 23908 11877 23908 11878 23908 11879 23909 11878 23909 11918 23909 11918 23910 11878 23910 11959 23910 11918 23911 11959 23911 11880 23911 11880 23912 11959 23912 11920 23912 11911 23913 11909 23913 11908 23913 11870 23914 11881 23914 11947 23914 11947 23915 11881 23915 11911 23915 11947 23916 11911 23916 11882 23916 11882 23917 11911 23917 11908 23917 11891 23918 11978 23918 11972 23918 11892 23919 11891 23919 11883 23919 11883 23920 11891 23920 11885 23920 11883 23921 11885 23921 11884 23921 11884 23922 11885 23922 11886 23922 11886 23923 11885 23923 11889 23923 11886 23924 11889 23924 11887 23924 11887 23925 11889 23925 11888 23925 11888 23926 11889 23926 11890 23926 11888 23927 11890 23927 11875 23927 11891 23928 11972 23928 11885 23928 11885 23929 11972 23929 11965 23929 11885 23930 11965 23930 11889 23930 11889 23931 11965 23931 11873 23931 11889 23932 11873 23932 11890 23932 12034 23933 11892 23933 11859 23933 12034 23934 11859 23934 12021 23934 12021 23935 11859 23935 11927 23935 12021 23936 11927 23936 11926 23936 11949 23937 11947 23937 11882 23937 11893 23938 11894 23938 11901 23938 11952 23939 11895 23939 11900 23939 11981 23940 11952 23940 11896 23940 11896 23941 11952 23941 11900 23941 11896 23942 11900 23942 11897 23942 11897 23943 11900 23943 11902 23943 11897 23944 11902 23944 11998 23944 11998 23945 11902 23945 11898 23945 11998 23946 11898 23946 11899 23946 11899 23947 11898 23947 11905 23947 11899 23948 11905 23948 11992 23948 11992 23949 11905 23949 11906 23949 11895 23950 11893 23950 11900 23950 11900 23951 11893 23951 11901 23951 11900 23952 11901 23952 11902 23952 11902 23953 11901 23953 11903 23953 11902 23954 11903 23954 11898 23954 11898 23955 11903 23955 11904 23955 11898 23956 11904 23956 11905 23956 11905 23957 11904 23957 11910 23957 11905 23958 11910 23958 11906 23958 11906 23959 11910 23959 11907 23959 11894 23960 11949 23960 11901 23960 11901 23961 11949 23961 11882 23961 11901 23962 11882 23962 11903 23962 11903 23963 11882 23963 11908 23963 11903 23964 11908 23964 11904 23964 11904 23965 11908 23965 11909 23965 11904 23966 11909 23966 11910 23966 11910 23967 11909 23967 11911 23967 11910 23968 11911 23968 11907 23968 11907 23969 11911 23969 11881 23969 11930 23970 11932 23970 11912 23970 11912 23971 11932 23971 11913 23971 11912 23972 11913 23972 11985 23972 11985 23973 11913 23973 11915 23973 11985 23974 11915 23974 11914 23974 11914 23975 11915 23975 11960 23975 11932 23976 11934 23976 11913 23976 11913 23977 11934 23977 11916 23977 11913 23978 11916 23978 11915 23978 11915 23979 11916 23979 11917 23979 11915 23980 11917 23980 11960 23980 11960 23981 11917 23981 11919 23981 11934 23982 11918 23982 11916 23982 11916 23983 11918 23983 11880 23983 11916 23984 11880 23984 11917 23984 11917 23985 11880 23985 11920 23985 11917 23986 11920 23986 11919 23986 11919 23987 11920 23987 11959 23987 12010 23988 11922 23988 11921 23988 11921 23989 11922 23989 11924 23989 11922 23990 11923 23990 11924 23990 11924 23991 11923 23991 11925 23991 11924 23992 11925 23992 11929 23992 11926 23993 11927 23993 12002 23993 12002 23994 11927 23994 11929 23994 12002 23995 11929 23995 11928 23995 11928 23996 11929 23996 11925 23996 11921 23997 11931 23997 11930 23997 11930 23998 11931 23998 11932 23998 11931 23999 11933 23999 11932 23999 11932 24000 11933 24000 11937 24000 11932 24001 11937 24001 11934 24001 11879 24002 11918 24002 11935 24002 11935 24003 11918 24003 11934 24003 11935 24004 11934 24004 11936 24004 11936 24005 11934 24005 11937 24005 11938 24006 11939 24006 11940 24006 11938 24007 11941 24007 11956 24007 11956 24008 11941 24008 11955 24008 11955 24009 11941 24009 11942 24009 11942 24010 11941 24010 11945 24010 11942 24011 11945 24011 11943 24011 11943 24012 11945 24012 11876 24012 11943 24013 11876 24013 11950 24013 11938 24014 11940 24014 11941 24014 11941 24015 11940 24015 11944 24015 11941 24016 11944 24016 11945 24016 11945 24017 11944 24017 11946 24017 11945 24018 11946 24018 11876 24018 11871 24019 11947 24019 11949 24019 11950 24020 11871 24020 11948 24020 11871 24021 11949 24021 11948 24021 11948 24022 11949 24022 11894 24022 11948 24023 11894 24023 11951 24023 11950 24024 11948 24024 11943 24024 11943 24025 11948 24025 11951 24025 11943 24026 11951 24026 11942 24026 11942 24027 11951 24027 11953 24027 11942 24028 11953 24028 11955 24028 11952 24029 11953 24029 11895 24029 11895 24030 11953 24030 11951 24030 11895 24031 11951 24031 11893 24031 11893 24032 11951 24032 11894 24032 11952 24033 11981 24033 11953 24033 11953 24034 11981 24034 11954 24034 11953 24035 11954 24035 11955 24035 11955 24036 11954 24036 11956 24036 11957 24037 11946 24037 11944 24037 11959 24038 11957 24038 11958 24038 11959 24039 11958 24039 11919 24039 11919 24040 11958 24040 11961 24040 11919 24041 11961 24041 11960 24041 11960 24042 11961 24042 11962 24042 11960 24043 11962 24043 11914 24043 11957 24044 11944 24044 11958 24044 11958 24045 11944 24045 11940 24045 11958 24046 11940 24046 11961 24046 11961 24047 11940 24047 11939 24047 11961 24048 11939 24048 11962 24048 11907 24049 11881 24049 11967 24049 11967 24050 11881 24050 11870 24050 11967 24051 11870 24051 11968 24051 11968 24052 11870 24052 11963 24052 11968 24053 11963 24053 11970 24053 11970 24054 11963 24054 11964 24054 11970 24055 11964 24055 11971 24055 11971 24056 11964 24056 11872 24056 11971 24057 11872 24057 11965 24057 11965 24058 11872 24058 11873 24058 11906 24059 11907 24059 11966 24059 11966 24060 11907 24060 11967 24060 11966 24061 11967 24061 11974 24061 11974 24062 11967 24062 11968 24062 11974 24063 11968 24063 11969 24063 11969 24064 11968 24064 11970 24064 11969 24065 11970 24065 11977 24065 11977 24066 11970 24066 11971 24066 11977 24067 11971 24067 11972 24067 11972 24068 11971 24068 11965 24068 11992 24069 11906 24069 11973 24069 11973 24070 11906 24070 11966 24070 11973 24071 11966 24071 11994 24071 11994 24072 11966 24072 11974 24072 11994 24073 11974 24073 11975 24073 11975 24074 11974 24074 11969 24074 11975 24075 11969 24075 11976 24075 11976 24076 11969 24076 11977 24076 11976 24077 11977 24077 11978 24077 11978 24078 11977 24078 11972 24078 11892 24079 12034 24079 12031 24079 11892 24080 12031 24080 11891 24080 11891 24081 12031 24081 11987 24081 11891 24082 11987 24082 11978 24082 11853 24083 12009 24083 11979 24083 11979 24084 12009 24084 12012 24084 11979 24085 12012 24085 12011 24085 11921 24086 11930 24086 12010 24086 12010 24087 11930 24087 11979 24087 12010 24088 11979 24088 11980 24088 11980 24089 11979 24089 12011 24089 11939 24090 11851 24090 11962 24090 11962 24091 11851 24091 11854 24091 11962 24092 11854 24092 11914 24092 11981 24093 12001 24093 11982 24093 11981 24094 11982 24094 11954 24094 11954 24095 11982 24095 11983 24095 11954 24096 11983 24096 11956 24096 11956 24097 11983 24097 11938 24097 11938 24098 11983 24098 11984 24098 11938 24099 11984 24099 11939 24099 11939 24100 11984 24100 11851 24100 11914 24101 11854 24101 11985 24101 11985 24102 11854 24102 11852 24102 11985 24103 11852 24103 11912 24103 11912 24104 11852 24104 11986 24104 11912 24105 11986 24105 11930 24105 11930 24106 11986 24106 11979 24106 11978 24107 11987 24107 11996 24107 11996 24108 11987 24108 11988 24108 11996 24109 11988 24109 12030 24109 12030 24110 11989 24110 11996 24110 11996 24111 11989 24111 11990 24111 11996 24112 11990 24112 11991 24112 11992 24113 11973 24113 11993 24113 11993 24114 11973 24114 11995 24114 11973 24115 11994 24115 11995 24115 11995 24116 11994 24116 11975 24116 11995 24117 11975 24117 11996 24117 11996 24118 11975 24118 11976 24118 11996 24119 11976 24119 11978 24119 11992 24120 11993 24120 11899 24120 11899 24121 11993 24121 11997 24121 11899 24122 11997 24122 11998 24122 11998 24123 11997 24123 11999 24123 11998 24124 11999 24124 11897 24124 11897 24125 11999 24125 12000 24125 11897 24126 12000 24126 11896 24126 11896 24127 12000 24127 11855 24127 11896 24128 11855 24128 11981 24128 11981 24129 11855 24129 12001 24129 12014 24130 11922 24130 12010 24130 11928 24131 11925 24131 12013 24131 12013 24132 11925 24132 11923 24132 11926 24133 12002 24133 12003 24133 12003 24134 12002 24134 12019 24134 12003 24135 12019 24135 12004 24135 12004 24136 12019 24136 12005 24136 12004 24137 12005 24137 12028 24137 12028 24138 12005 24138 12006 24138 12028 24139 12006 24139 12007 24139 12007 24140 12006 24140 12017 24140 12007 24141 12017 24141 12008 24141 12009 24142 11853 24142 12015 24142 12010 24143 11980 24143 12014 24143 12014 24144 11980 24144 12011 24144 12014 24145 12011 24145 12012 24145 12015 24146 12016 24146 12009 24146 12009 24147 12016 24147 12018 24147 12009 24148 12018 24148 12012 24148 12012 24149 12018 24149 12013 24149 12012 24150 12013 24150 12014 24150 12014 24151 12013 24151 11923 24151 12014 24152 11923 24152 11922 24152 12015 24153 12017 24153 12016 24153 12016 24154 12017 24154 12006 24154 12016 24155 12006 24155 12018 24155 12018 24156 12006 24156 12005 24156 12018 24157 12005 24157 12013 24157 12013 24158 12005 24158 12019 24158 12013 24159 12019 24159 11928 24159 11928 24160 12019 24160 12002 24160 12020 24161 12034 24161 12021 24161 11926 24162 12003 24162 12021 24162 12021 24163 12003 24163 12022 24163 12021 24164 12022 24164 12020 24164 12020 24165 12022 24165 12023 24165 12023 24166 12022 24166 12024 24166 12024 24167 12022 24167 12027 24167 12024 24168 12027 24168 12025 24168 12025 24169 12027 24169 12026 24169 12026 24170 12027 24170 12029 24170 12026 24171 12029 24171 12032 24171 12003 24172 12004 24172 12022 24172 12022 24173 12004 24173 12028 24173 12022 24174 12028 24174 12027 24174 12027 24175 12028 24175 12007 24175 12027 24176 12007 24176 12029 24176 12029 24177 12007 24177 12008 24177 11988 24178 11987 24178 12031 24178 11989 24179 12030 24179 12033 24179 12033 24180 12030 24180 11988 24180 12033 24181 11988 24181 12035 24181 12035 24182 11988 24182 12031 24182 12025 24183 12026 24183 11990 24183 11990 24184 12026 24184 12032 24184 11990 24185 12032 24185 11991 24185 11989 24186 12033 24186 11990 24186 11990 24187 12033 24187 12024 24187 11990 24188 12024 24188 12025 24188 12031 24189 12034 24189 12035 24189 12035 24190 12034 24190 12020 24190 12035 24191 12020 24191 12033 24191 12033 24192 12020 24192 12023 24192 12033 24193 12023 24193 12024 24193 12036 24194 12299 24194 12042 24194 12310 24195 12037 24195 12295 24195 12037 24196 12308 24196 12038 24196 12315 24197 12314 24197 12299 24197 12299 24198 12314 24198 12039 24198 12299 24199 12039 24199 12042 24199 12320 24200 12319 24200 12316 24200 12302 24201 12303 24201 12040 24201 12040 24202 12303 24202 12036 24202 12040 24203 12036 24203 12041 24203 12041 24204 12036 24204 12042 24204 12041 24205 12042 24205 12293 24205 12293 24206 12042 24206 12310 24206 12293 24207 12310 24207 12296 24207 12296 24208 12310 24208 12295 24208 12038 24209 12043 24209 12037 24209 12037 24210 12043 24210 12044 24210 12037 24211 12044 24211 12295 24211 12295 24212 12044 24212 12320 24212 12295 24213 12320 24213 12045 24213 12045 24214 12320 24214 12316 24214 12058 24215 12057 24215 12231 24215 12066 24216 12163 24216 12067 24216 12048 24217 12046 24217 12047 24217 12162 24218 12244 24218 12049 24218 12049 24219 12244 24219 12048 24219 12048 24220 12047 24220 12049 24220 12049 24221 12047 24221 12205 24221 12049 24222 12205 24222 12162 24222 12050 24223 12081 24223 12175 24223 12173 24224 12051 24224 12175 24224 12175 24225 12051 24225 12052 24225 12175 24226 12052 24226 12050 24226 12050 24227 12052 24227 12093 24227 12093 24228 12052 24228 12053 24228 12053 24229 12052 24229 12051 24229 12053 24230 12051 24230 12054 24230 12054 24231 12051 24231 12055 24231 12054 24232 12055 24232 12062 24232 12139 24233 12057 24233 12056 24233 12056 24234 12057 24234 12058 24234 12056 24235 12058 24235 12064 24235 12059 24236 12188 24236 12189 24236 12188 24237 12059 24237 12195 24237 12195 24238 12059 24238 12068 24238 12195 24239 12068 24239 12070 24239 12060 24240 12069 24240 12213 24240 12213 24241 12069 24241 12067 24241 12213 24242 12067 24242 12205 24242 12205 24243 12067 24243 12163 24243 12205 24244 12163 24244 12162 24244 12231 24245 12062 24245 12061 24245 12061 24246 12062 24246 12055 24246 12061 24247 12055 24247 12065 24247 12065 24248 12055 24248 12051 24248 12065 24249 12051 24249 12063 24249 12063 24250 12051 24250 12173 24250 12064 24251 12058 24251 12138 24251 12138 24252 12058 24252 12231 24252 12138 24253 12231 24253 12189 24253 12189 24254 12231 24254 12061 24254 12189 24255 12061 24255 12059 24255 12059 24256 12061 24256 12065 24256 12059 24257 12065 24257 12068 24257 12173 24258 12066 24258 12063 24258 12063 24259 12066 24259 12067 24259 12063 24260 12067 24260 12065 24260 12065 24261 12067 24261 12069 24261 12065 24262 12069 24262 12068 24262 12068 24263 12069 24263 12060 24263 12068 24264 12060 24264 12070 24264 12070 24265 12060 24265 12071 24265 12070 24266 12071 24266 12137 24266 12093 24267 12053 24267 12227 24267 12082 24268 12092 24268 12087 24268 12084 24269 12083 24269 12072 24269 12072 24270 12083 24270 12082 24270 12072 24271 12082 24271 12073 24271 12073 24272 12082 24272 12087 24272 12074 24273 12075 24273 12079 24273 12079 24274 12075 24274 12076 24274 12079 24275 12076 24275 12080 24275 12227 24276 12229 24276 12077 24276 12077 24277 12229 24277 12074 24277 12077 24278 12074 24278 12078 24278 12078 24279 12074 24279 12079 24279 12078 24280 12079 24280 12091 24280 12091 24281 12079 24281 12080 24281 12091 24282 12080 24282 12317 24282 12050 24283 12092 24283 12081 24283 12081 24284 12092 24284 12082 24284 12081 24285 12082 24285 12175 24285 12175 24286 12082 24286 12083 24286 12177 24287 12084 24287 12085 24287 12085 24288 12084 24288 12072 24288 12085 24289 12072 24289 12090 24289 12090 24290 12072 24290 12073 24290 12090 24291 12073 24291 12086 24291 12086 24292 12073 24292 12087 24292 12086 24293 12087 24293 12088 24293 12179 24294 12177 24294 12089 24294 12089 24295 12177 24295 12085 24295 12089 24296 12085 24296 12318 24296 12318 24297 12085 24297 12090 24297 12318 24298 12090 24298 12317 24298 12317 24299 12090 24299 12086 24299 12317 24300 12086 24300 12091 24300 12091 24301 12086 24301 12088 24301 12091 24302 12088 24302 12078 24302 12078 24303 12088 24303 12087 24303 12078 24304 12087 24304 12077 24304 12077 24305 12087 24305 12092 24305 12077 24306 12092 24306 12227 24306 12227 24307 12092 24307 12050 24307 12227 24308 12050 24308 12093 24308 12094 24309 12193 24309 12135 24309 12125 24310 12095 24310 12126 24310 12097 24311 12222 24311 12114 24311 12114 24312 12222 24312 12096 24312 12114 24313 12096 24313 12115 24313 12128 24314 12126 24314 12097 24314 12097 24315 12126 24315 12095 24315 12097 24316 12095 24316 12222 24316 12134 24317 12098 24317 12133 24317 12094 24318 12132 24318 12101 24318 12101 24319 12132 24319 12099 24319 12190 24320 12193 24320 12100 24320 12100 24321 12193 24321 12094 24321 12100 24322 12094 24322 12107 24322 12107 24323 12094 24323 12101 24323 12107 24324 12101 24324 12109 24324 12109 24325 12101 24325 12099 24325 12109 24326 12099 24326 12110 24326 12122 24327 12121 24327 12102 24327 12102 24328 12121 24328 12119 24328 12102 24329 12119 24329 12103 24329 12103 24330 12119 24330 12104 24330 12103 24331 12104 24331 12313 24331 12313 24332 12104 24332 12116 24332 12313 24333 12116 24333 12105 24333 12105 24334 12116 24334 12106 24334 12123 24335 12107 24335 12108 24335 12108 24336 12107 24336 12109 24336 12108 24337 12109 24337 12120 24337 12120 24338 12109 24338 12110 24338 12120 24339 12110 24339 12118 24339 12118 24340 12110 24340 12111 24340 12118 24341 12111 24341 12117 24341 12117 24342 12111 24342 12112 24342 12131 24343 12128 24343 12113 24343 12113 24344 12128 24344 12097 24344 12113 24345 12097 24345 12130 24345 12130 24346 12097 24346 12114 24346 12130 24347 12114 24347 12129 24347 12129 24348 12114 24348 12115 24348 12129 24349 12115 24349 12225 24349 12225 24350 12106 24350 12112 24350 12112 24351 12106 24351 12116 24351 12112 24352 12116 24352 12117 24352 12117 24353 12116 24353 12104 24353 12117 24354 12104 24354 12118 24354 12118 24355 12104 24355 12119 24355 12118 24356 12119 24356 12120 24356 12120 24357 12119 24357 12121 24357 12120 24358 12121 24358 12108 24358 12108 24359 12121 24359 12122 24359 12108 24360 12122 24360 12123 24360 12135 24361 12124 24361 12136 24361 12136 24362 12124 24362 12195 24362 12136 24363 12195 24363 12070 24363 12071 24364 12125 24364 12137 24364 12137 24365 12125 24365 12126 24365 12137 24366 12126 24366 12127 24366 12127 24367 12126 24367 12128 24367 12127 24368 12128 24368 12134 24368 12134 24369 12128 24369 12131 24369 12134 24370 12131 24370 12098 24370 12225 24371 12112 24371 12129 24371 12129 24372 12112 24372 12111 24372 12129 24373 12111 24373 12130 24373 12130 24374 12111 24374 12110 24374 12130 24375 12110 24375 12113 24375 12113 24376 12110 24376 12099 24376 12113 24377 12099 24377 12131 24377 12131 24378 12099 24378 12132 24378 12131 24379 12132 24379 12098 24379 12098 24380 12132 24380 12094 24380 12098 24381 12094 24381 12133 24381 12133 24382 12094 24382 12135 24382 12133 24383 12135 24383 12134 24383 12134 24384 12135 24384 12136 24384 12134 24385 12136 24385 12127 24385 12127 24386 12136 24386 12070 24386 12127 24387 12070 24387 12137 24387 12304 24388 12140 24388 12141 24388 12307 24389 12292 24389 12241 24389 12139 24390 12056 24390 12154 24390 12183 24391 12153 24391 12180 24391 12180 24392 12153 24392 12064 24392 12180 24393 12064 24393 12138 24393 12139 24394 12154 24394 12057 24394 12140 24395 12305 24395 12141 24395 12141 24396 12305 24396 12306 24396 12141 24397 12306 24397 12142 24397 12142 24398 12306 24398 12149 24398 12142 24399 12149 24399 12152 24399 12152 24400 12149 24400 12150 24400 12152 24401 12150 24401 12154 24401 12154 24402 12150 24402 12151 24402 12154 24403 12151 24403 12057 24403 12300 24404 12143 24404 12144 24404 12144 24405 12143 24405 12145 24405 12144 24406 12145 24406 12186 24406 12186 24407 12145 24407 12146 24407 12186 24408 12146 24408 12185 24408 12185 24409 12146 24409 12147 24409 12185 24410 12147 24410 12183 24410 12183 24411 12147 24411 12148 24411 12183 24412 12148 24412 12153 24412 12306 24413 12307 24413 12149 24413 12149 24414 12307 24414 12241 24414 12149 24415 12241 24415 12150 24415 12150 24416 12241 24416 12236 24416 12150 24417 12236 24417 12151 24417 12143 24418 12304 24418 12145 24418 12145 24419 12304 24419 12141 24419 12145 24420 12141 24420 12146 24420 12146 24421 12141 24421 12142 24421 12146 24422 12142 24422 12147 24422 12147 24423 12142 24423 12152 24423 12147 24424 12152 24424 12148 24424 12148 24425 12152 24425 12154 24425 12148 24426 12154 24426 12153 24426 12153 24427 12154 24427 12056 24427 12153 24428 12056 24428 12064 24428 12159 24429 12258 24429 12168 24429 12157 24430 12178 24430 12158 24430 12167 24431 12172 24431 12155 24431 12155 24432 12172 24432 12171 24432 12155 24433 12171 24433 12156 24433 12156 24434 12171 24434 12169 24434 12156 24435 12169 24435 12259 24435 12170 24436 12157 24436 12168 24436 12168 24437 12157 24437 12158 24437 12168 24438 12158 24438 12159 24438 12159 24439 12158 24439 12160 24439 12159 24440 12160 24440 12161 24440 12162 24441 12163 24441 12164 24441 12164 24442 12163 24442 12174 24442 12164 24443 12174 24443 12165 24443 12165 24444 12174 24444 12172 24444 12165 24445 12172 24445 12166 24445 12166 24446 12172 24446 12167 24446 12258 24447 12259 24447 12168 24447 12168 24448 12259 24448 12169 24448 12168 24449 12169 24449 12170 24449 12170 24450 12169 24450 12171 24450 12170 24451 12171 24451 12176 24451 12176 24452 12171 24452 12172 24452 12176 24453 12172 24453 12173 24453 12173 24454 12172 24454 12174 24454 12173 24455 12174 24455 12066 24455 12066 24456 12174 24456 12163 24456 12173 24457 12175 24457 12176 24457 12176 24458 12175 24458 12083 24458 12176 24459 12083 24459 12170 24459 12170 24460 12083 24460 12084 24460 12170 24461 12084 24461 12157 24461 12157 24462 12084 24462 12177 24462 12157 24463 12177 24463 12178 24463 12178 24464 12177 24464 12179 24464 12138 24465 12189 24465 12180 24465 12180 24466 12189 24466 12181 24466 12180 24467 12181 24467 12183 24467 12183 24468 12181 24468 12182 24468 12183 24469 12182 24469 12185 24469 12185 24470 12182 24470 12184 24470 12185 24471 12184 24471 12186 24471 12186 24472 12184 24472 12144 24472 12144 24473 12184 24473 12301 24473 12144 24474 12301 24474 12300 24474 12191 24475 12301 24475 12192 24475 12192 24476 12301 24476 12184 24476 12192 24477 12184 24477 12187 24477 12187 24478 12184 24478 12182 24478 12187 24479 12182 24479 12194 24479 12194 24480 12182 24480 12181 24480 12194 24481 12181 24481 12188 24481 12188 24482 12181 24482 12189 24482 12190 24483 12191 24483 12193 24483 12193 24484 12191 24484 12192 24484 12193 24485 12192 24485 12135 24485 12135 24486 12192 24486 12187 24486 12135 24487 12187 24487 12124 24487 12124 24488 12187 24488 12194 24488 12124 24489 12194 24489 12195 24489 12195 24490 12194 24490 12188 24490 12243 24491 12312 24491 12255 24491 12255 24492 12312 24492 12196 24492 12255 24493 12196 24493 12197 24493 12197 24494 12196 24494 12212 24494 12197 24495 12212 24495 12198 24495 12198 24496 12212 24496 12200 24496 12198 24497 12200 24497 12199 24497 12199 24498 12200 24498 12210 24498 12199 24499 12210 24499 12204 24499 12204 24500 12210 24500 12209 24500 12205 24501 12047 24501 12206 24501 12206 24502 12047 24502 12269 24502 12206 24503 12269 24503 12201 24503 12201 24504 12269 24504 12202 24504 12201 24505 12202 24505 12209 24505 12209 24506 12202 24506 12203 24506 12209 24507 12203 24507 12204 24507 12213 24508 12205 24508 12207 24508 12207 24509 12205 24509 12206 24509 12207 24510 12206 24510 12215 24510 12215 24511 12206 24511 12201 24511 12215 24512 12201 24512 12208 24512 12208 24513 12201 24513 12209 24513 12208 24514 12209 24514 12218 24514 12218 24515 12209 24515 12210 24515 12218 24516 12210 24516 12211 24516 12211 24517 12210 24517 12200 24517 12211 24518 12200 24518 12219 24518 12219 24519 12200 24519 12212 24519 12219 24520 12212 24520 12220 24520 12220 24521 12212 24521 12196 24521 12220 24522 12196 24522 12311 24522 12311 24523 12196 24523 12312 24523 12060 24524 12213 24524 12214 24524 12214 24525 12213 24525 12207 24525 12214 24526 12207 24526 12216 24526 12216 24527 12207 24527 12215 24527 12216 24528 12215 24528 12223 24528 12223 24529 12215 24529 12208 24529 12223 24530 12208 24530 12224 24530 12224 24531 12208 24531 12218 24531 12224 24532 12218 24532 12217 24532 12217 24533 12218 24533 12211 24533 12217 24534 12211 24534 12226 24534 12226 24535 12211 24535 12219 24535 12226 24536 12219 24536 12221 24536 12221 24537 12219 24537 12220 24537 12221 24538 12220 24538 12309 24538 12309 24539 12220 24539 12311 24539 12071 24540 12060 24540 12125 24540 12125 24541 12060 24541 12214 24541 12125 24542 12214 24542 12095 24542 12095 24543 12214 24543 12216 24543 12095 24544 12216 24544 12222 24544 12222 24545 12216 24545 12223 24545 12222 24546 12223 24546 12096 24546 12096 24547 12223 24547 12224 24547 12096 24548 12224 24548 12115 24548 12115 24549 12224 24549 12217 24549 12115 24550 12217 24550 12225 24550 12225 24551 12217 24551 12226 24551 12225 24552 12226 24552 12106 24552 12106 24553 12226 24553 12221 24553 12106 24554 12221 24554 12105 24554 12105 24555 12221 24555 12309 24555 12053 24556 12054 24556 12227 24556 12227 24557 12054 24557 12228 24557 12227 24558 12228 24558 12229 24558 12229 24559 12228 24559 12230 24559 12229 24560 12230 24560 12074 24560 12074 24561 12230 24561 12238 24561 12074 24562 12238 24562 12075 24562 12294 24563 12298 24563 12238 24563 12238 24564 12298 24564 12297 24564 12238 24565 12297 24565 12075 24565 12062 24566 12231 24566 12232 24566 12232 24567 12231 24567 12233 24567 12232 24568 12233 24568 12234 24568 12234 24569 12233 24569 12237 24569 12234 24570 12237 24570 12239 24570 12239 24571 12237 24571 12235 24571 12241 24572 12235 24572 12236 24572 12236 24573 12235 24573 12237 24573 12236 24574 12237 24574 12151 24574 12151 24575 12237 24575 12233 24575 12151 24576 12233 24576 12057 24576 12057 24577 12233 24577 12231 24577 12054 24578 12062 24578 12228 24578 12228 24579 12062 24579 12232 24579 12228 24580 12232 24580 12230 24580 12230 24581 12232 24581 12234 24581 12230 24582 12234 24582 12238 24582 12238 24583 12234 24583 12239 24583 12238 24584 12239 24584 12294 24584 12294 24585 12239 24585 12235 24585 12294 24586 12235 24586 12240 24586 12240 24587 12235 24587 12241 24587 12240 24588 12241 24588 12292 24588 12164 24589 12165 24589 12283 24589 12262 24590 12257 24590 12263 24590 12242 24591 12243 24591 12255 24591 12046 24592 12048 24592 12270 24592 12270 24593 12048 24593 12244 24593 12246 24594 12199 24594 12204 24594 12166 24595 12167 24595 12284 24595 12284 24596 12167 24596 12155 24596 12284 24597 12155 24597 12260 24597 12274 24598 12278 24598 12245 24598 12245 24599 12278 24599 12279 24599 12245 24600 12279 24600 12276 24600 12246 24601 12204 24601 12277 24601 12283 24602 12247 24602 12274 24602 12274 24603 12247 24603 12248 24603 12274 24604 12248 24604 12278 24604 12249 24605 12290 24605 12250 24605 12251 24606 12252 24606 12253 24606 12253 24607 12252 24607 12287 24607 12253 24608 12287 24608 12280 24608 12280 24609 12287 24609 12288 24609 12280 24610 12288 24610 12281 24610 12281 24611 12288 24611 12289 24611 12281 24612 12289 24612 12282 24612 12282 24613 12289 24613 12254 24613 12282 24614 12254 24614 12291 24614 12249 24615 12242 24615 12290 24615 12290 24616 12242 24616 12255 24616 12290 24617 12255 24617 12256 24617 12256 24618 12255 24618 12197 24618 12256 24619 12197 24619 12198 24619 12161 24620 12257 24620 12159 24620 12159 24621 12257 24621 12262 24621 12159 24622 12262 24622 12258 24622 12155 24623 12156 24623 12260 24623 12260 24624 12156 24624 12259 24624 12260 24625 12259 24625 12261 24625 12261 24626 12259 24626 12258 24626 12261 24627 12258 24627 12285 24627 12285 24628 12258 24628 12262 24628 12285 24629 12262 24629 12286 24629 12286 24630 12262 24630 12263 24630 12286 24631 12263 24631 12264 24631 12264 24632 12263 24632 12265 24632 12264 24633 12265 24633 12250 24633 12250 24634 12265 24634 12266 24634 12250 24635 12266 24635 12249 24635 12204 24636 12203 24636 12267 24636 12267 24637 12203 24637 12202 24637 12267 24638 12202 24638 12268 24638 12268 24639 12202 24639 12269 24639 12268 24640 12269 24640 12270 24640 12270 24641 12269 24641 12047 24641 12270 24642 12047 24642 12046 24642 12277 24643 12204 24643 12271 24643 12271 24644 12204 24644 12267 24644 12271 24645 12267 24645 12272 24645 12272 24646 12267 24646 12268 24646 12272 24647 12268 24647 12275 24647 12275 24648 12268 24648 12270 24648 12275 24649 12270 24649 12273 24649 12273 24650 12270 24650 12244 24650 12273 24651 12244 24651 12162 24651 12162 24652 12164 24652 12273 24652 12273 24653 12164 24653 12283 24653 12273 24654 12283 24654 12275 24654 12275 24655 12283 24655 12274 24655 12275 24656 12274 24656 12272 24656 12272 24657 12274 24657 12245 24657 12272 24658 12245 24658 12271 24658 12271 24659 12245 24659 12276 24659 12271 24660 12276 24660 12277 24660 12248 24661 12251 24661 12278 24661 12278 24662 12251 24662 12253 24662 12278 24663 12253 24663 12279 24663 12279 24664 12253 24664 12280 24664 12279 24665 12280 24665 12276 24665 12276 24666 12280 24666 12281 24666 12276 24667 12281 24667 12277 24667 12277 24668 12281 24668 12282 24668 12277 24669 12282 24669 12246 24669 12246 24670 12282 24670 12291 24670 12246 24671 12291 24671 12199 24671 12165 24672 12166 24672 12283 24672 12283 24673 12166 24673 12284 24673 12283 24674 12284 24674 12247 24674 12247 24675 12284 24675 12260 24675 12247 24676 12260 24676 12248 24676 12248 24677 12260 24677 12261 24677 12248 24678 12261 24678 12251 24678 12251 24679 12261 24679 12285 24679 12251 24680 12285 24680 12252 24680 12252 24681 12285 24681 12286 24681 12252 24682 12286 24682 12287 24682 12287 24683 12286 24683 12264 24683 12287 24684 12264 24684 12288 24684 12288 24685 12264 24685 12250 24685 12288 24686 12250 24686 12289 24686 12289 24687 12250 24687 12290 24687 12289 24688 12290 24688 12254 24688 12254 24689 12290 24689 12256 24689 12254 24690 12256 24690 12291 24690 12291 24691 12256 24691 12198 24691 12291 24692 12198 24692 12199 24692 12292 24693 12041 24693 12240 24693 12240 24694 12041 24694 12293 24694 12240 24695 12293 24695 12294 24695 12294 24696 12293 24696 12296 24696 12294 24697 12296 24697 12298 24697 12295 24698 12075 24698 12296 24698 12296 24699 12075 24699 12297 24699 12296 24700 12297 24700 12298 24700 12191 24701 12190 24701 12299 24701 12036 24702 12300 24702 12299 24702 12299 24703 12300 24703 12301 24703 12299 24704 12301 24704 12191 24704 12305 24705 12140 24705 12302 24705 12303 24706 12143 24706 12036 24706 12036 24707 12143 24707 12300 24707 12302 24708 12140 24708 12303 24708 12303 24709 12140 24709 12304 24709 12303 24710 12304 24710 12143 24710 12305 24711 12302 24711 12306 24711 12306 24712 12302 24712 12040 24712 12306 24713 12040 24713 12307 24713 12307 24714 12040 24714 12041 24714 12307 24715 12041 24715 12292 24715 12161 24716 12044 24716 12257 24716 12257 24717 12044 24717 12043 24717 12257 24718 12043 24718 12263 24718 12263 24719 12043 24719 12038 24719 12263 24720 12038 24720 12265 24720 12265 24721 12038 24721 12266 24721 12266 24722 12038 24722 12308 24722 12266 24723 12308 24723 12249 24723 12249 24724 12308 24724 12242 24724 12242 24725 12308 24725 12037 24725 12242 24726 12037 24726 12243 24726 12310 24727 12042 24727 12105 24727 12105 24728 12309 24728 12310 24728 12310 24729 12309 24729 12311 24729 12310 24730 12311 24730 12037 24730 12037 24731 12311 24731 12312 24731 12037 24732 12312 24732 12243 24732 12179 24733 12320 24733 12178 24733 12178 24734 12320 24734 12044 24734 12161 24735 12160 24735 12044 24735 12044 24736 12160 24736 12158 24736 12044 24737 12158 24737 12178 24737 12105 24738 12042 24738 12313 24738 12313 24739 12042 24739 12039 24739 12313 24740 12039 24740 12103 24740 12103 24741 12039 24741 12314 24741 12103 24742 12314 24742 12102 24742 12102 24743 12314 24743 12122 24743 12122 24744 12314 24744 12123 24744 12123 24745 12314 24745 12315 24745 12123 24746 12315 24746 12107 24746 12107 24747 12315 24747 12100 24747 12100 24748 12315 24748 12299 24748 12100 24749 12299 24749 12190 24749 12076 24750 12075 24750 12295 24750 12317 24751 12080 24751 12316 24751 12316 24752 12080 24752 12076 24752 12316 24753 12076 24753 12045 24753 12045 24754 12076 24754 12295 24754 12317 24755 12316 24755 12318 24755 12318 24756 12316 24756 12319 24756 12318 24757 12319 24757 12089 24757 12089 24758 12319 24758 12320 24758 12089 24759 12320 24759 12179 24759 12483 24760 12481 24760 12480 24760 12463 24761 12471 24761 12484 24761 12487 24762 12486 24762 12322 24762 12466 24763 12475 24763 12487 24763 12323 24764 12462 24764 12321 24764 12472 24765 12469 24765 12473 24765 12473 24766 12469 24766 12471 24766 12473 24767 12471 24767 12474 24767 12474 24768 12471 24768 12463 24768 12484 24769 12483 24769 12463 24769 12463 24770 12483 24770 12480 24770 12463 24771 12480 24771 12466 24771 12466 24772 12480 24772 12477 24772 12466 24773 12477 24773 12475 24773 12487 24774 12322 24774 12466 24774 12466 24775 12322 24775 12323 24775 12466 24776 12323 24776 12459 24776 12459 24777 12323 24777 12321 24777 12459 24778 12321 24778 12460 24778 12324 24779 12333 24779 12357 24779 12357 24780 12333 24780 12331 24780 12357 24781 12331 24781 12325 24781 12331 24782 12329 24782 12325 24782 12325 24783 12329 24783 12327 24783 12325 24784 12327 24784 12355 24784 12355 24785 12327 24785 12349 24785 12355 24786 12349 24786 12443 24786 12406 24787 12349 24787 12326 24787 12326 24788 12349 24788 12327 24788 12326 24789 12327 24789 12328 24789 12328 24790 12327 24790 12329 24790 12328 24791 12329 24791 12330 24791 12330 24792 12329 24792 12331 24792 12330 24793 12331 24793 12332 24793 12332 24794 12331 24794 12333 24794 12342 24795 12408 24795 12407 24795 12336 24796 12410 24796 12341 24796 12341 24797 12410 24797 12334 24797 12404 24798 12336 24798 12335 24798 12335 24799 12336 24799 12341 24799 12335 24800 12341 24800 12413 24800 12413 24801 12341 24801 12339 24801 12413 24802 12339 24802 12337 24802 12337 24803 12339 24803 12338 24803 12332 24804 12344 24804 12343 24804 12343 24805 12344 24805 12339 24805 12343 24806 12339 24806 12340 24806 12340 24807 12339 24807 12341 24807 12340 24808 12341 24808 12342 24808 12342 24809 12341 24809 12334 24809 12342 24810 12334 24810 12408 24810 12332 24811 12343 24811 12330 24811 12330 24812 12343 24812 12340 24812 12330 24813 12340 24813 12328 24813 12328 24814 12340 24814 12342 24814 12328 24815 12342 24815 12326 24815 12326 24816 12342 24816 12407 24816 12326 24817 12407 24817 12406 24817 12338 24818 12339 24818 12414 24818 12414 24819 12339 24819 12344 24819 12414 24820 12344 24820 12332 24820 12352 24821 12346 24821 12345 24821 12442 24822 12443 24822 12349 24822 12345 24823 12346 24823 12437 24823 12348 24824 12347 24824 12437 24824 12384 24825 12347 24825 12385 24825 12385 24826 12347 24826 12348 24826 12385 24827 12348 24827 12386 24827 12349 24828 12406 24828 12350 24828 12386 24829 12348 24829 12351 24829 12351 24830 12348 24830 12437 24830 12351 24831 12437 24831 12350 24831 12350 24832 12437 24832 12346 24832 12350 24833 12346 24833 12349 24833 12349 24834 12346 24834 12352 24834 12349 24835 12352 24835 12442 24835 12435 24836 12353 24836 12354 24836 12435 24837 12354 24837 12443 24837 12443 24838 12354 24838 12355 24838 12355 24839 12354 24839 12356 24839 12355 24840 12356 24840 12325 24840 12324 24841 12357 24841 12358 24841 12358 24842 12357 24842 12325 24842 12358 24843 12325 24843 12429 24843 12429 24844 12325 24844 12356 24844 12379 24845 12332 24845 12333 24845 12458 24846 12363 24846 12428 24846 12428 24847 12363 24847 12359 24847 12428 24848 12359 24848 12324 24848 12324 24849 12359 24849 12423 24849 12324 24850 12423 24850 12333 24850 12458 24851 12456 24851 12455 24851 12382 24852 12379 24852 12360 24852 12360 24853 12379 24853 12333 24853 12360 24854 12333 24854 12361 24854 12361 24855 12333 24855 12423 24855 12374 24856 12372 24856 12362 24856 12362 24857 12372 24857 12363 24857 12362 24858 12363 24858 12418 24858 12418 24859 12363 24859 12458 24859 12418 24860 12458 24860 12454 24860 12454 24861 12458 24861 12455 24861 12426 24862 12365 24862 12364 24862 12364 24863 12365 24863 12366 24863 12364 24864 12366 24864 12368 24864 12368 24865 12366 24865 12367 24865 12368 24866 12367 24866 12485 24866 12485 24867 12367 24867 12370 24867 12365 24868 12369 24868 12366 24868 12366 24869 12369 24869 12371 24869 12366 24870 12371 24870 12367 24870 12367 24871 12371 24871 12373 24871 12367 24872 12373 24872 12370 24872 12370 24873 12373 24873 12419 24873 12369 24874 12363 24874 12371 24874 12371 24875 12363 24875 12372 24875 12371 24876 12372 24876 12373 24876 12373 24877 12372 24877 12374 24877 12373 24878 12374 24878 12419 24878 12419 24879 12374 24879 12362 24879 12411 24880 12412 24880 12482 24880 12482 24881 12412 24881 12375 24881 12482 24882 12375 24882 12479 24882 12479 24883 12375 24883 12378 24883 12479 24884 12378 24884 12376 24884 12376 24885 12378 24885 12377 24885 12412 24886 12415 24886 12375 24886 12375 24887 12415 24887 12380 24887 12375 24888 12380 24888 12378 24888 12378 24889 12380 24889 12381 24889 12378 24890 12381 24890 12377 24890 12377 24891 12381 24891 12422 24891 12415 24892 12379 24892 12380 24892 12380 24893 12379 24893 12382 24893 12380 24894 12382 24894 12381 24894 12381 24895 12382 24895 12360 24895 12381 24896 12360 24896 12422 24896 12422 24897 12360 24897 12361 24897 12397 24898 12439 24898 12394 24898 12386 24899 12351 24899 12388 24899 12467 24900 12470 24900 12398 24900 12398 24901 12470 24901 12395 24901 12398 24902 12395 24902 12383 24902 12438 24903 12347 24903 12399 24903 12399 24904 12347 24904 12384 24904 12385 24905 12386 24905 12387 24905 12387 24906 12386 24906 12388 24906 12387 24907 12388 24907 12389 24907 12389 24908 12388 24908 12390 24908 12389 24909 12390 24909 12391 24909 12383 24910 12393 24910 12392 24910 12392 24911 12393 24911 12394 24911 12392 24912 12394 24912 12399 24912 12399 24913 12394 24913 12439 24913 12399 24914 12439 24914 12438 24914 12383 24915 12395 24915 12393 24915 12393 24916 12395 24916 12468 24916 12393 24917 12468 24917 12394 24917 12394 24918 12468 24918 12396 24918 12394 24919 12396 24919 12397 24919 12402 24920 12467 24920 12401 24920 12401 24921 12467 24921 12398 24921 12401 24922 12398 24922 12391 24922 12391 24923 12398 24923 12383 24923 12391 24924 12383 24924 12389 24924 12389 24925 12383 24925 12392 24925 12389 24926 12392 24926 12387 24926 12387 24927 12392 24927 12399 24927 12387 24928 12399 24928 12385 24928 12385 24929 12399 24929 12384 24929 12409 24930 12400 24930 12391 24930 12391 24931 12400 24931 12401 24931 12403 24932 12402 24932 12401 24932 12401 24933 12400 24933 12403 24933 12403 24934 12400 24934 12336 24934 12403 24935 12336 24935 12404 24935 12390 24936 12388 24936 12405 24936 12406 24937 12405 24937 12350 24937 12350 24938 12405 24938 12388 24938 12350 24939 12388 24939 12351 24939 12406 24940 12407 24940 12405 24940 12405 24941 12407 24941 12409 24941 12405 24942 12409 24942 12390 24942 12390 24943 12409 24943 12391 24943 12407 24944 12408 24944 12409 24944 12409 24945 12408 24945 12334 24945 12409 24946 12334 24946 12400 24946 12400 24947 12334 24947 12410 24947 12400 24948 12410 24948 12336 24948 12404 24949 12335 24949 12411 24949 12411 24950 12335 24950 12412 24950 12335 24951 12413 24951 12412 24951 12412 24952 12413 24952 12337 24952 12412 24953 12337 24953 12415 24953 12332 24954 12379 24954 12414 24954 12414 24955 12379 24955 12415 24955 12414 24956 12415 24956 12338 24956 12338 24957 12415 24957 12337 24957 12416 24958 12485 24958 12444 24958 12444 24959 12485 24959 12370 24959 12444 24960 12370 24960 12417 24960 12417 24961 12370 24961 12419 24961 12417 24962 12419 24962 12418 24962 12418 24963 12419 24963 12362 24963 12424 24964 12478 24964 12420 24964 12359 24965 12363 24965 12369 24965 12423 24966 12359 24966 12425 24966 12361 24967 12423 24967 12421 24967 12361 24968 12421 24968 12422 24968 12422 24969 12421 24969 12420 24969 12422 24970 12420 24970 12377 24970 12377 24971 12420 24971 12478 24971 12377 24972 12478 24972 12376 24972 12423 24973 12425 24973 12421 24973 12421 24974 12425 24974 12427 24974 12421 24975 12427 24975 12420 24975 12420 24976 12427 24976 12476 24976 12420 24977 12476 24977 12424 24977 12359 24978 12369 24978 12425 24978 12425 24979 12369 24979 12365 24979 12425 24980 12365 24980 12427 24980 12427 24981 12365 24981 12426 24981 12427 24982 12426 24982 12476 24982 12448 24983 12431 24983 12465 24983 12465 24984 12431 24984 12432 24984 12457 24985 12458 24985 12430 24985 12430 24986 12458 24986 12428 24986 12430 24987 12428 24987 12358 24987 12358 24988 12428 24988 12324 24988 12358 24989 12429 24989 12430 24989 12430 24990 12429 24990 12432 24990 12430 24991 12432 24991 12457 24991 12457 24992 12432 24992 12431 24992 12353 24993 12465 24993 12354 24993 12354 24994 12465 24994 12432 24994 12354 24995 12432 24995 12356 24995 12356 24996 12432 24996 12429 24996 12441 24997 12435 24997 12443 24997 12440 24998 12434 24998 12441 24998 12442 24999 12352 24999 12433 24999 12433 25000 12352 25000 12345 25000 12433 25001 12345 25001 12436 25001 12441 25002 12434 25002 12435 25002 12435 25003 12434 25003 12464 25003 12435 25004 12464 25004 12353 25004 12436 25005 12345 25005 12438 25005 12438 25006 12345 25006 12437 25006 12438 25007 12437 25007 12347 25007 12438 25008 12439 25008 12436 25008 12436 25009 12439 25009 12440 25009 12436 25010 12440 25010 12433 25010 12433 25011 12440 25011 12441 25011 12433 25012 12441 25012 12442 25012 12442 25013 12441 25013 12443 25013 12416 25014 12444 25014 12461 25014 12461 25015 12444 25015 12450 25015 12461 25016 12450 25016 12446 25016 12446 25017 12450 25017 12445 25017 12446 25018 12445 25018 12447 25018 12447 25019 12445 25019 12449 25019 12447 25020 12449 25020 12448 25020 12448 25021 12449 25021 12431 25021 12444 25022 12417 25022 12450 25022 12450 25023 12417 25023 12451 25023 12450 25024 12451 25024 12445 25024 12445 25025 12451 25025 12452 25025 12445 25026 12452 25026 12449 25026 12449 25027 12452 25027 12453 25027 12449 25028 12453 25028 12431 25028 12431 25029 12453 25029 12457 25029 12417 25030 12418 25030 12451 25030 12451 25031 12418 25031 12454 25031 12451 25032 12454 25032 12452 25032 12452 25033 12454 25033 12455 25033 12452 25034 12455 25034 12453 25034 12453 25035 12455 25035 12456 25035 12453 25036 12456 25036 12457 25036 12457 25037 12456 25037 12458 25037 12448 25038 12459 25038 12447 25038 12447 25039 12459 25039 12460 25039 12447 25040 12460 25040 12446 25040 12446 25041 12460 25041 12321 25041 12446 25042 12321 25042 12461 25042 12461 25043 12321 25043 12462 25043 12461 25044 12462 25044 12416 25044 12416 25045 12462 25045 12323 25045 12439 25046 12474 25046 12440 25046 12440 25047 12474 25047 12463 25047 12440 25048 12463 25048 12434 25048 12434 25049 12463 25049 12466 25049 12434 25050 12466 25050 12464 25050 12464 25051 12466 25051 12353 25051 12459 25052 12448 25052 12466 25052 12466 25053 12448 25053 12465 25053 12466 25054 12465 25054 12353 25054 12485 25055 12416 25055 12322 25055 12322 25056 12416 25056 12323 25056 12404 25057 12411 25057 12403 25057 12403 25058 12411 25058 12484 25058 12403 25059 12484 25059 12402 25059 12402 25060 12484 25060 12471 25060 12467 25061 12402 25061 12471 25061 12467 25062 12471 25062 12470 25062 12468 25063 12395 25063 12472 25063 12472 25064 12395 25064 12470 25064 12472 25065 12470 25065 12469 25065 12469 25066 12470 25066 12471 25066 12468 25067 12472 25067 12396 25067 12396 25068 12472 25068 12473 25068 12396 25069 12473 25069 12397 25069 12397 25070 12473 25070 12474 25070 12397 25071 12474 25071 12439 25071 12426 25072 12475 25072 12476 25072 12476 25073 12475 25073 12477 25073 12476 25074 12477 25074 12424 25074 12424 25075 12477 25075 12478 25075 12478 25076 12477 25076 12480 25076 12478 25077 12480 25077 12376 25077 12376 25078 12480 25078 12479 25078 12479 25079 12480 25079 12481 25079 12479 25080 12481 25080 12482 25080 12482 25081 12481 25081 12483 25081 12482 25082 12483 25082 12411 25082 12411 25083 12483 25083 12484 25083 12485 25084 12322 25084 12368 25084 12368 25085 12322 25085 12486 25085 12368 25086 12486 25086 12364 25086 12364 25087 12486 25087 12487 25087 12364 25088 12487 25088 12426 25088 12426 25089 12487 25089 12475 25089 12490 25090 12789 25090 12774 25090 12774 25091 12789 25091 12792 25091 12774 25092 12792 25092 12488 25092 12488 25093 12792 25093 12493 25093 12488 25094 12493 25094 12494 25094 12798 25095 12788 25095 12785 25095 12493 25096 12776 25096 12491 25096 12490 25097 12808 25097 12489 25097 12814 25098 12813 25098 12495 25098 12785 25099 12782 25099 12798 25099 12798 25100 12782 25100 12789 25100 12798 25101 12789 25101 12796 25101 12796 25102 12789 25102 12490 25102 12796 25103 12490 25103 12805 25103 12805 25104 12490 25104 12489 25104 12491 25105 12492 25105 12493 25105 12493 25106 12492 25106 12778 25106 12493 25107 12778 25107 12494 25107 12494 25108 12778 25108 12814 25108 12494 25109 12814 25109 12810 25109 12810 25110 12814 25110 12495 25110 12497 25111 12712 25111 12499 25111 12498 25112 12496 25112 12497 25112 12497 25113 12496 25113 12720 25113 12497 25114 12720 25114 12712 25114 12500 25115 12499 25115 12597 25115 12498 25116 12497 25116 12612 25116 12612 25117 12497 25117 12499 25117 12612 25118 12499 25118 12615 25118 12615 25119 12499 25119 12500 25119 12615 25120 12500 25120 12501 25120 12501 25121 12500 25121 12508 25121 12501 25122 12508 25122 12502 25122 12502 25123 12508 25123 12510 25123 12502 25124 12510 25124 12525 25124 12503 25125 12557 25125 12526 25125 12557 25126 12504 25126 12526 25126 12526 25127 12504 25127 12565 25127 12526 25128 12565 25128 12564 25128 12564 25129 12562 25129 12526 25129 12526 25130 12562 25130 12505 25130 12526 25131 12505 25131 12506 25131 12597 25132 12507 25132 12500 25132 12500 25133 12507 25133 12509 25133 12500 25134 12509 25134 12508 25134 12508 25135 12509 25135 12503 25135 12508 25136 12503 25136 12510 25136 12510 25137 12503 25137 12526 25137 12510 25138 12526 25138 12525 25138 12506 25139 12512 25139 12511 25139 12512 25140 12506 25140 12652 25140 12517 25141 12635 25141 12513 25141 12513 25142 12635 25142 12530 25142 12517 25143 12519 25143 12647 25143 12647 25144 12519 25144 12514 25144 12647 25145 12514 25145 12753 25145 12523 25146 12515 25146 12513 25146 12513 25147 12515 25147 12516 25147 12513 25148 12516 25148 12517 25148 12517 25149 12516 25149 12518 25149 12517 25150 12518 25150 12519 25150 12519 25151 12518 25151 12771 25151 12519 25152 12771 25152 12514 25152 12541 25153 12520 25153 12529 25153 12529 25154 12520 25154 12521 25154 12522 25155 12540 25155 12523 25155 12652 25156 12659 25156 12512 25156 12512 25157 12659 25157 12524 25157 12512 25158 12524 25158 12511 25158 12502 25159 12525 25159 12511 25159 12511 25160 12525 25160 12526 25160 12511 25161 12526 25161 12506 25161 12501 25162 12502 25162 12527 25162 12527 25163 12502 25163 12511 25163 12527 25164 12511 25164 12528 25164 12528 25165 12511 25165 12524 25165 12528 25166 12524 25166 12521 25166 12521 25167 12524 25167 12659 25167 12521 25168 12659 25168 12529 25168 12541 25169 12522 25169 12520 25169 12520 25170 12522 25170 12523 25170 12520 25171 12523 25171 12521 25171 12521 25172 12523 25172 12513 25172 12521 25173 12513 25173 12528 25173 12528 25174 12513 25174 12530 25174 12528 25175 12530 25175 12527 25175 12527 25176 12530 25176 12531 25176 12527 25177 12531 25177 12501 25177 12541 25178 12529 25178 12658 25178 12811 25179 12812 25179 12532 25179 12539 25180 12538 25180 12542 25180 12542 25181 12538 25181 12532 25181 12542 25182 12532 25182 12545 25182 12545 25183 12532 25183 12812 25183 12545 25184 12812 25184 12815 25184 12547 25185 12533 25185 12537 25185 12537 25186 12533 25186 12549 25186 12537 25187 12549 25187 12811 25187 12658 25188 12657 25188 12534 25188 12534 25189 12657 25189 12656 25189 12534 25190 12656 25190 12535 25190 12656 25191 12809 25191 12535 25191 12535 25192 12809 25192 12536 25192 12535 25193 12536 25193 12548 25193 12523 25194 12540 25194 12539 25194 12811 25195 12532 25195 12537 25195 12537 25196 12532 25196 12538 25196 12537 25197 12538 25197 12547 25197 12547 25198 12538 25198 12539 25198 12547 25199 12539 25199 12546 25199 12546 25200 12539 25200 12540 25200 12546 25201 12540 25201 12522 25201 12541 25202 12658 25202 12522 25202 12523 25203 12539 25203 12586 25203 12586 25204 12539 25204 12542 25204 12586 25205 12542 25205 12543 25205 12543 25206 12542 25206 12545 25206 12543 25207 12545 25207 12544 25207 12544 25208 12545 25208 12815 25208 12544 25209 12815 25209 12816 25209 12522 25210 12658 25210 12546 25210 12546 25211 12658 25211 12534 25211 12546 25212 12534 25212 12547 25212 12547 25213 12534 25213 12535 25213 12547 25214 12535 25214 12533 25214 12533 25215 12535 25215 12548 25215 12533 25216 12548 25216 12549 25216 12576 25217 12806 25217 12554 25217 12550 25218 12504 25218 12557 25218 12802 25219 12551 25219 12803 25219 12803 25220 12551 25220 12555 25220 12802 25221 12552 25221 12567 25221 12567 25222 12552 25222 12553 25222 12806 25223 12804 25223 12554 25223 12554 25224 12804 25224 12803 25224 12554 25225 12803 25225 12573 25225 12573 25226 12803 25226 12555 25226 12573 25227 12555 25227 12572 25227 12572 25228 12555 25228 12551 25228 12572 25229 12551 25229 12556 25229 12557 25230 12608 25230 12550 25230 12550 25231 12608 25231 12607 25231 12550 25232 12607 25232 12571 25232 12571 25233 12607 25233 12558 25233 12571 25234 12558 25234 12574 25234 12574 25235 12558 25235 12602 25235 12574 25236 12602 25236 12559 25236 12559 25237 12602 25237 12560 25237 12559 25238 12560 25238 12575 25238 12575 25239 12560 25239 12561 25239 12575 25240 12561 25240 12807 25240 12807 25241 12561 25241 12801 25241 12562 25242 12564 25242 12563 25242 12802 25243 12567 25243 12551 25243 12551 25244 12567 25244 12566 25244 12551 25245 12566 25245 12556 25245 12556 25246 12566 25246 12563 25246 12556 25247 12563 25247 12570 25247 12570 25248 12563 25248 12564 25248 12570 25249 12564 25249 12565 25249 12562 25250 12563 25250 12669 25250 12669 25251 12563 25251 12566 25251 12669 25252 12566 25252 12568 25252 12568 25253 12566 25253 12567 25253 12568 25254 12567 25254 12569 25254 12569 25255 12567 25255 12553 25255 12569 25256 12553 25256 12772 25256 12565 25257 12504 25257 12570 25257 12570 25258 12504 25258 12550 25258 12570 25259 12550 25259 12556 25259 12556 25260 12550 25260 12571 25260 12556 25261 12571 25261 12572 25261 12572 25262 12571 25262 12574 25262 12572 25263 12574 25263 12573 25263 12573 25264 12574 25264 12559 25264 12573 25265 12559 25265 12554 25265 12554 25266 12559 25266 12575 25266 12554 25267 12575 25267 12576 25267 12576 25268 12575 25268 12807 25268 12748 25269 12577 25269 12580 25269 12579 25270 12578 25270 12799 25270 12800 25271 12748 25271 12799 25271 12799 25272 12748 25272 12580 25272 12799 25273 12580 25273 12579 25273 12579 25274 12580 25274 12581 25274 12742 25275 12582 25275 12583 25275 12583 25276 12582 25276 12770 25276 12583 25277 12770 25277 12584 25277 12584 25278 12770 25278 12518 25278 12584 25279 12518 25279 12516 25279 12577 25280 12742 25280 12580 25280 12580 25281 12742 25281 12583 25281 12580 25282 12583 25282 12581 25282 12581 25283 12583 25283 12584 25283 12581 25284 12584 25284 12585 25284 12585 25285 12584 25285 12516 25285 12585 25286 12516 25286 12515 25286 12515 25287 12523 25287 12585 25287 12585 25288 12523 25288 12586 25288 12585 25289 12586 25289 12581 25289 12581 25290 12586 25290 12543 25290 12581 25291 12543 25291 12579 25291 12579 25292 12543 25292 12544 25292 12579 25293 12544 25293 12578 25293 12578 25294 12544 25294 12816 25294 12587 25295 12594 25295 12717 25295 12588 25296 12713 25296 12589 25296 12725 25297 12590 25297 12595 25297 12683 25298 12591 25298 12795 25298 12797 25299 12801 25299 12561 25299 12797 25300 12561 25300 12592 25300 12592 25301 12561 25301 12603 25301 12592 25302 12603 25302 12794 25302 12794 25303 12603 25303 12596 25303 12794 25304 12596 25304 12795 25304 12795 25305 12596 25305 12684 25305 12795 25306 12684 25306 12683 25306 12606 25307 12599 25307 12598 25307 12587 25308 12717 25308 12593 25308 12606 25309 12598 25309 12593 25309 12593 25310 12598 25310 12589 25310 12593 25311 12589 25311 12587 25311 12587 25312 12589 25312 12713 25312 12587 25313 12713 25313 12594 25313 12605 25314 12601 25314 12604 25314 12604 25315 12601 25315 12600 25315 12604 25316 12600 25316 12603 25316 12603 25317 12600 25317 12595 25317 12603 25318 12595 25318 12596 25318 12596 25319 12595 25319 12590 25319 12596 25320 12590 25320 12684 25320 12712 25321 12588 25321 12499 25321 12499 25322 12588 25322 12589 25322 12499 25323 12589 25323 12597 25323 12597 25324 12589 25324 12598 25324 12597 25325 12598 25325 12507 25325 12507 25326 12598 25326 12599 25326 12507 25327 12599 25327 12509 25327 12509 25328 12599 25328 12503 25328 12725 25329 12595 25329 12718 25329 12718 25330 12595 25330 12600 25330 12718 25331 12600 25331 12717 25331 12717 25332 12600 25332 12601 25332 12717 25333 12601 25333 12593 25333 12593 25334 12601 25334 12605 25334 12593 25335 12605 25335 12606 25335 12561 25336 12560 25336 12603 25336 12603 25337 12560 25337 12602 25337 12603 25338 12602 25338 12604 25338 12604 25339 12602 25339 12558 25339 12604 25340 12558 25340 12605 25340 12605 25341 12558 25341 12607 25341 12605 25342 12607 25342 12606 25342 12606 25343 12607 25343 12608 25343 12606 25344 12608 25344 12599 25344 12599 25345 12608 25345 12557 25345 12599 25346 12557 25346 12503 25346 12621 25347 12691 25347 12622 25347 12636 25348 12637 25348 12632 25348 12791 25349 12790 25349 12634 25349 12634 25350 12790 25350 12609 25350 12634 25351 12609 25351 12620 25351 12619 25352 12610 25352 12620 25352 12620 25353 12610 25353 12646 25353 12620 25354 12646 25354 12634 25354 12631 25355 12640 25355 12630 25355 12630 25356 12640 25356 12618 25356 12636 25357 12632 25357 12611 25357 12615 25358 12501 25358 12611 25358 12612 25359 12615 25359 12614 25359 12614 25360 12615 25360 12613 25360 12614 25361 12613 25361 12674 25361 12674 25362 12613 25362 12616 25362 12615 25363 12611 25363 12613 25363 12613 25364 12611 25364 12632 25364 12613 25365 12632 25365 12616 25365 12616 25366 12632 25366 12626 25366 12616 25367 12626 25367 12617 25367 12618 25368 12642 25368 12630 25368 12630 25369 12642 25369 12619 25369 12630 25370 12619 25370 12629 25370 12629 25371 12619 25371 12620 25371 12629 25372 12620 25372 12624 25372 12790 25373 12621 25373 12609 25373 12609 25374 12621 25374 12622 25374 12609 25375 12622 25375 12620 25375 12620 25376 12622 25376 12623 25376 12620 25377 12623 25377 12624 25377 12628 25378 12670 25378 12625 25378 12625 25379 12670 25379 12696 25379 12625 25380 12696 25380 12626 25380 12626 25381 12696 25381 12627 25381 12626 25382 12627 25382 12617 25382 12624 25383 12628 25383 12629 25383 12629 25384 12628 25384 12625 25384 12629 25385 12625 25385 12630 25385 12630 25386 12625 25386 12626 25386 12630 25387 12626 25387 12631 25387 12631 25388 12626 25388 12632 25388 12631 25389 12632 25389 12640 25389 12640 25390 12632 25390 12637 25390 12745 25391 12734 25391 12651 25391 12633 25392 12791 25392 12634 25392 12635 25393 12517 25393 12638 25393 12611 25394 12501 25394 12531 25394 12531 25395 12530 25395 12611 25395 12611 25396 12530 25396 12635 25396 12611 25397 12635 25397 12636 25397 12636 25398 12635 25398 12638 25398 12636 25399 12638 25399 12637 25399 12637 25400 12638 25400 12639 25400 12637 25401 12639 25401 12640 25401 12640 25402 12639 25402 12618 25402 12618 25403 12639 25403 12641 25403 12618 25404 12641 25404 12642 25404 12642 25405 12641 25405 12643 25405 12642 25406 12643 25406 12619 25406 12619 25407 12643 25407 12650 25407 12619 25408 12650 25408 12610 25408 12610 25409 12650 25409 12644 25409 12610 25410 12644 25410 12646 25410 12646 25411 12644 25411 12645 25411 12646 25412 12645 25412 12634 25412 12634 25413 12645 25413 12793 25413 12634 25414 12793 25414 12633 25414 12517 25415 12647 25415 12638 25415 12638 25416 12647 25416 12752 25416 12638 25417 12752 25417 12639 25417 12639 25418 12752 25418 12648 25418 12639 25419 12648 25419 12641 25419 12641 25420 12648 25420 12649 25420 12641 25421 12649 25421 12643 25421 12643 25422 12649 25422 12758 25422 12643 25423 12758 25423 12650 25423 12650 25424 12758 25424 12763 25424 12650 25425 12763 25425 12644 25425 12644 25426 12763 25426 12745 25426 12644 25427 12745 25427 12645 25427 12645 25428 12745 25428 12651 25428 12645 25429 12651 25429 12793 25429 12652 25430 12506 25430 12653 25430 12661 25431 12775 25431 12655 25431 12654 25432 12809 25432 12656 25432 12775 25433 12654 25433 12655 25433 12655 25434 12654 25434 12656 25434 12655 25435 12656 25435 12662 25435 12662 25436 12656 25436 12657 25436 12662 25437 12657 25437 12663 25437 12663 25438 12657 25438 12658 25438 12652 25439 12653 25439 12659 25439 12660 25440 12661 25440 12664 25440 12664 25441 12661 25441 12655 25441 12664 25442 12655 25442 12667 25442 12667 25443 12655 25443 12662 25443 12667 25444 12662 25444 12653 25444 12653 25445 12662 25445 12663 25445 12653 25446 12663 25446 12659 25446 12659 25447 12663 25447 12658 25447 12659 25448 12658 25448 12529 25448 12773 25449 12660 25449 12665 25449 12665 25450 12660 25450 12664 25450 12665 25451 12664 25451 12666 25451 12666 25452 12664 25452 12667 25452 12666 25453 12667 25453 12668 25453 12668 25454 12667 25454 12653 25454 12668 25455 12653 25455 12505 25455 12505 25456 12653 25456 12506 25456 12772 25457 12773 25457 12569 25457 12569 25458 12773 25458 12665 25458 12569 25459 12665 25459 12568 25459 12568 25460 12665 25460 12666 25460 12568 25461 12666 25461 12669 25461 12669 25462 12666 25462 12668 25462 12669 25463 12668 25463 12562 25463 12562 25464 12668 25464 12505 25464 12496 25465 12498 25465 12672 25465 12670 25466 12628 25466 12698 25466 12623 25467 12622 25467 12692 25467 12590 25468 12725 25468 12685 25468 12726 25469 12727 25469 12671 25469 12671 25470 12727 25470 12673 25470 12672 25471 12673 25471 12679 25471 12498 25472 12612 25472 12672 25472 12672 25473 12612 25473 12614 25473 12672 25474 12614 25474 12673 25474 12673 25475 12614 25475 12674 25475 12673 25476 12674 25476 12671 25476 12671 25477 12674 25477 12616 25477 12671 25478 12616 25478 12726 25478 12726 25479 12616 25479 12617 25479 12705 25480 12706 25480 12675 25480 12675 25481 12706 25481 12676 25481 12675 25482 12676 25482 12677 25482 12677 25483 12676 25483 12679 25483 12677 25484 12679 25484 12678 25484 12678 25485 12679 25485 12673 25485 12678 25486 12673 25486 12728 25486 12728 25487 12673 25487 12727 25487 12680 25488 12787 25488 12681 25488 12681 25489 12787 25489 12682 25489 12681 25490 12682 25490 12689 25490 12689 25491 12682 25491 12591 25491 12689 25492 12591 25492 12683 25492 12684 25493 12590 25493 12690 25493 12690 25494 12590 25494 12685 25494 12690 25495 12685 25495 12688 25495 12688 25496 12685 25496 12686 25496 12688 25497 12686 25497 12687 25497 12687 25498 12686 25498 12723 25498 12687 25499 12723 25499 12786 25499 12786 25500 12723 25500 12722 25500 12786 25501 12680 25501 12687 25501 12687 25502 12680 25502 12681 25502 12687 25503 12681 25503 12688 25503 12688 25504 12681 25504 12689 25504 12688 25505 12689 25505 12690 25505 12690 25506 12689 25506 12683 25506 12690 25507 12683 25507 12684 25507 12622 25508 12691 25508 12692 25508 12692 25509 12691 25509 12781 25509 12692 25510 12781 25510 12693 25510 12693 25511 12781 25511 12783 25511 12783 25512 12694 25512 12693 25512 12693 25513 12694 25513 12784 25513 12693 25514 12784 25514 12695 25514 12695 25515 12784 25515 12721 25515 12670 25516 12699 25516 12696 25516 12696 25517 12699 25517 12697 25517 12696 25518 12697 25518 12627 25518 12670 25519 12698 25519 12699 25519 12699 25520 12698 25520 12700 25520 12699 25521 12700 25521 12708 25521 12708 25522 12700 25522 12732 25522 12708 25523 12732 25523 12707 25523 12707 25524 12731 25524 12701 25524 12624 25525 12709 25525 12702 25525 12702 25526 12709 25526 12703 25526 12702 25527 12703 25527 12733 25527 12733 25528 12703 25528 12710 25528 12733 25529 12710 25529 12704 25529 12704 25530 12710 25530 12711 25530 12704 25531 12711 25531 12705 25531 12705 25532 12711 25532 12724 25532 12705 25533 12724 25533 12706 25533 12707 25534 12701 25534 12708 25534 12708 25535 12701 25535 12730 25535 12708 25536 12730 25536 12699 25536 12699 25537 12730 25537 12729 25537 12699 25538 12729 25538 12697 25538 12624 25539 12623 25539 12709 25539 12709 25540 12623 25540 12692 25540 12709 25541 12692 25541 12703 25541 12703 25542 12692 25542 12693 25542 12703 25543 12693 25543 12710 25543 12710 25544 12693 25544 12695 25544 12710 25545 12695 25545 12711 25545 12712 25546 12720 25546 12588 25546 12588 25547 12720 25547 12714 25547 12588 25548 12714 25548 12713 25548 12713 25549 12714 25549 12715 25549 12713 25550 12715 25550 12594 25550 12594 25551 12715 25551 12716 25551 12594 25552 12716 25552 12717 25552 12717 25553 12716 25553 12719 25553 12717 25554 12719 25554 12718 25554 12724 25555 12719 25555 12706 25555 12706 25556 12719 25556 12716 25556 12706 25557 12716 25557 12676 25557 12676 25558 12716 25558 12715 25558 12676 25559 12715 25559 12679 25559 12679 25560 12715 25560 12714 25560 12679 25561 12714 25561 12672 25561 12672 25562 12714 25562 12720 25562 12672 25563 12720 25563 12496 25563 12721 25564 12722 25564 12695 25564 12695 25565 12722 25565 12723 25565 12695 25566 12723 25566 12711 25566 12711 25567 12723 25567 12686 25567 12711 25568 12686 25568 12724 25568 12724 25569 12686 25569 12685 25569 12724 25570 12685 25570 12719 25570 12719 25571 12685 25571 12725 25571 12719 25572 12725 25572 12718 25572 12617 25573 12627 25573 12726 25573 12726 25574 12627 25574 12697 25574 12726 25575 12697 25575 12727 25575 12727 25576 12697 25576 12729 25576 12727 25577 12729 25577 12728 25577 12728 25578 12729 25578 12730 25578 12728 25579 12730 25579 12678 25579 12678 25580 12730 25580 12701 25580 12678 25581 12701 25581 12677 25581 12677 25582 12701 25582 12731 25582 12677 25583 12731 25583 12675 25583 12675 25584 12731 25584 12707 25584 12675 25585 12707 25585 12705 25585 12705 25586 12707 25586 12732 25586 12705 25587 12732 25587 12704 25587 12704 25588 12732 25588 12700 25588 12704 25589 12700 25589 12733 25589 12733 25590 12700 25590 12698 25590 12733 25591 12698 25591 12702 25591 12702 25592 12698 25592 12628 25592 12702 25593 12628 25593 12624 25593 12771 25594 12518 25594 12770 25594 12744 25595 12743 25595 12767 25595 12759 25596 12758 25596 12649 25596 12734 25597 12745 25597 12735 25597 12735 25598 12745 25598 12736 25598 12735 25599 12736 25599 12779 25599 12779 25600 12736 25600 12747 25600 12779 25601 12747 25601 12780 25601 12780 25602 12747 25602 12738 25602 12780 25603 12738 25603 12737 25603 12737 25604 12738 25604 12739 25604 12737 25605 12739 25605 12777 25605 12777 25606 12739 25606 12740 25606 12777 25607 12740 25607 12741 25607 12741 25608 12740 25608 12748 25608 12741 25609 12748 25609 12800 25609 12577 25610 12743 25610 12742 25610 12742 25611 12743 25611 12744 25611 12742 25612 12744 25612 12582 25612 12745 25613 12746 25613 12736 25613 12736 25614 12746 25614 12764 25614 12736 25615 12764 25615 12747 25615 12747 25616 12764 25616 12765 25616 12747 25617 12765 25617 12738 25617 12738 25618 12765 25618 12767 25618 12738 25619 12767 25619 12739 25619 12739 25620 12767 25620 12743 25620 12739 25621 12743 25621 12740 25621 12740 25622 12743 25622 12577 25622 12740 25623 12577 25623 12748 25623 12761 25624 12759 25624 12749 25624 12749 25625 12759 25625 12649 25625 12749 25626 12649 25626 12751 25626 12751 25627 12649 25627 12648 25627 12751 25628 12648 25628 12752 25628 12762 25629 12761 25629 12754 25629 12754 25630 12761 25630 12749 25630 12754 25631 12749 25631 12750 25631 12750 25632 12749 25632 12751 25632 12750 25633 12751 25633 12753 25633 12753 25634 12751 25634 12752 25634 12753 25635 12752 25635 12647 25635 12753 25636 12514 25636 12750 25636 12750 25637 12514 25637 12755 25637 12750 25638 12755 25638 12754 25638 12754 25639 12755 25639 12756 25639 12754 25640 12756 25640 12762 25640 12762 25641 12756 25641 12757 25641 12763 25642 12758 25642 12760 25642 12760 25643 12758 25643 12759 25643 12760 25644 12759 25644 12766 25644 12766 25645 12759 25645 12761 25645 12766 25646 12761 25646 12768 25646 12768 25647 12761 25647 12762 25647 12768 25648 12762 25648 12769 25648 12769 25649 12762 25649 12757 25649 12745 25650 12763 25650 12746 25650 12746 25651 12763 25651 12760 25651 12746 25652 12760 25652 12764 25652 12764 25653 12760 25653 12766 25653 12764 25654 12766 25654 12765 25654 12765 25655 12766 25655 12768 25655 12765 25656 12768 25656 12767 25656 12767 25657 12768 25657 12769 25657 12767 25658 12769 25658 12744 25658 12744 25659 12769 25659 12757 25659 12744 25660 12757 25660 12582 25660 12582 25661 12757 25661 12756 25661 12582 25662 12756 25662 12770 25662 12770 25663 12756 25663 12755 25663 12770 25664 12755 25664 12771 25664 12771 25665 12755 25665 12514 25665 12772 25666 12490 25666 12773 25666 12773 25667 12490 25667 12774 25667 12773 25668 12774 25668 12660 25668 12660 25669 12774 25669 12488 25669 12660 25670 12488 25670 12661 25670 12661 25671 12488 25671 12775 25671 12775 25672 12488 25672 12654 25672 12654 25673 12488 25673 12494 25673 12654 25674 12494 25674 12809 25674 12776 25675 12737 25675 12491 25675 12491 25676 12737 25676 12777 25676 12491 25677 12777 25677 12492 25677 12492 25678 12777 25678 12741 25678 12492 25679 12741 25679 12778 25679 12778 25680 12741 25680 12800 25680 12734 25681 12735 25681 12493 25681 12493 25682 12735 25682 12779 25682 12493 25683 12779 25683 12776 25683 12776 25684 12779 25684 12780 25684 12776 25685 12780 25685 12737 25685 12691 25686 12789 25686 12781 25686 12781 25687 12789 25687 12782 25687 12781 25688 12782 25688 12783 25688 12783 25689 12782 25689 12694 25689 12785 25690 12721 25690 12782 25690 12782 25691 12721 25691 12784 25691 12782 25692 12784 25692 12694 25692 12787 25693 12680 25693 12788 25693 12788 25694 12680 25694 12786 25694 12788 25695 12786 25695 12785 25695 12785 25696 12786 25696 12722 25696 12785 25697 12722 25697 12721 25697 12787 25698 12788 25698 12682 25698 12682 25699 12788 25699 12798 25699 12682 25700 12798 25700 12591 25700 12734 25701 12493 25701 12651 25701 12651 25702 12493 25702 12792 25702 12651 25703 12792 25703 12793 25703 12789 25704 12691 25704 12621 25704 12621 25705 12790 25705 12789 25705 12789 25706 12790 25706 12791 25706 12789 25707 12791 25707 12792 25707 12792 25708 12791 25708 12633 25708 12792 25709 12633 25709 12793 25709 12592 25710 12794 25710 12798 25710 12798 25711 12794 25711 12795 25711 12798 25712 12795 25712 12591 25712 12796 25713 12801 25713 12798 25713 12798 25714 12801 25714 12797 25714 12798 25715 12797 25715 12592 25715 12816 25716 12814 25716 12578 25716 12578 25717 12814 25717 12778 25717 12578 25718 12778 25718 12799 25718 12799 25719 12778 25719 12800 25719 12805 25720 12807 25720 12796 25720 12796 25721 12807 25721 12801 25721 12803 25722 12489 25722 12802 25722 12802 25723 12489 25723 12808 25723 12802 25724 12808 25724 12552 25724 12803 25725 12804 25725 12489 25725 12489 25726 12804 25726 12806 25726 12489 25727 12806 25727 12805 25727 12805 25728 12806 25728 12576 25728 12805 25729 12576 25729 12807 25729 12490 25730 12772 25730 12808 25730 12808 25731 12772 25731 12553 25731 12808 25732 12553 25732 12552 25732 12536 25733 12809 25733 12810 25733 12810 25734 12809 25734 12494 25734 12536 25735 12810 25735 12548 25735 12548 25736 12810 25736 12495 25736 12548 25737 12495 25737 12549 25737 12549 25738 12495 25738 12811 25738 12811 25739 12495 25739 12813 25739 12811 25740 12813 25740 12812 25740 12812 25741 12813 25741 12815 25741 12815 25742 12813 25742 12814 25742 12815 25743 12814 25743 12816 25743 12817 25744 12818 25744 13322 25744 13338 25745 13337 25745 13333 25745 13333 25746 13335 25746 13343 25746 13323 25747 13338 25747 13283 25747 13283 25748 13338 25748 13333 25748 13283 25749 13333 25749 13355 25749 13355 25750 13333 25750 13343 25750 12819 25751 13329 25751 13287 25751 13323 25752 13283 25752 13324 25752 13324 25753 13283 25753 13285 25753 13324 25754 13285 25754 12820 25754 12820 25755 13285 25755 13287 25755 12820 25756 13287 25756 13326 25756 13326 25757 13287 25757 13329 25757 13326 25758 13329 25758 13328 25758 13287 25759 13288 25759 12819 25759 12819 25760 13288 25760 13290 25760 12819 25761 13290 25761 12821 25761 12821 25762 13290 25762 13291 25762 12821 25763 13291 25763 13312 25763 13312 25764 13291 25764 13292 25764 13312 25765 13292 25765 13313 25765 13313 25766 13292 25766 13314 25766 12822 25767 12823 25767 12824 25767 12824 25768 12823 25768 13311 25768 12824 25769 13311 25769 12825 25769 13311 25770 12817 25770 12825 25770 12825 25771 12817 25771 13322 25771 12825 25772 13322 25772 12826 25772 12826 25773 13322 25773 12827 25773 12826 25774 12827 25774 13292 25774 13292 25775 12827 25775 12828 25775 13292 25776 12828 25776 13314 25776 12829 25777 13090 25777 12831 25777 12872 25778 12829 25778 12830 25778 12830 25779 12829 25779 12831 25779 12830 25780 12831 25780 12832 25780 12832 25781 12831 25781 12870 25781 12832 25782 12870 25782 12874 25782 12874 25783 12870 25783 12833 25783 12874 25784 12833 25784 12881 25784 12881 25785 12833 25785 13079 25785 12881 25786 13079 25786 12935 25786 12848 25787 12834 25787 12906 25787 12928 25788 12836 25788 12835 25788 12835 25789 12836 25789 12837 25789 12835 25790 12837 25790 12899 25790 12899 25791 12837 25791 12848 25791 12899 25792 12848 25792 12838 25792 12838 25793 12848 25793 12906 25793 12838 25794 12906 25794 12839 25794 12854 25795 12844 25795 12856 25795 12842 25796 12843 25796 12854 25796 12998 25797 12849 25797 12850 25797 12840 25798 12841 25798 12846 25798 12853 25799 12985 25799 12842 25799 12842 25800 12985 25800 12986 25800 12842 25801 12986 25801 12843 25801 12843 25802 12986 25802 12988 25802 12843 25803 12988 25803 13019 25803 12844 25804 12854 25804 12845 25804 12845 25805 12854 25805 12843 25805 12845 25806 12843 25806 12846 25806 12846 25807 12843 25807 13019 25807 12846 25808 13019 25808 12840 25808 12834 25809 12848 25809 12847 25809 12847 25810 12848 25810 12837 25810 12849 25811 12853 25811 12850 25811 12850 25812 12853 25812 12851 25812 12850 25813 12851 25813 12852 25813 12852 25814 12851 25814 12855 25814 12852 25815 12855 25815 12834 25815 12853 25816 12842 25816 12851 25816 12851 25817 12842 25817 12854 25817 12851 25818 12854 25818 12855 25818 12855 25819 12854 25819 12856 25819 12855 25820 12856 25820 12834 25820 12836 25821 12998 25821 12837 25821 12837 25822 12998 25822 12850 25822 12837 25823 12850 25823 12847 25823 12847 25824 12850 25824 12852 25824 12847 25825 12852 25825 12834 25825 13011 25826 13012 25826 12862 25826 12862 25827 13012 25827 13014 25827 12859 25828 12857 25828 12861 25828 12861 25829 12857 25829 12858 25829 13083 25830 12859 25830 12860 25830 12860 25831 12859 25831 12861 25831 12860 25832 12861 25832 13086 25832 13086 25833 12861 25833 12871 25833 13086 25834 12871 25834 13087 25834 12865 25835 12871 25835 12866 25835 12866 25836 12871 25836 12861 25836 12866 25837 12861 25837 12862 25837 12862 25838 12861 25838 12858 25838 12862 25839 12858 25839 13011 25839 13090 25840 12864 25840 12863 25840 12863 25841 12864 25841 13087 25841 13090 25842 12865 25842 12867 25842 12867 25843 12865 25843 12866 25843 12867 25844 12866 25844 12868 25844 12868 25845 12866 25845 12862 25845 12868 25846 12862 25846 12869 25846 12869 25847 12862 25847 13014 25847 12869 25848 13014 25848 13078 25848 13090 25849 12867 25849 12831 25849 12831 25850 12867 25850 12868 25850 12831 25851 12868 25851 12870 25851 12870 25852 12868 25852 12869 25852 12870 25853 12869 25853 12833 25853 12833 25854 12869 25854 13078 25854 12833 25855 13078 25855 13079 25855 13087 25856 12871 25856 12863 25856 12863 25857 12871 25857 12865 25857 12863 25858 12865 25858 13090 25858 12888 25859 12887 25859 12872 25859 12830 25860 12889 25860 12872 25860 12885 25861 12873 25861 12887 25861 12887 25862 12873 25862 12872 25862 12889 25863 12888 25863 12872 25863 12882 25864 13138 25864 12886 25864 12874 25865 12881 25865 12878 25865 13321 25866 13137 25866 12875 25866 13321 25867 12875 25867 12876 25867 12876 25868 12875 25868 12877 25868 12876 25869 12877 25869 13147 25869 13147 25870 12877 25870 12878 25870 13147 25871 12878 25871 12879 25871 12879 25872 12878 25872 12880 25872 12880 25873 12878 25873 12881 25873 12880 25874 12881 25874 12935 25874 13137 25875 12882 25875 12875 25875 12875 25876 12882 25876 12886 25876 12875 25877 12886 25877 12877 25877 12877 25878 12886 25878 12883 25878 12877 25879 12883 25879 12878 25879 12878 25880 12883 25880 12884 25880 12878 25881 12884 25881 12874 25881 12874 25882 12884 25882 12832 25882 13138 25883 12885 25883 12886 25883 12886 25884 12885 25884 12887 25884 12886 25885 12887 25885 12883 25885 12883 25886 12887 25886 12888 25886 12883 25887 12888 25887 12884 25887 12884 25888 12888 25888 12889 25888 12884 25889 12889 25889 12832 25889 12832 25890 12889 25890 12830 25890 12900 25891 12901 25891 12839 25891 12890 25892 13171 25892 12896 25892 12928 25893 12835 25893 12895 25893 12892 25894 13156 25894 12891 25894 13156 25895 12892 25895 12893 25895 12893 25896 12892 25896 12896 25896 12893 25897 12896 25897 13155 25897 13155 25898 12896 25898 12894 25898 12894 25899 12896 25899 13171 25899 12894 25900 13171 25900 13170 25900 12891 25901 12928 25901 12892 25901 12892 25902 12928 25902 12895 25902 12892 25903 12895 25903 12896 25903 12896 25904 12895 25904 12897 25904 12896 25905 12897 25905 12890 25905 13173 25906 12898 25906 12897 25906 12897 25907 12898 25907 13172 25907 12897 25908 13172 25908 12890 25908 12835 25909 12899 25909 12895 25909 12895 25910 12899 25910 12901 25910 12895 25911 12901 25911 12897 25911 12897 25912 12901 25912 12900 25912 12897 25913 12900 25913 13173 25913 13173 25914 12900 25914 12839 25914 12899 25915 12838 25915 12901 25915 12901 25916 12838 25916 12839 25916 12902 25917 12903 25917 13111 25917 12834 25918 12920 25918 12906 25918 12906 25919 12920 25919 12918 25919 12906 25920 12918 25920 12908 25920 13111 25921 12904 25921 12902 25921 12902 25922 12904 25922 12839 25922 12902 25923 12839 25923 12905 25923 12905 25924 12839 25924 12906 25924 12905 25925 12906 25925 12907 25925 12907 25926 12906 25926 12908 25926 12913 25927 12909 25927 12915 25927 12910 25928 13176 25928 12911 25928 12911 25929 13176 25929 12914 25929 12911 25930 12914 25930 13179 25930 13179 25931 12914 25931 12916 25931 13179 25932 12916 25932 13178 25932 13178 25933 12916 25933 12912 25933 13178 25934 12912 25934 12967 25934 12967 25935 12912 25935 12968 25935 13176 25936 12913 25936 12914 25936 12914 25937 12913 25937 12915 25937 12914 25938 12915 25938 12916 25938 12916 25939 12915 25939 12917 25939 12916 25940 12917 25940 12912 25940 12912 25941 12917 25941 12919 25941 12912 25942 12919 25942 12968 25942 12968 25943 12919 25943 12966 25943 12909 25944 12905 25944 12915 25944 12915 25945 12905 25945 12907 25945 12915 25946 12907 25946 12917 25946 12917 25947 12907 25947 12908 25947 12917 25948 12908 25948 12919 25948 12919 25949 12908 25949 12918 25949 12919 25950 12918 25950 12966 25950 12966 25951 12918 25951 12920 25951 13100 25952 13185 25952 12921 25952 12921 25953 13185 25953 13088 25953 12921 25954 13088 25954 13095 25954 13095 25955 13088 25955 12922 25955 13095 25956 12922 25956 12872 25956 12872 25957 12922 25957 12923 25957 12872 25958 12923 25958 12829 25958 12829 25959 12923 25959 13090 25959 12963 25960 12962 25960 12924 25960 12924 25961 12962 25961 13088 25961 12924 25962 13088 25962 12965 25962 12965 25963 13088 25963 13185 25963 13192 25964 12938 25964 12925 25964 13123 25965 12941 25965 13136 25965 13136 25966 12941 25966 12926 25966 13136 25967 12926 25967 13126 25967 13126 25968 12926 25968 13127 25968 12927 25969 13060 25969 12931 25969 12931 25970 13060 25970 12836 25970 12931 25971 12836 25971 12928 25971 12933 25972 12932 25972 12929 25972 12929 25973 12932 25973 12930 25973 12929 25974 12930 25974 13064 25974 12931 25975 13157 25975 12927 25975 12927 25976 13157 25976 12932 25976 12927 25977 12932 25977 13066 25977 13066 25978 12932 25978 12933 25978 13064 25979 12930 25979 12934 25979 12934 25980 12930 25980 12939 25980 12934 25981 12939 25981 13062 25981 12939 25982 12940 25982 13062 25982 13062 25983 12940 25983 12935 25983 13062 25984 12935 25984 13079 25984 12936 25985 12937 25985 13192 25985 13192 25986 12937 25986 12939 25986 13192 25987 12939 25987 12938 25987 12938 25988 12939 25988 12930 25988 13218 25989 13217 25989 13149 25989 12936 25990 13218 25990 12937 25990 12937 25991 13218 25991 13149 25991 12937 25992 13149 25992 12939 25992 12939 25993 13149 25993 13140 25993 12939 25994 13140 25994 12940 25994 12940 25995 13140 25995 13141 25995 12940 25996 13141 25996 12935 25996 12941 25997 12942 25997 12926 25997 12926 25998 12942 25998 12943 25998 12926 25999 12943 25999 12946 25999 12946 26000 12943 26000 12944 26000 12946 26001 12944 26001 12945 26001 13157 26002 13127 26002 12932 26002 12932 26003 13127 26003 12926 26003 12932 26004 12926 26004 12930 26004 12930 26005 12926 26005 12946 26005 12930 26006 12946 26006 12938 26006 12938 26007 12946 26007 12945 26007 12938 26008 12945 26008 12925 26008 12947 26009 12956 26009 12952 26009 13235 26010 12948 26010 12949 26010 12949 26011 12948 26011 12950 26011 12949 26012 12950 26012 13231 26012 13231 26013 12950 26013 12953 26013 13231 26014 12953 26014 12951 26014 12951 26015 12953 26015 12954 26015 12951 26016 12954 26016 13188 26016 13188 26017 12954 26017 12955 26017 12948 26018 12947 26018 12950 26018 12950 26019 12947 26019 12952 26019 12950 26020 12952 26020 12953 26020 12953 26021 12952 26021 12957 26021 12953 26022 12957 26022 12954 26022 12954 26023 12957 26023 12960 26023 12954 26024 12960 26024 12955 26024 12955 26025 12960 26025 12961 26025 12956 26026 13089 26026 12952 26026 12952 26027 13089 26027 12958 26027 12952 26028 12958 26028 12957 26028 12957 26029 12958 26029 12959 26029 12957 26030 12959 26030 12960 26030 12960 26031 12959 26031 12964 26031 12960 26032 12964 26032 12961 26032 12961 26033 12964 26033 13183 26033 13089 26034 13088 26034 12958 26034 12958 26035 13088 26035 12962 26035 12958 26036 12962 26036 12959 26036 12959 26037 12962 26037 12963 26037 12959 26038 12963 26038 12964 26038 12964 26039 12963 26039 12924 26039 12964 26040 12924 26040 13183 26040 13183 26041 12924 26041 12965 26041 12920 26042 12834 26042 12856 26042 12920 26043 12856 26043 12966 26043 12966 26044 12856 26044 12844 26044 12966 26045 12844 26045 12968 26045 12841 26046 12967 26046 12846 26046 12846 26047 12967 26047 12968 26047 12846 26048 12968 26048 12845 26048 12845 26049 12968 26049 12844 26049 12997 26050 12998 26050 12836 26050 12859 26051 13083 26051 13002 26051 12969 26052 12987 26052 12996 26052 12970 26053 12982 26053 12984 26053 13056 26054 12971 26054 12972 26054 12983 26055 12981 26055 12975 26055 12975 26056 12981 26056 12973 26056 12973 26057 12981 26057 12974 26057 12973 26058 12974 26058 12980 26058 12975 26059 12976 26059 12983 26059 12983 26060 12976 26060 13072 26060 12983 26061 13072 26061 12977 26061 12990 26062 13076 26062 12978 26062 12978 26063 13076 26063 12979 26063 12978 26064 12979 26064 13074 26064 13074 26065 12980 26065 12978 26065 12978 26066 12980 26066 12974 26066 12978 26067 12974 26067 12990 26067 12990 26068 12974 26068 12981 26068 12990 26069 12981 26069 12982 26069 12982 26070 12981 26070 12983 26070 12982 26071 12983 26071 12984 26071 12984 26072 12983 26072 12977 26072 12853 26073 12996 26073 12985 26073 12985 26074 12996 26074 12987 26074 12985 26075 12987 26075 12986 26075 12986 26076 12987 26076 12988 26076 13061 26077 13076 26077 12989 26077 12989 26078 13076 26078 12990 26078 12989 26079 12990 26079 13063 26079 13063 26080 12990 26080 12982 26080 13063 26081 12982 26081 13065 26081 13065 26082 12982 26082 12970 26082 13065 26083 12970 26083 12991 26083 12971 26084 13069 26084 12972 26084 12972 26085 13069 26085 12992 26085 12972 26086 12992 26086 13057 26086 13057 26087 12992 26087 12993 26087 13057 26088 12993 26088 13058 26088 13058 26089 12993 26089 12994 26089 13058 26090 12994 26090 13059 26090 13059 26091 12994 26091 12997 26091 12927 26092 13066 26092 12991 26092 13069 26093 12995 26093 12992 26093 12992 26094 12995 26094 12969 26094 12992 26095 12969 26095 12993 26095 12993 26096 12969 26096 12996 26096 12993 26097 12996 26097 12994 26097 12994 26098 12996 26098 12853 26098 12994 26099 12853 26099 12997 26099 12997 26100 12853 26100 12849 26100 12997 26101 12849 26101 12998 26101 13054 26102 13010 26102 12999 26102 12999 26103 13010 26103 13251 26103 12999 26104 13251 26104 13000 26104 13000 26105 13251 26105 13001 26105 13000 26106 13001 26106 13249 26106 12857 26107 12859 26107 13040 26107 13040 26108 12859 26108 13002 26108 13040 26109 13002 26109 13003 26109 13003 26110 13002 26110 13253 26110 13003 26111 13253 26111 13042 26111 13042 26112 13253 26112 13004 26112 13042 26113 13004 26113 13045 26113 13045 26114 13004 26114 13241 26114 13045 26115 13241 26115 13046 26115 13241 26116 13240 26116 13046 26116 13046 26117 13240 26117 13239 26117 13046 26118 13239 26118 13005 26118 13005 26119 13239 26119 13006 26119 13005 26120 13006 26120 13049 26120 13049 26121 13006 26121 13244 26121 13049 26122 13244 26122 13051 26122 13051 26123 13244 26123 13007 26123 13051 26124 13007 26124 13008 26124 13008 26125 13007 26125 13009 26125 13008 26126 13009 26126 13053 26126 13053 26127 13009 26127 13248 26127 13053 26128 13248 26128 13054 26128 13054 26129 13248 26129 13247 26129 13054 26130 13247 26130 13010 26130 13018 26131 13038 26131 13039 26131 12858 26132 13037 26132 13011 26132 13011 26133 13037 26133 13075 26133 13011 26134 13075 26134 13012 26134 13012 26135 13075 26135 13013 26135 13012 26136 13013 26136 13014 26136 13014 26137 13013 26137 13077 26137 13014 26138 13077 26138 13078 26138 13038 26139 13018 26139 13035 26139 13048 26140 13030 26140 13047 26140 13047 26141 13030 26141 13015 26141 13047 26142 13015 26142 13044 26142 13044 26143 13015 26143 13016 26143 13044 26144 13016 26144 13017 26144 13017 26145 13016 26145 13033 26145 13017 26146 13033 26146 13043 26146 13043 26147 13033 26147 13018 26147 13043 26148 13018 26148 13041 26148 13041 26149 13018 26149 13039 26149 12840 26150 13019 26150 13020 26150 13020 26151 13019 26151 13021 26151 13020 26152 13021 26152 13055 26152 13055 26153 13021 26153 13067 26153 13055 26154 13067 26154 13023 26154 13023 26155 13067 26155 13022 26155 13023 26156 13022 26156 13052 26156 13052 26157 13022 26157 13068 26157 13052 26158 13068 26158 13024 26158 13024 26159 13068 26159 13070 26159 13024 26160 13070 26160 13050 26160 13050 26161 13070 26161 13071 26161 13050 26162 13071 26162 13031 26162 13031 26163 13071 26163 13025 26163 13031 26164 13025 26164 13032 26164 13032 26165 13025 26165 13026 26165 13032 26166 13026 26166 13027 26166 13027 26167 13026 26167 13028 26167 13027 26168 13028 26168 13029 26168 13029 26169 13028 26169 13036 26169 13029 26170 13036 26170 13034 26170 13048 26171 13050 26171 13030 26171 13030 26172 13050 26172 13031 26172 13030 26173 13031 26173 13015 26173 13015 26174 13031 26174 13032 26174 13015 26175 13032 26175 13016 26175 13016 26176 13032 26176 13027 26176 13016 26177 13027 26177 13033 26177 13033 26178 13027 26178 13029 26178 13033 26179 13029 26179 13018 26179 13018 26180 13029 26180 13034 26180 13018 26181 13034 26181 13035 26181 13036 26182 13073 26182 13034 26182 13034 26183 13073 26183 13037 26183 13034 26184 13037 26184 13035 26184 13035 26185 13037 26185 12858 26185 13035 26186 12858 26186 13038 26186 13038 26187 12858 26187 12857 26187 13038 26188 12857 26188 13039 26188 13039 26189 12857 26189 13040 26189 13039 26190 13040 26190 13041 26190 13041 26191 13040 26191 13003 26191 13041 26192 13003 26192 13043 26192 13043 26193 13003 26193 13042 26193 13043 26194 13042 26194 13017 26194 13017 26195 13042 26195 13045 26195 13017 26196 13045 26196 13044 26196 13044 26197 13045 26197 13046 26197 13044 26198 13046 26198 13047 26198 13047 26199 13046 26199 13005 26199 13047 26200 13005 26200 13048 26200 13048 26201 13005 26201 13049 26201 13048 26202 13049 26202 13050 26202 13050 26203 13049 26203 13051 26203 13050 26204 13051 26204 13024 26204 13024 26205 13051 26205 13008 26205 13024 26206 13008 26206 13052 26206 13052 26207 13008 26207 13053 26207 13052 26208 13053 26208 13023 26208 13023 26209 13053 26209 13054 26209 13023 26210 13054 26210 13055 26210 13055 26211 13054 26211 12999 26211 13055 26212 12999 26212 13020 26212 13020 26213 12999 26213 13000 26213 13020 26214 13000 26214 12840 26214 12840 26215 13000 26215 13249 26215 12840 26216 13249 26216 12841 26216 13072 26217 13056 26217 12977 26217 12977 26218 13056 26218 12972 26218 12977 26219 12972 26219 12984 26219 12984 26220 12972 26220 13057 26220 12984 26221 13057 26221 12970 26221 12970 26222 13057 26222 13058 26222 12970 26223 13058 26223 12991 26223 12991 26224 13058 26224 13059 26224 12991 26225 13059 26225 12927 26225 12927 26226 13059 26226 12997 26226 12927 26227 12997 26227 13060 26227 13060 26228 12997 26228 12836 26228 13079 26229 13061 26229 13062 26229 13062 26230 13061 26230 12989 26230 13062 26231 12989 26231 12934 26231 12934 26232 12989 26232 13063 26232 12934 26233 13063 26233 13064 26233 13064 26234 13063 26234 13065 26234 13064 26235 13065 26235 12929 26235 12929 26236 13065 26236 12991 26236 12929 26237 12991 26237 12933 26237 12933 26238 12991 26238 13066 26238 13019 26239 12988 26239 13021 26239 13021 26240 12988 26240 12987 26240 13021 26241 12987 26241 13067 26241 13067 26242 12987 26242 12969 26242 13067 26243 12969 26243 13022 26243 13022 26244 12969 26244 12995 26244 13022 26245 12995 26245 13068 26245 13068 26246 12995 26246 13069 26246 13068 26247 13069 26247 13070 26247 13070 26248 13069 26248 12971 26248 13070 26249 12971 26249 13071 26249 13071 26250 12971 26250 13056 26250 13071 26251 13056 26251 13025 26251 13025 26252 13056 26252 13072 26252 13025 26253 13072 26253 13026 26253 13026 26254 13072 26254 12976 26254 13026 26255 12976 26255 13028 26255 13028 26256 12976 26256 12975 26256 13028 26257 12975 26257 13036 26257 13036 26258 12975 26258 12973 26258 13036 26259 12973 26259 13073 26259 13073 26260 12973 26260 12980 26260 13073 26261 12980 26261 13037 26261 13037 26262 12980 26262 13074 26262 13037 26263 13074 26263 13075 26263 13075 26264 13074 26264 12979 26264 13075 26265 12979 26265 13013 26265 13013 26266 12979 26266 13076 26266 13013 26267 13076 26267 13077 26267 13077 26268 13076 26268 13061 26268 13077 26269 13061 26269 13078 26269 13078 26270 13061 26270 13079 26270 13087 26271 12864 26271 13080 26271 13080 26272 13081 26272 13084 26272 12948 26273 13235 26273 13236 26273 13084 26274 12947 26274 12948 26274 12947 26275 13084 26275 12956 26275 12956 26276 13084 26276 13081 26276 12956 26277 13081 26277 13089 26277 13236 26278 13082 26278 13085 26278 13082 26279 13083 26279 13085 26279 13085 26280 13083 26280 12860 26280 13085 26281 12860 26281 13086 26281 12948 26282 13236 26282 13084 26282 13084 26283 13236 26283 13085 26283 13084 26284 13085 26284 13080 26284 13080 26285 13085 26285 13086 26285 13080 26286 13086 26286 13087 26286 13088 26287 13089 26287 12922 26287 12922 26288 13089 26288 13081 26288 12922 26289 13081 26289 12923 26289 12923 26290 13081 26290 13080 26290 12923 26291 13080 26291 13090 26291 13090 26292 13080 26292 12864 26292 13093 26293 13097 26293 13091 26293 13187 26294 13186 26294 13092 26294 13092 26295 13186 26295 13097 26295 13092 26296 13097 26296 13339 26296 13339 26297 13097 26297 13093 26297 13339 26298 13093 26298 13094 26298 13094 26299 13093 26299 13099 26299 13096 26300 13139 26300 13099 26300 13095 26301 13139 26301 12921 26301 12921 26302 13139 26302 13096 26302 12921 26303 13096 26303 13100 26303 13186 26304 13181 26304 13097 26304 13097 26305 13181 26305 13182 26305 13097 26306 13182 26306 13091 26306 13091 26307 13182 26307 13098 26307 13091 26308 13098 26308 13184 26308 13099 26309 13093 26309 13096 26309 13096 26310 13093 26310 13091 26310 13096 26311 13091 26311 13100 26311 13100 26312 13091 26312 13184 26312 13100 26313 13184 26313 13185 26313 13175 26314 13174 26314 13112 26314 13108 26315 13177 26315 13107 26315 13104 26316 13101 26316 13336 26316 13102 26317 13105 26317 13103 26317 13103 26318 13105 26318 13106 26318 13103 26319 13106 26319 13336 26319 13336 26320 13106 26320 13107 26320 13336 26321 13107 26321 13104 26321 13104 26322 13107 26322 13177 26322 13105 26323 13109 26323 13106 26323 13106 26324 13109 26324 13110 26324 13106 26325 13110 26325 13107 26325 13107 26326 13110 26326 13112 26326 13107 26327 13112 26327 13108 26327 13108 26328 13112 26328 13174 26328 13109 26329 12904 26329 13110 26329 13110 26330 12904 26330 13111 26330 13110 26331 13111 26331 13112 26331 13112 26332 13111 26332 12903 26332 13112 26333 12903 26333 13175 26333 13175 26334 12903 26334 12902 26334 13129 26335 13330 26335 13113 26335 13118 26336 13114 26336 13115 26336 13115 26337 13114 26337 13128 26337 13190 26338 13135 26338 13117 26338 13117 26339 13135 26339 13116 26339 13117 26340 13116 26340 13115 26340 13115 26341 13116 26341 13133 26341 13115 26342 13133 26342 13118 26342 13118 26343 13133 26343 13131 26343 13118 26344 13131 26344 13325 26344 13325 26345 13131 26345 13119 26345 13159 26346 13327 26346 13120 26346 13120 26347 13327 26347 13121 26347 13120 26348 13121 26348 13122 26348 13122 26349 13121 26349 13132 26349 13122 26350 13132 26350 13164 26350 13164 26351 13132 26351 13134 26351 13164 26352 13134 26352 13161 26352 13190 26353 12941 26353 13135 26353 13135 26354 12941 26354 13123 26354 13135 26355 13123 26355 13136 26355 13134 26356 13124 26356 13161 26356 13161 26357 13124 26357 13125 26357 13161 26358 13125 26358 13158 26358 13158 26359 13125 26359 13126 26359 13158 26360 13126 26360 13127 26360 13128 26361 13129 26361 13115 26361 13115 26362 13129 26362 13113 26362 13115 26363 13113 26363 13117 26363 13117 26364 13113 26364 13130 26364 13117 26365 13130 26365 13190 26365 13327 26366 13119 26366 13121 26366 13121 26367 13119 26367 13131 26367 13121 26368 13131 26368 13132 26368 13132 26369 13131 26369 13133 26369 13132 26370 13133 26370 13134 26370 13134 26371 13133 26371 13116 26371 13134 26372 13116 26372 13124 26372 13124 26373 13116 26373 13135 26373 13124 26374 13135 26374 13125 26374 13125 26375 13135 26375 13136 26375 13125 26376 13136 26376 13126 26376 13321 26377 13094 26377 13137 26377 13137 26378 13094 26378 13099 26378 13137 26379 13099 26379 12882 26379 12882 26380 13099 26380 13138 26380 13138 26381 13099 26381 13139 26381 13138 26382 13139 26382 12885 26382 12885 26383 13139 26383 12873 26383 12873 26384 13139 26384 13095 26384 12873 26385 13095 26385 12872 26385 13146 26386 12876 26386 13147 26386 13141 26387 13140 26387 13143 26387 13153 26388 13320 26388 13146 26388 13146 26389 13320 26389 13321 26389 13146 26390 13321 26390 12876 26390 12935 26391 13141 26391 13142 26391 13142 26392 13141 26392 13143 26392 13142 26393 13143 26393 13148 26393 13148 26394 13143 26394 13144 26394 13148 26395 13144 26395 13145 26395 13145 26396 13144 26396 13152 26396 13145 26397 13152 26397 13153 26397 13153 26398 13146 26398 13145 26398 13145 26399 13146 26399 13147 26399 13145 26400 13147 26400 13148 26400 13148 26401 13147 26401 12879 26401 13148 26402 12879 26402 13142 26402 13142 26403 12879 26403 12880 26403 13142 26404 12880 26404 12935 26404 13140 26405 13149 26405 13143 26405 13143 26406 13149 26406 13150 26406 13143 26407 13150 26407 13144 26407 13144 26408 13150 26408 13151 26408 13144 26409 13151 26409 13152 26409 13152 26410 13151 26410 13219 26410 13152 26411 13219 26411 13153 26411 13153 26412 13219 26412 13154 26412 13153 26413 13154 26413 13320 26413 13320 26414 13154 26414 13319 26414 13155 26415 12894 26415 13166 26415 13156 26416 12893 26416 13163 26416 13164 26417 13161 26417 13165 26417 13158 26418 13127 26418 13157 26418 13161 26419 13158 26419 13162 26419 13120 26420 13122 26420 13167 26420 13167 26421 13122 26421 13164 26421 13168 26422 13159 26422 13120 26422 13158 26423 13157 26423 13162 26423 13162 26424 13157 26424 12931 26424 13162 26425 12931 26425 13160 26425 13160 26426 12931 26426 12928 26426 13160 26427 12928 26427 12891 26427 13161 26428 13162 26428 13165 26428 13165 26429 13162 26429 13160 26429 13165 26430 13160 26430 13163 26430 13163 26431 13160 26431 12891 26431 13163 26432 12891 26432 13156 26432 13164 26433 13165 26433 13167 26433 13167 26434 13165 26434 13163 26434 13167 26435 13163 26435 13166 26435 13166 26436 13163 26436 12893 26436 13166 26437 12893 26437 13155 26437 13120 26438 13167 26438 13168 26438 13168 26439 13167 26439 13166 26439 13168 26440 13166 26440 13169 26440 13169 26441 13166 26441 12894 26441 13169 26442 12894 26442 13170 26442 13170 26443 13171 26443 13102 26443 13102 26444 13171 26444 13105 26444 13171 26445 12890 26445 13105 26445 13105 26446 12890 26446 13172 26446 13105 26447 13172 26447 13109 26447 12839 26448 12904 26448 13173 26448 13173 26449 12904 26449 13109 26449 13173 26450 13109 26450 12898 26450 12898 26451 13109 26451 13172 26451 13174 26452 13175 26452 12909 26452 12909 26453 13175 26453 12902 26453 12909 26454 12902 26454 12905 26454 13174 26455 12909 26455 13108 26455 13108 26456 12909 26456 12913 26456 13108 26457 12913 26457 13177 26457 13177 26458 12913 26458 13176 26458 13177 26459 13176 26459 13104 26459 13104 26460 13176 26460 12910 26460 13104 26461 12910 26461 13101 26461 12967 26462 13252 26462 13345 26462 12967 26463 13345 26463 13178 26463 13178 26464 13345 26464 13350 26464 13178 26465 13350 26465 13179 26465 13179 26466 13350 26466 13180 26466 13179 26467 13180 26467 12911 26467 12911 26468 13180 26468 13331 26468 12911 26469 13331 26469 12910 26469 13181 26470 12955 26470 13182 26470 13182 26471 12955 26471 12961 26471 13182 26472 12961 26472 13098 26472 13098 26473 12961 26473 13183 26473 13098 26474 13183 26474 13184 26474 13184 26475 13183 26475 12965 26475 13184 26476 12965 26476 13185 26476 13181 26477 13186 26477 12955 26477 12955 26478 13186 26478 13187 26478 12955 26479 13187 26479 13188 26479 13200 26480 13113 26480 13330 26480 13318 26481 13198 26481 13201 26481 13196 26482 13189 26482 13195 26482 12942 26483 12941 26483 13196 26483 13196 26484 12941 26484 13190 26484 13196 26485 13190 26485 13189 26485 13189 26486 13190 26486 13130 26486 13199 26487 12925 26487 12945 26487 13317 26488 13202 26488 13191 26488 13191 26489 13202 26489 13200 26489 13191 26490 13200 26490 13316 26490 13316 26491 13200 26491 13330 26491 13192 26492 12925 26492 13211 26492 13211 26493 12925 26493 13199 26493 13211 26494 13199 26494 13212 26494 13193 26495 12944 26495 12943 26495 13201 26496 13194 26496 13195 26496 13195 26497 13194 26497 13193 26497 13195 26498 13193 26498 13196 26498 13196 26499 13193 26499 12943 26499 13196 26500 12943 26500 12942 26500 13209 26501 13213 26501 13197 26501 13197 26502 13213 26502 13198 26502 13198 26503 13213 26503 13201 26503 13201 26504 13213 26504 13212 26504 13201 26505 13212 26505 13194 26505 13194 26506 13212 26506 13199 26506 13194 26507 13199 26507 13193 26507 13193 26508 13199 26508 12945 26508 13193 26509 12945 26509 12944 26509 13130 26510 13113 26510 13189 26510 13189 26511 13113 26511 13200 26511 13189 26512 13200 26512 13195 26512 13195 26513 13200 26513 13202 26513 13195 26514 13202 26514 13201 26514 13201 26515 13202 26515 13317 26515 13201 26516 13317 26516 13318 26516 12936 26517 13192 26517 13211 26517 13227 26518 13203 26518 13229 26518 13204 26519 13205 26519 13224 26519 13224 26520 13205 26520 13206 26520 13219 26521 13151 26521 13220 26521 13220 26522 13151 26522 13206 26522 13220 26523 13206 26523 13223 26523 13223 26524 13206 26524 13205 26524 13319 26525 13154 26525 13207 26525 13207 26526 13154 26526 13221 26526 13215 26527 13208 26527 13216 26527 13213 26528 13209 26528 13215 26528 13215 26529 13209 26529 13210 26529 13215 26530 13210 26530 13208 26530 13211 26531 13212 26531 13225 26531 13225 26532 13212 26532 13213 26532 13225 26533 13213 26533 13214 26533 13214 26534 13213 26534 13215 26534 13214 26535 13215 26535 13227 26535 13227 26536 13215 26536 13216 26536 13227 26537 13216 26537 13203 26537 13151 26538 13150 26538 13206 26538 13206 26539 13150 26539 13149 26539 13206 26540 13149 26540 13224 26540 13224 26541 13149 26541 13217 26541 13224 26542 13217 26542 13218 26542 12936 26543 13211 26543 13218 26543 13154 26544 13219 26544 13221 26544 13221 26545 13219 26545 13220 26545 13221 26546 13220 26546 13222 26546 13222 26547 13220 26547 13223 26547 13222 26548 13223 26548 13228 26548 13228 26549 13223 26549 13205 26549 13228 26550 13205 26550 13226 26550 13226 26551 13205 26551 13204 26551 13218 26552 13211 26552 13224 26552 13224 26553 13211 26553 13225 26553 13224 26554 13225 26554 13204 26554 13204 26555 13225 26555 13214 26555 13204 26556 13214 26556 13226 26556 13226 26557 13214 26557 13227 26557 13226 26558 13227 26558 13228 26558 13228 26559 13227 26559 13229 26559 13228 26560 13229 26560 13222 26560 13222 26561 13229 26561 13230 26561 13222 26562 13230 26562 13221 26562 13221 26563 13230 26563 13315 26563 13221 26564 13315 26564 13207 26564 13188 26565 13310 26565 13300 26565 13188 26566 13300 26566 12951 26566 12951 26567 13300 26567 13232 26567 12951 26568 13232 26568 13231 26568 13231 26569 13232 26569 13233 26569 13231 26570 13233 26570 12949 26570 12949 26571 13233 26571 13234 26571 12949 26572 13234 26572 13235 26572 13002 26573 13083 26573 13082 26573 13235 26574 13234 26574 13236 26574 13236 26575 13234 26575 13261 26575 13236 26576 13261 26576 13254 26576 13006 26577 13237 26577 13238 26577 13006 26578 13238 26578 13244 26578 13006 26579 13239 26579 13237 26579 13237 26580 13239 26580 13240 26580 13237 26581 13240 26581 13259 26581 13259 26582 13240 26582 13241 26582 13259 26583 13241 26583 13242 26583 13238 26584 13243 26584 13244 26584 13244 26585 13243 26585 13245 26585 13244 26586 13245 26586 13007 26586 13007 26587 13245 26587 13246 26587 13007 26588 13246 26588 13009 26588 13248 26589 13250 26589 13247 26589 13247 26590 13250 26590 13010 26590 13009 26591 13246 26591 13248 26591 13248 26592 13246 26592 13257 26592 13248 26593 13257 26593 13250 26593 13249 26594 13001 26594 13275 26594 13275 26595 13001 26595 13251 26595 13010 26596 13250 26596 13251 26596 13251 26597 13250 26597 13276 26597 13251 26598 13276 26598 13275 26598 13252 26599 12967 26599 13275 26599 13275 26600 12967 26600 12841 26600 13275 26601 12841 26601 13249 26601 13241 26602 13004 26602 13242 26602 13242 26603 13004 26603 13253 26603 13242 26604 13253 26604 13263 26604 13263 26605 13253 26605 13002 26605 13263 26606 13002 26606 13254 26606 13254 26607 13002 26607 13082 26607 13254 26608 13082 26608 13236 26608 13294 26609 13271 26609 13262 26609 13276 26610 13250 26610 13255 26610 13255 26611 13250 26611 13258 26611 13255 26612 13258 26612 13256 26612 13243 26613 13267 26613 13265 26613 13250 26614 13257 26614 13258 26614 13258 26615 13257 26615 13246 26615 13258 26616 13246 26616 13265 26616 13265 26617 13246 26617 13245 26617 13265 26618 13245 26618 13243 26618 13243 26619 13238 26619 13267 26619 13267 26620 13238 26620 13237 26620 13267 26621 13237 26621 13269 26621 13237 26622 13259 26622 13269 26622 13269 26623 13259 26623 13242 26623 13269 26624 13242 26624 13260 26624 13234 26625 13294 26625 13261 26625 13261 26626 13294 26626 13262 26626 13261 26627 13262 26627 13254 26627 13254 26628 13262 26628 13260 26628 13254 26629 13260 26629 13263 26629 13263 26630 13260 26630 13242 26630 13256 26631 13258 26631 13264 26631 13264 26632 13258 26632 13265 26632 13264 26633 13265 26633 13280 26633 13280 26634 13265 26634 13267 26634 13280 26635 13267 26635 13266 26635 13266 26636 13267 26636 13269 26636 13266 26637 13269 26637 13268 26637 13268 26638 13269 26638 13260 26638 13268 26639 13260 26639 13270 26639 13270 26640 13260 26640 13262 26640 13270 26641 13262 26641 13272 26641 13272 26642 13262 26642 13271 26642 13272 26643 13271 26643 13273 26643 13274 26644 13284 26644 13278 26644 13252 26645 13275 26645 13347 26645 13347 26646 13275 26646 13276 26646 13347 26647 13276 26647 13277 26647 13277 26648 13276 26648 13255 26648 13277 26649 13255 26649 13278 26649 13278 26650 13255 26650 13256 26650 13278 26651 13256 26651 13274 26651 13274 26652 13256 26652 13264 26652 13274 26653 13264 26653 13286 26653 13286 26654 13264 26654 13280 26654 13286 26655 13280 26655 13279 26655 13279 26656 13280 26656 13266 26656 13279 26657 13266 26657 13289 26657 13289 26658 13266 26658 13268 26658 13289 26659 13268 26659 13281 26659 13281 26660 13268 26660 13270 26660 13281 26661 13270 26661 13282 26661 13282 26662 13270 26662 13272 26662 13282 26663 13272 26663 13293 26663 13293 26664 13272 26664 13273 26664 13293 26665 13273 26665 13297 26665 13285 26666 13283 26666 13284 26666 13284 26667 13274 26667 13285 26667 13285 26668 13274 26668 13286 26668 13285 26669 13286 26669 13287 26669 13287 26670 13286 26670 13279 26670 13287 26671 13279 26671 13288 26671 13288 26672 13279 26672 13289 26672 13288 26673 13289 26673 13290 26673 13290 26674 13289 26674 13281 26674 13290 26675 13281 26675 13291 26675 13291 26676 13281 26676 13282 26676 13291 26677 13282 26677 13292 26677 13292 26678 13282 26678 13293 26678 13292 26679 13293 26679 12826 26679 12826 26680 13293 26680 13297 26680 12826 26681 13297 26681 12825 26681 12823 26682 12822 26682 13303 26682 13234 26683 13233 26683 13294 26683 13294 26684 13233 26684 13295 26684 13294 26685 13295 26685 13271 26685 13271 26686 13295 26686 13307 26686 13271 26687 13307 26687 13273 26687 13273 26688 13307 26688 13296 26688 13273 26689 13296 26689 13297 26689 13297 26690 13296 26690 12824 26690 13297 26691 12824 26691 12825 26691 13302 26692 13298 26692 13308 26692 13308 26693 13298 26693 13299 26693 13308 26694 13299 26694 13309 26694 13309 26695 13299 26695 13304 26695 13309 26696 13304 26696 13301 26696 13301 26697 13304 26697 13300 26697 13301 26698 13300 26698 13310 26698 13302 26699 12823 26699 13298 26699 13298 26700 12823 26700 13303 26700 13298 26701 13303 26701 13299 26701 13299 26702 13303 26702 13306 26702 13299 26703 13306 26703 13304 26703 13304 26704 13306 26704 13305 26704 13304 26705 13305 26705 13300 26705 13300 26706 13305 26706 13232 26706 12822 26707 12824 26707 13303 26707 13303 26708 12824 26708 13296 26708 13303 26709 13296 26709 13306 26709 13306 26710 13296 26710 13307 26710 13306 26711 13307 26711 13305 26711 13305 26712 13307 26712 13295 26712 13305 26713 13295 26713 13232 26713 13232 26714 13295 26714 13233 26714 12823 26715 13302 26715 13311 26715 13311 26716 13302 26716 13308 26716 13311 26717 13308 26717 13309 26717 13188 26718 13187 26718 13310 26718 13310 26719 13187 26719 13311 26719 13310 26720 13311 26720 13301 26720 13301 26721 13311 26721 13309 26721 13209 26722 13312 26722 13210 26722 13210 26723 13312 26723 13313 26723 13210 26724 13313 26724 13208 26724 13208 26725 13313 26725 13314 26725 13208 26726 13314 26726 13216 26726 13216 26727 13314 26727 13203 26727 13203 26728 13314 26728 12828 26728 13203 26729 12828 26729 13229 26729 13319 26730 13207 26730 12827 26730 12827 26731 13207 26731 13315 26731 12827 26732 13315 26732 12828 26732 12828 26733 13315 26733 13230 26733 12828 26734 13230 26734 13229 26734 13330 26735 13329 26735 13316 26735 13316 26736 13329 26736 12819 26736 13316 26737 12819 26737 13191 26737 13191 26738 12819 26738 13317 26738 13317 26739 12819 26739 12821 26739 13317 26740 12821 26740 13318 26740 13312 26741 13209 26741 13197 26741 13312 26742 13197 26742 12821 26742 12821 26743 13197 26743 13198 26743 12821 26744 13198 26744 13318 26744 13319 26745 12827 26745 13320 26745 13320 26746 12827 26746 13322 26746 13320 26747 13322 26747 13321 26747 13321 26748 13322 26748 13094 26748 13323 26749 13324 26749 13159 26749 13170 26750 13102 26750 13169 26750 13169 26751 13102 26751 13323 26751 13169 26752 13323 26752 13168 26752 13168 26753 13323 26753 13159 26753 13118 26754 13325 26754 13326 26754 13326 26755 13325 26755 13119 26755 13326 26756 13119 26756 12820 26756 12820 26757 13119 26757 13327 26757 12820 26758 13327 26758 13324 26758 13324 26759 13327 26759 13159 26759 13118 26760 13326 26760 13114 26760 13114 26761 13326 26761 13328 26761 13114 26762 13328 26762 13128 26762 13128 26763 13328 26763 13129 26763 13129 26764 13328 26764 13329 26764 13129 26765 13329 26765 13330 26765 13333 26766 13101 26766 12910 26766 12910 26767 13331 26767 13333 26767 13333 26768 13331 26768 13340 26768 13333 26769 13340 26769 13332 26769 13332 26770 13342 26770 13333 26770 13333 26771 13342 26771 13334 26771 13333 26772 13334 26772 13335 26772 13101 26773 13333 26773 13336 26773 13336 26774 13333 26774 13337 26774 13336 26775 13337 26775 13103 26775 13103 26776 13337 26776 13338 26776 13103 26777 13338 26777 13102 26777 13102 26778 13338 26778 13323 26778 13094 26779 13322 26779 13339 26779 13339 26780 13322 26780 12818 26780 13339 26781 12818 26781 13092 26781 13092 26782 12818 26782 12817 26782 13092 26783 12817 26783 13187 26783 13187 26784 12817 26784 13311 26784 13331 26785 13180 26785 13340 26785 13340 26786 13180 26786 13341 26786 13340 26787 13341 26787 13351 26787 13344 26788 13342 26788 13351 26788 13351 26789 13342 26789 13332 26789 13351 26790 13332 26790 13340 26790 13343 26791 13335 26791 13344 26791 13344 26792 13335 26792 13334 26792 13344 26793 13334 26793 13342 26793 13284 26794 13354 26794 13278 26794 13278 26795 13354 26795 13348 26795 13345 26796 13252 26796 13346 26796 13346 26797 13252 26797 13347 26797 13346 26798 13347 26798 13348 26798 13348 26799 13347 26799 13277 26799 13348 26800 13277 26800 13278 26800 13354 26801 13353 26801 13348 26801 13348 26802 13353 26802 13352 26802 13348 26803 13352 26803 13346 26803 13346 26804 13352 26804 13349 26804 13346 26805 13349 26805 13345 26805 13345 26806 13349 26806 13350 26806 13180 26807 13350 26807 13341 26807 13341 26808 13350 26808 13349 26808 13341 26809 13349 26809 13351 26809 13351 26810 13349 26810 13352 26810 13351 26811 13352 26811 13344 26811 13344 26812 13352 26812 13353 26812 13344 26813 13353 26813 13343 26813 13343 26814 13353 26814 13354 26814 13343 26815 13354 26815 13355 26815 13355 26816 13354 26816 13284 26816 13355 26817 13284 26817 13283 26817 13364 26818 13661 26818 13356 26818 13363 26819 13357 26819 13358 26819 13356 26820 13359 26820 13642 26820 13360 26821 13652 26821 13361 26821 13357 26822 13363 26822 13362 26822 13362 26823 13363 26823 13641 26823 13362 26824 13641 26824 13692 26824 13692 26825 13641 26825 13690 26825 13692 26826 13690 26826 13691 26826 13358 26827 13364 26827 13363 26827 13363 26828 13364 26828 13356 26828 13363 26829 13356 26829 13365 26829 13365 26830 13356 26830 13642 26830 13361 26831 13650 26831 13360 26831 13360 26832 13650 26832 13366 26832 13360 26833 13366 26833 13641 26833 13641 26834 13366 26834 13367 26834 13641 26835 13367 26835 13690 26835 13478 26836 13515 26836 13381 26836 13382 26837 13368 26837 13369 26837 13369 26838 13368 26838 13370 26838 13369 26839 13370 26839 13387 26839 13387 26840 13370 26840 13371 26840 13387 26841 13371 26841 13372 26841 13372 26842 13371 26842 13393 26842 13372 26843 13393 26843 13373 26843 13373 26844 13393 26844 13395 26844 13373 26845 13395 26845 13397 26845 13374 26846 13375 26846 13408 26846 13408 26847 13375 26847 13380 26847 13408 26848 13380 26848 13412 26848 13421 26849 13422 26849 13391 26849 13391 26850 13422 26850 13376 26850 13391 26851 13376 26851 13392 26851 13392 26852 13376 26852 13435 26852 13392 26853 13435 26853 13377 26853 13377 26854 13435 26854 13431 26854 13377 26855 13431 26855 13378 26855 13378 26856 13431 26856 13379 26856 13379 26857 13430 26857 13378 26857 13378 26858 13430 26858 13412 26858 13378 26859 13412 26859 13394 26859 13394 26860 13412 26860 13380 26860 13394 26861 13380 26861 13396 26861 13396 26862 13380 26862 13375 26862 13396 26863 13375 26863 13525 26863 13384 26864 13478 26864 13382 26864 13382 26865 13478 26865 13381 26865 13382 26866 13381 26866 13368 26866 13368 26867 13381 26867 13383 26867 13368 26868 13383 26868 13390 26868 13390 26869 13383 26869 13518 26869 13390 26870 13518 26870 13507 26870 13384 26871 13382 26871 13385 26871 13385 26872 13382 26872 13369 26872 13385 26873 13369 26873 13481 26873 13481 26874 13369 26874 13387 26874 13481 26875 13387 26875 13386 26875 13386 26876 13387 26876 13372 26876 13386 26877 13372 26877 13388 26877 13388 26878 13372 26878 13373 26878 13388 26879 13373 26879 13389 26879 13389 26880 13373 26880 13397 26880 13389 26881 13397 26881 13398 26881 13507 26882 13421 26882 13390 26882 13390 26883 13421 26883 13391 26883 13390 26884 13391 26884 13368 26884 13368 26885 13391 26885 13392 26885 13368 26886 13392 26886 13370 26886 13370 26887 13392 26887 13377 26887 13370 26888 13377 26888 13371 26888 13371 26889 13377 26889 13378 26889 13371 26890 13378 26890 13393 26890 13393 26891 13378 26891 13394 26891 13393 26892 13394 26892 13395 26892 13395 26893 13394 26893 13396 26893 13395 26894 13396 26894 13397 26894 13397 26895 13396 26895 13525 26895 13397 26896 13525 26896 13398 26896 13432 26897 13434 26897 13404 26897 13407 26898 13374 26898 13408 26898 13435 26899 13376 26899 13420 26899 13426 26900 13427 26900 13598 26900 13592 26901 13595 26901 13399 26901 13399 26902 13595 26902 13401 26902 13399 26903 13401 26903 13405 26903 13405 26904 13401 26904 13400 26904 13400 26905 13401 26905 13594 26905 13400 26906 13594 26906 13402 26906 13403 26907 13438 26907 13405 26907 13405 26908 13438 26908 13439 26908 13405 26909 13439 26909 13399 26909 13434 26910 13403 26910 13404 26910 13404 26911 13403 26911 13405 26911 13404 26912 13405 26912 13406 26912 13406 26913 13405 26913 13400 26913 13406 26914 13400 26914 13428 26914 13428 26915 13400 26915 13402 26915 13407 26916 13408 26916 13409 26916 13429 26917 13409 26917 13410 26917 13410 26918 13409 26918 13408 26918 13410 26919 13408 26919 13411 26919 13411 26920 13408 26920 13412 26920 13411 26921 13412 26921 13430 26921 13638 26922 13590 26922 13413 26922 13413 26923 13590 26923 13440 26923 13413 26924 13440 26924 13414 26924 13414 26925 13440 26925 13415 26925 13414 26926 13415 26926 13416 26926 13416 26927 13415 26927 13417 26927 13416 26928 13417 26928 13598 26928 13598 26929 13417 26929 13418 26929 13598 26930 13418 26930 13426 26930 13426 26931 13418 26931 13419 26931 13426 26932 13419 26932 13424 26932 13424 26933 13419 26933 13420 26933 13424 26934 13420 26934 13423 26934 13423 26935 13420 26935 13376 26935 13423 26936 13376 26936 13422 26936 13421 26937 13507 26937 13506 26937 13422 26938 13421 26938 13423 26938 13423 26939 13421 26939 13506 26939 13423 26940 13506 26940 13424 26940 13424 26941 13506 26941 13425 26941 13424 26942 13425 26942 13426 26942 13426 26943 13425 26943 13519 26943 13426 26944 13519 26944 13427 26944 13427 26945 13519 26945 13597 26945 13428 26946 13429 26946 13406 26946 13406 26947 13429 26947 13410 26947 13406 26948 13410 26948 13404 26948 13404 26949 13410 26949 13411 26949 13404 26950 13411 26950 13432 26950 13432 26951 13411 26951 13430 26951 13432 26952 13430 26952 13379 26952 13379 26953 13431 26953 13432 26953 13432 26954 13431 26954 13433 26954 13432 26955 13433 26955 13434 26955 13434 26956 13433 26956 13436 26956 13434 26957 13436 26957 13403 26957 13403 26958 13436 26958 13437 26958 13403 26959 13437 26959 13438 26959 13431 26960 13435 26960 13433 26960 13433 26961 13435 26961 13420 26961 13433 26962 13420 26962 13436 26962 13436 26963 13420 26963 13419 26963 13436 26964 13419 26964 13437 26964 13437 26965 13419 26965 13418 26965 13437 26966 13418 26966 13438 26966 13438 26967 13418 26967 13417 26967 13438 26968 13417 26968 13439 26968 13439 26969 13417 26969 13415 26969 13439 26970 13415 26970 13399 26970 13399 26971 13415 26971 13440 26971 13399 26972 13440 26972 13592 26972 13592 26973 13440 26973 13590 26973 13616 26974 13615 26974 13483 26974 13476 26975 13513 26975 13442 26975 13389 26976 13398 26976 13441 26976 13475 26977 13623 26977 13466 26977 13446 26978 13516 26978 13448 26978 13442 26979 13492 26979 13494 26979 13492 26980 13442 26980 13447 26980 13614 26981 13454 26981 13453 26981 13443 26982 13505 26982 13490 26982 13451 26983 13452 26983 13444 26983 13444 26984 13452 26984 13495 26984 13615 26985 13614 26985 13483 26985 13483 26986 13614 26986 13453 26986 13483 26987 13453 26987 13486 26987 13486 26988 13453 26988 13487 26988 13495 26989 13493 26989 13444 26989 13444 26990 13493 26990 13491 26990 13444 26991 13491 26991 13451 26991 13451 26992 13491 26992 13445 26992 13451 26993 13445 26993 13449 26993 13449 26994 13445 26994 13489 26994 13513 26995 13446 26995 13442 26995 13442 26996 13446 26996 13448 26996 13442 26997 13448 26997 13447 26997 13447 26998 13448 26998 13479 26998 13447 26999 13479 26999 13490 26999 13490 27000 13479 27000 13480 27000 13490 27001 13480 27001 13443 27001 13443 27002 13480 27002 13481 27002 13449 27003 13450 27003 13451 27003 13451 27004 13450 27004 13487 27004 13451 27005 13487 27005 13452 27005 13452 27006 13487 27006 13453 27006 13452 27007 13453 27007 13495 27007 13495 27008 13453 27008 13454 27008 13495 27009 13454 27009 13613 27009 13466 27010 13623 27010 13465 27010 13465 27011 13623 27011 13455 27011 13465 27012 13455 27012 13464 27012 13464 27013 13455 27013 13457 27013 13457 27014 13455 27014 13456 27014 13457 27015 13456 27015 13458 27015 13624 27016 13460 27016 13625 27016 13625 27017 13460 27017 13458 27017 13625 27018 13458 27018 13459 27018 13459 27019 13458 27019 13456 27019 13460 27020 13611 27020 13496 27020 13474 27021 13473 27021 13627 27021 13627 27022 13473 27022 13470 27022 13388 27023 13389 27023 13461 27023 13461 27024 13389 27024 13441 27024 13461 27025 13441 27025 13470 27025 13470 27026 13441 27026 13462 27026 13470 27027 13462 27027 13627 27027 13460 27028 13496 27028 13458 27028 13458 27029 13496 27029 13463 27029 13458 27030 13463 27030 13457 27030 13457 27031 13463 27031 13497 27031 13457 27032 13497 27032 13464 27032 13464 27033 13497 27033 13498 27033 13464 27034 13498 27034 13465 27034 13465 27035 13498 27035 13500 27035 13465 27036 13500 27036 13466 27036 13466 27037 13500 27037 13503 27037 13466 27038 13503 27038 13472 27038 13472 27039 13503 27039 13504 27039 13472 27040 13504 27040 13471 27040 13471 27041 13504 27041 13468 27041 13471 27042 13468 27042 13467 27042 13467 27043 13468 27043 13469 27043 13467 27044 13469 27044 13386 27044 13386 27045 13388 27045 13467 27045 13467 27046 13388 27046 13461 27046 13467 27047 13461 27047 13471 27047 13471 27048 13461 27048 13470 27048 13471 27049 13470 27049 13472 27049 13472 27050 13470 27050 13473 27050 13472 27051 13473 27051 13466 27051 13466 27052 13473 27052 13474 27052 13466 27053 13474 27053 13475 27053 13517 27054 13476 27054 13605 27054 13605 27055 13476 27055 13442 27055 13605 27056 13442 27056 13477 27056 13477 27057 13442 27057 13494 27057 13516 27058 13515 27058 13448 27058 13448 27059 13515 27059 13478 27059 13448 27060 13478 27060 13479 27060 13479 27061 13478 27061 13384 27061 13479 27062 13384 27062 13480 27062 13480 27063 13384 27063 13385 27063 13480 27064 13385 27064 13481 27064 13482 27065 13616 27065 13484 27065 13484 27066 13616 27066 13483 27066 13484 27067 13483 27067 13485 27067 13485 27068 13483 27068 13486 27068 13485 27069 13486 27069 13499 27069 13499 27070 13486 27070 13487 27070 13499 27071 13487 27071 13501 27071 13501 27072 13487 27072 13450 27072 13501 27073 13450 27073 13502 27073 13502 27074 13450 27074 13449 27074 13502 27075 13449 27075 13488 27075 13488 27076 13449 27076 13489 27076 13488 27077 13489 27077 13505 27077 13505 27078 13489 27078 13445 27078 13505 27079 13445 27079 13490 27079 13490 27080 13445 27080 13491 27080 13490 27081 13491 27081 13447 27081 13447 27082 13491 27082 13493 27082 13447 27083 13493 27083 13492 27083 13492 27084 13493 27084 13495 27084 13492 27085 13495 27085 13494 27085 13494 27086 13495 27086 13613 27086 13494 27087 13613 27087 13477 27087 13611 27088 13482 27088 13496 27088 13496 27089 13482 27089 13484 27089 13496 27090 13484 27090 13463 27090 13463 27091 13484 27091 13485 27091 13463 27092 13485 27092 13497 27092 13497 27093 13485 27093 13499 27093 13497 27094 13499 27094 13498 27094 13498 27095 13499 27095 13501 27095 13498 27096 13501 27096 13500 27096 13500 27097 13501 27097 13502 27097 13500 27098 13502 27098 13503 27098 13503 27099 13502 27099 13488 27099 13503 27100 13488 27100 13504 27100 13504 27101 13488 27101 13505 27101 13504 27102 13505 27102 13468 27102 13468 27103 13505 27103 13443 27103 13468 27104 13443 27104 13469 27104 13469 27105 13443 27105 13481 27105 13469 27106 13481 27106 13386 27106 13425 27107 13506 27107 13509 27107 13506 27108 13507 27108 13509 27108 13509 27109 13507 27109 13518 27109 13509 27110 13518 27110 13510 27110 13518 27111 13508 27111 13510 27111 13510 27112 13508 27112 13530 27112 13510 27113 13530 27113 13512 27113 13556 27114 13509 27114 13511 27114 13511 27115 13509 27115 13510 27115 13511 27116 13510 27116 13559 27116 13559 27117 13510 27117 13512 27117 13513 27118 13476 27118 13517 27118 13381 27119 13515 27119 13514 27119 13514 27120 13515 27120 13516 27120 13514 27121 13516 27121 13446 27121 13446 27122 13513 27122 13514 27122 13514 27123 13513 27123 13517 27123 13514 27124 13517 27124 13381 27124 13381 27125 13517 27125 13508 27125 13381 27126 13508 27126 13383 27126 13383 27127 13508 27127 13518 27127 13635 27128 13597 27128 13509 27128 13509 27129 13597 27129 13519 27129 13509 27130 13519 27130 13425 27130 13520 27131 13580 27131 13521 27131 13521 27132 13580 27132 13522 27132 13635 27133 13520 27133 13597 27133 13597 27134 13520 27134 13521 27134 13597 27135 13521 27135 13523 27135 13523 27136 13521 27136 13522 27136 13523 27137 13522 27137 13571 27137 13374 27138 13596 27138 13375 27138 13375 27139 13596 27139 13524 27139 13375 27140 13524 27140 13525 27140 13525 27141 13524 27141 13626 27141 13525 27142 13626 27142 13398 27142 13543 27143 13542 27143 13651 27143 13526 27144 13565 27144 13534 27144 13534 27145 13565 27145 13527 27145 13529 27146 13531 27146 13528 27146 13528 27147 13531 27147 13527 27147 13528 27148 13527 27148 13566 27148 13566 27149 13527 27149 13565 27149 13566 27150 13567 27150 13528 27150 13528 27151 13567 27151 13557 27151 13528 27152 13557 27152 13529 27152 13512 27153 13530 27153 13529 27153 13529 27154 13530 27154 13532 27154 13529 27155 13532 27155 13531 27155 13531 27156 13532 27156 13533 27156 13531 27157 13533 27157 13527 27157 13527 27158 13533 27158 13621 27158 13527 27159 13621 27159 13534 27159 13536 27160 13555 27160 13535 27160 13632 27161 13634 27161 13561 27161 13561 27162 13634 27162 13536 27162 13561 27163 13536 27163 13562 27163 13562 27164 13536 27164 13535 27164 13546 27165 13541 27165 13537 27165 13538 27166 13631 27166 13654 27166 13654 27167 13631 27167 13560 27167 13554 27168 13543 27168 13539 27168 13539 27169 13543 27169 13651 27169 13539 27170 13651 27170 13551 27170 13551 27171 13651 27171 13540 27171 13551 27172 13540 27172 13550 27172 13550 27173 13540 27173 13653 27173 13550 27174 13653 27174 13541 27174 13612 27175 13542 27175 13617 27175 13617 27176 13542 27176 13543 27176 13617 27177 13543 27177 13544 27177 13544 27178 13543 27178 13554 27178 13544 27179 13554 27179 13618 27179 13618 27180 13554 27180 13545 27180 13618 27181 13545 27181 13620 27181 13537 27182 13656 27182 13546 27182 13546 27183 13656 27183 13569 27183 13546 27184 13569 27184 13552 27184 13552 27185 13569 27185 13568 27185 13552 27186 13568 27186 13547 27186 13547 27187 13568 27187 13548 27187 13547 27188 13548 27188 13553 27188 13553 27189 13548 27189 13549 27189 13541 27190 13546 27190 13550 27190 13550 27191 13546 27191 13552 27191 13550 27192 13552 27192 13551 27192 13551 27193 13552 27193 13547 27193 13551 27194 13547 27194 13539 27194 13539 27195 13547 27195 13553 27195 13539 27196 13553 27196 13554 27196 13554 27197 13553 27197 13549 27197 13554 27198 13549 27198 13545 27198 13511 27199 13555 27199 13556 27199 13556 27200 13555 27200 13536 27200 13556 27201 13536 27201 13509 27201 13509 27202 13536 27202 13634 27202 13567 27203 13564 27203 13557 27203 13557 27204 13564 27204 13558 27204 13557 27205 13558 27205 13529 27205 13529 27206 13558 27206 13559 27206 13529 27207 13559 27207 13512 27207 13631 27208 13632 27208 13560 27208 13560 27209 13632 27209 13561 27209 13560 27210 13561 27210 13570 27210 13570 27211 13561 27211 13562 27211 13570 27212 13562 27212 13563 27212 13563 27213 13562 27213 13535 27213 13563 27214 13535 27214 13564 27214 13564 27215 13535 27215 13555 27215 13564 27216 13555 27216 13558 27216 13558 27217 13555 27217 13511 27217 13558 27218 13511 27218 13559 27218 13526 27219 13620 27219 13565 27219 13565 27220 13620 27220 13545 27220 13565 27221 13545 27221 13566 27221 13566 27222 13545 27222 13549 27222 13566 27223 13549 27223 13567 27223 13567 27224 13549 27224 13548 27224 13567 27225 13548 27225 13564 27225 13564 27226 13548 27226 13568 27226 13564 27227 13568 27227 13563 27227 13563 27228 13568 27228 13569 27228 13563 27229 13569 27229 13570 27229 13570 27230 13569 27230 13656 27230 13570 27231 13656 27231 13560 27231 13560 27232 13656 27232 13655 27232 13560 27233 13655 27233 13654 27233 13580 27234 13520 27234 13581 27234 13571 27235 13522 27235 13572 27235 13573 27236 13644 27236 13574 27236 13643 27237 13573 27237 13588 27237 13588 27238 13573 27238 13574 27238 13588 27239 13574 27239 13582 27239 13581 27240 13575 27240 13587 27240 13587 27241 13575 27241 13576 27241 13587 27242 13576 27242 13578 27242 13576 27243 13577 27243 13578 27243 13578 27244 13577 27244 13579 27244 13578 27245 13579 27245 13589 27245 13571 27246 13572 27246 13523 27246 13580 27247 13581 27247 13522 27247 13572 27248 13582 27248 13583 27248 13583 27249 13582 27249 13574 27249 13583 27250 13574 27250 13584 27250 13584 27251 13574 27251 13644 27251 13584 27252 13644 27252 13585 27252 13523 27253 13572 27253 13586 27253 13586 27254 13572 27254 13583 27254 13586 27255 13583 27255 13599 27255 13599 27256 13583 27256 13584 27256 13599 27257 13584 27257 13600 27257 13600 27258 13584 27258 13585 27258 13600 27259 13585 27259 13601 27259 13522 27260 13581 27260 13572 27260 13572 27261 13581 27261 13587 27261 13572 27262 13587 27262 13582 27262 13582 27263 13587 27263 13578 27263 13582 27264 13578 27264 13588 27264 13588 27265 13578 27265 13589 27265 13588 27266 13589 27266 13643 27266 13638 27267 13639 27267 13590 27267 13590 27268 13639 27268 13591 27268 13590 27269 13591 27269 13592 27269 13592 27270 13591 27270 13665 27270 13592 27271 13665 27271 13595 27271 13428 27272 13402 27272 13593 27272 13593 27273 13402 27273 13594 27273 13593 27274 13594 27274 13665 27274 13665 27275 13594 27275 13401 27275 13665 27276 13401 27276 13595 27276 13374 27277 13407 27277 13596 27277 13596 27278 13407 27278 13409 27278 13596 27279 13409 27279 13593 27279 13593 27280 13409 27280 13429 27280 13593 27281 13429 27281 13428 27281 13597 27282 13523 27282 13427 27282 13427 27283 13523 27283 13586 27283 13427 27284 13586 27284 13598 27284 13598 27285 13586 27285 13599 27285 13598 27286 13599 27286 13416 27286 13416 27287 13599 27287 13600 27287 13416 27288 13600 27288 13414 27288 13414 27289 13600 27289 13413 27289 13413 27290 13600 27290 13601 27290 13413 27291 13601 27291 13638 27291 13606 27292 13508 27292 13517 27292 13616 27293 13482 27293 13603 27293 13608 27294 13602 27294 13607 27294 13607 27295 13602 27295 13603 27295 13607 27296 13603 27296 13604 27296 13604 27297 13603 27297 13482 27297 13517 27298 13605 27298 13606 27298 13606 27299 13605 27299 13477 27299 13606 27300 13477 27300 13608 27300 13607 27301 13621 27301 13608 27301 13608 27302 13621 27302 13533 27302 13608 27303 13533 27303 13606 27303 13606 27304 13533 27304 13532 27304 13606 27305 13532 27305 13508 27305 13508 27306 13532 27306 13530 27306 13624 27307 13645 27307 13460 27307 13460 27308 13645 27308 13609 27308 13460 27309 13609 27309 13611 27309 13611 27310 13609 27310 13610 27310 13611 27311 13610 27311 13482 27311 13482 27312 13610 27312 13619 27312 13482 27313 13619 27313 13604 27313 13645 27314 13612 27314 13617 27314 13477 27315 13613 27315 13608 27315 13608 27316 13613 27316 13454 27316 13608 27317 13454 27317 13602 27317 13602 27318 13454 27318 13614 27318 13602 27319 13614 27319 13603 27319 13603 27320 13614 27320 13615 27320 13603 27321 13615 27321 13616 27321 13645 27322 13617 27322 13609 27322 13609 27323 13617 27323 13544 27323 13609 27324 13544 27324 13610 27324 13610 27325 13544 27325 13618 27325 13610 27326 13618 27326 13619 27326 13619 27327 13618 27327 13620 27327 13619 27328 13620 27328 13604 27328 13604 27329 13620 27329 13526 27329 13604 27330 13526 27330 13607 27330 13607 27331 13526 27331 13534 27331 13607 27332 13534 27332 13621 27332 13475 27333 13622 27333 13623 27333 13623 27334 13622 27334 13679 27334 13646 27335 13624 27335 13679 27335 13679 27336 13624 27336 13625 27336 13679 27337 13625 27337 13459 27337 13459 27338 13456 27338 13679 27338 13679 27339 13456 27339 13455 27339 13679 27340 13455 27340 13623 27340 13398 27341 13626 27341 13441 27341 13441 27342 13626 27342 13683 27342 13475 27343 13474 27343 13622 27343 13622 27344 13474 27344 13627 27344 13622 27345 13627 27345 13683 27345 13683 27346 13627 27346 13462 27346 13683 27347 13462 27347 13441 27347 13628 27348 13577 27348 13629 27348 13629 27349 13577 27349 13576 27349 13629 27350 13576 27350 13633 27350 13633 27351 13576 27351 13575 27351 13633 27352 13575 27352 13630 27352 13630 27353 13575 27353 13581 27353 13630 27354 13581 27354 13635 27354 13635 27355 13581 27355 13520 27355 13538 27356 13628 27356 13631 27356 13631 27357 13628 27357 13629 27357 13631 27358 13629 27358 13632 27358 13632 27359 13629 27359 13633 27359 13632 27360 13633 27360 13634 27360 13634 27361 13633 27361 13630 27361 13634 27362 13630 27362 13509 27362 13509 27363 13630 27363 13635 27363 13661 27364 13636 27364 13356 27364 13356 27365 13636 27365 13637 27365 13356 27366 13637 27366 13662 27366 13638 27367 13601 27367 13639 27367 13639 27368 13601 27368 13356 27368 13639 27369 13356 27369 13640 27369 13640 27370 13356 27370 13662 27370 13363 27371 13577 27371 13641 27371 13641 27372 13577 27372 13628 27372 13641 27373 13628 27373 13538 27373 13573 27374 13643 27374 13642 27374 13365 27375 13579 27375 13363 27375 13363 27376 13579 27376 13577 27376 13642 27377 13643 27377 13365 27377 13365 27378 13643 27378 13589 27378 13365 27379 13589 27379 13579 27379 13573 27380 13642 27380 13644 27380 13644 27381 13642 27381 13359 27381 13644 27382 13359 27382 13585 27382 13585 27383 13359 27383 13356 27383 13585 27384 13356 27384 13601 27384 13645 27385 13624 27385 13646 27385 13645 27386 13646 27386 13612 27386 13612 27387 13646 27387 13366 27387 13366 27388 13646 27388 13647 27388 13366 27389 13647 27389 13648 27389 13648 27390 13649 27390 13366 27390 13366 27391 13649 27391 13680 27391 13366 27392 13680 27392 13367 27392 13612 27393 13366 27393 13542 27393 13542 27394 13366 27394 13650 27394 13542 27395 13650 27395 13651 27395 13651 27396 13650 27396 13361 27396 13537 27397 13541 27397 13652 27397 13652 27398 13541 27398 13653 27398 13652 27399 13653 27399 13361 27399 13361 27400 13653 27400 13540 27400 13361 27401 13540 27401 13651 27401 13360 27402 13641 27402 13538 27402 13538 27403 13654 27403 13360 27403 13360 27404 13654 27404 13655 27404 13360 27405 13655 27405 13652 27405 13652 27406 13655 27406 13656 27406 13652 27407 13656 27407 13537 27407 13664 27408 13591 27408 13639 27408 13596 27409 13593 27409 13673 27409 13673 27410 13593 27410 13668 27410 13673 27411 13668 27411 13657 27411 13657 27412 13668 27412 13659 27412 13657 27413 13659 27413 13658 27413 13658 27414 13659 27414 13660 27414 13658 27415 13660 27415 13676 27415 13676 27416 13660 27416 13358 27416 13676 27417 13358 27417 13357 27417 13661 27418 13364 27418 13636 27418 13636 27419 13364 27419 13666 27419 13636 27420 13666 27420 13667 27420 13639 27421 13640 27421 13664 27421 13664 27422 13640 27422 13662 27422 13664 27423 13662 27423 13663 27423 13663 27424 13662 27424 13637 27424 13637 27425 13636 27425 13663 27425 13663 27426 13636 27426 13667 27426 13663 27427 13667 27427 13664 27427 13664 27428 13667 27428 13669 27428 13664 27429 13669 27429 13591 27429 13591 27430 13669 27430 13665 27430 13364 27431 13358 27431 13666 27431 13666 27432 13358 27432 13660 27432 13666 27433 13660 27433 13667 27433 13667 27434 13660 27434 13659 27434 13667 27435 13659 27435 13669 27435 13669 27436 13659 27436 13668 27436 13669 27437 13668 27437 13665 27437 13665 27438 13668 27438 13593 27438 13684 27439 13626 27439 13524 27439 13675 27440 13674 27440 13670 27440 13670 27441 13674 27441 13671 27441 13670 27442 13671 27442 13682 27442 13682 27443 13671 27443 13672 27443 13672 27444 13671 27444 13362 27444 13672 27445 13362 27445 13692 27445 13596 27446 13673 27446 13524 27446 13524 27447 13673 27447 13674 27447 13524 27448 13674 27448 13684 27448 13684 27449 13674 27449 13675 27449 13673 27450 13657 27450 13674 27450 13674 27451 13657 27451 13658 27451 13674 27452 13658 27452 13671 27452 13671 27453 13658 27453 13676 27453 13671 27454 13676 27454 13362 27454 13362 27455 13676 27455 13357 27455 13680 27456 13649 27456 13677 27456 13647 27457 13646 27457 13679 27457 13649 27458 13648 27458 13677 27458 13677 27459 13648 27459 13647 27459 13677 27460 13647 27460 13678 27460 13678 27461 13647 27461 13679 27461 13690 27462 13367 27462 13680 27462 13687 27463 13670 27463 13681 27463 13681 27464 13670 27464 13682 27464 13681 27465 13682 27465 13672 27465 13683 27466 13626 27466 13688 27466 13688 27467 13626 27467 13684 27467 13688 27468 13684 27468 13687 27468 13687 27469 13684 27469 13675 27469 13687 27470 13675 27470 13670 27470 13681 27471 13685 27471 13687 27471 13687 27472 13685 27472 13686 27472 13687 27473 13686 27473 13688 27473 13688 27474 13686 27474 13689 27474 13688 27475 13689 27475 13683 27475 13683 27476 13689 27476 13622 27476 13679 27477 13622 27477 13678 27477 13678 27478 13622 27478 13689 27478 13678 27479 13689 27479 13677 27479 13677 27480 13689 27480 13686 27480 13677 27481 13686 27481 13680 27481 13680 27482 13686 27482 13685 27482 13680 27483 13685 27483 13690 27483 13690 27484 13685 27484 13681 27484 13690 27485 13681 27485 13691 27485 13691 27486 13681 27486 13672 27486 13691 27487 13672 27487 13692 27487 25527 27488 25765 27488 13694 27488 13694 27489 25765 27489 24507 27489 25645 27490 24507 27490 13693 27490 13693 27491 24507 27491 13696 27491 25645 27492 25651 27492 24507 27492 24507 27493 25651 27493 25650 27493 24507 27494 25650 27494 13694 27494 24494 27495 25642 27495 13695 27495 13695 27496 25644 27496 24494 27496 24494 27497 25644 27497 25522 27497 24494 27498 25522 27498 13696 27498 13696 27499 25522 27499 25523 27499 13696 27500 25523 27500 13693 27500 13697 27501 25495 27501 24503 27501 24503 27502 25495 27502 25494 27502 24503 27503 25494 27503 24494 27503 24494 27504 25494 27504 13717 27504 24494 27505 13717 27505 25642 27505 13699 27506 13725 27506 25637 27506 25737 27507 13698 27507 24502 27507 24502 27508 13698 27508 13699 27508 24502 27509 13699 27509 13697 27509 13697 27510 13699 27510 25637 27510 13697 27511 25637 27511 25495 27511 25737 27512 24502 27512 13700 27512 13700 27513 24502 27513 13701 27513 13700 27514 13701 27514 13702 27514 13703 27515 13701 27515 24501 27515 13703 27516 25736 27516 13701 27516 13701 27517 25736 27517 25635 27517 13701 27518 25635 27518 13702 27518 25717 27519 25719 27519 24500 27519 24500 27520 25719 27520 13704 27520 24500 27521 13704 27521 24501 27521 24501 27522 13704 27522 25735 27522 24501 27523 25735 27523 13703 27523 13703 27524 25735 27524 13705 27524 25717 27525 24500 27525 13737 27525 13737 27526 24500 27526 24497 27526 13737 27527 24497 27527 13707 27527 13706 27528 24497 27528 13709 27528 13709 27529 24497 27529 24495 27529 13706 27530 25714 27530 24497 27530 24497 27531 25714 27531 25716 27531 24497 27532 25716 27532 13707 27532 13747 27533 13748 27533 24496 27533 24496 27534 13748 27534 13708 27534 24496 27535 13708 27535 24495 27535 24495 27536 13708 27536 25511 27536 24495 27537 25511 27537 13709 27537 13747 27538 24496 27538 25705 27538 25705 27539 24496 27539 13710 27539 25705 27540 13710 27540 25706 27540 25741 27541 13813 27541 25641 27541 25641 27542 13813 27542 13711 27542 13813 27543 13812 27543 13711 27543 13711 27544 13812 27544 13811 27544 13711 27545 13811 27545 13713 27545 13713 27546 13811 27546 13712 27546 13713 27547 13712 27547 13720 27547 13720 27548 13712 27548 13809 27548 13714 27549 25747 27549 13715 27549 13715 27550 25747 27550 13716 27550 13715 27551 13716 27551 13805 27551 13805 27552 13716 27552 13717 27552 13805 27553 13717 27553 13806 27553 13806 27554 13717 27554 25494 27554 13806 27555 25494 27555 13807 27555 13807 27556 25494 27556 13718 27556 13807 27557 13718 27557 13808 27557 13808 27558 13718 27558 13720 27558 13808 27559 13720 27559 13719 27559 13719 27560 13720 27560 13809 27560 13723 27561 13724 27561 13894 27561 13894 27562 13724 27562 13722 27562 13894 27563 13722 27563 13721 27563 13721 27564 13722 27564 25629 27564 13721 27565 25629 27565 25202 27565 13726 27566 13698 27566 13723 27566 13723 27567 13698 27567 25738 27567 13723 27568 25738 27568 13724 27568 25638 27569 13725 27569 13726 27569 13726 27570 13725 27570 13699 27570 13726 27571 13699 27571 13698 27571 13726 27572 13727 27572 25638 27572 25638 27573 13727 27573 13892 27573 25638 27574 13892 27574 13728 27574 13728 27575 13892 27575 13729 27575 13728 27576 13729 27576 25490 27576 25472 27577 25192 27577 13903 27577 25472 27578 13903 27578 13730 27578 13730 27579 13903 27579 13902 27579 13730 27580 13902 27580 25491 27580 25491 27581 13902 27581 13705 27581 13705 27582 13902 27582 13901 27582 13705 27583 13901 27583 13703 27583 13703 27584 13901 27584 13900 27584 13703 27585 13900 27585 25736 27585 25736 27586 13900 27586 13731 27586 25736 27587 13731 27587 13732 27587 13731 27588 13733 27588 13732 27588 13732 27589 13733 27589 13898 27589 13732 27590 13898 27590 13734 27590 13898 27591 13896 27591 13734 27591 13734 27592 13896 27592 13735 27592 13734 27593 13735 27593 13736 27593 13736 27594 13735 27594 25483 27594 13736 27595 25483 27595 25482 27595 25715 27596 25464 27596 13907 27596 13737 27597 13707 27597 13907 27597 13907 27598 13707 27598 13738 27598 13907 27599 13738 27599 25715 27599 13907 27600 13906 27600 13737 27600 13737 27601 13906 27601 13740 27601 13737 27602 13740 27602 13739 27602 13739 27603 13740 27603 13742 27603 13739 27604 13742 27604 13741 27604 13741 27605 13742 27605 13743 27605 13741 27606 13743 27606 25727 27606 25727 27607 13743 27607 13744 27607 25727 27608 13744 27608 25726 27608 25726 27609 13744 27609 13904 27609 25726 27610 13904 27610 13745 27610 13747 27611 13746 27611 13918 27611 13747 27612 13918 27612 13748 27612 13748 27613 13918 27613 13750 27613 13748 27614 13750 27614 13749 27614 13749 27615 13750 27615 13751 27615 13749 27616 13751 27616 13752 27616 13752 27617 13751 27617 13753 27617 13752 27618 13753 27618 13754 27618 13753 27619 13914 27619 13754 27619 13754 27620 13914 27620 13913 27620 13754 27621 13913 27621 13755 27621 13913 27622 13756 27622 13755 27622 13755 27623 13756 27623 13757 27623 13755 27624 13757 27624 13758 27624 13757 27625 13759 27625 13758 27625 13758 27626 13759 27626 13910 27626 13758 27627 13910 27627 13760 27627 13760 27628 13910 27628 13911 27628 13760 27629 13911 27629 25462 27629 25450 27630 25620 27630 13761 27630 13761 27631 25620 27631 13762 27631 25701 27632 13921 27632 13762 27632 13762 27633 13921 27633 13920 27633 13762 27634 13920 27634 13761 27634 13926 27635 13925 27635 25702 27635 25702 27636 13925 27636 13923 27636 25702 27637 13923 27637 25701 27637 25701 27638 13923 27638 13763 27638 25701 27639 13763 27639 13921 27639 13926 27640 25702 27640 13927 27640 13927 27641 25702 27641 13764 27641 13927 27642 13764 27642 13765 27642 13765 27643 13764 27643 13766 27643 13765 27644 13766 27644 13930 27644 13930 27645 13766 27645 13931 27645 13931 27646 13766 27646 13767 27646 13931 27647 13767 27647 13768 27647 25689 27648 13771 27648 25687 27648 25687 27649 13771 27649 13932 27649 25687 27650 13932 27650 25437 27650 13935 27651 13934 27651 25690 27651 25690 27652 13934 27652 13769 27652 25690 27653 13769 27653 25689 27653 25689 27654 13769 27654 13770 27654 25689 27655 13770 27655 13771 27655 13935 27656 25690 27656 13937 27656 13937 27657 25690 27657 25691 27657 13937 27658 25691 27658 13938 27658 13938 27659 25691 27659 13772 27659 13938 27660 13772 27660 13773 27660 13773 27661 13772 27661 25694 27661 13773 27662 25694 27662 13774 27662 13774 27663 25694 27663 25683 27663 13774 27664 25683 27664 13940 27664 25160 27665 25667 27665 13775 27665 13775 27666 25667 27666 25670 27666 25670 27667 25671 27667 13775 27667 13775 27668 25671 27668 13776 27668 13775 27669 13776 27669 13777 27669 13777 27670 13776 27670 13778 27670 13777 27671 13778 27671 13944 27671 13944 27672 13778 27672 13779 27672 13944 27673 13779 27673 13945 27673 13945 27674 13779 27674 25679 27674 13945 27675 25679 27675 13780 27675 13780 27676 25679 27676 25436 27676 13780 27677 25436 27677 25153 27677 25151 27678 25417 27678 25661 27678 25151 27679 25661 27679 13948 27679 13948 27680 25661 27680 25660 27680 13948 27681 25660 27681 13781 27681 13781 27682 25660 27682 25553 27682 13781 27683 25553 27683 13950 27683 13950 27684 25553 27684 25550 27684 13950 27685 25550 27685 13782 27685 13782 27686 25550 27686 25549 27686 13782 27687 25549 27687 13783 27687 13783 27688 25549 27688 13784 27688 13783 27689 13784 27689 13785 27689 13785 27690 13784 27690 13786 27690 13785 27691 13786 27691 25430 27691 25144 27692 25413 27692 13787 27692 25144 27693 13787 27693 13788 27693 13788 27694 13787 27694 25559 27694 13788 27695 25559 27695 13789 27695 13789 27696 25559 27696 13790 27696 13789 27697 13790 27697 13955 27697 13955 27698 13790 27698 13791 27698 13955 27699 13791 27699 13956 27699 13956 27700 13791 27700 25570 27700 13956 27701 25570 27701 13792 27701 13792 27702 25570 27702 25569 27702 13792 27703 25569 27703 25137 27703 25401 27704 13793 27704 25655 27704 25401 27705 25655 27705 13959 27705 13959 27706 25655 27706 25656 27706 13959 27707 25656 27707 13795 27707 13795 27708 25656 27708 13794 27708 13795 27709 13794 27709 13961 27709 13961 27710 13794 27710 13796 27710 13961 27711 13796 27711 13797 27711 13797 27712 13796 27712 25573 27712 13797 27713 25573 27713 13962 27713 13962 27714 25573 27714 25412 27714 13962 27715 25412 27715 13798 27715 25645 27716 25646 27716 13803 27716 13803 27717 25646 27717 13799 27717 13803 27718 13799 27718 13966 27718 13966 27719 13799 27719 25647 27719 13966 27720 25647 27720 13968 27720 13968 27721 25647 27721 13800 27721 13968 27722 13800 27722 13970 27722 13970 27723 13800 27723 13801 27723 13970 27724 13801 27724 13971 27724 13971 27725 13801 27725 25586 27725 13971 27726 25586 27726 13973 27726 13973 27727 25586 27727 13802 27727 13973 27728 13802 27728 13974 27728 25645 27729 13803 27729 25651 27729 25651 27730 13803 27730 25128 27730 25651 27731 25128 27731 25649 27731 13804 27732 13714 27732 13715 27732 13804 27733 13715 27733 25117 27733 25117 27734 13715 27734 13805 27734 25117 27735 13805 27735 25118 27735 13805 27736 13806 27736 25118 27736 25118 27737 13806 27737 13807 27737 25118 27738 13807 27738 25119 27738 25119 27739 13807 27739 13808 27739 25119 27740 13808 27740 25121 27740 13808 27741 13719 27741 25121 27741 25121 27742 13719 27742 13809 27742 25121 27743 13809 27743 25112 27743 13809 27744 13712 27744 25112 27744 25112 27745 13712 27745 13811 27745 25112 27746 13811 27746 13810 27746 13810 27747 13811 27747 13812 27747 13812 27748 13813 27748 13810 27748 13810 27749 13813 27749 25741 27749 13810 27750 25741 27750 25392 27750 13976 27751 25628 27751 13977 27751 13977 27752 25628 27752 13814 27752 25360 27753 25361 27753 13980 27753 13980 27754 25361 27754 25624 27754 13980 27755 25624 27755 13815 27755 13815 27756 25624 27756 25622 27756 13815 27757 25622 27757 13816 27757 13816 27758 25622 27758 25700 27758 13817 27759 25609 27759 13818 27759 13818 27760 25609 27760 25610 27760 13987 27761 13819 27761 13988 27761 13988 27762 13819 27762 13820 27762 13988 27763 13820 27763 13821 27763 13821 27764 13820 27764 25731 27764 13821 27765 25731 27765 13822 27765 13822 27766 25731 27766 13823 27766 25035 27767 25298 27767 13824 27767 13824 27768 25298 27768 25579 27768 25293 27769 25546 27769 25007 27769 25007 27770 25546 27770 25558 27770 25007 27771 25558 27771 25006 27771 25006 27772 25558 27772 25292 27772 25267 27773 25266 27773 13826 27773 13826 27774 25266 27774 13825 27774 13826 27775 13825 27775 13992 27775 13992 27776 13825 27776 13827 27776 13992 27777 13827 27777 13995 27777 13995 27778 13827 27778 25543 27778 13995 27779 25543 27779 13997 27779 13997 27780 25543 27780 13828 27780 13997 27781 13828 27781 13998 27781 13998 27782 13828 27782 13829 27782 13998 27783 13829 27783 24979 27783 24979 27784 13829 27784 13830 27784 13999 27785 25265 27785 14000 27785 14000 27786 25265 27786 13832 27786 14000 27787 13832 27787 13831 27787 13831 27788 13832 27788 25664 27788 13831 27789 25664 27789 13833 27789 13833 27790 25664 27790 13834 27790 13833 27791 13834 27791 13835 27791 13835 27792 13834 27792 25663 27792 13835 27793 25663 27793 14003 27793 14003 27794 25663 27794 13836 27794 14003 27795 13836 27795 24969 27795 24969 27796 13836 27796 13837 27796 14005 27797 25533 27797 13838 27797 13838 27798 25533 27798 13839 27798 13838 27799 13839 27799 14008 27799 14008 27800 13839 27800 13840 27800 14008 27801 13840 27801 13841 27801 13841 27802 13840 27802 25564 27802 13841 27803 25564 27803 14009 27803 14009 27804 25564 27804 25534 27804 14009 27805 25534 27805 13842 27805 13842 27806 25534 27806 13843 27806 13842 27807 13843 27807 24961 27807 24961 27808 13843 27808 13844 27808 14011 27809 25250 27809 13845 27809 13845 27810 25250 27810 25577 27810 13845 27811 25577 27811 14014 27811 14014 27812 25577 27812 13846 27812 14014 27813 13846 27813 13847 27813 13847 27814 13846 27814 25578 27814 13847 27815 25578 27815 13848 27815 13848 27816 25578 27816 13849 27816 13848 27817 13849 27817 13850 27817 13850 27818 13849 27818 25654 27818 13850 27819 25654 27819 14019 27819 14019 27820 25654 27820 13851 27820 24944 27821 25518 27821 13852 27821 13852 27822 25518 27822 25520 27822 13852 27823 25520 27823 13854 27823 13854 27824 25520 27824 13853 27824 13854 27825 13853 27825 13855 27825 13855 27826 13853 27826 13856 27826 13855 27827 13856 27827 14023 27827 14023 27828 13856 27828 13858 27828 14023 27829 13858 27829 13857 27829 13857 27830 13858 27830 13860 27830 13857 27831 13860 27831 13859 27831 13859 27832 13860 27832 25526 27832 14025 27833 25241 27833 14026 27833 14026 27834 25241 27834 25636 27834 14026 27835 25636 27835 13861 27835 13861 27836 25636 27836 25631 27836 13861 27837 25631 27837 13862 27837 13862 27838 25631 27838 25630 27838 13862 27839 25630 27839 14028 27839 14028 27840 25630 27840 13863 27840 14028 27841 13863 27841 14030 27841 14030 27842 13863 27842 13864 27842 14030 27843 13864 27843 24929 27843 24929 27844 13864 27844 25234 27844 25722 27845 25230 27845 13865 27845 13865 27846 14039 27846 25722 27846 25722 27847 14039 27847 13866 27847 25722 27848 13866 27848 13867 27848 13866 27849 14037 27849 13867 27849 13867 27850 14037 27850 13868 27850 13867 27851 13868 27851 25723 27851 13868 27852 13869 27852 25723 27852 25723 27853 13869 27853 13870 27853 25723 27854 13870 27854 25725 27854 25725 27855 13870 27855 13871 27855 25725 27856 13871 27856 13872 27856 13871 27857 13873 27857 13872 27857 13872 27858 13873 27858 13874 27858 13872 27859 13874 27859 25728 27859 24928 27860 25222 27860 14033 27860 14033 27861 25222 27861 25728 27861 14033 27862 25728 27862 14034 27862 14034 27863 25728 27863 13874 27863 13877 27864 13875 27864 24917 27864 24917 27865 13876 27865 13877 27865 13877 27866 13876 27866 14049 27866 13877 27867 14049 27867 13878 27867 14049 27868 13879 27868 13878 27868 13878 27869 13879 27869 13880 27869 13878 27870 13880 27870 25513 27870 25513 27871 13880 27871 13881 27871 25513 27872 13881 27872 25514 27872 13881 27873 14045 27873 25514 27873 25514 27874 14045 27874 13882 27874 25514 27875 13882 27875 13884 27875 13882 27876 13883 27876 13884 27876 13884 27877 13883 27877 13888 27877 13884 27878 13888 27878 13885 27878 14040 27879 13886 27879 14041 27879 14041 27880 13886 27880 13885 27880 14041 27881 13885 27881 13887 27881 13887 27882 13885 27882 13888 27882 25215 27883 25504 27883 14052 27883 14052 27884 25504 27884 25502 27884 14052 27885 25502 27885 13889 27885 13889 27886 25502 27886 25501 27886 13889 27887 25501 27887 14055 27887 14055 27888 25501 27888 25685 27888 14055 27889 25685 27889 14057 27889 14057 27890 25685 27890 25507 27890 14057 27891 25507 27891 14058 27891 14058 27892 25507 27892 25510 27892 14058 27893 25510 27893 25208 27893 25208 27894 25510 27894 13890 27894 13891 27895 13729 27895 13892 27895 13891 27896 13892 27896 24904 27896 24904 27897 13892 27897 13727 27897 24904 27898 13727 27898 13893 27898 13893 27899 13727 27899 13726 27899 13893 27900 13726 27900 24895 27900 24895 27901 13726 27901 13723 27901 24895 27902 13723 27902 24896 27902 24896 27903 13723 27903 13894 27903 24896 27904 13894 27904 24897 27904 24897 27905 13894 27905 13721 27905 24897 27906 13721 27906 13895 27906 13895 27907 13721 27907 25202 27907 13895 27908 25202 27908 25203 27908 13897 27909 24885 27909 13735 27909 13735 27910 24885 27910 25201 27910 13735 27911 25201 27911 25483 27911 13735 27912 13896 27912 13897 27912 13897 27913 13896 27913 13898 27913 13897 27914 13898 27914 13899 27914 13899 27915 13898 27915 13733 27915 13733 27916 13731 27916 13899 27916 13899 27917 13731 27917 13900 27917 13899 27918 13900 27918 24887 27918 13900 27919 13901 27919 24887 27919 24887 27920 13901 27920 13902 27920 24887 27921 13902 27921 24888 27921 13902 27922 13903 27922 24888 27922 24888 27923 13903 27923 25192 27923 24888 27924 25192 27924 25193 27924 24879 27925 13904 27925 13744 27925 24879 27926 13744 27926 24882 27926 24882 27927 13744 27927 13743 27927 24882 27928 13743 27928 24871 27928 24871 27929 13743 27929 13742 27929 24871 27930 13742 27930 24872 27930 24872 27931 13742 27931 13740 27931 24872 27932 13740 27932 13905 27932 13905 27933 13740 27933 13906 27933 13905 27934 13906 27934 24873 27934 24873 27935 13906 27935 13907 27935 24873 27936 13907 27936 13908 27936 13908 27937 13907 27937 25464 27937 13908 27938 25464 27938 24875 27938 13912 27939 13909 27939 13910 27939 13910 27940 13909 27940 24860 27940 13910 27941 24860 27941 13911 27941 13910 27942 13759 27942 13912 27942 13912 27943 13759 27943 13757 27943 13912 27944 13757 27944 13915 27944 13915 27945 13757 27945 13756 27945 13756 27946 13913 27946 13915 27946 13915 27947 13913 27947 13914 27947 13915 27948 13914 27948 13916 27948 13914 27949 13753 27949 13916 27949 13916 27950 13753 27950 13751 27950 13916 27951 13751 27951 13917 27951 13751 27952 13750 27952 13917 27952 13917 27953 13750 27953 13918 27953 13917 27954 13918 27954 24868 27954 13919 27955 25450 27955 13761 27955 13919 27956 13761 27956 24855 27956 24855 27957 13761 27957 13920 27957 24855 27958 13920 27958 13922 27958 13920 27959 13921 27959 13922 27959 13922 27960 13921 27960 13763 27960 13922 27961 13763 27961 24857 27961 13763 27962 13923 27962 24857 27962 24857 27963 13923 27963 13925 27963 24857 27964 13925 27964 13924 27964 13924 27965 13925 27965 13926 27965 13924 27966 13926 27966 13928 27966 13926 27967 13927 27967 13928 27967 13928 27968 13927 27968 13765 27968 13928 27969 13765 27969 13929 27969 13929 27970 13765 27970 13930 27970 13930 27971 13931 27971 13929 27971 13929 27972 13931 27972 13768 27972 13929 27973 13768 27973 25172 27973 13933 27974 24841 27974 13771 27974 13771 27975 24841 27975 24840 27975 13771 27976 24840 27976 13932 27976 13771 27977 13770 27977 13933 27977 13933 27978 13770 27978 13769 27978 13933 27979 13769 27979 13936 27979 13936 27980 13769 27980 13934 27980 13934 27981 13935 27981 13936 27981 13936 27982 13935 27982 13937 27982 13936 27983 13937 27983 24844 27983 13937 27984 13938 27984 24844 27984 24844 27985 13938 27985 13773 27985 24844 27986 13773 27986 13939 27986 13773 27987 13774 27987 13939 27987 13939 27988 13774 27988 13940 27988 13939 27989 13940 27989 13941 27989 13942 27990 25160 27990 13775 27990 13942 27991 13775 27991 13943 27991 13943 27992 13775 27992 13777 27992 13943 27993 13777 27993 24827 27993 24827 27994 13777 27994 13944 27994 24827 27995 13944 27995 24826 27995 24826 27996 13944 27996 13945 27996 24826 27997 13945 27997 13946 27997 13946 27998 13945 27998 13780 27998 13946 27999 13780 27999 24835 27999 24835 28000 13780 28000 25153 28000 24835 28001 25153 28001 13947 28001 25152 28002 25151 28002 13948 28002 25152 28003 13948 28003 24824 28003 24824 28004 13948 28004 13781 28004 24824 28005 13781 28005 13949 28005 13949 28006 13781 28006 13950 28006 13949 28007 13950 28007 13951 28007 13951 28008 13950 28008 13782 28008 13951 28009 13782 28009 13952 28009 13952 28010 13782 28010 13783 28010 13952 28011 13783 28011 13953 28011 13953 28012 13783 28012 13785 28012 13953 28013 13785 28013 24817 28013 24817 28014 13785 28014 25430 28014 24817 28015 25430 28015 25146 28015 24799 28016 25144 28016 13788 28016 24799 28017 13788 28017 24798 28017 24798 28018 13788 28018 13789 28018 24798 28019 13789 28019 13954 28019 13954 28020 13789 28020 13955 28020 13954 28021 13955 28021 24811 28021 24811 28022 13955 28022 13956 28022 24811 28023 13956 28023 13957 28023 13957 28024 13956 28024 13792 28024 13957 28025 13792 28025 13958 28025 13958 28026 13792 28026 25137 28026 13958 28027 25137 28027 24808 28027 24791 28028 25401 28028 13959 28028 24791 28029 13959 28029 13960 28029 13960 28030 13959 28030 13795 28030 13960 28031 13795 28031 24788 28031 24788 28032 13795 28032 13961 28032 24788 28033 13961 28033 24786 28033 24786 28034 13961 28034 13797 28034 24786 28035 13797 28035 24785 28035 24785 28036 13797 28036 13962 28036 24785 28037 13962 28037 13963 28037 13963 28038 13962 28038 13798 28038 13963 28039 13798 28039 13964 28039 25129 28040 25128 28040 13803 28040 25129 28041 13803 28041 13965 28041 13965 28042 13803 28042 13966 28042 13965 28043 13966 28043 13967 28043 13967 28044 13966 28044 13968 28044 13967 28045 13968 28045 24781 28045 24781 28046 13968 28046 13970 28046 24781 28047 13970 28047 13969 28047 13969 28048 13970 28048 13971 28048 13969 28049 13971 28049 13972 28049 13972 28050 13971 28050 13973 28050 13972 28051 13973 28051 24770 28051 24770 28052 13973 28052 13974 28052 24770 28053 13974 28053 13975 28053 25104 28054 13976 28054 24749 28054 24749 28055 13976 28055 13977 28055 25090 28056 13978 28056 24734 28056 25090 28057 24734 28057 25369 28057 25369 28058 24734 28058 25091 28058 25369 28059 25091 28059 25368 28059 24741 28060 25360 28060 13979 28060 13979 28061 25360 28061 13980 28061 13979 28062 13980 28062 13981 28062 13981 28063 13980 28063 13815 28063 13981 28064 13815 28064 24740 28064 24740 28065 13815 28065 13816 28065 25341 28066 24722 28066 13982 28066 13982 28067 24722 28067 13983 28067 13982 28068 13983 28068 25345 28068 25064 28069 13817 28069 13984 28069 13984 28070 13817 28070 13818 28070 13985 28071 13987 28071 13986 28071 13986 28072 13987 28072 13988 28072 13986 28073 13988 28073 13989 28073 13989 28074 13988 28074 13821 28074 13989 28075 13821 28075 24719 28075 24719 28076 13821 28076 13822 28076 14065 28077 25267 28077 14066 28077 14066 28078 25267 28078 13826 28078 14066 28079 13826 28079 13990 28079 13990 28080 13826 28080 13991 28080 13991 28081 13826 28081 13992 28081 13991 28082 13992 28082 14067 28082 14067 28083 13992 28083 13993 28083 13993 28084 13992 28084 13995 28084 13993 28085 13995 28085 13994 28085 13994 28086 13995 28086 14072 28086 14072 28087 13995 28087 13997 28087 14072 28088 13997 28088 14068 28088 14068 28089 13997 28089 13996 28089 13996 28090 13997 28090 13998 28090 13996 28091 13998 28091 14070 28091 14070 28092 13998 28092 14071 28092 14071 28093 13998 28093 24979 28093 14071 28094 24979 28094 14069 28094 24978 28095 13999 28095 14075 28095 14075 28096 13999 28096 14000 28096 14075 28097 14000 28097 14001 28097 14001 28098 14000 28098 13831 28098 14001 28099 13831 28099 14074 28099 14074 28100 13831 28100 13833 28100 14074 28101 13833 28101 14077 28101 14077 28102 13833 28102 13835 28102 14077 28103 13835 28103 14002 28103 14002 28104 13835 28104 14003 28104 14002 28105 14003 28105 14004 28105 14004 28106 14003 28106 24969 28106 14078 28107 14005 28107 14079 28107 14079 28108 14005 28108 13838 28108 14079 28109 13838 28109 14006 28109 14006 28110 13838 28110 14008 28110 14006 28111 14008 28111 14007 28111 14007 28112 14008 28112 13841 28112 14007 28113 13841 28113 14010 28113 14010 28114 13841 28114 14009 28114 14010 28115 14009 28115 14080 28115 14080 28116 14009 28116 13842 28116 14080 28117 13842 28117 24959 28117 24959 28118 13842 28118 24961 28118 24958 28119 14011 28119 14081 28119 14081 28120 14011 28120 13845 28120 14081 28121 13845 28121 14012 28121 14012 28122 13845 28122 14084 28122 14084 28123 13845 28123 14014 28123 14084 28124 14014 28124 14013 28124 14013 28125 14014 28125 14015 28125 14015 28126 14014 28126 13847 28126 14015 28127 13847 28127 14016 28127 14016 28128 13847 28128 14017 28128 14017 28129 13847 28129 13848 28129 14017 28130 13848 28130 14082 28130 14082 28131 13848 28131 14018 28131 14018 28132 13848 28132 13850 28132 14018 28133 13850 28133 14083 28133 14083 28134 13850 28134 14020 28134 14020 28135 13850 28135 14019 28135 14020 28136 14019 28136 24945 28136 14021 28137 24944 28137 14086 28137 14086 28138 24944 28138 13852 28138 14086 28139 13852 28139 14087 28139 14087 28140 13852 28140 13854 28140 14087 28141 13854 28141 14085 28141 14085 28142 13854 28142 13855 28142 14085 28143 13855 28143 14088 28143 14088 28144 13855 28144 14023 28144 14088 28145 14023 28145 14022 28145 14022 28146 14023 28146 13857 28146 14022 28147 13857 28147 14024 28147 14024 28148 13857 28148 13859 28148 24688 28149 14025 28149 14091 28149 14091 28150 14025 28150 14026 28150 14091 28151 14026 28151 14090 28151 14090 28152 14026 28152 13861 28152 14090 28153 13861 28153 14089 28153 14089 28154 13861 28154 13862 28154 14089 28155 13862 28155 14027 28155 14027 28156 13862 28156 14028 28156 14027 28157 14028 28157 14029 28157 14029 28158 14028 28158 14030 28158 14029 28159 14030 28159 14031 28159 14031 28160 14030 28160 24929 28160 24928 28161 14033 28161 14092 28161 14092 28162 14033 28162 14032 28162 14033 28163 14034 28163 14032 28163 14032 28164 14034 28164 13874 28164 14032 28165 13874 28165 14035 28165 13874 28166 13873 28166 14035 28166 14035 28167 13873 28167 13871 28167 14035 28168 13871 28168 14093 28168 13871 28169 13870 28169 14093 28169 14093 28170 13870 28170 13869 28170 14093 28171 13869 28171 14036 28171 13869 28172 13868 28172 14036 28172 14036 28173 13868 28173 14037 28173 14036 28174 14037 28174 14038 28174 13865 28175 24682 28175 14039 28175 14039 28176 24682 28176 14038 28176 14039 28177 14038 28177 13866 28177 13866 28178 14038 28178 14037 28178 14040 28179 14041 28179 14042 28179 14042 28180 14041 28180 14043 28180 14041 28181 13887 28181 14043 28181 14043 28182 13887 28182 13888 28182 14043 28183 13888 28183 14094 28183 13888 28184 13883 28184 14094 28184 14094 28185 13883 28185 13882 28185 14094 28186 13882 28186 14044 28186 13882 28187 14045 28187 14044 28187 14044 28188 14045 28188 13881 28188 14044 28189 13881 28189 14046 28189 13881 28190 13880 28190 14046 28190 14046 28191 13880 28191 13879 28191 14046 28192 13879 28192 14047 28192 24917 28193 14048 28193 13876 28193 13876 28194 14048 28194 14047 28194 13876 28195 14047 28195 14049 28195 14049 28196 14047 28196 13879 28196 24915 28197 25215 28197 14050 28197 14050 28198 25215 28198 14052 28198 14050 28199 14052 28199 14095 28199 14095 28200 14052 28200 14051 28200 14051 28201 14052 28201 13889 28201 14051 28202 13889 28202 14053 28202 14053 28203 13889 28203 14054 28203 14054 28204 13889 28204 14055 28204 14054 28205 14055 28205 14056 28205 14056 28206 14055 28206 14096 28206 14096 28207 14055 28207 14057 28207 14096 28208 14057 28208 14101 28208 14101 28209 14057 28209 14097 28209 14097 28210 14057 28210 14058 28210 14097 28211 14058 28211 14100 28211 14100 28212 14058 28212 14098 28212 14098 28213 14058 28213 25208 28213 14098 28214 25208 28214 14099 28214 14174 28215 25113 28215 14175 28215 14175 28216 25113 28216 14059 28216 14175 28217 14059 28217 14177 28217 14177 28218 14059 28218 25115 28218 14177 28219 25115 28219 14178 28219 14178 28220 25115 28220 14060 28220 14178 28221 14060 28221 14061 28221 14061 28222 14060 28222 14062 28222 14061 28223 14062 28223 14180 28223 14180 28224 14062 28224 14063 28224 14180 28225 14063 28225 14064 28225 14064 28226 14063 28226 24766 28226 14073 28227 14065 28227 14066 28227 13990 28228 13991 28228 14073 28228 14067 28229 13993 28229 14073 28229 13994 28230 14072 28230 14073 28230 14068 28231 13996 28231 14073 28231 14073 28232 14071 28232 14069 28232 14070 28233 14071 28233 14073 28233 13996 28234 14070 28234 14073 28234 14072 28235 14068 28235 14073 28235 13993 28236 13994 28236 14073 28236 13991 28237 14067 28237 14073 28237 14066 28238 13990 28238 14073 28238 14076 28239 14001 28239 14074 28239 14075 28240 14001 28240 14076 28240 24978 28241 14075 28241 14076 28241 14076 28242 14002 28242 14004 28242 14077 28243 14002 28243 14076 28243 14074 28244 14077 28244 14076 28244 24699 28245 14006 28245 14007 28245 14079 28246 14006 28246 24699 28246 14078 28247 14079 28247 24699 28247 24699 28248 14080 28248 24959 28248 14010 28249 14080 28249 24699 28249 14007 28250 14010 28250 24699 28250 24696 28251 24958 28251 14081 28251 14012 28252 14084 28252 24696 28252 14013 28253 14015 28253 24696 28253 14016 28254 14017 28254 24696 28254 14082 28255 14018 28255 24696 28255 24696 28256 14020 28256 24945 28256 14083 28257 14020 28257 24696 28257 14018 28258 14083 28258 24696 28258 14017 28259 14082 28259 24696 28259 14015 28260 14016 28260 24696 28260 14084 28261 14013 28261 24696 28261 14081 28262 14012 28262 24696 28262 24691 28263 14087 28263 14085 28263 14086 28264 14087 28264 24691 28264 14021 28265 14086 28265 24691 28265 24691 28266 14022 28266 14024 28266 14088 28267 14022 28267 24691 28267 14085 28268 14088 28268 24691 28268 24687 28269 14090 28269 14089 28269 14091 28270 14090 28270 24687 28270 24688 28271 14091 28271 24687 28271 24687 28272 14029 28272 14031 28272 14027 28273 14029 28273 24687 28273 14089 28274 14027 28274 24687 28274 24684 28275 14035 28275 14093 28275 14032 28276 14035 28276 24684 28276 14092 28277 14032 28277 24684 28277 24684 28278 14038 28278 24682 28278 14036 28279 14038 28279 24684 28279 14093 28280 14036 28280 24684 28280 24679 28281 14094 28281 14044 28281 14043 28282 14094 28282 24679 28282 14042 28283 14043 28283 24679 28283 24679 28284 14047 28284 14048 28284 14046 28285 14047 28285 24679 28285 14044 28286 14046 28286 24679 28286 24678 28287 24915 28287 14050 28287 14095 28288 14051 28288 24678 28288 14053 28289 14054 28289 24678 28289 14056 28290 14096 28290 24678 28290 14101 28291 14097 28291 24678 28291 24678 28292 14098 28292 14099 28292 14100 28293 14098 28293 24678 28293 14097 28294 14100 28294 24678 28294 14096 28295 14101 28295 24678 28295 14054 28296 14056 28296 24678 28296 14051 28297 14053 28297 24678 28297 14050 28298 14095 28298 24678 28298 14102 28299 14103 28299 14183 28299 14183 28300 14103 28300 24898 28300 14183 28301 24898 28301 14184 28301 14184 28302 24898 28302 24899 28302 14184 28303 24899 28303 14105 28303 14105 28304 24899 28304 14104 28304 14105 28305 14104 28305 14106 28305 14106 28306 14104 28306 14107 28306 14106 28307 14107 28307 14186 28307 14186 28308 14107 28308 14108 28308 14186 28309 14108 28309 24666 28309 24666 28310 14108 28310 24667 28310 14187 28311 14109 28311 14188 28311 14188 28312 14109 28312 24889 28312 14188 28313 24889 28313 14110 28313 14110 28314 24889 28314 14111 28314 14110 28315 14111 28315 14191 28315 14191 28316 14111 28316 14112 28316 14191 28317 14112 28317 14113 28317 14113 28318 14112 28318 14114 28318 14113 28319 14114 28319 14193 28319 14193 28320 14114 28320 24892 28320 14193 28321 24892 28321 14195 28321 14195 28322 24892 28322 14115 28322 14195 28323 14115 28323 14116 28323 14116 28324 14115 28324 24883 28324 14197 28325 24876 28325 14117 28325 14117 28326 24876 28326 14118 28326 14117 28327 14118 28327 14198 28327 14198 28328 14118 28328 14119 28328 14198 28329 14119 28329 14201 28329 14201 28330 14119 28330 14120 28330 14201 28331 14120 28331 14203 28331 14203 28332 14120 28332 24878 28332 14203 28333 24878 28333 14121 28333 14121 28334 24878 28334 14123 28334 14121 28335 14123 28335 14122 28335 14122 28336 14123 28336 24651 28336 24863 28337 24861 28337 24648 28337 24648 28338 14216 28338 24863 28338 24863 28339 14216 28339 14124 28339 24863 28340 14124 28340 24864 28340 14124 28341 14213 28341 24864 28341 24864 28342 14213 28342 14211 28342 24864 28343 14211 28343 24865 28343 24865 28344 14211 28344 14125 28344 14125 28345 14210 28345 24865 28345 24865 28346 14210 28346 14126 28346 24865 28347 14126 28347 14127 28347 14126 28348 14206 28348 14127 28348 14127 28349 14206 28349 14128 28349 14127 28350 14128 28350 24867 28350 24642 28351 14129 28351 14130 28351 14130 28352 14129 28352 24867 28352 14130 28353 24867 28353 14131 28353 14131 28354 24867 28354 14128 28354 14219 28355 24845 28355 14222 28355 14222 28356 24845 28356 24846 28356 14222 28357 24846 28357 14132 28357 14132 28358 24846 28358 14133 28358 14132 28359 14133 28359 14223 28359 14223 28360 14133 28360 24849 28360 14223 28361 24849 28361 14134 28361 14134 28362 24849 28362 24850 28362 14134 28363 24850 28363 14226 28363 14226 28364 24850 28364 24851 28364 14226 28365 24851 28365 14227 28365 14227 28366 24851 28366 24853 28366 14230 28367 24634 28367 14135 28367 14135 28368 24634 28368 14137 28368 14135 28369 14137 28369 14136 28369 14136 28370 14137 28370 14139 28370 14136 28371 14139 28371 14138 28371 14138 28372 14139 28372 14140 28372 14138 28373 14140 28373 14232 28373 14232 28374 14140 28374 24837 28374 14232 28375 24837 28375 14141 28375 14141 28376 24837 28376 14142 28376 14141 28377 14142 28377 14234 28377 14234 28378 14142 28378 24838 28378 14234 28379 24838 28379 14236 28379 14236 28380 24838 28380 14143 28380 24630 28381 14144 28381 14237 28381 14237 28382 14144 28382 14145 28382 14237 28383 14145 28383 14238 28383 14238 28384 14145 28384 14146 28384 14238 28385 14146 28385 14241 28385 14241 28386 14146 28386 24834 28386 14241 28387 24834 28387 14147 28387 14147 28388 24834 28388 24832 28388 14147 28389 24832 28389 14242 28389 14242 28390 24832 28390 14148 28390 14242 28391 14148 28391 24626 28391 24626 28392 14148 28392 24831 28392 14149 28393 24816 28393 14245 28393 14245 28394 24816 28394 14150 28394 14245 28395 14150 28395 14248 28395 14248 28396 14150 28396 24818 28396 14248 28397 24818 28397 14151 28397 14151 28398 24818 28398 24821 28398 14151 28399 24821 28399 14152 28399 14152 28400 24821 28400 24822 28400 14152 28401 24822 28401 14251 28401 14251 28402 24822 28402 14153 28402 14251 28403 14153 28403 24619 28403 24619 28404 14153 28404 24823 28404 14255 28405 14154 28405 14155 28405 14155 28406 14154 28406 24807 28406 14155 28407 24807 28407 14156 28407 14156 28408 24807 28408 24805 28408 14156 28409 24805 28409 14157 28409 14157 28410 24805 28410 24804 28410 14157 28411 24804 28411 14259 28411 14259 28412 24804 28412 24803 28412 14259 28413 24803 28413 14158 28413 14158 28414 24803 28414 14160 28414 14158 28415 14160 28415 14159 28415 14159 28416 14160 28416 24800 28416 24615 28417 14161 28417 14261 28417 14261 28418 14161 28418 14162 28418 14261 28419 14162 28419 14163 28419 14163 28420 14162 28420 24784 28420 14163 28421 24784 28421 14263 28421 14263 28422 24784 28422 24782 28422 14263 28423 24782 28423 14164 28423 14164 28424 24782 28424 14166 28424 14164 28425 14166 28425 14165 28425 14165 28426 14166 28426 24794 28426 14165 28427 24794 28427 14167 28427 14167 28428 24794 28428 24793 28428 14167 28429 24793 28429 24518 28429 24518 28430 24793 28430 24792 28430 24609 28431 24611 28431 14268 28431 14268 28432 24611 28432 14168 28432 14268 28433 14168 28433 14169 28433 14169 28434 14168 28434 14171 28434 14169 28435 14171 28435 14170 28435 14170 28436 14171 28436 24772 28436 14170 28437 24772 28437 14172 28437 14172 28438 24772 28438 14173 28438 14172 28439 14173 28439 14274 28439 14274 28440 14173 28440 24775 28440 14274 28441 24775 28441 14276 28441 14276 28442 24775 28442 24776 28442 17548 28443 14174 28443 14176 28443 14176 28444 14174 28444 14175 28444 14176 28445 14175 28445 17558 28445 17558 28446 14175 28446 17559 28446 17559 28447 14175 28447 14177 28447 17559 28448 14177 28448 17560 28448 17560 28449 14177 28449 17556 28449 17556 28450 14177 28450 14178 28450 17556 28451 14178 28451 17557 28451 17557 28452 14178 28452 17553 28452 17553 28453 14178 28453 14061 28453 17553 28454 14061 28454 17551 28454 17551 28455 14061 28455 14179 28455 14179 28456 14061 28456 14180 28456 14179 28457 14180 28457 17550 28457 17550 28458 14180 28458 14181 28458 14181 28459 14180 28459 14064 28459 14181 28460 14064 28460 24599 28460 14182 28461 14102 28461 17572 28461 17572 28462 14102 28462 14183 28462 17572 28463 14183 28463 17573 28463 17573 28464 14183 28464 17574 28464 17574 28465 14183 28465 14184 28465 17574 28466 14184 28466 17570 28466 17570 28467 14184 28467 17571 28467 17571 28468 14184 28468 14105 28468 17571 28469 14105 28469 14185 28469 14185 28470 14105 28470 17568 28470 17568 28471 14105 28471 14106 28471 17568 28472 14106 28472 17565 28472 17565 28473 14106 28473 17566 28473 17566 28474 14106 28474 14186 28474 17566 28475 14186 28475 17567 28475 17567 28476 14186 28476 17562 28476 17562 28477 14186 28477 24666 28477 17562 28478 24666 28478 24588 28478 24586 28479 14187 28479 17577 28479 17577 28480 14187 28480 14188 28480 17577 28481 14188 28481 14189 28481 14189 28482 14188 28482 14110 28482 14189 28483 14110 28483 14190 28483 14190 28484 14110 28484 14191 28484 14190 28485 14191 28485 14192 28485 14192 28486 14191 28486 14113 28486 14192 28487 14113 28487 17580 28487 17580 28488 14113 28488 14193 28488 17580 28489 14193 28489 14194 28489 14194 28490 14193 28490 14195 28490 14194 28491 14195 28491 17725 28491 17725 28492 14195 28492 14116 28492 17724 28493 14197 28493 14196 28493 14196 28494 14197 28494 14117 28494 14196 28495 14117 28495 14199 28495 14199 28496 14117 28496 14198 28496 14199 28497 14198 28497 14200 28497 14200 28498 14198 28498 14201 28498 14200 28499 14201 28499 17585 28499 17585 28500 14201 28500 14203 28500 17585 28501 14203 28501 14202 28501 14202 28502 14203 28502 14121 28502 14202 28503 14121 28503 17587 28503 17587 28504 14121 28504 14122 28504 14204 28505 24642 28505 17596 28505 17596 28506 24642 28506 14130 28506 17596 28507 14130 28507 17593 28507 17593 28508 14130 28508 14131 28508 17593 28509 14131 28509 17592 28509 17592 28510 14131 28510 14128 28510 17592 28511 14128 28511 14205 28511 14205 28512 14128 28512 14206 28512 14205 28513 14206 28513 14207 28513 14207 28514 14206 28514 14126 28514 14207 28515 14126 28515 14208 28515 14208 28516 14126 28516 14210 28516 14208 28517 14210 28517 14209 28517 14209 28518 14210 28518 14125 28518 14209 28519 14125 28519 17589 28519 17589 28520 14125 28520 14211 28520 17589 28521 14211 28521 14212 28521 14212 28522 14211 28522 14213 28522 14212 28523 14213 28523 14214 28523 14214 28524 14213 28524 14124 28524 14214 28525 14124 28525 14215 28525 14215 28526 14124 28526 14216 28526 14215 28527 14216 28527 14217 28527 14217 28528 14216 28528 24648 28528 14218 28529 14219 28529 17606 28529 17606 28530 14219 28530 14222 28530 17606 28531 14222 28531 14220 28531 14220 28532 14222 28532 14221 28532 14221 28533 14222 28533 14132 28533 14221 28534 14132 28534 17603 28534 17603 28535 14132 28535 17604 28535 17604 28536 14132 28536 14223 28536 17604 28537 14223 28537 17600 28537 17600 28538 14223 28538 17601 28538 17601 28539 14223 28539 14134 28539 17601 28540 14134 28540 14224 28540 14224 28541 14134 28541 14225 28541 14225 28542 14134 28542 14226 28542 14225 28543 14226 28543 17599 28543 17599 28544 14226 28544 17598 28544 17598 28545 14226 28545 14227 28545 17598 28546 14227 28546 24557 28546 14228 28547 14230 28547 14229 28547 14229 28548 14230 28548 14135 28548 14229 28549 14135 28549 14231 28549 14231 28550 14135 28550 14136 28550 14231 28551 14136 28551 17608 28551 17608 28552 14136 28552 14138 28552 17608 28553 14138 28553 17609 28553 17609 28554 14138 28554 14232 28554 17609 28555 14232 28555 17610 28555 17610 28556 14232 28556 14141 28556 17610 28557 14141 28557 14233 28557 14233 28558 14141 28558 14234 28558 14233 28559 14234 28559 14235 28559 14235 28560 14234 28560 14236 28560 24550 28561 24630 28561 17614 28561 17614 28562 24630 28562 14237 28562 17614 28563 14237 28563 17615 28563 17615 28564 14237 28564 14238 28564 17615 28565 14238 28565 14239 28565 14239 28566 14238 28566 14241 28566 14239 28567 14241 28567 14240 28567 14240 28568 14241 28568 14147 28568 14240 28569 14147 28569 17620 28569 17620 28570 14147 28570 14242 28570 17620 28571 14242 28571 14243 28571 14243 28572 14242 28572 24626 28572 24544 28573 14149 28573 17629 28573 17629 28574 14149 28574 14245 28574 17629 28575 14245 28575 14244 28575 14244 28576 14245 28576 14246 28576 14246 28577 14245 28577 14248 28577 14246 28578 14248 28578 14247 28578 14247 28579 14248 28579 17627 28579 17627 28580 14248 28580 14151 28580 17627 28581 14151 28581 17628 28581 17628 28582 14151 28582 14249 28582 14249 28583 14151 28583 14152 28583 14249 28584 14152 28584 14250 28584 14250 28585 14152 28585 17625 28585 17625 28586 14152 28586 14251 28586 17625 28587 14251 28587 17623 28587 17623 28588 14251 28588 17622 28588 17622 28589 14251 28589 24619 28589 17622 28590 24619 28590 14252 28590 14253 28591 14255 28591 14254 28591 14254 28592 14255 28592 14155 28592 14254 28593 14155 28593 14256 28593 14256 28594 14155 28594 14156 28594 14256 28595 14156 28595 17634 28595 17634 28596 14156 28596 14157 28596 17634 28597 14157 28597 14257 28597 14257 28598 14157 28598 14259 28598 14257 28599 14259 28599 14258 28599 14258 28600 14259 28600 14158 28600 14258 28601 14158 28601 14260 28601 14260 28602 14158 28602 14159 28602 24527 28603 24615 28603 14261 28603 24527 28604 14261 28604 14262 28604 14262 28605 14261 28605 14163 28605 14262 28606 14163 28606 17642 28606 17642 28607 14163 28607 17643 28607 17643 28608 14163 28608 14263 28608 17643 28609 14263 28609 17644 28609 17644 28610 14263 28610 14264 28610 14264 28611 14263 28611 14164 28611 14264 28612 14164 28612 17641 28612 17641 28613 14164 28613 14265 28613 14265 28614 14164 28614 14165 28614 14265 28615 14165 28615 17639 28615 17639 28616 14165 28616 14167 28616 17639 28617 14167 28617 14266 28617 14266 28618 14167 28618 24518 28618 14266 28619 24518 28619 14267 28619 17654 28620 24609 28620 17649 28620 17649 28621 24609 28621 14268 28621 17649 28622 14268 28622 17650 28622 17650 28623 14268 28623 17652 28623 17652 28624 14268 28624 14169 28624 17652 28625 14169 28625 17653 28625 17653 28626 14169 28626 14269 28626 14269 28627 14169 28627 14170 28627 14269 28628 14170 28628 17648 28628 17648 28629 14170 28629 14270 28629 14270 28630 14170 28630 14172 28630 14270 28631 14172 28631 14271 28631 14271 28632 14172 28632 14272 28632 14272 28633 14172 28633 14274 28633 14272 28634 14274 28634 14273 28634 14273 28635 14274 28635 14275 28635 14275 28636 14274 28636 14276 28636 14275 28637 14276 28637 14277 28637 24234 28638 14278 28638 25750 28638 14300 28639 14279 28639 14280 28639 14280 28640 14279 28640 14286 28640 24258 28641 25765 28641 14282 28641 14282 28642 25765 28642 25763 28642 24229 28643 25763 28643 24429 28643 24429 28644 25763 28644 14284 28644 24229 28645 14281 28645 25763 28645 25763 28646 14281 28646 24436 28646 25763 28647 24436 28647 14282 28647 14287 28648 24427 28648 24426 28648 24426 28649 14283 28649 14287 28649 14287 28650 14283 28650 24261 28650 14287 28651 24261 28651 14284 28651 14284 28652 24261 28652 14285 28652 14284 28653 14285 28653 24429 28653 14279 28654 24424 28654 14286 28654 14286 28655 24424 28655 24231 28655 14286 28656 24231 28656 14287 28656 14287 28657 24231 28657 14308 28657 14287 28658 14308 28658 24427 28658 14300 28659 14280 28659 14299 28659 14299 28660 14280 28660 14288 28660 14299 28661 14288 28661 24408 28661 14289 28662 14290 28662 14288 28662 14288 28663 14290 28663 14291 28663 14288 28664 14291 28664 24408 28664 14292 28665 14380 28665 14294 28665 14294 28666 14380 28666 24406 28666 14294 28667 24406 28667 14289 28667 14289 28668 24406 28668 14293 28668 14289 28669 14293 28669 14290 28669 25750 28670 14278 28670 14294 28670 14294 28671 14278 28671 24233 28671 14294 28672 24233 28672 14292 28672 24234 28673 25750 28673 14295 28673 14295 28674 25750 28674 25752 28674 14295 28675 25752 28675 24235 28675 25749 28676 14365 28676 14371 28676 14371 28677 24373 28677 25749 28677 25749 28678 24373 28678 24290 28678 25749 28679 24290 28679 14296 28679 14296 28680 24290 28680 14297 28680 14296 28681 14297 28681 25752 28681 25752 28682 14297 28682 24383 28682 25752 28683 24383 28683 24235 28683 13710 28684 24301 28684 25749 28684 25749 28685 24301 28685 24361 28685 25749 28686 24361 28686 14365 28686 24409 28687 24218 28687 14486 28687 14486 28688 14485 28688 24409 28688 24409 28689 14485 28689 14484 28689 24409 28690 14484 28690 24410 28690 14484 28691 14483 28691 24410 28691 24410 28692 14483 28692 14481 28692 24410 28693 14481 28693 24232 28693 24232 28694 14481 28694 14480 28694 24232 28695 14480 28695 14299 28695 14480 28696 14298 28696 14299 28696 14299 28697 14298 28697 14479 28697 14299 28698 14479 28698 14300 28698 14300 28699 14479 28699 14301 28699 14300 28700 14301 28700 14302 28700 14302 28701 14301 28701 14477 28701 14302 28702 14477 28702 14303 28702 14474 28703 24224 28703 14475 28703 14475 28704 24224 28704 14303 28704 14475 28705 14303 28705 14476 28705 14476 28706 14303 28706 14477 28706 14307 28707 14493 28707 24412 28707 14492 28708 24230 28708 14490 28708 14490 28709 24230 28709 24425 28709 14490 28710 24425 28710 14488 28710 14488 28711 24425 28711 24423 28711 14488 28712 24423 28712 14487 28712 14487 28713 24423 28713 14304 28713 14487 28714 14304 28714 14305 28714 14305 28715 14304 28715 24209 28715 24412 28716 14306 28716 14307 28716 14307 28717 14306 28717 14308 28717 14307 28718 14308 28718 14492 28718 14492 28719 14308 28719 24231 28719 14492 28720 24231 28720 24230 28720 24229 28721 24228 28721 14309 28721 14310 28722 14311 28722 14312 28722 14312 28723 14495 28723 14310 28723 14310 28724 14495 28724 14497 28724 14310 28725 14497 28725 24435 28725 14500 28726 24430 28726 24428 28726 14497 28727 14313 28727 24435 28727 24435 28728 14313 28728 14499 28728 24435 28729 14499 28729 24428 28729 24428 28730 14499 28730 14314 28730 24428 28731 14314 28731 14500 28731 14500 28732 14315 28732 24430 28732 24430 28733 14315 28733 14316 28733 24430 28734 14316 28734 24431 28734 24431 28735 14316 28735 14317 28735 24431 28736 14317 28736 24228 28736 24228 28737 14317 28737 14503 28737 24228 28738 14503 28738 14309 28738 24229 28739 14309 28739 14281 28739 14281 28740 14309 28740 24208 28740 14281 28741 24208 28741 14318 28741 24354 28742 24199 28742 14320 28742 14320 28743 24199 28743 14319 28743 14507 28744 24253 28744 14321 28744 14319 28745 14505 28745 14320 28745 14320 28746 14505 28746 14322 28746 14320 28747 14322 28747 14321 28747 14321 28748 14322 28748 14506 28748 14321 28749 14506 28749 14507 28749 14507 28750 14508 28750 24253 28750 24253 28751 14508 28751 14511 28751 24253 28752 14511 28752 24256 28752 14511 28753 14323 28753 24256 28753 24256 28754 14323 28754 14324 28754 24256 28755 14324 28755 14325 28755 23915 28756 24255 28756 14512 28756 14512 28757 24255 28757 14325 28757 14512 28758 14325 28758 14326 28758 14326 28759 14325 28759 14324 28759 24194 28760 23914 28760 14327 28760 14327 28761 23914 28761 14515 28761 14328 28762 14330 28762 14329 28762 14515 28763 14516 28763 14327 28763 14327 28764 14516 28764 14518 28764 14327 28765 14518 28765 14329 28765 14329 28766 14518 28766 14520 28766 14329 28767 14520 28767 14328 28767 14328 28768 14521 28768 14330 28768 14330 28769 14521 28769 14523 28769 14330 28770 14523 28770 24349 28770 14523 28771 14331 28771 24349 28771 24349 28772 14331 28772 14333 28772 24349 28773 14333 28773 24444 28773 24188 28774 14332 28774 14528 28774 14528 28775 14332 28775 24444 28775 14528 28776 24444 28776 14526 28776 14526 28777 24444 28777 14333 28777 24185 28778 23901 28778 24342 28778 24342 28779 23901 28779 14530 28779 14337 28780 14334 28780 14335 28780 14530 28781 14531 28781 24342 28781 24342 28782 14531 28782 14336 28782 24342 28783 14336 28783 14335 28783 14335 28784 14336 28784 14534 28784 14335 28785 14534 28785 14337 28785 14337 28786 14338 28786 14334 28786 14334 28787 14338 28787 14339 28787 14334 28788 14339 28788 14340 28788 14339 28789 14537 28789 14340 28789 14340 28790 14537 28790 14539 28790 14340 28791 14539 28791 24453 28791 24177 28792 14341 28792 14542 28792 14542 28793 14341 28793 24453 28793 14542 28794 24453 28794 14342 28794 14342 28795 24453 28795 14539 28795 14551 28796 24465 28796 14550 28796 14550 28797 24465 28797 24466 28797 14550 28798 24466 28798 14343 28798 14343 28799 24466 28799 14344 28799 14343 28800 14344 28800 14548 28800 14548 28801 14344 28801 14345 28801 14548 28802 14345 28802 14547 28802 14547 28803 14345 28803 24341 28803 14547 28804 24341 28804 14546 28804 14546 28805 24341 28805 14346 28805 14546 28806 14346 28806 14545 28806 14545 28807 14346 28807 14348 28807 14545 28808 14348 28808 14347 28808 14347 28809 14348 28809 24175 28809 24493 28810 24492 28810 14349 28810 14349 28811 14553 28811 24493 28811 24493 28812 14553 28812 14350 28812 24493 28813 14350 28813 14351 28813 14350 28814 14352 28814 14351 28814 14351 28815 14352 28815 14353 28815 14351 28816 14353 28816 14354 28816 14353 28817 14557 28817 14354 28817 14354 28818 14557 28818 14558 28818 14354 28819 14558 28819 14355 28819 14558 28820 14559 28820 14355 28820 14355 28821 14559 28821 14356 28821 14355 28822 14356 28822 24488 28822 24488 28823 14356 28823 14357 28823 24488 28824 14357 28824 24486 28824 24163 28825 14358 28825 14561 28825 14561 28826 14358 28826 24486 28826 14561 28827 24486 28827 14359 28827 14359 28828 24486 28828 14357 28828 24157 28829 24318 28829 14566 28829 14566 28830 24318 28830 24315 28830 14566 28831 24315 28831 14360 28831 14360 28832 24315 28832 14361 28832 14360 28833 14361 28833 14565 28833 14565 28834 14361 28834 24307 28834 14565 28835 24307 28835 14362 28835 14362 28836 24307 28836 24306 28836 14362 28837 24306 28837 14363 28837 14363 28838 24306 28838 14364 28838 14363 28839 14364 28839 23870 28839 23870 28840 14364 28840 24300 28840 14568 28841 14371 28841 23864 28841 23864 28842 14371 28842 14365 28842 23864 28843 14365 28843 24362 28843 14574 28844 24369 28844 14366 28844 14366 28845 24369 28845 24370 28845 14366 28846 24370 28846 14573 28846 14573 28847 24370 28847 14368 28847 14573 28848 14368 28848 14367 28848 14367 28849 14368 28849 24372 28849 14367 28850 24372 28850 14570 28850 14570 28851 24372 28851 14369 28851 14570 28852 14369 28852 14568 28852 14568 28853 14369 28853 14370 28853 14568 28854 14370 28854 14371 28854 14576 28855 14373 28855 14372 28855 14372 28856 14373 28856 24384 28856 14372 28857 24384 28857 24382 28857 14582 28858 24389 28858 14374 28858 14374 28859 24389 28859 14375 28859 14374 28860 14375 28860 14581 28860 14581 28861 14375 28861 24386 28861 14581 28862 24386 28862 14580 28862 14580 28863 24386 28863 14376 28863 14580 28864 14376 28864 14579 28864 14579 28865 14376 28865 14377 28865 14579 28866 14377 28866 14578 28866 14578 28867 14377 28867 14295 28867 14578 28868 14295 28868 14576 28868 14576 28869 14295 28869 24235 28869 14576 28870 24235 28870 14373 28870 14584 28871 14585 28871 24406 28871 14378 28872 14379 28872 24397 28872 24397 28873 14379 28873 14583 28873 24397 28874 14583 28874 24398 28874 24398 28875 14583 28875 14584 28875 24398 28876 14584 28876 14380 28876 14380 28877 14584 28877 24406 28877 24153 28878 24399 28878 14382 28878 14382 28879 24399 28879 14381 28879 14382 28880 14381 28880 14587 28880 14587 28881 14381 28881 24405 28881 14587 28882 24405 28882 14585 28882 14585 28883 24405 28883 14383 28883 14585 28884 14383 28884 24406 28884 14384 28885 24352 28885 14592 28885 14592 28886 24352 28886 14385 28886 14592 28887 14385 28887 14386 28887 14386 28888 14385 28888 24360 28888 14386 28889 24360 28889 14387 28889 14387 28890 24360 28890 24359 28890 14387 28891 24359 28891 14388 28891 14388 28892 24359 28892 24358 28892 14388 28893 24358 28893 14590 28893 14590 28894 24358 28894 24286 28894 14590 28895 24286 28895 14589 28895 14589 28896 24286 28896 14389 28896 14589 28897 14389 28897 14588 28897 14588 28898 14389 28898 24295 28898 24127 28899 14390 28899 23814 28899 23814 28900 14390 28900 24355 28900 24105 28901 24343 28901 14598 28901 14598 28902 24343 28902 14391 28902 14598 28903 14391 28903 14392 28903 14392 28904 14391 28904 14393 28904 14392 28905 14393 28905 23794 28905 23794 28906 14393 28906 24101 28906 23788 28907 24337 28907 24098 28907 24098 28908 24337 28908 24328 28908 14394 28909 14395 28909 14396 28909 14396 28910 14395 28910 14397 28910 14396 28911 14397 28911 24082 28911 24082 28912 14397 28912 24357 28912 14600 28913 14398 28913 14399 28913 14399 28914 14398 28914 24279 28914 23712 28915 14400 28915 14601 28915 14601 28916 14400 28916 14401 28916 14601 28917 14401 28917 14602 28917 14602 28918 14401 28918 14402 28918 14602 28919 14402 28919 23710 28919 23710 28920 14402 28920 14403 28920 24025 28921 14404 28921 24289 28921 24289 28922 14404 28922 14405 28922 24289 28923 14405 28923 14406 28923 14406 28924 14405 28924 14407 28924 14406 28925 14407 28925 24381 28925 24381 28926 14407 28926 14408 28926 24381 28927 14408 28927 14409 28927 14409 28928 14408 28928 14410 28928 14409 28929 14410 28929 14411 28929 14411 28930 14410 28930 14412 28930 14411 28931 14412 28931 24377 28931 24377 28932 14412 28932 14611 28932 24390 28933 14413 28933 14414 28933 14414 28934 14413 28934 14644 28934 14414 28935 14644 28935 24392 28935 24392 28936 14644 28936 14645 28936 24392 28937 14645 28937 14415 28937 14415 28938 14645 28938 14416 28938 14415 28939 14416 28939 14418 28939 14418 28940 14416 28940 14417 28940 14418 28941 14417 28941 24393 28941 24393 28942 14417 28942 14419 28942 24393 28943 14419 28943 14420 28943 14420 28944 14419 28944 14651 28944 14420 28945 14651 28945 24391 28945 24391 28946 14651 28946 23387 28946 24008 28947 14421 28947 24404 28947 24404 28948 14421 28948 14422 28948 24404 28949 14422 28949 24400 28949 24400 28950 14422 28950 14423 28950 24400 28951 14423 28951 24401 28951 24401 28952 14423 28952 14655 28952 24401 28953 14655 28953 24402 28953 24402 28954 14655 28954 14424 28954 24402 28955 14424 28955 24407 28955 24407 28956 14424 28956 14425 28956 24407 28957 14425 28957 23999 28957 23999 28958 14425 28958 14426 28958 24417 28959 23998 28959 24415 28959 24415 28960 23998 28960 14427 28960 24415 28961 14427 28961 24414 28961 24414 28962 14427 28962 14428 28962 24414 28963 14428 28963 24413 28963 24413 28964 14428 28964 14430 28964 24413 28965 14430 28965 14429 28965 14429 28966 14430 28966 14660 28966 14429 28967 14660 28967 24262 28967 24262 28968 14660 28968 14431 28968 24262 28969 14431 28969 14432 28969 14432 28970 14431 28970 14434 28970 14432 28971 14434 28971 14433 28971 14433 28972 14434 28972 23368 28972 14435 28973 23991 28973 14436 28973 14436 28974 23991 28974 14661 28974 14436 28975 14661 28975 14437 28975 14437 28976 14661 28976 14662 28976 14437 28977 14662 28977 24251 28977 24251 28978 14662 28978 14664 28978 24251 28979 14664 28979 24252 28979 24252 28980 14664 28980 14665 28980 24252 28981 14665 28981 14438 28981 14438 28982 14665 28982 14666 28982 14438 28983 14666 28983 24257 28983 24257 28984 14666 28984 14667 28984 23981 28985 14440 28985 14439 28985 14439 28986 14440 28986 14668 28986 14439 28987 14668 28987 14441 28987 14441 28988 14668 28988 14442 28988 14441 28989 14442 28989 24245 28989 24245 28990 14442 28990 14669 28990 24245 28991 14669 28991 24242 28991 24242 28992 14669 28992 14672 28992 24242 28993 14672 28993 14444 28993 14444 28994 14672 28994 14443 28994 14444 28995 14443 28995 23971 28995 23971 28996 14443 28996 23356 28996 24463 28997 14445 28997 14446 28997 14446 28998 14445 28998 14447 28998 14446 28999 14447 28999 14448 28999 14448 29000 14447 29000 14674 29000 14448 29001 14674 29001 24456 29001 24456 29002 14674 29002 14675 29002 24456 29003 14675 29003 14449 29003 14449 29004 14675 29004 14450 29004 14449 29005 14450 29005 14452 29005 14452 29006 14450 29006 14451 29006 14452 29007 14451 29007 14453 29007 14453 29008 14451 29008 14677 29008 24484 29009 23340 29009 14454 29009 24484 29010 14454 29010 14455 29010 14455 29011 14454 29011 14688 29011 14455 29012 14688 29012 24485 29012 24485 29013 14688 29013 14456 29013 24485 29014 14456 29014 14458 29014 14458 29015 14456 29015 14457 29015 14458 29016 14457 29016 14459 29016 14457 29017 14460 29017 14459 29017 14459 29018 14460 29018 14461 29018 14459 29019 14461 29019 14462 29019 14462 29020 14461 29020 14684 29020 14684 29021 14683 29021 14462 29021 14462 29022 14683 29022 14678 29022 14462 29023 14678 29023 14463 29023 14463 29024 14678 29024 14680 29024 14463 29025 14680 29025 24477 29025 14464 29026 23326 29026 14699 29026 14464 29027 14699 29027 14465 29027 14465 29028 14699 29028 14466 29028 14465 29029 14466 29029 24322 29029 24322 29030 14466 29030 14701 29030 24322 29031 14701 29031 14467 29031 14467 29032 14701 29032 14469 29032 14467 29033 14469 29033 14468 29033 14469 29034 14698 29034 14468 29034 14468 29035 14698 29035 14697 29035 14468 29036 14697 29036 14470 29036 14470 29037 14697 29037 14695 29037 14695 29038 14694 29038 14470 29038 14470 29039 14694 29039 14693 29039 14470 29040 14693 29040 14471 29040 14471 29041 14693 29041 14472 29041 14471 29042 14472 29042 24310 29042 14473 29043 14474 29043 14747 29043 14747 29044 14474 29044 14475 29044 14747 29045 14475 29045 14749 29045 14749 29046 14475 29046 14476 29046 14749 29047 14476 29047 14751 29047 14751 29048 14476 29048 14477 29048 14751 29049 14477 29049 14478 29049 14478 29050 14477 29050 14301 29050 14478 29051 14301 29051 14753 29051 14753 29052 14301 29052 14479 29052 14753 29053 14479 29053 14750 29053 14750 29054 14479 29054 14298 29054 14750 29055 14298 29055 14754 29055 14754 29056 14298 29056 14480 29056 14754 29057 14480 29057 14755 29057 14755 29058 14480 29058 14481 29058 14755 29059 14481 29059 14757 29059 14757 29060 14481 29060 14483 29060 14757 29061 14483 29061 14482 29061 14482 29062 14483 29062 14484 29062 14482 29063 14484 29063 14758 29063 14758 29064 14484 29064 14485 29064 14758 29065 14485 29065 23948 29065 23948 29066 14485 29066 14486 29066 14305 29067 23941 29067 14487 29067 14487 29068 23941 29068 14744 29068 14487 29069 14744 29069 14488 29069 14488 29070 14744 29070 14489 29070 14488 29071 14489 29071 14490 29071 14490 29072 14489 29072 14745 29072 14490 29073 14745 29073 14492 29073 14492 29074 14745 29074 14491 29074 14492 29075 14491 29075 14307 29075 14307 29076 14491 29076 14746 29076 14307 29077 14746 29077 14493 29077 14493 29078 14746 29078 14494 29078 14312 29079 23934 29079 14495 29079 14495 29080 23934 29080 14496 29080 14495 29081 14496 29081 14497 29081 14497 29082 14496 29082 14313 29082 14313 29083 14496 29083 14498 29083 14313 29084 14498 29084 14499 29084 14499 29085 14498 29085 14314 29085 14314 29086 14498 29086 14501 29086 14314 29087 14501 29087 14500 29087 14500 29088 14501 29088 14315 29088 14315 29089 14501 29089 14740 29089 14315 29090 14740 29090 14316 29090 14316 29091 14740 29091 14317 29091 14317 29092 14740 29092 14502 29092 14317 29093 14502 29093 14503 29093 14503 29094 14502 29094 14309 29094 14309 29095 14502 29095 14742 29095 14309 29096 14742 29096 24208 29096 24199 29097 14504 29097 14319 29097 14319 29098 14504 29098 14735 29098 14319 29099 14735 29099 14505 29099 14505 29100 14735 29100 14736 29100 14505 29101 14736 29101 14322 29101 14322 29102 14736 29102 14737 29102 14322 29103 14737 29103 14506 29103 14506 29104 14737 29104 14734 29104 14506 29105 14734 29105 14507 29105 14507 29106 14734 29106 14733 29106 14507 29107 14733 29107 14508 29107 14508 29108 14733 29108 14509 29108 14508 29109 14509 29109 14511 29109 14511 29110 14509 29110 14510 29110 14511 29111 14510 29111 14323 29111 14323 29112 14510 29112 14732 29112 14323 29113 14732 29113 14324 29113 14324 29114 14732 29114 14730 29114 14324 29115 14730 29115 14326 29115 14326 29116 14730 29116 14513 29116 14326 29117 14513 29117 14512 29117 14512 29118 14513 29118 14729 29118 14512 29119 14729 29119 23915 29119 23915 29120 14729 29120 14728 29120 23914 29121 14514 29121 14515 29121 14515 29122 14514 29122 14517 29122 14515 29123 14517 29123 14516 29123 14516 29124 14517 29124 14725 29124 14516 29125 14725 29125 14518 29125 14518 29126 14725 29126 14519 29126 14518 29127 14519 29127 14520 29127 14520 29128 14519 29128 14723 29128 14520 29129 14723 29129 14328 29129 14328 29130 14723 29130 14721 29130 14328 29131 14721 29131 14521 29131 14521 29132 14721 29132 14522 29132 14521 29133 14522 29133 14523 29133 14523 29134 14522 29134 14524 29134 14523 29135 14524 29135 14331 29135 14331 29136 14524 29136 14525 29136 14331 29137 14525 29137 14333 29137 14333 29138 14525 29138 14720 29138 14333 29139 14720 29139 14526 29139 14526 29140 14720 29140 14527 29140 14526 29141 14527 29141 14528 29141 14528 29142 14527 29142 14529 29142 14528 29143 14529 29143 24188 29143 24188 29144 14529 29144 14719 29144 23901 29145 23220 29145 14530 29145 14530 29146 23220 29146 14532 29146 14530 29147 14532 29147 14531 29147 14531 29148 14532 29148 14533 29148 14531 29149 14533 29149 14336 29149 14336 29150 14533 29150 14535 29150 14336 29151 14535 29151 14534 29151 14534 29152 14535 29152 14717 29152 14534 29153 14717 29153 14337 29153 14337 29154 14717 29154 14715 29154 14337 29155 14715 29155 14338 29155 14338 29156 14715 29156 14536 29156 14338 29157 14536 29157 14339 29157 14339 29158 14536 29158 14711 29158 14339 29159 14711 29159 14537 29159 14537 29160 14711 29160 14538 29160 14537 29161 14538 29161 14539 29161 14539 29162 14538 29162 14540 29162 14539 29163 14540 29163 14342 29163 14342 29164 14540 29164 14713 29164 14342 29165 14713 29165 14542 29165 14542 29166 14713 29166 14541 29166 14542 29167 14541 29167 24177 29167 24177 29168 14541 29168 14543 29168 14347 29169 14544 29169 14545 29169 14545 29170 14544 29170 14794 29170 14545 29171 14794 29171 14546 29171 14546 29172 14794 29172 14796 29172 14546 29173 14796 29173 14547 29173 14547 29174 14796 29174 14798 29174 14547 29175 14798 29175 14548 29175 14548 29176 14798 29176 14800 29176 14548 29177 14800 29177 14343 29177 14343 29178 14800 29178 14549 29178 14343 29179 14549 29179 14550 29179 14550 29180 14549 29180 14801 29180 14550 29181 14801 29181 14551 29181 14551 29182 14801 29182 14552 29182 14349 29183 14554 29183 14553 29183 14553 29184 14554 29184 14555 29184 14553 29185 14555 29185 14350 29185 14350 29186 14555 29186 14352 29186 14352 29187 14555 29187 14556 29187 14352 29188 14556 29188 14353 29188 14353 29189 14556 29189 14557 29189 14557 29190 14556 29190 14791 29190 14557 29191 14791 29191 14558 29191 14558 29192 14791 29192 14559 29192 14559 29193 14791 29193 14560 29193 14559 29194 14560 29194 14356 29194 14356 29195 14560 29195 14357 29195 14357 29196 14560 29196 14792 29196 14357 29197 14792 29197 14359 29197 14359 29198 14792 29198 14561 29198 14561 29199 14792 29199 14562 29199 14561 29200 14562 29200 24163 29200 23870 29201 14563 29201 14363 29201 14363 29202 14563 29202 14564 29202 14363 29203 14564 29203 14362 29203 14362 29204 14564 29204 14782 29204 14362 29205 14782 29205 14565 29205 14565 29206 14782 29206 14784 29206 14565 29207 14784 29207 14360 29207 14360 29208 14784 29208 14785 29208 14360 29209 14785 29209 14566 29209 14566 29210 14785 29210 14567 29210 14566 29211 14567 29211 24157 29211 24157 29212 14567 29212 14788 29212 23864 29213 14569 29213 14568 29213 14568 29214 14569 29214 14776 29214 14568 29215 14776 29215 14570 29215 14570 29216 14776 29216 14571 29216 14570 29217 14571 29217 14367 29217 14367 29218 14571 29218 14572 29218 14367 29219 14572 29219 14573 29219 14573 29220 14572 29220 14780 29220 14573 29221 14780 29221 14366 29221 14366 29222 14780 29222 14575 29222 14366 29223 14575 29223 14574 29223 14574 29224 14575 29224 23857 29224 14372 29225 23168 29225 14576 29225 14576 29226 23168 29226 14577 29226 14576 29227 14577 29227 14578 29227 14578 29228 14577 29228 14767 29228 14578 29229 14767 29229 14579 29229 14579 29230 14767 29230 14769 29230 14579 29231 14769 29231 14580 29231 14580 29232 14769 29232 14771 29232 14580 29233 14771 29233 14581 29233 14581 29234 14771 29234 14772 29234 14581 29235 14772 29235 14374 29235 14374 29236 14772 29236 14774 29236 14374 29237 14774 29237 14582 29237 14582 29238 14774 29238 23852 29238 14379 29239 14759 29239 14583 29239 14583 29240 14759 29240 14760 29240 14583 29241 14760 29241 14584 29241 14584 29242 14760 29242 14761 29242 14584 29243 14761 29243 14585 29243 14585 29244 14761 29244 14586 29244 14585 29245 14586 29245 14587 29245 14587 29246 14586 29246 14762 29246 14587 29247 14762 29247 14382 29247 14382 29248 14762 29248 14763 29248 14382 29249 14763 29249 24153 29249 24153 29250 14763 29250 14765 29250 14588 29251 23126 29251 14589 29251 14589 29252 23126 29252 23127 29252 14589 29253 23127 29253 14590 29253 14590 29254 23127 29254 23128 29254 14590 29255 23128 29255 14388 29255 14388 29256 23128 29256 14591 29256 14388 29257 14591 29257 14387 29257 14387 29258 14591 29258 23123 29258 14387 29259 23123 29259 14386 29259 14386 29260 23123 29260 14593 29260 14386 29261 14593 29261 14592 29261 14592 29262 14593 29262 23120 29262 14592 29263 23120 29263 14384 29263 14384 29264 23120 29264 23124 29264 24135 29265 14705 29265 14594 29265 14594 29266 14705 29266 14595 29266 14594 29267 14595 29267 23829 29267 23819 29268 24127 29268 14596 29268 14596 29269 24127 29269 23814 29269 14597 29270 24105 29270 14598 29270 14597 29271 14598 29271 23318 29271 23318 29272 14598 29272 14392 29272 23318 29273 14392 29273 14599 29273 14599 29274 14392 29274 23320 29274 23320 29275 14392 29275 23794 29275 23320 29276 23794 29276 23792 29276 23732 29277 14600 29277 23268 29277 23268 29278 14600 29278 14399 29278 23287 29279 23286 29279 14601 29279 14601 29280 23286 29280 23712 29280 23287 29281 14601 29281 14603 29281 14603 29282 14601 29282 14602 29282 14603 29283 14602 29283 14604 29283 14604 29284 14602 29284 14605 29284 14605 29285 14602 29285 23710 29285 14605 29286 23710 29286 14606 29286 23701 29287 23700 29287 14607 29287 23701 29288 14607 29288 24033 29288 24033 29289 14607 29289 23702 29289 24033 29290 23702 29290 24032 29290 14404 29291 14608 29291 14405 29291 14405 29292 14608 29292 14609 29292 14405 29293 14609 29293 14407 29293 14407 29294 14609 29294 23395 29294 14407 29295 23395 29295 14408 29295 14408 29296 23395 29296 14610 29296 14408 29297 14610 29297 14410 29297 14410 29298 14610 29298 23394 29298 14410 29299 23394 29299 14412 29299 14412 29300 23394 29300 23400 29300 14412 29301 23400 29301 14611 29301 14611 29302 23400 29302 23697 29302 23103 29303 14612 29303 14613 29303 23103 29304 14613 29304 23101 29304 23101 29305 14613 29305 14614 29305 23101 29306 14614 29306 23100 29306 23100 29307 14614 29307 14640 29307 23100 29308 14640 29308 14615 29308 14615 29309 14640 29309 14638 29309 14615 29310 14638 29310 14616 29310 14616 29311 14638 29311 14617 29311 14616 29312 14617 29312 14618 29312 14618 29313 14617 29313 14619 29313 14618 29314 14619 29314 14620 29314 14620 29315 14619 29315 14636 29315 14620 29316 14636 29316 23110 29316 23110 29317 14636 29317 14630 29317 23110 29318 14630 29318 14621 29318 14621 29319 14630 29319 14622 29319 14621 29320 14622 29320 23108 29320 23108 29321 14622 29321 14632 29321 23108 29322 14632 29322 14623 29322 14623 29323 14632 29323 14628 29323 14623 29324 14628 29324 23118 29324 23118 29325 14628 29325 14629 29325 23118 29326 14629 29326 23116 29326 23116 29327 14629 29327 14624 29327 23116 29328 14624 29328 23115 29328 23115 29329 14624 29329 14625 29329 23115 29330 14625 29330 23113 29330 14626 29331 14625 29331 23452 29331 23452 29332 14625 29332 14624 29332 23653 29333 14627 29333 14628 29333 14628 29334 14627 29334 23539 29334 14628 29335 23539 29335 14629 29335 14629 29336 23539 29336 23541 29336 14629 29337 23541 29337 14624 29337 14624 29338 23541 29338 23542 29338 14624 29339 23542 29339 23452 29339 23653 29340 14628 29340 23654 29340 23654 29341 14628 29341 14632 29341 23654 29342 14632 29342 23656 29342 14630 29343 23633 29343 14622 29343 14622 29344 23633 29344 14631 29344 14622 29345 14631 29345 14632 29345 14632 29346 14631 29346 14633 29346 14632 29347 14633 29347 23656 29347 14636 29348 14634 29348 14630 29348 14630 29349 14634 29349 14635 29349 14630 29350 14635 29350 23633 29350 14638 29351 23421 29351 14617 29351 14617 29352 23421 29352 23420 29352 14617 29353 23420 29353 14619 29353 14619 29354 23420 29354 23628 29354 14619 29355 23628 29355 14636 29355 14636 29356 23628 29356 23632 29356 14636 29357 23632 29357 14634 29357 23622 29358 14637 29358 14638 29358 14638 29359 14637 29359 14639 29359 14638 29360 14639 29360 23421 29360 23622 29361 14638 29361 14641 29361 14641 29362 14638 29362 14640 29362 14641 29363 14640 29363 23615 29363 23615 29364 14640 29364 23433 29364 23433 29365 14640 29365 14614 29365 23433 29366 14614 29366 23486 29366 23486 29367 14614 29367 14613 29367 23486 29368 14613 29368 14642 29368 14612 29369 23493 29369 14643 29369 14612 29370 14643 29370 14613 29370 14613 29371 14643 29371 23484 29371 14613 29372 23484 29372 14642 29372 14413 29373 23571 29373 14644 29373 14644 29374 23571 29374 14646 29374 14644 29375 14646 29375 14645 29375 14645 29376 14646 29376 14647 29376 14645 29377 14647 29377 14416 29377 14416 29378 14647 29378 14648 29378 14416 29379 14648 29379 14417 29379 14417 29380 14648 29380 14649 29380 14417 29381 14649 29381 14419 29381 14419 29382 14649 29382 23471 29382 14419 29383 23471 29383 14651 29383 14651 29384 23471 29384 14650 29384 14651 29385 14650 29385 23387 29385 23387 29386 14650 29386 23512 29386 14421 29387 14652 29387 14422 29387 14422 29388 14652 29388 14653 29388 14422 29389 14653 29389 14423 29389 14423 29390 14653 29390 14654 29390 14423 29391 14654 29391 14655 29391 14655 29392 14654 29392 14656 29392 14655 29393 14656 29393 14424 29393 14424 29394 14656 29394 14657 29394 14424 29395 14657 29395 14425 29395 14425 29396 14657 29396 23408 29396 14425 29397 23408 29397 14426 29397 14426 29398 23408 29398 23514 29398 23998 29399 23457 29399 14427 29399 14427 29400 23457 29400 14658 29400 14427 29401 14658 29401 14428 29401 14428 29402 14658 29402 14659 29402 14428 29403 14659 29403 14430 29403 14430 29404 14659 29404 23528 29404 14430 29405 23528 29405 14660 29405 14660 29406 23528 29406 23458 29406 14660 29407 23458 29407 14431 29407 14431 29408 23458 29408 23464 29408 14431 29409 23464 29409 14434 29409 14434 29410 23464 29410 23462 29410 14434 29411 23462 29411 23368 29411 23368 29412 23462 29412 23461 29412 23991 29413 23439 29413 14661 29413 14661 29414 23439 29414 14663 29414 14661 29415 14663 29415 14662 29415 14662 29416 14663 29416 23445 29416 14662 29417 23445 29417 14664 29417 14664 29418 23445 29418 23446 29418 14664 29419 23446 29419 14665 29419 14665 29420 23446 29420 23447 29420 14665 29421 23447 29421 14666 29421 14666 29422 23447 29422 23449 29422 14666 29423 23449 29423 14667 29423 14667 29424 23449 29424 23451 29424 14440 29425 23414 29425 14668 29425 14668 29426 23414 29426 23412 29426 14668 29427 23412 29427 14442 29427 14442 29428 23412 29428 14670 29428 14442 29429 14670 29429 14669 29429 14669 29430 14670 29430 14671 29430 14669 29431 14671 29431 14672 29431 14672 29432 14671 29432 23537 29432 14672 29433 23537 29433 14443 29433 14443 29434 23537 29434 23538 29434 14443 29435 23538 29435 23356 29435 23356 29436 23538 29436 23540 29436 14445 29437 23341 29437 14447 29437 14447 29438 23341 29438 23627 29438 14447 29439 23627 29439 14674 29439 14674 29440 23627 29440 14673 29440 14674 29441 14673 29441 14675 29441 14675 29442 14673 29442 23626 29442 14675 29443 23626 29443 14450 29443 14450 29444 23626 29444 23625 29444 14450 29445 23625 29445 14451 29445 14451 29446 23625 29446 14676 29446 14451 29447 14676 29447 14677 29447 14677 29448 14676 29448 23624 29448 14682 29449 23646 29449 14680 29449 14685 29450 23427 29450 14678 29450 14678 29451 23427 29451 14679 29451 14678 29452 14679 29452 14680 29452 14680 29453 14679 29453 14681 29453 14680 29454 14681 29454 14682 29454 14678 29455 14683 29455 14685 29455 14685 29456 14683 29456 14684 29456 14685 29457 14684 29457 14686 29457 14686 29458 14684 29458 14461 29458 14461 29459 14460 29459 14686 29459 14686 29460 14460 29460 14457 29460 14686 29461 14457 29461 14687 29461 23340 29462 23426 29462 14691 29462 14457 29463 14456 29463 14687 29463 14687 29464 14456 29464 14688 29464 14687 29465 14688 29465 23619 29465 23619 29466 14688 29466 14454 29466 23619 29467 14454 29467 14689 29467 14689 29468 14454 29468 23340 29468 14689 29469 23340 29469 14690 29469 14690 29470 23340 29470 14691 29470 23331 29471 14472 29471 14692 29471 14692 29472 14472 29472 14693 29472 14692 29473 14693 29473 23550 29473 14693 29474 14694 29474 23550 29474 23550 29475 14694 29475 14695 29475 23550 29476 14695 29476 14696 29476 14696 29477 14695 29477 14697 29477 14697 29478 14698 29478 14696 29478 14696 29479 14698 29479 14469 29479 14696 29480 14469 29480 23430 29480 23326 29481 23431 29481 14699 29481 14699 29482 23431 29482 14700 29482 14699 29483 14700 29483 14466 29483 14466 29484 14700 29484 23430 29484 14466 29485 23430 29485 14701 29485 14701 29486 23430 29486 14469 29486 23316 29487 23317 29487 23800 29487 23800 29488 23317 29488 14702 29488 23800 29489 14702 29489 23799 29489 23799 29490 14702 29490 14703 29490 23799 29491 14703 29491 14704 29491 14704 29492 14703 29492 23428 29492 14705 29493 23582 29493 14595 29493 14595 29494 23582 29494 14706 29494 23700 29495 23297 29495 14607 29495 14607 29496 23297 29496 23581 29496 14607 29497 23581 29497 23702 29497 23702 29498 23581 29498 23580 29498 23274 29499 23275 29499 23722 29499 23722 29500 23275 29500 23499 29500 23749 29501 23556 29501 14707 29501 14707 29502 23556 29502 14708 29502 14707 29503 14708 29503 23746 29503 23746 29504 14708 29504 14709 29504 23746 29505 14709 29505 23744 29505 23744 29506 14709 29506 23404 29506 23744 29507 23404 29507 23254 29507 23232 29508 23551 29508 23775 29508 23775 29509 23551 29509 23553 29509 14710 29510 14543 29510 14714 29510 14714 29511 14543 29511 14541 29511 14711 29512 23634 29512 14712 29512 14541 29513 14713 29513 14714 29513 14714 29514 14713 29514 14540 29514 14714 29515 14540 29515 14712 29515 14712 29516 14540 29516 14538 29516 14712 29517 14538 29517 14711 29517 14711 29518 14536 29518 23634 29518 23634 29519 14536 29519 14715 29519 23634 29520 14715 29520 14716 29520 14715 29521 14717 29521 14716 29521 14716 29522 14717 29522 14535 29522 14716 29523 14535 29523 23659 29523 23220 29524 23545 29524 14532 29524 14532 29525 23545 29525 23659 29525 14532 29526 23659 29526 14533 29526 14533 29527 23659 29527 14535 29527 14718 29528 14719 29528 23416 29528 23416 29529 14719 29529 14529 29529 14524 29530 23413 29530 23415 29530 14529 29531 14527 29531 23416 29531 23416 29532 14527 29532 14720 29532 23416 29533 14720 29533 23415 29533 23415 29534 14720 29534 14525 29534 23415 29535 14525 29535 14524 29535 14524 29536 14522 29536 23413 29536 23413 29537 14522 29537 14721 29537 23413 29538 14721 29538 14722 29538 14721 29539 14723 29539 14722 29539 14722 29540 14723 29540 14519 29540 14722 29541 14519 29541 14726 29541 14514 29542 14724 29542 14517 29542 14517 29543 14724 29543 14726 29543 14517 29544 14726 29544 14725 29544 14725 29545 14726 29545 14519 29545 14727 29546 14728 29546 23543 29546 23543 29547 14728 29547 14729 29547 14510 29548 23532 29548 14731 29548 14729 29549 14513 29549 23543 29549 23543 29550 14513 29550 14730 29550 23543 29551 14730 29551 14731 29551 14731 29552 14730 29552 14732 29552 14731 29553 14732 29553 14510 29553 14510 29554 14509 29554 23532 29554 23532 29555 14509 29555 14733 29555 23532 29556 14733 29556 23533 29556 14733 29557 14734 29557 23533 29557 23533 29558 14734 29558 14737 29558 23533 29559 14737 29559 23534 29559 14504 29560 23535 29560 14735 29560 14735 29561 23535 29561 23534 29561 14735 29562 23534 29562 14736 29562 14736 29563 23534 29563 14737 29563 23934 29564 23441 29564 14496 29564 14496 29565 23441 29565 23440 29565 14496 29566 23440 29566 14498 29566 14498 29567 23440 29567 14738 29567 14498 29568 14738 29568 14501 29568 14501 29569 14738 29569 14739 29569 14501 29570 14739 29570 14740 29570 14740 29571 14739 29571 14741 29571 14740 29572 14741 29572 14502 29572 14502 29573 14741 29573 14743 29573 14502 29574 14743 29574 14742 29574 14742 29575 14743 29575 23193 29575 23941 29576 23525 29576 14744 29576 14744 29577 23525 29577 23524 29577 14744 29578 23524 29578 14489 29578 14489 29579 23524 29579 23639 29579 14489 29580 23639 29580 14745 29580 14745 29581 23639 29581 23638 29581 14745 29582 23638 29582 14491 29582 14491 29583 23638 29583 23531 29583 14491 29584 23531 29584 14746 29584 14746 29585 23531 29585 23530 29585 14746 29586 23530 29586 14494 29586 14494 29587 23530 29587 23186 29587 14748 29588 23518 29588 14473 29588 14473 29589 14747 29589 14748 29589 14748 29590 14747 29590 14749 29590 14748 29591 14749 29591 14752 29591 14750 29592 23521 29592 23520 29592 14749 29593 14751 29593 14752 29593 14752 29594 14751 29594 14478 29594 14752 29595 14478 29595 23520 29595 23520 29596 14478 29596 14753 29596 23520 29597 14753 29597 14750 29597 14750 29598 14754 29598 23521 29598 23521 29599 14754 29599 14755 29599 23521 29600 14755 29600 14756 29600 14756 29601 14755 29601 14757 29601 14756 29602 14757 29602 23522 29602 23948 29603 23185 29603 14758 29603 14758 29604 23185 29604 23522 29604 14758 29605 23522 29605 14482 29605 14482 29606 23522 29606 14757 29606 14759 29607 23511 29607 14760 29607 14760 29608 23511 29608 23510 29608 14760 29609 23510 29609 14761 29609 14761 29610 23510 29610 23509 29610 14761 29611 23509 29611 14586 29611 14586 29612 23509 29612 23508 29612 14586 29613 23508 29613 14762 29613 14762 29614 23508 29614 23507 29614 14762 29615 23507 29615 14763 29615 14763 29616 23507 29616 14764 29616 14763 29617 14764 29617 14765 29617 14765 29618 14764 29618 14766 29618 23168 29619 23169 29619 14577 29619 14577 29620 23169 29620 14768 29620 14577 29621 14768 29621 14767 29621 14767 29622 14768 29622 14770 29622 14767 29623 14770 29623 14769 29623 14769 29624 14770 29624 23503 29624 14769 29625 23503 29625 14771 29625 14771 29626 23503 29626 23502 29626 14771 29627 23502 29627 14772 29627 14772 29628 23502 29628 14773 29628 14772 29629 14773 29629 14774 29629 14774 29630 14773 29630 14775 29630 14774 29631 14775 29631 23852 29631 23852 29632 14775 29632 23495 29632 14569 29633 23640 29633 14776 29633 14776 29634 23640 29634 14777 29634 14776 29635 14777 29635 14571 29635 14571 29636 14777 29636 23492 29636 14571 29637 23492 29637 14572 29637 14572 29638 23492 29638 14778 29638 14572 29639 14778 29639 14780 29639 14780 29640 14778 29640 14779 29640 14780 29641 14779 29641 14575 29641 14575 29642 14779 29642 23491 29642 14575 29643 23491 29643 23857 29643 23857 29644 23491 29644 14781 29644 14563 29645 23148 29645 14564 29645 14564 29646 23148 29646 23614 29646 14564 29647 23614 29647 14782 29647 14782 29648 23614 29648 14783 29648 14782 29649 14783 29649 14784 29649 14784 29650 14783 29650 14786 29650 14784 29651 14786 29651 14785 29651 14785 29652 14786 29652 14787 29652 14785 29653 14787 29653 14567 29653 14567 29654 14787 29654 23487 29654 14567 29655 23487 29655 14788 29655 14788 29656 23487 29656 23140 29656 14554 29657 23476 29657 14555 29657 14555 29658 23476 29658 14789 29658 14555 29659 14789 29659 14556 29659 14556 29660 14789 29660 14790 29660 14556 29661 14790 29661 14791 29661 14791 29662 14790 29662 23392 29662 14791 29663 23392 29663 14560 29663 14560 29664 23392 29664 23391 29664 14560 29665 23391 29665 14792 29665 14792 29666 23391 29666 14793 29666 14792 29667 14793 29667 14562 29667 14562 29668 14793 29668 23477 29668 14544 29669 23645 29669 14794 29669 14794 29670 23645 29670 14795 29670 14794 29671 14795 29671 14796 29671 14796 29672 14795 29672 14797 29672 14796 29673 14797 29673 14798 29673 14798 29674 14797 29674 14799 29674 14798 29675 14799 29675 14800 29675 14800 29676 14799 29676 23647 29676 14800 29677 23647 29677 14549 29677 14549 29678 23647 29678 23422 29678 14549 29679 23422 29679 14801 29679 14801 29680 23422 29680 14802 29680 14801 29681 14802 29681 14552 29681 14552 29682 14802 29682 23629 29682 23065 29683 23095 29683 14803 29683 23065 29684 14803 29684 23066 29684 23066 29685 14803 29685 14804 29685 23066 29686 14804 29686 23067 29686 23067 29687 14804 29687 14805 29687 23067 29688 14805 29688 14806 29688 14806 29689 14805 29689 14807 29689 14806 29690 14807 29690 23069 29690 23069 29691 14807 29691 14823 29691 23069 29692 14823 29692 23070 29692 23070 29693 14823 29693 14808 29693 23070 29694 14808 29694 23071 29694 23071 29695 14808 29695 14809 29695 23071 29696 14809 29696 14810 29696 14810 29697 14809 29697 14825 29697 14810 29698 14825 29698 23073 29698 23073 29699 14825 29699 14812 29699 23073 29700 14812 29700 14811 29700 14811 29701 14812 29701 14829 29701 14811 29702 14829 29702 23049 29702 23049 29703 14829 29703 14813 29703 23049 29704 14813 29704 14814 29704 14814 29705 14813 29705 14815 29705 14814 29706 14815 29706 14817 29706 14817 29707 14815 29707 14816 29707 14817 29708 14816 29708 14818 29708 14818 29709 14816 29709 14832 29709 14818 29710 14832 29710 23052 29710 23052 29711 14832 29711 14819 29711 23052 29712 14819 29712 23053 29712 23053 29713 14819 29713 23028 29713 23053 29714 23028 29714 23075 29714 23095 29715 23010 29715 14820 29715 23095 29716 14820 29716 14803 29716 14803 29717 14820 29717 14848 29717 14803 29718 14848 29718 14804 29718 14804 29719 14848 29719 14821 29719 14804 29720 14821 29720 14805 29720 14805 29721 14821 29721 14822 29721 14805 29722 14822 29722 14807 29722 14807 29723 14822 29723 14844 29723 14807 29724 14844 29724 14823 29724 14823 29725 14844 29725 14842 29725 14823 29726 14842 29726 14808 29726 14808 29727 14842 29727 14824 29727 14808 29728 14824 29728 14809 29728 14809 29729 14824 29729 14826 29729 14809 29730 14826 29730 14825 29730 14825 29731 14826 29731 14827 29731 14825 29732 14827 29732 14812 29732 14812 29733 14827 29733 14828 29733 14812 29734 14828 29734 14829 29734 14829 29735 14828 29735 14830 29735 14829 29736 14830 29736 14813 29736 14813 29737 14830 29737 14831 29737 14813 29738 14831 29738 14815 29738 14815 29739 14831 29739 14836 29739 14815 29740 14836 29740 14816 29740 14816 29741 14836 29741 14835 29741 14816 29742 14835 29742 14832 29742 14832 29743 14835 29743 14833 29743 14832 29744 14833 29744 14819 29744 14819 29745 14833 29745 14834 29745 14819 29746 14834 29746 23028 29746 23027 29747 14834 29747 14833 29747 23027 29748 14833 29748 23114 29748 23114 29749 14833 29749 14835 29749 23114 29750 14835 29750 23117 29750 23117 29751 14835 29751 14836 29751 23117 29752 14836 29752 14837 29752 14837 29753 14836 29753 14831 29753 14837 29754 14831 29754 23119 29754 23119 29755 14831 29755 14830 29755 23119 29756 14830 29756 14838 29756 14838 29757 14830 29757 14828 29757 14838 29758 14828 29758 23109 29758 23109 29759 14828 29759 14827 29759 23109 29760 14827 29760 14839 29760 14839 29761 14827 29761 14826 29761 14839 29762 14826 29762 14840 29762 14840 29763 14826 29763 14824 29763 14840 29764 14824 29764 14841 29764 14841 29765 14824 29765 14842 29765 14841 29766 14842 29766 14843 29766 14843 29767 14842 29767 14844 29767 14843 29768 14844 29768 14845 29768 14845 29769 14844 29769 14822 29769 14845 29770 14822 29770 23099 29770 23099 29771 14822 29771 14821 29771 23099 29772 14821 29772 14846 29772 14846 29773 14821 29773 14848 29773 14846 29774 14848 29774 14847 29774 14847 29775 14848 29775 14820 29775 14847 29776 14820 29776 23102 29776 23102 29777 14820 29777 23010 29777 23102 29778 23010 29778 23104 29778 17772 29779 23064 29779 14850 29779 17772 29780 14850 29780 14849 29780 14849 29781 14850 29781 14851 29781 14849 29782 14851 29782 14852 29782 14852 29783 14851 29783 14853 29783 14852 29784 14853 29784 14854 29784 14854 29785 14853 29785 23068 29785 14854 29786 23068 29786 17770 29786 17770 29787 23068 29787 14855 29787 17770 29788 14855 29788 17769 29788 17769 29789 14855 29789 14856 29789 17769 29790 14856 29790 14857 29790 14857 29791 14856 29791 23072 29791 14857 29792 23072 29792 14858 29792 14858 29793 23072 29793 14859 29793 14858 29794 14859 29794 17767 29794 17767 29795 14859 29795 23074 29795 17767 29796 23074 29796 17765 29796 17765 29797 23074 29797 23047 29797 17765 29798 23047 29798 17763 29798 17763 29799 23047 29799 23048 29799 17763 29800 23048 29800 17761 29800 17761 29801 23048 29801 14861 29801 17761 29802 14861 29802 14860 29802 14860 29803 14861 29803 14862 29803 14860 29804 14862 29804 14863 29804 14863 29805 14862 29805 23050 29805 14863 29806 23050 29806 14864 29806 14864 29807 23050 29807 23051 29807 14864 29808 23051 29808 17758 29808 17758 29809 23051 29809 22993 29809 17758 29810 22993 29810 14865 29810 22916 29811 22915 29811 14867 29811 22916 29812 14867 29812 14866 29812 14866 29813 14867 29813 16356 29813 14866 29814 16356 29814 20013 29814 20013 29815 16356 29815 16359 29815 20013 29816 16359 29816 20017 29816 20017 29817 16359 29817 14868 29817 20017 29818 14868 29818 20018 29818 20018 29819 14868 29819 16360 29819 20018 29820 16360 29820 14869 29820 14869 29821 16360 29821 14870 29821 14869 29822 14870 29822 20021 29822 20021 29823 14870 29823 19992 29823 20021 29824 19992 29824 14871 29824 14872 29825 22854 29825 16381 29825 14872 29826 16381 29826 14873 29826 14873 29827 16381 29827 14874 29827 14873 29828 14874 29828 14876 29828 14876 29829 14874 29829 14875 29829 14876 29830 14875 29830 14877 29830 14877 29831 14875 29831 14878 29831 14877 29832 14878 29832 14879 29832 14879 29833 14878 29833 16376 29833 14879 29834 16376 29834 16581 29834 16581 29835 16376 29835 14880 29835 16581 29836 14880 29836 14881 29836 14881 29837 14880 29837 14882 29837 14881 29838 14882 29838 16578 29838 16578 29839 14882 29839 16375 29839 16578 29840 16375 29840 14883 29840 14883 29841 16375 29841 16372 29841 14883 29842 16372 29842 16575 29842 16575 29843 16372 29843 14884 29843 16575 29844 14884 29844 16573 29844 16573 29845 14884 29845 16370 29845 16573 29846 16370 29846 14885 29846 14885 29847 16370 29847 16369 29847 14885 29848 16369 29848 14886 29848 14886 29849 16369 29849 14887 29849 14886 29850 14887 29850 16570 29850 16570 29851 14887 29851 16368 29851 16570 29852 16368 29852 14888 29852 14888 29853 16368 29853 16366 29853 14888 29854 16366 29854 14890 29854 14890 29855 16366 29855 14889 29855 14890 29856 14889 29856 14891 29856 14891 29857 14889 29857 16364 29857 14891 29858 16364 29858 14892 29858 14892 29859 16364 29859 16363 29859 14892 29860 16363 29860 14893 29860 14893 29861 16363 29861 14894 29861 14893 29862 14894 29862 16567 29862 14895 29863 14896 29863 16529 29863 16529 29864 14896 29864 20288 29864 16529 29865 20288 29865 22831 29865 16532 29866 14900 29866 16531 29866 16531 29867 14900 29867 20128 29867 16531 29868 20128 29868 14895 29868 14895 29869 20128 29869 20115 29869 14895 29870 20115 29870 14896 29870 20043 29871 16532 29871 14897 29871 14897 29872 16532 29872 16533 29872 20043 29873 14898 29873 16532 29873 16532 29874 14898 29874 14899 29874 16532 29875 14899 29875 14900 29875 20109 29876 16533 29876 20108 29876 20108 29877 16533 29877 14901 29877 20109 29878 14902 29878 16533 29878 16533 29879 14902 29879 20094 29879 16533 29880 20094 29880 14897 29880 20265 29881 20029 29881 16534 29881 16534 29882 20029 29882 20274 29882 16534 29883 20274 29883 14901 29883 14901 29884 20274 29884 20273 29884 14901 29885 20273 29885 20108 29885 20265 29886 16534 29886 14903 29886 14903 29887 16534 29887 16535 29887 14903 29888 16535 29888 20089 29888 14904 29889 20103 29889 14905 29889 14905 29890 20103 29890 20263 29890 14905 29891 20263 29891 16538 29891 16538 29892 20263 29892 14906 29892 16538 29893 14906 29893 16535 29893 16535 29894 14906 29894 20086 29894 16535 29895 20086 29895 20089 29895 20052 29896 14907 29896 14909 29896 14909 29897 14907 29897 14908 29897 14909 29898 14908 29898 14904 29898 14904 29899 14908 29899 20061 29899 14904 29900 20061 29900 20103 29900 20052 29901 14909 29901 20260 29901 20260 29902 14909 29902 14910 29902 20260 29903 14910 29903 20255 29903 20071 29904 14911 29904 14913 29904 14913 29905 14911 29905 14912 29905 14913 29906 14912 29906 14910 29906 14910 29907 14912 29907 20256 29907 14910 29908 20256 29908 20255 29908 20031 29909 20044 29909 14915 29909 14915 29910 20044 29910 20068 29910 14915 29911 20068 29911 14913 29911 14913 29912 20068 29912 14914 29912 14913 29913 14914 29913 20071 29913 14917 29914 20246 29914 16542 29914 16542 29915 20246 29915 20247 29915 16542 29916 20247 29916 14915 29916 14915 29917 20247 29917 20030 29917 14915 29918 20030 29918 20031 29918 20152 29919 14916 29919 14917 29919 14917 29920 14916 29920 20147 29920 14917 29921 20147 29921 20246 29921 14917 29922 16546 29922 20152 29922 20152 29923 16546 29923 19819 29923 20152 29924 19819 29924 20141 29924 22479 29925 14918 29925 16545 29925 22479 29926 16545 29926 14919 29926 14919 29927 16545 29927 16544 29927 14919 29928 16544 29928 14920 29928 14920 29929 16544 29929 16543 29929 14920 29930 16543 29930 14922 29930 14922 29931 16543 29931 14921 29931 14922 29932 14921 29932 14923 29932 14923 29933 14921 29933 14925 29933 14923 29934 14925 29934 14924 29934 14924 29935 14925 29935 16541 29935 14924 29936 16541 29936 14926 29936 14926 29937 16541 29937 14927 29937 14926 29938 14927 29938 14928 29938 14928 29939 14927 29939 16540 29939 14928 29940 16540 29940 22444 29940 22444 29941 16540 29941 16539 29941 22444 29942 16539 29942 14929 29942 14929 29943 16539 29943 16537 29943 14929 29944 16537 29944 22446 29944 22446 29945 16537 29945 16536 29945 22446 29946 16536 29946 22448 29946 22448 29947 16536 29947 14931 29947 22448 29948 14931 29948 14930 29948 14930 29949 14931 29949 14932 29949 14930 29950 14932 29950 22451 29950 22451 29951 14932 29951 14933 29951 22451 29952 14933 29952 14934 29952 14934 29953 14933 29953 14936 29953 14934 29954 14936 29954 14935 29954 14935 29955 14936 29955 14938 29955 14935 29956 14938 29956 14937 29956 14937 29957 14938 29957 14939 29957 14937 29958 14939 29958 22453 29958 22453 29959 14939 29959 16530 29959 22453 29960 16530 29960 14940 29960 14940 29961 16530 29961 14941 29961 14940 29962 14941 29962 22455 29962 22757 29963 16547 29963 16548 29963 22757 29964 16548 29964 22417 29964 22417 29965 16548 29965 16549 29965 22417 29966 16549 29966 14942 29966 14942 29967 16549 29967 14943 29967 14942 29968 14943 29968 22419 29968 22419 29969 14943 29969 14944 29969 22419 29970 14944 29970 22421 29970 22421 29971 14944 29971 16551 29971 22421 29972 16551 29972 22422 29972 22422 29973 16551 29973 16553 29973 22422 29974 16553 29974 22424 29974 22424 29975 16553 29975 14945 29975 22424 29976 14945 29976 22425 29976 22425 29977 14945 29977 16554 29977 22425 29978 16554 29978 22426 29978 22426 29979 16554 29979 16558 29979 22426 29980 16558 29980 14946 29980 14946 29981 16558 29981 16559 29981 14946 29982 16559 29982 14947 29982 14947 29983 16559 29983 14948 29983 14947 29984 14948 29984 14949 29984 14949 29985 14948 29985 14950 29985 14949 29986 14950 29986 14951 29986 14951 29987 14950 29987 14952 29987 14951 29988 14952 29988 22390 29988 22390 29989 14952 29989 16562 29989 22390 29990 16562 29990 22391 29990 22391 29991 16562 29991 16565 29991 22391 29992 16565 29992 22392 29992 22392 29993 16565 29993 14953 29993 22392 29994 14953 29994 14954 29994 14954 29995 14953 29995 14955 29995 14954 29996 14955 29996 14956 29996 14956 29997 14955 29997 16566 29997 14956 29998 16566 29998 22397 29998 22397 29999 16566 29999 22738 29999 22397 30000 22738 30000 22737 30000 14958 30001 14957 30001 14959 30001 14958 30002 14959 30002 14960 30002 14960 30003 14959 30003 14961 30003 14960 30004 14961 30004 22388 30004 22388 30005 14961 30005 14962 30005 22388 30006 14962 30006 22349 30006 22349 30007 14962 30007 16564 30007 22349 30008 16564 30008 22350 30008 22350 30009 16564 30009 16563 30009 22350 30010 16563 30010 14963 30010 14963 30011 16563 30011 16561 30011 14963 30012 16561 30012 14964 30012 14964 30013 16561 30013 14965 30013 14964 30014 14965 30014 22355 30014 22355 30015 14965 30015 16560 30015 22355 30016 16560 30016 14966 30016 14966 30017 16560 30017 16557 30017 14966 30018 16557 30018 22356 30018 22356 30019 16557 30019 16556 30019 22356 30020 16556 30020 22358 30020 22358 30021 16556 30021 16555 30021 22358 30022 16555 30022 14967 30022 14967 30023 16555 30023 16552 30023 14967 30024 16552 30024 22360 30024 22360 30025 16552 30025 14968 30025 22360 30026 14968 30026 14970 30026 14970 30027 14968 30027 14969 30027 14970 30028 14969 30028 14971 30028 14971 30029 14969 30029 14972 30029 14971 30030 14972 30030 22362 30030 22362 30031 14972 30031 14973 30031 22362 30032 14973 30032 22363 30032 22363 30033 14973 30033 16550 30033 22363 30034 16550 30034 14974 30034 14974 30035 16550 30035 14975 30035 14974 30036 14975 30036 22365 30036 22365 30037 14975 30037 19818 30037 22365 30038 19818 30038 22366 30038 14976 30039 22715 30039 14977 30039 14976 30040 14977 30040 14978 30040 14978 30041 14977 30041 16511 30041 14978 30042 16511 30042 14979 30042 14979 30043 16511 30043 16513 30043 14979 30044 16513 30044 14980 30044 14980 30045 16513 30045 14981 30045 14980 30046 14981 30046 14982 30046 14982 30047 14981 30047 14983 30047 14982 30048 14983 30048 22324 30048 22324 30049 14983 30049 14984 30049 22324 30050 14984 30050 14985 30050 14985 30051 14984 30051 14986 30051 14985 30052 14986 30052 22327 30052 22327 30053 14986 30053 16516 30053 22327 30054 16516 30054 22328 30054 22328 30055 16516 30055 16519 30055 22328 30056 16519 30056 22330 30056 22330 30057 16519 30057 16520 30057 22330 30058 16520 30058 22292 30058 22292 30059 16520 30059 16521 30059 22292 30060 16521 30060 22293 30060 22293 30061 16521 30061 16523 30061 22293 30062 16523 30062 22294 30062 22294 30063 16523 30063 14987 30063 22294 30064 14987 30064 22295 30064 22295 30065 14987 30065 14988 30065 22295 30066 14988 30066 22296 30066 22296 30067 14988 30067 14989 30067 22296 30068 14989 30068 14991 30068 14991 30069 14989 30069 14990 30069 14991 30070 14990 30070 22299 30070 22299 30071 14990 30071 14992 30071 22299 30072 14992 30072 22302 30072 22302 30073 14992 30073 16528 30073 22302 30074 16528 30074 14993 30074 14993 30075 16528 30075 22694 30075 14993 30076 22694 30076 22303 30076 22287 30077 14994 30077 16527 30077 22287 30078 16527 30078 22288 30078 22288 30079 16527 30079 14995 30079 22288 30080 14995 30080 14996 30080 14996 30081 14995 30081 16526 30081 14996 30082 16526 30082 14997 30082 14997 30083 16526 30083 16525 30083 14997 30084 16525 30084 22252 30084 22252 30085 16525 30085 14998 30085 22252 30086 14998 30086 14999 30086 14999 30087 14998 30087 15000 30087 14999 30088 15000 30088 22254 30088 22254 30089 15000 30089 16524 30089 22254 30090 16524 30090 15001 30090 15001 30091 16524 30091 16522 30091 15001 30092 16522 30092 15002 30092 15002 30093 16522 30093 16518 30093 15002 30094 16518 30094 15003 30094 15003 30095 16518 30095 16517 30095 15003 30096 16517 30096 15004 30096 15004 30097 16517 30097 15005 30097 15004 30098 15005 30098 22255 30098 22255 30099 15005 30099 16515 30099 22255 30100 16515 30100 22258 30100 22258 30101 16515 30101 15006 30101 22258 30102 15006 30102 22259 30102 22259 30103 15006 30103 16514 30103 22259 30104 16514 30104 15007 30104 15007 30105 16514 30105 15008 30105 15007 30106 15008 30106 15009 30106 15009 30107 15008 30107 16512 30107 15009 30108 16512 30108 22262 30108 22262 30109 16512 30109 16510 30109 22262 30110 16510 30110 15010 30110 15010 30111 16510 30111 16509 30111 15010 30112 16509 30112 22264 30112 22264 30113 16509 30113 19857 30113 22264 30114 19857 30114 15011 30114 22221 30115 15012 30115 15013 30115 22221 30116 15013 30116 15014 30116 15014 30117 15013 30117 15015 30117 15014 30118 15015 30118 22223 30118 22223 30119 15015 30119 16492 30119 22223 30120 16492 30120 22224 30120 22224 30121 16492 30121 16493 30121 22224 30122 16493 30122 22225 30122 22225 30123 16493 30123 15016 30123 22225 30124 15016 30124 15017 30124 15017 30125 15016 30125 15018 30125 15017 30126 15018 30126 22228 30126 22228 30127 15018 30127 16496 30127 22228 30128 16496 30128 15019 30128 15019 30129 16496 30129 15020 30129 15019 30130 15020 30130 15021 30130 15021 30131 15020 30131 16499 30131 15021 30132 16499 30132 22231 30132 22231 30133 16499 30133 15022 30133 22231 30134 15022 30134 22191 30134 22191 30135 15022 30135 16502 30135 22191 30136 16502 30136 22192 30136 22192 30137 16502 30137 15023 30137 22192 30138 15023 30138 15024 30138 15024 30139 15023 30139 16504 30139 15024 30140 16504 30140 22195 30140 22195 30141 16504 30141 15025 30141 22195 30142 15025 30142 15026 30142 15026 30143 15025 30143 15027 30143 15026 30144 15027 30144 15028 30144 15028 30145 15027 30145 15029 30145 15028 30146 15029 30146 15030 30146 15030 30147 15029 30147 16508 30147 15030 30148 16508 30148 22198 30148 22198 30149 16508 30149 15031 30149 22198 30150 15031 30150 22200 30150 22200 30151 15031 30151 22655 30151 22200 30152 22655 30152 22654 30152 15033 30153 15032 30153 15034 30153 15033 30154 15034 30154 22187 30154 22187 30155 15034 30155 16507 30155 22187 30156 16507 30156 22188 30156 22188 30157 16507 30157 16506 30157 22188 30158 16506 30158 22190 30158 22190 30159 16506 30159 15035 30159 22190 30160 15035 30160 15036 30160 15036 30161 15035 30161 15037 30161 15036 30162 15037 30162 22157 30162 22157 30163 15037 30163 16505 30163 22157 30164 16505 30164 22158 30164 22158 30165 16505 30165 16503 30165 22158 30166 16503 30166 22159 30166 22159 30167 16503 30167 16501 30167 22159 30168 16501 30168 15038 30168 15038 30169 16501 30169 16500 30169 15038 30170 16500 30170 22160 30170 22160 30171 16500 30171 16498 30171 22160 30172 16498 30172 22161 30172 22161 30173 16498 30173 16497 30173 22161 30174 16497 30174 22164 30174 22164 30175 16497 30175 15039 30175 22164 30176 15039 30176 22165 30176 22165 30177 15039 30177 16495 30177 22165 30178 16495 30178 15040 30178 15040 30179 16495 30179 16494 30179 15040 30180 16494 30180 22167 30180 22167 30181 16494 30181 16491 30181 22167 30182 16491 30182 22169 30182 22169 30183 16491 30183 15041 30183 22169 30184 15041 30184 22170 30184 22170 30185 15041 30185 15042 30185 22170 30186 15042 30186 22171 30186 22171 30187 15042 30187 15043 30187 22171 30188 15043 30188 15045 30188 15045 30189 15043 30189 15044 30189 15045 30190 15044 30190 22173 30190 22121 30191 22636 30191 15046 30191 22121 30192 15046 30192 15047 30192 15047 30193 15046 30193 15048 30193 15047 30194 15048 30194 15049 30194 15049 30195 15048 30195 15050 30195 15049 30196 15050 30196 22122 30196 22122 30197 15050 30197 16478 30197 22122 30198 16478 30198 15051 30198 15051 30199 16478 30199 15053 30199 15051 30200 15053 30200 15052 30200 15052 30201 15053 30201 15055 30201 15052 30202 15055 30202 15054 30202 15054 30203 15055 30203 15056 30203 15054 30204 15056 30204 22125 30204 22125 30205 15056 30205 16482 30205 22125 30206 16482 30206 15057 30206 15057 30207 16482 30207 15058 30207 15057 30208 15058 30208 15059 30208 15059 30209 15058 30209 15060 30209 15059 30210 15060 30210 22126 30210 22126 30211 15060 30211 16484 30211 22126 30212 16484 30212 15061 30212 15061 30213 16484 30213 15062 30213 15061 30214 15062 30214 22091 30214 22091 30215 15062 30215 15063 30215 22091 30216 15063 30216 22092 30216 22092 30217 15063 30217 15064 30217 22092 30218 15064 30218 22093 30218 22093 30219 15064 30219 16487 30219 22093 30220 16487 30220 22095 30220 22095 30221 16487 30221 15065 30221 22095 30222 15065 30222 22096 30222 22096 30223 15065 30223 15066 30223 22096 30224 15066 30224 22097 30224 22097 30225 15066 30225 15067 30225 22097 30226 15067 30226 22099 30226 22099 30227 15067 30227 22622 30227 22099 30228 22622 30228 22101 30228 15068 30229 16490 30229 16489 30229 15068 30230 16489 30230 15069 30230 15069 30231 16489 30231 15070 30231 15069 30232 15070 30232 22083 30232 22083 30233 15070 30233 16488 30233 22083 30234 16488 30234 15071 30234 15071 30235 16488 30235 15072 30235 15071 30236 15072 30236 22084 30236 22084 30237 15072 30237 15073 30237 22084 30238 15073 30238 22086 30238 22086 30239 15073 30239 16486 30239 22086 30240 16486 30240 15074 30240 15074 30241 16486 30241 16485 30241 15074 30242 16485 30242 15075 30242 15075 30243 16485 30243 15076 30243 15075 30244 15076 30244 22087 30244 22087 30245 15076 30245 16483 30245 22087 30246 16483 30246 22051 30246 22051 30247 16483 30247 15077 30247 22051 30248 15077 30248 15078 30248 15078 30249 15077 30249 16481 30249 15078 30250 16481 30250 15079 30250 15079 30251 16481 30251 15080 30251 15079 30252 15080 30252 15081 30252 15081 30253 15080 30253 16480 30253 15081 30254 16480 30254 15082 30254 15082 30255 16480 30255 16479 30255 15082 30256 16479 30256 15083 30256 15083 30257 16479 30257 16477 30257 15083 30258 16477 30258 22054 30258 22054 30259 16477 30259 16476 30259 22054 30260 16476 30260 15084 30260 15084 30261 16476 30261 16475 30261 15084 30262 16475 30262 15085 30262 15085 30263 16475 30263 15086 30263 15085 30264 15086 30264 22056 30264 22056 30265 15086 30265 16474 30265 22056 30266 16474 30266 22057 30266 22019 30267 22607 30267 15087 30267 22019 30268 15087 30268 22020 30268 22020 30269 15087 30269 16448 30269 22020 30270 16448 30270 15088 30270 15088 30271 16448 30271 16450 30271 15088 30272 16450 30272 22022 30272 22022 30273 16450 30273 16451 30273 22022 30274 16451 30274 22023 30274 22023 30275 16451 30275 16452 30275 22023 30276 16452 30276 22027 30276 22027 30277 16452 30277 16454 30277 22027 30278 16454 30278 22028 30278 22028 30279 16454 30279 16455 30279 22028 30280 16455 30280 22029 30280 22029 30281 16455 30281 15090 30281 22029 30282 15090 30282 15089 30282 15089 30283 15090 30283 16458 30283 15089 30284 16458 30284 15091 30284 15091 30285 16458 30285 15092 30285 15091 30286 15092 30286 22032 30286 22032 30287 15092 30287 15093 30287 22032 30288 15093 30288 21992 30288 21992 30289 15093 30289 16462 30289 21992 30290 16462 30290 21993 30290 21993 30291 16462 30291 16463 30291 21993 30292 16463 30292 15094 30292 15094 30293 16463 30293 16465 30293 15094 30294 16465 30294 15095 30294 15095 30295 16465 30295 15097 30295 15095 30296 15097 30296 15096 30296 15096 30297 15097 30297 16469 30297 15096 30298 16469 30298 21994 30298 21994 30299 16469 30299 16470 30299 21994 30300 16470 30300 15098 30300 15098 30301 16470 30301 15099 30301 15098 30302 15099 30302 15100 30302 15100 30303 15099 30303 16473 30303 15100 30304 16473 30304 22595 30304 21984 30305 16472 30305 16471 30305 21984 30306 16471 30306 15101 30306 15101 30307 16471 30307 16468 30307 15101 30308 16468 30308 21985 30308 21985 30309 16468 30309 16467 30309 21985 30310 16467 30310 21986 30310 21986 30311 16467 30311 16466 30311 21986 30312 16466 30312 21988 30312 21988 30313 16466 30313 16464 30313 21988 30314 16464 30314 21990 30314 21990 30315 16464 30315 16461 30315 21990 30316 16461 30316 21991 30316 21991 30317 16461 30317 15102 30317 21991 30318 15102 30318 15103 30318 15103 30319 15102 30319 16460 30319 15103 30320 16460 30320 15104 30320 15104 30321 16460 30321 16459 30321 15104 30322 16459 30322 15105 30322 15105 30323 16459 30323 16457 30323 15105 30324 16457 30324 21951 30324 21951 30325 16457 30325 16456 30325 21951 30326 16456 30326 21953 30326 21953 30327 16456 30327 16453 30327 21953 30328 16453 30328 15106 30328 15106 30329 16453 30329 15107 30329 15106 30330 15107 30330 21955 30330 21955 30331 15107 30331 15108 30331 21955 30332 15108 30332 21957 30332 21957 30333 15108 30333 15109 30333 21957 30334 15109 30334 21958 30334 21958 30335 15109 30335 16449 30335 21958 30336 16449 30336 15110 30336 15110 30337 16449 30337 15111 30337 15110 30338 15111 30338 21961 30338 21961 30339 15111 30339 16447 30339 21961 30340 16447 30340 15112 30340 15112 30341 16447 30341 22577 30341 15112 30342 22577 30342 22578 30342 21913 30343 16427 30343 15113 30343 21913 30344 15113 30344 15114 30344 15114 30345 15113 30345 15115 30345 15114 30346 15115 30346 21915 30346 21915 30347 15115 30347 16430 30347 21915 30348 16430 30348 21916 30348 21916 30349 16430 30349 16431 30349 21916 30350 16431 30350 21917 30350 21917 30351 16431 30351 16432 30351 21917 30352 16432 30352 21918 30352 21918 30353 16432 30353 16433 30353 21918 30354 16433 30354 15116 30354 15116 30355 16433 30355 15117 30355 15116 30356 15117 30356 21919 30356 21919 30357 15117 30357 16434 30357 21919 30358 16434 30358 21920 30358 21920 30359 16434 30359 16436 30359 21920 30360 16436 30360 21921 30360 21921 30361 16436 30361 16437 30361 21921 30362 16437 30362 15118 30362 15118 30363 16437 30363 16440 30363 15118 30364 16440 30364 21924 30364 21924 30365 16440 30365 16441 30365 21924 30366 16441 30366 15119 30366 15119 30367 16441 30367 16442 30367 15119 30368 16442 30368 15120 30368 15120 30369 16442 30369 16443 30369 15120 30370 16443 30370 15121 30370 15121 30371 16443 30371 15122 30371 15121 30372 15122 30372 21926 30372 21926 30373 15122 30373 15123 30373 21926 30374 15123 30374 21928 30374 21928 30375 15123 30375 15124 30375 21928 30376 15124 30376 21929 30376 21929 30377 15124 30377 16446 30377 21929 30378 16446 30378 21931 30378 21931 30379 16446 30379 15125 30379 21931 30380 15125 30380 15126 30380 22560 30381 22559 30381 15127 30381 22560 30382 15127 30382 15128 30382 15128 30383 15127 30383 16445 30383 15128 30384 16445 30384 15129 30384 15129 30385 16445 30385 16444 30385 15129 30386 16444 30386 21891 30386 21891 30387 16444 30387 15130 30387 21891 30388 15130 30388 15132 30388 15132 30389 15130 30389 15131 30389 15132 30390 15131 30390 15134 30390 15134 30391 15131 30391 15133 30391 15134 30392 15133 30392 15135 30392 15135 30393 15133 30393 16439 30393 15135 30394 16439 30394 15136 30394 15136 30395 16439 30395 16438 30395 15136 30396 16438 30396 21864 30396 21864 30397 16438 30397 15137 30397 21864 30398 15137 30398 21866 30398 21866 30399 15137 30399 15138 30399 21866 30400 15138 30400 15139 30400 15139 30401 15138 30401 16435 30401 15139 30402 16435 30402 15140 30402 15140 30403 16435 30403 15142 30403 15140 30404 15142 30404 15141 30404 15141 30405 15142 30405 15143 30405 15141 30406 15143 30406 21868 30406 21868 30407 15143 30407 15144 30407 21868 30408 15144 30408 21869 30408 21869 30409 15144 30409 15145 30409 21869 30410 15145 30410 15146 30410 15146 30411 15145 30411 16429 30411 15146 30412 16429 30412 15147 30412 15147 30413 16429 30413 16428 30413 15147 30414 16428 30414 15148 30414 15148 30415 16428 30415 15150 30415 15148 30416 15150 30416 15149 30416 15149 30417 15150 30417 15151 30417 15149 30418 15151 30418 21873 30418 15152 30419 16406 30419 16407 30419 15152 30420 16407 30420 15153 30420 15153 30421 16407 30421 16408 30421 15153 30422 16408 30422 15154 30422 15154 30423 16408 30423 16410 30423 15154 30424 16410 30424 21825 30424 21825 30425 16410 30425 15156 30425 21825 30426 15156 30426 15155 30426 15155 30427 15156 30427 15157 30427 15155 30428 15157 30428 21827 30428 21827 30429 15157 30429 16411 30429 21827 30430 16411 30430 21829 30430 21829 30431 16411 30431 15158 30431 21829 30432 15158 30432 21830 30432 21830 30433 15158 30433 16413 30433 21830 30434 16413 30434 15159 30434 15159 30435 16413 30435 16414 30435 15159 30436 16414 30436 21832 30436 21832 30437 16414 30437 15160 30437 21832 30438 15160 30438 21833 30438 21833 30439 15160 30439 16417 30439 21833 30440 16417 30440 15161 30440 15161 30441 16417 30441 16420 30441 15161 30442 16420 30442 15162 30442 15162 30443 16420 30443 16421 30443 15162 30444 16421 30444 21835 30444 21835 30445 16421 30445 16422 30445 21835 30446 16422 30446 21836 30446 21836 30447 16422 30447 15164 30447 21836 30448 15164 30448 15163 30448 15163 30449 15164 30449 15165 30449 15163 30450 15165 30450 21837 30450 21837 30451 15165 30451 15166 30451 21837 30452 15166 30452 15168 30452 15168 30453 15166 30453 15167 30453 15168 30454 15167 30454 21839 30454 21839 30455 15167 30455 19935 30455 21839 30456 19935 30456 21841 30456 22515 30457 19934 30457 16426 30457 22515 30458 16426 30458 15169 30458 15169 30459 16426 30459 15170 30459 15169 30460 15170 30460 21807 30460 21807 30461 15170 30461 16425 30461 21807 30462 16425 30462 15171 30462 15171 30463 16425 30463 16424 30463 15171 30464 16424 30464 15172 30464 15172 30465 16424 30465 16423 30465 15172 30466 16423 30466 15173 30466 15173 30467 16423 30467 16419 30467 15173 30468 16419 30468 15174 30468 15174 30469 16419 30469 16418 30469 15174 30470 16418 30470 15175 30470 15175 30471 16418 30471 16416 30471 15175 30472 16416 30472 21776 30472 21776 30473 16416 30473 16415 30473 21776 30474 16415 30474 15176 30474 15176 30475 16415 30475 15178 30475 15176 30476 15178 30476 15177 30476 15177 30477 15178 30477 16412 30477 15177 30478 16412 30478 21780 30478 21780 30479 16412 30479 15179 30479 21780 30480 15179 30480 21781 30480 21781 30481 15179 30481 15180 30481 21781 30482 15180 30482 21784 30482 21784 30483 15180 30483 15181 30483 21784 30484 15181 30484 15183 30484 15183 30485 15181 30485 15182 30485 15183 30486 15182 30486 21786 30486 21786 30487 15182 30487 16409 30487 21786 30488 16409 30488 15184 30488 15184 30489 16409 30489 15185 30489 15184 30490 15185 30490 15186 30490 15186 30491 15185 30491 15187 30491 15186 30492 15187 30492 15188 30492 15188 30493 15187 30493 16405 30493 15188 30494 16405 30494 21789 30494 21745 30495 16383 30495 15189 30495 21745 30496 15189 30496 21747 30496 21747 30497 15189 30497 15191 30497 21747 30498 15191 30498 15190 30498 15190 30499 15191 30499 16387 30499 15190 30500 16387 30500 15192 30500 15192 30501 16387 30501 16388 30501 15192 30502 16388 30502 15193 30502 15193 30503 16388 30503 16389 30503 15193 30504 16389 30504 15195 30504 15195 30505 16389 30505 15194 30505 15195 30506 15194 30506 21751 30506 21751 30507 15194 30507 16390 30507 21751 30508 16390 30508 15196 30508 15196 30509 16390 30509 15198 30509 15196 30510 15198 30510 15197 30510 15197 30511 15198 30511 16394 30511 15197 30512 16394 30512 15199 30512 15199 30513 16394 30513 15201 30513 15199 30514 15201 30514 15200 30514 15200 30515 15201 30515 16398 30515 15200 30516 16398 30516 21753 30516 21753 30517 16398 30517 15203 30517 21753 30518 15203 30518 15202 30518 15202 30519 15203 30519 16400 30519 15202 30520 16400 30520 21718 30520 21718 30521 16400 30521 15205 30521 21718 30522 15205 30522 15204 30522 15204 30523 15205 30523 15206 30523 15204 30524 15206 30524 21720 30524 21720 30525 15206 30525 15207 30525 21720 30526 15207 30526 21721 30526 21721 30527 15207 30527 15208 30527 21721 30528 15208 30528 21722 30528 21722 30529 15208 30529 16403 30529 21722 30530 16403 30530 15209 30530 15209 30531 16403 30531 22480 30531 15209 30532 22480 30532 22482 30532 22454 30533 22441 30533 15211 30533 22454 30534 15211 30534 15210 30534 15210 30535 15211 30535 15212 30535 15210 30536 15212 30536 15213 30536 15213 30537 15212 30537 22418 30537 15213 30538 22418 30538 22452 30538 22452 30539 22418 30539 22420 30539 22452 30540 22420 30540 15214 30540 15214 30541 22420 30541 15215 30541 15214 30542 15215 30542 22450 30542 22450 30543 15215 30543 15216 30543 22450 30544 15216 30544 22449 30544 22449 30545 15216 30545 22423 30545 22449 30546 22423 30546 15217 30546 15217 30547 22423 30547 15218 30547 15217 30548 15218 30548 22447 30548 22447 30549 15218 30549 15219 30549 22447 30550 15219 30550 22445 30550 22445 30551 15219 30551 22427 30551 22445 30552 22427 30552 15220 30552 15220 30553 22427 30553 15221 30553 15220 30554 15221 30554 15222 30554 15222 30555 15221 30555 15224 30555 15222 30556 15224 30556 15223 30556 15223 30557 15224 30557 15225 30557 15223 30558 15225 30558 22443 30558 22443 30559 15225 30559 22389 30559 22443 30560 22389 30560 22442 30560 22442 30561 22389 30561 22393 30561 22442 30562 22393 30562 15226 30562 15226 30563 22393 30563 15227 30563 15226 30564 15227 30564 15228 30564 15228 30565 15227 30565 22394 30565 15228 30566 22394 30566 15229 30566 15229 30567 22394 30567 22395 30567 15229 30568 22395 30568 15230 30568 15230 30569 22395 30569 22396 30569 15230 30570 22396 30570 15231 30570 15232 30571 22319 30571 22320 30571 15232 30572 22320 30572 15233 30572 15233 30573 22320 30573 22321 30573 15233 30574 22321 30574 22364 30574 22364 30575 22321 30575 22322 30575 22364 30576 22322 30576 15234 30576 15234 30577 22322 30577 15235 30577 15234 30578 15235 30578 15236 30578 15236 30579 15235 30579 22323 30579 15236 30580 22323 30580 22361 30580 22361 30581 22323 30581 22325 30581 22361 30582 22325 30582 15237 30582 15237 30583 22325 30583 15238 30583 15237 30584 15238 30584 22359 30584 22359 30585 15238 30585 22326 30585 22359 30586 22326 30586 15239 30586 15239 30587 22326 30587 22329 30587 15239 30588 22329 30588 22357 30588 22357 30589 22329 30589 22291 30589 22357 30590 22291 30590 15240 30590 15240 30591 22291 30591 15241 30591 15240 30592 15241 30592 15242 30592 15242 30593 15241 30593 15243 30593 15242 30594 15243 30594 22354 30594 22354 30595 15243 30595 15244 30595 22354 30596 15244 30596 22353 30596 22353 30597 15244 30597 15245 30597 22353 30598 15245 30598 22352 30598 22352 30599 15245 30599 22297 30599 22352 30600 22297 30600 22351 30600 22351 30601 22297 30601 22298 30601 22351 30602 22298 30602 15246 30602 15246 30603 22298 30603 22300 30603 15246 30604 22300 30604 15247 30604 15247 30605 22300 30605 22301 30605 15247 30606 22301 30606 22387 30606 22387 30607 22301 30607 15248 30607 22387 30608 15248 30608 22331 30608 22265 30609 22250 30609 22222 30609 22265 30610 22222 30610 22263 30610 22263 30611 22222 30611 15249 30611 22263 30612 15249 30612 15250 30612 15250 30613 15249 30613 15251 30613 15250 30614 15251 30614 22261 30614 22261 30615 15251 30615 15252 30615 22261 30616 15252 30616 15253 30616 15253 30617 15252 30617 22226 30617 15253 30618 22226 30618 22260 30618 22260 30619 22226 30619 22227 30619 22260 30620 22227 30620 15254 30620 15254 30621 22227 30621 22229 30621 15254 30622 22229 30622 22257 30622 22257 30623 22229 30623 22230 30623 22257 30624 22230 30624 22256 30624 22256 30625 22230 30625 15255 30625 22256 30626 15255 30626 15256 30626 15256 30627 15255 30627 22232 30627 15256 30628 22232 30628 15257 30628 15257 30629 22232 30629 15258 30629 15257 30630 15258 30630 15259 30630 15259 30631 15258 30631 22193 30631 15259 30632 22193 30632 15260 30632 15260 30633 22193 30633 22194 30633 15260 30634 22194 30634 22253 30634 22253 30635 22194 30635 22196 30635 22253 30636 22196 30636 15261 30636 15261 30637 22196 30637 15262 30637 15261 30638 15262 30638 22251 30638 22251 30639 15262 30639 22197 30639 22251 30640 22197 30640 22290 30640 22290 30641 22197 30641 15263 30641 22290 30642 15263 30642 22289 30642 22289 30643 15263 30643 22199 30643 22289 30644 22199 30644 15264 30644 15264 30645 22199 30645 22201 30645 15264 30646 22201 30646 22286 30646 22154 30647 22119 30647 15266 30647 22154 30648 15266 30648 15265 30648 15265 30649 15266 30649 15267 30649 15265 30650 15267 30650 22172 30650 22172 30651 15267 30651 15268 30651 22172 30652 15268 30652 15269 30652 15269 30653 15268 30653 15270 30653 15269 30654 15270 30654 22168 30654 22168 30655 15270 30655 15271 30655 22168 30656 15271 30656 22166 30656 22166 30657 15271 30657 22123 30657 22166 30658 22123 30658 15272 30658 15272 30659 22123 30659 15273 30659 15272 30660 15273 30660 15274 30660 15274 30661 15273 30661 22124 30661 15274 30662 22124 30662 22163 30662 22163 30663 22124 30663 15275 30663 22163 30664 15275 30664 22162 30664 22162 30665 15275 30665 15276 30665 22162 30666 15276 30666 15277 30666 15277 30667 15276 30667 22089 30667 15277 30668 22089 30668 15278 30668 15278 30669 22089 30669 15279 30669 15278 30670 15279 30670 15280 30670 15280 30671 15279 30671 22090 30671 15280 30672 22090 30672 22156 30672 22156 30673 22090 30673 15281 30673 22156 30674 15281 30674 22155 30674 22155 30675 15281 30675 22094 30675 22155 30676 22094 30676 15282 30676 15282 30677 22094 30677 15283 30677 15282 30678 15283 30678 22189 30678 22189 30679 15283 30679 15284 30679 22189 30680 15284 30680 15285 30680 15285 30681 15284 30681 22098 30681 15285 30682 22098 30682 15286 30682 15286 30683 22098 30683 22127 30683 15286 30684 22127 30684 15287 30684 22049 30685 22018 30685 15288 30685 22049 30686 15288 30686 15289 30686 15289 30687 15288 30687 22021 30687 15289 30688 22021 30688 15291 30688 15291 30689 22021 30689 15290 30689 15291 30690 15290 30690 22055 30690 22055 30691 15290 30691 22024 30691 22055 30692 22024 30692 15292 30692 15292 30693 22024 30693 22025 30693 15292 30694 22025 30694 22053 30694 22053 30695 22025 30695 22026 30695 22053 30696 22026 30696 22052 30696 22052 30697 22026 30697 15293 30697 22052 30698 15293 30698 15294 30698 15294 30699 15293 30699 22030 30699 15294 30700 22030 30700 15295 30700 15295 30701 22030 30701 15296 30701 15295 30702 15296 30702 22050 30702 22050 30703 15296 30703 22031 30703 22050 30704 22031 30704 22088 30704 22088 30705 22031 30705 15297 30705 22088 30706 15297 30706 15298 30706 15298 30707 15297 30707 15299 30707 15298 30708 15299 30708 15300 30708 15300 30709 15299 30709 15302 30709 15300 30710 15302 30710 15301 30710 15301 30711 15302 30711 15303 30711 15301 30712 15303 30712 22085 30712 22085 30713 15303 30713 15304 30713 22085 30714 15304 30714 15305 30714 15305 30715 15304 30715 15306 30715 15305 30716 15306 30716 22082 30716 22082 30717 15306 30717 21995 30717 22082 30718 21995 30718 22081 30718 22081 30719 21995 30719 21996 30719 22081 30720 21996 30720 15307 30720 15307 30721 21996 30721 15308 30721 15307 30722 15308 30722 15309 30722 21962 30723 15310 30723 21914 30723 21962 30724 21914 30724 21960 30724 21960 30725 21914 30725 15311 30725 21960 30726 15311 30726 21959 30726 21959 30727 15311 30727 15312 30727 21959 30728 15312 30728 15313 30728 15313 30729 15312 30729 15314 30729 15313 30730 15314 30730 15315 30730 15315 30731 15314 30731 15316 30731 15315 30732 15316 30732 21956 30732 21956 30733 15316 30733 15317 30733 21956 30734 15317 30734 15318 30734 15318 30735 15317 30735 15319 30735 15318 30736 15319 30736 21954 30736 21954 30737 15319 30737 15321 30737 21954 30738 15321 30738 15320 30738 15320 30739 15321 30739 15322 30739 15320 30740 15322 30740 21952 30740 21952 30741 15322 30741 21922 30741 21952 30742 21922 30742 15323 30742 15323 30743 21922 30743 15324 30743 15323 30744 15324 30744 21950 30744 21950 30745 15324 30745 21923 30745 21950 30746 21923 30746 15326 30746 15326 30747 21923 30747 15325 30747 15326 30748 15325 30748 21949 30748 21949 30749 15325 30749 21925 30749 21949 30750 21925 30750 21989 30750 21989 30751 21925 30751 15327 30751 21989 30752 15327 30752 21987 30752 21987 30753 15327 30753 21927 30753 21987 30754 21927 30754 15328 30754 15328 30755 21927 30755 15330 30755 15328 30756 15330 30756 15329 30756 15329 30757 15330 30757 21930 30757 15329 30758 21930 30758 15331 30758 15331 30759 21930 30759 15332 30759 15331 30760 15332 30760 21983 30760 21861 30761 21859 30761 15333 30761 21861 30762 15333 30762 21872 30762 21872 30763 15333 30763 15334 30763 21872 30764 15334 30764 15335 30764 15335 30765 15334 30765 21826 30765 15335 30766 21826 30766 21871 30766 21871 30767 21826 30767 15336 30767 21871 30768 15336 30768 21870 30768 21870 30769 15336 30769 15337 30769 21870 30770 15337 30770 15338 30770 15338 30771 15337 30771 15340 30771 15338 30772 15340 30772 15339 30772 15339 30773 15340 30773 21828 30773 15339 30774 21828 30774 15341 30774 15341 30775 21828 30775 15342 30775 15341 30776 15342 30776 21867 30776 21867 30777 15342 30777 21831 30777 21867 30778 21831 30778 15343 30778 15343 30779 21831 30779 15344 30779 15343 30780 15344 30780 21865 30780 21865 30781 15344 30781 15345 30781 21865 30782 15345 30782 21863 30782 21863 30783 15345 30783 21834 30783 21863 30784 21834 30784 21862 30784 21862 30785 21834 30785 15347 30785 21862 30786 15347 30786 15346 30786 15346 30787 15347 30787 15348 30787 15346 30788 15348 30788 21893 30788 21893 30789 15348 30789 15349 30789 21893 30790 15349 30790 21892 30790 21892 30791 15349 30791 15350 30791 21892 30792 15350 30792 15351 30792 15351 30793 15350 30793 21838 30793 15351 30794 21838 30794 15352 30794 15352 30795 21838 30795 15353 30795 15352 30796 15353 30796 21890 30796 21890 30797 15353 30797 21840 30797 21890 30798 21840 30798 15354 30798 15355 30799 21744 30799 15356 30799 15355 30800 15356 30800 21788 30800 21788 30801 15356 30801 21746 30801 21788 30802 21746 30802 21787 30802 21787 30803 21746 30803 15357 30803 21787 30804 15357 30804 15358 30804 15358 30805 15357 30805 21748 30805 15358 30806 21748 30806 15359 30806 15359 30807 21748 30807 21749 30807 15359 30808 21749 30808 21785 30808 21785 30809 21749 30809 15360 30809 21785 30810 15360 30810 21783 30810 21783 30811 15360 30811 21750 30811 21783 30812 21750 30812 21782 30812 21782 30813 21750 30813 15361 30813 21782 30814 15361 30814 21779 30814 21779 30815 15361 30815 21752 30815 21779 30816 21752 30816 21778 30816 21778 30817 21752 30817 15362 30817 21778 30818 15362 30818 21777 30818 21777 30819 15362 30819 15363 30819 21777 30820 15363 30820 21775 30820 21775 30821 15363 30821 15364 30821 21775 30822 15364 30822 15365 30822 15365 30823 15364 30823 21754 30823 15365 30824 21754 30824 21811 30824 21811 30825 21754 30825 15366 30825 21811 30826 15366 30826 21810 30826 21810 30827 15366 30827 21719 30827 21810 30828 21719 30828 21809 30828 21809 30829 21719 30829 15367 30829 21809 30830 15367 30830 21808 30830 21808 30831 15367 30831 21723 30831 21808 30832 21723 30832 21806 30832 21806 30833 21723 30833 15368 30833 21806 30834 15368 30834 21805 30834 21805 30835 15368 30835 15369 30835 21805 30836 15369 30836 15370 30836 21674 30837 16404 30837 16402 30837 21674 30838 16402 30838 15371 30838 15371 30839 16402 30839 15372 30839 15371 30840 15372 30840 15373 30840 15373 30841 15372 30841 15374 30841 15373 30842 15374 30842 21677 30842 21677 30843 15374 30843 16401 30843 21677 30844 16401 30844 21678 30844 21678 30845 16401 30845 15376 30845 21678 30846 15376 30846 15375 30846 15375 30847 15376 30847 16399 30847 15375 30848 16399 30848 15377 30848 15377 30849 16399 30849 16397 30849 15377 30850 16397 30850 21648 30850 21648 30851 16397 30851 16396 30851 21648 30852 16396 30852 21650 30852 21650 30853 16396 30853 16395 30853 21650 30854 16395 30854 15378 30854 15378 30855 16395 30855 16393 30855 15378 30856 16393 30856 15379 30856 15379 30857 16393 30857 16392 30857 15379 30858 16392 30858 21653 30858 21653 30859 16392 30859 16391 30859 21653 30860 16391 30860 21654 30860 21654 30861 16391 30861 15380 30861 21654 30862 15380 30862 15381 30862 15381 30863 15380 30863 15382 30863 15381 30864 15382 30864 15383 30864 15383 30865 15382 30865 16386 30865 15383 30866 16386 30866 15384 30866 15384 30867 16386 30867 16385 30867 15384 30868 16385 30868 21657 30868 21657 30869 16385 30869 16384 30869 21657 30870 16384 30870 15385 30870 15385 30871 16384 30871 15386 30871 15385 30872 15386 30872 15387 30872 15387 30873 15386 30873 16382 30873 15387 30874 16382 30874 15388 30874 21617 30875 19990 30875 15389 30875 21617 30876 15389 30876 21618 30876 21618 30877 15389 30877 16365 30877 21618 30878 16365 30878 15390 30878 15390 30879 16365 30879 15391 30879 15390 30880 15391 30880 21621 30880 21621 30881 15391 30881 16367 30881 21621 30882 16367 30882 15393 30882 15393 30883 16367 30883 15392 30883 15393 30884 15392 30884 21623 30884 21623 30885 15392 30885 15394 30885 21623 30886 15394 30886 15395 30886 15395 30887 15394 30887 15396 30887 15395 30888 15396 30888 15397 30888 15397 30889 15396 30889 15398 30889 15397 30890 15398 30890 21625 30890 21625 30891 15398 30891 16371 30891 21625 30892 16371 30892 15399 30892 15399 30893 16371 30893 16373 30893 15399 30894 16373 30894 15400 30894 15400 30895 16373 30895 16374 30895 15400 30896 16374 30896 15401 30896 15401 30897 16374 30897 15402 30897 15401 30898 15402 30898 15403 30898 15403 30899 15402 30899 16377 30899 15403 30900 16377 30900 15404 30900 15404 30901 16377 30901 16378 30901 15404 30902 16378 30902 21592 30902 21592 30903 16378 30903 15406 30903 21592 30904 15406 30904 15405 30904 15405 30905 15406 30905 16379 30905 15405 30906 16379 30906 15407 30906 15407 30907 16379 30907 16380 30907 15407 30908 16380 30908 21594 30908 21594 30909 16380 30909 15408 30909 21594 30910 15408 30910 21595 30910 21595 30911 15408 30911 19978 30911 21595 30912 19978 30912 21596 30912 21658 30913 15409 30913 21619 30913 21658 30914 21619 30914 15410 30914 15410 30915 21619 30915 21620 30915 15410 30916 21620 30916 15411 30916 15411 30917 21620 30917 15412 30917 15411 30918 15412 30918 21656 30918 21656 30919 15412 30919 15413 30919 21656 30920 15413 30920 15414 30920 15414 30921 15413 30921 21622 30921 15414 30922 21622 30922 21655 30922 21655 30923 21622 30923 15415 30923 21655 30924 15415 30924 15416 30924 15416 30925 15415 30925 21624 30925 15416 30926 21624 30926 21652 30926 21652 30927 21624 30927 15417 30927 21652 30928 15417 30928 15418 30928 15418 30929 15417 30929 15419 30929 15418 30930 15419 30930 21651 30930 21651 30931 15419 30931 15420 30931 21651 30932 15420 30932 15421 30932 15421 30933 15420 30933 21589 30933 15421 30934 21589 30934 21649 30934 21649 30935 21589 30935 15422 30935 21649 30936 15422 30936 21647 30936 21647 30937 15422 30937 21590 30937 21647 30938 21590 30938 15424 30938 15424 30939 21590 30939 15423 30939 15424 30940 15423 30940 21679 30940 21679 30941 15423 30941 21591 30941 21679 30942 21591 30942 15425 30942 15425 30943 21591 30943 21593 30943 15425 30944 21593 30944 15426 30944 15426 30945 21593 30945 15427 30945 15426 30946 15427 30946 21676 30946 21676 30947 15427 30947 15428 30947 21676 30948 15428 30948 21675 30948 21675 30949 15428 30949 21597 30949 21675 30950 21597 30950 21673 30950 15429 30951 21544 30951 15430 30951 15430 30952 21544 30952 15431 30952 15430 30953 15431 30953 15436 30953 15436 30954 15431 30954 21552 30954 15436 30955 21552 30955 15432 30955 15432 30956 21552 30956 15433 30956 15432 30957 15433 30957 15437 30957 15437 30958 15433 30958 21565 30958 15437 30959 21565 30959 15434 30959 15434 30960 21565 30960 15435 30960 15434 30961 15435 30961 21578 30961 21578 30962 15435 30962 21579 30962 21577 30963 15436 30963 15432 30963 15430 30964 15436 30964 21577 30964 15429 30965 15430 30965 21577 30965 21577 30966 15434 30966 21578 30966 15437 30967 15434 30967 21577 30967 15432 30968 15437 30968 21577 30968 15438 30969 21559 30969 15439 30969 15439 30970 21559 30970 15440 30970 15439 30971 15440 30971 15446 30971 15446 30972 15440 30972 15441 30972 15446 30973 15441 30973 15442 30973 15442 30974 15441 30974 21557 30974 15442 30975 21557 30975 15447 30975 15447 30976 21557 30976 15444 30976 15447 30977 15444 30977 15443 30977 15443 30978 15444 30978 15445 30978 15443 30979 15445 30979 21568 30979 21568 30980 15445 30980 21569 30980 21567 30981 15446 30981 15442 30981 15439 30982 15446 30982 21567 30982 15438 30983 15439 30983 21567 30983 21567 30984 15443 30984 21568 30984 15447 30985 15443 30985 21567 30985 15442 30986 15447 30986 21567 30986 21539 30987 15448 30987 15457 30987 15457 30988 15448 30988 15449 30988 15457 30989 15449 30989 15450 30989 15450 30990 15449 30990 21506 30990 15450 30991 21506 30991 15451 30991 15451 30992 21506 30992 21504 30992 15451 30993 21504 30993 15452 30993 15452 30994 21504 30994 15453 30994 15452 30995 15453 30995 15455 30995 15455 30996 15453 30996 15454 30996 15455 30997 15454 30997 15456 30997 15456 30998 15454 30998 21531 30998 21530 30999 15450 30999 15451 30999 15457 31000 15450 31000 21530 31000 21539 31001 15457 31001 21530 31001 21530 31002 15455 31002 15456 31002 15452 31003 15455 31003 21530 31003 15451 31004 15452 31004 21530 31004 21520 31005 15458 31005 15466 31005 15466 31006 15458 31006 21496 31006 15466 31007 21496 31007 15465 31007 15465 31008 21496 31008 15460 31008 15465 31009 15460 31009 15459 31009 15459 31010 15460 31010 15461 31010 15459 31011 15461 31011 15462 31011 15462 31012 15461 31012 21494 31012 15462 31013 21494 31013 15463 31013 15463 31014 21494 31014 21514 31014 15463 31015 21514 31015 15468 31015 15468 31016 21514 31016 15464 31016 15467 31017 15465 31017 15459 31017 15466 31018 15465 31018 15467 31018 21520 31019 15466 31019 15467 31019 15467 31020 15463 31020 15468 31020 15462 31021 15463 31021 15467 31021 15459 31022 15462 31022 15467 31022 15475 31023 18149 31023 15469 31023 15469 31024 18149 31024 15470 31024 15469 31025 15470 31025 15478 31025 15478 31026 15470 31026 15471 31026 15478 31027 15471 31027 15480 31027 15480 31028 15471 31028 18147 31028 15480 31029 18147 31029 15481 31029 15481 31030 18147 31030 15473 31030 15481 31031 15473 31031 15472 31031 15472 31032 15473 31032 15474 31032 15472 31033 15474 31033 21488 31033 21488 31034 15474 31034 18144 31034 21487 31035 15475 31035 15476 31035 15476 31036 15475 31036 15469 31036 15476 31037 15469 31037 15477 31037 15477 31038 15469 31038 15478 31038 15477 31039 15478 31039 15486 31039 15486 31040 15478 31040 15480 31040 15486 31041 15480 31041 15479 31041 15479 31042 15480 31042 15481 31042 15479 31043 15481 31043 15482 31043 15482 31044 15481 31044 15472 31044 15482 31045 15472 31045 15483 31045 15483 31046 15472 31046 21488 31046 15483 31047 15484 31047 15482 31047 15482 31048 15484 31048 21401 31048 15482 31049 21401 31049 15479 31049 15479 31050 21401 31050 15485 31050 15479 31051 15485 31051 15486 31051 15486 31052 15485 31052 21402 31052 15486 31053 21402 31053 15477 31053 15477 31054 21402 31054 15487 31054 15477 31055 15487 31055 15476 31055 15476 31056 15487 31056 21403 31056 15476 31057 21403 31057 21487 31057 21487 31058 21403 31058 21405 31058 18132 31059 18135 31059 21461 31059 21461 31060 15508 31060 18132 31060 18132 31061 15508 31061 15507 31061 18132 31062 15507 31062 15488 31062 15507 31063 15505 31063 15488 31063 15488 31064 15505 31064 15489 31064 15488 31065 15489 31065 15490 31065 15490 31066 15489 31066 15502 31066 15502 31067 15501 31067 15490 31067 15490 31068 15501 31068 15492 31068 15490 31069 15492 31069 15491 31069 15492 31070 15499 31070 15491 31070 15491 31071 15499 31071 15498 31071 15491 31072 15498 31072 18128 31072 15493 31073 21471 31073 15496 31073 15496 31074 21471 31074 18128 31074 15496 31075 18128 31075 15494 31075 15494 31076 18128 31076 15498 31076 21468 31077 15493 31077 15495 31077 15495 31078 15493 31078 15496 31078 15495 31079 15496 31079 15497 31079 15497 31080 15496 31080 15494 31080 15497 31081 15494 31081 15510 31081 15510 31082 15494 31082 15498 31082 15510 31083 15498 31083 15511 31083 15511 31084 15498 31084 15499 31084 15511 31085 15499 31085 15512 31085 15512 31086 15499 31086 15492 31086 15512 31087 15492 31087 15500 31087 15500 31088 15492 31088 15501 31088 15500 31089 15501 31089 15514 31089 15514 31090 15501 31090 15502 31090 15514 31091 15502 31091 15503 31091 15503 31092 15502 31092 15489 31092 15503 31093 15489 31093 15504 31093 15504 31094 15489 31094 15505 31094 15504 31095 15505 31095 15506 31095 15506 31096 15505 31096 15507 31096 15506 31097 15507 31097 15517 31097 15517 31098 15507 31098 15508 31098 15517 31099 15508 31099 15515 31099 15515 31100 15508 31100 21461 31100 15509 31101 21377 31101 21468 31101 21468 31102 15495 31102 15509 31102 15509 31103 15495 31103 15497 31103 15509 31104 15497 31104 21374 31104 15497 31105 15510 31105 21374 31105 21374 31106 15510 31106 15511 31106 21374 31107 15511 31107 15513 31107 15513 31108 15511 31108 15512 31108 15512 31109 15500 31109 15513 31109 15513 31110 15500 31110 15514 31110 15513 31111 15514 31111 21388 31111 15514 31112 15503 31112 21388 31112 21388 31113 15503 31113 15504 31113 21388 31114 15504 31114 15516 31114 15515 31115 21385 31115 15517 31115 15517 31116 21385 31116 15516 31116 15517 31117 15516 31117 15506 31117 15506 31118 15516 31118 15504 31118 21436 31119 21446 31119 15523 31119 15523 31120 21446 31120 18118 31120 15523 31121 18118 31121 15524 31121 15524 31122 18118 31122 15518 31122 15524 31123 15518 31123 15519 31123 15519 31124 15518 31124 15520 31124 15519 31125 15520 31125 15525 31125 15525 31126 15520 31126 15521 31126 15525 31127 15521 31127 15527 31127 15527 31128 15521 31128 15522 31128 15527 31129 15522 31129 21445 31129 21445 31130 15522 31130 18114 31130 21433 31131 21436 31131 15534 31131 15534 31132 21436 31132 15523 31132 15534 31133 15523 31133 15533 31133 15533 31134 15523 31134 15524 31134 15533 31135 15524 31135 15531 31135 15531 31136 15524 31136 15519 31136 15531 31137 15519 31137 15530 31137 15530 31138 15519 31138 15525 31138 15530 31139 15525 31139 15526 31139 15526 31140 15525 31140 15527 31140 15526 31141 15527 31141 15528 31141 15528 31142 15527 31142 21445 31142 15528 31143 21356 31143 15526 31143 15526 31144 21356 31144 15529 31144 15526 31145 15529 31145 15530 31145 15530 31146 15529 31146 21355 31146 15530 31147 21355 31147 15531 31147 15531 31148 21355 31148 15532 31148 15531 31149 15532 31149 15533 31149 15533 31150 15532 31150 15535 31150 15533 31151 15535 31151 15534 31151 15534 31152 15535 31152 21352 31152 15534 31153 21352 31153 21433 31153 21433 31154 21352 31154 21350 31154 21412 31155 21421 31155 15536 31155 15536 31156 21421 31156 20164 31156 15536 31157 20164 31157 15537 31157 15537 31158 20164 31158 15538 31158 15537 31159 15538 31159 15548 31159 15548 31160 15538 31160 15539 31160 15548 31161 15539 31161 15540 31161 15540 31162 15539 31162 20165 31162 15540 31163 20165 31163 15541 31163 15541 31164 20165 31164 15542 31164 15541 31165 15542 31165 15543 31165 15543 31166 15542 31166 20160 31166 15544 31167 21412 31167 15545 31167 15545 31168 21412 31168 15536 31168 15545 31169 15536 31169 15546 31169 15546 31170 15536 31170 15537 31170 15546 31171 15537 31171 15547 31171 15547 31172 15537 31172 15548 31172 15547 31173 15548 31173 15549 31173 15549 31174 15548 31174 15540 31174 15549 31175 15540 31175 21404 31175 21404 31176 15540 31176 15541 31176 21404 31177 15541 31177 21406 31177 21406 31178 15541 31178 15543 31178 15560 31179 15550 31179 15562 31179 15562 31180 15550 31180 15551 31180 15562 31181 15551 31181 15552 31181 15552 31182 15551 31182 15553 31182 15552 31183 15553 31183 15554 31183 15554 31184 15553 31184 15555 31184 15554 31185 15555 31185 15564 31185 15564 31186 15555 31186 20215 31186 15564 31187 20215 31187 15565 31187 15565 31188 20215 31188 15557 31188 15565 31189 15557 31189 15556 31189 15556 31190 15557 31190 15559 31190 15556 31191 15559 31191 15558 31191 15558 31192 15559 31192 21394 31192 21386 31193 15560 31193 21387 31193 21387 31194 15560 31194 15562 31194 21387 31195 15562 31195 15561 31195 15561 31196 15562 31196 15552 31196 15561 31197 15552 31197 15563 31197 15563 31198 15552 31198 15554 31198 15563 31199 15554 31199 21373 31199 21373 31200 15554 31200 15564 31200 21373 31201 15564 31201 21375 31201 21375 31202 15564 31202 15565 31202 21375 31203 15565 31203 21376 31203 21376 31204 15565 31204 15556 31204 21376 31205 15556 31205 21378 31205 21378 31206 15556 31206 15558 31206 15568 31207 21365 31207 15566 31207 15566 31208 15567 31208 15568 31208 15568 31209 15567 31209 15569 31209 15568 31210 15569 31210 15570 31210 15569 31211 15584 31211 15570 31211 15570 31212 15584 31212 15572 31212 15570 31213 15572 31213 15571 31213 15572 31214 15582 31214 15571 31214 15571 31215 15582 31215 15581 31215 15571 31216 15581 31216 20114 31216 20114 31217 15581 31217 15580 31217 20114 31218 15580 31218 15573 31218 15580 31219 15574 31219 15573 31219 15573 31220 15574 31220 15576 31220 15573 31221 15576 31221 15575 31221 21370 31222 21372 31222 15577 31222 15577 31223 21372 31223 15575 31223 15577 31224 15575 31224 15578 31224 15578 31225 15575 31225 15576 31225 21370 31226 15577 31226 21364 31226 21364 31227 15577 31227 15579 31227 15577 31228 15578 31228 15579 31228 15579 31229 15578 31229 15576 31229 15579 31230 15576 31230 21354 31230 15576 31231 15574 31231 21354 31231 21354 31232 15574 31232 15580 31232 21354 31233 15580 31233 21353 31233 15580 31234 15581 31234 21353 31234 21353 31235 15581 31235 15582 31235 21353 31236 15582 31236 15583 31236 15582 31237 15572 31237 15583 31237 15583 31238 15572 31238 15584 31238 15583 31239 15584 31239 15585 31239 15566 31240 21351 31240 15567 31240 15567 31241 21351 31241 15585 31241 15567 31242 15585 31242 15569 31242 15569 31243 15585 31243 15584 31243 21347 31244 15587 31244 15586 31244 15586 31245 15587 31245 15588 31245 15586 31246 15588 31246 15589 31246 15589 31247 15588 31247 20162 31247 15589 31248 20162 31248 15590 31248 15590 31249 20162 31249 20161 31249 15590 31250 20161 31250 15591 31250 15591 31251 20161 31251 15592 31251 15591 31252 15592 31252 15634 31252 15634 31253 15592 31253 15593 31253 15634 31254 15593 31254 15631 31254 15631 31255 15593 31255 20158 31255 15631 31256 20158 31256 21310 31256 21310 31257 20158 31257 20157 31257 20209 31258 21336 31258 15594 31258 15594 31259 15640 31259 20209 31259 20209 31260 15640 31260 15595 31260 20209 31261 15595 31261 20208 31261 15595 31262 15641 31262 20208 31262 20208 31263 15641 31263 15596 31263 20208 31264 15596 31264 15597 31264 15597 31265 15596 31265 15644 31265 15597 31266 15644 31266 15598 31266 15644 31267 15599 31267 15598 31267 15598 31268 15599 31268 15600 31268 15598 31269 15600 31269 15602 31269 15600 31270 15646 31270 15602 31270 15602 31271 15646 31271 15601 31271 15602 31272 15601 31272 15605 31272 15603 31273 20207 31273 15604 31273 15604 31274 20207 31274 15605 31274 15604 31275 15605 31275 15606 31275 15606 31276 15605 31276 15601 31276 21270 31277 15607 31277 15661 31277 15661 31278 15607 31278 20229 31278 15661 31279 20229 31279 15660 31279 15660 31280 20229 31280 15608 31280 15660 31281 15608 31281 15609 31281 15609 31282 15608 31282 20231 31282 15609 31283 20231 31283 15610 31283 15610 31284 20231 31284 20232 31284 15610 31285 20232 31285 15611 31285 15611 31286 20232 31286 15613 31286 15611 31287 15613 31287 15612 31287 15612 31288 15613 31288 15614 31288 15612 31289 15614 31289 21275 31289 21275 31290 15614 31290 21329 31290 15615 31291 15616 31291 15673 31291 15673 31292 15616 31292 20343 31292 15673 31293 20343 31293 15672 31293 15672 31294 20343 31294 20341 31294 15672 31295 20341 31295 15670 31295 15670 31296 20341 31296 20340 31296 15670 31297 20340 31297 15617 31297 15617 31298 20340 31298 20333 31298 15617 31299 20333 31299 15618 31299 15618 31300 20333 31300 20339 31300 15618 31301 20339 31301 21264 31301 21264 31302 20339 31302 15619 31302 21319 31303 15635 31303 18105 31303 18105 31304 15635 31304 15620 31304 18105 31305 15620 31305 15621 31305 15620 31306 15622 31306 15621 31306 15621 31307 15622 31307 15623 31307 15621 31308 15623 31308 15625 31308 15625 31309 15623 31309 15624 31309 15624 31310 15626 31310 15625 31310 15625 31311 15626 31311 15627 31311 15625 31312 15627 31312 15628 31312 21308 31313 15629 31313 15632 31313 15632 31314 15629 31314 18109 31314 15632 31315 18109 31315 15630 31315 15630 31316 18109 31316 15628 31316 15630 31317 15628 31317 15633 31317 15633 31318 15628 31318 15627 31318 21310 31319 21308 31319 15632 31319 21310 31320 15632 31320 15631 31320 15631 31321 15632 31321 15630 31321 15631 31322 15630 31322 15634 31322 15634 31323 15630 31323 15633 31323 15634 31324 15633 31324 15591 31324 15633 31325 15627 31325 15591 31325 15591 31326 15627 31326 15626 31326 15591 31327 15626 31327 15590 31327 15626 31328 15624 31328 15590 31328 15590 31329 15624 31329 15623 31329 15590 31330 15623 31330 15589 31330 15623 31331 15622 31331 15589 31331 15589 31332 15622 31332 15620 31332 15589 31333 15620 31333 15586 31333 15586 31334 15620 31334 15635 31334 15586 31335 15635 31335 21347 31335 21287 31336 18090 31336 15642 31336 15642 31337 18090 31337 18100 31337 15642 31338 18100 31338 15643 31338 15643 31339 18100 31339 18097 31339 15643 31340 18097 31340 15636 31340 15636 31341 18097 31341 15637 31341 15636 31342 15637 31342 15645 31342 15645 31343 15637 31343 15638 31343 15645 31344 15638 31344 15647 31344 15647 31345 15638 31345 18096 31345 15647 31346 18096 31346 15648 31346 15648 31347 18096 31347 15639 31347 15594 31348 21287 31348 15640 31348 15640 31349 21287 31349 15642 31349 15640 31350 15642 31350 15595 31350 15595 31351 15642 31351 15641 31351 15641 31352 15642 31352 15643 31352 15641 31353 15643 31353 15596 31353 15596 31354 15643 31354 15644 31354 15644 31355 15643 31355 15636 31355 15644 31356 15636 31356 15599 31356 15599 31357 15636 31357 15600 31357 15600 31358 15636 31358 15645 31358 15600 31359 15645 31359 15646 31359 15646 31360 15645 31360 15601 31360 15601 31361 15645 31361 15647 31361 15601 31362 15647 31362 15606 31362 15606 31363 15647 31363 15604 31363 15604 31364 15647 31364 15648 31364 15604 31365 15648 31365 15603 31365 21280 31366 15649 31366 15656 31366 15656 31367 15649 31367 15650 31367 15656 31368 15650 31368 15657 31368 15657 31369 15650 31369 18078 31369 15657 31370 18078 31370 15658 31370 15658 31371 18078 31371 15651 31371 15658 31372 15651 31372 15652 31372 15652 31373 15651 31373 15653 31373 15652 31374 15653 31374 15659 31374 15659 31375 15653 31375 15654 31375 15659 31376 15654 31376 15662 31376 15662 31377 15654 31377 15655 31377 15662 31378 15655 31378 21271 31378 21271 31379 15655 31379 18086 31379 21275 31380 21280 31380 15612 31380 15612 31381 21280 31381 15656 31381 15612 31382 15656 31382 15611 31382 15611 31383 15656 31383 15657 31383 15611 31384 15657 31384 15610 31384 15610 31385 15657 31385 15658 31385 15610 31386 15658 31386 15609 31386 15609 31387 15658 31387 15652 31387 15609 31388 15652 31388 15660 31388 15660 31389 15652 31389 15659 31389 15660 31390 15659 31390 15661 31390 15661 31391 15659 31391 15662 31391 15661 31392 15662 31392 21270 31392 21270 31393 15662 31393 21271 31393 15668 31394 21269 31394 15669 31394 15669 31395 21269 31395 18073 31395 15669 31396 18073 31396 15663 31396 15663 31397 18073 31397 15664 31397 15663 31398 15664 31398 15671 31398 15671 31399 15664 31399 18072 31399 15671 31400 18072 31400 15666 31400 15666 31401 18072 31401 15665 31401 15666 31402 15665 31402 15674 31402 15674 31403 15665 31403 18071 31403 15674 31404 18071 31404 15667 31404 15667 31405 18071 31405 18069 31405 21264 31406 15668 31406 15618 31406 15618 31407 15668 31407 15669 31407 15618 31408 15669 31408 15617 31408 15617 31409 15669 31409 15663 31409 15617 31410 15663 31410 15670 31410 15670 31411 15663 31411 15671 31411 15670 31412 15671 31412 15672 31412 15672 31413 15671 31413 15666 31413 15672 31414 15666 31414 15673 31414 15673 31415 15666 31415 15674 31415 15673 31416 15674 31416 15615 31416 15615 31417 15674 31417 15667 31417 15675 31418 18063 31418 15681 31418 15681 31419 18063 31419 15676 31419 15681 31420 15676 31420 15677 31420 15677 31421 15676 31421 15678 31421 15677 31422 15678 31422 15682 31422 15682 31423 15678 31423 15679 31423 15682 31424 15679 31424 15683 31424 15683 31425 15679 31425 18059 31425 15683 31426 18059 31426 15685 31426 15685 31427 18059 31427 15680 31427 15685 31428 15680 31428 21258 31428 21258 31429 15680 31429 18058 31429 21232 31430 15675 31430 15689 31430 15689 31431 15675 31431 15681 31431 15689 31432 15681 31432 15688 31432 15688 31433 15681 31433 15677 31433 15688 31434 15677 31434 15687 31434 15687 31435 15677 31435 15682 31435 15687 31436 15682 31436 15686 31436 15686 31437 15682 31437 15683 31437 15686 31438 15683 31438 15684 31438 15684 31439 15683 31439 15685 31439 15684 31440 15685 31440 21226 31440 21226 31441 15685 31441 21258 31441 21226 31442 21225 31442 15684 31442 15684 31443 21225 31443 21159 31443 15684 31444 21159 31444 15686 31444 15686 31445 21159 31445 21160 31445 15686 31446 21160 31446 15687 31446 15687 31447 21160 31447 21161 31447 15687 31448 21161 31448 15688 31448 15688 31449 21161 31449 21164 31449 15688 31450 21164 31450 15689 31450 15689 31451 21164 31451 15690 31451 15689 31452 15690 31452 21232 31452 21232 31453 15690 31453 21233 31453 21218 31454 18052 31454 15691 31454 15691 31455 18052 31455 18051 31455 15691 31456 18051 31456 15696 31456 15696 31457 18051 31457 18049 31457 15696 31458 18049 31458 15699 31458 15699 31459 18049 31459 15692 31459 15699 31460 15692 31460 15701 31460 15701 31461 15692 31461 18048 31461 15701 31462 18048 31462 15693 31462 15693 31463 18048 31463 18047 31463 15693 31464 18047 31464 15702 31464 15702 31465 18047 31465 18046 31465 15703 31466 21218 31466 15704 31466 15704 31467 21218 31467 15691 31467 15704 31468 15691 31468 15694 31468 15694 31469 15691 31469 15695 31469 15695 31470 15691 31470 15696 31470 15695 31471 15696 31471 15697 31471 15697 31472 15696 31472 15698 31472 15698 31473 15696 31473 15699 31473 15698 31474 15699 31474 15707 31474 15707 31475 15699 31475 15709 31475 15709 31476 15699 31476 15701 31476 15709 31477 15701 31477 15710 31477 15710 31478 15701 31478 15700 31478 15700 31479 15701 31479 15693 31479 15700 31480 15693 31480 15716 31480 15716 31481 15693 31481 15715 31481 15715 31482 15693 31482 15702 31482 15715 31483 15702 31483 15712 31483 15705 31484 21207 31484 15703 31484 15703 31485 15704 31485 15705 31485 15705 31486 15704 31486 15694 31486 15705 31487 15694 31487 15706 31487 15694 31488 15695 31488 15706 31488 15706 31489 15695 31489 15697 31489 15706 31490 15697 31490 21143 31490 15697 31491 15698 31491 21143 31491 21143 31492 15698 31492 15707 31492 21143 31493 15707 31493 15708 31493 15708 31494 15707 31494 15709 31494 15708 31495 15709 31495 15711 31495 15709 31496 15710 31496 15711 31496 15711 31497 15710 31497 15700 31497 15711 31498 15700 31498 15714 31498 15712 31499 15713 31499 15715 31499 15715 31500 15713 31500 15714 31500 15715 31501 15714 31501 15716 31501 15716 31502 15714 31502 15700 31502 21196 31503 15718 31503 15717 31503 15717 31504 15718 31504 18031 31504 15717 31505 18031 31505 15719 31505 15719 31506 18031 31506 15721 31506 15719 31507 15721 31507 15720 31507 15720 31508 15721 31508 18028 31508 15720 31509 18028 31509 15727 31509 15727 31510 18028 31510 15722 31510 15727 31511 15722 31511 15728 31511 15728 31512 15722 31512 18027 31512 15728 31513 18027 31513 15723 31513 15723 31514 18027 31514 18039 31514 15723 31515 18039 31515 21190 31515 21190 31516 18039 31516 15724 31516 15725 31517 21196 31517 15717 31517 15725 31518 15717 31518 15729 31518 15729 31519 15717 31519 15719 31519 15729 31520 15719 31520 15730 31520 15730 31521 15719 31521 15731 31521 15731 31522 15719 31522 15720 31522 15731 31523 15720 31523 15732 31523 15732 31524 15720 31524 15726 31524 15726 31525 15720 31525 15727 31525 15726 31526 15727 31526 15733 31526 15733 31527 15727 31527 15738 31527 15738 31528 15727 31528 15728 31528 15738 31529 15728 31529 15737 31529 15737 31530 15728 31530 15723 31530 15737 31531 15723 31531 15735 31531 15735 31532 15723 31532 21190 31532 15735 31533 21190 31533 21189 31533 21118 31534 15725 31534 21117 31534 21117 31535 15725 31535 15729 31535 21117 31536 15729 31536 21116 31536 15729 31537 15730 31537 21116 31537 21116 31538 15730 31538 15731 31538 21116 31539 15731 31539 21115 31539 21115 31540 15731 31540 15732 31540 15732 31541 15726 31541 21115 31541 21115 31542 15726 31542 15733 31542 21115 31543 15733 31543 15734 31543 21189 31544 21113 31544 15735 31544 15735 31545 21113 31545 15736 31545 15735 31546 15736 31546 15737 31546 15737 31547 15736 31547 15734 31547 15737 31548 15734 31548 15738 31548 15738 31549 15734 31549 15733 31549 15745 31550 20056 31550 15739 31550 15739 31551 20056 31551 15740 31551 15739 31552 15740 31552 15747 31552 15747 31553 15740 31553 20051 31553 15747 31554 20051 31554 15748 31554 15748 31555 20051 31555 15741 31555 15748 31556 15741 31556 15742 31556 15742 31557 15741 31557 15743 31557 15742 31558 15743 31558 15750 31558 15750 31559 15743 31559 20057 31559 15750 31560 20057 31560 15744 31560 15744 31561 20057 31561 20050 31561 21179 31562 15745 31562 21158 31562 21158 31563 15745 31563 15739 31563 21158 31564 15739 31564 15746 31564 15746 31565 15739 31565 15747 31565 15746 31566 15747 31566 21162 31566 21162 31567 15747 31567 15748 31567 21162 31568 15748 31568 21163 31568 21163 31569 15748 31569 15742 31569 21163 31570 15742 31570 15749 31570 15749 31571 15742 31571 15750 31571 15749 31572 15750 31572 21165 31572 21165 31573 15750 31573 15744 31573 21155 31574 20067 31574 15751 31574 15751 31575 20067 31575 15752 31575 15751 31576 15752 31576 15753 31576 15753 31577 15752 31577 20049 31577 15753 31578 20049 31578 15754 31578 15754 31579 20049 31579 20408 31579 15754 31580 20408 31580 15755 31580 15755 31581 20408 31581 20407 31581 15755 31582 20407 31582 15762 31582 15762 31583 20407 31583 15756 31583 15762 31584 15756 31584 15757 31584 15757 31585 15756 31585 21149 31585 21148 31586 21155 31586 15758 31586 15758 31587 21155 31587 15751 31587 15758 31588 15751 31588 15759 31588 15759 31589 15751 31589 15753 31589 15759 31590 15753 31590 21142 31590 21142 31591 15753 31591 15754 31591 21142 31592 15754 31592 15760 31592 15760 31593 15754 31593 15755 31593 15760 31594 15755 31594 15761 31594 15761 31595 15755 31595 15762 31595 15761 31596 15762 31596 21138 31596 21138 31597 15762 31597 15757 31597 21133 31598 21135 31598 15770 31598 15770 31599 21135 31599 15763 31599 15770 31600 15763 31600 15772 31600 15772 31601 15763 31601 15764 31601 15772 31602 15764 31602 15765 31602 15765 31603 15764 31603 15767 31603 15765 31604 15767 31604 15766 31604 15766 31605 15767 31605 20155 31605 15766 31606 20155 31606 15776 31606 15776 31607 20155 31607 15768 31607 15776 31608 15768 31608 21126 31608 21126 31609 15768 31609 15769 31609 21112 31610 21133 31610 21114 31610 21114 31611 21133 31611 15770 31611 21114 31612 15770 31612 15771 31612 15771 31613 15770 31613 15772 31613 15771 31614 15772 31614 15773 31614 15773 31615 15772 31615 15765 31615 15773 31616 15765 31616 15774 31616 15774 31617 15765 31617 15766 31617 15774 31618 15766 31618 15775 31618 15775 31619 15766 31619 15776 31619 15775 31620 15776 31620 21122 31620 21122 31621 15776 31621 21126 31621 15777 31622 20053 31622 15779 31622 15779 31623 20053 31623 15778 31623 15779 31624 15778 31624 15780 31624 15780 31625 15778 31625 20060 31625 15780 31626 20060 31626 15782 31626 15782 31627 20060 31627 15781 31627 15782 31628 15781 31628 15783 31628 15783 31629 15781 31629 15784 31629 15783 31630 15784 31630 15819 31630 15819 31631 15784 31631 15785 31631 15819 31632 15785 31632 15786 31632 15786 31633 15785 31633 20058 31633 15786 31634 20058 31634 15787 31634 15787 31635 20058 31635 21103 31635 20082 31636 21054 31636 20075 31636 20075 31637 21054 31637 15788 31637 20075 31638 15788 31638 20076 31638 15788 31639 15831 31639 20076 31639 20076 31640 15831 31640 15832 31640 20076 31641 15832 31641 15790 31641 15790 31642 15832 31642 15789 31642 15789 31643 15834 31643 15790 31643 15790 31644 15834 31644 15795 31644 15790 31645 15795 31645 15791 31645 21092 31646 21091 31646 15792 31646 15792 31647 21091 31647 15793 31647 15792 31648 15793 31648 15794 31648 15794 31649 15793 31649 15791 31649 15794 31650 15791 31650 15836 31650 15836 31651 15791 31651 15795 31651 15796 31652 21089 31652 21088 31652 21088 31653 15847 31653 15796 31653 15796 31654 15847 31654 15797 31654 15796 31655 15797 31655 15798 31655 15797 31656 15849 31656 15798 31656 15798 31657 15849 31657 15799 31657 15798 31658 15799 31658 20412 31658 20412 31659 15799 31659 15800 31659 15800 31660 15851 31660 20412 31660 20412 31661 15851 31661 15801 31661 20412 31662 15801 31662 15802 31662 15801 31663 15803 31663 15802 31663 15802 31664 15803 31664 15806 31664 15802 31665 15806 31665 15805 31665 21079 31666 20045 31666 15804 31666 15804 31667 20045 31667 15805 31667 15804 31668 15805 31668 15853 31668 15853 31669 15805 31669 15806 31669 20998 31670 15807 31670 15864 31670 15864 31671 15807 31671 20151 31671 15864 31672 20151 31672 15808 31672 15808 31673 20151 31673 20150 31673 15808 31674 20150 31674 15862 31674 15862 31675 20150 31675 15810 31675 15862 31676 15810 31676 15809 31676 15809 31677 15810 31677 15811 31677 15809 31678 15811 31678 15812 31678 15812 31679 15811 31679 20143 31679 15812 31680 20143 31680 21076 31680 21076 31681 20143 31681 21077 31681 21062 31682 15813 31682 15818 31682 15818 31683 15813 31683 18017 31683 15818 31684 18017 31684 15814 31684 15814 31685 18017 31685 18015 31685 15814 31686 18015 31686 15820 31686 15820 31687 18015 31687 15815 31687 15820 31688 15815 31688 15821 31688 15821 31689 15815 31689 15816 31689 15821 31690 15816 31690 15822 31690 15822 31691 15816 31691 15817 31691 15822 31692 15817 31692 15823 31692 15823 31693 15817 31693 18025 31693 15823 31694 18025 31694 21063 31694 21063 31695 18025 31695 21065 31695 15787 31696 21062 31696 15786 31696 15786 31697 21062 31697 15818 31697 15786 31698 15818 31698 15819 31698 15819 31699 15818 31699 15814 31699 15819 31700 15814 31700 15783 31700 15783 31701 15814 31701 15820 31701 15783 31702 15820 31702 15782 31702 15782 31703 15820 31703 15821 31703 15782 31704 15821 31704 15780 31704 15780 31705 15821 31705 15822 31705 15780 31706 15822 31706 15779 31706 15779 31707 15822 31707 15823 31707 15779 31708 15823 31708 15777 31708 15777 31709 15823 31709 21063 31709 21059 31710 15824 31710 15825 31710 15825 31711 15824 31711 15826 31711 15825 31712 15826 31712 15827 31712 15827 31713 15826 31713 18003 31713 15827 31714 18003 31714 15833 31714 15833 31715 18003 31715 15828 31715 15833 31716 15828 31716 15835 31716 15835 31717 15828 31717 18002 31717 15835 31718 18002 31718 15837 31718 15837 31719 18002 31719 15829 31719 15837 31720 15829 31720 15838 31720 15838 31721 15829 31721 15830 31721 15838 31722 15830 31722 21046 31722 21046 31723 15830 31723 21055 31723 21054 31724 21059 31724 15825 31724 21054 31725 15825 31725 15788 31725 15788 31726 15825 31726 15827 31726 15788 31727 15827 31727 15831 31727 15831 31728 15827 31728 15832 31728 15832 31729 15827 31729 15833 31729 15832 31730 15833 31730 15789 31730 15789 31731 15833 31731 15834 31731 15834 31732 15833 31732 15835 31732 15834 31733 15835 31733 15795 31733 15795 31734 15835 31734 15836 31734 15836 31735 15835 31735 15837 31735 15836 31736 15837 31736 15794 31736 15794 31737 15837 31737 15838 31737 15794 31738 15838 31738 15792 31738 15792 31739 15838 31739 21046 31739 15792 31740 21046 31740 21092 31740 17995 31741 21042 31741 21041 31741 21041 31742 15854 31742 17995 31742 17995 31743 15854 31743 15839 31743 17995 31744 15839 31744 17996 31744 15839 31745 15840 31745 17996 31745 17996 31746 15840 31746 15841 31746 17996 31747 15841 31747 15842 31747 15842 31748 15841 31748 15843 31748 15843 31749 15844 31749 15842 31749 15842 31750 15844 31750 15852 31750 15842 31751 15852 31751 17999 31751 15852 31752 15845 31752 17999 31752 17999 31753 15845 31753 15850 31753 17999 31754 15850 31754 18000 31754 21034 31755 21033 31755 15848 31755 15848 31756 21033 31756 18000 31756 15848 31757 18000 31757 15846 31757 15846 31758 18000 31758 15850 31758 21088 31759 21034 31759 15847 31759 15847 31760 21034 31760 15848 31760 15847 31761 15848 31761 15797 31761 15797 31762 15848 31762 15846 31762 15797 31763 15846 31763 15849 31763 15849 31764 15846 31764 15850 31764 15849 31765 15850 31765 15799 31765 15799 31766 15850 31766 15845 31766 15799 31767 15845 31767 15800 31767 15800 31768 15845 31768 15852 31768 15800 31769 15852 31769 15851 31769 15851 31770 15852 31770 15844 31770 15851 31771 15844 31771 15801 31771 15801 31772 15844 31772 15843 31772 15801 31773 15843 31773 15803 31773 15803 31774 15843 31774 15841 31774 15803 31775 15841 31775 15806 31775 15806 31776 15841 31776 15840 31776 15806 31777 15840 31777 15853 31777 15853 31778 15840 31778 15839 31778 15853 31779 15839 31779 15804 31779 15804 31780 15839 31780 15854 31780 15804 31781 15854 31781 21079 31781 21079 31782 15854 31782 21041 31782 15860 31783 17983 31783 15861 31783 15861 31784 17983 31784 17984 31784 15861 31785 17984 31785 15855 31785 15855 31786 17984 31786 15856 31786 15855 31787 15856 31787 15863 31787 15863 31788 15856 31788 17986 31788 15863 31789 17986 31789 15857 31789 15857 31790 17986 31790 17987 31790 15857 31791 17987 31791 15858 31791 15858 31792 17987 31792 15859 31792 15858 31793 15859 31793 21018 31793 21018 31794 15859 31794 21019 31794 21076 31795 15860 31795 15812 31795 15812 31796 15860 31796 15861 31796 15812 31797 15861 31797 15809 31797 15809 31798 15861 31798 15855 31798 15809 31799 15855 31799 15862 31799 15862 31800 15855 31800 15863 31800 15862 31801 15863 31801 15808 31801 15808 31802 15863 31802 15857 31802 15808 31803 15857 31803 15864 31803 15864 31804 15857 31804 15858 31804 15864 31805 15858 31805 20998 31805 20998 31806 15858 31806 21018 31806 15865 31807 20996 31807 20995 31807 20995 31808 15866 31808 15865 31808 15865 31809 15866 31809 15886 31809 15865 31810 15886 31810 17973 31810 15886 31811 15883 31811 17973 31811 17973 31812 15883 31812 15867 31812 17973 31813 15867 31813 15868 31813 15868 31814 15867 31814 15882 31814 15882 31815 15880 31815 15868 31815 15868 31816 15880 31816 15869 31816 15868 31817 15869 31817 15870 31817 15869 31818 15877 31818 15870 31818 15870 31819 15877 31819 15871 31819 15870 31820 15871 31820 15872 31820 20973 31821 17975 31821 15873 31821 15873 31822 17975 31822 15872 31822 15873 31823 15872 31823 15876 31823 15876 31824 15872 31824 15871 31824 20974 31825 20973 31825 15888 31825 15888 31826 20973 31826 15873 31826 15888 31827 15873 31827 15874 31827 15874 31828 15873 31828 15876 31828 15874 31829 15876 31829 15875 31829 15875 31830 15876 31830 15871 31830 15875 31831 15871 31831 15889 31831 15889 31832 15871 31832 15877 31832 15889 31833 15877 31833 15878 31833 15878 31834 15877 31834 15869 31834 15878 31835 15869 31835 15879 31835 15879 31836 15869 31836 15880 31836 15879 31837 15880 31837 15892 31837 15892 31838 15880 31838 15882 31838 15892 31839 15882 31839 15881 31839 15881 31840 15882 31840 15867 31840 15881 31841 15867 31841 15893 31841 15893 31842 15867 31842 15883 31842 15893 31843 15883 31843 15884 31843 15884 31844 15883 31844 15886 31844 15884 31845 15886 31845 15885 31845 15885 31846 15886 31846 15866 31846 15885 31847 15866 31847 20965 31847 20965 31848 15866 31848 20995 31848 15887 31849 20900 31849 20974 31849 20974 31850 15888 31850 15887 31850 15887 31851 15888 31851 15874 31851 15887 31852 15874 31852 20902 31852 15874 31853 15875 31853 20902 31853 20902 31854 15875 31854 15889 31854 20902 31855 15889 31855 15890 31855 15890 31856 15889 31856 15878 31856 15878 31857 15879 31857 15890 31857 15890 31858 15879 31858 15892 31858 15890 31859 15892 31859 15891 31859 15892 31860 15881 31860 15891 31860 15891 31861 15881 31861 15893 31861 15891 31862 15893 31862 15894 31862 20965 31863 20905 31863 15885 31863 15885 31864 20905 31864 15894 31864 15885 31865 15894 31865 15884 31865 15884 31866 15894 31866 15893 31866 20959 31867 20963 31867 15895 31867 15895 31868 20963 31868 17954 31868 15895 31869 17954 31869 15896 31869 15896 31870 17954 31870 17953 31870 15896 31871 17953 31871 15901 31871 15901 31872 17953 31872 17951 31872 15901 31873 17951 31873 15897 31873 15897 31874 17951 31874 17967 31874 15897 31875 17967 31875 15898 31875 15898 31876 17967 31876 17966 31876 15898 31877 17966 31877 15899 31877 15899 31878 17966 31878 17964 31878 15899 31879 17964 31879 20953 31879 20953 31880 17964 31880 17963 31880 15900 31881 20959 31881 15913 31881 15913 31882 20959 31882 15895 31882 15913 31883 15895 31883 15911 31883 15911 31884 15895 31884 15896 31884 15911 31885 15896 31885 15909 31885 15909 31886 15896 31886 15901 31886 15909 31887 15901 31887 15908 31887 15908 31888 15901 31888 15897 31888 15908 31889 15897 31889 15902 31889 15902 31890 15897 31890 15898 31890 15902 31891 15898 31891 15903 31891 15903 31892 15898 31892 15899 31892 15903 31893 15899 31893 20952 31893 20952 31894 15899 31894 20953 31894 20952 31895 15904 31895 15903 31895 15903 31896 15904 31896 15905 31896 15903 31897 15905 31897 15902 31897 15902 31898 15905 31898 15906 31898 15902 31899 15906 31899 15908 31899 15908 31900 15906 31900 15907 31900 15908 31901 15907 31901 15909 31901 15909 31902 15907 31902 20875 31902 15909 31903 20875 31903 15911 31903 15911 31904 20875 31904 15910 31904 15911 31905 15910 31905 15913 31905 15913 31906 15910 31906 15912 31906 15913 31907 15912 31907 15900 31907 15900 31908 15912 31908 20943 31908 20942 31909 15915 31909 15914 31909 15914 31910 15915 31910 17940 31910 15914 31911 17940 31911 15922 31911 15922 31912 17940 31912 15916 31912 15922 31913 15916 31913 15917 31913 15917 31914 15916 31914 17938 31914 15917 31915 17938 31915 15923 31915 15923 31916 17938 31916 17936 31916 15923 31917 17936 31917 15924 31917 15924 31918 17936 31918 15918 31918 15924 31919 15918 31919 15926 31919 15926 31920 15918 31920 17949 31920 15926 31921 17949 31921 15919 31921 15919 31922 17949 31922 17948 31922 20927 31923 20942 31923 15914 31923 20927 31924 15914 31924 15920 31924 15920 31925 15914 31925 15922 31925 15920 31926 15922 31926 15921 31926 15921 31927 15922 31927 15928 31927 15928 31928 15922 31928 15917 31928 15928 31929 15917 31929 15929 31929 15929 31930 15917 31930 15930 31930 15930 31931 15917 31931 15923 31931 15930 31932 15923 31932 15932 31932 15932 31933 15923 31933 15935 31933 15935 31934 15923 31934 15924 31934 15935 31935 15924 31935 15925 31935 15925 31936 15924 31936 15926 31936 15925 31937 15926 31937 15934 31937 15934 31938 15926 31938 15919 31938 15934 31939 15919 31939 20920 31939 20928 31940 20927 31940 20854 31940 20854 31941 20927 31941 15920 31941 20854 31942 15920 31942 15927 31942 15920 31943 15921 31943 15927 31943 15927 31944 15921 31944 15928 31944 15927 31945 15928 31945 15931 31945 15931 31946 15928 31946 15929 31946 15929 31947 15930 31947 15931 31947 15931 31948 15930 31948 15932 31948 15931 31949 15932 31949 15933 31949 20920 31950 20850 31950 15934 31950 15934 31951 20850 31951 20849 31951 15934 31952 20849 31952 15925 31952 15925 31953 20849 31953 15933 31953 15925 31954 15933 31954 15935 31954 15935 31955 15933 31955 15932 31955 20919 31956 20168 31956 15936 31956 15936 31957 20168 31957 15937 31957 15936 31958 15937 31958 15938 31958 15938 31959 15937 31959 15940 31959 15938 31960 15940 31960 15939 31960 15939 31961 15940 31961 15941 31961 15939 31962 15941 31962 15942 31962 15942 31963 15941 31963 20172 31963 15942 31964 20172 31964 15945 31964 15945 31965 20172 31965 20039 31965 15945 31966 20039 31966 20907 31966 20907 31967 20039 31967 20184 31967 20912 31968 20919 31968 20904 31968 20904 31969 20919 31969 15936 31969 20904 31970 15936 31970 15943 31970 15943 31971 15936 31971 15938 31971 15943 31972 15938 31972 20903 31972 20903 31973 15938 31973 15939 31973 20903 31974 15939 31974 20901 31974 20901 31975 15939 31975 15942 31975 20901 31976 15942 31976 15944 31976 15944 31977 15942 31977 15945 31977 15944 31978 15945 31978 20899 31978 20899 31979 15945 31979 20907 31979 15951 31980 15946 31980 15947 31980 15947 31981 15946 31981 20205 31981 15947 31982 20205 31982 15953 31982 15953 31983 20205 31983 20206 31983 15953 31984 20206 31984 15948 31984 15948 31985 20206 31985 15949 31985 15948 31986 15949 31986 15956 31986 15956 31987 15949 31987 15950 31987 15956 31988 15950 31988 15957 31988 15957 31989 15950 31989 20178 31989 15957 31990 20178 31990 20886 31990 20886 31991 20178 31991 20179 31991 20877 31992 15951 31992 20876 31992 20876 31993 15951 31993 15947 31993 20876 31994 15947 31994 15952 31994 15952 31995 15947 31995 15953 31995 15952 31996 15953 31996 15954 31996 15954 31997 15953 31997 15948 31997 15954 31998 15948 31998 15955 31998 15955 31999 15948 31999 15956 31999 15955 32000 15956 32000 20874 32000 20874 32001 15956 32001 15957 32001 20874 32002 15957 32002 20882 32002 20882 32003 15957 32003 20886 32003 20296 32004 20862 32004 15959 32004 15959 32005 20862 32005 15958 32005 15959 32006 15958 32006 20297 32006 15958 32007 15972 32007 20297 32007 20297 32008 15972 32008 15961 32008 20297 32009 15961 32009 15960 32009 15960 32010 15961 32010 15962 32010 15962 32011 15969 32011 15960 32011 15960 32012 15969 32012 15968 32012 15960 32013 15968 32013 15966 32013 20872 32014 15963 32014 15964 32014 15964 32015 15963 32015 20290 32015 15964 32016 20290 32016 15965 32016 15965 32017 20290 32017 15966 32017 15965 32018 15966 32018 15967 32018 15967 32019 15966 32019 15968 32019 20867 32020 20872 32020 15964 32020 20867 32021 15964 32021 20848 32021 20848 32022 15964 32022 15965 32022 20848 32023 15965 32023 20847 32023 20847 32024 15965 32024 15967 32024 20847 32025 15967 32025 15970 32025 15967 32026 15968 32026 15970 32026 15970 32027 15968 32027 15969 32027 15970 32028 15969 32028 20853 32028 15969 32029 15962 32029 20853 32029 20853 32030 15962 32030 15961 32030 20853 32031 15961 32031 15971 32031 15961 32032 15972 32032 15971 32032 15971 32033 15972 32033 15958 32033 15971 32034 15958 32034 15973 32034 15973 32035 15958 32035 20862 32035 15973 32036 20862 32036 20855 32036 16014 32037 20185 32037 16012 32037 16012 32038 20185 32038 15974 32038 16012 32039 15974 32039 15975 32039 15975 32040 15974 32040 15976 32040 15975 32041 15976 32041 16009 32041 16009 32042 15976 32042 20183 32042 16009 32043 20183 32043 15977 32043 15977 32044 20183 32044 15978 32044 15977 32045 15978 32045 16008 32045 16008 32046 15978 32046 20186 32046 16008 32047 20186 32047 20806 32047 20806 32048 20186 32048 15979 32048 20195 32049 20836 32049 20785 32049 20785 32050 16017 32050 20195 32050 20195 32051 16017 32051 16018 32051 20195 32052 16018 32052 15980 32052 16018 32053 16020 32053 15980 32053 15980 32054 16020 32054 15981 32054 15980 32055 15981 32055 20196 32055 15981 32056 16021 32056 20196 32056 20196 32057 16021 32057 15982 32057 20196 32058 15982 32058 15983 32058 15983 32059 15982 32059 15984 32059 15983 32060 15984 32060 15985 32060 15984 32061 16025 32061 15985 32061 15985 32062 16025 32062 15986 32062 15985 32063 15986 32063 20201 32063 20829 32064 15987 32064 16028 32064 16028 32065 15987 32065 20201 32065 16028 32066 20201 32066 16027 32066 16027 32067 20201 32067 15986 32067 20765 32068 20828 32068 16043 32068 16043 32069 20828 32069 15988 32069 16043 32070 15988 32070 16042 32070 16042 32071 15988 32071 15989 32071 16042 32072 15989 32072 16041 32072 16041 32073 15989 32073 15990 32073 16041 32074 15990 32074 16039 32074 16039 32075 15990 32075 20180 32075 16039 32076 20180 32076 15991 32076 15991 32077 20180 32077 15992 32077 15991 32078 15992 32078 16037 32078 16037 32079 15992 32079 20177 32079 16037 32080 20177 32080 15993 32080 15993 32081 20177 32081 20176 32081 15994 32082 20821 32082 16061 32082 16061 32083 20821 32083 15995 32083 16061 32084 15995 32084 16059 32084 16059 32085 15995 32085 20138 32085 16059 32086 20138 32086 15996 32086 15996 32087 20138 32087 15997 32087 15996 32088 15997 32088 15998 32088 15998 32089 15997 32089 15999 32089 15998 32090 15999 32090 16000 32090 16000 32091 15999 32091 20135 32091 16000 32092 20135 32092 16056 32092 16056 32093 20135 32093 20134 32093 16056 32094 20134 32094 16001 32094 16001 32095 20134 32095 20814 32095 16007 32096 20808 32096 16002 32096 16002 32097 20808 32097 17926 32097 16002 32098 17926 32098 16003 32098 16003 32099 17926 32099 16004 32099 16003 32100 16004 32100 16010 32100 16010 32101 16004 32101 16005 32101 16010 32102 16005 32102 16011 32102 16011 32103 16005 32103 17924 32103 16011 32104 17924 32104 16013 32104 16013 32105 17924 32105 17922 32105 16013 32106 17922 32106 16006 32106 16006 32107 17922 32107 20812 32107 20806 32108 16007 32108 16008 32108 16008 32109 16007 32109 16002 32109 16008 32110 16002 32110 15977 32110 15977 32111 16002 32111 16003 32111 15977 32112 16003 32112 16009 32112 16009 32113 16003 32113 16010 32113 16009 32114 16010 32114 15975 32114 15975 32115 16010 32115 16011 32115 15975 32116 16011 32116 16012 32116 16012 32117 16011 32117 16013 32117 16012 32118 16013 32118 16014 32118 16014 32119 16013 32119 16006 32119 16015 32120 17915 32120 16019 32120 16019 32121 17915 32121 17914 32121 16019 32122 17914 32122 16022 32122 16022 32123 17914 32123 17913 32123 16022 32124 17913 32124 16023 32124 16023 32125 17913 32125 17911 32125 16023 32126 17911 32126 16024 32126 16024 32127 17911 32127 16016 32127 16024 32128 16016 32128 16026 32128 16026 32129 16016 32129 17909 32129 16026 32130 17909 32130 16029 32130 16029 32131 17909 32131 17905 32131 20785 32132 16015 32132 16017 32132 16017 32133 16015 32133 16019 32133 16017 32134 16019 32134 16018 32134 16018 32135 16019 32135 16020 32135 16020 32136 16019 32136 16022 32136 16020 32137 16022 32137 15981 32137 15981 32138 16022 32138 16021 32138 16021 32139 16022 32139 16023 32139 16021 32140 16023 32140 15982 32140 15982 32141 16023 32141 15984 32141 15984 32142 16023 32142 16024 32142 15984 32143 16024 32143 16025 32143 16025 32144 16024 32144 15986 32144 15986 32145 16024 32145 16026 32145 15986 32146 16026 32146 16027 32146 16027 32147 16026 32147 16028 32147 16028 32148 16026 32148 16029 32148 16028 32149 16029 32149 20829 32149 20776 32150 16030 32150 16038 32150 16038 32151 16030 32151 16031 32151 16038 32152 16031 32152 16032 32152 16032 32153 16031 32153 17893 32153 16032 32154 17893 32154 16040 32154 16040 32155 17893 32155 17892 32155 16040 32156 17892 32156 16033 32156 16033 32157 17892 32157 17891 32157 16033 32158 17891 32158 16034 32158 16034 32159 17891 32159 16035 32159 16034 32160 16035 32160 16044 32160 16044 32161 16035 32161 16036 32161 16044 32162 16036 32162 16045 32162 16045 32163 16036 32163 17900 32163 15993 32164 20776 32164 16037 32164 16037 32165 20776 32165 16038 32165 16037 32166 16038 32166 15991 32166 15991 32167 16038 32167 16032 32167 15991 32168 16032 32168 16039 32168 16039 32169 16032 32169 16040 32169 16039 32170 16040 32170 16041 32170 16041 32171 16040 32171 16033 32171 16041 32172 16033 32172 16042 32172 16042 32173 16033 32173 16034 32173 16042 32174 16034 32174 16043 32174 16043 32175 16034 32175 16044 32175 16043 32176 16044 32176 20765 32176 20765 32177 16044 32177 16045 32177 20761 32178 20760 32178 16046 32178 16046 32179 20760 32179 16060 32179 16046 32180 16060 32180 16047 32180 16060 32181 16048 32181 16047 32181 16047 32182 16048 32182 16049 32182 16047 32183 16049 32183 17887 32183 17887 32184 16049 32184 16058 32184 16058 32185 16050 32185 17887 32185 17887 32186 16050 32186 16055 32186 17887 32187 16055 32187 16053 32187 20751 32188 17890 32188 16051 32188 16051 32189 17890 32189 16052 32189 16051 32190 16052 32190 16054 32190 16054 32191 16052 32191 16053 32191 16054 32192 16053 32192 16057 32192 16057 32193 16053 32193 16055 32193 16001 32194 20751 32194 16051 32194 16001 32195 16051 32195 16056 32195 16056 32196 16051 32196 16054 32196 16056 32197 16054 32197 16000 32197 16000 32198 16054 32198 16057 32198 16000 32199 16057 32199 15998 32199 16057 32200 16055 32200 15998 32200 15998 32201 16055 32201 16050 32201 15998 32202 16050 32202 15996 32202 16050 32203 16058 32203 15996 32203 15996 32204 16058 32204 16049 32204 15996 32205 16049 32205 16059 32205 16049 32206 16048 32206 16059 32206 16059 32207 16048 32207 16060 32207 16059 32208 16060 32208 16061 32208 16061 32209 16060 32209 20760 32209 16061 32210 20760 32210 15994 32210 16068 32211 20743 32211 16062 32211 16062 32212 20743 32212 16063 32212 16062 32213 16063 32213 16069 32213 16069 32214 16063 32214 17787 32214 16069 32215 17787 32215 16064 32215 16064 32216 17787 32216 17785 32216 16064 32217 17785 32217 16065 32217 16065 32218 17785 32218 17784 32218 16065 32219 17784 32219 16066 32219 16066 32220 17784 32220 17783 32220 16066 32221 17783 32221 16067 32221 16067 32222 17783 32222 17780 32222 20738 32223 16068 32223 16080 32223 16080 32224 16068 32224 16062 32224 16080 32225 16062 32225 16077 32225 16077 32226 16062 32226 16069 32226 16077 32227 16069 32227 16070 32227 16070 32228 16069 32228 16064 32228 16070 32229 16064 32229 16074 32229 16074 32230 16064 32230 16065 32230 16074 32231 16065 32231 16071 32231 16071 32232 16065 32232 16066 32232 16071 32233 16066 32233 16072 32233 16072 32234 16066 32234 16067 32234 16072 32235 16073 32235 16071 32235 16071 32236 16073 32236 16075 32236 16071 32237 16075 32237 16074 32237 16074 32238 16075 32238 16076 32238 16074 32239 16076 32239 16070 32239 16070 32240 16076 32240 16078 32240 16070 32241 16078 32241 16077 32241 16077 32242 16078 32242 16079 32242 16077 32243 16079 32243 16080 32243 16080 32244 16079 32244 16081 32244 16080 32245 16081 32245 20738 32245 20738 32246 16081 32246 16082 32246 17806 32247 17803 32247 20718 32247 20718 32248 16083 32248 17806 32248 17806 32249 16083 32249 16100 32249 17806 32250 16100 32250 17807 32250 16100 32251 16098 32251 17807 32251 17807 32252 16098 32252 16097 32252 17807 32253 16097 32253 17791 32253 17791 32254 16097 32254 16084 32254 16084 32255 16094 32255 17791 32255 17791 32256 16094 32256 16085 32256 17791 32257 16085 32257 17792 32257 16085 32258 16091 32258 17792 32258 17792 32259 16091 32259 16086 32259 17792 32260 16086 32260 17794 32260 20727 32261 17796 32261 16089 32261 16089 32262 17796 32262 17794 32262 16089 32263 17794 32263 16087 32263 16087 32264 17794 32264 16086 32264 20722 32265 20727 32265 16088 32265 16088 32266 20727 32266 16089 32266 16088 32267 16089 32267 16102 32267 16102 32268 16089 32268 16087 32268 16102 32269 16087 32269 16103 32269 16103 32270 16087 32270 16086 32270 16103 32271 16086 32271 16090 32271 16090 32272 16086 32272 16091 32272 16090 32273 16091 32273 16092 32273 16092 32274 16091 32274 16085 32274 16092 32275 16085 32275 16093 32275 16093 32276 16085 32276 16094 32276 16093 32277 16094 32277 16095 32277 16095 32278 16094 32278 16084 32278 16095 32279 16084 32279 16096 32279 16096 32280 16084 32280 16097 32280 16096 32281 16097 32281 16107 32281 16107 32282 16097 32282 16098 32282 16107 32283 16098 32283 16099 32283 16099 32284 16098 32284 16100 32284 16099 32285 16100 32285 16101 32285 16101 32286 16100 32286 16083 32286 16101 32287 16083 32287 20716 32287 20716 32288 16083 32288 20718 32288 20646 32289 20708 32289 20722 32289 20722 32290 16088 32290 20646 32290 20646 32291 16088 32291 16102 32291 20646 32292 16102 32292 16104 32292 16102 32293 16103 32293 16104 32293 16104 32294 16103 32294 16090 32294 16104 32295 16090 32295 16105 32295 16105 32296 16090 32296 16092 32296 16092 32297 16093 32297 16105 32297 16105 32298 16093 32298 16095 32298 16105 32299 16095 32299 20643 32299 16095 32300 16096 32300 20643 32300 20643 32301 16096 32301 16107 32301 20643 32302 16107 32302 16106 32302 20716 32303 20717 32303 16101 32303 16101 32304 20717 32304 16106 32304 16101 32305 16106 32305 16099 32305 16099 32306 16106 32306 16107 32306 17876 32307 17875 32307 20696 32307 20696 32308 16108 32308 17876 32308 17876 32309 16108 32309 16109 32309 17876 32310 16109 32310 17877 32310 16109 32311 16110 32311 17877 32311 17877 32312 16110 32312 16111 32312 17877 32313 16111 32313 17865 32313 16111 32314 16124 32314 17865 32314 17865 32315 16124 32315 16112 32315 17865 32316 16112 32316 17866 32316 17866 32317 16112 32317 16114 32317 17866 32318 16114 32318 16113 32318 16114 32319 16115 32319 16113 32319 16113 32320 16115 32320 16119 32320 16113 32321 16119 32321 17867 32321 20707 32322 16117 32322 16116 32322 16116 32323 16117 32323 17867 32323 16116 32324 17867 32324 16118 32324 16118 32325 17867 32325 16119 32325 20696 32326 16120 32326 16108 32326 16108 32327 16120 32327 16121 32327 16108 32328 16121 32328 16109 32328 16109 32329 16121 32329 16122 32329 16109 32330 16122 32330 16110 32330 16110 32331 16122 32331 16134 32331 16110 32332 16134 32332 16111 32332 16111 32333 16134 32333 16123 32333 16111 32334 16123 32334 16124 32334 16124 32335 16123 32335 16125 32335 16124 32336 16125 32336 16112 32336 16112 32337 16125 32337 16126 32337 16112 32338 16126 32338 16114 32338 16114 32339 16126 32339 16127 32339 16114 32340 16127 32340 16115 32340 16115 32341 16127 32341 16128 32341 16115 32342 16128 32342 16119 32342 16119 32343 16128 32343 16132 32343 16119 32344 16132 32344 16118 32344 16118 32345 16132 32345 16131 32345 16118 32346 16131 32346 16116 32346 16116 32347 16131 32347 16129 32347 16116 32348 16129 32348 20707 32348 20707 32349 16129 32349 20701 32349 16130 32350 20609 32350 20701 32350 20701 32351 16129 32351 16130 32351 16130 32352 16129 32352 16131 32352 16130 32353 16131 32353 20607 32353 16131 32354 16132 32354 20607 32354 20607 32355 16132 32355 16128 32355 20607 32356 16128 32356 16133 32356 16128 32357 16127 32357 16133 32357 16133 32358 16127 32358 16126 32358 16133 32359 16126 32359 20616 32359 20616 32360 16126 32360 16125 32360 20616 32361 16125 32361 20615 32361 16125 32362 16123 32362 20615 32362 20615 32363 16123 32363 16134 32363 20615 32364 16134 32364 20614 32364 16120 32365 16135 32365 16121 32365 16121 32366 16135 32366 20614 32366 16121 32367 20614 32367 16122 32367 16122 32368 20614 32368 16134 32368 16137 32369 16136 32369 16156 32369 16156 32370 16138 32370 16137 32370 16137 32371 16138 32371 16157 32371 16137 32372 16157 32372 16140 32372 16157 32373 16139 32373 16140 32373 16140 32374 16139 32374 16155 32374 16140 32375 16155 32375 16142 32375 16155 32376 16141 32376 16142 32376 16142 32377 16141 32377 16143 32377 16142 32378 16143 32378 16145 32378 16145 32379 16143 32379 16144 32379 16145 32380 16144 32380 16146 32380 16144 32381 16153 32381 16146 32381 16146 32382 16153 32382 16152 32382 16146 32383 16152 32383 20084 32383 16149 32384 20687 32384 16147 32384 16147 32385 20687 32385 20084 32385 16147 32386 20084 32386 16148 32386 16148 32387 20084 32387 16152 32387 16149 32388 16147 32388 16150 32388 16150 32389 16147 32389 16151 32389 16147 32390 16148 32390 16151 32390 16151 32391 16148 32391 16152 32391 16151 32392 16152 32392 16154 32392 16152 32393 16153 32393 16154 32393 16154 32394 16153 32394 16144 32394 16154 32395 16144 32395 20672 32395 16144 32396 16143 32396 20672 32396 20672 32397 16143 32397 16141 32397 20672 32398 16141 32398 20673 32398 16141 32399 16155 32399 20673 32399 20673 32400 16155 32400 16139 32400 20673 32401 16139 32401 16158 32401 16156 32402 20676 32402 16138 32402 16138 32403 20676 32403 16158 32403 16138 32404 16158 32404 16157 32404 16157 32405 16158 32405 16139 32405 16166 32406 16159 32406 16167 32406 16167 32407 16159 32407 16160 32407 16167 32408 16160 32408 16161 32408 16161 32409 16160 32409 16162 32409 16161 32410 16162 32410 16168 32410 16168 32411 16162 32411 20397 32411 16168 32412 20397 32412 16163 32412 16163 32413 20397 32413 16164 32413 16163 32414 16164 32414 16165 32414 16165 32415 16164 32415 20042 32415 16165 32416 20042 32416 16169 32416 16169 32417 20042 32417 20661 32417 20659 32418 16166 32418 20642 32418 20642 32419 16166 32419 16167 32419 20642 32420 16167 32420 20644 32420 20644 32421 16167 32421 16161 32421 20644 32422 16161 32422 20645 32422 20645 32423 16161 32423 16168 32423 20645 32424 16168 32424 20647 32424 20647 32425 16168 32425 16163 32425 20647 32426 16163 32426 20648 32426 20648 32427 16163 32427 16165 32427 20648 32428 16165 32428 20651 32428 20651 32429 16165 32429 16169 32429 20117 32430 16185 32430 20118 32430 20118 32431 16185 32431 16183 32431 20118 32432 16183 32432 16170 32432 16183 32433 16182 32433 16170 32433 16170 32434 16182 32434 16181 32434 16170 32435 16181 32435 20119 32435 20119 32436 16181 32436 16180 32436 16180 32437 16171 32437 20119 32437 20119 32438 16171 32438 16172 32438 20119 32439 16172 32439 20120 32439 20630 32440 20629 32440 16173 32440 16173 32441 20629 32441 16174 32441 16173 32442 16174 32442 16176 32442 16176 32443 16174 32443 20120 32443 16176 32444 20120 32444 16177 32444 16177 32445 20120 32445 16172 32445 20627 32446 20630 32446 16173 32446 20627 32447 16173 32447 16175 32447 16175 32448 16173 32448 16176 32448 16175 32449 16176 32449 20617 32449 20617 32450 16176 32450 16177 32450 20617 32451 16177 32451 16178 32451 16177 32452 16172 32452 16178 32452 16178 32453 16172 32453 16171 32453 16178 32454 16171 32454 16179 32454 16171 32455 16180 32455 16179 32455 16179 32456 16180 32456 16181 32456 16179 32457 16181 32457 20608 32457 16181 32458 16182 32458 20608 32458 20608 32459 16182 32459 16183 32459 20608 32460 16183 32460 16184 32460 16184 32461 16183 32461 16185 32461 16184 32462 16185 32462 16186 32462 22930 32463 20606 32463 16187 32463 16187 32464 20606 32464 16188 32464 16187 32465 16188 32465 16189 32465 16189 32466 16188 32466 20357 32466 16189 32467 20357 32467 16190 32467 16190 32468 20357 32468 16191 32468 16190 32469 16191 32469 16192 32469 16192 32470 16191 32470 20097 32470 16192 32471 20097 32471 16193 32471 16193 32472 20097 32472 20099 32472 16193 32473 20099 32473 16194 32473 16194 32474 20099 32474 20602 32474 22937 32475 20601 32475 16195 32475 16195 32476 20601 32476 16196 32476 16195 32477 16196 32477 22936 32477 22936 32478 16196 32478 20272 32478 22936 32479 20272 32479 22934 32479 22934 32480 20272 32480 16197 32480 22934 32481 16197 32481 22935 32481 22935 32482 16197 32482 16198 32482 22935 32483 16198 32483 22932 32483 22932 32484 16198 32484 20276 32484 22932 32485 20276 32485 16199 32485 16199 32486 20276 32486 20592 32486 20591 32487 20283 32487 22939 32487 22939 32488 20283 32488 20281 32488 22939 32489 20281 32489 22940 32489 22940 32490 20281 32490 16201 32490 22940 32491 16201 32491 16200 32491 16200 32492 16201 32492 16202 32492 16200 32493 16202 32493 16203 32493 16203 32494 16202 32494 20280 32494 16203 32495 20280 32495 16204 32495 16204 32496 20280 32496 20278 32496 16204 32497 20278 32497 16205 32497 16205 32498 20278 32498 20028 32498 22947 32499 20253 32499 22941 32499 22941 32500 20253 32500 20252 32500 22941 32501 20252 32501 22945 32501 22945 32502 20252 32502 16207 32502 22945 32503 16207 32503 16206 32503 16206 32504 16207 32504 16208 32504 16206 32505 16208 32505 22942 32505 22942 32506 16208 32506 16209 32506 22942 32507 16209 32507 22943 32507 22943 32508 16209 32508 20248 32508 22943 32509 20248 32509 22944 32509 22944 32510 20248 32510 16210 32510 22944 32511 16210 32511 20573 32511 20573 32512 16210 32512 20250 32512 20572 32513 20259 32513 16211 32513 16211 32514 20259 32514 20258 32514 16211 32515 20258 32515 16212 32515 16212 32516 20258 32516 20371 32516 16212 32517 20371 32517 22950 32517 22950 32518 20371 32518 16214 32518 22950 32519 16214 32519 16213 32519 16213 32520 16214 32520 20254 32520 16213 32521 20254 32521 22951 32521 22951 32522 20254 32522 16215 32522 22951 32523 16215 32523 16216 32523 16216 32524 16215 32524 20257 32524 20562 32525 20563 32525 16217 32525 16217 32526 20563 32526 16218 32526 16217 32527 16218 32527 16219 32527 16219 32528 16218 32528 20330 32528 16219 32529 20330 32529 16220 32529 16220 32530 20330 32530 16221 32530 16220 32531 16221 32531 16222 32531 16222 32532 16221 32532 16224 32532 16222 32533 16224 32533 16223 32533 16223 32534 16224 32534 20329 32534 16223 32535 20329 32535 22955 32535 22955 32536 20329 32536 16225 32536 22955 32537 16225 32537 22954 32537 22954 32538 16225 32538 20555 32538 20554 32539 20322 32539 16226 32539 16226 32540 20322 32540 16227 32540 16226 32541 16227 32541 16228 32541 16228 32542 16227 32542 16229 32542 16228 32543 16229 32543 16230 32543 16230 32544 16229 32544 20318 32544 16230 32545 20318 32545 22963 32545 22963 32546 20318 32546 20327 32546 22963 32547 20327 32547 16232 32547 16232 32548 20327 32548 16231 32548 16232 32549 16231 32549 22962 32549 22962 32550 16231 32550 20320 32550 22962 32551 20320 32551 22960 32551 22960 32552 20320 32552 16233 32552 20551 32553 16234 32553 22968 32553 22968 32554 16234 32554 20313 32554 22968 32555 20313 32555 16235 32555 16235 32556 20313 32556 20312 32556 16235 32557 20312 32557 16236 32557 16236 32558 20312 32558 20305 32558 16236 32559 20305 32559 16238 32559 16238 32560 20305 32560 16237 32560 16238 32561 16237 32561 22965 32561 22965 32562 16237 32562 16239 32562 22965 32563 16239 32563 22966 32563 22966 32564 16239 32564 20546 32564 22971 32565 16240 32565 16241 32565 16241 32566 16240 32566 16243 32566 16241 32567 16243 32567 16242 32567 16242 32568 16243 32568 16244 32568 16242 32569 16244 32569 22970 32569 22970 32570 16244 32570 16245 32570 22970 32571 16245 32571 16246 32571 16246 32572 16245 32572 20194 32572 16246 32573 20194 32573 16247 32573 16247 32574 20194 32574 16248 32574 16247 32575 16248 32575 20537 32575 20537 32576 16248 32576 20198 32576 16249 32577 20536 32577 22976 32577 22976 32578 20536 32578 16250 32578 22976 32579 16250 32579 16252 32579 16252 32580 16250 32580 16251 32580 16252 32581 16251 32581 16253 32581 16253 32582 16251 32582 16254 32582 16253 32583 16254 32583 16256 32583 16256 32584 16254 32584 16255 32584 16256 32585 16255 32585 22974 32585 22974 32586 16255 32586 20027 32586 22974 32587 20027 32587 16257 32587 16257 32588 20027 32588 16258 32588 20528 32589 20269 32589 16302 32589 16302 32590 20269 32590 16260 32590 16302 32591 16260 32591 16259 32591 16259 32592 16260 32592 16261 32592 16259 32593 16261 32593 16301 32593 16301 32594 16261 32594 16262 32594 16301 32595 16262 32595 16300 32595 16300 32596 16262 32596 20348 32596 16300 32597 20348 32597 16263 32597 16263 32598 20348 32598 20267 32598 16263 32599 20267 32599 16265 32599 16265 32600 20267 32600 16264 32600 16265 32601 16264 32601 20489 32601 20489 32602 16264 32602 20522 32602 16266 32603 20106 32603 16267 32603 16267 32604 20106 32604 16268 32604 16267 32605 16268 32605 16269 32605 16269 32606 16268 32606 20365 32606 16269 32607 20365 32607 16310 32607 16310 32608 20365 32608 20105 32608 16310 32609 20105 32609 16270 32609 16270 32610 20105 32610 16271 32610 16270 32611 16271 32611 16307 32611 16307 32612 16271 32612 20090 32612 16307 32613 20090 32613 20480 32613 20480 32614 20090 32614 20520 32614 16272 32615 20285 32615 20459 32615 20459 32616 16273 32616 16272 32616 16272 32617 16273 32617 16327 32617 16272 32618 16327 32618 16274 32618 16327 32619 16328 32619 16274 32619 16274 32620 16328 32620 16329 32620 16274 32621 16329 32621 16275 32621 16275 32622 16329 32622 16330 32622 16330 32623 16332 32623 16275 32623 16275 32624 16332 32624 16276 32624 16275 32625 16276 32625 16277 32625 16276 32626 16334 32626 16277 32626 16277 32627 16334 32627 16278 32627 16277 32628 16278 32628 16279 32628 20453 32629 16281 32629 16280 32629 16280 32630 16281 32630 16279 32630 16280 32631 16279 32631 16336 32631 16336 32632 16279 32632 16278 32632 16282 32633 16283 32633 20116 32633 20116 32634 16283 32634 16284 32634 20116 32635 16284 32635 16286 32635 16284 32636 16285 32636 16286 32636 16286 32637 16285 32637 16347 32637 16286 32638 16347 32638 16287 32638 16287 32639 16347 32639 16348 32639 16348 32640 16349 32640 16287 32640 16287 32641 16349 32641 16351 32641 16287 32642 16351 32642 20122 32642 20496 32643 20495 32643 16288 32643 16288 32644 20495 32644 16289 32644 16288 32645 16289 32645 16354 32645 16354 32646 16289 32646 20122 32646 16354 32647 20122 32647 16290 32647 16290 32648 20122 32648 16351 32648 16298 32649 17813 32649 16299 32649 16299 32650 17813 32650 17811 32650 16299 32651 17811 32651 16291 32651 16291 32652 17811 32652 17810 32652 16291 32653 17810 32653 16292 32653 16292 32654 17810 32654 17808 32654 16292 32655 17808 32655 16293 32655 16293 32656 17808 32656 16295 32656 16293 32657 16295 32657 16294 32657 16294 32658 16295 32658 16296 32658 16294 32659 16296 32659 16297 32659 16297 32660 16296 32660 17819 32660 16297 32661 17819 32661 20490 32661 20490 32662 17819 32662 17818 32662 20489 32663 16298 32663 16265 32663 16265 32664 16298 32664 16299 32664 16265 32665 16299 32665 16263 32665 16263 32666 16299 32666 16291 32666 16263 32667 16291 32667 16300 32667 16300 32668 16291 32668 16292 32668 16300 32669 16292 32669 16301 32669 16301 32670 16292 32670 16293 32670 16301 32671 16293 32671 16259 32671 16259 32672 16293 32672 16294 32672 16259 32673 16294 32673 16302 32673 16302 32674 16294 32674 16297 32674 16302 32675 16297 32675 20528 32675 20528 32676 16297 32676 20490 32676 16308 32677 16304 32677 16303 32677 16303 32678 16304 32678 17836 32678 16303 32679 17836 32679 16309 32679 16309 32680 17836 32680 16305 32680 16309 32681 16305 32681 16311 32681 16311 32682 16305 32682 16306 32682 16311 32683 16306 32683 16312 32683 16312 32684 16306 32684 17834 32684 16312 32685 17834 32685 16313 32685 16313 32686 17834 32686 17831 32686 16313 32687 17831 32687 16314 32687 16314 32688 17831 32688 17830 32688 20480 32689 16308 32689 16307 32689 16307 32690 16308 32690 16303 32690 16307 32691 16303 32691 16270 32691 16270 32692 16303 32692 16309 32692 16270 32693 16309 32693 16310 32693 16310 32694 16309 32694 16311 32694 16310 32695 16311 32695 16269 32695 16269 32696 16311 32696 16312 32696 16269 32697 16312 32697 16267 32697 16267 32698 16312 32698 16313 32698 16267 32699 16313 32699 16266 32699 16266 32700 16313 32700 16314 32700 17841 32701 17843 32701 16315 32701 16315 32702 16338 32702 17841 32702 17841 32703 16338 32703 16316 32703 17841 32704 16316 32704 16317 32704 16316 32705 16337 32705 16317 32705 16317 32706 16337 32706 16318 32706 16317 32707 16318 32707 17839 32707 17839 32708 16318 32708 16335 32708 16335 32709 16319 32709 17839 32709 17839 32710 16319 32710 16333 32710 17839 32711 16333 32711 16320 32711 16333 32712 16331 32712 16320 32712 16320 32713 16331 32713 16321 32713 16320 32714 16321 32714 16324 32714 16322 32715 16323 32715 16326 32715 16326 32716 16323 32716 16324 32716 16326 32717 16324 32717 16325 32717 16325 32718 16324 32718 16321 32718 20459 32719 16322 32719 16273 32719 16273 32720 16322 32720 16326 32720 16273 32721 16326 32721 16327 32721 16327 32722 16326 32722 16325 32722 16327 32723 16325 32723 16328 32723 16328 32724 16325 32724 16321 32724 16328 32725 16321 32725 16329 32725 16329 32726 16321 32726 16331 32726 16329 32727 16331 32727 16330 32727 16330 32728 16331 32728 16333 32728 16330 32729 16333 32729 16332 32729 16332 32730 16333 32730 16319 32730 16332 32731 16319 32731 16276 32731 16276 32732 16319 32732 16335 32732 16276 32733 16335 32733 16334 32733 16334 32734 16335 32734 16318 32734 16334 32735 16318 32735 16278 32735 16278 32736 16318 32736 16337 32736 16278 32737 16337 32737 16336 32737 16336 32738 16337 32738 16316 32738 16336 32739 16316 32739 16280 32739 16280 32740 16316 32740 16338 32740 16280 32741 16338 32741 20453 32741 20453 32742 16338 32742 16315 32742 20452 32743 17854 32743 16339 32743 16339 32744 17854 32744 16340 32744 16339 32745 16340 32745 16346 32745 16346 32746 16340 32746 17852 32746 16346 32747 17852 32747 16350 32747 16350 32748 17852 32748 16341 32748 16350 32749 16341 32749 16352 32749 16352 32750 16341 32750 16342 32750 16352 32751 16342 32751 16353 32751 16353 32752 16342 32752 16343 32752 16353 32753 16343 32753 16344 32753 16344 32754 16343 32754 17862 32754 16344 32755 17862 32755 16345 32755 16345 32756 17862 32756 17860 32756 16283 32757 20452 32757 16339 32757 16283 32758 16339 32758 16284 32758 16284 32759 16339 32759 16346 32759 16284 32760 16346 32760 16285 32760 16285 32761 16346 32761 16347 32761 16347 32762 16346 32762 16350 32762 16347 32763 16350 32763 16348 32763 16348 32764 16350 32764 16349 32764 16349 32765 16350 32765 16352 32765 16349 32766 16352 32766 16351 32766 16351 32767 16352 32767 16290 32767 16290 32768 16352 32768 16353 32768 16290 32769 16353 32769 16354 32769 16354 32770 16353 32770 16344 32770 16354 32771 16344 32771 16288 32771 16288 32772 16344 32772 16345 32772 16288 32773 16345 32773 20496 32773 22915 32774 20429 32774 20413 32774 22915 32775 20413 32775 14867 32775 14867 32776 20413 32776 16355 32776 14867 32777 16355 32777 16356 32777 16356 32778 16355 32778 16357 32778 16356 32779 16357 32779 16359 32779 16359 32780 16357 32780 16358 32780 16359 32781 16358 32781 14868 32781 14868 32782 16358 32782 16361 32782 14868 32783 16361 32783 16360 32783 16360 32784 16361 32784 16362 32784 16360 32785 16362 32785 14870 32785 14870 32786 16362 32786 19991 32786 14870 32787 19991 32787 19992 32787 19990 32788 14894 32788 16363 32788 19990 32789 16363 32789 15389 32789 15389 32790 16363 32790 16364 32790 15389 32791 16364 32791 16365 32791 16365 32792 16364 32792 14889 32792 16365 32793 14889 32793 15391 32793 15391 32794 14889 32794 16366 32794 15391 32795 16366 32795 16367 32795 16367 32796 16366 32796 16368 32796 16367 32797 16368 32797 15392 32797 15392 32798 16368 32798 14887 32798 15392 32799 14887 32799 15394 32799 15394 32800 14887 32800 16369 32800 15394 32801 16369 32801 15396 32801 15396 32802 16369 32802 16370 32802 15396 32803 16370 32803 15398 32803 15398 32804 16370 32804 14884 32804 15398 32805 14884 32805 16371 32805 16371 32806 14884 32806 16372 32806 16371 32807 16372 32807 16373 32807 16373 32808 16372 32808 16375 32808 16373 32809 16375 32809 16374 32809 16374 32810 16375 32810 14882 32810 16374 32811 14882 32811 15402 32811 15402 32812 14882 32812 14880 32812 15402 32813 14880 32813 16377 32813 16377 32814 14880 32814 16376 32814 16377 32815 16376 32815 16378 32815 16378 32816 16376 32816 14878 32816 16378 32817 14878 32817 15406 32817 15406 32818 14878 32818 14875 32818 15406 32819 14875 32819 16379 32819 16379 32820 14875 32820 14874 32820 16379 32821 14874 32821 16380 32821 16380 32822 14874 32822 16381 32822 16380 32823 16381 32823 15408 32823 15408 32824 16381 32824 22854 32824 15408 32825 22854 32825 19978 32825 16383 32826 16382 32826 15386 32826 16383 32827 15386 32827 15189 32827 15189 32828 15386 32828 16384 32828 15189 32829 16384 32829 15191 32829 15191 32830 16384 32830 16385 32830 15191 32831 16385 32831 16387 32831 16387 32832 16385 32832 16386 32832 16387 32833 16386 32833 16388 32833 16388 32834 16386 32834 15382 32834 16388 32835 15382 32835 16389 32835 16389 32836 15382 32836 15380 32836 16389 32837 15380 32837 15194 32837 15194 32838 15380 32838 16391 32838 15194 32839 16391 32839 16390 32839 16390 32840 16391 32840 16392 32840 16390 32841 16392 32841 15198 32841 15198 32842 16392 32842 16393 32842 15198 32843 16393 32843 16394 32843 16394 32844 16393 32844 16395 32844 16394 32845 16395 32845 15201 32845 15201 32846 16395 32846 16396 32846 15201 32847 16396 32847 16398 32847 16398 32848 16396 32848 16397 32848 16398 32849 16397 32849 15203 32849 15203 32850 16397 32850 16399 32850 15203 32851 16399 32851 16400 32851 16400 32852 16399 32852 15376 32852 16400 32853 15376 32853 15205 32853 15205 32854 15376 32854 16401 32854 15205 32855 16401 32855 15206 32855 15206 32856 16401 32856 15374 32856 15206 32857 15374 32857 15207 32857 15207 32858 15374 32858 15372 32858 15207 32859 15372 32859 15208 32859 15208 32860 15372 32860 16402 32860 15208 32861 16402 32861 16403 32861 16403 32862 16402 32862 16404 32862 16403 32863 16404 32863 22480 32863 16406 32864 16405 32864 15187 32864 16406 32865 15187 32865 16407 32865 16407 32866 15187 32866 15185 32866 16407 32867 15185 32867 16408 32867 16408 32868 15185 32868 16409 32868 16408 32869 16409 32869 16410 32869 16410 32870 16409 32870 15182 32870 16410 32871 15182 32871 15156 32871 15156 32872 15182 32872 15181 32872 15156 32873 15181 32873 15157 32873 15157 32874 15181 32874 15180 32874 15157 32875 15180 32875 16411 32875 16411 32876 15180 32876 15179 32876 16411 32877 15179 32877 15158 32877 15158 32878 15179 32878 16412 32878 15158 32879 16412 32879 16413 32879 16413 32880 16412 32880 15178 32880 16413 32881 15178 32881 16414 32881 16414 32882 15178 32882 16415 32882 16414 32883 16415 32883 15160 32883 15160 32884 16415 32884 16416 32884 15160 32885 16416 32885 16417 32885 16417 32886 16416 32886 16418 32886 16417 32887 16418 32887 16420 32887 16420 32888 16418 32888 16419 32888 16420 32889 16419 32889 16421 32889 16421 32890 16419 32890 16423 32890 16421 32891 16423 32891 16422 32891 16422 32892 16423 32892 16424 32892 16422 32893 16424 32893 15164 32893 15164 32894 16424 32894 16425 32894 15164 32895 16425 32895 15165 32895 15165 32896 16425 32896 15170 32896 15165 32897 15170 32897 15166 32897 15166 32898 15170 32898 16426 32898 15166 32899 16426 32899 15167 32899 15167 32900 16426 32900 19934 32900 15167 32901 19934 32901 19935 32901 16427 32902 15151 32902 15150 32902 16427 32903 15150 32903 15113 32903 15113 32904 15150 32904 16428 32904 15113 32905 16428 32905 15115 32905 15115 32906 16428 32906 16429 32906 15115 32907 16429 32907 16430 32907 16430 32908 16429 32908 15145 32908 16430 32909 15145 32909 16431 32909 16431 32910 15145 32910 15144 32910 16431 32911 15144 32911 16432 32911 16432 32912 15144 32912 15143 32912 16432 32913 15143 32913 16433 32913 16433 32914 15143 32914 15142 32914 16433 32915 15142 32915 15117 32915 15117 32916 15142 32916 16435 32916 15117 32917 16435 32917 16434 32917 16434 32918 16435 32918 15138 32918 16434 32919 15138 32919 16436 32919 16436 32920 15138 32920 15137 32920 16436 32921 15137 32921 16437 32921 16437 32922 15137 32922 16438 32922 16437 32923 16438 32923 16440 32923 16440 32924 16438 32924 16439 32924 16440 32925 16439 32925 16441 32925 16441 32926 16439 32926 15133 32926 16441 32927 15133 32927 16442 32927 16442 32928 15133 32928 15131 32928 16442 32929 15131 32929 16443 32929 16443 32930 15131 32930 15130 32930 16443 32931 15130 32931 15122 32931 15122 32932 15130 32932 16444 32932 15122 32933 16444 32933 15123 32933 15123 32934 16444 32934 16445 32934 15123 32935 16445 32935 15124 32935 15124 32936 16445 32936 15127 32936 15124 32937 15127 32937 16446 32937 16446 32938 15127 32938 22559 32938 16446 32939 22559 32939 15125 32939 22607 32940 22577 32940 16447 32940 22607 32941 16447 32941 15087 32941 15087 32942 16447 32942 15111 32942 15087 32943 15111 32943 16448 32943 16448 32944 15111 32944 16449 32944 16448 32945 16449 32945 16450 32945 16450 32946 16449 32946 15109 32946 16450 32947 15109 32947 16451 32947 16451 32948 15109 32948 15108 32948 16451 32949 15108 32949 16452 32949 16452 32950 15108 32950 15107 32950 16452 32951 15107 32951 16454 32951 16454 32952 15107 32952 16453 32952 16454 32953 16453 32953 16455 32953 16455 32954 16453 32954 16456 32954 16455 32955 16456 32955 15090 32955 15090 32956 16456 32956 16457 32956 15090 32957 16457 32957 16458 32957 16458 32958 16457 32958 16459 32958 16458 32959 16459 32959 15092 32959 15092 32960 16459 32960 16460 32960 15092 32961 16460 32961 15093 32961 15093 32962 16460 32962 15102 32962 15093 32963 15102 32963 16462 32963 16462 32964 15102 32964 16461 32964 16462 32965 16461 32965 16463 32965 16463 32966 16461 32966 16464 32966 16463 32967 16464 32967 16465 32967 16465 32968 16464 32968 16466 32968 16465 32969 16466 32969 15097 32969 15097 32970 16466 32970 16467 32970 15097 32971 16467 32971 16469 32971 16469 32972 16467 32972 16468 32972 16469 32973 16468 32973 16470 32973 16470 32974 16468 32974 16471 32974 16470 32975 16471 32975 15099 32975 15099 32976 16471 32976 16472 32976 15099 32977 16472 32977 16473 32977 22636 32978 16474 32978 15086 32978 22636 32979 15086 32979 15046 32979 15046 32980 15086 32980 16475 32980 15046 32981 16475 32981 15048 32981 15048 32982 16475 32982 16476 32982 15048 32983 16476 32983 15050 32983 15050 32984 16476 32984 16477 32984 15050 32985 16477 32985 16478 32985 16478 32986 16477 32986 16479 32986 16478 32987 16479 32987 15053 32987 15053 32988 16479 32988 16480 32988 15053 32989 16480 32989 15055 32989 15055 32990 16480 32990 15080 32990 15055 32991 15080 32991 15056 32991 15056 32992 15080 32992 16481 32992 15056 32993 16481 32993 16482 32993 16482 32994 16481 32994 15077 32994 16482 32995 15077 32995 15058 32995 15058 32996 15077 32996 16483 32996 15058 32997 16483 32997 15060 32997 15060 32998 16483 32998 15076 32998 15060 32999 15076 32999 16484 32999 16484 33000 15076 33000 16485 33000 16484 33001 16485 33001 15062 33001 15062 33002 16485 33002 16486 33002 15062 33003 16486 33003 15063 33003 15063 33004 16486 33004 15073 33004 15063 33005 15073 33005 15064 33005 15064 33006 15073 33006 15072 33006 15064 33007 15072 33007 16487 33007 16487 33008 15072 33008 16488 33008 16487 33009 16488 33009 15065 33009 15065 33010 16488 33010 15070 33010 15065 33011 15070 33011 15066 33011 15066 33012 15070 33012 16489 33012 15066 33013 16489 33013 15067 33013 15067 33014 16489 33014 16490 33014 15067 33015 16490 33015 22622 33015 15012 33016 15044 33016 15043 33016 15012 33017 15043 33017 15013 33017 15013 33018 15043 33018 15042 33018 15013 33019 15042 33019 15015 33019 15015 33020 15042 33020 15041 33020 15015 33021 15041 33021 16492 33021 16492 33022 15041 33022 16491 33022 16492 33023 16491 33023 16493 33023 16493 33024 16491 33024 16494 33024 16493 33025 16494 33025 15016 33025 15016 33026 16494 33026 16495 33026 15016 33027 16495 33027 15018 33027 15018 33028 16495 33028 15039 33028 15018 33029 15039 33029 16496 33029 16496 33030 15039 33030 16497 33030 16496 33031 16497 33031 15020 33031 15020 33032 16497 33032 16498 33032 15020 33033 16498 33033 16499 33033 16499 33034 16498 33034 16500 33034 16499 33035 16500 33035 15022 33035 15022 33036 16500 33036 16501 33036 15022 33037 16501 33037 16502 33037 16502 33038 16501 33038 16503 33038 16502 33039 16503 33039 15023 33039 15023 33040 16503 33040 16505 33040 15023 33041 16505 33041 16504 33041 16504 33042 16505 33042 15037 33042 16504 33043 15037 33043 15025 33043 15025 33044 15037 33044 15035 33044 15025 33045 15035 33045 15027 33045 15027 33046 15035 33046 16506 33046 15027 33047 16506 33047 15029 33047 15029 33048 16506 33048 16507 33048 15029 33049 16507 33049 16508 33049 16508 33050 16507 33050 15034 33050 16508 33051 15034 33051 15031 33051 15031 33052 15034 33052 15032 33052 15031 33053 15032 33053 22655 33053 22715 33054 19857 33054 16509 33054 22715 33055 16509 33055 14977 33055 14977 33056 16509 33056 16510 33056 14977 33057 16510 33057 16511 33057 16511 33058 16510 33058 16512 33058 16511 33059 16512 33059 16513 33059 16513 33060 16512 33060 15008 33060 16513 33061 15008 33061 14981 33061 14981 33062 15008 33062 16514 33062 14981 33063 16514 33063 14983 33063 14983 33064 16514 33064 15006 33064 14983 33065 15006 33065 14984 33065 14984 33066 15006 33066 16515 33066 14984 33067 16515 33067 14986 33067 14986 33068 16515 33068 15005 33068 14986 33069 15005 33069 16516 33069 16516 33070 15005 33070 16517 33070 16516 33071 16517 33071 16519 33071 16519 33072 16517 33072 16518 33072 16519 33073 16518 33073 16520 33073 16520 33074 16518 33074 16522 33074 16520 33075 16522 33075 16521 33075 16521 33076 16522 33076 16524 33076 16521 33077 16524 33077 16523 33077 16523 33078 16524 33078 15000 33078 16523 33079 15000 33079 14987 33079 14987 33080 15000 33080 14998 33080 14987 33081 14998 33081 14988 33081 14988 33082 14998 33082 16525 33082 14988 33083 16525 33083 14989 33083 14989 33084 16525 33084 16526 33084 14989 33085 16526 33085 14990 33085 14990 33086 16526 33086 14995 33086 14990 33087 14995 33087 14992 33087 14992 33088 14995 33088 16527 33088 14992 33089 16527 33089 16528 33089 16528 33090 16527 33090 14994 33090 16528 33091 14994 33091 22694 33091 22831 33092 14941 33092 16530 33092 22831 33093 16530 33093 16529 33093 16529 33094 16530 33094 14939 33094 16529 33095 14939 33095 14895 33095 14895 33096 14939 33096 14938 33096 14895 33097 14938 33097 16531 33097 16531 33098 14938 33098 14936 33098 16531 33099 14936 33099 16532 33099 16532 33100 14936 33100 14933 33100 16532 33101 14933 33101 16533 33101 16533 33102 14933 33102 14932 33102 16533 33103 14932 33103 14901 33103 14901 33104 14932 33104 14931 33104 14901 33105 14931 33105 16534 33105 16534 33106 14931 33106 16536 33106 16534 33107 16536 33107 16535 33107 16535 33108 16536 33108 16537 33108 16535 33109 16537 33109 16538 33109 16538 33110 16537 33110 16539 33110 16538 33111 16539 33111 14905 33111 14905 33112 16539 33112 16540 33112 14905 33113 16540 33113 14904 33113 14904 33114 16540 33114 14927 33114 14904 33115 14927 33115 14909 33115 14909 33116 14927 33116 16541 33116 14909 33117 16541 33117 14910 33117 14910 33118 16541 33118 14925 33118 14910 33119 14925 33119 14913 33119 14913 33120 14925 33120 14921 33120 14913 33121 14921 33121 14915 33121 14915 33122 14921 33122 16543 33122 14915 33123 16543 33123 16542 33123 16542 33124 16543 33124 16544 33124 16542 33125 16544 33125 14917 33125 14917 33126 16544 33126 16545 33126 14917 33127 16545 33127 16546 33127 16546 33128 16545 33128 14918 33128 16546 33129 14918 33129 19819 33129 16547 33130 19818 33130 14975 33130 16547 33131 14975 33131 16548 33131 16548 33132 14975 33132 16550 33132 16548 33133 16550 33133 16549 33133 16549 33134 16550 33134 14973 33134 16549 33135 14973 33135 14943 33135 14943 33136 14973 33136 14972 33136 14943 33137 14972 33137 14944 33137 14944 33138 14972 33138 14969 33138 14944 33139 14969 33139 16551 33139 16551 33140 14969 33140 14968 33140 16551 33141 14968 33141 16553 33141 16553 33142 14968 33142 16552 33142 16553 33143 16552 33143 14945 33143 14945 33144 16552 33144 16555 33144 14945 33145 16555 33145 16554 33145 16554 33146 16555 33146 16556 33146 16554 33147 16556 33147 16558 33147 16558 33148 16556 33148 16557 33148 16558 33149 16557 33149 16559 33149 16559 33150 16557 33150 16560 33150 16559 33151 16560 33151 14948 33151 14948 33152 16560 33152 14965 33152 14948 33153 14965 33153 14950 33153 14950 33154 14965 33154 16561 33154 14950 33155 16561 33155 14952 33155 14952 33156 16561 33156 16563 33156 14952 33157 16563 33157 16562 33157 16562 33158 16563 33158 16564 33158 16562 33159 16564 33159 16565 33159 16565 33160 16564 33160 14962 33160 16565 33161 14962 33161 14953 33161 14953 33162 14962 33162 14961 33162 14953 33163 14961 33163 14955 33163 14955 33164 14961 33164 14959 33164 14955 33165 14959 33165 16566 33165 16566 33166 14959 33166 14957 33166 16566 33167 14957 33167 22738 33167 16567 33168 16568 33168 16569 33168 16567 33169 16569 33169 14893 33169 14893 33170 16569 33170 17455 33170 14893 33171 17455 33171 14892 33171 14892 33172 17455 33172 17456 33172 14892 33173 17456 33173 14891 33173 14891 33174 17456 33174 17458 33174 14891 33175 17458 33175 14890 33175 14890 33176 17458 33176 17460 33176 14890 33177 17460 33177 14888 33177 14888 33178 17460 33178 17461 33178 14888 33179 17461 33179 16570 33179 16570 33180 17461 33180 17462 33180 16570 33181 17462 33181 14886 33181 14886 33182 17462 33182 16571 33182 14886 33183 16571 33183 14885 33183 14885 33184 16571 33184 16572 33184 14885 33185 16572 33185 16573 33185 16573 33186 16572 33186 16574 33186 16573 33187 16574 33187 16575 33187 16575 33188 16574 33188 16576 33188 16575 33189 16576 33189 14883 33189 14883 33190 16576 33190 16577 33190 14883 33191 16577 33191 16578 33191 16578 33192 16577 33192 16579 33192 16578 33193 16579 33193 14881 33193 14881 33194 16579 33194 16580 33194 14881 33195 16580 33195 16581 33195 16581 33196 16580 33196 17466 33196 16581 33197 17466 33197 14879 33197 14879 33198 17466 33198 17468 33198 14879 33199 17468 33199 14877 33199 14877 33200 17468 33200 17469 33200 14877 33201 17469 33201 14876 33201 14876 33202 17469 33202 17471 33202 14876 33203 17471 33203 14873 33203 14873 33204 17471 33204 19739 33204 14873 33205 19739 33205 14872 33205 17474 33206 18513 33206 16582 33206 16582 33207 18513 33207 18508 33207 16582 33208 18508 33208 16583 33208 16583 33209 18508 33209 18519 33209 16583 33210 18519 33210 17477 33210 17477 33211 18519 33211 18518 33211 17477 33212 18518 33212 16584 33212 16584 33213 18518 33213 18516 33213 16584 33214 18516 33214 17481 33214 17481 33215 18516 33215 16585 33215 17481 33216 16585 33216 17482 33216 17482 33217 16585 33217 16587 33217 17482 33218 16587 33218 16586 33218 16586 33219 16587 33219 19733 33219 17484 33220 16588 33220 17485 33220 17485 33221 16588 33221 16589 33221 17485 33222 16589 33222 16590 33222 16590 33223 16589 33223 16591 33223 16590 33224 16591 33224 17486 33224 17486 33225 16591 33225 18504 33225 17486 33226 18504 33226 16592 33226 16592 33227 18504 33227 18500 33227 16592 33228 18500 33228 17488 33228 17488 33229 18500 33229 16593 33229 17488 33230 16593 33230 18222 33230 18222 33231 16593 33231 16594 33231 18221 33232 16595 33232 17492 33232 17492 33233 16595 33233 18493 33233 17492 33234 18493 33234 17493 33234 17493 33235 18493 33235 16596 33235 17493 33236 16596 33236 17494 33236 17494 33237 16596 33237 18499 33237 17494 33238 18499 33238 16598 33238 16598 33239 18499 33239 16597 33239 16598 33240 16597 33240 16599 33240 16599 33241 16597 33241 18498 33241 16599 33242 18498 33242 17497 33242 17497 33243 18498 33243 18492 33243 17497 33244 18492 33244 19717 33244 19717 33245 18492 33245 18491 33245 16600 33246 16601 33246 17498 33246 17498 33247 16601 33247 16602 33247 17498 33248 16602 33248 17499 33248 17499 33249 16602 33249 16603 33249 17499 33250 16603 33250 16604 33250 16604 33251 16603 33251 16605 33251 16604 33252 16605 33252 17502 33252 17502 33253 16605 33253 16606 33253 17502 33254 16606 33254 16607 33254 16607 33255 16606 33255 16608 33255 16607 33256 16608 33256 18205 33256 18205 33257 16608 33257 18529 33257 17506 33258 16609 33258 16610 33258 16610 33259 16609 33259 18522 33259 16610 33260 18522 33260 16611 33260 16611 33261 18522 33261 16612 33261 16611 33262 16612 33262 16613 33262 16613 33263 16612 33263 18528 33263 16613 33264 18528 33264 17509 33264 17509 33265 18528 33265 16614 33265 17509 33266 16614 33266 17511 33266 17511 33267 16614 33267 16615 33267 17511 33268 16615 33268 17513 33268 17513 33269 16615 33269 18527 33269 17513 33270 18527 33270 19702 33270 19702 33271 18527 33271 19703 33271 17514 33272 19701 33272 16616 33272 16616 33273 19701 33273 16617 33273 16616 33274 16617 33274 16618 33274 16618 33275 16617 33275 16619 33275 16618 33276 16619 33276 17517 33276 17517 33277 16619 33277 16620 33277 17517 33278 16620 33278 17518 33278 17518 33279 16620 33279 16621 33279 17518 33280 16621 33280 17520 33280 17520 33281 16621 33281 18471 33281 17520 33282 18471 33282 18188 33282 18188 33283 18471 33283 18468 33283 19689 33284 18599 33284 16622 33284 16622 33285 18599 33285 16623 33285 16622 33286 16623 33286 17522 33286 17522 33287 16623 33287 18555 33287 17522 33288 18555 33288 17524 33288 17524 33289 18555 33289 18554 33289 17524 33290 18554 33290 17526 33290 17526 33291 18554 33291 16624 33291 17526 33292 16624 33292 17527 33292 17527 33293 16624 33293 16625 33293 17527 33294 16625 33294 18178 33294 18178 33295 16625 33295 18553 33295 19680 33296 18543 33296 17529 33296 17529 33297 18543 33297 16627 33297 17529 33298 16627 33298 16626 33298 16626 33299 16627 33299 18541 33299 16626 33300 18541 33300 17531 33300 17531 33301 18541 33301 18540 33301 17531 33302 18540 33302 16628 33302 16628 33303 18540 33303 16629 33303 16628 33304 16629 33304 17533 33304 17533 33305 16629 33305 18546 33305 17533 33306 18546 33306 18170 33306 18170 33307 18546 33307 18545 33307 19675 33308 19676 33308 16631 33308 16631 33309 19676 33309 16630 33309 16631 33310 16630 33310 16632 33310 16632 33311 16630 33311 18570 33311 16632 33312 18570 33312 17538 33312 17538 33313 18570 33313 18571 33313 17538 33314 18571 33314 16634 33314 16634 33315 18571 33315 16633 33315 16634 33316 16633 33316 16635 33316 16635 33317 16633 33317 16636 33317 16635 33318 16636 33318 18162 33318 18162 33319 16636 33319 18568 33319 18160 33320 16637 33320 16638 33320 18160 33321 16638 33321 16639 33321 16639 33322 16638 33322 18566 33322 16639 33323 18566 33323 16640 33323 16640 33324 18566 33324 17546 33324 17546 33325 18566 33325 16642 33325 17546 33326 16642 33326 17545 33326 17545 33327 16642 33327 16641 33327 16641 33328 16642 33328 18565 33328 16641 33329 18565 33329 17543 33329 17543 33330 18565 33330 16643 33330 16643 33331 18565 33331 16644 33331 16643 33332 16644 33332 16645 33332 16645 33333 16644 33333 16646 33333 16645 33334 16646 33334 16647 33334 16647 33335 16646 33335 16648 33335 16647 33336 16648 33336 16649 33336 17757 33337 17452 33337 17451 33337 17757 33338 17451 33338 16650 33338 16650 33339 17451 33339 17450 33339 16650 33340 17450 33340 16651 33340 16651 33341 17450 33341 17449 33341 16651 33342 17449 33342 17759 33342 17759 33343 17449 33343 16652 33343 17759 33344 16652 33344 17760 33344 17760 33345 16652 33345 17447 33345 17760 33346 17447 33346 17762 33346 17762 33347 17447 33347 16653 33347 17762 33348 16653 33348 17764 33348 17764 33349 16653 33349 17445 33349 17764 33350 17445 33350 17766 33350 17766 33351 17445 33351 16654 33351 17766 33352 16654 33352 16655 33352 16655 33353 16654 33353 17444 33353 16655 33354 17444 33354 16656 33354 16656 33355 17444 33355 17441 33355 16656 33356 17441 33356 17768 33356 17768 33357 17441 33357 16657 33357 17768 33358 16657 33358 16658 33358 16658 33359 16657 33359 17440 33359 16658 33360 17440 33360 17771 33360 17771 33361 17440 33361 16659 33361 17771 33362 16659 33362 16660 33362 16660 33363 16659 33363 17439 33363 16660 33364 17439 33364 16661 33364 16661 33365 17439 33365 17437 33365 16661 33366 17437 33366 16662 33366 16662 33367 17437 33367 16663 33367 16662 33368 16663 33368 19645 33368 16683 33369 17457 33369 17454 33369 18464 33370 19644 33370 17470 33370 16667 33371 18342 33371 16664 33371 16664 33372 18342 33372 18337 33372 16664 33373 18337 33373 17467 33373 17467 33374 18337 33374 18338 33374 17467 33375 18338 33375 17470 33375 17470 33376 18338 33376 16665 33376 17470 33377 16665 33377 18464 33377 16668 33378 18327 33378 16669 33378 16669 33379 18327 33379 18531 33379 16669 33380 18531 33380 16664 33380 16664 33381 18531 33381 16666 33381 16664 33382 16666 33382 16667 33382 16668 33383 16669 33383 18321 33383 18321 33384 16669 33384 16670 33384 18321 33385 16670 33385 18322 33385 16671 33386 18317 33386 17465 33386 17465 33387 18317 33387 18318 33387 17465 33388 18318 33388 16670 33388 16670 33389 18318 33389 18345 33389 16670 33390 18345 33390 18322 33390 18520 33391 18521 33391 16673 33391 16673 33392 18521 33392 17465 33392 17465 33393 18521 33393 18524 33393 17465 33394 18524 33394 16671 33394 16672 33395 18359 33395 16674 33395 16674 33396 18359 33396 18234 33396 16674 33397 18234 33397 16673 33397 16673 33398 18234 33398 18306 33398 16673 33399 18306 33399 18520 33399 16672 33400 16674 33400 16675 33400 16675 33401 16674 33401 17464 33401 16675 33402 17464 33402 16676 33402 16676 33403 17464 33403 17463 33403 16676 33404 17463 33404 18512 33404 18512 33405 17463 33405 18511 33405 18511 33406 17463 33406 16677 33406 18511 33407 16677 33407 18406 33407 18406 33408 16677 33408 18408 33408 18408 33409 16677 33409 16679 33409 18408 33410 16679 33410 18372 33410 18502 33411 18505 33411 16678 33411 16678 33412 18505 33412 18507 33412 16678 33413 18507 33413 16679 33413 16679 33414 18507 33414 18370 33414 16679 33415 18370 33415 18372 33415 18502 33416 16678 33416 18377 33416 18377 33417 16678 33417 16680 33417 18377 33418 16680 33418 18393 33418 17459 33419 18399 33419 18402 33419 17459 33420 18402 33420 16680 33420 16680 33421 18402 33421 16681 33421 16680 33422 16681 33422 18393 33422 16683 33423 16682 33423 17457 33423 17457 33424 16682 33424 18495 33424 17457 33425 18495 33425 17459 33425 17459 33426 18495 33426 18490 33426 17459 33427 18490 33427 18399 33427 18480 33428 18482 33428 17454 33428 17454 33429 18482 33429 18483 33429 17454 33430 18483 33430 16683 33430 18480 33431 17454 33431 18390 33431 18390 33432 17454 33432 16684 33432 18390 33433 16684 33433 16685 33433 16685 33434 16684 33434 19621 33434 16685 33435 19621 33435 18252 33435 16691 33436 19620 33436 16693 33436 16693 33437 19620 33437 16686 33437 16693 33438 16686 33438 16695 33438 16695 33439 16686 33439 18560 33439 16695 33440 18560 33440 16697 33440 16697 33441 18560 33441 18557 33441 16697 33442 18557 33442 16687 33442 16687 33443 18557 33443 16688 33443 16687 33444 16688 33444 16701 33444 16701 33445 16688 33445 16689 33445 16701 33446 16689 33446 19605 33446 19605 33447 16689 33447 18558 33447 16690 33448 16691 33448 16692 33448 16692 33449 16691 33449 16693 33449 16692 33450 16693 33450 16703 33450 16703 33451 16693 33451 16694 33451 16694 33452 16693 33452 16695 33452 16694 33453 16695 33453 16704 33453 16704 33454 16695 33454 16705 33454 16705 33455 16695 33455 16697 33455 16705 33456 16697 33456 16696 33456 16696 33457 16697 33457 16698 33457 16698 33458 16697 33458 16687 33458 16698 33459 16687 33459 16699 33459 16699 33460 16687 33460 16707 33460 16707 33461 16687 33461 16701 33461 16707 33462 16701 33462 16700 33462 16700 33463 16701 33463 16708 33463 16708 33464 16701 33464 19605 33464 16708 33465 19605 33465 19604 33465 16702 33466 19600 33466 16690 33466 16690 33467 16692 33467 16702 33467 16702 33468 16692 33468 16703 33468 16702 33469 16703 33469 18108 33469 16703 33470 16694 33470 18108 33470 18108 33471 16694 33471 16704 33471 18108 33472 16704 33472 18107 33472 16704 33473 16705 33473 18107 33473 18107 33474 16705 33474 16696 33474 18107 33475 16696 33475 18106 33475 18106 33476 16696 33476 16698 33476 18106 33477 16698 33477 16706 33477 16698 33478 16699 33478 16706 33478 16706 33479 16699 33479 16707 33479 16706 33480 16707 33480 16709 33480 19604 33481 18104 33481 16708 33481 16708 33482 18104 33482 16709 33482 16708 33483 16709 33483 16700 33483 16700 33484 16709 33484 16707 33484 16712 33485 19590 33485 16710 33485 16710 33486 16711 33486 16712 33486 16712 33487 16711 33487 16729 33487 16712 33488 16729 33488 18448 33488 16729 33489 16727 33489 18448 33489 18448 33490 16727 33490 16725 33490 18448 33491 16725 33491 16713 33491 16713 33492 16725 33492 16724 33492 16724 33493 16723 33493 16713 33493 16713 33494 16723 33494 16721 33494 16713 33495 16721 33495 18552 33495 16721 33496 16719 33496 18552 33496 18552 33497 16719 33497 16716 33497 18552 33498 16716 33498 18449 33498 19580 33499 16714 33499 16715 33499 16715 33500 16714 33500 18449 33500 16715 33501 18449 33501 16717 33501 16717 33502 18449 33502 16716 33502 19567 33503 19580 33503 16730 33503 16730 33504 19580 33504 16715 33504 16730 33505 16715 33505 16731 33505 16731 33506 16715 33506 16717 33506 16731 33507 16717 33507 16718 33507 16718 33508 16717 33508 16716 33508 16718 33509 16716 33509 16732 33509 16732 33510 16716 33510 16719 33510 16732 33511 16719 33511 16733 33511 16733 33512 16719 33512 16721 33512 16733 33513 16721 33513 16720 33513 16720 33514 16721 33514 16723 33514 16720 33515 16723 33515 16722 33515 16722 33516 16723 33516 16724 33516 16722 33517 16724 33517 16735 33517 16735 33518 16724 33518 16725 33518 16735 33519 16725 33519 16726 33519 16726 33520 16725 33520 16727 33520 16726 33521 16727 33521 16738 33521 16738 33522 16727 33522 16729 33522 16738 33523 16729 33523 16728 33523 16728 33524 16729 33524 16711 33524 16728 33525 16711 33525 16737 33525 16737 33526 16711 33526 16710 33526 18099 33527 18101 33527 19567 33527 19567 33528 16730 33528 18099 33528 18099 33529 16730 33529 16731 33529 18099 33530 16731 33530 18098 33530 18098 33531 16731 33531 16718 33531 16718 33532 16732 33532 18098 33532 18098 33533 16732 33533 16733 33533 18098 33534 16733 33534 16734 33534 16733 33535 16720 33535 16734 33535 16734 33536 16720 33536 16722 33536 16734 33537 16722 33537 16736 33537 16722 33538 16735 33538 16736 33538 16736 33539 16735 33539 16726 33539 16736 33540 16726 33540 16739 33540 16737 33541 18095 33541 16728 33541 16728 33542 18095 33542 16739 33542 16728 33543 16739 33543 16738 33543 16738 33544 16739 33544 16726 33544 16746 33545 18241 33545 16747 33545 16747 33546 18241 33546 18240 33546 16747 33547 18240 33547 16740 33547 16740 33548 18240 33548 16741 33548 16740 33549 16741 33549 16742 33549 16742 33550 16741 33550 18444 33550 16742 33551 18444 33551 16752 33551 16752 33552 18444 33552 16743 33552 16752 33553 16743 33553 16755 33553 16755 33554 16743 33554 16744 33554 16755 33555 16744 33555 19561 33555 19561 33556 16744 33556 19563 33556 16745 33557 16746 33557 16758 33557 16758 33558 16746 33558 16747 33558 16758 33559 16747 33559 16748 33559 16748 33560 16747 33560 16749 33560 16749 33561 16747 33561 16740 33561 16749 33562 16740 33562 16750 33562 16750 33563 16740 33563 16760 33563 16760 33564 16740 33564 16742 33564 16760 33565 16742 33565 16751 33565 16751 33566 16742 33566 16753 33566 16753 33567 16742 33567 16752 33567 16753 33568 16752 33568 16754 33568 16754 33569 16752 33569 16762 33569 16762 33570 16752 33570 16755 33570 16762 33571 16755 33571 16764 33571 16764 33572 16755 33572 16756 33572 16756 33573 16755 33573 19561 33573 16756 33574 19561 33574 19549 33574 16757 33575 18079 33575 16745 33575 16745 33576 16758 33576 16757 33576 16757 33577 16758 33577 16748 33577 16757 33578 16748 33578 16759 33578 16748 33579 16749 33579 16759 33579 16759 33580 16749 33580 16750 33580 16759 33581 16750 33581 16761 33581 16750 33582 16760 33582 16761 33582 16761 33583 16760 33583 16751 33583 16761 33584 16751 33584 18089 33584 18089 33585 16751 33585 16753 33585 18089 33586 16753 33586 16763 33586 16753 33587 16754 33587 16763 33587 16763 33588 16754 33588 16762 33588 16763 33589 16762 33589 18088 33589 19549 33590 18087 33590 16756 33590 16756 33591 18087 33591 18088 33591 16756 33592 18088 33592 16764 33592 16764 33593 18088 33593 16762 33593 16772 33594 18457 33594 16775 33594 16775 33595 18457 33595 16765 33595 16775 33596 16765 33596 16767 33596 16767 33597 16765 33597 16766 33597 16767 33598 16766 33598 16776 33598 16776 33599 16766 33599 16768 33599 16776 33600 16768 33600 16777 33600 16777 33601 16768 33601 18460 33601 16777 33602 18460 33602 16769 33602 16769 33603 18460 33603 16770 33603 16769 33604 16770 33604 16771 33604 16771 33605 16770 33605 19543 33605 16785 33606 16772 33606 16773 33606 16773 33607 16772 33607 16775 33607 16773 33608 16775 33608 16774 33608 16774 33609 16775 33609 16767 33609 16774 33610 16767 33610 16782 33610 16782 33611 16767 33611 16776 33611 16782 33612 16776 33612 16780 33612 16780 33613 16776 33613 16777 33613 16780 33614 16777 33614 16778 33614 16778 33615 16777 33615 16769 33615 16778 33616 16769 33616 19521 33616 19521 33617 16769 33617 16771 33617 19521 33618 19511 33618 16778 33618 16778 33619 19511 33619 16779 33619 16778 33620 16779 33620 16780 33620 16780 33621 16779 33621 18070 33621 16780 33622 18070 33622 16782 33622 16782 33623 18070 33623 16781 33623 16782 33624 16781 33624 16774 33624 16774 33625 16781 33625 16783 33625 16774 33626 16783 33626 16773 33626 16773 33627 16783 33627 16784 33627 16773 33628 16784 33628 16785 33628 16785 33629 16784 33629 19518 33629 19510 33630 18431 33630 16786 33630 16786 33631 18431 33631 18441 33631 16786 33632 18441 33632 16787 33632 16787 33633 18441 33633 16788 33633 16787 33634 16788 33634 16789 33634 16789 33635 16788 33635 18470 33635 16789 33636 18470 33636 16790 33636 16790 33637 18470 33637 18440 33637 16790 33638 18440 33638 16791 33638 16791 33639 18440 33639 16793 33639 16791 33640 16793 33640 16792 33640 16792 33641 16793 33641 18438 33641 16794 33642 16795 33642 18454 33642 18454 33643 16795 33643 16797 33643 18454 33644 16797 33644 16796 33644 16796 33645 16797 33645 16801 33645 16869 33646 18611 33646 16798 33646 16798 33647 18611 33647 16799 33647 16798 33648 16799 33648 16870 33648 16870 33649 16799 33649 18452 33649 16870 33650 18452 33650 16872 33650 16872 33651 18452 33651 16800 33651 16872 33652 16800 33652 16801 33652 16801 33653 16800 33653 18456 33653 16801 33654 18456 33654 16796 33654 16802 33655 16803 33655 16876 33655 16876 33656 16803 33656 18461 33656 16876 33657 18461 33657 16877 33657 16877 33658 18461 33658 16804 33658 16877 33659 16804 33659 16879 33659 16879 33660 16804 33660 16805 33660 16879 33661 16805 33661 16807 33661 16807 33662 16805 33662 16806 33662 16807 33663 16806 33663 16808 33663 16808 33664 16806 33664 18459 33664 16808 33665 18459 33665 16809 33665 16809 33666 18459 33666 19495 33666 16811 33667 19407 33667 16812 33667 16812 33668 19407 33668 19408 33668 16812 33669 19408 33669 16813 33669 16813 33670 19408 33670 16810 33670 16813 33671 16810 33671 16815 33671 16815 33672 16810 33672 19411 33672 16815 33673 19411 33673 16816 33673 16816 33674 19411 33674 19412 33674 16816 33675 19412 33675 16819 33675 16819 33676 19412 33676 19414 33676 16819 33677 19414 33677 16820 33677 16820 33678 19414 33678 19415 33678 19481 33679 16811 33679 16825 33679 16825 33680 16811 33680 16812 33680 16825 33681 16812 33681 16824 33681 16824 33682 16812 33682 16813 33682 16824 33683 16813 33683 16814 33683 16814 33684 16813 33684 16815 33684 16814 33685 16815 33685 16823 33685 16823 33686 16815 33686 16816 33686 16823 33687 16816 33687 16817 33687 16817 33688 16816 33688 16819 33688 16817 33689 16819 33689 16818 33689 16818 33690 16819 33690 16820 33690 16818 33691 16821 33691 16817 33691 16817 33692 16821 33692 16822 33692 16817 33693 16822 33693 16823 33693 16823 33694 16822 33694 18145 33694 16823 33695 18145 33695 16814 33695 16814 33696 18145 33696 18146 33696 16814 33697 18146 33697 16824 33697 16824 33698 18146 33698 18148 33698 16824 33699 18148 33699 16825 33699 16825 33700 18148 33700 16826 33700 16825 33701 16826 33701 19481 33701 19481 33702 16826 33702 19472 33702 16827 33703 16829 33703 16828 33703 16828 33704 16829 33704 16830 33704 16828 33705 16830 33705 16832 33705 16832 33706 16830 33706 16831 33706 16832 33707 16831 33707 16833 33707 16833 33708 16831 33708 16834 33708 16833 33709 16834 33709 16839 33709 16839 33710 16834 33710 19397 33710 16839 33711 19397 33711 16835 33711 16835 33712 19397 33712 16837 33712 16835 33713 16837 33713 16836 33713 16836 33714 16837 33714 19398 33714 16838 33715 16827 33715 16845 33715 16845 33716 16827 33716 16828 33716 16845 33717 16828 33717 16844 33717 16844 33718 16828 33718 16832 33718 16844 33719 16832 33719 16842 33719 16842 33720 16832 33720 16833 33720 16842 33721 16833 33721 16841 33721 16841 33722 16833 33722 16839 33722 16841 33723 16839 33723 16840 33723 16840 33724 16839 33724 16835 33724 16840 33725 16835 33725 19456 33725 19456 33726 16835 33726 16836 33726 19456 33727 18134 33727 16840 33727 16840 33728 18134 33728 18133 33728 16840 33729 18133 33729 16841 33729 16841 33730 18133 33730 16843 33730 16841 33731 16843 33731 16842 33731 16842 33732 16843 33732 18131 33732 16842 33733 18131 33733 16844 33733 16844 33734 18131 33734 18130 33734 16844 33735 18130 33735 16845 33735 16845 33736 18130 33736 18129 33736 16845 33737 18129 33737 16838 33737 16838 33738 18129 33738 18127 33738 19438 33739 16846 33739 16847 33739 16847 33740 16846 33740 16848 33740 16847 33741 16848 33741 16849 33741 16849 33742 16848 33742 16850 33742 16849 33743 16850 33743 16857 33743 16857 33744 16850 33744 19384 33744 16857 33745 19384 33745 16859 33745 16859 33746 19384 33746 16851 33746 16859 33747 16851 33747 16852 33747 16852 33748 16851 33748 16854 33748 16852 33749 16854 33749 16853 33749 16853 33750 16854 33750 19448 33750 16863 33751 19438 33751 16855 33751 16855 33752 19438 33752 16847 33752 16855 33753 16847 33753 16856 33753 16856 33754 16847 33754 16849 33754 16856 33755 16849 33755 16862 33755 16862 33756 16849 33756 16857 33756 16862 33757 16857 33757 16860 33757 16860 33758 16857 33758 16859 33758 16860 33759 16859 33759 16858 33759 16858 33760 16859 33760 16852 33760 16858 33761 16852 33761 19430 33761 19430 33762 16852 33762 16853 33762 19430 33763 18113 33763 16858 33763 16858 33764 18113 33764 16861 33764 16858 33765 16861 33765 16860 33765 16860 33766 16861 33766 18115 33766 16860 33767 18115 33767 16862 33767 16862 33768 18115 33768 18116 33768 16862 33769 18116 33769 16856 33769 16856 33770 18116 33770 18117 33770 16856 33771 18117 33771 16855 33771 16855 33772 18117 33772 16864 33772 16855 33773 16864 33773 16863 33773 16863 33774 16864 33774 18119 33774 16865 33775 19510 33775 19409 33775 19409 33776 19510 33776 16786 33776 19409 33777 16786 33777 19410 33777 19410 33778 16786 33778 16787 33778 19410 33779 16787 33779 19413 33779 19413 33780 16787 33780 16789 33780 19413 33781 16789 33781 16866 33781 16866 33782 16789 33782 16790 33782 16866 33783 16790 33783 16867 33783 16867 33784 16790 33784 16791 33784 16867 33785 16791 33785 19417 33785 19417 33786 16791 33786 16792 33786 19394 33787 16869 33787 16868 33787 16868 33788 16869 33788 16798 33788 16868 33789 16798 33789 19395 33789 19395 33790 16798 33790 16870 33790 19395 33791 16870 33791 19396 33791 19396 33792 16870 33792 16872 33792 19396 33793 16872 33793 16871 33793 16871 33794 16872 33794 16801 33794 16871 33795 16801 33795 16873 33795 16873 33796 16801 33796 16797 33796 16873 33797 16797 33797 16874 33797 16874 33798 16797 33798 16795 33798 19377 33799 16802 33799 16875 33799 16875 33800 16802 33800 16876 33800 16875 33801 16876 33801 19385 33801 19385 33802 16876 33802 16877 33802 19385 33803 16877 33803 16878 33803 16878 33804 16877 33804 16879 33804 16878 33805 16879 33805 19383 33805 19383 33806 16879 33806 16807 33806 19383 33807 16807 33807 16880 33807 16880 33808 16807 33808 16808 33808 16880 33809 16808 33809 19382 33809 19382 33810 16808 33810 16809 33810 19367 33811 18563 33811 16881 33811 16881 33812 18563 33812 16882 33812 16881 33813 16882 33813 16890 33813 16890 33814 16882 33814 16883 33814 16890 33815 16883 33815 16884 33815 16884 33816 16883 33816 16885 33816 16884 33817 16885 33817 16886 33817 16886 33818 16885 33818 18286 33818 16886 33819 18286 33819 16887 33819 16887 33820 18286 33820 18287 33820 16887 33821 18287 33821 16893 33821 16893 33822 18287 33822 18288 33822 19351 33823 19367 33823 16888 33823 16888 33824 19367 33824 16881 33824 16888 33825 16881 33825 16895 33825 16895 33826 16881 33826 16890 33826 16895 33827 16890 33827 16889 33827 16889 33828 16890 33828 16884 33828 16889 33829 16884 33829 16891 33829 16891 33830 16884 33830 16886 33830 16891 33831 16886 33831 16892 33831 16892 33832 16886 33832 16887 33832 16892 33833 16887 33833 19346 33833 19346 33834 16887 33834 16893 33834 19346 33835 17919 33835 16892 33835 16892 33836 17919 33836 17921 33836 16892 33837 17921 33837 16891 33837 16891 33838 17921 33838 17923 33838 16891 33839 17923 33839 16889 33839 16889 33840 17923 33840 16894 33840 16889 33841 16894 33841 16895 33841 16895 33842 16894 33842 17925 33842 16895 33843 17925 33843 16888 33843 16888 33844 17925 33844 16896 33844 16888 33845 16896 33845 19351 33845 19351 33846 16896 33846 19352 33846 19345 33847 18283 33847 16900 33847 16900 33848 18283 33848 18276 33848 16900 33849 18276 33849 16902 33849 16902 33850 18276 33850 16897 33850 16902 33851 16897 33851 16904 33851 16904 33852 16897 33852 16898 33852 16904 33853 16898 33853 16905 33853 16905 33854 16898 33854 16899 33854 16905 33855 16899 33855 16908 33855 16908 33856 16899 33856 18272 33856 16908 33857 18272 33857 19332 33857 19332 33858 18272 33858 18629 33858 19329 33859 19345 33859 16910 33859 16910 33860 19345 33860 16900 33860 16910 33861 16900 33861 16901 33861 16901 33862 16900 33862 16902 33862 16901 33863 16902 33863 16903 33863 16903 33864 16902 33864 16904 33864 16903 33865 16904 33865 16909 33865 16909 33866 16904 33866 16905 33866 16909 33867 16905 33867 16906 33867 16906 33868 16905 33868 16908 33868 16906 33869 16908 33869 16907 33869 16907 33870 16908 33870 19332 33870 16907 33871 17906 33871 16906 33871 16906 33872 17906 33872 17907 33872 16906 33873 17907 33873 16909 33873 16909 33874 17907 33874 17908 33874 16909 33875 17908 33875 16903 33875 16903 33876 17908 33876 17910 33876 16903 33877 17910 33877 16901 33877 16901 33878 17910 33878 17912 33878 16901 33879 17912 33879 16910 33879 16910 33880 17912 33880 16911 33880 16910 33881 16911 33881 19329 33881 19329 33882 16911 33882 19330 33882 16917 33883 16912 33883 16918 33883 16918 33884 16912 33884 18269 33884 16918 33885 18269 33885 16913 33885 16913 33886 18269 33886 18268 33886 16913 33887 18268 33887 16914 33887 16914 33888 18268 33888 18267 33888 16914 33889 18267 33889 16920 33889 16920 33890 18267 33890 16915 33890 16920 33891 16915 33891 16922 33891 16922 33892 16915 33892 18264 33892 16922 33893 18264 33893 16916 33893 16916 33894 18264 33894 18263 33894 16916 33895 18263 33895 19313 33895 19313 33896 18263 33896 18260 33896 16931 33897 16917 33897 16929 33897 16929 33898 16917 33898 16918 33898 16929 33899 16918 33899 16919 33899 16919 33900 16918 33900 16913 33900 16919 33901 16913 33901 16927 33901 16927 33902 16913 33902 16914 33902 16927 33903 16914 33903 16921 33903 16921 33904 16914 33904 16920 33904 16921 33905 16920 33905 16923 33905 16923 33906 16920 33906 16922 33906 16923 33907 16922 33907 16924 33907 16924 33908 16922 33908 16916 33908 16924 33909 16916 33909 19305 33909 19305 33910 16916 33910 19313 33910 19305 33911 17899 33911 16924 33911 16924 33912 17899 33912 17901 33912 16924 33913 17901 33913 16923 33913 16923 33914 17901 33914 17902 33914 16923 33915 17902 33915 16921 33915 16921 33916 17902 33916 16925 33916 16921 33917 16925 33917 16927 33917 16927 33918 16925 33918 16926 33918 16927 33919 16926 33919 16919 33919 16919 33920 16926 33920 16928 33920 16919 33921 16928 33921 16929 33921 16929 33922 16928 33922 16930 33922 16929 33923 16930 33923 16931 33923 16931 33924 16930 33924 17894 33924 16932 33925 18251 33925 16933 33925 16933 33926 18251 33926 16934 33926 16933 33927 16934 33927 16942 33927 16942 33928 16934 33928 16935 33928 16942 33929 16935 33929 16936 33929 16936 33930 16935 33930 16937 33930 16936 33931 16937 33931 16944 33931 16944 33932 16937 33932 16938 33932 16944 33933 16938 33933 16939 33933 16939 33934 16938 33934 16940 33934 16939 33935 16940 33935 19295 33935 19295 33936 16940 33936 18580 33936 19282 33937 16932 33937 16947 33937 16947 33938 16932 33938 16933 33938 16947 33939 16933 33939 16941 33939 16941 33940 16933 33940 16948 33940 16948 33941 16933 33941 16942 33941 16948 33942 16942 33942 16949 33942 16949 33943 16942 33943 16950 33943 16950 33944 16942 33944 16936 33944 16950 33945 16936 33945 16951 33945 16951 33946 16936 33946 16943 33946 16943 33947 16936 33947 16944 33947 16943 33948 16944 33948 16953 33948 16953 33949 16944 33949 16954 33949 16954 33950 16944 33950 16939 33950 16954 33951 16939 33951 16957 33951 16957 33952 16939 33952 16945 33952 16945 33953 16939 33953 19295 33953 16945 33954 19295 33954 16946 33954 17889 33955 19284 33955 19282 33955 19282 33956 16947 33956 17889 33956 17889 33957 16947 33957 16941 33957 17889 33958 16941 33958 17888 33958 16941 33959 16948 33959 17888 33959 17888 33960 16948 33960 16949 33960 17888 33961 16949 33961 17886 33961 16949 33962 16950 33962 17886 33962 17886 33963 16950 33963 16951 33963 17886 33964 16951 33964 17885 33964 17885 33965 16951 33965 16943 33965 17885 33966 16943 33966 16952 33966 16943 33967 16953 33967 16952 33967 16952 33968 16953 33968 16954 33968 16952 33969 16954 33969 16956 33969 16946 33970 16955 33970 16945 33970 16945 33971 16955 33971 16956 33971 16945 33972 16956 33972 16957 33972 16957 33973 16956 33973 16954 33973 17041 33974 19271 33974 17042 33974 17042 33975 19271 33975 16958 33975 17042 33976 16958 33976 16960 33976 16960 33977 16958 33977 16959 33977 16960 33978 16959 33978 17044 33978 17044 33979 16959 33979 16961 33979 17044 33980 16961 33980 16962 33980 16962 33981 16961 33981 18299 33981 16962 33982 18299 33982 16963 33982 16963 33983 18299 33983 18298 33983 16963 33984 18298 33984 16964 33984 16964 33985 18298 33985 19278 33985 17047 33986 18266 33986 17048 33986 17048 33987 18266 33987 18271 33987 17048 33988 18271 33988 17049 33988 17049 33989 18271 33989 16965 33989 17049 33990 16965 33990 16966 33990 16966 33991 16965 33991 18284 33991 16966 33992 18284 33992 17050 33992 17050 33993 18284 33993 16967 33993 17050 33994 16967 33994 16968 33994 16968 33995 16967 33995 18282 33995 16968 33996 18282 33996 17051 33996 17051 33997 18282 33997 16969 33997 17051 33998 16969 33998 19175 33998 19175 33999 16969 33999 18277 33999 18248 34000 19156 34000 16970 34000 16970 34001 19156 34001 16971 34001 16970 34002 16971 34002 16972 34002 16972 34003 16971 34003 17057 34003 17057 34004 17056 34004 16972 34004 16972 34005 17056 34005 17055 34005 16972 34006 17055 34006 16973 34006 17055 34007 17054 34007 16973 34007 16973 34008 17054 34008 16974 34008 16973 34009 16974 34009 16977 34009 19161 34010 18255 34010 17053 34010 17053 34011 18255 34011 18253 34011 17053 34012 18253 34012 16975 34012 16975 34013 18253 34013 16977 34013 16975 34014 16977 34014 16976 34014 16976 34015 16977 34015 16974 34015 16986 34016 19198 34016 16987 34016 16987 34017 19198 34017 16978 34017 16987 34018 16978 34018 16988 34018 16988 34019 16978 34019 19196 34019 16988 34020 19196 34020 16979 34020 16979 34021 19196 34021 19195 34021 16979 34022 19195 34022 16980 34022 16980 34023 19195 34023 16981 34023 16980 34024 16981 34024 16982 34024 16982 34025 16981 34025 16983 34025 16982 34026 16983 34026 16984 34026 16984 34027 16983 34027 19251 34027 16985 34028 16986 34028 16997 34028 16997 34029 16986 34029 16987 34029 16997 34030 16987 34030 16989 34030 16989 34031 16987 34031 16988 34031 16989 34032 16988 34032 16990 34032 16990 34033 16988 34033 16979 34033 16990 34034 16979 34034 16994 34034 16994 34035 16979 34035 16980 34035 16994 34036 16980 34036 16991 34036 16991 34037 16980 34037 16982 34037 16991 34038 16982 34038 16992 34038 16992 34039 16982 34039 16984 34039 16992 34040 16993 34040 16991 34040 16991 34041 16993 34041 16995 34041 16991 34042 16995 34042 16994 34042 16994 34043 16995 34043 17972 34043 16994 34044 17972 34044 16990 34044 16990 34045 17972 34045 16996 34045 16990 34046 16996 34046 16989 34046 16989 34047 16996 34047 17974 34047 16989 34048 17974 34048 16997 34048 16997 34049 17974 34049 16998 34049 16997 34050 16998 34050 16985 34050 16985 34051 16998 34051 16999 34051 19238 34052 19239 34052 17004 34052 17004 34053 19239 34053 17000 34053 17004 34054 17000 34054 17007 34054 17007 34055 17000 34055 18659 34055 17007 34056 18659 34056 17008 34056 17008 34057 18659 34057 17001 34057 17008 34058 17001 34058 17002 34058 17002 34059 17001 34059 18649 34059 17002 34060 18649 34060 17010 34060 17010 34061 18649 34061 18650 34061 17010 34062 18650 34062 17013 34062 17013 34063 18650 34063 17003 34063 17013 34064 17003 34064 19231 34064 19231 34065 17003 34065 18653 34065 19230 34066 19238 34066 17005 34066 17005 34067 19238 34067 17004 34067 17005 34068 17004 34068 17006 34068 17006 34069 17004 34069 17007 34069 17006 34070 17007 34070 17016 34070 17016 34071 17007 34071 17008 34071 17016 34072 17008 34072 17009 34072 17009 34073 17008 34073 17002 34073 17009 34074 17002 34074 17011 34074 17011 34075 17002 34075 17010 34075 17011 34076 17010 34076 17012 34076 17012 34077 17010 34077 17013 34077 17012 34078 17013 34078 19226 34078 19226 34079 17013 34079 19231 34079 19226 34080 19225 34080 17012 34080 17012 34081 19225 34081 17014 34081 17012 34082 17014 34082 17011 34082 17011 34083 17014 34083 17015 34083 17011 34084 17015 34084 17009 34084 17009 34085 17015 34085 17965 34085 17009 34086 17965 34086 17016 34086 17016 34087 17965 34087 17950 34087 17016 34088 17950 34088 17006 34088 17006 34089 17950 34089 17017 34089 17006 34090 17017 34090 17005 34090 17005 34091 17017 34091 17952 34091 17005 34092 17952 34092 19230 34092 19230 34093 17952 34093 17955 34093 17026 34094 17018 34094 17029 34094 17029 34095 17018 34095 17019 34095 17029 34096 17019 34096 17020 34096 17020 34097 17019 34097 19162 34097 17020 34098 19162 34098 17022 34098 17022 34099 19162 34099 17021 34099 17022 34100 17021 34100 17023 34100 17023 34101 17021 34101 17024 34101 17023 34102 17024 34102 17031 34102 17031 34103 17024 34103 17025 34103 17031 34104 17025 34104 17032 34104 17032 34105 17025 34105 19167 34105 17032 34106 19167 34106 19211 34106 19211 34107 19167 34107 19212 34107 17040 34108 17026 34108 17027 34108 17027 34109 17026 34109 17029 34109 17027 34110 17029 34110 17028 34110 17028 34111 17029 34111 17020 34111 17028 34112 17020 34112 17030 34112 17030 34113 17020 34113 17022 34113 17030 34114 17022 34114 17038 34114 17038 34115 17022 34115 17023 34115 17038 34116 17023 34116 17037 34116 17037 34117 17023 34117 17031 34117 17037 34118 17031 34118 17035 34118 17035 34119 17031 34119 17032 34119 17035 34120 17032 34120 17033 34120 17033 34121 17032 34121 19211 34121 17033 34122 17034 34122 17035 34122 17035 34123 17034 34123 17036 34123 17035 34124 17036 34124 17037 34124 17037 34125 17036 34125 17934 34125 17037 34126 17934 34126 17038 34126 17038 34127 17934 34127 17039 34127 17038 34128 17039 34128 17030 34128 17030 34129 17039 34129 17935 34129 17030 34130 17935 34130 17028 34130 17028 34131 17935 34131 17937 34131 17028 34132 17937 34132 17027 34132 17027 34133 17937 34133 17939 34133 17027 34134 17939 34134 17040 34134 17040 34135 17939 34135 17941 34135 19189 34136 17041 34136 19197 34136 19197 34137 17041 34137 17042 34137 19197 34138 17042 34138 19194 34138 19194 34139 17042 34139 16960 34139 19194 34140 16960 34140 17043 34140 17043 34141 16960 34141 17044 34141 17043 34142 17044 34142 17045 34142 17045 34143 17044 34143 16962 34143 17045 34144 16962 34144 17046 34144 17046 34145 16962 34145 16963 34145 17046 34146 16963 34146 19193 34146 19193 34147 16963 34147 16964 34147 18658 34148 17047 34148 18660 34148 18660 34149 17047 34149 17048 34149 18660 34150 17048 34150 18661 34150 18661 34151 17048 34151 17049 34151 18661 34152 17049 34152 18662 34152 18662 34153 17049 34153 16966 34153 18662 34154 16966 34154 18651 34154 18651 34155 16966 34155 17050 34155 18651 34156 17050 34156 18652 34156 18652 34157 17050 34157 16968 34157 18652 34158 16968 34158 18654 34158 18654 34159 16968 34159 17051 34159 18654 34160 17051 34160 17052 34160 17052 34161 17051 34161 19175 34161 19172 34162 19161 34162 17053 34162 19172 34163 17053 34163 19173 34163 19173 34164 17053 34164 16975 34164 19173 34165 16975 34165 19163 34165 19163 34166 16975 34166 16976 34166 19163 34167 16976 34167 19164 34167 16976 34168 16974 34168 19164 34168 19164 34169 16974 34169 17054 34169 19164 34170 17054 34170 19165 34170 17054 34171 17055 34171 19165 34171 19165 34172 17055 34172 17056 34172 19165 34173 17056 34173 19166 34173 17056 34174 17057 34174 19166 34174 19166 34175 17057 34175 16971 34175 19166 34176 16971 34176 17058 34176 17058 34177 16971 34177 19156 34177 17058 34178 19156 34178 19168 34178 19148 34179 18301 34179 17059 34179 17059 34180 18301 34180 18303 34180 17059 34181 18303 34181 17065 34181 17065 34182 18303 34182 18311 34182 17065 34183 18311 34183 17067 34183 17067 34184 18311 34184 17060 34184 17067 34185 17060 34185 17068 34185 17068 34186 17060 34186 17061 34186 17068 34187 17061 34187 17069 34187 17069 34188 17061 34188 18309 34188 17069 34189 18309 34189 17062 34189 17062 34190 18309 34190 18308 34190 17062 34191 18308 34191 19140 34191 19140 34192 18308 34192 19149 34192 19146 34193 19148 34193 17063 34193 17063 34194 19148 34194 17059 34194 17063 34195 17059 34195 17064 34195 17064 34196 17059 34196 17065 34196 17064 34197 17065 34197 17074 34197 17074 34198 17065 34198 17067 34198 17074 34199 17067 34199 17066 34199 17066 34200 17067 34200 17068 34200 17066 34201 17068 34201 17072 34201 17072 34202 17068 34202 17069 34202 17072 34203 17069 34203 17071 34203 17071 34204 17069 34204 17062 34204 17071 34205 17062 34205 17070 34205 17070 34206 17062 34206 19140 34206 17070 34207 18022 34207 17071 34207 17071 34208 18022 34208 18024 34208 17071 34209 18024 34209 17072 34209 17072 34210 18024 34210 18026 34210 17072 34211 18026 34211 17066 34211 17066 34212 18026 34212 17073 34212 17066 34213 17073 34213 17074 34213 17074 34214 17073 34214 17075 34214 17074 34215 17075 34215 17064 34215 17064 34216 17075 34216 17076 34216 17064 34217 17076 34217 17063 34217 17063 34218 17076 34218 18016 34218 17063 34219 18016 34219 19146 34219 19146 34220 18016 34220 17077 34220 19132 34221 17079 34221 17078 34221 17078 34222 17079 34222 17080 34222 17078 34223 17080 34223 17086 34223 17086 34224 17080 34224 17081 34224 17086 34225 17081 34225 17082 34225 17082 34226 17081 34226 17083 34226 17082 34227 17083 34227 17087 34227 17087 34228 17083 34228 18312 34228 17087 34229 18312 34229 17088 34229 17088 34230 18312 34230 17084 34230 17088 34231 17084 34231 17090 34231 17090 34232 17084 34232 17085 34232 17090 34233 17085 34233 19127 34233 19127 34234 17085 34234 18343 34234 17102 34235 19132 34235 17101 34235 17101 34236 19132 34236 17078 34236 17101 34237 17078 34237 17099 34237 17099 34238 17078 34238 17086 34238 17099 34239 17086 34239 17097 34239 17097 34240 17086 34240 17082 34240 17097 34241 17082 34241 17096 34241 17096 34242 17082 34242 17087 34242 17096 34243 17087 34243 17092 34243 17092 34244 17087 34244 17088 34244 17092 34245 17088 34245 17089 34245 17089 34246 17088 34246 17090 34246 17089 34247 17090 34247 17091 34247 17091 34248 17090 34248 19127 34248 17091 34249 18014 34249 17089 34249 17089 34250 18014 34250 17093 34250 17089 34251 17093 34251 17092 34251 17092 34252 17093 34252 17094 34252 17092 34253 17094 34253 17096 34253 17096 34254 17094 34254 17095 34254 17096 34255 17095 34255 17097 34255 17097 34256 17095 34256 17098 34256 17097 34257 17098 34257 17099 34257 17099 34258 17098 34258 17100 34258 17099 34259 17100 34259 17101 34259 17101 34260 17100 34260 18004 34260 17101 34261 18004 34261 17102 34261 17102 34262 18004 34262 17103 34262 19114 34263 19121 34263 17104 34263 17104 34264 19121 34264 18323 34264 17104 34265 18323 34265 17112 34265 17112 34266 18323 34266 17105 34266 17112 34267 17105 34267 17106 34267 17106 34268 17105 34268 18330 34268 17106 34269 18330 34269 17107 34269 17107 34270 18330 34270 17108 34270 17107 34271 17108 34271 17115 34271 17115 34272 17108 34272 18329 34272 17115 34273 18329 34273 17116 34273 17116 34274 18329 34274 17109 34274 17116 34275 17109 34275 19110 34275 19110 34276 17109 34276 19115 34276 17122 34277 19114 34277 17110 34277 17110 34278 19114 34278 17104 34278 17110 34279 17104 34279 17111 34279 17111 34280 17104 34280 17112 34280 17111 34281 17112 34281 17121 34281 17121 34282 17112 34282 17106 34282 17121 34283 17106 34283 17113 34283 17113 34284 17106 34284 17107 34284 17113 34285 17107 34285 17114 34285 17114 34286 17107 34286 17115 34286 17114 34287 17115 34287 17118 34287 17118 34288 17115 34288 17116 34288 17118 34289 17116 34289 19108 34289 19108 34290 17116 34290 19110 34290 19108 34291 17117 34291 17118 34291 17118 34292 17117 34292 17994 34292 17118 34293 17994 34293 17114 34293 17114 34294 17994 34294 17119 34294 17114 34295 17119 34295 17113 34295 17113 34296 17119 34296 17120 34296 17113 34297 17120 34297 17121 34297 17121 34298 17120 34298 17997 34298 17121 34299 17997 34299 17111 34299 17111 34300 17997 34300 17998 34300 17111 34301 17998 34301 17110 34301 17110 34302 17998 34302 18001 34302 17110 34303 18001 34303 17122 34303 17122 34304 18001 34304 19102 34304 19101 34305 18331 34305 17129 34305 17129 34306 18331 34306 17123 34306 17129 34307 17123 34307 17131 34307 17131 34308 17123 34308 18333 34308 17131 34309 18333 34309 17124 34309 17124 34310 18333 34310 17125 34310 17124 34311 17125 34311 17133 34311 17133 34312 17125 34312 18336 34312 17133 34313 18336 34313 17126 34313 17126 34314 18336 34314 18340 34314 17126 34315 18340 34315 17127 34315 17127 34316 18340 34316 18339 34316 17128 34317 19101 34317 17140 34317 17140 34318 19101 34318 17129 34318 17140 34319 17129 34319 17130 34319 17130 34320 17129 34320 17131 34320 17130 34321 17131 34321 17132 34321 17132 34322 17131 34322 17124 34322 17132 34323 17124 34323 17137 34323 17137 34324 17124 34324 17133 34324 17137 34325 17133 34325 17135 34325 17135 34326 17133 34326 17126 34326 17135 34327 17126 34327 17134 34327 17134 34328 17126 34328 17127 34328 17134 34329 17136 34329 17135 34329 17135 34330 17136 34330 17988 34330 17135 34331 17988 34331 17137 34331 17137 34332 17988 34332 17138 34332 17137 34333 17138 34333 17132 34333 17132 34334 17138 34334 17139 34334 17132 34335 17139 34335 17130 34335 17130 34336 17139 34336 17141 34336 17130 34337 17141 34337 17140 34337 17140 34338 17141 34338 17985 34338 17140 34339 17985 34339 17128 34339 17128 34340 17985 34340 17982 34340 17230 34341 17142 34341 17231 34341 17231 34342 17142 34342 18591 34342 17231 34343 18591 34343 17143 34343 17143 34344 18591 34344 18353 34344 17143 34345 18353 34345 17144 34345 17144 34346 18353 34346 17145 34346 17144 34347 17145 34347 17146 34347 17146 34348 17145 34348 18351 34348 17146 34349 18351 34349 17234 34349 17234 34350 18351 34350 18356 34350 17234 34351 18356 34351 17235 34351 17235 34352 18356 34352 18355 34352 18952 34353 18348 34353 17239 34353 17239 34354 18348 34354 18347 34354 17239 34355 18347 34355 17148 34355 17148 34356 18347 34356 17147 34356 17148 34357 17147 34357 17149 34357 17149 34358 17147 34358 17150 34358 17149 34359 17150 34359 17151 34359 17151 34360 17150 34360 18349 34360 17151 34361 18349 34361 17240 34361 17240 34362 18349 34362 17152 34362 17240 34363 17152 34363 18947 34363 18947 34364 17152 34364 18320 34364 17154 34365 18535 34365 19063 34365 19063 34366 17252 34366 17154 34366 17154 34367 17252 34367 17153 34367 17154 34368 17153 34368 18536 34368 17153 34369 17249 34369 18536 34369 18536 34370 17249 34370 17155 34370 18536 34371 17155 34371 17157 34371 17155 34372 17156 34372 17157 34372 17157 34373 17156 34373 17248 34373 17157 34374 17248 34374 17158 34374 17158 34375 17248 34375 17247 34375 17158 34376 17247 34376 17160 34376 17247 34377 17159 34377 17160 34377 17160 34378 17159 34378 17246 34378 17160 34379 17246 34379 17161 34379 17242 34380 18642 34380 17243 34380 17243 34381 18642 34381 17161 34381 17243 34382 17161 34382 17245 34382 17245 34383 17161 34383 17246 34383 17171 34384 17162 34384 17172 34384 17172 34385 17162 34385 17164 34385 17172 34386 17164 34386 17163 34386 17163 34387 17164 34387 17166 34387 17163 34388 17166 34388 17165 34388 17165 34389 17166 34389 17167 34389 17165 34390 17167 34390 17175 34390 17175 34391 17167 34391 17168 34391 17175 34392 17168 34392 17176 34392 17176 34393 17168 34393 17169 34393 17176 34394 17169 34394 17170 34394 17170 34395 17169 34395 18979 34395 19053 34396 17171 34396 17181 34396 17181 34397 17171 34397 17172 34397 17181 34398 17172 34398 17173 34398 17173 34399 17172 34399 17163 34399 17173 34400 17163 34400 17180 34400 17180 34401 17163 34401 17165 34401 17180 34402 17165 34402 17174 34402 17174 34403 17165 34403 17175 34403 17174 34404 17175 34404 17179 34404 17179 34405 17175 34405 17176 34405 17179 34406 17176 34406 17177 34406 17177 34407 17176 34407 17170 34407 17177 34408 17178 34408 17179 34408 17179 34409 17178 34409 18057 34409 17179 34410 18057 34410 17174 34410 17174 34411 18057 34411 18060 34411 17174 34412 18060 34412 17180 34412 17180 34413 18060 34413 18061 34413 17180 34414 18061 34414 17173 34414 17173 34415 18061 34415 17182 34415 17173 34416 17182 34416 17181 34416 17181 34417 17182 34417 18062 34417 17181 34418 18062 34418 19053 34418 19053 34419 18062 34419 19038 34419 18966 34420 18964 34420 19028 34420 19028 34421 17183 34421 18966 34421 18966 34422 17183 34422 17201 34422 18966 34423 17201 34423 17184 34423 17201 34424 17199 34424 17184 34424 17184 34425 17199 34425 17185 34425 17184 34426 17185 34426 18953 34426 17185 34427 17186 34427 18953 34427 18953 34428 17186 34428 17196 34428 18953 34429 17196 34429 18955 34429 18955 34430 17196 34430 17188 34430 18955 34431 17188 34431 17187 34431 17188 34432 17195 34432 17187 34432 17187 34433 17195 34433 17192 34433 17187 34434 17192 34434 17189 34434 17190 34435 17191 34435 17193 34435 17193 34436 17191 34436 17189 34436 17193 34437 17189 34437 17194 34437 17194 34438 17189 34438 17192 34438 17190 34439 17193 34439 17208 34439 17208 34440 17193 34440 17207 34440 17193 34441 17194 34441 17207 34441 17207 34442 17194 34442 17192 34442 17207 34443 17192 34443 17206 34443 17192 34444 17195 34444 17206 34444 17206 34445 17195 34445 17188 34445 17206 34446 17188 34446 17197 34446 17188 34447 17196 34447 17197 34447 17197 34448 17196 34448 17186 34448 17197 34449 17186 34449 17198 34449 17186 34450 17185 34450 17198 34450 17198 34451 17185 34451 17199 34451 17198 34452 17199 34452 17200 34452 19028 34453 19027 34453 17183 34453 17183 34454 19027 34454 17200 34454 17183 34455 17200 34455 17201 34455 17201 34456 17200 34456 17199 34456 19027 34457 18045 34457 17200 34457 17200 34458 18045 34458 17202 34458 17200 34459 17202 34459 17198 34459 17198 34460 17202 34460 17203 34460 17198 34461 17203 34461 17197 34461 17197 34462 17203 34462 17204 34462 17197 34463 17204 34463 17206 34463 17206 34464 17204 34464 17205 34464 17206 34465 17205 34465 17207 34465 17207 34466 17205 34466 18050 34466 17207 34467 18050 34467 17208 34467 17208 34468 18050 34468 17209 34468 19013 34469 17210 34469 18945 34469 18945 34470 17210 34470 17223 34470 18945 34471 17223 34471 18944 34471 17223 34472 17222 34472 18944 34472 18944 34473 17222 34473 17211 34473 18944 34474 17211 34474 18943 34474 18943 34475 17211 34475 17220 34475 17220 34476 17212 34476 18943 34476 18943 34477 17212 34477 17219 34477 18943 34478 17219 34478 17213 34478 19002 34479 19001 34479 17214 34479 17214 34480 19001 34480 18940 34480 17214 34481 18940 34481 17216 34481 17216 34482 18940 34482 17213 34482 17216 34483 17213 34483 17218 34483 17218 34484 17213 34484 17219 34484 18999 34485 19002 34485 17214 34485 18999 34486 17214 34486 17215 34486 17215 34487 17214 34487 17216 34487 17215 34488 17216 34488 17217 34488 17217 34489 17216 34489 17218 34489 17217 34490 17218 34490 17227 34490 17218 34491 17219 34491 17227 34491 17227 34492 17219 34492 17212 34492 17227 34493 17212 34493 17225 34493 17212 34494 17220 34494 17225 34494 17225 34495 17220 34495 17211 34495 17225 34496 17211 34496 17221 34496 17211 34497 17222 34497 17221 34497 17221 34498 17222 34498 17223 34498 17221 34499 17223 34499 17224 34499 17224 34500 17223 34500 17210 34500 17224 34501 17210 34501 18991 34501 18991 34502 18990 34502 17224 34502 17224 34503 18990 34503 18038 34503 17224 34504 18038 34504 17221 34504 17221 34505 18038 34505 18040 34505 17221 34506 18040 34506 17225 34506 17225 34507 18040 34507 17226 34507 17225 34508 17226 34508 17227 34508 17227 34509 17226 34509 17228 34509 17227 34510 17228 34510 17217 34510 17217 34511 17228 34511 18029 34511 17217 34512 18029 34512 17215 34512 17215 34513 18029 34513 17229 34513 17215 34514 17229 34514 18999 34514 18999 34515 17229 34515 18030 34515 18975 34516 17230 34516 18976 34516 18976 34517 17230 34517 17231 34517 18976 34518 17231 34518 18977 34518 18977 34519 17231 34519 17143 34519 18977 34520 17143 34520 17232 34520 17232 34521 17143 34521 17144 34521 17232 34522 17144 34522 18978 34522 18978 34523 17144 34523 17146 34523 18978 34524 17146 34524 17233 34524 17233 34525 17146 34525 17234 34525 17233 34526 17234 34526 18981 34526 18981 34527 17234 34527 17235 34527 17236 34528 18952 34528 17237 34528 17237 34529 18952 34529 17239 34529 17237 34530 17239 34530 17238 34530 17238 34531 17239 34531 17148 34531 17238 34532 17148 34532 18954 34532 18954 34533 17148 34533 17149 34533 18954 34534 17149 34534 18967 34534 18967 34535 17149 34535 17151 34535 18967 34536 17151 34536 18965 34536 18965 34537 17151 34537 17240 34537 18965 34538 17240 34538 17241 34538 17241 34539 17240 34539 18947 34539 17242 34540 17243 34540 18939 34540 18939 34541 17243 34541 17244 34541 17243 34542 17245 34542 17244 34542 17244 34543 17245 34543 17246 34543 17244 34544 17246 34544 18941 34544 17246 34545 17159 34545 18941 34545 18941 34546 17159 34546 17247 34546 18941 34547 17247 34547 18942 34547 17247 34548 17248 34548 18942 34548 18942 34549 17248 34549 17156 34549 18942 34550 17156 34550 17250 34550 17156 34551 17155 34551 17250 34551 17250 34552 17155 34552 17249 34552 17250 34553 17249 34553 17251 34553 19063 34554 18946 34554 17252 34554 17252 34555 18946 34555 17251 34555 17252 34556 17251 34556 17153 34556 17153 34557 17251 34557 17249 34557 18918 34558 18924 34558 17258 34558 17258 34559 18924 34559 18371 34559 17258 34560 18371 34560 17261 34560 17261 34561 18371 34561 18369 34561 17261 34562 18369 34562 17253 34562 17253 34563 18369 34563 17254 34563 17253 34564 17254 34564 17264 34564 17264 34565 17254 34565 17255 34565 17264 34566 17255 34566 17268 34566 17268 34567 17255 34567 18365 34567 17268 34568 18365 34568 18912 34568 18912 34569 18365 34569 17256 34569 17270 34570 18918 34570 17257 34570 17257 34571 18918 34571 17258 34571 17257 34572 17258 34572 17271 34572 17271 34573 17258 34573 17259 34573 17259 34574 17258 34574 17261 34574 17259 34575 17261 34575 17260 34575 17260 34576 17261 34576 17262 34576 17262 34577 17261 34577 17253 34577 17262 34578 17253 34578 17263 34578 17263 34579 17253 34579 17265 34579 17265 34580 17253 34580 17264 34580 17265 34581 17264 34581 17266 34581 17266 34582 17264 34582 17267 34582 17267 34583 17264 34583 17268 34583 17267 34584 17268 34584 17277 34584 17277 34585 17268 34585 17276 34585 17276 34586 17268 34586 18912 34586 17276 34587 18912 34587 17274 34587 17812 34588 17269 34588 17270 34588 17270 34589 17257 34589 17812 34589 17812 34590 17257 34590 17271 34590 17812 34591 17271 34591 17809 34591 17271 34592 17259 34592 17809 34592 17809 34593 17259 34593 17260 34593 17809 34594 17260 34594 17272 34594 17260 34595 17262 34595 17272 34595 17272 34596 17262 34596 17263 34596 17272 34597 17263 34597 17821 34597 17821 34598 17263 34598 17265 34598 17821 34599 17265 34599 17820 34599 17265 34600 17266 34600 17820 34600 17820 34601 17266 34601 17267 34601 17820 34602 17267 34602 17273 34602 17274 34603 17275 34603 17276 34603 17276 34604 17275 34604 17273 34604 17276 34605 17273 34605 17277 34605 17277 34606 17273 34606 17267 34606 17278 34607 18894 34607 17282 34607 17282 34608 18894 34608 18375 34608 17282 34609 18375 34609 17284 34609 17284 34610 18375 34610 17279 34610 17284 34611 17279 34611 17285 34611 17285 34612 17279 34612 17280 34612 17285 34613 17280 34613 17288 34613 17288 34614 17280 34614 18374 34614 17288 34615 18374 34615 17289 34615 17289 34616 18374 34616 17281 34616 17289 34617 17281 34617 18887 34617 18887 34618 17281 34618 18609 34618 18881 34619 17278 34619 17293 34619 17293 34620 17278 34620 17282 34620 17293 34621 17282 34621 17283 34621 17283 34622 17282 34622 17284 34622 17283 34623 17284 34623 17286 34623 17286 34624 17284 34624 17285 34624 17286 34625 17285 34625 17287 34625 17287 34626 17285 34626 17288 34626 17287 34627 17288 34627 17290 34627 17290 34628 17288 34628 17289 34628 17290 34629 17289 34629 18888 34629 18888 34630 17289 34630 18887 34630 18888 34631 18886 34631 17290 34631 17290 34632 18886 34632 17832 34632 17290 34633 17832 34633 17287 34633 17287 34634 17832 34634 17833 34634 17287 34635 17833 34635 17286 34635 17286 34636 17833 34636 17291 34636 17286 34637 17291 34637 17283 34637 17283 34638 17291 34638 17292 34638 17283 34639 17292 34639 17293 34639 17293 34640 17292 34640 17835 34640 17293 34641 17835 34641 18881 34641 18881 34642 17835 34642 17294 34642 17304 34643 18394 34643 17305 34643 17305 34644 18394 34644 18489 34644 17305 34645 18489 34645 17307 34645 17307 34646 18489 34646 17295 34646 17307 34647 17295 34647 17296 34647 17296 34648 17295 34648 17297 34648 17296 34649 17297 34649 17309 34649 17309 34650 17297 34650 17298 34650 17309 34651 17298 34651 17310 34651 17310 34652 17298 34652 18403 34652 17310 34653 18403 34653 17299 34653 17299 34654 18403 34654 17300 34654 17299 34655 17300 34655 18871 34655 18871 34656 17300 34656 17301 34656 17302 34657 17304 34657 17303 34657 17303 34658 17304 34658 17305 34658 17303 34659 17305 34659 17306 34659 17306 34660 17305 34660 17307 34660 17306 34661 17307 34661 17316 34661 17316 34662 17307 34662 17296 34662 17316 34663 17296 34663 17308 34663 17308 34664 17296 34664 17309 34664 17308 34665 17309 34665 17311 34665 17311 34666 17309 34666 17310 34666 17311 34667 17310 34667 17312 34667 17312 34668 17310 34668 17299 34668 17312 34669 17299 34669 17313 34669 17313 34670 17299 34670 18871 34670 17313 34671 17844 34671 17312 34671 17312 34672 17844 34672 17314 34672 17312 34673 17314 34673 17311 34673 17311 34674 17314 34674 17842 34674 17311 34675 17842 34675 17308 34675 17308 34676 17842 34676 17840 34676 17308 34677 17840 34677 17316 34677 17316 34678 17840 34678 17315 34678 17316 34679 17315 34679 17306 34679 17306 34680 17315 34680 17838 34680 17306 34681 17838 34681 17303 34681 17303 34682 17838 34682 17837 34682 17303 34683 17837 34683 17302 34683 17302 34684 17837 34684 18865 34684 18859 34685 18484 34685 17321 34685 17321 34686 18484 34686 17317 34686 17321 34687 17317 34687 17318 34687 17318 34688 17317 34688 18479 34688 17318 34689 18479 34689 17319 34689 17319 34690 18479 34690 18478 34690 17319 34691 18478 34691 17326 34691 17326 34692 18478 34692 18477 34692 17326 34693 18477 34693 17327 34693 17327 34694 18477 34694 18476 34694 17327 34695 18476 34695 17320 34695 17320 34696 18476 34696 18475 34696 17328 34697 18859 34697 17329 34697 17329 34698 18859 34698 17321 34698 17329 34699 17321 34699 17330 34699 17330 34700 17321 34700 17322 34700 17322 34701 17321 34701 17318 34701 17322 34702 17318 34702 17332 34702 17332 34703 17318 34703 17323 34703 17323 34704 17318 34704 17319 34704 17323 34705 17319 34705 17333 34705 17333 34706 17319 34706 17324 34706 17324 34707 17319 34707 17326 34707 17324 34708 17326 34708 17336 34708 17336 34709 17326 34709 17325 34709 17325 34710 17326 34710 17327 34710 17325 34711 17327 34711 17339 34711 17339 34712 17327 34712 17338 34712 17338 34713 17327 34713 17320 34713 17338 34714 17320 34714 18848 34714 17853 34715 18844 34715 17328 34715 17328 34716 17329 34716 17853 34716 17853 34717 17329 34717 17330 34717 17853 34718 17330 34718 17331 34718 17330 34719 17322 34719 17331 34719 17331 34720 17322 34720 17332 34720 17331 34721 17332 34721 17334 34721 17332 34722 17323 34722 17334 34722 17334 34723 17323 34723 17333 34723 17334 34724 17333 34724 17335 34724 17335 34725 17333 34725 17324 34725 17335 34726 17324 34726 17863 34726 17324 34727 17336 34727 17863 34727 17863 34728 17336 34728 17325 34728 17863 34729 17325 34729 17861 34729 18848 34730 17337 34730 17338 34730 17338 34731 17337 34731 17861 34731 17338 34732 17861 34732 17339 34732 17339 34733 17861 34733 17325 34733 17418 34734 17340 34734 17341 34734 17341 34735 17340 34735 18366 34735 17341 34736 18366 34736 17419 34736 17419 34737 18366 34737 18364 34737 17419 34738 18364 34738 17420 34738 17420 34739 18364 34739 17342 34739 17420 34740 17342 34740 17421 34740 17421 34741 17342 34741 18363 34741 17421 34742 18363 34742 17343 34742 17343 34743 18363 34743 18362 34743 17343 34744 18362 34744 18739 34744 18739 34745 18362 34745 18834 34745 17425 34746 18401 34746 17344 34746 17344 34747 18401 34747 18395 34747 17344 34748 18395 34748 17426 34748 17426 34749 18395 34749 18396 34749 17426 34750 18396 34750 17429 34750 17429 34751 18396 34751 18405 34751 17429 34752 18405 34752 17346 34752 17346 34753 18405 34753 17345 34753 17346 34754 17345 34754 17432 34754 17432 34755 17345 34755 17348 34755 17432 34756 17348 34756 17347 34756 17347 34757 17348 34757 18423 34757 18701 34758 17349 34758 17434 34758 17434 34759 17349 34759 18389 34759 17434 34760 18389 34760 17350 34760 17350 34761 18389 34761 17352 34761 17350 34762 17352 34762 17351 34762 17351 34763 17352 34763 18388 34763 17351 34764 18388 34764 17435 34764 17435 34765 18388 34765 18380 34765 17435 34766 18380 34766 17353 34766 17353 34767 18380 34767 18578 34767 17353 34768 18578 34768 18695 34768 18695 34769 18578 34769 18378 34769 17354 34770 18815 34770 17362 34770 17362 34771 18815 34771 18750 34771 17362 34772 18750 34772 17363 34772 17363 34773 18750 34773 18751 34773 17363 34774 18751 34774 17355 34774 17355 34775 18751 34775 17357 34775 17355 34776 17357 34776 17356 34776 17356 34777 17357 34777 17358 34777 17356 34778 17358 34778 17359 34778 17359 34779 17358 34779 17360 34779 17359 34780 17360 34780 17361 34780 17361 34781 17360 34781 18755 34781 18808 34782 17354 34782 17370 34782 17370 34783 17354 34783 17362 34783 17370 34784 17362 34784 17369 34784 17369 34785 17362 34785 17363 34785 17369 34786 17363 34786 17364 34786 17364 34787 17363 34787 17355 34787 17364 34788 17355 34788 17367 34788 17367 34789 17355 34789 17356 34789 17367 34790 17356 34790 17365 34790 17365 34791 17356 34791 17359 34791 17365 34792 17359 34792 18801 34792 18801 34793 17359 34793 17361 34793 18801 34794 17366 34794 17365 34794 17365 34795 17366 34795 17781 34795 17365 34796 17781 34796 17367 34796 17367 34797 17781 34797 17782 34797 17367 34798 17782 34798 17364 34798 17364 34799 17782 34799 17368 34799 17364 34800 17368 34800 17369 34800 17369 34801 17368 34801 17786 34801 17369 34802 17786 34802 17370 34802 17370 34803 17786 34803 17788 34803 17370 34804 17788 34804 18808 34804 18808 34805 17788 34805 17789 34805 18731 34806 18730 34806 17371 34806 17371 34807 17388 34807 18731 34807 18731 34808 17388 34808 17372 34808 18731 34809 17372 34809 17373 34809 17372 34810 17374 34810 17373 34810 17373 34811 17374 34811 17375 34811 17373 34812 17375 34812 18738 34812 17375 34813 17376 34813 18738 34813 18738 34814 17376 34814 17377 34814 18738 34815 17377 34815 18737 34815 18737 34816 17377 34816 17385 34816 18737 34817 17385 34817 17378 34817 17385 34818 17384 34818 17378 34818 17378 34819 17384 34819 17381 34819 17378 34820 17381 34820 18735 34820 17379 34821 18792 34821 17382 34821 17382 34822 18792 34822 18735 34822 17382 34823 18735 34823 17380 34823 17380 34824 18735 34824 17381 34824 17379 34825 17382 34825 18777 34825 18777 34826 17382 34826 17383 34826 17382 34827 17380 34827 17383 34827 17383 34828 17380 34828 17381 34828 17383 34829 17381 34829 17394 34829 17381 34830 17384 34830 17394 34830 17394 34831 17384 34831 17385 34831 17394 34832 17385 34832 17391 34832 17385 34833 17377 34833 17391 34833 17391 34834 17377 34834 17376 34834 17391 34835 17376 34835 17386 34835 17376 34836 17375 34836 17386 34836 17386 34837 17375 34837 17374 34837 17386 34838 17374 34838 17389 34838 17371 34839 17387 34839 17388 34839 17388 34840 17387 34840 17389 34840 17388 34841 17389 34841 17372 34841 17372 34842 17389 34842 17374 34842 17387 34843 17804 34843 17389 34843 17389 34844 17804 34844 17805 34844 17389 34845 17805 34845 17386 34845 17386 34846 17805 34846 17390 34846 17386 34847 17390 34847 17391 34847 17391 34848 17390 34848 17392 34848 17391 34849 17392 34849 17394 34849 17394 34850 17392 34850 17393 34850 17394 34851 17393 34851 17383 34851 17383 34852 17393 34852 17793 34852 17383 34853 17793 34853 18777 34853 18777 34854 17793 34854 17795 34854 18776 34855 18708 34855 17395 34855 17395 34856 18708 34856 18706 34856 17395 34857 18706 34857 17396 34857 17396 34858 18706 34858 17397 34858 17396 34859 17397 34859 17407 34859 17407 34860 17397 34860 17398 34860 17407 34861 17398 34861 17408 34861 17408 34862 17398 34862 18703 34862 17408 34863 18703 34863 17399 34863 17399 34864 18703 34864 17400 34864 17399 34865 17400 34865 17410 34865 17410 34866 17400 34866 18715 34866 17410 34867 18715 34867 17401 34867 17401 34868 18715 34868 17402 34868 17403 34869 18776 34869 17404 34869 17404 34870 18776 34870 17395 34870 17404 34871 17395 34871 17405 34871 17405 34872 17395 34872 17396 34872 17405 34873 17396 34873 17406 34873 17406 34874 17396 34874 17407 34874 17406 34875 17407 34875 17414 34875 17414 34876 17407 34876 17408 34876 17414 34877 17408 34877 17413 34877 17413 34878 17408 34878 17399 34878 17413 34879 17399 34879 17409 34879 17409 34880 17399 34880 17410 34880 17409 34881 17410 34881 17411 34881 17411 34882 17410 34882 17401 34882 17411 34883 17412 34883 17409 34883 17409 34884 17412 34884 17874 34884 17409 34885 17874 34885 17413 34885 17413 34886 17874 34886 17878 34886 17413 34887 17878 34887 17414 34887 17414 34888 17878 34888 17415 34888 17414 34889 17415 34889 17406 34889 17406 34890 17415 34890 17864 34890 17406 34891 17864 34891 17405 34891 17405 34892 17864 34892 17416 34892 17405 34893 17416 34893 17404 34893 17404 34894 17416 34894 17417 34894 17404 34895 17417 34895 17403 34895 17403 34896 17417 34896 17868 34896 18749 34897 17418 34897 18752 34897 18752 34898 17418 34898 17341 34898 18752 34899 17341 34899 18753 34899 18753 34900 17341 34900 17419 34900 18753 34901 17419 34901 18754 34901 18754 34902 17419 34902 17420 34902 18754 34903 17420 34903 17422 34903 17422 34904 17420 34904 17421 34904 17422 34905 17421 34905 17423 34905 17423 34906 17421 34906 17343 34906 17423 34907 17343 34907 18756 34907 18756 34908 17343 34908 18739 34908 17424 34909 17425 34909 18736 34909 18736 34910 17425 34910 17344 34910 18736 34911 17344 34911 17427 34911 17427 34912 17344 34912 17426 34912 17427 34913 17426 34913 17428 34913 17428 34914 17426 34914 17429 34914 17428 34915 17429 34915 17430 34915 17430 34916 17429 34916 17346 34916 17430 34917 17346 34917 17431 34917 17431 34918 17346 34918 17432 34918 17431 34919 17432 34919 17433 34919 17433 34920 17432 34920 17347 34920 18702 34921 18701 34921 18705 34921 18705 34922 18701 34922 17434 34922 18705 34923 17434 34923 18704 34923 18704 34924 17434 34924 17350 34924 18704 34925 17350 34925 18716 34925 18716 34926 17350 34926 17351 34926 18716 34927 17351 34927 17436 34927 17436 34928 17351 34928 17435 34928 17436 34929 17435 34929 18714 34929 18714 34930 17435 34930 17353 34930 18714 34931 17353 34931 18713 34931 18713 34932 17353 34932 18695 34932 18429 34933 16663 34933 17437 34933 18429 34934 17437 34934 18430 34934 18430 34935 17437 34935 17439 34935 18430 34936 17439 34936 17438 34936 17438 34937 17439 34937 16659 34937 17438 34938 16659 34938 18585 34938 18585 34939 16659 34939 17440 34939 18585 34940 17440 34940 18426 34940 18426 34941 17440 34941 16657 34941 18426 34942 16657 34942 18427 34942 18427 34943 16657 34943 17441 34943 18427 34944 17441 34944 17442 34944 17442 34945 17441 34945 17444 34945 17442 34946 17444 34946 17443 34946 17443 34947 17444 34947 16654 34947 17443 34948 16654 34948 18421 34948 18421 34949 16654 34949 17445 34949 18421 34950 17445 34950 17446 34950 17446 34951 17445 34951 16653 34951 17446 34952 16653 34952 17448 34952 17448 34953 16653 34953 17447 34953 17448 34954 17447 34954 18235 34954 18235 34955 17447 34955 16652 34955 18235 34956 16652 34956 18630 34956 18630 34957 16652 34957 17449 34957 18630 34958 17449 34958 18631 34958 18631 34959 17449 34959 17450 34959 18631 34960 17450 34960 18418 34960 18418 34961 17450 34961 17451 34961 18418 34962 17451 34962 17453 34962 17453 34963 17451 34963 17452 34963 17453 34964 17452 34964 18417 34964 16568 34965 19621 34965 16684 34965 16568 34966 16684 34966 16569 34966 16569 34967 16684 34967 17454 34967 16569 34968 17454 34968 17455 34968 17455 34969 17454 34969 17457 34969 17455 34970 17457 34970 17456 34970 17456 34971 17457 34971 17459 34971 17456 34972 17459 34972 17458 34972 17458 34973 17459 34973 16680 34973 17458 34974 16680 34974 17460 34974 17460 34975 16680 34975 16678 34975 17460 34976 16678 34976 17461 34976 17461 34977 16678 34977 16679 34977 17461 34978 16679 34978 17462 34978 17462 34979 16679 34979 16677 34979 17462 34980 16677 34980 16571 34980 16571 34981 16677 34981 17463 34981 16571 34982 17463 34982 16572 34982 16572 34983 17463 34983 17464 34983 16572 34984 17464 34984 16574 34984 16574 34985 17464 34985 16674 34985 16574 34986 16674 34986 16576 34986 16576 34987 16674 34987 16673 34987 16576 34988 16673 34988 16577 34988 16577 34989 16673 34989 17465 34989 16577 34990 17465 34990 16579 34990 16579 34991 17465 34991 16670 34991 16579 34992 16670 34992 16580 34992 16580 34993 16670 34993 16669 34993 16580 34994 16669 34994 17466 34994 17466 34995 16669 34995 16664 34995 17466 34996 16664 34996 17468 34996 17468 34997 16664 34997 17467 34997 17468 34998 17467 34998 17469 34998 17469 34999 17467 34999 17470 34999 17469 35000 17470 35000 17471 35000 17471 35001 17470 35001 19644 35001 17471 35002 19644 35002 19739 35002 17472 35003 17474 35003 17473 35003 17473 35004 17474 35004 16582 35004 17473 35005 16582 35005 17475 35005 17475 35006 16582 35006 16583 35006 17475 35007 16583 35007 17476 35007 17476 35008 16583 35008 17477 35008 17476 35009 17477 35009 17478 35009 17478 35010 17477 35010 16584 35010 17478 35011 16584 35011 17479 35011 17479 35012 16584 35012 17481 35012 17479 35013 17481 35013 17480 35013 17480 35014 17481 35014 17482 35014 17480 35015 17482 35015 17483 35015 17483 35016 17482 35016 16586 35016 19768 35017 17484 35017 19766 35017 19766 35018 17484 35018 17485 35018 19766 35019 17485 35019 19767 35019 19767 35020 17485 35020 16590 35020 19767 35021 16590 35021 19761 35021 19761 35022 16590 35022 17486 35022 19761 35023 17486 35023 17487 35023 17487 35024 17486 35024 16592 35024 17487 35025 16592 35025 17489 35025 17489 35026 16592 35026 17488 35026 17489 35027 17488 35027 19765 35027 19765 35028 17488 35028 18222 35028 18220 35029 18221 35029 17490 35029 17490 35030 18221 35030 17492 35030 17490 35031 17492 35031 17491 35031 17491 35032 17492 35032 17493 35032 17491 35033 17493 35033 19769 35033 19769 35034 17493 35034 17494 35034 19769 35035 17494 35035 19770 35035 19770 35036 17494 35036 16598 35036 19770 35037 16598 35037 17495 35037 17495 35038 16598 35038 16599 35038 17495 35039 16599 35039 19771 35039 19771 35040 16599 35040 17497 35040 19771 35041 17497 35041 17496 35041 17496 35042 17497 35042 19717 35042 18211 35043 16600 35043 19776 35043 19776 35044 16600 35044 17498 35044 19776 35045 17498 35045 19775 35045 19775 35046 17498 35046 17499 35046 19775 35047 17499 35047 17500 35047 17500 35048 17499 35048 16604 35048 17500 35049 16604 35049 17501 35049 17501 35050 16604 35050 17502 35050 17501 35051 17502 35051 17503 35051 17503 35052 17502 35052 16607 35052 17503 35053 16607 35053 17504 35053 17504 35054 16607 35054 18205 35054 18204 35055 17506 35055 17505 35055 17505 35056 17506 35056 16610 35056 17505 35057 16610 35057 19778 35057 19778 35058 16610 35058 16611 35058 19778 35059 16611 35059 17507 35059 17507 35060 16611 35060 16613 35060 17507 35061 16613 35061 17508 35061 17508 35062 16613 35062 17509 35062 17508 35063 17509 35063 17510 35063 17510 35064 17509 35064 17511 35064 17510 35065 17511 35065 17512 35065 17512 35066 17511 35066 17513 35066 17512 35067 17513 35067 19780 35067 19780 35068 17513 35068 19702 35068 19784 35069 17514 35069 19783 35069 19783 35070 17514 35070 16616 35070 19783 35071 16616 35071 17515 35071 17515 35072 16616 35072 16618 35072 17515 35073 16618 35073 17516 35073 17516 35074 16618 35074 17517 35074 17516 35075 17517 35075 19782 35075 19782 35076 17517 35076 17518 35076 19782 35077 17518 35077 17519 35077 17519 35078 17518 35078 17520 35078 17519 35079 17520 35079 18187 35079 18187 35080 17520 35080 18188 35080 18185 35081 19689 35081 19786 35081 19786 35082 19689 35082 16622 35082 19786 35083 16622 35083 17521 35083 17521 35084 16622 35084 17522 35084 17521 35085 17522 35085 17523 35085 17523 35086 17522 35086 17524 35086 17523 35087 17524 35087 19787 35087 19787 35088 17524 35088 17526 35088 19787 35089 17526 35089 17525 35089 17525 35090 17526 35090 17527 35090 17525 35091 17527 35091 18177 35091 18177 35092 17527 35092 18178 35092 19792 35093 19680 35093 19794 35093 19794 35094 19680 35094 17529 35094 19794 35095 17529 35095 17528 35095 17528 35096 17529 35096 16626 35096 17528 35097 16626 35097 17530 35097 17530 35098 16626 35098 17531 35098 17530 35099 17531 35099 17532 35099 17532 35100 17531 35100 16628 35100 17532 35101 16628 35101 19793 35101 19793 35102 16628 35102 17533 35102 19793 35103 17533 35103 17534 35103 17534 35104 17533 35104 18170 35104 19797 35105 19675 35105 17535 35105 17535 35106 19675 35106 16631 35106 17535 35107 16631 35107 17536 35107 17536 35108 16631 35108 16632 35108 17536 35109 16632 35109 17537 35109 17537 35110 16632 35110 17538 35110 17537 35111 17538 35111 19796 35111 19796 35112 17538 35112 16634 35112 19796 35113 16634 35113 17539 35113 17539 35114 16634 35114 16635 35114 17539 35115 16635 35115 18161 35115 18161 35116 16635 35116 18162 35116 17540 35117 19799 35117 18160 35117 16649 35118 19800 35118 16647 35118 16647 35119 19800 35119 17541 35119 16647 35120 17541 35120 16645 35120 16645 35121 17541 35121 19798 35121 17542 35122 17543 35122 19798 35122 19798 35123 17543 35123 16643 35123 19798 35124 16643 35124 16645 35124 17544 35125 17545 35125 17542 35125 17542 35126 17545 35126 16641 35126 17542 35127 16641 35127 17543 35127 18160 35128 16639 35128 17540 35128 17540 35129 16639 35129 16640 35129 17540 35130 16640 35130 17544 35130 17544 35131 16640 35131 17546 35131 17544 35132 17546 35132 17545 35132 17547 35133 17742 35133 17548 35133 24599 35134 17549 35134 14181 35134 14181 35135 17549 35135 25769 35135 14181 35136 25769 35136 17550 35136 17550 35137 25769 35137 25770 35137 17552 35138 17551 35138 25770 35138 25770 35139 17551 35139 14179 35139 25770 35140 14179 35140 17550 35140 17555 35141 17557 35141 17552 35141 17552 35142 17557 35142 17553 35142 17552 35143 17553 35143 17551 35143 17554 35144 17560 35144 17555 35144 17555 35145 17560 35145 17556 35145 17555 35146 17556 35146 17557 35146 17548 35147 14176 35147 17547 35147 17547 35148 14176 35148 17558 35148 17547 35149 17558 35149 17554 35149 17554 35150 17558 35150 17559 35150 17554 35151 17559 35151 17560 35151 25773 35152 25772 35152 14182 35152 24588 35153 17561 35153 17562 35153 17562 35154 17561 35154 25771 35154 17562 35155 25771 35155 17567 35155 17567 35156 25771 35156 17563 35156 17564 35157 17565 35157 17563 35157 17563 35158 17565 35158 17566 35158 17563 35159 17566 35159 17567 35159 25774 35160 14185 35160 17564 35160 17564 35161 14185 35161 17568 35161 17564 35162 17568 35162 17565 35162 17569 35163 17570 35163 25774 35163 25774 35164 17570 35164 17571 35164 25774 35165 17571 35165 14185 35165 14182 35166 17572 35166 25773 35166 25773 35167 17572 35167 17573 35167 25773 35168 17573 35168 17569 35168 17569 35169 17573 35169 17574 35169 17569 35170 17574 35170 17570 35170 25778 35171 24586 35171 17575 35171 17575 35172 24586 35172 17577 35172 17575 35173 17577 35173 17576 35173 17576 35174 17577 35174 14189 35174 17576 35175 14189 35175 17578 35175 17578 35176 14189 35176 14190 35176 17578 35177 14190 35177 25780 35177 25780 35178 14190 35178 14192 35178 25780 35179 14192 35179 17579 35179 17579 35180 14192 35180 17580 35180 17579 35181 17580 35181 17581 35181 17581 35182 17580 35182 14194 35182 17581 35183 14194 35183 17582 35183 17582 35184 14194 35184 17725 35184 17723 35185 17724 35185 25783 35185 25783 35186 17724 35186 14196 35186 25783 35187 14196 35187 17583 35187 17583 35188 14196 35188 14199 35188 17583 35189 14199 35189 25782 35189 25782 35190 14199 35190 14200 35190 25782 35191 14200 35191 17584 35191 17584 35192 14200 35192 17585 35192 17584 35193 17585 35193 17586 35193 17586 35194 17585 35194 14202 35194 17586 35195 14202 35195 25781 35195 25781 35196 14202 35196 17587 35196 14217 35197 17703 35197 14215 35197 14215 35198 17703 35198 17588 35198 14215 35199 17588 35199 14214 35199 14214 35200 17588 35200 14212 35200 14212 35201 17588 35201 25786 35201 14212 35202 25786 35202 17589 35202 17589 35203 25786 35203 14209 35203 14209 35204 25786 35204 17590 35204 14209 35205 17590 35205 14208 35205 14208 35206 17590 35206 14207 35206 14207 35207 17590 35207 17591 35207 14207 35208 17591 35208 14205 35208 14205 35209 17591 35209 17592 35209 17592 35210 17591 35210 17594 35210 17592 35211 17594 35211 17593 35211 17593 35212 17594 35212 17596 35212 17596 35213 17594 35213 17595 35213 17596 35214 17595 35214 14204 35214 17607 35215 17701 35215 14218 35215 24557 35216 17597 35216 17598 35216 17598 35217 17597 35217 25789 35217 17598 35218 25789 35218 17599 35218 17599 35219 25789 35219 25788 35219 25787 35220 14224 35220 25788 35220 25788 35221 14224 35221 14225 35221 25788 35222 14225 35222 17599 35222 17605 35223 17600 35223 25787 35223 25787 35224 17600 35224 17601 35224 25787 35225 17601 35225 14224 35225 17602 35226 17603 35226 17605 35226 17605 35227 17603 35227 17604 35227 17605 35228 17604 35228 17600 35228 14218 35229 17606 35229 17607 35229 17607 35230 17606 35230 14220 35230 17607 35231 14220 35231 17602 35231 17602 35232 14220 35232 14221 35232 17602 35233 14221 35233 17603 35233 25796 35234 14228 35234 25793 35234 25793 35235 14228 35235 14229 35235 25793 35236 14229 35236 25792 35236 25792 35237 14229 35237 14231 35237 25792 35238 14231 35238 25794 35238 25794 35239 14231 35239 17608 35239 25794 35240 17608 35240 25791 35240 25791 35241 17608 35241 17609 35241 25791 35242 17609 35242 25795 35242 25795 35243 17609 35243 17610 35243 25795 35244 17610 35244 17611 35244 17611 35245 17610 35245 14233 35245 17611 35246 14233 35246 17688 35246 17688 35247 14233 35247 14235 35247 17612 35248 24550 35248 17613 35248 17613 35249 24550 35249 17614 35249 17613 35250 17614 35250 25803 35250 25803 35251 17614 35251 17615 35251 25803 35252 17615 35252 17616 35252 17616 35253 17615 35253 14239 35253 17616 35254 14239 35254 17617 35254 17617 35255 14239 35255 14240 35255 17617 35256 14240 35256 17618 35256 17618 35257 14240 35257 17620 35257 17618 35258 17620 35258 17619 35258 17619 35259 17620 35259 14243 35259 25805 35260 17621 35260 24544 35260 14252 35261 17676 35261 17622 35261 17622 35262 17676 35262 25807 35262 17622 35263 25807 35263 17623 35263 17623 35264 25807 35264 25809 35264 17624 35265 14250 35265 25809 35265 25809 35266 14250 35266 17625 35266 25809 35267 17625 35267 17623 35267 17626 35268 17628 35268 17624 35268 17624 35269 17628 35269 14249 35269 17624 35270 14249 35270 14250 35270 17630 35271 14247 35271 17626 35271 17626 35272 14247 35272 17627 35272 17626 35273 17627 35273 17628 35273 24544 35274 17629 35274 25805 35274 25805 35275 17629 35275 14244 35275 25805 35276 14244 35276 17630 35276 17630 35277 14244 35277 14246 35277 17630 35278 14246 35278 14247 35278 17631 35279 14253 35279 17632 35279 17632 35280 14253 35280 14254 35280 17632 35281 14254 35281 25813 35281 25813 35282 14254 35282 14256 35282 25813 35283 14256 35283 17633 35283 17633 35284 14256 35284 17634 35284 17633 35285 17634 35285 17635 35285 17635 35286 17634 35286 14257 35286 17635 35287 14257 35287 25811 35287 25811 35288 14257 35288 14258 35288 25811 35289 14258 35289 17636 35289 17636 35290 14258 35290 14260 35290 17637 35291 17666 35291 24527 35291 14267 35292 17662 35292 14266 35292 14266 35293 17662 35293 17638 35293 14266 35294 17638 35294 17639 35294 17639 35295 17638 35295 25816 35295 17640 35296 17641 35296 25816 35296 25816 35297 17641 35297 14265 35297 25816 35298 14265 35298 17639 35298 25815 35299 17644 35299 17640 35299 17640 35300 17644 35300 14264 35300 17640 35301 14264 35301 17641 35301 24527 35302 14262 35302 17637 35302 17637 35303 14262 35303 17642 35303 17637 35304 17642 35304 25815 35304 25815 35305 17642 35305 17643 35305 25815 35306 17643 35306 17644 35306 17651 35307 17645 35307 17654 35307 14277 35308 17646 35308 14275 35308 14275 35309 17646 35309 17647 35309 14275 35310 17647 35310 14273 35310 14273 35311 17647 35311 25821 35311 25819 35312 14271 35312 25821 35312 25821 35313 14271 35313 14272 35313 25821 35314 14272 35314 14273 35314 25820 35315 17648 35315 25819 35315 25819 35316 17648 35316 14270 35316 25819 35317 14270 35317 14271 35317 25822 35318 17653 35318 25820 35318 25820 35319 17653 35319 14269 35319 25820 35320 14269 35320 17648 35320 17654 35321 17649 35321 17651 35321 17651 35322 17649 35322 17650 35322 17651 35323 17650 35323 25822 35323 25822 35324 17650 35324 17652 35324 25822 35325 17652 35325 17653 35325 25824 35326 17646 35326 14277 35326 17654 35327 17645 35327 24516 35327 24516 35328 17645 35328 25818 35328 24516 35329 25818 35329 17655 35329 17655 35330 25818 35330 17656 35330 17657 35331 17659 35331 17656 35331 17656 35332 17659 35332 24514 35332 17656 35333 24514 35333 17655 35333 25823 35334 24512 35334 17657 35334 17657 35335 24512 35335 17658 35335 17657 35336 17658 35336 17659 35336 14277 35337 17660 35337 25824 35337 25824 35338 17660 35338 17661 35338 25824 35339 17661 35339 25823 35339 25823 35340 17661 35340 24510 35340 25823 35341 24510 35341 24512 35341 17662 35342 14267 35342 25817 35342 25817 35343 14267 35343 24517 35343 25817 35344 24517 35344 17663 35344 17663 35345 24517 35345 24519 35345 17663 35346 24519 35346 17664 35346 17664 35347 24519 35347 24522 35347 17664 35348 24522 35348 17665 35348 17665 35349 24522 35349 24524 35349 17665 35350 24524 35350 25814 35350 25814 35351 24524 35351 24525 35351 25814 35352 24525 35352 17666 35352 17666 35353 24525 35353 24527 35353 17636 35354 14260 35354 25810 35354 25810 35355 14260 35355 24528 35355 25810 35356 24528 35356 17667 35356 17667 35357 24528 35357 17669 35357 17667 35358 17669 35358 17668 35358 17668 35359 17669 35359 24531 35359 17668 35360 24531 35360 17670 35360 17670 35361 24531 35361 17671 35361 17670 35362 17671 35362 17672 35362 17672 35363 17671 35363 17673 35363 17672 35364 17673 35364 25812 35364 25812 35365 17673 35365 17674 35365 25812 35366 17674 35366 17631 35366 17631 35367 17674 35367 14253 35367 17675 35368 17676 35368 14252 35368 24544 35369 17621 35369 24543 35369 24543 35370 17621 35370 17677 35370 24543 35371 17677 35371 17678 35371 17678 35372 17677 35372 25804 35372 25808 35373 17679 35373 25804 35373 25804 35374 17679 35374 24541 35374 25804 35375 24541 35375 17678 35375 25806 35376 24537 35376 25808 35376 25808 35377 24537 35377 24539 35377 25808 35378 24539 35378 17679 35378 14252 35379 17680 35379 17675 35379 17675 35380 17680 35380 24535 35380 17675 35381 24535 35381 25806 35381 25806 35382 24535 35382 24536 35382 25806 35383 24536 35383 24537 35383 17619 35384 14243 35384 25799 35384 25799 35385 14243 35385 17681 35385 25799 35386 17681 35386 17683 35386 17683 35387 17681 35387 17682 35387 17683 35388 17682 35388 25800 35388 25800 35389 17682 35389 17684 35389 25800 35390 17684 35390 25801 35390 25801 35391 17684 35391 24546 35391 25801 35392 24546 35392 17686 35392 17686 35393 24546 35393 17685 35393 17686 35394 17685 35394 25802 35394 25802 35395 17685 35395 17687 35395 25802 35396 17687 35396 17612 35396 17612 35397 17687 35397 24550 35397 17688 35398 14235 35398 25798 35398 25798 35399 14235 35399 24551 35399 25798 35400 24551 35400 17689 35400 17689 35401 24551 35401 24552 35401 17689 35402 24552 35402 25797 35402 25797 35403 24552 35403 17691 35403 25797 35404 17691 35404 17690 35404 17690 35405 17691 35405 17692 35405 17690 35406 17692 35406 17693 35406 17693 35407 17692 35407 17694 35407 17693 35408 17694 35408 25796 35408 25796 35409 17694 35409 14228 35409 17597 35410 24557 35410 17695 35410 17695 35411 24557 35411 24559 35411 17695 35412 24559 35412 17696 35412 17696 35413 24559 35413 17697 35413 17696 35414 17697 35414 17698 35414 17698 35415 17697 35415 17700 35415 17698 35416 17700 35416 17699 35416 17699 35417 17700 35417 24564 35417 17699 35418 24564 35418 25790 35418 25790 35419 24564 35419 17702 35419 25790 35420 17702 35420 17701 35420 17701 35421 17702 35421 14218 35421 17712 35422 17703 35422 14217 35422 14204 35423 17595 35423 24567 35423 24567 35424 17595 35424 17704 35424 24567 35425 17704 35425 17705 35425 17705 35426 17704 35426 17706 35426 25785 35427 17707 35427 17706 35427 17706 35428 17707 35428 17708 35428 17706 35429 17708 35429 17705 35429 17709 35430 24573 35430 25785 35430 25785 35431 24573 35431 24571 35431 25785 35432 24571 35432 17707 35432 17713 35433 17710 35433 17709 35433 17709 35434 17710 35434 24575 35434 17709 35435 24575 35435 24573 35435 14217 35436 17711 35436 17712 35436 17712 35437 17711 35437 17714 35437 17712 35438 17714 35438 17713 35438 17713 35439 17714 35439 17715 35439 17713 35440 17715 35440 17710 35440 25781 35441 17587 35441 17716 35441 17716 35442 17587 35442 17717 35442 17716 35443 17717 35443 17718 35443 17718 35444 17717 35444 24578 35444 17718 35445 24578 35445 17719 35445 17719 35446 24578 35446 24579 35446 17719 35447 24579 35447 25784 35447 25784 35448 24579 35448 24580 35448 25784 35449 24580 35449 17720 35449 17720 35450 24580 35450 24582 35450 17720 35451 24582 35451 17721 35451 17721 35452 24582 35452 17722 35452 17721 35453 17722 35453 17723 35453 17723 35454 17722 35454 17724 35454 17582 35455 17725 35455 25779 35455 25779 35456 17725 35456 17726 35456 25779 35457 17726 35457 17727 35457 17727 35458 17726 35458 24584 35458 17727 35459 24584 35459 17728 35459 17728 35460 24584 35460 17729 35460 17728 35461 17729 35461 17731 35461 17731 35462 17729 35462 17730 35462 17731 35463 17730 35463 25777 35463 25777 35464 17730 35464 24585 35464 25777 35465 24585 35465 25778 35465 25778 35466 24585 35466 24586 35466 25776 35467 17561 35467 24588 35467 14182 35468 25772 35468 17732 35468 17732 35469 25772 35469 17733 35469 17732 35470 17733 35470 24598 35470 24598 35471 17733 35471 25775 35471 17734 35472 24595 35472 25775 35472 25775 35473 24595 35473 24596 35473 25775 35474 24596 35474 24598 35474 17735 35475 24592 35475 17734 35475 17734 35476 24592 35476 24593 35476 17734 35477 24593 35477 24595 35477 24588 35478 24589 35478 25776 35478 25776 35479 24589 35479 17736 35479 25776 35480 17736 35480 17735 35480 17735 35481 17736 35481 17737 35481 17735 35482 17737 35482 24592 35482 17549 35483 24599 35483 25766 35483 25766 35484 24599 35484 24602 35484 25766 35485 24602 35485 17738 35485 17738 35486 24602 35486 24603 35486 17738 35487 24603 35487 17740 35487 17740 35488 24603 35488 17739 35488 17740 35489 17739 35489 25768 35489 25768 35490 17739 35490 24605 35490 25768 35491 24605 35491 25767 35491 25767 35492 24605 35492 17741 35492 25767 35493 17741 35493 17742 35493 17742 35494 17741 35494 17548 35494 23009 35495 17773 35495 17743 35495 17743 35496 17773 35496 19648 35496 17743 35497 19648 35497 17744 35497 17744 35498 19648 35498 17745 35498 17744 35499 17745 35499 17746 35499 17746 35500 17745 35500 19649 35500 17746 35501 19649 35501 17747 35501 17747 35502 19649 35502 19651 35502 17747 35503 19651 35503 23005 35503 23005 35504 19651 35504 17748 35504 23005 35505 17748 35505 23003 35505 23003 35506 17748 35506 17749 35506 23003 35507 17749 35507 23001 35507 23001 35508 17749 35508 17750 35508 23001 35509 17750 35509 17751 35509 17751 35510 17750 35510 17753 35510 17751 35511 17753 35511 17752 35511 17752 35512 17753 35512 19655 35512 17752 35513 19655 35513 22999 35513 22999 35514 19655 35514 19657 35514 22999 35515 19657 35515 22998 35515 22998 35516 19657 35516 17755 35516 22998 35517 17755 35517 17754 35517 17754 35518 17755 35518 19660 35518 17754 35519 19660 35519 22996 35519 22996 35520 19660 35520 19661 35520 22996 35521 19661 35521 22994 35521 22994 35522 19661 35522 17756 35522 22994 35523 17756 35523 14865 35523 14865 35524 17756 35524 17757 35524 14865 35525 17757 35525 17758 35525 17758 35526 17757 35526 16650 35526 17758 35527 16650 35527 14864 35527 14864 35528 16650 35528 16651 35528 14864 35529 16651 35529 14863 35529 14863 35530 16651 35530 17759 35530 14863 35531 17759 35531 14860 35531 14860 35532 17759 35532 17760 35532 14860 35533 17760 35533 17761 35533 17761 35534 17760 35534 17762 35534 17761 35535 17762 35535 17763 35535 17763 35536 17762 35536 17764 35536 17763 35537 17764 35537 17765 35537 17765 35538 17764 35538 17766 35538 17765 35539 17766 35539 17767 35539 17767 35540 17766 35540 16655 35540 17767 35541 16655 35541 14858 35541 14858 35542 16655 35542 16656 35542 14858 35543 16656 35543 14857 35543 14857 35544 16656 35544 17768 35544 14857 35545 17768 35545 17769 35545 17769 35546 17768 35546 16658 35546 17769 35547 16658 35547 17770 35547 17770 35548 16658 35548 17771 35548 17770 35549 17771 35549 14854 35549 14854 35550 17771 35550 16660 35550 14854 35551 16660 35551 14852 35551 14852 35552 16660 35552 16661 35552 14852 35553 16661 35553 14849 35553 14849 35554 16661 35554 16662 35554 14849 35555 16662 35555 17772 35555 17772 35556 16662 35556 19645 35556 17772 35557 19645 35557 23009 35557 23009 35558 19645 35558 17773 35558 18797 35559 17774 35559 17775 35559 17775 35560 17774 35560 17776 35560 17775 35561 17776 35561 18799 35561 18799 35562 17776 35562 17777 35562 18799 35563 17777 35563 17778 35563 17778 35564 17777 35564 17779 35564 17778 35565 17779 35565 17366 35565 17366 35566 17779 35566 17780 35566 17366 35567 17780 35567 17781 35567 17781 35568 17780 35568 17783 35568 17781 35569 17783 35569 17782 35569 17782 35570 17783 35570 17784 35570 17782 35571 17784 35571 17368 35571 17368 35572 17784 35572 17785 35572 17368 35573 17785 35573 17786 35573 17786 35574 17785 35574 17787 35574 17786 35575 17787 35575 17788 35575 17788 35576 17787 35576 16063 35576 17788 35577 16063 35577 17789 35577 17789 35578 16063 35578 20743 35578 17789 35579 20743 35579 18794 35579 18794 35580 20743 35580 17790 35580 18794 35581 17790 35581 18795 35581 18795 35582 17790 35582 20741 35582 18795 35583 20741 35583 18797 35583 18797 35584 20741 35584 17774 35584 17392 35585 17791 35585 17393 35585 17393 35586 17791 35586 17792 35586 17393 35587 17792 35587 17793 35587 17793 35588 17792 35588 17794 35588 17793 35589 17794 35589 17795 35589 17795 35590 17794 35590 17796 35590 17795 35591 17796 35591 18778 35591 18778 35592 17796 35592 17797 35592 18778 35593 17797 35593 17798 35593 17798 35594 17797 35594 20726 35594 17798 35595 20726 35595 18781 35595 18781 35596 20726 35596 17799 35596 18781 35597 17799 35597 18783 35597 18783 35598 17799 35598 17800 35598 18783 35599 17800 35599 17801 35599 17801 35600 17800 35600 17802 35600 17801 35601 17802 35601 17804 35601 17804 35602 17802 35602 17803 35602 17804 35603 17803 35603 17805 35603 17805 35604 17803 35604 17806 35604 17805 35605 17806 35605 17390 35605 17390 35606 17806 35606 17807 35606 17390 35607 17807 35607 17392 35607 17392 35608 17807 35608 17791 35608 17821 35609 16295 35609 17272 35609 17272 35610 16295 35610 17808 35610 17272 35611 17808 35611 17809 35611 17809 35612 17808 35612 17810 35612 17809 35613 17810 35613 17812 35613 17812 35614 17810 35614 17811 35614 17812 35615 17811 35615 17269 35615 17269 35616 17811 35616 17813 35616 17269 35617 17813 35617 18907 35617 18907 35618 17813 35618 17814 35618 18907 35619 17814 35619 18908 35619 18908 35620 17814 35620 20494 35620 18908 35621 20494 35621 17815 35621 17815 35622 20494 35622 20492 35622 17815 35623 20492 35623 18910 35623 18910 35624 20492 35624 20491 35624 18910 35625 20491 35625 17816 35625 17816 35626 20491 35626 17817 35626 17816 35627 17817 35627 17275 35627 17275 35628 17817 35628 17818 35628 17275 35629 17818 35629 17273 35629 17273 35630 17818 35630 17819 35630 17273 35631 17819 35631 17820 35631 17820 35632 17819 35632 16296 35632 17820 35633 16296 35633 17821 35633 17821 35634 16296 35634 16295 35634 16304 35635 17822 35635 18883 35635 18883 35636 17822 35636 17823 35636 18883 35637 17823 35637 17824 35637 17824 35638 17823 35638 17825 35638 17824 35639 17825 35639 17826 35639 17826 35640 17825 35640 17828 35640 17826 35641 17828 35641 17827 35641 17827 35642 17828 35642 20483 35642 17827 35643 20483 35643 18885 35643 18885 35644 20483 35644 17829 35644 18885 35645 17829 35645 18886 35645 18886 35646 17829 35646 17830 35646 18886 35647 17830 35647 17832 35647 17832 35648 17830 35648 17831 35648 17832 35649 17831 35649 17833 35649 17833 35650 17831 35650 17834 35650 17833 35651 17834 35651 17291 35651 17291 35652 17834 35652 16306 35652 17291 35653 16306 35653 17292 35653 17292 35654 16306 35654 16305 35654 17292 35655 16305 35655 17835 35655 17835 35656 16305 35656 17836 35656 17835 35657 17836 35657 17294 35657 17294 35658 17836 35658 16304 35658 17294 35659 16304 35659 18883 35659 17851 35660 18865 35660 16323 35660 16323 35661 18865 35661 17837 35661 16323 35662 17837 35662 16324 35662 16324 35663 17837 35663 17838 35663 16324 35664 17838 35664 16320 35664 16320 35665 17838 35665 17315 35665 16320 35666 17315 35666 17839 35666 17839 35667 17315 35667 17840 35667 17839 35668 17840 35668 16317 35668 16317 35669 17840 35669 17842 35669 16317 35670 17842 35670 17841 35670 17841 35671 17842 35671 17314 35671 17841 35672 17314 35672 17843 35672 17843 35673 17314 35673 17844 35673 17843 35674 17844 35674 17845 35674 17845 35675 17844 35675 17846 35675 17845 35676 17846 35676 20461 35676 20461 35677 17846 35677 18869 35677 20461 35678 18869 35678 17847 35678 17847 35679 18869 35679 18867 35679 17847 35680 18867 35680 17848 35680 17848 35681 18867 35681 17849 35681 17848 35682 17849 35682 17850 35682 17850 35683 17849 35683 17851 35683 17850 35684 17851 35684 16323 35684 17335 35685 16342 35685 17334 35685 17334 35686 16342 35686 16341 35686 17334 35687 16341 35687 17331 35687 17331 35688 16341 35688 17852 35688 17331 35689 17852 35689 17853 35689 17853 35690 17852 35690 16340 35690 17853 35691 16340 35691 18844 35691 18844 35692 16340 35692 17854 35692 18844 35693 17854 35693 18845 35693 18845 35694 17854 35694 17855 35694 18845 35695 17855 35695 18847 35695 18847 35696 17855 35696 20451 35696 18847 35697 20451 35697 17856 35697 17856 35698 20451 35698 17857 35698 17856 35699 17857 35699 17858 35699 17858 35700 17857 35700 20450 35700 17858 35701 20450 35701 18840 35701 18840 35702 20450 35702 17859 35702 18840 35703 17859 35703 17337 35703 17337 35704 17859 35704 17860 35704 17337 35705 17860 35705 17861 35705 17861 35706 17860 35706 17862 35706 17861 35707 17862 35707 17863 35707 17863 35708 17862 35708 16343 35708 17863 35709 16343 35709 17335 35709 17335 35710 16343 35710 16342 35710 17415 35711 17865 35711 17864 35711 17864 35712 17865 35712 17866 35712 17864 35713 17866 35713 17416 35713 17416 35714 17866 35714 16113 35714 17416 35715 16113 35715 17417 35715 17417 35716 16113 35716 17867 35716 17417 35717 17867 35717 17868 35717 17868 35718 17867 35718 16117 35718 17868 35719 16117 35719 17869 35719 17869 35720 16117 35720 17870 35720 17869 35721 17870 35721 18763 35721 18763 35722 17870 35722 20705 35722 18763 35723 20705 35723 18764 35723 18764 35724 20705 35724 20703 35724 18764 35725 20703 35725 18766 35725 18766 35726 20703 35726 17871 35726 18766 35727 17871 35727 17872 35727 17872 35728 17871 35728 17873 35728 17872 35729 17873 35729 17412 35729 17412 35730 17873 35730 17875 35730 17412 35731 17875 35731 17874 35731 17874 35732 17875 35732 17876 35732 17874 35733 17876 35733 17878 35733 17878 35734 17876 35734 17877 35734 17878 35735 17877 35735 17415 35735 17415 35736 17877 35736 17865 35736 17890 35737 20752 35737 17879 35737 17879 35738 20752 35738 20754 35738 17879 35739 20754 35739 17880 35739 17880 35740 20754 35740 20756 35740 17880 35741 20756 35741 17881 35741 17881 35742 20756 35742 20759 35742 17881 35743 20759 35743 17882 35743 17882 35744 20759 35744 17883 35744 17882 35745 17883 35745 17884 35745 17884 35746 17883 35746 20763 35746 17884 35747 20763 35747 16955 35747 16955 35748 20763 35748 20761 35748 16955 35749 20761 35749 16956 35749 16956 35750 20761 35750 16046 35750 16956 35751 16046 35751 16952 35751 16952 35752 16046 35752 16047 35752 16952 35753 16047 35753 17885 35753 17885 35754 16047 35754 17887 35754 17885 35755 17887 35755 17886 35755 17886 35756 17887 35756 16053 35756 17886 35757 16053 35757 17888 35757 17888 35758 16053 35758 16052 35758 17888 35759 16052 35759 17889 35759 17889 35760 16052 35760 17890 35760 17889 35761 17890 35761 19284 35761 19284 35762 17890 35762 17879 35762 17902 35763 16035 35763 16925 35763 16925 35764 16035 35764 17891 35764 16925 35765 17891 35765 16926 35765 16926 35766 17891 35766 17892 35766 16926 35767 17892 35767 16928 35767 16928 35768 17892 35768 17893 35768 16928 35769 17893 35769 16930 35769 16930 35770 17893 35770 16031 35770 16930 35771 16031 35771 17894 35771 17894 35772 16031 35772 16030 35772 17894 35773 16030 35773 19303 35773 19303 35774 16030 35774 20777 35774 19303 35775 20777 35775 17895 35775 17895 35776 20777 35776 20774 35776 17895 35777 20774 35777 17896 35777 17896 35778 20774 35778 20773 35778 17896 35779 20773 35779 17897 35779 17897 35780 20773 35780 20771 35780 17897 35781 20771 35781 19306 35781 19306 35782 20771 35782 17898 35782 19306 35783 17898 35783 17899 35783 17899 35784 17898 35784 17900 35784 17899 35785 17900 35785 17901 35785 17901 35786 17900 35786 16036 35786 17901 35787 16036 35787 17902 35787 17902 35788 16036 35788 16035 35788 19324 35789 17903 35789 19323 35789 19323 35790 17903 35790 20788 35790 19323 35791 20788 35791 17904 35791 17904 35792 20788 35792 20787 35792 17904 35793 20787 35793 17906 35793 17906 35794 20787 35794 17905 35794 17906 35795 17905 35795 17907 35795 17907 35796 17905 35796 17909 35796 17907 35797 17909 35797 17908 35797 17908 35798 17909 35798 16016 35798 17908 35799 16016 35799 17910 35799 17910 35800 16016 35800 17911 35800 17910 35801 17911 35801 17912 35801 17912 35802 17911 35802 17913 35802 17912 35803 17913 35803 16911 35803 16911 35804 17913 35804 17914 35804 16911 35805 17914 35805 19330 35805 19330 35806 17914 35806 17915 35806 19330 35807 17915 35807 19328 35807 19328 35808 17915 35808 20791 35808 19328 35809 20791 35809 17916 35809 17916 35810 20791 35810 17917 35810 17916 35811 17917 35811 19325 35811 19325 35812 17917 35812 17918 35812 19325 35813 17918 35813 19324 35813 19324 35814 17918 35814 17903 35814 19348 35815 17920 35815 17919 35815 17919 35816 17920 35816 20812 35816 17919 35817 20812 35817 17921 35817 17921 35818 20812 35818 17922 35818 17921 35819 17922 35819 17923 35819 17923 35820 17922 35820 17924 35820 17923 35821 17924 35821 16894 35821 16894 35822 17924 35822 16005 35822 16894 35823 16005 35823 17925 35823 17925 35824 16005 35824 16004 35824 17925 35825 16004 35825 16896 35825 16896 35826 16004 35826 17926 35826 16896 35827 17926 35827 19352 35827 19352 35828 17926 35828 20808 35828 19352 35829 20808 35829 19350 35829 19350 35830 20808 35830 17927 35830 19350 35831 17927 35831 17928 35831 17928 35832 17927 35832 20809 35832 17928 35833 20809 35833 17929 35833 17929 35834 20809 35834 17930 35834 17929 35835 17930 35835 17931 35835 17931 35836 17930 35836 17932 35836 17931 35837 17932 35837 17933 35837 17933 35838 17932 35838 20811 35838 17933 35839 20811 35839 19348 35839 19348 35840 20811 35840 17920 35840 17934 35841 15918 35841 17039 35841 17039 35842 15918 35842 17936 35842 17039 35843 17936 35843 17935 35843 17935 35844 17936 35844 17938 35844 17935 35845 17938 35845 17937 35845 17937 35846 17938 35846 15916 35846 17937 35847 15916 35847 17939 35847 17939 35848 15916 35848 17940 35848 17939 35849 17940 35849 17941 35849 17941 35850 17940 35850 15915 35850 17941 35851 15915 35851 19202 35851 19202 35852 15915 35852 20941 35852 19202 35853 20941 35853 17942 35853 17942 35854 20941 35854 17943 35854 17942 35855 17943 35855 17944 35855 17944 35856 17943 35856 17945 35856 17944 35857 17945 35857 17946 35857 17946 35858 17945 35858 17947 35858 17946 35859 17947 35859 19205 35859 19205 35860 17947 35860 20939 35860 19205 35861 20939 35861 17034 35861 17034 35862 20939 35862 17948 35862 17034 35863 17948 35863 17036 35863 17036 35864 17948 35864 17949 35864 17036 35865 17949 35865 17934 35865 17934 35866 17949 35866 15918 35866 17950 35867 17951 35867 17017 35867 17017 35868 17951 35868 17953 35868 17017 35869 17953 35869 17952 35869 17952 35870 17953 35870 17954 35870 17952 35871 17954 35871 17955 35871 17955 35872 17954 35872 20963 35872 17955 35873 20963 35873 19220 35873 19220 35874 20963 35874 17956 35874 19220 35875 17956 35875 17957 35875 17957 35876 17956 35876 20962 35876 17957 35877 20962 35877 17958 35877 17958 35878 20962 35878 17959 35878 17958 35879 17959 35879 17960 35879 17960 35880 17959 35880 17961 35880 17960 35881 17961 35881 19224 35881 19224 35882 17961 35882 17962 35882 19224 35883 17962 35883 19225 35883 19225 35884 17962 35884 17963 35884 19225 35885 17963 35885 17014 35885 17014 35886 17963 35886 17964 35886 17014 35887 17964 35887 17015 35887 17015 35888 17964 35888 17966 35888 17015 35889 17966 35889 17965 35889 17965 35890 17966 35890 17967 35890 17965 35891 17967 35891 17950 35891 17950 35892 17967 35892 17951 35892 17968 35893 17976 35893 19243 35893 19243 35894 17976 35894 20989 35894 19243 35895 20989 35895 17969 35895 17969 35896 20989 35896 20991 35896 17969 35897 20991 35897 17970 35897 17970 35898 20991 35898 20993 35898 17970 35899 20993 35899 19246 35899 19246 35900 20993 35900 17971 35900 19246 35901 17971 35901 16993 35901 16993 35902 17971 35902 20996 35902 16993 35903 20996 35903 16995 35903 16995 35904 20996 35904 15865 35904 16995 35905 15865 35905 17972 35905 17972 35906 15865 35906 17973 35906 17972 35907 17973 35907 16996 35907 16996 35908 17973 35908 15868 35908 16996 35909 15868 35909 17974 35909 17974 35910 15868 35910 15870 35910 17974 35911 15870 35911 16998 35911 16998 35912 15870 35912 15872 35912 16998 35913 15872 35913 16999 35913 16999 35914 15872 35914 17975 35914 16999 35915 17975 35915 19241 35915 19241 35916 17975 35916 20985 35916 19241 35917 20985 35917 17968 35917 17968 35918 20985 35918 17976 35918 17988 35919 17136 35919 21019 35919 21019 35920 17136 35920 17977 35920 21019 35921 17977 35921 17978 35921 17978 35922 17977 35922 17979 35922 17978 35923 17979 35923 21017 35923 21017 35924 17979 35924 19080 35924 21017 35925 19080 35925 21014 35925 21014 35926 19080 35926 17980 35926 21014 35927 17980 35927 17981 35927 17981 35928 17980 35928 19084 35928 17981 35929 19084 35929 21013 35929 21013 35930 19084 35930 19085 35930 21013 35931 19085 35931 17983 35931 17983 35932 19085 35932 17982 35932 17983 35933 17982 35933 17984 35933 17984 35934 17982 35934 17985 35934 17984 35935 17985 35935 15856 35935 15856 35936 17985 35936 17141 35936 15856 35937 17141 35937 17986 35937 17986 35938 17141 35938 17139 35938 17986 35939 17139 35939 17987 35939 17987 35940 17139 35940 17138 35940 17987 35941 17138 35941 15859 35941 15859 35942 17138 35942 17988 35942 15859 35943 17988 35943 21019 35943 21033 35944 21036 35944 19104 35944 19104 35945 21036 35945 21037 35945 19104 35946 21037 35946 17989 35946 17989 35947 21037 35947 17991 35947 17989 35948 17991 35948 17990 35948 17990 35949 17991 35949 21040 35949 17990 35950 21040 35950 19106 35950 19106 35951 21040 35951 17992 35951 19106 35952 17992 35952 19107 35952 19107 35953 17992 35953 17993 35953 19107 35954 17993 35954 17117 35954 17117 35955 17993 35955 21042 35955 17117 35956 21042 35956 17994 35956 17994 35957 21042 35957 17995 35957 17994 35958 17995 35958 17119 35958 17119 35959 17995 35959 17996 35959 17119 35960 17996 35960 17120 35960 17120 35961 17996 35961 15842 35961 17120 35962 15842 35962 17997 35962 17997 35963 15842 35963 17999 35963 17997 35964 17999 35964 17998 35964 17998 35965 17999 35965 18000 35965 17998 35966 18000 35966 18001 35966 18001 35967 18000 35967 21033 35967 18001 35968 21033 35968 19102 35968 19102 35969 21033 35969 19104 35969 17093 35970 15830 35970 17094 35970 17094 35971 15830 35971 15829 35971 17094 35972 15829 35972 17095 35972 17095 35973 15829 35973 18002 35973 17095 35974 18002 35974 17098 35974 17098 35975 18002 35975 15828 35975 17098 35976 15828 35976 17100 35976 17100 35977 15828 35977 18003 35977 17100 35978 18003 35978 18004 35978 18004 35979 18003 35979 15826 35979 18004 35980 15826 35980 17103 35980 17103 35981 15826 35981 15824 35981 17103 35982 15824 35982 18005 35982 18005 35983 15824 35983 18007 35983 18005 35984 18007 35984 18006 35984 18006 35985 18007 35985 21058 35985 18006 35986 21058 35986 18009 35986 18009 35987 21058 35987 18008 35987 18009 35988 18008 35988 18010 35988 18010 35989 18008 35989 18012 35989 18010 35990 18012 35990 18011 35990 18011 35991 18012 35991 18013 35991 18011 35992 18013 35992 18014 35992 18014 35993 18013 35993 21055 35993 18014 35994 21055 35994 17093 35994 17093 35995 21055 35995 15830 35995 17073 35996 15816 35996 17075 35996 17075 35997 15816 35997 15815 35997 17075 35998 15815 35998 17076 35998 17076 35999 15815 35999 18015 35999 17076 36000 18015 36000 18016 36000 18016 36001 18015 36001 18017 36001 18016 36002 18017 36002 17077 36002 17077 36003 18017 36003 15813 36003 17077 36004 15813 36004 18018 36004 18018 36005 15813 36005 21071 36005 18018 36006 21071 36006 18019 36006 18019 36007 21071 36007 21069 36007 18019 36008 21069 36008 19137 36008 19137 36009 21069 36009 18020 36009 19137 36010 18020 36010 19138 36010 19138 36011 18020 36011 18021 36011 19138 36012 18021 36012 19139 36012 19139 36013 18021 36013 18023 36013 19139 36014 18023 36014 18022 36014 18022 36015 18023 36015 21065 36015 18022 36016 21065 36016 18024 36016 18024 36017 21065 36017 18025 36017 18024 36018 18025 36018 18026 36018 18026 36019 18025 36019 15817 36019 18026 36020 15817 36020 17073 36020 17073 36021 15817 36021 15816 36021 18040 36022 18027 36022 17226 36022 17226 36023 18027 36023 15722 36023 17226 36024 15722 36024 17228 36024 17228 36025 15722 36025 18028 36025 17228 36026 18028 36026 18029 36026 18029 36027 18028 36027 15721 36027 18029 36028 15721 36028 17229 36028 17229 36029 15721 36029 18031 36029 17229 36030 18031 36030 18030 36030 18030 36031 18031 36031 15718 36031 18030 36032 15718 36032 18032 36032 18032 36033 15718 36033 18034 36033 18032 36034 18034 36034 18033 36034 18033 36035 18034 36035 21200 36035 18033 36036 21200 36036 18035 36036 18035 36037 21200 36037 18036 36037 18035 36038 18036 36038 18987 36038 18987 36039 18036 36039 21198 36039 18987 36040 21198 36040 18989 36040 18989 36041 21198 36041 18037 36041 18989 36042 18037 36042 18990 36042 18990 36043 18037 36043 15724 36043 18990 36044 15724 36044 18038 36044 18038 36045 15724 36045 18039 36045 18038 36046 18039 36046 18040 36046 18040 36047 18039 36047 18027 36047 19021 36048 18041 36048 18042 36048 18042 36049 18041 36049 18043 36049 18042 36050 18043 36050 19018 36050 19018 36051 18043 36051 18044 36051 19018 36052 18044 36052 19016 36052 19016 36053 18044 36053 21220 36053 19016 36054 21220 36054 18045 36054 18045 36055 21220 36055 18046 36055 18045 36056 18046 36056 17202 36056 17202 36057 18046 36057 18047 36057 17202 36058 18047 36058 17203 36058 17203 36059 18047 36059 18048 36059 17203 36060 18048 36060 17204 36060 17204 36061 18048 36061 15692 36061 17204 36062 15692 36062 17205 36062 17205 36063 15692 36063 18049 36063 17205 36064 18049 36064 18050 36064 18050 36065 18049 36065 18051 36065 18050 36066 18051 36066 17209 36066 17209 36067 18051 36067 18052 36067 17209 36068 18052 36068 19026 36068 19026 36069 18052 36069 21223 36069 19026 36070 21223 36070 19024 36070 19024 36071 21223 36071 18053 36071 19024 36072 18053 36072 19021 36072 19021 36073 18053 36073 18041 36073 19041 36074 21251 36074 18054 36074 18054 36075 21251 36075 21253 36075 18054 36076 21253 36076 19043 36076 19043 36077 21253 36077 21254 36077 19043 36078 21254 36078 18055 36078 18055 36079 21254 36079 21256 36079 18055 36080 21256 36080 18056 36080 18056 36081 21256 36081 21257 36081 18056 36082 21257 36082 17178 36082 17178 36083 21257 36083 18058 36083 17178 36084 18058 36084 18057 36084 18057 36085 18058 36085 15680 36085 18057 36086 15680 36086 18060 36086 18060 36087 15680 36087 18059 36087 18060 36088 18059 36088 18061 36088 18061 36089 18059 36089 15679 36089 18061 36090 15679 36090 17182 36090 17182 36091 15679 36091 15678 36091 17182 36092 15678 36092 18062 36092 18062 36093 15678 36093 15676 36093 18062 36094 15676 36094 19038 36094 19038 36095 15676 36095 18063 36095 19038 36096 18063 36096 19039 36096 19039 36097 18063 36097 21249 36097 19039 36098 21249 36098 19041 36098 19041 36099 21249 36099 21251 36099 18064 36100 18077 36100 18065 36100 18065 36101 18077 36101 18067 36101 18065 36102 18067 36102 18066 36102 18066 36103 18067 36103 18068 36103 18066 36104 18068 36104 19511 36104 19511 36105 18068 36105 18069 36105 19511 36106 18069 36106 16779 36106 16779 36107 18069 36107 18071 36107 16779 36108 18071 36108 18070 36108 18070 36109 18071 36109 15665 36109 18070 36110 15665 36110 16781 36110 16781 36111 15665 36111 18072 36111 16781 36112 18072 36112 16783 36112 16783 36113 18072 36113 15664 36113 16783 36114 15664 36114 16784 36114 16784 36115 15664 36115 18073 36115 16784 36116 18073 36116 19518 36116 19518 36117 18073 36117 21269 36117 19518 36118 21269 36118 19520 36118 19520 36119 21269 36119 21268 36119 19520 36120 21268 36120 19516 36120 19516 36121 21268 36121 18075 36121 19516 36122 18075 36122 18074 36122 18074 36123 18075 36123 18076 36123 18074 36124 18076 36124 18064 36124 18064 36125 18076 36125 18077 36125 16761 36126 15651 36126 16759 36126 16759 36127 15651 36127 18078 36127 16759 36128 18078 36128 16757 36128 16757 36129 18078 36129 15650 36129 16757 36130 15650 36130 18079 36130 18079 36131 15650 36131 15649 36131 18079 36132 15649 36132 18080 36132 18080 36133 15649 36133 21279 36133 18080 36134 21279 36134 18081 36134 18081 36135 21279 36135 21277 36135 18081 36136 21277 36136 18082 36136 18082 36137 21277 36137 18083 36137 18082 36138 18083 36138 19546 36138 19546 36139 18083 36139 18084 36139 19546 36140 18084 36140 19545 36140 19545 36141 18084 36141 18085 36141 19545 36142 18085 36142 18087 36142 18087 36143 18085 36143 18086 36143 18087 36144 18086 36144 18088 36144 18088 36145 18086 36145 15655 36145 18088 36146 15655 36146 16763 36146 16763 36147 15655 36147 15654 36147 16763 36148 15654 36148 18089 36148 18089 36149 15654 36149 15653 36149 18089 36150 15653 36150 16761 36150 16761 36151 15653 36151 15651 36151 18090 36152 18091 36152 19569 36152 19569 36153 18091 36153 21291 36153 19569 36154 21291 36154 18093 36154 18093 36155 21291 36155 18092 36155 18093 36156 18092 36156 18094 36156 18094 36157 18092 36157 21294 36157 18094 36158 21294 36158 19570 36158 19570 36159 21294 36159 21296 36159 19570 36160 21296 36160 19572 36160 19572 36161 21296 36161 21299 36161 19572 36162 21299 36162 18095 36162 18095 36163 21299 36163 15639 36163 18095 36164 15639 36164 16739 36164 16739 36165 15639 36165 18096 36165 16739 36166 18096 36166 16736 36166 16736 36167 18096 36167 15638 36167 16736 36168 15638 36168 16734 36168 16734 36169 15638 36169 15637 36169 16734 36170 15637 36170 18098 36170 18098 36171 15637 36171 18097 36171 18098 36172 18097 36172 18099 36172 18099 36173 18097 36173 18100 36173 18099 36174 18100 36174 18101 36174 18101 36175 18100 36175 18090 36175 18101 36176 18090 36176 19569 36176 15629 36177 21312 36177 19601 36177 19601 36178 21312 36178 21315 36178 19601 36179 21315 36179 19599 36179 19599 36180 21315 36180 21316 36180 19599 36181 21316 36181 19598 36181 19598 36182 21316 36182 21317 36182 19598 36183 21317 36183 19595 36183 19595 36184 21317 36184 18102 36184 19595 36185 18102 36185 18103 36185 18103 36186 18102 36186 21320 36186 18103 36187 21320 36187 18104 36187 18104 36188 21320 36188 21319 36188 18104 36189 21319 36189 16709 36189 16709 36190 21319 36190 18105 36190 16709 36191 18105 36191 16706 36191 16706 36192 18105 36192 15621 36192 16706 36193 15621 36193 18106 36193 18106 36194 15621 36194 15625 36194 18106 36195 15625 36195 18107 36195 18107 36196 15625 36196 15628 36196 18107 36197 15628 36197 18108 36197 18108 36198 15628 36198 18109 36198 18108 36199 18109 36199 16702 36199 16702 36200 18109 36200 15629 36200 16702 36201 15629 36201 19600 36201 19600 36202 15629 36202 19601 36202 19428 36203 18110 36203 19429 36203 19429 36204 18110 36204 21453 36204 19429 36205 21453 36205 18112 36205 18112 36206 21453 36206 18111 36206 18112 36207 18111 36207 18113 36207 18113 36208 18111 36208 18114 36208 18113 36209 18114 36209 16861 36209 16861 36210 18114 36210 15522 36210 16861 36211 15522 36211 18115 36211 18115 36212 15522 36212 15521 36212 18115 36213 15521 36213 18116 36213 18116 36214 15521 36214 15520 36214 18116 36215 15520 36215 18117 36215 18117 36216 15520 36216 15518 36216 18117 36217 15518 36217 16864 36217 16864 36218 15518 36218 18118 36218 16864 36219 18118 36219 18119 36219 18119 36220 18118 36220 21446 36220 18119 36221 21446 36221 19424 36221 19424 36222 21446 36222 18120 36222 19424 36223 18120 36223 19426 36223 19426 36224 18120 36224 21448 36224 19426 36225 21448 36225 19428 36225 19428 36226 21448 36226 21451 36226 19428 36227 21451 36227 18110 36227 19455 36228 19453 36228 18121 36228 18121 36229 19453 36229 18123 36229 18121 36230 18123 36230 18122 36230 18122 36231 18123 36231 19452 36231 18122 36232 19452 36232 18124 36232 18124 36233 19452 36233 19450 36233 18124 36234 19450 36234 18125 36234 18125 36235 19450 36235 18126 36235 18125 36236 18126 36236 21471 36236 21471 36237 18126 36237 18127 36237 21471 36238 18127 36238 18128 36238 18128 36239 18127 36239 18129 36239 18128 36240 18129 36240 15491 36240 15491 36241 18129 36241 18130 36241 15491 36242 18130 36242 15490 36242 15490 36243 18130 36243 18131 36243 15490 36244 18131 36244 15488 36244 15488 36245 18131 36245 16843 36245 15488 36246 16843 36246 18132 36246 18132 36247 16843 36247 18133 36247 18132 36248 18133 36248 18135 36248 18135 36249 18133 36249 18134 36249 18135 36250 18134 36250 18136 36250 18136 36251 18134 36251 19455 36251 18136 36252 19455 36252 18121 36252 18137 36253 18138 36253 18139 36253 18139 36254 18138 36254 18141 36254 18139 36255 18141 36255 18140 36255 18140 36256 18141 36256 18143 36256 18140 36257 18143 36257 18142 36257 18142 36258 18143 36258 21490 36258 18142 36259 21490 36259 16821 36259 16821 36260 21490 36260 18144 36260 16821 36261 18144 36261 16822 36261 16822 36262 18144 36262 15474 36262 16822 36263 15474 36263 18145 36263 18145 36264 15474 36264 15473 36264 18145 36265 15473 36265 18146 36265 18146 36266 15473 36266 18147 36266 18146 36267 18147 36267 18148 36267 18148 36268 18147 36268 15471 36268 18148 36269 15471 36269 16826 36269 16826 36270 15471 36270 15470 36270 16826 36271 15470 36271 19472 36271 19472 36272 15470 36272 18149 36272 19472 36273 18149 36273 18150 36273 18150 36274 18149 36274 18151 36274 18150 36275 18151 36275 18152 36275 18152 36276 18151 36276 18153 36276 18152 36277 18153 36277 18137 36277 18137 36278 18153 36278 18138 36278 19800 36279 16649 36279 18154 36279 18154 36280 16649 36280 18155 36280 18154 36281 18155 36281 18156 36281 18156 36282 18155 36282 19663 36282 18156 36283 19663 36283 19802 36283 19802 36284 19663 36284 18157 36284 19802 36285 18157 36285 19801 36285 19801 36286 18157 36286 19667 36286 19801 36287 19667 36287 18158 36287 18158 36288 19667 36288 18159 36288 18158 36289 18159 36289 19799 36289 19799 36290 18159 36290 18160 36290 18161 36291 18162 36291 18163 36291 18163 36292 18162 36292 19669 36292 18163 36293 19669 36293 18165 36293 18165 36294 19669 36294 18164 36294 18165 36295 18164 36295 18166 36295 18166 36296 18164 36296 18167 36296 18166 36297 18167 36297 18168 36297 18168 36298 18167 36298 19672 36298 18168 36299 19672 36299 19795 36299 19795 36300 19672 36300 19674 36300 19795 36301 19674 36301 19797 36301 19797 36302 19674 36302 19675 36302 17534 36303 18170 36303 18169 36303 18169 36304 18170 36304 18171 36304 18169 36305 18171 36305 18173 36305 18173 36306 18171 36306 18172 36306 18173 36307 18172 36307 18174 36307 18174 36308 18172 36308 19678 36308 18174 36309 19678 36309 18175 36309 18175 36310 19678 36310 19679 36310 18175 36311 19679 36311 19791 36311 19791 36312 19679 36312 18176 36312 19791 36313 18176 36313 19792 36313 19792 36314 18176 36314 19680 36314 18177 36315 18178 36315 19790 36315 19790 36316 18178 36316 18180 36316 19790 36317 18180 36317 18179 36317 18179 36318 18180 36318 19682 36318 18179 36319 19682 36319 19788 36319 19788 36320 19682 36320 18181 36320 19788 36321 18181 36321 19789 36321 19789 36322 18181 36322 18182 36322 19789 36323 18182 36323 18183 36323 18183 36324 18182 36324 19686 36324 18183 36325 19686 36325 18184 36325 18184 36326 19686 36326 18186 36326 18184 36327 18186 36327 18185 36327 18185 36328 18186 36328 19689 36328 18194 36329 18187 36329 18188 36329 17514 36330 19784 36330 19700 36330 19700 36331 19784 36331 18189 36331 19700 36332 18189 36332 19699 36332 19699 36333 18189 36333 19785 36333 18191 36334 18190 36334 19785 36334 19785 36335 18190 36335 19697 36335 19785 36336 19697 36336 19699 36336 19781 36337 19694 36337 18191 36337 18191 36338 19694 36338 19695 36338 18191 36339 19695 36339 18190 36339 18192 36340 19693 36340 19781 36340 19781 36341 19693 36341 18193 36341 19781 36342 18193 36342 19694 36342 18188 36343 19690 36343 18194 36343 18194 36344 19690 36344 18195 36344 18194 36345 18195 36345 18192 36345 18192 36346 18195 36346 18196 36346 18192 36347 18196 36347 19693 36347 19780 36348 19702 36348 19779 36348 19779 36349 19702 36349 19705 36349 19779 36350 19705 36350 18197 36350 18197 36351 19705 36351 19706 36351 18197 36352 19706 36352 18198 36352 18198 36353 19706 36353 18200 36353 18198 36354 18200 36354 18199 36354 18199 36355 18200 36355 18201 36355 18199 36356 18201 36356 18202 36356 18202 36357 18201 36357 18203 36357 18202 36358 18203 36358 18204 36358 18204 36359 18203 36359 17506 36359 17504 36360 18205 36360 19777 36360 19777 36361 18205 36361 18206 36361 19777 36362 18206 36362 18207 36362 18207 36363 18206 36363 18208 36363 18207 36364 18208 36364 18209 36364 18209 36365 18208 36365 19709 36365 18209 36366 19709 36366 18210 36366 18210 36367 19709 36367 19711 36367 18210 36368 19711 36368 19773 36368 19773 36369 19711 36369 19713 36369 19773 36370 19713 36370 19774 36370 19774 36371 19713 36371 19715 36371 19774 36372 19715 36372 18211 36372 18211 36373 19715 36373 16600 36373 17496 36374 19717 36374 18212 36374 18212 36375 19717 36375 18213 36375 18212 36376 18213 36376 18214 36376 18214 36377 18213 36377 19719 36377 18214 36378 19719 36378 19772 36378 19772 36379 19719 36379 18215 36379 19772 36380 18215 36380 18216 36380 18216 36381 18215 36381 18217 36381 18216 36382 18217 36382 18219 36382 18219 36383 18217 36383 18218 36383 18219 36384 18218 36384 18220 36384 18220 36385 18218 36385 18221 36385 19765 36386 18222 36386 19764 36386 19764 36387 18222 36387 19722 36387 19764 36388 19722 36388 19763 36388 19763 36389 19722 36389 19723 36389 19763 36390 19723 36390 18223 36390 18223 36391 19723 36391 19726 36391 18223 36392 19726 36392 19762 36392 19762 36393 19726 36393 19727 36393 19762 36394 19727 36394 18224 36394 18224 36395 19727 36395 18225 36395 18224 36396 18225 36396 18226 36396 18226 36397 18225 36397 18227 36397 18226 36398 18227 36398 19768 36398 19768 36399 18227 36399 17484 36399 17483 36400 16586 36400 19759 36400 19759 36401 16586 36401 19732 36401 19759 36402 19732 36402 18228 36402 18228 36403 19732 36403 19734 36403 18228 36404 19734 36404 18229 36404 18229 36405 19734 36405 19736 36405 18229 36406 19736 36406 19760 36406 19760 36407 19736 36407 18230 36407 19760 36408 18230 36408 19758 36408 19758 36409 18230 36409 18231 36409 19758 36410 18231 36410 17472 36410 17472 36411 18231 36411 17474 36411 18615 36412 18628 36412 18614 36412 19635 36413 18556 36413 18439 36413 19639 36414 18600 36414 19636 36414 18232 36415 19683 36415 18620 36415 18327 36416 18233 36416 18531 36416 18359 36417 18354 36417 18234 36417 16683 36418 18494 36418 16682 36418 18235 36419 18346 36419 18604 36419 18346 36420 18235 36420 18630 36420 18236 36421 18637 36421 18635 36421 18481 36422 18237 36422 18384 36422 17142 36423 19077 36423 18517 36423 18243 36424 18636 36424 18239 36424 19498 36425 16741 36425 18238 36425 18238 36426 16741 36426 18240 36426 18238 36427 18240 36427 18239 36427 18239 36428 18240 36428 18241 36428 18239 36429 18241 36429 18243 36429 19642 36430 16744 36430 18242 36430 18242 36431 16744 36431 16743 36431 18242 36432 16743 36432 18444 36432 18243 36433 18244 36433 18636 36433 18636 36434 18244 36434 18245 36434 18636 36435 18245 36435 18246 36435 18246 36436 18245 36436 19566 36436 18246 36437 19566 36437 18542 36437 18542 36438 19566 36438 18247 36438 18542 36439 18247 36439 19564 36439 18382 36440 19263 36440 18379 36440 18579 36441 16940 36441 16938 36441 18379 36442 19296 36442 18580 36442 16970 36443 16972 36443 19299 36443 19263 36444 19262 36444 18379 36444 18379 36445 19262 36445 18248 36445 18379 36446 18248 36446 19296 36446 19296 36447 18248 36447 16970 36447 19296 36448 16970 36448 19298 36448 19298 36449 16970 36449 19299 36449 18251 36450 18249 36450 16973 36450 16973 36451 18249 36451 18250 36451 16973 36452 18250 36452 16972 36452 16972 36453 18250 36453 19301 36453 16972 36454 19301 36454 19299 36454 16937 36455 16935 36455 19622 36455 19622 36456 16935 36456 16934 36456 19622 36457 16934 36457 19623 36457 19623 36458 16934 36458 18251 36458 19623 36459 18251 36459 18254 36459 18254 36460 18251 36460 16973 36460 18254 36461 16973 36461 16977 36461 18381 36462 18252 36462 18256 36462 16977 36463 18253 36463 18254 36463 18254 36464 18253 36464 18255 36464 18254 36465 18255 36465 18256 36465 18256 36466 18255 36466 19266 36466 18256 36467 19266 36467 18381 36467 18381 36468 19266 36468 18257 36468 18412 36469 18588 36469 19269 36469 19269 36470 18588 36470 18590 36470 19269 36471 18590 36471 18261 36471 18590 36472 19316 36472 19315 36472 18258 36473 19627 36473 16912 36473 19316 36474 18590 36474 19317 36474 19317 36475 18590 36475 18572 36475 19317 36476 18572 36476 19319 36476 19315 36477 18259 36477 18590 36477 18590 36478 18259 36478 18260 36478 18590 36479 18260 36479 18261 36479 18261 36480 18260 36480 18263 36480 18261 36481 18263 36481 18262 36481 18262 36482 18263 36482 18264 36482 18271 36483 18266 36483 18265 36483 18265 36484 18266 36484 18262 36484 18264 36485 16915 36485 18262 36485 18262 36486 16915 36486 18267 36486 18262 36487 18267 36487 18265 36487 18265 36488 18267 36488 18268 36488 18265 36489 18268 36489 19627 36489 19627 36490 18268 36490 18269 36490 19627 36491 18269 36491 16912 36491 19628 36492 16965 36492 18270 36492 18270 36493 16965 36493 18271 36493 18270 36494 18271 36494 19626 36494 19626 36495 18271 36495 18265 36495 18272 36496 16899 36496 18275 36496 18273 36497 19342 36497 18628 36497 18628 36498 19342 36498 18274 36498 18628 36499 18274 36499 18629 36499 16899 36500 16898 36500 18275 36500 18275 36501 16898 36501 16897 36501 18275 36502 16897 36502 19628 36502 19628 36503 16897 36503 18276 36503 19628 36504 18276 36504 18283 36504 18280 36505 18273 36505 16969 36505 16969 36506 18273 36506 18628 36506 16969 36507 18628 36507 18277 36507 18277 36508 18628 36508 18615 36508 18277 36509 18615 36509 18278 36509 18278 36510 18615 36510 18412 36510 18278 36511 18412 36511 18279 36511 18279 36512 18412 36512 19269 36512 18280 36513 16969 36513 18281 36513 18281 36514 16969 36514 18282 36514 18281 36515 18282 36515 18283 36515 18283 36516 18282 36516 16967 36516 18283 36517 16967 36517 19628 36517 19628 36518 16967 36518 18284 36518 19628 36519 18284 36519 16965 36519 16885 36520 16883 36520 18285 36520 18563 36521 19368 36521 18290 36521 19278 36522 18298 36522 18593 36522 18286 36523 16958 36523 18287 36523 18287 36524 16958 36524 19271 36524 18287 36525 19271 36525 18288 36525 18285 36526 16883 36526 18289 36526 18289 36527 16883 36527 16882 36527 18289 36528 16882 36528 18564 36528 19368 36529 18291 36529 18290 36529 18290 36530 18291 36530 18292 36530 18290 36531 18292 36531 18602 36531 18602 36532 18292 36532 18293 36532 18602 36533 18293 36533 18295 36533 18297 36534 18294 36534 18602 36534 19271 36535 19272 36535 18288 36535 18288 36536 19272 36536 18296 36536 18288 36537 18296 36537 18295 36537 18295 36538 18296 36538 19274 36538 18295 36539 19274 36539 18602 36539 18602 36540 19274 36540 19276 36540 18602 36541 19276 36541 18297 36541 18298 36542 18299 36542 18474 36542 18474 36543 18299 36543 18300 36543 18474 36544 18300 36544 18473 36544 18299 36545 16961 36545 18300 36545 18300 36546 16961 36546 16959 36546 18300 36547 16959 36547 18285 36547 18285 36548 16959 36548 16958 36548 18285 36549 16958 36549 16885 36549 16885 36550 16958 36550 18286 36550 19155 36551 18354 36551 18301 36551 18301 36552 18354 36552 18302 36552 18301 36553 18302 36553 18303 36553 18303 36554 18302 36554 18311 36554 19155 36555 18304 36555 18354 36555 18354 36556 18304 36556 19154 36556 18354 36557 19154 36557 18234 36557 18234 36558 19154 36558 18305 36558 18234 36559 18305 36559 18306 36559 18306 36560 18305 36560 19151 36560 18306 36561 19151 36561 18520 36561 19149 36562 18308 36562 18307 36562 18307 36563 18308 36563 18309 36563 18307 36564 18309 36564 18310 36564 18310 36565 18309 36565 17061 36565 18310 36566 17061 36566 18594 36566 18594 36567 17061 36567 17060 36567 18594 36568 17060 36568 18311 36568 19069 36569 18343 36569 17085 36569 17081 36570 17080 36570 18604 36570 17081 36571 18604 36571 17083 36571 17083 36572 18604 36572 19071 36572 17083 36573 19071 36573 18312 36573 19069 36574 17085 36574 19071 36574 19071 36575 17085 36575 17084 36575 19071 36576 17084 36576 18312 36576 18313 36577 18317 36577 18314 36577 18314 36578 18317 36578 16671 36578 18314 36579 16671 36579 17079 36579 17079 36580 16671 36580 18315 36580 17079 36581 18315 36581 17080 36581 18313 36582 18316 36582 18317 36582 18317 36583 18316 36583 19135 36583 18317 36584 19135 36584 18318 36584 18318 36585 19135 36585 19133 36585 18318 36586 19133 36586 18343 36586 17152 36587 18349 36587 18350 36587 18350 36588 18319 36588 17152 36588 17152 36589 18319 36589 18325 36589 17152 36590 18325 36590 18320 36590 18320 36591 18325 36591 18321 36591 18320 36592 18321 36592 19066 36592 19066 36593 18321 36593 18322 36593 19066 36594 18322 36594 18345 36594 17105 36595 18323 36595 18324 36595 18324 36596 18323 36596 19121 36596 18325 36597 18326 36597 18321 36597 18321 36598 18326 36598 19117 36598 18321 36599 19117 36599 16668 36599 16668 36600 19117 36600 19115 36600 16668 36601 19115 36601 18327 36601 18327 36602 19115 36602 17109 36602 18327 36603 17109 36603 18233 36603 18233 36604 17109 36604 18329 36604 18233 36605 18329 36605 18328 36605 18328 36606 18329 36606 17108 36606 18328 36607 17108 36607 18324 36607 18324 36608 17108 36608 18330 36608 18324 36609 18330 36609 17105 36609 18331 36610 18332 36610 17123 36610 17123 36611 18332 36611 18335 36611 17123 36612 18335 36612 18333 36612 18533 36613 18334 36613 18341 36613 18341 36614 18334 36614 18331 36614 18333 36615 18335 36615 17125 36615 17125 36616 18335 36616 18338 36616 17125 36617 18338 36617 18336 36617 18342 36618 19096 36618 18337 36618 18337 36619 19096 36619 18339 36619 18337 36620 18339 36620 18338 36620 18338 36621 18339 36621 18340 36621 18338 36622 18340 36622 18336 36622 18341 36623 19100 36623 18533 36623 18533 36624 19100 36624 19098 36624 18533 36625 19098 36625 18342 36625 18342 36626 19098 36626 19097 36626 18342 36627 19097 36627 19096 36627 18343 36628 19069 36628 18318 36628 18318 36629 19069 36629 18344 36629 18318 36630 18344 36630 18345 36630 18345 36631 18344 36631 19067 36631 18345 36632 19067 36632 19066 36632 17147 36633 18347 36633 18346 36633 18346 36634 18347 36634 18604 36634 18604 36635 18347 36635 18348 36635 18604 36636 18348 36636 19071 36636 17147 36637 18346 36637 17150 36637 17150 36638 18346 36638 18324 36638 17150 36639 18324 36639 18349 36639 18349 36640 18324 36640 19121 36640 18349 36641 19121 36641 18350 36641 18351 36642 17145 36642 18302 36642 18302 36643 17145 36643 18352 36643 18352 36644 17145 36644 18353 36644 18352 36645 18353 36645 18591 36645 18359 36646 18360 36646 18354 36646 18354 36647 18360 36647 18355 36647 18354 36648 18355 36648 18302 36648 18302 36649 18355 36649 18356 36649 18302 36650 18356 36650 18351 36650 17142 36651 18517 36651 18591 36651 16672 36652 16675 36652 19076 36652 19076 36653 18357 36653 16672 36653 16672 36654 18357 36654 18358 36654 16672 36655 18358 36655 18359 36655 18359 36656 18358 36656 19073 36656 18359 36657 19073 36657 18360 36657 18838 36658 18836 36658 18510 36658 18510 36659 18836 36659 18834 36659 18365 36660 17255 36660 18595 36660 18409 36661 18408 36661 18922 36661 18922 36662 18408 36662 18372 36662 18410 36663 18361 36663 17340 36663 17340 36664 18361 36664 18366 36664 18362 36665 18363 36665 18595 36665 18595 36666 18363 36666 17342 36666 18595 36667 17342 36667 18365 36667 18365 36668 17342 36668 18364 36668 18365 36669 18364 36669 17256 36669 17256 36670 18364 36670 18366 36670 17256 36671 18366 36671 18367 36671 18367 36672 18366 36672 18361 36672 18596 36673 17254 36673 18368 36673 18368 36674 17254 36674 18369 36674 18368 36675 18369 36675 18506 36675 18506 36676 18369 36676 18371 36676 18506 36677 18371 36677 18370 36677 18370 36678 18371 36678 18924 36678 18370 36679 18924 36679 18372 36679 18372 36680 18924 36680 18923 36680 18372 36681 18923 36681 18922 36681 18392 36682 18828 36682 18894 36682 18501 36683 18373 36683 18503 36683 18503 36684 18373 36684 18609 36684 17281 36685 18374 36685 18424 36685 18424 36686 18374 36686 17280 36686 18424 36687 17280 36687 18829 36687 18829 36688 17280 36688 17279 36688 18829 36689 17279 36689 18828 36689 18828 36690 17279 36690 18375 36690 18828 36691 18375 36691 18894 36691 18376 36692 18377 36692 18898 36692 18898 36693 18377 36693 18393 36693 18898 36694 18393 36694 18893 36694 18825 36695 18378 36695 18386 36695 18578 36696 18380 36696 18379 36696 18379 36697 18380 36697 18381 36697 18379 36698 18381 36698 18382 36698 18382 36699 18381 36699 18257 36699 18237 36700 18383 36700 18384 36700 18384 36701 18383 36701 18385 36701 18384 36702 18385 36702 18386 36702 18386 36703 18385 36703 18387 36703 18386 36704 18387 36704 18825 36704 18380 36705 18388 36705 18381 36705 18381 36706 18388 36706 17352 36706 18381 36707 17352 36707 18389 36707 18817 36708 18480 36708 18390 36708 18252 36709 18381 36709 16685 36709 16685 36710 18381 36710 18389 36710 16685 36711 18389 36711 18390 36711 18390 36712 18389 36712 17349 36712 18390 36713 17349 36713 18817 36713 18423 36714 17348 36714 18582 36714 18402 36715 18391 36715 16681 36715 16681 36716 18391 36716 18392 36716 16681 36717 18392 36717 18393 36717 18393 36718 18392 36718 18894 36718 18393 36719 18894 36719 18893 36719 18400 36720 18395 36720 18401 36720 18394 36721 18398 36721 18399 36721 18400 36722 18879 36722 18395 36722 18395 36723 18879 36723 18878 36723 18395 36724 18878 36724 18396 36724 18396 36725 18878 36725 18397 36725 18396 36726 18397 36726 17301 36726 18398 36727 18400 36727 18399 36727 18399 36728 18400 36728 18401 36728 18399 36729 18401 36729 18402 36729 18402 36730 18401 36730 18826 36730 18402 36731 18826 36731 18391 36731 17295 36732 18489 36732 18488 36732 17300 36733 18403 36733 18404 36733 18404 36734 18403 36734 17298 36734 18404 36735 17298 36735 18488 36735 18488 36736 17298 36736 17297 36736 18488 36737 17297 36737 17295 36737 17345 36738 18405 36738 18583 36738 18583 36739 18405 36739 18396 36739 18583 36740 18396 36740 18404 36740 18404 36741 18396 36741 17301 36741 18404 36742 17301 36742 17300 36742 18511 36743 18406 36743 18509 36743 18509 36744 18406 36744 18407 36744 18407 36745 18406 36745 18408 36745 18407 36746 18408 36746 18410 36746 18410 36747 18408 36747 18409 36747 18410 36748 18409 36748 18361 36748 18589 36749 18411 36749 18694 36749 18412 36750 18618 36750 18411 36750 18411 36751 18618 36751 18693 36751 18411 36752 18693 36752 18694 36752 18616 36753 18413 36753 18690 36753 18690 36754 18413 36754 18688 36754 18414 36755 18612 36755 18416 36755 18613 36756 18415 36756 18685 36756 18685 36757 18415 36757 18414 36757 18685 36758 18414 36758 18684 36758 18684 36759 18414 36759 18416 36759 18648 36760 18417 36760 18641 36760 18632 36761 18631 36761 18418 36761 18422 36762 17448 36762 18419 36762 18419 36763 17448 36763 18235 36763 18419 36764 18235 36764 18420 36764 18420 36765 18235 36765 18604 36765 18428 36766 18421 36766 18422 36766 18422 36767 18421 36767 17446 36767 18422 36768 17446 36768 17448 36768 18829 36769 18423 36769 18424 36769 18424 36770 18423 36770 18582 36770 18424 36771 18582 36771 18425 36771 18585 36772 18426 36772 18582 36772 18582 36773 18426 36773 18427 36773 18582 36774 18427 36774 18425 36774 18425 36775 18427 36775 17442 36775 18425 36776 17442 36776 18428 36776 18428 36777 17442 36777 17443 36777 18428 36778 17443 36778 18421 36778 18586 36779 17438 36779 18585 36779 18694 36780 18429 36780 18575 36780 18575 36781 18429 36781 18430 36781 18442 36782 18441 36782 18431 36782 18431 36783 18432 36783 18592 36783 18432 36784 18433 36784 18592 36784 18592 36785 18433 36785 18434 36785 18592 36786 18434 36786 18435 36786 18435 36787 18434 36787 18436 36787 18435 36788 18436 36788 19506 36788 19506 36789 18437 36789 18435 36789 18435 36790 18437 36790 18438 36790 18435 36791 18438 36791 18556 36791 18556 36792 18438 36792 16793 36792 18556 36793 16793 36793 18439 36793 18439 36794 16793 36794 18440 36794 18439 36795 18440 36795 18469 36795 18441 36796 18442 36796 16788 36796 16788 36797 18442 36797 18443 36797 16788 36798 18443 36798 18470 36798 18444 36799 16741 36799 18242 36799 18242 36800 16741 36800 19498 36800 18242 36801 19498 36801 18445 36801 18445 36802 19498 36802 16794 36802 18445 36803 16794 36803 18453 36803 18416 36804 18610 36804 18446 36804 18416 36805 18446 36805 18636 36805 18636 36806 18446 36806 19502 36806 18636 36807 19502 36807 18239 36807 18619 36808 16799 36808 18611 36808 18447 36809 18448 36809 18551 36809 18551 36810 18448 36810 16713 36810 18552 36811 18449 36811 18620 36811 18452 36812 19590 36812 18447 36812 18447 36813 19590 36813 16712 36813 18447 36814 16712 36814 18448 36814 18449 36815 16714 36815 18619 36815 18619 36816 16714 36816 19582 36816 19582 36817 18450 36817 18619 36817 18619 36818 18450 36818 18451 36818 18619 36819 18451 36819 16799 36819 18451 36820 19586 36820 16799 36820 16799 36821 19586 36821 19588 36821 16799 36822 19588 36822 18452 36822 18452 36823 19588 36823 19589 36823 18452 36824 19589 36824 19590 36824 16794 36825 18454 36825 18453 36825 18453 36826 18454 36826 16796 36826 18453 36827 16796 36827 18455 36827 18455 36828 16796 36828 18456 36828 18455 36829 18456 36829 18447 36829 18447 36830 18456 36830 16800 36830 18447 36831 16800 36831 18452 36831 18643 36832 18644 36832 19534 36832 19534 36833 18644 36833 18457 36833 18458 36834 19496 36834 19495 36834 16806 36835 16805 36835 18466 36835 18458 36836 19495 36836 18466 36836 18466 36837 19495 36837 18459 36837 18466 36838 18459 36838 16806 36838 18460 36839 18537 36839 16770 36839 16770 36840 18537 36840 18466 36840 19487 36841 18643 36841 16803 36841 16803 36842 18643 36842 19534 36842 16803 36843 19534 36843 18461 36843 18461 36844 19534 36844 19535 36844 18461 36845 19535 36845 16804 36845 18457 36846 18462 36846 16765 36846 16765 36847 18462 36847 18463 36847 16765 36848 18463 36848 16766 36848 16766 36849 18463 36849 16768 36849 19487 36850 19490 36850 18643 36850 18643 36851 19490 36851 19491 36851 18643 36852 19491 36852 18464 36852 18464 36853 19491 36853 18465 36853 18464 36854 18465 36854 18458 36854 18458 36855 18465 36855 19494 36855 18458 36856 19494 36856 19496 36856 19535 36857 19536 36857 16804 36857 16804 36858 19536 36858 19538 36858 16804 36859 19538 36859 16805 36859 19538 36860 19541 36860 16805 36860 16805 36861 19541 36861 19542 36861 16805 36862 19542 36862 18466 36862 18466 36863 19542 36863 19543 36863 18466 36864 19543 36864 16770 36864 18298 36865 18474 36865 18593 36865 18593 36866 18474 36866 19701 36866 18593 36867 19701 36867 19698 36867 19698 36868 19696 36868 18593 36868 18593 36869 19696 36869 18467 36869 18593 36870 18467 36870 18442 36870 18467 36871 19692 36871 18442 36871 18442 36872 19692 36872 19691 36872 18442 36873 19691 36873 18443 36873 18443 36874 19691 36874 18468 36874 18443 36875 18468 36875 18471 36875 18440 36876 18470 36876 18469 36876 18469 36877 18470 36877 18443 36877 18469 36878 18443 36878 18472 36878 18472 36879 18443 36879 18471 36879 18471 36880 16621 36880 18472 36880 18472 36881 16621 36881 16620 36881 18472 36882 16620 36882 18473 36882 18473 36883 16620 36883 16619 36883 18473 36884 16619 36884 18474 36884 18474 36885 16619 36885 16617 36885 18474 36886 16617 36886 19701 36886 18494 36887 18486 36887 18475 36887 18476 36888 18477 36888 18386 36888 18386 36889 18477 36889 18478 36889 18386 36890 18478 36890 18384 36890 18384 36891 18478 36891 18479 36891 18384 36892 18479 36892 17317 36892 18817 36893 18481 36893 18480 36893 18480 36894 18481 36894 18384 36894 18480 36895 18384 36895 18482 36895 18482 36896 18384 36896 17317 36896 18482 36897 17317 36897 18483 36897 18862 36898 16683 36898 18864 36898 18864 36899 16683 36899 18483 36899 18864 36900 18483 36900 18484 36900 18484 36901 18483 36901 17317 36901 18862 36902 18485 36902 16683 36902 16683 36903 18485 36903 18861 36903 16683 36904 18861 36904 18494 36904 18494 36905 18861 36905 18860 36905 18494 36906 18860 36906 18486 36906 18496 36907 18487 36907 18488 36907 18488 36908 18487 36908 19718 36908 18488 36909 19718 36909 18491 36909 18394 36910 18399 36910 18489 36910 18489 36911 18399 36911 18490 36911 18489 36912 18490 36912 18488 36912 18488 36913 18490 36913 18495 36913 18488 36914 18495 36914 18496 36914 18491 36915 18492 36915 18497 36915 16596 36916 18493 36916 18494 36916 18494 36917 18493 36917 16595 36917 18494 36918 16595 36918 16682 36918 16682 36919 16595 36919 19721 36919 16682 36920 19721 36920 18495 36920 18495 36921 19721 36921 19720 36921 18495 36922 19720 36922 18496 36922 18492 36923 18498 36923 18497 36923 18497 36924 18498 36924 16597 36924 18497 36925 16597 36925 18494 36925 18494 36926 16597 36926 18499 36926 18494 36927 18499 36927 16596 36927 16593 36928 18500 36928 18608 36928 16591 36929 16589 36929 18503 36929 18503 36930 16589 36930 18502 36930 18503 36931 18502 36931 18501 36931 18501 36932 18502 36932 18377 36932 18501 36933 18377 36933 18902 36933 18902 36934 18377 36934 18376 36934 19725 36935 19724 36935 18368 36935 18368 36936 19724 36936 16594 36936 18608 36937 18500 36937 18503 36937 18503 36938 18500 36938 18504 36938 18503 36939 18504 36939 16591 36939 16589 36940 16588 36940 18502 36940 18502 36941 16588 36941 19731 36941 18502 36942 19731 36942 18505 36942 19731 36943 19730 36943 18505 36943 18505 36944 19730 36944 19729 36944 18505 36945 19729 36945 19728 36945 18370 36946 18507 36946 18506 36946 18506 36947 18507 36947 18505 36947 18506 36948 18505 36948 18368 36948 18368 36949 18505 36949 19728 36949 18368 36950 19728 36950 19725 36950 18508 36951 18513 36951 18510 36951 18509 36952 18838 36952 18511 36952 18511 36953 18838 36953 18510 36953 18511 36954 18510 36954 18512 36954 18512 36955 18510 36955 18513 36955 18512 36956 18513 36956 18514 36956 16676 36957 18517 36957 16675 36957 16675 36958 18517 36958 19077 36958 16675 36959 19077 36959 19076 36959 18514 36960 19738 36960 18512 36960 18512 36961 19738 36961 19737 36961 18512 36962 19737 36962 16676 36962 16676 36963 19737 36963 19735 36963 19735 36964 18515 36964 16676 36964 16676 36965 18515 36965 19733 36965 16676 36966 19733 36966 18517 36966 18517 36967 19733 36967 16587 36967 18517 36968 16587 36968 16585 36968 16585 36969 18516 36969 18517 36969 18517 36970 18516 36970 18518 36970 18517 36971 18518 36971 18510 36971 18510 36972 18518 36972 18519 36972 18510 36973 18519 36973 18508 36973 19151 36974 19149 36974 18520 36974 18520 36975 19149 36975 18307 36975 18520 36976 18307 36976 18521 36976 18521 36977 18307 36977 18310 36977 18521 36978 18310 36978 18524 36978 16609 36979 19707 36979 18310 36979 16609 36980 18310 36980 18522 36980 19707 36981 18523 36981 18310 36981 18310 36982 18523 36982 18525 36982 18310 36983 18525 36983 18524 36983 18524 36984 18525 36984 18526 36984 18524 36985 18526 36985 16671 36985 18605 36986 16612 36986 18522 36986 18526 36987 19704 36987 16671 36987 16671 36988 19704 36988 19703 36988 16671 36989 19703 36989 18315 36989 18315 36990 19703 36990 18527 36990 18527 36991 16615 36991 18315 36991 18315 36992 16615 36992 16614 36992 18315 36993 16614 36993 18605 36993 18605 36994 16614 36994 18528 36994 18605 36995 18528 36995 16612 36995 16666 36996 18532 36996 18529 36996 18530 36997 16602 36997 16601 36997 16608 36998 16606 36998 18334 36998 18334 36999 16606 36999 16605 36999 18334 37000 16605 37000 18530 37000 18530 37001 16605 37001 16603 37001 18530 37002 16603 37002 16602 37002 19716 37003 19714 37003 18233 37003 18233 37004 19714 37004 19712 37004 18233 37005 19712 37005 18531 37005 18531 37006 19712 37006 19710 37006 18531 37007 19710 37007 16666 37007 16666 37008 19710 37008 19708 37008 16666 37009 19708 37009 18532 37009 18342 37010 16667 37010 18533 37010 18533 37011 16667 37011 16666 37011 18533 37012 16666 37012 18334 37012 18334 37013 16666 37013 18529 37013 18334 37014 18529 37014 16608 37014 18642 37015 18534 37015 18335 37015 16665 37016 18338 37016 18535 37016 18535 37017 18338 37017 19064 37017 18534 37018 19059 37018 18335 37018 18335 37019 19059 37019 19061 37019 18335 37020 19061 37020 18338 37020 18338 37021 19061 37021 19062 37021 18338 37022 19062 37022 19064 37022 17160 37023 17161 37023 18643 37023 18643 37024 17161 37024 18642 37024 18535 37025 17154 37025 16665 37025 16665 37026 17154 37026 18536 37026 16665 37027 18536 37027 18464 37027 18464 37028 18536 37028 17157 37028 18464 37029 17157 37029 18643 37029 18643 37030 17157 37030 17158 37030 18643 37031 17158 37031 17160 37031 18460 37032 16768 37032 18537 37032 18537 37033 16768 37033 18463 37033 18537 37034 18463 37034 18538 37034 18538 37035 18463 37035 18462 37035 18538 37036 18462 37036 18539 37036 18540 37037 18541 37037 18542 37037 18542 37038 18541 37038 16627 37038 18542 37039 16627 37039 18543 37039 18548 37040 18544 37040 18462 37040 18462 37041 18544 37041 18545 37041 18462 37042 18545 37042 18539 37042 18539 37043 18545 37043 18546 37043 18539 37044 18546 37044 18549 37044 18549 37045 18546 37045 16629 37045 18543 37046 19681 37046 18639 37046 18639 37047 19681 37047 18547 37047 18639 37048 18547 37048 18462 37048 18462 37049 18547 37049 19677 37049 18462 37050 19677 37050 18548 37050 16629 37051 18540 37051 18549 37051 18549 37052 18540 37052 18542 37052 18549 37053 18542 37053 19640 37053 19640 37054 18542 37054 19564 37054 19640 37055 19564 37055 19642 37055 19642 37056 19564 37056 19563 37056 19642 37057 19563 37057 16744 37057 18553 37058 16625 37058 18550 37058 18550 37059 16625 37059 19639 37059 16713 37060 18552 37060 18551 37060 18551 37061 18552 37061 18620 37061 18551 37062 18620 37062 18550 37062 18550 37063 18620 37063 19683 37063 18550 37064 19683 37064 18553 37064 16625 37065 16624 37065 19639 37065 19639 37066 16624 37066 18554 37066 19639 37067 18554 37067 18600 37067 18554 37068 18555 37068 18600 37068 18600 37069 18555 37069 16623 37069 18600 37070 16623 37070 18599 37070 18599 37071 19688 37071 18621 37071 19688 37072 19687 37072 18621 37072 18621 37073 19687 37073 19685 37073 18621 37074 19685 37074 18620 37074 18620 37075 19685 37075 19684 37075 18620 37076 19684 37076 18232 37076 18600 37077 19613 37077 19636 37077 19636 37078 19613 37078 18558 37078 19636 37079 18558 37079 19637 37079 18560 37080 18556 37080 18557 37080 18557 37081 18556 37081 19635 37081 18557 37082 19635 37082 16688 37082 16688 37083 19635 37083 19637 37083 16688 37084 19637 37084 16689 37084 16689 37085 19637 37085 18558 37085 19617 37086 19616 37086 18435 37086 18435 37087 19616 37087 19614 37087 18435 37088 19614 37088 18600 37088 18600 37089 19614 37089 18559 37089 18600 37090 18559 37090 19613 37090 18560 37091 16686 37091 18556 37091 18556 37092 16686 37092 19620 37092 18556 37093 19620 37093 18435 37093 18435 37094 19620 37094 19619 37094 18435 37095 19619 37095 19617 37095 16637 37096 19668 37096 18561 37096 19668 37097 19666 37097 18561 37097 18561 37098 19666 37098 19665 37098 18561 37099 19665 37099 18603 37099 18603 37100 19665 37100 18562 37100 18603 37101 18562 37101 19664 37101 18272 37102 18275 37102 18561 37102 18561 37103 18275 37103 19631 37103 18561 37104 19631 37104 16637 37104 16648 37105 16646 37105 18290 37105 18290 37106 16646 37106 16644 37106 18290 37107 16644 37107 18565 37107 16882 37108 18563 37108 18564 37108 18564 37109 18563 37109 18290 37109 18564 37110 18290 37110 19630 37110 19630 37111 18290 37111 18565 37111 18565 37112 16642 37112 19630 37112 19630 37113 16642 37113 18566 37113 19630 37114 18566 37114 19631 37114 19631 37115 18566 37115 16638 37115 19631 37116 16638 37116 16637 37116 18574 37117 18567 37117 18568 37117 16636 37118 16633 37118 18572 37118 19676 37119 18569 37119 18579 37119 16630 37120 18573 37120 18570 37120 18570 37121 18573 37121 19625 37121 18570 37122 19625 37122 18571 37122 16912 37123 19319 37123 18258 37123 18258 37124 19319 37124 18572 37124 18258 37125 18572 37125 19625 37125 19625 37126 18572 37126 16633 37126 19625 37127 16633 37127 18571 37127 16630 37128 19676 37128 18573 37128 18573 37129 19676 37129 18579 37129 18573 37130 18579 37130 19622 37130 19622 37131 18579 37131 16938 37131 19622 37132 16938 37132 16937 37132 18569 37133 19673 37133 18579 37133 18579 37134 19673 37134 19671 37134 18579 37135 19671 37135 18574 37135 18574 37136 19671 37136 19670 37136 18574 37137 19670 37137 18567 37137 17438 37138 18586 37138 18430 37138 18430 37139 18586 37139 18587 37139 18430 37140 18587 37140 18575 37140 18575 37141 18587 37141 18577 37141 18575 37142 18577 37142 18576 37142 18576 37143 18577 37143 18386 37143 18576 37144 18386 37144 18379 37144 18379 37145 18386 37145 18378 37145 18379 37146 18378 37146 18578 37146 18694 37147 18575 37147 18589 37147 18589 37148 18575 37148 18576 37148 18589 37149 18576 37149 18574 37149 18574 37150 18576 37150 18379 37150 18574 37151 18379 37151 18579 37151 18579 37152 18379 37152 18580 37152 18579 37153 18580 37153 16940 37153 18491 37154 18497 37154 18488 37154 18488 37155 18497 37155 18581 37155 18488 37156 18581 37156 18404 37156 18404 37157 18581 37157 18584 37157 18404 37158 18584 37158 18583 37158 17348 37159 17345 37159 18582 37159 18582 37160 17345 37160 18583 37160 18582 37161 18583 37161 18585 37161 18585 37162 18583 37162 18584 37162 18585 37163 18584 37163 18586 37163 18586 37164 18584 37164 18581 37164 18586 37165 18581 37165 18587 37165 18587 37166 18581 37166 18497 37166 18587 37167 18497 37167 18577 37167 18577 37168 18497 37168 18494 37168 18577 37169 18494 37169 18386 37169 18386 37170 18494 37170 18475 37170 18386 37171 18475 37171 18476 37171 18412 37172 18411 37172 18588 37172 18588 37173 18411 37173 18589 37173 18588 37174 18589 37174 18590 37174 18590 37175 18589 37175 18574 37175 18590 37176 18574 37176 18572 37176 18572 37177 18574 37177 18568 37177 18572 37178 18568 37178 16636 37178 18591 37179 18517 37179 18352 37179 18352 37180 18517 37180 18510 37180 18352 37181 18510 37181 18595 37181 18595 37182 18510 37182 18834 37182 18595 37183 18834 37183 18362 37183 18431 37184 18592 37184 18442 37184 18442 37185 18592 37185 18602 37185 18442 37186 18602 37186 18593 37186 18593 37187 18602 37187 18294 37187 18593 37188 18294 37188 19278 37188 18311 37189 18302 37189 18594 37189 18594 37190 18302 37190 18352 37190 18594 37191 18352 37191 18597 37191 18597 37192 18352 37192 18595 37192 18597 37193 18595 37193 18596 37193 18596 37194 18595 37194 17255 37194 18596 37195 17255 37195 17254 37195 18522 37196 18310 37196 18605 37196 18605 37197 18310 37197 18594 37197 18605 37198 18594 37198 18606 37198 18606 37199 18594 37199 18597 37199 18606 37200 18597 37200 18607 37200 18607 37201 18597 37201 18596 37201 18607 37202 18596 37202 18598 37202 18598 37203 18596 37203 18368 37203 18598 37204 18368 37204 18608 37204 18608 37205 18368 37205 16594 37205 18608 37206 16594 37206 16593 37206 18599 37207 18621 37207 18600 37207 18600 37208 18621 37208 18623 37208 18600 37209 18623 37209 18435 37209 18435 37210 18623 37210 18601 37210 18435 37211 18601 37211 18592 37211 18592 37212 18601 37212 18627 37212 18592 37213 18627 37213 18602 37213 18602 37214 18627 37214 18603 37214 18602 37215 18603 37215 18290 37215 18290 37216 18603 37216 19664 37216 18290 37217 19664 37217 16648 37217 17080 37218 18315 37218 18604 37218 18604 37219 18315 37219 18605 37219 18604 37220 18605 37220 18420 37220 18420 37221 18605 37221 18606 37221 18420 37222 18606 37222 18419 37222 18419 37223 18606 37223 18607 37223 18419 37224 18607 37224 18422 37224 18422 37225 18607 37225 18598 37225 18422 37226 18598 37226 18428 37226 18428 37227 18598 37227 18608 37227 18428 37228 18608 37228 18425 37228 18425 37229 18608 37229 18503 37229 18425 37230 18503 37230 18424 37230 18424 37231 18503 37231 18609 37231 18424 37232 18609 37232 17281 37232 18610 37233 18416 37233 18611 37233 18611 37234 18416 37234 18612 37234 18611 37235 18612 37235 18619 37235 18619 37236 18612 37236 18414 37236 18619 37237 18414 37237 18622 37237 18622 37238 18414 37238 18415 37238 18622 37239 18415 37239 18624 37239 18624 37240 18415 37240 18613 37240 18624 37241 18613 37241 18625 37241 18625 37242 18613 37242 18686 37242 18625 37243 18686 37243 18626 37243 18626 37244 18686 37244 18688 37244 18626 37245 18688 37245 18614 37245 18614 37246 18688 37246 18413 37246 18614 37247 18413 37247 18615 37247 18615 37248 18413 37248 18616 37248 18615 37249 18616 37249 18412 37249 18412 37250 18616 37250 18617 37250 18412 37251 18617 37251 18618 37251 18449 37252 18619 37252 18620 37252 18620 37253 18619 37253 18622 37253 18620 37254 18622 37254 18621 37254 18621 37255 18622 37255 18624 37255 18621 37256 18624 37256 18623 37256 18623 37257 18624 37257 18625 37257 18623 37258 18625 37258 18601 37258 18601 37259 18625 37259 18626 37259 18601 37260 18626 37260 18627 37260 18627 37261 18626 37261 18614 37261 18627 37262 18614 37262 18603 37262 18603 37263 18614 37263 18628 37263 18603 37264 18628 37264 18561 37264 18561 37265 18628 37265 18629 37265 18561 37266 18629 37266 18272 37266 18630 37267 18631 37267 18346 37267 18346 37268 18631 37268 18632 37268 18346 37269 18632 37269 18324 37269 18324 37270 18632 37270 18633 37270 18324 37271 18633 37271 18328 37271 18328 37272 18633 37272 18530 37272 18328 37273 18530 37273 18233 37273 18233 37274 18530 37274 16601 37274 18233 37275 16601 37275 19716 37275 18543 37276 18639 37276 18542 37276 18542 37277 18639 37277 18634 37277 18542 37278 18634 37278 18246 37278 18246 37279 18634 37279 18635 37279 18246 37280 18635 37280 18636 37280 18636 37281 18635 37281 18637 37281 18636 37282 18637 37282 18416 37282 18416 37283 18637 37283 18683 37283 18416 37284 18683 37284 18684 37284 18331 37285 18334 37285 18332 37285 18332 37286 18334 37286 18530 37286 18332 37287 18530 37287 18645 37287 18645 37288 18530 37288 18633 37288 18645 37289 18633 37289 18646 37289 18646 37290 18633 37290 18632 37290 18646 37291 18632 37291 18638 37291 18638 37292 18632 37292 18418 37292 18638 37293 18418 37293 17453 37293 18457 37294 18644 37294 18462 37294 18462 37295 18644 37295 18640 37295 18462 37296 18640 37296 18639 37296 18639 37297 18640 37297 18647 37297 18639 37298 18647 37298 18634 37298 18634 37299 18647 37299 18648 37299 18634 37300 18648 37300 18635 37300 18635 37301 18648 37301 18641 37301 18635 37302 18641 37302 18236 37302 18642 37303 18335 37303 18643 37303 18643 37304 18335 37304 18332 37304 18643 37305 18332 37305 18644 37305 18644 37306 18332 37306 18645 37306 18644 37307 18645 37307 18640 37307 18640 37308 18645 37308 18646 37308 18640 37309 18646 37309 18647 37309 18647 37310 18646 37310 18638 37310 18647 37311 18638 37311 18648 37311 18648 37312 18638 37312 17453 37312 18648 37313 17453 37313 18417 37313 18649 37314 18651 37314 18650 37314 18650 37315 18651 37315 18652 37315 18650 37316 18652 37316 17003 37316 17003 37317 18652 37317 18654 37317 17003 37318 18654 37318 18653 37318 18653 37319 18654 37319 17052 37319 18653 37320 17052 37320 19233 37320 19233 37321 17052 37321 19174 37321 19233 37322 19174 37322 19234 37322 19234 37323 19174 37323 18655 37323 19234 37324 18655 37324 19236 37324 19236 37325 18655 37325 19176 37325 19236 37326 19176 37326 18656 37326 18656 37327 19176 37327 19177 37327 18656 37328 19177 37328 18657 37328 18657 37329 19177 37329 19178 37329 18657 37330 19178 37330 19239 37330 19239 37331 19178 37331 18658 37331 19239 37332 18658 37332 17000 37332 17000 37333 18658 37333 18660 37333 17000 37334 18660 37334 18659 37334 18659 37335 18660 37335 18661 37335 18659 37336 18661 37336 17001 37336 17001 37337 18661 37337 18662 37337 17001 37338 18662 37338 18649 37338 18649 37339 18662 37339 18651 37339 19739 37340 19644 37340 19643 37340 19739 37341 19643 37341 19740 37341 19740 37342 19643 37342 18664 37342 19740 37343 18664 37343 18663 37343 18663 37344 18664 37344 18665 37344 18663 37345 18665 37345 19743 37345 19743 37346 18665 37346 19641 37346 19743 37347 19641 37347 18666 37347 18666 37348 19641 37348 18667 37348 18666 37349 18667 37349 19744 37349 19744 37350 18667 37350 19638 37350 19744 37351 19638 37351 19747 37351 19747 37352 19638 37352 18668 37352 19747 37353 18668 37353 19748 37353 19748 37354 18668 37354 18670 37354 19748 37355 18670 37355 18669 37355 18669 37356 18670 37356 18671 37356 18669 37357 18671 37357 18672 37357 18672 37358 18671 37358 19632 37358 18672 37359 19632 37359 18673 37359 18673 37360 19632 37360 19633 37360 18673 37361 19633 37361 19750 37361 19750 37362 19633 37362 19634 37362 19750 37363 19634 37363 18674 37363 18674 37364 19634 37364 18676 37364 18674 37365 18676 37365 18675 37365 18675 37366 18676 37366 19629 37366 18675 37367 19629 37367 19753 37367 19753 37368 19629 37368 18677 37368 19753 37369 18677 37369 18678 37369 18678 37370 18677 37370 18679 37370 18678 37371 18679 37371 19755 37371 19755 37372 18679 37372 18680 37372 19755 37373 18680 37373 19757 37373 19757 37374 18680 37374 19624 37374 19757 37375 19624 37375 18681 37375 18681 37376 19624 37376 19621 37376 18681 37377 19621 37377 16568 37377 18417 37378 17452 37378 19662 37378 18417 37379 19662 37379 18641 37379 18641 37380 19662 37380 18682 37380 18641 37381 18682 37381 18236 37381 18236 37382 18682 37382 19659 37382 18236 37383 19659 37383 18637 37383 18637 37384 19659 37384 19658 37384 18637 37385 19658 37385 18683 37385 18683 37386 19658 37386 19656 37386 18683 37387 19656 37387 18684 37387 18684 37388 19656 37388 19654 37388 18684 37389 19654 37389 18685 37389 18685 37390 19654 37390 19653 37390 18685 37391 19653 37391 18613 37391 18613 37392 19653 37392 18687 37392 18613 37393 18687 37393 18686 37393 18686 37394 18687 37394 19652 37394 18686 37395 19652 37395 18688 37395 18688 37396 19652 37396 18689 37396 18688 37397 18689 37397 18690 37397 18690 37398 18689 37398 19650 37398 18690 37399 19650 37399 18616 37399 18616 37400 19650 37400 18691 37400 18616 37401 18691 37401 18617 37401 18617 37402 18691 37402 18692 37402 18617 37403 18692 37403 18618 37403 18618 37404 18692 37404 19647 37404 18618 37405 19647 37405 18693 37405 18693 37406 19647 37406 19646 37406 18693 37407 19646 37407 18694 37407 18694 37408 19646 37408 16663 37408 18694 37409 16663 37409 18429 37409 18695 37410 18696 37410 18713 37410 18713 37411 18696 37411 18712 37411 18696 37412 18697 37412 18712 37412 18712 37413 18697 37413 18824 37413 18712 37414 18824 37414 18711 37414 18824 37415 18823 37415 18711 37415 18711 37416 18823 37416 18822 37416 18711 37417 18822 37417 18698 37417 18822 37418 18821 37418 18698 37418 18698 37419 18821 37419 18820 37419 18698 37420 18820 37420 18700 37420 18820 37421 18699 37421 18700 37421 18700 37422 18699 37422 18819 37422 18700 37423 18819 37423 18707 37423 18701 37424 18702 37424 18816 37424 18816 37425 18702 37425 18707 37425 18816 37426 18707 37426 18818 37426 18818 37427 18707 37427 18819 37427 17400 37428 18703 37428 18716 37428 18716 37429 18703 37429 17398 37429 18716 37430 17398 37430 18704 37430 18704 37431 17398 37431 17397 37431 18704 37432 17397 37432 18705 37432 18705 37433 17397 37433 18706 37433 18705 37434 18706 37434 18702 37434 18702 37435 18706 37435 18708 37435 18702 37436 18708 37436 18707 37436 18707 37437 18708 37437 18709 37437 18707 37438 18709 37438 18700 37438 18700 37439 18709 37439 18710 37439 18700 37440 18710 37440 18698 37440 18698 37441 18710 37441 18773 37441 18698 37442 18773 37442 18711 37442 18711 37443 18773 37443 18772 37443 18711 37444 18772 37444 18712 37444 18712 37445 18772 37445 18771 37445 18712 37446 18771 37446 18713 37446 18713 37447 18771 37447 17402 37447 18713 37448 17402 37448 18714 37448 18714 37449 17402 37449 18715 37449 18714 37450 18715 37450 17436 37450 17436 37451 18715 37451 17400 37451 17436 37452 17400 37452 18716 37452 17433 37453 17347 37453 18717 37453 17433 37454 18717 37454 18718 37454 18718 37455 18717 37455 18830 37455 18718 37456 18830 37456 18719 37456 18719 37457 18830 37457 18831 37457 18719 37458 18831 37458 18720 37458 18831 37459 18721 37459 18720 37459 18720 37460 18721 37460 18722 37460 18720 37461 18722 37461 18732 37461 18722 37462 18723 37462 18732 37462 18732 37463 18723 37463 18724 37463 18732 37464 18724 37464 18725 37464 18724 37465 18827 37465 18725 37465 18725 37466 18827 37466 18726 37466 18725 37467 18726 37467 18734 37467 18734 37468 18726 37468 17425 37468 18734 37469 17425 37469 17424 37469 18727 37470 18728 37470 18719 37470 18719 37471 18728 37471 18718 37471 18718 37472 18728 37472 18729 37472 18718 37473 18729 37473 17433 37473 17433 37474 18729 37474 18730 37474 17433 37475 18730 37475 17431 37475 17431 37476 18730 37476 18731 37476 17431 37477 18731 37477 17430 37477 17430 37478 18731 37478 17373 37478 17430 37479 17373 37479 17428 37479 18719 37480 18720 37480 18727 37480 18727 37481 18720 37481 18732 37481 18727 37482 18732 37482 18789 37482 18789 37483 18732 37483 18725 37483 18789 37484 18725 37484 18733 37484 18733 37485 18725 37485 18734 37485 18733 37486 18734 37486 18792 37486 18792 37487 18734 37487 17424 37487 18792 37488 17424 37488 18735 37488 18735 37489 17424 37489 18736 37489 18735 37490 18736 37490 17378 37490 17378 37491 18736 37491 17427 37491 17378 37492 17427 37492 18737 37492 18737 37493 17427 37493 17428 37493 18737 37494 17428 37494 18738 37494 18738 37495 17428 37495 17373 37495 18756 37496 18739 37496 18835 37496 18756 37497 18835 37497 18757 37497 18757 37498 18835 37498 18837 37498 18757 37499 18837 37499 18740 37499 18740 37500 18837 37500 18741 37500 18740 37501 18741 37501 18742 37501 18741 37502 18839 37502 18742 37502 18742 37503 18839 37503 18743 37503 18742 37504 18743 37504 18745 37504 18743 37505 18744 37505 18745 37505 18745 37506 18744 37506 18833 37506 18745 37507 18833 37507 18746 37507 18833 37508 18832 37508 18746 37508 18746 37509 18832 37509 18747 37509 18746 37510 18747 37510 18748 37510 18748 37511 18747 37511 17418 37511 18748 37512 17418 37512 18749 37512 18759 37513 18746 37513 18814 37513 18814 37514 18746 37514 18748 37514 18814 37515 18748 37515 18815 37515 18815 37516 18748 37516 18749 37516 18815 37517 18749 37517 18750 37517 18750 37518 18749 37518 18752 37518 18750 37519 18752 37519 18751 37519 18751 37520 18752 37520 18753 37520 18751 37521 18753 37521 17357 37521 17357 37522 18753 37522 18754 37522 17357 37523 18754 37523 17358 37523 17358 37524 18754 37524 17422 37524 17358 37525 17422 37525 17360 37525 17360 37526 17422 37526 17423 37526 17360 37527 17423 37527 18755 37527 18755 37528 17423 37528 18756 37528 18755 37529 18756 37529 18809 37529 18809 37530 18756 37530 18757 37530 18809 37531 18757 37531 18810 37531 18810 37532 18757 37532 18740 37532 18810 37533 18740 37533 18758 37533 18758 37534 18740 37534 18742 37534 18758 37535 18742 37535 18812 37535 18812 37536 18742 37536 18745 37536 18812 37537 18745 37537 18759 37537 18759 37538 18745 37538 18746 37538 17403 37539 17868 37539 18760 37539 18760 37540 17868 37540 17869 37540 18760 37541 17869 37541 18761 37541 18761 37542 17869 37542 18763 37542 18761 37543 18763 37543 18762 37543 18762 37544 18763 37544 18764 37544 18762 37545 18764 37545 18767 37545 18767 37546 18764 37546 18766 37546 18767 37547 18766 37547 18765 37547 18765 37548 18766 37548 17872 37548 18765 37549 17872 37549 17411 37549 17411 37550 17872 37550 17412 37550 17411 37551 17401 37551 18765 37551 18765 37552 17401 37552 18770 37552 18765 37553 18770 37553 18767 37553 18767 37554 18770 37554 18768 37554 18767 37555 18768 37555 18762 37555 18762 37556 18768 37556 18769 37556 18762 37557 18769 37557 18761 37557 18761 37558 18769 37558 18774 37558 18761 37559 18774 37559 18760 37559 18760 37560 18774 37560 18775 37560 18760 37561 18775 37561 17403 37561 17403 37562 18775 37562 18776 37562 17401 37563 17402 37563 18770 37563 18770 37564 17402 37564 18771 37564 18770 37565 18771 37565 18768 37565 18768 37566 18771 37566 18772 37566 18768 37567 18772 37567 18769 37567 18769 37568 18772 37568 18773 37568 18769 37569 18773 37569 18774 37569 18774 37570 18773 37570 18710 37570 18774 37571 18710 37571 18775 37571 18775 37572 18710 37572 18709 37572 18775 37573 18709 37573 18776 37573 18776 37574 18709 37574 18708 37574 18777 37575 17795 37575 18779 37575 18779 37576 17795 37576 18778 37576 18779 37577 18778 37577 18785 37577 18785 37578 18778 37578 17798 37578 18785 37579 17798 37579 18780 37579 18780 37580 17798 37580 18781 37580 18780 37581 18781 37581 18784 37581 18784 37582 18781 37582 18783 37582 18784 37583 18783 37583 18782 37583 18782 37584 18783 37584 17801 37584 18782 37585 17801 37585 17387 37585 17387 37586 17801 37586 17804 37586 17387 37587 17371 37587 18782 37587 18782 37588 17371 37588 18786 37588 18782 37589 18786 37589 18784 37589 18784 37590 18786 37590 18787 37590 18784 37591 18787 37591 18780 37591 18780 37592 18787 37592 18788 37592 18780 37593 18788 37593 18785 37593 18785 37594 18788 37594 18790 37594 18785 37595 18790 37595 18779 37595 18779 37596 18790 37596 18791 37596 18779 37597 18791 37597 18777 37597 18777 37598 18791 37598 17379 37598 17371 37599 18730 37599 18786 37599 18786 37600 18730 37600 18729 37600 18786 37601 18729 37601 18787 37601 18787 37602 18729 37602 18728 37602 18787 37603 18728 37603 18788 37603 18788 37604 18728 37604 18727 37604 18788 37605 18727 37605 18790 37605 18790 37606 18727 37606 18789 37606 18790 37607 18789 37607 18791 37607 18791 37608 18789 37608 18733 37608 18791 37609 18733 37609 17379 37609 17379 37610 18733 37610 18792 37610 18808 37611 17789 37611 18793 37611 18793 37612 17789 37612 18794 37612 18793 37613 18794 37613 18796 37613 18796 37614 18794 37614 18795 37614 18796 37615 18795 37615 18805 37615 18805 37616 18795 37616 18797 37616 18805 37617 18797 37617 18798 37617 18798 37618 18797 37618 17775 37618 18798 37619 17775 37619 18803 37619 18803 37620 17775 37620 18799 37620 18803 37621 18799 37621 18800 37621 18800 37622 18799 37622 17778 37622 18800 37623 17778 37623 18801 37623 18801 37624 17778 37624 17366 37624 18801 37625 17361 37625 18800 37625 18800 37626 17361 37626 18802 37626 18800 37627 18802 37627 18803 37627 18803 37628 18802 37628 18811 37628 18803 37629 18811 37629 18798 37629 18798 37630 18811 37630 18804 37630 18798 37631 18804 37631 18805 37631 18805 37632 18804 37632 18806 37632 18805 37633 18806 37633 18796 37633 18796 37634 18806 37634 18807 37634 18796 37635 18807 37635 18793 37635 18793 37636 18807 37636 18813 37636 18793 37637 18813 37637 18808 37637 18808 37638 18813 37638 17354 37638 17361 37639 18755 37639 18802 37639 18802 37640 18755 37640 18809 37640 18802 37641 18809 37641 18811 37641 18811 37642 18809 37642 18810 37642 18811 37643 18810 37643 18804 37643 18804 37644 18810 37644 18758 37644 18804 37645 18758 37645 18806 37645 18806 37646 18758 37646 18812 37646 18806 37647 18812 37647 18807 37647 18807 37648 18812 37648 18759 37648 18807 37649 18759 37649 18813 37649 18813 37650 18759 37650 18814 37650 18813 37651 18814 37651 17354 37651 17354 37652 18814 37652 18815 37652 18817 37653 17349 37653 18701 37653 18701 37654 18816 37654 18817 37654 18817 37655 18816 37655 18818 37655 18817 37656 18818 37656 18481 37656 18481 37657 18818 37657 18237 37657 18818 37658 18819 37658 18237 37658 18237 37659 18819 37659 18699 37659 18237 37660 18699 37660 18383 37660 18699 37661 18820 37661 18383 37661 18383 37662 18820 37662 18821 37662 18383 37663 18821 37663 18385 37663 18385 37664 18821 37664 18822 37664 18385 37665 18822 37665 18387 37665 18822 37666 18823 37666 18387 37666 18387 37667 18823 37667 18824 37667 18387 37668 18824 37668 18825 37668 18695 37669 18378 37669 18696 37669 18696 37670 18378 37670 18825 37670 18696 37671 18825 37671 18697 37671 18697 37672 18825 37672 18824 37672 18401 37673 17425 37673 18826 37673 18826 37674 17425 37674 18726 37674 18826 37675 18726 37675 18391 37675 18391 37676 18726 37676 18827 37676 18827 37677 18724 37677 18391 37677 18391 37678 18724 37678 18723 37678 18391 37679 18723 37679 18392 37679 18723 37680 18722 37680 18392 37680 18392 37681 18722 37681 18721 37681 18392 37682 18721 37682 18828 37682 17347 37683 18423 37683 18717 37683 18717 37684 18423 37684 18829 37684 18717 37685 18829 37685 18830 37685 18830 37686 18829 37686 18828 37686 18830 37687 18828 37687 18831 37687 18831 37688 18828 37688 18721 37688 17340 37689 17418 37689 18410 37689 18410 37690 17418 37690 18747 37690 18410 37691 18747 37691 18407 37691 18407 37692 18747 37692 18832 37692 18832 37693 18833 37693 18407 37693 18407 37694 18833 37694 18744 37694 18407 37695 18744 37695 18509 37695 18744 37696 18743 37696 18509 37696 18509 37697 18743 37697 18839 37697 18509 37698 18839 37698 18838 37698 18739 37699 18834 37699 18835 37699 18835 37700 18834 37700 18836 37700 18835 37701 18836 37701 18837 37701 18837 37702 18836 37702 18838 37702 18837 37703 18838 37703 18741 37703 18741 37704 18838 37704 18839 37704 17337 37705 18848 37705 18840 37705 18840 37706 18848 37706 18850 37706 18840 37707 18850 37707 17858 37707 17858 37708 18850 37708 18852 37708 18852 37709 18841 37709 17858 37709 17858 37710 18841 37710 18853 37710 17858 37711 18853 37711 17856 37711 18853 37712 18842 37712 17856 37712 17856 37713 18842 37713 18855 37713 17856 37714 18855 37714 18847 37714 17328 37715 18844 37715 18843 37715 18843 37716 18844 37716 18845 37716 18843 37717 18845 37717 18846 37717 18846 37718 18845 37718 18847 37718 18846 37719 18847 37719 18857 37719 18857 37720 18847 37720 18855 37720 18848 37721 17320 37721 18849 37721 18848 37722 18849 37722 18850 37722 18850 37723 18849 37723 18851 37723 18850 37724 18851 37724 18852 37724 18852 37725 18851 37725 18841 37725 18841 37726 18851 37726 18854 37726 18841 37727 18854 37727 18853 37727 18853 37728 18854 37728 18842 37728 18842 37729 18854 37729 18856 37729 18842 37730 18856 37730 18855 37730 18855 37731 18856 37731 18857 37731 18857 37732 18856 37732 18858 37732 18857 37733 18858 37733 18846 37733 18846 37734 18858 37734 18863 37734 18846 37735 18863 37735 18843 37735 18843 37736 18863 37736 18859 37736 18843 37737 18859 37737 17328 37737 17320 37738 18475 37738 18849 37738 18849 37739 18475 37739 18486 37739 18849 37740 18486 37740 18851 37740 18851 37741 18486 37741 18860 37741 18851 37742 18860 37742 18854 37742 18854 37743 18860 37743 18861 37743 18854 37744 18861 37744 18856 37744 18856 37745 18861 37745 18485 37745 18856 37746 18485 37746 18858 37746 18858 37747 18485 37747 18862 37747 18858 37748 18862 37748 18863 37748 18863 37749 18862 37749 18864 37749 18863 37750 18864 37750 18859 37750 18859 37751 18864 37751 18484 37751 17302 37752 18865 37752 18866 37752 18866 37753 18865 37753 17851 37753 18866 37754 17851 37754 18875 37754 18875 37755 17851 37755 17849 37755 18875 37756 17849 37756 18874 37756 18874 37757 17849 37757 18867 37757 18874 37758 18867 37758 18868 37758 18868 37759 18867 37759 18869 37759 18868 37760 18869 37760 18870 37760 18870 37761 18869 37761 17846 37761 18870 37762 17846 37762 17313 37762 17313 37763 17846 37763 17844 37763 17313 37764 18871 37764 18870 37764 18870 37765 18871 37765 18872 37765 18870 37766 18872 37766 18868 37766 18868 37767 18872 37767 18877 37767 18868 37768 18877 37768 18874 37768 18874 37769 18877 37769 18873 37769 18874 37770 18873 37770 18875 37770 18875 37771 18873 37771 18880 37771 18875 37772 18880 37772 18866 37772 18866 37773 18880 37773 18876 37773 18866 37774 18876 37774 17302 37774 17302 37775 18876 37775 17304 37775 18871 37776 17301 37776 18872 37776 18872 37777 17301 37777 18397 37777 18872 37778 18397 37778 18877 37778 18877 37779 18397 37779 18878 37779 18877 37780 18878 37780 18873 37780 18873 37781 18878 37781 18879 37781 18873 37782 18879 37782 18880 37782 18880 37783 18879 37783 18400 37783 18880 37784 18400 37784 18876 37784 18876 37785 18400 37785 18398 37785 18876 37786 18398 37786 17304 37786 17304 37787 18398 37787 18394 37787 18881 37788 17294 37788 18882 37788 18882 37789 17294 37789 18883 37789 18882 37790 18883 37790 18892 37790 18892 37791 18883 37791 17824 37791 18892 37792 17824 37792 18891 37792 18891 37793 17824 37793 17826 37793 18891 37794 17826 37794 18889 37794 18889 37795 17826 37795 17827 37795 18889 37796 17827 37796 18884 37796 18884 37797 17827 37797 18885 37797 18884 37798 18885 37798 18888 37798 18888 37799 18885 37799 18886 37799 18887 37800 18905 37800 18888 37800 18888 37801 18905 37801 18884 37801 18905 37802 18906 37802 18884 37802 18884 37803 18906 37803 18904 37803 18884 37804 18904 37804 18889 37804 18904 37805 18903 37805 18889 37805 18889 37806 18903 37806 18890 37806 18889 37807 18890 37807 18891 37807 18890 37808 18901 37808 18891 37808 18891 37809 18901 37809 18900 37809 18891 37810 18900 37810 18892 37810 18900 37811 18899 37811 18892 37811 18892 37812 18899 37812 18897 37812 18892 37813 18897 37813 18882 37813 17278 37814 18881 37814 18895 37814 18895 37815 18881 37815 18882 37815 18895 37816 18882 37816 18896 37816 18896 37817 18882 37817 18897 37817 18893 37818 18894 37818 17278 37818 17278 37819 18895 37819 18893 37819 18893 37820 18895 37820 18896 37820 18893 37821 18896 37821 18898 37821 18896 37822 18897 37822 18898 37822 18898 37823 18897 37823 18899 37823 18898 37824 18899 37824 18376 37824 18376 37825 18899 37825 18900 37825 18376 37826 18900 37826 18902 37826 18900 37827 18901 37827 18902 37827 18902 37828 18901 37828 18890 37828 18902 37829 18890 37829 18501 37829 18890 37830 18903 37830 18501 37830 18501 37831 18903 37831 18904 37831 18501 37832 18904 37832 18373 37832 18887 37833 18609 37833 18905 37833 18905 37834 18609 37834 18373 37834 18905 37835 18373 37835 18906 37835 18906 37836 18373 37836 18904 37836 17270 37837 17269 37837 18916 37837 18916 37838 17269 37838 18907 37838 18916 37839 18907 37839 18915 37839 18915 37840 18907 37840 18908 37840 18915 37841 18908 37841 18909 37841 18909 37842 18908 37842 17815 37842 18909 37843 17815 37843 18913 37843 18913 37844 17815 37844 18910 37844 18913 37845 18910 37845 18911 37845 18911 37846 18910 37846 17816 37846 18911 37847 17816 37847 17274 37847 17274 37848 17816 37848 17275 37848 17274 37849 18912 37849 18911 37849 18911 37850 18912 37850 18919 37850 18911 37851 18919 37851 18913 37851 18913 37852 18919 37852 18914 37852 18913 37853 18914 37853 18909 37853 18909 37854 18914 37854 18920 37854 18909 37855 18920 37855 18915 37855 18915 37856 18920 37856 18917 37856 18915 37857 18917 37857 18916 37857 18916 37858 18917 37858 18921 37858 18916 37859 18921 37859 17270 37859 17270 37860 18921 37860 18918 37860 18912 37861 17256 37861 18919 37861 18919 37862 17256 37862 18367 37862 18919 37863 18367 37863 18914 37863 18914 37864 18367 37864 18361 37864 18914 37865 18361 37865 18920 37865 18920 37866 18361 37866 18409 37866 18920 37867 18409 37867 18917 37867 18917 37868 18409 37868 18922 37868 18917 37869 18922 37869 18921 37869 18921 37870 18922 37870 18923 37870 18921 37871 18923 37871 18918 37871 18918 37872 18923 37872 18924 37872 18946 37873 19063 37873 18925 37873 18946 37874 18925 37874 18927 37874 18927 37875 18925 37875 18926 37875 18927 37876 18926 37876 18928 37876 18928 37877 18926 37877 18929 37877 18928 37878 18929 37878 18931 37878 18929 37879 18930 37879 18931 37879 18931 37880 18930 37880 18932 37880 18931 37881 18932 37881 18933 37881 18932 37882 19060 37882 18933 37882 18933 37883 19060 37883 18934 37883 18933 37884 18934 37884 18935 37884 18934 37885 19058 37885 18935 37885 18935 37886 19058 37886 18937 37886 18935 37887 18937 37887 18936 37887 18936 37888 18937 37888 17242 37888 18936 37889 17242 37889 18939 37889 19007 37890 18933 37890 18938 37890 18938 37891 18933 37891 18935 37891 18938 37892 18935 37892 19004 37892 19004 37893 18935 37893 18936 37893 19004 37894 18936 37894 19001 37894 19001 37895 18936 37895 18939 37895 19001 37896 18939 37896 18940 37896 18940 37897 18939 37897 17244 37897 18940 37898 17244 37898 17213 37898 17213 37899 17244 37899 18941 37899 17213 37900 18941 37900 18943 37900 18943 37901 18941 37901 18942 37901 18943 37902 18942 37902 18944 37902 18944 37903 18942 37903 17250 37903 18944 37904 17250 37904 18945 37904 18945 37905 17250 37905 17251 37905 18945 37906 17251 37906 19013 37906 19013 37907 17251 37907 18946 37907 19013 37908 18946 37908 19014 37908 19014 37909 18946 37909 18927 37909 19014 37910 18927 37910 19011 37910 19011 37911 18927 37911 18928 37911 19011 37912 18928 37912 19010 37912 19010 37913 18928 37913 18931 37913 19010 37914 18931 37914 19007 37914 19007 37915 18931 37915 18933 37915 17241 37916 18947 37916 18948 37916 18948 37917 18947 37917 19065 37917 18948 37918 19065 37918 18949 37918 18949 37919 19065 37919 18950 37919 18949 37920 18950 37920 18960 37920 18960 37921 18950 37921 18951 37921 18960 37922 18951 37922 18958 37922 18958 37923 18951 37923 19068 37923 18958 37924 19068 37924 18956 37924 18956 37925 19068 37925 19070 37925 18956 37926 19070 37926 17236 37926 17236 37927 19070 37927 18952 37927 17184 37928 18953 37928 18954 37928 18954 37929 18953 37929 18955 37929 18954 37930 18955 37930 17238 37930 17238 37931 18955 37931 17187 37931 17238 37932 17187 37932 17237 37932 17237 37933 17187 37933 17189 37933 17237 37934 17189 37934 17236 37934 17236 37935 17189 37935 17191 37935 17236 37936 17191 37936 18956 37936 18956 37937 17191 37937 18957 37937 18956 37938 18957 37938 18958 37938 18958 37939 18957 37939 18959 37939 18958 37940 18959 37940 18960 37940 18960 37941 18959 37941 18961 37941 18960 37942 18961 37942 18949 37942 18949 37943 18961 37943 18962 37943 18949 37944 18962 37944 18948 37944 18948 37945 18962 37945 18963 37945 18948 37946 18963 37946 17241 37946 17241 37947 18963 37947 18964 37947 17241 37948 18964 37948 18965 37948 18965 37949 18964 37949 18966 37949 18965 37950 18966 37950 18967 37950 18967 37951 18966 37951 17184 37951 18967 37952 17184 37952 18954 37952 18981 37953 17235 37953 18968 37953 18968 37954 17235 37954 19072 37954 18968 37955 19072 37955 18969 37955 18969 37956 19072 37956 18970 37956 18969 37957 18970 37957 18982 37957 18982 37958 18970 37958 18971 37958 18982 37959 18971 37959 18983 37959 18983 37960 18971 37960 19074 37960 18983 37961 19074 37961 18972 37961 18972 37962 19074 37962 18973 37962 18972 37963 18973 37963 18974 37963 18974 37964 18973 37964 19075 37964 18974 37965 19075 37965 18975 37965 18975 37966 19075 37966 17230 37966 18985 37967 18974 37967 17162 37967 17162 37968 18974 37968 18975 37968 17162 37969 18975 37969 17164 37969 17164 37970 18975 37970 18976 37970 17164 37971 18976 37971 17166 37971 17166 37972 18976 37972 18977 37972 17166 37973 18977 37973 17167 37973 17167 37974 18977 37974 17232 37974 17167 37975 17232 37975 17168 37975 17168 37976 17232 37976 18978 37976 17168 37977 18978 37977 17169 37977 17169 37978 18978 37978 17233 37978 17169 37979 17233 37979 18979 37979 18979 37980 17233 37980 18981 37980 18979 37981 18981 37981 18980 37981 18980 37982 18981 37982 18968 37982 18980 37983 18968 37983 19055 37983 19055 37984 18968 37984 18969 37984 19055 37985 18969 37985 19056 37985 19056 37986 18969 37986 18982 37986 19056 37987 18982 37987 18984 37987 18984 37988 18982 37988 18983 37988 18984 37989 18983 37989 19057 37989 19057 37990 18983 37990 18972 37990 19057 37991 18972 37991 18985 37991 18985 37992 18972 37992 18974 37992 18999 37993 18030 37993 19000 37993 19000 37994 18030 37994 18032 37994 19000 37995 18032 37995 18998 37995 18998 37996 18032 37996 18033 37996 18998 37997 18033 37997 18996 37997 18996 37998 18033 37998 18035 37998 18996 37999 18035 37999 18986 37999 18986 38000 18035 38000 18987 38000 18986 38001 18987 38001 18988 38001 18988 38002 18987 38002 18989 38002 18988 38003 18989 38003 18991 38003 18991 38004 18989 38004 18990 38004 17210 38005 18992 38005 18991 38005 18991 38006 18992 38006 18988 38006 18992 38007 18993 38007 18988 38007 18988 38008 18993 38008 19012 38008 18988 38009 19012 38009 18986 38009 19012 38010 18994 38010 18986 38010 18986 38011 18994 38011 18995 38011 18986 38012 18995 38012 18996 38012 18995 38013 19009 38013 18996 38013 18996 38014 19009 38014 19008 38014 18996 38015 19008 38015 18998 38015 19008 38016 18997 38016 18998 38016 18998 38017 18997 38017 19006 38017 18998 38018 19006 38018 19000 38018 19002 38019 18999 38019 19003 38019 19003 38020 18999 38020 19000 38020 19003 38021 19000 38021 19005 38021 19005 38022 19000 38022 19006 38022 19004 38023 19001 38023 19002 38023 19002 38024 19003 38024 19004 38024 19004 38025 19003 38025 19005 38025 19004 38026 19005 38026 18938 38026 19005 38027 19006 38027 18938 38027 18938 38028 19006 38028 18997 38028 18938 38029 18997 38029 19007 38029 19007 38030 18997 38030 19008 38030 19007 38031 19008 38031 19010 38031 19008 38032 19009 38032 19010 38032 19010 38033 19009 38033 18995 38033 19010 38034 18995 38034 19011 38034 18995 38035 18994 38035 19011 38035 19011 38036 18994 38036 19012 38036 19011 38037 19012 38037 19014 38037 17210 38038 19013 38038 18992 38038 18992 38039 19013 38039 19014 38039 18992 38040 19014 38040 18993 38040 18993 38041 19014 38041 19012 38041 19016 38042 18045 38042 19027 38042 19027 38043 19015 38043 19016 38043 19016 38044 19015 38044 19029 38044 19016 38045 19029 38045 19018 38045 19029 38046 19017 38046 19018 38046 19018 38047 19017 38047 19019 38047 19018 38048 19019 38048 18042 38048 19019 38049 19030 38049 18042 38049 18042 38050 19030 38050 19020 38050 18042 38051 19020 38051 19021 38051 19021 38052 19020 38052 19022 38052 19021 38053 19022 38053 19024 38053 19022 38054 19023 38054 19024 38054 19024 38055 19023 38055 19033 38055 19024 38056 19033 38056 19026 38056 17208 38057 17209 38057 19035 38057 19035 38058 17209 38058 19026 38058 19035 38059 19026 38059 19025 38059 19025 38060 19026 38060 19033 38060 19027 38061 19028 38061 19015 38061 19015 38062 19028 38062 19036 38062 19015 38063 19036 38063 19029 38063 19029 38064 19036 38064 19017 38064 19017 38065 19036 38065 19031 38065 19017 38066 19031 38066 19019 38066 19019 38067 19031 38067 19030 38067 19030 38068 19031 38068 19032 38068 19030 38069 19032 38069 19020 38069 19020 38070 19032 38070 19022 38070 19022 38071 19032 38071 19037 38071 19022 38072 19037 38072 19023 38072 19023 38073 19037 38073 19033 38073 19033 38074 19037 38074 19034 38074 19033 38075 19034 38075 19025 38075 19025 38076 19034 38076 19035 38076 19035 38077 19034 38077 17190 38077 19035 38078 17190 38078 17208 38078 19028 38079 18964 38079 19036 38079 19036 38080 18964 38080 18963 38080 19036 38081 18963 38081 19031 38081 19031 38082 18963 38082 18962 38082 19031 38083 18962 38083 19032 38083 19032 38084 18962 38084 18961 38084 19032 38085 18961 38085 19037 38085 19037 38086 18961 38086 18959 38086 19037 38087 18959 38087 19034 38087 19034 38088 18959 38088 18957 38088 19034 38089 18957 38089 17190 38089 17190 38090 18957 38090 17191 38090 19053 38091 19038 38091 19051 38091 19051 38092 19038 38092 19039 38092 19051 38093 19039 38093 19048 38093 19048 38094 19039 38094 19041 38094 19048 38095 19041 38095 19040 38095 19040 38096 19041 38096 18054 38096 19040 38097 18054 38097 19042 38097 19042 38098 18054 38098 19043 38098 19042 38099 19043 38099 19046 38099 19046 38100 19043 38100 18055 38100 19046 38101 18055 38101 19044 38101 19044 38102 18055 38102 18056 38102 19044 38103 18056 38103 17177 38103 17177 38104 18056 38104 17178 38104 17177 38105 17170 38105 19044 38105 19044 38106 17170 38106 19045 38106 19044 38107 19045 38107 19046 38107 19046 38108 19045 38108 19054 38108 19046 38109 19054 38109 19042 38109 19042 38110 19054 38110 19047 38110 19042 38111 19047 38111 19040 38111 19040 38112 19047 38112 19049 38112 19040 38113 19049 38113 19048 38113 19048 38114 19049 38114 19050 38114 19048 38115 19050 38115 19051 38115 19051 38116 19050 38116 19052 38116 19051 38117 19052 38117 19053 38117 19053 38118 19052 38118 17171 38118 17170 38119 18979 38119 19045 38119 19045 38120 18979 38120 18980 38120 19045 38121 18980 38121 19054 38121 19054 38122 18980 38122 19055 38122 19054 38123 19055 38123 19047 38123 19047 38124 19055 38124 19056 38124 19047 38125 19056 38125 19049 38125 19049 38126 19056 38126 18984 38126 19049 38127 18984 38127 19050 38127 19050 38128 18984 38128 19057 38128 19050 38129 19057 38129 19052 38129 19052 38130 19057 38130 18985 38130 19052 38131 18985 38131 17171 38131 17171 38132 18985 38132 17162 38132 18642 38133 17242 38133 18534 38133 18534 38134 17242 38134 18937 38134 18534 38135 18937 38135 19059 38135 19059 38136 18937 38136 19058 38136 19058 38137 18934 38137 19059 38137 19059 38138 18934 38138 19060 38138 19059 38139 19060 38139 19061 38139 19060 38140 18932 38140 19061 38140 19061 38141 18932 38141 18930 38141 19061 38142 18930 38142 19062 38142 19063 38143 18535 38143 18925 38143 18925 38144 18535 38144 19064 38144 18925 38145 19064 38145 18926 38145 18926 38146 19064 38146 19062 38146 18926 38147 19062 38147 18929 38147 18929 38148 19062 38148 18930 38148 18947 38149 18320 38149 19065 38149 19065 38150 18320 38150 19066 38150 19065 38151 19066 38151 18950 38151 18950 38152 19066 38152 19067 38152 18950 38153 19067 38153 18951 38153 18951 38154 19067 38154 18344 38154 18951 38155 18344 38155 19068 38155 19068 38156 18344 38156 19069 38156 19068 38157 19069 38157 19070 38157 19070 38158 19069 38158 19071 38158 19070 38159 19071 38159 18952 38159 18952 38160 19071 38160 18348 38160 17235 38161 18355 38161 19072 38161 19072 38162 18355 38162 18360 38162 19072 38163 18360 38163 18970 38163 18970 38164 18360 38164 19073 38164 18970 38165 19073 38165 18971 38165 18971 38166 19073 38166 18358 38166 18971 38167 18358 38167 19074 38167 19074 38168 18358 38168 18357 38168 19074 38169 18357 38169 18973 38169 18973 38170 18357 38170 19076 38170 18973 38171 19076 38171 19075 38171 19075 38172 19076 38172 19077 38172 19075 38173 19077 38173 17230 38173 17230 38174 19077 38174 17142 38174 17977 38175 17136 38175 17134 38175 17134 38176 19087 38176 17977 38176 17977 38177 19087 38177 19088 38177 17977 38178 19088 38178 17979 38178 19088 38179 19078 38179 17979 38179 17979 38180 19078 38180 19079 38180 17979 38181 19079 38181 19080 38181 19079 38182 19090 38182 19080 38182 19080 38183 19090 38183 19081 38183 19080 38184 19081 38184 17980 38184 17980 38185 19081 38185 19082 38185 17980 38186 19082 38186 19084 38186 19082 38187 19083 38187 19084 38187 19084 38188 19083 38188 19092 38188 19084 38189 19092 38189 19085 38189 17128 38190 17982 38190 19093 38190 19093 38191 17982 38191 19085 38191 19093 38192 19085 38192 19086 38192 19086 38193 19085 38193 19092 38193 17134 38194 17127 38194 19087 38194 19087 38195 17127 38195 19095 38195 19087 38196 19095 38196 19088 38196 19088 38197 19095 38197 19078 38197 19078 38198 19095 38198 19089 38198 19078 38199 19089 38199 19079 38199 19079 38200 19089 38200 19090 38200 19090 38201 19089 38201 19099 38201 19090 38202 19099 38202 19081 38202 19081 38203 19099 38203 19082 38203 19082 38204 19099 38204 19091 38204 19082 38205 19091 38205 19083 38205 19083 38206 19091 38206 19092 38206 19092 38207 19091 38207 19094 38207 19092 38208 19094 38208 19086 38208 19086 38209 19094 38209 19093 38209 19093 38210 19094 38210 19101 38210 19093 38211 19101 38211 17128 38211 17127 38212 18339 38212 19095 38212 19095 38213 18339 38213 19096 38213 19095 38214 19096 38214 19089 38214 19089 38215 19096 38215 19097 38215 19089 38216 19097 38216 19099 38216 19099 38217 19097 38217 19098 38217 19099 38218 19098 38218 19091 38218 19091 38219 19098 38219 19100 38219 19091 38220 19100 38220 19094 38220 19094 38221 19100 38221 18341 38221 19094 38222 18341 38222 19101 38222 19101 38223 18341 38223 18331 38223 17122 38224 19102 38224 19103 38224 19103 38225 19102 38225 19104 38225 19103 38226 19104 38226 19112 38226 19112 38227 19104 38227 17989 38227 19112 38228 17989 38228 19105 38228 19105 38229 17989 38229 17990 38229 19105 38230 17990 38230 19111 38230 19111 38231 17990 38231 19106 38231 19111 38232 19106 38232 19109 38232 19109 38233 19106 38233 19107 38233 19109 38234 19107 38234 19108 38234 19108 38235 19107 38235 17117 38235 19108 38236 19110 38236 19109 38236 19109 38237 19110 38237 19116 38237 19109 38238 19116 38238 19111 38238 19111 38239 19116 38239 19118 38239 19111 38240 19118 38240 19105 38240 19105 38241 19118 38241 19119 38241 19105 38242 19119 38242 19112 38242 19112 38243 19119 38243 19120 38243 19112 38244 19120 38244 19103 38244 19103 38245 19120 38245 19113 38245 19103 38246 19113 38246 17122 38246 17122 38247 19113 38247 19114 38247 19110 38248 19115 38248 19116 38248 19116 38249 19115 38249 19117 38249 19116 38250 19117 38250 19118 38250 19118 38251 19117 38251 18326 38251 19118 38252 18326 38252 19119 38252 19119 38253 18326 38253 18325 38253 19119 38254 18325 38254 19120 38254 19120 38255 18325 38255 18319 38255 19120 38256 18319 38256 19113 38256 19113 38257 18319 38257 18350 38257 19113 38258 18350 38258 19114 38258 19114 38259 18350 38259 19121 38259 17102 38260 17103 38260 19122 38260 19122 38261 17103 38261 18005 38261 19122 38262 18005 38262 19123 38262 19123 38263 18005 38263 18006 38263 19123 38264 18006 38264 19124 38264 19124 38265 18006 38265 18009 38265 19124 38266 18009 38266 19125 38266 19125 38267 18009 38267 18010 38267 19125 38268 18010 38268 19126 38268 19126 38269 18010 38269 18011 38269 19126 38270 18011 38270 17091 38270 17091 38271 18011 38271 18014 38271 17091 38272 19127 38272 19126 38272 19126 38273 19127 38273 19128 38273 19126 38274 19128 38274 19125 38274 19125 38275 19128 38275 19134 38275 19125 38276 19134 38276 19124 38276 19124 38277 19134 38277 19129 38277 19124 38278 19129 38278 19123 38278 19123 38279 19129 38279 19130 38279 19123 38280 19130 38280 19122 38280 19122 38281 19130 38281 19131 38281 19122 38282 19131 38282 17102 38282 17102 38283 19131 38283 19132 38283 19127 38284 18343 38284 19128 38284 19128 38285 18343 38285 19133 38285 19128 38286 19133 38286 19134 38286 19134 38287 19133 38287 19135 38287 19134 38288 19135 38288 19129 38288 19129 38289 19135 38289 18316 38289 19129 38290 18316 38290 19130 38290 19130 38291 18316 38291 18313 38291 19130 38292 18313 38292 19131 38292 19131 38293 18313 38293 18314 38293 19131 38294 18314 38294 19132 38294 19132 38295 18314 38295 17079 38295 19146 38296 17077 38296 19145 38296 19145 38297 17077 38297 18018 38297 19145 38298 18018 38298 19143 38298 19143 38299 18018 38299 18019 38299 19143 38300 18019 38300 19136 38300 19136 38301 18019 38301 19137 38301 19136 38302 19137 38302 19142 38302 19142 38303 19137 38303 19138 38303 19142 38304 19138 38304 19141 38304 19141 38305 19138 38305 19139 38305 19141 38306 19139 38306 17070 38306 17070 38307 19139 38307 18022 38307 17070 38308 19140 38308 19141 38308 19141 38309 19140 38309 19150 38309 19141 38310 19150 38310 19142 38310 19142 38311 19150 38311 19152 38311 19142 38312 19152 38312 19136 38312 19136 38313 19152 38313 19153 38313 19136 38314 19153 38314 19143 38314 19143 38315 19153 38315 19144 38315 19143 38316 19144 38316 19145 38316 19145 38317 19144 38317 19147 38317 19145 38318 19147 38318 19146 38318 19146 38319 19147 38319 19148 38319 19140 38320 19149 38320 19150 38320 19150 38321 19149 38321 19151 38321 19150 38322 19151 38322 19152 38322 19152 38323 19151 38323 18305 38323 19152 38324 18305 38324 19153 38324 19153 38325 18305 38325 19154 38325 19153 38326 19154 38326 19144 38326 19144 38327 19154 38327 18304 38327 19144 38328 18304 38328 19147 38328 19147 38329 18304 38329 19155 38329 19147 38330 19155 38330 19148 38330 19148 38331 19155 38331 18301 38331 19168 38332 19156 38332 19157 38332 19157 38333 19156 38333 19260 38333 19157 38334 19260 38334 19169 38334 19169 38335 19260 38335 19261 38335 19169 38336 19261 38336 19170 38336 19170 38337 19261 38337 19264 38337 19170 38338 19264 38338 19158 38338 19158 38339 19264 38339 19265 38339 19158 38340 19265 38340 19159 38340 19159 38341 19265 38341 19160 38341 19159 38342 19160 38342 19172 38342 19172 38343 19160 38343 19161 38343 19162 38344 19163 38344 17021 38344 17021 38345 19163 38345 19164 38345 17021 38346 19164 38346 17024 38346 17024 38347 19164 38347 19165 38347 17024 38348 19165 38348 17025 38348 17025 38349 19165 38349 19166 38349 17025 38350 19166 38350 19167 38350 19167 38351 19166 38351 17058 38351 19167 38352 17058 38352 19212 38352 19212 38353 17058 38353 19168 38353 19212 38354 19168 38354 19214 38354 19214 38355 19168 38355 19157 38355 19214 38356 19157 38356 19215 38356 19215 38357 19157 38357 19169 38357 19215 38358 19169 38358 19216 38358 19216 38359 19169 38359 19170 38359 19216 38360 19170 38360 19171 38360 19171 38361 19170 38361 19158 38361 19171 38362 19158 38362 19218 38362 19218 38363 19158 38363 19159 38363 19218 38364 19159 38364 17018 38364 17018 38365 19159 38365 19172 38365 17018 38366 19172 38366 17019 38366 17019 38367 19172 38367 19173 38367 17019 38368 19173 38368 19162 38368 19162 38369 19173 38369 19163 38369 17052 38370 19175 38370 19174 38370 19174 38371 19175 38371 19267 38371 19174 38372 19267 38372 18655 38372 18655 38373 19267 38373 19268 38373 18655 38374 19268 38374 19176 38374 19176 38375 19268 38375 19270 38375 19176 38376 19270 38376 19177 38376 19177 38377 19270 38377 19179 38377 19177 38378 19179 38378 19178 38378 19178 38379 19179 38379 19180 38379 19178 38380 19180 38380 18658 38380 18658 38381 19180 38381 17047 38381 16964 38382 19279 38382 19193 38382 19193 38383 19279 38383 19181 38383 19279 38384 19280 38384 19181 38384 19181 38385 19280 38385 19277 38385 19181 38386 19277 38386 19183 38386 19277 38387 19182 38387 19183 38387 19183 38388 19182 38388 19184 38388 19183 38389 19184 38389 19192 38389 19184 38390 19275 38390 19192 38390 19192 38391 19275 38391 19185 38391 19192 38392 19185 38392 19187 38392 19185 38393 19186 38393 19187 38393 19187 38394 19186 38394 19273 38394 19187 38395 19273 38395 19188 38395 17041 38396 19189 38396 19190 38396 19190 38397 19189 38397 19188 38397 19190 38398 19188 38398 19191 38398 19191 38399 19188 38399 19273 38399 19192 38400 19200 38400 19183 38400 19183 38401 19200 38401 19254 38401 19183 38402 19254 38402 19181 38402 19181 38403 19254 38403 19252 38403 19181 38404 19252 38404 19193 38404 19193 38405 19252 38405 19251 38405 19193 38406 19251 38406 17046 38406 17046 38407 19251 38407 16983 38407 17046 38408 16983 38408 17045 38408 17045 38409 16983 38409 16981 38409 17045 38410 16981 38410 17043 38410 17043 38411 16981 38411 19195 38411 17043 38412 19195 38412 19194 38412 19194 38413 19195 38413 19196 38413 19194 38414 19196 38414 19197 38414 19197 38415 19196 38415 16978 38415 19197 38416 16978 38416 19189 38416 19189 38417 16978 38417 19198 38417 19189 38418 19198 38418 19188 38418 19188 38419 19198 38419 19259 38419 19188 38420 19259 38420 19187 38420 19187 38421 19259 38421 19199 38421 19187 38422 19199 38422 19192 38422 19192 38423 19199 38423 19257 38423 19192 38424 19257 38424 19200 38424 17040 38425 17941 38425 19201 38425 19201 38426 17941 38426 19202 38426 19201 38427 19202 38427 19203 38427 19203 38428 19202 38428 17942 38428 19203 38429 17942 38429 19208 38429 19208 38430 17942 38430 17944 38430 19208 38431 17944 38431 19207 38431 19207 38432 17944 38432 17946 38432 19207 38433 17946 38433 19204 38433 19204 38434 17946 38434 19205 38434 19204 38435 19205 38435 17033 38435 17033 38436 19205 38436 17034 38436 17033 38437 19211 38437 19204 38437 19204 38438 19211 38438 19206 38438 19204 38439 19206 38439 19207 38439 19207 38440 19206 38440 19213 38440 19207 38441 19213 38441 19208 38441 19208 38442 19213 38442 19209 38442 19208 38443 19209 38443 19203 38443 19203 38444 19209 38444 19210 38444 19203 38445 19210 38445 19201 38445 19201 38446 19210 38446 19217 38446 19201 38447 19217 38447 17040 38447 17040 38448 19217 38448 17026 38448 19211 38449 19212 38449 19206 38449 19206 38450 19212 38450 19214 38450 19206 38451 19214 38451 19213 38451 19213 38452 19214 38452 19215 38452 19213 38453 19215 38453 19209 38453 19209 38454 19215 38454 19216 38454 19209 38455 19216 38455 19210 38455 19210 38456 19216 38456 19171 38456 19210 38457 19171 38457 19217 38457 19217 38458 19171 38458 19218 38458 19217 38459 19218 38459 17026 38459 17026 38460 19218 38460 17018 38460 19230 38461 17955 38461 19219 38461 19219 38462 17955 38462 19220 38462 19219 38463 19220 38463 19221 38463 19221 38464 19220 38464 17957 38464 19221 38465 17957 38465 19222 38465 19222 38466 17957 38466 17958 38466 19222 38467 17958 38467 19227 38467 19227 38468 17958 38468 17960 38468 19227 38469 17960 38469 19223 38469 19223 38470 17960 38470 19224 38470 19223 38471 19224 38471 19226 38471 19226 38472 19224 38472 19225 38472 19226 38473 19231 38473 19223 38473 19223 38474 19231 38474 19232 38474 19223 38475 19232 38475 19227 38475 19227 38476 19232 38476 19228 38476 19227 38477 19228 38477 19222 38477 19222 38478 19228 38478 19235 38478 19222 38479 19235 38479 19221 38479 19221 38480 19235 38480 19229 38480 19221 38481 19229 38481 19219 38481 19219 38482 19229 38482 19237 38482 19219 38483 19237 38483 19230 38483 19230 38484 19237 38484 19238 38484 19231 38485 18653 38485 19232 38485 19232 38486 18653 38486 19233 38486 19232 38487 19233 38487 19228 38487 19228 38488 19233 38488 19234 38488 19228 38489 19234 38489 19235 38489 19235 38490 19234 38490 19236 38490 19235 38491 19236 38491 19229 38491 19229 38492 19236 38492 18656 38492 19229 38493 18656 38493 19237 38493 19237 38494 18656 38494 18657 38494 19237 38495 18657 38495 19238 38495 19238 38496 18657 38496 19239 38496 16985 38497 16999 38497 19240 38497 19240 38498 16999 38498 19241 38498 19240 38499 19241 38499 19250 38499 19250 38500 19241 38500 17968 38500 19250 38501 17968 38501 19242 38501 19242 38502 17968 38502 19243 38502 19242 38503 19243 38503 19248 38503 19248 38504 19243 38504 17969 38504 19248 38505 17969 38505 19244 38505 19244 38506 17969 38506 17970 38506 19244 38507 17970 38507 19245 38507 19245 38508 17970 38508 19246 38508 19245 38509 19246 38509 16992 38509 16992 38510 19246 38510 16993 38510 16992 38511 16984 38511 19245 38511 19245 38512 16984 38512 19247 38512 19245 38513 19247 38513 19244 38513 19244 38514 19247 38514 19253 38514 19244 38515 19253 38515 19248 38515 19248 38516 19253 38516 19255 38516 19248 38517 19255 38517 19242 38517 19242 38518 19255 38518 19256 38518 19242 38519 19256 38519 19250 38519 19250 38520 19256 38520 19249 38520 19250 38521 19249 38521 19240 38521 19240 38522 19249 38522 19258 38522 19240 38523 19258 38523 16985 38523 16985 38524 19258 38524 16986 38524 16984 38525 19251 38525 19247 38525 19247 38526 19251 38526 19252 38526 19247 38527 19252 38527 19253 38527 19253 38528 19252 38528 19254 38528 19253 38529 19254 38529 19255 38529 19255 38530 19254 38530 19200 38530 19255 38531 19200 38531 19256 38531 19256 38532 19200 38532 19257 38532 19256 38533 19257 38533 19249 38533 19249 38534 19257 38534 19199 38534 19249 38535 19199 38535 19258 38535 19258 38536 19199 38536 19259 38536 19258 38537 19259 38537 16986 38537 16986 38538 19259 38538 19198 38538 19156 38539 18248 38539 19260 38539 19260 38540 18248 38540 19262 38540 19260 38541 19262 38541 19261 38541 19261 38542 19262 38542 19263 38542 19261 38543 19263 38543 19264 38543 19264 38544 19263 38544 18382 38544 19264 38545 18382 38545 19265 38545 19265 38546 18382 38546 18257 38546 19265 38547 18257 38547 19160 38547 19160 38548 18257 38548 19266 38548 19160 38549 19266 38549 19161 38549 19161 38550 19266 38550 18255 38550 19175 38551 18277 38551 19267 38551 19267 38552 18277 38552 18278 38552 19267 38553 18278 38553 19268 38553 19268 38554 18278 38554 18279 38554 19268 38555 18279 38555 19270 38555 19270 38556 18279 38556 19269 38556 19270 38557 19269 38557 19179 38557 19179 38558 19269 38558 18261 38558 19179 38559 18261 38559 19180 38559 19180 38560 18261 38560 18262 38560 19180 38561 18262 38561 17047 38561 17047 38562 18262 38562 18266 38562 19272 38563 19271 38563 17041 38563 17041 38564 19190 38564 19272 38564 19272 38565 19190 38565 19191 38565 19272 38566 19191 38566 18296 38566 19191 38567 19273 38567 18296 38567 18296 38568 19273 38568 19186 38568 18296 38569 19186 38569 19274 38569 19186 38570 19185 38570 19274 38570 19274 38571 19185 38571 19275 38571 19274 38572 19275 38572 19276 38572 19276 38573 19275 38573 19184 38573 19276 38574 19184 38574 18297 38574 19184 38575 19182 38575 18297 38575 18297 38576 19182 38576 19277 38576 18297 38577 19277 38577 18294 38577 16964 38578 19278 38578 19279 38578 19279 38579 19278 38579 18294 38579 19279 38580 18294 38580 19280 38580 19280 38581 18294 38581 19277 38581 16955 38582 16946 38582 17884 38582 17884 38583 16946 38583 19286 38583 17884 38584 19286 38584 17882 38584 17882 38585 19286 38585 19281 38585 19281 38586 19287 38586 17882 38586 17882 38587 19287 38587 19289 38587 17882 38588 19289 38588 17881 38588 19289 38589 19291 38589 17881 38589 17881 38590 19291 38590 19285 38590 17881 38591 19285 38591 17880 38591 19282 38592 19284 38592 19283 38592 19283 38593 19284 38593 17879 38593 19283 38594 17879 38594 19293 38594 19293 38595 17879 38595 17880 38595 19293 38596 17880 38596 19292 38596 19292 38597 17880 38597 19285 38597 16946 38598 19295 38598 19297 38598 16946 38599 19297 38599 19286 38599 19286 38600 19297 38600 19288 38600 19286 38601 19288 38601 19281 38601 19281 38602 19288 38602 19287 38602 19287 38603 19288 38603 19290 38603 19287 38604 19290 38604 19289 38604 19289 38605 19290 38605 19291 38605 19291 38606 19290 38606 19300 38606 19291 38607 19300 38607 19285 38607 19285 38608 19300 38608 19292 38608 19292 38609 19300 38609 19302 38609 19292 38610 19302 38610 19293 38610 19293 38611 19302 38611 19294 38611 19293 38612 19294 38612 19283 38612 19283 38613 19294 38613 16932 38613 19283 38614 16932 38614 19282 38614 19295 38615 18580 38615 19297 38615 19297 38616 18580 38616 19296 38616 19297 38617 19296 38617 19288 38617 19288 38618 19296 38618 19298 38618 19288 38619 19298 38619 19290 38619 19290 38620 19298 38620 19299 38620 19290 38621 19299 38621 19300 38621 19300 38622 19299 38622 19301 38622 19300 38623 19301 38623 19302 38623 19302 38624 19301 38624 18250 38624 19302 38625 18250 38625 19294 38625 19294 38626 18250 38626 18249 38626 19294 38627 18249 38627 16932 38627 16932 38628 18249 38628 18251 38628 16931 38629 17894 38629 19312 38629 19312 38630 17894 38630 19303 38630 19312 38631 19303 38631 19310 38631 19310 38632 19303 38632 17895 38632 19310 38633 17895 38633 19304 38633 19304 38634 17895 38634 17896 38634 19304 38635 17896 38635 19308 38635 19308 38636 17896 38636 17897 38636 19308 38637 17897 38637 19307 38637 19307 38638 17897 38638 19306 38638 19307 38639 19306 38639 19305 38639 19305 38640 19306 38640 17899 38640 19305 38641 19313 38641 19307 38641 19307 38642 19313 38642 19314 38642 19307 38643 19314 38643 19308 38643 19308 38644 19314 38644 19309 38644 19308 38645 19309 38645 19304 38645 19304 38646 19309 38646 19311 38646 19304 38647 19311 38647 19310 38647 19310 38648 19311 38648 19318 38648 19310 38649 19318 38649 19312 38649 19312 38650 19318 38650 19320 38650 19312 38651 19320 38651 16931 38651 16931 38652 19320 38652 16917 38652 19313 38653 18260 38653 19314 38653 19314 38654 18260 38654 18259 38654 19314 38655 18259 38655 19309 38655 19309 38656 18259 38656 19315 38656 19309 38657 19315 38657 19311 38657 19311 38658 19315 38658 19316 38658 19311 38659 19316 38659 19318 38659 19318 38660 19316 38660 19317 38660 19318 38661 19317 38661 19320 38661 19320 38662 19317 38662 19319 38662 19320 38663 19319 38663 16917 38663 16917 38664 19319 38664 16912 38664 17904 38665 17906 38665 16907 38665 16907 38666 19333 38666 17904 38666 17904 38667 19333 38667 19321 38667 17904 38668 19321 38668 19323 38668 19321 38669 19322 38669 19323 38669 19323 38670 19322 38670 19336 38670 19323 38671 19336 38671 19324 38671 19336 38672 19337 38672 19324 38672 19324 38673 19337 38673 19338 38673 19324 38674 19338 38674 19325 38674 19325 38675 19338 38675 19326 38675 19325 38676 19326 38676 17916 38676 19326 38677 19327 38677 17916 38677 17916 38678 19327 38678 19339 38678 17916 38679 19339 38679 19328 38679 19329 38680 19330 38680 19331 38680 19331 38681 19330 38681 19328 38681 19331 38682 19328 38682 19340 38682 19340 38683 19328 38683 19339 38683 16907 38684 19332 38684 19333 38684 19333 38685 19332 38685 19334 38685 19333 38686 19334 38686 19321 38686 19321 38687 19334 38687 19322 38687 19322 38688 19334 38688 19335 38688 19322 38689 19335 38689 19336 38689 19336 38690 19335 38690 19337 38690 19337 38691 19335 38691 19341 38691 19337 38692 19341 38692 19338 38692 19338 38693 19341 38693 19326 38693 19326 38694 19341 38694 19343 38694 19326 38695 19343 38695 19327 38695 19327 38696 19343 38696 19339 38696 19339 38697 19343 38697 19344 38697 19339 38698 19344 38698 19340 38698 19340 38699 19344 38699 19331 38699 19331 38700 19344 38700 19345 38700 19331 38701 19345 38701 19329 38701 19332 38702 18629 38702 19334 38702 19334 38703 18629 38703 18274 38703 19334 38704 18274 38704 19335 38704 19335 38705 18274 38705 19342 38705 19335 38706 19342 38706 19341 38706 19341 38707 19342 38707 18273 38707 19341 38708 18273 38708 19343 38708 19343 38709 18273 38709 18280 38709 19343 38710 18280 38710 19344 38710 19344 38711 18280 38711 18281 38711 19344 38712 18281 38712 19345 38712 19345 38713 18281 38713 18283 38713 19348 38714 17919 38714 19346 38714 19346 38715 19354 38715 19348 38715 19348 38716 19354 38716 19347 38716 19348 38717 19347 38717 17933 38717 19347 38718 19356 38718 17933 38718 17933 38719 19356 38719 19349 38719 17933 38720 19349 38720 17931 38720 19349 38721 19357 38721 17931 38721 17931 38722 19357 38722 19358 38722 17931 38723 19358 38723 17929 38723 17929 38724 19358 38724 19359 38724 17929 38725 19359 38725 17928 38725 19359 38726 19360 38726 17928 38726 17928 38727 19360 38727 19361 38727 17928 38728 19361 38728 19350 38728 19351 38729 19352 38729 19362 38729 19362 38730 19352 38730 19350 38730 19362 38731 19350 38731 19353 38731 19353 38732 19350 38732 19361 38732 19346 38733 16893 38733 19354 38733 19354 38734 16893 38734 19355 38734 19354 38735 19355 38735 19347 38735 19347 38736 19355 38736 19356 38736 19356 38737 19355 38737 19363 38737 19356 38738 19363 38738 19349 38738 19349 38739 19363 38739 19357 38739 19357 38740 19363 38740 19364 38740 19357 38741 19364 38741 19358 38741 19358 38742 19364 38742 19359 38742 19359 38743 19364 38743 19365 38743 19359 38744 19365 38744 19360 38744 19360 38745 19365 38745 19361 38745 19361 38746 19365 38746 19366 38746 19361 38747 19366 38747 19353 38747 19353 38748 19366 38748 19362 38748 19362 38749 19366 38749 19367 38749 19362 38750 19367 38750 19351 38750 16893 38751 18288 38751 19355 38751 19355 38752 18288 38752 18295 38752 19355 38753 18295 38753 19363 38753 19363 38754 18295 38754 18293 38754 19363 38755 18293 38755 19364 38755 19364 38756 18293 38756 18292 38756 19364 38757 18292 38757 19365 38757 19365 38758 18292 38758 18291 38758 19365 38759 18291 38759 19366 38759 19366 38760 18291 38760 19368 38760 19366 38761 19368 38761 19367 38761 19367 38762 19368 38762 18563 38762 16809 38763 19369 38763 19382 38763 19382 38764 19369 38764 19381 38764 19369 38765 19370 38765 19381 38765 19381 38766 19370 38766 19371 38766 19381 38767 19371 38767 19379 38767 19371 38768 19372 38768 19379 38768 19379 38769 19372 38769 19493 38769 19379 38770 19493 38770 19373 38770 19493 38771 19492 38771 19373 38771 19373 38772 19492 38772 19374 38772 19373 38773 19374 38773 19387 38773 19374 38774 19375 38774 19387 38774 19387 38775 19375 38775 19376 38775 19387 38776 19376 38776 19386 38776 16802 38777 19377 38777 19488 38777 19488 38778 19377 38778 19386 38778 19488 38779 19386 38779 19489 38779 19489 38780 19386 38780 19376 38780 19442 38781 19378 38781 19373 38781 19373 38782 19378 38782 19443 38782 19373 38783 19443 38783 19379 38783 19379 38784 19443 38784 19380 38784 19379 38785 19380 38785 19381 38785 19381 38786 19380 38786 19449 38786 19381 38787 19449 38787 19382 38787 19382 38788 19449 38788 19448 38788 19382 38789 19448 38789 16880 38789 16880 38790 19448 38790 16854 38790 16880 38791 16854 38791 19383 38791 19383 38792 16854 38792 16851 38792 19383 38793 16851 38793 16878 38793 16878 38794 16851 38794 19384 38794 16878 38795 19384 38795 19385 38795 19385 38796 19384 38796 16850 38796 19385 38797 16850 38797 16875 38797 16875 38798 16850 38798 16848 38798 16875 38799 16848 38799 19377 38799 19377 38800 16848 38800 16846 38800 19377 38801 16846 38801 19386 38801 19386 38802 16846 38802 19439 38802 19386 38803 19439 38803 19387 38803 19387 38804 19439 38804 19442 38804 19387 38805 19442 38805 19373 38805 16874 38806 16795 38806 19388 38806 19388 38807 16795 38807 19497 38807 19388 38808 19497 38808 19399 38808 19399 38809 19497 38809 19499 38809 19399 38810 19499 38810 19389 38810 19389 38811 19499 38811 19500 38811 19389 38812 19500 38812 19391 38812 19391 38813 19500 38813 19501 38813 19391 38814 19501 38814 19392 38814 19392 38815 19501 38815 19503 38815 19392 38816 19503 38816 19393 38816 19393 38817 19503 38817 19504 38817 19393 38818 19504 38818 19394 38818 19394 38819 19504 38819 16869 38819 19467 38820 19389 38820 19390 38820 19390 38821 19389 38821 19391 38821 19390 38822 19391 38822 19468 38822 19468 38823 19391 38823 19392 38823 19468 38824 19392 38824 19471 38824 19471 38825 19392 38825 19393 38825 19471 38826 19393 38826 16829 38826 16829 38827 19393 38827 19394 38827 16829 38828 19394 38828 16830 38828 16830 38829 19394 38829 16868 38829 16830 38830 16868 38830 16831 38830 16831 38831 16868 38831 19395 38831 16831 38832 19395 38832 16834 38832 16834 38833 19395 38833 19396 38833 16834 38834 19396 38834 19397 38834 19397 38835 19396 38835 16871 38835 19397 38836 16871 38836 16837 38836 16837 38837 16871 38837 16873 38837 16837 38838 16873 38838 19398 38838 19398 38839 16873 38839 16874 38839 19398 38840 16874 38840 19465 38840 19465 38841 16874 38841 19388 38841 19465 38842 19388 38842 19466 38842 19466 38843 19388 38843 19399 38843 19466 38844 19399 38844 19467 38844 19467 38845 19399 38845 19389 38845 19417 38846 16792 38846 19400 38846 19400 38847 16792 38847 19505 38847 19400 38848 19505 38848 19419 38848 19419 38849 19505 38849 19507 38849 19419 38850 19507 38850 19401 38850 19401 38851 19507 38851 19508 38851 19401 38852 19508 38852 19402 38852 19402 38853 19508 38853 19403 38853 19402 38854 19403 38854 19422 38854 19422 38855 19403 38855 19404 38855 19422 38856 19404 38856 19405 38856 19405 38857 19404 38857 19509 38857 19405 38858 19509 38858 16865 38858 16865 38859 19509 38859 19510 38859 19421 38860 19422 38860 19406 38860 19406 38861 19422 38861 19405 38861 19406 38862 19405 38862 19407 38862 19407 38863 19405 38863 16865 38863 19407 38864 16865 38864 19408 38864 19408 38865 16865 38865 19409 38865 19408 38866 19409 38866 16810 38866 16810 38867 19409 38867 19410 38867 16810 38868 19410 38868 19411 38868 19411 38869 19410 38869 19413 38869 19411 38870 19413 38870 19412 38870 19412 38871 19413 38871 16866 38871 19412 38872 16866 38872 19414 38872 19414 38873 16866 38873 16867 38873 19414 38874 16867 38874 19415 38874 19415 38875 16867 38875 19417 38875 19415 38876 19417 38876 19416 38876 19416 38877 19417 38877 19400 38877 19416 38878 19400 38878 19418 38878 19418 38879 19400 38879 19419 38879 19418 38880 19419 38880 19420 38880 19420 38881 19419 38881 19401 38881 19420 38882 19401 38882 19486 38882 19486 38883 19401 38883 19402 38883 19486 38884 19402 38884 19421 38884 19421 38885 19402 38885 19422 38885 16863 38886 18119 38886 19423 38886 19423 38887 18119 38887 19424 38887 19423 38888 19424 38888 19425 38888 19425 38889 19424 38889 19426 38889 19425 38890 19426 38890 19433 38890 19433 38891 19426 38891 19428 38891 19433 38892 19428 38892 19427 38892 19427 38893 19428 38893 19429 38893 19427 38894 19429 38894 19432 38894 19432 38895 19429 38895 18112 38895 19432 38896 18112 38896 19430 38896 19430 38897 18112 38897 18113 38897 16853 38898 19447 38898 19430 38898 19430 38899 19447 38899 19432 38899 19447 38900 19431 38900 19432 38900 19432 38901 19431 38901 19446 38901 19432 38902 19446 38902 19427 38902 19446 38903 19445 38903 19427 38903 19427 38904 19445 38904 19434 38904 19427 38905 19434 38905 19433 38905 19434 38906 19444 38906 19433 38906 19433 38907 19444 38907 19435 38907 19433 38908 19435 38908 19425 38908 19435 38909 19441 38909 19425 38909 19425 38910 19441 38910 19436 38910 19425 38911 19436 38911 19423 38911 19438 38912 16863 38912 19437 38912 19437 38913 16863 38913 19423 38913 19437 38914 19423 38914 19440 38914 19440 38915 19423 38915 19436 38915 19439 38916 16846 38916 19438 38916 19438 38917 19437 38917 19439 38917 19439 38918 19437 38918 19440 38918 19439 38919 19440 38919 19442 38919 19440 38920 19436 38920 19442 38920 19442 38921 19436 38921 19441 38921 19442 38922 19441 38922 19378 38922 19441 38923 19435 38923 19378 38923 19378 38924 19435 38924 19444 38924 19378 38925 19444 38925 19443 38925 19443 38926 19444 38926 19434 38926 19443 38927 19434 38927 19380 38927 19434 38928 19445 38928 19380 38928 19380 38929 19445 38929 19446 38929 19380 38930 19446 38930 19449 38930 16853 38931 19448 38931 19447 38931 19447 38932 19448 38932 19449 38932 19447 38933 19449 38933 19431 38933 19431 38934 19449 38934 19446 38934 16838 38935 18127 38935 19463 38935 19463 38936 18127 38936 18126 38936 19463 38937 18126 38937 19462 38937 19462 38938 18126 38938 19450 38938 19462 38939 19450 38939 19451 38939 19451 38940 19450 38940 19452 38940 19451 38941 19452 38941 19459 38941 19459 38942 19452 38942 18123 38942 19459 38943 18123 38943 19458 38943 19458 38944 18123 38944 19453 38944 19458 38945 19453 38945 19454 38945 19454 38946 19453 38946 19455 38946 19454 38947 19455 38947 19456 38947 19456 38948 19455 38948 18134 38948 19456 38949 16836 38949 19454 38949 19454 38950 16836 38950 19457 38950 19454 38951 19457 38951 19458 38951 19458 38952 19457 38952 19464 38952 19458 38953 19464 38953 19459 38953 19459 38954 19464 38954 19460 38954 19459 38955 19460 38955 19451 38955 19451 38956 19460 38956 19461 38956 19451 38957 19461 38957 19462 38957 19462 38958 19461 38958 19469 38958 19462 38959 19469 38959 19463 38959 19463 38960 19469 38960 19470 38960 19463 38961 19470 38961 16838 38961 16838 38962 19470 38962 16827 38962 16836 38963 19398 38963 19457 38963 19457 38964 19398 38964 19465 38964 19457 38965 19465 38965 19464 38965 19464 38966 19465 38966 19466 38966 19464 38967 19466 38967 19460 38967 19460 38968 19466 38968 19467 38968 19460 38969 19467 38969 19461 38969 19461 38970 19467 38970 19390 38970 19461 38971 19390 38971 19469 38971 19469 38972 19390 38972 19468 38972 19469 38973 19468 38973 19470 38973 19470 38974 19468 38974 19471 38974 19470 38975 19471 38975 16827 38975 16827 38976 19471 38976 16829 38976 19481 38977 19472 38977 19473 38977 19473 38978 19472 38978 18150 38978 19473 38979 18150 38979 19479 38979 19479 38980 18150 38980 18152 38980 19479 38981 18152 38981 19474 38981 19474 38982 18152 38982 18137 38982 19474 38983 18137 38983 19475 38983 19475 38984 18137 38984 18139 38984 19475 38985 18139 38985 19476 38985 19476 38986 18139 38986 18140 38986 19476 38987 18140 38987 19477 38987 19477 38988 18140 38988 18142 38988 19477 38989 18142 38989 16818 38989 16818 38990 18142 38990 16821 38990 16818 38991 16820 38991 19477 38991 19477 38992 16820 38992 19483 38992 19477 38993 19483 38993 19476 38993 19476 38994 19483 38994 19478 38994 19476 38995 19478 38995 19475 38995 19475 38996 19478 38996 19484 38996 19475 38997 19484 38997 19474 38997 19474 38998 19484 38998 19485 38998 19474 38999 19485 38999 19479 38999 19479 39000 19485 39000 19480 39000 19479 39001 19480 39001 19473 39001 19473 39002 19480 39002 19482 39002 19473 39003 19482 39003 19481 39003 19481 39004 19482 39004 16811 39004 16820 39005 19415 39005 19483 39005 19483 39006 19415 39006 19416 39006 19483 39007 19416 39007 19478 39007 19478 39008 19416 39008 19418 39008 19478 39009 19418 39009 19484 39009 19484 39010 19418 39010 19420 39010 19484 39011 19420 39011 19485 39011 19485 39012 19420 39012 19486 39012 19485 39013 19486 39013 19480 39013 19480 39014 19486 39014 19421 39014 19480 39015 19421 39015 19482 39015 19482 39016 19421 39016 19406 39016 19482 39017 19406 39017 16811 39017 16811 39018 19406 39018 19407 39018 19487 39019 16803 39019 16802 39019 16802 39020 19488 39020 19487 39020 19487 39021 19488 39021 19489 39021 19487 39022 19489 39022 19490 39022 19489 39023 19376 39023 19490 39023 19490 39024 19376 39024 19375 39024 19490 39025 19375 39025 19491 39025 19375 39026 19374 39026 19491 39026 19491 39027 19374 39027 19492 39027 19491 39028 19492 39028 18465 39028 18465 39029 19492 39029 19493 39029 18465 39030 19493 39030 19494 39030 19493 39031 19372 39031 19494 39031 19494 39032 19372 39032 19371 39032 19494 39033 19371 39033 19496 39033 16809 39034 19495 39034 19369 39034 19369 39035 19495 39035 19496 39035 19369 39036 19496 39036 19370 39036 19370 39037 19496 39037 19371 39037 16795 39038 16794 39038 19497 39038 19497 39039 16794 39039 19498 39039 19497 39040 19498 39040 19499 39040 19499 39041 19498 39041 18238 39041 19499 39042 18238 39042 19500 39042 19500 39043 18238 39043 18239 39043 19500 39044 18239 39044 19501 39044 19501 39045 18239 39045 19502 39045 19501 39046 19502 39046 19503 39046 19503 39047 19502 39047 18446 39047 19503 39048 18446 39048 19504 39048 19504 39049 18446 39049 18610 39049 19504 39050 18610 39050 16869 39050 16869 39051 18610 39051 18611 39051 16792 39052 18438 39052 19505 39052 19505 39053 18438 39053 18437 39053 19505 39054 18437 39054 19507 39054 19507 39055 18437 39055 19506 39055 19507 39056 19506 39056 19508 39056 19508 39057 19506 39057 18436 39057 19508 39058 18436 39058 19403 39058 19403 39059 18436 39059 18434 39059 19403 39060 18434 39060 19404 39060 19404 39061 18434 39061 18433 39061 19404 39062 18433 39062 19509 39062 19509 39063 18433 39063 18432 39063 19509 39064 18432 39064 19510 39064 19510 39065 18432 39065 18431 39065 18066 39066 19511 39066 19521 39066 19521 39067 19512 39067 18066 39067 18066 39068 19512 39068 19513 39068 18066 39069 19513 39069 18065 39069 19513 39070 19522 39070 18065 39070 18065 39071 19522 39071 19525 39071 18065 39072 19525 39072 18064 39072 19525 39073 19514 39073 18064 39073 18064 39074 19514 39074 19515 39074 18064 39075 19515 39075 18074 39075 18074 39076 19515 39076 19527 39076 18074 39077 19527 39077 19516 39077 19527 39078 19528 39078 19516 39078 19516 39079 19528 39079 19517 39079 19516 39080 19517 39080 19520 39080 16785 39081 19518 39081 19519 39081 19519 39082 19518 39082 19520 39082 19519 39083 19520 39083 19531 39083 19531 39084 19520 39084 19517 39084 19521 39085 16771 39085 19512 39085 19512 39086 16771 39086 19544 39086 19512 39087 19544 39087 19513 39087 19513 39088 19544 39088 19523 39088 19513 39089 19523 39089 19522 39089 19522 39090 19523 39090 19524 39090 19522 39091 19524 39091 19525 39091 19525 39092 19524 39092 19526 39092 19525 39093 19526 39093 19514 39093 19514 39094 19526 39094 19540 39094 19514 39095 19540 39095 19515 39095 19515 39096 19540 39096 19539 39096 19515 39097 19539 39097 19527 39097 19527 39098 19539 39098 19537 39098 19527 39099 19537 39099 19528 39099 19528 39100 19537 39100 19529 39100 19528 39101 19529 39101 19517 39101 19517 39102 19529 39102 19530 39102 19517 39103 19530 39103 19531 39103 19531 39104 19530 39104 19532 39104 19531 39105 19532 39105 19519 39105 19519 39106 19532 39106 19533 39106 19519 39107 19533 39107 16785 39107 16785 39108 19533 39108 16772 39108 19534 39109 18457 39109 16772 39109 16772 39110 19533 39110 19534 39110 19534 39111 19533 39111 19532 39111 19534 39112 19532 39112 19535 39112 19532 39113 19530 39113 19535 39113 19535 39114 19530 39114 19529 39114 19535 39115 19529 39115 19536 39115 19536 39116 19529 39116 19537 39116 19536 39117 19537 39117 19538 39117 19537 39118 19539 39118 19538 39118 19538 39119 19539 39119 19540 39119 19538 39120 19540 39120 19541 39120 19540 39121 19526 39121 19541 39121 19541 39122 19526 39122 19524 39122 19541 39123 19524 39123 19542 39123 16771 39124 19543 39124 19544 39124 19544 39125 19543 39125 19542 39125 19544 39126 19542 39126 19523 39126 19523 39127 19542 39127 19524 39127 18087 39128 19549 39128 19545 39128 19545 39129 19549 39129 19550 39129 19545 39130 19550 39130 19546 39130 19546 39131 19550 39131 19551 39131 19551 39132 19552 39132 19546 39132 19546 39133 19552 39133 19547 39133 19546 39134 19547 39134 18082 39134 19547 39135 19554 39135 18082 39135 18082 39136 19554 39136 19556 39136 18082 39137 19556 39137 18081 39137 16745 39138 18079 39138 19560 39138 19560 39139 18079 39139 18080 39139 19560 39140 18080 39140 19548 39140 19548 39141 18080 39141 18081 39141 19548 39142 18081 39142 19557 39142 19557 39143 18081 39143 19556 39143 19549 39144 19561 39144 19562 39144 19549 39145 19562 39145 19550 39145 19550 39146 19562 39146 19565 39146 19550 39147 19565 39147 19551 39147 19551 39148 19565 39148 19552 39148 19552 39149 19565 39149 19553 39149 19552 39150 19553 39150 19547 39150 19547 39151 19553 39151 19554 39151 19554 39152 19553 39152 19555 39152 19554 39153 19555 39153 19556 39153 19556 39154 19555 39154 19557 39154 19557 39155 19555 39155 19558 39155 19557 39156 19558 39156 19548 39156 19548 39157 19558 39157 19559 39157 19548 39158 19559 39158 19560 39158 19560 39159 19559 39159 16746 39159 19560 39160 16746 39160 16745 39160 19561 39161 19563 39161 19562 39161 19562 39162 19563 39162 19564 39162 19562 39163 19564 39163 19565 39163 19565 39164 19564 39164 18247 39164 19565 39165 18247 39165 19553 39165 19553 39166 18247 39166 19566 39166 19553 39167 19566 39167 19555 39167 19555 39168 19566 39168 18245 39168 19555 39169 18245 39169 19558 39169 19558 39170 18245 39170 18244 39170 19558 39171 18244 39171 19559 39171 19559 39172 18244 39172 18243 39172 19559 39173 18243 39173 16746 39173 16746 39174 18243 39174 18241 39174 19567 39175 18101 39175 19568 39175 19568 39176 18101 39176 19569 39176 19568 39177 19569 39177 19577 39177 19577 39178 19569 39178 18093 39178 19577 39179 18093 39179 19576 39179 19576 39180 18093 39180 18094 39180 19576 39181 18094 39181 19574 39181 19574 39182 18094 39182 19570 39182 19574 39183 19570 39183 19571 39183 19571 39184 19570 39184 19572 39184 19571 39185 19572 39185 16737 39185 16737 39186 19572 39186 18095 39186 16710 39187 19591 39187 16737 39187 16737 39188 19591 39188 19571 39188 19591 39189 19592 39189 19571 39189 19571 39190 19592 39190 19573 39190 19571 39191 19573 39191 19574 39191 19573 39192 19587 39192 19574 39192 19574 39193 19587 39193 19585 39193 19574 39194 19585 39194 19576 39194 19585 39195 19584 39195 19576 39195 19576 39196 19584 39196 19575 39196 19576 39197 19575 39197 19577 39197 19575 39198 19583 39198 19577 39198 19577 39199 19583 39199 19578 39199 19577 39200 19578 39200 19568 39200 19580 39201 19567 39201 19579 39201 19579 39202 19567 39202 19568 39202 19579 39203 19568 39203 19581 39203 19581 39204 19568 39204 19578 39204 19582 39205 16714 39205 19580 39205 19580 39206 19579 39206 19582 39206 19582 39207 19579 39207 19581 39207 19582 39208 19581 39208 18450 39208 19581 39209 19578 39209 18450 39209 18450 39210 19578 39210 19583 39210 18450 39211 19583 39211 18451 39211 18451 39212 19583 39212 19575 39212 18451 39213 19575 39213 19586 39213 19575 39214 19584 39214 19586 39214 19586 39215 19584 39215 19585 39215 19586 39216 19585 39216 19588 39216 19585 39217 19587 39217 19588 39217 19588 39218 19587 39218 19573 39218 19588 39219 19573 39219 19589 39219 16710 39220 19590 39220 19591 39220 19591 39221 19590 39221 19589 39221 19591 39222 19589 39222 19592 39222 19592 39223 19589 39223 19573 39223 18104 39224 19604 39224 18103 39224 18103 39225 19604 39225 19593 39225 18103 39226 19593 39226 19595 39226 19595 39227 19593 39227 19607 39227 19607 39228 19594 39228 19595 39228 19595 39229 19594 39229 19596 39229 19595 39230 19596 39230 19598 39230 19596 39231 19597 39231 19598 39231 19598 39232 19597 39232 19609 39232 19598 39233 19609 39233 19599 39233 16690 39234 19600 39234 19602 39234 19602 39235 19600 39235 19601 39235 19602 39236 19601 39236 19603 39236 19603 39237 19601 39237 19599 39237 19603 39238 19599 39238 19610 39238 19610 39239 19599 39239 19609 39239 19604 39240 19605 39240 19612 39240 19604 39241 19612 39241 19593 39241 19593 39242 19612 39242 19606 39242 19593 39243 19606 39243 19607 39243 19607 39244 19606 39244 19594 39244 19594 39245 19606 39245 19608 39245 19594 39246 19608 39246 19596 39246 19596 39247 19608 39247 19597 39247 19597 39248 19608 39248 19615 39248 19597 39249 19615 39249 19609 39249 19609 39250 19615 39250 19610 39250 19610 39251 19615 39251 19611 39251 19610 39252 19611 39252 19603 39252 19603 39253 19611 39253 19618 39253 19603 39254 19618 39254 19602 39254 19602 39255 19618 39255 16691 39255 19602 39256 16691 39256 16690 39256 19605 39257 18558 39257 19612 39257 19612 39258 18558 39258 19613 39258 19612 39259 19613 39259 19606 39259 19606 39260 19613 39260 18559 39260 19606 39261 18559 39261 19608 39261 19608 39262 18559 39262 19614 39262 19608 39263 19614 39263 19615 39263 19615 39264 19614 39264 19616 39264 19615 39265 19616 39265 19611 39265 19611 39266 19616 39266 19617 39266 19611 39267 19617 39267 19618 39267 19618 39268 19617 39268 19619 39268 19618 39269 19619 39269 16691 39269 16691 39270 19619 39270 19620 39270 18252 39271 19621 39271 19624 39271 18573 39272 19622 39272 18679 39272 18679 39273 19622 39273 19623 39273 18679 39274 19623 39274 18680 39274 18680 39275 19623 39275 18254 39275 18680 39276 18254 39276 19624 39276 19624 39277 18254 39277 18256 39277 19624 39278 18256 39278 18252 39278 18573 39279 18679 39279 19625 39279 19625 39280 18679 39280 18677 39280 19625 39281 18677 39281 18258 39281 18270 39282 19626 39282 19629 39282 19629 39283 19626 39283 18265 39283 19629 39284 18265 39284 18677 39284 18677 39285 18265 39285 19627 39285 18677 39286 19627 39286 18258 39286 18270 39287 19629 39287 19628 39287 19628 39288 19629 39288 18676 39288 19628 39289 18676 39289 18275 39289 19634 39290 18564 39290 19630 39290 19634 39291 19630 39291 18676 39291 18676 39292 19630 39292 19631 39292 18676 39293 19631 39293 18275 39293 18439 39294 18469 39294 18670 39294 18670 39295 18469 39295 18472 39295 18670 39296 18472 39296 18671 39296 18671 39297 18472 39297 18473 39297 18671 39298 18473 39298 19632 39298 19632 39299 18473 39299 18300 39299 19632 39300 18300 39300 19633 39300 19633 39301 18300 39301 18285 39301 19633 39302 18285 39302 19634 39302 19634 39303 18285 39303 18289 39303 19634 39304 18289 39304 18564 39304 18439 39305 18670 39305 19635 39305 19635 39306 18670 39306 18668 39306 19635 39307 18668 39307 19637 39307 19638 39308 19639 39308 18668 39308 18668 39309 19639 39309 19636 39309 18668 39310 19636 39310 19637 39310 18455 39311 18447 39311 18667 39311 18667 39312 18447 39312 18551 39312 18667 39313 18551 39313 19638 39313 19638 39314 18551 39314 18550 39314 19638 39315 18550 39315 19639 39315 19642 39316 18242 39316 19641 39316 19641 39317 18242 39317 18445 39317 19641 39318 18445 39318 18667 39318 18667 39319 18445 39319 18453 39319 18667 39320 18453 39320 18455 39320 18538 39321 18539 39321 18665 39321 18665 39322 18539 39322 18549 39322 18665 39323 18549 39323 19641 39323 19641 39324 18549 39324 19640 39324 19641 39325 19640 39325 19642 39325 18538 39326 18665 39326 18537 39326 18537 39327 18665 39327 18664 39327 18537 39328 18664 39328 18466 39328 18466 39329 18664 39329 19643 39329 18466 39330 19643 39330 18458 39330 18458 39331 19643 39331 19644 39331 18458 39332 19644 39332 18464 39332 19645 39333 16663 39333 19646 39333 19645 39334 19646 39334 17773 39334 17773 39335 19646 39335 19647 39335 17773 39336 19647 39336 19648 39336 19648 39337 19647 39337 18692 39337 19648 39338 18692 39338 17745 39338 17745 39339 18692 39339 18691 39339 17745 39340 18691 39340 19649 39340 19649 39341 18691 39341 19650 39341 19649 39342 19650 39342 19651 39342 19651 39343 19650 39343 18689 39343 19651 39344 18689 39344 17748 39344 17748 39345 18689 39345 19652 39345 17748 39346 19652 39346 17749 39346 17749 39347 19652 39347 18687 39347 17749 39348 18687 39348 17750 39348 17750 39349 18687 39349 19653 39349 17750 39350 19653 39350 17753 39350 17753 39351 19653 39351 19654 39351 17753 39352 19654 39352 19655 39352 19655 39353 19654 39353 19656 39353 19655 39354 19656 39354 19657 39354 19657 39355 19656 39355 19658 39355 19657 39356 19658 39356 17755 39356 17755 39357 19658 39357 19659 39357 17755 39358 19659 39358 19660 39358 19660 39359 19659 39359 18682 39359 19660 39360 18682 39360 19661 39360 19661 39361 18682 39361 19662 39361 19661 39362 19662 39362 17756 39362 17756 39363 19662 39363 17452 39363 17756 39364 17452 39364 17757 39364 16649 39365 16648 39365 18155 39365 18155 39366 16648 39366 19664 39366 18155 39367 19664 39367 19663 39367 19663 39368 19664 39368 18562 39368 19663 39369 18562 39369 18157 39369 18157 39370 18562 39370 19665 39370 18157 39371 19665 39371 19667 39371 19667 39372 19665 39372 19666 39372 19667 39373 19666 39373 18159 39373 18159 39374 19666 39374 19668 39374 18159 39375 19668 39375 18160 39375 18160 39376 19668 39376 16637 39376 18162 39377 18568 39377 19669 39377 19669 39378 18568 39378 18567 39378 19669 39379 18567 39379 18164 39379 18164 39380 18567 39380 19670 39380 18164 39381 19670 39381 18167 39381 18167 39382 19670 39382 19671 39382 18167 39383 19671 39383 19672 39383 19672 39384 19671 39384 19673 39384 19672 39385 19673 39385 19674 39385 19674 39386 19673 39386 18569 39386 19674 39387 18569 39387 19675 39387 19675 39388 18569 39388 19676 39388 18170 39389 18545 39389 18171 39389 18171 39390 18545 39390 18544 39390 18171 39391 18544 39391 18172 39391 18172 39392 18544 39392 18548 39392 18172 39393 18548 39393 19678 39393 19678 39394 18548 39394 19677 39394 19678 39395 19677 39395 19679 39395 19679 39396 19677 39396 18547 39396 19679 39397 18547 39397 18176 39397 18176 39398 18547 39398 19681 39398 18176 39399 19681 39399 19680 39399 19680 39400 19681 39400 18543 39400 18178 39401 18553 39401 18180 39401 18180 39402 18553 39402 19683 39402 18180 39403 19683 39403 19682 39403 19682 39404 19683 39404 18232 39404 19682 39405 18232 39405 18181 39405 18181 39406 18232 39406 19684 39406 18181 39407 19684 39407 18182 39407 18182 39408 19684 39408 19685 39408 18182 39409 19685 39409 19686 39409 19686 39410 19685 39410 19687 39410 19686 39411 19687 39411 18186 39411 18186 39412 19687 39412 19688 39412 18186 39413 19688 39413 19689 39413 19689 39414 19688 39414 18599 39414 18188 39415 18468 39415 19690 39415 19690 39416 18468 39416 19691 39416 19690 39417 19691 39417 18195 39417 18195 39418 19691 39418 18196 39418 18196 39419 19691 39419 19692 39419 18196 39420 19692 39420 19693 39420 19693 39421 19692 39421 18193 39421 18193 39422 19692 39422 18467 39422 18193 39423 18467 39423 19694 39423 19694 39424 18467 39424 19695 39424 19695 39425 18467 39425 19696 39425 19695 39426 19696 39426 18190 39426 18190 39427 19696 39427 19697 39427 19697 39428 19696 39428 19698 39428 19697 39429 19698 39429 19699 39429 19699 39430 19698 39430 19700 39430 19700 39431 19698 39431 19701 39431 19700 39432 19701 39432 17514 39432 19702 39433 19703 39433 19705 39433 19705 39434 19703 39434 19704 39434 19705 39435 19704 39435 19706 39435 19706 39436 19704 39436 18526 39436 19706 39437 18526 39437 18200 39437 18200 39438 18526 39438 18525 39438 18200 39439 18525 39439 18201 39439 18201 39440 18525 39440 18523 39440 18201 39441 18523 39441 18203 39441 18203 39442 18523 39442 19707 39442 18203 39443 19707 39443 17506 39443 17506 39444 19707 39444 16609 39444 18205 39445 18529 39445 18206 39445 18206 39446 18529 39446 18532 39446 18206 39447 18532 39447 18208 39447 18208 39448 18532 39448 19708 39448 18208 39449 19708 39449 19709 39449 19709 39450 19708 39450 19710 39450 19709 39451 19710 39451 19711 39451 19711 39452 19710 39452 19712 39452 19711 39453 19712 39453 19713 39453 19713 39454 19712 39454 19714 39454 19713 39455 19714 39455 19715 39455 19715 39456 19714 39456 19716 39456 19715 39457 19716 39457 16600 39457 16600 39458 19716 39458 16601 39458 19717 39459 18491 39459 18213 39459 18213 39460 18491 39460 19718 39460 18213 39461 19718 39461 19719 39461 19719 39462 19718 39462 18487 39462 19719 39463 18487 39463 18215 39463 18215 39464 18487 39464 18496 39464 18215 39465 18496 39465 18217 39465 18217 39466 18496 39466 19720 39466 18217 39467 19720 39467 18218 39467 18218 39468 19720 39468 19721 39468 18218 39469 19721 39469 18221 39469 18221 39470 19721 39470 16595 39470 18222 39471 16594 39471 19722 39471 19722 39472 16594 39472 19724 39472 19722 39473 19724 39473 19723 39473 19723 39474 19724 39474 19725 39474 19723 39475 19725 39475 19726 39475 19726 39476 19725 39476 19728 39476 19726 39477 19728 39477 19727 39477 19727 39478 19728 39478 19729 39478 19727 39479 19729 39479 18225 39479 18225 39480 19729 39480 19730 39480 18225 39481 19730 39481 18227 39481 18227 39482 19730 39482 19731 39482 18227 39483 19731 39483 17484 39483 17484 39484 19731 39484 16588 39484 16586 39485 19733 39485 19732 39485 19732 39486 19733 39486 18515 39486 19732 39487 18515 39487 19734 39487 19734 39488 18515 39488 19735 39488 19734 39489 19735 39489 19736 39489 19736 39490 19735 39490 19737 39490 19736 39491 19737 39491 18230 39491 18230 39492 19737 39492 19738 39492 18230 39493 19738 39493 18231 39493 18231 39494 19738 39494 18514 39494 18231 39495 18514 39495 17474 39495 17474 39496 18514 39496 18513 39496 14872 39497 19739 39497 19740 39497 14872 39498 19740 39498 19741 39498 19741 39499 19740 39499 18663 39499 19741 39500 18663 39500 19742 39500 19742 39501 18663 39501 19743 39501 19742 39502 19743 39502 22852 39502 22852 39503 19743 39503 18666 39503 22852 39504 18666 39504 22851 39504 22851 39505 18666 39505 19744 39505 22851 39506 19744 39506 19745 39506 19745 39507 19744 39507 19747 39507 19745 39508 19747 39508 19746 39508 19746 39509 19747 39509 19748 39509 19746 39510 19748 39510 22847 39510 22847 39511 19748 39511 18669 39511 22847 39512 18669 39512 19749 39512 19749 39513 18669 39513 18672 39513 19749 39514 18672 39514 22845 39514 22845 39515 18672 39515 18673 39515 22845 39516 18673 39516 22842 39516 22842 39517 18673 39517 19750 39517 22842 39518 19750 39518 22841 39518 22841 39519 19750 39519 18674 39519 22841 39520 18674 39520 19751 39520 19751 39521 18674 39521 18675 39521 19751 39522 18675 39522 19752 39522 19752 39523 18675 39523 19753 39523 19752 39524 19753 39524 19754 39524 19754 39525 19753 39525 18678 39525 19754 39526 18678 39526 22838 39526 22838 39527 18678 39527 19755 39527 22838 39528 19755 39528 19756 39528 19756 39529 19755 39529 19757 39529 19756 39530 19757 39530 22836 39530 22836 39531 19757 39531 18681 39531 22836 39532 18681 39532 22832 39532 22832 39533 18681 39533 16568 39533 22832 39534 16568 39534 16567 39534 19760 39535 17479 39535 17480 39535 19760 39536 19758 39536 17479 39536 17479 39537 19758 39537 17472 39537 17479 39538 17472 39538 17473 39538 17473 39539 17475 39539 17479 39539 17479 39540 17475 39540 17476 39540 17479 39541 17476 39541 17478 39541 18228 39542 18229 39542 19759 39542 19759 39543 18229 39543 19760 39543 19759 39544 19760 39544 17483 39544 17483 39545 19760 39545 17480 39545 19761 39546 19762 39546 18224 39546 18223 39547 19762 39547 19763 39547 19763 39548 19762 39548 19761 39548 19763 39549 19761 39549 19764 39549 17487 39550 17489 39550 19761 39550 19761 39551 17489 39551 19765 39551 19761 39552 19765 39552 19764 39552 19766 39553 19767 39553 19768 39553 19768 39554 19767 39554 19761 39554 19768 39555 19761 39555 18226 39555 18226 39556 19761 39556 18224 39556 19771 39557 17496 39557 18212 39557 17491 39558 19769 39558 19770 39558 18220 39559 17490 39559 18212 39559 18212 39560 17490 39560 17491 39560 17491 39561 19770 39561 18212 39561 18212 39562 19770 39562 17495 39562 18212 39563 17495 39563 19771 39563 18216 39564 18219 39564 19772 39564 19772 39565 18219 39565 18220 39565 19772 39566 18220 39566 18214 39566 18214 39567 18220 39567 18212 39567 19774 39568 18211 39568 19776 39568 19775 39569 17500 39569 17501 39569 18210 39570 19773 39570 18209 39570 18209 39571 19773 39571 19774 39571 17501 39572 17503 39572 19775 39572 19775 39573 17503 39573 17504 39573 19775 39574 17504 39574 19776 39574 19776 39575 17504 39575 19777 39575 19776 39576 19777 39576 19774 39576 19774 39577 19777 39577 18207 39577 19774 39578 18207 39578 18209 39578 18199 39579 17510 39579 17512 39579 18202 39580 18204 39580 18199 39580 18199 39581 18204 39581 17505 39581 17508 39582 17510 39582 17507 39582 17507 39583 17510 39583 18199 39583 17507 39584 18199 39584 19778 39584 19778 39585 18199 39585 17505 39585 18197 39586 18198 39586 19779 39586 19779 39587 18198 39587 18199 39587 19779 39588 18199 39588 19780 39588 19780 39589 18199 39589 17512 39589 18194 39590 18192 39590 17516 39590 18192 39591 19781 39591 17516 39591 17516 39592 19781 39592 18191 39592 17516 39593 18191 39593 19785 39593 19782 39594 17519 39594 17516 39594 17516 39595 17519 39595 18187 39595 17516 39596 18187 39596 18194 39596 19783 39597 17515 39597 19784 39597 19784 39598 17515 39598 17516 39598 19784 39599 17516 39599 18189 39599 18189 39600 17516 39600 19785 39600 18184 39601 18185 39601 19786 39601 17521 39602 17523 39602 19786 39602 19786 39603 17523 39603 19787 39603 18179 39604 19788 39604 19789 39604 19789 39605 18183 39605 18179 39605 18179 39606 18183 39606 18184 39606 18179 39607 18184 39607 19790 39607 19790 39608 18184 39608 19786 39608 19790 39609 19786 39609 18177 39609 18177 39610 19786 39610 19787 39610 18177 39611 19787 39611 17525 39611 19793 39612 17534 39612 19791 39612 19791 39613 17534 39613 18169 39613 19794 39614 17528 39614 17530 39614 18169 39615 18173 39615 19791 39615 19791 39616 18173 39616 18174 39616 19791 39617 18174 39617 18175 39617 19791 39618 19792 39618 19793 39618 19793 39619 19792 39619 19794 39619 19793 39620 19794 39620 17532 39620 17532 39621 19794 39621 17530 39621 19796 39622 17539 39622 18161 39622 18168 39623 19795 39623 19797 39623 18165 39624 18166 39624 18168 39624 17536 39625 17537 39625 19796 39625 18161 39626 18163 39626 18165 39626 18165 39627 18168 39627 18161 39627 18161 39628 18168 39628 19797 39628 18161 39629 19797 39629 19796 39629 19796 39630 19797 39630 17535 39630 19796 39631 17535 39631 17536 39631 19801 39632 18158 39632 19799 39632 19798 39633 17541 39633 19800 39633 19800 39634 18154 39634 18156 39634 17544 39635 17542 39635 17540 39635 17540 39636 17542 39636 19798 39636 17540 39637 19798 39637 19799 39637 19799 39638 19798 39638 19800 39638 19799 39639 19800 39639 19801 39639 19801 39640 19800 39640 18156 39640 19801 39641 18156 39641 19802 39641 22738 39642 14957 39642 22735 39642 22738 39643 22735 39643 22739 39643 22739 39644 22735 39644 19803 39644 22739 39645 19803 39645 19804 39645 19804 39646 19803 39646 22734 39646 19804 39647 22734 39647 19806 39647 19806 39648 22734 39648 19805 39648 19806 39649 19805 39649 19807 39649 19807 39650 19805 39650 22732 39650 19807 39651 22732 39651 22742 39651 22742 39652 22732 39652 19808 39652 22742 39653 19808 39653 19810 39653 19810 39654 19808 39654 19809 39654 19810 39655 19809 39655 22743 39655 22743 39656 19809 39656 22730 39656 22743 39657 22730 39657 22746 39657 22746 39658 22730 39658 19811 39658 22746 39659 19811 39659 22748 39659 22748 39660 19811 39660 22728 39660 22748 39661 22728 39661 19812 39661 19812 39662 22728 39662 22727 39662 19812 39663 22727 39663 19813 39663 19813 39664 22727 39664 19814 39664 19813 39665 19814 39665 22750 39665 22750 39666 19814 39666 22724 39666 22750 39667 22724 39667 22751 39667 22751 39668 22724 39668 22723 39668 22751 39669 22723 39669 19815 39669 19815 39670 22723 39670 22720 39670 19815 39671 22720 39671 22753 39671 22753 39672 22720 39672 22719 39672 22753 39673 22719 39673 19816 39673 19816 39674 22719 39674 22717 39674 19816 39675 22717 39675 19817 39675 19817 39676 22717 39676 22716 39676 19817 39677 22716 39677 22756 39677 22756 39678 22716 39678 19818 39678 22756 39679 19818 39679 16547 39679 19819 39680 14918 39680 19820 39680 19819 39681 19820 39681 22809 39681 22809 39682 19820 39682 19822 39682 22809 39683 19822 39683 19821 39683 19821 39684 19822 39684 22771 39684 19821 39685 22771 39685 22813 39685 22813 39686 22771 39686 19823 39686 22813 39687 19823 39687 19824 39687 19824 39688 19823 39688 22768 39688 19824 39689 22768 39689 19825 39689 19825 39690 22768 39690 22767 39690 19825 39691 22767 39691 19826 39691 19826 39692 22767 39692 19828 39692 19826 39693 19828 39693 19827 39693 19827 39694 19828 39694 19829 39694 19827 39695 19829 39695 22818 39695 22818 39696 19829 39696 19830 39696 22818 39697 19830 39697 22819 39697 22819 39698 19830 39698 19831 39698 22819 39699 19831 39699 22824 39699 22824 39700 19831 39700 22764 39700 22824 39701 22764 39701 22821 39701 22821 39702 22764 39702 22763 39702 22821 39703 22763 39703 19832 39703 19832 39704 22763 39704 19833 39704 19832 39705 19833 39705 19834 39705 19834 39706 19833 39706 19835 39706 19834 39707 19835 39707 22827 39707 22827 39708 19835 39708 19836 39708 22827 39709 19836 39709 19837 39709 19837 39710 19836 39710 19838 39710 19837 39711 19838 39711 19839 39711 19839 39712 19838 39712 22760 39712 19839 39713 22760 39713 22830 39713 22830 39714 22760 39714 22759 39714 22830 39715 22759 39715 19840 39715 19840 39716 22759 39716 14941 39716 19840 39717 14941 39717 22831 39717 22694 39718 14994 39718 19841 39718 22694 39719 19841 39719 22695 39719 22695 39720 19841 39720 22693 39720 22695 39721 22693 39721 19842 39721 19842 39722 22693 39722 22692 39722 19842 39723 22692 39723 22697 39723 22697 39724 22692 39724 19843 39724 22697 39725 19843 39725 19845 39725 19845 39726 19843 39726 19844 39726 19845 39727 19844 39727 22700 39727 22700 39728 19844 39728 22689 39728 22700 39729 22689 39729 19846 39729 19846 39730 22689 39730 22688 39730 19846 39731 22688 39731 19847 39731 19847 39732 22688 39732 19848 39732 19847 39733 19848 39733 22703 39733 22703 39734 19848 39734 19850 39734 22703 39735 19850 39735 19849 39735 19849 39736 19850 39736 22685 39736 19849 39737 22685 39737 19851 39737 19851 39738 22685 39738 22684 39738 19851 39739 22684 39739 22705 39739 22705 39740 22684 39740 22682 39740 22705 39741 22682 39741 19852 39741 19852 39742 22682 39742 19853 39742 19852 39743 19853 39743 22707 39743 22707 39744 19853 39744 22680 39744 22707 39745 22680 39745 19855 39745 19855 39746 22680 39746 19854 39746 19855 39747 19854 39747 22709 39747 22709 39748 19854 39748 22678 39748 22709 39749 22678 39749 19856 39749 19856 39750 22678 39750 22675 39750 19856 39751 22675 39751 22711 39751 22711 39752 22675 39752 22674 39752 22711 39753 22674 39753 22713 39753 22713 39754 22674 39754 19857 39754 22713 39755 19857 39755 22715 39755 22655 39756 15032 39756 19858 39756 22655 39757 19858 39757 22656 39757 22656 39758 19858 39758 19859 39758 22656 39759 19859 39759 19860 39759 19860 39760 19859 39760 22652 39760 19860 39761 22652 39761 19861 39761 19861 39762 22652 39762 22651 39762 19861 39763 22651 39763 19862 39763 19862 39764 22651 39764 19864 39764 19862 39765 19864 39765 19863 39765 19863 39766 19864 39766 19865 39766 19863 39767 19865 39767 22657 39767 22657 39768 19865 39768 19866 39768 22657 39769 19866 39769 22659 39769 22659 39770 19866 39770 19867 39770 22659 39771 19867 39771 22660 39771 22660 39772 19867 39772 19868 39772 22660 39773 19868 39773 19869 39773 19869 39774 19868 39774 22646 39774 19869 39775 22646 39775 22663 39775 22663 39776 22646 39776 22645 39776 22663 39777 22645 39777 22664 39777 22664 39778 22645 39778 22643 39778 22664 39779 22643 39779 22666 39779 22666 39780 22643 39780 19870 39780 22666 39781 19870 39781 22667 39781 22667 39782 19870 39782 19872 39782 22667 39783 19872 39783 19871 39783 19871 39784 19872 39784 22639 39784 19871 39785 22639 39785 19873 39785 19873 39786 22639 39786 22638 39786 19873 39787 22638 39787 22669 39787 22669 39788 22638 39788 19874 39788 22669 39789 19874 39789 22671 39789 22671 39790 19874 39790 22637 39790 22671 39791 22637 39791 22673 39791 22673 39792 22637 39792 15044 39792 22673 39793 15044 39793 15012 39793 22622 39794 16490 39794 19875 39794 22622 39795 19875 39795 19877 39795 19877 39796 19875 39796 19876 39796 19877 39797 19876 39797 22623 39797 22623 39798 19876 39798 19878 39798 22623 39799 19878 39799 19879 39799 19879 39800 19878 39800 19881 39800 19879 39801 19881 39801 19880 39801 19880 39802 19881 39802 22619 39802 19880 39803 22619 39803 22627 39803 22627 39804 22619 39804 19882 39804 22627 39805 19882 39805 19883 39805 19883 39806 19882 39806 19884 39806 19883 39807 19884 39807 19885 39807 19885 39808 19884 39808 19886 39808 19885 39809 19886 39809 22629 39809 22629 39810 19886 39810 19888 39810 22629 39811 19888 39811 19887 39811 19887 39812 19888 39812 22615 39812 19887 39813 22615 39813 19889 39813 19889 39814 22615 39814 22614 39814 19889 39815 22614 39815 22630 39815 22630 39816 22614 39816 22613 39816 22630 39817 22613 39817 22631 39817 22631 39818 22613 39818 22611 39818 22631 39819 22611 39819 19890 39819 19890 39820 22611 39820 19892 39820 19890 39821 19892 39821 19891 39821 19891 39822 19892 39822 22610 39822 19891 39823 22610 39823 22633 39823 22633 39824 22610 39824 19893 39824 22633 39825 19893 39825 22634 39825 22634 39826 19893 39826 22609 39826 22634 39827 22609 39827 19894 39827 19894 39828 22609 39828 19895 39828 19894 39829 19895 39829 22635 39829 22635 39830 19895 39830 16474 39830 22635 39831 16474 39831 22636 39831 16473 39832 16472 39832 22594 39832 16473 39833 22594 39833 19896 39833 19896 39834 22594 39834 22593 39834 19896 39835 22593 39835 22596 39835 22596 39836 22593 39836 22591 39836 22596 39837 22591 39837 19897 39837 19897 39838 22591 39838 22590 39838 19897 39839 22590 39839 19898 39839 19898 39840 22590 39840 19899 39840 19898 39841 19899 39841 22597 39841 22597 39842 19899 39842 19900 39842 22597 39843 19900 39843 19902 39843 19902 39844 19900 39844 19901 39844 19902 39845 19901 39845 19904 39845 19904 39846 19901 39846 19903 39846 19904 39847 19903 39847 22599 39847 22599 39848 19903 39848 19905 39848 22599 39849 19905 39849 19906 39849 19906 39850 19905 39850 19907 39850 19906 39851 19907 39851 19908 39851 19908 39852 19907 39852 19909 39852 19908 39853 19909 39853 19910 39853 19910 39854 19909 39854 19911 39854 19910 39855 19911 39855 19912 39855 19912 39856 19911 39856 22584 39856 19912 39857 22584 39857 19913 39857 19913 39858 22584 39858 22583 39858 19913 39859 22583 39859 22602 39859 22602 39860 22583 39860 19914 39860 22602 39861 19914 39861 22605 39861 22605 39862 19914 39862 22580 39862 22605 39863 22580 39863 19915 39863 19915 39864 22580 39864 22579 39864 19915 39865 22579 39865 22606 39865 22606 39866 22579 39866 19916 39866 22606 39867 19916 39867 19917 39867 19917 39868 19916 39868 22577 39868 19917 39869 22577 39869 22607 39869 15125 39870 22559 39870 19918 39870 15125 39871 19918 39871 22561 39871 22561 39872 19918 39872 22557 39872 22561 39873 22557 39873 19919 39873 19919 39874 22557 39874 19920 39874 19919 39875 19920 39875 19921 39875 19921 39876 19920 39876 22555 39876 19921 39877 22555 39877 19922 39877 19922 39878 22555 39878 22553 39878 19922 39879 22553 39879 19923 39879 19923 39880 22553 39880 19924 39880 19923 39881 19924 39881 19925 39881 19925 39882 19924 39882 22551 39882 19925 39883 22551 39883 22566 39883 22566 39884 22551 39884 22550 39884 22566 39885 22550 39885 19926 39885 19926 39886 22550 39886 22548 39886 19926 39887 22548 39887 22568 39887 22568 39888 22548 39888 22546 39888 22568 39889 22546 39889 22569 39889 22569 39890 22546 39890 19927 39890 22569 39891 19927 39891 19928 39891 19928 39892 19927 39892 19929 39892 19928 39893 19929 39893 22570 39893 22570 39894 19929 39894 22543 39894 22570 39895 22543 39895 22571 39895 22571 39896 22543 39896 22541 39896 22571 39897 22541 39897 22573 39897 22573 39898 22541 39898 22540 39898 22573 39899 22540 39899 19930 39899 19930 39900 22540 39900 22539 39900 19930 39901 22539 39901 22576 39901 22576 39902 22539 39902 19931 39902 22576 39903 19931 39903 19932 39903 19932 39904 19931 39904 22536 39904 19932 39905 22536 39905 19933 39905 19933 39906 22536 39906 15151 39906 19933 39907 15151 39907 16427 39907 19935 39908 19934 39908 19936 39908 19935 39909 19936 39909 19938 39909 19938 39910 19936 39910 19937 39910 19938 39911 19937 39911 22516 39911 22516 39912 19937 39912 19939 39912 22516 39913 19939 39913 19940 39913 19940 39914 19939 39914 19942 39914 19940 39915 19942 39915 19941 39915 19941 39916 19942 39916 19943 39916 19941 39917 19943 39917 19944 39917 19944 39918 19943 39918 22511 39918 19944 39919 22511 39919 19946 39919 19946 39920 22511 39920 19945 39920 19946 39921 19945 39921 22522 39921 22522 39922 19945 39922 19947 39922 22522 39923 19947 39923 19948 39923 19948 39924 19947 39924 19949 39924 19948 39925 19949 39925 19951 39925 19951 39926 19949 39926 19950 39926 19951 39927 19950 39927 19952 39927 19952 39928 19950 39928 22507 39928 19952 39929 22507 39929 22526 39929 22526 39930 22507 39930 22506 39930 22526 39931 22506 39931 19953 39931 19953 39932 22506 39932 19955 39932 19953 39933 19955 39933 19954 39933 19954 39934 19955 39934 22503 39934 19954 39935 22503 39935 22529 39935 22529 39936 22503 39936 19956 39936 22529 39937 19956 39937 19957 39937 19957 39938 19956 39938 22502 39938 19957 39939 22502 39939 22532 39939 22532 39940 22502 39940 19958 39940 22532 39941 19958 39941 22533 39941 22533 39942 19958 39942 19959 39942 22533 39943 19959 39943 19960 39943 19960 39944 19959 39944 16405 39944 19960 39945 16405 39945 16406 39945 22480 39946 16404 39946 21717 39946 22480 39947 21717 39947 22481 39947 22481 39948 21717 39948 19961 39948 22481 39949 19961 39949 22483 39949 22483 39950 19961 39950 21715 39950 22483 39951 21715 39951 19962 39951 19962 39952 21715 39952 21714 39952 19962 39953 21714 39953 19963 39953 19963 39954 21714 39954 19965 39954 19963 39955 19965 39955 19964 39955 19964 39956 19965 39956 19966 39956 19964 39957 19966 39957 22486 39957 22486 39958 19966 39958 19967 39958 22486 39959 19967 39959 22487 39959 22487 39960 19967 39960 19969 39960 22487 39961 19969 39961 19968 39961 19968 39962 19969 39962 19970 39962 19968 39963 19970 39963 19971 39963 19971 39964 19970 39964 19972 39964 19971 39965 19972 39965 22490 39965 22490 39966 19972 39966 21709 39966 22490 39967 21709 39967 22491 39967 22491 39968 21709 39968 19973 39968 22491 39969 19973 39969 22493 39969 22493 39970 19973 39970 21706 39970 22493 39971 21706 39971 19974 39971 19974 39972 21706 39972 21704 39972 19974 39973 21704 39973 22496 39973 22496 39974 21704 39974 21703 39974 22496 39975 21703 39975 22497 39975 22497 39976 21703 39976 19975 39976 22497 39977 19975 39977 22498 39977 22498 39978 19975 39978 21701 39978 22498 39979 21701 39979 22499 39979 22499 39980 21701 39980 19977 39980 22499 39981 19977 39981 19976 39981 19976 39982 19977 39982 16382 39982 19976 39983 16382 39983 16383 39983 19978 39984 22854 39984 22853 39984 19978 39985 22853 39985 19979 39985 19979 39986 22853 39986 19980 39986 19979 39987 19980 39987 21680 39987 21680 39988 19980 39988 19981 39988 21680 39989 19981 39989 21681 39989 21681 39990 19981 39990 22850 39990 21681 39991 22850 39991 21683 39991 21683 39992 22850 39992 22849 39992 21683 39993 22849 39993 21685 39993 21685 39994 22849 39994 22848 39994 21685 39995 22848 39995 21686 39995 21686 39996 22848 39996 22846 39996 21686 39997 22846 39997 21688 39997 21688 39998 22846 39998 19982 39998 21688 39999 19982 39999 21689 39999 21689 40000 19982 40000 22844 40000 21689 40001 22844 40001 21690 40001 21690 40002 22844 40002 22843 40002 21690 40003 22843 40003 19983 40003 19983 40004 22843 40004 19984 40004 19983 40005 19984 40005 19985 40005 19985 40006 19984 40006 19986 40006 19985 40007 19986 40007 21694 40007 21694 40008 19986 40008 22840 40008 21694 40009 22840 40009 19987 40009 19987 40010 22840 40010 22839 40010 19987 40011 22839 40011 19988 40011 19988 40012 22839 40012 22837 40012 19988 40013 22837 40013 21695 40013 21695 40014 22837 40014 22835 40014 21695 40015 22835 40015 21697 40015 21697 40016 22835 40016 22834 40016 21697 40017 22834 40017 19989 40017 19989 40018 22834 40018 22833 40018 19989 40019 22833 40019 21698 40019 21698 40020 22833 40020 14894 40020 21698 40021 14894 40021 19990 40021 19992 40022 19991 40022 19993 40022 19992 40023 19993 40023 19995 40023 19995 40024 19993 40024 19994 40024 19995 40025 19994 40025 22919 40025 22919 40026 19994 40026 19996 40026 22919 40027 19996 40027 22921 40027 22921 40028 19996 40028 19997 40028 22921 40029 19997 40029 19998 40029 19998 40030 19997 40030 20345 40030 19998 40031 20345 40031 22923 40031 22923 40032 20345 40032 20346 40032 22923 40033 20346 40033 22924 40033 22924 40034 20346 40034 21587 40034 22924 40035 21587 40035 22926 40035 20000 40036 21588 40036 19999 40036 20000 40037 19999 40037 20001 40037 20001 40038 19999 40038 20034 40038 20001 40039 20034 40039 22897 40039 22897 40040 20034 40040 20233 40040 22897 40041 20233 40041 22900 40041 22900 40042 20233 40042 20235 40042 22900 40043 20235 40043 20002 40043 20002 40044 20235 40044 20238 40044 20002 40045 20238 40045 22901 40045 22901 40046 20238 40046 20237 40046 22901 40047 20237 40047 22904 40047 22904 40048 20237 40048 20003 40048 22904 40049 20003 40049 22906 40049 22906 40050 20003 40050 20417 40050 22906 40051 20417 40051 22907 40051 22907 40052 20417 40052 20425 40052 22907 40053 20425 40053 20004 40053 20004 40054 20425 40054 20424 40054 20004 40055 20424 40055 22910 40055 22910 40056 20424 40056 20422 40056 22910 40057 20422 40057 20005 40057 20005 40058 20422 40058 20006 40058 20005 40059 20006 40059 20007 40059 20007 40060 20006 40060 20008 40060 20007 40061 20008 40061 20009 40061 22903 40062 20015 40062 20016 40062 20016 40063 20010 40063 22914 40063 22914 40064 20010 40064 22911 40064 22914 40065 20011 40065 20016 40065 20016 40066 20011 40066 22898 40066 20016 40067 22898 40067 22899 40067 22911 40068 20012 40068 22914 40068 22914 40069 20012 40069 22913 40069 22914 40070 22913 40070 22917 40070 22917 40071 22913 40071 22912 40071 22917 40072 22912 40072 22916 40072 22916 40073 14866 40073 22917 40073 22917 40074 14866 40074 20013 40074 22917 40075 20013 40075 20017 40075 22899 40076 20014 40076 20016 40076 20016 40077 20014 40077 22902 40077 20016 40078 22902 40078 22903 40078 20015 40079 22905 40079 20016 40079 20016 40080 22905 40080 22908 40080 20016 40081 22908 40081 22909 40081 20017 40082 20018 40082 22917 40082 22917 40083 20018 40083 14869 40083 22917 40084 14869 40084 20021 40084 22918 40085 22920 40085 20019 40085 20019 40086 22922 40086 22918 40086 22918 40087 22922 40087 20020 40087 22918 40088 20020 40088 22925 40088 20021 40089 14871 40089 22917 40089 22917 40090 14871 40090 22918 40090 22917 40091 22918 40091 20022 40091 20022 40092 22918 40092 22925 40092 22778 40093 22779 40093 20023 40093 20023 40094 22779 40094 22985 40094 22888 40095 22773 40095 22781 40095 22781 40096 22773 40096 22986 40096 22788 40097 22990 40097 22777 40097 22777 40098 22990 40098 22988 40098 22785 40099 22991 40099 22790 40099 22790 40100 22991 40100 22789 40100 22868 40101 22808 40101 22855 40101 22855 40102 22808 40102 22800 40102 22876 40103 22980 40103 22880 40103 22880 40104 22980 40104 22981 40104 22867 40105 22978 40105 22791 40105 22791 40106 22978 40106 22793 40106 22860 40107 22805 40107 22863 40107 22863 40108 22805 40108 20024 40108 22811 40109 20335 40109 20025 40109 22829 40110 20026 40110 22828 40110 16258 40111 20027 40111 20131 40111 20028 40112 20278 40112 14900 40112 20029 40113 20268 40113 20274 40113 20089 40114 20270 40114 14903 40114 20030 40115 20411 40115 20031 40115 21587 40116 20346 40116 20032 40116 16357 40117 20033 40117 20242 40117 20436 40118 21556 40118 20435 40118 19999 40119 20366 40119 20034 40119 20035 40120 21505 40120 20036 40120 15557 40121 20215 40121 20214 40121 20195 40122 20037 40122 20038 40122 20388 40123 20892 40123 20390 40123 20038 40124 22826 40124 20206 40124 20184 40125 20039 40125 20040 40125 20122 40126 16289 40126 20041 40126 15790 40127 15791 40127 20373 40127 20285 40128 16272 40128 20386 40128 20386 40129 16272 40129 16274 40129 20386 40130 16274 40130 16275 40130 20387 40131 16277 40131 16279 40131 20387 40132 16279 40132 20396 40132 16164 40133 20397 40133 20396 40133 20042 40134 16164 40134 20510 40134 20510 40135 16164 40135 20396 40135 20510 40136 20396 40136 16281 40136 16281 40137 20396 40137 16279 40137 14897 40138 20661 40138 20042 40138 20510 40139 20509 40139 20042 40139 20042 40140 20509 40140 20508 40140 20042 40141 20508 40141 14897 40141 14897 40142 20508 40142 20506 40142 14897 40143 20506 40143 20043 40143 20043 40144 20506 40144 20284 40144 20043 40145 20284 40145 14898 40145 15796 40146 15798 40146 20404 40146 15796 40147 20404 40147 21089 40147 21089 40148 20404 40148 20048 40148 21089 40149 20048 40149 21087 40149 20044 40150 20047 40150 20068 40150 20068 40151 20047 40151 21081 40151 20068 40152 21081 40152 21082 40152 20412 40153 15802 40153 20411 40153 20411 40154 15802 40154 15805 40154 20411 40155 15805 40155 20031 40155 20031 40156 15805 40156 20045 40156 20031 40157 20045 40157 20044 40157 20044 40158 20045 40158 20046 40158 20044 40159 20046 40159 20047 40159 20048 40160 20408 40160 21087 40160 21087 40161 20408 40161 20049 40161 21087 40162 20049 40162 21086 40162 21086 40163 20049 40163 15752 40163 21086 40164 15752 40164 21082 40164 21082 40165 15752 40165 20067 40165 21082 40166 20067 40166 20068 40166 20057 40167 20354 40167 20050 40167 20050 40168 20354 40168 20355 40168 20050 40169 20355 40169 20065 40169 20051 40170 20064 40170 20059 40170 20052 40171 20053 40171 14907 40171 14907 40172 20053 40172 20054 40172 14907 40173 20054 40173 14908 40173 14908 40174 20054 40174 20055 40174 14908 40175 20055 40175 21105 40175 20051 40176 15740 40176 20064 40176 20064 40177 15740 40177 20056 40177 20064 40178 20056 40178 20063 40178 15784 40179 20354 40179 15785 40179 15785 40180 20354 40180 20058 40180 20057 40181 15743 40181 20354 40181 20354 40182 15743 40182 15741 40182 20354 40183 15741 40183 20058 40183 20058 40184 15741 40184 20051 40184 20058 40185 20051 40185 21103 40185 21103 40186 20051 40186 20059 40186 15778 40187 20360 40187 20060 40187 20060 40188 20360 40188 15781 40188 21183 40189 20061 40189 20062 40189 20062 40190 20061 40190 14908 40190 20062 40191 14908 40191 20063 40191 20063 40192 14908 40192 21105 40192 20063 40193 21105 40193 20064 40193 20065 40194 20355 40194 21181 40194 21181 40195 20355 40195 20066 40195 21181 40196 20066 40196 21182 40196 20067 40197 20069 40197 20068 40197 20068 40198 20069 40198 20070 40198 20068 40199 20070 40199 14914 40199 14914 40200 20070 40200 21154 40200 14914 40201 21154 40201 20071 40201 20071 40202 21154 40202 20072 40202 20071 40203 20072 40203 15793 40203 15793 40204 20072 40204 20073 40204 15793 40205 20073 40205 15791 40205 15791 40206 20073 40206 20074 40206 15791 40207 20074 40207 20373 40207 20373 40208 20074 40208 21149 40208 20373 40209 21149 40209 20406 40209 20406 40210 21149 40210 15756 40210 20406 40211 15756 40211 20407 40211 20081 40212 20075 40212 20076 40212 20080 40213 14912 40213 20079 40213 15793 40214 21091 40214 20071 40214 20071 40215 21091 40215 20077 40215 20071 40216 20077 40216 14911 40216 14911 40217 20077 40217 20078 40217 14911 40218 20078 40218 14912 40218 14912 40219 20078 40219 21096 40219 14912 40220 21096 40220 20079 40220 20079 40221 21100 40221 20080 40221 20080 40222 21100 40222 21102 40222 20080 40223 21102 40223 20081 40223 20081 40224 21102 40224 20082 40224 20081 40225 20082 40225 20075 40225 20350 40226 16146 40226 20084 40226 20350 40227 20084 40227 20356 40227 16137 40228 20083 40228 16136 40228 16136 40229 20083 40229 20270 40229 16136 40230 20270 40230 20691 40230 20691 40231 20270 40231 20089 40231 16137 40232 16140 40232 20083 40232 20083 40233 16140 40233 16142 40233 20083 40234 16142 40234 16145 40234 20084 40235 20687 40235 20356 40235 20356 40236 20687 40236 20688 40236 20356 40237 20688 40237 20262 40237 20262 40238 20688 40238 20085 40238 20262 40239 20085 40239 20086 40239 20086 40240 20085 40240 20087 40240 20086 40241 20087 40241 20089 40241 20089 40242 20087 40242 20088 40242 20089 40243 20088 40243 20691 40243 20520 40244 20090 40244 20092 40244 14902 40245 20109 40245 20111 40245 16271 40246 20665 40246 20090 40246 20090 40247 20665 40247 20091 40247 20090 40248 20091 40248 20092 40248 16159 40249 20093 40249 16160 40249 16160 40250 20093 40250 20362 40250 16160 40251 20362 40251 16162 40251 20111 40252 20520 40252 14902 40252 14902 40253 20520 40253 20092 40253 14902 40254 20092 40254 20094 40254 20092 40255 20095 40255 20094 40255 20094 40256 20095 40256 20096 40256 20094 40257 20096 40257 14897 40257 14897 40258 20096 40258 20662 40258 14897 40259 20662 40259 20661 40259 20097 40260 16191 40260 20356 40260 20355 40261 20357 40261 16188 40261 20261 40262 20098 40262 20262 40262 20262 40263 20098 40263 20602 40263 20262 40264 20602 40264 20356 40264 20356 40265 20602 40265 20099 40265 20356 40266 20099 40266 20097 40266 20355 40267 16188 40267 20066 40267 20066 40268 16188 40268 20606 40268 20066 40269 20606 40269 20100 40269 21183 40270 21182 40270 20061 40270 20061 40271 21182 40271 20066 40271 20061 40272 20066 40272 20103 40272 20103 40273 20066 40273 20100 40273 20103 40274 20100 40274 20101 40274 20101 40275 20102 40275 20103 40275 20103 40276 20102 40276 20104 40276 20103 40277 20104 40277 20263 40277 20105 40278 20093 40278 16271 40278 16271 40279 20093 40279 16159 40279 16271 40280 16159 40280 20665 40280 20365 40281 16268 40281 20364 40281 20364 40282 16268 40282 20106 40282 20364 40283 20106 40283 20107 40283 20107 40284 20106 40284 20511 40284 20513 40285 20515 40285 20108 40285 20108 40286 20515 40286 20516 40286 20108 40287 20516 40287 20109 40287 20109 40288 20516 40288 20110 40288 20109 40289 20110 40289 20111 40289 21371 40290 20139 40290 21372 40290 21372 40291 20139 40291 20025 40291 20142 40292 20140 40292 21368 40292 21368 40293 20112 40293 20113 40293 20113 40294 20112 40294 21367 40294 20113 40295 21367 40295 20337 40295 20337 40296 21367 40296 21365 40296 21365 40297 15568 40297 20337 40297 20337 40298 15568 40298 15570 40298 20337 40299 15570 40299 15571 40299 15571 40300 20114 40300 20335 40300 20335 40301 20114 40301 15573 40301 20335 40302 15573 40302 20025 40302 20025 40303 15573 40303 15575 40303 20025 40304 15575 40304 21372 40304 20495 40305 20279 40305 20378 40305 20128 40306 14900 40306 20127 40306 20127 40307 14900 40307 20279 40307 20127 40308 20279 40308 20126 40308 20126 40309 20279 40309 20495 40309 20116 40310 16286 40310 20115 40310 20116 40311 20115 40311 16282 40311 20117 40312 20118 40312 14896 40312 14896 40313 20118 40313 16170 40313 20041 40314 20119 40314 20120 40314 16286 40315 16287 40315 20633 40315 20633 40316 16287 40316 20629 40316 20117 40317 14896 40317 20637 40317 20637 40318 14896 40318 20115 40318 20637 40319 20115 40319 20121 40319 20120 40320 16174 40320 20041 40320 20041 40321 16174 40321 20629 40321 20041 40322 20629 40322 20122 40322 20122 40323 20629 40323 16287 40323 16282 40324 20115 40324 20123 40324 20123 40325 20115 40325 20128 40325 20123 40326 20128 40326 20129 40326 20633 40327 20124 40327 16286 40327 16286 40328 20124 40328 20634 40328 16286 40329 20634 40329 20115 40329 20115 40330 20634 40330 20125 40330 20115 40331 20125 40331 20121 40331 20126 40332 20499 40332 20127 40332 20127 40333 20499 40333 20500 40333 20127 40334 20500 40334 20128 40334 20128 40335 20500 40335 20502 40335 20128 40336 20502 40336 20129 40336 20138 40337 20130 40337 20137 40337 20137 40338 20130 40338 20131 40338 20137 40339 20131 40339 20136 40339 20138 40340 15995 40340 20130 40340 20130 40341 15995 40341 20821 40341 20130 40342 20821 40342 20376 40342 20376 40343 20821 40343 20374 40343 20132 40344 20295 40344 20816 40344 20374 40345 20819 40345 20375 40345 20375 40346 20819 40346 20133 40346 20375 40347 20133 40347 20295 40347 20295 40348 20133 40348 20817 40348 20295 40349 20817 40349 20816 40349 20816 40350 20814 40350 20132 40350 20132 40351 20814 40351 20134 40351 20132 40352 20134 40352 20136 40352 20134 40353 20135 40353 20136 40353 20136 40354 20135 40354 15999 40354 20136 40355 15999 40355 20137 40355 20137 40356 15999 40356 15997 40356 20137 40357 15997 40357 20138 40357 21371 40358 20140 40358 20139 40358 20139 40359 20140 40359 20142 40359 20139 40360 20142 40360 20141 40360 20141 40361 20142 40361 20152 40361 15767 40362 15764 40362 20142 40362 20142 40363 15764 40363 15763 40363 20142 40364 15763 40364 20152 40364 20152 40365 15763 40365 21135 40365 20152 40366 21135 40366 21134 40366 20383 40367 21077 40367 20113 40367 20113 40368 21077 40368 20143 40368 20113 40369 20143 40369 15811 40369 21368 40370 20113 40370 20142 40370 20142 40371 20113 40371 20155 40371 20142 40372 20155 40372 15767 40372 20245 40373 20246 40373 20144 40373 20144 40374 20246 40374 20147 40374 20145 40375 21074 40375 20383 40375 20383 40376 21074 40376 20146 40376 20383 40377 20146 40377 21077 40377 14916 40378 20151 40378 20147 40378 20147 40379 20151 40379 15807 40379 20147 40380 15807 40380 20144 40380 20150 40381 20149 40381 20148 40381 20150 40382 20148 40382 15810 40382 20149 40383 20150 40383 21132 40383 21132 40384 20150 40384 20151 40384 21132 40385 20151 40385 21134 40385 21134 40386 20151 40386 14916 40386 21134 40387 14916 40387 20152 40387 20148 40388 20153 40388 15810 40388 15810 40389 20153 40389 20154 40389 15810 40390 20154 40390 15811 40390 15811 40391 20154 40391 15769 40391 15811 40392 15769 40392 20113 40392 20113 40393 15769 40393 15768 40393 20113 40394 15768 40394 20155 40394 15587 40395 21346 40395 20325 40395 20164 40396 21421 40396 15593 40396 20156 40397 21342 40397 21420 40397 21420 40398 21342 40398 20157 40398 21420 40399 20157 40399 21421 40399 21421 40400 20157 40400 20158 40400 21421 40401 20158 40401 15593 40401 21417 40402 21415 40402 20212 40402 20212 40403 21415 40403 21414 40403 20212 40404 21414 40404 20159 40404 20159 40405 21414 40405 20160 40405 20159 40406 20160 40406 15542 40406 15592 40407 20161 40407 22820 40407 22820 40408 20161 40408 20162 40408 22820 40409 20162 40409 20163 40409 20163 40410 20162 40410 15588 40410 20163 40411 15588 40411 22817 40411 15593 40412 15592 40412 20164 40412 20164 40413 15592 40413 22820 40413 20164 40414 22820 40414 15538 40414 15538 40415 22820 40415 20166 40415 20306 40416 20165 40416 20166 40416 20166 40417 20165 40417 15539 40417 20166 40418 15539 40418 15538 40418 20917 40419 20916 40419 20167 40419 20167 40420 20916 40420 20915 40420 15940 40421 15937 40421 20308 40421 20308 40422 15937 40422 20168 40422 20308 40423 20168 40423 20432 40423 20168 40424 20169 40424 20432 40424 20432 40425 20169 40425 20170 40425 20432 40426 20170 40426 20917 40426 20039 40427 20172 40427 20171 40427 20171 40428 20172 40428 22822 40428 22822 40429 20172 40429 15941 40429 22822 40430 15941 40430 22823 40430 20206 40431 22826 40431 15949 40431 15949 40432 22826 40432 22825 40432 15949 40433 22825 40433 15950 40433 15950 40434 22825 40434 20173 40434 15950 40435 20173 40435 20178 40435 20174 40436 20175 40436 20026 40436 20176 40437 22828 40437 20823 40437 20823 40438 22828 40438 20026 40438 20823 40439 20026 40439 20824 40439 20824 40440 20026 40440 20175 40440 20176 40441 20177 40441 22828 40441 22828 40442 20177 40442 15992 40442 22828 40443 15992 40443 20173 40443 20173 40444 15992 40444 20180 40444 20178 40445 20173 40445 20179 40445 20179 40446 20173 40446 20180 40446 20179 40447 20180 40447 20888 40447 20888 40448 20180 40448 15990 40448 20888 40449 15990 40449 20889 40449 20889 40450 15990 40450 15989 40450 20889 40451 15989 40451 20181 40451 20181 40452 15989 40452 15988 40452 20181 40453 15988 40453 20892 40453 20892 40454 15988 40454 20828 40454 20892 40455 20828 40455 20390 40455 20390 40456 20828 40456 20827 40456 20390 40457 20827 40457 20174 40457 20389 40458 20182 40458 20388 40458 20183 40459 15976 40459 20040 40459 20040 40460 15976 40460 15974 40460 20303 40461 20426 40461 20844 40461 20039 40462 20171 40462 20040 40462 20040 40463 20171 40463 20188 40463 20040 40464 20188 40464 20183 40464 20915 40465 20184 40465 20167 40465 20167 40466 20184 40466 20040 40466 20167 40467 20040 40467 20185 40467 20185 40468 20040 40468 15974 40468 20303 40469 20844 40469 20301 40469 20301 40470 20844 40470 15979 40470 20301 40471 15979 40471 20187 40471 20187 40472 15979 40472 20186 40472 20187 40473 20186 40473 20188 40473 20188 40474 20186 40474 15978 40474 20188 40475 15978 40475 20183 40475 20185 40476 20189 40476 20167 40476 20167 40477 20189 40477 20839 40477 20167 40478 20839 40478 20190 40478 20190 40479 20839 40479 20841 40479 20190 40480 20841 40480 20427 40480 20191 40481 20204 40481 15987 40481 15987 40482 20192 40482 20191 40482 20191 40483 20192 40483 20832 40483 20191 40484 20832 40484 20415 40484 20415 40485 20832 40485 20833 40485 20415 40486 20833 40486 20193 40486 20199 40487 20194 40487 16245 40487 20196 40488 20539 40488 20198 40488 16244 40489 16243 40489 20304 40489 20304 40490 16243 40490 16240 40490 20304 40491 16240 40491 20204 40491 20204 40492 16240 40492 20544 40492 20195 40493 15980 40493 20037 40493 20037 40494 15980 40494 20196 40494 20037 40495 20196 40495 20197 40495 20197 40496 20196 40496 20198 40496 20197 40497 20198 40497 20199 40497 20199 40498 20198 40498 16248 40498 20199 40499 16248 40499 20194 40499 20196 40500 15983 40500 20539 40500 20539 40501 15983 40501 15985 40501 20539 40502 15985 40502 20200 40502 20200 40503 15985 40503 20201 40503 20200 40504 20201 40504 20202 40504 20202 40505 20201 40505 15987 40505 20202 40506 15987 40506 20203 40506 20203 40507 15987 40507 20204 40507 20203 40508 20204 40508 20543 40508 20543 40509 20204 40509 20544 40509 15946 40510 20415 40510 20205 40510 20205 40511 20415 40511 20193 40511 20205 40512 20193 40512 20206 40512 20206 40513 20193 40513 20837 40513 20206 40514 20837 40514 20038 40514 20038 40515 20837 40515 20836 40515 20038 40516 20836 40516 20195 40516 20207 40517 22816 40517 15605 40517 15605 40518 22816 40518 22815 40518 22814 40519 15598 40519 22815 40519 22815 40520 15598 40520 15602 40520 22815 40521 15602 40521 15605 40521 20419 40522 20209 40522 20321 40522 20321 40523 20209 40523 20208 40523 20321 40524 20208 40524 22814 40524 22814 40525 20208 40525 15597 40525 22814 40526 15597 40526 15598 40526 20219 40527 20218 40527 21340 40527 21340 40528 21338 40528 20420 40528 20420 40529 21338 40529 21337 40529 20420 40530 21337 40530 20419 40530 20419 40531 21337 40531 21336 40531 20419 40532 21336 40532 20209 40532 20325 40533 21346 40533 20210 40533 20210 40534 21346 40534 20211 40534 20210 40535 20211 40535 21344 40535 20156 40536 21417 40536 21342 40536 21342 40537 21417 40537 20212 40537 21342 40538 20212 40538 20213 40538 20213 40539 20212 40539 20430 40539 20213 40540 20430 40540 21344 40540 20207 40541 20214 40541 22816 40541 22816 40542 20214 40542 20215 40542 22816 40543 20215 40543 20216 40543 20216 40544 20215 40544 20217 40544 20215 40545 15555 40545 20217 40545 20217 40546 15555 40546 15553 40546 20217 40547 15553 40547 20224 40547 15557 40548 20214 40548 15559 40548 15559 40549 20214 40549 20218 40549 15559 40550 20218 40550 21394 40550 21394 40551 20218 40551 20219 40551 21394 40552 20219 40552 20220 40552 20220 40553 20219 40553 20416 40553 20220 40554 20416 40554 20398 40554 15607 40555 20221 40555 20222 40555 20222 40556 20221 40556 21333 40556 20222 40557 21333 40557 20223 40557 15553 40558 15551 40558 20224 40558 20224 40559 15551 40559 15550 40559 20224 40560 15550 40560 21396 40560 15614 40561 15613 40561 21396 40561 20223 40562 20225 40562 20399 40562 20399 40563 20225 40563 20226 40563 20399 40564 20226 40564 20398 40564 20398 40565 20226 40565 21329 40565 20398 40566 21329 40566 20227 40566 20227 40567 21329 40567 15614 40567 20227 40568 15614 40568 20228 40568 20228 40569 15614 40569 21396 40569 20229 40570 20230 40570 15608 40570 15608 40571 20230 40571 20224 40571 15608 40572 20224 40572 20231 40572 20231 40573 20224 40573 21396 40573 20231 40574 21396 40574 20232 40574 20232 40575 21396 40575 15613 40575 20366 40576 19999 40576 20367 40576 20367 40577 19999 40577 21588 40577 20367 40578 21588 40578 20035 40578 20034 40579 20368 40579 20233 40579 20233 40580 20368 40580 20234 40580 20233 40581 20234 40581 20235 40581 20401 40582 20003 40582 20236 40582 20236 40583 20003 40583 20237 40583 20236 40584 20237 40584 20372 40584 20372 40585 20237 40585 20238 40585 20372 40586 20238 40586 20235 40586 20439 40587 21551 40587 20239 40587 20422 40588 20240 40588 20006 40588 20006 40589 20240 40589 20241 40589 20006 40590 20241 40590 20008 40590 16355 40591 20414 40591 16357 40591 16357 40592 20414 40592 20389 40592 16357 40593 20389 40593 20033 40593 16362 40594 20242 40594 20394 40594 16362 40595 16361 40595 20242 40595 20242 40596 16361 40596 16358 40596 20242 40597 16358 40597 16357 40597 19996 40598 19994 40598 20243 40598 20243 40599 19994 40599 19993 40599 20243 40600 19993 40600 20394 40600 20394 40601 19993 40601 19991 40601 20394 40602 19991 40602 16362 40602 20361 40603 20345 40603 19997 40603 21587 40604 20032 40604 21511 40604 20244 40605 21512 40605 21511 40605 21512 40606 20244 40606 21505 40606 20245 40607 20145 40607 20246 40607 20246 40608 20145 40608 20383 40608 20246 40609 20383 40609 20247 40609 20247 40610 20383 40610 20253 40610 16209 40611 20249 40611 20248 40611 20248 40612 20249 40612 16210 40612 16210 40613 20249 40613 20250 40613 20250 40614 20249 40614 20411 40614 20250 40615 20411 40615 20575 40615 20253 40616 20581 40616 20247 40616 20247 40617 20581 40617 20579 40617 20247 40618 20579 40618 20030 40618 20030 40619 20579 40619 20577 40619 20030 40620 20577 40620 20411 40620 20411 40621 20577 40621 20251 40621 20411 40622 20251 40622 20575 40622 16208 40623 16207 40623 20383 40623 20383 40624 16207 40624 20252 40624 20383 40625 20252 40625 20253 40625 20371 40626 20258 40626 20080 40626 20359 40627 20254 40627 16214 40627 20258 40628 20255 40628 20080 40628 20080 40629 20255 40629 20256 40629 20080 40630 20256 40630 14912 40630 20568 40631 20567 40631 20360 40631 20567 40632 20565 40632 20360 40632 20360 40633 20565 40633 20257 40633 20360 40634 20257 40634 20359 40634 20359 40635 20257 40635 16215 40635 20359 40636 16215 40636 20254 40636 20258 40637 20259 40637 20255 40637 20255 40638 20259 40638 20571 40638 20255 40639 20571 40639 20260 40639 20260 40640 20571 40640 20570 40640 20260 40641 20570 40641 20569 40641 20569 40642 20568 40642 20260 40642 20260 40643 20568 40643 20360 40643 20260 40644 20360 40644 20052 40644 20052 40645 20360 40645 15778 40645 20052 40646 15778 40646 20053 40646 20104 40647 20261 40647 20263 40647 20263 40648 20261 40648 20262 40648 20263 40649 20262 40649 14906 40649 14906 40650 20262 40650 20086 40650 20270 40651 20526 40651 20524 40651 20270 40652 20524 40652 14903 40652 14903 40653 20524 40653 20264 40653 14903 40654 20264 40654 20265 40654 20265 40655 20264 40655 20266 40655 20265 40656 20266 40656 20029 40656 20029 40657 20266 40657 20522 40657 20029 40658 20522 40658 20268 40658 20522 40659 16264 40659 20268 40659 20268 40660 16264 40660 20267 40660 20268 40661 20267 40661 20348 40661 20083 40662 16262 40662 16261 40662 16261 40663 16260 40663 20083 40663 20083 40664 16260 40664 20269 40664 20083 40665 20269 40665 20270 40665 20270 40666 20269 40666 20271 40666 20270 40667 20271 40667 20526 40667 20511 40668 20513 40668 20107 40668 20107 40669 20513 40669 20108 40669 20107 40670 20108 40670 16197 40670 16197 40671 20108 40671 16198 40671 16197 40672 20272 40672 20107 40672 20107 40673 20272 40673 16196 40673 20107 40674 16196 40674 20268 40674 20268 40675 16196 40675 20601 40675 20268 40676 20601 40676 20600 40676 20273 40677 20274 40677 20594 40677 20594 40678 20275 40678 20273 40678 20273 40679 20275 40679 20592 40679 20273 40680 20592 40680 20108 40680 20108 40681 20592 40681 20276 40681 20108 40682 20276 40682 16198 40682 20600 40683 20599 40683 20268 40683 20268 40684 20599 40684 20277 40684 20268 40685 20277 40685 20274 40685 20274 40686 20277 40686 20596 40686 20274 40687 20596 40687 20594 40687 14900 40688 20278 40688 20279 40688 20279 40689 20278 40689 20280 40689 20279 40690 20280 40690 16202 40690 16201 40691 20281 40691 20282 40691 20282 40692 20281 40692 20283 40692 20282 40693 20283 40693 20386 40693 20386 40694 20283 40694 20589 40694 20386 40695 20589 40695 20286 40695 20284 40696 20285 40696 14898 40696 14898 40697 20285 40697 20386 40697 14898 40698 20386 40698 14899 40698 14899 40699 20386 40699 20286 40699 14899 40700 20286 40700 20588 40700 20588 40701 20585 40701 14899 40701 14899 40702 20585 40702 20287 40702 14899 40703 20287 40703 14900 40703 14900 40704 20287 40704 20582 40704 14900 40705 20582 40705 20028 40705 16170 40706 20119 40706 14896 40706 14896 40707 20119 40707 20041 40707 14896 40708 20041 40708 20288 40708 20288 40709 20041 40709 20292 40709 20289 40710 20041 40710 15963 40710 15963 40711 20041 40711 20375 40711 15963 40712 20375 40712 20290 40712 20291 40713 20292 40713 20293 40713 20293 40714 20292 40714 20041 40714 20293 40715 20041 40715 20294 40715 20294 40716 20041 40716 20289 40716 15959 40717 20295 40717 20296 40717 20296 40718 20295 40718 20292 40718 20296 40719 20292 40719 20868 40719 20868 40720 20292 40720 20291 40720 15959 40721 20297 40721 20295 40721 20295 40722 20297 40722 15960 40722 20295 40723 15960 40723 20375 40723 20375 40724 15960 40724 15966 40724 20375 40725 15966 40725 20290 40725 20131 40726 20027 40726 22829 40726 20027 40727 16255 40727 22829 40727 22829 40728 16255 40728 16254 40728 22829 40729 16254 40729 20026 40729 20026 40730 16254 40730 16251 40730 16251 40731 16250 40731 20026 40731 20026 40732 16250 40732 20536 40732 20026 40733 20536 40733 20384 40733 20536 40734 20298 40734 20384 40734 20384 40735 20298 40735 20299 40735 20384 40736 20299 40736 20534 40736 20534 40737 20532 40737 20130 40737 20130 40738 20532 40738 20529 40738 20130 40739 20529 40739 20131 40739 20131 40740 20529 40740 20300 40740 20131 40741 20300 40741 16258 40741 20301 40742 20302 40742 20303 40742 20303 40743 20302 40743 20199 40743 20303 40744 20199 40744 20304 40744 20304 40745 20199 40745 16245 40745 20304 40746 16245 40746 16244 40746 16239 40747 16237 40747 20309 40747 20309 40748 16237 40748 20305 40748 20309 40749 20305 40749 20314 40749 20314 40750 20305 40750 20312 40750 20314 40751 20159 40751 20306 40751 20306 40752 20159 40752 15542 40752 20306 40753 15542 40753 20165 40753 20307 40754 20546 40754 20308 40754 15941 40755 15940 40755 22823 40755 22823 40756 15940 40756 20308 40756 22823 40757 20308 40757 20309 40757 20309 40758 20308 40758 20546 40758 20309 40759 20546 40759 16239 40759 20310 40760 20437 40760 20159 40760 20437 40761 20549 40761 20308 40761 20308 40762 20549 40762 20311 40762 20308 40763 20311 40763 20307 40763 20312 40764 20313 40764 20314 40764 20314 40765 20313 40765 16234 40765 20314 40766 16234 40766 20159 40766 20159 40767 16234 40767 20315 40767 20159 40768 20315 40768 20310 40768 20419 40769 20324 40769 20418 40769 20418 40770 20552 40770 20316 40770 20316 40771 20552 40771 20317 40771 20316 40772 20317 40772 20210 40772 20210 40773 20317 40773 16233 40773 20318 40774 16229 40774 20319 40774 20319 40775 16229 40775 20321 40775 16233 40776 20320 40776 20210 40776 20210 40777 20320 40777 16231 40777 20210 40778 16231 40778 20327 40778 16229 40779 16227 40779 20321 40779 20321 40780 16227 40780 20322 40780 20321 40781 20322 40781 20419 40781 20419 40782 20322 40782 20323 40782 20419 40783 20323 40783 20324 40783 15588 40784 15587 40784 22817 40784 22817 40785 15587 40785 20325 40785 22817 40786 20325 40786 20326 40786 20326 40787 20325 40787 20210 40787 20326 40788 20210 40788 20319 40788 20319 40789 20210 40789 20327 40789 20319 40790 20327 40790 20318 40790 20328 40791 20560 40791 20338 40791 20328 40792 20338 40792 20331 40792 20560 40793 20558 40793 20380 40793 20558 40794 20557 40794 20380 40794 20380 40795 20557 40795 20555 40795 20380 40796 20555 40796 20222 40796 20555 40797 16225 40797 20222 40797 20222 40798 16225 40798 20329 40798 20222 40799 20329 40799 16224 40799 20229 40800 15607 40800 20230 40800 20230 40801 15607 40801 20222 40801 20230 40802 20222 40802 22812 40802 22812 40803 20222 40803 16224 40803 16224 40804 16221 40804 22812 40804 22812 40805 16221 40805 20330 40805 22812 40806 20330 40806 20332 40806 20332 40807 20330 40807 16218 40807 20332 40808 16218 40808 20563 40808 20563 40809 20331 40809 20332 40809 20332 40810 20331 40810 20338 40810 20332 40811 20338 40811 20342 40811 20342 40812 20338 40812 20333 40812 20342 40813 20333 40813 20340 40813 20337 40814 20334 40814 21323 40814 15571 40815 20335 40815 20337 40815 20337 40816 20335 40816 20336 40816 20337 40817 20336 40817 20334 40817 21323 40818 21322 40818 20337 40818 20337 40819 21322 40819 15619 40819 20337 40820 15619 40820 20338 40820 20338 40821 15619 40821 20339 40821 20338 40822 20339 40822 20333 40822 20340 40823 20341 40823 20342 40823 20342 40824 20341 40824 20343 40824 20342 40825 20343 40825 22810 40825 22810 40826 20343 40826 15616 40826 22810 40827 15616 40827 22811 40827 22811 40828 15616 40828 21327 40828 22811 40829 21327 40829 20335 40829 20335 40830 21327 40830 20344 40830 20335 40831 20344 40831 20336 40831 20345 40832 20361 40832 20346 40832 20346 40833 20361 40833 20363 40833 20346 40834 20363 40834 20032 40834 20032 40835 20363 40835 20364 40835 20032 40836 20364 40836 20349 40836 20349 40837 20364 40837 20107 40837 20349 40838 20107 40838 20347 40838 20347 40839 20107 40839 20268 40839 20347 40840 20268 40840 20083 40840 20083 40841 20268 40841 20348 40841 20083 40842 20348 40842 16262 40842 21511 40843 20032 40843 20244 40843 20244 40844 20032 40844 20349 40844 20244 40845 20349 40845 20351 40845 20351 40846 20349 40846 20347 40846 20351 40847 20347 40847 20352 40847 20352 40848 20347 40848 20083 40848 20352 40849 20083 40849 20350 40849 20350 40850 20083 40850 16145 40850 20350 40851 16145 40851 16146 40851 21505 40852 20244 40852 20036 40852 20036 40853 20244 40853 20351 40853 20036 40854 20351 40854 20358 40854 20358 40855 20351 40855 20352 40855 20358 40856 20352 40856 20353 40856 20353 40857 20352 40857 20350 40857 20353 40858 20350 40858 20354 40858 20354 40859 20350 40859 20356 40859 20354 40860 20356 40860 20355 40860 20355 40861 20356 40861 16191 40861 20355 40862 16191 40862 20357 40862 20035 40863 20036 40863 20367 40863 20367 40864 20036 40864 20358 40864 20367 40865 20358 40865 20370 40865 20370 40866 20358 40866 20353 40866 20370 40867 20353 40867 20359 40867 20359 40868 20353 40868 20354 40868 20359 40869 20354 40869 20360 40869 20360 40870 20354 40870 15784 40870 20360 40871 15784 40871 15781 40871 19996 40872 20243 40872 19997 40872 19997 40873 20243 40873 20395 40873 19997 40874 20395 40874 20361 40874 20361 40875 20395 40875 20362 40875 20361 40876 20362 40876 20363 40876 20363 40877 20362 40877 20093 40877 20363 40878 20093 40878 20364 40878 20364 40879 20093 40879 20105 40879 20364 40880 20105 40880 20365 40880 20034 40881 20366 40881 20368 40881 20368 40882 20366 40882 20367 40882 20368 40883 20367 40883 20369 40883 20369 40884 20367 40884 20370 40884 20369 40885 20370 40885 20081 40885 20081 40886 20370 40886 20359 40886 20081 40887 20359 40887 20080 40887 20080 40888 20359 40888 16214 40888 20080 40889 16214 40889 20371 40889 20235 40890 20234 40890 20372 40890 20372 40891 20234 40891 20368 40891 20372 40892 20368 40892 20405 40892 20405 40893 20368 40893 20369 40893 20405 40894 20369 40894 20406 40894 20406 40895 20369 40895 20081 40895 20406 40896 20081 40896 20373 40896 20373 40897 20081 40897 20076 40897 20373 40898 20076 40898 15790 40898 20374 40899 20375 40899 20376 40899 20376 40900 20375 40900 20041 40900 20376 40901 20041 40901 20378 40901 20378 40902 20041 40902 16289 40902 20378 40903 16289 40903 20495 40903 20534 40904 20130 40904 20384 40904 20384 40905 20130 40905 20376 40905 20384 40906 20376 40906 20377 40906 20377 40907 20376 40907 20378 40907 20377 40908 20378 40908 20379 40908 20379 40909 20378 40909 20279 40909 20379 40910 20279 40910 20282 40910 20282 40911 20279 40911 16202 40911 20282 40912 16202 40912 16201 40912 20560 40913 20380 40913 20338 40913 20338 40914 20380 40914 20381 40914 20338 40915 20381 40915 20337 40915 20337 40916 20381 40916 20382 40916 20337 40917 20382 40917 20113 40917 20113 40918 20382 40918 20249 40918 20113 40919 20249 40919 20383 40919 20383 40920 20249 40920 16209 40920 20383 40921 16209 40921 16208 40921 20174 40922 20026 40922 20390 40922 20390 40923 20026 40923 20384 40923 20390 40924 20384 40924 20391 40924 20391 40925 20384 40925 20377 40925 20391 40926 20377 40926 20392 40926 20392 40927 20377 40927 20379 40927 20392 40928 20379 40928 20393 40928 20393 40929 20379 40929 20282 40929 20393 40930 20282 40930 20385 40930 20385 40931 20282 40931 20386 40931 20385 40932 20386 40932 20387 40932 20387 40933 20386 40933 16275 40933 20387 40934 16275 40934 16277 40934 20388 40935 20390 40935 20389 40935 20389 40936 20390 40936 20391 40936 20389 40937 20391 40937 20033 40937 20033 40938 20391 40938 20392 40938 20033 40939 20392 40939 20242 40939 20242 40940 20392 40940 20393 40940 20242 40941 20393 40941 20394 40941 20394 40942 20393 40942 20385 40942 20394 40943 20385 40943 20243 40943 20243 40944 20385 40944 20387 40944 20243 40945 20387 40945 20395 40945 20395 40946 20387 40946 20396 40946 20395 40947 20396 40947 20362 40947 20362 40948 20396 40948 20397 40948 20362 40949 20397 40949 16162 40949 20398 40950 20416 40950 20399 40950 20399 40951 20416 40951 20400 40951 20399 40952 20400 40952 20409 40952 20409 40953 20400 40953 20401 40953 20409 40954 20401 40954 20402 40954 20402 40955 20401 40955 20236 40955 20402 40956 20236 40956 20410 40956 20410 40957 20236 40957 20372 40957 20410 40958 20372 40958 20403 40958 20403 40959 20372 40959 20405 40959 20403 40960 20405 40960 20404 40960 20404 40961 20405 40961 20406 40961 20404 40962 20406 40962 20048 40962 20048 40963 20406 40963 20407 40963 20048 40964 20407 40964 20408 40964 20223 40965 20399 40965 20222 40965 20222 40966 20399 40966 20409 40966 20222 40967 20409 40967 20380 40967 20380 40968 20409 40968 20402 40968 20380 40969 20402 40969 20381 40969 20381 40970 20402 40970 20410 40970 20381 40971 20410 40971 20382 40971 20382 40972 20410 40972 20403 40972 20382 40973 20403 40973 20249 40973 20249 40974 20403 40974 20404 40974 20249 40975 20404 40975 20411 40975 20411 40976 20404 40976 15798 40976 20411 40977 15798 40977 20412 40977 16355 40978 20413 40978 20414 40978 20414 40979 20413 40979 20191 40979 20414 40980 20191 40980 20389 40980 20389 40981 20191 40981 20415 40981 20389 40982 20415 40982 20182 40982 20182 40983 20415 40983 15946 40983 21340 40984 20420 40984 20219 40984 20219 40985 20420 40985 20421 40985 20219 40986 20421 40986 20416 40986 20416 40987 20421 40987 20423 40987 20416 40988 20423 40988 20400 40988 20400 40989 20423 40989 20425 40989 20400 40990 20425 40990 20401 40990 20401 40991 20425 40991 20417 40991 20401 40992 20417 40992 20003 40992 20418 40993 20316 40993 20419 40993 20419 40994 20316 40994 20241 40994 20419 40995 20241 40995 20420 40995 20420 40996 20241 40996 20240 40996 20420 40997 20240 40997 20421 40997 20421 40998 20240 40998 20422 40998 20421 40999 20422 40999 20423 40999 20423 41000 20422 41000 20424 41000 20423 41001 20424 41001 20425 41001 20426 41002 20303 41002 20427 41002 20427 41003 20303 41003 20304 41003 20427 41004 20304 41004 20190 41004 20190 41005 20304 41005 20204 41005 20190 41006 20204 41006 20428 41006 20428 41007 20204 41007 20191 41007 20428 41008 20191 41008 20434 41008 20434 41009 20191 41009 20413 41009 20434 41010 20413 41010 20429 41010 21344 41011 20430 41011 20210 41011 20210 41012 20430 41012 20431 41012 20210 41013 20431 41013 20316 41013 20316 41014 20431 41014 20439 41014 20316 41015 20439 41015 20241 41015 20241 41016 20439 41016 20239 41016 20241 41017 20239 41017 20008 41017 20917 41018 20167 41018 20432 41018 20432 41019 20167 41019 20190 41019 20432 41020 20190 41020 20438 41020 20438 41021 20190 41021 20428 41021 20438 41022 20428 41022 20433 41022 20433 41023 20428 41023 20434 41023 20433 41024 20434 41024 20435 41024 20435 41025 20434 41025 20429 41025 20435 41026 20429 41026 20436 41026 20437 41027 20308 41027 20159 41027 20159 41028 20308 41028 20432 41028 20159 41029 20432 41029 20212 41029 20212 41030 20432 41030 20438 41030 20212 41031 20438 41031 20430 41031 20430 41032 20438 41032 20433 41032 20430 41033 20433 41033 20431 41033 20431 41034 20433 41034 20435 41034 20431 41035 20435 41035 20439 41035 20439 41036 20435 41036 21556 41036 20439 41037 21556 41037 21551 41037 20496 41038 16345 41038 20497 41038 20497 41039 16345 41039 20448 41039 20497 41040 20448 41040 20498 41040 20498 41041 20448 41041 20440 41041 20440 41042 20448 41042 20449 41042 20440 41043 20449 41043 20441 41043 20441 41044 20449 41044 20501 41044 20501 41045 20449 41045 20442 41045 20501 41046 20442 41046 20443 41046 20443 41047 20442 41047 20444 41047 20444 41048 20442 41048 20445 41048 20444 41049 20445 41049 20503 41049 20503 41050 20445 41050 20505 41050 20505 41051 20445 41051 20447 41051 20505 41052 20447 41052 20446 41052 20446 41053 20447 41053 20504 41053 20504 41054 20447 41054 20452 41054 20504 41055 20452 41055 16283 41055 16345 41056 17860 41056 20448 41056 20448 41057 17860 41057 17859 41057 20448 41058 17859 41058 20449 41058 20449 41059 17859 41059 20450 41059 20449 41060 20450 41060 20442 41060 20442 41061 20450 41061 17857 41061 20442 41062 17857 41062 20445 41062 20445 41063 17857 41063 20451 41063 20445 41064 20451 41064 20447 41064 20447 41065 20451 41065 17855 41065 20447 41066 17855 41066 20452 41066 20452 41067 17855 41067 17854 41067 20453 41068 16315 41068 20454 41068 20454 41069 16315 41069 20460 41069 20454 41070 20460 41070 20507 41070 20507 41071 20460 41071 20462 41071 20507 41072 20462 41072 20455 41072 20455 41073 20462 41073 20463 41073 20455 41074 20463 41074 20456 41074 20456 41075 20463 41075 20464 41075 20456 41076 20464 41076 20457 41076 20457 41077 20464 41077 20458 41077 20457 41078 20458 41078 20459 41078 20459 41079 20458 41079 16322 41079 16315 41080 17843 41080 20460 41080 20460 41081 17843 41081 17845 41081 20460 41082 17845 41082 20462 41082 20462 41083 17845 41083 20461 41083 20462 41084 20461 41084 20463 41084 20463 41085 20461 41085 17847 41085 20463 41086 17847 41086 20464 41086 20464 41087 17847 41087 17848 41087 20464 41088 17848 41088 20458 41088 20458 41089 17848 41089 17850 41089 20458 41090 17850 41090 16322 41090 16322 41091 17850 41091 16323 41091 16266 41092 16314 41092 20465 41092 20465 41093 16314 41093 20466 41093 20465 41094 20466 41094 20512 41094 20512 41095 20466 41095 20467 41095 20512 41096 20467 41096 20468 41096 20468 41097 20467 41097 20482 41097 20468 41098 20482 41098 20469 41098 20469 41099 20482 41099 20470 41099 20469 41100 20470 41100 20514 41100 20514 41101 20470 41101 20472 41101 20514 41102 20472 41102 20471 41102 20471 41103 20472 41103 20481 41103 20471 41104 20481 41104 20517 41104 20517 41105 20481 41105 20473 41105 20517 41106 20473 41106 20518 41106 20518 41107 20473 41107 20474 41107 20518 41108 20474 41108 20519 41108 20519 41109 20474 41109 20475 41109 20519 41110 20475 41110 20476 41110 20476 41111 20475 41111 20477 41111 20476 41112 20477 41112 20479 41112 20479 41113 20477 41113 20478 41113 20479 41114 20478 41114 20480 41114 20480 41115 20478 41115 16308 41115 17822 41116 16304 41116 16308 41116 16308 41117 20478 41117 17822 41117 17822 41118 20478 41118 20477 41118 17822 41119 20477 41119 17823 41119 20477 41120 20475 41120 17823 41120 17823 41121 20475 41121 20474 41121 17823 41122 20474 41122 17825 41122 17825 41123 20474 41123 20473 41123 17825 41124 20473 41124 17828 41124 20473 41125 20481 41125 17828 41125 17828 41126 20481 41126 20472 41126 17828 41127 20472 41127 20483 41127 20472 41128 20470 41128 20483 41128 20483 41129 20470 41129 20482 41129 20483 41130 20482 41130 17829 41130 16314 41131 17830 41131 20466 41131 20466 41132 17830 41132 17829 41132 20466 41133 17829 41133 20467 41133 20467 41134 17829 41134 20482 41134 20528 41135 20490 41135 20527 41135 20527 41136 20490 41136 20484 41136 20527 41137 20484 41137 20525 41137 20525 41138 20484 41138 20485 41138 20525 41139 20485 41139 20486 41139 20486 41140 20485 41140 20487 41140 20486 41141 20487 41141 20523 41141 20523 41142 20487 41142 20493 41142 20523 41143 20493 41143 20521 41143 20521 41144 20493 41144 20488 41144 20521 41145 20488 41145 20489 41145 20489 41146 20488 41146 16298 41146 20490 41147 17818 41147 20484 41147 20484 41148 17818 41148 17817 41148 20484 41149 17817 41149 20485 41149 20485 41150 17817 41150 20491 41150 20485 41151 20491 41151 20487 41151 20487 41152 20491 41152 20492 41152 20487 41153 20492 41153 20493 41153 20493 41154 20492 41154 20494 41154 20493 41155 20494 41155 20488 41155 20488 41156 20494 41156 17814 41156 20488 41157 17814 41157 16298 41157 16298 41158 17814 41158 17813 41158 20126 41159 20495 41159 20496 41159 20496 41160 20497 41160 20126 41160 20126 41161 20497 41161 20498 41161 20126 41162 20498 41162 20499 41162 20498 41163 20440 41163 20499 41163 20499 41164 20440 41164 20441 41164 20499 41165 20441 41165 20500 41165 20500 41166 20441 41166 20501 41166 20500 41167 20501 41167 20502 41167 20501 41168 20443 41168 20502 41168 20502 41169 20443 41169 20444 41169 20502 41170 20444 41170 20129 41170 20444 41171 20503 41171 20129 41171 20129 41172 20503 41172 20505 41172 20129 41173 20505 41173 20123 41173 16283 41174 16282 41174 20504 41174 20504 41175 16282 41175 20123 41175 20504 41176 20123 41176 20446 41176 20446 41177 20123 41177 20505 41177 20459 41178 20285 41178 20457 41178 20457 41179 20285 41179 20284 41179 20457 41180 20284 41180 20456 41180 20456 41181 20284 41181 20506 41181 20456 41182 20506 41182 20455 41182 20455 41183 20506 41183 20508 41183 20455 41184 20508 41184 20507 41184 20507 41185 20508 41185 20509 41185 20507 41186 20509 41186 20454 41186 20454 41187 20509 41187 20510 41187 20454 41188 20510 41188 20453 41188 20453 41189 20510 41189 16281 41189 20511 41190 20106 41190 16266 41190 16266 41191 20465 41191 20511 41191 20511 41192 20465 41192 20512 41192 20511 41193 20512 41193 20513 41193 20512 41194 20468 41194 20513 41194 20513 41195 20468 41195 20469 41195 20513 41196 20469 41196 20515 41196 20469 41197 20514 41197 20515 41197 20515 41198 20514 41198 20471 41198 20515 41199 20471 41199 20516 41199 20516 41200 20471 41200 20517 41200 20516 41201 20517 41201 20110 41201 20517 41202 20518 41202 20110 41202 20110 41203 20518 41203 20519 41203 20110 41204 20519 41204 20111 41204 20480 41205 20520 41205 20479 41205 20479 41206 20520 41206 20111 41206 20479 41207 20111 41207 20476 41207 20476 41208 20111 41208 20519 41208 20489 41209 20522 41209 20521 41209 20521 41210 20522 41210 20266 41210 20521 41211 20266 41211 20523 41211 20523 41212 20266 41212 20264 41212 20523 41213 20264 41213 20486 41213 20486 41214 20264 41214 20524 41214 20486 41215 20524 41215 20525 41215 20525 41216 20524 41216 20526 41216 20525 41217 20526 41217 20527 41217 20527 41218 20526 41218 20271 41218 20527 41219 20271 41219 20528 41219 20528 41220 20271 41220 20269 41220 16257 41221 16258 41221 22975 41221 22975 41222 16258 41222 20300 41222 22975 41223 20300 41223 22977 41223 22977 41224 20300 41224 20529 41224 22977 41225 20529 41225 20530 41225 20530 41226 20529 41226 20532 41226 20530 41227 20532 41227 20531 41227 20531 41228 20532 41228 20534 41228 20531 41229 20534 41229 20533 41229 20533 41230 20534 41230 20299 41230 20533 41231 20299 41231 20535 41231 20535 41232 20299 41232 20298 41232 20535 41233 20298 41233 16249 41233 16249 41234 20298 41234 20536 41234 20537 41235 20198 41235 20538 41235 20538 41236 20198 41236 20539 41236 20538 41237 20539 41237 20540 41237 20540 41238 20539 41238 20200 41238 20540 41239 20200 41239 20541 41239 20541 41240 20200 41240 20202 41240 20541 41241 20202 41241 20542 41241 20542 41242 20202 41242 20203 41242 20542 41243 20203 41243 22973 41243 22973 41244 20203 41244 20543 41244 22973 41245 20543 41245 22972 41245 22972 41246 20543 41246 20544 41246 22972 41247 20544 41247 22971 41247 22971 41248 20544 41248 16240 41248 22966 41249 20546 41249 20545 41249 20545 41250 20546 41250 20307 41250 20545 41251 20307 41251 20547 41251 20547 41252 20307 41252 20311 41252 20547 41253 20311 41253 22967 41253 22967 41254 20311 41254 20549 41254 22967 41255 20549 41255 20548 41255 20548 41256 20549 41256 20437 41256 20548 41257 20437 41257 20550 41257 20550 41258 20437 41258 20310 41258 20550 41259 20310 41259 22969 41259 22969 41260 20310 41260 20315 41260 22969 41261 20315 41261 20551 41261 20551 41262 20315 41262 16234 41262 22960 41263 16233 41263 22961 41263 22961 41264 16233 41264 20317 41264 22961 41265 20317 41265 22964 41265 22964 41266 20317 41266 20552 41266 22964 41267 20552 41267 20553 41267 20553 41268 20552 41268 20418 41268 20553 41269 20418 41269 22958 41269 22958 41270 20418 41270 20324 41270 22958 41271 20324 41271 22959 41271 22959 41272 20324 41272 20323 41272 22959 41273 20323 41273 20554 41273 20554 41274 20323 41274 20322 41274 22954 41275 20555 41275 20556 41275 20556 41276 20555 41276 20557 41276 20556 41277 20557 41277 22956 41277 22956 41278 20557 41278 20558 41278 22956 41279 20558 41279 20559 41279 20559 41280 20558 41280 20560 41280 20559 41281 20560 41281 20561 41281 20561 41282 20560 41282 20328 41282 20561 41283 20328 41283 22957 41283 22957 41284 20328 41284 20331 41284 22957 41285 20331 41285 20562 41285 20562 41286 20331 41286 20563 41286 16216 41287 20257 41287 20564 41287 20564 41288 20257 41288 20565 41288 20564 41289 20565 41289 20566 41289 20566 41290 20565 41290 20567 41290 20566 41291 20567 41291 22948 41291 22948 41292 20567 41292 20568 41292 22948 41293 20568 41293 22949 41293 22949 41294 20568 41294 20569 41294 22949 41295 20569 41295 22953 41295 22953 41296 20569 41296 20570 41296 22953 41297 20570 41297 22952 41297 22952 41298 20570 41298 20571 41298 22952 41299 20571 41299 20572 41299 20572 41300 20571 41300 20259 41300 20573 41301 20250 41301 20574 41301 20574 41302 20250 41302 20575 41302 20574 41303 20575 41303 22946 41303 22946 41304 20575 41304 20251 41304 22946 41305 20251 41305 20576 41305 20576 41306 20251 41306 20577 41306 20576 41307 20577 41307 20578 41307 20578 41308 20577 41308 20579 41308 20578 41309 20579 41309 20580 41309 20580 41310 20579 41310 20581 41310 20580 41311 20581 41311 22947 41311 22947 41312 20581 41312 20253 41312 16205 41313 20028 41313 22938 41313 22938 41314 20028 41314 20582 41314 22938 41315 20582 41315 20583 41315 20583 41316 20582 41316 20287 41316 20583 41317 20287 41317 20584 41317 20584 41318 20287 41318 20585 41318 20584 41319 20585 41319 20586 41319 20586 41320 20585 41320 20588 41320 20586 41321 20588 41321 20587 41321 20587 41322 20588 41322 20286 41322 20587 41323 20286 41323 20590 41323 20590 41324 20286 41324 20589 41324 20590 41325 20589 41325 20591 41325 20591 41326 20589 41326 20283 41326 16199 41327 20592 41327 22933 41327 22933 41328 20592 41328 20275 41328 22933 41329 20275 41329 20593 41329 20593 41330 20275 41330 20594 41330 20593 41331 20594 41331 20595 41331 20595 41332 20594 41332 20596 41332 20595 41333 20596 41333 20597 41333 20597 41334 20596 41334 20277 41334 20597 41335 20277 41335 20598 41335 20598 41336 20277 41336 20599 41336 20598 41337 20599 41337 22931 41337 22931 41338 20599 41338 20600 41338 22931 41339 20600 41339 22937 41339 22937 41340 20600 41340 20601 41340 16194 41341 20602 41341 22929 41341 22929 41342 20602 41342 20098 41342 22929 41343 20098 41343 20603 41343 20603 41344 20098 41344 20261 41344 20603 41345 20261 41345 20604 41345 20604 41346 20261 41346 20104 41346 20604 41347 20104 41347 22928 41347 22928 41348 20104 41348 20102 41348 22928 41349 20102 41349 22927 41349 22927 41350 20102 41350 20101 41350 22927 41351 20101 41351 20605 41351 20605 41352 20101 41352 20100 41352 20605 41353 20100 41353 22930 41353 22930 41354 20100 41354 20606 41354 20616 41355 16178 41355 16133 41355 16133 41356 16178 41356 16179 41356 16133 41357 16179 41357 20607 41357 20607 41358 16179 41358 20608 41358 20607 41359 20608 41359 16130 41359 16130 41360 20608 41360 16184 41360 16130 41361 16184 41361 20609 41361 20609 41362 16184 41362 16186 41362 20609 41363 16186 41363 20610 41363 20610 41364 16186 41364 20618 41364 20610 41365 20618 41365 20611 41365 20611 41366 20618 41366 20620 41366 20611 41367 20620 41367 20612 41367 20612 41368 20620 41368 20623 41368 20612 41369 20623 41369 20613 41369 20613 41370 20623 41370 20625 41370 20613 41371 20625 41371 20695 41371 20695 41372 20625 41372 20628 41372 20695 41373 20628 41373 16135 41373 16135 41374 20628 41374 20627 41374 16135 41375 20627 41375 20614 41375 20614 41376 20627 41376 16175 41376 20614 41377 16175 41377 20615 41377 20615 41378 16175 41378 20617 41378 20615 41379 20617 41379 20616 41379 20616 41380 20617 41380 16178 41380 16185 41381 20638 41381 16186 41381 16186 41382 20638 41382 20618 41382 20638 41383 20639 41383 20618 41383 20618 41384 20639 41384 20619 41384 20618 41385 20619 41385 20620 41385 20619 41386 20621 41386 20620 41386 20620 41387 20621 41387 20636 41387 20620 41388 20636 41388 20623 41388 20636 41389 20635 41389 20623 41389 20623 41390 20635 41390 20622 41390 20623 41391 20622 41391 20625 41391 20622 41392 20624 41392 20625 41392 20625 41393 20624 41393 20626 41393 20625 41394 20626 41394 20628 41394 20630 41395 20627 41395 20631 41395 20631 41396 20627 41396 20628 41396 20631 41397 20628 41397 20632 41397 20632 41398 20628 41398 20626 41398 20633 41399 20629 41399 20630 41399 20630 41400 20631 41400 20633 41400 20633 41401 20631 41401 20632 41401 20633 41402 20632 41402 20124 41402 20632 41403 20626 41403 20124 41403 20124 41404 20626 41404 20624 41404 20124 41405 20624 41405 20634 41405 20624 41406 20622 41406 20634 41406 20634 41407 20622 41407 20635 41407 20634 41408 20635 41408 20125 41408 20125 41409 20635 41409 20636 41409 20125 41410 20636 41410 20121 41410 20636 41411 20621 41411 20121 41411 20121 41412 20621 41412 20619 41412 20121 41413 20619 41413 20637 41413 16185 41414 20117 41414 20638 41414 20638 41415 20117 41415 20637 41415 20638 41416 20637 41416 20639 41416 20639 41417 20637 41417 20619 41417 20712 41418 20657 41418 20714 41418 20714 41419 20657 41419 20658 41419 20714 41420 20658 41420 20640 41420 20640 41421 20658 41421 20641 41421 20640 41422 20641 41422 20717 41422 20717 41423 20641 41423 20659 41423 20717 41424 20659 41424 16106 41424 16106 41425 20659 41425 20642 41425 16106 41426 20642 41426 20643 41426 20643 41427 20642 41427 20644 41427 20643 41428 20644 41428 16105 41428 16105 41429 20644 41429 20645 41429 16105 41430 20645 41430 16104 41430 16104 41431 20645 41431 20647 41431 16104 41432 20647 41432 20646 41432 20646 41433 20647 41433 20648 41433 20646 41434 20648 41434 20708 41434 20708 41435 20648 41435 20651 41435 20708 41436 20651 41436 20710 41436 20710 41437 20651 41437 20652 41437 20710 41438 20652 41438 20649 41438 20649 41439 20652 41439 20650 41439 20649 41440 20650 41440 20712 41440 20712 41441 20650 41441 20655 41441 20712 41442 20655 41442 20657 41442 20651 41443 16169 41443 20652 41443 20652 41444 16169 41444 20653 41444 20652 41445 20653 41445 20650 41445 20650 41446 20653 41446 20654 41446 20650 41447 20654 41447 20655 41447 20655 41448 20654 41448 20663 41448 20655 41449 20663 41449 20657 41449 20657 41450 20663 41450 20656 41450 20657 41451 20656 41451 20658 41451 20658 41452 20656 41452 20664 41452 20658 41453 20664 41453 20641 41453 20641 41454 20664 41454 20660 41454 20641 41455 20660 41455 20659 41455 20659 41456 20660 41456 16166 41456 16169 41457 20661 41457 20653 41457 20653 41458 20661 41458 20662 41458 20653 41459 20662 41459 20654 41459 20654 41460 20662 41460 20096 41460 20654 41461 20096 41461 20663 41461 20663 41462 20096 41462 20095 41462 20663 41463 20095 41463 20656 41463 20656 41464 20095 41464 20092 41464 20656 41465 20092 41465 20664 41465 20664 41466 20092 41466 20091 41466 20664 41467 20091 41467 20660 41467 20660 41468 20091 41468 20665 41468 20660 41469 20665 41469 16166 41469 16166 41470 20665 41470 16159 41470 20674 41471 20677 41471 20666 41471 20666 41472 20677 41472 20678 41472 20666 41473 20678 41473 20728 41473 20728 41474 20678 41474 20667 41474 20728 41475 20667 41475 20668 41475 20668 41476 20667 41476 20683 41476 20668 41477 20683 41477 20669 41477 20669 41478 20683 41478 20686 41478 20669 41479 20686 41479 20670 41479 20670 41480 20686 41480 20671 41480 20670 41481 20671 41481 16073 41481 16073 41482 20671 41482 16150 41482 16073 41483 16150 41483 16075 41483 16075 41484 16150 41484 16151 41484 16075 41485 16151 41485 16076 41485 16076 41486 16151 41486 16154 41486 16076 41487 16154 41487 16078 41487 16078 41488 16154 41488 20672 41488 16078 41489 20672 41489 16079 41489 16079 41490 20672 41490 20673 41490 16079 41491 20673 41491 16081 41491 16081 41492 20673 41492 16158 41492 16081 41493 16158 41493 16082 41493 16082 41494 16158 41494 20676 41494 16082 41495 20676 41495 20674 41495 20674 41496 20676 41496 20677 41496 20676 41497 16156 41497 20675 41497 20676 41498 20675 41498 20677 41498 20677 41499 20675 41499 20679 41499 20677 41500 20679 41500 20678 41500 20678 41501 20679 41501 20680 41501 20678 41502 20680 41502 20667 41502 20680 41503 20690 41503 20667 41503 20667 41504 20690 41504 20681 41504 20667 41505 20681 41505 20683 41505 20681 41506 20682 41506 20683 41506 20683 41507 20682 41507 20684 41507 20683 41508 20684 41508 20686 41508 20684 41509 20685 41509 20686 41509 20686 41510 20685 41510 20689 41510 20686 41511 20689 41511 20671 41511 20671 41512 20689 41512 16149 41512 20671 41513 16149 41513 16150 41513 20687 41514 16149 41514 20688 41514 20688 41515 16149 41515 20689 41515 20688 41516 20689 41516 20085 41516 20689 41517 20685 41517 20085 41517 20085 41518 20685 41518 20684 41518 20085 41519 20684 41519 20087 41519 20087 41520 20684 41520 20682 41520 20682 41521 20681 41521 20087 41521 20087 41522 20681 41522 20690 41522 20087 41523 20690 41523 20088 41523 16156 41524 16136 41524 20675 41524 20675 41525 16136 41525 20691 41525 20675 41526 20691 41526 20679 41526 20679 41527 20691 41527 20088 41527 20679 41528 20088 41528 20680 41528 20680 41529 20088 41529 20690 41529 20701 41530 20609 41530 20692 41530 20692 41531 20609 41531 20610 41531 20692 41532 20610 41532 20700 41532 20700 41533 20610 41533 20611 41533 20700 41534 20611 41534 20693 41534 20693 41535 20611 41535 20612 41535 20693 41536 20612 41536 20698 41536 20698 41537 20612 41537 20613 41537 20698 41538 20613 41538 20694 41538 20694 41539 20613 41539 20695 41539 20694 41540 20695 41540 16120 41540 16120 41541 20695 41541 16135 41541 16120 41542 20696 41542 20694 41542 20694 41543 20696 41543 20697 41543 20694 41544 20697 41544 20698 41544 20698 41545 20697 41545 20702 41545 20698 41546 20702 41546 20693 41546 20693 41547 20702 41547 20699 41547 20693 41548 20699 41548 20700 41548 20700 41549 20699 41549 20704 41549 20700 41550 20704 41550 20692 41550 20692 41551 20704 41551 20706 41551 20692 41552 20706 41552 20701 41552 20701 41553 20706 41553 20707 41553 20696 41554 17875 41554 20697 41554 20697 41555 17875 41555 17873 41555 20697 41556 17873 41556 20702 41556 20702 41557 17873 41557 17871 41557 20702 41558 17871 41558 20699 41558 20699 41559 17871 41559 20703 41559 20699 41560 20703 41560 20704 41560 20704 41561 20703 41561 20705 41561 20704 41562 20705 41562 20706 41562 20706 41563 20705 41563 17870 41563 20706 41564 17870 41564 20707 41564 20707 41565 17870 41565 16117 41565 20722 41566 20708 41566 20709 41566 20709 41567 20708 41567 20710 41567 20709 41568 20710 41568 20719 41568 20719 41569 20710 41569 20649 41569 20719 41570 20649 41570 20711 41570 20711 41571 20649 41571 20712 41571 20711 41572 20712 41572 20713 41572 20713 41573 20712 41573 20714 41573 20713 41574 20714 41574 20715 41574 20715 41575 20714 41575 20640 41575 20715 41576 20640 41576 20716 41576 20716 41577 20640 41577 20717 41577 20716 41578 20718 41578 20715 41578 20715 41579 20718 41579 20723 41579 20715 41580 20723 41580 20713 41580 20713 41581 20723 41581 20724 41581 20713 41582 20724 41582 20711 41582 20711 41583 20724 41583 20725 41583 20711 41584 20725 41584 20719 41584 20719 41585 20725 41585 20720 41585 20719 41586 20720 41586 20709 41586 20709 41587 20720 41587 20721 41587 20709 41588 20721 41588 20722 41588 20722 41589 20721 41589 20727 41589 20718 41590 17803 41590 20723 41590 20723 41591 17803 41591 17802 41591 20723 41592 17802 41592 20724 41592 20724 41593 17802 41593 17800 41593 20724 41594 17800 41594 20725 41594 20725 41595 17800 41595 17799 41595 20725 41596 17799 41596 20720 41596 20720 41597 17799 41597 20726 41597 20720 41598 20726 41598 20721 41598 20721 41599 20726 41599 17797 41599 20721 41600 17797 41600 20727 41600 20727 41601 17797 41601 17796 41601 20738 41602 16082 41602 20736 41602 20736 41603 16082 41603 20674 41603 20736 41604 20674 41604 20735 41604 20735 41605 20674 41605 20666 41605 20735 41606 20666 41606 20729 41606 20729 41607 20666 41607 20728 41607 20729 41608 20728 41608 20734 41608 20734 41609 20728 41609 20668 41609 20734 41610 20668 41610 20731 41610 20731 41611 20668 41611 20669 41611 20731 41612 20669 41612 20730 41612 20730 41613 20669 41613 20670 41613 20730 41614 20670 41614 16072 41614 16072 41615 20670 41615 16073 41615 16072 41616 16067 41616 20730 41616 20730 41617 16067 41617 20739 41617 20730 41618 20739 41618 20731 41618 20731 41619 20739 41619 20732 41619 20731 41620 20732 41620 20734 41620 20734 41621 20732 41621 20733 41621 20734 41622 20733 41622 20729 41622 20729 41623 20733 41623 20740 41623 20729 41624 20740 41624 20735 41624 20735 41625 20740 41625 20737 41625 20735 41626 20737 41626 20736 41626 20736 41627 20737 41627 20742 41627 20736 41628 20742 41628 20738 41628 20738 41629 20742 41629 16068 41629 16067 41630 17780 41630 20739 41630 20739 41631 17780 41631 17779 41631 20739 41632 17779 41632 20732 41632 20732 41633 17779 41633 17777 41633 20732 41634 17777 41634 20733 41634 20733 41635 17777 41635 17776 41635 20733 41636 17776 41636 20740 41636 20740 41637 17776 41637 17774 41637 20740 41638 17774 41638 20737 41638 20737 41639 17774 41639 20741 41639 20737 41640 20741 41640 20742 41640 20742 41641 20741 41641 17790 41641 20742 41642 17790 41642 16068 41642 16068 41643 17790 41643 20743 41643 20760 41644 20762 41644 15994 41644 15994 41645 20762 41645 20820 41645 20762 41646 20744 41646 20820 41646 20820 41647 20744 41647 20764 41647 20820 41648 20764 41648 20745 41648 20764 41649 20746 41649 20745 41649 20745 41650 20746 41650 20747 41650 20745 41651 20747 41651 20818 41651 20747 41652 20758 41652 20818 41652 20818 41653 20758 41653 20757 41653 20818 41654 20757 41654 20748 41654 20757 41655 20755 41655 20748 41655 20748 41656 20755 41656 20749 41656 20748 41657 20749 41657 20815 41657 20751 41658 16001 41658 20750 41658 20750 41659 16001 41659 20815 41659 20750 41660 20815 41660 20753 41660 20753 41661 20815 41661 20749 41661 20752 41662 17890 41662 20751 41662 20751 41663 20750 41663 20752 41663 20752 41664 20750 41664 20753 41664 20752 41665 20753 41665 20754 41665 20753 41666 20749 41666 20754 41666 20754 41667 20749 41667 20755 41667 20754 41668 20755 41668 20756 41668 20756 41669 20755 41669 20757 41669 20756 41670 20757 41670 20759 41670 20757 41671 20758 41671 20759 41671 20759 41672 20758 41672 20747 41672 20759 41673 20747 41673 17883 41673 20747 41674 20746 41674 17883 41674 17883 41675 20746 41675 20764 41675 17883 41676 20764 41676 20763 41676 20760 41677 20761 41677 20762 41677 20762 41678 20761 41678 20763 41678 20762 41679 20763 41679 20744 41679 20744 41680 20763 41680 20764 41680 20765 41681 16045 41681 20826 41681 20826 41682 16045 41682 20767 41682 20826 41683 20767 41683 20766 41683 20766 41684 20767 41684 20770 41684 20766 41685 20770 41685 20825 41685 20825 41686 20770 41686 20772 41686 20825 41687 20772 41687 20768 41687 20768 41688 20772 41688 20769 41688 20768 41689 20769 41689 20822 41689 20822 41690 20769 41690 20775 41690 20822 41691 20775 41691 15993 41691 15993 41692 20775 41692 20776 41692 16045 41693 17900 41693 20767 41693 20767 41694 17900 41694 17898 41694 20767 41695 17898 41695 20770 41695 20770 41696 17898 41696 20771 41696 20770 41697 20771 41697 20772 41697 20772 41698 20771 41698 20773 41698 20772 41699 20773 41699 20769 41699 20769 41700 20773 41700 20774 41700 20769 41701 20774 41701 20775 41701 20775 41702 20774 41702 20777 41702 20775 41703 20777 41703 20776 41703 20776 41704 20777 41704 16030 41704 20829 41705 16029 41705 20786 41705 20829 41706 20786 41706 20778 41706 20778 41707 20786 41707 20779 41707 20778 41708 20779 41708 20830 41708 20830 41709 20779 41709 20831 41709 20831 41710 20779 41710 20780 41710 20831 41711 20780 41711 20834 41711 20834 41712 20780 41712 20835 41712 20835 41713 20780 41713 20789 41713 20835 41714 20789 41714 20838 41714 20838 41715 20789 41715 20781 41715 20781 41716 20789 41716 20782 41716 20781 41717 20782 41717 20783 41717 20783 41718 20782 41718 20790 41718 20783 41719 20790 41719 20784 41719 20784 41720 20790 41720 16015 41720 20784 41721 16015 41721 20785 41721 16029 41722 17905 41722 20786 41722 20786 41723 17905 41723 20787 41723 20786 41724 20787 41724 20779 41724 20779 41725 20787 41725 20788 41725 20779 41726 20788 41726 20780 41726 20780 41727 20788 41727 17903 41727 20780 41728 17903 41728 20789 41728 20789 41729 17903 41729 17918 41729 20789 41730 17918 41730 20782 41730 20782 41731 17918 41731 17917 41731 20782 41732 17917 41732 20790 41732 20790 41733 17917 41733 20791 41733 20790 41734 20791 41734 16015 41734 16015 41735 20791 41735 17915 41735 16014 41736 16006 41736 20792 41736 20792 41737 16006 41737 20793 41737 20792 41738 20793 41738 20840 41738 20840 41739 20793 41739 20794 41739 20840 41740 20794 41740 20795 41740 20795 41741 20794 41741 20813 41741 20795 41742 20813 41742 20796 41742 20796 41743 20813 41743 20797 41743 20796 41744 20797 41744 20842 41744 20842 41745 20797 41745 20798 41745 20842 41746 20798 41746 20799 41746 20799 41747 20798 41747 20810 41747 20799 41748 20810 41748 20843 41748 20843 41749 20810 41749 20800 41749 20843 41750 20800 41750 20801 41750 20801 41751 20800 41751 20802 41751 20801 41752 20802 41752 20846 41752 20846 41753 20802 41753 20803 41753 20846 41754 20803 41754 20845 41754 20845 41755 20803 41755 20804 41755 20845 41756 20804 41756 20805 41756 20805 41757 20804 41757 20807 41757 20805 41758 20807 41758 20806 41758 20806 41759 20807 41759 16007 41759 17927 41760 20808 41760 16007 41760 16007 41761 20807 41761 17927 41761 17927 41762 20807 41762 20804 41762 17927 41763 20804 41763 20809 41763 20804 41764 20803 41764 20809 41764 20809 41765 20803 41765 20802 41765 20809 41766 20802 41766 17930 41766 17930 41767 20802 41767 20800 41767 17930 41768 20800 41768 17932 41768 20800 41769 20810 41769 17932 41769 17932 41770 20810 41770 20798 41770 17932 41771 20798 41771 20811 41771 20798 41772 20797 41772 20811 41772 20811 41773 20797 41773 20813 41773 20811 41774 20813 41774 17920 41774 16006 41775 20812 41775 20793 41775 20793 41776 20812 41776 17920 41776 20793 41777 17920 41777 20794 41777 20794 41778 17920 41778 20813 41778 16001 41779 20814 41779 20815 41779 20815 41780 20814 41780 20816 41780 20815 41781 20816 41781 20748 41781 20748 41782 20816 41782 20817 41782 20748 41783 20817 41783 20818 41783 20818 41784 20817 41784 20133 41784 20818 41785 20133 41785 20745 41785 20745 41786 20133 41786 20819 41786 20745 41787 20819 41787 20820 41787 20820 41788 20819 41788 20374 41788 20820 41789 20374 41789 15994 41789 15994 41790 20374 41790 20821 41790 15993 41791 20176 41791 20822 41791 20822 41792 20176 41792 20823 41792 20822 41793 20823 41793 20768 41793 20768 41794 20823 41794 20824 41794 20768 41795 20824 41795 20825 41795 20825 41796 20824 41796 20175 41796 20825 41797 20175 41797 20766 41797 20766 41798 20175 41798 20174 41798 20766 41799 20174 41799 20826 41799 20826 41800 20174 41800 20827 41800 20826 41801 20827 41801 20765 41801 20765 41802 20827 41802 20828 41802 15987 41803 20829 41803 20192 41803 20192 41804 20829 41804 20778 41804 20192 41805 20778 41805 20832 41805 20778 41806 20830 41806 20832 41806 20832 41807 20830 41807 20831 41807 20832 41808 20831 41808 20833 41808 20833 41809 20831 41809 20834 41809 20834 41810 20835 41810 20833 41810 20833 41811 20835 41811 20838 41811 20833 41812 20838 41812 20193 41812 20785 41813 20836 41813 20784 41813 20784 41814 20836 41814 20837 41814 20784 41815 20837 41815 20783 41815 20783 41816 20837 41816 20193 41816 20783 41817 20193 41817 20781 41817 20781 41818 20193 41818 20838 41818 20189 41819 20185 41819 16014 41819 16014 41820 20792 41820 20189 41820 20189 41821 20792 41821 20840 41821 20189 41822 20840 41822 20839 41822 20840 41823 20795 41823 20839 41823 20839 41824 20795 41824 20796 41824 20839 41825 20796 41825 20841 41825 20841 41826 20796 41826 20842 41826 20841 41827 20842 41827 20427 41827 20842 41828 20799 41828 20427 41828 20427 41829 20799 41829 20843 41829 20427 41830 20843 41830 20426 41830 20843 41831 20801 41831 20426 41831 20426 41832 20801 41832 20846 41832 20426 41833 20846 41833 20844 41833 20806 41834 15979 41834 20805 41834 20805 41835 15979 41835 20844 41835 20805 41836 20844 41836 20845 41836 20845 41837 20844 41837 20846 41837 15931 41838 15933 41838 20847 41838 20847 41839 15933 41839 20848 41839 20848 41840 15933 41840 20849 41840 20848 41841 20849 41841 20867 41841 20867 41842 20849 41842 20850 41842 20867 41843 20850 41843 20851 41843 20851 41844 20850 41844 20852 41844 20851 41845 20852 41845 20865 41845 20865 41846 20852 41846 20861 41846 20865 41847 20861 41847 20864 41847 20847 41848 15970 41848 15931 41848 15931 41849 15970 41849 20853 41849 15931 41850 20853 41850 15927 41850 15927 41851 20853 41851 15971 41851 15927 41852 15971 41852 20854 41852 20854 41853 15971 41853 15973 41853 20854 41854 15973 41854 20928 41854 20928 41855 15973 41855 20855 41855 20928 41856 20855 41856 20856 41856 20856 41857 20855 41857 20858 41857 20856 41858 20858 41858 20857 41858 20857 41859 20858 41859 20859 41859 20857 41860 20859 41860 20860 41860 20860 41861 20859 41861 20864 41861 20860 41862 20864 41862 20924 41862 20924 41863 20864 41863 20861 41863 20855 41864 20862 41864 20858 41864 20858 41865 20862 41865 20869 41865 20858 41866 20869 41866 20859 41866 20859 41867 20869 41867 20863 41867 20859 41868 20863 41868 20864 41868 20864 41869 20863 41869 20870 41869 20864 41870 20870 41870 20865 41870 20865 41871 20870 41871 20871 41871 20865 41872 20871 41872 20851 41872 20851 41873 20871 41873 20866 41873 20851 41874 20866 41874 20867 41874 20867 41875 20866 41875 20872 41875 20862 41876 20296 41876 20869 41876 20869 41877 20296 41877 20868 41877 20869 41878 20868 41878 20863 41878 20863 41879 20868 41879 20291 41879 20863 41880 20291 41880 20870 41880 20870 41881 20291 41881 20293 41881 20870 41882 20293 41882 20871 41882 20871 41883 20293 41883 20294 41883 20871 41884 20294 41884 20866 41884 20866 41885 20294 41885 20289 41885 20866 41886 20289 41886 20872 41886 20872 41887 20289 41887 15963 41887 20948 41888 20946 41888 20881 41888 20881 41889 20946 41889 20873 41889 20873 41890 20946 41890 20944 41890 20873 41891 20944 41891 20882 41891 20882 41892 20944 41892 20943 41892 20882 41893 20943 41893 20874 41893 20874 41894 20943 41894 15912 41894 20874 41895 15912 41895 15955 41895 15955 41896 15912 41896 15910 41896 15955 41897 15910 41897 15954 41897 15910 41898 20875 41898 15954 41898 15954 41899 20875 41899 15907 41899 15954 41900 15907 41900 15952 41900 15952 41901 15907 41901 15906 41901 15952 41902 15906 41902 20876 41902 20876 41903 15906 41903 15905 41903 20876 41904 15905 41904 20877 41904 20877 41905 15905 41905 15904 41905 20877 41906 15904 41906 20878 41906 20878 41907 15904 41907 20951 41907 20878 41908 20951 41908 20884 41908 20884 41909 20951 41909 20949 41909 20884 41910 20949 41910 20879 41910 20879 41911 20949 41911 20948 41911 20879 41912 20948 41912 20880 41912 20880 41913 20948 41913 20881 41913 20882 41914 20886 41914 20873 41914 20873 41915 20886 41915 20887 41915 20873 41916 20887 41916 20881 41916 20881 41917 20887 41917 20883 41917 20881 41918 20883 41918 20880 41918 20880 41919 20883 41919 20890 41919 20880 41920 20890 41920 20879 41920 20879 41921 20890 41921 20891 41921 20879 41922 20891 41922 20884 41922 20884 41923 20891 41923 20885 41923 20884 41924 20885 41924 20878 41924 20878 41925 20885 41925 20893 41925 20878 41926 20893 41926 20877 41926 20877 41927 20893 41927 15951 41927 20886 41928 20179 41928 20887 41928 20887 41929 20179 41929 20888 41929 20887 41930 20888 41930 20883 41930 20883 41931 20888 41931 20889 41931 20883 41932 20889 41932 20890 41932 20890 41933 20889 41933 20181 41933 20890 41934 20181 41934 20891 41934 20891 41935 20181 41935 20892 41935 20891 41936 20892 41936 20885 41936 20885 41937 20892 41937 20388 41937 20885 41938 20388 41938 20893 41938 20893 41939 20388 41939 20182 41939 20893 41940 20182 41940 15951 41940 15951 41941 20182 41941 15946 41941 20967 41942 20894 41942 20895 41942 20895 41943 20894 41943 20896 41943 20895 41944 20896 41944 20908 41944 20908 41945 20896 41945 20971 41945 20908 41946 20971 41946 20897 41946 20897 41947 20971 41947 20898 41947 20897 41948 20898 41948 20899 41948 20899 41949 20898 41949 20900 41949 20899 41950 20900 41950 15944 41950 15944 41951 20900 41951 15887 41951 15944 41952 15887 41952 20901 41952 20901 41953 15887 41953 20902 41953 20901 41954 20902 41954 20903 41954 20903 41955 20902 41955 15890 41955 20903 41956 15890 41956 15943 41956 15943 41957 15890 41957 15891 41957 15943 41958 15891 41958 20904 41958 20904 41959 15891 41959 15894 41959 20904 41960 15894 41960 20912 41960 20912 41961 15894 41961 20905 41961 20912 41962 20905 41962 20906 41962 20906 41963 20905 41963 20964 41963 20906 41964 20964 41964 20910 41964 20910 41965 20964 41965 20967 41965 20910 41966 20967 41966 20895 41966 20899 41967 20907 41967 20897 41967 20897 41968 20907 41968 20913 41968 20897 41969 20913 41969 20908 41969 20908 41970 20913 41970 20914 41970 20908 41971 20914 41971 20895 41971 20895 41972 20914 41972 20909 41972 20895 41973 20909 41973 20910 41973 20910 41974 20909 41974 20918 41974 20910 41975 20918 41975 20906 41975 20906 41976 20918 41976 20911 41976 20906 41977 20911 41977 20912 41977 20912 41978 20911 41978 20919 41978 20907 41979 20184 41979 20913 41979 20913 41980 20184 41980 20915 41980 20913 41981 20915 41981 20914 41981 20914 41982 20915 41982 20916 41982 20914 41983 20916 41983 20909 41983 20909 41984 20916 41984 20917 41984 20909 41985 20917 41985 20918 41985 20918 41986 20917 41986 20170 41986 20918 41987 20170 41987 20911 41987 20911 41988 20170 41988 20169 41988 20911 41989 20169 41989 20919 41989 20919 41990 20169 41990 20168 41990 20852 41991 20850 41991 20920 41991 20920 41992 20930 41992 20852 41992 20852 41993 20930 41993 20921 41993 20852 41994 20921 41994 20861 41994 20921 41995 20931 41995 20861 41995 20861 41996 20931 41996 20922 41996 20861 41997 20922 41997 20924 41997 20922 41998 20923 41998 20924 41998 20924 41999 20923 41999 20925 41999 20924 42000 20925 42000 20860 42000 20860 42001 20925 42001 20933 42001 20860 42002 20933 42002 20857 42002 20933 42003 20926 42003 20857 42003 20857 42004 20926 42004 20935 42004 20857 42005 20935 42005 20856 42005 20927 42006 20928 42006 20929 42006 20929 42007 20928 42007 20856 42007 20929 42008 20856 42008 20937 42008 20937 42009 20856 42009 20935 42009 20920 42010 15919 42010 20930 42010 20930 42011 15919 42011 20938 42011 20930 42012 20938 42012 20921 42012 20921 42013 20938 42013 20931 42013 20931 42014 20938 42014 20940 42014 20931 42015 20940 42015 20922 42015 20922 42016 20940 42016 20923 42016 20923 42017 20940 42017 20932 42017 20923 42018 20932 42018 20925 42018 20925 42019 20932 42019 20933 42019 20933 42020 20932 42020 20934 42020 20933 42021 20934 42021 20926 42021 20926 42022 20934 42022 20935 42022 20935 42023 20934 42023 20936 42023 20935 42024 20936 42024 20937 42024 20937 42025 20936 42025 20929 42025 20929 42026 20936 42026 20942 42026 20929 42027 20942 42027 20927 42027 15919 42028 17948 42028 20938 42028 20938 42029 17948 42029 20939 42029 20938 42030 20939 42030 20940 42030 20940 42031 20939 42031 17947 42031 20940 42032 17947 42032 20932 42032 20932 42033 17947 42033 17945 42033 20932 42034 17945 42034 20934 42034 20934 42035 17945 42035 17943 42035 20934 42036 17943 42036 20936 42036 20936 42037 17943 42037 20941 42037 20936 42038 20941 42038 20942 42038 20942 42039 20941 42039 15915 42039 15900 42040 20943 42040 20957 42040 20957 42041 20943 42041 20944 42041 20957 42042 20944 42042 20956 42042 20956 42043 20944 42043 20946 42043 20956 42044 20946 42044 20945 42044 20945 42045 20946 42045 20948 42045 20945 42046 20948 42046 20947 42046 20947 42047 20948 42047 20949 42047 20947 42048 20949 42048 20950 42048 20950 42049 20949 42049 20951 42049 20950 42050 20951 42050 20952 42050 20952 42051 20951 42051 15904 42051 20952 42052 20953 42052 20950 42052 20950 42053 20953 42053 20954 42053 20950 42054 20954 42054 20947 42054 20947 42055 20954 42055 20955 42055 20947 42056 20955 42056 20945 42056 20945 42057 20955 42057 20960 42057 20945 42058 20960 42058 20956 42058 20956 42059 20960 42059 20961 42059 20956 42060 20961 42060 20957 42060 20957 42061 20961 42061 20958 42061 20957 42062 20958 42062 15900 42062 15900 42063 20958 42063 20959 42063 20953 42064 17963 42064 20954 42064 20954 42065 17963 42065 17962 42065 20954 42066 17962 42066 20955 42066 20955 42067 17962 42067 17961 42067 20955 42068 17961 42068 20960 42068 20960 42069 17961 42069 17959 42069 20960 42070 17959 42070 20961 42070 20961 42071 17959 42071 20962 42071 20961 42072 20962 42072 20958 42072 20958 42073 20962 42073 17956 42073 20958 42074 17956 42074 20959 42074 20959 42075 17956 42075 20963 42075 20964 42076 20905 42076 20965 42076 20965 42077 20966 42077 20964 42077 20964 42078 20966 42078 20983 42078 20964 42079 20983 42079 20967 42079 20983 42080 20982 42080 20967 42080 20967 42081 20982 42081 20968 42081 20967 42082 20968 42082 20894 42082 20968 42083 20980 42083 20894 42083 20894 42084 20980 42084 20969 42084 20894 42085 20969 42085 20896 42085 20896 42086 20969 42086 20970 42086 20896 42087 20970 42087 20971 42087 20970 42088 20979 42088 20971 42088 20971 42089 20979 42089 20978 42089 20971 42090 20978 42090 20898 42090 20974 42091 20900 42091 20972 42091 20972 42092 20900 42092 20898 42092 20972 42093 20898 42093 20976 42093 20976 42094 20898 42094 20978 42094 20973 42095 20974 42095 20986 42095 20986 42096 20974 42096 20972 42096 20986 42097 20972 42097 20975 42097 20975 42098 20972 42098 20976 42098 20975 42099 20976 42099 20977 42099 20977 42100 20976 42100 20978 42100 20977 42101 20978 42101 20987 42101 20987 42102 20978 42102 20979 42102 20987 42103 20979 42103 20988 42103 20988 42104 20979 42104 20970 42104 20988 42105 20970 42105 20990 42105 20990 42106 20970 42106 20969 42106 20990 42107 20969 42107 20981 42107 20981 42108 20969 42108 20980 42108 20981 42109 20980 42109 20992 42109 20992 42110 20980 42110 20968 42110 20992 42111 20968 42111 20994 42111 20994 42112 20968 42112 20982 42112 20994 42113 20982 42113 20984 42113 20984 42114 20982 42114 20983 42114 20984 42115 20983 42115 20997 42115 20997 42116 20983 42116 20966 42116 20997 42117 20966 42117 20995 42117 20995 42118 20966 42118 20965 42118 20985 42119 17975 42119 20973 42119 20973 42120 20986 42120 20985 42120 20985 42121 20986 42121 20975 42121 20985 42122 20975 42122 17976 42122 20975 42123 20977 42123 17976 42123 17976 42124 20977 42124 20987 42124 17976 42125 20987 42125 20989 42125 20989 42126 20987 42126 20988 42126 20989 42127 20988 42127 20991 42127 20988 42128 20990 42128 20991 42128 20991 42129 20990 42129 20981 42129 20991 42130 20981 42130 20993 42130 20981 42131 20992 42131 20993 42131 20993 42132 20992 42132 20994 42132 20993 42133 20994 42133 17971 42133 20995 42134 20996 42134 20997 42134 20997 42135 20996 42135 17971 42135 20997 42136 17971 42136 20984 42136 20984 42137 17971 42137 20994 42137 20998 42138 21018 42138 20999 42138 20999 42139 21018 42139 21001 42139 20999 42140 21001 42140 21000 42140 21000 42141 21001 42141 21020 42141 21000 42142 21020 42142 21002 42142 21002 42143 21020 42143 21021 42143 21002 42144 21021 42144 21072 42144 21072 42145 21021 42145 21003 42145 21072 42146 21003 42146 21073 42146 21073 42147 21003 42147 21004 42147 21073 42148 21004 42148 21005 42148 21005 42149 21004 42149 21016 42149 21005 42150 21016 42150 21006 42150 21006 42151 21016 42151 21007 42151 21006 42152 21007 42152 21075 42152 21075 42153 21007 42153 21015 42153 21075 42154 21015 42154 21008 42154 21008 42155 21015 42155 21009 42155 21008 42156 21009 42156 21010 42156 21010 42157 21009 42157 21011 42157 21010 42158 21011 42158 21078 42158 21078 42159 21011 42159 21012 42159 21078 42160 21012 42160 21076 42160 21076 42161 21012 42161 15860 42161 21013 42162 17983 42162 15860 42162 15860 42163 21012 42163 21013 42163 21013 42164 21012 42164 21011 42164 21013 42165 21011 42165 17981 42165 21011 42166 21009 42166 17981 42166 17981 42167 21009 42167 21015 42167 17981 42168 21015 42168 21014 42168 21014 42169 21015 42169 21007 42169 21007 42170 21016 42170 21014 42170 21014 42171 21016 42171 21004 42171 21014 42172 21004 42172 21017 42172 21004 42173 21003 42173 21017 42173 21017 42174 21003 42174 21021 42174 21017 42175 21021 42175 17978 42175 21018 42176 21019 42176 21001 42176 21001 42177 21019 42177 17978 42177 21001 42178 17978 42178 21020 42178 21020 42179 17978 42179 21021 42179 21079 42180 21041 42180 21022 42180 21022 42181 21041 42181 21043 42181 21022 42182 21043 42182 21023 42182 21023 42183 21043 42183 21044 42183 21023 42184 21044 42184 21024 42184 21024 42185 21044 42185 21045 42185 21024 42186 21045 42186 21080 42186 21080 42187 21045 42187 21025 42187 21080 42188 21025 42188 21026 42188 21026 42189 21025 42189 21027 42189 21026 42190 21027 42190 21028 42190 21028 42191 21027 42191 21039 42191 21028 42192 21039 42192 21083 42192 21083 42193 21039 42193 21029 42193 21083 42194 21029 42194 21084 42194 21084 42195 21029 42195 21038 42195 21084 42196 21038 42196 21085 42196 21085 42197 21038 42197 21030 42197 21085 42198 21030 42198 21090 42198 21090 42199 21030 42199 21031 42199 21090 42200 21031 42200 21032 42200 21032 42201 21031 42201 21035 42201 21032 42202 21035 42202 21088 42202 21088 42203 21035 42203 21034 42203 21036 42204 21033 42204 21034 42204 21034 42205 21035 42205 21036 42205 21036 42206 21035 42206 21031 42206 21036 42207 21031 42207 21037 42207 21031 42208 21030 42208 21037 42208 21037 42209 21030 42209 21038 42209 21037 42210 21038 42210 17991 42210 17991 42211 21038 42211 21029 42211 17991 42212 21029 42212 21040 42212 21029 42213 21039 42213 21040 42213 21040 42214 21039 42214 21027 42214 21040 42215 21027 42215 17992 42215 21027 42216 21025 42216 17992 42216 17992 42217 21025 42217 21045 42217 17992 42218 21045 42218 17993 42218 21041 42219 21042 42219 21043 42219 21043 42220 21042 42220 17993 42220 21043 42221 17993 42221 21044 42221 21044 42222 17993 42222 21045 42222 21092 42223 21046 42223 21093 42223 21093 42224 21046 42224 21056 42224 21093 42225 21056 42225 21094 42225 21094 42226 21056 42226 21047 42226 21047 42227 21056 42227 21048 42227 21047 42228 21048 42228 21095 42228 21095 42229 21048 42229 21049 42229 21049 42230 21048 42230 21057 42230 21049 42231 21057 42231 21097 42231 21097 42232 21057 42232 21098 42232 21098 42233 21057 42233 21050 42233 21098 42234 21050 42234 21099 42234 21099 42235 21050 42235 21051 42235 21051 42236 21050 42236 21053 42236 21051 42237 21053 42237 21052 42237 21052 42238 21053 42238 21101 42238 21101 42239 21053 42239 21059 42239 21101 42240 21059 42240 21054 42240 21046 42241 21055 42241 21056 42241 21056 42242 21055 42242 18013 42242 21056 42243 18013 42243 21048 42243 21048 42244 18013 42244 18012 42244 21048 42245 18012 42245 21057 42245 21057 42246 18012 42246 18008 42246 21057 42247 18008 42247 21050 42247 21050 42248 18008 42248 21058 42248 21050 42249 21058 42249 21053 42249 21053 42250 21058 42250 18007 42250 21053 42251 18007 42251 21059 42251 21059 42252 18007 42252 15824 42252 15777 42253 21063 42253 21107 42253 21107 42254 21063 42254 21064 42254 21107 42255 21064 42255 21106 42255 21106 42256 21064 42256 21066 42256 21106 42257 21066 42257 21060 42257 21060 42258 21066 42258 21067 42258 21060 42259 21067 42259 21104 42259 21104 42260 21067 42260 21068 42260 21104 42261 21068 42261 21061 42261 21061 42262 21068 42262 21070 42262 21061 42263 21070 42263 15787 42263 15787 42264 21070 42264 21062 42264 21063 42265 21065 42265 21064 42265 21064 42266 21065 42266 18023 42266 21064 42267 18023 42267 21066 42267 21066 42268 18023 42268 18021 42268 21066 42269 18021 42269 21067 42269 21067 42270 18021 42270 18020 42270 21067 42271 18020 42271 21068 42271 21068 42272 18020 42272 21069 42272 21068 42273 21069 42273 21070 42273 21070 42274 21069 42274 21071 42274 21070 42275 21071 42275 21062 42275 21062 42276 21071 42276 15813 42276 20144 42277 15807 42277 20998 42277 20998 42278 20999 42278 20144 42278 20144 42279 20999 42279 21000 42279 20144 42280 21000 42280 20245 42280 21000 42281 21002 42281 20245 42281 20245 42282 21002 42282 21072 42282 20245 42283 21072 42283 20145 42283 20145 42284 21072 42284 21073 42284 21073 42285 21005 42285 20145 42285 20145 42286 21005 42286 21006 42286 20145 42287 21006 42287 21074 42287 21006 42288 21075 42288 21074 42288 21074 42289 21075 42289 21008 42289 21074 42290 21008 42290 20146 42290 21076 42291 21077 42291 21078 42291 21078 42292 21077 42292 20146 42292 21078 42293 20146 42293 21010 42293 21010 42294 20146 42294 21008 42294 20046 42295 20045 42295 21079 42295 21079 42296 21022 42296 20046 42296 20046 42297 21022 42297 21023 42297 20046 42298 21023 42298 20047 42298 21023 42299 21024 42299 20047 42299 20047 42300 21024 42300 21080 42300 20047 42301 21080 42301 21081 42301 21080 42302 21026 42302 21081 42302 21081 42303 21026 42303 21028 42303 21081 42304 21028 42304 21082 42304 21082 42305 21028 42305 21083 42305 21082 42306 21083 42306 21086 42306 21083 42307 21084 42307 21086 42307 21086 42308 21084 42308 21085 42308 21086 42309 21085 42309 21087 42309 21088 42310 21089 42310 21032 42310 21032 42311 21089 42311 21087 42311 21032 42312 21087 42312 21090 42312 21090 42313 21087 42313 21085 42313 20077 42314 21091 42314 21092 42314 21092 42315 21093 42315 20077 42315 20077 42316 21093 42316 21094 42316 20077 42317 21094 42317 20078 42317 21094 42318 21047 42318 20078 42318 20078 42319 21047 42319 21095 42319 20078 42320 21095 42320 21096 42320 21096 42321 21095 42321 21049 42321 21096 42322 21049 42322 20079 42322 21049 42323 21097 42323 20079 42323 20079 42324 21097 42324 21098 42324 20079 42325 21098 42325 21100 42325 21098 42326 21099 42326 21100 42326 21100 42327 21099 42327 21051 42327 21100 42328 21051 42328 21102 42328 21054 42329 20082 42329 21101 42329 21101 42330 20082 42330 21102 42330 21101 42331 21102 42331 21052 42331 21052 42332 21102 42332 21051 42332 15787 42333 21103 42333 21061 42333 21061 42334 21103 42334 20059 42334 21061 42335 20059 42335 21104 42335 21104 42336 20059 42336 20064 42336 21104 42337 20064 42337 21060 42337 21060 42338 20064 42338 21105 42338 21060 42339 21105 42339 21106 42339 21106 42340 21105 42340 20055 42340 21106 42341 20055 42341 21107 42341 21107 42342 20055 42342 20054 42342 21107 42343 20054 42343 15777 42343 15777 42344 20054 42344 20053 42344 21121 42345 21124 42345 21108 42345 21108 42346 21124 42346 21109 42346 21108 42347 21109 42347 21110 42347 21110 42348 21109 42348 21111 42348 21110 42349 21111 42349 21187 42349 21187 42350 21111 42350 21125 42350 21187 42351 21125 42351 21113 42351 21113 42352 21125 42352 21112 42352 21113 42353 21112 42353 15736 42353 15736 42354 21112 42354 21114 42354 15736 42355 21114 42355 15734 42355 15734 42356 21114 42356 15771 42356 15734 42357 15771 42357 21115 42357 21115 42358 15771 42358 15773 42358 21115 42359 15773 42359 21116 42359 21116 42360 15773 42360 15774 42360 21116 42361 15774 42361 21117 42361 21117 42362 15774 42362 15775 42362 21117 42363 15775 42363 21118 42363 21118 42364 15775 42364 21122 42364 21118 42365 21122 42365 21119 42365 21119 42366 21122 42366 21120 42366 21119 42367 21120 42367 21185 42367 21185 42368 21120 42368 21121 42368 21185 42369 21121 42369 21108 42369 21122 42370 21126 42370 21120 42370 21120 42371 21126 42371 21123 42371 21120 42372 21123 42372 21121 42372 21121 42373 21123 42373 21127 42373 21121 42374 21127 42374 21124 42374 21124 42375 21127 42375 21128 42375 21124 42376 21128 42376 21109 42376 21109 42377 21128 42377 21129 42377 21109 42378 21129 42378 21111 42378 21111 42379 21129 42379 21130 42379 21111 42380 21130 42380 21125 42380 21125 42381 21130 42381 21131 42381 21125 42382 21131 42382 21112 42382 21112 42383 21131 42383 21133 42383 21126 42384 15769 42384 21123 42384 21123 42385 15769 42385 20154 42385 21123 42386 20154 42386 21127 42386 21127 42387 20154 42387 20153 42387 21127 42388 20153 42388 21128 42388 21128 42389 20153 42389 20148 42389 21128 42390 20148 42390 21129 42390 21129 42391 20148 42391 20149 42391 21129 42392 20149 42392 21130 42392 21130 42393 20149 42393 21132 42393 21130 42394 21132 42394 21131 42394 21131 42395 21132 42395 21134 42395 21131 42396 21134 42396 21133 42396 21133 42397 21134 42397 21135 42397 21205 42398 21211 42398 21136 42398 21136 42399 21211 42399 21137 42399 21137 42400 21211 42400 21209 42400 21137 42401 21209 42401 21138 42401 21138 42402 21209 42402 21207 42402 21138 42403 21207 42403 15761 42403 15761 42404 21207 42404 15705 42404 15761 42405 15705 42405 15760 42405 15760 42406 15705 42406 15706 42406 15760 42407 15706 42407 21142 42407 21136 42408 21139 42408 21205 42408 21205 42409 21139 42409 21145 42409 21205 42410 21145 42410 21140 42410 21140 42411 21145 42411 21141 42411 21140 42412 21141 42412 21201 42412 21201 42413 21141 42413 21146 42413 21201 42414 21146 42414 15713 42414 15713 42415 21146 42415 21148 42415 15713 42416 21148 42416 15714 42416 15714 42417 21148 42417 15758 42417 15714 42418 15758 42418 15711 42418 15711 42419 15758 42419 15759 42419 15711 42420 15759 42420 15708 42420 15708 42421 15759 42421 21142 42421 15708 42422 21142 42422 21143 42422 21143 42423 21142 42423 15706 42423 21138 42424 15757 42424 21137 42424 21137 42425 15757 42425 21150 42425 21137 42426 21150 42426 21136 42426 21136 42427 21150 42427 21151 42427 21136 42428 21151 42428 21139 42428 21139 42429 21151 42429 21144 42429 21139 42430 21144 42430 21145 42430 21145 42431 21144 42431 21152 42431 21145 42432 21152 42432 21141 42432 21141 42433 21152 42433 21153 42433 21141 42434 21153 42434 21146 42434 21146 42435 21153 42435 21147 42435 21146 42436 21147 42436 21148 42436 21148 42437 21147 42437 21155 42437 15757 42438 21149 42438 21150 42438 21150 42439 21149 42439 20074 42439 21150 42440 20074 42440 21151 42440 21151 42441 20074 42441 20073 42441 21151 42442 20073 42442 21144 42442 21144 42443 20073 42443 20072 42443 21144 42444 20072 42444 21152 42444 21152 42445 20072 42445 21154 42445 21152 42446 21154 42446 21153 42446 21153 42447 21154 42447 20070 42447 21153 42448 20070 42448 21147 42448 21147 42449 20070 42449 20069 42449 21147 42450 20069 42450 21155 42450 21155 42451 20069 42451 20067 42451 21168 42452 21171 42452 21156 42452 21156 42453 21171 42453 21172 42453 21156 42454 21172 42454 21157 42454 21157 42455 21172 42455 21175 42455 21157 42456 21175 42456 21224 42456 21224 42457 21175 42457 21178 42457 21224 42458 21178 42458 21225 42458 21225 42459 21178 42459 21179 42459 21225 42460 21179 42460 21159 42460 21159 42461 21179 42461 21158 42461 21159 42462 21158 42462 21160 42462 21160 42463 21158 42463 15746 42463 21160 42464 15746 42464 21161 42464 21161 42465 15746 42465 21162 42465 21161 42466 21162 42466 21164 42466 21164 42467 21162 42467 21163 42467 21164 42468 21163 42468 15690 42468 15690 42469 21163 42469 15749 42469 15690 42470 15749 42470 21233 42470 21233 42471 15749 42471 21165 42471 21233 42472 21165 42472 21234 42472 21234 42473 21165 42473 21166 42473 21234 42474 21166 42474 21167 42474 21167 42475 21166 42475 21169 42475 21167 42476 21169 42476 21168 42476 21168 42477 21169 42477 21171 42477 21165 42478 15744 42478 21166 42478 21166 42479 15744 42479 21180 42479 21166 42480 21180 42480 21169 42480 21169 42481 21180 42481 21170 42481 21169 42482 21170 42482 21171 42482 21171 42483 21170 42483 21173 42483 21171 42484 21173 42484 21172 42484 21172 42485 21173 42485 21174 42485 21172 42486 21174 42486 21175 42486 21175 42487 21174 42487 21176 42487 21175 42488 21176 42488 21178 42488 21178 42489 21176 42489 21177 42489 21178 42490 21177 42490 21179 42490 21179 42491 21177 42491 15745 42491 15744 42492 20050 42492 21180 42492 21180 42493 20050 42493 20065 42493 21180 42494 20065 42494 21170 42494 21170 42495 20065 42495 21181 42495 21170 42496 21181 42496 21173 42496 21173 42497 21181 42497 21182 42497 21173 42498 21182 42498 21174 42498 21174 42499 21182 42499 21183 42499 21174 42500 21183 42500 21176 42500 21176 42501 21183 42501 20062 42501 21176 42502 20062 42502 21177 42502 21177 42503 20062 42503 20063 42503 21177 42504 20063 42504 15745 42504 15745 42505 20063 42505 20056 42505 15725 42506 21118 42506 21184 42506 21184 42507 21118 42507 21119 42507 21184 42508 21119 42508 21186 42508 21186 42509 21119 42509 21185 42509 21186 42510 21185 42510 21193 42510 21193 42511 21185 42511 21108 42511 21193 42512 21108 42512 21192 42512 21192 42513 21108 42513 21110 42513 21192 42514 21110 42514 21188 42514 21188 42515 21110 42515 21187 42515 21188 42516 21187 42516 21189 42516 21189 42517 21187 42517 21113 42517 21189 42518 21190 42518 21188 42518 21188 42519 21190 42519 21191 42519 21188 42520 21191 42520 21192 42520 21192 42521 21191 42521 21197 42521 21192 42522 21197 42522 21193 42522 21193 42523 21197 42523 21194 42523 21193 42524 21194 42524 21186 42524 21186 42525 21194 42525 21199 42525 21186 42526 21199 42526 21184 42526 21184 42527 21199 42527 21195 42527 21184 42528 21195 42528 15725 42528 15725 42529 21195 42529 21196 42529 21190 42530 15724 42530 21191 42530 21191 42531 15724 42531 18037 42531 21191 42532 18037 42532 21197 42532 21197 42533 18037 42533 21198 42533 21197 42534 21198 42534 21194 42534 21194 42535 21198 42535 18036 42535 21194 42536 18036 42536 21199 42536 21199 42537 18036 42537 21200 42537 21199 42538 21200 42538 21195 42538 21195 42539 21200 42539 18034 42539 21195 42540 18034 42540 21196 42540 21196 42541 18034 42541 15718 42541 15713 42542 15712 42542 21201 42542 21201 42543 15712 42543 21202 42543 21201 42544 21202 42544 21140 42544 21202 42545 21212 42545 21140 42545 21140 42546 21212 42546 21203 42546 21140 42547 21203 42547 21205 42547 21205 42548 21203 42548 21204 42548 21204 42549 21214 42549 21205 42549 21205 42550 21214 42550 21206 42550 21205 42551 21206 42551 21211 42551 15703 42552 21207 42552 21208 42552 21208 42553 21207 42553 21209 42553 21208 42554 21209 42554 21210 42554 21210 42555 21209 42555 21211 42555 21210 42556 21211 42556 21216 42556 21216 42557 21211 42557 21206 42557 15712 42558 15702 42558 21219 42558 15712 42559 21219 42559 21202 42559 21202 42560 21219 42560 21221 42560 21202 42561 21221 42561 21212 42561 21212 42562 21221 42562 21203 42562 21203 42563 21221 42563 21213 42563 21203 42564 21213 42564 21204 42564 21204 42565 21213 42565 21214 42565 21214 42566 21213 42566 21215 42566 21214 42567 21215 42567 21206 42567 21206 42568 21215 42568 21216 42568 21216 42569 21215 42569 21222 42569 21216 42570 21222 42570 21210 42570 21210 42571 21222 42571 21217 42571 21210 42572 21217 42572 21208 42572 21208 42573 21217 42573 21218 42573 21208 42574 21218 42574 15703 42574 15702 42575 18046 42575 21219 42575 21219 42576 18046 42576 21220 42576 21219 42577 21220 42577 21221 42577 21221 42578 21220 42578 18044 42578 21221 42579 18044 42579 21213 42579 21213 42580 18044 42580 18043 42580 21213 42581 18043 42581 21215 42581 21215 42582 18043 42582 18041 42582 21215 42583 18041 42583 21222 42583 21222 42584 18041 42584 18053 42584 21222 42585 18053 42585 21217 42585 21217 42586 18053 42586 21223 42586 21217 42587 21223 42587 21218 42587 21218 42588 21223 42588 18052 42588 21224 42589 21225 42589 21226 42589 21226 42590 21227 42590 21224 42590 21224 42591 21227 42591 21228 42591 21224 42592 21228 42592 21157 42592 21228 42593 21229 42593 21157 42593 21157 42594 21229 42594 21230 42594 21157 42595 21230 42595 21156 42595 21156 42596 21230 42596 21231 42596 21156 42597 21231 42597 21168 42597 21231 42598 21244 42598 21168 42598 21168 42599 21244 42599 21242 42599 21168 42600 21242 42600 21167 42600 21242 42601 21240 42601 21167 42601 21167 42602 21240 42602 21236 42602 21167 42603 21236 42603 21234 42603 21232 42604 21233 42604 21238 42604 21238 42605 21233 42605 21234 42605 21238 42606 21234 42606 21235 42606 21235 42607 21234 42607 21236 42607 15675 42608 21232 42608 21237 42608 21237 42609 21232 42609 21238 42609 21237 42610 21238 42610 21250 42610 21250 42611 21238 42611 21235 42611 21250 42612 21235 42612 21239 42612 21239 42613 21235 42613 21236 42613 21239 42614 21236 42614 21252 42614 21252 42615 21236 42615 21240 42615 21252 42616 21240 42616 21241 42616 21241 42617 21240 42617 21242 42617 21241 42618 21242 42618 21243 42618 21243 42619 21242 42619 21244 42619 21243 42620 21244 42620 21245 42620 21245 42621 21244 42621 21231 42621 21245 42622 21231 42622 21255 42622 21255 42623 21231 42623 21230 42623 21255 42624 21230 42624 21246 42624 21246 42625 21230 42625 21229 42625 21246 42626 21229 42626 21247 42626 21247 42627 21229 42627 21228 42627 21247 42628 21228 42628 21248 42628 21248 42629 21228 42629 21227 42629 21248 42630 21227 42630 21258 42630 21258 42631 21227 42631 21226 42631 21249 42632 18063 42632 15675 42632 15675 42633 21237 42633 21249 42633 21249 42634 21237 42634 21250 42634 21249 42635 21250 42635 21251 42635 21250 42636 21239 42636 21251 42636 21251 42637 21239 42637 21252 42637 21251 42638 21252 42638 21253 42638 21253 42639 21252 42639 21241 42639 21253 42640 21241 42640 21254 42640 21241 42641 21243 42641 21254 42641 21254 42642 21243 42642 21245 42642 21254 42643 21245 42643 21256 42643 21245 42644 21255 42644 21256 42644 21256 42645 21255 42645 21246 42645 21256 42646 21246 42646 21257 42646 21258 42647 18058 42647 21248 42647 21248 42648 18058 42648 21257 42648 21248 42649 21257 42649 21247 42649 21247 42650 21257 42650 21246 42650 15615 42651 15667 42651 21328 42651 21328 42652 15667 42652 21265 42652 21328 42653 21265 42653 21259 42653 21259 42654 21265 42654 21266 42654 21259 42655 21266 42655 21326 42655 21326 42656 21266 42656 21267 42656 21326 42657 21267 42657 21325 42657 21325 42658 21267 42658 21260 42658 21325 42659 21260 42659 21324 42659 21324 42660 21260 42660 21261 42660 21324 42661 21261 42661 21262 42661 21262 42662 21261 42662 21263 42662 21262 42663 21263 42663 21264 42663 21264 42664 21263 42664 15668 42664 15667 42665 18069 42665 21265 42665 21265 42666 18069 42666 18068 42666 21265 42667 18068 42667 21266 42667 21266 42668 18068 42668 18067 42668 21266 42669 18067 42669 21267 42669 21267 42670 18067 42670 18077 42670 21267 42671 18077 42671 21260 42671 21260 42672 18077 42672 18076 42672 21260 42673 18076 42673 21261 42673 21261 42674 18076 42674 18075 42674 21261 42675 18075 42675 21263 42675 21263 42676 18075 42676 21268 42676 21263 42677 21268 42677 15668 42677 15668 42678 21268 42678 21269 42678 21270 42679 21271 42679 21335 42679 21335 42680 21271 42680 21272 42680 21335 42681 21272 42681 21334 42681 21334 42682 21272 42682 21273 42682 21334 42683 21273 42683 21332 42683 21332 42684 21273 42684 21274 42684 21332 42685 21274 42685 21331 42685 21331 42686 21274 42686 21276 42686 21331 42687 21276 42687 21330 42687 21330 42688 21276 42688 21278 42688 21330 42689 21278 42689 21275 42689 21275 42690 21278 42690 21280 42690 21271 42691 18086 42691 21272 42691 21272 42692 18086 42692 18085 42692 21272 42693 18085 42693 21273 42693 21273 42694 18085 42694 18084 42694 21273 42695 18084 42695 21274 42695 21274 42696 18084 42696 18083 42696 21274 42697 18083 42697 21276 42697 21276 42698 18083 42698 21277 42698 21276 42699 21277 42699 21278 42699 21278 42700 21277 42700 21279 42700 21278 42701 21279 42701 21280 42701 21280 42702 21279 42702 15649 42702 15648 42703 21281 42703 15603 42703 15603 42704 21281 42704 21283 42704 21281 42705 21282 42705 21283 42705 21283 42706 21282 42706 21298 42706 21283 42707 21298 42707 21341 42707 21298 42708 21297 42708 21341 42708 21341 42709 21297 42709 21284 42709 21341 42710 21284 42710 21339 42710 21284 42711 21295 42711 21339 42711 21339 42712 21295 42712 21293 42712 21339 42713 21293 42713 21285 42713 21293 42714 21292 42714 21285 42714 21285 42715 21292 42715 21290 42715 21285 42716 21290 42716 21286 42716 21287 42717 15594 42717 21288 42717 21288 42718 15594 42718 21286 42718 21288 42719 21286 42719 21289 42719 21289 42720 21286 42720 21290 42720 18091 42721 18090 42721 21287 42721 21287 42722 21288 42722 18091 42722 18091 42723 21288 42723 21289 42723 18091 42724 21289 42724 21291 42724 21289 42725 21290 42725 21291 42725 21291 42726 21290 42726 21292 42726 21291 42727 21292 42727 18092 42727 18092 42728 21292 42728 21293 42728 18092 42729 21293 42729 21294 42729 21293 42730 21295 42730 21294 42730 21294 42731 21295 42731 21284 42731 21294 42732 21284 42732 21296 42732 21284 42733 21297 42733 21296 42733 21296 42734 21297 42734 21298 42734 21296 42735 21298 42735 21299 42735 15648 42736 15639 42736 21281 42736 21281 42737 15639 42737 21299 42737 21281 42738 21299 42738 21282 42738 21282 42739 21299 42739 21298 42739 15635 42740 21300 42740 21347 42740 21347 42741 21300 42741 21345 42741 21300 42742 21321 42742 21345 42742 21345 42743 21321 42743 21301 42743 21345 42744 21301 42744 21303 42744 21301 42745 21318 42745 21303 42745 21303 42746 21318 42746 21302 42746 21303 42747 21302 42747 21306 42747 21302 42748 21304 42748 21306 42748 21306 42749 21304 42749 21305 42749 21306 42750 21305 42750 21343 42750 21305 42751 21314 42751 21343 42751 21343 42752 21314 42752 21313 42752 21343 42753 21313 42753 21307 42753 21308 42754 21310 42754 21309 42754 21309 42755 21310 42755 21307 42755 21309 42756 21307 42756 21311 42756 21311 42757 21307 42757 21313 42757 21312 42758 15629 42758 21308 42758 21308 42759 21309 42759 21312 42759 21312 42760 21309 42760 21311 42760 21312 42761 21311 42761 21315 42761 21311 42762 21313 42762 21315 42762 21315 42763 21313 42763 21314 42763 21315 42764 21314 42764 21316 42764 21314 42765 21305 42765 21316 42765 21316 42766 21305 42766 21304 42766 21316 42767 21304 42767 21317 42767 21317 42768 21304 42768 21302 42768 21317 42769 21302 42769 18102 42769 21302 42770 21318 42770 18102 42770 18102 42771 21318 42771 21301 42771 18102 42772 21301 42772 21320 42772 15635 42773 21319 42773 21300 42773 21300 42774 21319 42774 21320 42774 21300 42775 21320 42775 21321 42775 21321 42776 21320 42776 21301 42776 21264 42777 15619 42777 21262 42777 21262 42778 15619 42778 21322 42778 21262 42779 21322 42779 21324 42779 21324 42780 21322 42780 21323 42780 21324 42781 21323 42781 21325 42781 21325 42782 21323 42782 20334 42782 21325 42783 20334 42783 21326 42783 21326 42784 20334 42784 20336 42784 21326 42785 20336 42785 21259 42785 21259 42786 20336 42786 20344 42786 21259 42787 20344 42787 21328 42787 21328 42788 20344 42788 21327 42788 21328 42789 21327 42789 15615 42789 15615 42790 21327 42790 15616 42790 21275 42791 21329 42791 21330 42791 21330 42792 21329 42792 20226 42792 21330 42793 20226 42793 21331 42793 21331 42794 20226 42794 20225 42794 21331 42795 20225 42795 21332 42795 21332 42796 20225 42796 20223 42796 21332 42797 20223 42797 21334 42797 21334 42798 20223 42798 21333 42798 21334 42799 21333 42799 21335 42799 21335 42800 21333 42800 20221 42800 21335 42801 20221 42801 21270 42801 21270 42802 20221 42802 15607 42802 15594 42803 21336 42803 21286 42803 21286 42804 21336 42804 21337 42804 21286 42805 21337 42805 21285 42805 21285 42806 21337 42806 21338 42806 21285 42807 21338 42807 21339 42807 21339 42808 21338 42808 21340 42808 21339 42809 21340 42809 21341 42809 21341 42810 21340 42810 20218 42810 21341 42811 20218 42811 21283 42811 21283 42812 20218 42812 20214 42812 21283 42813 20214 42813 15603 42813 15603 42814 20214 42814 20207 42814 21310 42815 20157 42815 21307 42815 21307 42816 20157 42816 21342 42816 21307 42817 21342 42817 21343 42817 21343 42818 21342 42818 20213 42818 21343 42819 20213 42819 21306 42819 21306 42820 20213 42820 21344 42820 21306 42821 21344 42821 21303 42821 21303 42822 21344 42822 20211 42822 21303 42823 20211 42823 21345 42823 21345 42824 20211 42824 21346 42824 21345 42825 21346 42825 21347 42825 21347 42826 21346 42826 15587 42826 21424 42827 21426 42827 21359 42827 21359 42828 21426 42828 21429 42828 21359 42829 21429 42829 21348 42829 21348 42830 21429 42830 21431 42830 21348 42831 21431 42831 21349 42831 21349 42832 21431 42832 21434 42832 21349 42833 21434 42833 21351 42833 21351 42834 21434 42834 21350 42834 21351 42835 21350 42835 15585 42835 15585 42836 21350 42836 21352 42836 15585 42837 21352 42837 15583 42837 15583 42838 21352 42838 15535 42838 15583 42839 15535 42839 21353 42839 21353 42840 15535 42840 15532 42840 21353 42841 15532 42841 21354 42841 21354 42842 15532 42842 21355 42842 21354 42843 21355 42843 15579 42843 15579 42844 21355 42844 15529 42844 15579 42845 15529 42845 21364 42845 21364 42846 15529 42846 21356 42846 21364 42847 21356 42847 21363 42847 21363 42848 21356 42848 21357 42848 21363 42849 21357 42849 21361 42849 21361 42850 21357 42850 21424 42850 21361 42851 21424 42851 21359 42851 21351 42852 15566 42852 21349 42852 21349 42853 15566 42853 21366 42853 21349 42854 21366 42854 21348 42854 21348 42855 21366 42855 21358 42855 21348 42856 21358 42856 21359 42856 21359 42857 21358 42857 21360 42857 21359 42858 21360 42858 21361 42858 21361 42859 21360 42859 21362 42859 21361 42860 21362 42860 21363 42860 21363 42861 21362 42861 21369 42861 21363 42862 21369 42862 21364 42862 21364 42863 21369 42863 21370 42863 15566 42864 21365 42864 21366 42864 21366 42865 21365 42865 21367 42865 21366 42866 21367 42866 21358 42866 21358 42867 21367 42867 20112 42867 21358 42868 20112 42868 21360 42868 21360 42869 20112 42869 21368 42869 21360 42870 21368 42870 21362 42870 21362 42871 21368 42871 20140 42871 21362 42872 20140 42872 21369 42872 21369 42873 20140 42873 21371 42873 21369 42874 21371 42874 21370 42874 21370 42875 21371 42875 21372 42875 15561 42876 15563 42876 15513 42876 15513 42877 15563 42877 21373 42877 15513 42878 21373 42878 21374 42878 21374 42879 21373 42879 21375 42879 21374 42880 21375 42880 15509 42880 15509 42881 21375 42881 21376 42881 15509 42882 21376 42882 21377 42882 21377 42883 21376 42883 21378 42883 21377 42884 21378 42884 21456 42884 21456 42885 21378 42885 21379 42885 21456 42886 21379 42886 21458 42886 21458 42887 21379 42887 21389 42887 21458 42888 21389 42888 21381 42888 21381 42889 21389 42889 21380 42889 21381 42890 21380 42890 21460 42890 21460 42891 21380 42891 21382 42891 21460 42892 21382 42892 21383 42892 21383 42893 21382 42893 21384 42893 21383 42894 21384 42894 21385 42894 21385 42895 21384 42895 21386 42895 21385 42896 21386 42896 15516 42896 15516 42897 21386 42897 21387 42897 15516 42898 21387 42898 21388 42898 21388 42899 21387 42899 15561 42899 21388 42900 15561 42900 15513 42900 21378 42901 15558 42901 21379 42901 21379 42902 15558 42902 21395 42902 21379 42903 21395 42903 21389 42903 21389 42904 21395 42904 21390 42904 21389 42905 21390 42905 21380 42905 21380 42906 21390 42906 21391 42906 21380 42907 21391 42907 21382 42907 21382 42908 21391 42908 21392 42908 21382 42909 21392 42909 21384 42909 21384 42910 21392 42910 21393 42910 21384 42911 21393 42911 21386 42911 21386 42912 21393 42912 15560 42912 15558 42913 21394 42913 21395 42913 21395 42914 21394 42914 20220 42914 21395 42915 20220 42915 21390 42915 21390 42916 20220 42916 20398 42916 21390 42917 20398 42917 21391 42917 21391 42918 20398 42918 20227 42918 21391 42919 20227 42919 21392 42919 21392 42920 20227 42920 20228 42920 21392 42921 20228 42921 21393 42921 21393 42922 20228 42922 21396 42922 21393 42923 21396 42923 15560 42923 15560 42924 21396 42924 15550 42924 21479 42925 21407 42925 21397 42925 21397 42926 21407 42926 21399 42926 21397 42927 21399 42927 21398 42927 21398 42928 21399 42928 21409 42928 21398 42929 21409 42929 21474 42929 21474 42930 21409 42930 21410 42930 21474 42931 21410 42931 21400 42931 21400 42932 21410 42932 21411 42932 21400 42933 21411 42933 15484 42933 15484 42934 21411 42934 15544 42934 15484 42935 15544 42935 21401 42935 21401 42936 15544 42936 15545 42936 21401 42937 15545 42937 15485 42937 15485 42938 15545 42938 15546 42938 15485 42939 15546 42939 21402 42939 21402 42940 15546 42940 15547 42940 21402 42941 15547 42941 15487 42941 15487 42942 15547 42942 15549 42942 15487 42943 15549 42943 21403 42943 21403 42944 15549 42944 21404 42944 21403 42945 21404 42945 21405 42945 21405 42946 21404 42946 21406 42946 21405 42947 21406 42947 21479 42947 21479 42948 21406 42948 21407 42948 21406 42949 15543 42949 21407 42949 21407 42950 15543 42950 21413 42950 21407 42951 21413 42951 21399 42951 21399 42952 21413 42952 21408 42952 21399 42953 21408 42953 21409 42953 21409 42954 21408 42954 21416 42954 21409 42955 21416 42955 21410 42955 21410 42956 21416 42956 21418 42956 21410 42957 21418 42957 21411 42957 21411 42958 21418 42958 21419 42958 21411 42959 21419 42959 15544 42959 15544 42960 21419 42960 21412 42960 15543 42961 20160 42961 21413 42961 21413 42962 20160 42962 21414 42962 21413 42963 21414 42963 21408 42963 21408 42964 21414 42964 21415 42964 21408 42965 21415 42965 21416 42965 21416 42966 21415 42966 21417 42966 21416 42967 21417 42967 21418 42967 21418 42968 21417 42968 20156 42968 21418 42969 20156 42969 21419 42969 21419 42970 20156 42970 21420 42970 21419 42971 21420 42971 21412 42971 21412 42972 21420 42972 21421 42972 21357 42973 21356 42973 15528 42973 15528 42974 21444 42974 21357 42974 21357 42975 21444 42975 21422 42975 21357 42976 21422 42976 21424 42976 21422 42977 21423 42977 21424 42977 21424 42978 21423 42978 21425 42978 21424 42979 21425 42979 21426 42979 21426 42980 21425 42980 21427 42980 21426 42981 21427 42981 21429 42981 21427 42982 21428 42982 21429 42982 21429 42983 21428 42983 21430 42983 21429 42984 21430 42984 21431 42984 21430 42985 21441 42985 21431 42985 21431 42986 21441 42986 21432 42986 21431 42987 21432 42987 21434 42987 21433 42988 21350 42988 21437 42988 21437 42989 21350 42989 21434 42989 21437 42990 21434 42990 21435 42990 21435 42991 21434 42991 21432 42991 21436 42992 21433 42992 21447 42992 21447 42993 21433 42993 21437 42993 21447 42994 21437 42994 21438 42994 21438 42995 21437 42995 21435 42995 21438 42996 21435 42996 21439 42996 21439 42997 21435 42997 21432 42997 21439 42998 21432 42998 21440 42998 21440 42999 21432 42999 21441 42999 21440 43000 21441 43000 21449 43000 21449 43001 21441 43001 21430 43001 21449 43002 21430 43002 21450 43002 21450 43003 21430 43003 21428 43003 21450 43004 21428 43004 21452 43004 21452 43005 21428 43005 21427 43005 21452 43006 21427 43006 21454 43006 21454 43007 21427 43007 21425 43007 21454 43008 21425 43008 21455 43008 21455 43009 21425 43009 21423 43009 21455 43010 21423 43010 21442 43010 21442 43011 21423 43011 21422 43011 21442 43012 21422 43012 21443 43012 21443 43013 21422 43013 21444 43013 21443 43014 21444 43014 21445 43014 21445 43015 21444 43015 15528 43015 18120 43016 21446 43016 21436 43016 21436 43017 21447 43017 18120 43017 18120 43018 21447 43018 21438 43018 18120 43019 21438 43019 21448 43019 21438 43020 21439 43020 21448 43020 21448 43021 21439 43021 21440 43021 21448 43022 21440 43022 21451 43022 21440 43023 21449 43023 21451 43023 21451 43024 21449 43024 21450 43024 21451 43025 21450 43025 18110 43025 18110 43026 21450 43026 21452 43026 18110 43027 21452 43027 21453 43027 21452 43028 21454 43028 21453 43028 21453 43029 21454 43029 21455 43029 21453 43030 21455 43030 18111 43030 21445 43031 18114 43031 21443 43031 21443 43032 18114 43032 18111 43032 21443 43033 18111 43033 21442 43033 21442 43034 18111 43034 21455 43034 21468 43035 21377 43035 21467 43035 21467 43036 21377 43036 21456 43036 21467 43037 21456 43037 21465 43037 21465 43038 21456 43038 21458 43038 21465 43039 21458 43039 21457 43039 21457 43040 21458 43040 21381 43040 21457 43041 21381 43041 21463 43041 21463 43042 21381 43042 21460 43042 21463 43043 21460 43043 21459 43043 21459 43044 21460 43044 21383 43044 21459 43045 21383 43045 15515 43045 15515 43046 21383 43046 21385 43046 15515 43047 21461 43047 21459 43047 21459 43048 21461 43048 21462 43048 21459 43049 21462 43049 21463 43049 21463 43050 21462 43050 21469 43050 21463 43051 21469 43051 21457 43051 21457 43052 21469 43052 21464 43052 21457 43053 21464 43053 21465 43053 21465 43054 21464 43054 21470 43054 21465 43055 21470 43055 21467 43055 21467 43056 21470 43056 21466 43056 21467 43057 21466 43057 21468 43057 21468 43058 21466 43058 15493 43058 21461 43059 18135 43059 21462 43059 21462 43060 18135 43060 18136 43060 21462 43061 18136 43061 21469 43061 21469 43062 18136 43062 18121 43062 21469 43063 18121 43063 21464 43063 21464 43064 18121 43064 18122 43064 21464 43065 18122 43065 21470 43065 21470 43066 18122 43066 18124 43066 21470 43067 18124 43067 21466 43067 21466 43068 18124 43068 18125 43068 21466 43069 18125 43069 15493 43069 15493 43070 18125 43070 21471 43070 15484 43071 15483 43071 21400 43071 21400 43072 15483 43072 21472 43072 21400 43073 21472 43073 21474 43073 21472 43074 21473 43074 21474 43074 21474 43075 21473 43075 21475 43075 21474 43076 21475 43076 21398 43076 21398 43077 21475 43077 21476 43077 21476 43078 21477 43078 21398 43078 21398 43079 21477 43079 21478 43079 21398 43080 21478 43080 21397 43080 21487 43081 21405 43081 21486 43081 21486 43082 21405 43082 21479 43082 21486 43083 21479 43083 21484 43083 21484 43084 21479 43084 21397 43084 21484 43085 21397 43085 21480 43085 21480 43086 21397 43086 21478 43086 15483 43087 21488 43087 21489 43087 15483 43088 21489 43088 21472 43088 21472 43089 21489 43089 21481 43089 21472 43090 21481 43090 21473 43090 21473 43091 21481 43091 21475 43091 21475 43092 21481 43092 21491 43092 21475 43093 21491 43093 21476 43093 21476 43094 21491 43094 21477 43094 21477 43095 21491 43095 21482 43095 21477 43096 21482 43096 21478 43096 21478 43097 21482 43097 21480 43097 21480 43098 21482 43098 21483 43098 21480 43099 21483 43099 21484 43099 21484 43100 21483 43100 21485 43100 21484 43101 21485 43101 21486 43101 21486 43102 21485 43102 15475 43102 21486 43103 15475 43103 21487 43103 21488 43104 18144 43104 21489 43104 21489 43105 18144 43105 21490 43105 21489 43106 21490 43106 21481 43106 21481 43107 21490 43107 18143 43107 21481 43108 18143 43108 21491 43108 21491 43109 18143 43109 18141 43109 21491 43110 18141 43110 21482 43110 21482 43111 18141 43111 18138 43111 21482 43112 18138 43112 21483 43112 21483 43113 18138 43113 18153 43113 21483 43114 18153 43114 21485 43114 21485 43115 18153 43115 18151 43115 21485 43116 18151 43116 15475 43116 15475 43117 18151 43117 18149 43117 21492 43118 21509 43118 21493 43118 21493 43119 21536 43119 21535 43119 21492 43120 21493 43120 22866 43120 21535 43121 21533 43121 21493 43121 21493 43122 21533 43122 21531 43122 21493 43123 21531 43123 20035 43123 20035 43124 21531 43124 15454 43124 21494 43125 15461 43125 21511 43125 21511 43126 15461 43126 15460 43126 21498 43127 21526 43127 21497 43127 21497 43128 21526 43128 21525 43128 21499 43129 21497 43129 22859 43129 22859 43130 21497 43130 21525 43130 22859 43131 21525 43131 22856 43131 22856 43132 21525 43132 21495 43132 22856 43133 21495 43133 21517 43133 21517 43134 21495 43134 15464 43134 15460 43135 21496 43135 21511 43135 21511 43136 21496 43136 15458 43136 21511 43137 15458 43137 21497 43137 21497 43138 15458 43138 21527 43138 21497 43139 21527 43139 21498 43139 21499 43140 21500 43140 21497 43140 21497 43141 21500 43141 21501 43141 21497 43142 21501 43142 21493 43142 21493 43143 21501 43143 22862 43143 21493 43144 22862 43144 22866 43144 21507 43145 21502 43145 21505 43145 21505 43146 21502 43146 21503 43146 15454 43147 15453 43147 20035 43147 20035 43148 15453 43148 21504 43148 20035 43149 21504 43149 21505 43149 21505 43150 21504 43150 21506 43150 21505 43151 21506 43151 21507 43151 21507 43152 21506 43152 15449 43152 21507 43153 15449 43153 21508 43153 21508 43154 15449 43154 15448 43154 21508 43155 15448 43155 21509 43155 21509 43156 15448 43156 21510 43156 21509 43157 21510 43157 21493 43157 21493 43158 21510 43158 21537 43158 21493 43159 21537 43159 21536 43159 21511 43160 21512 43160 21494 43160 21494 43161 21512 43161 21513 43161 21494 43162 21513 43162 21514 43162 21514 43163 21513 43163 21515 43163 21514 43164 21515 43164 15464 43164 15464 43165 21515 43165 21516 43165 15464 43166 21516 43166 21517 43166 21503 43167 22878 43167 21505 43167 21505 43168 22878 43168 21518 43168 21505 43169 21518 43169 21512 43169 21512 43170 21518 43170 22869 43170 21512 43171 22869 43171 21513 43171 15467 43172 21519 43172 21522 43172 21524 43173 21519 43173 15467 43173 15468 43174 21524 43174 15467 43174 15467 43175 21521 43175 21520 43175 21523 43176 21521 43176 15467 43176 21522 43177 21523 43177 15467 43177 15468 43178 15464 43178 21524 43178 21524 43179 15464 43179 21495 43179 21524 43180 21495 43180 21519 43180 21519 43181 21495 43181 21525 43181 21519 43182 21525 43182 21522 43182 21522 43183 21525 43183 21526 43183 21522 43184 21526 43184 21523 43184 21523 43185 21526 43185 21498 43185 21523 43186 21498 43186 21521 43186 21521 43187 21498 43187 21527 43187 21521 43188 21527 43188 21520 43188 21520 43189 21527 43189 15458 43189 21530 43190 21534 43190 21528 43190 21532 43191 21534 43191 21530 43191 15456 43192 21532 43192 21530 43192 21530 43193 21538 43193 21539 43193 21529 43194 21538 43194 21530 43194 21528 43195 21529 43195 21530 43195 15456 43196 21531 43196 21532 43196 21532 43197 21531 43197 21533 43197 21532 43198 21533 43198 21534 43198 21534 43199 21533 43199 21535 43199 21534 43200 21535 43200 21528 43200 21528 43201 21535 43201 21536 43201 21528 43202 21536 43202 21529 43202 21529 43203 21536 43203 21537 43203 21529 43204 21537 43204 21538 43204 21538 43205 21537 43205 21510 43205 21538 43206 21510 43206 21539 43206 21539 43207 21510 43207 15448 43207 21573 43208 21571 43208 21561 43208 21571 43209 21540 43209 21561 43209 21561 43210 21540 43210 21569 43210 21561 43211 21569 43211 20436 43211 20436 43212 21569 43212 15445 43212 21541 43213 21561 43213 21542 43213 21542 43214 21561 43214 21555 43214 21579 43215 15435 43215 21543 43215 21543 43216 15435 43216 22884 43216 21545 43217 21546 43217 21544 43217 21544 43218 21546 43218 20239 43218 21544 43219 20239 43219 15431 43219 15431 43220 20239 43220 21552 43220 21545 43221 21586 43221 21546 43221 21546 43222 21586 43222 21583 43222 21546 43223 21583 43223 21547 43223 21553 43224 21546 43224 21548 43224 21548 43225 21546 43225 21547 43225 21548 43226 21547 43226 21549 43226 21549 43227 21547 43227 21581 43227 21549 43228 21581 43228 21550 43228 21550 43229 21581 43229 21579 43229 21550 43230 21579 43230 22889 43230 22889 43231 21579 43231 21543 43231 21551 43232 21565 43232 20239 43232 20239 43233 21565 43233 15433 43233 20239 43234 15433 43234 21552 43234 21556 43235 21558 43235 21563 43235 21553 43236 22896 43236 21546 43236 21546 43237 22896 43237 21554 43237 21546 43238 21554 43238 21561 43238 21561 43239 21554 43239 22891 43239 21561 43240 22891 43240 21555 43240 15445 43241 15444 43241 20436 43241 20436 43242 15444 43242 21557 43242 20436 43243 21557 43243 21556 43243 21556 43244 21557 43244 15441 43244 21556 43245 15441 43245 21558 43245 21558 43246 15441 43246 15440 43246 21558 43247 15440 43247 22887 43247 22887 43248 15440 43248 21559 43248 22887 43249 21559 43249 21541 43249 21541 43250 21559 43250 21560 43250 21541 43251 21560 43251 21561 43251 21561 43252 21560 43252 21562 43252 21561 43253 21562 43253 21573 43253 21563 43254 22882 43254 21556 43254 21556 43255 22882 43255 21564 43255 21556 43256 21564 43256 21551 43256 21551 43257 21564 43257 22884 43257 21551 43258 22884 43258 21565 43258 21565 43259 22884 43259 15435 43259 21567 43260 21566 43260 21572 43260 21570 43261 21566 43261 21567 43261 21568 43262 21570 43262 21567 43262 21567 43263 21575 43263 15438 43263 21574 43264 21575 43264 21567 43264 21572 43265 21574 43265 21567 43265 21568 43266 21569 43266 21570 43266 21570 43267 21569 43267 21540 43267 21570 43268 21540 43268 21566 43268 21566 43269 21540 43269 21571 43269 21566 43270 21571 43270 21572 43270 21572 43271 21571 43271 21573 43271 21572 43272 21573 43272 21574 43272 21574 43273 21573 43273 21562 43273 21574 43274 21562 43274 21575 43274 21575 43275 21562 43275 21560 43275 21575 43276 21560 43276 15438 43276 15438 43277 21560 43277 21559 43277 21577 43278 21582 43278 21576 43278 21580 43279 21582 43279 21577 43279 21578 43280 21580 43280 21577 43280 21577 43281 21585 43281 15429 43281 21584 43282 21585 43282 21577 43282 21576 43283 21584 43283 21577 43283 21578 43284 21579 43284 21580 43284 21580 43285 21579 43285 21581 43285 21580 43286 21581 43286 21582 43286 21582 43287 21581 43287 21547 43287 21582 43288 21547 43288 21576 43288 21576 43289 21547 43289 21583 43289 21576 43290 21583 43290 21584 43290 21584 43291 21583 43291 21586 43291 21584 43292 21586 43292 21585 43292 21585 43293 21586 43293 21545 43293 21585 43294 21545 43294 15429 43294 15429 43295 21545 43295 21544 43295 20436 43296 20429 43296 21561 43296 21561 43297 20429 43297 22915 43297 20008 43298 20239 43298 20009 43298 20009 43299 20239 43299 21546 43299 21587 43300 21511 43300 22926 43300 22926 43301 21511 43301 21497 43301 20035 43302 21588 43302 21493 43302 21493 43303 21588 43303 20000 43303 15420 43304 15400 43304 21589 43304 21589 43305 15400 43305 15401 43305 21589 43306 15401 43306 15422 43306 15422 43307 15401 43307 15403 43307 15422 43308 15403 43308 21590 43308 21590 43309 15403 43309 15404 43309 21590 43310 15404 43310 15423 43310 15423 43311 15404 43311 21592 43311 15423 43312 21592 43312 21591 43312 21591 43313 21592 43313 15405 43313 21591 43314 15405 43314 21593 43314 21593 43315 15405 43315 15407 43315 21593 43316 15407 43316 15427 43316 15427 43317 15407 43317 21594 43317 15427 43318 21594 43318 15428 43318 15428 43319 21594 43319 21595 43319 15428 43320 21595 43320 21597 43320 21597 43321 21595 43321 21596 43321 21597 43322 21596 43322 21626 43322 21626 43323 21596 43323 21598 43323 21626 43324 21598 43324 21627 43324 21627 43325 21598 43325 21599 43325 21627 43326 21599 43326 21628 43326 21628 43327 21599 43327 21682 43327 21628 43328 21682 43328 21631 43328 21631 43329 21682 43329 21600 43329 21631 43330 21600 43330 21601 43330 21601 43331 21600 43331 21684 43331 21601 43332 21684 43332 21602 43332 21602 43333 21684 43333 21687 43333 21602 43334 21687 43334 21634 43334 21634 43335 21687 43335 21603 43335 21634 43336 21603 43336 21635 43336 21635 43337 21603 43337 21691 43337 21635 43338 21691 43338 21638 43338 21638 43339 21691 43339 21604 43339 21638 43340 21604 43340 21639 43340 21639 43341 21604 43341 21692 43341 21639 43342 21692 43342 21605 43342 21605 43343 21692 43343 21607 43343 21605 43344 21607 43344 21606 43344 21606 43345 21607 43345 21693 43345 21606 43346 21693 43346 21608 43346 21608 43347 21693 43347 21609 43347 21608 43348 21609 43348 21610 43348 21610 43349 21609 43349 21611 43349 21610 43350 21611 43350 21612 43350 21612 43351 21611 43351 21696 43351 21612 43352 21696 43352 21643 43352 21643 43353 21696 43353 21613 43353 21643 43354 21613 43354 21614 43354 21614 43355 21613 43355 21615 43355 21614 43356 21615 43356 21645 43356 21645 43357 21615 43357 21616 43357 21645 43358 21616 43358 15409 43358 15409 43359 21616 43359 21617 43359 15409 43360 21617 43360 21619 43360 21619 43361 21617 43361 21618 43361 21619 43362 21618 43362 21620 43362 21620 43363 21618 43363 15390 43363 21620 43364 15390 43364 15412 43364 15412 43365 15390 43365 21621 43365 15412 43366 21621 43366 15413 43366 15413 43367 21621 43367 15393 43367 15413 43368 15393 43368 21622 43368 21622 43369 15393 43369 21623 43369 21622 43370 21623 43370 15415 43370 15415 43371 21623 43371 15395 43371 15415 43372 15395 43372 21624 43372 21624 43373 15395 43373 15397 43373 21624 43374 15397 43374 15417 43374 15417 43375 15397 43375 21625 43375 15417 43376 21625 43376 15419 43376 15419 43377 21625 43377 15399 43377 15419 43378 15399 43378 15420 43378 15420 43379 15399 43379 15400 43379 21673 43380 21597 43380 21626 43380 21673 43381 21626 43381 21671 43381 21671 43382 21626 43382 21627 43382 21671 43383 21627 43383 21629 43383 21629 43384 21627 43384 21628 43384 21629 43385 21628 43385 21630 43385 21630 43386 21628 43386 21631 43386 21630 43387 21631 43387 21668 43387 21668 43388 21631 43388 21601 43388 21668 43389 21601 43389 21632 43389 21632 43390 21601 43390 21602 43390 21632 43391 21602 43391 21633 43391 21633 43392 21602 43392 21634 43392 21633 43393 21634 43393 21665 43393 21665 43394 21634 43394 21635 43394 21665 43395 21635 43395 21636 43395 21636 43396 21635 43396 21638 43396 21636 43397 21638 43397 21637 43397 21637 43398 21638 43398 21639 43398 21637 43399 21639 43399 21664 43399 21664 43400 21639 43400 21605 43400 21664 43401 21605 43401 21662 43401 21662 43402 21605 43402 21606 43402 21662 43403 21606 43403 21640 43403 21640 43404 21606 43404 21608 43404 21640 43405 21608 43405 21641 43405 21641 43406 21608 43406 21610 43406 21641 43407 21610 43407 21660 43407 21660 43408 21610 43408 21612 43408 21660 43409 21612 43409 21642 43409 21642 43410 21612 43410 21643 43410 21642 43411 21643 43411 21644 43411 21644 43412 21643 43412 21614 43412 21644 43413 21614 43413 21659 43413 21659 43414 21614 43414 21645 43414 21659 43415 21645 43415 21646 43415 21646 43416 21645 43416 15409 43416 21646 43417 15409 43417 21658 43417 15424 43418 15377 43418 21647 43418 21647 43419 15377 43419 21648 43419 21647 43420 21648 43420 21649 43420 21649 43421 21648 43421 21650 43421 21649 43422 21650 43422 15421 43422 15421 43423 21650 43423 15378 43423 15421 43424 15378 43424 21651 43424 21651 43425 15378 43425 15379 43425 21651 43426 15379 43426 15418 43426 15418 43427 15379 43427 21653 43427 15418 43428 21653 43428 21652 43428 21652 43429 21653 43429 21654 43429 21652 43430 21654 43430 15416 43430 15416 43431 21654 43431 15381 43431 15416 43432 15381 43432 21655 43432 21655 43433 15381 43433 15383 43433 21655 43434 15383 43434 15414 43434 15414 43435 15383 43435 15384 43435 15414 43436 15384 43436 21656 43436 21656 43437 15384 43437 21657 43437 21656 43438 21657 43438 15411 43438 15411 43439 21657 43439 15385 43439 15411 43440 15385 43440 15410 43440 15410 43441 15385 43441 15387 43441 15410 43442 15387 43442 21658 43442 21658 43443 15387 43443 15388 43443 21658 43444 15388 43444 21646 43444 21646 43445 15388 43445 21699 43445 21646 43446 21699 43446 21659 43446 21659 43447 21699 43447 21700 43447 21659 43448 21700 43448 21644 43448 21644 43449 21700 43449 21702 43449 21644 43450 21702 43450 21642 43450 21642 43451 21702 43451 21705 43451 21642 43452 21705 43452 21660 43452 21660 43453 21705 43453 21661 43453 21660 43454 21661 43454 21641 43454 21641 43455 21661 43455 21707 43455 21641 43456 21707 43456 21640 43456 21640 43457 21707 43457 21708 43457 21640 43458 21708 43458 21662 43458 21662 43459 21708 43459 21663 43459 21662 43460 21663 43460 21664 43460 21664 43461 21663 43461 21710 43461 21664 43462 21710 43462 21637 43462 21637 43463 21710 43463 21711 43463 21637 43464 21711 43464 21636 43464 21636 43465 21711 43465 21712 43465 21636 43466 21712 43466 21665 43466 21665 43467 21712 43467 21666 43467 21665 43468 21666 43468 21633 43468 21633 43469 21666 43469 21667 43469 21633 43470 21667 43470 21632 43470 21632 43471 21667 43471 21713 43471 21632 43472 21713 43472 21668 43472 21668 43473 21713 43473 21669 43473 21668 43474 21669 43474 21630 43474 21630 43475 21669 43475 21670 43475 21630 43476 21670 43476 21629 43476 21629 43477 21670 43477 21716 43477 21629 43478 21716 43478 21671 43478 21671 43479 21716 43479 21672 43479 21671 43480 21672 43480 21673 43480 21673 43481 21672 43481 21674 43481 21673 43482 21674 43482 21675 43482 21675 43483 21674 43483 15371 43483 21675 43484 15371 43484 21676 43484 21676 43485 15371 43485 15373 43485 21676 43486 15373 43486 15426 43486 15426 43487 15373 43487 21677 43487 15426 43488 21677 43488 15425 43488 15425 43489 21677 43489 21678 43489 15425 43490 21678 43490 21679 43490 21679 43491 21678 43491 15375 43491 21679 43492 15375 43492 15424 43492 15424 43493 15375 43493 15377 43493 21596 43494 19978 43494 19979 43494 21596 43495 19979 43495 21598 43495 21598 43496 19979 43496 21680 43496 21598 43497 21680 43497 21599 43497 21599 43498 21680 43498 21681 43498 21599 43499 21681 43499 21682 43499 21682 43500 21681 43500 21683 43500 21682 43501 21683 43501 21600 43501 21600 43502 21683 43502 21685 43502 21600 43503 21685 43503 21684 43503 21684 43504 21685 43504 21686 43504 21684 43505 21686 43505 21687 43505 21687 43506 21686 43506 21688 43506 21687 43507 21688 43507 21603 43507 21603 43508 21688 43508 21689 43508 21603 43509 21689 43509 21691 43509 21691 43510 21689 43510 21690 43510 21691 43511 21690 43511 21604 43511 21604 43512 21690 43512 19983 43512 21604 43513 19983 43513 21692 43513 21692 43514 19983 43514 19985 43514 21692 43515 19985 43515 21607 43515 21607 43516 19985 43516 21694 43516 21607 43517 21694 43517 21693 43517 21693 43518 21694 43518 19987 43518 21693 43519 19987 43519 21609 43519 21609 43520 19987 43520 19988 43520 21609 43521 19988 43521 21611 43521 21611 43522 19988 43522 21695 43522 21611 43523 21695 43523 21696 43523 21696 43524 21695 43524 21697 43524 21696 43525 21697 43525 21613 43525 21613 43526 21697 43526 19989 43526 21613 43527 19989 43527 21615 43527 21615 43528 19989 43528 21698 43528 21615 43529 21698 43529 21616 43529 21616 43530 21698 43530 19990 43530 21616 43531 19990 43531 21617 43531 15388 43532 16382 43532 19977 43532 15388 43533 19977 43533 21699 43533 21699 43534 19977 43534 21701 43534 21699 43535 21701 43535 21700 43535 21700 43536 21701 43536 19975 43536 21700 43537 19975 43537 21702 43537 21702 43538 19975 43538 21703 43538 21702 43539 21703 43539 21705 43539 21705 43540 21703 43540 21704 43540 21705 43541 21704 43541 21661 43541 21661 43542 21704 43542 21706 43542 21661 43543 21706 43543 21707 43543 21707 43544 21706 43544 19973 43544 21707 43545 19973 43545 21708 43545 21708 43546 19973 43546 21709 43546 21708 43547 21709 43547 21663 43547 21663 43548 21709 43548 19972 43548 21663 43549 19972 43549 21710 43549 21710 43550 19972 43550 19970 43550 21710 43551 19970 43551 21711 43551 21711 43552 19970 43552 19969 43552 21711 43553 19969 43553 21712 43553 21712 43554 19969 43554 19967 43554 21712 43555 19967 43555 21666 43555 21666 43556 19967 43556 19966 43556 21666 43557 19966 43557 21667 43557 21667 43558 19966 43558 19965 43558 21667 43559 19965 43559 21713 43559 21713 43560 19965 43560 21714 43560 21713 43561 21714 43561 21669 43561 21669 43562 21714 43562 21715 43562 21669 43563 21715 43563 21670 43563 21670 43564 21715 43564 19961 43564 21670 43565 19961 43565 21716 43565 21716 43566 19961 43566 21717 43566 21716 43567 21717 43567 21672 43567 21672 43568 21717 43568 16404 43568 21672 43569 16404 43569 21674 43569 21754 43570 21718 43570 15366 43570 15366 43571 21718 43571 15204 43571 15366 43572 15204 43572 21719 43572 21719 43573 15204 43573 21720 43573 21719 43574 21720 43574 15367 43574 15367 43575 21720 43575 21721 43575 15367 43576 21721 43576 21723 43576 21723 43577 21721 43577 21722 43577 21723 43578 21722 43578 15368 43578 15368 43579 21722 43579 15209 43579 15368 43580 15209 43580 15369 43580 15369 43581 15209 43581 22482 43581 15369 43582 22482 43582 21755 43582 21755 43583 22482 43583 21724 43583 21755 43584 21724 43584 21726 43584 21726 43585 21724 43585 21725 43585 21726 43586 21725 43586 21727 43586 21727 43587 21725 43587 21728 43587 21727 43588 21728 43588 21757 43588 21757 43589 21728 43589 22484 43589 21757 43590 22484 43590 21729 43590 21729 43591 22484 43591 22485 43591 21729 43592 22485 43592 21730 43592 21730 43593 22485 43593 21731 43593 21730 43594 21731 43594 21760 43594 21760 43595 21731 43595 22488 43595 21760 43596 22488 43596 21733 43596 21733 43597 22488 43597 21732 43597 21733 43598 21732 43598 21761 43598 21761 43599 21732 43599 22489 43599 21761 43600 22489 43600 21735 43600 21735 43601 22489 43601 21734 43601 21735 43602 21734 43602 21736 43602 21736 43603 21734 43603 22492 43603 21736 43604 22492 43604 21737 43604 21737 43605 22492 43605 22494 43605 21737 43606 22494 43606 21738 43606 21738 43607 22494 43607 22495 43607 21738 43608 22495 43608 21739 43608 21739 43609 22495 43609 21740 43609 21739 43610 21740 43610 21768 43610 21768 43611 21740 43611 21741 43611 21768 43612 21741 43612 21769 43612 21769 43613 21741 43613 21742 43613 21769 43614 21742 43614 21770 43614 21770 43615 21742 43615 22500 43615 21770 43616 22500 43616 21773 43616 21773 43617 22500 43617 21743 43617 21773 43618 21743 43618 21744 43618 21744 43619 21743 43619 21745 43619 21744 43620 21745 43620 15356 43620 15356 43621 21745 43621 21747 43621 15356 43622 21747 43622 21746 43622 21746 43623 21747 43623 15190 43623 21746 43624 15190 43624 15357 43624 15357 43625 15190 43625 15192 43625 15357 43626 15192 43626 21748 43626 21748 43627 15192 43627 15193 43627 21748 43628 15193 43628 21749 43628 21749 43629 15193 43629 15195 43629 21749 43630 15195 43630 15360 43630 15360 43631 15195 43631 21751 43631 15360 43632 21751 43632 21750 43632 21750 43633 21751 43633 15196 43633 21750 43634 15196 43634 15361 43634 15361 43635 15196 43635 15197 43635 15361 43636 15197 43636 21752 43636 21752 43637 15197 43637 15199 43637 21752 43638 15199 43638 15362 43638 15362 43639 15199 43639 15200 43639 15362 43640 15200 43640 15363 43640 15363 43641 15200 43641 21753 43641 15363 43642 21753 43642 15364 43642 15364 43643 21753 43643 15202 43643 15364 43644 15202 43644 21754 43644 21754 43645 15202 43645 21718 43645 15370 43646 15369 43646 21755 43646 15370 43647 21755 43647 21803 43647 21803 43648 21755 43648 21726 43648 21803 43649 21726 43649 21756 43649 21756 43650 21726 43650 21727 43650 21756 43651 21727 43651 21801 43651 21801 43652 21727 43652 21757 43652 21801 43653 21757 43653 21800 43653 21800 43654 21757 43654 21729 43654 21800 43655 21729 43655 21758 43655 21758 43656 21729 43656 21730 43656 21758 43657 21730 43657 21797 43657 21797 43658 21730 43658 21760 43658 21797 43659 21760 43659 21759 43659 21759 43660 21760 43660 21733 43660 21759 43661 21733 43661 21796 43661 21796 43662 21733 43662 21761 43662 21796 43663 21761 43663 21762 43663 21762 43664 21761 43664 21735 43664 21762 43665 21735 43665 21763 43665 21763 43666 21735 43666 21736 43666 21763 43667 21736 43667 21764 43667 21764 43668 21736 43668 21737 43668 21764 43669 21737 43669 21765 43669 21765 43670 21737 43670 21738 43670 21765 43671 21738 43671 21766 43671 21766 43672 21738 43672 21739 43672 21766 43673 21739 43673 21767 43673 21767 43674 21739 43674 21768 43674 21767 43675 21768 43675 21792 43675 21792 43676 21768 43676 21769 43676 21792 43677 21769 43677 21771 43677 21771 43678 21769 43678 21770 43678 21771 43679 21770 43679 21772 43679 21772 43680 21770 43680 21773 43680 21772 43681 21773 43681 21774 43681 21774 43682 21773 43682 21744 43682 21774 43683 21744 43683 15355 43683 21811 43684 15174 43684 15365 43684 15365 43685 15174 43685 15175 43685 15365 43686 15175 43686 21775 43686 21775 43687 15175 43687 21776 43687 21775 43688 21776 43688 21777 43688 21777 43689 21776 43689 15176 43689 21777 43690 15176 43690 21778 43690 21778 43691 15176 43691 15177 43691 21778 43692 15177 43692 21779 43692 21779 43693 15177 43693 21780 43693 21779 43694 21780 43694 21782 43694 21782 43695 21780 43695 21781 43695 21782 43696 21781 43696 21783 43696 21783 43697 21781 43697 21784 43697 21783 43698 21784 43698 21785 43698 21785 43699 21784 43699 15183 43699 21785 43700 15183 43700 15359 43700 15359 43701 15183 43701 21786 43701 15359 43702 21786 43702 15358 43702 15358 43703 21786 43703 15184 43703 15358 43704 15184 43704 21787 43704 21787 43705 15184 43705 15186 43705 21787 43706 15186 43706 21788 43706 21788 43707 15186 43707 15188 43707 21788 43708 15188 43708 15355 43708 15355 43709 15188 43709 21789 43709 15355 43710 21789 43710 21774 43710 21774 43711 21789 43711 21790 43711 21774 43712 21790 43712 21772 43712 21772 43713 21790 43713 22501 43713 21772 43714 22501 43714 21771 43714 21771 43715 22501 43715 21791 43715 21771 43716 21791 43716 21792 43716 21792 43717 21791 43717 21793 43717 21792 43718 21793 43718 21767 43718 21767 43719 21793 43719 22504 43719 21767 43720 22504 43720 21766 43720 21766 43721 22504 43721 22505 43721 21766 43722 22505 43722 21765 43722 21765 43723 22505 43723 21794 43723 21765 43724 21794 43724 21764 43724 21764 43725 21794 43725 21795 43725 21764 43726 21795 43726 21763 43726 21763 43727 21795 43727 22508 43727 21763 43728 22508 43728 21762 43728 21762 43729 22508 43729 22509 43729 21762 43730 22509 43730 21796 43730 21796 43731 22509 43731 22510 43731 21796 43732 22510 43732 21759 43732 21759 43733 22510 43733 21798 43733 21759 43734 21798 43734 21797 43734 21797 43735 21798 43735 21799 43735 21797 43736 21799 43736 21758 43736 21758 43737 21799 43737 22512 43737 21758 43738 22512 43738 21800 43738 21800 43739 22512 43739 22513 43739 21800 43740 22513 43740 21801 43740 21801 43741 22513 43741 21802 43741 21801 43742 21802 43742 21756 43742 21756 43743 21802 43743 22514 43743 21756 43744 22514 43744 21803 43744 21803 43745 22514 43745 21804 43745 21803 43746 21804 43746 15370 43746 15370 43747 21804 43747 22515 43747 15370 43748 22515 43748 21805 43748 21805 43749 22515 43749 15169 43749 21805 43750 15169 43750 21806 43750 21806 43751 15169 43751 21807 43751 21806 43752 21807 43752 21808 43752 21808 43753 21807 43753 15171 43753 21808 43754 15171 43754 21809 43754 21809 43755 15171 43755 15172 43755 21809 43756 15172 43756 21810 43756 21810 43757 15172 43757 15173 43757 21810 43758 15173 43758 21811 43758 21811 43759 15173 43759 15174 43759 21842 43760 22518 43760 21812 43760 21812 43761 22518 43761 22519 43761 21812 43762 22519 43762 21845 43762 21845 43763 22519 43763 22520 43763 21845 43764 22520 43764 21813 43764 21813 43765 22520 43765 22521 43765 21813 43766 22521 43766 21815 43766 21815 43767 22521 43767 21814 43767 21815 43768 21814 43768 21848 43768 21848 43769 21814 43769 21816 43769 21848 43770 21816 43770 21851 43770 21851 43771 21816 43771 22523 43771 21851 43772 22523 43772 21852 43772 21852 43773 22523 43773 22524 43773 21852 43774 22524 43774 21817 43774 21817 43775 22524 43775 22525 43775 21817 43776 22525 43776 21818 43776 21818 43777 22525 43777 22527 43777 21818 43778 22527 43778 21820 43778 21820 43779 22527 43779 21819 43779 21820 43780 21819 43780 21821 43780 21821 43781 21819 43781 22528 43781 21821 43782 22528 43782 21822 43782 21822 43783 22528 43783 22530 43783 21822 43784 22530 43784 21823 43784 21823 43785 22530 43785 22531 43785 21823 43786 22531 43786 21856 43786 21856 43787 22531 43787 21824 43787 21856 43788 21824 43788 21857 43788 21857 43789 21824 43789 22534 43789 21857 43790 22534 43790 21858 43790 21858 43791 22534 43791 22535 43791 21858 43792 22535 43792 21859 43792 21859 43793 22535 43793 15152 43793 21859 43794 15152 43794 15333 43794 15333 43795 15152 43795 15153 43795 15333 43796 15153 43796 15334 43796 15334 43797 15153 43797 15154 43797 15334 43798 15154 43798 21826 43798 21826 43799 15154 43799 21825 43799 21826 43800 21825 43800 15336 43800 15336 43801 21825 43801 15155 43801 15336 43802 15155 43802 15337 43802 15337 43803 15155 43803 21827 43803 15337 43804 21827 43804 15340 43804 15340 43805 21827 43805 21829 43805 15340 43806 21829 43806 21828 43806 21828 43807 21829 43807 21830 43807 21828 43808 21830 43808 15342 43808 15342 43809 21830 43809 15159 43809 15342 43810 15159 43810 21831 43810 21831 43811 15159 43811 21832 43811 21831 43812 21832 43812 15344 43812 15344 43813 21832 43813 21833 43813 15344 43814 21833 43814 15345 43814 15345 43815 21833 43815 15161 43815 15345 43816 15161 43816 21834 43816 21834 43817 15161 43817 15162 43817 21834 43818 15162 43818 15347 43818 15347 43819 15162 43819 21835 43819 15347 43820 21835 43820 15348 43820 15348 43821 21835 43821 21836 43821 15348 43822 21836 43822 15349 43822 15349 43823 21836 43823 15163 43823 15349 43824 15163 43824 15350 43824 15350 43825 15163 43825 21837 43825 15350 43826 21837 43826 21838 43826 21838 43827 21837 43827 15168 43827 21838 43828 15168 43828 15353 43828 15353 43829 15168 43829 21839 43829 15353 43830 21839 43830 21840 43830 21840 43831 21839 43831 21841 43831 21840 43832 21841 43832 21843 43832 21843 43833 21841 43833 22517 43833 21843 43834 22517 43834 21842 43834 21842 43835 22517 43835 22518 43835 15354 43836 21840 43836 21843 43836 15354 43837 21843 43837 21844 43837 21844 43838 21843 43838 21842 43838 21844 43839 21842 43839 21888 43839 21888 43840 21842 43840 21812 43840 21888 43841 21812 43841 21886 43841 21886 43842 21812 43842 21845 43842 21886 43843 21845 43843 21846 43843 21846 43844 21845 43844 21813 43844 21846 43845 21813 43845 21847 43845 21847 43846 21813 43846 21815 43846 21847 43847 21815 43847 21883 43847 21883 43848 21815 43848 21848 43848 21883 43849 21848 43849 21849 43849 21849 43850 21848 43850 21851 43850 21849 43851 21851 43851 21850 43851 21850 43852 21851 43852 21852 43852 21850 43853 21852 43853 21853 43853 21853 43854 21852 43854 21817 43854 21853 43855 21817 43855 21882 43855 21882 43856 21817 43856 21818 43856 21882 43857 21818 43857 21881 43857 21881 43858 21818 43858 21820 43858 21881 43859 21820 43859 21854 43859 21854 43860 21820 43860 21821 43860 21854 43861 21821 43861 21855 43861 21855 43862 21821 43862 21822 43862 21855 43863 21822 43863 21878 43863 21878 43864 21822 43864 21823 43864 21878 43865 21823 43865 21876 43865 21876 43866 21823 43866 21856 43866 21876 43867 21856 43867 21875 43867 21875 43868 21856 43868 21857 43868 21875 43869 21857 43869 21874 43869 21874 43870 21857 43870 21858 43870 21874 43871 21858 43871 21860 43871 21860 43872 21858 43872 21859 43872 21860 43873 21859 43873 21861 43873 15346 43874 15135 43874 21862 43874 21862 43875 15135 43875 15136 43875 21862 43876 15136 43876 21863 43876 21863 43877 15136 43877 21864 43877 21863 43878 21864 43878 21865 43878 21865 43879 21864 43879 21866 43879 21865 43880 21866 43880 15343 43880 15343 43881 21866 43881 15139 43881 15343 43882 15139 43882 21867 43882 21867 43883 15139 43883 15140 43883 21867 43884 15140 43884 15341 43884 15341 43885 15140 43885 15141 43885 15341 43886 15141 43886 15339 43886 15339 43887 15141 43887 21868 43887 15339 43888 21868 43888 15338 43888 15338 43889 21868 43889 21869 43889 15338 43890 21869 43890 21870 43890 21870 43891 21869 43891 15146 43891 21870 43892 15146 43892 21871 43892 21871 43893 15146 43893 15147 43893 21871 43894 15147 43894 15335 43894 15335 43895 15147 43895 15148 43895 15335 43896 15148 43896 21872 43896 21872 43897 15148 43897 15149 43897 21872 43898 15149 43898 21861 43898 21861 43899 15149 43899 21873 43899 21861 43900 21873 43900 21860 43900 21860 43901 21873 43901 22537 43901 21860 43902 22537 43902 21874 43902 21874 43903 22537 43903 22538 43903 21874 43904 22538 43904 21875 43904 21875 43905 22538 43905 21877 43905 21875 43906 21877 43906 21876 43906 21876 43907 21877 43907 22542 43907 21876 43908 22542 43908 21878 43908 21878 43909 22542 43909 21879 43909 21878 43910 21879 43910 21855 43910 21855 43911 21879 43911 21880 43911 21855 43912 21880 43912 21854 43912 21854 43913 21880 43913 22544 43913 21854 43914 22544 43914 21881 43914 21881 43915 22544 43915 22545 43915 21881 43916 22545 43916 21882 43916 21882 43917 22545 43917 22547 43917 21882 43918 22547 43918 21853 43918 21853 43919 22547 43919 22549 43919 21853 43920 22549 43920 21850 43920 21850 43921 22549 43921 22552 43921 21850 43922 22552 43922 21849 43922 21849 43923 22552 43923 21884 43923 21849 43924 21884 43924 21883 43924 21883 43925 21884 43925 21885 43925 21883 43926 21885 43926 21847 43926 21847 43927 21885 43927 22554 43927 21847 43928 22554 43928 21846 43928 21846 43929 22554 43929 21887 43929 21846 43930 21887 43930 21886 43930 21886 43931 21887 43931 22556 43931 21886 43932 22556 43932 21888 43932 21888 43933 22556 43933 22558 43933 21888 43934 22558 43934 21844 43934 21844 43935 22558 43935 21889 43935 21844 43936 21889 43936 15354 43936 15354 43937 21889 43937 22560 43937 15354 43938 22560 43938 21890 43938 21890 43939 22560 43939 15128 43939 21890 43940 15128 43940 15352 43940 15352 43941 15128 43941 15129 43941 15352 43942 15129 43942 15351 43942 15351 43943 15129 43943 21891 43943 15351 43944 21891 43944 21892 43944 21892 43945 21891 43945 15132 43945 21892 43946 15132 43946 21893 43946 21893 43947 15132 43947 15134 43947 21893 43948 15134 43948 15346 43948 15346 43949 15134 43949 15135 43949 21894 43950 21895 43950 21936 43950 21936 43951 21895 43951 22563 43951 21936 43952 22563 43952 21896 43952 21896 43953 22563 43953 22564 43953 21896 43954 22564 43954 21937 43954 21937 43955 22564 43955 22565 43955 21937 43956 22565 43956 21897 43956 21897 43957 22565 43957 21898 43957 21897 43958 21898 43958 21899 43958 21899 43959 21898 43959 22567 43959 21899 43960 22567 43960 21900 43960 21900 43961 22567 43961 21901 43961 21900 43962 21901 43962 21902 43962 21902 43963 21901 43963 21903 43963 21902 43964 21903 43964 21904 43964 21904 43965 21903 43965 21905 43965 21904 43966 21905 43966 21939 43966 21939 43967 21905 43967 21906 43967 21939 43968 21906 43968 21942 43968 21942 43969 21906 43969 21907 43969 21942 43970 21907 43970 21943 43970 21943 43971 21907 43971 22572 43971 21943 43972 22572 43972 21908 43972 21908 43973 22572 43973 22574 43973 21908 43974 22574 43974 21946 43974 21946 43975 22574 43975 22575 43975 21946 43976 22575 43976 21947 43976 21947 43977 22575 43977 21910 43977 21947 43978 21910 43978 21909 43978 21909 43979 21910 43979 21911 43979 21909 43980 21911 43980 21948 43980 21948 43981 21911 43981 21912 43981 21948 43982 21912 43982 15310 43982 15310 43983 21912 43983 21913 43983 15310 43984 21913 43984 21914 43984 21914 43985 21913 43985 15114 43985 21914 43986 15114 43986 15311 43986 15311 43987 15114 43987 21915 43987 15311 43988 21915 43988 15312 43988 15312 43989 21915 43989 21916 43989 15312 43990 21916 43990 15314 43990 15314 43991 21916 43991 21917 43991 15314 43992 21917 43992 15316 43992 15316 43993 21917 43993 21918 43993 15316 43994 21918 43994 15317 43994 15317 43995 21918 43995 15116 43995 15317 43996 15116 43996 15319 43996 15319 43997 15116 43997 21919 43997 15319 43998 21919 43998 15321 43998 15321 43999 21919 43999 21920 43999 15321 44000 21920 44000 15322 44000 15322 44001 21920 44001 21921 44001 15322 44002 21921 44002 21922 44002 21922 44003 21921 44003 15118 44003 21922 44004 15118 44004 15324 44004 15324 44005 15118 44005 21924 44005 15324 44006 21924 44006 21923 44006 21923 44007 21924 44007 15119 44007 21923 44008 15119 44008 15325 44008 15325 44009 15119 44009 15120 44009 15325 44010 15120 44010 21925 44010 21925 44011 15120 44011 15121 44011 21925 44012 15121 44012 15327 44012 15327 44013 15121 44013 21926 44013 15327 44014 21926 44014 21927 44014 21927 44015 21926 44015 21928 44015 21927 44016 21928 44016 15330 44016 15330 44017 21928 44017 21929 44017 15330 44018 21929 44018 21930 44018 21930 44019 21929 44019 21931 44019 21930 44020 21931 44020 15332 44020 15332 44021 21931 44021 15126 44021 15332 44022 15126 44022 21933 44022 21933 44023 15126 44023 22562 44023 21933 44024 22562 44024 21894 44024 21894 44025 22562 44025 21895 44025 21983 44026 15332 44026 21933 44026 21983 44027 21933 44027 21932 44027 21932 44028 21933 44028 21894 44028 21932 44029 21894 44029 21934 44029 21934 44030 21894 44030 21936 44030 21934 44031 21936 44031 21935 44031 21935 44032 21936 44032 21896 44032 21935 44033 21896 44033 21979 44033 21979 44034 21896 44034 21937 44034 21979 44035 21937 44035 21977 44035 21977 44036 21937 44036 21897 44036 21977 44037 21897 44037 21976 44037 21976 44038 21897 44038 21899 44038 21976 44039 21899 44039 21974 44039 21974 44040 21899 44040 21900 44040 21974 44041 21900 44041 21938 44041 21938 44042 21900 44042 21902 44042 21938 44043 21902 44043 21972 44043 21972 44044 21902 44044 21904 44044 21972 44045 21904 44045 21971 44045 21971 44046 21904 44046 21939 44046 21971 44047 21939 44047 21940 44047 21940 44048 21939 44048 21942 44048 21940 44049 21942 44049 21941 44049 21941 44050 21942 44050 21943 44050 21941 44051 21943 44051 21944 44051 21944 44052 21943 44052 21908 44052 21944 44053 21908 44053 21945 44053 21945 44054 21908 44054 21946 44054 21945 44055 21946 44055 21967 44055 21967 44056 21946 44056 21947 44056 21967 44057 21947 44057 21966 44057 21966 44058 21947 44058 21909 44058 21966 44059 21909 44059 21965 44059 21965 44060 21909 44060 21948 44060 21965 44061 21948 44061 21963 44061 21963 44062 21948 44062 15310 44062 21963 44063 15310 44063 21962 44063 21949 44064 21991 44064 15326 44064 15326 44065 21991 44065 15103 44065 15326 44066 15103 44066 21950 44066 21950 44067 15103 44067 15104 44067 21950 44068 15104 44068 15323 44068 15323 44069 15104 44069 15105 44069 15323 44070 15105 44070 21952 44070 21952 44071 15105 44071 21951 44071 21952 44072 21951 44072 15320 44072 15320 44073 21951 44073 21953 44073 15320 44074 21953 44074 21954 44074 21954 44075 21953 44075 15106 44075 21954 44076 15106 44076 15318 44076 15318 44077 15106 44077 21955 44077 15318 44078 21955 44078 21956 44078 21956 44079 21955 44079 21957 44079 21956 44080 21957 44080 15315 44080 15315 44081 21957 44081 21958 44081 15315 44082 21958 44082 15313 44082 15313 44083 21958 44083 15110 44083 15313 44084 15110 44084 21959 44084 21959 44085 15110 44085 21961 44085 21959 44086 21961 44086 21960 44086 21960 44087 21961 44087 15112 44087 21960 44088 15112 44088 21962 44088 21962 44089 15112 44089 22578 44089 21962 44090 22578 44090 21963 44090 21963 44091 22578 44091 21964 44091 21963 44092 21964 44092 21965 44092 21965 44093 21964 44093 22581 44093 21965 44094 22581 44094 21966 44094 21966 44095 22581 44095 22582 44095 21966 44096 22582 44096 21967 44096 21967 44097 22582 44097 21968 44097 21967 44098 21968 44098 21945 44098 21945 44099 21968 44099 21969 44099 21945 44100 21969 44100 21944 44100 21944 44101 21969 44101 22585 44101 21944 44102 22585 44102 21941 44102 21941 44103 22585 44103 21970 44103 21941 44104 21970 44104 21940 44104 21940 44105 21970 44105 22586 44105 21940 44106 22586 44106 21971 44106 21971 44107 22586 44107 22587 44107 21971 44108 22587 44108 21972 44108 21972 44109 22587 44109 22588 44109 21972 44110 22588 44110 21938 44110 21938 44111 22588 44111 21973 44111 21938 44112 21973 44112 21974 44112 21974 44113 21973 44113 22589 44113 21974 44114 22589 44114 21976 44114 21976 44115 22589 44115 21975 44115 21976 44116 21975 44116 21977 44116 21977 44117 21975 44117 21978 44117 21977 44118 21978 44118 21979 44118 21979 44119 21978 44119 21980 44119 21979 44120 21980 44120 21935 44120 21935 44121 21980 44121 22592 44121 21935 44122 22592 44122 21934 44122 21934 44123 22592 44123 21981 44123 21934 44124 21981 44124 21932 44124 21932 44125 21981 44125 21982 44125 21932 44126 21982 44126 21983 44126 21983 44127 21982 44127 21984 44127 21983 44128 21984 44128 15331 44128 15331 44129 21984 44129 15101 44129 15331 44130 15101 44130 15329 44130 15329 44131 15101 44131 21985 44131 15329 44132 21985 44132 15328 44132 15328 44133 21985 44133 21986 44133 15328 44134 21986 44134 21987 44134 21987 44135 21986 44135 21988 44135 21987 44136 21988 44136 21989 44136 21989 44137 21988 44137 21990 44137 21989 44138 21990 44138 21949 44138 21949 44139 21990 44139 21991 44139 22031 44140 22032 44140 15297 44140 15297 44141 22032 44141 21992 44141 15297 44142 21992 44142 15299 44142 15299 44143 21992 44143 21993 44143 15299 44144 21993 44144 15302 44144 15302 44145 21993 44145 15094 44145 15302 44146 15094 44146 15303 44146 15303 44147 15094 44147 15095 44147 15303 44148 15095 44148 15304 44148 15304 44149 15095 44149 15096 44149 15304 44150 15096 44150 15306 44150 15306 44151 15096 44151 21994 44151 15306 44152 21994 44152 21995 44152 21995 44153 21994 44153 15098 44153 21995 44154 15098 44154 21996 44154 21996 44155 15098 44155 15100 44155 21996 44156 15100 44156 15308 44156 15308 44157 15100 44157 22595 44157 15308 44158 22595 44158 22033 44158 22033 44159 22595 44159 21997 44159 22033 44160 21997 44160 21998 44160 21998 44161 21997 44161 21999 44161 21998 44162 21999 44162 22000 44162 22000 44163 21999 44163 22001 44163 22000 44164 22001 44164 22002 44164 22002 44165 22001 44165 22003 44165 22002 44166 22003 44166 22035 44166 22035 44167 22003 44167 22598 44167 22035 44168 22598 44168 22037 44168 22037 44169 22598 44169 22004 44169 22037 44170 22004 44170 22005 44170 22005 44171 22004 44171 22006 44171 22005 44172 22006 44172 22007 44172 22007 44173 22006 44173 22008 44173 22007 44174 22008 44174 22009 44174 22009 44175 22008 44175 22600 44175 22009 44176 22600 44176 22039 44176 22039 44177 22600 44177 22601 44177 22039 44178 22601 44178 22040 44178 22040 44179 22601 44179 22010 44179 22040 44180 22010 44180 22042 44180 22042 44181 22010 44181 22011 44181 22042 44182 22011 44182 22012 44182 22012 44183 22011 44183 22603 44183 22012 44184 22603 44184 22013 44184 22013 44185 22603 44185 22604 44185 22013 44186 22604 44186 22044 44186 22044 44187 22604 44187 22014 44187 22044 44188 22014 44188 22045 44188 22045 44189 22014 44189 22015 44189 22045 44190 22015 44190 22047 44190 22047 44191 22015 44191 22016 44191 22047 44192 22016 44192 22017 44192 22017 44193 22016 44193 22608 44193 22017 44194 22608 44194 22018 44194 22018 44195 22608 44195 22019 44195 22018 44196 22019 44196 15288 44196 15288 44197 22019 44197 22020 44197 15288 44198 22020 44198 22021 44198 22021 44199 22020 44199 15088 44199 22021 44200 15088 44200 15290 44200 15290 44201 15088 44201 22022 44201 15290 44202 22022 44202 22024 44202 22024 44203 22022 44203 22023 44203 22024 44204 22023 44204 22025 44204 22025 44205 22023 44205 22027 44205 22025 44206 22027 44206 22026 44206 22026 44207 22027 44207 22028 44207 22026 44208 22028 44208 15293 44208 15293 44209 22028 44209 22029 44209 15293 44210 22029 44210 22030 44210 22030 44211 22029 44211 15089 44211 22030 44212 15089 44212 15296 44212 15296 44213 15089 44213 15091 44213 15296 44214 15091 44214 22031 44214 22031 44215 15091 44215 22032 44215 15309 44216 15308 44216 22033 44216 15309 44217 22033 44217 22034 44217 22034 44218 22033 44218 21998 44218 22034 44219 21998 44219 22079 44219 22079 44220 21998 44220 22000 44220 22079 44221 22000 44221 22077 44221 22077 44222 22000 44222 22002 44222 22077 44223 22002 44223 22036 44223 22036 44224 22002 44224 22035 44224 22036 44225 22035 44225 22076 44225 22076 44226 22035 44226 22037 44226 22076 44227 22037 44227 22074 44227 22074 44228 22037 44228 22005 44228 22074 44229 22005 44229 22073 44229 22073 44230 22005 44230 22007 44230 22073 44231 22007 44231 22070 44231 22070 44232 22007 44232 22009 44232 22070 44233 22009 44233 22069 44233 22069 44234 22009 44234 22039 44234 22069 44235 22039 44235 22038 44235 22038 44236 22039 44236 22040 44236 22038 44237 22040 44237 22041 44237 22041 44238 22040 44238 22042 44238 22041 44239 22042 44239 22067 44239 22067 44240 22042 44240 22012 44240 22067 44241 22012 44241 22064 44241 22064 44242 22012 44242 22013 44242 22064 44243 22013 44243 22043 44243 22043 44244 22013 44244 22044 44244 22043 44245 22044 44245 22061 44245 22061 44246 22044 44246 22045 44246 22061 44247 22045 44247 22046 44247 22046 44248 22045 44248 22047 44248 22046 44249 22047 44249 22060 44249 22060 44250 22047 44250 22017 44250 22060 44251 22017 44251 22048 44251 22048 44252 22017 44252 22018 44252 22048 44253 22018 44253 22049 44253 22088 44254 22051 44254 22050 44254 22050 44255 22051 44255 15078 44255 22050 44256 15078 44256 15295 44256 15295 44257 15078 44257 15079 44257 15295 44258 15079 44258 15294 44258 15294 44259 15079 44259 15081 44259 15294 44260 15081 44260 22052 44260 22052 44261 15081 44261 15082 44261 22052 44262 15082 44262 22053 44262 22053 44263 15082 44263 15083 44263 22053 44264 15083 44264 15292 44264 15292 44265 15083 44265 22054 44265 15292 44266 22054 44266 22055 44266 22055 44267 22054 44267 15084 44267 22055 44268 15084 44268 15291 44268 15291 44269 15084 44269 15085 44269 15291 44270 15085 44270 15289 44270 15289 44271 15085 44271 22056 44271 15289 44272 22056 44272 22049 44272 22049 44273 22056 44273 22057 44273 22049 44274 22057 44274 22048 44274 22048 44275 22057 44275 22058 44275 22048 44276 22058 44276 22060 44276 22060 44277 22058 44277 22059 44277 22060 44278 22059 44278 22046 44278 22046 44279 22059 44279 22062 44279 22046 44280 22062 44280 22061 44280 22061 44281 22062 44281 22063 44281 22061 44282 22063 44282 22043 44282 22043 44283 22063 44283 22612 44283 22043 44284 22612 44284 22064 44284 22064 44285 22612 44285 22065 44285 22064 44286 22065 44286 22067 44286 22067 44287 22065 44287 22066 44287 22067 44288 22066 44288 22041 44288 22041 44289 22066 44289 22068 44289 22041 44290 22068 44290 22038 44290 22038 44291 22068 44291 22616 44291 22038 44292 22616 44292 22069 44292 22069 44293 22616 44293 22071 44293 22069 44294 22071 44294 22070 44294 22070 44295 22071 44295 22072 44295 22070 44296 22072 44296 22073 44296 22073 44297 22072 44297 22617 44297 22073 44298 22617 44298 22074 44298 22074 44299 22617 44299 22075 44299 22074 44300 22075 44300 22076 44300 22076 44301 22075 44301 22618 44301 22076 44302 22618 44302 22036 44302 22036 44303 22618 44303 22620 44303 22036 44304 22620 44304 22077 44304 22077 44305 22620 44305 22078 44305 22077 44306 22078 44306 22079 44306 22079 44307 22078 44307 22621 44307 22079 44308 22621 44308 22034 44308 22034 44309 22621 44309 22080 44309 22034 44310 22080 44310 15309 44310 15309 44311 22080 44311 15068 44311 15309 44312 15068 44312 15307 44312 15307 44313 15068 44313 15069 44313 15307 44314 15069 44314 22081 44314 22081 44315 15069 44315 22083 44315 22081 44316 22083 44316 22082 44316 22082 44317 22083 44317 15071 44317 22082 44318 15071 44318 15305 44318 15305 44319 15071 44319 22084 44319 15305 44320 22084 44320 22085 44320 22085 44321 22084 44321 22086 44321 22085 44322 22086 44322 15301 44322 15301 44323 22086 44323 15074 44323 15301 44324 15074 44324 15300 44324 15300 44325 15074 44325 15075 44325 15300 44326 15075 44326 15298 44326 15298 44327 15075 44327 22087 44327 15298 44328 22087 44328 22088 44328 22088 44329 22087 44329 22051 44329 15276 44330 22126 44330 22089 44330 22089 44331 22126 44331 15061 44331 22089 44332 15061 44332 15279 44332 15279 44333 15061 44333 22091 44333 15279 44334 22091 44334 22090 44334 22090 44335 22091 44335 22092 44335 22090 44336 22092 44336 15281 44336 15281 44337 22092 44337 22093 44337 15281 44338 22093 44338 22094 44338 22094 44339 22093 44339 22095 44339 22094 44340 22095 44340 15283 44340 15283 44341 22095 44341 22096 44341 15283 44342 22096 44342 15284 44342 15284 44343 22096 44343 22097 44343 15284 44344 22097 44344 22098 44344 22098 44345 22097 44345 22099 44345 22098 44346 22099 44346 22127 44346 22127 44347 22099 44347 22101 44347 22127 44348 22101 44348 22100 44348 22100 44349 22101 44349 22624 44349 22100 44350 22624 44350 22130 44350 22130 44351 22624 44351 22625 44351 22130 44352 22625 44352 22131 44352 22131 44353 22625 44353 22626 44353 22131 44354 22626 44354 22133 44354 22133 44355 22626 44355 22102 44355 22133 44356 22102 44356 22135 44356 22135 44357 22102 44357 22103 44357 22135 44358 22103 44358 22138 44358 22138 44359 22103 44359 22628 44359 22138 44360 22628 44360 22104 44360 22104 44361 22628 44361 22105 44361 22104 44362 22105 44362 22140 44362 22140 44363 22105 44363 22106 44363 22140 44364 22106 44364 22141 44364 22141 44365 22106 44365 22107 44365 22141 44366 22107 44366 22144 44366 22144 44367 22107 44367 22108 44367 22144 44368 22108 44368 22109 44368 22109 44369 22108 44369 22110 44369 22109 44370 22110 44370 22111 44370 22111 44371 22110 44371 22112 44371 22111 44372 22112 44372 22146 44372 22146 44373 22112 44373 22113 44373 22146 44374 22113 44374 22114 44374 22114 44375 22113 44375 22632 44375 22114 44376 22632 44376 22149 44376 22149 44377 22632 44377 22115 44377 22149 44378 22115 44378 22150 44378 22150 44379 22115 44379 22116 44379 22150 44380 22116 44380 22117 44380 22117 44381 22116 44381 22118 44381 22117 44382 22118 44382 22153 44382 22153 44383 22118 44383 22120 44383 22153 44384 22120 44384 22119 44384 22119 44385 22120 44385 22121 44385 22119 44386 22121 44386 15266 44386 15266 44387 22121 44387 15047 44387 15266 44388 15047 44388 15267 44388 15267 44389 15047 44389 15049 44389 15267 44390 15049 44390 15268 44390 15268 44391 15049 44391 22122 44391 15268 44392 22122 44392 15270 44392 15270 44393 22122 44393 15051 44393 15270 44394 15051 44394 15271 44394 15271 44395 15051 44395 15052 44395 15271 44396 15052 44396 22123 44396 22123 44397 15052 44397 15054 44397 22123 44398 15054 44398 15273 44398 15273 44399 15054 44399 22125 44399 15273 44400 22125 44400 22124 44400 22124 44401 22125 44401 15057 44401 22124 44402 15057 44402 15275 44402 15275 44403 15057 44403 15059 44403 15275 44404 15059 44404 15276 44404 15276 44405 15059 44405 22126 44405 15287 44406 22127 44406 22100 44406 15287 44407 22100 44407 22128 44407 22128 44408 22100 44408 22130 44408 22128 44409 22130 44409 22129 44409 22129 44410 22130 44410 22131 44410 22129 44411 22131 44411 22132 44411 22132 44412 22131 44412 22133 44412 22132 44413 22133 44413 22134 44413 22134 44414 22133 44414 22135 44414 22134 44415 22135 44415 22136 44415 22136 44416 22135 44416 22138 44416 22136 44417 22138 44417 22137 44417 22137 44418 22138 44418 22104 44418 22137 44419 22104 44419 22139 44419 22139 44420 22104 44420 22140 44420 22139 44421 22140 44421 22182 44421 22182 44422 22140 44422 22141 44422 22182 44423 22141 44423 22142 44423 22142 44424 22141 44424 22144 44424 22142 44425 22144 44425 22143 44425 22143 44426 22144 44426 22109 44426 22143 44427 22109 44427 22145 44427 22145 44428 22109 44428 22111 44428 22145 44429 22111 44429 22179 44429 22179 44430 22111 44430 22146 44430 22179 44431 22146 44431 22147 44431 22147 44432 22146 44432 22114 44432 22147 44433 22114 44433 22148 44433 22148 44434 22114 44434 22149 44434 22148 44435 22149 44435 22177 44435 22177 44436 22149 44436 22150 44436 22177 44437 22150 44437 22176 44437 22176 44438 22150 44438 22117 44438 22176 44439 22117 44439 22151 44439 22151 44440 22117 44440 22153 44440 22151 44441 22153 44441 22152 44441 22152 44442 22153 44442 22119 44442 22152 44443 22119 44443 22154 44443 22189 44444 22190 44444 15282 44444 15282 44445 22190 44445 15036 44445 15282 44446 15036 44446 22155 44446 22155 44447 15036 44447 22157 44447 22155 44448 22157 44448 22156 44448 22156 44449 22157 44449 22158 44449 22156 44450 22158 44450 15280 44450 15280 44451 22158 44451 22159 44451 15280 44452 22159 44452 15278 44452 15278 44453 22159 44453 15038 44453 15278 44454 15038 44454 15277 44454 15277 44455 15038 44455 22160 44455 15277 44456 22160 44456 22162 44456 22162 44457 22160 44457 22161 44457 22162 44458 22161 44458 22163 44458 22163 44459 22161 44459 22164 44459 22163 44460 22164 44460 15274 44460 15274 44461 22164 44461 22165 44461 15274 44462 22165 44462 15272 44462 15272 44463 22165 44463 15040 44463 15272 44464 15040 44464 22166 44464 22166 44465 15040 44465 22167 44465 22166 44466 22167 44466 22168 44466 22168 44467 22167 44467 22169 44467 22168 44468 22169 44468 15269 44468 15269 44469 22169 44469 22170 44469 15269 44470 22170 44470 22172 44470 22172 44471 22170 44471 22171 44471 22172 44472 22171 44472 15265 44472 15265 44473 22171 44473 15045 44473 15265 44474 15045 44474 22154 44474 22154 44475 15045 44475 22173 44475 22154 44476 22173 44476 22152 44476 22152 44477 22173 44477 22174 44477 22152 44478 22174 44478 22151 44478 22151 44479 22174 44479 22175 44479 22151 44480 22175 44480 22176 44480 22176 44481 22175 44481 22178 44481 22176 44482 22178 44482 22177 44482 22177 44483 22178 44483 22640 44483 22177 44484 22640 44484 22148 44484 22148 44485 22640 44485 22641 44485 22148 44486 22641 44486 22147 44486 22147 44487 22641 44487 22642 44487 22147 44488 22642 44488 22179 44488 22179 44489 22642 44489 22644 44489 22179 44490 22644 44490 22145 44490 22145 44491 22644 44491 22180 44491 22145 44492 22180 44492 22143 44492 22143 44493 22180 44493 22181 44493 22143 44494 22181 44494 22142 44494 22142 44495 22181 44495 22647 44495 22142 44496 22647 44496 22182 44496 22182 44497 22647 44497 22648 44497 22182 44498 22648 44498 22139 44498 22139 44499 22648 44499 22649 44499 22139 44500 22649 44500 22137 44500 22137 44501 22649 44501 22183 44501 22137 44502 22183 44502 22136 44502 22136 44503 22183 44503 22184 44503 22136 44504 22184 44504 22134 44504 22134 44505 22184 44505 22650 44505 22134 44506 22650 44506 22132 44506 22132 44507 22650 44507 22653 44507 22132 44508 22653 44508 22129 44508 22129 44509 22653 44509 22185 44509 22129 44510 22185 44510 22128 44510 22128 44511 22185 44511 22186 44511 22128 44512 22186 44512 15287 44512 15287 44513 22186 44513 15033 44513 15287 44514 15033 44514 15286 44514 15286 44515 15033 44515 22187 44515 15286 44516 22187 44516 15285 44516 15285 44517 22187 44517 22188 44517 15285 44518 22188 44518 22189 44518 22189 44519 22188 44519 22190 44519 22232 44520 22191 44520 15258 44520 15258 44521 22191 44521 22192 44521 15258 44522 22192 44522 22193 44522 22193 44523 22192 44523 15024 44523 22193 44524 15024 44524 22194 44524 22194 44525 15024 44525 22195 44525 22194 44526 22195 44526 22196 44526 22196 44527 22195 44527 15026 44527 22196 44528 15026 44528 15262 44528 15262 44529 15026 44529 15028 44529 15262 44530 15028 44530 22197 44530 22197 44531 15028 44531 15030 44531 22197 44532 15030 44532 15263 44532 15263 44533 15030 44533 22198 44533 15263 44534 22198 44534 22199 44534 22199 44535 22198 44535 22200 44535 22199 44536 22200 44536 22201 44536 22201 44537 22200 44537 22654 44537 22201 44538 22654 44538 22233 44538 22233 44539 22654 44539 22203 44539 22233 44540 22203 44540 22202 44540 22202 44541 22203 44541 22204 44541 22202 44542 22204 44542 22236 44542 22236 44543 22204 44543 22205 44543 22236 44544 22205 44544 22206 44544 22206 44545 22205 44545 22207 44545 22206 44546 22207 44546 22238 44546 22238 44547 22207 44547 22208 44547 22238 44548 22208 44548 22239 44548 22239 44549 22208 44549 22658 44549 22239 44550 22658 44550 22240 44550 22240 44551 22658 44551 22209 44551 22240 44552 22209 44552 22210 44552 22210 44553 22209 44553 22661 44553 22210 44554 22661 44554 22211 44554 22211 44555 22661 44555 22662 44555 22211 44556 22662 44556 22242 44556 22242 44557 22662 44557 22212 44557 22242 44558 22212 44558 22213 44558 22213 44559 22212 44559 22665 44559 22213 44560 22665 44560 22245 44560 22245 44561 22665 44561 22214 44561 22245 44562 22214 44562 22215 44562 22215 44563 22214 44563 22216 44563 22215 44564 22216 44564 22246 44564 22246 44565 22216 44565 22217 44565 22246 44566 22217 44566 22247 44566 22247 44567 22217 44567 22668 44567 22247 44568 22668 44568 22248 44568 22248 44569 22668 44569 22670 44569 22248 44570 22670 44570 22218 44570 22218 44571 22670 44571 22672 44571 22218 44572 22672 44572 22219 44572 22219 44573 22672 44573 22220 44573 22219 44574 22220 44574 22250 44574 22250 44575 22220 44575 22221 44575 22250 44576 22221 44576 22222 44576 22222 44577 22221 44577 15014 44577 22222 44578 15014 44578 15249 44578 15249 44579 15014 44579 22223 44579 15249 44580 22223 44580 15251 44580 15251 44581 22223 44581 22224 44581 15251 44582 22224 44582 15252 44582 15252 44583 22224 44583 22225 44583 15252 44584 22225 44584 22226 44584 22226 44585 22225 44585 15017 44585 22226 44586 15017 44586 22227 44586 22227 44587 15017 44587 22228 44587 22227 44588 22228 44588 22229 44588 22229 44589 22228 44589 15019 44589 22229 44590 15019 44590 22230 44590 22230 44591 15019 44591 15021 44591 22230 44592 15021 44592 15255 44592 15255 44593 15021 44593 22231 44593 15255 44594 22231 44594 22232 44594 22232 44595 22231 44595 22191 44595 22286 44596 22201 44596 22233 44596 22286 44597 22233 44597 22234 44597 22234 44598 22233 44598 22202 44598 22234 44599 22202 44599 22235 44599 22235 44600 22202 44600 22236 44600 22235 44601 22236 44601 22281 44601 22281 44602 22236 44602 22206 44602 22281 44603 22206 44603 22237 44603 22237 44604 22206 44604 22238 44604 22237 44605 22238 44605 22280 44605 22280 44606 22238 44606 22239 44606 22280 44607 22239 44607 22279 44607 22279 44608 22239 44608 22240 44608 22279 44609 22240 44609 22278 44609 22278 44610 22240 44610 22210 44610 22278 44611 22210 44611 22241 44611 22241 44612 22210 44612 22211 44612 22241 44613 22211 44613 22275 44613 22275 44614 22211 44614 22242 44614 22275 44615 22242 44615 22243 44615 22243 44616 22242 44616 22213 44616 22243 44617 22213 44617 22273 44617 22273 44618 22213 44618 22245 44618 22273 44619 22245 44619 22244 44619 22244 44620 22245 44620 22215 44620 22244 44621 22215 44621 22272 44621 22272 44622 22215 44622 22246 44622 22272 44623 22246 44623 22271 44623 22271 44624 22246 44624 22247 44624 22271 44625 22247 44625 22268 44625 22268 44626 22247 44626 22248 44626 22268 44627 22248 44627 22249 44627 22249 44628 22248 44628 22218 44628 22249 44629 22218 44629 22267 44629 22267 44630 22218 44630 22219 44630 22267 44631 22219 44631 22266 44631 22266 44632 22219 44632 22250 44632 22266 44633 22250 44633 22265 44633 22290 44634 14997 44634 22251 44634 22251 44635 14997 44635 22252 44635 22251 44636 22252 44636 15261 44636 15261 44637 22252 44637 14999 44637 15261 44638 14999 44638 22253 44638 22253 44639 14999 44639 22254 44639 22253 44640 22254 44640 15260 44640 15260 44641 22254 44641 15001 44641 15260 44642 15001 44642 15259 44642 15259 44643 15001 44643 15002 44643 15259 44644 15002 44644 15257 44644 15257 44645 15002 44645 15003 44645 15257 44646 15003 44646 15256 44646 15256 44647 15003 44647 15004 44647 15256 44648 15004 44648 22256 44648 22256 44649 15004 44649 22255 44649 22256 44650 22255 44650 22257 44650 22257 44651 22255 44651 22258 44651 22257 44652 22258 44652 15254 44652 15254 44653 22258 44653 22259 44653 15254 44654 22259 44654 22260 44654 22260 44655 22259 44655 15007 44655 22260 44656 15007 44656 15253 44656 15253 44657 15007 44657 15009 44657 15253 44658 15009 44658 22261 44658 22261 44659 15009 44659 22262 44659 22261 44660 22262 44660 15250 44660 15250 44661 22262 44661 15010 44661 15250 44662 15010 44662 22263 44662 22263 44663 15010 44663 22264 44663 22263 44664 22264 44664 22265 44664 22265 44665 22264 44665 15011 44665 22265 44666 15011 44666 22266 44666 22266 44667 15011 44667 22676 44667 22266 44668 22676 44668 22267 44668 22267 44669 22676 44669 22677 44669 22267 44670 22677 44670 22249 44670 22249 44671 22677 44671 22269 44671 22249 44672 22269 44672 22268 44672 22268 44673 22269 44673 22679 44673 22268 44674 22679 44674 22271 44674 22271 44675 22679 44675 22270 44675 22271 44676 22270 44676 22272 44676 22272 44677 22270 44677 22681 44677 22272 44678 22681 44678 22244 44678 22244 44679 22681 44679 22683 44679 22244 44680 22683 44680 22273 44680 22273 44681 22683 44681 22274 44681 22273 44682 22274 44682 22243 44682 22243 44683 22274 44683 22686 44683 22243 44684 22686 44684 22275 44684 22275 44685 22686 44685 22687 44685 22275 44686 22687 44686 22241 44686 22241 44687 22687 44687 22276 44687 22241 44688 22276 44688 22278 44688 22278 44689 22276 44689 22277 44689 22278 44690 22277 44690 22279 44690 22279 44691 22277 44691 22690 44691 22279 44692 22690 44692 22280 44692 22280 44693 22690 44693 22691 44693 22280 44694 22691 44694 22237 44694 22237 44695 22691 44695 22282 44695 22237 44696 22282 44696 22281 44696 22281 44697 22282 44697 22283 44697 22281 44698 22283 44698 22235 44698 22235 44699 22283 44699 22284 44699 22235 44700 22284 44700 22234 44700 22234 44701 22284 44701 22285 44701 22234 44702 22285 44702 22286 44702 22286 44703 22285 44703 22287 44703 22286 44704 22287 44704 15264 44704 15264 44705 22287 44705 22288 44705 15264 44706 22288 44706 22289 44706 22289 44707 22288 44707 14996 44707 22289 44708 14996 44708 22290 44708 22290 44709 14996 44709 14997 44709 22291 44710 22292 44710 15241 44710 15241 44711 22292 44711 22293 44711 15241 44712 22293 44712 15243 44712 15243 44713 22293 44713 22294 44713 15243 44714 22294 44714 15244 44714 15244 44715 22294 44715 22295 44715 15244 44716 22295 44716 15245 44716 15245 44717 22295 44717 22296 44717 15245 44718 22296 44718 22297 44718 22297 44719 22296 44719 14991 44719 22297 44720 14991 44720 22298 44720 22298 44721 14991 44721 22299 44721 22298 44722 22299 44722 22300 44722 22300 44723 22299 44723 22302 44723 22300 44724 22302 44724 22301 44724 22301 44725 22302 44725 14993 44725 22301 44726 14993 44726 15248 44726 15248 44727 14993 44727 22303 44727 15248 44728 22303 44728 22332 44728 22332 44729 22303 44729 22304 44729 22332 44730 22304 44730 22334 44730 22334 44731 22304 44731 22696 44731 22334 44732 22696 44732 22335 44732 22335 44733 22696 44733 22698 44733 22335 44734 22698 44734 22305 44734 22305 44735 22698 44735 22699 44735 22305 44736 22699 44736 22338 44736 22338 44737 22699 44737 22701 44737 22338 44738 22701 44738 22339 44738 22339 44739 22701 44739 22306 44739 22339 44740 22306 44740 22307 44740 22307 44741 22306 44741 22308 44741 22307 44742 22308 44742 22309 44742 22309 44743 22308 44743 22702 44743 22309 44744 22702 44744 22343 44744 22343 44745 22702 44745 22704 44745 22343 44746 22704 44746 22344 44746 22344 44747 22704 44747 22310 44747 22344 44748 22310 44748 22345 44748 22345 44749 22310 44749 22311 44749 22345 44750 22311 44750 22346 44750 22346 44751 22311 44751 22706 44751 22346 44752 22706 44752 22312 44752 22312 44753 22706 44753 22708 44753 22312 44754 22708 44754 22313 44754 22313 44755 22708 44755 22314 44755 22313 44756 22314 44756 22347 44756 22347 44757 22314 44757 22315 44757 22347 44758 22315 44758 22316 44758 22316 44759 22315 44759 22710 44759 22316 44760 22710 44760 22317 44760 22317 44761 22710 44761 22712 44761 22317 44762 22712 44762 22318 44762 22318 44763 22712 44763 22714 44763 22318 44764 22714 44764 22319 44764 22319 44765 22714 44765 14976 44765 22319 44766 14976 44766 22320 44766 22320 44767 14976 44767 14978 44767 22320 44768 14978 44768 22321 44768 22321 44769 14978 44769 14979 44769 22321 44770 14979 44770 22322 44770 22322 44771 14979 44771 14980 44771 22322 44772 14980 44772 15235 44772 15235 44773 14980 44773 14982 44773 15235 44774 14982 44774 22323 44774 22323 44775 14982 44775 22324 44775 22323 44776 22324 44776 22325 44776 22325 44777 22324 44777 14985 44777 22325 44778 14985 44778 15238 44778 15238 44779 14985 44779 22327 44779 15238 44780 22327 44780 22326 44780 22326 44781 22327 44781 22328 44781 22326 44782 22328 44782 22329 44782 22329 44783 22328 44783 22330 44783 22329 44784 22330 44784 22291 44784 22291 44785 22330 44785 22292 44785 22331 44786 15248 44786 22332 44786 22331 44787 22332 44787 22386 44787 22386 44788 22332 44788 22334 44788 22386 44789 22334 44789 22333 44789 22333 44790 22334 44790 22335 44790 22333 44791 22335 44791 22336 44791 22336 44792 22335 44792 22305 44792 22336 44793 22305 44793 22337 44793 22337 44794 22305 44794 22338 44794 22337 44795 22338 44795 22383 44795 22383 44796 22338 44796 22339 44796 22383 44797 22339 44797 22340 44797 22340 44798 22339 44798 22307 44798 22340 44799 22307 44799 22341 44799 22341 44800 22307 44800 22309 44800 22341 44801 22309 44801 22379 44801 22379 44802 22309 44802 22343 44802 22379 44803 22343 44803 22342 44803 22342 44804 22343 44804 22344 44804 22342 44805 22344 44805 22377 44805 22377 44806 22344 44806 22345 44806 22377 44807 22345 44807 22375 44807 22375 44808 22345 44808 22346 44808 22375 44809 22346 44809 22374 44809 22374 44810 22346 44810 22312 44810 22374 44811 22312 44811 22373 44811 22373 44812 22312 44812 22313 44812 22373 44813 22313 44813 22371 44813 22371 44814 22313 44814 22347 44814 22371 44815 22347 44815 22370 44815 22370 44816 22347 44816 22316 44816 22370 44817 22316 44817 22369 44817 22369 44818 22316 44818 22317 44818 22369 44819 22317 44819 22348 44819 22348 44820 22317 44820 22318 44820 22348 44821 22318 44821 22367 44821 22367 44822 22318 44822 22319 44822 22367 44823 22319 44823 15232 44823 15246 44824 22349 44824 22351 44824 22351 44825 22349 44825 22350 44825 22351 44826 22350 44826 22352 44826 22352 44827 22350 44827 14963 44827 22352 44828 14963 44828 22353 44828 22353 44829 14963 44829 14964 44829 22353 44830 14964 44830 22354 44830 22354 44831 14964 44831 22355 44831 22354 44832 22355 44832 15242 44832 15242 44833 22355 44833 14966 44833 15242 44834 14966 44834 15240 44834 15240 44835 14966 44835 22356 44835 15240 44836 22356 44836 22357 44836 22357 44837 22356 44837 22358 44837 22357 44838 22358 44838 15239 44838 15239 44839 22358 44839 14967 44839 15239 44840 14967 44840 22359 44840 22359 44841 14967 44841 22360 44841 22359 44842 22360 44842 15237 44842 15237 44843 22360 44843 14970 44843 15237 44844 14970 44844 22361 44844 22361 44845 14970 44845 14971 44845 22361 44846 14971 44846 15236 44846 15236 44847 14971 44847 22362 44847 15236 44848 22362 44848 15234 44848 15234 44849 22362 44849 22363 44849 15234 44850 22363 44850 22364 44850 22364 44851 22363 44851 14974 44851 22364 44852 14974 44852 15233 44852 15233 44853 14974 44853 22365 44853 15233 44854 22365 44854 15232 44854 15232 44855 22365 44855 22366 44855 15232 44856 22366 44856 22367 44856 22367 44857 22366 44857 22368 44857 22367 44858 22368 44858 22348 44858 22348 44859 22368 44859 22718 44859 22348 44860 22718 44860 22369 44860 22369 44861 22718 44861 22721 44861 22369 44862 22721 44862 22370 44862 22370 44863 22721 44863 22722 44863 22370 44864 22722 44864 22371 44864 22371 44865 22722 44865 22372 44865 22371 44866 22372 44866 22373 44866 22373 44867 22372 44867 22725 44867 22373 44868 22725 44868 22374 44868 22374 44869 22725 44869 22376 44869 22374 44870 22376 44870 22375 44870 22375 44871 22376 44871 22726 44871 22375 44872 22726 44872 22377 44872 22377 44873 22726 44873 22729 44873 22377 44874 22729 44874 22342 44874 22342 44875 22729 44875 22378 44875 22342 44876 22378 44876 22379 44876 22379 44877 22378 44877 22380 44877 22379 44878 22380 44878 22341 44878 22341 44879 22380 44879 22381 44879 22341 44880 22381 44880 22340 44880 22340 44881 22381 44881 22382 44881 22340 44882 22382 44882 22383 44882 22383 44883 22382 44883 22731 44883 22383 44884 22731 44884 22337 44884 22337 44885 22731 44885 22733 44885 22337 44886 22733 44886 22336 44886 22336 44887 22733 44887 22384 44887 22336 44888 22384 44888 22333 44888 22333 44889 22384 44889 22385 44889 22333 44890 22385 44890 22386 44890 22386 44891 22385 44891 22736 44891 22386 44892 22736 44892 22331 44892 22331 44893 22736 44893 14958 44893 22331 44894 14958 44894 22387 44894 22387 44895 14958 44895 14960 44895 22387 44896 14960 44896 15247 44896 15247 44897 14960 44897 22388 44897 15247 44898 22388 44898 15246 44898 15246 44899 22388 44899 22349 44899 22427 44900 14947 44900 15221 44900 15221 44901 14947 44901 14949 44901 15221 44902 14949 44902 15224 44902 15224 44903 14949 44903 14951 44903 15224 44904 14951 44904 15225 44904 15225 44905 14951 44905 22390 44905 15225 44906 22390 44906 22389 44906 22389 44907 22390 44907 22391 44907 22389 44908 22391 44908 22393 44908 22393 44909 22391 44909 22392 44909 22393 44910 22392 44910 15227 44910 15227 44911 22392 44911 14954 44911 15227 44912 14954 44912 22394 44912 22394 44913 14954 44913 14956 44913 22394 44914 14956 44914 22395 44914 22395 44915 14956 44915 22397 44915 22395 44916 22397 44916 22396 44916 22396 44917 22397 44917 22737 44917 22396 44918 22737 44918 22429 44918 22429 44919 22737 44919 22740 44919 22429 44920 22740 44920 22398 44920 22398 44921 22740 44921 22741 44921 22398 44922 22741 44922 22430 44922 22430 44923 22741 44923 22399 44923 22430 44924 22399 44924 22400 44924 22400 44925 22399 44925 22401 44925 22400 44926 22401 44926 22433 44926 22433 44927 22401 44927 22402 44927 22433 44928 22402 44928 22403 44928 22403 44929 22402 44929 22744 44929 22403 44930 22744 44930 22404 44930 22404 44931 22744 44931 22745 44931 22404 44932 22745 44932 22434 44932 22434 44933 22745 44933 22747 44933 22434 44934 22747 44934 22435 44934 22435 44935 22747 44935 22405 44935 22435 44936 22405 44936 22436 44936 22436 44937 22405 44937 22406 44937 22436 44938 22406 44938 22407 44938 22407 44939 22406 44939 22749 44939 22407 44940 22749 44940 22408 44940 22408 44941 22749 44941 22409 44941 22408 44942 22409 44942 22410 44942 22410 44943 22409 44943 22411 44943 22410 44944 22411 44944 22412 44944 22412 44945 22411 44945 22752 44945 22412 44946 22752 44946 22413 44946 22413 44947 22752 44947 22414 44947 22413 44948 22414 44948 22438 44948 22438 44949 22414 44949 22415 44949 22438 44950 22415 44950 22439 44950 22439 44951 22415 44951 22754 44951 22439 44952 22754 44952 22416 44952 22416 44953 22754 44953 22755 44953 22416 44954 22755 44954 22441 44954 22441 44955 22755 44955 22757 44955 22441 44956 22757 44956 15211 44956 15211 44957 22757 44957 22417 44957 15211 44958 22417 44958 15212 44958 15212 44959 22417 44959 14942 44959 15212 44960 14942 44960 22418 44960 22418 44961 14942 44961 22419 44961 22418 44962 22419 44962 22420 44962 22420 44963 22419 44963 22421 44963 22420 44964 22421 44964 15215 44964 15215 44965 22421 44965 22422 44965 15215 44966 22422 44966 15216 44966 15216 44967 22422 44967 22424 44967 15216 44968 22424 44968 22423 44968 22423 44969 22424 44969 22425 44969 22423 44970 22425 44970 15218 44970 15218 44971 22425 44971 22426 44971 15218 44972 22426 44972 15219 44972 15219 44973 22426 44973 14946 44973 15219 44974 14946 44974 22427 44974 22427 44975 14946 44975 14947 44975 15231 44976 22396 44976 22429 44976 15231 44977 22429 44977 22428 44977 22428 44978 22429 44978 22398 44978 22428 44979 22398 44979 22477 44979 22477 44980 22398 44980 22430 44980 22477 44981 22430 44981 22431 44981 22431 44982 22430 44982 22400 44982 22431 44983 22400 44983 22432 44983 22432 44984 22400 44984 22433 44984 22432 44985 22433 44985 22475 44985 22475 44986 22433 44986 22403 44986 22475 44987 22403 44987 22473 44987 22473 44988 22403 44988 22404 44988 22473 44989 22404 44989 22471 44989 22471 44990 22404 44990 22434 44990 22471 44991 22434 44991 22469 44991 22469 44992 22434 44992 22435 44992 22469 44993 22435 44993 22468 44993 22468 44994 22435 44994 22436 44994 22468 44995 22436 44995 22467 44995 22467 44996 22436 44996 22407 44996 22467 44997 22407 44997 22465 44997 22465 44998 22407 44998 22408 44998 22465 44999 22408 44999 22463 44999 22463 45000 22408 45000 22410 45000 22463 45001 22410 45001 22461 45001 22461 45002 22410 45002 22412 45002 22461 45003 22412 45003 22459 45003 22459 45004 22412 45004 22413 45004 22459 45005 22413 45005 22437 45005 22437 45006 22413 45006 22438 45006 22437 45007 22438 45007 22457 45007 22457 45008 22438 45008 22439 45008 22457 45009 22439 45009 22456 45009 22456 45010 22439 45010 22416 45010 22456 45011 22416 45011 22440 45011 22440 45012 22416 45012 22441 45012 22440 45013 22441 45013 22454 45013 15228 45014 14922 45014 15226 45014 15226 45015 14922 45015 14923 45015 15226 45016 14923 45016 22442 45016 22442 45017 14923 45017 14924 45017 22442 45018 14924 45018 22443 45018 22443 45019 14924 45019 14926 45019 22443 45020 14926 45020 15223 45020 15223 45021 14926 45021 14928 45021 15223 45022 14928 45022 15222 45022 15222 45023 14928 45023 22444 45023 15222 45024 22444 45024 15220 45024 15220 45025 22444 45025 14929 45025 15220 45026 14929 45026 22445 45026 22445 45027 14929 45027 22446 45027 22445 45028 22446 45028 22447 45028 22447 45029 22446 45029 22448 45029 22447 45030 22448 45030 15217 45030 15217 45031 22448 45031 14930 45031 15217 45032 14930 45032 22449 45032 22449 45033 14930 45033 22451 45033 22449 45034 22451 45034 22450 45034 22450 45035 22451 45035 14934 45035 22450 45036 14934 45036 15214 45036 15214 45037 14934 45037 14935 45037 15214 45038 14935 45038 22452 45038 22452 45039 14935 45039 14937 45039 22452 45040 14937 45040 15213 45040 15213 45041 14937 45041 22453 45041 15213 45042 22453 45042 15210 45042 15210 45043 22453 45043 14940 45043 15210 45044 14940 45044 22454 45044 22454 45045 14940 45045 22455 45045 22454 45046 22455 45046 22440 45046 22440 45047 22455 45047 22758 45047 22440 45048 22758 45048 22456 45048 22456 45049 22758 45049 22761 45049 22456 45050 22761 45050 22457 45050 22457 45051 22761 45051 22458 45051 22457 45052 22458 45052 22437 45052 22437 45053 22458 45053 22762 45053 22437 45054 22762 45054 22459 45054 22459 45055 22762 45055 22460 45055 22459 45056 22460 45056 22461 45056 22461 45057 22460 45057 22462 45057 22461 45058 22462 45058 22463 45058 22463 45059 22462 45059 22464 45059 22463 45060 22464 45060 22465 45060 22465 45061 22464 45061 22466 45061 22465 45062 22466 45062 22467 45062 22467 45063 22466 45063 22765 45063 22467 45064 22765 45064 22468 45064 22468 45065 22765 45065 22470 45065 22468 45066 22470 45066 22469 45066 22469 45067 22470 45067 22766 45067 22469 45068 22766 45068 22471 45068 22471 45069 22766 45069 22472 45069 22471 45070 22472 45070 22473 45070 22473 45071 22472 45071 22474 45071 22473 45072 22474 45072 22475 45072 22475 45073 22474 45073 22476 45073 22475 45074 22476 45074 22432 45074 22432 45075 22476 45075 22769 45075 22432 45076 22769 45076 22431 45076 22431 45077 22769 45077 22770 45077 22431 45078 22770 45078 22477 45078 22477 45079 22770 45079 22772 45079 22477 45080 22772 45080 22428 45080 22428 45081 22772 45081 22478 45081 22428 45082 22478 45082 15231 45082 15231 45083 22478 45083 22479 45083 15231 45084 22479 45084 15230 45084 15230 45085 22479 45085 14919 45085 15230 45086 14919 45086 15229 45086 15229 45087 14919 45087 14920 45087 15229 45088 14920 45088 15228 45088 15228 45089 14920 45089 14922 45089 22482 45090 22480 45090 22481 45090 22482 45091 22481 45091 21724 45091 21724 45092 22481 45092 22483 45092 21724 45093 22483 45093 21725 45093 21725 45094 22483 45094 19962 45094 21725 45095 19962 45095 21728 45095 21728 45096 19962 45096 19963 45096 21728 45097 19963 45097 22484 45097 22484 45098 19963 45098 19964 45098 22484 45099 19964 45099 22485 45099 22485 45100 19964 45100 22486 45100 22485 45101 22486 45101 21731 45101 21731 45102 22486 45102 22487 45102 21731 45103 22487 45103 22488 45103 22488 45104 22487 45104 19968 45104 22488 45105 19968 45105 21732 45105 21732 45106 19968 45106 19971 45106 21732 45107 19971 45107 22489 45107 22489 45108 19971 45108 22490 45108 22489 45109 22490 45109 21734 45109 21734 45110 22490 45110 22491 45110 21734 45111 22491 45111 22492 45111 22492 45112 22491 45112 22493 45112 22492 45113 22493 45113 22494 45113 22494 45114 22493 45114 19974 45114 22494 45115 19974 45115 22495 45115 22495 45116 19974 45116 22496 45116 22495 45117 22496 45117 21740 45117 21740 45118 22496 45118 22497 45118 21740 45119 22497 45119 21741 45119 21741 45120 22497 45120 22498 45120 21741 45121 22498 45121 21742 45121 21742 45122 22498 45122 22499 45122 21742 45123 22499 45123 22500 45123 22500 45124 22499 45124 19976 45124 22500 45125 19976 45125 21743 45125 21743 45126 19976 45126 16383 45126 21743 45127 16383 45127 21745 45127 21789 45128 16405 45128 19959 45128 21789 45129 19959 45129 21790 45129 21790 45130 19959 45130 19958 45130 21790 45131 19958 45131 22501 45131 22501 45132 19958 45132 22502 45132 22501 45133 22502 45133 21791 45133 21791 45134 22502 45134 19956 45134 21791 45135 19956 45135 21793 45135 21793 45136 19956 45136 22503 45136 21793 45137 22503 45137 22504 45137 22504 45138 22503 45138 19955 45138 22504 45139 19955 45139 22505 45139 22505 45140 19955 45140 22506 45140 22505 45141 22506 45141 21794 45141 21794 45142 22506 45142 22507 45142 21794 45143 22507 45143 21795 45143 21795 45144 22507 45144 19950 45144 21795 45145 19950 45145 22508 45145 22508 45146 19950 45146 19949 45146 22508 45147 19949 45147 22509 45147 22509 45148 19949 45148 19947 45148 22509 45149 19947 45149 22510 45149 22510 45150 19947 45150 19945 45150 22510 45151 19945 45151 21798 45151 21798 45152 19945 45152 22511 45152 21798 45153 22511 45153 21799 45153 21799 45154 22511 45154 19943 45154 21799 45155 19943 45155 22512 45155 22512 45156 19943 45156 19942 45156 22512 45157 19942 45157 22513 45157 22513 45158 19942 45158 19939 45158 22513 45159 19939 45159 21802 45159 21802 45160 19939 45160 19937 45160 21802 45161 19937 45161 22514 45161 22514 45162 19937 45162 19936 45162 22514 45163 19936 45163 21804 45163 21804 45164 19936 45164 19934 45164 21804 45165 19934 45165 22515 45165 21841 45166 19935 45166 19938 45166 21841 45167 19938 45167 22517 45167 22517 45168 19938 45168 22516 45168 22517 45169 22516 45169 22518 45169 22518 45170 22516 45170 19940 45170 22518 45171 19940 45171 22519 45171 22519 45172 19940 45172 19941 45172 22519 45173 19941 45173 22520 45173 22520 45174 19941 45174 19944 45174 22520 45175 19944 45175 22521 45175 22521 45176 19944 45176 19946 45176 22521 45177 19946 45177 21814 45177 21814 45178 19946 45178 22522 45178 21814 45179 22522 45179 21816 45179 21816 45180 22522 45180 19948 45180 21816 45181 19948 45181 22523 45181 22523 45182 19948 45182 19951 45182 22523 45183 19951 45183 22524 45183 22524 45184 19951 45184 19952 45184 22524 45185 19952 45185 22525 45185 22525 45186 19952 45186 22526 45186 22525 45187 22526 45187 22527 45187 22527 45188 22526 45188 19953 45188 22527 45189 19953 45189 21819 45189 21819 45190 19953 45190 19954 45190 21819 45191 19954 45191 22528 45191 22528 45192 19954 45192 22529 45192 22528 45193 22529 45193 22530 45193 22530 45194 22529 45194 19957 45194 22530 45195 19957 45195 22531 45195 22531 45196 19957 45196 22532 45196 22531 45197 22532 45197 21824 45197 21824 45198 22532 45198 22533 45198 21824 45199 22533 45199 22534 45199 22534 45200 22533 45200 19960 45200 22534 45201 19960 45201 22535 45201 22535 45202 19960 45202 16406 45202 22535 45203 16406 45203 15152 45203 21873 45204 15151 45204 22536 45204 21873 45205 22536 45205 22537 45205 22537 45206 22536 45206 19931 45206 22537 45207 19931 45207 22538 45207 22538 45208 19931 45208 22539 45208 22538 45209 22539 45209 21877 45209 21877 45210 22539 45210 22540 45210 21877 45211 22540 45211 22542 45211 22542 45212 22540 45212 22541 45212 22542 45213 22541 45213 21879 45213 21879 45214 22541 45214 22543 45214 21879 45215 22543 45215 21880 45215 21880 45216 22543 45216 19929 45216 21880 45217 19929 45217 22544 45217 22544 45218 19929 45218 19927 45218 22544 45219 19927 45219 22545 45219 22545 45220 19927 45220 22546 45220 22545 45221 22546 45221 22547 45221 22547 45222 22546 45222 22548 45222 22547 45223 22548 45223 22549 45223 22549 45224 22548 45224 22550 45224 22549 45225 22550 45225 22552 45225 22552 45226 22550 45226 22551 45226 22552 45227 22551 45227 21884 45227 21884 45228 22551 45228 19924 45228 21884 45229 19924 45229 21885 45229 21885 45230 19924 45230 22553 45230 21885 45231 22553 45231 22554 45231 22554 45232 22553 45232 22555 45232 22554 45233 22555 45233 21887 45233 21887 45234 22555 45234 19920 45234 21887 45235 19920 45235 22556 45235 22556 45236 19920 45236 22557 45236 22556 45237 22557 45237 22558 45237 22558 45238 22557 45238 19918 45238 22558 45239 19918 45239 21889 45239 21889 45240 19918 45240 22559 45240 21889 45241 22559 45241 22560 45241 15126 45242 15125 45242 22561 45242 15126 45243 22561 45243 22562 45243 22562 45244 22561 45244 19919 45244 22562 45245 19919 45245 21895 45245 21895 45246 19919 45246 19921 45246 21895 45247 19921 45247 22563 45247 22563 45248 19921 45248 19922 45248 22563 45249 19922 45249 22564 45249 22564 45250 19922 45250 19923 45250 22564 45251 19923 45251 22565 45251 22565 45252 19923 45252 19925 45252 22565 45253 19925 45253 21898 45253 21898 45254 19925 45254 22566 45254 21898 45255 22566 45255 22567 45255 22567 45256 22566 45256 19926 45256 22567 45257 19926 45257 21901 45257 21901 45258 19926 45258 22568 45258 21901 45259 22568 45259 21903 45259 21903 45260 22568 45260 22569 45260 21903 45261 22569 45261 21905 45261 21905 45262 22569 45262 19928 45262 21905 45263 19928 45263 21906 45263 21906 45264 19928 45264 22570 45264 21906 45265 22570 45265 21907 45265 21907 45266 22570 45266 22571 45266 21907 45267 22571 45267 22572 45267 22572 45268 22571 45268 22573 45268 22572 45269 22573 45269 22574 45269 22574 45270 22573 45270 19930 45270 22574 45271 19930 45271 22575 45271 22575 45272 19930 45272 22576 45272 22575 45273 22576 45273 21910 45273 21910 45274 22576 45274 19932 45274 21910 45275 19932 45275 21911 45275 21911 45276 19932 45276 19933 45276 21911 45277 19933 45277 21912 45277 21912 45278 19933 45278 16427 45278 21912 45279 16427 45279 21913 45279 22578 45280 22577 45280 19916 45280 22578 45281 19916 45281 21964 45281 21964 45282 19916 45282 22579 45282 21964 45283 22579 45283 22581 45283 22581 45284 22579 45284 22580 45284 22581 45285 22580 45285 22582 45285 22582 45286 22580 45286 19914 45286 22582 45287 19914 45287 21968 45287 21968 45288 19914 45288 22583 45288 21968 45289 22583 45289 21969 45289 21969 45290 22583 45290 22584 45290 21969 45291 22584 45291 22585 45291 22585 45292 22584 45292 19911 45292 22585 45293 19911 45293 21970 45293 21970 45294 19911 45294 19909 45294 21970 45295 19909 45295 22586 45295 22586 45296 19909 45296 19907 45296 22586 45297 19907 45297 22587 45297 22587 45298 19907 45298 19905 45298 22587 45299 19905 45299 22588 45299 22588 45300 19905 45300 19903 45300 22588 45301 19903 45301 21973 45301 21973 45302 19903 45302 19901 45302 21973 45303 19901 45303 22589 45303 22589 45304 19901 45304 19900 45304 22589 45305 19900 45305 21975 45305 21975 45306 19900 45306 19899 45306 21975 45307 19899 45307 21978 45307 21978 45308 19899 45308 22590 45308 21978 45309 22590 45309 21980 45309 21980 45310 22590 45310 22591 45310 21980 45311 22591 45311 22592 45311 22592 45312 22591 45312 22593 45312 22592 45313 22593 45313 21981 45313 21981 45314 22593 45314 22594 45314 21981 45315 22594 45315 21982 45315 21982 45316 22594 45316 16472 45316 21982 45317 16472 45317 21984 45317 22595 45318 16473 45318 19896 45318 22595 45319 19896 45319 21997 45319 21997 45320 19896 45320 22596 45320 21997 45321 22596 45321 21999 45321 21999 45322 22596 45322 19897 45322 21999 45323 19897 45323 22001 45323 22001 45324 19897 45324 19898 45324 22001 45325 19898 45325 22003 45325 22003 45326 19898 45326 22597 45326 22003 45327 22597 45327 22598 45327 22598 45328 22597 45328 19902 45328 22598 45329 19902 45329 22004 45329 22004 45330 19902 45330 19904 45330 22004 45331 19904 45331 22006 45331 22006 45332 19904 45332 22599 45332 22006 45333 22599 45333 22008 45333 22008 45334 22599 45334 19906 45334 22008 45335 19906 45335 22600 45335 22600 45336 19906 45336 19908 45336 22600 45337 19908 45337 22601 45337 22601 45338 19908 45338 19910 45338 22601 45339 19910 45339 22010 45339 22010 45340 19910 45340 19912 45340 22010 45341 19912 45341 22011 45341 22011 45342 19912 45342 19913 45342 22011 45343 19913 45343 22603 45343 22603 45344 19913 45344 22602 45344 22603 45345 22602 45345 22604 45345 22604 45346 22602 45346 22605 45346 22604 45347 22605 45347 22014 45347 22014 45348 22605 45348 19915 45348 22014 45349 19915 45349 22015 45349 22015 45350 19915 45350 22606 45350 22015 45351 22606 45351 22016 45351 22016 45352 22606 45352 19917 45352 22016 45353 19917 45353 22608 45353 22608 45354 19917 45354 22607 45354 22608 45355 22607 45355 22019 45355 22057 45356 16474 45356 19895 45356 22057 45357 19895 45357 22058 45357 22058 45358 19895 45358 22609 45358 22058 45359 22609 45359 22059 45359 22059 45360 22609 45360 19893 45360 22059 45361 19893 45361 22062 45361 22062 45362 19893 45362 22610 45362 22062 45363 22610 45363 22063 45363 22063 45364 22610 45364 19892 45364 22063 45365 19892 45365 22612 45365 22612 45366 19892 45366 22611 45366 22612 45367 22611 45367 22065 45367 22065 45368 22611 45368 22613 45368 22065 45369 22613 45369 22066 45369 22066 45370 22613 45370 22614 45370 22066 45371 22614 45371 22068 45371 22068 45372 22614 45372 22615 45372 22068 45373 22615 45373 22616 45373 22616 45374 22615 45374 19888 45374 22616 45375 19888 45375 22071 45375 22071 45376 19888 45376 19886 45376 22071 45377 19886 45377 22072 45377 22072 45378 19886 45378 19884 45378 22072 45379 19884 45379 22617 45379 22617 45380 19884 45380 19882 45380 22617 45381 19882 45381 22075 45381 22075 45382 19882 45382 22619 45382 22075 45383 22619 45383 22618 45383 22618 45384 22619 45384 19881 45384 22618 45385 19881 45385 22620 45385 22620 45386 19881 45386 19878 45386 22620 45387 19878 45387 22078 45387 22078 45388 19878 45388 19876 45388 22078 45389 19876 45389 22621 45389 22621 45390 19876 45390 19875 45390 22621 45391 19875 45391 22080 45391 22080 45392 19875 45392 16490 45392 22080 45393 16490 45393 15068 45393 22101 45394 22622 45394 19877 45394 22101 45395 19877 45395 22624 45395 22624 45396 19877 45396 22623 45396 22624 45397 22623 45397 22625 45397 22625 45398 22623 45398 19879 45398 22625 45399 19879 45399 22626 45399 22626 45400 19879 45400 19880 45400 22626 45401 19880 45401 22102 45401 22102 45402 19880 45402 22627 45402 22102 45403 22627 45403 22103 45403 22103 45404 22627 45404 19883 45404 22103 45405 19883 45405 22628 45405 22628 45406 19883 45406 19885 45406 22628 45407 19885 45407 22105 45407 22105 45408 19885 45408 22629 45408 22105 45409 22629 45409 22106 45409 22106 45410 22629 45410 19887 45410 22106 45411 19887 45411 22107 45411 22107 45412 19887 45412 19889 45412 22107 45413 19889 45413 22108 45413 22108 45414 19889 45414 22630 45414 22108 45415 22630 45415 22110 45415 22110 45416 22630 45416 22631 45416 22110 45417 22631 45417 22112 45417 22112 45418 22631 45418 19890 45418 22112 45419 19890 45419 22113 45419 22113 45420 19890 45420 19891 45420 22113 45421 19891 45421 22632 45421 22632 45422 19891 45422 22633 45422 22632 45423 22633 45423 22115 45423 22115 45424 22633 45424 22634 45424 22115 45425 22634 45425 22116 45425 22116 45426 22634 45426 19894 45426 22116 45427 19894 45427 22118 45427 22118 45428 19894 45428 22635 45428 22118 45429 22635 45429 22120 45429 22120 45430 22635 45430 22636 45430 22120 45431 22636 45431 22121 45431 22173 45432 15044 45432 22637 45432 22173 45433 22637 45433 22174 45433 22174 45434 22637 45434 19874 45434 22174 45435 19874 45435 22175 45435 22175 45436 19874 45436 22638 45436 22175 45437 22638 45437 22178 45437 22178 45438 22638 45438 22639 45438 22178 45439 22639 45439 22640 45439 22640 45440 22639 45440 19872 45440 22640 45441 19872 45441 22641 45441 22641 45442 19872 45442 19870 45442 22641 45443 19870 45443 22642 45443 22642 45444 19870 45444 22643 45444 22642 45445 22643 45445 22644 45445 22644 45446 22643 45446 22645 45446 22644 45447 22645 45447 22180 45447 22180 45448 22645 45448 22646 45448 22180 45449 22646 45449 22181 45449 22181 45450 22646 45450 19868 45450 22181 45451 19868 45451 22647 45451 22647 45452 19868 45452 19867 45452 22647 45453 19867 45453 22648 45453 22648 45454 19867 45454 19866 45454 22648 45455 19866 45455 22649 45455 22649 45456 19866 45456 19865 45456 22649 45457 19865 45457 22183 45457 22183 45458 19865 45458 19864 45458 22183 45459 19864 45459 22184 45459 22184 45460 19864 45460 22651 45460 22184 45461 22651 45461 22650 45461 22650 45462 22651 45462 22652 45462 22650 45463 22652 45463 22653 45463 22653 45464 22652 45464 19859 45464 22653 45465 19859 45465 22185 45465 22185 45466 19859 45466 19858 45466 22185 45467 19858 45467 22186 45467 22186 45468 19858 45468 15032 45468 22186 45469 15032 45469 15033 45469 22654 45470 22655 45470 22656 45470 22654 45471 22656 45471 22203 45471 22203 45472 22656 45472 19860 45472 22203 45473 19860 45473 22204 45473 22204 45474 19860 45474 19861 45474 22204 45475 19861 45475 22205 45475 22205 45476 19861 45476 19862 45476 22205 45477 19862 45477 22207 45477 22207 45478 19862 45478 19863 45478 22207 45479 19863 45479 22208 45479 22208 45480 19863 45480 22657 45480 22208 45481 22657 45481 22658 45481 22658 45482 22657 45482 22659 45482 22658 45483 22659 45483 22209 45483 22209 45484 22659 45484 22660 45484 22209 45485 22660 45485 22661 45485 22661 45486 22660 45486 19869 45486 22661 45487 19869 45487 22662 45487 22662 45488 19869 45488 22663 45488 22662 45489 22663 45489 22212 45489 22212 45490 22663 45490 22664 45490 22212 45491 22664 45491 22665 45491 22665 45492 22664 45492 22666 45492 22665 45493 22666 45493 22214 45493 22214 45494 22666 45494 22667 45494 22214 45495 22667 45495 22216 45495 22216 45496 22667 45496 19871 45496 22216 45497 19871 45497 22217 45497 22217 45498 19871 45498 19873 45498 22217 45499 19873 45499 22668 45499 22668 45500 19873 45500 22669 45500 22668 45501 22669 45501 22670 45501 22670 45502 22669 45502 22671 45502 22670 45503 22671 45503 22672 45503 22672 45504 22671 45504 22673 45504 22672 45505 22673 45505 22220 45505 22220 45506 22673 45506 15012 45506 22220 45507 15012 45507 22221 45507 15011 45508 19857 45508 22674 45508 15011 45509 22674 45509 22676 45509 22676 45510 22674 45510 22675 45510 22676 45511 22675 45511 22677 45511 22677 45512 22675 45512 22678 45512 22677 45513 22678 45513 22269 45513 22269 45514 22678 45514 19854 45514 22269 45515 19854 45515 22679 45515 22679 45516 19854 45516 22680 45516 22679 45517 22680 45517 22270 45517 22270 45518 22680 45518 19853 45518 22270 45519 19853 45519 22681 45519 22681 45520 19853 45520 22682 45520 22681 45521 22682 45521 22683 45521 22683 45522 22682 45522 22684 45522 22683 45523 22684 45523 22274 45523 22274 45524 22684 45524 22685 45524 22274 45525 22685 45525 22686 45525 22686 45526 22685 45526 19850 45526 22686 45527 19850 45527 22687 45527 22687 45528 19850 45528 19848 45528 22687 45529 19848 45529 22276 45529 22276 45530 19848 45530 22688 45530 22276 45531 22688 45531 22277 45531 22277 45532 22688 45532 22689 45532 22277 45533 22689 45533 22690 45533 22690 45534 22689 45534 19844 45534 22690 45535 19844 45535 22691 45535 22691 45536 19844 45536 19843 45536 22691 45537 19843 45537 22282 45537 22282 45538 19843 45538 22692 45538 22282 45539 22692 45539 22283 45539 22283 45540 22692 45540 22693 45540 22283 45541 22693 45541 22284 45541 22284 45542 22693 45542 19841 45542 22284 45543 19841 45543 22285 45543 22285 45544 19841 45544 14994 45544 22285 45545 14994 45545 22287 45545 22303 45546 22694 45546 22695 45546 22303 45547 22695 45547 22304 45547 22304 45548 22695 45548 19842 45548 22304 45549 19842 45549 22696 45549 22696 45550 19842 45550 22697 45550 22696 45551 22697 45551 22698 45551 22698 45552 22697 45552 19845 45552 22698 45553 19845 45553 22699 45553 22699 45554 19845 45554 22700 45554 22699 45555 22700 45555 22701 45555 22701 45556 22700 45556 19846 45556 22701 45557 19846 45557 22306 45557 22306 45558 19846 45558 19847 45558 22306 45559 19847 45559 22308 45559 22308 45560 19847 45560 22703 45560 22308 45561 22703 45561 22702 45561 22702 45562 22703 45562 19849 45562 22702 45563 19849 45563 22704 45563 22704 45564 19849 45564 19851 45564 22704 45565 19851 45565 22310 45565 22310 45566 19851 45566 22705 45566 22310 45567 22705 45567 22311 45567 22311 45568 22705 45568 19852 45568 22311 45569 19852 45569 22706 45569 22706 45570 19852 45570 22707 45570 22706 45571 22707 45571 22708 45571 22708 45572 22707 45572 19855 45572 22708 45573 19855 45573 22314 45573 22314 45574 19855 45574 22709 45574 22314 45575 22709 45575 22315 45575 22315 45576 22709 45576 19856 45576 22315 45577 19856 45577 22710 45577 22710 45578 19856 45578 22711 45578 22710 45579 22711 45579 22712 45579 22712 45580 22711 45580 22713 45580 22712 45581 22713 45581 22714 45581 22714 45582 22713 45582 22715 45582 22714 45583 22715 45583 14976 45583 22366 45584 19818 45584 22716 45584 22366 45585 22716 45585 22368 45585 22368 45586 22716 45586 22717 45586 22368 45587 22717 45587 22718 45587 22718 45588 22717 45588 22719 45588 22718 45589 22719 45589 22721 45589 22721 45590 22719 45590 22720 45590 22721 45591 22720 45591 22722 45591 22722 45592 22720 45592 22723 45592 22722 45593 22723 45593 22372 45593 22372 45594 22723 45594 22724 45594 22372 45595 22724 45595 22725 45595 22725 45596 22724 45596 19814 45596 22725 45597 19814 45597 22376 45597 22376 45598 19814 45598 22727 45598 22376 45599 22727 45599 22726 45599 22726 45600 22727 45600 22728 45600 22726 45601 22728 45601 22729 45601 22729 45602 22728 45602 19811 45602 22729 45603 19811 45603 22378 45603 22378 45604 19811 45604 22730 45604 22378 45605 22730 45605 22380 45605 22380 45606 22730 45606 19809 45606 22380 45607 19809 45607 22381 45607 22381 45608 19809 45608 19808 45608 22381 45609 19808 45609 22382 45609 22382 45610 19808 45610 22732 45610 22382 45611 22732 45611 22731 45611 22731 45612 22732 45612 19805 45612 22731 45613 19805 45613 22733 45613 22733 45614 19805 45614 22734 45614 22733 45615 22734 45615 22384 45615 22384 45616 22734 45616 19803 45616 22384 45617 19803 45617 22385 45617 22385 45618 19803 45618 22735 45618 22385 45619 22735 45619 22736 45619 22736 45620 22735 45620 14957 45620 22736 45621 14957 45621 14958 45621 22737 45622 22738 45622 22739 45622 22737 45623 22739 45623 22740 45623 22740 45624 22739 45624 19804 45624 22740 45625 19804 45625 22741 45625 22741 45626 19804 45626 19806 45626 22741 45627 19806 45627 22399 45627 22399 45628 19806 45628 19807 45628 22399 45629 19807 45629 22401 45629 22401 45630 19807 45630 22742 45630 22401 45631 22742 45631 22402 45631 22402 45632 22742 45632 19810 45632 22402 45633 19810 45633 22744 45633 22744 45634 19810 45634 22743 45634 22744 45635 22743 45635 22745 45635 22745 45636 22743 45636 22746 45636 22745 45637 22746 45637 22747 45637 22747 45638 22746 45638 22748 45638 22747 45639 22748 45639 22405 45639 22405 45640 22748 45640 19812 45640 22405 45641 19812 45641 22406 45641 22406 45642 19812 45642 19813 45642 22406 45643 19813 45643 22749 45643 22749 45644 19813 45644 22750 45644 22749 45645 22750 45645 22409 45645 22409 45646 22750 45646 22751 45646 22409 45647 22751 45647 22411 45647 22411 45648 22751 45648 19815 45648 22411 45649 19815 45649 22752 45649 22752 45650 19815 45650 22753 45650 22752 45651 22753 45651 22414 45651 22414 45652 22753 45652 19816 45652 22414 45653 19816 45653 22415 45653 22415 45654 19816 45654 19817 45654 22415 45655 19817 45655 22754 45655 22754 45656 19817 45656 22756 45656 22754 45657 22756 45657 22755 45657 22755 45658 22756 45658 16547 45658 22755 45659 16547 45659 22757 45659 22455 45660 14941 45660 22759 45660 22455 45661 22759 45661 22758 45661 22758 45662 22759 45662 22760 45662 22758 45663 22760 45663 22761 45663 22761 45664 22760 45664 19838 45664 22761 45665 19838 45665 22458 45665 22458 45666 19838 45666 19836 45666 22458 45667 19836 45667 22762 45667 22762 45668 19836 45668 19835 45668 22762 45669 19835 45669 22460 45669 22460 45670 19835 45670 19833 45670 22460 45671 19833 45671 22462 45671 22462 45672 19833 45672 22763 45672 22462 45673 22763 45673 22464 45673 22464 45674 22763 45674 22764 45674 22464 45675 22764 45675 22466 45675 22466 45676 22764 45676 19831 45676 22466 45677 19831 45677 22765 45677 22765 45678 19831 45678 19830 45678 22765 45679 19830 45679 22470 45679 22470 45680 19830 45680 19829 45680 22470 45681 19829 45681 22766 45681 22766 45682 19829 45682 19828 45682 22766 45683 19828 45683 22472 45683 22472 45684 19828 45684 22767 45684 22472 45685 22767 45685 22474 45685 22474 45686 22767 45686 22768 45686 22474 45687 22768 45687 22476 45687 22476 45688 22768 45688 19823 45688 22476 45689 19823 45689 22769 45689 22769 45690 19823 45690 22771 45690 22769 45691 22771 45691 22770 45691 22770 45692 22771 45692 19822 45692 22770 45693 19822 45693 22772 45693 22772 45694 19822 45694 19820 45694 22772 45695 19820 45695 22478 45695 22478 45696 19820 45696 14918 45696 22478 45697 14918 45697 22479 45697 22773 45698 22888 45698 22886 45698 22773 45699 22886 45699 22989 45699 22989 45700 22886 45700 22775 45700 22989 45701 22775 45701 22774 45701 22774 45702 22775 45702 22885 45702 22774 45703 22885 45703 22776 45703 22776 45704 22885 45704 22777 45704 22776 45705 22777 45705 22988 45705 22778 45706 22894 45706 22779 45706 22779 45707 22894 45707 22780 45707 22894 45708 22895 45708 22780 45708 22780 45709 22895 45709 22893 45709 22780 45710 22893 45710 22983 45710 22781 45711 22986 45711 22782 45711 22782 45712 22986 45712 22983 45712 22782 45713 22983 45713 22783 45713 22783 45714 22983 45714 22893 45714 22991 45715 22785 45715 22784 45715 22784 45716 22785 45716 22890 45716 22784 45717 22890 45717 22786 45717 22786 45718 22890 45718 22787 45718 22786 45719 22787 45719 22984 45719 22984 45720 22787 45720 22892 45720 22984 45721 22892 45721 22985 45721 22985 45722 22892 45722 20023 45722 22990 45723 22788 45723 22987 45723 22987 45724 22788 45724 22881 45724 22987 45725 22881 45725 22992 45725 22992 45726 22881 45726 22883 45726 22992 45727 22883 45727 22789 45727 22789 45728 22883 45728 22790 45728 22791 45729 22793 45729 22792 45729 22792 45730 22793 45730 22794 45730 22792 45731 22794 45731 22874 45731 22874 45732 22794 45732 22875 45732 22875 45733 22794 45733 22795 45733 22875 45734 22795 45734 22879 45734 22879 45735 22795 45735 22877 45735 22877 45736 22795 45736 22980 45736 22877 45737 22980 45737 22876 45737 22863 45738 20024 45738 22864 45738 22864 45739 20024 45739 22796 45739 22864 45740 22796 45740 22865 45740 22865 45741 22796 45741 22797 45741 22797 45742 22796 45742 22979 45742 22797 45743 22979 45743 22798 45743 22798 45744 22979 45744 22799 45744 22799 45745 22979 45745 22978 45745 22799 45746 22978 45746 22867 45746 22855 45747 22800 45747 22857 45747 22857 45748 22800 45748 22801 45748 22857 45749 22801 45749 22858 45749 22858 45750 22801 45750 22802 45750 22802 45751 22801 45751 22803 45751 22802 45752 22803 45752 22861 45752 22861 45753 22803 45753 22804 45753 22804 45754 22803 45754 22805 45754 22804 45755 22805 45755 22860 45755 22880 45756 22981 45756 22806 45756 22806 45757 22981 45757 22982 45757 22806 45758 22982 45758 22870 45758 22870 45759 22982 45759 22871 45759 22871 45760 22982 45760 22807 45760 22871 45761 22807 45761 22873 45761 22873 45762 22807 45762 22872 45762 22872 45763 22807 45763 22808 45763 22872 45764 22808 45764 22868 45764 19819 45765 22809 45765 20141 45765 20141 45766 22809 45766 20139 45766 20139 45767 22809 45767 20025 45767 20025 45768 22809 45768 19821 45768 20025 45769 19821 45769 22811 45769 22813 45770 20342 45770 19821 45770 19821 45771 20342 45771 22810 45771 19821 45772 22810 45772 22811 45772 19824 45773 22812 45773 22813 45773 22813 45774 22812 45774 20332 45774 22813 45775 20332 45775 20342 45775 20216 45776 20217 45776 19825 45776 19825 45777 20217 45777 20224 45777 19825 45778 20224 45778 19824 45778 19824 45779 20224 45779 20230 45779 19824 45780 20230 45780 22812 45780 20321 45781 22814 45781 19826 45781 19826 45782 22814 45782 22815 45782 19826 45783 22815 45783 19825 45783 19825 45784 22815 45784 22816 45784 19825 45785 22816 45785 20216 45785 22817 45786 20326 45786 19827 45786 19827 45787 20326 45787 19826 45787 19826 45788 20326 45788 20319 45788 19826 45789 20319 45789 20321 45789 22818 45790 22820 45790 19827 45790 19827 45791 22820 45791 20163 45791 19827 45792 20163 45792 22817 45792 22824 45793 20314 45793 22819 45793 22819 45794 20314 45794 20306 45794 22819 45795 20306 45795 22818 45795 22818 45796 20306 45796 20166 45796 22818 45797 20166 45797 22820 45797 20171 45798 22822 45798 22821 45798 22821 45799 22822 45799 22823 45799 22821 45800 22823 45800 22824 45800 22824 45801 22823 45801 20309 45801 22824 45802 20309 45802 20314 45802 20171 45803 22821 45803 20188 45803 20188 45804 22821 45804 19832 45804 20188 45805 19832 45805 20187 45805 19834 45806 20199 45806 20302 45806 19834 45807 20302 45807 19832 45807 19832 45808 20302 45808 20301 45808 19832 45809 20301 45809 20187 45809 22827 45810 22825 45810 22826 45810 22826 45811 20038 45811 22827 45811 22827 45812 20038 45812 20037 45812 22827 45813 20037 45813 19834 45813 19834 45814 20037 45814 20197 45814 19834 45815 20197 45815 20199 45815 22825 45816 22827 45816 20173 45816 20173 45817 22827 45817 19837 45817 20173 45818 19837 45818 22828 45818 22828 45819 19837 45819 22829 45819 22829 45820 19837 45820 19839 45820 22829 45821 19839 45821 20131 45821 20131 45822 19839 45822 20136 45822 20136 45823 19839 45823 22830 45823 20136 45824 22830 45824 20132 45824 20132 45825 22830 45825 20295 45825 20295 45826 22830 45826 19840 45826 20295 45827 19840 45827 20292 45827 20292 45828 19840 45828 22831 45828 20292 45829 22831 45829 20288 45829 16567 45830 14894 45830 22833 45830 16567 45831 22833 45831 22832 45831 22832 45832 22833 45832 22834 45832 22832 45833 22834 45833 22836 45833 22836 45834 22834 45834 22835 45834 22836 45835 22835 45835 19756 45835 19756 45836 22835 45836 22837 45836 19756 45837 22837 45837 22838 45837 22838 45838 22837 45838 22839 45838 22838 45839 22839 45839 19754 45839 19754 45840 22839 45840 22840 45840 19754 45841 22840 45841 19752 45841 19752 45842 22840 45842 19986 45842 19752 45843 19986 45843 19751 45843 19751 45844 19986 45844 19984 45844 19751 45845 19984 45845 22841 45845 22841 45846 19984 45846 22843 45846 22841 45847 22843 45847 22842 45847 22842 45848 22843 45848 22844 45848 22842 45849 22844 45849 22845 45849 22845 45850 22844 45850 19982 45850 22845 45851 19982 45851 19749 45851 19749 45852 19982 45852 22846 45852 19749 45853 22846 45853 22847 45853 22847 45854 22846 45854 22848 45854 22847 45855 22848 45855 19746 45855 19746 45856 22848 45856 22849 45856 19746 45857 22849 45857 19745 45857 19745 45858 22849 45858 22850 45858 19745 45859 22850 45859 22851 45859 22851 45860 22850 45860 19981 45860 22851 45861 19981 45861 22852 45861 22852 45862 19981 45862 19980 45862 22852 45863 19980 45863 19742 45863 19742 45864 19980 45864 22853 45864 19742 45865 22853 45865 19741 45865 19741 45866 22853 45866 22854 45866 19741 45867 22854 45867 14872 45867 21500 45868 22860 45868 21501 45868 21501 45869 22860 45869 22863 45869 22856 45870 21517 45870 22855 45870 22855 45871 22857 45871 22856 45871 22856 45872 22857 45872 22858 45872 22856 45873 22858 45873 22859 45873 22859 45874 22858 45874 22802 45874 22859 45875 22802 45875 21499 45875 22860 45876 21500 45876 22804 45876 22804 45877 21500 45877 21499 45877 22804 45878 21499 45878 22861 45878 22861 45879 21499 45879 22802 45879 22862 45880 21501 45880 22863 45880 22863 45881 22864 45881 22862 45881 22862 45882 22864 45882 22865 45882 22862 45883 22865 45883 22866 45883 22866 45884 22865 45884 22797 45884 22866 45885 22797 45885 21492 45885 22867 45886 21509 45886 22799 45886 22799 45887 21509 45887 21492 45887 22799 45888 21492 45888 22798 45888 22798 45889 21492 45889 22797 45889 21516 45890 22868 45890 21517 45890 21517 45891 22868 45891 22855 45891 22791 45892 21508 45892 22867 45892 22867 45893 21508 45893 21509 45893 22869 45894 21518 45894 22880 45894 22880 45895 22806 45895 22869 45895 22869 45896 22806 45896 22870 45896 22869 45897 22870 45897 21513 45897 21513 45898 22870 45898 22871 45898 21513 45899 22871 45899 21515 45899 22868 45900 21516 45900 22872 45900 22872 45901 21516 45901 21515 45901 22872 45902 21515 45902 22873 45902 22873 45903 21515 45903 22871 45903 21507 45904 21508 45904 22791 45904 22791 45905 22792 45905 21507 45905 21507 45906 22792 45906 22874 45906 21507 45907 22874 45907 21502 45907 21502 45908 22874 45908 22875 45908 21502 45909 22875 45909 21503 45909 22876 45910 22878 45910 22877 45910 22877 45911 22878 45911 21503 45911 22877 45912 21503 45912 22879 45912 22879 45913 21503 45913 22875 45913 22878 45914 22876 45914 21518 45914 21518 45915 22876 45915 22880 45915 22882 45916 22788 45916 21564 45916 21564 45917 22788 45917 22777 45917 22788 45918 22882 45918 22881 45918 22881 45919 22882 45919 21563 45919 22881 45920 21563 45920 22883 45920 22883 45921 21563 45921 21558 45921 22883 45922 21558 45922 22790 45922 22790 45923 21558 45923 22887 45923 21564 45924 22777 45924 22884 45924 22884 45925 22777 45925 22885 45925 22884 45926 22885 45926 21543 45926 22888 45927 22889 45927 22886 45927 22886 45928 22889 45928 21543 45928 22886 45929 21543 45929 22775 45929 22775 45930 21543 45930 22885 45930 21541 45931 22785 45931 22887 45931 22887 45932 22785 45932 22790 45932 22781 45933 21550 45933 22888 45933 22888 45934 21550 45934 22889 45934 22785 45935 21541 45935 22890 45935 22890 45936 21541 45936 21542 45936 22890 45937 21542 45937 22787 45937 22787 45938 21542 45938 21555 45938 22787 45939 21555 45939 22892 45939 22892 45940 21555 45940 22891 45940 22892 45941 22891 45941 20023 45941 20023 45942 22891 45942 21554 45942 21549 45943 21550 45943 22781 45943 22781 45944 22782 45944 21549 45944 21549 45945 22782 45945 22783 45945 21549 45946 22783 45946 21548 45946 21548 45947 22783 45947 22893 45947 21548 45948 22893 45948 21553 45948 22778 45949 22896 45949 22894 45949 22894 45950 22896 45950 21553 45950 22894 45951 21553 45951 22895 45951 22895 45952 21553 45952 22893 45952 22896 45953 22778 45953 21554 45953 21554 45954 22778 45954 20023 45954 20011 45955 20000 45955 20001 45955 20011 45956 20001 45956 22898 45956 22898 45957 20001 45957 22897 45957 22898 45958 22897 45958 22899 45958 22899 45959 22897 45959 22900 45959 22899 45960 22900 45960 20014 45960 20014 45961 22900 45961 20002 45961 20014 45962 20002 45962 22902 45962 22902 45963 20002 45963 22901 45963 22902 45964 22901 45964 22903 45964 22903 45965 22901 45965 22904 45965 22903 45966 22904 45966 20015 45966 20015 45967 22904 45967 22906 45967 20015 45968 22906 45968 22905 45968 22905 45969 22906 45969 22907 45969 22905 45970 22907 45970 22908 45970 22908 45971 22907 45971 20004 45971 22908 45972 20004 45972 22909 45972 22909 45973 20004 45973 22910 45973 22909 45974 22910 45974 20016 45974 20016 45975 22910 45975 20005 45975 20016 45976 20005 45976 20010 45976 20010 45977 20005 45977 20007 45977 20010 45978 20007 45978 22911 45978 22911 45979 20007 45979 20009 45979 22911 45980 20009 45980 20012 45980 20009 45981 21546 45981 20012 45981 20012 45982 21546 45982 22913 45982 21493 45983 20000 45983 22914 45983 22914 45984 20000 45984 20011 45984 21561 45985 22912 45985 21546 45985 21546 45986 22912 45986 22913 45986 22917 45987 21497 45987 22914 45987 22914 45988 21497 45988 21493 45988 21561 45989 22915 45989 22912 45989 22912 45990 22915 45990 22916 45990 22926 45991 21497 45991 20022 45991 20022 45992 21497 45992 22917 45992 14871 45993 19992 45993 19995 45993 14871 45994 19995 45994 22918 45994 22918 45995 19995 45995 22919 45995 22918 45996 22919 45996 22920 45996 22920 45997 22919 45997 22921 45997 22920 45998 22921 45998 20019 45998 20019 45999 22921 45999 19998 45999 20019 46000 19998 46000 22922 46000 22922 46001 19998 46001 22923 46001 22922 46002 22923 46002 20020 46002 20020 46003 22923 46003 22924 46003 20020 46004 22924 46004 22925 46004 22925 46005 22924 46005 22926 46005 22925 46006 22926 46006 20022 46006 20605 46007 16192 46007 22927 46007 22927 46008 16192 46008 20604 46008 22927 46009 20604 46009 22928 46009 20603 46010 20604 46010 22929 46010 22929 46011 20604 46011 16192 46011 22929 46012 16192 46012 16194 46012 16194 46013 16192 46013 16193 46013 16189 46014 16190 46014 16187 46014 16187 46015 16190 46015 16192 46015 16187 46016 16192 46016 22930 46016 22930 46017 16192 46017 20605 46017 22937 46018 22932 46018 22931 46018 22931 46019 22932 46019 16199 46019 22931 46020 16199 46020 22933 46020 20598 46021 22931 46021 20597 46021 20597 46022 22931 46022 22933 46022 20597 46023 22933 46023 20595 46023 20595 46024 22933 46024 20593 46024 22934 46025 22935 46025 22936 46025 22936 46026 22935 46026 22932 46026 22936 46027 22932 46027 16195 46027 16195 46028 22932 46028 22937 46028 16203 46029 16204 46029 16205 46029 22938 46030 20583 46030 22940 46030 22940 46031 20583 46031 20584 46031 22940 46032 20584 46032 20586 46032 22938 46033 22940 46033 16205 46033 16205 46034 22940 46034 16200 46034 16205 46035 16200 46035 16203 46035 20591 46036 22939 46036 20590 46036 20590 46037 22939 46037 22940 46037 20590 46038 22940 46038 20587 46038 20587 46039 22940 46039 20586 46039 22941 46040 22945 46040 22946 46040 22942 46041 22943 46041 22944 46041 20578 46042 20580 46042 22947 46042 20574 46043 22946 46043 20573 46043 20573 46044 22946 46044 22945 46044 20573 46045 22945 46045 22944 46045 22944 46046 22945 46046 16206 46046 22944 46047 16206 46047 22942 46047 22941 46048 22946 46048 22947 46048 22947 46049 22946 46049 20576 46049 22947 46050 20576 46050 20578 46050 20564 46051 20566 46051 22948 46051 22951 46052 16216 46052 22953 46052 22953 46053 16216 46053 20564 46053 22953 46054 20564 46054 22949 46054 22949 46055 20564 46055 22948 46055 16212 46056 22950 46056 16211 46056 16211 46057 22950 46057 16213 46057 16211 46058 16213 46058 20572 46058 20572 46059 16213 46059 22951 46059 20572 46060 22951 46060 22952 46060 22952 46061 22951 46061 22953 46061 16217 46062 16219 46062 22956 46062 22956 46063 16219 46063 16220 46063 22956 46064 16220 46064 16222 46064 22956 46065 20559 46065 20561 46065 22954 46066 20556 46066 22955 46066 22955 46067 20556 46067 22956 46067 22955 46068 22956 46068 16223 46068 16223 46069 22956 46069 16222 46069 16217 46070 22956 46070 20562 46070 20562 46071 22956 46071 20561 46071 20562 46072 20561 46072 22957 46072 22958 46073 22959 46073 20554 46073 16226 46074 16228 46074 22964 46074 22964 46075 16228 46075 16230 46075 22964 46076 16230 46076 22963 46076 22960 46077 22961 46077 22962 46077 22962 46078 22961 46078 22964 46078 22962 46079 22964 46079 16232 46079 16232 46080 22964 46080 22963 46080 16226 46081 22964 46081 20554 46081 20554 46082 22964 46082 20553 46082 20554 46083 20553 46083 22958 46083 22969 46084 20551 46084 22968 46084 16238 46085 22965 46085 16236 46085 16236 46086 22965 46086 22966 46086 16236 46087 22966 46087 16235 46087 20547 46088 22967 46088 20545 46088 20545 46089 22967 46089 20548 46089 16235 46090 22966 46090 22968 46090 22968 46091 22966 46091 20545 46091 22968 46092 20545 46092 22969 46092 22969 46093 20545 46093 20548 46093 22969 46094 20548 46094 20550 46094 20541 46095 20542 46095 22970 46095 22970 46096 20542 46096 22973 46096 22970 46097 16246 46097 16247 46097 20540 46098 20541 46098 20538 46098 20538 46099 20541 46099 22970 46099 20538 46100 22970 46100 20537 46100 20537 46101 22970 46101 16247 46101 16241 46102 16242 46102 22971 46102 22971 46103 16242 46103 22970 46103 22971 46104 22970 46104 22972 46104 22972 46105 22970 46105 22973 46105 22976 46106 22975 46106 22977 46106 22977 46107 20530 46107 20531 46107 16253 46108 16256 46108 16252 46108 16252 46109 16256 46109 22974 46109 16252 46110 22974 46110 22976 46110 22976 46111 22974 46111 16257 46111 22976 46112 16257 46112 22975 46112 16249 46113 22976 46113 20535 46113 20535 46114 22976 46114 22977 46114 20535 46115 22977 46115 20533 46115 20533 46116 22977 46116 20531 46116 22805 46117 22803 46117 22801 46117 22793 46118 22978 46118 22808 46118 22808 46119 22978 46119 22979 46119 22808 46120 22979 46120 22796 46120 22796 46121 20024 46121 22808 46121 22808 46122 20024 46122 22805 46122 22808 46123 22805 46123 22800 46123 22800 46124 22805 46124 22801 46124 22795 46125 22794 46125 22980 46125 22980 46126 22794 46126 22793 46126 22980 46127 22793 46127 22981 46127 22981 46128 22793 46128 22808 46128 22981 46129 22808 46129 22982 46129 22982 46130 22808 46130 22807 46130 22784 46131 22773 46131 22991 46131 22991 46132 22773 46132 22989 46132 22779 46133 22780 46133 22983 46133 22786 46134 22984 46134 22784 46134 22784 46135 22984 46135 22985 46135 22784 46136 22985 46136 22773 46136 22773 46137 22985 46137 22779 46137 22773 46138 22779 46138 22986 46138 22986 46139 22779 46139 22983 46139 22990 46140 22987 46140 22992 46140 22774 46141 22776 46141 22989 46141 22989 46142 22776 46142 22988 46142 22989 46143 22988 46143 22991 46143 22991 46144 22988 46144 22990 46144 22991 46145 22990 46145 22789 46145 22789 46146 22990 46146 22992 46146 14865 46147 22993 46147 23054 46147 14865 46148 23054 46148 22994 46148 22994 46149 23054 46149 22995 46149 22994 46150 22995 46150 22996 46150 22996 46151 22995 46151 23055 46151 22996 46152 23055 46152 17754 46152 17754 46153 23055 46153 22997 46153 17754 46154 22997 46154 22998 46154 22998 46155 22997 46155 23056 46155 22998 46156 23056 46156 22999 46156 22999 46157 23056 46157 23057 46157 22999 46158 23057 46158 17752 46158 17752 46159 23057 46159 23000 46159 17752 46160 23000 46160 17751 46160 17751 46161 23000 46161 23059 46161 17751 46162 23059 46162 23001 46162 23001 46163 23059 46163 23002 46163 23001 46164 23002 46164 23003 46164 23003 46165 23002 46165 23004 46165 23003 46166 23004 46166 23005 46166 23005 46167 23004 46167 23006 46167 23005 46168 23006 46168 17747 46168 17747 46169 23006 46169 23061 46169 17747 46170 23061 46170 17746 46170 17746 46171 23061 46171 23063 46171 17746 46172 23063 46172 17744 46172 17744 46173 23063 46173 23007 46173 17744 46174 23007 46174 17743 46174 17743 46175 23007 46175 23008 46175 17743 46176 23008 46176 23009 46176 23009 46177 23008 46177 23064 46177 23009 46178 23064 46178 17772 46178 23104 46179 23010 46179 23045 46179 23104 46180 23045 46180 23105 46180 23105 46181 23045 46181 23012 46181 23105 46182 23012 46182 23011 46182 23011 46183 23012 46183 23043 46183 23011 46184 23043 46184 23107 46184 23107 46185 23043 46185 23042 46185 23107 46186 23042 46186 23013 46186 23013 46187 23042 46187 23040 46187 23013 46188 23040 46188 23014 46188 23014 46189 23040 46189 23015 46189 23014 46190 23015 46190 23097 46190 23097 46191 23015 46191 23038 46191 23097 46192 23038 46192 23016 46192 23016 46193 23038 46193 23036 46193 23016 46194 23036 46194 23017 46194 23017 46195 23036 46195 23034 46195 23017 46196 23034 46196 23018 46196 23018 46197 23034 46197 23020 46197 23018 46198 23020 46198 23019 46198 23019 46199 23020 46199 23022 46199 23019 46200 23022 46200 23021 46200 23021 46201 23022 46201 23032 46201 23021 46202 23032 46202 23023 46202 23023 46203 23032 46203 23024 46203 23023 46204 23024 46204 23111 46204 23111 46205 23024 46205 23031 46205 23111 46206 23031 46206 23025 46206 23025 46207 23031 46207 23030 46207 23025 46208 23030 46208 23026 46208 23026 46209 23030 46209 14834 46209 23026 46210 14834 46210 23027 46210 23028 46211 14834 46211 23030 46211 23028 46212 23030 46212 23029 46212 23029 46213 23030 46213 23031 46213 23029 46214 23031 46214 23078 46214 23078 46215 23031 46215 23024 46215 23078 46216 23024 46216 23080 46216 23080 46217 23024 46217 23032 46217 23080 46218 23032 46218 23082 46218 23082 46219 23032 46219 23022 46219 23082 46220 23022 46220 23033 46220 23033 46221 23022 46221 23020 46221 23033 46222 23020 46222 23083 46222 23083 46223 23020 46223 23034 46223 23083 46224 23034 46224 23035 46224 23035 46225 23034 46225 23036 46225 23035 46226 23036 46226 23086 46226 23086 46227 23036 46227 23038 46227 23086 46228 23038 46228 23037 46228 23037 46229 23038 46229 23015 46229 23037 46230 23015 46230 23039 46230 23039 46231 23015 46231 23040 46231 23039 46232 23040 46232 23041 46232 23041 46233 23040 46233 23042 46233 23041 46234 23042 46234 23090 46234 23090 46235 23042 46235 23043 46235 23090 46236 23043 46236 23044 46236 23044 46237 23043 46237 23012 46237 23044 46238 23012 46238 23092 46238 23092 46239 23012 46239 23045 46239 23092 46240 23045 46240 23046 46240 23046 46241 23045 46241 23010 46241 23046 46242 23010 46242 23095 46242 23047 46243 23049 46243 23048 46243 23048 46244 23049 46244 14814 46244 23048 46245 14814 46245 14861 46245 14861 46246 14814 46246 14817 46246 14861 46247 14817 46247 14862 46247 14862 46248 14817 46248 14818 46248 14862 46249 14818 46249 23050 46249 23050 46250 14818 46250 23052 46250 23050 46251 23052 46251 23051 46251 23051 46252 23052 46252 23053 46252 23051 46253 23053 46253 22993 46253 22993 46254 23053 46254 23075 46254 22993 46255 23075 46255 23054 46255 23054 46256 23075 46256 23076 46256 23054 46257 23076 46257 22995 46257 22995 46258 23076 46258 23077 46258 22995 46259 23077 46259 23055 46259 23055 46260 23077 46260 23079 46260 23055 46261 23079 46261 22997 46261 22997 46262 23079 46262 23081 46262 22997 46263 23081 46263 23056 46263 23056 46264 23081 46264 23084 46264 23056 46265 23084 46265 23057 46265 23057 46266 23084 46266 23058 46266 23057 46267 23058 46267 23000 46267 23000 46268 23058 46268 23085 46268 23000 46269 23085 46269 23059 46269 23059 46270 23085 46270 23087 46270 23059 46271 23087 46271 23002 46271 23002 46272 23087 46272 23060 46272 23002 46273 23060 46273 23004 46273 23004 46274 23060 46274 23088 46274 23004 46275 23088 46275 23006 46275 23006 46276 23088 46276 23089 46276 23006 46277 23089 46277 23061 46277 23061 46278 23089 46278 23091 46278 23061 46279 23091 46279 23063 46279 23063 46280 23091 46280 23062 46280 23063 46281 23062 46281 23007 46281 23007 46282 23062 46282 23093 46282 23007 46283 23093 46283 23008 46283 23008 46284 23093 46284 23094 46284 23008 46285 23094 46285 23064 46285 23064 46286 23094 46286 23065 46286 23064 46287 23065 46287 14850 46287 14850 46288 23065 46288 23066 46288 14850 46289 23066 46289 14851 46289 14851 46290 23066 46290 23067 46290 14851 46291 23067 46291 14853 46291 14853 46292 23067 46292 14806 46292 14853 46293 14806 46293 23068 46293 23068 46294 14806 46294 23069 46294 23068 46295 23069 46295 14855 46295 14855 46296 23069 46296 23070 46296 14855 46297 23070 46297 14856 46297 14856 46298 23070 46298 23071 46298 14856 46299 23071 46299 23072 46299 23072 46300 23071 46300 14810 46300 23072 46301 14810 46301 14859 46301 14859 46302 14810 46302 23073 46302 14859 46303 23073 46303 23074 46303 23074 46304 23073 46304 14811 46304 23074 46305 14811 46305 23047 46305 23047 46306 14811 46306 23049 46306 23075 46307 23028 46307 23029 46307 23075 46308 23029 46308 23076 46308 23076 46309 23029 46309 23078 46309 23076 46310 23078 46310 23077 46310 23077 46311 23078 46311 23080 46311 23077 46312 23080 46312 23079 46312 23079 46313 23080 46313 23082 46313 23079 46314 23082 46314 23081 46314 23081 46315 23082 46315 23033 46315 23081 46316 23033 46316 23084 46316 23084 46317 23033 46317 23083 46317 23084 46318 23083 46318 23058 46318 23058 46319 23083 46319 23035 46319 23058 46320 23035 46320 23085 46320 23085 46321 23035 46321 23086 46321 23085 46322 23086 46322 23087 46322 23087 46323 23086 46323 23037 46323 23087 46324 23037 46324 23060 46324 23060 46325 23037 46325 23039 46325 23060 46326 23039 46326 23088 46326 23088 46327 23039 46327 23041 46327 23088 46328 23041 46328 23089 46328 23089 46329 23041 46329 23090 46329 23089 46330 23090 46330 23091 46330 23091 46331 23090 46331 23044 46331 23091 46332 23044 46332 23062 46332 23062 46333 23044 46333 23092 46333 23062 46334 23092 46334 23093 46334 23093 46335 23092 46335 23046 46335 23093 46336 23046 46336 23094 46336 23094 46337 23046 46337 23095 46337 23094 46338 23095 46338 23065 46338 23106 46339 23013 46339 23687 46339 23687 46340 23013 46340 23014 46340 23687 46341 23014 46341 23096 46341 23096 46342 23014 46342 23097 46342 23096 46343 23097 46343 23686 46343 23686 46344 23097 46344 23016 46344 23686 46345 23016 46345 23098 46345 23098 46346 23016 46346 23017 46346 23098 46347 23017 46347 23684 46347 23684 46348 23017 46348 23018 46348 23684 46349 23018 46349 23682 46349 23682 46350 23018 46350 23019 46350 23682 46351 23019 46351 23681 46351 14616 46352 23099 46352 14615 46352 14615 46353 23099 46353 14846 46353 14615 46354 14846 46354 23100 46354 23100 46355 14846 46355 14847 46355 23100 46356 14847 46356 23101 46356 23101 46357 14847 46357 23102 46357 23101 46358 23102 46358 23103 46358 23103 46359 23102 46359 23104 46359 23103 46360 23104 46360 23690 46360 23690 46361 23104 46361 23105 46361 23690 46362 23105 46362 23689 46362 23689 46363 23105 46363 23011 46363 23689 46364 23011 46364 23106 46364 23106 46365 23011 46365 23107 46365 23106 46366 23107 46366 23013 46366 23118 46367 23119 46367 14623 46367 14623 46368 23119 46368 14838 46368 14623 46369 14838 46369 23108 46369 23108 46370 14838 46370 23109 46370 23108 46371 23109 46371 14621 46371 14621 46372 23109 46372 14839 46372 14621 46373 14839 46373 23110 46373 23110 46374 14839 46374 14840 46374 23110 46375 14840 46375 14620 46375 14620 46376 14840 46376 14841 46376 14620 46377 14841 46377 14618 46377 14618 46378 14841 46378 14843 46378 14618 46379 14843 46379 14616 46379 14616 46380 14843 46380 14845 46380 14616 46381 14845 46381 23099 46381 23019 46382 23021 46382 23681 46382 23681 46383 23021 46383 23023 46383 23681 46384 23023 46384 23679 46384 23679 46385 23023 46385 23111 46385 23679 46386 23111 46386 23112 46386 23112 46387 23111 46387 23025 46387 23112 46388 23025 46388 23677 46388 23677 46389 23025 46389 23026 46389 23677 46390 23026 46390 23113 46390 23113 46391 23026 46391 23027 46391 23113 46392 23027 46392 23115 46392 23115 46393 23027 46393 23114 46393 23115 46394 23114 46394 23116 46394 23116 46395 23114 46395 23117 46395 23116 46396 23117 46396 23118 46396 23118 46397 23117 46397 14837 46397 23118 46398 14837 46398 23119 46398 23120 46399 14593 46399 23123 46399 23122 46400 23838 46400 23121 46400 23122 46401 23123 46401 23839 46401 23839 46402 23123 46402 14591 46402 23839 46403 14591 46403 23128 46403 23122 46404 23121 46404 23123 46404 23123 46405 23121 46405 23124 46405 23123 46406 23124 46406 23120 46406 23842 46407 23125 46407 23126 46407 23126 46408 23125 46408 23839 46408 23126 46409 23839 46409 23127 46409 23127 46410 23839 46410 23128 46410 14552 46411 23629 46411 23129 46411 23129 46412 23629 46412 23130 46412 23129 46413 23130 46413 23131 46413 23131 46414 23130 46414 23132 46414 23131 46415 23132 46415 23881 46415 23881 46416 23132 46416 23133 46416 23881 46417 23133 46417 23882 46417 23882 46418 23133 46418 23419 46418 23882 46419 23419 46419 23883 46419 23883 46420 23419 46420 23643 46420 23883 46421 23643 46421 14544 46421 14544 46422 23643 46422 23645 46422 14562 46423 23477 46423 23872 46423 23872 46424 23477 46424 23134 46424 23872 46425 23134 46425 23135 46425 23135 46426 23134 46426 23620 46426 23135 46427 23620 46427 23874 46427 23874 46428 23620 46428 23136 46428 23874 46429 23136 46429 23876 46429 23876 46430 23136 46430 23137 46430 23876 46431 23137 46431 23138 46431 23138 46432 23137 46432 23139 46432 23138 46433 23139 46433 14554 46433 14554 46434 23139 46434 23476 46434 14788 46435 23140 46435 23866 46435 23866 46436 23140 46436 23141 46436 23866 46437 23141 46437 23143 46437 23143 46438 23141 46438 23142 46438 23143 46439 23142 46439 23144 46439 23144 46440 23142 46440 23429 46440 23144 46441 23429 46441 23145 46441 23145 46442 23429 46442 23146 46442 23145 46443 23146 46443 23147 46443 23147 46444 23146 46444 23485 46444 23147 46445 23485 46445 14563 46445 14563 46446 23485 46446 23148 46446 23149 46447 23640 46447 14569 46447 23153 46448 23154 46448 23405 46448 14569 46449 23150 46449 23149 46449 23149 46450 23150 46450 23151 46450 23149 46451 23151 46451 23405 46451 23405 46452 23151 46452 23152 46452 23405 46453 23152 46453 23153 46453 23153 46454 23862 46454 23154 46454 23154 46455 23862 46455 23155 46455 23154 46456 23155 46456 23158 46456 23857 46457 14781 46457 23156 46457 23156 46458 14781 46458 23489 46458 23156 46459 23489 46459 23157 46459 23157 46460 23489 46460 23158 46460 23157 46461 23158 46461 23159 46461 23159 46462 23158 46462 23155 46462 23852 46463 23495 46463 23160 46463 23160 46464 23495 46464 23496 46464 23160 46465 23496 46465 23161 46465 23161 46466 23496 46466 23163 46466 23161 46467 23163 46467 23162 46467 23162 46468 23163 46468 23494 46468 23162 46469 23494 46469 23165 46469 23165 46470 23494 46470 23164 46470 23165 46471 23164 46471 23166 46471 23166 46472 23164 46472 23167 46472 23166 46473 23167 46473 23168 46473 23168 46474 23167 46474 23169 46474 23170 46475 23511 46475 14759 46475 14759 46476 23848 46476 23170 46476 23170 46477 23848 46477 23849 46477 23170 46478 23849 46478 23171 46478 23172 46479 23175 46479 23513 46479 23849 46480 23847 46480 23171 46480 23171 46481 23847 46481 23173 46481 23171 46482 23173 46482 23513 46482 23513 46483 23173 46483 23845 46483 23513 46484 23845 46484 23172 46484 23172 46485 23174 46485 23175 46485 23175 46486 23174 46486 23176 46486 23175 46487 23176 46487 23474 46487 23474 46488 23176 46488 23179 46488 23474 46489 23179 46489 23505 46489 14765 46490 14766 46490 23177 46490 23177 46491 14766 46491 23505 46491 23177 46492 23505 46492 23178 46492 23178 46493 23505 46493 23179 46493 14473 46494 23518 46494 23943 46494 23943 46495 23518 46495 23517 46495 23943 46496 23517 46496 23180 46496 23180 46497 23517 46497 23181 46497 23180 46498 23181 46498 23945 46498 23945 46499 23181 46499 23182 46499 23945 46500 23182 46500 23946 46500 23946 46501 23182 46501 23183 46501 23946 46502 23183 46502 23184 46502 23184 46503 23183 46503 23516 46503 23184 46504 23516 46504 23948 46504 23948 46505 23516 46505 23185 46505 14494 46506 23186 46506 23935 46506 23935 46507 23186 46507 23187 46507 23935 46508 23187 46508 23188 46508 23188 46509 23187 46509 23527 46509 23188 46510 23527 46510 23938 46510 23938 46511 23527 46511 23189 46511 23938 46512 23189 46512 23939 46512 23939 46513 23189 46513 23190 46513 23939 46514 23190 46514 23191 46514 23191 46515 23190 46515 23526 46515 23191 46516 23526 46516 23940 46516 23940 46517 23526 46517 23192 46517 23940 46518 23192 46518 23941 46518 23941 46519 23192 46519 23525 46519 14742 46520 23193 46520 23194 46520 23194 46521 23193 46521 23450 46521 23194 46522 23450 46522 23195 46522 23195 46523 23450 46523 23448 46523 23195 46524 23448 46524 23196 46524 23196 46525 23448 46525 23444 46525 23196 46526 23444 46526 23197 46526 23197 46527 23444 46527 23198 46527 23197 46528 23198 46528 23932 46528 23932 46529 23198 46529 23443 46529 23932 46530 23443 46530 23934 46530 23934 46531 23443 46531 23441 46531 23536 46532 23535 46532 14504 46532 14504 46533 23199 46533 23536 46533 23536 46534 23199 46534 23203 46534 23536 46535 23203 46535 23204 46535 23200 46536 23201 46536 23202 46536 23203 46537 23929 46537 23204 46537 23204 46538 23929 46538 23928 46538 23204 46539 23928 46539 23202 46539 23202 46540 23928 46540 23926 46540 23202 46541 23926 46541 23200 46541 23200 46542 23923 46542 23201 46542 23201 46543 23923 46543 23922 46543 23201 46544 23922 46544 23205 46544 23205 46545 23922 46545 23208 46545 23205 46546 23208 46546 23207 46546 14728 46547 14727 46547 23917 46547 23917 46548 14727 46548 23207 46548 23917 46549 23207 46549 23206 46549 23206 46550 23207 46550 23208 46550 23210 46551 14724 46551 14514 46551 14514 46552 23209 46552 23210 46552 23210 46553 23209 46553 23913 46553 23210 46554 23913 46554 23544 46554 23910 46555 23215 46555 23211 46555 23913 46556 23212 46556 23544 46556 23544 46557 23212 46557 23213 46557 23544 46558 23213 46558 23211 46558 23211 46559 23213 46559 23214 46559 23211 46560 23214 46560 23910 46560 23910 46561 23908 46561 23215 46561 23215 46562 23908 46562 23216 46562 23215 46563 23216 46563 23217 46563 23217 46564 23216 46564 23906 46564 23217 46565 23906 46565 23218 46565 14719 46566 14718 46566 23904 46566 23904 46567 14718 46567 23218 46567 23904 46568 23218 46568 23219 46568 23219 46569 23218 46569 23906 46569 23221 46570 23545 46570 23220 46570 23220 46571 23902 46571 23221 46571 23221 46572 23902 46572 23900 46572 23221 46573 23900 46573 23222 46573 23900 46574 23898 46574 23222 46574 23222 46575 23898 46575 23896 46575 23222 46576 23896 46576 23223 46576 23896 46577 23224 46577 23223 46577 23223 46578 23224 46578 23893 46578 23223 46579 23893 46579 23546 46579 23893 46580 23892 46580 23546 46580 23546 46581 23892 46581 23890 46581 23546 46582 23890 46582 23225 46582 23225 46583 23890 46583 23888 46583 23225 46584 23888 46584 23226 46584 14543 46585 14710 46585 23886 46585 23886 46586 14710 46586 23226 46586 23886 46587 23226 46587 23887 46587 23887 46588 23226 46588 23888 46588 23776 46589 23227 46589 23778 46589 23778 46590 23227 46590 23554 46590 23778 46591 23554 46591 23779 46591 23779 46592 23554 46592 23547 46592 23227 46593 23776 46593 23228 46593 23228 46594 23776 46594 23229 46594 23228 46595 23229 46595 23230 46595 23230 46596 23229 46596 23774 46596 23230 46597 23774 46597 23553 46597 23553 46598 23774 46598 23231 46598 23553 46599 23231 46599 23775 46599 23766 46600 23435 46600 23772 46600 23772 46601 23435 46601 23549 46601 23772 46602 23549 46602 23232 46602 23232 46603 23549 46603 23551 46603 23770 46604 23234 46604 23233 46604 23233 46605 23234 46605 23478 46605 23233 46606 23478 46606 23235 46606 23235 46607 23478 46607 23236 46607 23235 46608 23236 46608 23767 46608 23767 46609 23236 46609 23237 46609 23767 46610 23237 46610 23766 46610 23766 46611 23237 46611 23435 46611 23764 46612 23482 46612 23765 46612 23765 46613 23482 46613 23481 46613 23765 46614 23481 46614 23770 46614 23770 46615 23481 46615 23234 46615 23784 46616 23238 46616 23787 46616 23787 46617 23238 46617 23240 46617 23787 46618 23240 46618 23239 46618 23239 46619 23240 46619 23241 46619 23239 46620 23241 46620 23764 46620 23764 46621 23241 46621 23482 46621 23784 46622 23242 46622 23238 46622 23238 46623 23242 46623 23243 46623 23779 46624 23547 46624 23781 46624 23781 46625 23547 46625 23244 46625 23781 46626 23244 46626 23782 46626 23782 46627 23244 46627 23245 46627 23782 46628 23245 46628 23242 46628 23242 46629 23245 46629 23243 46629 23252 46630 23500 46630 23755 46630 23755 46631 23500 46631 23501 46631 23755 46632 23501 46632 23246 46632 23246 46633 23501 46633 23259 46633 23754 46634 23497 46634 23247 46634 23247 46635 23497 46635 23248 46635 23247 46636 23248 46636 23250 46636 23250 46637 23248 46637 23249 46637 23250 46638 23249 46638 23251 46638 23251 46639 23249 46639 23498 46639 23251 46640 23498 46640 23252 46640 23252 46641 23498 46641 23500 46641 23751 46642 23402 46642 23253 46642 23253 46643 23402 46643 23401 46643 23253 46644 23401 46644 23754 46644 23754 46645 23401 46645 23497 46645 23254 46646 23404 46646 23751 46646 23751 46647 23404 46647 23402 46647 23255 46648 23558 46648 23743 46648 23743 46649 23558 46649 23557 46649 23743 46650 23557 46650 23749 46650 23749 46651 23557 46651 23556 46651 23758 46652 23561 46652 23256 46652 23256 46653 23561 46653 23257 46653 23256 46654 23257 46654 23762 46654 23762 46655 23257 46655 23560 46655 23762 46656 23560 46656 23255 46656 23255 46657 23560 46657 23558 46657 23758 46658 23258 46658 23561 46658 23561 46659 23258 46659 23261 46659 23246 46660 23259 46660 23756 46660 23756 46661 23259 46661 23555 46661 23756 46662 23555 46662 23757 46662 23757 46663 23555 46663 23260 46663 23757 46664 23260 46664 23258 46664 23258 46665 23260 46665 23261 46665 23732 46666 23390 46666 23262 46666 23262 46667 23390 46667 23263 46667 23262 46668 23263 46668 23734 46668 23734 46669 23263 46669 23578 46669 23565 46670 23390 46670 23732 46670 23726 46671 23264 46671 23265 46671 23265 46672 23264 46672 23266 46672 23265 46673 23266 46673 23728 46673 23728 46674 23266 46674 23267 46674 23728 46675 23267 46675 23727 46675 23727 46676 23267 46676 23565 46676 23727 46677 23565 46677 23268 46677 23268 46678 23565 46678 23732 46678 23723 46679 23271 46679 23725 46679 23725 46680 23271 46680 23269 46680 23725 46681 23269 46681 23726 46681 23726 46682 23269 46682 23264 46682 23722 46683 23499 46683 23720 46683 23720 46684 23499 46684 23569 46684 23720 46685 23569 46685 23719 46685 23719 46686 23569 46686 23270 46686 23719 46687 23270 46687 23723 46687 23723 46688 23270 46688 23271 46688 23277 46689 23562 46689 23272 46689 23272 46690 23562 46690 23273 46690 23272 46691 23273 46691 23274 46691 23274 46692 23273 46692 23275 46692 23738 46693 23280 46693 23741 46693 23741 46694 23280 46694 23563 46694 23741 46695 23563 46695 23276 46695 23276 46696 23563 46696 23278 46696 23276 46697 23278 46697 23277 46697 23277 46698 23278 46698 23562 46698 23738 46699 23279 46699 23280 46699 23280 46700 23279 46700 23283 46700 23734 46701 23578 46701 23281 46701 23281 46702 23578 46702 23579 46702 23281 46703 23579 46703 23737 46703 23737 46704 23579 46704 23282 46704 23737 46705 23282 46705 23279 46705 23279 46706 23282 46706 23283 46706 23286 46707 23465 46707 23284 46707 23284 46708 23465 46708 23469 46708 23284 46709 23469 46709 23714 46709 23714 46710 23469 46710 23470 46710 23465 46711 23286 46711 23285 46711 23285 46712 23286 46712 23287 46712 23285 46713 23287 46713 23468 46713 23287 46714 14603 46714 23468 46714 23468 46715 14603 46715 14604 46715 23468 46716 14604 46716 23467 46716 23709 46717 23288 46717 14606 46717 14606 46718 23288 46718 23467 46718 14606 46719 23467 46719 14605 46719 14605 46720 23467 46720 14604 46720 23707 46721 23293 46721 23708 46721 23708 46722 23293 46722 23456 46722 23708 46723 23456 46723 23709 46723 23709 46724 23456 46724 23288 46724 23703 46725 23290 46725 23289 46725 23289 46726 23290 46726 23291 46726 23289 46727 23291 46727 23705 46727 23705 46728 23291 46728 23575 46728 23705 46729 23575 46729 23292 46729 23292 46730 23575 46730 23574 46730 23292 46731 23574 46731 23707 46731 23707 46732 23574 46732 23293 46732 23295 46733 23577 46733 23294 46733 23294 46734 23577 46734 23576 46734 23294 46735 23576 46735 23703 46735 23703 46736 23576 46736 23290 46736 23702 46737 23580 46737 23295 46737 23295 46738 23580 46738 23577 46738 23700 46739 23296 46739 23297 46739 23297 46740 23296 46740 23298 46740 23714 46741 23470 46741 23715 46741 23715 46742 23470 46742 23590 46742 23715 46743 23590 46743 23717 46743 23717 46744 23590 46744 23299 46744 23717 46745 23299 46745 23296 46745 23296 46746 23299 46746 23298 46746 23827 46747 23586 46747 23828 46747 23828 46748 23586 46748 23584 46748 23828 46749 23584 46749 14705 46749 14705 46750 23584 46750 23582 46750 23826 46751 23411 46751 23825 46751 23825 46752 23411 46752 23300 46752 23825 46753 23300 46753 23824 46753 23824 46754 23300 46754 23588 46754 23824 46755 23588 46755 23821 46755 23821 46756 23588 46756 23301 46756 23821 46757 23301 46757 23827 46757 23827 46758 23301 46758 23586 46758 23819 46759 23303 46759 23820 46759 23820 46760 23303 46760 23302 46760 23820 46761 23302 46761 23826 46761 23826 46762 23302 46762 23411 46762 23304 46763 23303 46763 23819 46763 23819 46764 14596 46764 23304 46764 23304 46765 14596 46765 23305 46765 23304 46766 23305 46766 23309 46766 23306 46767 23307 46767 23818 46767 23818 46768 23307 46768 23597 46768 23818 46769 23597 46769 23308 46769 23308 46770 23597 46770 23309 46770 23308 46771 23309 46771 23815 46771 23815 46772 23309 46772 23305 46772 23835 46773 23589 46773 23813 46773 23813 46774 23589 46774 23600 46774 23813 46775 23600 46775 23306 46775 23306 46776 23600 46776 23307 46776 23311 46777 23594 46777 23834 46777 23834 46778 23594 46778 23593 46778 23834 46779 23593 46779 23310 46779 23310 46780 23593 46780 23591 46780 23310 46781 23591 46781 23835 46781 23835 46782 23591 46782 23589 46782 23311 46783 23832 46783 23594 46783 23594 46784 23832 46784 23595 46784 14595 46785 14706 46785 23830 46785 23830 46786 14706 46786 23312 46786 23830 46787 23312 46787 23832 46787 23832 46788 23312 46788 23595 46788 23798 46789 23479 46789 23313 46789 23313 46790 23479 46790 23480 46790 23313 46791 23480 46791 23802 46791 23802 46792 23480 46792 23483 46792 14704 46793 23428 46793 23798 46793 23798 46794 23428 46794 23479 46794 14597 46795 23314 46795 23796 46795 23796 46796 23314 46796 23315 46796 23796 46797 23315 46797 23316 46797 23316 46798 23315 46798 23317 46798 23314 46799 14597 46799 23607 46799 23607 46800 14597 46800 23318 46800 23607 46801 23318 46801 23608 46801 23608 46802 23318 46802 14599 46802 23608 46803 14599 46803 23319 46803 23793 46804 23585 46804 23792 46804 23792 46805 23585 46805 23319 46805 23792 46806 23319 46806 23320 46806 23320 46807 23319 46807 14599 46807 23789 46808 23322 46808 23790 46808 23790 46809 23322 46809 23583 46809 23790 46810 23583 46810 23793 46810 23793 46811 23583 46811 23585 46811 23807 46812 23321 46812 23808 46812 23808 46813 23321 46813 23606 46813 23808 46814 23606 46814 23810 46814 23810 46815 23606 46815 23605 46815 23810 46816 23605 46816 23789 46816 23789 46817 23605 46817 23322 46817 23807 46818 23323 46818 23321 46818 23321 46819 23323 46819 23652 46819 23802 46820 23483 46820 23803 46820 23803 46821 23483 46821 23602 46821 23803 46822 23602 46822 23324 46822 23324 46823 23602 46823 23325 46823 23324 46824 23325 46824 23323 46824 23323 46825 23325 46825 23652 46825 23432 46826 23431 46826 23326 46826 23326 46827 23327 46827 23432 46827 23432 46828 23327 46828 23956 46828 23432 46829 23956 46829 23434 46829 23956 46830 23953 46830 23434 46830 23434 46831 23953 46831 23328 46831 23434 46832 23328 46832 23617 46832 23617 46833 23328 46833 23952 46833 23617 46834 23952 46834 23618 46834 23952 46835 23329 46835 23618 46835 23618 46836 23329 46836 23330 46836 23618 46837 23330 46837 23437 46837 23330 46838 23951 46838 23437 46838 23437 46839 23951 46839 23949 46839 23437 46840 23949 46840 23436 46840 14472 46841 23331 46841 23332 46841 23332 46842 23331 46842 23436 46842 23332 46843 23436 46843 23333 46843 23333 46844 23436 46844 23949 46844 14680 46845 23646 46845 23334 46845 23334 46846 23646 46846 23335 46846 23334 46847 23335 46847 23957 46847 23957 46848 23335 46848 23644 46848 23957 46849 23644 46849 23336 46849 23336 46850 23644 46850 23337 46850 23336 46851 23337 46851 23960 46851 23960 46852 23337 46852 23339 46852 23960 46853 23339 46853 23338 46853 23338 46854 23339 46854 23424 46854 23338 46855 23424 46855 23340 46855 23340 46856 23424 46856 23426 46856 23630 46857 23341 46857 14445 46857 14445 46858 23968 46858 23630 46858 23630 46859 23968 46859 23969 46859 23630 46860 23969 46860 23631 46860 23969 46861 23342 46861 23631 46861 23631 46862 23342 46862 23967 46862 23631 46863 23967 46863 23343 46863 23967 46864 23966 46864 23343 46864 23343 46865 23966 46865 23965 46865 23343 46866 23965 46866 23344 46866 23344 46867 23965 46867 23964 46867 23344 46868 23964 46868 23346 46868 23964 46869 23963 46869 23346 46869 23346 46870 23963 46870 23345 46870 23346 46871 23345 46871 23347 46871 14677 46872 23624 46872 23348 46872 23348 46873 23624 46873 23347 46873 23348 46874 23347 46874 23961 46874 23961 46875 23347 46875 23345 46875 23349 46876 23414 46876 14440 46876 14440 46877 23982 46877 23349 46877 23349 46878 23982 46878 23350 46878 23349 46879 23350 46879 23417 46879 23350 46880 23983 46880 23417 46880 23417 46881 23983 46881 23351 46881 23417 46882 23351 46882 23418 46882 23351 46883 23978 46883 23418 46883 23418 46884 23978 46884 23353 46884 23418 46885 23353 46885 23352 46885 23352 46886 23353 46886 23976 46886 23352 46887 23976 46887 23354 46887 23976 46888 23975 46888 23354 46888 23354 46889 23975 46889 23974 46889 23354 46890 23974 46890 23355 46890 23356 46891 23540 46891 23970 46891 23970 46892 23540 46892 23355 46892 23970 46893 23355 46893 23973 46893 23973 46894 23355 46894 23974 46894 23439 46895 23991 46895 23455 46895 23455 46896 23991 46896 23989 46896 23455 46897 23989 46897 23357 46897 23989 46898 23358 46898 23357 46898 23357 46899 23358 46899 23359 46899 23357 46900 23359 46900 23361 46900 23361 46901 23359 46901 23360 46901 23360 46902 23987 46902 23361 46902 23361 46903 23987 46903 23362 46903 23361 46904 23362 46904 23453 46904 14667 46905 23451 46905 23363 46905 23363 46906 23451 46906 23364 46906 23363 46907 23364 46907 23365 46907 23365 46908 23364 46908 23453 46908 23365 46909 23453 46909 23985 46909 23985 46910 23453 46910 23362 46910 23457 46911 23998 46911 23366 46911 23366 46912 23998 46912 23997 46912 23366 46913 23997 46913 23466 46913 23466 46914 23997 46914 23996 46914 23466 46915 23996 46915 23367 46915 23367 46916 23996 46916 23995 46916 23368 46917 23461 46917 23993 46917 23993 46918 23461 46918 23369 46918 23993 46919 23369 46919 23994 46919 23994 46920 23369 46920 23370 46920 23994 46921 23370 46921 23995 46921 23995 46922 23370 46922 23438 46922 23995 46923 23438 46923 23367 46923 23371 46924 14652 46924 14421 46924 14421 46925 24007 46925 23371 46925 23371 46926 24007 46926 24009 46926 23371 46927 24009 46927 23372 46927 24009 46928 24006 46928 23372 46928 23372 46929 24006 46929 23373 46929 23372 46930 23373 46930 23374 46930 23374 46931 23373 46931 24004 46931 23374 46932 24004 46932 23375 46932 24004 46933 23376 46933 23375 46933 23375 46934 23376 46934 24002 46934 23375 46935 24002 46935 23406 46935 24002 46936 23377 46936 23406 46936 23406 46937 23377 46937 23380 46937 23406 46938 23380 46938 23407 46938 14426 46939 23514 46939 23378 46939 23378 46940 23514 46940 23407 46940 23378 46941 23407 46941 23379 46941 23379 46942 23407 46942 23380 46942 23571 46943 14413 46943 23570 46943 23570 46944 14413 46944 23381 46944 23570 46945 23381 46945 23382 46945 23382 46946 23381 46946 23383 46946 23382 46947 23383 46947 23385 46947 23385 46948 23383 46948 23384 46948 23385 46949 23384 46949 23568 46949 23568 46950 23384 46950 23386 46950 23568 46951 23386 46951 23567 46951 23567 46952 23386 46952 24012 46952 23567 46953 24012 46953 23472 46953 23472 46954 24012 46954 23387 46954 23472 46955 23387 46955 23512 46955 23396 46956 23397 46956 23388 46956 23664 46957 23399 46957 23663 46957 23670 46958 23389 46958 23409 46958 23315 46959 23609 46959 23317 46959 23314 46960 23612 46960 23315 46960 23608 46961 23319 46961 23587 46961 23390 46962 23565 46962 23290 46962 23282 46963 23579 46963 23649 46963 23524 46964 23525 46964 23564 46964 23391 46965 23392 46965 23435 46965 23393 46966 23675 46966 23460 46966 23460 46967 23675 46967 23442 46967 23394 46968 14610 46968 23167 46968 23663 46969 23395 46969 14609 46969 23663 46970 14609 46970 23396 46970 23396 46971 14609 46971 14608 46971 23396 46972 14608 46972 23397 46972 23397 46973 14608 46973 23691 46973 23397 46974 23691 46974 23398 46974 23395 46975 23663 46975 14610 46975 14610 46976 23663 46976 23399 46976 14610 46977 23399 46977 23167 46977 23394 46978 23167 46978 23400 46978 23400 46979 23167 46979 23164 46979 23400 46980 23164 46980 23494 46980 23556 46981 23559 46981 14708 46981 14708 46982 23559 46982 23403 46982 23697 46983 23497 46983 23698 46983 23698 46984 23497 46984 23401 46984 23698 46985 23401 46985 23695 46985 23695 46986 23401 46986 23402 46986 23695 46987 23402 46987 23490 46987 23490 46988 23402 46988 23404 46988 23490 46989 23404 46989 23403 46989 23403 46990 23404 46990 14709 46990 23403 46991 14709 46991 14708 46991 23158 46992 23403 46992 23154 46992 23154 46993 23403 46993 23641 46993 23154 46994 23641 46994 23405 46994 23405 46995 23641 46995 23149 46995 23515 46996 23407 46996 23514 46996 23372 46997 23374 46997 23473 46997 23473 46998 23374 46998 23375 46998 23473 46999 23375 46999 23515 46999 23515 47000 23375 47000 23406 47000 23515 47001 23406 47001 23407 47001 14657 47002 23389 47002 23408 47002 23408 47003 23389 47003 23523 47003 23408 47004 23523 47004 23514 47004 23668 47005 23409 47005 23410 47005 23410 47006 23409 47006 23389 47006 23410 47007 23389 47007 14656 47007 14656 47008 23389 47008 14657 47008 14656 47009 14654 47009 23410 47009 23410 47010 14654 47010 14653 47010 23410 47011 14653 47011 23506 47011 23506 47012 14653 47012 14652 47012 23506 47013 14652 47013 23473 47013 23473 47014 14652 47014 23371 47014 23473 47015 23371 47015 23372 47015 23302 47016 23413 47016 23411 47016 23411 47017 23413 47017 14722 47017 23411 47018 14722 47018 23300 47018 14670 47019 23412 47019 23302 47019 23302 47020 23412 47020 23414 47020 23302 47021 23414 47021 23413 47021 23413 47022 23414 47022 23349 47022 23413 47023 23349 47023 23415 47023 23415 47024 23349 47024 23417 47024 23415 47025 23417 47025 23416 47025 23416 47026 23417 47026 23418 47026 23416 47027 23418 47027 14718 47027 23540 47028 23538 47028 23205 47028 23355 47029 23539 47029 23354 47029 23354 47030 23539 47030 14627 47030 23218 47031 14718 47031 23636 47031 23636 47032 14718 47032 23418 47032 23636 47033 23418 47033 14627 47033 14627 47034 23418 47034 23352 47034 14627 47035 23352 47035 23354 47035 23628 47036 23132 47036 23130 47036 23132 47037 23628 47037 23133 47037 23133 47038 23628 47038 23420 47038 23133 47039 23420 47039 23419 47039 23643 47040 23419 47040 23644 47040 23644 47041 23419 47041 23420 47041 23644 47042 23420 47042 23337 47042 23337 47043 23420 47043 23421 47043 23337 47044 23421 47044 23339 47044 23339 47045 23421 47045 14639 47045 23339 47046 14639 47046 23424 47046 23629 47047 14802 47047 23423 47047 23423 47048 14802 47048 23422 47048 23423 47049 23422 47049 23647 47049 23424 47050 14639 47050 23426 47050 23426 47051 14639 47051 23425 47051 23426 47052 23425 47052 14691 47052 14691 47053 23425 47053 23623 47053 14691 47054 23623 47054 14690 47054 23428 47055 14686 47055 23477 47055 23477 47056 14686 47056 14687 47056 23477 47057 14687 47057 23134 47057 23134 47058 14687 47058 23620 47058 14702 47059 14679 47059 14703 47059 14703 47060 14679 47060 23427 47060 14703 47061 23427 47061 23428 47061 23428 47062 23427 47062 14685 47062 23428 47063 14685 47063 14686 47063 23610 47064 14681 47064 14679 47064 23429 47065 23142 47065 23486 47065 14700 47066 23486 47066 23430 47066 23430 47067 23486 47067 23142 47067 23430 47068 23142 47068 14696 47068 14696 47069 23142 47069 23141 47069 14700 47070 23431 47070 23486 47070 23486 47071 23431 47071 23432 47071 23486 47072 23432 47072 23433 47072 23433 47073 23432 47073 23434 47073 23433 47074 23434 47074 23617 47074 23549 47075 23435 47075 23331 47075 23331 47076 23435 47076 23392 47076 23331 47077 23392 47077 23436 47077 23436 47078 23392 47078 14790 47078 23436 47079 14790 47079 23437 47079 14739 47080 23370 47080 23460 47080 23370 47081 14739 47081 23438 47081 23439 47082 23598 47082 14663 47082 14663 47083 23598 47083 23367 47083 14739 47084 14738 47084 23438 47084 23438 47085 14738 47085 23440 47085 23438 47086 23440 47086 23367 47086 23367 47087 23440 47087 23441 47087 23367 47088 23441 47088 14663 47088 14663 47089 23441 47089 23443 47089 14663 47090 23443 47090 23445 47090 23450 47091 23193 47091 23442 47091 23442 47092 23193 47092 14743 47092 23442 47093 14743 47093 23460 47093 23460 47094 14743 47094 14741 47094 23460 47095 14741 47095 14739 47095 23443 47096 23198 47096 23445 47096 23445 47097 23198 47097 23444 47097 23445 47098 23444 47098 23446 47098 23446 47099 23444 47099 23448 47099 23446 47100 23448 47100 23447 47100 23447 47101 23448 47101 23450 47101 23447 47102 23450 47102 23449 47102 23449 47103 23450 47103 23442 47103 23449 47104 23442 47104 23451 47104 23451 47105 23442 47105 14626 47105 23451 47106 14626 47106 23364 47106 23364 47107 14626 47107 23452 47107 23364 47108 23452 47108 23453 47108 23453 47109 23452 47109 23454 47109 23455 47110 23357 47110 23596 47110 23596 47111 23357 47111 23361 47111 23288 47112 23456 47112 23366 47112 23366 47113 23456 47113 23457 47113 23457 47114 23456 47114 23293 47114 23457 47115 23293 47115 23564 47115 23529 47116 23463 47116 23459 47116 23459 47117 23463 47117 23458 47117 23459 47118 23458 47118 23528 47118 23370 47119 23369 47119 23460 47119 23460 47120 23369 47120 23461 47120 23460 47121 23461 47121 23393 47121 23393 47122 23461 47122 23462 47122 23393 47123 23462 47123 23463 47123 23463 47124 23462 47124 23464 47124 23463 47125 23464 47125 23458 47125 23465 47126 23285 47126 23598 47126 23366 47127 23466 47127 23288 47127 23288 47128 23466 47128 23367 47128 23288 47129 23367 47129 23467 47129 23467 47130 23367 47130 23598 47130 23467 47131 23598 47131 23468 47131 23468 47132 23598 47132 23285 47132 23465 47133 23598 47133 23469 47133 23469 47134 23598 47134 23599 47134 23469 47135 23599 47135 23470 47135 23471 47136 14649 47136 23667 47136 23472 47137 23175 47137 23473 47137 23473 47138 23175 47138 23474 47138 23437 47139 14790 47139 23618 47139 23618 47140 14790 47140 14789 47140 23618 47141 14789 47141 23616 47141 23616 47142 14789 47142 23476 47142 23616 47143 23476 47143 23475 47143 23476 47144 23139 47144 23475 47144 23475 47145 23139 47145 23137 47145 23475 47146 23137 47146 23136 47146 23241 47147 23240 47147 23603 47147 23391 47148 23435 47148 14793 47148 14793 47149 23435 47149 23237 47149 14793 47150 23237 47150 23477 47150 23477 47151 23237 47151 23236 47151 23477 47152 23236 47152 23428 47152 23236 47153 23478 47153 23428 47153 23428 47154 23478 47154 23234 47154 23428 47155 23234 47155 23479 47155 23479 47156 23234 47156 23480 47156 23480 47157 23234 47157 23481 47157 23480 47158 23481 47158 23483 47158 23483 47159 23481 47159 23482 47159 23483 47160 23482 47160 23602 47160 14643 47161 23614 47161 23484 47161 23484 47162 23614 47162 23148 47162 23484 47163 23148 47163 14642 47163 14642 47164 23148 47164 23485 47164 14642 47165 23485 47165 23486 47165 23486 47166 23485 47166 23146 47166 23486 47167 23146 47167 23429 47167 23487 47168 23642 47168 23140 47168 23140 47169 23642 47169 23552 47169 23140 47170 23552 47170 23141 47170 23141 47171 23552 47171 23550 47171 23141 47172 23550 47172 14696 47172 23487 47173 14787 47173 23642 47173 23642 47174 14787 47174 14786 47174 23642 47175 14786 47175 23488 47175 23488 47176 14786 47176 14783 47176 23158 47177 23489 47177 23403 47177 23403 47178 23489 47178 14781 47178 23403 47179 14781 47179 23490 47179 23490 47180 14781 47180 23491 47180 23490 47181 23491 47181 23693 47181 23693 47182 23491 47182 14779 47182 23693 47183 14779 47183 23398 47183 23398 47184 14779 47184 14778 47184 23398 47185 14778 47185 23397 47185 23397 47186 14778 47186 23492 47186 23397 47187 23492 47187 23388 47187 23388 47188 23492 47188 14777 47188 23388 47189 14777 47189 23660 47189 23660 47190 14777 47190 23640 47190 23660 47191 23640 47191 23493 47191 23163 47192 23497 47192 23494 47192 23494 47193 23497 47193 23697 47193 23494 47194 23697 47194 23400 47194 23499 47195 23498 47195 23249 47195 23495 47196 23499 47196 23496 47196 23496 47197 23499 47197 23249 47197 23496 47198 23249 47198 23163 47198 23163 47199 23249 47199 23248 47199 23163 47200 23248 47200 23497 47200 23498 47201 23499 47201 23500 47201 23500 47202 23499 47202 23275 47202 23500 47203 23275 47203 23501 47203 23501 47204 23275 47204 23273 47204 23501 47205 23273 47205 23259 47205 14773 47206 23502 47206 23572 47206 23572 47207 23502 47207 23504 47207 23572 47208 23504 47208 23573 47208 23502 47209 23503 47209 23504 47209 23504 47210 23503 47210 14770 47210 23504 47211 14770 47211 23664 47211 23664 47212 14770 47212 14768 47212 23664 47213 14768 47213 23399 47213 23399 47214 14768 47214 23169 47214 23399 47215 23169 47215 23167 47215 23474 47216 23505 47216 23473 47216 23473 47217 23505 47217 14766 47217 23473 47218 14766 47218 23506 47218 23506 47219 14766 47219 14764 47219 23506 47220 14764 47220 23410 47220 23410 47221 14764 47221 23507 47221 23410 47222 23507 47222 23668 47222 23507 47223 23508 47223 23668 47223 23668 47224 23508 47224 23509 47224 23668 47225 23509 47225 23667 47225 23667 47226 23509 47226 23510 47226 23667 47227 23510 47227 23471 47227 23471 47228 23510 47228 23511 47228 23471 47229 23511 47229 14650 47229 14650 47230 23511 47230 23170 47230 14650 47231 23170 47231 23512 47231 23512 47232 23170 47232 23171 47232 23512 47233 23171 47233 23472 47233 23472 47234 23171 47234 23513 47234 23472 47235 23513 47235 23175 47235 23514 47236 23523 47236 23515 47236 23515 47237 23523 47237 23185 47237 23515 47238 23185 47238 23516 47238 23516 47239 23183 47239 23515 47239 23515 47240 23183 47240 23182 47240 23515 47241 23182 47241 23566 47241 23182 47242 23181 47242 23566 47242 23566 47243 23181 47243 23517 47243 23566 47244 23517 47244 23637 47244 23637 47245 23517 47245 23518 47245 23637 47246 23518 47246 14748 47246 14748 47247 14752 47247 23637 47247 23637 47248 14752 47248 23670 47248 23637 47249 23670 47249 23519 47249 14752 47250 23520 47250 23670 47250 23670 47251 23520 47251 23521 47251 23670 47252 23521 47252 23389 47252 23389 47253 23521 47253 14756 47253 23389 47254 14756 47254 23523 47254 23523 47255 14756 47255 23522 47255 23523 47256 23522 47256 23185 47256 23638 47257 23673 47257 23531 47257 23531 47258 23673 47258 23529 47258 23566 47259 23639 47259 23524 47259 23525 47260 23192 47260 23564 47260 23564 47261 23192 47261 23526 47261 23564 47262 23526 47262 23457 47262 23457 47263 23526 47263 23190 47263 23457 47264 23190 47264 14658 47264 14658 47265 23190 47265 23189 47265 14658 47266 23189 47266 14659 47266 14659 47267 23189 47267 23527 47267 14659 47268 23527 47268 23528 47268 23528 47269 23527 47269 23187 47269 23528 47270 23187 47270 23459 47270 23459 47271 23187 47271 23186 47271 23459 47272 23186 47272 23529 47272 23529 47273 23186 47273 23530 47273 23529 47274 23530 47274 23531 47274 23532 47275 23596 47275 23454 47275 23454 47276 23596 47276 23361 47276 23454 47277 23361 47277 23453 47277 23532 47278 23533 47278 23596 47278 23596 47279 23533 47279 23534 47279 23596 47280 23534 47280 23601 47280 23601 47281 23534 47281 23535 47281 23601 47282 23535 47282 14670 47282 14670 47283 23535 47283 23536 47283 14670 47284 23536 47284 14671 47284 14671 47285 23536 47285 23204 47285 14671 47286 23204 47286 23537 47286 23537 47287 23204 47287 23202 47287 23537 47288 23202 47288 23538 47288 23538 47289 23202 47289 23201 47289 23538 47290 23201 47290 23205 47290 23355 47291 23540 47291 23539 47291 23539 47292 23540 47292 23205 47292 23539 47293 23205 47293 23541 47293 23541 47294 23205 47294 23207 47294 23541 47295 23207 47295 23542 47295 23542 47296 23207 47296 14727 47296 23542 47297 14727 47297 23452 47297 23452 47298 14727 47298 23543 47298 23452 47299 23543 47299 23454 47299 23454 47300 23543 47300 14731 47300 23454 47301 14731 47301 23532 47301 14724 47302 23210 47302 23613 47302 23210 47303 23544 47303 23613 47303 23613 47304 23544 47304 23211 47304 23613 47305 23211 47305 23655 47305 23655 47306 23211 47306 23215 47306 23655 47307 23215 47307 23217 47307 14714 47308 14712 47308 23635 47308 14714 47309 23635 47309 14710 47309 23545 47310 23221 47310 14634 47310 23221 47311 23222 47311 14634 47311 14634 47312 23222 47312 23223 47312 14634 47313 23223 47313 14635 47313 14635 47314 23223 47314 23546 47314 14635 47315 23546 47315 23633 47315 23633 47316 23546 47316 23225 47316 23633 47317 23225 47317 23226 47317 23243 47318 23245 47318 23548 47318 23245 47319 23244 47319 23548 47319 23548 47320 23244 47320 23547 47320 23548 47321 23547 47321 23559 47321 23240 47322 23238 47322 23603 47322 23603 47323 23238 47323 23243 47323 23603 47324 23243 47324 23650 47324 23650 47325 23243 47325 23548 47325 23331 47326 14692 47326 23549 47326 23549 47327 14692 47327 23550 47327 23549 47328 23550 47328 23551 47328 23551 47329 23550 47329 23552 47329 23551 47330 23552 47330 23553 47330 23553 47331 23552 47331 23642 47331 23553 47332 23642 47332 23230 47332 23547 47333 23554 47333 23559 47333 23559 47334 23554 47334 23227 47334 23559 47335 23227 47335 23403 47335 23403 47336 23227 47336 23228 47336 23548 47337 23260 47337 23648 47337 23648 47338 23260 47338 23555 47338 23648 47339 23555 47339 23259 47339 23556 47340 23557 47340 23559 47340 23559 47341 23557 47341 23558 47341 23559 47342 23558 47342 23548 47342 23548 47343 23558 47343 23560 47343 23548 47344 23560 47344 23257 47344 23257 47345 23561 47345 23548 47345 23548 47346 23561 47346 23261 47346 23548 47347 23261 47347 23260 47347 23282 47348 23649 47348 23283 47348 23273 47349 23562 47349 23259 47349 23259 47350 23562 47350 23278 47350 23259 47351 23278 47351 23648 47351 23648 47352 23278 47352 23563 47352 23648 47353 23563 47353 23280 47353 23524 47354 23564 47354 23566 47354 23566 47355 23564 47355 23565 47355 23566 47356 23565 47356 23267 47356 23267 47357 23266 47357 23566 47357 23566 47358 23266 47358 23264 47358 23566 47359 23264 47359 23515 47359 23515 47360 23264 47360 23269 47360 23515 47361 23269 47361 23473 47361 23473 47362 23269 47362 23271 47362 23473 47363 23271 47363 23472 47363 23472 47364 23271 47364 23270 47364 23472 47365 23270 47365 23567 47365 23567 47366 23270 47366 23569 47366 23567 47367 23569 47367 23568 47367 23568 47368 23569 47368 23499 47368 23568 47369 23499 47369 23385 47369 23385 47370 23499 47370 23495 47370 23385 47371 23495 47371 23382 47371 23382 47372 23495 47372 14775 47372 23382 47373 14775 47373 23570 47373 23570 47374 14775 47374 14773 47374 23570 47375 14773 47375 23571 47375 23571 47376 14773 47376 23572 47376 23571 47377 23572 47377 14646 47377 14646 47378 23572 47378 23573 47378 14646 47379 23573 47379 14647 47379 14647 47380 23573 47380 23667 47380 14647 47381 23667 47381 14648 47381 14648 47382 23667 47382 14649 47382 23293 47383 23574 47383 23564 47383 23564 47384 23574 47384 23575 47384 23564 47385 23575 47385 23565 47385 23565 47386 23575 47386 23291 47386 23565 47387 23291 47387 23290 47387 23390 47388 23290 47388 23263 47388 23263 47389 23290 47389 23576 47389 23263 47390 23576 47390 23578 47390 23578 47391 23576 47391 23577 47391 23578 47392 23577 47392 23579 47392 23297 47393 23298 47393 23592 47393 23592 47394 23298 47394 23299 47394 23592 47395 23299 47395 23590 47395 23579 47396 23577 47396 23649 47396 23649 47397 23577 47397 23580 47397 23649 47398 23580 47398 23592 47398 23592 47399 23580 47399 23581 47399 23592 47400 23581 47400 23297 47400 23651 47401 23595 47401 23604 47401 23604 47402 23595 47402 23312 47402 23604 47403 23312 47403 14706 47403 23322 47404 23605 47404 23582 47404 23582 47405 23605 47405 14706 47405 23322 47406 23582 47406 23583 47406 23583 47407 23582 47407 23584 47407 23583 47408 23584 47408 23585 47408 23585 47409 23584 47409 23586 47409 23585 47410 23586 47410 23319 47410 23319 47411 23586 47411 23301 47411 23319 47412 23301 47412 23587 47412 23587 47413 23301 47413 23588 47413 23587 47414 23588 47414 23300 47414 23589 47415 23592 47415 23599 47415 23599 47416 23592 47416 23590 47416 23599 47417 23590 47417 23470 47417 23589 47418 23591 47418 23592 47418 23592 47419 23591 47419 23593 47419 23592 47420 23593 47420 23651 47420 23651 47421 23593 47421 23594 47421 23651 47422 23594 47422 23595 47422 23309 47423 23598 47423 23596 47423 23596 47424 23598 47424 23439 47424 23596 47425 23439 47425 23455 47425 23309 47426 23597 47426 23598 47426 23598 47427 23597 47427 23307 47427 23598 47428 23307 47428 23599 47428 23599 47429 23307 47429 23600 47429 23599 47430 23600 47430 23589 47430 14670 47431 23302 47431 23601 47431 23601 47432 23302 47432 23303 47432 23601 47433 23303 47433 23596 47433 23596 47434 23303 47434 23304 47434 23596 47435 23304 47435 23309 47435 23482 47436 23241 47436 23602 47436 23602 47437 23241 47437 23603 47437 23602 47438 23603 47438 23325 47438 23325 47439 23603 47439 23652 47439 14706 47440 23605 47440 23604 47440 23604 47441 23605 47441 23606 47441 23604 47442 23606 47442 23321 47442 23607 47443 23608 47443 23613 47443 23613 47444 23608 47444 23587 47444 23613 47445 23587 47445 14724 47445 14724 47446 23587 47446 23300 47446 14724 47447 23300 47447 14726 47447 14726 47448 23300 47448 14722 47448 14702 47449 23317 47449 14679 47449 14679 47450 23317 47450 23609 47450 14679 47451 23609 47451 23610 47451 23610 47452 23609 47452 23315 47452 23610 47453 23315 47453 23611 47453 23611 47454 23315 47454 23612 47454 23611 47455 23612 47455 23613 47455 23613 47456 23612 47456 23314 47456 23613 47457 23314 47457 23607 47457 23493 47458 23488 47458 14643 47458 14643 47459 23488 47459 14783 47459 14643 47460 14783 47460 23614 47460 14641 47461 23615 47461 23475 47461 23475 47462 23615 47462 23433 47462 23475 47463 23433 47463 23616 47463 23616 47464 23433 47464 23617 47464 23616 47465 23617 47465 23618 47465 14687 47466 23619 47466 23620 47466 23620 47467 23619 47467 14689 47467 23620 47468 14689 47468 23136 47468 23136 47469 14689 47469 23621 47469 23136 47470 23621 47470 23475 47470 23475 47471 23621 47471 23622 47471 23475 47472 23622 47472 14641 47472 14639 47473 14637 47473 23425 47473 23425 47474 14637 47474 23622 47474 23425 47475 23622 47475 23623 47475 23623 47476 23622 47476 23621 47476 23623 47477 23621 47477 14690 47477 14690 47478 23621 47478 14689 47478 23624 47479 14676 47479 23658 47479 23659 47480 23545 47480 23658 47480 23658 47481 23545 47481 14634 47481 23658 47482 14634 47482 23624 47482 23624 47483 14634 47483 23347 47483 14676 47484 23625 47484 23658 47484 23658 47485 23625 47485 23626 47485 23658 47486 23626 47486 23423 47486 23423 47487 23626 47487 14673 47487 23423 47488 14673 47488 23627 47488 23627 47489 23341 47489 23423 47489 23423 47490 23341 47490 23628 47490 23423 47491 23628 47491 23629 47491 23629 47492 23628 47492 23130 47492 23341 47493 23630 47493 23628 47493 23628 47494 23630 47494 23631 47494 23628 47495 23631 47495 23632 47495 23631 47496 23343 47496 23632 47496 23632 47497 23343 47497 23344 47497 23632 47498 23344 47498 14634 47498 14634 47499 23344 47499 23346 47499 14634 47500 23346 47500 23347 47500 23226 47501 14710 47501 23633 47501 23633 47502 14710 47502 23635 47502 23633 47503 23635 47503 14631 47503 14631 47504 23635 47504 14633 47504 14712 47505 23634 47505 23635 47505 23635 47506 23634 47506 23657 47506 23635 47507 23657 47507 14633 47507 14633 47508 23657 47508 23656 47508 23217 47509 23218 47509 23655 47509 23655 47510 23218 47510 23636 47510 23655 47511 23636 47511 23653 47511 23653 47512 23636 47512 14627 47512 23519 47513 23672 47513 23637 47513 23637 47514 23672 47514 23673 47514 23637 47515 23673 47515 23566 47515 23566 47516 23673 47516 23638 47516 23566 47517 23638 47517 23639 47517 23640 47518 23149 47518 23493 47518 23493 47519 23149 47519 23641 47519 23493 47520 23641 47520 23488 47520 23488 47521 23641 47521 23403 47521 23488 47522 23403 47522 23642 47522 23642 47523 23403 47523 23228 47523 23642 47524 23228 47524 23230 47524 23643 47525 23644 47525 23645 47525 23645 47526 23644 47526 23335 47526 23645 47527 23335 47527 14795 47527 14795 47528 23335 47528 23646 47528 14795 47529 23646 47529 14797 47529 14797 47530 23646 47530 14682 47530 14797 47531 14682 47531 14799 47531 14799 47532 14682 47532 14681 47532 14799 47533 14681 47533 23647 47533 23647 47534 14681 47534 23610 47534 23647 47535 23610 47535 23423 47535 23423 47536 23610 47536 23611 47536 23423 47537 23611 47537 23658 47537 23280 47538 23283 47538 23648 47538 23648 47539 23283 47539 23649 47539 23648 47540 23649 47540 23548 47540 23548 47541 23649 47541 23592 47541 23548 47542 23592 47542 23650 47542 23650 47543 23592 47543 23651 47543 23650 47544 23651 47544 23603 47544 23603 47545 23651 47545 23604 47545 23603 47546 23604 47546 23652 47546 23652 47547 23604 47547 23321 47547 23653 47548 23654 47548 23655 47548 23655 47549 23654 47549 23656 47549 23655 47550 23656 47550 23613 47550 23613 47551 23656 47551 23657 47551 23613 47552 23657 47552 23611 47552 23611 47553 23657 47553 23634 47553 23611 47554 23634 47554 23658 47554 23658 47555 23634 47555 14716 47555 23658 47556 14716 47556 23659 47556 14612 47557 23661 47557 23493 47557 23493 47558 23661 47558 23660 47558 23660 47559 23661 47559 23388 47559 23388 47560 23661 47560 23662 47560 23388 47561 23662 47561 23396 47561 23396 47562 23662 47562 23663 47562 23663 47563 23662 47563 23688 47563 23663 47564 23688 47564 23664 47564 23664 47565 23688 47565 23504 47565 23504 47566 23688 47566 23665 47566 23504 47567 23665 47567 23573 47567 23573 47568 23665 47568 23666 47568 23573 47569 23666 47569 23667 47569 23667 47570 23666 47570 23685 47570 23667 47571 23685 47571 23668 47571 23668 47572 23685 47572 23669 47572 23668 47573 23669 47573 23409 47573 23409 47574 23669 47574 23683 47574 23409 47575 23683 47575 23670 47575 23670 47576 23683 47576 23519 47576 23519 47577 23683 47577 23671 47577 23519 47578 23671 47578 23672 47578 23672 47579 23671 47579 23680 47579 23672 47580 23680 47580 23673 47580 23673 47581 23680 47581 23529 47581 23529 47582 23680 47582 23678 47582 23529 47583 23678 47583 23463 47583 23463 47584 23678 47584 23393 47584 23393 47585 23678 47585 23674 47585 23393 47586 23674 47586 23675 47586 23675 47587 23674 47587 23676 47587 23675 47588 23676 47588 23442 47588 23442 47589 23676 47589 14625 47589 23442 47590 14625 47590 14626 47590 23113 47591 14625 47591 23676 47591 23113 47592 23676 47592 23677 47592 23677 47593 23676 47593 23674 47593 23677 47594 23674 47594 23112 47594 23112 47595 23674 47595 23678 47595 23112 47596 23678 47596 23679 47596 23679 47597 23678 47597 23680 47597 23679 47598 23680 47598 23681 47598 23681 47599 23680 47599 23671 47599 23681 47600 23671 47600 23682 47600 23682 47601 23671 47601 23683 47601 23682 47602 23683 47602 23684 47602 23684 47603 23683 47603 23669 47603 23684 47604 23669 47604 23098 47604 23098 47605 23669 47605 23685 47605 23098 47606 23685 47606 23686 47606 23686 47607 23685 47607 23666 47607 23686 47608 23666 47608 23096 47608 23096 47609 23666 47609 23665 47609 23096 47610 23665 47610 23687 47610 23687 47611 23665 47611 23688 47611 23687 47612 23688 47612 23106 47612 23106 47613 23688 47613 23662 47613 23106 47614 23662 47614 23689 47614 23689 47615 23662 47615 23661 47615 23689 47616 23661 47616 23690 47616 23690 47617 23661 47617 14612 47617 23690 47618 14612 47618 23103 47618 23691 47619 14608 47619 14404 47619 14404 47620 24024 47620 23691 47620 23691 47621 24024 47621 24026 47621 23691 47622 24026 47622 23398 47622 24026 47623 24027 47623 23398 47623 23398 47624 24027 47624 23692 47624 23398 47625 23692 47625 23693 47625 23692 47626 23694 47626 23693 47626 23693 47627 23694 47627 24020 47627 23693 47628 24020 47628 23490 47628 23490 47629 24020 47629 24019 47629 23490 47630 24019 47630 23695 47630 24019 47631 23696 47631 23695 47631 23695 47632 23696 47632 23699 47632 23695 47633 23699 47633 23698 47633 14611 47634 23697 47634 24015 47634 24015 47635 23697 47635 23698 47635 24015 47636 23698 47636 24017 47636 24017 47637 23698 47637 23699 47637 23296 47638 23700 47638 24028 47638 24028 47639 23700 47639 23701 47639 24032 47640 23702 47640 24030 47640 24030 47641 23702 47641 23295 47641 24030 47642 23295 47642 24036 47642 24036 47643 23295 47643 24035 47643 24035 47644 23295 47644 23294 47644 24035 47645 23294 47645 24039 47645 24039 47646 23294 47646 23703 47646 23707 47647 23704 47647 23292 47647 23292 47648 23704 47648 24037 47648 23292 47649 24037 47649 23705 47649 23705 47650 24037 47650 23706 47650 23705 47651 23706 47651 23289 47651 23289 47652 23706 47652 24038 47652 23289 47653 24038 47653 23703 47653 23703 47654 24038 47654 24039 47654 23704 47655 23707 47655 24040 47655 24040 47656 23707 47656 23708 47656 24040 47657 23708 47657 23711 47657 23711 47658 23708 47658 23709 47658 14606 47659 23710 47659 23709 47659 23709 47660 23710 47660 23711 47660 23712 47661 23286 47661 24043 47661 24043 47662 23286 47662 23284 47662 24043 47663 23284 47663 23713 47663 23713 47664 23284 47664 23714 47664 23713 47665 23714 47665 24044 47665 24044 47666 23714 47666 23715 47666 24044 47667 23715 47667 23716 47667 23716 47668 23715 47668 23717 47668 23716 47669 23717 47669 24028 47669 24028 47670 23717 47670 23296 47670 23742 47671 23277 47671 23718 47671 23718 47672 23277 47672 23272 47672 23718 47673 23272 47673 24053 47673 24053 47674 23272 47674 23274 47674 23723 47675 24048 47675 24049 47675 23723 47676 24049 47676 23719 47676 23719 47677 24049 47677 24051 47677 23719 47678 24051 47678 23720 47678 23720 47679 24051 47679 23721 47679 23720 47680 23721 47680 23722 47680 23722 47681 23721 47681 24053 47681 23722 47682 24053 47682 23274 47682 24048 47683 23723 47683 23724 47683 23724 47684 23723 47684 23725 47684 23724 47685 23725 47685 23730 47685 23730 47686 23725 47686 23726 47686 23268 47687 14399 47687 23727 47687 23727 47688 14399 47688 24055 47688 23727 47689 24055 47689 23728 47689 23728 47690 24055 47690 23729 47690 23728 47691 23729 47691 23265 47691 23265 47692 23729 47692 23730 47692 23265 47693 23730 47693 23726 47693 14600 47694 23732 47694 23731 47694 23731 47695 23732 47695 23262 47695 23731 47696 23262 47696 23733 47696 23733 47697 23262 47697 23734 47697 23733 47698 23734 47698 23735 47698 23735 47699 23734 47699 23281 47699 23735 47700 23281 47700 23736 47700 23736 47701 23281 47701 23737 47701 23736 47702 23737 47702 23739 47702 23739 47703 23737 47703 23279 47703 23279 47704 23738 47704 23739 47704 23739 47705 23738 47705 24061 47705 24061 47706 23738 47706 23740 47706 23740 47707 23738 47707 23741 47707 23740 47708 23741 47708 24062 47708 24062 47709 23741 47709 23276 47709 24062 47710 23276 47710 23742 47710 23742 47711 23276 47711 23277 47711 24083 47712 23255 47712 24065 47712 24065 47713 23255 47713 23743 47713 24065 47714 23743 47714 23748 47714 23748 47715 23743 47715 23749 47715 23751 47716 23750 47716 23254 47716 23254 47717 23750 47717 23745 47717 23254 47718 23745 47718 23744 47718 23744 47719 23745 47719 24067 47719 23744 47720 24067 47720 23746 47720 23746 47721 24067 47721 23747 47721 23746 47722 23747 47722 14707 47722 14707 47723 23747 47723 23748 47723 14707 47724 23748 47724 23749 47724 23750 47725 23751 47725 24070 47725 24070 47726 23751 47726 23253 47726 24070 47727 23253 47727 24076 47727 24076 47728 23253 47728 23754 47728 23252 47729 24081 47729 23251 47729 23251 47730 24081 47730 23752 47730 23251 47731 23752 47731 23250 47731 23250 47732 23752 47732 23753 47732 23250 47733 23753 47733 23247 47733 23247 47734 23753 47734 24075 47734 23247 47735 24075 47735 23754 47735 23754 47736 24075 47736 24076 47736 24081 47737 23252 47737 24079 47737 24079 47738 23252 47738 23755 47738 24079 47739 23755 47739 24078 47739 24078 47740 23755 47740 23246 47740 24078 47741 23246 47741 23756 47741 24078 47742 23756 47742 24082 47742 24082 47743 23756 47743 23757 47743 24082 47744 23757 47744 14396 47744 14396 47745 23757 47745 23258 47745 14396 47746 23258 47746 14394 47746 23258 47747 23758 47747 14394 47747 14394 47748 23758 47748 23759 47748 23759 47749 23758 47749 23760 47749 23760 47750 23758 47750 23256 47750 23760 47751 23256 47751 23761 47751 23761 47752 23256 47752 23762 47752 23761 47753 23762 47753 24083 47753 24083 47754 23762 47754 23255 47754 23788 47755 23764 47755 23763 47755 23763 47756 23764 47756 23765 47756 23763 47757 23765 47757 24088 47757 24088 47758 23765 47758 23770 47758 23766 47759 24086 47759 23767 47759 23767 47760 24086 47760 24087 47760 23767 47761 24087 47761 23235 47761 23235 47762 24087 47762 23768 47762 23235 47763 23768 47763 23233 47763 23233 47764 23768 47764 23769 47764 23233 47765 23769 47765 23770 47765 23770 47766 23769 47766 24088 47766 24086 47767 23766 47767 23771 47767 23771 47768 23766 47768 23772 47768 23771 47769 23772 47769 24089 47769 24089 47770 23772 47770 23232 47770 23776 47771 24095 47771 24090 47771 23776 47772 24090 47772 23229 47772 23229 47773 24090 47773 23773 47773 23229 47774 23773 47774 23774 47774 23774 47775 23773 47775 24093 47775 23774 47776 24093 47776 23231 47776 23231 47777 24093 47777 23775 47777 23775 47778 24093 47778 24089 47778 23775 47779 24089 47779 23232 47779 24095 47780 23776 47780 24094 47780 24094 47781 23776 47781 23778 47781 24094 47782 23778 47782 23777 47782 23777 47783 23778 47783 23779 47783 23777 47784 23779 47784 24096 47784 24096 47785 23779 47785 23781 47785 24096 47786 23781 47786 23780 47786 23780 47787 23781 47787 23782 47787 23780 47788 23782 47788 23783 47788 23783 47789 23782 47789 23242 47789 23242 47790 23784 47790 23783 47790 23783 47791 23784 47791 23785 47791 23785 47792 23784 47792 23787 47792 23785 47793 23787 47793 23786 47793 23786 47794 23787 47794 23239 47794 23786 47795 23239 47795 24098 47795 24098 47796 23239 47796 23764 47796 24098 47797 23764 47797 23788 47797 24117 47798 23789 47798 24099 47798 24099 47799 23789 47799 23790 47799 24099 47800 23790 47800 23791 47800 23791 47801 23790 47801 23793 47801 23792 47802 23794 47802 23793 47802 23793 47803 23794 47803 23791 47803 24105 47804 14597 47804 23795 47804 23795 47805 14597 47805 23796 47805 23795 47806 23796 47806 24103 47806 24103 47807 23796 47807 23316 47807 23798 47808 23797 47808 24106 47808 23798 47809 24106 47809 14704 47809 14704 47810 24106 47810 24108 47810 14704 47811 24108 47811 23799 47811 23799 47812 24108 47812 24111 47812 23799 47813 24111 47813 23800 47813 23800 47814 24111 47814 24103 47814 23800 47815 24103 47815 23316 47815 23797 47816 23798 47816 24113 47816 24113 47817 23798 47817 23313 47817 24113 47818 23313 47818 23801 47818 23801 47819 23313 47819 23802 47819 23801 47820 23802 47820 24114 47820 24114 47821 23802 47821 23803 47821 24114 47822 23803 47822 23804 47822 23804 47823 23803 47823 23324 47823 23804 47824 23324 47824 23805 47824 23805 47825 23324 47825 23323 47825 23323 47826 23807 47826 23805 47826 23805 47827 23807 47827 24119 47827 24119 47828 23807 47828 23806 47828 23806 47829 23807 47829 23808 47829 23806 47830 23808 47830 23809 47830 23809 47831 23808 47831 23810 47831 23809 47832 23810 47832 24117 47832 24117 47833 23810 47833 23789 47833 23811 47834 23835 47834 23812 47834 23812 47835 23835 47835 23813 47835 23812 47836 23813 47836 24120 47836 24120 47837 23813 47837 23306 47837 14596 47838 23814 47838 23305 47838 23305 47839 23814 47839 23816 47839 23305 47840 23816 47840 23815 47840 23815 47841 23816 47841 23308 47841 23308 47842 23816 47842 23817 47842 23308 47843 23817 47843 23818 47843 23818 47844 23817 47844 24120 47844 23818 47845 24120 47845 23306 47845 24127 47846 23819 47846 24126 47846 24126 47847 23819 47847 23820 47847 24126 47848 23820 47848 24125 47848 24125 47849 23820 47849 23826 47849 23827 47850 24133 47850 23821 47850 23821 47851 24133 47851 23822 47851 23821 47852 23822 47852 23824 47852 23824 47853 23822 47853 23823 47853 23824 47854 23823 47854 23825 47854 23825 47855 23823 47855 24130 47855 23825 47856 24130 47856 23826 47856 23826 47857 24130 47857 24125 47857 24133 47858 23827 47858 24131 47858 24131 47859 23827 47859 23828 47859 24131 47860 23828 47860 24135 47860 24135 47861 23828 47861 14705 47861 23829 47862 14595 47862 23830 47862 23829 47863 23830 47863 23831 47863 23831 47864 23830 47864 23832 47864 23831 47865 23832 47865 23833 47865 23832 47866 23311 47866 23833 47866 23833 47867 23311 47867 24142 47867 24142 47868 23311 47868 24141 47868 24141 47869 23311 47869 23834 47869 24141 47870 23834 47870 24139 47870 24139 47871 23834 47871 23310 47871 24139 47872 23310 47872 23811 47872 23811 47873 23310 47873 23835 47873 14384 47874 23124 47874 23836 47874 23836 47875 23124 47875 23121 47875 23836 47876 23121 47876 24146 47876 24146 47877 23121 47877 23838 47877 24146 47878 23838 47878 23837 47878 23837 47879 23838 47879 23122 47879 23837 47880 23122 47880 24144 47880 24144 47881 23122 47881 23839 47881 24144 47882 23839 47882 23840 47882 23840 47883 23839 47883 23125 47883 23840 47884 23125 47884 23841 47884 23841 47885 23125 47885 23842 47885 23841 47886 23842 47886 14588 47886 14588 47887 23842 47887 23126 47887 14765 47888 23177 47888 24153 47888 24153 47889 23177 47889 24150 47889 23177 47890 23178 47890 24150 47890 24150 47891 23178 47891 23179 47891 24150 47892 23179 47892 23843 47892 23179 47893 23176 47893 23843 47893 23843 47894 23176 47894 23174 47894 23843 47895 23174 47895 23844 47895 23174 47896 23172 47896 23844 47896 23844 47897 23172 47897 23845 47897 23844 47898 23845 47898 23846 47898 23845 47899 23173 47899 23846 47899 23846 47900 23173 47900 23847 47900 23846 47901 23847 47901 23850 47901 14759 47902 14379 47902 23848 47902 23848 47903 14379 47903 23850 47903 23848 47904 23850 47904 23849 47904 23849 47905 23850 47905 23847 47905 14582 47906 23852 47906 23851 47906 23851 47907 23852 47907 23160 47907 23851 47908 23160 47908 23853 47908 23853 47909 23160 47909 23161 47909 23853 47910 23161 47910 23854 47910 23854 47911 23161 47911 23162 47911 23854 47912 23162 47912 23855 47912 23855 47913 23162 47913 23165 47913 23855 47914 23165 47914 23856 47914 23856 47915 23165 47915 23166 47915 23856 47916 23166 47916 14372 47916 14372 47917 23166 47917 23168 47917 14574 47918 23857 47918 23156 47918 14574 47919 23156 47919 23858 47919 23858 47920 23156 47920 23157 47920 23858 47921 23157 47921 23859 47921 23859 47922 23157 47922 23159 47922 23859 47923 23159 47923 23860 47923 23159 47924 23155 47924 23860 47924 23860 47925 23155 47925 23862 47925 23860 47926 23862 47926 23861 47926 23862 47927 23153 47927 23861 47927 23861 47928 23153 47928 23152 47928 23861 47929 23152 47929 23863 47929 23152 47930 23151 47930 23863 47930 23863 47931 23151 47931 23150 47931 23863 47932 23150 47932 24154 47932 24154 47933 23150 47933 14569 47933 24154 47934 14569 47934 23864 47934 24157 47935 14788 47935 23865 47935 23865 47936 14788 47936 23866 47936 23865 47937 23866 47937 24159 47937 24159 47938 23866 47938 23143 47938 24159 47939 23143 47939 23867 47939 23867 47940 23143 47940 23144 47940 23867 47941 23144 47941 23868 47941 23868 47942 23144 47942 23145 47942 23868 47943 23145 47943 23869 47943 23869 47944 23145 47944 23147 47944 23869 47945 23147 47945 23870 47945 23870 47946 23147 47946 14563 47946 24163 47947 14562 47947 23871 47947 23871 47948 14562 47948 23872 47948 23871 47949 23872 47949 23873 47949 23873 47950 23872 47950 24165 47950 24165 47951 23872 47951 23135 47951 24165 47952 23135 47952 24166 47952 24166 47953 23135 47953 24167 47953 24167 47954 23135 47954 23874 47954 24167 47955 23874 47955 24168 47955 24168 47956 23874 47956 24169 47956 24169 47957 23874 47957 23876 47957 24169 47958 23876 47958 24171 47958 24171 47959 23876 47959 23875 47959 23875 47960 23876 47960 23138 47960 23875 47961 23138 47961 24170 47961 24170 47962 23138 47962 23877 47962 23877 47963 23138 47963 14554 47963 23877 47964 14554 47964 14349 47964 14551 47965 14552 47965 24172 47965 24172 47966 14552 47966 23129 47966 24172 47967 23129 47967 23878 47967 23878 47968 23129 47968 23131 47968 23878 47969 23131 47969 23879 47969 23879 47970 23131 47970 23881 47970 23879 47971 23881 47971 23880 47971 23880 47972 23881 47972 23882 47972 23880 47973 23882 47973 23884 47973 23884 47974 23882 47974 23883 47974 23884 47975 23883 47975 14347 47975 14347 47976 23883 47976 14544 47976 24177 47977 14543 47977 23885 47977 23885 47978 14543 47978 23886 47978 23885 47979 23886 47979 24179 47979 24179 47980 23886 47980 23887 47980 24179 47981 23887 47981 24180 47981 24180 47982 23887 47982 23888 47982 24180 47983 23888 47983 23889 47983 23889 47984 23888 47984 23890 47984 23889 47985 23890 47985 23891 47985 23891 47986 23890 47986 23892 47986 23891 47987 23892 47987 24182 47987 24182 47988 23892 47988 23893 47988 24182 47989 23893 47989 23894 47989 23894 47990 23893 47990 23224 47990 23894 47991 23224 47991 23895 47991 23895 47992 23224 47992 23896 47992 23895 47993 23896 47993 23897 47993 23897 47994 23896 47994 23898 47994 23897 47995 23898 47995 23899 47995 23899 47996 23898 47996 23900 47996 23899 47997 23900 47997 24186 47997 24186 47998 23900 47998 23902 47998 24186 47999 23902 47999 23901 47999 23901 48000 23902 48000 23220 48000 24188 48001 14719 48001 23903 48001 23903 48002 14719 48002 23904 48002 23903 48003 23904 48003 23905 48003 23905 48004 23904 48004 23219 48004 23905 48005 23219 48005 24190 48005 24190 48006 23219 48006 23906 48006 24190 48007 23906 48007 23907 48007 23907 48008 23906 48008 23216 48008 23907 48009 23216 48009 24191 48009 24191 48010 23216 48010 23908 48010 24191 48011 23908 48011 23909 48011 23909 48012 23908 48012 23910 48012 23909 48013 23910 48013 23911 48013 23911 48014 23910 48014 23214 48014 23911 48015 23214 48015 24192 48015 24192 48016 23214 48016 23213 48016 24192 48017 23213 48017 24196 48017 24196 48018 23213 48018 23212 48018 24196 48019 23212 48019 23912 48019 23912 48020 23212 48020 23913 48020 23912 48021 23913 48021 24195 48021 24195 48022 23913 48022 23209 48022 24195 48023 23209 48023 23914 48023 23914 48024 23209 48024 14514 48024 23915 48025 14728 48025 23916 48025 23916 48026 14728 48026 23917 48026 23916 48027 23917 48027 23918 48027 23918 48028 23917 48028 23206 48028 23918 48029 23206 48029 23919 48029 23919 48030 23206 48030 23208 48030 23919 48031 23208 48031 23920 48031 23920 48032 23208 48032 23922 48032 23920 48033 23922 48033 23921 48033 23921 48034 23922 48034 23923 48034 23921 48035 23923 48035 23924 48035 23924 48036 23923 48036 23200 48036 23924 48037 23200 48037 23925 48037 23925 48038 23200 48038 23926 48038 23925 48039 23926 48039 23927 48039 23927 48040 23926 48040 23928 48040 23927 48041 23928 48041 24203 48041 24203 48042 23928 48042 23929 48042 24203 48043 23929 48043 24202 48043 24202 48044 23929 48044 23203 48044 24202 48045 23203 48045 24200 48045 24200 48046 23203 48046 23199 48046 24200 48047 23199 48047 24199 48047 24199 48048 23199 48048 14504 48048 24208 48049 14742 48049 23930 48049 23930 48050 14742 48050 23194 48050 23930 48051 23194 48051 24206 48051 24206 48052 23194 48052 23195 48052 24206 48053 23195 48053 23931 48053 23931 48054 23195 48054 23196 48054 23931 48055 23196 48055 24205 48055 24205 48056 23196 48056 23197 48056 24205 48057 23197 48057 23933 48057 23933 48058 23197 48058 23932 48058 23933 48059 23932 48059 14312 48059 14312 48060 23932 48060 23934 48060 14493 48061 14494 48061 24215 48061 24215 48062 14494 48062 23935 48062 24215 48063 23935 48063 23936 48063 23936 48064 23935 48064 23188 48064 23936 48065 23188 48065 24213 48065 24213 48066 23188 48066 23938 48066 24213 48067 23938 48067 23937 48067 23937 48068 23938 48068 23939 48068 23937 48069 23939 48069 24212 48069 24212 48070 23939 48070 23191 48070 24212 48071 23191 48071 24210 48071 24210 48072 23191 48072 23940 48072 24210 48073 23940 48073 14305 48073 14305 48074 23940 48074 23941 48074 14474 48075 14473 48075 23942 48075 23942 48076 14473 48076 23943 48076 23942 48077 23943 48077 24221 48077 24221 48078 23943 48078 23180 48078 24221 48079 23180 48079 23944 48079 23944 48080 23180 48080 23945 48080 23944 48081 23945 48081 23947 48081 23947 48082 23945 48082 23946 48082 23947 48083 23946 48083 24217 48083 24217 48084 23946 48084 23184 48084 24217 48085 23184 48085 14486 48085 14486 48086 23184 48086 23948 48086 24310 48087 14472 48087 23332 48087 24310 48088 23332 48088 24311 48088 24311 48089 23332 48089 23333 48089 24311 48090 23333 48090 23950 48090 23333 48091 23949 48091 23950 48091 23950 48092 23949 48092 23951 48092 23950 48093 23951 48093 24313 48093 24313 48094 23951 48094 23330 48094 23330 48095 23329 48095 24313 48095 24313 48096 23329 48096 23952 48096 24313 48097 23952 48097 23954 48097 23952 48098 23328 48098 23954 48098 23954 48099 23328 48099 23953 48099 23954 48100 23953 48100 23955 48100 23326 48101 14464 48101 23327 48101 23327 48102 14464 48102 23955 48102 23327 48103 23955 48103 23956 48103 23956 48104 23955 48104 23953 48104 24477 48105 14680 48105 24473 48105 24473 48106 14680 48106 23334 48106 24473 48107 23334 48107 24478 48107 24478 48108 23334 48108 23957 48108 24478 48109 23957 48109 23958 48109 23958 48110 23957 48110 23336 48110 23958 48111 23336 48111 24481 48111 24481 48112 23336 48112 23960 48112 24481 48113 23960 48113 23959 48113 23959 48114 23960 48114 23338 48114 23959 48115 23338 48115 24484 48115 24484 48116 23338 48116 23340 48116 14453 48117 14677 48117 23348 48117 14453 48118 23348 48118 24467 48118 24467 48119 23348 48119 23961 48119 24467 48120 23961 48120 23962 48120 23961 48121 23345 48121 23962 48121 23962 48122 23345 48122 23963 48122 23962 48123 23963 48123 24461 48123 24461 48124 23963 48124 23964 48124 23964 48125 23965 48125 24461 48125 24461 48126 23965 48126 23966 48126 24461 48127 23966 48127 24458 48127 23966 48128 23967 48128 24458 48128 24458 48129 23967 48129 23342 48129 24458 48130 23342 48130 24457 48130 14445 48131 24463 48131 23968 48131 23968 48132 24463 48132 24457 48132 23968 48133 24457 48133 23969 48133 23969 48134 24457 48134 23342 48134 23971 48135 23356 48135 23970 48135 23971 48136 23970 48136 23972 48136 23972 48137 23970 48137 23973 48137 23972 48138 23973 48138 24443 48138 23973 48139 23974 48139 24443 48139 24443 48140 23974 48140 23975 48140 24443 48141 23975 48141 23977 48141 23977 48142 23975 48142 23976 48142 23976 48143 23353 48143 23977 48143 23977 48144 23353 48144 23978 48144 23977 48145 23978 48145 23979 48145 23978 48146 23351 48146 23979 48146 23979 48147 23351 48147 23983 48147 23979 48148 23983 48148 23980 48148 14440 48149 23981 48149 23982 48149 23982 48150 23981 48150 23980 48150 23982 48151 23980 48151 23350 48151 23350 48152 23980 48152 23983 48152 24257 48153 14667 48153 23363 48153 24257 48154 23363 48154 23984 48154 23984 48155 23363 48155 23365 48155 23984 48156 23365 48156 24259 48156 24259 48157 23365 48157 23985 48157 24259 48158 23985 48158 23986 48158 23986 48159 23985 48159 23362 48159 23986 48160 23362 48160 24260 48160 23362 48161 23987 48161 24260 48161 24260 48162 23987 48162 23360 48162 24260 48163 23360 48163 23988 48163 23988 48164 23360 48164 23359 48164 23359 48165 23358 48165 23988 48165 23988 48166 23358 48166 23989 48166 23988 48167 23989 48167 23990 48167 23990 48168 23989 48168 23991 48168 23990 48169 23991 48169 14435 48169 14433 48170 23368 48170 23992 48170 23992 48171 23368 48171 23993 48171 23992 48172 23993 48172 24433 48172 24433 48173 23993 48173 23994 48173 24433 48174 23994 48174 24239 48174 24239 48175 23994 48175 23995 48175 24239 48176 23995 48176 24263 48176 24263 48177 23995 48177 23996 48177 24263 48178 23996 48178 24265 48178 24265 48179 23996 48179 23997 48179 24265 48180 23997 48180 24417 48180 24417 48181 23997 48181 23998 48181 23999 48182 14426 48182 23378 48182 23999 48183 23378 48183 24000 48183 24000 48184 23378 48184 23379 48184 24000 48185 23379 48185 24001 48185 23379 48186 23380 48186 24001 48186 24001 48187 23380 48187 23377 48187 24001 48188 23377 48188 24003 48188 24003 48189 23377 48189 24002 48189 24002 48190 23376 48190 24003 48190 24003 48191 23376 48191 24004 48191 24003 48192 24004 48192 24005 48192 24004 48193 23373 48193 24005 48193 24005 48194 23373 48194 24006 48194 24005 48195 24006 48195 24010 48195 14421 48196 24008 48196 24007 48196 24007 48197 24008 48197 24010 48197 24007 48198 24010 48198 24009 48198 24009 48199 24010 48199 24006 48199 24391 48200 23387 48200 24011 48200 24011 48201 23387 48201 24012 48201 24011 48202 24012 48202 24387 48202 24387 48203 24012 48203 23386 48203 24387 48204 23386 48204 24388 48204 24388 48205 23386 48205 23384 48205 24388 48206 23384 48206 24013 48206 24013 48207 23384 48207 23383 48207 24013 48208 23383 48208 24014 48208 24014 48209 23383 48209 23381 48209 24014 48210 23381 48210 24390 48210 24390 48211 23381 48211 14413 48211 24377 48212 14611 48212 24015 48212 24377 48213 24015 48213 24016 48213 24016 48214 24015 48214 24017 48214 24016 48215 24017 48215 24018 48215 24017 48216 23699 48216 24018 48216 24018 48217 23699 48217 23696 48217 24018 48218 23696 48218 24021 48218 24021 48219 23696 48219 24019 48219 24019 48220 24020 48220 24021 48220 24021 48221 24020 48221 23694 48221 24021 48222 23694 48222 24022 48222 23694 48223 23692 48223 24022 48223 24022 48224 23692 48224 24027 48224 24022 48225 24027 48225 24023 48225 14404 48226 24025 48226 24024 48226 24024 48227 24025 48227 24023 48227 24024 48228 24023 48228 24026 48228 24026 48229 24023 48229 24027 48229 24028 48230 23701 48230 24029 48230 24029 48231 23701 48231 24272 48231 24272 48232 23701 48232 24273 48232 24273 48233 23701 48233 24033 48233 24273 48234 24033 48234 24031 48234 24036 48235 24276 48235 24030 48235 24030 48236 24276 48236 24031 48236 24030 48237 24031 48237 24032 48237 24032 48238 24031 48238 24033 48238 24039 48239 24034 48239 24035 48239 24035 48240 24034 48240 24277 48240 24035 48241 24277 48241 24036 48241 24036 48242 24277 48242 24276 48242 23704 48243 24419 48243 24037 48243 24037 48244 24419 48244 24421 48244 24037 48245 24421 48245 23706 48245 23706 48246 24421 48246 24238 48246 23706 48247 24238 48247 24038 48247 24038 48248 24238 48248 24278 48248 24038 48249 24278 48249 24039 48249 24039 48250 24278 48250 24034 48250 24419 48251 23704 48251 24264 48251 24264 48252 23704 48252 24040 48252 24264 48253 24040 48253 24271 48253 24271 48254 24040 48254 23711 48254 24271 48255 23711 48255 24041 48255 23710 48256 14403 48256 23711 48256 23711 48257 14403 48257 24041 48257 23713 48258 24042 48258 24043 48258 24043 48259 24042 48259 24267 48259 24043 48260 24267 48260 23712 48260 23712 48261 24267 48261 14400 48261 24028 48262 24029 48262 23716 48262 23716 48263 24029 48263 24045 48263 23716 48264 24045 48264 24044 48264 24044 48265 24045 48265 24269 48265 24044 48266 24269 48266 23713 48266 23713 48267 24269 48267 24042 48267 24053 48268 24287 48268 23718 48268 23718 48269 24287 48269 24046 48269 23718 48270 24046 48270 23742 48270 23742 48271 24046 48271 24047 48271 24048 48272 24396 48272 24049 48272 24049 48273 24396 48273 24050 48273 24049 48274 24050 48274 24051 48274 24051 48275 24050 48275 24052 48275 24051 48276 24052 48276 23721 48276 23721 48277 24052 48277 24281 48277 23721 48278 24281 48278 24053 48278 24053 48279 24281 48279 24287 48279 23730 48280 24280 48280 23724 48280 23724 48281 24280 48281 24395 48281 23724 48282 24395 48282 24048 48282 24048 48283 24395 48283 24396 48283 14399 48284 24279 48284 24055 48284 24055 48285 24279 48285 24054 48285 24055 48286 24054 48286 23729 48286 23729 48287 24054 48287 24056 48287 23729 48288 24056 48288 23730 48288 23730 48289 24056 48289 24280 48289 23733 48290 24057 48290 23731 48290 23731 48291 24057 48291 24275 48291 23731 48292 24275 48292 14600 48292 14600 48293 24275 48293 14398 48293 23739 48294 24060 48294 23736 48294 23736 48295 24060 48295 24058 48295 23736 48296 24058 48296 23735 48296 23735 48297 24058 48297 24059 48297 23735 48298 24059 48298 23733 48298 23733 48299 24059 48299 24057 48299 23739 48300 24061 48300 24060 48300 24060 48301 24061 48301 24064 48301 23742 48302 24047 48302 24062 48302 24062 48303 24047 48303 24283 48303 24062 48304 24283 48304 23740 48304 23740 48305 24283 48305 24063 48305 23740 48306 24063 48306 24061 48306 24061 48307 24063 48307 24064 48307 23748 48308 24364 48308 24065 48308 24065 48309 24364 48309 24066 48309 24065 48310 24066 48310 24083 48310 24083 48311 24066 48311 24084 48311 23750 48312 24371 48312 23745 48312 23745 48313 24371 48313 24368 48313 23745 48314 24368 48314 24067 48314 24067 48315 24368 48315 24367 48315 24067 48316 24367 48316 23747 48316 23747 48317 24367 48317 24068 48317 23747 48318 24068 48318 23748 48318 23748 48319 24068 48319 24364 48319 24371 48320 23750 48320 24069 48320 24069 48321 23750 48321 24070 48321 24069 48322 24070 48322 24072 48322 24076 48323 24077 48323 24070 48323 24070 48324 24077 48324 24071 48324 24070 48325 24071 48325 24072 48325 24081 48326 24288 48326 23752 48326 23752 48327 24288 48327 24073 48327 23752 48328 24073 48328 23753 48328 23753 48329 24073 48329 24074 48329 23753 48330 24074 48330 24075 48330 24075 48331 24074 48331 24374 48331 24075 48332 24374 48332 24076 48332 24076 48333 24374 48333 24077 48333 24078 48334 24285 48334 24079 48334 24079 48335 24285 48335 24080 48335 24079 48336 24080 48336 24081 48336 24081 48337 24080 48337 24288 48337 24082 48338 24357 48338 24078 48338 24078 48339 24357 48339 24285 48339 14394 48340 23759 48340 14395 48340 14395 48341 23759 48341 24284 48341 24083 48342 24084 48342 23761 48342 23761 48343 24084 48343 24292 48343 23761 48344 24292 48344 23760 48344 23760 48345 24292 48345 24237 48345 23760 48346 24237 48346 23759 48346 23759 48347 24237 48347 24284 48347 24088 48348 24332 48348 23763 48348 23763 48349 24332 48349 24085 48349 23763 48350 24085 48350 23788 48350 23788 48351 24085 48351 24337 48351 24086 48352 24489 48352 24087 48352 24087 48353 24489 48353 24487 48353 24087 48354 24487 48354 23768 48354 23768 48355 24487 48355 24329 48355 23768 48356 24329 48356 23769 48356 23769 48357 24329 48357 24331 48357 23769 48358 24331 48358 24088 48358 24088 48359 24331 48359 24332 48359 24489 48360 24086 48360 24321 48360 24321 48361 24086 48361 23771 48361 24321 48362 23771 48362 24320 48362 24320 48363 23771 48363 24317 48363 24317 48364 23771 48364 24089 48364 24317 48365 24089 48365 24316 48365 24095 48366 24303 48366 24090 48366 24090 48367 24303 48367 24309 48367 24090 48368 24309 48368 23773 48368 23773 48369 24309 48369 24091 48369 23773 48370 24091 48370 24093 48370 24093 48371 24091 48371 24092 48371 24093 48372 24092 48372 24089 48372 24089 48373 24092 48373 24316 48373 23777 48374 24305 48374 24094 48374 24094 48375 24305 48375 24304 48375 24094 48376 24304 48376 24095 48376 24095 48377 24304 48377 24303 48377 23783 48378 24297 48378 23780 48378 23780 48379 24297 48379 24296 48379 23780 48380 24296 48380 24096 48380 24096 48381 24296 48381 24097 48381 24096 48382 24097 48382 23777 48382 23777 48383 24097 48383 24305 48383 23783 48384 23785 48384 24297 48384 24297 48385 23785 48385 24298 48385 24098 48386 24328 48386 23786 48386 23786 48387 24328 48387 24299 48387 23786 48388 24299 48388 23785 48388 23785 48389 24299 48389 24298 48389 23791 48390 24102 48390 24099 48390 24099 48391 24102 48391 24344 48391 24099 48392 24344 48392 24117 48392 24117 48393 24344 48393 24100 48393 23794 48394 24101 48394 23791 48394 23791 48395 24101 48395 24102 48395 24103 48396 24340 48396 23795 48396 23795 48397 24340 48397 24104 48397 23795 48398 24104 48398 24105 48398 24105 48399 24104 48399 24343 48399 23797 48400 24107 48400 24106 48400 24106 48401 24107 48401 24109 48401 24106 48402 24109 48402 24108 48402 24108 48403 24109 48403 24110 48403 24108 48404 24110 48404 24111 48404 24111 48405 24110 48405 24112 48405 24111 48406 24112 48406 24103 48406 24103 48407 24112 48407 24340 48407 23801 48408 24327 48408 24113 48408 24113 48409 24327 48409 24338 48409 24113 48410 24338 48410 23797 48410 23797 48411 24338 48411 24107 48411 23805 48412 24334 48412 23804 48412 23804 48413 24334 48413 24115 48413 23804 48414 24115 48414 24114 48414 24114 48415 24115 48415 24116 48415 24114 48416 24116 48416 23801 48416 23801 48417 24116 48417 24327 48417 23805 48418 24119 48418 24334 48418 24334 48419 24119 48419 24335 48419 24117 48420 24100 48420 23809 48420 23809 48421 24100 48421 24118 48421 23809 48422 24118 48422 23806 48422 23806 48423 24118 48423 24336 48423 23806 48424 24336 48424 24119 48424 24119 48425 24336 48425 24335 48425 24120 48426 24353 48426 23812 48426 23812 48427 24353 48427 24121 48427 23812 48428 24121 48428 23811 48428 23811 48429 24121 48429 24122 48429 23814 48430 24355 48430 23816 48430 23816 48431 24355 48431 24123 48431 23816 48432 24123 48432 23817 48432 23817 48433 24123 48433 24124 48433 23817 48434 24124 48434 24120 48434 24120 48435 24124 48435 24353 48435 24125 48436 24350 48436 24126 48436 24126 48437 24350 48437 24247 48437 24126 48438 24247 48438 24127 48438 24127 48439 24247 48439 14390 48439 24133 48440 24345 48440 23822 48440 23822 48441 24345 48441 24128 48441 23822 48442 24128 48442 23823 48442 23823 48443 24128 48443 24129 48443 23823 48444 24129 48444 24130 48444 24130 48445 24129 48445 24452 48445 24130 48446 24452 48446 24125 48446 24125 48447 24452 48447 24350 48447 24135 48448 24134 48448 24131 48448 24131 48449 24134 48449 24132 48449 24131 48450 24132 48450 24133 48450 24133 48451 24132 48451 24345 48451 24137 48452 24134 48452 24135 48452 23833 48453 24347 48453 23831 48453 23831 48454 24347 48454 24136 48454 23831 48455 24136 48455 23829 48455 23829 48456 24136 48456 24137 48456 23829 48457 24137 48457 14594 48457 14594 48458 24137 48458 24135 48458 23833 48459 24142 48459 24347 48459 24347 48460 24142 48460 24138 48460 23811 48461 24122 48461 24139 48461 24139 48462 24122 48462 24140 48462 24139 48463 24140 48463 24141 48463 24141 48464 24140 48464 24351 48464 24141 48465 24351 48465 24142 48465 24142 48466 24351 48466 24138 48466 14588 48467 24295 48467 23841 48467 23841 48468 24295 48468 24143 48468 23841 48469 24143 48469 23840 48469 23840 48470 24143 48470 24293 48470 23840 48471 24293 48471 24144 48471 24144 48472 24293 48472 24145 48472 24144 48473 24145 48473 23837 48473 23837 48474 24145 48474 24356 48474 23837 48475 24356 48475 24146 48475 24146 48476 24356 48476 24348 48476 24146 48477 24348 48477 23836 48477 23836 48478 24348 48478 24346 48478 23836 48479 24346 48479 14384 48479 14384 48480 24346 48480 24352 48480 14379 48481 14378 48481 23850 48481 23850 48482 14378 48482 24147 48482 23850 48483 24147 48483 23846 48483 23846 48484 24147 48484 24148 48484 23846 48485 24148 48485 23844 48485 23844 48486 24148 48486 24149 48486 23844 48487 24149 48487 23843 48487 23843 48488 24149 48488 24151 48488 23843 48489 24151 48489 24150 48489 24150 48490 24151 48490 24152 48490 24150 48491 24152 48491 24153 48491 24153 48492 24152 48492 24399 48492 14372 48493 24382 48493 23856 48493 23856 48494 24382 48494 24380 48494 23856 48495 24380 48495 23855 48495 23855 48496 24380 48496 24379 48496 23855 48497 24379 48497 23854 48497 23854 48498 24379 48498 24378 48498 23854 48499 24378 48499 23853 48499 23853 48500 24378 48500 24376 48500 23853 48501 24376 48501 23851 48501 23851 48502 24376 48502 24375 48502 23851 48503 24375 48503 14582 48503 14582 48504 24375 48504 24389 48504 23864 48505 24362 48505 24154 48505 24154 48506 24362 48506 24155 48506 24154 48507 24155 48507 23863 48507 23863 48508 24155 48508 24363 48508 23863 48509 24363 48509 23861 48509 23861 48510 24363 48510 24291 48510 23861 48511 24291 48511 23860 48511 23860 48512 24291 48512 24156 48512 23860 48513 24156 48513 23859 48513 23859 48514 24156 48514 24365 48514 23859 48515 24365 48515 23858 48515 23858 48516 24365 48516 24366 48516 23858 48517 24366 48517 14574 48517 14574 48518 24366 48518 24369 48518 24318 48519 24157 48519 24319 48519 24319 48520 24157 48520 23865 48520 24319 48521 23865 48521 24325 48521 24325 48522 23865 48522 24159 48522 24325 48523 24159 48523 24158 48523 24158 48524 24159 48524 23867 48524 24158 48525 23867 48525 24324 48525 24324 48526 23867 48526 23868 48526 24324 48527 23868 48527 24160 48527 24160 48528 23868 48528 23869 48528 24160 48529 23869 48529 24161 48529 24161 48530 23869 48530 24162 48530 24162 48531 23869 48531 23870 48531 24162 48532 23870 48532 24300 48532 24164 48533 14358 48533 24163 48533 24163 48534 23871 48534 24164 48534 24164 48535 23871 48535 23873 48535 24164 48536 23873 48536 24483 48536 23873 48537 24165 48537 24483 48537 24483 48538 24165 48538 24166 48538 24483 48539 24166 48539 24474 48539 24166 48540 24167 48540 24474 48540 24474 48541 24167 48541 24168 48541 24474 48542 24168 48542 24476 48542 24476 48543 24168 48543 24169 48543 24476 48544 24169 48544 24498 48544 14349 48545 24492 48545 23877 48545 23877 48546 24492 48546 24490 48546 23877 48547 24490 48547 24170 48547 24170 48548 24490 48548 24499 48548 24170 48549 24499 48549 23875 48549 23875 48550 24499 48550 24498 48550 23875 48551 24498 48551 24171 48551 24171 48552 24498 48552 24169 48552 23879 48553 24470 48553 23878 48553 23878 48554 24470 48554 24469 48554 23878 48555 24469 48555 24172 48555 24172 48556 24469 48556 24464 48556 24172 48557 24464 48557 14551 48557 14551 48558 24464 48558 24465 48558 23880 48559 24173 48559 23879 48559 23879 48560 24173 48560 24174 48560 23879 48561 24174 48561 24470 48561 14347 48562 24175 48562 23884 48562 23884 48563 24175 48563 24176 48563 23884 48564 24176 48564 23880 48564 23880 48565 24176 48565 24471 48565 23880 48566 24471 48566 24173 48566 24178 48567 14341 48567 24177 48567 24177 48568 23885 48568 24178 48568 24178 48569 23885 48569 24179 48569 24178 48570 24179 48570 24454 48570 24454 48571 24179 48571 24180 48571 24454 48572 24180 48572 24505 48572 24505 48573 24180 48573 23889 48573 24505 48574 23889 48574 24181 48574 23889 48575 23891 48575 24181 48575 24181 48576 23891 48576 24182 48576 24181 48577 24182 48577 24183 48577 24182 48578 23894 48578 24183 48578 24183 48579 23894 48579 23895 48579 24183 48580 23895 48580 24184 48580 24184 48581 23895 48581 23897 48581 24184 48582 23897 48582 24455 48582 23901 48583 24185 48583 24186 48583 24186 48584 24185 48584 24455 48584 24186 48585 24455 48585 23899 48585 23899 48586 24455 48586 23897 48586 24187 48587 14332 48587 24188 48587 24188 48588 23903 48588 24187 48588 24187 48589 23903 48589 23905 48589 24187 48590 23905 48590 24189 48590 24189 48591 23905 48591 24447 48591 23905 48592 24190 48592 24447 48592 24447 48593 24190 48593 23907 48593 24447 48594 23907 48594 24448 48594 23907 48595 24191 48595 24448 48595 24448 48596 24191 48596 23909 48596 24448 48597 23909 48597 24449 48597 23909 48598 23911 48598 24449 48598 24449 48599 23911 48599 24192 48599 24449 48600 24192 48600 24193 48600 24193 48601 24192 48601 24196 48601 24193 48602 24196 48602 24450 48602 23914 48603 24194 48603 24195 48603 24195 48604 24194 48604 24450 48604 24195 48605 24450 48605 23912 48605 23912 48606 24450 48606 24196 48606 24508 48607 24255 48607 23915 48607 24508 48608 23915 48608 24442 48608 24442 48609 23915 48609 23916 48609 24442 48610 23916 48610 24197 48610 24197 48611 23916 48611 23918 48611 24197 48612 23918 48612 24440 48612 23918 48613 23919 48613 24440 48613 24440 48614 23919 48614 23920 48614 24440 48615 23920 48615 24198 48615 23920 48616 23921 48616 24198 48616 24198 48617 23921 48617 23924 48617 24198 48618 23924 48618 24241 48618 23924 48619 23925 48619 24241 48619 24241 48620 23925 48620 23927 48620 24241 48621 23927 48621 24243 48621 24243 48622 23927 48622 24203 48622 24243 48623 24203 48623 24201 48623 24199 48624 24354 48624 24200 48624 24200 48625 24354 48625 24201 48625 24200 48626 24201 48626 24202 48626 24202 48627 24201 48627 24203 48627 14312 48628 14311 48628 23933 48628 23933 48629 14311 48629 24204 48629 23933 48630 24204 48630 24205 48630 24205 48631 24204 48631 24248 48631 24205 48632 24248 48632 23931 48632 23931 48633 24248 48633 24249 48633 23931 48634 24249 48634 24206 48634 24206 48635 24249 48635 24207 48635 24206 48636 24207 48636 23930 48636 23930 48637 24207 48637 24250 48637 23930 48638 24250 48638 24208 48638 24208 48639 24250 48639 14318 48639 14305 48640 24209 48640 24210 48640 24210 48641 24209 48641 24211 48641 24210 48642 24211 48642 24212 48642 24212 48643 24211 48643 24420 48643 24212 48644 24420 48644 23937 48644 23937 48645 24420 48645 24418 48645 23937 48646 24418 48646 24213 48646 24213 48647 24418 48647 24214 48647 24213 48648 24214 48648 23936 48648 23936 48649 24214 48649 24416 48649 23936 48650 24416 48650 24215 48650 24215 48651 24416 48651 24216 48651 24215 48652 24216 48652 14493 48652 14493 48653 24216 48653 24412 48653 14486 48654 24218 48654 24217 48654 24217 48655 24218 48655 24403 48655 24217 48656 24403 48656 23947 48656 23947 48657 24403 48657 24219 48657 23947 48658 24219 48658 23944 48658 23944 48659 24219 48659 24220 48659 23944 48660 24220 48660 24221 48660 24221 48661 24220 48661 24222 48661 24221 48662 24222 48662 23942 48662 23942 48663 24222 48663 24223 48663 23942 48664 24223 48664 14474 48664 14474 48665 24223 48665 24224 48665 24470 48666 24174 48666 24459 48666 24454 48667 24505 48667 24225 48667 24504 48668 24226 48668 24225 48668 24201 48669 24244 48669 24243 48669 24204 48670 24227 48670 24248 48670 24435 48671 24428 48671 24432 48671 24228 48672 24229 48672 24429 48672 24261 48673 24432 48673 14285 48673 24230 48674 24231 48674 24424 48674 14279 48675 24411 48675 24424 48675 24232 48676 14299 48676 24408 48676 24398 48677 14380 48677 14292 48677 24233 48678 24394 48678 14292 48678 14377 48679 24234 48679 14295 48679 14373 48680 24235 48680 24383 48680 24336 48681 24118 48681 24236 48681 24327 48682 24116 48682 24333 48682 24097 48683 24296 48683 24294 48683 24284 48684 24237 48684 24294 48684 24238 48685 24421 48685 24422 48685 24433 48686 24239 48686 24270 48686 24443 48687 23977 48687 24240 48687 23971 48688 23972 48688 24438 48688 14444 48689 24241 48689 24242 48689 24242 48690 24241 48690 24243 48690 24242 48691 24243 48691 24245 48691 24245 48692 24243 48692 24244 48692 24245 48693 24244 48693 14441 48693 24438 48694 23972 48694 24246 48694 23977 48695 23979 48695 24350 48695 23979 48696 23980 48696 24350 48696 24350 48697 23980 48697 23981 48697 24350 48698 23981 48698 24247 48698 24247 48699 23981 48699 14439 48699 24247 48700 14439 48700 14441 48700 14435 48701 14436 48701 24248 48701 24248 48702 14436 48702 24249 48702 24249 48703 14436 48703 14437 48703 24249 48704 14437 48704 24207 48704 14282 48705 24250 48705 24207 48705 14437 48706 24251 48706 24207 48706 24207 48707 24251 48707 24252 48707 24207 48708 24252 48708 14282 48708 14282 48709 24252 48709 14438 48709 14282 48710 14438 48710 24258 48710 24253 48711 23988 48711 14321 48711 14321 48712 23988 48712 23990 48712 24508 48713 24254 48713 24255 48713 24255 48714 24254 48714 24258 48714 24255 48715 24258 48715 14325 48715 14325 48716 24258 48716 24256 48716 14438 48717 24257 48717 24258 48717 24258 48718 24257 48718 23984 48718 24258 48719 23984 48719 24256 48719 23984 48720 24259 48720 24256 48720 24256 48721 24259 48721 23986 48721 24256 48722 23986 48722 24253 48722 24253 48723 23986 48723 24260 48723 24253 48724 24260 48724 23988 48724 23992 48725 24432 48725 14433 48725 14433 48726 24432 48726 24261 48726 14433 48727 24261 48727 14432 48727 14432 48728 24261 48728 24262 48728 24239 48729 24263 48729 24264 48729 24264 48730 24263 48730 24265 48730 24264 48731 24265 48731 24419 48731 24419 48732 24265 48732 24417 48732 24262 48733 24261 48733 14429 48733 14429 48734 24261 48734 14283 48734 14429 48735 14283 48735 24413 48735 14403 48736 14402 48736 24266 48736 14402 48737 14401 48737 24266 48737 24266 48738 14401 48738 14400 48738 24266 48739 14400 48739 24268 48739 24268 48740 14400 48740 24267 48740 24268 48741 24267 48741 24352 48741 24352 48742 24267 48742 24042 48742 24352 48743 24042 48743 24269 48743 24239 48744 24264 48744 24270 48744 24270 48745 24264 48745 24271 48745 24270 48746 24271 48746 24434 48746 24238 48747 24422 48747 24278 48747 24057 48748 24059 48748 24276 48748 24276 48749 24059 48749 24274 48749 24269 48750 24045 48750 24352 48750 24352 48751 24045 48751 24029 48751 24352 48752 24029 48752 14385 48752 14385 48753 24029 48753 24272 48753 14385 48754 24272 48754 24360 48754 24360 48755 24272 48755 24273 48755 24360 48756 24273 48756 24274 48756 24274 48757 24273 48757 24031 48757 24274 48758 24031 48758 24276 48758 24059 48759 24058 48759 24274 48759 24274 48760 24058 48760 24060 48760 24274 48761 24060 48761 24282 48761 24282 48762 24060 48762 24064 48762 24411 48763 24223 48763 24422 48763 24422 48764 24223 48764 24222 48764 24422 48765 24222 48765 24220 48765 24057 48766 24276 48766 24275 48766 24275 48767 24276 48767 24277 48767 24275 48768 24277 48768 14398 48768 14398 48769 24277 48769 24034 48769 14398 48770 24034 48770 24279 48770 24279 48771 24034 48771 24278 48771 24279 48772 24278 48772 24054 48772 24054 48773 24278 48773 24422 48773 24054 48774 24422 48774 24056 48774 24056 48775 24422 48775 24220 48775 24056 48776 24220 48776 24280 48776 24280 48777 24220 48777 24219 48777 24280 48778 24219 48778 24395 48778 24287 48779 24281 48779 24385 48779 24385 48780 24281 48780 24052 48780 24064 48781 24063 48781 24282 48781 24282 48782 24063 48782 24283 48782 24282 48783 24283 48783 24047 48783 14395 48784 24284 48784 14389 48784 14389 48785 24284 48785 24295 48785 24357 48786 24282 48786 24285 48786 24285 48787 24282 48787 24047 48787 24285 48788 24047 48788 24080 48788 24080 48789 24047 48789 24046 48789 24080 48790 24046 48790 24288 48790 14395 48791 14389 48791 14397 48791 14397 48792 14389 48792 24286 48792 14397 48793 24286 48793 24357 48793 24046 48794 24287 48794 24288 48794 24288 48795 24287 48795 24385 48795 24288 48796 24385 48796 24073 48796 14297 48797 24289 48797 24383 48797 24383 48798 24289 48798 14406 48798 24383 48799 14406 48799 24381 48799 24077 48800 24377 48800 24071 48800 24071 48801 24377 48801 24016 48801 24071 48802 24016 48802 24072 48802 24290 48803 24023 48803 14297 48803 14297 48804 24023 48804 24025 48804 14297 48805 24025 48805 24289 48805 24016 48806 24018 48806 24072 48806 24072 48807 24018 48807 24021 48807 24072 48808 24021 48808 24290 48808 24290 48809 24021 48809 24022 48809 24290 48810 24022 48810 24023 48810 24291 48811 24363 48811 24301 48811 24291 48812 24301 48812 24156 48812 24156 48813 24301 48813 24308 48813 24156 48814 24308 48814 24365 48814 24237 48815 24292 48815 24294 48815 24294 48816 24292 48816 24084 48816 24294 48817 24084 48817 24308 48817 24308 48818 24084 48818 24066 48818 24333 48819 24293 48819 24299 48819 24284 48820 24294 48820 24295 48820 24295 48821 24294 48821 24296 48821 24295 48822 24296 48822 24143 48822 24143 48823 24296 48823 24297 48823 24143 48824 24297 48824 24293 48824 24293 48825 24297 48825 24298 48825 24293 48826 24298 48826 24299 48826 14364 48827 24301 48827 24300 48827 24300 48828 24301 48828 24302 48828 24300 48829 24302 48829 24162 48829 24309 48830 24303 48830 24308 48830 24308 48831 24303 48831 24304 48831 24308 48832 24304 48832 24294 48832 24294 48833 24304 48833 24305 48833 24294 48834 24305 48834 24097 48834 14364 48835 24306 48835 24301 48835 24301 48836 24306 48836 24307 48836 24301 48837 24307 48837 24308 48837 24308 48838 24307 48838 14361 48838 24308 48839 14361 48839 24309 48839 24309 48840 14361 48840 24091 48840 24310 48841 24311 48841 24326 48841 14465 48842 24323 48842 14464 48842 14464 48843 24323 48843 24314 48843 24311 48844 23950 48844 24326 48844 24326 48845 23950 48845 24313 48845 24326 48846 24313 48846 24312 48846 24312 48847 24313 48847 23954 48847 24312 48848 23954 48848 24314 48848 24314 48849 23954 48849 23955 48849 24314 48850 23955 48850 14464 48850 24091 48851 14361 48851 24092 48851 24092 48852 14361 48852 24315 48852 24092 48853 24315 48853 24316 48853 24316 48854 24315 48854 24318 48854 24316 48855 24318 48855 24317 48855 24317 48856 24318 48856 24319 48856 24317 48857 24319 48857 24320 48857 24320 48858 24319 48858 24325 48858 24320 48859 24325 48859 24321 48859 24321 48860 24325 48860 24326 48860 24321 48861 24326 48861 24489 48861 14467 48862 24325 48862 24322 48862 24322 48863 24325 48863 24158 48863 24322 48864 24158 48864 14465 48864 14465 48865 24158 48865 24324 48865 14465 48866 24324 48866 24323 48866 24323 48867 24324 48867 24160 48867 24323 48868 24160 48868 24161 48868 14467 48869 14468 48869 24325 48869 24325 48870 14468 48870 14470 48870 24325 48871 14470 48871 24326 48871 24326 48872 14470 48872 14471 48872 24326 48873 14471 48873 24310 48873 24338 48874 24327 48874 24337 48874 24337 48875 24327 48875 24333 48875 24337 48876 24333 48876 24328 48876 24328 48877 24333 48877 24299 48877 24329 48878 24339 48878 24331 48878 24331 48879 24339 48879 24330 48879 24331 48880 24330 48880 24332 48880 24332 48881 24330 48881 24085 48881 24116 48882 24115 48882 24333 48882 24333 48883 24115 48883 24334 48883 24333 48884 24334 48884 24236 48884 24236 48885 24334 48885 24335 48885 24236 48886 24335 48886 24336 48886 24337 48887 24085 48887 24338 48887 24338 48888 24085 48888 24330 48888 24338 48889 24330 48889 24107 48889 24107 48890 24330 48890 24339 48890 24107 48891 24339 48891 24109 48891 14344 48892 24104 48892 14345 48892 14345 48893 24104 48893 24340 48893 14345 48894 24340 48894 24341 48894 24341 48895 24340 48895 24112 48895 24112 48896 24110 48896 24341 48896 24341 48897 24110 48897 24109 48897 24341 48898 24109 48898 14346 48898 14346 48899 24109 48899 24339 48899 14346 48900 24339 48900 14348 48900 24226 48901 24451 48901 14340 48901 14344 48902 24466 48902 24104 48902 24104 48903 24466 48903 24342 48903 24104 48904 24342 48904 24343 48904 24343 48905 24342 48905 14335 48905 24343 48906 14335 48906 14391 48906 14391 48907 14335 48907 14334 48907 24451 48908 24452 48908 24129 48908 14334 48909 14340 48909 14391 48909 14391 48910 14340 48910 24451 48910 14391 48911 24451 48911 14393 48911 14393 48912 24451 48912 24129 48912 14393 48913 24129 48913 24128 48913 24134 48914 24100 48914 24132 48914 24132 48915 24100 48915 24344 48915 24132 48916 24344 48916 24345 48916 24345 48917 24344 48917 24102 48917 24345 48918 24102 48918 24128 48918 24128 48919 24102 48919 24101 48919 24128 48920 24101 48920 14393 48920 24137 48921 24236 48921 24134 48921 24134 48922 24236 48922 24118 48922 24134 48923 24118 48923 24100 48923 24351 48924 24352 48924 24138 48924 24138 48925 24352 48925 24346 48925 24138 48926 24346 48926 24347 48926 24347 48927 24346 48927 24348 48927 24347 48928 24348 48928 24136 48928 24136 48929 24348 48929 24137 48929 24349 48930 24444 48930 24240 48930 23977 48931 24350 48931 24240 48931 24240 48932 24350 48932 14330 48932 24240 48933 14330 48933 24349 48933 24266 48934 24124 48934 24123 48934 24351 48935 24140 48935 24352 48935 24352 48936 24140 48936 24122 48936 24352 48937 24122 48937 24268 48937 24268 48938 24122 48938 24121 48938 24268 48939 24121 48939 24266 48939 24266 48940 24121 48940 24353 48940 24266 48941 24353 48941 24124 48941 14441 48942 24244 48942 24247 48942 24247 48943 24244 48943 24201 48943 24247 48944 24201 48944 14390 48944 14390 48945 24201 48945 24354 48945 14390 48946 24354 48946 24355 48946 24355 48947 24354 48947 14320 48947 24355 48948 14320 48948 24123 48948 24137 48949 24348 48949 24236 48949 24236 48950 24348 48950 24356 48950 24236 48951 24356 48951 24333 48951 24333 48952 24356 48952 24145 48952 24333 48953 24145 48953 24293 48953 24357 48954 24286 48954 24282 48954 24282 48955 24286 48955 24358 48955 24282 48956 24358 48956 24274 48956 24274 48957 24358 48957 24359 48957 24274 48958 24359 48958 24360 48958 14365 48959 24361 48959 24362 48959 24362 48960 24361 48960 24301 48960 24362 48961 24301 48961 24155 48961 24155 48962 24301 48962 24363 48962 24066 48963 24364 48963 24308 48963 24308 48964 24364 48964 24068 48964 24308 48965 24068 48965 24365 48965 24365 48966 24068 48966 24367 48966 24365 48967 24367 48967 24366 48967 24366 48968 24367 48968 24368 48968 24366 48969 24368 48969 24369 48969 24369 48970 24368 48970 24371 48970 24369 48971 24371 48971 24370 48971 24370 48972 24371 48972 24069 48972 24370 48973 24069 48973 14368 48973 14368 48974 24069 48974 24072 48974 14368 48975 24072 48975 24372 48975 24372 48976 24072 48976 24290 48976 24372 48977 24290 48977 14369 48977 14369 48978 24290 48978 24373 48978 14369 48979 24373 48979 14370 48979 14370 48980 24373 48980 14371 48980 24074 48981 24389 48981 24374 48981 24374 48982 24389 48982 24375 48982 24374 48983 24375 48983 24077 48983 24077 48984 24375 48984 24376 48984 24077 48985 24376 48985 24377 48985 24377 48986 24376 48986 24378 48986 24377 48987 24378 48987 14411 48987 14411 48988 24378 48988 24379 48988 14411 48989 24379 48989 14409 48989 14409 48990 24379 48990 24380 48990 14409 48991 24380 48991 24381 48991 24381 48992 24380 48992 24382 48992 24381 48993 24382 48993 24383 48993 24383 48994 24382 48994 24384 48994 24383 48995 24384 48995 14373 48995 24387 48996 24389 48996 24385 48996 24385 48997 24389 48997 24074 48997 24385 48998 24074 48998 24073 48998 24013 48999 24014 48999 24386 48999 24387 49000 24388 49000 24389 49000 24389 49001 24388 49001 24013 49001 24389 49002 24013 49002 14375 49002 14375 49003 24013 49003 24386 49003 14414 49004 14278 49004 24390 49004 24390 49005 14278 49005 24234 49005 24394 49006 24391 49006 24385 49006 24385 49007 24391 49007 24011 49007 24385 49008 24011 49008 24387 49008 24014 49009 24390 49009 24386 49009 24386 49010 24390 49010 24234 49010 24386 49011 24234 49011 14376 49011 14376 49012 24234 49012 14377 49012 14414 49013 24392 49013 14278 49013 14278 49014 24392 49014 14415 49014 14278 49015 14415 49015 24233 49015 14415 49016 14418 49016 24233 49016 24233 49017 14418 49017 24393 49017 24233 49018 24393 49018 24394 49018 24394 49019 24393 49019 14420 49019 24394 49020 14420 49020 24391 49020 24219 49021 24403 49021 24395 49021 24395 49022 24403 49022 24152 49022 24395 49023 24152 49023 24396 49023 24396 49024 24152 49024 24151 49024 24396 49025 24151 49025 24050 49025 24050 49026 24151 49026 24149 49026 24050 49027 24149 49027 24052 49027 24052 49028 24149 49028 24148 49028 24052 49029 24148 49029 24385 49029 24385 49030 24148 49030 24147 49030 24385 49031 24147 49031 24394 49031 24394 49032 24147 49032 14378 49032 24394 49033 14378 49033 14292 49033 14292 49034 14378 49034 24397 49034 14292 49035 24397 49035 24398 49035 14290 49036 14293 49036 24404 49036 24403 49037 24003 49037 24152 49037 24152 49038 24003 49038 24005 49038 24152 49039 24005 49039 24399 49039 24399 49040 24005 49040 24010 49040 24399 49041 24010 49041 14381 49041 24404 49042 24400 49042 14290 49042 14290 49043 24400 49043 24401 49043 14290 49044 24401 49044 14291 49044 14291 49045 24401 49045 24402 49045 14291 49046 24402 49046 24408 49046 24408 49047 24402 49047 24407 49047 24407 49048 23999 49048 24409 49048 24409 49049 23999 49049 24218 49049 24218 49050 23999 49050 24000 49050 24218 49051 24000 49051 24403 49051 24403 49052 24000 49052 24001 49052 24403 49053 24001 49053 24003 49053 24010 49054 24008 49054 14381 49054 14381 49055 24008 49055 24404 49055 14381 49056 24404 49056 24405 49056 24405 49057 24404 49057 14293 49057 24405 49058 14293 49058 14383 49058 14383 49059 14293 49059 24406 49059 24407 49060 24409 49060 24408 49060 24408 49061 24409 49061 24410 49061 24408 49062 24410 49062 24232 49062 14300 49063 14302 49063 14279 49063 14279 49064 14302 49064 14303 49064 14279 49065 14303 49065 24411 49065 24411 49066 14303 49066 24224 49066 24411 49067 24224 49067 24223 49067 14283 49068 24412 49068 24413 49068 24413 49069 24412 49069 24216 49069 24413 49070 24216 49070 24414 49070 24414 49071 24216 49071 24416 49071 24414 49072 24416 49072 24415 49072 24415 49073 24416 49073 24214 49073 24415 49074 24214 49074 24417 49074 24417 49075 24214 49075 24418 49075 24417 49076 24418 49076 24419 49076 24419 49077 24418 49077 24420 49077 24419 49078 24420 49078 24421 49078 24421 49079 24420 49079 24211 49079 24421 49080 24211 49080 24422 49080 24422 49081 24211 49081 24209 49081 24422 49082 24209 49082 24411 49082 24209 49083 14304 49083 24411 49083 24411 49084 14304 49084 24423 49084 24411 49085 24423 49085 24424 49085 24424 49086 24423 49086 24425 49086 24424 49087 24425 49087 24230 49087 14283 49088 24426 49088 24412 49088 24412 49089 24426 49089 24427 49089 24412 49090 24427 49090 14306 49090 14306 49091 24427 49091 14308 49091 24432 49092 24428 49092 14285 49092 14285 49093 24428 49093 24430 49093 14285 49094 24430 49094 24429 49094 24429 49095 24430 49095 24431 49095 24429 49096 24431 49096 24228 49096 23992 49097 24433 49097 24432 49097 24432 49098 24433 49098 24270 49098 24432 49099 24270 49099 24435 49099 24435 49100 24270 49100 24434 49100 24435 49101 24434 49101 14310 49101 14310 49102 24434 49102 24271 49102 14310 49103 24271 49103 14311 49103 14311 49104 24271 49104 24041 49104 14311 49105 24041 49105 24204 49105 24204 49106 24041 49106 14403 49106 24204 49107 14403 49107 24227 49107 24227 49108 14403 49108 24266 49108 24227 49109 24266 49109 24248 49109 24248 49110 24266 49110 24437 49110 24248 49111 24437 49111 14435 49111 24250 49112 14282 49112 14318 49112 14318 49113 14282 49113 24436 49113 14318 49114 24436 49114 14281 49114 24123 49115 14320 49115 24266 49115 24266 49116 14320 49116 14321 49116 24266 49117 14321 49117 24437 49117 24437 49118 14321 49118 23990 49118 24437 49119 23990 49119 14435 49119 14444 49120 23971 49120 24241 49120 24241 49121 23971 49121 24438 49121 24241 49122 24438 49122 24198 49122 24198 49123 24438 49123 24439 49123 24198 49124 24439 49124 24440 49124 24440 49125 24439 49125 24441 49125 24440 49126 24441 49126 24197 49126 24197 49127 24441 49127 24442 49127 23972 49128 24443 49128 24246 49128 24246 49129 24443 49129 24240 49129 24246 49130 24240 49130 24506 49130 24506 49131 24240 49131 24444 49131 24506 49132 24444 49132 24445 49132 24445 49133 24444 49133 14332 49133 24445 49134 14332 49134 24446 49134 24446 49135 14332 49135 24187 49135 24446 49136 24187 49136 24189 49136 24447 49137 24448 49137 24504 49137 24504 49138 24448 49138 24449 49138 24504 49139 24449 49139 24226 49139 24449 49140 24193 49140 24226 49140 24226 49141 24193 49141 24450 49141 24226 49142 24450 49142 24451 49142 24451 49143 24450 49143 24194 49143 24451 49144 24194 49144 24452 49144 24452 49145 24194 49145 14327 49145 24452 49146 14327 49146 24350 49146 24350 49147 14327 49147 14329 49147 24350 49148 14329 49148 14330 49148 14340 49149 24453 49149 24226 49149 24226 49150 24453 49150 14341 49150 24226 49151 14341 49151 24225 49151 24225 49152 14341 49152 24178 49152 24225 49153 24178 49153 24454 49153 24455 49154 14453 49154 24467 49154 24466 49155 24456 49155 24342 49155 24342 49156 24456 49156 14449 49156 24342 49157 14449 49157 14452 49157 24457 49158 24459 49158 24458 49158 24458 49159 24459 49159 24460 49159 24458 49160 24460 49160 24461 49160 24461 49161 24460 49161 24462 49161 24461 49162 24462 49162 23962 49162 24457 49163 24463 49163 24464 49163 24464 49164 24463 49164 24465 49164 24465 49165 24463 49165 14446 49165 24465 49166 14446 49166 24466 49166 24466 49167 14446 49167 14448 49167 24466 49168 14448 49168 24456 49168 23962 49169 24462 49169 24467 49169 24467 49170 24462 49170 24468 49170 24467 49171 24468 49171 24455 49171 14453 49172 24455 49172 14452 49172 14452 49173 24455 49173 24185 49173 14452 49174 24185 49174 24342 49174 24181 49175 24183 49175 24468 49175 24468 49176 24183 49176 24184 49176 24468 49177 24184 49177 24455 49177 24457 49178 24464 49178 24459 49178 24459 49179 24464 49179 24469 49179 24459 49180 24469 49180 24470 49180 24472 49181 24173 49181 24471 49181 14348 49182 24479 49182 24175 49182 24175 49183 24479 49183 24472 49183 24175 49184 24472 49184 24176 49184 24176 49185 24472 49185 24471 49185 24473 49186 24478 49186 24479 49186 24483 49187 24474 49187 24475 49187 24475 49188 24474 49188 24476 49188 24475 49189 24476 49189 24498 49189 24473 49190 24479 49190 24477 49190 24478 49191 23958 49191 24479 49191 24479 49192 23958 49192 24480 49192 24479 49193 24480 49193 24472 49193 23958 49194 24481 49194 24480 49194 24480 49195 24481 49195 23959 49195 24480 49196 23959 49196 24482 49196 24482 49197 23959 49197 24484 49197 14348 49198 24339 49198 24479 49198 24479 49199 24339 49199 14463 49199 24479 49200 14463 49200 24477 49200 24485 49201 24164 49201 14455 49201 14455 49202 24164 49202 24483 49202 14455 49203 24483 49203 24484 49203 24484 49204 24483 49204 24475 49204 24484 49205 24475 49205 24482 49205 14458 49206 14459 49206 24339 49206 24339 49207 14459 49207 14462 49207 24339 49208 14462 49208 14463 49208 24485 49209 14458 49209 24164 49209 24164 49210 14458 49210 24339 49210 24164 49211 24339 49211 14358 49211 14358 49212 24339 49212 24329 49212 14358 49213 24329 49213 24486 49213 24486 49214 24329 49214 24487 49214 24486 49215 24487 49215 24488 49215 24488 49216 24487 49216 24489 49216 24488 49217 24489 49217 14355 49217 14355 49218 24489 49218 24326 49218 14355 49219 24326 49219 14354 49219 14354 49220 24326 49220 24312 49220 14354 49221 24312 49221 14351 49221 24499 49222 24490 49222 24491 49222 24491 49223 24490 49223 24492 49223 24491 49224 24492 49224 24312 49224 24312 49225 24492 49225 24493 49225 24312 49226 24493 49226 14351 49226 24445 49227 24446 49227 24494 49227 24468 49228 24462 49228 24502 49228 24161 49229 24496 49229 24323 49229 24323 49230 24496 49230 24495 49230 24323 49231 24495 49231 24314 49231 24301 49232 13710 49232 24302 49232 24302 49233 13710 49233 24496 49233 24302 49234 24496 49234 24162 49234 24162 49235 24496 49235 24161 49235 24314 49236 24495 49236 24312 49236 24312 49237 24495 49237 24497 49237 24312 49238 24497 49238 24491 49238 24482 49239 24475 49239 24500 49239 24500 49240 24475 49240 24498 49240 24500 49241 24498 49241 24497 49241 24497 49242 24498 49242 24499 49242 24497 49243 24499 49243 24491 49243 24482 49244 24500 49244 24480 49244 24480 49245 24500 49245 24501 49245 24480 49246 24501 49246 24472 49246 13701 49247 24459 49247 24174 49247 13701 49248 24174 49248 24501 49248 24501 49249 24174 49249 24173 49249 24501 49250 24173 49250 24472 49250 24502 49251 24462 49251 13701 49251 13701 49252 24462 49252 24460 49252 13701 49253 24460 49253 24459 49253 24468 49254 24502 49254 24181 49254 24181 49255 24502 49255 13697 49255 24181 49256 13697 49256 24505 49256 24446 49257 24189 49257 24494 49257 24494 49258 24189 49258 24447 49258 24494 49259 24447 49259 24503 49259 24503 49260 24447 49260 24504 49260 24503 49261 24504 49261 13697 49261 13697 49262 24504 49262 24225 49262 13697 49263 24225 49263 24505 49263 13696 49264 24438 49264 24246 49264 13696 49265 24246 49265 24494 49265 24494 49266 24246 49266 24506 49266 24494 49267 24506 49267 24445 49267 24508 49268 24442 49268 24507 49268 24507 49269 24442 49269 24441 49269 24507 49270 24441 49270 13696 49270 13696 49271 24441 49271 24439 49271 13696 49272 24439 49272 24438 49272 25765 49273 24258 49273 24507 49273 24507 49274 24258 49274 24254 49274 24507 49275 24254 49275 24508 49275 14277 49276 14276 49276 24509 49276 14277 49277 24509 49277 17660 49277 17660 49278 24509 49278 24607 49278 17660 49279 24607 49279 17661 49279 17661 49280 24607 49280 24510 49280 24510 49281 24607 49281 24511 49281 24510 49282 24511 49282 24512 49282 24512 49283 24511 49283 17658 49283 17658 49284 24511 49284 24513 49284 17658 49285 24513 49285 17659 49285 17659 49286 24513 49286 24514 49286 24514 49287 24513 49287 24515 49287 24514 49288 24515 49288 17655 49288 17655 49289 24515 49289 24608 49289 17655 49290 24608 49290 24516 49290 24516 49291 24608 49291 24609 49291 24516 49292 24609 49292 17654 49292 14267 49293 24518 49293 24517 49293 24517 49294 24518 49294 24520 49294 24517 49295 24520 49295 24519 49295 24519 49296 24520 49296 24521 49296 24519 49297 24521 49297 24522 49297 24522 49298 24521 49298 24523 49298 24522 49299 24523 49299 24524 49299 24524 49300 24523 49300 24526 49300 24524 49301 24526 49301 24525 49301 24525 49302 24526 49302 24612 49302 24525 49303 24612 49303 24527 49303 24527 49304 24612 49304 24615 49304 14260 49305 14159 49305 24528 49305 24528 49306 14159 49306 24529 49306 24528 49307 24529 49307 17669 49307 17669 49308 24529 49308 24530 49308 17669 49309 24530 49309 24531 49309 24531 49310 24530 49310 24532 49310 24531 49311 24532 49311 17671 49311 17671 49312 24532 49312 24533 49312 17671 49313 24533 49313 17673 49313 17673 49314 24533 49314 24618 49314 17673 49315 24618 49315 17674 49315 17674 49316 24618 49316 24534 49316 17674 49317 24534 49317 14253 49317 14253 49318 24534 49318 14255 49318 14252 49319 24619 49319 24620 49319 14252 49320 24620 49320 17680 49320 17680 49321 24620 49321 24622 49321 17680 49322 24622 49322 24535 49322 24535 49323 24622 49323 24536 49323 24536 49324 24622 49324 24538 49324 24536 49325 24538 49325 24537 49325 24537 49326 24538 49326 24539 49326 24539 49327 24538 49327 24540 49327 24539 49328 24540 49328 17679 49328 17679 49329 24540 49329 24541 49329 24541 49330 24540 49330 24625 49330 24541 49331 24625 49331 17678 49331 17678 49332 24625 49332 24542 49332 17678 49333 24542 49333 24543 49333 24543 49334 24542 49334 14149 49334 24543 49335 14149 49335 24544 49335 14243 49336 24626 49336 17681 49336 17681 49337 24626 49337 24545 49337 17681 49338 24545 49338 17682 49338 17682 49339 24545 49339 24627 49339 17682 49340 24627 49340 17684 49340 17684 49341 24627 49341 24547 49341 17684 49342 24547 49342 24546 49342 24546 49343 24547 49343 24628 49343 24546 49344 24628 49344 17685 49344 17685 49345 24628 49345 24548 49345 17685 49346 24548 49346 17687 49346 17687 49347 24548 49347 24549 49347 17687 49348 24549 49348 24550 49348 24550 49349 24549 49349 24630 49349 14235 49350 14236 49350 24551 49350 24551 49351 14236 49351 24631 49351 24551 49352 24631 49352 24552 49352 24552 49353 24631 49353 24553 49353 24552 49354 24553 49354 17691 49354 17691 49355 24553 49355 24554 49355 17691 49356 24554 49356 17692 49356 17692 49357 24554 49357 24555 49357 17692 49358 24555 49358 17694 49358 17694 49359 24555 49359 24556 49359 17694 49360 24556 49360 14228 49360 14228 49361 24556 49361 14230 49361 14227 49362 24558 49362 24557 49362 24557 49363 24558 49363 24559 49363 24558 49364 24560 49364 24559 49364 24559 49365 24560 49365 24561 49365 24559 49366 24561 49366 17697 49366 24561 49367 24562 49367 17697 49367 17697 49368 24562 49368 24563 49368 17697 49369 24563 49369 17700 49369 24563 49370 24640 49370 17700 49370 17700 49371 24640 49371 24639 49371 17700 49372 24639 49372 24564 49372 24639 49373 24638 49373 24564 49373 24564 49374 24638 49374 24637 49374 24564 49375 24637 49375 17702 49375 14219 49376 14218 49376 24565 49376 24565 49377 14218 49377 17702 49377 24565 49378 17702 49378 24566 49378 24566 49379 17702 49379 24637 49379 24642 49380 14204 49380 24643 49380 24643 49381 14204 49381 24567 49381 24643 49382 24567 49382 24568 49382 24568 49383 24567 49383 17705 49383 24568 49384 17705 49384 24569 49384 24569 49385 17705 49385 17708 49385 24569 49386 17708 49386 24570 49386 24570 49387 17708 49387 17707 49387 24570 49388 17707 49388 24645 49388 24645 49389 17707 49389 24571 49389 24645 49390 24571 49390 24572 49390 24572 49391 24571 49391 24573 49391 24572 49392 24573 49392 24646 49392 24646 49393 24573 49393 24575 49393 24646 49394 24575 49394 24574 49394 24574 49395 24575 49395 17710 49395 24574 49396 17710 49396 24576 49396 24576 49397 17710 49397 17715 49397 24576 49398 17715 49398 24650 49398 24650 49399 17715 49399 17714 49399 24650 49400 17714 49400 24577 49400 24577 49401 17714 49401 17711 49401 24577 49402 17711 49402 24648 49402 24648 49403 17711 49403 14217 49403 17587 49404 14122 49404 17717 49404 17717 49405 14122 49405 24652 49405 17717 49406 24652 49406 24578 49406 24578 49407 24652 49407 24653 49407 24578 49408 24653 49408 24579 49408 24579 49409 24653 49409 24654 49409 24579 49410 24654 49410 24580 49410 24580 49411 24654 49411 24581 49411 24580 49412 24581 49412 24582 49412 24582 49413 24581 49413 24657 49413 24582 49414 24657 49414 17722 49414 17722 49415 24657 49415 24583 49415 17722 49416 24583 49416 17724 49416 17724 49417 24583 49417 14197 49417 17725 49418 14116 49418 17726 49418 17726 49419 14116 49419 24659 49419 17726 49420 24659 49420 24584 49420 24584 49421 24659 49421 24660 49421 24584 49422 24660 49422 17729 49422 17729 49423 24660 49423 24662 49423 17729 49424 24662 49424 17730 49424 17730 49425 24662 49425 24664 49425 17730 49426 24664 49426 24585 49426 24585 49427 24664 49427 24587 49427 24585 49428 24587 49428 24586 49428 24586 49429 24587 49429 14187 49429 24588 49430 24666 49430 24668 49430 24588 49431 24668 49431 24589 49431 24589 49432 24668 49432 24590 49432 24589 49433 24590 49433 17736 49433 17736 49434 24590 49434 17737 49434 17737 49435 24590 49435 24591 49435 17737 49436 24591 49436 24592 49436 24592 49437 24591 49437 24593 49437 24593 49438 24591 49438 24594 49438 24593 49439 24594 49439 24595 49439 24595 49440 24594 49440 24596 49440 24596 49441 24594 49441 24597 49441 24596 49442 24597 49442 24598 49442 24598 49443 24597 49443 24672 49443 24598 49444 24672 49444 17732 49444 17732 49445 24672 49445 14102 49445 17732 49446 14102 49446 14182 49446 14064 49447 24600 49447 24599 49447 24599 49448 24600 49448 24602 49448 24600 49449 24601 49449 24602 49449 24602 49450 24601 49450 24765 49450 24602 49451 24765 49451 24603 49451 24765 49452 24764 49452 24603 49452 24603 49453 24764 49453 24762 49453 24603 49454 24762 49454 17739 49454 24762 49455 24761 49455 17739 49455 17739 49456 24761 49456 24604 49456 17739 49457 24604 49457 24605 49457 24604 49458 24759 49458 24605 49458 24605 49459 24759 49459 24757 49459 24605 49460 24757 49460 17741 49460 14174 49461 17548 49461 24755 49461 24755 49462 17548 49462 17741 49462 24755 49463 17741 49463 24606 49463 24606 49464 17741 49464 24757 49464 14276 49465 24776 49465 24509 49465 24509 49466 24776 49466 24778 49466 24509 49467 24778 49467 24607 49467 24607 49468 24778 49468 24779 49468 24607 49469 24779 49469 24511 49469 24511 49470 24779 49470 24780 49470 24511 49471 24780 49471 24513 49471 24513 49472 24780 49472 24768 49472 24513 49473 24768 49473 24515 49473 24515 49474 24768 49474 24769 49474 24515 49475 24769 49475 24608 49475 24608 49476 24769 49476 24610 49476 24608 49477 24610 49477 24609 49477 24609 49478 24610 49478 24611 49478 24518 49479 24792 49479 24520 49479 24520 49480 24792 49480 24790 49480 24520 49481 24790 49481 24521 49481 24521 49482 24790 49482 24789 49482 24521 49483 24789 49483 24523 49483 24523 49484 24789 49484 24787 49484 24523 49485 24787 49485 24526 49485 24526 49486 24787 49486 24613 49486 24526 49487 24613 49487 24612 49487 24612 49488 24613 49488 24614 49488 24612 49489 24614 49489 24615 49489 24615 49490 24614 49490 14161 49490 14159 49491 24800 49491 24529 49491 24529 49492 24800 49492 24616 49492 24529 49493 24616 49493 24530 49493 24530 49494 24616 49494 24797 49494 24530 49495 24797 49495 24532 49495 24532 49496 24797 49496 24812 49496 24532 49497 24812 49497 24533 49497 24533 49498 24812 49498 24617 49498 24533 49499 24617 49499 24618 49499 24618 49500 24617 49500 24810 49500 24618 49501 24810 49501 24534 49501 24534 49502 24810 49502 24809 49502 24534 49503 24809 49503 14255 49503 14255 49504 24809 49504 14154 49504 24619 49505 24823 49505 24620 49505 24620 49506 24823 49506 24621 49506 24620 49507 24621 49507 24622 49507 24622 49508 24621 49508 24623 49508 24622 49509 24623 49509 24538 49509 24538 49510 24623 49510 24624 49510 24538 49511 24624 49511 24540 49511 24540 49512 24624 49512 24813 49512 24540 49513 24813 49513 24625 49513 24625 49514 24813 49514 24814 49514 24625 49515 24814 49515 24542 49515 24542 49516 24814 49516 24815 49516 24542 49517 24815 49517 14149 49517 14149 49518 24815 49518 24816 49518 24626 49519 24831 49519 24545 49519 24545 49520 24831 49520 24830 49520 24545 49521 24830 49521 24627 49521 24627 49522 24830 49522 24829 49522 24627 49523 24829 49523 24547 49523 24547 49524 24829 49524 24828 49524 24547 49525 24828 49525 24628 49525 24628 49526 24828 49526 24629 49526 24628 49527 24629 49527 24548 49527 24548 49528 24629 49528 24825 49528 24548 49529 24825 49529 24549 49529 24549 49530 24825 49530 24836 49530 24549 49531 24836 49531 24630 49531 24630 49532 24836 49532 14144 49532 14236 49533 14143 49533 24631 49533 24631 49534 14143 49534 24839 49534 24631 49535 24839 49535 24553 49535 24553 49536 24839 49536 24632 49536 24553 49537 24632 49537 24554 49537 24554 49538 24632 49538 24842 49538 24554 49539 24842 49539 24555 49539 24555 49540 24842 49540 24843 49540 24555 49541 24843 49541 24556 49541 24556 49542 24843 49542 24633 49542 24556 49543 24633 49543 14230 49543 14230 49544 24633 49544 24634 49544 24635 49545 24845 49545 14219 49545 14219 49546 24565 49546 24635 49546 24635 49547 24565 49547 24566 49547 24635 49548 24566 49548 24636 49548 24566 49549 24637 49549 24636 49549 24636 49550 24637 49550 24638 49550 24636 49551 24638 49551 24858 49551 24858 49552 24638 49552 24639 49552 24858 49553 24639 49553 24856 49553 24639 49554 24640 49554 24856 49554 24856 49555 24640 49555 24563 49555 24856 49556 24563 49556 24641 49556 24563 49557 24562 49557 24641 49557 24641 49558 24562 49558 24561 49558 24641 49559 24561 49559 24854 49559 14227 49560 24853 49560 24558 49560 24558 49561 24853 49561 24854 49561 24558 49562 24854 49562 24560 49562 24560 49563 24854 49563 24561 49563 24644 49564 14129 49564 24642 49564 24642 49565 24643 49565 24644 49565 24644 49566 24643 49566 24568 49566 24644 49567 24568 49567 24869 49567 24568 49568 24569 49568 24869 49568 24869 49569 24569 49569 24570 49569 24869 49570 24570 49570 24870 49570 24570 49571 24645 49571 24870 49571 24870 49572 24645 49572 24572 49572 24870 49573 24572 49573 24859 49573 24859 49574 24572 49574 24646 49574 24859 49575 24646 49575 24647 49575 24646 49576 24574 49576 24647 49576 24647 49577 24574 49577 24576 49577 24647 49578 24576 49578 24649 49578 24648 49579 24861 49579 24577 49579 24577 49580 24861 49580 24649 49580 24577 49581 24649 49581 24650 49581 24650 49582 24649 49582 24576 49582 14122 49583 24651 49583 24652 49583 24652 49584 24651 49584 24880 49584 24652 49585 24880 49585 24653 49585 24653 49586 24880 49586 24881 49586 24653 49587 24881 49587 24654 49587 24654 49588 24881 49588 24655 49588 24654 49589 24655 49589 24581 49589 24581 49590 24655 49590 24656 49590 24581 49591 24656 49591 24657 49591 24657 49592 24656 49592 24874 49592 24657 49593 24874 49593 24583 49593 24583 49594 24874 49594 24658 49594 24583 49595 24658 49595 14197 49595 14197 49596 24658 49596 24876 49596 14116 49597 24883 49597 24659 49597 24659 49598 24883 49598 24884 49598 24659 49599 24884 49599 24660 49599 24660 49600 24884 49600 24661 49600 24660 49601 24661 49601 24662 49601 24662 49602 24661 49602 24663 49602 24662 49603 24663 49603 24664 49603 24664 49604 24663 49604 24886 49604 24664 49605 24886 49605 24587 49605 24587 49606 24886 49606 24665 49606 24587 49607 24665 49607 14187 49607 14187 49608 24665 49608 14109 49608 24666 49609 24667 49609 24668 49609 24668 49610 24667 49610 24903 49610 24668 49611 24903 49611 24590 49611 24590 49612 24903 49612 24905 49612 24590 49613 24905 49613 24591 49613 24591 49614 24905 49614 24669 49614 24591 49615 24669 49615 24594 49615 24594 49616 24669 49616 24670 49616 24594 49617 24670 49617 24597 49617 24597 49618 24670 49618 24671 49618 24597 49619 24671 49619 24672 49619 24672 49620 24671 49620 24673 49620 24672 49621 24673 49621 14102 49621 14102 49622 24673 49622 14103 49622 24678 49623 14099 49623 24674 49623 24907 49624 24908 49624 24678 49624 24677 49625 24676 49625 24678 49625 24910 49626 24911 49626 24678 49626 24678 49627 24675 49627 24915 49627 24913 49628 24675 49628 24678 49628 24911 49629 24913 49629 24678 49629 24676 49630 24910 49630 24678 49630 24908 49631 24677 49631 24678 49631 24674 49632 24907 49632 24678 49632 24679 49633 24920 49633 24681 49633 24916 49634 24920 49634 24679 49634 14048 49635 24916 49635 24679 49635 24679 49636 24680 49636 14042 49636 24921 49637 24680 49637 24679 49637 24681 49638 24921 49638 24679 49638 24684 49639 24682 49639 24923 49639 24684 49640 24926 49640 24683 49640 24924 49641 24926 49641 24684 49641 24923 49642 24924 49642 24684 49642 24684 49643 24927 49643 14092 49643 24685 49644 24927 49644 24684 49644 24683 49645 24685 49645 24684 49645 24687 49646 14031 49646 24686 49646 24687 49647 24933 49647 24934 49647 24930 49648 24933 49648 24687 49648 24686 49649 24930 49649 24687 49649 24687 49650 24936 49650 24688 49650 24689 49651 24936 49651 24687 49651 24934 49652 24689 49652 24687 49652 24691 49653 14024 49653 24937 49653 24691 49654 24939 49654 24693 49654 24690 49655 24939 49655 24691 49655 24937 49656 24690 49656 24691 49656 24691 49657 24692 49657 14021 49657 24941 49658 24692 49658 24691 49658 24693 49659 24941 49659 24691 49659 24696 49660 24945 49660 24947 49660 24948 49661 24949 49661 24696 49661 24694 49662 24951 49662 24696 49662 24952 49663 24695 49663 24696 49663 24696 49664 24957 49664 24958 49664 24956 49665 24957 49665 24696 49665 24695 49666 24956 49666 24696 49666 24951 49667 24952 49667 24696 49667 24949 49668 24694 49668 24696 49668 24947 49669 24948 49669 24696 49669 24699 49670 24959 49670 24960 49670 24699 49671 24963 49671 24965 49671 24697 49672 24963 49672 24699 49672 24960 49673 24697 49673 24699 49673 24699 49674 24967 49674 14078 49674 24698 49675 24967 49675 24699 49675 24965 49676 24698 49676 24699 49676 14076 49677 14004 49677 24970 49677 14076 49678 24972 49678 24974 49678 24971 49679 24972 49679 14076 49679 24970 49680 24971 49680 14076 49680 14076 49681 24976 49681 24978 49681 24700 49682 24976 49682 14076 49682 24974 49683 24700 49683 14076 49683 14073 49684 24982 49684 24985 49684 24980 49685 24982 49685 14073 49685 14069 49686 24980 49686 14073 49686 14073 49687 24988 49687 14065 49687 24986 49688 24988 49688 14073 49688 24985 49689 24986 49689 14073 49689 24993 49690 24701 49690 24702 49690 25000 49691 25001 49691 24707 49691 25005 49692 24705 49692 24703 49692 24703 49693 24705 49693 24996 49693 24703 49694 24996 49694 25008 49694 25008 49695 24996 49695 25009 49695 24704 49696 25012 49696 24996 49696 24996 49697 25012 49697 25011 49697 24996 49698 25011 49698 25009 49698 24705 49699 25003 49699 24996 49699 24996 49700 25003 49700 24706 49700 24996 49701 24706 49701 24707 49701 24707 49702 24706 49702 24997 49702 24707 49703 24997 49703 25000 49703 24708 49704 24993 49704 24709 49704 24709 49705 24993 49705 24702 49705 24709 49706 24702 49706 24996 49706 24996 49707 24702 49707 24992 49707 24996 49708 24992 49708 24704 49708 24716 49709 24710 49709 25018 49709 25018 49710 24710 49710 24711 49710 25027 49711 24713 49711 25029 49711 25029 49712 24713 49712 25018 49712 25029 49713 25018 49713 25030 49713 25030 49714 25018 49714 25032 49714 24711 49715 24712 49715 25018 49715 25018 49716 24712 49716 25033 49716 25018 49717 25033 49717 25032 49717 25023 49718 25024 49718 25022 49718 25022 49719 25024 49719 25019 49719 25022 49720 25019 49720 25020 49720 25020 49721 25019 49721 25018 49721 25020 49722 25018 49722 25025 49722 25025 49723 25018 49723 24713 49723 25014 49724 24714 49724 24715 49724 24715 49725 24714 49725 24716 49725 24715 49726 24716 49726 25017 49726 25017 49727 24716 49727 25018 49727 24717 49728 25053 49728 25052 49728 13985 49729 13986 49729 13989 49729 25057 49730 25056 49730 24717 49730 24717 49731 25056 49731 24718 49731 24717 49732 24718 49732 25053 49732 25042 49733 25043 49733 25044 49733 13989 49734 24719 49734 13985 49734 13985 49735 24719 49735 25039 49735 13985 49736 25039 49736 24717 49736 24717 49737 25039 49737 25037 49737 24717 49738 25037 49738 25057 49738 25052 49739 24720 49739 24717 49739 24717 49740 24720 49740 25050 49740 24717 49741 25050 49741 25048 49741 25048 49742 25046 49742 24717 49742 24717 49743 25046 49743 24721 49743 24717 49744 24721 49744 25044 49744 25044 49745 24721 49745 25041 49745 25044 49746 25041 49746 25042 49746 24730 49747 24733 49747 24728 49747 24728 49748 24733 49748 25068 49748 24733 49749 24724 49749 24723 49749 25068 49750 24733 49750 24722 49750 24722 49751 24733 49751 24723 49751 24722 49752 24723 49752 13983 49752 24724 49753 24733 49753 25071 49753 25071 49754 24733 49754 25073 49754 25071 49755 25073 49755 24725 49755 24726 49756 24727 49756 24728 49756 24728 49757 24727 49757 24729 49757 24728 49758 24729 49758 24730 49758 24731 49759 25062 49759 13984 49759 13984 49760 25062 49760 25063 49760 13984 49761 25063 49761 25064 49761 25064 49762 25063 49762 24732 49762 25064 49763 24732 49763 24733 49763 24733 49764 24732 49764 25058 49764 24733 49765 25058 49765 25073 49765 24737 49766 25077 49766 25078 49766 25076 49767 25091 49767 24738 49767 24738 49768 25091 49768 24734 49768 24734 49769 13978 49769 24738 49769 24738 49770 13978 49770 24735 49770 24738 49771 24735 49771 25089 49771 25078 49772 24736 49772 24737 49772 24737 49773 24736 49773 25080 49773 24737 49774 25080 49774 24738 49774 24738 49775 25080 49775 24739 49775 24738 49776 24739 49776 25076 49776 24741 49777 13979 49777 13981 49777 13981 49778 24740 49778 24741 49778 24741 49779 24740 49779 25083 49779 24741 49780 25083 49780 24742 49780 24742 49781 25083 49781 24738 49781 24742 49782 24738 49782 24743 49782 24743 49783 24738 49783 25089 49783 24743 49784 25089 49784 25088 49784 24744 49785 24745 49785 25100 49785 24745 49786 25108 49786 25100 49786 25100 49787 25108 49787 24746 49787 25100 49788 24746 49788 24750 49788 24752 49789 25094 49789 24751 49789 25111 49790 24747 49790 25100 49790 25100 49791 24747 49791 25109 49791 25100 49792 25109 49792 24744 49792 25101 49793 24748 49793 24749 49793 24749 49794 24748 49794 25103 49794 24749 49795 25103 49795 25104 49795 25104 49796 25103 49796 25100 49796 25104 49797 25100 49797 25106 49797 25106 49798 25100 49798 24750 49798 24751 49799 25096 49799 24752 49799 24752 49800 25096 49800 24753 49800 24752 49801 24753 49801 25100 49801 25100 49802 24753 49802 24754 49802 25100 49803 24754 49803 25111 49803 24756 49804 25113 49804 14174 49804 14174 49805 24755 49805 24756 49805 24756 49806 24755 49806 24606 49806 24756 49807 24606 49807 24758 49807 24606 49808 24757 49808 24758 49808 24758 49809 24757 49809 24759 49809 24758 49810 24759 49810 25120 49810 24759 49811 24604 49811 25120 49811 25120 49812 24604 49812 24761 49812 25120 49813 24761 49813 24760 49813 24760 49814 24761 49814 24762 49814 24760 49815 24762 49815 24763 49815 24762 49816 24764 49816 24763 49816 24763 49817 24764 49817 24765 49817 24763 49818 24765 49818 24767 49818 14064 49819 24766 49819 24600 49819 24600 49820 24766 49820 24767 49820 24600 49821 24767 49821 24601 49821 24601 49822 24767 49822 24765 49822 24780 49823 24781 49823 24768 49823 24768 49824 24781 49824 13969 49824 24768 49825 13969 49825 24769 49825 24769 49826 13969 49826 13972 49826 24769 49827 13972 49827 24610 49827 24610 49828 13972 49828 24770 49828 24610 49829 24770 49829 24611 49829 24611 49830 24770 49830 13975 49830 24611 49831 13975 49831 14168 49831 14168 49832 13975 49832 24771 49832 14168 49833 24771 49833 14171 49833 14171 49834 24771 49834 25125 49834 14171 49835 25125 49835 24772 49835 24772 49836 25125 49836 24773 49836 24772 49837 24773 49837 14173 49837 14173 49838 24773 49838 24774 49838 14173 49839 24774 49839 24775 49839 24775 49840 24774 49840 24777 49840 24775 49841 24777 49841 24776 49841 24776 49842 24777 49842 25129 49842 24776 49843 25129 49843 24778 49843 24778 49844 25129 49844 13965 49844 24778 49845 13965 49845 24779 49845 24779 49846 13965 49846 13967 49846 24779 49847 13967 49847 24780 49847 24780 49848 13967 49848 24781 49848 24794 49849 14166 49849 24796 49849 24796 49850 14166 49850 24782 49850 24796 49851 24782 49851 24783 49851 24783 49852 24782 49852 24784 49852 24783 49853 24784 49853 25130 49853 25130 49854 24784 49854 14162 49854 25130 49855 14162 49855 13964 49855 13964 49856 14162 49856 14161 49856 13964 49857 14161 49857 13963 49857 13963 49858 14161 49858 24614 49858 13963 49859 24614 49859 24785 49859 24785 49860 24614 49860 24613 49860 24785 49861 24613 49861 24786 49861 24786 49862 24613 49862 24787 49862 24786 49863 24787 49863 24788 49863 24788 49864 24787 49864 24789 49864 24788 49865 24789 49865 13960 49865 13960 49866 24789 49866 24790 49866 13960 49867 24790 49867 24791 49867 24791 49868 24790 49868 24792 49868 24791 49869 24792 49869 25136 49869 25136 49870 24792 49870 24793 49870 25136 49871 24793 49871 24795 49871 24795 49872 24793 49872 24794 49872 24795 49873 24794 49873 24796 49873 24811 49874 24812 49874 13954 49874 13954 49875 24812 49875 24797 49875 13954 49876 24797 49876 24798 49876 24798 49877 24797 49877 24616 49877 24798 49878 24616 49878 24799 49878 24799 49879 24616 49879 24800 49879 24799 49880 24800 49880 25142 49880 25142 49881 24800 49881 14160 49881 25142 49882 14160 49882 24801 49882 24801 49883 14160 49883 24803 49883 24801 49884 24803 49884 24802 49884 24802 49885 24803 49885 24804 49885 24802 49886 24804 49886 25139 49886 25139 49887 24804 49887 24805 49887 25139 49888 24805 49888 24806 49888 24806 49889 24805 49889 24807 49889 24806 49890 24807 49890 24808 49890 24808 49891 24807 49891 14154 49891 24808 49892 14154 49892 13958 49892 13958 49893 14154 49893 24809 49893 13958 49894 24809 49894 13957 49894 13957 49895 24809 49895 24810 49895 13957 49896 24810 49896 24811 49896 24811 49897 24810 49897 24617 49897 24811 49898 24617 49898 24812 49898 24624 49899 13951 49899 24813 49899 24813 49900 13951 49900 13952 49900 24813 49901 13952 49901 24814 49901 24814 49902 13952 49902 13953 49902 24814 49903 13953 49903 24815 49903 24815 49904 13953 49904 24817 49904 24815 49905 24817 49905 24816 49905 24816 49906 24817 49906 25146 49906 24816 49907 25146 49907 14150 49907 14150 49908 25146 49908 25145 49908 14150 49909 25145 49909 24818 49909 24818 49910 25145 49910 24819 49910 24818 49911 24819 49911 24821 49911 24821 49912 24819 49912 24820 49912 24821 49913 24820 49913 24822 49913 24822 49914 24820 49914 25149 49914 24822 49915 25149 49915 14153 49915 14153 49916 25149 49916 25150 49916 14153 49917 25150 49917 24823 49917 24823 49918 25150 49918 25152 49918 24823 49919 25152 49919 24621 49919 24621 49920 25152 49920 24824 49920 24621 49921 24824 49921 24623 49921 24623 49922 24824 49922 13949 49922 24623 49923 13949 49923 24624 49923 24624 49924 13949 49924 13951 49924 24825 49925 24629 49925 24826 49925 24826 49926 24629 49926 24828 49926 24826 49927 24828 49927 24827 49927 24827 49928 24828 49928 24829 49928 24827 49929 24829 49929 13943 49929 13943 49930 24829 49930 24830 49930 13943 49931 24830 49931 13942 49931 13942 49932 24830 49932 24831 49932 13942 49933 24831 49933 25159 49933 25159 49934 24831 49934 14148 49934 25159 49935 14148 49935 25158 49935 25158 49936 14148 49936 24832 49936 25158 49937 24832 49937 24833 49937 24833 49938 24832 49938 24834 49938 24833 49939 24834 49939 25156 49939 25156 49940 24834 49940 14146 49940 25156 49941 14146 49941 25155 49941 25155 49942 14146 49942 14145 49942 25155 49943 14145 49943 13947 49943 13947 49944 14145 49944 14144 49944 13947 49945 14144 49945 24835 49945 24835 49946 14144 49946 24836 49946 24835 49947 24836 49947 13946 49947 13946 49948 24836 49948 24825 49948 13946 49949 24825 49949 24826 49949 14137 49950 25162 49950 14139 49950 14139 49951 25162 49951 25163 49951 14139 49952 25163 49952 14140 49952 14140 49953 25163 49953 25166 49953 14140 49954 25166 49954 24837 49954 24837 49955 25166 49955 25167 49955 24837 49956 25167 49956 14142 49956 14142 49957 25167 49957 25169 49957 14142 49958 25169 49958 24838 49958 24838 49959 25169 49959 25171 49959 24838 49960 25171 49960 14143 49960 14143 49961 25171 49961 24840 49961 14143 49962 24840 49962 24839 49962 24839 49963 24840 49963 24841 49963 24839 49964 24841 49964 24632 49964 24632 49965 24841 49965 13933 49965 24632 49966 13933 49966 24842 49966 24842 49967 13933 49967 13936 49967 24842 49968 13936 49968 24843 49968 24843 49969 13936 49969 24844 49969 24843 49970 24844 49970 24633 49970 24633 49971 24844 49971 13939 49971 24633 49972 13939 49972 24634 49972 24634 49973 13939 49973 13941 49973 24634 49974 13941 49974 14137 49974 14137 49975 13941 49975 25162 49975 24635 49976 13929 49976 24845 49976 24845 49977 13929 49977 25172 49977 24845 49978 25172 49978 24846 49978 24846 49979 25172 49979 24847 49979 24846 49980 24847 49980 14133 49980 14133 49981 24847 49981 24848 49981 14133 49982 24848 49982 24849 49982 24849 49983 24848 49983 25174 49983 24849 49984 25174 49984 24850 49984 24850 49985 25174 49985 25178 49985 24850 49986 25178 49986 24851 49986 24851 49987 25178 49987 24852 49987 24851 49988 24852 49988 24853 49988 24853 49989 24852 49989 13919 49989 24853 49990 13919 49990 24854 49990 24854 49991 13919 49991 24855 49991 24854 49992 24855 49992 24641 49992 24641 49993 24855 49993 13922 49993 24641 49994 13922 49994 24856 49994 24856 49995 13922 49995 24857 49995 24856 49996 24857 49996 24858 49996 24858 49997 24857 49997 13924 49997 24858 49998 13924 49998 24636 49998 24636 49999 13924 49999 13928 49999 24636 50000 13928 50000 24635 50000 24635 50001 13928 50001 13929 50001 13915 50002 24859 50002 13912 50002 13912 50003 24859 50003 24647 50003 13912 50004 24647 50004 13909 50004 13909 50005 24647 50005 24649 50005 13909 50006 24649 50006 24860 50006 24860 50007 24649 50007 24861 50007 24860 50008 24861 50008 25183 50008 25183 50009 24861 50009 24863 50009 25183 50010 24863 50010 24862 50010 24862 50011 24863 50011 24864 50011 24862 50012 24864 50012 25182 50012 25182 50013 24864 50013 24865 50013 25182 50014 24865 50014 25181 50014 25181 50015 24865 50015 14127 50015 25181 50016 14127 50016 24866 50016 24866 50017 14127 50017 24867 50017 24866 50018 24867 50018 24868 50018 24868 50019 24867 50019 14129 50019 24868 50020 14129 50020 13917 50020 13917 50021 14129 50021 24644 50021 13917 50022 24644 50022 13916 50022 13916 50023 24644 50023 24869 50023 13916 50024 24869 50024 13915 50024 13915 50025 24869 50025 24870 50025 13915 50026 24870 50026 24859 50026 24881 50027 24871 50027 24655 50027 24655 50028 24871 50028 24872 50028 24655 50029 24872 50029 24656 50029 24656 50030 24872 50030 13905 50030 24656 50031 13905 50031 24874 50031 24874 50032 13905 50032 24873 50032 24874 50033 24873 50033 24658 50033 24658 50034 24873 50034 13908 50034 24658 50035 13908 50035 24876 50035 24876 50036 13908 50036 24875 50036 24876 50037 24875 50037 14118 50037 14118 50038 24875 50038 25185 50038 14118 50039 25185 50039 14119 50039 14119 50040 25185 50040 25184 50040 14119 50041 25184 50041 14120 50041 14120 50042 25184 50042 24877 50042 14120 50043 24877 50043 24878 50043 24878 50044 24877 50044 25190 50044 24878 50045 25190 50045 14123 50045 14123 50046 25190 50046 25191 50046 14123 50047 25191 50047 24651 50047 24651 50048 25191 50048 24879 50048 24651 50049 24879 50049 24880 50049 24880 50050 24879 50050 24882 50050 24880 50051 24882 50051 24881 50051 24881 50052 24882 50052 24871 50052 14115 50053 24894 50053 24883 50053 24883 50054 24894 50054 25201 50054 24883 50055 25201 50055 24884 50055 24884 50056 25201 50056 24885 50056 24884 50057 24885 50057 24661 50057 24661 50058 24885 50058 13897 50058 24661 50059 13897 50059 24663 50059 24663 50060 13897 50060 13899 50060 24663 50061 13899 50061 24886 50061 24886 50062 13899 50062 24887 50062 24886 50063 24887 50063 24665 50063 24665 50064 24887 50064 24888 50064 24665 50065 24888 50065 14109 50065 14109 50066 24888 50066 25193 50066 14109 50067 25193 50067 24889 50067 24889 50068 25193 50068 24890 50068 24889 50069 24890 50069 14111 50069 14111 50070 24890 50070 24891 50070 14111 50071 24891 50071 14112 50071 14112 50072 24891 50072 25196 50072 14112 50073 25196 50073 14114 50073 14114 50074 25196 50074 25197 50074 14114 50075 25197 50075 24892 50075 24892 50076 25197 50076 24893 50076 24892 50077 24893 50077 14115 50077 14115 50078 24893 50078 24894 50078 24669 50079 24895 50079 24670 50079 24670 50080 24895 50080 24896 50080 24670 50081 24896 50081 24671 50081 24671 50082 24896 50082 24897 50082 24671 50083 24897 50083 24673 50083 24673 50084 24897 50084 13895 50084 24673 50085 13895 50085 14103 50085 14103 50086 13895 50086 25203 50086 14103 50087 25203 50087 24898 50087 24898 50088 25203 50088 25205 50088 24898 50089 25205 50089 24899 50089 24899 50090 25205 50090 24900 50090 24899 50091 24900 50091 14104 50091 14104 50092 24900 50092 24901 50092 14104 50093 24901 50093 14107 50093 14107 50094 24901 50094 24902 50094 14107 50095 24902 50095 14108 50095 14108 50096 24902 50096 25207 50096 14108 50097 25207 50097 24667 50097 24667 50098 25207 50098 13891 50098 24667 50099 13891 50099 24903 50099 24903 50100 13891 50100 24904 50100 24903 50101 24904 50101 24905 50101 24905 50102 24904 50102 13893 50102 24905 50103 13893 50103 24669 50103 24669 50104 13893 50104 24895 50104 14099 50105 25208 50105 24906 50105 14099 50106 24906 50106 24674 50106 24674 50107 24906 50107 25210 50107 24674 50108 25210 50108 24907 50108 24907 50109 25210 50109 24908 50109 24908 50110 25210 50110 25212 50110 24908 50111 25212 50111 24677 50111 24677 50112 25212 50112 24676 50112 24676 50113 25212 50113 24909 50113 24676 50114 24909 50114 24910 50114 24910 50115 24909 50115 24911 50115 24911 50116 24909 50116 24912 50116 24911 50117 24912 50117 24913 50117 24913 50118 24912 50118 24914 50118 24913 50119 24914 50119 24675 50119 24675 50120 24914 50120 25215 50120 24675 50121 25215 50121 24915 50121 14048 50122 24917 50122 24916 50122 24916 50123 24917 50123 24918 50123 24916 50124 24918 50124 24920 50124 24920 50125 24918 50125 24919 50125 24920 50126 24919 50126 24681 50126 24681 50127 24919 50127 25218 50127 24681 50128 25218 50128 24921 50128 24921 50129 25218 50129 25219 50129 24921 50130 25219 50130 24680 50130 24680 50131 25219 50131 24922 50131 24680 50132 24922 50132 14042 50132 14042 50133 24922 50133 14040 50133 24682 50134 13865 50134 25231 50134 24682 50135 25231 50135 24923 50135 24923 50136 25231 50136 25232 50136 24923 50137 25232 50137 24924 50137 24924 50138 25232 50138 24925 50138 24924 50139 24925 50139 24926 50139 24925 50140 25229 50140 24926 50140 24926 50141 25229 50141 25228 50141 24926 50142 25228 50142 24683 50142 25228 50143 25227 50143 24683 50143 24683 50144 25227 50144 25226 50144 24683 50145 25226 50145 24685 50145 25226 50146 25225 50146 24685 50146 24685 50147 25225 50147 25224 50147 24685 50148 25224 50148 24927 50148 24927 50149 25224 50149 24928 50149 24927 50150 24928 50150 14092 50150 14031 50151 24929 50151 24686 50151 24686 50152 24929 50152 24931 50152 24686 50153 24931 50153 24930 50153 24930 50154 24931 50154 24932 50154 24930 50155 24932 50155 24933 50155 24933 50156 24932 50156 25235 50156 24933 50157 25235 50157 24934 50157 24934 50158 25235 50158 24935 50158 24934 50159 24935 50159 24689 50159 24689 50160 24935 50160 25237 50160 24689 50161 25237 50161 24936 50161 24936 50162 25237 50162 25238 50162 24936 50163 25238 50163 24688 50163 24688 50164 25238 50164 14025 50164 14024 50165 13859 50165 24937 50165 24937 50166 13859 50166 25242 50166 24937 50167 25242 50167 24690 50167 24690 50168 25242 50168 24938 50168 24690 50169 24938 50169 24939 50169 24939 50170 24938 50170 25243 50170 24939 50171 25243 50171 24693 50171 24693 50172 25243 50172 24940 50172 24693 50173 24940 50173 24941 50173 24941 50174 24940 50174 24942 50174 24941 50175 24942 50175 24692 50175 24692 50176 24942 50176 24943 50176 24692 50177 24943 50177 14021 50177 14021 50178 24943 50178 24944 50178 24945 50179 14019 50179 24946 50179 24945 50180 24946 50180 24947 50180 24947 50181 24946 50181 25247 50181 24947 50182 25247 50182 24948 50182 24948 50183 25247 50183 24949 50183 24949 50184 25247 50184 24950 50184 24949 50185 24950 50185 24694 50185 24694 50186 24950 50186 24951 50186 24951 50187 24950 50187 24953 50187 24951 50188 24953 50188 24952 50188 24952 50189 24953 50189 24695 50189 24695 50190 24953 50190 24954 50190 24695 50191 24954 50191 24956 50191 24956 50192 24954 50192 24955 50192 24956 50193 24955 50193 24957 50193 24957 50194 24955 50194 14011 50194 24957 50195 14011 50195 24958 50195 24959 50196 24961 50196 24960 50196 24960 50197 24961 50197 25251 50197 24960 50198 25251 50198 24697 50198 24697 50199 25251 50199 24962 50199 24697 50200 24962 50200 24963 50200 24963 50201 24962 50201 24964 50201 24963 50202 24964 50202 24965 50202 24965 50203 24964 50203 24966 50203 24965 50204 24966 50204 24698 50204 24698 50205 24966 50205 25254 50205 24698 50206 25254 50206 24967 50206 24967 50207 25254 50207 24968 50207 24967 50208 24968 50208 14078 50208 14078 50209 24968 50209 14005 50209 14004 50210 24969 50210 24970 50210 24970 50211 24969 50211 25257 50211 24970 50212 25257 50212 24971 50212 24971 50213 25257 50213 25258 50213 24971 50214 25258 50214 24972 50214 24972 50215 25258 50215 24973 50215 24972 50216 24973 50216 24974 50216 24974 50217 24973 50217 24975 50217 24974 50218 24975 50218 24700 50218 24700 50219 24975 50219 25261 50219 24700 50220 25261 50220 24976 50220 24976 50221 25261 50221 24977 50221 24976 50222 24977 50222 24978 50222 24978 50223 24977 50223 13999 50223 24979 50224 25276 50224 14069 50224 14069 50225 25276 50225 24980 50225 25276 50226 25277 50226 24980 50226 24980 50227 25277 50227 24981 50227 24980 50228 24981 50228 24982 50228 24981 50229 25275 50229 24982 50229 24982 50230 25275 50230 24983 50230 24982 50231 24983 50231 24985 50231 24983 50232 24984 50232 24985 50232 24985 50233 24984 50233 25273 50233 24985 50234 25273 50234 24986 50234 25273 50235 24987 50235 24986 50235 24986 50236 24987 50236 25271 50236 24986 50237 25271 50237 24988 50237 25267 50238 14065 50238 24989 50238 24989 50239 14065 50239 24988 50239 24989 50240 24988 50240 25269 50240 25269 50241 24988 50241 25271 50241 24990 50242 24704 50242 24991 50242 24991 50243 24704 50243 24992 50243 24991 50244 24992 50244 25284 50244 25284 50245 24992 50245 24702 50245 24709 50246 25278 50246 24708 50246 24708 50247 25278 50247 24994 50247 24708 50248 24994 50248 24993 50248 24993 50249 24994 50249 25280 50249 24993 50250 25280 50250 24701 50250 24701 50251 25280 50251 25282 50251 24701 50252 25282 50252 24702 50252 24702 50253 25282 50253 25284 50253 25278 50254 24709 50254 24995 50254 24995 50255 24709 50255 24996 50255 24995 50256 24996 50256 25288 50256 25288 50257 24996 50257 24707 50257 24706 50258 25285 50258 24997 50258 24997 50259 25285 50259 24998 50259 24997 50260 24998 50260 25000 50260 25000 50261 24998 50261 24999 50261 25000 50262 24999 50262 25001 50262 25001 50263 24999 50263 25002 50263 25001 50264 25002 50264 24707 50264 24707 50265 25002 50265 25288 50265 25285 50266 24706 50266 25290 50266 25290 50267 24706 50267 25003 50267 25290 50268 25003 50268 25004 50268 25004 50269 25003 50269 24705 50269 25004 50270 24705 50270 25005 50270 25004 50271 25005 50271 25006 50271 25006 50272 25005 50272 24703 50272 25006 50273 24703 50273 25007 50273 25007 50274 24703 50274 25008 50274 25007 50275 25008 50275 25293 50275 25008 50276 25009 50276 25293 50276 25293 50277 25009 50277 25294 50277 25294 50278 25009 50278 25010 50278 25010 50279 25009 50279 25011 50279 25010 50280 25011 50280 25296 50280 25296 50281 25011 50281 25012 50281 25296 50282 25012 50282 24990 50282 24990 50283 25012 50283 24704 50283 25035 50284 24711 50284 25013 50284 25013 50285 24711 50285 24710 50285 25013 50286 24710 50286 25301 50286 25301 50287 24710 50287 24716 50287 25017 50288 25016 50288 24715 50288 24715 50289 25016 50289 25299 50289 24715 50290 25299 50290 25014 50290 25014 50291 25299 50291 25300 50291 25014 50292 25300 50292 24714 50292 24714 50293 25300 50293 25015 50293 24714 50294 25015 50294 24716 50294 24716 50295 25015 50295 25301 50295 25016 50296 25017 50296 25302 50296 25302 50297 25017 50297 25018 50297 25302 50298 25018 50298 25309 50298 25309 50299 25018 50299 25019 50299 25020 50300 25304 50300 25022 50300 25022 50301 25304 50301 25021 50301 25022 50302 25021 50302 25023 50302 25023 50303 25021 50303 25306 50303 25023 50304 25306 50304 25024 50304 25024 50305 25306 50305 25308 50305 25024 50306 25308 50306 25019 50306 25019 50307 25308 50307 25309 50307 25304 50308 25020 50308 25310 50308 25310 50309 25020 50309 25025 50309 25310 50310 25025 50310 25026 50310 25026 50311 25025 50311 24713 50311 25026 50312 24713 50312 25313 50312 25313 50313 24713 50313 25027 50313 25313 50314 25027 50314 25312 50314 25312 50315 25027 50315 25029 50315 25312 50316 25029 50316 25028 50316 25028 50317 25029 50317 25030 50317 25030 50318 25032 50318 25028 50318 25028 50319 25032 50319 25031 50319 25031 50320 25032 50320 25033 50320 25031 50321 25033 50321 25034 50321 25034 50322 25033 50322 24712 50322 25034 50323 24712 50323 13824 50323 13824 50324 24712 50324 24711 50324 13824 50325 24711 50325 25035 50325 25316 50326 25057 50326 25036 50326 25036 50327 25057 50327 25037 50327 25036 50328 25037 50328 25038 50328 25038 50329 25037 50329 25039 50329 24719 50330 13822 50330 25039 50330 25039 50331 13822 50331 25038 50331 13987 50332 13985 50332 25040 50332 25040 50333 13985 50333 24717 50333 25040 50334 24717 50334 25325 50334 25325 50335 24717 50335 25044 50335 24721 50336 25318 50336 25041 50336 25041 50337 25318 50337 25320 50337 25041 50338 25320 50338 25042 50338 25042 50339 25320 50339 25321 50339 25042 50340 25321 50340 25043 50340 25043 50341 25321 50341 25322 50341 25043 50342 25322 50342 25044 50342 25044 50343 25322 50343 25325 50343 25318 50344 24721 50344 25045 50344 25045 50345 24721 50345 25046 50345 25045 50346 25046 50346 25047 50346 25047 50347 25046 50347 25048 50347 25047 50348 25048 50348 25049 50348 25049 50349 25048 50349 25050 50349 25049 50350 25050 50350 25051 50350 25051 50351 25050 50351 24720 50351 25051 50352 24720 50352 25327 50352 25327 50353 24720 50353 25052 50353 25052 50354 25053 50354 25327 50354 25327 50355 25053 50355 25328 50355 25328 50356 25053 50356 25054 50356 25054 50357 25053 50357 24718 50357 25054 50358 24718 50358 25055 50358 25055 50359 24718 50359 25056 50359 25055 50360 25056 50360 25316 50360 25316 50361 25056 50361 25057 50361 25074 50362 25058 50362 25059 50362 25059 50363 25058 50363 24732 50363 25059 50364 24732 50364 25060 50364 25060 50365 24732 50365 25063 50365 13984 50366 13818 50366 24731 50366 24731 50367 13818 50367 25061 50367 24731 50368 25061 50368 25062 50368 25062 50369 25061 50369 25332 50369 25062 50370 25332 50370 25063 50370 25063 50371 25332 50371 25060 50371 13817 50372 25064 50372 25065 50372 25065 50373 25064 50373 24733 50373 25065 50374 24733 50374 25066 50374 25066 50375 24733 50375 24730 50375 24728 50376 25340 50376 24726 50376 24726 50377 25340 50377 25067 50377 24726 50378 25067 50378 24727 50378 24727 50379 25067 50379 25335 50379 24727 50380 25335 50380 24729 50380 24729 50381 25335 50381 25337 50381 24729 50382 25337 50382 24730 50382 24730 50383 25337 50383 25066 50383 25340 50384 24728 50384 25339 50384 25339 50385 24728 50385 25068 50385 25339 50386 25068 50386 25341 50386 25341 50387 25068 50387 24722 50387 25345 50388 13983 50388 24723 50388 25345 50389 24723 50389 25342 50389 25342 50390 24723 50390 24724 50390 25342 50391 24724 50391 25069 50391 24724 50392 25071 50392 25069 50392 25069 50393 25071 50393 25070 50393 25070 50394 25071 50394 25072 50394 25072 50395 25071 50395 24725 50395 25072 50396 24725 50396 25348 50396 25348 50397 24725 50397 25073 50397 25348 50398 25073 50398 25074 50398 25074 50399 25073 50399 25058 50399 25366 50400 25076 50400 25075 50400 25075 50401 25076 50401 24739 50401 25075 50402 24739 50402 25350 50402 25350 50403 24739 50403 25080 50403 24737 50404 25358 50404 25077 50404 25077 50405 25358 50405 25079 50405 25077 50406 25079 50406 25078 50406 25078 50407 25079 50407 25354 50407 25078 50408 25354 50408 24736 50408 24736 50409 25354 50409 25081 50409 24736 50410 25081 50410 25080 50410 25080 50411 25081 50411 25350 50411 25358 50412 24737 50412 25357 50412 25357 50413 24737 50413 24738 50413 25357 50414 24738 50414 25082 50414 25082 50415 24738 50415 25083 50415 24740 50416 13816 50416 25083 50416 25083 50417 13816 50417 25082 50417 25360 50418 24741 50418 25084 50418 25084 50419 24741 50419 24742 50419 25084 50420 24742 50420 25085 50420 25085 50421 24742 50421 24743 50421 25085 50422 24743 50422 25086 50422 25086 50423 24743 50423 25088 50423 25086 50424 25088 50424 25087 50424 25087 50425 25088 50425 25089 50425 25087 50426 25089 50426 25362 50426 25362 50427 25089 50427 24735 50427 24735 50428 13978 50428 25362 50428 25362 50429 13978 50429 25090 50429 25368 50430 25091 50430 25092 50430 25092 50431 25091 50431 25076 50431 25092 50432 25076 50432 25366 50432 25110 50433 25111 50433 25093 50433 25093 50434 25111 50434 24754 50434 25093 50435 24754 50435 25098 50435 25098 50436 24754 50436 24753 50436 24752 50437 25375 50437 25094 50437 25094 50438 25375 50438 25095 50438 25094 50439 25095 50439 24751 50439 24751 50440 25095 50440 25373 50440 24751 50441 25373 50441 25096 50441 25096 50442 25373 50442 25097 50442 25096 50443 25097 50443 24753 50443 24753 50444 25097 50444 25098 50444 25375 50445 24752 50445 25099 50445 25099 50446 24752 50446 25100 50446 25099 50447 25100 50447 25379 50447 25379 50448 25100 50448 25103 50448 24749 50449 13977 50449 25101 50449 25101 50450 13977 50450 25377 50450 25101 50451 25377 50451 24748 50451 24748 50452 25377 50452 25102 50452 24748 50453 25102 50453 25103 50453 25103 50454 25102 50454 25379 50454 13976 50455 25104 50455 25105 50455 25105 50456 25104 50456 25106 50456 25105 50457 25106 50457 25107 50457 25107 50458 25106 50458 24750 50458 25107 50459 24750 50459 25383 50459 25383 50460 24750 50460 24746 50460 25383 50461 24746 50461 25382 50461 25382 50462 24746 50462 25108 50462 25382 50463 25108 50463 25381 50463 25381 50464 25108 50464 24745 50464 24745 50465 24744 50465 25381 50465 25381 50466 24744 50466 25390 50466 25390 50467 24744 50467 25388 50467 25388 50468 24744 50468 25109 50468 25388 50469 25109 50469 25387 50469 25387 50470 25109 50470 24747 50470 25387 50471 24747 50471 25110 50471 25110 50472 24747 50472 25111 50472 25120 50473 25121 50473 24758 50473 24758 50474 25121 50474 25112 50474 24758 50475 25112 50475 24756 50475 24756 50476 25112 50476 13810 50476 24756 50477 13810 50477 25113 50477 25113 50478 13810 50478 25392 50478 25113 50479 25392 50479 14059 50479 14059 50480 25392 50480 25114 50480 14059 50481 25114 50481 25115 50481 25115 50482 25114 50482 25395 50482 25115 50483 25395 50483 14060 50483 14060 50484 25395 50484 25116 50484 14060 50485 25116 50485 14062 50485 14062 50486 25116 50486 25397 50486 14062 50487 25397 50487 14063 50487 14063 50488 25397 50488 25398 50488 14063 50489 25398 50489 24766 50489 24766 50490 25398 50490 13804 50490 24766 50491 13804 50491 24767 50491 24767 50492 13804 50492 25117 50492 24767 50493 25117 50493 24763 50493 24763 50494 25117 50494 25118 50494 24763 50495 25118 50495 24760 50495 24760 50496 25118 50496 25119 50496 24760 50497 25119 50497 25120 50497 25120 50498 25119 50498 25121 50498 13975 50499 13974 50499 25122 50499 13975 50500 25122 50500 24771 50500 24771 50501 25122 50501 25123 50501 24771 50502 25123 50502 25125 50502 25125 50503 25123 50503 25124 50503 25125 50504 25124 50504 24773 50504 24773 50505 25124 50505 25126 50505 24773 50506 25126 50506 24774 50506 24774 50507 25126 50507 25127 50507 24774 50508 25127 50508 24777 50508 24777 50509 25127 50509 25128 50509 24777 50510 25128 50510 25129 50510 24783 50511 25130 50511 25410 50511 25410 50512 25130 50512 13964 50512 25410 50513 13964 50513 13798 50513 25410 50514 25131 50514 24783 50514 24783 50515 25131 50515 25408 50515 24783 50516 25408 50516 24796 50516 24796 50517 25408 50517 25132 50517 25132 50518 25133 50518 24796 50518 24796 50519 25133 50519 25134 50519 24796 50520 25134 50520 24795 50520 25134 50521 25406 50521 24795 50521 24795 50522 25406 50522 25404 50522 24795 50523 25404 50523 25136 50523 25404 50524 25135 50524 25136 50524 25136 50525 25135 50525 25401 50525 25136 50526 25401 50526 24791 50526 24808 50527 25137 50527 25138 50527 24808 50528 25138 50528 24806 50528 24806 50529 25138 50529 25140 50529 24806 50530 25140 50530 25139 50530 25139 50531 25140 50531 25415 50531 25139 50532 25415 50532 24802 50532 24802 50533 25415 50533 25141 50533 24802 50534 25141 50534 24801 50534 24801 50535 25141 50535 25143 50535 24801 50536 25143 50536 25142 50536 25142 50537 25143 50537 25144 50537 25142 50538 25144 50538 24799 50538 24819 50539 25145 50539 25429 50539 25429 50540 25145 50540 25146 50540 25429 50541 25146 50541 25430 50541 25429 50542 25427 50542 24819 50542 24819 50543 25427 50543 25147 50543 24819 50544 25147 50544 24820 50544 24820 50545 25147 50545 25148 50545 25148 50546 25426 50546 24820 50546 24820 50547 25426 50547 25423 50547 24820 50548 25423 50548 25149 50548 25423 50549 25421 50549 25149 50549 25149 50550 25421 50550 25420 50550 25149 50551 25420 50551 25150 50551 25420 50552 25419 50552 25150 50552 25150 50553 25419 50553 25151 50553 25150 50554 25151 50554 25152 50554 13947 50555 25153 50555 25435 50555 13947 50556 25435 50556 25155 50556 25155 50557 25435 50557 25154 50557 25155 50558 25154 50558 25156 50558 25156 50559 25154 50559 25433 50559 25156 50560 25433 50560 24833 50560 24833 50561 25433 50561 25157 50561 24833 50562 25157 50562 25158 50562 25158 50563 25157 50563 25434 50563 25158 50564 25434 50564 25159 50564 25159 50565 25434 50565 25160 50565 25159 50566 25160 50566 13942 50566 13941 50567 13940 50567 25161 50567 13941 50568 25161 50568 25162 50568 25162 50569 25161 50569 25442 50569 25162 50570 25442 50570 25163 50570 25442 50571 25164 50571 25163 50571 25163 50572 25164 50572 25165 50572 25163 50573 25165 50573 25166 50573 25165 50574 25445 50574 25166 50574 25166 50575 25445 50575 25446 50575 25166 50576 25446 50576 25167 50576 25167 50577 25446 50577 25168 50577 25167 50578 25168 50578 25169 50578 25168 50579 25441 50579 25169 50579 25169 50580 25441 50580 25170 50580 25169 50581 25170 50581 25171 50581 25171 50582 25170 50582 25440 50582 25440 50583 25438 50583 25171 50583 25171 50584 25438 50584 13932 50584 25171 50585 13932 50585 24840 50585 24848 50586 24847 50586 25454 50586 25454 50587 24847 50587 25172 50587 25454 50588 25172 50588 13768 50588 25454 50589 25173 50589 24848 50589 24848 50590 25173 50590 25453 50590 24848 50591 25453 50591 25174 50591 25174 50592 25453 50592 25451 50592 25451 50593 25175 50593 25174 50593 25174 50594 25175 50594 25176 50594 25174 50595 25176 50595 25178 50595 25176 50596 25177 50596 25178 50596 25178 50597 25177 50597 25449 50597 25178 50598 25449 50598 24852 50598 25449 50599 25179 50599 24852 50599 24852 50600 25179 50600 25450 50600 24852 50601 25450 50601 13919 50601 24868 50602 13918 50602 25180 50602 24868 50603 25180 50603 24866 50603 24866 50604 25180 50604 25456 50604 24866 50605 25456 50605 25181 50605 25181 50606 25456 50606 25459 50606 25181 50607 25459 50607 25182 50607 25182 50608 25459 50608 25460 50608 25182 50609 25460 50609 24862 50609 24862 50610 25460 50610 25461 50610 24862 50611 25461 50611 25183 50611 25183 50612 25461 50612 13911 50612 25183 50613 13911 50613 24860 50613 25184 50614 25185 50614 25186 50614 25186 50615 25185 50615 24875 50615 25186 50616 24875 50616 25464 50616 25186 50617 25467 50617 25184 50617 25184 50618 25467 50618 25187 50618 25184 50619 25187 50619 24877 50619 24877 50620 25187 50620 25188 50620 25188 50621 25189 50621 24877 50621 24877 50622 25189 50622 25468 50622 24877 50623 25468 50623 25190 50623 25468 50624 25469 50624 25190 50624 25190 50625 25469 50625 25470 50625 25190 50626 25470 50626 25191 50626 25470 50627 25471 50627 25191 50627 25191 50628 25471 50628 13904 50628 25191 50629 13904 50629 24879 50629 25193 50630 25192 50630 25194 50630 25193 50631 25194 50631 24890 50631 24890 50632 25194 50632 25195 50632 24890 50633 25195 50633 24891 50633 25195 50634 25473 50634 24891 50634 24891 50635 25473 50635 25476 50635 24891 50636 25476 50636 25196 50636 25196 50637 25476 50637 25475 50637 25196 50638 25475 50638 25197 50638 25475 50639 25198 50639 25197 50639 25197 50640 25198 50640 25199 50640 25197 50641 25199 50641 24893 50641 25199 50642 25477 50642 24893 50642 24893 50643 25477 50643 25479 50643 24893 50644 25479 50644 24894 50644 24894 50645 25479 50645 25200 50645 25200 50646 25481 50646 24894 50646 24894 50647 25481 50647 25483 50647 24894 50648 25483 50648 25201 50648 25203 50649 25202 50649 25204 50649 25203 50650 25204 50650 25205 50650 25205 50651 25204 50651 25485 50651 25205 50652 25485 50652 24900 50652 24900 50653 25485 50653 25206 50653 24900 50654 25206 50654 24901 50654 24901 50655 25206 50655 25487 50655 24901 50656 25487 50656 24902 50656 24902 50657 25487 50657 25489 50657 24902 50658 25489 50658 25207 50658 25207 50659 25489 50659 13729 50659 25207 50660 13729 50660 13891 50660 25208 50661 13890 50661 24906 50661 24906 50662 13890 50662 25209 50662 24906 50663 25209 50663 25210 50663 25210 50664 25209 50664 25211 50664 25210 50665 25211 50665 25212 50665 25212 50666 25211 50666 25213 50666 25212 50667 25213 50667 24909 50667 24909 50668 25213 50668 25214 50668 24909 50669 25214 50669 24912 50669 24912 50670 25214 50670 25508 50670 24912 50671 25508 50671 24914 50671 24914 50672 25508 50672 25506 50672 24914 50673 25506 50673 25215 50673 25215 50674 25506 50674 25504 50674 24917 50675 13875 50675 24918 50675 24918 50676 13875 50676 25216 50676 24918 50677 25216 50677 24919 50677 24919 50678 25216 50678 25217 50678 24919 50679 25217 50679 25218 50679 25218 50680 25217 50680 25512 50680 25218 50681 25512 50681 25219 50681 25219 50682 25512 50682 25220 50682 25219 50683 25220 50683 24922 50683 24922 50684 25220 50684 25221 50684 24922 50685 25221 50685 14040 50685 14040 50686 25221 50686 13886 50686 25222 50687 24928 50687 25223 50687 25223 50688 24928 50688 25224 50688 25223 50689 25224 50689 25718 50689 25224 50690 25225 50690 25718 50690 25718 50691 25225 50691 25226 50691 25718 50692 25226 50692 25720 50692 25720 50693 25226 50693 25227 50693 25227 50694 25228 50694 25720 50694 25720 50695 25228 50695 25229 50695 25720 50696 25229 50696 25233 50696 13865 50697 25230 50697 25231 50697 25231 50698 25230 50698 25721 50698 25231 50699 25721 50699 25232 50699 25232 50700 25721 50700 25233 50700 25232 50701 25233 50701 24925 50701 24925 50702 25233 50702 25229 50702 24929 50703 25234 50703 24931 50703 24931 50704 25234 50704 25632 50704 24931 50705 25632 50705 24932 50705 24932 50706 25632 50706 25633 50706 24932 50707 25633 50707 25235 50707 25235 50708 25633 50708 25634 50708 25235 50709 25634 50709 24935 50709 24935 50710 25634 50710 25236 50710 24935 50711 25236 50711 25237 50711 25237 50712 25236 50712 25239 50712 25237 50713 25239 50713 25238 50713 25238 50714 25239 50714 25240 50714 25238 50715 25240 50715 14025 50715 14025 50716 25240 50716 25241 50716 13859 50717 25526 50717 25242 50717 25242 50718 25526 50718 25525 50718 25242 50719 25525 50719 24938 50719 24938 50720 25525 50720 25524 50720 24938 50721 25524 50721 25243 50721 25243 50722 25524 50722 25244 50722 25243 50723 25244 50723 24940 50723 24940 50724 25244 50724 25245 50724 24940 50725 25245 50725 24942 50725 24942 50726 25245 50726 25519 50726 24942 50727 25519 50727 24943 50727 24943 50728 25519 50728 25246 50728 24943 50729 25246 50729 24944 50729 24944 50730 25246 50730 25518 50730 14019 50731 13851 50731 24946 50731 24946 50732 13851 50732 25528 50732 24946 50733 25528 50733 25247 50733 25247 50734 25528 50734 25248 50734 25247 50735 25248 50735 24950 50735 24950 50736 25248 50736 25648 50736 24950 50737 25648 50737 24953 50737 24953 50738 25648 50738 25532 50738 24953 50739 25532 50739 24954 50739 24954 50740 25532 50740 25249 50740 24954 50741 25249 50741 24955 50741 24955 50742 25249 50742 25529 50742 24955 50743 25529 50743 14011 50743 14011 50744 25529 50744 25250 50744 24961 50745 13844 50745 25251 50745 25251 50746 13844 50746 25252 50746 25251 50747 25252 50747 24962 50747 24962 50748 25252 50748 25253 50748 24962 50749 25253 50749 24964 50749 24964 50750 25253 50750 25537 50750 24964 50751 25537 50751 24966 50751 24966 50752 25537 50752 25536 50752 24966 50753 25536 50753 25254 50753 25254 50754 25536 50754 25255 50754 25254 50755 25255 50755 24968 50755 24968 50756 25255 50756 25256 50756 24968 50757 25256 50757 14005 50757 14005 50758 25256 50758 25533 50758 24969 50759 13837 50759 25257 50759 25257 50760 13837 50760 25669 50760 25257 50761 25669 50761 25258 50761 25258 50762 25669 50762 25259 50762 25258 50763 25259 50763 24973 50763 24973 50764 25259 50764 25260 50764 24973 50765 25260 50765 24975 50765 24975 50766 25260 50766 25262 50766 24975 50767 25262 50767 25261 50767 25261 50768 25262 50768 25263 50768 25261 50769 25263 50769 24977 50769 24977 50770 25263 50770 25264 50770 24977 50771 25264 50771 13999 50771 13999 50772 25264 50772 25265 50772 25268 50773 25266 50773 25267 50773 25267 50774 24989 50774 25268 50774 25268 50775 24989 50775 25269 50775 25268 50776 25269 50776 25270 50776 25269 50777 25271 50777 25270 50777 25270 50778 25271 50778 24987 50778 25270 50779 24987 50779 25272 50779 25272 50780 24987 50780 25273 50780 25272 50781 25273 50781 25540 50781 25273 50782 24984 50782 25540 50782 25540 50783 24984 50783 24983 50783 25540 50784 24983 50784 25274 50784 24983 50785 25275 50785 25274 50785 25274 50786 25275 50786 24981 50786 25274 50787 24981 50787 25538 50787 24979 50788 13830 50788 25276 50788 25276 50789 13830 50789 25538 50789 25276 50790 25538 50790 25277 50790 25277 50791 25538 50791 24981 50791 25284 50792 25576 50792 24991 50792 24991 50793 25576 50793 25575 50793 24991 50794 25575 50794 24990 50794 24990 50795 25575 50795 25545 50795 25278 50796 25572 50796 24994 50796 24994 50797 25572 50797 25279 50797 24994 50798 25279 50798 25280 50798 25280 50799 25279 50799 25281 50799 25280 50800 25281 50800 25282 50800 25282 50801 25281 50801 25283 50801 25282 50802 25283 50802 25284 50802 25284 50803 25283 50803 25576 50803 25288 50804 25565 50804 24995 50804 24995 50805 25565 50805 25571 50805 24995 50806 25571 50806 25278 50806 25278 50807 25571 50807 25572 50807 25285 50808 25556 50808 24998 50808 24998 50809 25556 50809 25555 50809 24998 50810 25555 50810 24999 50810 24999 50811 25555 50811 25286 50811 24999 50812 25286 50812 25002 50812 25002 50813 25286 50813 25287 50813 25002 50814 25287 50814 25288 50814 25288 50815 25287 50815 25565 50815 25004 50816 25289 50816 25290 50816 25290 50817 25289 50817 25291 50817 25290 50818 25291 50818 25285 50818 25285 50819 25291 50819 25556 50819 25006 50820 25292 50820 25004 50820 25004 50821 25292 50821 25289 50821 25293 50822 25294 50822 25546 50822 25546 50823 25294 50823 25295 50823 24990 50824 25545 50824 25296 50824 25296 50825 25545 50825 25544 50825 25296 50826 25544 50826 25010 50826 25010 50827 25544 50827 25548 50827 25010 50828 25548 50828 25294 50828 25294 50829 25548 50829 25295 50829 25301 50830 25297 50830 25013 50830 25013 50831 25297 50831 25590 50831 25013 50832 25590 50832 25035 50832 25035 50833 25590 50833 25298 50833 25016 50834 25517 50834 25299 50834 25299 50835 25517 50835 25640 50835 25299 50836 25640 50836 25300 50836 25300 50837 25640 50837 25593 50837 25300 50838 25593 50838 25015 50838 25015 50839 25593 50839 25592 50839 25015 50840 25592 50840 25301 50840 25301 50841 25592 50841 25297 50841 25309 50842 25303 50842 25302 50842 25302 50843 25303 50843 25516 50843 25302 50844 25516 50844 25016 50844 25016 50845 25516 50845 25517 50845 25304 50846 25311 50846 25021 50846 25021 50847 25311 50847 25305 50847 25021 50848 25305 50848 25306 50848 25306 50849 25305 50849 25307 50849 25306 50850 25307 50850 25308 50850 25308 50851 25307 50851 25585 50851 25308 50852 25585 50852 25309 50852 25309 50853 25585 50853 25303 50853 25026 50854 25580 50854 25310 50854 25310 50855 25580 50855 25584 50855 25310 50856 25584 50856 25304 50856 25304 50857 25584 50857 25311 50857 25028 50858 25582 50858 25312 50858 25312 50859 25582 50859 25581 50859 25312 50860 25581 50860 25313 50860 25313 50861 25581 50861 25314 50861 25313 50862 25314 50862 25026 50862 25026 50863 25314 50863 25580 50863 25028 50864 25031 50864 25582 50864 25582 50865 25031 50865 25315 50865 13824 50866 25579 50866 25034 50866 25034 50867 25579 50867 25595 50867 25034 50868 25595 50868 25031 50868 25031 50869 25595 50869 25315 50869 25038 50870 25499 50870 25036 50870 25036 50871 25499 50871 25608 50871 25036 50872 25608 50872 25316 50872 25316 50873 25608 50873 25604 50873 13822 50874 13823 50874 25038 50874 25038 50875 13823 50875 25499 50875 25325 50876 25599 50876 25040 50876 25040 50877 25599 50877 25317 50877 25040 50878 25317 50878 13987 50878 13987 50879 25317 50879 13819 50879 25318 50880 25319 50880 25320 50880 25320 50881 25319 50881 25591 50881 25320 50882 25591 50882 25321 50882 25321 50883 25591 50883 25323 50883 25321 50884 25323 50884 25322 50884 25322 50885 25323 50885 25324 50885 25322 50886 25324 50886 25325 50886 25325 50887 25324 50887 25599 50887 25047 50888 25588 50888 25045 50888 25045 50889 25588 50889 25589 50889 25045 50890 25589 50890 25318 50890 25318 50891 25589 50891 25319 50891 25327 50892 25597 50892 25051 50892 25051 50893 25597 50893 25596 50893 25051 50894 25596 50894 25049 50894 25049 50895 25596 50895 25326 50895 25049 50896 25326 50896 25047 50896 25047 50897 25326 50897 25588 50897 25327 50898 25328 50898 25597 50898 25597 50899 25328 50899 25329 50899 25316 50900 25604 50900 25055 50900 25055 50901 25604 50901 25594 50901 25055 50902 25594 50902 25054 50902 25054 50903 25594 50903 25330 50903 25054 50904 25330 50904 25328 50904 25328 50905 25330 50905 25329 50905 25060 50906 25614 50906 25059 50906 25059 50907 25614 50907 25331 50907 25059 50908 25331 50908 25074 50908 25074 50909 25331 50909 25347 50909 13818 50910 25610 50910 25061 50910 25061 50911 25610 50911 25611 50911 25061 50912 25611 50912 25332 50912 25332 50913 25611 50913 25333 50913 25332 50914 25333 50914 25060 50914 25060 50915 25333 50915 25614 50915 25066 50916 25498 50916 25065 50916 25065 50917 25498 50917 25515 50917 25065 50918 25515 50918 13817 50918 13817 50919 25515 50919 25609 50919 25340 50920 25334 50920 25067 50920 25067 50921 25334 50921 25724 50921 25067 50922 25724 50922 25335 50922 25335 50923 25724 50923 25336 50923 25335 50924 25336 50924 25337 50924 25337 50925 25336 50925 25338 50925 25337 50926 25338 50926 25066 50926 25066 50927 25338 50927 25498 50927 25341 50928 25603 50928 25339 50928 25339 50929 25603 50929 25607 50929 25339 50930 25607 50930 25340 50930 25340 50931 25607 50931 25334 50931 25605 50932 25603 50932 25341 50932 25069 50933 25343 50933 25342 50933 25342 50934 25343 50934 25344 50934 25342 50935 25344 50935 25345 50935 25345 50936 25344 50936 25605 50936 25345 50937 25605 50937 13982 50937 13982 50938 25605 50938 25341 50938 25069 50939 25070 50939 25343 50939 25343 50940 25070 50940 25346 50940 25074 50941 25347 50941 25348 50941 25348 50942 25347 50942 25612 50942 25348 50943 25612 50943 25072 50943 25072 50944 25612 50944 25349 50944 25072 50945 25349 50945 25070 50945 25070 50946 25349 50946 25346 50946 25350 50947 25351 50947 25075 50947 25075 50948 25351 50948 25352 50948 25075 50949 25352 50949 25366 50949 25366 50950 25352 50950 25353 50950 25358 50951 25497 50951 25079 50951 25079 50952 25497 50952 25688 50952 25079 50953 25688 50953 25354 50953 25354 50954 25688 50954 25355 50954 25354 50955 25355 50955 25081 50955 25081 50956 25355 50956 25356 50956 25081 50957 25356 50957 25350 50957 25350 50958 25356 50958 25351 50958 25082 50959 25621 50959 25357 50959 25357 50960 25621 50960 25509 50960 25357 50961 25509 50961 25358 50961 25358 50962 25509 50962 25497 50962 13816 50963 25700 50963 25082 50963 25082 50964 25700 50964 25621 50964 25085 50965 25359 50965 25084 50965 25084 50966 25359 50966 25618 50966 25084 50967 25618 50967 25360 50967 25360 50968 25618 50968 25361 50968 25362 50969 25616 50969 25087 50969 25087 50970 25616 50970 25617 50970 25087 50971 25617 50971 25086 50971 25086 50972 25617 50972 25363 50972 25086 50973 25363 50973 25085 50973 25085 50974 25363 50974 25359 50974 25362 50975 25090 50975 25616 50975 25616 50976 25090 50976 25364 50976 25364 50977 25090 50977 25365 50977 25365 50978 25090 50978 25369 50978 25365 50979 25369 50979 25367 50979 25366 50980 25353 50980 25092 50980 25092 50981 25353 50981 25367 50981 25092 50982 25367 50982 25368 50982 25368 50983 25367 50983 25369 50983 25098 50984 25557 50984 25093 50984 25093 50985 25557 50985 25370 50985 25093 50986 25370 50986 25110 50986 25110 50987 25370 50987 25371 50987 25375 50988 25552 50988 25095 50988 25095 50989 25552 50989 25372 50989 25095 50990 25372 50990 25373 50990 25373 50991 25372 50991 25374 50991 25373 50992 25374 50992 25097 50992 25097 50993 25374 50993 25554 50993 25097 50994 25554 50994 25098 50994 25098 50995 25554 50995 25557 50995 25379 50996 25673 50996 25099 50996 25099 50997 25673 50997 25376 50997 25099 50998 25376 50998 25375 50998 25375 50999 25376 50999 25552 50999 13977 51000 13814 51000 25377 51000 25377 51001 13814 51001 25378 51001 25377 51002 25378 51002 25102 51002 25102 51003 25378 51003 25674 51003 25102 51004 25674 51004 25379 51004 25379 51005 25674 51005 25673 51005 25107 51006 25380 51006 25105 51006 25105 51007 25380 51007 25627 51007 25105 51008 25627 51008 13976 51008 13976 51009 25627 51009 25628 51009 25381 51010 25385 51010 25382 51010 25382 51011 25385 51011 25625 51011 25382 51012 25625 51012 25383 51012 25383 51013 25625 51013 25384 51013 25383 51014 25384 51014 25107 51014 25107 51015 25384 51015 25380 51015 25381 51016 25390 51016 25385 51016 25385 51017 25390 51017 25386 51017 25110 51018 25371 51018 25387 51018 25387 51019 25371 51019 25389 51019 25387 51020 25389 51020 25388 51020 25388 51021 25389 51021 25391 51021 25388 51022 25391 51022 25390 51022 25390 51023 25391 51023 25386 51023 25392 51024 25741 51024 25393 51024 25392 51025 25393 51025 25114 51025 25114 51026 25393 51026 25394 51026 25114 51027 25394 51027 25395 51027 25395 51028 25394 51028 25396 51028 25395 51029 25396 51029 25116 51029 25116 51030 25396 51030 25745 51030 25116 51031 25745 51031 25397 51031 25397 51032 25745 51032 25746 51032 25397 51033 25746 51033 25398 51033 25398 51034 25746 51034 13714 51034 25398 51035 13714 51035 13804 51035 13974 51036 13802 51036 25500 51036 13974 51037 25500 51037 25122 51037 25122 51038 25500 51038 25399 51038 25122 51039 25399 51039 25123 51039 25123 51040 25399 51040 25530 51040 25123 51041 25530 51041 25124 51041 25124 51042 25530 51042 25531 51042 25124 51043 25531 51043 25126 51043 25126 51044 25531 51044 25400 51044 25126 51045 25400 51045 25127 51045 25127 51046 25400 51046 25649 51046 25127 51047 25649 51047 25128 51047 25652 51048 13793 51048 25401 51048 25652 51049 25401 51049 25402 51049 25402 51050 25401 51050 25135 51050 25402 51051 25135 51051 25403 51051 25403 51052 25135 51052 25404 51052 25403 51053 25404 51053 25405 51053 25405 51054 25404 51054 25406 51054 25405 51055 25406 51055 25658 51055 25406 51056 25134 51056 25658 51056 25658 51057 25134 51057 25133 51057 25658 51058 25133 51058 25407 51058 25133 51059 25132 51059 25407 51059 25407 51060 25132 51060 25408 51060 25407 51061 25408 51061 25409 51061 25408 51062 25131 51062 25409 51062 25409 51063 25131 51063 25410 51063 25409 51064 25410 51064 25411 51064 25411 51065 25410 51065 13798 51065 25411 51066 13798 51066 25412 51066 25762 51067 25561 51067 25143 51067 25143 51068 25561 51068 25413 51068 25143 51069 25413 51069 25144 51069 25762 51070 25143 51070 25760 51070 25760 51071 25143 51071 25141 51071 25760 51072 25141 51072 25414 51072 25414 51073 25141 51073 25415 51073 25414 51074 25415 51074 25416 51074 25416 51075 25415 51075 25140 51075 25416 51076 25140 51076 25567 51076 25567 51077 25140 51077 25138 51077 25567 51078 25138 51078 25568 51078 25568 51079 25138 51079 25137 51079 25568 51080 25137 51080 25569 51080 25417 51081 25151 51081 25419 51081 25417 51082 25419 51082 25418 51082 25418 51083 25419 51083 25420 51083 25418 51084 25420 51084 25492 51084 25492 51085 25420 51085 25758 51085 25758 51086 25420 51086 25421 51086 25758 51087 25421 51087 25422 51087 25422 51088 25421 51088 25423 51088 25422 51089 25423 51089 25424 51089 25424 51090 25423 51090 25426 51090 25424 51091 25426 51091 25425 51091 25426 51092 25148 51092 25425 51092 25425 51093 25148 51093 25147 51093 25425 51094 25147 51094 25675 51094 25147 51095 25427 51095 25675 51095 25675 51096 25427 51096 25429 51096 25675 51097 25429 51097 25428 51097 25428 51098 25429 51098 25430 51098 25428 51099 25430 51099 13786 51099 25431 51100 25432 51100 25433 51100 25433 51101 25432 51101 25677 51101 25433 51102 25677 51102 25157 51102 25157 51103 25677 51103 25676 51103 25157 51104 25676 51104 25434 51104 25434 51105 25676 51105 25667 51105 25434 51106 25667 51106 25160 51106 25431 51107 25433 51107 25756 51107 25756 51108 25433 51108 25154 51108 25756 51109 25154 51109 25678 51109 25678 51110 25154 51110 25435 51110 25678 51111 25435 51111 25680 51111 25680 51112 25435 51112 25153 51112 25680 51113 25153 51113 25436 51113 13932 51114 25438 51114 25437 51114 25437 51115 25438 51115 25439 51115 25438 51116 25440 51116 25439 51116 25439 51117 25440 51117 25170 51117 25439 51118 25170 51118 25539 51118 25539 51119 25170 51119 25441 51119 25539 51120 25441 51120 25681 51120 25681 51121 25441 51121 25168 51121 13940 51122 25683 51122 25161 51122 25161 51123 25683 51123 25443 51123 25161 51124 25443 51124 25442 51124 25442 51125 25443 51125 25753 51125 25442 51126 25753 51126 25164 51126 25164 51127 25753 51127 25751 51127 25164 51128 25751 51128 25165 51128 25165 51129 25751 51129 25444 51129 25165 51130 25444 51130 25445 51130 25445 51131 25444 51131 25681 51131 25445 51132 25681 51132 25446 51132 25446 51133 25681 51133 25168 51133 25175 51134 25699 51134 25176 51134 25176 51135 25699 51135 25447 51135 25176 51136 25447 51136 25177 51136 25177 51137 25447 51137 25697 51137 25177 51138 25697 51138 25449 51138 25449 51139 25697 51139 25448 51139 25449 51140 25448 51140 25179 51140 25179 51141 25448 51141 25620 51141 25179 51142 25620 51142 25450 51142 25175 51143 25451 51143 25699 51143 25699 51144 25451 51144 25453 51144 25699 51145 25453 51145 25452 51145 25452 51146 25453 51146 25173 51146 25452 51147 25173 51147 25454 51147 13767 51148 25455 51148 13768 51148 13768 51149 25455 51149 25695 51149 13768 51150 25695 51150 25454 51150 25454 51151 25695 51151 25696 51151 25454 51152 25696 51152 25452 51152 13918 51153 13746 51153 25707 51153 13918 51154 25707 51154 25180 51154 25180 51155 25707 51155 25703 51155 25180 51156 25703 51156 25456 51156 25456 51157 25703 51157 25457 51157 25456 51158 25457 51158 25459 51158 25459 51159 25457 51159 25458 51159 25459 51160 25458 51160 25460 51160 25460 51161 25458 51161 25704 51161 25460 51162 25704 51162 25461 51162 25461 51163 25704 51163 25462 51163 25461 51164 25462 51164 13911 51164 25466 51165 25186 51165 25463 51165 25463 51166 25186 51166 25464 51166 25463 51167 25464 51167 25715 51167 25189 51168 25188 51168 25465 51168 25465 51169 25188 51169 25187 51169 25465 51170 25187 51170 25466 51170 25466 51171 25187 51171 25467 51171 25466 51172 25467 51172 25186 51172 25189 51173 25465 51173 25468 51173 25468 51174 25465 51174 25712 51174 25468 51175 25712 51175 25469 51175 25469 51176 25712 51176 25710 51176 25469 51177 25710 51177 25470 51177 25470 51178 25710 51178 25709 51178 25470 51179 25709 51179 25471 51179 25471 51180 25709 51180 13745 51180 25471 51181 13745 51181 13904 51181 25192 51182 25472 51182 25194 51182 25194 51183 25472 51183 25734 51183 25732 51184 25473 51184 25734 51184 25734 51185 25473 51185 25195 51185 25734 51186 25195 51186 25194 51186 25199 51187 25198 51187 25474 51187 25474 51188 25198 51188 25475 51188 25474 51189 25475 51189 25732 51189 25732 51190 25475 51190 25476 51190 25732 51191 25476 51191 25473 51191 25199 51192 25474 51192 25477 51192 25477 51193 25474 51193 25478 51193 25477 51194 25478 51194 25479 51194 25479 51195 25478 51195 25480 51195 25479 51196 25480 51196 25200 51196 25200 51197 25480 51197 25481 51197 25481 51198 25480 51198 25482 51198 25481 51199 25482 51199 25483 51199 25202 51200 25629 51200 25204 51200 25204 51201 25629 51201 25730 51201 25730 51202 25729 51202 25204 51202 25204 51203 25729 51203 25484 51203 25204 51204 25484 51204 25485 51204 25485 51205 25484 51205 25600 51205 25485 51206 25600 51206 25206 51206 25206 51207 25600 51207 25486 51207 25206 51208 25486 51208 25487 51208 25487 51209 25486 51209 25488 51209 25487 51210 25488 51210 25489 51210 25489 51211 25488 51211 25490 51211 25489 51212 25490 51212 13729 51212 25738 51213 13698 51213 25737 51213 25491 51214 13705 51214 25735 51214 13704 51215 25733 51215 25735 51215 13758 51216 13760 51216 25708 51216 25444 51217 25751 51217 25754 51217 25757 51218 25542 51218 25755 51218 25671 51219 25672 51219 13776 51219 25432 51220 25431 51220 25666 51220 25492 51221 25758 51221 25662 51221 25662 51222 25562 51222 25493 51222 25493 51223 25562 51223 25563 51223 25761 51224 25566 51224 25560 51224 25409 51225 25411 51225 25659 51225 25644 51226 25521 51226 25522 51226 13718 51227 25494 51227 25495 51227 25637 51228 25496 51228 25495 51228 25389 51229 25371 51229 25626 51229 25509 51230 25692 51230 25497 51230 25498 51231 25711 51231 25515 51231 25608 51232 25499 51232 25601 51232 25545 51233 25575 51233 25574 51233 25399 51234 25500 51234 25583 51234 25503 51235 25684 51235 25501 51235 25698 51236 25505 51236 25508 51236 25501 51237 25502 51237 25503 51237 25503 51238 25502 51238 25504 51238 25503 51239 25504 51239 25505 51239 25505 51240 25504 51240 25506 51240 25505 51241 25506 51241 25508 51241 25685 51242 25693 51242 25507 51242 25507 51243 25693 51243 25692 51243 25507 51244 25692 51244 25510 51244 25508 51245 25214 51245 25698 51245 25698 51246 25214 51246 25213 51246 25698 51247 25213 51247 25509 51247 25213 51248 25211 51248 25509 51248 25509 51249 25211 51249 25209 51249 25509 51250 25209 51250 25692 51250 25692 51251 25209 51251 13890 51251 25692 51252 13890 51252 25510 51252 13709 51253 25511 51253 25221 51253 13708 51254 13885 51254 25511 51254 25511 51255 13885 51255 13886 51255 25511 51256 13886 51256 25221 51256 25217 51257 25711 51257 25512 51257 25512 51258 25711 51258 25713 51258 25512 51259 25713 51259 25220 51259 13878 51260 25513 51260 25708 51260 25708 51261 25513 51261 25514 51261 25708 51262 25514 51262 13708 51262 13708 51263 25514 51263 13884 51263 13708 51264 13884 51264 13885 51264 25217 51265 25216 51265 25711 51265 25711 51266 25216 51266 13875 51266 25711 51267 13875 51267 25515 51267 25515 51268 13875 51268 13877 51268 25515 51269 13877 51269 13878 51269 25516 51270 25520 51270 25517 51270 25517 51271 25520 51271 25518 51271 25518 51272 25246 51272 25517 51272 25517 51273 25246 51273 25519 51273 25517 51274 25519 51274 25521 51274 13693 51275 25523 51275 25526 51275 25526 51276 13860 51276 13693 51276 13693 51277 13860 51277 13858 51277 13693 51278 13858 51278 25587 51278 25587 51279 13858 51279 13856 51279 25587 51280 13856 51280 25516 51280 25516 51281 13856 51281 13853 51281 25516 51282 13853 51282 25520 51282 25519 51283 25245 51283 25521 51283 25521 51284 25245 51284 25244 51284 25521 51285 25244 51285 25522 51285 25522 51286 25244 51286 25524 51286 25522 51287 25524 51287 25523 51287 25523 51288 25524 51288 25525 51288 25523 51289 25525 51289 25526 51289 25654 51290 25764 51290 13851 51290 13851 51291 25764 51291 25527 51291 13851 51292 25527 51292 25528 51292 25528 51293 25527 51293 25248 51293 25577 51294 25250 51294 25583 51294 25583 51295 25250 51295 25529 51295 25583 51296 25529 51296 25399 51296 25399 51297 25529 51297 25530 51297 25648 51298 25531 51298 25532 51298 25532 51299 25531 51299 25530 51299 25532 51300 25530 51300 25249 51300 25249 51301 25530 51301 25529 51301 25564 51302 13840 51302 25565 51302 13840 51303 13839 51303 25565 51303 25565 51304 13839 51304 25533 51304 25565 51305 25533 51305 25571 51305 25571 51306 25533 51306 25256 51306 25571 51307 25256 51307 25255 51307 25564 51308 25566 51308 25534 51308 25534 51309 25566 51309 25761 51309 25534 51310 25761 51310 13843 51310 13843 51311 25761 51311 25535 51311 25657 51312 25252 51312 25535 51312 25535 51313 25252 51313 13844 51313 25535 51314 13844 51314 13843 51314 25255 51315 25536 51315 25659 51315 25659 51316 25536 51316 25537 51316 25659 51317 25537 51317 25657 51317 25657 51318 25537 51318 25253 51318 25657 51319 25253 51319 25252 51319 25274 51320 25538 51320 25686 51320 13825 51321 25266 51321 25539 51321 25539 51322 25266 51322 25268 51322 25539 51323 25268 51323 25439 51323 25686 51324 25437 51324 25439 51324 25268 51325 25270 51325 25439 51325 25439 51326 25270 51326 25272 51326 25439 51327 25272 51327 25686 51327 25686 51328 25272 51328 25540 51328 25686 51329 25540 51329 25274 51329 25538 51330 13830 51330 25541 51330 25541 51331 13830 51331 13829 51331 25541 51332 13829 51332 25542 51332 13829 51333 13828 51333 25542 51333 25542 51334 13828 51334 25543 51334 25542 51335 25543 51335 25755 51335 25755 51336 25543 51336 13827 51336 25755 51337 13827 51337 25754 51337 25754 51338 13827 51338 13825 51338 25547 51339 25544 51339 25545 51339 25558 51340 25546 51340 25626 51340 25626 51341 25546 51341 25295 51341 25626 51342 25295 51342 25547 51342 25547 51343 25295 51343 25548 51343 25547 51344 25548 51344 25544 51344 13784 51345 25549 51345 25551 51345 25551 51346 25549 51346 25550 51346 25563 51347 25287 51347 25286 51347 25376 51348 25551 51348 25552 51348 25552 51349 25551 51349 25550 51349 25552 51350 25550 51350 25372 51350 25372 51351 25550 51351 25553 51351 25372 51352 25553 51352 25374 51352 25374 51353 25553 51353 25554 51353 25286 51354 25555 51354 25660 51354 25553 51355 25660 51355 25554 51355 25554 51356 25660 51356 25555 51356 25554 51357 25555 51357 25557 51357 25557 51358 25555 51358 25556 51358 25557 51359 25556 51359 25370 51359 25370 51360 25556 51360 25291 51360 25370 51361 25291 51361 25371 51361 25371 51362 25291 51362 25289 51362 25371 51363 25289 51363 25626 51363 25626 51364 25289 51364 25292 51364 25626 51365 25292 51365 25558 51365 25562 51366 25760 51366 25414 51366 25559 51367 13787 51367 25566 51367 25566 51368 13787 51368 25413 51368 25566 51369 25413 51369 25560 51369 25560 51370 25413 51370 25561 51370 25560 51371 25561 51371 25762 51371 25414 51372 25416 51372 25562 51372 25562 51373 25416 51373 25567 51373 25562 51374 25567 51374 25563 51374 25564 51375 25565 51375 25566 51375 25566 51376 25565 51376 13790 51376 25566 51377 13790 51377 25559 51377 25567 51378 25568 51378 25563 51378 25563 51379 25568 51379 25569 51379 25563 51380 25569 51380 25287 51380 25287 51381 25569 51381 25570 51381 25287 51382 25570 51382 25565 51382 25565 51383 25570 51383 13791 51383 25565 51384 13791 51384 13790 51384 25255 51385 25659 51385 25571 51385 25571 51386 25659 51386 25411 51386 25571 51387 25411 51387 25572 51387 25411 51388 25412 51388 25572 51388 25572 51389 25412 51389 25573 51389 25572 51390 25573 51390 25279 51390 25279 51391 25573 51391 25281 51391 25574 51392 25575 51392 25583 51392 25583 51393 25575 51393 25576 51393 25583 51394 25576 51394 25283 51394 25283 51395 25281 51395 25583 51395 25583 51396 25281 51396 25573 51396 25583 51397 25573 51397 25577 51397 25577 51398 25573 51398 13796 51398 25577 51399 13796 51399 13846 51399 13846 51400 13796 51400 13794 51400 13846 51401 13794 51401 25578 51401 25578 51402 13794 51402 25656 51402 25595 51403 25579 51403 25326 51403 25545 51404 25574 51404 25547 51404 25547 51405 25574 51405 25580 51405 25547 51406 25580 51406 25314 51406 25314 51407 25581 51407 25547 51407 25547 51408 25581 51408 25582 51408 25547 51409 25582 51409 25740 51409 25740 51410 25582 51410 25315 51410 25740 51411 25315 51411 25595 51411 25307 51412 25305 51412 25583 51412 25583 51413 25305 51413 25311 51413 25583 51414 25311 51414 25574 51414 25574 51415 25311 51415 25584 51415 25574 51416 25584 51416 25580 51416 25307 51417 25583 51417 25585 51417 25585 51418 25583 51418 25500 51418 25585 51419 25500 51419 25303 51419 25303 51420 25500 51420 13802 51420 25303 51421 13802 51421 25516 51421 25516 51422 13802 51422 25586 51422 25516 51423 25586 51423 25587 51423 25521 51424 25744 51424 25639 51424 25326 51425 25579 51425 25588 51425 25588 51426 25579 51426 25298 51426 25588 51427 25298 51427 25589 51427 25589 51428 25298 51428 25590 51428 25589 51429 25590 51429 25319 51429 25319 51430 25590 51430 25297 51430 25319 51431 25297 51431 25591 51431 25591 51432 25297 51432 25592 51432 25591 51433 25592 51433 25598 51433 25598 51434 25592 51434 25593 51434 25598 51435 25593 51435 25640 51435 25329 51436 25330 51436 25606 51436 25606 51437 25330 51437 25594 51437 25606 51438 25594 51438 25604 51438 25595 51439 25326 51439 25740 51439 25740 51440 25326 51440 25596 51440 25740 51441 25596 51441 25597 51441 25496 51442 25488 51442 25598 51442 25598 51443 25488 51443 25486 51443 25598 51444 25486 51444 25600 51444 25729 51445 25317 51445 25484 51445 25484 51446 25317 51446 25599 51446 25484 51447 25599 51447 25600 51447 25600 51448 25599 51448 25324 51448 25600 51449 25324 51449 25598 51449 25598 51450 25324 51450 25323 51450 25598 51451 25323 51451 25591 51451 25601 51452 25499 51452 25602 51452 25602 51453 25499 51453 13823 51453 25602 51454 13823 51454 25731 51454 25607 51455 25603 51455 25604 51455 25604 51456 25603 51456 25605 51456 25604 51457 25605 51457 25606 51457 25606 51458 25605 51458 25344 51458 25619 51459 25739 51459 25346 51459 25346 51460 25739 51460 25606 51460 25346 51461 25606 51461 25343 51461 25343 51462 25606 51462 25344 51462 25604 51463 25608 51463 25607 51463 25607 51464 25608 51464 25601 51464 25607 51465 25601 51465 25334 51465 25334 51466 25601 51466 25724 51466 25709 51467 25338 51467 25336 51467 13878 51468 25708 51468 25515 51468 25515 51469 25708 51469 13760 51469 25515 51470 13760 51470 25609 51470 25704 51471 25613 51471 25611 51471 13760 51472 25462 51472 25609 51472 25609 51473 25462 51473 25704 51473 25609 51474 25704 51474 25610 51474 25610 51475 25704 51475 25611 51475 25346 51476 25349 51476 25619 51476 25619 51477 25349 51477 25612 51477 25619 51478 25612 51478 25347 51478 25347 51479 25331 51479 25623 51479 25623 51480 25331 51480 25614 51480 25623 51481 25614 51481 25613 51481 25613 51482 25614 51482 25333 51482 25613 51483 25333 51483 25611 51483 25616 51484 25364 51484 25615 51484 25615 51485 25364 51485 25365 51485 25384 51486 25367 51486 25380 51486 25380 51487 25367 51487 25353 51487 25380 51488 25353 51488 25627 51488 25359 51489 25363 51489 25619 51489 25615 51490 25739 51490 25616 51490 25616 51491 25739 51491 25619 51491 25616 51492 25619 51492 25617 51492 25617 51493 25619 51493 25363 51493 25347 51494 25623 51494 25619 51494 25619 51495 25623 51495 25618 51495 25619 51496 25618 51496 25359 51496 13762 51497 25620 51497 25621 51497 25700 51498 25622 51498 25613 51498 25613 51499 25622 51499 25624 51499 25613 51500 25624 51500 25623 51500 25623 51501 25624 51501 25361 51501 25623 51502 25361 51502 25618 51502 25621 51503 25620 51503 25509 51503 25509 51504 25620 51504 25448 51504 25509 51505 25448 51505 25698 51505 25625 51506 25615 51506 25384 51506 25384 51507 25615 51507 25365 51507 25384 51508 25365 51508 25367 51508 25385 51509 25386 51509 25626 51509 25626 51510 25386 51510 25391 51510 25626 51511 25391 51511 25389 51511 25353 51512 25352 51512 25627 51512 25627 51513 25352 51513 25686 51513 25627 51514 25686 51514 25628 51514 25628 51515 25686 51515 13814 51515 25538 51516 25541 51516 25686 51516 25686 51517 25541 51517 25378 51517 25686 51518 25378 51518 13814 51518 25632 51519 25234 51519 13722 51519 25630 51520 25480 51520 25730 51520 13722 51521 25234 51521 25629 51521 25629 51522 25234 51522 13864 51522 25629 51523 13864 51523 25730 51523 25730 51524 13864 51524 13863 51524 25730 51525 13863 51525 25630 51525 25630 51526 25631 51526 25480 51526 25480 51527 25631 51527 25636 51527 25480 51528 25636 51528 25482 51528 25482 51529 25636 51529 13736 51529 25632 51530 25737 51530 25633 51530 25633 51531 25737 51531 13700 51531 25240 51532 25239 51532 13702 51532 13702 51533 25239 51533 25236 51533 13702 51534 25236 51534 13700 51534 13700 51535 25236 51535 25634 51535 13700 51536 25634 51536 25633 51536 13702 51537 25635 51537 25240 51537 25240 51538 25635 51538 13736 51538 25240 51539 13736 51539 25241 51539 25241 51540 13736 51540 25636 51540 13725 51541 25638 51541 25637 51541 25637 51542 25638 51542 13728 51542 25637 51543 13728 51543 25496 51543 25496 51544 13728 51544 25490 51544 25496 51545 25490 51545 25488 51545 25521 51546 25639 51546 25517 51546 25517 51547 25639 51547 25743 51547 25517 51548 25743 51548 25640 51548 25640 51549 25743 51549 25742 51549 25640 51550 25742 51550 25598 51550 25598 51551 25742 51551 25641 51551 25598 51552 25641 51552 25496 51552 25641 51553 13711 51553 25496 51553 25496 51554 13711 51554 13713 51554 25496 51555 13713 51555 25495 51555 25495 51556 13713 51556 13720 51556 25495 51557 13720 51557 13718 51557 25747 51558 25642 51558 13716 51558 13716 51559 25642 51559 13717 51559 25744 51560 25521 51560 25643 51560 25643 51561 25521 51561 25644 51561 25643 51562 25644 51562 25747 51562 25747 51563 25644 51563 13695 51563 25747 51564 13695 51564 25642 51564 25645 51565 13693 51565 25646 51565 25646 51566 13693 51566 13799 51566 25586 51567 13801 51567 25587 51567 25587 51568 13801 51568 13800 51568 25587 51569 13800 51569 13693 51569 13693 51570 13800 51570 25647 51570 13693 51571 25647 51571 13799 51571 25648 51572 25248 51572 25531 51572 25531 51573 25248 51573 25527 51573 25531 51574 25527 51574 25400 51574 25400 51575 25527 51575 13694 51575 25400 51576 13694 51576 25649 51576 25649 51577 13694 51577 25650 51577 25649 51578 25650 51578 25651 51578 25652 51579 25653 51579 13793 51579 13793 51580 25653 51580 25764 51580 13793 51581 25764 51581 25655 51581 25655 51582 25764 51582 25654 51582 25655 51583 25654 51583 25656 51583 25656 51584 25654 51584 13849 51584 25656 51585 13849 51585 25578 51585 25657 51586 25402 51586 25403 51586 25403 51587 25405 51587 25657 51587 25657 51588 25405 51588 25658 51588 25657 51589 25658 51589 25659 51589 25659 51590 25658 51590 25407 51590 25659 51591 25407 51591 25409 51591 25286 51592 25660 51592 25563 51592 25563 51593 25660 51593 25661 51593 25563 51594 25661 51594 25493 51594 25493 51595 25661 51595 25417 51595 25493 51596 25417 51596 25662 51596 25662 51597 25417 51597 25418 51597 25662 51598 25418 51598 25492 51598 13836 51599 25663 51599 25668 51599 25668 51600 25663 51600 13834 51600 25668 51601 13834 51601 25665 51601 25665 51602 13834 51602 25664 51602 25665 51603 25664 51603 25666 51603 25666 51604 25664 51604 13832 51604 13786 51605 13784 51605 25669 51605 25263 51606 25670 51606 25264 51606 25264 51607 25670 51607 25667 51607 25264 51608 25667 51608 25265 51608 25265 51609 25667 51609 25676 51609 25265 51610 25676 51610 13832 51610 13786 51611 25669 51611 25428 51611 25668 51612 25759 51612 13836 51612 13836 51613 25759 51613 25428 51613 13836 51614 25428 51614 13837 51614 13837 51615 25428 51615 25669 51615 25262 51616 25260 51616 13784 51616 13784 51617 25260 51617 25259 51617 13784 51618 25259 51618 25669 51618 25263 51619 25262 51619 25670 51619 25670 51620 25262 51620 13784 51620 25670 51621 13784 51621 25671 51621 25671 51622 13784 51622 25551 51622 25671 51623 25551 51623 25672 51623 25672 51624 25551 51624 25376 51624 25672 51625 25376 51625 13776 51625 13776 51626 25376 51626 25673 51626 13776 51627 25673 51627 13778 51627 13778 51628 25673 51628 25674 51628 13778 51629 25674 51629 13779 51629 25424 51630 25425 51630 25759 51630 25759 51631 25425 51631 25675 51631 25759 51632 25675 51632 25428 51632 13832 51633 25676 51633 25666 51633 25666 51634 25676 51634 25677 51634 25666 51635 25677 51635 25432 51635 25757 51636 25756 51636 25678 51636 25674 51637 25378 51637 13779 51637 13779 51638 25378 51638 25541 51638 13779 51639 25541 51639 25679 51639 25679 51640 25541 51640 25542 51640 25679 51641 25542 51641 25436 51641 25436 51642 25542 51642 25757 51642 25436 51643 25757 51643 25680 51643 25680 51644 25757 51644 25678 51644 13825 51645 25539 51645 25754 51645 25754 51646 25539 51646 25681 51646 25754 51647 25681 51647 25444 51647 25682 51648 25753 51648 25443 51648 25683 51649 25694 51649 25693 51649 25443 51650 25683 51650 25682 51650 25682 51651 25683 51651 25693 51651 25682 51652 25693 51652 25684 51652 25684 51653 25693 51653 25685 51653 25684 51654 25685 51654 25501 51654 25352 51655 25351 51655 25686 51655 25686 51656 25351 51656 25356 51656 25686 51657 25356 51657 25437 51657 25437 51658 25356 51658 25355 51658 25437 51659 25355 51659 25687 51659 25687 51660 25355 51660 25688 51660 25687 51661 25688 51661 25689 51661 25689 51662 25688 51662 25497 51662 25689 51663 25497 51663 25690 51663 25690 51664 25497 51664 25692 51664 25690 51665 25692 51665 25691 51665 25691 51666 25692 51666 25693 51666 25691 51667 25693 51667 13772 51667 13772 51668 25693 51668 25694 51668 25695 51669 25505 51669 25696 51669 25696 51670 25505 51670 25452 51670 25448 51671 25697 51671 25698 51671 25698 51672 25697 51672 25447 51672 25698 51673 25447 51673 25505 51673 25505 51674 25447 51674 25699 51674 25505 51675 25699 51675 25452 51675 25621 51676 25700 51676 13762 51676 13762 51677 25700 51677 25613 51677 13762 51678 25613 51678 25701 51678 25701 51679 25613 51679 25702 51679 25702 51680 25613 51680 13764 51680 13764 51681 25613 51681 25706 51681 13764 51682 25706 51682 13766 51682 13766 51683 25706 51683 13767 51683 13767 51684 25706 51684 25748 51684 13767 51685 25748 51685 25455 51685 25703 51686 25706 51686 25457 51686 25457 51687 25706 51687 25613 51687 25457 51688 25613 51688 25458 51688 25458 51689 25613 51689 25704 51689 13747 51690 25705 51690 13746 51690 13746 51691 25705 51691 25706 51691 13746 51692 25706 51692 25707 51692 25707 51693 25706 51693 25703 51693 13708 51694 13748 51694 13749 51694 13749 51695 13752 51695 13708 51695 13708 51696 13752 51696 13754 51696 13708 51697 13754 51697 25708 51697 25708 51698 13754 51698 13755 51698 25708 51699 13755 51699 13758 51699 25711 51700 25465 51700 25713 51700 25713 51701 25465 51701 25466 51701 25713 51702 25466 51702 25463 51702 25338 51703 25709 51703 25498 51703 25498 51704 25709 51704 25710 51704 25498 51705 25710 51705 25711 51705 25711 51706 25710 51706 25712 51706 25711 51707 25712 51707 25465 51707 25221 51708 25220 51708 13709 51708 13709 51709 25220 51709 25713 51709 13709 51710 25713 51710 13706 51710 13706 51711 25713 51711 25463 51711 13706 51712 25463 51712 25714 51712 25714 51713 25463 51713 25715 51713 25714 51714 25715 51714 25716 51714 25716 51715 25715 51715 13738 51715 25716 51716 13738 51716 13707 51716 25719 51717 25717 51717 25222 51717 25222 51718 25223 51718 25719 51718 25719 51719 25223 51719 25718 51719 25719 51720 25718 51720 13704 51720 25718 51721 25720 51721 13704 51721 13704 51722 25720 51722 25233 51722 13704 51723 25233 51723 25733 51723 25233 51724 25721 51724 25733 51724 25733 51725 25721 51725 25230 51725 25733 51726 25230 51726 25602 51726 25602 51727 25230 51727 25722 51727 25602 51728 25722 51728 13867 51728 13867 51729 25723 51729 25602 51729 25602 51730 25723 51730 13745 51730 25602 51731 13745 51731 25601 51731 25601 51732 13745 51732 25709 51732 25601 51733 25709 51733 25724 51733 25724 51734 25709 51734 25336 51734 25723 51735 25725 51735 13745 51735 13745 51736 25725 51736 13872 51736 13745 51737 13872 51737 25726 51737 25726 51738 13872 51738 25727 51738 13872 51739 25728 51739 25727 51739 25727 51740 25728 51740 25222 51740 25727 51741 25222 51741 13741 51741 13741 51742 25222 51742 25717 51742 13741 51743 25717 51743 13739 51743 13739 51744 25717 51744 13737 51744 25729 51745 25730 51745 25317 51745 25317 51746 25730 51746 25480 51746 25317 51747 25480 51747 13819 51747 13819 51748 25480 51748 25478 51748 13819 51749 25478 51749 13820 51749 13820 51750 25478 51750 25474 51750 13820 51751 25474 51751 25731 51751 25731 51752 25474 51752 25732 51752 25731 51753 25732 51753 25602 51753 25602 51754 25732 51754 25734 51754 25602 51755 25734 51755 25733 51755 25733 51756 25734 51756 25472 51756 25733 51757 25472 51757 25735 51757 25735 51758 25472 51758 13730 51758 25735 51759 13730 51759 25491 51759 25736 51760 13732 51760 25635 51760 25635 51761 13732 51761 13734 51761 25635 51762 13734 51762 13736 51762 25632 51763 13722 51763 25737 51763 25737 51764 13722 51764 13724 51764 25737 51765 13724 51765 25738 51765 25625 51766 25385 51766 25615 51766 25615 51767 25385 51767 25626 51767 25615 51768 25626 51768 25739 51768 25739 51769 25626 51769 25547 51769 25739 51770 25547 51770 25606 51770 25606 51771 25547 51771 25740 51771 25606 51772 25740 51772 25329 51772 25329 51773 25740 51773 25597 51773 25741 51774 25641 51774 25742 51774 25741 51775 25742 51775 25393 51775 25393 51776 25742 51776 25743 51776 25393 51777 25743 51777 25394 51777 25394 51778 25743 51778 25639 51778 25394 51779 25639 51779 25396 51779 25396 51780 25639 51780 25744 51780 25396 51781 25744 51781 25745 51781 25745 51782 25744 51782 25643 51782 25745 51783 25643 51783 25746 51783 25746 51784 25643 51784 25747 51784 25746 51785 25747 51785 13714 51785 25665 51786 14289 51786 14288 51786 25455 51787 25748 51787 25749 51787 25749 51788 25748 51788 25706 51788 25749 51789 25706 51789 13710 51789 14296 51790 25503 51790 25505 51790 14296 51791 25505 51791 25749 51791 25749 51792 25505 51792 25695 51792 25749 51793 25695 51793 25455 51793 25503 51794 14296 51794 25684 51794 25684 51795 14296 51795 25752 51795 25684 51796 25752 51796 25682 51796 25750 51797 25754 51797 25751 51797 25750 51798 25751 51798 25752 51798 25752 51799 25751 51799 25753 51799 25752 51800 25753 51800 25682 51800 25754 51801 25750 51801 25755 51801 25755 51802 25750 51802 14294 51802 25755 51803 14294 51803 25757 51803 25665 51804 25666 51804 14289 51804 14289 51805 25666 51805 25431 51805 14289 51806 25431 51806 14294 51806 14294 51807 25431 51807 25756 51807 14294 51808 25756 51808 25757 51808 25662 51809 25758 51809 25422 51809 25424 51810 25759 51810 14288 51810 14288 51811 25759 51811 25668 51811 14288 51812 25668 51812 25665 51812 25424 51813 14288 51813 25422 51813 25422 51814 14288 51814 14280 51814 25422 51815 14280 51815 25662 51815 25662 51816 14280 51816 14286 51816 25662 51817 14286 51817 25562 51817 25562 51818 14286 51818 25760 51818 25760 51819 14286 51819 14287 51819 25760 51820 14287 51820 25762 51820 14284 51821 25761 51821 14287 51821 14287 51822 25761 51822 25560 51822 14287 51823 25560 51823 25762 51823 25763 51824 25653 51824 25652 51824 25652 51825 25402 51825 25763 51825 25763 51826 25402 51826 25657 51826 25763 51827 25657 51827 14284 51827 14284 51828 25657 51828 25535 51828 14284 51829 25535 51829 25761 51829 25653 51830 25763 51830 25764 51830 25764 51831 25763 51831 25765 51831 25764 51832 25765 51832 25527 51832 17742 51833 17547 51833 25766 51833 17547 51834 17554 51834 17555 51834 25767 51835 17742 51835 25768 51835 25768 51836 17742 51836 25766 51836 25768 51837 25766 51837 17740 51837 17740 51838 25766 51838 17738 51838 17549 51839 25766 51839 25769 51839 25769 51840 25766 51840 17547 51840 25769 51841 17547 51841 25770 51841 25770 51842 17547 51842 17555 51842 25770 51843 17555 51843 17552 51843 25775 51844 17563 51844 25771 51844 17733 51845 25772 51845 25775 51845 25775 51846 25772 51846 25773 51846 25775 51847 25773 51847 17569 51847 17569 51848 25774 51848 25775 51848 25775 51849 25774 51849 17564 51849 25775 51850 17564 51850 17563 51850 17735 51851 17734 51851 25776 51851 25776 51852 17734 51852 25775 51852 25776 51853 25775 51853 17561 51853 17561 51854 25775 51854 25771 51854 17576 51855 17578 51855 25779 51855 17727 51856 17728 51856 17731 51856 17731 51857 25777 51857 17727 51857 17727 51858 25777 51858 25778 51858 17727 51859 25778 51859 25779 51859 25779 51860 25778 51860 17575 51860 25779 51861 17575 51861 17576 51861 17581 51862 17582 51862 17579 51862 17579 51863 17582 51863 25779 51863 17579 51864 25779 51864 25780 51864 25780 51865 25779 51865 17578 51865 25781 51866 17716 51866 25783 51866 25783 51867 17716 51867 17718 51867 25783 51868 17718 51868 17719 51868 17586 51869 25781 51869 17584 51869 17584 51870 25781 51870 25783 51870 17584 51871 25783 51871 25782 51871 25782 51872 25783 51872 17583 51872 17721 51873 17723 51873 17720 51873 17720 51874 17723 51874 25783 51874 17720 51875 25783 51875 25784 51875 25784 51876 25783 51876 17719 51876 17590 51877 25785 51877 17706 51877 17709 51878 25785 51878 17713 51878 17713 51879 25785 51879 17590 51879 17713 51880 17590 51880 17712 51880 25786 51881 17588 51881 17590 51881 17590 51882 17588 51882 17703 51882 17590 51883 17703 51883 17712 51883 17594 51884 17591 51884 17595 51884 17595 51885 17591 51885 17590 51885 17595 51886 17590 51886 17704 51886 17704 51887 17590 51887 17706 51887 25789 51888 17597 51888 17695 51888 17696 51889 17698 51889 17699 51889 25787 51890 25788 51890 17605 51890 17605 51891 25788 51891 17607 51891 17605 51892 17607 51892 17602 51892 25788 51893 25789 51893 17607 51893 17607 51894 25789 51894 17695 51894 17607 51895 17695 51895 17701 51895 17701 51896 17695 51896 17696 51896 17701 51897 17696 51897 25790 51897 25790 51898 17696 51898 17699 51898 25794 51899 25791 51899 25795 51899 17611 51900 17690 51900 25795 51900 25795 51901 17690 51901 17693 51901 25792 51902 25794 51902 25793 51902 25793 51903 25794 51903 25795 51903 25793 51904 25795 51904 25796 51904 25796 51905 25795 51905 17693 51905 17689 51906 25797 51906 25798 51906 25798 51907 25797 51907 17690 51907 25798 51908 17690 51908 17688 51908 17688 51909 17690 51909 17611 51909 25803 51910 17616 51910 17617 51910 25799 51911 17683 51911 25803 51911 25803 51912 17683 51912 25800 51912 25803 51913 25800 51913 25801 51913 17612 51914 17613 51914 25802 51914 25802 51915 17613 51915 25803 51915 25802 51916 25803 51916 17686 51916 17686 51917 25803 51917 25801 51917 25799 51918 25803 51918 17619 51918 17619 51919 25803 51919 17617 51919 17619 51920 17617 51920 17618 51920 25808 51921 17624 51921 25809 51921 17626 51922 17624 51922 17630 51922 17630 51923 17624 51923 25808 51923 17630 51924 25808 51924 25805 51924 25804 51925 17677 51925 25808 51925 25808 51926 17677 51926 17621 51926 25808 51927 17621 51927 25805 51927 17675 51928 25806 51928 17676 51928 17676 51929 25806 51929 25808 51929 17676 51930 25808 51930 25807 51930 25807 51931 25808 51931 25809 51931 17636 51932 25810 51932 25813 51932 25810 51933 17667 51933 25813 51933 25813 51934 17667 51934 17668 51934 25813 51935 17668 51935 17670 51935 17633 51936 17635 51936 25813 51936 25813 51937 17635 51937 25811 51937 25813 51938 25811 51938 17636 51938 17631 51939 17632 51939 25812 51939 25812 51940 17632 51940 25813 51940 25812 51941 25813 51941 17672 51941 17672 51942 25813 51942 17670 51942 25814 51943 17666 51943 17637 51943 17662 51944 25817 51944 17638 51944 17638 51945 25817 51945 25815 51945 17638 51946 25815 51946 25816 51946 25816 51947 25815 51947 17640 51947 17664 51948 17665 51948 17663 51948 17663 51949 17665 51949 25814 51949 17663 51950 25814 51950 25817 51950 25817 51951 25814 51951 17637 51951 25817 51952 17637 51952 25815 51952 17646 51953 25818 51953 17647 51953 17647 51954 25818 51954 17645 51954 17647 51955 17645 51955 17651 51955 25819 51956 25821 51956 25820 51956 25820 51957 25821 51957 17647 51957 25820 51958 17647 51958 25822 51958 25822 51959 17647 51959 17651 51959 17657 51960 17656 51960 25823 51960 25823 51961 17656 51961 25818 51961 25823 51962 25818 51962 25824 51962 25824 51963 25818 51963 17646 51963 25836 51964 25825 51964 25828 51964 25836 51965 25832 51965 25833 51965 25826 51966 25832 51966 25836 51966 25828 51967 25826 51967 25836 51967 25836 51968 25827 51968 25831 51968 25834 51969 25827 51969 25836 51969 25833 51970 25834 51970 25836 51970 25831 51971 25827 51971 25837 51971 25837 51972 25827 51972 25828 51972 25837 51973 25828 51973 25825 51973 25835 51974 25830 51974 25829 51974 25829 51975 25830 51975 25831 51975 25829 51976 25831 51976 25838 51976 25838 51977 25831 51977 25837 51977 25832 51978 25826 51978 25833 51978 25833 51979 25826 51979 25828 51979 25833 51980 25828 51980 25834 51980 25834 51981 25828 51981 25827 51981 25836 51982 25835 51982 25829 51982 25830 51983 25835 51983 25836 51983 25831 51984 25830 51984 25836 51984 25836 51985 25837 51985 25825 51985 25838 51986 25837 51986 25836 51986 25829 51987 25838 51987 25836 51987 25840 51988 25844 51988 25846 51988 25840 51989 25839 51989 25841 51989 25847 51990 25839 51990 25840 51990 25846 51991 25847 51991 25840 51991 25840 51992 25848 51992 25849 51992 25842 51993 25848 51993 25840 51993 25841 51994 25842 51994 25840 51994 25851 51995 25843 51995 25845 51995 25844 51996 25850 51996 25852 51996 25852 51997 25851 51997 25844 51997 25844 51998 25851 51998 25845 51998 25844 51999 25845 51999 25846 51999 25846 52000 25845 52000 25849 52000 25846 52001 25849 52001 25848 52001 25839 52002 25847 52002 25841 52002 25841 52003 25847 52003 25846 52003 25841 52004 25846 52004 25842 52004 25842 52005 25846 52005 25848 52005 25840 52006 25843 52006 25851 52006 25845 52007 25843 52007 25840 52007 25849 52008 25845 52008 25840 52008 25840 52009 25850 52009 25844 52009 25852 52010 25850 52010 25840 52010 25851 52011 25852 52011 25840 52011 25853 52012 25855 52012 25859 52012 25859 52013 25855 52013 25854 52013 25857 52014 25854 52014 25856 52014 25856 52015 25854 52015 25855 52015 25856 52016 25855 52016 25860 52016 25860 52017 25855 52017 25853 52017 25857 52018 25856 52018 25858 52018 25858 52019 25856 52019 25860 52019 25854 52020 25857 52020 25859 52020 25859 52021 25857 52021 25858 52021 25859 52022 25858 52022 25853 52022 25853 52023 25858 52023 25860 52023 25861 52024 25868 52024 25862 52024 25862 52025 25868 52025 25863 52025 25868 52026 25865 52026 25863 52026 25863 52027 25865 52027 25864 52027 25864 52028 25865 52028 25866 52028 25866 52029 25865 52029 25867 52029 25864 52030 25866 52030 25863 52030 25863 52031 25866 52031 25862 52031 25862 52032 25866 52032 25861 52032 25861 52033 25866 52033 25867 52033 25861 52034 25867 52034 25868 52034 25868 52035 25867 52035 25865 52035 25876 52036 25872 52036 25869 52036 25869 52037 25872 52037 25873 52037 25876 52038 25870 52038 25872 52038 25872 52039 25870 52039 25874 52039 25871 52040 25874 52040 25875 52040 25875 52041 25874 52041 25870 52041 25872 52042 25874 52042 25873 52042 25873 52043 25874 52043 25871 52043 25873 52044 25871 52044 25869 52044 25869 52045 25871 52045 25875 52045 25875 52046 25870 52046 25869 52046 25869 52047 25870 52047 25876 52047 25877 52048 25883 52048 25878 52048 25878 52049 25883 52049 25879 52049 25882 52050 25877 52050 25880 52050 25880 52051 25877 52051 25878 52051 25880 52052 25878 52052 25884 52052 25884 52053 25878 52053 25879 52053 25884 52054 25881 52054 25880 52054 25880 52055 25881 52055 25882 52055 25877 52056 25882 52056 25883 52056 25883 52057 25882 52057 25881 52057 25883 52058 25881 52058 25879 52058 25879 52059 25881 52059 25884 52059 25886 52060 25889 52060 25887 52060 25887 52061 25889 52061 25885 52061 25887 52062 25885 52062 25888 52062 25888 52063 25885 52063 25890 52063 25886 52064 25887 52064 25891 52064 25891 52065 25887 52065 25888 52065 25889 52066 25886 52066 25892 52066 25892 52067 25886 52067 25891 52067 25892 52068 25891 52068 25890 52068 25890 52069 25891 52069 25888 52069 25890 52070 25885 52070 25892 52070 25892 52071 25885 52071 25889 52071 25898 52072 25893 52072 25897 52072 25897 52073 25893 52073 25896 52073 25896 52074 25893 52074 25895 52074 25895 52075 25893 52075 25900 52075 25895 52076 25900 52076 25894 52076 25894 52077 25900 52077 25899 52077 25895 52078 25894 52078 25896 52078 25896 52079 25894 52079 25897 52079 25894 52080 25899 52080 25897 52080 25897 52081 25899 52081 25898 52081 25898 52082 25899 52082 25893 52082 25893 52083 25899 52083 25900 52083 25901 52084 25908 52084 25902 52084 25902 52085 25908 52085 25903 52085 25902 52086 25903 52086 25904 52086 25904 52087 25903 52087 25907 52087 25907 52088 25906 52088 25904 52088 25904 52089 25906 52089 25905 52089 25905 52090 25901 52090 25904 52090 25904 52091 25901 52091 25902 52091 25905 52092 25906 52092 25901 52092 25901 52093 25906 52093 25908 52093 25903 52094 25908 52094 25907 52094 25907 52095 25908 52095 25906 52095 25909 52096 25915 52096 25910 52096 25910 52097 25915 52097 25914 52097 25910 52098 25914 52098 25911 52098 25911 52099 25914 52099 25916 52099 25909 52100 25910 52100 25912 52100 25912 52101 25910 52101 25911 52101 25916 52102 25914 52102 25913 52102 25913 52103 25914 52103 25915 52103 25915 52104 25909 52104 25913 52104 25913 52105 25909 52105 25912 52105 25913 52106 25912 52106 25916 52106 25916 52107 25912 52107 25911 52107 25930 52108 25925 52108 25924 52108 25930 52109 25920 52109 25919 52109 25923 52110 25920 52110 25930 52110 25924 52111 25923 52111 25930 52111 25930 52112 25917 52112 25922 52112 25918 52113 25917 52113 25930 52113 25919 52114 25918 52114 25930 52114 25920 52115 25923 52115 25919 52115 25919 52116 25923 52116 25928 52116 25919 52117 25928 52117 25918 52117 25925 52118 25929 52118 25921 52118 25927 52119 25922 52119 25928 52119 25928 52120 25922 52120 25917 52120 25928 52121 25917 52121 25918 52121 25923 52122 25924 52122 25928 52122 25928 52123 25924 52123 25925 52123 25928 52124 25925 52124 25926 52124 25926 52125 25925 52125 25921 52125 25930 52126 25928 52126 25926 52126 25927 52127 25928 52127 25930 52127 25922 52128 25927 52128 25930 52128 25930 52129 25929 52129 25925 52129 25921 52130 25929 52130 25930 52130 25926 52131 25921 52131 25930 52131 25943 52132 25931 52132 25938 52132 25943 52133 25932 52133 25937 52133 25933 52134 25932 52134 25943 52134 25938 52135 25933 52135 25943 52135 25943 52136 25940 52136 25939 52136 25934 52137 25940 52137 25943 52137 25937 52138 25934 52138 25943 52138 25935 52139 25941 52139 25942 52139 25931 52140 25944 52140 25936 52140 25932 52141 25933 52141 25937 52141 25937 52142 25933 52142 25938 52142 25937 52143 25938 52143 25934 52143 25934 52144 25938 52144 25940 52144 25936 52145 25935 52145 25931 52145 25931 52146 25935 52146 25942 52146 25931 52147 25942 52147 25938 52147 25938 52148 25942 52148 25939 52148 25938 52149 25939 52149 25940 52149 25943 52150 25941 52150 25935 52150 25942 52151 25941 52151 25943 52151 25939 52152 25942 52152 25943 52152 25943 52153 25944 52153 25931 52153 25936 52154 25944 52154 25943 52154 25935 52155 25936 52155 25943 52155 25958 52156 25945 52156 25952 52156 25952 52157 25945 52157 25946 52157 25957 52158 25949 52158 25948 52158 25947 52159 25958 52159 25948 52159 25948 52160 25958 52160 25952 52160 25948 52161 25952 52161 25957 52161 25957 52162 25952 52162 25953 52162 25959 52163 25960 52163 25955 52163 25948 52164 25949 52164 25950 52164 25950 52165 25949 52165 25956 52165 25950 52166 25956 52166 25951 52166 25953 52167 25952 52167 25959 52167 25953 52168 25959 52168 25954 52168 25954 52169 25959 52169 25955 52169 25954 52170 25955 52170 25956 52170 25956 52171 25955 52171 25961 52171 25956 52172 25961 52172 25951 52172 25956 52173 25949 52173 25954 52173 25954 52174 25949 52174 25957 52174 25954 52175 25957 52175 25953 52175 25951 52176 25958 52176 25950 52176 25950 52177 25958 52177 25947 52177 25959 52178 25946 52178 25960 52178 25960 52179 25946 52179 25945 52179 25952 52180 25946 52180 25959 52180 25945 52181 25958 52181 25951 52181 25961 52182 25955 52182 25951 52182 25951 52183 25955 52183 25960 52183 25951 52184 25960 52184 25945 52184 25947 52185 25948 52185 25950 52185 25967 52186 25962 52186 25972 52186 25972 52187 25962 52187 25963 52187 25972 52188 25963 52188 25969 52188 25978 52189 25974 52189 25962 52189 25962 52190 25974 52190 25977 52190 25962 52191 25977 52191 25963 52191 25963 52192 25977 52192 25964 52192 25965 52193 25966 52193 25971 52193 25962 52194 25967 52194 25973 52194 25973 52195 25967 52195 25968 52195 25973 52196 25968 52196 25976 52196 25969 52197 25963 52197 25965 52197 25969 52198 25965 52198 25970 52198 25970 52199 25965 52199 25971 52199 25970 52200 25971 52200 25968 52200 25968 52201 25971 52201 25975 52201 25968 52202 25975 52202 25976 52202 25969 52203 25970 52203 25972 52203 25972 52204 25970 52204 25968 52204 25972 52205 25968 52205 25967 52205 25976 52206 25974 52206 25973 52206 25973 52207 25974 52207 25978 52207 25965 52208 25964 52208 25966 52208 25966 52209 25964 52209 25977 52209 25963 52210 25964 52210 25965 52210 25977 52211 25974 52211 25976 52211 25975 52212 25971 52212 25976 52212 25976 52213 25971 52213 25966 52213 25976 52214 25966 52214 25977 52214 25978 52215 25962 52215 25973 52215 25988 52216 25986 52216 25980 52216 25980 52217 25986 52217 25985 52217 25983 52218 25986 52218 25988 52218 25985 52219 25984 52219 25979 52219 25992 52220 25987 52220 25979 52220 25979 52221 25987 52221 25980 52221 25979 52222 25980 52222 25985 52222 25981 52223 25982 52223 25995 52223 25994 52224 25982 52224 25993 52224 25993 52225 25982 52225 25983 52225 25993 52226 25983 52226 25989 52226 25981 52227 25984 52227 25982 52227 25982 52228 25984 52228 25985 52228 25982 52229 25985 52229 25983 52229 25983 52230 25985 52230 25986 52230 25988 52231 25980 52231 25987 52231 25982 52232 25994 52232 25995 52232 25995 52233 25994 52233 25991 52233 25995 52234 25991 52234 25979 52234 25989 52235 25983 52235 25988 52235 25989 52236 25988 52236 25990 52236 25990 52237 25988 52237 25987 52237 25990 52238 25987 52238 25991 52238 25991 52239 25987 52239 25992 52239 25991 52240 25992 52240 25979 52240 25989 52241 25990 52241 25993 52241 25993 52242 25990 52242 25991 52242 25993 52243 25991 52243 25994 52243 25979 52244 25984 52244 25995 52244 25995 52245 25984 52245 25981 52245 26008 52246 25996 52246 26011 52246 26011 52247 25996 52247 26010 52247 25997 52248 26001 52248 25998 52248 26009 52249 26008 52249 25998 52249 25998 52250 26008 52250 26011 52250 25998 52251 26011 52251 25997 52251 25997 52252 26011 52252 26006 52252 25999 52253 26000 52253 26003 52253 25998 52254 26001 52254 26002 52254 26002 52255 26001 52255 26004 52255 26002 52256 26004 52256 26012 52256 26006 52257 26011 52257 25999 52257 26006 52258 25999 52258 26007 52258 26007 52259 25999 52259 26003 52259 26007 52260 26003 52260 26004 52260 26004 52261 26003 52261 26005 52261 26004 52262 26005 52262 26012 52262 26006 52263 26007 52263 25997 52263 25997 52264 26007 52264 26004 52264 25997 52265 26004 52265 26001 52265 26012 52266 26008 52266 26002 52266 26002 52267 26008 52267 26009 52267 25999 52268 26010 52268 26000 52268 26000 52269 26010 52269 25996 52269 26011 52270 26010 52270 25999 52270 26005 52271 26003 52271 26012 52271 26012 52272 26003 52272 26000 52272 26012 52273 26000 52273 26008 52273 26008 52274 26000 52274 25996 52274 26009 52275 25998 52275 26002 52275 26013 52276 26020 52276 26014 52276 26014 52277 26020 52277 26015 52277 26014 52278 26015 52278 26021 52278 26027 52279 26016 52279 26020 52279 26020 52280 26016 52280 26017 52280 26020 52281 26017 52281 26015 52281 26015 52282 26017 52282 26018 52282 26028 52283 26019 52283 26029 52283 26020 52284 26013 52284 26026 52284 26026 52285 26013 52285 26025 52285 26026 52286 26025 52286 26024 52286 26021 52287 26015 52287 26028 52287 26021 52288 26028 52288 26022 52288 26022 52289 26028 52289 26029 52289 26022 52290 26029 52290 26025 52290 26025 52291 26029 52291 26023 52291 26025 52292 26023 52292 26024 52292 26025 52293 26013 52293 26022 52293 26022 52294 26013 52294 26014 52294 26022 52295 26014 52295 26021 52295 26024 52296 26016 52296 26026 52296 26026 52297 26016 52297 26027 52297 26028 52298 26018 52298 26019 52298 26019 52299 26018 52299 26017 52299 26015 52300 26018 52300 26028 52300 26017 52301 26016 52301 26024 52301 26023 52302 26029 52302 26024 52302 26024 52303 26029 52303 26019 52303 26024 52304 26019 52304 26017 52304 26027 52305 26020 52305 26026 52305 26031 52306 26044 52306 26035 52306 26035 52307 26044 52307 26043 52307 26039 52308 26033 52308 26032 52308 26030 52309 26031 52309 26032 52309 26032 52310 26031 52310 26035 52310 26032 52311 26035 52311 26039 52311 26039 52312 26035 52312 26036 52312 26042 52313 26046 52313 26045 52313 26032 52314 26033 52314 26034 52314 26034 52315 26033 52315 26040 52315 26034 52316 26040 52316 26041 52316 26036 52317 26035 52317 26042 52317 26036 52318 26042 52318 26038 52318 26038 52319 26042 52319 26045 52319 26038 52320 26045 52320 26040 52320 26040 52321 26045 52321 26037 52321 26040 52322 26037 52322 26041 52322 26036 52323 26038 52323 26039 52323 26039 52324 26038 52324 26040 52324 26039 52325 26040 52325 26033 52325 26041 52326 26031 52326 26034 52326 26034 52327 26031 52327 26030 52327 26042 52328 26043 52328 26046 52328 26046 52329 26043 52329 26044 52329 26035 52330 26043 52330 26042 52330 26044 52331 26031 52331 26041 52331 26037 52332 26045 52332 26041 52332 26041 52333 26045 52333 26046 52333 26041 52334 26046 52334 26044 52334 26030 52335 26032 52335 26034 52335 26047 52336 26060 52336 26049 52336 26049 52337 26060 52337 26048 52337 26059 52338 26051 52338 26050 52338 26063 52339 26047 52339 26050 52339 26050 52340 26047 52340 26049 52340 26050 52341 26049 52341 26059 52341 26059 52342 26049 52342 26058 52342 26054 52343 26062 52343 26056 52343 26050 52344 26051 52344 26053 52344 26053 52345 26051 52345 26052 52345 26053 52346 26052 52346 26061 52346 26058 52347 26049 52347 26054 52347 26058 52348 26054 52348 26055 52348 26055 52349 26054 52349 26056 52349 26055 52350 26056 52350 26052 52350 26052 52351 26056 52351 26057 52351 26052 52352 26057 52352 26061 52352 26058 52353 26055 52353 26059 52353 26059 52354 26055 52354 26052 52354 26059 52355 26052 52355 26051 52355 26061 52356 26047 52356 26053 52356 26053 52357 26047 52357 26063 52357 26054 52358 26048 52358 26062 52358 26062 52359 26048 52359 26060 52359 26049 52360 26048 52360 26054 52360 26060 52361 26047 52361 26061 52361 26057 52362 26056 52362 26061 52362 26061 52363 26056 52363 26062 52363 26061 52364 26062 52364 26060 52364 26063 52365 26050 52365 26053 52365 26075 52366 26064 52366 26069 52366 26069 52367 26064 52367 26065 52367 26066 52368 26064 52368 26075 52368 26065 52369 26080 52369 26079 52369 26067 52370 26068 52370 26079 52370 26079 52371 26068 52371 26069 52371 26079 52372 26069 52372 26065 52372 26070 52373 26071 52373 26074 52373 26080 52374 26065 52374 26066 52374 26066 52375 26065 52375 26064 52375 26077 52376 26073 52376 26071 52376 26070 52377 26080 52377 26071 52377 26071 52378 26080 52378 26066 52378 26071 52379 26066 52379 26077 52379 26077 52380 26066 52380 26072 52380 26075 52381 26069 52381 26068 52381 26071 52382 26073 52382 26074 52382 26074 52383 26073 52383 26078 52383 26074 52384 26078 52384 26079 52384 26072 52385 26066 52385 26075 52385 26072 52386 26075 52386 26076 52386 26076 52387 26075 52387 26068 52387 26076 52388 26068 52388 26078 52388 26078 52389 26068 52389 26067 52389 26078 52390 26067 52390 26079 52390 26072 52391 26076 52391 26077 52391 26077 52392 26076 52392 26078 52392 26077 52393 26078 52393 26073 52393 26079 52394 26080 52394 26074 52394 26074 52395 26080 52395 26070 52395 26093 52396 26081 52396 26091 52396 26091 52397 26081 52397 26086 52397 26091 52398 26086 52398 26085 52398 26097 52399 26094 52399 26081 52399 26081 52400 26094 52400 26082 52400 26081 52401 26082 52401 26086 52401 26086 52402 26082 52402 26083 52402 26088 52403 26096 52403 26089 52403 26081 52404 26093 52404 26084 52404 26084 52405 26093 52405 26092 52405 26084 52406 26092 52406 26095 52406 26085 52407 26086 52407 26088 52407 26085 52408 26088 52408 26087 52408 26087 52409 26088 52409 26089 52409 26087 52410 26089 52410 26092 52410 26092 52411 26089 52411 26090 52411 26092 52412 26090 52412 26095 52412 26085 52413 26087 52413 26091 52413 26091 52414 26087 52414 26092 52414 26091 52415 26092 52415 26093 52415 26095 52416 26094 52416 26084 52416 26084 52417 26094 52417 26097 52417 26088 52418 26083 52418 26096 52418 26096 52419 26083 52419 26082 52419 26086 52420 26083 52420 26088 52420 26082 52421 26094 52421 26095 52421 26090 52422 26089 52422 26095 52422 26095 52423 26089 52423 26096 52423 26095 52424 26096 52424 26082 52424 26097 52425 26081 52425 26084 52425 26101 52426 26105 52426 26108 52426 26108 52427 26105 52427 26104 52427 26110 52428 26099 52428 26102 52428 26102 52429 26099 52429 26103 52429 26098 52430 26099 52430 26110 52430 26100 52431 26111 52431 26101 52431 26101 52432 26111 52432 26102 52432 26101 52433 26102 52433 26105 52433 26105 52434 26102 52434 26103 52434 26104 52435 26107 52435 26108 52435 26105 52436 26103 52436 26098 52436 26098 52437 26103 52437 26099 52437 26114 52438 26109 52438 26107 52438 26104 52439 26105 52439 26107 52439 26107 52440 26105 52440 26098 52440 26107 52441 26098 52441 26114 52441 26114 52442 26098 52442 26106 52442 26110 52443 26102 52443 26111 52443 26107 52444 26109 52444 26108 52444 26108 52445 26109 52445 26112 52445 26108 52446 26112 52446 26101 52446 26106 52447 26098 52447 26110 52447 26106 52448 26110 52448 26113 52448 26113 52449 26110 52449 26111 52449 26113 52450 26111 52450 26112 52450 26112 52451 26111 52451 26100 52451 26112 52452 26100 52452 26101 52452 26106 52453 26113 52453 26114 52453 26114 52454 26113 52454 26112 52454 26114 52455 26112 52455 26109 52455 26115 52456 26129 52456 26119 52456 26119 52457 26129 52457 26116 52457 26117 52458 26125 52458 26130 52458 26127 52459 26115 52459 26130 52459 26130 52460 26115 52460 26119 52460 26130 52461 26119 52461 26117 52461 26117 52462 26119 52462 26118 52462 26120 52463 26128 52463 26121 52463 26130 52464 26125 52464 26131 52464 26131 52465 26125 52465 26123 52465 26131 52466 26123 52466 26126 52466 26118 52467 26119 52467 26120 52467 26118 52468 26120 52468 26124 52468 26124 52469 26120 52469 26121 52469 26124 52470 26121 52470 26123 52470 26123 52471 26121 52471 26122 52471 26123 52472 26122 52472 26126 52472 26123 52473 26125 52473 26124 52473 26124 52474 26125 52474 26117 52474 26124 52475 26117 52475 26118 52475 26126 52476 26115 52476 26131 52476 26131 52477 26115 52477 26127 52477 26120 52478 26116 52478 26128 52478 26128 52479 26116 52479 26129 52479 26119 52480 26116 52480 26120 52480 26129 52481 26115 52481 26126 52481 26122 52482 26121 52482 26126 52482 26126 52483 26121 52483 26128 52483 26126 52484 26128 52484 26129 52484 26127 52485 26130 52485 26131 52485 26146 52486 26133 52486 26132 52486 26132 52487 26133 52487 26141 52487 26132 52488 26141 52488 26134 52488 26135 52489 26136 52489 26133 52489 26133 52490 26136 52490 26137 52490 26133 52491 26137 52491 26141 52491 26141 52492 26137 52492 26138 52492 26142 52493 26148 52493 26147 52493 26133 52494 26146 52494 26139 52494 26139 52495 26146 52495 26145 52495 26139 52496 26145 52496 26140 52496 26134 52497 26141 52497 26142 52497 26134 52498 26142 52498 26143 52498 26143 52499 26142 52499 26147 52499 26143 52500 26147 52500 26145 52500 26145 52501 26147 52501 26144 52501 26145 52502 26144 52502 26140 52502 26134 52503 26143 52503 26132 52503 26132 52504 26143 52504 26145 52504 26132 52505 26145 52505 26146 52505 26140 52506 26136 52506 26139 52506 26139 52507 26136 52507 26135 52507 26142 52508 26138 52508 26148 52508 26148 52509 26138 52509 26137 52509 26141 52510 26138 52510 26142 52510 26144 52511 26147 52511 26140 52511 26140 52512 26147 52512 26148 52512 26140 52513 26148 52513 26136 52513 26136 52514 26148 52514 26137 52514 26135 52515 26133 52515 26139 52515 26153 52516 26157 52516 26149 52516 26153 52517 26150 52517 26162 52517 26151 52518 26150 52518 26153 52518 26149 52519 26151 52519 26153 52519 26153 52520 26161 52520 26152 52520 26154 52521 26161 52521 26153 52521 26162 52522 26154 52522 26153 52522 26153 52523 26155 52523 26156 52523 26159 52524 26155 52524 26153 52524 26152 52525 26159 52525 26153 52525 26153 52526 26160 52526 26157 52526 26158 52527 26160 52527 26153 52527 26156 52528 26158 52528 26153 52528 26152 52529 26161 52529 26160 52529 26161 52530 26154 52530 26162 52530 26159 52531 26152 52531 26155 52531 26155 52532 26152 52532 26160 52532 26155 52533 26160 52533 26156 52533 26156 52534 26160 52534 26158 52534 26157 52535 26160 52535 26149 52535 26149 52536 26160 52536 26161 52536 26149 52537 26161 52537 26151 52537 26151 52538 26161 52538 26162 52538 26151 52539 26162 52539 26150 52539 26174 52540 26163 52540 26164 52540 26174 52541 26168 52541 26165 52541 26166 52542 26168 52542 26174 52542 26164 52543 26166 52543 26174 52543 26174 52544 26169 52544 26171 52544 26167 52545 26169 52545 26174 52545 26165 52546 26167 52546 26174 52546 26172 52547 26168 52547 26166 52547 26165 52548 26168 52548 26167 52548 26167 52549 26168 52549 26172 52549 26167 52550 26172 52550 26169 52550 26170 52551 26175 52551 26172 52551 26172 52552 26175 52552 26171 52552 26172 52553 26171 52553 26169 52553 26176 52554 26173 52554 26163 52554 26163 52555 26173 52555 26172 52555 26163 52556 26172 52556 26164 52556 26164 52557 26172 52557 26166 52557 26174 52558 26170 52558 26172 52558 26175 52559 26170 52559 26174 52559 26171 52560 26175 52560 26174 52560 26174 52561 26176 52561 26163 52561 26173 52562 26176 52562 26174 52562 26172 52563 26173 52563 26174 52563 26203 52564 26177 52564 26185 52564 26185 52565 26177 52565 26187 52565 26185 52566 26187 52566 26178 52566 26178 52567 26187 52567 26180 52567 26178 52568 26180 52568 26179 52568 26179 52569 26180 52569 26181 52569 26179 52570 26181 52570 26182 52570 26182 52571 26181 52571 26193 52571 26182 52572 26193 52572 26183 52572 26183 52573 26193 52573 26192 52573 26183 52574 26192 52574 26186 52574 26186 52575 26192 52575 26184 52575 26186 52576 26184 52576 26194 52576 26194 52577 26184 52577 26198 52577 26196 52578 26203 52578 26185 52578 26196 52579 26179 52579 26182 52579 26178 52580 26179 52580 26196 52580 26185 52581 26178 52581 26196 52581 26196 52582 26186 52582 26194 52582 26183 52583 26186 52583 26196 52583 26182 52584 26183 52584 26196 52584 26187 52585 26177 52585 26191 52585 26188 52586 26201 52586 26189 52586 26181 52587 26180 52587 26193 52587 26193 52588 26180 52588 26187 52588 26189 52589 26190 52589 26188 52589 26188 52590 26190 52590 26198 52590 26188 52591 26198 52591 26191 52591 26191 52592 26198 52592 26184 52592 26191 52593 26184 52593 26187 52593 26187 52594 26184 52594 26192 52594 26187 52595 26192 52595 26193 52595 26196 52596 26199 52596 26200 52596 26195 52597 26199 52597 26196 52597 26194 52598 26195 52598 26196 52598 26196 52599 26202 52599 26203 52599 26197 52600 26202 52600 26196 52600 26200 52601 26197 52601 26196 52601 26194 52602 26198 52602 26195 52602 26195 52603 26198 52603 26190 52603 26195 52604 26190 52604 26199 52604 26199 52605 26190 52605 26189 52605 26199 52606 26189 52606 26200 52606 26200 52607 26189 52607 26201 52607 26200 52608 26201 52608 26197 52608 26197 52609 26201 52609 26188 52609 26197 52610 26188 52610 26202 52610 26202 52611 26188 52611 26191 52611 26202 52612 26191 52612 26203 52612 26203 52613 26191 52613 26177 52613 26205 52614 26213 52614 26204 52614 26204 52615 26213 52615 26232 52615 26204 52616 26232 52616 26239 52616 26207 52617 26215 52617 26218 52617 26218 52618 26215 52618 26206 52618 26218 52619 26206 52619 26205 52619 26205 52620 26206 52620 26214 52620 26205 52621 26214 52621 26213 52621 26207 52622 26218 52622 26208 52622 26208 52623 26218 52623 26209 52623 26208 52624 26209 52624 26210 52624 26210 52625 26209 52625 26220 52625 26210 52626 26220 52626 26217 52626 26217 52627 26220 52627 26211 52627 26217 52628 26211 52628 26212 52628 26212 52629 26211 52629 26235 52629 26212 52630 26235 52630 26216 52630 26227 52631 26232 52631 26213 52631 26214 52632 26206 52632 26227 52632 26215 52633 26207 52633 26227 52633 26208 52634 26210 52634 26227 52634 26227 52635 26212 52635 26216 52635 26217 52636 26212 52636 26227 52636 26210 52637 26217 52637 26227 52637 26207 52638 26208 52638 26227 52638 26206 52639 26215 52639 26227 52639 26213 52640 26214 52640 26227 52640 26205 52641 26204 52641 26218 52641 26218 52642 26204 52642 26219 52642 26209 52643 26218 52643 26220 52643 26220 52644 26218 52644 26219 52644 26220 52645 26219 52645 26211 52645 26211 52646 26219 52646 26235 52646 26223 52647 26221 52647 26222 52647 26204 52648 26239 52648 26219 52648 26219 52649 26239 52649 26223 52649 26219 52650 26223 52650 26224 52650 26224 52651 26223 52651 26222 52651 26227 52652 26216 52652 26225 52652 26226 52653 26234 52653 26227 52653 26237 52654 26236 52654 26227 52654 26228 52655 26229 52655 26227 52655 26230 52656 26233 52656 26227 52656 26227 52657 26231 52657 26232 52657 26238 52658 26231 52658 26227 52658 26233 52659 26238 52659 26227 52659 26229 52660 26230 52660 26227 52660 26236 52661 26228 52661 26227 52661 26234 52662 26237 52662 26227 52662 26225 52663 26226 52663 26227 52663 26216 52664 26235 52664 26225 52664 26225 52665 26235 52665 26219 52665 26224 52666 26234 52666 26219 52666 26219 52667 26234 52667 26226 52667 26219 52668 26226 52668 26225 52668 26229 52669 26228 52669 26222 52669 26222 52670 26228 52670 26236 52670 26222 52671 26236 52671 26224 52671 26224 52672 26236 52672 26237 52672 26224 52673 26237 52673 26234 52673 26229 52674 26222 52674 26230 52674 26230 52675 26222 52675 26221 52675 26230 52676 26221 52676 26233 52676 26233 52677 26221 52677 26223 52677 26233 52678 26223 52678 26238 52678 26238 52679 26223 52679 26231 52679 26231 52680 26223 52680 26239 52680 26231 52681 26239 52681 26232 52681 26240 52682 26242 52682 26241 52682 26241 52683 26242 52683 26243 52683 26241 52684 26244 52684 26240 52684 26240 52685 26244 52685 26246 52685 26241 52686 26243 52686 26244 52686 26244 52687 26243 52687 26245 52687 26247 52688 26245 52688 26242 52688 26242 52689 26245 52689 26243 52689 26244 52690 26245 52690 26246 52690 26246 52691 26245 52691 26247 52691 26246 52692 26247 52692 26240 52692 26240 52693 26247 52693 26242 52693 26248 52694 26254 52694 26249 52694 26249 52695 26254 52695 26252 52695 26252 52696 26254 52696 26251 52696 26251 52697 26254 52697 26255 52697 26251 52698 26255 52698 26250 52698 26250 52699 26255 52699 26253 52699 26251 52700 26250 52700 26252 52700 26252 52701 26250 52701 26249 52701 26250 52702 26253 52702 26249 52702 26249 52703 26253 52703 26248 52703 26248 52704 26253 52704 26254 52704 26254 52705 26253 52705 26255 52705 26261 52706 26257 52706 26256 52706 26256 52707 26257 52707 26258 52707 26256 52708 26258 52708 26259 52708 26259 52709 26258 52709 26262 52709 26262 52710 26263 52710 26259 52710 26259 52711 26263 52711 26260 52711 26260 52712 26261 52712 26259 52712 26259 52713 26261 52713 26256 52713 26260 52714 26263 52714 26261 52714 26261 52715 26263 52715 26257 52715 26258 52716 26257 52716 26262 52716 26262 52717 26257 52717 26263 52717 26270 52718 26268 52718 26264 52718 26264 52719 26268 52719 26265 52719 26264 52720 26265 52720 26266 52720 26266 52721 26265 52721 26271 52721 26270 52722 26264 52722 26267 52722 26267 52723 26264 52723 26266 52723 26268 52724 26270 52724 26269 52724 26269 52725 26270 52725 26267 52725 26269 52726 26267 52726 26271 52726 26271 52727 26267 52727 26266 52727 26271 52728 26265 52728 26269 52728 26269 52729 26265 52729 26268 52729 26274 52730 26275 52730 26273 52730 26273 52731 26275 52731 26278 52731 26276 52732 26274 52732 26272 52732 26272 52733 26274 52733 26273 52733 26272 52734 26273 52734 26279 52734 26279 52735 26273 52735 26278 52735 26279 52736 26277 52736 26272 52736 26272 52737 26277 52737 26276 52737 26274 52738 26276 52738 26275 52738 26275 52739 26276 52739 26277 52739 26275 52740 26277 52740 26278 52740 26278 52741 26277 52741 26279 52741 26280 52742 26282 52742 26281 52742 26281 52743 26282 52743 26286 52743 26282 52744 26283 52744 26286 52744 26286 52745 26283 52745 26285 52745 26285 52746 26283 52746 26284 52746 26284 52747 26283 52747 26287 52747 26285 52748 26284 52748 26286 52748 26286 52749 26284 52749 26281 52749 26281 52750 26284 52750 26280 52750 26280 52751 26284 52751 26287 52751 26280 52752 26287 52752 26282 52752 26282 52753 26287 52753 26283 52753 26288 52754 26291 52754 26294 52754 26294 52755 26291 52755 26292 52755 26288 52756 26295 52756 26291 52756 26291 52757 26295 52757 26289 52757 26293 52758 26289 52758 26290 52758 26290 52759 26289 52759 26295 52759 26291 52760 26289 52760 26292 52760 26292 52761 26289 52761 26293 52761 26292 52762 26293 52762 26294 52762 26294 52763 26293 52763 26290 52763 26290 52764 26295 52764 26294 52764 26294 52765 26295 52765 26288 52765 26300 52766 26302 52766 26296 52766 26296 52767 26302 52767 26303 52767 26296 52768 26303 52768 26301 52768 26301 52769 26303 52769 26297 52769 26298 52770 26299 52770 26300 52770 26300 52771 26299 52771 26302 52771 26296 52772 26301 52772 26300 52772 26300 52773 26301 52773 26298 52773 26301 52774 26297 52774 26298 52774 26298 52775 26297 52775 26299 52775 26299 52776 26297 52776 26302 52776 26302 52777 26297 52777 26303 52777 26306 52778 26312 52778 26304 52778 26309 52779 26312 52779 26306 52779 26310 52780 26309 52780 26306 52780 26306 52781 26305 52781 26308 52781 26311 52782 26305 52782 26306 52782 26304 52783 26311 52783 26306 52783 26309 52784 26307 52784 26308 52784 26309 52785 26310 52785 26316 52785 26304 52786 26312 52786 26311 52786 26311 52787 26312 52787 26309 52787 26311 52788 26309 52788 26305 52788 26305 52789 26309 52789 26308 52789 26313 52790 26307 52790 26315 52790 26315 52791 26307 52791 26309 52791 26315 52792 26309 52792 26314 52792 26314 52793 26309 52793 26316 52793 26306 52794 26313 52794 26315 52794 26307 52795 26313 52795 26306 52795 26308 52796 26307 52796 26306 52796 26306 52797 26316 52797 26310 52797 26314 52798 26316 52798 26306 52798 26315 52799 26314 52799 26306 52799 26317 52800 26318 52800 26319 52800 26319 52801 26318 52801 26321 52801 26320 52802 26322 52802 26321 52802 26321 52803 26322 52803 26327 52803 26321 52804 26327 52804 26319 52804 26319 52805 26327 52805 26324 52805 26321 52806 26318 52806 26323 52806 26323 52807 26318 52807 26329 52807 26323 52808 26329 52808 26326 52808 26326 52809 26329 52809 26328 52809 26329 52810 26318 52810 26332 52810 26332 52811 26318 52811 26317 52811 26326 52812 26322 52812 26323 52812 26323 52813 26322 52813 26320 52813 26331 52814 26324 52814 26325 52814 26325 52815 26324 52815 26327 52815 26319 52816 26324 52816 26331 52816 26327 52817 26322 52817 26326 52817 26328 52818 26330 52818 26326 52818 26326 52819 26330 52819 26325 52819 26326 52820 26325 52820 26327 52820 26320 52821 26321 52821 26323 52821 26331 52822 26325 52822 26330 52822 26328 52823 26329 52823 26330 52823 26330 52824 26329 52824 26332 52824 26330 52825 26332 52825 26331 52825 26331 52826 26332 52826 26317 52826 26331 52827 26317 52827 26319 52827 26339 52828 26333 52828 26335 52828 26335 52829 26333 52829 26346 52829 26342 52830 26333 52830 26339 52830 26338 52831 26336 52831 26334 52831 26334 52832 26336 52832 26335 52832 26334 52833 26335 52833 26349 52833 26349 52834 26335 52834 26346 52834 26349 52835 26346 52835 26345 52835 26344 52836 26343 52836 26350 52836 26339 52837 26335 52837 26336 52837 26334 52838 26337 52838 26338 52838 26338 52839 26337 52839 26348 52839 26338 52840 26348 52840 26336 52840 26336 52841 26348 52841 26347 52841 26336 52842 26347 52842 26339 52842 26339 52843 26347 52843 26340 52843 26339 52844 26340 52844 26342 52844 26340 52845 26341 52845 26342 52845 26342 52846 26341 52846 26343 52846 26344 52847 26345 52847 26343 52847 26343 52848 26345 52848 26346 52848 26343 52849 26346 52849 26342 52849 26342 52850 26346 52850 26333 52850 26343 52851 26341 52851 26350 52851 26350 52852 26341 52852 26337 52852 26350 52853 26337 52853 26349 52853 26349 52854 26337 52854 26334 52854 26347 52855 26348 52855 26340 52855 26340 52856 26348 52856 26337 52856 26340 52857 26337 52857 26341 52857 26349 52858 26345 52858 26350 52858 26350 52859 26345 52859 26344 52859 26362 52860 26352 52860 26360 52860 26360 52861 26352 52861 26351 52861 26360 52862 26351 52862 26356 52862 26366 52863 26365 52863 26352 52863 26352 52864 26365 52864 26353 52864 26352 52865 26353 52865 26351 52865 26351 52866 26353 52866 26364 52866 26357 52867 26363 52867 26354 52867 26352 52868 26362 52868 26367 52868 26367 52869 26362 52869 26361 52869 26367 52870 26361 52870 26355 52870 26356 52871 26351 52871 26357 52871 26356 52872 26357 52872 26359 52872 26359 52873 26357 52873 26354 52873 26359 52874 26354 52874 26361 52874 26361 52875 26354 52875 26358 52875 26361 52876 26358 52876 26355 52876 26356 52877 26359 52877 26360 52877 26360 52878 26359 52878 26361 52878 26360 52879 26361 52879 26362 52879 26355 52880 26365 52880 26367 52880 26367 52881 26365 52881 26366 52881 26357 52882 26364 52882 26363 52882 26363 52883 26364 52883 26353 52883 26351 52884 26364 52884 26357 52884 26353 52885 26365 52885 26355 52885 26358 52886 26354 52886 26355 52886 26355 52887 26354 52887 26363 52887 26355 52888 26363 52888 26353 52888 26366 52889 26352 52889 26367 52889 26368 52890 26370 52890 26377 52890 26377 52891 26370 52891 26371 52891 26377 52892 26371 52892 26375 52892 26384 52893 26369 52893 26370 52893 26370 52894 26369 52894 26380 52894 26370 52895 26380 52895 26371 52895 26371 52896 26380 52896 26381 52896 26372 52897 26379 52897 26373 52897 26370 52898 26368 52898 26374 52898 26374 52899 26368 52899 26376 52899 26374 52900 26376 52900 26383 52900 26375 52901 26371 52901 26372 52901 26375 52902 26372 52902 26378 52902 26378 52903 26372 52903 26373 52903 26378 52904 26373 52904 26376 52904 26376 52905 26373 52905 26382 52905 26376 52906 26382 52906 26383 52906 26375 52907 26378 52907 26377 52907 26377 52908 26378 52908 26376 52908 26377 52909 26376 52909 26368 52909 26383 52910 26369 52910 26374 52910 26374 52911 26369 52911 26384 52911 26372 52912 26381 52912 26379 52912 26379 52913 26381 52913 26380 52913 26371 52914 26381 52914 26372 52914 26380 52915 26369 52915 26383 52915 26382 52916 26373 52916 26383 52916 26383 52917 26373 52917 26379 52917 26383 52918 26379 52918 26380 52918 26384 52919 26370 52919 26374 52919 26390 52920 26400 52920 26395 52920 26395 52921 26400 52921 26385 52921 26395 52922 26385 52922 26386 52922 26387 52923 26388 52923 26400 52923 26400 52924 26388 52924 26396 52924 26400 52925 26396 52925 26385 52925 26385 52926 26396 52926 26389 52926 26392 52927 26399 52927 26397 52927 26400 52928 26390 52928 26401 52928 26401 52929 26390 52929 26391 52929 26401 52930 26391 52930 26398 52930 26386 52931 26385 52931 26392 52931 26386 52932 26392 52932 26394 52932 26394 52933 26392 52933 26397 52933 26394 52934 26397 52934 26391 52934 26391 52935 26397 52935 26393 52935 26391 52936 26393 52936 26398 52936 26386 52937 26394 52937 26395 52937 26395 52938 26394 52938 26391 52938 26395 52939 26391 52939 26390 52939 26398 52940 26388 52940 26401 52940 26401 52941 26388 52941 26387 52941 26392 52942 26389 52942 26399 52942 26399 52943 26389 52943 26396 52943 26385 52944 26389 52944 26392 52944 26396 52945 26388 52945 26398 52945 26393 52946 26397 52946 26398 52946 26398 52947 26397 52947 26399 52947 26398 52948 26399 52948 26396 52948 26387 52949 26400 52949 26401 52949 26411 52950 26402 52950 26403 52950 26403 52951 26402 52951 26404 52951 26409 52952 26402 52952 26411 52952 26404 52953 26418 52953 26405 52953 26413 52954 26412 52954 26405 52954 26405 52955 26412 52955 26403 52955 26405 52956 26403 52956 26404 52956 26407 52957 26408 52957 26417 52957 26406 52958 26408 52958 26415 52958 26415 52959 26408 52959 26409 52959 26415 52960 26409 52960 26410 52960 26407 52961 26418 52961 26408 52961 26408 52962 26418 52962 26404 52962 26408 52963 26404 52963 26409 52963 26409 52964 26404 52964 26402 52964 26411 52965 26403 52965 26412 52965 26408 52966 26406 52966 26417 52966 26417 52967 26406 52967 26416 52967 26417 52968 26416 52968 26405 52968 26410 52969 26409 52969 26411 52969 26410 52970 26411 52970 26414 52970 26414 52971 26411 52971 26412 52971 26414 52972 26412 52972 26416 52972 26416 52973 26412 52973 26413 52973 26416 52974 26413 52974 26405 52974 26410 52975 26414 52975 26415 52975 26415 52976 26414 52976 26416 52976 26415 52977 26416 52977 26406 52977 26405 52978 26418 52978 26417 52978 26417 52979 26418 52979 26407 52979 26432 52980 26419 52980 26421 52980 26421 52981 26419 52981 26434 52981 26431 52982 26423 52982 26420 52982 26433 52983 26432 52983 26420 52983 26420 52984 26432 52984 26421 52984 26420 52985 26421 52985 26431 52985 26431 52986 26421 52986 26424 52986 26425 52987 26435 52987 26427 52987 26420 52988 26423 52988 26422 52988 26422 52989 26423 52989 26430 52989 26422 52990 26430 52990 26429 52990 26424 52991 26421 52991 26425 52991 26424 52992 26425 52992 26426 52992 26426 52993 26425 52993 26427 52993 26426 52994 26427 52994 26430 52994 26430 52995 26427 52995 26428 52995 26430 52996 26428 52996 26429 52996 26430 52997 26423 52997 26426 52997 26426 52998 26423 52998 26431 52998 26426 52999 26431 52999 26424 52999 26429 53000 26432 53000 26422 53000 26422 53001 26432 53001 26433 53001 26425 53002 26434 53002 26435 53002 26435 53003 26434 53003 26419 53003 26421 53004 26434 53004 26425 53004 26428 53005 26427 53005 26429 53005 26429 53006 26427 53006 26435 53006 26429 53007 26435 53007 26432 53007 26432 53008 26435 53008 26419 53008 26433 53009 26420 53009 26422 53009 26438 53010 26452 53010 26440 53010 26440 53011 26452 53011 26436 53011 26439 53012 26449 53012 26437 53012 26450 53013 26438 53013 26437 53013 26437 53014 26438 53014 26440 53014 26437 53015 26440 53015 26439 53015 26439 53016 26440 53016 26448 53016 26441 53017 26442 53017 26446 53017 26437 53018 26449 53018 26443 53018 26443 53019 26449 53019 26444 53019 26443 53020 26444 53020 26451 53020 26448 53021 26440 53021 26441 53021 26448 53022 26441 53022 26445 53022 26445 53023 26441 53023 26446 53023 26445 53024 26446 53024 26444 53024 26444 53025 26446 53025 26447 53025 26444 53026 26447 53026 26451 53026 26448 53027 26445 53027 26439 53027 26439 53028 26445 53028 26444 53028 26439 53029 26444 53029 26449 53029 26451 53030 26438 53030 26443 53030 26443 53031 26438 53031 26450 53031 26441 53032 26436 53032 26442 53032 26442 53033 26436 53033 26452 53033 26440 53034 26436 53034 26441 53034 26452 53035 26438 53035 26451 53035 26447 53036 26446 53036 26451 53036 26451 53037 26446 53037 26442 53037 26451 53038 26442 53038 26452 53038 26450 53039 26437 53039 26443 53039 26470 53040 26459 53040 26468 53040 26468 53041 26459 53041 26467 53041 26453 53042 26461 53042 26467 53042 26467 53043 26461 53043 26466 53043 26467 53044 26466 53044 26468 53044 26468 53045 26466 53045 26463 53045 26467 53046 26459 53046 26460 53046 26460 53047 26459 53047 26454 53047 26460 53048 26454 53048 26465 53048 26469 53049 26455 53049 26456 53049 26456 53050 26455 53050 26457 53050 26456 53051 26457 53051 26454 53051 26454 53052 26457 53052 26458 53052 26454 53053 26458 53053 26465 53053 26456 53054 26454 53054 26469 53054 26469 53055 26454 53055 26459 53055 26469 53056 26459 53056 26470 53056 26465 53057 26461 53057 26460 53057 26460 53058 26461 53058 26453 53058 26464 53059 26463 53059 26462 53059 26462 53060 26463 53060 26466 53060 26468 53061 26463 53061 26464 53061 26465 53062 26458 53062 26457 53062 26466 53063 26461 53063 26462 53063 26462 53064 26461 53064 26465 53064 26462 53065 26465 53065 26455 53065 26455 53066 26465 53066 26457 53066 26453 53067 26467 53067 26460 53067 26462 53068 26455 53068 26464 53068 26464 53069 26455 53069 26469 53069 26464 53070 26469 53070 26468 53070 26468 53071 26469 53071 26470 53071 26480 53072 26479 53072 26471 53072 26471 53073 26479 53073 26472 53073 26482 53074 26481 53074 26472 53074 26472 53075 26481 53075 26473 53075 26472 53076 26473 53076 26471 53076 26471 53077 26473 53077 26484 53077 26472 53078 26479 53078 26474 53078 26474 53079 26479 53079 26475 53079 26474 53080 26475 53080 26478 53080 26486 53081 26476 53081 26475 53081 26475 53082 26476 53082 26477 53082 26475 53083 26477 53083 26478 53083 26475 53084 26479 53084 26486 53084 26486 53085 26479 53085 26480 53085 26478 53086 26481 53086 26474 53086 26474 53087 26481 53087 26482 53087 26485 53088 26484 53088 26483 53088 26483 53089 26484 53089 26473 53089 26471 53090 26484 53090 26485 53090 26477 53091 26476 53091 26478 53091 26478 53092 26476 53092 26483 53092 26478 53093 26483 53093 26481 53093 26481 53094 26483 53094 26473 53094 26482 53095 26472 53095 26474 53095 26480 53096 26471 53096 26485 53096 26483 53097 26476 53097 26485 53097 26485 53098 26476 53098 26486 53098 26485 53099 26486 53099 26480 53099 26487 53100 26492 53100 26496 53100 26489 53101 26502 53101 26504 53101 26499 53102 26488 53102 26504 53102 26504 53103 26488 53103 26490 53103 26504 53104 26490 53104 26489 53104 26489 53105 26490 53105 26500 53105 26489 53106 26500 53106 26501 53106 26500 53107 26491 53107 26501 53107 26501 53108 26491 53108 26492 53108 26487 53109 26493 53109 26492 53109 26492 53110 26493 53110 26494 53110 26492 53111 26494 53111 26501 53111 26501 53112 26494 53112 26495 53112 26492 53113 26491 53113 26496 53113 26496 53114 26491 53114 26497 53114 26496 53115 26497 53115 26498 53115 26488 53116 26499 53116 26497 53116 26497 53117 26499 53117 26503 53117 26497 53118 26503 53118 26498 53118 26488 53119 26497 53119 26490 53119 26490 53120 26497 53120 26491 53120 26490 53121 26491 53121 26500 53121 26498 53122 26493 53122 26496 53122 26496 53123 26493 53123 26487 53123 26489 53124 26495 53124 26502 53124 26502 53125 26495 53125 26494 53125 26501 53126 26495 53126 26489 53126 26502 53127 26494 53127 26493 53127 26499 53128 26504 53128 26503 53128 26503 53129 26504 53129 26502 53129 26503 53130 26502 53130 26498 53130 26498 53131 26502 53131 26493 53131

+
+
+
+
+ + + + + + + + + + + + + + +
diff --git a/robots/b1_description/meshes/trunk.dae b/robots/b1_description/meshes/trunk.dae new file mode 100644 index 0000000..ae928a6 --- /dev/null +++ b/robots/b1_description/meshes/trunk.dae @@ -0,0 +1,63 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + 周四 2月 24 03:20:03 2022 + 周四 2月 24 03:20:03 2022 + + + + + + + + + 0.0633495 0.149472 0.0241369 0.0633682 0.149438 0.024133 0.0636669 0.149608 0.0235659 0.0663423 0.149274 0.0247781 0.06549 0.149781 0.0231412 0.0660704 0.149714 0.0235231 0.064826 0.14982 0.0229928 0.0636316 0.149669 0.0235521 0.0633246 0.149502 0.0241381 0.0655162 0.149826 0.0230966 0.064826 0.149866 0.0229427 0.0641368 0.149826 0.0230969 0.0644788 0.149882 0.02292 0.0637142 0.149784 0.0233006 0.0635833 0.149714 0.023523 0.0658037 0.149592 0.023397 0.0659695 0.149542 0.0235633 0.0659758 0.149575 0.0235665 0.0662262 0.149409 0.023995 0.0662682 0.14937 0.0241199 0.0648261 0.14976 0.0230248 0.0654637 0.149688 0.0231742 0.0659868 0.149607 0.023566 0.0663242 0.149239 0.0247652 0.0633802 0.149404 0.0241268 0.0633269 0.149235 0.0245353 0.0633424 0.149306 0.0243199 0.0633857 0.14937 0.024119 0.0636111 0.149514 0.0236564 0.0636778 0.149575 0.0235665 0.0641893 0.149688 0.0231744 0.0633391 0.149202 0.0247529 0.0641935 0.149657 0.0231753 0.0648268 0.149697 0.023035 0.0663293 0.149501 0.0241391 0.0663043 0.149471 0.0241379 0.0660221 0.149669 0.0235522 0.0663924 0.149545 0.0241332 0.0663877 0.149619 0.0239147 0.0632615 0.149545 0.0241322 0.064163 0.149781 0.0231415 0.0641828 0.14972 0.0231686 0.0654702 0.149721 0.0231684 0.0662737 0.149404 0.0241278 0.0662856 0.149438 0.024134 0.0663268 0.149235 0.0245358 0.0663125 0.149166 0.024742 0.066126 0.148981 0.0252847 0.065578 0.148788 0.0258335 0.0653634 0.148751 0.0259358 0.0640758 0.148788 0.0258333 0.0638361 0.14889 0.025667 0.0635054 0.149034 0.0252532 0.0634992 0.149072 0.0252684 0.0633294 0.149239 0.0247652 0.0634845 0.14911 0.0252877 0.0634613 0.149142 0.0253099 0.0633113 0.149274 0.0247781 0.0632852 0.149305 0.024791 0.0632162 0.149347 0.0248131 0.0633968 0.149182 0.0253567 0.0637552 0.149042 0.025806 0.0638334 0.148931 0.025683 0.063504 0.148996 0.0252424 0.064296 0.148792 0.0259428 0.0638233 0.14897 0.0257066 0.063806 0.149004 0.0257366 0.0642954 0.148835 0.0259582 0.0642905 0.148876 0.025984 0.0642812 0.14891 0.0260192 0.0648287 0.148914 0.0262101 0.064253 0.148947 0.0261052 0.064716 0.148907 0.0262922 0.0648268 0.148715 0.026035 0.0648285 0.148757 0.0260396 0.0653613 0.148836 0.0259571 0.0653662 0.148876 0.0259829 0.0648285 0.148801 0.0260546 0.0648285 0.148843 0.026081 0.0653755 0.148911 0.0260181 0.0648286 0.148877 0.026118 0.0654039 0.148948 0.0261039 0.0648666 0.148906 0.0262954 0.0656706 0.148977 0.0260712 0.0659005 0.149043 0.0258041 0.0658497 0.149004 0.0257348 0.0653606 0.148793 0.0259416 0.0658195 0.148891 0.0256652 0.0658229 0.148851 0.0256566 0.0661554 0.149073 0.0252666 0.0658223 0.148932 0.0256812 0.0658323 0.148971 0.0257048 0.0663145 0.149202 0.0247529 0.0661505 0.148996 0.0252405 0.0661492 0.149034 0.0252514 0.0663684 0.149305 0.024791 0.0661701 0.14911 0.0252858 0.0664374 0.149347 0.0248131 0.0661933 0.149143 0.025308 0.0662578 0.149183 0.0253547 0.0503684 0.149305 0.024791 0.0503293 0.149501 0.0241391 0.0504374 0.149347 0.0248131 0.0500221 0.149669 0.0235522 0.0500704 0.149714 0.0235231 0.048826 0.149866 0.0229427 0.0495162 0.149826 0.0230966 0.0498914 0.149795 0.0232604 0.0484788 0.149882 0.02292 0.0481368 0.149826 0.0230969 0.0477142 0.149784 0.0233006 0.0475833 0.149714 0.023523 0.0472615 0.149545 0.0241322 0.0499758 0.149575 0.0235665 0.0494637 0.149688 0.0231742 0.0502737 0.149404 0.0241278 0.0503242 0.149239 0.0247652 0.0473391 0.149202 0.0247529 0.0473269 0.149235 0.0245353 0.0473424 0.149306 0.0243199 0.0473857 0.14937 0.024119 0.0476111 0.149514 0.0236564 0.048076 0.149639 0.0232366 0.0481828 0.14972 0.0231686 0.0476778 0.149575 0.0235665 0.0476669 0.149608 0.0235659 0.0473802 0.149404 0.0241268 0.0473682 0.149438 0.024133 0.0481893 0.149688 0.0231744 0.0494596 0.149657 0.023175 0.0495781 0.149639 0.0232369 0.0503924 0.149545 0.0241332 0.0505105 0.149358 0.0248265 0.050521 0.149386 0.0247317 0.0503423 0.149274 0.0247781 0.0503043 0.149471 0.0241379 0.0503877 0.149619 0.0239147 0.0473246 0.149502 0.0241381 0.0473495 0.149472 0.0241369 0.0476316 0.149669 0.0235521 0.048163 0.149781 0.0231415 0.048826 0.14982 0.0229928 0.0488261 0.14976 0.0230248 0.04949 0.149781 0.0231412 0.0494702 0.149721 0.0231684 0.0502856 0.149438 0.024134 0.0499868 0.149607 0.023566 0.0503145 0.149202 0.0247529 0.0493634 0.148751 0.0259358 0.0493606 0.148793 0.0259416 0.0473411 0.149166 0.024742 0.0474992 0.149072 0.0252684 0.0473294 0.149239 0.0247652 0.0473113 0.149274 0.0247781 0.0472852 0.149305 0.024791 0.0472162 0.149347 0.0248131 0.0473968 0.149182 0.0253567 0.0474613 0.149142 0.0253099 0.0474845 0.14911 0.0252877 0.0478361 0.14889 0.025667 0.0475054 0.149034 0.0252532 0.0475276 0.148981 0.0252847 0.047504 0.148996 0.0252424 0.0480758 0.148788 0.0258333 0.048296 0.148792 0.0259428 0.0478334 0.148931 0.025683 0.0482905 0.148876 0.025984 0.0478234 0.14897 0.0257066 0.0482812 0.14891 0.0260192 0.048253 0.148947 0.0261052 0.047806 0.149004 0.0257366 0.0477552 0.149042 0.025806 0.0474604 0.149122 0.0256052 0.0488285 0.148757 0.0260396 0.0482954 0.148835 0.0259582 0.0488286 0.148877 0.026118 0.0479905 0.148976 0.0260752 0.0493613 0.148836 0.0259571 0.0488285 0.148801 0.0260546 0.0488285 0.148843 0.026081 0.0494039 0.148948 0.0261039 0.0488287 0.148914 0.0262101 0.0496706 0.148977 0.0260712 0.0499005 0.149043 0.0258041 0.0493755 0.148911 0.0260181 0.0493662 0.148876 0.0259829 0.0498323 0.148971 0.0257048 0.0498229 0.148851 0.0256566 0.0501505 0.148996 0.0252405 0.050126 0.148981 0.0252847 0.0501554 0.149073 0.0252666 0.0498195 0.148891 0.0256652 0.0498223 0.148932 0.0256812 0.0501701 0.14911 0.0252858 0.0501933 0.149143 0.025308 0.0498497 0.149004 0.0257348 0.0502578 0.149183 0.0253547 0.0501918 0.149122 0.0256076 0.0501492 0.149034 0.0252514 0.0335162 0.149826 0.0230966 0.0321368 0.149826 0.0230969 0.032826 0.149866 0.0229427 0.0324788 0.149882 0.02292 0.0315833 0.149714 0.023523 0.0312386 0.149601 0.0239821 0.0312615 0.149545 0.0241322 0.0335781 0.149639 0.0232369 0.0339695 0.149542 0.0235633 0.0341268 0.149474 0.0237867 0.0342737 0.149404 0.0241278 0.0342262 0.149409 0.023995 0.0342682 0.14937 0.0241199 0.0334637 0.149688 0.0231742 0.0339868 0.149607 0.023566 0.0339758 0.149575 0.0235665 0.0343242 0.149239 0.0247652 0.0342856 0.149438 0.024134 0.0313269 0.149235 0.0245353 0.0313424 0.149306 0.0243199 0.0313802 0.149404 0.0241268 0.0313857 0.14937 0.024119 0.0316111 0.149514 0.0236564 0.0321893 0.149688 0.0231744 0.0313294 0.149239 0.0247652 0.0313113 0.149274 0.0247781 0.0313495 0.149472 0.0241369 0.0321828 0.14972 0.0231686 0.0316669 0.149608 0.0235659 0.0313682 0.149438 0.024133 0.0316778 0.149575 0.0235665 0.0313391 0.149202 0.0247529 0.0321576 0.149652 0.0231926 0.0321935 0.149657 0.0231753 0.0328261 0.14976 0.0230248 0.0331271 0.149688 0.0230654 0.0334595 0.149657 0.023175 0.0343877 0.149619 0.0239147 0.0344374 0.149347 0.0248131 0.0343293 0.149501 0.0241391 0.0343043 0.149471 0.0241379 0.0340221 0.149669 0.0235522 0.0343924 0.149545 0.0241332 0.0340704 0.149714 0.0235231 0.0312162 0.149347 0.0248131 0.0313246 0.149502 0.0241381 0.0312852 0.149305 0.024791 0.0316316 0.149669 0.0235521 0.032163 0.149781 0.0231415 0.032826 0.14982 0.0229928 0.03349 0.149781 0.0231412 0.0334702 0.149721 0.0231684 0.0343268 0.149235 0.0245358 0.033578 0.148788 0.0258335 0.0318361 0.14889 0.025667 0.031504 0.148996 0.0252424 0.0315054 0.149034 0.0252532 0.0313411 0.149166 0.024742 0.0314845 0.14911 0.0252877 0.0314613 0.149142 0.0253099 0.0313968 0.149182 0.0253567 0.0317552 0.149042 0.025806 0.0318334 0.148931 0.025683 0.0314992 0.149072 0.0252684 0.0318327 0.14885 0.0256583 0.0315276 0.148981 0.0252847 0.0322932 0.14875 0.0259369 0.0320758 0.148788 0.0258333 0.032296 0.148792 0.0259428 0.0322954 0.148835 0.0259582 0.0318234 0.14897 0.0257066 0.031806 0.149004 0.0257366 0.0314604 0.149122 0.0256052 0.0328285 0.148757 0.0260396 0.0322905 0.148876 0.025984 0.0322812 0.14891 0.0260192 0.032253 0.148947 0.0261052 0.0328287 0.148914 0.0262101 0.032716 0.148907 0.0262922 0.0328268 0.148715 0.026035 0.0333606 0.148793 0.0259416 0.0333613 0.148836 0.0259571 0.0328285 0.148801 0.0260546 0.0328285 0.148843 0.026081 0.0333755 0.148911 0.0260181 0.0328286 0.148877 0.026118 0.0328665 0.148906 0.0262954 0.0334039 0.148948 0.0261039 0.0333662 0.148876 0.0259829 0.0338323 0.148971 0.0257048 0.034126 0.148981 0.0252847 0.0341492 0.149034 0.0252514 0.0338195 0.148891 0.0256652 0.0338223 0.148932 0.0256812 0.0341701 0.14911 0.0252858 0.0341933 0.149143 0.025308 0.0338497 0.149004 0.0257348 0.0342578 0.149183 0.0253547 0.0339005 0.149043 0.0258041 0.0343145 0.149202 0.0247529 0.0341554 0.149073 0.0252666 0.0343423 0.149274 0.0247781 0.0343684 0.149305 0.024791 0.0345105 0.149358 0.0248265 0.0183293 0.149501 0.0241391 0.0183684 0.149305 0.024791 0.0175162 0.149826 0.0230966 0.016826 0.14982 0.0229928 0.016826 0.149866 0.0229427 0.0161368 0.149826 0.0230969 0.0155833 0.149714 0.023523 0.0180704 0.149714 0.0235231 0.017174 0.149882 0.0229198 0.0164788 0.149882 0.02292 0.0157142 0.149784 0.0233006 0.0178037 0.149592 0.023397 0.0174637 0.149688 0.0231742 0.0179758 0.149575 0.0235665 0.0179695 0.149542 0.0235633 0.0181268 0.149474 0.0237867 0.0182262 0.149409 0.023995 0.0182682 0.14937 0.0241199 0.0174702 0.149721 0.0231684 0.0183145 0.149202 0.0247529 0.0156778 0.149575 0.0235665 0.0153411 0.149166 0.024742 0.0153269 0.149235 0.0245353 0.0153424 0.149306 0.0243199 0.0153802 0.149404 0.0241268 0.0153113 0.149274 0.0247781 0.0161828 0.14972 0.0231686 0.0153682 0.149438 0.024133 0.0161893 0.149688 0.0231744 0.0161935 0.149657 0.0231753 0.0168261 0.14976 0.0230248 0.0171271 0.149688 0.0230654 0.0183924 0.149545 0.0241332 0.0184374 0.149347 0.0248131 0.0183043 0.149471 0.0241379 0.0180221 0.149669 0.0235522 0.0152615 0.149545 0.0241322 0.0152852 0.149305 0.024791 0.0153246 0.149502 0.0241381 0.0153495 0.149472 0.0241369 0.0156669 0.149608 0.0235659 0.0156316 0.149669 0.0235521 0.016163 0.149781 0.0231415 0.01749 0.149781 0.0231412 0.0179868 0.149607 0.023566 0.0182856 0.149438 0.024134 0.0182737 0.149404 0.0241278 0.0183268 0.149235 0.0245358 0.0183125 0.149166 0.024742 0.0178229 0.148851 0.0256566 0.0153391 0.149202 0.0247529 0.0153294 0.149239 0.0247652 0.0154992 0.149072 0.0252684 0.0153968 0.149182 0.0253567 0.0152162 0.149347 0.0248131 0.015143 0.149358 0.0248265 0.0154613 0.149142 0.0253099 0.0157552 0.149042 0.025806 0.015806 0.149004 0.0257366 0.0154845 0.14911 0.0252877 0.0158234 0.14897 0.0257066 0.0158361 0.14889 0.025667 0.0155054 0.149034 0.0252532 0.0155276 0.148981 0.0252847 0.015504 0.148996 0.0252424 0.016296 0.148792 0.0259428 0.0162905 0.148876 0.025984 0.0158334 0.148931 0.025683 0.0159905 0.148976 0.0260752 0.0154604 0.149122 0.0256052 0.0162954 0.148835 0.0259582 0.0168285 0.148843 0.026081 0.0162812 0.14891 0.0260192 0.016253 0.148947 0.0261052 0.0173634 0.148751 0.0259358 0.0168285 0.148757 0.0260396 0.0168285 0.148801 0.0260546 0.0173755 0.148911 0.0260181 0.0168286 0.148877 0.026118 0.0168665 0.148906 0.0262954 0.0168287 0.148914 0.0262101 0.0174039 0.148948 0.0261039 0.0179005 0.149043 0.0258041 0.0178323 0.148971 0.0257048 0.0173662 0.148876 0.0259829 0.0173613 0.148836 0.0259571 0.0173606 0.148793 0.0259416 0.0178195 0.148891 0.0256652 0.0181492 0.149034 0.0252514 0.0178223 0.148932 0.0256812 0.0181554 0.149073 0.0252666 0.0178497 0.149004 0.0257348 0.0181918 0.149122 0.0256076 0.0181505 0.148996 0.0252405 0.0183242 0.149239 0.0247652 0.0183423 0.149274 0.0247781 0.0181701 0.14911 0.0252858 0.0181933 0.149143 0.025308 0.0182578 0.149183 0.0253547 0.0185105 0.149358 0.0248265 -0.0478123 0.150404 0.0180354 -0.0473257 0.150725 0.0180822 -0.0467516 0.151335 0.0112278 -0.0478123 0.150896 0.0112278 -0.0478123 0.150896 -0.0121577 -0.0473257 0.151221 -0.0121577 -0.0473257 0.151221 0.0112278 -0.0473257 0.146685 0.0320597 -0.0473257 0.149249 0.024794 -0.0478123 0.146384 0.0319362 -0.0472341 0.145124 0.0356839 -0.0478123 0.148937 0.0247014 -0.0467516 0.149358 -0.0257564 -0.0473257 0.150725 -0.0190121 -0.0478123 0.150404 -0.0189653 -0.0465949 0.143039 0.039752 -0.0459526 0.142971 0.0400625 -0.0449061 0.141831 0.0420521 -0.0434768 0.140778 0.0437775 -0.042794 0.140032 0.0448342 -0.0408743 0.139279 0.0459785 -0.0363729 0.138841 0.0467044 -0.0471508 0.144103 0.0377112 -0.0470249 0.142744 0.0397477 -0.0456703 0.141971 0.0416612 -0.0460521 0.141675 0.0417165 -0.0443999 0.140952 0.0433715 -0.0447228 0.140655 0.043477 -0.0410506 0.138981 0.0461563 -0.0387878 0.138479 0.0469155 -0.0386973 0.138777 0.0467178 -0.036373 0.138301 0.0471792 -0.0473257 0.149249 -0.0257239 -0.0473257 0.146685 -0.0329896 -0.0474542 0.145038 -0.036572 -0.0478123 0.146384 -0.0328661 0.118027 0.1386 0.0469746 -0.0363729 0.1386 0.0469746 -0.036373 0.138841 -0.0476343 -0.036373 0.1386 -0.0479045 -0.0382823 0.138969 -0.0474499 -0.041931 0.139976 -0.0459545 -0.0433187 0.140682 -0.0448587 -0.0464502 0.143814 -0.0394255 -0.0471508 0.144103 -0.0386411 -0.0465949 0.143039 -0.0406819 -0.0444 0.140952 -0.0443014 -0.0470249 0.142744 -0.0406776 -0.0456704 0.141971 -0.0425911 -0.0460521 0.141675 -0.0426464 -0.0447228 0.140655 -0.0444069 -0.042794 0.140032 -0.0457641 -0.0408743 0.139279 -0.0469084 -0.0410507 0.138981 -0.0470862 -0.0386974 0.138777 -0.0476477 0.122454 0.139257 0.0460123 0.121805 0.13935 0.0459627 0.123585 0.139976 0.0450244 0.124972 0.140682 0.0439287 0.128104 0.143814 0.0384954 0.127391 0.142692 0.0405634 0.12824 0.143026 0.0397757 0.119936 0.138969 0.0465199 0.118027 0.138841 0.0467044 0.120256 0.138763 0.0467386 0.128396 0.144869 0.0364019 0.129268 0.143804 0.0376517 0.128802 0.144097 0.0377237 0.127304 0.141952 0.0416936 0.127685 0.141656 0.0417498 0.126019 0.140928 0.0434098 0.124395 0.140007 0.0448732 0.118027 0.138841 -0.0476343 0.128979 0.146685 0.0320597 0.128844 0.145136 0.0356899 0.129466 0.146384 0.0319362 0.128804 0.144103 -0.0386411 0.128248 0.143039 -0.0406819 0.127606 0.142971 -0.0409923 0.127324 0.141971 -0.0425911 0.12656 0.141832 -0.042982 0.126054 0.140952 -0.0443014 0.124448 0.140032 -0.0457641 0.12513 0.140778 -0.0447075 0.123457 0.139921 -0.0460377 0.122528 0.139279 -0.0469084 0.120351 0.138777 -0.0476477 0.121621 0.139301 -0.0469656 0.119721 0.138941 -0.0474894 0.118027 0.1386 -0.0479045 0.12927 0.14381 -0.0385687 0.12911 0.145038 -0.0365713 0.126376 0.140655 -0.0444069 0.124702 0.139734 -0.0459106 0.120441 0.138479 -0.0478454 0.118027 0.138301 -0.0481091 0.128979 0.149249 0.024794 0.129466 0.150404 0.0180354 0.128979 0.150725 0.0180822 0.128979 0.151221 0.0112278 0.129466 0.1448 -0.0364563 0.128979 0.146685 -0.0329896 0.128979 0.149249 -0.0257239 0.129466 0.150896 0.0112278 0.129466 0.150896 -0.0121577 0.128979 0.151221 -0.0121577 0.128979 0.150725 -0.0190121 0.129466 0.148937 -0.0256313 0.131026 0.142764 -0.0357346 0.130587 0.147862 -0.025312 0.130587 0.143786 -0.0359775 0.130912 0.145561 -0.0305806 0.130972 0.143155 -0.0357703 0.131027 0.148714 -0.0121577 0.131027 0.148244 -0.0186514 0.130912 0.149288 -0.0121577 0.130912 0.148812 -0.018734 0.130912 0.147396 -0.0251734 0.130608 0.143767 -0.0359706 0.130379 0.142786 -0.0382913 0.131022 0.142865 -0.0357186 0.130707 0.142356 -0.0381455 0.118027 0.136981 -0.0487469 0.121486 0.136884 -0.048321 0.12076 0.136786 -0.048499 0.120634 0.137485 -0.0483463 0.120705 0.137146 -0.0484653 0.123241 0.137621 -0.0476441 0.125502 0.138343 -0.0463552 0.130034 0.141289 -0.0405321 0.129718 0.1417 -0.0406191 0.130912 0.143323 -0.0358197 0.127401 0.139232 -0.0447001 0.128925 0.140234 -0.0427327 0.129097 0.139795 -0.0426049 0.130197 0.14082 -0.0403592 0.131027 0.148714 0.0112278 0.118027 0.137316 -0.0486207 -0.036373 0.136981 -0.0487469 -0.036373 0.136625 -0.0487897 0.131027 0.146845 0.02408 0.131027 0.148244 0.0177215 0.130912 0.147396 0.0242435 0.130587 0.149294 0.0178741 0.130912 0.148812 0.0178041 0.130912 0.149288 0.0112278 -0.0489336 0.143786 -0.0359775 -0.0415872 0.137621 -0.0476441 -0.0459125 0.138819 -0.0446213 -0.0483801 0.141289 -0.0405321 -0.0490533 0.142356 -0.0381455 -0.039051 0.137146 -0.0484653 -0.0414482 0.137968 -0.0475462 -0.0438488 0.138343 -0.0463552 -0.0454966 0.139607 -0.0446794 -0.0457469 0.139232 -0.0447001 -0.0472712 0.140234 -0.0427327 -0.0489584 0.143762 -0.035969 0.130912 0.145561 0.0296507 0.130964 0.143182 0.0348477 0.13102 0.14289 0.0347896 0.131026 0.142763 0.0348055 -0.0493684 0.142865 -0.0357186 -0.0493726 0.142764 -0.0357346 -0.0493729 0.142724 -0.0357636 -0.049373 0.142701 -0.0357897 -0.0492588 0.145561 -0.0305806 -0.0492589 0.143323 -0.0358197 -0.0493189 0.143153 -0.0357698 -0.0489336 0.146015 -0.0307545 -0.0492588 0.147396 -0.0251734 0.130912 0.143323 0.0348899 0.131027 0.142724 0.0348337 0.130025 0.141278 0.0396247 0.123145 0.137597 0.046756 0.125776 0.138003 0.0452979 0.121961 0.136961 0.0472501 0.120612 0.137135 0.0475547 0.120666 0.136775 0.047589 0.118027 0.136981 0.0478169 0.123009 0.137944 0.046657 0.125426 0.138313 0.045479 0.125229 0.138673 0.0454133 0.127351 0.139204 0.0438227 0.128903 0.140218 0.0418367 0.127102 0.139579 0.0438006 0.130705 0.142351 0.0372278 0.130376 0.142781 0.0373733 0.130587 0.143786 0.0350476 -0.049373 0.146845 -0.02501 -0.0492588 0.148812 -0.018734 -0.0489336 0.149294 -0.018804 -0.049373 0.148244 -0.0186514 -0.0492588 0.149288 -0.0121577 -0.036373 0.137316 0.0476908 -0.036373 0.136981 0.0478169 0.118027 0.136625 0.0478598 -0.0489336 0.149775 0.0112278 -0.0489309 0.143789 0.0350486 -0.036373 0.136625 0.0478598 -0.040829 0.137058 0.0470723 -0.0389589 0.137135 0.0475547 -0.0414919 0.137597 0.046756 -0.049311 0.14318 0.0348472 -0.0493726 0.142762 0.0348056 -0.044579 0.138186 0.0449425 -0.0462237 0.138992 0.043343 -0.0472497 0.140218 0.0418367 -0.0470624 0.139519 0.0422581 -0.0483714 0.141278 0.0396247 -0.0490511 0.142351 0.0372278 -0.0413555 0.137944 0.046657 -0.0435751 0.138673 0.0454133 -0.0437729 0.138313 0.045479 -0.0454481 0.139579 0.0438006 -0.0456972 0.139204 0.0438227 -0.0480559 0.141689 0.0397112 -0.0487228 0.142781 0.0373733 -0.0492588 0.149288 0.0112278 -0.049373 0.148244 0.0177215 -0.049373 0.146845 0.02408 -0.0492588 0.148812 0.0178041 -0.0489336 0.149294 0.0178741 -0.0492588 0.147396 0.0242435 -0.0489336 0.147862 0.0243821 -0.0492588 0.143323 0.0348899 -0.0489336 0.146015 0.0298246 -0.0492588 0.145561 0.0296507 -0.0493665 0.142889 0.0347896 -0.039838 0.120535 0.0368603 -0.0468698 0.120535 0.0348598 -0.0468698 0.120535 -0.0357897 -0.0460708 0.120535 -0.0398067 -0.039838 0.120535 -0.0377902 -0.0437954 0.120535 -0.0432121 -0.0403899 0.120535 -0.0454876 -0.036373 0.120535 -0.0397908 -0.036373 0.120535 -0.0462866 0.118027 0.120535 -0.0397908 0.119558 0.120535 -0.0394862 0.120856 0.120535 -0.0386189 0.121723 0.120535 -0.0373209 0.128523 0.120535 -0.0357897 0.121723 0.120535 0.0363909 0.120856 0.120535 0.037689 0.125449 0.120535 0.0422822 0.119558 0.120535 0.0385563 0.122044 0.120535 0.0445576 -0.0383735 0.120535 0.0383248 -0.036373 0.120535 0.0453567 -0.0403899 0.120535 0.0445576 -0.0469529 0.112141 -0.0357897 -0.0385158 0.112027 -0.0465626 -0.036373 0.112027 -0.0467736 -0.0424753 0.112027 -0.0449225 -0.0417905 0.11199 -0.0451732 -0.0440346 0.11199 -0.0434513 -0.0457565 0.11199 -0.0412073 -0.0473569 0.112027 -0.0357897 -0.0470606 0.112032 -0.0357897 -0.0468389 0.11199 -0.0385941 -0.0439303 0.112032 -0.043347 -0.0466965 0.112032 -0.0385559 -0.0456288 0.112032 -0.0411336 -0.0438541 0.112141 -0.0432709 -0.0417168 0.112032 -0.0450455 -0.0416629 0.112141 -0.0449522 -0.0455355 0.112141 -0.0410797 -0.0465924 0.112141 -0.038528 -0.0391009 0.112289 -0.0459706 -0.0391773 0.11199 -0.0462557 -0.0405763 0.112027 -0.0459375 -0.0391391 0.112032 -0.0461132 -0.0391113 0.112141 -0.0460092 -0.036373 0.112032 -0.0464774 -0.0472081 0.11199 -0.0357897 -0.0473569 0.112027 0.0348598 -0.0472081 0.11199 0.0348598 -0.0469529 0.112141 0.0348598 -0.046913 0.112289 -0.0357897 -0.0457565 0.11199 0.0402774 -0.0424753 0.112027 0.0439926 -0.0385158 0.112027 0.0456326 -0.036373 0.112032 0.0455475 -0.0391773 0.11199 0.0453258 -0.0391391 0.112032 0.0451833 -0.0417905 0.11199 0.0442433 -0.0440346 0.11199 0.0425214 -0.036373 0.112141 0.0454397 -0.0417168 0.112032 0.0441156 -0.0416629 0.112141 0.0440223 -0.0439303 0.112032 0.0424171 -0.0438541 0.112141 0.0423409 -0.0404065 0.112289 0.0445975 -0.0391113 0.112141 0.0450792 -0.0391009 0.112289 0.0450407 -0.0468389 0.11199 0.0376641 -0.0456288 0.112032 0.0402036 -0.0455355 0.112141 0.0401498 -0.0461107 0.112289 0.0388933 -0.0465539 0.112289 0.0375878 -0.0471458 0.112027 0.0370027 -0.0470606 0.112032 0.0348598 -0.0466965 0.112032 0.037626 -0.0465924 0.112141 0.0375981 -0.046913 0.112289 0.0348598 -0.0460708 0.120535 0.0388768 -0.0455009 0.112289 0.0401298 -0.0438259 0.112289 0.0423127 -0.041643 0.112289 0.0439877 -0.0437954 0.120535 0.0422822 -0.0404065 0.112289 -0.0455274 -0.041643 0.112289 -0.0449177 -0.0438259 0.112289 -0.0432427 -0.0455009 0.112289 -0.0410597 -0.0461107 0.112289 -0.0398232 -0.0465539 0.112289 -0.0385177 -0.0479039 0.112782 -0.0380834 -0.048426 0.114007 -0.0389643 -0.0478883 0.114007 -0.0405595 -0.0472349 0.112782 -0.0402889 -0.0446863 0.112782 -0.0441031 -0.0435853 0.114007 -0.0459551 -0.0408721 0.112782 -0.0466516 -0.0411428 0.114007 -0.047305 -0.0386666 0.112782 -0.0473207 -0.036373 0.112782 -0.0475466 -0.0492367 0.114972 -0.0357897 -0.0488124 0.114972 -0.0390661 -0.0452367 0.114007 -0.0445526 -0.0455209 0.114972 -0.0448335 -0.0466202 0.114007 -0.0428853 -0.0469488 0.114972 -0.0431128 -0.0480571 0.114972 -0.0411707 -0.0476942 0.114007 -0.0410036 -0.0481809 0.116007 -0.0412277 -0.0470608 0.116007 -0.0431904 -0.0456178 0.116007 -0.0449294 -0.0438954 0.116007 -0.0463922 -0.0438166 0.114972 -0.046281 -0.0419458 0.116007 -0.0475347 -0.0418873 0.114972 -0.0474115 -0.041716 0.114007 -0.0470505 -0.0397915 0.114972 -0.0481909 -0.0396853 0.114007 -0.0478056 -0.036373 0.114972 -0.0486534 -0.036373 0.114007 -0.0482538 -0.0396853 0.114007 0.0468757 -0.0408721 0.112782 0.0457217 -0.0446863 0.112782 0.0431732 -0.0435853 0.114007 0.0450252 -0.0461484 0.112782 0.0413916 -0.0466202 0.114007 0.0419554 -0.0472349 0.112782 0.039359 -0.0479039 0.112782 0.0371535 -0.048426 0.114007 0.0380344 -0.0481298 0.112782 0.0348598 -0.036373 0.114007 0.0473239 -0.0397915 0.114972 0.047261 -0.036373 0.116007 0.0478598 -0.0452367 0.114007 0.0436227 -0.0455209 0.114972 0.0439036 -0.0438166 0.114972 0.0453511 -0.041716 0.114007 0.0461206 -0.0418873 0.114972 0.0464816 -0.0411428 0.114007 0.0463751 -0.0456178 0.116007 0.0439994 -0.0469488 0.114972 0.0421829 -0.0480571 0.114972 0.0402408 -0.0478883 0.114007 0.0396296 -0.0476942 0.114007 0.0400737 -0.0488124 0.114972 0.0381362 -0.049373 0.116007 -0.0357897 -0.0488371 0.114007 -0.0357897 -0.0492367 0.114972 0.0348598 -0.0488371 0.114007 0.0348598 -0.0477953 0.112351 -0.0357897 -0.0461484 0.112782 -0.0423215 -0.0444498 0.112351 -0.0438665 -0.0429047 0.112782 -0.0455652 -0.0427189 0.112351 -0.045287 -0.0386014 0.112351 -0.0469926 -0.0471458 0.112027 -0.0379326 -0.0475758 0.112351 -0.0380181 -0.0469258 0.112351 -0.0401609 -0.0458703 0.112351 -0.0421356 -0.0465208 0.112027 -0.0399931 -0.0455057 0.112027 -0.041892 -0.0441398 0.112027 -0.0435565 -0.0407441 0.112351 -0.0463426 -0.0386666 0.112782 0.0463908 -0.0386014 0.112351 0.0460627 -0.0429047 0.112782 0.0446353 -0.0427189 0.112351 0.0443571 -0.0444498 0.112351 0.0429366 -0.0469258 0.112351 0.0392309 -0.0475758 0.112351 0.0370882 -0.0407441 0.112351 0.0454127 -0.0405763 0.112027 0.0450076 -0.0441398 0.112027 0.0426266 -0.0458703 0.112351 0.0412057 -0.0455057 0.112027 0.0409621 -0.0465208 0.112027 0.0390632 -0.0481298 0.112782 -0.0357897 -0.0477953 0.112351 0.0348598 0.00854374 0.151285 0.00902563 0.00868649 0.151335 0.0112278 0.0083411 0.151139 0.0090251 0.00878171 0.151335 -0.00502075 0.00854388 0.151284 -0.0099556 0.00834108 0.151138 -0.00995511 0.00834156 0.151139 -0.0088276 0.00834093 0.151143 0.00371928 0.00561435 0.151076 0.0156392 0.00671068 0.151142 0.0148544 0.00656947 0.150999 0.0146935 0.00844406 0.151283 0.0111995 0.00794719 0.151113 0.0124841 0.00824152 0.151134 0.0111759 0.00430007 0.150899 0.0158768 0.00298685 0.150886 0.0160487 0.00814042 0.151263 0.0125539 0.00837609 0.151315 0.0126352 0.00755719 0.151212 0.0137948 0.00776977 0.151259 0.0139298 0.0043967 0.151061 0.0163425 0.0043435 0.151032 0.0160926 0.00299818 0.151015 0.016268 0.003012 0.151041 0.0165207 0.000221765 0.151023 0.0162117 0.000221357 0.151048 0.016461 0.00878559 0.151335 -0.00995619 -0.0254688 0.150897 0.0159945 0.000222101 0.150898 0.0159944 -0.002016 0.150896 0.0159945 -0.0254685 0.151023 0.0162137 -0.017928 0.150896 0.015995 -0.023232 0.150896 0.0159947 0.00305731 0.151042 -0.0174452 0.00673338 0.151144 -0.0157587 0.00639485 0.151148 -0.0163787 0.00743961 0.151229 -0.0153407 0.00806746 0.151287 -0.0143126 0.000222127 0.150898 -0.0169243 0.00302111 0.150887 -0.0169737 0.000221792 0.151023 -0.0171417 0.002306 0.15104 -0.017462 0.000929704 0.151046 -0.0174045 0.00303323 0.151015 -0.0171929 0.00565133 0.151078 -0.0165457 0.00410061 0.151055 -0.0173269 0.00756768 0.151213 -0.0147017 0.00659118 0.151001 -0.0155988 0.00438856 0.151034 -0.0170086 0.00329042 0.150888 -0.0169534 0.00844422 0.151283 -0.0121293 0.0081453 0.151263 -0.0134646 0.00824157 0.151134 -0.0121055 0.00739308 0.151065 -0.0145866 0.00829904 0.151308 -0.0137769 -0.0282879 0.151015 0.0162632 -0.0296428 0.151033 0.0160772 -0.0295977 0.1509 0.0158615 -0.0308081 0.15094 0.015417 -0.0309046 0.151078 0.0156128 -0.0318456 0.151001 0.0146617 -0.0322622 0.151033 0.0142013 -0.0328182 0.151213 0.0137661 -0.0333932 0.151263 0.0125309 -0.033488 0.151134 0.0111757 -0.0296981 0.151062 0.0163271 -0.0310231 0.151112 0.0158401 -0.0319882 0.151145 0.0148214 -0.0321631 0.151186 0.0150065 -0.0336293 0.151315 0.0126118 -0.0254688 0.150897 -0.0169244 -0.0254685 0.151022 -0.0171419 -0.0126234 0.151047 -0.0173939 -0.0336893 0.151283 0.0111993 -0.0335875 0.151138 0.00902514 -0.0331938 0.151112 -0.0134134 -0.0333873 0.151263 -0.0134833 -0.0328047 0.151211 -0.0147239 -0.0318174 0.150998 -0.0156224 -0.0307677 0.150937 -0.0163714 -0.0308625 0.151076 -0.0165683 -0.0295487 0.150899 -0.0168057 -0.0336234 0.151315 -0.0135647 -0.0330177 0.151259 -0.0148592 -0.0319588 0.151142 -0.0157835 -0.0321322 0.151183 -0.0159703 -0.0295922 0.151032 -0.0170218 -0.0309788 0.151109 -0.0167969 -0.028246 0.151015 -0.0171987 -0.0282602 0.151041 -0.0174519 -0.034032 0.151335 0.00902627 -0.0340272 0.151335 -0.000464958 -0.0337903 0.151284 0.00902565 -0.0337904 0.151284 -0.0099556 -0.0335875 0.151142 -0.00464619 -0.0336894 0.151283 -0.0121291 -0.033488 0.151133 -0.0121055 0.00674609 0.149628 -0.011944 0.00691713 0.149719 -0.00995446 0.00676814 0.149516 0.00902442 0.00671601 0.149274 -0.00995425 0.00691116 0.14972 -0.000467643 0.00676923 0.149518 -0.00995436 0.00545896 0.149748 -0.0149328 0.00539861 0.149497 -0.0149136 0.00606294 0.149638 -0.0140551 0.00602087 0.149515 -0.0140437 0.00663977 0.149395 -0.0119322 0.00600398 0.149388 -0.0140446 0.00256627 0.150129 -0.0163262 0.00461098 0.149769 -0.0155859 0.00351673 0.14985 -0.0160769 0.00458871 0.149643 -0.0155827 0.00661561 0.149755 -0.0130572 0.00612753 0.14975 -0.0140793 0.00264099 0.15045 -0.0165074 0.00261452 0.150359 -0.0164255 0.00469654 0.150002 -0.0156627 0.00668049 0.149518 -0.0119365 0.00464763 0.149892 -0.0156129 0.00258902 0.150249 -0.0163635 0.000221302 0.150457 -0.0165113 0.00663974 0.149396 0.0110023 0.00668037 0.149518 0.0110066 0.00691654 0.149719 0.00902449 -0.0254677 0.150457 -0.0165114 -0.0126232 0.150213 -0.0164591 -0.00732014 0.150659 -0.0166611 0.00256725 0.150249 0.0154373 0.00654313 0.149768 0.012371 0.000221308 0.150458 0.0155814 0.0060133 0.149514 0.0131282 0.00544594 0.149747 0.0140171 0.0059957 0.149387 0.0131303 0.00624483 0.149335 0.0125793 0.0060555 0.149637 0.0131394 0.00612015 0.149749 0.0131636 0.00570353 0.149439 0.013606 0.00457197 0.149642 0.0146631 0.00459423 0.149768 0.0146664 0.00426949 0.1497 0.0148339 0.0025446 0.150129 0.0154 0.00674582 0.149628 0.0110141 0.00620201 0.149841 0.0131987 0.000221543 0.15066 0.0157291 0.00463073 0.149891 0.0146936 0.00473645 0.150093 0.0148122 0.00557652 0.14995 0.0141084 -0.0319929 0.149628 -0.011944 -0.0268058 0.150136 -0.0164288 -0.0302362 0.149567 -0.0152973 -0.0306926 0.149747 -0.0149471 -0.0298408 0.149768 -0.0155963 -0.0298774 0.149891 -0.0156237 -0.0277906 0.150128 -0.0163301 -0.0313022 0.149637 -0.0140692 -0.0309502 0.149438 -0.0145356 -0.0298186 0.149642 -0.0155929 -0.0281849 0.149944 -0.0162372 -0.025892 0.150654 -0.0166584 -0.0318722 0.14927 -0.0119314 -0.0318862 0.149395 -0.0119322 -0.0312491 0.149384 -0.014047 -0.0319271 0.149517 -0.0119365 -0.0312598 0.149513 -0.014058 -0.0313671 0.149748 -0.0140935 -0.0278129 0.150249 -0.0163677 -0.0286061 0.150339 -0.0163437 -0.0299835 0.150093 -0.015743 -0.0254674 0.150215 0.0155292 -0.0187884 0.150213 0.0155292 -0.0254677 0.150458 0.0155816 -0.0232326 0.150659 0.0157306 -0.0179286 0.150659 0.0157312 -0.00201657 0.15066 0.0157303 -0.0319624 0.149274 -0.00995425 -0.0320158 0.149518 -0.00995437 -0.032164 0.149719 -0.00995447 -0.0308031 0.149468 0.0138 -0.0312673 0.149514 0.0131138 -0.0319269 0.149517 0.0110066 -0.0318722 0.14927 0.0110016 -0.0318862 0.149395 0.0110024 -0.0312498 0.149387 0.0131157 -0.0300006 0.150093 0.014802 -0.032078 0.14972 0.0110244 -0.0313741 0.149749 0.0131495 -0.0268643 0.150131 0.015495 -0.029894 0.149891 0.0146833 -0.0278343 0.150249 0.015434 -0.0307054 0.149747 0.0140031 -0.0285669 0.149883 0.0152081 -0.0298573 0.149768 0.0146561 -0.029835 0.149642 0.0146528 -0.027812 0.150128 0.0153965 -0.025468 0.15066 0.0157297 -0.030692 0.149976 0.0142473 -0.0313094 0.149638 0.0131252 -0.0319624 0.149279 -0.00501982 -0.0319926 0.149628 0.0110142 -0.032015 0.149517 0.00902443 -0.00177061 0.147087 0.0123619 -0.00177058 0.147086 0.0142858 -0.0013732 0.148234 0.00901872 -0.0013732 0.147084 0.00901269 -0.0012732 0.13067 -0.0166299 -0.0012732 0.132085 0.0162858 -0.0012732 0.130085 0.0142858 -0.0012732 0.146586 0.0142858 -0.0012732 0.146586 -0.0152157 -0.0012732 0.130237 -0.0159811 -0.0012732 0.130085 -0.0152157 -0.0012732 0.144586 -0.0172157 -0.0012732 0.146 -0.0166299 -0.0012732 0.146 0.0157 -0.0012732 0.145351 0.0161336 -0.049373 0.129219 -0.0164654 -0.049373 0.147637 -0.0154634 -0.049373 0.148714 -0.0121577 -0.049373 0.129762 -0.0173479 -0.049373 0.13016 -0.01771 -0.049373 0.145025 -0.0303754 -0.049373 0.14708 -0.0171398 -0.049373 0.12959 0.0162099 -0.049373 0.129034 0.0145335 -0.049373 0.146909 0.016418 -0.049373 0.145025 0.0294455 -0.049373 0.148714 0.0112278 -0.049373 0.129952 0.0166086 -0.0340145 0.151335 -0.0110584 -0.0339334 0.151335 0.0112278 -0.0340141 0.151335 0.0101285 -0.0340283 0.151335 0.00409083 -0.0467516 0.151335 -0.0121577 -0.0340324 0.151335 -0.00995619 -0.0489442 0.116007 -0.0391008 -0.0491946 0.141856 -0.0379358 -0.0485434 0.14082 -0.0403592 -0.0474433 0.139795 -0.0426049 -0.0470624 0.139519 -0.043188 -0.0439918 0.137953 -0.0463232 -0.0416923 0.137249 -0.0476516 -0.0398323 0.136884 -0.048321 -0.0398277 0.116007 -0.0483223 -0.0391066 0.136786 -0.048499 -0.0493729 0.142724 0.0348337 -0.049373 0.142701 0.0348598 -0.0492167 0.141912 0.0368696 -0.049373 0.116007 0.0348598 -0.0489442 0.116007 0.0381709 -0.0470608 0.116007 0.0422604 -0.0481809 0.116007 0.0402978 -0.0475754 0.139898 0.0414556 -0.0486421 0.14094 0.0391572 -0.0439147 0.137924 0.0454486 -0.0398277 0.116007 0.0473924 -0.0386287 0.136734 0.0476626 -0.0419458 0.116007 0.0466048 -0.0415952 0.137225 0.0467648 -0.0438954 0.116007 0.0454623 -0.0426938 0.137518 0.0462197 -0.0489336 0.149775 -0.0121577 -0.0489336 0.147862 -0.025312 -0.0478123 0.148937 -0.0256313 -0.0478124 0.1448 -0.0364562 -0.0489336 0.143786 0.0350476 -0.036373 0.138301 -0.0481091 -0.036373 0.137316 -0.0486207 -0.03898 0.137485 -0.0483463 -0.0387879 0.138479 -0.0478454 -0.0430482 0.139734 -0.0459106 -0.043649 0.138703 -0.0462909 -0.0469817 0.140627 -0.0427634 -0.0480645 0.1417 -0.0406191 -0.048725 0.142786 -0.0382913 -0.0476167 0.14381 -0.0385687 -0.0489309 0.143789 -0.0359785 -0.0478123 0.1448 0.0355264 -0.0476167 0.14381 0.0376388 -0.0469608 0.14061 0.0418665 -0.0430482 0.139734 0.0449807 -0.0388903 0.137473 0.0474352 -0.049073 0.144834 0.0170335 -0.00177058 0.144586 0.0167858 -0.00177058 0.129585 0.0142858 -0.049073 0.129337 -0.0154634 -0.00177058 0.129585 -0.0152157 -0.049073 0.147334 -0.0154634 -0.0317186 0.147243 -0.0127176 -0.0317321 0.147243 0.0117293 -0.0307922 0.147238 0.0137874 -0.0301227 0.147234 0.0144343 -0.0319518 0.147244 -0.00994362 -0.0254503 0.146954 0.0155121 0.000212227 0.148535 0.0155204 -0.00479647 0.148535 0.0155204 0.000221027 0.150216 0.0155292 -0.0126232 0.150213 0.0155292 -0.0078732 0.148236 0.0155188 -0.0166157 0.146885 0.0155117 -0.0319624 0.149274 0.00902434 -0.0319624 0.14928 -0.000464956 -0.0319518 0.147244 0.00901371 -0.0166157 0.146885 -0.0164417 -0.00645797 0.150213 -0.0164591 -0.00479647 0.148535 -0.0164503 -0.0041713 0.148535 -0.0162442 -0.00257494 0.148535 0.0142922 -0.00411271 0.148535 -0.0162209 0.000212227 0.148535 -0.0164503 -0.00278787 0.148535 -0.015422 0.00126479 0.148535 -0.0164353 0.00558592 0.148535 -0.0146822 -0.00158011 0.148535 0.0127268 0.00349018 0.148535 0.0151466 0.00472601 0.148535 0.0145537 -0.00148156 0.148535 0.0124565 0.00494406 0.148535 0.0143942 -0.00109113 0.148535 0.0101939 0.00671214 0.148535 0.00902047 0.00639889 0.148535 0.0121006 -0.00107137 0.148535 0.00932617 0.00669117 0.148535 -0.0111341 -0.00134642 0.148535 -0.0129304 0.00671603 0.149279 -0.000464957 -0.00176978 0.146896 -0.0161724 -0.00492395 0.146922 -0.0161647 -0.0017695 0.146354 -0.0169835 -0.0490734 0.147179 -0.0163287 -0.0254503 0.146954 -0.016442 -0.0490736 0.146396 -0.0174156 -0.00348478 0.147073 -0.0155581 -0.0490734 0.145661 -0.0178225 -0.00177058 0.132085 -0.0177157 -0.0490733 0.131288 -0.0179024 -0.0490736 0.130512 -0.0175833 -0.0017695 0.130317 -0.0169835 -0.0490736 0.129885 -0.0170252 -0.0490733 0.129398 0.0150823 -0.0490736 0.129717 0.0158587 -0.00176978 0.131128 0.0165955 -0.0490733 0.145383 0.0169725 -0.00495913 0.146919 0.015244 -0.0078732 0.146815 0.0155114 -0.049073 0.147334 0.0145335 -0.0490734 0.147179 0.0153988 -0.0268412 0.146981 0.015479 -0.0490736 0.146786 0.0160953 -0.0078732 0.148236 -0.0164487 -0.0078732 0.146815 -0.0164413 -0.00601908 0.146839 -0.0163662 -0.00457268 0.148236 -0.0160675 -0.00364122 0.147059 -0.0156519 -0.00327486 0.148235 -0.0154229 -0.00260185 0.148235 -0.0148055 -0.00302606 0.147093 -0.0152223 -0.00239471 0.148235 -0.014541 -0.00219926 0.147088 -0.0142355 -0.0013849 0.148234 -0.0109157 -0.00163132 0.148235 -0.0128245 -0.00177061 0.147087 -0.0132918 -0.00205469 0.148235 -0.0139781 -0.00157247 0.147044 -0.0125653 -0.00138624 0.146903 -0.0109456 -0.0013732 0.148234 -0.00994863 -0.00690612 0.148236 0.0155071 -0.00631955 0.146826 0.0154658 -0.00499736 0.148236 0.0152607 -0.00367792 0.147056 0.0147428 -0.00367792 0.148236 0.014749 -0.00346172 0.148235 0.0146196 -0.00302606 0.147093 0.0142924 -0.00251419 0.14709 0.0137634 -0.0018614 0.148235 0.0126162 -0.00175439 0.148235 0.0123193 -0.00158133 0.147048 0.0116764 -0.0015663 0.148235 0.0116124 0.00254768 0.150005 -0.0163154 0.0020868 0.148535 -0.0163727 0.00197441 0.150089 -0.0163941 0.00134345 0.150161 -0.0164408 0.000221027 0.150216 -0.0164591 0.00329231 0.148535 -0.016137 0.00570072 0.149443 -0.0145399 0.00466336 0.148535 -0.0155255 0.00474971 0.149614 -0.0154769 0.00671214 0.148535 -0.00995039 0.00662582 0.14927 -0.0119315 0.0065845 0.149274 -0.0122158 0.00640863 0.148535 -0.0129963 0.00633833 0.148535 -0.0132283 0.00618678 0.149351 -0.0136546 0.00574547 0.148535 -0.0144642 0.00601203 0.149386 -0.0140292 0.00139592 0.148535 0.0154994 0.00156055 0.150137 0.0154988 0.00325811 0.148535 0.0152169 0.00252603 0.150006 0.0153892 0.00538557 0.149497 0.0139978 0.00578732 0.148535 0.0134716 0.00662583 0.149271 0.0110015 0.00670105 0.149273 0.0100769 0.00663455 0.148535 0.010895 0.00671601 0.149275 0.00902434 -0.0254674 0.150215 -0.0164591 -0.0281666 0.147068 -0.0162229 -0.0295158 0.149699 -0.0157639 -0.0291887 0.147171 -0.0158977 -0.0301227 0.147234 -0.0153642 -0.0312384 0.14724 -0.0140348 -0.0306321 0.149496 -0.0149276 -0.0312421 0.149386 -0.0140602 -0.0319185 0.147244 -0.0113343 -0.0295535 0.149696 0.0148144 -0.0295411 0.147204 0.0148009 -0.0282266 0.147074 0.0152791 -0.0277939 0.150004 0.0153855 -0.0316041 0.149312 0.0122546 -0.0313799 0.147241 0.0128117 -0.030645 0.149496 0.0139837 -0.0304347 0.149535 0.0141953 -0.0490736 0.146954 -0.0167886 -0.049373 0.147531 -0.0162253 -0.0490733 0.147273 -0.0160122 -0.049373 0.146718 -0.0175386 -0.049373 0.145836 -0.0180814 -0.049373 0.144834 -0.0182665 -0.049073 0.144834 -0.0179634 -0.0490734 0.145699 0.016879 -0.049373 0.145596 0.0172311 -0.049373 0.14651 0.0167801 -0.0490736 0.146159 0.0166534 -0.049373 0.147452 0.0155355 -0.0490734 0.147193 0.015361 -0.049373 0.147637 0.0145335 -0.049373 0.131837 -0.0182665 -0.049073 0.131837 0.0170335 -0.049373 0.131837 0.0173366 -0.049373 0.144834 0.0173366 -0.049373 0.131075 -0.018161 -0.0490734 0.130972 -0.0178089 -0.049073 0.131837 -0.0179634 -0.0490734 0.129478 -0.0162909 -0.049373 0.129034 -0.0154634 -0.0490734 0.129491 0.0153988 -0.049073 0.129337 0.0145335 -0.049373 0.129139 0.0152954 -0.0490736 0.130275 0.0164856 -0.049373 0.130835 0.0171514 -0.0490734 0.131009 0.0168925 -0.0036687 0.148535 0.0150872 -0.00473655 0.148236 0.015189 -0.00547089 0.148388 0.0155196 -0.0032809 0.148235 0.0144973 -0.00239904 0.148235 0.0136171 -0.00138182 0.148234 0.00988914 -0.00107097 0.148535 0.00901872 -0.00107097 0.148535 -0.00994863 -0.0052796 0.148236 -0.0162556 -0.00606885 0.148305 -0.0164491 -0.00700278 0.148236 -0.0164401 -0.00227237 0.148235 -0.0143602 -0.00227764 0.148535 -0.0148874 -0.0017851 0.148535 -0.0141147 -0.00184673 0.148235 -0.0135084 -0.00170303 0.148235 -0.0130854 -0.00133975 0.129835 -0.0152157 -0.00130673 0.13007 -0.01605 -0.00141669 0.129913 -0.0161153 -0.00158557 0.129809 -0.0161585 -0.00176978 0.129775 -0.0161724 -0.00158536 0.130343 -0.0169576 -0.00177058 0.144586 -0.0177157 -0.00158615 0.144586 -0.0176794 -0.00158615 0.132085 -0.0176794 -0.00152169 0.144586 -0.0176479 -0.00141697 0.144586 -0.0175666 -0.00133975 0.132085 -0.017465 -0.0012732 0.132085 -0.0172157 -0.00158615 0.129621 -0.0152157 -0.00152169 0.129652 -0.0152157 -0.00152169 0.129652 0.0142858 -0.00141697 0.129734 -0.0152157 -0.00141697 0.129734 0.0142858 -0.00158557 0.145529 -0.0174917 -0.00176978 0.145543 -0.0175254 -0.0012732 0.145351 -0.0170635 -0.00130673 0.14542 -0.0172298 -0.00133975 0.144586 -0.017465 -0.00141659 0.146248 -0.0168778 -0.00141669 0.145486 -0.0173874 -0.00177058 0.132085 0.0167858 -0.00133975 0.132085 0.016535 -0.00130673 0.13125 0.0162999 -0.00141697 0.132085 0.0166367 -0.00152169 0.132085 0.0167179 -0.00158557 0.131142 0.0165617 -0.0017695 0.130317 0.0160536 -0.00141669 0.131185 0.0164575 -0.0012732 0.13067 0.0157 -0.0012732 0.131319 0.0161336 -0.0013732 0.146886 -0.00994562 -0.00131147 0.146778 -0.0152157 -0.0014204 0.14694 -0.0152157 -0.00158334 0.147049 -0.0152157 -0.00158334 0.147049 0.0142858 -0.0013732 0.146886 0.00901166 -0.00131147 0.146778 0.0142858 -0.00158615 0.132085 0.0167495 -0.00158615 0.144586 0.0167495 -0.00141697 0.144586 0.0166367 -0.00141669 0.146758 0.0151853 -0.0014204 0.14694 0.0142858 -0.0012732 0.146434 0.0150512 -0.0017695 0.146354 0.0160536 -0.00176978 0.146896 0.0152425 -0.00158536 0.146328 0.0160277 -0.00141659 0.146248 0.0159479 -0.00158557 0.146862 0.0152285 -0.00130671 0.146128 0.0158273 -0.00130673 0.1466 0.0151201 0.00558995 0.149951 -0.0150237 -0.0308366 0.14995 0.0140943 0.00691542 0.149719 -0.00883223 0.00795198 0.151113 -0.013395 0.00555538 0.15094 -0.0163498 -0.0321636 0.149719 0.00902451 -0.0326434 0.151065 0.013651 0.00691502 0.149719 0.00789692 0.00593835 0.150203 0.0141719 0.00551994 0.150938 0.0154424 0.00261883 0.15045 0.0155812 -0.0126246 0.150659 0.0157314 -0.012624 0.150895 0.0159953 -0.026997 0.150568 0.0156891 -0.0278856 0.150449 0.0155786 -0.0282755 0.150886 0.0160438 -0.0285935 0.150344 0.0154174 -0.0297221 0.150143 0.014966 -0.0321588 0.14972 -0.00465076 -0.0321578 0.14972 -0.000468469 -0.0335874 0.151143 -0.000463893 -0.032162 0.149719 0.00789609 -0.033588 0.151139 0.00790067 -0.0325159 0.15005 0.0099883 -0.0331997 0.151113 0.0124615 -0.0335875 0.151138 -0.0099551 -0.033588 0.151139 -0.00882848 -0.0321623 0.149719 -0.00883306 -0.032515 0.150308 -0.0130134 -0.0282345 0.150885 -0.0169791 -0.0278637 0.15045 -0.0165125 -0.025468 0.15066 -0.0166597 -0.0232321 0.150659 -0.0166606 -0.0232315 0.150896 -0.0169247 -0.0126236 0.150895 -0.016925 -0.0126241 0.150659 -0.0166613 -0.00731956 0.150896 -0.0169251 -0.00201614 0.15066 -0.0166603 -0.00201556 0.150896 -0.0169244 0.000221533 0.15066 -0.0166591 0.00174395 0.150568 -0.0166186 0.00334215 0.150346 -0.0163477 0.00434352 0.150901 -0.0167932 0.0072643 0.150045 -0.0109223 0.00726496 0.150308 -0.0130126 0.00683137 0.14972 -0.0119542 0.00834156 0.15114 0.00790156 0.00691198 0.14972 0.00371464 0.00834111 0.151144 -0.000463005 -0.0311892 0.150206 -0.0151049 -0.0317935 0.149768 -0.0132912 -0.030567 0.149994 -0.0152975 -0.0308236 0.14995 -0.015039 -0.0314493 0.14984 -0.0141286 -0.0320784 0.14972 -0.0119543 -0.0325157 0.150049 -0.0109231 -0.0326307 0.151063 -0.0146072 -0.0311786 0.14989 0.0136546 -0.0314561 0.149841 0.0131846 -0.0325153 0.15031 0.0120803 -0.0318645 0.149754 0.01212 -0.0311896 0.150207 0.0141711 0.00738338 0.151064 0.0136781 0.00329007 0.150888 0.0160268 0.00334889 0.150341 0.0154156 0.00531249 0.149996 0.0143738 0.00683092 0.14972 0.0110243 0.00726402 0.150046 0.00998913 0.00726462 0.150306 0.0120811 0.00701698 0.151033 -0.0151299 0.00593875 0.150208 -0.0151041 0.00592717 0.149891 -0.0145912 0.00620938 0.149842 -0.0141143 0.00446877 0.150145 -0.0158989 0.00475394 0.150094 -0.0157311 -0.036373 0.112141 -0.0463697 0.118027 0.112032 -0.0464774 -0.036373 0.11199 -0.0466249 0.118027 0.11199 -0.0466249 0.120831 0.11199 -0.0462557 0.128174 0.112027 -0.0399931 0.128636 0.112027 -0.0386326 0.120869 0.112027 -0.0463993 0.12223 0.112027 -0.0459375 0.125688 0.11199 -0.0434513 0.120793 0.112032 -0.0461132 0.123444 0.11199 -0.0451732 0.125584 0.112032 -0.043347 0.12741 0.11199 -0.0412073 0.118027 0.112141 -0.0463697 0.123317 0.112141 -0.0449522 0.12337 0.112032 -0.0450455 0.127282 0.112032 -0.0411336 0.127764 0.112289 -0.0398232 0.127154 0.112289 -0.0410597 0.125479 0.112289 -0.0432427 0.125508 0.112141 -0.0432709 0.123297 0.112289 -0.0449177 0.120755 0.112289 -0.0459706 0.120765 0.112141 -0.0460092 0.128207 0.112289 -0.0385177 0.128246 0.112141 -0.038528 0.12835 0.112032 -0.0385559 0.127189 0.112141 -0.0410797 0.128493 0.11199 -0.0385941 0.128714 0.112032 -0.0357897 0.118027 0.112141 0.0454397 0.118027 0.112032 0.0455475 -0.036373 0.11199 0.045695 0.128606 0.112141 0.0348598 0.128606 0.112141 -0.0357897 0.128714 0.112032 0.0348598 0.128862 0.11199 -0.0357897 0.12901 0.112027 -0.0357897 0.128493 0.11199 0.0376641 0.128636 0.112027 0.0377026 0.128862 0.11199 0.0348598 0.127539 0.112027 0.0403518 0.12741 0.11199 0.0402774 0.123519 0.112027 0.0443721 0.125688 0.11199 0.0425214 0.125584 0.112032 0.0424171 0.128246 0.112141 0.0375981 0.12835 0.112032 0.037626 0.127282 0.112032 0.0402036 0.123297 0.112289 0.0439877 0.123317 0.112141 0.0440223 0.125479 0.112289 0.0423127 0.125508 0.112141 0.0423409 0.127189 0.112141 0.0401498 0.127764 0.112289 0.0388933 0.128207 0.112289 0.0375878 0.120793 0.112032 0.0451833 0.12337 0.112032 0.0441156 0.123444 0.11199 0.0442433 0.120831 0.11199 0.0453258 0.118027 0.11199 0.045695 0.120765 0.112141 0.0450792 0.120755 0.112289 0.0450407 0.12206 0.112289 0.0445975 0.127154 0.112289 0.0401298 0.127724 0.120535 0.0388768 0.128523 0.120535 0.0348598 0.128567 0.112289 0.0348598 0.127724 0.120535 -0.0398067 0.125449 0.120535 -0.0432121 0.12206 0.112289 -0.0455274 0.122044 0.120535 -0.0454876 0.118027 0.120535 -0.0462866 0.118027 0.112289 -0.0463298 0.122796 0.114007 -0.047305 0.122526 0.112782 -0.0466516 0.12337 0.114007 -0.0470505 0.127802 0.112782 -0.0423215 0.12689 0.114007 -0.0445526 0.128274 0.114007 -0.0428853 0.129542 0.114007 -0.0405595 0.129558 0.112782 -0.0380834 0.129783 0.112782 -0.0357897 0.118027 0.114007 -0.0482538 0.128602 0.114972 -0.0431128 0.125239 0.114007 -0.0459551 0.121445 0.114972 -0.0481909 0.121339 0.114007 -0.0478056 0.121481 0.116007 -0.0483223 0.123599 0.116007 -0.0475347 0.123541 0.114972 -0.0474115 0.12547 0.114972 -0.046281 0.125549 0.116007 -0.0463922 0.127271 0.116007 -0.0449294 0.127174 0.114972 -0.0448335 0.129711 0.114972 -0.0411707 0.129348 0.114007 -0.0410036 0.130466 0.114972 -0.0390661 0.13008 0.114007 -0.0389643 0.118027 0.112782 -0.0475466 0.118027 0.114972 -0.0486534 -0.036373 0.112782 0.0466167 0.118027 0.114007 0.0473239 0.118027 0.114972 0.0477235 -0.036373 0.114972 0.0477235 0.129783 0.112782 0.0348598 0.13008 0.114007 0.0380344 0.128888 0.112782 0.039359 0.129348 0.114007 0.0400737 0.12689 0.114007 0.0436227 0.124558 0.112782 0.0446353 0.12032 0.112782 0.0463908 0.122796 0.114007 0.0463751 0.125239 0.114007 0.0450252 0.128274 0.114007 0.0419554 0.129542 0.114007 0.0396296 0.129711 0.114972 0.0402408 0.130466 0.114972 0.0381362 0.129835 0.116007 0.0402978 0.128714 0.116007 0.0422604 0.128602 0.114972 0.0421829 0.127271 0.116007 0.0439994 0.127174 0.114972 0.0439036 0.12547 0.114972 0.0453511 0.12337 0.114007 0.0461206 0.121445 0.114972 0.047261 0.123541 0.114972 0.0464816 0.121481 0.116007 0.0473924 0.121339 0.114007 0.0468757 0.130491 0.114007 0.0348598 0.130491 0.114007 -0.0357897 0.13089 0.114972 -0.0357897 0.13089 0.114972 0.0348598 0.131027 0.116007 0.0348598 0.118027 0.112351 -0.0472121 0.12032 0.112782 -0.0473207 0.120255 0.112351 -0.0469926 0.124558 0.112782 -0.0455652 0.12634 0.112782 -0.0441031 0.127524 0.112351 -0.0421356 0.128888 0.112782 -0.0402889 0.128579 0.112351 -0.0401609 0.129229 0.112351 -0.0380181 0.118027 0.112027 -0.0467736 0.122398 0.112351 -0.0463426 0.124372 0.112351 -0.045287 0.123519 0.112027 -0.0453021 0.125793 0.112027 -0.0435565 0.126103 0.112351 -0.0438665 0.127539 0.112027 -0.0412817 0.129558 0.112782 0.0371535 0.12901 0.112027 0.0348598 0.129229 0.112351 0.0370882 0.127802 0.112782 0.0413916 0.127524 0.112351 0.0412057 0.12634 0.112782 0.0431732 0.126103 0.112351 0.0429366 0.122526 0.112782 0.0457217 0.118027 0.112782 0.0466167 0.128579 0.112351 0.0392309 0.128174 0.112027 0.0390632 0.125793 0.112027 0.0426266 0.124372 0.112351 0.0443571 0.122398 0.112351 0.0454127 0.12223 0.112027 0.0450076 0.120869 0.112027 0.0454694 0.120255 0.112351 0.0460627 0.118027 0.112027 0.0458437 0.129449 0.112351 -0.0357897 0.129449 0.112351 0.0348598 -0.036373 0.112351 -0.0472121 -0.036373 0.112027 0.0458437 0.118027 0.112351 0.0462821 -0.036373 0.112351 0.0462821 0.072868 0.151335 -0.00995619 0.0733125 0.151139 0.0090251 0.0733127 0.151143 0.00371938 0.0731099 0.151285 0.00902563 0.073312 0.151139 -0.00882739 0.0732109 0.151283 0.0111994 0.0734121 0.151134 0.0111759 0.0735132 0.151263 0.0125539 0.0742702 0.151064 0.0136781 0.0750841 0.150999 0.0146935 0.0749429 0.151142 0.0148544 0.0761337 0.150938 0.0154424 0.0760392 0.151076 0.0156392 0.0773535 0.150899 0.0158768 0.0732775 0.151315 0.0126352 0.0738838 0.151259 0.0139298 0.0740964 0.151212 0.0137948 0.0747698 0.151183 0.0150409 0.0772569 0.151061 0.0163425 0.0773101 0.151032 0.0160926 0.0783635 0.150888 0.0160268 0.0786554 0.151015 0.016268 0.0814318 0.151023 0.0162135 0.0786668 0.150886 0.0160487 0.0814315 0.150898 0.0159944 0.0731097 0.151284 -0.0099556 0.094277 0.151047 0.016464 0.0814322 0.151048 0.016461 0.104886 0.150896 0.0159947 0.107122 0.151022 0.0162119 0.0942776 0.150895 0.0159953 0.0735083 0.151263 -0.0134646 0.0740859 0.151213 -0.0147017 0.0742234 0.151228 -0.0153529 0.0765114 0.151084 -0.017054 0.0760023 0.151078 -0.0165457 0.0781728 0.151045 -0.0174111 0.0814318 0.151023 -0.0171417 0.0786204 0.151015 -0.0171929 0.0783632 0.150888 -0.0169534 0.0806028 0.151046 -0.0174104 0.077265 0.151034 -0.0170086 0.0760982 0.15094 -0.0163498 0.0749202 0.151144 -0.0157587 0.0750624 0.151001 -0.0155988 0.0732108 0.151283 -0.0121291 0.0737016 0.151113 -0.013395 0.073412 0.151134 -0.0121055 0.109941 0.151015 0.0162632 0.109929 0.150886 0.0160438 0.111251 0.1509 0.0158615 0.109957 0.151042 0.0165165 0.111352 0.151062 0.0163271 0.111296 0.151033 0.0160772 0.112558 0.151078 0.0156128 0.112677 0.151112 0.0158401 0.114472 0.151213 0.0137661 0.115587 0.151335 0.0112278 0.113499 0.151001 0.0146617 0.113916 0.151033 0.0142014 0.113642 0.151145 0.0148214 0.115047 0.151263 0.0125309 0.094277 0.151047 -0.0173939 0.100442 0.151047 -0.0173937 0.0889732 0.150896 -0.0169251 0.107122 0.151022 -0.0171419 0.115241 0.151138 0.00902514 0.115344 0.151283 0.0111994 0.115587 0.151335 -0.0121577 0.115041 0.151263 -0.0134833 0.114458 0.151211 -0.0147239 0.113612 0.151142 -0.0157835 0.112632 0.151109 -0.0167969 0.109914 0.151041 -0.0174519 0.114847 0.151112 -0.0134134 0.114284 0.151063 -0.0146072 0.113471 0.150998 -0.0156224 0.112516 0.151076 -0.0165683 0.111246 0.151032 -0.0170218 0.1099 0.151015 -0.0171987 0.109888 0.150885 -0.0169791 0.115681 0.151335 -0.000464958 0.115686 0.151335 -0.00995619 0.115242 0.151139 -0.00882828 0.115444 0.151284 -0.0099556 0.115444 0.151284 0.00902565 0.115241 0.151143 -0.000463756 0.115344 0.151283 -0.0121293 0.115241 0.151138 -0.0099551 0.0749731 0.149518 -0.0119365 0.0747365 0.149719 -0.00995446 0.0749075 0.149628 -0.011944 0.0747386 0.149719 0.00789699 0.0748853 0.149516 -0.00995436 0.0748845 0.149518 0.00902442 0.0747416 0.14972 0.00371474 0.0750379 0.149755 -0.013057 0.0754442 0.149842 -0.0141143 0.0761946 0.149748 -0.0149328 0.0756327 0.149515 -0.0140437 0.0756501 0.149388 -0.0140456 0.0755907 0.149638 -0.0140551 0.0750138 0.149395 -0.0119322 0.0750278 0.14927 -0.0119315 0.0790126 0.15045 -0.0165074 0.0783115 0.150346 -0.0163477 0.0769571 0.150002 -0.0156627 0.0760636 0.149951 -0.0150237 0.0755261 0.14975 -0.0140793 0.0783475 0.149887 -0.0161422 0.0790873 0.150129 -0.0163262 0.0791059 0.150005 -0.0163154 0.0803738 0.150167 -0.0164436 0.0764722 0.149537 -0.0151316 0.0770426 0.149769 -0.0155859 0.077006 0.149892 -0.0156129 0.0790646 0.150249 -0.0163635 0.0814323 0.150457 -0.0165113 0.0790391 0.150359 -0.0164255 0.0749078 0.149628 0.0110141 0.0750278 0.149271 0.0110015 0.0749376 0.149275 0.00902434 0.0750139 0.149396 0.0110023 0.0942777 0.150659 -0.0166613 0.0889737 0.150659 -0.0166611 0.0942768 0.150213 -0.0164591 0.0814326 0.150216 -0.0164591 0.0769171 0.150093 0.0148122 0.076268 0.149497 0.0139978 0.0760771 0.14995 0.0141084 0.0762077 0.149747 0.0140171 0.0759501 0.149439 0.013606 0.0756403 0.149514 0.0131282 0.0791276 0.150006 0.0153892 0.0770594 0.149768 0.0146664 0.0800931 0.150137 0.0154988 0.0783047 0.150341 0.0154156 0.0748227 0.14972 0.0110243 0.0755334 0.149749 0.0131636 0.0755981 0.149637 0.0131394 0.0749732 0.149518 0.0110066 0.0754088 0.149335 0.0125793 0.0770229 0.149891 0.0146936 0.0790863 0.150249 0.0154373 0.079109 0.150129 0.0154 0.112346 0.149747 -0.0149471 0.111472 0.149642 -0.0155929 0.113447 0.149768 -0.0132912 0.112477 0.14995 -0.015039 0.112956 0.149637 -0.0140692 0.109444 0.150128 -0.0163301 0.111494 0.149768 -0.0155963 0.109838 0.149944 -0.0162372 0.111169 0.149699 -0.0157639 0.107121 0.150457 -0.0165114 0.107121 0.150215 -0.0164591 0.111531 0.149891 -0.0156237 0.111637 0.150093 -0.015743 0.107546 0.150654 -0.0166584 0.113646 0.149628 -0.011944 0.113021 0.149748 -0.0140935 0.112913 0.149513 -0.014058 0.112903 0.149384 -0.014047 0.112896 0.149386 -0.0140602 0.109466 0.150249 -0.0163677 0.0814323 0.150458 0.0155814 0.0942782 0.150659 0.0157314 0.0814326 0.150216 0.0155292 0.107121 0.150458 0.0155816 0.113669 0.149516 -0.00995437 0.113526 0.14927 -0.0119314 0.11354 0.149395 -0.0119322 0.113581 0.149517 -0.0119365 0.113646 0.149628 0.0110142 0.110247 0.150344 0.0154174 0.113028 0.149749 0.0131495 0.112359 0.149747 0.0140031 0.112963 0.149638 0.0131252 0.11354 0.149395 0.0110024 0.112921 0.149514 0.0131138 0.107122 0.15066 0.0157297 0.111548 0.149891 0.0146833 0.111376 0.150143 0.014966 0.111654 0.150093 0.014802 0.111511 0.149768 0.0146561 0.109466 0.150128 0.0153965 0.111207 0.149696 0.0148144 0.112088 0.149535 0.0141953 0.109488 0.150249 0.015434 0.108518 0.150131 0.015495 0.107121 0.150215 0.0155292 0.113816 0.149719 -0.00883285 0.113818 0.149719 -0.00995447 0.113616 0.149279 -0.00501982 0.113811 0.14972 -0.000468332 0.113669 0.149518 0.00902443 0.113616 0.149274 0.00902434 0.113581 0.149517 0.0110066 0.113103 0.14984 -0.0141286 0.114169 0.150049 -0.0109229 0.0743896 0.150046 0.00998918 0.113817 0.149719 0.00902451 0.115142 0.151134 0.0111757 0.114169 0.15031 0.0120803 0.114297 0.151065 0.013651 0.11311 0.149841 0.0131846 0.112843 0.150207 0.0141711 0.109539 0.150449 0.0155786 0.108651 0.150568 0.0156891 0.107122 0.150897 0.0159945 0.104886 0.150659 0.0157306 0.0995822 0.150659 0.0157312 0.0995816 0.150896 0.015995 0.0836696 0.150896 0.0159945 0.0836702 0.15066 0.0157303 0.0814321 0.15066 0.0157291 0.0790348 0.15045 0.0155812 0.0757153 0.150203 0.0141719 0.0747424 0.14972 -0.000467507 0.0733125 0.151144 -0.000462869 0.073312 0.15114 0.00790163 0.0733125 0.151138 -0.00995511 0.0747382 0.149719 -0.00883203 0.0743886 0.150308 -0.0130124 0.0742605 0.151065 -0.0145866 0.0746364 0.151034 -0.0151297 0.0786325 0.150887 -0.0169737 0.0799096 0.150568 -0.0166186 0.0814315 0.150898 -0.0169243 0.0814321 0.15066 -0.0166591 0.0836692 0.150896 -0.0169244 0.0836697 0.15066 -0.0166603 0.0942772 0.150895 -0.016925 0.104886 0.150659 -0.0166606 0.104885 0.150896 -0.0169247 0.107122 0.150897 -0.0169244 0.107122 0.15066 -0.0166597 0.109517 0.15045 -0.0165125 0.11026 0.150339 -0.0163437 0.111202 0.150899 -0.0168057 0.112421 0.150937 -0.0163714 0.115242 0.151139 0.00790074 0.113816 0.149719 0.00789616 0.115241 0.151142 -0.00464601 0.113812 0.14972 -0.00465059 0.115142 0.151133 -0.0121055 0.114169 0.150308 -0.0130132 0.113732 0.14972 -0.0119543 0.112843 0.150206 -0.0151046 0.112221 0.149994 -0.0152975 0.0757264 0.149891 -0.0145912 0.0771848 0.150145 -0.0158989 0.0773101 0.150901 -0.0167932 0.0757148 0.150207 -0.0151038 0.0768997 0.150094 -0.0157311 0.0748222 0.14972 -0.0119542 0.0743893 0.150045 -0.0109221 0.0747371 0.149719 0.00902449 0.074389 0.150306 0.0120811 0.0737064 0.151113 0.0124841 0.0751105 0.149768 0.012371 0.0754516 0.149841 0.0131987 0.0763411 0.149996 0.0143738 0.112832 0.14989 0.0136546 0.11249 0.14995 0.0140943 0.112346 0.149976 0.0142473 0.112462 0.15094 0.015417 0.113732 0.14972 0.0110244 0.113518 0.149754 0.01212 0.11417 0.15005 0.00998835 0.114853 0.151113 0.0124615 0.0830703 0.146758 0.0151853 0.0832392 0.146862 0.0152285 0.0829268 0.146434 0.0150512 0.0829603 0.1466 0.0151201 0.0829268 0.144586 0.0162858 0.0829934 0.144586 0.016535 0.0829934 0.132085 0.016535 0.0830706 0.144586 0.0166367 0.0831753 0.132085 0.0167179 0.0831753 0.144586 0.0167179 0.0834242 0.132085 0.0167858 0.0832397 0.144586 0.0167495 0.0832261 0.147044 -0.0125653 0.0829651 0.146778 0.0142858 0.083074 0.14694 0.0142858 0.0832349 0.147048 0.0116764 0.0832369 0.147049 0.0142858 0.0834242 0.147087 0.0123619 0.0832397 0.132085 0.0167495 0.0832392 0.131142 0.0165617 0.0830703 0.131185 0.0164575 0.0830706 0.132085 0.0166367 0.0829268 0.131319 0.0161336 0.0829603 0.130543 0.0158273 0.0829603 0.13125 0.0162999 0.0829603 0.14542 -0.0172298 0.0829268 0.144586 -0.0172157 0.0832392 0.145529 -0.0174917 0.0830703 0.145486 -0.0173874 0.0831753 0.144586 -0.0176479 0.0829603 0.146128 -0.0167572 0.0830702 0.146248 -0.0168778 0.083239 0.146328 -0.0169576 0.0834231 0.146354 -0.0169835 0.0829934 0.129835 0.0142858 0.0830706 0.129734 -0.0152157 0.0831753 0.129652 -0.0152157 0.0830706 0.129734 0.0142858 0.0831753 0.129652 0.0142858 0.0834242 0.129585 -0.0152157 0.0834242 0.144586 -0.0177157 0.0832397 0.144586 -0.0176794 0.0831753 0.132085 -0.0176479 0.0830706 0.144586 -0.0175666 0.0830706 0.132085 -0.0175666 0.0829934 0.144586 -0.017465 0.0829268 0.130237 -0.0159811 0.0832397 0.129621 -0.0152157 0.0829934 0.129835 -0.0152157 0.0829268 0.13067 -0.0166299 0.0829603 0.130543 -0.0167572 0.0829603 0.13007 -0.01605 0.0830703 0.129913 -0.0161153 0.083239 0.130343 -0.0169576 0.0832392 0.129809 -0.0161585 0.0869387 0.148236 -0.0162568 0.0864501 0.148535 -0.0164503 0.0849361 0.148235 -0.0154283 0.0858249 0.148535 -0.0162442 0.0862379 0.148236 -0.0160713 0.0839312 0.148535 -0.0148874 0.0837083 0.148235 -0.0139781 0.0833588 0.148235 -0.0130927 0.0830389 0.148234 -0.0109271 0.0830268 0.148234 -0.00994863 0.0827246 0.148535 -0.00994863 0.0840472 0.148235 0.0136095 0.0842285 0.148535 0.0142922 0.0834042 0.148235 0.0123077 0.0831352 0.148535 0.0124565 0.0832188 0.148235 0.0116069 0.082725 0.148535 0.00932617 0.0871159 0.14839 0.0155196 0.0853223 0.148535 0.0150872 0.08511 0.148235 0.0146162 0.131027 0.129034 -0.0154634 0.130727 0.129337 -0.0154634 0.130727 0.131837 0.0170335 0.131027 0.129952 0.0166086 0.131027 0.12959 0.0162099 0.130727 0.129491 0.0153988 0.130727 0.129398 0.0150823 0.130727 0.129337 0.0145335 0.131027 0.129762 -0.0173479 0.130727 0.129885 -0.0170252 0.130727 0.130972 -0.0178089 0.130727 0.131288 -0.0179024 0.130727 0.131837 -0.0179634 0.130727 0.144834 0.0170335 0.131027 0.147637 0.0145335 0.131027 0.147452 0.0155355 0.130727 0.145699 0.016879 0.130727 0.145383 0.0169725 0.130727 0.144834 -0.0179634 0.130727 0.145661 -0.0178225 0.131027 0.145836 -0.0180814 0.131027 0.146718 -0.0175386 0.130727 0.147179 -0.0163287 0.130727 0.147273 -0.0160122 0.111489 0.149642 0.0146528 0.111195 0.147204 0.0148009 0.110221 0.149883 0.0152081 0.10988 0.147074 0.0152791 0.109447 0.150004 0.0153855 0.111776 0.147234 0.0144343 0.112299 0.149496 0.0139837 0.112446 0.147238 0.0137874 0.112457 0.149468 0.0138 0.112903 0.149387 0.0131157 0.113526 0.14927 0.0110016 0.113258 0.149312 0.0122546 0.108459 0.150136 -0.0164288 0.107104 0.146954 -0.016442 0.10982 0.147068 -0.0162229 0.11189 0.149567 -0.0152973 0.110842 0.147171 -0.0158977 0.112286 0.149496 -0.0149276 0.111776 0.147234 -0.0153642 0.112604 0.149438 -0.0145356 0.113372 0.147243 -0.0127176 0.113605 0.147244 -0.00994362 0.113616 0.149274 -0.00995425 0.0773841 0.1497 0.0148339 0.0769276 0.148535 0.0145537 0.0767095 0.148535 0.0143942 0.0770816 0.149642 0.0146631 0.0761649 0.148535 0.0138711 0.0756579 0.149387 0.0131303 0.0758663 0.148535 0.0134716 0.0783613 0.148535 -0.016137 0.0770649 0.149643 -0.0155827 0.0769902 0.148535 -0.0155255 0.076255 0.149497 -0.0149136 0.0759081 0.148535 -0.0144642 0.0753153 0.148535 -0.0132283 0.075297 0.149313 -0.0131881 0.0749624 0.148535 -0.0111341 0.0841678 0.14709 0.0137634 0.083515 0.148235 0.0126162 0.0849271 0.148235 0.014492 0.0846797 0.147093 0.0142924 0.0853315 0.147056 0.0147428 0.0866127 0.146919 0.015244 0.0853315 0.148236 0.014749 0.0895268 0.148236 0.0155188 0.0885483 0.148236 0.0155067 0.086642 0.148236 0.0152584 0.0863828 0.148236 0.0151868 0.0830268 0.148234 0.00901872 0.0830352 0.148234 0.00988052 0.0830268 0.146886 0.00901166 0.0830268 0.147084 0.00901269 0.0865775 0.146922 -0.0161647 0.088665 0.148236 -0.0164404 0.0876727 0.146839 -0.0163662 0.0846797 0.147093 -0.0152223 0.0846403 0.148235 -0.0151944 0.0842555 0.148235 -0.0148055 0.0840536 0.148235 -0.0145484 0.0839294 0.148235 -0.0143655 0.0838529 0.147088 -0.0142355 0.0832872 0.148235 -0.0128335 0.0830398 0.146903 -0.0109456 0.0834242 0.147086 0.0142858 0.0834234 0.146896 0.0152425 0.0879732 0.146826 0.0154658 0.130727 0.146786 0.0160953 0.0834231 0.146354 0.0160536 0.130727 0.146159 0.0166534 0.0834242 0.144586 0.0167858 0.130727 0.147193 0.015361 0.108495 0.146981 0.015479 0.107104 0.146954 0.0155121 0.0834234 0.129775 0.0152425 0.0834231 0.130317 0.0160536 0.130727 0.129717 0.0158587 0.0834234 0.131128 0.0165955 0.130727 0.130275 0.0164856 0.130727 0.131009 0.0168925 0.130727 0.130512 -0.0175833 0.0834234 0.131128 -0.0175254 0.0834234 0.129775 -0.0161724 0.130727 0.129478 -0.0162909 0.0851384 0.147073 -0.0155581 0.0982693 0.146885 -0.0164417 0.0852948 0.147059 -0.0156519 0.130727 0.146954 -0.0167886 0.130727 0.146396 -0.0174156 0.0834234 0.145543 -0.0175254 0.0749376 0.149279 -0.000464957 0.0749415 0.148535 -0.00995039 0.0749376 0.149274 -0.00995425 0.0857663 0.148535 -0.0162209 0.0814414 0.148535 -0.0164503 0.0864501 0.148535 0.0155204 0.0814414 0.148535 0.0155204 0.0802577 0.148535 0.0154994 0.0783955 0.148535 0.0152169 0.0832337 0.148535 0.0127268 0.0781634 0.148535 0.0151466 0.0760677 0.148535 -0.0146822 0.0795668 0.148535 -0.0163727 0.0834387 0.148535 -0.0141147 0.0844415 0.148535 -0.015422 0.0750191 0.148535 0.010895 0.0827447 0.148535 0.0101939 0.0752547 0.148535 0.0121006 0.0749415 0.148535 0.00902047 0.0827246 0.148535 0.00901872 0.083 0.148535 -0.0129304 0.075245 0.148535 -0.0129963 0.0881116 0.150213 -0.0164591 0.0877353 0.148303 -0.0164491 0.0895268 0.148236 -0.0164487 0.0895268 0.146815 -0.0164413 0.113616 0.14928 -0.000464956 0.113605 0.147244 0.00901371 0.100442 0.150213 0.0155292 0.0982693 0.146885 0.0155117 0.0895268 0.146815 0.0155114 0.0942768 0.150213 0.0155292 0.130727 0.147334 0.0145335 0.113033 0.147241 0.0128117 0.130727 0.147334 -0.0154634 0.112892 0.14724 -0.0140348 0.113386 0.147243 0.0117293 0.113572 0.147244 -0.0113343 0.0834242 0.132085 -0.0177157 0.118027 0.137316 0.0476908 0.118027 0.138301 0.0471792 0.120343 0.138464 0.0469369 0.120544 0.137473 0.0474352 0.122628 0.138959 0.046191 0.124647 0.139709 0.0450208 0.12634 0.140632 0.0435164 0.128614 0.14061 0.0418665 0.128669 0.142731 0.0397721 0.12971 0.141689 0.0397112 0.130585 0.143789 -0.0359785 0.128635 0.140627 -0.0427634 0.128679 0.142744 -0.0406776 0.127706 0.141675 -0.0426464 0.12715 0.139607 -0.0446794 0.125303 0.138703 -0.0462909 0.123102 0.137968 -0.0475462 0.122704 0.138981 -0.0470862 0.130585 0.143789 0.0350486 0.130587 0.146015 0.0298246 0.130587 0.147862 0.0243821 0.129466 0.1448 0.0355263 0.130587 0.146015 -0.0307545 0.129466 0.146384 -0.0328661 0.130587 0.149775 0.0112278 0.129466 0.148937 0.0247014 0.130587 0.149294 -0.018804 0.129466 0.150404 -0.0189653 0.130587 0.149775 -0.0121577 0.131027 0.142701 0.0348598 0.130786 0.141714 0.037348 0.118027 0.116007 0.0478598 0.119687 0.136684 0.0477534 0.130598 0.116007 0.0381709 0.130113 0.140723 0.0396477 0.12901 0.13973 0.0418142 0.127524 0.138797 0.0437363 0.125549 0.116007 0.0454623 0.123785 0.13736 0.0465147 0.123599 0.116007 0.0466048 0.130598 0.116007 -0.0391008 0.131027 0.142724 -0.0357636 0.123346 0.137249 -0.0476516 0.125645 0.137953 -0.0463232 0.127566 0.138819 -0.0446213 0.128714 0.116007 -0.0431904 0.128716 0.139519 -0.0431879 0.129835 0.116007 -0.0412277 0.130848 0.141856 -0.0379358 0.115682 0.151335 0.00409083 0.115686 0.151335 0.00902627 0.115668 0.151335 0.0101285 0.115668 0.151335 -0.0110584 0.128405 0.151335 0.0112278 0.118027 0.116007 -0.0487897 -0.036373 0.116007 -0.0487897 0.118027 0.136625 -0.0487897 0.128405 0.149358 -0.0257564 0.128405 0.146791 -0.033033 0.122816 0.140991 -0.0443661 -0.0446678 0.141627 -0.0433255 -0.041055 0.140839 -0.0446095 -0.0401516 0.13935 -0.0468928 -0.045737 0.142692 -0.0414934 0.12822 0.1441 -0.038873 0.128405 0.145194 -0.036651 -0.0467421 0.144868 -0.037332 -0.0467516 0.145194 -0.036651 -0.0467516 0.146791 -0.033033 -0.0380825 0.138943 0.0465568 -0.041812 0.139925 0.0451016 -0.039982 0.139304 0.0460301 0.126321 0.141627 0.0423955 -0.0411628 0.140991 0.0434363 0.122709 0.140839 0.0436795 -0.0465668 0.1441 0.0379431 -0.0467516 0.145194 0.035721 0.128405 0.145194 0.035721 -0.0467516 0.146791 0.0321031 0.128405 0.149358 0.0248265 0.0665106 0.149358 0.0248265 0.0661919 0.149122 0.0256076 0.128405 0.146791 0.0321031 0.0639905 0.148976 0.0260752 0.0634604 0.149122 0.0256052 0.0488665 0.148906 0.0262954 0.048716 0.148907 0.0262922 0.0336706 0.148977 0.0260712 0.0341918 0.149122 0.0256076 0.0311431 0.149358 0.0248265 0.0319905 0.148976 0.0260752 0.0176706 0.148977 0.0260712 0.016716 0.148907 0.0262922 0.131027 0.146909 0.016418 0.131027 0.13016 -0.01771 0.131027 0.129139 0.0152954 0.131027 0.147531 -0.0162253 0.131027 0.14708 -0.0171398 0.131027 0.146845 -0.02501 0.131027 0.145025 -0.0303754 0.131027 0.142701 -0.0357897 0.131027 0.144834 -0.0182665 0.131027 0.131837 -0.0182665 0.131027 0.116007 -0.0357897 0.131027 0.131075 -0.018161 0.131027 0.129219 -0.0164654 0.131027 0.129034 0.0145335 0.131027 0.130835 0.0171514 0.131027 0.131837 0.0173366 0.131027 0.147637 -0.0154634 0.131027 0.145025 0.0294455 0.131027 0.144834 0.0173366 0.131027 0.145596 0.0172311 0.131027 0.14651 0.0167801 0.0829268 0.130085 -0.0152157 0.0829268 0.146586 -0.0152157 0.0829268 0.146 -0.0166299 0.0829268 0.145351 -0.0170635 0.0829268 0.146586 0.0142858 0.0829268 0.132085 0.0162858 0.0829268 0.130085 0.0142858 0.0830268 0.146886 -0.00994562 -0.0339338 0.151335 -0.0121577 0.0030616 0.151042 -0.0174449 0.00308588 0.151042 -0.0174434 0.00553738 0.1511 -0.0168889 0.00577728 0.151112 -0.0167687 0.00578927 0.151113 -0.0167623 0.0733878 0.151305 -0.0138633 0.0080627 0.151286 -0.0143222 0.0729667 0.151335 -0.0121577 -0.0296455 0.151061 -0.0172723 -0.0254682 0.151048 -0.0173916 -0.0187889 0.151047 -0.0173937 0.000221386 0.151048 -0.017391 0.000576395 0.151047 -0.017394 -0.0467516 0.150838 -0.0190286 0.000896008 0.151046 -0.017403 0.00298863 0.151041 -0.0174491 0.0753279 0.151144 -0.016429 0.0814322 0.151048 -0.017391 0.107122 0.151048 -0.0173916 0.111299 0.151061 -0.0172723 0.113786 0.151183 -0.0159703 0.128405 0.151335 -0.0121577 0.115277 0.151315 -0.0135647 0.114671 0.151259 -0.0148592 0.128405 0.150838 -0.0190286 0.113817 0.151186 0.0150065 0.115283 0.151315 0.0126118 0.114686 0.151261 0.0138994 0.107122 0.151048 0.0164616 0.0786416 0.151041 0.0165207 0.0881115 0.151047 0.0164637 0.0759234 0.151109 0.0158675 0.00688381 0.151183 0.0150409 0.00573023 0.151109 0.0158675 -0.00645792 0.151047 0.0164637 -0.0126234 0.151047 0.016464 -0.0254682 0.151048 0.0164616 -0.028303 0.151042 0.0165165 -0.0330321 0.151261 0.0138994 -0.0467516 0.149358 0.0248265 0.0183877 0.149619 0.0239147 0.018521 0.149386 0.0247317 0.0152386 0.149601 0.0239821 -0.0467516 0.150838 0.0180986 0.047143 0.149358 0.0248265 0.034521 0.149386 0.0247317 0.0178914 0.149795 0.0232604 0.0317142 0.149784 0.0233006 0.0632386 0.149601 0.0239821 0.0631431 0.149358 0.0248265 0.0338914 0.149795 0.0232604 0.0472386 0.149601 0.0239821 0.033174 0.149882 0.0229198 0.065174 0.149882 0.0229198 0.049174 0.149882 0.0229198 0.0658914 0.149795 0.0232604 0.128405 0.150838 0.0180986 0.066521 0.149386 0.0247317 0.0465529 0.151335 -0.00692841 0.00868689 0.151335 -0.0121577 0.0351007 0.151335 -0.00692841 0.0408268 0.151335 -0.00910004 0.0428933 0.151335 -0.00884912 0.0729671 0.151335 0.0112278 0.0448397 0.151335 0.00718103 0.0408268 0.151335 0.00817013 0.0368139 0.151335 0.00718103 0.0728865 0.151335 0.0101284 0.0728685 0.151335 0.00902627 0.0489007 0.151335 0.00259709 0.0493989 0.151335 0.000575887 0.0728728 0.151335 -0.000464958 0.0728719 0.151335 -0.00502075 0.0489007 0.151335 -0.003527 0.0728852 0.151335 -0.0110584 0.0351007 0.151335 0.0059985 0.00876708 0.151335 0.0101284 0.0327529 0.151335 -0.003527 0.0087684 0.151335 -0.0110584 0.0322547 0.151335 0.000575887 0.0327529 0.151335 0.00259709 0.00878075 0.151335 -0.000464958 0.00878511 0.151335 0.00902627 0.0842555 0.14709 -0.0147995 0.0834242 0.147086 -0.0152157 0.0834242 0.147087 -0.0132918 0.128567 0.112289 -0.0357897 0.118027 0.120535 0.0453567 0.118027 0.112289 0.0453998 -0.036373 0.112289 0.0453998 -0.036373 0.112289 -0.0463298 0.0829603 0.14542 0.0162999 0.0829268 0.146 0.0157 0.0829603 0.146128 0.0158273 0.0830703 0.145486 0.0164575 0.0830702 0.146248 0.0159479 0.083239 0.146328 0.0160277 0.0834234 0.145543 0.0165955 0.0829268 0.145351 0.0161336 0.0832392 0.145529 0.0165617 0.0829268 0.130237 0.0150512 0.0829268 0.13067 0.0157 0.0830702 0.130422 0.0159479 0.0832392 0.129809 0.0152285 0.083239 0.130343 0.0160277 0.0829603 0.13007 0.0151201 0.0830703 0.129913 0.0151853 0.0832397 0.129621 0.0142858 0.0834242 0.129585 0.0142858 0.0829268 0.146434 -0.0159811 0.0830703 0.146758 -0.0161153 0.0834234 0.146896 -0.0161724 0.0829603 0.1466 -0.01605 0.0829651 0.146778 -0.0152157 0.083074 0.14694 -0.0152157 0.0832369 0.147049 -0.0152157 0.0832392 0.146862 -0.0161585 0.0829268 0.131319 -0.0170635 0.0830703 0.131185 -0.0173874 0.0830702 0.130422 -0.0168778 0.0832392 0.131142 -0.0174917 0.0834231 0.130317 -0.0169835 0.0829268 0.132085 -0.0172157 0.0829934 0.132085 -0.017465 0.0829603 0.13125 -0.0172298 0.0832397 0.132085 -0.0176794 -0.00130673 0.14542 0.0162999 -0.0012732 0.144586 0.0162858 -0.00176978 0.145543 0.0165955 -0.00158557 0.145529 0.0165617 -0.00141669 0.145486 0.0164575 -0.00152169 0.144586 0.0167179 -0.00133975 0.144586 0.016535 -0.0012732 0.130237 0.0150512 -0.00130671 0.130543 0.0158273 -0.00130673 0.13007 0.0151201 -0.00176978 0.129775 0.0152425 -0.00158557 0.129809 0.0152285 -0.00158536 0.130343 0.0160277 -0.00133975 0.129835 0.0142858 -0.00141659 0.130422 0.0159479 -0.00158615 0.129621 0.0142858 -0.00141669 0.129913 0.0151853 -0.00158557 0.146862 -0.0161585 -0.00158536 0.146328 -0.0169576 -0.00130673 0.1466 -0.01605 -0.00130671 0.146128 -0.0167572 -0.0012732 0.146434 -0.0159811 -0.00177058 0.147086 -0.0152157 -0.00141669 0.146758 -0.0161153 -0.0012732 0.131319 -0.0170635 -0.00130671 0.130543 -0.0167572 -0.00141659 0.130422 -0.0168778 -0.00176978 0.131128 -0.0175254 -0.00141669 0.131185 -0.0173874 -0.00130673 0.13125 -0.0172298 -0.00158557 0.131142 -0.0174917 -0.00152169 0.132085 -0.0176479 -0.00141697 0.132085 -0.0175666 0.037109 0.150375 -0.00754861 0.037109 0.116935 -0.00754861 0.0328851 0.116935 -0.00142925 0.0328851 0.150375 -0.00142925 0.0328851 0.150375 0.000499336 0.0333467 0.150375 0.00237188 0.0342429 0.150375 0.00407956 0.0355218 0.150375 0.00552313 0.0355218 0.116935 0.00552313 0.0408268 0.150375 0.00753504 0.0427413 0.150375 0.00730258 0.0445446 0.150375 0.00661869 0.0427413 0.116935 0.00730258 0.0461318 0.116935 0.00552313 0.0461318 0.150375 0.00552313 0.0483069 0.116935 0.00237188 0.0487685 0.150375 0.000499336 0.0487685 0.150375 -0.00142925 0.0487685 0.116935 -0.00142925 0.0474107 0.116935 -0.00500948 0.0474107 0.150375 -0.00500948 0.0445446 0.116935 -0.00754861 0.0408268 0.116935 -0.00846496 0.0175781 0.149639 0.0232369 0.0168268 0.149697 0.023035 0.0181258 0.116935 0.025285 0.017578 0.148788 0.0258335 0.018126 0.148981 0.0252847 0.0160768 0.116935 0.0258341 0.0162932 0.14875 0.0259369 0.0168268 0.148715 0.026035 0.0175768 0.116935 0.0258341 0.0155278 0.116935 0.025285 0.0158327 0.14885 0.0256583 0.0160758 0.148788 0.0258333 0.0153857 0.14937 0.024119 0.0160768 0.116935 0.023236 0.0155278 0.116935 0.023785 0.0155271 0.149474 0.0237862 0.0161576 0.149652 0.0231926 0.0168268 0.116935 0.023035 0.016076 0.149639 0.0232366 0.0156111 0.149514 0.0236564 0.0175768 0.116935 0.023236 0.0174595 0.149657 0.023175 0.0181258 0.116935 0.023785 0.0183268 0.116935 0.024535 0.0338037 0.149592 0.023397 0.0328268 0.116935 0.023035 0.0338229 0.148851 0.0256566 0.0341258 0.116935 0.025285 0.0341505 0.148996 0.0252405 0.0333634 0.148751 0.0259358 0.0315278 0.116935 0.025285 0.0313268 0.116935 0.024535 0.0315278 0.116935 0.023785 0.0315271 0.149474 0.0237862 0.0328268 0.149697 0.023035 0.032076 0.149639 0.0232366 0.0341258 0.116935 0.023785 0.0343125 0.149166 0.024742 0.0495768 0.116935 0.023236 0.0491271 0.149688 0.0230654 0.0488268 0.116935 0.023035 0.049578 0.148788 0.0258335 0.0503125 0.149166 0.024742 0.0482932 0.14875 0.0259369 0.0488268 0.148715 0.026035 0.0495768 0.116935 0.0258341 0.0478327 0.14885 0.0256583 0.0480768 0.116935 0.0258341 0.0475278 0.116935 0.025285 0.0475278 0.116935 0.023785 0.0475271 0.149474 0.0237862 0.0488268 0.149697 0.023035 0.0481935 0.149657 0.0231753 0.0481576 0.149652 0.0231926 0.0480768 0.116935 0.023236 0.0498037 0.149592 0.023397 0.0499695 0.149542 0.0235633 0.0503268 0.149235 0.0245358 0.0503268 0.116935 0.024535 0.0502682 0.14937 0.0241199 0.0501258 0.116935 0.023785 0.0502262 0.149409 0.023995 0.0501268 0.149474 0.0237867 0.0655781 0.149639 0.0232369 0.0661258 0.116935 0.025285 0.0648268 0.116935 0.026035 0.0655768 0.116935 0.0258341 0.0638327 0.14885 0.0256583 0.0640768 0.116935 0.0258341 0.0642932 0.14875 0.0259369 0.0633411 0.149166 0.024742 0.0635276 0.148981 0.0252847 0.0635278 0.116935 0.023785 0.0635271 0.149474 0.0237862 0.0640768 0.116935 0.023236 0.0641576 0.149652 0.0231926 0.064076 0.149639 0.0232366 0.0648268 0.116935 0.023035 0.0654595 0.149657 0.023175 0.0651271 0.149688 0.0230654 0.0655768 0.116935 0.023236 0.0661267 0.149474 0.0237867 0.0663268 0.116935 0.024535 0.0369346 0.151185 -0.0078809 0.0354685 0.150675 -0.00651321 0.035273 0.151185 -0.00673394 0.0329958 0.151185 -0.00343487 0.0328053 0.150675 -0.00143894 0.0325126 0.151185 0.000544571 0.0332715 0.150675 0.00240039 0.0339341 0.151185 0.00429274 0.0354685 0.150675 0.0055833 0.0388225 0.151185 0.00766695 0.0408268 0.150675 0.00761543 0.0408268 0.151185 0.00791032 0.044719 0.151185 0.00695098 0.0463806 0.151185 0.00580403 0.0486578 0.151185 0.00250496 0.0483821 0.150675 -0.0033303 0.0477195 0.151185 -0.00522266 0.0461851 0.150675 -0.00651321 0.0463806 0.151185 -0.00673394 0.0445819 0.150675 -0.00761978 0.0427606 0.150675 -0.00831054 0.0408268 0.151185 -0.00884023 0.0388225 0.151185 -0.00859686 0.0368836 0.151295 -0.00797813 0.0352001 0.151295 -0.00681613 0.0339341 0.151185 -0.00522266 0.0328931 0.151295 -0.00347381 0.0324036 0.151295 -0.00148772 0.0325126 0.151185 -0.00147449 0.0324036 0.151295 0.000557807 0.0329958 0.151185 0.00250496 0.0338437 0.151295 0.00435512 0.0352001 0.151295 0.00588622 0.035273 0.151185 0.00580403 0.0369346 0.151185 0.00695098 0.0387962 0.151295 0.00777357 0.0408268 0.151295 0.00802013 0.0428311 0.151185 0.00766695 0.0478099 0.151295 0.00435512 0.0487605 0.151295 0.0025439 0.0477195 0.151185 0.00429274 0.049141 0.151185 0.000544571 0.049141 0.151185 -0.00147449 0.04925 0.151295 -0.00148772 0.0486578 0.151185 -0.00343487 0.04477 0.151295 -0.00797813 0.044719 0.151185 -0.0078809 0.0428311 0.151185 -0.00859686 0.0408268 0.151295 -0.00895004 0.0387603 0.151335 -0.00884912 0.0387962 0.151295 -0.00870348 0.0368139 0.151335 -0.00811095 0.0337203 0.151335 -0.00537024 0.0338437 0.151295 -0.00528503 0.0322547 0.151335 -0.0015058 0.0328931 0.151295 0.0025439 0.0337203 0.151335 0.00444033 0.0368836 0.151295 0.00704821 0.0387603 0.151335 0.00791921 0.0428933 0.151335 0.00791921 0.0428574 0.151295 0.00777357 0.04477 0.151295 0.00704821 0.0464534 0.151295 0.00588622 0.0465529 0.151335 0.0059985 0.0479333 0.151335 0.00444033 0.04925 0.151295 0.000557807 0.0493989 0.151335 -0.0015058 0.0479333 0.151335 -0.00537024 0.0487605 0.151295 -0.00347381 0.0478099 0.151295 -0.00528503 0.0464534 0.151295 -0.00681613 0.0448397 0.151335 -0.00811095 0.0428574 0.151295 -0.00870348 0.038893 0.150675 0.00738063 0.037109 0.150375 0.00661869 0.0370717 0.150675 0.00668987 0.0341768 0.150675 0.00412522 0.0328053 0.150675 0.000509026 0.0333467 0.150375 -0.0033018 0.0332715 0.150675 -0.0033303 0.0342429 0.150375 -0.00500948 0.0341768 0.150675 -0.00505514 0.0355218 0.150375 -0.00645304 0.0389123 0.150375 -0.00823249 0.0370717 0.150675 -0.00761978 0.038893 0.150675 -0.00831054 0.0408268 0.150375 -0.00846496 0.0408268 0.150675 -0.00854534 0.0427413 0.150375 -0.00823249 0.0445446 0.150375 -0.00754861 0.0461318 0.150375 -0.00645304 0.0474768 0.150675 -0.00505514 0.0483069 0.150375 -0.0033018 0.0488483 0.150675 -0.00143894 0.0488483 0.150675 0.000509026 0.0483069 0.150375 0.00237188 0.0483821 0.150675 0.00240039 0.0474768 0.150675 0.00412522 0.0474107 0.150375 0.00407956 0.0461851 0.150675 0.0055833 0.0445819 0.150675 0.00668987 0.0427606 0.150675 0.00738063 0.0389123 0.150375 0.00730258 0.0320768 0.116935 0.023236 0.0335768 0.116935 0.023236 -0.040374 0.116935 0.015285 0.0495768 0.116935 0.015285 0.0335768 0.116935 0.0258341 0.0473268 0.116935 0.024535 0.0343268 0.116935 0.024535 -0.039838 0.116935 0.0368603 -0.040374 0.116935 0.0348598 0.0153268 0.116935 0.024535 0.0168268 0.116935 0.026035 0.0320768 0.116935 0.0258341 0.0495768 0.116935 0.0388609 0.0328268 0.116935 0.026035 0.122028 0.116935 0.015285 0.0661258 0.116935 0.023785 0.121723 0.116935 0.0363909 0.0488268 0.116935 0.026035 0.0635278 0.116935 0.025285 0.0501258 0.116935 0.025285 0.0633268 0.116935 0.024535 0.120856 0.116935 -0.0386189 0.119558 0.116935 -0.0394862 0.122028 0.116935 -0.0357897 0.0495768 0.116935 -0.0397908 0.0342429 0.116935 -0.00500948 -0.036373 0.116935 -0.0397908 -0.039838 0.116935 -0.0377902 -0.040374 0.116935 -0.0357897 0.0333467 0.116935 0.00237188 0.0389123 0.116935 0.00730258 0.0408268 0.116935 0.00753504 -0.040374 0.120535 0.0348598 -0.040374 0.120535 -0.0357897 -0.0383735 0.116935 0.0383248 0.118027 0.116935 0.0388609 0.118027 0.120535 0.0388609 -0.036373 0.120535 0.0388609 -0.036373 0.116935 0.0388609 0.122028 0.116935 0.0348598 0.122028 0.120535 0.0348598 0.120856 0.116935 0.037689 0.119558 0.116935 0.0385563 0.121723 0.116935 -0.0373209 0.122028 0.120535 -0.0357897 0.118027 0.116935 -0.0397908 -0.0383735 0.120535 -0.0392547 -0.0383735 0.116935 -0.0392547 0.183902 -0.0116155 0.077235 0.183902 -0.0116155 0.084235 0.177643 -0.000500042 0.084235 0.177643 -0.000500042 0.077235 0.434327 0.00559996 0.077235 0.434327 -0.00240004 0.077235 0.416931 -0.018 0.084235 0.371203 -0.0138616 0.081235 0.401851 -0.0169616 0.084235 0.39524 -0.0161001 0.081235 0.363203 -0.0134248 0.081235 0.340411 -0.0130183 0.081235 0.371203 -0.0138616 0.084235 0.309639 -0.0144362 0.084235 0.331056 -0.0132099 0.081235 0.309639 -0.0144362 0.081235 0.279054 -0.0181076 0.084235 0.248821 -0.0240128 0.081235 0.246826 -0.0243659 0.08112 0.244827 -0.0245 0.084235 0.240821 -0.024118 0.084235 0.244827 -0.0245 0.0807813 0.188018 -0.0132323 0.077235 0.434327 -0.00560004 0.077235 0.433383 -0.0103453 0.077235 0.250577 0.001299 0.077235 0.249827 -0.00150004 0.077235 0.248528 0.000749958 0.077235 0.192501 -0.00165004 0.077235 0.221969 -0.00165004 0.077235 0.178395 -0.0048583 0.077235 0.248327 -4.19898e-08 0.077235 0.248528 -0.000750042 0.077235 0.224827 0.00329996 0.077235 0.223177 0.00285784 0.077235 0.266449 0.0162198 0.077235 0.251327 -4.19898e-08 0.077235 0.188018 0.0132322 0.077235 0.187993 0.00285784 0.077235 0.178395 0.00485822 0.077235 0.186785 0.00164996 0.077235 0.187993 -0.00285793 0.077235 0.180565 -0.00871213 0.077235 0.189643 -0.00330004 0.077235 0.235915 -0.0231067 0.077235 0.325677 -0.00240004 0.077235 0.426633 -0.0170724 0.077235 0.403327 -0.00330004 0.077235 0.430695 -0.0143682 0.077235 0.427977 -0.00285793 0.077235 0.426327 -0.00330004 0.077235 0.424677 -0.00285793 0.077235 0.429185 -0.00165004 0.077235 0.429627 -4.19898e-08 0.077235 0.429185 0.00164996 0.077235 0.430695 0.0143681 0.077235 0.426327 0.00329996 0.077235 0.406185 0.00164996 0.077235 0.404977 0.00285784 0.077235 0.423469 0.00164996 0.077235 0.426633 0.0170723 0.077235 0.426672 0.0170561 0.077235 0.403327 0.00329996 0.077235 0.395725 0.0121295 0.077235 0.400469 0.00164996 0.077235 0.278899 0.0171197 0.085235 0.249827 -0.00150004 0.085235 0.224827 0.00639996 0.085235 0.230369 0.00319996 0.085235 0.231227 -4.19898e-08 0.085235 0.248528 -0.000750042 0.085235 0.250577 0.001299 0.085235 0.251126 0.000749958 0.085235 0.251327 -4.19898e-08 0.085235 0.251126 -0.000750042 0.085235 0.181341 0.00808035 0.085235 0.184101 0.00319996 0.085235 0.192843 0.00554252 0.085235 0.241023 0.0231385 0.085235 0.189643 0.00639996 0.085235 0.186443 0.00554252 0.085235 0.18442 0.0107604 0.085235 0.249827 0.00149996 0.085235 0.249077 0.001299 0.085235 0.196043 -4.19898e-08 0.085235 0.195186 -0.00320004 0.085235 0.278899 -0.0171198 0.085235 0.178643 0.000499958 0.085235 0.178643 -0.000500042 0.085235 0.186443 -0.0055426 0.085235 0.244814 -0.0235001 0.085235 0.228027 -0.0055426 0.085235 0.248593 -0.0230391 0.085235 0.224827 -0.00640004 0.085235 0.18822 -0.0122529 0.085235 0.340401 0.0120183 0.085235 0.400127 0.00554252 0.085235 0.421927 0.017 0.085235 0.420784 -0.00320004 0.085235 0.426327 0.00639996 0.085235 0.431869 0.00319996 0.085235 0.432727 -4.19898e-08 0.085235 0.433327 -0.00395004 0.085235 0.429527 -0.0055426 0.085235 0.433327 -0.00560004 0.085235 0.432459 -0.00996263 0.085235 0.429988 -0.0136611 0.085235 0.426289 -0.0161323 0.085235 0.426327 -0.00640004 0.085235 0.421927 -0.017 0.085235 0.403327 -0.00640004 0.085235 0.400127 -0.0055426 0.085235 0.340401 -0.0120184 0.085235 0.324127 -0.00395004 0.085235 0.177643 0.000499958 0.084235 0.177643 0.000499958 0.077235 0.178395 0.00485822 0.084235 0.180565 0.00871205 0.077235 0.183902 0.0116154 0.077235 0.240821 0.0241179 0.0794443 0.244827 0.0245 0.084235 0.248821 0.0240127 0.084235 0.248821 0.0240127 0.081235 0.267184 0.0201517 0.081235 0.309639 0.0144361 0.084235 0.309639 0.0144361 0.081235 0.363203 0.0134247 0.081235 0.371203 0.0138615 0.084235 0.401851 0.0169615 0.084235 0.409401 0.017742 0.0809047 0.416931 0.018 0.084235 0.416931 0.018 0.0799264 0.424404 0.01775 0.0783278 0.421927 0.018 0.084235 0.430695 0.0143681 0.084235 0.433383 0.0103452 0.077235 0.426672 -0.0170561 0.077235 0.421927 -0.018 0.084235 0.421927 -0.018 0.0790359 0.426672 -0.0170561 0.084235 0.433383 -0.0103453 0.084235 0.434327 -0.00560004 0.084235 0.186343 -4.19898e-08 0.077235 0.186785 0.00164996 0.082135 0.186785 -0.00165004 0.077235 0.189643 -0.00330004 0.082135 0.191293 -0.00285793 0.077235 0.192943 -4.19898e-08 0.077235 0.192501 0.00164996 0.077235 0.191293 0.00285784 0.082135 0.191293 0.00285784 0.077235 0.189643 0.00329996 0.077235 0.189643 0.00329996 0.082135 0.183243 -4.19898e-08 0.085235 0.186343 -4.19898e-08 0.082135 0.186785 -0.00165004 0.082135 0.184101 -0.00320004 0.085235 0.187993 -0.00285793 0.082135 0.191293 -0.00285793 0.082135 0.189643 -0.00640004 0.085235 0.192843 -0.0055426 0.085235 0.192501 -0.00165004 0.082135 0.192943 -4.19898e-08 0.082135 0.192501 0.00164996 0.082135 0.195186 0.00319996 0.085235 0.187993 0.00285784 0.082135 0.224827 0.00329996 0.082135 0.221969 0.00164996 0.077235 0.221969 0.00164996 0.082135 0.221527 -4.19898e-08 0.082135 0.221527 -4.19898e-08 0.077235 0.221969 -0.00165004 0.082135 0.223177 -0.00285793 0.082135 0.223177 -0.00285793 0.077235 0.224827 -0.00330004 0.082135 0.224827 -0.00330004 0.077235 0.226477 -0.00285793 0.077235 0.227685 -0.00165004 0.077235 0.228127 -4.19898e-08 0.082135 0.228127 -4.19898e-08 0.077235 0.227685 0.00164996 0.077235 0.227685 0.00164996 0.082135 0.226477 0.00285784 0.082135 0.226477 0.00285784 0.077235 0.221627 0.00554252 0.085235 0.219284 0.00319996 0.085235 0.218427 -4.19898e-08 0.085235 0.219284 -0.00320004 0.085235 0.221627 -0.0055426 0.085235 0.226477 -0.00285793 0.082135 0.230369 -0.00320004 0.085235 0.227685 -0.00165004 0.082135 0.228027 0.00554252 0.085235 0.223177 0.00285784 0.082135 0.401677 0.00285784 0.077235 0.400027 -4.19898e-08 0.077235 0.400469 0.00164996 0.082135 0.400027 -4.19898e-08 0.082135 0.400469 -0.00165004 0.077235 0.401677 -0.00285793 0.077235 0.403327 -0.00330004 0.082135 0.404977 -0.00285793 0.077235 0.404977 -0.00285793 0.082135 0.406185 -0.00165004 0.077235 0.406185 -0.00165004 0.082135 0.406627 -4.19898e-08 0.077235 0.406627 -4.19898e-08 0.082135 0.403327 0.00329996 0.082135 0.397784 0.00319996 0.085235 0.396927 -4.19898e-08 0.085235 0.400469 -0.00165004 0.082135 0.397784 -0.00320004 0.085235 0.401677 -0.00285793 0.082135 0.406527 -0.0055426 0.085235 0.408869 -0.00320004 0.085235 0.409727 -4.19898e-08 0.085235 0.406185 0.00164996 0.082135 0.408869 0.00319996 0.085235 0.404977 0.00285784 0.082135 0.406527 0.00554252 0.085235 0.403327 0.00639996 0.085235 0.401677 0.00285784 0.082135 0.426327 0.00329996 0.082135 0.424677 0.00285784 0.077235 0.423027 -4.19898e-08 0.077235 0.423469 -0.00165004 0.077235 0.429185 -0.00165004 0.082135 0.427977 0.00285784 0.077235 0.424677 0.00285784 0.082135 0.423469 0.00164996 0.082135 0.420784 0.00319996 0.085235 0.423027 -4.19898e-08 0.082135 0.419927 -4.19898e-08 0.085235 0.423469 -0.00165004 0.082135 0.424677 -0.00285793 0.082135 0.423127 -0.0055426 0.085235 0.426327 -0.00330004 0.082135 0.427977 -0.00285793 0.082135 0.429627 -4.19898e-08 0.082135 0.431869 -0.00320004 0.085235 0.429185 0.00164996 0.082135 0.429527 0.00554252 0.085235 0.427977 0.00285784 0.082135 0.423127 0.00554252 0.085235 0.279054 0.0181075 0.084235 0.340411 0.0130182 0.084235 0.309556 0.0134395 0.085235 0.371267 0.0128636 0.085235 0.401988 0.0159709 0.085235 0.248593 0.023039 0.085235 0.244814 0.0235 0.085235 0.240821 0.0241179 0.084235 0.416931 0.017 0.085235 0.18822 0.0122528 0.085235 0.188018 0.0132322 0.084235 0.183902 0.0116154 0.084235 0.180565 0.00871205 0.084235 0.179338 0.00452297 0.085235 0.433327 0.00559996 0.085235 0.432459 0.00996255 0.085235 0.433383 0.0103452 0.084235 0.429988 0.013661 0.085235 0.426672 0.0170561 0.084235 0.426289 0.0161322 0.085235 0.434327 0.00559996 0.084235 0.178395 -0.0048583 0.084235 0.179338 -0.00452305 0.085235 0.180565 -0.00871213 0.084235 0.181341 -0.00808043 0.085235 0.18442 -0.0107604 0.085235 0.188018 -0.0132323 0.084235 0.430695 -0.0143682 0.084235 0.416931 -0.017 0.085235 0.241023 -0.0231386 0.085235 0.248821 -0.0240128 0.084235 0.401988 -0.015971 0.085235 0.371267 -0.0128637 0.085235 0.340411 -0.0130183 0.084235 0.309556 -0.0134396 0.085235 0.244827 0.0245 0.0807813 0.246821 0.0243665 0.0811193 0.235915 0.0231066 0.077235 0.421927 0.018 0.0790359 0.279054 0.0181075 0.081235 0.298555 0.01148 0.077235 0.298987 0.0154565 0.081235 0.33093 0.00921184 0.077235 0.331056 0.0132098 0.081235 0.363383 0.00942879 0.077235 0.340411 0.0130182 0.081235 0.371203 0.0138615 0.081235 0.39524 0.0161 0.081235 0.401851 0.0169615 0.081235 0.424387 -0.0177535 0.0783343 0.416931 -0.018 0.0799264 0.409401 -0.017742 0.0809047 0.401851 -0.0169616 0.081235 0.395725 -0.0121296 0.077235 0.363383 -0.00942888 0.077235 0.33093 -0.00921193 0.077235 0.298555 -0.01148 0.077235 0.298987 -0.0154566 0.081235 0.279054 -0.0181076 0.081235 0.266449 -0.0162199 0.077235 0.267184 -0.0201517 0.081235 0.240821 -0.024118 0.0794443 0.249077 -0.00129908 0.085235 0.249077 -0.00129908 0.077235 0.248327 -4.19898e-08 0.085235 0.248528 0.000749958 0.085235 0.249077 0.001299 0.077235 0.249827 0.00149996 0.077235 0.251126 0.000749958 0.077235 0.250577 -0.00129908 0.085235 0.251126 -0.000750042 0.077235 0.250577 -0.00129908 0.077235 -0.137975 0.0547289 0.081935 -0.138579 0.054125 0.081935 -0.138579 0.054125 0.08486 -0.1388 0.0533 0.08486 -0.137975 0.051871 0.081935 -0.138579 0.052475 0.08486 -0.13715 0.05165 0.081935 -0.136325 0.051871 0.08486 -0.135721 0.052475 0.081935 -0.135721 0.052475 0.08486 -0.1355 0.0533 0.081935 -0.135721 0.054125 0.081935 -0.136325 0.0547289 0.081935 -0.13715 0.05495 0.081935 -0.13715 0.05495 0.08486 -0.0687996 0.05495 0.08486 -0.0696246 0.0547289 0.081935 -0.0696246 0.0547289 0.08486 -0.0702285 0.054125 0.081935 -0.0704496 0.0533 0.081935 -0.0702285 0.054125 0.08486 -0.0702285 0.052475 0.081935 -0.0702285 0.052475 0.08486 -0.0696246 0.051871 0.08486 -0.0687996 0.05165 0.081935 -0.0679746 0.051871 0.081935 -0.0679746 0.0547289 0.081935 -0.0687996 0.05495 0.081935 -0.137975 0.0014289 0.081935 -0.137975 0.0014289 0.08486 -0.138579 0.000824958 0.081935 -0.1388 -4.19898e-08 0.081935 -0.138579 -0.000825042 0.081935 -0.137975 -0.00142898 0.081935 -0.13715 -0.00165004 0.08486 -0.135721 -0.000825042 0.081935 -0.1355 -4.19898e-08 0.081935 -0.135721 0.000824958 0.081935 -0.13715 0.00164996 0.081935 -0.0687996 0.00164996 0.081935 -0.0704496 -4.19898e-08 0.081935 -0.0702285 -0.000825042 0.08486 -0.0687996 -0.00165004 0.081935 -0.0696246 -0.00142898 0.08486 -0.0679746 -0.00142898 0.081935 -0.0673706 -0.000825042 0.081935 -0.0671496 -4.19898e-08 0.081935 -0.0671496 -4.19898e-08 0.08486 -0.0673706 0.000824958 0.08486 -0.0687996 0.00164996 0.08486 -0.13715 -0.05165 0.08486 -0.137975 -0.0518711 0.08486 -0.138579 -0.052475 0.081935 -0.1388 -0.0533 0.08486 -0.137975 -0.054729 0.08486 -0.13715 -0.05495 0.081935 -0.13715 -0.05495 0.08486 -0.1355 -0.0533 0.081935 -0.135721 -0.052475 0.081935 -0.1355 -0.0533 0.08486 -0.13715 -0.05165 0.081935 -0.0687996 -0.05165 0.081935 -0.0702285 -0.052475 0.08486 -0.0704496 -0.0533 0.08486 -0.0702285 -0.054125 0.081935 -0.0687996 -0.05495 0.081935 -0.0679746 -0.054729 0.081935 -0.0673706 -0.054125 0.081935 -0.0671496 -0.0533 0.08486 -0.0671496 -0.0533 0.081935 -0.0673706 -0.052475 0.08486 -0.0679746 -0.0518711 0.08486 0.172668 0.0762251 0.084435 0.175357 0.0789142 0.084435 -0.177704 0.0789142 0.084435 -0.175015 0.0762251 0.081935 -0.175015 -0.0762252 0.081935 0.172668 -0.0762252 0.081935 0.171533 -0.0754665 0.081935 -0.17254 -0.0752 0.084435 -0.173879 -0.0754665 0.081935 -0.17254 0.0752 0.081935 -0.173879 0.0754664 0.084435 0.171533 0.0754664 0.084435 -0.15749 0.0356837 0.078935 -0.159173 0.034 0.078935 -0.15749 0.0356837 0.084735 -0.15519 0.0363 0.078935 -0.14684 0.0334603 0.084735 -0.147106 0.034 0.078935 -0.149329 0.0359498 0.084735 -0.14649 0.0317 0.078935 -0.14879 -0.0356838 0.084735 -0.147837 -0.0349527 0.084735 -0.147837 -0.0349527 0.078935 -0.147106 -0.034 0.084735 -0.14649 -0.0317 0.084735 -0.14684 -0.0334604 0.078935 -0.14649 -0.0317 0.078935 -0.15519 -0.0363 0.078935 -0.15109 -0.0363 0.078935 -0.15109 -0.0363 0.084735 -0.159439 -0.0334604 0.078935 -0.159439 -0.0334604 0.084735 -0.158442 -0.0349527 0.078935 -0.158442 -0.0349527 0.084735 -0.15519 -0.0363 0.084735 -0.15979 0.0317 0.084735 -0.15979 -4.19898e-08 0.078935 -0.15979 -0.0317 0.084735 -0.15979 -0.0317 0.078935 0.176772 0.0795 0.084435 0.176006 0.0793477 0.081935 0.176006 0.0793477 0.084435 -0.177704 -0.0789143 0.084435 -0.178353 -0.0793478 0.084435 -0.177704 -0.0789143 0.081935 0.176772 -0.0795 0.081935 0.176006 -0.0793478 0.084435 0.175357 -0.0789143 0.084435 0.175357 -0.0789143 0.081935 0.207927 -0.06875 0.078935 0.212552 -0.05959 0.078935 0.209052 0.0729485 0.078935 0.212552 0.0795 0.078935 0.212552 0.034275 0.078935 0.214723 0.0198353 0.078935 0.214152 0.0191346 0.078935 0.214927 0.0207157 0.078935 0.213331 0.0187569 0.078935 0.214927 0.034275 0.078935 0.214927 0.0775 0.078935 0.212927 0.0795 0.078935 0.213927 0.079232 0.078935 -0.212222 0.072125 0.078935 -0.209148 0.0729485 0.078935 -0.201131 0.0795 0.078935 -0.212523 0.071 0.078935 -0.211398 0.0690514 0.078935 -0.210273 0.07325 0.078935 -0.211398 0.0729485 0.078935 -0.216039 0.0793477 0.078935 -0.209148 0.0690514 0.078935 -0.201131 0.05959 0.078935 -0.208325 0.069875 0.078935 -0.217273 0.0775 0.078935 -0.216687 0.0789142 0.078935 -0.216498 0.0191346 0.078935 -0.215677 0.0187569 0.078935 -0.193938 0.031125 0.078935 -0.18974 0.03 0.078935 -0.174765 0.034275 0.078935 -0.190041 0.031125 0.078935 -0.193115 0.0280514 0.078935 -0.19199 0.02775 0.078935 -0.174765 -4.19898e-08 0.078935 -0.190865 -0.0280515 0.078935 -0.17969 0.000499958 0.078935 -0.18974 -0.03 0.078935 -0.193115 -0.0280515 0.078935 -0.19199 -0.02775 0.078935 -0.201131 -0.05959 0.078935 -0.193115 -0.0319486 0.078935 -0.19199 -0.03225 0.078935 -0.190865 -0.0319486 0.078935 -0.190041 -0.031125 0.078935 -0.215273 -0.0795 0.078935 -0.216039 -0.0793478 0.078935 0.212552 -0.076375 0.078935 0.213331 -0.0187569 0.078935 0.177343 -4.19898e-08 0.078935 0.187695 -0.031125 0.078935 0.198785 -0.05959 0.078935 0.189643 -0.03225 0.078935 0.187695 -0.028875 0.078935 0.188518 -0.0280515 0.078935 0.190768 -0.0280515 0.078935 0.191592 -0.028875 0.078935 0.198785 -0.0157582 0.078935 0.189643 0.03225 0.078935 0.198785 0.034275 0.078935 0.191592 0.028875 0.078935 0.156965 0.034275 0.078935 0.187393 0.03 0.078935 0.188518 0.0280514 0.078935 0.156965 -4.19898e-08 0.078935 -0.12865 0.0466301 0.078935 -0.14082 0.034275 0.078935 -0.0751802 0.0442134 0.078935 -0.0580214 0.05959 0.078935 -0.12615 0.0473 0.078935 -0.129685 -0.0458356 0.078935 -0.128063 -0.0469194 0.078935 -0.0797996 -0.0473 0.078935 -0.076264 -0.0458356 0.078935 -0.0580214 -4.19898e-08 0.078935 -0.0747996 -0.0423 0.078935 -0.0747996 -4.19898e-08 0.078935 -0.0580214 0.034275 0.078935 -0.0747996 0.0423 0.078935 -0.149329 -0.0359499 0.078935 -0.174765 -0.05959 0.078935 -0.15695 -0.0359499 0.078935 -0.15979 0.0317 0.078935 -0.174765 0.05959 0.078935 -0.14082 -0.05959 0.078935 -0.14082 -4.19898e-08 0.078935 -0.14649 -4.19898e-08 0.078935 0.214152 -0.0191347 0.078935 0.214927 -0.05959 0.078935 0.214927 -0.076375 0.078935 0.198785 0.0795 0.078935 0.205978 0.069875 0.078935 0.198785 0.05959 0.078935 0.212552 0.05959 0.078935 0.209052 0.0690514 0.078935 0.210177 0.071 0.078935 0.205978 -0.069875 0.078935 0.206802 -0.0690515 0.078935 0.209052 -0.0729486 0.078935 0.210177 -0.071 0.078935 0.198785 -0.076375 0.078935 0.207927 -0.07325 0.078935 0.126537 0.071 0.078935 0.123162 0.0729485 0.078935 0.124287 0.07325 0.078935 0.125412 0.0729485 0.078935 0.122338 0.072125 0.078935 0.122037 0.071 0.078935 0.122338 0.069875 0.078935 0.124287 0.06875 0.078935 0.156965 0.05959 0.078935 0.205677 0.071 0.078935 0.0824668 0.034275 0.078935 0.0824668 0.05959 0.078935 0.126235 -0.069875 0.078935 0.124287 -0.06875 0.078935 0.0824668 -0.05959 0.078935 0.123162 -0.0690515 0.078935 0.122338 -0.069875 0.078935 0.122338 -0.072125 0.078935 0.123162 -0.0729486 0.078935 0.124287 -0.07325 0.078935 0.125412 -0.0729486 0.078935 0.156965 -0.05959 0.078935 0.0395218 0.0729485 0.078935 0.0406468 0.07325 0.078935 -0.0011732 0.0795 0.078935 0.0386982 0.069875 0.078935 0.0395218 0.0690514 0.078935 0.0417718 0.0690514 0.078935 0.0425954 0.069875 0.078935 -0.0011732 -0.05959 0.078935 0.0824668 -4.19898e-08 0.078935 0.0417718 -0.0690515 0.078935 0.0428968 -0.071 0.078935 0.0395218 -0.0690515 0.078935 0.0383968 -0.071 0.078935 0.0425954 -0.072125 0.078935 -0.0449418 0.069875 0.078935 -0.0441182 0.0690514 0.078935 -0.0410446 0.072125 0.078935 -0.0418682 0.0729485 0.078935 -0.0580214 0.0795 0.078935 -0.0441182 0.0729485 0.078935 -0.0452432 0.071 0.078935 -0.0418682 0.0690514 0.078935 -0.0011732 0.05959 0.078935 -0.0441182 -0.0690515 0.078935 -0.0429932 -0.06875 0.078935 -0.0011732 0.034275 0.078935 -0.0011732 -4.19898e-08 0.078935 -0.0011732 -0.076375 0.078935 -0.0410446 -0.069875 0.078935 -0.0441182 -0.0729486 0.078935 -0.0580214 -0.076375 0.078935 -0.0429932 -0.07325 0.078935 -0.0418682 -0.0729486 0.078935 -0.0410446 -0.072125 0.078935 -0.128582 0.069875 0.078935 -0.128883 0.071 0.078935 -0.125508 0.0729485 0.078935 -0.14082 0.0795 0.078935 -0.127758 0.0690514 0.078935 -0.14082 0.05959 0.078935 -0.126633 0.06875 0.078935 -0.0975914 0.0795 0.078935 -0.0975914 0.05959 0.078935 -0.125508 -0.0690515 0.078935 -0.126633 -0.06875 0.078935 -0.128582 -0.069875 0.078935 -0.0580214 -0.05959 0.078935 -0.0975914 -0.05959 0.078935 -0.126633 -0.07325 0.078935 -0.128883 -0.071 0.078935 -0.128582 -0.072125 0.078935 -0.127758 -0.0729486 0.078935 -0.14879 0.0356837 0.078935 -0.15109 0.0363 0.078935 -0.190865 0.0319485 0.078935 -0.19199 0.03225 0.078935 -0.174765 0.0795 0.078935 0.156965 -0.076375 0.078935 0.0824668 -0.076375 0.078935 -0.0975914 -0.076375 0.078935 -0.14082 -0.0795 0.078935 -0.174765 -0.0795 0.078935 -0.217273 -0.0775 0.078935 -0.217069 0.0198353 0.078935 -0.217273 0.0207157 0.078935 -0.201131 0.034275 0.078935 -0.217273 0.034275 0.078935 -0.217273 0.05959 0.078935 -0.210273 0.06875 0.078935 -0.201131 -0.076375 0.078935 -0.217069 -0.0198353 0.078935 -0.14082 -0.076375 0.078935 -0.174765 -0.076375 0.078935 -0.208023 -0.071 0.078935 -0.208325 -0.069875 0.078935 -0.217273 -0.05959 0.078935 -0.217273 -0.076375 0.078935 -0.212222 -0.072125 0.078935 -0.211398 -0.0729486 0.078935 -0.210273 -0.07325 0.078935 -0.208325 -0.072125 0.078935 -0.242499 0.0615447 0.084435 -0.239998 0.0786447 0.083035 -0.247105 0.0300447 0.083035 -0.247105 0.0300447 0.084935 -0.246839 0.0275645 0.084935 -0.245408 0.0255215 0.083035 -0.243167 0.0244242 0.084935 -0.239009 -0.0795 0.083035 -0.201131 -0.0795 0.078935 0.236662 -0.0795 0.083035 0.212927 -0.0795 0.083035 -0.0011732 -0.0795 0.078935 -0.0580214 -0.0795 0.078935 -0.179118 -0.0795 0.081935 -0.0975914 -0.0795 0.078935 0.0824668 -0.0795 0.078935 0.156965 -0.0795 0.078935 0.198785 -0.0795 0.078935 0.212552 -0.0795 0.078935 0.212927 -0.0795 0.078935 -0.215677 -0.0187569 0.083035 -0.190304 -0.0135261 0.084935 -0.243167 -0.0244243 0.084935 -0.242499 -0.0615447 0.084935 -0.242499 -0.0615447 0.084435 -0.247105 -0.0300448 0.083035 -0.239009 0.0795 0.084435 0.212927 0.0795 0.083035 0.156965 0.0795 0.078935 0.176772 0.0795 0.081935 0.0824668 0.0795 0.078935 -0.179118 0.0795 0.081935 0.213331 0.0187569 0.083035 0.198785 0.0157582 0.078935 0.240821 0.0244242 0.083035 0.240821 0.0244242 0.084935 0.244493 0.0275645 0.083035 0.243061 0.0255215 0.084935 0.240153 -0.0615447 0.084435 0.244759 -0.0300448 0.084935 0.244493 -0.0275645 0.083035 0.240821 -0.0244243 0.083035 0.236891 -0.0789446 0.084935 0.237069 -0.0787907 0.084935 0.207927 -0.07325 0.084935 0.175711 -0.0785607 0.084935 0.236662 -0.079 0.084935 0.205978 -0.069875 0.084935 0.207927 -0.06875 0.084935 0.239163 -0.0624 0.084935 0.209052 -0.0690515 0.084935 0.210177 -0.071 0.084935 0.206802 -0.0729486 0.084935 0.205978 -0.072125 0.084935 0.171724 -0.0750045 0.084935 0.205677 -0.071 0.084935 0.170193 -0.0747 0.084935 0.122338 -0.069875 0.084935 0.0824668 -0.0747 0.084935 0.123162 -0.0729486 0.084935 0.0824668 -0.0624 0.084935 0.166107 -0.0624 0.084935 0.126235 -0.069875 0.084935 0.126537 -0.071 0.084935 0.0417718 -0.0690515 0.084935 0.0428968 -0.071 0.084935 0.0425954 -0.072125 0.084935 0.0406468 -0.07325 0.084935 0.0395218 -0.0690515 0.084935 0.0386982 -0.072125 0.084935 0.0386982 -0.069875 0.084935 -0.0418682 -0.0690515 0.084935 -0.0410446 -0.069875 0.084935 -0.0410446 -0.072125 0.084935 -0.0418682 -0.0729486 0.084935 -0.0429932 -0.07325 0.084935 -0.0848132 -0.0747 0.084935 -0.0848132 -0.0624 0.084935 -0.0449418 -0.069875 0.084935 -0.125508 -0.0729486 0.084935 -0.126633 -0.07325 0.084935 -0.126633 -0.06875 0.084935 -0.209148 -0.0729486 0.084935 -0.210273 -0.07325 0.084935 -0.178057 -0.0785607 0.084935 -0.211398 -0.0690515 0.084935 -0.168453 -0.0624 0.084935 -0.208023 -0.071 0.084935 -0.208325 -0.072125 0.084935 -0.239238 -0.0789446 0.084935 -0.239009 -0.079 0.084935 -0.239504 -0.0785724 0.084935 -0.227201 -0.076125 0.084935 -0.178544 -0.0788859 0.084935 -0.227201 -0.0624 0.084935 -0.241879 -0.0623293 0.084935 -0.239861 0.076125 0.084935 -0.239416 0.0787906 0.084935 -0.239009 0.079 0.084935 -0.239504 0.0785723 0.084935 -0.210273 0.06875 0.084935 -0.178544 0.0788858 0.084935 -0.211398 0.0729485 0.084935 -0.212222 0.069875 0.084935 -0.212222 0.072125 0.084935 -0.174071 0.0750044 0.084935 -0.126633 0.06875 0.084935 -0.127758 0.0690514 0.084935 -0.128582 0.069875 0.084935 -0.128883 0.071 0.084935 -0.128582 0.072125 0.084935 -0.127758 0.0729485 0.084935 -0.168453 0.0747 0.084935 -0.124383 0.071 0.084935 -0.124685 0.069875 0.084935 -0.125508 0.0690514 0.084935 -0.0410446 0.072125 0.084935 -0.0848132 0.0747 0.084935 -0.0429932 0.07325 0.084935 -0.0418682 0.0729485 0.084935 -0.0429932 0.06875 0.084935 -0.0848132 0.0624 0.084935 -0.0449418 0.069875 0.084935 0.0386982 0.072125 0.084935 -0.0011732 0.0747 0.084935 -0.0011732 0.0624 0.084935 0.0386982 0.069875 0.084935 0.0383968 0.071 0.084935 0.0395218 0.0729485 0.084935 0.0428968 0.071 0.084935 0.0425954 0.072125 0.084935 0.0417718 0.0690514 0.084935 0.0406468 0.06875 0.084935 0.126235 0.069875 0.084935 0.166107 0.0624 0.084935 0.124287 0.06875 0.084935 0.123162 0.0690514 0.084935 0.0824668 0.0624 0.084935 0.122037 0.071 0.084935 0.0824668 0.0747 0.084935 0.224855 0.0624 0.084935 0.209052 0.0690514 0.084935 0.206802 0.0729485 0.084935 0.207927 0.07325 0.084935 0.224855 0.076125 0.084935 0.206802 0.0690514 0.084935 0.205978 0.069875 0.084935 0.171724 0.0750044 0.084935 0.236662 0.079 0.084935 0.224855 0.079 0.084935 0.175711 0.0785606 0.084935 0.209875 0.072125 0.084935 0.210177 0.071 0.084935 0.237157 0.0785723 0.084935 0.182498 -0.011014 0.084935 0.177343 -0.000500042 0.084935 0.177343 -0.000500042 0.078935 0.177343 0.000499958 0.084935 0.182498 0.0110139 0.084935 0.187958 0.013526 0.084935 -0.215677 0.0187569 0.083035 -0.184844 0.0110139 0.078935 -0.17969 -4.19898e-08 0.078935 -0.184844 -0.011014 0.084935 0.213331 -0.0187569 0.083035 0.206802 0.0729485 0.078935 0.205978 0.072125 0.078935 0.205978 0.072125 0.084935 0.205677 0.071 0.084935 0.206802 0.0690514 0.078935 0.207927 0.06875 0.078935 0.207927 0.06875 0.084935 0.209875 0.069875 0.078935 0.209875 0.069875 0.084935 0.209875 0.072125 0.078935 0.207927 0.07325 0.078935 0.209052 0.0729485 0.084935 0.124287 0.07325 0.084935 0.123162 0.0729485 0.084935 0.122338 0.072125 0.084935 0.122338 0.069875 0.084935 0.123162 0.0690514 0.078935 0.125412 0.0690514 0.078935 0.125412 0.0690514 0.084935 0.126235 0.069875 0.078935 0.126537 0.071 0.084935 0.126235 0.072125 0.078935 0.126235 0.072125 0.084935 0.125412 0.0729485 0.084935 0.0386982 0.072125 0.078935 0.0383968 0.071 0.078935 0.0395218 0.0690514 0.084935 0.0406468 0.06875 0.078935 0.0425954 0.069875 0.084935 0.0428968 0.071 0.078935 0.0425954 0.072125 0.078935 0.0417718 0.0729485 0.078935 0.0417718 0.0729485 0.084935 0.0406468 0.07325 0.084935 -0.0449418 0.072125 0.078935 -0.0441182 0.0729485 0.084935 -0.0449418 0.072125 0.084935 -0.0452432 0.071 0.084935 -0.0441182 0.0690514 0.084935 -0.0429932 0.06875 0.078935 -0.0418682 0.0690514 0.084935 -0.0410446 0.069875 0.078935 -0.0410446 0.069875 0.084935 -0.0407432 0.071 0.084935 -0.0407432 0.071 0.078935 -0.0429932 0.07325 0.078935 -0.127758 0.0729485 0.078935 -0.128582 0.072125 0.078935 -0.125508 0.0690514 0.078935 -0.124685 0.069875 0.078935 -0.124383 0.071 0.078935 -0.124685 0.072125 0.078935 -0.124685 0.072125 0.084935 -0.125508 0.0729485 0.084935 -0.126633 0.07325 0.078935 -0.126633 0.07325 0.084935 -0.210273 0.07325 0.084935 -0.212523 0.071 0.084935 -0.212222 0.069875 0.078935 -0.211398 0.0690514 0.084935 -0.209148 0.0690514 0.084935 -0.208325 0.069875 0.084935 -0.208023 0.071 0.084935 -0.208023 0.071 0.078935 -0.208325 0.072125 0.078935 -0.208325 0.072125 0.084935 -0.209148 0.0729485 0.084935 -0.210273 -0.06875 0.078935 -0.210273 -0.06875 0.084935 -0.211398 -0.0690515 0.078935 -0.212222 -0.069875 0.078935 -0.212222 -0.069875 0.084935 -0.212523 -0.071 0.078935 -0.212523 -0.071 0.084935 -0.212222 -0.072125 0.084935 -0.211398 -0.0729486 0.084935 -0.209148 -0.0729486 0.078935 -0.208325 -0.069875 0.084935 -0.209148 -0.0690515 0.078935 -0.209148 -0.0690515 0.084935 -0.127758 -0.0690515 0.078935 -0.127758 -0.0690515 0.084935 -0.128582 -0.069875 0.084935 -0.128883 -0.071 0.084935 -0.128582 -0.072125 0.084935 -0.127758 -0.0729486 0.084935 -0.125508 -0.0729486 0.078935 -0.124685 -0.072125 0.084935 -0.124685 -0.072125 0.078935 -0.124383 -0.071 0.078935 -0.124383 -0.071 0.084935 -0.124685 -0.069875 0.078935 -0.124685 -0.069875 0.084935 -0.125508 -0.0690515 0.084935 -0.0429932 -0.06875 0.084935 -0.0449418 -0.069875 0.078935 -0.0441182 -0.0690515 0.084935 -0.0452432 -0.071 0.084935 -0.0452432 -0.071 0.078935 -0.0449418 -0.072125 0.078935 -0.0449418 -0.072125 0.084935 -0.0441182 -0.0729486 0.084935 -0.0407432 -0.071 0.078935 -0.0407432 -0.071 0.084935 -0.0418682 -0.0690515 0.078935 0.0406468 -0.06875 0.078935 0.0386982 -0.069875 0.078935 0.0383968 -0.071 0.084935 0.0386982 -0.072125 0.078935 0.0395218 -0.0729486 0.084935 0.0395218 -0.0729486 0.078935 0.0406468 -0.07325 0.078935 0.0417718 -0.0729486 0.078935 0.0417718 -0.0729486 0.084935 0.0425954 -0.069875 0.078935 0.0425954 -0.069875 0.084935 0.0406468 -0.06875 0.084935 0.124287 -0.06875 0.084935 0.123162 -0.0690515 0.084935 0.122037 -0.071 0.084935 0.122037 -0.071 0.078935 0.122338 -0.072125 0.084935 0.124287 -0.07325 0.084935 0.126235 -0.072125 0.078935 0.125412 -0.0729486 0.084935 0.126235 -0.072125 0.084935 0.126537 -0.071 0.078935 0.125412 -0.0690515 0.078935 0.125412 -0.0690515 0.084935 0.206802 -0.0690515 0.084935 0.205677 -0.071 0.078935 0.205978 -0.072125 0.078935 0.206802 -0.0729486 0.078935 0.209052 -0.0729486 0.084935 0.209875 -0.072125 0.078935 0.209875 -0.072125 0.084935 0.209875 -0.069875 0.078935 0.209875 -0.069875 0.084935 0.209052 -0.0690515 0.078935 0.214927 -0.0775 0.082735 0.214302 -0.0192635 0.082735 0.214659 -0.0785 0.082735 0.240761 -0.0247182 0.082735 0.244462 -0.0300014 0.082735 0.214927 -0.0207158 0.082735 0.214927 0.05959 0.078935 0.214927 0.0775 0.082735 0.214302 0.0192634 0.082735 0.237355 0.0786012 0.082735 0.242866 0.0257494 0.082735 0.244462 0.0300013 0.082735 0.214927 0.0207157 0.082735 0.214659 0.0785 0.082735 0.236662 0.0792 0.082735 0.21398 0.0792 0.082735 -0.216327 -0.0792 0.082735 -0.246808 -0.0300014 0.082735 -0.217273 -0.0207158 0.082735 -0.217121 -0.0782654 0.082735 -0.216687 -0.0789143 0.082735 -0.243107 0.0247181 0.082735 -0.216687 0.0789142 0.082735 -0.239701 0.0786012 0.082735 -0.245213 0.0257494 0.082735 -0.217273 0.0207157 0.082735 -0.217273 0.0775 0.082735 -0.19199 0.03225 0.082385 -0.193115 0.0319485 0.078935 -0.19424 0.03 0.078935 -0.193938 0.028875 0.078935 -0.193938 0.028875 0.082385 -0.193115 0.0280514 0.082385 -0.19199 0.02775 0.082385 -0.190865 0.0280514 0.078935 -0.190041 0.028875 0.078935 -0.190041 0.028875 0.082385 -0.18974 0.03 0.082385 -0.193115 0.0319485 0.082385 -0.193938 0.031125 0.082385 -0.19439 0.0341569 0.084935 -0.196146 0.0324 0.084935 -0.19424 0.03 0.082385 -0.19679 0.03 0.084935 -0.196146 0.0276 0.084935 -0.19439 0.025843 0.084935 -0.190865 0.0280514 0.082385 -0.190041 0.031125 0.082385 -0.18719 0.03 0.084935 -0.190865 0.0319485 0.082385 -0.19199 0.0348 0.084935 -0.19439 0.0341569 0.085235 -0.196146 0.0276 0.085235 -0.19439 0.025843 0.085235 -0.19199 0.0252 0.084935 -0.18959 0.025843 0.084935 -0.19199 0.0252 0.085235 -0.18959 0.025843 0.085235 -0.187833 0.0276 0.084935 -0.187833 0.0324 0.084935 -0.18959 0.0341569 0.084935 -0.187833 0.0324 0.085235 -0.18959 0.0341569 0.085235 -0.19199 -0.02775 0.082385 -0.193115 -0.0280515 0.082385 -0.193938 -0.028875 0.078935 -0.19424 -0.03 0.078935 -0.193938 -0.031125 0.078935 -0.193115 -0.0319486 0.082385 -0.19199 -0.03225 0.082385 -0.190041 -0.028875 0.078935 -0.190041 -0.028875 0.082385 -0.193938 -0.028875 0.082385 -0.19439 -0.0258431 0.084935 -0.19424 -0.03 0.082385 -0.193938 -0.031125 0.082385 -0.196146 -0.0324 0.084935 -0.19439 -0.034157 0.084935 -0.190865 -0.0319486 0.082385 -0.190041 -0.031125 0.082385 -0.18959 -0.034157 0.084935 -0.18974 -0.03 0.082385 -0.187833 -0.0324 0.084935 -0.18719 -0.03 0.084935 -0.190865 -0.0280515 0.082385 -0.187833 -0.0276 0.084935 -0.18959 -0.0258431 0.084935 -0.196146 -0.0276 0.084935 -0.19439 -0.0258431 0.085235 -0.196146 -0.0276 0.085235 -0.19679 -0.03 0.084935 -0.19679 -0.03 0.085235 -0.19199 -0.0348 0.084935 -0.19199 -0.0348 0.085235 -0.18959 -0.034157 0.085235 -0.187833 -0.0324 0.085235 -0.18719 -0.03 0.085235 -0.19199 -0.0252 0.084935 -0.19199 -0.0252 0.085235 0.188518 0.0319485 0.078935 0.187695 0.031125 0.078935 0.187695 0.031125 0.082385 0.187695 0.028875 0.078935 0.187695 0.028875 0.082385 0.189643 0.02775 0.078935 0.190768 0.0280514 0.078935 0.190768 0.0280514 0.082385 0.191893 0.03 0.078935 0.191893 0.03 0.082385 0.191592 0.031125 0.078935 0.190768 0.0319485 0.078935 0.187393 0.03 0.082385 0.188518 0.0280514 0.082385 0.189643 0.0252 0.084935 0.189643 0.02775 0.082385 0.191592 0.028875 0.082385 0.1938 0.0276 0.084935 0.194443 0.03 0.084935 0.191592 0.031125 0.082385 0.190768 0.0319485 0.082385 0.189643 0.03225 0.082385 0.188518 0.0319485 0.082385 0.187243 0.0341569 0.084935 0.187243 0.0341569 0.085235 0.185486 0.0324 0.084935 0.184843 0.03 0.084935 0.185486 0.0276 0.084935 0.185486 0.0276 0.085235 0.187243 0.025843 0.085235 0.187243 0.025843 0.084935 0.189643 0.0252 0.085235 0.192043 0.025843 0.085235 0.192043 0.025843 0.084935 0.1938 0.0276 0.085235 0.194443 0.03 0.085235 0.1938 0.0324 0.084935 0.1938 0.0324 0.085235 0.192043 0.0341569 0.084935 0.189643 0.0348 0.084935 0.189643 0.0348 0.085235 0.189643 -0.02775 0.078935 0.187393 -0.03 0.078935 0.188518 -0.0319486 0.078935 0.190768 -0.0319486 0.078935 0.191592 -0.031125 0.078935 0.191592 -0.031125 0.082385 0.191893 -0.03 0.078935 0.190768 -0.0280515 0.082385 0.189643 -0.02775 0.082385 0.187695 -0.028875 0.082385 0.187393 -0.03 0.082385 0.185486 -0.0276 0.084935 0.184843 -0.03 0.084935 0.187695 -0.031125 0.082385 0.188518 -0.0319486 0.082385 0.187243 -0.034157 0.084935 0.189643 -0.03225 0.082385 0.190768 -0.0319486 0.082385 0.192043 -0.034157 0.084935 0.191893 -0.03 0.082385 0.1938 -0.0324 0.084935 0.191592 -0.028875 0.082385 0.194443 -0.03 0.084935 0.1938 -0.0276 0.084935 0.192043 -0.0258431 0.084935 0.189643 -0.0252 0.084935 0.188518 -0.0280515 0.082385 0.187243 -0.0258431 0.084935 0.187243 -0.0258431 0.085235 0.185486 -0.0324 0.084935 0.187243 -0.034157 0.085235 0.189643 -0.0348 0.084935 0.189643 -0.0348 0.085235 0.1938 -0.0324 0.085235 -0.138162 0.0550537 0.085235 -0.138903 0.0543125 0.085235 -0.139175 0.0533 0.085235 -0.138903 0.0522875 0.085235 -0.137975 0.051871 0.08486 -0.13715 0.05165 0.08486 -0.1355 0.0533 0.08486 -0.135125 0.0533 0.085235 -0.135721 0.054125 0.08486 -0.135396 0.0543125 0.085235 -0.136325 0.0547289 0.08486 -0.137975 0.0547289 0.08486 -0.13715 0.055325 0.085235 -0.0705533 0.0543125 0.085235 -0.0708246 0.0533 0.085235 -0.0704496 0.0533 0.08486 -0.0705533 0.0522875 0.085235 -0.0687996 0.05165 0.08486 -0.0679746 0.051871 0.08486 -0.0673706 0.052475 0.08486 -0.0677871 0.0515463 0.085235 -0.0671496 0.0533 0.08486 -0.0667746 0.0533 0.085235 -0.0673706 0.054125 0.08486 -0.0670459 0.0543125 0.085235 -0.0679746 0.0547289 0.08486 -0.0687996 0.055325 0.085235 -0.138903 0.00101246 0.085235 -0.138579 0.000824958 0.08486 -0.1388 -4.19898e-08 0.08486 -0.138579 -0.000825042 0.08486 -0.138903 -0.00101254 0.085235 -0.137975 -0.00142898 0.08486 -0.13715 -0.00202504 0.085235 -0.136137 -0.00175374 0.085235 -0.136325 -0.00142898 0.08486 -0.135721 -0.000825042 0.08486 -0.1355 -4.19898e-08 0.08486 -0.135396 -0.00101254 0.085235 -0.135721 0.000824958 0.08486 -0.135396 0.00101246 0.085235 -0.136325 0.0014289 0.08486 -0.136137 0.00175366 0.085235 -0.13715 0.00202496 0.085235 -0.13715 0.00164996 0.08486 -0.0696246 0.0014289 0.08486 -0.0702285 0.000824958 0.08486 -0.0704496 -4.19898e-08 0.08486 -0.0705533 0.00101246 0.085235 -0.0708246 -4.19898e-08 0.085235 -0.0705533 -0.00101254 0.085235 -0.0698121 -0.00175374 0.085235 -0.0687996 -0.00165004 0.08486 -0.0687996 -0.00202504 0.085235 -0.0679746 -0.00142898 0.08486 -0.0673706 -0.000825042 0.08486 -0.0670459 -0.00101254 0.085235 -0.0670459 0.00101246 0.085235 -0.0679746 0.0014289 0.08486 -0.0677871 0.00175366 0.085235 -0.0698121 0.00175366 0.085235 -0.138162 -0.0515463 0.085235 -0.138579 -0.052475 0.08486 -0.139175 -0.0533 0.085235 -0.138579 -0.054125 0.08486 -0.138903 -0.0543125 0.085235 -0.138162 -0.0550537 0.085235 -0.13715 -0.055325 0.085235 -0.136325 -0.054729 0.08486 -0.136137 -0.0550537 0.085235 -0.135721 -0.054125 0.08486 -0.135721 -0.052475 0.08486 -0.135125 -0.0533 0.085235 -0.136325 -0.0518711 0.08486 -0.135396 -0.0522875 0.085235 -0.0696246 -0.0518711 0.08486 -0.0705533 -0.0522875 0.085235 -0.0705533 -0.0543125 0.085235 -0.0702285 -0.054125 0.08486 -0.0696246 -0.054729 0.08486 -0.0687996 -0.05495 0.08486 -0.0679746 -0.054729 0.08486 -0.0677871 -0.0550537 0.085235 -0.0673706 -0.054125 0.08486 -0.0687996 -0.05165 0.08486 -0.0687996 -0.051275 0.085235 -0.239998 -0.0786447 0.084435 -0.239009 -0.0795 0.084435 -0.239822 0.0790813 0.083035 -0.239822 0.0790813 0.084435 0.237652 0.0786447 0.084435 0.23712 0.0793892 0.083035 0.236662 0.0795 0.083035 0.23712 -0.0793892 0.083035 0.236662 -0.0795 0.084435 0.23712 -0.0793892 0.084435 0.237652 -0.0786447 0.083035 0.213927 -0.0792321 0.078935 0.213927 -0.0792321 0.0827671 0.21398 -0.0792 0.082735 0.214659 -0.0785 0.078935 0.214927 -0.0775 0.078935 0.214927 -0.0207158 0.078935 0.214723 -0.0198353 0.078935 0.214723 -0.0198353 0.082735 0.213763 -0.0188988 0.0829833 0.214723 0.0198353 0.082735 0.214659 0.0785 0.078935 0.213444 0.0794318 0.0829669 -0.215273 0.0795 0.078935 -0.216327 0.0792 0.082735 -0.217121 0.0782653 0.078935 -0.217121 0.0782653 0.082735 -0.217069 0.0198353 0.082735 -0.216648 0.0192634 0.082735 -0.216109 0.0188988 0.0829833 -0.217273 -0.0775 0.082735 -0.217121 -0.0782654 0.078935 -0.216687 -0.0789143 0.078935 -0.215663 -0.0794616 0.0829966 -0.215273 -0.0795 0.083035 -0.217069 -0.0198353 0.082735 -0.215677 -0.0187569 0.078935 -0.216109 -0.0188988 0.0829833 -0.216498 -0.0191347 0.0828308 -0.216498 -0.0191347 0.078935 -0.216648 -0.0192635 0.082735 -0.217273 -0.0207158 0.078935 0.239621 0.0622892 0.084935 0.240153 0.0615447 0.084935 0.240153 0.0615447 0.084435 0.239977 -0.0619814 0.084935 0.239621 -0.0622892 0.084935 -0.242389 0.0618762 0.0844961 -0.242323 0.0619813 0.084935 -0.242171 0.0621496 0.084935 -0.242171 0.0621496 0.0846717 -0.241879 0.0623292 0.084935 -0.242171 -0.0621497 0.0846717 -0.242171 -0.0621497 0.084935 -0.242389 -0.0618763 0.0844961 0.239532 0.0623292 0.084935 0.239825 0.0621496 0.0846717 0.240042 0.0618762 0.0844961 0.237476 0.0790813 0.084435 0.23712 0.0793892 0.084435 0.237069 0.0787906 0.084935 0.236891 0.0789446 0.084935 0.236662 0.0795 0.084435 0.176772 0.079 0.084935 0.176198 0.0788858 0.084935 0.170193 0.0752 0.084435 0.170193 0.0747 0.084935 0.173022 0.0758715 0.084935 -0.17254 0.0747 0.084935 -0.17254 0.0752 0.084435 0.166107 0.0747 0.084935 -0.175015 0.0762251 0.084435 -0.175368 0.0758715 0.084935 -0.178057 0.0785606 0.084935 -0.178353 0.0793477 0.084435 -0.179118 0.079 0.084935 -0.179118 0.0795 0.084435 -0.239238 0.0789446 0.084935 -0.239466 0.0793892 0.084435 -0.239998 0.0786447 0.084435 -0.239416 -0.0787907 0.084935 -0.239822 -0.0790814 0.084435 -0.239466 -0.0793892 0.084435 -0.179118 -0.0795 0.084435 -0.227201 -0.079 0.084935 -0.179118 -0.079 0.084935 -0.175368 -0.0758716 0.084935 -0.173879 -0.0754665 0.084435 -0.174071 -0.0750045 0.084935 -0.175015 -0.0762252 0.084435 0.166107 -0.0747 0.084935 -0.0011732 -0.0747 0.084935 0.170193 -0.0752 0.084435 -0.168453 -0.0747 0.084935 -0.17254 -0.0747 0.084935 0.172668 -0.0762252 0.084435 0.173022 -0.0758716 0.084935 0.171533 -0.0754665 0.084435 0.176772 -0.0795 0.084435 0.176198 -0.0788859 0.084935 0.176772 -0.079 0.084935 0.237476 -0.0790814 0.084435 0.237652 -0.0786447 0.084435 0.237157 -0.0785724 0.084935 0.240042 -0.0618763 0.0844961 0.239825 -0.0621497 0.0846717 0.237515 -0.076125 0.084935 0.239532 -0.0623293 0.084935 0.213929 0.0792308 0.0827659 0.236983 0.0791224 0.082735 0.237476 0.0790813 0.083035 0.237232 0.0789069 0.082735 0.244759 0.0300447 0.083035 0.237652 0.0786447 0.083035 0.244212 0.0276699 0.082735 0.243061 0.0255215 0.083035 0.213763 0.0188988 0.0829833 0.240761 0.0247181 0.082735 0.214152 0.0191346 0.0828308 0.236662 -0.0792 0.082735 0.213444 -0.0794319 0.0829669 0.237355 -0.0786013 0.082735 0.237476 -0.0790814 0.083035 0.237232 -0.078907 0.082735 0.236983 -0.0791225 0.082735 0.242866 -0.0257495 0.082735 0.243061 -0.0255215 0.083035 0.244212 -0.02767 0.082735 0.244759 -0.0300448 0.083035 0.214157 -0.0191389 0.0828278 -0.243167 0.0244242 0.083035 -0.216503 0.0191388 0.0828278 -0.246839 0.0275645 0.083035 -0.246558 0.0276699 0.082735 -0.246808 0.0300013 0.082735 -0.239578 0.0789069 0.082735 -0.239329 0.0791224 0.082735 -0.239466 0.0793892 0.083035 -0.239009 0.0795 0.083035 -0.215273 0.0795 0.083035 -0.215663 0.0794615 0.0829966 -0.239009 0.0792 0.082735 -0.216039 0.0793477 0.0828828 -0.216047 -0.0793442 0.0828791 -0.239466 -0.0793892 0.083035 -0.239009 -0.0792 0.082735 -0.239329 -0.0791225 0.082735 -0.239822 -0.0790814 0.083035 -0.239578 -0.078907 0.082735 -0.239998 -0.0786447 0.083035 -0.239701 -0.0786013 0.082735 -0.246839 -0.0275645 0.083035 -0.246558 -0.02767 0.082735 -0.245408 -0.0255215 0.083035 -0.245213 -0.0257495 0.082735 -0.243167 -0.0244243 0.083035 -0.243107 -0.0247182 0.082735 -0.246808 0.0300013 0.085235 -0.246558 0.0276699 0.085235 -0.245408 0.0255215 0.084935 -0.245213 0.0257494 0.085235 -0.241509 0.0621 0.085235 -0.241967 0.0622892 0.084935 -0.24183 0.0620224 0.085235 -0.242499 0.0615447 0.084935 -0.190304 0.013526 0.084935 -0.241509 0.0624 0.084935 -0.17374 0.0621 0.085235 -0.168453 0.0624 0.084935 -0.133137 0.0621 0.085235 0.0590343 0.0621 0.085235 0.219477 0.0621 0.085235 0.239163 0.0624 0.084935 -0.181048 0.00635471 0.084935 -0.184844 0.0110139 0.084935 0.239977 0.0619813 0.084935 0.239733 0.0618069 0.085235 0.239483 0.0620224 0.085235 0.239825 0.0621496 0.084935 -0.17969 -0.000500042 0.084935 -0.17969 0.000499958 0.084935 -0.17939 0.000499958 0.085235 0.244759 0.0300447 0.084935 0.239856 0.0615012 0.085235 -0.181048 -0.00635479 0.084935 0.240761 0.0247181 0.085235 0.242866 0.0257494 0.085235 0.244493 0.0275645 0.084935 0.244462 0.0300013 0.085235 -0.245408 -0.0255215 0.084935 -0.246839 -0.0275645 0.084935 0.187897 0.0138198 0.085235 0.178701 0.00635471 0.084935 -0.247105 -0.0300448 0.084935 -0.245047 -0.04205 0.085235 0.177043 0.000499958 0.085235 -0.242323 -0.0619814 0.084935 -0.242202 -0.0615013 0.085235 -0.242079 -0.061807 0.085235 -0.241509 -0.0624 0.084935 -0.24183 -0.0620225 0.085235 -0.241967 -0.0622892 0.084935 0.178701 -0.00635479 0.084935 0.177043 -0.000500042 0.085235 0.178432 -0.00648685 0.085235 0.182314 -0.0112511 0.085235 0.187897 -0.0138199 0.085235 -0.241509 -0.0621 0.085235 -0.0687996 -0.0621 0.085235 -0.0011732 -0.0624 0.084935 0.0590343 -0.0621 0.085235 0.187958 -0.0135261 0.084935 0.239483 -0.0620225 0.085235 0.239825 -0.0621497 0.084935 0.239856 -0.0615013 0.085235 0.244493 -0.0275645 0.084935 0.244212 -0.02767 0.085235 0.243061 -0.0255215 0.084935 0.242866 -0.0257495 0.085235 0.240821 -0.0244243 0.084935 0.240153 -0.0615447 0.084935 0.244462 -0.0300014 0.085235 -0.16029 -0.0136125 0.085235 -0.159901 -0.0336517 0.085235 -0.158796 -0.0353063 0.085235 -0.15695 -0.0359499 0.084735 -0.15519 -0.0368 0.085235 -0.15519 0.0363 0.084735 -0.159173 0.034 0.084735 -0.15774 0.0361167 0.085235 -0.159606 0.03425 0.085235 -0.16029 0.0317 0.085235 -0.15109 0.0368 0.085235 -0.15519 0.0368 0.085235 -0.14854 -0.0361168 0.085235 -0.15109 0.0363 0.084735 -0.149138 0.0364117 0.085235 -0.14879 0.0356837 0.084735 -0.147483 0.0353062 0.085235 -0.146378 0.0336516 0.085235 -0.147106 0.034 0.084735 -0.147837 0.0349526 0.084735 -0.14649 0.0317 0.084735 -0.178353 -0.0793478 0.081935 0.170193 -0.0752 0.081935 -0.17254 -0.0752 0.081935 0.176006 -0.0793478 0.081935 -0.173879 0.0754664 0.081935 -0.177704 0.0789142 0.081935 0.170193 0.0752 0.081935 -0.178353 0.0793477 0.081935 0.175357 0.0789142 0.081935 0.172668 0.0762251 0.081935 0.171533 0.0754664 0.081935 -0.0696246 -0.054729 0.081935 -0.0696246 -0.0518711 0.081935 -0.0702285 -0.052475 0.081935 -0.0704496 -0.0533 0.081935 -0.0673706 -0.052475 0.081935 -0.0679746 -0.0518711 0.081935 -0.0687996 -0.0533 0.081935 -0.13715 -0.0533 0.081935 -0.137975 -0.054729 0.081935 -0.136325 -0.054729 0.081935 -0.137975 -0.0518711 0.081935 -0.1388 -0.0533 0.081935 -0.138579 -0.054125 0.081935 -0.136325 -0.0518711 0.081935 -0.135721 -0.054125 0.081935 -0.0687996 -4.19898e-08 0.081935 -0.0696246 -0.00142898 0.081935 -0.0702285 0.000824958 0.081935 -0.0702285 -0.000825042 0.081935 -0.0673706 0.000824958 0.081935 -0.0679746 0.0014289 0.081935 -0.0696246 0.0014289 0.081935 -0.13715 -0.00165004 0.081935 -0.136325 0.0014289 0.081935 -0.13715 -4.19898e-08 0.081935 -0.136325 -0.00142898 0.081935 -0.0696246 0.051871 0.081935 -0.0687996 0.0533 0.081935 -0.0673706 0.052475 0.081935 -0.0671496 0.0533 0.081935 -0.0673706 0.054125 0.081935 -0.138579 0.052475 0.081935 -0.1388 0.0533 0.081935 -0.13715 0.0533 0.081935 -0.136325 0.051871 0.081935 -0.12615 -0.0473 0.078935 -0.0975914 -0.0473 0.078935 -0.0797996 -0.0473 0.085235 -0.0778861 -0.0469194 0.078935 -0.076264 -0.0458356 0.085235 -0.0751802 -0.0442135 0.078935 -0.0747996 -0.0423 0.085235 -0.0747996 0.034275 0.078935 -0.0747996 -0.04205 0.085235 -0.076264 0.0458355 0.078935 -0.076264 0.0458355 0.085235 -0.0778861 0.0469194 0.078935 -0.0797996 0.0473 0.078935 -0.0975914 0.0473 0.078935 -0.12865 0.0466301 0.085235 -0.13048 0.0448 0.078935 -0.13115 0.0423 0.078935 -0.13115 0.034275 0.078935 -0.13115 0.04205 0.085235 -0.13115 -0.0136125 0.085235 -0.13115 -4.19898e-08 0.078935 -0.13115 -0.0423 0.078935 -0.130769 -0.0442135 0.078935 -0.13115 -0.0423 0.085235 -0.129685 -0.0458356 0.085235 -0.12615 -0.0473 0.085235 -0.136137 0.0515463 0.085235 -0.13115 -0.04205 0.085235 0.178432 0.00648677 0.085235 -0.0747996 0.04205 0.085235 -0.0747996 0.0423 0.085235 -0.0687996 0.04205 0.085235 -0.0687996 0.051275 0.085235 -0.0698121 0.0515463 0.085235 -0.0751802 0.0442134 0.085235 -0.13115 0.0423 0.085235 -0.0797996 0.0473 0.085235 -0.0778861 0.0469194 0.085235 -0.12615 0.0473 0.085235 -0.13048 0.0448 0.085235 -0.0698121 0.0550537 0.085235 -0.0687996 0.0621 0.085235 -0.0677871 0.0550537 0.085235 -0.0670459 0.0522875 0.085235 -0.0747996 -0.0136125 0.085235 -0.0747996 0.0136125 0.085235 -0.0687996 0.00202496 0.085235 0.0590343 0.0136125 0.085235 -0.0667746 -4.19898e-08 0.085235 -0.0708246 -0.0533 0.085235 -0.0698121 -0.0550537 0.085235 -0.133137 -0.0621 0.085235 -0.0698121 -0.0515463 0.085235 -0.0677871 -0.0515463 0.085235 -0.0670459 -0.0522875 0.085235 -0.0667746 -0.0533 0.085235 -0.0670459 -0.0543125 0.085235 -0.0687996 -0.055325 0.085235 -0.19439 -0.034157 0.085235 -0.196146 -0.0324 0.085235 -0.246808 -0.0300014 0.085235 -0.246558 -0.02767 0.085235 -0.17374 -0.04205 0.085235 -0.187833 -0.0276 0.085235 -0.17374 -0.0136125 0.085235 -0.18959 -0.0258431 0.085235 -0.18466 -0.0112511 0.085235 -0.190244 -0.0138199 0.085235 -0.243107 -0.0247182 0.085235 -0.245213 -0.0257495 0.085235 -0.17939 -0.000500042 0.085235 -0.180778 -0.00648685 0.085235 -0.18466 0.011251 0.085235 -0.180778 0.00648677 0.085235 -0.17374 0.0136125 0.085235 -0.190244 0.0138198 0.085235 -0.243107 0.0247181 0.085235 -0.19679 0.03 0.085235 -0.19199 0.0348 0.085235 -0.242202 0.0615012 0.085235 -0.196146 0.0324 0.085235 -0.17374 0.04205 0.085235 -0.18719 0.03 0.085235 -0.187833 0.0276 0.085235 0.239163 0.0621 0.085235 0.184843 0.03 0.085235 0.182314 0.011251 0.085235 0.185486 0.0324 0.085235 0.192043 0.0341569 0.085235 0.0590343 -0.0136125 0.085235 0.194443 -0.03 0.085235 0.192043 -0.034157 0.085235 0.185486 -0.0324 0.085235 0.184843 -0.03 0.085235 0.185486 -0.0276 0.085235 0.189643 -0.0252 0.085235 0.192043 -0.0258431 0.085235 0.1938 -0.0276 0.085235 0.240761 -0.0247182 0.085235 0.219477 -0.0621 0.085235 0.239163 -0.0621 0.085235 0.239733 -0.061807 0.085235 -0.142582 0.04205 0.085235 -0.16029 0.0136125 0.085235 -0.14599 -0.0136125 0.085235 -0.14599 -0.0317 0.085235 -0.146673 -0.03425 0.085235 -0.16029 -0.0317 0.085235 -0.15109 -0.0368 0.085235 -0.157141 -0.0364118 0.085235 -0.0751802 -0.0442135 0.085235 -0.0778861 -0.0469194 0.085235 -0.133137 -0.0492875 0.085235 -0.128063 -0.0469194 0.085235 -0.0687996 -0.0492875 0.085235 -0.0687996 -0.04205 0.085235 -0.0687996 -0.0136125 0.085235 -0.13115 0.0136125 0.085235 -0.142582 -0.04205 0.085235 -0.17374 -0.0492875 0.085235 -0.17374 -0.0621 0.085235 -0.13715 0.051275 0.085235 -0.138162 0.0515463 0.085235 -0.242079 0.0618069 0.085235 -0.142582 0.0621 0.085235 -0.135396 0.0522875 0.085235 -0.136137 0.0550537 0.085235 -0.14599 0.0317 0.085235 -0.133137 0.04205 0.085235 -0.142582 0.0136125 0.085235 -0.138162 0.00175366 0.085235 -0.133137 0.0136125 0.085235 -0.135125 -4.19898e-08 0.085235 -0.139175 -4.19898e-08 0.085235 -0.142582 -0.0136125 0.085235 -0.138162 -0.00175374 0.085235 -0.14599 0.0136125 0.085235 -0.133137 -0.0136125 0.085235 -0.133137 -0.04205 0.085235 -0.136137 -0.0515463 0.085235 -0.135396 -0.0543125 0.085235 -0.142582 -0.0621 0.085235 -0.138903 -0.0522875 0.085235 -0.142582 -0.0492875 0.085235 -0.13715 -0.051275 0.085235 -0.130769 -0.0442135 0.085235 -0.0687996 0.0136125 0.085235 0.0590343 0.04205 0.085235 0.0590343 -0.0492875 0.085235 -0.0677871 -0.00175374 0.085235 0.219477 0.04205 0.085235 0.244212 0.0276699 0.085235 0.0590343 -0.04205 0.085235 0.219477 -0.04205 0.085235 0.219477 -0.0492875 0.085235 -0.214748 0.0474003 0.081935 -0.215499 0.04665 0.081935 -0.215773 0.0328 0.081935 -0.215499 0.031775 0.081935 -0.214748 0.0310246 0.081935 -0.200264 0.04665 0.081935 -0.19999 0.045625 0.081935 -0.20204 0.047675 0.081935 -0.213723 0.047675 0.081935 -0.20204 0.047675 0.083735 -0.201015 0.0474003 0.083735 -0.200264 0.04665 0.083735 -0.19999 0.045625 0.083735 -0.20059 0.0313504 0.083735 -0.201255 0.030906 0.083735 -0.214748 0.0310246 0.083735 -0.213723 0.03075 0.083735 -0.214748 0.0474003 0.083735 -0.215773 0.045625 0.083735 -0.19999 0.0328 0.083735 -0.215773 0.0328 0.083735 -0.215499 0.031775 0.083735 -0.213723 0.047675 0.083735 -0.215499 0.04665 0.083735 -0.215773 0.045625 0.081935 -0.201255 0.030906 0.081935 -0.20059 0.0313504 0.081935 -0.200146 0.0320155 0.081935 -0.200146 0.0320155 0.083735 -0.19999 0.0328 0.081935 -0.213723 0.03075 0.081935 -0.20204 0.03075 0.081935 -0.20204 0.03075 0.083735 -0.201015 0.0474003 0.081935 -0.201552 0.0175789 0.081935 -0.19999 0.01957 0.081935 -0.215773 0.0219787 0.081935 -0.202453 0.0175623 0.081935 -0.200188 0.0186903 0.081935 -0.215564 0.0210763 0.081935 -0.214137 0.0199709 0.081935 -0.213723 0.02925 0.081935 -0.215773 0.0272 0.081935 -0.19999 0.0272 0.081935 -0.200264 0.028225 0.081935 -0.215773 0.0219787 0.083735 -0.215773 0.0272 0.083735 -0.201552 0.0175789 0.083735 -0.19999 0.01957 0.083735 -0.202453 0.0175623 0.083735 -0.214979 0.0203582 0.083735 -0.201015 0.0289753 0.083735 -0.19999 0.0272 0.083735 -0.213723 0.02925 0.083735 -0.214137 0.0199709 0.083735 -0.215564 0.0210763 0.083735 -0.214979 0.0203582 0.081935 -0.214748 0.0289753 0.081935 -0.214748 0.0289753 0.083735 -0.215499 0.028225 0.081935 -0.215499 0.028225 0.083735 -0.200745 0.0179809 0.081935 -0.200745 0.0179809 0.083735 -0.200188 0.0186903 0.083735 -0.201015 0.0289753 0.081935 -0.200264 0.028225 0.083735 -0.20204 0.02925 0.083735 -0.20204 0.02925 0.081935 -0.197695 0.016795 0.081935 -0.19849 0.0184156 0.081935 -0.195385 0.0243403 0.081935 -0.193172 0.0235067 0.081935 -0.196853 0.0164078 0.081935 -0.190807 0.0235067 0.081935 -0.186347 0.0147766 0.081935 -0.19831 0.0234225 0.081935 -0.197053 0.0245384 0.081935 -0.188594 0.0243403 0.081935 -0.18567 0.0234225 0.081935 -0.195385 0.0243403 0.083735 -0.19828 0.0175131 0.083735 -0.185717 0.0155066 0.083735 -0.187242 0.0144159 0.083735 -0.188594 0.0243403 0.083735 -0.190001 0.0149951 0.083735 -0.193172 0.0235067 0.083735 -0.187781 0.0246181 0.083735 -0.186926 0.0245384 0.083735 -0.187781 0.0246181 0.081935 -0.186178 0.024115 0.083735 -0.186926 0.0245384 0.081935 -0.186178 0.024115 0.081935 -0.18567 0.0234225 0.083735 -0.18549 0.0225824 0.083735 -0.19849 0.0225824 0.081935 -0.19831 0.0234225 0.083735 -0.197801 0.024115 0.083735 -0.197801 0.024115 0.081935 -0.197053 0.0245384 0.083735 -0.196198 0.0246181 0.083735 -0.196198 0.0246181 0.081935 -0.190807 0.0235067 0.083735 -0.19828 0.0175131 0.081935 -0.19849 0.0184156 0.083735 -0.197695 0.016795 0.083735 -0.196853 0.0164078 0.083735 -0.19849 0.0225824 0.083735 -0.190001 0.0149951 0.081935 -0.18549 0.0164442 0.083735 -0.185717 0.0155066 0.081935 -0.186347 0.0147766 0.083735 -0.187242 0.0144159 0.081935 -0.188203 0.0145044 0.083735 -0.188203 0.0145044 0.081935 -0.18549 0.0164442 0.081935 -0.18549 0.0225824 0.081935 -0.183284 0.0116732 0.081935 -0.17836 0.00273972 0.081935 -0.177267 0.001225 0.081935 -0.173515 0.00127461 0.081935 -0.17249 0.00304996 0.081935 -0.183715 0.028225 0.081935 -0.17454 0.02925 0.081935 -0.17249 0.0272 0.083735 -0.17249 0.00304996 0.083735 -0.172764 0.00202496 0.083735 -0.177996 0.00185071 0.083735 -0.17836 0.00273972 0.083735 -0.177267 0.001225 0.083735 -0.176334 0.000999958 0.083735 -0.183284 0.0116732 0.083735 -0.17454 0.02925 0.083735 -0.173755 0.0290939 0.083735 -0.17309 0.0286495 0.083735 -0.182965 0.0289753 0.083735 -0.18399 0.0132208 0.083735 -0.18399 0.0272 0.083735 -0.18399 0.0272 0.081935 -0.183715 0.028225 0.083735 -0.182965 0.0289753 0.081935 -0.183805 0.0123703 0.083735 -0.183805 0.0123703 0.081935 -0.18399 0.0132208 0.081935 -0.172646 0.0279845 0.081935 -0.172646 0.0279845 0.083735 -0.17309 0.0286495 0.081935 -0.173755 0.0290939 0.081935 -0.18194 0.02925 0.083735 -0.18194 0.02925 0.081935 -0.17454 0.000999958 0.081935 -0.17454 0.000999958 0.083735 -0.173515 0.00127461 0.083735 -0.172764 0.00202496 0.081935 -0.17249 0.0272 0.081935 -0.176334 0.000999958 0.081935 -0.177996 0.00185071 0.081935 -0.180028 0.00764406 0.081935 -0.180028 0.00764406 0.083735 -0.19849 0.06405 0.081935 -0.19849 0.051225 0.081935 -0.19644 0.0661 0.081935 -0.18549 0.06405 0.081935 -0.186515 0.0494496 0.081935 -0.185764 0.0502 0.081935 -0.18549 0.051225 0.081935 -0.19644 0.049175 0.081935 -0.197465 0.0494496 0.081935 -0.186755 0.0659439 0.083735 -0.197465 0.0494496 0.083735 -0.197465 0.0658253 0.083735 -0.19849 0.06405 0.083735 -0.185764 0.0502 0.083735 -0.18549 0.051225 0.083735 -0.18549 0.06405 0.083735 -0.198215 0.0502 0.083735 -0.19849 0.051225 0.083735 -0.18754 0.049175 0.083735 -0.18754 0.0661 0.083735 -0.18609 0.0654995 0.083735 -0.198215 0.065075 0.083735 -0.198215 0.065075 0.081935 -0.19644 0.0661 0.083735 -0.197465 0.0658253 0.081935 -0.198215 0.0502 0.081935 -0.185646 0.0648345 0.083735 -0.185646 0.0648345 0.081935 -0.18609 0.0654995 0.081935 -0.186755 0.0659439 0.081935 -0.18754 0.0661 0.081935 -0.186515 0.0494496 0.083735 -0.18754 0.049175 0.081935 -0.19644 0.049175 0.083735 -0.215773 0.051225 0.081935 -0.213723 0.049175 0.081935 -0.214748 0.0494496 0.081935 -0.215499 0.0502 0.081935 -0.20204 0.049175 0.081935 -0.213723 0.0661 0.081935 -0.215773 0.06405 0.081935 -0.20204 0.0661 0.081935 -0.200264 0.065075 0.081935 -0.215773 0.06405 0.083735 -0.215499 0.065075 0.083735 -0.201015 0.0658253 0.083735 -0.213723 0.049175 0.083735 -0.214748 0.0658253 0.083735 -0.19999 0.06405 0.083735 -0.20204 0.049175 0.083735 -0.20059 0.0497754 0.083735 -0.214748 0.0658253 0.081935 -0.215499 0.065075 0.081935 -0.214748 0.0494496 0.083735 -0.215499 0.0502 0.083735 -0.215773 0.051225 0.083735 -0.201255 0.049331 0.081935 -0.20059 0.0497754 0.081935 -0.201255 0.049331 0.083735 -0.200146 0.0504405 0.081935 -0.200146 0.0504405 0.083735 -0.201015 0.0658253 0.081935 -0.200264 0.065075 0.083735 -0.19999 0.051225 0.081935 -0.19999 0.051225 0.083735 -0.19999 0.06405 0.081935 -0.20204 0.0661 0.083735 -0.213723 0.0661 0.083735 0.211377 0.03075 0.081935 0.212161 0.030906 0.081935 0.197643 0.045625 0.081935 0.198668 0.0310246 0.081935 0.199693 0.03075 0.081935 0.213271 0.0320155 0.081935 0.199693 0.047675 0.081935 0.197918 0.04665 0.081935 0.213427 0.045625 0.081935 0.213152 0.04665 0.081935 0.199693 0.047675 0.083735 0.211377 0.047675 0.083735 0.197918 0.031775 0.083735 0.211377 0.03075 0.083735 0.213427 0.0328 0.083735 0.197643 0.045625 0.083735 0.197643 0.0328 0.083735 0.197918 0.031775 0.081935 0.198668 0.0310246 0.083735 0.199693 0.03075 0.083735 0.213427 0.0328 0.081935 0.213271 0.0320155 0.083735 0.212826 0.0313504 0.083735 0.212826 0.0313504 0.081935 0.212161 0.030906 0.083735 0.213427 0.045625 0.083735 0.213152 0.04665 0.083735 0.212402 0.0474003 0.083735 0.212402 0.0474003 0.081935 0.211377 0.047675 0.081935 0.197918 0.04665 0.083735 0.198668 0.0474003 0.081935 0.198668 0.0474003 0.083735 0.197643 0.0328 0.081935 0.197643 0.0272 0.081935 0.213427 0.0272 0.081935 0.212826 0.0286495 0.081935 0.198668 0.0289753 0.081935 0.197918 0.028225 0.081935 0.199693 0.02925 0.081935 0.211377 0.02925 0.081935 0.199205 0.0175789 0.081935 0.197842 0.0186903 0.081935 0.197643 0.01957 0.081935 0.211791 0.0199709 0.081935 0.212632 0.0203582 0.081935 0.213217 0.0210763 0.081935 0.197643 0.0272 0.083735 0.198668 0.0289753 0.083735 0.213217 0.0210763 0.083735 0.213427 0.0219787 0.083735 0.199205 0.0175789 0.083735 0.197842 0.0186903 0.083735 0.213271 0.0279845 0.083735 0.211377 0.02925 0.083735 0.211791 0.0199709 0.083735 0.199693 0.02925 0.083735 0.197643 0.01957 0.083735 0.198398 0.0179809 0.081935 0.198398 0.0179809 0.083735 0.200107 0.0175623 0.081935 0.212632 0.0203582 0.083735 0.213427 0.0272 0.083735 0.213271 0.0279845 0.081935 0.212161 0.0290939 0.081935 0.212826 0.0286495 0.083735 0.212161 0.0290939 0.083735 0.213427 0.0219787 0.081935 0.197918 0.028225 0.083735 0.200107 0.0175623 0.083735 0.183143 0.0164442 0.081935 0.195963 0.0234225 0.081935 0.193852 0.0246181 0.081935 0.193039 0.0243403 0.081935 0.186248 0.0243403 0.081935 0.188461 0.0235067 0.081935 0.190826 0.0235067 0.081935 0.187655 0.0149951 0.081935 0.194507 0.0164078 0.081935 0.195349 0.016795 0.081935 0.184579 0.0245384 0.081935 0.183143 0.0225824 0.081935 0.183143 0.0225824 0.083735 0.183832 0.024115 0.083735 0.184579 0.0245384 0.083735 0.194707 0.0245384 0.083735 0.195963 0.0234225 0.083735 0.196143 0.0225824 0.083735 0.196143 0.0184156 0.083735 0.186248 0.0243403 0.083735 0.184896 0.0144159 0.083735 0.194507 0.0164078 0.083735 0.195934 0.0175131 0.081935 0.195349 0.016795 0.083735 0.195934 0.0175131 0.083735 0.183323 0.0234225 0.083735 0.183323 0.0234225 0.081935 0.183832 0.024115 0.081935 0.185435 0.0246181 0.083735 0.185435 0.0246181 0.081935 0.193852 0.0246181 0.083735 0.194707 0.0245384 0.081935 0.195455 0.024115 0.081935 0.195455 0.024115 0.083735 0.196143 0.0225824 0.081935 0.188461 0.0235067 0.083735 0.190826 0.0235067 0.083735 0.193039 0.0243403 0.083735 0.185856 0.0145044 0.083735 0.184896 0.0144159 0.081935 0.184001 0.0147766 0.083735 0.184001 0.0147766 0.081935 0.18337 0.0155066 0.083735 0.18337 0.0155066 0.081935 0.183143 0.0164442 0.083735 0.185856 0.0145044 0.081935 0.187655 0.0149951 0.083735 0.196143 0.0184156 0.081935 0.185193 0.047675 0.081935 0.184168 0.0474003 0.081935 0.188461 0.0364932 0.081935 0.183418 0.04665 0.081935 0.186248 0.0356596 0.081935 0.183143 0.045625 0.081935 0.190826 0.0364932 0.081935 0.196143 0.045625 0.081935 0.195963 0.0365774 0.081935 0.194707 0.0354616 0.081935 0.196143 0.0374175 0.081935 0.193852 0.0353818 0.081935 0.185435 0.0353818 0.081935 0.184168 0.0474003 0.083735 0.183418 0.04665 0.083735 0.195963 0.0365774 0.083735 0.190826 0.0364932 0.083735 0.195869 0.04665 0.083735 0.193039 0.0356596 0.083735 0.196143 0.0374175 0.083735 0.186248 0.0356596 0.083735 0.183323 0.0365774 0.083735 0.183143 0.045625 0.083735 0.194093 0.047675 0.081935 0.195118 0.0474003 0.083735 0.195118 0.0474003 0.081935 0.195869 0.04665 0.081935 0.185193 0.047675 0.083735 0.185435 0.0353818 0.083735 0.184579 0.0354616 0.083735 0.184579 0.0354616 0.081935 0.183832 0.0358849 0.081935 0.183832 0.0358849 0.083735 0.183323 0.0365774 0.081935 0.183143 0.0374175 0.083735 0.183143 0.0374175 0.081935 0.194093 0.047675 0.083735 0.195455 0.0358849 0.083735 0.195455 0.0358849 0.081935 0.194707 0.0354616 0.083735 0.193852 0.0353818 0.083735 0.196143 0.045625 0.083735 0.193039 0.0356596 0.081935 0.188461 0.0364932 0.083735 0.179593 0.03075 0.081935 0.181043 0.0313504 0.081935 0.172193 0.03075 0.081935 0.170418 0.04665 0.081935 0.170143 0.045625 0.081935 0.180618 0.0474003 0.081935 0.180618 0.0474003 0.083735 0.181643 0.045625 0.083735 0.179593 0.047675 0.083735 0.181643 0.0328 0.083735 0.179593 0.03075 0.083735 0.180378 0.030906 0.083735 0.181043 0.0313504 0.083735 0.179593 0.047675 0.081935 0.181369 0.04665 0.083735 0.181369 0.04665 0.081935 0.180378 0.030906 0.081935 0.181487 0.0320155 0.081935 0.181487 0.0320155 0.083735 0.181643 0.0328 0.081935 0.181643 0.045625 0.081935 0.172193 0.047675 0.081935 0.171168 0.0474003 0.081935 0.171168 0.0474003 0.083735 0.170418 0.04665 0.083735 0.172193 0.047675 0.083735 0.171168 0.0310246 0.083735 0.171168 0.0310246 0.081935 0.170418 0.031775 0.081935 0.170418 0.031775 0.083735 0.170143 0.0328 0.081935 0.170143 0.045625 0.083735 0.170143 0.0328 0.083735 0.172193 0.03075 0.083735 0.180938 0.0116732 0.081935 0.170143 0.0272 0.081935 0.170299 0.00226546 0.081935 0.170143 0.00304996 0.081935 0.181369 0.028225 0.081935 0.180618 0.0289753 0.081935 0.181643 0.0272 0.081935 0.171168 0.0289753 0.081935 0.181643 0.0132208 0.081935 0.180938 0.0116732 0.083735 0.172193 0.000999958 0.083735 0.171409 0.001156 0.083735 0.181369 0.028225 0.083735 0.170143 0.00304996 0.083735 0.181643 0.0132208 0.083735 0.170299 0.00226546 0.083735 0.17565 0.00185071 0.083735 0.170143 0.0272 0.083735 0.170418 0.028225 0.083735 0.171168 0.0289753 0.083735 0.180618 0.0289753 0.083735 0.179593 0.02925 0.081935 0.181643 0.0272 0.083735 0.170418 0.028225 0.081935 0.170744 0.00160039 0.081935 0.170744 0.00160039 0.083735 0.171409 0.001156 0.081935 0.172193 0.000999958 0.081935 0.176014 0.00273972 0.083735 0.176014 0.00273972 0.081935 0.17565 0.00185071 0.081935 0.174921 0.001225 0.083735 0.174921 0.001225 0.081935 0.173987 0.000999958 0.081935 0.173987 0.000999958 0.083735 0.172193 0.02925 0.081935 0.179593 0.02925 0.083735 0.172193 0.02925 0.083735 0.181458 0.0123703 0.083735 0.181458 0.0123703 0.081935 0.177682 0.00764406 0.081935 0.177682 0.00764406 0.083735 0.180378 0.049331 0.081935 0.181643 0.051225 0.081935 0.170143 0.06405 0.081935 0.171168 0.0494496 0.081935 0.172193 0.049175 0.081935 0.170418 0.065075 0.081935 0.172193 0.0661 0.081935 0.179593 0.0661 0.081935 0.181643 0.06405 0.081935 0.180618 0.0658253 0.081935 0.181369 0.065075 0.081935 0.170418 0.065075 0.083735 0.171168 0.0658253 0.083735 0.172193 0.0661 0.083735 0.170143 0.06405 0.083735 0.181643 0.051225 0.083735 0.179593 0.049175 0.083735 0.180618 0.0658253 0.083735 0.181369 0.065075 0.083735 0.181643 0.06405 0.083735 0.171168 0.0658253 0.081935 0.172193 0.049175 0.083735 0.171168 0.0494496 0.083735 0.170418 0.0502 0.083735 0.170418 0.0502 0.081935 0.170143 0.051225 0.081935 0.170143 0.051225 0.083735 0.179593 0.0661 0.083735 0.181043 0.0497754 0.081935 0.180378 0.049331 0.083735 0.181043 0.0497754 0.083735 0.181487 0.0504405 0.081935 0.181487 0.0504405 0.083735 0.179593 0.049175 0.081935 0.185193 0.0661 0.081935 0.196143 0.051225 0.081935 0.196143 0.06405 0.081935 0.194093 0.049175 0.081935 0.183143 0.051225 0.081935 0.196143 0.051225 0.083735 0.195118 0.0494496 0.083735 0.194093 0.049175 0.083735 0.195543 0.0654995 0.083735 0.196143 0.06405 0.083735 0.194093 0.0661 0.083735 0.194093 0.0661 0.081935 0.194878 0.0659439 0.081935 0.194878 0.0659439 0.083735 0.195543 0.0654995 0.081935 0.195987 0.0648345 0.081935 0.195987 0.0648345 0.083735 0.184168 0.0658253 0.081935 0.184168 0.0658253 0.083735 0.183418 0.065075 0.081935 0.183418 0.065075 0.083735 0.185193 0.049175 0.081935 0.184168 0.0494496 0.081935 0.184168 0.0494496 0.083735 0.183418 0.0502 0.083735 0.183418 0.0502 0.081935 0.183143 0.06405 0.081935 0.183143 0.06405 0.083735 0.183143 0.051225 0.083735 0.185193 0.0661 0.083735 0.195118 0.0494496 0.081935 0.195869 0.0502 0.083735 0.195869 0.0502 0.081935 0.185193 0.049175 0.083735 -0.19999 -0.0328 0.081935 -0.213723 -0.03075 0.081935 -0.214508 -0.047519 0.081935 -0.215617 -0.0464095 0.081935 -0.215773 -0.045625 0.081935 -0.20204 -0.03075 0.081935 -0.200264 -0.04665 0.081935 -0.200264 -0.04665 0.083735 -0.215773 -0.045625 0.083735 -0.214748 -0.0310247 0.083735 -0.201015 -0.0310247 0.083735 -0.19999 -0.045625 0.083735 -0.213723 -0.03075 0.083735 -0.200264 -0.031775 0.081935 -0.19999 -0.0328 0.083735 -0.200264 -0.031775 0.083735 -0.201015 -0.0310247 0.081935 -0.20204 -0.03075 0.083735 -0.215773 -0.0328 0.081935 -0.215499 -0.031775 0.083735 -0.215499 -0.031775 0.081935 -0.214748 -0.0310247 0.081935 -0.215173 -0.0470746 0.081935 -0.215617 -0.0464095 0.083735 -0.215173 -0.0470746 0.083735 -0.214508 -0.047519 0.083735 -0.213723 -0.047675 0.083735 -0.215773 -0.0328 0.083735 -0.19999 -0.045625 0.081935 -0.201015 -0.0474004 0.083735 -0.201015 -0.0474004 0.081935 -0.20204 -0.047675 0.081935 -0.213723 -0.047675 0.081935 -0.20204 -0.047675 0.083735 -0.215773 -0.0272 0.081935 -0.20204 -0.02925 0.081935 -0.20059 -0.0286496 0.081935 -0.213723 -0.02925 0.081935 -0.202453 -0.0175623 0.081935 -0.200188 -0.0186904 0.081935 -0.215564 -0.0210764 0.081935 -0.215773 -0.0219788 0.081935 -0.20059 -0.0286496 0.083735 -0.201255 -0.029094 0.083735 -0.20204 -0.02925 0.083735 -0.19999 -0.0272 0.083735 -0.215564 -0.0210764 0.083735 -0.214979 -0.0203582 0.083735 -0.202453 -0.0175623 0.083735 -0.19999 -0.0195701 0.083735 -0.200745 -0.0179809 0.083735 -0.200188 -0.0186904 0.083735 -0.200745 -0.0179809 0.081935 -0.201552 -0.017579 0.081935 -0.201552 -0.017579 0.083735 -0.214137 -0.019971 0.083735 -0.214979 -0.0203582 0.081935 -0.215773 -0.0272 0.083735 -0.215499 -0.028225 0.083735 -0.215499 -0.028225 0.081935 -0.214748 -0.0289754 0.081935 -0.214748 -0.0289754 0.083735 -0.215773 -0.0219788 0.083735 -0.200146 -0.0279845 0.083735 -0.19999 -0.0272 0.081935 -0.200146 -0.0279845 0.081935 -0.201255 -0.029094 0.081935 -0.213723 -0.02925 0.083735 -0.19999 -0.0195701 0.081935 -0.214137 -0.019971 0.081935 -0.19849 -0.0225825 0.081935 -0.19831 -0.0234226 0.081935 -0.186347 -0.0147767 0.081935 -0.187242 -0.014416 0.081935 -0.188203 -0.0145045 0.081935 -0.190807 -0.0235068 0.081935 -0.193172 -0.0235068 0.081935 -0.197695 -0.0167951 0.081935 -0.186178 -0.0241151 0.081935 -0.18567 -0.0234226 0.081935 -0.19828 -0.0175132 0.083735 -0.197695 -0.0167951 0.083735 -0.18549 -0.0225825 0.083735 -0.187781 -0.0246182 0.083735 -0.186926 -0.0245384 0.083735 -0.188594 -0.0243404 0.083735 -0.190001 -0.0149952 0.083735 -0.197053 -0.0245384 0.083735 -0.196198 -0.0246182 0.083735 -0.197801 -0.0241151 0.083735 -0.19831 -0.0234226 0.083735 -0.195385 -0.0243404 0.083735 -0.196853 -0.0164079 0.083735 -0.19828 -0.0175132 0.081935 -0.18567 -0.0234226 0.083735 -0.186178 -0.0241151 0.083735 -0.186926 -0.0245384 0.081935 -0.187781 -0.0246182 0.081935 -0.196198 -0.0246182 0.081935 -0.197053 -0.0245384 0.081935 -0.197801 -0.0241151 0.081935 -0.19849 -0.0225825 0.083735 -0.188594 -0.0243404 0.081935 -0.190807 -0.0235068 0.083735 -0.195385 -0.0243404 0.081935 -0.193172 -0.0235068 0.083735 -0.188203 -0.0145045 0.083735 -0.187242 -0.014416 0.083735 -0.186347 -0.0147767 0.083735 -0.185717 -0.0155067 0.081935 -0.185717 -0.0155067 0.083735 -0.18549 -0.0164443 0.083735 -0.18549 -0.0225825 0.081935 -0.18549 -0.0164443 0.081935 -0.190001 -0.0149952 0.081935 -0.196853 -0.0164079 0.081935 -0.19849 -0.0184156 0.083735 -0.19849 -0.0184156 0.081935 -0.197889 -0.0470746 0.081935 -0.187781 -0.0353819 0.081935 -0.188594 -0.0356597 0.081935 -0.19644 -0.047675 0.081935 -0.193172 -0.0364933 0.081935 -0.18754 -0.047675 0.081935 -0.196198 -0.0353819 0.081935 -0.195385 -0.0356597 0.081935 -0.185764 -0.04665 0.081935 -0.190807 -0.0364933 0.081935 -0.186515 -0.0474004 0.081935 -0.18567 -0.0365775 0.081935 -0.18549 -0.0374176 0.081935 -0.186515 -0.0474004 0.083735 -0.193172 -0.0364933 0.083735 -0.18754 -0.047675 0.083735 -0.18567 -0.0365775 0.083735 -0.18549 -0.0374176 0.083735 -0.195385 -0.0356597 0.083735 -0.197053 -0.0354616 0.083735 -0.197801 -0.035885 0.083735 -0.19831 -0.0365775 0.083735 -0.19849 -0.045625 0.083735 -0.186178 -0.035885 0.083735 -0.197224 -0.047519 0.083735 -0.197224 -0.047519 0.081935 -0.197889 -0.0470746 0.083735 -0.198334 -0.0464095 0.083735 -0.198334 -0.0464095 0.081935 -0.19849 -0.045625 0.081935 -0.18549 -0.045625 0.081935 -0.185764 -0.04665 0.083735 -0.188594 -0.0356597 0.083735 -0.187781 -0.0353819 0.083735 -0.186926 -0.0354616 0.083735 -0.186926 -0.0354616 0.081935 -0.186178 -0.035885 0.081935 -0.18549 -0.045625 0.083735 -0.19644 -0.047675 0.083735 -0.19849 -0.0374176 0.081935 -0.19831 -0.0365775 0.081935 -0.197801 -0.035885 0.081935 -0.197053 -0.0354616 0.081935 -0.196198 -0.0353819 0.083735 -0.19849 -0.0374176 0.083735 -0.190807 -0.0364933 0.083735 -0.18399 -0.045625 0.081935 -0.18399 -0.0328 0.081935 -0.17249 -0.0328 0.081935 -0.183834 -0.0464095 0.081935 -0.18194 -0.047675 0.081935 -0.182965 -0.0310247 0.081935 -0.18194 -0.03075 0.081935 -0.183715 -0.031775 0.081935 -0.17309 -0.0313505 0.081935 -0.172646 -0.0320155 0.081935 -0.172764 -0.04665 0.083735 -0.17249 -0.045625 0.083735 -0.18194 -0.047675 0.083735 -0.183389 -0.0470746 0.083735 -0.183834 -0.0464095 0.083735 -0.18399 -0.0328 0.083735 -0.173755 -0.0309061 0.083735 -0.18194 -0.03075 0.083735 -0.17454 -0.047675 0.083735 -0.17454 -0.03075 0.083735 -0.172646 -0.0320155 0.083735 -0.182724 -0.047519 0.083735 -0.182724 -0.047519 0.081935 -0.183389 -0.0470746 0.081935 -0.18399 -0.045625 0.083735 -0.182965 -0.0310247 0.083735 -0.183715 -0.031775 0.083735 -0.173515 -0.0474004 0.081935 -0.173515 -0.0474004 0.083735 -0.172764 -0.04665 0.081935 -0.17454 -0.047675 0.081935 -0.17454 -0.03075 0.081935 -0.173755 -0.0309061 0.081935 -0.17309 -0.0313505 0.083735 -0.17249 -0.0328 0.083735 -0.17249 -0.045625 0.081935 -0.173755 -0.00115609 0.081935 -0.183805 -0.0123704 0.081935 -0.18399 -0.0272 0.081935 -0.172646 -0.00226554 0.081935 -0.17249 -0.00305004 0.081935 -0.177267 -0.00122508 0.081935 -0.177996 -0.0018508 0.081935 -0.17249 -0.0272 0.081935 -0.17836 -0.0027398 0.081935 -0.183284 -0.0116733 0.081935 -0.18194 -0.02925 0.081935 -0.182965 -0.0289754 0.081935 -0.18399 -0.0132209 0.083735 -0.183805 -0.0123704 0.083735 -0.173755 -0.00115609 0.083735 -0.183284 -0.0116733 0.083735 -0.17836 -0.0027398 0.083735 -0.17454 -0.00100004 0.083735 -0.172646 -0.00226554 0.083735 -0.17249 -0.00305004 0.083735 -0.176334 -0.00100004 0.083735 -0.177996 -0.0018508 0.083735 -0.18194 -0.02925 0.083735 -0.183715 -0.028225 0.083735 -0.18399 -0.0272 0.083735 -0.17454 -0.02925 0.083735 -0.182965 -0.0289754 0.083735 -0.183715 -0.028225 0.081935 -0.173515 -0.0289754 0.081935 -0.173515 -0.0289754 0.083735 -0.172764 -0.028225 0.081935 -0.172764 -0.028225 0.083735 -0.17249 -0.0272 0.083735 -0.17309 -0.00160047 0.081935 -0.17309 -0.00160047 0.083735 -0.17454 -0.00100004 0.081935 -0.177267 -0.00122508 0.083735 -0.176334 -0.00100004 0.081935 -0.17454 -0.02925 0.081935 -0.18399 -0.0132209 0.081935 -0.180028 -0.00764414 0.081935 -0.180028 -0.00764414 0.083735 -0.17454 -0.049175 0.081935 -0.173515 -0.0658254 0.081935 -0.183715 -0.065075 0.081935 -0.18194 -0.0661 0.081935 -0.18399 -0.051225 0.081935 -0.18194 -0.049175 0.081935 -0.183715 -0.0502 0.081935 -0.182965 -0.0494497 0.083735 -0.18194 -0.049175 0.083735 -0.172764 -0.065075 0.083735 -0.173515 -0.0658254 0.083735 -0.18194 -0.0661 0.083735 -0.18399 -0.06405 0.083735 -0.17454 -0.0661 0.083735 -0.17454 -0.049175 0.083735 -0.17309 -0.0497755 0.083735 -0.17249 -0.051225 0.083735 -0.172646 -0.0504405 0.083735 -0.182965 -0.0658254 0.083735 -0.182965 -0.0658254 0.081935 -0.183715 -0.065075 0.083735 -0.18399 -0.06405 0.081935 -0.17454 -0.0661 0.081935 -0.172764 -0.065075 0.081935 -0.17249 -0.06405 0.081935 -0.17249 -0.06405 0.083735 -0.173755 -0.0493311 0.083735 -0.173755 -0.0493311 0.081935 -0.17309 -0.0497755 0.081935 -0.172646 -0.0504405 0.081935 -0.17249 -0.051225 0.081935 -0.182965 -0.0494497 0.081935 -0.183715 -0.0502 0.083735 -0.18399 -0.051225 0.083735 -0.185646 -0.0504405 0.081935 -0.18549 -0.051225 0.081935 -0.18754 -0.049175 0.081935 -0.18549 -0.06405 0.081935 -0.197465 -0.0494497 0.081935 -0.19849 -0.06405 0.081935 -0.19644 -0.0661 0.081935 -0.18754 -0.0661 0.081935 -0.19644 -0.049175 0.081935 -0.19849 -0.051225 0.083735 -0.19644 -0.049175 0.083735 -0.18754 -0.049175 0.083735 -0.186755 -0.0493311 0.083735 -0.18609 -0.0497755 0.083735 -0.18549 -0.06405 0.083735 -0.19644 -0.0661 0.083735 -0.18754 -0.0661 0.083735 -0.18549 -0.051225 0.083735 -0.185646 -0.0504405 0.083735 -0.197465 -0.0658254 0.083735 -0.197465 -0.0658254 0.081935 -0.198215 -0.065075 0.083735 -0.19849 -0.06405 0.083735 -0.198215 -0.065075 0.081935 -0.186515 -0.0658254 0.081935 -0.186515 -0.0658254 0.083735 -0.185764 -0.065075 0.081935 -0.185764 -0.065075 0.083735 -0.186755 -0.0493311 0.081935 -0.18609 -0.0497755 0.081935 -0.197465 -0.0494497 0.083735 -0.198215 -0.0502 0.081935 -0.198215 -0.0502 0.083735 -0.19849 -0.051225 0.081935 -0.200264 -0.065075 0.081935 -0.20204 -0.0661 0.081935 -0.215773 -0.051225 0.081935 -0.200264 -0.0502 0.081935 -0.214508 -0.065944 0.083735 -0.215773 -0.06405 0.083735 -0.19999 -0.051225 0.083735 -0.201015 -0.0658254 0.083735 -0.20204 -0.0661 0.083735 -0.213723 -0.0661 0.083735 -0.215173 -0.0654996 0.083735 -0.20204 -0.049175 0.083735 -0.215773 -0.051225 0.083735 -0.215499 -0.0502 0.083735 -0.214748 -0.0494497 0.083735 -0.215499 -0.0502 0.081935 -0.214748 -0.0494497 0.081935 -0.213723 -0.049175 0.083735 -0.19999 -0.051225 0.081935 -0.200264 -0.0502 0.083735 -0.201015 -0.0494497 0.081935 -0.201015 -0.0494497 0.083735 -0.20204 -0.049175 0.081935 -0.213723 -0.049175 0.081935 -0.215617 -0.0648345 0.081935 -0.215173 -0.0654996 0.081935 -0.215617 -0.0648345 0.083735 -0.214508 -0.065944 0.081935 -0.215773 -0.06405 0.081935 -0.200264 -0.065075 0.083735 -0.201015 -0.0658254 0.081935 -0.213723 -0.0661 0.081935 -0.19999 -0.06405 0.083735 -0.19999 -0.06405 0.081935 0.198668 -0.0310247 0.081935 0.211377 -0.03075 0.081935 0.198909 -0.047519 0.081935 0.197799 -0.0464095 0.081935 0.197643 -0.045625 0.081935 0.213152 -0.031775 0.081935 0.213427 -0.045625 0.081935 0.213152 -0.04665 0.081935 0.211377 -0.047675 0.081935 0.199693 -0.047675 0.083735 0.198244 -0.0470746 0.083735 0.197918 -0.031775 0.083735 0.212402 -0.0310247 0.083735 0.211377 -0.03075 0.083735 0.213427 -0.0328 0.083735 0.212402 -0.0474004 0.083735 0.213427 -0.045625 0.083735 0.197643 -0.045625 0.083735 0.199693 -0.03075 0.083735 0.212402 -0.0310247 0.081935 0.213152 -0.031775 0.083735 0.213427 -0.0328 0.081935 0.212402 -0.0474004 0.081935 0.213152 -0.04665 0.083735 0.198668 -0.0310247 0.083735 0.197918 -0.031775 0.081935 0.197643 -0.0328 0.083735 0.199693 -0.03075 0.081935 0.198909 -0.047519 0.083735 0.197799 -0.0464095 0.083735 0.198244 -0.0470746 0.081935 0.197643 -0.0328 0.081935 0.211377 -0.047675 0.083735 0.199693 -0.047675 0.081935 0.199693 -0.02925 0.081935 0.211377 -0.02925 0.081935 0.213271 -0.0279845 0.081935 0.213427 -0.0272 0.081935 0.213217 -0.0210764 0.081935 0.213427 -0.0219788 0.081935 0.197643 -0.0195701 0.081935 0.197842 -0.0186904 0.081935 0.212161 -0.029094 0.083735 0.199693 -0.02925 0.083735 0.213427 -0.0272 0.083735 0.213271 -0.0279845 0.083735 0.197842 -0.0186904 0.083735 0.211791 -0.019971 0.081935 0.212632 -0.0203582 0.083735 0.212632 -0.0203582 0.081935 0.213217 -0.0210764 0.083735 0.211377 -0.02925 0.083735 0.212161 -0.029094 0.081935 0.212826 -0.0286496 0.081935 0.212826 -0.0286496 0.083735 0.213427 -0.0219788 0.083735 0.200107 -0.0175623 0.083735 0.199205 -0.017579 0.083735 0.199205 -0.017579 0.081935 0.198398 -0.0179809 0.081935 0.198398 -0.0179809 0.083735 0.200107 -0.0175623 0.081935 0.211791 -0.019971 0.083735 0.198668 -0.0289754 0.083735 0.198668 -0.0289754 0.081935 0.197918 -0.028225 0.083735 0.197918 -0.028225 0.081935 0.197643 -0.0272 0.083735 0.197643 -0.0272 0.081935 0.197643 -0.0195701 0.083735 0.195934 -0.0175132 0.081935 0.183832 -0.0241151 0.081935 0.184579 -0.0245384 0.081935 0.183143 -0.0225825 0.081935 0.195963 -0.0234226 0.081935 0.196143 -0.0225825 0.081935 0.195455 -0.0241151 0.081935 0.193852 -0.0246182 0.081935 0.187655 -0.0149952 0.081935 0.184896 -0.014416 0.081935 0.193852 -0.0246182 0.083735 0.193039 -0.0243404 0.083735 0.184001 -0.0147767 0.083735 0.186248 -0.0243404 0.083735 0.188461 -0.0235068 0.083735 0.187655 -0.0149952 0.083735 0.190826 -0.0235068 0.083735 0.195349 -0.0167951 0.083735 0.185435 -0.0246182 0.083735 0.185435 -0.0246182 0.081935 0.184579 -0.0245384 0.083735 0.183832 -0.0241151 0.083735 0.183323 -0.0234226 0.083735 0.183323 -0.0234226 0.081935 0.195963 -0.0234226 0.083735 0.195455 -0.0241151 0.083735 0.194707 -0.0245384 0.083735 0.194707 -0.0245384 0.081935 0.193039 -0.0243404 0.081935 0.190826 -0.0235068 0.081935 0.188461 -0.0235068 0.081935 0.186248 -0.0243404 0.081935 0.196143 -0.0184156 0.081935 0.196143 -0.0184156 0.083735 0.195934 -0.0175132 0.083735 0.195349 -0.0167951 0.081935 0.194507 -0.0164079 0.081935 0.196143 -0.0225825 0.083735 0.194507 -0.0164079 0.083735 0.183143 -0.0164443 0.083735 0.18337 -0.0155067 0.083735 0.18337 -0.0155067 0.081935 0.184001 -0.0147767 0.081935 0.184896 -0.014416 0.083735 0.185856 -0.0145045 0.081935 0.185856 -0.0145045 0.083735 0.183143 -0.0164443 0.081935 0.183143 -0.0225825 0.083735 0.176014 -0.0027398 0.081935 0.177682 -0.00764414 0.081935 0.180938 -0.0116733 0.081935 0.181643 -0.0132209 0.081935 0.172193 -0.00100004 0.081935 0.170418 -0.00202504 0.081935 0.170143 -0.00305004 0.081935 0.174921 -0.00122508 0.081935 0.171409 -0.029094 0.081935 0.170299 -0.0279845 0.081935 0.179593 -0.02925 0.081935 0.181043 -0.0286496 0.081935 0.179593 -0.02925 0.083735 0.172193 -0.02925 0.083735 0.172193 -0.00100004 0.083735 0.170143 -0.00305004 0.083735 0.170744 -0.0286496 0.083735 0.170299 -0.0279845 0.083735 0.181487 -0.0279845 0.083735 0.181643 -0.0272 0.083735 0.181643 -0.0272 0.081935 0.181487 -0.0279845 0.081935 0.181043 -0.0286496 0.083735 0.180378 -0.029094 0.083735 0.180378 -0.029094 0.081935 0.180938 -0.0116733 0.083735 0.181458 -0.0123704 0.083735 0.181458 -0.0123704 0.081935 0.181643 -0.0132209 0.083735 0.170744 -0.0286496 0.081935 0.171409 -0.029094 0.083735 0.172193 -0.02925 0.081935 0.171168 -0.00127469 0.081935 0.171168 -0.00127469 0.083735 0.170418 -0.00202504 0.083735 0.170143 -0.0272 0.083735 0.170143 -0.0272 0.081935 0.173987 -0.00100004 0.081935 0.174921 -0.00122508 0.083735 0.17565 -0.0018508 0.081935 0.17565 -0.0018508 0.083735 0.176014 -0.0027398 0.083735 0.173987 -0.00100004 0.083735 0.177682 -0.00764414 0.083735 0.195118 -0.0494497 0.081935 0.183744 -0.0654996 0.081935 0.183299 -0.0648345 0.081935 0.195118 -0.0658254 0.081935 0.194093 -0.0661 0.081935 0.185193 -0.0661 0.081935 0.183143 -0.051225 0.081935 0.194093 -0.049175 0.081935 0.185193 -0.0661 0.083735 0.183299 -0.0648345 0.083735 0.195118 -0.0494497 0.083735 0.195869 -0.0502 0.083735 0.194093 -0.049175 0.083735 0.196143 -0.051225 0.083735 0.185193 -0.049175 0.083735 0.183143 -0.051225 0.083735 0.196143 -0.06405 0.083735 0.196143 -0.06405 0.081935 0.195869 -0.065075 0.083735 0.195118 -0.0658254 0.083735 0.195869 -0.065075 0.081935 0.195869 -0.0502 0.081935 0.196143 -0.051225 0.081935 0.183744 -0.0654996 0.083735 0.184409 -0.065944 0.083735 0.184409 -0.065944 0.081935 0.194093 -0.0661 0.083735 0.183418 -0.0502 0.083735 0.184168 -0.0494497 0.083735 0.183418 -0.0502 0.081935 0.184168 -0.0494497 0.081935 0.183143 -0.06405 0.083735 0.183143 -0.06405 0.081935 0.185193 -0.049175 0.081935 0.212402 -0.0658254 0.081935 0.212826 -0.0497755 0.081935 0.213427 -0.051225 0.081935 0.198668 -0.0494497 0.081935 0.198668 -0.0658254 0.081935 0.197643 -0.06405 0.081935 0.197643 -0.051225 0.081935 0.211377 -0.049175 0.081935 0.212161 -0.0493311 0.083735 0.198668 -0.0494497 0.083735 0.212402 -0.0658254 0.083735 0.213427 -0.06405 0.083735 0.211377 -0.0661 0.083735 0.199693 -0.0661 0.083735 0.197643 -0.06405 0.083735 0.212826 -0.0497755 0.083735 0.211377 -0.0661 0.081935 0.213152 -0.065075 0.081935 0.213152 -0.065075 0.083735 0.212161 -0.0493311 0.081935 0.213271 -0.0504405 0.083735 0.213427 -0.051225 0.083735 0.213271 -0.0504405 0.081935 0.199693 -0.049175 0.083735 0.197918 -0.0502 0.081935 0.197918 -0.0502 0.083735 0.197643 -0.051225 0.083735 0.211377 -0.049175 0.083735 0.199693 -0.049175 0.081935 0.198668 -0.0658254 0.083735 0.197918 -0.065075 0.083735 0.197918 -0.065075 0.081935 0.199693 -0.0661 0.081935 0.213427 -0.06405 0.081935 -0.205173 -0.0773996 0.081935 -0.178882 -0.0676 0.081935 -0.205773 -0.06965 0.081935 -0.177857 -0.0678747 0.081935 -0.180897 -0.077844 0.081935 -0.180232 -0.0773996 0.083435 -0.181681 -0.078 0.083435 -0.203723 -0.078 0.083435 -0.204508 -0.077844 0.083435 -0.205773 -0.06965 0.083435 -0.205773 -0.07595 0.083435 -0.205173 -0.0773996 0.083435 -0.177857 -0.0678747 0.083435 -0.203723 -0.0676 0.083435 -0.204748 -0.0678747 0.083435 -0.176832 -0.06965 0.081935 -0.176832 -0.06965 0.083435 -0.177107 -0.068625 0.081935 -0.177107 -0.068625 0.083435 -0.176988 -0.0739354 0.081935 -0.176832 -0.0731509 0.081935 -0.176988 -0.0739354 0.083435 -0.176832 -0.0731509 0.083435 -0.181681 -0.078 0.081935 -0.180897 -0.077844 0.083435 -0.205617 -0.0767345 0.083435 -0.205617 -0.0767345 0.081935 -0.204508 -0.077844 0.081935 -0.205499 -0.068625 0.081935 -0.205499 -0.068625 0.083435 -0.204748 -0.0678747 0.081935 -0.205773 -0.07595 0.081935 -0.203723 -0.078 0.081935 -0.177433 -0.0746005 0.083435 -0.180232 -0.0773996 0.081935 -0.177433 -0.0746005 0.081935 -0.178882 -0.0676 0.083435 -0.203723 -0.0676 0.081935 0.174486 -0.0731509 0.081935 0.203427 -0.07595 0.081935 0.202161 -0.077844 0.081935 0.179335 -0.078 0.081935 0.202402 -0.0678747 0.081935 0.201377 -0.0676 0.081935 0.175086 -0.0682005 0.081935 0.176536 -0.0676 0.081935 0.174642 -0.0688655 0.081935 0.174642 -0.0739354 0.083435 0.203152 -0.068625 0.083435 0.203427 -0.06965 0.083435 0.203427 -0.07595 0.083435 0.203271 -0.0767345 0.083435 0.176536 -0.0676 0.083435 0.174486 -0.0731509 0.083435 0.177885 -0.0773996 0.083435 0.174642 -0.0739354 0.081935 0.175751 -0.0677561 0.081935 0.175751 -0.0677561 0.083435 0.175086 -0.0682005 0.083435 0.174642 -0.0688655 0.083435 0.174486 -0.06965 0.081935 0.174486 -0.06965 0.083435 0.17855 -0.077844 0.081935 0.17855 -0.077844 0.083435 0.179335 -0.078 0.083435 0.175086 -0.0746005 0.081935 0.175086 -0.0746005 0.083435 0.177885 -0.0773996 0.081935 0.201377 -0.078 0.083435 0.202161 -0.077844 0.083435 0.202826 -0.0773996 0.081935 0.202826 -0.0773996 0.083435 0.203271 -0.0767345 0.081935 0.201377 -0.078 0.081935 0.203152 -0.068625 0.081935 0.202402 -0.0678747 0.083435 0.201377 -0.0676 0.083435 0.203427 -0.06965 0.081935 0.180618 -0.0494497 0.081935 0.172193 -0.049175 0.081935 0.180618 -0.0658254 0.081935 0.179593 -0.0661 0.081935 0.181369 -0.065075 0.081935 0.181643 -0.06405 0.081935 0.170143 -0.06405 0.081935 0.171168 -0.0658254 0.081935 0.172193 -0.0661 0.081935 0.170143 -0.051225 0.081935 0.181643 -0.051225 0.081935 0.179593 -0.049175 0.083735 0.172193 -0.049175 0.083735 0.170418 -0.0502 0.083735 0.170418 -0.065075 0.083735 0.170143 -0.06405 0.083735 0.181643 -0.06405 0.083735 0.181369 -0.065075 0.083735 0.180618 -0.0658254 0.083735 0.181643 -0.051225 0.083735 0.181369 -0.0502 0.081935 0.181369 -0.0502 0.083735 0.180618 -0.0494497 0.083735 0.179593 -0.049175 0.081935 0.170418 -0.065075 0.081935 0.171168 -0.0658254 0.083735 0.172193 -0.0661 0.083735 0.179593 -0.0661 0.083735 0.170143 -0.051225 0.083735 0.170418 -0.0502 0.081935 0.171168 -0.0494497 0.083735 0.171168 -0.0494497 0.081935 0.179593 -0.047675 0.081935 0.181369 -0.04665 0.081935 0.181643 -0.045625 0.081935 0.170143 -0.045625 0.081935 0.181369 -0.04665 0.083735 0.180618 -0.0474004 0.083735 0.181643 -0.045625 0.083735 0.181643 -0.0328 0.083735 0.179593 -0.03075 0.083735 0.170418 -0.031775 0.083735 0.171168 -0.0310247 0.083735 0.170143 -0.045625 0.083735 0.170418 -0.04665 0.083735 0.171168 -0.0474004 0.083735 0.170418 -0.04665 0.081935 0.171168 -0.0474004 0.081935 0.172193 -0.047675 0.081935 0.172193 -0.047675 0.083735 0.179593 -0.047675 0.083735 0.180618 -0.0474004 0.081935 0.181643 -0.0328 0.081935 0.181369 -0.031775 0.083735 0.181369 -0.031775 0.081935 0.180618 -0.0310247 0.081935 0.179593 -0.03075 0.081935 0.180618 -0.0310247 0.083735 0.170418 -0.031775 0.081935 0.172193 -0.03075 0.083735 0.171168 -0.0310247 0.081935 0.172193 -0.03075 0.081935 0.170143 -0.0328 0.083735 0.170143 -0.0328 0.081935 0.183744 -0.0470746 0.081935 0.196143 -0.0374176 0.081935 0.196143 -0.045625 0.081935 0.190826 -0.0364933 0.081935 0.185193 -0.047675 0.081935 0.194093 -0.047675 0.081935 0.195118 -0.0474004 0.081935 0.183299 -0.0464095 0.081935 0.188461 -0.0364933 0.081935 0.183143 -0.045625 0.081935 0.186248 -0.0356597 0.081935 0.183143 -0.0374176 0.081935 0.183832 -0.035885 0.081935 0.183323 -0.0365775 0.081935 0.194093 -0.047675 0.083735 0.196143 -0.045625 0.083735 0.195455 -0.035885 0.083735 0.193852 -0.0353819 0.083735 0.184579 -0.0354616 0.083735 0.183143 -0.0374176 0.083735 0.188461 -0.0364933 0.083735 0.186248 -0.0356597 0.083735 0.183143 -0.045625 0.083735 0.195869 -0.04665 0.083735 0.195118 -0.0474004 0.083735 0.195869 -0.04665 0.081935 0.193039 -0.0356597 0.083735 0.193039 -0.0356597 0.081935 0.193852 -0.0353819 0.081935 0.194707 -0.0354616 0.083735 0.194707 -0.0354616 0.081935 0.195455 -0.035885 0.081935 0.195963 -0.0365775 0.083735 0.196143 -0.0374176 0.083735 0.195963 -0.0365775 0.081935 0.183299 -0.0464095 0.083735 0.183744 -0.0470746 0.083735 0.184409 -0.047519 0.081935 0.184409 -0.047519 0.083735 0.185193 -0.047675 0.083735 0.183323 -0.0365775 0.083735 0.183832 -0.035885 0.083735 0.185435 -0.0353819 0.083735 0.184579 -0.0354616 0.081935 0.185435 -0.0353819 0.081935 0.190826 -0.0364933 0.083735 -0.17249 0.051225 0.081935 -0.18399 0.06405 0.081935 -0.17249 0.06405 0.081935 -0.18399 0.051225 0.081935 -0.183715 0.065075 0.081935 -0.17309 0.0654995 0.081935 -0.17249 0.051225 0.083735 -0.183715 0.0502 0.083735 -0.18194 0.049175 0.083735 -0.18399 0.06405 0.083735 -0.17309 0.0654995 0.083735 -0.183715 0.065075 0.083735 -0.182965 0.0658253 0.083735 -0.18194 0.0661 0.083735 -0.182965 0.0658253 0.081935 -0.18399 0.051225 0.083735 -0.183715 0.0502 0.081935 -0.182965 0.0494496 0.081935 -0.182965 0.0494496 0.083735 -0.172646 0.0648345 0.081935 -0.17249 0.06405 0.083735 -0.172646 0.0648345 0.083735 -0.173755 0.0659439 0.081935 -0.17454 0.0661 0.081935 -0.173755 0.0659439 0.083735 -0.17454 0.0661 0.083735 -0.18194 0.0661 0.081935 -0.172764 0.0502 0.083735 -0.172764 0.0502 0.081935 -0.173515 0.0494496 0.081935 -0.173515 0.0494496 0.083735 -0.17454 0.049175 0.083735 -0.18194 0.049175 0.081935 -0.17454 0.049175 0.081935 -0.17454 0.03075 0.081935 -0.182965 0.0474003 0.081935 -0.18194 0.047675 0.081935 -0.17249 0.0328 0.081935 -0.183715 0.031775 0.081935 -0.183715 0.031775 0.083735 -0.173515 0.0310246 0.083735 -0.17249 0.0328 0.083735 -0.18399 0.045625 0.083735 -0.18194 0.047675 0.083735 -0.17249 0.045625 0.083735 -0.172764 0.04665 0.081935 -0.172764 0.04665 0.083735 -0.173515 0.0474003 0.083735 -0.173515 0.0474003 0.081935 -0.17454 0.047675 0.081935 -0.183715 0.04665 0.083735 -0.18399 0.045625 0.081935 -0.182965 0.0474003 0.083735 -0.183715 0.04665 0.081935 -0.182965 0.0310246 0.081935 -0.18194 0.03075 0.081935 -0.182965 0.0310246 0.083735 -0.18194 0.03075 0.083735 -0.18399 0.0328 0.081935 -0.18399 0.0328 0.083735 -0.172764 0.031775 0.083735 -0.172764 0.031775 0.081935 -0.173515 0.0310246 0.081935 -0.17454 0.03075 0.083735 -0.17249 0.045625 0.081935 -0.17454 0.047675 0.083735 -0.193172 0.0364932 0.081935 -0.188594 0.0356596 0.081935 -0.186178 0.0358849 0.081935 -0.185764 0.04665 0.081935 -0.190807 0.0364932 0.081935 -0.18549 0.045625 0.081935 -0.18567 0.0365774 0.081935 -0.197053 0.0354616 0.081935 -0.195385 0.0356596 0.081935 -0.197801 0.0358849 0.081935 -0.19831 0.0365774 0.081935 -0.19849 0.0374175 0.081935 -0.18549 0.0374175 0.083735 -0.197465 0.0474003 0.083735 -0.186926 0.0354616 0.083735 -0.186178 0.0358849 0.083735 -0.19849 0.045625 0.083735 -0.198215 0.04665 0.083735 -0.193172 0.0364932 0.083735 -0.19644 0.047675 0.083735 -0.18754 0.047675 0.083735 -0.186515 0.0474003 0.083735 -0.196198 0.0353818 0.083735 -0.195385 0.0356596 0.083735 -0.198215 0.04665 0.081935 -0.197465 0.0474003 0.081935 -0.19644 0.047675 0.081935 -0.196198 0.0353818 0.081935 -0.197053 0.0354616 0.083735 -0.197801 0.0358849 0.083735 -0.19831 0.0365774 0.083735 -0.19849 0.0374175 0.083735 -0.19849 0.045625 0.081935 -0.185764 0.04665 0.083735 -0.186515 0.0474003 0.081935 -0.18754 0.047675 0.081935 -0.18549 0.0374175 0.081935 -0.18567 0.0365774 0.083735 -0.186926 0.0354616 0.081935 -0.187781 0.0353818 0.083735 -0.188594 0.0356596 0.083735 -0.187781 0.0353818 0.081935 -0.18549 0.045625 0.083735 -0.190807 0.0364932 0.083735 0.213427 0.051225 0.081935 0.211377 0.049175 0.081935 0.212161 0.049331 0.081935 0.197918 0.065075 0.081935 0.199693 0.0661 0.081935 0.211377 0.0661 0.081935 0.197643 0.06405 0.081935 0.213427 0.06405 0.081935 0.213271 0.0648345 0.081935 0.198668 0.0494496 0.081935 0.199693 0.049175 0.081935 0.199693 0.049175 0.083735 0.211377 0.049175 0.083735 0.213427 0.051225 0.083735 0.211377 0.0661 0.083735 0.197643 0.06405 0.083735 0.199693 0.0661 0.083735 0.198668 0.0658253 0.083735 0.212826 0.0654995 0.083735 0.213271 0.0504405 0.081935 0.213271 0.0504405 0.083735 0.212826 0.0497754 0.083735 0.212826 0.0497754 0.081935 0.212161 0.049331 0.083735 0.197918 0.0502 0.081935 0.197918 0.0502 0.083735 0.198668 0.0494496 0.083735 0.213271 0.0648345 0.083735 0.212826 0.0654995 0.081935 0.212161 0.0659439 0.081935 0.212161 0.0659439 0.083735 0.213427 0.06405 0.083735 0.197918 0.065075 0.083735 0.198668 0.0658253 0.081935 0.197643 0.051225 0.083735 0.197643 0.051225 0.081935 0.203427 0.06965 0.081935 0.175086 0.0682004 0.081935 0.202161 0.067756 0.081935 0.174486 0.06965 0.081935 0.201377 0.0676 0.081935 0.202402 0.0777253 0.081935 0.201377 0.078 0.081935 0.179335 0.078 0.081935 0.174642 0.0739353 0.083435 0.201377 0.0676 0.083435 0.176536 0.0676 0.083435 0.175751 0.067756 0.083435 0.174486 0.06965 0.083435 0.203152 0.076975 0.083435 0.175086 0.0746004 0.083435 0.203271 0.0688655 0.083435 0.202826 0.0682004 0.083435 0.201377 0.078 0.083435 0.179335 0.078 0.083435 0.174486 0.0731508 0.083435 0.17855 0.0778439 0.081935 0.17855 0.0778439 0.083435 0.203152 0.076975 0.081935 0.202402 0.0777253 0.083435 0.202826 0.0682004 0.081935 0.202161 0.067756 0.083435 0.203271 0.0688655 0.081935 0.203427 0.06965 0.083435 0.174486 0.0731508 0.081935 0.174642 0.0739353 0.081935 0.174642 0.0688655 0.081935 0.174642 0.0688655 0.083435 0.175086 0.0682004 0.083435 0.175751 0.067756 0.081935 0.176536 0.0676 0.081935 0.203427 0.07595 0.083435 0.203427 0.07595 0.081935 0.177885 0.0773995 0.083435 0.177885 0.0773995 0.081935 0.175086 0.0746004 0.081935 0.172211 0.072975 0.081935 0.129387 0.0682004 0.081935 0.130052 0.067756 0.081935 0.172486 0.06965 0.081935 0.172486 0.07195 0.081935 0.130052 0.0738439 0.081935 0.171885 0.0682004 0.081935 0.17233 0.0688655 0.081935 0.128787 0.07195 0.081935 0.172211 0.072975 0.083435 0.170436 0.074 0.083435 0.128787 0.06965 0.083435 0.129387 0.0682004 0.083435 0.17122 0.067756 0.083435 0.170436 0.0676 0.081935 0.17122 0.067756 0.081935 0.171885 0.0682004 0.083435 0.17233 0.0688655 0.083435 0.172486 0.06965 0.083435 0.170436 0.074 0.081935 0.171461 0.0737253 0.083435 0.171461 0.0737253 0.081935 0.172486 0.07195 0.083435 0.130837 0.074 0.083435 0.129387 0.0733995 0.081935 0.130052 0.0738439 0.083435 0.129387 0.0733995 0.083435 0.128943 0.0727345 0.081935 0.128943 0.0727345 0.083435 0.130837 0.0676 0.083435 0.130837 0.0676 0.081935 0.130052 0.067756 0.083435 0.128943 0.0688655 0.081935 0.128943 0.0688655 0.083435 0.128787 0.06965 0.081935 0.128787 0.07195 0.083435 0.130837 0.074 0.081935 0.170436 0.0676 0.083435 -0.0364432 0.074 0.081935 -0.0384932 0.07195 0.081935 -0.0383372 0.0688655 0.081935 -0.00244785 0.072975 0.081935 -0.00277363 0.0682004 0.081935 -0.0034387 0.067756 0.081935 -0.0042232 0.0676 0.081935 -0.0031982 0.0737253 0.081935 -0.0042232 0.074 0.081935 -0.0021732 0.07195 0.081935 -0.0021732 0.06965 0.081935 -0.0031982 0.0737253 0.083435 -0.0042232 0.074 0.083435 -0.00277363 0.0682004 0.083435 -0.00232925 0.0688655 0.083435 -0.0034387 0.067756 0.083435 -0.0021732 0.07195 0.083435 -0.0384932 0.07195 0.083435 -0.0382186 0.072975 0.083435 -0.0378928 0.0682004 0.083435 -0.0364432 0.074 0.083435 -0.0384932 0.06965 0.083435 -0.0042232 0.0676 0.083435 -0.0364432 0.0676 0.083435 -0.00232925 0.0688655 0.081935 -0.0021732 0.06965 0.083435 -0.00244785 0.072975 0.083435 -0.0374682 0.0737253 0.083435 -0.0374682 0.0737253 0.081935 -0.0382186 0.072975 0.081935 -0.0364432 0.0676 0.081935 -0.0372277 0.067756 0.081935 -0.0372277 0.067756 0.083435 -0.0378928 0.0682004 0.081935 -0.0383372 0.0688655 0.083435 -0.0384932 0.06965 0.081935 -0.0021732 -0.06965 0.081935 -0.00244785 -0.068625 0.081935 -0.0384932 -0.07195 0.081935 -0.0374682 -0.0678747 0.081935 -0.0382186 -0.068625 0.081935 -0.0384932 -0.06965 0.081935 -0.0042232 -0.0676 0.081935 -0.00244785 -0.072975 0.081935 -0.0364432 -0.074 0.081935 -0.0378928 -0.0733996 0.083435 -0.0364432 -0.074 0.083435 -0.0021732 -0.07195 0.083435 -0.0042232 -0.074 0.083435 -0.0021732 -0.06965 0.083435 -0.0382186 -0.068625 0.083435 -0.0031982 -0.0678747 0.083435 -0.00244785 -0.068625 0.083435 -0.0031982 -0.0678747 0.081935 -0.00244785 -0.072975 0.083435 -0.0031982 -0.0737254 0.081935 -0.0031982 -0.0737254 0.083435 -0.0021732 -0.07195 0.081935 -0.0383372 -0.0727345 0.081935 -0.0378928 -0.0733996 0.081935 -0.0383372 -0.0727345 0.083435 -0.0372277 -0.073844 0.081935 -0.0372277 -0.073844 0.083435 -0.0384932 -0.06965 0.083435 -0.0374682 -0.0678747 0.083435 -0.0384932 -0.07195 0.083435 -0.0042232 -0.074 0.081935 -0.0364432 -0.0676 0.081935 -0.0042232 -0.0676 0.083435 -0.0364432 -0.0676 0.083435 0.0461718 -0.0678747 0.081935 0.0454214 -0.068625 0.081935 0.0451468 -0.06965 0.081935 0.0464123 -0.073844 0.081935 0.0451468 -0.07195 0.081935 0.0804418 -0.0737254 0.081935 0.0811922 -0.072975 0.081935 0.0794168 -0.074 0.081935 0.0471968 -0.074 0.081935 0.0814668 -0.07195 0.081935 0.0814668 -0.06965 0.081935 0.0794168 -0.0676 0.081935 0.0804418 -0.0678747 0.081935 0.0457472 -0.0733996 0.083435 0.0461718 -0.0678747 0.083435 0.0451468 -0.06965 0.083435 0.0471968 -0.0676 0.083435 0.0811922 -0.068625 0.083435 0.0804418 -0.0678747 0.083435 0.0811922 -0.072975 0.083435 0.0814668 -0.06965 0.083435 0.0811922 -0.068625 0.081935 0.0814668 -0.07195 0.083435 0.0804418 -0.0737254 0.083435 0.0794168 -0.074 0.083435 0.0451468 -0.07195 0.083435 0.0453028 -0.0727345 0.081935 0.0457472 -0.0733996 0.081935 0.0453028 -0.0727345 0.083435 0.0464123 -0.073844 0.083435 0.0471968 -0.074 0.083435 0.0454214 -0.068625 0.083435 0.0794168 -0.0676 0.083435 0.0471968 -0.0676 0.081935 -0.122133 -0.07195 0.081935 -0.120868 -0.073844 0.081935 -0.0868382 -0.0737254 0.081935 -0.0860878 -0.072975 0.081935 -0.120083 -0.0676 0.081935 -0.0878632 -0.074 0.083435 -0.120083 -0.074 0.083435 -0.122133 -0.07195 0.083435 -0.121977 -0.0727345 0.083435 -0.122133 -0.06965 0.083435 -0.120083 -0.0676 0.083435 -0.0878632 -0.0676 0.083435 -0.0858132 -0.07195 0.083435 -0.0858132 -0.06965 0.081935 -0.0860878 -0.068625 0.081935 -0.0858132 -0.06965 0.083435 -0.0860878 -0.068625 0.083435 -0.0868382 -0.0678747 0.083435 -0.0868382 -0.0678747 0.081935 -0.0878632 -0.0676 0.081935 -0.0860878 -0.072975 0.083435 -0.0868382 -0.0737254 0.083435 -0.0878632 -0.074 0.081935 -0.0858132 -0.07195 0.081935 -0.121977 -0.0727345 0.081935 -0.121533 -0.0733996 0.081935 -0.121533 -0.0733996 0.083435 -0.120868 -0.073844 0.083435 -0.120083 -0.074 0.081935 -0.121859 -0.068625 0.081935 -0.121859 -0.068625 0.083435 -0.121108 -0.0678747 0.081935 -0.121108 -0.0678747 0.083435 -0.122133 -0.06965 0.081935 0.129061 -0.068625 0.081935 0.128787 -0.07195 0.081935 0.172486 -0.07195 0.081935 0.172486 -0.06965 0.081935 0.171461 -0.0678747 0.081935 0.170436 -0.0676 0.081935 0.130837 -0.0676 0.081935 0.128943 -0.0727345 0.083435 0.128787 -0.07195 0.083435 0.172211 -0.068625 0.083435 0.170436 -0.074 0.083435 0.172486 -0.07195 0.083435 0.172486 -0.06965 0.083435 0.128787 -0.06965 0.083435 0.130837 -0.0676 0.083435 0.130052 -0.073844 0.083435 0.172211 -0.068625 0.081935 0.171461 -0.0678747 0.083435 0.170436 -0.0676 0.083435 0.17233 -0.0727345 0.083435 0.171885 -0.0733996 0.083435 0.17233 -0.0727345 0.081935 0.171885 -0.0733996 0.081935 0.17122 -0.073844 0.083435 0.17122 -0.073844 0.081935 0.128943 -0.0727345 0.081935 0.129387 -0.0733996 0.081935 0.129387 -0.0733996 0.083435 0.130052 -0.073844 0.081935 0.130837 -0.074 0.081935 0.130837 -0.074 0.083435 0.128787 -0.06965 0.081935 0.129061 -0.068625 0.083435 0.129812 -0.0678747 0.083435 0.129812 -0.0678747 0.081935 0.170436 -0.074 0.081935 0.0834668 -0.07195 0.081935 0.0837414 -0.072975 0.081935 0.118521 -0.0677561 0.081935 0.119787 -0.07195 0.081935 0.117737 -0.074 0.081935 0.0855168 -0.074 0.081935 0.0844918 -0.0678747 0.081935 0.119186 -0.0682005 0.081935 0.0855168 -0.0676 0.081935 0.0837414 -0.072975 0.083435 0.0834668 -0.07195 0.083435 0.118521 -0.0677561 0.083435 0.119631 -0.0688655 0.083435 0.118762 -0.0737254 0.083435 0.119787 -0.07195 0.083435 0.117737 -0.074 0.083435 0.0837414 -0.068625 0.083435 0.0855168 -0.0676 0.083435 0.117737 -0.0676 0.083435 0.119787 -0.06965 0.083435 0.119512 -0.072975 0.083435 0.119512 -0.072975 0.081935 0.118762 -0.0737254 0.081935 0.119787 -0.06965 0.081935 0.119631 -0.0688655 0.081935 0.119186 -0.0682005 0.083435 0.117737 -0.0676 0.081935 0.0844918 -0.0737254 0.083435 0.0844918 -0.0737254 0.081935 0.0837414 -0.068625 0.081935 0.0844918 -0.0678747 0.083435 0.0834668 -0.06965 0.081935 0.0834668 -0.06965 0.083435 0.0855168 -0.074 0.083435 -0.0485182 -0.0737254 0.081935 -0.0477678 -0.072975 0.081935 -0.0495432 -0.074 0.081935 -0.0474932 -0.07195 0.081935 -0.0480936 -0.0682005 0.081935 -0.0476492 -0.0688655 0.081935 -0.0835386 -0.068625 0.081935 -0.0838132 -0.06965 0.081935 -0.0495432 -0.0676 0.081935 -0.0480936 -0.0682005 0.083435 -0.0838132 -0.06965 0.083435 -0.0835386 -0.072975 0.083435 -0.0477678 -0.072975 0.083435 -0.0485182 -0.0737254 0.083435 -0.0474932 -0.06965 0.083435 -0.0476492 -0.0688655 0.083435 -0.0487587 -0.0677561 0.081935 -0.0487587 -0.0677561 0.083435 -0.0474932 -0.06965 0.081935 -0.0474932 -0.07195 0.083435 -0.0817632 -0.074 0.081935 -0.0827882 -0.0737254 0.081935 -0.0827882 -0.0737254 0.083435 -0.0835386 -0.072975 0.081935 -0.0838132 -0.07195 0.083435 -0.0817632 -0.0676 0.081935 -0.0817632 -0.0676 0.083435 -0.0827882 -0.0678747 0.081935 -0.0827882 -0.0678747 0.083435 -0.0835386 -0.068625 0.083435 -0.0838132 -0.07195 0.081935 -0.0817632 -0.074 0.083435 -0.0495432 -0.074 0.083435 -0.0495432 -0.0676 0.083435 -0.132158 -0.0737254 0.081935 -0.133183 -0.0676 0.081935 -0.174832 -0.06965 0.081935 -0.133183 -0.074 0.081935 -0.172782 -0.074 0.081935 -0.173567 -0.0677561 0.081935 -0.172782 -0.0676 0.081935 -0.173567 -0.073844 0.081935 -0.131408 -0.068625 0.081935 -0.132158 -0.0678747 0.081935 -0.174232 -0.0733996 0.083435 -0.172782 -0.074 0.083435 -0.131408 -0.068625 0.083435 -0.133183 -0.0676 0.083435 -0.173567 -0.0677561 0.083435 -0.174676 -0.0688655 0.083435 -0.131133 -0.07195 0.083435 -0.174832 -0.07195 0.083435 -0.131408 -0.072975 0.083435 -0.131133 -0.07195 0.081935 -0.131408 -0.072975 0.081935 -0.132158 -0.0737254 0.083435 -0.133183 -0.074 0.083435 -0.131133 -0.06965 0.083435 -0.132158 -0.0678747 0.083435 -0.131133 -0.06965 0.081935 -0.173567 -0.073844 0.083435 -0.174232 -0.0733996 0.081935 -0.174676 -0.0727345 0.083435 -0.174676 -0.0727345 0.081935 -0.174232 -0.0682005 0.081935 -0.174232 -0.0682005 0.083435 -0.174676 -0.0688655 0.081935 -0.174832 -0.06965 0.083435 -0.174832 -0.07195 0.081935 -0.172782 -0.0676 0.083435 0.0018768 -0.074 0.081935 0.0340968 -0.0676 0.081935 0.0361468 -0.07195 0.081935 0.0348813 -0.0677561 0.081935 0.0010923 -0.073844 0.083435 0.0355464 -0.0682005 0.083435 0.0010923 -0.0677561 0.083435 0.0018768 -0.0676 0.083435 -1.7154e-05 -0.0688655 0.083435 0.0361468 -0.07195 0.083435 0.0359908 -0.0727345 0.083435 0.0355464 -0.0733996 0.083435 0.0359908 -0.0727345 0.081935 0.0355464 -0.0733996 0.081935 0.0348813 -0.073844 0.083435 0.0348813 -0.073844 0.081935 0.0340968 -0.074 0.081935 0.0361468 -0.06965 0.081935 0.0359908 -0.0688655 0.081935 0.0359908 -0.0688655 0.083435 0.0355464 -0.0682005 0.081935 0.0348813 -0.0677561 0.083435 0.0361468 -0.06965 0.083435 0.0018768 -0.074 0.083435 0.00042723 -0.0733996 0.083435 0.0010923 -0.073844 0.081935 0.00042723 -0.0733996 0.081935 -1.7154e-05 -0.0727345 0.083435 -1.7154e-05 -0.0727345 0.081935 -0.000173201 -0.07195 0.083435 0.0010923 -0.0677561 0.081935 0.00042723 -0.0682005 0.083435 0.00042723 -0.0682005 0.081935 -1.7154e-05 -0.0688655 0.081935 -0.000173201 -0.06965 0.083435 -0.000173201 -0.06965 0.081935 -0.000173201 -0.07195 0.081935 0.0340968 -0.074 0.083435 0.0340968 -0.0676 0.083435 0.0018768 -0.0676 0.081935 -0.122133 0.07195 0.081935 -0.0878632 0.074 0.081935 -0.0860878 0.068625 0.081935 -0.0858132 0.06965 0.081935 -0.122133 0.06965 0.081935 -0.0860878 0.072975 0.081935 -0.121533 0.0733995 0.083435 -0.122133 0.07195 0.083435 -0.120868 0.0738439 0.083435 -0.120083 0.074 0.083435 -0.0878632 0.074 0.083435 -0.120868 0.067756 0.083435 -0.0868382 0.0737253 0.083435 -0.0858132 0.07195 0.083435 -0.0868382 0.0678746 0.081935 -0.0868382 0.0678746 0.083435 -0.0860878 0.068625 0.083435 -0.0858132 0.06965 0.083435 -0.0860878 0.072975 0.083435 -0.0868382 0.0737253 0.081935 -0.0858132 0.07195 0.081935 -0.120868 0.0738439 0.081935 -0.121533 0.0733995 0.081935 -0.121977 0.0727345 0.081935 -0.121977 0.0727345 0.083435 -0.120083 0.0676 0.081935 -0.121533 0.0682004 0.083435 -0.120868 0.067756 0.081935 -0.121533 0.0682004 0.081935 -0.121977 0.0688655 0.083435 -0.122133 0.06965 0.083435 -0.121977 0.0688655 0.081935 -0.120083 0.0676 0.083435 -0.0878632 0.0676 0.083435 -0.0878632 0.0676 0.081935 -0.120083 0.074 0.081935 0.0471968 0.074 0.081935 0.0471968 0.0676 0.081935 0.0453028 0.0688655 0.081935 0.0451468 0.06965 0.081935 0.0814668 0.07195 0.081935 0.0804418 0.0737253 0.081935 0.0794168 0.0676 0.081935 0.0804418 0.0678746 0.081935 0.0457472 0.0682004 0.083435 0.0451468 0.07195 0.083435 0.0471968 0.074 0.083435 0.0814668 0.06965 0.083435 0.0804418 0.0678746 0.083435 0.0811922 0.068625 0.081935 0.0814668 0.06965 0.081935 0.0811922 0.068625 0.083435 0.0804418 0.0737253 0.083435 0.0811922 0.072975 0.083435 0.0811922 0.072975 0.081935 0.0814668 0.07195 0.083435 0.0461718 0.0737253 0.081935 0.0461718 0.0737253 0.083435 0.0454214 0.072975 0.081935 0.0454214 0.072975 0.083435 0.0451468 0.07195 0.081935 0.0464123 0.067756 0.083435 0.0464123 0.067756 0.081935 0.0457472 0.0682004 0.081935 0.0453028 0.0688655 0.083435 0.0451468 0.06965 0.083435 0.0471968 0.0676 0.083435 0.0794168 0.0676 0.083435 0.0794168 0.074 0.081935 0.0794168 0.074 0.083435 -0.0817632 0.0676 0.081935 -0.0495432 0.074 0.081935 -0.0836572 0.0727345 0.081935 -0.0838132 0.06965 0.081935 -0.0485182 0.0737253 0.081935 -0.0480936 0.0682004 0.081935 -0.0495432 0.074 0.083435 -0.0495432 0.0676 0.083435 -0.0476492 0.0688655 0.083435 -0.0838132 0.06965 0.083435 -0.0832128 0.0682004 0.083435 -0.0817632 0.0676 0.083435 -0.0836572 0.0727345 0.083435 -0.0825477 0.0738439 0.083435 -0.0485182 0.0737253 0.083435 -0.0477678 0.072975 0.083435 -0.0477678 0.072975 0.081935 -0.0474932 0.07195 0.083435 -0.0474932 0.07195 0.081935 -0.0495432 0.0676 0.081935 -0.0487587 0.067756 0.081935 -0.0487587 0.067756 0.083435 -0.0476492 0.0688655 0.081935 -0.0480936 0.0682004 0.083435 -0.0474932 0.06965 0.081935 -0.0474932 0.06965 0.083435 -0.0838132 0.07195 0.081935 -0.0832128 0.0733995 0.083435 -0.0832128 0.0733995 0.081935 -0.0825477 0.0738439 0.081935 -0.0817632 0.074 0.083435 -0.0817632 0.074 0.081935 -0.0836572 0.0688655 0.081935 -0.0836572 0.0688655 0.083435 -0.0832128 0.0682004 0.081935 -0.0825477 0.067756 0.083435 -0.0825477 0.067756 0.081935 -0.0838132 0.07195 0.083435 0.118521 0.067756 0.081935 0.119186 0.0682004 0.081935 0.119186 0.0733995 0.081935 0.118521 0.0738439 0.081935 0.117737 0.074 0.081935 0.119787 0.07195 0.081935 0.119631 0.0727345 0.081935 0.0847323 0.0738439 0.081935 0.0847323 0.067756 0.081935 0.0840672 0.0733995 0.081935 0.0855168 0.074 0.081935 0.0834668 0.06965 0.081935 0.119787 0.07195 0.083435 0.118521 0.0738439 0.083435 0.0855168 0.074 0.083435 0.0834668 0.07195 0.083435 0.119631 0.0688655 0.083435 0.118521 0.067756 0.083435 0.119787 0.06965 0.083435 0.117737 0.074 0.083435 0.119186 0.0733995 0.083435 0.119631 0.0727345 0.083435 0.117737 0.0676 0.081935 0.119631 0.0688655 0.081935 0.119186 0.0682004 0.083435 0.119787 0.06965 0.081935 0.0834668 0.07195 0.081935 0.0836228 0.0727345 0.083435 0.0840672 0.0733995 0.083435 0.0836228 0.0727345 0.081935 0.0847323 0.0738439 0.083435 0.0836228 0.0688655 0.081935 0.0836228 0.0688655 0.083435 0.0840672 0.0682004 0.083435 0.0840672 0.0682004 0.081935 0.0855168 0.0676 0.081935 0.0847323 0.067756 0.083435 0.0834668 0.06965 0.083435 0.0855168 0.0676 0.083435 0.117737 0.0676 0.083435 0.0358722 0.068625 0.081935 0.0348813 0.0738439 0.081935 0.0359908 0.0727345 0.081935 0.0010923 0.0738439 0.081935 0.000101447 0.068625 0.081935 0.0340968 0.074 0.081935 0.0018768 0.074 0.083435 -0.000173201 0.06965 0.083435 -0.000173201 0.07195 0.083435 0.0340968 0.074 0.083435 0.0351218 0.0678746 0.083435 0.0361468 0.06965 0.083435 0.0018768 0.0676 0.083435 0.0348813 0.0738439 0.083435 0.0361468 0.07195 0.083435 0.0355464 0.0733995 0.083435 0.0359908 0.0727345 0.083435 0.0355464 0.0733995 0.081935 0.0361468 0.07195 0.081935 0.0340968 0.0676 0.081935 0.0340968 0.0676 0.083435 0.0351218 0.0678746 0.081935 0.0358722 0.068625 0.083435 0.0361468 0.06965 0.081935 -0.000173201 0.07195 0.081935 -1.7154e-05 0.0727345 0.081935 -1.7154e-05 0.0727345 0.083435 0.00042723 0.0733995 0.083435 0.00042723 0.0733995 0.081935 0.0010923 0.0738439 0.083435 -0.000173201 0.06965 0.081935 0.000101447 0.068625 0.083435 0.000851799 0.0678746 0.081935 0.000851799 0.0678746 0.083435 0.0018768 0.0676 0.081935 0.0018768 0.074 0.081935 -0.131289 0.0727345 0.081935 -0.131734 0.0682004 0.081935 -0.131289 0.0688655 0.081935 -0.131133 0.06965 0.081935 -0.173567 0.0738439 0.081935 -0.174232 0.0682004 0.081935 -0.174676 0.0688655 0.081935 -0.172782 0.0676 0.081935 -0.174676 0.0727345 0.083435 -0.173567 0.0738439 0.083435 -0.172782 0.074 0.083435 -0.174832 0.07195 0.083435 -0.174832 0.06965 0.083435 -0.131734 0.0682004 0.083435 -0.131289 0.0688655 0.083435 -0.172782 0.0676 0.083435 -0.133183 0.0676 0.083435 -0.133183 0.074 0.083435 -0.132399 0.0738439 0.081935 -0.132399 0.0738439 0.083435 -0.131734 0.0733995 0.083435 -0.131734 0.0733995 0.081935 -0.131289 0.0727345 0.083435 -0.131133 0.07195 0.081935 -0.132399 0.067756 0.081935 -0.132399 0.067756 0.083435 -0.131133 0.06965 0.083435 -0.131133 0.07195 0.083435 -0.174832 0.07195 0.081935 -0.174676 0.0727345 0.081935 -0.174232 0.0733995 0.081935 -0.174232 0.0733995 0.083435 -0.174676 0.0688655 0.083435 -0.173567 0.067756 0.081935 -0.174232 0.0682004 0.083435 -0.173567 0.067756 0.083435 -0.174832 0.06965 0.081935 -0.133183 0.074 0.081935 -0.172782 0.074 0.081935 -0.133183 0.0676 0.081935 -0.0637996 -0.00507004 0.081935 -0.0030232 -0.0047753 0.081935 -0.00221794 -0.00397004 0.081935 -0.0019232 -0.00287004 0.081935 -0.0019232 -0.00280004 0.081935 -0.0041232 -0.00507004 0.081935 -0.0637996 -0.00507004 0.083735 -0.0041232 -0.000600042 0.083735 -0.0019232 -0.00287004 0.083735 -0.00209067 -0.00195814 0.083735 -0.0041232 -0.00507004 0.083735 -0.0030232 -0.0047753 0.083735 -0.00221794 -0.00397004 0.083735 -0.0032813 -0.000767507 0.083735 -0.0041232 -0.000600042 0.081935 -0.0032813 -0.000767507 0.081935 -0.00256757 -0.00124441 0.083735 -0.00256757 -0.00124441 0.081935 -0.00209067 -0.00195814 0.081935 -0.0019232 -0.00280004 0.083735 -0.0637996 -0.000600042 0.081935 -0.0637996 -0.000600042 0.083735 -0.000128457 -0.00170004 0.081935 0.0873768 -0.000600042 0.081935 0.000934896 -0.00490258 0.081935 0.0884768 -0.000894786 0.081935 0.0895768 -0.00280004 0.081935 -0.000423201 -0.00287004 0.081935 0.000676799 -0.000894786 0.083735 0.0017768 -0.000600042 0.083735 0.0884768 -0.000894786 0.083735 0.0895768 -0.00287004 0.083735 0.0892821 -0.00397004 0.083735 0.000221164 -0.00442568 0.083735 -0.000255736 -0.00371195 0.083735 0.0873768 -0.00507004 0.083735 0.0884768 -0.0047753 0.083735 0.0884768 -0.0047753 0.081935 0.0892821 -0.00397004 0.081935 0.0895768 -0.00287004 0.081935 0.0873768 -0.000600042 0.083735 0.0892821 -0.00170004 0.081935 0.0892821 -0.00170004 0.083735 0.0895768 -0.00280004 0.083735 0.000676799 -0.000894786 0.081935 -0.000128457 -0.00170004 0.083735 -0.000423201 -0.00280004 0.083735 0.0017768 -0.00507004 0.083735 0.0017768 -0.00507004 0.081935 0.000934896 -0.00490258 0.083735 0.000221164 -0.00442568 0.081935 -0.000255736 -0.00371195 0.081935 -0.000423201 -0.00287004 0.083735 -0.000423201 -0.00280004 0.081935 0.0017768 -0.000600042 0.081935 0.0873768 -0.00507004 0.081935 -0.0956232 -0.05163 0.081935 -0.0937179 -0.055 0.081935 -0.0934232 -0.0539 0.081935 -0.0947813 -0.0517975 0.081935 -0.0956232 -0.0561 0.081935 -0.0934232 -0.05383 0.081935 -0.13001 -0.05163 0.083735 -0.0956232 -0.0561 0.083735 -0.0945232 -0.0558053 0.083735 -0.0934232 -0.05383 0.083735 -0.0935907 -0.0529881 0.083735 -0.0940676 -0.0522744 0.083735 -0.13001 -0.0561 0.081935 -0.0945232 -0.0558053 0.081935 -0.0937179 -0.055 0.083735 -0.0956232 -0.05163 0.083735 -0.0947813 -0.0517975 0.083735 -0.0940676 -0.0522744 0.081935 -0.0935907 -0.0529881 0.081935 -0.0934232 -0.0539 0.083735 -0.13001 -0.0561 0.083735 -0.13001 -0.05163 0.081935 -0.13001 0.0561 0.081935 -0.13001 0.05163 0.081935 -0.0945232 0.0519247 0.081935 -0.0956232 0.05163 0.081935 -0.0940676 0.0554556 0.081935 -0.0935907 0.0547419 0.081935 -0.0937179 0.05273 0.083735 -0.0945232 0.0519247 0.083735 -0.0940676 0.0554556 0.083735 -0.0935907 0.0547419 0.083735 -0.0947813 0.0559325 0.083735 -0.0934232 0.0539 0.083735 -0.13001 0.05163 0.083735 -0.13001 0.0561 0.083735 -0.0956232 0.05163 0.083735 -0.0937179 0.05273 0.081935 -0.0934232 0.05383 0.081935 -0.0934232 0.05383 0.083735 -0.0956232 0.0561 0.083735 -0.0947813 0.0559325 0.081935 -0.0934232 0.0539 0.081935 -0.0956232 0.0561 0.081935 -0.0637996 0.0561 0.081935 -0.0019232 0.05383 0.081935 -0.00256757 0.0554556 0.081935 -0.0041232 0.0561 0.081935 -0.0637996 0.05163 0.081935 -0.00256757 0.0554556 0.083735 -0.00209067 0.0547419 0.083735 -0.0041232 0.05163 0.083735 -0.0019232 0.0539 0.083735 -0.0637996 0.0561 0.083735 -0.0637996 0.05163 0.083735 -0.0030232 0.0519247 0.081935 -0.0030232 0.0519247 0.083735 -0.00221794 0.05273 0.081935 -0.00221794 0.05273 0.083735 -0.0019232 0.05383 0.083735 -0.0032813 0.0559325 0.083735 -0.0032813 0.0559325 0.081935 -0.00209067 0.0547419 0.081935 -0.0019232 0.0539 0.081935 -0.0041232 0.05163 0.081935 -0.0041232 0.0561 0.083735 -0.0912788 0.0522743 0.081935 -0.0916285 0.055 0.081935 -0.0759391 0.0561 0.081935 -0.0919232 0.0539 0.081935 -0.0897232 0.05163 0.081935 -0.0905651 0.0517974 0.081935 -0.0759391 0.05163 0.083735 -0.0897232 0.05163 0.083735 -0.0905651 0.0517974 0.083735 -0.0912788 0.0522743 0.083735 -0.0916285 0.055 0.083735 -0.0759391 0.0561 0.083735 -0.0897232 0.0561 0.081935 -0.0908232 0.0558052 0.081935 -0.0897232 0.0561 0.083735 -0.0908232 0.0558052 0.083735 -0.0917557 0.0529881 0.083735 -0.0917557 0.0529881 0.081935 -0.0919232 0.05383 0.081935 -0.0919232 0.0539 0.083735 -0.0919232 0.05383 0.083735 -0.0759391 0.05163 0.081935 -0.0030232 0.0462547 0.081935 -0.00221794 0.04706 0.081935 -0.0019232 0.04816 0.081935 -0.0041232 0.04596 0.081935 -0.0637996 0.04596 0.081935 -0.0019232 0.04823 0.081935 -0.0041232 0.05043 0.081935 -0.0637996 0.04596 0.083735 -0.0637996 0.05043 0.083735 -0.0032813 0.0502625 0.083735 -0.00256757 0.0497856 0.083735 -0.00221794 0.04706 0.083735 -0.0030232 0.0462547 0.083735 -0.0019232 0.04823 0.083735 -0.00209067 0.0490719 0.083735 -0.0032813 0.0502625 0.081935 -0.00256757 0.0497856 0.081935 -0.00209067 0.0490719 0.081935 -0.0019232 0.04816 0.083735 -0.0041232 0.04596 0.083735 -0.0041232 0.05043 0.083735 -0.0637996 0.05043 0.081935 -0.0030232 0.0405847 0.081935 -0.0019232 0.04249 0.081935 -0.0707996 0.04029 0.081935 -0.0019232 0.04256 0.081935 -0.00256757 0.0441156 0.081935 -0.00221794 0.04139 0.083735 -0.0041232 0.04476 0.083735 -0.0711423 0.04476 0.083735 -0.0707996 0.0423 0.081935 -0.0707996 0.0423 0.083735 -0.0041232 0.04029 0.083735 -0.00221794 0.04139 0.081935 -0.0030232 0.0405847 0.083735 -0.0032813 0.0445925 0.083735 -0.0032813 0.0445925 0.081935 -0.00256757 0.0441156 0.083735 -0.00209067 0.0434019 0.083735 -0.00209067 0.0434019 0.081935 -0.0019232 0.04249 0.083735 -0.0019232 0.04256 0.083735 -0.0707996 0.04029 0.083735 -0.0041232 0.04029 0.081935 -0.0041232 0.04476 0.081935 -0.0711423 0.04476 0.081935 -0.0019232 0.03689 0.081935 -0.00209067 0.0377319 0.081935 -0.0030232 0.0349147 0.081935 -0.0041232 0.03462 0.081935 -0.0041232 0.03909 0.081935 -0.0030232 0.0349147 0.083735 -0.0019232 0.03682 0.083735 -0.0032813 0.0389225 0.083735 -0.0041232 0.03462 0.083735 -0.0707996 0.03909 0.083735 -0.0707996 0.03462 0.083735 -0.0707996 0.03462 0.081935 -0.00221794 0.03572 0.081935 -0.00221794 0.03572 0.083735 -0.0032813 0.0389225 0.081935 -0.00256757 0.0384456 0.083735 -0.00256757 0.0384456 0.081935 -0.00209067 0.0377319 0.083735 -0.0019232 0.03689 0.083735 -0.0019232 0.03682 0.081935 -0.0707996 0.03909 0.081935 -0.0041232 0.03909 0.083735 -0.0707996 0.03342 0.081935 -0.0707996 0.02895 0.081935 -0.00221794 0.03005 0.081935 -0.00256757 0.0327756 0.081935 -0.0041232 0.03342 0.081935 -0.0019232 0.03122 0.081935 -0.0041232 0.02895 0.083735 -0.00256757 0.0327756 0.083735 -0.0707996 0.03342 0.083735 -0.0707996 0.02895 0.083735 -0.0041232 0.02895 0.081935 -0.0030232 0.0292447 0.081935 -0.0030232 0.0292447 0.083735 -0.00221794 0.03005 0.083735 -0.0019232 0.03115 0.081935 -0.0019232 0.03115 0.083735 -0.0041232 0.03342 0.083735 -0.0032813 0.0332525 0.083735 -0.0032813 0.0332525 0.081935 -0.00209067 0.0320619 0.083735 -0.0019232 0.03122 0.083735 -0.00209067 0.0320619 0.081935 -0.0041232 0.02775 0.081935 -0.0030232 0.0235747 0.081935 -0.00221794 0.02438 0.081935 -0.0041232 0.02328 0.081935 -0.00209067 0.0263919 0.081935 -0.0019232 0.02555 0.081935 -0.00256757 0.0271056 0.083735 -0.00209067 0.0263919 0.083735 -0.0019232 0.02555 0.083735 -0.0041232 0.02775 0.083735 -0.0030232 0.0235747 0.083735 -0.0019232 0.02548 0.083735 -0.0707996 0.02775 0.083735 -0.0707996 0.02328 0.083735 -0.0707996 0.02775 0.081935 -0.0707996 0.02328 0.081935 -0.00221794 0.02438 0.083735 -0.0032813 0.0275825 0.083735 -0.0032813 0.0275825 0.081935 -0.00256757 0.0271056 0.081935 -0.0019232 0.02548 0.081935 -0.0041232 0.02328 0.083735 -0.00256757 0.0214356 0.081935 -0.0041232 0.01761 0.081935 -0.0019232 0.01988 0.081935 -0.0041232 0.02208 0.081935 -0.0019232 0.01988 0.083735 -0.0032813 0.0219125 0.083735 -0.0041232 0.02208 0.083735 -0.0030232 0.0179047 0.083735 -0.0707996 0.02208 0.083735 -0.0707996 0.01761 0.083735 -0.0030232 0.0179047 0.081935 -0.00221794 0.01871 0.081935 -0.00221794 0.01871 0.083735 -0.0032813 0.0219125 0.081935 -0.00256757 0.0214356 0.083735 -0.00209067 0.0207219 0.083735 -0.00209067 0.0207219 0.081935 -0.0019232 0.01981 0.081935 -0.0019232 0.01981 0.083735 -0.0707996 0.01761 0.081935 -0.0041232 0.01761 0.083735 -0.0707996 0.02208 0.081935 -0.0707996 0.01641 0.081935 -0.00221794 0.01304 0.081935 -0.00256757 0.0157656 0.081935 -0.00209067 0.0150519 0.081935 -0.0019232 0.01421 0.081935 -0.0019232 0.01421 0.083735 -0.0041232 0.01194 0.083735 -0.0707996 0.01194 0.083735 -0.0707996 0.01641 0.083735 -0.0041232 0.01641 0.083735 -0.0707996 0.01194 0.081935 -0.0041232 0.01194 0.081935 -0.0030232 0.0122347 0.081935 -0.0030232 0.0122347 0.083735 -0.0019232 0.01414 0.081935 -0.00221794 0.01304 0.083735 -0.0019232 0.01414 0.083735 -0.0041232 0.01641 0.081935 -0.0032813 0.0162425 0.083735 -0.0032813 0.0162425 0.081935 -0.00256757 0.0157656 0.083735 -0.00209067 0.0150519 0.083735 -0.0707996 0.01074 0.081935 -0.0707996 0.00626996 0.081935 -0.00256757 0.0100956 0.081935 -0.0041232 0.01074 0.081935 -0.0019232 0.00853996 0.081935 -0.0707996 0.01074 0.083735 -0.0030232 0.0065647 0.083735 -0.00209067 0.00938186 0.083735 -0.00256757 0.0100956 0.083735 -0.0707996 0.00626996 0.083735 -0.0041232 0.00626996 0.081935 -0.0030232 0.0065647 0.081935 -0.00221794 0.00736996 0.083735 -0.00221794 0.00736996 0.081935 -0.0019232 0.00846996 0.081935 -0.0041232 0.01074 0.083735 -0.0032813 0.0105725 0.083735 -0.0032813 0.0105725 0.081935 -0.00209067 0.00938186 0.081935 -0.0019232 0.00846996 0.083735 -0.0019232 0.00853996 0.083735 -0.0041232 0.00626996 0.083735 -0.0637996 0.000599958 0.081935 -0.0041232 0.00506996 0.081935 -0.00221794 0.00169996 0.081935 -0.0019232 0.00279996 0.081935 -0.00209067 0.00371186 0.081935 -0.0041232 0.000599958 0.081935 -0.0019232 0.00286996 0.083735 -0.00256757 0.00442559 0.083735 -0.00209067 0.00371186 0.083735 -0.00221794 0.00169996 0.083735 -0.0030232 0.000894702 0.083735 -0.0637996 0.00506996 0.083735 -0.0030232 0.000894702 0.081935 -0.0041232 0.000599958 0.083735 -0.0019232 0.00279996 0.083735 -0.0041232 0.00506996 0.083735 -0.0032813 0.00490249 0.083735 -0.0032813 0.00490249 0.081935 -0.00256757 0.00442559 0.081935 -0.0019232 0.00286996 0.081935 -0.0637996 0.000599958 0.083735 -0.0637996 0.00506996 0.081935 -0.0041232 -0.01074 0.081935 -0.0019232 -0.00847004 0.081935 -0.0707996 -0.01074 0.081935 -0.0041232 -0.00627004 0.081935 -0.00256757 -0.00691441 0.081935 -0.00209067 -0.00762814 0.083735 -0.0032813 -0.00643751 0.083735 -0.0041232 -0.00627004 0.083735 -0.0019232 -0.00847004 0.083735 -0.00221794 -0.00964004 0.083735 -0.0019232 -0.00854004 0.083735 -0.0030232 -0.0104453 0.083735 -0.0041232 -0.01074 0.083735 -0.0707996 -0.01074 0.083735 -0.0707996 -0.00627004 0.083735 -0.0030232 -0.0104453 0.081935 -0.00221794 -0.00964004 0.081935 -0.0019232 -0.00854004 0.081935 -0.00256757 -0.00691441 0.083735 -0.0032813 -0.00643751 0.081935 -0.00209067 -0.00762814 0.081935 -0.0707996 -0.00627004 0.081935 -0.0707996 -0.01641 0.081935 -0.0030232 -0.0161153 0.081935 -0.0041232 -0.01194 0.081935 -0.0032813 -0.0121075 0.083735 -0.0019232 -0.01414 0.083735 -0.0041232 -0.01194 0.083735 -0.0030232 -0.0161153 0.083735 -0.0707996 -0.01641 0.083735 -0.0707996 -0.01194 0.083735 -0.0707996 -0.01194 0.081935 -0.00221794 -0.01531 0.081935 -0.0019232 -0.01421 0.081935 -0.00221794 -0.01531 0.083735 -0.0019232 -0.01421 0.083735 -0.0032813 -0.0121075 0.081935 -0.00256757 -0.0125844 0.083735 -0.00256757 -0.0125844 0.081935 -0.00209067 -0.0132981 0.083735 -0.00209067 -0.0132981 0.081935 -0.0019232 -0.01414 0.081935 -0.0041232 -0.01641 0.081935 -0.0041232 -0.01641 0.083735 -0.0707996 -0.02208 0.081935 -0.0041232 -0.01761 0.081935 -0.00221794 -0.02098 0.081935 -0.0041232 -0.02208 0.081935 -0.00209067 -0.0189681 0.081935 -0.0032813 -0.0177775 0.083735 -0.00209067 -0.0189681 0.083735 -0.0707996 -0.02208 0.083735 -0.0019232 -0.01981 0.083735 -0.0707996 -0.01761 0.083735 -0.0707996 -0.01761 0.081935 -0.0030232 -0.0217853 0.081935 -0.0041232 -0.02208 0.083735 -0.0030232 -0.0217853 0.083735 -0.00221794 -0.02098 0.083735 -0.0019232 -0.01988 0.083735 -0.0041232 -0.01761 0.083735 -0.0032813 -0.0177775 0.081935 -0.00256757 -0.0182544 0.083735 -0.00256757 -0.0182544 0.081935 -0.0019232 -0.01981 0.081935 -0.0019232 -0.01988 0.081935 -0.0030232 -0.0274553 0.081935 -0.0032813 -0.0234475 0.081935 -0.0041232 -0.02328 0.081935 -0.0041232 -0.02775 0.081935 -0.00209067 -0.0246381 0.081935 -0.00221794 -0.02665 0.083735 -0.0030232 -0.0274553 0.083735 -0.00256757 -0.0239244 0.083735 -0.0032813 -0.0234475 0.083735 -0.00209067 -0.0246381 0.083735 -0.0019232 -0.02548 0.083735 -0.0041232 -0.02328 0.083735 -0.0019232 -0.02555 0.083735 -0.0707996 -0.02775 0.081935 -0.0041232 -0.02775 0.083735 -0.00221794 -0.02665 0.081935 -0.0019232 -0.02555 0.081935 -0.00256757 -0.0239244 0.081935 -0.0019232 -0.02548 0.081935 -0.0707996 -0.02775 0.083735 -0.0707996 -0.02328 0.081935 -0.0707996 -0.02328 0.083735 -0.0041232 -0.02895 0.081935 -0.00221794 -0.03232 0.081935 -0.0041232 -0.03342 0.081935 -0.0019232 -0.03122 0.081935 -0.0707996 -0.03342 0.083735 -0.0030232 -0.0331253 0.083735 -0.0019232 -0.03122 0.083735 -0.00209067 -0.0303081 0.083735 -0.0032813 -0.0291175 0.083735 -0.0041232 -0.02895 0.083735 -0.0041232 -0.03342 0.083735 -0.0707996 -0.02895 0.083735 -0.0707996 -0.03342 0.081935 -0.0030232 -0.0331253 0.081935 -0.00221794 -0.03232 0.083735 -0.0032813 -0.0291175 0.081935 -0.00256757 -0.0295944 0.083735 -0.00256757 -0.0295944 0.081935 -0.00209067 -0.0303081 0.081935 -0.0019232 -0.03115 0.083735 -0.0019232 -0.03115 0.081935 -0.0707996 -0.02895 0.081935 -0.0707996 -0.03462 0.081935 -0.0041232 -0.03909 0.081935 -0.0030232 -0.0387953 0.081935 -0.00221794 -0.03572 0.081935 -0.0030232 -0.0349148 0.081935 -0.00221794 -0.03799 0.081935 -0.0019232 -0.03689 0.083735 -0.00221794 -0.03572 0.083735 -0.0041232 -0.03462 0.083735 -0.00221794 -0.03799 0.083735 -0.0707996 -0.03909 0.083735 -0.0041232 -0.03909 0.083735 -0.0030232 -0.0387953 0.083735 -0.0041232 -0.03462 0.081935 -0.0030232 -0.0349148 0.083735 -0.0019232 -0.03682 0.083735 -0.0019232 -0.03682 0.081935 -0.0019232 -0.03689 0.081935 -0.0707996 -0.03909 0.081935 -0.0707996 -0.03462 0.083735 -0.0707996 -0.0423 0.081935 -0.0711423 -0.04476 0.081935 -0.0041232 -0.04476 0.081935 -0.00221794 -0.04366 0.081935 -0.00221794 -0.04139 0.081935 -0.0019232 -0.04249 0.081935 -0.0041232 -0.04029 0.081935 -0.0041232 -0.04029 0.083735 -0.0030232 -0.0444653 0.083735 -0.0041232 -0.04476 0.083735 -0.0707996 -0.04029 0.083735 -0.0019232 -0.04249 0.083735 -0.00221794 -0.04139 0.083735 -0.0707996 -0.0423 0.083735 -0.0030232 -0.0444653 0.081935 -0.00221794 -0.04366 0.083735 -0.0019232 -0.04256 0.081935 -0.0019232 -0.04256 0.083735 -0.0030232 -0.0405848 0.083735 -0.0030232 -0.0405848 0.081935 -0.0711423 -0.04476 0.083735 -0.0707996 -0.04029 0.081935 -0.0030232 -0.0501353 0.081935 -0.0030232 -0.0462548 0.083735 -0.00221794 -0.04706 0.083735 -0.0637996 -0.04596 0.083735 -0.00221794 -0.04933 0.083735 -0.0637996 -0.05043 0.081935 -0.0041232 -0.05043 0.083735 -0.0030232 -0.0501353 0.083735 -0.00221794 -0.04933 0.081935 -0.0019232 -0.04823 0.081935 -0.0019232 -0.04823 0.083735 -0.0041232 -0.04596 0.083735 -0.0030232 -0.0462548 0.081935 -0.00221794 -0.04706 0.081935 -0.0019232 -0.04816 0.081935 -0.0019232 -0.04816 0.083735 -0.0041232 -0.05043 0.081935 -0.0637996 -0.05043 0.083735 -0.0041232 -0.04596 0.081935 -0.0637996 -0.04596 0.081935 -0.0637996 -0.05163 0.081935 -0.0637996 -0.0561 0.081935 -0.0030232 -0.0519248 0.081935 -0.0019232 -0.0539 0.083735 -0.0041232 -0.05163 0.083735 -0.0637996 -0.05163 0.083735 -0.0030232 -0.0558053 0.083735 -0.00221794 -0.055 0.083735 -0.0637996 -0.0561 0.083735 -0.0041232 -0.0561 0.081935 -0.0030232 -0.0558053 0.081935 -0.00221794 -0.055 0.081935 -0.0019232 -0.0539 0.081935 -0.0030232 -0.0519248 0.083735 -0.00221794 -0.05273 0.083735 -0.00221794 -0.05273 0.081935 -0.0019232 -0.05383 0.083735 -0.0019232 -0.05383 0.081935 -0.0041232 -0.0561 0.083735 -0.0041232 -0.05163 0.081935 -0.0919232 -0.0539 0.081935 -0.0919232 -0.05383 0.081935 -0.0759391 -0.0561 0.081935 -0.0759391 -0.05163 0.081935 -0.0897232 -0.05163 0.081935 -0.0908232 -0.0558053 0.083735 -0.0916285 -0.05273 0.083735 -0.0919232 -0.0539 0.083735 -0.0919232 -0.05383 0.083735 -0.0897232 -0.05163 0.083735 -0.0908232 -0.0519248 0.081935 -0.0916285 -0.05273 0.081935 -0.0908232 -0.0519248 0.083735 -0.0897232 -0.0561 0.081935 -0.0908232 -0.0558053 0.081935 -0.0916285 -0.055 0.081935 -0.0916285 -0.055 0.083735 -0.0759391 -0.0561 0.083735 -0.0897232 -0.0561 0.083735 -0.0759391 -0.05163 0.083735 0.0884768 -0.0558053 0.081935 0.0892821 -0.055 0.081935 0.000676799 -0.0519248 0.081935 -0.000128457 -0.05273 0.081935 -0.000423201 -0.0539 0.081935 -0.000255736 -0.0547419 0.081935 0.0895768 -0.05383 0.081935 0.0873768 -0.05163 0.081935 0.0017768 -0.0561 0.081935 0.000934896 -0.0559326 0.081935 0.000221164 -0.0554557 0.081935 0.0873768 -0.0561 0.083735 0.0895768 -0.05383 0.083735 0.0894093 -0.0529881 0.083735 -0.000423201 -0.05383 0.083735 0.0873768 -0.05163 0.083735 0.0017768 -0.05163 0.081935 0.0017768 -0.05163 0.083735 0.000676799 -0.0519248 0.083735 -0.000128457 -0.05273 0.083735 -0.000423201 -0.05383 0.081935 0.000934896 -0.0559326 0.083735 0.000221164 -0.0554557 0.083735 -0.000255736 -0.0547419 0.083735 -0.000423201 -0.0539 0.083735 0.0873768 -0.0561 0.081935 0.0884768 -0.0558053 0.083735 0.0892821 -0.055 0.083735 0.0895768 -0.0539 0.081935 0.0882187 -0.0517975 0.083735 0.0882187 -0.0517975 0.081935 0.0889324 -0.0522744 0.081935 0.0889324 -0.0522744 0.083735 0.0894093 -0.0529881 0.081935 0.0895768 -0.0539 0.083735 0.0017768 -0.0561 0.083735 0.0884768 -0.0501353 0.081935 -0.000255736 -0.0490719 0.081935 0.000676799 -0.0462548 0.081935 -0.000128457 -0.04706 0.081935 0.0894093 -0.0473181 0.081935 0.0873768 -0.04596 0.081935 0.0017768 -0.05043 0.081935 -0.000423201 -0.04823 0.081935 0.0895768 -0.04823 0.083735 0.0017768 -0.05043 0.083735 0.000676799 -0.0462548 0.083735 0.0017768 -0.04596 0.083735 -0.000423201 -0.04823 0.083735 0.0017768 -0.04596 0.081935 -0.000128457 -0.04706 0.083735 -0.000423201 -0.04816 0.083735 0.000934896 -0.0502626 0.083735 0.000934896 -0.0502626 0.081935 0.000221164 -0.0497857 0.083735 -0.000255736 -0.0490719 0.083735 0.000221164 -0.0497857 0.081935 -0.000423201 -0.04816 0.081935 0.0884768 -0.0501353 0.083735 0.0892821 -0.04933 0.081935 0.0892821 -0.04933 0.083735 0.0873768 -0.04596 0.083735 0.0882187 -0.0461275 0.083735 0.0882187 -0.0461275 0.081935 0.0889324 -0.0466044 0.083735 0.0894093 -0.0473181 0.083735 0.0889324 -0.0466044 0.081935 0.0895768 -0.04816 0.081935 0.0895768 -0.04823 0.081935 0.0895768 -0.04816 0.083735 0.0873768 -0.05043 0.081935 0.0873768 -0.05043 0.083735 0.0873768 -0.04476 0.081935 0.0895768 -0.04256 0.081935 0.0017768 -0.04476 0.081935 0.0895768 -0.04249 0.081935 -0.000128457 -0.04139 0.081935 0.0873768 -0.04029 0.081935 -0.000423201 -0.04256 0.081935 0.000221164 -0.0441157 0.081935 0.0889324 -0.0409344 0.081935 0.0892821 -0.04366 0.083735 0.0895768 -0.04249 0.083735 0.000676799 -0.0405848 0.083735 0.000934896 -0.0445926 0.083735 -0.000255736 -0.0434019 0.083735 0.0873768 -0.04476 0.083735 0.0017768 -0.04476 0.083735 0.0873768 -0.04029 0.083735 0.0017768 -0.04029 0.083735 0.000676799 -0.0405848 0.081935 -0.000128457 -0.04139 0.083735 -0.000423201 -0.04249 0.083735 0.000221164 -0.0441157 0.083735 0.000934896 -0.0445926 0.081935 -0.000255736 -0.0434019 0.081935 -0.000423201 -0.04256 0.083735 -0.000423201 -0.04249 0.081935 0.0884768 -0.0444653 0.081935 0.0884768 -0.0444653 0.083735 0.0892821 -0.04366 0.081935 0.0882187 -0.0404575 0.083735 0.0889324 -0.0409344 0.083735 0.0882187 -0.0404575 0.081935 0.0894093 -0.0416481 0.083735 0.0894093 -0.0416481 0.081935 0.0895768 -0.04256 0.083735 0.0017768 -0.04029 0.081935 0.0895768 -0.03689 0.081935 0.0873768 -0.03909 0.081935 -0.000128457 -0.03572 0.081935 0.000221164 -0.0384457 0.081935 0.000934896 -0.0389226 0.081935 -0.000423201 -0.03689 0.081935 0.0873768 -0.03462 0.081935 0.0895768 -0.03682 0.081935 0.0895768 -0.03689 0.083735 0.0873768 -0.03909 0.083735 0.0895768 -0.03682 0.083735 -0.000423201 -0.03689 0.083735 -0.000128457 -0.03572 0.083735 0.0889324 -0.0352644 0.083735 0.0882187 -0.0347875 0.083735 0.0017768 -0.03462 0.081935 0.000676799 -0.0349148 0.081935 0.000676799 -0.0349148 0.083735 -0.000423201 -0.03682 0.083735 0.0017768 -0.03909 0.081935 0.000934896 -0.0389226 0.083735 0.000221164 -0.0384457 0.083735 -0.000255736 -0.0377319 0.083735 -0.000255736 -0.0377319 0.081935 -0.000423201 -0.03682 0.081935 0.0884768 -0.0387953 0.081935 0.0884768 -0.0387953 0.083735 0.0892821 -0.03799 0.081935 0.0892821 -0.03799 0.083735 0.0882187 -0.0347875 0.081935 0.0889324 -0.0352644 0.081935 0.0894093 -0.0359781 0.083735 0.0894093 -0.0359781 0.081935 0.0017768 -0.03909 0.083735 0.0873768 -0.03462 0.083735 0.0017768 -0.03462 0.083735 0.000676799 -0.0292448 0.081935 0.000221164 -0.0327757 0.081935 -0.000255736 -0.0320619 0.081935 0.0017768 -0.03342 0.081935 0.0873768 -0.02895 0.081935 0.0884768 -0.0331253 0.081935 0.0884768 -0.0292448 0.081935 0.0892821 -0.03232 0.081935 0.0884768 -0.0292448 0.083735 -0.000128457 -0.03005 0.083735 -0.000423201 -0.03115 0.083735 0.000676799 -0.0292448 0.083735 -0.000423201 -0.03122 0.083735 0.0892821 -0.03005 0.083735 0.0895768 -0.03115 0.083735 0.0873768 -0.02895 0.083735 0.0873768 -0.03342 0.083735 0.0017768 -0.03342 0.083735 0.0017768 -0.02895 0.083735 -0.000128457 -0.03005 0.081935 -0.000423201 -0.03115 0.081935 0.000934896 -0.0332526 0.083735 0.000221164 -0.0327757 0.083735 0.000934896 -0.0332526 0.081935 -0.000255736 -0.0320619 0.083735 -0.000423201 -0.03122 0.081935 0.0884768 -0.0331253 0.083735 0.0895768 -0.03122 0.081935 0.0892821 -0.03232 0.083735 0.0895768 -0.03122 0.083735 0.0892821 -0.03005 0.081935 0.0895768 -0.03115 0.081935 0.0873768 -0.03342 0.081935 0.0017768 -0.02895 0.081935 0.000221164 -0.0271057 0.081935 -0.000423201 -0.02555 0.081935 0.0873768 -0.02775 0.081935 0.0895768 -0.02555 0.081935 0.000934896 -0.0275826 0.081935 0.0895768 -0.02548 0.081935 0.0873768 -0.02328 0.081935 -0.000423201 -0.02548 0.081935 0.0017768 -0.02328 0.081935 -0.000128457 -0.02438 0.081935 -0.000128457 -0.02438 0.083735 0.0895768 -0.02548 0.083735 0.0873768 -0.02328 0.083735 0.0892821 -0.02665 0.083735 0.0873768 -0.02775 0.083735 0.000934896 -0.0275826 0.083735 0.0017768 -0.02328 0.083735 0.000676799 -0.0235748 0.081935 0.000676799 -0.0235748 0.083735 0.000221164 -0.0271057 0.083735 -0.000255736 -0.0263919 0.083735 -0.000255736 -0.0263919 0.081935 -0.000423201 -0.02555 0.083735 -0.000423201 -0.02548 0.083735 0.0884768 -0.0274553 0.081935 0.0884768 -0.0274553 0.083735 0.0892821 -0.02665 0.081935 0.0884768 -0.0235748 0.081935 0.0884768 -0.0235748 0.083735 0.0892821 -0.02438 0.083735 0.0892821 -0.02438 0.081935 0.0895768 -0.02555 0.083735 0.0017768 -0.02775 0.081935 0.0017768 -0.02775 0.083735 0.000676799 -0.0179048 0.081935 -0.000128457 -0.01871 0.081935 0.0873768 -0.02208 0.081935 0.0884768 -0.0179048 0.081935 0.000934896 -0.0219126 0.081935 -0.000255736 -0.0207219 0.081935 -0.000423201 -0.01988 0.081935 0.0895768 -0.01988 0.081935 0.0017768 -0.02208 0.081935 -0.000128457 -0.01871 0.083735 0.000676799 -0.0179048 0.083735 -0.000423201 -0.01981 0.083735 -0.000423201 -0.01988 0.083735 -0.000255736 -0.0207219 0.083735 0.0892821 -0.01871 0.083735 0.0873768 -0.01761 0.083735 0.0895768 -0.01988 0.083735 0.0873768 -0.02208 0.083735 0.0017768 -0.01761 0.083735 -0.000423201 -0.01981 0.081935 0.0017768 -0.02208 0.083735 0.000934896 -0.0219126 0.083735 0.000221164 -0.0214357 0.083735 0.000221164 -0.0214357 0.081935 0.0884768 -0.0217853 0.081935 0.0884768 -0.0217853 0.083735 0.0892821 -0.02098 0.081935 0.0892821 -0.02098 0.083735 0.0884768 -0.0179048 0.083735 0.0895768 -0.01981 0.083735 0.0892821 -0.01871 0.081935 0.0895768 -0.01981 0.081935 0.0873768 -0.01761 0.081935 0.0017768 -0.01761 0.081935 -0.000128457 -0.01304 0.081935 0.0017768 -0.01641 0.081935 0.000221164 -0.0157657 0.081935 -0.000255736 -0.0150519 0.081935 0.0884768 -0.0161153 0.081935 0.0895768 -0.01414 0.081935 0.0017768 -0.01194 0.083735 0.000934896 -0.0162426 0.083735 0.000676799 -0.0122348 0.083735 -0.000423201 -0.01421 0.083735 0.000221164 -0.0157657 0.083735 0.0884768 -0.0122348 0.083735 0.000676799 -0.0122348 0.081935 -0.000128457 -0.01304 0.083735 -0.000423201 -0.01414 0.081935 0.000934896 -0.0162426 0.081935 -0.000255736 -0.0150519 0.083735 -0.000423201 -0.01421 0.081935 -0.000423201 -0.01414 0.083735 0.0873768 -0.01641 0.083735 0.0884768 -0.0161153 0.083735 0.0892821 -0.01531 0.081935 0.0892821 -0.01531 0.083735 0.0873768 -0.01194 0.081935 0.0884768 -0.0122348 0.081935 0.0892821 -0.01304 0.083735 0.0895768 -0.01414 0.083735 0.0892821 -0.01304 0.081935 0.0895768 -0.01421 0.081935 0.0895768 -0.01421 0.083735 0.0873768 -0.01641 0.081935 0.0017768 -0.01641 0.083735 0.0017768 -0.01194 0.081935 0.0873768 -0.01194 0.083735 0.0017768 -0.00627004 0.081935 -0.000423201 -0.00854004 0.081935 0.000221164 -0.0100957 0.081935 -0.000255736 -0.00938195 0.081935 0.0895768 -0.00854004 0.081935 0.0873768 -0.00627004 0.083735 -0.000423201 -0.00847004 0.083735 0.0017768 -0.00627004 0.083735 0.0884768 -0.00656479 0.083735 0.0873768 -0.01074 0.083735 0.000221164 -0.0100957 0.083735 -0.000255736 -0.00938195 0.083735 0.0884768 -0.0104453 0.081935 0.0884768 -0.0104453 0.083735 0.0892821 -0.00964004 0.081935 0.0892821 -0.00964004 0.083735 0.0873768 -0.00627004 0.081935 0.0884768 -0.00656479 0.081935 0.0892821 -0.00737004 0.083735 0.0892821 -0.00737004 0.081935 0.0895768 -0.00847004 0.083735 0.0895768 -0.00854004 0.083735 0.0895768 -0.00847004 0.081935 0.000676799 -0.00656479 0.081935 0.000676799 -0.00656479 0.083735 -0.000128457 -0.00737004 0.081935 -0.000128457 -0.00737004 0.083735 0.0017768 -0.01074 0.083735 0.0017768 -0.01074 0.081935 0.000934896 -0.0105726 0.083735 0.000934896 -0.0105726 0.081935 -0.000423201 -0.00854004 0.083735 -0.000423201 -0.00847004 0.081935 0.0873768 -0.01074 0.081935 -0.000128457 0.00396996 0.081935 0.0892821 0.00396996 0.081935 0.0884768 0.00477521 0.081935 0.0017768 0.000599958 0.081935 0.0017768 0.00506996 0.081935 -0.000255736 0.00195805 0.081935 0.0892821 0.00169996 0.081935 0.0895768 0.00279996 0.081935 0.0873768 0.00506996 0.081935 0.0017768 0.000599958 0.083735 0.000676799 0.00477521 0.083735 -0.000423201 0.00286996 0.083735 0.0017768 0.00506996 0.083735 -0.000423201 0.00279996 0.083735 0.0895768 0.00279996 0.083735 0.0873768 0.00506996 0.083735 0.0895768 0.00286996 0.083735 0.000221164 0.00124432 0.083735 0.000676799 0.00477521 0.081935 -0.000423201 0.00286996 0.081935 -0.000128457 0.00396996 0.083735 0.000934896 0.000767423 0.081935 0.000934896 0.000767423 0.083735 0.000221164 0.00124432 0.081935 -0.000255736 0.00195805 0.083735 -0.000423201 0.00279996 0.081935 0.0873768 0.000599958 0.083735 0.0884768 0.000894702 0.081935 0.0884768 0.000894702 0.083735 0.0892821 0.00169996 0.083735 0.0884768 0.00477521 0.083735 0.0892821 0.00396996 0.083735 0.0895768 0.00286996 0.081935 0.0873768 0.000599958 0.081935 0.0017768 0.01074 0.081935 0.000676799 0.0104452 0.081935 -0.000423201 0.00853996 0.081935 0.000221164 0.00691432 0.081935 0.0873768 0.00626996 0.081935 0.0873768 0.01074 0.081935 0.0884768 0.0065647 0.081935 0.0895768 0.00846996 0.081935 0.0873768 0.00626996 0.083735 -0.000255736 0.00762805 0.083735 0.0884768 0.0104452 0.083735 0.0895768 0.00846996 0.083735 0.000221164 0.00691432 0.083735 0.0017768 0.01074 0.083735 -0.000128457 0.00963996 0.081935 0.000676799 0.0104452 0.083735 -0.000128457 0.00963996 0.083735 0.0017768 0.00626996 0.083735 0.000934896 0.00643742 0.083735 0.000934896 0.00643742 0.081935 -0.000255736 0.00762805 0.081935 -0.000423201 0.00846996 0.081935 -0.000423201 0.00853996 0.083735 -0.000423201 0.00846996 0.083735 0.0884768 0.0065647 0.083735 0.0892821 0.00736996 0.081935 0.0892821 0.00736996 0.083735 0.0873768 0.01074 0.083735 0.0884768 0.0104452 0.081935 0.0892821 0.00963996 0.083735 0.0895768 0.00853996 0.083735 0.0892821 0.00963996 0.081935 0.0895768 0.00853996 0.081935 0.0017768 0.00626996 0.081935 0.0017768 0.01194 0.081935 -0.000255736 0.0132981 0.081935 0.0884768 0.0161152 0.081935 0.0895768 0.01421 0.081935 0.0873768 0.01641 0.083735 0.0873768 0.01194 0.083735 -0.000423201 0.01421 0.083735 0.0017768 0.01641 0.083735 0.0895768 0.01421 0.083735 0.0895768 0.01414 0.083735 -0.000255736 0.0132981 0.083735 0.000676799 0.0161152 0.081935 0.000676799 0.0161152 0.083735 -0.000128457 0.01531 0.081935 -0.000128457 0.01531 0.083735 -0.000423201 0.01421 0.081935 0.000934896 0.0121074 0.081935 0.000934896 0.0121074 0.083735 0.000221164 0.0125843 0.083735 0.000221164 0.0125843 0.081935 -0.000423201 0.01414 0.083735 -0.000423201 0.01414 0.081935 0.0884768 0.0122347 0.081935 0.0892821 0.01304 0.081935 0.0884768 0.0122347 0.083735 0.0892821 0.01304 0.083735 0.0884768 0.0161152 0.083735 0.0873768 0.01641 0.081935 0.0892821 0.01531 0.081935 0.0892821 0.01531 0.083735 0.0895768 0.01414 0.081935 0.0017768 0.01194 0.083735 0.0873768 0.01194 0.081935 0.0017768 0.01641 0.081935 0.000676799 0.0217852 0.081935 -0.000128457 0.02098 0.081935 -0.000423201 0.01988 0.081935 0.0895768 0.01981 0.081935 0.000221164 0.0182543 0.081935 0.0884768 0.0217852 0.081935 0.0895768 0.01988 0.081935 0.0873768 0.02208 0.083735 0.0884768 0.0217852 0.083735 0.0892821 0.02098 0.083735 0.000676799 0.0217852 0.083735 -0.000423201 0.01981 0.083735 0.0895768 0.01988 0.083735 0.000934896 0.0177774 0.083735 -0.000255736 0.0189681 0.083735 0.0017768 0.01761 0.083735 0.0017768 0.02208 0.083735 0.0873768 0.01761 0.083735 -0.000128457 0.02098 0.083735 -0.000423201 0.01988 0.083735 0.000934896 0.0177774 0.081935 0.000221164 0.0182543 0.083735 -0.000255736 0.0189681 0.081935 -0.000423201 0.01981 0.081935 0.0873768 0.01761 0.081935 0.0884768 0.0179047 0.081935 0.0884768 0.0179047 0.083735 0.0892821 0.01871 0.081935 0.0892821 0.01871 0.083735 0.0873768 0.02208 0.081935 0.0892821 0.02098 0.081935 0.0895768 0.01981 0.083735 0.0017768 0.01761 0.081935 0.0017768 0.02208 0.081935 -0.000423201 0.02548 0.081935 0.000221164 0.0239243 0.081935 -0.000255736 0.0246381 0.081935 0.0884768 0.0235747 0.081935 0.0873768 0.02328 0.081935 0.0892821 0.02665 0.081935 0.0884768 0.0274552 0.081935 0.0895768 0.02548 0.081935 0.0884768 0.0235747 0.083735 0.000934896 0.0234474 0.083735 0.000221164 0.0239243 0.083735 0.0017768 0.02775 0.083735 -0.000423201 0.02555 0.083735 0.0892821 0.02665 0.083735 0.0873768 0.02775 0.083735 0.0895768 0.02548 0.083735 0.0873768 0.02328 0.083735 0.0017768 0.02328 0.083735 0.000676799 0.0274552 0.081935 -0.000128457 0.02665 0.081935 0.000676799 0.0274552 0.083735 -0.000128457 0.02665 0.083735 -0.000423201 0.02555 0.081935 0.0017768 0.02328 0.081935 0.000934896 0.0234474 0.081935 -0.000255736 0.0246381 0.083735 -0.000423201 0.02548 0.083735 0.0892821 0.02438 0.081935 0.0892821 0.02438 0.083735 0.0873768 0.02775 0.081935 0.0884768 0.0274552 0.083735 0.0895768 0.02555 0.081935 0.0895768 0.02555 0.083735 0.0017768 0.02775 0.081935 0.000676799 0.0331252 0.081935 -0.000128457 0.03232 0.081935 0.000934896 0.0291174 0.081935 0.000221164 0.0295943 0.081935 -0.000255736 0.0303081 0.081935 0.0895768 0.03115 0.081935 0.0017768 0.03342 0.081935 -0.000128457 0.03232 0.083735 -0.000423201 0.03122 0.083735 0.000676799 0.0331252 0.083735 0.0017768 0.03342 0.083735 0.0892821 0.03232 0.083735 0.0895768 0.03122 0.083735 0.0884768 0.0292447 0.083735 -0.000423201 0.03122 0.081935 0.0017768 0.02895 0.081935 0.000934896 0.0291174 0.083735 0.000221164 0.0295943 0.083735 -0.000255736 0.0303081 0.083735 -0.000423201 0.03115 0.083735 -0.000423201 0.03115 0.081935 0.0884768 0.0292447 0.081935 0.0892821 0.03005 0.081935 0.0892821 0.03005 0.083735 0.0884768 0.0331252 0.083735 0.0873768 0.03342 0.081935 0.0884768 0.0331252 0.081935 0.0892821 0.03232 0.081935 0.0895768 0.03122 0.081935 0.0895768 0.03115 0.083735 0.0873768 0.02895 0.081935 0.0017768 0.02895 0.083735 0.0873768 0.02895 0.083735 0.0873768 0.03342 0.083735 0.0017768 0.03909 0.081935 0.000221164 0.0352643 0.081935 -0.000255736 0.0359781 0.081935 0.0895768 0.03682 0.081935 0.0895768 0.03689 0.081935 0.0884768 0.0387952 0.081935 0.0873768 0.03909 0.081935 0.0017768 0.03462 0.081935 -0.000423201 0.03682 0.083735 -0.000423201 0.03689 0.083735 0.0017768 0.03909 0.083735 0.0873768 0.03909 0.083735 0.0895768 0.03682 0.083735 0.000934896 0.0347874 0.083735 0.0017768 0.03462 0.083735 0.0884768 0.0349147 0.083735 0.000676799 0.0387952 0.081935 -0.000128457 0.03799 0.081935 0.000676799 0.0387952 0.083735 -0.000423201 0.03689 0.081935 -0.000128457 0.03799 0.083735 0.000221164 0.0352643 0.083735 0.000934896 0.0347874 0.081935 -0.000255736 0.0359781 0.083735 -0.000423201 0.03682 0.081935 0.0873768 0.03462 0.081935 0.0884768 0.0349147 0.081935 0.0892821 0.03572 0.083735 0.0892821 0.03572 0.081935 0.0884768 0.0387952 0.083735 0.0892821 0.03799 0.083735 0.0895768 0.03689 0.083735 0.0892821 0.03799 0.081935 0.0873768 0.03462 0.083735 0.0017768 0.04476 0.081935 0.000676799 0.0444652 0.081935 -0.000128457 0.04366 0.081935 -0.000423201 0.04249 0.081935 0.0884768 0.0444652 0.081935 0.0895768 0.04249 0.081935 0.0892821 0.04139 0.081935 0.0017768 0.04029 0.083735 0.0873768 0.04029 0.083735 0.0873768 0.04476 0.083735 -0.000423201 0.04256 0.083735 0.0892821 0.04139 0.083735 0.0895768 0.04249 0.083735 0.0895768 0.04256 0.083735 0.000934896 0.0404574 0.083735 0.000676799 0.0444652 0.083735 -0.000128457 0.04366 0.083735 -0.000423201 0.04256 0.081935 0.000934896 0.0404574 0.081935 0.000221164 0.0409343 0.083735 0.000221164 0.0409343 0.081935 -0.000255736 0.0416481 0.083735 -0.000255736 0.0416481 0.081935 -0.000423201 0.04249 0.083735 0.0873768 0.04029 0.081935 0.0884768 0.0405847 0.081935 0.0884768 0.0405847 0.083735 0.0884768 0.0444652 0.083735 0.0873768 0.04476 0.081935 0.0892821 0.04366 0.083735 0.0892821 0.04366 0.081935 0.0895768 0.04256 0.081935 0.0017768 0.04029 0.081935 0.0017768 0.04476 0.083735 0.0017768 0.05043 0.081935 -0.000423201 0.04823 0.081935 -0.000255736 0.0473181 0.081935 -0.000423201 0.04816 0.081935 0.0017768 0.04596 0.081935 0.0873768 0.04596 0.081935 0.0873768 0.05043 0.081935 0.0892821 0.04706 0.081935 0.0884768 0.0501352 0.081935 -0.000255736 0.0473181 0.083735 -0.000423201 0.04816 0.083735 0.0884768 0.0501352 0.083735 0.0892821 0.04933 0.083735 0.0895768 0.04823 0.083735 0.0873768 0.05043 0.083735 0.0895768 0.04816 0.083735 0.0884768 0.0462547 0.083735 0.000676799 0.0501352 0.083735 0.000676799 0.0501352 0.081935 -0.000128457 0.04933 0.081935 -0.000128457 0.04933 0.083735 -0.000423201 0.04823 0.083735 0.0017768 0.04596 0.083735 0.000934896 0.0461274 0.081935 0.000934896 0.0461274 0.083735 0.000221164 0.0466043 0.083735 0.000221164 0.0466043 0.081935 0.0884768 0.0462547 0.081935 0.0892821 0.04706 0.083735 0.0892821 0.04933 0.081935 0.0895768 0.04816 0.081935 0.0895768 0.04823 0.081935 0.0873768 0.04596 0.083735 0.0017768 0.05043 0.083735 -0.000423201 0.0539 0.081935 0.000221164 0.0522743 0.081935 0.0884768 0.0519247 0.081935 0.0884768 0.0558052 0.081935 0.0873768 0.0561 0.081935 0.0895768 0.0539 0.081935 0.0895768 0.05383 0.083735 0.0884768 0.0519247 0.083735 0.0873768 0.0561 0.083735 0.0873768 0.05163 0.083735 0.0017768 0.05163 0.083735 -0.000255736 0.0529881 0.083735 0.0017768 0.0561 0.081935 0.000676799 0.0558052 0.081935 0.000676799 0.0558052 0.083735 -0.000128457 0.055 0.083735 -0.000128457 0.055 0.081935 0.000934896 0.0517974 0.083735 0.000934896 0.0517974 0.081935 0.000221164 0.0522743 0.083735 -0.000423201 0.05383 0.083735 -0.000255736 0.0529881 0.081935 -0.000423201 0.05383 0.081935 -0.000423201 0.0539 0.083735 0.0873768 0.05163 0.081935 0.0892821 0.05273 0.081935 0.0895768 0.05383 0.081935 0.0892821 0.05273 0.083735 0.0884768 0.0558052 0.083735 0.0892821 0.055 0.083735 0.0892821 0.055 0.081935 0.0895768 0.0539 0.083735 0.0017768 0.05163 0.081935 0.0017768 0.0561 0.083735 -0.163215 -0.00108257 0.081935 -0.161965 -0.00108257 0.081935 -0.163672 0.000624958 0.081935 -0.161507 0.000624958 0.081935 -0.161965 0.00108249 0.081935 -0.16259 0.00124996 0.081935 -0.161507 -0.000625042 0.081935 -0.16259 -4.19898e-08 0.081935 -0.16259 -4.19898e-08 0.0846861 -0.163215 -0.00108257 0.083935 -0.163672 0.000624958 0.083935 -0.163672 -0.000625042 0.083935 -0.16384 -4.19898e-08 0.083935 -0.161965 0.00108249 0.083935 -0.16134 -4.19898e-08 0.083935 -0.161507 -0.000625042 0.083935 -0.161507 0.000624958 0.083935 -0.163672 -0.000625042 0.081935 -0.16384 -4.19898e-08 0.081935 -0.163215 0.00108249 0.081935 -0.163215 0.00108249 0.083935 -0.16259 0.00124996 0.083935 -0.16134 -4.19898e-08 0.081935 -0.161965 -0.00108257 0.083935 -0.16259 -0.00125004 0.083935 -0.16259 -0.00125004 0.081935 -0.144315 0.00108249 0.081935 -0.144772 0.000624958 0.081935 -0.14369 -4.19898e-08 0.081935 -0.143065 -0.00108257 0.081935 -0.144315 -0.00108257 0.083935 -0.144772 -0.000625042 0.083935 -0.144772 0.000624958 0.083935 -0.14494 -4.19898e-08 0.083935 -0.14369 0.00124996 0.083935 -0.144315 0.00108249 0.083935 -0.14369 -4.19898e-08 0.0846861 -0.14369 -0.00125004 0.083935 -0.14369 -0.00125004 0.081935 -0.144315 -0.00108257 0.081935 -0.144772 -0.000625042 0.081935 -0.14494 -4.19898e-08 0.081935 -0.14369 0.00124996 0.081935 -0.143065 0.00108249 0.083935 -0.143065 0.00108249 0.081935 -0.142607 0.000624958 0.083935 -0.14244 -4.19898e-08 0.083935 -0.142607 0.000624958 0.081935 -0.14244 -4.19898e-08 0.081935 -0.142607 -0.000625042 0.083935 -0.143065 -0.00108257 0.083935 -0.142607 -0.000625042 0.081935 -0.144772 0.029575 0.081935 -0.14369 0.02895 0.081935 -0.144772 0.030825 0.081935 -0.14369 0.0302 0.081935 -0.143065 0.0312825 0.081935 -0.14369 0.03145 0.081935 -0.144315 0.0312825 0.081935 -0.14369 0.0302 0.0846861 -0.144772 0.030825 0.083935 -0.144772 0.029575 0.083935 -0.143065 0.0312825 0.083935 -0.142607 0.029575 0.083935 -0.142607 0.030825 0.083935 -0.14244 0.0302 0.083935 -0.143065 0.0291174 0.083935 -0.144315 0.0291174 0.083935 -0.144315 0.0291174 0.081935 -0.14494 0.0302 0.083935 -0.14494 0.0302 0.081935 -0.144315 0.0312825 0.083935 -0.14369 0.03145 0.083935 -0.142607 0.030825 0.081935 -0.14244 0.0302 0.081935 -0.142607 0.029575 0.081935 -0.143065 0.0291174 0.081935 -0.14369 0.02895 0.083935 -0.163672 0.029575 0.081935 -0.16259 0.02895 0.081935 -0.163672 0.030825 0.081935 -0.16384 0.0302 0.081935 -0.161507 0.030825 0.081935 -0.16259 0.0302 0.081935 -0.161965 0.0312825 0.081935 -0.161965 0.0291174 0.081935 -0.16134 0.0302 0.081935 -0.163215 0.0291174 0.083935 -0.163215 0.0312825 0.083935 -0.16259 0.0302 0.0846861 -0.161965 0.0291174 0.083935 -0.16134 0.0302 0.083935 -0.161507 0.029575 0.083935 -0.16259 0.02895 0.083935 -0.163672 0.029575 0.083935 -0.163215 0.0291174 0.081935 -0.16384 0.0302 0.083935 -0.163672 0.030825 0.083935 -0.163215 0.0312825 0.081935 -0.16259 0.03145 0.083935 -0.16259 0.03145 0.081935 -0.161965 0.0312825 0.083935 -0.161507 0.030825 0.083935 -0.161507 0.029575 0.081935 -0.144772 -0.030825 0.081935 -0.14369 -0.0302 0.081935 -0.144315 -0.0312826 0.081935 -0.143065 -0.0312826 0.081935 -0.144772 -0.029575 0.081935 -0.14494 -0.0302 0.081935 -0.144315 -0.0291175 0.081935 -0.14494 -0.0302 0.083935 -0.143065 -0.0291175 0.083935 -0.142607 -0.029575 0.083935 -0.14369 -0.0302 0.0846861 -0.14244 -0.0302 0.083935 -0.144315 -0.0312826 0.083935 -0.144772 -0.030825 0.083935 -0.144772 -0.029575 0.083935 -0.144315 -0.0291175 0.083935 -0.14369 -0.02895 0.083935 -0.14369 -0.02895 0.081935 -0.143065 -0.0291175 0.081935 -0.142607 -0.029575 0.081935 -0.14244 -0.0302 0.081935 -0.142607 -0.030825 0.083935 -0.143065 -0.0312826 0.083935 -0.142607 -0.030825 0.081935 -0.14369 -0.03145 0.083935 -0.14369 -0.03145 0.081935 -0.163215 -0.0312826 0.081935 -0.16259 -0.0302 0.081935 -0.16134 -0.0302 0.081935 -0.163672 -0.029575 0.083935 -0.16259 -0.0302 0.0846861 -0.161965 -0.0291175 0.083935 -0.161507 -0.030825 0.083935 -0.161507 -0.029575 0.083935 -0.16259 -0.03145 0.081935 -0.163215 -0.0312826 0.083935 -0.163672 -0.030825 0.083935 -0.163672 -0.030825 0.081935 -0.16384 -0.0302 0.083935 -0.16384 -0.0302 0.081935 -0.163672 -0.029575 0.081935 -0.163215 -0.0291175 0.083935 -0.16259 -0.02895 0.083935 -0.163215 -0.0291175 0.081935 -0.16259 -0.02895 0.081935 -0.161965 -0.0291175 0.081935 -0.161507 -0.029575 0.081935 -0.16134 -0.0302 0.083935 -0.161507 -0.030825 0.081935 -0.161965 -0.0312826 0.083935 -0.161965 -0.0312826 0.081935 -0.16259 -0.03145 0.083935 0.0921768 -0.000894786 0.081935 0.0912443 -0.00371195 0.081935 0.0924349 -0.00490258 0.081935 0.0910768 -0.00287004 0.081935 0.158943 -0.000600042 0.081935 0.160043 -0.000894786 0.081935 0.161143 -0.00287004 0.081935 0.160043 -0.0047753 0.081935 0.160848 -0.00397004 0.081935 0.0913715 -0.00170004 0.083735 0.0932768 -0.000600042 0.083735 0.0910768 -0.00280004 0.083735 0.0910768 -0.00287004 0.083735 0.0917212 -0.00442568 0.083735 0.160848 -0.00170004 0.083735 0.158943 -0.000600042 0.083735 0.161143 -0.00280004 0.083735 0.160848 -0.00397004 0.083735 0.0932768 -0.00507004 0.083735 0.0924349 -0.00490258 0.083735 0.160043 -0.0047753 0.083735 0.158943 -0.00507004 0.083735 0.160848 -0.00170004 0.081935 0.160043 -0.000894786 0.083735 0.161143 -0.00280004 0.081935 0.161143 -0.00287004 0.083735 0.0921768 -0.000894786 0.083735 0.0913715 -0.00170004 0.081935 0.0917212 -0.00442568 0.081935 0.0912443 -0.00371195 0.083735 0.0910768 -0.00280004 0.081935 0.0932768 -0.000600042 0.081935 0.0932768 -0.00507004 0.081935 0.158943 -0.00507004 0.081935 0.0921768 -0.0235748 0.081935 0.0912443 -0.0263919 0.081935 0.0917212 -0.0271057 0.081935 0.160848 -0.02665 0.081935 0.158943 -0.02775 0.081935 0.0910768 -0.02555 0.081935 0.0932768 -0.02775 0.081935 0.158943 -0.02328 0.081935 0.160043 -0.0274553 0.083735 0.0913715 -0.02438 0.083735 0.0912443 -0.0263919 0.083735 0.158943 -0.02775 0.083735 0.0932768 -0.02775 0.083735 0.161143 -0.02548 0.083735 0.0932768 -0.02328 0.083735 0.158943 -0.02328 0.083735 0.161143 -0.02548 0.081935 0.160848 -0.02438 0.081935 0.160043 -0.0235748 0.081935 0.160848 -0.02438 0.083735 0.160043 -0.0235748 0.083735 0.0921768 -0.0235748 0.083735 0.0913715 -0.02438 0.081935 0.0910768 -0.02548 0.083735 0.0924349 -0.0275826 0.083735 0.0924349 -0.0275826 0.081935 0.0917212 -0.0271057 0.083735 0.0910768 -0.02555 0.083735 0.0910768 -0.02548 0.081935 0.160848 -0.02665 0.083735 0.160043 -0.0274553 0.081935 0.0932768 -0.02328 0.081935 0.161143 -0.02555 0.083735 0.161143 -0.02555 0.081935 0.0910768 -0.0539 0.081935 0.158943 -0.05163 0.081935 0.158943 -0.0561 0.081935 0.160043 -0.0558053 0.081935 0.161143 -0.05383 0.081935 0.160848 -0.055 0.081935 0.0921768 -0.0519248 0.083735 0.160043 -0.0519248 0.083735 0.158943 -0.0561 0.083735 0.161143 -0.0539 0.083735 0.161143 -0.05383 0.083735 0.160848 -0.05273 0.083735 0.0910768 -0.05383 0.083735 0.0913715 -0.05273 0.083735 0.0932768 -0.05163 0.083735 0.160848 -0.05273 0.081935 0.160043 -0.0519248 0.081935 0.0932768 -0.05163 0.081935 0.0921768 -0.0519248 0.081935 0.0913715 -0.05273 0.081935 0.0910768 -0.05383 0.081935 0.0921768 -0.0558053 0.083735 0.0932768 -0.0561 0.081935 0.0921768 -0.0558053 0.081935 0.0913715 -0.055 0.083735 0.0913715 -0.055 0.081935 0.0910768 -0.0539 0.083735 0.161143 -0.0539 0.081935 0.160848 -0.055 0.083735 0.160043 -0.0558053 0.083735 0.0932768 -0.0561 0.083735 0.158943 -0.05163 0.083735 0.159785 -0.0461275 0.081935 0.158943 -0.04596 0.081935 0.158943 -0.05043 0.081935 0.160976 -0.0473181 0.081935 0.161143 -0.04816 0.081935 0.0921768 -0.0501353 0.081935 0.0913715 -0.04706 0.081935 0.0910768 -0.04823 0.081935 0.0913715 -0.04706 0.083735 0.160499 -0.0466044 0.083735 0.160976 -0.0473181 0.083735 0.159785 -0.0461275 0.083735 0.160043 -0.0501353 0.083735 0.0913715 -0.04933 0.083735 0.0932768 -0.05043 0.083735 0.0910768 -0.04823 0.083735 0.0910768 -0.04816 0.083735 0.160499 -0.0466044 0.081935 0.158943 -0.04596 0.083735 0.0921768 -0.0462548 0.081935 0.0921768 -0.0462548 0.083735 0.0932768 -0.05043 0.081935 0.0921768 -0.0501353 0.083735 0.0913715 -0.04933 0.081935 0.0910768 -0.04816 0.081935 0.161143 -0.04823 0.083735 0.160848 -0.04933 0.083735 0.160848 -0.04933 0.081935 0.160043 -0.0501353 0.081935 0.158943 -0.05043 0.083735 0.0932768 -0.04596 0.081935 0.0932768 -0.04596 0.083735 0.161143 -0.04816 0.083735 0.161143 -0.04823 0.081935 0.0932768 -0.04029 0.081935 0.0913715 -0.04139 0.081935 0.0910768 -0.04256 0.081935 0.0921768 -0.0444653 0.081935 0.0932768 -0.04476 0.081935 0.158943 -0.04476 0.081935 0.158943 -0.04029 0.081935 0.160848 -0.04366 0.081935 0.160043 -0.0405848 0.083735 0.160043 -0.0444653 0.083735 0.0932768 -0.04476 0.083735 0.0910768 -0.04249 0.083735 0.0921768 -0.0405848 0.083735 0.160848 -0.04139 0.083735 0.158943 -0.04029 0.083735 0.161143 -0.04249 0.083735 0.0932768 -0.04029 0.083735 0.0910768 -0.04256 0.083735 0.160848 -0.04139 0.081935 0.160043 -0.0405848 0.081935 0.0921768 -0.0405848 0.081935 0.0913715 -0.04139 0.083735 0.0921768 -0.0444653 0.083735 0.0913715 -0.04366 0.083735 0.0913715 -0.04366 0.081935 0.0910768 -0.04249 0.081935 0.160848 -0.04366 0.083735 0.160043 -0.0444653 0.081935 0.158943 -0.04476 0.083735 0.161143 -0.04256 0.083735 0.161143 -0.04256 0.081935 0.161143 -0.04249 0.081935 0.158943 -0.03909 0.081935 0.158943 -0.03462 0.081935 0.160499 -0.0352644 0.081935 0.0932768 -0.03462 0.081935 0.0921768 -0.0387953 0.083735 0.158943 -0.03909 0.083735 0.160848 -0.03799 0.083735 0.161143 -0.03682 0.083735 0.0921768 -0.0349148 0.083735 0.0932768 -0.03462 0.083735 0.158943 -0.03462 0.083735 0.160499 -0.0352644 0.083735 0.159785 -0.0347875 0.083735 0.161143 -0.03682 0.081935 0.160976 -0.0359781 0.081935 0.160976 -0.0359781 0.083735 0.159785 -0.0347875 0.081935 0.0921768 -0.0349148 0.081935 0.0913715 -0.03572 0.081935 0.0910768 -0.03682 0.081935 0.0913715 -0.03572 0.083735 0.0932768 -0.03909 0.081935 0.0921768 -0.0387953 0.081935 0.0913715 -0.03799 0.083735 0.0913715 -0.03799 0.081935 0.0910768 -0.03689 0.083735 0.0910768 -0.03689 0.081935 0.0910768 -0.03682 0.083735 0.161143 -0.03689 0.083735 0.160848 -0.03799 0.081935 0.160043 -0.0387953 0.083735 0.160043 -0.0387953 0.081935 0.0932768 -0.03909 0.083735 0.161143 -0.03689 0.081935 0.0932768 -0.02895 0.081935 0.0910768 -0.03115 0.081935 0.0917212 -0.0327757 0.081935 0.0910768 -0.03122 0.081935 0.159785 -0.0291175 0.081935 0.161143 -0.03115 0.081935 0.160499 -0.0295944 0.081935 0.160976 -0.0303081 0.083735 0.160043 -0.0331253 0.083735 0.161143 -0.03122 0.083735 0.0921768 -0.0292448 0.083735 0.0924349 -0.0332526 0.083735 0.0917212 -0.0327757 0.083735 0.0912443 -0.0320619 0.083735 0.0932768 -0.03342 0.083735 0.158943 -0.03342 0.083735 0.158943 -0.02895 0.083735 0.0910768 -0.03115 0.083735 0.160976 -0.0303081 0.081935 0.161143 -0.03115 0.083735 0.160499 -0.0295944 0.083735 0.158943 -0.02895 0.081935 0.159785 -0.0291175 0.083735 0.0921768 -0.0292448 0.081935 0.0913715 -0.03005 0.081935 0.0913715 -0.03005 0.083735 0.0932768 -0.03342 0.081935 0.0924349 -0.0332526 0.081935 0.0912443 -0.0320619 0.081935 0.0910768 -0.03122 0.083735 0.160848 -0.03232 0.083735 0.160848 -0.03232 0.081935 0.160043 -0.0331253 0.081935 0.158943 -0.03342 0.081935 0.0932768 -0.02895 0.083735 0.161143 -0.03122 0.081935 0.0910768 -0.01988 0.081935 0.0924349 -0.0219126 0.081935 0.0921768 -0.0179048 0.081935 0.0932768 -0.01761 0.081935 0.160848 -0.02098 0.081935 0.158943 -0.02208 0.081935 0.160976 -0.0189681 0.081935 0.161143 -0.01981 0.081935 0.0932768 -0.02208 0.081935 0.0917212 -0.0214357 0.081935 0.0913715 -0.01871 0.083735 0.0921768 -0.0179048 0.083735 0.0910768 -0.01981 0.083735 0.0932768 -0.01761 0.083735 0.160848 -0.02098 0.083735 0.0912443 -0.0207219 0.083735 0.0924349 -0.0219126 0.083735 0.160499 -0.0182544 0.083735 0.160976 -0.0189681 0.083735 0.161143 -0.01981 0.083735 0.160499 -0.0182544 0.081935 0.159785 -0.0177775 0.081935 0.159785 -0.0177775 0.083735 0.158943 -0.01761 0.081935 0.158943 -0.01761 0.083735 0.0913715 -0.01871 0.081935 0.0917212 -0.0214357 0.083735 0.0912443 -0.0207219 0.081935 0.0910768 -0.01988 0.083735 0.0910768 -0.01981 0.081935 0.160043 -0.0217853 0.083735 0.160043 -0.0217853 0.081935 0.0932768 -0.02208 0.083735 0.158943 -0.02208 0.083735 0.161143 -0.01988 0.083735 0.161143 -0.01988 0.081935 0.0913715 -0.01304 0.081935 0.0912443 -0.0150519 0.081935 0.160848 -0.01531 0.081935 0.161143 -0.01421 0.081935 0.160043 -0.0122348 0.081935 0.161143 -0.01414 0.081935 0.0910768 -0.01421 0.081935 0.158943 -0.01194 0.083735 0.0917212 -0.0157657 0.083735 0.0924349 -0.0162426 0.083735 0.161143 -0.01414 0.083735 0.160848 -0.01304 0.081935 0.160848 -0.01304 0.083735 0.160043 -0.0122348 0.083735 0.158943 -0.01194 0.081935 0.0932768 -0.01194 0.083735 0.0921768 -0.0122348 0.081935 0.0921768 -0.0122348 0.083735 0.0913715 -0.01304 0.083735 0.0910768 -0.01414 0.081935 0.0910768 -0.01414 0.083735 0.0924349 -0.0162426 0.081935 0.0917212 -0.0157657 0.081935 0.0912443 -0.0150519 0.083735 0.0910768 -0.01421 0.083735 0.160848 -0.01531 0.083735 0.160043 -0.0161153 0.083735 0.160043 -0.0161153 0.081935 0.0932768 -0.01641 0.081935 0.158943 -0.01641 0.081935 0.0932768 -0.01641 0.083735 0.158943 -0.01641 0.083735 0.0932768 -0.01194 0.081935 0.161143 -0.01421 0.083735 0.0917212 -0.0100957 0.081935 0.158943 -0.01074 0.081935 0.161143 -0.00854004 0.081935 0.158943 -0.00627004 0.081935 0.0932768 -0.01074 0.081935 0.0912443 -0.00938195 0.081935 0.160848 -0.00964004 0.083735 0.160043 -0.0104453 0.083735 0.159785 -0.00643751 0.083735 0.160499 -0.00691441 0.083735 0.160976 -0.00762814 0.083735 0.0921768 -0.00656479 0.083735 0.0917212 -0.0100957 0.083735 0.161143 -0.00854004 0.083735 0.158943 -0.00627004 0.083735 0.0932768 -0.00627004 0.083735 0.161143 -0.00847004 0.083735 0.160976 -0.00762814 0.081935 0.160499 -0.00691441 0.081935 0.159785 -0.00643751 0.081935 0.0921768 -0.00656479 0.081935 0.0913715 -0.00737004 0.081935 0.0913715 -0.00737004 0.083735 0.0910768 -0.00847004 0.081935 0.0924349 -0.0105726 0.083735 0.0924349 -0.0105726 0.081935 0.0912443 -0.00938195 0.083735 0.0910768 -0.00854004 0.083735 0.0910768 -0.00854004 0.081935 0.0910768 -0.00847004 0.083735 0.0932768 -0.00627004 0.081935 0.160848 -0.00964004 0.081935 0.160043 -0.0104453 0.081935 0.0932768 -0.01074 0.083735 0.158943 -0.01074 0.083735 0.161143 -0.00847004 0.081935 0.0921768 0.00477521 0.081935 0.0910768 0.00286996 0.081935 0.0917212 0.00124432 0.081935 0.0924349 0.000767423 0.081935 0.158943 0.000599958 0.081935 0.161143 0.00279996 0.081935 0.160499 0.00442559 0.081935 0.161143 0.00286996 0.081935 0.158943 0.00506996 0.081935 0.0932768 0.000599958 0.081935 0.0912443 0.00195805 0.083735 0.0910768 0.00279996 0.083735 0.161143 0.00279996 0.083735 0.0932768 0.000599958 0.083735 0.159785 0.00490249 0.083735 0.0932768 0.00506996 0.083735 0.0910768 0.00286996 0.083735 0.0921768 0.00477521 0.083735 0.0913715 0.00396996 0.083735 0.161143 0.00286996 0.083735 0.160976 0.00371186 0.081935 0.160976 0.00371186 0.083735 0.160499 0.00442559 0.083735 0.159785 0.00490249 0.081935 0.158943 0.00506996 0.083735 0.0932768 0.00506996 0.081935 0.0913715 0.00396996 0.081935 0.0924349 0.000767423 0.083735 0.0917212 0.00124432 0.083735 0.0912443 0.00195805 0.081935 0.0910768 0.00279996 0.081935 0.160848 0.00169996 0.083735 0.160043 0.000894702 0.083735 0.160848 0.00169996 0.081935 0.160043 0.000894702 0.081935 0.158943 0.000599958 0.083735 -0.16239 -0.0558053 0.081935 -0.16129 -0.05163 0.081935 -0.16349 -0.0539 0.081935 -0.14215 -0.05163 0.081935 -0.16129 -0.0561 0.083735 -0.162845 -0.0522744 0.083735 -0.14215 -0.05163 0.083735 -0.16129 -0.05163 0.083735 -0.14215 -0.0561 0.083735 -0.16349 -0.05383 0.083735 -0.162131 -0.0517975 0.083735 -0.16239 -0.0558053 0.083735 -0.163195 -0.055 0.083735 -0.163195 -0.055 0.081935 -0.162131 -0.0517975 0.081935 -0.162845 -0.0522744 0.081935 -0.163322 -0.0529881 0.083735 -0.163322 -0.0529881 0.081935 -0.16349 -0.05383 0.081935 -0.16349 -0.0539 0.083735 -0.16129 -0.0561 0.081935 -0.14215 -0.0561 0.081935 -0.16239 -0.0462548 0.081935 -0.163195 -0.04706 0.081935 -0.16349 -0.04816 0.081935 -0.163195 -0.04933 0.081935 -0.16349 -0.04823 0.081935 -0.14215 -0.05043 0.081935 -0.14215 -0.05043 0.083735 -0.16239 -0.0501353 0.083735 -0.16349 -0.04823 0.083735 -0.16349 -0.04816 0.083735 -0.16129 -0.05043 0.083735 -0.16239 -0.0501353 0.081935 -0.163195 -0.04933 0.083735 -0.16239 -0.0462548 0.083735 -0.163195 -0.04706 0.083735 -0.14215 -0.04596 0.081935 -0.16129 -0.05043 0.081935 -0.14215 -0.04596 0.083735 -0.16129 -0.04596 0.081935 -0.16129 -0.04596 0.083735 -0.16129 -0.04476 0.081935 -0.16239 -0.0444653 0.081935 -0.162131 -0.0404575 0.081935 -0.162845 -0.0409344 0.081935 -0.163195 -0.04366 0.081935 -0.16349 -0.04256 0.081935 -0.16129 -0.04476 0.083735 -0.13515 -0.0423 0.083735 -0.163322 -0.0416481 0.083735 -0.16129 -0.04029 0.083735 -0.16239 -0.0444653 0.083735 -0.163195 -0.04366 0.083735 -0.16129 -0.04029 0.081935 -0.162131 -0.0404575 0.083735 -0.162845 -0.0409344 0.083735 -0.163322 -0.0416481 0.081935 -0.16349 -0.04249 0.081935 -0.16349 -0.04249 0.083735 -0.16349 -0.04256 0.083735 -0.13515 -0.0423 0.081935 -0.13515 -0.04029 0.081935 -0.134807 -0.04476 0.083735 -0.134807 -0.04476 0.081935 -0.13515 -0.04029 0.083735 0.0921768 0.0104452 0.081935 0.0913715 0.00963996 0.081935 0.0910768 0.00853996 0.081935 0.0932768 0.01074 0.081935 0.0910768 0.00846996 0.081935 0.160043 0.0065647 0.081935 0.158943 0.00626996 0.081935 0.160848 0.00736996 0.081935 0.161143 0.00853996 0.081935 0.160499 0.0100956 0.081935 0.158943 0.01074 0.081935 0.0912443 0.00762805 0.081935 0.0913715 0.00963996 0.083735 0.0910768 0.00853996 0.083735 0.0910768 0.00846996 0.083735 0.0912443 0.00762805 0.083735 0.160499 0.0100956 0.083735 0.0932768 0.01074 0.083735 0.161143 0.00846996 0.083735 0.0932768 0.00626996 0.083735 0.0917212 0.00691432 0.083735 0.160976 0.00938186 0.081935 0.160976 0.00938186 0.083735 0.159785 0.0105725 0.081935 0.159785 0.0105725 0.083735 0.0921768 0.0104452 0.083735 0.0924349 0.00643742 0.083735 0.0932768 0.00626996 0.081935 0.0924349 0.00643742 0.081935 0.0917212 0.00691432 0.081935 0.161143 0.00846996 0.081935 0.160848 0.00736996 0.083735 0.160043 0.0065647 0.083735 0.158943 0.00626996 0.083735 0.158943 0.01074 0.083735 0.161143 0.00853996 0.083735 0.0910768 0.01421 0.081935 0.0924349 0.0121074 0.081935 0.0932768 0.01194 0.081935 0.161143 0.01421 0.081935 0.158943 0.01194 0.083735 0.0932768 0.01194 0.083735 0.0924349 0.0121074 0.083735 0.0910768 0.01421 0.083735 0.0921768 0.0161152 0.083735 0.0932768 0.01641 0.083735 0.158943 0.01641 0.083735 0.160848 0.01531 0.083735 0.160848 0.01304 0.083735 0.161143 0.01414 0.083735 0.160848 0.01531 0.081935 0.161143 0.01421 0.083735 0.160043 0.0161152 0.081935 0.160043 0.0161152 0.083735 0.0921768 0.0161152 0.081935 0.0913715 0.01531 0.081935 0.0913715 0.01531 0.083735 0.0917212 0.0125843 0.081935 0.0917212 0.0125843 0.083735 0.0912443 0.0132981 0.081935 0.0912443 0.0132981 0.083735 0.0910768 0.01414 0.083735 0.0910768 0.01414 0.081935 0.160848 0.01304 0.081935 0.160043 0.0122347 0.083735 0.160043 0.0122347 0.081935 0.158943 0.01194 0.081935 0.158943 0.01641 0.081935 0.0932768 0.01641 0.081935 0.161143 0.01414 0.081935 0.159785 0.0219125 0.081935 0.158943 0.02208 0.081935 0.0932768 0.02208 0.081935 0.0913715 0.02098 0.081935 0.0910768 0.01981 0.081935 0.161143 0.01988 0.081935 0.160499 0.0214356 0.081935 0.158943 0.01761 0.081935 0.0932768 0.01761 0.081935 0.0924349 0.0177774 0.083735 0.0913715 0.02098 0.083735 0.0910768 0.01988 0.083735 0.0921768 0.0217852 0.083735 0.161143 0.01988 0.083735 0.158943 0.02208 0.083735 0.0910768 0.01981 0.083735 0.160043 0.0179047 0.083735 0.160976 0.0207219 0.081935 0.160976 0.0207219 0.083735 0.160499 0.0214356 0.083735 0.159785 0.0219125 0.083735 0.0921768 0.0217852 0.081935 0.0910768 0.01988 0.081935 0.0932768 0.01761 0.083735 0.0924349 0.0177774 0.081935 0.0917212 0.0182543 0.083735 0.0917212 0.0182543 0.081935 0.0912443 0.0189681 0.083735 0.0912443 0.0189681 0.081935 0.161143 0.01981 0.083735 0.160848 0.01871 0.083735 0.160848 0.01871 0.081935 0.160043 0.0179047 0.081935 0.158943 0.01761 0.083735 0.0932768 0.02208 0.083735 0.161143 0.01981 0.081935 0.0921768 0.0274552 0.081935 0.0913715 0.02665 0.081935 0.0932768 0.02775 0.081935 0.0917212 0.0239243 0.081935 0.0932768 0.02328 0.081935 0.160848 0.02438 0.081935 0.161143 0.02555 0.081935 0.160848 0.02665 0.081935 0.160043 0.0274552 0.081935 0.161143 0.02548 0.081935 0.158943 0.02328 0.081935 0.160043 0.0274552 0.083735 0.0921768 0.0274552 0.083735 0.0932768 0.02775 0.083735 0.160043 0.0235747 0.083735 0.158943 0.02328 0.083735 0.161143 0.02555 0.083735 0.0924349 0.0234474 0.083735 0.160848 0.02665 0.083735 0.158943 0.02775 0.081935 0.0913715 0.02665 0.083735 0.0910768 0.02555 0.081935 0.0910768 0.02555 0.083735 0.0932768 0.02328 0.083735 0.0924349 0.0234474 0.081935 0.0917212 0.0239243 0.083735 0.0912443 0.0246381 0.083735 0.0912443 0.0246381 0.081935 0.0910768 0.02548 0.081935 0.0910768 0.02548 0.083735 0.160848 0.02438 0.083735 0.160043 0.0235747 0.081935 0.158943 0.02775 0.083735 0.161143 0.02548 0.083735 0.0932768 0.02895 0.081935 0.160499 0.0327756 0.081935 0.0910768 0.03115 0.081935 0.0932768 0.03342 0.081935 0.0913715 0.03232 0.081935 0.158943 0.02895 0.081935 0.160848 0.03005 0.081935 0.161143 0.03122 0.081935 0.160976 0.0320619 0.081935 0.0932768 0.03342 0.083735 0.158943 0.03342 0.083735 0.160848 0.03005 0.083735 0.161143 0.03115 0.083735 0.158943 0.02895 0.083735 0.0924349 0.0291174 0.083735 0.0910768 0.03115 0.083735 0.0912443 0.0303081 0.083735 0.0917212 0.0295943 0.083735 0.161143 0.03122 0.083735 0.160976 0.0320619 0.083735 0.160499 0.0327756 0.083735 0.159785 0.0332525 0.083735 0.159785 0.0332525 0.081935 0.0921768 0.0331252 0.081935 0.0921768 0.0331252 0.083735 0.0913715 0.03232 0.083735 0.0910768 0.03122 0.081935 0.0932768 0.02895 0.083735 0.0924349 0.0291174 0.081935 0.0917212 0.0295943 0.081935 0.0912443 0.0303081 0.081935 0.0910768 0.03122 0.083735 0.161143 0.03115 0.081935 0.160043 0.0292447 0.083735 0.160043 0.0292447 0.081935 0.158943 0.03342 0.081935 0.0917212 0.0352643 0.081935 0.0932768 0.03909 0.081935 0.0912443 0.0359781 0.081935 0.158943 0.03909 0.081935 0.160043 0.0349147 0.081935 0.160848 0.03799 0.081935 0.160043 0.0387952 0.081935 0.0932768 0.03462 0.083735 0.160043 0.0349147 0.083735 0.0912443 0.0359781 0.083735 0.160043 0.0387952 0.083735 0.161143 0.03689 0.081935 0.161143 0.03689 0.083735 0.160848 0.03799 0.083735 0.0932768 0.03909 0.083735 0.0921768 0.0387952 0.081935 0.0921768 0.0387952 0.083735 0.0913715 0.03799 0.083735 0.0913715 0.03799 0.081935 0.0910768 0.03689 0.083735 0.0924349 0.0347874 0.083735 0.0924349 0.0347874 0.081935 0.0917212 0.0352643 0.083735 0.0910768 0.03682 0.083735 0.0910768 0.03682 0.081935 0.0910768 0.03689 0.081935 0.160848 0.03572 0.083735 0.160848 0.03572 0.081935 0.158943 0.03462 0.083735 0.0932768 0.03462 0.081935 0.158943 0.03462 0.081935 0.158943 0.03909 0.083735 0.161143 0.03682 0.081935 0.161143 0.03682 0.083735 0.161143 0.04256 0.081935 0.0913715 0.04366 0.081935 0.0932768 0.04476 0.081935 0.0910768 0.04249 0.081935 0.0917212 0.0409343 0.081935 0.160043 0.0405847 0.083735 0.158943 0.04029 0.083735 0.0917212 0.0409343 0.083735 0.0924349 0.0404574 0.083735 0.161143 0.04256 0.083735 0.161143 0.04249 0.083735 0.0921768 0.0444652 0.083735 0.0932768 0.04476 0.083735 0.160976 0.0434019 0.083735 0.160976 0.0434019 0.081935 0.160499 0.0441156 0.081935 0.159785 0.0445925 0.081935 0.160499 0.0441156 0.083735 0.158943 0.04476 0.081935 0.159785 0.0445925 0.083735 0.0921768 0.0444652 0.081935 0.0913715 0.04366 0.083735 0.0910768 0.04256 0.081935 0.0932768 0.04029 0.081935 0.0924349 0.0404574 0.081935 0.0912443 0.0416481 0.083735 0.0912443 0.0416481 0.081935 0.0910768 0.04249 0.083735 0.0910768 0.04256 0.083735 0.160848 0.04139 0.083735 0.160848 0.04139 0.081935 0.160043 0.0405847 0.081935 0.158943 0.04029 0.081935 0.0932768 0.04029 0.083735 0.158943 0.04476 0.083735 0.161143 0.04249 0.081935 -0.16129 0.04476 0.081935 -0.162845 0.0409343 0.081935 -0.16129 0.04029 0.081935 -0.13515 0.0423 0.083735 -0.16349 0.04256 0.083735 -0.16349 0.04249 0.083735 -0.13515 0.04029 0.083735 -0.16129 0.04029 0.083735 -0.16239 0.0444652 0.083735 -0.16239 0.0444652 0.081935 -0.163195 0.04366 0.083735 -0.163195 0.04366 0.081935 -0.16349 0.04256 0.081935 -0.162131 0.0404574 0.083735 -0.162131 0.0404574 0.081935 -0.162845 0.0409343 0.083735 -0.163322 0.0416481 0.083735 -0.163322 0.0416481 0.081935 -0.16349 0.04249 0.081935 -0.13515 0.04029 0.081935 -0.13515 0.0423 0.081935 -0.134807 0.04476 0.083735 -0.134807 0.04476 0.081935 -0.16129 0.04476 0.083735 -0.163195 0.04933 0.081935 -0.16129 0.04596 0.081935 -0.163195 0.04706 0.083735 -0.16129 0.04596 0.083735 -0.16239 0.0501352 0.083735 -0.16129 0.05043 0.083735 -0.14215 0.05043 0.083735 -0.14215 0.04596 0.083735 -0.16129 0.05043 0.081935 -0.16239 0.0501352 0.081935 -0.163195 0.04933 0.083735 -0.16349 0.04823 0.083735 -0.16239 0.0462547 0.083735 -0.16239 0.0462547 0.081935 -0.163195 0.04706 0.081935 -0.16349 0.04816 0.083735 -0.16349 0.04816 0.081935 -0.16349 0.04823 0.081935 -0.14215 0.04596 0.081935 -0.14215 0.05043 0.081935 0.159785 0.0502625 0.081935 0.0932768 0.05043 0.081935 0.0921768 0.0501352 0.081935 0.0910768 0.04823 0.081935 0.0912443 0.0473181 0.081935 0.161143 0.04816 0.081935 0.158943 0.04596 0.081935 0.158943 0.05043 0.081935 0.0924349 0.0461274 0.081935 0.0917212 0.0466043 0.081935 0.0910768 0.04823 0.083735 0.0913715 0.04933 0.083735 0.0932768 0.05043 0.083735 0.160499 0.0497856 0.083735 0.160976 0.0490719 0.083735 0.0932768 0.04596 0.083735 0.0910768 0.04816 0.083735 0.0917212 0.0466043 0.083735 0.161143 0.04823 0.081935 0.161143 0.04823 0.083735 0.160976 0.0490719 0.081935 0.160499 0.0497856 0.081935 0.159785 0.0502625 0.083735 0.158943 0.05043 0.083735 0.0921768 0.0501352 0.083735 0.0913715 0.04933 0.081935 0.0932768 0.04596 0.081935 0.0924349 0.0461274 0.083735 0.0912443 0.0473181 0.083735 0.0910768 0.04816 0.081935 0.160848 0.04706 0.083735 0.160043 0.0462547 0.083735 0.160848 0.04706 0.081935 0.160043 0.0462547 0.081935 0.158943 0.04596 0.083735 0.161143 0.04816 0.083735 -0.16129 0.05163 0.081935 -0.14215 0.0561 0.081935 -0.16349 0.0539 0.081935 -0.16349 0.05383 0.081935 -0.16349 0.0539 0.083735 -0.16129 0.05163 0.083735 -0.162845 0.0522743 0.083735 -0.14215 0.05163 0.083735 -0.16129 0.0561 0.083735 -0.162131 0.0517974 0.083735 -0.162131 0.0517974 0.081935 -0.162845 0.0522743 0.081935 -0.163322 0.0529881 0.081935 -0.163322 0.0529881 0.083735 -0.16349 0.05383 0.083735 -0.16129 0.0561 0.081935 -0.162131 0.0559325 0.083735 -0.162131 0.0559325 0.081935 -0.162845 0.0554556 0.081935 -0.163322 0.0547419 0.081935 -0.162845 0.0554556 0.083735 -0.163322 0.0547419 0.083735 -0.14215 0.05163 0.081935 -0.14215 0.0561 0.083735 0.0912443 0.0529881 0.081935 0.0910768 0.05383 0.081935 0.0932768 0.05163 0.081935 0.158943 0.0561 0.081935 0.160848 0.055 0.081935 0.161143 0.0539 0.081935 0.160848 0.05273 0.081935 0.0910768 0.05383 0.083735 0.0924349 0.0517974 0.083735 0.0910768 0.0539 0.083735 0.158943 0.0561 0.083735 0.0932768 0.05163 0.083735 0.160848 0.055 0.083735 0.160043 0.0558052 0.081935 0.160043 0.0558052 0.083735 0.0921768 0.0558052 0.083735 0.0921768 0.0558052 0.081935 0.0913715 0.055 0.081935 0.0913715 0.055 0.083735 0.0910768 0.0539 0.081935 0.0924349 0.0517974 0.081935 0.0917212 0.0522743 0.083735 0.0912443 0.0529881 0.083735 0.0917212 0.0522743 0.081935 0.161143 0.05383 0.083735 0.160848 0.05273 0.083735 0.161143 0.05383 0.081935 0.160043 0.0519247 0.083735 0.160043 0.0519247 0.081935 0.158943 0.05163 0.081935 0.158943 0.05163 0.083735 0.0932768 0.0561 0.081935 0.0932768 0.0561 0.083735 0.161143 0.0539 0.083735 -0.13515 -0.02328 0.081935 -0.13759 -0.02328 0.081935 -0.139145 -0.0271057 0.081935 -0.138431 -0.0275826 0.081935 -0.13979 -0.02555 0.083735 -0.13979 -0.02548 0.083735 -0.13759 -0.02775 0.083735 -0.139145 -0.0271057 0.083735 -0.139622 -0.0263919 0.083735 -0.139145 -0.0239244 0.083735 -0.138431 -0.0234475 0.081935 -0.13759 -0.02328 0.083735 -0.138431 -0.0234475 0.083735 -0.139145 -0.0239244 0.081935 -0.139622 -0.0246381 0.081935 -0.139622 -0.0246381 0.083735 -0.13759 -0.02775 0.081935 -0.138431 -0.0275826 0.083735 -0.139622 -0.0263919 0.081935 -0.13979 -0.02555 0.081935 -0.13979 -0.02548 0.081935 -0.13515 -0.02328 0.083735 -0.13515 -0.02775 0.081935 -0.13515 -0.02775 0.083735 -0.13515 -0.03462 0.081935 -0.13759 -0.03462 0.081935 -0.13979 -0.03689 0.081935 -0.13759 -0.03909 0.081935 -0.13869 -0.0349148 0.081935 -0.13759 -0.03462 0.083735 -0.139495 -0.03572 0.083735 -0.13759 -0.03909 0.083735 -0.13869 -0.0349148 0.083735 -0.139495 -0.03572 0.081935 -0.139495 -0.03799 0.081935 -0.13979 -0.03689 0.083735 -0.139495 -0.03799 0.083735 -0.13869 -0.0387953 0.083735 -0.13869 -0.0387953 0.081935 -0.13979 -0.03682 0.081935 -0.13979 -0.03682 0.083735 -0.13515 -0.03909 0.081935 -0.13515 -0.03909 0.083735 -0.13515 -0.03462 0.083735 -0.13759 0.02328 0.081935 -0.13515 0.02775 0.081935 -0.138431 0.0234474 0.081935 -0.138431 0.0275825 0.081935 -0.13759 0.02775 0.081935 -0.13979 0.02555 0.081935 -0.13979 0.02548 0.081935 -0.13979 0.02548 0.083735 -0.13759 0.02328 0.083735 -0.13759 0.02775 0.083735 -0.139145 0.0239243 0.083735 -0.139622 0.0263919 0.083735 -0.13979 0.02555 0.083735 -0.138431 0.0275825 0.083735 -0.139145 0.0271056 0.081935 -0.139622 0.0263919 0.081935 -0.139145 0.0271056 0.083735 -0.139622 0.0246381 0.083735 -0.139622 0.0246381 0.081935 -0.139145 0.0239243 0.081935 -0.138431 0.0234474 0.083735 -0.13515 0.02328 0.081935 -0.13515 0.02328 0.083735 -0.13515 0.02775 0.083735 -0.13759 0.02895 0.081935 -0.13515 0.02895 0.081935 -0.13869 0.0331252 0.081935 -0.13979 0.03122 0.081935 -0.139145 0.0295943 0.081935 -0.13979 0.03115 0.081935 -0.13759 0.02895 0.083735 -0.138431 0.0291174 0.083735 -0.13979 0.03122 0.083735 -0.13869 0.0331252 0.083735 -0.13759 0.03342 0.083735 -0.139145 0.0295943 0.083735 -0.13759 0.03342 0.081935 -0.139495 0.03232 0.081935 -0.139495 0.03232 0.083735 -0.138431 0.0291174 0.081935 -0.139622 0.0303081 0.083735 -0.13979 0.03115 0.083735 -0.139622 0.0303081 0.081935 -0.13515 0.03342 0.081935 -0.13515 0.02895 0.083735 -0.13515 0.03342 0.083735 -0.14359 0.0217852 0.081935 -0.144395 0.02098 0.081935 -0.14469 0.01988 0.081935 -0.14469 0.01981 0.081935 -0.14249 0.02208 0.081935 -0.13515 0.01761 0.083735 -0.14469 0.01981 0.083735 -0.144522 0.0189681 0.083735 -0.144522 0.0189681 0.081935 -0.144045 0.0182543 0.081935 -0.144045 0.0182543 0.083735 -0.143331 0.0177774 0.081935 -0.143331 0.0177774 0.083735 -0.144395 0.02098 0.083735 -0.14359 0.0217852 0.083735 -0.14469 0.01988 0.083735 -0.14249 0.01761 0.081935 -0.14249 0.01761 0.083735 -0.13515 0.01761 0.081935 -0.13515 0.02208 0.081935 -0.13515 0.02208 0.083735 -0.14249 0.02208 0.083735 -0.14469 0.01421 0.081935 -0.144522 0.0132981 0.081935 -0.14249 0.01641 0.081935 -0.13515 0.01641 0.083735 -0.144395 0.01531 0.083735 -0.143331 0.0121074 0.083735 -0.14249 0.01194 0.083735 -0.144522 0.0132981 0.083735 -0.144045 0.0125843 0.081935 -0.144045 0.0125843 0.083735 -0.143331 0.0121074 0.081935 -0.14249 0.01194 0.081935 -0.14359 0.0161152 0.083735 -0.144395 0.01531 0.081935 -0.14359 0.0161152 0.081935 -0.14469 0.01421 0.083735 -0.14469 0.01414 0.083735 -0.14469 0.01414 0.081935 -0.13515 0.01194 0.083735 -0.13515 0.01641 0.081935 -0.13515 0.01194 0.081935 -0.14249 0.01641 0.083735 -0.14359 0.0104452 0.081935 -0.14469 0.00853996 0.081935 -0.13515 0.00626996 0.081935 -0.143331 0.00643742 0.081935 -0.143331 0.00643742 0.083735 -0.144045 0.00691432 0.083735 -0.144522 0.00762805 0.083735 -0.14249 0.00626996 0.083735 -0.14469 0.00846996 0.083735 -0.14359 0.0104452 0.083735 -0.13515 0.00626996 0.083735 -0.14469 0.00846996 0.081935 -0.144522 0.00762805 0.081935 -0.144045 0.00691432 0.081935 -0.14249 0.00626996 0.081935 -0.14469 0.00853996 0.083735 -0.144395 0.00963996 0.083735 -0.144395 0.00963996 0.081935 -0.13515 0.01074 0.081935 -0.13515 0.01074 0.083735 -0.14249 0.01074 0.081935 -0.14249 0.01074 0.083735 -0.144395 -0.00737004 0.081935 -0.14249 -0.01074 0.081935 -0.14359 -0.00656479 0.083735 -0.14249 -0.00627004 0.083735 -0.13515 -0.00627004 0.083735 -0.13515 -0.01074 0.083735 -0.13515 -0.01074 0.081935 -0.14469 -0.00854004 0.083735 -0.144522 -0.00938195 0.081935 -0.144522 -0.00938195 0.083735 -0.144045 -0.0100957 0.081935 -0.144045 -0.0100957 0.083735 -0.143331 -0.0105726 0.081935 -0.143331 -0.0105726 0.083735 -0.14469 -0.00847004 0.083735 -0.144395 -0.00737004 0.083735 -0.14359 -0.00656479 0.081935 -0.14249 -0.00627004 0.081935 -0.14469 -0.00847004 0.081935 -0.14469 -0.00854004 0.081935 -0.13515 -0.00627004 0.081935 -0.14249 -0.01074 0.083735 -0.14249 -0.01194 0.081935 -0.14249 -0.01641 0.081935 -0.144045 -0.0157657 0.081935 -0.144522 -0.0150519 0.081935 -0.14359 -0.0122348 0.083735 -0.14249 -0.01641 0.083735 -0.144522 -0.0150519 0.083735 -0.144045 -0.0157657 0.083735 -0.143331 -0.0162426 0.081935 -0.143331 -0.0162426 0.083735 -0.14469 -0.01414 0.081935 -0.144395 -0.01304 0.083735 -0.144395 -0.01304 0.081935 -0.14249 -0.01194 0.083735 -0.14359 -0.0122348 0.081935 -0.14469 -0.01414 0.083735 -0.14469 -0.01421 0.083735 -0.14469 -0.01421 0.081935 -0.13515 -0.01641 0.083735 -0.13515 -0.01641 0.081935 -0.13515 -0.01194 0.081935 -0.13515 -0.01194 0.083735 -0.144395 -0.01871 0.081935 -0.14469 -0.01988 0.081935 -0.144522 -0.0207219 0.081935 -0.144045 -0.0214357 0.081935 -0.144522 -0.0207219 0.083735 -0.144045 -0.0214357 0.083735 -0.143331 -0.0219126 0.081935 -0.14249 -0.02208 0.081935 -0.143331 -0.0219126 0.083735 -0.14249 -0.02208 0.083735 -0.144395 -0.01871 0.083735 -0.14469 -0.01981 0.081935 -0.14359 -0.0179048 0.083735 -0.14359 -0.0179048 0.081935 -0.14249 -0.01761 0.081935 -0.14469 -0.01981 0.083735 -0.14469 -0.01988 0.083735 -0.13515 -0.02208 0.081935 -0.13515 -0.02208 0.083735 -0.13515 -0.01761 0.081935 -0.13515 -0.01761 0.083735 -0.14249 -0.01761 0.083735 -0.13759 -0.02895 0.081935 -0.13515 -0.02895 0.081935 -0.13515 -0.03342 0.081935 -0.13979 -0.03115 0.081935 -0.139145 -0.0327757 0.083735 -0.13515 -0.03342 0.083735 -0.13759 -0.03342 0.083735 -0.138431 -0.0332526 0.083735 -0.13979 -0.03122 0.083735 -0.13759 -0.02895 0.083735 -0.13869 -0.0292448 0.083735 -0.13869 -0.0292448 0.081935 -0.139495 -0.03005 0.081935 -0.139495 -0.03005 0.083735 -0.13979 -0.03115 0.083735 -0.138431 -0.0332526 0.081935 -0.139622 -0.0320619 0.083735 -0.139145 -0.0327757 0.081935 -0.139622 -0.0320619 0.081935 -0.13979 -0.03122 0.081935 -0.13759 -0.03342 0.081935 -0.13515 -0.02895 0.083735 -0.13515 0.03462 0.081935 -0.139145 0.0384456 0.081935 -0.139622 0.0377319 0.081935 -0.13759 0.03462 0.081935 -0.138431 0.0389225 0.081935 -0.139145 0.0352643 0.081935 -0.139622 0.0359781 0.081935 -0.13979 0.03689 0.081935 -0.13515 0.03909 0.083735 -0.13759 0.03909 0.083735 -0.13759 0.03462 0.083735 -0.138431 0.0347874 0.083735 -0.139145 0.0352643 0.083735 -0.139145 0.0384456 0.083735 -0.139622 0.0377319 0.083735 -0.13515 0.03462 0.083735 -0.138431 0.0389225 0.083735 -0.138431 0.0347874 0.081935 -0.139622 0.0359781 0.083735 -0.13979 0.03682 0.083735 -0.13979 0.03682 0.081935 -0.13979 0.03689 0.083735 -0.13515 0.03909 0.081935 -0.13759 0.03909 0.081935 -0.205773 0.07595 0.081935 -0.176988 0.0688655 0.081935 -0.205173 0.0682004 0.081935 -0.204508 0.067756 0.081935 -0.205773 0.06965 0.081935 -0.203723 0.0676 0.081935 -0.178882 0.0676 0.081935 -0.176832 0.06965 0.081935 -0.176988 0.0739353 0.081935 -0.204508 0.0778439 0.081935 -0.180232 0.0773995 0.081935 -0.205617 0.0688655 0.083435 -0.204508 0.0778439 0.083435 -0.205617 0.0767345 0.083435 -0.180232 0.0773995 0.083435 -0.203723 0.078 0.083435 -0.203723 0.0676 0.083435 -0.205773 0.06965 0.083435 -0.176832 0.0731508 0.083435 -0.178098 0.067756 0.081935 -0.178098 0.067756 0.083435 -0.177433 0.0682004 0.081935 -0.177433 0.0682004 0.083435 -0.176988 0.0688655 0.083435 -0.176988 0.0739353 0.083435 -0.177433 0.0746004 0.083435 -0.176832 0.0731508 0.081935 -0.176832 0.06965 0.083435 -0.203723 0.078 0.081935 -0.205173 0.0773995 0.081935 -0.205617 0.0767345 0.081935 -0.205173 0.0773995 0.083435 -0.204508 0.067756 0.083435 -0.205173 0.0682004 0.083435 -0.205617 0.0688655 0.081935 -0.205773 0.07595 0.083435 -0.178882 0.0676 0.083435 -0.180897 0.0778439 0.081935 -0.180897 0.0778439 0.083435 -0.181681 0.078 0.083435 -0.177433 0.0746004 0.081935 -0.181681 0.078 0.081935 0.443575 -0.053541 0.0690202 0.446427 -0.054756 0.0671875 0.447014 -0.0547559 0.0671878 0.447118 -0.0547553 0.0671889 0.442427 -0.048243 0.0749483 0.44245 -0.0511252 0.0720712 0.442821 -0.0524501 0.0704837 0.444278 -0.0397172 0.0799985 0.443754 -0.0401259 0.0798569 0.447533 -0.0390729 0.0801983 0.448355 -0.0413813 0.0793123 0.454838 -0.0405089 0.078742 0.45116 -0.039076 0.0799925 0.464961 -0.0398782 0.0726776 0.463793 -0.039284 0.0741209 0.462541 -0.0390877 0.0752782 0.466466 -0.0442804 0.0677075 0.466022 -0.0452883 0.0673627 0.46422 -0.0475214 0.0673924 0.464122 -0.0437725 0.0710598 0.45555 -0.0507739 0.0708532 0.45819 -0.0522982 0.0674576 0.461477 -0.0488847 0.0689414 0.449914 -0.0546992 0.0671743 0.449036 -0.0515914 0.071351 0.451661 -0.0410623 0.0791817 0.458595 -0.0499785 0.0700942 0.455432 -0.0469729 0.074411 0.452352 -0.0512901 0.0712439 0.457863 -0.0396765 0.0779341 0.458151 -0.0419948 0.0767064 0.451933 -0.043353 0.0779176 0.448638 -0.043692 0.0780745 0.448956 -0.0478581 0.0749981 0.455114 -0.0428044 0.0774842 0.452244 -0.0475067 0.0748249 0.458487 -0.0461956 0.0736759 0.461035 -0.0409058 0.07556 0.461387 -0.0451339 0.0725656 0.463762 -0.0395291 0.0740342 0.442652 0.0520347 0.0710021 0.442427 0.0482453 0.0749462 0.466575 0.0425239 0.069046 0.45511 0.0428 0.0774875 0.458148 0.0419909 0.0767142 0.461031 0.0408992 0.0755681 0.463369 0.0391724 0.0745513 0.454116 0.0390755 0.0794692 0.451655 0.0410606 0.0791848 0.449982 0.0390749 0.0800965 0.445211 0.0392673 0.0801438 0.446427 0.0390728 0.0802034 0.448349 0.0413811 0.0793136 0.447014 0.0547559 0.0671876 0.44904 0.0515905 0.0713518 0.443306 0.0532333 0.0694489 0.447431 0.054756 0.0671867 0.455554 0.05077 0.0708575 0.458598 0.0499719 0.0700987 0.46148 0.0488765 0.0689477 0.448956 0.0478572 0.0749988 0.452244 0.0475041 0.0748271 0.451929 0.0433501 0.0779192 0.455433 0.0469686 0.0744147 0.458488 0.0461899 0.0736814 0.463757 0.0395201 0.0740427 0.448635 0.043692 0.0780761 0.454832 0.0405043 0.0787449 0.457858 0.0396718 0.0779408 0.452356 0.0512882 0.071247 0.461387 0.0451267 0.0725729 0.464208 0.0475025 0.0674291 0.464121 0.0437634 0.0710684 0.465806 0.0456064 0.0673437 0.466592 0.0436615 0.0680857 0.466312 0.0447191 0.0675115 0.456657 0.0350729 0.0796491 0.445024 0.0347411 0.0810547 0.442427 0.0331305 0.0811719 0.444204 0.036529 0.0808045 0.445263 0.0370442 0.080708 0.446831 0.0372218 0.0806719 0.446427 0.0372218 0.0806718 0.451914 0.0350027 0.0807633 0.448529 0.0348871 0.0810136 0.448426 0.0372228 0.0806468 0.45649 0.0372376 0.0792595 0.454247 0.0372319 0.0799395 0.460932 0.0350171 0.0776539 0.464397 0.0372555 0.0743997 0.4648 0.0320676 0.0753423 0.462655 0.0372523 0.0758779 0.470969 0.0340898 0.0672139 0.465066 0.0372564 0.0737545 0.467007 0.0372589 0.0716128 0.468361 0.037028 0.0699608 0.469424 0.0364634 0.0686855 0.470797 0.0346587 0.0672836 0.471686 0.0292123 0.067175 0.471563 0.0305661 0.0671888 0.472098 0.0234837 0.0673495 0.470284 0.0205922 0.0705299 0.468522 0.0236258 0.0724491 0.465565 0.0199357 0.0757829 0.46496 0.0238978 0.0759862 0.461155 0.0199264 0.0787139 0.450797 0.019901 0.0811793 0.451743 0.0199019 0.0811265 0.456728 0.0240575 0.0802621 0.454202 0.0199062 0.0808605 0.456759 0.0322758 0.0799537 0.445049 0.0319244 0.0812243 0.444851 0.0236636 0.0812387 0.448375 0.0238145 0.0812318 0.448564 0.032073 0.081201 0.451966 0.0321928 0.0809793 0.451823 0.0239459 0.0810898 0.461072 0.0322297 0.0780253 0.46115 0.024039 0.0785244 0.4683 0.03178 0.0716977 0.470228 0.0315525 0.0691156 0.470473 0.0234042 0.0699072 0.47016 -0.0325226 0.0689901 0.470969 -0.0340893 0.0672138 0.470048 -0.0358916 0.0679792 0.468233 -0.0327453 0.0715796 0.467007 -0.037259 0.0716128 0.460636 -0.0372481 0.0772697 0.456347 -0.0372373 0.0793105 0.450217 -0.0372254 0.0805592 0.451944 -0.0331324 0.0809315 0.45672 -0.0332201 0.0798775 0.453451 -0.0372302 0.0801212 0.443227 -0.035582 0.0809511 0.444958 -0.0284636 0.0812458 0.442427 -0.0331306 0.0811719 0.445027 -0.0328543 0.081192 0.442609 -0.034347 0.081088 0.443312 -0.021387 0.081235 0.444214 -0.0205591 0.081235 0.446827 -0.0199 0.0812351 0.451914 -0.0287517 0.0810552 0.454322 -0.0199066 0.0808421 0.456691 -0.0199131 0.0803629 0.46113 -0.0288345 0.0782954 0.460185 -0.0199236 0.0791693 0.471372 -0.0225717 0.0686705 0.468405 -0.0284158 0.0720571 0.47033 -0.0281928 0.069465 0.471687 -0.0292098 0.067175 0.472108 -0.0243208 0.0671938 0.448543 -0.033008 0.0811628 0.450747 -0.019901 0.0811814 0.448486 -0.0286203 0.0812377 0.445446 -0.0200125 0.081235 0.46474 -0.0330246 0.0752318 0.461021 -0.0331798 0.0779275 0.456766 -0.0288588 0.0801347 0.464889 -0.0286896 0.0756704 0.47543 0.0269313 -0.045685 0.47543 0.02665 -0.046735 0.47543 0.02875 -0.046735 0.47543 0.02875 -0.044635 0.47543 -0.02665 -0.046735 0.47543 -0.0269314 -0.045685 0.47543 -0.02875 -0.046735 0.47543 -0.02875 -0.048835 0.47543 -0.0277 -0.0485536 0.47543 -0.0277 -0.0449163 0.426772 -0.0391417 0.0821509 0.423044 -0.0343828 0.0825276 0.426112 -0.0426138 0.0676042 0.425724 -0.0420324 0.0664743 0.424527 -0.0397441 0.0690651 0.424364 -0.0399447 0.0650237 0.419886 -0.0341545 0.069561 0.418155 -0.032393 0.0666911 0.420957 -0.0340095 0.0787661 0.418441 -0.0317985 0.0786974 0.4177 -0.0318071 0.0758888 0.421572 -0.0337218 0.080989 0.42148 -0.0332317 0.0818529 0.424035 -0.0364137 0.0807089 0.424522 -0.0357681 0.0828058 0.427376 -0.0426866 0.0787522 0.427533 -0.042316 0.0798138 0.427539 -0.0416633 0.0807489 0.426527 -0.0411636 0.0781983 0.426526 -0.0427948 0.0751816 0.421245 -0.0357405 0.0648427 0.423654 -0.0388976 0.0648733 0.42483 -0.0398396 0.07372 0.426381 -0.0428007 0.073235 0.427101 -0.0409059 0.0804305 0.427166 -0.0400164 0.0818873 0.426191 -0.0393276 0.0804981 0.425605 -0.0395935 0.0782684 0.42345 -0.0366798 0.0784793 0.42513 -0.0397802 0.076014 0.422332 -0.0368586 0.0692848 0.422693 -0.0369121 0.0739266 0.420199 -0.0342428 0.0742137 0.405866 0.0210122 0.0789889 0.415427 0.0275395 0.0829488 0.416024 0.0281734 0.0826811 0.416822 0.0291318 0.0820463 0.412469 0.0250067 0.0831175 0.414244 0.0264677 0.0831174 0.409615 0.0245396 0.0787314 0.406267 0.0210878 0.0797953 0.407233 0.0215015 0.0809553 0.410247 0.0241668 0.0811427 0.404263 0.0203049 0.075598 0.404948 0.0208473 0.0764299 0.40534 0.0210189 0.0773472 0.402227 0.0182442 0.073235 0.405354 0.0215454 0.0742537 0.403813 0.0198838 0.0752595 0.402086 0.0179822 0.0719965 0.405245 0.0214108 0.0718481 0.40538 0.0210413 0.0694452 0.407525 0.0205984 0.0647539 0.405834 0.0203614 0.0670457 0.412652 0.0264501 0.0646562 0.412537 0.0263266 0.0646532 0.409166 0.0237773 0.0667046 0.413246 0.0276655 0.0783936 0.416885 0.0305063 0.0785892 0.413818 0.027351 0.0808041 0.415968 0.0305171 0.073235 0.404833 0.0185506 0.0663699 0.408876 0.0242972 0.0691059 0.408923 0.0247306 0.0739152 0.406146 0.021257 0.0790711 0.427159 0.0449425 0.0697912 0.426896 0.0440657 0.0720331 0.427183 0.0447888 0.0744059 0.427604 0.0469424 0.0716103 0.428063 0.0514816 0.0706685 0.427515 0.0456152 0.0753075 0.427807 0.0466008 0.0758595 0.427718 0.0473502 0.066962 0.427264 0.0459239 0.0649082 0.426977 0.0449371 0.0658094 0.428352 0.0505978 0.0631718 0.428721 0.0557361 0.0649857 0.427928 0.0494068 0.0688105 0.428679 0.0530679 0.062887 0.428669 0.0515077 0.07443 0.428334 0.0524698 0.0715719 0.42881 0.0532323 0.072508 0.428933 0.056277 0.0677578 0.426801 0.0440789 0.0682857 0.401162 0.00124996 0.067235 0.400827 -4.19898e-08 0.077235 0.402077 -0.00216511 0.067235 0.404577 -0.00216511 0.067235 0.405492 -0.00125004 0.077235 0.405827 -4.19898e-08 0.067235 0.405827 -4.19898e-08 0.077235 0.405492 0.00124996 0.067235 0.404577 0.00216502 0.067235 0.404577 0.00216502 0.077235 0.403327 0.00249996 0.067235 0.402077 0.00216502 0.067235 0.401162 -0.00125004 0.067235 0.400827 -4.19898e-08 0.067235 0.403327 -4.19898e-08 0.0657329 0.403327 -0.00250004 0.067235 0.405492 -0.00125004 0.067235 0.425077 0.00216502 0.067235 0.424162 0.00124996 0.067235 0.424162 -0.00125004 0.067235 0.425077 -0.00216511 0.077235 0.426327 -0.00250004 0.067235 0.426327 -0.00250004 0.077235 0.427577 -0.00216511 0.077235 0.427577 0.00216502 0.067235 0.428492 0.00124996 0.077235 0.427577 0.00216502 0.077235 0.426327 0.00249996 0.077235 0.426327 -4.19898e-08 0.0657329 0.425077 -0.00216511 0.067235 0.423827 -4.19898e-08 0.067235 0.427577 -0.00216511 0.067235 0.428492 0.00124996 0.067235 0.428492 -0.00125004 0.067235 0.428827 -4.19898e-08 0.067235 0.426327 0.00249996 0.067235 0.44726 0.0557013 -0.0362806 0.442795 0.0558154 -0.0446875 0.442107 0.0561801 -0.0363339 0.441059 0.0561318 -0.0374391 0.441272 0.0556171 -0.038015 0.440509 0.0560866 -0.0384746 0.440704 0.0554805 -0.0408312 0.441468 0.0553838 -0.0428252 0.441633 0.0558531 -0.0438223 0.442919 0.0553189 -0.044162 0.445169 0.0552897 -0.044765 0.445733 0.0552914 -0.0447294 0.447489 0.0558141 -0.0447157 0.446984 0.0553082 -0.0443828 0.447724 0.0553283 -0.043969 0.449066 0.0553988 -0.0425149 0.449151 0.0554063 -0.0423607 0.450137 0.0559831 -0.0408458 0.449669 0.055508 -0.040265 0.449066 0.0556171 -0.038015 0.442848 0.0562009 -0.0358579 0.445169 -0.0562259 -0.0352868 0.44372 -0.0562165 -0.0355012 0.443077 -0.0557013 -0.0362806 0.442919 -0.0556971 -0.0363679 0.447542 -0.0558154 -0.0446875 0.447419 -0.0556971 -0.0363679 0.447724 -0.0556877 -0.036561 0.449279 -0.0561319 -0.0374391 0.450137 -0.056032 -0.0397278 0.449151 -0.0556097 -0.0381692 0.449417 -0.0554361 -0.0417477 0.449889 -0.0559356 -0.0419357 0.448704 -0.0558532 -0.0438223 0.448869 -0.0553838 -0.0428252 0.447419 -0.055319 -0.044162 0.444953 -0.0557895 -0.0452821 0.445169 -0.0552897 -0.044765 0.442848 -0.0558142 -0.0447157 0.441059 -0.0558832 -0.0431345 0.441272 -0.0553989 -0.0425149 0.4402 -0.0559832 -0.0408458 0.441187 -0.0554064 -0.0423607 0.440669 -0.0555081 -0.040265 0.440704 -0.0555355 -0.0396987 0.440448 -0.0560796 -0.0386378 0.441272 -0.0556172 -0.038015 0.441468 -0.0556323 -0.0377047 0.445733 -0.0557246 -0.0358005 0.446472 -0.055717 -0.0359579 0.446341 0.0575 0.05266 0.447534 0.0572 0.0534434 0.448809 0.0572 0.053785 0.447384 0.0575 0.0537032 0.448809 0.0575 0.054085 0.450084 0.0572 0.0534434 0.451017 0.0572 0.05251 0.451359 0.0572 0.051235 0.451277 0.0575 0.04981 0.450084 0.0572 0.0490267 0.450234 0.0575 0.0487669 0.448809 0.0575 0.048385 0.4466 0.0572 0.04996 0.4466 0.0572 0.05251 0.443894 0.0535 -0.0380566 0.443744 0.0538 -0.0377968 0.446594 0.0538 -0.0377968 0.447637 0.0538 -0.03884 0.447377 0.0535 -0.03899 0.447719 0.0535 -0.040265 0.447377 0.0535 -0.04154 0.447637 0.0538 -0.04169 0.446594 0.0538 -0.0427331 0.445169 0.0538 -0.043115 0.443744 0.0538 -0.0427331 0.44296 0.0535 -0.04154 0.442319 0.0538 -0.040265 0.44296 0.0535 -0.03899 0.447534 -0.0572 0.0534434 0.447384 -0.0575 0.0537032 0.446341 -0.0575 0.05266 0.4466 -0.0572 0.05251 0.446259 -0.0572 0.051235 0.4466 -0.0572 0.04996 0.446341 -0.0575 0.04981 0.447534 -0.0572 0.0490267 0.448809 -0.0575 0.048385 0.451277 -0.0575 0.04981 0.451659 -0.0575 0.051235 0.447377 -0.0535 -0.03899 0.442319 -0.0538 -0.040265 0.443744 -0.0538 -0.0427331 0.443894 -0.0535 -0.0424733 0.445169 -0.0535 -0.042815 0.446594 -0.0538 -0.0427331 0.447377 -0.0535 -0.04154 0.447637 -0.0538 -0.04169 0.447719 -0.0535 -0.040265 0.448019 -0.0538 -0.040265 0.447637 -0.0538 -0.03884 0.431563 -0.01975 0.080935 0.431303 -0.0244 0.081235 0.431563 -0.02425 0.080935 0.43546 -0.0265 0.080935 0.43546 -0.0268 0.081235 0.43771 -0.0181029 0.080935 0.43546 -0.0175 0.080935 0.43546 -0.0172 0.081235 0.43306 -0.0178431 0.081235 0.431303 0.0244 0.081235 0.431563 0.01975 0.080935 0.43321 0.0181028 0.080935 0.43546 0.0175 0.080935 0.43546 0.0172 0.081235 0.43771 0.0181028 0.080935 0.43771 0.0258971 0.080935 0.478189 0.0287488 -0.050535 0.476827 0.02875 -0.050535 0.478228 0.0284059 -0.0505194 0.479058 0.0254088 -0.048545 0.478594 0.0265942 -0.0498643 0.476827 0.02685 -0.0500259 0.478525 0.0268478 -0.0500247 0.476827 0.02495 -0.046735 0.479539 0.02495 -0.046735 0.479904 0.0254586 -0.0448356 0.476827 0.02685 -0.0434441 0.480033 0.0268505 -0.043444 0.476827 0.02875 -0.042935 0.479248 0.0318189 -0.0444941 0.479536 0.0309468 -0.0436343 0.476827 0.03065 -0.0434441 0.476827 0.0320409 -0.044835 0.478142 0.0306509 -0.0500256 0.476827 0.03065 -0.0500259 0.478229 0.0316311 -0.0492126 0.476827 0.0320409 -0.048635 0.476827 0.03255 -0.046735 0.478484 0.032443 -0.0476303 0.446558 0.0588191 0.0551319 0.448076 0.0587 0.0556749 0.446213 0.058864 0.0549111 0.446559 0.0575 0.0551321 0.444912 0.0591039 0.0534854 0.444912 0.0575 0.048985 0.444912 0.0575 0.053485 0.445479 0.0593414 0.0482079 0.446559 0.0575 0.0473379 0.448809 0.0575 0.046735 0.449424 0.059286 0.0467773 0.452706 0.0590319 0.048985 0.451059 0.0575 0.0473379 0.451585 0.0591927 0.0476935 0.45311 0.0589262 0.0499135 0.452706 0.0575 0.048985 0.453153 0.0587247 0.0524086 0.453286 0.0588408 0.0507797 0.452706 0.0586849 0.053485 0.452784 0.0586882 0.0533449 0.451059 0.0575 0.0551321 0.448809 0.0575 0.055735 0.43321 -0.0181029 0.080935 0.43096 -0.022 0.078235 0.43096 -0.022 0.080935 0.43321 -0.0258972 0.080935 0.43771 -0.0258972 0.080935 0.43771 -0.0258972 0.078235 0.439357 -0.02425 0.080935 0.43996 -0.022 0.080935 0.439357 -0.01975 0.080935 0.43771 -0.0181029 0.078235 0.43546 0.0265 0.080935 0.43321 0.0258971 0.078235 0.43321 0.0258971 0.080935 0.431563 0.02425 0.080935 0.43096 0.022 0.078235 0.43096 0.022 0.080935 0.431563 0.01975 0.078235 0.43321 0.0181028 0.078235 0.43771 0.0181028 0.078235 0.439357 0.01975 0.080935 0.43996 0.022 0.080935 0.439357 0.02425 0.080935 0.446559 -0.0593107 0.0473379 0.448809 -0.0575 0.055735 0.446559 -0.0575 0.0551321 0.451428 -0.0586702 0.0548942 0.453309 -0.0575 0.051235 0.453081 -0.0587133 0.0526478 0.452706 -0.058685 0.0534849 0.452706 -0.0575 0.048985 0.452706 -0.0590321 0.0489851 0.449429 -0.0592861 0.0467779 0.448809 -0.0575 0.046735 0.447783 -0.0592896 0.0468535 0.445687 -0.059335 0.0479944 0.446265 -0.0593181 0.0475232 0.444735 -0.0593609 0.0493243 0.44432 -0.0593326 0.050916 0.444309 -0.0575 0.051235 0.444309 -0.0593174 0.051235 0.446558 -0.0588192 0.0551319 0.446387 -0.0588406 0.0550278 0.444912 -0.0575 0.053485 0.444912 -0.059104 0.0534855 0.476827 -0.02875 -0.050535 0.478312 -0.0320411 -0.0486345 0.476827 -0.03065 -0.0500259 0.478171 -0.0311156 -0.0497089 0.478458 -0.0324071 -0.0477675 0.478666 -0.03255 -0.046735 0.478883 -0.0324363 -0.0458122 0.476827 -0.0320409 -0.044835 0.47951 -0.0310408 -0.0437031 0.479242 -0.0318332 -0.0445137 0.476827 -0.02875 -0.042935 0.480029 -0.026559 -0.0436302 0.476827 -0.02685 -0.0434441 0.479966 -0.0282473 -0.0429684 0.479886 -0.025393 -0.0449545 0.476827 -0.02495 -0.046735 0.476827 -0.0254591 -0.048635 0.478738 -0.0261411 -0.0494979 0.479043 -0.0254352 -0.0485929 0.478127 -0.0301676 -0.0502607 0.478548 -0.0267581 -0.049971 0.444604 0.0557245 -0.0358005 0.443865 0.0557169 -0.0359579 0.442919 0.0538 -0.0363679 0.442919 0.055697 -0.0363679 0.442613 0.0556877 -0.036561 0.441272 0.0538 -0.038015 0.441187 0.0556096 -0.0381692 0.440669 0.0538 -0.040265 0.440669 0.055508 -0.040265 0.441272 0.0538 -0.042515 0.44092 0.055436 -0.0417477 0.441272 0.0553988 -0.0425149 0.445169 0.0538 -0.044765 0.447419 0.0553189 -0.044162 0.445363 0.0552899 -0.0447608 0.442919 0.0538 -0.0441621 0.443077 0.0553147 -0.0442493 0.447419 0.0538 -0.0441621 0.44949 0.0555688 -0.039011 0.449669 0.0538 -0.040265 0.449633 0.0555354 -0.0396987 0.447419 0.0538 -0.0363679 0.448869 0.0556322 -0.0377047 0.445169 0.0557263 -0.035765 0.447419 0.055697 -0.0363679 0.449066 -0.0538 -0.038015 0.449066 -0.0556172 -0.038015 0.449633 -0.0554806 -0.0408312 0.449669 -0.0555081 -0.040265 0.449066 -0.0553989 -0.0425149 0.444604 -0.0552915 -0.0447294 0.445169 -0.0538 -0.044765 0.442919 -0.0538 -0.0441621 0.443354 -0.0553083 -0.0443828 0.442919 -0.055319 -0.044162 0.444974 -0.05529 -0.0447608 0.44726 -0.0553148 -0.0442493 0.441272 -0.0538 -0.042515 0.442613 -0.0553284 -0.043969 0.440847 -0.0555689 -0.039011 0.441272 -0.0538 -0.038015 0.445169 -0.0557264 -0.035765 0.476827 0.0269313 -0.045685 0.476827 0.0277 -0.0449163 0.47543 0.0277 -0.0449163 0.47543 0.0298 -0.0449163 0.47543 0.0305686 -0.045685 0.47543 0.03085 -0.046735 0.476827 0.0305686 -0.047785 0.47543 0.0305686 -0.047785 0.47543 0.0298 -0.0485536 0.47543 0.02875 -0.048835 0.476827 0.0277 -0.0485536 0.47543 0.0277 -0.0485536 0.476827 0.0269313 -0.047785 0.476827 0.02665 -0.046735 0.47543 0.0269313 -0.047785 0.415677 -0.0141814 -0.061565 0.414908 -0.01495 -0.061565 0.415677 -0.0141814 -0.058565 0.414627 -0.016 -0.058565 0.414908 -0.01705 -0.061565 0.414908 -0.01705 -0.058565 0.415677 -0.0178187 -0.058565 0.416727 -0.0181 -0.058565 0.416727 -0.0181 -0.061565 0.417777 -0.0178187 -0.058565 0.417777 -0.0178187 -0.061565 0.418545 -0.01705 -0.061565 0.418545 -0.01705 -0.058565 0.418827 -0.016 -0.058565 0.418545 -0.01495 -0.058565 0.417777 -0.0141814 -0.058565 0.415677 0.0178186 -0.061565 0.415677 0.0178186 -0.058565 0.414908 0.01705 -0.058565 0.414908 0.01495 -0.058565 0.415677 0.0141813 -0.061565 0.416727 0.0139 -0.061565 0.417777 0.0141813 -0.061565 0.416727 0.0139 -0.058565 0.417777 0.0141813 -0.058565 0.418545 0.01495 -0.061565 0.418827 0.016 -0.061565 0.418545 0.01495 -0.058565 0.418827 0.016 -0.058565 0.418545 0.01705 -0.058565 0.417777 0.0178186 -0.061565 0.476827 -0.03085 -0.046735 0.47543 -0.0305687 -0.045685 0.476827 -0.0298 -0.0449163 0.47543 -0.0298 -0.0449163 0.476827 -0.02875 -0.044635 0.47543 -0.02875 -0.044635 0.476827 -0.0269314 -0.045685 0.476827 -0.02665 -0.046735 0.476827 -0.0269314 -0.047785 0.47543 -0.0269314 -0.047785 0.476827 -0.0277 -0.0485536 0.476827 -0.02875 -0.048835 0.47543 -0.0298 -0.0485536 0.47543 -0.0305687 -0.047785 0.47543 -0.03085 -0.046735 0.4466 0.0565 0.05251 0.446259 0.0572 0.051235 0.451017 0.0565 0.05251 0.451017 0.0572 0.04996 0.450084 0.0565 0.0490267 0.448809 0.0572 0.048685 0.447534 0.0572 0.0490267 0.434378 -0.021375 0.07796 0.43414 -0.0212375 0.078235 0.434378 -0.022625 0.07796 0.433935 -0.022 0.078235 0.434835 -0.0230826 0.07796 0.436985 -0.022 0.078235 0.436085 -0.0209175 0.07796 0.434378 0.022625 0.07796 0.434698 0.0233206 0.078235 0.433935 0.022 0.078235 0.434835 0.0209174 0.07796 0.434698 0.0206793 0.078235 0.43546 0.02075 0.07796 0.43546 0.020475 0.078235 0.436223 0.0206793 0.078235 0.436543 0.021375 0.07796 0.43671 0.022 0.07796 0.436781 0.0212375 0.078235 0.436543 0.022625 0.07796 0.436223 0.0233206 0.078235 0.43546 0.02325 0.07796 0.434835 0.0230825 0.07796 0.43546 0.023525 0.078235 0.451359 -0.0572 0.051235 0.451017 -0.0572 0.05251 0.450084 -0.0565 0.0534434 0.450084 -0.0572 0.0534434 0.448809 -0.0572 0.053785 0.4466 -0.0565 0.04996 0.447534 -0.0565 0.0490267 0.448809 -0.0565 0.048685 0.448809 -0.0572 0.048685 0.450084 -0.0565 0.0490267 0.450084 -0.0572 0.0490267 0.451017 -0.0572 0.04996 0.44296 0.0528 -0.03899 0.445169 0.0535 -0.037715 0.446444 0.0535 -0.0380566 0.447377 0.0528 -0.03899 0.446444 0.0528 -0.0424733 0.446444 0.0535 -0.0424733 0.445169 0.0535 -0.042815 0.443894 0.0535 -0.0424733 0.442619 0.0535 -0.040265 0.43546 -0.02075 0.070735 0.43546 -0.02075 0.07796 0.434378 -0.021375 0.070735 0.434835 -0.0209175 0.07796 0.434378 -0.022625 0.070735 0.43421 -0.022 0.07796 0.43546 -0.02325 0.07796 0.436085 -0.0230826 0.070735 0.436085 -0.0230826 0.07796 0.436543 -0.022625 0.070735 0.436543 -0.022625 0.07796 0.43671 -0.022 0.07796 0.43671 -0.022 0.070735 0.436543 -0.021375 0.07796 0.436085 -0.0209175 0.070735 0.434835 0.0230825 0.070735 0.434378 0.022625 0.070735 0.43421 0.022 0.070735 0.43421 0.022 0.07796 0.434378 0.021375 0.07796 0.434835 0.0209174 0.070735 0.43546 0.02075 0.070735 0.436085 0.0209174 0.07796 0.436085 0.0230825 0.07796 0.445169 -0.0528 -0.037715 0.446444 -0.0535 -0.0380566 0.445169 -0.0535 -0.037715 0.443894 -0.0528 -0.0380566 0.443894 -0.0535 -0.0380566 0.44296 -0.0528 -0.03899 0.44296 -0.0535 -0.03899 0.442619 -0.0535 -0.040265 0.44296 -0.0535 -0.04154 0.446444 -0.0528 -0.0424733 0.446444 -0.0535 -0.0424733 0.447377 -0.0528 -0.04154 0.480416 0.00357619 0.016546 0.479357 0.00690772 0.0170679 0.480359 0.00484636 0.0165788 0.480416 0.00442372 0.016546 0.480435 0.00399996 0.016535 0.479822 -0.000657841 0.0179863 0.479605 -0.00326073 0.0209242 0.479357 -0.00326078 0.0209243 0.479695 -0.00207473 0.019227 0.479357 -0.00326078 0.0285458 0.479577 -0.00375042 0.027413 0.479357 -0.00420004 0.024735 0.479557 -0.00420004 0.024735 0.479695 -0.00207447 0.0302433 0.479928 0.000300922 0.0320533 0.480416 0.00442372 0.0329241 0.480359 0.00315356 0.0328912 0.479928 0.00769753 0.032054 0.479689 0.0101376 0.0301728 0.479357 0.00690772 0.0324022 0.480034 0.00690672 0.0324025 0.479568 0.0119617 0.0227726 0.479557 0.0122 0.024735 0.479565 0.0120759 0.0261562 0.479581 0.0116494 0.0217811 0.479577 0.0117503 0.022057 0.479928 0.00769899 0.0174168 0.480412 -0.0254201 0.0182987 0.480435 -0.025 0.018285 0.479357 -0.021775 0.0191492 0.47989 -0.0282236 0.0191483 0.479998 -0.0275581 0.0188138 0.48034 -0.0258384 0.0183398 0.479357 -0.025 0.018285 0.479666 -0.0300807 0.0207616 0.479357 -0.0305859 0.02151 0.479581 -0.0310322 0.0270188 0.479571 -0.0312112 0.0264752 0.479357 -0.03145 0.024735 0.479692 -0.0298347 0.0290045 0.480412 -0.0245799 0.0311713 0.480412 -0.0254201 0.0311713 0.479357 -0.028225 0.0303209 0.480143 -0.0267995 0.0309289 0.47989 -0.0217765 0.0303218 0.479998 -0.022442 0.0306563 0.479357 -0.021775 0.0303209 0.479797 -0.0210904 0.0298651 0.479357 -0.0194142 0.02796 0.479565 -0.0186567 0.0259034 0.479357 -0.01855 0.024735 0.479571 -0.0187889 0.0229948 0.479692 -0.0201654 0.0204655 0.479581 -0.0189679 0.0224512 0.480412 0.0245799 0.0182987 0.479357 0.025 0.018285 0.480143 0.0267994 0.0185411 0.479357 0.021775 0.0191492 0.479357 0.0194141 0.02151 0.479617 0.0194143 0.0215098 0.479357 0.0194141 0.02796 0.479357 0.01855 0.024735 0.479557 0.01855 0.024735 0.479692 0.0201653 0.0290045 0.479357 0.021775 0.0303209 0.479725 0.0204715 0.0293279 0.480412 0.0254201 0.0311713 0.479357 0.025 0.031185 0.48034 0.0241616 0.0311303 0.47989 0.0282235 0.0303218 0.479998 0.027558 0.0306563 0.479357 0.028225 0.0303209 0.47959 0.030906 0.0273276 0.479581 0.0310321 0.0224512 0.479357 0.028225 0.0191492 0.479615 0.0306069 0.021547 0.431933 -0.0595493 0.0454182 0.441027 -0.0463678 0.0625451 0.428963 -0.0509928 0.0607873 0.428815 -0.0502045 0.0612024 0.428403 -0.0483225 0.0619919 0.430306 -0.0575676 0.0540914 0.42999 -0.0564718 0.0558592 0.441027 -0.0509939 0.0607867 0.429697 -0.0551634 0.0574804 0.429423 -0.0536742 0.0589184 0.42914 -0.0520068 0.0601705 0.431395 -0.0594423 0.0481789 0.441027 -0.0577638 0.0537148 0.430646 -0.0584347 0.0522058 0.447726 0.056225 0.05186 0.448184 0.056225 0.0523176 0.448809 0.0565 0.05276 0.450059 0.056225 0.051235 0.450129 0.0565 0.0504725 0.449891 0.056225 0.05061 0.449434 0.056225 0.0501525 0.449571 0.0565 0.0499143 0.448809 0.0565 0.04971 0.447488 0.0565 0.0504725 0.447726 0.056225 0.05061 0.447284 0.0565 0.051235 0.447559 0.056225 0.051235 0.447488 0.0565 0.0519975 0.434835 -0.0209175 0.070735 0.43421 -0.022 0.070735 0.43546 -0.02325 0.070735 0.434835 -0.0230826 0.070735 0.43546 -0.022 0.069984 0.436543 -0.021375 0.070735 0.43546 0.02325 0.070735 0.434378 0.021375 0.070735 0.436085 0.0209174 0.070735 0.436085 0.0230825 0.070735 0.43671 0.022 0.070735 0.436543 0.022625 0.070735 0.43546 0.022 0.069984 0.436543 0.021375 0.070735 0.448809 -0.0565 0.05276 0.447726 -0.056225 0.05186 0.448046 -0.0565 0.0525557 0.447559 -0.056225 0.051235 0.447488 -0.0565 0.0504725 0.448809 -0.0565 0.04971 0.449571 -0.0565 0.0499143 0.449891 -0.056225 0.05061 0.450059 -0.056225 0.051235 0.450334 -0.0565 0.051235 0.444406 0.0528 -0.0389443 0.445169 0.0528 -0.03874 0.446251 0.052525 -0.03964 0.446419 0.052525 -0.040265 0.446694 0.0528 -0.040265 0.446489 0.0528 -0.0410275 0.445931 0.0528 -0.0415857 0.445169 0.052525 -0.041515 0.445169 0.0528 -0.04179 0.443848 0.0528 -0.0410275 0.443919 0.052525 -0.040265 0.447559 0.0505 0.051235 0.447726 0.0505 0.05186 0.448184 0.0505 0.0523176 0.448809 0.0505 0.052485 0.448809 0.056225 0.052485 0.449891 0.0505 0.05186 0.449434 0.056225 0.0523176 0.449891 0.056225 0.05186 0.449891 0.0505 0.05061 0.448809 0.056225 0.049985 0.447726 0.0505 0.05061 0.448184 0.056225 0.0501525 0.449891 -0.056225 0.05186 0.449891 -0.0505 0.05186 0.449434 -0.056225 0.0523176 0.448809 -0.0505 0.052485 0.448809 -0.056225 0.052485 0.448184 -0.056225 0.0523176 0.448184 -0.0505 0.0501525 0.447726 -0.056225 0.05061 0.448184 -0.056225 0.0501525 0.448809 -0.056225 0.049985 0.449434 -0.056225 0.0501525 0.445794 -0.052525 -0.0391824 0.445169 -0.0528 -0.03874 0.444086 -0.052525 -0.03964 0.443848 -0.0528 -0.0395025 0.444086 -0.052525 -0.04089 0.443848 -0.0528 -0.0410275 0.444406 -0.0528 -0.0415857 0.444544 -0.052525 -0.0413475 0.445169 -0.052525 -0.041515 0.445169 -0.0528 -0.04179 0.446489 -0.0528 -0.0410275 0.446251 -0.052525 -0.04089 0.444086 0.0468 -0.03964 0.444086 0.052525 -0.03964 0.444544 0.0468 -0.0391824 0.444544 0.052525 -0.0391824 0.445794 0.0468 -0.0391824 0.445169 0.052525 -0.039015 0.445794 0.052525 -0.0391824 0.446251 0.0468 -0.04089 0.446251 0.052525 -0.04089 0.445794 0.0468 -0.0413475 0.445794 0.052525 -0.0413475 0.445169 0.0468 -0.041515 0.444544 0.0468 -0.0413475 0.444086 0.0468 -0.04089 0.444544 0.052525 -0.0413475 0.444086 0.052525 -0.04089 0.448809 0.0497489 0.051235 0.449434 0.0505 0.0523176 0.449434 0.0505 0.0501525 0.450059 0.0505 0.051235 0.448184 0.0505 0.0501525 0.448809 0.0505 0.049985 0.448809 -0.049749 0.051235 0.448184 -0.0505 0.0523176 0.449434 -0.0505 0.0523176 0.447726 -0.0505 0.05061 0.447559 -0.0505 0.051235 0.447726 -0.0505 0.05186 0.448809 -0.0505 0.049985 0.449434 -0.0505 0.0501525 0.449891 -0.0505 0.05061 0.450059 -0.0505 0.051235 0.446419 -0.052525 -0.040265 0.445794 -0.0468 -0.0391824 0.446251 -0.052525 -0.03964 0.445169 -0.0468 -0.039015 0.445169 -0.052525 -0.039015 0.444544 -0.0468 -0.0391824 0.444544 -0.052525 -0.0391824 0.444086 -0.0468 -0.03964 0.443919 -0.052525 -0.040265 0.443919 -0.0468 -0.040265 0.444544 -0.0468 -0.0413475 0.445169 -0.0468 -0.041515 0.445794 -0.0468 -0.0413475 0.445794 -0.052525 -0.0413475 0.446419 -0.0468 -0.040265 0.445169 0.0468 -0.039015 0.445169 0.0460489 -0.040265 0.446419 0.0468 -0.040265 0.446251 0.0468 -0.03964 0.443919 0.0468 -0.040265 0.445169 -0.046049 -0.040265 0.446251 -0.0468 -0.03964 0.444086 -0.0468 -0.04089 0.446251 -0.0468 -0.04089 0.426958 0.0442457 0.073235 0.426381 0.0428006 0.073235 0.42735 0.0450482 0.0752414 0.428017 0.0472488 0.076688 0.427641 0.0448616 0.0771769 0.427193 0.0427654 0.0780055 0.427476 0.0425295 0.0793187 0.427554 0.0418967 0.0804733 0.42794 0.0446953 0.0788088 0.427958 0.0463083 0.0773127 0.420326 0.0325407 0.0810934 0.419824 0.0313432 0.0826745 0.41748 0.0318091 0.073235 0.41619 0.0305143 0.0759085 0.41654 0.0305102 0.0774801 0.417714 0.0318064 0.0759774 0.419141 0.0319781 0.0799318 0.417024 0.0305046 0.0789762 0.417305 0.0303301 0.0801559 0.417238 0.0298571 0.0811925 0.421863 0.0334889 0.0820526 0.420842 0.0322399 0.0826717 0.42735 -0.0450483 0.0752414 0.427193 -0.044811 0.0744389 0.427513 -0.045612 0.0753049 0.427745 -0.0427212 0.0801329 0.427193 -0.0427655 0.0780055 0.427958 -0.0463084 0.0773127 0.427641 -0.0448617 0.0771769 0.427987 -0.046144 0.0776693 0.41673 -0.0311616 0.073235 0.41748 -0.0318093 0.073235 0.415971 -0.030517 0.0735696 0.41753 -0.0318089 0.0745457 0.415968 -0.030517 0.073235 0.416252 -0.0305136 0.0762481 0.419012 -0.0319304 0.0797608 0.420041 -0.03239 0.080861 0.420842 -0.03224 0.0826717 0.423294 -0.0345814 0.0826252 0.408635 -0.0222978 0.0819885 0.40534 -0.0210189 0.0773472 0.404759 -0.0190496 0.0807492 0.406906 -0.0201389 0.082835 0.406454 -0.0211519 0.0800733 0.407442 -0.0216101 0.0811442 0.402681 -0.0187459 0.0741788 0.401652 -0.0175299 0.073235 0.397217 -0.00803447 0.073235 0.398001 -0.0109588 0.073235 0.397618 -0.00759948 0.0765006 0.396693 -0.00264513 0.073235 0.396899 -0.00370616 0.0749226 0.396743 -0.00380697 0.0736214 0.397329 -0.00748291 0.0753673 0.398233 -0.0109676 0.0756628 0.400234 -0.0149721 0.0764179 0.399641 -0.0141414 0.0757997 0.401497 -0.017039 0.0757956 0.403715 -0.0197134 0.0756775 0.404448 -0.019014 0.0801447 0.404112 -0.0194583 0.0782526 0.402227 -0.0182443 0.073235 0.402113 -0.0179736 0.0717445 0.407592 -0.0206654 0.0647322 0.407455 -0.0186387 0.0632117 0.412271 -0.0252884 0.063328 0.413965 -0.027947 0.0649832 0.412842 -0.026657 0.0646665 0.412652 -0.0264502 0.0646562 0.419034 -0.0332548 0.0657062 0.417623 -0.0319208 0.0678168 0.41552 -0.0298362 0.0665781 0.417464 -0.0317998 0.0688237 0.414821 -0.0289842 0.0656177 0.420118 -0.0344237 0.065055 0.415055 -0.0285258 0.0633789 0.42545 -0.0420205 0.0636281 0.426799 -0.0443038 0.0667618 0.426284 -0.0428105 0.0688611 0.426815 -0.0443099 0.0669545 0.426801 -0.044079 0.0682857 0.426896 -0.0440657 0.0720331 0.426958 -0.0442458 0.073235 0.428895 -0.0546261 0.060889 0.43022 -0.0598379 0.0521068 0.430521 -0.0595673 0.0502484 0.429682 -0.0593482 0.0556329 0.429495 -0.0569158 0.0560882 0.429202 -0.0555779 0.0577714 0.428896 -0.0570634 0.0626749 0.428752 -0.0541775 0.0633138 0.428676 -0.0530384 0.0628811 0.428646 -0.0523548 0.060575 0.428352 -0.0505978 0.0631718 0.427918 -0.0486098 0.0624813 0.427841 -0.0480252 0.0641514 0.425936 -0.0430015 0.063471 0.427116 -0.0457362 0.0637491 0.425136 -0.0411233 0.0655865 0.407319 -0.0182674 0.0631179 0.405809 -0.0153383 0.0630875 0.399089 -4.19898e-08 0.0670986 0.398825 -0.00383267 0.0675192 0.397353 -4.19898e-08 0.0699556 0.396986 -0.0037847 0.0712232 0.398281 -0.011098 0.071275 0.397365 -0.00750312 0.0712472 0.399003 -0.011215 0.0693609 0.400076 -0.0113107 0.0675909 0.403056 -0.00701687 0.0634509 0.400525 -0.00766381 0.0659364 0.400179 -0.00385058 0.0659108 0.399186 -0.0076216 0.0675471 0.39772 -0.00381074 0.0692917 0.398092 -0.00756832 0.069321 0.396734 -0.00381372 0.073235 0.403891 -0.00932787 0.0630545 0.401379 -0.0113871 0.0659801 0.404359 -0.011491 0.063103 0.401589 -0.0148349 0.0676508 0.400551 -0.0146907 0.069412 0.399832 -0.0145219 0.0713073 0.42381 -0.0392854 0.0634582 0.420699 -0.0350609 0.0634763 0.41965 -0.0337821 0.0633952 0.41074 -0.0233029 0.063195 0.409696 -0.0220084 0.0632717 0.40565 -0.0151386 0.063153 0.40486 -0.0183391 0.0661139 0.402833 -0.0149561 0.0660417 0.402276 -0.0179704 0.0708781 0.398965 -0.0132758 0.073235 0.402009 -0.0177574 0.0713409 0.428803 -0.0516689 0.0745977 0.428669 -0.0515087 0.0744293 0.428887 -0.0542593 0.0712222 0.429571 -0.0547418 0.0721487 0.432394 -0.0555759 0.0729798 0.431401 -0.0600958 0.0455242 0.431854 -0.0612535 0.044653 0.429226 -0.0584015 0.0592453 0.429857 -0.0595625 0.0544239 0.429882 -0.060645 0.0565948 0.430925 -0.0553997 0.0727504 0.431648 -0.0615668 0.0615525 0.432806 -0.0601291 0.0657227 0.432697 -0.0592468 0.067428 0.429074 -0.0579182 0.0643641 0.430294 -0.0607644 0.0611274 0.42941 -0.0595057 0.0605886 0.430767 -0.0619349 0.0570048 0.431358 -0.0625724 0.0528171 0.429729 -0.0571134 0.0687003 0.431095 -0.0578498 0.0692441 0.429958 -0.0591364 0.0650241 0.431322 -0.0599152 0.0655065 0.433563 -0.0629895 0.0576226 0.432108 -0.0627595 0.0573726 0.432687 -0.0634205 0.0531166 0.434128 -0.0636719 0.0533752 0.433347 -0.0635874 0.0489347 0.434777 -0.0638612 0.0491914 0.435482 -0.0637453 0.045235 0.432734 -0.062583 0.0447626 0.432027 -0.0627221 0.048699 0.431145 -0.0614012 0.0485432 0.430475 -0.0612606 0.0525441 0.432192 -0.052864 0.076073 0.428504 -0.0501296 0.0756277 0.429706 -0.052355 0.0753495 0.430028 -0.0511875 0.0769081 0.430813 -0.0527508 0.0758366 0.432137 -0.0521843 0.0767508 0.428325 -0.0433791 0.0809938 0.427465 -0.0410258 0.0813627 0.427552 -0.0399932 0.0825744 0.426821 -0.0383563 0.083069 0.425475 -0.0369845 0.0826478 0.42847 -0.0468173 0.0786854 0.428301 -0.0491996 0.0759932 0.429384 -0.0473798 0.0795705 0.429133 -0.0507283 0.0763323 0.429407 -0.0509019 0.0765445 0.428512 -0.0375881 0.0845179 0.428908 -0.0417461 0.0827646 0.429982 -0.0416445 0.0833766 0.430537 -0.0457436 0.0814178 0.429218 -0.0436334 0.081889 0.430601 -0.0477194 0.0801522 0.429371 -0.0395682 0.0840537 0.430354 -0.0437116 0.0824957 0.431064 -0.0514404 0.0772721 0.425848 -0.0367769 0.0833884 0.427582 -0.0380459 0.0839309 0.428369 -0.0398564 0.0834502 0.428045 -0.0416863 0.0818748 0.427965 -0.0453179 0.0783371 0.397375 -4.19901e-08 0.0765779 0.397154 -4.19898e-08 0.0759712 0.397376 0.00493773 0.0765364 0.396724 0.00357342 0.073235 0.397038 0.00700332 0.0732356 0.396672 -4.19898e-08 0.073235 0.396743 0.00380687 0.073622 0.396903 -5.04053e-07 0.0751424 0.399641 0.0141413 0.0758002 0.398686 0.0126828 0.0732353 0.397106 0.00742596 0.0732357 0.402853 0.0189243 0.0744117 0.401497 0.0170389 0.075796 0.402261 0.0182849 0.0733393 0.404759 0.0190495 0.0807494 0.408661 0.0223139 0.0820035 0.408986 0.0221896 0.0827783 0.404112 0.0194582 0.0782529 0.403422 0.0190242 0.077235 0.403715 0.0197133 0.075678 0.400113 0.0153409 0.0732352 0.397607 0.00752253 0.0765016 0.396899 0.00370602 0.0749231 0.397329 0.00748277 0.0753677 0.398233 0.0109675 0.0756633 0.428895 0.054626 0.060889 0.397365 0.00750304 0.0712472 0.41673 0.0311615 0.073235 0.42545 0.0420205 0.0636281 0.428751 0.0541421 0.0632943 0.428761 0.0550749 0.0640269 0.428711 0.0558224 0.0651738 0.428866 0.0536927 0.0595766 0.427116 0.0457361 0.0637491 0.42761 0.0471293 0.0643919 0.426799 0.0443037 0.0667618 0.426813 0.0443021 0.0669764 0.426284 0.0428105 0.0688611 0.425839 0.0422086 0.0667339 0.426144 0.0426584 0.0677522 0.419928 0.0342113 0.0651357 0.421245 0.0357404 0.0648427 0.414795 0.0289513 0.0655908 0.41547 0.0297751 0.0664864 0.418896 0.0331134 0.065827 0.415055 0.0285258 0.0633789 0.416028 0.030506 0.0688095 0.415925 0.0303355 0.0676615 0.417653 0.0319452 0.0677232 0.418168 0.0324054 0.0666708 0.413812 0.0277648 0.0649105 0.409661 0.0230852 0.0645775 0.406177 0.0194271 0.065388 0.40872 0.0219337 0.0645522 0.409696 0.0220083 0.0632717 0.403777 0.0180754 0.0674728 0.402833 0.0149561 0.0660417 0.401589 0.0148348 0.0676508 0.40306 0.017938 0.0686184 0.402608 0.0179546 0.0697242 0.402113 0.0179735 0.0717445 0.402195 0.0182049 0.0731246 0.40471 0.0124964 0.0630676 0.40565 0.0151385 0.063153 0.40585 0.0154293 0.0630883 0.407455 0.0186386 0.0632117 0.412271 0.0252883 0.063328 0.418932 0.0329339 0.0633813 0.420699 0.0350608 0.0634763 0.428547 0.0518961 0.0628173 0.428186 0.0496466 0.063586 0.428286 0.0503249 0.0617513 0.426741 0.0448275 0.0633684 0.425936 0.0430014 0.063471 0.429138 0.0581194 0.0600685 0.429357 0.0587481 0.0581155 0.429726 0.0577652 0.0547488 0.42986 0.059566 0.054401 0.430452 0.0599239 0.0507172 0.400179 0.0038505 0.0659108 0.399697 -4.19898e-08 0.0663747 0.396986 0.00378462 0.0712232 0.397732 0.0101255 0.0732352 0.399003 0.0112149 0.0693609 0.399186 0.00762152 0.0675471 0.400076 0.0113106 0.0675909 0.398281 0.0110979 0.071275 0.400551 0.0146906 0.069412 0.39772 0.00381066 0.0692917 0.398092 0.00756824 0.069321 0.398825 0.00383258 0.0675192 0.399832 0.0145218 0.0713073 0.402009 0.0177573 0.0713409 0.401379 0.011387 0.0659801 0.400525 0.00766373 0.0659364 0.40486 0.018339 0.0661139 0.403917 0.00961778 0.0630834 0.404359 0.0114909 0.063103 0.403094 0.00708427 0.0634258 0.403914 0.00944392 0.0630549 0.431953 0.0528696 0.0760569 0.432394 0.0555751 0.0729807 0.429506 0.0522409 0.0752217 0.429571 0.0547411 0.0721495 0.429003 0.0557305 0.0691571 0.429729 0.0571129 0.068701 0.428763 0.0562599 0.0664211 0.428996 0.0575599 0.0615243 0.42941 0.0595054 0.0605891 0.429598 0.0592221 0.0562372 0.430179 0.0598165 0.0523538 0.430903 0.0599499 0.0481501 0.432582 0.0580525 0.0694616 0.432806 0.0601287 0.0657233 0.431648 0.0615665 0.0615531 0.433563 0.0629893 0.057623 0.434128 0.0636718 0.0533755 0.433347 0.0635873 0.0489348 0.430925 0.055399 0.0727512 0.431095 0.0578493 0.0692449 0.431322 0.0599148 0.0655072 0.430294 0.0607641 0.061128 0.432108 0.0627593 0.0573731 0.431358 0.0625723 0.0528174 0.432687 0.0634203 0.0531169 0.434053 0.0634599 0.0449754 0.432734 0.0625829 0.0447626 0.42901 0.0558633 0.0689403 0.429074 0.0579178 0.0643647 0.429958 0.059136 0.0650248 0.430767 0.0619347 0.0570053 0.429882 0.0606448 0.0565953 0.430475 0.0612605 0.0525444 0.432027 0.062722 0.0486992 0.431145 0.0614012 0.0485434 0.459993 -0.055646 -0.0416333 0.462892 -0.0550423 -0.042541 0.472809 -0.0533788 0.0162537 0.453761 -0.0592161 0.0524947 0.456849 -0.0559746 -0.0404426 0.481571 -0.0294712 0.0331595 0.454103 -0.0390756 0.0794725 0.452693 -0.0543596 0.0672209 0.451573 -0.0545448 0.0671897 0.465864 -0.0407891 0.0711468 0.468178 -0.0398053 0.0687089 0.466442 -0.041953 0.069649 0.466624 -0.0431024 0.0685169 0.461227 -0.0383388 0.0765329 0.449987 -0.039075 0.0800962 0.454531 -0.0372326 0.0798674 0.455423 -0.0386885 0.0792183 0.459195 -0.0372449 0.0780811 0.457075 -0.0390794 0.0784945 0.459992 -0.0390845 0.0770409 0.462022 -0.0372515 0.0763487 0.464465 -0.0372557 0.0743356 0.448412 -0.0372229 0.0806472 0.446831 -0.0372219 0.0806719 0.448019 -0.037984 0.0804856 0.446832 -0.0386277 0.0803314 0.448783 -0.0390737 0.0801623 0.469141 -0.036655 0.0690196 0.467939 -0.0371517 0.0704757 0.466595 -0.0373398 0.0720687 0.464818 -0.0394571 0.0730416 0.476227 -0.029429 0.0571703 0.475486 -0.0314219 0.0586597 0.478683 -0.0294593 0.048922 0.476525 -0.0327738 0.0551415 0.481492 -0.0331238 0.0293568 0.480413 -0.0294758 0.0407456 0.481543 -0.0340385 0.027114 0.481665 -0.0344421 0.0247991 0.48302 -0.0299356 0.015406 0.482793 -0.0311514 0.016321 0.482557 -0.0322356 0.0174604 0.481236 -0.0301422 -0.0360636 0.480408 -0.033694 -0.0386836 0.479444 -0.0328937 -0.04545 0.478769 -0.0324079 -0.0491953 0.478617 -0.0306119 -0.0507413 0.478532 -0.0303966 -0.0511845 0.478081 -0.0341134 -0.0511869 0.477488 -0.0369827 -0.0511966 0.477257 -0.0378696 -0.051202 0.474804 -0.0440776 -0.0513186 0.476079 -0.0414529 -0.0510899 0.462195 -0.0543522 -0.0526042 0.45932 -0.0548475 -0.0551963 0.459526 -0.0550897 -0.0515759 0.45666 -0.0555158 -0.0501705 0.456617 -0.0552627 -0.0550425 0.457609 -0.0550901 -0.0558726 0.456024 -0.0583345 0.0131347 0.451567 -0.0592659 0.0343387 0.452207 -0.0591148 0.0308831 0.45498 -0.0590687 0.0321942 0.452864 -0.0589592 0.0273147 0.451345 -0.0595201 0.0404185 0.451149 -0.0597064 0.0453588 0.450463 -0.0597741 0.0464928 0.449591 -0.0597604 0.0456698 0.456738 -0.0587738 0.048828 0.453218 -0.0586927 0.056548 0.450962 -0.0591572 0.0558661 0.449526 -0.0591598 0.0562894 0.44978 -0.0591585 0.0562468 0.44721 -0.0564903 0.0640582 0.447433 -0.0576614 0.0613936 0.447513 -0.0579757 0.0605551 0.447862 -0.058947 0.057341 0.474712 -0.0493107 -0.0333263 0.478458 -0.0353391 -0.0484079 0.479491 -0.0372898 -0.0399598 0.47737 -0.0385364 -0.049856 0.476128 -0.0412427 -0.0512416 0.481172 -0.0349983 -0.0300983 0.482929 -0.0298419 -0.0174888 0.473949 -0.0481477 -0.0432032 0.475597 -0.0459369 -0.0426757 0.477076 -0.0434008 -0.0419567 0.478378 -0.0405224 -0.0410507 0.48022 -0.0386687 -0.0310405 0.480688 -0.0396169 -0.0218695 0.481669 -0.0358926 -0.0212189 0.481935 -0.0364974 -0.0121564 0.483351 -0.0296875 -0.00583 0.479777 -0.0435451 -0.0128813 0.477047 -0.0487834 -0.0133738 0.477047 -0.0492248 -0.00352157 0.473691 -0.0529205 -0.00375484 0.472132 -0.0500558 -0.0435309 0.476331 -0.0472164 -0.0329758 0.479091 -0.0419203 -0.0318333 0.480929 -0.040254 -0.0125486 0.482006 -0.0369105 -0.00296792 0.468799 -0.0511988 0.0521352 0.476355 -0.0495505 0.0164239 0.475641 -0.049369 0.0265404 0.472862 -0.0510106 0.0368269 0.477744 -0.04349 0.0358596 0.474064 -0.0482862 0.0417 0.474659 -0.0487974 0.0366771 0.470626 -0.035043 0.0674112 0.472834 -0.0368635 0.0623035 0.469559 -0.041957 0.0648711 0.474956 -0.0399988 0.0542467 0.476531 -0.0422183 0.0453482 0.471759 -0.0453546 0.0561787 0.471675 -0.0293721 0.0671754 0.471214 -0.0329017 0.0672052 0.472986 -0.0325477 0.0640494 0.471505 -0.0350268 0.0659014 0.475347 -0.0357084 0.0568843 0.473979 -0.038529 0.058398 0.471561 -0.0307949 0.0671486 0.473851 -0.0293996 0.0630172 0.474252 -0.0341819 0.0606056 0.477427 -0.0340321 0.0514017 0.476289 -0.0370912 0.052931 0.477106 -0.0382677 0.0487648 0.478221 -0.0351074 0.0474393 0.454361 -0.0593511 0.0422428 0.457255 -0.0588494 0.0437584 0.45398 -0.059426 0.0472608 0.466862 -0.0563655 -0.00410557 0.469454 -0.0554581 -0.00398447 0.468427 -0.0560584 0.0156953 0.471975 -0.0533221 0.0264663 0.473392 -0.0475687 0.0466503 0.45034 -0.0585556 0.0585388 0.452779 -0.0575256 0.0607977 0.452141 -0.0558527 0.0647807 0.449801 -0.0572081 0.0623842 0.449022 -0.0554893 0.0659097 0.447431 -0.0547563 0.0671863 0.454359 -0.0542627 0.0667825 0.458111 -0.0562152 0.0597525 0.455115 -0.0561995 0.0626986 0.45569 -0.0576025 0.0583292 0.458764 -0.0572409 0.0550309 0.456206 -0.0584294 0.0537055 0.460016 -0.0580298 0.0449764 0.458149 -0.0587344 0.0335378 0.454769 -0.0584798 0.016336 0.455929 -0.0581102 0.00787131 0.455286 -0.0536292 0.0673445 0.460463 -0.0545826 0.0608058 0.457389 -0.0546236 0.0642112 0.459401 -0.0577887 0.0500847 0.461114 -0.0581105 0.034642 0.46356 -0.0482158 0.0674118 0.460998 -0.0504666 0.0674674 0.461759 -0.0509111 0.0659953 0.463837 -0.0488409 0.0662735 0.464897 -0.0507344 0.0617964 0.462728 -0.0527464 0.0614853 0.465101 -0.0555276 0.046565 0.467413 -0.0538886 0.0469549 0.466409 -0.056046 0.0361506 0.463868 -0.0572106 0.0355103 0.462885 -0.0577305 0.0146759 0.464933 -0.0571958 0.0252463 0.465817 -0.0570214 0.015248 0.467523 -0.0561586 0.0258146 0.466656 -0.053193 0.052058 0.465825 -0.0521684 0.0570285 0.467939 -0.0500697 0.0570447 0.460678 -0.0566012 -0.0225299 0.454438 -0.0553014 -0.0560443 0.464675 -0.0533165 -0.0532789 0.46554 -0.0541764 -0.0431704 0.466257 -0.0548431 -0.03314 0.463886 -0.0561337 -0.0229913 0.461063 -0.054485 -0.05453 0.464308 -0.0534647 -0.0533975 0.466748 -0.0554192 -0.0233161 0.463899 -0.0570293 -0.00423299 0.469861 -0.0548693 0.0262174 0.468748 -0.0546249 0.0365748 0.470894 -0.0529488 0.0367961 0.469568 -0.0520113 0.0470901 0.472631 -0.0466027 0.0514905 0.471562 -0.0499035 0.046984 0.469138 -0.0507865 -0.0521055 0.471386 -0.048797 -0.051698 0.470945 -0.0525826 -0.0335708 0.471496 -0.0532904 -0.0235905 0.472925 -0.0510859 -0.0335269 0.473462 -0.0518667 -0.0235589 0.473719 -0.052469 -0.0136492 0.476812 -0.0481319 -0.023189 0.479547 -0.0428891 -0.0224135 0.481569 -0.0373565 0.0157151 0.456823 -0.0575699 -0.00450268 0.459619 -0.0581729 0.0139725 0.462072 -0.0579757 0.0245018 0.462634 -0.0569146 0.0459086 0.46195 -0.0565093 0.0510395 0.461229 -0.0557775 0.0560274 0.464371 -0.0549691 0.0516958 0.463586 -0.0540775 0.0566924 0.459607 -0.0528471 0.065312 0.456137 -0.056449 -0.0301777 0.457128 -0.0568065 -0.021926 0.460726 -0.0570308 -0.0133845 0.46055 -0.0574355 -0.00436607 0.464029 -0.0566035 -0.0135587 0.466956 -0.0559252 -0.0136681 0.46952 -0.0550093 -0.0137168 0.471712 -0.0543137 -0.00386844 0.470743 -0.0548471 0.0160271 0.473385 -0.0532287 0.00619155 0.476818 -0.049483 0.00640137 0.479641 -0.0442153 0.0064465 0.479271 -0.0442752 0.0162429 0.478652 -0.0440864 0.0260821 0.479024 -0.0403727 0.035198 0.477178 -0.0429584 0.040659 0.478465 -0.0398867 0.039861 0.467949 -0.0530567 -0.0435328 0.470139 -0.0516858 -0.0436464 0.468734 -0.0538308 -0.0334465 0.469274 -0.0544701 -0.0235126 0.479806 -0.0439709 -0.00326268 0.480977 -0.0406724 -0.00312011 0.4805 -0.0410265 0.0160226 0.480995 -0.0373247 0.0251007 0.47991 -0.0408949 0.0256567 0.48012 -0.0369351 0.0343686 0.478931 -0.0359373 0.0432543 0.477827 -0.0391973 0.0443982 0.475797 -0.0412356 0.0498879 0.466962 -0.0485661 0.0617508 0.470745 -0.0438071 0.0606627 0.465835 -0.0466529 0.0661649 0.465807 -0.0456066 0.0673434 0.431303 0.0196 0.081235 0.43306 -0.026157 0.081235 0.430808 0.0238308 0.081235 0.43141 0.0249318 0.081235 0.43066 0.022 0.081235 0.430502 0.0213595 0.081235 0.430817 0.0201448 0.081235 0.443086 0.0216872 0.081235 0.435381 -0.0147216 0.081235 0.44026 0.022 0.081235 0.442652 0.0154601 0.081235 0.43786 0.017843 0.081235 0.442539 0.0229195 0.081235 0.439617 0.0244 0.081235 0.442427 0.0239 0.081235 0.442427 0.0294574 0.081235 0.43786 0.0261569 0.081235 0.43546 0.0268 0.081235 0.437564 0.0294574 0.081235 0.435567 0.0278145 0.081235 0.43306 0.0261569 0.081235 0.433327 0.0265218 0.081235 0.43066 -0.022 0.081235 0.430498 -0.0226146 0.081235 0.430808 -0.0238309 0.081235 0.432288 -0.0181353 0.081235 0.431303 -0.0196 0.081235 0.439617 0.0196 0.081235 0.430817 -0.0201449 0.081235 0.443914 0.0207848 0.081235 0.445067 0.0201256 0.081235 0.442539 0.00391955 0.081235 0.442427 0.00489993 0.081235 0.442427 0.0141 0.081235 0.445446 0.0179875 0.081235 0.446427 0.0199 0.081235 0.446827 0.0199 0.0812351 0.446427 0.0181 0.0812351 0.433327 -0.0265219 0.081235 0.43786 -0.026157 0.081235 0.439617 -0.0244 0.081235 0.442427 -0.0239 0.081235 0.442652 -0.0225399 0.081235 0.44026 -0.022 0.081235 0.442652 -0.00353989 0.081235 0.438027 -0.00600004 0.081235 0.431426 0.019047 0.081235 0.432288 0.0181352 0.081235 0.43306 0.017843 0.081235 0.446427 -0.0199 0.081235 0.446827 -0.0181 0.0812351 0.445067 -0.0178744 0.081235 0.439617 -0.0196 0.081235 0.43786 -0.0178431 0.081235 0.442539 -0.0150805 0.081235 0.446427 -0.000900043 0.0812351 0.446427 0.000899959 0.0812351 0.445067 0.00112557 0.081235 0.445446 -0.00101247 0.081235 0.444214 -0.00155905 0.081235 0.442427 -0.00490004 0.081235 0.437351 -0.010557 0.081235 0.43652 -0.0127119 0.081235 0.437351 0.0105569 0.081235 0.446648 -0.0598034 0.0467066 0.445391 -0.0598332 0.0475702 0.444516 -0.0598571 0.0486647 0.443999 -0.059861 0.0491652 0.444282 -0.0598608 0.0491099 0.443821 -0.0598322 0.0508996 0.444111 -0.0596898 0.052997 0.443388 -0.0593998 0.0551577 0.445837 -0.0593677 0.0553426 0.447051 -0.0592418 0.0560136 0.447995 -0.0591896 0.0562701 0.445439 -0.0546301 0.0673888 0.442521 -0.0545399 0.0675329 0.444537 -0.0542735 0.0679441 0.442427 -0.0506881 0.0725551 0.442356 -0.0502252 0.0730481 0.442427 -0.0502251 0.073048 0.442331 -0.0474141 0.0756508 0.442427 -0.0454209 0.0771384 0.442327 -0.0454212 0.0771387 0.442327 -0.0434329 0.0783593 0.442427 -0.0431835 0.0784949 0.442325 -0.0401624 0.0798438 0.443299 -0.0406223 0.0796724 0.442327 -0.0403724 0.079767 0.442655 -0.0418176 0.0791708 0.444201 -0.036528 0.0808046 0.445258 -0.0370425 0.0807084 0.445435 -0.0392011 0.0801643 0.446427 -0.0390729 0.0802034 0.446427 -0.0372219 0.0806718 0.446832 -0.0390728 0.0802031 0.442033 -0.037481 0.0806166 0.441121 -0.0345904 0.0810656 0.442427 -0.0294575 0.081235 0.482855 -4.19898e-08 0.0351274 0.48135 -0.015535 0.0416962 0.481688 -0.0272251 0.0341403 0.481576 -0.0293804 0.0332038 0.479086 -0.0294635 0.0472479 0.477484 -0.0294452 0.0533095 0.476748 -0.0153292 0.0585887 0.475739 -0.0294228 0.0585106 0.471495 -0.021804 0.0685867 0.472213 -0.0161757 0.068071 0.471933 -0.022731 0.0677443 0.472122 -0.0237899 0.0672579 0.472448 -0.0293817 0.0658068 0.470592 -0.0208115 0.0700704 0.47036 -0.0177947 0.0707186 0.469382 -0.020157 0.0717736 0.469025 -0.0181235 0.0724122 0.468053 -0.0199382 0.0733659 0.467545 -0.0181343 0.0740689 0.465469 -0.0199356 0.0758643 0.464341 -0.0181313 0.0768744 0.465011 -0.019935 0.0762383 0.463874 -0.0181305 0.0772055 0.456611 -0.0181122 0.0804206 0.457132 -0.0199144 0.0802467 0.458947 -0.0199198 0.0796676 0.461288 -0.0181249 0.0787334 0.462489 -0.0181278 0.0780851 0.46242 -0.0199298 0.0780256 0.462976 -0.0199312 0.0776864 0.472421 -0.00272018 0.0685608 0.472911 -0.00376896 0.0677039 0.473067 -0.00460274 0.0674053 0.472796 -0.0139241 0.0672906 0.472778 -0.0143105 0.0672863 0.472614 -0.0152708 0.0674811 0.471551 -0.00177625 0.0699536 0.470349 -0.00112402 0.0716702 0.469011 -0.000902039 0.0733384 0.462746 -4.87505e-08 0.0785055 0.461783 -0.000901472 0.0789916 0.4589 -0.00090119 0.0800836 0.455625 -0.000900756 0.0807992 0.451258 -4.22847e-08 0.0811806 0.473079 -0.00497629 0.0673726 0.47695 -5.0691e-08 0.0590214 0.473241 -0.0151901 0.0663763 0.479382 -0.0154441 0.050284 0.479624 -3.17285e-08 0.0506564 0.482759 -0.00843211 0.0350696 0.482636 -0.0125096 0.0349991 0.472108 0.0243207 0.0671938 0.471233 0.0172772 0.0695094 0.471842 0.0224804 0.067931 0.472447 0.0293809 0.0658086 0.478682 0.0294764 0.0489203 0.478422 0.0294668 0.0499441 0.48044 0.0294591 0.0406033 0.481587 0.0290866 0.0333681 0.482115 0.0221441 0.0346939 0.47893 0.0294851 0.0478981 0.482636 0.0125093 0.0349992 0.482509 0.0155915 0.034926 0.446827 -4.19898e-08 0.081235 0.455026 0.000900593 0.0808833 0.455402 -4.03447e-08 0.0808323 0.459239 -4.54334e-08 0.0799812 0.456799 0.000900829 0.0805956 0.461377 0.000901347 0.0791768 0.465918 -3.67318e-08 0.0763731 0.467918 0.000901943 0.074532 0.469011 0.00090195 0.0733382 0.468749 -4.22576e-08 0.0736399 0.470855 0.00133556 0.0709731 0.472557 0.0154442 0.0675616 0.473416 -4.51059e-08 0.0668529 0.472975 0.0040089 0.0675854 0.471241 -3.3084e-08 0.0704252 0.471255 0.0214692 0.0690045 0.469021 0.0200529 0.0722317 0.468053 0.0199381 0.0733659 0.460132 0.0181224 0.0792661 0.463037 0.0199313 0.0776479 0.465303 0.0181324 0.0761343 0.467839 0.0181344 0.0737595 0.460409 0.0199242 0.079069 0.458948 0.0199197 0.0796672 0.457276 0.0181132 0.0802509 0.457595 0.0199156 0.080115 0.452056 0.0181021 0.0811097 0.473004 0.00830257 0.0673477 0.473242 0.01519 0.0663736 0.47675 0.0153291 0.058585 0.479383 0.0154439 0.0502793 0.481351 0.0155348 0.0416907 0.481643 -4.17149e-08 0.042004 0.444253 0.0541031 0.0682018 0.445312 0.0545945 0.067445 0.446319 0.0547542 0.0671901 0.446427 0.0547557 0.0671877 0.442484 0.0539521 0.0684276 0.442427 0.0506878 0.0725553 0.443142 0.0408385 0.0795877 0.442582 0.0420516 0.0790629 0.442327 0.0406728 0.0796529 0.442427 0.0458439 0.0768455 0.442327 0.0434328 0.0783593 0.442427 0.0431834 0.0784949 0.446832 0.0390727 0.0802031 0.442327 0.0403723 0.079767 0.444047 0.03988 0.0799431 0.442027 0.0374537 0.0806226 0.443316 0.0356973 0.0809353 0.441506 0.0355759 0.0809519 0.442655 0.0344869 0.0810753 0.447186 0.0563345 0.0643719 0.447251 0.0567563 0.0635038 0.443156 0.0588426 0.0577542 0.443394 0.0594115 0.0550879 0.443714 0.0597831 0.0518475 0.443954 0.0597374 0.0524747 0.4441 0.0598605 0.0495567 0.445988 0.0598174 0.0470894 0.447149 0.0597951 0.0464987 0.447674 0.0597889 0.0463449 0.44852 0.0597839 0.0462225 0.477889 0.0471081 0.0163766 0.479807 0.043968 -0.00326255 0.461228 0.0383375 0.0765326 0.471563 0.0307926 0.0671466 0.471676 0.0293717 0.0671746 0.450563 0.0595087 0.0399045 0.454685 0.0585027 0.0168623 0.456025 0.0583344 0.0131349 0.455861 0.0581361 0.00846685 0.456661 0.0555156 -0.0501708 0.457128 0.0568064 -0.0219261 0.456798 0.0570528 -0.0163451 0.454379 0.0552152 -0.0571664 0.463521 0.0537581 -0.0536558 0.464676 0.0533159 -0.0532791 0.468426 0.0512975 -0.0522605 0.47014 0.0516849 -0.0436464 0.47395 0.0481462 -0.0432029 0.472563 0.0474624 -0.0515357 0.476604 0.0399689 -0.0512224 0.47795 0.0348515 -0.0511886 0.478459 0.0353358 -0.0484063 0.478018 0.0344809 -0.0511877 0.478858 0.0327572 -0.0485548 0.478629 0.0309829 -0.0505467 0.47853 0.030424 -0.0511845 0.478552 0.0303937 -0.0511002 0.480409 0.0336899 -0.0386822 0.479492 0.0372864 -0.0399586 0.479978 0.0314869 -0.0434567 0.481173 0.0349941 -0.0300973 0.483224 0.0297476 -0.0107768 0.4834 0.0295915 0.00349467 0.483405 0.0296391 -0.00137032 0.481665 0.0344421 0.024799 0.482409 0.0328317 0.0182822 0.482611 0.0320035 0.0171831 0.481571 0.0373523 0.0157148 0.482816 0.0310352 0.0162193 0.483021 0.0299323 0.015404 0.483089 0.0295327 0.0151682 0.480121 0.0369311 0.0343676 0.481492 0.0331128 0.0293778 0.481474 0.0294081 0.0330524 0.475703 0.0294224 0.0586066 0.476228 0.0294265 0.0571689 0.475487 0.0314188 0.0586575 0.477389 0.0294377 0.0536278 0.477428 0.0340287 0.0513999 0.470258 0.0356332 0.0677578 0.455423 0.0386873 0.0792184 0.457113 0.0390794 0.0784786 0.457308 0.0372396 0.0789466 0.459904 0.0390843 0.0770927 0.446988 0.0390726 0.0802029 0.447408 0.037222 0.0806689 0.451238 0.0372272 0.0804696 0.451196 0.0372271 0.0804741 0.451038 0.0390758 0.0800056 0.451014 0.0372268 0.0804926 0.448792 0.0390736 0.0801619 0.44802 0.0379829 0.0804859 0.447527 0.0390728 0.0801984 0.466254 0.0414601 0.0702359 0.466596 0.0373381 0.0720678 0.460093 0.0372468 0.0775923 0.460736 0.0372483 0.0772083 0.462541 0.0390877 0.0752784 0.464636 0.0396635 0.0731245 0.465575 0.0404318 0.0716966 0.465836 0.0466514 0.0661647 0.46818 0.0398035 0.068708 0.449801 0.0572079 0.0623844 0.45034 0.0585554 0.058539 0.447815 0.0588427 0.057754 0.447579 0.0582098 0.0598829 0.447995 0.0591895 0.0562701 0.453218 0.0586925 0.0565483 0.4688 0.0511975 0.0521352 0.471564 0.0499019 0.0469839 0.469569 0.05201 0.0470901 0.470896 0.0529476 0.0367962 0.469561 0.041955 0.0648703 0.466963 0.0485646 0.0617507 0.470746 0.0438051 0.0606621 0.467941 0.0500682 0.0570446 0.474065 0.0482843 0.0416998 0.471506 0.0350245 0.0658998 0.47398 0.0385264 0.0583968 0.47176 0.0453526 0.0561781 0.475798 0.0412328 0.049887 0.472632 0.0466007 0.05149 0.473393 0.0475668 0.04665 0.476533 0.0422156 0.0453474 0.472836 0.036861 0.062302 0.474253 0.0341791 0.0606038 0.475349 0.0357055 0.0568827 0.474957 0.0399961 0.0542456 0.472988 0.0325451 0.0640475 0.47391 0.0293991 0.0628895 0.476526 0.0327705 0.0551395 0.47629 0.0370882 0.0529296 0.477107 0.0382646 0.0487636 0.478222 0.0351039 0.0474378 0.478466 0.0398835 0.0398602 0.479272 0.0442724 0.0162428 0.478653 0.0440835 0.0260818 0.475643 0.0493672 0.0265404 0.476081 0.0414505 -0.051089 0.474575 0.0444906 -0.0513356 0.479025 0.0403693 0.0351973 0.477745 0.0434872 0.0358591 0.478932 0.0359336 0.043253 0.480996 0.0373206 0.0251 0.479912 0.0408914 0.0256562 0.480501 0.041023 0.0160224 0.481734 0.0300721 -0.0319957 0.480221 0.0386652 -0.0310396 0.479092 0.0419174 -0.0318326 0.479548 0.0428863 -0.0224131 0.476332 0.0472146 -0.0329754 0.474713 0.0493093 -0.0333261 0.477077 0.0433985 -0.041956 0.477371 0.0385336 -0.0498548 0.479366 0.0329949 -0.0457953 0.469083 0.0558131 0.00578637 0.477048 0.049223 -0.00352148 0.469455 0.0554576 -0.00398441 0.469521 0.0550087 -0.0137168 0.469275 0.0544696 -0.0235127 0.466863 0.0563651 -0.00410551 0.473692 0.0529194 -0.00375477 0.473386 0.0532277 0.00619164 0.475455 0.0512408 -0.00364022 0.47372 0.052468 -0.0136491 0.45962 0.0581727 0.0139727 0.456823 0.0575699 -0.00450266 0.457053 0.0571924 -0.0131417 0.46403 0.0566033 -0.0135587 0.456849 0.0559744 -0.0404429 0.472926 0.0510848 -0.0335269 0.466749 0.0554188 -0.0233162 0.463887 0.0561334 -0.0229914 0.459994 0.0556458 -0.0416335 0.480458 0.0302322 -0.0413597 0.478379 0.0405195 -0.0410498 0.475598 0.045935 -0.0426753 0.472134 0.0500547 -0.0435307 0.470946 0.0525818 -0.0335708 0.468735 0.0538302 -0.0334466 0.46795 0.0530561 -0.0435329 0.466258 0.0548426 -0.0331402 0.465541 0.054176 -0.0431706 0.463488 0.0556171 -0.0326381 0.462893 0.055042 -0.0425412 0.459527 0.0550895 -0.0515762 0.462196 0.0543518 -0.0526045 0.459004 0.0549006 -0.0553201 0.456617 0.0552626 -0.0550428 0.457391 0.0551129 -0.0559599 0.447324 0.0547561 0.0671872 0.449022 0.0554891 0.0659099 0.450868 0.054625 0.0671806 0.452141 0.0558524 0.0647811 0.456739 0.0587735 0.0488283 0.456207 0.0584291 0.0537059 0.45278 0.0575253 0.060798 0.453514 0.0541746 0.0672555 0.452204 0.059115 0.0308875 0.454361 0.059351 0.0422431 0.451552 0.0592691 0.0344171 0.453981 0.0594259 0.0472611 0.451345 0.05952 0.0404187 0.451149 0.0597063 0.0453589 0.458856 0.0519149 0.0674692 0.45739 0.054623 0.0642116 0.459608 0.0528463 0.0653124 0.458765 0.0572404 0.0550313 0.460464 0.0545818 0.0608061 0.46123 0.0557768 0.0560277 0.462635 0.056914 0.0459089 0.460016 0.0580294 0.0449767 0.461115 0.0581101 0.0346424 0.464934 0.0571954 0.0252465 0.46641 0.0560453 0.0361509 0.463869 0.0572101 0.0355106 0.461951 0.0565087 0.0510398 0.46176 0.0509101 0.0659955 0.461433 0.050128 0.0674615 0.463828 0.0479402 0.067404 0.462729 0.0527454 0.0614856 0.463587 0.0540765 0.0566926 0.464372 0.0549683 0.051696 0.465102 0.0555268 0.0465652 0.477828 0.0391941 0.0443971 0.477179 0.0429556 0.0406583 0.47466 0.0487956 0.0366769 0.472863 0.0510091 0.0368269 0.468749 0.054624 0.036575 0.467414 0.0538876 0.046955 0.466657 0.0531919 0.0520581 0.465826 0.0521672 0.0570286 0.464898 0.0507332 0.0617964 0.463838 0.0488397 0.0662736 0.457256 0.0588491 0.0437587 0.45498 0.0590686 0.0321944 0.458149 0.0587342 0.0335381 0.4639 0.057029 -0.00423295 0.466957 0.0559248 -0.0136681 0.473463 0.0518657 -0.0235589 0.477049 0.0487816 -0.0133736 0.476813 0.0481301 -0.0231888 0.479778 0.0435422 -0.0128811 0.48093 0.0402504 -0.0125483 0.480689 0.0396134 -0.0218689 0.48167 0.0358883 -0.0212181 0.455451 0.0535677 0.0673536 0.45436 0.0542622 0.0667829 0.456268 0.0532392 0.0673929 0.455115 0.0561991 0.062699 0.455691 0.0576021 0.0583296 0.458112 0.0562146 0.0597529 0.459402 0.0577882 0.050085 0.462886 0.0577302 0.0146761 0.465818 0.057021 0.0152482 0.468428 0.0560578 0.0156955 0.467524 0.0561579 0.0258149 0.47281 0.0533777 0.0162538 0.469862 0.0548684 0.0262176 0.471976 0.053321 0.0264664 0.474669 0.051625 0.0163839 0.476356 0.0495487 0.0164239 0.478497 0.046812 -0.0033961 0.480978 0.0406689 -0.00311996 0.482007 0.0369061 -0.00296775 0.481936 0.0364931 -0.012156 0.481361 0.0297528 0.0326981 0.481559 0.0298866 0.0328897 0.481506 0.0316933 0.0313425 0.481296 0.0329038 0.0292607 0.481542 0.0340358 0.0271306 0.481895 0.0343053 0.0221051 0.482414 0.0318195 0.0173042 0.482618 0.0308736 0.0163611 0.4817 0.0340695 0.0221253 0.482221 0.0334932 0.019479 0.482024 0.0332751 0.0195516 0.482213 0.0326288 0.0183801 0.482347 0.0321007 0.0176433 0.483072 0.0296347 0.0152257 0.479066 0.0264077 -0.0504222 0.479168 0.0260311 -0.0501387 0.479652 0.0248203 -0.0484791 0.480002 0.0244973 -0.0469563 0.480117 0.0245201 -0.0463758 0.485009 0.00446528 0.0132254 0.483522 0.0266317 0.0141352 0.483385 0.0276198 0.0143714 0.482883 0.0298529 -0.0183061 0.483608 0.0259703 0.0140367 0.483283 0.029723 -0.00881435 0.484242 0.0230848 -0.00137321 0.482072 0.0232775 -0.0352196 0.482594 0.029922 -0.0226976 0.480403 0.0288185 -0.0425184 0.481518 0.00802599 -0.0438387 0.482989 -4.22848e-08 -0.0355921 0.484412 -4.07941e-08 -0.0231367 0.482899 0.00803667 -0.0354528 0.479668 0.0153952 -0.0511827 0.483211 0.0297525 -0.0111608 0.48124 0.0158642 -0.0436875 0.48259 0.0158653 -0.0353318 0.483686 0.023189 -0.0183601 0.484284 0.015832 -0.0184159 0.484871 0.0157719 -0.00137793 0.484649 0.00803363 -0.0184776 0.485256 0.00800952 -0.00138337 0.465715 -0.052374 -0.0533471 0.470395 -0.0491681 -0.0522136 0.466953 -0.0450938 -0.052992 0.467605 -0.0430452 -0.0528196 0.467827 -0.0361823 -0.0527642 0.467827 -0.0213178 -0.0527642 0.47224 -0.0471629 -0.0519296 0.467827 0.0147796 -0.0527642 0.467827 0.0213177 -0.0527642 0.467827 0.0361822 -0.0527642 0.467754 0.0421371 -0.0527822 0.467273 0.0442638 -0.0529059 0.467178 0.044535 -0.0529313 0.469619 0.0498579 -0.0523609 0.463029 -0.0534589 -0.0542327 0.463301 -0.0533674 -0.0541367 0.459197 -0.0543952 -0.0557003 0.457015 -0.0546638 -0.0565893 0.434327 -0.0477008 -0.061565 0.438032 -0.0504816 -0.0615169 0.436255 -0.054589 -0.0615578 0.43607 -0.0548195 -0.0615596 0.434327 -0.0582175 -0.061565 0.449869 -0.0545228 -0.0593331 0.449869 -0.0514 -0.0593327 0.442468 -0.0514 -0.0611312 0.442469 -0.0542269 -0.0611312 0.442327 -0.0514 -0.0611513 0.437023 -0.0541729 -0.0615458 0.43674 -0.0542592 -0.0615511 0.475473 0.038331 -0.0516445 0.474187 0.044253 -0.0517277 0.476161 0.0398095 -0.051614 0.467827 -0.0037204 -0.0527642 0.477026 -0.0368659 -0.051588 0.47515 -0.0387614 -0.051662 0.476582 -0.0385013 -0.0515998 0.477483 -0.0347418 -0.0515789 0.466368 0.0462395 -0.0531554 0.465081 0.0479798 -0.0535421 0.461575 0.0505023 -0.0547677 0.449869 0.0514 -0.0593327 0.457327 0.0514 -0.0564615 0.454565 0.0547171 -0.0575861 0.435935 0.0550784 -0.0615608 0.434327 0.0582174 -0.061565 0.435824 0.0582181 -0.0615616 0.437664 0.050308 -0.0615294 0.438693 0.0507512 -0.0614881 0.434902 0.0483246 -0.0615646 0.435835 0.0491525 -0.0615614 0.442468 0.0514 -0.0611312 0.441798 0.0542092 -0.0612213 0.439698 0.0510655 -0.061427 0.43757 0.0551886 -0.0574543 0.449178 0.054993 -0.0591042 0.448704 0.0561619 -0.0367512 0.456596 0.0568136 -0.0218244 0.446617 0.0562164 -0.0355012 0.449279 0.0558832 -0.0431345 0.449652 0.0559108 -0.0425003 0.456202 0.0564955 -0.0291091 0.449889 0.0560795 -0.0386378 0.445169 0.0562258 -0.0352868 0.444344 0.0568649 -0.0206494 0.456872 0.0574359 -0.0075715 0.456567 0.0577966 0.000689669 0.44372 0.0557985 -0.0450724 0.445169 0.0557892 -0.0452868 0.445385 0.0557894 -0.0452821 0.44555 0.0593267 0.0357366 0.444417 0.0597491 0.0454095 0.4402 0.0560319 -0.0397278 0.439893 0.0559699 -0.0411477 0.440448 0.0559355 -0.0419357 0.43796 0.0554266 -0.0535905 0.447654 0.0578563 0.00205898 0.452605 0.0590205 0.0287229 0.445867 0.0592086 0.0330303 0.436562 0.0586932 -0.0576096 0.438819 0.0594626 -0.0414851 0.445354 0.0583135 -0.0102363 0.444225 0.0580433 -0.0163885 0.438911 0.0569689 -0.0410036 0.44192 0.0615229 0.0610469 0.441994 0.0591891 0.0600329 0.442399 0.0603977 0.0551627 0.443423 0.0607481 0.0452534 0.446756 0.0591261 0.0082057 0.446759 0.0616149 0.00790689 0.446762 0.0615876 0.00728067 0.441484 0.0547798 0.0689507 0.441379 0.0553655 0.0724478 0.441332 0.0521755 0.0760604 0.441327 0.0485095 0.079235 0.44192 0.0588361 0.0610464 0.441718 0.0603173 0.0641557 0.441327 0.0407205 0.0833533 0.441327 0.0439157 0.079235 0.441046 0.0378617 0.0815995 0.440958 0.0374497 0.0841733 0.440856 0.0370296 0.0817758 0.438778 0.0324483 0.0822169 0.439043 0.0328513 0.0846766 0.434997 0.0286365 0.082235 0.4329 0.0274262 0.084735 0.4329 0.0274262 0.082235 0.481918 0.0221186 0.0344655 0.48265 0.0024863 0.0348918 0.482602 0.00646329 0.0348631 0.481882 0.0248437 0.0345597 0.482345 0.0187297 0.0348296 0.482148 0.0187103 0.0346006 0.481685 0.0248128 0.0343319 0.481686 0.0272542 0.0341325 0.48156 0.0262254 0.0341533 0.48149 0.0271616 0.0339179 0.429889 0.0197737 0.082235 0.429889 0.0197737 0.084735 0.430619 0.0184564 0.082235 0.429506 0.0227374 0.084735 0.429877 0.024197 0.082235 0.4306 0.0255181 0.082235 0.4306 0.0255181 0.084735 0.436394 0.0102667 0.082235 0.436394 0.0102667 0.084735 0.43455 0.014166 0.084735 0.43455 0.014166 0.082235 0.43322 0.015871 0.082235 0.437027 0.00599996 0.082235 0.43455 -0.0141661 0.082235 0.436394 -0.0102668 0.082235 0.431629 -0.0266177 0.082235 0.4306 -0.0255182 0.082235 0.429877 -0.0241971 0.082235 0.429506 -0.0227375 0.084735 0.429506 -0.0227375 0.082235 0.429889 -0.0197738 0.082235 0.431654 -0.0173624 0.084735 0.431654 -0.0173624 0.082235 0.435579 -0.0290609 0.084735 0.438014 -0.031424 0.0847204 0.440856 -0.03703 0.0817758 0.440961 -0.0374619 0.0841711 0.441051 -0.0378883 0.0815933 0.441327 -0.0407206 0.0807044 0.481559 -0.0298818 0.0328929 0.481367 -0.0295949 0.0328007 0.481391 -0.0292875 0.0330063 0.481685 -0.024813 0.0343319 0.481385 -0.0292886 0.0329986 0.481379 -0.0293007 0.0329837 0.481491 -0.0271459 0.0339216 0.482658 -4.19928e-08 0.0348967 0.482441 -0.0124231 0.0347707 0.482509 -0.0155926 0.034926 0.482167 -0.018384 0.0346117 0.481882 -0.024844 0.0345597 0.454585 -0.0554267 -0.0535905 0.446617 -0.0557986 -0.0450724 0.445169 -0.0557893 -0.0452868 0.441633 -0.0561619 -0.0367512 0.456782 -0.0570271 -0.0169352 0.440685 -0.0559109 -0.0425003 0.4402 -0.056032 -0.0397278 0.439695 -0.0559241 -0.042198 0.449829 -0.0560867 -0.0384746 0.446483 -0.0589676 0.02751 0.447148 -0.0586634 0.0205421 0.448231 -0.0561802 -0.0363339 0.447489 -0.0562009 -0.0358579 0.447642 -0.0578441 0.00177661 0.456605 -0.0577695 6.69793e-05 0.447552 -0.0577727 0.000140989 0.456879 -0.0574166 -0.00801466 0.447153 -0.057571 -0.00447761 0.450563 -0.0595085 0.0399018 0.449809 -0.0550226 -0.0588932 0.454379 -0.0552153 -0.0571664 0.441967 -0.0547055 -0.0607931 0.43757 -0.0551887 -0.0574543 0.480043 -0.000347852 -0.0511827 0.480044 -4.19898e-08 -0.0511828 0.482486 -4.48753e-08 -0.0388991 0.483384 -0.029588 0.0049413 0.483382 -0.0276416 0.0143742 0.484242 -0.0230837 -0.00137266 0.479457 -0.025202 -0.0492033 0.479142 -0.0261226 -0.0502137 0.480296 -0.0247598 -0.045348 0.480091 -0.0245079 -0.0465098 0.480002 -0.0244973 -0.046953 0.479791 -0.0246317 -0.0479113 0.478866 -0.0273499 -0.050898 0.478681 -0.0287208 -0.0511485 0.478613 -0.0300101 -0.0509697 0.480222 -0.0302542 -0.0427733 0.480386 -0.0289858 -0.0425223 0.482195 -0.0299993 -0.0275107 0.480497 -0.0276002 -0.0426903 0.48052 -0.0263426 -0.0432932 0.483687 -0.0231879 -0.0183598 0.482072 -0.0232764 -0.0352194 0.479171 -0.0233282 -0.0511826 0.480767 -0.0233085 -0.0435452 0.484871 -0.0157711 -0.00137737 0.485256 -0.00800916 -0.00138281 0.484649 -0.00803327 -0.0184772 0.484768 -4.22754e-08 -0.0185508 0.485335 -4.27621e-08 -0.00571315 0.484721 -0.0128806 0.0133903 0.484285 -0.0158312 -0.0184156 0.48259 -0.0158646 -0.0353316 0.482899 -0.00803631 -0.0354527 0.48124 -0.0158635 -0.0436874 0.479664 -0.0154866 -0.0511827 0.48289 -0.0294134 0.0153366 0.483037 -0.0298377 0.0153455 0.482823 -0.0298005 0.015566 0.481469 -0.0342038 0.0247694 0.481765 -0.0344572 0.0234768 0.482112 -0.0338175 0.0202592 0.482326 -0.0331395 0.0187922 0.482286 -0.0323486 0.0179719 0.482344 -0.0321138 0.0176604 0.481304 -0.0332469 0.0285769 0.481505 -0.03171 0.0313249 0.481296 -0.0329143 0.0292404 0.441327 -0.0477851 0.0797593 0.441327 -0.0485095 0.079235 0.441327 -0.04661 0.0805437 0.441327 -0.0439157 0.079235 0.441462 -0.057411 0.0695574 0.44178 -0.0607499 0.0631324 0.442113 -0.062275 0.0585001 0.442392 -0.0603856 0.055235 0.441343 -0.0535197 0.0746496 0.441369 -0.0516493 0.072966 0.441482 -0.0547436 0.0690043 0.446151 -0.0596625 0.020416 0.442727 -0.0632997 0.0517335 0.443423 -0.0607482 0.0452534 0.444879 -0.0602056 0.0328238 0.444866 -0.0627054 0.0329359 0.446757 -0.0616239 0.00811347 0.446762 -0.0615877 0.00728067 0.446159 -0.0585701 -0.00441111 0.445303 -0.0582999 -0.0105472 0.445298 -0.0608116 -0.0105784 0.44144 -0.0600046 -0.0290893 0.438838 -0.0594669 -0.0413869 0.436319 -0.0582181 -0.0610894 0.436935 -0.0589234 -0.0537989 0.437479 -0.0565988 -0.0495312 0.437479 -0.0591104 -0.0495312 0.481682 0.0248435 0.0343302 0.481389 0.0289828 0.0331593 0.481157 0.0273769 0.0338498 0.481157 0.0297528 0.0326981 0.481309 0.0315169 0.0311845 0.481295 0.0323551 0.0301402 0.481347 0.0338061 0.0270581 0.481469 0.0342037 0.0247694 0.481157 0.0321008 0.0176434 0.481843 0.0337768 0.0208773 0.483177 0.0276069 0.0145748 0.483387 0.0276082 0.014368 0.483324 0.0265706 0.0143231 0.483409 0.0259237 0.0142264 0.483461 0.0255155 0.0141889 0.482823 0.0297973 0.0155641 0.482891 0.0294094 0.0153346 0.481157 0.0297973 0.0155641 0.483189 0.0275261 0.0145508 0.484525 0.0127866 0.0135781 0.483747 0.0229773 0.0140244 0.483659 0.0255529 0.0139984 0.484678 0.013683 0.0134149 0.476827 0.0254591 -0.048635 0.476827 0.02875 -0.048835 0.476827 0.0298 -0.0485536 0.476827 0.03085 -0.046735 0.476827 0.0305686 -0.045685 0.476827 0.0298 -0.0449163 0.476827 0.02875 -0.044635 0.476827 0.0254591 -0.044835 0.467827 -0.0409 -0.0527642 0.467827 0.00372029 -0.0527642 0.467827 0.0409 -0.0636624 0.467827 -0.0409 -0.0636624 0.467827 -0.0147797 -0.0527642 0.467827 0.0409 -0.0527642 0.463535 0.0493679 -0.0540555 0.459474 0.051178 -0.0555885 0.438309 0.0506007 -0.0636624 0.441843 0.0513888 -0.0612155 0.442327 0.0514 -0.0636624 0.442327 0.0514 -0.0611513 0.414908 0.01495 -0.061565 0.414627 0.016 -0.061565 0.407336 0.00382371 -0.061565 0.416727 -0.0139 -0.061565 0.418545 -0.01495 -0.061565 0.418827 -0.016 -0.061565 0.432476 0.0445342 -0.061565 0.427658 0.0436788 -0.061565 0.418545 0.01705 -0.061565 0.40833 -0.0111962 -0.061565 0.411148 -0.0182507 -0.061565 0.414627 -0.016 -0.061565 0.415677 -0.0178187 -0.061565 0.422085 -0.033691 -0.061565 0.417777 -0.0141814 -0.061565 0.409601 0.0150036 -0.061565 0.414908 0.01705 -0.061565 0.411245 0.0184281 -0.061565 0.413193 0.0216582 -0.061565 0.417624 0.027777 -0.061565 0.416727 0.0181 -0.061565 0.430668 0.0571738 -0.061565 0.431817 0.0579439 -0.061565 0.434327 0.0477007 -0.061565 0.428728 0.0472591 -0.061565 0.427613 -0.0435575 -0.061565 0.42871 -0.0471846 -0.061565 0.433174 -0.0582175 -0.061565 0.431815 -0.0579429 -0.061565 0.430666 -0.0571723 -0.061565 0.42934 -0.0508957 -0.061565 0.434327 0.058709 -0.0611565 0.433174 0.058709 -0.0611565 0.436438 0.0594228 -0.053765 0.436063 0.0591911 -0.0576133 0.43473 0.058709 -0.0611565 0.433525 0.059161 -0.0579328 0.43582 0.0587096 -0.0611531 0.436063 -0.0591912 -0.0576133 0.43582 -0.0587097 -0.0611531 0.434761 -0.0481807 -0.0615648 0.434902 -0.0483247 -0.0636624 0.432626 -0.0449182 -0.0636624 0.432476 -0.0445343 -0.061565 0.431827 -0.0409 -0.061565 0.43625 -0.0494627 -0.0615578 0.44016 -0.051174 -0.0613912 0.457327 -0.0514 -0.0564615 0.461345 -0.0506008 -0.0636624 0.458968 -0.051271 -0.0557925 0.460935 -0.0507607 -0.0550126 0.462923 -0.0497842 -0.0542713 0.464599 -0.0484742 -0.0536966 0.465902 -0.0469596 -0.0532912 0.447384 0.0575 0.0487669 0.446341 0.0575 0.04981 0.445959 0.0575 0.051235 0.444309 0.0575 0.051235 0.450234 0.0575 0.0537032 0.451277 0.0575 0.05266 0.452706 0.0575 0.053485 0.451659 0.0575 0.051235 0.453309 0.0575 0.051235 0.436555 0.0600014 -0.0405133 0.440911 0.0604961 -0.0291842 0.4436 0.0610292 -0.0169729 0.438964 0.0605803 -0.0272552 0.441327 0.0617511 -0.000439448 0.440865 0.0622538 0.0110751 0.445652 0.0626596 0.0203701 0.437646 0.0632505 0.0339025 0.430312 0.0388933 0.0843953 0.440025 0.0360835 0.0849197 0.431139 0.041525 0.0836045 0.440827 0.0416735 0.0835505 0.431568 0.0437363 0.0826908 0.428327 0.0322708 0.0852082 0.428327 0.0350713 0.0850376 0.437624 0.031746 0.0852204 0.439391 0.0345394 0.0850863 0.428949 0.0360731 0.0849211 0.429498 0.0370777 0.0847689 0.431821 0.046309 0.0813173 0.440827 0.0450168 0.0820505 0.440827 0.0488084 0.0796358 0.440832 0.0525285 0.0764118 0.432192 0.0528639 0.076073 0.440943 0.0574558 0.0703851 0.432533 0.0574557 0.0703853 0.441005 0.0585343 0.0686736 0.432947 0.0610044 0.0637947 0.433119 0.0617853 0.0617829 0.441706 0.0630287 0.0574455 0.442919 0.0637453 0.045235 0.434777 0.0638611 0.0491915 0.442284 0.0638248 0.0511648 0.441925 0.0634848 0.054923 0.428327 0.0294574 0.085235 0.430195 0.0258113 0.085235 0.430195 -0.0258114 0.085235 0.432687 -0.0278785 0.085235 0.416956 -0.0241246 0.085235 0.416956 0.0241245 0.085235 0.41066 0.0187 0.085235 0.422327 0.0187 0.085235 0.429424 -0.0195883 0.085235 0.42901 0.0227989 0.085235 0.43406 0.01086 0.085235 0.435915 -0.0101216 0.085235 0.43406 -0.0108601 0.085235 0.436527 -0.00600004 0.085235 0.435027 0.00599996 0.085235 0.436527 0.00599996 0.085235 0.482438 0.0124973 0.0347692 0.482441 0.0124228 0.0347707 0.442395 -0.0638554 0.0500767 0.433119 -0.0617856 0.0617824 0.43321 -0.062109 0.0608315 0.434002 -0.0635728 0.054264 0.432086 -0.0514867 0.0774104 0.432582 -0.0580531 0.0694608 0.440832 -0.0525374 0.0764031 0.432039 -0.050782 0.0780419 0.440827 -0.0507817 0.0780422 0.431861 -0.047072 0.0808418 0.440827 -0.0488085 0.0796358 0.440827 -0.0455138 0.0817791 0.428327 -0.0350714 0.0850376 0.429484 -0.0370492 0.0847738 0.439547 -0.0348767 0.0850564 0.430496 -0.039384 0.0842711 0.430791 -0.0402663 0.0840213 0.43158 -0.0438219 0.0826507 0.431766 -0.0455111 0.0817806 0.428327 -0.0294575 0.085235 0.428327 -0.0348886 0.0850553 0.436781 -0.0212375 0.078235 0.436223 -0.0206794 0.078235 0.439357 -0.01975 0.078235 0.43546 -0.020475 0.078235 0.43546 -0.0175 0.078235 0.434698 -0.0206794 0.078235 0.43321 -0.0181029 0.078235 0.431563 -0.01975 0.078235 0.43414 -0.0227625 0.078235 0.431563 -0.02425 0.078235 0.434698 -0.0233207 0.078235 0.43321 -0.0258972 0.078235 0.43546 -0.0265 0.078235 0.43546 -0.023525 0.078235 0.436223 -0.0233207 0.078235 0.436781 -0.0227625 0.078235 0.439357 -0.02425 0.078235 0.43996 -0.022 0.078235 0.439357 0.02425 0.078235 0.43771 0.0258971 0.078235 0.43546 0.0265 0.078235 0.43414 0.0227625 0.078235 0.431563 0.02425 0.078235 0.43414 0.0212375 0.078235 0.43546 0.0175 0.078235 0.439357 0.01975 0.078235 0.436985 0.022 0.078235 0.436781 0.0227625 0.078235 0.43996 0.022 0.078235 0.481376 -0.0293125 0.0329736 0.481372 -0.0294343 0.0329007 0.481157 -0.024813 0.0343319 0.4819 -0.0223432 0.0344554 0.448809 -0.0575 0.054085 0.451059 -0.0575 0.0551321 0.445959 -0.0575 0.051235 0.444912 -0.0575 0.048985 0.446559 -0.0575 0.0473379 0.447384 -0.0575 0.0487669 0.451059 -0.0575 0.0473379 0.450234 -0.0575 0.0487669 0.451277 -0.0575 0.05266 0.450234 -0.0575 0.0537032 0.452706 -0.0575 0.053485 0.484848 -4.19263e-08 0.0133932 0.485047 -4.19898e-08 0.0132035 0.484762 -0.00665376 0.0134424 0.484525 -0.0127879 0.0135781 0.484924 -0.00798056 0.0132742 0.484091 -0.0215621 0.0137509 0.483089 -0.0295346 0.0151689 0.483461 -0.0255157 0.0141889 0.483659 -0.025553 0.0139984 0.482967 -0.028954 0.0150974 0.476827 -0.0305687 -0.045685 0.476827 -0.03255 -0.046735 0.476827 -0.0305687 -0.047785 0.476827 -0.0320409 -0.048635 0.476827 -0.0298 -0.0485536 0.476827 -0.02685 -0.0500259 0.476827 -0.0277 -0.0449163 0.476827 -0.0254591 -0.044835 0.476827 -0.03065 -0.0434441 0.483323 -0.0265742 0.0143218 0.481157 -0.0255157 0.0141889 0.483409 -0.0259249 0.0142262 0.481157 -0.0298005 0.015566 0.481157 -0.0277337 0.0146107 0.483188 -0.0275317 0.0145489 0.481157 -0.032349 0.0179725 0.482627 -0.0308301 0.0163237 0.482129 -0.0329296 0.0188794 0.481841 -0.0337833 0.0208891 0.48157 -0.0342184 0.0234712 0.481348 -0.0338087 0.0270417 0.481362 -0.0297479 0.0327014 0.481309 -0.0315334 0.0311672 0.481157 -0.0332468 0.0285771 0.442919 -0.0637453 0.045235 0.437646 -0.0632506 0.0339025 0.446257 -0.0621234 0.00808737 0.446148 -0.0618528 0.0018892 0.441327 -0.0617512 -0.000439448 0.441167 -0.0614571 -0.00717558 0.43411 -0.0594229 -0.053765 0.438347 -0.0599665 -0.0413157 0.438964 -0.0605804 -0.0272552 0.481157 -0.0189381 0.0296135 0.481157 -4.19928e-08 0.0348967 0.481157 0.0131656 0.0214267 0.481157 -0.0127861 0.013578 0.481157 -0.0124185 0.0347708 0.481157 -0.0273986 0.0338418 0.481157 -0.0288221 0.0311004 0.481157 -0.0297479 0.0327014 0.481157 -0.0309818 0.0317238 0.481157 -0.03305 0.024735 0.481157 -0.0342038 0.0247694 0.481157 -0.0338896 0.0212694 0.481157 -0.0310619 0.0198566 0.481157 0.0174511 0.0220964 0.481157 0.01695 0.024735 0.481157 0.0112993 0.0308509 0.481157 -0.00329935 0.0186192 0.481157 0.0238165 0.0178684 0.481157 0.028822 0.0183696 0.481157 0.0277412 0.0146166 0.481157 0.0310619 0.0198566 0.481157 0.0337772 0.0208785 0.481157 0.0342037 0.0247694 0.481157 0.0338808 0.0267809 0.481157 0.0310619 0.0296135 0.481157 0.0323552 0.0301401 0.481157 0.0261834 0.0316016 0.481157 0.0248128 0.0343319 0.481157 0.0211779 0.0311004 0.481157 0.0112993 0.0186192 0.481157 0.0084917 0.0167528 0.481157 0.00518338 0.0161184 0.481157 -4.19263e-08 0.0133932 0.481157 -0.0174512 0.0273737 0.481157 -0.00329935 0.0308509 0.481157 -0.000491784 0.0327172 0.481157 0.0124186 0.0347708 0.481157 0.0084917 0.0327172 0.484123 0.0189143 0.0138085 0.481157 0.0255155 0.0141889 0.481157 0.0127833 0.013578 0.484478 0.0136659 0.0136049 0.43318 -0.0446886 -0.0642624 0.464327 -0.0479004 -0.0642624 0.457327 -0.0508 -0.0642624 0.438538 -0.0500464 -0.0642624 0.464327 0.0479003 -0.0642624 0.457327 0.0508 -0.0642624 0.467227 0.0409 -0.0642624 0.466473 -0.0446886 -0.0642624 0.43318 0.0446885 -0.0642624 0.442327 0.0508 -0.0642624 0.431827 0.0409 -0.061565 0.433174 -0.058709 -0.0611565 0.433525 -0.059161 -0.0579328 0.431623 -0.0583998 -0.0611321 0.430755 -0.0580643 -0.0574543 0.429429 -0.0562257 -0.061059 0.429867 -0.0567613 -0.0572075 0.429091 -0.0546891 -0.0610176 0.432085 -0.0589079 -0.0577151 0.431372 -0.0583252 -0.0532759 0.423966 -0.0281996 -0.0506332 0.424478 -0.021204 -0.0468304 0.425557 -0.0147964 -0.0436571 0.422447 -0.00710975 -0.0469232 0.425106 -0.00989414 -0.043648 0.424869 -4.19898e-08 -0.0436436 0.428259 -0.0351961 -0.0467314 0.428909 -0.0325915 -0.0437434 0.431111 -0.0438741 -0.0432894 0.429882 -0.0421829 -0.0466772 0.430711 -0.0418016 -0.0436674 0.430911 -0.0491885 -0.0466111 0.430163 -0.0555681 -0.0529608 0.430091 -0.0490113 -0.050253 0.429562 -0.0553261 -0.057026 0.429266 -0.0520073 -0.0575967 0.429343 -0.0487881 -0.0538846 0.428726 -0.0484426 -0.0576218 0.427832 -0.044941 -0.0576478 0.428224 -0.047298 -0.0610475 0.423165 -0.0347156 -0.0577085 0.421686 -0.0339767 -0.0609699 0.417155 -0.0279207 -0.0608685 0.415406 -0.0224488 -0.0582612 0.414122 -0.0210348 -0.0588192 0.41383 -0.0206061 -0.0588846 0.412752 -0.0217207 -0.0607691 0.413514 -0.0200457 -0.0589074 0.411884 -0.016336 -0.0588441 0.410995 -0.0100599 -0.0581096 0.412037 -0.00894404 -0.0571349 0.412356 -0.00873168 -0.0568539 0.417074 -0.0246499 -0.0577562 0.416418 -0.0232563 -0.0576083 0.417438 -0.0238693 -0.0567903 0.421853 -0.0243774 -0.0516373 0.415167 -0.00795829 -0.0544147 0.423126 -0.0141738 -0.0468796 0.425628 -0.0403158 -0.0610386 0.426318 -0.0282073 -0.0467806 0.418023 -0.0241291 -0.056249 0.419088 -0.0280103 -0.0577402 0.421501 -0.0281584 -0.0542819 0.42481 -0.0350192 -0.05417 0.431501 -0.0458719 -0.0426616 0.428704 -0.0420699 -0.0504025 0.427571 -0.0418761 -0.0540435 0.426581 -0.0414942 -0.0576714 0.407325 -0.00755842 -0.0606694 0.414901 -0.007204 -0.0545931 0.418807 -0.00714615 -0.0509418 0.418589 -4.19898e-08 -0.051014 0.42187 -0.0207532 -0.0501368 0.42655 -0.0351443 -0.050524 0.426297 -0.0384465 -0.0541102 0.425004 -0.0380894 -0.0576913 0.421501 0.0281583 -0.0542822 0.416416 0.023255 -0.0576096 0.431119 0.0557512 -0.0474796 0.433215 0.053817 -0.0364013 0.433554 0.0562361 -0.0347208 0.433941 0.0557941 -0.032617 0.431816 0.047485 -0.0419443 0.432175 0.0493087 -0.040869 0.432524 0.0509934 -0.039569 0.431436 0.0455363 -0.0427863 0.43104 0.0435073 -0.0433758 0.429882 0.0421828 -0.0466774 0.428259 0.035196 -0.0467316 0.427766 0.027341 -0.043711 0.424477 0.0212039 -0.0468305 0.425457 0.0139198 -0.043655 0.42203 -4.19898e-08 -0.0472832 0.407035 0.00383487 -0.0606661 0.407337 0.0076551 -0.0606696 0.41248 0.00865853 -0.0567452 0.410656 0.0108575 -0.058502 0.409284 0.0151336 -0.0607001 0.411884 0.0163359 -0.0588441 0.414125 0.0210381 -0.0588185 0.423856 0.0372087 -0.0610118 0.426581 0.0414941 -0.0576717 0.430163 0.055568 -0.0529608 0.429343 0.048788 -0.0538848 0.417074 0.0246498 -0.0577564 0.423126 0.0141737 -0.0468798 0.421866 0.00794429 -0.0476675 0.418806 0.00714606 -0.050942 0.418022 0.0241289 -0.0562495 0.419548 0.0244298 -0.0545696 0.421853 0.0243773 -0.0516373 0.429562 0.055326 -0.057026 0.428848 0.050985 -0.0610331 0.429266 0.0520072 -0.057597 0.428726 0.0484424 -0.0576221 0.426297 0.0384464 -0.0541105 0.427571 0.041876 -0.0540438 0.42655 0.0351442 -0.0505242 0.424809 0.0350191 -0.0541702 0.428241 0.0473712 -0.0610472 0.42719 0.0438518 -0.0610512 0.427832 0.0449408 -0.0576481 0.425004 0.0380893 -0.0576915 0.419088 0.0280102 -0.0577404 0.423165 0.0347155 -0.0577087 0.417258 0.0280572 -0.0608708 0.422447 0.00710967 -0.0469234 0.414901 0.00720392 -0.0545933 0.415353 -4.19898e-08 -0.0540366 0.430091 0.0490112 -0.0502532 0.430911 0.0491884 -0.0466113 0.428704 0.0420698 -0.0504027 0.423966 0.0281995 -0.0506334 0.426318 0.0282072 -0.0467808 0.429091 0.054689 -0.0610176 0.42943 0.0562288 -0.0610591 0.430316 0.0575275 -0.0610986 0.431626 0.058401 -0.0611322 0.429867 0.0567612 -0.0572075 0.430755 0.0580642 -0.0574543 0.432085 0.0589078 -0.0577151 0.43411 0.0594228 -0.053765 0.445169 0.0538 -0.037415 0.445169 0.0538 -0.035765 0.449066 0.0538 -0.038015 0.448019 0.0538 -0.040265 0.449066 0.0538 -0.042515 0.442701 0.0538 -0.04169 0.442701 0.0538 -0.03884 0.436824 0.0575723 -0.012308 0.43745 0.0589349 -0.0068906 0.431292 0.055781 -0.0465506 0.432756 0.0560604 -0.038917 0.439695 0.0611789 -0.00709423 0.441167 0.061457 -0.00717558 0.440699 0.0611638 -0.0138912 0.437508 0.0603089 -0.0270064 0.435109 0.0597326 -0.0402227 0.43834 0.0602901 -0.00699166 0.439231 0.0608883 -0.0137444 0.43788 0.0600012 -0.0135816 0.43268 0.0591614 -0.0535231 0.437681 0.0593992 -0.000336763 0.436993 0.0586465 -0.0134411 0.435289 0.058071 -0.0265476 0.436167 0.0594247 -0.0267496 0.433776 0.0588527 -0.0399276 0.432902 0.0575036 -0.0397002 0.431358 0.0583116 -0.0532731 0.430472 0.0570052 -0.0530733 0.436892 0.0585864 0.0109204 0.434075 0.0609005 0.033343 0.431854 0.0612534 0.044653 0.436264 0.0629846 0.0336579 0.435482 0.0637453 0.045235 0.439559 0.0627537 0.0225252 0.434972 0.0621637 0.0334542 0.435963 0.0604043 0.0221039 0.435929 0.0589773 0.0198732 0.438167 0.0624895 0.0223339 0.436866 0.0616688 0.0221802 0.438145 0.0611708 0.0109069 0.437237 0.0599025 0.0108902 0.437339 0.0581363 0.000610398 0.438592 0.0606712 -0.0003923 0.439913 0.061493 -0.00042818 0.439459 0.0619923 0.0109751 0.428616 0.0508825 0.0750619 0.429178 0.0509336 0.0761856 0.430641 0.0527092 0.0757818 0.431092 0.0516312 0.0770996 0.432144 0.0522764 0.0766608 0.427569 0.0400396 0.0825578 0.426833 0.0383785 0.0830635 0.428336 0.0434731 0.08094 0.428296 0.0491786 0.0759982 0.425848 0.0367768 0.0833884 0.427595 0.0380704 0.0839255 0.42806 0.0417569 0.0818414 0.428925 0.041825 0.0827318 0.42923 0.0437379 0.081835 0.428544 0.0503429 0.0754978 0.428039 0.0478673 0.0760854 0.428471 0.0469623 0.0785708 0.427989 0.0462293 0.0775972 0.432099 0.0516757 0.0772351 0.428525 0.0376147 0.0845127 0.431175 0.0416718 0.0835511 0.430368 0.0438256 0.0824409 0.430544 0.0458833 0.0813355 0.430604 0.0478801 0.0800393 0.430706 0.0515649 0.0769949 0.430067 0.0513842 0.0767457 0.429391 0.0396249 0.0840378 0.428387 0.0399081 0.083434 0.430002 0.0417312 0.0833439 0.429384 0.0475341 0.0794568 0.431873 0.0473324 0.080672 0.4319 0.0479611 0.0802462 0.433598 0.0106687 0.077235 0.422327 0.0182 0.084735 0.426996 -0.0172714 0.077235 0.422327 -0.0182 0.084735 0.430954 -0.0146267 0.077235 0.434527 -0.00600004 0.077235 0.445169 -0.0538 -0.037415 0.445169 -0.0538 -0.035765 0.443744 -0.0538 -0.0377968 0.442701 -0.0538 -0.03884 0.442919 -0.0538 -0.0363679 0.440669 -0.0538 -0.040265 0.442701 -0.0538 -0.04169 0.445169 -0.0538 -0.043115 0.447419 -0.0538 -0.0441621 0.449066 -0.0538 -0.042515 0.449669 -0.0538 -0.040265 0.446594 -0.0538 -0.0377968 0.447419 -0.0538 -0.0363679 0.484835 -0.00255895 0.0134004 0.483892 -0.0215326 0.0139413 0.436826 -0.0586217 0.0117255 0.435615 -0.0590751 0.0221113 0.436264 -0.0629846 0.0336579 0.434053 -0.06346 0.0449754 0.438167 -0.0624896 0.0223339 0.436866 -0.0616689 0.0221802 0.434972 -0.0621637 0.0334542 0.435963 -0.0604044 0.0221039 0.434075 -0.0609006 0.033343 0.440865 -0.0622539 0.0110751 0.439559 -0.0627538 0.0225252 0.439459 -0.0619924 0.0109751 0.438592 -0.0606713 -0.000392301 0.438145 -0.0611709 0.0109069 0.437237 -0.0599026 0.0108902 0.440643 -0.0611375 -0.0144954 0.439258 -0.0608988 -0.0137473 0.439722 -0.0611894 -0.00709595 0.438748 -0.0605234 -0.0285592 0.432706 -0.0591714 -0.0535277 0.437399 -0.0601947 -0.0360889 0.43503 -0.0569546 -0.0264567 0.434887 -0.0569166 -0.027327 0.43431 -0.0564164 -0.030578 0.432905 -0.0575125 -0.0397012 0.43215 -0.0559374 -0.0420564 0.435906 -0.0572102 -0.0206013 0.436997 -0.0586555 -0.0134418 0.437342 -0.0580975 -0.000279926 0.437681 -0.0593993 -0.000336764 0.438354 -0.0603043 -0.00699294 0.437454 -0.0589439 -0.00689115 0.437894 -0.0600154 -0.0135835 0.435292 -0.05808 -0.0265485 0.436181 -0.0594388 -0.0267525 0.430475 -0.057014 -0.0530742 0.439913 -0.0614931 -0.00042818 0.437534 -0.0603193 -0.0270111 0.435135 -0.059743 -0.0402282 0.43379 -0.0588667 -0.0399309 0.481157 0.00281654 0.0161184 0.480359 0.00315356 0.0165788 0.479565 -0.00407595 0.0233139 0.481157 -0.00580004 0.024735 0.479677 -0.00229108 0.0194755 0.481157 -0.0051657 0.0214267 0.479597 -0.00338395 0.0211688 0.479581 -0.00364948 0.021781 0.479567 -0.00401629 0.0230088 0.479928 0.000302387 0.017416 0.481157 -0.000491784 0.0167528 0.479801 -0.000874413 0.0181411 0.480222 0.0023217 0.0167086 0.479961 0.0005583 0.0172922 0.480053 0.00122093 0.0324498 0.479717 -0.00180138 0.0305302 0.479822 -0.000657922 0.0314837 0.47985 -0.00038719 0.0316627 0.479623 -0.00299502 0.0290141 0.479605 -0.00326073 0.0285459 0.479562 -0.00414445 0.0256882 0.481157 -0.0051657 0.0280434 0.479581 -0.00364952 0.0276889 0.480435 0.00399996 0.032935 0.480416 0.00357619 0.0329241 0.481157 0.00281654 0.0333516 0.479581 0.0116494 0.027689 0.479569 0.0119617 0.0266974 0.479567 0.0120162 0.0264612 0.481157 0.0138 0.024735 0.481157 0.0131656 0.0280434 0.479677 0.010291 0.0299946 0.479597 0.0113839 0.0283012 0.479801 0.00887433 0.031329 0.480359 0.00484636 0.0328912 0.481157 0.00518338 0.0333516 0.480222 0.00567821 0.0327615 0.479961 0.00744162 0.0321778 0.480053 0.00677898 0.0170203 0.47985 0.00838711 0.0178073 0.479717 0.00980129 0.0189398 0.479562 0.0121444 0.0237818 0.479623 0.0109949 0.020456 0.479689 0.0101376 0.0192973 0.481157 -0.0261835 0.0316016 0.479889 -0.0282289 0.0303187 0.479725 -0.0295285 0.0293279 0.481157 -0.0310619 0.0296135 0.479615 -0.030607 0.0279231 0.481157 -0.0325489 0.0273737 0.479557 -0.03145 0.024735 0.481157 -0.0238166 0.0316016 0.480435 -0.025 0.031185 0.48034 -0.0258384 0.0311303 0.481157 -0.01695 0.024735 0.47959 -0.019094 0.0273276 0.479617 -0.0194144 0.0279602 0.479666 -0.0199194 0.0287085 0.481157 -0.021178 0.0311004 0.48034 -0.0241616 0.0311303 0.48034 -0.0241616 0.0183398 0.480143 -0.0232006 0.0185411 0.479889 -0.0217712 0.0191513 0.481157 -0.021178 0.0183696 0.479725 -0.0204716 0.0201421 0.481157 -0.0189381 0.0198566 0.479615 -0.0193931 0.021547 0.481157 -0.0174512 0.0220964 0.479557 -0.01855 0.024735 0.481157 -0.0261835 0.0178684 0.480412 -0.0245799 0.0182987 0.481157 -0.0238166 0.0178684 0.479565 -0.0313433 0.0235667 0.47959 -0.0309061 0.0221425 0.481157 -0.0325489 0.0220964 0.479617 -0.0305857 0.0215098 0.479797 -0.0289097 0.0196049 0.481157 -0.0288221 0.0183696 0.479557 0.03145 0.024735 0.481157 0.03305 0.024735 0.479565 0.0313433 0.0259034 0.481157 0.0325488 0.0273737 0.479617 0.0305856 0.0279602 0.479666 0.0300806 0.0287085 0.479797 0.0289096 0.0298651 0.481157 0.028822 0.0311004 0.479889 0.0282288 0.0191513 0.481157 0.0261834 0.0178684 0.479725 0.0295284 0.0201421 0.479692 0.0298346 0.0204655 0.481157 0.0325488 0.0220964 0.479571 0.0312111 0.0229948 0.480435 0.025 0.018285 0.480412 0.0254201 0.0182987 0.48034 0.0258384 0.0183398 0.479565 0.0186567 0.0235667 0.47959 0.0190939 0.0221425 0.481157 0.0189381 0.0198566 0.479666 0.0199193 0.0207616 0.479797 0.0210903 0.0196049 0.481157 0.0211779 0.0183696 0.47989 0.0217764 0.0191483 0.48034 0.0241616 0.0183398 0.479998 0.0224419 0.0188138 0.480143 0.0232005 0.0309289 0.481157 0.0238165 0.0316016 0.479889 0.0217711 0.0303187 0.481157 0.0189381 0.0296135 0.479615 0.019393 0.0279231 0.479571 0.0187888 0.0264752 0.481157 0.0174511 0.0273737 0.479581 0.0189678 0.0270188 0.480412 0.0245799 0.0311713 0.480435 0.025 0.031185 0.48034 0.0258384 0.0311303 0.414908 -0.01495 -0.058565 0.416727 -0.0139 -0.058565 0.420427 0.0123 -0.058565 0.414627 0.016 -0.058565 0.412528 0.0160807 -0.058565 0.415677 0.0141813 -0.058565 0.411286 0.0123 -0.058565 0.414184 0.0197 -0.058565 0.420427 0.0197 -0.058565 0.416727 0.0181 -0.058565 0.417777 0.0178186 -0.058565 0.420435 -0.0231 -0.054974 0.420427 -0.0194704 -0.0538229 0.420429 -0.0231 -0.055165 0.420431 -0.0231 -0.0550694 0.420795 -0.0201502 -0.0518695 0.420665 -0.00882952 -0.0499647 0.42058 -0.00887914 -0.0502998 0.420795 -0.0160521 -0.0506833 0.420794 -0.0118815 -0.0499126 0.420427 -0.00890004 -0.0516527 0.421872 -0.0164711 -0.048896 0.421868 -0.0121363 -0.0480963 0.421012 -0.0085695 -0.0490304 0.420797 -0.00873576 -0.0495561 0.42053 -0.0232033 -0.0541537 0.420608 -0.0233006 -0.0538035 0.42079 -0.0235078 -0.0532475 0.421107 -0.0238186 -0.0525994 0.421254 -0.0239459 -0.052365 0.41951 -0.0239855 -0.0545384 0.416762 -0.0224982 -0.0573562 0.41965 -0.0235161 -0.054653 0.416493 -0.0229685 -0.0574365 0.418799 -0.0239479 -0.0553549 0.419548 -0.0244299 -0.0545696 0.414414 -0.0207518 -0.0585382 0.415121 -0.0214989 -0.0582583 0.420115 -0.0231229 -0.0550308 0.417 -0.0222459 -0.0574429 0.413998 -0.0197961 -0.0585871 0.414604 -0.0205955 -0.0584792 0.4148 -0.0204485 -0.0584816 0.415608 -0.0211691 -0.0582312 0.415321 -0.0212892 -0.0582205 0.416879 -0.0223617 -0.057387 0.418601 -0.0229107 -0.0563467 0.418049 -0.0237534 -0.0561214 0.416655 -0.0226499 -0.0573541 0.418203 -0.0233462 -0.056113 0.418853 -0.0237218 -0.0553586 0.419554 -0.0237473 -0.0545748 0.418947 -0.0235057 -0.0554007 0.414249 -0.0209028 -0.0586561 0.414956 -0.0217104 -0.058374 0.416086 -0.0218745 -0.0578507 0.418459 -0.0230187 -0.0562434 0.418323 -0.0231661 -0.0561626 0.419782 -0.023333 -0.0547603 0.41995 -0.023195 -0.0548967 0.412528 -0.0160808 -0.058565 0.410661 -0.012464 -0.0588018 0.412181 -0.0162184 -0.0586374 0.414184 -0.0197 -0.058565 0.413816 -0.0198899 -0.0586546 0.413652 -0.0199749 -0.0587643 0.410953 -0.0123873 -0.058626 0.412483 -0.00951977 -0.0571793 0.411815 -0.00999781 -0.0576999 0.411645 -0.00986519 -0.0576767 0.414815 -0.00797017 -0.0547227 0.413565 -0.00819694 -0.0558065 0.412154 -0.00915403 -0.0571003 0.415009 -0.00894445 -0.0557149 0.415595 -0.00883694 -0.0549022 0.414792 -0.00884924 -0.0554795 0.414002 -0.00896289 -0.0560553 0.413103 -0.00943012 -0.0569881 0.410572 -0.0113123 -0.0586474 0.411286 -0.0123 -0.058565 0.411207 -0.0119942 -0.0585511 0.41086 -0.0114291 -0.0585098 0.411125 -0.0105559 -0.058165 0.412307 -0.00935236 -0.0571148 0.413657 -0.008488 -0.0558153 0.413809 -0.00875779 -0.0559007 0.420507 -0.00890004 -0.0506737 0.421866 -0.00794437 -0.0476675 0.421355 -0.00830606 -0.0483875 0.418889 -0.00862816 -0.0513556 0.419126 -0.00883636 -0.0515914 0.418218 -0.00890004 -0.0529735 0.415375 -0.00863076 -0.0546519 0.415224 -0.00831211 -0.0544802 0.418728 -0.00830667 -0.0511947 0.418667 -0.00795062 -0.0511346 0.43766 -0.0572457 -0.00734388 0.43784 -0.0575552 -0.000256247 0.435734 -0.0586439 0.0246794 0.432056 -0.0595209 0.0447672 0.431992 -0.0595356 0.0451029 0.431591 -0.0436898 -0.0429301 0.441027 -0.0439127 -0.0428726 0.441027 -0.0396045 -0.043435 0.431186 -0.0416661 -0.0433079 0.435378 -0.0563707 -0.0273848 0.434803 -0.0559281 -0.030549 0.434429 -0.0553167 -0.0325492 0.434058 -0.0544565 -0.0344669 0.433355 -0.052107 -0.0378478 0.441027 -0.0530731 -0.0366646 0.433612 -0.0530732 -0.0366645 0.433704 -0.0533897 -0.036224 0.432362 -0.047516 -0.0414531 0.441027 -0.0490193 -0.0405453 0.432668 -0.0490191 -0.0405454 0.427841 -0.0255642 -0.043435 0.427375 0.0233101 -0.043435 0.425868 0.0138742 -0.043435 0.420435 0.0231 -0.054974 0.420523 0.0231954 -0.0541871 0.420358 0.0231 -0.0550695 0.420115 0.0231228 -0.0550308 0.420966 0.0236876 -0.052856 0.420789 0.023507 -0.0532492 0.419554 0.0237472 -0.0545748 0.41965 0.0235161 -0.054653 0.420794 0.0118814 -0.0499126 0.420427 0.0115942 -0.0519599 0.420795 0.0201501 -0.0518695 0.420427 0.0194703 -0.0538229 0.420429 0.0231 -0.055165 0.420427 0.0230989 -0.0552478 0.420427 0.0222095 -0.0549123 0.421249 0.0239416 -0.0523725 0.42187 0.0207531 -0.0501368 0.420795 0.0160521 -0.0506833 0.421872 0.0164711 -0.048896 0.420829 0.00871149 -0.0494691 0.421868 0.0121362 -0.0480963 0.420507 0.00889996 -0.0506737 0.419126 0.00883628 -0.0515914 0.42067 0.00882652 -0.0499492 0.421362 0.00830098 -0.0483765 0.418728 0.00830659 -0.0511947 0.421557 0.00815779 -0.0480767 0.415167 0.00795821 -0.0544147 0.418667 0.00795054 -0.0511346 0.415375 0.00863068 -0.0546519 0.418889 0.00862807 -0.0513556 0.415595 0.00883686 -0.0549022 0.418218 0.00889996 -0.0529735 0.410953 0.0123873 -0.058626 0.413648 0.00849035 -0.0558232 0.415224 0.00831203 -0.0544802 0.4138 0.00875978 -0.0559081 0.411814 0.00999847 -0.0577006 0.411124 0.0105571 -0.0581657 0.411449 0.0107257 -0.0581786 0.412149 0.00915735 -0.0571048 0.411645 0.00986592 -0.0576775 0.411483 0.0106709 -0.0581493 0.415709 0.00888431 -0.0550325 0.414121 0.00909792 -0.0563082 0.412658 0.0096453 -0.0572893 0.412478 0.00952259 -0.0571832 0.412591 0.00968321 -0.0573358 0.412285 0.00987473 -0.057548 0.413992 0.00896477 -0.0560622 0.412302 0.00935538 -0.057119 0.412867 0.00953787 -0.0571476 0.414095 0.00903427 -0.0561571 0.410593 0.0121292 -0.058787 0.410859 0.0114298 -0.05851 0.410912 0.0102075 -0.0581972 0.411364 0.0095545 -0.0577473 0.413555 0.0081997 -0.0558146 0.413652 0.0199748 -0.0587643 0.414091 0.0197478 -0.0585704 0.413998 0.019796 -0.0585871 0.412181 0.0162183 -0.0586374 0.410661 0.0124639 -0.0588018 0.419162 0.024415 -0.0550344 0.417081 0.0236772 -0.0570948 0.414845 0.0218999 -0.0585481 0.414416 0.0207546 -0.0585375 0.42028 0.0231 -0.055165 0.419221 0.0231748 -0.055586 0.41995 0.0231949 -0.0548967 0.419073 0.0233186 -0.0554793 0.418322 0.0231659 -0.056163 0.418203 0.023346 -0.0561135 0.418459 0.0230185 -0.0562438 0.417434 0.0230575 -0.0567698 0.416999 0.0222449 -0.0574439 0.417046 0.0221143 -0.0575589 0.41951 0.0239854 -0.0545384 0.415428 0.0211954 -0.0582304 0.415124 0.0215014 -0.058257 0.417673 0.0227445 -0.0568487 0.419377 0.0230803 -0.0557097 0.418866 0.0228801 -0.056368 0.413816 0.0198898 -0.0586546 0.414251 0.0209058 -0.0586553 0.415324 0.0212915 -0.0582193 0.416878 0.0223607 -0.0573881 0.416653 0.0226489 -0.0573553 0.414959 0.0217131 -0.0583726 0.413514 0.0200456 -0.0589074 0.419782 0.023333 -0.0547603 0.418946 0.0235056 -0.0554009 0.41811 0.0235468 -0.0560998 0.418049 0.0237532 -0.0561218 0.416491 0.0229673 -0.0574377 0.432667 0.0490188 -0.0405456 0.435378 0.0563706 -0.0273848 0.441027 0.0490192 -0.0405453 0.441027 0.0439126 -0.0428726 0.441027 0.0396044 -0.043435 0.433014 0.0506456 -0.0392913 0.432721 0.049275 -0.0403685 0.434596 0.0556208 -0.0316643 0.441027 0.0556208 -0.0316644 0.434304 0.0550548 -0.0332045 0.441027 0.0530731 -0.0366646 0.433612 0.0530733 -0.0366642 0.437709 0.0572915 -0.00629376 0.431933 0.0595493 0.0454182 0.432056 0.0595208 0.0447672 0.437837 0.0575941 0.000637275 0.43784 0.0575551 -0.000256247 0.437182 0.0569606 -0.0138722 0.441027 0.0563706 -0.0273848 0.435814 0.0564889 -0.0246755 0.448046 0.0565 0.0525557 0.447534 0.0565 0.0534434 0.448809 0.0565 0.053785 0.449571 0.0565 0.0525557 0.450084 0.0565 0.0534434 0.450129 0.0565 0.0519975 0.450334 0.0565 0.051235 0.451359 0.0565 0.051235 0.451017 0.0565 0.04996 0.448809 0.0565 0.048685 0.448046 0.0565 0.0499143 0.447534 0.0565 0.0490267 0.4466 0.0565 0.04996 0.446259 0.0565 0.051235 0.423294 0.0345813 0.0826252 0.421229 0.0318071 0.0836973 0.425131 0.0328425 0.085026 0.425954 0.032043 0.085214 0.42333 0.0294574 0.085235 0.423709 0.0341997 0.0836418 0.426556 0.0363278 0.0842398 0.427422 0.0357313 0.0848073 0.424346 0.0335974 0.0844851 0.413765 0.0255706 0.0837153 0.410906 0.023823 0.0829045 0.410386 0.0234619 0.0827466 0.409927 0.0222544 0.0837575 0.406788 0.0189493 0.0839551 0.411258 0.0207764 0.0850763 0.415038 0.0240192 0.0850717 0.410525 0.02159 0.0845688 0.422572 0.0303054 0.0850698 0.414335 0.024876 0.0845493 0.421829 0.0311359 0.0845409 0.404823 0.0182 0.0800323 0.404286 0.0182 0.078711 0.403816 0.0182 0.077235 0.41066 0.0182 0.084735 0.407057 0.0182 0.0836151 0.406204 0.0182 0.0826623 0.422327 0.0182 0.077235 0.404577 -0.00216511 0.077235 0.403327 -0.00250004 0.077235 0.433598 -0.0106688 0.077235 0.428492 -0.00125004 0.077235 0.402077 0.00216502 0.077235 0.39856 0.0073828 0.077235 0.401162 0.00124996 0.077235 0.403327 0.00249996 0.077235 0.426996 0.0172713 0.077235 0.405492 0.00124996 0.077235 0.424162 0.00124996 0.077235 0.423827 -4.19898e-08 0.077235 0.424162 -0.00125004 0.077235 0.422327 -0.0182 0.077235 0.425077 0.00216502 0.077235 0.430954 0.0146267 0.077235 0.434527 0.00599996 0.077235 0.428827 -4.19898e-08 0.077235 0.398364 0.00551355 0.077235 0.39831 0.000675094 0.077235 0.401162 -0.00125004 0.077235 0.402077 -0.00216511 0.077235 0.399943 -0.0122658 0.077235 0.40032 -0.0130756 0.077235 0.41066 -0.0182 0.084735 0.404056 -0.0182 0.0780436 0.403815 -0.0182014 0.077235 0.404634 -0.0182 0.0795963 0.407055 -0.0182 0.083614 0.414244 -0.0264678 0.0831174 0.415543 -0.0276573 0.0829091 0.416024 -0.0281734 0.0826811 0.419824 -0.0313433 0.0826745 0.406786 -0.0189494 0.0839539 0.410525 -0.0215901 0.0845688 0.410386 -0.023462 0.0827466 0.409927 -0.0222545 0.0837575 0.414335 -0.0248761 0.0845493 0.411258 -0.0207765 0.0850763 0.41066 -0.0187 0.085235 0.422572 -0.0303055 0.0850698 0.415038 -0.0240193 0.0850717 0.421829 -0.0311359 0.0845409 0.413765 -0.0255707 0.0837153 0.423377 -0.0346676 0.082621 0.424941 -0.0362666 0.0827676 0.425131 -0.0328426 0.085026 0.42333 -0.0294575 0.085235 0.423709 -0.0341998 0.0836418 0.421229 -0.0318071 0.0836973 0.427422 -0.0357314 0.0848073 0.425954 -0.032043 0.085214 0.424346 -0.0335975 0.0844851 0.426556 -0.0363279 0.0842398 0.448809 -0.0565 0.053785 0.447534 -0.0565 0.0534434 0.447488 -0.0565 0.0519975 0.4466 -0.0565 0.05251 0.447284 -0.0565 0.051235 0.446259 -0.0565 0.051235 0.448046 -0.0565 0.0499143 0.450129 -0.0565 0.0504725 0.451017 -0.0565 0.04996 0.450129 -0.0565 0.0519975 0.451359 -0.0565 0.051235 0.451017 -0.0565 0.05251 0.449571 -0.0565 0.0525557 0.420427 -0.0123 -0.058565 0.420427 -0.00989588 -0.0575691 0.420427 -0.0111232 -0.0583548 0.412317 -0.00985309 -0.0575256 0.411988 -0.010103 -0.0577598 0.411558 -0.0105621 -0.0580872 0.411242 -0.0111998 -0.058382 0.420427 -0.00890004 -0.055165 0.415825 -0.00890004 -0.055165 0.414107 -0.0091012 -0.0563171 0.420427 -0.00911019 -0.0563418 0.420427 -0.0197 -0.058565 0.420427 -0.0208768 -0.0583548 0.420427 -0.0221042 -0.0575691 0.416309 -0.0216717 -0.0579349 0.417046 -0.0221139 -0.0575594 0.417119 -0.0221538 -0.0575185 0.420427 -0.0228899 -0.0563418 0.418238 -0.0226697 -0.0568214 0.41874 -0.0228427 -0.0564626 0.420427 -0.023099 -0.0552478 0.420427 -0.023096 -0.0553305 0.420427 -0.0115942 -0.0519599 0.420427 -0.0169665 -0.0530495 0.419528 0.023033 -0.0558386 0.41874 0.0228424 -0.056463 0.417932 0.0225458 -0.0570263 0.417832 0.0225027 -0.0570906 0.417117 0.0221528 -0.0575194 0.420427 0.0221041 -0.0575691 0.415407 0.0210066 -0.0583039 0.420427 0.0208768 -0.0583548 0.420427 0.00911011 -0.0563418 0.420427 0.0098958 -0.0575691 0.411188 0.0114784 -0.0584642 0.420427 0.0111232 -0.0583548 0.420427 0.00889996 -0.055165 0.420427 0.0230959 -0.0553305 0.420427 0.0228898 -0.0563418 0.420427 0.0161761 -0.0528433 0.42028 -0.0231 -0.055165 0.420358 -0.0231 -0.0550695 0.441027 -0.0369682 0.0327113 0.441027 -0.0556209 -0.0316644 0.441027 -0.035169 0.014066 0.441027 -0.0324763 0.0122668 0.441027 0.0463677 0.0625451 0.441027 -0.0593188 0.0490164 0.441027 -0.0595493 0.0454182 0.441027 -0.0376 0.019935 0.441027 -0.0563707 -0.0273848 0.441027 -0.0369682 0.0167588 0.441027 -0.054906 0.0577554 0.441027 0.0324762 0.0372032 0.441027 -0.0427831 0.0629324 0.441027 -0.0293 0.037835 0.441027 -0.0293 0.011635 0.441027 0.0369682 0.0167588 0.441027 0.0376 0.019935 0.441027 0.0595493 0.0454182 0.441027 0.0369682 0.0327113 0.441027 0.0577637 0.0537148 0.441027 0.0351689 0.035404 0.441027 0.0549059 0.0577554 0.422856 -0.0370357 0.0629324 0.424861 -0.0400127 0.0629324 0.441027 0.042783 0.0629324 0.419234 -0.0325215 0.0629324 0.416726 -0.0296558 0.0629324 0.416405 -0.0292923 0.0629324 0.416719 0.0296478 0.0629324 0.403575 -0.00244309 0.0629324 0.403561 -4.20037e-08 0.0629324 0.403812 0.00663548 0.0629324 0.404235 0.0093784 0.0629324 0.412078 -0.0242701 0.0629324 0.405006 0.0123035 0.0629324 0.406179 0.0152768 0.0629324 0.407562 0.0179139 0.0629324 0.405613 -0.0139685 0.0629324 0.411087 -0.0230318 0.0629324 0.404062 -0.00844893 0.0629324 0.403768 -0.00620178 0.0629324 0.420431 0.0231 -0.0550694 0.420427 0.00889996 -0.0516527 0.415825 0.00889996 -0.055165 0.431395 0.0594422 0.0481789 0.441027 0.0593187 0.0490164 0.430552 0.0582242 0.0527239 0.430373 0.0577639 0.0537144 0.430221 0.0573024 0.0545664 0.429647 0.0549065 0.0577548 0.429912 0.0561513 0.0562958 0.441027 0.0509938 0.0607867 0.428777 0.0500124 0.0612955 0.443894 0.0528 -0.0380566 0.445169 0.0528 -0.037715 0.445931 0.0528 -0.0389443 0.446444 0.0528 -0.0380566 0.446489 0.0528 -0.0395025 0.447719 0.0528 -0.040265 0.447377 0.0528 -0.04154 0.445169 0.0528 -0.042815 0.444406 0.0528 -0.0415857 0.443894 0.0528 -0.0424733 0.443644 0.0528 -0.040265 0.44296 0.0528 -0.04154 0.443848 0.0528 -0.0395025 0.442619 0.0528 -0.040265 0.446444 -0.0528 -0.0380566 0.444406 -0.0528 -0.0389443 0.443644 -0.0528 -0.040265 0.442619 -0.0528 -0.040265 0.44296 -0.0528 -0.04154 0.443894 -0.0528 -0.0424733 0.445169 -0.0528 -0.042815 0.445931 -0.0528 -0.0415857 0.446694 -0.0528 -0.040265 0.446489 -0.0528 -0.0395025 0.447719 -0.0528 -0.040265 0.445931 -0.0528 -0.0389443 0.447377 -0.0528 -0.03899 0.479357 -0.0353 0.019935 0.479357 -0.0323 0.0147389 0.479357 -0.028225 0.0191492 0.479357 0.03145 0.024735 0.479357 0.0305858 0.02796 0.479357 0.0344961 0.032535 0.479357 0.0323 0.0347312 0.479357 -0.000658173 0.0179866 0.479357 0.00301156 0.0165948 0.479357 0.0293 0.013935 0.479357 0.0101377 0.0192974 0.479357 0.0119617 0.0227726 0.479357 0.0119617 0.0266974 0.479357 0.0101377 0.0301726 0.479357 -0.025 0.031185 0.479357 0.0323 0.0147389 0.479357 0.0344961 0.016935 0.479357 0.0305858 0.02151 0.479357 -0.0194142 0.02151 0.479357 -0.000658173 0.0314835 0.479357 -0.0353 0.029535 0.479357 -0.0305859 0.02796 0.479357 -0.0344962 0.032535 0.479357 -0.0323 0.0347312 0.479357 -0.0293 0.035535 0.479357 0.00301156 0.0328752 0.479357 0.0293 0.035535 0.472465 -0.0353 0.029535 0.472465 -0.0293 0.035535 0.472465 0.0353 0.029535 0.479357 0.0353 0.019935 0.479357 0.0353 0.029535 0.472465 0.0323 0.0147389 0.479357 -0.0293 0.013935 0.472465 -0.0293 0.013935 0.472465 -0.0344962 0.016935 0.479357 -0.0344962 0.016935 0.472465 -0.0353 0.019935 0.472165 0.03245 0.0144791 0.472165 0.0324762 0.0122668 0.472165 -0.0293 0.011635 0.472165 0.0347559 0.032685 0.472165 0.0376 0.019935 0.472165 0.0347559 0.016785 0.472165 -0.03245 0.0144791 0.472165 -0.0356 0.029535 0.472165 -0.0376 0.029535 0.472165 -0.0369682 0.0327113 0.472165 -0.03245 0.034991 0.472165 -0.0293 0.035835 0.472165 -0.0293 0.037835 0.472165 0.03245 0.034991 0.441027 0.0293 0.011635 0.472165 0.0293 0.011635 0.472165 -0.0324763 0.0122668 0.472165 -0.035169 0.014066 0.472165 -0.0369682 0.0167588 0.472165 -0.0376 0.019935 0.441027 -0.0376 0.029535 0.472165 -0.035169 0.035404 0.472165 -0.0324763 0.0372032 0.441027 -0.035169 0.035404 0.441027 -0.0324763 0.0372032 0.472165 0.0293 0.037835 0.441027 0.0293 0.037835 0.472165 0.0324762 0.0372032 0.472165 0.0351689 0.035404 0.472165 0.0369682 0.0327113 0.441027 0.0376 0.029535 0.472165 0.0376 0.029535 0.472165 0.0369682 0.0167588 0.472165 0.0351689 0.014066 0.441027 0.0351689 0.014066 0.441027 0.0324762 0.0122668 0.472165 0.0293 0.035835 0.472465 0.0293 0.035535 0.472465 0.0323 0.0347312 0.472465 0.0344961 0.032535 0.472165 0.0356 0.029535 0.472165 -0.034756 0.032685 0.472465 -0.0344962 0.032535 0.472465 -0.0323 0.0347312 0.472465 0.0353 0.019935 0.472465 0.0344961 0.016935 0.472165 0.0356 0.019935 0.472465 0.0293 0.013935 0.472165 0.0293 0.013635 0.472465 -0.0323 0.0147389 0.472165 -0.034756 0.016785 0.472165 -0.0356 0.019935 0.472165 -0.0293 0.013635 0.430793 0.0396044 -0.043435 0.430323 0.0396876 -0.0437865 0.428203 0.0272457 -0.043435 0.426947 0.0233956 -0.0436895 0.425296 0.00411743 -0.043435 0.424889 0.00412311 -0.0436439 0.426972 -0.0212198 -0.043435 0.425275 -4.17382e-08 -0.043435 0.426684 -0.0196044 -0.043435 0.425601 -0.0110544 -0.043435 0.425514 -0.00986698 -0.043435 0.426264 -0.0196762 -0.0436729 0.428464 -0.0305454 -0.0437305 0.42936 -0.032493 -0.043435 0.430793 -0.0396045 -0.043435 0.43431 0.0564163 -0.030578 0.433501 0.0526724 -0.0371822 0.432867 0.0524991 -0.0380765 0.433575 0.0549272 -0.0345615 0.431919 0.0453142 -0.0424338 0.432302 0.0472188 -0.0416081 0.432664 0.0490006 -0.0405579 0.431875 0.0450949 -0.0425114 0.431115 0.0413062 -0.0433485 0.430641 0.0414327 -0.0437071 0.431006 0.0407418 -0.0433964 0.433938 -0.0557875 -0.032635 0.433567 -0.0549031 -0.0346077 0.433212 -0.0538074 -0.0364153 0.432865 -0.0524913 -0.0380854 0.432578 -0.051245 -0.0393443 0.433068 -0.0508912 -0.0390726 0.432233 -0.0495968 -0.0406697 0.430323 -0.0396877 -0.0437865 0.431985 -0.0456423 -0.0423112 0.431875 -0.0477891 -0.0417858 0.432722 -0.049282 -0.0403636 0.434803 0.055928 -0.030549 0.434887 0.0569165 -0.027327 0.437342 0.0580974 -0.000279926 0.437211 0.0578347 -0.00629595 0.436436 0.0566768 -0.0203727 0.436731 0.057526 -0.0133681 0.435274 0.0570213 -0.0249275 0.4364 -0.056665 -0.0206441 0.436686 -0.057505 -0.0138507 0.437182 -0.0569606 -0.013874 0.437162 -0.0577891 -0.00734389 0.437813 -0.0574361 -0.00298348 0.431567 0.0600591 0.0446505 0.435365 0.0587431 0.0269538 0.434874 0.0592819 0.0268485 0.436422 0.0584379 0.0199629 0.437221 0.0581312 0.0129391 0.436725 0.0586715 0.0128698 0.431567 -0.0600592 0.0446505 0.434743 -0.0593161 0.0276296 0.435234 -0.0587773 0.0277362 0.435241 -0.0591828 0.0245785 0.437323 -0.0580812 0.0117911 0.436892 -0.0585865 0.0109204 0.431992 0.0595355 0.0451029 0.431443 0.0600876 0.0453022 0.431443 -0.0600877 0.0453022 0.431869 -0.0595605 0.0457462 0.431789 -0.0595653 0.0461503 0.430759 0.0598376 0.0489358 0.431251 0.0593317 0.0489405 0.430059 0.0587075 0.0528427 0.429416 0.0565881 0.056541 0.427203 0.0445872 0.0628352 0.427868 0.0464235 0.0625328 0.427393 0.0466857 0.0630497 0.428962 0.0509912 0.0607882 0.429362 0.0533182 0.0592137 0.427378 -0.0466374 0.0630608 0.427852 -0.0463758 0.0625434 0.428324 -0.0505201 0.0616538 0.428927 -0.0540562 0.0592688 0.429812 -0.0580364 0.0542571 0.431013 -0.0590663 0.0502124 0.430903 -0.0599499 0.0481501 0.430153 -0.0589226 0.0523073 0.430373 -0.0577639 0.0537145 0.403455 0.0063007 0.0630486 0.407307 0.0182462 0.0631177 0.411194 0.0231684 0.0629324 0.411901 0.0240525 0.0629324 0.410847 0.0234412 0.0631975 0.414841 0.0282458 0.0632917 0.41931 0.0326104 0.0629324 0.422685 0.0368036 0.0629324 0.422764 0.0377603 0.0634458 0.424885 0.0400507 0.0629324 0.424459 0.0403105 0.0634641 0.426384 0.042783 0.0629324 0.426384 -0.0427831 0.0629324 0.416134 -0.0289857 0.0629324 0.411751 -0.0245847 0.0632189 0.408335 -0.0191774 0.0629324 0.405001 -0.0122863 0.0629324 0.404767 -0.0126708 0.0630686 0.403475 -0.00649952 0.0630488 0.403244 -4.19898e-08 0.0630463 0.436574 0.056184 -0.0574655 0.436646 0.0558192 -0.0574366 0.436868 0.055483 -0.0574232 0.436924 0.0547084 -0.0611569 0.437205 0.0552608 -0.0574303 0.437038 0.0560589 -0.0535127 0.437259 0.055721 -0.0535233 0.437595 0.0554982 -0.0535519 0.440236 0.0560466 -0.0393912 0.43954 0.0560398 -0.0410832 0.442161 0.0565776 -0.0287616 0.444903 0.0569798 -0.0180168 0.444852 0.0571142 -0.0164742 0.446927 0.057489 -0.00635539 0.447749 0.0580006 0.00536332 0.447756 0.058127 0.00825862 0.447404 0.0585141 0.0171243 0.444057 0.0598152 0.0453658 0.438983 0.0566007 -0.0410013 0.446267 0.0582155 -0.0040735 0.445426 0.0579449 -0.010232 0.446194 0.0585845 -0.00408187 0.444297 0.057675 -0.0163869 0.441536 0.0575064 -0.028661 0.436966 0.0564257 -0.0535206 0.446727 0.0584858 0.00207222 0.446655 0.0588554 0.00205923 0.446762 0.0590854 0.00728066 0.446142 0.059667 0.0205218 0.444874 0.0602076 0.0328717 0.443492 0.0603772 0.0452774 0.445166 0.0594959 0.0329366 0.444943 0.0598366 0.0328959 0.446212 0.0592963 0.0205438 0.446827 0.058756 0.00822251 0.447053 0.058416 0.00823946 0.446952 0.0581461 0.00207715 0.446491 0.0578762 -0.00408278 0.441608 0.0571384 -0.0286612 0.439205 0.0562619 -0.0410289 0.445507 0.0592747 0.0329858 0.446437 0.0589558 0.0205774 0.446778 0.0587345 0.0206154 0.447395 0.0581945 0.00825231 0.447294 0.0579244 0.00207181 0.44683 0.0576543 -0.00410955 0.445649 0.057606 -0.0102535 0.445986 0.0573839 -0.0102986 0.444518 0.0573363 -0.0164167 0.441829 0.0567999 -0.0286962 0.443716 0.0600364 0.0453176 0.44351 0.059921 0.050271 0.443876 0.0598502 0.0503074 0.442881 0.0608499 0.0502268 0.44207 0.0588442 0.0599242 0.441689 0.0572883 0.0646439 0.441561 0.0544786 0.0687494 0.44137 0.0516858 0.0729252 0.441443 0.0514142 0.0726821 0.441331 0.0480797 0.0763941 0.442952 0.0604824 0.0502257 0.442695 0.0597055 0.0550736 0.442473 0.0600376 0.0551091 0.442294 0.0585257 0.0598351 0.441767 0.0569633 0.0644864 0.443031 0.0594849 0.0550671 0.443173 0.0601438 0.050241 0.441991 0.0566632 0.0643496 0.441784 0.0542006 0.0685695 0.442004 0.0509976 0.0723179 0.441667 0.0511637 0.0724609 0.441625 0.0476324 0.0758491 0.442331 0.0474461 0.0756246 0.442369 0.0509426 0.0722755 0.441963 0.0474912 0.0756781 0.44212 0.0540152 0.0684566 0.442688 0.0563932 0.0642547 0.442325 0.0564624 0.0642686 0.442991 0.05824 0.0597924 0.442629 0.0583129 0.0597895 0.441402 0.0478469 0.0761101 0.44162 0.0435742 0.0786158 0.441959 0.0434667 0.0784208 0.442327 0.0458439 0.0768455 0.441327 0.0407205 0.0807044 0.441397 0.0405923 0.0803594 0.441397 0.0437379 0.0789127 0.442018 0.0403893 0.0798129 0.441518 0.0405158 0.0801534 0.439605 0.0318633 0.0812171 0.438833 0.0324026 0.0818463 0.439017 0.0322701 0.0815055 0.440249 0.0350043 0.0816876 0.441103 0.03777 0.0812314 0.441319 0.0376535 0.0808939 0.439299 0.0320734 0.0812837 0.441118 0.0345823 0.0810663 0.441657 0.0375394 0.0806792 0.441739 0.0404388 0.079946 0.440453 0.0348864 0.0813445 0.440771 0.0347326 0.0811254 0.437072 0.0299647 0.0815279 0.44162 0.0404743 0.0800416 0.441376 0.0406129 0.0804147 0.440195 0.0350633 0.0820617 0.436868 0.0301748 0.082235 0.435041 0.0285739 0.0818523 0.432932 0.0273574 0.0818523 0.436921 0.0301202 0.0818523 0.435164 0.0283958 0.0815279 0.432957 0.027305 0.081735 0.433025 0.0271613 0.0815279 0.433113 0.026974 0.081369 0.435349 0.0281291 0.0813112 0.437298 0.0297319 0.0813112 0.431715 0.0265145 0.081735 0.431629 0.0266176 0.082235 0.429639 0.0227209 0.081735 0.429643 0.0212485 0.081735 0.429506 0.0227374 0.082235 0.42951 0.0212313 0.082235 0.431654 0.0173623 0.082235 0.431949 0.0262328 0.081369 0.430709 0.0254396 0.081735 0.431005 0.025225 0.081369 0.430342 0.0240139 0.081369 0.430002 0.0241479 0.081735 0.430002 0.0226759 0.081369 0.430013 0.0198234 0.081735 0.431022 0.0187517 0.081369 0.430727 0.0185355 0.081735 0.433163 0.0268679 0.0813112 0.432268 0.025848 0.081235 0.430498 0.0226145 0.081235 0.430006 0.0212954 0.081369 0.430353 0.0199592 0.081369 0.438027 0.00599996 0.081235 0.437857 0.00830337 0.081235 0.436872 0.0104118 0.081369 0.43652 0.0127119 0.081235 0.435381 0.0147215 0.081235 0.43359 0.0162067 0.081369 0.433961 0.0165425 0.081235 0.431971 0.0177488 0.081369 0.437161 0.00599996 0.081735 0.437 0.00817631 0.081735 0.437362 0.00823001 0.081369 0.436522 0.0103056 0.081735 0.436068 0.0124981 0.081369 0.434661 0.0142404 0.081735 0.434966 0.0144438 0.081369 0.433319 0.0159609 0.081735 0.431739 0.0174658 0.081735 0.436868 0.00815665 0.082235 0.435616 0.0122844 0.082235 0.435737 0.0123416 0.081735 0.437527 -0.00600004 0.081369 0.437527 0.00599996 0.081369 0.437027 -0.00600004 0.082235 0.43359 -0.0162068 0.081369 0.433961 -0.0165425 0.081235 0.434966 -0.0144439 0.081369 0.436068 -0.0124982 0.081369 0.437857 -0.00830345 0.081235 0.433319 -0.015961 0.081735 0.434661 -0.0142405 0.081735 0.435737 -0.0123417 0.081735 0.436522 -0.0103056 0.081735 0.436872 -0.0104119 0.081369 0.437362 -0.00823009 0.081369 0.437161 -0.00600004 0.081735 0.431739 -0.0174659 0.081735 0.43322 -0.015871 0.082235 0.435616 -0.0122844 0.082235 0.436868 -0.00815674 0.082235 0.437 -0.00817639 0.081735 0.430619 -0.0184565 0.082235 0.430013 -0.0198235 0.081735 0.42951 -0.0212314 0.082235 0.430002 -0.024148 0.081735 0.430709 -0.0254397 0.081735 0.431715 -0.0265146 0.081735 0.4329 -0.0274263 0.082235 0.430353 -0.0199593 0.081369 0.430727 -0.0185356 0.081735 0.429643 -0.0212486 0.081735 0.429639 -0.022721 0.081735 0.430342 -0.024014 0.081369 0.431971 -0.0177488 0.081369 0.431426 -0.0190471 0.081235 0.431022 -0.0187518 0.081369 0.430502 -0.0213595 0.081235 0.430006 -0.0212955 0.081369 0.430002 -0.022676 0.081369 0.43141 -0.0249319 0.081235 0.431005 -0.0252251 0.081369 0.431949 -0.0262329 0.081369 0.432268 -0.0258481 0.081235 0.437564 -0.0294575 0.081235 0.436042 -0.0294313 0.082235 0.436961 -0.0300788 0.081735 0.433113 -0.0269741 0.081369 0.436682 -0.0286633 0.081235 0.436362 -0.0290473 0.081369 0.432957 -0.0273051 0.081735 0.436128 -0.0293284 0.081735 0.441663 -0.037566 0.0806733 0.440456 -0.0348943 0.0813437 0.440198 -0.0350712 0.0820609 0.441108 -0.0377963 0.0812253 0.440774 -0.0347406 0.0811246 0.439614 -0.0318765 0.0812168 0.439307 -0.0320862 0.0812834 0.437216 -0.0298162 0.081369 0.437072 -0.0299648 0.0815279 0.439025 -0.0322828 0.0815051 0.436917 -0.0301245 0.0818669 0.441324 -0.0376797 0.080888 0.440253 -0.0350121 0.0816868 0.438842 -0.0324151 0.081846 0.438787 -0.0324608 0.0822166 0.436868 -0.0301749 0.082235 0.441518 -0.0436319 0.0787203 0.44162 -0.0404744 0.0800416 0.441397 -0.0405924 0.0803594 0.441959 -0.0403968 0.0798328 0.443871 -0.0598493 0.0503486 0.44192 -0.0588361 0.0610464 0.442069 -0.0588398 0.0599377 0.442482 -0.0539169 0.0684796 0.441376 -0.0437665 0.0789644 0.442018 -0.0434565 0.0784022 0.442003 -0.050962 0.0723574 0.441963 -0.047459 0.0757044 0.441739 -0.0435251 0.0785266 0.442369 -0.0509072 0.0723149 0.441666 -0.0511279 0.0725008 0.441625 -0.0476 0.0758757 0.441402 -0.0478142 0.076137 0.44162 -0.0435743 0.0786158 0.442118 -0.0539799 0.0685087 0.442685 -0.0563727 0.0642959 0.442873 -0.0576621 0.0613939 0.442323 -0.0564419 0.06431 0.441782 -0.0541651 0.068622 0.441988 -0.0566426 0.0643913 0.441558 -0.0544428 0.0688025 0.441443 -0.051378 0.0727224 0.44299 -0.0582357 0.0598056 0.442628 -0.0583086 0.0598028 0.443024 -0.0594732 0.0551372 0.442293 -0.0585214 0.0598485 0.442877 -0.060849 0.0502692 0.442947 -0.0604815 0.0502677 0.441993 -0.0591846 0.0600466 0.442466 -0.0600257 0.0551805 0.442689 -0.0596937 0.0551443 0.441764 -0.0569425 0.0645285 0.441687 -0.0572672 0.0646864 0.441331 -0.0480466 0.0764213 0.443169 -0.060143 0.0502827 0.443506 -0.0599202 0.0503123 0.443712 -0.06004 0.045317 0.444417 -0.0597492 0.0454095 0.446787 -0.0587299 0.0205093 0.447685 -0.0582711 0.0115569 0.447397 -0.0581856 0.00804679 0.445934 -0.0573704 -0.010611 0.44633 -0.0573116 -0.0104201 0.445151 -0.0570327 -0.0168077 0.443151 -0.0566308 -0.0260135 0.441344 -0.056278 -0.0340919 0.439521 -0.0560356 -0.041181 0.43796 -0.0554267 -0.0535905 0.438964 -0.0565965 -0.0410993 0.438892 -0.0569648 -0.0411017 0.441495 -0.0574986 -0.0288426 0.444171 -0.0580317 -0.0166529 0.444243 -0.0576635 -0.0166514 0.445375 -0.0579314 -0.010543 0.446714 -0.0584736 0.00179239 0.446643 -0.0588432 0.00177959 0.446829 -0.0587471 0.0080179 0.446758 -0.0591172 0.0080012 0.443491 -0.0603795 0.0452772 0.44405 -0.0598179 0.045365 0.444948 -0.0598346 0.032848 0.446445 -0.0589513 0.0204714 0.446221 -0.0592918 0.020438 0.445598 -0.0575924 -0.010565 0.446231 -0.0582011 -0.00440298 0.444465 -0.0573248 -0.0166814 0.441788 -0.056792 -0.0288778 0.441568 -0.0571306 -0.0288428 0.439186 -0.0562577 -0.0411268 0.44212 -0.0565698 -0.0289431 0.444799 -0.0571027 -0.0167393 0.446455 -0.0578618 -0.00441301 0.446794 -0.0576399 -0.00444092 0.44694 -0.0581339 0.00179671 0.447281 -0.0579122 0.00179046 0.447054 -0.0584071 0.00803448 0.445513 -0.0592727 0.0329379 0.445172 -0.0594939 0.0328888 0.43711 -0.0546515 -0.0611527 0.437205 -0.0552609 -0.0574303 0.436751 -0.0548038 -0.0611555 0.436868 -0.055483 -0.0574232 0.436602 -0.0549313 -0.0611491 0.436646 -0.0558193 -0.0574366 0.436574 -0.0561841 -0.0574655 0.437602 -0.0554957 -0.0535526 0.437263 -0.0557176 -0.0535235 0.437038 -0.0560568 -0.0535127 0.436966 -0.0564258 -0.0535206 0.436173 -0.0583331 -0.0612292 0.436319 -0.0556547 -0.0610894 0.435824 -0.0582181 -0.0615616 0.437307 -0.0546338 -0.0611427 0.436923 -0.0547088 -0.0611569 0.43648 -0.0544003 -0.061555 0.435935 -0.0550797 -0.0615608 0.43648 -0.0550875 -0.0611384 0.435851 -0.0553623 -0.0615614 0.436391 -0.055264 -0.0611244 0.436337 -0.055456 -0.0611077 0.435824 -0.0556547 -0.0615616 0.450396 -0.0545466 -0.0591546 0.437319 -0.0541446 -0.061539 0.441771 -0.0542086 -0.0612246 0.445835 -0.0548415 -0.0600634 0.446135 -0.0543566 -0.0604194 0.478051 -0.0303599 -0.0515713 0.454565 -0.0547172 -0.0575861 0.45791 -0.0550556 -0.0557524 0.459108 -0.0548837 -0.0552792 0.460283 -0.0541927 -0.0552675 0.463314 -0.0538301 -0.0537261 0.466857 -0.0522657 -0.0526487 0.475384 -0.0418219 -0.0516491 0.47405 -0.0444977 -0.0517389 0.473147 -0.0467034 -0.0514674 0.468118 -0.0509889 -0.0526929 0.467008 -0.0516856 -0.052977 0.478372 -0.0320566 -0.0511846 0.479179 -0.0154633 -0.0515654 0.479558 -0.00034735 -0.051565 0.479558 -4.56064e-08 -0.051565 0.479558 0.000347266 -0.051565 0.480043 0.000347768 -0.0511827 0.478532 0.0303952 -0.0511845 0.479184 0.0153721 -0.0515654 0.477403 0.0351617 -0.0515803 0.478368 0.0320924 -0.0511846 0.478052 0.0303572 -0.0515713 0.477043 0.0386113 -0.0512079 0.474251 0.0450435 -0.0513615 0.475835 0.0419478 -0.0512555 0.472888 0.0463042 -0.0518517 0.471364 0.0481873 -0.0520528 0.470671 0.0495001 -0.0518134 0.463502 0.0532971 -0.0540662 0.465981 0.0527245 -0.0528892 0.465647 0.0524073 -0.0533667 0.467709 0.0512603 -0.0527937 0.460667 0.0545778 -0.0546787 0.459095 0.0544118 -0.0557411 0.45659 0.0551807 -0.0562812 0.44606 0.0548511 -0.0600077 0.449869 0.0545227 -0.0593332 0.44618 0.0543584 -0.0604085 0.441332 0.0546896 -0.0608723 0.445181 0.0548144 -0.0602165 0.442469 0.0542268 -0.0611312 0.437319 0.0541445 -0.061539 0.437307 0.0546337 -0.0611427 0.436255 0.0545881 -0.0615578 0.436391 0.0552631 -0.0611244 0.436741 0.0542586 -0.0615511 0.436602 0.0549307 -0.0611492 0.435824 0.0556546 -0.0615616 0.436319 0.0556546 -0.0610894 0.436173 0.058333 -0.0612292 0.435926 -0.0583344 -0.0614644 0.436026 -0.058448 -0.0613692 0.435424 -0.0587093 -0.0611551 0.435073 -0.0587091 -0.0611561 0.434327 -0.058709 -0.0611565 0.429888 -0.0560276 -0.061565 0.430314 -0.0575258 -0.0610985 0.429589 -0.0546753 -0.061565 0.428844 -0.0509511 -0.0610332 0.427145 -0.0437326 -0.0610511 0.426072 -0.040088 -0.061565 0.423961 -0.0373783 -0.0610136 0.407288 -4.18639e-08 -0.061565 0.407628 -0.00751942 -0.061565 0.408022 -0.0112755 -0.0606792 0.409201 -0.0149244 -0.0606986 0.409517 -0.0147973 -0.061565 0.410822 -0.0184267 -0.0607291 0.41309 -0.0215008 -0.061565 0.414578 -0.0244218 -0.0608096 0.41752 -0.0276412 -0.061565 0.429589 0.0546753 -0.061565 0.429344 0.05093 -0.061565 0.425693 0.0404429 -0.0610394 0.426138 0.0402167 -0.061565 0.424278 0.036945 -0.061565 0.421776 0.0341035 -0.0609718 0.422176 0.0338183 -0.061565 0.412854 0.0218801 -0.0607713 0.410918 0.0186065 -0.060731 0.408062 0.0114343 -0.0606798 0.408371 0.0113529 -0.061565 0.40764 0.00761517 -0.061565 0.406987 -4.19898e-08 -0.0606657 0.433174 0.0582174 -0.061565 0.429889 0.0560304 -0.061565 0.435926 0.0583343 -0.0614644 0.435073 0.058709 -0.0611561 0.436026 0.0584479 -0.0613692 0.479679 0.0324352 -0.044501 0.479424 0.0327043 -0.0454952 0.479083 0.0331048 -0.0471971 0.478936 0.0327524 -0.0479625 0.478662 0.0313571 -0.0500331 0.478705 0.0319933 -0.0497278 0.478584 0.0302709 -0.0505394 0.478172 0.0311265 -0.0497001 0.478378 0.0311453 -0.0497426 0.478655 0.0324349 -0.0478258 0.478455 0.0324023 -0.047784 0.478312 0.0320421 -0.0486327 0.478281 0.0319146 -0.0488385 0.47896 0.032347 -0.0455096 0.478687 0.0325487 -0.0466391 0.478881 0.0325905 -0.0466761 0.478666 0.03255 -0.046735 0.479815 0.0300549 -0.0431583 0.479608 0.030651 -0.0434444 0.479854 0.0311418 -0.0436104 0.479954 0.0300895 -0.0431215 0.480133 0.0301663 -0.0429847 0.480058 0.0301278 -0.0430596 0.47916 0.0329179 -0.0467225 0.478836 0.0325598 -0.0478909 0.478768 0.0322171 -0.0491023 0.478563 0.0312278 -0.0498626 0.47852 0.030232 -0.0504404 0.478975 0.0326454 -0.0466931 0.479057 0.032722 -0.0467073 0.478752 0.032486 -0.0478562 0.478584 0.031983 -0.048923 0.478669 0.0320474 -0.0489767 0.479692 0.0310561 -0.043674 0.479593 0.031982 -0.0444687 0.479702 0.0321331 -0.0443878 0.479965 0.0312522 -0.0434971 0.47912 0.0320918 -0.0449261 0.479147 0.0323962 -0.0455361 0.479428 0.0318705 -0.0445051 0.479318 0.0325233 -0.0455323 0.478486 0.0319393 -0.0488812 0.478336 0.0301803 -0.0503049 0.478478 0.0311786 -0.0497934 0.480215 0.0282274 -0.0429049 0.4799 0.0300742 -0.0431409 0.478721 0.028337 -0.0511245 0.479034 0.0265402 -0.0505077 0.479536 0.0250319 -0.0489205 0.479054 0.0265152 -0.0502566 0.480303 0.0250769 -0.045004 0.480518 0.0262673 -0.0433469 0.480435 0.025288 -0.0443417 0.480357 0.024933 -0.0449414 0.479957 0.0246657 -0.0469424 0.480522 0.0268159 -0.0430063 0.480289 0.0282257 -0.0428528 0.48006 0.0301285 -0.0430583 0.479731 0.0300411 -0.043161 0.479915 0.0287519 -0.0429349 0.478127 0.0301659 -0.0502613 0.47825 0.0292778 -0.0505089 0.478688 0.0283669 -0.0508089 0.478639 0.0293527 -0.0509015 0.478618 0.0303108 -0.0506402 0.478613 0.0303898 -0.0508371 0.47871 0.0284369 -0.0511341 0.480222 0.030256 -0.0427739 0.480403 0.028215 -0.042715 0.478723 0.0283592 -0.0509194 0.479014 0.0265655 -0.0501665 0.479506 0.0251893 -0.0488255 0.479399 0.0253304 -0.0487185 0.479847 0.0248202 -0.0469151 0.48019 0.0252095 -0.0450526 0.479879 0.0253704 -0.0449976 0.480109 0.0265067 -0.0436595 0.480029 0.0265565 -0.043632 0.479967 0.0282266 -0.0429712 0.48005 0.0282232 -0.0429648 0.478677 0.0266501 -0.0499138 0.479049 0.0254236 -0.0485722 0.479139 0.0254264 -0.0485951 0.479599 0.0249443 -0.0468604 0.478541 0.0283698 -0.0506217 0.478442 0.0283649 -0.0505605 0.478586 0.0274677 -0.0503582 0.478337 0.0283565 -0.0505251 0.47887 0.0266354 -0.0500079 0.480034 0.0252997 -0.0450745 0.479771 0.0248787 -0.0468977 0.480134 0.0282265 -0.0429425 0.478386 0.0274506 -0.0503059 0.478484 0.0274629 -0.0503212 0.478776 0.0266496 -0.0499513 0.479232 0.0254126 -0.0486277 0.479686 0.0249204 -0.0468791 0.47995 0.0253242 -0.0450744 0.480192 0.0264928 -0.0436437 0.480457 0.0272419 -0.0429763 0.480346 0.026439 -0.0435759 0.48046 0.0263577 -0.0434687 0.480116 0.0252612 -0.0450672 0.47932 0.0253805 -0.0486695 0.478952 0.0266067 -0.0500813 0.478625 0.0283706 -0.0507066 0.478356 0.0292881 -0.0505428 0.478436 0.0302019 -0.0503623 0.479958 -0.0246667 -0.0469391 0.479499 -0.0252029 -0.0488474 0.479044 -0.0265539 -0.0502804 0.478616 -0.0284371 -0.0507105 0.47853 -0.0284351 -0.0506255 0.478434 -0.0302029 -0.0503595 0.478242 -0.0293492 -0.0504973 0.478189 -0.028749 -0.0505351 0.478225 -0.0284355 -0.0505219 0.478524 -0.0268493 -0.0500253 0.478325 -0.0284207 -0.0505303 0.479229 -0.025152 -0.0479571 0.479539 -0.02495 -0.046735 0.47995 -0.0253351 -0.0450537 0.480107 -0.0265479 -0.0436306 0.479904 -0.0254589 -0.0448356 0.479871 -0.0253453 -0.0450475 0.480033 -0.0268505 -0.0434437 0.480041 -0.0282914 -0.0429564 0.479915 -0.0287518 -0.0429352 0.48013 -0.0301607 -0.0429881 0.480294 -0.0293048 -0.042709 0.480282 -0.028297 -0.042845 0.480397 -0.0282891 -0.0427062 0.480461 -0.0264024 -0.0434376 0.480455 -0.0273003 -0.0429541 0.480458 -0.0254448 -0.0441337 0.479391 -0.0253441 -0.0487387 0.479529 -0.025045 -0.048944 0.479312 -0.0253939 -0.0486892 0.479846 -0.0248218 -0.0469116 0.480191 -0.0252214 -0.0450315 0.480306 -0.0250888 -0.044982 0.478348 -0.0293595 -0.0505303 0.47847 -0.0275147 -0.0503385 0.478572 -0.0275202 -0.0503747 0.47843 -0.0284293 -0.0505648 0.478679 -0.0284349 -0.0508133 0.478941 -0.0266441 -0.050103 0.478858 -0.0266719 -0.0500291 0.478763 -0.0266854 -0.0499726 0.478634 -0.0294298 -0.0508885 0.478715 -0.0284289 -0.0509247 0.478856 -0.027451 -0.0507171 0.479004 -0.0266036 -0.0501891 0.479957 -0.0300866 -0.0431191 0.480207 -0.0282974 -0.0428972 0.480116 -0.0252729 -0.0450464 0.480035 -0.0253111 -0.0450537 0.479596 -0.0249449 -0.0468566 0.48019 -0.0265346 -0.0436148 0.480125 -0.0282955 -0.0429346 0.479901 -0.0300706 -0.0431396 0.478663 -0.026685 -0.0499356 0.479222 -0.0254253 -0.0486472 0.479129 -0.0254383 -0.0486147 0.479684 -0.0249215 -0.0468754 0.479769 -0.0248802 -0.0468941 0.480346 -0.0264823 -0.0435464 0.480411 -0.0256486 -0.0441288 0.478613 -0.030391 -0.0508367 0.478613 -0.0303035 -0.050616 0.478666 -0.0315987 -0.0501087 0.478665 -0.031396 -0.0500019 0.478943 -0.0329546 -0.0480085 0.479173 -0.0331195 -0.0467208 0.48 -0.0313966 -0.0433872 0.480217 -0.030241 -0.0428061 0.479846 -0.0311739 -0.0436347 0.479732 -0.0300374 -0.0431597 0.478772 -0.0322361 -0.0490741 0.478939 -0.0327576 -0.0479447 0.479161 -0.0329179 -0.046719 0.480059 -0.0301243 -0.0430583 0.478958 -0.0323504 -0.0455195 0.479422 -0.0318848 -0.0445251 0.479146 -0.0320409 -0.0448353 0.479348 -0.031559 -0.0441757 0.479608 -0.0306532 -0.0434457 0.479812 -0.0300506 -0.0431573 0.479684 -0.0310872 -0.0436975 0.478175 -0.0311622 -0.0496712 0.478381 -0.0311811 -0.0497137 0.478142 -0.0306504 -0.0500259 0.47833 -0.0301811 -0.0503014 0.479957 -0.0312858 -0.0435223 0.479588 -0.0319967 -0.0444892 0.479145 -0.0323996 -0.0455461 0.478755 -0.032491 -0.0478395 0.478658 -0.0324398 -0.0478093 0.478489 -0.0319568 -0.0488551 0.478285 -0.031932 -0.0488123 0.478329 -0.0321044 -0.0485204 0.478882 -0.0325905 -0.0466729 0.47973 -0.032302 -0.0443066 0.479696 -0.0321486 -0.0444092 0.479421 -0.032708 -0.045506 0.479316 -0.0325268 -0.0455427 0.479058 -0.0327221 -0.0467039 0.478976 -0.0326454 -0.0466899 0.478839 -0.0325649 -0.0478739 0.478588 -0.0320007 -0.0488966 0.478673 -0.0320654 -0.0489498 0.478566 -0.0312647 -0.0498329 0.478481 -0.0312149 -0.0497642 0.47852 -0.0302339 -0.0504397 0.436319 0.0582181 -0.0610894 0.436935 0.0589233 -0.0537989 0.435924 0.0585777 -0.0612621 0.437479 0.0591103 -0.0495312 0.438328 0.0599621 -0.0414141 0.441399 0.0599965 -0.0292723 0.44409 0.0605297 -0.0170512 0.446128 0.0610679 -0.0046813 0.445631 0.0615674 -0.0046467 0.446634 0.0613408 0.00160342 0.446135 0.0618404 0.00160576 0.446259 0.0621144 0.0078816 0.44615 0.0621601 0.0204332 0.444046 0.063009 0.0398928 0.443416 0.0632457 0.0453131 0.442025 0.0619685 0.0596246 0.441526 0.0624488 0.0597258 0.442395 0.0638553 0.0500778 0.442892 0.0633554 0.0501217 0.442423 0.0629899 0.0548978 0.441504 0.0581047 0.0684379 0.441219 0.0607751 0.0643274 0.440834 0.0527854 0.0761531 0.440879 0.0557606 0.0727433 0.441327 0.0415563 0.0830608 0.441327 0.0428765 0.0825302 0.441327 0.0447816 0.0816093 0.440827 0.0473324 0.080672 0.440827 0.0408773 0.0838281 0.43984 0.0342786 0.084588 0.440471 0.0376553 0.0846643 0.435275 0.0294574 0.085235 0.438011 0.0314202 0.0847204 0.435579 0.0290608 0.084735 0.432687 0.0278784 0.085235 0.429424 0.0195882 0.085235 0.437027 0.00599996 0.084735 0.435915 0.0101215 0.085235 0.434134 0.0138883 0.085235 0.431654 0.0173623 0.084735 0.431336 0.0169758 0.085235 0.437027 -0.00600004 0.084735 0.431336 -0.0169759 0.085235 0.434134 -0.0138884 0.085235 0.43455 -0.0141661 0.084735 0.436394 -0.0102668 0.084735 0.429889 -0.0197738 0.084735 0.42901 -0.0227989 0.085235 0.4306 -0.0255182 0.084735 0.4329 -0.0274263 0.084735 0.435275 -0.0294575 0.085235 0.440473 -0.0376674 0.084662 0.439843 -0.0342839 0.0845876 0.439393 -0.0345446 0.0850859 0.439043 -0.0328513 0.0846766 0.437627 -0.0317497 0.0852203 0.441327 -0.0447817 0.0816093 0.441327 -0.0407206 0.0833533 0.440827 -0.0408773 0.0838281 0.440865 -0.0551925 0.0734591 0.44138 -0.0553952 0.0724096 0.44088 -0.0557908 0.0727045 0.441006 -0.0585514 0.0686449 0.441058 -0.0592467 0.067428 0.441219 -0.0607793 0.064318 0.44192 -0.0615222 0.0610492 0.441445 -0.0621088 0.0608321 0.441527 -0.0624534 0.0597102 0.442423 -0.062991 0.0548907 0.441925 -0.0634859 0.0549158 0.443416 -0.0632458 0.0453131 0.444046 -0.0630091 0.0398926 0.446231 -0.0621164 0.0194284 0.445643 -0.0626643 0.0204753 0.44437 -0.0632049 0.0328565 0.446141 -0.0621648 0.0205385 0.446648 -0.0613533 0.00188823 0.446166 -0.0610825 -0.00434565 0.445669 -0.061582 -0.00431272 0.444145 -0.0605414 -0.0167831 0.444804 -0.0613111 -0.0105186 0.443655 -0.061041 -0.0167054 0.440952 -0.0605041 -0.0290011 0.436438 -0.0594229 -0.053765 0.435924 -0.0585778 -0.061262 0.436562 -0.0586933 -0.0576096 0.403222 0.0190235 0.0763893 0.403356 0.0189347 0.0767952 0.404448 0.019014 0.0801447 0.403789 0.0182557 0.0772335 0.405459 0.0182 0.0813384 0.405085 0.0190094 0.0814711 0.405865 0.0190052 0.0828662 0.409389 0.0182 0.0846204 0.409299 0.0187899 0.085104 0.408162 0.0182 0.0842583 0.40798 0.0188748 0.0846903 0.433598 0.0106687 0.084735 0.430954 0.0146267 0.084735 0.431307 0.0149802 0.085235 0.426996 0.0172713 0.084735 0.427187 0.0177332 0.085235 0.434527 -0.00600004 0.084735 0.434527 0.00599996 0.084735 0.422327 -0.0187 0.085235 0.426996 -0.0172714 0.084735 0.427187 -0.0177333 0.085235 0.430954 -0.0146267 0.084735 0.433598 -0.0106688 0.084735 0.431307 -0.0149803 0.085235 0.435027 -0.00600004 0.085235 0.406204 -0.0182 0.0826623 0.408162 -0.0182 0.0842584 0.40798 -0.0188749 0.0846903 0.409389 -0.0182 0.0846204 0.409299 -0.0187899 0.085104 0.403898 -0.019019 0.0787719 0.405865 -0.0190053 0.0828662 0.403422 -0.0190243 0.077235 0.403243 -0.0190208 0.076478 0.448787 -0.0586802 0.055735 0.449663 -0.0586698 0.0556532 0.450284 -0.0586684 0.0554862 0.451535 -0.0591581 0.0555545 0.451059 -0.0586693 0.0551321 0.452223 -0.0591589 0.0550375 0.453177 -0.0591691 0.0538939 0.45291 -0.0591632 0.0542879 0.452399 -0.0586769 0.0539479 0.453309 -0.0588019 0.051235 0.453289 -0.0588377 0.0508129 0.453903 -0.0593083 0.0510318 0.453247 -0.0588673 0.0504926 0.452848 -0.0590005 0.0492523 0.453591 -0.0594428 0.0495346 0.452884 -0.0595814 0.0482484 0.452694 -0.0596083 0.048012 0.452013 -0.0591448 0.0480756 0.451781 -0.059704 0.0471742 0.451059 -0.0592363 0.0473381 0.45082 -0.0592511 0.0472093 0.45125 -0.0597405 0.0468406 0.449495 -0.0597857 0.0462616 0.448809 -0.0592842 0.046735 0.447978 -0.0597865 0.0462839 0.443945 -0.0598546 0.0500833 0.444912 -0.0593579 0.048985 0.444767 -0.0595405 0.0542479 0.444509 -0.059215 0.0525624 0.443814 -0.0598047 0.0514969 0.445171 -0.0590454 0.0538844 0.447824 -0.0587113 0.055626 0.448077 -0.0587 0.0556751 0.446574 0.059283 0.0558023 0.447338 0.0587427 0.055488 0.445414 0.0594282 0.0549868 0.445182 0.059043 0.0538987 0.444472 0.0596016 0.0537846 0.444546 0.0592031 0.0526758 0.444309 0.0593173 0.051235 0.443819 0.0598306 0.0509383 0.444332 0.059338 0.0507752 0.444694 0.0593611 0.0494124 0.444273 0.0598608 0.0491294 0.444912 0.0593578 0.048985 0.444817 0.0598494 0.0482133 0.446597 0.0593101 0.0473163 0.44581 0.0598218 0.0472169 0.448809 0.0592842 0.046735 0.447994 0.0592876 0.0468095 0.448809 0.0586797 0.055735 0.449456 0.0586711 0.0556883 0.449809 0.0591583 0.056241 0.450844 0.0586689 0.0552487 0.451059 0.0586692 0.0551321 0.452928 0.0591638 0.054264 0.451995 0.0586721 0.0544132 0.451232 0.0586696 0.055027 0.451558 0.0591581 0.0555393 0.452437 0.0586775 0.0538972 0.45388 0.0593302 0.050759 0.453309 0.0588018 0.051235 0.453737 0.0592116 0.0525888 0.453257 0.058753 0.051917 0.453344 0.0595008 0.0489777 0.452701 0.0596073 0.0480204 0.452486 0.0590741 0.0486409 0.450979 0.0592415 0.0472931 0.449495 0.0597856 0.0462616 0.451255 0.0597401 0.0468439 0.45039 0.0592709 0.047022 0.401064 0.0144436 0.077235 0.40046 0.0133528 0.077235 0.399633 0.0123519 0.0771828 0.398031 0.00490737 0.0771897 0.398258 0.00742709 0.0771872 0.399298 0.010567 0.077235 0.40176 0.0170474 0.0767224 0.401669 0.017115 0.0764015 0.400318 0.0148859 0.0767338 0.400218 0.0149452 0.0764181 0.399028 0.0126148 0.0764399 0.399138 0.0125667 0.0767486 0.398144 0.0101113 0.0764681 0.397737 0.00750341 0.0767899 0.397513 0.00493137 0.0768129 0.397964 0.00747012 0.0770333 0.398265 0.0100773 0.0767676 0.400517 0.014768 0.0770069 0.398024 1.17537e-06 0.0771921 0.397741 0.0049208 0.077044 0.398779 0.0099333 0.0771848 0.398487 0.0100151 0.0770228 0.39935 0.0124747 0.0770139 0.400785 0.0146087 0.0771812 0.402197 0.0167205 0.07718 0.401945 0.0169091 0.0770016 0.403552 0.0186752 0.0770955 0.402468 -0.0165368 0.077235 0.398794 -0.00999316 0.0771841 0.398267 -0.00750206 0.0771865 0.39876 -0.008521 0.077235 0.398402 -0.00601082 0.077235 0.398033 -0.00499731 0.077189 0.398314 1.84642e-06 0.077235 0.402204 -0.0167341 0.0771793 0.400799 -0.0146358 0.0771805 0.399649 -0.0123944 0.0771821 0.403471 -0.0187938 0.0769957 0.403392 -0.018895 0.0768667 0.403222 -0.0190236 0.0763893 0.401679 -0.0171277 0.0764014 0.399046 -0.012658 0.0764395 0.398161 -0.0101727 0.0764674 0.398279 -0.0101392 0.0767619 0.397745 -0.00758042 0.0767843 0.397514 -0.00502287 0.0768074 0.39738 -0.00502945 0.0765352 0.397514 -3.98632e-09 0.0768356 0.403308 -0.0176028 0.077235 0.403569 -0.0186492 0.0771124 0.401951 -0.0169236 0.0769987 0.40053 -0.0147961 0.0770041 0.399365 -0.0125184 0.0770111 0.401766 -0.0170619 0.0767168 0.400331 -0.0149142 0.0767282 0.398501 -0.0100763 0.07702 0.399154 -0.0126109 0.076743 0.397972 -0.00754633 0.0770305 0.397742 -0.00501165 0.0770413 0.397741 5.19933e-07 0.0770544 0.457327 0.0514 -0.0636624 0.461345 0.0506007 -0.0636624 0.461115 0.0500464 -0.0642624 0.464751 0.0483246 -0.0636624 0.467028 0.0449181 -0.0636624 0.466473 0.0446885 -0.0642624 0.467227 -0.0409 -0.0642624 0.467028 -0.0449182 -0.0636624 0.464751 -0.0483247 -0.0636624 0.461115 -0.0500464 -0.0642624 0.457327 -0.0514 -0.0636624 0.432626 0.0449181 -0.0636624 0.435326 0.0479003 -0.0642624 0.434902 0.0483246 -0.0636624 0.438538 0.0500464 -0.0642624 0.442327 -0.0514 -0.0636624 0.442327 -0.0508 -0.0642624 0.438309 -0.0506008 -0.0636624 0.435326 -0.0479004 -0.0642624 0.432427 -0.0409 -0.0642624 0.431827 -0.0409 -0.0636624 0.432427 0.0409 -0.0642624 0.431827 0.0409 -0.0636624 0.427539 0.0416632 0.0807489 0.418441 0.0317984 0.0786974 0.426126 0.0379717 0.0824466 0.423377 0.0346676 0.082621 0.423924 0.0351594 0.0827508 0.424941 0.0362665 0.0827676 0.425475 0.0369844 0.0826478 0.42157 0.0337195 0.080989 0.419885 0.0341532 0.0695552 0.417465 0.0317997 0.0688237 0.423654 0.0388975 0.0648733 0.424524 0.039739 0.0690608 0.425291 0.0413627 0.0657685 0.426591 0.0427921 0.0755624 0.425126 0.0397741 0.0760131 0.427403 0.0407394 0.0815562 0.427166 0.0400163 0.0818873 0.421053 0.035509 0.0648465 0.420954 0.0340075 0.078765 0.417529 0.0318085 0.0745415 0.420197 0.0342412 0.0742103 0.423446 0.0366758 0.0784789 0.426187 0.0393208 0.0804994 0.424032 0.0364093 0.0807096 0.424541 0.0402122 0.0651107 0.42233 0.0368556 0.0692798 0.424826 0.0398339 0.0737179 0.42269 0.0369086 0.0739239 0.425601 0.0395872 0.0782686 0.427097 0.0408977 0.080432 0.415926 -0.0303372 0.067667 0.409176 -0.0237876 0.0667057 0.40872 -0.0219338 0.0645522 0.403941 -0.0181338 0.0672721 0.405026 -0.0186594 0.0662052 0.402108 -0.0180831 0.0726942 0.405386 -0.0210448 0.0694374 0.40306 -0.0179381 0.0686184 0.405209 -0.020989 0.0769525 0.405352 -0.0215445 0.0742438 0.404654 -0.0206348 0.0760112 0.403813 -0.0198839 0.0752595 0.403522 -0.0195982 0.0750608 0.410238 -0.024161 0.0811372 0.412469 -0.0250068 0.0831175 0.416853 -0.0291756 0.0820067 0.417256 -0.0299035 0.081118 0.417296 -0.0303541 0.0800728 0.417024 -0.0305047 0.0789762 0.416028 -0.0305061 0.0688095 0.408885 -0.0243033 0.069106 0.413244 -0.0276631 0.0783971 0.413812 -0.0273461 0.0808066 0.412059 -0.0246756 0.0831014 0.406271 -0.0194987 0.0653326 0.405843 -0.0203677 0.067039 0.405248 -0.021412 0.0718393 0.408926 -0.024731 0.0739131 0.409609 -0.0245359 0.0787271 0.406136 -0.0212523 0.0790589 0.405866 -0.0210122 0.0789889 0.428964 -0.0562195 0.0680388 0.429003 -0.0557306 0.0691571 0.428335 -0.0524723 0.0715719 0.4288 -0.0563047 0.0667283 0.428758 -0.0552028 0.0641698 0.428711 -0.0558225 0.0651738 0.428521 -0.0517096 0.0628394 0.427929 -0.0494072 0.0688112 0.427718 -0.0473493 0.0669633 0.42761 -0.0471294 0.0643919 0.426983 -0.0449593 0.0657813 0.427256 -0.0458972 0.0649255 0.428616 -0.0508826 0.0750619 0.428039 -0.0478674 0.0760854 0.427821 -0.046662 0.0758814 0.427159 -0.0449432 0.0697944 0.427604 -0.0469446 0.0716128 0.428064 -0.0514833 0.0706688 0.428703 -0.0559458 0.065425 0.444214 0.0174409 0.081235 0.443312 0.016613 0.081235 0.444428 0.0161 0.0812371 0.443086 0.00268724 0.081235 0.444428 0.00289998 0.0812368 0.443914 0.00178477 0.081235 0.454082 0.0181055 0.0808955 0.446827 0.0181 0.0812351 0.450735 0.0181008 0.0811843 0.446827 0.00089996 0.0812351 0.450972 0.000900108 0.0811905 0.451261 0.000900114 0.0811804 0.455408 0.000900653 0.080831 0.458454 0.000901033 0.0802098 0.459006 0.0181187 0.0797073 0.459248 0.000901163 0.0799775 0.462942 0.0181287 0.0778141 0.464345 0.0181312 0.076872 0.462759 0.00090144 0.0784974 0.463995 0.000901534 0.0777671 0.465933 0.000901734 0.0763589 0.466568 0.000901816 0.0758193 0.468718 0.0181346 0.0727768 0.469719 0.000962371 0.0724852 0.470065 0.0179092 0.071109 0.471927 0.00211217 0.0693677 0.473079 0.00497621 0.0673726 0.472612 0.00304195 0.0682348 0.472768 0.0144673 0.0672898 0.472029 0.0164536 0.0683448 0.472778 0.0143105 0.0672862 0.471466 0.0161113 0.069267 0.472796 0.0139252 0.0672905 0.443312 -0.00238704 0.081235 0.444428 -0.00290008 0.0812368 0.446827 -0.000900044 0.0812351 0.443086 -0.0163128 0.081235 0.442427 -0.0141001 0.081235 0.446427 -0.0181 0.0812351 0.444428 -0.0161001 0.0812371 0.443914 -0.0172152 0.081235 0.452863 -0.000900242 0.0810961 0.452016 -0.0181022 0.0811127 0.455288 -0.018108 0.080701 0.456801 -0.000900905 0.0805953 0.458294 -0.0181167 0.0799498 0.464532 -0.000901669 0.0774107 0.466277 -0.0181334 0.0752982 0.467019 -0.000901955 0.0754112 0.468718 -0.0181347 0.0727769 0.471766 -0.00305197 0.0696025 0.471467 -0.017082 0.069174 -0.14165 0.02665 0.088235 -0.139315 0.05205 0.088235 -0.13965 0.0533 0.088235 -0.141307 0.055022 0.088235 -0.140332 0.0564819 0.088235 -0.139315 0.05455 0.088235 -0.13715 0.02665 0.088235 -0.13965 -4.19898e-08 0.088235 -0.13465 -4.19898e-08 0.088235 -0.13715 -0.00250004 0.088235 -0.1384 -0.00216511 0.088235 -0.134984 0.00124996 0.088235 -0.13715 -0.02665 0.088235 -0.102975 -0.02665 0.088235 -0.134984 -0.05205 0.088235 -0.13715 -0.0508 0.088235 -0.13715 -0.0558 0.088235 -0.134984 -0.05455 0.088235 -0.138872 -0.0574575 0.088235 -0.0700496 0.0511349 0.088235 -0.0709646 0.05205 0.088235 -0.0712996 0.0533 0.088235 -0.102975 0.0578 0.088235 -0.0709646 0.05455 0.088235 -0.0687996 0.0558 0.088235 -0.0675496 0.055465 0.088235 -0.0662996 0.0533 0.088235 -0.0652996 0.02665 0.088235 -0.0670775 -0.0574575 0.088235 -0.0700496 -0.0554651 0.088235 -0.0662996 -0.0533 0.088235 -0.0675496 -0.0554651 0.088235 -0.0652996 -0.02665 0.088235 -0.0666345 -0.05205 0.088235 -0.0712996 -0.0533 0.088235 -0.0709646 -0.05455 0.088235 -0.102975 -0.0568 0.088235 -0.13715 -0.0568 0.088235 -0.13715 -0.0578 0.088235 -0.102975 -0.0578 0.088235 -0.0687996 -0.0578 0.088235 -0.0700496 -0.051135 0.088235 -0.0709646 -0.05205 0.088235 -0.102975 0.02665 0.088235 -0.0709646 -0.00125004 0.088235 -0.0700496 0.00216502 0.088235 -0.0687996 0.00249996 0.088235 -0.0675496 0.00216502 0.088235 -0.0666345 0.00124996 0.088235 -0.0662996 -4.19898e-08 0.088235 -0.0642996 -0.0533 0.088235 -0.0642996 -0.02665 0.088235 -0.0642996 0.02665 0.088235 -0.0642996 0.0533 0.088235 -0.0646421 0.055022 0.088235 -0.13715 -0.0583 0.085535 -0.0687996 -0.0583 0.087735 -0.0668861 -0.0579194 0.085535 -0.0668861 -0.0579194 0.087735 -0.065264 -0.0568356 0.085535 -0.065264 -0.0568356 0.087735 -0.0637996 -0.0533 0.085535 -0.0637996 0.0533 0.085535 -0.0637996 0.0533 0.087735 -0.065264 0.0568355 0.087735 -0.0668861 0.0579194 0.087735 -0.0668861 0.0579194 0.085535 -0.0687996 0.0583 0.085535 -0.0687996 0.0583 0.087735 -0.139063 0.0579194 0.085535 -0.139063 0.0579194 0.087735 -0.141769 0.0552134 0.087735 -0.14215 0.0533 0.085535 -0.141769 -0.0552135 0.085535 -0.141769 -0.0552135 0.087735 -0.140685 -0.0568356 0.087735 -0.140685 -0.0568356 0.085535 -0.139063 -0.0579194 0.085535 -0.139063 -0.0579194 0.087735 -0.0687996 0.05535 0.085235 -0.0654246 -0.049725 0.085235 -0.0687996 -0.05125 0.085235 -0.128407 0.0477508 0.085235 -0.0723746 0.049725 0.085235 -0.0775417 0.0477508 0.085235 -0.0797996 0.0482 0.085235 -0.12615 0.0482 0.085235 -0.133575 0.025125 0.085235 -0.1316 0.0445578 0.085235 -0.0738996 0.00499996 0.085235 -0.0738996 0.0423 0.085235 -0.13205 0.00499996 0.085235 -0.131024 0.00252508 0.085235 -0.0773996 0.00149996 0.085235 -0.14185 -4.19898e-08 0.085235 -0.14185 0.025125 0.085235 -0.1351 -4.19898e-08 0.085235 -0.0705749 -0.00102504 0.085235 -0.0705749 0.00102496 0.085235 -0.0698246 -0.00177539 0.085235 -0.0677746 -0.00177539 0.085235 -0.0667496 -4.19898e-08 0.085235 -0.0670242 0.00102496 0.085235 -0.0723746 -0.049725 0.085235 -0.0708496 -0.0533 0.085235 -0.0687996 -0.05535 0.085235 -0.0670009 -0.0576423 0.085235 -0.0677746 -0.0550754 0.085235 -0.0670242 -0.054325 0.085235 -0.0723746 0.058 0.085235 -0.0644573 0.0550986 0.085235 -0.0667496 0.0533 0.085235 -0.0654762 0.0566234 0.085235 -0.0670009 0.0576422 0.085235 -0.138175 0.0515246 0.085235 -0.133575 0.049725 0.085235 -0.138925 0.052275 0.085235 -0.14185 0.049725 0.085235 -0.14185 0.0533 0.085235 -0.138925 0.054325 0.085235 -0.140473 0.0566234 0.085235 -0.138175 0.0550753 0.085235 -0.138948 0.0576422 0.085235 -0.13715 0.058 0.085235 -0.136125 0.0550753 0.085235 -0.1351 0.0533 0.085235 -0.136125 -0.0550754 0.085235 -0.14185 -0.049725 0.085235 -0.138175 -0.00177539 0.085235 -0.13715 -0.05125 0.085235 -0.138175 -0.0515247 0.085235 -0.138925 -0.052275 0.085235 -0.14185 -0.0533 0.085235 -0.1392 -0.0533 0.085235 -0.138925 -0.054325 0.085235 -0.135374 -0.054325 0.085235 -0.1351 -0.0533 0.085235 -0.135374 -0.052275 0.085235 -0.138948 -0.0576423 0.085235 -0.0640996 0.049725 0.085235 -0.0654246 0.025125 0.085235 -0.0640996 0.025125 0.085235 -0.0654246 -4.19898e-08 0.085235 -0.0640996 -4.19898e-08 0.085235 -0.0723746 0.025125 0.085235 -0.0654246 0.049725 0.085235 -0.0687996 0.05125 0.085235 -0.133575 0.058 0.085235 -0.0708496 0.0533 0.085235 -0.133575 -4.19898e-08 0.085235 -0.12855 0.00149996 0.085235 -0.12855 -0.00150004 0.085235 -0.0723746 -4.19898e-08 0.085235 -0.13205 -0.00500004 0.085235 -0.130321 -0.046472 0.085235 -0.0743487 -0.0445579 0.085235 -0.0738996 -0.00500004 0.085235 -0.0775417 -0.0477509 0.085235 -0.0723746 -0.056675 0.085235 -0.133575 -0.056675 0.085235 -0.133575 -0.049725 0.085235 -0.12615 -0.0482 0.085235 -0.13715 0.00204996 0.085235 -0.13715 0.05535 0.085235 -0.13715 0.05535 0.087785 -0.138175 0.0550753 0.087785 -0.1392 0.0533 0.085235 -0.13715 0.05125 0.085235 -0.136125 0.0515246 0.087785 -0.136125 0.0515246 0.085235 -0.135374 0.052275 0.087785 -0.135374 0.052275 0.085235 -0.1351 0.0533 0.087785 -0.135374 0.054325 0.085235 -0.136125 0.0550753 0.087785 -0.138925 0.054325 0.087785 -0.1384 0.055465 0.088235 -0.1392 0.0533 0.087785 -0.138925 0.052275 0.087785 -0.1384 0.0511349 0.088235 -0.138175 0.0515246 0.087785 -0.13715 0.05125 0.087785 -0.13715 0.0508 0.088235 -0.1359 0.0511349 0.088235 -0.134984 0.05205 0.088235 -0.135374 0.054325 0.087785 -0.13465 0.0533 0.088235 -0.134984 0.05455 0.088235 -0.1359 0.055465 0.088235 -0.13715 0.0558 0.088235 -0.0687996 0.05535 0.087785 -0.0698246 0.0550753 0.085235 -0.0705749 0.054325 0.085235 -0.0705749 0.054325 0.087785 -0.0705749 0.052275 0.085235 -0.0708496 0.0533 0.087785 -0.0705749 0.052275 0.087785 -0.0698246 0.0515246 0.085235 -0.0677746 0.0515246 0.085235 -0.0670242 0.052275 0.085235 -0.0667496 0.0533 0.087785 -0.0670242 0.054325 0.087785 -0.0670242 0.054325 0.085235 -0.0677746 0.0550753 0.085235 -0.0698246 0.0515246 0.087785 -0.0687996 0.05125 0.087785 -0.0687996 0.0508 0.088235 -0.0677746 0.0515246 0.087785 -0.0675496 0.0511349 0.088235 -0.0670242 0.052275 0.087785 -0.0666345 0.05205 0.088235 -0.0666345 0.05455 0.088235 -0.0677746 0.0550753 0.087785 -0.0698246 0.0550753 0.087785 -0.0700496 0.055465 0.088235 -0.138175 0.00177531 0.085235 -0.13715 0.00204996 0.087785 -0.138925 0.00102496 0.085235 -0.1392 -4.19898e-08 0.085235 -0.138925 -0.00102504 0.085235 -0.138925 -0.00102504 0.087785 -0.13715 -0.00205004 0.085235 -0.136125 -0.00177539 0.085235 -0.136125 -0.00177539 0.087785 -0.135374 -0.00102504 0.087785 -0.135374 -0.00102504 0.085235 -0.135374 0.00102496 0.085235 -0.136125 0.00177531 0.085235 -0.138175 0.00177531 0.087785 -0.138925 0.00102496 0.087785 -0.139315 0.00124996 0.088235 -0.1392 -4.19898e-08 0.087785 -0.139315 -0.00125004 0.088235 -0.138175 -0.00177539 0.087785 -0.13715 -0.00205004 0.087785 -0.1359 -0.00216511 0.088235 -0.134984 -0.00125004 0.088235 -0.1351 -4.19898e-08 0.087785 -0.135374 0.00102496 0.087785 -0.136125 0.00177531 0.087785 -0.1359 0.00216502 0.088235 -0.13715 0.00249996 0.088235 -0.1384 0.00216502 0.088235 -0.0698246 0.00177531 0.085235 -0.0698246 0.00177531 0.087785 -0.0708496 -4.19898e-08 0.085235 -0.0705749 0.00102496 0.087785 -0.0705749 -0.00102504 0.087785 -0.0698246 -0.00177539 0.087785 -0.0687996 -0.00205004 0.085235 -0.0687996 -0.00205004 0.087785 -0.0670242 -0.00102504 0.085235 -0.0670242 -0.00102504 0.087785 -0.0667496 -4.19898e-08 0.087785 -0.0670242 0.00102496 0.087785 -0.0677746 0.00177531 0.085235 -0.0687996 0.00204996 0.085235 -0.0687996 0.00204996 0.087785 -0.0709646 0.00124996 0.088235 -0.0708496 -4.19898e-08 0.087785 -0.0712996 -4.19898e-08 0.088235 -0.0700496 -0.00216511 0.088235 -0.0687996 -0.00250004 0.088235 -0.0677746 -0.00177539 0.087785 -0.0675496 -0.00216511 0.088235 -0.0666345 -0.00125004 0.088235 -0.0677746 0.00177531 0.087785 -0.13715 -0.05125 0.087785 -0.138925 -0.052275 0.087785 -0.1392 -0.0533 0.087785 -0.138175 -0.0550754 0.085235 -0.13715 -0.05535 0.087785 -0.13715 -0.05535 0.085235 -0.136125 -0.0550754 0.087785 -0.135374 -0.054325 0.087785 -0.135374 -0.052275 0.087785 -0.136125 -0.0515247 0.085235 -0.136125 -0.0515247 0.087785 -0.1384 -0.051135 0.088235 -0.139315 -0.05205 0.088235 -0.138925 -0.054325 0.087785 -0.13965 -0.0533 0.088235 -0.139315 -0.05455 0.088235 -0.138175 -0.0550754 0.087785 -0.1384 -0.0554651 0.088235 -0.1359 -0.0554651 0.088235 -0.1351 -0.0533 0.087785 -0.13465 -0.0533 0.088235 -0.1359 -0.051135 0.088235 -0.138175 -0.0515247 0.087785 -0.0687996 -0.05125 0.087785 -0.0698246 -0.0515247 0.085235 -0.0705749 -0.052275 0.085235 -0.0708496 -0.0533 0.087785 -0.0705749 -0.054325 0.085235 -0.0705749 -0.054325 0.087785 -0.0698246 -0.0550754 0.085235 -0.0698246 -0.0550754 0.087785 -0.0687996 -0.05535 0.087785 -0.0677746 -0.0550754 0.087785 -0.0670242 -0.054325 0.087785 -0.0667496 -0.0533 0.085235 -0.0670242 -0.052275 0.085235 -0.0677746 -0.0515247 0.085235 -0.0698246 -0.0515247 0.087785 -0.0705749 -0.052275 0.087785 -0.0687996 -0.0558 0.088235 -0.0666345 -0.05455 0.088235 -0.0667496 -0.0533 0.087785 -0.0670242 -0.052275 0.087785 -0.0677746 -0.0515247 0.087785 -0.0675496 -0.051135 0.088235 -0.0687996 -0.0508 0.088235 -0.14165 0.0533 0.088235 -0.14165 -0.02665 0.088235 -0.14215 0.0533 0.087735 -0.14215 -0.0533 0.087735 -0.14165 -0.0533 0.088235 -0.141307 -0.0550221 0.088235 -0.140332 -0.056482 0.088235 -0.13715 0.0578 0.088235 -0.138872 0.0574574 0.088235 -0.140685 0.0568355 0.087735 -0.13715 -0.0583 0.087735 -0.0687996 0.0578 0.088235 -0.13715 0.0583 0.087735 -0.0656176 -0.056482 0.088235 -0.0641802 -0.0552135 0.087735 -0.0646421 -0.0550221 0.088235 -0.0641802 0.0552134 0.087735 -0.0656176 0.0564819 0.088235 -0.0670775 0.0574574 0.088235 -0.0637996 -0.0533 0.087735 -0.0640996 -0.049725 0.085235 -0.065264 0.0568355 0.085535 -0.0641802 0.0552134 0.085535 -0.0640996 0.0533 0.085235 -0.0640996 -0.0533 0.085235 -0.0641802 -0.0552135 0.085535 -0.0644573 -0.0550987 0.085235 -0.0654762 -0.0566234 0.085235 -0.0687996 -0.058 0.085235 -0.13715 0.0583 0.085535 -0.0687996 0.058 0.085235 -0.0723746 -0.058 0.085235 -0.0687996 -0.0583 0.085535 -0.133575 -0.058 0.085235 -0.141769 0.0552134 0.085535 -0.141492 0.0550986 0.085235 -0.140685 0.0568355 0.085535 -0.13715 -0.058 0.085235 -0.140473 -0.0566234 0.085235 -0.141492 -0.0550987 0.085235 -0.14215 -0.0533 0.085535 -0.13205 0.00499996 0.087035 -0.0773996 0.00149996 0.087035 -0.0797996 0.0482 0.087035 -0.0756276 0.0464719 0.087035 -0.0738996 0.0423 0.087035 -0.130321 0.0464719 0.087035 -0.13205 0.0423 0.087035 -0.128407 0.0477508 0.087035 -0.0773996 -0.00150004 0.087035 -0.13205 -0.00500004 0.087035 -0.1303 -0.00196895 0.087035 -0.12855 -0.00150004 0.087035 -0.0749247 -0.00252517 0.087035 -0.074166 -0.00366065 0.087035 -0.0756276 -0.046472 0.087035 -0.1316 -0.0445579 0.087035 -0.13205 0.0423 0.085235 -0.1316 0.0445578 0.087035 -0.130321 0.0464719 0.085235 -0.12615 0.0482 0.087035 -0.0775417 0.0477508 0.087035 -0.0756276 0.0464719 0.085235 -0.0743487 0.0445578 0.087035 -0.0743487 0.0445578 0.085235 -0.0738996 0.025125 0.085235 -0.0760602 0.00176638 0.085235 -0.0749247 0.00252508 0.085235 -0.0760602 0.00176638 0.087035 -0.0749247 0.00252508 0.087035 -0.074166 0.00366057 0.087035 -0.074166 0.00366057 0.085235 -0.0738996 0.00499996 0.087035 -0.12855 0.00149996 0.087035 -0.131783 0.00366057 0.085235 -0.131783 0.00366057 0.087035 -0.131024 0.00252508 0.087035 -0.129889 0.00176638 0.085235 -0.129889 0.00176638 0.087035 -0.13205 0.025125 0.085235 -0.0738996 -0.0423 0.087035 -0.0738996 -0.0423 0.085235 -0.0743487 -0.0445579 0.087035 -0.0775417 -0.0477509 0.087035 -0.0756276 -0.046472 0.085235 -0.0797996 -0.0482 0.087035 -0.0797996 -0.0482 0.085235 -0.12615 -0.0482 0.087035 -0.128407 -0.0477509 0.087035 -0.128407 -0.0477509 0.085235 -0.130321 -0.046472 0.087035 -0.1316 -0.0445579 0.085235 -0.13205 -0.0423 0.087035 -0.13205 -0.0423 0.085235 -0.1303 -0.00196895 0.085235 -0.131581 -0.00325004 0.087035 -0.131581 -0.00325004 0.085235 -0.074166 -0.00366065 0.085235 -0.0749247 -0.00252517 0.085235 -0.0760602 -0.00176646 0.087035 -0.0760602 -0.00176646 0.085235 -0.0773996 -0.00150004 0.085235 -0.0738996 -0.00500004 0.087035 -0.247173 -0.0245 0.084235 -0.251167 -0.0240128 0.084235 -0.265616 -0.020903 0.081235 -0.293444 -0.0163898 0.081235 -0.342757 -0.0130183 0.084235 -0.404198 -0.0169616 0.081235 -0.37355 -0.0138616 0.084235 -0.37786 -0.0141606 0.081235 -0.349693 -0.0130109 0.081235 -0.342757 -0.0130183 0.081235 -0.404198 -0.0169616 0.084235 -0.444673 -0.00560004 0.084235 -0.444673 0.00559996 0.077235 -0.432273 0.018 0.084235 -0.404198 0.0169615 0.084235 -0.37355 0.0138615 0.084235 -0.342757 0.0130182 0.084235 -0.321511 0.013755 0.081235 -0.293444 0.0163897 0.081235 -0.311985 0.0144361 0.084235 -0.281401 0.0181075 0.081235 -0.265616 0.0209029 0.081235 -0.281401 0.0181075 0.084235 -0.247173 0.0245 0.084235 -0.243167 0.0241179 0.084235 -0.209581 0.0171939 0.077235 -0.186248 0.0116154 0.077235 -0.180742 0.00485822 0.084235 -0.180742 0.00485822 0.077235 -0.17999 0.000499958 0.084235 -0.17999 -0.000500042 0.077235 -0.180742 -0.0048583 0.084235 -0.182912 -0.00871213 0.084235 -0.180742 -0.0048583 0.077235 -0.182912 -0.00871213 0.077235 -0.186248 -0.0116155 0.084235 -0.190365 -0.0132323 0.084235 -0.209581 -0.017194 0.077235 -0.183687 -0.00808043 0.085235 -0.436673 0.00639996 0.085235 -0.430273 -4.19898e-08 0.085235 -0.433473 -0.0055426 0.085235 -0.432273 -0.017 0.085235 -0.440334 -0.0136611 0.085235 -0.436673 -0.00640004 0.085235 -0.436636 -0.0161323 0.085235 -0.436636 0.0161322 0.085235 -0.439873 0.00554252 0.085235 -0.442805 0.00996255 0.085235 -0.442216 0.00319996 0.085235 -0.442216 -0.00320004 0.085235 -0.443673 -0.00560004 0.085235 -0.442805 -0.00996263 0.085235 -0.420073 -4.19898e-08 0.085235 -0.425173 -0.00395004 0.085235 -0.431131 0.00319996 0.085235 -0.433473 0.00554252 0.085235 -0.408131 -0.00320004 0.085235 -0.333473 -0.00395004 0.085235 -0.425173 0.017 0.085235 -0.416873 0.00554252 0.085235 -0.419277 0.017 0.085235 -0.419216 -0.00320004 0.085235 -0.416873 -0.0055426 0.085235 -0.425173 -0.017 0.085235 -0.410473 -0.0055426 0.085235 -0.419277 -0.017 0.085235 -0.233573 -4.19898e-08 0.085235 -0.232716 -0.00320004 0.085235 -0.242123 -0.00395004 0.085235 -0.209581 0.0161729 0.085235 -0.230373 0.00554252 0.085235 -0.221631 -0.00320004 0.085235 -0.223973 -0.0055426 0.085235 -0.197532 -0.00320004 0.085235 -0.19839 -4.19898e-08 0.085235 -0.209581 -0.00395004 0.085235 -0.221631 0.00319996 0.085235 -0.223973 0.00554252 0.085235 -0.197532 0.00319996 0.085235 -0.190567 0.0122528 0.085235 -0.186767 0.0107604 0.085235 -0.18879 0.00554252 0.085235 -0.183687 0.00808035 0.085235 -0.18329 -0.00395004 0.085235 -0.19519 -0.0055426 0.085235 -0.186767 -0.0107604 0.085235 -0.259472 0.000749958 0.085235 -0.258923 0.001299 0.085235 -0.257423 0.001299 0.085235 -0.255147 0.0220784 0.085235 -0.256874 0.000749958 0.085235 -0.258173 -0.00150004 0.085235 -0.258923 -0.00129908 0.085235 -0.281245 0.0171197 0.085235 -0.250874 -0.000750042 0.085235 -0.250874 0.000749958 0.085235 -0.251423 -0.00129908 0.085235 -0.250673 -4.19898e-08 0.085235 -0.255173 -0.00395004 0.085235 -0.253472 0.000749958 0.085235 -0.252173 0.00149996 0.085235 -0.251423 0.001299 0.085235 -0.18099 0.000499958 0.085235 -0.18099 -0.000500042 0.085235 -0.227173 -0.00640004 0.085235 -0.230373 -0.0055426 0.085235 -0.24716 -0.0235001 0.085235 -0.373614 -0.0128637 0.085235 -0.281245 -0.0171198 0.085235 -0.25094 -0.0230391 0.085235 -0.257423 0.001299 0.077235 -0.190365 -0.0132323 0.077235 -0.186248 -0.0116155 0.077235 -0.18434 -0.00240004 0.077235 -0.182912 0.00871205 0.077235 -0.17999 0.000499958 0.077235 -0.18869 -4.19898e-08 0.077235 -0.190365 0.0132322 0.077235 -0.19199 0.00329996 0.077235 -0.225523 0.00285784 0.077235 -0.230031 0.00164996 0.077235 -0.228823 0.00285784 0.077235 -0.252173 0.00149996 0.077235 -0.255173 -0.00240004 0.077235 -0.253472 -0.000750042 0.077235 -0.252923 -0.00129908 0.077235 -0.250874 -0.000750042 0.077235 -0.238262 0.0231066 0.077235 -0.250673 -4.19898e-08 0.077235 -0.250874 0.000749958 0.077235 -0.258173 0.00149996 0.077235 -0.264844 0.0169783 0.077235 -0.259472 0.000749958 0.077235 -0.256673 -4.19898e-08 0.077235 -0.43332 0.0179557 0.077235 -0.416973 -4.19898e-08 0.077235 -0.410373 -4.19898e-08 0.077235 -0.349722 0.00901093 0.077235 -0.378158 0.0101715 0.077235 -0.412023 0.00285784 0.077235 -0.413673 0.00329996 0.077235 -0.433815 -0.00165004 0.077235 -0.425173 -0.00240004 0.077235 -0.433373 -4.19898e-08 0.077235 -0.437018 0.0170561 0.077235 -0.441041 0.0143681 0.077235 -0.437018 -0.0170561 0.077235 -0.435023 -0.00285793 0.077235 -0.438323 -0.00285793 0.077235 -0.439973 -4.19898e-08 0.077235 -0.444673 -0.00240004 0.077235 -0.439531 -0.00165004 0.077235 -0.444673 -0.00560004 0.077235 -0.443729 -0.0103453 0.077235 -0.335023 -0.00240004 0.077235 -0.43332 -0.0179558 0.077235 -0.415323 -0.00285793 0.077235 -0.406452 -0.0132389 0.077235 -0.413673 -0.00330004 0.077235 -0.378158 -0.0101716 0.077235 -0.410815 -0.00165004 0.077235 -0.292936 -0.0124221 0.077235 -0.240573 -0.00240004 0.077235 -0.238262 -0.0231067 0.077235 -0.228823 -0.00285793 0.077235 -0.227173 -0.00330004 0.077235 -0.225523 -0.00285793 0.077235 -0.209581 -0.00240004 0.077235 -0.436673 0.00329996 0.077235 -0.438323 0.00285784 0.077235 -0.439531 0.00164996 0.082135 -0.439531 0.00164996 0.077235 -0.439973 -4.19898e-08 0.082135 -0.439531 -0.00165004 0.082135 -0.436673 -0.00330004 0.077235 -0.438323 -0.00285793 0.082135 -0.436673 -0.00330004 0.082135 -0.435023 -0.00285793 0.082135 -0.433815 -0.00165004 0.082135 -0.433815 0.00164996 0.077235 -0.433815 0.00164996 0.082135 -0.435023 0.00285784 0.077235 -0.443073 -4.19898e-08 0.085235 -0.439873 -0.0055426 0.085235 -0.431131 -0.00320004 0.085235 -0.433373 -4.19898e-08 0.082135 -0.435023 0.00285784 0.082135 -0.436673 0.00329996 0.082135 -0.438323 0.00285784 0.082135 -0.413673 0.00329996 0.082135 -0.415323 0.00285784 0.077235 -0.416531 0.00164996 0.077235 -0.416531 -0.00165004 0.077235 -0.416531 -0.00165004 0.082135 -0.415323 -0.00285793 0.082135 -0.412023 -0.00285793 0.077235 -0.410815 -0.00165004 0.082135 -0.410815 0.00164996 0.077235 -0.416531 0.00164996 0.082135 -0.416973 -4.19898e-08 0.082135 -0.419216 0.00319996 0.085235 -0.413673 -0.00330004 0.082135 -0.413673 -0.00640004 0.085235 -0.412023 -0.00285793 0.082135 -0.410373 -4.19898e-08 0.082135 -0.407273 -4.19898e-08 0.085235 -0.408131 0.00319996 0.085235 -0.410815 0.00164996 0.082135 -0.412023 0.00285784 0.082135 -0.410473 0.00554252 0.085235 -0.415323 0.00285784 0.082135 -0.413673 0.00639996 0.085235 -0.230031 0.00164996 0.082135 -0.230473 -4.19898e-08 0.077235 -0.230031 -0.00165004 0.077235 -0.230473 -4.19898e-08 0.082135 -0.228823 -0.00285793 0.082135 -0.227173 -0.00330004 0.082135 -0.224315 -0.00165004 0.077235 -0.223873 -4.19898e-08 0.077235 -0.223873 -4.19898e-08 0.082135 -0.224315 0.00164996 0.077235 -0.225523 0.00285784 0.082135 -0.227173 0.00329996 0.077235 -0.228823 0.00285784 0.082135 -0.232716 0.00319996 0.085235 -0.230031 -0.00165004 0.082135 -0.225523 -0.00285793 0.082135 -0.224315 -0.00165004 0.082135 -0.220773 -4.19898e-08 0.085235 -0.224315 0.00164996 0.082135 -0.227173 0.00329996 0.082135 -0.227173 0.00639996 0.085235 -0.19364 0.00285784 0.077235 -0.19364 0.00285784 0.082135 -0.194847 0.00164996 0.077235 -0.19529 -4.19898e-08 0.077235 -0.194847 -0.00165004 0.077235 -0.19529 -4.19898e-08 0.082135 -0.19364 -0.00285793 0.077235 -0.19364 -0.00285793 0.082135 -0.19199 -0.00330004 0.077235 -0.19034 -0.00285793 0.077235 -0.189132 -0.00165004 0.077235 -0.189132 0.00164996 0.077235 -0.19034 0.00285784 0.077235 -0.19199 0.00329996 0.082135 -0.194847 0.00164996 0.082135 -0.19519 0.00554252 0.085235 -0.194847 -0.00165004 0.082135 -0.19199 -0.00330004 0.082135 -0.19034 -0.00285793 0.082135 -0.19199 -0.00640004 0.085235 -0.18879 -0.0055426 0.085235 -0.189132 -0.00165004 0.082135 -0.186447 -0.00320004 0.085235 -0.18869 -4.19898e-08 0.082135 -0.18559 -4.19898e-08 0.085235 -0.189132 0.00164996 0.082135 -0.186447 0.00319996 0.085235 -0.19034 0.00285784 0.082135 -0.19199 0.00639996 0.085235 -0.441041 -0.0143682 0.077235 -0.432273 0.018 0.0774912 -0.443729 0.0103452 0.077235 -0.444673 0.00559996 0.084235 -0.243167 -0.024118 0.0794443 -0.247173 -0.0245 0.0807813 -0.412591 -0.0177967 0.0808271 -0.419277 -0.018 0.0799264 -0.432273 -0.018 0.0774912 -0.251167 -0.0240128 0.081235 -0.264844 -0.0169784 0.077235 -0.281401 -0.0181076 0.081235 -0.321272 -0.00976229 0.077235 -0.311985 -0.0144362 0.081235 -0.321511 -0.0137551 0.081235 -0.349722 -0.00901101 0.077235 -0.37355 -0.0138616 0.081235 -0.419277 0.018 0.0799264 -0.412591 0.0177966 0.0808271 -0.243167 0.0241179 0.0794443 -0.406452 0.0132388 0.077235 -0.40589 0.0171823 0.0812183 -0.404198 0.0169615 0.081235 -0.37786 0.0141605 0.081235 -0.37355 0.0138615 0.081235 -0.349693 0.0130108 0.081235 -0.342757 0.0130182 0.081235 -0.321272 0.0097622 0.077235 -0.311985 0.0144361 0.081235 -0.292936 0.012422 0.077235 -0.255128 0.0190096 0.077235 -0.251167 0.0240127 0.081235 -0.247173 0.0245 0.0807813 -0.373614 0.0128636 0.085235 -0.342748 0.0120183 0.085235 -0.311903 0.0134395 0.085235 -0.251167 0.0240127 0.084235 -0.25094 0.023039 0.085235 -0.419277 0.018 0.084235 -0.404335 0.0159709 0.085235 -0.243369 0.0231385 0.085235 -0.24716 0.0235 0.085235 -0.242123 0.0228816 0.085235 -0.190365 0.0132322 0.084235 -0.432273 0.017 0.085235 -0.437018 0.0170561 0.084235 -0.441041 0.0143681 0.084235 -0.440334 0.013661 0.085235 -0.443729 0.0103452 0.084235 -0.443673 0.00559996 0.085235 -0.182912 0.00871205 0.084235 -0.181684 0.00452297 0.085235 -0.186248 0.0116154 0.084235 -0.443673 -0.00395004 0.085235 -0.17999 -0.000500042 0.084235 -0.443729 -0.0103453 0.084235 -0.441041 -0.0143682 0.084235 -0.437018 -0.0170561 0.084235 -0.432273 -0.018 0.084235 -0.190567 -0.0122529 0.085235 -0.181684 -0.00452305 0.085235 -0.419277 -0.018 0.084235 -0.243167 -0.024118 0.084235 -0.209581 -0.0161729 0.085235 -0.243369 -0.0231386 0.085235 -0.281401 -0.0181076 0.084235 -0.311985 -0.0144362 0.084235 -0.311903 -0.0134396 0.085235 -0.342748 -0.0120184 0.085235 -0.404335 -0.015971 0.085235 -0.258173 0.00149996 0.085235 -0.258923 0.001299 0.077235 -0.259673 -4.19898e-08 0.077235 -0.259472 -0.000750042 0.077235 -0.259673 -4.19898e-08 0.085235 -0.259472 -0.000750042 0.085235 -0.258923 -0.00129908 0.077235 -0.258173 -0.00150004 0.077235 -0.257423 -0.00129908 0.077235 -0.257423 -0.00129908 0.085235 -0.256874 -0.000750042 0.077235 -0.256874 -0.000750042 0.085235 -0.256673 -4.19898e-08 0.085235 -0.256874 0.000749958 0.077235 -0.252923 0.001299 0.077235 -0.252923 0.001299 0.085235 -0.253472 0.000749958 0.077235 -0.253673 -4.19898e-08 0.077235 -0.253673 -4.19898e-08 0.085235 -0.253472 -0.000750042 0.085235 -0.252923 -0.00129908 0.085235 -0.252173 -0.00150004 0.077235 -0.252173 -0.00150004 0.085235 -0.251423 -0.00129908 0.077235 -0.251423 0.001299 0.077235 0.198152 -0.0324539 -0.084765 0.187581 -0.0430249 -0.084765 0.2066 -0.0581547 -0.084765 0.187959 -0.0563141 -0.084765 0.187454 -0.0448 -0.084765 0.187581 -0.0545751 -0.084765 0.191759 -0.0353735 -0.084765 0.1905 -0.0366319 -0.084765 0.189434 -0.0380566 -0.084765 0.2066 -0.0381547 -0.084765 0.193183 -0.034307 -0.084765 0.22567 -0.034307 -0.084765 0.230895 -0.0563141 -0.084765 0.211694 -0.0406082 -0.084765 0.210685 -0.0414129 -0.084765 0.224108 -0.064146 -0.084765 0.198152 -0.0651462 -0.084765 0.194745 -0.064146 -0.084765 0.1905 -0.0609682 -0.084765 0.207159 -0.0369919 -0.084765 0.208169 -0.0361872 -0.084765 0.212254 -0.0394454 -0.084765 0.227095 -0.0353735 -0.084765 0.2314 -0.0528 -0.084765 0.2314 -0.0448 -0.084765 0.22942 -0.0595435 -0.084765 0.209427 -0.0359 -0.084765 0.218927 -0.0323269 -0.084765 0.212254 -0.0381547 -0.084765 0.228353 -0.0609682 -0.084765 0.20401 -0.047845 -0.084765 0.204258 -0.0469189 -0.084765 0.204664 -0.04605 -0.084765 0.212177 -0.0535632 -0.084765 0.204664 -0.05155 -0.084765 0.204258 -0.0506812 -0.084765 0.203927 -0.0488 -0.084765 0.205214 -0.0452647 -0.084765 0.208169 -0.0414129 -0.084765 0.205891 -0.0445868 -0.084765 0.206677 -0.0440369 -0.084765 0.207546 -0.0436317 -0.084765 0.212254 -0.0581547 -0.084765 0.214595 -0.0506812 -0.084765 0.207159 -0.0569919 -0.084765 0.205891 -0.0530133 -0.084765 0.21419 -0.04605 -0.084765 0.209427 -0.0417 -0.084765 0.214843 -0.047845 -0.084765 0.211308 -0.0436317 -0.084765 0.212177 -0.0440369 -0.084765 0.21364 -0.0452647 -0.084765 0.194475 -0.0582522 -0.113265 0.21596 -0.0407085 -0.113265 0.192311 -0.0435938 -0.113265 0.20014 -0.0534822 -0.113265 0.192594 -0.0551827 -0.113265 0.192311 -0.0540062 -0.113265 0.192216 -0.0488 -0.113265 0.19926 -0.046609 -0.113265 0.192216 -0.0448 -0.113265 0.202231 -0.0563084 -0.113265 0.218927 -0.0370895 -0.113265 0.211184 -0.0385496 -0.113265 0.207669 -0.0385496 -0.113265 0.192594 -0.0424174 -0.113265 0.193057 -0.0412995 -0.113265 0.199927 -0.0605106 -0.113265 0.218927 -0.0605106 -0.113265 0.208545 -0.0591626 -0.113265 0.218283 -0.0433472 -0.113265 0.20162 -0.041929 -0.113265 0.194475 -0.0393479 -0.113265 0.200571 -0.0433472 -0.113265 0.224379 -0.0393479 -0.113265 0.225165 -0.0402679 -0.113265 0.217234 -0.041929 -0.113265 0.221309 -0.0374669 -0.113265 0.199927 -0.0370895 -0.113265 0.198721 -0.0371845 -0.113265 0.218713 -0.0534822 -0.113265 0.224379 -0.0582522 -0.113265 0.225797 -0.0563005 -0.113265 0.219817 -0.0483587 -0.113265 0.219743 -0.050121 -0.113265 0.226637 -0.0448 -0.113265 0.216623 -0.0563084 -0.113265 0.221309 -0.0601332 -0.113265 0.186954 -0.0488 -0.0852911 0.188447 -0.0425165 -0.109474 0.187204 -0.0422692 -0.0852911 0.188795 -0.041183 -0.109474 0.189498 -0.0394861 -0.109474 0.190194 -0.0382971 -0.109474 0.189014 -0.0377866 -0.0852911 0.190123 -0.0363049 -0.0852911 0.19165 -0.0365233 -0.109474 0.197396 -0.0320769 -0.0852911 0.196272 -0.0323531 -0.0852911 0.197643 -0.0333199 -0.109474 0.199927 -0.0318276 -0.0852911 0.22121 -0.0333199 -0.109474 0.222544 -0.0336679 -0.109474 0.221458 -0.0320769 -0.0852911 0.222582 -0.0323531 -0.0852911 0.223891 -0.0328151 -0.0852911 0.223406 -0.033986 -0.109474 0.224316 -0.0329999 -0.0852911 0.22543 -0.0350677 -0.109474 0.227204 -0.0365233 -0.109474 0.227422 -0.0349961 -0.0852911 0.230632 -0.0448 -0.109474 0.230488 -0.042969 -0.109474 0.231767 -0.0429539 -0.0852911 0.230059 -0.041183 -0.109474 0.229356 -0.0394861 -0.109474 0.22984 -0.0377866 -0.0852911 0.228396 -0.03792 -0.109474 0.230632 -0.0528 -0.109474 0.230488 -0.0546311 -0.109474 0.231767 -0.0546462 -0.0852911 0.230407 -0.0550836 -0.109474 0.230059 -0.0564171 -0.109474 0.229741 -0.0572794 -0.109474 0.230912 -0.0577644 -0.0852911 0.230727 -0.058189 -0.0852911 0.228659 -0.059303 -0.109474 0.228396 -0.0596801 -0.109474 0.227204 -0.0610768 -0.109474 0.221458 -0.0655232 -0.0852911 0.222544 -0.0639322 -0.109474 0.223891 -0.064785 -0.0852911 0.22594 -0.0637131 -0.0852911 0.22543 -0.0625324 -0.109474 0.218927 -0.0657725 -0.0852911 0.198081 -0.0656404 -0.0852911 0.197643 -0.0642802 -0.109474 0.197396 -0.0655232 -0.0852911 0.19631 -0.0639322 -0.109474 0.195447 -0.0636141 -0.109474 0.194538 -0.0646002 -0.0852911 0.193424 -0.0625324 -0.109474 0.193047 -0.0622696 -0.109474 0.191432 -0.0626039 -0.0852911 0.189014 -0.0598135 -0.0852911 0.190123 -0.0612952 -0.0852911 0.186954 -0.0528 -0.0852911 0.187086 -0.0546462 -0.0852911 0.188222 -0.0528 -0.109474 0.188366 -0.0546311 -0.109474 0.187204 -0.0553308 -0.0852911 0.188795 -0.0564171 -0.109474 0.189113 -0.0572794 -0.109474 0.189498 -0.058114 -0.109474 0.188222 -0.0488 -0.109474 0.231763 -0.0528 -0.0849208 0.231899 -0.0528 -0.0852911 0.231899 -0.0448 -0.0852911 0.231468 -0.0429968 -0.0848056 0.231763 -0.0448 -0.0849208 0.231374 -0.0411453 -0.0852911 0.23165 -0.0422692 -0.0852911 0.231737 -0.0429582 -0.0850919 0.231869 -0.0448 -0.0850919 0.230912 -0.0398357 -0.0852911 0.230727 -0.0394111 -0.0852911 0.230699 -0.0394237 -0.0850919 0.228731 -0.0363049 -0.0852911 0.228708 -0.0363247 -0.0850919 0.2281 -0.0356272 -0.0852911 0.227402 -0.035019 -0.0850919 0.22594 -0.0338869 -0.0852911 0.224303 -0.0330274 -0.0850919 0.220773 -0.0319597 -0.0852911 0.231632 -0.0429733 -0.0849208 0.231243 -0.0411838 -0.0849208 0.231345 -0.0411538 -0.0850919 0.230603 -0.0394679 -0.0849208 0.229814 -0.037803 -0.0850919 0.228627 -0.0363944 -0.0849208 0.227332 -0.0350994 -0.0849208 0.225924 -0.0339124 -0.0850919 0.222573 -0.0323821 -0.0850919 0.220769 -0.0319896 -0.0850919 0.218927 -0.0318578 -0.0850919 0.231597 -0.0448 -0.0848056 0.230452 -0.0395365 -0.0848056 0.229725 -0.0378605 -0.0849208 0.229586 -0.0379499 -0.0848056 0.227224 -0.0352243 -0.0848056 0.225866 -0.0340019 -0.0849208 0.225777 -0.034141 -0.0848056 0.224259 -0.0331242 -0.0849208 0.22419 -0.0332746 -0.0848056 0.222496 -0.0326428 -0.0848056 0.222543 -0.0324842 -0.0849208 0.220754 -0.0320949 -0.0849208 0.22073 -0.0322585 -0.0848056 0.218927 -0.0319642 -0.0849208 0.231273 -0.0430249 -0.084765 0.231084 -0.0412304 -0.0848056 0.230895 -0.041286 -0.084765 0.230273 -0.0396185 -0.084765 0.22942 -0.0380566 -0.084765 0.228353 -0.0366319 -0.084765 0.228503 -0.0365026 -0.0848056 0.224108 -0.0334541 -0.084765 0.222441 -0.0328322 -0.084765 0.220702 -0.0324539 -0.084765 0.218927 -0.0321296 -0.0848056 0.22073 -0.0653416 -0.0848056 0.218927 -0.0654705 -0.0848056 0.218927 -0.0656358 -0.0849208 0.222582 -0.065247 -0.0852911 0.222573 -0.065218 -0.0850919 0.220773 -0.0656404 -0.0852911 0.224316 -0.0646002 -0.0852911 0.227422 -0.0626039 -0.0852911 0.227402 -0.0625811 -0.0850919 0.2281 -0.0619729 -0.0852911 0.228708 -0.0612754 -0.0850919 0.228731 -0.0612952 -0.0852911 0.22984 -0.0598135 -0.0852911 0.230699 -0.0581764 -0.0850919 0.231345 -0.0564463 -0.0850919 0.231374 -0.0564548 -0.0852911 0.23165 -0.0553308 -0.0852911 0.231869 -0.0528 -0.0850919 0.220769 -0.0656105 -0.0850919 0.220754 -0.0655052 -0.0849208 0.224303 -0.0645727 -0.0850919 0.225924 -0.0636877 -0.0850919 0.225866 -0.0635982 -0.0849208 0.227332 -0.0625007 -0.0849208 0.229814 -0.0597971 -0.0850919 0.229725 -0.0597396 -0.0849208 0.230603 -0.0581322 -0.0849208 0.231737 -0.0546419 -0.0850919 0.222543 -0.0651159 -0.0849208 0.224259 -0.0644759 -0.0849208 0.22419 -0.0643255 -0.0848056 0.225777 -0.0634591 -0.0848056 0.228627 -0.0612057 -0.0849208 0.231243 -0.0564163 -0.0849208 0.230452 -0.0580636 -0.0848056 0.231632 -0.0546268 -0.0849208 0.220702 -0.0651462 -0.084765 0.222441 -0.0647679 -0.084765 0.222496 -0.0649573 -0.0848056 0.22567 -0.0632931 -0.084765 0.227224 -0.0623758 -0.0848056 0.227095 -0.0622266 -0.084765 0.228503 -0.0610974 -0.0848056 0.229586 -0.0596502 -0.0848056 0.230273 -0.0579816 -0.084765 0.231084 -0.0563697 -0.0848056 0.231468 -0.0546032 -0.0848056 0.231273 -0.0545751 -0.084765 0.231597 -0.0528 -0.0848056 0.199927 -0.0318578 -0.0850919 0.218927 -0.0318276 -0.0852911 0.199927 -0.0652732 -0.084765 0.218927 -0.0652732 -0.084765 0.218927 -0.0657422 -0.0850919 0.199927 -0.0657725 -0.0852911 0.199927 -0.0323269 -0.084765 0.199927 -0.0321296 -0.0848056 0.1981 -0.0320949 -0.0849208 0.199927 -0.0319642 -0.0849208 0.194962 -0.0328151 -0.0852911 0.196281 -0.0323821 -0.0850919 0.198085 -0.0319896 -0.0850919 0.198081 -0.0319597 -0.0852911 0.194538 -0.0329999 -0.0852911 0.19455 -0.0330274 -0.0850919 0.192913 -0.0338869 -0.0852911 0.191432 -0.0349961 -0.0852911 0.190754 -0.0356272 -0.0852911 0.187509 -0.0411538 -0.0850919 0.189039 -0.037803 -0.0850919 0.188127 -0.0394111 -0.0852911 0.187942 -0.0398357 -0.0852911 0.18748 -0.0411453 -0.0852911 0.187086 -0.0429539 -0.0852911 0.187116 -0.0429582 -0.0850919 0.196311 -0.0324842 -0.0849208 0.19293 -0.0339124 -0.0850919 0.192987 -0.0340019 -0.0849208 0.191451 -0.035019 -0.0850919 0.190146 -0.0363247 -0.0850919 0.189129 -0.0378605 -0.0849208 0.188154 -0.0394237 -0.0850919 0.187091 -0.0448 -0.0849208 0.198124 -0.0322585 -0.0848056 0.194663 -0.0332746 -0.0848056 0.194595 -0.0331242 -0.0849208 0.193077 -0.034141 -0.0848056 0.191521 -0.0350994 -0.0849208 0.191629 -0.0352243 -0.0848056 0.190226 -0.0363944 -0.0849208 0.190351 -0.0365026 -0.0848056 0.188251 -0.0394679 -0.0849208 0.188401 -0.0395365 -0.0848056 0.187611 -0.0411838 -0.0849208 0.187222 -0.0429733 -0.0849208 0.196357 -0.0326428 -0.0848056 0.196413 -0.0328322 -0.084765 0.194745 -0.0334541 -0.084765 0.189268 -0.0379499 -0.0848056 0.188581 -0.0396185 -0.084765 0.187959 -0.041286 -0.084765 0.18777 -0.0412304 -0.0848056 0.187385 -0.0429968 -0.0848056 0.187256 -0.0448 -0.0848056 0.187091 -0.0528 -0.0849208 0.186985 -0.0528 -0.0850919 0.187942 -0.0577644 -0.0852911 0.18748 -0.0564548 -0.0852911 0.187509 -0.0564463 -0.0850919 0.188127 -0.058189 -0.0852911 0.189039 -0.0597971 -0.0850919 0.190754 -0.0619729 -0.0852911 0.192913 -0.0637131 -0.0852911 0.19293 -0.0636877 -0.0850919 0.19455 -0.0645727 -0.0850919 0.194962 -0.064785 -0.0852911 0.196272 -0.065247 -0.0852911 0.198085 -0.0656105 -0.0850919 0.187222 -0.0546268 -0.0849208 0.187116 -0.0546419 -0.0850919 0.188154 -0.0581764 -0.0850919 0.190226 -0.0612057 -0.0849208 0.190146 -0.0612754 -0.0850919 0.191451 -0.0625811 -0.0850919 0.191521 -0.0625007 -0.0849208 0.196281 -0.065218 -0.0850919 0.196311 -0.0651159 -0.0849208 0.1981 -0.0655052 -0.0849208 0.199927 -0.0657422 -0.0850919 0.199927 -0.0656358 -0.0849208 0.187385 -0.0546032 -0.0848056 0.187611 -0.0564163 -0.0849208 0.18777 -0.0563697 -0.0848056 0.188251 -0.0581322 -0.0849208 0.189129 -0.0597396 -0.0849208 0.191629 -0.0623758 -0.0848056 0.192987 -0.0635982 -0.0849208 0.194595 -0.0644759 -0.0849208 0.196357 -0.0649573 -0.0848056 0.188581 -0.0579816 -0.084765 0.188401 -0.0580636 -0.0848056 0.189268 -0.0596502 -0.0848056 0.190351 -0.0610974 -0.0848056 0.189434 -0.0595435 -0.084765 0.191759 -0.0622266 -0.084765 0.193077 -0.0634591 -0.0848056 0.193183 -0.0632931 -0.084765 0.194663 -0.0643255 -0.0848056 0.196413 -0.0647679 -0.084765 0.198124 -0.0653416 -0.0848056 0.199927 -0.0654705 -0.0848056 0.187454 -0.0488 -0.084765 0.187091 -0.0488 -0.0849208 0.186985 -0.0448 -0.0850919 0.186954 -0.0448 -0.0852911 0.187454 -0.0528 -0.084765 0.187256 -0.0528 -0.0848056 0.187256 -0.0488 -0.0848056 0.186985 -0.0488 -0.0850919 0.199927 -0.033095 -0.109474 0.218927 -0.033095 -0.109474 0.199927 -0.0334569 -0.11094 0.199927 -0.0336973 -0.111385 0.218927 -0.0336973 -0.111385 0.218927 -0.0351503 -0.112763 0.199927 -0.0356073 -0.11298 0.199927 -0.036088 -0.113138 0.218927 -0.036088 -0.113138 0.189113 -0.0403207 -0.109474 0.190603 -0.0380256 -0.110468 0.193424 -0.0350677 -0.109474 0.194613 -0.0343708 -0.109474 0.198564 -0.0361953 -0.113138 0.191329 -0.0404191 -0.112763 0.190749 -0.0418181 -0.112763 0.190034 -0.0397595 -0.111385 0.189975 -0.0415665 -0.112166 0.191641 -0.0421079 -0.113138 0.190396 -0.0432905 -0.112763 0.199927 -0.0343361 -0.112166 0.199927 -0.0351503 -0.112763 0.197235 -0.0365144 -0.113138 0.195972 -0.0370376 -0.113138 0.196693 -0.0348482 -0.112166 0.194886 -0.0349075 -0.111385 0.191215 -0.0448 -0.113138 0.191322 -0.0434372 -0.113138 0.190734 -0.0448 -0.11298 0.190277 -0.0448 -0.112763 0.189463 -0.0448 -0.112166 0.189592 -0.0431631 -0.112166 0.188824 -0.0448 -0.111385 0.189367 -0.0413691 -0.111385 0.188961 -0.0430632 -0.111385 0.188584 -0.0448 -0.11094 0.198096 -0.0332391 -0.109474 0.199927 -0.0332747 -0.110468 0.198124 -0.0334166 -0.110468 0.19631 -0.0336679 -0.109474 0.196365 -0.0338387 -0.110468 0.196496 -0.0342407 -0.111385 0.19819 -0.033834 -0.111385 0.19829 -0.0344649 -0.112166 0.196945 -0.0356226 -0.112763 0.198417 -0.0352691 -0.112763 0.197544 -0.0374669 -0.113265 0.195447 -0.033986 -0.109474 0.193047 -0.0353305 -0.109474 0.193152 -0.0354758 -0.110468 0.194694 -0.0345308 -0.110468 0.193776 -0.0363345 -0.112166 0.195176 -0.0354766 -0.112166 0.195546 -0.036202 -0.112763 0.195395 -0.0385621 -0.113265 0.196426 -0.0379299 -0.113265 0.193766 -0.0386397 -0.113138 0.194806 -0.0377519 -0.113138 0.194255 -0.0369932 -0.112763 0.193103 -0.0379766 -0.112763 0.193401 -0.0358178 -0.111385 0.191777 -0.0366504 -0.110468 0.193689 -0.0402679 -0.113265 0.19212 -0.0391281 -0.112763 0.192528 -0.0374009 -0.112166 0.191461 -0.0386495 -0.112166 0.192076 -0.0369492 -0.111385 0.190457 -0.03792 -0.109474 0.189658 -0.0395676 -0.110468 0.190945 -0.038274 -0.111385 0.190603 -0.0400495 -0.112166 0.192164 -0.0408449 -0.113138 0.192879 -0.0396792 -0.113138 0.188965 -0.0412385 -0.110468 0.188366 -0.042969 -0.109474 0.188543 -0.0429971 -0.110468 0.188222 -0.0448 -0.109474 0.228659 -0.0382971 -0.109474 0.22029 -0.0361953 -0.113138 0.220133 -0.0371845 -0.113265 0.226542 -0.0435938 -0.113265 0.227639 -0.0448 -0.113138 0.227532 -0.0434372 -0.113138 0.222427 -0.0379299 -0.113265 0.222882 -0.0370376 -0.113138 0.223308 -0.036202 -0.112763 0.223677 -0.0354766 -0.112166 0.224159 -0.0345308 -0.110468 0.221619 -0.0365144 -0.113138 0.221909 -0.0356226 -0.112763 0.220436 -0.0352691 -0.112763 0.22216 -0.0348482 -0.112166 0.220564 -0.0344649 -0.112166 0.222358 -0.0342407 -0.111385 0.23031 -0.0429971 -0.110468 0.23027 -0.0448 -0.11094 0.23003 -0.0448 -0.111385 0.228577 -0.0448 -0.112763 0.22812 -0.0448 -0.11298 0.22626 -0.0424174 -0.113265 0.225797 -0.0412995 -0.113265 0.228104 -0.0418181 -0.112763 0.227525 -0.0404191 -0.112763 0.228879 -0.0415665 -0.112166 0.22825 -0.0400495 -0.112166 0.228819 -0.0397595 -0.111385 0.229486 -0.0413691 -0.111385 0.218927 -0.0356073 -0.11298 0.218927 -0.0343361 -0.112166 0.220664 -0.033834 -0.111385 0.22073 -0.0334166 -0.110468 0.218927 -0.0334569 -0.11094 0.218927 -0.0332747 -0.110468 0.229888 -0.0412385 -0.110468 0.230407 -0.0425165 -0.109474 0.229893 -0.0430632 -0.111385 0.229262 -0.0431631 -0.112166 0.227212 -0.0421079 -0.113138 0.228458 -0.0432905 -0.112763 0.229196 -0.0395676 -0.110468 0.229741 -0.0403207 -0.109474 0.228251 -0.0380256 -0.110468 0.227392 -0.0386495 -0.112166 0.226734 -0.0391281 -0.112763 0.225975 -0.0396792 -0.113138 0.226689 -0.0408449 -0.113138 0.225087 -0.0386397 -0.113138 0.22575 -0.0379766 -0.112763 0.227909 -0.038274 -0.111385 0.223459 -0.0385621 -0.113265 0.224048 -0.0377519 -0.113138 0.226326 -0.0374009 -0.112166 0.225077 -0.0363345 -0.112166 0.226778 -0.0369492 -0.111385 0.225453 -0.0358178 -0.111385 0.227076 -0.0366504 -0.110468 0.225807 -0.0353305 -0.109474 0.224241 -0.0343708 -0.109474 0.225701 -0.0354758 -0.110468 0.223967 -0.0349075 -0.111385 0.224599 -0.0369932 -0.112763 0.222488 -0.0338387 -0.110468 0.220758 -0.0332391 -0.109474 0.189463 -0.0488 -0.112166 0.188584 -0.0488 -0.11094 0.188401 -0.0448 -0.110468 0.227639 -0.0528 -0.113138 0.22812 -0.0528 -0.11298 0.229391 -0.0448 -0.112166 0.229391 -0.0528 -0.112166 0.230452 -0.0448 -0.110468 0.192216 -0.0528 -0.113265 0.191215 -0.0528 -0.113138 0.190277 -0.0528 -0.112763 0.190734 -0.0488 -0.11298 0.188824 -0.0528 -0.111385 0.188401 -0.0528 -0.110468 0.229888 -0.0563616 -0.110468 0.224241 -0.0632293 -0.109474 0.224159 -0.0630692 -0.110468 0.223406 -0.0636141 -0.109474 0.220758 -0.064361 -0.109474 0.22073 -0.0641835 -0.110468 0.226637 -0.0528 -0.113265 0.218927 -0.0615121 -0.113138 0.220133 -0.0604156 -0.113265 0.22029 -0.0614048 -0.113138 0.218927 -0.0619928 -0.11298 0.228458 -0.0543096 -0.112763 0.228577 -0.0528 -0.112763 0.220436 -0.062331 -0.112763 0.218927 -0.0643254 -0.110468 0.218927 -0.0641431 -0.11094 0.22121 -0.0642802 -0.109474 0.222488 -0.0637613 -0.110468 0.220664 -0.0637661 -0.111385 0.220564 -0.0631352 -0.112166 0.221619 -0.0610857 -0.113138 0.222358 -0.0633593 -0.111385 0.223677 -0.0621235 -0.112166 0.22216 -0.0627518 -0.112166 0.221909 -0.0619775 -0.112763 0.222882 -0.0605625 -0.113138 0.222427 -0.0596702 -0.113265 0.225807 -0.0622696 -0.109474 0.225701 -0.0621243 -0.110468 0.225453 -0.0617823 -0.111385 0.223967 -0.0626926 -0.111385 0.223308 -0.061398 -0.112763 0.223459 -0.059038 -0.113265 0.224048 -0.0598482 -0.113138 0.224599 -0.0606069 -0.112763 0.225077 -0.0612655 -0.112166 0.226326 -0.0601992 -0.112166 0.226778 -0.0606508 -0.111385 0.227076 -0.0609497 -0.110468 0.225087 -0.0589604 -0.113138 0.225165 -0.0573322 -0.113265 0.225975 -0.0579209 -0.113138 0.22575 -0.0596235 -0.112763 0.227909 -0.0593261 -0.111385 0.228251 -0.0595745 -0.110468 0.229356 -0.058114 -0.109474 0.22825 -0.0575506 -0.112166 0.227525 -0.0571809 -0.112763 0.227392 -0.0589506 -0.112166 0.226734 -0.058472 -0.112763 0.226689 -0.0567552 -0.113138 0.229196 -0.0580325 -0.110468 0.228819 -0.0578406 -0.111385 0.227212 -0.0554922 -0.113138 0.22626 -0.0551827 -0.113265 0.23031 -0.054603 -0.110468 0.229893 -0.0545369 -0.111385 0.229486 -0.056231 -0.111385 0.229262 -0.054437 -0.112166 0.228879 -0.0560336 -0.112166 0.228104 -0.055782 -0.112763 0.227532 -0.0541629 -0.113138 0.226542 -0.0540062 -0.113265 0.23003 -0.0528 -0.111385 0.23027 -0.0528 -0.11094 0.230452 -0.0528 -0.110468 0.193152 -0.0621243 -0.110468 0.190194 -0.059303 -0.109474 0.189658 -0.0580325 -0.110468 0.188543 -0.054603 -0.110468 0.190734 -0.0528 -0.11298 0.190396 -0.0543096 -0.112763 0.196426 -0.0596702 -0.113265 0.197544 -0.0601332 -0.113265 0.195546 -0.061398 -0.112763 0.196693 -0.0627518 -0.112166 0.194886 -0.0626926 -0.111385 0.196496 -0.0633593 -0.111385 0.198721 -0.0604156 -0.113265 0.197235 -0.0610857 -0.113138 0.198564 -0.0614048 -0.113138 0.198417 -0.062331 -0.112763 0.196945 -0.0619775 -0.112763 0.19829 -0.0631352 -0.112166 0.188584 -0.0528 -0.11094 0.188961 -0.0545369 -0.111385 0.189592 -0.054437 -0.112166 0.189463 -0.0528 -0.112166 0.191641 -0.0554922 -0.113138 0.193057 -0.0563005 -0.113265 0.190749 -0.055782 -0.112763 0.192164 -0.0567552 -0.113138 0.189367 -0.056231 -0.111385 0.188965 -0.0563616 -0.110468 0.199927 -0.0615121 -0.113138 0.199927 -0.0619928 -0.11298 0.194694 -0.0630692 -0.110468 0.196365 -0.0637613 -0.110468 0.19819 -0.0637661 -0.111385 0.188447 -0.0550836 -0.109474 0.189975 -0.0560336 -0.112166 0.191322 -0.0541629 -0.113138 0.190603 -0.0595745 -0.110468 0.190945 -0.0593261 -0.111385 0.190034 -0.0578406 -0.111385 0.190603 -0.0575506 -0.112166 0.191329 -0.0571809 -0.112763 0.193689 -0.0573322 -0.113265 0.192879 -0.0579209 -0.113138 0.193766 -0.0589604 -0.113138 0.19212 -0.058472 -0.112763 0.193103 -0.0596235 -0.112763 0.191461 -0.0589506 -0.112166 0.192076 -0.0606508 -0.111385 0.190457 -0.0596801 -0.109474 0.192528 -0.0601992 -0.112166 0.193776 -0.0612655 -0.112166 0.191777 -0.0609497 -0.110468 0.19165 -0.0610768 -0.109474 0.194613 -0.0632293 -0.109474 0.193401 -0.0617823 -0.111385 0.195176 -0.0621235 -0.112166 0.195972 -0.0605625 -0.113138 0.194255 -0.0606069 -0.112763 0.194806 -0.0598482 -0.113138 0.195395 -0.059038 -0.113265 0.198096 -0.064361 -0.109474 0.198124 -0.0641835 -0.110468 0.199927 -0.0643254 -0.110468 0.199927 -0.0645051 -0.109474 0.218927 -0.0645051 -0.109474 0.199927 -0.0641431 -0.11094 0.218927 -0.0639028 -0.111385 0.218927 -0.063264 -0.112166 0.199927 -0.0639028 -0.111385 0.218927 -0.0624498 -0.112763 0.199927 -0.063264 -0.112166 0.199927 -0.0624498 -0.112763 0.210139 -0.0571698 -0.111265 0.211543 -0.056929 -0.111265 0.215366 -0.0547397 -0.090065 0.214131 -0.0557595 -0.111265 0.213627 -0.0560747 -0.111265 0.21618 -0.053795 -0.111265 0.216701 -0.053 -0.090065 0.216701 -0.053 -0.111265 0.216927 -0.0525818 -0.111265 0.217541 -0.0509741 -0.090065 0.217759 -0.049867 -0.111265 0.217827 -0.0488 -0.090065 0.217827 -0.0488 -0.111265 0.217221 -0.045668 -0.111265 0.216701 -0.0446 -0.090065 0.216701 -0.0446 -0.111265 0.21658 -0.0443959 -0.111265 0.215366 -0.0428603 -0.090065 0.215732 -0.0432504 -0.111265 0.212225 -0.0408799 -0.111265 0.211601 -0.0406863 -0.090065 0.213627 -0.0415254 -0.090065 0.214704 -0.0422645 -0.111265 0.211601 -0.0406863 -0.111265 0.210846 -0.0405209 -0.111265 0.207253 -0.0406863 -0.111265 0.207253 -0.0406863 -0.090065 0.206628 -0.0408799 -0.111265 0.205227 -0.0415254 -0.111265 0.20533 -0.0414667 -0.111265 0.203121 -0.0432504 -0.111265 0.203487 -0.0428603 -0.111265 0.20415 -0.0422645 -0.111265 0.201027 -0.0488 -0.090065 0.201027 -0.0488 -0.111265 0.201926 -0.0525818 -0.111265 0.201395 -0.0512598 -0.111265 0.201313 -0.0509741 -0.090065 0.202152 -0.053 -0.090065 0.203487 -0.0547397 -0.090065 0.207253 -0.0569138 -0.090065 0.205967 -0.0564544 -0.111265 0.205227 -0.0560747 -0.111265 0.209427 -0.0572 -0.111265 0.20731 -0.056929 -0.111265 0.214595 -0.0469189 -0.090065 0.214927 -0.0488 -0.090065 0.217541 -0.046626 -0.090065 0.209427 -0.0404 -0.090065 0.21364 -0.0452647 -0.090065 0.212962 -0.0445868 -0.090065 0.212177 -0.0440369 -0.090065 0.210382 -0.0433836 -0.090065 0.203927 -0.0488 -0.090065 0.205227 -0.0560747 -0.090065 0.205214 -0.0523354 -0.090065 0.209427 -0.0433 -0.090065 0.207546 -0.0436317 -0.090065 0.205227 -0.0415254 -0.090065 0.203487 -0.0428603 -0.090065 0.202152 -0.0446 -0.090065 0.205214 -0.0452647 -0.090065 0.204664 -0.04605 -0.090065 0.201313 -0.046626 -0.090065 0.206677 -0.0535632 -0.090065 0.209427 -0.0572 -0.090065 0.211601 -0.0569138 -0.090065 0.213627 -0.0560747 -0.090065 0.211308 -0.0539684 -0.090065 0.212177 -0.0535632 -0.090065 0.206578 -0.0407363 -0.11203 0.205256 -0.0413338 -0.11203 0.204054 -0.0421461 -0.11203 0.202274 -0.0443959 -0.111265 0.201491 -0.0456113 -0.11203 0.202152 -0.0446 -0.111265 0.201633 -0.045668 -0.111265 0.201313 -0.046626 -0.111265 0.201215 -0.0470303 -0.111265 0.201034 -0.0484435 -0.111265 0.201095 -0.049867 -0.111265 0.201313 -0.0509741 -0.111265 0.20179 -0.0526503 -0.11203 0.202152 -0.053 -0.111265 0.202673 -0.053795 -0.111265 0.203487 -0.0547397 -0.111265 0.203615 -0.0548645 -0.111265 0.204723 -0.0557595 -0.111265 0.207272 -0.0570763 -0.11203 0.208714 -0.0571698 -0.111265 0.210152 -0.0573215 -0.11203 0.208702 -0.0573215 -0.11203 0.211582 -0.0570763 -0.11203 0.214216 -0.0558857 -0.11203 0.212949 -0.0565931 -0.11203 0.212887 -0.0564544 -0.111265 0.215344 -0.0549744 -0.11203 0.215239 -0.0548645 -0.111265 0.215366 -0.0547397 -0.111265 0.217063 -0.0526503 -0.11203 0.217459 -0.0512598 -0.111265 0.217541 -0.0509741 -0.111265 0.21791 -0.0498863 -0.11203 0.217971 -0.0484371 -0.11203 0.217819 -0.0484435 -0.111265 0.217787 -0.0469983 -0.11203 0.217638 -0.0470303 -0.111265 0.217541 -0.046626 -0.111265 0.217362 -0.0456113 -0.11203 0.216709 -0.044316 -0.11203 0.215366 -0.0428603 -0.111265 0.214799 -0.0421461 -0.11203 0.213627 -0.0415254 -0.111265 0.213523 -0.0414667 -0.111265 0.213598 -0.0413338 -0.11203 0.208007 -0.0405209 -0.111265 0.209427 -0.0404 -0.111265 0.210872 -0.0403708 -0.11203 0.21242 -0.0403275 -0.112679 0.213809 -0.0409553 -0.112679 0.212276 -0.0407363 -0.11203 0.215847 -0.0431498 -0.11203 0.218019 -0.0514313 -0.112679 0.217604 -0.0513043 -0.11203 0.216303 -0.0538855 -0.11203 0.214459 -0.0562449 -0.112679 0.213128 -0.0569881 -0.112679 0.211691 -0.0574959 -0.112679 0.205726 -0.0569881 -0.112679 0.205904 -0.0565931 -0.11203 0.204638 -0.0558857 -0.11203 0.203209 -0.0552874 -0.112679 0.203509 -0.0549744 -0.11203 0.201403 -0.0528455 -0.112679 0.202551 -0.0538855 -0.11203 0.201249 -0.0513043 -0.11203 0.200514 -0.0499414 -0.112679 0.200944 -0.0498863 -0.11203 0.200449 -0.0484187 -0.112679 0.200882 -0.0484371 -0.11203 0.201067 -0.0469983 -0.11203 0.201089 -0.0454496 -0.112679 0.201775 -0.0440887 -0.112679 0.202681 -0.0428634 -0.112679 0.202144 -0.044316 -0.11203 0.203007 -0.0431498 -0.11203 0.205044 -0.0409553 -0.112679 0.206433 -0.0403275 -0.112679 0.207981 -0.0403708 -0.11203 0.209427 -0.0402478 -0.11203 0.210945 -0.0399435 -0.112679 0.211055 -0.039304 -0.113113 0.212636 -0.0397158 -0.113113 0.214126 -0.0403889 -0.113113 0.216659 -0.0424347 -0.113113 0.215072 -0.0418088 -0.112679 0.216172 -0.0428634 -0.112679 0.217078 -0.0440887 -0.112679 0.218367 -0.0452077 -0.113113 0.217765 -0.0454496 -0.112679 0.218211 -0.0469069 -0.112679 0.218404 -0.0484187 -0.112679 0.21834 -0.0499414 -0.112679 0.21745 -0.0528455 -0.112679 0.217173 -0.0545291 -0.113113 0.216651 -0.0541433 -0.112679 0.215644 -0.0552874 -0.112679 0.216093 -0.0557558 -0.113113 0.213395 -0.0575794 -0.113113 0.210189 -0.0577535 -0.112679 0.210244 -0.0584 -0.113113 0.208665 -0.0577535 -0.112679 0.207163 -0.0574959 -0.112679 0.205458 -0.0575794 -0.113113 0.204032 -0.0567824 -0.113113 0.204395 -0.0562449 -0.112679 0.201681 -0.0545291 -0.113113 0.202202 -0.0541433 -0.112679 0.200824 -0.0531376 -0.113113 0.200835 -0.0514313 -0.112679 0.19987 -0.0500238 -0.113113 0.199801 -0.0483911 -0.113113 0.200643 -0.0469069 -0.112679 0.200008 -0.0467702 -0.113113 0.201223 -0.0437485 -0.113113 0.202194 -0.0424347 -0.113113 0.203782 -0.0418088 -0.112679 0.204728 -0.0403889 -0.113113 0.207908 -0.0399435 -0.112679 0.209427 -0.0398143 -0.112679 0.212891 -0.0389941 -0.113265 0.214499 -0.0397207 -0.113265 0.215479 -0.041304 -0.113113 0.217631 -0.0437485 -0.113113 0.219077 -0.0449223 -0.113265 0.219593 -0.046609 -0.113265 0.218845 -0.0467702 -0.113113 0.219053 -0.0483911 -0.113113 0.218983 -0.0500238 -0.113113 0.219371 -0.0518454 -0.113265 0.218639 -0.0516213 -0.113113 0.21803 -0.0531376 -0.113113 0.217788 -0.0549842 -0.113265 0.215251 -0.0574165 -0.113265 0.213711 -0.0582768 -0.113265 0.214822 -0.0567824 -0.113113 0.212047 -0.0588645 -0.113265 0.211855 -0.0581238 -0.113113 0.210309 -0.0591626 -0.113265 0.206806 -0.0588645 -0.113265 0.20861 -0.0584 -0.113113 0.206999 -0.0581238 -0.113113 0.205143 -0.0582768 -0.113265 0.203603 -0.0574165 -0.113265 0.20276 -0.0557558 -0.113113 0.201065 -0.0549842 -0.113265 0.199483 -0.0518454 -0.113265 0.199111 -0.050121 -0.113265 0.200214 -0.0516213 -0.113113 0.199036 -0.0483587 -0.113265 0.199777 -0.0449223 -0.113265 0.200487 -0.0452077 -0.113113 0.202893 -0.0407085 -0.113265 0.203374 -0.041304 -0.113113 0.204355 -0.0397207 -0.113265 0.205962 -0.0389941 -0.113265 0.206217 -0.0397158 -0.113113 0.209427 -0.0384 -0.113265 0.207799 -0.039304 -0.113113 0.209427 -0.0391654 -0.113113 0.208559 -0.0537241 -0.085265 0.206927 -0.0531302 -0.085265 0.205597 -0.052014 -0.085265 0.206213 -0.0526303 -0.089565 0.205597 -0.052014 -0.089565 0.204728 -0.0505101 -0.089565 0.204503 -0.0496683 -0.089565 0.204427 -0.0488 -0.089565 0.204503 -0.0479318 -0.089565 0.204728 -0.0470899 -0.085265 0.205097 -0.0463 -0.085265 0.205097 -0.0463 -0.089565 0.206213 -0.0449698 -0.085265 0.206927 -0.0444699 -0.085265 0.206927 -0.0444699 -0.089565 0.208559 -0.043876 -0.085265 0.209427 -0.0438 -0.089565 0.210295 -0.043876 -0.085265 0.211137 -0.0441016 -0.085265 0.211927 -0.0444699 -0.085265 0.212641 -0.0449698 -0.085265 0.214125 -0.0470899 -0.089565 0.214351 -0.0479318 -0.085265 0.214351 -0.0496683 -0.085265 0.214125 -0.0505101 -0.085265 0.213757 -0.0513 -0.085265 0.213257 -0.052014 -0.085265 0.213757 -0.0513 -0.089565 0.213257 -0.052014 -0.089565 0.211927 -0.0531302 -0.089565 0.211927 -0.0531302 -0.085265 0.211137 -0.0534985 -0.085265 0.211137 -0.0534985 -0.089565 0.209427 -0.0538 -0.089565 0.208169 -0.0361872 -0.082265 0.206814 -0.0375418 -0.082265 0.207159 -0.0369919 -0.082265 0.2066 -0.0394454 -0.084765 0.2066 -0.0381547 -0.082265 0.2066 -0.0394454 -0.082265 0.207159 -0.0406082 -0.084765 0.206814 -0.0400583 -0.082265 0.208781 -0.0416273 -0.082265 0.211235 -0.0410674 -0.082265 0.210072 -0.0416273 -0.082265 0.21204 -0.0375418 -0.082265 0.212327 -0.0388 -0.082265 0.211235 -0.0365327 -0.082265 0.211694 -0.0369919 -0.084765 0.208781 -0.0359728 -0.082265 0.210072 -0.0359728 -0.082265 0.210685 -0.0361872 -0.084765 0.208602 -0.0405119 -0.081265 0.207574 -0.0392228 -0.081265 0.207527 -0.0388 -0.081265 0.209427 -0.0388 -0.081265 0.207941 -0.0376154 -0.081265 0.210912 -0.0376154 -0.081265 0.211279 -0.0383773 -0.081265 0.211139 -0.0396244 -0.081265 0.210611 -0.0402855 -0.081265 0.208169 -0.0561872 -0.084765 0.208781 -0.0559728 -0.082265 0.207619 -0.0565327 -0.082265 0.206814 -0.0575418 -0.082265 0.2066 -0.0581547 -0.082265 0.206814 -0.0600583 -0.082265 0.2066 -0.0594454 -0.084765 0.208169 -0.0614129 -0.084765 0.207159 -0.0606082 -0.082265 0.207159 -0.0606082 -0.084765 0.210685 -0.0614129 -0.084765 0.209427 -0.0617 -0.084765 0.209427 -0.0617 -0.082265 0.210685 -0.0614129 -0.082265 0.210072 -0.0616273 -0.082265 0.211694 -0.0606082 -0.084765 0.21204 -0.0600583 -0.082265 0.211235 -0.0610674 -0.082265 0.212327 -0.0588 -0.082265 0.212254 -0.0594454 -0.084765 0.21204 -0.0575418 -0.082265 0.212254 -0.0581547 -0.082265 0.210685 -0.0561872 -0.084765 0.211694 -0.0569919 -0.084765 0.211694 -0.0569919 -0.082265 0.209427 -0.0559 -0.082265 0.210072 -0.0559728 -0.082265 0.209427 -0.0559 -0.084765 0.210685 -0.0561872 -0.082265 0.20985 -0.0606524 -0.081265 0.209004 -0.0606524 -0.081265 0.209427 -0.0607 -0.081265 0.207715 -0.0596244 -0.081265 0.207715 -0.0579757 -0.081265 0.207574 -0.0583773 -0.081265 0.207574 -0.0592228 -0.081265 0.208242 -0.0573146 -0.081265 0.209427 -0.0569 -0.081265 0.209004 -0.0569477 -0.081265 0.210912 -0.0576154 -0.081265 0.209427 -0.0588 -0.081265 0.210251 -0.0570882 -0.081265 0.211139 -0.0579757 -0.081265 0.211139 -0.0596244 -0.081265 0.210611 -0.0602855 -0.081265 0.209961 -0.0611399 -0.0813989 0.210468 -0.0609624 -0.0813989 0.210251 -0.0605119 -0.081265 0.211303 -0.0602964 -0.0813989 0.210912 -0.0599847 -0.081265 0.211767 -0.0593341 -0.0813989 0.211279 -0.0592228 -0.081265 0.211327 -0.0588 -0.081265 0.211767 -0.058266 -0.0813989 0.211279 -0.0583773 -0.081265 0.211589 -0.0577587 -0.0813989 0.211303 -0.0573037 -0.0813989 0.210923 -0.0569236 -0.0813989 0.210611 -0.0573146 -0.081265 0.210468 -0.0566377 -0.0813989 0.20985 -0.0569477 -0.081265 0.208893 -0.0564602 -0.0813989 0.208602 -0.0570882 -0.081265 0.208385 -0.0566377 -0.0813989 0.20793 -0.0569236 -0.0813989 0.20755 -0.0573037 -0.0813989 0.207941 -0.0576154 -0.081265 0.207264 -0.0577587 -0.0813989 0.207527 -0.0588 -0.081265 0.207264 -0.0598414 -0.0813989 0.20755 -0.0602964 -0.0813989 0.207941 -0.0599847 -0.081265 0.20793 -0.0606764 -0.0813989 0.208242 -0.0602855 -0.081265 0.208385 -0.0609624 -0.0813989 0.208602 -0.0605119 -0.081265 0.209427 -0.0612 -0.0813989 0.210042 -0.0614967 -0.081765 0.211151 -0.0609626 -0.081765 0.210923 -0.0606764 -0.0813989 0.211589 -0.0605246 -0.081765 0.211919 -0.0600002 -0.081765 0.211589 -0.0598414 -0.0813989 0.211827 -0.0588 -0.0813989 0.212123 -0.0581845 -0.081765 0.209961 -0.0564602 -0.0813989 0.210042 -0.0561034 -0.081765 0.209427 -0.0564 -0.0813989 0.206935 -0.0575999 -0.081765 0.20673 -0.0581845 -0.081765 0.207087 -0.058266 -0.0813989 0.207027 -0.0588 -0.0813989 0.20673 -0.0594155 -0.081765 0.207087 -0.0593341 -0.0813989 0.207264 -0.0605246 -0.081765 0.207702 -0.0609626 -0.081765 0.208227 -0.0612921 -0.081765 0.208811 -0.0614967 -0.081765 0.208893 -0.0611399 -0.0813989 0.210627 -0.0612921 -0.081765 0.211694 -0.0606082 -0.082265 0.212254 -0.0594454 -0.082265 0.212123 -0.0594155 -0.081765 0.212193 -0.0588 -0.081765 0.211919 -0.0575999 -0.081765 0.211235 -0.0565327 -0.082265 0.211589 -0.0570755 -0.081765 0.211151 -0.0566375 -0.081765 0.210627 -0.0563079 -0.081765 0.209427 -0.056034 -0.081765 0.208811 -0.0561034 -0.081765 0.208227 -0.0563079 -0.081765 0.208169 -0.0561872 -0.082265 0.207702 -0.0566375 -0.081765 0.207159 -0.0569919 -0.082265 0.207264 -0.0570755 -0.081765 0.206527 -0.0588 -0.082265 0.2066 -0.0594454 -0.082265 0.206661 -0.0588 -0.081765 0.206935 -0.0600002 -0.081765 0.207619 -0.0610674 -0.082265 0.208169 -0.0614129 -0.082265 0.208781 -0.0616273 -0.082265 0.209427 -0.0615661 -0.081765 0.209427 -0.0407 -0.081265 0.20985 -0.0406524 -0.081265 0.209961 -0.0411399 -0.0813989 0.210251 -0.0405119 -0.081265 0.210912 -0.0399847 -0.081265 0.211767 -0.0393341 -0.0813989 0.211279 -0.0392228 -0.081265 0.211327 -0.0388 -0.081265 0.211589 -0.0377587 -0.0813989 0.211303 -0.0373037 -0.0813989 0.211139 -0.0379757 -0.081265 0.210923 -0.0369236 -0.0813989 0.210611 -0.0373146 -0.081265 0.210251 -0.0370882 -0.081265 0.20985 -0.0369477 -0.081265 0.209961 -0.0364602 -0.0813989 0.209427 -0.0364 -0.0813989 0.209427 -0.0369 -0.081265 0.209004 -0.0369477 -0.081265 0.208602 -0.0370882 -0.081265 0.208242 -0.0373146 -0.081265 0.207715 -0.0379757 -0.081265 0.207574 -0.0383773 -0.081265 0.207087 -0.038266 -0.0813989 0.207027 -0.0388 -0.0813989 0.207264 -0.0398414 -0.0813989 0.207715 -0.0396244 -0.081265 0.207941 -0.0399847 -0.081265 0.208242 -0.0402855 -0.081265 0.208385 -0.0409624 -0.0813989 0.209004 -0.0406524 -0.081265 0.209427 -0.0412 -0.0813989 0.210468 -0.0409624 -0.0813989 0.211151 -0.0409626 -0.081765 0.210923 -0.0406764 -0.0813989 0.211303 -0.0402964 -0.0813989 0.211589 -0.0398414 -0.0813989 0.212123 -0.0394155 -0.081765 0.211827 -0.0388 -0.0813989 0.212123 -0.0381845 -0.081765 0.211767 -0.038266 -0.0813989 0.211151 -0.0366375 -0.081765 0.210627 -0.0363079 -0.081765 0.210468 -0.0366377 -0.0813989 0.210042 -0.0361034 -0.081765 0.209427 -0.036034 -0.081765 0.208893 -0.0364602 -0.0813989 0.208385 -0.0366377 -0.0813989 0.207702 -0.0366375 -0.081765 0.20793 -0.0369236 -0.0813989 0.207264 -0.0370755 -0.081765 0.20755 -0.0373037 -0.0813989 0.207264 -0.0377587 -0.0813989 0.206661 -0.0388 -0.081765 0.207087 -0.0393341 -0.0813989 0.207264 -0.0405246 -0.081765 0.20755 -0.0402964 -0.0813989 0.20793 -0.0406764 -0.0813989 0.208811 -0.0414967 -0.081765 0.208893 -0.0411399 -0.0813989 0.210042 -0.0414967 -0.081765 0.210685 -0.0414129 -0.082265 0.210627 -0.0412921 -0.081765 0.211694 -0.0406082 -0.082265 0.21204 -0.0400583 -0.082265 0.211589 -0.0405246 -0.081765 0.211919 -0.0400002 -0.081765 0.212254 -0.0394454 -0.082265 0.212193 -0.0388 -0.081765 0.212254 -0.0381547 -0.082265 0.211919 -0.0375999 -0.081765 0.211694 -0.0369919 -0.082265 0.211589 -0.0370755 -0.081765 0.210685 -0.0361872 -0.082265 0.209427 -0.0359 -0.082265 0.208811 -0.0361034 -0.081765 0.208227 -0.0363079 -0.081765 0.207619 -0.0365327 -0.082265 0.206935 -0.0375999 -0.081765 0.20673 -0.0381845 -0.081765 0.206527 -0.0388 -0.082265 0.20673 -0.0394155 -0.081765 0.206935 -0.0400002 -0.081765 0.207159 -0.0406082 -0.082265 0.207619 -0.0410674 -0.082265 0.208169 -0.0414129 -0.082265 0.207702 -0.0409626 -0.081765 0.208227 -0.0412921 -0.081765 0.209427 -0.0415661 -0.081765 0.209427 -0.0417 -0.082265 0.210338 -0.0539703 -0.089998 0.211222 -0.0537334 -0.089998 0.210382 -0.0542165 -0.090065 0.212962 -0.0530133 -0.090065 0.213449 -0.0521747 -0.089998 0.21364 -0.0523354 -0.090065 0.213973 -0.051425 -0.089998 0.21419 -0.05155 -0.090065 0.214595 -0.0506812 -0.090065 0.214597 -0.0497117 -0.089998 0.214843 -0.0497551 -0.090065 0.214677 -0.0488 -0.089998 0.21436 -0.0470044 -0.089998 0.214843 -0.047845 -0.090065 0.21419 -0.04605 -0.090065 0.212052 -0.0442534 -0.089998 0.211308 -0.0436317 -0.090065 0.209427 -0.04355 -0.089998 0.208472 -0.0433836 -0.090065 0.207631 -0.0438667 -0.089998 0.206677 -0.0440369 -0.090065 0.206802 -0.0442534 -0.089998 0.206052 -0.0447783 -0.089998 0.205891 -0.0445868 -0.090065 0.20488 -0.046175 -0.089998 0.204493 -0.0470044 -0.089998 0.204258 -0.0469189 -0.090065 0.20401 -0.047845 -0.090065 0.204177 -0.0488 -0.089998 0.20401 -0.0497551 -0.090065 0.204258 -0.0506812 -0.090065 0.20488 -0.051425 -0.089998 0.204664 -0.05155 -0.090065 0.205891 -0.0530133 -0.090065 0.207546 -0.0539684 -0.090065 0.208472 -0.0542165 -0.090065 0.208515 -0.0539703 -0.089998 0.209427 -0.05405 -0.089998 0.209427 -0.0543 -0.090065 0.210307 -0.0537901 -0.089815 0.212052 -0.0533467 -0.089998 0.212801 -0.0528218 -0.089998 0.213308 -0.052057 -0.089815 0.213815 -0.0513335 -0.089815 0.21436 -0.0505956 -0.089998 0.214597 -0.0478884 -0.089998 0.213973 -0.046175 -0.089998 0.213815 -0.0462665 -0.089815 0.213449 -0.0454254 -0.089998 0.213308 -0.045543 -0.089815 0.212684 -0.0449185 -0.089815 0.212801 -0.0447783 -0.089998 0.21196 -0.0444119 -0.089815 0.21116 -0.0440386 -0.089815 0.210307 -0.04381 -0.089815 0.211222 -0.0438667 -0.089998 0.210338 -0.0436298 -0.089998 0.209427 -0.0437331 -0.089815 0.208515 -0.0436298 -0.089998 0.208547 -0.04381 -0.089815 0.20617 -0.0449185 -0.089815 0.205405 -0.0454254 -0.089998 0.205039 -0.0462665 -0.089815 0.204665 -0.047067 -0.089815 0.204437 -0.0479202 -0.089815 0.204257 -0.0478884 -0.089998 0.204257 -0.0497117 -0.089998 0.204493 -0.0505956 -0.089998 0.205039 -0.0513335 -0.089815 0.205545 -0.052057 -0.089815 0.205405 -0.0521747 -0.089998 0.206052 -0.0528218 -0.089998 0.206893 -0.0531882 -0.089815 0.206802 -0.0533467 -0.089998 0.207631 -0.0537334 -0.089998 0.208547 -0.0537901 -0.089815 0.209427 -0.053867 -0.089815 0.210295 -0.0537241 -0.089565 0.21116 -0.0535615 -0.089815 0.21196 -0.0531882 -0.089815 0.212641 -0.0526303 -0.089565 0.212684 -0.0526816 -0.089815 0.214125 -0.0505101 -0.089565 0.214351 -0.0496683 -0.089565 0.214188 -0.0505331 -0.089815 0.214417 -0.0496799 -0.089815 0.214427 -0.0488 -0.089565 0.214351 -0.0479318 -0.089565 0.214494 -0.0488 -0.089815 0.214417 -0.0479202 -0.089815 0.214188 -0.047067 -0.089815 0.213757 -0.0463 -0.089565 0.213257 -0.0455861 -0.089565 0.212641 -0.0449698 -0.089565 0.211927 -0.0444699 -0.089565 0.211137 -0.0441016 -0.089565 0.210295 -0.043876 -0.089565 0.208559 -0.043876 -0.089565 0.207717 -0.0441016 -0.089565 0.207694 -0.0440386 -0.089815 0.206893 -0.0444119 -0.089815 0.206213 -0.0449698 -0.089565 0.205597 -0.0455861 -0.089565 0.205545 -0.045543 -0.089815 0.204728 -0.0470899 -0.089565 0.20436 -0.0488 -0.089815 0.204437 -0.0496799 -0.089815 0.204665 -0.0505331 -0.089815 0.205097 -0.0513 -0.089565 0.20617 -0.0526816 -0.089815 0.206927 -0.0531302 -0.089565 0.207694 -0.0535615 -0.089815 0.207717 -0.0534985 -0.089565 0.208559 -0.0537241 -0.089565 0.210338 -0.0436298 -0.084832 0.210382 -0.0433836 -0.084765 0.212801 -0.0447783 -0.084832 0.212962 -0.0445868 -0.084765 0.213449 -0.0454254 -0.084832 0.21436 -0.0470044 -0.084832 0.214595 -0.0469189 -0.084765 0.214597 -0.0478884 -0.084832 0.214927 -0.0488 -0.084765 0.214843 -0.0497551 -0.084765 0.21436 -0.0505956 -0.084832 0.213973 -0.051425 -0.084832 0.21419 -0.05155 -0.084765 0.21364 -0.0523354 -0.084765 0.212052 -0.0533467 -0.084832 0.212962 -0.0530133 -0.084765 0.211308 -0.0539684 -0.084765 0.210382 -0.0542165 -0.084765 0.210338 -0.0539703 -0.084832 0.209427 -0.0543 -0.084765 0.208515 -0.0539703 -0.084832 0.208472 -0.0542165 -0.084765 0.207546 -0.0539684 -0.084765 0.206677 -0.0535632 -0.084765 0.206052 -0.0528218 -0.084832 0.205214 -0.0523354 -0.084765 0.204493 -0.0505956 -0.084832 0.20401 -0.0497551 -0.084765 0.204177 -0.0488 -0.084832 0.20488 -0.046175 -0.084832 0.205405 -0.0454254 -0.084832 0.206052 -0.0447783 -0.084832 0.206802 -0.0442534 -0.084832 0.207631 -0.0438667 -0.084832 0.208515 -0.0436298 -0.084832 0.208472 -0.0433836 -0.084765 0.209427 -0.04355 -0.084832 0.209427 -0.0433 -0.084765 0.211222 -0.0438667 -0.084832 0.212052 -0.0442534 -0.084832 0.212684 -0.0449185 -0.085015 0.213308 -0.045543 -0.085015 0.213815 -0.0462665 -0.085015 0.214188 -0.047067 -0.085015 0.213973 -0.046175 -0.084832 0.214417 -0.0479202 -0.085015 0.214677 -0.0488 -0.084832 0.214597 -0.0497117 -0.084832 0.214188 -0.0505331 -0.085015 0.213449 -0.0521747 -0.084832 0.212801 -0.0528218 -0.084832 0.21116 -0.0535615 -0.085015 0.211222 -0.0537334 -0.084832 0.209427 -0.05405 -0.084832 0.208547 -0.0537901 -0.085015 0.207631 -0.0537334 -0.084832 0.206893 -0.0531882 -0.085015 0.206802 -0.0533467 -0.084832 0.20617 -0.0526816 -0.085015 0.205545 -0.052057 -0.085015 0.205405 -0.0521747 -0.084832 0.205039 -0.0513335 -0.085015 0.20488 -0.051425 -0.084832 0.204665 -0.0505331 -0.085015 0.204257 -0.0497117 -0.084832 0.204257 -0.0478884 -0.084832 0.204493 -0.0470044 -0.084832 0.204665 -0.047067 -0.085015 0.205039 -0.0462665 -0.085015 0.208547 -0.04381 -0.085015 0.209427 -0.0437331 -0.085015 0.210307 -0.04381 -0.085015 0.21116 -0.0440386 -0.085015 0.21196 -0.0444119 -0.085015 0.213257 -0.0455861 -0.085265 0.213757 -0.0463 -0.085265 0.214125 -0.0470899 -0.085265 0.214494 -0.0488 -0.085015 0.214427 -0.0488 -0.085265 0.214417 -0.0496799 -0.085015 0.213815 -0.0513335 -0.085015 0.213308 -0.052057 -0.085015 0.212684 -0.0526816 -0.085015 0.212641 -0.0526303 -0.085265 0.21196 -0.0531882 -0.085015 0.210295 -0.0537241 -0.085265 0.210307 -0.0537901 -0.085015 0.209427 -0.0538 -0.085265 0.209427 -0.053867 -0.085015 0.207717 -0.0534985 -0.085265 0.207694 -0.0535615 -0.085015 0.206213 -0.0526303 -0.085265 0.205097 -0.0513 -0.085265 0.204728 -0.0505101 -0.085265 0.204503 -0.0496683 -0.085265 0.204427 -0.0488 -0.085265 0.204437 -0.0496799 -0.085015 0.20436 -0.0488 -0.085015 0.204503 -0.0479318 -0.085265 0.204437 -0.0479202 -0.085015 0.205597 -0.0455861 -0.085265 0.205545 -0.045543 -0.085015 0.20617 -0.0449185 -0.085015 0.206893 -0.0444119 -0.085015 0.207694 -0.0440386 -0.085015 0.207717 -0.0441016 -0.085265 0.209427 -0.0438 -0.085265 0.178395 -0.0048583 -0.084765 0.178395 -0.0048583 -0.077765 0.183902 -0.0116155 -0.084765 0.183902 -0.0116155 -0.077765 0.188018 -0.0132323 -0.084765 0.248821 -0.0240128 -0.081765 0.267184 -0.0201517 -0.081765 0.279054 -0.0181076 -0.081765 0.279054 -0.0181076 -0.084765 0.309639 -0.0144362 -0.084765 0.371203 -0.0138616 -0.084765 0.401851 -0.0169616 -0.084765 0.421927 -0.018 -0.0795659 0.416931 -0.018 -0.0804563 0.434327 -0.00560004 -0.077765 0.177643 0.000499958 -0.077765 0.401988 0.0159709 -0.085765 0.408869 0.00319996 -0.085765 0.416931 0.017 -0.085765 0.421927 0.017 -0.085765 0.429988 -0.0136611 -0.085765 0.421927 -0.017 -0.085765 0.426327 -0.00640004 -0.085765 0.192843 0.00554252 -0.085765 0.189643 0.00639996 -0.085765 0.186443 0.00554252 -0.085765 0.244814 0.0235 -0.085765 0.431869 -0.00320004 -0.085765 0.426289 0.0161322 -0.085765 0.426327 0.00639996 -0.085765 0.423127 0.00554252 -0.085765 0.420784 0.00319996 -0.085765 0.419927 -4.19898e-08 -0.085765 0.420784 -0.00320004 -0.085765 0.192843 -0.0055426 -0.085765 0.196043 -4.19898e-08 -0.085765 0.224827 0.00639996 -0.085765 0.221627 0.00554252 -0.085765 0.219284 0.00319996 -0.085765 0.184101 0.00319996 -0.085765 0.184101 -0.00320004 -0.085765 0.179338 -0.00452305 -0.085765 0.181341 -0.00808043 -0.085765 0.218427 -4.19898e-08 -0.085765 0.219284 -0.00320004 -0.085765 0.18822 -0.0122529 -0.085765 0.221627 -0.0055426 -0.085765 0.278899 -0.0171198 -0.085765 0.396927 -4.19898e-08 -0.085765 0.400127 -0.0055426 -0.085765 0.406527 0.00554252 -0.085765 0.400127 0.00554252 -0.085765 0.231227 -4.19898e-08 -0.085765 0.224827 -0.00640004 -0.085765 0.241023 -0.0231386 -0.085765 0.228027 -0.0055426 -0.085765 0.244814 -0.0235001 -0.085765 0.248593 -0.0230391 -0.085765 0.230369 -0.00320004 -0.085765 0.230369 0.00319996 -0.085765 0.278899 0.0171197 -0.085765 0.309556 0.0134395 -0.085765 0.226477 0.00285784 -0.077765 0.227685 0.00164996 -0.077765 0.426327 -0.00330004 -0.077765 0.406627 -4.19898e-08 -0.077765 0.406185 -0.00165004 -0.077765 0.404977 -0.00285793 -0.077765 0.235915 -0.0231067 -0.077765 0.227685 -0.00165004 -0.077765 0.424677 -0.00285793 -0.077765 0.423469 -0.00165004 -0.077765 0.423027 -4.19898e-08 -0.077765 0.180565 -0.00871213 -0.077765 0.191293 -0.00285793 -0.077765 0.188018 -0.0132323 -0.077765 0.430695 -0.0143682 -0.077765 0.429627 -4.19898e-08 -0.077765 0.266449 -0.0162199 -0.077765 0.298555 -0.01148 -0.077765 0.400027 -4.19898e-08 -0.077765 0.33093 -0.00921193 -0.077765 0.363383 -0.00942888 -0.077765 0.400469 -0.00165004 -0.077765 0.401677 -0.00285793 -0.077765 0.177643 -0.000500042 -0.077765 0.186785 -0.00165004 -0.077765 0.221527 -4.19898e-08 -0.077765 0.221969 -0.00165004 -0.077765 0.223177 -0.00285793 -0.077765 0.423469 0.00164996 -0.077765 0.183902 0.0116154 -0.077765 0.187993 0.00285784 -0.077765 0.186343 -4.19898e-08 -0.077765 0.403327 0.00329996 -0.077765 0.404977 0.00285784 -0.077765 0.429185 0.00164996 -0.077765 0.188018 0.0132322 -0.077765 0.434327 0.00559996 -0.077765 0.427977 0.00285784 -0.077765 0.235915 0.0231066 -0.077765 0.248821 0.0240127 -0.084765 0.244827 0.0245 -0.0813113 0.371203 0.0138615 -0.084765 0.340411 0.0130182 -0.081765 0.309639 0.0144361 -0.081765 0.279054 0.0181075 -0.084765 0.401851 0.0169615 -0.084765 0.416931 0.018 -0.0804563 0.183902 0.0116154 -0.084765 0.180565 0.00871205 -0.077765 0.178395 0.00485822 -0.084765 0.177643 0.000499958 -0.084765 0.178395 0.00485822 -0.077765 0.421927 0.018 -0.084765 0.426672 0.0170561 -0.084765 0.424387 0.0177534 -0.0788642 0.426672 0.0170561 -0.077765 0.430695 0.0143681 -0.077765 0.433383 0.0103452 -0.077765 0.434327 0.00559996 -0.084765 0.424404 -0.0177501 -0.0788578 0.426633 -0.0170724 -0.077765 0.426672 -0.0170561 -0.077765 0.433383 -0.0103453 -0.077765 0.187993 -0.00285793 -0.077765 0.187993 -0.00285793 -0.082665 0.186785 0.00164996 -0.077765 0.187993 0.00285784 -0.082665 0.189643 0.00329996 -0.082665 0.189643 0.00329996 -0.077765 0.191293 0.00285784 -0.077765 0.192501 0.00164996 -0.077765 0.192943 -4.19898e-08 -0.077765 0.192501 0.00164996 -0.082665 0.192501 -0.00165004 -0.077765 0.192501 -0.00165004 -0.082665 0.189643 -0.00330004 -0.077765 0.186785 -0.00165004 -0.082665 0.186443 -0.0055426 -0.085765 0.186343 -4.19898e-08 -0.082665 0.183243 -4.19898e-08 -0.085765 0.186785 0.00164996 -0.082665 0.191293 0.00285784 -0.082665 0.195186 0.00319996 -0.085765 0.192943 -4.19898e-08 -0.082665 0.195186 -0.00320004 -0.085765 0.191293 -0.00285793 -0.082665 0.189643 -0.00330004 -0.082665 0.189643 -0.00640004 -0.085765 0.223177 -0.00285793 -0.082665 0.221969 0.00164996 -0.077765 0.223177 0.00285784 -0.077765 0.221969 0.00164996 -0.082665 0.223177 0.00285784 -0.082665 0.224827 0.00329996 -0.077765 0.224827 0.00329996 -0.082665 0.226477 0.00285784 -0.082665 0.227685 0.00164996 -0.082665 0.228127 -4.19898e-08 -0.077765 0.228127 -4.19898e-08 -0.082665 0.226477 -0.00285793 -0.077765 0.226477 -0.00285793 -0.082665 0.224827 -0.00330004 -0.077765 0.224827 -0.00330004 -0.082665 0.221969 -0.00165004 -0.082665 0.221527 -4.19898e-08 -0.082665 0.228027 0.00554252 -0.085765 0.227685 -0.00165004 -0.082665 0.424677 -0.00285793 -0.082665 0.423027 -4.19898e-08 -0.082665 0.423469 0.00164996 -0.082665 0.424677 0.00285784 -0.077765 0.424677 0.00285784 -0.082665 0.426327 0.00329996 -0.077765 0.429627 -4.19898e-08 -0.082665 0.429185 -0.00165004 -0.077765 0.429185 -0.00165004 -0.082665 0.427977 -0.00285793 -0.077765 0.423469 -0.00165004 -0.082665 0.426327 0.00329996 -0.082665 0.427977 0.00285784 -0.082665 0.429527 0.00554252 -0.085765 0.429185 0.00164996 -0.082665 0.431869 0.00319996 -0.085765 0.432727 -4.19898e-08 -0.085765 0.429527 -0.0055426 -0.085765 0.427977 -0.00285793 -0.082665 0.426327 -0.00330004 -0.082665 0.423127 -0.0055426 -0.085765 0.401677 -0.00285793 -0.082665 0.400469 0.00164996 -0.077765 0.400469 0.00164996 -0.082665 0.401677 0.00285784 -0.082665 0.401677 0.00285784 -0.077765 0.404977 0.00285784 -0.082665 0.406185 0.00164996 -0.077765 0.406185 0.00164996 -0.082665 0.406627 -4.19898e-08 -0.082665 0.403327 -0.00330004 -0.077765 0.404977 -0.00285793 -0.082665 0.400469 -0.00165004 -0.082665 0.397784 -0.00320004 -0.085765 0.400027 -4.19898e-08 -0.082665 0.397784 0.00319996 -0.085765 0.403327 0.00329996 -0.082665 0.403327 0.00639996 -0.085765 0.409727 -4.19898e-08 -0.085765 0.408869 -0.00320004 -0.085765 0.406185 -0.00165004 -0.082665 0.406527 -0.0055426 -0.085765 0.403327 -0.00330004 -0.082665 0.403327 -0.00640004 -0.085765 0.244827 -0.0245 -0.0813113 0.240821 -0.024118 -0.0799742 0.246821 -0.0243666 -0.0816493 0.409401 -0.017742 -0.0814346 0.298987 -0.0154566 -0.081765 0.309639 -0.0144362 -0.081765 0.331056 -0.0132099 -0.081765 0.340411 -0.0130183 -0.081765 0.363203 -0.0134248 -0.081765 0.371203 -0.0138616 -0.081765 0.395725 -0.0121296 -0.077765 0.39524 -0.0161001 -0.081765 0.401851 -0.0169616 -0.081765 0.426633 0.0170723 -0.077765 0.421927 0.018 -0.0795659 0.409401 0.017742 -0.0814346 0.401851 0.0169615 -0.081765 0.395725 0.0121295 -0.077765 0.39524 0.0161 -0.081765 0.371203 0.0138615 -0.081765 0.363383 0.00942879 -0.077765 0.363203 0.0134247 -0.081765 0.33093 0.00921184 -0.077765 0.331056 0.0132098 -0.081765 0.298987 0.0154565 -0.081765 0.298555 0.01148 -0.077765 0.279054 0.0181075 -0.081765 0.266449 0.0162198 -0.077765 0.267184 0.0201517 -0.081765 0.240821 0.0241179 -0.0799742 0.248821 0.0240127 -0.081765 0.246826 0.0243659 -0.0816499 0.371267 0.0128636 -0.085765 0.340411 0.0130182 -0.084765 0.340401 0.0120183 -0.085765 0.309639 0.0144361 -0.084765 0.248593 0.023039 -0.085765 0.240821 0.0241179 -0.084765 0.244827 0.0245 -0.084765 0.18822 0.0122528 -0.085765 0.241023 0.0231385 -0.085765 0.416931 0.018 -0.084765 0.179338 0.00452297 -0.085765 0.181341 0.00808035 -0.085765 0.180565 0.00871205 -0.084765 0.188018 0.0132322 -0.084765 0.18442 0.0107604 -0.085765 0.430695 0.0143681 -0.084765 0.429988 0.013661 -0.085765 0.433383 0.0103452 -0.084765 0.432459 0.00996255 -0.085765 0.178643 -0.000500042 -0.085765 0.177643 -0.000500042 -0.084765 0.178643 0.000499958 -0.085765 0.433327 -0.00560004 -0.085765 0.433327 0.00559996 -0.085765 0.18442 -0.0107604 -0.085765 0.180565 -0.00871213 -0.084765 0.434327 -0.00560004 -0.084765 0.432459 -0.00996263 -0.085765 0.433383 -0.0103453 -0.084765 0.430695 -0.0143682 -0.084765 0.426289 -0.0161323 -0.085765 0.426672 -0.0170561 -0.084765 0.421927 -0.018 -0.084765 0.248821 -0.0240128 -0.084765 0.244827 -0.0245 -0.084765 0.240821 -0.024118 -0.084765 0.416931 -0.018 -0.084765 0.416931 -0.017 -0.085765 0.401988 -0.015971 -0.085765 0.309556 -0.0134396 -0.085765 0.340411 -0.0130183 -0.084765 0.340401 -0.0120184 -0.085765 0.371267 -0.0128637 -0.085765 0.441027 0.0103 0.0455442 0.435002 0.0103 0.0455442 0.441027 0.010925 0.0466268 0.435002 0.0104674 0.0461692 0.435002 0.010925 0.0466268 0.435002 0.01155 0.0467942 0.435002 0.012175 0.0466268 0.435002 0.0126325 0.0461692 0.441027 -0.0126763 0.0460866 0.435002 -0.0126763 0.0460866 0.441027 -0.0123294 0.0465215 0.441027 -0.0118282 0.0467629 0.435002 -0.0118282 0.0467629 0.441027 -0.0112719 0.0467629 0.435002 -0.0112719 0.0467629 0.441027 -0.0107707 0.0465215 0.441027 -0.0104238 0.0460866 0.435002 -0.0104238 0.0460866 0.441027 -0.0103 0.0455442 0.441027 0.00854996 0.0453442 0.436027 0.00854996 0.0453442 0.441027 0.00800066 0.0432942 0.436027 0.00800066 0.0432942 0.436027 0.00649996 0.0417935 0.436027 0.00444996 0.0412442 0.441027 -0.00800075 0.0432942 0.441027 -0.00855004 0.0453442 0.436027 -0.00855004 0.0453442 0.441027 -0.00855004 0.0457442 0.436027 -0.00855004 0.0457442 0.441027 -0.00800075 0.0477942 0.436027 -0.00800075 0.0477942 0.436027 -0.00650004 0.0492949 0.441027 -0.00445004 0.0498442 0.436027 0.00444996 0.0498442 0.441027 0.00649996 0.0492949 0.436027 0.00649996 0.0492949 0.436027 0.00800066 0.0477942 0.441027 0.00854996 0.0457442 0.435002 -0.0104675 0.0449192 0.441027 -0.010925 0.0444617 0.435002 -0.010925 0.0444617 0.441027 -0.01155 0.0442942 0.435002 -0.01155 0.0442942 0.441027 -0.012175 0.0444617 0.435002 -0.012175 0.0444617 0.441027 -0.0126326 0.0449192 0.435002 -0.0126326 0.0449192 0.441027 -0.0128 0.0455442 0.441027 0.0126325 0.0449192 0.435002 0.0128 0.0455442 0.435002 0.0126325 0.0449192 0.441027 0.010925 0.0444617 0.435002 0.010925 0.0444617 0.435002 0.0104674 0.0449192 0.434727 0.00444996 0.0399442 0.436027 -0.00445004 0.0412442 0.436027 -0.00650004 0.0417935 0.436027 -0.00800075 0.0432942 0.434727 0.0091265 0.0426442 0.434727 0.00984996 0.0457442 0.434727 -0.00985004 0.0457442 0.434727 -0.00912658 0.0484442 0.434727 -0.00715004 0.0504208 0.436027 -0.00445004 0.0498442 0.436027 0.00854996 0.0457442 0.434727 -0.00445004 0.0511442 0.428729 0.0490655 0.0531965 0.428686 0.0490702 0.0535687 0.428637 0.0489261 0.0534931 0.429152 0.0498586 0.0526932 0.429014 0.0496373 0.0524148 0.429611 0.0518254 0.0514269 0.42937 0.0506998 0.0516888 0.429772 0.0532813 0.0516754 0.429769 0.0532044 0.0518665 0.429778 0.0542528 0.0525675 0.429679 0.0551394 0.0535452 0.428795 0.0491942 0.0536542 0.429045 0.0497588 0.0525493 0.429868 0.0531198 0.0520624 0.429736 0.0519667 0.0518344 0.429385 0.0507729 0.0518701 0.429487 0.0508259 0.0520587 0.429674 0.0519751 0.0517344 0.429638 0.0519795 0.0516257 0.429537 0.0551894 0.0548682 0.429688 0.0549554 0.0536223 0.42979 0.0547736 0.0537086 0.429878 0.0541077 0.052719 0.429805 0.0531611 0.0519687 0.429702 0.0524661 0.0514541 0.430184 0.052304 0.0520425 0.430259 0.0530296 0.052231 0.430157 0.0530385 0.0522232 0.430272 0.0539013 0.0527802 0.430166 0.0539914 0.0528516 0.43001 0.0548442 0.0549202 0.429757 0.0508277 0.0522332 0.429493 0.0498913 0.0528718 0.429405 0.0499054 0.0528457 0.429315 0.0499049 0.0528076 0.429005 0.0491554 0.0541238 0.428655 0.0490186 0.0548507 0.428813 0.0490445 0.0548785 0.429873 0.0547038 0.0537466 0.429963 0.0540516 0.0527801 0.430062 0.0540124 0.0528248 0.430052 0.0530565 0.0521933 0.42982 0.0519547 0.051917 0.429918 0.0519403 0.0519761 0.429229 0.0498894 0.0527561 0.42966 0.0508375 0.0521953 0.430021 0.0519247 0.0520099 0.430072 0.0546295 0.053799 0.42997 0.0546554 0.0537772 0.429912 0.0548536 0.0549178 0.429033 0.049278 0.0537607 0.42895 0.0492657 0.0537306 0.429567 0.0508373 0.0521364 0.429953 0.053084 0.0521392 0.42964 0.0550095 0.0548815 0.429795 -0.0548868 0.0549797 0.42968 -0.0549829 0.0537026 0.429877 -0.0541614 0.0527772 0.429775 -0.0532785 0.0519031 0.429651 -0.0520606 0.0516308 0.429751 -0.0520429 0.0518379 0.42907 -0.049818 0.0524972 0.430034 -0.0519986 0.0520105 0.429972 -0.051231 0.0521092 0.429873 -0.0508771 0.0522236 0.42973 -0.0504505 0.0524345 0.42943 -0.0499571 0.0527963 0.429057 -0.0493083 0.0536936 0.429139 -0.0493055 0.0537173 0.429996 -0.054843 0.0550059 0.429901 -0.0548527 0.0549932 0.43019 -0.0545545 0.0536567 0.430063 -0.0546579 0.0538698 0.430272 -0.0539013 0.05278 0.430163 -0.0540446 0.0529057 0.430277 -0.0537536 0.0526538 0.430264 -0.0530991 0.05226 0.430162 -0.0531075 0.0522524 0.430213 -0.0525318 0.0520803 0.430089 -0.0517449 0.052027 0.43006 -0.0540656 0.0528796 0.429681 -0.0509051 0.0521691 0.429778 -0.0508948 0.0522064 0.42934 -0.0499574 0.0527584 0.428672 -0.0490218 0.0547728 0.42871 -0.0491061 0.0534955 0.428661 -0.04896 0.053414 0.429405 -0.0508481 0.0518443 0.429649 -0.0520637 0.0514225 0.42979 -0.0540003 0.0520805 0.429776 -0.0543082 0.0526308 0.429711 -0.0549355 0.0549696 0.429963 -0.0546837 0.0538487 0.429867 -0.054732 0.0538196 0.429961 -0.0541048 0.0528362 0.430058 -0.0531254 0.0522231 0.429959 -0.0531534 0.0521702 0.429932 -0.0520142 0.0519774 0.429835 -0.0520294 0.0519193 0.429589 -0.0509061 0.0521108 0.428974 -0.0492969 0.053663 0.42882 -0.0492277 0.0535844 0.428446 -0.048864 0.0547251 0.429783 -0.0548014 0.0537837 0.429874 -0.0531902 0.0520952 0.429508 -0.0508964 0.0520335 0.429177 -0.0499141 0.0526433 0.429254 -0.0499433 0.0527067 0.437165 -0.0558332 0.00639945 0.437101 -0.0568935 0.00762319 0.437175 -0.0561628 0.0069244 0.437191 -0.0542861 0.00579967 0.437111 -0.0509066 0.00790573 0.437063 -0.0507149 0.00913231 0.437061 -0.050621 0.0081463 0.43708 -0.0507374 0.00783166 0.437646 -0.0519072 0.00705513 0.437597 -0.0513151 0.00781227 0.437491 -0.051191 0.00805024 0.437407 -0.0509564 0.00915888 0.437686 -0.0531553 0.00638348 0.437505 -0.0538947 0.00625972 0.437556 -0.0559411 0.00716033 0.437681 -0.0550025 0.00652842 0.437494 -0.0550137 0.00649412 0.437496 -0.0565614 0.00810951 0.437646 -0.05592 0.00715037 0.437172 -0.0516152 0.00687472 0.437318 -0.0527305 0.00635954 0.437208 -0.0526653 0.00619194 0.43722 -0.053898 0.00596121 0.437209 -0.0551261 0.00621816 0.43732 -0.0550573 0.00638427 0.437285 -0.0560379 0.0070521 0.437228 -0.0566884 0.00804299 0.437116 -0.0568495 0.00797192 0.437553 -0.0518313 0.0071158 0.437403 -0.0509557 0.0091586 0.437401 -0.0565848 0.0080946 0.437245 -0.0508974 0.00914697 0.437142 -0.0508182 0.00913893 0.437396 -0.0511681 0.00803465 0.437223 -0.0510659 0.00798048 0.437283 -0.0517372 0.0070052 0.437457 -0.0518146 0.00709354 0.437493 -0.0527716 0.00647037 0.43733 -0.0538961 0.00614133 0.43746 -0.0559584 0.00713855 0.437312 -0.056802 0.0092166 0.432897 -0.0462207 -0.0377953 0.433511 -0.0454747 -0.0357677 0.432803 -0.0471629 -0.0384769 0.432931 -0.0494408 -0.0385402 0.433117 -0.0504111 -0.0379195 0.433059 -0.0491637 -0.0386045 0.432978 -0.0482906 -0.0387127 0.432966 -0.0480597 -0.0386968 0.433203 -0.0503853 -0.0379128 0.433279 -0.0503559 -0.0379314 0.432793 -0.0507331 -0.0381816 0.43303 -0.0514918 -0.0371063 0.432821 -0.045381 -0.0368477 0.43265 -0.0455431 -0.0375361 0.432629 -0.0460394 -0.0379228 0.432474 -0.0470038 -0.0388052 0.433073 -0.0513264 -0.0370411 0.432843 -0.0506114 -0.0380654 0.432957 -0.0504957 -0.0379707 0.43266 -0.0495518 -0.0387411 0.43255 -0.0483057 -0.0389554 0.432535 -0.0470681 -0.0386675 0.433057 -0.0462522 -0.0377904 0.433176 -0.0456465 -0.0368172 0.433091 -0.0456205 -0.0368106 0.433436 -0.0454685 -0.0357023 0.433255 -0.0456576 -0.0368284 0.433438 -0.0510346 -0.0369868 0.433349 -0.0510639 -0.0369813 0.433595 -0.0513104 -0.0358692 0.433076 -0.0451802 -0.0356148 0.432489 -0.0483043 -0.0391093 0.432507 -0.0485951 -0.0391057 0.432604 -0.0496152 -0.0388878 0.433262 -0.0454006 -0.0356624 0.433348 -0.0454438 -0.0356823 0.432934 -0.0455236 -0.0368163 0.432744 -0.0461463 -0.0378409 0.432651 -0.0471248 -0.0385504 0.432819 -0.048298 -0.038739 0.432665 -0.0483035 -0.0388232 0.432775 -0.0494896 -0.0386164 0.433262 -0.0511099 -0.0369839 0.433185 -0.0511714 -0.0369952 0.433102 0.0513853 -0.0369005 0.433061 0.0456703 -0.0369409 0.432681 0.0454385 -0.037361 0.433154 0.0453387 -0.0357885 0.432793 0.0454363 -0.0369904 0.43274 0.0452833 -0.0370459 0.432645 0.0472616 -0.0386102 0.432531 0.0472119 -0.0387299 0.432725 0.0462473 -0.0379475 0.432905 0.0455751 -0.0369522 0.432611 0.0461462 -0.0380344 0.432679 0.0496957 -0.0386822 0.43282 0.0508472 -0.0380676 0.433049 0.0490847 -0.0386256 0.433273 0.050332 -0.0379535 0.433472 0.0509232 -0.0371971 0.433809 0.0512739 -0.0357665 0.433804 0.0512742 -0.0357902 0.433722 0.0512816 -0.0357496 0.433113 0.0495428 -0.0384681 0.432947 0.0495731 -0.0384861 0.43319 0.0499717 -0.0382343 0.433226 0.050484 -0.0378144 0.433204 0.0457551 -0.0370587 0.432797 0.0472947 -0.0385341 0.433004 0.0465987 -0.0381068 0.433028 0.0464166 -0.0379534 0.433144 0.0456965 -0.0369455 0.433317 0.0454424 -0.0358219 0.433212 0.0512274 -0.0368615 0.433348 0.0516003 -0.0356725 0.432593 0.049529 -0.0389195 0.432558 0.0484627 -0.038957 0.43247 0.0471553 -0.0388699 0.432552 0.0460343 -0.0381404 0.433538 0.0513564 -0.0357129 0.43329 0.0511648 -0.0368529 0.432869 0.05072 -0.0379573 0.433061 0.0515537 -0.0369581 0.432877 0.0463181 -0.0378975 0.432672 0.0484531 -0.0388249 0.432792 0.0496268 -0.0385604 0.432825 0.0484422 -0.0387403 0.432981 0.0505992 -0.0378678 0.43314 0.0505109 -0.0378202 0.433375 0.0511179 -0.0368523 0.433465 0.051088 -0.036859 0.43714 0.0514334 0.00679237 0.437107 0.0508795 0.0079706 0.437093 0.0508357 0.00762193 0.437207 0.0526026 0.00621779 0.437179 0.0525295 0.0060452 0.437191 0.0534411 0.00579974 0.437192 0.0538287 0.00577355 0.437185 0.0549778 0.00596038 0.437177 0.0561137 0.0068755 0.43709 0.0569919 0.00783297 0.437046 0.0570727 0.00913132 0.43712 0.0568224 0.00790702 0.437071 0.0571086 0.00814819 0.437667 0.0554832 0.00678982 0.437605 0.0564131 0.00781303 0.4375 0.0565369 0.0080507 0.437505 0.0538334 0.00625971 0.437692 0.0538335 0.00629571 0.437683 0.0529673 0.00643756 0.437403 0.0509565 0.00922267 0.43749 0.0509639 0.00921209 0.437487 0.0511665 0.00810902 0.437288 0.0559914 0.00700586 0.43733 0.0538323 0.00614132 0.43721 0.0550634 0.00619229 0.43722 0.0538306 0.0059612 0.437317 0.0526712 0.00638398 0.43728 0.0516907 0.00705142 0.437169 0.051566 0.00692358 0.437218 0.0510402 0.00804186 0.437058 0.0507147 0.00920115 0.437558 0.0558967 0.00711602 0.437405 0.05656 0.00803536 0.43755 0.0517869 0.00716009 0.437462 0.0559136 0.00709393 0.437231 0.0566626 0.00798158 0.437321 0.0549979 0.00635981 0.437496 0.0549565 0.00647051 0.437492 0.0527145 0.00649396 0.437454 0.0517698 0.00713814 0.437392 0.0511434 0.00809387 0.425327 -0.00226735 0.0606406 0.425077 -0.00289264 0.0594927 0.425327 -0.00282733 0.0594778 0.425077 -0.00289264 0.0581722 0.425327 -0.00290004 0.0588324 0.425077 -0.00231973 0.0569826 0.425077 -0.00128737 0.0561593 0.425327 -4.19898e-08 0.0559324 0.425077 -0.00128737 0.0615056 0.425077 -0.00231973 0.0606823 0.424894 -0.00307106 0.0595334 0.424894 -0.00136678 0.0559944 0.424827 -4.19898e-08 0.0622324 0.424894 -0.00136678 0.0616705 0.424894 -0.00246281 0.0607964 0.424827 -0.00265827 0.0609523 0.424894 -0.00307106 0.0581315 0.424827 -0.00265827 0.0567126 0.424894 -0.00246281 0.0568685 0.424827 -0.00147525 0.0557692 0.424894 -4.19898e-08 0.0556824 0.426698 0.00217094 -0.0412903 0.427596 0.00273947 -0.0402866 0.430043 0.000712905 -0.0365236 0.430095 -4.17934e-08 -0.036435 0.42964 0.0019608 -0.0371984 0.4287 0.00282669 -0.0386856 0.428895 0.0027405 -0.0383865 0.426395 0.0024609 -0.0414114 0.427132 0.00300592 -0.0403 0.426474 0.00236685 -0.0413282 0.427232 0.00285929 -0.040303 0.42854 0.00290376 -0.0380337 0.428505 0.00299671 -0.0379799 0.429069 0.00234049 -0.0369472 0.429456 0.00129431 -0.036211 0.428671 0.00276226 -0.0381588 0.428002 0.002983 -0.0392361 0.428079 0.00293602 -0.0392806 0.428758 0.00272466 -0.0382205 0.428849 0.00271065 -0.0382757 0.428159 0.00290866 -0.0393272 0.429619 0.00118025 -0.0365472 0.429154 0.00219221 -0.0371273 0.429235 0.00214487 -0.037213 0.429542 0.00212372 -0.0373602 0.429331 0.00212122 -0.0372852 0.429434 0.00212026 -0.0373396 0.42612 0.000221141 -0.0422266 0.426071 -4.06031e-08 -0.0422367 0.426356 0.00129581 -0.0419293 0.425887 0.00135163 -0.0421766 0.426074 0.00126874 -0.0420166 0.425847 -4.14699e-08 -0.0423117 0.426191 0.001219 -0.0419843 0.426763 0.00213808 -0.041302 0.427114 0.00241393 -0.040942 0.427365 0.00275017 -0.0403423 0.426574 0.00225879 -0.0412921 0.427296 0.00279861 -0.0403185 0.425973 0.00132658 -0.0420781 0.42953 0.00124868 -0.0359466 0.42909 0.00250781 -0.0368046 0.428263 0.00331725 -0.0383292 0.427335 0.00329785 -0.0399175 0.429725 0.00117015 -0.036623 0.429984 -4.18539e-08 -0.0364223 0.429837 0.00117452 -0.03667 0.427437 0.00271531 -0.0403729 0.427933 0.00304846 -0.0391966 0.427836 0.00321867 -0.0391427 0.428596 0.00282329 -0.0380948 0.429097 0.00225981 -0.0370358 0.429533 0.00120609 -0.0364463 0.429477 0.00124572 -0.03633 0.42967 -4.20109e-08 -0.0361977 0.425994 -4.09069e-08 -0.0422493 0.429098 -0.00225919 -0.037035 0.429478 -0.00124356 -0.036329 0.429614 -4.20329e-08 -0.0360713 0.429456 -0.00129207 -0.03621 0.428497 -0.00318995 -0.0379091 0.429596 -4.20353e-08 -0.0359572 0.429648 -4.19898e-08 -0.0357111 0.428503 -0.00299823 -0.0379836 0.42907 -0.00233986 -0.0369464 0.428538 -0.00290528 -0.0380372 0.427832 -0.00321877 -0.0391502 0.427928 -0.00304865 -0.0392038 0.427129 -0.00300377 -0.0403058 0.426283 -0.00109388 -0.0420208 0.426191 -0.00121895 -0.0419844 0.429945 -0.00118781 -0.0366894 0.430043 -0.000714224 -0.0365243 0.429838 -0.00117249 -0.036669 0.429434 -0.00211969 -0.0373389 0.428892 -0.0027422 -0.0383912 0.428847 -0.00271203 -0.038279 0.428264 -0.00290004 -0.039335 0.427597 -0.00274015 -0.0402849 0.427292 -0.00279668 -0.0403239 0.428074 -0.00293618 -0.0392875 0.428756 -0.00272608 -0.0382238 0.428669 -0.00276373 -0.0381622 0.429332 -0.00212065 -0.0372846 0.42962 -0.0011782 -0.0365463 0.429725 -0.00116813 -0.0366221 0.429852 -4.19228e-08 -0.0363716 0.428155 -0.00290874 -0.039334 0.427433 -0.00271338 -0.0403781 0.427362 -0.00274825 -0.0403476 0.426764 -0.00213831 -0.0413018 0.426698 -0.00217117 -0.0412902 0.426408 -0.00248008 -0.0413914 0.427801 -0.00340289 -0.0391352 0.428233 -0.00332935 -0.0383837 0.426873 -0.00216764 -0.0412616 0.426715 -0.00196471 -0.041468 0.426074 -0.00126868 -0.0420166 0.425973 -0.00132652 -0.0420782 0.426574 -0.00225903 -0.041292 0.426474 -0.0023671 -0.041328 0.427228 -0.00285731 -0.0403085 0.427997 -0.0029832 -0.0392431 0.428594 -0.00282478 -0.0380983 0.429154 -0.00219161 -0.0371266 0.429235 -0.00214428 -0.0372123 0.429534 -0.001204 -0.0364454 0.429758 -4.19697e-08 -0.0363041 0.425898 0.0160221 0.0427771 0.425916 0.0157322 0.0440564 0.426664 0.0152105 0.04144 0.425896 0.0156694 0.0433489 0.426744 0.0150261 0.0415895 0.425725 0.0159252 0.0432017 0.425819 0.0157382 0.0432949 0.425331 0.0158865 0.0453078 0.425985 0.0156242 0.0434021 0.42644 0.015324 0.0425399 0.42687 0.0151363 0.0422418 0.42749 0.0140001 0.04006 0.42776 0.0137163 0.0393147 0.428053 0.0125717 0.0387795 0.428071 0.0125075 0.0388946 0.428539 0.0124149 0.0392633 0.428241 0.0132483 0.039851 0.428211 0.0124158 0.039111 0.428051 0.013169 0.0397179 0.428318 0.0123982 0.039189 0.427982 0.013784 0.0403374 0.427347 0.0144367 0.0410078 0.427727 0.0138486 0.0403271 0.427627 0.0138749 0.0402503 0.42725 0.0144678 0.0409324 0.426912 0.0149278 0.0417407 0.428888 0.0106636 0.038507 0.428849 0.00875363 0.0382313 0.428623 0.00876095 0.0381119 0.428659 0.0106559 0.0384463 0.428534 0.00876385 0.0380019 0.428461 0.0106867 0.0382604 0.428407 0.0107163 0.0381341 0.428391 0.0107508 0.0380045 0.42717 0.0145258 0.040846 0.42669 0.0151116 0.0415105 0.427469 0.0140862 0.0399659 0.426664 0.0152155 0.0414368 0.428374 0.0114087 0.0379747 0.427947 0.0131908 0.0396403 0.427863 0.0132359 0.0395431 0.427545 0.0139269 0.0401582 0.426822 0.014963 0.0416694 0.428104 0.0127001 0.0385901 0.428126 0.0124533 0.0390094 0.428549 0.010666 0.0383681 0.428431 0.0123994 0.0392392 0.428776 0.0106559 0.0384914 0.425446 0.01585 0.0457442 0.425025 0.0163679 0.0452473 0.425054 0.016179 0.045253 0.425162 0.0160028 0.0452744 0.424982 0.0161759 0.0456756 0.428462 0.00876617 0.0377355 0.42836 -4.20576e-08 0.0377331 0.428479 0.00876564 0.0378711 0.428376 -4.20406e-08 0.0378692 0.428735 0.00875732 0.0381897 0.428632 -4.17643e-08 0.0381894 0.428962 0.00874996 0.0382442 0.425261 0.0158862 0.0457169 0.425153 0.0155718 0.047822 0.424972 0.0156836 0.047856 0.425091 0.0160013 0.0456917 0.428962 -0.00875004 0.0382442 0.42852 -4.1885e-08 0.0381112 0.428534 -0.00876394 0.0380019 0.428431 -4.19982e-08 0.0380007 0.428479 -0.00876573 0.0378711 0.425077 0.00874996 0.0529112 0.424972 0.00874996 0.0529924 0.425327 0.010277 0.0526781 0.425327 0.00874996 0.0528442 0.425153 0.0137543 0.0508248 0.424856 0.015858 0.0479091 0.424827 0.0153738 0.0494704 0.424827 0.0140832 0.0511587 0.424856 0.0139642 0.0510379 0.424827 0.0123756 0.0524236 0.424856 0.00874996 0.0531746 0.424827 0.0103846 0.0531664 0.424856 0.0103481 0.0530007 0.425153 0.0102838 0.0527086 0.424972 0.0122078 0.0521144 0.425153 0.012152 0.0520117 0.424972 0.0138363 0.050908 0.425153 0.0149653 0.0492406 0.424856 0.0122947 0.0522746 0.424972 0.0103089 0.0528227 0.424856 0.015226 0.0493873 0.424972 0.0150671 0.0492979 0.42845 -0.0108262 0.0377869 0.428729 -0.00972573 0.0382544 0.426664 -0.0152105 0.0414398 0.428519 -0.0115659 0.0387656 0.42896 -0.00972626 0.0383117 0.428735 -0.00875741 0.0381897 0.42839 -0.0107581 0.0380065 0.428406 -0.0107234 0.0381361 0.428069 -0.012516 0.0388995 0.428209 -0.0124241 0.0391159 0.428315 -0.0124065 0.0391938 0.428537 -0.0124232 0.0392682 0.426915 -0.0149269 0.0417431 0.427014 -0.014918 0.0418043 0.427097 -0.0149285 0.0418458 0.427487 -0.0140068 0.0400666 0.426739 -0.0150316 0.0415835 0.426821 -0.0149628 0.0416695 0.427724 -0.013855 0.0403336 0.427785 -0.0136561 0.0392644 0.427504 -0.0142657 0.0398265 0.428462 -0.00876626 0.0377355 0.42846 -0.0106938 0.0382623 0.428623 -0.00876103 0.0381119 0.428548 -0.010673 0.03837 0.428658 -0.0106629 0.0384482 0.428336 -0.0116482 0.0380671 0.428051 -0.0125804 0.0387846 0.427465 -0.0140929 0.0399727 0.428123 -0.0124617 0.0390143 0.427541 -0.0139334 0.0401648 0.427623 -0.0138814 0.0402568 0.428428 -0.0124076 0.0392441 0.427831 -0.0138531 0.0403902 0.427984 -0.0137794 0.0403328 0.425153 0.00874996 0.0528755 0.424894 0.00874996 0.0530942 0.425732 -0.0159216 0.0431875 0.42669 -0.0151115 0.0415105 0.426896 -0.0149319 0.0417291 0.426449 -0.0153175 0.0425243 0.425992 -0.0156206 0.0433888 0.426177 -0.0156008 0.0434794 0.425331 -0.0158866 0.0453078 0.425728 -0.016121 0.0431314 0.425437 -0.0162631 0.04382 0.425825 -0.0157345 0.0432811 0.425162 -0.0160029 0.0452744 0.425902 -0.0156657 0.0433354 0.425153 -0.0155719 0.047822 0.425327 -0.0154112 0.0482017 0.425327 -0.0149601 0.0491859 0.425327 -0.013756 0.0507792 0.425153 -0.0121708 0.0520015 0.425327 -0.0102861 0.0526761 0.425153 -0.0102929 0.0527066 0.425153 -0.00875004 0.0528755 0.424972 -0.0103182 0.0528207 0.424972 -0.00875004 0.0529924 0.424856 -0.00875004 0.0531746 0.424856 -0.0123143 0.052264 0.424856 -0.0139889 0.0510135 0.424827 -0.0141085 0.0511337 0.424827 -0.0153974 0.0494283 0.424856 -0.0152491 0.0493461 0.425153 -0.0149875 0.0492011 0.425153 -0.013778 0.0508013 0.424972 -0.0138604 0.0508842 0.425077 -0.00875004 0.0529112 0.424972 -0.0150897 0.0492577 0.424972 -0.0122268 0.052104 0.424856 -0.0103576 0.0529986 0.424894 -0.00875004 0.0530942 0.424982 -0.0161759 0.0456756 0.425054 -0.0161791 0.045253 0.425261 -0.0158863 0.0457169 0.425446 -0.01585 0.0457442 0.424827 -0.0160203 0.0479585 0.424972 -0.0156837 0.047856 0.425091 -0.0160013 0.0456917 0.424856 -0.015858 0.0479091 0.424873 -0.0163286 0.046366 0.431973 0.03565 0.035735 0.431788 0.0357214 0.0358759 0.431959 0.0367116 0.0356774 0.432194 0.0367786 0.0354729 0.432209 0.0375336 0.0351221 0.4324 0.0373718 0.0350365 0.432529 0.0376382 0.0347138 0.432493 0.0380759 0.0343032 0.432892 0.0380371 0.0336301 0.432496 0.0333 0.033385 0.43233 0.0333568 0.0338987 0.432213 0.0334781 0.0342825 0.431966 0.0342185 0.0352487 0.431922 0.034903 0.0356132 0.437526 0.03805 0.000106899 0.432945 0.0382657 0.0326728 0.432964 0.03805 0.033385 0.433901 0.03805 0.0296362 0.434946 0.0382568 0.0238273 0.435617 0.03805 0.021293 0.436144 0.0382528 0.016632 0.436342 0.03805 0.0166595 0.436529 0.0382518 0.0135912 0.436836 0.038251 0.0105766 0.437227 0.0382501 0.00461732 0.433411 0.0331128 0.0294383 0.433068 0.0333 0.0314423 0.435055 0.0382565 -0.0240387 0.435647 0.0382544 -0.0206222 0.436492 0.03805 -0.0161848 0.436997 0.03805 -0.0116141 0.436812 0.0382511 -0.0114437 0.433604 0.0333 0.0294895 0.434467 0.03784 -0.027886 0.434697 0.03805 -0.026915 0.434501 0.0382587 -0.0268749 0.436516 0.0333 -0.0117866 0.436653 0.0333 0.000190231 0.436461 0.0331721 0.000493852 0.436158 0.0331678 0.00869425 0.436328 0.0333 0.00903419 0.433811 0.0333 0.0286417 0.43417 0.0331255 0.0259424 0.434659 0.0333 0.0243742 0.434683 0.0333 0.0242356 0.435095 0.0331397 0.0202649 0.436062 0.0333 0.0129617 0.433805 0.035662 -0.0294193 0.433808 0.035712 -0.0294193 0.433999 0.03565 -0.029265 0.434002 0.0357 -0.029265 0.43532 0.033116 -0.0216457 0.435231 0.0331112 -0.0221903 0.435427 0.0333 -0.0222242 0.435327 0.0333 -0.0227705 0.433785 0.0350166 -0.0293356 0.433826 0.0341837 -0.0289462 0.433979 0.0350986 -0.0291994 0.434067 0.0339877 -0.0285761 0.434249 0.0334489 -0.0277382 0.434449 0.0333 -0.026915 0.431288 0.02975 0.035735 0.431764 0.0314266 0.0350316 0.431576 0.03159 0.0351077 0.431558 0.0309261 0.0354195 0.43139 0.0303322 0.0356617 0.431864 0.0316119 0.0348188 0.431978 0.0317852 0.0345598 0.432421 0.0321 0.033385 0.431748 0.0271398 0.0333187 0.431426 0.0273243 0.0342654 0.431279 0.0296727 0.035735 0.433167 0.0323137 0.0301366 0.43268 0.0323158 0.0318399 0.433359 0.0321 0.0301898 0.43226 0.0271378 0.0318249 0.432358 0.0273227 0.0321587 0.433208 0.032315 0.0299857 0.432739 0.0271351 0.0302884 0.435903 0.0321 -0.0179982 0.435526 0.0323209 -0.0196044 0.435168 0.0323155 -0.0222104 0.435832 0.0321 0.0127427 0.435792 0.0323615 0.0102774 0.43606 0.0321 0.00876572 0.436343 0.0321 0.000395059 0.436419 0.0321 -0.00826212 0.436137 0.0323451 -0.0117397 0.436078 0.0323409 -0.0130535 0.436162 0.0321 -0.0149333 0.434222 0.0323262 0.0250707 0.435111 0.0321 0.0204293 0.433515 0.0321 0.0295759 0.435338 0.0271228 0.00388273 0.434643 0.0273227 -0.0248333 0.435461 0.0273227 -0.0182062 0.435261 0.0271275 -0.0181912 0.4354 0.0271267 -0.015951 0.435535 0.0271251 -0.0112624 0.435523 0.0271237 -0.00629959 0.435745 0.0273227 -0.00933873 0.435423 0.0271227 -0.000642697 0.435719 0.0273227 -0.00598687 0.435539 0.0273227 0.00381186 0.435315 0.027123 0.00501404 0.435152 0.0271245 0.0106695 0.435418 0.0273227 0.00877077 0.435105 0.0271248 0.0118 0.434991 0.0271253 0.0140603 0.43524 0.0273227 0.0131515 0.434756 0.0271263 0.0174469 0.434658 0.0271269 0.0185742 0.434759 0.0273227 0.0196048 0.434426 0.027128 0.0208255 0.43453 0.0273227 0.0216414 0.433974 0.02713 0.0241901 0.433375 0.0271332 0.0275317 0.435195 0.0321 -0.0232836 0.434213 0.0323099 -0.0268696 0.434408 0.0321 -0.026915 0.434777 0.0321 -0.0252856 0.434135 0.0271318 -0.0261364 0.434514 0.0273227 -0.0254405 0.433737 0.0315761 -0.0286579 0.434042 0.0317026 -0.0282226 0.433973 0.0321199 -0.0278362 0.433541 0.0307527 -0.0292141 0.433423 0.0297627 -0.0294127 0.433591 0.029121 -0.0291993 0.433701 0.0280103 -0.028576 0.433458 0.0281682 -0.0289119 0.433532 0.0277768 -0.0285545 0.433739 0.0278635 -0.0284147 0.43373 0.027281 -0.0277184 0.433948 0.0271325 -0.0268647 0.433908 0.0274798 -0.0277599 0.433418 0.0296854 -0.0294126 0.433611 0.0296727 -0.029265 0.43062 0.0237727 0.035735 0.43072 0.0243542 0.0356619 0.430939 0.0256182 0.0350916 0.430938 0.0250583 0.0353522 0.430896 0.024949 0.0354194 0.431359 0.0258082 0.0345595 0.431676 0.0263395 0.0333176 0.431245 0.0211595 0.0333114 0.430879 0.0213414 0.0342517 0.431217 0.0213996 0.0338867 0.430765 0.0220017 0.0350141 0.430672 0.0223077 0.0352815 0.430415 0.022707 0.0356495 0.430583 0.0230146 0.0356342 0.430612 0.0236954 0.035735 0.431864 0.0261227 0.033385 0.432631 0.0263356 0.0304896 0.432716 0.0213454 0.0298331 0.433619 0.0261227 0.0271399 0.434613 0.0261227 -0.0248208 0.435433 0.0261227 -0.0183207 0.435224 0.0263276 -0.0184284 0.435379 0.0261227 -0.0189758 0.435473 0.0263259 -0.013774 0.435736 0.0261227 -0.0098215 0.435363 0.0261227 0.0102429 0.43553 0.0261227 0.00426488 0.434402 0.0261227 0.0224422 0.434816 0.0263259 0.0165133 0.433679 0.0263305 0.0257626 0.434366 0.026328 0.0211525 0.434693 0.0211512 -0.0219832 0.434234 0.0211522 -0.024719 0.435301 0.0213454 -0.0183984 0.435114 0.0211501 -0.0182387 0.435417 0.0211485 -0.0129642 0.435347 0.0211454 0.00340393 0.43543 0.0211455 -0.00112156 0.435692 0.0213454 -0.00631855 0.435082 0.0211469 0.0113202 0.435261 0.0211459 0.00679753 0.435419 0.0213454 0.00807641 0.434952 0.0211477 0.0135797 0.435273 0.0213454 0.0114904 0.434584 0.0211493 0.0180908 0.434553 0.0213454 0.020181 0.434692 0.0211488 0.0169644 0.434713 0.0213454 0.0187807 0.434875 0.021148 0.0147086 0.433544 0.0213454 0.0263995 0.433651 0.0211524 0.0248145 0.433204 0.0211536 0.0270334 0.434416 0.0263305 -0.0247848 0.43416 0.0211523 -0.0250628 0.434075 0.0211524 -0.0254011 0.434479 0.0261227 -0.0254389 0.433872 0.021153 -0.0261404 0.434268 0.0213454 -0.0254532 0.433434 0.0250295 -0.0289006 0.433376 0.0256017 -0.0286481 0.433748 0.0258276 -0.0280551 0.433163 0.0247781 -0.0292061 0.433252 0.0240099 -0.029253 0.433215 0.0231411 -0.0291987 0.433232 0.0227812 -0.0290798 0.433357 0.0220329 -0.0285759 0.433171 0.0218841 -0.0286409 0.43327 0.0224528 -0.0289096 0.433394 0.0213419 -0.027817 0.433668 0.0211536 -0.0268595 0.433042 0.0237842 -0.0294063 0.433037 0.0237069 -0.0294062 0.433233 0.0237727 -0.029265 0.43006 0.0177181 0.035735 0.429886 0.0178097 0.0358503 0.430064 0.018823 0.0356424 0.430364 0.0190648 0.0353627 0.43065 0.0196147 0.0348726 0.431008 0.0200089 0.0341743 0.430625 0.0155459 0.0342816 0.430115 0.0158855 0.035062 0.430296 0.0160185 0.0350079 0.429902 0.0167166 0.0356394 0.431651 0.0203577 0.0321223 0.431936 0.0201454 0.0319327 0.431186 0.020359 0.0333106 0.431371 0.0201454 0.033385 0.432043 0.0151755 0.0303741 0.432397 0.0203556 0.0300626 0.432686 0.0201454 0.0297925 0.432481 0.0201454 0.0304425 0.432166 0.0151756 0.03003 0.43528 0.0201454 -0.0184243 0.435094 0.0203501 -0.0182558 0.435214 0.0201454 -0.0191243 0.434687 0.0203511 -0.0218598 0.434404 0.0201454 -0.0247557 0.434207 0.020352 -0.0247169 0.435416 0.0203483 -0.0126017 0.43549 0.0203466 -0.00680895 0.435673 0.0201454 -0.0100368 0.435477 0.0203474 -0.00971898 0.435054 0.020347 0.0117235 0.435395 0.0201454 0.00864807 0.435536 0.0201454 0.00390006 0.434628 0.0203489 0.0175009 0.435223 0.0201454 0.0122996 0.434828 0.0203481 0.0151922 0.434503 0.0201454 0.0204259 0.434233 0.0203503 0.0209545 0.434305 0.02035 0.0204008 0.433427 0.0201454 0.0267989 0.433252 0.0203532 0.0266658 0.434524 0.0151729 -0.0220447 0.434041 0.0151732 -0.0247776 0.435659 0.0153681 -0.00464901 0.435659 0.0153681 -0.00678219 0.435421 0.0151702 -0.009904 0.435621 0.0153681 -0.00990812 0.435243 0.0153681 -0.0175498 0.434964 0.0151724 -0.0184141 0.435143 0.0153681 -0.0186387 0.434874 0.0151726 -0.0192986 0.435353 0.0153681 0.0090912 0.435206 0.0151689 0.00786397 0.434599 0.0151714 0.0168947 0.434516 0.0153681 0.01942 0.43448 0.0151718 0.0180199 0.433681 0.0151735 0.0236204 0.433241 0.0153681 0.0267812 0.432997 0.0151746 0.0269457 0.432433 0.0151755 0.0291378 0.434132 0.0203521 -0.0250669 0.433952 0.0151731 -0.0251676 0.433827 0.0201454 -0.026915 0.434237 0.0201454 -0.0254644 0.434038 0.0153681 -0.025612 0.433844 0.0153681 -0.0262652 0.433649 0.0151733 -0.0262193 0.433454 0.0151736 -0.0268556 0.433428 0.0198313 -0.0280886 0.433147 0.0191862 -0.0288092 0.433059 0.019626 -0.0286386 0.433027 0.0187146 -0.0290777 0.432837 0.0188019 -0.0291989 0.432912 0.0177954 -0.029265 0.432719 0.0177268 -0.0294008 0.433134 0.0159213 -0.0284295 0.433087 0.0160555 -0.0285757 0.432903 0.0159006 -0.0286328 0.433156 0.0153608 -0.0278104 0.433353 0.0155327 -0.0277789 0.432723 0.0178041 -0.0294008 0.429692 0.0118181 0.035735 0.429513 0.0118263 0.0358457 0.429667 0.0128455 0.0356349 0.42976 0.0123935 0.0356635 0.429985 0.0136688 0.0350636 0.430391 0.014195 0.0342496 0.430415 0.0138543 0.0345584 0.430167 0.00978435 0.0346868 0.429829 0.00989889 0.0350546 0.429854 0.0104082 0.0353206 0.429573 0.0107275 0.0356328 0.429689 0.0117409 0.035735 0.432001 0.014375 0.0304049 0.43082 0.014377 0.0333054 0.430632 0.00919539 0.0333027 0.431704 0.00919448 0.030789 0.432187 0.0141681 0.0304761 0.432157 0.00939087 0.0301161 0.435126 0.0141681 -0.0186394 0.434517 0.0143727 -0.0219637 0.43413 0.0143728 -0.0242344 0.435613 0.0141681 -0.00988023 0.434935 0.0143723 -0.0185347 0.435451 0.0143686 -0.00357009 0.435452 0.0143693 -0.00702438 0.435413 0.0143701 -0.00987591 0.435322 0.0143709 -0.0128034 0.435447 0.0141681 0.0067359 0.435091 0.0143694 0.0102422 0.4352 0.0143689 0.00794193 0.435354 0.0143682 0.00306635 0.435554 0.0141681 0.00307092 0.435429 0.0143682 -0.00126733 0.434192 0.0141681 0.0216272 0.433995 0.0143726 0.0215971 0.434299 0.0143718 0.0194179 0.435032 0.0141681 0.0141752 0.435129 0.0141681 0.01288 0.434026 0.0141681 0.0226719 0.432984 0.0141681 0.0277362 0.434052 0.00939087 -0.0250823 0.435101 0.00939087 -0.017836 0.43491 0.00919461 -0.0177278 0.434795 0.00919465 -0.018891 0.435282 0.00919346 -0.0120829 0.435391 0.00919263 -0.00869025 0.435625 0.00939087 -0.00667035 0.435637 0.00939087 -0.00522717 0.435422 0.00919168 -0.000770236 0.435364 0.00919088 0.0025905 0.435165 0.00919171 0.00827979 0.435338 0.00939087 0.00881602 0.435052 0.00939087 0.0132274 0.43504 0.00919224 0.0105394 0.434025 0.00919504 0.0206694 0.434112 0.00939087 0.0214221 0.433147 0.00939087 0.0264604 0.431966 0.00919582 0.030056 0.433817 0.0143726 -0.02559 0.434212 0.0141681 -0.0248396 0.433432 0.0143732 -0.0268551 0.433623 0.0143729 -0.0262364 0.433629 0.0091932 -0.0259087 0.433329 0.00919344 -0.0268532 0.433519 0.00939087 -0.026915 0.432906 0.0131854 -0.0288263 0.433018 0.0135 -0.0285562 0.43312 0.0141865 -0.0278113 0.433434 0.014105 -0.0274559 0.432747 0.0124412 -0.0291809 0.432696 0.0118181 -0.029265 0.432921 0.0100781 -0.0285756 0.432555 0.0107463 -0.0291935 0.432802 0.0104947 -0.0289074 0.433213 0.00955246 -0.0277713 0.42934 0.00584331 0.0358436 0.429465 0.00686509 0.0356312 0.429734 0.00707545 0.0353846 0.429713 0.00701675 0.0354197 0.429567 0.00641134 0.0356647 0.42999 0.00761058 0.0349312 0.430193 0.00787719 0.034558 0.43034 0.00801321 0.0342814 0.430795 0.00819087 0.033385 0.430554 0.00321433 0.0333016 0.430117 0.00339318 0.0342365 0.430482 0.00346834 0.0338893 0.430064 0.00381261 0.034695 0.429726 0.00444537 0.0353305 0.429615 0.00482111 0.0355378 0.429437 0.00474257 0.0356301 0.429339 0.00576598 0.0358436 0.431032 0.00839444 0.0323577 0.430913 0.00321428 0.0325054 0.43111 0.00341359 0.0325551 0.431475 0.00341359 0.0317117 0.431839 0.00819087 0.0309534 0.431653 0.00839398 0.0308783 0.432109 0.00819087 0.0302034 0.43157 0.00321642 0.0309006 0.434973 0.00819087 -0.0189677 0.434027 0.00819087 -0.0251345 0.434345 0.00839447 -0.0222775 0.433948 0.00839393 -0.0245323 0.43522 0.00839347 -0.0131673 0.435019 0.00819087 -0.0185246 0.434994 0.00839406 -0.016593 0.435404 0.00839034 0.00056176 0.435435 0.00839159 -0.00516002 0.435425 0.0083918 -0.00630437 0.435583 0.00819087 -0.00877704 0.43555 0.00819087 -0.0099866 0.435387 0.00839235 -0.00859286 0.43535 0.00839279 -0.00998048 0.434847 0.00839269 0.0131736 0.435493 0.00819087 0.00510715 0.435328 0.00839098 0.00399407 0.435383 0.00839071 0.00170596 0.434718 0.00839313 0.014684 0.433903 0.00839444 0.0213686 0.432565 0.00839541 0.0279062 0.432899 0.00819087 0.0274058 0.433852 0.00341359 -0.0256059 0.433749 0.00321643 -0.0251324 0.434536 0.00321705 -0.0202022 0.434627 0.00321697 -0.0194255 0.434781 0.00321698 -0.0179525 0.434924 0.00341359 -0.0185342 0.43506 0.00321688 -0.0145696 0.435493 0.00341359 -0.0101682 0.435195 0.00321595 -0.0123107 0.435293 0.00321546 -0.0101604 0.435336 0.00321523 -0.00891928 0.435627 0.00341359 -0.00391387 0.435412 0.00321434 -0.00552578 0.435584 0.0034136 -0.00713905 0.435578 0.00341359 0.00199094 0.435392 0.00321374 0.00126265 0.435338 0.00321373 0.00352491 0.435301 0.00321389 0.00465576 0.435282 0.00341359 0.00926322 0.435358 0.00341359 0.00792059 0.434526 0.00321622 0.0159415 0.434936 0.00341359 0.0138431 0.434399 0.00321637 0.0170658 0.434113 0.00321711 0.0193106 0.433777 0.00321761 0.0215485 0.433891 0.00341359 0.0220794 0.433161 0.00321725 0.0248868 0.432717 0.00341359 0.0277037 0.431759 0.00341359 0.0309645 0.431747 0.00321661 0.0303632 0.433728 0.00839349 -0.0255265 0.433519 0.00321476 -0.026111 0.433403 0.00321398 -0.0264959 0.433319 0.00839308 -0.026853 0.433652 0.00819087 -0.0264741 0.433791 0.00819087 -0.0260313 0.433594 0.00341359 -0.0265574 0.433509 0.00819087 -0.026915 0.432785 0.00720964 -0.0288252 0.432999 0.00820712 -0.0278066 0.433317 0.00812913 -0.0274501 0.432664 0.00484211 -0.0290768 0.432679 0.00393742 -0.0286265 0.432859 0.00410081 -0.0285756 0.432477 0.00476468 -0.0291916 0.432731 0.00451245 -0.0289042 0.432966 0.00340037 -0.0278065 0.432408 0.00576503 -0.0293953 0.432595 0.00576359 -0.029265 0.429489 -7.35627e-05 0.0357342 0.429311 -0.000136407 0.0358433 0.429491 -1.07373e-05 0.0357317 0.429313 -4.19898e-08 0.0358397 0.430734 -0.00256368 0.033385 0.430277 -0.00238571 0.0342821 0.429892 -0.00191668 0.0350044 0.429311 -0.000213683 0.0358433 0.429489 -0.000213678 0.035735 0.429442 0.000975304 0.0355891 0.429721 0.00120208 0.0353166 0.429735 0.00175402 0.0350077 0.429665 0.00104067 0.035419 0.430131 0.00189998 0.0345579 0.430125 0.00224556 0.0342101 0.430734 0.00221359 0.033385 0.430895 -0.0027642 0.0325417 0.431091 -0.00256368 0.0325941 0.431256 -0.00276417 0.0317122 0.431074 0.00221359 0.0326298 0.43144 -0.00256368 0.0317907 0.4314 -0.00276542 0.0313559 0.431591 -0.00256368 0.0314178 0.431727 -0.00256368 0.0310397 0.431699 0.00221359 0.0311053 0.431561 0.00221359 0.0314867 0.431224 0.00241398 0.0317843 0.434153 -0.00276647 -0.022888 0.434813 -0.00256368 -0.0194979 0.434941 -0.00276621 -0.0160792 0.435288 -0.00276543 -0.0101872 0.435487 -0.00256368 -0.0101951 0.435267 -0.00256368 0.00945674 0.434901 -0.00276535 0.0118316 0.434075 -0.00256368 0.0208901 0.433696 -0.00276703 0.0219877 0.433825 0.00221359 -0.025689 0.434776 0.00221359 -0.0197665 0.434613 0.00241712 -0.0194329 0.43558 0.00221359 0.00188334 0.435283 0.00241551 -0.0102235 0.435483 0.00221359 -0.0102315 0.435279 0.00241554 -0.0103072 0.434801 0.00221359 -0.0195419 0.435371 0.00241362 0.00227388 0.434839 0.00241563 0.0125543 0.4348 0.0022136 0.0151432 0.434746 0.00241587 0.0136296 0.433895 0.00221359 0.0219596 0.433747 0.00241733 0.0216384 0.432324 0.00241767 0.0283515 0.433428 0.0022136 0.0245025 0.432664 0.00221359 0.0278506 0.43151 0.00241688 0.0310409 0.433629 0.00241586 -0.0256458 0.43351 0.00241485 -0.0261288 0.433387 -0.00276399 -0.0265448 0.433337 -0.00276398 -0.0266987 0.433286 -0.00276399 -0.0268524 0.433476 0.00221359 -0.026915 0.433373 0.00241384 -0.0265853 0.432468 -0.0012138 -0.0291914 0.432916 -0.00202095 -0.0284171 0.432725 -0.00146729 -0.0289027 0.432655 -0.00113526 -0.0290767 0.432756 0.00123548 -0.028823 0.432994 0.00182205 -0.0282138 0.432691 0.00173684 -0.0285778 0.433042 0.00189917 -0.0280893 0.432706 0.00104007 -0.0289493 0.432483 0.000957076 -0.0291494 0.432671 0.000871248 -0.029038 0.43258 -1.07376e-05 -0.0292616 0.432392 -0.000213687 -0.029395 0.432579 -7.35614e-05 -0.0292641 0.432392 -6.82007e-05 -0.0293941 0.429346 -0.00619366 0.0358437 0.429522 -0.00611368 0.035735 0.429523 -0.00619095 0.035735 0.429552 -0.00554866 0.0356661 0.42944 -0.00509473 0.035631 0.429696 -0.00489155 0.0353922 0.430138 -0.00407728 0.0345579 0.430264 -0.00395615 0.0343165 0.430671 -0.00376743 0.0335178 0.430738 -0.00376368 0.033385 0.430547 -0.00848469 0.0338962 0.430123 -0.00813663 0.0347029 0.430348 -0.00836284 0.0342825 0.429956 -0.00789251 0.0350059 0.42965 -0.00713332 0.0355378 0.430866 -0.0035645 0.0326142 0.431342 -0.00854095 0.0321609 0.431676 -0.00874428 0.0308383 0.431783 -0.00376368 0.0309091 0.43139 -0.00356495 0.0313982 0.431316 -0.00356442 0.0315783 0.431861 -0.00854095 0.0309133 0.434188 -0.00356697 -0.0227436 0.433787 -0.00356675 -0.0249714 0.435483 -0.00376368 -0.0105008 0.435289 -0.00356569 -0.0103524 0.435363 -0.0035652 -0.00809073 0.43524 -0.00356592 -0.0114829 0.435449 -0.00376368 -0.0112854 0.434917 -0.00376368 -0.0186622 0.434638 -0.00356724 -0.0193791 0.434808 -0.00376368 -0.019653 0.434505 -0.00356732 -0.0205027 0.435585 -0.00376368 0.00165142 0.435398 -0.00356387 0.00096019 0.435375 -0.00356374 0.00209141 0.435312 -0.00356394 0.00435345 0.43484 -0.00376368 0.0148944 0.43478 -0.00356596 0.0133885 0.435106 -0.00356471 0.00887454 0.434439 -0.00356648 0.0167657 0.433942 -0.00376368 0.021808 0.433445 -0.00356751 0.0234803 0.432741 -0.00356743 0.0268009 0.433498 -0.00376368 0.0242629 0.432718 -0.00376368 0.0277211 0.433842 -0.00874423 -0.0250692 0.433977 -0.00874409 -0.024416 0.434734 -0.00874467 -0.0193779 0.434983 -0.00854095 -0.0189409 0.434958 -0.00874434 -0.0170992 0.435198 -0.00874361 -0.0136732 0.435554 -0.00854095 -0.00996976 0.435256 -0.00874352 -0.0125299 0.435565 -0.00854095 0.00255898 0.435173 -0.00874176 0.00807201 0.435338 -0.00854095 0.00877648 0.434105 -0.00854095 0.0214127 0.434332 -0.00874405 0.0183386 0.43443 -0.00854095 0.0191482 0.4347 -0.00874331 0.014924 0.433143 -0.00854095 0.0264309 0.433453 -0.00874528 0.0239942 0.43213 -0.00854095 0.0301642 0.433417 -0.00356414 -0.0264566 0.433607 -0.00376368 -0.026518 0.433575 -0.00356528 -0.0259142 0.433669 -0.00356609 -0.0255247 0.43374 -0.00874368 -0.025501 0.433478 -0.00376368 -0.026915 0.433353 -0.00356415 -0.0266546 0.433804 -0.00854095 -0.0260031 0.433323 -0.00874332 -0.0268531 0.432967 -0.00374983 -0.0278047 0.433285 -0.00382452 -0.0274462 0.432765 -0.00474002 -0.0288217 0.432715 -0.00493722 -0.0289493 0.432479 -0.00511312 -0.0291908 0.432496 -0.00719299 -0.0291919 0.432955 -0.00800262 -0.0284118 0.433003 -0.0085566 -0.0278086 0.432411 -0.00619259 -0.0293954 0.43241 -0.00611528 -0.0293954 0.432599 -0.00619095 -0.029265 0.429705 -0.012091 0.035735 0.430041 -0.0103485 0.0349619 0.429587 -0.0110801 0.0356339 0.42983 -0.0108793 0.0353986 0.430348 -0.00994629 0.0343457 0.430823 -0.00974095 0.033385 0.430769 -0.0144597 0.0339061 0.430352 -0.01411 0.0347087 0.430578 -0.0143399 0.0342831 0.430004 -0.0140196 0.0350634 0.42953 -0.0121767 0.0358459 0.431197 -0.00954526 0.0320333 0.431911 -0.00974095 0.0308266 0.430925 -0.0095455 0.0326634 0.431378 -0.00974095 0.0321183 0.431553 -0.0147261 0.0315868 0.432206 -0.0145182 0.0304615 0.431726 -0.00954478 0.0307522 0.432178 -0.00974095 0.0300805 0.435562 -0.00974095 -0.0099691 0.435233 -0.00954401 -0.0132273 0.435097 -0.00954469 -0.0154863 0.435062 -0.00974095 -0.0183126 0.434915 -0.00954471 -0.017742 0.435003 -0.00974095 -0.0188932 0.435564 -0.00974095 0.00261748 0.435596 -0.00974095 -0.00858016 0.435394 -0.00954272 -0.00870429 0.435286 -0.00954356 -0.012097 0.435336 -0.00954108 0.0037408 0.434119 -0.00974095 0.0214236 0.435167 -0.00954179 0.00826379 0.433823 -0.00974095 0.0231906 0.434218 -0.0147229 -0.0238116 0.434806 -0.0147226 -0.0198229 0.435134 -0.0145182 -0.0186248 0.434935 -0.0147224 -0.0186052 0.435232 -0.0145182 -0.0175712 0.435617 -0.0145182 -0.00987172 0.435658 -0.0145182 -0.00463565 0.435425 -0.0147201 -0.00946487 0.435221 -0.0147189 0.00746626 0.434986 -0.0147199 0.0120683 0.435045 -0.0145182 0.0140634 0.434821 -0.0147205 0.0143662 0.433686 -0.0147235 0.0235242 0.433231 -0.0145182 0.0267592 0.432415 -0.0147253 0.0291408 0.433766 -0.00954395 -0.0254456 0.434062 -0.00974095 -0.0250607 0.43383 -0.0147228 -0.0255746 0.434222 -0.0145182 -0.0248297 0.433334 -0.00954369 -0.0268533 0.433524 -0.00974095 -0.026915 0.433642 -0.00954342 -0.0258824 0.433442 -0.0147235 -0.0268553 0.433336 -0.00980137 -0.0274444 0.432935 -0.0104067 -0.0285538 0.433104 -0.0100553 -0.0280892 0.432795 -0.0109146 -0.0289494 0.432517 -0.0121734 -0.0293972 0.432888 -0.0134347 -0.0288945 0.43275 -0.0127402 -0.0291943 0.433092 -0.0139915 -0.0283976 0.432839 -0.0139979 -0.0286324 0.433351 -0.0143778 -0.0277153 0.430094 -0.0181455 0.035735 0.429907 -0.0180828 0.0358506 0.430108 -0.0171355 0.035542 0.429927 -0.0170695 0.0356408 0.430157 -0.0168642 0.0354032 0.430609 -0.0159311 0.0343624 0.43096 -0.0157283 0.0336024 0.431061 -0.0157182 0.033385 0.431397 -0.0204955 0.033385 0.431157 -0.0204341 0.0339186 0.430808 -0.0205254 0.0342614 0.430598 -0.0198361 0.0350174 0.430416 -0.0199953 0.0350763 0.430275 -0.0190793 0.0355415 0.430094 -0.0191741 0.0356424 0.431957 -0.0204955 0.0319389 0.432183 -0.0155259 0.0300206 0.432248 -0.0157182 0.0304331 0.432699 -0.0204955 0.0298094 0.432496 -0.0204955 0.030455 0.432507 -0.0207054 0.0297557 0.434541 -0.015523 -0.0219832 0.434162 -0.0155234 -0.0242149 0.435624 -0.0157182 -0.00990241 0.435218 -0.015522 -0.0152291 0.435191 -0.0157182 -0.0182131 0.435358 -0.0155182 0.00287025 0.435435 -0.0155184 -0.00165524 0.435647 -0.0157182 -0.00849263 0.435448 -0.0155199 -0.00844427 0.434947 -0.0155203 0.0127858 0.435065 -0.0157182 0.0139282 0.434501 -0.0155219 0.0178879 0.434189 -0.0157182 0.0218265 0.434068 -0.0157182 0.0225949 0.432972 -0.0157182 0.0279453 0.434219 -0.0207022 -0.0247175 0.434415 -0.0204955 -0.0247561 0.434918 -0.0207006 -0.0201027 0.435278 -0.0206958 0.00618781 0.43509 -0.0207002 -0.0183955 0.43568 -0.0204955 -0.00970905 0.43569 -0.0204955 -0.00633539 0.435687 -0.0204955 -0.00575832 0.435361 -0.0206955 0.00271158 0.435156 -0.0206965 0.0096629 0.435419 -0.0204955 0.00803993 0.435043 -0.0206971 0.0119784 0.434976 -0.0206974 0.0131355 0.434813 -0.0206983 0.015448 0.434709 -0.0204955 0.018736 0.433539 -0.0204955 0.0263413 0.432659 -0.020705 0.0291965 0.434247 -0.0157182 -0.0248101 0.434144 -0.0207023 -0.0250648 0.433464 -0.0155239 -0.0268557 0.433856 -0.0157182 -0.0262583 0.433661 -0.0155235 -0.0262124 0.434251 -0.0204955 -0.0254591 0.434049 -0.0204955 -0.0261886 0.433841 -0.0204955 -0.026915 0.433655 -0.0157182 -0.026915 0.433168 -0.0157104 -0.0278091 0.433223 -0.0161016 -0.0282013 0.432928 -0.0173906 -0.0291652 0.432739 -0.0181544 -0.0294011 0.432854 -0.0191503 -0.0292 0.433587 -0.0203654 -0.0276862 0.433336 -0.019983 -0.0283799 0.433265 -0.0198231 -0.0285606 0.432984 -0.0187203 -0.0291936 0.433649 -0.0207035 -0.0268592 0.432736 -0.0180771 -0.029401 0.432925 -0.0180682 -0.029265 0.430657 -0.0241228 0.035735 0.430465 -0.0240648 0.0358578 0.43045 -0.0230598 0.035651 0.430613 -0.0222263 0.035077 0.43097 -0.0220093 0.0345582 0.430908 -0.0216921 0.0342529 0.431052 -0.0219053 0.0343556 0.431362 -0.0217061 0.0336083 0.431161 -0.0258061 0.0350248 0.430665 -0.0251481 0.0356532 0.430849 -0.0250496 0.0355446 0.430976 -0.0259686 0.0350919 0.432004 -0.0216955 0.0319556 0.431458 -0.0216955 0.033385 0.432238 -0.0266877 0.0317829 0.432729 -0.0216955 0.0298531 0.432531 -0.0216955 0.0304887 0.43275 -0.0264728 0.0308605 0.432645 -0.0266858 0.0305243 0.435118 -0.0216955 -0.020305 0.435455 -0.0214958 -0.00272582 0.435331 -0.0214956 0.00411664 0.43539 -0.0216955 0.00890309 0.435235 -0.0216955 0.0122632 0.434574 -0.0216955 0.0200693 0.434376 -0.0215003 0.0200455 0.433542 -0.0215029 0.0254631 0.434275 -0.0216955 0.02232 0.43483 -0.0266789 -0.0222508 0.435449 -0.0264728 -0.0182219 0.435249 -0.0266776 -0.0182067 0.435178 -0.0266731 0.00991738 0.435286 -0.0264728 0.0121306 0.434575 -0.0266772 0.0193318 0.434345 -0.0266783 0.0214002 0.433994 -0.0266799 0.0239578 0.434562 -0.0264728 0.0212725 0.433239 -0.0264728 0.0289754 0.434173 -0.0215025 -0.0250619 0.434282 -0.0216955 -0.0254493 0.434429 -0.0266807 -0.0247915 0.434369 -0.0266809 -0.0250954 0.434625 -0.0264728 -0.0248274 0.4343 -0.0266811 -0.0253929 0.434082 -0.0216955 -0.0261836 0.434089 -0.0215026 -0.0253974 0.434114 -0.0266818 -0.0261363 0.434494 -0.0264728 -0.0254408 0.433875 -0.0216955 -0.026915 0.43338 -0.022366 -0.0285587 0.433411 -0.0216914 -0.0278157 0.43328 -0.0228696 -0.0289496 0.433058 -0.0240571 -0.0294065 0.433396 -0.0259506 -0.0286497 0.433661 -0.0259731 -0.0283637 0.433588 -0.0257968 -0.0285642 0.433184 -0.0251264 -0.0292073 0.433316 -0.0246992 -0.0291932 0.433657 -0.0264926 -0.0278299 0.433895 -0.0263509 -0.0276619 0.433063 -0.0241344 -0.0294066 0.433249 -0.0240455 -0.029265 0.431142 -0.0301218 0.0358668 0.431133 -0.0300445 0.0358667 0.431304 -0.0288123 0.0353993 0.431545 -0.0279866 0.0345583 0.431893 -0.0276812 0.0335842 0.431951 -0.032042 0.0347084 0.432258 -0.0323831 0.0339421 0.432263 -0.032668 0.0333263 0.431941 -0.0324795 0.0342898 0.43143 -0.0306803 0.0356623 0.431968 -0.0276728 0.033385 0.433022 -0.0326645 0.030749 0.432454 -0.03245 0.033385 0.43297 -0.03245 0.0316563 0.432945 -0.0276728 0.0303762 0.432676 -0.0274861 0.0306057 0.432594 -0.0274868 0.0308763 0.433546 -0.03245 0.0295823 0.433436 -0.03267 0.0291861 0.435271 -0.0274779 -0.0181766 0.435475 -0.0276728 -0.0181265 0.435748 -0.0276728 -0.00929794 0.435511 -0.0274735 -0.00534163 0.435149 -0.0274746 0.0108085 0.435289 -0.0276728 0.012203 0.43519 -0.0274744 0.00967771 0.435258 -0.0274737 0.00741562 0.435442 -0.0274729 -0.00163492 0.435744 -0.0276728 -0.00827422 0.435486 -0.0274732 -0.0038976 0.434542 -0.0274776 0.0198393 0.434839 -0.027476 0.0164576 0.435228 -0.0276728 0.0134479 0.434132 -0.0274795 0.0232092 0.434421 -0.0276728 0.0225721 0.433382 -0.0276728 0.028541 0.435776 -0.0326759 -0.0177559 0.436357 -0.03245 -0.0128769 0.435362 -0.03245 -0.0224346 0.436086 -0.0326875 -0.014111 0.436508 -0.03245 -0.00126114 0.436085 -0.03245 0.0105069 0.43583 -0.0327114 0.0115446 0.434759 -0.032684 0.0220489 0.435226 -0.03245 0.0200682 0.434596 -0.03245 0.0243518 0.43363 -0.03245 0.0292305 0.434658 -0.0276728 -0.0248316 0.434531 -0.0276728 -0.0254335 0.434159 -0.0276728 -0.026915 0.433966 -0.0274826 -0.026865 0.434626 -0.0326584 -0.0251099 0.435206 -0.03245 -0.023309 0.433863 -0.0275148 -0.027266 0.433815 -0.028049 -0.0281904 0.433841 -0.0279873 -0.0280894 0.434012 -0.0277337 -0.0274466 0.433644 -0.0288472 -0.0289498 0.433495 -0.0284135 -0.0288305 0.433425 -0.0291968 -0.0292706 0.433616 -0.0293019 -0.0291517 0.433634 -0.0300228 -0.029265 0.434022 -0.0319591 -0.0283525 0.433952 -0.0317709 -0.0285675 0.433564 -0.0311007 -0.0292153 0.43384 -0.0313907 -0.0288788 0.434232 -0.032333 -0.0276473 0.433992 -0.0324691 -0.0278387 0.434426 -0.03245 -0.026915 0.433441 -0.0300355 -0.029413 0.434017 -0.0372489 -0.0289056 0.434667 -0.0380461 -0.0270509 0.434298 -0.0380805 -0.0278126 0.434501 -0.0382588 -0.0268749 0.434697 -0.03805 -0.026915 0.435695 -0.03805 -0.0215663 0.437038 -0.03805 -0.0111608 0.436839 -0.0382511 -0.0111431 0.437457 -0.03805 -0.00437589 0.433494 -0.0382631 0.0304805 0.434935 -0.03805 0.0249133 0.434935 -0.0382569 0.0238862 0.436344 -0.03805 0.0166472 0.43637 -0.0382523 0.0149145 0.436893 -0.03805 0.012077 0.436996 -0.03805 0.0110225 0.437527 -0.03805 -0.000264971 0.432275 -0.0376915 0.034947 0.432585 -0.0377327 0.0345643 0.432265 -0.0370102 0.0353359 0.432038 -0.0368296 0.0355837 0.440727 -0.0561709 -0.0273761 0.441027 -0.0564848 -0.0133092 0.441027 -0.0582019 0.0260199 0.441027 -0.0589332 0.0427692 0.440727 -0.0551866 -0.0323242 0.441027 -0.0514219 -0.0378536 0.441027 -0.0515763 -0.0376884 0.441027 -0.0445006 -0.0421814 0.441027 -0.0509242 0.060251 0.441027 -0.0585105 0.0503644 0.440727 -0.0588003 0.050442 0.441027 -0.0396045 -0.042935 0.441027 0.0297871 0.0624324 0.441027 0.042783 0.0624324 0.441027 -0.0427831 0.0624324 0.441027 -0.0297872 0.0624324 0.441027 -0.00942504 0.0624324 0.441027 -0.00507504 0.0624324 0.441027 0.0445005 -0.0421814 0.440727 0.0491155 -0.0402361 0.441027 0.0489435 -0.0399904 0.441027 0.0525219 -0.0365648 0.440727 0.0551866 -0.0323242 0.441027 0.0549046 -0.0322216 0.440727 0.0589456 0.0498569 0.441027 0.0586532 0.0497899 0.441027 0.0571146 0.0538778 0.441027 0.0545447 0.0574096 0.440727 0.0547614 0.0576171 0.441027 0.0471114 0.0618466 0.440727 0.042783 0.0627325 0.440727 0.0593495 0.045427 0.440727 0.0561708 -0.0273761 0.434708 0.0558023 -0.0282714 0.435165 0.0561708 -0.0273761 0.434838 0.0559684 -0.0293342 0.434316 0.0554097 -0.0305194 0.434448 0.0554409 -0.0315694 0.434055 0.054603 -0.0337245 0.433973 0.0543886 -0.0341625 0.433467 0.05276 -0.0367473 0.432647 0.0491155 -0.0402361 0.43217 0.0480457 -0.0405244 0.432135 0.0464709 -0.0417465 0.431777 0.0460269 -0.0415584 0.431781 0.0445906 -0.0424675 0.431456 0.0428377 -0.0429167 0.430892 0.0396044 -0.043235 0.425734 -4.10421e-08 -0.043235 0.425538 0.00582955 -0.0427653 0.425767 0.00499494 -0.043235 0.426003 0.0105173 -0.043235 0.425858 0.0119133 -0.0427693 0.426168 0.0125937 -0.043235 0.427108 0.019912 -0.043235 0.428112 0.0267978 -0.0428029 0.428746 0.0285568 -0.043235 0.429658 0.0344252 -0.0428302 0.429815 0.0337759 -0.043235 0.43051 0.0374015 -0.043235 0.430432 0.0386035 -0.0428448 0.430608 0.0396511 -0.0428482 0.4376 0.057235 -0.00300247 0.437446 0.0570449 -0.00735514 0.436969 0.0567603 -0.0138738 0.435994 0.0564046 -0.0220205 0.435341 0.0560012 -0.0243655 0.430608 -0.0396512 -0.0428482 0.430892 -0.0396045 -0.043235 0.428213 -0.025932 -0.043235 0.428396 -0.0268421 -0.043235 0.428293 -0.0263342 -0.043235 0.42639 -0.0168243 -0.0427764 0.426777 -0.0177591 -0.043235 0.42649 -0.0156051 -0.043235 0.425797 -0.0111405 -0.0427685 0.425906 -0.0089495 -0.043235 0.425658 -0.0089628 -0.0427668 0.425777 -0.00545243 -0.043235 0.433794 0.0585058 0.0328944 0.431401 0.0590561 0.0453834 0.431561 0.059019 0.0445509 0.432227 0.0592294 0.0426778 0.4344 0.0583586 0.0295271 0.434696 0.0586569 0.0295659 0.43649 0.0581396 0.0177169 0.437456 0.0576541 0.00659667 0.437286 0.0572005 0.00307729 0.43077 -0.0406109 -0.0428228 0.431177 -0.0428638 -0.0425365 0.434869 -0.0558726 -0.0273139 0.43476 -0.0558313 -0.0279621 0.433507 -0.0529092 -0.0365499 0.433637 -0.0540146 -0.0341842 0.43397 -0.0543808 -0.034178 0.433801 -0.0544358 -0.0333233 0.434312 -0.0551867 -0.0323242 0.43462 -0.0557113 -0.0305947 0.432482 -0.0495798 -0.0394719 0.432873 -0.0513485 -0.0378819 0.433055 -0.051061 -0.038641 0.433427 -0.0526107 -0.0369391 0.432048 -0.0460103 -0.0419477 0.432602 -0.0488895 -0.0403917 0.431046 -0.0405299 -0.0432091 0.431227 -0.0415686 -0.0431182 0.431638 -0.0438216 -0.0426898 0.426749 0.0442681 0.0626658 0.427523 0.0472978 0.0618314 0.427779 0.047186 0.0621372 0.428114 0.0484024 0.0617513 0.428384 0.049519 0.0613027 0.428773 0.0513786 0.0603307 0.428994 0.0525329 0.0595633 0.429126 0.0532319 0.0590262 0.429197 0.0536024 0.0587165 0.42943 0.0547615 0.057617 0.429534 0.0552383 0.0570972 0.429287 0.0552578 0.0566187 0.429608 0.0555605 0.0567194 0.429958 0.0568998 0.05485 0.430392 0.0581102 0.0524784 0.430917 0.059 0.0496113 0.431539 0.0593648 0.0462641 0.431148 0.0590613 0.0467117 0.437567 -0.0571758 -0.00435971 0.437327 -0.0570543 -0.00026497 0.437207 -0.0568025 -0.00602277 0.437023 -0.0566529 -0.00944712 0.436118 -0.0564432 -0.0211386 0.435165 -0.0561709 -0.0273761 0.426002 0.0433041 0.0624487 0.426086 0.042783 0.0627325 0.43509 -0.0585568 0.0272714 0.434691 -0.0582852 0.0278462 0.435119 -0.0581718 0.0252541 0.435631 -0.0580248 0.0218952 0.43723 -0.0578133 0.0102419 0.437112 -0.0573916 0.00743724 0.425294 0.0404734 0.0627325 0.42515 0.039263 0.0627325 0.425612 0.0424595 0.0624491 0.425321 0.0417172 0.0624466 0.427097 -0.0459784 0.0621517 0.426306 -0.0439711 0.0624161 0.428315 -0.0492203 0.061432 0.427766 -0.0471448 0.0621485 0.427724 -0.0480034 0.06161 0.427407 -0.0460169 0.0624141 0.42843 -0.0510386 0.0602125 0.428741 -0.0512174 0.0604272 0.42943 -0.0547616 0.057617 0.428942 -0.0536567 0.0582835 0.42922 -0.0537179 0.0586162 0.42887 -0.0518802 0.0600143 0.430026 -0.0571184 0.054485 0.429669 -0.05582 0.0563977 0.429556 -0.0553367 0.0569844 0.430578 -0.0584924 0.0514595 0.430402 -0.0581318 0.0524261 0.430191 -0.0580489 0.0518078 0.431413 -0.0593466 0.0469387 0.43124 -0.059072 0.0462285 0.43099 -0.0590789 0.0492191 0.430872 -0.0589458 0.0498566 0.425127 0.0380608 0.0627325 0.424977 -0.0380607 0.0625824 0.425815 -0.0429101 0.0624503 0.426226 -0.0430834 0.0627297 0.425885 -0.043058 0.06245 0.426273 -0.0431834 0.0627276 0.425296 -0.0404858 0.0627325 0.425602 -0.0416119 0.0627325 0.425102 0.0239174 0.0572574 0.424827 0.0242375 0.0579531 0.425102 0.025 0.0578824 0.424827 0.025 0.0581574 0.425102 0.025625 0.057715 0.424827 0.0257625 0.0579531 0.425102 0.0260825 0.0572574 0.424827 0.0263206 0.0573949 0.433327 0.0239174 0.0572574 0.425102 0.024375 0.057715 0.433327 0.025 0.0578824 0.433327 0.024375 0.057715 0.434078 0.025 0.0566324 0.433327 0.0260825 0.0572574 0.433327 0.025625 0.057715 0.425102 -0.025 0.0578824 0.424827 -0.025 0.0581574 0.424827 -0.0236794 0.0573949 0.433327 -0.02625 0.0566324 0.425102 -0.02625 0.0566324 0.433327 -0.0260826 0.0572574 0.433327 -0.025625 0.057715 0.425102 -0.0260826 0.0572574 0.425102 -0.025625 0.057715 0.433327 -0.024375 0.057715 0.425102 -0.024375 0.057715 0.433327 -0.0239175 0.0572574 0.425102 -0.0239175 0.0572574 0.425102 -0.02375 0.0566324 0.433327 -0.025 0.0578824 0.425939 0.0433339 0.0606727 0.425955 0.0432056 0.0624482 0.425002 0.0405449 0.0624411 0.424827 0.0382921 0.0601973 0.424829 0.0385954 0.062433 0.42485 0.0392797 0.0624352 0.424827 0.0379091 0.0587141 0.424827 0.0368365 0.0572651 0.424868 0.0330053 0.0524655 0.424827 0.0322264 0.0537942 0.424951 0.0163636 0.045671 0.425721 0.0161246 0.0431459 0.425307 0.0163133 0.0441852 0.426669 0.0275562 0.0445668 0.425848 0.0270683 0.0458643 0.425856 0.0230969 0.0445116 0.425819 0.0309188 0.0475527 0.426613 0.0318706 0.0464914 0.426535 0.0348211 0.0481681 0.425557 0.0399395 0.0543587 0.426178 0.0405859 0.0531849 0.425503 0.0407482 0.055563 0.425815 0.04291 0.0624503 0.425451 0.0422182 0.0609208 0.425947 0.042555 0.0566913 0.425036 0.0408752 0.0608475 0.425422 0.0420669 0.0592019 0.424999 0.0405299 0.0624411 0.424854 0.0395263 0.0607739 0.425027 0.0407663 0.0593871 0.424853 0.0394592 0.0595732 0.424854 0.0390857 0.0582796 0.425037 0.0402994 0.0576876 0.424859 0.0378266 0.0563377 0.425075 0.0388954 0.0553366 0.424863 0.0363184 0.0548394 0.425144 0.0338407 0.0510403 0.424871 0.0295062 0.0505845 0.424872 0.0258748 0.0490381 0.425175 0.0226206 0.0461132 0.424872 0.022127 0.0477731 0.424985 0.0163657 0.0454587 0.425448 0.0414989 0.0571024 0.426048 0.0417529 0.0549426 0.425105 0.0372928 0.0536338 0.425646 0.0382394 0.0524627 0.425759 0.034648 0.0496631 0.425164 0.0302253 0.0490411 0.425173 0.0264824 0.0474225 0.426352 -0.0385068 0.050947 0.425646 -0.0382419 0.052465 0.425759 -0.034664 0.0496733 0.425036 -0.0408754 0.0608432 0.424951 -0.0163637 0.045671 0.424985 -0.0163658 0.0454587 0.424827 -0.029611 0.0523956 0.424827 -0.0322409 0.0538026 0.424827 -0.0342073 0.0550572 0.424854 -0.0390815 0.0582694 0.424853 -0.0394581 0.0595641 0.424827 -0.0382843 0.0607028 0.424827 -0.0382613 0.0610162 0.425644 -0.0425343 0.0624494 0.425027 -0.0407646 0.0593752 0.425037 -0.0402943 0.0576746 0.425902 -0.042998 0.05818 0.426079 -0.0415008 0.05451 0.425075 -0.0388826 0.0553204 0.426478 -0.0362581 0.0491349 0.425819 -0.0309146 0.0475506 0.426636 -0.0306196 0.0458767 0.426682 -0.022616 0.0429256 0.426674 -0.0268039 0.0442817 0.425848 -0.027039 0.0458529 0.425025 -0.016368 0.0452473 0.425856 -0.0230693 0.0445033 0.426059 -0.0159191 0.0424635 0.425038 -0.0407171 0.062442 0.424858 -0.039405 0.0624357 0.424854 -0.0395267 0.0607701 0.425056 -0.0396274 0.0563714 0.425105 -0.0372953 0.0536358 0.425173 -0.0264539 0.0474114 0.425175 -0.0225938 0.046105 0.424859 -0.0378148 0.0563236 0.424863 -0.0363208 0.0548411 0.425144 -0.0338562 0.0510499 0.425164 -0.0302213 0.049039 0.424868 -0.0330203 0.0524743 0.424871 -0.0295024 0.0505824 0.424872 -0.0258473 0.0490274 0.424872 -0.022101 0.0477651 0.424827 -0.0235289 0.0499128 0.424827 -0.0033148 0.059589 0.424827 -0.0263207 0.0573949 0.424827 -0.0380608 0.0624324 0.424827 -0.0242375 0.0579531 0.424827 -0.0257625 0.0579531 0.424827 0.0280741 0.0516782 0.424827 0.0301436 0.0526607 0.424827 0.026525 0.0566324 0.424827 -0.026525 0.0566324 0.424827 -0.0368954 0.0573283 0.424827 -0.037992 0.0588817 0.424827 -0.0381382 0.0592471 0.424827 0.0380607 0.0624324 0.424827 0.0360729 0.0565225 0.424827 0.0347978 0.0554832 0.424827 -0.00147525 0.0618957 0.424827 0.0236793 0.0573949 0.424827 0.00147516 0.0618957 0.424827 -0.0123956 0.0524128 0.424827 -0.0242375 0.0553118 0.424827 0.0236793 0.0558699 0.424827 0.0242375 0.0553118 0.424827 0.0160202 0.0479586 0.424827 0.0216097 0.049306 0.424827 -0.0033148 0.0580759 0.424827 0.00331471 0.0580759 0.424827 0.00265819 0.0609523 0.424827 0.023475 0.0566324 0.424827 0.00874996 0.0533442 0.424827 -4.19898e-08 0.0554324 0.424827 -0.00875004 0.0533442 0.424827 -0.023475 0.0566324 0.424827 -0.0103943 0.0531642 0.432685 0.0378729 0.0342798 0.432223 0.0368758 0.0354197 0.438727 0.036875 0.0354202 0.432586 0.037735 0.0345602 0.438727 0.0377351 0.03456 0.431978 0.0357 0.035735 0.438727 0.0339883 0.0350467 0.43211 0.0336666 0.0346456 0.438727 0.0334788 0.0342843 0.438727 0.0333 0.033385 0.431601 0.0310465 0.035345 0.438727 0.0317851 0.03456 0.432165 0.0319901 0.0340953 0.431234 0.0289502 0.0356212 0.431296 0.0282586 0.035262 0.431479 0.0276924 0.0346503 0.431613 0.0274914 0.0342594 0.431746 0.0273779 0.0338913 0.431936 0.0273227 0.033385 0.438727 0.0261227 0.033385 0.431558 0.026003 0.0341255 0.438727 0.0258078 0.03456 0.43122 0.0256169 0.0348416 0.430812 0.0246988 0.0355448 0.438727 0.0249477 0.0354202 0.438727 0.0220337 0.0350467 0.430899 0.0217218 0.0346606 0.431064 0.0215119 0.0342538 0.438727 0.0215243 0.0342843 0.438727 0.0198306 0.03456 0.430816 0.0198312 0.0345589 0.430066 0.0177954 0.035735 0.430154 0.0183747 0.0356625 0.438727 0.0189704 0.0354202 0.430246 0.0187285 0.0355418 0.430328 0.0189717 0.0354194 0.430052 0.0170881 0.035649 0.430083 0.0167831 0.035541 0.430172 0.0163601 0.0353029 0.438727 0.0168188 0.0355561 0.438727 0.0160564 0.0350467 0.430445 0.0157532 0.0346741 0.438727 0.015547 0.0342843 0.430809 0.015422 0.0338852 0.431043 0.0153681 0.033385 0.431003 0.0141681 0.033385 0.430586 0.0140101 0.0342324 0.430225 0.0136099 0.0349055 0.438727 0.0118181 0.035735 0.429846 0.0127566 0.0355395 0.429923 0.0129943 0.0354195 0.429951 0.0130688 0.0353746 0.429701 0.0111583 0.0356617 0.438727 0.0108416 0.0355561 0.429752 0.0108005 0.0355387 0.430009 0.010038 0.0350045 0.438727 0.0100792 0.0350467 0.43037 0.00956868 0.0342817 0.430567 0.00944502 0.0338866 0.430814 0.00939087 0.033385 0.438727 0.00701587 0.0354202 0.429518 0.00584087 0.035735 0.438727 0.00584087 0.035735 0.429643 0.0067818 0.0355384 0.429517 0.00576359 0.035735 0.429547 0.00521202 0.0356694 0.438727 0.00486429 0.0355561 0.438727 0.00410189 0.0350467 0.4299 0.00406025 0.035004 0.43028 0.00359151 0.034282 0.430341 0.00208314 0.0341571 0.438727 0.00189875 0.03456 0.429985 0.00171524 0.0348321 0.429489 -0.000136406 0.035735 0.429546 0.000549676 0.0356326 0.42962 0.00088803 0.0355 0.429525 -0.00075701 0.0356714 0.429599 -0.00115634 0.0355377 0.429713 -0.00152837 0.0353329 0.430057 -0.00216304 0.0346975 0.438727 -0.0023848 0.0342843 0.430479 -0.00250862 0.0338907 0.429618 -0.0051729 0.0355385 0.438727 -0.00493868 0.0354202 0.429932 -0.00435926 0.0349485 0.429566 -0.00671977 0.0356748 0.438727 -0.00709026 0.0355561 0.429769 -0.00749975 0.0353368 0.430734 -0.00974793 0.0335659 0.438727 -0.00991983 0.0342843 0.438727 -0.0104293 0.0350467 0.429766 -0.0111526 0.0355396 0.438727 -0.0111916 0.0355561 0.429714 -0.0115309 0.0356673 0.438727 -0.012091 0.035735 0.429709 -0.0121682 0.035735 0.429767 -0.0126864 0.0356772 0.429865 -0.0131077 0.0355391 0.438727 -0.0130675 0.0355561 0.429992 -0.0134758 0.0353376 0.430184 -0.0138654 0.0350105 0.438727 -0.0138299 0.0350467 0.438727 -0.0143393 0.0342843 0.438727 -0.0145182 0.033385 0.43102 -0.0145182 0.033385 0.430337 -0.0163308 0.0349674 0.438727 -0.0160331 0.03456 0.430519 -0.0160319 0.034558 0.430088 -0.0180682 0.035735 0.430074 -0.0175157 0.0356692 0.438727 -0.0181455 0.035735 0.430171 -0.0186694 0.0356759 0.438727 -0.0190448 0.0355561 0.438727 -0.0198072 0.0350467 0.430413 -0.0194608 0.0353325 0.430765 -0.0200851 0.0347118 0.438727 -0.0203166 0.0342843 0.430983 -0.0203169 0.0342837 0.438727 -0.0220103 0.03456 0.430817 -0.0223013 0.0349599 0.430669 -0.022842 0.0354035 0.438727 -0.0228705 0.0354202 0.430617 -0.0235006 0.035671 0.430749 -0.0246696 0.0356705 0.438727 -0.0241228 0.035735 0.430993 -0.025453 0.0353223 0.431321 -0.0260626 0.0347115 0.431675 -0.0264084 0.0339314 0.438727 -0.0276728 0.033385 0.431624 -0.0278702 0.0343278 0.438727 -0.0279876 0.03456 0.431423 -0.028262 0.0349414 0.438727 -0.0288478 0.0354202 0.438727 -0.0300228 0.035735 0.431277 -0.0294831 0.0356722 0.43166 -0.0314486 0.0353096 0.438727 -0.0309993 0.0355561 0.431803 -0.031777 0.0350313 0.438727 -0.0317617 0.0350467 0.438727 -0.0322712 0.0342843 0.438727 -0.03585 0.0357302 0.432019 -0.0359861 0.0357176 0.438727 -0.0369606 0.0353683 0.432369 -0.0372968 0.0351093 0.438727 -0.03365 0.033385 0.432109 -0.0337879 0.034178 0.43193 -0.0341939 0.0348885 0.431875 -0.0344447 0.0351467 0.431832 -0.0348033 0.0354075 0.438727 -0.0344457 0.0351476 0.438727 -0.0353086 0.035631 0.431998 -0.03585 0.0357302 0.431999 -0.0362946 0.0357165 0.431896 -0.0362604 0.0357206 0.432093 -0.0372018 0.0354045 0.433989 -0.0363533 -0.0292383 0.434014 -0.03585 -0.0292602 0.433844 -0.0353405 -0.0291705 0.438727 -0.0353405 -0.0291705 0.438727 -0.0344625 -0.0286921 0.433918 -0.0343681 -0.028606 0.434195 -0.0336743 -0.0272515 0.434403 -0.0377124 -0.0281286 0.434293 -0.0374127 -0.0285241 0.438727 -0.0369486 -0.0289058 0.434166 -0.0369175 -0.028925 0.438727 -0.0322712 -0.0278143 0.438727 -0.0317617 -0.0285767 0.433701 -0.0306766 -0.0291931 0.438727 -0.0300228 -0.029265 0.433675 -0.0286033 -0.0287878 0.438727 -0.0279876 -0.02809 0.434119 -0.0264728 -0.026915 0.438727 -0.0262939 -0.0278143 0.433463 -0.0254081 -0.0288823 0.433254 -0.0241228 -0.029265 0.43324 -0.0233436 -0.0291577 0.438727 -0.0240455 -0.029265 0.438727 -0.0228705 -0.0289501 0.433484 -0.0220746 -0.0281949 0.433317 -0.0226379 -0.0287967 0.433515 -0.0220099 -0.0280893 0.433711 -0.0217558 -0.027444 0.438727 -0.0216955 -0.026915 0.438727 -0.0203166 -0.0278143 0.438727 -0.0190448 -0.0290861 0.43313 -0.0194222 -0.0288879 0.432928 -0.0181455 -0.029265 0.432984 -0.0168921 -0.0289495 0.438727 -0.0168932 -0.0289501 0.433106 -0.0163858 -0.0285557 0.433027 -0.0166747 -0.0288072 0.43326 -0.0160326 -0.0280892 0.433477 -0.0157784 -0.0274434 0.438727 -0.0143393 -0.0278143 0.432807 -0.0130884 -0.0290773 0.432721 -0.0114367 -0.029172 0.432841 -0.0107098 -0.0288163 0.433061 -0.0101286 -0.0282079 0.438727 -0.010916 -0.0289501 0.438727 -0.00836207 -0.0278143 0.433213 -0.00839127 -0.0277403 0.438727 -0.00785265 -0.0285767 0.432758 -0.0074486 -0.0289001 0.432684 -0.00711244 -0.0290768 0.432632 -0.00675968 -0.0291951 0.438727 -0.00619095 -0.029265 0.432628 -0.00547473 -0.0291764 0.432869 -0.00442908 -0.0285535 0.432999 -0.00415435 -0.0282125 0.433046 -0.00407809 -0.0280892 0.438727 -0.00407852 -0.02809 0.433476 -0.00256368 -0.026915 0.43317 -0.00241002 -0.0277508 0.438727 -0.00187538 -0.0285767 0.432607 -0.000779801 -0.0291958 0.438727 -0.00111298 -0.0290861 0.432579 -0.000213678 -0.029265 0.432614 0.000498576 -0.0291776 0.432579 -0.000136406 -0.029265 0.438727 0.00103859 -0.0289501 0.438727 0.00189875 -0.02809 0.433283 0.00215256 -0.0274471 0.438727 0.00359248 -0.0278143 0.433169 0.00356987 -0.0277576 0.432918 0.00395949 -0.0284209 0.438727 0.00486429 -0.0290861 0.432619 0.00519826 -0.029196 0.432596 0.00584087 -0.029265 0.432636 0.00646924 -0.0291794 0.438727 0.00584087 -0.029265 0.432734 0.00701737 -0.0289493 0.433027 0.00779731 -0.0282168 0.432894 0.00752476 -0.0285542 0.433076 0.00787641 -0.0280893 0.438727 0.00787603 -0.02809 0.438727 0.00956975 -0.0278143 0.432975 0.00994218 -0.0284273 0.438727 0.0100792 -0.0285767 0.438727 0.0108416 -0.0290861 0.432743 0.0108205 -0.0290772 0.432705 0.0111783 -0.0291966 0.432694 0.0117409 -0.029265 0.438727 0.0118181 -0.029265 0.438727 0.0129931 -0.0289501 0.432853 0.0129946 -0.0289493 0.43315 0.0137721 -0.0282206 0.433201 0.0138536 -0.0280894 0.433623 0.0141681 -0.026915 0.438727 0.015547 -0.0278143 0.433645 0.0153681 -0.026915 0.438727 0.0160564 -0.0285767 0.438727 0.0168188 -0.0290861 0.432982 0.0164755 -0.0289096 0.432934 0.0168003 -0.0290783 0.432907 0.0171597 -0.0291977 0.432909 0.0177181 -0.029265 0.432944 0.0181875 -0.029232 0.433086 0.0189725 -0.0289489 0.438727 0.0189704 -0.0289501 0.433496 0.0199291 -0.0278997 0.43386 0.0213454 -0.026915 0.433593 0.0215084 -0.0277748 0.4334 0.0218948 -0.028425 0.433228 0.0236954 -0.029265 0.438727 0.0237727 -0.029265 0.433413 0.0249484 -0.0289497 0.433354 0.0246886 -0.0290792 0.433568 0.0254479 -0.0285631 0.434142 0.0273227 -0.026915 0.438727 0.0275016 -0.0278143 0.438727 0.028011 -0.0285767 0.43363 0.0284263 -0.0289072 0.438727 0.0287734 -0.0290861 0.433689 0.0304002 -0.0291732 0.433931 0.0314219 -0.0285663 0.433842 0.031134 -0.0288142 0.438727 0.030925 -0.0289501 0.43379 0.0309259 -0.0289496 0.438727 0.0317851 -0.02809 0.43426 0.0320321 -0.0274755 0.434083 0.0317852 -0.0280898 0.438727 0.0334788 -0.0278143 0.434102 0.0338295 -0.0284011 0.434009 0.0343968 -0.0289029 0.438727 0.0357 -0.029265 0.434029 0.0360172 -0.0292435 0.438727 0.036875 -0.0289501 0.434158 0.0368762 -0.0289494 0.434211 0.0371135 -0.0287923 0.434414 0.0377354 -0.0280894 0.433518 0.0331167 0.0290196 0.433321 0.0323193 0.0295309 0.433617 0.0331207 0.0285982 0.432662 0.0271359 0.0305698 0.43271 0.0263349 0.0302029 0.432563 0.0267365 0.0308041 0.432524 0.0211555 0.0297797 0.432429 0.021156 0.0300989 0.432327 0.0211564 0.0304072 0.432126 0.0143752 0.0300569 0.432022 0.0147752 0.0303887 0.432238 0.0143753 0.0297052 0.432276 0.0151757 0.0296813 0.431844 0.00919517 0.0304207 0.431795 0.00839475 0.0305079 0.431919 0.00839547 0.0301428 0.43126 0.00281274 0.0317031 0.431291 0.00321422 0.0316335 0.43137 0.00241544 0.0314256 0.431433 0.00321531 0.0312803 0.431462 -0.00356549 0.0312145 0.431538 -0.00276667 0.0309755 0.431287 -0.00316358 0.0316418 0.431701 -0.00914442 0.0307943 0.431865 -0.00954543 0.0303849 0.431817 -0.00874501 0.0304688 0.432061 -0.0155258 0.0303628 0.432143 -0.0147254 0.0300442 0.432273 -0.0151257 0.0296826 0.432443 -0.0215062 0.0301168 0.432342 -0.0215067 0.0304231 0.432325 -0.0211065 0.0304051 0.432308 -0.0207063 0.0303888 0.432537 -0.0215058 0.0297998 0.432411 -0.0207059 0.0300776 0.43256 -0.0266865 0.0307994 0.432577 -0.0270867 0.0308375 0.43339 -0.032668 0.0293833 0.433531 -0.0329206 0.0288828 0.435 0.0323107 -0.0232405 0.435027 0.0327262 -0.0231935 0.434926 0.0323071 -0.0236193 0.434302 0.0267311 -0.0253932 0.434319 0.0271311 -0.025393 0.434446 0.0271308 -0.0247977 0.434355 0.0263308 -0.0250905 0.434388 0.027131 -0.0250952 0.43406 0.0207523 -0.025406 0.433846 0.0151729 -0.0255559 0.433832 0.0147727 -0.0255725 0.434016 0.014373 -0.0247988 0.433925 0.0143728 -0.0251947 0.433615 0.008793 -0.0259397 0.433754 0.00919375 -0.0254694 0.433831 0.00839406 -0.0250925 0.433657 0.00321587 -0.0255628 0.433522 -0.0027649 -0.0260936 0.433613 -0.00874311 -0.0259437 0.433867 -0.00954444 -0.0250189 0.433845 -0.015123 -0.0255579 0.433859 -0.0155232 -0.0255422 0.433963 -0.0155233 -0.0251569 0.433937 -0.014723 -0.0251823 0.434027 -0.0147231 -0.024789 0.434058 -0.0207024 -0.0254067 0.434073 -0.0211025 -0.0254017 0.434246 -0.0215024 -0.0247208 0.434317 -0.0270813 -0.0253933 0.434336 -0.0274813 -0.0253863 0.434404 -0.0274812 -0.0250894 0.435011 -0.0326605 -0.0232657 0.435165 -0.0326651 -0.0224032 0.435304 -0.03365 -0.0219133 0.435444 -0.0334147 -0.0209941 0.435381 -0.03365 -0.0214791 0.435065 0.0323144 -0.0228598 0.435674 0.0323243 -0.0182977 0.435855 0.0331265 -0.0175726 0.435802 0.0323281 -0.0169889 0.435911 0.0323322 -0.0156784 0.436304 0.0331435 -0.0120925 0.43624 0.0323598 -0.00647966 0.436495 0.0331604 -0.0064336 0.43611 0.0323701 0.00222312 0.433734 0.0331217 0.0280685 0.435641 0.0323565 0.0127298 0.436049 0.0331646 0.0104993 0.435506 0.0323523 0.0145625 0.435453 0.0331479 0.0173497 0.434974 0.0323387 0.0199319 0.434518 0.0263301 -0.0242111 0.435065 0.0271288 -0.0203903 0.434864 0.0263285 -0.0219059 0.435004 0.0263281 -0.0207489 0.435308 0.0263271 -0.0172661 0.43538 0.0271226 0.00162002 0.435445 0.0271228 -0.00177404 0.435358 0.0263227 0.00286068 0.435537 0.0263245 -0.00911266 0.435431 0.0263262 -0.0149386 0.435525 0.0263251 -0.0112852 0.435229 0.0271239 0.00840764 0.43519 0.0263229 0.00953188 0.435261 0.0271236 0.00727653 0.435342 0.0263227 0.0036554 0.435357 0.0271227 0.00286039 0.435146 0.0263232 0.0106964 0.435039 0.0263241 0.0130245 0.434974 0.0263247 0.014188 0.434921 0.0271255 0.0151897 0.434722 0.0263264 0.0176748 0.434498 0.0263274 0.0199947 0.434219 0.0263287 0.0223085 0.43429 0.0271286 0.0219489 0.433877 0.0263301 0.0246141 0.433793 0.027131 0.025307 0.432877 0.0271347 0.0297398 0.434316 0.0203517 -0.0241479 0.434872 0.0211508 -0.0206112 0.435022 0.0211504 -0.0192357 0.435197 0.0203496 -0.0169614 0.435469 0.0203476 -0.0102849 0.435485 0.0211475 -0.00968806 0.435489 0.0203469 -0.00796762 0.435495 0.0211468 -0.00728471 0.435475 0.020346 -0.00449164 0.435322 0.0211455 0.00453521 0.435315 0.0203455 0.00477658 0.43525 0.0203459 0.00709301 0.435224 0.0211461 0.00792849 0.435165 0.0203464 0.00940881 0.435113 0.0203467 0.0105663 0.435135 0.0211466 0.0101899 0.434913 0.0203477 0.0140366 0.434332 0.0211503 0.02034 0.43451 0.0203493 0.0186536 0.434185 0.0211508 0.021462 0.433846 0.0211518 0.0236998 0.434072 0.0203508 0.022102 0.432672 0.0211551 0.0292336 0.432494 0.0203552 0.0297386 0.434713 0.0151728 -0.0206734 0.434676 0.0143726 -0.0208232 0.435322 0.0151712 -0.0130835 0.435424 0.01437 -0.0093271 0.435455 0.0151695 -0.00735443 0.435457 0.0143688 -0.0047215 0.435249 0.0151686 0.00673326 0.435428 0.0151682 -0.00118532 0.435348 0.0151682 0.00334011 0.435319 0.0151683 0.00447128 0.43504 0.0151697 0.0112545 0.435102 0.0151694 0.0101247 0.434952 0.0143699 0.0125409 0.43487 0.0143702 0.0136894 0.434892 0.0151704 0.0135127 0.434804 0.0151707 0.0146409 0.434675 0.014371 0.0159842 0.434562 0.0143713 0.01713 0.434204 0.0151727 0.0202663 0.434146 0.0143722 0.0205592 0.434045 0.0151729 0.0213866 0.433796 0.0143731 0.0228355 0.433473 0.0151739 0.0247326 0.433595 0.0143734 0.0239693 0.433136 0.0143741 0.0262263 0.432875 0.0143744 0.0273477 0.433856 0.00919426 -0.0250404 0.434369 0.00919464 -0.0222212 0.435093 0.0091946 -0.0154721 0.435437 0.00919166 -0.00529611 0.435359 0.00919292 -0.00995768 0.435326 0.00887301 -0.0108589 0.435437 0.00839086 -0.00287123 0.435431 0.0083904 -0.00172687 0.435366 0.00839088 0.00251882 0.435085 0.00839203 0.00971102 0.435292 0.00839112 0.00513789 0.434794 0.00919325 0.0139249 0.434461 0.00919397 0.0173031 0.434189 0.00839404 0.019405 0.433459 0.00919528 0.0240165 0.433852 0.00919515 0.0217876 0.433236 0.00919545 0.0251259 0.43347 0.00839511 0.023866 0.432731 0.00919565 0.0273321 0.432133 0.00919583 0.0295153 0.434673 0.00919479 -0.0199785 0.434654 0.00839452 -0.0200094 0.43471 0.00844524 -0.0195423 0.434782 0.00839458 -0.0188721 0.435081 0.00839375 -0.0154519 0.435274 0.00839337 -0.0120242 0.435357 0.00839271 -0.00973686 0.434391 0.00321695 -0.0213244 0.43525 0.00321565 -0.0111806 0.434978 0.00321713 -0.0156981 0.435368 0.00321497 -0.00778829 0.43543 0.00321398 -0.00326293 0.435411 0.0032139 0.00013135 0.435429 0.003214 -0.00213149 0.434749 0.00321589 0.0136895 0.434846 0.00321558 0.0125623 0.434897 0.00313973 0.0119272 0.435015 0.00321489 0.0103056 0.435087 0.00321465 0.00917644 0.435208 0.00321421 0.00691677 0.433587 0.00321752 0.0226641 0.432922 0.00321729 0.0259927 0.432795 0.00316722 0.026543 0.432383 0.00321699 0.0281908 0.433925 0.00316827 0.0205975 0.435404 0.00304766 0.000571617 0.434514 0.00271101 -0.0203101 0.435238 0.00288145 -0.0113681 0.43538 0.00241356 0.00187899 0.434526 -0.00304432 -0.0202594 0.434614 -0.0027669 -0.0194754 0.435385 -0.00276458 -0.0069505 0.435243 -0.00323338 -0.0113306 0.435379 -0.00276365 0.00193211 0.435264 -0.00276409 0.00561545 0.434528 -0.00276637 0.0158706 0.434305 -0.00356675 0.0178892 0.434002 -0.00356755 0.0201318 0.433149 -0.00276762 0.0249037 0.432811 -0.00340278 0.0264938 0.433831 -0.00356775 0.0212503 0.433229 -0.00356743 0.0245909 0.431734 -0.00356681 0.0304201 0.431594 -0.00356655 0.0308454 0.433947 -0.00342685 0.020483 0.434676 -0.00356619 0.0145152 0.435223 -0.00356426 0.00661463 0.434907 -0.00351915 0.0118373 0.43496 -0.00356525 0.0111327 0.435389 -0.00356488 -0.00695959 0.435422 -0.00356425 -0.0046969 0.435429 -0.0035641 -0.00356548 0.435425 -0.00356411 -0.00130256 0.435404 -0.00341793 0.000618441 0.434864 -0.00356737 -0.0171274 0.43496 -0.00356742 -0.016 0.435118 -0.00356681 -0.0137425 0.433641 -0.00276585 -0.0256095 0.434599 -0.00874463 -0.0205147 0.433982 -0.00954475 -0.0244649 0.43505 -0.00874399 -0.0159581 0.434784 -0.00874468 -0.0189198 0.435433 -0.00874177 -0.00566376 0.43544 -0.00954155 -0.00304716 0.435421 -0.00874199 -0.00680849 0.435378 -0.00874259 -0.00909767 0.435345 -0.00874297 -0.010242 0.435439 -0.00874117 -0.00337419 0.435426 -0.00874029 -0.00108466 0.435433 -0.00954173 -0.00191569 0.435393 -0.00874063 0.0012172 0.435365 -0.00874097 0.00255439 0.435407 -0.00954155 0.000347126 0.435364 -0.00954097 0.00260968 0.434026 -0.00874437 0.0206077 0.434327 -0.00954453 0.0184853 0.434466 -0.00874394 0.0172017 0.434832 -0.00954323 0.0135094 0.434801 -0.00874295 0.0137837 0.434974 -0.00874246 0.0115006 0.435048 -0.00874225 0.0103582 0.431987 -0.00954606 0.0300206 0.43194 -0.00874571 0.0301039 0.432109 -0.00874567 0.029557 0.432526 -0.00954594 0.0281605 0.432716 -0.00874559 0.0273486 0.432991 -0.00954573 0.0262834 0.433621 -0.00954532 0.0231849 0.433228 -0.00874538 0.0251166 0.433851 -0.00874469 0.0217391 0.434036 -0.00954514 0.0206418 0.435366 -0.00954298 -0.00983542 0.43543 -0.00954208 -0.00644158 0.435438 -0.00954175 -0.00531013 0.434373 -0.00954478 -0.0222354 0.434678 -0.0095449 -0.0199928 0.434804 -0.00954476 -0.0188723 0.43472 -0.00879336 -0.0195106 0.435331 -0.00923279 -0.0108444 0.434051 -0.0155234 -0.0247696 0.434833 -0.0155228 -0.0197387 0.435332 -0.0155213 -0.0129688 0.434952 -0.0155225 -0.0186133 0.435143 -0.0155222 -0.0163582 0.435431 -0.0155202 -0.00957567 0.435424 -0.0155203 -0.00989839 0.435373 -0.0155209 -0.0118381 0.435184 -0.0147215 -0.0155381 0.435404 -0.0152099 -0.0106618 0.43539 -0.0147206 -0.0109716 0.435417 -0.0147202 -0.00986751 0.435462 -0.015519 -0.00504971 0.433988 -0.0147228 0.0216921 0.435447 -0.0155185 -0.0027867 0.435431 -0.0147183 -0.00143496 0.435386 -0.0147182 0.00149699 0.435386 -0.0155182 0.0014976 0.435353 -0.0147182 0.00310324 0.435226 -0.0155188 0.00739453 0.434866 -0.0155206 0.0139131 0.434441 -0.0147217 0.0182926 0.433992 -0.0155232 0.0217963 0.433341 -0.0155243 0.0254404 0.433847 -0.0155234 0.022707 0.433243 -0.0147242 0.0257855 0.43286 -0.0155251 0.0275658 0.432991 -0.0147245 0.0269095 0.432292 -0.0155259 0.0296731 0.432255 -0.0147255 0.0296939 0.435462 -0.0155193 -0.00618123 0.435121 -0.0215002 -0.0182556 0.434326 -0.0207019 -0.0241574 0.435281 -0.0206993 -0.0157817 0.435457 -0.020698 -0.0111968 0.435266 -0.0214997 -0.0163001 0.435464 -0.021498 -0.011351 0.435481 -0.0206975 -0.0097068 0.435489 -0.0214975 -0.00966917 0.435491 -0.0206966 -0.00656031 0.435309 -0.0206957 0.00502915 0.435162 -0.0214965 0.00962511 0.435202 -0.0206963 0.00850474 0.433083 -0.0215042 0.0276398 0.433205 -0.0207035 0.026943 0.434061 -0.020701 0.0222453 0.434327 -0.0207001 0.0202949 0.434732 -0.0214987 0.0165721 0.434609 -0.0206991 0.0177573 0.434831 -0.0214983 0.0153656 0.43489 -0.0274802 -0.0219997 0.434558 -0.027481 -0.0242388 0.434461 -0.0274812 -0.0247962 0.435547 -0.0274742 -0.00929816 0.435514 -0.0266736 -0.00580063 0.435539 -0.0266744 -0.00853008 0.435541 -0.0266746 -0.00937405 0.435512 -0.0274753 -0.0129528 0.435346 -0.0274773 -0.017068 0.43549 -0.0266758 -0.01336 0.43527 -0.0266775 -0.0179276 0.434783 -0.0266762 0.0170097 0.43505 -0.0266742 0.0128793 0.435249 -0.0266728 0.00769215 0.435048 -0.0274751 0.0130694 0.434452 -0.0266778 0.0204909 0.434751 -0.0274765 0.0175858 0.434987 -0.0274754 0.0141993 0.432723 -0.0266851 0.0302399 0.432752 -0.0274854 0.0303267 0.432866 -0.0266843 0.029675 0.433365 -0.0274835 0.0276696 0.43338 -0.0266816 0.0274006 0.433583 -0.0274824 0.0265593 0.433604 -0.0266809 0.0262566 0.433966 -0.0274802 0.0243285 0.434162 -0.0266791 0.0228044 0.434419 -0.0274782 0.0209642 0.433581 -0.0326706 0.0285421 0.433855 -0.0326724 0.0272508 0.434344 -0.0326774 0.0246561 0.43456 -0.0326806 0.0233539 0.434941 -0.0326876 0.0207415 0.435259 -0.032695 0.0181206 0.435312 -0.03365 0.019445 0.435397 -0.0326986 0.0168078 0.435964 -0.03365 0.013625 0.43642 -0.03365 0.00706575 0.435985 -0.0327163 0.0089091 0.436203 -0.032722 0.00363322 0.436356 -0.0327147 -0.00480793 0.436348 -0.0327097 -0.00692761 0.436521 -0.03365 -0.0101863 0.436185 -0.0326931 -0.0124358 0.438727 0.03565 -0.029265 0.438727 0.0347507 -0.0290861 0.438727 0.0357 0.035735 0.438727 0.03565 0.035735 0.438727 0.0347507 0.0355561 0.438727 0.0377351 -0.02809 0.438727 0.0339883 -0.0285767 0.438727 0.03805 0.033385 0.437384 0.03805 -0.00612686 0.438727 0.03805 -0.026915 0.435382 0.03805 -0.0233591 0.437122 0.03805 0.00958544 0.437527 0.03805 -0.000264971 0.434907 0.0333 -0.0248387 0.435517 0.0333 -0.0216761 0.435938 0.0333 0.0144315 0.435353 0.0333 0.0198092 0.433712 0.0333 0.0290666 0.436699 0.0333 -0.00454137 0.438727 0.0333 -0.026915 0.438727 0.030925 0.0354202 0.438727 0.02975 0.035735 0.438727 0.0296727 -0.029265 0.438727 0.0275016 0.0342843 0.438727 0.028011 0.0350467 0.438727 0.0287734 0.0355561 0.438727 0.0273227 0.033385 0.433589 0.0273227 0.0274826 0.432932 0.0273227 0.0303382 0.43277 0.0273227 0.030903 0.438727 0.0273227 -0.026915 0.43554 0.0273227 -0.017042 0.43572 0.0273227 -0.00608852 0.433616 0.02975 -0.029265 0.438727 0.02975 -0.029265 0.43344 0.0321 0.0298877 0.438727 0.0321 0.033385 0.432903 0.0321 0.0317911 0.438727 0.0321 -0.026915 0.435262 0.0321 -0.0228918 0.435122 0.0321 -0.0236594 0.438727 0.0296727 0.035735 0.438727 0.0215243 -0.0278143 0.438727 0.0236954 -0.029265 0.438727 0.0227961 -0.0290861 0.438727 0.0237727 0.035735 0.438727 0.0258078 -0.02809 0.438727 0.0249477 -0.0289501 0.438727 0.0227961 0.0355561 0.438727 0.0236954 0.035735 0.438727 0.0220337 -0.0285767 0.438727 0.0261227 -0.026915 0.434067 0.0213454 -0.0261857 0.43443 0.0213454 -0.0247575 0.432516 0.0213454 0.0304732 0.431983 0.0213454 0.0319479 0.431431 0.0213454 0.033385 0.438727 0.0213454 0.033385 0.435402 0.0213454 -0.0171323 0.435685 0.0213454 -0.00969015 0.438727 0.0213454 -0.026915 0.435689 0.0213454 -0.00578068 0.435533 0.0213454 0.00404857 0.434101 0.0261227 -0.026915 0.432306 0.0261227 0.032122 0.432736 0.0261227 0.0308281 0.432903 0.0261227 0.0302533 0.435284 0.0261227 0.0121203 0.438727 0.0177954 0.035735 0.438727 0.0198306 -0.02809 0.438727 0.0201454 -0.026915 0.438727 0.0177181 -0.029265 0.438727 0.0153681 -0.026915 0.438727 0.0201454 0.033385 0.434236 0.0153681 -0.0248182 0.432467 0.0153681 0.029738 0.43223 0.0153681 0.0304447 0.431653 0.0153681 0.0319217 0.438727 0.0153681 0.033385 0.434201 0.0153681 0.0216921 0.435553 0.0153681 0.00310334 0.43505 0.0153681 0.0140717 0.438727 0.0177954 -0.029265 0.434035 0.0201454 -0.0261913 0.434243 0.0201454 0.0223113 0.438727 0.0177181 0.035735 0.438727 0.00939087 -0.026915 0.438727 0.0129931 0.0354202 0.438727 0.0138533 0.03456 0.438727 0.0141681 0.033385 0.438727 0.0117409 0.035735 0.438727 0.0138533 -0.02809 0.438727 0.00956975 0.0342843 0.433671 0.00939087 -0.0264425 0.43382 0.00939087 -0.025968 0.431889 0.00939087 0.0308636 0.431362 0.00939087 0.0321365 0.434435 0.00939087 0.0191749 0.438727 0.00939087 0.033385 0.434994 0.00939087 -0.018912 0.435558 0.00939087 -0.00996356 0.435564 0.00939087 0.00259509 0.438727 0.0117409 -0.029265 0.434009 0.0141681 -0.0256466 0.433818 0.0141681 -0.0262825 0.431612 0.0141681 0.0319373 0.432429 0.0141681 0.0297624 0.435187 0.0141681 -0.017996 0.438727 0.0141681 -0.026915 0.435641 0.0141681 -0.00823179 0.438727 0.00787603 0.03456 0.438727 0.00819087 0.033385 0.438727 0.00701587 -0.0289501 0.438727 0.00410189 -0.0285767 0.438727 0.00576359 -0.029265 0.438727 0.00341359 -0.026915 0.438727 0.00576359 0.035735 0.438727 0.00359248 0.0342843 0.433477 0.00341359 -0.026915 0.434826 0.00341359 -0.0194479 0.438727 0.00341359 0.033385 0.430736 0.00341359 0.033385 0.434111 0.00341359 0.0207087 0.431327 0.00819087 0.0321807 0.433768 0.00819087 0.0233571 0.4341 0.00819087 0.0213995 0.435003 0.00819087 0.0137141 0.435566 0.00819087 0.0025234 0.438727 0.00819087 -0.026915 0.438727 -0.0023848 -0.0278143 0.438727 0.00103859 0.0354202 0.438727 -0.000136406 0.035735 0.438727 -0.000213678 0.035735 0.438727 -0.00187538 0.0350467 0.438727 -0.00111298 0.0355561 0.438727 -0.000136406 -0.029265 0.438727 -0.000213678 -0.029265 0.433837 -0.00256368 -0.0256527 0.433577 -0.00256368 -0.0266065 0.432668 -0.00256368 0.0278619 0.438727 -0.00256368 0.033385 0.43494 -0.00256368 0.0137391 0.438727 -0.00256368 -0.026915 0.434911 -0.00256368 -0.0185919 0.435579 -0.00256368 -0.00723539 0.435627 -0.00256368 -0.00363682 0.435361 -0.00256368 0.00784125 0.433563 0.00221359 -0.0266471 0.438727 0.00221359 -0.026915 0.431408 0.00221359 0.0318631 0.438727 0.00221359 0.033385 0.435362 0.00221359 0.00777705 0.435556 0.00221359 0.00286241 0.43545 0.00221359 -0.0109924 0.438727 -0.00407852 0.03456 0.438727 -0.00611368 0.035735 0.438727 -0.00619095 0.035735 0.438727 -0.00493868 -0.0289501 0.438727 -0.00611368 -0.029265 0.438727 -0.00709026 -0.0290861 0.438727 -0.00785265 0.0350467 0.438727 -0.00854095 -0.026915 0.438727 -0.00376368 0.033385 0.438727 -0.00836207 0.0342843 0.433514 -0.00854095 -0.026915 0.43366 -0.00854095 -0.02646 0.434038 -0.00854095 -0.0251112 0.438727 -0.00854095 0.033385 0.430803 -0.00854095 0.033385 0.43509 -0.00854095 -0.0178688 0.435623 -0.00854095 -0.00667623 0.435636 -0.00854095 -0.00521158 0.435049 -0.00854095 0.0132009 0.432598 -0.00611368 -0.029265 0.433865 -0.00376368 -0.0255677 0.431123 -0.00376368 0.0325277 0.4315 -0.00376368 0.0316563 0.435377 -0.00376368 0.00759288 0.435555 -0.00376368 0.00293712 0.438727 -0.00376368 -0.026915 0.438727 -0.0121682 -0.029265 0.438727 -0.0100558 -0.02809 0.438727 -0.012091 -0.029265 0.438727 -0.0130675 -0.0290861 0.438727 -0.0138299 -0.0285767 0.433632 -0.0145182 -0.026915 0.43383 -0.0145182 -0.0262747 0.434022 -0.0145182 -0.025631 0.432446 -0.0145182 0.0297509 0.43163 -0.0145182 0.0319301 0.434507 -0.0145182 0.0194204 0.434186 -0.0145182 0.0217223 0.435656 -0.0145182 -0.00679132 0.438727 -0.0145182 -0.026915 0.435553 -0.0145182 0.00310781 0.435351 -0.0145182 0.00909521 0.432705 -0.0121682 -0.029265 0.432703 -0.012091 -0.029265 0.438727 -0.00974095 0.033385 0.433833 -0.00974095 -0.0259414 0.43368 -0.00974095 -0.0264293 0.432918 -0.00974095 0.0274448 0.438727 -0.00974095 -0.026915 0.435032 -0.00974095 0.013512 0.435483 -0.00974095 0.00546306 0.438727 -0.0121682 0.035735 0.438727 -0.0181455 -0.029265 0.438727 -0.0168932 0.0354202 0.438727 -0.0160331 -0.02809 0.438727 -0.0157182 -0.026915 0.438727 -0.0180682 -0.029265 0.438727 -0.0198072 -0.0285767 0.438727 -0.0204955 0.033385 0.434525 -0.0204955 0.0203196 0.435289 -0.0204955 -0.0184132 0.435392 -0.0204955 -0.0171452 0.438727 -0.0204955 -0.026915 0.435535 -0.0204955 0.00396267 0.435259 -0.0204955 0.0117013 0.434051 -0.0157182 -0.0255981 0.431672 -0.0157182 0.0319159 0.432484 -0.0157182 0.0297297 0.438727 -0.0157182 0.033385 0.435152 -0.0157182 -0.0186241 0.435148 -0.0157182 0.012776 0.435441 -0.0157182 0.00699605 0.435552 -0.0157182 0.00314328 0.438727 -0.0180682 0.035735 0.438727 -0.0241228 -0.029265 0.438727 -0.0250221 -0.0290861 0.438727 -0.0262939 0.0342843 0.438727 -0.0216955 0.033385 0.438727 -0.0257845 0.0350467 0.438727 -0.0250221 0.0355561 0.438727 -0.0220103 -0.02809 0.438727 -0.0257845 -0.0285767 0.438727 -0.0264728 0.033385 0.433453 -0.0264728 0.0280204 0.438727 -0.0264728 -0.026915 0.435529 -0.0264728 -0.0170598 0.432916 -0.0264728 0.03029 0.432329 -0.0264728 0.0321379 0.431895 -0.0264728 0.033385 0.435741 -0.0264728 -0.00937414 0.435723 -0.0264728 -0.00647492 0.435558 -0.0264728 0.0028596 0.433535 -0.0216955 0.0265111 0.43531 -0.0216955 -0.0183855 0.434442 -0.0216955 -0.0247592 0.435531 -0.0216955 0.00412115 0.435682 -0.0216955 -0.0102462 0.430649 -0.0240455 0.035735 0.438727 -0.0240455 0.035735 0.438727 -0.0309993 -0.0290861 0.438727 -0.0301 0.035735 0.438727 -0.0288478 -0.0289501 0.438727 -0.0301 -0.029265 0.438727 -0.0276728 -0.026915 0.438727 -0.03245 -0.026915 0.435811 -0.03245 0.0143931 0.438727 -0.03245 0.033385 0.43483 -0.03245 -0.0251095 0.435288 -0.03245 -0.0228726 0.433458 -0.03245 0.0299192 0.436545 -0.03245 -0.00576848 0.433639 -0.0301 -0.029265 0.432382 -0.0276728 0.0321751 0.432785 -0.0276728 0.0309367 0.435541 -0.0276728 0.00374001 0.43132 -0.0300228 0.035735 0.431329 -0.0301 0.035735 0.438727 -0.0377598 0.0345164 0.438727 -0.03805 0.033385 0.438727 -0.0338582 0.0343519 0.438727 -0.0338628 -0.027892 0.438727 -0.03585 -0.0292602 0.438727 -0.0377563 -0.0280526 0.438727 -0.03805 -0.026915 0.435192 -0.03805 0.0236084 0.436685 -0.03805 -0.0146018 0.433905 -0.03805 0.0296216 0.432964 -0.03805 0.033385 0.436053 -0.03365 -0.0163887 0.435558 -0.03365 -0.0203603 0.433619 -0.03365 0.0287732 0.433897 -0.03365 0.0275886 0.434407 -0.03365 0.0250651 0.434812 -0.03365 -0.0244186 0.436657 -0.03365 -0.000358619 0.438727 -0.03365 -0.026915 0.436679 -0.03365 -0.00343081 0.434727 0.0102293 0.0463067 0.434727 0.0128706 0.0463067 0.434727 0.013075 0.0455442 0.434727 -0.013075 0.0455442 0.435002 -0.0123294 0.0465215 0.434727 -0.0125009 0.0467365 0.434727 -0.0118894 0.047031 0.435002 -0.0107707 0.0465215 0.434727 -0.0112107 0.047031 0.434727 -0.0101761 0.0462059 0.434727 0.0154111 0.0482017 0.434727 0.0137704 0.0507647 0.434727 0.0112074 0.0524054 0.434727 0.0123125 0.0468649 0.434727 0.01155 0.0470692 0.434727 0.0091265 0.0484442 0.434727 0.0107875 0.0468649 0.434727 -0.0107875 0.0442235 0.434727 -0.0102294 0.0447817 0.434727 -0.00912658 0.0426442 0.434727 -0.00985004 0.0453442 0.434727 -0.0105992 0.0467365 0.434727 0.00874996 0.0528442 0.434727 0.00714996 0.0504208 0.434727 0.00444996 0.0511442 0.434727 -0.00875004 0.0528442 0.434727 0.01155 0.0440192 0.434727 0.0123125 0.0442235 0.434727 0.00984996 0.0453442 0.434727 0.010025 0.0455442 0.434727 -0.0137705 0.0507647 0.434727 -0.01585 0.0457442 0.434727 -0.012924 0.0462059 0.434727 -0.0123125 0.0442235 0.434727 -0.0112075 0.0386831 0.434727 -0.00715004 0.0406677 0.434727 -0.00445004 0.0399442 0.434727 0.00714996 0.0406677 0.428875 -0.00437546 0.0382442 0.42886 -4.24604e-08 0.0382442 0.434727 -0.00875004 0.0382442 0.428875 0.00437537 0.0382442 0.439027 -0.0511443 0.0563058 0.441027 -0.0505586 0.0557202 0.441027 -0.0511443 0.0563058 0.441027 -0.0519443 0.0565202 0.441027 -0.0527443 0.0563058 0.439027 -0.0533299 0.0557202 0.441027 -0.0533299 0.0557202 0.441027 -0.0535443 0.0549202 0.439027 -0.0527443 0.0535345 0.439027 -0.0533299 0.0541202 0.439027 -0.0548443 0.0549202 0.439027 -0.0527443 0.0563058 0.439027 -0.0539008 0.0570607 0.439027 -0.0519443 0.0565202 0.439027 -0.0505586 0.0557202 0.439027 -0.0503443 0.0549202 0.439027 -0.0490443 0.0549202 0.439027 -0.0511443 0.0535345 0.439027 -0.0519443 0.0533202 0.439027 -0.0526529 0.0521081 0.428804 -0.0490443 0.0549202 0.428688 -0.0495212 0.0565135 0.439027 -0.049207 0.055878 0.42877 -0.0500286 0.0570973 0.439027 -0.0499877 0.0570607 0.439027 -0.0512357 0.0577323 0.428923 -0.0507498 0.0575627 0.429325 -0.0526522 0.0577325 0.439027 -0.0526529 0.0577323 0.439027 -0.0546815 0.055878 0.430003 -0.054844 0.0549631 0.439027 0.000799958 0.0602181 0.439027 -0.000800042 0.0602181 0.439027 0.00144996 0.0613439 0.439027 0.00251143 0.0602824 0.439027 0.0013856 0.0596324 0.439027 0.00159996 0.0588324 0.439027 0.00289996 0.0588324 0.439027 0.0013856 0.0580324 0.439027 0.00144996 0.056321 0.439027 -4.19898e-08 0.0559324 0.439027 -0.00138568 0.0596324 0.439027 -0.00251152 0.0602824 0.439027 -4.19898e-08 0.0604324 0.439027 -0.00145004 0.0613439 0.441027 0.0533298 0.0557202 0.439027 0.0533298 0.0557202 0.439027 0.0527442 0.0563058 0.439027 0.0519442 0.0565202 0.441027 0.0511442 0.0563058 0.439027 0.0499877 0.0570607 0.439027 0.0539007 0.0570607 0.439027 0.0546815 0.055878 0.439027 0.0535442 0.0549202 0.439027 0.0548442 0.0549202 0.439027 0.0539007 0.0527796 0.439027 0.0526528 0.0521081 0.439027 0.0512356 0.0521081 0.439027 0.0509466 0.0536692 0.439027 0.0505027 0.0542259 0.439027 0.0503442 0.0549202 0.439027 0.0492069 0.0539623 0.439027 0.0505586 0.0557202 0.439027 0.0492069 0.055878 0.439027 0.0511442 0.0563058 0.430008 0.0548442 0.0549307 0.429616 0.0539896 0.056976 0.439027 0.0526528 0.0577323 0.429353 0.0527894 0.0576942 0.439027 0.0512356 0.0577323 0.428676 0.0493322 0.05618 0.439027 -0.0522639 0.00919555 0.441027 -0.0522639 0.00919555 0.441027 -0.0524783 0.00999555 0.439027 -0.0530639 0.0105812 0.441027 -0.0530639 0.0105812 0.439027 -0.0546639 0.0105812 0.439027 -0.0552496 0.00999555 0.439027 -0.0554639 0.00919555 0.439027 -0.0538639 0.0107955 0.439027 -0.0531553 0.0120076 0.439027 -0.0519074 0.0113361 0.439027 -0.0524783 0.00999555 0.439027 -0.0509639 0.00919555 0.439027 -0.0511267 0.00823774 0.439027 -0.0538639 0.00759555 0.439027 -0.0519074 0.007055 0.439027 -0.0531553 0.00638345 0.439027 -0.0566012 0.00823774 0.439027 -0.0567639 0.00919555 0.439027 -0.0558205 0.0113361 0.437398 -0.0511728 0.0102762 0.439027 -0.0511267 0.0101534 0.437247 -0.0527229 0.0118617 0.437238 -0.0529897 0.0119606 0.439027 -0.0545725 0.0120076 0.437227 -0.0538303 0.0120954 0.437284 -0.0554758 0.0116063 0.437505 -0.0567639 0.00919555 0.437504 -0.0567639 0.00921232 0.437502 -0.0567637 0.0092291 0.439027 -0.0566012 0.0101534 0.437319 -0.0558915 0.0112689 0.439027 -0.0469887 -0.0350139 0.439027 -0.0475744 -0.0344283 0.441027 -0.0475744 -0.0344283 0.439027 -0.0483744 -0.0342139 0.441027 -0.0483744 -0.0342139 0.439027 -0.04976 -0.0350139 0.441027 -0.04976 -0.0350139 0.439027 -0.0483744 -0.0374139 0.439027 -0.0499744 -0.0358139 0.439027 -0.0511116 -0.0348561 0.439027 -0.0491744 -0.0344283 0.439027 -0.0503309 -0.0336734 0.439027 -0.049083 -0.0330018 0.439027 -0.0476658 -0.0330018 0.439027 -0.0456371 -0.0348561 0.439027 -0.0467744 -0.0358139 0.439027 -0.0454744 -0.0358139 0.439027 -0.0469887 -0.0366139 0.439027 -0.0475744 -0.0371996 0.439027 -0.0464178 -0.0379545 0.439027 -0.0476658 -0.038626 0.4335 -0.0454744 -0.0358139 0.439027 -0.0464178 -0.0336734 0.434301 -0.0476649 -0.033002 0.434261 -0.0473273 -0.0331096 0.434071 -0.0463726 -0.0337156 0.434353 -0.0484498 -0.0329149 0.434357 -0.0490832 -0.0330019 0.434337 -0.0495637 -0.033169 0.434219 -0.0504909 -0.0338315 0.434023 -0.0510888 -0.0347932 0.433799 -0.0512744 -0.0358139 0.439027 0.0013856 -0.038535 0.439027 0.000799958 -0.0379493 0.441027 0.0013856 -0.038535 0.439027 -4.19898e-08 -0.037735 0.441027 -4.19898e-08 -0.037735 0.441027 -0.00138568 -0.038535 0.441027 -0.00160004 -0.039335 0.439027 -0.00138568 -0.040135 0.439027 -0.00290004 -0.039335 0.439027 -0.00160004 -0.039335 0.439027 -0.00138568 -0.038535 0.439027 -0.000800042 -0.0379493 0.439027 -0.00195659 -0.0371944 0.439027 0.000708545 -0.0365229 0.439027 0.00159996 -0.039335 0.439027 0.00289996 -0.039335 0.439027 0.000799958 -0.0407206 0.439027 -4.19898e-08 -0.040935 0.439027 0.0019565 -0.0414755 0.428264 0.00289996 -0.039335 0.429945 0.00118848 -0.0366897 0.439027 0.0019565 -0.0371944 0.439027 0.00273722 -0.0383772 0.429636 -0.00196786 -0.0372047 0.42988 -0.00140876 -0.0368001 0.439027 -0.000708629 -0.0365229 0.430089 -0.000255087 -0.0364462 0.429533 -0.00213706 -0.0373746 0.429288 -0.00244117 -0.0377695 0.439027 -0.0027373 -0.0383772 0.441027 0.0499743 -0.0358139 0.441027 0.0475743 -0.0344283 0.439027 0.0490829 -0.0330018 0.439027 0.0491743 -0.0344283 0.439027 0.0497599 -0.0350139 0.439027 0.0511116 -0.0348561 0.439027 0.0499743 -0.0358139 0.439027 0.0497599 -0.0366139 0.439027 0.0475743 -0.0371996 0.439027 0.0476657 -0.038626 0.439027 0.0467743 -0.0358139 0.439027 0.0454743 -0.0358139 0.439027 0.0469887 -0.0350139 0.439027 0.0475743 -0.0344283 0.439027 0.0483743 -0.0342139 0.439027 0.0512743 -0.0358139 0.433799 0.0512743 -0.0358139 0.439027 0.0503308 -0.0336734 0.434344 0.049439 -0.0331164 0.434357 0.0490829 -0.0330018 0.434348 0.0483148 -0.0329145 0.439027 0.0476657 -0.0330018 0.434243 0.0472023 -0.0331613 0.439027 0.0464178 -0.0336734 0.439027 0.045637 -0.0348561 0.434043 0.0462761 -0.033812 0.439027 0.0552495 0.00999555 0.441027 0.0552495 0.00999555 0.439027 0.0538638 0.0107955 0.441027 0.0538638 0.0107955 0.441027 0.0524782 0.00999555 0.439027 0.0546638 0.0105812 0.439027 0.0567638 0.00919555 0.439027 0.0554638 0.00919555 0.439027 0.0546638 0.00780991 0.439027 0.0538638 0.00759555 0.439027 0.0531553 0.00638345 0.439027 0.0530638 0.00780991 0.439027 0.0524782 0.00839555 0.439027 0.0511266 0.00823774 0.439027 0.0522638 0.00919555 0.439027 0.0509638 0.00919555 0.439027 0.0524782 0.00999555 0.439027 0.0530638 0.0105812 0.437505 0.0567638 0.00919555 0.437436 0.0566438 0.010021 0.439027 0.0566011 0.0101534 0.437324 0.0559373 0.0112231 0.439027 0.0558204 0.0113361 0.437256 0.0550045 0.0118618 0.439027 0.0545724 0.0120076 0.437245 0.0547432 0.011959 0.439027 0.0531553 0.0120076 0.437234 0.053155 0.0120076 0.437245 0.0527843 0.0118871 0.439027 0.0519073 0.0113361 0.439027 0.0511266 0.0101534 0.437298 0.0519071 0.0113359 0.437492 0.0509638 0.00919555 0.437489 0.050964 0.00922862 0.43737 0.0513165 0.0105816 0.441027 0.0297871 -0.0133092 0.441027 -0.0469973 0.0618776 0.441027 -0.0513041 0.0427692 0.441027 -0.052522 -0.0365648 0.441027 0.0564847 -0.0133092 0.441027 0.0590497 0.04544 0.441027 0.0511284 0.0601312 0.441027 0.0126325 0.0461692 0.441027 0.0128 0.0455442 0.441027 0.00444996 0.0498442 0.441027 0.012175 0.0466268 0.441027 0.01155 0.0467942 0.441027 0.012175 0.0444617 0.441027 0.0297871 0.0427692 0.441027 0.0104674 0.0449192 0.441027 0.0104674 0.0461692 0.441027 0.00800066 0.0477942 0.441027 -0.00650004 0.0492949 0.441027 0.00649996 0.0417935 0.441027 0.00444996 0.0412442 0.441027 0.054504 0.0260199 0.441027 0.0546638 0.0105812 0.441027 0.0554638 0.00919555 0.441027 0.0558711 -0.027363 0.441027 0.0396044 -0.042935 0.441027 -0.0489436 -0.0399904 0.441027 -0.0513041 -0.0133092 0.441027 -0.0558712 -0.027363 0.441027 -0.0549047 -0.0322216 0.441027 -0.0513041 0.0260199 0.441027 -0.0538639 0.0107955 0.441027 -0.0554639 0.00919555 0.441027 -0.0552496 0.00999555 0.441027 -0.0546639 0.0105812 0.441027 -0.0590498 0.04544 0.441027 -0.0519443 0.0533202 0.441027 -0.0542964 0.0576635 0.441027 -0.0568839 0.0542914 0.441027 -0.0527443 0.0535345 0.441027 -0.0513041 0.0568763 0.441027 -0.0513041 0.0515822 0.441027 0.054504 -0.0133092 0.441027 0.0530638 0.00780991 0.441027 0.0501592 -0.0133092 0.441027 0.0530638 0.0105812 0.441027 -0.0501593 0.0515822 0.441027 -0.0499744 -0.0358139 0.441027 -0.0501593 -0.0133092 0.441027 -0.0469887 -0.0350139 0.441027 -0.0467744 -0.0358139 0.441027 -0.0469887 -0.0366139 0.441027 -0.0475744 -0.0371996 0.441027 -0.0513041 -0.0375745 0.441027 -0.050277 -0.0389494 0.441027 -0.0501593 -0.0375745 0.441027 -0.0297872 -0.0133092 0.441027 -0.0491744 -0.0344283 0.441027 -0.00942504 0.0515822 0.441027 -0.0104675 0.0449192 0.441027 -0.0501593 0.0427692 0.441027 -0.0501593 0.0260199 0.441027 -0.0297872 0.0427692 0.441027 -0.00507504 0.0568763 0.441027 -0.00942504 0.0568763 0.441027 -0.0501593 0.0568763 0.441027 -0.0297872 0.0260199 0.441027 -0.00942504 0.0260199 0.441027 -0.00942504 -0.0133092 0.441027 -0.00507504 -0.0133092 0.441027 -0.0297872 -0.0375745 0.441027 -0.00507504 -0.0375745 0.441027 0.0013856 0.0596324 0.441027 0.00159996 0.0588324 0.441027 0.0013856 0.0580324 0.441027 0.00507496 0.0568763 0.441027 -4.19898e-08 0.0572324 0.441027 -0.000800042 0.0574468 0.441027 -0.00138568 0.0580324 0.441027 -0.00138568 0.0596324 0.441027 -0.000800042 0.0602181 0.441027 -4.19898e-08 0.0604324 0.441027 0.000799958 0.0602181 0.441027 -0.00942504 -0.0375745 0.441027 -0.0297872 -0.042935 0.441027 -0.00942504 -0.042935 0.441027 -0.00507504 -0.042935 0.441027 -0.000800042 -0.0379493 0.441027 0.00159996 -0.039335 0.441027 -4.19898e-08 -0.040935 0.441027 -0.00942504 0.0427692 0.441027 -0.00650004 0.0417935 0.441027 -0.00445004 0.0412442 0.441027 -0.00507504 0.0260199 0.441027 0.00507496 0.0260199 0.441027 0.00507496 -0.0375745 0.441027 0.000799958 -0.0379493 0.441027 0.00507496 0.0624324 0.441027 0.0297871 0.0568763 0.441027 0.00507496 -0.0133092 0.441027 0.0297871 -0.0375745 0.441027 0.00507496 -0.042935 0.441027 0.0297871 -0.042935 0.441027 0.0501592 -0.0375745 0.441027 0.0483743 -0.0342139 0.441027 0.0491743 -0.0344283 0.441027 0.0497599 -0.0350139 0.441027 0.0483743 -0.0374139 0.441027 0.0491743 -0.0371996 0.441027 0.0475743 -0.0371996 0.441027 0.0467743 -0.0358139 0.441027 0.0469887 -0.0350139 0.441027 0.0519442 0.0565202 0.441027 0.0505586 0.0557202 0.441027 0.0533858 0.0542259 0.441027 0.0535442 0.0549202 0.441027 0.054504 0.0568763 0.441027 0.0527442 0.0563058 0.441027 0.0523002 0.0533603 0.441027 0.0501592 0.0515822 0.441027 0.0505027 0.0542259 0.441027 -0.0503443 0.0549202 0.441027 -0.0297872 0.0568763 0.441027 -0.0297872 0.0515822 0.441027 -0.00507504 0.0515822 0.441027 0.00507496 0.0515822 0.441027 0.0501592 0.0568763 0.441027 0.0503442 0.0549202 0.441027 0.0297871 0.0515822 0.441027 0.054504 0.0515822 0.441027 0.054504 0.0427692 0.441027 0.0582018 0.0260199 0.441027 0.0589331 0.0427692 0.441027 0.0501592 0.0427692 0.441027 0.0501592 0.0260199 0.441027 0.0297871 0.0260199 0.441027 0.01155 0.0442942 0.4371 0.0578838 0.0118579 0.437627 0.0573539 -0.000278057 0.43544 0.0584634 0.0251332 0.426272 0.0431833 0.0627276 0.426179 0.0429832 0.0627312 0.426131 0.0428788 0.0627322 0.428358 0.0494071 0.061352 0.440727 0.0471912 0.0621358 0.427512 0.0463291 0.0623489 0.440727 0.0512821 0.0603888 0.440727 0.0573787 0.0540202 0.430511 0.058363 0.0518278 0.430129 0.0574308 0.0539228 0.431696 0.0593495 0.045427 0.431112 0.0591895 0.0485582 0.440727 -0.0593653 0.0461503 0.440727 -0.0545085 0.0578756 0.440727 -0.0571437 0.0544414 0.440727 -0.0510742 0.0605109 0.440727 -0.0427831 0.0627325 0.426619 -0.0439608 0.0626906 0.440727 -0.0470749 0.0621674 0.437098 -0.0568229 -0.0124426 0.435609 -0.0562916 -0.0246108 0.431696 -0.0593495 0.045427 0.436125 -0.0582625 0.0205294 0.436866 -0.0579933 0.014363 0.440727 -0.0593495 0.045427 0.437609 -0.0574505 0.00193275 0.437627 -0.057354 -0.000278057 0.440727 -0.0445908 -0.0424675 0.432521 -0.0484805 -0.0406594 0.432133 -0.0464568 -0.041753 0.431781 -0.0445906 -0.0424676 0.432976 -0.0507023 -0.0389738 0.440727 -0.0491156 -0.0402361 0.432775 -0.0497489 -0.0397699 0.432647 -0.0491156 -0.0402362 0.433467 -0.05276 -0.0367474 0.440727 -0.05276 -0.0367474 0.43436 -0.0552803 -0.0320599 0.433888 -0.0541512 -0.0346128 0.435008 -0.0561022 -0.0283247 0.440727 -0.0396045 -0.043235 0.435013 0.0561049 -0.0282964 0.433591 0.0532066 -0.0361369 0.433936 0.0542871 -0.0343591 0.434312 0.0551866 -0.0323242 0.432686 0.0493077 -0.0400995 0.433058 0.0510762 -0.0386264 0.433137 0.0514245 -0.0382827 0.440727 0.0527599 -0.0367474 0.43351 0.052921 -0.0365339 0.440727 0.0445908 -0.0424675 0.43222 0.0469165 -0.0415357 0.432605 0.0489057 -0.0403806 0.43105 0.0405548 -0.0432077 0.440727 0.0396044 -0.043235 0.43173 0.0443169 -0.0425513 0.433852 -0.0481975 -0.0323257 0.433864 -0.0493395 -0.0324568 0.435693 -0.0561048 -0.0219953 0.432563 -0.0110949 -0.0291929 0.432747 -0.0102671 -0.0286269 0.432392 -0.000136411 -0.029395 0.433402 -0.00316414 -0.0265013 0.433288 -0.00356415 -0.0268524 0.432964 -0.00257755 -0.0278068 0.43268 -0.00428649 -0.0286253 0.432674 -0.0020406 -0.0286265 0.433627 -0.00914323 -0.0259126 0.43347 -0.00874322 -0.0263988 0.43349 -0.00954356 -0.0263683 0.433021 -0.00972955 -0.0278054 0.43271 -0.00801945 -0.0286278 0.433062 -0.0230627 -0.0292043 0.432293 -0.0280251 -0.0327911 0.43276 -0.0170787 -0.0291975 0.433635 -0.0147231 -0.0262287 0.43313 -0.014536 -0.0278135 0.432917 -0.0162498 -0.0286319 0.432618 -0.0131724 -0.0291947 0.433887 -0.0215032 -0.0261385 0.433683 -0.0215038 -0.0268598 0.433854 -0.0207029 -0.0261432 0.433189 -0.0222333 -0.0286401 0.433355 -0.0205148 -0.0278211 0.433075 -0.019975 -0.0286402 0.434152 -0.0274819 -0.0261332 0.433853 -0.0349969 -0.0290401 0.433907 -0.0365282 -0.0292049 0.432911 -0.0350216 -0.0328077 0.433888 -0.0363384 -0.0292405 0.433849 -0.0357431 -0.0292509 0.433926 -0.0266825 -0.0268643 0.433649 -0.0278238 -0.0281348 0.433758 -0.0319249 -0.0286595 0.433446 -0.0301128 -0.0294131 0.434037 -0.0339115 -0.0279923 0.434231 -0.03266 -0.0268699 0.434271 -0.03365 -0.026915 0.43501 -0.0326569 -0.0232696 0.434558 -0.0422224 -0.0274306 0.434098 -0.037569 -0.0286184 0.436292 -0.0425723 -0.0165661 0.435927 -0.0382536 -0.018815 0.436864 -0.0427346 -0.0110896 0.436758 -0.0382513 -0.0120151 0.437327 -0.03825 -0.000264971 0.433846 -0.0497826 -0.0326205 0.434591 -0.0557174 -0.028954 0.435638 -0.0494571 -0.0220033 0.433752 -0.0507213 -0.0332496 0.434198 -0.0552323 -0.0311761 0.433531 -0.0515682 -0.0345238 0.433252 -0.0528156 -0.0361211 0.433287 -0.0517846 -0.0358244 0.432964 -0.0513327 -0.0374188 0.432715 -0.0506614 -0.0385561 0.432689 -0.0501976 -0.0385972 0.43234 -0.0488901 -0.0399774 0.431951 -0.0469272 -0.0411415 0.432467 -0.0474471 -0.038971 0.431873 -0.0465244 -0.0413363 0.431468 -0.0444085 -0.042148 0.430391 -0.0383654 -0.042844 0.431381 -0.0348646 -0.038046 0.429722 -0.0347559 -0.0428314 0.428321 -0.0278365 -0.0428065 0.42896 -0.0309581 -0.0428176 0.428872 -0.0139869 -0.0379442 0.426524 -0.0177956 -0.0427783 0.427248 -0.0222761 -0.042789 0.42855 -0.0069965 -0.0379112 0.425526 -0.00531151 -0.0427652 0.427149 -0.0032032 -0.0402225 0.425898 -0.00138634 -0.0421615 0.426211 -0.00215548 -0.0416915 0.425771 -0.000843289 -0.0423488 0.425593 -4.19898e-08 -0.0426093 0.425487 -0.00106234 -0.0427648 0.425487 -4.19898e-08 -0.0427648 0.429488 -0.00144469 -0.0360304 0.431079 -0.00701487 -0.0327362 0.42909 -0.00250713 -0.0368037 0.432548 -0.046065 -0.03817 0.432768 -0.0452232 -0.0368964 0.433443 -0.0420284 -0.0328256 0.433399 -0.0454617 -0.0340035 0.43369 -0.0465936 -0.0328339 0.433771 -0.0471663 -0.0325478 0.436572 -0.0564176 -0.0148322 0.436419 -0.0563545 -0.0162785 0.435517 -0.042403 -0.0220099 0.431288 -0.0140276 -0.0327547 0.432515 -0.0120961 -0.0293972 0.428982 -0.00268252 -0.0370091 0.429531 -0.0209553 -0.0379792 0.430425 -0.0279091 -0.0380133 0.432203 -0.0418401 -0.0380812 0.432943 -0.0450221 -0.0360304 0.435131 0.0331064 -0.0227323 0.436848 0.0427288 -0.0112854 0.425699 -4.19898e-08 -0.042454 0.427082 0.00316164 -0.0403308 0.426447 0.00253552 -0.0413315 0.427806 0.00340292 -0.0391274 0.426514 0.0177212 -0.0427781 0.429516 0.0209548 -0.0380106 0.431153 0.0427331 -0.0425619 0.430749 0.0404852 -0.0428294 0.429722 0.0347558 -0.0428314 0.43248 0.0481071 -0.0390972 0.431696 0.0456019 -0.0417324 0.431285 0.0434388 -0.0424108 0.432342 0.0489023 -0.0399688 0.432499 0.0484693 -0.0391104 0.432718 0.050671 -0.0385471 0.433094 0.0522349 -0.0368793 0.433127 0.0516605 -0.0366376 0.433261 0.0528458 -0.036079 0.433646 0.054038 -0.0341395 0.433853 0.0496366 -0.0325588 0.433614 0.051355 -0.0340643 0.434041 0.0549532 -0.0320391 0.43381 0.0502495 -0.0328768 0.434869 0.0558725 -0.0273139 0.435675 0.0560991 -0.0221243 0.435619 0.0494523 -0.0221325 0.436891 0.0565723 -0.0112885 0.437225 0.0382502 -0.00522568 0.436531 0.0382518 -0.0141853 0.434616 0.0382582 -0.0263085 0.435261 0.0382557 -0.0229015 0.435496 0.0423988 -0.0221393 0.436272 0.0425673 -0.0167283 0.436407 0.05635 -0.0163797 0.433892 0.0365501 -0.0292786 0.434039 0.0373436 -0.0288305 0.434228 0.0379412 -0.0281077 0.434433 0.0382381 -0.0272003 0.433894 0.0337481 -0.0285541 0.434063 0.0332583 -0.0277242 0.434254 0.0331099 -0.0268703 0.434574 0.0323085 -0.0252771 0.432745 0.0167301 -0.029198 0.433041 0.0227143 -0.0292048 0.432272 0.0280235 -0.0328548 0.433908 0.0263323 -0.0268639 0.433638 0.0261434 -0.0278274 0.433399 0.028993 -0.0293163 0.434098 0.0263317 -0.0261352 0.434285 0.026331 -0.0253908 0.434044 0.0203522 -0.0254116 0.43384 0.0203527 -0.0261458 0.433635 0.0203532 -0.0268589 0.43334 0.0201655 -0.0278186 0.43274 0.00991789 -0.0286279 0.432393 -4.19914e-08 -0.0293914 0.432508 0.0118231 -0.0293971 0.432506 0.0117458 -0.029397 0.432829 0.0136488 -0.028631 0.432608 0.0128239 -0.0291937 0.433481 0.00919332 -0.0263814 0.432408 0.00584234 -0.0293953 0.432493 0.0068445 -0.0291911 0.432706 0.00767033 -0.0286266 0.433015 0.00937996 -0.027807 0.433461 0.00839298 -0.0264128 0.4336 0.00839288 -0.0259717 0.433389 0.00281375 -0.0265393 0.433345 0.00321399 -0.0266742 0.432974 0.0022401 -0.0277749 0.433287 0.00321399 -0.0268524 0.433286 0.00241384 -0.0268524 0.433329 0.00241384 -0.0267189 0.428499 0.00318841 -0.0379052 0.428533 0.00699635 -0.0379426 0.431112 -4.19898e-08 -0.0325709 0.433559 0.0459583 -0.0333471 0.433001 0.0450065 -0.0357605 0.432196 0.0418389 -0.0381126 0.432498 0.0465414 -0.0385493 0.433857 0.0483213 -0.032321 0.434539 0.042219 -0.0275276 0.433753 0.0470202 -0.0326081 0.431052 0.00701451 -0.032799 0.428856 0.0139867 -0.0379756 0.431262 0.014027 -0.0328177 0.433429 0.042026 -0.0328899 0.433209 0.0451227 -0.0348183 0.431371 0.0348636 -0.0380774 0.432894 0.0350195 -0.0328717 0.430412 0.0279084 -0.0380447 0.426899 0.0202387 -0.0427837 0.425327 -0.00875004 0.0528442 0.425327 -0.015542 0.0478129 0.434727 -0.0112075 0.0524054 0.425327 -0.0112075 0.0524054 0.434727 -0.0154112 0.0482017 0.425327 -0.0121558 0.0519741 0.425478 -0.01585 0.0455438 0.425515 -0.01585 0.0453442 0.426492 -0.0154098 0.0428829 0.426264 -0.0155514 0.0433068 0.434727 -0.01585 0.0453442 0.425682 -0.0158211 0.0447035 0.428887 -0.0106706 0.0385089 0.428803 -0.0112627 0.0387037 0.434727 -0.0137705 0.0403238 0.428156 -0.0134381 0.0400122 0.427109 -0.0149313 0.0418511 0.434727 -0.0154112 0.0428868 0.434727 0.00874996 0.0382442 0.428847 0.010985 0.0386053 0.434727 0.0112074 0.0386831 0.434727 0.0137704 0.0403238 0.426627 0.015318 0.0426477 0.427109 0.0149313 0.0418512 0.42755 0.0144478 0.0411086 0.434727 0.0154111 0.0428868 0.434727 0.01585 0.0453442 0.425515 0.01585 0.0453442 0.425478 0.01585 0.0455438 0.434727 0.01585 0.0457442 0.425327 0.0155419 0.0478129 0.425327 0.014938 0.0492253 0.425327 0.0154111 0.0482017 0.425327 0.0112074 0.0524054 0.425327 0.0121371 0.0519842 0.425327 0.0137323 0.0508025 0.425327 0.00282725 0.0594778 0.425327 0.00251143 0.0602824 0.425327 0.00144996 0.0613439 0.425327 0.00125822 0.0614453 0.439027 -4.19898e-08 0.0617324 0.425327 -0.0012583 0.0614453 0.425327 -0.00145004 0.0613439 0.425327 -0.00251152 0.0602824 0.425885 -0.0423362 0.0627325 0.426086 -0.0427831 0.0627325 0.425129 0.0385919 0.0627325 0.425127 -0.0380607 0.0627325 0.425967 -0.0423972 0.0562834 0.428524 -0.00876426 0.0375038 0.43211 -0.0274887 0.0323593 0.432338 -0.03365 0.033385 0.437176 -0.0382503 0.00573372 0.433133 -0.0442085 0.0337629 0.428038 -0.0492355 0.0611342 0.428005 -0.0490985 0.0611929 0.428333 -0.0504914 0.0595057 0.428571 -0.0513781 0.058225 0.428669 -0.0519219 0.0582878 0.428852 -0.0529659 0.0581509 0.428788 -0.0528723 0.0589486 0.429106 -0.054331 0.0573541 0.429283 -0.0552422 0.0566375 0.429309 -0.0550976 0.0562623 0.429639 -0.0565926 0.0547744 0.429805 -0.057108 0.0538864 0.429704 -0.0524808 0.0514563 0.429776 -0.0533623 0.05171 0.430601 -0.0586946 0.0496069 0.430808 -0.058896 0.0485072 0.430206 -0.0520081 0.0488132 0.431401 -0.0590562 0.0453834 0.432334 -0.0588421 0.0405581 0.436811 -0.0514344 0.0115294 0.436778 -0.0519026 0.0119275 0.434863 -0.0439861 0.0252909 0.435828 -0.0579638 0.0205016 0.436189 -0.0437417 0.0168312 0.436575 -0.0576908 0.0142676 0.43693 -0.057514 0.0102326 0.436934 -0.0571077 0.0101797 0.437004 -0.0572643 0.00920109 0.43726 -0.0572417 0.00401541 0.437146 -0.0562955 0.00679319 0.437303 -0.0571667 0.00230351 0.437181 -0.0551993 0.00604558 0.437324 -0.0570918 0.000591225 0.437192 -0.0539 0.00577356 0.437183 -0.0527594 0.00595713 0.437143 -0.0514865 0.00673954 0.437032 -0.0434778 0.00834118 0.43542 -0.0382552 0.0212552 0.436709 -0.0382514 0.0119183 0.43693 -0.0382509 0.00948396 0.432771 -0.0382667 0.033334 0.432921 -0.0382659 0.0327645 0.432551 -0.0381457 0.0341122 0.43133 -0.0311198 0.0356654 0.431614 -0.0319405 0.0351078 0.431825 -0.0355165 0.0356847 0.431338 -0.0369238 0.0377564 0.432035 -0.0369811 0.0355204 0.432178 -0.0374524 0.0352008 0.433603 -0.0336103 0.0288292 0.433266 -0.0326634 0.0298668 0.431093 -0.0290481 0.0356632 0.430373 -0.0295551 0.0376902 0.431708 -0.0266897 0.0333181 0.431341 -0.0265033 0.0342757 0.43178 -0.02749 0.0333192 0.43146 -0.0276751 0.0342673 0.431213 -0.0282145 0.0350934 0.429471 -0.0221898 0.0376231 0.430474 -0.0241421 0.0358579 0.430478 -0.0157081 0.0342422 0.430138 -0.0162373 0.0350637 0.429914 -0.0181601 0.0358507 0.431877 -0.0207075 0.0315817 0.431822 -0.0215082 0.031873 0.431212 -0.0207093 0.033311 0.431272 -0.0215098 0.0333118 0.42881 -0.0148105 0.0375545 0.430878 -0.0155281 0.0333062 0.430727 -0.0147579 0.0335613 0.432019 -0.0147253 0.0303906 0.431457 -0.015527 0.0319138 0.43204 -0.0151255 0.0303758 0.429526 -0.0120994 0.0358459 0.429685 -0.013197 0.0356346 0.430409 -0.0145459 0.0342488 0.430837 -0.0147274 0.0333056 0.431273 -0.0087446 0.031813 0.429312 -6.81987e-05 0.0358424 0.429344 -0.00611633 0.0358437 0.428829 -0.00802164 0.0369001 0.430621 -0.0087451 0.0333026 0.430641 -0.00954576 0.0333029 0.430183 -0.00856534 0.0342404 0.430215 -0.00972479 0.0342372 0.429777 -0.00804145 0.0350555 0.429472 -0.00721705 0.0356306 0.42984 -0.0102504 0.0350559 0.430553 -0.00276424 0.0333016 0.430556 -0.00356455 0.0333016 0.430118 -0.00374363 0.034237 0.430113 -0.00258522 0.0342371 0.429713 -0.002062 0.0350531 0.429723 -0.00426765 0.0350538 0.429421 -0.0012367 0.0356299 0.428102 -0.012709 0.0385954 0.428531 -0.00916147 0.0375145 0.426684 -0.0185126 0.0419154 0.428674 -0.0296492 0.041602 0.426669 -0.0275262 0.0445551 0.426571 -0.033645 0.0474566 0.428475 -0.0371601 0.0454217 0.426492 -0.0408898 0.0526279 0.428685 -0.048191 0.052482 0.428561 -0.0488274 0.0537646 0.42835 -0.0486667 0.0546996 0.4282 -0.0488798 0.0560377 0.429774 -0.0544588 0.0524867 0.429923 -0.0555908 0.0523131 0.42967 -0.0551723 0.0536289 0.429702 -0.0550402 0.0533247 0.427314 -0.0467845 0.0594757 0.427882 -0.0477077 0.0560278 0.426002 -0.0433043 0.0624462 0.428195 -0.0489801 0.0562839 0.428307 -0.0499434 0.0575431 0.428436 -0.0506498 0.0579862 0.429038 -0.0496965 0.0523561 0.4277 -0.0445391 0.0525605 0.426672 -0.0440732 0.0560676 0.425921 -0.0432968 0.0600863 0.42665 -0.0297717 0.0454834 0.43114 -0.0444249 0.0416725 0.430026 -0.0445474 0.0453545 0.426805 -0.0372826 0.0491124 0.42885 -0.0446428 0.0489775 0.426219 -0.0401664 0.052666 0.433499 -0.0516003 0.0338224 0.429431 -0.0509394 0.0515972 0.431035 -0.0519516 0.0452767 0.431857 -0.0518517 0.0417144 0.430004 -0.0370277 0.0416359 0.432163 -0.0443148 0.0378272 0.427427 -0.0222696 0.0415679 0.426687 -0.0154084 0.0413411 0.427319 0.0468009 0.0594781 0.428337 0.0505095 0.0595083 0.429384 0.0556575 0.0561207 0.430726 0.0147632 0.0335628 0.429769 0.00769034 0.0350561 0.430879 0.00241401 0.0325758 0.428877 -4.19898e-08 0.0366692 0.429721 0.00391645 0.0350528 0.430552 0.00241404 0.0333016 0.42951 0.0117489 0.0358457 0.428858 0.00821388 0.0368553 0.430174 0.00821466 0.034241 0.430205 0.0093743 0.0342368 0.430613 0.00839473 0.0333025 0.431679 0.00879412 0.0308327 0.43129 0.00919483 0.0317935 0.431317 0.0143762 0.0321292 0.42988 0.0177324 0.0358502 0.430387 0.0196447 0.0350761 0.42881 0.0148158 0.0375562 0.430458 0.0153576 0.0342417 0.43086 0.0151777 0.033306 0.4315 0.0151765 0.0317684 0.432292 0.020356 0.0303759 0.431836 0.0211578 0.0317713 0.43231 0.0207563 0.0303907 0.43078 0.0201745 0.0342623 0.430581 0.0218743 0.0350749 0.431054 0.0286954 0.0356615 0.430628 0.0247971 0.035653 0.430437 0.0237918 0.0358574 0.430429 0.0237145 0.0358573 0.432546 0.0263363 0.0307667 0.432579 0.0271366 0.0308423 0.431176 0.0278625 0.035091 0.431306 0.0261525 0.0342767 0.432026 0.0263382 0.0323242 0.431905 0.0321287 0.0342909 0.431938 0.0334729 0.0346195 0.431783 0.0356714 0.0358758 0.431339 0.0369371 0.0377581 0.431785 0.0340578 0.0352994 0.431733 0.034835 0.0357337 0.431289 0.0307687 0.0356653 0.431101 0.0297717 0.0358663 0.431092 0.0296944 0.0358662 0.432172 0.0331582 0.0337739 0.432305 0.0331179 0.0333269 0.43223 0.0323179 0.0333258 0.433098 0.0331142 0.0305973 0.433286 0.0327315 0.029808 0.432771 0.0382666 0.033334 0.437327 0.03825 -0.000264971 0.437161 0.0518952 0.00639917 0.437327 0.0570542 -0.000264971 0.437148 0.056243 0.00674082 0.437317 0.0571274 0.0014064 0.437165 0.0573467 0.00641567 0.436966 0.0574925 0.00974249 0.436893 0.056891 0.0107063 0.436692 0.057638 0.013064 0.43679 0.0558285 0.0119282 0.436758 0.0552026 0.0122771 0.436057 0.0578884 0.0187797 0.434863 0.044002 0.0252921 0.436189 0.0437575 0.016832 0.436894 0.0507389 0.010492 0.437032 0.0434935 0.0083416 0.436919 0.0506221 0.0101777 0.43699 0.0504653 0.00919926 0.431857 0.0518706 0.0417162 0.432528 0.0587979 0.0395573 0.431036 0.0519704 0.0452782 0.430208 0.0520268 0.0488148 0.430128 0.0579187 0.0521468 0.42806 0.0493308 0.0610924 0.428092 0.0494661 0.0610318 0.428594 0.0518664 0.0596875 0.428735 0.0522906 0.0582784 0.42848 0.0512876 0.0600618 0.426496 0.0409042 0.0526298 0.427704 0.0445547 0.0525623 0.425899 0.0430859 0.0585894 0.42668 0.0246867 0.0435502 0.426661 0.0285072 0.0449469 0.429471 0.0221977 0.0376248 0.428423 -4.19898e-08 0.0375012 0.428524 0.00876418 0.0375038 0.42845 0.0108187 0.0377848 0.427507 0.0142588 0.0398195 0.426687 0.0154083 0.0413411 0.429515 0.0553959 0.054866 0.429746 0.0569315 0.054205 0.430719 0.0588189 0.0489796 0.430302 0.0582577 0.0512098 0.42979 0.0539182 0.0520219 0.429925 0.055611 0.0523149 0.429777 0.0543966 0.0524225 0.429712 0.0549925 0.0532314 0.428255 0.0487021 0.0553349 0.428334 0.0486647 0.0547898 0.428688 0.048208 0.0524838 0.429218 0.0501864 0.051964 0.427138 0.0460949 0.0621282 0.42828 0.0497795 0.0574002 0.428197 0.0489131 0.0561258 0.427887 0.0477243 0.0560299 0.429322 0.0551323 0.056181 0.429345 0.0553219 0.0561623 0.428945 0.053671 0.0582705 0.42891 0.0532969 0.0580324 0.426357 0.044087 0.062408 0.426678 0.0440884 0.0560696 0.428853 0.0446587 0.0489791 0.426313 0.0390502 0.0514627 0.426428 0.0372622 0.0498903 0.430028 0.0445635 0.0453562 0.428477 0.0371735 0.0454235 0.426808 0.0372959 0.0491142 0.426516 0.0353312 0.0484978 0.426652 0.0297824 0.0454853 0.431141 0.044441 0.0416743 0.432206 0.0588713 0.0412218 0.433133 0.0442245 0.0337646 0.433499 0.051619 0.0338241 0.434964 0.0582137 0.0262139 0.432165 0.0443309 0.037829 0.430374 0.0295658 0.0376919 0.430006 0.037041 0.0416378 0.428675 0.0296599 0.0416038 0.427427 0.0222776 0.0415697 0.426684 0.0200669 0.0422637 0.439027 -0.00290004 0.0588324 0.425327 -0.00282733 0.0581871 0.439027 -0.00251152 0.0573824 0.425327 -0.00251152 0.0573824 0.425327 -0.00226735 0.0570243 0.425327 -0.00145004 0.056321 0.425327 -0.0012583 0.0562196 0.439027 -0.00145004 0.056321 0.425327 0.00125822 0.0562196 0.439027 0.00251143 0.0573824 0.425327 0.00282725 0.0581871 0.425327 0.00289996 0.0588324 0.437686 0.0531552 0.00638344 0.437557 0.0510849 0.0083661 0.439027 0.0519073 0.007055 0.437678 0.0527253 0.00652841 0.437641 0.0518076 0.00715055 0.437691 0.0541471 0.00630938 0.437688 0.0545725 0.00638348 0.439027 0.0566011 0.00823774 0.439027 0.0558204 0.007055 0.437652 0.0558205 0.00705512 0.437682 0.0549459 0.00650499 0.439027 0.0545724 0.00638345 0.441027 0.0522638 0.00919555 0.441027 0.0524782 0.00839555 0.441027 0.0538638 0.00759555 0.439027 0.0552495 0.00839555 0.441027 0.0546638 0.00780991 0.441027 0.0552495 0.00839555 0.433552 0.0510745 -0.0368717 0.4335 0.0454743 -0.0358139 0.433494 0.0454744 -0.035836 0.439027 0.045637 -0.0367717 0.433488 0.0454746 -0.0358582 0.433039 0.046349 -0.0378896 0.432957 0.0473072 -0.0385105 0.439027 0.0464178 -0.0379545 0.439027 0.0490829 -0.038626 0.433 0.0486002 -0.0387052 0.432958 0.0478294 -0.0386623 0.432955 0.0476654 -0.038626 0.439027 0.0511116 -0.0367717 0.439027 0.0503308 -0.0379545 0.439027 0.0469887 -0.0366139 0.441027 0.0469887 -0.0366139 0.439027 0.0483743 -0.0374139 0.439027 0.0491743 -0.0371996 0.441027 0.0497599 -0.0366139 0.439027 0.000708545 -0.0421471 0.426185 0.000716542 -0.042145 0.426313 0.00118188 -0.0419832 0.427508 0.00269409 -0.0404081 0.42672 0.0019716 -0.0414617 0.439027 0.00273722 -0.0402928 0.427931 -0.00286031 -0.0398158 0.439027 -0.0027373 -0.0402928 0.426113 -4.0434e-08 -0.042235 0.439027 -0.000708629 -0.0421471 0.426184 -0.000714208 -0.0421457 0.439027 -0.00195659 -0.0414755 0.439027 -0.000800042 -0.0407206 0.441027 -0.00138568 -0.040135 0.441027 -0.000800042 -0.0407206 0.441027 0.000799958 -0.0407206 0.439027 0.0013856 -0.040135 0.441027 0.0013856 -0.040135 0.432961 -0.0471776 -0.0384555 0.432955 -0.0476655 -0.038626 0.439027 -0.0512744 -0.0358139 0.433778 -0.051273 -0.0359036 0.433313 -0.050481 -0.037807 0.439027 -0.0511116 -0.0367717 0.433576 -0.0511118 -0.0367715 0.433614 -0.0511628 -0.0366111 0.433093 -0.0494133 -0.0385215 0.439027 -0.0503309 -0.0379545 0.439027 -0.049083 -0.038626 0.433175 -0.0458228 -0.0371923 0.439027 -0.0456371 -0.0367717 0.433028 -0.0464162 -0.037953 0.432989 -0.0467419 -0.0382108 0.439027 -0.04976 -0.0366139 0.441027 -0.04976 -0.0366139 0.439027 -0.0491744 -0.0371996 0.441027 -0.0491744 -0.0371996 0.441027 -0.0483744 -0.0374139 0.437688 -0.0545725 0.00638344 0.437493 -0.050964 0.0091803 0.437494 -0.0509641 0.00916506 0.437567 -0.0566429 0.00836631 0.439027 -0.0558205 0.007055 0.437685 -0.0547563 0.00643623 0.437692 -0.0538943 0.00629571 0.439027 -0.0545725 0.00638345 0.437691 -0.0535818 0.00630927 0.437663 -0.0522453 0.00678928 0.437679 -0.0527819 0.00650498 0.439027 -0.0552496 0.00839555 0.441027 -0.0552496 0.00839555 0.441027 -0.0546639 0.00780991 0.439027 -0.0546639 0.00780991 0.441027 -0.0538639 0.00759555 0.439027 -0.0530639 0.00780991 0.439027 -0.0524783 0.00839555 0.441027 -0.0530639 0.00780991 0.441027 -0.0524783 0.00839555 0.428804 0.0490442 0.0549202 0.439027 0.0490442 0.0549202 0.429056 0.0492074 0.0539606 0.429972 0.0512327 0.0521088 0.4299 0.0509695 0.0521889 0.439027 0.0499877 0.0527796 0.43012 0.0519094 0.0520204 0.430201 0.0545052 0.0535595 0.439027 0.0546815 0.0539623 0.430278 0.0535997 0.0525396 0.430227 0.0526515 0.0521078 0.441027 0.0509466 0.0536692 0.441027 0.0515882 0.0533603 0.439027 0.0515882 0.0533603 0.439027 0.0523002 0.0533603 0.439027 0.0529418 0.0536692 0.441027 0.0529418 0.0536692 0.439027 0.0533858 0.0542259 0.439027 -0.00160004 0.0588324 0.441027 -0.00160004 0.0588324 0.439027 -0.00138568 0.0580324 0.439027 -0.000800042 0.0574468 0.439027 -4.19898e-08 0.0572324 0.439027 0.000799958 0.0574468 0.441027 0.000799958 0.0574468 0.439027 -0.049207 0.0539623 0.43001 -0.0548443 0.0549202 0.439027 -0.0546815 0.0539623 0.439027 -0.0539008 0.0527796 0.439027 -0.0512357 0.0521081 0.42923 -0.0494296 0.0534757 0.439027 -0.0499877 0.0527796 0.429538 -0.0499866 0.0527806 0.439027 -0.0535443 0.0549202 0.441027 -0.0533299 0.0541202 0.439027 -0.0505586 0.0541202 0.441027 -0.0511443 0.0535345 0.441027 -0.0505586 0.0541202 0.435002 -0.0103 0.0455442 0.434727 -0.010025 0.0455442 0.434727 -0.01155 0.0440192 0.434727 -0.0128707 0.0447817 0.435002 -0.0128 0.0455442 0.434727 0.0128706 0.0447817 0.435002 0.012175 0.0444617 0.435002 0.01155 0.0442942 0.434727 0.0107875 0.0442235 0.434727 0.0102293 0.0447817 0.434078 -0.025 0.0566324 0.433327 -0.025 0.0553824 0.433327 -0.025625 0.0555499 0.433327 -0.02375 0.0566324 0.433327 -0.0239175 0.0560074 0.433327 -0.024375 0.0555499 0.425102 -0.025625 0.0555499 0.425102 -0.0260826 0.0560074 0.433327 -0.0260826 0.0560074 0.425102 -0.0239175 0.0560074 0.424827 -0.0236794 0.0558699 0.425102 -0.024375 0.0555499 0.424827 -0.025 0.0551074 0.425102 -0.025 0.0553824 0.424827 -0.0257625 0.0553118 0.424827 -0.0263207 0.0558699 0.433327 0.0260825 0.0560074 0.433327 0.025625 0.0555499 0.433327 0.0239174 0.0560074 0.433327 0.02375 0.0566324 0.433327 0.02625 0.0566324 0.425102 0.025 0.0553824 0.433327 0.025 0.0553824 0.433327 0.024375 0.0555499 0.425102 0.024375 0.0555499 0.425102 0.02375 0.0566324 0.425102 0.02625 0.0566324 0.425102 0.0260825 0.0560074 0.424827 0.0263206 0.0558699 0.425102 0.025625 0.0555499 0.424827 0.0257625 0.0553118 0.424827 0.025 0.0551074 0.425102 0.0239174 0.0560074 0.441027 -0.0590653 0.0461503 0.425077 -4.19898e-08 0.0558655 0.425327 0.00144996 0.056321 0.425327 0.00226727 0.0570243 0.425077 0.00231964 0.0569826 0.425327 0.00251143 0.0573824 0.425077 0.00289256 0.0581722 0.425077 0.00289256 0.0594927 0.425077 0.00128729 0.0615056 0.425327 0.00226727 0.0606406 0.425327 -4.19898e-08 0.0617324 0.425077 0.00128729 0.0561593 0.424894 0.00246273 0.0568685 0.425077 0.00231964 0.0606823 0.424894 0.00307098 0.0595334 0.424894 0.00136669 0.0616705 0.425077 -4.19898e-08 0.0617994 0.424894 0.00136669 0.0559944 0.424827 0.00147516 0.0557692 0.424827 0.00265819 0.0567126 0.424894 0.00307098 0.0581315 0.424894 0.00246273 0.0607964 0.424827 0.00331471 0.059589 0.424894 -4.19898e-08 0.0619824 0.436825 0.0562959 0.0115309 0.436867 0.0561705 0.0114119 0.437009 0.0572643 0.0091268 0.436733 0.0542748 0.0125255 0.436729 0.0539047 0.0125498 0.436775 0.0539026 0.0123819 0.436792 0.0526641 0.01215 0.436741 0.0527982 0.0123784 0.436807 0.0514894 0.0115843 0.436849 0.05161 0.0114619 0.437044 0.0510565 0.0103679 0.436962 0.0517259 0.0113526 0.436933 0.0509018 0.0104253 0.436803 0.0551344 0.012122 0.436916 0.0550691 0.0119801 0.437064 0.0566972 0.0103071 0.436953 0.0568543 0.0103617 0.437272 0.0522512 0.0116059 0.437069 0.0527674 0.011915 0.437212 0.0511605 0.0103365 0.437305 0.0518359 0.0112686 0.437303 0.0511871 0.0103323 0.437508 0.0567637 0.00916551 0.437506 0.0567638 0.00918053 0.43742 0.0567714 0.00915954 0.437416 0.0567721 0.00915927 0.437324 0.0565648 0.0102739 0.437322 0.0559217 0.0112389 0.437414 0.0565547 0.0102768 0.437239 0.0545725 0.0120076 0.437227 0.0538973 0.0120954 0.437227 0.0535903 0.0120825 0.43724 0.0508971 0.00921189 0.437137 0.0508179 0.00920555 0.437127 0.0518055 0.0112849 0.436905 0.0527251 0.0120071 0.437052 0.0538984 0.0121272 0.437079 0.0550233 0.0118889 0.436889 0.0539003 0.0122276 0.437145 0.0559688 0.0112385 0.436979 0.0560509 0.0113046 0.437232 0.0565916 0.0102776 0.437316 0.0568017 0.00915227 0.437154 0.0569102 0.00914026 0.433777 0.0456733 -0.0347582 0.434083 0.046417 -0.0336741 0.433952 0.0462812 -0.0337942 0.434149 0.0472086 -0.0331486 0.434301 0.0476645 -0.0330021 0.434252 0.0483183 -0.0329051 0.434248 0.0494386 -0.0331063 0.434144 0.0503941 -0.0337204 0.434238 0.0503954 -0.0337343 0.43405 0.0510375 -0.0346661 0.433318 0.0517855 -0.0356638 0.433558 0.051508 -0.0343749 0.433866 0.0486699 -0.0323322 0.433757 0.0506173 -0.0334277 0.433747 0.0507562 -0.0332832 0.433861 0.0483253 -0.0325255 0.433787 0.0473127 -0.032495 0.433288 0.0452357 -0.0344738 0.43354 0.0458868 -0.0334231 0.433043 0.0451792 -0.035767 0.433428 0.0455607 -0.0346331 0.433232 0.0453993 -0.0358042 0.433406 0.0454672 -0.0358405 0.433319 0.0454054 -0.0345472 0.433572 0.0460771 -0.0335048 0.433762 0.0471007 -0.0327928 0.433865 0.0471715 -0.0329827 0.433963 0.0483257 -0.0327332 0.433858 0.0495619 -0.0327487 0.43396 0.04949 -0.0329427 0.433578 0.0513311 -0.0344546 0.433507 0.0456172 -0.0346737 0.43376 0.0462455 -0.0337124 0.433678 0.0462022 -0.0336505 0.434046 0.0494636 -0.0330195 0.433861 0.0504861 -0.0335797 0.433685 0.0511638 -0.0345459 0.433767 0.0511018 -0.0345875 0.433457 0.0514239 -0.0356964 0.433597 0.0456548 -0.0347092 0.433854 0.0462719 -0.0337609 0.43395 0.0471944 -0.033059 0.434049 0.0483241 -0.0328147 0.434043 0.0504076 -0.0336899 0.433946 0.0504384 -0.0336424 0.43369 0.0456727 -0.0347379 0.434047 0.0472067 -0.0331149 0.434148 0.0483215 -0.0328726 0.434145 0.0494464 -0.0330746 0.433861 0.05106 -0.0346224 0.433628 0.0513086 -0.0357311 0.433959 0.0510394 -0.0346489 0.434253 -0.0484529 -0.0329048 0.434237 -0.0495631 -0.0331577 0.433739 -0.050724 -0.0335338 0.433323 -0.0452971 -0.0343264 0.433643 -0.0512562 -0.0338984 0.433739 -0.0511573 -0.0347159 0.433925 -0.0505376 -0.0337391 0.434021 -0.050505 -0.0337856 0.433928 -0.0510918 -0.034775 0.433366 -0.0517723 -0.035416 0.433318 -0.0516014 -0.0358247 0.433552 -0.0513898 -0.0345946 0.433426 -0.0514264 -0.0358402 0.433657 -0.0512206 -0.0346774 0.433505 -0.0513589 -0.0358534 0.433831 -0.051114 -0.034749 0.433687 -0.0512821 -0.0358863 0.433842 -0.0505876 -0.0336786 0.434036 -0.049591 -0.0330705 0.434122 -0.05049 -0.0338162 0.43425 -0.0503315 -0.0336739 0.43385 -0.0496997 -0.0328053 0.433865 -0.0484738 -0.0325249 0.433952 -0.0496202 -0.0329949 0.434051 -0.048461 -0.0328133 0.434134 -0.0495718 -0.0331254 0.434149 -0.0484567 -0.0328716 0.433964 -0.0473212 -0.0330054 0.43388 -0.0473009 -0.032928 0.433966 -0.0484656 -0.0327317 0.433778 -0.0472381 -0.0327353 0.434162 -0.0473336 -0.0330964 0.433878 -0.0463692 -0.0336634 0.43406 -0.047332 -0.0330622 0.433784 -0.046344 -0.0336135 0.43372 -0.0457261 -0.0346108 0.433976 -0.046378 -0.0336974 0.433538 -0.0456716 -0.0345437 0.433458 -0.0456161 -0.0345004 0.433702 -0.0463026 -0.0335495 0.433598 -0.0461832 -0.0333981 0.433582 -0.0460509 -0.0332553 0.433523 -0.0454759 -0.0357214 0.433811 -0.0457261 -0.0346321 0.433627 -0.0457085 -0.0345811 0.433186 -0.04534 -0.0356438 0.433035 -0.0450075 -0.0356005 0.433351 -0.0454636 -0.0344073 0.437308 -0.051806 0.0112388 0.436853 -0.0515591 0.0114109 0.436878 -0.0508391 0.0107047 0.436938 -0.050875 0.0103601 0.436996 -0.0504653 0.009125 0.436749 -0.0525281 0.0122763 0.43673 -0.0534575 0.0125254 0.436729 -0.0538262 0.0125497 0.436748 -0.0549239 0.0123818 0.436862 -0.0561197 0.0114628 0.436821 -0.0562404 0.0115862 0.436948 -0.0568275 0.0104269 0.43691 -0.056991 0.0104939 0.437042 -0.0570729 0.00920145 0.4368 -0.0550662 0.0121503 0.436913 -0.0550044 0.012007 0.436888 -0.0538296 0.0122277 0.436775 -0.0538281 0.0123819 0.436794 -0.0525959 0.0121216 0.436966 -0.0516778 0.0113041 0.43705 -0.0510312 0.0103061 0.437239 -0.0545728 0.0120076 0.437077 -0.0549611 0.0119148 0.437253 -0.0549432 0.0118872 0.437312 -0.0558207 0.0113359 0.437227 -0.0565672 0.0103372 0.437319 -0.0565405 0.0103329 0.437415 -0.0567715 0.00922327 0.437386 -0.0564111 0.0105817 0.437421 -0.0510842 0.0100218 0.437492 -0.0509639 0.00919555 0.437308 -0.0511628 0.0102733 0.437071 -0.0527051 0.011889 0.437234 -0.0531553 0.0120076 0.43723 -0.0541356 0.0120827 0.43715 -0.0569105 0.00920689 0.437059 -0.0566719 0.010369 0.43714 -0.0559224 0.0112851 0.436975 -0.0560028 0.011353 0.437051 -0.0538304 0.0121272 0.436907 -0.0526604 0.0119801 0.437131 -0.0517591 0.0112382 0.437217 -0.0511361 0.0102769 0.429042 -0.0512903 0.0577455 0.429216 -0.0521175 0.0578149 0.428311 -0.0496851 0.0570931 0.428249 -0.0495809 0.0571993 0.429336 -0.0549218 0.0561874 0.429248 -0.0540697 0.0571074 0.429139 -0.0542 0.0572217 0.429043 -0.0530689 0.0577487 0.429389 -0.0529654 0.0576344 0.429499 -0.0534859 0.0573765 0.4293 -0.0529819 0.057637 0.42951 -0.053944 0.0570321 0.429074 -0.0518648 0.0578269 0.428986 -0.0518797 0.057852 0.429594 -0.0539007 0.0570609 0.429754 -0.0544593 0.0563639 0.428901 -0.0518934 0.0578952 0.429328 -0.0540155 0.0570674 0.429616 -0.0546331 0.0561028 0.429525 -0.0546837 0.0561108 0.429209 -0.0530051 0.0576563 0.429417 -0.0539731 0.0570423 0.429711 -0.0546014 0.0561039 0.428828 -0.0490467 0.0548025 0.428683 -0.0492065 0.0558766 0.428743 -0.0490657 0.0552717 0.428816 -0.0490449 0.0548614 0.428732 -0.0498268 0.0569016 0.428574 -0.0498188 0.0569312 0.428524 -0.0489415 0.0547425 0.428266 -0.0490135 0.0559906 0.428424 -0.0497699 0.0569978 0.42838 -0.0491269 0.0559527 0.428526 -0.0492 0.0559309 0.428617 -0.0489995 0.0547618 0.429526 -0.0551885 0.0549517 0.429629 -0.0550089 0.0549605 0.428713 -0.0519199 0.058113 0.428933 -0.0531444 0.057898 0.429362 -0.0552247 0.0559313 0.429503 -0.0553946 0.0549547 0.428489 -0.0507086 0.0578342 0.428841 -0.0507597 0.057575 0.428757 -0.0507636 0.0576012 0.428601 -0.0507499 0.0576961 0.428824 -0.0519051 0.0579553 0.429122 -0.0530345 0.0576937 0.429444 -0.0547517 0.0561283 0.428508 0.0489386 0.0548241 0.428431 0.0488613 0.0548095 0.429457 0.0547823 0.0560556 0.429262 0.0541259 0.0570518 0.429058 0.0531433 0.0577184 0.428728 0.0520052 0.058114 0.428947 0.0532227 0.0578661 0.429152 0.0542593 0.057163 0.42912 0.0543939 0.0572922 0.429349 0.0549543 0.0561105 0.429271 0.0549849 0.0564925 0.428211 0.0492841 0.0568245 0.428762 0.0499886 0.0570616 0.428808 0.0490443 0.0548993 0.429723 0.054631 0.0560349 0.429873 0.0547276 0.0557339 0.429816 0.0546175 0.0560441 0.429315 0.0530534 0.0576086 0.429177 0.0519273 0.0578201 0.429057 0.0513611 0.0577609 0.42909 0.0519426 0.057828 0.428939 0.0508215 0.057594 0.428856 0.050832 0.0576061 0.428795 0.0501524 0.0572005 0.428264 0.0490453 0.0560744 0.42832 0.0497463 0.0571576 0.429136 0.0531074 0.0576642 0.429537 0.0547137 0.0560397 0.429807 0.0548874 0.0549036 0.428377 0.0491572 0.0560322 0.428583 0.0498753 0.0569896 0.428433 0.0498285 0.0570588 0.428772 0.0508367 0.0576325 0.429002 0.0519581 0.0578529 0.429224 0.053077 0.0576274 0.42943 0.0540274 0.056989 0.429523 0.0539981 0.0569796 0.429629 0.0546628 0.0560329 0.428503 0.0507878 0.0578689 0.428451 0.0507327 0.0580233 0.428535 0.0511799 0.0581785 0.429015 0.0538744 0.0577214 0.428678 0.0492532 0.0560012 0.428523 0.0492292 0.056007 0.428601 0.0489967 0.054841 0.428616 0.0508255 0.0577286 0.428917 0.051973 0.0578959 0.42884 0.0519863 0.057956 0.429341 0.0540705 0.0570131 0.429722 0.054936 0.0548923 -0.140777 0.14095 -0.014662 -0.140777 0.142368 -0.0151503 -0.139626 0.141685 -0.012527 -0.137834 0.142269 -0.0108326 -0.139626 0.143104 -0.0130153 -0.135576 0.144062 -0.0102331 -0.133073 0.144191 -0.00985828 -0.0730732 0.144191 -0.00985828 -0.0730732 0.142772 -0.00936993 -0.0705702 0.144062 -0.0102331 -0.0705702 0.142643 -0.00974477 -0.0665202 0.143104 -0.0130153 -0.0665202 0.141685 -0.012527 -0.0653696 0.14095 -0.014662 -0.0653696 0.142368 -0.0151503 -0.0649732 0.139443 -0.0190379 -0.0649732 0.132965 -0.0378537 -0.0649732 0.130564 -0.0448269 -0.0653696 0.129749 -0.0471935 -0.0649732 0.131982 -0.0453152 -0.0683121 0.12843 -0.0510229 -0.0705702 0.128055 -0.0521107 -0.0730732 0.129345 -0.0529739 -0.0730732 0.127926 -0.0524856 -0.0816732 0.127926 -0.0524856 -0.100098 0.127926 -0.0524856 -0.135576 0.129474 -0.0525991 -0.137834 0.129848 -0.0515113 -0.139626 0.129013 -0.0493286 -0.141173 0.132965 -0.0378537 -0.141173 0.131982 -0.0453152 -0.141173 0.137734 -0.0240018 -0.0762954 0.13218 -0.0462764 -0.0831732 0.140114 -0.0232347 -0.0701232 0.13724 -0.0315789 -0.0654732 0.140114 -0.0232347 -0.0705123 0.13804 -0.029256 -0.0756165 0.134779 -0.0387279 -0.0827461 0.135146 -0.0376602 -0.0985982 0.134367 -0.0399231 -0.0780732 0.139829 -0.024062 -0.0845049 0.138762 -0.0271606 -0.101829 0.134584 -0.0392945 -0.0985982 0.130037 -0.0524985 -0.106112 0.131527 -0.0481704 -0.111548 0.134367 -0.0399231 -0.111548 0.130037 -0.0524985 -0.103073 0.130094 -0.052333 -0.101563 0.130215 -0.051981 -0.100399 0.130551 -0.0510057 -0.0998469 0.131025 -0.0496305 -0.102295 0.13218 -0.0462764 -0.103851 0.13218 -0.0462764 -0.115897 0.138552 -0.0277689 -0.109806 0.13421 -0.0403789 -0.114404 0.139308 -0.0255728 -0.140673 0.140114 -0.0232347 -0.128073 0.139829 -0.024062 -0.136023 0.13724 -0.0315789 -0.134505 0.135719 -0.0359972 -0.132746 0.135146 -0.0376602 -0.120512 0.136441 -0.0339017 -0.118448 0.140114 -0.0232347 -0.0669247 0.143481 -0.013456 -0.0658452 0.142791 -0.0154592 -0.0654732 0.142026 -0.0176798 -0.0654732 0.141334 -0.019689 -0.0797479 0.142727 -0.0156433 -0.0831732 0.141334 -0.019689 -0.0730732 0.144501 -0.0104938 -0.0802995 0.143201 -0.0142681 -0.077851 0.144356 -0.0109141 -0.0792283 0.144121 -0.0115976 -0.0707247 0.144379 -0.0108455 -0.0785836 0.142392 -0.0166186 -0.0719732 0.141334 -0.019689 -0.129073 0.14227 -0.0169706 -0.126399 0.142727 -0.0156433 -0.122973 0.141334 -0.019689 -0.125847 0.143201 -0.0142681 -0.133073 0.144501 -0.0104938 -0.135422 0.144379 -0.0108455 -0.132112 0.143704 -0.012808 -0.140301 0.142791 -0.0154592 -0.132299 0.143201 -0.0142681 -0.140673 0.142026 -0.0176798 -0.140673 0.141334 -0.019689 -0.128295 0.13218 -0.0462764 -0.131228 0.131944 -0.04696 -0.139222 0.131 -0.0497018 -0.132299 0.131025 -0.0496305 -0.129073 0.130094 -0.052333 -0.126034 0.131527 -0.0481704 -0.0654732 0.134367 -0.0399231 -0.0654732 0.132455 -0.045478 -0.0719732 0.134367 -0.0399231 -0.080112 0.131527 -0.0481704 -0.0831732 0.134367 -0.0399231 -0.077851 0.13218 -0.0462764 -0.0792283 0.131944 -0.04696 -0.0785836 0.130215 -0.051981 -0.0770732 0.130094 -0.052333 -0.0730732 0.12998 -0.052664 -0.0719732 0.130037 -0.0524985 -0.0738469 0.131025 -0.0496305 -0.0985982 0.140114 -0.0232347 -0.0719732 0.140114 -0.0232347 -0.0831732 0.130037 -0.0524985 -0.102295 0.144356 -0.0109141 -0.103851 0.144356 -0.0109141 -0.111548 0.144501 -0.0104938 -0.101563 0.142392 -0.0166186 -0.100399 0.142727 -0.0156433 -0.0985982 0.141334 -0.019689 -0.0985982 0.144501 -0.0104938 -0.122973 0.144501 -0.0104938 -0.111548 0.141334 -0.019689 -0.1063 0.143201 -0.0142681 -0.122973 0.134367 -0.0399231 -0.118448 0.134367 -0.0399231 -0.118448 0.130037 -0.0524985 -0.1063 0.131025 -0.0496305 -0.0831732 0.12998 -0.052664 -0.111548 0.12998 -0.052664 -0.118448 0.12998 -0.052664 -0.122973 0.12998 -0.052664 -0.133073 0.12998 -0.052664 -0.122973 0.130037 -0.0524985 -0.134193 0.130007 -0.0525856 -0.109806 0.140271 -0.0227789 -0.111548 0.140114 -0.0232347 -0.118448 0.141334 -0.019689 -0.122973 0.140114 -0.0232347 -0.0761982 0.128768 -0.0500419 -0.0761982 0.140944 -0.0146795 -0.0770732 0.140868 -0.0149012 -0.110048 0.142772 -0.00936993 -0.118448 0.142772 -0.00936993 -0.128198 0.140944 -0.0146795 -0.129073 0.140868 -0.0149012 -0.124473 0.139443 -0.0190379 -0.0649732 0.140135 -0.0170286 -0.0683121 0.142269 -0.0108326 -0.0734732 0.128309 -0.0513746 -0.0665202 0.129013 -0.0493286 -0.128198 0.128768 -0.0500419 -0.124473 0.128309 -0.0513746 -0.129948 0.128768 -0.0500419 -0.137834 0.12843 -0.0510229 -0.140777 0.129749 -0.0471935 -0.129948 0.129755 -0.047176 -0.141173 0.130564 -0.0448269 -0.130589 0.141153 -0.0140739 -0.141173 0.140135 -0.0170286 -0.135576 0.142643 -0.00974477 -0.130823 0.141438 -0.0132466 -0.133073 0.142772 -0.00936993 -0.129073 0.142007 -0.0115919 -0.124473 0.142772 -0.00936993 -0.127323 0.141438 -0.0132466 -0.127558 0.141153 -0.0140739 -0.107073 0.138019 -0.0231745 -0.111893 0.13319 -0.0372003 -0.118448 0.132965 -0.0378537 -0.103073 0.128692 -0.0502636 -0.100098 0.128309 -0.0513746 -0.103948 0.128768 -0.0500419 -0.102198 0.129755 -0.047176 -0.104589 0.129546 -0.0477816 -0.109607 0.13281 -0.0383015 -0.100098 0.132965 -0.0378537 -0.0802792 0.133376 -0.0366586 -0.103073 0.129831 -0.0469543 -0.102253 0.13319 -0.0372003 -0.0816732 0.137734 -0.0240018 -0.100098 0.137734 -0.0240018 -0.102253 0.137509 -0.0246552 -0.0844252 0.135714 -0.0298687 -0.0844252 0.134985 -0.0319868 -0.0988732 0.135349 -0.0309278 -0.0992745 0.134524 -0.0333236 -0.124473 0.137734 -0.0240018 -0.133659 0.136399 -0.0278785 -0.130279 0.133376 -0.0366586 -0.128073 0.133249 -0.0370263 -0.122487 0.134299 -0.0339771 -0.0780732 0.137449 -0.0248292 -0.0758672 0.137323 -0.025197 -0.0734732 0.137734 -0.0240018 -0.0724873 0.136399 -0.0278785 -0.0649732 0.137734 -0.0240018 -0.0717212 0.135714 -0.0298687 -0.0724873 0.134299 -0.0339771 -0.0739272 0.133741 -0.0355995 -0.141173 0.139443 -0.0190379 -0.118448 0.137734 -0.0240018 -0.118448 0.139443 -0.0190379 -0.124473 0.132965 -0.0378537 -0.101558 0.141722 -0.0124192 -0.110048 0.139443 -0.0190379 -0.103948 0.140944 -0.0146795 -0.104589 0.141153 -0.0140739 -0.113707 0.136919 -0.0263705 -0.104823 0.141438 -0.0132466 -0.103948 0.141931 -0.0118136 -0.102198 0.141931 -0.0118136 -0.100098 0.142772 -0.00936993 -0.0816732 0.142772 -0.00936993 -0.0734732 0.139443 -0.0190379 -0.0816732 0.139443 -0.0190379 -0.0755577 0.141722 -0.0124192 -0.0734732 0.142772 -0.00936993 -0.0753232 0.141438 -0.0132466 -0.0770732 0.128692 -0.0502636 -0.0779482 0.128768 -0.0500419 -0.0816732 0.128309 -0.0513746 -0.0755577 0.128976 -0.0494363 -0.0816732 0.132965 -0.0378537 -0.0734732 0.132965 -0.0378537 -0.0770732 0.129831 -0.0469543 -0.135576 0.128055 -0.0521107 -0.133073 0.127926 -0.0524856 -0.124473 0.127926 -0.0524856 -0.118448 0.128309 -0.0513746 -0.118448 0.127926 -0.0524856 -0.110048 0.128309 -0.0513746 -0.110048 0.127926 -0.0524856 -0.0734732 0.127926 -0.0524856 -0.100098 0.139443 -0.0190379 -0.129886 0.12923 -0.0502369 -0.130589 0.129449 -0.0495991 -0.130589 0.128976 -0.0494363 -0.130823 0.129261 -0.048609 -0.130709 0.129936 -0.048185 -0.130589 0.129546 -0.0477816 -0.129948 0.130227 -0.0473388 -0.129492 0.130287 -0.0471652 -0.129073 0.130304 -0.0471171 -0.129073 0.129831 -0.0469543 -0.128198 0.129755 -0.047176 -0.128198 0.130227 -0.0473388 -0.127558 0.129546 -0.0477816 -0.127323 0.129734 -0.0487717 -0.127323 0.129261 -0.048609 -0.127336 0.129665 -0.0489712 -0.127558 0.129449 -0.0495991 -0.127558 0.128976 -0.0494363 -0.127633 0.12941 -0.0497117 -0.128198 0.129241 -0.0502047 -0.12826 0.12923 -0.0502369 -0.129073 0.128692 -0.0502636 -0.126399 0.130551 -0.0510057 -0.125847 0.131025 -0.0496305 -0.127437 0.129936 -0.048185 -0.127558 0.130019 -0.0479444 -0.127913 0.13016 -0.0475332 -0.126918 0.131944 -0.04696 -0.128654 0.130287 -0.0471652 -0.129851 0.13218 -0.0462764 -0.130234 0.13016 -0.0475332 -0.130589 0.130019 -0.0479444 -0.132112 0.131527 -0.0481704 -0.130823 0.129734 -0.0487717 -0.13081 0.129665 -0.0489712 -0.131748 0.130551 -0.0510057 -0.130513 0.12941 -0.0497117 -0.129948 0.129241 -0.0502047 -0.130584 0.130215 -0.051981 -0.127563 0.130215 -0.051981 -0.129073 0.129164 -0.0504264 -0.103886 0.12923 -0.0502369 -0.104589 0.129449 -0.0495991 -0.10481 0.129665 -0.0489712 -0.104589 0.128976 -0.0494363 -0.104823 0.129261 -0.048609 -0.104823 0.129734 -0.0487717 -0.104709 0.129936 -0.048185 -0.104234 0.13016 -0.0475332 -0.103948 0.129755 -0.047176 -0.101558 0.129546 -0.0477816 -0.101558 0.130019 -0.0479444 -0.101437 0.129936 -0.048185 -0.101323 0.129734 -0.0487717 -0.101323 0.129261 -0.048609 -0.101336 0.129665 -0.0489712 -0.101558 0.128976 -0.0494363 -0.102198 0.128768 -0.0500419 -0.10226 0.12923 -0.0502369 -0.102198 0.129241 -0.0502047 -0.101633 0.12941 -0.0497117 -0.101558 0.129449 -0.0495991 -0.100034 0.131527 -0.0481704 -0.101913 0.13016 -0.0475332 -0.100918 0.131944 -0.04696 -0.102198 0.130227 -0.0473388 -0.102654 0.130287 -0.0471652 -0.103073 0.130304 -0.0471171 -0.103492 0.130287 -0.0471652 -0.103948 0.130227 -0.0473388 -0.105228 0.131944 -0.04696 -0.104589 0.130019 -0.0479444 -0.105748 0.130551 -0.0510057 -0.104513 0.12941 -0.0497117 -0.103948 0.129241 -0.0502047 -0.104584 0.130215 -0.051981 -0.103073 0.129164 -0.0504264 -0.0779482 0.129241 -0.0502047 -0.0785134 0.12941 -0.0497117 -0.0785887 0.129449 -0.0495991 -0.0785887 0.128976 -0.0494363 -0.0788104 0.129665 -0.0489712 -0.0788232 0.129261 -0.048609 -0.0785887 0.129546 -0.0477816 -0.0785887 0.130019 -0.0479444 -0.0779482 0.129755 -0.047176 -0.0779482 0.130227 -0.0473388 -0.077492 0.130287 -0.0471652 -0.0766544 0.130287 -0.0471652 -0.0761982 0.130227 -0.0473388 -0.0761982 0.129755 -0.047176 -0.0759127 0.13016 -0.0475332 -0.0755577 0.129546 -0.0477816 -0.0754369 0.129936 -0.048185 -0.0753232 0.129261 -0.048609 -0.0753232 0.129734 -0.0487717 -0.0762599 0.12923 -0.0502369 -0.0778865 0.12923 -0.0502369 -0.0761982 0.129241 -0.0502047 -0.075633 0.12941 -0.0497117 -0.0755577 0.129449 -0.0495991 -0.0743985 0.130551 -0.0510057 -0.075336 0.129665 -0.0489712 -0.0740344 0.131527 -0.0481704 -0.0755577 0.130019 -0.0479444 -0.0749181 0.131944 -0.04696 -0.0770732 0.130304 -0.0471171 -0.0782337 0.13016 -0.0475332 -0.0787095 0.129936 -0.048185 -0.0802995 0.131025 -0.0496305 -0.0788232 0.129734 -0.0487717 -0.0797479 0.130551 -0.0510057 -0.0770732 0.129164 -0.0504264 -0.0755628 0.130215 -0.051981 -0.129948 0.140944 -0.0146795 -0.130513 0.141587 -0.0143493 -0.13081 0.141842 -0.0136088 -0.130823 0.14191 -0.0134093 -0.130589 0.141722 -0.0124192 -0.129948 0.142404 -0.0119764 -0.129948 0.141931 -0.0118136 -0.129492 0.142463 -0.0118028 -0.128198 0.141931 -0.0118136 -0.127913 0.142337 -0.0121708 -0.127558 0.142195 -0.012582 -0.127558 0.141722 -0.0124192 -0.127437 0.142112 -0.0128226 -0.129886 0.141406 -0.0148745 -0.128198 0.141417 -0.0148423 -0.127633 0.141587 -0.0143493 -0.127558 0.141625 -0.0142367 -0.127336 0.141842 -0.0136088 -0.127323 0.14191 -0.0134093 -0.126034 0.143704 -0.012808 -0.126918 0.144121 -0.0115976 -0.128198 0.142404 -0.0119764 -0.128654 0.142463 -0.0118028 -0.129073 0.14248 -0.0117547 -0.128295 0.144356 -0.0109141 -0.129851 0.144356 -0.0109141 -0.131228 0.144121 -0.0115976 -0.130234 0.142337 -0.0121708 -0.130589 0.142195 -0.012582 -0.130709 0.142112 -0.0128226 -0.130589 0.141625 -0.0142367 -0.131748 0.142727 -0.0156433 -0.130584 0.142392 -0.0166186 -0.129948 0.141417 -0.0148423 -0.129073 0.141341 -0.015064 -0.12826 0.141406 -0.0148745 -0.127563 0.142392 -0.0166186 -0.104589 0.141625 -0.0142367 -0.10481 0.141842 -0.0136088 -0.104589 0.141722 -0.0124192 -0.103948 0.142404 -0.0119764 -0.103073 0.142007 -0.0115919 -0.102654 0.142463 -0.0118028 -0.102198 0.142404 -0.0119764 -0.101558 0.142195 -0.012582 -0.101437 0.142112 -0.0128226 -0.101323 0.141438 -0.0132466 -0.101558 0.141625 -0.0142367 -0.101558 0.141153 -0.0140739 -0.101633 0.141587 -0.0143493 -0.102198 0.140944 -0.0146795 -0.10226 0.141406 -0.0148745 -0.103073 0.140868 -0.0149012 -0.103073 0.141341 -0.015064 -0.103886 0.141406 -0.0148745 -0.0998469 0.143201 -0.0142681 -0.101336 0.141842 -0.0136088 -0.101323 0.14191 -0.0134093 -0.100034 0.143704 -0.012808 -0.101913 0.142337 -0.0121708 -0.100918 0.144121 -0.0115976 -0.103073 0.14248 -0.0117547 -0.103492 0.142463 -0.0118028 -0.105228 0.144121 -0.0115976 -0.104234 0.142337 -0.0121708 -0.104589 0.142195 -0.012582 -0.106112 0.143704 -0.012808 -0.104709 0.142112 -0.0128226 -0.104823 0.14191 -0.0134093 -0.105748 0.142727 -0.0156433 -0.104513 0.141587 -0.0143493 -0.103948 0.141417 -0.0148423 -0.104584 0.142392 -0.0166186 -0.103073 0.14227 -0.0169706 -0.102198 0.141417 -0.0148423 -0.0779482 0.140944 -0.0146795 -0.0779482 0.141417 -0.0148423 -0.0785134 0.141587 -0.0143493 -0.0785887 0.141153 -0.0140739 -0.0788232 0.141438 -0.0132466 -0.0787095 0.142112 -0.0128226 -0.0785887 0.141722 -0.0124192 -0.0785887 0.142195 -0.012582 -0.0779482 0.142404 -0.0119764 -0.0779482 0.141931 -0.0118136 -0.0770732 0.142007 -0.0115919 -0.077492 0.142463 -0.0118028 -0.0770732 0.14248 -0.0117547 -0.0761982 0.141931 -0.0118136 -0.0754369 0.142112 -0.0128226 -0.0755577 0.141625 -0.0142367 -0.0755577 0.141153 -0.0140739 -0.075633 0.141587 -0.0143493 -0.0761982 0.141417 -0.0148423 -0.0743985 0.142727 -0.0156433 -0.075336 0.141842 -0.0136088 -0.0738469 0.143201 -0.0142681 -0.0753232 0.14191 -0.0134093 -0.0740344 0.143704 -0.012808 -0.0755577 0.142195 -0.012582 -0.0759127 0.142337 -0.0121708 -0.0749181 0.144121 -0.0115976 -0.0761982 0.142404 -0.0119764 -0.0766544 0.142463 -0.0118028 -0.0762954 0.144356 -0.0109141 -0.0782337 0.142337 -0.0121708 -0.080112 0.143704 -0.012808 -0.0788232 0.14191 -0.0134093 -0.0788104 0.141842 -0.0136088 -0.0785887 0.141625 -0.0142367 -0.0770732 0.14227 -0.0169706 -0.0778865 0.141406 -0.0148745 -0.0770732 0.141341 -0.015064 -0.0755628 0.142392 -0.0166186 -0.0762599 0.141406 -0.0148745 -0.109607 0.138361 -0.0237168 -0.109607 0.137888 -0.023554 -0.111506 0.138068 -0.0245681 -0.111893 0.137509 -0.0246552 -0.111893 0.137982 -0.024818 -0.114532 0.136931 -0.0278697 -0.114872 0.136174 -0.0285319 -0.11519 0.136202 -0.0299871 -0.115273 0.135349 -0.0309278 -0.11519 0.135442 -0.0321939 -0.113707 0.13378 -0.035485 -0.111893 0.133662 -0.0373631 -0.11327 0.134074 -0.0361678 -0.113707 0.134253 -0.0356478 -0.114872 0.134524 -0.0333236 -0.114532 0.134713 -0.0343114 -0.104763 0.133261 -0.0385297 -0.107073 0.13268 -0.038681 -0.104539 0.133283 -0.0384643 -0.104539 0.13281 -0.0383015 -0.10264 0.133576 -0.037613 -0.102253 0.133662 -0.0373631 -0.100876 0.134074 -0.0361678 -0.100439 0.134253 -0.0356478 -0.100439 0.13378 -0.035485 -0.0996142 0.134713 -0.0343114 -0.0992745 0.134997 -0.0334864 -0.0992745 0.136647 -0.0286947 -0.102253 0.137982 -0.024818 -0.100876 0.13757 -0.0260132 -0.100439 0.136919 -0.0263705 -0.0992745 0.136174 -0.0285319 -0.100439 0.137391 -0.0265333 -0.0996142 0.136931 -0.0278697 -0.109383 0.138384 -0.0236513 -0.104763 0.138384 -0.0236513 -0.104539 0.137888 -0.023554 -0.104539 0.138361 -0.0237168 -0.130279 0.137323 -0.025197 -0.131864 0.137521 -0.0261567 -0.132219 0.137431 -0.0264187 -0.132219 0.136958 -0.026256 -0.133659 0.136872 -0.0280412 -0.134208 0.136471 -0.029206 -0.134425 0.135714 -0.0298687 -0.134425 0.136187 -0.0300315 -0.133659 0.134299 -0.0339771 -0.133291 0.134588 -0.0346752 -0.134425 0.134985 -0.0319868 -0.133659 0.134772 -0.0341398 -0.134208 0.135173 -0.0329751 -0.134425 0.135457 -0.0321495 -0.131864 0.134123 -0.0360244 -0.132219 0.133741 -0.0355995 -0.128073 0.133722 -0.0371891 -0.12608 0.133825 -0.0368906 -0.125867 0.133376 -0.0366586 -0.124282 0.134123 -0.0360244 -0.123927 0.133741 -0.0355995 -0.122855 0.134588 -0.0346752 -0.122487 0.134772 -0.0341398 -0.121939 0.135173 -0.0329751 -0.121721 0.134985 -0.0319868 -0.123927 0.136958 -0.026256 -0.123927 0.137431 -0.0264187 -0.122487 0.136399 -0.0278785 -0.121721 0.135714 -0.0298687 -0.128073 0.137449 -0.0248292 -0.125867 0.137323 -0.025197 -0.124282 0.137521 -0.0261567 -0.0802792 0.137323 -0.025197 -0.0800664 0.137819 -0.0252904 -0.0822192 0.136958 -0.026256 -0.0822192 0.137431 -0.0264187 -0.0832914 0.137056 -0.0275059 -0.0836591 0.136872 -0.0280412 -0.0836591 0.136399 -0.0278785 -0.0822192 0.133741 -0.0355995 -0.0836591 0.134299 -0.0339771 -0.0836591 0.134772 -0.0341398 -0.0842075 0.135173 -0.0329751 -0.0802792 0.133849 -0.0368213 -0.0780732 0.133249 -0.0370263 -0.07608 0.133825 -0.0368906 -0.0758672 0.133849 -0.0368213 -0.0758672 0.133376 -0.0366586 -0.0739272 0.134214 -0.0357623 -0.072855 0.134588 -0.0346752 -0.0724873 0.134772 -0.0341398 -0.0717212 0.134985 -0.0319868 -0.0739272 0.136958 -0.026256 -0.0724873 0.136872 -0.0280412 -0.0717212 0.136187 -0.0300315 -0.0758672 0.137795 -0.0253597 -0.123927 0.134214 -0.0357623 -0.1234 0.135146 -0.0376602 -0.121642 0.135719 -0.0359972 -0.121721 0.135457 -0.0321495 -0.120123 0.13724 -0.0315789 -0.121623 0.135822 -0.0310905 -0.120512 0.13804 -0.029256 -0.121721 0.136187 -0.0300315 -0.121939 0.136471 -0.029206 -0.121642 0.138762 -0.0271606 -0.122487 0.136872 -0.0280412 -0.122855 0.137056 -0.0275059 -0.1234 0.139334 -0.0254976 -0.125617 0.139702 -0.0244299 -0.125867 0.137795 -0.0253597 -0.12608 0.137819 -0.0252904 -0.13053 0.139702 -0.0244299 -0.128073 0.137922 -0.0249919 -0.130066 0.137819 -0.0252904 -0.130279 0.137795 -0.0253597 -0.132746 0.139334 -0.0254976 -0.133291 0.137056 -0.0275059 -0.134505 0.138762 -0.0271606 -0.135634 0.13804 -0.029256 -0.134523 0.135822 -0.0310905 -0.135634 0.136441 -0.0339017 -0.132219 0.134214 -0.0357623 -0.13053 0.134779 -0.0387279 -0.130279 0.133849 -0.0368213 -0.130066 0.133825 -0.0368906 -0.128073 0.134652 -0.0390958 -0.125617 0.134779 -0.0387279 -0.125867 0.133849 -0.0368213 -0.10434 0.13421 -0.0403789 -0.0997424 0.135172 -0.037585 -0.0982498 0.135929 -0.0353889 -0.0974719 0.136791 -0.0328841 -0.0989567 0.135442 -0.0321939 -0.0988732 0.135822 -0.0310905 -0.0974719 0.13769 -0.0302736 -0.0989567 0.136202 -0.0299871 -0.0982498 0.138552 -0.0277689 -0.0997424 0.139308 -0.0255728 -0.101829 0.139897 -0.0238633 -0.10264 0.138068 -0.0245681 -0.10434 0.140271 -0.0227789 -0.107073 0.140398 -0.0224074 -0.107073 0.138492 -0.0233373 -0.112317 0.139897 -0.0238633 -0.11327 0.13757 -0.0260132 -0.113707 0.137391 -0.0265333 -0.114872 0.136647 -0.0286947 -0.116674 0.13769 -0.0302736 -0.115273 0.135822 -0.0310905 -0.116674 0.136791 -0.0328841 -0.115897 0.135929 -0.0353889 -0.114872 0.134997 -0.0334864 -0.114404 0.135172 -0.037585 -0.112317 0.134584 -0.0392945 -0.110902 0.134339 -0.0400059 -0.111506 0.133576 -0.037613 -0.109607 0.133283 -0.0384643 -0.109383 0.133261 -0.0385297 -0.107073 0.134082 -0.0407504 -0.107073 0.133152 -0.0388438 -0.074282 0.134123 -0.0360244 -0.0734003 0.135146 -0.0376602 -0.0716415 0.135719 -0.0359972 -0.0719389 0.135173 -0.0329751 -0.0717212 0.135457 -0.0321495 -0.0705123 0.136441 -0.0339017 -0.0716232 0.135822 -0.0310905 -0.0719389 0.136471 -0.029206 -0.0716415 0.138762 -0.0271606 -0.072855 0.137056 -0.0275059 -0.0739272 0.137431 -0.0264187 -0.0734003 0.139334 -0.0254976 -0.0756165 0.139702 -0.0244299 -0.074282 0.137521 -0.0261567 -0.07608 0.137819 -0.0252904 -0.0780732 0.137922 -0.0249919 -0.0805299 0.139702 -0.0244299 -0.0802792 0.137795 -0.0253597 -0.0818644 0.137521 -0.0261567 -0.0827461 0.139334 -0.0254976 -0.0842075 0.136471 -0.029206 -0.0844252 0.136187 -0.0300315 -0.0856341 0.13804 -0.029256 -0.0860232 0.13724 -0.0315789 -0.0845232 0.135822 -0.0310905 -0.0856341 0.136441 -0.0339017 -0.0844252 0.135457 -0.0321495 -0.0845049 0.135719 -0.0359972 -0.0832914 0.134588 -0.0346752 -0.0822192 0.134214 -0.0357623 -0.0818644 0.134123 -0.0360244 -0.0805299 0.134779 -0.0387279 -0.0780732 0.134652 -0.0390958 -0.0800664 0.133825 -0.0368906 -0.0780732 0.133722 -0.0371891 -0.118448 0.144501 -0.0104938 -0.0831732 0.144501 -0.0104938 -0.139222 0.143481 -0.013456 -0.137834 0.143687 -0.011321 -0.13754 0.144028 -0.0118662 -0.0683121 0.143687 -0.011321 -0.068606 0.144028 -0.0118662 -0.0649732 0.141554 -0.017517 -0.141173 0.141554 -0.017517 -0.140673 0.134367 -0.0399231 -0.133073 0.129345 -0.0529739 -0.135422 0.130101 -0.0523123 -0.13754 0.130453 -0.0512916 -0.139626 0.130432 -0.0498169 -0.140777 0.131167 -0.0476819 -0.140301 0.13169 -0.0476986 -0.140673 0.132455 -0.045478 -0.0653696 0.131167 -0.0476819 -0.0665202 0.130432 -0.0498169 -0.0658452 0.13169 -0.0476986 -0.0669247 0.131 -0.0497018 -0.0683121 0.129848 -0.0515113 -0.0705702 0.129474 -0.0525991 -0.068606 0.130453 -0.0512916 -0.0707247 0.130101 -0.0523123 -0.0985982 0.12998 -0.052664 -0.238673 -0.0617141 0.0275474 -0.238673 -0.0671836 0.0286003 -0.228673 -0.0690154 0.0287186 -0.238673 -0.0690154 0.0287186 -0.228673 -0.083341 0.025546 -0.238673 -0.0943662 0.0158645 -0.228673 -0.0943662 0.0158645 -0.228673 -0.0993636 0.00206901 -0.238673 -0.0991459 -0.00532244 -0.228673 -0.0970968 -0.0124275 -0.238673 -0.0933452 -0.0187998 -0.238673 -0.0746722 -0.0298926 -0.228673 -0.0746722 -0.0298926 -0.228673 -0.0672816 -0.0301395 -0.238673 -0.0490516 -0.0215354 -0.228673 -0.0479102 -0.0203172 -0.238673 -0.0437418 -0.0142094 -0.228673 -0.0437418 -0.0142094 -0.228673 -0.0412232 -0.00725684 -0.228673 -0.0405128 0.000103622 -0.228673 -0.0416552 0.0074095 -0.228673 -0.0445786 0.0142018 -0.190673 -0.041624 -0.0354843 -0.190673 -0.0419835 -0.0350598 -0.190673 -0.0424916 -0.0348333 -0.190673 -0.0430477 -0.0348497 -0.190673 -0.0414843 -0.0360228 -0.185973 -0.0424916 -0.0348333 -0.190673 -0.0435416 -0.0351057 -0.185973 -0.0435416 -0.0351057 -0.190673 -0.0438755 -0.0355507 -0.190673 -0.0439832 -0.0360964 -0.185973 -0.0674374 -0.0453088 -0.190673 -0.0674374 -0.0453088 -0.190673 -0.068094 -0.0442452 -0.185973 -0.0679366 -0.0443458 -0.185973 -0.0684447 -0.0441193 -0.190673 -0.0684447 -0.0441193 -0.190673 -0.0693434 -0.044282 -0.190673 -0.0694946 -0.0443917 -0.190673 -0.0699363 -0.0453824 -0.190673 -0.0676232 -0.044689 -0.190673 -0.0679366 -0.0443458 -0.191424 -0.0686869 -0.0453456 -0.190673 -0.0697873 -0.0447528 -0.190673 -0.0687236 -0.0440962 -0.190673 -0.0690008 -0.0441357 -0.185973 -0.093892 -0.0375666 -0.185973 -0.0940318 -0.0370281 -0.190673 -0.093892 -0.0375666 -0.190673 -0.0940778 -0.0369468 -0.190673 -0.0943912 -0.0366035 -0.185973 -0.0954554 -0.0363934 -0.190673 -0.0954554 -0.0363934 -0.190673 -0.096242 -0.0370105 -0.190673 -0.0945487 -0.0365029 -0.190673 -0.0948994 -0.036377 -0.190673 -0.0951783 -0.0363539 -0.190673 -0.0957981 -0.0365397 -0.190673 -0.0959493 -0.0366494 -0.191424 -0.0951415 -0.0376034 -0.190673 -0.110929 -0.0151335 -0.190673 -0.1114 -0.0146896 -0.190673 -0.11265 -0.0147264 -0.190673 -0.113093 -0.0151972 -0.190673 -0.11203 -0.0145406 -0.190673 -0.112054 0.0127621 -0.190673 -0.112562 0.0129886 -0.185973 -0.112562 0.0129886 -0.190673 -0.113118 0.0129722 -0.190673 -0.111695 0.0123376 -0.190673 -0.113946 0.0122712 -0.190673 -0.113612 0.0127162 -0.185973 -0.096516 0.0355295 -0.190673 -0.0962026 0.0351863 -0.190673 -0.0966734 0.0356301 -0.190673 -0.0970241 0.035756 -0.185973 -0.0970241 0.035756 -0.185973 -0.0975802 0.0357396 -0.190673 -0.0980741 0.0354836 -0.185973 -0.0985158 0.0344929 -0.190673 -0.0983668 0.0351225 -0.190673 -0.0985158 0.0344929 -0.190673 -0.096516 0.0355295 -0.190673 -0.0973031 0.0357791 -0.190673 -0.0979229 0.0355933 -0.190673 -0.0975802 0.0357396 -0.191424 -0.0972663 0.0345297 -0.190673 -0.0700638 0.0438525 -0.190673 -0.0702035 0.044391 -0.185973 -0.0700638 0.0438525 -0.185973 -0.0702035 0.044391 -0.190673 -0.070563 0.0448155 -0.190673 -0.0710711 0.045042 -0.190673 -0.0716271 0.0450256 -0.185973 -0.0716271 0.0450256 -0.190673 -0.072121 0.0447696 -0.185973 -0.072121 0.0447696 -0.190673 -0.0724549 0.0443247 -0.190673 -0.0725627 0.0437789 -0.185973 -0.0724549 0.0443247 -0.191424 -0.0713132 0.0438157 -0.190673 -0.0437488 0.0366487 -0.185973 -0.0437949 0.03673 -0.185973 -0.0442657 0.0371739 -0.190673 -0.0442657 0.0371739 -0.190673 -0.0446164 0.0372997 -0.190673 -0.0448954 0.0373229 -0.190673 -0.0451725 0.0372834 -0.190673 -0.0456664 0.0370273 -0.190673 -0.0437949 0.03673 -0.190673 -0.0441083 0.0370732 -0.191424 -0.0448586 0.0360734 -0.190673 -0.045959 0.0366663 -0.190673 -0.0460003 0.0365824 -0.190673 -0.0455152 0.0371371 -0.185973 -0.0267577 0.0142969 -0.185973 -0.0268974 0.0148354 -0.190673 -0.0269435 0.0149167 -0.190673 -0.0272569 0.0152599 -0.190673 -0.027765 0.0154865 -0.190673 -0.0280439 0.0155096 -0.185973 -0.028321 0.0154701 -0.190673 -0.0286637 0.0153238 -0.185973 -0.0288149 0.0152141 -0.185973 -0.0291488 0.0147691 -0.190673 -0.0267577 0.0142969 -0.190673 -0.0274143 0.0153606 -0.190673 -0.028321 0.0154701 -0.190673 -0.0291076 0.014853 -0.190673 -0.0288149 0.0152141 -0.191424 -0.0280071 0.0142601 -0.185973 -0.0259461 -0.0132554 -0.190673 -0.0269534 -0.0120659 -0.185973 -0.0275094 -0.0120823 -0.190673 -0.0280033 -0.0123383 -0.190673 -0.028296 -0.0126994 -0.190673 -0.0264453 -0.0122924 -0.190673 -0.0266027 -0.0121918 -0.190673 -0.0272323 -0.0120428 -0.190673 -0.0275094 -0.0120823 -0.191424 -0.0271955 -0.0132922 -0.190673 -0.028445 -0.013329 -0.190673 -0.0278521 -0.0122286 -0.190673 -0.0261319 -0.0126356 -0.229755 -0.136604 -0.0131747 -0.229782 -0.136542 -0.0131029 -0.229763 -0.136579 -0.0131878 -0.232755 -0.128383 -0.0122837 -0.231382 -0.132814 -0.00842854 -0.229776 -0.1336 -0.0239483 -0.230964 -0.130574 -0.0227174 -0.232755 -0.12569 -0.021736 -0.231739 -0.129106 -0.0204568 -0.231907 -0.129044 -0.0191472 -0.232755 -0.127232 -0.0170655 -0.231768 -0.130077 -0.0169515 -0.231118 -0.132214 -0.0158054 -0.230658 -0.133513 -0.0158054 -0.230491 -0.133961 -0.0159108 -0.229776 -0.135865 -0.0163917 -0.229744 -0.136498 -0.0138849 -0.229744 -0.135968 -0.0163317 -0.231739 -0.111342 -0.0473718 -0.232755 -0.108997 -0.0457141 -0.231706 -0.111295 -0.0475315 -0.23191 -0.112844 -0.0453432 -0.231768 -0.113935 -0.0448216 -0.231498 -0.115135 -0.0446629 -0.230658 -0.117484 -0.0455469 -0.229784 -0.119161 -0.0472682 -0.229776 -0.119228 -0.0472308 -0.229744 -0.119347 -0.0472303 -0.229749 -0.113522 -0.0527074 -0.229764 -0.113539 -0.0526426 -0.229784 -0.113529 -0.052578 -0.232755 -0.101067 -0.0515198 -0.230964 -0.111483 -0.0500635 -0.232755 -0.105152 -0.048781 -0.231409 -0.111168 -0.048724 -0.23191 -0.0848146 -0.0607926 -0.229807 -0.0892962 -0.06556 -0.229776 -0.0893996 -0.0656194 -0.230491 -0.0888636 -0.0637294 -0.229776 -0.0817227 -0.0674359 -0.229749 -0.0817203 -0.0675097 -0.229744 -0.0816567 -0.0675353 -0.229744 -0.073606 -0.0684491 -0.230491 -0.0813548 -0.0655062 -0.229764 -0.0817672 -0.0674618 -0.231409 -0.081673 -0.0628826 -0.230964 -0.0812759 -0.0642001 -0.231739 -0.0824997 -0.0617985 -0.232755 -0.0780622 -0.0597243 -0.232755 -0.0829035 -0.0588571 -0.231907 -0.0836024 -0.0610895 -0.232755 -0.0584814 -0.0591475 -0.229807 -0.0543135 -0.0665272 -0.229776 -0.0543733 -0.0666303 -0.229764 -0.0543274 -0.0666536 -0.229776 -0.0468167 -0.064365 -0.232755 -0.0445018 -0.0545333 -0.231907 -0.0516178 -0.0598087 -0.232755 -0.0536995 -0.0579969 -0.23191 -0.052816 -0.0601577 -0.23189 -0.0530609 -0.0602853 -0.230658 -0.0252181 -0.0482487 -0.229776 -0.0235342 -0.0499926 -0.229807 -0.023534 -0.0498734 -0.229784 -0.0234968 -0.049926 -0.229776 -0.0181227 -0.0442526 -0.229744 -0.0180036 -0.0442451 -0.229749 -0.0180576 -0.0442874 -0.229807 -0.0182416 -0.0442598 -0.23136 -0.0218739 -0.0419449 -0.231409 -0.0220411 -0.0419329 -0.232755 -0.0250509 -0.0397621 -0.231808 -0.023776 -0.0422501 -0.232755 -0.0284248 -0.0433407 -0.231498 -0.0261021 -0.0459004 -0.231928 -0.0250428 -0.0431399 -0.23191 -0.0254219 -0.0436086 -0.229749 -0.00325533 -0.0124853 -0.229784 -0.00336418 -0.0125556 -0.229776 -0.00332911 -0.0124876 -0.231409 -0.00788239 -0.0124379 -0.231481 -0.00810442 -0.0125611 -0.232755 -0.0110407 -0.00882717 -0.231808 -0.00922625 -0.0135801 -0.232755 -0.0119079 -0.0136685 -0.232755 -0.0131719 -0.0184216 -0.230658 -0.00747588 -0.0194961 -0.229784 -0.00514653 -0.020088 -0.229744 -0.00527219 -0.020876 -0.229807 -0.00520503 -0.0200611 -0.229776 -0.00514564 -0.0201645 -0.229764 -0.00510253 -0.0201364 -0.232755 -0.0105763 -0.00393081 -0.231382 -0.00674732 0.00109824 -0.231316 -0.00673987 -0.00580417 -0.229763 -0.00280543 -0.00924732 -0.229747 -0.00276455 -0.00927974 -0.230209 -0.00395556 -0.00856521 -0.229755 -0.00278069 -0.00923273 -0.229744 -0.00829793 -0.0288185 -0.229744 -0.0126299 -0.0368595 -0.229744 -0.0312731 -0.0563921 -0.232755 -0.0401487 -0.0522441 -0.230491 -0.0474629 -0.0625099 -0.231498 -0.054551 -0.0618024 -0.232755 -0.0633419 -0.0598993 -0.229744 -0.0624163 -0.0681195 -0.229744 -0.063444 -0.0682273 -0.232755 -0.0731659 -0.0601887 -0.232755 -0.0922892 -0.055941 -0.232755 -0.0967695 -0.0539119 -0.229744 -0.0953876 -0.063611 -0.230491 -0.112204 -0.0511551 -0.229807 -0.113495 -0.0525234 -0.229776 -0.113488 -0.0526424 -0.232755 -0.115864 -0.0386824 -0.232755 -0.118838 -0.0347655 -0.232755 -0.121479 -0.0306163 -0.229744 -0.128635 -0.0347659 -0.232755 -0.123768 -0.0262633 -0.229744 -0.133432 -0.0246512 -0.233273 -0.126126 -0.00241824 -0.230673 -0.122933 0.0179683 -0.230673 -0.118589 0.0273757 -0.233273 -0.118589 0.0273757 -0.230673 -0.112591 0.0358249 -0.230673 -0.105143 0.043028 -0.233273 -0.105143 0.043028 -0.230673 -0.0964973 0.0487397 -0.230673 -0.0664676 0.0552738 -0.233273 -0.0768249 0.0549687 -0.233273 -0.0664676 0.0552738 -0.233273 -0.0296365 0.0382684 -0.230673 -0.0231514 0.030187 -0.233273 -0.0231514 0.030187 -0.233273 -0.0182617 0.0210516 -0.230673 -0.0182617 0.0210516 -0.233273 -0.0151338 0.0111732 -0.230673 -0.0151338 0.0111732 -0.236073 -0.125474 0.00792297 -0.236673 -0.126126 -0.00241824 -0.236073 -0.118589 0.0273757 -0.236673 -0.118589 0.0273757 -0.236073 -0.112591 0.0358249 -0.236673 -0.112591 0.0358249 -0.236073 -0.0964973 0.0487397 -0.236673 -0.105143 0.043028 -0.236673 -0.0964973 0.0487397 -0.236073 -0.0869497 0.0527657 -0.236073 -0.0664676 0.0552738 -0.236073 -0.0464626 0.0502136 -0.236673 -0.0296365 0.0382684 -0.236073 -0.0296365 0.0382684 -0.236073 -0.0231514 0.030187 -0.236073 -0.0182617 0.0210516 -0.230473 -0.11618 -0.00212528 -0.228873 -0.115558 0.00691013 -0.228873 -0.113185 0.0156506 -0.230473 -0.109153 0.0237602 -0.228873 -0.109153 0.0237602 -0.230473 -0.103616 0.0309273 -0.228873 -0.0967873 0.0368765 -0.230473 -0.0889291 0.0413792 -0.230473 -0.0803435 0.0442623 -0.228873 -0.0623249 0.044793 -0.230473 -0.0623249 0.044793 -0.228873 -0.0535845 0.0424203 -0.230473 -0.0535845 0.0424203 -0.228873 -0.0454749 0.038388 -0.230473 -0.0454749 0.038388 -0.228873 -0.0383078 0.0328511 -0.230473 -0.0383078 0.0328511 -0.228873 -0.0323585 0.0260223 -0.228873 -0.0278559 0.0181641 -0.228873 -0.0249728 0.00957846 -0.233695 -0.128825 -0.00249774 -0.233695 -0.128481 -0.00734951 -0.233695 -0.127737 -0.0121563 -0.233695 -0.126599 -0.0168853 -0.237673 -0.120077 -0.0316778 -0.233695 -0.120077 -0.0316778 -0.233695 -0.12091 -0.0302863 -0.237673 -0.124684 -0.0225124 -0.233695 -0.123174 -0.0259813 -0.233695 -0.124684 -0.0225124 -0.233695 -0.113948 -0.039904 -0.233695 -0.115357 -0.0382631 -0.233695 -0.118298 -0.0343895 -0.233695 -0.0979117 -0.0525749 -0.233695 -0.100723 -0.0509586 -0.233695 -0.106484 -0.0469409 -0.237673 -0.0884909 -0.0566345 -0.237673 -0.0785084 -0.0589967 -0.233695 -0.0827609 -0.0582148 -0.233695 -0.0884909 -0.0566345 -0.233695 -0.0731309 -0.0595316 -0.237673 -0.0580788 -0.0583949 -0.237673 -0.0682673 -0.0595895 -0.233695 -0.0482526 -0.0554493 -0.233695 -0.0492609 -0.0558396 -0.233695 -0.0447837 -0.0539388 -0.233695 -0.0404788 -0.0516749 -0.233695 -0.0325019 -0.0461215 -0.233695 -0.0363755 -0.0490631 -0.237673 -0.0390872 -0.0508421 -0.237673 -0.030861 -0.0447133 -0.237673 -0.0181902 -0.0286766 -0.233695 -0.022515 -0.0355283 -0.237673 -0.0141305 -0.0192559 -0.233695 -0.0154341 -0.0228077 -0.237673 -0.0117683 -0.00927329 -0.233695 -0.0112334 -0.00389581 -0.233695 -0.0116926 -0.00873803 -0.233695 -0.0117683 -0.00927329 -0.236873 -0.127044 0.00756986 -0.237673 -0.127625 -0.00246241 -0.236873 -0.12473 0.0173489 -0.237673 -0.127044 0.00756986 -0.236873 -0.120753 0.0265775 -0.236873 -0.115234 0.0349754 -0.237673 -0.100283 0.048291 -0.237673 -0.091304 0.0528043 -0.236873 -0.0816782 0.0556898 -0.237673 -0.0816782 0.0556898 -0.236873 -0.0716975 0.05686 -0.237673 -0.0616652 0.0562793 -0.236873 -0.0518862 0.0539654 -0.237673 -0.0518862 0.0539654 -0.236873 -0.0426576 0.0499885 -0.237673 -0.0426576 0.0499885 -0.236873 -0.020944 0.0295176 -0.236873 -0.012375 0.000932466 -0.230673 -0.119345 -0.0115019 -0.236673 -0.116532 -0.0203863 -0.230673 -0.116532 -0.0203863 -0.236673 -0.106302 -0.0358707 -0.230673 -0.106302 -0.0358707 -0.236673 -0.0992333 -0.0419434 -0.230673 -0.091169 -0.0466139 -0.230673 -0.0823839 -0.049723 -0.230673 -0.073177 -0.0511649 -0.236673 -0.0638619 -0.0508906 -0.230673 -0.0638619 -0.0508906 -0.230673 -0.0547559 -0.0489092 -0.230673 -0.046169 -0.0452883 -0.230673 -0.0383936 -0.0401513 -0.236673 -0.0316945 -0.033673 -0.230673 -0.0316945 -0.033673 -0.236673 -0.0262999 -0.0260741 -0.230673 -0.0262999 -0.0260741 -0.230673 -0.0223935 -0.0176133 -0.236673 -0.0201082 -0.0085787 -0.230673 -0.0195219 0.000721942 -0.236973 -0.118593 -0.0119275 -0.238273 -0.115482 -0.0211931 -0.238273 -0.110622 -0.0296736 -0.236973 -0.110622 -0.0296736 -0.238273 -0.104202 -0.0370432 -0.236973 -0.104202 -0.0370432 -0.238273 -0.078283 -0.0499309 -0.236973 -0.068532 -0.0506021 -0.238273 -0.068532 -0.0506021 -0.236973 -0.0588375 -0.0493581 -0.238273 -0.0588375 -0.0493581 -0.238273 -0.0410914 -0.0413874 -0.236973 -0.0337218 -0.0349671 -0.238273 -0.0337218 -0.0349671 -0.236973 -0.0277464 -0.0272324 -0.238273 -0.0233948 -0.0184805 -0.230673 -0.117333 0.00720916 -0.238173 -0.114868 0.0162901 -0.230673 -0.114868 0.0162901 -0.230673 -0.110678 0.0247157 -0.238173 -0.110678 0.0247157 -0.230673 -0.0896666 0.0430212 -0.238173 -0.097831 0.0383431 -0.230673 -0.0807465 0.0460166 -0.230673 -0.0620259 0.046568 -0.238173 -0.0714133 0.0472142 -0.238173 -0.0620259 0.046568 -0.230673 -0.0529449 0.0441029 -0.230673 -0.0445193 0.0399135 -0.230673 -0.037073 0.0341608 -0.230673 -0.030892 0.027066 -0.230673 -0.0262139 0.0189016 -0.238173 -0.0262139 0.0189016 -0.233299 -0.128906 -0.00250015 -0.233695 -0.128767 0.00236587 -0.233299 -0.128848 0.00237022 -0.233695 -0.128232 0.00774335 -0.233299 -0.12753 0.0120136 -0.233299 -0.126278 0.0167207 -0.233695 -0.12587 0.0177259 -0.233695 -0.122559 0.0257085 -0.233299 -0.122632 0.0257453 -0.233299 -0.120263 0.0300011 -0.233695 -0.117485 0.0339984 -0.233695 -0.114452 0.0378009 -0.233299 -0.114514 0.0378545 -0.233695 -0.111116 0.04134 -0.233695 -0.109139 0.0431834 -0.233299 -0.111173 0.0413986 -0.233299 -0.0995624 0.0502157 -0.233695 -0.100913 0.0493121 -0.233695 -0.0995213 0.0501449 -0.233695 -0.0952164 0.0524089 -0.233695 -0.0917475 0.0539193 -0.233299 -0.090768 0.0543862 -0.233695 -0.0907392 0.0543096 -0.233695 -0.0819212 0.0568649 -0.233299 -0.0861427 0.0559128 -0.233299 -0.0814072 0.0570523 -0.233695 -0.0813914 0.056972 -0.233695 -0.0765846 0.0577155 -0.233695 -0.0717328 0.0580595 -0.233299 -0.0717352 0.0581413 -0.233299 -0.0668649 0.0580834 -0.233299 -0.0620159 0.0576235 -0.233695 -0.062027 0.0575424 -0.233695 -0.0614917 0.0574667 -0.233299 -0.0572215 0.0567647 -0.233299 -0.0525144 0.055513 -0.233695 -0.0479573 0.053801 -0.233695 -0.0420884 0.0510449 -0.233695 -0.0314341 0.0436872 -0.233299 -0.0313805 0.043749 -0.233695 -0.0260517 0.0383741 -0.233695 -0.0246435 0.0367332 -0.233299 -0.0245805 0.0367853 -0.233299 -0.0190194 0.0287973 -0.233695 -0.0190902 0.0287563 -0.233695 -0.0153157 0.0209825 -0.233299 -0.0167523 0.0244864 -0.232755 -0.129482 -0.00251711 -0.232967 -0.1265 0.0167895 -0.232755 -0.128092 0.0121385 -0.232755 -0.125176 0.0215242 -0.232967 -0.120461 0.0301222 -0.232755 -0.120755 0.0303019 -0.232755 -0.118016 0.0343871 -0.232967 -0.111335 0.0415645 -0.232755 -0.107917 0.0450986 -0.232967 -0.107698 0.0448333 -0.232967 -0.0996787 0.0504163 -0.232967 -0.0953508 0.0526924 -0.232755 -0.0954983 0.0530034 -0.232967 -0.0908498 0.0546032 -0.232755 -0.0815187 0.0576176 -0.232967 -0.0766197 0.0580273 -0.232755 -0.0766582 0.0583694 -0.232755 -0.0717522 0.0587172 -0.232967 -0.0717421 0.0583731 -0.232967 -0.0668525 0.058315 -0.232967 -0.0571712 0.0569912 -0.232967 -0.0524455 0.0557345 -0.232967 -0.0478398 0.0540919 -0.232967 -0.0391129 0.0496963 -0.232967 -0.0350514 0.0469733 -0.232755 -0.034848 0.047251 -0.232755 -0.031003 0.0441842 -0.232967 -0.0244017 0.0369331 -0.232967 -0.0214444 0.0330389 -0.232755 -0.0211619 0.0332355 -0.232967 -0.0188187 0.0289137 -0.232967 -0.0165427 0.0245858 -0.232967 -0.0146318 0.0200848 -0.232755 -0.0143097 0.0202061 -0.232967 -0.0130992 0.0154413 -0.232755 -0.0127681 0.0155356 -0.233299 -0.128388 0.00721917 -0.232967 -0.12908 0.00238256 -0.232967 -0.128618 0.00725059 -0.232967 -0.127756 0.0120639 -0.233299 -0.124642 0.0213084 -0.232967 -0.124857 0.0213953 -0.232967 -0.12284 0.0258496 -0.233299 -0.117551 0.0340467 -0.232967 -0.117738 0.0341837 -0.232967 -0.114689 0.0380065 -0.233299 -0.10755 0.0446546 -0.233299 -0.103671 0.0476003 -0.232967 -0.103804 0.0477907 -0.233299 -0.0952514 0.0524828 -0.232967 -0.0862063 0.0561359 -0.232967 -0.0814521 0.0572798 -0.233299 -0.0765937 0.0577968 -0.232967 -0.0619845 0.0578533 -0.233299 -0.0479267 0.0538768 -0.233299 -0.0434898 0.0518674 -0.232967 -0.0433855 0.0520745 -0.233299 -0.039234 0.0494984 -0.233299 -0.0351884 0.0467861 -0.233299 -0.0278365 0.0404077 -0.232967 -0.0312285 0.0439242 -0.232967 -0.0276706 0.0405698 -0.233299 -0.0216348 0.0329063 -0.233299 -0.0148489 0.020003 -0.233299 -0.0133223 0.0153777 -0.233695 -0.0123701 0.0111562 -0.232967 -0.0112078 0.00585467 -0.232967 -0.0119552 0.0106871 -0.233299 -0.0121828 0.0106422 -0.232967 -0.0108619 0.000977036 -0.232755 -0.0108657 0.00589319 -0.233299 -0.0114383 0.00582872 -0.233299 -0.0110938 0.000970206 -0.233695 -0.0115196 0.00581957 -0.235573 -0.120753 0.0265775 -0.235573 -0.122943 0.02205 -0.233773 -0.12473 0.0173489 -0.235573 -0.12473 0.0173489 -0.233773 -0.126237 0.0119217 -0.235573 -0.127044 0.00756986 -0.233773 -0.127044 0.00756986 -0.235573 -0.127554 0.0025664 -0.233773 -0.127383 0.00477331 -0.235573 -0.127625 -0.00246241 -0.233773 -0.127625 -0.00246241 -0.233773 -0.0894215 0.0535151 -0.235573 -0.0865541 0.0544572 -0.235573 -0.091304 0.0528043 -0.233773 -0.0960715 0.050653 -0.235573 -0.104443 0.0454651 -0.233773 -0.100283 0.048291 -0.233773 -0.115234 0.0349754 -0.233773 -0.120753 0.0265775 -0.235573 -0.0567252 0.0553358 -0.235573 -0.0616652 0.0562793 -0.233773 -0.0616652 0.0562793 -0.233773 -0.0680758 0.0568529 -0.235573 -0.0716975 0.05686 -0.233773 -0.0716975 0.05686 -0.233773 -0.0753124 0.0566397 -0.233773 -0.0816782 0.0556898 -0.235573 -0.0816782 0.0556898 -0.235573 -0.020944 0.0295176 -0.233773 -0.0243782 0.0344794 -0.233773 -0.0269478 0.037576 -0.235573 -0.0342597 0.0444694 -0.235573 -0.0383382 0.0474123 -0.233773 -0.0405562 0.048799 -0.235573 -0.0518862 0.0539654 -0.233773 -0.012375 0.000932466 -0.235573 -0.0127423 0.00594836 -0.235573 -0.0135452 0.0109132 -0.235573 -0.0147779 0.0157891 -0.233773 -0.0146076 0.0152099 -0.235573 -0.0184914 0.0251268 -0.233773 -0.0164308 0.020539 -0.233773 -0.0170465 0.0220264 -0.233773 -0.0203206 0.0284836 -0.235723 -0.0124152 0.000931282 -0.235723 -0.0127822 0.00594368 -0.235723 -0.0164682 0.0205242 -0.235573 -0.0164308 0.020539 -0.235573 -0.02377 0.0336778 -0.235573 -0.0269478 0.037576 -0.235573 -0.0304533 0.0411823 -0.235723 -0.0342846 0.0444379 -0.235723 -0.0383602 0.0473787 -0.235723 -0.0426766 0.0499531 -0.235573 -0.0426576 0.0499885 -0.235573 -0.0471851 0.0521784 -0.235723 -0.0518988 0.0539272 -0.235723 -0.0567344 0.0552967 -0.235573 -0.0666687 0.0567887 -0.235573 -0.0767134 0.0564928 -0.235723 -0.08167 0.0556505 -0.235723 -0.0865425 0.0544187 -0.235723 -0.0912892 0.0527669 -0.235573 -0.0958918 0.0507437 -0.235573 -0.100283 0.048291 -0.235573 -0.108341 0.0422873 -0.235573 -0.111947 0.0387818 -0.235723 -0.115203 0.0349504 -0.235573 -0.115234 0.0349754 -0.235573 -0.118177 0.0308969 -0.235723 -0.122906 0.0220341 -0.235723 -0.124692 0.0173362 -0.235723 -0.126062 0.0125006 -0.235573 -0.126101 0.0125099 -0.235723 -0.127514 0.00256408 -0.235723 -0.127005 0.00756405 -0.235833 -0.127404 0.00255773 -0.235833 -0.124588 0.0173017 -0.235723 -0.120718 0.0265584 -0.235833 -0.122806 0.0219906 -0.235833 -0.118052 0.0308145 -0.235723 -0.118144 0.0308748 -0.235723 -0.111918 0.0387542 -0.235833 -0.115117 0.0348824 -0.235723 -0.108314 0.0422572 -0.235833 -0.111838 0.0386789 -0.235833 -0.108241 0.0421752 -0.235723 -0.104419 0.0454328 -0.235833 -0.104353 0.0453448 -0.235723 -0.100261 0.0482568 -0.235723 -0.0958738 0.0507077 -0.235833 -0.0958245 0.0506096 -0.235833 -0.0816478 0.0555429 -0.235723 -0.0767087 0.0564529 -0.235723 -0.0716963 0.0568199 -0.235723 -0.066671 0.0567486 -0.235833 -0.0716931 0.0567101 -0.235723 -0.061671 0.0562396 -0.235833 -0.0666773 0.0566389 -0.235723 -0.047201 0.0521415 -0.235833 -0.0472444 0.0520406 -0.235833 -0.0427287 0.0498564 -0.235833 -0.0343527 0.0443517 -0.235723 -0.0304809 0.0411531 -0.235833 -0.0305562 0.0410732 -0.235723 -0.0269778 0.0375492 -0.235723 -0.0238022 0.0336538 -0.235833 -0.0270598 0.0374762 -0.235723 -0.0209782 0.0294964 -0.235723 -0.0185273 0.0251088 -0.235833 -0.0186254 0.0250594 -0.235723 -0.0148164 0.0157775 -0.235833 -0.0136921 0.0108828 -0.235723 -0.0135846 0.010905 -0.235873 -0.0130402 0.00591342 -0.235833 -0.0128912 0.00593089 -0.235833 -0.0149216 0.015746 -0.235873 -0.0150653 0.0157029 -0.235873 -0.0167096 0.0204281 -0.235873 -0.0187595 0.0249921 -0.235833 -0.0165702 0.0204836 -0.235833 -0.0210717 0.0294388 -0.235873 -0.0240106 0.0334986 -0.235873 -0.0271719 0.0373765 -0.235833 -0.0238903 0.0335882 -0.235833 -0.0384205 0.0472869 -0.235873 -0.0427998 0.0497244 -0.235833 -0.0519333 0.053823 -0.235833 -0.0567597 0.0551899 -0.235873 -0.0617086 0.0559825 -0.235833 -0.0616869 0.0561309 -0.235873 -0.066686 0.0564892 -0.235873 -0.0766784 0.0561949 -0.235833 -0.0766959 0.0563438 -0.235873 -0.0816174 0.055396 -0.235833 -0.086511 0.0543135 -0.235873 -0.0911932 0.0525255 -0.235833 -0.0912486 0.0526649 -0.235833 -0.100204 0.0481634 -0.235873 -0.104264 0.0452245 -0.235873 -0.111729 0.038576 -0.235873 -0.114999 0.0347894 -0.235873 -0.117927 0.0307322 -0.235873 -0.120489 0.0264352 -0.235873 -0.122668 0.0219313 -0.235833 -0.120621 0.0265064 -0.235873 -0.124446 0.0172546 -0.235833 -0.125955 0.0124753 -0.235833 -0.126896 0.00754817 -0.233496 -0.0538593 0.0543865 -0.233496 -0.0132251 0.0081128 -0.233473 -0.121048 0.0253719 -0.233496 -0.0125602 0.000927013 -0.233513 -0.012525 0.000928049 -0.233561 -0.0608835 0.0560706 -0.233561 -0.0680788 0.0567651 -0.233496 -0.0608989 0.0559745 -0.233473 -0.0609171 0.0558612 -0.233496 -0.068082 0.0566678 -0.233473 -0.0680858 0.0565531 -0.233561 -0.126151 0.0119023 -0.233561 -0.124121 0.01884 -0.233496 -0.124029 0.0188069 -0.233496 -0.126056 0.0118809 -0.233658 -0.0203403 0.028472 -0.233658 -0.0170675 0.0220174 -0.233473 -0.0148958 0.0151268 -0.233496 -0.0172166 0.0219532 -0.233561 -0.0244477 0.0344257 -0.233658 -0.0291714 0.0399033 -0.233473 -0.0205791 0.0283314 -0.233496 -0.0292864 0.0397887 -0.233561 -0.0292174 0.0398574 -0.233658 -0.0345904 0.0446998 -0.233473 -0.0347607 0.0444812 -0.233496 -0.0406508 0.0486397 -0.233561 -0.0470354 0.0520179 -0.233561 -0.0406011 0.0487234 -0.233658 -0.0470095 0.0520775 -0.233658 -0.0538137 0.0545423 -0.233773 -0.0608696 0.0561574 -0.233658 -0.0824603 0.055499 -0.233561 -0.0824463 0.0554355 -0.233496 -0.0752954 0.0564553 -0.233496 -0.0824252 0.0553405 -0.233561 -0.0893919 0.0534324 -0.233561 -0.102261 0.0469071 -0.233658 -0.108024 0.0425367 -0.233561 -0.107982 0.0424878 -0.233773 -0.113169 0.0374447 -0.233658 -0.113152 0.0374295 -0.233473 -0.102142 0.0467314 -0.233496 -0.107917 0.0424147 -0.233561 -0.113103 0.0373864 -0.233658 -0.121295 0.0254982 -0.233473 -0.112944 0.0372458 -0.233496 -0.11303 0.0373219 -0.233561 -0.117545 0.0316834 -0.233561 -0.121237 0.0254686 -0.233773 -0.124203 0.01887 -0.233561 -0.0124629 0.000929878 -0.233658 -0.0130647 0.00813788 -0.233623 -0.0124152 0.000931282 -0.233773 -0.0130422 0.00814141 -0.233561 -0.013129 0.00812783 -0.233561 -0.014692 0.0151855 -0.233658 -0.0146295 0.0152036 -0.233773 -0.0135452 0.0109132 -0.233496 -0.0147855 0.0151586 -0.233561 -0.0171272 0.0219917 -0.233561 -0.0203963 0.028439 -0.233773 -0.0291552 0.0399194 -0.233658 -0.0243962 0.0344655 -0.233773 -0.020944 0.0295176 -0.233496 -0.0204802 0.0283896 -0.233496 -0.0245247 0.0343662 -0.233773 -0.0345764 0.0447178 -0.233496 -0.0346902 0.0445717 -0.233561 -0.0346304 0.0446485 -0.233658 -0.0405679 0.0487793 -0.233773 -0.0538073 0.0545642 -0.233773 -0.0518862 0.0539654 -0.233773 -0.0470004 0.0520984 -0.233773 -0.0426576 0.0499885 -0.233473 -0.0471201 0.0518233 -0.233496 -0.0470743 0.0519286 -0.233561 -0.053832 0.0544799 -0.233658 -0.0680766 0.0568301 -0.233658 -0.0608732 0.0561349 -0.233561 -0.0753043 0.0565522 -0.233773 -0.0824653 0.0555213 -0.233658 -0.0753103 0.056617 -0.233658 -0.0894138 0.0534936 -0.233658 -0.0960611 0.0506326 -0.233773 -0.108039 0.0425539 -0.233658 -0.102297 0.046961 -0.233773 -0.10231 0.0469799 -0.233773 -0.091304 0.0528043 -0.233473 -0.0893204 0.0532327 -0.233496 -0.0893591 0.0533408 -0.233496 -0.0959877 0.0504878 -0.233561 -0.0960317 0.0505746 -0.233496 -0.102206 0.0468265 -0.233773 -0.121315 0.0255086 -0.233658 -0.117599 0.03172 -0.233773 -0.117617 0.0317329 -0.233496 -0.117464 0.0316285 -0.233496 -0.12115 0.0254242 -0.233658 -0.126215 0.0119167 -0.233658 -0.124182 0.0188622 -0.233473 -0.125944 0.0118557 -0.233496 -0.127199 0.00475551 -0.233561 -0.127296 0.00476486 -0.233623 -0.127585 -0.00246122 -0.233658 -0.127361 0.00477111 -0.235873 -0.0136745 0.000894189 -0.236073 -0.0151338 0.0111732 -0.235873 -0.0180774 0.0211293 -0.235873 -0.0229845 0.0302973 -0.235873 -0.0294927 0.0384075 -0.236073 -0.0374961 0.0450206 -0.235873 -0.0373803 0.0451837 -0.236073 -0.0562307 0.0536706 -0.236073 -0.0768249 0.0549687 -0.235873 -0.0965917 0.0489161 -0.236073 -0.105143 0.043028 -0.235873 -0.118762 0.027476 -0.236073 -0.122933 0.0179683 -0.233273 -0.125474 0.00792297 -0.233473 -0.125671 0.00795392 -0.233273 -0.122933 0.0179683 -0.233473 -0.123121 0.0180351 -0.233473 -0.118762 0.027476 -0.233273 -0.112591 0.0358249 -0.233473 -0.105268 0.0431839 -0.233473 -0.0965917 0.0489161 -0.233273 -0.0964973 0.0487397 -0.233273 -0.0869497 0.0527657 -0.233473 -0.0664551 0.0554734 -0.233273 -0.0562307 0.0536706 -0.233273 -0.0464626 0.0502136 -0.233473 -0.0463788 0.0503952 -0.233273 -0.0374961 0.0450206 -0.233473 -0.0294927 0.0384075 -0.233473 -0.0229845 0.0302973 -0.233473 -0.0136745 0.000894189 -0.229847 -0.0542624 -0.0633554 -0.224773 -0.052725 -0.0626156 -0.226573 -0.052725 -0.0626156 -0.226573 -0.0522977 -0.062046 -0.224773 -0.0516655 -0.0617183 -0.226573 -0.0516655 -0.0617183 -0.224773 -0.0509537 -0.0616974 -0.224773 -0.0498432 -0.0625307 -0.224773 -0.0496644 -0.0632199 -0.226573 -0.0535972 -0.0659302 -0.226573 -0.0535555 -0.0661879 -0.230091 -0.0579074 0.0620975 -0.23089 -0.0562422 0.0600123 -0.226573 -0.055279 0.059747 -0.230652 -0.0538617 0.0599459 -0.226573 -0.0538665 0.059944 -0.226573 -0.0520558 0.0620408 -0.226573 -0.0282385 0.0466239 -0.230738 -0.0280946 0.0457901 -0.226573 -0.026931 0.0442343 -0.23092 -0.0273017 0.0445331 -0.226573 -0.0278716 0.0452722 -0.230848 -0.0278727 0.0452742 -0.2308 -0.0279923 0.0455189 -0.230912 -0.0270491 0.0443193 -0.226573 -0.0256217 0.0437366 -0.230454 -0.0250486 0.0437183 -0.226573 -0.0242292 0.0438876 -0.226573 -0.023057 0.0446543 -0.23089 -0.0104865 0.0177091 -0.23087 -0.0104967 0.0178831 -0.23092 -0.0103732 0.0171151 -0.230912 -0.0102614 0.0168037 -0.226573 -0.0101483 0.0165659 -0.230773 -0.00971079 0.0159457 -0.230614 -0.00924922 0.0155356 -0.226573 -0.00925337 0.0155386 -0.226573 -0.00799634 0.0150131 -0.23087 -0.00950216 -0.0158782 -0.230773 -0.00943266 -0.0164378 -0.226573 -0.00919089 -0.0171232 -0.229996 -0.00820937 -0.0182576 -0.226573 -0.00836948 -0.0181389 -0.226573 -0.0252595 -0.0467543 -0.226573 -0.0866242 -0.0643087 -0.226573 -0.0860589 -0.0630405 -0.224773 -0.084715 -0.0626919 -0.224773 -0.0840646 -0.0629818 -0.226573 -0.0840646 -0.0629818 -0.226573 -0.0836044 -0.0635252 -0.224773 -0.0836044 -0.0635252 -0.224773 -0.0834256 -0.0642144 -0.224773 -0.11636 -0.0482893 -0.224773 -0.115601 -0.0468807 -0.226573 -0.114807 -0.0466429 -0.224773 -0.114807 -0.0466429 -0.224773 -0.114001 -0.0468336 -0.226573 -0.114001 -0.0468336 -0.224773 -0.134101 -0.0195484 -0.224773 -0.133911 -0.0187425 -0.224773 -0.133343 -0.0181399 -0.226573 -0.133343 -0.0181399 -0.224773 -0.132549 -0.017902 -0.224773 -0.131743 -0.0180927 -0.224773 -0.130903 -0.0194542 -0.226573 -0.131141 -0.0186609 -0.226573 -0.135096 0.0142128 -0.226573 -0.134905 0.0150188 -0.226573 -0.132135 0.0151004 -0.226573 -0.118886 0.0447541 -0.224773 -0.118886 0.0447541 -0.226573 -0.118318 0.0453567 -0.224773 -0.117524 0.0455945 -0.224773 -0.116116 0.0448357 -0.224773 -0.090145 0.062496 -0.224773 -0.0895769 0.0630986 -0.226573 -0.0895769 0.0630986 -0.224773 -0.0887835 0.0633364 -0.226573 -0.0879776 0.0631457 -0.226573 -0.0873749 0.0625776 -0.224773 -0.0560092 0.0639526 -0.226573 -0.0564365 0.0633831 -0.226573 -0.0560092 0.0639526 -0.224773 -0.055377 0.0642803 -0.224773 -0.0540148 0.0640114 -0.224773 -0.0535547 0.063468 -0.224773 -0.0533759 0.0627787 -0.224773 -0.0268391 0.0466651 -0.224773 -0.0267012 0.0473637 -0.226573 -0.0262738 0.0479333 -0.226573 -0.0256416 0.048261 -0.224773 -0.0249299 0.0482819 -0.224773 -0.0242795 0.047992 -0.224773 -0.0083384 0.0193329 -0.226573 -0.0067391 0.01938 -0.224773 -0.00613647 0.0188118 -0.226573 -0.00613647 0.0188118 -0.224773 -0.00796483 -0.0151384 -0.226573 -0.00753745 -0.0145688 -0.224773 -0.00690527 -0.0142411 -0.224773 -0.00619351 -0.0142202 -0.226573 -0.00554314 -0.0145101 -0.224773 -0.0241221 -0.0455723 -0.226573 -0.0233633 -0.0441637 -0.226573 -0.0225699 -0.0439259 -0.224773 -0.021764 -0.0441166 -0.226573 -0.0211613 -0.0446847 -0.224773 -0.0209235 -0.0454781 -0.228743 -0.057844 0.0662901 -0.2263 -0.0580385 0.0664013 -0.226273 -0.0582626 0.0664682 -0.228784 -0.057435 0.0655125 -0.228776 -0.057448 0.0656465 -0.226573 -0.0575476 0.065945 -0.22876 -0.0575476 0.065945 -0.228757 -0.0258605 0.0508542 -0.22636 -0.0259604 0.0512615 -0.226324 -0.00584525 0.0223725 -0.228737 -0.00590571 0.0226867 -0.228772 -0.00494886 -0.0193515 -0.226573 -0.00497213 -0.0193325 -0.226573 -0.00536387 -0.0191423 -0.228753 -0.00469834 -0.019671 -0.226573 -0.022985 -0.0493184 -0.228774 -0.0229648 -0.049367 -0.228757 -0.0228986 -0.0496965 -0.238473 -0.0203628 0.000697172 -0.238273 -0.0208341 -0.00904789 -0.238473 -0.0235817 -0.0184095 -0.238273 -0.0277464 -0.0272324 -0.238473 -0.0338673 -0.0348299 -0.238473 -0.0412074 -0.0412245 -0.238473 -0.0496539 -0.0460642 -0.238273 -0.0495719 -0.0462467 -0.238473 -0.0588823 -0.0491632 -0.238473 -0.0685379 -0.0504022 -0.238473 -0.0782497 -0.0497337 -0.238273 -0.0877156 -0.0473703 -0.238273 -0.0964674 -0.0430186 -0.238473 -0.0963613 -0.0428491 -0.238473 -0.104065 -0.0368977 -0.238473 -0.11046 -0.0295577 -0.238273 -0.118593 -0.0119275 -0.236673 -0.125474 0.00792297 -0.236673 -0.122933 0.0179683 -0.236873 -0.125671 0.00795392 -0.236873 -0.123121 0.0180351 -0.236873 -0.118762 0.027476 -0.236873 -0.112743 0.0359552 -0.236873 -0.0965917 0.0489161 -0.236673 -0.0869497 0.0527657 -0.236673 -0.0768249 0.0549687 -0.236673 -0.0664676 0.0552738 -0.236673 -0.0562307 0.0536706 -0.236873 -0.0664551 0.0554734 -0.236873 -0.0561816 0.0538645 -0.236673 -0.0464626 0.0502136 -0.236873 -0.0463788 0.0503952 -0.236673 -0.0374961 0.0450206 -0.236873 -0.0373803 0.0451837 -0.236673 -0.0231514 0.030187 -0.236673 -0.0182617 0.0210516 -0.236673 -0.0151338 0.0111732 -0.236873 -0.0180774 0.0211293 -0.236873 -0.0136745 0.000894189 -0.237673 -0.12473 0.0173489 -0.237673 -0.120753 0.0265775 -0.237673 -0.115234 0.0349754 -0.237873 -0.12093 0.0266724 -0.237873 -0.115391 0.0350993 -0.237673 -0.108341 0.0422873 -0.237873 -0.108474 0.0424366 -0.237873 -0.100388 0.0484612 -0.237673 -0.0716975 0.05686 -0.237873 -0.0616363 0.0564772 -0.237873 -0.0518234 0.0541552 -0.237873 -0.0341357 0.0446264 -0.237673 -0.0342597 0.0444694 -0.237673 -0.0269478 0.037576 -0.237673 -0.020944 0.0295176 -0.237873 -0.0267985 0.037709 -0.237873 -0.0207739 0.0296226 -0.237873 -0.016245 0.0206129 -0.237673 -0.0164308 0.020539 -0.237673 -0.0135452 0.0109132 -0.237873 -0.0133494 0.0109537 -0.237873 -0.0143203 -0.019193 -0.237873 -0.0183662 -0.0285817 -0.237673 -0.0238241 -0.0372492 -0.237873 -0.030994 -0.044564 -0.237873 -0.0391922 -0.0506719 -0.237873 -0.0483265 -0.0552634 -0.237673 -0.0482526 -0.0554493 -0.237873 -0.0978168 -0.0523988 -0.237673 -0.0979117 -0.0525749 -0.237673 -0.106484 -0.0469409 -0.237873 -0.113799 -0.039771 -0.237673 -0.113948 -0.039904 -0.237873 -0.119907 -0.0315728 -0.237673 -0.12763 -0.0126862 -0.237873 -0.127434 -0.0126457 -0.228673 -0.0247779 0.00962324 -0.228673 -0.0321956 0.0261383 -0.228673 -0.0453687 0.0385575 -0.228673 -0.0622917 0.0449903 -0.228873 -0.0713603 0.045415 -0.228873 -0.0803435 0.0442623 -0.228673 -0.0713662 0.0456149 -0.228873 -0.0889291 0.0413792 -0.228673 -0.0890111 0.0415616 -0.228673 -0.0969033 0.0370395 -0.228873 -0.103616 0.0309273 -0.228673 -0.109323 0.0238664 -0.228673 -0.113372 0.0157216 -0.228873 -0.11618 -0.00212528 -0.230473 -0.115558 0.00691013 -0.230473 -0.113185 0.0156506 -0.230673 -0.113372 0.0157216 -0.230673 -0.109323 0.0238664 -0.230473 -0.0967873 0.0368765 -0.230673 -0.0969033 0.0370395 -0.230673 -0.0890111 0.0415616 -0.230473 -0.0713603 0.045415 -0.230473 -0.0323585 0.0260223 -0.230673 -0.0321956 0.0261383 -0.230473 -0.0278559 0.0181641 -0.230473 -0.0249728 0.00957846 -0.230473 -0.0238201 0.000595334 -0.230673 -0.0247779 0.00962324 -0.238173 -0.117333 0.00720916 -0.238473 -0.117629 0.007259 -0.238473 -0.115148 0.0163967 -0.238473 -0.110933 0.024875 -0.238473 -0.105144 0.0323679 -0.238173 -0.104926 0.0321621 -0.238173 -0.0896666 0.0430212 -0.238473 -0.0897895 0.0432948 -0.238173 -0.0807465 0.0460166 -0.238473 -0.0619761 0.0468639 -0.238173 -0.0529449 0.0441029 -0.238173 -0.0445193 0.0399135 -0.238173 -0.037073 0.0341608 -0.238473 -0.0368672 0.0343791 -0.238473 -0.0306476 0.0272399 -0.238173 -0.030892 0.027066 -0.238473 -0.0259402 0.0190245 -0.238173 -0.0232185 0.00998145 -0.236673 -0.0195219 0.000721942 -0.236673 -0.0223935 -0.0176133 -0.236973 -0.0204046 -0.00853228 -0.236973 -0.0226763 -0.0175132 -0.236973 -0.0265595 -0.0259237 -0.236973 -0.0319221 -0.0334775 -0.236673 -0.0383936 -0.0401513 -0.236973 -0.0463106 -0.0450238 -0.236673 -0.046169 -0.0452883 -0.236673 -0.0547559 -0.0489092 -0.236973 -0.0731581 -0.0508655 -0.236673 -0.073177 -0.0511649 -0.236673 -0.0823839 -0.049723 -0.236673 -0.091169 -0.0466139 -0.236973 -0.0910433 -0.0463415 -0.236973 -0.0990596 -0.0416988 -0.236673 -0.112135 -0.0286025 -0.236973 -0.116256 -0.0202697 -0.236673 -0.119345 -0.0115019 -0.236973 -0.119052 -0.0114381 -0.236673 -0.120478 -0.00225188 -0.225073 -0.133626 0.00321728 -0.230374 -0.133626 0.00321728 -0.225073 -0.133773 -0.0103489 -0.225073 -0.133348 -0.00946449 -0.225073 -0.00627768 0.00111207 -0.225073 -0.00254235 -0.00859799 -0.228744 -0.00235547 -0.00890491 -0.225073 -0.00243821 -0.00873777 -0.224773 -0.00269349 -0.00889535 -0.225073 -0.00599203 -0.00627536 -0.225073 -0.00501276 -0.0071986 -0.224773 -0.00701706 0.00691917 -0.224773 -0.00320532 0.0116657 -0.224773 -0.00321704 0.0117743 -0.231382 -0.133253 -0.00262818 -0.219624 -0.00627768 0.00111207 -0.219624 -0.00671926 0.0069555 -0.224773 -0.133326 0.00319854 -0.224773 -0.132963 -0.00871493 -0.224773 -0.133532 -0.0105276 -0.224773 -0.134338 -0.011268 -0.224773 -0.136463 -0.0125794 -0.224473 -0.136975 -0.0127008 -0.224773 -0.136666 -0.0127703 -0.224473 -0.137071 -0.0129589 -0.224473 -0.00290545 0.0116746 -0.224473 -0.00281485 -0.00838268 -0.224473 -0.00228957 -0.00923361 -0.221685 -0.0023128 -0.00904681 -0.224473 -0.00671926 0.0069555 -0.21982 -0.133263 -0.00872376 -0.224473 -0.133263 -0.00872376 -0.21984 -0.133269 -0.00900067 -0.224473 -0.13339 -0.0096069 -0.224473 -0.133573 -0.0100335 -0.21982 -0.133622 0.00345624 -0.219816 -0.133621 0.00333517 -0.224473 -0.133622 0.00345624 -0.224473 -0.133626 0.00321728 -0.224773 -0.0236645 -0.0450162 -0.219452 -0.0236645 -0.0450162 -0.224773 -0.0233306 -0.0445713 -0.219429 -0.0233306 -0.0445713 -0.224773 -0.0228367 -0.0443152 -0.224773 -0.0222807 -0.0442989 -0.219642 -0.0222807 -0.0442989 -0.224773 -0.0217726 -0.0445254 -0.220035 -0.0214131 -0.0449499 -0.220205 -0.0212734 -0.0454884 -0.219442 -0.00775292 -0.0158266 -0.224773 -0.00764515 -0.0152809 -0.224773 -0.00731126 -0.0148359 -0.219517 -0.00731126 -0.0148359 -0.219672 -0.00681737 -0.0145799 -0.219869 -0.00626131 -0.0145635 -0.220067 -0.00575321 -0.01479 -0.224773 -0.00539371 -0.0152146 -0.220228 -0.00539371 -0.0152146 -0.219538 -0.00863964 0.0184804 -0.224773 -0.00830575 0.0189253 -0.219703 -0.00830575 0.0189253 -0.224773 -0.00781187 0.0191813 -0.219903 -0.00781187 0.0191813 -0.224773 -0.0072558 0.0191977 -0.224773 -0.0067477 0.0189712 -0.220249 -0.0067477 0.0189712 -0.224773 -0.0062485 0.0180082 -0.220328 -0.0063882 0.0185467 -0.224773 -0.0264893 0.0466754 -0.224773 -0.0263815 0.0472212 -0.219735 -0.0263815 0.0472212 -0.224773 -0.0260476 0.0476662 -0.219937 -0.0260476 0.0476662 -0.224773 -0.0255537 0.0479222 -0.220268 -0.0249977 0.0479386 -0.224773 -0.0244896 0.0477121 -0.224773 -0.0241301 0.0472875 -0.220311 -0.0241301 0.0472875 -0.219768 -0.0562246 0.0626948 -0.220154 -0.055783 0.0636855 -0.224773 -0.0542249 0.0637314 -0.224773 -0.0538654 0.0633069 -0.220181 -0.0538654 0.0633069 -0.220336 -0.0890957 0.0629344 -0.220321 -0.089393 0.0628008 -0.220003 -0.0899859 0.0617003 -0.224773 -0.0898369 0.06233 -0.220276 -0.0896472 0.0625932 -0.220321 -0.0887732 0.0629866 -0.224773 -0.0887732 0.0629866 -0.220205 -0.0881435 0.0628376 -0.224773 -0.0876727 0.0623937 -0.219768 -0.087487 0.0617739 -0.224773 -0.118578 0.0445881 -0.224773 -0.118134 0.0450589 -0.220276 -0.117834 0.0451933 -0.224773 -0.117514 0.0452447 -0.220205 -0.117514 0.0452447 -0.224773 -0.134638 0.0147689 -0.220249 -0.134304 0.0152138 -0.220097 -0.133811 0.0154698 -0.224773 -0.133254 0.0154862 -0.219903 -0.133254 0.0154862 -0.224773 -0.132746 0.0152597 -0.219538 -0.132387 0.0148352 -0.224773 -0.132247 0.0142967 -0.224773 -0.133752 -0.0195381 -0.224773 -0.133644 -0.0189924 -0.220228 -0.133644 -0.0189924 -0.224773 -0.13331 -0.0185474 -0.224773 -0.132816 -0.0182914 -0.224773 -0.13226 -0.018275 -0.224773 -0.131752 -0.0185015 -0.219517 -0.131752 -0.0185015 -0.224773 -0.131392 -0.0189261 -0.219434 -0.131392 -0.0189261 -0.219442 -0.131253 -0.0194645 -0.224773 -0.11601 -0.048279 -0.224773 -0.115902 -0.0477332 -0.219835 -0.115568 -0.0472883 -0.224773 -0.115074 -0.0470322 -0.219642 -0.115074 -0.0470322 -0.224773 -0.11401 -0.0472424 -0.219429 -0.11401 -0.0472424 -0.224773 -0.113511 -0.0482054 -0.219801 -0.0861666 -0.0637526 -0.219614 -0.0858327 -0.0633076 -0.224773 -0.0853388 -0.0630516 -0.21948 -0.0853388 -0.0630516 -0.219427 -0.0847828 -0.0630352 -0.224773 -0.0847828 -0.0630352 -0.224773 -0.0842747 -0.0632617 -0.219465 -0.0842747 -0.0632617 -0.224773 -0.0837755 -0.0642247 -0.219768 -0.0525131 -0.0633039 -0.219587 -0.0524054 -0.0627581 -0.219427 -0.0515776 -0.0620571 -0.224773 -0.0515776 -0.0620571 -0.224773 -0.0510215 -0.0620407 -0.224773 -0.0505134 -0.0622672 -0.224773 -0.0501539 -0.0626918 -0.219614 -0.0505134 -0.0622672 -0.219801 -0.0501539 -0.0626918 -0.220003 -0.0500142 -0.0632303 -0.186473 -0.0281182 0.000468725 -0.185973 -0.0364464 0.0251563 -0.186473 -0.0668491 0.0410164 -0.186473 -0.0756048 0.0407585 -0.186473 -0.0841156 0.0386858 -0.185973 -0.084284 0.0391566 -0.185973 -0.092272 0.0353144 -0.186473 -0.0920094 0.0348889 -0.185973 -0.105021 0.0231363 -0.185973 -0.109225 0.0153327 -0.185973 -0.130774 -0.00255516 -0.187973 -0.132773 -0.00261404 -0.187973 -0.128355 -0.0239721 -0.185973 -0.121736 -0.0327021 -0.185973 -0.115405 -0.0412009 -0.187973 -0.0997851 -0.0560523 -0.185973 -0.0891036 -0.0584858 -0.185973 -0.0787903 -0.0609262 -0.187973 -0.0572787 -0.062263 -0.187973 -0.0467929 -0.0591197 -0.185973 -0.0576838 -0.0603045 -0.185973 -0.047532 -0.0572612 -0.185973 -0.0380629 -0.0525014 -0.187973 -0.028234 -0.0476631 -0.185973 -0.022294 -0.0384582 -0.187973 -0.0147127 -0.03055 -0.185973 -0.0164734 -0.0296014 -0.185973 -0.0122792 -0.0198686 -0.185973 -0.00983883 -0.00955522 -0.219214 -0.133325 0.00266983 -0.218289 -0.132708 0.00263635 -0.218685 -0.132313 0.00767713 -0.218289 -0.132232 0.00766615 -0.218289 -0.13214 0.00831443 -0.218685 -0.131432 0.0126589 -0.218685 -0.130154 0.0175537 -0.218289 -0.12962 0.018967 -0.218289 -0.126368 0.0269207 -0.218685 -0.12403 0.0314041 -0.218289 -0.125287 0.0290201 -0.218685 -0.12127 0.0356433 -0.218685 -0.118177 0.0396468 -0.218289 -0.118114 0.0395942 -0.218685 -0.114772 0.0433887 -0.218289 -0.114714 0.0433313 -0.218289 -0.102988 0.0526733 -0.218289 -0.102875 0.0527428 -0.218685 -0.089154 0.0591287 -0.218289 -0.089129 0.0590508 -0.218685 -0.0842774 0.0604745 -0.218685 -0.0793084 0.061424 -0.218289 -0.0742736 0.0618895 -0.218685 -0.0742792 0.061971 -0.218289 -0.0718491 0.0620078 -0.218289 -0.0502681 0.0588546 -0.218289 -0.0493972 0.0585593 -0.218685 -0.0446621 0.056786 -0.218289 -0.0401567 0.0544909 -0.218685 -0.0277567 0.0458142 -0.218289 -0.0278116 0.0457536 -0.218685 -0.0241491 0.0422677 -0.218289 -0.0231019 0.0410011 -0.218685 -0.0208383 0.0384427 -0.218685 -0.0151905 0.0300577 -0.218685 -0.0128902 0.0255521 -0.218289 -0.0129645 0.0255178 -0.218289 -0.0116454 0.0224421 -0.218289 -0.00948975 0.0160382 -0.218685 -0.00941095 0.01606 -0.218289 -0.00833484 0.0111196 -0.218685 -0.00749776 0.00613312 -0.218289 -0.00757905 0.00612415 -0.219214 -0.133391 -0.00263225 -0.219017 -0.133021 0.00265334 -0.218685 -0.13279 0.00264078 -0.219017 -0.132542 0.00770828 -0.219017 -0.130376 0.0176213 -0.218685 -0.128487 0.02233 -0.219017 -0.12423 0.0315228 -0.218685 -0.126441 0.0269567 -0.219017 -0.121459 0.0357776 -0.219017 -0.118355 0.0397959 -0.219017 -0.114938 0.0435516 -0.219017 -0.11123 0.0470205 -0.218685 -0.111078 0.0468449 -0.219017 -0.107255 0.0501802 -0.218685 -0.107118 0.0499929 -0.218685 -0.102918 0.0528124 -0.219017 -0.0986096 0.0554919 -0.218685 -0.0985044 0.0552852 -0.218685 -0.0939066 0.0573951 -0.219017 -0.08433 0.0607004 -0.219017 -0.0742949 0.0622025 -0.218685 -0.0692222 0.062112 -0.219017 -0.0692194 0.062344 -0.218685 -0.0641703 0.061846 -0.218685 -0.0591562 0.0611748 -0.219017 -0.0492943 0.0588557 -0.218685 -0.0542122 0.0601026 -0.218685 -0.0493704 0.0586365 -0.219017 -0.0445687 0.0569983 -0.218685 -0.0401179 0.0545629 -0.218685 -0.035767 0.0519818 -0.219017 -0.0314962 0.049243 -0.219017 -0.0276008 0.045986 -0.218685 -0.0316377 0.0490592 -0.219017 -0.0239799 0.0424264 -0.218685 -0.0178456 0.0343639 -0.219017 -0.0149884 0.0301714 -0.219017 -0.0126795 0.0256492 -0.219017 -0.0107417 0.0209559 -0.218685 -0.0109595 0.0208761 -0.219017 -0.00918744 0.0161221 -0.218685 -0.00825454 0.0111351 -0.219017 -0.00802676 0.011179 -0.219017 -0.00726719 0.00615857 -0.219229 -0.0146883 0.0303401 -0.219017 -0.0176532 0.0344935 -0.219229 -0.0173677 0.0346858 -0.219017 -0.0206569 0.0385873 -0.219229 -0.0203878 0.0388019 -0.219229 -0.0273696 0.046241 -0.219017 -0.0356407 0.0521763 -0.219017 -0.0400076 0.054767 -0.219229 -0.04443 0.0573133 -0.219229 -0.0491814 0.0591808 -0.219017 -0.054154 0.0603272 -0.219017 -0.0591162 0.0614033 -0.219017 -0.0641488 0.062077 -0.219229 -0.0641169 0.0624197 -0.219229 -0.0692151 0.0626882 -0.219017 -0.0793427 0.0616535 -0.219017 -0.0892246 0.0593496 -0.219229 -0.0893295 0.0596775 -0.219017 -0.0939948 0.0576097 -0.219017 -0.103039 0.0530101 -0.219229 -0.111455 0.0472812 -0.219229 -0.121739 0.0359769 -0.219017 -0.12665 0.027059 -0.219017 -0.128703 0.0224152 -0.219229 -0.129023 0.0225416 -0.219017 -0.131659 0.0127084 -0.219229 -0.132884 0.00775449 -0.219214 -0.133294 0.00319655 -0.218289 -0.132092 -0.010167 -0.218289 -0.131498 -0.0134863 -0.187973 -0.131498 -0.0134863 -0.218289 -0.116898 -0.042531 -0.187973 -0.123438 -0.0337527 -0.187973 -0.116898 -0.042531 -0.218289 -0.11576 -0.0437751 -0.187973 -0.108933 -0.0500403 -0.218289 -0.0905307 -0.0601142 -0.187973 -0.089732 -0.0603845 -0.218289 -0.0790794 -0.0629052 -0.187973 -0.0790794 -0.0629052 -0.218289 -0.0757309 -0.0633029 -0.187973 -0.068151 -0.0635377 -0.218289 -0.0467929 -0.0591197 -0.218289 -0.0460116 -0.0588028 -0.218289 -0.0391908 -0.0554882 -0.187973 -0.0370123 -0.0542032 -0.218289 -0.0328193 -0.0513756 -0.187973 -0.0207247 -0.0396981 -0.218289 -0.0269899 -0.0465249 -0.218289 -0.0172887 -0.0349022 -0.218289 -0.0135582 -0.0282997 -0.218289 -0.0106508 -0.0212956 -0.187973 -0.0103805 -0.020497 -0.187973 -0.00722727 0.0010841 -0.187973 -0.00785984 -0.00984437 -0.218289 -0.00860882 -0.0139921 -0.220205 -0.13456 0.0136033 -0.220802 -0.136218 0.0137045 -0.220328 -0.134638 0.0147689 -0.219703 -0.132746 0.0152597 -0.219442 -0.132247 0.0142967 -0.219229 -0.130706 0.0177215 -0.219229 -0.131995 0.0127819 -0.219442 -0.132396 0.013667 -0.219562 -0.13284 0.0131962 -0.219768 -0.13346 0.0130104 -0.22032 -0.136023 0.00679165 -0.220746 -0.137131 0.00739015 -0.220003 -0.134089 0.0131594 -0.219563 -0.134067 0.00551658 -0.219229 -0.00692504 0.00619633 -0.219313 -0.00689853 0.00785858 -0.21947 -0.00658437 0.00872011 -0.219517 -0.0082482 0.0169716 -0.219229 -0.00885576 0.0162142 -0.219229 -0.00768875 0.0112441 -0.219229 -0.0104185 0.0210744 -0.219442 -0.00874741 0.0179346 -0.220097 -0.0072558 0.0191977 -0.220802 -0.00636038 0.0225619 -0.220321 -0.0062485 0.0180082 -0.219229 -0.0123669 0.0257932 -0.220126 -0.0255537 0.0479222 -0.219562 -0.0264893 0.0466754 -0.220333 -0.0244896 0.0477121 -0.220802 -0.024466 0.0494426 -0.220205 -0.0239904 0.046749 -0.220035 -0.0240981 0.0462033 -0.219229 -0.023729 0.042662 -0.219497 -0.025482 0.0454859 -0.220802 -0.0529824 0.0648441 -0.220284 -0.0552891 0.0639416 -0.21997 -0.0561169 0.0632406 -0.219614 -0.0541674 0.0617777 -0.21948 -0.0546613 0.0615217 -0.219427 -0.0552173 0.0615053 -0.220336 -0.054733 0.0639579 -0.220299 -0.0542249 0.0637314 -0.220003 -0.0537257 0.0627684 -0.219229 -0.0312862 0.0495158 -0.219229 -0.0354533 0.0524651 -0.219229 -0.039844 0.0550699 -0.220802 -0.0404018 0.0602112 -0.220802 -0.0505027 0.0641504 -0.219229 -0.0540675 0.0606604 -0.219229 -0.0590568 0.0617423 -0.220802 -0.0637162 0.0667233 -0.220802 -0.0719298 0.0669877 -0.219229 -0.0743184 0.0625459 -0.219229 -0.0793937 0.0619939 -0.220205 -0.0898369 0.06233 -0.220276 -0.0884463 0.062953 -0.220003 -0.0876727 0.0623937 -0.219229 -0.0844082 0.0610357 -0.219427 -0.0884225 0.0605272 -0.21948 -0.0889786 0.0605108 -0.219614 -0.0894867 0.0607373 -0.219229 -0.0941256 0.0579281 -0.220802 -0.103021 0.0584277 -0.219229 -0.0987656 0.0557988 -0.219229 -0.103219 0.0533034 -0.219229 -0.107458 0.050458 -0.219452 -0.116336 0.0434863 -0.219497 -0.117163 0.0427853 -0.220205 -0.118727 0.0439584 -0.220276 -0.118694 0.0442807 -0.220321 -0.118578 0.0445881 -0.220336 -0.118387 0.0448528 -0.220802 -0.119976 0.0450228 -0.220321 -0.118134 0.0450589 -0.220802 -0.114278 0.0505536 -0.220003 -0.116884 0.0450957 -0.219229 -0.115183 0.0437933 -0.219768 -0.116414 0.0446518 -0.219562 -0.116228 0.044032 -0.220802 -0.12193 0.0427948 -0.219229 -0.118618 0.0400171 -0.219229 -0.124525 0.0316989 -0.220802 -0.13185 0.0269619 -0.219229 -0.126959 0.0272108 -0.213123 -0.111223 0.00673601 -0.186473 -0.111223 0.00673601 -0.186473 -0.108763 0.0151429 -0.213123 -0.108763 0.0151429 -0.186473 -0.104608 0.0228545 -0.186473 -0.0989413 0.0295338 -0.213123 -0.0756048 0.0407585 -0.186473 -0.0582312 0.0394483 -0.186473 -0.0501275 0.0361226 -0.213123 -0.0428924 0.0311848 -0.186473 -0.0428924 0.0311848 -0.186473 -0.0368421 0.0248506 -0.186473 -0.0322409 0.0173969 -0.213123 -0.0322409 0.0173969 -0.186473 -0.0292899 0.00914949 -0.213123 -0.0292899 0.00914949 -0.187122 -0.0502268 0.0260288 -0.187573 -0.0506211 0.0266677 -0.187573 -0.0915047 0.0255452 -0.187573 -0.0920018 0.0251242 -0.187573 -0.0908656 0.025419 -0.187573 -0.0490783 -0.0257096 -0.187573 -0.0494343 -0.0263705 -0.187573 -0.0493448 -0.0259924 -0.185773 -0.0245227 -0.0173292 -0.185973 -0.0247106 -0.0172607 -0.185973 -0.0340197 -0.0328376 -0.185973 -0.0407003 -0.0390372 -0.185973 -0.11753 0.00724238 -0.185773 -0.111017 0.0249281 -0.185973 -0.105071 0.0322993 -0.185773 -0.0898305 0.0433861 -0.185973 -0.0897485 0.0432036 -0.185773 -0.080836 0.0464064 -0.185773 -0.0714251 0.047614 -0.185773 -0.0619595 0.0469625 -0.185973 -0.0444132 0.040083 -0.185973 -0.0369358 0.0343063 -0.185773 -0.0305661 0.0272979 -0.185773 -0.025849 0.0190655 -0.185973 -0.0260315 0.0189835 -0.185973 -0.0230236 0.0100262 -0.183973 -0.101984 -0.0267355 -0.183973 -0.103738 -0.0244122 -0.183973 -0.104818 -0.0227908 -0.184973 -0.104646 -0.0211536 -0.183973 -0.108171 -0.0162703 -0.183973 -0.110315 -0.00925868 -0.184973 -0.109952 -0.00522751 -0.184973 -0.118379 -0.00219005 -0.184973 -0.117246 -0.0112715 -0.183973 -0.113506 -0.0195804 -0.184973 -0.110013 -0.0279962 -0.184973 -0.104171 -0.0350415 -0.183973 -0.0965481 -0.0400328 -0.183973 -0.0238033 0.00984712 -0.183973 -0.0448379 0.039405 -0.183973 -0.0374846 0.0337242 -0.184973 -0.0367986 0.0344518 -0.183973 -0.0365761 0.0328446 -0.183973 -0.0267612 0.0186558 -0.184973 -0.080836 0.0464064 -0.184973 -0.0714251 0.047614 -0.184973 -0.0619595 0.0469625 -0.183973 -0.0581737 0.045136 -0.184973 -0.0528028 0.0444768 -0.183973 -0.0531581 0.043542 -0.183973 -0.0974831 0.0378542 -0.184973 -0.0980629 0.038669 -0.184973 -0.0898305 0.0433861 -0.183973 -0.110994 0.0230316 -0.184973 -0.111017 0.0249281 -0.183973 -0.11017 0.0243972 -0.184973 -0.115242 0.0164323 -0.183973 -0.116741 0.00710948 -0.184963 -0.0536417 0.0297421 -0.182042 -0.0928427 -0.00548959 -0.182481 -0.0934856 -0.00595873 -0.1818 -0.0923417 -0.00547484 -0.182481 -0.0927293 -0.00593645 -0.181561 -0.0915765 -0.00590249 -0.180823 -0.0914082 -0.00589753 -0.180823 -0.0943702 -0.00553459 -0.181366 -0.0945129 0.00351513 -0.181366 -0.0942464 -0.00553094 -0.1818 -0.0941662 0.00352535 -0.1818 -0.0938997 -0.00552073 -0.182042 -0.0933987 -0.00550597 -0.1818 -0.0926082 0.00357124 -0.181366 -0.0922615 0.00358145 -0.181366 -0.091995 -0.00546462 -0.180823 -0.0921377 0.0035851 -0.180823 -0.0946366 0.00351149 -0.182042 -0.0936652 0.0035401 -0.182042 -0.0931092 0.00355648 -0.182523 -0.0466276 -0.00457845 -0.181906 -0.0460161 -0.00411024 -0.182295 -0.045778 -0.00455342 -0.180823 -0.0478903 -0.00416545 -0.181448 -0.0477229 -0.00416052 -0.181906 -0.0472656 -0.00414705 -0.181906 -0.0475321 0.00489903 -0.182073 -0.0469073 0.00491743 -0.182073 -0.0466409 -0.00412865 -0.181906 -0.0462826 0.00493583 -0.181448 -0.0458253 0.0049493 -0.181448 -0.0455588 -0.00409677 -0.180823 -0.0456579 0.00495424 -0.181448 -0.0479894 0.00488556 -0.1818 -0.0706598 -0.00483616 -0.182042 -0.0701588 -0.0048214 -0.182042 -0.0696028 -0.00480503 -0.182481 -0.0694894 -0.00525188 -0.182152 -0.0688081 -0.00523181 -0.181561 -0.0683366 -0.00521792 -0.181366 -0.071273 0.0041997 -0.180823 -0.0711303 -0.00485002 -0.1818 -0.0709263 0.00420991 -0.181366 -0.0710065 -0.00484637 -0.182042 -0.0704253 0.00422467 -0.1818 -0.0691018 -0.00479027 -0.181366 -0.0690215 0.00426602 -0.180823 -0.0688978 0.00426967 -0.181366 -0.0687551 -0.00478006 -0.180823 -0.0701694 0.00498361 -0.182042 -0.0698692 0.00424105 -0.1818 -0.0693682 0.00425581 -0.186788 -0.0365572 0.0235086 -0.186788 -0.0333129 0.0182531 -0.186773 -0.0364953 0.0235535 -0.186788 -0.0308882 0.0125727 -0.186832 -0.110961 0.00418039 -0.186873 -0.111209 -0.00197885 -0.186832 -0.111241 -0.00197978 -0.186973 -0.10471 0.0214315 -0.186832 -0.107684 0.0160342 -0.186832 -0.109767 0.0102301 -0.186788 -0.107743 0.0160606 -0.186832 -0.104759 0.021463 -0.186832 -0.101058 0.0263953 -0.186899 -0.101025 0.0263662 -0.186773 -0.104878 0.0215392 -0.186788 -0.0967049 0.0307704 -0.186788 -0.101107 0.026438 -0.186832 -0.0916724 0.0343431 -0.186897 -0.0916497 0.0343062 -0.186973 -0.0861748 0.0371272 -0.186973 -0.0838797 0.0380267 -0.186788 -0.0862233 0.0372408 -0.186899 -0.0803502 0.0391286 -0.186773 -0.0917467 0.0344635 -0.186773 -0.0862533 0.0373112 -0.186832 -0.0803613 0.0391714 -0.186832 -0.0742934 0.0402696 -0.186897 -0.0742889 0.0402265 -0.186897 -0.0681315 0.0404079 -0.186973 -0.0681322 0.0403927 -0.186773 -0.0803968 0.0393083 -0.186788 -0.0743001 0.0403342 -0.186773 -0.0743081 0.0404103 -0.186832 -0.0681295 0.0404512 -0.186899 -0.062016 0.0396687 -0.186832 -0.0620075 0.039712 -0.186773 -0.0619801 0.0398508 -0.186788 -0.056042 0.0381298 -0.186832 -0.056064 0.0380687 -0.186897 -0.0504523 0.0355198 -0.186899 -0.0452632 0.0322003 -0.186773 -0.0560162 0.0382018 -0.186788 -0.0451977 0.0322876 -0.186832 -0.0405948 0.0281763 -0.186832 -0.0366097 0.0234705 -0.186897 -0.033409 0.0182032 -0.186897 -0.111197 -0.0019785 -0.186788 -0.111026 0.00418817 -0.186788 -0.109829 0.0102474 -0.186899 -0.109724 0.0102183 -0.186973 -0.110534 0.0066107 -0.186899 -0.110917 0.00417509 -0.186973 -0.10763 0.0160103 -0.186973 -0.108115 0.0148771 -0.186897 -0.107644 0.0160165 -0.186773 -0.111102 0.00419734 -0.186897 -0.104722 0.0214397 -0.186973 -0.0984578 0.0290276 -0.186973 -0.10403 0.0224599 -0.186788 -0.104814 0.021498 -0.186832 -0.096663 0.0307209 -0.186899 -0.0966344 0.0306871 -0.186788 -0.0917065 0.0343983 -0.186832 -0.0861978 0.0371811 -0.186899 -0.0861804 0.0371404 -0.186973 -0.0755112 0.0400648 -0.186788 -0.0803776 0.0392342 -0.186973 -0.0560837 0.0380136 -0.186973 -0.0584278 0.0387764 -0.186788 -0.0681266 0.040516 -0.186788 -0.0619949 0.0397757 -0.186899 -0.0560789 0.0380271 -0.186973 -0.0504595 0.0355063 -0.186788 -0.050401 0.035615 -0.186832 -0.0452367 0.0322357 -0.186832 -0.0504318 0.0355579 -0.186899 -0.0406263 0.0281453 -0.186973 -0.0433453 0.030651 -0.186973 -0.0334226 0.0181962 -0.186897 -0.0366448 0.023445 -0.186973 -0.0406365 0.0281353 -0.186773 -0.0451518 0.0323488 -0.186788 -0.0405485 0.0282219 -0.186773 -0.040494 0.0282755 -0.186832 -0.0333706 0.0182232 -0.186973 -0.0328717 0.0170935 -0.186973 -0.0310051 0.0125329 -0.186773 -0.0308158 0.0125974 -0.186788 -0.0293372 0.00659443 -0.186832 -0.0309496 0.0125518 -0.186899 -0.0309915 0.0125375 -0.1868 -0.0287179 0.000451059 -0.186832 -0.029401 0.00658288 -0.186832 -0.0287594 0.000449839 -0.186899 -0.0294445 0.00657501 -0.186973 -0.0288179 0.000448115 -0.186773 -0.0290229 -0.0082212 -0.186773 -0.0314686 -0.0165779 -0.186573 -0.0312835 -0.0166538 -0.186573 -0.0354331 -0.0243562 -0.186773 -0.0355983 -0.0242435 -0.186573 -0.048017 -0.0363763 -0.186573 -0.0559014 -0.0401687 -0.186773 -0.0644287 -0.0420407 -0.186773 -0.0816987 -0.0407383 -0.186573 -0.103118 -0.02635 -0.186573 -0.110662 -0.0106676 -0.186773 -0.110467 -0.0106203 -0.186573 -0.111832 -0.00199719 -0.184973 -0.0881338 0.0289849 -0.184973 -0.0881574 0.0284632 -0.186573 -0.0881338 0.0289849 -0.186573 -0.0881574 0.0284632 -0.184073 -0.0287948 -0.0133393 -0.183973 -0.0287482 -0.0126 -0.183973 -0.0282941 -0.0119949 -0.184073 -0.0282295 -0.0120712 -0.184073 -0.0275973 -0.0117435 -0.183973 -0.0268662 -0.0116244 -0.183973 -0.0261752 -0.0119325 -0.184073 -0.025775 -0.0125559 -0.184073 -0.025834 -0.0124518 -0.185873 -0.0255962 -0.0132451 -0.184073 -0.0262352 -0.0120125 -0.184073 -0.0264367 -0.0118836 -0.184073 -0.0268856 -0.0117225 -0.184073 -0.0272426 -0.0116929 -0.184073 -0.028036 -0.0119307 -0.185873 -0.0286041 -0.0125334 -0.184073 -0.0286569 -0.0126408 -0.184073 -0.0286041 -0.0125334 -0.185873 -0.028036 -0.0119307 -0.185873 -0.0272426 -0.0116929 -0.185873 -0.0264367 -0.0118836 -0.185873 -0.025834 -0.0124518 -0.185973 -0.0257489 -0.0123993 -0.185973 -0.0254963 -0.0132422 -0.184073 -0.0296064 0.014213 -0.183973 -0.0295598 0.0149523 -0.184073 -0.0294157 0.015019 -0.183973 -0.028434 0.0159057 -0.184073 -0.0284089 0.0158089 -0.184073 -0.0280542 0.0158594 -0.183973 -0.0276778 0.0159279 -0.183973 -0.0269868 0.0156199 -0.184073 -0.0266456 0.0151006 -0.183973 -0.0264978 0.0150425 -0.184073 -0.0270468 0.0155399 -0.184073 -0.0265866 0.0149965 -0.185873 -0.0266456 0.0151006 -0.184073 -0.0272483 0.0156687 -0.184073 -0.0276972 0.0158298 -0.184073 -0.0288476 0.0156216 -0.184073 -0.0290411 0.0154811 -0.184073 -0.0294685 0.0149116 -0.185873 -0.0294157 0.015019 -0.185973 -0.0295037 0.0150664 -0.185873 -0.0288476 0.0156216 -0.185973 -0.0289001 0.0157067 -0.185873 -0.0280542 0.0158594 -0.185873 -0.0272483 0.0156687 -0.184073 -0.0432593 0.0361205 -0.184073 -0.0440997 0.037482 -0.183973 -0.0440523 0.0375701 -0.183973 -0.0449086 0.0377727 -0.184073 -0.045699 0.0374349 -0.184073 -0.0462672 0.0368323 -0.184073 -0.0464579 0.0360263 -0.185873 -0.0434381 0.0368098 -0.184073 -0.0434971 0.0369139 -0.185873 -0.0434971 0.0369139 -0.185873 -0.0438983 0.0373532 -0.185873 -0.0440997 0.037482 -0.184073 -0.0449057 0.0376727 -0.185873 -0.0458926 0.0372944 -0.185873 -0.0463199 0.0367249 -0.185873 -0.0432593 0.0361205 -0.185873 -0.0445486 0.0376431 -0.185973 -0.0445293 0.0377412 -0.185873 -0.0449057 0.0376727 -0.185873 -0.0452604 0.0376221 -0.185973 -0.0459572 0.0373707 -0.185873 -0.045699 0.0374349 -0.185873 -0.0464579 0.0360263 -0.185973 -0.0464113 0.0367656 -0.185873 -0.0462672 0.0368323 -0.184073 -0.0697139 0.0438628 -0.183973 -0.0698667 0.0447087 -0.184073 -0.0705544 0.0452243 -0.184073 -0.0721537 0.0451772 -0.183973 -0.0713633 0.045515 -0.183973 -0.0722062 0.0452623 -0.184073 -0.0727218 0.0445745 -0.184073 -0.0729125 0.0437686 -0.184073 -0.0699518 0.0446561 -0.185873 -0.0705544 0.0452243 -0.184073 -0.0713603 0.045415 -0.185873 -0.0729125 0.0437686 -0.185873 -0.0727218 0.0445745 -0.185973 -0.0728099 0.044622 -0.185873 -0.0721537 0.0451772 -0.185973 -0.0722062 0.0452623 -0.185973 -0.0713633 0.045515 -0.185873 -0.0713603 0.045415 -0.185873 -0.0699518 0.0446561 -0.185873 -0.0697139 0.0438628 -0.185973 -0.0698667 0.0447087 -0.185973 -0.069614 0.0438657 -0.183973 -0.0976932 0.0361752 -0.184073 -0.0976681 0.0360784 -0.183973 -0.0983649 0.035827 -0.183973 -0.098819 0.0352219 -0.184073 -0.095667 0.0345768 -0.184073 -0.0958458 0.035266 -0.184073 -0.096306 0.0358094 -0.185873 -0.0965074 0.0359383 -0.184073 -0.0969563 0.0360994 -0.185873 -0.0969563 0.0360994 -0.185873 -0.0973134 0.036129 -0.185873 -0.0976681 0.0360784 -0.185873 -0.0981067 0.0358912 -0.184073 -0.0983003 0.0357507 -0.185873 -0.0983003 0.0357507 -0.184073 -0.0987277 0.0351811 -0.185973 -0.09646 0.0360263 -0.185873 -0.0959048 0.0353701 -0.185873 -0.096306 0.0358094 -0.185873 -0.0986749 0.0352885 -0.184073 -0.113645 0.0131238 -0.183973 -0.112855 0.0134616 -0.183973 -0.114301 0.0125686 -0.184073 -0.114213 0.0125211 -0.184073 -0.111205 0.0118094 -0.184073 -0.111443 0.0126027 -0.185873 -0.112046 0.0131709 -0.184073 -0.112046 0.0131709 -0.184073 -0.112852 0.0133616 -0.185873 -0.114213 0.0125211 -0.185873 -0.113645 0.0131238 -0.185973 -0.113698 0.0132089 -0.185873 -0.112852 0.0133616 -0.185973 -0.112855 0.0134616 -0.185873 -0.111443 0.0126027 -0.185973 -0.111358 0.0126553 -0.185973 -0.111105 0.0118123 -0.183973 -0.110546 -0.0148971 -0.183973 -0.111187 -0.0142934 -0.184073 -0.11204 -0.0141908 -0.183973 -0.112043 -0.0140908 -0.183973 -0.11349 -0.0149838 -0.184073 -0.113402 -0.0150312 -0.184073 -0.110631 -0.0149496 -0.185873 -0.110631 -0.0149496 -0.185873 -0.111033 -0.0145103 -0.185873 -0.111234 -0.0143815 -0.184073 -0.111234 -0.0143815 -0.185873 -0.111683 -0.0142204 -0.184073 -0.112833 -0.0144286 -0.185873 -0.113027 -0.0145691 -0.185873 -0.113454 -0.0151386 -0.184073 -0.113592 -0.0158372 -0.185873 -0.110394 -0.015743 -0.185873 -0.110572 -0.0150537 -0.185973 -0.110484 -0.0150077 -0.185973 -0.110973 -0.0144303 -0.185973 -0.111664 -0.0141223 -0.185973 -0.11242 -0.0141446 -0.185873 -0.11204 -0.0141908 -0.185873 -0.112395 -0.0142413 -0.185873 -0.112833 -0.0144286 -0.185973 -0.113092 -0.0144927 -0.185973 -0.113546 -0.0150979 -0.185873 -0.113402 -0.0150312 -0.184073 -0.0943826 -0.0361948 -0.183973 -0.0951916 -0.0359041 -0.183973 -0.0966381 -0.0367971 -0.184073 -0.0935422 -0.0375562 -0.184073 -0.09378 -0.0367629 -0.184073 -0.0951886 -0.0360041 -0.184073 -0.095982 -0.0362419 -0.185873 -0.095982 -0.0362419 -0.184073 -0.0965501 -0.0368445 -0.185973 -0.0968408 -0.0376534 -0.185973 -0.0966381 -0.0367971 -0.185873 -0.0965501 -0.0368445 -0.185873 -0.0951886 -0.0360041 -0.185873 -0.0943826 -0.0361948 -0.185973 -0.0936949 -0.0367104 -0.185873 -0.09378 -0.0367629 -0.185873 -0.0935422 -0.0375562 -0.184073 -0.0670875 -0.0452985 -0.184073 -0.0672664 -0.0446093 -0.183973 -0.0671776 -0.0445633 -0.183973 -0.0676665 -0.0439859 -0.184073 -0.0683769 -0.0437759 -0.183973 -0.0683575 -0.0436778 -0.183973 -0.0702396 -0.0446534 -0.183973 -0.0703861 -0.0453957 -0.185873 -0.0670875 -0.0452985 -0.185873 -0.0673254 -0.0445052 -0.185873 -0.0677265 -0.0440659 -0.184073 -0.0677265 -0.0440659 -0.185873 -0.067928 -0.043937 -0.185873 -0.068734 -0.0437463 -0.184073 -0.0690887 -0.0437969 -0.185873 -0.0690887 -0.0437969 -0.185873 -0.0695273 -0.0439841 -0.185873 -0.0697208 -0.0441246 -0.184073 -0.0697208 -0.0441246 -0.184073 -0.0701482 -0.0446942 -0.185873 -0.0700954 -0.0445868 -0.184073 -0.0702862 -0.0453927 -0.185973 -0.0672403 -0.0444527 -0.185873 -0.0683769 -0.0437759 -0.185973 -0.0687369 -0.0436464 -0.185973 -0.0695798 -0.0438991 -0.185873 -0.0702862 -0.0453927 -0.185973 -0.0701835 -0.0445394 -0.184073 -0.0413723 -0.0352192 -0.184073 -0.0419749 -0.034651 -0.183973 -0.0419275 -0.034563 -0.184073 -0.0435742 -0.0346981 -0.183973 -0.0442304 -0.0352533 -0.184073 -0.0443331 -0.0361067 -0.185873 -0.0411345 -0.0360125 -0.185873 -0.0413723 -0.0352192 -0.184073 -0.0427809 -0.0344603 -0.185873 -0.0441424 -0.0353008 -0.184073 -0.0441424 -0.0353008 -0.185873 -0.0443331 -0.0361067 -0.185973 -0.0442304 -0.0352533 -0.185873 -0.0435742 -0.0346981 -0.185873 -0.0427809 -0.0344603 -0.185973 -0.0427838 -0.0343603 -0.185873 -0.0419749 -0.034651 -0.186573 -0.0817549 -0.0409302 -0.185873 -0.0889538 -0.0380769 -0.186573 -0.0898488 -0.0376085 -0.186273 -0.0812818 -0.0410656 -0.186273 -0.0817549 -0.0409302 -0.186573 -0.0644019 -0.0422389 -0.185973 -0.0644762 -0.0422488 -0.186573 -0.0731472 -0.0424965 -0.185873 -0.0643765 -0.0422354 -0.186273 -0.0559014 -0.0401687 -0.186273 -0.0489695 -0.036947 -0.185973 -0.048017 -0.0363763 -0.186573 -0.0410933 -0.0310276 -0.185973 -0.0312835 -0.0166538 -0.186573 -0.0288261 -0.00825701 -0.185973 -0.0288261 -0.00825701 -0.185973 -0.0281682 0.000467253 -0.185973 -0.0970753 -0.0326766 -0.186573 -0.0970753 -0.0326766 -0.185973 -0.107714 -0.0189052 -0.186573 -0.107714 -0.0189052 -0.185973 -0.111832 -0.00199719 -0.184973 -0.0298551 -0.00286814 -0.184973 -0.030244 -0.00672272 -0.186573 -0.0298175 0.000418671 -0.184973 -0.031179 -0.0112036 -0.184973 -0.0319296 -0.0136754 -0.185773 -0.117246 -0.0112715 -0.185773 -0.114424 -0.0199774 -0.184973 -0.114424 -0.0199774 -0.185773 -0.110013 -0.0279962 -0.185773 -0.0228286 0.010071 -0.184973 -0.0228286 0.010071 -0.184973 -0.025849 0.0190655 -0.184973 -0.0305661 0.0272979 -0.185773 -0.0367986 0.0344518 -0.184973 -0.044307 0.0402524 -0.185773 -0.044307 0.0402524 -0.185773 -0.0528028 0.0444768 -0.185773 -0.0980629 0.038669 -0.185773 -0.105217 0.0324365 -0.184973 -0.105217 0.0324365 -0.185773 -0.115242 0.0164323 -0.184973 -0.117727 0.00727561 -0.185773 -0.117727 0.00727561 -0.185773 -0.118379 -0.00219005 -0.186973 -0.111182 -0.00197806 -0.187573 -0.11003 -0.0105138 -0.186973 -0.108995 -0.0140628 -0.187573 -0.107128 -0.0186235 -0.186973 -0.107128 -0.0186235 -0.186973 -0.106578 -0.0197262 -0.186973 -0.0993636 -0.0296652 -0.187573 -0.102604 -0.0259526 -0.187573 -0.0966548 -0.032181 -0.186973 -0.0895405 -0.0370363 -0.187573 -0.0815723 -0.0403064 -0.186973 -0.0779813 -0.0411845 -0.186973 -0.0815723 -0.0403064 -0.187573 -0.0730983 -0.0418483 -0.186973 -0.0657128 -0.0417413 -0.187573 -0.0644889 -0.0415947 -0.187573 -0.0561203 -0.0395566 -0.187573 -0.0483584 -0.0358232 -0.186973 -0.0538253 -0.0386572 -0.186973 -0.0483584 -0.0358232 -0.186973 -0.0415423 -0.0305576 -0.186973 -0.0389863 -0.0278867 -0.186973 -0.03597 -0.0239898 -0.186973 -0.0323699 -0.0175403 -0.187573 -0.0318849 -0.016407 -0.186973 -0.0290971 -0.00570331 -0.185973 -0.0898488 -0.0376085 -0.185973 -0.0901097 -0.0380927 -0.185973 -0.0974311 -0.033096 -0.185973 -0.103118 -0.02635 -0.185973 -0.103554 -0.0266863 -0.185973 -0.110662 -0.0106676 -0.185973 -0.111196 -0.0107977 -0.185973 -0.112382 -0.00201339 -0.185973 -0.111715 0.00682553 -0.185973 -0.104567 0.0228263 -0.185973 -0.0989067 0.0294976 -0.185973 -0.0919831 0.0348464 -0.185973 -0.0992866 0.0298954 -0.185973 -0.0840987 0.0386387 -0.185973 -0.0755981 0.0407089 -0.185973 -0.0756717 0.041254 -0.185973 -0.0668115 0.041515 -0.185973 -0.0582452 0.0394003 -0.185973 -0.0501513 0.0360786 -0.185973 -0.0580907 0.0399281 -0.185973 -0.0498904 0.0365628 -0.185973 -0.042569 0.0315661 -0.185973 -0.0429248 0.0311467 -0.185973 -0.0368816 0.0248201 -0.185973 -0.0317903 0.0176137 -0.185973 -0.0288041 0.0092678 -0.185973 -0.028285 -0.00835547 -0.185973 -0.0354331 -0.0243562 -0.185973 -0.0349788 -0.0246663 -0.185973 -0.0410933 -0.0310276 -0.185973 -0.0477281 -0.0368443 -0.185973 -0.0487965 -0.0368459 -0.185973 -0.0730725 -0.042502 -0.186973 -0.0294587 0.00657244 -0.186973 -0.02997 0.00898385 -0.187573 -0.0328717 0.0170935 -0.186973 -0.0366571 0.0234361 -0.186973 -0.037396 0.0244227 -0.186973 -0.0452718 0.0321889 -0.187573 -0.0433453 0.030651 -0.187573 -0.0584278 0.0387764 -0.187573 -0.0669018 0.0403184 -0.186973 -0.0620188 0.0396546 -0.186973 -0.0669018 0.0403184 -0.187573 -0.0838797 0.0380267 -0.187573 -0.0755112 0.0400648 -0.186973 -0.0803466 0.0391147 -0.186973 -0.0742873 0.0402114 -0.187573 -0.0916417 0.0342933 -0.186973 -0.0916417 0.0342933 -0.186973 -0.101014 0.0263567 -0.187573 -0.10403 0.0224599 -0.186973 -0.0966251 0.0306762 -0.187573 -0.108115 0.0148771 -0.186973 -0.10971 0.0102145 -0.187573 -0.110534 0.0066107 -0.186973 -0.110903 0.00417337 -0.187573 -0.111182 -0.00197806 -0.183973 -0.0365577 -0.0248285 -0.183973 -0.0960345 -0.0361568 -0.183973 -0.103465 -0.0343333 -0.183973 -0.0943352 -0.0361067 -0.183973 -0.0926507 -0.0299445 -0.183973 -0.0936949 -0.0367104 -0.183973 -0.0900096 -0.0313674 -0.183973 -0.0934422 -0.0375533 -0.183973 -0.0894549 -0.0365487 -0.183973 -0.0947146 -0.0392489 -0.183973 -0.0954708 -0.0392712 -0.183973 -0.11627 -0.0110545 -0.183973 -0.112886 -0.0143435 -0.183973 -0.110294 -0.01574 -0.183973 -0.111182 -0.00197806 -0.183973 -0.103567 -0.0266967 -0.183973 -0.109186 -0.0274336 -0.183973 -0.111943 -0.0174893 -0.183973 -0.111358 0.0126553 -0.183973 -0.111105 0.0118123 -0.183973 -0.111308 0.010956 -0.183973 -0.112755 0.010063 -0.183973 -0.117379 -0.00216061 -0.183973 -0.115739 -0.00211228 -0.183973 -0.114251 0.0108693 -0.183973 -0.114307 0.016077 -0.183973 -0.105035 0.023146 -0.183973 -0.111998 0.0132589 -0.183973 -0.10507 0.0208569 -0.183973 -0.104984 0.0209962 -0.183973 -0.103437 0.0233063 -0.183973 -0.113698 0.0132089 -0.183973 -0.104489 0.0317505 -0.183973 -0.0902868 0.033176 -0.183973 -0.0957697 0.0337234 -0.183973 -0.0942847 0.0325171 -0.183973 -0.0963733 0.0330831 -0.183973 -0.0871507 0.0347247 -0.183973 -0.0875659 0.0333718 -0.183973 -0.0884976 0.0321105 -0.183973 -0.0958483 0.038967 -0.183973 -0.096937 0.0361975 -0.183973 -0.096246 0.0358894 -0.183973 -0.095757 0.035312 -0.183973 -0.095567 0.0345797 -0.183973 -0.0923641 0.033322 -0.183973 -0.0862904 0.0358484 -0.183973 -0.0850927 0.0366022 -0.183973 -0.0712632 0.0421164 -0.183973 -0.0842898 0.0391727 -0.183973 -0.0727598 0.0429227 -0.183973 -0.0730125 0.0437656 -0.183973 -0.0894208 0.0424738 -0.183973 -0.070507 0.0453123 -0.183973 -0.0621256 0.0459764 -0.183973 -0.0698166 0.0430094 -0.183973 -0.0728099 0.044622 -0.183973 -0.0806121 0.0454318 -0.183973 -0.0713957 0.0466145 -0.183973 -0.0364328 0.0251668 -0.183973 -0.054474 0.0343466 -0.183973 -0.0558931 0.0367438 -0.183973 -0.0463552 0.0368797 -0.183973 -0.0457516 0.03752 -0.183973 -0.043412 0.0369664 -0.183973 -0.0380584 0.0252575 -0.183973 -0.0409723 0.0284725 -0.183973 -0.0439656 0.0346268 -0.183973 -0.0477165 0.0338888 -0.183973 -0.0456649 0.0345768 -0.183973 -0.0463052 0.0351804 -0.183973 -0.0279571 0.0125609 -0.183973 -0.0288134 0.0127635 -0.183973 -0.0263078 0.0143102 -0.183973 -0.0355076 0.0217675 -0.183973 -0.0291057 0.0155575 -0.183973 -0.0313808 0.0267181 -0.183973 -0.0254623 -0.0169869 -0.183973 -0.0256989 -0.0140985 -0.183973 -0.0254963 -0.0132422 -0.183973 -0.0232049 -0.00831308 -0.183973 -0.0286421 -0.0141852 -0.183973 -0.0288948 -0.0133423 -0.183973 -0.0276224 -0.0116467 -0.183973 -0.0256862 -0.0125099 -0.183973 -0.0226206 0.000630666 -0.183973 -0.0412372 -0.0368659 -0.183973 -0.0411866 -0.038402 -0.183973 -0.0426837 -0.0377589 -0.183973 -0.046362 -0.0381364 -0.183973 -0.0441804 -0.0369526 -0.183973 -0.0456711 -0.0285607 -0.183973 -0.0436268 -0.034613 -0.183973 -0.0380509 -0.0267783 -0.183973 -0.0427838 -0.0343603 -0.183973 -0.0412872 -0.0351666 -0.183973 -0.0349647 -0.0246759 -0.183973 -0.0271455 -0.0149915 -0.183973 -0.0485815 -0.0316477 -0.183973 -0.0782691 0.0386775 -0.183973 -0.0580859 0.0399446 -0.183973 -0.0640669 0.0390959 -0.187573 -0.0498707 0.0266898 -0.187573 -0.0504595 0.0355063 -0.187573 -0.0502489 0.0267792 -0.187573 -0.0897954 -0.0268084 -0.187573 -0.0911707 0.025555 -0.187573 -0.0905658 0.0248406 -0.187573 -0.0508877 0.0263849 -0.187573 -0.0906497 0.025164 -0.187573 -0.0894172 -0.0268979 -0.187573 -0.0906552 0.0244624 -0.187573 -0.0891345 -0.0271644 -0.187573 -0.048706 -0.025598 -0.187573 -0.0890229 -0.0275367 -0.187573 -0.02997 0.00898385 -0.187573 -0.037396 0.0244227 -0.187573 -0.0494764 0.0260509 -0.187573 -0.049588 0.0264232 -0.187573 -0.0901676 -0.02692 -0.187573 -0.091955 0.0244242 -0.187573 -0.0920665 0.0247964 -0.187573 -0.0918013 0.0253914 -0.187573 -0.0984578 0.0290276 -0.187573 -0.0892881 -0.0281317 -0.187573 -0.0890876 -0.0278645 -0.187573 -0.0288179 0.000448115 -0.187573 -0.0483279 -0.0256875 -0.187573 -0.0480451 -0.0259541 -0.187573 -0.0294656 -0.00814064 -0.187573 -0.0479335 -0.0263263 -0.187573 -0.03597 -0.0239898 -0.187573 -0.0415423 -0.0305576 -0.187573 -0.0479983 -0.0266541 -0.187573 -0.0904342 -0.0272027 -0.187573 -0.0481988 -0.0269213 -0.187573 -0.0484954 -0.0270751 -0.187573 -0.0488294 -0.0270849 -0.187573 -0.0904398 -0.0279043 -0.187573 -0.0902239 -0.0281592 -0.187573 -0.0895405 -0.0370363 -0.187573 -0.0895848 -0.0282854 -0.187573 -0.0493504 -0.0266939 -0.184973 -0.0405787 -0.039196 -0.185773 -0.0338704 -0.0329707 -0.184973 -0.0338704 -0.0329707 -0.185773 -0.0284538 -0.0255938 -0.184973 -0.0284538 -0.0255938 -0.184973 -0.0245227 -0.0173292 -0.185773 -0.0222177 -0.00847232 -0.185773 -0.021621 0.00066011 -0.184973 -0.021621 0.00066011 -0.184973 -0.103973 -0.0222562 -0.184973 -0.107245 -0.0158939 -0.186573 -0.104646 -0.0211536 -0.184973 -0.108139 -0.0134706 -0.184973 -0.109336 -0.00905252 -0.186573 -0.109952 -0.00522751 -0.186573 -0.110003 0.00321223 -0.184973 -0.107644 0.0133402 -0.186573 -0.108291 0.0114767 -0.184973 -0.108291 0.0114767 -0.184973 -0.0999533 0.0260463 -0.184973 -0.0936953 0.0317092 -0.184973 -0.0416769 0.0277629 -0.184973 -0.0298175 0.000418671 -0.184973 -0.0303007 0.00555998 -0.186573 -0.0307992 0.00814219 -0.184973 -0.0332514 0.0155316 -0.183973 -0.0701334 -0.0462386 -0.183973 -0.0686368 -0.0470449 -0.183973 -0.0671902 -0.0461519 -0.183973 -0.0653936 -0.0470055 -0.183973 -0.0669876 -0.0452956 -0.183973 -0.0651655 -0.0460175 -0.183973 -0.071542 -0.0333245 -0.183973 -0.0697855 -0.0440483 -0.183973 -0.0724473 -0.0339687 -0.183973 -0.0691138 -0.0437001 -0.183973 -0.0656638 -0.0336516 -0.186573 -0.0421473 0.0282224 -0.186573 -0.0458085 0.0218237 -0.186573 -0.0651428 -0.0327216 -0.186573 -0.0999533 0.0260463 -0.186573 -0.0954793 0.0203606 -0.186573 -0.0529769 0.0260642 -0.186573 -0.0503387 0.0232808 -0.186573 -0.0414375 -0.0274355 -0.186573 -0.0446035 -0.00451883 -0.186573 -0.0399916 -0.0270757 -0.186573 -0.0388264 -0.0261469 -0.186573 -0.0441077 -0.00437019 -0.186573 -0.0348209 -0.0202192 -0.186573 -0.0319296 -0.0136754 -0.186573 -0.0436334 -0.00348982 -0.186573 -0.030244 -0.00672272 -0.186573 -0.104891 0.0192015 -0.186573 -0.0968173 0.0172556 -0.186573 -0.0964924 0.0189564 -0.186573 -0.0527122 0.0324885 -0.186573 -0.037082 0.0223097 -0.186573 -0.0332514 0.0155316 -0.186573 -0.089853 0.022708 -0.186573 -0.090806 0.032283 -0.186573 -0.0936953 0.0317092 -0.186573 -0.0984078 -0.0287964 -0.186573 -0.0969432 -0.0290706 -0.186573 -0.0956353 -0.00588802 -0.186573 -0.108139 -0.0134706 -0.186573 -0.0961606 -0.00503709 -0.186573 -0.072332 -0.0324996 -0.186573 -0.0491042 -0.0296622 -0.186573 -0.0457005 -0.0275611 -0.186573 -0.0500169 -0.0318584 -0.186573 -0.0640965 -0.035273 -0.186573 -0.0605273 -0.0367387 -0.186573 -0.0645253 -0.033972 -0.186573 -0.0898185 -0.0300328 -0.186573 -0.0889135 -0.0313044 -0.186573 -0.0823475 -0.035856 -0.186573 -0.0747349 -0.0366164 -0.186573 -0.0759693 -0.0372104 -0.186573 -0.0773389 -0.0372339 -0.185773 -0.0669773 -0.0490705 -0.185973 -0.0293385 0.00913766 -0.185973 -0.0322859 0.0173753 -0.186573 -0.0368816 0.0248201 -0.186573 -0.0429248 0.0311467 -0.186573 -0.0501513 0.0360786 -0.186573 -0.0582452 0.0394003 -0.186573 -0.0668529 0.0409665 -0.185973 -0.0668529 0.0409665 -0.186573 -0.0840987 0.0386387 -0.186573 -0.0989067 0.0294976 -0.186573 -0.104567 0.0228263 -0.185973 -0.108717 0.0151239 -0.186573 -0.111174 0.00672706 -0.185973 -0.111174 0.00672706 -0.186773 -0.0755714 0.0405107 -0.186773 -0.0840313 0.0384504 -0.186773 -0.091878 0.0346762 -0.186773 -0.0967544 0.0308288 -0.186773 -0.0987686 0.029353 -0.186773 -0.104402 0.0227135 -0.186773 -0.101164 0.0264884 -0.186773 -0.107813 0.0160918 -0.186773 -0.108532 0.015048 -0.186773 -0.109903 0.0102678 -0.186773 -0.0292619 0.00660806 -0.186773 -0.0324662 0.0172886 -0.186773 -0.111382 -0.00198395 -0.186773 -0.111632 -0.00199131 -0.186773 -0.109184 -0.0141274 -0.186773 -0.107534 -0.0188185 -0.186773 -0.028618 0.000454003 -0.186773 -0.033245 0.0182883 -0.186773 -0.0430542 0.0309942 -0.186773 -0.0503647 0.0356824 -0.186773 -0.0681231 0.0405925 -0.186773 -0.0668679 0.0407671 -0.186773 -0.106755 -0.0198182 -0.186773 -0.10296 -0.0262277 -0.186773 -0.0969459 -0.0325241 -0.186773 -0.0995061 -0.0298055 -0.186773 -0.089754 -0.0374325 -0.186773 -0.07802 -0.0413807 -0.186773 -0.0731321 -0.042297 -0.186773 -0.071877 -0.0421224 -0.186773 -0.0559688 -0.0399803 -0.186773 -0.048122 -0.0362061 -0.186773 -0.0432457 -0.0323587 -0.186773 -0.0412315 -0.030883 -0.186773 -0.0388357 -0.0280183 -0.183973 -0.0571331 0.0374258 -0.175523 -0.0640669 0.0390959 -0.183973 -0.0711866 0.0395176 -0.175523 -0.0711866 0.0395176 -0.175523 -0.0782691 0.0386775 -0.186573 -0.0951316 -0.00600721 -0.182152 -0.0941669 -0.0059788 -0.182152 -0.092048 -0.00591638 -0.180823 -0.0715668 -0.00531307 -0.181561 -0.0946384 -0.00599269 -0.175523 -0.0951316 -0.00600721 -0.179973 -0.0945791 -0.00599094 -0.179351 -0.0690179 -0.00523799 -0.184048 -0.0676935 -0.00519898 -0.184211 -0.0738778 -0.00538115 -0.179351 -0.0939571 -0.00597262 -0.176696 -0.0888843 -0.00582319 -0.179351 -0.0922578 -0.00592256 -0.178398 -0.0905856 -0.0058733 -0.180723 -0.0912083 -0.00589165 -0.179351 -0.0707172 -0.00528805 -0.176427 -0.0753857 -0.00542556 -0.182481 -0.0702457 -0.00527416 -0.182152 -0.070927 -0.00529423 -0.182703 -0.0728702 -0.00535147 -0.181561 -0.0713985 -0.00530812 -0.180923 -0.0725164 -0.00534105 -0.178944 -0.0728702 -0.00535147 -0.176073 -0.0771644 -0.00547796 -0.186573 -0.0676935 -0.00519898 -0.185573 -0.0771644 -0.00547796 -0.18495 -0.0888843 -0.00582319 -0.175523 -0.0446035 -0.00451883 -0.179973 -0.045156 -0.0045351 -0.181673 -0.045156 -0.0045351 -0.182295 -0.0474773 -0.00460348 -0.180923 -0.0485268 -0.00463439 -0.181673 -0.0480992 -0.0046218 -0.18495 -0.0648947 -0.00511654 -0.176696 -0.0508508 -0.00470285 -0.179351 -0.0474773 -0.00460348 -0.179973 -0.0480992 -0.0046218 -0.178398 -0.0491495 -0.00465274 -0.183248 -0.066596 -0.00516665 -0.178398 -0.066596 -0.00516665 -0.185573 -0.0625707 -0.00504808 -0.175523 -0.0436334 -0.00348982 -0.183973 -0.0540977 0.0322646 -0.175523 -0.0529769 0.0260642 -0.186573 -0.0885729 0.0250156 -0.183973 -0.087819 0.0312713 -0.175523 -0.0910427 0.0220818 -0.175023 -0.0518533 0.0234286 -0.175023 -0.0951463 -0.00550743 -0.175023 -0.0895394 0.0223185 -0.175023 -0.093824 0.020726 -0.175023 -0.0885499 0.023494 -0.175023 -0.0956608 -0.00502237 -0.175023 -0.0963175 0.0172704 -0.175023 -0.0951467 0.0199872 -0.175023 -0.0441332 -0.00350454 -0.175023 -0.0867062 0.0344958 -0.175023 -0.0849054 0.0361386 -0.175023 -0.0870695 0.033312 -0.175023 -0.0880764 0.0249558 -0.175023 -0.0711719 0.0390178 -0.175023 -0.053469 0.0259752 -0.175023 -0.0572927 0.0369519 -0.186073 -0.049581 -0.0316772 -0.186073 -0.0494722 -0.0353709 -0.184973 -0.0731621 -0.046253 -0.186191 -0.0734997 -0.0347914 -0.184973 -0.0735117 -0.0343829 -0.185773 -0.073273 -0.0424868 -0.186273 -0.073273 -0.0424868 -0.186573 -0.0715715 -0.0323249 -0.186273 -0.0642769 -0.0422218 -0.186073 -0.0642828 -0.0420207 -0.184973 -0.0645156 -0.0341179 -0.185773 -0.0892711 -0.0386655 -0.184973 -0.0892711 -0.0386655 -0.186073 -0.0812279 -0.0408731 -0.186073 -0.0745978 -0.036763 -0.186073 -0.0759146 -0.037403 -0.186073 -0.088571 -0.032681 -0.186073 -0.0885641 -0.0328255 -0.186073 -0.0884553 -0.0365192 -0.186073 -0.0886498 -0.0376735 -0.186073 -0.0887692 -0.0379462 -0.186073 -0.0642821 -0.035352 -0.186073 -0.0498502 -0.0319691 -0.186073 -0.0490749 -0.0367769 -0.186073 -0.0492101 -0.0365117 -0.186073 -0.0564308 -0.0401426 -0.186073 -0.0604763 -0.0369321 -0.186073 -0.0632913 -0.0364299 -0.184973 -0.0949297 -0.0416802 -0.184973 -0.0926165 -0.0414243 -0.185773 -0.0926165 -0.0414243 -0.185773 -0.0906697 -0.0401489 -0.184973 -0.047048 -0.038864 -0.185773 -0.0450295 -0.0400225 -0.185773 -0.0427052 -0.0401418 -0.184973 -0.0450295 -0.0400225 -0.184973 -0.0427052 -0.0401418 -0.185773 -0.065533 -0.0485938 -0.185773 -0.064508 -0.04747 -0.184973 -0.064508 -0.04747 -0.184973 -0.064166 -0.045988 -0.185773 -0.0716441 -0.0487738 -0.184973 -0.0701742 -0.0491647 -0.186265 -0.0645156 -0.0341179 -0.184973 -0.0655662 -0.0324161 -0.186573 -0.0665736 -0.0321777 -0.186573 -0.0658041 -0.0323073 -0.184973 -0.0648129 -0.0331263 -0.186573 -0.0646903 -0.0333574 -0.186265 -0.0735117 -0.0343829 -0.186271 -0.0735125 -0.0343099 -0.186273 -0.0735107 -0.0342366 -0.186573 -0.0735107 -0.0342366 -0.186573 -0.0733821 -0.0336134 -0.186573 -0.0729678 -0.0329521 -0.184973 -0.072332 -0.0324996 -0.184973 -0.0715715 -0.0323249 -0.186573 -0.0556085 -0.0350684 -0.186273 -0.0556085 -0.0350684 -0.186273 -0.0605273 -0.0367387 -0.186273 -0.0871153 -0.0337939 -0.186573 -0.0871153 -0.0337939 -0.186573 -0.0524881 0.0248117 -0.186573 -0.0515632 0.0238359 -0.175523 -0.0515632 0.0238359 -0.175523 -0.0503387 0.0232808 -0.186573 -0.0910427 0.0220818 -0.175523 -0.089853 0.022708 -0.186573 -0.0889871 0.0237365 -0.175523 -0.0889871 0.0237365 -0.186573 -0.04429 0.0188029 -0.186573 -0.0447144 0.0204816 -0.175523 -0.0458085 0.0218237 -0.186573 -0.0473672 0.0225776 -0.186573 -0.0939676 0.021205 -0.175523 -0.0939676 0.021205 -0.175523 -0.0862904 0.0358484 -0.175523 -0.0871507 0.0347247 -0.183973 -0.0549681 0.0356727 -0.175523 -0.0549681 0.0356727 -0.175523 -0.0558931 0.0367438 -0.175523 -0.0441077 -0.00437019 -0.186573 -0.0437526 -0.00399354 -0.175523 -0.0437526 -0.00399354 -0.186573 -0.096012 -0.00553293 -0.175523 -0.0956353 -0.00588802 -0.185773 -0.0888644 -0.0381221 -0.186173 -0.0888153 -0.0380349 -0.184973 -0.0886498 -0.0376735 -0.185773 -0.0489695 -0.036947 -0.184973 -0.0492101 -0.0365117 -0.184973 -0.0494722 -0.0353709 -0.186273 -0.0887183 -0.0318374 -0.184973 -0.0891587 -0.0308421 -0.184973 -0.0885641 -0.0328255 -0.186573 -0.0926801 -0.028945 -0.186573 -0.0911411 -0.0292043 -0.184973 -0.0898185 -0.0300328 -0.186573 -0.0494853 -0.0306817 -0.184973 -0.049581 -0.0316772 -0.186573 -0.0476839 -0.0281557 -0.186573 -0.0881183 -0.0329807 -0.186573 -0.0887183 -0.0318374 -0.186273 -0.0494853 -0.0306817 -0.186273 -0.0500124 -0.0318521 -0.186573 -0.0509703 -0.0327292 -0.186573 -0.0618959 -0.0367959 -0.186573 -0.0631631 -0.0362755 -0.186273 -0.0631767 -0.0362661 -0.186573 -0.0738621 -0.0355606 -0.186273 -0.0747219 -0.0366061 -0.186273 -0.0773389 -0.0372339 -0.180923 -0.0669487 0.00602782 -0.180723 -0.0491751 -0.00300429 -0.178698 -0.0497174 -0.00302026 -0.179173 -0.0497645 0.00653401 -0.177859 -0.0503608 -0.00303922 -0.177859 -0.050642 0.00650816 -0.180923 -0.0494563 0.00654308 -0.180723 -0.0494563 0.00654308 -0.184973 -0.0535046 0.00642384 -0.184665 -0.0519554 0.00646947 -0.184665 -0.0516741 -0.0030779 -0.183787 -0.050642 0.00650816 -0.180923 -0.0491751 -0.00300429 -0.180923 -0.0666675 -0.00351956 -0.182948 -0.0664064 0.00604379 -0.184431 -0.0649246 0.00608744 -0.184431 -0.0646434 -0.00345993 -0.184973 -0.0629005 0.00614706 -0.177216 -0.0649246 0.00608744 -0.177216 -0.0646434 -0.00345993 -0.178698 -0.0664064 0.00604379 -0.180723 -0.0669487 0.00602782 -0.176673 -0.0626192 -0.00340031 -0.180723 -0.0734459 0.00583643 -0.180923 -0.0731647 -0.00371094 -0.179173 -0.0737541 0.00582735 -0.177859 -0.0746316 0.0058015 -0.176981 -0.0756637 -0.00378455 -0.184973 -0.0774942 0.00571718 -0.184431 -0.07547 0.00577681 -0.184431 -0.0751888 -0.00377056 -0.183787 -0.0743504 -0.00374587 -0.182473 -0.0734728 -0.00372002 -0.180923 -0.0734459 0.00583643 -0.182948 -0.073707 -0.00372692 -0.184973 -0.0868901 0.00544041 -0.184973 -0.0772129 -0.00383019 -0.184431 -0.0889142 0.00538079 -0.184431 -0.088633 -0.00416658 -0.176673 -0.0868901 0.00544041 -0.180723 -0.0909383 0.00532117 -0.178698 -0.0901147 -0.00421023 -0.175023 -0.0447898 0.0187882 -0.175523 -0.04429 0.0188029 -0.175523 -0.0447144 0.0204816 -0.175023 -0.0451612 0.0202571 -0.175023 -0.0461185 0.0214314 -0.175023 -0.0446182 -0.00401904 -0.175023 -0.0443703 -0.00394472 -0.175023 -0.0441928 -0.0037564 -0.175523 -0.0473672 0.0225776 -0.175023 -0.0474824 0.0220911 -0.175523 -0.0676935 -0.00519898 -0.175023 -0.0529103 0.0245438 -0.175523 -0.0524881 0.0248117 -0.175023 -0.0504538 0.0227942 -0.175523 -0.096012 -0.00553293 -0.175023 -0.0955865 -0.00527029 -0.175023 -0.0953982 -0.00544783 -0.175523 -0.054474 0.0343466 -0.175023 -0.054966 0.0342577 -0.175523 -0.0961606 -0.00503709 -0.175023 -0.0553984 0.035418 -0.175023 -0.0562077 0.0363552 -0.175523 -0.0571331 0.0374258 -0.175523 -0.0954793 0.0203606 -0.175023 -0.0960333 0.0187585 -0.175523 -0.0964924 0.0189564 -0.175523 -0.0968173 0.0172556 -0.175023 -0.0641406 0.0386013 -0.175023 -0.0781666 0.0381882 -0.175523 -0.0850927 0.0366022 -0.175023 -0.0908991 0.0216028 -0.175023 -0.0859534 0.035479 -0.175523 -0.0885729 0.0250156 -0.175523 -0.0875659 0.0333718 -0.185973 -0.0410345 -0.0360096 -0.185873 -0.0413252 -0.0368185 -0.185873 -0.0418933 -0.0374211 -0.185973 -0.0412372 -0.0368659 -0.185873 -0.0426867 -0.0376589 -0.185873 -0.0440953 -0.0369001 -0.185973 -0.0435401 -0.0375562 -0.185973 -0.0441804 -0.0369526 -0.185973 -0.0444331 -0.0361097 -0.185873 -0.0434926 -0.0374682 -0.184073 -0.0426867 -0.0376589 -0.184073 -0.0413252 -0.0368185 -0.183973 -0.0444331 -0.0361097 -0.184073 -0.0440953 -0.0369001 -0.184073 -0.0434926 -0.0374682 -0.183973 -0.0435401 -0.0375562 -0.184073 -0.0418933 -0.0374211 -0.183973 -0.0418408 -0.0375062 -0.184073 -0.0411345 -0.0360125 -0.183973 -0.0410345 -0.0360096 -0.185873 -0.0672783 -0.0461045 -0.185973 -0.0686368 -0.0470449 -0.185873 -0.0686397 -0.0469449 -0.185873 -0.0694457 -0.0467542 -0.185973 -0.0694931 -0.0468423 -0.185973 -0.0701334 -0.0462386 -0.185873 -0.0700483 -0.0461861 -0.184073 -0.0686397 -0.0469449 -0.185873 -0.0678464 -0.0467071 -0.184073 -0.0678464 -0.0467071 -0.184073 -0.0700483 -0.0461861 -0.184073 -0.0694457 -0.0467542 -0.183973 -0.0694931 -0.0468423 -0.183973 -0.0677939 -0.0467922 -0.184073 -0.0672783 -0.0461045 -0.185973 -0.0965881 -0.0384963 -0.185873 -0.0967408 -0.0376505 -0.185873 -0.0961018 -0.0388831 -0.185973 -0.0959478 -0.0391 -0.185873 -0.0959004 -0.039012 -0.185873 -0.0950944 -0.0392027 -0.185873 -0.0947397 -0.0391521 -0.185973 -0.0942485 -0.0390499 -0.185873 -0.0937329 -0.0383622 -0.185973 -0.0934422 -0.0375533 -0.184073 -0.0967408 -0.0376505 -0.185873 -0.096503 -0.0384438 -0.185873 -0.0954515 -0.0391731 -0.184073 -0.0954515 -0.0391731 -0.184073 -0.0947397 -0.0391521 -0.185873 -0.0943011 -0.0389648 -0.184073 -0.0941075 -0.0388244 -0.185873 -0.0941075 -0.0388244 -0.184073 -0.0936801 -0.0382548 -0.183973 -0.0968408 -0.0376534 -0.184073 -0.096562 -0.0383397 -0.183973 -0.0966508 -0.0383857 -0.183973 -0.0961618 -0.0389631 -0.184073 -0.0961018 -0.0388831 -0.183973 -0.0940429 -0.0389007 -0.183973 -0.0935888 -0.0382955 -0.185973 -0.110496 -0.0165964 -0.185973 -0.112799 -0.0172867 -0.185873 -0.113592 -0.0158372 -0.185973 -0.113692 -0.0158401 -0.185873 -0.113354 -0.0166305 -0.184073 -0.113354 -0.0166305 -0.185873 -0.112752 -0.0171987 -0.184073 -0.111946 -0.0173894 -0.185873 -0.111946 -0.0173894 -0.184073 -0.111153 -0.0171516 -0.185873 -0.111153 -0.0171516 -0.185873 -0.110584 -0.0165489 -0.184073 -0.110394 -0.015743 -0.183973 -0.113692 -0.0158401 -0.183973 -0.11344 -0.0166831 -0.184073 -0.112752 -0.0171987 -0.183973 -0.112799 -0.0172867 -0.183973 -0.1111 -0.0172367 -0.184073 -0.110584 -0.0165489 -0.183973 -0.110496 -0.0165964 -0.185973 -0.111308 0.010956 -0.185973 -0.111912 0.0103157 -0.185873 -0.114404 0.0117152 -0.185873 -0.114166 0.0109218 -0.184073 -0.114166 0.0109218 -0.184073 -0.113563 0.0103537 -0.185873 -0.113563 0.0103537 -0.184073 -0.112757 0.010163 -0.185873 -0.112757 0.010163 -0.185873 -0.111964 0.0104008 -0.184073 -0.111964 0.0104008 -0.185873 -0.111396 0.0110034 -0.184073 -0.111396 0.0110034 -0.185873 -0.111205 0.0118094 -0.184073 -0.114404 0.0117152 -0.183973 -0.114504 0.0117122 -0.183973 -0.113611 0.0102657 -0.183973 -0.111912 0.0103157 -0.185873 -0.0958577 0.0337708 -0.185973 -0.0963733 0.0330831 -0.185973 -0.0972162 0.0328304 -0.185873 -0.0986278 0.0336892 -0.185973 -0.0987129 0.0336367 -0.185873 -0.0988656 0.0344826 -0.184073 -0.0988656 0.0344826 -0.185873 -0.0980252 0.0331211 -0.185873 -0.0972192 0.0329304 -0.184073 -0.0972192 0.0329304 -0.185873 -0.0964258 0.0331682 -0.185873 -0.095667 0.0345768 -0.183973 -0.0989656 0.0344796 -0.184073 -0.0986278 0.0336892 -0.184073 -0.0980252 0.0331211 -0.183973 -0.0987129 0.0336367 -0.183973 -0.0980726 0.033033 -0.183973 -0.0972162 0.0328304 -0.184073 -0.0964258 0.0331682 -0.184073 -0.0958577 0.0337708 -0.185973 -0.0698166 0.0430094 -0.185973 -0.0712632 0.0421164 -0.185873 -0.0720721 0.0424071 -0.185973 -0.0721195 0.0423191 -0.185973 -0.0727598 0.0429227 -0.185873 -0.0726747 0.0429752 -0.184073 -0.0726747 0.0429752 -0.184073 -0.0712661 0.0422164 -0.185873 -0.0712661 0.0422164 -0.185873 -0.0704728 0.0424542 -0.184073 -0.0704728 0.0424542 -0.185873 -0.0699046 0.0430568 -0.184073 -0.0720721 0.0424071 -0.183973 -0.0721195 0.0423191 -0.183973 -0.0704203 0.0423691 -0.184073 -0.0699046 0.0430568 -0.183973 -0.069614 0.0438657 -0.185973 -0.0431593 0.0361235 -0.185973 -0.043362 0.0352671 -0.185873 -0.0440181 0.0347119 -0.185873 -0.0448115 0.0344741 -0.185973 -0.0439656 0.0346268 -0.185973 -0.0456649 0.0345768 -0.185973 -0.0463052 0.0351804 -0.185873 -0.0462201 0.035233 -0.184073 -0.0462201 0.035233 -0.184073 -0.0456174 0.0346648 -0.185873 -0.0456174 0.0346648 -0.185873 -0.04345 0.0353146 -0.184073 -0.04345 0.0353146 -0.183973 -0.0465578 0.0360234 -0.184073 -0.0448115 0.0344741 -0.183973 -0.0448085 0.0343742 -0.184073 -0.0440181 0.0347119 -0.183973 -0.043362 0.0352671 -0.183973 -0.0431593 0.0361235 -0.185873 -0.0264078 0.0143072 -0.185873 -0.0265985 0.0135013 -0.185973 -0.0265105 0.0134539 -0.185873 -0.0271667 0.0128986 -0.185973 -0.0271141 0.0128136 -0.185973 -0.0279571 0.0125609 -0.185973 -0.0288134 0.0127635 -0.185873 -0.0296064 0.014213 -0.185973 -0.0297064 0.0142101 -0.185873 -0.0293686 0.0134197 -0.185873 -0.028766 0.0128515 -0.185873 -0.02796 0.0126608 -0.184073 -0.02796 0.0126608 -0.184073 -0.0271667 0.0128986 -0.184073 -0.0265985 0.0135013 -0.184073 -0.0264078 0.0143072 -0.184073 -0.0293686 0.0134197 -0.183973 -0.0297064 0.0142101 -0.183973 -0.0294537 0.0133672 -0.184073 -0.028766 0.0128515 -0.183973 -0.0271141 0.0128136 -0.183973 -0.0265105 0.0134539 -0.185873 -0.0257869 -0.0140511 -0.185973 -0.0271455 -0.0149915 -0.185873 -0.0279544 -0.0147008 -0.185873 -0.0287948 -0.0133393 -0.185973 -0.0286421 -0.0141852 -0.185973 -0.0288948 -0.0133423 -0.185873 -0.028557 -0.0141327 -0.184073 -0.028557 -0.0141327 -0.184073 -0.0279544 -0.0147008 -0.185873 -0.0271484 -0.0148915 -0.185873 -0.0263551 -0.0146537 -0.184073 -0.0257869 -0.0140511 -0.183973 -0.0280018 -0.0147889 -0.184073 -0.0271484 -0.0148915 -0.184073 -0.0263551 -0.0146537 -0.183973 -0.0263025 -0.0147388 -0.184073 -0.0255962 -0.0132451 -0.185573 -0.0531748 -0.00477131 -0.184973 -0.0532233 -0.00312354 -0.185219 -0.0513961 -0.00471891 -0.183787 -0.0503608 -0.00303922 -0.184211 -0.0498882 -0.0046745 -0.182703 -0.0488806 -0.00464482 -0.182473 -0.0494832 -0.00301337 -0.182948 -0.0661251 -0.00350358 -0.180923 -0.0672187 -0.00518499 -0.184973 -0.0626192 -0.00340031 -0.180723 -0.0666675 -0.00351956 -0.180723 -0.0672187 -0.00518499 -0.176073 -0.0531748 -0.00477131 -0.176673 -0.0532233 -0.00312354 -0.177216 -0.0511992 -0.00306391 -0.180723 -0.0485268 -0.00463439 -0.178698 -0.0661251 -0.00350358 -0.176696 -0.0648947 -0.00511654 -0.176073 -0.0625707 -0.00504808 -0.185573 -0.0865603 -0.00575473 -0.184665 -0.0756637 -0.00378455 -0.185219 -0.0753857 -0.00542556 -0.180923 -0.0906571 -0.00422621 -0.182948 -0.0901147 -0.00421023 -0.180923 -0.0912083 -0.00589165 -0.183248 -0.0905856 -0.0058733 -0.184973 -0.0866088 -0.00410696 -0.180723 -0.0731647 -0.00371094 -0.179173 -0.0734728 -0.00372002 -0.180723 -0.0725164 -0.00534105 -0.177859 -0.0743504 -0.00374587 -0.177435 -0.0738778 -0.00538115 -0.176673 -0.0772129 -0.00383019 -0.177216 -0.088633 -0.00416658 -0.180723 -0.0906571 -0.00422621 -0.176073 -0.0865603 -0.00575473 -0.176673 -0.0866088 -0.00410696 -0.184973 -0.0984078 -0.0287964 -0.184973 -0.0996256 -0.0279379 -0.186573 -0.0996256 -0.0279379 -0.184973 -0.0399916 -0.0270757 -0.184973 -0.0414375 -0.0274355 -0.186573 -0.092314 0.0323149 -0.186573 -0.0894515 0.0316195 -0.184973 -0.0891942 0.031393 -0.184973 -0.088502 0.0304476 -0.186573 -0.088502 0.0304476 -0.184973 -0.0883247 0.0300265 -0.184973 -0.0535946 0.0294813 -0.184973 -0.0536489 0.0300007 -0.186573 -0.0535946 0.0294813 -0.186573 -0.0535088 0.0310892 -0.184973 -0.0533674 0.0314825 -0.184973 -0.0527122 0.0324885 -0.186573 -0.0513734 0.0333832 -0.184973 -0.0524885 0.0327083 -0.186573 -0.0497757 0.0335837 -0.186573 -0.0482574 0.0330477 -0.186573 -0.108717 0.0151239 -0.186773 -0.110977 0.00669126 -0.186573 -0.0919831 0.0348464 -0.186573 -0.0755981 0.0407089 -0.186773 -0.0583014 0.0392083 -0.186773 -0.0502461 0.0359025 -0.186573 -0.0322859 0.0173753 -0.186773 -0.0370399 0.0246978 -0.186773 -0.0295328 0.00909033 -0.186573 -0.0293385 0.00913766 -0.186573 -0.0281682 0.000467253 -0.186773 -0.0283681 0.000461364 -0.186973 -0.0730983 -0.0418483 -0.186873 -0.0718691 -0.0419494 -0.186973 -0.0718679 -0.0419226 -0.1868 -0.0718724 -0.0420225 -0.1868 -0.0780006 -0.0412826 -0.1868 -0.0433103 -0.0322824 -0.1868 -0.0352062 -0.0230153 -0.186773 -0.0351219 -0.0230691 -0.186773 -0.0321872 -0.0176217 -0.1868 -0.0483059 -0.0359083 -0.186773 -0.0482534 -0.0359934 -0.1868 -0.053786 -0.0387491 -0.186773 -0.0537468 -0.0388411 -0.186773 -0.0596033 -0.0408382 -0.186773 -0.0839839 -0.0397318 -0.186773 -0.0896354 -0.0372124 -0.1868 -0.0947883 -0.0337988 -0.186773 -0.0948483 -0.0338788 -0.1868 -0.0994348 -0.0297353 -0.1868 -0.10909 -0.0140951 -0.1868 -0.106666 -0.0197722 -0.186788 -0.111306 -0.00198169 -0.186773 -0.110738 -0.008138 -0.186873 -0.0323454 -0.0175512 -0.1868 -0.0301936 -0.0117711 -0.1868 -0.0322785 -0.017581 -0.186873 -0.0352678 -0.0229758 -0.186973 -0.0352904 -0.0229614 -0.186877 -0.043359 -0.032225 -0.186873 -0.0483443 -0.035846 -0.1868 -0.0596284 -0.0407414 -0.1868 -0.0839501 -0.0396377 -0.1868 -0.089588 -0.0371243 -0.1868 -0.103424 -0.0250247 -0.186873 -0.0287911 0.000448904 -0.186773 -0.0288985 -0.00572729 -0.1868 -0.0289978 -0.0057153 -0.186877 -0.0302661 -0.011751 -0.186877 -0.0290725 -0.00570628 -0.186973 -0.0294656 -0.00814064 -0.186973 -0.0318849 -0.016407 -0.186973 -0.0302899 -0.0117444 -0.186773 -0.0300972 -0.0117977 -0.1868 -0.038911 -0.0279525 -0.186877 -0.0389677 -0.0279029 -0.186877 -0.0596473 -0.0406686 -0.186877 -0.0538156 -0.0386799 -0.186973 -0.043375 -0.0322061 -0.186873 -0.06571 -0.041768 -0.186973 -0.0644889 -0.0415947 -0.186973 -0.0596535 -0.0406446 -0.186973 -0.0561203 -0.0395566 -0.186773 -0.065692 -0.0419402 -0.1868 -0.0657024 -0.0418408 -0.186877 -0.0839247 -0.0395668 -0.186877 -0.077986 -0.0412088 -0.186877 -0.0993812 -0.0296825 -0.186973 -0.0966548 -0.032181 -0.186973 -0.0947283 -0.0337188 -0.186877 -0.0947431 -0.0337386 -0.186873 -0.0895533 -0.0370599 -0.186973 -0.0839163 -0.0395435 -0.186973 -0.103343 -0.024966 -0.186873 -0.103365 -0.0249817 -0.186973 -0.102604 -0.0259526 -0.186773 -0.103505 -0.0250835 -0.186873 -0.106601 -0.0197385 -0.186877 -0.109018 -0.0140708 -0.1868 -0.11064 -0.0081202 -0.186973 -0.11003 -0.0105138 -0.1868 -0.111282 -0.001981 -0.186877 -0.110566 -0.00810679 -0.186973 -0.110541 -0.00810239 -0.179741 -0.0695225 0.00425126 -0.179741 -0.070772 0.00421446 -0.180823 -0.0686313 -0.00477641 -0.180198 -0.0690652 0.00426474 -0.179573 -0.0701473 0.00423286 -0.179741 -0.0692561 -0.00479481 -0.179573 -0.0698808 -0.00481321 -0.179741 -0.0705055 -0.00483162 -0.180198 -0.0712293 0.00420099 -0.180823 -0.0713967 0.00419606 -0.180198 -0.0709629 -0.00484509 -0.180823 -0.0681683 -0.00521297 -0.180198 -0.0687987 -0.00478134 -0.179973 -0.0683959 -0.00521967 -0.179123 -0.0698675 -0.00526302 -0.179973 -0.0713392 -0.00530637 -0.180823 -0.0469295 0.00566818 -0.179846 -0.0461283 0.00494038 -0.179605 -0.0466293 0.00492562 -0.179846 -0.0476864 0.00489448 -0.179741 -0.0475321 0.00489903 -0.179573 -0.0469073 0.00491743 -0.180281 -0.0457816 0.00495059 -0.180823 -0.0453914 -0.00409184 -0.180198 -0.0455588 -0.00409677 -0.180198 -0.0458253 0.0049493 -0.179741 -0.0462826 0.00493583 -0.179741 -0.0460161 -0.00411024 -0.179605 -0.0471854 0.00490924 -0.179741 -0.0472656 -0.00414705 -0.180198 -0.0479894 0.00488556 -0.180281 -0.0480331 0.00488427 -0.180823 -0.0481568 0.00488063 -0.180823 -0.0449284 -0.0045284 -0.179351 -0.045778 -0.00455342 -0.179573 -0.0466409 -0.00412865 -0.179123 -0.0466276 -0.00457845 -0.180198 -0.0477229 -0.00416052 -0.180823 -0.0483269 -0.00462851 -0.179741 -0.0927625 0.00356669 -0.180823 -0.0934093 0.00429904 -0.179573 -0.0933872 0.00354829 -0.180198 -0.0923051 0.00358017 -0.179741 -0.0940119 0.00352989 -0.179741 -0.0937454 -0.00551619 -0.180198 -0.0942028 -0.00552966 -0.180198 -0.0944692 0.00351642 -0.180823 -0.0918713 -0.00546098 -0.180198 -0.0920387 -0.00546591 -0.179741 -0.092496 -0.00547938 -0.179973 -0.0916359 -0.00590424 -0.179573 -0.0931207 -0.00549778 -0.179123 -0.0931075 -0.00594759 -0.180823 -0.0948067 -0.00599764 -0.184973 -0.0665736 -0.0321777 -0.183973 -0.0655152 -0.0341474 -0.184973 -0.0651428 -0.0327216 -0.183973 -0.0660405 -0.0332965 -0.183973 -0.0665442 -0.0331773 -0.183973 -0.0719223 -0.0334118 -0.184973 -0.0729678 -0.0329521 -0.183973 -0.0722402 -0.0336381 -0.184973 -0.0733821 -0.0336134 -0.183973 -0.0725122 -0.0343535 -0.184973 -0.0669773 -0.0490705 -0.184973 -0.065533 -0.0485938 -0.183973 -0.0670398 -0.0480724 -0.183973 -0.0660769 -0.0477546 -0.183973 -0.0721625 -0.0462236 -0.183973 -0.0718767 -0.0471964 -0.184973 -0.0727334 -0.0477123 -0.184973 -0.0716441 -0.0487738 -0.183973 -0.0711505 -0.0479041 -0.183973 -0.0701706 -0.0481647 -0.184279 -0.0540058 0.0317561 -0.184934 -0.0536883 0.0299996 -0.184973 -0.0535088 0.0310892 -0.183973 -0.0495353 0.0345616 -0.184973 -0.049672 0.033571 -0.184973 -0.0511754 0.0334503 -0.183973 -0.0514683 0.0344065 -0.183973 -0.0531565 0.0334524 -0.184973 -0.0482574 0.0330477 -0.183973 -0.0362703 0.0228939 -0.184973 -0.037082 0.0223097 -0.184973 -0.0363448 0.0212206 -0.183973 -0.0315633 0.0140694 -0.184973 -0.0324962 0.0137093 -0.183973 -0.0293132 0.00571731 -0.184973 -0.0307992 0.00814219 -0.183973 -0.0288181 0.000453173 -0.183973 -0.0288565 -0.00292046 -0.183973 -0.0302133 -0.0114632 -0.184973 -0.034214 -0.0190789 -0.183973 -0.0333238 -0.0195344 -0.183973 -0.0348624 -0.0222774 -0.183973 -0.041408 -0.0284351 -0.184973 -0.0388264 -0.0261469 -0.183973 -0.039549 -0.0279724 -0.184973 -0.0457005 -0.0275611 -0.184973 -0.0476839 -0.0281557 -0.183973 -0.0471586 -0.0290066 -0.183973 -0.0482239 -0.0301365 -0.184973 -0.0491042 -0.0296622 -0.183973 -0.0484726 -0.0353415 -0.183973 -0.0482979 -0.036102 -0.184973 -0.0485315 -0.0374654 -0.183973 -0.0478455 -0.0367378 -0.183973 -0.0447472 -0.0390632 -0.183973 -0.0428878 -0.0391586 -0.183973 -0.0346169 -0.0323053 -0.183973 -0.0293122 -0.0250808 -0.184973 -0.0222177 -0.00847232 -0.184973 -0.0971082 -0.0408612 -0.183973 -0.0948053 -0.040688 -0.183973 -0.0929547 -0.0404832 -0.184973 -0.0906697 -0.0401489 -0.183973 -0.0899988 -0.0379795 -0.183973 -0.0913973 -0.0394629 -0.183973 -0.0895845 -0.0373182 -0.184973 -0.0884553 -0.0365192 -0.183973 -0.0895637 -0.0328549 -0.184973 -0.0906652 -0.0294218 -0.184973 -0.0926801 -0.028945 -0.183973 -0.0911395 -0.0303021 -0.183973 -0.0969138 -0.0300701 -0.183973 -0.100363 -0.0286138 -0.183973 -0.0987968 -0.0297176 -0.184973 -0.0969432 -0.0290706 -0.184973 -0.110183 -0.00194861 -0.184973 -0.110003 0.00321223 -0.183973 -0.110644 0.00598309 -0.184973 -0.109657 0.0058193 -0.183973 -0.108581 0.0136911 -0.184973 -0.104891 0.0192015 -0.184973 -0.104219 0.0203321 -0.183973 -0.100245 0.0272117 -0.184973 -0.0995107 0.0265326 -0.184973 -0.0922015 0.0323353 -0.184973 -0.0905858 0.0322218 -0.18458 -0.0879536 0.0301549 -0.186073 -0.0495827 -0.0315325 -0.186073 -0.0555311 -0.0352528 -0.186273 -0.0509703 -0.0327292 -0.186073 -0.050868 -0.032901 -0.186073 -0.0644919 -0.0349244 -0.186273 -0.0641091 -0.0352515 -0.186271 -0.0645191 -0.034045 -0.186273 -0.0645253 -0.033972 -0.186191 -0.0645036 -0.0345264 -0.186273 -0.0619041 -0.0367944 -0.186073 -0.0619392 -0.0369913 -0.186073 -0.0732789 -0.0422857 -0.186273 -0.0888644 -0.0381221 -0.186173 -0.0490236 -0.0368628 -0.186273 -0.0563657 -0.0403317 -0.186273 -0.0738508 -0.0355385 -0.186273 -0.0759612 -0.0372085 -0.186073 -0.0736722 -0.0356286 -0.186073 -0.073488 -0.0351894 -0.186273 -0.0823475 -0.035856 -0.186073 -0.0824139 -0.0360447 -0.186073 -0.0773784 -0.0374299 -0.186273 -0.0881232 -0.0329747 -0.186073 -0.0882782 -0.0331011 -0.186073 -0.0872073 -0.0339715 -0.185873 -0.0731728 -0.0424945 -0.185773 -0.0731621 -0.046253 -0.185973 -0.0730562 -0.0430547 -0.185773 -0.0727334 -0.0477123 -0.185773 -0.0701742 -0.0491647 -0.185773 -0.064166 -0.045988 -0.185973 -0.0656418 -0.048426 -0.185973 -0.0669898 -0.0488709 -0.185773 -0.0642769 -0.0422218 -0.185773 -0.0485315 -0.0374654 -0.185873 -0.0488829 -0.0368965 -0.185973 -0.0469108 -0.0387185 -0.185773 -0.0405787 -0.039196 -0.185973 -0.0427418 -0.0399452 -0.185773 -0.047048 -0.038864 -0.185773 -0.104171 -0.0350415 -0.185973 -0.10403 -0.0348999 -0.185973 -0.117051 -0.0112281 -0.185973 -0.118179 -0.00218416 -0.185773 -0.0949297 -0.0416802 -0.185773 -0.0971082 -0.0408612 -0.185973 -0.0949048 -0.0414817 -0.185973 -0.0908152 -0.0400117 -0.185973 -0.0890431 -0.0380314 -0.187122 -0.0486839 -0.0263484 -0.187573 -0.0491345 -0.0269489 -0.187573 -0.0909218 0.0241797 -0.187573 -0.0916722 0.0241576 -0.187573 -0.091294 0.0240681 -0.187122 -0.0913161 0.0248185 -0.187573 -0.0495659 0.0256728 -0.187573 -0.0498325 0.02539 -0.187573 -0.0508656 0.0256345 -0.187573 -0.0509772 0.0260067 -0.187573 -0.0505828 0.0253679 -0.187573 -0.0502047 0.0252785 -0.187122 -0.0897733 -0.0275588 -0.187573 -0.0899187 -0.0282953 -0.187573 -0.0905237 -0.0275809 -0.178698 -0.090396 0.00533714 -0.182948 -0.0739883 0.00582046 -0.176981 -0.075945 0.00576282 -0.176673 -0.0774942 0.00571718 -0.182948 -0.090396 0.00533714 -0.180923 -0.0909383 0.00532117 -0.177216 -0.0889142 0.00538079 -0.182473 -0.0497645 0.00653401 -0.176981 -0.0519554 0.00646947 -0.176673 -0.0629005 0.00614706 -0.176673 -0.0535046 0.00642384 -0.213123 -0.0368421 0.0248506 -0.213123 -0.0920094 0.0348889 -0.213123 -0.0989413 0.0295338 -0.213123 -0.104608 0.0228545 -0.213123 -0.11071 -0.0106794 -0.213123 -0.103158 -0.0263806 -0.213123 -0.0971076 -0.0327147 -0.213123 -0.0898725 -0.0376526 -0.213123 -0.0841156 0.0386858 -0.213123 -0.0643953 -0.0422884 -0.213123 -0.0668491 0.0410164 -0.213123 -0.0287769 -0.00826596 -0.213123 -0.0582312 0.0394483 -0.213123 -0.0501275 0.0361226 -0.224773 -0.0509498 -0.064477 -0.224773 -0.0500142 -0.0632303 -0.224773 -0.0503034 -0.0619873 -0.224773 -0.0522977 -0.062046 -0.224773 -0.0520715 -0.0623131 -0.224773 -0.0524054 -0.0627581 -0.224773 -0.052863 -0.0633142 -0.224773 -0.0525131 -0.0633039 -0.224773 -0.0523734 -0.0638423 -0.224773 -0.0520225 -0.0646757 -0.224773 -0.0839152 -0.0636863 -0.224773 -0.0854267 -0.0627128 -0.224773 -0.0860589 -0.0630405 -0.224773 -0.0858327 -0.0633076 -0.224773 -0.0861666 -0.0637526 -0.224773 -0.0864863 -0.0636101 -0.224773 -0.0866242 -0.0643087 -0.224773 -0.0857838 -0.0656701 -0.224773 -0.114518 -0.0470159 -0.224773 -0.115568 -0.0472883 -0.224773 -0.116169 -0.0474833 -0.224773 -0.115824 -0.0488988 -0.224773 -0.116122 -0.0490826 -0.224773 -0.114713 -0.0498415 -0.224773 -0.114104 -0.0493058 -0.224773 -0.113161 -0.0481951 -0.224773 -0.113399 -0.0474017 -0.224773 -0.113651 -0.0476669 -0.224773 -0.131662 -0.0208628 -0.224773 -0.131694 -0.0204553 -0.224773 -0.13136 -0.0200103 -0.224773 -0.131094 -0.0202602 -0.224773 -0.131253 -0.0194645 -0.224773 -0.131141 -0.0186609 -0.224773 -0.133864 -0.0203418 -0.224773 -0.133261 -0.0209099 -0.224773 -0.132455 -0.0211006 -0.224773 -0.132188 -0.0207113 -0.224773 -0.133544 0.0158592 -0.224773 -0.134337 0.0156214 -0.224773 -0.133811 0.0154698 -0.224773 -0.134304 0.0152138 -0.224773 -0.134905 0.0150188 -0.224773 -0.134746 0.0142231 -0.224773 -0.134255 0.0128513 -0.224773 -0.134089 0.0131594 -0.224773 -0.13346 0.0130104 -0.224773 -0.13345 0.0126606 -0.224773 -0.13284 0.0131962 -0.224773 -0.132656 0.0128984 -0.224773 -0.131897 0.014307 -0.224773 -0.132135 0.0151004 -0.224773 -0.132387 0.0148352 -0.224773 -0.132738 0.0156685 -0.224773 -0.116069 0.0432364 -0.224773 -0.116669 0.0430413 -0.224773 -0.115878 0.0440424 -0.224773 -0.116228 0.044032 -0.224773 -0.116414 0.0446518 -0.224773 -0.116718 0.0454038 -0.224773 -0.116884 0.0450957 -0.224773 -0.118318 0.0453567 -0.224773 -0.119077 0.0439481 -0.224773 -0.118727 0.0439584 -0.224773 -0.118839 0.0431548 -0.224773 -0.0889786 0.0605108 -0.224773 -0.0879286 0.0607832 -0.224773 -0.0871371 0.0617842 -0.224773 -0.087487 0.0617739 -0.224773 -0.0873749 0.0625776 -0.224773 -0.0879776 0.0631457 -0.224773 -0.0881435 0.0628376 -0.224773 -0.089393 0.0628008 -0.224773 -0.0899859 0.0617003 -0.224773 -0.0900979 0.0608967 -0.224773 -0.0552173 0.0615053 -0.224773 -0.0541674 0.0617777 -0.224773 -0.0541347 0.0613701 -0.224773 -0.0535666 0.0619728 -0.224773 -0.0538335 0.0622226 -0.224773 -0.0537257 0.0627684 -0.224773 -0.0546652 0.0643013 -0.224773 -0.054733 0.0639579 -0.224773 -0.0552891 0.0639416 -0.224773 -0.0564365 0.0633831 -0.224773 -0.055783 0.0636855 -0.224773 -0.0565745 0.0626845 -0.224773 -0.0561169 0.0632406 -0.224773 -0.0562246 0.0626948 -0.224773 -0.055734 0.061323 -0.224773 -0.0549281 0.0611323 -0.224773 -0.025482 0.0454859 -0.224773 -0.0238312 0.0459534 -0.224773 -0.0236405 0.0467594 -0.224773 -0.0239904 0.046749 -0.224773 -0.0238193 0.0474486 -0.224773 -0.0249977 0.0479386 -0.224773 -0.0256416 0.048261 -0.224773 -0.0262738 0.0479333 -0.224773 -0.0266013 0.0458718 -0.224773 -0.0259987 0.0453036 -0.224773 -0.00754506 0.0195707 -0.224773 -0.00890655 0.0187303 -0.224773 -0.00863964 0.0184804 -0.224773 -0.00909726 0.0179243 -0.224773 -0.00874741 0.0179346 -0.224773 -0.00860771 0.0173961 -0.224773 -0.00745084 0.0163721 -0.224773 -0.00718404 0.0167615 -0.224773 -0.00635626 0.0174624 -0.224773 -0.00589865 0.0180185 -0.224773 -0.0063882 0.0185467 -0.224773 -0.0067391 0.01938 -0.224773 -0.00753745 -0.0145688 -0.224773 -0.00681737 -0.0145799 -0.224773 -0.00626131 -0.0145635 -0.224773 -0.00575321 -0.01479 -0.224773 -0.00554314 -0.0145101 -0.224773 -0.00508298 -0.0150535 -0.224773 -0.00490416 -0.0157427 -0.224773 -0.00584686 -0.0168535 -0.224773 -0.00646666 -0.0170393 -0.224773 -0.00726232 -0.0171984 -0.224773 -0.00786495 -0.0166303 -0.224773 -0.0216824 -0.0468867 -0.224773 -0.0211613 -0.0446847 -0.224773 -0.0214131 -0.0449499 -0.224773 -0.0225699 -0.0439259 -0.224773 -0.0233633 -0.0441637 -0.224773 -0.0239314 -0.0447663 -0.224773 -0.0237723 -0.045562 -0.224773 -0.0232817 -0.0469338 -0.224773 -0.0224757 -0.0471245 -0.224773 -0.0232731 -0.046525 -0.213123 -0.0281182 0.000468725 -0.186473 -0.0312373 -0.0166728 -0.186473 -0.0353918 -0.0243844 -0.213123 -0.0312373 -0.0166728 -0.213123 -0.0353918 -0.0243844 -0.186473 -0.0410588 -0.0310637 -0.186473 -0.0479907 -0.0364189 -0.213123 -0.0410588 -0.0310637 -0.213123 -0.0479907 -0.0364189 -0.213123 -0.0558845 -0.0402157 -0.186473 -0.0643953 -0.0422884 -0.213123 -0.0731509 -0.0425463 -0.213123 -0.0817689 -0.0409782 -0.186473 -0.0817689 -0.0409782 -0.186473 -0.0971076 -0.0327147 -0.186473 -0.103158 -0.0263806 -0.186473 -0.107759 -0.0189269 -0.213123 -0.107759 -0.0189269 -0.186473 -0.111882 -0.00199867 -0.213123 -0.111882 -0.00199867 -0.220284 -0.084711 -0.0654715 -0.220802 -0.135251 -0.0191071 -0.219229 -0.128646 -0.0250048 -0.220802 -0.134335 -0.0220996 -0.220328 -0.133612 -0.0200766 -0.220321 -0.133752 -0.0195381 -0.220776 -0.136609 -0.0129159 -0.220067 -0.13331 -0.0185474 -0.219229 -0.132743 -0.0102655 -0.219229 -0.132912 -0.00907448 -0.219902 -0.134411 -0.0115429 -0.219672 -0.13226 -0.018275 -0.219869 -0.132816 -0.0182914 -0.22032 -0.135464 -0.0121947 -0.220744 -0.00284739 -0.0087047 -0.220774 -0.00276963 -0.00875406 -0.220802 -0.00280505 -0.0096522 -0.21961 -0.00579281 -0.00694362 -0.220319 -0.00395535 -0.00810683 -0.219257 -0.00658868 -0.00473381 -0.219229 -0.00680684 -0.00655585 -0.219229 -0.121141 -0.0383353 -0.219229 -0.12252 -0.036382 -0.220276 -0.115046 -0.049459 -0.220802 -0.117194 -0.0494151 -0.220205 -0.11601 -0.048279 -0.220035 -0.115902 -0.0477332 -0.219452 -0.113651 -0.0476669 -0.219497 -0.114518 -0.0470159 -0.219562 -0.113511 -0.0482054 -0.219768 -0.11366 -0.048835 -0.220802 -0.111181 -0.0546009 -0.219229 -0.0999793 -0.0566949 -0.219229 -0.0978232 -0.0577982 -0.220802 -0.102021 -0.0605044 -0.220802 -0.0814774 -0.0675663 -0.220336 -0.0852671 -0.0654879 -0.220299 -0.0857752 -0.0652614 -0.220802 -0.089371 -0.0657182 -0.220181 -0.0861347 -0.0648368 -0.220003 -0.0862744 -0.0642984 -0.219229 -0.0833658 -0.0627994 -0.219587 -0.0839152 -0.0636863 -0.21997 -0.0838832 -0.0647705 -0.220336 -0.0509498 -0.064477 -0.220802 -0.0597546 -0.0677663 -0.220802 -0.0679384 -0.0685138 -0.219229 -0.0681316 -0.0641954 -0.220802 -0.0787668 -0.0679758 -0.219229 -0.0757909 -0.0639582 -0.219768 -0.0837755 -0.0642247 -0.21997 -0.0523734 -0.0638423 -0.219229 -0.0604995 -0.0635077 -0.219465 -0.0520715 -0.0623131 -0.21948 -0.0510215 -0.0620407 -0.219229 -0.0504795 -0.061146 -0.220802 -0.04915 -0.0652586 -0.220802 -0.0467154 -0.0644201 -0.220802 -0.0390843 -0.0610838 -0.219229 -0.038868 -0.0560616 -0.220802 -0.0368639 -0.0598932 -0.219562 -0.0237723 -0.045562 -0.220126 -0.022765 -0.0467515 -0.220802 -0.0298176 -0.05535 -0.219229 -0.0324297 -0.0519058 -0.219229 -0.0246766 -0.0451801 -0.219937 -0.0232731 -0.046525 -0.219229 -0.0212826 -0.0414286 -0.220802 -0.0146129 -0.0398343 -0.220802 -0.0199347 -0.0464554 -0.220802 -0.0215896 -0.0482053 -0.219497 -0.0228367 -0.0443152 -0.219835 -0.0217726 -0.0445254 -0.219229 -0.0181448 -0.037343 -0.220802 -0.00809662 -0.0283714 -0.219229 -0.010029 -0.0215107 -0.220336 -0.005287 -0.0160774 -0.220276 -0.0055955 -0.016649 -0.220205 -0.00584686 -0.0168535 -0.220003 -0.00646666 -0.0170393 -0.219768 -0.00709632 -0.0168903 -0.219562 -0.00756712 -0.0164464 -0.219434 -0.00764515 -0.0152809 -0.22181 -0.00517744 0.0205914 -0.22181 -0.00941183 0.0306537 -0.224473 -0.0107192 0.0330557 -0.22181 -0.0107192 0.0330557 -0.22181 -0.0151964 0.0399121 -0.224473 -0.017141 0.042409 -0.22181 -0.0223832 0.0481298 -0.224473 -0.0250237 0.0505691 -0.22181 -0.0341492 0.0573107 -0.22181 -0.0442655 0.0624473 -0.22181 -0.0503675 0.0646004 -0.224473 -0.0550929 0.0658371 -0.224473 -0.0663323 0.0673864 -0.22181 -0.077673 0.0670523 -0.224473 -0.0994108 0.0608229 -0.22181 -0.0888017 0.0648442 -0.22181 -0.11792 0.0478327 -0.22181 -0.10325 0.058838 -0.22181 -0.0994108 0.0608229 -0.22181 -0.12703 0.0367268 -0.224473 -0.125309 0.0392227 -0.224473 -0.135339 0.0189561 -0.22181 -0.135339 0.0189561 -0.22181 -0.132278 0.0271541 -0.224473 -0.134065 -0.0242978 -0.22181 -0.130527 -0.0323015 -0.224473 -0.129281 -0.0345857 -0.22181 -0.124724 -0.0415487 -0.22181 -0.122859 -0.0439389 -0.22181 -0.117522 -0.0497523 -0.224473 -0.114976 -0.0520991 -0.224473 -0.0957346 -0.0639773 -0.22181 -0.0788276 -0.0684417 -0.224473 -0.0849072 -0.0673671 -0.22181 -0.0736678 -0.0689163 -0.224473 -0.0736678 -0.0689163 -0.22181 -0.0679241 -0.0689834 -0.22181 -0.0623271 -0.0685823 -0.22181 -0.0405893 -0.0623529 -0.22181 -0.0366342 -0.0603031 -0.22181 -0.00883118 -0.0310376 -0.224473 -0.0146914 -0.0407527 -0.22181 -0.0146914 -0.0407527 -0.22181 -0.00466136 -0.020486 -0.22181 -0.00766751 -0.0285628 -0.221426 -0.137596 0.00726715 -0.220983 -0.137366 0.00744434 -0.221642 -0.137674 0.00746213 -0.221685 -0.00291768 0.0114865 -0.221546 -0.00295566 0.0113309 -0.220998 -0.00318405 0.0111573 -0.22181 -0.112328 0.052774 -0.22181 -0.109207 0.0550997 -0.220802 -0.112036 0.0524054 -0.220802 -0.105482 0.056986 -0.220802 -0.0957688 0.0619257 -0.22181 -0.0933212 0.0633769 -0.220802 -0.0931607 0.0629354 -0.220802 -0.0853895 0.065245 -0.22181 -0.0827959 0.0662748 -0.220802 -0.0827078 0.0658133 -0.220802 -0.0746125 0.0668581 -0.22181 -0.0719432 0.0674574 -0.22181 -0.0663323 0.0673864 -0.22181 -0.0610407 0.0668944 -0.220802 -0.0611024 0.0664286 -0.22181 -0.0550929 0.0658371 -0.220802 -0.0426884 0.0612691 -0.22181 -0.0401966 0.0606339 -0.22181 -0.0307883 0.0550965 -0.220802 -0.0331003 0.0560906 -0.220802 -0.0310582 0.0547119 -0.22181 -0.0250237 0.0505691 -0.220802 -0.022711 0.0477932 -0.22181 -0.017141 0.042409 -0.220802 -0.0170087 0.0414969 -0.220802 -0.0155737 0.0396321 -0.220802 -0.010921 0.0324587 -0.22181 -0.00593547 0.0227678 -0.220802 -0.00982893 0.0304374 -0.220802 -0.00562369 0.0204443 -0.22181 -0.00292219 0.0118297 -0.220802 -0.00344468 0.0120621 -0.22181 -0.120323 0.0453402 -0.220802 -0.126638 0.0364687 -0.22181 -0.125309 0.0392227 -0.220802 -0.128239 0.03391 -0.22181 -0.131169 0.0295077 -0.220802 -0.133043 0.024129 -0.220802 -0.135479 0.0167457 -0.22181 -0.135933 0.0168671 -0.221426 -0.137006 -0.012762 -0.22181 -0.137078 -0.0133596 -0.221784 -0.00228957 -0.00923361 -0.221524 -0.00236788 -0.0088741 -0.221193 -0.00249688 -0.00865287 -0.220802 -0.136669 -0.0129903 -0.22181 -0.134781 -0.0222475 -0.220802 -0.131469 -0.0293266 -0.22181 -0.134065 -0.0242978 -0.220802 -0.13011 -0.0320844 -0.22181 -0.129281 -0.0345857 -0.220802 -0.126097 -0.0388079 -0.220802 -0.124348 -0.0412679 -0.220802 -0.119276 -0.0473059 -0.22181 -0.114976 -0.0520991 -0.22181 -0.109103 -0.0567026 -0.220802 -0.108834 -0.0563176 -0.22181 -0.105851 -0.0588406 -0.22181 -0.0996839 -0.0622217 -0.220802 -0.0994795 -0.0617987 -0.22181 -0.0957346 -0.0639773 -0.220802 -0.092034 -0.0648637 -0.22181 -0.0895053 -0.0661684 -0.22181 -0.0849072 -0.0673671 -0.220802 -0.0706241 -0.0685422 -0.220802 -0.0571627 -0.0673183 -0.22181 -0.0570737 -0.0677797 -0.22181 -0.0511984 -0.0663741 -0.22181 -0.046554 -0.0648614 -0.220802 -0.0278603 -0.0538535 -0.22181 -0.0307929 -0.0566297 -0.22181 -0.0275681 -0.0542215 -0.22181 -0.02208 -0.0493626 -0.22181 -0.0195877 -0.0467721 -0.220802 -0.0132902 -0.0378883 -0.22181 -0.0128971 -0.0381457 -0.220802 -0.00906781 -0.0304536 -0.220802 -0.00509765 -0.0203054 -0.22181 -0.00403276 -0.0182687 -0.220802 -0.00448689 -0.0181482 -0.220998 -0.00259813 -0.00873365 -0.22181 -0.00229715 -0.00938942 -0.221803 -0.00229027 -0.00931062 -0.224473 -0.137703 0.00785948 -0.224773 -0.137405 0.00782157 -0.224773 -0.135052 0.0188694 -0.224473 -0.131169 0.0295077 -0.224773 -0.1309 0.0293746 -0.224473 -0.11792 0.0478327 -0.224773 -0.117709 0.0476191 -0.224473 -0.109207 0.0550997 -0.224773 -0.0992815 0.0605522 -0.224773 -0.088719 0.0645558 -0.224473 -0.0888017 0.0648442 -0.224473 -0.077673 0.0670523 -0.224773 -0.0776393 0.0667542 -0.224773 -0.0663484 0.0670868 -0.224773 -0.0551584 0.0655444 -0.224473 -0.0442655 0.0624473 -0.224773 -0.0343068 0.0570554 -0.224473 -0.0341492 0.0573107 -0.224473 -0.00593547 0.0227678 -0.224773 -0.00621708 0.0226644 -0.224473 -0.00292219 0.0118297 -0.224473 -0.00466136 -0.020486 -0.224473 -0.00883118 -0.0310376 -0.224473 -0.02208 -0.0493626 -0.224773 -0.0222907 -0.049149 -0.224473 -0.0307929 -0.0566297 -0.224773 -0.0309652 -0.0563841 -0.224773 -0.0407186 -0.0620822 -0.224473 -0.0405893 -0.0623529 -0.224473 -0.0511984 -0.0663741 -0.224773 -0.051281 -0.0660857 -0.224473 -0.0623271 -0.0685823 -0.224773 -0.0736517 -0.0686168 -0.224773 -0.0848417 -0.0670743 -0.224473 -0.105851 -0.0588406 -0.224773 -0.105693 -0.0585853 -0.224773 -0.114779 -0.0518734 -0.224473 -0.122859 -0.0439389 -0.224773 -0.122627 -0.0437491 -0.224773 -0.12902 -0.034437 -0.224473 -0.137078 -0.0133596 -0.224773 -0.136783 -0.0133042 -0.218289 -0.00850202 0.0119564 -0.187973 -0.00850202 0.0119564 -0.218289 -0.0110363 0.0208479 -0.218289 -0.0152618 0.0300176 -0.187973 -0.0116454 0.0224421 -0.218289 -0.0165618 0.0322228 -0.218289 -0.0179135 0.0343182 -0.187973 -0.031067 0.0485103 -0.187973 -0.0231019 0.0410011 -0.218289 -0.0242087 0.0422117 -0.218289 -0.0209022 0.0383917 -0.187973 -0.040215 0.0545224 -0.218289 -0.0316876 0.0489944 -0.218289 -0.031067 0.0485103 -0.218289 -0.0446951 0.0567111 -0.218289 -0.0358115 0.0519131 -0.187973 -0.0502681 0.0588546 -0.187973 -0.0609206 0.0613752 -0.218289 -0.0542327 0.0600234 -0.218289 -0.0591703 0.0610942 -0.218289 -0.0692232 0.0620302 -0.218289 -0.0641779 0.0617646 -0.218289 -0.0609206 0.0613752 -0.218289 -0.0827214 0.0607331 -0.218289 -0.0792963 0.0613432 -0.218289 -0.0842588 0.0603949 -0.187973 -0.0827214 0.0607331 -0.218289 -0.0932072 0.0575897 -0.187973 -0.0932072 0.0575897 -0.218289 -0.0938755 0.0573195 -0.218289 -0.0984674 0.0552123 -0.187973 -0.102988 0.0526733 -0.218289 -0.10707 0.0499269 -0.218289 -0.111025 0.046783 -0.218289 -0.111766 0.0461332 -0.218289 -0.12396 0.0313623 -0.218289 -0.121203 0.0355959 -0.187973 -0.119275 0.0381681 -0.218289 -0.119275 0.0381681 -0.218289 -0.128411 0.0222999 -0.218289 -0.131352 0.0126414 -0.218289 -0.130076 0.0175299 -0.187973 -0.13214 0.00831443 -0.218289 -0.089732 -0.0603845 -0.218688 -0.0905577 -0.0601924 -0.21902 -0.10431 -0.0537427 -0.21902 -0.0976739 -0.057492 -0.219229 -0.0167364 -0.0352599 -0.219229 -0.00656958 0.00110347 -0.219017 -0.00691365 0.00109334 -0.219229 -0.00708991 -0.00908548 -0.21902 -0.00714608 -0.00652476 -0.219229 -0.0129668 -0.0285882 -0.219229 -0.00923632 -0.0190594 -0.21902 -0.00829862 -0.014059 -0.219229 -0.0079656 -0.0141307 -0.21902 -0.0215442 -0.0412103 -0.219229 -0.0457603 -0.0594109 -0.21902 -0.0530972 -0.0615769 -0.219229 -0.053006 -0.0619051 -0.21902 -0.0605505 -0.0631709 -0.21902 -0.0681416 -0.0638549 -0.219229 -0.0705843 -0.0642203 -0.219229 -0.0807455 -0.0633066 -0.21902 -0.0757598 -0.0636189 -0.21902 -0.083294 -0.0624664 -0.219229 -0.0907458 -0.060736 -0.21902 -0.0906344 -0.0604141 -0.219229 -0.110664 -0.0494824 -0.219229 -0.108555 -0.0511679 -0.219229 -0.104495 -0.0540286 -0.219229 -0.125297 -0.031897 -0.21902 -0.130812 -0.0176678 -0.218688 -0.132174 -0.0101794 -0.218688 -0.132856 -0.00261648 -0.218688 -0.11582 -0.0438317 -0.218688 -0.110295 -0.0490408 -0.218688 -0.0605856 -0.062939 -0.218688 -0.0757384 -0.0633854 -0.218688 -0.0832446 -0.0622371 -0.218688 -0.0269333 -0.0465852 -0.218688 -0.0217243 -0.04106 -0.218289 -0.0217878 -0.041007 -0.218685 -0.00714552 0.00108651 -0.21902 -0.0103509 -0.0213993 -0.218289 -0.132773 -0.00261404 -0.21902 -0.13309 -0.00262339 -0.219214 -0.132951 -0.00844527 -0.21902 -0.132406 -0.0102145 -0.218688 -0.130586 -0.017605 -0.219229 -0.13114 -0.017759 -0.218688 -0.128114 -0.024785 -0.218289 -0.128355 -0.0239721 -0.218289 -0.130506 -0.0175828 -0.219229 -0.127549 -0.0275053 -0.218688 -0.124795 -0.0316148 -0.21902 -0.128331 -0.0248746 -0.218289 -0.124723 -0.0315742 -0.218289 -0.128038 -0.0247534 -0.21902 -0.120866 -0.0381336 -0.21902 -0.125 -0.0317299 -0.218688 -0.120677 -0.0379947 -0.218289 -0.123438 -0.0337527 -0.218289 -0.110242 -0.0489772 -0.218289 -0.120611 -0.0379457 -0.219229 -0.116239 -0.0442257 -0.21902 -0.115991 -0.0439924 -0.21902 -0.110445 -0.0492208 -0.218289 -0.108933 -0.0500403 -0.218688 -0.104182 -0.0535458 -0.218289 -0.0997851 -0.0560523 -0.218289 -0.104137 -0.0534763 -0.218688 -0.097571 -0.0572812 -0.218289 -0.0975347 -0.0572068 -0.218289 -0.0832272 -0.0621562 -0.218289 -0.068151 -0.0635377 -0.218688 -0.0681485 -0.0636205 -0.218289 -0.060598 -0.0628572 -0.218289 -0.0572787 -0.062263 -0.218289 -0.0531822 -0.0612712 -0.218688 -0.04598 -0.0588793 -0.218688 -0.05316 -0.0613509 -0.219229 -0.0410557 -0.0572374 -0.21902 -0.0458904 -0.0590961 -0.21902 -0.0390351 -0.0557647 -0.21902 -0.0326314 -0.0516313 -0.218688 -0.0391502 -0.0555603 -0.218688 -0.0327703 -0.0514423 -0.218289 -0.028234 -0.0476631 -0.218289 -0.0370123 -0.0542032 -0.219229 -0.0265393 -0.0470043 -0.21902 -0.0267726 -0.0467561 -0.218289 -0.0207247 -0.0396981 -0.21902 -0.0170223 -0.0350747 -0.218688 -0.0134838 -0.0283359 -0.218289 -0.0147127 -0.03055 -0.218688 -0.0172192 -0.0349472 -0.21902 -0.013273 -0.0284388 -0.218289 -0.00722727 0.0010841 -0.218688 -0.00737966 -0.00650335 -0.218289 -0.00746207 -0.0064958 -0.218289 -0.00785984 -0.00984437 -0.218688 -0.00852792 -0.0140096 -0.218688 -0.0105726 -0.0213226 -0.218289 -0.0103805 -0.020497 -0.187973 -0.0165618 0.0322228 -0.185973 -0.0135038 0.0217031 -0.185973 -0.0245954 0.0396709 -0.185973 -0.0323069 0.046941 -0.185973 -0.0411636 0.0527616 -0.187973 -0.0718491 0.0620078 -0.187973 -0.111766 0.0461332 -0.185973 -0.117706 0.0369282 -0.187973 -0.125287 0.0290201 -0.187973 -0.12962 0.018967 -0.185973 -0.0407134 -0.0314253 -0.185973 -0.0307747 -0.0168626 -0.186473 -0.0287769 -0.00826596 -0.185973 -0.0276184 0.000483447 -0.186473 -0.0558845 -0.0402157 -0.185973 -0.0557161 -0.0406865 -0.186473 -0.0731509 -0.0425463 -0.185973 -0.0644599 -0.0428015 -0.185973 -0.0643284 -0.0427839 -0.186473 -0.11071 -0.0106794 -0.185973 -0.10821 -0.0191436 -0.186473 -0.0898725 -0.0376526 -0.185973 -0.0893726 -0.0384805 -0.224773 -0.050122 -0.063776 -0.220181 -0.050122 -0.063776 -0.224773 -0.0504559 -0.064221 -0.220299 -0.0504559 -0.064221 -0.220284 -0.0515058 -0.0644934 -0.224773 -0.0515058 -0.0644934 -0.224773 -0.0520139 -0.0642669 -0.220154 -0.0520139 -0.0642669 -0.224773 -0.0838832 -0.0647705 -0.224773 -0.0842171 -0.0652155 -0.220154 -0.0842171 -0.0652155 -0.224773 -0.084711 -0.0654715 -0.224773 -0.0852671 -0.0654879 -0.224773 -0.0857752 -0.0652614 -0.224773 -0.0861347 -0.0648368 -0.224773 -0.0862744 -0.0642984 -0.224773 -0.115353 -0.0493427 -0.224773 -0.11366 -0.048835 -0.220003 -0.114104 -0.0493058 -0.220205 -0.114723 -0.0494916 -0.224773 -0.114723 -0.0494916 -0.220321 -0.115353 -0.0493427 -0.220336 -0.115617 -0.0491519 -0.220321 -0.115824 -0.0488988 -0.220276 -0.115958 -0.0485991 -0.219538 -0.13136 -0.0200103 -0.219703 -0.131694 -0.0204553 -0.224773 -0.132744 -0.0207277 -0.219903 -0.132188 -0.0207113 -0.220097 -0.132744 -0.0207277 -0.224773 -0.133252 -0.0205011 -0.220249 -0.133252 -0.0205011 -0.224773 -0.133612 -0.0200766 -0.219426 -0.13228 0.0139723 -0.224773 -0.132396 0.013667 -0.219489 -0.132589 0.0134007 -0.220321 -0.134746 0.0142231 -0.220276 -0.134693 0.0138981 -0.224773 -0.13456 0.0136033 -0.224773 -0.116336 0.0434863 -0.219429 -0.116669 0.0430413 -0.224773 -0.117163 0.0427853 -0.219642 -0.117719 0.0427689 -0.224773 -0.117719 0.0427689 -0.224773 -0.118228 0.0429954 -0.219835 -0.118228 0.0429954 -0.220035 -0.118587 0.04342 -0.224773 -0.118587 0.04342 -0.219587 -0.0875947 0.0612282 -0.224773 -0.0875947 0.0612282 -0.224773 -0.0884225 0.0605272 -0.219465 -0.0879286 0.0607832 -0.224773 -0.0894867 0.0607373 -0.224773 -0.0898462 0.0611618 -0.219801 -0.0898462 0.0611618 -0.219801 -0.0538335 0.0622226 -0.224773 -0.0546613 0.0615217 -0.224773 -0.0557254 0.0617318 -0.219465 -0.0557254 0.0617318 -0.224773 -0.0560849 0.0621563 -0.219587 -0.0560849 0.0621563 -0.224773 -0.0240981 0.0462033 -0.224773 -0.024432 0.0457583 -0.224773 -0.0249259 0.0455023 -0.219835 -0.024432 0.0457583 -0.219642 -0.0249259 0.0455023 -0.224773 -0.0259901 0.0457124 -0.219429 -0.0259901 0.0457124 -0.224773 -0.0263496 0.046137 -0.219452 -0.0263496 0.046137 -0.220228 -0.00635626 0.0174624 -0.224773 -0.00669015 0.0170175 -0.220067 -0.00669015 0.0170175 -0.224773 -0.0077401 0.0167451 -0.219869 -0.00718404 0.0167615 -0.219672 -0.0077401 0.0167451 -0.224773 -0.0082482 0.0169716 -0.219434 -0.00860771 0.0173961 -0.220321 -0.005254 -0.015753 -0.224773 -0.005254 -0.015753 -0.224773 -0.005403 -0.0163827 -0.220321 -0.005403 -0.0163827 -0.224773 -0.00709632 -0.0168903 -0.224773 -0.00756712 -0.0164464 -0.219489 -0.00769994 -0.0161517 -0.224773 -0.00775292 -0.0158266 -0.224773 -0.0212734 -0.0454884 -0.220311 -0.0213811 -0.0460341 -0.224773 -0.0213811 -0.0460341 -0.224773 -0.021715 -0.0464791 -0.220333 -0.021715 -0.0464791 -0.220268 -0.0222089 -0.0467351 -0.224773 -0.0222089 -0.0467351 -0.224773 -0.022765 -0.0467515 -0.224773 -0.0236326 -0.0461005 -0.219735 -0.0236326 -0.0461005 -0.224473 -0.133722 -0.00264201 -0.219815 -0.133722 -0.00264201 -0.220194 -0.13432 0.00515396 -0.224473 -0.133281 -0.00848544 -0.221356 -0.137185 0.00685274 -0.224473 -0.134987 0.00566866 -0.220513 -0.134496 -0.0110127 -0.224473 -0.134496 -0.0110127 -0.21972 -0.00662592 0.00802686 -0.224473 -0.0062269 0.00881898 -0.219949 -0.00618889 0.00886896 -0.220069 -0.0054651 -0.00688932 -0.219828 -0.00599355 -0.0062729 -0.224473 -0.0062499 -0.00572062 -0.219677 -0.00630049 -0.00554619 -0.219624 -0.00637454 -0.00474722 -0.220685 -0.00445121 0.0101328 -0.221111 -0.00281485 -0.00838268 -0.220685 -0.0039234 -0.00778547 -0.224473 -0.00308919 0.0110668 -0.221111 -0.00337974 0.0107942 -0.221784 -0.00290545 0.0116746 -0.224473 -0.00295566 0.0113309 -0.221761 -0.137707 0.0076449 -0.224473 -0.137711 0.00770367 -0.22181 -0.137703 0.00785948 -0.224473 -0.137562 0.00720783 -0.224473 -0.137185 0.00685274 -0.221356 -0.13662 -0.0123241 -0.22176 -0.137095 -0.0131441 -0.22164 -0.137071 -0.0129589 -0.224773 -0.00328876 0.0113131 -0.224473 -0.00292815 0.0114313 -0.224473 -0.00337974 0.0107942 -0.224773 -0.00566172 0.00973807 -0.224773 -0.00353732 0.0110495 -0.224473 -0.00550414 0.00948279 -0.224773 -0.00669148 0.0086458 -0.224473 -0.00665214 0.00793455 -0.224773 -0.00703714 0.00718499 -0.224473 -0.00627768 0.00111207 -0.224773 -0.00657755 0.00110324 -0.224473 -0.00637454 -0.00474722 -0.224473 -0.00577335 -0.00657848 -0.224773 -0.00624731 -0.00643295 -0.224473 -0.00501276 -0.0071986 -0.224773 -0.00515504 -0.00746271 -0.224473 -0.00250876 -0.00863774 -0.224473 -0.00232655 -0.00899207 -0.224773 -0.00258944 -0.00924244 -0.224473 -0.00229715 -0.00938942 -0.224473 -0.137095 -0.0132045 -0.224773 -0.136795 -0.0131957 -0.224473 -0.13662 -0.0123241 -0.224773 -0.133997 0.0052411 -0.224473 -0.134008 0.00474542 -0.224773 -0.134845 0.00593277 -0.224773 -0.137043 0.00711685 -0.224473 -0.137674 0.00746213 -0.220746 -0.136534 -0.0128574 -0.221393 -0.136834 -0.0125009 -0.221115 -0.136837 -0.0128772 -0.22022 -0.13391 -0.0105177 -0.219602 -0.133678 -0.0109181 -0.220081 -0.13365 -0.0101676 -0.21947 -0.133377 -0.0105064 -0.219952 -0.133426 -0.00970983 -0.219365 -0.13315 -0.010065 -0.219218 -0.132922 -0.00876236 -0.219815 -0.133281 -0.00848544 -0.219829 -0.133262 -0.00886265 -0.219815 -0.133626 0.00321728 -0.219828 -0.133629 0.00359142 -0.21984 -0.133644 0.00373228 -0.219229 -0.133292 0.00382702 -0.219969 -0.133874 0.00449977 -0.219319 -0.133482 0.0045596 -0.220039 -0.134009 0.00474766 -0.21947 -0.13384 0.00522845 -0.220513 -0.134987 0.00566866 -0.219902 -0.134933 0.00620297 -0.22093 -0.136077 0.00625552 -0.221398 -0.137436 0.00704432 -0.220776 -0.137209 0.00744422 -0.220802 -0.137273 0.00751491 -0.220802 -0.00328998 0.0112315 -0.220774 -0.00335651 0.0111675 -0.221152 -0.00322434 0.0109125 -0.221193 -0.00307822 0.0110826 -0.220744 -0.00343118 0.0111137 -0.220319 -0.00450202 0.0104517 -0.219901 -0.00555526 0.00980049 -0.219719 -0.00600593 0.00945786 -0.220268 -0.00550414 0.00948279 -0.219627 -0.00673607 0.00716037 -0.219257 -0.00693224 0.00692952 -0.219257 -0.00649215 0.00110576 -0.21927 -0.00658315 -0.00517729 -0.219389 -0.00632945 -0.00614286 -0.219901 -0.00504509 -0.00751875 -0.220268 -0.00501276 -0.0071986 -0.220802 -0.0026995 -0.00881399 -0.221157 -0.00263143 -0.00850978 -0.228673 -0.0763786 0.0280372 -0.228673 -0.0803882 0.0444572 -0.228673 -0.0535134 0.0426073 -0.228673 -0.0617141 0.0275474 -0.228673 -0.0549334 0.0245973 -0.228673 -0.0490994 0.0200536 -0.228673 -0.11638 -0.00213116 -0.228673 -0.0977363 0.0092824 -0.228673 -0.115755 0.00694335 -0.228673 -0.0894652 0.0214017 -0.228673 -0.103762 0.0310645 -0.228673 -0.0881266 -0.0240389 -0.228673 -0.107804 -0.0276682 -0.228673 -0.0933452 -0.0187998 -0.228673 -0.0991459 -0.00532244 -0.228673 -0.0381706 0.0329966 -0.228673 -0.0276734 0.018246 -0.228673 -0.0236202 0.000601223 -0.228673 -0.0817692 -0.0278156 -0.228673 -0.0864867 -0.0441372 -0.228673 -0.0946314 -0.0400875 -0.228673 -0.0362385 -0.0325945 -0.228673 -0.0534666 -0.0251964 -0.228673 -0.0600619 -0.0285406 -0.228737 -0.00228957 -0.00923361 -0.229767 -0.00280945 -0.00919339 -0.228756 -0.00252618 -0.0086166 -0.228775 -0.00281485 -0.00838268 -0.229201 -0.00392345 -0.00778544 -0.229782 -0.00284773 -0.0091647 -0.231382 -0.00684347 -0.00471787 -0.230371 -0.00637947 -0.0049377 -0.230265 -0.00622307 -0.00579819 -0.231129 -0.00630978 -0.00679556 -0.230835 -0.00558082 -0.00761658 -0.229997 -0.00573967 -0.0066179 -0.230627 -0.00504504 -0.00797556 -0.231382 -0.00718565 0.0068986 -0.230374 -0.00671926 0.0069555 -0.230374 -0.00627768 0.00111207 -0.22962 -0.00550414 0.00948279 -0.230996 -0.00647568 0.00945549 -0.231376 -0.00721023 0.00723576 -0.230627 -0.0055821 0.0102565 -0.230209 -0.00452921 0.0109093 -0.229782 -0.00345859 0.0115729 -0.229767 -0.00342207 0.0116038 -0.228775 -0.00337974 0.0107942 -0.228758 -0.00312756 0.0110162 -0.229747 -0.00338233 0.0116927 -0.228737 -0.00290545 0.0116746 -0.229744 -0.00338397 0.011743 -0.229744 -0.137237 0.0078001 -0.229747 -0.137236 0.0077498 -0.229755 -0.137219 0.00770279 -0.229767 -0.137191 0.00766344 -0.229201 -0.136077 0.0062555 -0.230209 -0.136045 0.00703527 -0.230627 -0.134955 0.00644562 -0.230369 -0.133622 0.00345624 -0.231382 -0.133157 0.00318793 -0.230265 -0.133777 0.00426825 -0.230835 -0.134419 0.00608666 -0.229997 -0.13426 0.00508796 -0.230071 -0.133677 -0.0102094 -0.22977 -0.134214 -0.0108115 -0.230996 -0.133524 -0.0109853 -0.230627 -0.134418 -0.0117864 -0.230374 -0.133281 -0.00848544 -0.231376 -0.13279 -0.00876553 -0.230272 -0.133359 -0.00950627 -0.231259 -0.132956 -0.00991458 -0.229201 -0.135549 -0.0116627 -0.230209 -0.135471 -0.0124392 -0.229767 -0.136578 -0.0131338 -0.228758 -0.136873 -0.0125463 -0.228745 -0.137037 -0.0128396 -0.229747 -0.136618 -0.0132226 -0.228738 -0.137095 -0.0131705 -0.229744 -0.136616 -0.0132729 -0.224773 -0.136779 -0.0130254 -0.225073 -0.134496 -0.0110127 -0.224773 -0.133058 -0.00954113 -0.225073 -0.133263 -0.00872376 -0.225073 -0.133722 -0.00264201 -0.224773 -0.133423 -0.00263318 -0.224773 -0.132983 -0.00844911 -0.224773 -0.133322 0.00346508 -0.224773 -0.133465 0.00428425 -0.225073 -0.137185 0.00685274 -0.224773 -0.137411 0.0077125 -0.225073 -0.137674 0.00746213 -0.224773 -0.137385 0.00754342 -0.224773 -0.137257 0.00729539 -0.225073 -0.00337974 0.0107942 -0.225073 -0.00302465 0.0111708 -0.225073 -0.00673727 0.00719382 -0.225073 -0.00642737 0.00850352 -0.225073 -0.00637454 -0.00474722 -0.224773 -0.00667396 -0.00472848 -0.224773 -0.00667836 -0.00499502 -0.225073 -0.00281485 -0.00838268 -0.224773 -0.00295714 -0.00864679 -0.225073 -0.00228957 -0.00923361 -0.224773 -0.00259475 -0.00935151 -0.228737 -0.00229033 -0.0093119 -0.225073 -0.00290545 0.0116746 -0.22874 -0.00291775 0.011486 -0.225073 -0.137072 -0.0129612 -0.225073 -0.136911 -0.0125968 -0.225073 -0.13662 -0.0123241 -0.228775 -0.137185 0.00685274 -0.228764 -0.137345 0.00696007 -0.225073 -0.137491 0.0071078 -0.22875 -0.137565 0.00721318 -0.22874 -0.137689 0.00752455 -0.225073 -0.137703 0.00785948 -0.22962 -0.00501276 -0.0071986 -0.229201 -0.00445126 0.0101327 -0.225073 -0.00550414 0.00948279 -0.225073 -0.00637849 -0.00498618 -0.225073 -0.0062499 -0.00572062 -0.230374 -0.00637454 -0.00474722 -0.225073 -0.00671926 0.0069555 -0.230315 -0.00669606 0.00773767 -0.225073 -0.00665214 0.00793455 -0.230146 -0.00644782 0.00846477 -0.230014 -0.00622497 0.00882158 -0.229876 -0.00598091 0.00910482 -0.228775 -0.13662 -0.0123241 -0.22962 -0.134496 -0.0110127 -0.22962 -0.134987 0.00566866 -0.225073 -0.134987 0.00566866 -0.225073 -0.133281 -0.00848544 -0.230369 -0.133263 -0.00872376 -0.225073 -0.133622 0.00345624 -0.225073 -0.13375 0.00419067 -0.225073 -0.134227 0.00504854 -0.230374 -0.133722 -0.00264201 -0.236973 -0.119595 0.00700234 -0.236673 -0.1137 0.0245441 -0.236673 -0.108306 0.0321431 -0.236973 -0.101419 0.0383874 -0.236673 -0.0938311 0.0437584 -0.236673 -0.0852442 0.0473793 -0.236973 -0.0936895 0.0434939 -0.236673 -0.048831 0.045084 -0.236973 -0.0576898 0.0479022 -0.236973 -0.0409404 0.0401689 -0.236673 -0.0278655 0.0270725 -0.236973 -0.0339137 0.0341322 -0.236973 -0.0281158 0.0269072 -0.236973 -0.0237442 0.0187398 -0.238173 -0.0220209 0.000648333 -0.238173 -0.0251322 -0.0178201 -0.238473 -0.0248518 -0.0179267 -0.238473 -0.034856 -0.0338978 -0.238473 -0.0419952 -0.0401174 -0.238173 -0.0592536 -0.0475465 -0.238473 -0.0591865 -0.0478389 -0.238173 -0.0779742 -0.048098 -0.238473 -0.0685779 -0.049044 -0.238173 -0.0870552 -0.0456328 -0.238473 -0.078024 -0.0483938 -0.238473 -0.09564 -0.0416976 -0.238173 -0.102927 -0.0356907 -0.238473 -0.109353 -0.0287698 -0.238473 -0.11406 -0.0205544 -0.238173 -0.117979 -0.00217827 -0.230673 -0.0236202 0.000601223 -0.230673 -0.0242448 -0.00847329 -0.230473 -0.0308471 -0.0252901 -0.230673 -0.0266278 -0.0172516 -0.230673 -0.0430968 -0.0385694 -0.230673 -0.0686338 -0.0471449 -0.230473 -0.0864156 -0.0439503 -0.230673 -0.0864867 -0.0441372 -0.230473 -0.0945252 -0.039918 -0.230473 -0.101692 -0.034381 -0.230673 -0.10183 -0.0345265 -0.230473 -0.107642 -0.0275522 -0.230473 -0.112144 -0.019694 -0.230673 -0.115222 -0.0111532 -0.230673 -0.11638 -0.00213116 -0.228673 -0.115222 -0.0111532 -0.228873 -0.112144 -0.019694 -0.228673 -0.112327 -0.019776 -0.228873 -0.107642 -0.0275522 -0.228673 -0.10183 -0.0345265 -0.228873 -0.0686397 -0.0469449 -0.228673 -0.0777084 -0.0465202 -0.228673 -0.0686338 -0.0471449 -0.228873 -0.0596566 -0.0457922 -0.228673 -0.0596118 -0.0459871 -0.228673 -0.050989 -0.0430916 -0.228873 -0.0432128 -0.0384065 -0.228673 -0.0430968 -0.0385694 -0.228673 -0.0306776 -0.0253963 -0.228673 -0.0266278 -0.0172516 -0.228873 -0.0238201 0.000595334 -0.228673 -0.0242448 -0.00847329 -0.237873 -0.128625 -0.00249185 -0.237673 -0.128825 -0.00249774 -0.237873 -0.12568 0.0176631 -0.237873 -0.109006 0.043034 -0.237873 -0.100808 0.049142 -0.237673 -0.0819212 0.0568649 -0.237873 -0.0818807 0.0566691 -0.237673 -0.0614917 0.0574667 -0.237873 -0.0615206 0.0572688 -0.237873 -0.0200931 0.0300428 -0.237873 -0.0155016 0.0209085 -0.237873 -0.012566 0.0111157 -0.237873 -0.0113755 0.000961909 -0.237673 -0.0129557 -0.0090998 -0.237673 -0.0152697 -0.0188788 -0.237873 -0.0246087 -0.0366293 -0.237873 -0.0396125 -0.0499912 -0.237673 -0.0583219 -0.0572198 -0.237873 -0.0582814 -0.0574156 -0.237673 -0.0683026 -0.05839 -0.237673 -0.0783349 -0.0578093 -0.237873 -0.0783638 -0.0580072 -0.237873 -0.0974374 -0.0516945 -0.237673 -0.10574 -0.0459994 -0.237873 -0.105864 -0.0461563 -0.237673 -0.119056 -0.0310475 -0.237873 -0.123755 -0.0221429 -0.237873 -0.127825 -0.0024683 -0.236873 -0.0143287 -0.00948386 -0.236673 -0.0170672 -0.0194983 -0.236873 -0.0272572 -0.0374851 -0.236673 -0.0435027 -0.0502697 -0.236873 -0.05299 -0.0544863 -0.236873 -0.0631509 -0.0566972 -0.236673 -0.0935374 -0.0517435 -0.236873 -0.0936213 -0.0519251 -0.236873 -0.10262 -0.0467136 -0.236673 -0.102504 -0.0465505 -0.236673 -0.110364 -0.0397984 -0.236873 -0.117016 -0.0318272 -0.236673 -0.116849 -0.031717 -0.236873 -0.121923 -0.0226592 -0.236873 -0.125062 -0.0127457 -0.238273 -0.119837 -0.002233 -0.238273 -0.119166 0.00751794 -0.238473 -0.116418 0.0168795 -0.238473 -0.112084 0.0255963 -0.238473 -0.0987927 0.0396945 -0.238273 -0.0904282 0.0447167 -0.238473 -0.0811178 0.0476332 -0.238473 -0.0617504 0.0482037 -0.238273 -0.0522845 0.0458403 -0.238273 -0.0293776 0.0281437 -0.238473 -0.0295405 0.0280277 -0.238273 -0.0214069 0.0103976 -0.228737 -0.109682 0.0547634 -0.228737 -0.0994108 0.0608229 -0.228737 -0.101856 0.0595944 -0.229744 -0.101637 0.0591789 -0.228737 -0.109207 0.0550997 -0.229744 -0.109409 0.0543811 -0.229749 -0.0932223 0.0628978 -0.228748 -0.0928456 0.0633552 -0.228762 -0.0925405 0.0632136 -0.229784 -0.093107 0.0628387 -0.22878 -0.0922996 0.0629788 -0.228739 -0.09318 0.0633877 -0.22874 -0.11699 0.0486566 -0.22875 -0.117092 0.0483376 -0.229764 -0.116517 0.0484599 -0.229807 -0.0930767 0.0627819 -0.229483 -0.0916101 0.0608757 -0.2288 -0.0921502 0.0626774 -0.230653 -0.0850428 0.0627612 -0.230189 -0.0858161 0.0610503 -0.231113 -0.0850384 0.0614618 -0.231495 -0.0854432 0.0602832 -0.230722 -0.0865512 0.0596817 -0.231766 -0.0861779 0.0593206 -0.230912 -0.0875687 0.0589737 -0.23189 -0.0869395 0.0587552 -0.23191 -0.087173 0.0586331 -0.23092 -0.0878801 0.0588619 -0.23089 -0.0884741 0.0587486 -0.2308 -0.0890792 0.0587568 -0.231741 -0.0896787 0.0583386 -0.231413 -0.0909382 0.0588595 -0.231364 -0.0910774 0.0589532 -0.230091 -0.0909588 0.0597219 -0.230969 -0.0919443 0.0597984 -0.230491 -0.12039 0.0414391 -0.229483 -0.119535 0.0418124 -0.229624 -0.119305 0.0416164 -0.230969 -0.119286 0.0407123 -0.231364 -0.118113 0.0404138 -0.231413 -0.117945 0.0404023 -0.2308 -0.116284 0.0412428 -0.231907 -0.115431 0.041185 -0.23089 -0.115756 0.0415383 -0.23092 -0.115298 0.0419334 -0.23191 -0.114571 0.0420888 -0.230883 -0.11489 0.0424768 -0.231766 -0.114053 0.0431818 -0.230773 -0.114617 0.0430917 -0.230598 -0.114487 0.0437522 -0.230653 -0.114791 0.0467289 -0.229996 -0.114766 0.0452794 -0.229483 -0.115419 0.0461781 -0.22874 -0.0859833 0.0655301 -0.229749 -0.0856287 0.0651742 -0.229764 -0.0856727 0.0651236 -0.228755 -0.0863108 0.0651877 -0.228741 -0.12204 0.0432681 -0.228762 -0.12151 0.0433719 -0.229764 -0.121878 0.0427741 -0.22878 -0.121184 0.043289 -0.228739 -0.122151 0.0432029 -0.229749 -0.121943 0.0427575 -0.229744 -0.0775837 0.0665896 -0.228737 -0.077673 0.0670523 -0.228737 -0.0674085 0.0674358 -0.228737 -0.0582626 0.0664682 -0.228737 -0.0663323 0.0673864 -0.228737 -0.135339 0.0189561 -0.228737 -0.13213 0.027483 -0.228737 -0.127768 0.0355797 -0.229744 -0.12737 0.0353295 -0.229744 -0.124691 0.0392735 -0.228737 -0.125309 0.0392227 -0.228765 -0.0575013 0.0658422 -0.229784 -0.0582094 0.0658709 -0.22875 -0.0576732 0.0661314 -0.229764 -0.0582329 0.0659319 -0.22874 -0.057931 0.066347 -0.229744 -0.0583434 0.0660053 -0.228737 -0.135364 0.0188733 -0.22875 -0.135334 0.0182132 -0.229749 -0.134919 0.0186698 -0.229764 -0.134898 0.0186064 -0.228764 -0.135159 0.0179274 -0.229784 -0.134854 0.0185581 -0.228783 -0.134899 0.0177153 -0.229483 -0.132806 0.0171793 -0.2288 -0.134636 0.0176124 -0.229996 -0.0525074 0.0610257 -0.230653 -0.0512644 0.0617717 -0.229483 -0.0520558 0.0620408 -0.231113 -0.0519102 0.0606442 -0.230454 -0.0533126 0.0602344 -0.230134 -0.0527024 0.0607734 -0.231709 -0.057611 0.0603739 -0.230773 -0.0543273 0.0598024 -0.230912 -0.0553456 0.0597546 -0.23092 -0.0556712 0.0598135 -0.231907 -0.0563858 0.0595545 -0.2308 -0.0567622 0.0603219 -0.230738 -0.0569864 0.0605056 -0.230969 -0.0587227 0.0626566 -0.230491 -0.0586453 0.0639763 -0.231364 -0.0583945 0.0614911 -0.230469 -0.0575588 0.0612068 -0.229624 -0.13389 0.0112858 -0.230969 -0.133422 0.0105124 -0.23019 -0.132637 0.0113856 -0.230469 -0.131972 0.0116763 -0.230738 -0.131271 0.0122487 -0.231907 -0.13032 0.0128492 -0.231928 -0.130122 0.0134542 -0.23191 -0.130027 0.0140618 -0.230912 -0.13052 0.0138895 -0.231766 -0.130125 0.0152674 -0.231495 -0.130591 0.0163849 -0.231113 -0.131409 0.0173249 -0.229996 -0.131791 0.0167276 -0.230491 -0.0511364 0.0621995 -0.230491 -0.134741 0.0105898 -0.229744 -0.050497 0.0641487 -0.229749 -0.0505652 0.0641543 -0.228764 -0.0513077 0.0643938 -0.228783 -0.0515198 0.0641336 -0.229784 -0.050677 0.0640885 -0.229749 -0.136745 0.0109553 -0.228748 -0.136953 0.0115103 -0.22878 -0.136353 0.0117949 -0.229784 -0.136636 0.0110256 -0.2288 -0.136018 0.0117736 -0.229807 -0.136572 0.0110235 -0.228739 -0.137148 0.0112369 -0.229744 -0.13677 0.0108917 -0.228737 -0.0503618 0.0645986 -0.228737 -0.0442655 0.0624473 -0.228737 -0.0417521 0.0613649 -0.229744 -0.0346146 0.0570452 -0.229744 -0.0339055 0.0566052 -0.2288 -0.0261324 0.0501388 -0.229784 -0.0264711 0.0510481 -0.22878 -0.0259461 0.0504188 -0.228762 -0.0258632 0.0507448 -0.228744 -0.0259265 0.0511834 -0.229749 -0.0264776 0.0511775 -0.228737 -0.0262185 0.0515919 -0.22875 -0.13607 -0.0169964 -0.229749 -0.135939 -0.0163936 -0.228756 -0.135938 -0.0170838 -0.229764 -0.135889 -0.0164376 -0.229784 -0.135826 -0.0164575 -0.229807 -0.135762 -0.0164515 -0.229483 -0.0274227 0.0487702 -0.2288 -0.135165 -0.0171678 -0.231113 -0.0236292 0.043372 -0.229996 -0.0239557 0.044001 -0.229483 -0.023057 0.0446543 -0.230653 -0.0225061 0.0440255 -0.230491 -0.0221815 0.044332 -0.230123 -0.0242262 0.0438887 -0.231495 -0.0248523 0.0431333 -0.230637 -0.0256165 0.043736 -0.230773 -0.0261434 0.0438515 -0.23181 -0.0263093 0.0433733 -0.23191 -0.0271463 0.0438063 -0.23089 -0.0276968 0.0449908 -0.231907 -0.0280501 0.0446661 -0.231808 -0.0285149 0.0454591 -0.230491 -0.0277959 0.0496252 -0.231709 -0.0287013 0.0459883 -0.23049 -0.0282385 0.0466239 -0.231413 -0.0288328 0.0471802 -0.230278 -0.0282014 0.0471911 -0.231364 -0.0288213 0.0473476 -0.230008 -0.0280325 0.0478082 -0.230969 -0.0285228 0.048521 -0.229624 -0.131356 -0.0222737 -0.230091 -0.130487 -0.0217237 -0.23136 -0.129726 -0.0218534 -0.231409 -0.129632 -0.0217147 -0.231706 -0.129146 -0.0206184 -0.231808 -0.129039 -0.0200536 -0.23089 -0.129514 -0.019239 -0.231928 -0.129176 -0.0185116 -0.23191 -0.129393 -0.017949 -0.231498 -0.131037 -0.016214 -0.230454 -0.131171 -0.0168129 -0.229996 -0.132259 -0.0165112 -0.230491 -0.131745 -0.0233021 -0.229807 -0.133547 -0.0238416 -0.229483 -0.131641 -0.022375 -0.229749 -0.0207093 0.0457394 -0.228756 -0.0210551 0.0463368 -0.229784 -0.020839 0.0457383 -0.229807 -0.0208916 0.0457011 -0.2288 -0.0217667 0.0460229 -0.229764 -0.133645 -0.0239227 -0.229784 -0.133604 -0.0238719 -0.229749 -0.133663 -0.0239872 -0.228737 -0.020311 0.0460225 -0.228737 -0.017141 0.042409 -0.228737 -0.0107192 0.0330557 -0.228737 -0.00593547 0.0227678 -0.229744 -0.122239 -0.0439532 -0.228737 -0.122859 -0.0439389 -0.228737 -0.125528 -0.040447 -0.229744 -0.125146 -0.0401738 -0.228737 -0.129281 -0.0345857 -0.229744 -0.129944 -0.0324017 -0.229744 -0.133653 -0.0240552 -0.22878 -0.00625637 0.0215345 -0.228762 -0.00602154 0.0217754 -0.228753 -0.00592647 0.0219473 -0.229749 -0.00633727 0.0224573 -0.228748 -0.00587991 0.0220805 -0.22874 -0.00584525 0.0223725 -0.229749 -0.119291 -0.0472693 -0.228756 -0.118945 -0.0478667 -0.229764 -0.119225 -0.0472822 -0.230491 -0.117819 -0.045862 -0.229807 -0.119108 -0.047231 -0.231113 -0.00777326 0.0142733 -0.229996 -0.00774148 0.0149813 -0.230491 -0.00603943 0.0143809 -0.231907 -0.0109547 0.0176045 -0.231928 -0.0108237 0.0169817 -0.231766 -0.00991443 0.0154129 -0.230454 -0.00882929 0.015283 -0.231741 -0.0108965 0.0189137 -0.231364 -0.0102819 0.0203124 -0.230969 -0.00943669 0.0211793 -0.230079 -0.00949142 0.0202133 -0.230091 -0.111904 -0.0491591 -0.23136 -0.11118 -0.0488911 -0.231533 -0.111172 -0.0482728 -0.230598 -0.11179 -0.0478221 -0.230738 -0.111906 -0.04732 -0.231808 -0.111485 -0.046989 -0.2308 -0.112008 -0.0470489 -0.231907 -0.111942 -0.0462063 -0.231928 -0.112375 -0.0457222 -0.230598 -0.114517 -0.045252 -0.231118 -0.116359 -0.0448975 -0.229744 -0.00403166 0.0148017 -0.22875 -0.00393007 0.0154665 -0.229749 -0.00406086 0.0148636 -0.228764 -0.00422473 0.0156264 -0.229807 -0.00423784 0.0149216 -0.228762 -0.114137 -0.0522749 -0.228739 -0.113968 -0.0529157 -0.229744 -0.11348 -0.0527614 -0.229744 -0.0980535 -0.0624671 -0.228737 -0.0957346 -0.0639773 -0.229744 -0.105385 -0.0585752 -0.228737 -0.098248 -0.0628948 -0.229744 -0.106095 -0.0581351 -0.228748 -0.00304756 -0.0130402 -0.228762 -0.00332272 -0.0132336 -0.229764 -0.00330322 -0.0125321 -0.22878 -0.00364659 -0.0133249 -0.2288 -0.00398227 -0.0133036 -0.229807 -0.00342852 -0.0125534 -0.228739 -0.00285225 -0.0127669 -0.229744 -0.00322975 -0.0124216 -0.228737 -0.00276691 -0.0125024 -0.229744 -0.0895031 -0.0656786 -0.229749 -0.0894349 -0.0656843 -0.229764 -0.0893715 -0.0656625 -0.228756 -0.0888367 -0.0660288 -0.229784 -0.0893231 -0.0656185 -0.228783 -0.0884803 -0.0656636 -0.231118 -0.00860072 -0.0188467 -0.229483 -0.00719426 -0.0187092 -0.230809 -0.00893869 -0.0140378 -0.231907 -0.00967556 -0.0143673 -0.231928 -0.00987846 -0.0149841 -0.23191 -0.00997239 -0.0155796 -0.23181 -0.00992984 -0.0165331 -0.231768 -0.00987828 -0.0167857 -0.231498 -0.00941558 -0.0179044 -0.230579 -0.00918885 -0.0171273 -0.230454 -0.00900061 -0.0174525 -0.231739 -0.00896649 -0.0132646 -0.230614 -0.00839431 -0.0134608 -0.231706 -0.00885147 -0.0131443 -0.230464 -0.00801388 -0.0131978 -0.230327 -0.00768449 -0.0130321 -0.23136 -0.0077316 -0.0123648 -0.230964 -0.0065649 -0.0120408 -0.230107 -0.00717325 -0.0128656 -0.229976 -0.00687773 -0.0128133 -0.230491 -0.00525881 -0.0121197 -0.229624 -0.0820508 -0.0646551 -0.230091 -0.0820927 -0.0636274 -0.23136 -0.0815999 -0.0630334 -0.230469 -0.0824413 -0.0627367 -0.231706 -0.0823794 -0.0619135 -0.230738 -0.0830137 -0.0620355 -0.231808 -0.0828152 -0.0615388 -0.23089 -0.0837579 -0.0615422 -0.231928 -0.0842192 -0.0608866 -0.230912 -0.0846545 -0.0612845 -0.230883 -0.0850035 -0.0612616 -0.231768 -0.0860207 -0.0608867 -0.231498 -0.0871395 -0.0613494 -0.230598 -0.0863095 -0.0615505 -0.230454 -0.0866875 -0.0617644 -0.229996 -0.0874927 -0.0625556 -0.231118 -0.0880817 -0.0621643 -0.230658 -0.0887311 -0.0632891 -0.229483 -0.0879443 -0.0635708 -0.230491 -0.00703559 -0.0196286 -0.229807 -0.0817885 -0.0673365 -0.229749 -0.00508073 -0.0201998 -0.228756 -0.00473266 -0.0196077 -0.228748 -0.0822753 -0.0677174 -0.228762 -0.0824687 -0.0674423 -0.22878 -0.08256 -0.0671184 -0.229784 -0.0817906 -0.0674008 -0.228739 -0.0820019 -0.0679128 -0.228737 -0.0817375 -0.0679981 -0.229744 -0.0050864 -0.020268 -0.229744 -0.00946517 -0.0312556 -0.228737 -0.00787021 -0.0290129 -0.228737 -0.00883118 -0.0310376 -0.229744 -0.0153094 -0.0408035 -0.228737 -0.0146914 -0.0407527 -0.228737 -0.0176432 -0.0445465 -0.229744 -0.0725737 -0.0684962 -0.229764 -0.0181225 -0.044304 -0.229784 -0.018187 -0.0442939 -0.22878 -0.0188162 -0.0448189 -0.2288 -0.0190963 -0.0446326 -0.228739 -0.0178493 -0.0447328 -0.229744 -0.0544334 -0.0667334 -0.228743 -0.0539202 -0.0669899 -0.229749 -0.0543714 -0.0667042 -0.228776 -0.0535607 -0.0663226 -0.229784 -0.0543076 -0.0665913 -0.2288 -0.0535972 -0.0659302 -0.230491 -0.0196099 -0.0429691 -0.230491 -0.0548542 -0.0647256 -0.229483 -0.0541373 -0.0641285 -0.229996 -0.0252341 -0.0468094 -0.231118 -0.0258675 -0.0471238 -0.231482 -0.0261001 -0.0459576 -0.230429 -0.0255114 -0.0457872 -0.23049 -0.0255215 -0.0456135 -0.231768 -0.0259434 -0.0447002 -0.230773 -0.0253845 -0.0446246 -0.23181 -0.0258618 -0.0444557 -0.23092 -0.0247762 -0.0435447 -0.230904 -0.024376 -0.043166 -0.231907 -0.0245587 -0.0427072 -0.230859 -0.0240265 -0.0429292 -0.230779 -0.0236189 -0.0427326 -0.231739 -0.0233932 -0.0421067 -0.230642 -0.0230906 -0.0425794 -0.231706 -0.0232335 -0.0420601 -0.230127 -0.0216863 -0.0426442 -0.230964 -0.0207015 -0.0422477 -0.229946 -0.0488337 -0.0615078 -0.230964 -0.0480476 -0.0613393 -0.230135 -0.0491109 -0.0611777 -0.23136 -0.0489116 -0.0604909 -0.231409 -0.0490503 -0.0603969 -0.231928 -0.0522534 -0.0599414 -0.231808 -0.0507114 -0.0598042 -0.230829 -0.0510778 -0.0602728 -0.230761 -0.0507335 -0.0603143 -0.231739 -0.0503083 -0.0598714 -0.230652 -0.0503168 -0.0604204 -0.231706 -0.0501466 -0.0599109 -0.231481 -0.049268 -0.0602662 -0.230802 -0.0531822 -0.0609607 -0.231768 -0.0538135 -0.0608423 -0.230009 -0.0542511 -0.0629929 -0.230658 -0.0549596 -0.064278 -0.230318 -0.0540939 -0.0622722 -0.231118 -0.0549596 -0.0629792 -0.230491 -0.024903 -0.0485836 -0.2288 -0.0478499 -0.0642073 -0.228737 -0.0232126 -0.050454 -0.229749 -0.0234957 -0.0500557 -0.229764 -0.0234829 -0.0499899 -0.228793 -0.0231363 -0.0490782 -0.2288 -0.0232122 -0.0489983 -0.229764 -0.0468423 -0.0644097 -0.228762 -0.0474596 -0.0647435 -0.229784 -0.0468931 -0.0643686 -0.229807 -0.0469234 -0.0643118 -0.228741 -0.0469488 -0.0649186 -0.228739 -0.0468201 -0.0649176 -0.229749 -0.0467778 -0.0644277 -0.229744 -0.0467099 -0.0644181 -0.229744 -0.0409573 -0.0620077 -0.229744 -0.0383633 -0.0607088 -0.229744 -0.0305912 -0.0559111 -0.229744 -0.0235347 -0.0501119 -0.226296 -0.0230728 -0.0502906 -0.226273 -0.02208 -0.0493626 -0.226573 -0.0228983 -0.0497407 -0.22654 -0.00469833 -0.019671 -0.226573 -0.00318962 -0.0131573 -0.226294 -0.00282335 -0.0127014 -0.226294 -0.0036426 0.0151053 -0.226354 -0.00374513 0.0152766 -0.226294 -0.0204679 0.0461578 -0.226354 -0.0206424 0.0462549 -0.226273 -0.0250237 0.0505691 -0.226296 -0.0260696 0.0514374 -0.226273 -0.0262185 0.0515919 -0.226354 -0.050765 0.0646342 -0.226573 -0.0576077 0.0660454 -0.226375 -0.057844 0.0662901 -0.226273 -0.0550929 0.0658371 -0.226273 -0.0888017 0.0648442 -0.226354 -0.0930513 0.0633886 -0.226294 -0.0932512 0.06338 -0.226294 -0.116923 0.0487671 -0.226573 -0.121663 0.0433723 -0.226354 -0.12204 0.0432681 -0.226273 -0.11792 0.0478327 -0.226354 -0.135399 0.0184701 -0.226354 -0.137084 0.0113489 -0.226573 -0.134056 -0.0234381 -0.226354 -0.136255 -0.0168065 -0.226354 -0.134154 -0.0238162 -0.226294 -0.119532 -0.0476877 -0.226273 -0.114976 -0.0520991 -0.226273 -0.0849072 -0.0673671 -0.226294 -0.0819364 -0.0679417 -0.228753 -0.0228997 -0.0497825 -0.22874 -0.0230105 -0.0501865 -0.22636 -0.0229744 -0.0501089 -0.226573 -0.0183511 -0.0449032 -0.226573 -0.0187517 -0.0448449 -0.226573 -0.0190963 -0.0446326 -0.228762 -0.0184901 -0.0449018 -0.228748 -0.0181551 -0.0448719 -0.228741 -0.0179603 -0.044798 -0.226354 -0.0179603 -0.044798 -0.226294 -0.0177915 -0.0446906 -0.226324 -0.00459457 -0.020086 -0.22874 -0.00459457 -0.020086 -0.228737 -0.00463643 -0.0204032 -0.226573 -0.00320164 -0.0131654 -0.226573 -0.00357768 -0.0133151 -0.228741 -0.00291578 -0.0128788 -0.226354 -0.00291577 -0.0128788 -0.228737 -0.00357437 0.0149096 -0.22874 -0.00370493 0.0152183 -0.228756 -0.00406163 0.0155539 -0.226573 -0.00404737 0.0155458 -0.228783 -0.00455607 0.0156799 -0.226573 -0.00443157 0.0156732 -0.226543 -0.00592646 0.0219473 -0.226573 -0.00617976 0.0215963 -0.226573 -0.00655767 0.0213852 -0.2288 -0.00655767 0.0213852 -0.226273 -0.020311 0.0460225 -0.228764 -0.0212326 0.046318 -0.22875 -0.0208975 0.0463269 -0.226573 -0.0210388 0.0463369 -0.22874 -0.0205784 0.0462245 -0.228783 -0.0215463 0.0461987 -0.226573 -0.0258605 0.0508542 -0.226573 -0.0259253 0.0504695 -0.22874 -0.0506944 0.0646399 -0.228756 -0.0511634 0.0644988 -0.22875 -0.0510219 0.064569 -0.226573 -0.0511367 0.0645142 -0.226294 -0.0505654 0.0646374 -0.226573 -0.0514517 0.0642381 -0.226573 -0.0516227 0.0638712 -0.2288 -0.0574614 0.0652528 -0.228764 -0.0863914 0.0650103 -0.226573 -0.0864382 0.0648035 -0.226573 -0.0863108 0.0651877 -0.22875 -0.0862315 0.065305 -0.226573 -0.0863035 0.0652002 -0.226354 -0.0860416 0.0654899 -0.226294 -0.0858703 0.0655925 -0.228783 -0.0864449 0.064679 -0.226573 -0.0923425 0.0630336 -0.228741 -0.0930513 0.0633886 -0.228737 -0.0934517 0.0633294 -0.228737 -0.116787 0.0489241 -0.228764 -0.117083 0.0480024 -0.228755 -0.117102 0.0481963 -0.226573 -0.117102 0.0482108 -0.226354 -0.11702 0.0485927 -0.226573 -0.11702 0.0477999 -0.228783 -0.116964 0.0476887 -0.2288 -0.116788 0.0474684 -0.226573 -0.121649 0.0433733 -0.226573 -0.121248 0.043315 -0.2288 -0.120904 0.0431027 -0.228748 -0.121845 0.0433419 -0.226294 -0.122209 0.0431606 -0.228737 -0.122357 0.0430165 -0.226273 -0.122357 0.0430165 -0.226294 -0.135402 0.0186697 -0.228755 -0.135272 0.0180858 -0.226573 -0.135272 0.0180858 -0.22874 -0.135405 0.0185406 -0.228762 -0.136677 0.0117037 -0.226573 -0.136798 0.0116354 -0.226573 -0.136422 0.0117852 -0.228741 -0.137084 0.0113489 -0.226294 -0.137177 0.0111714 -0.228764 -0.135775 -0.0171563 -0.226573 -0.135569 -0.0172031 -0.226573 -0.135965 -0.0170684 -0.22874 -0.136295 -0.0167483 -0.226294 -0.136357 -0.0166352 -0.228783 -0.135444 -0.0172099 -0.228762 -0.133979 -0.0233055 -0.226573 -0.134049 -0.0234251 -0.22878 -0.133744 -0.0230645 -0.226573 -0.133799 -0.0231074 -0.226573 -0.133442 -0.0229151 -0.228748 -0.13412 -0.0236105 -0.228741 -0.134154 -0.0238162 -0.228739 -0.134153 -0.0239449 -0.228737 -0.134094 -0.0242166 -0.226294 -0.134145 -0.0240161 -0.228764 -0.118767 -0.047848 -0.22875 -0.119103 -0.0478568 -0.226573 -0.118976 -0.0478668 -0.22874 -0.119422 -0.0477545 -0.226354 -0.119358 -0.0477848 -0.228783 -0.118454 -0.0477286 -0.2288 -0.118233 -0.0475529 -0.226573 -0.118565 -0.0477851 -0.226573 -0.114138 -0.0524139 -0.22878 -0.114054 -0.0519488 -0.228748 -0.114107 -0.0526099 -0.228741 -0.114033 -0.0528047 -0.226354 -0.114033 -0.0528047 -0.226294 -0.113926 -0.0529735 -0.228737 -0.113782 -0.0531218 -0.226273 -0.0896383 -0.0661286 -0.226294 -0.0894347 -0.0661673 -0.228737 -0.0896383 -0.0661286 -0.228764 -0.0886924 -0.0659237 -0.226573 -0.0888508 -0.0660371 -0.22875 -0.0889782 -0.066099 -0.22874 -0.0893057 -0.0661699 -0.226354 -0.0892351 -0.0661642 -0.226573 -0.0885484 -0.065768 -0.226573 -0.0825502 -0.0671873 -0.226573 -0.0825386 -0.0667827 -0.2288 -0.0825386 -0.0667827 -0.228741 -0.0821139 -0.0678492 -0.226354 -0.0821139 -0.0678492 -0.226573 -0.0209235 -0.0454781 -0.224773 -0.0211142 -0.046284 -0.226573 -0.0211142 -0.046284 -0.226573 -0.0224757 -0.0471245 -0.224773 -0.0238843 -0.0463656 -0.224773 -0.00509487 -0.0165487 -0.224773 -0.00566301 -0.0171513 -0.226573 -0.00645635 -0.0173892 -0.224773 -0.00645635 -0.0173892 -0.224773 -0.00810277 -0.015837 -0.224773 -0.00608936 0.0172125 -0.226573 -0.00589865 0.0180185 -0.226573 -0.00608936 0.0172125 -0.224773 -0.0066575 0.0166099 -0.226573 -0.00745084 0.0163721 -0.224773 -0.00825681 0.0165628 -0.226573 -0.00825681 0.0165628 -0.224773 -0.00885944 0.0171309 -0.226573 -0.00909726 0.0179243 -0.226573 -0.0236405 0.0467594 -0.224773 -0.0243994 0.0453508 -0.226573 -0.0238312 0.0459534 -0.224773 -0.0251927 0.0451129 -0.226573 -0.0259987 0.0453036 -0.226573 -0.0549281 0.0611323 -0.224773 -0.0563367 0.0618912 -0.226573 -0.0871371 0.0617842 -0.224773 -0.0873278 0.0609783 -0.226573 -0.0873278 0.0609783 -0.224773 -0.087896 0.0603756 -0.224773 -0.0886893 0.0601378 -0.224773 -0.0894953 0.0603285 -0.226573 -0.0894953 0.0603285 -0.226573 -0.0900979 0.0608967 -0.224773 -0.0903357 0.06169 -0.226573 -0.116069 0.0432364 -0.224773 -0.116637 0.0426338 -0.224773 -0.11743 0.0423959 -0.226573 -0.116637 0.0426338 -0.226573 -0.11743 0.0423959 -0.226573 -0.118236 0.0425866 -0.224773 -0.118236 0.0425866 -0.226573 -0.119077 0.0439481 -0.224773 -0.132088 0.013501 -0.226573 -0.13345 0.0126606 -0.224773 -0.134858 0.0134195 -0.224773 -0.135096 0.0142128 -0.226573 -0.134858 0.0134195 -0.226573 -0.130903 -0.0194542 -0.226573 -0.131094 -0.0202602 -0.226573 -0.131662 -0.0208628 -0.226573 -0.132455 -0.0211006 -0.224773 -0.113352 -0.049001 -0.224773 -0.11392 -0.0496037 -0.226573 -0.11392 -0.0496037 -0.224773 -0.115519 -0.0496508 -0.226573 -0.116122 -0.0490826 -0.226573 -0.0834256 -0.0642144 -0.224773 -0.0836163 -0.0650204 -0.224773 -0.0841845 -0.065623 -0.226573 -0.0841845 -0.065623 -0.224773 -0.0849778 -0.0658609 -0.226573 -0.0849778 -0.0658609 -0.224773 -0.0863864 -0.065102 -0.2288 -0.0883774 -0.0654011 -0.229483 -0.0821055 -0.0649524 -0.226573 -0.0821055 -0.0649524 -0.226573 -0.0826646 -0.0624098 -0.230598 -0.0826625 -0.0624125 -0.226573 -0.0837018 -0.0615691 -0.23092 -0.0843289 -0.0613434 -0.2308 -0.0832379 -0.0618519 -0.230773 -0.0856728 -0.0613324 -0.226573 -0.0863864 -0.065102 -0.226573 -0.0857838 -0.0656701 -0.226573 -0.0823924 -0.0675754 -0.226573 -0.0824004 -0.0675634 -0.226573 -0.0888634 -0.0660442 -0.226573 -0.0864863 -0.0636101 -0.226573 -0.0883774 -0.0654011 -0.226573 -0.0879443 -0.0635708 -0.226573 -0.0873555 -0.0623725 -0.226573 -0.086305 -0.0615484 -0.226573 -0.0854267 -0.0627128 -0.226573 -0.084715 -0.0626919 -0.226573 -0.0850011 -0.0612616 -0.226573 -0.0820949 -0.0636173 -0.226573 -0.0836163 -0.0650204 -0.229483 -0.0245808 -0.047708 -0.226573 -0.0245808 -0.047708 -0.229483 -0.0204649 -0.0433423 -0.229959 -0.0213249 -0.0427747 -0.226573 -0.0204649 -0.0433423 -0.226573 -0.0216883 -0.0426436 -0.23032 -0.0221493 -0.0425485 -0.23046 -0.0225257 -0.0425252 -0.226573 -0.0252491 -0.0442733 -0.230842 -0.0252504 -0.044276 -0.226573 -0.0228986 -0.0496965 -0.226573 -0.0183367 -0.0449023 -0.226573 -0.0216824 -0.0468867 -0.226573 -0.0232817 -0.0469338 -0.226573 -0.0232122 -0.0489983 -0.226573 -0.0238843 -0.0463656 -0.226573 -0.0241221 -0.0455723 -0.226573 -0.0255215 -0.0456135 -0.226573 -0.0239314 -0.0447663 -0.226573 -0.024377 -0.0431667 -0.226573 -0.0230958 -0.0425804 -0.226573 -0.021764 -0.0441166 -0.2288 -0.00536387 -0.0191423 -0.226573 -0.00398227 -0.0133036 -0.229483 -0.00581266 -0.0128705 -0.226573 -0.00581266 -0.0128705 -0.226573 -0.00717511 -0.012866 -0.230892 -0.00923119 -0.014541 -0.226573 -0.00923198 -0.0145428 -0.226573 -0.00839903 -0.0134646 -0.230916 -0.00936262 -0.0148814 -0.23092 -0.0094216 -0.0150938 -0.226573 -0.00508298 -0.0150535 -0.226573 -0.00490416 -0.0157427 -0.226573 -0.00509487 -0.0165487 -0.226573 -0.00472082 -0.0196283 -0.226573 -0.00566301 -0.0171513 -0.226573 -0.00719426 -0.0187092 -0.226573 -0.00726232 -0.0171984 -0.226573 -0.00786495 -0.0166303 -0.226573 -0.00810277 -0.015837 -0.226573 -0.00796483 -0.0151384 -0.226573 -0.00950216 -0.0158782 -0.226573 -0.00690527 -0.0142411 -0.226573 -0.00619351 -0.0142202 -0.229483 -0.00663651 0.0150977 -0.226573 -0.00663651 0.0150977 -0.2288 -0.00483479 0.0156378 -0.226573 -0.00483479 0.0156378 -0.229483 -0.0083594 0.0208451 -0.226573 -0.0083594 0.0208451 -0.229927 -0.00922251 0.0204262 -0.230323 -0.00989283 0.0197782 -0.230473 -0.0101153 0.0194376 -0.23077 -0.0104579 0.0184602 -0.226573 -0.00403491 0.0155385 -0.226573 -0.00594434 0.0219081 -0.226573 -0.0066575 0.0166099 -0.226573 -0.00885944 0.0171309 -0.226573 -0.0104967 0.0178831 -0.226573 -0.00890655 0.0187303 -0.226573 -0.0083384 0.0193329 -0.226573 -0.010253 0.0191586 -0.226573 -0.00949315 0.0202118 -0.226573 -0.00754506 0.0195707 -0.226573 -0.0217667 0.0460229 -0.226573 -0.0261324 0.0501388 -0.226573 -0.0274227 0.0487702 -0.229813 -0.0278455 0.048199 -0.226573 -0.0214352 0.0462551 -0.226573 -0.0238193 0.0474486 -0.226573 -0.0210243 0.0463368 -0.226573 -0.0258627 0.0508984 -0.226573 -0.0242795 0.047992 -0.226573 -0.0249299 0.0482819 -0.226573 -0.0243994 0.0453508 -0.226573 -0.0251927 0.0451129 -0.226573 -0.0266013 0.0458718 -0.226573 -0.0268391 0.0466651 -0.226573 -0.0267012 0.0473637 -0.226573 -0.0280466 0.0477716 -0.2288 -0.0516227 0.0638712 -0.226573 -0.0578946 0.0634224 -0.229483 -0.0578946 0.0634224 -0.229847 -0.0579739 0.0626433 -0.226573 -0.055377 0.0642803 -0.226573 -0.057435 0.0655125 -0.226573 -0.0511493 0.0645071 -0.226573 -0.0540148 0.0640114 -0.226573 -0.0546652 0.0643013 -0.226573 -0.0535547 0.063468 -0.226573 -0.0533759 0.0627787 -0.226573 -0.0535666 0.0619728 -0.226573 -0.0527046 0.0607708 -0.226573 -0.0541347 0.0613701 -0.226573 -0.055734 0.061323 -0.226573 -0.0566228 0.0602246 -0.226573 -0.0563367 0.0618912 -0.226573 -0.0575943 0.0612686 -0.226573 -0.0565745 0.0626845 -0.226573 -0.0579739 0.0626433 -0.226573 -0.0574614 0.0652528 -0.229483 -0.0858627 0.0625986 -0.2288 -0.0864029 0.0644003 -0.226573 -0.0921502 0.0626774 -0.229624 -0.0915088 0.060591 -0.23019 -0.090796 0.0595559 -0.230469 -0.0902115 0.0591248 -0.226573 -0.0894272 0.0588177 -0.230738 -0.0893652 0.0588037 -0.230773 -0.0867107 0.0595243 -0.226573 -0.087875 0.0588635 -0.230454 -0.086048 0.0604058 -0.226573 -0.0858627 0.0625986 -0.229996 -0.0857463 0.0614936 -0.226573 -0.0926602 0.0632843 -0.226573 -0.090145 0.062496 -0.226573 -0.0887835 0.0633364 -0.226573 -0.0926732 0.0632907 -0.226573 -0.0864029 0.0644003 -0.226573 -0.085817 0.0610463 -0.226573 -0.0865536 0.0596792 -0.226573 -0.087896 0.0603756 -0.226573 -0.0886893 0.0601378 -0.226573 -0.0907943 0.0595543 -0.226573 -0.0916101 0.0608757 -0.226573 -0.0903357 0.06169 -0.226573 -0.116788 0.0474684 -0.226573 -0.120904 0.0431027 -0.226573 -0.119535 0.0418124 -0.226573 -0.118384 0.0411356 -0.230091 -0.118394 0.0411388 -0.230469 -0.117449 0.0409954 -0.230598 -0.117057 0.0410248 -0.230738 -0.116555 0.0411405 -0.226573 -0.117054 0.0410253 -0.230912 -0.115084 0.0421859 -0.226573 -0.115807 0.0415032 -0.226573 -0.114488 0.0437473 -0.230454 -0.114483 0.0441865 -0.226573 -0.114676 0.045069 -0.226573 -0.117102 0.0481963 -0.226573 -0.117524 0.0455945 -0.226573 -0.116718 0.0454038 -0.226573 -0.115419 0.0461781 -0.226573 -0.116116 0.0448357 -0.226573 -0.115878 0.0440424 -0.226573 -0.114891 0.0424746 -0.226573 -0.118839 0.0431548 -0.229483 -0.134187 0.0113405 -0.230091 -0.132863 0.0113277 -0.226573 -0.132635 0.0113862 -0.226573 -0.131314 0.012202 -0.2308 -0.131087 0.0124729 -0.23089 -0.130777 0.0129928 -0.230773 -0.130567 0.0149078 -0.226573 -0.130577 0.0135691 -0.23092 -0.130578 0.0135639 -0.230722 -0.130624 0.0151247 -0.230454 -0.130999 0.0159225 -0.230189 -0.131442 0.0164456 -0.226573 -0.132806 0.0171793 -0.226573 -0.135279 0.0180984 -0.226573 -0.13681 0.0116274 -0.226573 -0.134337 0.0156214 -0.226573 -0.135003 0.0177834 -0.226573 -0.133544 0.0158592 -0.226573 -0.134636 0.0176124 -0.226573 -0.132738 0.0156685 -0.226573 -0.131439 0.0164428 -0.226573 -0.131897 0.014307 -0.226573 -0.130623 0.0151213 -0.226573 -0.132088 0.013501 -0.226573 -0.132656 0.0128984 -0.226573 -0.134187 0.0113405 -0.226573 -0.136018 0.0117736 -0.226573 -0.134255 0.0128513 -0.2288 -0.133442 -0.0229151 -0.226573 -0.131641 -0.022375 -0.23019 -0.130321 -0.021561 -0.230469 -0.12989 -0.0209764 -0.230738 -0.129569 -0.02013 -0.2308 -0.129522 -0.0198441 -0.226573 -0.129583 -0.0201921 -0.226573 -0.129628 -0.0186399 -0.230912 -0.129739 -0.0183336 -0.23092 -0.129627 -0.0186451 -0.230773 -0.130289 -0.0174756 -0.230722 -0.130447 -0.0173161 -0.230189 -0.131815 -0.016581 -0.226573 -0.133364 -0.0166277 -0.229483 -0.133364 -0.0166277 -0.226573 -0.135953 -0.0170758 -0.226573 -0.133911 -0.0187425 -0.226573 -0.134101 -0.0195484 -0.226573 -0.135165 -0.0171678 -0.226573 -0.132549 -0.017902 -0.226573 -0.131811 -0.016582 -0.226573 -0.131743 -0.0180927 -0.226573 -0.130444 -0.0173185 -0.226573 -0.133864 -0.0203418 -0.226573 -0.130319 -0.0215593 -0.226573 -0.133261 -0.0209099 -0.2288 -0.113868 -0.0516687 -0.229483 -0.112577 -0.0503001 -0.229624 -0.112381 -0.0500701 -0.230469 -0.11176 -0.0482134 -0.226573 -0.11179 -0.0478187 -0.230883 -0.113242 -0.0456549 -0.230912 -0.112951 -0.0458492 -0.23092 -0.112698 -0.046063 -0.226573 -0.112268 -0.046572 -0.23089 -0.112303 -0.0465207 -0.230773 -0.113857 -0.0453815 -0.230454 -0.114952 -0.0452483 -0.229996 -0.116044 -0.0455309 -0.226573 -0.115834 -0.0454409 -0.226573 -0.116943 -0.0461842 -0.229483 -0.116943 -0.0461842 -0.226273 -0.0543255 -0.0671906 -0.2263 -0.0541065 -0.0671111 -0.226374 -0.0539202 -0.06699 -0.226273 -0.0511984 -0.0663741 -0.226573 -0.0473269 -0.0648207 -0.226294 -0.0467489 -0.0649099 -0.228737 -0.0543255 -0.0671906 -0.22874 -0.0540167 -0.06706 -0.226573 -0.0536966 -0.0667301 -0.228753 -0.0537202 -0.0667677 -0.228764 -0.0536104 -0.0665452 -0.228784 -0.0535555 -0.0661879 -0.226573 -0.0473399 -0.0648143 -0.22878 -0.0477005 -0.0645087 -0.228748 -0.0471545 -0.0648851 -0.226354 -0.0469488 -0.0649186 -0.228737 -0.0465484 -0.0648593 -0.224773 -0.0498551 -0.0640259 -0.224773 -0.0504232 -0.0646285 -0.226573 -0.0512166 -0.0648664 -0.224773 -0.0512166 -0.0648664 -0.226573 -0.0520225 -0.0646757 -0.224773 -0.0526252 -0.0641075 -0.226573 -0.052863 -0.0633142 -0.226573 -0.0541373 -0.0641285 -0.229483 -0.04839 -0.0624056 -0.226573 -0.0478499 -0.0642073 -0.226573 -0.04839 -0.0624056 -0.226573 -0.0491125 -0.061176 -0.230008 -0.0489182 -0.0613966 -0.229751 -0.0486072 -0.0618731 -0.230317 -0.0494458 -0.0608806 -0.230461 -0.0497676 -0.0606667 -0.230906 -0.0517191 -0.0603018 -0.226573 -0.0517427 -0.0603055 -0.23069 -0.0535333 -0.0613052 -0.226573 -0.053056 -0.0608613 -0.230886 -0.0527184 -0.0606434 -0.230918 -0.0522889 -0.0604477 -0.226573 -0.0542624 -0.0633554 -0.226573 -0.0539643 -0.0619608 -0.230475 -0.0539254 -0.0618832 -0.226573 -0.0504232 -0.0646285 -0.226573 -0.0536448 -0.0666313 -0.226573 -0.0526252 -0.0641075 -0.226573 -0.0509537 -0.0616974 -0.226573 -0.0503211 -0.060419 -0.226573 -0.0503034 -0.0619873 -0.226573 -0.0498432 -0.0625307 -0.226573 -0.0496644 -0.0632199 -0.226573 -0.0498551 -0.0640259 -0.226573 -0.0476576 -0.0645635 -0.233273 -0.0138744 0.0008883 -0.233273 -0.0145262 -0.00945291 -0.233273 -0.0170672 -0.0194983 -0.233473 -0.0212376 -0.0290059 -0.233273 -0.0435027 -0.0502697 -0.233473 -0.0434084 -0.050446 -0.233473 -0.05299 -0.0544863 -0.233273 -0.0530504 -0.0542956 -0.233273 -0.0735324 -0.0568037 -0.233273 -0.0935374 -0.0517435 -0.233473 -0.0936213 -0.0519251 -0.233273 -0.102504 -0.0465505 -0.233473 -0.117016 -0.0318272 -0.233473 -0.126326 -0.00242413 -0.235873 -0.126326 -0.00242413 -0.235873 -0.10262 -0.0467136 -0.236073 -0.0735324 -0.0568037 -0.235873 -0.0838184 -0.0553944 -0.236073 -0.0631752 -0.0564987 -0.235873 -0.05299 -0.0544863 -0.235873 -0.0434084 -0.050446 -0.235873 -0.0347323 -0.0447139 -0.236073 -0.0145262 -0.00945291 -0.235873 -0.0143287 -0.00948386 -0.236073 -0.0138744 0.0008883 -0.233561 -0.127537 -0.00245982 -0.233513 -0.127475 -0.00245799 -0.233623 -0.0124865 -0.00409402 -0.233658 -0.0123979 0.000931793 -0.233773 -0.0138992 -0.0140398 -0.233623 -0.0153078 -0.0188662 -0.233773 -0.0170567 -0.02358 -0.233773 -0.0218228 -0.0324269 -0.233773 -0.0247656 -0.0365053 -0.233773 -0.0280527 -0.0403117 -0.233623 -0.0316858 -0.0437872 -0.233623 -0.0355812 -0.0469628 -0.233773 -0.0355572 -0.046995 -0.233623 -0.0397386 -0.0497868 -0.233623 -0.0487109 -0.0542969 -0.233773 -0.0441083 -0.0522736 -0.233623 -0.0534575 -0.0559486 -0.233773 -0.053446 -0.0559871 -0.233773 -0.0632867 -0.0580228 -0.233623 -0.0733291 -0.0582785 -0.233773 -0.0683026 -0.05839 -0.233773 -0.0783349 -0.0578093 -0.233773 -0.0832749 -0.0568658 -0.233623 -0.0927991 -0.0536714 -0.233773 -0.0881139 -0.0554953 -0.233623 -0.0973235 -0.051483 -0.233773 -0.101662 -0.0489422 -0.233773 -0.10574 -0.0459994 -0.233623 -0.109519 -0.042683 -0.233773 -0.109547 -0.0427123 -0.233623 -0.116198 -0.0351838 -0.233773 -0.11623 -0.0352078 -0.233623 -0.119022 -0.0310264 -0.233773 -0.119056 -0.0310475 -0.233773 -0.121509 -0.0266568 -0.233623 -0.123532 -0.0220541 -0.233773 -0.123569 -0.022069 -0.233623 -0.125184 -0.0173075 -0.233773 -0.125222 -0.017319 -0.233773 -0.127258 -0.0074783 -0.233623 -0.127218 -0.00747362 -0.233623 -0.126415 -0.012435 -0.233513 -0.126308 -0.0124127 -0.233513 -0.12343 -0.0220135 -0.233623 -0.121473 -0.0266387 -0.233513 -0.118928 -0.0309687 -0.233513 -0.11611 -0.0351182 -0.233623 -0.113022 -0.0390792 -0.233513 -0.11294 -0.0390062 -0.233623 -0.105715 -0.0459678 -0.233513 -0.105647 -0.0458817 -0.233623 -0.10164 -0.0489086 -0.233513 -0.10158 -0.0488169 -0.233623 -0.0881013 -0.0554572 -0.233513 -0.0880668 -0.0553529 -0.233623 -0.0832656 -0.0568267 -0.233623 -0.0783291 -0.0577695 -0.233623 -0.0683038 -0.0583498 -0.233513 -0.068307 -0.05824 -0.233623 -0.0632914 -0.0579828 -0.233513 -0.0633042 -0.0578738 -0.233623 -0.0583301 -0.0571804 -0.233513 -0.0487515 -0.0541948 -0.233623 -0.0441263 -0.0522377 -0.233513 -0.0397963 -0.0496933 -0.233513 -0.0356469 -0.0468747 -0.233513 -0.0317589 -0.0437052 -0.233623 -0.028082 -0.0402842 -0.233623 -0.0247972 -0.0364804 -0.233513 -0.0248833 -0.0364123 -0.233623 -0.0218564 -0.0324048 -0.233623 -0.019282 -0.0280884 -0.233513 -0.0193787 -0.0280363 -0.233623 -0.0170936 -0.023564 -0.233513 -0.0171944 -0.0235206 -0.233513 -0.0154121 -0.0188317 -0.233623 -0.0139383 -0.0140306 -0.233513 -0.0140452 -0.0140053 -0.233623 -0.0129955 -0.00909399 -0.233513 -0.0125961 -0.00408768 -0.233473 -0.0127459 -0.00407901 -0.233473 -0.0132526 -0.00905643 -0.233513 -0.0131042 -0.00907811 -0.233473 -0.0141912 -0.0139707 -0.233473 -0.0155545 -0.0187846 -0.233473 -0.0173322 -0.0234612 -0.233513 -0.0219481 -0.0323445 -0.233473 -0.025001 -0.0363193 -0.233473 -0.028271 -0.0401059 -0.233513 -0.0281619 -0.0402088 -0.233473 -0.0357365 -0.0467544 -0.233513 -0.0441756 -0.0521396 -0.233473 -0.0488069 -0.0540554 -0.233473 -0.0583827 -0.056926 -0.233513 -0.0534891 -0.0558434 -0.233513 -0.0583523 -0.0570729 -0.233473 -0.0633217 -0.0577248 -0.233473 -0.0683114 -0.0580901 -0.233473 -0.0733141 -0.0580191 -0.233513 -0.0733228 -0.0581689 -0.233513 -0.0783132 -0.0576609 -0.233473 -0.0832058 -0.0565738 -0.233513 -0.0832404 -0.0567198 -0.233473 -0.0880196 -0.0552105 -0.233513 -0.0927557 -0.0535706 -0.233513 -0.0972714 -0.0513864 -0.233473 -0.101497 -0.0486915 -0.233473 -0.105554 -0.045764 -0.233473 -0.109341 -0.042494 -0.233473 -0.112828 -0.0389064 -0.233513 -0.109444 -0.0426031 -0.233473 -0.115989 -0.0350285 -0.233473 -0.118801 -0.0308899 -0.233513 -0.121375 -0.0265894 -0.233513 -0.125079 -0.0172759 -0.233473 -0.126161 -0.0123823 -0.233513 -0.127109 -0.00746083 -0.235833 -0.127475 -0.00245799 -0.235873 -0.126662 -0.009625 -0.23585 -0.126775 -0.00964274 -0.235873 -0.0126749 0.000923632 -0.23585 -0.050641 -0.0548707 -0.235873 -0.0506796 -0.0547626 -0.235873 -0.0440643 -0.0519153 -0.235873 -0.122678 -0.0234378 -0.23585 -0.122783 -0.0234832 -0.23585 -0.11952 -0.0299195 -0.23585 -0.0125602 0.000927013 -0.235833 -0.012525 0.000928049 -0.235785 -0.0124629 0.000929878 -0.23585 -0.0647047 -0.0579853 -0.23585 -0.0575749 -0.0568704 -0.235873 -0.0647153 -0.057871 -0.235785 -0.122873 -0.0235216 -0.235785 -0.125308 -0.0167155 -0.23585 -0.125215 -0.0166885 -0.235688 -0.0137856 -0.0134466 -0.235573 -0.0186851 -0.0270386 -0.235873 -0.0160789 -0.0202977 -0.23585 -0.0159709 -0.0203368 -0.23585 -0.01885 -0.0269542 -0.235785 -0.0224553 -0.0332133 -0.235873 -0.0226305 -0.0330937 -0.23585 -0.0225357 -0.0331584 -0.235573 -0.0376898 -0.0485098 -0.235688 -0.0377026 -0.0484909 -0.23585 -0.0320828 -0.0439447 -0.235688 -0.0439389 -0.0521625 -0.235785 -0.0439684 -0.0521045 -0.235873 -0.0321585 -0.0438584 -0.235873 -0.037858 -0.0482614 -0.23585 -0.0440124 -0.0520177 -0.23585 -0.0377936 -0.0483565 -0.235688 -0.0575398 -0.0570289 -0.235785 -0.0791166 -0.0576006 -0.235688 -0.0791269 -0.0576648 -0.235785 -0.0719213 -0.058295 -0.23585 -0.0791012 -0.0575045 -0.235785 -0.0861681 -0.0560098 -0.235873 -0.09288 -0.0533533 -0.23585 -0.0993493 -0.0501697 -0.235785 -0.10537 -0.0461785 -0.235688 -0.10541 -0.0462298 -0.235573 -0.110845 -0.0414494 -0.235873 -0.105239 -0.0460111 -0.23585 -0.10531 -0.0461017 -0.235785 -0.110783 -0.0413874 -0.23585 -0.110714 -0.0413187 -0.235785 -0.115552 -0.0359556 -0.235785 -0.119604 -0.0299689 -0.235688 -0.11966 -0.0300019 -0.235573 -0.122954 -0.0235564 -0.235688 -0.0126394 -0.00630105 -0.235688 -0.0123979 0.000931793 -0.235573 -0.0126167 -0.00630325 -0.235573 -0.012375 0.000932466 -0.23585 -0.012801 -0.00628546 -0.235785 -0.013849 -0.0134323 -0.235785 -0.0127041 -0.00629481 -0.235688 -0.0158183 -0.0203921 -0.235573 -0.0157968 -0.0203999 -0.235573 -0.0129557 -0.0090998 -0.23585 -0.013944 -0.0134109 -0.235785 -0.0158794 -0.02037 -0.235785 -0.0187633 -0.0269985 -0.235688 -0.0187054 -0.0270281 -0.235573 -0.0192466 -0.0281075 -0.235688 -0.0268483 -0.0389595 -0.235688 -0.0224016 -0.03325 -0.235785 -0.026897 -0.0389164 -0.235688 -0.0319757 -0.0440667 -0.23585 -0.0269699 -0.0388519 -0.235785 -0.0320186 -0.0440178 -0.235785 -0.0377391 -0.0484371 -0.235573 -0.0575348 -0.0570512 -0.235573 -0.0505786 -0.0550451 -0.235688 -0.0505863 -0.0550236 -0.235573 -0.0439286 -0.0521829 -0.235785 -0.0506082 -0.0549623 -0.235785 -0.0575538 -0.0569654 -0.235688 -0.0646898 -0.0581469 -0.235573 -0.0646877 -0.0581697 -0.23585 -0.0719181 -0.0581978 -0.235785 -0.0646957 -0.0580822 -0.235688 -0.0719235 -0.05836 -0.235573 -0.0861928 -0.0560941 -0.235573 -0.0791305 -0.0576873 -0.235573 -0.0783349 -0.0578093 -0.235688 -0.0861864 -0.0560722 -0.235573 -0.0994439 -0.0503289 -0.235688 -0.0994322 -0.0503093 -0.235573 -0.0973425 -0.0515184 -0.235688 -0.0929906 -0.0536074 -0.23585 -0.0861408 -0.0559164 -0.235873 -0.0861085 -0.0558062 -0.235785 -0.0929646 -0.0535478 -0.23585 -0.0929258 -0.0534585 -0.235785 -0.099399 -0.0502534 -0.235688 -0.110829 -0.0414333 -0.235573 -0.119056 -0.0310475 -0.235688 -0.115604 -0.0359954 -0.235873 -0.110632 -0.0412377 -0.23585 -0.115475 -0.0358961 -0.235688 -0.122933 -0.0235474 -0.235688 -0.125371 -0.0167335 -0.235785 -0.126871 -0.00965778 -0.235785 -0.127537 -0.00245982 -0.235723 -0.127585 -0.00246122 -0.235688 -0.126935 -0.00966782 -0.235873 -0.0768492 0.0551672 -0.235873 -0.125671 0.00795392 -0.235873 -0.125809 0.0124408 -0.235873 -0.0716886 0.0565602 -0.235873 -0.0664551 0.0554734 -0.235873 -0.0385029 0.0471616 -0.235873 -0.0463788 0.0503952 -0.235873 -0.0473038 0.0519029 -0.235873 -0.0519805 0.0536806 -0.235873 -0.0561816 0.0538645 -0.235873 -0.0567943 0.0550439 -0.235873 -0.0575997 -0.0567583 -0.235873 -0.123121 0.0180351 -0.235873 -0.0344457 0.044234 -0.235873 -0.0306591 0.040964 -0.235873 -0.0211993 0.02936 -0.235873 -0.079083 -0.0573911 -0.235873 -0.073545 -0.0570034 -0.235873 -0.0719142 -0.058083 -0.235873 -0.0631509 -0.0566972 -0.235873 -0.110507 -0.0399374 -0.235873 -0.115385 -0.0358259 -0.235873 -0.125104 -0.0166567 -0.235873 -0.121923 -0.0226592 -0.235873 -0.117016 -0.0318272 -0.235873 -0.119421 -0.0298613 -0.235873 -0.112743 0.0359552 -0.235873 -0.105268 0.0431839 -0.235873 -0.100125 0.0480358 -0.235873 -0.108141 0.0420632 -0.235873 -0.0864679 0.0541698 -0.235873 -0.0870101 0.0529564 -0.235873 -0.0957571 0.0504756 -0.235873 -0.0129153 -0.00627443 -0.235873 -0.0149384 0.0112157 -0.235873 -0.013839 0.0108524 -0.235873 -0.0212376 -0.0290059 -0.235873 -0.0189522 -0.0269018 -0.235873 -0.0168787 -0.019565 -0.235873 -0.0140559 -0.0133856 -0.235873 -0.0270559 -0.0387758 -0.235873 -0.0272572 -0.0374851 -0.235873 -0.0992907 -0.050071 -0.235873 -0.0936213 -0.0519251 -0.235873 -0.126748 0.00752648 -0.235873 -0.127254 0.00254907 -0.235873 -0.125062 -0.0127457 -0.235873 -0.127325 -0.00245357 -0.233473 -0.0870101 0.0529564 -0.233473 -0.0768492 0.0551672 -0.233473 -0.0752848 0.056341 -0.233473 -0.123921 0.0187678 -0.233473 -0.0168787 -0.019565 -0.233473 -0.0133386 0.00809506 -0.233473 -0.0126749 0.000923632 -0.233473 -0.0143287 -0.00948386 -0.233473 -0.0959358 0.0503854 -0.233473 -0.0824004 0.0552284 -0.233473 -0.11737 0.0315638 -0.233473 -0.112743 0.0359552 -0.233473 -0.107842 0.0423284 -0.233473 -0.127085 0.00474449 -0.233473 -0.127325 -0.00245357 -0.233473 -0.12696 -0.00744336 -0.233473 -0.0561816 0.0538645 -0.233473 -0.0538916 0.0542763 -0.233473 -0.125062 -0.0127457 -0.233473 -0.124935 -0.0172329 -0.233473 -0.121923 -0.0226592 -0.233473 -0.121241 -0.026522 -0.233473 -0.123291 -0.0219581 -0.233473 -0.0180774 0.0211293 -0.233473 -0.0173221 0.0219078 -0.233473 -0.0149384 0.0112157 -0.233473 -0.110507 -0.0399374 -0.233473 -0.10262 -0.0467136 -0.233473 -0.0972002 -0.0512543 -0.233473 -0.0926963 -0.0534328 -0.233473 -0.0838184 -0.0553944 -0.233473 -0.0782915 -0.0575124 -0.233473 -0.073545 -0.0570034 -0.233473 -0.0631509 -0.0566972 -0.233473 -0.0407094 0.048541 -0.233473 -0.0373803 0.0451837 -0.233473 -0.0293677 0.0397077 -0.233473 -0.0246156 0.034296 -0.233473 -0.0398751 -0.0495657 -0.233473 -0.044243 -0.0520056 -0.233473 -0.0535321 -0.0556998 -0.233473 -0.0195107 -0.0279652 -0.233473 -0.0220735 -0.0322621 -0.233473 -0.0272572 -0.0374851 -0.233473 -0.0347323 -0.0447139 -0.233473 -0.0318586 -0.0435932 -0.233773 -0.0124464 -0.00409634 -0.233773 -0.0129557 -0.0090998 -0.233773 -0.0152697 -0.0188788 -0.235573 -0.0137633 -0.0134516 -0.235573 -0.0152697 -0.0188788 -0.233773 -0.0192466 -0.0281075 -0.235573 -0.0223827 -0.0332628 -0.235573 -0.0247656 -0.0365053 -0.235573 -0.0268312 -0.0389746 -0.235573 -0.0319606 -0.0440838 -0.233773 -0.0316591 -0.0438172 -0.233773 -0.0397175 -0.049821 -0.235573 -0.0397175 -0.049821 -0.233773 -0.0486961 -0.0543342 -0.235573 -0.0486961 -0.0543342 -0.233773 -0.0583219 -0.0572198 -0.235573 -0.0583219 -0.0572198 -0.235573 -0.0683026 -0.05839 -0.233773 -0.0733314 -0.0583186 -0.235573 -0.0719243 -0.0583829 -0.235573 -0.0881139 -0.0554953 -0.233773 -0.092815 -0.0537083 -0.235573 -0.0929997 -0.0536284 -0.233773 -0.0973425 -0.0515184 -0.235573 -0.105424 -0.0462478 -0.233773 -0.113052 -0.0391059 -0.235573 -0.113052 -0.0391059 -0.235573 -0.115622 -0.0360094 -0.235573 -0.119679 -0.0300135 -0.235573 -0.123569 -0.022069 -0.235573 -0.125393 -0.0167398 -0.233773 -0.126455 -0.0124431 -0.235573 -0.126455 -0.0124431 -0.235573 -0.126958 -0.00967135 -0.233695 -0.0125502 -0.0135258 -0.233299 -0.0116116 -0.00874911 -0.233695 -0.0138002 -0.0182264 -0.233299 -0.0137221 -0.0182506 -0.233695 -0.0141305 -0.0192559 -0.233695 -0.0174407 -0.0272384 -0.233695 -0.0181902 -0.0286766 -0.233695 -0.0198064 -0.0314883 -0.233695 -0.0238241 -0.0372492 -0.233299 -0.022449 -0.0355766 -0.233299 -0.0254861 -0.0393845 -0.233695 -0.0255479 -0.0393309 -0.233695 -0.0288845 -0.04287 -0.233695 -0.030861 -0.0447133 -0.233695 -0.0390872 -0.0508421 -0.233299 -0.0404377 -0.0517456 -0.233299 -0.0447486 -0.0540127 -0.233695 -0.0538797 -0.0573641 -0.233299 -0.0492321 -0.0559161 -0.233695 -0.0580788 -0.0583949 -0.233695 -0.0586087 -0.058502 -0.233695 -0.0634155 -0.0592454 -0.233299 -0.0585929 -0.0585822 -0.233695 -0.0682673 -0.0595895 -0.233299 -0.0682649 -0.0596712 -0.233299 -0.0731352 -0.0596133 -0.233695 -0.0779731 -0.0590724 -0.233695 -0.0785084 -0.0589967 -0.233299 -0.0779842 -0.0591534 -0.233695 -0.0874614 -0.0569648 -0.233695 -0.0920427 -0.0553309 -0.233299 -0.0920734 -0.0554067 -0.233695 -0.0964735 -0.0533243 -0.233299 -0.0965103 -0.0533973 -0.233299 -0.100766 -0.0510283 -0.233695 -0.104763 -0.04825 -0.233299 -0.10862 -0.0452789 -0.233695 -0.108566 -0.0452171 -0.233695 -0.112105 -0.0418805 -0.233299 -0.112164 -0.0419377 -0.233299 -0.118365 -0.0344363 -0.233299 -0.125151 -0.021533 -0.232967 -0.0109201 -0.0039125 -0.232967 -0.0113818 -0.00878054 -0.232967 -0.0122439 -0.0135938 -0.232755 -0.014824 -0.0230541 -0.232755 -0.0168531 -0.0275344 -0.232755 -0.0192452 -0.0318318 -0.232967 -0.0222618 -0.0357137 -0.232755 -0.0219841 -0.035917 -0.232967 -0.032302 -0.0463633 -0.232755 -0.0320826 -0.0466286 -0.232967 -0.0361962 -0.0493206 -0.232755 -0.0359995 -0.0496031 -0.232755 -0.049029 -0.0564553 -0.232967 -0.0537938 -0.0576658 -0.232967 -0.058548 -0.0588098 -0.232967 -0.0633804 -0.0595572 -0.232755 -0.0682479 -0.0602471 -0.232967 -0.0731476 -0.0598449 -0.232755 -0.0876567 -0.0575932 -0.232967 -0.0921603 -0.0556218 -0.232755 -0.112576 -0.0423402 -0.232967 -0.115598 -0.038463 -0.232967 -0.118556 -0.0345688 -0.232967 -0.125368 -0.0216147 -0.232967 -0.126901 -0.0169712 -0.232967 -0.128045 -0.012217 -0.233299 -0.0111517 -0.00390016 -0.233299 -0.0124704 -0.0135435 -0.232967 -0.0135006 -0.0183195 -0.233299 -0.0153583 -0.0228383 -0.232967 -0.0151432 -0.0229252 -0.232967 -0.0171605 -0.0273796 -0.233299 -0.0173677 -0.0272752 -0.233299 -0.0197367 -0.031531 -0.232967 -0.0195388 -0.0316521 -0.232967 -0.0253109 -0.0395365 -0.233299 -0.0288273 -0.0429285 -0.233299 -0.0324498 -0.0461845 -0.232967 -0.0286653 -0.0430945 -0.233299 -0.0363288 -0.0491302 -0.232967 -0.0403214 -0.0519463 -0.232967 -0.0446493 -0.0542223 -0.232967 -0.0491503 -0.0561332 -0.233299 -0.0538573 -0.0574427 -0.233299 -0.0634064 -0.0593267 -0.232967 -0.068258 -0.0599031 -0.232967 -0.0780156 -0.0593832 -0.233299 -0.0827786 -0.0582947 -0.232967 -0.0828289 -0.0585211 -0.233299 -0.0874857 -0.0570429 -0.232967 -0.0875545 -0.0572644 -0.232967 -0.0966146 -0.0536045 -0.232967 -0.100887 -0.0512262 -0.233299 -0.104812 -0.048316 -0.232967 -0.104949 -0.0485032 -0.232967 -0.108772 -0.0454541 -0.232967 -0.11233 -0.0420998 -0.233299 -0.11542 -0.0383152 -0.233299 -0.120981 -0.0303273 -0.232967 -0.121181 -0.0304436 -0.233299 -0.123248 -0.0260164 -0.232967 -0.123457 -0.0261158 -0.233299 -0.126678 -0.0169077 -0.233299 -0.127817 -0.0121721 -0.233695 -0.125075 -0.0215041 -0.233695 -0.12763 -0.0126862 -0.232967 -0.128792 -0.00738461 -0.232755 -0.129134 -0.00742313 -0.232967 -0.129138 -0.00250698 -0.233299 -0.128562 -0.00735866 -0.230673 -0.0350743 -0.033692 -0.230673 -0.0421691 -0.039873 -0.230673 -0.050989 -0.0430916 -0.230673 -0.0503335 -0.0445511 -0.230673 -0.0596118 -0.0459871 -0.230673 -0.0592536 -0.0475465 -0.230673 -0.0779742 -0.048098 -0.230673 -0.0777084 -0.0465202 -0.230673 -0.0946314 -0.0400875 -0.230673 -0.107804 -0.0276682 -0.230673 -0.112327 -0.019776 -0.230673 -0.117979 -0.00217827 -0.230673 -0.115755 0.00694335 -0.230673 -0.103762 0.0310645 -0.230673 -0.104926 0.0321621 -0.230673 -0.097831 0.0383431 -0.230673 -0.0803882 0.0444572 -0.230673 -0.0713662 0.0456149 -0.230673 -0.0714133 0.0472142 -0.230673 -0.0622917 0.0449903 -0.230673 -0.0535134 0.0426073 -0.230673 -0.0453687 0.0385575 -0.230673 -0.0381706 0.0329966 -0.230673 -0.0276734 0.018246 -0.230673 -0.0232185 0.00998145 -0.230673 -0.0220209 0.000648333 -0.230673 -0.022667 -0.0087391 -0.230673 -0.0251322 -0.0178201 -0.230673 -0.0306776 -0.0253963 -0.230673 -0.0362385 -0.0325945 -0.238173 -0.022667 -0.0087391 -0.230673 -0.0293216 -0.0262457 -0.238173 -0.0293216 -0.0262457 -0.238173 -0.0350743 -0.033692 -0.238173 -0.0421691 -0.039873 -0.238173 -0.0503335 -0.0445511 -0.230673 -0.0685867 -0.0487442 -0.238173 -0.0685867 -0.0487442 -0.230673 -0.0870552 -0.0456328 -0.230673 -0.0954807 -0.0414434 -0.238173 -0.0954807 -0.0414434 -0.230673 -0.102927 -0.0356907 -0.230673 -0.109108 -0.0285959 -0.238173 -0.109108 -0.0285959 -0.230673 -0.113786 -0.0204315 -0.238173 -0.113786 -0.0204315 -0.230673 -0.116782 -0.0115114 -0.238173 -0.116782 -0.0115114 -0.238473 -0.0502106 -0.0448248 -0.238473 -0.0876445 -0.0471833 -0.238473 -0.0871618 -0.0459132 -0.238473 -0.103133 -0.035909 -0.238473 -0.115299 -0.0211111 -0.238473 -0.117074 -0.0115786 -0.238473 -0.118398 -0.0118828 -0.238473 -0.118279 -0.00218711 -0.238473 -0.119637 -0.00222711 -0.238473 -0.118969 0.00748472 -0.238473 -0.0980049 0.0385875 -0.238473 -0.106133 0.0332999 -0.238473 -0.0808136 0.046309 -0.238473 -0.0903462 0.0445343 -0.238473 -0.0714222 0.0475141 -0.238473 -0.0714622 0.0488722 -0.238473 -0.0528383 0.0443833 -0.238473 -0.0523556 0.0456534 -0.238473 -0.0436388 0.0413192 -0.238473 -0.0443601 0.0401677 -0.238473 -0.0359351 0.0353677 -0.238473 -0.0247008 0.0195812 -0.238473 -0.0229261 0.0100486 -0.238473 -0.021721 0.000657166 -0.238473 -0.0216019 0.0103528 -0.238473 -0.0223712 -0.00878894 -0.238473 -0.0210314 -0.00901466 -0.238473 -0.0290674 -0.0264049 -0.238473 -0.0279159 -0.0271262 -0.236973 -0.0201629 0.000703061 -0.238273 -0.0201629 0.000703061 -0.236973 -0.0214069 0.0103976 -0.236973 -0.0245183 0.0196632 -0.238273 -0.0245183 0.0196632 -0.238273 -0.0357979 0.0355132 -0.236973 -0.0357979 0.0355132 -0.238273 -0.0435326 0.0414887 -0.236973 -0.0435326 0.0414887 -0.238273 -0.0617171 0.0484009 -0.238273 -0.0714681 0.0490721 -0.238273 -0.0811626 0.0478281 -0.236973 -0.0714681 0.0490721 -0.236973 -0.0904282 0.0447167 -0.238273 -0.0989087 0.0398575 -0.238273 -0.106278 0.0334371 -0.236973 -0.0989087 0.0398575 -0.236973 -0.106278 0.0334371 -0.238273 -0.112254 0.0257024 -0.238273 -0.116605 0.0169506 -0.236973 -0.119166 0.00751794 -0.236973 -0.119837 -0.002233 -0.236973 -0.112254 0.0257024 -0.236973 -0.108078 0.0319476 -0.236973 -0.0851536 0.0470932 -0.236973 -0.0811626 0.0478281 -0.236973 -0.0761017 0.0490628 -0.236973 -0.0617171 0.0484009 -0.236973 -0.066842 0.0493356 -0.236973 -0.0522845 0.0458403 -0.236973 -0.0489568 0.0448116 -0.236973 -0.0293776 0.0281437 -0.236973 -0.0209478 0.00990817 -0.236973 -0.0198218 0.000713109 -0.236973 -0.0208341 -0.00904789 -0.236973 -0.0233948 -0.0184805 -0.236973 -0.0385814 -0.0399173 -0.236973 -0.0410914 -0.0413874 -0.236973 -0.0495719 -0.0462467 -0.236973 -0.0548465 -0.0486232 -0.236973 -0.0638984 -0.0505928 -0.236973 -0.078283 -0.0499309 -0.236973 -0.0823103 -0.0494322 -0.236973 -0.0877156 -0.0473703 -0.236973 -0.0964674 -0.0430186 -0.236973 -0.106086 -0.0356621 -0.236973 -0.111884 -0.0284371 -0.236973 -0.115482 -0.0211931 -0.236973 -0.120178 -0.00224305 -0.236973 -0.116605 0.0169506 -0.236973 -0.117324 0.0159832 -0.236973 -0.113441 0.0243938 -0.236673 -0.0206546 0.00997195 -0.230673 -0.0206546 0.00997195 -0.236673 -0.0234677 0.0188563 -0.230673 -0.0234677 0.0188563 -0.230673 -0.0278655 0.0270725 -0.236673 -0.033698 0.0343408 -0.230673 -0.033698 0.0343408 -0.230673 -0.0407668 0.0404135 -0.236673 -0.0407668 0.0404135 -0.230673 -0.048831 0.045084 -0.236673 -0.0576162 0.0481931 -0.236673 -0.0668231 0.049635 -0.230673 -0.0668231 0.049635 -0.236673 -0.0761381 0.0493606 -0.230673 -0.0761381 0.0493606 -0.230673 -0.0852442 0.0473793 -0.236673 -0.101606 0.0386214 -0.230673 -0.0938311 0.0437584 -0.230673 -0.101606 0.0386214 -0.230673 -0.117607 0.0160833 -0.236673 -0.117607 0.0160833 -0.236673 -0.119892 0.00704876 -0.230673 -0.120478 -0.00225188 -0.230673 -0.0735324 -0.0568037 -0.230673 -0.0992333 -0.0419434 -0.230673 -0.112135 -0.0286025 -0.230673 -0.116849 -0.031717 -0.230673 -0.121738 -0.0225815 -0.230673 -0.126126 -0.00241824 -0.230673 -0.119892 0.00704876 -0.230673 -0.125474 0.00792297 -0.230673 -0.1137 0.0245441 -0.230673 -0.108306 0.0321431 -0.230673 -0.0869497 0.0527657 -0.230673 -0.0768249 0.0549687 -0.230673 -0.0576162 0.0481931 -0.230673 -0.0562307 0.0536706 -0.230673 -0.0464626 0.0502136 -0.230673 -0.0374961 0.0450206 -0.230673 -0.0296365 0.0382684 -0.230673 -0.0138744 0.0008883 -0.230673 -0.0201082 -0.0085787 -0.230673 -0.0170672 -0.0194983 -0.230673 -0.0274089 -0.0373548 -0.236873 -0.105268 0.0431839 -0.236873 -0.100283 0.048291 -0.236873 -0.091304 0.0528043 -0.236873 -0.0870101 0.0529564 -0.236873 -0.0768492 0.0551672 -0.236873 -0.0616652 0.0562793 -0.236873 -0.0342597 0.0444694 -0.236873 -0.0269478 0.037576 -0.236873 -0.0294927 0.0384075 -0.236873 -0.0229845 0.0302973 -0.236873 -0.0164308 0.020539 -0.236873 -0.0149384 0.0112157 -0.236873 -0.0135452 0.0109132 -0.236873 -0.0168787 -0.019565 -0.236873 -0.0152697 -0.0188788 -0.236873 -0.0212376 -0.0290059 -0.236873 -0.0192466 -0.0281075 -0.236873 -0.0347323 -0.0447139 -0.236873 -0.0316591 -0.0438172 -0.236873 -0.0434084 -0.050446 -0.236873 -0.0486961 -0.0543342 -0.236873 -0.0783349 -0.0578093 -0.236873 -0.073545 -0.0570034 -0.236873 -0.0838184 -0.0553944 -0.236873 -0.110507 -0.0399374 -0.236873 -0.123569 -0.022069 -0.236873 -0.127625 -0.00246241 -0.236873 -0.126326 -0.00242413 -0.236873 -0.108341 0.0422873 -0.237673 -0.012375 0.000932466 -0.236873 -0.0129557 -0.0090998 -0.236873 -0.0247656 -0.0365053 -0.237673 -0.0192466 -0.0281075 -0.237673 -0.0247656 -0.0365053 -0.237673 -0.0316591 -0.0438172 -0.236873 -0.0397175 -0.049821 -0.237673 -0.0397175 -0.049821 -0.236873 -0.0583219 -0.0572198 -0.237673 -0.0486961 -0.0543342 -0.236873 -0.0683026 -0.05839 -0.236873 -0.0881139 -0.0554953 -0.237673 -0.0881139 -0.0554953 -0.236873 -0.0973425 -0.0515184 -0.237673 -0.0973425 -0.0515184 -0.236873 -0.10574 -0.0459994 -0.237673 -0.113052 -0.0391059 -0.236873 -0.113052 -0.0391059 -0.236873 -0.119056 -0.0310475 -0.237673 -0.123569 -0.022069 -0.236873 -0.126455 -0.0124431 -0.237673 -0.126455 -0.0124431 -0.237873 -0.0682967 -0.0585899 -0.237873 -0.0581193 -0.058199 -0.237873 -0.0682732 -0.0593895 -0.237873 -0.0784794 -0.0587988 -0.237873 -0.0881767 -0.0556852 -0.237873 -0.0884281 -0.0564447 -0.237873 -0.10636 -0.046784 -0.237873 -0.113202 -0.0392389 -0.237873 -0.119226 -0.0311526 -0.237873 -0.126651 -0.0124836 -0.237873 -0.124498 -0.0224385 -0.237873 -0.127242 0.00759877 -0.237873 -0.128034 0.00771443 -0.237873 -0.12492 0.0174117 -0.237873 -0.121634 0.0270518 -0.237873 -0.116019 0.0355953 -0.237873 -0.0913779 0.0529901 -0.237873 -0.0916736 0.0537335 -0.237873 -0.0817187 0.0558857 -0.237873 -0.0717034 0.0570599 -0.237873 -0.0717269 0.0578596 -0.237873 -0.051572 0.0549147 -0.237873 -0.0425627 0.0501645 -0.237873 -0.0421833 0.0508688 -0.237873 -0.0336398 0.0452541 -0.237873 -0.026201 0.038241 -0.237873 -0.0121751 0.000938354 -0.237873 -0.0127578 -0.00912871 -0.237873 -0.0119662 -0.00924438 -0.237873 -0.0150798 -0.0189417 -0.237873 -0.0190705 -0.0282023 -0.237873 -0.023981 -0.0371253 -0.237873 -0.0315261 -0.0439666 -0.237873 -0.0486222 -0.05452 -0.237673 -0.0123701 0.0111562 -0.233695 -0.0122631 0.0106264 -0.237673 -0.0111756 0.000967798 -0.233695 -0.0111756 0.000967798 -0.233695 -0.0149255 0.0199742 -0.233695 -0.0134009 0.0153553 -0.233695 -0.0199229 0.0301479 -0.237673 -0.0153157 0.0209825 -0.233695 -0.0168262 0.0244514 -0.233695 -0.0217019 0.0328596 -0.237673 -0.0199229 0.0301479 -0.237673 -0.0260517 0.0383741 -0.233695 -0.0335158 0.045411 -0.233695 -0.027895 0.0403506 -0.233695 -0.0435266 0.0517943 -0.233695 -0.0392767 0.0494286 -0.237673 -0.0335158 0.045411 -0.233695 -0.0352367 0.0467201 -0.237673 -0.0420884 0.0510449 -0.233695 -0.0572392 0.0566849 -0.237673 -0.0515092 0.0551046 -0.233695 -0.0525386 0.0554349 -0.233695 -0.0515092 0.0551046 -0.233695 -0.0668692 0.0580017 -0.237673 -0.0717328 0.0580595 -0.233695 -0.0861203 0.0558341 -0.237673 -0.0917475 0.0539193 -0.233695 -0.107498 0.0445915 -0.237673 -0.100913 0.0493121 -0.233695 -0.103625 0.0475332 -0.237673 -0.109139 0.0431834 -0.233695 -0.116176 0.0357193 -0.233695 -0.12181 0.0271467 -0.237673 -0.12181 0.0271467 -0.233695 -0.120194 0.0299584 -0.237673 -0.116176 0.0357193 -0.233695 -0.124566 0.0212777 -0.237673 -0.12587 0.0177259 -0.233695 -0.12745 0.0119958 -0.233695 -0.1262 0.0166964 -0.233695 -0.128307 0.00720809 -0.237673 -0.128232 0.00774335 -0.228873 -0.024442 -0.00844007 -0.228873 -0.0268147 -0.0171805 -0.230473 -0.024442 -0.00844007 -0.228873 -0.0308471 -0.0252901 -0.230473 -0.0268147 -0.0171805 -0.228873 -0.036384 -0.0324573 -0.230473 -0.036384 -0.0324573 -0.230473 -0.0432128 -0.0384065 -0.228873 -0.051071 -0.0429091 -0.230473 -0.051071 -0.0429091 -0.230473 -0.0596566 -0.0457922 -0.230473 -0.0686397 -0.0469449 -0.228873 -0.0776751 -0.046323 -0.228873 -0.0864156 -0.0439503 -0.230473 -0.0776751 -0.046323 -0.228873 -0.0945252 -0.039918 -0.228873 -0.101692 -0.034381 -0.228873 -0.115027 -0.0111084 -0.230473 -0.115027 -0.0111084 -0.236673 -0.0138744 0.0008883 -0.236673 -0.0145262 -0.00945291 -0.236073 -0.0170672 -0.0194983 -0.236073 -0.0214107 -0.0289057 -0.236673 -0.0214107 -0.0289057 -0.236073 -0.0274089 -0.0373548 -0.236673 -0.0274089 -0.0373548 -0.236073 -0.0348574 -0.0445579 -0.236073 -0.0435027 -0.0502697 -0.236673 -0.0348574 -0.0445579 -0.236073 -0.0530504 -0.0542956 -0.236673 -0.0530504 -0.0542956 -0.236673 -0.0631752 -0.0564987 -0.236673 -0.0735324 -0.0568037 -0.236073 -0.0837694 -0.0552005 -0.236673 -0.0837694 -0.0552005 -0.236073 -0.0935374 -0.0517435 -0.236073 -0.102504 -0.0465505 -0.236073 -0.110364 -0.0397984 -0.236073 -0.116849 -0.031717 -0.236073 -0.121738 -0.0225815 -0.236073 -0.124866 -0.0127032 -0.236673 -0.121738 -0.0225815 -0.236673 -0.124866 -0.0127032 -0.236073 -0.126126 -0.00241824 -0.230673 -0.0145262 -0.00945291 -0.230673 -0.0214107 -0.0289057 -0.233273 -0.0214107 -0.0289057 -0.233273 -0.0274089 -0.0373548 -0.230673 -0.0348574 -0.0445579 -0.233273 -0.0348574 -0.0445579 -0.230673 -0.0435027 -0.0502697 -0.230673 -0.0530504 -0.0542956 -0.230673 -0.0631752 -0.0564987 -0.233273 -0.0631752 -0.0564987 -0.230673 -0.0837694 -0.0552005 -0.230673 -0.0935374 -0.0517435 -0.233273 -0.0837694 -0.0552005 -0.230673 -0.102504 -0.0465505 -0.230673 -0.110364 -0.0397984 -0.233273 -0.110364 -0.0397984 -0.233273 -0.116849 -0.031717 -0.233273 -0.121738 -0.0225815 -0.230673 -0.124866 -0.0127032 -0.233273 -0.124866 -0.0127032 -0.226573 -0.118961 -0.0478669 -0.226573 -0.11636 -0.0482893 -0.226573 -0.114137 -0.0524283 -0.226573 -0.113868 -0.0516687 -0.226573 -0.11408 -0.0520133 -0.226573 -0.115519 -0.0496508 -0.226573 -0.114713 -0.0498415 -0.226573 -0.118233 -0.0475529 -0.226573 -0.116169 -0.0474833 -0.226573 -0.115601 -0.0468807 -0.226573 -0.114512 -0.0452524 -0.226573 -0.113399 -0.0474017 -0.226573 -0.11324 -0.0456561 -0.226573 -0.113161 -0.0481951 -0.226573 -0.113352 -0.049001 -0.226573 -0.111901 -0.0491492 -0.226573 -0.112577 -0.0503001 -0.225073 -0.137078 -0.0133596 -0.224773 -0.133783 -0.0241943 -0.225073 -0.114976 -0.0520991 -0.224773 -0.0956215 -0.0636994 -0.225073 -0.0849072 -0.0673671 -0.224773 -0.0623608 -0.0682842 -0.225073 -0.0511984 -0.0663741 -0.225073 -0.0307929 -0.0566297 -0.224773 -0.0149345 -0.0405769 -0.224773 -0.00910006 -0.0309046 -0.225073 -0.00466136 -0.020486 -0.224773 -0.00494857 -0.0203993 -0.225073 -0.0107192 0.0330557 -0.224773 -0.0109797 0.0329071 -0.224773 -0.0173734 0.0422192 -0.224773 -0.0252214 0.0503435 -0.225073 -0.0250237 0.0505691 -0.225073 -0.0341492 0.0573107 -0.224773 -0.0443786 0.0621695 -0.225073 -0.0550929 0.0658371 -0.225073 -0.0663323 0.0673864 -0.224773 -0.109035 0.0548542 -0.225073 -0.11792 0.0478327 -0.224773 -0.125066 0.0390469 -0.225073 -0.131169 0.0295077 -0.228737 -0.136426 -0.0164396 -0.228737 -0.137078 -0.0133596 -0.228737 -0.137233 0.0109725 -0.228737 -0.00229715 -0.00938942 -0.229744 -0.00284482 -0.00994789 -0.229744 -0.00276323 -0.00933005 -0.228737 -0.00292219 0.0118297 -0.229755 -0.00339567 0.0116448 -0.229763 -0.00342123 0.0116579 -0.231259 -0.00704395 0.00838481 -0.232755 -0.0105179 0.000987172 -0.229776 -0.00639998 0.0224184 -0.229744 -0.00634695 0.0225252 -0.229764 -0.00635533 0.0223928 -0.229784 -0.00639639 0.022342 -0.230491 -0.00825512 0.0217721 -0.231413 -0.0103756 0.0201732 -0.231709 -0.0108577 0.0190752 -0.231808 -0.0109608 0.0185237 -0.23191 -0.010602 0.016408 -0.232755 -0.0116175 0.0107537 -0.23181 -0.0100937 0.0156145 -0.231495 -0.00895183 0.0146782 -0.230653 -0.00647384 0.0142778 -0.229784 -0.00417371 0.0149275 -0.229744 -0.00350179 0.0123549 -0.229776 -0.00413473 0.0148618 -0.229764 -0.00411144 0.0149076 -0.231741 -0.0286542 0.045829 -0.231928 -0.0276251 0.0441923 -0.231766 -0.0260533 0.0432882 -0.232755 -0.0274243 0.0408103 -0.229776 -0.0207724 0.0457008 -0.229744 -0.017761 0.0424233 -0.229744 -0.0206531 0.0457004 -0.229764 -0.0207751 0.0457522 -0.229776 -0.0265124 0.0511124 -0.229744 -0.0265199 0.0512315 -0.232755 -0.0389332 0.0499898 -0.231533 -0.0288282 0.0467421 -0.23191 -0.0551732 0.0592617 -0.231495 -0.0528501 0.0598259 -0.231766 -0.0539676 0.0593596 -0.232755 -0.0523434 0.0560632 -0.23181 -0.0542319 0.0593052 -0.229807 -0.0507039 0.06403 -0.229776 -0.0506005 0.0640894 -0.229764 -0.0506286 0.0641325 -0.229749 -0.0582797 0.0659797 -0.229807 -0.0582116 0.0658065 -0.232755 -0.0668342 0.0586587 -0.229744 -0.0663941 0.0669192 -0.229776 -0.0582774 0.065906 -0.231413 -0.0583208 0.0613404 -0.232755 -0.0619378 0.0581943 -0.231481 -0.0582039 0.0611306 -0.231741 -0.0574905 0.0602595 -0.232755 -0.0570966 0.0573272 -0.231808 -0.0571849 0.0600088 -0.231928 -0.0557809 0.0593566 -0.229807 -0.0856866 0.0649972 -0.229784 -0.0856925 0.0650614 -0.230491 -0.0851459 0.0631956 -0.229776 -0.0856268 0.0651003 -0.229744 -0.0855667 0.0652034 -0.229776 -0.0931834 0.0628351 -0.229744 -0.0932902 0.0628881 -0.229764 -0.0931578 0.0628797 -0.231481 -0.0907321 0.0587363 -0.232755 -0.0909711 0.0549254 -0.231709 -0.0898402 0.0583774 -0.231808 -0.0892887 0.0582743 -0.231907 -0.0883695 0.0582803 -0.232755 -0.0863006 0.0564669 -0.231928 -0.0877467 0.0584114 -0.23181 -0.0863795 0.0591414 -0.229744 -0.116465 0.048582 -0.229776 -0.116466 0.0484627 -0.229749 -0.116504 0.0485257 -0.231113 -0.114137 0.0456058 -0.229744 -0.108727 0.0548622 -0.230491 -0.115097 0.0470536 -0.229807 -0.116466 0.0483435 -0.229784 -0.116503 0.0483961 -0.229776 -0.121877 0.0427226 -0.229744 -0.121996 0.0427151 -0.229784 -0.121813 0.0427639 -0.231709 -0.116753 0.0405337 -0.232755 -0.114949 0.0382321 -0.231741 -0.116594 0.0405809 -0.232755 -0.111575 0.0418108 -0.231928 -0.114957 0.04161 -0.231808 -0.116224 0.0407202 -0.229776 -0.136671 0.0109577 -0.229764 -0.136697 0.0110022 -0.231709 -0.131139 0.0116241 -0.232755 -0.128959 0.00729723 -0.231413 -0.132105 0.0109143 -0.231364 -0.132256 0.0108405 -0.231741 -0.131025 0.0117446 -0.231808 -0.130774 0.0120502 -0.229807 -0.134795 0.0185312 -0.229776 -0.134854 0.0186345 -0.230491 -0.132964 0.0180986 -0.229744 -0.134914 0.0187381 -0.232755 -0.129424 0.00240087 -0.231316 -0.13326 0.00427426 -0.231129 -0.13369 0.00526565 -0.229744 -0.137155 0.00841795 -0.229782 -0.137152 0.00763476 -0.229763 -0.137195 0.00771738 -0.230653 -0.132537 0.0179707 -0.232755 -0.126828 0.0168917 -0.229744 -0.134728 0.0193461 -0.229744 -0.131702 0.0272885 -0.232755 -0.123147 0.0260045 -0.229744 -0.130535 0.0297257 -0.229807 -0.121758 0.0427299 -0.231495 -0.113898 0.0443827 -0.232755 -0.104001 0.0480732 -0.232755 -0.0998514 0.0507141 -0.229744 -0.0990428 0.0604777 -0.230491 -0.0925372 0.06098 -0.229744 -0.0765561 0.0666974 -0.229744 -0.0674264 0.0669663 -0.232755 -0.0477109 0.054411 -0.229744 -0.0446125 0.062081 -0.229744 -0.0419466 0.0609371 -0.232755 -0.0432306 0.052382 -0.229807 -0.0265052 0.0509934 -0.229764 -0.026461 0.0511126 -0.232755 -0.0241364 0.0371524 -0.229744 -0.014854 0.0386439 -0.232755 -0.018521 0.0290864 -0.232755 -0.0162317 0.0247333 -0.229744 -0.0113649 0.033236 -0.229744 -0.0100562 0.0308718 -0.229744 -0.0065682 0.0231212 -0.229807 -0.00645319 0.0223117 -0.226273 -0.00276691 -0.0125024 -0.225073 -0.00229715 -0.00938942 -0.228737 -0.0307929 -0.0566297 -0.228737 -0.030318 -0.0562933 -0.226273 -0.0232126 -0.050454 -0.225073 -0.02208 -0.0493626 -0.226273 -0.0465484 -0.0648593 -0.225073 -0.0957346 -0.0639773 -0.226273 -0.0817375 -0.0679981 -0.225073 -0.122859 -0.0439389 -0.228737 -0.119689 -0.0475524 -0.226273 -0.119689 -0.0475524 -0.226273 -0.136426 -0.0164396 -0.226273 -0.134094 -0.0242166 -0.225073 -0.134065 -0.0242978 -0.228737 -0.134065 -0.0242978 -0.225073 -0.129281 -0.0345857 -0.228737 -0.130359 -0.032621 -0.226273 -0.113782 -0.0531218 -0.228737 -0.106345 -0.0585328 -0.225073 -0.105851 -0.0588406 -0.228737 -0.105851 -0.0588406 -0.228737 -0.0736678 -0.0689163 -0.228737 -0.0725916 -0.0689657 -0.225073 -0.0736678 -0.0689163 -0.225073 -0.0623271 -0.0685823 -0.228737 -0.0633986 -0.068695 -0.228737 -0.0623271 -0.0685823 -0.228737 -0.038144 -0.0611243 -0.228737 -0.0405893 -0.0623529 -0.225073 -0.0405893 -0.0623529 -0.226273 -0.0176432 -0.0445465 -0.225073 -0.0146914 -0.0407527 -0.228737 -0.0122322 -0.0371097 -0.228737 -0.00466136 -0.020486 -0.226273 -0.00463643 -0.0204032 -0.225073 -0.00883118 -0.0310376 -0.228737 -0.0766015 0.067165 -0.226273 -0.00590571 0.0226867 -0.226273 -0.137233 0.0109725 -0.228737 -0.137703 0.00785948 -0.225073 -0.125309 0.0392227 -0.225073 -0.109207 0.0550997 -0.226273 -0.116787 0.0489241 -0.228737 -0.0856746 0.0656607 -0.226273 -0.0856746 0.0656607 -0.225073 -0.077673 0.0670523 -0.225073 -0.0888017 0.0648442 -0.226273 -0.0503618 0.0645986 -0.225073 -0.017141 0.042409 -0.225073 -0.00292219 0.0118297 -0.226273 -0.00357437 0.0149096 -0.225073 -0.00593547 0.0227678 -0.228737 -0.00964067 0.0310911 -0.228737 -0.0144717 0.0389171 -0.228737 -0.0336553 0.0570029 -0.228737 -0.0341492 0.0573107 -0.225073 -0.0442655 0.0624473 -0.225073 -0.0994108 0.0608229 -0.226273 -0.0934517 0.0633294 -0.226273 -0.135364 0.0188733 -0.225073 -0.135339 0.0189561 -0.228737 -0.131169 0.0295077 -0.185973 -0.0646852 -0.0473771 -0.185973 -0.0682099 -0.0615386 -0.185973 -0.0988365 -0.0542916 -0.185973 -0.0701734 -0.0489647 -0.185973 -0.0715453 -0.0485999 -0.185973 -0.072562 -0.0476091 -0.185973 -0.0926841 -0.0412361 -0.185973 -0.0819094 -0.0414581 -0.185973 -0.0894167 -0.0385283 -0.185973 -0.0729622 -0.0462471 -0.185973 -0.0731886 -0.0430449 -0.185973 -0.0483943 -0.0373199 -0.185973 -0.048441 -0.0372748 -0.185973 -0.0528739 0.0442898 -0.185973 -0.0508965 0.0569558 -0.185973 -0.0612098 0.0593962 -0.185973 -0.0619927 0.0467653 -0.185973 -0.0714192 0.0474141 -0.185973 -0.0807912 0.0462115 -0.185973 -0.0717902 0.0600087 -0.185973 -0.0823163 0.0587745 -0.185973 -0.0924681 0.0557313 -0.185973 -0.107693 -0.048471 -0.185973 -0.0969962 -0.0406955 -0.185973 -0.101937 0.0509715 -0.185973 -0.0979469 0.038506 -0.185973 -0.110436 0.0446396 -0.185973 -0.110848 0.0248219 -0.185973 -0.123527 0.0280715 -0.185973 -0.115055 0.0163612 -0.185973 -0.127721 0.0183386 -0.185973 -0.130161 0.00802527 -0.185973 -0.12954 -0.0130812 -0.185973 -0.126496 -0.023233 -0.185973 -0.11424 -0.019898 -0.185973 -0.109847 -0.0278837 -0.185973 -0.0449731 -0.0398307 -0.185973 -0.0643659 -0.0459939 -0.185973 -0.0295641 -0.0461696 -0.185973 -0.0286255 -0.0254912 -0.185973 -0.0224151 -0.00844047 -0.185973 -0.0218209 0.000654221 -0.185973 -0.0092264 0.00102521 -0.185973 -0.0104606 0.0115512 -0.185973 -0.0182636 0.0311722 -0.185973 -0.030729 0.0271819 -0.190673 -0.0259461 -0.0132554 -0.190673 -0.026095 -0.0138851 -0.190673 -0.0265389 -0.0143559 -0.190673 -0.0271587 -0.0145417 -0.190673 -0.0282592 -0.0139488 -0.190673 -0.0283053 -0.0138675 -0.190673 -0.0279458 -0.014292 -0.185973 -0.0277884 -0.0143927 -0.190673 -0.0277884 -0.0143927 -0.190673 -0.0274377 -0.0145186 -0.190673 -0.0268816 -0.0145022 -0.185973 -0.0271587 -0.0145417 -0.190673 -0.0263877 -0.0142461 -0.185973 -0.026095 -0.0138851 -0.190673 -0.0260538 -0.0138012 -0.185973 -0.0280033 -0.0123383 -0.185973 -0.0263892 -0.0117956 -0.185973 -0.0269534 -0.0120659 -0.185973 -0.0264453 -0.0122924 -0.185973 -0.0260858 -0.012717 -0.185973 -0.0256989 -0.0140985 -0.185973 -0.0263025 -0.0147388 -0.185973 -0.0265389 -0.0143559 -0.185973 -0.0280018 -0.0147889 -0.185973 -0.0282592 -0.0139488 -0.185973 -0.028445 -0.013329 -0.185973 -0.0286921 -0.0124859 -0.185973 -0.0283372 -0.0127833 -0.185973 -0.0280885 -0.0118457 -0.185973 -0.0272456 -0.011593 -0.190673 -0.0292566 0.0142233 -0.190673 -0.0291169 0.0136849 -0.190673 -0.0286 0.0131597 -0.190673 -0.0282493 0.0130338 -0.190673 -0.0269066 0.0136673 -0.190673 -0.0271993 0.0133062 -0.190673 -0.0276932 0.0130502 -0.190673 -0.0287574 0.0132603 -0.190673 -0.0290708 0.0136035 -0.185973 -0.0290708 0.0136035 -0.190673 -0.0279703 0.0130107 -0.185973 -0.0279703 0.0130107 -0.185973 -0.0273505 0.0131965 -0.190673 -0.0273505 0.0131965 -0.185973 -0.0269066 0.0136673 -0.190673 -0.0268654 0.0137512 -0.185973 -0.0272008 0.0157568 -0.185973 -0.0265605 0.0151531 -0.185973 -0.0272569 0.0152599 -0.185973 -0.0263078 0.0143102 -0.185973 -0.0294537 0.0133672 -0.185973 -0.0286 0.0131597 -0.185973 -0.0292566 0.0142233 -0.185973 -0.0280572 0.0159594 -0.185973 -0.027765 0.0154865 -0.190673 -0.044202 0.0350098 -0.190673 -0.0437581 0.0354806 -0.190673 -0.0448218 0.034824 -0.190673 -0.046108 0.0360366 -0.185973 -0.046108 0.0360366 -0.190673 -0.0459222 0.0354168 -0.185973 -0.0459222 0.0354168 -0.185973 -0.0454514 0.034973 -0.190673 -0.0454514 0.034973 -0.190673 -0.0436091 0.0361102 -0.185973 -0.0437581 0.0354806 -0.185973 -0.0455152 0.0371371 -0.185973 -0.0452855 0.0377189 -0.185973 -0.045959 0.0366663 -0.185973 -0.0465578 0.0360234 -0.185973 -0.0448085 0.0343742 -0.185973 -0.0448218 0.034824 -0.185973 -0.044202 0.0350098 -0.185973 -0.0436091 0.0361102 -0.185973 -0.0433493 0.0368558 -0.185973 -0.0438382 0.0374332 -0.185973 -0.0448954 0.0373229 -0.190673 -0.0706566 0.042752 -0.190673 -0.0712764 0.0425662 -0.190673 -0.0723769 0.0431591 -0.190673 -0.0719061 0.0427152 -0.185973 -0.0712764 0.0425662 -0.185973 -0.0706566 0.042752 -0.190673 -0.0702128 0.0432228 -0.185973 -0.070507 0.0453123 -0.185973 -0.0710711 0.045042 -0.185973 -0.070563 0.0448155 -0.185973 -0.0702128 0.0432228 -0.185973 -0.0704203 0.0423691 -0.185973 -0.0719061 0.0427152 -0.185973 -0.0723769 0.0431591 -0.185973 -0.0730125 0.0437656 -0.185973 -0.0725627 0.0437789 -0.190673 -0.0980165 0.0335299 -0.190673 -0.0969524 0.0333197 -0.190673 -0.0966097 0.033466 -0.190673 -0.0983761 0.0339544 -0.185973 -0.09833 0.0338731 -0.190673 -0.09833 0.0338731 -0.190673 -0.0978592 0.0334292 -0.190673 -0.0975084 0.0333033 -0.185973 -0.0972295 0.0332802 -0.190673 -0.0972295 0.0332802 -0.185973 -0.0966097 0.033466 -0.190673 -0.0964585 0.0335757 -0.190673 -0.0961658 0.0339368 -0.185973 -0.0961658 0.0339368 -0.190673 -0.0961246 0.0340207 -0.190673 -0.0960168 0.0345665 -0.185973 -0.0973163 0.0362289 -0.185973 -0.0958197 0.0354226 -0.185973 -0.0961565 0.0351049 -0.185973 -0.095567 0.0345797 -0.185973 -0.0960168 0.0345665 -0.185973 -0.0957697 0.0337234 -0.185973 -0.0980726 0.033033 -0.185973 -0.0978592 0.0334292 -0.185973 -0.0989656 0.0344796 -0.185973 -0.0987629 0.035336 -0.185973 -0.0981593 0.0359762 -0.185973 -0.098408 0.0350386 -0.185973 -0.0980741 0.0354836 -0.190673 -0.112768 0.0105128 -0.190673 -0.113868 0.0111057 -0.191424 -0.112805 0.0117623 -0.190673 -0.114054 0.0117255 -0.190673 -0.111704 0.0111694 -0.185973 -0.113868 0.0111057 -0.190673 -0.113397 0.0106618 -0.190673 -0.112148 0.0106986 -0.190673 -0.111555 0.0117991 -0.185973 -0.111555 0.0117991 -0.185973 -0.113118 0.0129722 -0.185973 -0.111998 0.0132589 -0.185973 -0.112054 0.0127621 -0.185973 -0.111695 0.0123376 -0.185973 -0.111704 0.0111694 -0.185973 -0.112148 0.0106986 -0.185973 -0.112755 0.010063 -0.185973 -0.112768 0.0105128 -0.185973 -0.113611 0.0102657 -0.185973 -0.114251 0.0108693 -0.185973 -0.113397 0.0106618 -0.185973 -0.114504 0.0117122 -0.185973 -0.114054 0.0117255 -0.185973 -0.114301 0.0125686 -0.185973 -0.113946 0.0122712 -0.185973 -0.113612 0.0127162 -0.191424 -0.111993 -0.0157901 -0.190673 -0.110893 -0.0163829 -0.190673 -0.111185 -0.016744 -0.190673 -0.113057 -0.0164467 -0.190673 -0.113242 -0.0158269 -0.185973 -0.113103 -0.0163654 -0.185973 -0.112743 -0.0167899 -0.190673 -0.112743 -0.0167899 -0.190673 -0.112586 -0.0168905 -0.190673 -0.112235 -0.0170164 -0.190673 -0.111956 -0.0170395 -0.190673 -0.111679 -0.017 -0.185973 -0.111679 -0.017 -0.190673 -0.111336 -0.0168537 -0.185973 -0.111185 -0.016744 -0.185973 -0.110744 -0.0157533 -0.190673 -0.110744 -0.0157533 -0.185973 -0.1114 -0.0146896 -0.185973 -0.110929 -0.0151335 -0.185973 -0.110294 -0.01574 -0.185973 -0.110851 -0.016299 -0.185973 -0.1111 -0.0172367 -0.185973 -0.111943 -0.0174893 -0.185973 -0.11203 -0.0145406 -0.185973 -0.11265 -0.0147264 -0.185973 -0.113093 -0.0151972 -0.185973 -0.113242 -0.0158269 -0.185973 -0.11344 -0.0166831 -0.185973 -0.112235 -0.0170164 -0.190673 -0.0939998 -0.0381123 -0.190673 -0.0943337 -0.0385573 -0.190673 -0.094041 -0.0381962 -0.190673 -0.0948276 -0.0388133 -0.190673 -0.0944849 -0.038667 -0.190673 -0.0953837 -0.0388297 -0.190673 -0.0962513 -0.0381786 -0.190673 -0.0962052 -0.03826 -0.190673 -0.096391 -0.0376402 -0.185973 -0.096391 -0.0376402 -0.190673 -0.0958918 -0.0386032 -0.185973 -0.0957344 -0.0387038 -0.190673 -0.0957344 -0.0387038 -0.185973 -0.0951047 -0.0388528 -0.190673 -0.0951047 -0.0388528 -0.185973 -0.094041 -0.0381962 -0.185973 -0.0959493 -0.0366494 -0.185973 -0.0948994 -0.036377 -0.185973 -0.0951916 -0.0359041 -0.185973 -0.0943352 -0.0361067 -0.185973 -0.0943912 -0.0366035 -0.185973 -0.0936449 -0.0384096 -0.185973 -0.0944849 -0.038667 -0.185973 -0.0950914 -0.0393026 -0.185973 -0.0962052 -0.03826 -0.185973 -0.0962832 -0.0370944 -0.185973 -0.0960345 -0.0361568 -0.190673 -0.0697505 -0.0460022 -0.190673 -0.068929 -0.046572 -0.190673 -0.06865 -0.0465951 -0.190673 -0.0680302 -0.0464093 -0.190673 -0.0675452 -0.0458546 -0.190673 -0.0683729 -0.0465556 -0.190673 -0.0697966 -0.0459209 -0.185973 -0.0699363 -0.0453824 -0.185973 -0.0697505 -0.0460022 -0.190673 -0.0694371 -0.0463454 -0.190673 -0.0692797 -0.0464461 -0.185973 -0.0692797 -0.0464461 -0.185973 -0.06865 -0.0465951 -0.190673 -0.0678791 -0.0462996 -0.185973 -0.0680302 -0.0464093 -0.190673 -0.0675864 -0.0459385 -0.185973 -0.0675864 -0.0459385 -0.185973 -0.0690008 -0.0441357 -0.185973 -0.0678806 -0.043849 -0.185973 -0.0675771 -0.0447704 -0.185973 -0.0669876 -0.0452956 -0.185973 -0.0671902 -0.0461519 -0.185973 -0.0677939 -0.0467922 -0.185973 -0.0703861 -0.0453957 -0.185973 -0.0698285 -0.0448367 -0.185973 -0.0694946 -0.0443917 -0.185973 -0.0430477 -0.0348497 -0.185973 -0.0419275 -0.034563 -0.185973 -0.0419835 -0.0350598 -0.185973 -0.0412872 -0.0351666 -0.185973 -0.041624 -0.0354843 -0.185973 -0.0418408 -0.0375062 -0.185973 -0.0420772 -0.0371233 -0.185973 -0.042697 -0.0373091 -0.185973 -0.0426837 -0.0377589 -0.185973 -0.0433266 -0.0371601 -0.185973 -0.0439832 -0.0360964 -0.185973 -0.0438755 -0.0355507 -0.185973 -0.0436268 -0.034613 -0.190673 -0.0433266 -0.0371601 -0.185973 -0.0437974 -0.0367162 -0.190673 -0.042697 -0.0373091 -0.190673 -0.0420772 -0.0371233 -0.190673 -0.0416333 -0.0366525 -0.185973 -0.0416333 -0.0366525 -0.185973 -0.0414843 -0.0360228 -0.191424 -0.0427338 -0.0360596 -0.190673 -0.0437974 -0.0367162 -0.238073 -0.12384 -0.0124799 -0.237873 -0.124036 -0.0125224 -0.237873 -0.109753 -0.0392075 -0.238073 -0.101896 -0.0456943 -0.237873 -0.083561 -0.0543765 -0.238073 -0.0633028 -0.0554564 -0.237873 -0.073479 -0.0559554 -0.238073 -0.0439982 -0.0493439 -0.237873 -0.053307 -0.0534853 -0.237873 -0.0439039 -0.0495203 -0.238073 -0.0355146 -0.043739 -0.237873 -0.0353894 -0.043895 -0.237873 -0.0280536 -0.0368009 -0.238073 -0.018057 -0.019148 -0.237873 -0.0178685 -0.0192147 -0.237873 -0.015366 -0.00932139 -0.237473 -0.125062 -0.0127457 -0.237473 -0.121923 -0.0226592 -0.237273 -0.110651 -0.0400764 -0.237473 -0.10262 -0.0467136 -0.237273 -0.102736 -0.0468767 -0.237473 -0.0936213 -0.0519251 -0.237273 -0.0937051 -0.0521067 -0.237473 -0.0838184 -0.0553944 -0.237473 -0.073545 -0.0570034 -0.237473 -0.05299 -0.0544863 -0.237473 -0.0434084 -0.050446 -0.237273 -0.0529296 -0.054677 -0.237273 -0.0271055 -0.0376155 -0.237273 -0.0166901 -0.0196317 -0.237473 -0.0143287 -0.00948386 -0.237273 -0.0127749 0.000920688 -0.237473 -0.0137411 0.0108726 -0.237273 -0.0168025 0.0203912 -0.237473 -0.0211142 0.0294125 -0.237273 -0.0212844 0.0293074 -0.237473 -0.0343837 0.0443125 -0.237473 -0.0616941 0.0560814 -0.237273 -0.061723 0.0558835 -0.237473 -0.0716916 0.0566601 -0.237473 -0.0816377 0.055494 -0.237473 -0.0912301 0.0526184 -0.237273 -0.0911562 0.0524326 -0.237473 -0.100178 0.0481208 -0.237473 -0.108208 0.0421379 -0.237273 -0.114921 0.0347274 -0.237273 -0.120401 0.0263878 -0.237473 -0.126846 0.00754094 -0.237873 -0.0173229 0.000786719 -0.238073 -0.0183095 0.0104822 -0.237873 -0.0185049 0.0104397 -0.238073 -0.0212563 0.0197888 -0.238073 -0.025863 0.0283955 -0.237873 -0.0260299 0.0282852 -0.238073 -0.0393775 0.0423705 -0.238073 -0.047825 0.0472629 -0.237873 -0.0570767 0.0503259 -0.237873 -0.0764055 0.0515443 -0.238073 -0.0949637 0.0458744 -0.237873 -0.102983 0.0403372 -0.238073 -0.103109 0.0404932 -0.238073 -0.110126 0.033707 -0.237873 -0.115604 0.0256467 -0.238073 -0.115777 0.0257469 -0.238073 -0.119869 0.016884 -0.237873 -0.119681 0.0168173 -0.238073 -0.122263 0.00742011 -0.237873 -0.122065 0.00738916 -0.237873 -0.121007 -0.0118633 -0.238073 -0.117914 -0.0209691 -0.237873 -0.118099 -0.0210468 -0.237873 -0.113553 -0.0295396 -0.238073 -0.113386 -0.0294293 -0.238073 -0.10738 -0.0369134 -0.237873 -0.100217 -0.0433296 -0.238073 -0.0827517 -0.0511772 -0.237873 -0.0918817 -0.0481573 -0.237873 -0.0828008 -0.0513711 -0.237873 -0.0636553 -0.0525779 -0.237873 -0.0542427 -0.0505299 -0.238073 -0.0454611 -0.0466108 -0.237873 -0.0373296 -0.0414772 -0.237873 -0.0304051 -0.0347808 -0.237873 -0.0248288 -0.0269261 -0.238073 -0.0180226 0.000766108 -0.238273 -0.012566 0.0111157 -0.238273 -0.0155016 0.0209085 -0.238273 -0.0336398 0.0452541 -0.238273 -0.0717269 0.0578596 -0.238273 -0.0818807 0.0566691 -0.238473 -0.0819212 0.0568649 -0.238273 -0.0916736 0.0537335 -0.238273 -0.100808 0.049142 -0.238273 -0.109006 0.043034 -0.238273 -0.116019 0.0355953 -0.238473 -0.12181 0.0271467 -0.238473 -0.12587 0.0177259 -0.238473 -0.128232 0.00774335 -0.238273 -0.12568 0.0176631 -0.238473 -0.128825 -0.00249774 -0.238673 -0.0579924 0.0334108 -0.238873 -0.0581923 0.0334049 -0.238873 -0.0585156 0.0317676 -0.238673 -0.0584633 0.0314211 -0.238673 -0.0598659 0.0299333 -0.238873 -0.0595173 0.0304327 -0.238873 -0.0637193 0.0299931 -0.238673 -0.0638141 0.029817 -0.238873 -0.0641915 0.0302951 -0.238873 -0.0656891 0.0331841 -0.238673 -0.065889 0.0331782 -0.238673 -0.0653019 0.0312196 -0.238873 -0.0651317 0.0313247 -0.238673 -0.0425133 0.0228283 -0.238873 -0.0422424 0.0248121 -0.238873 -0.045049 0.0210719 -0.238873 -0.0435673 0.02184 -0.238873 -0.0440209 0.0215108 -0.238873 -0.0467172 0.0210228 -0.238873 -0.0491817 0.0227319 -0.238673 -0.0493519 0.0226269 -0.238873 -0.0477693 0.0214003 -0.238873 -0.0330489 0.00775831 -0.238873 -0.0331726 0.00750662 -0.238673 -0.0328663 0.00767688 -0.238673 -0.0354821 0.00546177 -0.238673 -0.0372392 0.00541001 -0.238873 -0.0363636 0.00553681 -0.238673 -0.0388448 0.00612578 -0.238873 -0.0402224 0.00917477 -0.238673 -0.0404223 0.00916888 -0.238673 -0.0399808 0.0074673 -0.238873 -0.039665 0.00731538 -0.238673 -0.0319923 -0.00870799 -0.238673 -0.0324631 -0.0106977 -0.238873 -0.0349988 -0.0124541 -0.238873 -0.0335172 -0.011686 -0.238873 -0.0339708 -0.0120153 -0.238873 -0.0358302 -0.0125727 -0.238673 -0.0358243 -0.0127726 -0.238673 -0.037814 -0.0123018 -0.238873 -0.036667 -0.0125033 -0.238873 -0.0377191 -0.0121257 -0.238873 -0.0392698 -0.0105501 -0.238673 -0.0398889 -0.00894059 -0.238873 -0.0391316 -0.0107941 -0.238673 -0.0393017 -0.0108992 -0.238873 -0.0477243 -0.0267441 -0.238873 -0.0463119 -0.0280757 -0.238673 -0.0464068 -0.0282517 -0.238673 -0.044417 -0.0287226 -0.238873 -0.0444229 -0.0285227 -0.238873 -0.0425635 -0.0279653 -0.238673 -0.0410559 -0.0266477 -0.238673 -0.0560016 -0.0341747 -0.238873 -0.0565248 -0.0358179 -0.238673 -0.0563421 -0.0358993 -0.238673 -0.0573972 -0.0373054 -0.238873 -0.0598395 -0.0380394 -0.238673 -0.0589579 -0.0381144 -0.238873 -0.0606763 -0.03797 -0.238673 -0.0623207 -0.0374504 -0.238873 -0.0632791 -0.0360168 -0.238873 -0.0631409 -0.0362608 -0.238873 -0.0622006 -0.0372904 -0.238673 -0.0741111 -0.0347081 -0.238673 -0.0744516 -0.0364328 -0.238873 -0.074758 -0.036603 -0.238873 -0.0760896 -0.0380154 -0.238873 -0.0771176 -0.0384543 -0.238873 -0.077949 -0.0385728 -0.238673 -0.0788245 -0.0386996 -0.238873 -0.0803101 -0.0378239 -0.238873 -0.0813886 -0.0365503 -0.238673 -0.0820076 -0.0349407 -0.238873 -0.0812503 -0.0367942 -0.238673 -0.0815662 -0.0366423 -0.238673 -0.0938931 -0.03018 -0.238873 -0.091586 -0.0290934 -0.238873 -0.0920395 -0.0294227 -0.238873 -0.0938989 -0.0299801 -0.238873 -0.0947358 -0.0299106 -0.238873 -0.0977577 -0.0263421 -0.238873 -0.0962601 -0.0292311 -0.238873 -0.100101 -0.012342 -0.238873 -0.100225 -0.0125937 -0.238673 -0.0999183 -0.0124234 -0.238873 -0.103416 -0.0145635 -0.238873 -0.101103 -0.0136769 -0.238673 -0.100973 -0.0138295 -0.238873 -0.101556 -0.0140061 -0.238673 -0.102534 -0.0146385 -0.238873 -0.102584 -0.014445 -0.238673 -0.104291 -0.0146903 -0.238873 -0.104253 -0.0144941 -0.238873 -0.105305 -0.0141165 -0.238873 -0.105777 -0.0138146 -0.238673 -0.107474 -0.0109314 -0.238873 -0.106855 -0.012541 -0.238673 -0.107033 -0.012633 -0.238873 -0.106717 -0.0127849 -0.238873 -0.107808 0.00718394 -0.238673 -0.105933 0.00381688 -0.238873 -0.100758 0.00551578 -0.238673 -0.100582 0.00542093 -0.238873 -0.100311 0.00740476 -0.238873 -0.0986577 0.0212745 -0.238673 -0.0988279 0.0211695 -0.238673 -0.0973402 0.0197669 -0.238673 -0.0953504 0.0192961 -0.238673 -0.0933919 0.0198832 -0.238873 -0.0934969 0.0200534 -0.238873 -0.0921654 0.0214658 -0.238673 -0.0919893 0.0213709 -0.238673 -0.0915185 0.0233606 -0.238873 -0.0763018 0.0328715 -0.238673 -0.0765727 0.0308876 -0.238873 -0.0776268 0.0298993 -0.238873 -0.0780804 0.0295701 -0.238673 -0.0799339 0.0288128 -0.238873 -0.0799398 0.0290127 -0.238873 -0.0807766 0.0290821 -0.238673 -0.0819236 0.0292836 -0.238873 -0.0818288 0.0294597 -0.241473 -0.0566485 -0.0360696 -0.241673 -0.0560016 -0.0341747 -0.241473 -0.0631409 -0.0362608 -0.241473 -0.0478626 -0.0265001 -0.241673 -0.0480402 -0.0265922 -0.241473 -0.0477243 -0.0267441 -0.241673 -0.0469041 -0.0279337 -0.241473 -0.0463119 -0.0280757 -0.241673 -0.0452985 -0.0286495 -0.241473 -0.0444229 -0.0285227 -0.241473 -0.0435916 -0.0284041 -0.241473 -0.0425635 -0.0279653 -0.241673 -0.040585 -0.024658 -0.241473 -0.0421099 -0.027636 -0.241673 -0.0398889 -0.00894059 -0.241473 -0.0392698 -0.0105501 -0.241473 -0.036667 -0.0125033 -0.241473 -0.0391316 -0.0107941 -0.241473 -0.0381913 -0.0118237 -0.241473 -0.0358302 -0.0125727 -0.241473 -0.0349988 -0.0124541 -0.241673 -0.0338657 -0.0121855 -0.241473 -0.0325155 -0.0103512 -0.241473 -0.0335172 -0.011686 -0.241473 -0.0327256 0.0093956 -0.241473 -0.0345042 0.00609421 -0.241473 -0.0363636 0.00553681 -0.241673 -0.0383474 0.00580772 -0.241473 -0.0382526 0.00598379 -0.241673 -0.0398352 0.00721032 -0.241673 -0.0404223 0.00916888 -0.241473 -0.0422424 0.0248121 -0.241473 -0.0425657 0.0231749 -0.241673 -0.0449988 0.0208783 -0.241673 -0.0467559 0.0208266 -0.241473 -0.04932 0.0229759 -0.241673 -0.0483615 0.0215423 -0.241673 -0.0494976 0.0228839 -0.241473 -0.0651317 0.0313247 -0.241473 -0.0641915 0.0302951 -0.241673 -0.0638141 0.029817 -0.241473 -0.0637193 0.0299931 -0.241473 -0.0626672 0.0296155 -0.241473 -0.060999 0.0296647 -0.241673 -0.0584633 0.0314211 -0.241473 -0.0581923 0.0334049 -0.241473 -0.0585156 0.0317676 -0.241673 -0.0579924 0.0334108 -0.241473 -0.0595173 0.0304327 -0.241473 -0.0766251 0.0312342 -0.241673 -0.0764425 0.0311527 -0.241473 -0.0776268 0.0298993 -0.241473 -0.0791085 0.0291312 -0.241473 -0.0823009 0.0297616 -0.241673 -0.0808154 0.0288859 -0.241673 -0.099415 0.023128 -0.241473 -0.0992151 0.0231339 -0.241473 -0.0986577 0.0212745 -0.241473 -0.0977175 0.0202449 -0.241473 -0.0972453 0.0199429 -0.241473 -0.094525 0.0196145 -0.241473 -0.0934969 0.0200534 -0.241473 -0.0920417 0.0217175 -0.241473 -0.0930433 0.0203826 -0.241673 -0.108008 0.00717805 -0.241473 -0.107389 0.00556851 -0.241673 -0.107566 0.00547647 -0.241473 -0.105838 0.00399295 -0.241673 -0.10643 0.00413494 -0.241673 -0.103068 0.00347093 -0.241473 -0.100634 0.00576747 -0.241473 -0.100758 0.00551578 -0.241673 -0.0995778 -0.0106988 -0.241673 -0.100049 -0.0126886 -0.241673 -0.101451 -0.0141763 -0.241473 -0.105305 -0.0141165 -0.241673 -0.105399 -0.0142926 -0.241673 -0.0900611 -0.0261154 -0.241473 -0.0947358 -0.0299106 -0.241673 -0.0947745 -0.0301068 -0.241673 -0.0975162 -0.0280496 -0.241473 -0.074758 -0.036603 -0.241673 -0.0745819 -0.0366979 -0.241473 -0.0760896 -0.0380154 -0.241473 -0.077949 -0.0385728 -0.241673 -0.111004 0.00682422 -0.241673 -0.111026 0.00670021 -0.241373 -0.111322 0.00675392 -0.241673 -0.104443 0.0227417 -0.241673 -0.0919043 0.0347187 -0.241373 -0.0841492 0.0387799 -0.241673 -0.0840482 0.0384975 -0.241373 -0.0756182 0.0408576 -0.241673 -0.0755781 0.0405603 -0.241373 -0.0668416 0.0411161 -0.241673 -0.0582873 0.0392563 -0.241373 -0.0500801 0.0362106 -0.241373 -0.0428277 0.0312611 -0.241673 -0.0370003 0.0247284 -0.241673 -0.0324211 0.0173103 -0.241373 -0.0321508 0.0174403 -0.241673 -0.0294842 0.00910216 -0.241373 -0.0280183 0.00047167 -0.238973 -0.0321508 0.0174403 -0.238673 -0.0294842 0.00910216 -0.238973 -0.0500801 0.0362106 -0.238973 -0.0428277 0.0312611 -0.238673 -0.0416971 0.0298591 -0.238673 -0.0370003 0.0247284 -0.238673 -0.0502224 0.0359465 -0.238673 -0.0988031 0.0293892 -0.238673 -0.0919043 0.0347187 -0.238673 -0.0840482 0.0384975 -0.238973 -0.0668416 0.0411161 -0.238673 -0.0569304 0.0388339 -0.238973 -0.104691 0.0229108 -0.238673 -0.100592 0.0275723 -0.238673 -0.100074 0.028122 -0.238873 -0.0340506 0.00642343 -0.241473 -0.0331726 0.00750662 -0.238873 -0.0345042 0.00609421 -0.238873 -0.0355323 0.00565536 -0.238873 -0.0372005 0.00560622 -0.238873 -0.0382526 0.00598379 -0.238873 -0.0387248 0.00628575 -0.241473 -0.039665 0.00731538 -0.238873 -0.0398033 0.00755935 -0.238873 -0.0426893 0.0229232 -0.241473 -0.0435673 0.02184 -0.241473 -0.045049 0.0210719 -0.238873 -0.0458803 0.0209534 -0.241473 -0.0467172 0.0210228 -0.238873 -0.0482415 0.0217023 -0.241473 -0.0482415 0.0217023 -0.241473 -0.0497391 0.0245913 -0.238873 -0.0586393 0.0315159 -0.241473 -0.0586393 0.0315159 -0.238873 -0.0599709 0.0301035 -0.241473 -0.0599709 0.0301035 -0.238873 -0.060999 0.0296647 -0.238873 -0.0618303 0.0295461 -0.238873 -0.0626672 0.0296155 -0.241473 -0.0618303 0.0295461 -0.238873 -0.06527 0.0315687 -0.241473 -0.06527 0.0315687 -0.238873 -0.0767488 0.0309825 -0.238873 -0.0791085 0.0291312 -0.241473 -0.0807766 0.0290821 -0.238873 -0.0823009 0.0297616 -0.241473 -0.0833795 0.0310352 -0.241473 -0.0837986 0.0326506 -0.238873 -0.0832412 0.0307912 -0.241473 -0.0921654 0.0214658 -0.241473 -0.0953563 0.019496 -0.238873 -0.0953563 0.019496 -0.238873 -0.0972453 0.0199429 -0.241473 -0.0961932 0.0195654 -0.241473 -0.098796 0.0215185 -0.238873 -0.10209 0.00410337 -0.241473 -0.101636 0.00443259 -0.241473 -0.10209 0.00410337 -0.241473 -0.103118 0.00366452 -0.241473 -0.103949 0.00354598 -0.238873 -0.103949 0.00354598 -0.241473 -0.104786 0.00361539 -0.238873 -0.105838 0.00399295 -0.241473 -0.10725 0.00532454 -0.238873 -0.10725 0.00532454 -0.241473 -0.10631 0.00429491 -0.241473 -0.100225 -0.0125937 -0.241473 -0.101556 -0.0140061 -0.241473 -0.103416 -0.0145635 -0.241473 -0.106717 -0.0127849 -0.241473 -0.107274 -0.0109255 -0.241473 -0.0905843 -0.0277586 -0.238873 -0.090708 -0.0280102 -0.241473 -0.091586 -0.0290934 -0.241473 -0.0930676 -0.0298615 -0.238873 -0.0930676 -0.0298615 -0.238873 -0.0957879 -0.0295331 -0.241473 -0.0962601 -0.0292311 -0.238873 -0.0972003 -0.0282015 -0.241473 -0.0973386 -0.0279575 -0.238873 -0.0746343 -0.0363513 -0.238873 -0.075636 -0.0376862 -0.238873 -0.0787858 -0.0385034 -0.238873 -0.0798379 -0.0381258 -0.241473 -0.0798379 -0.0381258 -0.241473 -0.0812503 -0.0367942 -0.238873 -0.0818077 -0.0349349 -0.238873 -0.0562015 -0.0341806 -0.241473 -0.0562015 -0.0341806 -0.238873 -0.0566485 -0.0360696 -0.238873 -0.0575265 -0.0371527 -0.241473 -0.0579801 -0.037482 -0.238873 -0.0579801 -0.037482 -0.238873 -0.0590081 -0.0379208 -0.241473 -0.0598395 -0.0380394 -0.238873 -0.0617284 -0.0375924 -0.241473 -0.0617284 -0.0375924 -0.241473 -0.0636983 -0.0344014 -0.241473 -0.0411083 -0.0263012 -0.238873 -0.0412319 -0.0265528 -0.241473 -0.0412319 -0.0265528 -0.241473 -0.0452598 -0.0284532 -0.238873 -0.0482817 -0.0248847 -0.241473 -0.0467841 -0.0277737 -0.238873 -0.0321922 -0.00871388 -0.238873 -0.0325155 -0.0103512 -0.238873 -0.0326392 -0.0106029 -0.241473 -0.0326392 -0.0106029 -0.241473 -0.0339708 -0.0120153 -0.241473 -0.0377191 -0.0121257 -0.238873 -0.0381913 -0.0118237 -0.238873 -0.0396889 -0.0089347 -0.239023 -0.0420471 0.0164906 -0.241673 -0.0400762 0.012822 -0.239023 -0.0412373 0.0157271 -0.241673 -0.0376962 0.0135355 -0.239023 -0.0401543 0.0154708 -0.241673 -0.0359918 0.0153433 -0.241673 -0.0354424 0.0171322 -0.239023 -0.0383248 0.0166002 -0.238673 -0.0380685 0.0176832 -0.238673 -0.0383248 0.0166002 -0.238673 -0.0390882 0.0157904 -0.238673 -0.0401543 0.0154708 -0.239023 -0.0390882 0.0157904 -0.238673 -0.0420471 0.0164906 -0.241673 -0.0491743 0.0277715 -0.241673 -0.0532588 0.0252501 -0.241673 -0.0556767 0.0258223 -0.239023 -0.0552296 0.0289187 -0.241673 -0.058198 0.0299067 -0.238673 -0.0515073 0.0290283 -0.239023 -0.051251 0.0301113 -0.239023 -0.0515073 0.0290283 -0.238673 -0.0522707 0.0282185 -0.239023 -0.0522707 0.0282185 -0.239023 -0.0533368 0.027899 -0.239023 -0.0544198 0.0281552 -0.238673 -0.0555492 0.0299847 -0.239023 -0.0555492 0.0299847 -0.241673 -0.0685092 0.0301354 -0.239023 -0.0709673 0.0320708 -0.241673 -0.0708892 0.0294219 -0.239023 -0.0720503 0.0323271 -0.241673 -0.0733071 0.0299941 -0.239023 -0.0728601 0.0330905 -0.239023 -0.0731796 0.0341565 -0.239023 -0.0691378 0.0332001 -0.238673 -0.0699012 0.0323904 -0.239023 -0.0699012 0.0323904 -0.238673 -0.0709673 0.0320708 -0.238673 -0.0720503 0.0323271 -0.238673 -0.0728601 0.0330905 -0.238673 -0.0731796 0.0341565 -0.239023 -0.0989203 0.0148153 -0.241673 -0.0965873 0.0135584 -0.241673 -0.0982917 0.0117505 -0.239023 -0.10075 0.0136859 -0.239023 -0.101833 0.0139422 -0.239023 -0.102643 0.0147056 -0.241673 -0.104898 0.0133136 -0.239023 -0.098664 0.0158983 -0.239023 -0.0996837 0.0140055 -0.238673 -0.10075 0.0136859 -0.238673 -0.102962 0.0157717 -0.239023 -0.102962 0.0157717 -0.241673 -0.100759 -0.00407207 -0.239023 -0.104922 -0.00394457 -0.239023 -0.106005 -0.0036883 -0.241673 -0.109783 -0.00193683 -0.239023 -0.102836 -0.0017322 -0.239023 -0.103092 -0.00281522 -0.239023 -0.103856 -0.003625 -0.238673 -0.104922 -0.00394457 -0.238673 -0.106814 -0.00292486 -0.239023 -0.106814 -0.00292486 -0.241673 -0.104044 -0.0213589 -0.239023 -0.101612 -0.0202792 -0.239023 -0.101073 -0.0208695 -0.241673 -0.102663 -0.0229891 -0.241673 -0.0985771 -0.023796 -0.239023 -0.0992426 -0.021231 -0.239023 -0.0986532 -0.0209793 -0.241673 -0.0966806 -0.0228129 -0.241673 -0.0953984 -0.0211043 -0.239023 -0.0978897 -0.0201696 -0.239023 -0.0983931 -0.0207906 -0.239023 -0.0978188 -0.0200253 -0.238673 -0.0986532 -0.0209793 -0.239023 -0.0997192 -0.0212989 -0.238673 -0.0997192 -0.0212989 -0.239023 -0.100199 -0.0212591 -0.239023 -0.100802 -0.0210427 -0.239023 -0.101932 -0.0192132 -0.239023 -0.101691 -0.0201393 -0.239023 -0.0711186 -0.0358131 -0.241673 -0.073231 -0.0379589 -0.239023 -0.070799 -0.0368792 -0.241673 -0.0718505 -0.0395891 -0.239023 -0.0702599 -0.0374695 -0.241673 -0.0677641 -0.040396 -0.239023 -0.0689062 -0.0378989 -0.239023 -0.0684296 -0.0378309 -0.241673 -0.0658676 -0.0394128 -0.239023 -0.0678402 -0.0375793 -0.239023 -0.0675801 -0.0373905 -0.241673 -0.0645854 -0.0377042 -0.239023 -0.0670058 -0.0366252 -0.239023 -0.0670767 -0.0367695 -0.238673 -0.0699892 -0.0376426 -0.239023 -0.069386 -0.0378591 -0.239023 -0.0699892 -0.0376426 -0.239023 -0.0708783 -0.0367393 -0.239023 -0.0497224 -0.0315672 -0.239023 -0.0504858 -0.0323769 -0.241673 -0.0490938 -0.0346319 -0.239023 -0.0515519 -0.0326965 -0.241673 -0.0514738 -0.0353454 -0.241673 -0.0538917 -0.0347732 -0.239023 -0.0534447 -0.0316768 -0.238673 -0.0494661 -0.0304841 -0.239023 -0.0494661 -0.0304841 -0.238673 -0.0504858 -0.0323769 -0.238673 -0.0526349 -0.0324403 -0.239023 -0.0526349 -0.0324403 -0.239023 -0.0372942 -0.0183846 -0.241673 -0.0349612 -0.0196415 -0.241673 -0.0366657 -0.0214494 -0.239023 -0.0391237 -0.019514 -0.241673 -0.0390457 -0.0221628 -0.238673 -0.037038 -0.0173016 -0.239023 -0.037038 -0.0173016 -0.239023 -0.0380577 -0.0191944 -0.238673 -0.0391237 -0.019514 -0.239023 -0.0402067 -0.0192577 -0.239023 -0.0410165 -0.0184943 -0.238673 -0.0413361 -0.0174282 -0.239373 -0.0630227 0.0406514 -0.239373 -0.0290662 0.00863815 -0.240173 -0.0280383 0.0180822 -0.239373 -0.0291928 0.00917315 -0.239373 -0.0428277 0.0312611 -0.239373 -0.0411889 0.0297951 -0.239373 -0.0367629 0.0249118 -0.240173 -0.0325215 0.0259063 -0.239373 -0.0582031 0.0395442 -0.239373 -0.0668416 0.0411161 -0.240173 -0.0713545 0.0452151 -0.240173 -0.0888472 0.0411967 -0.239373 -0.0920619 0.034974 -0.240173 -0.0966714 0.0367136 -0.239373 -0.104691 0.0229108 -0.239373 -0.105594 0.0215306 -0.239373 -0.111322 0.00675392 -0.240173 -0.115361 0.0068769 -0.240173 -0.0597014 -0.0455973 -0.240173 -0.0543031 -0.0503392 -0.240173 -0.0454611 -0.0466108 -0.240173 -0.0365295 -0.0323201 -0.240173 -0.0305568 -0.0346505 -0.240173 -0.0250019 -0.0268258 -0.240173 -0.0209794 -0.0181137 -0.240173 -0.0270017 -0.0171095 -0.240173 -0.02402 0.000589445 -0.240173 -0.0186263 -0.00881079 -0.240173 -0.0251677 0.00953368 -0.240173 -0.0384449 0.0327056 -0.240173 -0.045581 0.0382185 -0.240173 -0.0536556 0.0422334 -0.240173 -0.0398985 0.0416366 -0.240173 -0.0623582 0.0445958 -0.240173 -0.0572484 0.0496473 -0.240173 -0.0802987 0.0440674 -0.240173 -0.103471 0.0307901 -0.240173 -0.109443 0.0331205 -0.240173 -0.108984 0.023654 -0.240173 -0.112998 0.0155795 -0.240173 -0.111962 -0.0196121 -0.240173 -0.094419 -0.0397485 -0.240173 -0.10738 -0.0369134 -0.240173 -0.0776419 -0.0461258 -0.240173 -0.0636796 -0.0523794 -0.240173 -0.0180226 0.000766108 -0.238073 -0.0186263 -0.00881079 -0.238073 -0.0209794 -0.0181137 -0.238073 -0.0250019 -0.0268258 -0.238073 -0.0305568 -0.0346505 -0.238073 -0.0374548 -0.0413212 -0.240173 -0.0374548 -0.0413212 -0.238073 -0.0543031 -0.0503392 -0.238073 -0.0636796 -0.0523794 -0.238073 -0.0732714 -0.052662 -0.240173 -0.0732714 -0.052662 -0.238073 -0.0917978 -0.0479757 -0.240173 -0.0827517 -0.0511772 -0.240173 -0.0917978 -0.0479757 -0.240173 -0.100102 -0.0431666 -0.238073 -0.100102 -0.0431666 -0.240173 -0.113386 -0.0294293 -0.238073 -0.120811 -0.0118208 -0.240173 -0.117914 -0.0209691 -0.240173 -0.120811 -0.0118208 -0.238073 -0.121977 -0.00229605 -0.240173 -0.121977 -0.00229605 -0.237873 -0.0219013 0.0195168 -0.237873 -0.0214406 0.0197111 -0.237873 -0.0264471 0.0280096 -0.237873 -0.0321165 0.0358701 -0.237873 -0.0397827 0.0417997 -0.237873 -0.0394932 0.0422074 -0.237873 -0.0571993 0.0498412 -0.237873 -0.0479088 0.0470813 -0.237873 -0.0666847 0.0518306 -0.237873 -0.0763448 0.051048 -0.237873 -0.0857574 0.049 -0.237873 -0.0946333 0.0452572 -0.237873 -0.0859083 0.0494766 -0.237873 -0.0948693 0.045698 -0.237873 -0.109974 0.0335767 -0.237873 -0.119209 0.0166505 -0.237873 -0.121571 0.0073118 -0.237873 -0.122177 -0.00230194 -0.237873 -0.121495 -0.0119696 -0.237873 -0.107524 -0.0370525 -0.237873 -0.100507 -0.0437373 -0.237873 -0.0920913 -0.0486113 -0.237873 -0.0732839 -0.0528616 -0.237873 -0.0829234 -0.0518558 -0.237873 -0.0635945 -0.0530742 -0.237873 -0.0453667 -0.0467872 -0.237873 -0.0451308 -0.047228 -0.237873 -0.0370167 -0.0418671 -0.237873 -0.0300258 -0.0351066 -0.237873 -0.0243962 -0.0271766 -0.237873 -0.0207909 -0.0181804 -0.237873 -0.0203195 -0.0183472 -0.237873 -0.0184287 -0.00884174 -0.237873 -0.0179347 -0.0089191 -0.238073 -0.017123 0.000792607 -0.239973 -0.0319728 0.0360091 -0.238073 -0.0319728 0.0360091 -0.239973 -0.0393775 0.0423705 -0.239973 -0.047825 0.0472629 -0.238073 -0.0570277 0.0505198 -0.239973 -0.0666721 0.0520302 -0.238073 -0.0666721 0.0520302 -0.238073 -0.0764299 0.0517428 -0.239973 -0.0859687 0.0496673 -0.238073 -0.0859687 0.0496673 -0.239973 -0.103109 0.0404932 -0.239973 -0.110126 0.033707 -0.239973 -0.119869 0.016884 -0.239973 -0.0564882 0.0526526 -0.239973 -0.0764299 0.0517428 -0.239973 -0.0766973 0.0539265 -0.239973 -0.0949637 0.0458744 -0.239973 -0.104485 0.042209 -0.239973 -0.115777 0.0257469 -0.239973 -0.117681 0.0268495 -0.239973 -0.122263 0.00742011 -0.239973 -0.122877 -0.00232255 -0.239973 -0.121691 -0.0120122 -0.239973 -0.12384 -0.0124799 -0.239973 -0.120771 -0.0221736 -0.239973 -0.108027 -0.0375391 -0.239973 -0.115973 -0.0311382 -0.239973 -0.100623 -0.0439004 -0.239973 -0.0930973 -0.0507902 -0.239973 -0.0921751 -0.0487929 -0.239973 -0.073328 -0.0535602 -0.239973 -0.0633028 -0.0554564 -0.239973 -0.0298741 -0.035237 -0.239973 -0.0355146 -0.043739 -0.239973 -0.0282053 -0.0366706 -0.239973 -0.0242231 -0.0272769 -0.239973 -0.0223193 -0.0283795 -0.239973 -0.020131 -0.018414 -0.239973 -0.0177371 -0.00895005 -0.239973 -0.0155636 -0.00929045 -0.239973 -0.017123 0.000792607 -0.239973 -0.0183095 0.0104822 -0.239973 -0.0212563 0.0197888 -0.239973 -0.025863 0.0283955 -0.239973 -0.0192292 0.0206436 -0.239973 -0.0469028 0.0492603 -0.239973 -0.0570277 0.0505198 -0.239973 -0.0149239 0.000857384 -0.238073 -0.0155636 -0.00929045 -0.239973 -0.018057 -0.019148 -0.238073 -0.0223193 -0.0283795 -0.238073 -0.0282053 -0.0366706 -0.239973 -0.0439982 -0.0493439 -0.238073 -0.0533673 -0.0532946 -0.239973 -0.0533673 -0.0532946 -0.238073 -0.0734664 -0.0557558 -0.239973 -0.0734664 -0.0557558 -0.238073 -0.0835119 -0.0541826 -0.239973 -0.0835119 -0.0541826 -0.238073 -0.0930973 -0.0507902 -0.239973 -0.101896 -0.0456943 -0.238073 -0.109609 -0.0390684 -0.238073 -0.115973 -0.0311382 -0.239973 -0.109609 -0.0390684 -0.238073 -0.120771 -0.0221736 -0.238073 -0.125076 -0.00238733 -0.237873 -0.0272572 -0.0374851 -0.237873 -0.0221463 -0.0284797 -0.237873 -0.0212376 -0.0290059 -0.237873 -0.0168787 -0.019565 -0.237873 -0.014724 0.000863273 -0.237873 -0.0149384 0.0112157 -0.237873 -0.0190449 0.0207213 -0.237873 -0.0238606 0.0297185 -0.237873 -0.0229845 0.0302973 -0.237873 -0.0302475 0.0376775 -0.237873 -0.0379882 0.0443275 -0.237873 -0.0468189 0.0494419 -0.237873 -0.0564391 0.0528465 -0.237873 -0.0767216 0.054125 -0.237873 -0.0664551 0.0554734 -0.237873 -0.0768492 0.0551672 -0.237873 -0.111946 0.035271 -0.237873 -0.112743 0.0359552 -0.237873 -0.118762 0.027476 -0.237873 -0.125276 -0.00239321 -0.237873 -0.126326 -0.00242413 -0.237873 -0.121923 -0.0226592 -0.237873 -0.120955 -0.0222513 -0.237873 -0.11614 -0.0312484 -0.237873 -0.117016 -0.0318272 -0.237873 -0.102012 -0.0458574 -0.237873 -0.110507 -0.0399374 -0.237873 -0.0931811 -0.0509718 -0.237873 -0.073545 -0.0570034 -0.237873 -0.0632785 -0.055655 -0.237873 -0.05299 -0.0544863 -0.237873 -0.0136745 0.000894189 -0.237873 -0.0143287 -0.00948386 -0.237473 -0.0168787 -0.019565 -0.237473 -0.0212376 -0.0290059 -0.237473 -0.0272572 -0.0374851 -0.237473 -0.0347323 -0.0447139 -0.237873 -0.0347323 -0.0447139 -0.237873 -0.0434084 -0.050446 -0.237473 -0.0631509 -0.0566972 -0.237873 -0.0631509 -0.0566972 -0.237873 -0.0838184 -0.0553944 -0.237873 -0.0936213 -0.0519251 -0.237473 -0.110507 -0.0399374 -0.237873 -0.10262 -0.0467136 -0.237473 -0.117016 -0.0318272 -0.237873 -0.125062 -0.0127457 -0.237273 -0.0345077 0.0441556 -0.237273 -0.0428473 0.0496363 -0.237273 -0.046295 0.0505767 -0.237273 -0.0520119 0.0535856 -0.237273 -0.0664425 0.055673 -0.237273 -0.0716857 0.0564602 -0.237273 -0.0815971 0.0552981 -0.237273 -0.0966861 0.0490924 -0.237273 -0.100072 0.0479507 -0.237273 -0.108075 0.0419885 -0.237273 -0.118936 0.0275762 -0.237273 -0.124351 0.0172232 -0.237273 -0.126649 0.00751203 -0.237273 -0.126526 -0.00243002 -0.237273 -0.127225 -0.00245063 -0.237273 -0.125257 -0.0127882 -0.237273 -0.122107 -0.0227369 -0.237273 -0.118716 -0.0308374 -0.237273 -0.117182 -0.0319375 -0.237273 -0.0971528 -0.0511663 -0.237273 -0.0838675 -0.0555883 -0.237273 -0.0735576 -0.057203 -0.237273 -0.0631266 -0.0568957 -0.237273 -0.0683144 -0.0579901 -0.237273 -0.0399276 -0.0494806 -0.237273 -0.043314 -0.0506223 -0.237273 -0.0346071 -0.0448699 -0.237273 -0.0319251 -0.0435185 -0.237273 -0.0210646 -0.0291061 -0.237273 -0.0195988 -0.0279177 -0.237273 -0.0141311 -0.0095148 -0.237273 -0.0134746 0.000900077 -0.237273 -0.0133515 -0.00904197 -0.237273 -0.013937 0.0108321 -0.237273 -0.0178931 0.021207 -0.237273 -0.0228176 0.0304075 -0.237273 -0.0272465 0.03731 -0.238273 -0.0137411 0.0108726 -0.237473 -0.0166166 0.0204651 -0.237473 -0.0270972 0.037443 -0.238273 -0.0427524 0.0498124 -0.237473 -0.0427524 0.0498124 -0.238273 -0.051949 0.0537755 -0.237473 -0.051949 0.0537755 -0.238273 -0.0616941 0.0560814 -0.238273 -0.0716916 0.0566601 -0.238273 -0.108208 0.0421379 -0.238273 -0.115078 0.0348514 -0.237473 -0.115078 0.0348514 -0.238273 -0.124541 0.017286 -0.237473 -0.120577 0.0264827 -0.237473 -0.124541 0.017286 -0.238273 -0.126846 0.00754094 -0.238273 -0.127425 -0.00245652 -0.238273 -0.0249226 -0.0363813 -0.238273 -0.0183662 -0.0285817 -0.238273 -0.0154596 -0.018816 -0.238273 -0.0119662 -0.00924438 -0.238273 -0.012575 0.000926577 -0.238273 -0.0113755 0.000961909 -0.238273 -0.0166166 0.0204651 -0.238273 -0.0211142 0.0294125 -0.238273 -0.0270972 0.037443 -0.238273 -0.0200931 0.0300428 -0.238273 -0.026201 0.038241 -0.238273 -0.0343837 0.0443125 -0.238273 -0.0421833 0.0508688 -0.238273 -0.051572 0.0549147 -0.238273 -0.0615206 0.0572688 -0.238273 -0.0816377 0.055494 -0.238273 -0.0912301 0.0526184 -0.238273 -0.100178 0.0481208 -0.238273 -0.121634 0.0270518 -0.238273 -0.120577 0.0264827 -0.238273 -0.128034 0.00771443 -0.238273 -0.128625 -0.00249185 -0.238273 -0.126259 -0.0124026 -0.238273 -0.127434 -0.0126457 -0.238273 -0.124498 -0.0224385 -0.238273 -0.105616 -0.0458425 -0.238273 -0.0972477 -0.0513423 -0.238273 -0.0978168 -0.0523988 -0.238273 -0.078306 -0.0576114 -0.238273 -0.0884281 -0.0564447 -0.238273 -0.0683085 -0.0581901 -0.238273 -0.0682732 -0.0593895 -0.238273 -0.0583624 -0.0570239 -0.238273 -0.04877 -0.0541484 -0.238273 -0.0581193 -0.058199 -0.238273 -0.0483265 -0.0552634 -0.238273 -0.0391922 -0.0506719 -0.238973 -0.0123701 0.0111562 -0.238973 -0.0153157 0.0209825 -0.238473 -0.0123701 0.0111562 -0.238473 -0.0153157 0.0209825 -0.238473 -0.0199229 0.0301479 -0.238473 -0.0260517 0.0383741 -0.238973 -0.0335158 0.045411 -0.238473 -0.0335158 0.045411 -0.238973 -0.0420884 0.0510449 -0.238473 -0.0420884 0.0510449 -0.238473 -0.0515092 0.0551046 -0.238973 -0.0614917 0.0574667 -0.238473 -0.0614917 0.0574667 -0.238473 -0.0717328 0.0580595 -0.238473 -0.0917475 0.0539193 -0.238473 -0.100913 0.0493121 -0.238473 -0.109139 0.0431834 -0.238973 -0.116176 0.0357193 -0.238473 -0.116176 0.0357193 -0.238973 -0.12181 0.0271467 -0.238973 -0.12587 0.0177259 -0.238973 -0.128232 0.00774335 -0.238973 -0.128825 -0.00249774 -0.241173 -0.125776 -0.00240794 -0.241173 -0.113783 0.0338284 -0.238973 -0.109139 0.0431834 -0.241173 -0.0993108 0.0467168 -0.238973 -0.100913 0.0493121 -0.241173 -0.0906204 0.0510852 -0.238973 -0.0917475 0.0539193 -0.241173 -0.0813034 0.0538782 -0.238973 -0.0819212 0.0568649 -0.238973 -0.0717328 0.0580595 -0.238973 -0.0515092 0.0551046 -0.241173 -0.0524675 0.0522091 -0.238973 -0.0260517 0.0383741 -0.241173 -0.0283294 0.0363456 -0.238973 -0.0199229 0.0301479 -0.241173 -0.0225183 0.0285458 -0.241173 -0.0153569 0.0105384 -0.241173 -0.0142242 0.000877994 -0.241173 -0.107111 0.0409057 -0.241173 -0.0920619 0.034974 -0.241173 -0.0841492 0.0387799 -0.241173 -0.110807 -0.0107031 -0.241173 -0.12185 -0.0213853 -0.241173 -0.125214 0.00730239 -0.241173 -0.122974 0.0167676 -0.241173 -0.119125 0.0257001 -0.241173 -0.0367629 0.0249118 -0.241173 -0.0181499 0.0198554 -0.241173 -0.0291928 0.00917315 -0.241173 -0.0280183 0.00047167 -0.241173 -0.071643 0.0550108 -0.241173 -0.0619327 0.0544488 -0.241173 -0.0668416 0.0411161 -0.241173 -0.0500801 0.0362106 -0.241173 -0.0428277 0.0312611 -0.241173 -0.043535 0.0483598 -0.241173 -0.0354066 0.0430179 -0.241173 -0.0208753 -0.02723 -0.241173 -0.0353092 -0.0244408 -0.241173 -0.0328895 -0.0424356 -0.241173 -0.0406893 -0.0482468 -0.241173 -0.0780674 -0.0559787 -0.241173 -0.0964651 -0.0498897 -0.241173 -0.104593 -0.0445478 -0.241173 -0.111671 -0.0378756 -0.241173 -0.117482 -0.0300757 -0.241373 -0.0291928 0.00917315 -0.241173 -0.0321508 0.0174403 -0.241373 -0.0367629 0.0249118 -0.241373 -0.0582031 0.0395442 -0.241173 -0.0582031 0.0395442 -0.241173 -0.0756182 0.0408576 -0.241373 -0.0920619 0.034974 -0.241373 -0.0990103 0.0296061 -0.241173 -0.0990103 0.0296061 -0.241373 -0.104691 0.0229108 -0.241173 -0.104691 0.0229108 -0.241373 -0.108855 0.0151808 -0.241173 -0.108855 0.0151808 -0.241173 -0.111322 0.00675392 -0.238973 -0.0291928 0.00917315 -0.239373 -0.0316872 0.0164433 -0.239373 -0.0321508 0.0174403 -0.239373 -0.0357805 0.0235871 -0.239373 -0.0477044 0.0348287 -0.238973 -0.0367629 0.0249118 -0.238973 -0.0582031 0.0395442 -0.239373 -0.0500801 0.0362106 -0.239373 -0.0550768 0.0384944 -0.239373 -0.0712367 0.0412168 -0.238973 -0.0756182 0.0408576 -0.239373 -0.0756182 0.0408576 -0.239373 -0.0794032 0.0401689 -0.238973 -0.0841492 0.0387799 -0.239373 -0.0841492 0.0387799 -0.239373 -0.0872083 0.0375479 -0.238973 -0.0920619 0.034974 -0.239373 -0.0943521 0.0334546 -0.238973 -0.0990103 0.0296061 -0.239373 -0.0990103 0.0296061 -0.239373 -0.10056 0.0280462 -0.238973 -0.108855 0.0151808 -0.239373 -0.108855 0.0151808 -0.239373 -0.109259 0.0141583 -0.239373 -0.111982 -0.00200161 -0.239373 -0.111416 0.00621239 -0.238973 -0.111322 0.00675392 -0.238673 -0.0672816 -0.0301395 -0.238673 -0.0907165 -0.0217669 -0.238673 -0.0445786 0.0142018 -0.238673 -0.0490994 0.0200536 -0.238673 -0.0977363 0.0092824 -0.238673 -0.0566837 0.0287393 -0.238673 -0.0549334 0.0245973 -0.238673 -0.0746982 -0.0327496 -0.238673 -0.0407517 0.0142821 -0.238673 -0.104443 0.0227417 -0.238673 -0.108578 0.0150669 -0.238673 -0.0424585 -0.0281354 -0.238673 -0.0402273 -0.00351888 -0.238673 -0.0304053 -0.0138471 -0.238673 -0.0392503 -0.0152158 -0.238673 -0.0399167 -0.0140643 -0.238673 -0.0338657 -0.0121855 -0.238673 -0.0314223 -0.0165969 -0.238673 -0.0373575 -0.0162356 -0.238673 -0.035557 -0.0242717 -0.238673 -0.0449354 -0.0202598 -0.238673 -0.0446496 -0.020826 -0.238673 -0.0397387 -0.0201067 -0.238673 -0.044674 -0.0291309 -0.238673 -0.044657 -0.02971 -0.238673 -0.0399436 -0.02967 -0.238673 -0.041197 -0.0309191 -0.238673 -0.0445693 -0.0326855 -0.238673 -0.0634567 -0.0361089 -0.238673 -0.0559519 -0.0400274 -0.238673 -0.0607151 -0.0381662 -0.238673 -0.0678402 -0.0375793 -0.238673 -0.0654108 -0.0332994 -0.238673 -0.064422 -0.0420902 -0.238673 -0.0670767 -0.0367695 -0.238673 -0.0679498 -0.033857 -0.238673 -0.0690328 -0.0336007 -0.238673 -0.0700989 -0.0339203 -0.238673 -0.0731359 -0.0423469 -0.238673 -0.0689062 -0.0378989 -0.238673 -0.0708623 -0.0347301 -0.238673 -0.0711186 -0.0358131 -0.238673 -0.070799 -0.0368792 -0.238673 -0.0755067 -0.0378388 -0.238673 -0.0770674 -0.0386479 -0.238673 -0.0804302 -0.0379838 -0.238673 -0.0988713 -0.0308539 -0.238673 -0.0983213 -0.0313721 -0.238673 -0.107579 -0.0188402 -0.238673 -0.10702 -0.0160409 -0.238673 -0.102046 -0.0219421 -0.238673 -0.101984 -0.0275214 -0.238673 -0.110516 -0.0106321 -0.238673 -0.111026 0.00670021 -0.238673 -0.108008 0.00717805 -0.238673 -0.107537 0.00916777 -0.238673 -0.103504 0.0240624 -0.238673 -0.100056 0.02814 -0.238673 -0.0801665 0.0367093 -0.238673 -0.0755781 0.0405603 -0.238673 -0.0508308 0.0362679 -0.238673 -0.051251 0.0301113 -0.238673 -0.0515706 0.0311774 -0.238673 -0.0523804 0.0319408 -0.238673 -0.0534634 0.0321971 -0.238673 -0.0430218 0.0310323 -0.238673 -0.0506583 0.0294963 -0.238673 -0.0420424 0.024818 -0.238673 -0.0409297 0.0203245 -0.238673 -0.0383881 0.0187493 -0.238673 -0.0312439 0.0146251 -0.238673 -0.0283181 0.000462837 -0.238673 -0.0399515 0.0111586 -0.238673 -0.0404411 0.00373664 -0.238673 -0.0331129 0.0113601 -0.238673 -0.0325257 0.00940149 -0.238673 -0.0339214 0.00627081 -0.238673 -0.0839985 0.0326448 -0.238673 -0.0729234 0.0352396 -0.238673 -0.0781768 0.0362385 -0.238673 -0.0761019 0.0328774 -0.238673 -0.0700109 0.0361127 -0.238673 -0.0688815 0.0342832 -0.238673 -0.0691378 0.0332001 -0.238673 -0.0953431 0.0281801 -0.238673 -0.0879992 0.0361748 -0.238673 -0.0834114 0.0306862 -0.238673 -0.0779753 0.0293999 -0.238673 -0.099415 0.023128 -0.238673 -0.0990745 0.0248527 -0.238673 -0.0999436 0.027465 -0.238673 -0.0964587 0.0270678 -0.238673 -0.095326 0.027601 -0.238673 -0.101985 0.00393318 -0.238673 -0.103943 0.00334606 -0.238673 -0.107421 0.00521948 -0.238673 -0.102186 0.0107718 -0.238673 -0.100698 0.00936921 -0.238673 -0.100111 0.00741065 -0.238673 -0.0995043 0.0125514 -0.238673 -0.105897 -0.0139745 -0.238673 -0.0995778 -0.0106988 -0.238673 -0.107331 -0.00549551 -0.238673 -0.105601 -0.00745396 -0.238673 -0.102534 -0.00535423 -0.238673 -0.0935077 -0.034127 -0.238673 -0.0969783 -0.0325622 -0.238673 -0.098303 -0.0313891 -0.238673 -0.0958828 -0.0297091 -0.238673 -0.09823 -0.0307085 -0.238673 -0.0973705 -0.0283065 -0.238673 -0.0905319 -0.0281051 -0.238673 -0.0860396 -0.0303494 -0.238673 -0.0919345 -0.0295928 -0.238673 -0.0979576 -0.026348 -0.238673 -0.0974868 -0.0243583 -0.238673 -0.0960842 -0.0228705 -0.238673 -0.0941257 -0.0222834 -0.238673 -0.0881266 -0.0240389 -0.238673 -0.0900611 -0.0261154 -0.238673 -0.0859349 -0.033904 -0.238673 -0.0815368 -0.032951 -0.238673 -0.0860226 -0.0309285 -0.238673 -0.0638982 -0.0344073 -0.238673 -0.0654984 -0.0303239 -0.238673 -0.0634274 -0.0324176 -0.238673 -0.054953 -0.0300133 -0.238673 -0.0548654 -0.0329888 -0.238673 -0.0565887 -0.0322161 -0.238673 -0.0478945 -0.0268491 -0.238673 -0.0484816 -0.0248906 -0.238673 -0.0479102 -0.0203172 -0.238673 -0.0426296 0.0267766 -0.238673 -0.0441173 0.0281792 -0.238673 -0.0410486 0.0292468 -0.238673 -0.0411288 0.0293239 -0.238673 -0.046107 0.02865 -0.238673 -0.0439159 0.0213406 -0.238673 -0.0458744 0.0207534 -0.238673 -0.0478642 0.0212243 -0.238673 -0.0503105 0.0212025 -0.238673 -0.049939 0.0245854 -0.238673 -0.0654182 0.0351679 -0.238673 -0.0674751 0.0367794 -0.238673 -0.0668642 0.040817 -0.238673 -0.0640156 0.0366557 -0.238673 -0.062057 0.0372428 -0.238673 -0.0582873 0.0392563 -0.238673 -0.0569296 0.03709 -0.238673 -0.0545295 0.0318775 -0.238673 -0.0531897 0.0373965 -0.238673 -0.0567007 0.0293184 -0.238673 -0.0618244 0.0293462 -0.238673 -0.0672461 0.0290077 -0.238673 -0.0324211 0.0173103 -0.238673 -0.0402809 0.019769 -0.238673 -0.0461263 0.0201714 -0.238673 -0.0421104 0.0186396 -0.238673 -0.0533368 0.027899 -0.238673 -0.0950652 0.0147909 -0.238673 -0.0989203 0.0148153 -0.238673 -0.0996837 0.0140055 -0.238673 -0.101833 0.0139422 -0.238673 -0.102643 0.0147056 -0.238673 -0.102706 0.0168547 -0.238673 -0.103237 0.0184891 -0.238673 -0.0996823 0.0185938 -0.238673 -0.0950647 0.0187299 -0.238673 -0.0989836 0.0169643 -0.238673 -0.098664 0.0158983 -0.238673 -0.103059 0.0124467 -0.238673 -0.107855 0.0123054 -0.238673 -0.109595 0.0123172 -0.238673 -0.0987628 -0.0172571 -0.238673 -0.100165 -0.00874026 -0.238673 -0.0970968 -0.0124275 -0.238673 -0.100802 -0.0210427 -0.238673 -0.097953 -0.0180205 -0.238673 -0.0938738 -0.0217014 -0.238673 -0.0984913 -0.0218374 -0.238673 -0.0978897 -0.0201696 -0.238673 -0.101612 -0.0202792 -0.238673 -0.101932 -0.0192132 -0.238673 -0.102224 -0.0158997 -0.238673 -0.0986693 -0.015795 -0.238673 -0.0534447 -0.0316768 -0.238673 -0.0515519 -0.0326965 -0.238673 -0.0489276 -0.0292562 -0.238673 -0.0488229 -0.0328108 -0.238673 -0.0497224 -0.0315672 -0.238673 -0.0600619 -0.0285406 -0.238673 -0.0534666 -0.0251964 -0.238673 -0.0549701 -0.0294342 -0.238673 -0.0372942 -0.0183846 -0.238673 -0.0380577 -0.0191944 -0.238673 -0.0402067 -0.0192577 -0.238673 -0.0410165 -0.0184943 -0.238673 -0.0466082 -0.0214131 -0.238673 -0.0544198 0.0281552 -0.238673 -0.0552296 0.0289187 -0.238673 -0.0877703 0.0284032 -0.238673 -0.083341 0.025546 -0.238673 -0.0894652 0.0214017 -0.238673 -0.053508 -0.0295277 -0.238673 -0.0817692 -0.0278156 -0.238673 -0.0412232 -0.00725684 -0.238673 -0.0405128 0.000103622 -0.238673 -0.0416552 0.0074095 -0.238673 -0.0412373 0.0157271 -0.238673 -0.0506412 0.0289173 -0.238673 -0.0464047 0.0296216 -0.238673 -0.0463876 0.0290426 -0.238673 -0.0877532 0.0278241 -0.238673 -0.0763786 0.0280372 -0.238673 -0.106878 -0.000775794 -0.238673 -0.107544 0.00176001 -0.238673 -0.0993636 0.00206901 -0.238673 -0.102836 -0.0017322 -0.238673 -0.103092 -0.00281522 -0.238673 -0.103856 -0.003625 -0.238673 -0.106005 -0.0036883 -0.238673 -0.102748 0.00190129 -0.238673 -0.105048 0.000353563 -0.238673 -0.0489106 -0.0298353 -0.238673 -0.0897777 -0.0374765 -0.238673 -0.0935954 -0.0311516 -0.238673 -0.0936124 -0.0305725 -0.239373 -0.110934 -0.0101681 -0.238973 -0.110807 -0.0107031 -0.239373 -0.110807 -0.0107031 -0.238973 -0.107849 -0.0189702 -0.239373 -0.103237 -0.0264417 -0.238973 -0.08992 -0.0377406 -0.239373 -0.0922956 -0.0363586 -0.239373 -0.08992 -0.0377406 -0.238973 -0.0731585 -0.042646 -0.238973 -0.0558508 -0.0403099 -0.239373 -0.0527918 -0.0390778 -0.238973 -0.0479382 -0.0365039 -0.239373 -0.045648 -0.0349845 -0.239373 -0.03944 -0.0295761 -0.238973 -0.0353092 -0.0244408 -0.239373 -0.0344064 -0.0230606 -0.239373 -0.0311448 -0.0167108 -0.238973 -0.0311448 -0.0167108 -0.239373 -0.0280183 0.00047167 -0.239373 -0.0286785 -0.00828386 -0.239373 -0.0307407 -0.0156882 -0.241173 -0.111982 -0.00200161 -0.241373 -0.107849 -0.0189702 -0.241373 -0.103237 -0.0264417 -0.241173 -0.107849 -0.0189702 -0.241173 -0.103237 -0.0264417 -0.241173 -0.0971723 -0.032791 -0.241173 -0.08992 -0.0377406 -0.241373 -0.08992 -0.0377406 -0.241373 -0.081797 -0.0410742 -0.241173 -0.081797 -0.0410742 -0.241173 -0.0731585 -0.042646 -0.241173 -0.0643819 -0.0423875 -0.241173 -0.0558508 -0.0403099 -0.241373 -0.0558508 -0.0403099 -0.241373 -0.0479382 -0.0365039 -0.241173 -0.0479382 -0.0365039 -0.241373 -0.0409897 -0.031136 -0.241173 -0.0409897 -0.031136 -0.241173 -0.0311448 -0.0167108 -0.241173 -0.0286785 -0.00828386 -0.238973 -0.0117683 -0.00927329 -0.241173 -0.0147863 -0.00883233 -0.238973 -0.0141305 -0.0192559 -0.241173 -0.017026 -0.0182975 -0.241173 -0.0262172 -0.0353584 -0.241173 -0.0493797 -0.0526152 -0.238973 -0.0580788 -0.0583949 -0.241173 -0.0586967 -0.0554081 -0.238973 -0.0682673 -0.0595895 -0.241173 -0.0683571 -0.0565408 -0.238973 -0.0785084 -0.0589967 -0.241173 -0.0875326 -0.053739 -0.238973 -0.0979117 -0.0525749 -0.238973 -0.120077 -0.0316778 -0.238973 -0.12763 -0.0126862 -0.241173 -0.124643 -0.0120683 -0.238473 -0.124684 -0.0225124 -0.238973 -0.124684 -0.0225124 -0.238473 -0.120077 -0.0316778 -0.238973 -0.113948 -0.039904 -0.238973 -0.106484 -0.0469409 -0.238473 -0.106484 -0.0469409 -0.238473 -0.0979117 -0.0525749 -0.238973 -0.0884909 -0.0566345 -0.238473 -0.0884909 -0.0566345 -0.238473 -0.0785084 -0.0589967 -0.238473 -0.0682673 -0.0595895 -0.238973 -0.0482526 -0.0554493 -0.238973 -0.0390872 -0.0508421 -0.238973 -0.030861 -0.0447133 -0.238473 -0.0390872 -0.0508421 -0.238973 -0.0238241 -0.0372492 -0.238973 -0.0181902 -0.0286766 -0.238473 -0.0238241 -0.0372492 -0.238473 -0.0181902 -0.0286766 -0.238473 -0.0141305 -0.0192559 -0.238973 -0.0111756 0.000967798 -0.237473 -0.127425 -0.00245652 -0.238273 -0.123383 -0.021995 -0.238273 -0.118886 -0.0309424 -0.238273 -0.112903 -0.0389729 -0.237473 -0.112903 -0.0389729 -0.237473 -0.105616 -0.0458425 -0.238273 -0.088051 -0.0553054 -0.237473 -0.0583624 -0.0570239 -0.237473 -0.04877 -0.0541484 -0.238273 -0.0398226 -0.0496508 -0.238273 -0.0317921 -0.0436678 -0.238273 -0.0194227 -0.0280126 -0.237473 -0.0154596 -0.018816 -0.238273 -0.0131536 -0.00907088 -0.237473 -0.0131536 -0.00907088 -0.237473 -0.126326 -0.00242413 -0.237873 -0.125671 0.00795392 -0.237873 -0.123121 0.0180351 -0.237473 -0.118762 0.027476 -0.237873 -0.105268 0.0431839 -0.237473 -0.105268 0.0431839 -0.237473 -0.0870101 0.0529564 -0.237873 -0.0965917 0.0489161 -0.237873 -0.0870101 0.0529564 -0.237473 -0.0768492 0.0551672 -0.237473 -0.0664551 0.0554734 -0.237473 -0.0561816 0.0538645 -0.237873 -0.0561816 0.0538645 -0.237873 -0.0463788 0.0503952 -0.237473 -0.0373803 0.0451837 -0.237873 -0.0373803 0.0451837 -0.237473 -0.0294927 0.0384075 -0.237873 -0.0294927 0.0384075 -0.237873 -0.0180774 0.0211293 -0.237473 -0.0136745 0.000894189 -0.239973 -0.125076 -0.00238733 -0.239973 -0.124436 0.00776051 -0.239973 -0.121943 0.017618 -0.238073 -0.111795 0.0351406 -0.239973 -0.111795 0.0351406 -0.238073 -0.104485 0.042209 -0.238073 -0.0866328 0.0517647 -0.239973 -0.0960018 0.047814 -0.239973 -0.0866328 0.0517647 -0.239973 -0.0665337 0.0542259 -0.238073 -0.0469028 0.0492603 -0.238073 -0.0381039 0.0441644 -0.239973 -0.0381039 0.0441644 -0.239973 -0.0303913 0.0375385 -0.238073 -0.0240274 0.0296082 -0.239973 -0.0240274 0.0296082 -0.238073 -0.0192292 0.0206436 -0.239973 -0.0161598 0.01095 -0.238073 -0.122877 -0.00232255 -0.238073 -0.118744 -0.0213188 -0.239973 -0.118744 -0.0213188 -0.238073 -0.114137 -0.0299254 -0.239973 -0.114137 -0.0299254 -0.238073 -0.100623 -0.0439004 -0.238073 -0.0921751 -0.0487929 -0.239973 -0.0829724 -0.0520497 -0.238073 -0.0829724 -0.0520497 -0.238073 -0.073328 -0.0535602 -0.239973 -0.0635702 -0.0532728 -0.239973 -0.0540314 -0.0511972 -0.239973 -0.0450364 -0.0474043 -0.239973 -0.0368915 -0.0420231 -0.238073 -0.0298741 -0.035237 -0.238073 -0.0242231 -0.0272769 -0.238073 -0.0177371 -0.00895005 -0.240173 -0.121374 0.00728085 -0.240173 -0.119021 0.0165838 -0.240173 -0.114998 0.0252959 -0.240173 -0.102545 0.0397913 -0.240173 -0.0945389 0.0450809 -0.238073 -0.085697 0.0488093 -0.240173 -0.085697 0.0488093 -0.240173 -0.0763205 0.0508495 -0.238073 -0.0667287 0.051132 -0.240173 -0.0667287 0.051132 -0.240173 -0.0482023 0.0464458 -0.238073 -0.0398985 0.0416366 -0.240173 -0.0326197 0.0353835 -0.240173 -0.0266139 0.0278994 -0.240173 -0.0220856 0.0194391 -0.240173 -0.0191889 0.0102909 -0.239373 -0.0731585 -0.042646 -0.240173 -0.11598 -0.00211939 -0.240173 -0.114832 -0.0110636 -0.239373 -0.10422 -0.025117 -0.239373 -0.107849 -0.0189702 -0.239373 -0.108313 -0.0179732 -0.239373 -0.0971723 -0.032791 -0.240173 -0.101555 -0.0342355 -0.239373 -0.0988112 -0.031325 -0.240173 -0.107479 -0.0274363 -0.239373 -0.0769774 -0.0421814 -0.240173 -0.0863445 -0.0437633 -0.239373 -0.081797 -0.0410742 -0.239373 -0.0849233 -0.0400243 -0.239373 -0.0687634 -0.0427468 -0.239373 -0.0643819 -0.0423875 -0.240173 -0.0686456 -0.046745 -0.239373 -0.0605969 -0.0416988 -0.239373 -0.0558508 -0.0403099 -0.240173 -0.0511529 -0.0427267 -0.239373 -0.0479382 -0.0365039 -0.240173 -0.0433287 -0.0382435 -0.239373 -0.0409897 -0.031136 -0.239373 -0.0353092 -0.0244408 -0.240173 -0.0310165 -0.025184 -0.240173 -0.0246392 -0.00840684 -0.239373 -0.0285837 -0.00774233 -0.238673 -0.0410798 -0.0163452 -0.238673 -0.0403164 -0.0155354 -0.239023 -0.0405764 -0.0157242 -0.239023 -0.0403164 -0.0155354 -0.239023 -0.039727 -0.0152838 -0.238673 -0.0381673 -0.0154721 -0.239023 -0.0381673 -0.0154721 -0.239023 -0.0372782 -0.0163754 -0.241673 -0.0349256 -0.0151558 -0.239023 -0.0373575 -0.0162356 -0.239023 -0.0378966 -0.0156452 -0.239023 -0.0387705 -0.0152556 -0.239023 -0.0392503 -0.0152158 -0.239023 -0.0413361 -0.0174282 -0.239023 -0.0411507 -0.0164895 -0.241673 -0.0435711 -0.0154105 -0.239023 -0.0410798 -0.0163452 -0.238673 -0.0537642 -0.0306108 -0.239023 -0.0537642 -0.0306108 -0.238673 -0.0527445 -0.028718 -0.238673 -0.0516785 -0.0283984 -0.239023 -0.0527445 -0.028718 -0.239023 -0.0516785 -0.0283984 -0.239023 -0.0505955 -0.0286547 -0.238673 -0.0505955 -0.0286547 -0.238673 -0.0497857 -0.0294181 -0.239023 -0.0497857 -0.0294181 -0.239023 -0.053508 -0.0295277 -0.241673 -0.0541365 -0.026463 -0.241673 -0.0493386 -0.0263217 -0.241673 -0.0475307 -0.0280261 -0.239023 -0.0708623 -0.0347301 -0.239023 -0.0700989 -0.0339203 -0.239023 -0.0690328 -0.0336007 -0.238673 -0.06714 -0.0346204 -0.239023 -0.0679498 -0.033857 -0.238673 -0.0668204 -0.0356865 -0.239023 -0.06714 -0.0346204 -0.239023 -0.0668204 -0.0356865 -0.241673 -0.0691108 -0.0309519 -0.241673 -0.0648851 -0.0332284 -0.241673 -0.0641716 -0.0356085 -0.238673 -0.101675 -0.0181301 -0.238673 -0.100912 -0.0173204 -0.239023 -0.100912 -0.0173204 -0.238673 -0.0998458 -0.0170008 -0.239023 -0.0998458 -0.0170008 -0.239023 -0.0987628 -0.0172571 -0.239023 -0.097953 -0.0180205 -0.238673 -0.0976335 -0.0190865 -0.239023 -0.0976335 -0.0190865 -0.239023 -0.101675 -0.0181301 -0.241673 -0.097506 -0.0149241 -0.241673 -0.0949846 -0.0190085 -0.238673 -0.107134 -0.00185881 -0.239023 -0.106114 3.39907e-05 -0.238673 -0.106114 3.39907e-05 -0.238673 -0.103965 9.72949e-05 -0.238673 -0.103155 -0.000666148 -0.239023 -0.103155 -0.000666148 -0.239023 -0.107134 -0.00185881 -0.239023 -0.106878 -0.000775794 -0.241673 -0.109211 0.000481059 -0.241673 -0.107506 0.00228895 -0.239023 -0.105048 0.000353563 -0.239023 -0.103965 9.72949e-05 -0.241673 -0.1009 0.000725851 -0.238673 -0.101942 0.0176645 -0.238673 -0.100876 0.017984 -0.239023 -0.100876 0.017984 -0.238673 -0.0997933 0.0177278 -0.241673 -0.105611 0.0156936 -0.239023 -0.102706 0.0168547 -0.241673 -0.105039 0.0181115 -0.239023 -0.101942 0.0176645 -0.239023 -0.0997933 0.0177278 -0.241673 -0.0985365 0.0200608 -0.239023 -0.0989836 0.0169643 -0.239023 -0.0729234 0.0352396 -0.238673 -0.0721599 0.0360494 -0.239023 -0.0721599 0.0360494 -0.239023 -0.0715705 0.036301 -0.238673 -0.0710939 0.0363689 -0.239023 -0.0688815 0.0342832 -0.238673 -0.0692011 0.0353492 -0.239023 -0.0692011 0.0353492 -0.239023 -0.0691218 0.0352093 -0.241673 -0.0667691 0.0364289 -0.241673 -0.0681496 0.0380591 -0.239023 -0.0697401 0.0359395 -0.239023 -0.0700109 0.0361127 -0.241673 -0.0701007 0.0389289 -0.239023 -0.0706141 0.0363291 -0.239023 -0.0710939 0.0363689 -0.241673 -0.0741325 0.0378829 -0.239023 -0.0729943 0.0350953 -0.241673 -0.0754147 0.0361743 -0.239023 -0.07242 0.0358606 -0.238673 -0.0552929 0.0310678 -0.239023 -0.0552929 0.0310678 -0.239023 -0.0547895 0.0316888 -0.239023 -0.0529836 0.0321573 -0.239023 -0.0521097 0.0317677 -0.239023 -0.0514913 0.0310375 -0.241673 -0.0491386 0.0322571 -0.239023 -0.0515706 0.0311774 -0.239023 -0.0523804 0.0319408 -0.241673 -0.0524702 0.0347571 -0.239023 -0.0534634 0.0321971 -0.241673 -0.056502 0.0337111 -0.239023 -0.05394 0.0321291 -0.239023 -0.0545295 0.0318775 -0.239023 -0.0553638 0.0309235 -0.241673 -0.0577842 0.0320024 -0.238673 -0.0423666 0.0175566 -0.239023 -0.0421813 0.0184953 -0.238673 -0.0413469 0.0194494 -0.239023 -0.0413469 0.0194494 -0.239023 -0.0402809 0.019769 -0.239023 -0.0398011 0.0197292 -0.238673 -0.0391979 0.0195127 -0.239023 -0.0389271 0.0193396 -0.239023 -0.0383088 0.0186094 -0.241673 -0.0359561 0.019829 -0.239023 -0.0380685 0.0176832 -0.239023 -0.0383881 0.0187493 -0.241673 -0.0392877 0.022329 -0.239023 -0.0391979 0.0195127 -0.241673 -0.041423 0.0222661 -0.239023 -0.0407575 0.019701 -0.241673 -0.0433195 0.021283 -0.239023 -0.041607 0.0192607 -0.239023 -0.0423666 0.0175566 -0.241673 -0.0450155 0.0174786 -0.239023 -0.0421104 0.0186396 -0.241673 -0.0446017 0.0195743 -0.241473 -0.0393656 -0.00729741 -0.241473 -0.039242 -0.00704573 -0.241473 -0.038364 -0.00596254 -0.241473 -0.0379104 -0.00563331 -0.238873 -0.0379104 -0.00563331 -0.238873 -0.036051 -0.00507592 -0.238873 -0.034162 -0.0055229 -0.241473 -0.034162 -0.0055229 -0.241473 -0.0336898 -0.00582485 -0.241473 -0.0482817 -0.0248847 -0.238873 -0.0478347 -0.0229957 -0.238873 -0.0465031 -0.0215833 -0.238873 -0.0446438 -0.0210259 -0.241473 -0.0427548 -0.0214729 -0.238873 -0.0413424 -0.0228045 -0.238873 -0.0636983 -0.0344014 -0.241473 -0.063375 -0.0327641 -0.238873 -0.0623733 -0.0314292 -0.238873 -0.0619197 -0.0311 -0.241473 -0.0608916 -0.0306612 -0.238873 -0.0600603 -0.0305426 -0.241473 -0.0566206 -0.0325652 -0.238873 -0.0567589 -0.0323212 -0.238873 -0.0813608 -0.0330459 -0.238873 -0.0804828 -0.0319627 -0.238873 -0.0800292 -0.0316335 -0.241473 -0.0790011 -0.0311946 -0.241473 -0.0773329 -0.0311455 -0.238873 -0.0762808 -0.031523 -0.238873 -0.0748684 -0.0328546 -0.238873 -0.0973107 -0.0244531 -0.241473 -0.0977577 -0.0263421 -0.238873 -0.0941198 -0.0224833 -0.241473 -0.0922308 -0.0229303 -0.241473 -0.0908184 -0.0242619 -0.238873 -0.0908184 -0.0242619 -0.238873 -0.090261 -0.0261213 -0.241473 -0.090261 -0.0261213 -0.241473 -0.106951 -0.00928825 -0.238873 -0.106827 -0.00903656 -0.238873 -0.105949 -0.00795337 -0.238873 -0.105496 -0.00762415 -0.238873 -0.104468 -0.0071853 -0.238873 -0.103636 -0.00706676 -0.241473 -0.100197 -0.00908929 -0.241473 -0.0997777 -0.0107047 -0.238873 -0.107361 0.00907291 -0.238873 -0.106029 0.0104853 -0.238873 -0.10417 0.0110427 -0.241473 -0.10417 0.0110427 -0.238873 -0.102281 0.0105957 -0.241473 -0.100869 0.00926416 -0.241473 -0.100311 0.00740476 -0.238873 -0.0992151 0.0231339 -0.241473 -0.0974366 0.0264353 -0.238873 -0.0974366 0.0264353 -0.238873 -0.0955772 0.0269927 -0.238873 -0.0947403 0.0269233 -0.238873 -0.0922758 0.0252141 -0.238873 -0.0917184 0.0233548 -0.241473 -0.0833516 0.0345396 -0.238873 -0.0801606 0.0365094 -0.241473 -0.0763018 0.0328715 -0.241473 -0.0656891 0.0331841 -0.238873 -0.0652421 0.0350731 -0.241473 -0.0652421 0.0350731 -0.241473 -0.0643641 0.0361563 -0.238873 -0.0639105 0.0364855 -0.241473 -0.0639105 0.0364855 -0.241473 -0.0628825 0.0369243 -0.241473 -0.0620511 0.0370429 -0.238873 -0.0620511 0.0370429 -0.241473 -0.0612143 0.0369735 -0.238873 -0.0601622 0.0365959 -0.241473 -0.0601622 0.0365959 -0.241473 -0.05969 0.0362939 -0.238873 -0.0587497 0.0352643 -0.241473 -0.0586115 0.0350203 -0.238873 -0.0492921 0.0264803 -0.241473 -0.0479605 0.0278927 -0.241473 -0.0461011 0.0284501 -0.241473 -0.0442122 0.0280031 -0.238873 -0.0427998 0.0266715 -0.241473 -0.0402224 0.00917477 -0.238873 -0.0397754 0.0110638 -0.238873 -0.0388974 0.0121469 -0.241473 -0.0388974 0.0121469 -0.241473 -0.0374158 0.012915 -0.238873 -0.0374158 0.012915 -0.238873 -0.0365844 0.0130336 -0.241473 -0.0357476 0.0129642 -0.241473 -0.0342233 0.0122846 -0.238873 -0.0342233 0.0122846 -0.241473 -0.0331448 0.011011 -0.238673 -0.111682 -0.00199278 -0.238973 -0.111982 -0.00200161 -0.238673 -0.103 -0.0262583 -0.238673 -0.107003 -0.0199916 -0.238973 -0.103237 -0.0264417 -0.238973 -0.0971723 -0.032791 -0.238973 -0.0643819 -0.0423875 -0.238673 -0.0817128 -0.0407862 -0.238973 -0.081797 -0.0410742 -0.238673 -0.0480958 -0.0362487 -0.238673 -0.0546222 -0.0395259 -0.238673 -0.0394078 -0.0291023 -0.238973 -0.0409897 -0.031136 -0.238673 -0.0393322 -0.0290205 -0.238973 -0.0286785 -0.00828386 -0.238973 -0.0280183 0.00047167 -0.238673 -0.0289737 -0.00823015 -0.241673 -0.0283181 0.000462837 -0.241373 -0.0286785 -0.00828386 -0.241373 -0.0311448 -0.0167108 -0.241673 -0.035557 -0.0242717 -0.241373 -0.0353092 -0.0244408 -0.241673 -0.0395718 -0.0292784 -0.241673 -0.0397416 -0.0294584 -0.241373 -0.0971723 -0.032791 -0.241673 -0.0897777 -0.0374765 -0.241673 -0.0817128 -0.0407862 -0.241373 -0.0731585 -0.042646 -0.241373 -0.0643819 -0.0423875 -0.241673 -0.0559519 -0.0400274 -0.241673 -0.0969783 -0.0325622 -0.241673 -0.0986971 -0.03102 -0.241373 -0.110807 -0.0107031 -0.241673 -0.110516 -0.0106321 -0.241373 -0.111982 -0.00200161 -0.241473 -0.0818077 -0.0349349 -0.241473 -0.0814844 -0.0332976 -0.241473 -0.0804828 -0.0319627 -0.241473 -0.0758086 -0.031825 -0.241473 -0.0747301 -0.0330986 -0.241473 -0.074311 -0.034714 -0.241673 -0.0745525 -0.0330066 -0.241673 -0.0741111 -0.0347081 -0.241473 -0.0973107 -0.0244531 -0.241473 -0.0959792 -0.0230407 -0.241473 -0.0941198 -0.0224833 -0.241673 -0.0921359 -0.0227542 -0.241673 -0.107134 -0.00920682 -0.241473 -0.105949 -0.00795337 -0.241673 -0.106079 -0.00780075 -0.241473 -0.104468 -0.0071853 -0.241473 -0.1028 -0.00713616 -0.241473 -0.101275 -0.00781569 -0.241673 -0.102761 -0.00693995 -0.241673 -0.101155 -0.00765572 -0.241473 -0.107808 0.00718394 -0.241473 -0.107361 0.00907291 -0.241673 -0.107537 0.00916777 -0.241473 -0.106029 0.0104853 -0.241673 -0.102186 0.0107718 -0.241473 -0.102281 0.0105957 -0.241673 -0.100111 0.00741065 -0.241473 -0.0987681 0.0250229 -0.241673 -0.0989442 0.0251178 -0.241673 -0.0975416 0.0266055 -0.241473 -0.0955772 0.0269927 -0.241673 -0.0955831 0.0271926 -0.241473 -0.0936882 0.0265457 -0.241673 -0.0935933 0.0267218 -0.241473 -0.0922758 0.0252141 -0.241473 -0.0917184 0.0233548 -0.241673 -0.0921056 0.0253192 -0.241673 -0.0915185 0.0233606 -0.241673 -0.0839985 0.0326448 -0.241673 -0.0835277 0.0346345 -0.241473 -0.08202 0.035952 -0.241673 -0.0821251 0.0361222 -0.241473 -0.0801606 0.0365094 -0.241673 -0.0801665 0.0367093 -0.241473 -0.0782716 0.0360624 -0.241473 -0.0768592 0.0347309 -0.241673 -0.076689 0.0348359 -0.241473 -0.0587497 0.0352643 -0.241673 -0.0595699 0.0364539 -0.241673 -0.0629327 0.0371179 -0.241673 -0.0644934 0.0363089 -0.241673 -0.0655485 0.0349028 -0.241473 -0.0653658 0.0348214 -0.241473 -0.0492921 0.0264803 -0.241673 -0.049939 0.0245854 -0.241473 -0.0427998 0.0266715 -0.241673 -0.0426296 0.0267766 -0.241473 -0.0398991 0.0108121 -0.241673 -0.0400818 0.0108935 -0.241673 -0.0390267 0.0122996 -0.241673 -0.0341032 0.0124446 -0.241673 -0.0329672 0.0111031 -0.241673 -0.0325257 0.00940149 -0.241673 -0.0324338 -0.00700641 -0.241473 -0.0321922 -0.00871388 -0.241473 -0.0326113 -0.00709845 -0.241473 -0.0327496 -0.00685448 -0.241473 -0.0352141 -0.00514533 -0.241473 -0.036051 -0.00507592 -0.241473 -0.0368823 -0.00519447 -0.241673 -0.0369325 -0.00500087 -0.241473 -0.0396889 -0.0089347 -0.241673 -0.0395483 -0.00721598 -0.241473 -0.0478347 -0.0229957 -0.241473 -0.0465031 -0.0215833 -0.241473 -0.0446438 -0.0210259 -0.241473 -0.0413424 -0.0228045 -0.241473 -0.040785 -0.0246639 -0.241673 -0.0411722 -0.0226994 -0.241473 -0.0623733 -0.0314292 -0.241673 -0.0625025 -0.0312766 -0.241673 -0.0609418 -0.0304676 -0.241473 -0.0592234 -0.030612 -0.241473 -0.0576991 -0.0312916 -0.241673 -0.0564431 -0.0324731 -0.238873 -0.0768592 0.0347309 -0.238673 -0.076689 0.0348359 -0.238873 -0.0782716 0.0360624 -0.238873 -0.08202 0.035952 -0.238673 -0.0821251 0.0361222 -0.238873 -0.0833516 0.0345396 -0.238873 -0.0837986 0.0326506 -0.238673 -0.0835277 0.0346345 -0.238873 -0.0988918 0.0247712 -0.238873 -0.0987681 0.0250229 -0.238873 -0.0978901 0.0261061 -0.238673 -0.0980194 0.0262587 -0.238873 -0.0964085 0.0268742 -0.238673 -0.0947016 0.0271195 -0.238873 -0.0936882 0.0265457 -0.238673 -0.093096 0.0264037 -0.238873 -0.093216 0.0262438 -0.238673 -0.0919599 0.0250622 -0.238873 -0.0921375 0.0249702 -0.238873 -0.100869 0.00926416 -0.238673 -0.104176 0.0112426 -0.238673 -0.106134 0.0106555 -0.238873 -0.107274 -0.0109255 -0.238673 -0.107004 -0.00894171 -0.238673 -0.103642 -0.00686684 -0.238873 -0.0997777 -0.0107047 -0.238873 -0.100335 -0.00884532 -0.238873 -0.101275 -0.00781569 -0.238873 -0.101747 -0.00751373 -0.238673 -0.101653 -0.00733766 -0.238873 -0.1028 -0.00713616 -0.238673 -0.0906482 -0.0241568 -0.238673 -0.0921359 -0.0227542 -0.238873 -0.0922308 -0.0229303 -0.238873 -0.0959792 -0.0230407 -0.238673 -0.0781757 -0.0308762 -0.238673 -0.0801342 -0.0314633 -0.238873 -0.0790011 -0.0311946 -0.238873 -0.0781698 -0.0310761 -0.238873 -0.074311 -0.034714 -0.238873 -0.0758086 -0.031825 -0.238673 -0.0761859 -0.031347 -0.238873 -0.0773329 -0.0311455 -0.238873 -0.0608916 -0.0306612 -0.238673 -0.0600662 -0.0303427 -0.238873 -0.0632513 -0.0325124 -0.238673 -0.0620247 -0.0309298 -0.238873 -0.0592234 -0.030612 -0.238673 -0.0580765 -0.0308135 -0.238873 -0.0576991 -0.0312916 -0.238873 -0.0581713 -0.0309896 -0.238873 -0.040785 -0.0246639 -0.238673 -0.040585 -0.024658 -0.238673 -0.0411722 -0.0226994 -0.238873 -0.0427548 -0.0214729 -0.238673 -0.0426599 -0.0212968 -0.238673 -0.0480108 -0.0229009 -0.238673 -0.0325794 -0.00674943 -0.238873 -0.0327496 -0.00685448 -0.238673 -0.0340672 -0.00534682 -0.238673 -0.0360569 -0.004876 -0.238873 -0.039242 -0.00704573 -0.238673 -0.0380154 -0.00546313 -0.238673 -0.039418 -0.00695087 -0.238673 -0.0365903 0.0132335 -0.238873 -0.0384438 0.0124762 -0.238673 -0.0385489 0.0126464 -0.238673 -0.0346006 0.0127627 -0.238873 -0.0327256 0.0093956 -0.238873 -0.033283 0.011255 -0.238873 -0.0346955 0.0125866 -0.238873 -0.0357476 0.0129642 -0.238873 -0.0442122 0.0280031 -0.238873 -0.0461011 0.0284501 -0.238673 -0.0480656 0.0280629 -0.238873 -0.0479605 0.0278927 -0.238673 -0.0494682 0.0265752 -0.238873 -0.0497391 0.0245913 -0.238673 -0.0585796 0.0353694 -0.238673 -0.0600673 0.036772 -0.238473 -0.12763 -0.0126862 -0.238273 -0.119907 -0.0315728 -0.238473 -0.113948 -0.039904 -0.238273 -0.113799 -0.039771 -0.238273 -0.10636 -0.046784 -0.238273 -0.0784794 -0.0587988 -0.238473 -0.0580788 -0.0583949 -0.238473 -0.0482526 -0.0554493 -0.238473 -0.030861 -0.0447133 -0.238273 -0.030994 -0.044564 -0.238273 -0.023981 -0.0371253 -0.238273 -0.0143203 -0.019193 -0.238473 -0.0117683 -0.00927329 -0.238473 -0.0111756 0.000967798 -0.238073 -0.0191889 0.0102909 -0.237873 -0.0178227 0.000771997 -0.237873 -0.0189935 0.0103334 -0.238073 -0.0220856 0.0194391 -0.238073 -0.0266139 0.0278994 -0.238073 -0.0326197 0.0353835 -0.237873 -0.0324759 0.0355225 -0.238073 -0.0482023 0.0464458 -0.237873 -0.0481184 0.0466274 -0.238073 -0.0572484 0.0496473 -0.237873 -0.0667161 0.0513316 -0.238073 -0.0763205 0.0508495 -0.238073 -0.0945389 0.0450809 -0.238073 -0.102545 0.0397913 -0.237873 -0.10267 0.0399472 -0.238073 -0.109443 0.0331205 -0.238073 -0.114998 0.0252959 -0.237873 -0.109595 0.0332509 -0.238073 -0.119021 0.0165838 -0.237873 -0.115171 0.0253961 -0.238073 -0.121374 0.00728085 -0.237873 -0.122677 -0.00231666 -0.238073 -0.121691 -0.0120122 -0.237873 -0.118559 -0.0212411 -0.237873 -0.11397 -0.0298152 -0.238073 -0.108027 -0.0375391 -0.237873 -0.107884 -0.0374001 -0.238073 -0.0635702 -0.0532728 -0.237873 -0.0733154 -0.0533606 -0.238073 -0.0540314 -0.0511972 -0.237873 -0.0540918 -0.0510066 -0.238073 -0.0450364 -0.0474043 -0.238073 -0.0368915 -0.0420231 -0.238073 -0.020131 -0.018414 -0.237473 -0.126259 -0.0124026 -0.237273 -0.126063 -0.0123621 -0.237473 -0.123383 -0.021995 -0.237473 -0.118886 -0.0309424 -0.237273 -0.123198 -0.0219211 -0.237273 -0.112754 -0.0388399 -0.237273 -0.105492 -0.0456855 -0.237473 -0.0972477 -0.0513423 -0.237273 -0.0879882 -0.0551156 -0.237473 -0.088051 -0.0553054 -0.237473 -0.078306 -0.0576114 -0.237273 -0.078277 -0.0574135 -0.237473 -0.0683085 -0.0581901 -0.237273 -0.0584029 -0.0568281 -0.237273 -0.0488439 -0.0539625 -0.237473 -0.0398226 -0.0496508 -0.237473 -0.0317921 -0.0436678 -0.237473 -0.0249226 -0.0363813 -0.237273 -0.0250795 -0.0362573 -0.237473 -0.0194227 -0.0280126 -0.237273 -0.0156494 -0.0187531 -0.237473 -0.012575 0.000926577 -0.237473 -0.0149384 0.0112157 -0.237273 -0.014743 0.0112583 -0.237473 -0.0180774 0.0211293 -0.237473 -0.0229845 0.0302973 -0.237273 -0.0293489 0.0385465 -0.237273 -0.0372646 0.0453468 -0.237473 -0.0463788 0.0503952 -0.237273 -0.0561326 0.0540584 -0.237273 -0.0768735 0.0553658 -0.237273 -0.0870705 0.053147 -0.237473 -0.0965917 0.0489161 -0.237473 -0.112743 0.0359552 -0.237273 -0.105393 0.0433399 -0.237273 -0.112895 0.0360855 -0.237273 -0.12331 0.0181018 -0.237473 -0.123121 0.0180351 -0.237473 -0.125671 0.00795392 -0.237273 -0.125869 0.00798486 -0.238073 -0.0149239 0.000857384 -0.238073 -0.0161598 0.01095 -0.237873 -0.0159644 0.0109925 -0.238073 -0.0303913 0.0375385 -0.238073 -0.0564882 0.0526526 -0.238073 -0.0665337 0.0542259 -0.237873 -0.0665211 0.0544255 -0.238073 -0.0766973 0.0539265 -0.238073 -0.0960018 0.047814 -0.237873 -0.0866931 0.0519553 -0.237873 -0.0960962 0.0479903 -0.237873 -0.104611 0.042365 -0.238073 -0.117681 0.0268495 -0.237873 -0.117854 0.0269497 -0.238073 -0.121943 0.017618 -0.238073 -0.124436 0.00776051 -0.237873 -0.122132 0.0176847 -0.237873 -0.124634 0.00779145 -0.241673 -0.0466027 0.0168353 -0.241673 -0.107192 0.0180932 -0.241673 -0.106916 0.0150586 -0.241673 -0.108578 0.0150669 -0.241673 -0.111682 -0.00199278 -0.241673 -0.110486 -0.0107546 -0.241673 -0.107579 -0.0188402 -0.241673 -0.10458 -0.0192912 -0.241673 -0.105921 -0.0187341 -0.241673 -0.0985171 -0.0311898 -0.241673 -0.103 -0.0262583 -0.241673 -0.0984034 -0.0308924 -0.241673 -0.0985615 -0.0255221 -0.241673 -0.100712 -0.0238589 -0.241673 -0.0714909 -0.0316653 -0.241673 -0.0772942 -0.0309493 -0.241673 -0.0641637 -0.0306348 -0.241673 -0.0666929 -0.031524 -0.241673 -0.0922607 -0.0314624 -0.241673 -0.0979545 -0.0317075 -0.241673 -0.0756886 -0.031665 -0.241673 -0.0816671 -0.0332161 -0.241673 -0.0820076 -0.0349407 -0.241673 -0.0814205 -0.0368993 -0.241673 -0.0731953 -0.0334732 -0.241673 -0.0737674 -0.0358911 -0.241673 -0.0759845 -0.0381856 -0.241673 -0.0779431 -0.0387727 -0.241673 -0.0799328 -0.0383019 -0.241673 -0.0731359 -0.0423469 -0.241673 -0.0698994 -0.0404589 -0.241673 -0.064422 -0.0420902 -0.241673 -0.0638164 -0.0420039 -0.241673 -0.0635576 -0.0326827 -0.241673 -0.0638982 -0.0344073 -0.241673 -0.063311 -0.0363659 -0.241673 -0.0618233 -0.0377685 -0.241673 -0.0598336 -0.0382393 -0.241673 -0.057875 -0.0376522 -0.241673 -0.0398726 -0.0291683 -0.241673 -0.0403925 -0.0127187 -0.241673 -0.0393017 -0.0108992 -0.241673 -0.0382572 -0.0126558 -0.241673 -0.0363061 -0.0135256 -0.241673 -0.037814 -0.0123018 -0.241673 -0.0343891 -0.0172236 -0.241673 -0.0314223 -0.0165969 -0.241673 -0.0351754 -0.00494912 -0.241673 -0.0405888 -0.0048551 -0.241673 -0.0335698 -0.00566488 -0.241673 -0.0358243 -0.0127726 -0.241673 -0.0324631 -0.0106977 -0.241673 -0.0289737 -0.00823015 -0.241673 -0.0319923 -0.00870799 -0.241673 -0.0343992 0.00592402 -0.241673 -0.0329966 0.00741177 -0.241673 -0.0408805 0.00504927 -0.241673 -0.0363577 0.0053369 -0.241673 -0.0384932 -0.00580991 -0.241673 -0.0424941 0.0133941 -0.241673 -0.0357088 0.0131604 -0.241673 -0.037466 0.0131086 -0.241673 -0.0354196 0.0177612 -0.241673 -0.0373366 0.0214592 -0.241673 -0.0430218 0.0310323 -0.241673 -0.0611755 0.0371697 -0.241673 -0.0668642 0.040817 -0.241673 -0.0963801 -0.0293911 -0.241673 -0.0922828 -0.0307121 -0.241673 -0.0941257 -0.0222834 -0.241673 -0.0979576 -0.026348 -0.241673 -0.0974868 -0.0243583 -0.241673 -0.0930174 -0.0300551 -0.241673 -0.0914567 -0.0292461 -0.241673 -0.0904016 -0.02784 -0.241673 -0.10341 -0.0147634 -0.241673 -0.102304 -0.0150654 -0.241673 -0.104008 -0.0168733 -0.241673 -0.106887 -0.01289 -0.241673 -0.107605 -0.0187857 -0.241673 -0.107474 -0.0109314 -0.241673 -0.110456 -0.0108727 -0.241673 -0.0999239 -0.0143519 -0.241673 -0.100019 -0.00899725 -0.241673 -0.104518 -0.00699171 -0.241673 -0.100672 0.0110371 -0.241673 -0.10309 0.0116092 -0.241673 -0.104176 0.0112426 -0.241673 -0.106134 0.0106555 -0.241673 -0.103334 0.0199194 -0.241673 -0.104825 0.00341917 -0.241673 -0.106564 0.00311445 -0.241673 -0.0994113 0.00332516 -0.241673 -0.101507 0.00427997 -0.241673 -0.100452 0.00568604 -0.241673 -0.0929141 0.02023 -0.241673 -0.091859 0.021636 -0.241673 -0.0876003 0.0226324 -0.241673 -0.0940069 0.0278186 -0.241673 -0.100127 0.0276383 -0.241673 -0.0999693 0.0222681 -0.241673 -0.0989736 0.0214265 -0.241673 -0.072236 0.038866 -0.241673 -0.0781768 0.0362385 -0.241673 -0.0758285 0.0340785 -0.241673 -0.0761019 0.0328774 -0.241673 -0.0662327 0.0343612 -0.241673 -0.0879692 0.0351557 -0.241673 -0.0988031 0.0293892 -0.241673 -0.100954 0.0206329 -0.241673 -0.0978375 0.0200849 -0.241673 -0.0967286 0.0183563 -0.241673 -0.0962319 0.0193692 -0.241673 -0.083557 0.0309432 -0.241673 -0.0877585 0.0280027 -0.241673 -0.082421 0.0296016 -0.241673 -0.075115 0.0316985 -0.241673 -0.0774976 0.0297467 -0.241673 -0.0790582 0.0289376 -0.241673 -0.0659099 0.0286463 -0.241673 -0.0668048 0.0319433 -0.241673 -0.0598659 0.0299333 -0.241673 -0.0618244 0.0293462 -0.241673 -0.0505191 0.0338873 -0.241673 -0.0502224 0.0359465 -0.241673 -0.0546055 0.0346942 -0.241673 -0.0541764 0.0361511 -0.241673 -0.0584339 0.0351124 -0.241673 -0.065889 0.0331782 -0.241673 -0.0661206 0.0357993 -0.241673 -0.0420424 0.024818 -0.241673 -0.042383 0.0230934 -0.241673 -0.0434381 0.0216874 -0.241673 -0.0538075 0.0236278 -0.241673 -0.0441173 0.0281792 -0.241673 -0.046107 0.02865 -0.241673 -0.0494682 0.0265752 -0.241673 -0.0508787 0.0259636 -0.241673 -0.0486022 0.0301894 -0.241673 -0.0480656 0.0280629 -0.241673 -0.046967 0.0292043 -0.241673 -0.0415967 0.0293625 -0.241673 -0.0414385 0.0239922 -0.241673 -0.0452429 -0.0293265 -0.241673 -0.0435414 -0.0285977 -0.241673 -0.0466082 -0.0214131 -0.241673 -0.0480108 -0.0229009 -0.241673 -0.0523998 -0.0241623 -0.241673 -0.0484816 -0.0248906 -0.241673 -0.0402727 -0.0300084 -0.241673 -0.0419807 -0.0277887 -0.241673 -0.0409256 -0.0263826 -0.241673 -0.0426599 -0.0212968 -0.241673 -0.0432715 -0.0198863 -0.241673 -0.0414636 -0.0215907 -0.241673 -0.0400308 -0.023798 -0.241673 -0.0619616 0.0287626 -0.241673 -0.0618034 0.0233923 -0.241673 -0.0960151 0.0159763 -0.241673 -0.110587 -0.00691699 -0.241673 -0.104844 -0.00659342 -0.241673 -0.106273 -0.00678992 -0.241673 -0.107261 -0.00602129 -0.241673 -0.109069 -0.00431686 -0.241673 -0.102464 -0.00587996 -0.241673 -0.0991195 -0.00657921 -0.241673 -0.100187 -0.00165417 -0.241673 -0.102708 0.00243028 -0.241673 -0.105126 0.00300241 -0.241673 -0.110878 0.00298738 -0.241673 -0.0439849 -0.0175062 -0.241673 -0.0456073 -0.0169575 -0.241673 -0.042289 -0.0137019 -0.241673 -0.0575791 -0.0311316 -0.241673 -0.0564131 -0.0306888 -0.241673 -0.0591847 -0.0304158 -0.241673 -0.0558409 -0.0282709 -0.241673 -0.0602375 -0.0297682 -0.241673 -0.0603957 -0.0243979 -0.241673 -0.0564724 -0.0361644 -0.241673 -0.0556996 -0.0330688 -0.241673 -0.0480958 -0.0362487 -0.241673 -0.041197 -0.0309191 -0.241673 -0.0473894 -0.032824 -0.241673 -0.0452208 -0.0300768 -0.241673 -0.0468172 -0.0304061 -0.241673 -0.0469706 -0.0293358 -0.241673 -0.0960842 -0.0228705 -0.241673 -0.0926471 -0.0183431 -0.241673 -0.0790513 -0.031001 -0.241673 -0.0860123 -0.0312784 -0.241673 -0.080612 -0.0318101 -0.241673 -0.044302 0.0150986 -0.241673 -0.0458428 -0.00896158 -0.241673 -0.0404725 -0.00880339 -0.241673 -0.0956981 -0.0166285 -0.241673 -0.0928826 -0.0103472 -0.241673 -0.0990032 -0.0105275 -0.241673 -0.0929989 -0.00639892 -0.241673 -0.100698 0.00936921 -0.241673 -0.0536014 0.0166291 -0.241673 -0.0462508 0.00489108 -0.241673 -0.0459591 -0.00501329 -0.241673 -0.0446496 -0.020826 -0.241673 -0.0906482 -0.0241568 -0.241673 -0.0863987 -0.0181591 -0.241673 -0.0867505 -0.00621487 -0.241673 -0.0870423 0.0036895 -0.241673 -0.0932907 0.00350545 -0.241673 -0.0936425 0.0154496 -0.241673 -0.0944748 0.0194209 -0.241673 -0.0517565 -0.0257495 -0.241673 -0.052606 -0.0171636 -0.241673 -0.0528415 -0.00916773 -0.241673 -0.0529578 -0.00521945 -0.241673 -0.0609537 -0.00545498 -0.241673 -0.0532495 0.00468492 -0.241673 -0.0615973 0.0163936 -0.241673 -0.0574846 0.0275267 -0.241673 -0.0641858 -0.0298845 -0.241673 -0.064344 -0.0245142 -0.241673 -0.0606019 -0.0173992 -0.241673 -0.0608374 -0.00940327 -0.241673 -0.064902 -0.00557128 -0.241673 -0.0612454 0.00444939 -0.241673 -0.0653019 0.0312196 -0.241673 -0.0860344 -0.0305281 -0.241673 -0.0861925 -0.0251578 -0.241673 -0.0645501 -0.0175155 -0.241673 -0.0647857 -0.00951957 -0.241673 -0.0866342 -0.0101632 -0.241673 -0.0651937 0.00433309 -0.241673 -0.0655456 0.0162773 -0.241673 -0.0873941 0.0156337 -0.241673 -0.0657517 0.023276 -0.229365 -0.0728181 -0.0666032 -0.229692 -0.0587538 -0.0647832 -0.23002 -0.0589095 -0.0638968 -0.229938 -0.0582828 -0.064012 -0.229919 -0.0582196 -0.0640534 -0.229497 -0.0579409 -0.0651819 -0.229803 -0.0579677 -0.0643298 -0.229692 -0.0774585 -0.0653342 -0.23002 -0.0773553 -0.0644401 -0.229986 -0.0777665 -0.0644867 -0.23002 -0.0711987 -0.0648523 -0.229365 -0.0680597 -0.0666349 -0.229365 -0.0585981 -0.0656696 -0.228993 -0.0632503 -0.0669225 -0.229365 -0.0633115 -0.0663232 -0.228993 -0.068042 -0.0672371 -0.228993 -0.0728439 -0.0672051 -0.228414 -0.0728612 -0.0676106 -0.228414 -0.0632091 -0.0673263 -0.228414 -0.0776775 -0.0672299 -0.22772 -0.0728674 -0.0677536 -0.228414 -0.06803 -0.0676428 -0.22772 -0.0631946 -0.0674687 -0.22772 -0.0583988 -0.0668037 -0.224573 -0.0644424 -0.0629672 -0.224773 -0.0644602 -0.062768 -0.224773 -0.0718807 -0.0629866 -0.224773 -0.078967 -0.0623657 -0.224573 -0.0793042 -0.062518 -0.224773 -0.0792744 -0.0623202 -0.224773 -0.0560425 -0.066755 -0.224773 -0.0639974 -0.0679473 -0.224573 -0.0720317 -0.0679843 -0.224773 -0.0720378 -0.0681842 -0.224573 -0.0800193 -0.0672644 -0.224573 -0.0818757 -0.0639646 -0.224773 -0.0822327 -0.0645038 -0.224773 -0.0806118 -0.062471 -0.224573 -0.0811722 -0.0630261 -0.224573 -0.0815382 -0.0633949 -0.224573 -0.082035 -0.0645336 -0.224773 -0.082082 -0.0658412 -0.224573 -0.081158 -0.0667677 -0.224573 -0.0816547 -0.0662284 -0.224573 -0.0550968 -0.0623249 -0.224773 -0.0542588 -0.063041 -0.224773 -0.0593505 -0.0613867 -0.224773 -0.0681878 -0.0622883 -0.224773 -0.0782696 -0.0620288 -0.222889 -0.0806926 -0.0670587 -0.22288 -0.0809247 -0.066932 -0.224573 -0.0820504 -0.0651243 -0.222736 -0.0820296 -0.0652829 -0.224573 -0.0818958 -0.0657682 -0.222663 -0.0820349 -0.0645333 -0.222721 -0.0820504 -0.0651243 -0.224573 -0.0805387 -0.0626572 -0.222503 -0.0811724 -0.0630263 -0.224573 -0.0560356 -0.061874 -0.222444 -0.0561481 -0.0618506 -0.222498 -0.0552396 -0.0622209 -0.222575 -0.0545871 -0.0628747 -0.224573 -0.0544374 -0.063131 -0.222602 -0.0544394 -0.063127 -0.222663 -0.0542328 -0.0637131 -0.222899 -0.0560838 -0.0665594 -0.224573 -0.0640152 -0.0677481 -0.224573 -0.0718867 -0.0631865 -0.222426 -0.0718867 -0.0631865 -0.224573 -0.0570771 -0.0618633 -0.220853 -0.0801483 -0.0649647 -0.220795 -0.0798752 -0.0648444 -0.221326 -0.0814284 -0.0643437 -0.221035 -0.080279 -0.0633305 -0.220992 -0.0794154 -0.0632559 -0.220826 -0.080209 -0.0637187 -0.220978 -0.0809004 -0.0647909 -0.221131 -0.0810169 -0.0652507 -0.220951 -0.0808097 -0.064058 -0.220833 -0.0805954 -0.0643899 -0.220725 -0.0801175 -0.0641283 -0.220683 -0.0795408 -0.0640887 -0.221652 -0.0814843 -0.0657021 -0.221283 -0.0813202 -0.0651491 -0.222899 -0.0800193 -0.0672644 -0.22215 -0.0811675 -0.0630683 -0.222448 -0.0803337 -0.0625872 -0.222426 -0.0793042 -0.062518 -0.222606 -0.0818757 -0.0639647 -0.222575 -0.0817307 -0.0636749 -0.222519 -0.0813274 -0.0631633 -0.222827 -0.0816156 -0.066285 -0.222469 -0.0819508 -0.0655296 -0.222363 -0.0820221 -0.0646458 -0.222623 -0.0819377 -0.0641296 -0.222287 -0.0814595 -0.0663461 -0.222182 -0.08185 -0.065605 -0.222055 -0.0819453 -0.0647706 -0.221904 -0.0816932 -0.065664 -0.221919 -0.0817203 -0.0639388 -0.221602 -0.0816106 -0.064128 -0.221451 -0.0811089 -0.0634488 -0.221695 -0.0803282 -0.0627629 -0.221335 -0.0803196 -0.0630026 -0.221618 -0.0793336 -0.0627135 -0.222252 -0.0817573 -0.0637864 -0.221791 -0.0811683 -0.063223 -0.222077 -0.0803082 -0.0626209 -0.22123 -0.0801266 -0.0660144 -0.221469 -0.080368 -0.0664131 -0.221626 -0.0799375 -0.0667215 -0.222206 -0.079998 -0.0671229 -0.221019 -0.0803996 -0.0653852 -0.221391 -0.0807292 -0.0661109 -0.221564 -0.0809494 -0.0662127 -0.22186 -0.0806252 -0.0667232 -0.221777 -0.0811504 -0.0662881 -0.222357 -0.0808186 -0.0669017 -0.222559 -0.0815571 -0.0663289 -0.221496 -0.0815872 -0.0650303 -0.22176 -0.0817994 -0.0649013 -0.221161 -0.0809866 -0.0637347 -0.221889 -0.0561502 -0.0662458 -0.220806 -0.0562914 -0.0641675 -0.220854 -0.0560892 -0.0642569 -0.221469 -0.0557861 -0.065689 -0.221391 -0.0554432 -0.0653661 -0.221183 -0.0559028 -0.0651429 -0.221274 -0.0552423 -0.0649497 -0.221098 -0.0558075 -0.0648829 -0.221496 -0.0546503 -0.0642359 -0.220981 -0.0558443 -0.0645621 -0.221131 -0.0552067 -0.0644898 -0.221326 -0.0548494 -0.0635603 -0.221035 -0.0560559 -0.0626171 -0.220978 -0.0553501 -0.064038 -0.220878 -0.0560196 -0.0643105 -0.220951 -0.0554836 -0.0633121 -0.220833 -0.055678 -0.063656 -0.220826 -0.0561029 -0.0630088 -0.220725 -0.0561703 -0.0634231 -0.220691 -0.0567623 -0.0633519 -0.222252 -0.054554 -0.0629845 -0.222515 -0.0550615 -0.0623531 -0.222049 -0.0570686 -0.0619034 -0.222363 -0.0542389 -0.0638263 -0.222469 -0.0542577 -0.0647132 -0.222705 -0.0541815 -0.0641406 -0.222751 -0.0542162 -0.0646241 -0.2228 -0.0543806 -0.0651707 -0.222808 -0.0544215 -0.0652595 -0.222559 -0.0546039 -0.0655351 -0.222827 -0.0545481 -0.0654878 -0.222877 -0.0551436 -0.0661336 -0.222357 -0.0553076 -0.0661504 -0.222381 -0.0561 -0.0664829 -0.222206 -0.0561135 -0.0664193 -0.22186 -0.0555111 -0.0659835 -0.221904 -0.054507 -0.0648627 -0.222055 -0.0543081 -0.0639554 -0.221602 -0.0546803 -0.0633342 -0.221791 -0.0551746 -0.0624574 -0.221695 -0.0560401 -0.0620475 -0.222077 -0.0560684 -0.061907 -0.22215 -0.0551845 -0.062303 -0.221919 -0.0545819 -0.0631388 -0.222182 -0.0543539 -0.0647945 -0.222287 -0.0547003 -0.065558 -0.221241 -0.0561164 -0.0653515 -0.221777 -0.0550124 -0.0655183 -0.221652 -0.0547133 -0.064913 -0.22176 -0.0544461 -0.0640946 -0.221161 -0.0553259 -0.0629789 -0.221451 -0.0552206 -0.0626863 -0.221335 -0.0560346 -0.0622874 -0.22129 -0.0569906 -0.0622724 -0.221626 -0.0640641 -0.0672012 -0.221889 -0.0799716 -0.0669475 -0.221497 -0.0799146 -0.0665694 -0.221626 -0.0720151 -0.0674355 -0.221254 -0.0641177 -0.0666012 -0.221254 -0.0638447 -0.0665763 -0.222899 -0.0720317 -0.0679843 -0.222382 -0.0800077 -0.0671871 -0.222206 -0.0720274 -0.0678412 -0.221626 -0.0561975 -0.0660222 -0.222206 -0.064028 -0.0676056 -0.222899 -0.0640152 -0.0677481 -0.220781 -0.0719577 -0.0655339 -0.220691 -0.0719327 -0.0647074 -0.220781 -0.0565911 -0.064161 -0.220691 -0.064307 -0.0644827 -0.220691 -0.0795309 -0.0640226 -0.220778 -0.079477 -0.0636648 -0.221618 -0.0570362 -0.0620567 -0.220992 -0.0569227 -0.0625933 -0.220992 -0.064376 -0.0637105 -0.220778 -0.0568371 -0.062998 -0.222426 -0.0644424 -0.0629672 -0.222426 -0.0570771 -0.0618633 -0.220992 -0.0719092 -0.0639324 -0.22129 -0.0793665 -0.0629315 -0.221618 -0.0718927 -0.0633841 -0.221618 -0.0644248 -0.0631641 -0.222049 -0.0793103 -0.0625585 -0.221018 -0.0797509 -0.0654831 -0.220781 -0.0796541 -0.0648403 -0.220781 -0.0722271 -0.0655252 -0.220939 -0.0803286 -0.0651747 -0.221159 -0.0803309 -0.065785 -0.221056 -0.0804066 -0.065488 -0.221254 -0.0563221 -0.0654328 -0.221018 -0.0564566 -0.0647969 -0.220781 -0.0639657 -0.0652819 -0.220781 -0.0642334 -0.0653064 -0.221254 -0.0719969 -0.0668333 -0.221254 -0.0722718 -0.0668245 -0.221254 -0.0798478 -0.0661258 -0.224573 -0.0544035 -0.0652216 -0.224573 -0.0560838 -0.0665594 -0.224573 -0.0541815 -0.0641406 -0.224573 -0.0550857 -0.0660889 -0.224773 -0.0549611 -0.0662454 -0.227999 -0.0800387 -0.0648176 -0.224973 -0.0800387 -0.0648176 -0.227753 -0.0788126 -0.0669753 -0.227841 -0.0796299 -0.0661554 -0.224773 -0.0802386 -0.0648235 -0.224973 -0.0797092 -0.0660214 -0.224973 -0.0788652 -0.0669409 -0.224973 -0.077694 -0.0673721 -0.224773 -0.0777169 -0.0675708 -0.224773 -0.0793171 -0.06264 -0.224773 -0.0800156 -0.0636314 -0.224973 -0.0798313 -0.0637092 -0.224773 -0.0770628 -0.0619084 -0.224973 -0.0791818 -0.0627873 -0.224973 -0.0564385 -0.0631113 -0.224973 -0.0593159 -0.0615836 -0.224773 -0.0578809 -0.0615162 -0.224773 -0.0574227 -0.0617311 -0.224773 -0.056673 -0.0623631 -0.224973 -0.0562473 -0.0637352 -0.224773 -0.0561798 -0.0651701 -0.224773 -0.0570268 -0.0663781 -0.224973 -0.0566215 -0.0656162 -0.224773 -0.0542221 -0.0653058 -0.224773 -0.0539816 -0.0641348 -0.224773 -0.0549731 -0.0621677 -0.224773 -0.0560503 -0.0637006 -0.224773 -0.0559902 -0.0616792 -0.224773 -0.0571185 -0.0616676 -0.224773 -0.0583642 -0.0670007 -0.224773 -0.0680199 -0.0679858 -0.224773 -0.0800491 -0.0674622 -0.224773 -0.0789766 -0.067107 -0.224773 -0.0812827 -0.0669241 -0.224773 -0.0798843 -0.0661182 -0.224773 -0.0816946 -0.0632702 -0.224973 -0.0681819 -0.0624882 -0.228376 -0.0652132 -0.0623292 -0.224973 -0.0770858 -0.0621071 -0.224973 -0.0680258 -0.0677859 -0.224973 -0.0583988 -0.0668037 -0.227734 -0.0576658 -0.0665609 -0.224973 -0.0571553 -0.0662248 -0.227819 -0.0566631 -0.0656795 -0.224973 -0.0563677 -0.0651016 -0.228046 -0.0562475 -0.0637343 -0.224973 -0.0562144 -0.0643868 -0.224973 -0.0572402 -0.0620943 -0.224973 -0.0568263 -0.0624916 -0.228348 -0.0582298 -0.0616191 -0.224973 -0.0579494 -0.0617041 -0.228268 -0.05724 -0.0620945 -0.228275 -0.0790689 -0.0626894 -0.224973 -0.0782079 -0.062219 -0.228168 -0.0797188 -0.0634752 -0.228376 -0.0593159 -0.0615836 -0.228376 -0.0681819 -0.0624882 -0.228376 -0.0711548 -0.0625042 -0.228376 -0.0770858 -0.0621071 -0.229184 -0.0711585 -0.0627019 -0.229511 -0.0771338 -0.0625224 -0.230023 -0.0591153 -0.0627255 -0.230111 -0.0650952 -0.0638461 -0.229809 -0.0651553 -0.0630731 -0.229184 -0.0651978 -0.0625263 -0.229809 -0.0711688 -0.0632503 -0.229809 -0.0771714 -0.0628484 -0.230111 -0.0711833 -0.0640255 -0.23002 -0.0650311 -0.0646706 -0.230111 -0.0590526 -0.0630823 -0.23002 -0.0681123 -0.0648357 -0.22772 -0.0680258 -0.0677859 -0.229255 -0.0575519 -0.0655268 -0.22969 -0.0578592 -0.0646257 -0.229577 -0.0572457 -0.0644758 -0.229463 -0.0580027 -0.0652867 -0.230009 -0.0586747 -0.0638861 -0.229212 -0.056682 -0.0642416 -0.228949 -0.0564734 -0.0641077 -0.22877 -0.0565624 -0.0649675 -0.228869 -0.0571272 -0.0656936 -0.228359 -0.0568172 -0.0657441 -0.228087 -0.0567203 -0.0657246 -0.229639 -0.0578458 -0.0647655 -0.229023 -0.0567699 -0.0650106 -0.229401 -0.0572989 -0.065029 -0.228493 -0.0564074 -0.0649049 -0.228168 -0.0566065 -0.0627951 -0.228251 -0.057103 -0.0622076 -0.228491 -0.0565771 -0.062906 -0.229967 -0.0582808 -0.0627644 -0.229809 -0.0591867 -0.0623186 -0.229511 -0.0592435 -0.0619954 -0.229184 -0.0592816 -0.0617784 -0.229458 -0.0581881 -0.0620461 -0.229098 -0.0581855 -0.0618063 -0.228752 -0.0593088 -0.061624 -0.228109 -0.0563835 -0.0632436 -0.228622 -0.0572496 -0.0621322 -0.229416 -0.0568913 -0.0634709 -0.229821 -0.057582 -0.0631299 -0.229611 -0.0574133 -0.0628025 -0.229759 -0.0582204 -0.0623747 -0.229321 -0.0572984 -0.0625139 -0.228981 -0.0572448 -0.0622869 -0.228717 -0.0582091 -0.0616649 -0.228275 -0.057302 -0.0620481 -0.228238 -0.0584124 -0.0667267 -0.22827 -0.0575149 -0.0663845 -0.228766 -0.0577122 -0.0662109 -0.228414 -0.0584236 -0.0666627 -0.22873 -0.0584543 -0.0664882 -0.229157 -0.0579767 -0.0659072 -0.229399 -0.0582164 -0.0655072 -0.228993 -0.0584938 -0.0662629 -0.227747 -0.0574084 -0.0664124 -0.22795 -0.0562275 -0.0645202 -0.228206 -0.0563086 -0.0648271 -0.228346 -0.0562575 -0.0638471 -0.228653 -0.056331 -0.0639735 -0.228823 -0.0566101 -0.0630592 -0.22914 -0.0567149 -0.0632509 -0.229764 -0.0574072 -0.0639306 -0.229939 -0.0577878 -0.0634667 -0.230069 -0.0583622 -0.063176 -0.22873 -0.0776572 -0.0670539 -0.227748 -0.0787253 -0.0670285 -0.22772 -0.077694 -0.0673721 -0.229098 -0.0782015 -0.0623961 -0.229885 -0.0781235 -0.0647194 -0.228993 -0.0776309 -0.0668266 -0.229365 -0.0775618 -0.0662282 -0.229376 -0.0777908 -0.0661711 -0.229445 -0.0781306 -0.0659381 -0.229255 -0.0786145 -0.0661473 -0.229463 -0.0781786 -0.0658811 -0.229578 -0.0783413 -0.0655439 -0.229577 -0.0789821 -0.0651154 -0.229401 -0.0788965 -0.0656648 -0.22969 -0.0783608 -0.0652291 -0.229764 -0.0788527 -0.0645619 -0.229416 -0.0793948 -0.0641331 -0.229821 -0.0787257 -0.0637528 -0.230023 -0.0772188 -0.0632588 -0.229741 -0.0783337 -0.0650914 -0.229939 -0.0785004 -0.0640769 -0.229967 -0.0780498 -0.0633469 -0.230069 -0.0779443 -0.0637529 -0.230111 -0.0772604 -0.0636186 -0.228135 -0.0798417 -0.0637341 -0.228256 -0.0792176 -0.0628207 -0.228353 -0.0780603 -0.0621758 -0.228717 -0.0781863 -0.0622535 -0.228752 -0.0770905 -0.0621478 -0.229184 -0.0771085 -0.0623035 -0.228087 -0.079433 -0.0663939 -0.227863 -0.0797392 -0.0659657 -0.228206 -0.0798971 -0.0655213 -0.228046 -0.0800221 -0.0644334 -0.228346 -0.0800055 -0.0645453 -0.22798 -0.0800295 -0.064974 -0.227924 -0.0799466 -0.0654366 -0.227819 -0.0794927 -0.0663522 -0.229321 -0.0790451 -0.0631546 -0.22914 -0.0795838 -0.0639239 -0.228359 -0.079335 -0.0664076 -0.228766 -0.078414 -0.0668208 -0.228622 -0.0791163 -0.0627764 -0.228981 -0.0791119 -0.0629311 -0.228491 -0.0797416 -0.0635876 -0.228823 -0.0796996 -0.0637386 -0.228653 -0.0799247 -0.0646673 -0.228493 -0.0797939 -0.0655931 -0.22827 -0.0786007 -0.0670059 -0.228238 -0.077685 -0.0672944 -0.229157 -0.078168 -0.0665021 -0.228869 -0.0790286 -0.0663388 -0.229023 -0.0794258 -0.0656774 -0.228771 -0.0796355 -0.0656466 -0.229212 -0.0795586 -0.0649145 -0.228949 -0.0797747 -0.0647929 -0.229611 -0.0789133 -0.063436 -0.229759 -0.0781331 -0.0629614 -0.229458 -0.0781848 -0.0626352 -0.224573 -0.0404232 -0.0557669 -0.222426 -0.0471812 -0.0588967 -0.224573 -0.0454273 -0.0633648 -0.224573 -0.0464834 -0.0635241 -0.222736 -0.0481589 -0.0626539 -0.222663 -0.0485384 -0.0620074 -0.222503 -0.0485449 -0.060271 -0.224573 -0.0485976 -0.0604235 -0.222606 -0.0486848 -0.0614354 -0.222623 -0.048656 -0.0616092 -0.222899 -0.0454273 -0.0633648 -0.224573 -0.0381499 -0.0599944 -0.224773 -0.0286246 -0.0472745 -0.224773 -0.0405179 -0.0555908 -0.224573 -0.0250511 -0.0507865 -0.222899 -0.0250511 -0.0507865 -0.224573 -0.0242562 -0.0489307 -0.224573 -0.024449 -0.0499462 -0.224773 -0.0240563 -0.0489248 -0.224973 -0.0462778 -0.0617458 -0.228061 -0.0468917 -0.0607994 -0.227962 -0.0464911 -0.0615071 -0.22784 -0.0456369 -0.0622137 -0.227924 -0.0462782 -0.0617455 -0.224773 -0.0446371 -0.0627047 -0.224973 -0.0446214 -0.0625053 -0.224973 -0.0453259 -0.0623511 -0.224773 -0.0459418 -0.0622685 -0.224973 -0.0467163 -0.0611732 -0.224773 -0.0472613 -0.0599474 -0.224973 -0.0458344 -0.0620997 -0.228376 -0.0454654 -0.0574317 -0.228376 -0.0401305 -0.0548101 -0.224973 -0.0375639 -0.0533098 -0.228376 -0.0375639 -0.0533098 -0.224973 -0.0433596 -0.0622954 -0.224773 -0.0432801 -0.0624789 -0.224773 -0.0346748 -0.0579899 -0.224973 -0.0269337 -0.0521556 -0.227734 -0.0264203 -0.0515789 -0.224973 -0.0261462 -0.0510324 -0.224973 -0.0259883 -0.0502385 -0.224973 -0.0270822 -0.0479777 -0.22795 -0.0261951 -0.0490924 -0.228376 -0.0303379 -0.0480934 -0.224973 -0.0277279 -0.0476349 -0.228109 -0.0269685 -0.0480648 -0.224973 -0.0454654 -0.0574317 -0.228362 -0.0461045 -0.057824 -0.224973 -0.0463242 -0.0580283 -0.228349 -0.0463376 -0.0580424 -0.228282 -0.0468601 -0.0588478 -0.224973 -0.0468853 -0.0589108 -0.224973 -0.0470614 -0.0599415 -0.230111 -0.0448609 -0.058828 -0.23002 -0.0445323 -0.0595869 -0.228376 -0.0350724 -0.0516877 -0.229184 -0.0400349 -0.0549831 -0.229809 -0.0346503 -0.0523031 -0.228752 -0.0454491 -0.0574693 -0.229809 -0.0397695 -0.0554632 -0.230023 -0.0295933 -0.048982 -0.229184 -0.0349605 -0.0518507 -0.230111 -0.0393945 -0.0561418 -0.229809 -0.0451689 -0.0581165 -0.23002 -0.0288295 -0.0498934 -0.23002 -0.033744 -0.0536244 -0.230111 -0.0342117 -0.0529425 -0.224973 -0.0347799 -0.0578197 -0.228168 -0.0273858 -0.0477879 -0.228622 -0.0282742 -0.0475353 -0.229803 -0.0277973 -0.0497976 -0.229255 -0.0268387 -0.0506263 -0.229497 -0.027348 -0.0505221 -0.229939 -0.0280731 -0.0489602 -0.229919 -0.0281536 -0.0496842 -0.230009 -0.0286314 -0.0497668 -0.230111 -0.0293606 -0.0492596 -0.229023 -0.0264196 -0.0497882 -0.22877 -0.0262614 -0.0496472 -0.228653 -0.0265581 -0.0486707 -0.228493 -0.0261585 -0.0495154 -0.227747 -0.0262716 -0.0513215 -0.229463 -0.0273492 -0.0506438 -0.229157 -0.0270164 -0.0511681 -0.228766 -0.0266356 -0.0512989 -0.22969 -0.0275554 -0.0499995 -0.229401 -0.0268686 -0.0500687 -0.229577 -0.027099 -0.049563 -0.228869 -0.0263875 -0.0505583 -0.228359 -0.0260938 -0.0504472 -0.229809 -0.0298586 -0.0486654 -0.229511 -0.0300694 -0.0484138 -0.229458 -0.02913 -0.04793 -0.229184 -0.0302109 -0.0482449 -0.228752 -0.0303116 -0.0481248 -0.229098 -0.0292476 -0.0477211 -0.228717 -0.0293388 -0.0476104 -0.228251 -0.0281096 -0.0475273 -0.228491 -0.0273049 -0.0478692 -0.228981 -0.0281927 -0.0476669 -0.229321 -0.0281256 -0.0478903 -0.22914 -0.0272518 -0.0482368 -0.229416 -0.0272946 -0.0485155 -0.229611 -0.0280809 -0.0481977 -0.229759 -0.0289937 -0.0482308 -0.228348 -0.0293797 -0.047581 -0.228268 -0.0282847 -0.0474979 -0.22827 -0.0263778 -0.0513506 -0.228993 -0.0272864 -0.0517347 -0.227819 -0.0259926 -0.0503141 -0.228087 -0.0260196 -0.0503818 -0.228206 -0.0261118 -0.0493987 -0.228046 -0.0266053 -0.0484217 -0.228346 -0.0265576 -0.0485244 -0.228823 -0.027257 -0.0480184 -0.228949 -0.0266143 -0.048858 -0.229212 -0.0267279 -0.0490784 -0.229764 -0.0275116 -0.0491716 -0.229821 -0.0280632 -0.0485656 -0.229967 -0.0288512 -0.0485984 -0.230069 -0.0287159 -0.0489956 -0.228766 -0.0442588 -0.062178 -0.228993 -0.0435778 -0.0617915 -0.229885 -0.0450579 -0.0602129 -0.229986 -0.0448651 -0.0598328 -0.230069 -0.045386 -0.0592862 -0.229445 -0.0444547 -0.0612718 -0.229463 -0.0445248 -0.0612465 -0.229578 -0.0448343 -0.0610358 -0.229401 -0.0452547 -0.0614181 -0.229577 -0.0456035 -0.0609851 -0.229416 -0.046452 -0.0603408 -0.229611 -0.0463837 -0.0594963 -0.229967 -0.0456804 -0.0589874 -0.22969 -0.0450086 -0.060773 -0.229764 -0.0457683 -0.060441 -0.229741 -0.045054 -0.0606401 -0.229939 -0.0457055 -0.0598449 -0.229821 -0.0460627 -0.0596769 -0.230023 -0.0450048 -0.0584956 -0.229184 -0.0453869 -0.0576131 -0.228717 -0.0463453 -0.0581087 -0.228167 -0.0470614 -0.0599415 -0.228491 -0.0470251 -0.0600417 -0.228346 -0.0467748 -0.0610031 -0.228119 -0.0470177 -0.0603486 -0.22781 -0.0453263 -0.062351 -0.228087 -0.0453548 -0.0623177 -0.227748 -0.0444246 -0.0625135 -0.228238 -0.0433907 -0.0622236 -0.228493 -0.0460677 -0.0618047 -0.228653 -0.0466439 -0.0610683 -0.22914 -0.0467204 -0.0602541 -0.229098 -0.0462872 -0.0582398 -0.229458 -0.0461531 -0.0584386 -0.229511 -0.0452993 -0.0578153 -0.228622 -0.0468892 -0.0590266 -0.228981 -0.0468081 -0.0591584 -0.228823 -0.0469133 -0.0601515 -0.228206 -0.046193 -0.0617941 -0.228359 -0.0452631 -0.0622806 -0.22827 -0.0443279 -0.0624316 -0.229157 -0.0442051 -0.0617789 -0.229376 -0.044044 -0.0613038 -0.229255 -0.0447692 -0.061695 -0.228869 -0.0450321 -0.0620679 -0.229023 -0.0457067 -0.0616937 -0.228771 -0.0459037 -0.0617718 -0.229212 -0.0462032 -0.0610994 -0.228949 -0.0464512 -0.0611021 -0.229321 -0.0466385 -0.0593185 -0.229759 -0.0459452 -0.0586952 -0.229938 -0.0282291 -0.0496799 -0.229399 -0.027424 -0.0509416 -0.229692 -0.0282514 -0.0505832 -0.229639 -0.0274739 -0.050114 -0.229365 -0.0438171 -0.0612387 -0.229692 -0.0441747 -0.0604128 -0.23002 -0.0389945 -0.0568656 -0.23002 -0.0363299 -0.055308 -0.229365 -0.0353847 -0.0568399 -0.229365 -0.0314285 -0.0541958 -0.22772 -0.0433596 -0.0622954 -0.228238 -0.0269839 -0.0520957 -0.228414 -0.0270257 -0.0520459 -0.228993 -0.0310759 -0.0546842 -0.229365 -0.0276733 -0.051273 -0.228993 -0.0350683 -0.0573525 -0.229365 -0.0395214 -0.0591916 -0.228993 -0.0392428 -0.0597257 -0.22873 -0.0434869 -0.0620014 -0.228414 -0.0390551 -0.0600856 -0.228414 -0.034855 -0.0576979 -0.22873 -0.0271395 -0.0519101 -0.228414 -0.0434165 -0.062164 -0.22772 -0.0389889 -0.0602125 -0.22772 -0.0347799 -0.0578197 -0.228414 -0.0308383 -0.0550133 -0.22772 -0.0307545 -0.0551294 -0.22772 -0.0269337 -0.0521556 -0.224573 -0.0282593 -0.0472162 -0.224773 -0.0342009 -0.0516912 -0.224573 -0.0340859 -0.0518548 -0.224573 -0.0471812 -0.0588967 -0.224773 -0.0482102 -0.0593624 -0.224773 -0.0487887 -0.0603646 -0.224573 -0.0480636 -0.0594985 -0.224573 -0.0485449 -0.0602708 -0.224573 -0.0486774 -0.0614886 -0.224573 -0.0482871 -0.0624829 -0.224773 -0.0476041 -0.0633825 -0.224773 -0.0453542 -0.063551 -0.224573 -0.0473616 -0.0632853 -0.224573 -0.0475041 -0.0632093 -0.224773 -0.028393 -0.0470674 -0.224773 -0.0251192 -0.0469035 -0.224573 -0.0313255 -0.0557817 -0.224773 -0.0312104 -0.0559453 -0.22123 -0.0461452 -0.0623359 -0.221469 -0.0461549 -0.0628019 -0.220853 -0.0466888 -0.0614377 -0.220833 -0.0473634 -0.0611634 -0.220795 -0.0465125 -0.0611969 -0.220781 -0.046323 -0.0610829 -0.220683 -0.0466008 -0.0603753 -0.221326 -0.0481079 -0.06154 -0.221161 -0.0480299 -0.0607916 -0.220951 -0.0477149 -0.0609832 -0.221035 -0.0476191 -0.0600878 -0.220826 -0.0473644 -0.060389 -0.221283 -0.0476115 -0.0621833 -0.221131 -0.0472981 -0.0621196 -0.220978 -0.0474271 -0.0616633 -0.220725 -0.0470803 -0.0606979 -0.220691 -0.0466252 -0.0603131 -0.221777 -0.0468949 -0.0630848 -0.221496 -0.0479021 -0.0622139 -0.222889 -0.0461132 -0.0635234 -0.222077 -0.0479993 -0.0594879 -0.222575 -0.0487041 -0.0611119 -0.222519 -0.0486106 -0.0604672 -0.222448 -0.0480382 -0.0594714 -0.22288 -0.0463775 -0.0635297 -0.222827 -0.0472994 -0.0633147 -0.222721 -0.0482563 -0.062527 -0.222469 -0.0479674 -0.0628282 -0.222363 -0.048471 -0.0620984 -0.222252 -0.0486714 -0.0612218 -0.222055 -0.0483422 -0.0621681 -0.221919 -0.0485632 -0.0613352 -0.221602 -0.0483736 -0.0614443 -0.221451 -0.0482787 -0.0606051 -0.221695 -0.0479455 -0.0596208 -0.221618 -0.0471089 -0.0590808 -0.221335 -0.0478182 -0.0598241 -0.222182 -0.0478424 -0.0628431 -0.22215 -0.0485197 -0.060305 -0.221791 -0.048443 -0.0604394 -0.22186 -0.0462226 -0.0631991 -0.221626 -0.0456279 -0.0628537 -0.221019 -0.0466962 -0.0619275 -0.221056 -0.0466509 -0.06202 -0.221391 -0.0466188 -0.0627208 -0.221564 -0.0467586 -0.0629191 -0.222357 -0.0463008 -0.0634503 -0.222206 -0.0454796 -0.0632316 -0.222382 -0.0454558 -0.063292 -0.222559 -0.0472268 -0.0633235 -0.222287 -0.0471337 -0.0632896 -0.221904 -0.047677 -0.0628158 -0.221652 -0.0474771 -0.0627443 -0.22176 -0.0481504 -0.0622084 -0.22129 -0.0470284 -0.059286 -0.220992 -0.0469085 -0.0595914 -0.221618 -0.0339722 -0.0520166 -0.220781 -0.0327353 -0.0537762 -0.220781 -0.0393109 -0.0578353 -0.220781 -0.0266896 -0.048963 -0.220691 -0.0397026 -0.057107 -0.220778 -0.0467574 -0.0599763 -0.220781 -0.0325157 -0.0536211 -0.220992 -0.0400698 -0.0564241 -0.220992 -0.0336567 -0.0524653 -0.220691 -0.0332108 -0.0530996 -0.222426 -0.0340859 -0.0518548 -0.222426 -0.0282593 -0.0472162 -0.221618 -0.0403295 -0.0559411 -0.222426 -0.0404232 -0.0557669 -0.222049 -0.0471662 -0.0589349 -0.221254 -0.045848 -0.062293 -0.221889 -0.0455444 -0.0630665 -0.221497 -0.0456841 -0.0627105 -0.221254 -0.0386952 -0.0589803 -0.221254 -0.0319876 -0.0548397 -0.222206 -0.0382177 -0.0598684 -0.222899 -0.0381499 -0.0599944 -0.221626 -0.0316412 -0.0553325 -0.221889 -0.0252653 -0.0505481 -0.222206 -0.0251467 -0.05068 -0.221626 -0.0384099 -0.0595108 -0.222206 -0.0314078 -0.0556646 -0.222899 -0.0313255 -0.0557817 -0.222877 -0.0244496 -0.0499477 -0.222381 -0.0251033 -0.0507283 -0.221326 -0.0254816 -0.047572 -0.22186 -0.024843 -0.0500014 -0.220806 -0.0264267 -0.0488188 -0.220878 -0.0261198 -0.0488068 -0.221183 -0.0256025 -0.0494693 -0.221274 -0.0251271 -0.0489717 -0.221652 -0.0246873 -0.0486754 -0.221098 -0.02565 -0.0491964 -0.221131 -0.0253262 -0.0485556 -0.220978 -0.0256763 -0.048236 -0.220778 -0.0274841 -0.0480789 -0.220992 -0.0277605 -0.0477712 -0.220833 -0.0261512 -0.0480692 -0.220951 -0.0261548 -0.0476742 -0.220725 -0.0266941 -0.0481136 -0.220826 -0.0268429 -0.0477212 -0.220691 -0.0272423 -0.0483479 -0.222498 -0.0264891 -0.0466071 -0.222049 -0.0282319 -0.0472467 -0.222077 -0.0273639 -0.0467496 -0.222751 -0.0244013 -0.0481767 -0.22251 -0.0263314 -0.0466232 -0.222575 -0.0255972 -0.0468471 -0.222363 -0.0248198 -0.0474971 -0.222469 -0.0243926 -0.0482746 -0.222663 -0.0248711 -0.047396 -0.222827 -0.0242569 -0.0490907 -0.222559 -0.0242815 -0.0491594 -0.222357 -0.0245833 -0.0500442 -0.221626 -0.0254181 -0.0503781 -0.221469 -0.0252284 -0.0498839 -0.221777 -0.0246437 -0.0493491 -0.222182 -0.0244353 -0.0483931 -0.221791 -0.0263146 -0.0467795 -0.221335 -0.0271444 -0.0470622 -0.22129 -0.0279798 -0.0475273 -0.221618 -0.0281272 -0.0473633 -0.22215 -0.0264004 -0.0466507 -0.221695 -0.0272691 -0.0468573 -0.221919 -0.0254607 -0.0470732 -0.222252 -0.0255136 -0.0469256 -0.222055 -0.0248153 -0.0476435 -0.222287 -0.0243536 -0.0492276 -0.221391 -0.0250928 -0.0494328 -0.221904 -0.0245338 -0.0485287 -0.221496 -0.0249713 -0.0480576 -0.22176 -0.0248651 -0.0478331 -0.221602 -0.0254481 -0.0472916 -0.221161 -0.0261849 -0.0473068 -0.221451 -0.02624 -0.0470007 -0.221035 -0.0269979 -0.0473584 -0.221018 -0.0460855 -0.0616879 -0.220939 -0.04674 -0.0617097 -0.221159 -0.0464368 -0.0622393 -0.221254 -0.0258207 -0.04993 -0.221241 -0.0256832 -0.0497567 -0.220854 -0.026207 -0.0487952 -0.220981 -0.0258423 -0.048937 -0.221018 -0.0262551 -0.0494465 -0.221254 -0.0317637 -0.0546815 -0.220781 -0.0395486 -0.0579625 -0.221254 -0.0389377 -0.05911 -0.222443 -0.0274759 -0.046746 -0.224573 -0.0273124 -0.0466931 -0.224573 -0.0262319 -0.046639 -0.224573 -0.0252374 -0.0470649 -0.222816 -0.0242562 -0.0489307 -0.224573 -0.024531 -0.0478843 -0.222726 -0.0245073 -0.0479307 -0.222613 -0.0252491 -0.0470564 -0.224773 -0.0470719 -0.0588388 -0.224773 -0.0464685 -0.0578898 -0.224773 -0.0304664 -0.0479401 -0.224973 -0.0303379 -0.0480934 -0.224973 -0.0290943 -0.0475145 -0.224773 -0.029129 -0.0473175 -0.224973 -0.028285 -0.0474978 -0.224773 -0.0276594 -0.047447 -0.224773 -0.0264514 -0.0482939 -0.224973 -0.0266047 -0.0484224 -0.224973 -0.0262504 -0.0489703 -0.224773 -0.0259583 -0.051101 -0.224973 -0.0260258 -0.049666 -0.224773 -0.0258288 -0.0496314 -0.224773 -0.024354 -0.0477912 -0.224773 -0.0261966 -0.0464421 -0.224773 -0.0273671 -0.0465007 -0.224773 -0.0242652 -0.050025 -0.224773 -0.0488751 -0.0615184 -0.224773 -0.0468901 -0.061272 -0.224773 -0.0484523 -0.0625955 -0.224773 -0.0464984 -0.0637235 -0.224773 -0.0380552 -0.0601706 -0.224773 -0.0268053 -0.0523089 -0.224773 -0.0249174 -0.0509352 -0.224773 -0.0469653 -0.0585963 -0.224773 -0.0472542 -0.0587106 -0.224773 -0.0455449 -0.0572481 -0.224773 -0.0376689 -0.0531396 -0.224773 -0.108809 -0.0494362 -0.224773 -0.109852 -0.0489342 -0.224773 -0.111009 -0.0489343 -0.224573 -0.109897 -0.0491292 -0.224573 -0.110965 -0.0491293 -0.224573 -0.111927 -0.0495928 -0.224773 -0.112052 -0.0494364 -0.224773 -0.112773 -0.0503411 -0.224573 -0.112593 -0.0504279 -0.224773 -0.11303 -0.0514692 -0.224773 -0.112051 -0.0535019 -0.224573 -0.112593 -0.0525105 -0.224573 -0.112825 -0.0516306 -0.224573 -0.088512 -0.0606227 -0.224573 -0.0879283 -0.0614026 -0.224573 -0.0877026 -0.0623502 -0.224773 -0.0910881 -0.0585897 -0.224773 -0.0991922 -0.0549519 -0.224773 -0.106688 -0.0501853 -0.224773 -0.102739 -0.0537101 -0.222889 -0.112407 -0.0528308 -0.224573 -0.111927 -0.0533455 -0.222827 -0.112819 -0.0516992 -0.224573 -0.11283 -0.0514692 -0.222736 -0.112677 -0.0506244 -0.222663 -0.112307 -0.0499725 -0.222623 -0.112021 -0.0496715 -0.222606 -0.111885 -0.0495598 -0.224573 -0.110806 -0.0490986 -0.222436 -0.0887207 -0.0604579 -0.222495 -0.0879644 -0.0613287 -0.222899 -0.0908455 -0.0647027 -0.224573 -0.0908455 -0.0647027 -0.224573 -0.0983086 -0.0617665 -0.222899 -0.105369 -0.0579628 -0.222426 -0.102845 -0.0538802 -0.224573 -0.0962881 -0.0574125 -0.222426 -0.0962881 -0.0574125 -0.224573 -0.0893576 -0.0601391 -0.220978 -0.111453 -0.0507629 -0.220778 -0.109657 -0.0504993 -0.221326 -0.111687 -0.0501116 -0.220992 -0.109399 -0.050176 -0.221283 -0.111996 -0.0508632 -0.221131 -0.111784 -0.0511028 -0.220939 -0.11115 -0.0513811 -0.220951 -0.111008 -0.0501735 -0.220833 -0.110988 -0.0505681 -0.220725 -0.110444 -0.0505805 -0.220826 -0.110318 -0.0501801 -0.221056 -0.111374 -0.0516134 -0.221159 -0.111457 -0.0519085 -0.221564 -0.112206 -0.0519697 -0.22186 -0.112181 -0.0525739 -0.222382 -0.111878 -0.0532844 -0.222448 -0.10986 -0.0491377 -0.222575 -0.111614 -0.0493812 -0.222519 -0.111009 -0.0491399 -0.22215 -0.110823 -0.0491375 -0.222503 -0.110806 -0.0490987 -0.222559 -0.112791 -0.0517664 -0.222469 -0.112732 -0.0508774 -0.222721 -0.112616 -0.0504766 -0.222252 -0.111693 -0.0494645 -0.221904 -0.112576 -0.0511227 -0.222055 -0.112348 -0.0502228 -0.22176 -0.112287 -0.050409 -0.221602 -0.111737 -0.0498337 -0.221451 -0.110962 -0.0494963 -0.221695 -0.109943 -0.0492927 -0.222287 -0.112715 -0.0518302 -0.222182 -0.112682 -0.0509931 -0.222363 -0.112352 -0.0500764 -0.221919 -0.111737 -0.049615 -0.221791 -0.110901 -0.0492711 -0.222077 -0.109855 -0.0491797 -0.222049 -0.10896 -0.0496246 -0.221618 -0.109057 -0.0497472 -0.22123 -0.111395 -0.0522093 -0.221497 -0.111489 -0.052796 -0.221469 -0.111803 -0.0524339 -0.221889 -0.111727 -0.053095 -0.221019 -0.111316 -0.0515279 -0.221391 -0.111965 -0.0519916 -0.221777 -0.112418 -0.0519345 -0.22288 -0.112545 -0.052605 -0.222357 -0.112437 -0.0526318 -0.221652 -0.112414 -0.05126 -0.221496 -0.112167 -0.0506268 -0.221161 -0.111 -0.049805 -0.221335 -0.110056 -0.0495046 -0.221035 -0.110185 -0.0498088 -0.22129 -0.109195 -0.0499196 -0.221889 -0.0907461 -0.064398 -0.221626 -0.0906753 -0.0641806 -0.220806 -0.0898292 -0.0625275 -0.220691 -0.0898292 -0.0615857 -0.220854 -0.0896989 -0.062706 -0.220725 -0.0893522 -0.0619433 -0.220833 -0.0890423 -0.0623912 -0.220878 -0.0896654 -0.0627872 -0.221391 -0.089694 -0.0639896 -0.221098 -0.0897679 -0.063389 -0.221274 -0.0893118 -0.0637295 -0.221496 -0.0884423 -0.0634073 -0.221131 -0.089051 -0.063349 -0.220978 -0.0889493 -0.062886 -0.220951 -0.088702 -0.0621906 -0.220826 -0.0890867 -0.0616183 -0.221035 -0.0888501 -0.0613026 -0.220992 -0.0895889 -0.0608486 -0.220981 -0.0896394 -0.0630927 -0.222252 -0.0877331 -0.0623716 -0.222583 -0.0877026 -0.0623502 -0.222445 -0.0885195 -0.0606161 -0.222077 -0.0885059 -0.0606813 -0.222049 -0.0893703 -0.0601781 -0.222426 -0.0893576 -0.0601391 -0.222469 -0.0883408 -0.0640169 -0.222754 -0.0882836 -0.0639878 -0.222363 -0.0878811 -0.0632583 -0.222808 -0.0887538 -0.0644067 -0.222559 -0.0890516 -0.0645556 -0.222836 -0.0890968 -0.0646004 -0.222357 -0.0899687 -0.0647366 -0.221777 -0.089397 -0.0643368 -0.221904 -0.0886315 -0.0640218 -0.22176 -0.0881947 -0.063387 -0.221602 -0.0880173 -0.0626114 -0.222055 -0.0880057 -0.0633354 -0.221919 -0.0878345 -0.0624913 -0.221451 -0.0881614 -0.0617801 -0.22215 -0.0879384 -0.0614663 -0.221695 -0.0885517 -0.0608172 -0.221791 -0.0880071 -0.0616049 -0.222182 -0.0884648 -0.0640393 -0.222287 -0.0891466 -0.0645273 -0.22186 -0.0900615 -0.0644904 -0.222206 -0.0908011 -0.0645666 -0.221254 -0.0904885 -0.0636079 -0.221469 -0.0901524 -0.0640978 -0.221241 -0.0902697 -0.0636404 -0.221652 -0.0888353 -0.0639622 -0.221326 -0.0882769 -0.0627226 -0.221161 -0.0883988 -0.0619809 -0.221335 -0.0886668 -0.0610276 -0.22129 -0.0894872 -0.0605367 -0.222206 -0.0982484 -0.0616367 -0.221254 -0.104997 -0.0568383 -0.221626 -0.111584 -0.0529162 -0.221626 -0.10508 -0.0574958 -0.221626 -0.0980775 -0.0612684 -0.221254 -0.104764 -0.0569834 -0.221254 -0.097575 -0.0608369 -0.222206 -0.111837 -0.0532336 -0.222899 -0.111927 -0.0533455 -0.222206 -0.105294 -0.057841 -0.222899 -0.0983086 -0.0617665 -0.222381 -0.0908212 -0.0646283 -0.220781 -0.0900856 -0.062372 -0.220781 -0.110398 -0.0514288 -0.220683 -0.109924 -0.0508345 -0.220691 -0.103645 -0.0551744 -0.220691 -0.109883 -0.0507823 -0.220781 -0.0972767 -0.0595428 -0.221618 -0.0894189 -0.0603271 -0.220691 -0.0969286 -0.0587927 -0.220778 -0.0897171 -0.0612418 -0.221618 -0.0963713 -0.0575919 -0.220992 -0.103237 -0.0545149 -0.220992 -0.0966022 -0.0580894 -0.221618 -0.102949 -0.0540484 -0.222426 -0.108934 -0.0495926 -0.220781 -0.104309 -0.0557354 -0.220853 -0.110889 -0.0512895 -0.220795 -0.110592 -0.0513218 -0.221018 -0.0902871 -0.06299 -0.221183 -0.0899804 -0.0635666 -0.220781 -0.0970326 -0.0596555 -0.220781 -0.10408 -0.0558777 -0.221254 -0.0978239 -0.060722 -0.221018 -0.110804 -0.051937 -0.221254 -0.111209 -0.0524453 -0.222645 -0.0877682 -0.0629824 -0.222663 -0.0878192 -0.0631633 -0.224573 -0.0886634 -0.0643423 -0.224573 -0.089097 -0.0646006 -0.224573 -0.0897104 -0.0647888 -0.222877 -0.0898183 -0.0648041 -0.224773 -0.0885435 -0.0645024 -0.224773 -0.0875027 -0.0623443 -0.224573 -0.0879398 -0.0634635 -0.224773 -0.0877597 -0.0635504 -0.224573 -0.0882933 -0.063999 -0.227819 -0.111015 -0.0528188 -0.224973 -0.111036 -0.0525517 -0.227748 -0.110688 -0.0537882 -0.224973 -0.110737 -0.0536993 -0.224973 -0.109967 -0.0546015 -0.224773 -0.110914 -0.0537918 -0.224773 -0.110233 -0.0503026 -0.224773 -0.110991 -0.0513159 -0.224773 -0.107847 -0.0496754 -0.224973 -0.107884 -0.0498718 -0.224973 -0.0901663 -0.0594181 -0.224773 -0.0900231 -0.0592785 -0.224773 -0.0893624 -0.0603612 -0.224973 -0.089552 -0.0604248 -0.224973 -0.0894353 -0.0615984 -0.224773 -0.0896714 -0.062815 -0.224973 -0.0918024 -0.0639042 -0.224773 -0.0917826 -0.0641032 -0.224773 -0.09058 -0.0637 -0.224973 -0.0908395 -0.063617 -0.224973 -0.0898394 -0.0627063 -0.224773 -0.0892956 -0.059949 -0.224773 -0.0883795 -0.0604729 -0.224773 -0.0896778 -0.0649861 -0.224773 -0.0892369 -0.0616234 -0.224773 -0.0877472 -0.0613177 -0.224773 -0.108566 -0.0496293 -0.224773 -0.109111 -0.0497173 -0.224773 -0.111236 -0.0525576 -0.224773 -0.112773 -0.0525973 -0.224773 -0.110086 -0.054762 -0.224773 -0.101896 -0.05997 -0.224773 -0.093041 -0.0639447 -0.224773 -0.0983928 -0.0619479 -0.224973 -0.0992871 -0.0551279 -0.228376 -0.106808 -0.0503459 -0.228376 -0.10187 -0.0536553 -0.224973 -0.0911566 -0.0587776 -0.227734 -0.0922163 -0.0639131 -0.224973 -0.0929725 -0.0637568 -0.22795 -0.0899503 -0.0628649 -0.224973 -0.0906842 -0.0635293 -0.228046 -0.0895746 -0.0621743 -0.228251 -0.0895522 -0.0604243 -0.228109 -0.0894471 -0.0616813 -0.228376 -0.0911566 -0.0587776 -0.228348 -0.0902338 -0.0593513 -0.224973 -0.0896144 -0.0602577 -0.228374 -0.107043 -0.0501901 -0.224973 -0.106808 -0.0503459 -0.224973 -0.109061 -0.0499107 -0.228168 -0.109772 -0.0502142 -0.228112 -0.110149 -0.050494 -0.224973 -0.110104 -0.0504549 -0.227988 -0.110761 -0.0512951 -0.224973 -0.110809 -0.0513972 -0.227924 -0.11095 -0.051799 -0.23002 -0.108207 -0.0522316 -0.229184 -0.0912244 -0.0589633 -0.228376 -0.0966366 -0.0564746 -0.228376 -0.0992871 -0.0551279 -0.229184 -0.101972 -0.0538247 -0.229809 -0.102255 -0.0542945 -0.230111 -0.0972929 -0.0578473 -0.229511 -0.0912998 -0.0591703 -0.229184 -0.0967219 -0.0566529 -0.229809 -0.0969585 -0.0571478 -0.229809 -0.107252 -0.0509451 -0.23002 -0.100401 -0.0571957 -0.230111 -0.102655 -0.0549586 -0.23002 -0.103082 -0.0556669 -0.22772 -0.109967 -0.0546015 -0.224973 -0.101801 -0.0597939 -0.228622 -0.0896415 -0.0602858 -0.229639 -0.0914745 -0.0622682 -0.229497 -0.091765 -0.0625813 -0.229463 -0.0918709 -0.0626411 -0.229938 -0.0914761 -0.0613972 -0.229919 -0.0914421 -0.0614646 -0.230069 -0.0911269 -0.0606334 -0.230009 -0.0917525 -0.0610922 -0.230111 -0.0916779 -0.0602071 -0.229577 -0.0908098 -0.0623174 -0.229212 -0.0902046 -0.0623964 -0.229023 -0.0906652 -0.0630184 -0.228653 -0.0897666 -0.0623397 -0.227747 -0.091919 -0.0639132 -0.229157 -0.0921586 -0.0631915 -0.229255 -0.0916006 -0.0630744 -0.228869 -0.0913161 -0.0634312 -0.22827 -0.0919974 -0.0638357 -0.228359 -0.091073 -0.06363 -0.228087 -0.0909793 -0.0636616 -0.22969 -0.0914161 -0.0621404 -0.229401 -0.0911326 -0.0627698 -0.22877 -0.090464 -0.0630848 -0.228493 -0.0902984 -0.0631081 -0.228126 -0.0894286 -0.0615395 -0.228491 -0.0894459 -0.0612922 -0.228168 -0.0894159 -0.0611814 -0.230023 -0.0915538 -0.0598667 -0.229809 -0.0914123 -0.0594787 -0.229458 -0.0904111 -0.059742 -0.228752 -0.0911706 -0.0588161 -0.228981 -0.0897146 -0.0604221 -0.229321 -0.0898746 -0.0605919 -0.22914 -0.0897377 -0.061522 -0.229967 -0.0908506 -0.0603177 -0.229821 -0.0904282 -0.0609836 -0.229759 -0.0906035 -0.0600104 -0.229611 -0.0901184 -0.0607844 -0.229098 -0.090289 -0.0595356 -0.228717 -0.0902387 -0.0594013 -0.228268 -0.0896143 -0.0602579 -0.22772 -0.0929725 -0.0637568 -0.228238 -0.0929457 -0.0636834 -0.228766 -0.0920814 -0.0635867 -0.229399 -0.0921663 -0.0627252 -0.229365 -0.092578 -0.062675 -0.227819 -0.0909072 -0.0636511 -0.228206 -0.090174 -0.0630901 -0.228346 -0.0896397 -0.0622669 -0.228823 -0.0895512 -0.0614083 -0.228949 -0.089957 -0.0623847 -0.229416 -0.0900005 -0.0616242 -0.229764 -0.0906771 -0.0617644 -0.229939 -0.0907748 -0.0611724 -0.229885 -0.109012 -0.0520895 -0.229986 -0.108587 -0.0520664 -0.229939 -0.109018 -0.0513446 -0.230069 -0.108374 -0.051342 -0.229365 -0.10928 -0.0536769 -0.229463 -0.109641 -0.0530679 -0.229401 -0.110155 -0.0525216 -0.229255 -0.110152 -0.0530805 -0.229577 -0.109954 -0.052003 -0.22969 -0.109473 -0.0524122 -0.229764 -0.109565 -0.0515883 -0.229821 -0.109051 -0.0509513 -0.229967 -0.108262 -0.0509376 -0.229759 -0.108142 -0.0505622 -0.229741 -0.10938 -0.0523064 -0.230111 -0.107715 -0.0515677 -0.230023 -0.107499 -0.0512768 -0.228221 -0.109347 -0.0500037 -0.228257 -0.109003 -0.0498963 -0.228717 -0.107834 -0.0499225 -0.228352 -0.107711 -0.0499113 -0.228322 -0.108228 -0.0498285 -0.228275 -0.108816 -0.0498587 -0.228622 -0.108901 -0.0499103 -0.228752 -0.106832 -0.0503788 -0.229184 -0.106925 -0.0505047 -0.227844 -0.111036 -0.0525517 -0.228087 -0.110984 -0.0528848 -0.228206 -0.110949 -0.051897 -0.228069 -0.110396 -0.0507459 -0.228238 -0.10992 -0.0545387 -0.22827 -0.110569 -0.053831 -0.228993 -0.109639 -0.0541606 -0.229157 -0.109942 -0.053611 -0.228359 -0.110906 -0.0529457 -0.228493 -0.110896 -0.0520108 -0.228949 -0.110479 -0.0513275 -0.228823 -0.109887 -0.0504519 -0.22914 -0.109879 -0.0506703 -0.228981 -0.108974 -0.0500465 -0.229098 -0.107918 -0.0500383 -0.229511 -0.107057 -0.0506816 -0.228491 -0.109848 -0.0503002 -0.228346 -0.110555 -0.0509977 -0.228653 -0.110546 -0.0511436 -0.228766 -0.110315 -0.053764 -0.228869 -0.110606 -0.0530393 -0.229023 -0.110619 -0.0522679 -0.229212 -0.110353 -0.0515408 -0.228771 -0.110785 -0.0521364 -0.229416 -0.10982 -0.050946 -0.229611 -0.109055 -0.050583 -0.229321 -0.109028 -0.0502735 -0.229458 -0.108023 -0.0502538 -0.229692 -0.108744 -0.0529543 -0.229692 -0.0922696 -0.0618295 -0.23002 -0.0919612 -0.060984 -0.23002 -0.0976496 -0.0585934 -0.229803 -0.0913622 -0.0618299 -0.229376 -0.10945 -0.053513 -0.229445 -0.109628 -0.0531413 -0.229578 -0.109613 -0.0526945 -0.229365 -0.101255 -0.0587802 -0.22873 -0.0928627 -0.0634558 -0.228993 -0.0927844 -0.063241 -0.229365 -0.0969867 -0.0608843 -0.228993 -0.105683 -0.0568819 -0.229365 -0.10536 -0.0563735 -0.22873 -0.109776 -0.0543442 -0.228414 -0.105901 -0.0572244 -0.228993 -0.10154 -0.0593105 -0.228414 -0.101733 -0.0596679 -0.228993 -0.0972334 -0.0614339 -0.228414 -0.0929234 -0.0636223 -0.228414 -0.109881 -0.0544865 -0.22772 -0.105978 -0.0573452 -0.22772 -0.101801 -0.0597939 -0.228414 -0.0973996 -0.0618043 -0.22772 -0.0974582 -0.0619348 -0.224773 -0.0895908 -0.0598519 -0.224773 -0.0962039 -0.0572311 -0.224573 -0.102845 -0.0538802 -0.224573 -0.108934 -0.0495926 -0.224773 -0.0909074 -0.0648928 -0.224573 -0.105369 -0.0579628 -0.224773 -0.105474 -0.0581329 -0.222503 -0.115848 -0.044346 -0.222663 -0.116631 -0.0458939 -0.224573 -0.116469 -0.0457333 -0.222641 -0.116469 -0.0457332 -0.222602 -0.116223 -0.0454167 -0.222703 -0.116957 -0.0461406 -0.222745 -0.117344 -0.0463379 -0.224573 -0.117345 -0.046338 -0.222807 -0.118046 -0.0465022 -0.224573 -0.117909 -0.0464874 -0.222832 -0.118395 -0.0465045 -0.224573 -0.118396 -0.0465045 -0.224573 -0.119062 -0.0463635 -0.224573 -0.120022 -0.0457139 -0.222899 -0.120022 -0.0457139 -0.224773 -0.117882 -0.0466855 -0.224773 -0.116716 -0.0462189 -0.224573 -0.115837 -0.0440392 -0.224573 -0.116084 -0.0451718 -0.224773 -0.115905 -0.0452602 -0.224573 -0.116833 -0.0460566 -0.224973 -0.13153 -0.0274054 -0.22772 -0.13153 -0.0274054 -0.227726 -0.131685 -0.0269279 -0.224773 -0.131947 -0.0264364 -0.230023 -0.127731 -0.0257602 -0.228376 -0.117328 -0.0404271 -0.228376 -0.120923 -0.0356926 -0.229184 -0.11748 -0.0405541 -0.229184 -0.121086 -0.0358045 -0.228376 -0.122545 -0.0332012 -0.229809 -0.121538 -0.0361147 -0.229184 -0.124218 -0.0307301 -0.229511 -0.12705 -0.0254657 -0.229809 -0.124698 -0.0309955 -0.229809 -0.127352 -0.0255961 -0.230023 -0.118217 -0.0411717 -0.230111 -0.125377 -0.0313705 -0.23002 -0.122859 -0.037021 -0.230111 -0.122178 -0.0365533 -0.23002 -0.126101 -0.0317705 -0.22772 -0.129448 -0.0317761 -0.22772 -0.127055 -0.0359851 -0.224973 -0.127055 -0.0359851 -0.229255 -0.119861 -0.0439263 -0.229497 -0.119757 -0.043417 -0.229938 -0.118915 -0.042536 -0.230009 -0.119002 -0.0421336 -0.230111 -0.118495 -0.0414044 -0.229919 -0.118919 -0.0426114 -0.229803 -0.119033 -0.0429677 -0.229764 -0.118407 -0.0432535 -0.229577 -0.118798 -0.043666 -0.229023 -0.119023 -0.0443454 -0.228949 -0.118093 -0.0441507 -0.228346 -0.117759 -0.0442074 -0.227734 -0.120814 -0.0443447 -0.228766 -0.120534 -0.0441295 -0.228869 -0.119793 -0.0443775 -0.228087 -0.119617 -0.0447454 -0.228359 -0.119682 -0.0446712 -0.229639 -0.119349 -0.0432911 -0.229401 -0.119304 -0.0438965 -0.22877 -0.118882 -0.0445036 -0.228493 -0.11875 -0.0446065 -0.228126 -0.117213 -0.0436829 -0.229809 -0.1179 -0.0409064 -0.229759 -0.117466 -0.0417713 -0.229511 -0.117649 -0.0406956 -0.229098 -0.116956 -0.0415174 -0.228752 -0.11736 -0.0404534 -0.228348 -0.116816 -0.0413853 -0.228251 -0.116762 -0.0426554 -0.228622 -0.11677 -0.0424908 -0.228823 -0.117253 -0.0435081 -0.22914 -0.117472 -0.0435133 -0.229611 -0.117433 -0.0426842 -0.229416 -0.117751 -0.0434704 -0.229821 -0.117801 -0.0427018 -0.229967 -0.117834 -0.0419139 -0.229458 -0.117165 -0.041635 -0.229321 -0.117125 -0.0426394 -0.228981 -0.116902 -0.0425723 -0.228717 -0.116845 -0.0414262 -0.22772 -0.121391 -0.0438313 -0.228238 -0.121331 -0.0437811 -0.22827 -0.120586 -0.0443872 -0.229157 -0.120403 -0.0437486 -0.229399 -0.120177 -0.043341 -0.227747 -0.120557 -0.0444934 -0.228206 -0.118634 -0.0446532 -0.228491 -0.117104 -0.0434601 -0.228653 -0.117906 -0.0442069 -0.229212 -0.118313 -0.0440371 -0.229939 -0.118195 -0.0426919 -0.230069 -0.118231 -0.0420491 -0.229212 -0.130334 -0.0245618 -0.229885 -0.129448 -0.0257071 -0.229939 -0.12908 -0.0250595 -0.230069 -0.128521 -0.025379 -0.23002 -0.128822 -0.0262327 -0.229365 -0.130474 -0.0269479 -0.229401 -0.130653 -0.0255103 -0.229023 -0.130929 -0.0250583 -0.229255 -0.13093 -0.0259958 -0.229577 -0.13022 -0.0251615 -0.229416 -0.129576 -0.024313 -0.229821 -0.128912 -0.0247023 -0.229611 -0.128731 -0.0243813 -0.229759 -0.12793 -0.0248198 -0.229741 -0.129875 -0.025711 -0.229764 -0.129676 -0.0249968 -0.230111 -0.128063 -0.0259042 -0.229967 -0.128222 -0.0250846 -0.228622 -0.128262 -0.0238758 -0.228275 -0.128163 -0.0238733 -0.228376 -0.126667 -0.0252996 -0.228752 -0.126704 -0.0253159 -0.227743 -0.131747 -0.0264305 -0.227834 -0.131478 -0.0251851 -0.228087 -0.131553 -0.0254103 -0.228206 -0.131029 -0.024572 -0.22827 -0.131667 -0.0264371 -0.228414 -0.131399 -0.0273485 -0.228869 -0.131303 -0.0257329 -0.228949 -0.130337 -0.0243138 -0.22914 -0.129489 -0.0240446 -0.228823 -0.129387 -0.0238517 -0.229321 -0.128554 -0.0241266 -0.229098 -0.127475 -0.0244778 -0.229184 -0.126848 -0.0253782 -0.228717 -0.127344 -0.0244198 -0.228981 -0.128393 -0.0239569 -0.228491 -0.129277 -0.0237399 -0.228346 -0.130238 -0.0239902 -0.228653 -0.130303 -0.0241211 -0.228493 -0.13104 -0.0246973 -0.228359 -0.131516 -0.025502 -0.228766 -0.131413 -0.0265062 -0.229157 -0.131014 -0.0265599 -0.229376 -0.130539 -0.026721 -0.228771 -0.131007 -0.0248613 -0.229458 -0.127674 -0.0246119 -0.23002 -0.119129 -0.0419355 -0.229463 -0.119879 -0.0434159 -0.229692 -0.119818 -0.0425136 -0.22969 -0.119235 -0.0432096 -0.22969 -0.130008 -0.0257564 -0.229445 -0.130507 -0.0263103 -0.229692 -0.129648 -0.0265903 -0.229463 -0.130482 -0.0262402 -0.229578 -0.130271 -0.0259307 -0.229986 -0.129068 -0.0258999 -0.229365 -0.128427 -0.0312436 -0.23002 -0.124543 -0.0344352 -0.228414 -0.121281 -0.0437393 -0.22873 -0.121145 -0.0436255 -0.228993 -0.12097 -0.0434786 -0.229365 -0.120508 -0.0430917 -0.229365 -0.123431 -0.0393366 -0.229365 -0.126075 -0.0353803 -0.228993 -0.131027 -0.0271872 -0.22873 -0.131236 -0.0272781 -0.228993 -0.128961 -0.0315222 -0.228993 -0.126588 -0.0356967 -0.228993 -0.123919 -0.0396891 -0.228414 -0.124248 -0.0399268 -0.228238 -0.131459 -0.0273743 -0.228414 -0.129321 -0.0317099 -0.228414 -0.126933 -0.03591 -0.22772 -0.124364 -0.0400105 -0.224773 -0.116302 -0.042372 -0.224573 -0.12109 -0.0366791 -0.224773 -0.120926 -0.0365641 -0.224773 -0.124826 -0.0302471 -0.224773 -0.127831 -0.0237997 -0.224573 -0.125017 -0.0394396 -0.224573 -0.12923 -0.0326151 -0.224773 -0.128597 -0.0225548 -0.224773 -0.1296 -0.0219763 -0.224573 -0.129659 -0.0221674 -0.224773 -0.131831 -0.0223127 -0.224573 -0.132759 -0.0242816 -0.224773 -0.132959 -0.0242667 -0.224573 -0.13252 -0.0234035 -0.224573 -0.132444 -0.0232609 -0.224773 -0.115823 -0.0431436 -0.224773 -0.115638 -0.0440333 -0.224773 -0.117175 -0.0402986 -0.224773 -0.122375 -0.0330961 -0.224573 -0.1326 -0.0253377 -0.22288 -0.132765 -0.0243875 -0.222827 -0.13255 -0.0234656 -0.222736 -0.131889 -0.0226061 -0.224573 -0.131718 -0.0224779 -0.224573 -0.130724 -0.0220876 -0.222503 -0.129506 -0.0222201 -0.222575 -0.130347 -0.0220609 -0.222623 -0.130844 -0.022109 -0.224573 -0.128734 -0.0227014 -0.224573 -0.129506 -0.0222202 -0.222426 -0.116451 -0.0425057 -0.224573 -0.116008 -0.043218 -0.222899 -0.125017 -0.0394396 -0.222899 -0.12923 -0.0326151 -0.222899 -0.1326 -0.0253377 -0.224573 -0.128132 -0.0235839 -0.224573 -0.125002 -0.0303418 -0.222426 -0.12109 -0.0366791 -0.224573 -0.116451 -0.0425057 -0.221497 -0.131946 -0.0250809 -0.220853 -0.130673 -0.0240762 -0.220795 -0.130432 -0.0242525 -0.220725 -0.129933 -0.0236847 -0.220992 -0.128826 -0.0238565 -0.221131 -0.131355 -0.0234669 -0.220978 -0.130898 -0.0233379 -0.220939 -0.130945 -0.024025 -0.220951 -0.130218 -0.0230501 -0.220833 -0.130398 -0.0234016 -0.220826 -0.129624 -0.0234006 -0.220691 -0.129548 -0.0241398 -0.221652 -0.131979 -0.0232879 -0.221283 -0.131418 -0.0231535 -0.221391 -0.131956 -0.0241462 -0.221159 -0.131474 -0.0243282 -0.222287 -0.132525 -0.0236314 -0.222889 -0.132758 -0.0246518 -0.222382 -0.132527 -0.0253092 -0.222448 -0.128706 -0.0227268 -0.222077 -0.128723 -0.0227658 -0.222426 -0.128132 -0.0235839 -0.22215 -0.12954 -0.0222453 -0.222519 -0.129702 -0.0221544 -0.222721 -0.131762 -0.0225087 -0.222663 -0.131242 -0.0222266 -0.222606 -0.13067 -0.0220803 -0.222182 -0.132078 -0.0229226 -0.22176 -0.131443 -0.0226146 -0.221919 -0.13057 -0.0222018 -0.221451 -0.12984 -0.0224863 -0.221695 -0.128856 -0.0228195 -0.221335 -0.129059 -0.0229468 -0.222469 -0.132063 -0.0227976 -0.222363 -0.131334 -0.022294 -0.222055 -0.131403 -0.0224229 -0.222252 -0.130457 -0.0220936 -0.221791 -0.129674 -0.022322 -0.221618 -0.128316 -0.0236561 -0.221469 -0.132037 -0.0246101 -0.221626 -0.132089 -0.0251371 -0.22186 -0.132434 -0.0245424 -0.221056 -0.131255 -0.0241141 -0.221777 -0.13232 -0.0238701 -0.221564 -0.132154 -0.0240065 -0.222206 -0.132467 -0.0252855 -0.222559 -0.132559 -0.0235382 -0.222357 -0.132685 -0.0244642 -0.221904 -0.132051 -0.023088 -0.221496 -0.131449 -0.0228629 -0.221602 -0.130679 -0.0223914 -0.221326 -0.130775 -0.0226571 -0.221161 -0.130027 -0.0227352 -0.221035 -0.129323 -0.0231459 -0.222877 -0.119183 -0.0463154 -0.22186 -0.119237 -0.045922 -0.221889 -0.119783 -0.0454997 -0.221626 -0.119613 -0.045347 -0.220878 -0.118042 -0.0446452 -0.221274 -0.118207 -0.0456379 -0.221131 -0.117791 -0.0454388 -0.221098 -0.118431 -0.045115 -0.220981 -0.118172 -0.0449227 -0.220978 -0.117471 -0.0450887 -0.220826 -0.116956 -0.0439221 -0.220778 -0.117314 -0.0432809 -0.220951 -0.116909 -0.0446102 -0.220833 -0.117304 -0.0446138 -0.220725 -0.117349 -0.0440709 -0.220691 -0.117583 -0.0435227 -0.222575 -0.116082 -0.0451678 -0.222541 -0.115941 -0.0448096 -0.222252 -0.116161 -0.0452514 -0.222077 -0.115985 -0.0434011 -0.22244 -0.116006 -0.0432244 -0.222482 -0.115837 -0.0440392 -0.222469 -0.11751 -0.0463724 -0.222559 -0.118395 -0.0464835 -0.222182 -0.117628 -0.0463297 -0.222055 -0.116879 -0.0459498 -0.221919 -0.116308 -0.0453043 -0.221791 -0.116015 -0.0444504 -0.221695 -0.116092 -0.0434959 -0.22129 -0.116762 -0.0427852 -0.22215 -0.115886 -0.0443646 -0.222363 -0.116732 -0.0459452 -0.222287 -0.118463 -0.0464115 -0.222357 -0.119279 -0.0461817 -0.222206 -0.119915 -0.0456183 -0.221241 -0.118992 -0.0450818 -0.221469 -0.119119 -0.0455367 -0.221391 -0.118668 -0.0456722 -0.221652 -0.11791 -0.0460777 -0.221777 -0.118584 -0.0461213 -0.221904 -0.117764 -0.0462312 -0.221496 -0.117293 -0.0457937 -0.22176 -0.117068 -0.0458999 -0.221326 -0.116807 -0.0452834 -0.221602 -0.116527 -0.0453169 -0.221161 -0.116542 -0.0445801 -0.221451 -0.116236 -0.044525 -0.221035 -0.116593 -0.0437671 -0.221335 -0.116297 -0.0436206 -0.221626 -0.128746 -0.0323551 -0.221254 -0.131528 -0.024917 -0.221254 -0.128345 -0.0318273 -0.221626 -0.124568 -0.0391238 -0.221254 -0.124075 -0.0387774 -0.222206 -0.129103 -0.0325474 -0.221254 -0.123917 -0.0390013 -0.222381 -0.119963 -0.0456617 -0.221889 -0.132302 -0.0252207 -0.222206 -0.1249 -0.0393573 -0.222049 -0.116482 -0.0425331 -0.220781 -0.12707 -0.0314541 -0.220781 -0.118198 -0.0440754 -0.220683 -0.12961 -0.0241642 -0.220691 -0.126342 -0.0310625 -0.220691 -0.122335 -0.0375542 -0.220992 -0.117006 -0.0430045 -0.221618 -0.121252 -0.0367929 -0.220778 -0.129211 -0.0240076 -0.220992 -0.125659 -0.0306952 -0.22129 -0.128521 -0.0237367 -0.221618 -0.125176 -0.0304355 -0.221618 -0.116598 -0.0426379 -0.220992 -0.1217 -0.0371083 -0.222426 -0.125002 -0.0303418 -0.222049 -0.12817 -0.0235988 -0.220781 -0.130318 -0.024442 -0.22123 -0.131571 -0.0246198 -0.221019 -0.131163 -0.0240688 -0.221254 -0.119165 -0.0449443 -0.221183 -0.118704 -0.0451625 -0.220806 -0.118054 -0.0443383 -0.220854 -0.11803 -0.044558 -0.221018 -0.118682 -0.0445099 -0.220781 -0.122856 -0.0382493 -0.220781 -0.123011 -0.0380298 -0.221254 -0.128215 -0.0320698 -0.220781 -0.127198 -0.0312164 -0.221018 -0.130923 -0.0246795 -0.224973 -0.131747 -0.0264305 -0.224973 -0.131506 -0.0252455 -0.224973 -0.128465 -0.0237793 -0.224773 -0.128417 -0.0235851 -0.224973 -0.128347 -0.0238112 -0.224973 -0.126667 -0.0252996 -0.224773 -0.127259 -0.024176 -0.224773 -0.116597 -0.0414277 -0.224973 -0.116733 -0.04248 -0.224973 -0.116762 -0.0426559 -0.224973 -0.117248 -0.0437306 -0.224773 -0.117089 -0.0438515 -0.224973 -0.119474 -0.0447767 -0.224773 -0.11929 -0.0449783 -0.224773 -0.127946 -0.0235108 -0.224773 -0.129718 -0.0235706 -0.224773 -0.11913 -0.0465513 -0.224773 -0.118061 -0.0446661 -0.224773 -0.11651 -0.0421404 -0.224773 -0.116566 -0.0426957 -0.224773 -0.12017 -0.0458476 -0.224773 -0.120533 -0.0447262 -0.224773 -0.12518 -0.0395546 -0.224773 -0.129406 -0.0327099 -0.224773 -0.132786 -0.0254108 -0.224773 -0.131714 -0.0274849 -0.224773 -0.131688 -0.0251619 -0.224773 -0.132618 -0.0231609 -0.224773 -0.130889 -0.0241354 -0.224773 -0.130754 -0.0218899 -0.224773 -0.126483 -0.0252201 -0.224973 -0.122545 -0.0332012 -0.224973 -0.117328 -0.0404271 -0.228376 -0.124045 -0.0306345 -0.224973 -0.121391 -0.0438313 -0.224773 -0.127225 -0.0360902 -0.224773 -0.121544 -0.0439597 -0.224973 -0.120451 -0.044544 -0.224973 -0.119295 -0.0447784 -0.227819 -0.119549 -0.0447724 -0.22795 -0.118327 -0.04457 -0.224973 -0.118152 -0.0444881 -0.228046 -0.117657 -0.0441597 -0.228109 -0.1173 -0.0437965 -0.228168 -0.117023 -0.0433792 -0.224973 -0.116791 -0.0414769 -0.228268 -0.116733 -0.0424803 -0.228349 -0.127276 -0.0244284 -0.224973 -0.127209 -0.0244946 -0.224973 -0.127388 -0.0243287 -0.228252 -0.12839 -0.023799 -0.228168 -0.129168 -0.0237034 -0.224973 -0.129674 -0.0237658 -0.228104 -0.1297 -0.0237716 -0.228046 -0.13015 -0.0239198 -0.227953 -0.130797 -0.0243188 -0.224973 -0.130764 -0.024291 -0.224973 -0.130857 -0.0243698 -0.227819 -0.131547 -0.0253377 -0.222436 -0.129688 0.0179633 -0.224573 -0.130052 0.0175514 -0.224573 -0.1324 0.0170547 -0.222606 -0.13182 0.0169421 -0.22259 -0.13166 0.0169365 -0.224573 -0.130666 0.0171504 -0.222877 -0.134039 0.0190533 -0.224573 -0.133745 0.0181542 -0.222827 -0.133778 0.0182147 -0.222822 -0.133744 0.018154 -0.224573 -0.133441 0.0177324 -0.222899 -0.133938 0.0200804 -0.222899 -0.127198 0.0346042 -0.224573 -0.131002 0.0275436 -0.224573 -0.127198 0.0346042 -0.224573 -0.122581 0.0411617 -0.222426 -0.123115 0.0320797 -0.224573 -0.126648 0.0255231 -0.222426 -0.126648 0.0255231 -0.224573 -0.129374 0.0185926 -0.221469 -0.121669 0.041038 -0.220978 -0.119998 0.040688 -0.220725 -0.119816 0.0396786 -0.220691 -0.120017 0.0391178 -0.221035 -0.119044 0.0394196 -0.220992 -0.119411 0.0386344 -0.220778 -0.119734 0.0388922 -0.221283 -0.120098 0.0412306 -0.221131 -0.120338 0.0410187 -0.220833 -0.119803 0.0402233 -0.220951 -0.119409 0.040243 -0.220826 -0.119415 0.0395531 -0.221496 -0.119862 0.0414024 -0.221326 -0.119347 0.0409217 -0.22186 -0.121809 0.0414158 -0.222745 -0.119945 0.0419421 -0.22288 -0.12184 0.0417796 -0.222898 -0.122463 0.0412987 -0.222498 -0.118324 0.039972 -0.222077 -0.118415 0.0390901 -0.222363 -0.119311 0.0415868 -0.222641 -0.119035 0.0413902 -0.222563 -0.118555 0.0407332 -0.222287 -0.121065 0.0419498 -0.221904 -0.120358 0.0418111 -0.222182 -0.120228 0.0419174 -0.22176 -0.119644 0.0415217 -0.222055 -0.119458 0.0415827 -0.221919 -0.11885 0.040972 -0.221618 -0.118982 0.0382924 -0.222469 -0.120112 0.041967 -0.222252 -0.1187 0.0409278 -0.221791 -0.118506 0.0401361 -0.22215 -0.118373 0.040058 -0.221695 -0.118528 0.0391784 -0.222049 -0.11886 0.0381947 -0.22123 -0.121444 0.0406296 -0.221497 -0.122031 0.0407235 -0.221019 -0.120763 0.0405514 -0.221056 -0.120849 0.0406089 -0.221391 -0.121227 0.0411997 -0.221564 -0.121205 0.0414413 -0.222559 -0.121001 0.0420257 -0.222357 -0.121867 0.0416725 -0.221777 -0.12117 0.0416531 -0.221652 -0.120495 0.0416492 -0.221602 -0.119069 0.0409716 -0.221451 -0.118731 0.0401975 -0.221161 -0.11904 0.0402345 -0.221335 -0.11874 0.0392908 -0.221326 -0.131958 0.0175119 -0.220806 -0.131763 0.0190642 -0.220854 -0.131941 0.0189339 -0.221241 -0.132875 0.0195047 -0.221098 -0.132624 0.0190029 -0.221131 -0.132584 0.018286 -0.221274 -0.132965 0.0185468 -0.220951 -0.131426 0.017937 -0.220778 -0.130477 0.0189521 -0.220878 -0.132022 0.0189004 -0.220978 -0.132121 0.0181843 -0.220833 -0.131626 0.0182773 -0.220725 -0.131178 0.0185871 -0.220826 -0.130853 0.0183217 -0.222445 -0.129851 0.0177545 -0.22215 -0.130701 0.0171734 -0.222498 -0.130603 0.01718 -0.222426 -0.129374 0.0185926 -0.222559 -0.133791 0.0182866 -0.222807 -0.133635 0.0179782 -0.222663 -0.132398 0.0170542 -0.222363 -0.132493 0.0171161 -0.222704 -0.132782 0.0172171 -0.222721 -0.132935 0.0173056 -0.222751 -0.133196 0.0174954 -0.222357 -0.133972 0.0192037 -0.221626 -0.133416 0.0199102 -0.22186 -0.133725 0.0192965 -0.222287 -0.133762 0.0183816 -0.221904 -0.133257 0.0178665 -0.222182 -0.133274 0.0176998 -0.22176 -0.132622 0.0174297 -0.221919 -0.131726 0.0170694 -0.221451 -0.131015 0.0173964 -0.221791 -0.13084 0.017242 -0.221335 -0.130263 0.0179018 -0.221695 -0.130052 0.0177866 -0.221618 -0.129562 0.0186539 -0.222077 -0.129916 0.0177408 -0.222252 -0.131607 0.0169681 -0.222055 -0.13257 0.0172406 -0.222469 -0.133252 0.0175758 -0.222206 -0.133802 0.0200361 -0.221469 -0.133333 0.0193874 -0.221391 -0.133225 0.018929 -0.221777 -0.133572 0.018632 -0.221652 -0.133197 0.0180703 -0.221496 -0.132642 0.0176773 -0.221602 -0.131846 0.0172523 -0.221161 -0.131216 0.0176338 -0.221035 -0.130538 0.0180851 -0.221626 -0.130504 0.0273125 -0.222206 -0.130872 0.0274834 -0.221254 -0.12168 0.0404438 -0.221889 -0.12233 0.0409619 -0.221626 -0.122151 0.0408194 -0.222206 -0.122469 0.0410725 -0.222899 -0.122581 0.0411617 -0.222382 -0.122519 0.041113 -0.222206 -0.127076 0.0345289 -0.221254 -0.130072 0.02681 -0.221889 -0.133633 0.0199811 -0.221626 -0.126731 0.0343154 -0.222899 -0.131002 0.0275436 -0.222381 -0.133863 0.0200562 -0.222049 -0.129413 0.0186053 -0.220691 -0.124409 0.0328799 -0.220781 -0.131607 0.0193206 -0.220683 -0.12007 0.0391594 -0.220992 -0.127324 0.0258372 -0.220781 -0.125113 0.0333149 -0.220691 -0.128028 0.0261636 -0.22129 -0.129772 0.0187222 -0.220992 -0.130084 0.0188239 -0.220691 -0.130821 0.0190642 -0.220992 -0.12375 0.0324721 -0.22129 -0.119155 0.0384299 -0.221618 -0.126827 0.0256063 -0.221618 -0.123283 0.0321837 -0.220781 -0.120664 0.0396333 -0.220781 -0.124971 0.0335439 -0.220939 -0.120616 0.0403847 -0.220853 -0.120525 0.0401235 -0.220795 -0.120557 0.0398269 -0.221159 -0.121144 0.0406918 -0.221254 -0.132843 0.0197235 -0.221183 -0.132802 0.0192154 -0.221018 -0.132225 0.019522 -0.220981 -0.132328 0.0188744 -0.220781 -0.128891 0.0262676 -0.220781 -0.128778 0.0265117 -0.221254 -0.129957 0.0270589 -0.221254 -0.126218 0.0339986 -0.221254 -0.126073 0.0342322 -0.221018 -0.121172 0.0400386 -0.22244 -0.118425 0.0389123 -0.222482 -0.118305 0.0397361 -0.224573 -0.118305 0.0397361 -0.224573 -0.118427 0.0389063 -0.222426 -0.118828 0.0381692 -0.224773 -0.118105 0.039742 -0.224773 -0.118238 0.038843 -0.224573 -0.118828 0.0381692 -0.224773 -0.118671 0.0380445 -0.228111 -0.130897 0.0186792 -0.224973 -0.130925 0.0186834 -0.228083 -0.131124 0.0187234 -0.228046 -0.131409 0.0188096 -0.224973 -0.132043 0.0191436 -0.224973 -0.132141 0.0192168 -0.227928 -0.132243 0.0193016 -0.224973 -0.132841 0.0200527 -0.2278 -0.132975 0.0203459 -0.224973 -0.133151 0.0212215 -0.228168 -0.130417 0.0186509 -0.224973 -0.129718 0.0187681 -0.228275 -0.129422 0.0188798 -0.228348 -0.128586 0.0194687 -0.228376 -0.128013 0.0203916 -0.224773 -0.128537 0.0192351 -0.224973 -0.128675 0.01938 -0.224973 -0.129603 0.0188069 -0.224773 -0.130957 0.018486 -0.224973 -0.123837 0.0392017 -0.224973 -0.122762 0.040054 -0.224973 -0.121978 0.0402584 -0.224773 -0.118878 0.0372951 -0.224773 -0.119093 0.0387545 -0.224973 -0.119657 0.0392994 -0.224773 -0.12001 0.0399105 -0.224773 -0.133351 0.0212156 -0.224773 -0.129659 0.0185771 -0.224773 -0.132159 0.0189809 -0.224773 -0.129918 0.0174026 -0.224773 -0.133017 0.0199586 -0.224773 -0.13318 0.022276 -0.224773 -0.131183 0.0276278 -0.224773 -0.127368 0.0347093 -0.224773 -0.123997 0.0393209 -0.224773 -0.122841 0.0402375 -0.224773 -0.120502 0.0422575 -0.224773 -0.121382 0.0404533 -0.224773 -0.11931 0.0418603 -0.224773 -0.11942 0.0359233 -0.224973 -0.124363 0.0285221 -0.224973 -0.128013 0.0203916 -0.224973 -0.119581 0.0360425 -0.224773 -0.129205 0.0311306 -0.22772 -0.132992 0.0222075 -0.224973 -0.119076 0.037318 -0.224973 -0.120129 0.0397499 -0.228046 -0.120127 0.0397486 -0.224973 -0.119277 0.038675 -0.224973 -0.119107 0.0381269 -0.228275 -0.119094 0.0380511 -0.228349 -0.119131 0.0370075 -0.22772 -0.123837 0.0392017 -0.224973 -0.121405 0.0402546 -0.227826 -0.121978 0.0402584 -0.227842 -0.1218 0.0402705 -0.224973 -0.120697 0.0400713 -0.230111 -0.124194 0.03189 -0.229184 -0.128198 0.0204593 -0.228752 -0.128051 0.0204056 -0.228376 -0.12571 0.0258716 -0.228376 -0.124363 0.0285221 -0.228376 -0.12289 0.0311047 -0.229809 -0.126383 0.0261935 -0.229809 -0.128714 0.0206473 -0.228752 -0.119614 0.0360669 -0.229184 -0.11974 0.0361604 -0.229184 -0.12306 0.0312068 -0.229809 -0.12353 0.0314898 -0.229511 -0.119917 0.0362917 -0.230023 -0.129102 0.0207888 -0.230111 -0.127082 0.0265279 -0.229511 -0.128405 0.0205348 -0.229184 -0.125888 0.0259569 -0.230023 -0.120512 0.0367336 -0.230111 -0.129442 0.0209129 -0.23002 -0.127828 0.0268846 -0.23002 -0.126431 0.0296356 -0.22772 -0.129029 0.0310358 -0.224973 -0.129029 0.0310358 -0.224973 -0.132992 0.0222075 -0.229463 -0.131876 0.0211059 -0.229255 -0.13231 0.0208355 -0.229939 -0.130407 0.0200098 -0.229764 -0.130999 0.0199121 -0.230069 -0.129868 0.0203619 -0.229821 -0.130219 0.0196632 -0.229967 -0.129553 0.0200856 -0.229399 -0.13196 0.0214012 -0.229611 -0.13002 0.0193534 -0.229577 -0.131552 0.0200448 -0.229023 -0.132253 0.0199002 -0.228206 -0.132325 0.019409 -0.227944 -0.132141 0.0192167 -0.228087 -0.132897 0.0202142 -0.227726 -0.133119 0.021719 -0.227743 -0.133151 0.0212215 -0.229639 -0.131503 0.0207094 -0.229401 -0.132005 0.0203675 -0.22827 -0.133071 0.0212324 -0.228717 -0.128636 0.0194737 -0.228622 -0.129521 0.0188765 -0.228253 -0.129642 0.0187929 -0.228346 -0.131502 0.0188747 -0.228491 -0.130527 0.0186809 -0.228493 -0.132343 0.0195334 -0.228653 -0.131575 0.0190016 -0.22914 -0.130757 0.0189727 -0.229321 -0.129827 0.0191096 -0.229098 -0.128771 0.019524 -0.229458 -0.128977 0.0196461 -0.228823 -0.130643 0.0187861 -0.228981 -0.129657 0.0189496 -0.228238 -0.132918 0.0221807 -0.228766 -0.132822 0.0213164 -0.22873 -0.132691 0.0220977 -0.229157 -0.132427 0.0213936 -0.228993 -0.132476 0.0220193 -0.229365 -0.13191 0.0218129 -0.228869 -0.132666 0.0205511 -0.228359 -0.132865 0.020308 -0.22877 -0.13232 0.019699 -0.228949 -0.13162 0.019192 -0.229212 -0.131631 0.0194396 -0.229416 -0.130859 0.0192355 -0.229759 -0.129245 0.0198385 -0.229416 -0.120181 0.0390552 -0.229212 -0.120776 0.0395878 -0.22873 -0.123579 0.0390108 -0.229939 -0.12058 0.0382525 -0.229885 -0.121325 0.0382474 -0.229986 -0.121301 0.0378218 -0.23002 -0.121467 0.0374424 -0.229445 -0.122376 0.0388629 -0.229023 -0.121503 0.0398542 -0.229401 -0.121757 0.0393895 -0.22969 -0.121647 0.0387078 -0.229577 -0.121238 0.0391889 -0.229821 -0.120186 0.0382856 -0.229611 -0.119818 0.0382897 -0.229764 -0.120823 0.0388001 -0.230069 -0.120577 0.0376089 -0.230111 -0.120803 0.0369495 -0.229967 -0.120173 0.0374973 -0.228362 -0.119217 0.0367213 -0.228168 -0.119449 0.0390068 -0.228142 -0.119574 0.0391929 -0.228346 -0.120233 0.0397902 -0.228376 -0.119581 0.0360425 -0.227983 -0.120565 0.0400128 -0.227924 -0.121034 0.0401848 -0.227819 -0.122054 0.0402495 -0.227748 -0.123023 0.0399231 -0.229157 -0.122846 0.0391772 -0.228771 -0.121371 0.0400204 -0.228493 -0.121246 0.0401309 -0.228653 -0.120379 0.0397812 -0.228981 -0.119282 0.0382092 -0.229098 -0.119273 0.0371532 -0.228717 -0.119158 0.0370688 -0.228622 -0.119145 0.0381356 -0.228491 -0.119535 0.0390828 -0.228823 -0.119687 0.0391219 -0.228206 -0.121132 0.0401843 -0.228087 -0.12212 0.0402186 -0.228359 -0.122181 0.0401407 -0.22827 -0.123066 0.0398038 -0.228766 -0.122999 0.0395496 -0.229365 -0.122912 0.0385153 -0.229255 -0.122316 0.0393865 -0.228869 -0.122274 0.0398409 -0.228949 -0.120563 0.0397141 -0.22914 -0.119905 0.0391143 -0.229321 -0.119509 0.0382631 -0.229759 -0.119797 0.0373767 -0.229458 -0.119489 0.0372584 -0.229809 -0.12018 0.0364873 -0.230009 -0.130327 0.0209875 -0.23002 -0.130219 0.0211962 -0.229938 -0.130632 0.0207111 -0.229919 -0.1307 0.0206771 -0.229803 -0.131065 0.0205972 -0.229497 -0.131816 0.021 -0.22969 -0.131375 0.0206511 -0.229578 -0.12193 0.0388482 -0.229376 -0.122748 0.0386851 -0.229463 -0.122303 0.038876 -0.229692 -0.122189 0.0379789 -0.229741 -0.121542 0.0386154 -0.229365 -0.125609 0.0345947 -0.23002 -0.124902 0.0323168 -0.229365 -0.130119 0.0262217 -0.229692 -0.131065 0.0215046 -0.228414 -0.132857 0.0221584 -0.229365 -0.128015 0.0304897 -0.228993 -0.126117 0.0349179 -0.228993 -0.123396 0.0388744 -0.228414 -0.126459 0.0351357 -0.228993 -0.128546 0.0307754 -0.228993 -0.130669 0.0264683 -0.228414 -0.123722 0.0391164 -0.228238 -0.123774 0.0391551 -0.228414 -0.128903 0.0309679 -0.22772 -0.12658 0.0352125 -0.228414 -0.131039 0.0266346 -0.22772 -0.13117 0.0266932 -0.224773 -0.129087 0.0188258 -0.224773 -0.129184 0.0185306 -0.224773 -0.126466 0.0254389 -0.224573 -0.123115 0.0320797 -0.224573 -0.133938 0.0200804 -0.224773 -0.134128 0.0201424 -0.224573 -0.118453 0.0404989 -0.224573 -0.118618 0.0408522 -0.224773 -0.118444 0.0409511 -0.224573 -0.119035 0.0413901 -0.224573 -0.119418 0.0416915 -0.224573 -0.12166 0.0418667 -0.224773 -0.122737 0.0412864 -0.224773 -0.12174 0.0420501 -0.224573 -0.121004 0.0420466 -0.224573 -0.120517 0.0420581 -0.224573 -0.119945 0.0419422 -0.224573 -0.134004 0.0188399 -0.224773 -0.1342 0.0187985 -0.224773 -0.13359 0.0175987 -0.224573 -0.132935 0.0173057 -0.224773 -0.132462 0.0168646 -0.224573 -0.13182 0.0169421 -0.224773 -0.131118 0.0167928 -0.224573 -0.131159 0.0169885 -0.224773 -0.118864 0.0378011 -0.224773 -0.127825 0.0203231 -0.224773 -0.124187 0.0284272 -0.224773 -0.122945 0.0319745 -0.222663 -0.119208 0.0415417 -0.222675 -0.119303 0.0416137 -0.222784 -0.120375 0.0420428 -0.222832 -0.121004 0.0420467 -0.222865 -0.121532 0.0419184 -0.229365 -0.096183 0.0597088 -0.229938 -0.111771 0.0481499 -0.229919 -0.111846 0.0481542 -0.229497 -0.112652 0.0489922 -0.229639 -0.112526 0.048584 -0.229692 -0.111749 0.0490533 -0.22969 -0.112445 0.0484696 -0.229803 -0.112203 0.0482677 -0.229986 -0.095135 0.0583028 -0.229885 -0.0949422 0.0586829 -0.229692 -0.0958254 0.0588828 -0.229365 -0.100479 0.0576617 -0.23002 -0.101006 0.0553356 -0.23002 -0.10367 0.0537781 -0.22873 -0.0965132 0.0604715 -0.228414 -0.0965836 0.0606341 -0.229365 -0.112327 0.0497431 -0.228993 -0.108924 0.0531542 -0.229365 -0.108572 0.0526658 -0.229365 -0.104615 0.0553099 -0.228993 -0.0964223 0.0602616 -0.228993 -0.100757 0.0581958 -0.228414 -0.100945 0.0585557 -0.228993 -0.104932 0.0558225 -0.228414 -0.109162 0.0534834 -0.22873 -0.112861 0.0503801 -0.228238 -0.0966094 0.0606937 -0.228414 -0.105145 0.056168 -0.22772 -0.101011 0.0586826 -0.22772 -0.10522 0.0562898 -0.224773 -0.0927458 0.0571806 -0.224773 -0.115083 0.0494053 -0.224573 -0.108675 0.0542517 -0.224573 -0.10185 0.0584645 -0.224773 -0.10879 0.0544154 -0.224773 -0.101945 0.0586406 -0.224773 -0.0914246 0.0608662 -0.224773 -0.091097 0.0596774 -0.224573 -0.0912969 0.0596715 -0.224573 -0.0915993 0.0607689 -0.224573 -0.0919837 0.0612826 -0.224573 -0.0934448 0.0619877 -0.224773 -0.0946459 0.0620211 -0.224773 -0.0922631 0.0617704 -0.224573 -0.0928214 0.0618358 -0.224573 -0.0923733 0.0616035 -0.224573 -0.114949 0.0492565 -0.224773 -0.11594 0.0473185 -0.224573 -0.115745 0.0474917 -0.224773 -0.115617 0.0462075 -0.224573 -0.111741 0.0456862 -0.224773 -0.112618 0.044975 -0.224773 -0.113773 0.0449069 -0.224573 -0.11374 0.0451042 -0.224773 -0.0930348 0.0570664 -0.224773 -0.111375 0.0457446 -0.224773 -0.105799 0.0501613 -0.224773 -0.0994822 0.0540608 -0.224773 -0.0934326 0.0564685 -0.222685 -0.0915497 0.060675 -0.224573 -0.0914456 0.0604352 -0.222663 -0.0914617 0.0604774 -0.222436 -0.112327 0.045298 -0.224573 -0.112674 0.045167 -0.224573 -0.11358 0.045083 -0.222445 -0.112573 0.0451989 -0.224573 -0.114728 0.0455102 -0.224573 -0.115565 0.0483838 -0.222827 -0.115743 0.0475607 -0.222822 -0.115745 0.0474916 -0.222807 -0.115738 0.0472844 -0.224573 -0.115741 0.0473303 -0.224573 -0.115442 0.0463047 -0.222751 -0.115599 0.0466467 -0.222899 -0.108675 0.0542517 -0.222899 -0.10185 0.0584645 -0.224573 -0.0945728 0.0618349 -0.224573 -0.0995769 0.054237 -0.224573 -0.105914 0.0503249 -0.221254 -0.0941521 0.060763 -0.221159 -0.0935633 0.0607094 -0.22123 -0.0938549 0.060806 -0.221469 -0.0938452 0.0612719 -0.220795 -0.0934876 0.059667 -0.220951 -0.0922852 0.0594532 -0.221035 -0.092381 0.0585578 -0.220826 -0.0926357 0.0588591 -0.221283 -0.0923885 0.0606534 -0.221326 -0.0918922 0.06001 -0.220978 -0.092573 0.0601333 -0.220833 -0.0926367 0.0596335 -0.220725 -0.0929198 0.059168 -0.220691 -0.0933749 0.0587832 -0.221652 -0.0925229 0.0612143 -0.221564 -0.0932415 0.0613891 -0.222756 -0.0919836 0.0612825 -0.222287 -0.0928664 0.0617597 -0.222469 -0.0920326 0.0612982 -0.222836 -0.0928211 0.0618357 -0.2228 -0.0923846 0.061611 -0.222794 -0.0923177 0.0615657 -0.222899 -0.0945728 0.0618349 -0.222874 -0.0934789 0.061991 -0.222077 -0.0920008 0.0579579 -0.222363 -0.0915291 0.0605685 -0.222583 -0.0912969 0.0596715 -0.222252 -0.0913287 0.0596918 -0.222519 -0.091389 0.0589389 -0.222498 -0.0914812 0.0586761 -0.222448 -0.0919619 0.0579415 -0.222055 -0.0916579 0.0606381 -0.221919 -0.0914369 0.0598053 -0.221695 -0.0920545 0.0580909 -0.221335 -0.0921819 0.0582941 -0.221618 -0.0928912 0.0575508 -0.222182 -0.0921577 0.0613132 -0.22215 -0.0914804 0.058775 -0.221791 -0.091557 0.0589094 -0.222049 -0.0928339 0.057405 -0.22186 -0.0937775 0.0616691 -0.221056 -0.0933492 0.0604901 -0.221131 -0.092702 0.0605897 -0.221391 -0.0933813 0.0611909 -0.222357 -0.0936993 0.0619203 -0.222382 -0.0945442 0.0617621 -0.222559 -0.0927733 0.0617936 -0.221777 -0.0931052 0.0615549 -0.221904 -0.092323 0.0612858 -0.22176 -0.0918497 0.0606784 -0.221496 -0.092098 0.060684 -0.221602 -0.0916265 0.0599143 -0.221161 -0.0919702 0.0592617 -0.221451 -0.0917214 0.0590752 -0.221496 -0.115029 0.0465276 -0.221889 -0.114735 0.0490182 -0.220806 -0.113573 0.0472889 -0.220725 -0.113306 0.0465836 -0.221469 -0.114772 0.0483539 -0.221183 -0.114398 0.0479379 -0.221391 -0.114907 0.0479028 -0.221274 -0.114873 0.0474418 -0.221131 -0.114674 0.0470257 -0.220978 -0.114324 0.0467061 -0.221035 -0.113002 0.0458285 -0.220878 -0.11388 0.0472769 -0.220833 -0.113849 0.0465392 -0.220951 -0.113845 0.0461442 -0.220826 -0.113157 0.0461912 -0.220778 -0.112516 0.0465489 -0.222498 -0.113511 0.0450771 -0.22215 -0.1136 0.0451208 -0.22259 -0.114548 0.0453947 -0.222252 -0.114486 0.0453957 -0.222606 -0.114684 0.0454797 -0.222077 -0.112636 0.0452197 -0.222049 -0.111768 0.0457167 -0.222363 -0.11518 0.0459672 -0.222663 -0.115129 0.0458661 -0.222704 -0.11538 0.0461989 -0.222721 -0.115468 0.046352 -0.222559 -0.115719 0.0476295 -0.222357 -0.115417 0.0485142 -0.222877 -0.11555 0.0484177 -0.222381 -0.114897 0.0491984 -0.222206 -0.114853 0.0491501 -0.22186 -0.115157 0.0484715 -0.221777 -0.115356 0.0478192 -0.221602 -0.114552 0.0457616 -0.221451 -0.11376 0.0454708 -0.221791 -0.113685 0.0452495 -0.221695 -0.112731 0.0453273 -0.22129 -0.11202 0.0459973 -0.221618 -0.111873 0.0458333 -0.221919 -0.114539 0.0455433 -0.222055 -0.115185 0.0461136 -0.222469 -0.115607 0.0467446 -0.222182 -0.115565 0.0468631 -0.222287 -0.115647 0.0476976 -0.221254 -0.114179 0.0484001 -0.221241 -0.114317 0.0482268 -0.221652 -0.115313 0.0471455 -0.221904 -0.115466 0.0469988 -0.22176 -0.115135 0.0463031 -0.221326 -0.114519 0.0460421 -0.221161 -0.113815 0.0457768 -0.221335 -0.112856 0.0455323 -0.220992 -0.11224 0.0462413 -0.221626 -0.114582 0.0488481 -0.221497 -0.094316 0.0611806 -0.221626 -0.0943722 0.0613238 -0.221254 -0.101062 0.0575801 -0.221254 -0.101305 0.0574504 -0.221626 -0.108359 0.0538025 -0.221254 -0.108012 0.0533097 -0.221254 -0.108236 0.0531516 -0.222206 -0.0945205 0.0617017 -0.221889 -0.0944557 0.0615366 -0.222206 -0.101782 0.0583384 -0.221626 -0.10159 0.0579809 -0.222206 -0.108592 0.0541347 -0.222899 -0.114949 0.0492565 -0.220781 -0.100689 0.0563054 -0.220691 -0.100298 0.0555771 -0.220781 -0.11331 0.0474331 -0.220781 -0.107484 0.0520912 -0.220691 -0.112758 0.046818 -0.220781 -0.0936771 0.0595529 -0.220781 -0.100451 0.0564326 -0.220683 -0.0933993 0.0588453 -0.220992 -0.0999303 0.0548942 -0.220781 -0.107265 0.0522462 -0.220778 -0.0932427 0.0584463 -0.220992 -0.106343 0.0509354 -0.220691 -0.106789 0.0515697 -0.222426 -0.105914 0.0503249 -0.222426 -0.111741 0.0456862 -0.220992 -0.0930916 0.0580614 -0.22129 -0.0929717 0.0577561 -0.221618 -0.0996705 0.0544111 -0.221618 -0.106028 0.0504867 -0.222426 -0.0995769 0.054237 -0.222426 -0.0928189 0.0573668 -0.220939 -0.0932601 0.0601798 -0.220853 -0.0933113 0.0599077 -0.221018 -0.0939146 0.060158 -0.221019 -0.0933039 0.0603975 -0.220854 -0.113793 0.0472652 -0.220981 -0.114158 0.0474071 -0.221098 -0.11435 0.0476665 -0.221018 -0.113745 0.0479166 -0.224573 -0.0914664 0.0587122 -0.224573 -0.0920033 0.0578993 -0.224573 -0.0928189 0.0573668 -0.222443 -0.0920383 0.0578652 -0.224773 -0.0912807 0.0586382 -0.224773 -0.0918622 0.0577576 -0.227953 -0.113795 0.0475387 -0.228046 -0.113395 0.0468918 -0.224973 -0.112959 0.0464782 -0.224973 -0.111886 0.0459963 -0.228168 -0.112614 0.0462579 -0.228252 -0.111879 0.0459951 -0.228275 -0.111638 0.0459588 -0.224973 -0.109662 0.0465635 -0.228376 -0.109662 0.0465635 -0.224773 -0.109534 0.0464102 -0.224773 -0.11066 0.045833 -0.224973 -0.110709 0.0460268 -0.224973 -0.114013 0.0485165 -0.224973 -0.113718 0.0473774 -0.224773 -0.0967199 0.060949 -0.224773 -0.095473 0.0611813 -0.224773 -0.0942488 0.0608496 -0.224973 -0.0945029 0.0607514 -0.224973 -0.0943427 0.060673 -0.224773 -0.0927858 0.0588556 -0.224973 -0.0930298 0.0576405 -0.224973 -0.0930822 0.05747 -0.224973 -0.0945347 0.0559017 -0.224773 -0.0944552 0.0557182 -0.224973 -0.0935838 0.0565994 -0.224773 -0.113964 0.0497617 -0.224773 -0.11575 0.0484598 -0.224773 -0.113896 0.0472855 -0.224773 -0.11308 0.0463185 -0.224773 -0.114844 0.0453468 -0.224773 -0.111925 0.0458003 -0.224773 -0.111607 0.0455375 -0.224773 -0.0928368 0.0575882 -0.224773 -0.0932897 0.0600195 -0.224773 -0.0934239 0.0621866 -0.224773 -0.113195 0.0507789 -0.224773 -0.114213 0.0485106 -0.224773 -0.102331 0.0516097 -0.228376 -0.104928 0.0501577 -0.224973 -0.102436 0.0517798 -0.224973 -0.10522 0.0562898 -0.224773 -0.105325 0.0564599 -0.22772 -0.113066 0.0506256 -0.224973 -0.113782 0.0496798 -0.227819 -0.114007 0.0487842 -0.228362 -0.0938797 0.0563073 -0.228349 -0.0936625 0.0565124 -0.228168 -0.0929385 0.058403 -0.224973 -0.0929824 0.0588189 -0.228142 -0.0929538 0.0586267 -0.228046 -0.0931549 0.0593845 -0.224973 -0.093451 0.0599012 -0.227983 -0.0934021 0.0598323 -0.224973 -0.0954811 0.0609814 -0.22772 -0.0966405 0.0607654 -0.227748 -0.0955755 0.0609835 -0.227819 -0.0945727 0.0607816 -0.230111 -0.0951392 0.057298 -0.229511 -0.109931 0.0468839 -0.229184 -0.10504 0.0503208 -0.228376 -0.102436 0.0517798 -0.228376 -0.0998696 0.0532801 -0.229184 -0.0999652 0.0534532 -0.229511 -0.0947008 0.0562854 -0.229809 -0.100231 0.0539333 -0.230111 -0.105788 0.0514125 -0.230023 -0.110407 0.047452 -0.229809 -0.10535 0.0507731 -0.230111 -0.100606 0.0546119 -0.23002 -0.111171 0.0483635 -0.23002 -0.106256 0.0520945 -0.224973 -0.0966405 0.0607654 -0.224973 -0.113066 0.0506256 -0.22772 -0.109246 0.0535994 -0.229577 -0.112901 0.0480331 -0.229212 -0.113272 0.0475484 -0.229463 -0.112651 0.0491139 -0.229255 -0.113161 0.0490964 -0.230009 -0.111369 0.0482369 -0.229939 -0.111927 0.0474302 -0.229764 -0.112489 0.0476416 -0.229023 -0.11358 0.0482583 -0.228653 -0.113442 0.0471407 -0.228206 -0.113888 0.0478688 -0.227757 -0.113812 0.0496112 -0.228238 -0.113016 0.0505657 -0.227747 -0.113729 0.0497916 -0.227844 -0.114013 0.0485165 -0.228087 -0.11398 0.0488519 -0.228359 -0.113906 0.0489172 -0.228493 -0.113842 0.0479855 -0.22827 -0.113622 0.0498207 -0.22877 -0.113739 0.0481173 -0.228869 -0.113613 0.0490284 -0.228949 -0.113386 0.0473281 -0.22811 -0.113019 0.0465248 -0.229809 -0.110141 0.0471354 -0.229759 -0.111006 0.0467008 -0.229184 -0.109789 0.046715 -0.229458 -0.11087 0.0464 -0.228752 -0.109688 0.0465949 -0.228717 -0.110661 0.0460804 -0.228491 -0.112695 0.0463393 -0.228622 -0.111726 0.0460054 -0.229321 -0.111874 0.0463604 -0.229967 -0.111149 0.0470685 -0.229611 -0.111919 0.0466678 -0.229098 -0.110752 0.0461911 -0.228981 -0.111807 0.0461369 -0.228348 -0.11062 0.0460511 -0.229157 -0.112984 0.0496382 -0.228993 -0.112714 0.0502048 -0.229399 -0.112576 0.0494117 -0.229401 -0.113132 0.0485387 -0.228766 -0.113365 0.0497689 -0.228414 -0.112974 0.050516 -0.228346 -0.113442 0.0469945 -0.228823 -0.112743 0.0464884 -0.22914 -0.112748 0.0467069 -0.229416 -0.112705 0.0469856 -0.229821 -0.111937 0.0470357 -0.230069 -0.111284 0.0474656 -0.230111 -0.110639 0.0477297 -0.229416 -0.0935481 0.0588108 -0.229212 -0.0937968 0.0595694 -0.229577 -0.0943966 0.0594552 -0.229741 -0.0949461 0.0591101 -0.229939 -0.0942945 0.0583149 -0.230069 -0.0946141 0.0577563 -0.23002 -0.0954678 0.0580569 -0.229376 -0.0959561 0.0597738 -0.229445 -0.0955454 0.0597419 -0.229463 -0.0954752 0.0597166 -0.229255 -0.0952309 0.060165 -0.229401 -0.0947454 0.0598881 -0.229023 -0.0942933 0.0601637 -0.229578 -0.0951657 0.0595058 -0.22969 -0.0949915 0.059243 -0.229821 -0.0939374 0.0581469 -0.229759 -0.0940548 0.0571653 -0.230023 -0.0949953 0.0569657 -0.229809 -0.0948312 0.0565865 -0.229764 -0.0942318 0.0589111 -0.229967 -0.0943197 0.0574574 -0.228717 -0.0936548 0.0565787 -0.228275 -0.0931084 0.0573976 -0.228752 -0.094551 0.0559393 -0.228376 -0.0945347 0.0559017 -0.227842 -0.0943427 0.0606729 -0.228346 -0.0932252 0.0594732 -0.227966 -0.0934866 0.0599486 -0.227924 -0.0937219 0.0602156 -0.227826 -0.0945027 0.0607513 -0.228087 -0.0946453 0.0607878 -0.22827 -0.0956721 0.0609016 -0.228869 -0.094968 0.060538 -0.228771 -0.0940963 0.0602419 -0.228493 -0.0939323 0.0602748 -0.228949 -0.0935489 0.0595722 -0.228823 -0.0930868 0.0586216 -0.228981 -0.093192 0.0576284 -0.229321 -0.0933616 0.0577885 -0.229458 -0.093847 0.0569086 -0.229098 -0.0937129 0.0567099 -0.229184 -0.0946132 0.0560832 -0.228622 -0.0931109 0.0574966 -0.228491 -0.0929749 0.0585118 -0.228653 -0.0933562 0.0595384 -0.228206 -0.0938071 0.0602642 -0.228359 -0.094737 0.0607507 -0.228766 -0.0957413 0.060648 -0.229157 -0.095795 0.060249 -0.22914 -0.0932797 0.0587241 -0.229611 -0.0936164 0.0579663 -0.222899 -0.0839162 0.0650294 -0.221889 -0.0838499 0.0647159 -0.221626 -0.0838026 0.0644922 -0.220781 -0.083409 0.062631 -0.220691 -0.0832378 0.061822 -0.220806 -0.0837087 0.0626375 -0.220854 -0.0839109 0.0627269 -0.220878 -0.0839805 0.0627806 -0.221391 -0.0845569 0.0638362 -0.221274 -0.0847578 0.0634198 -0.221131 -0.0847934 0.0629598 -0.220978 -0.08465 0.062508 -0.221326 -0.0851507 0.0620303 -0.220826 -0.0838971 0.0614789 -0.221035 -0.0839442 0.0610872 -0.220833 -0.0843221 0.0621261 -0.220951 -0.0845165 0.0617822 -0.220725 -0.0838298 0.0618931 -0.220778 -0.083163 0.061468 -0.222436 -0.0836246 0.0602901 -0.222445 -0.0838873 0.0603274 -0.222498 -0.0847605 0.0606909 -0.222077 -0.0839317 0.060377 -0.222252 -0.0854461 0.0614545 -0.221618 -0.0829639 0.0605268 -0.222559 -0.0853962 0.0640051 -0.222663 -0.0857673 0.0621832 -0.222704 -0.0858181 0.0625968 -0.222827 -0.085452 0.0639579 -0.222357 -0.0846924 0.0646204 -0.222381 -0.0839001 0.0649529 -0.221777 -0.0849877 0.0639883 -0.222182 -0.0856462 0.0632646 -0.221919 -0.0854182 0.0616088 -0.221451 -0.0847794 0.0611564 -0.221791 -0.0848255 0.0609275 -0.22129 -0.0830095 0.0607425 -0.221695 -0.08396 0.0605176 -0.22215 -0.0848156 0.0607731 -0.222363 -0.0857612 0.0622963 -0.222055 -0.0856919 0.0624254 -0.222469 -0.0857424 0.0631832 -0.222287 -0.0852998 0.0640281 -0.22186 -0.084489 0.0644536 -0.221469 -0.084214 0.0641591 -0.221241 -0.0838837 0.0638216 -0.221652 -0.0852868 0.0633831 -0.221496 -0.0853497 0.062706 -0.221904 -0.0854931 0.0633327 -0.22176 -0.085554 0.0625647 -0.221602 -0.0853198 0.0618042 -0.221161 -0.0846742 0.061449 -0.221335 -0.0839655 0.0607574 -0.220992 -0.0830774 0.0610634 -0.221626 -0.067985 0.0659055 -0.221254 -0.0761554 0.0650463 -0.221497 -0.0600855 0.0650394 -0.221254 -0.0680032 0.0653034 -0.221626 -0.075936 0.0656713 -0.222382 -0.0599924 0.0656572 -0.222899 -0.0679684 0.0664543 -0.222206 -0.0759721 0.0660756 -0.222206 -0.0838866 0.0648894 -0.222206 -0.0679727 0.0663113 -0.220781 -0.0757667 0.0637765 -0.220781 -0.0760344 0.063752 -0.220781 -0.0677729 0.0639953 -0.220781 -0.0680424 0.064004 -0.220691 -0.0756931 0.0629528 -0.220683 -0.0604592 0.0625587 -0.220691 -0.0604692 0.0624926 -0.220691 -0.0680674 0.0631774 -0.220778 -0.0605231 0.0621348 -0.222426 -0.0755577 0.0614372 -0.221618 -0.0755753 0.0616342 -0.222049 -0.0829315 0.0603734 -0.220992 -0.0680908 0.0624024 -0.220992 -0.0605847 0.061726 -0.220992 -0.0756241 0.0621805 -0.222426 -0.0681134 0.0616565 -0.221618 -0.0681074 0.0618542 -0.222049 -0.0606898 0.0610286 -0.222426 -0.0606959 0.060988 -0.220795 -0.0601249 0.0633144 -0.221018 -0.0602492 0.0639531 -0.221159 -0.0596692 0.064255 -0.221056 -0.0595934 0.063958 -0.221019 -0.0596005 0.0638552 -0.221254 -0.083678 0.0639029 -0.221183 -0.0840981 0.0636118 -0.221018 -0.0835435 0.0632669 -0.221098 -0.0841926 0.0633529 -0.220981 -0.0841557 0.0630321 -0.221254 -0.0758824 0.0650713 -0.221254 -0.0677283 0.0652945 -0.221254 -0.0601523 0.0645959 -0.222448 -0.0596664 0.0610573 -0.224573 -0.0581353 0.062409 -0.224573 -0.0587462 0.0615654 -0.224573 -0.0596569 0.06106 -0.224773 -0.0596001 0.0608683 -0.224973 -0.0837916 0.0625857 -0.228046 -0.0837526 0.0622044 -0.224973 -0.0835193 0.0614914 -0.228168 -0.0833936 0.0612652 -0.224973 -0.0828167 0.0606094 -0.228275 -0.0826981 0.0605182 -0.224773 -0.0818614 0.0599058 -0.224973 -0.0806842 0.0600537 -0.224973 -0.081811 0.0600994 -0.224773 -0.0825774 0.0602012 -0.224773 -0.0836987 0.0614029 -0.228376 -0.0718182 0.0609583 -0.224973 -0.0629143 0.0605771 -0.224773 -0.0622832 0.0660408 -0.224773 -0.0719801 0.0664559 -0.224973 -0.0816012 0.0652738 -0.227721 -0.0817403 0.0652455 -0.227763 -0.0828402 0.0646989 -0.227819 -0.083337 0.0641496 -0.224973 -0.0827451 0.0647744 -0.224973 -0.0835335 0.0638068 -0.227871 -0.0835931 0.0636727 -0.228362 -0.0621443 0.0606009 -0.224973 -0.061742 0.0607059 -0.228275 -0.0609312 0.0611595 -0.228168 -0.0602813 0.0619453 -0.224973 -0.0601114 0.0623274 -0.224973 -0.0611941 0.0654495 -0.224973 -0.0603625 0.0646132 -0.224973 -0.0599761 0.063499 -0.227924 -0.0600535 0.0639067 -0.229809 -0.0688313 0.0617203 -0.228752 -0.0806913 0.0600941 -0.228376 -0.0747869 0.0607992 -0.229184 -0.0748022 0.0609963 -0.229184 -0.0688416 0.0611719 -0.228376 -0.0688453 0.0609742 -0.228376 -0.0629143 0.0605771 -0.229809 -0.0808133 0.0607887 -0.228752 -0.0629096 0.0606179 -0.230111 -0.0809475 0.0615523 -0.229511 -0.0807566 0.0604654 -0.229809 -0.0748448 0.0615432 -0.230111 -0.0749049 0.0623162 -0.230111 -0.0688168 0.0624955 -0.23002 -0.0718878 0.0633058 -0.224973 -0.0719742 0.066256 -0.229939 -0.0822122 0.0619368 -0.229938 -0.0817173 0.0624821 -0.229919 -0.0817805 0.0625235 -0.229577 -0.0827544 0.0629459 -0.230023 -0.0808848 0.0611956 -0.229967 -0.0817193 0.0612345 -0.230069 -0.0816379 0.061646 -0.230009 -0.0813254 0.0623562 -0.229611 -0.0825867 0.0612726 -0.229416 -0.0831088 0.0619409 -0.229821 -0.0824181 0.0616 -0.229764 -0.0825928 0.0624006 -0.227924 -0.0837359 0.0632098 -0.228087 -0.0832798 0.0641947 -0.228206 -0.0836915 0.0632972 -0.227863 -0.0835601 0.0637495 -0.22969 -0.0821409 0.0630957 -0.229639 -0.0821543 0.0632356 -0.229401 -0.0827012 0.063499 -0.228869 -0.0828729 0.0641636 -0.229255 -0.0824482 0.0639969 -0.228766 -0.0822878 0.0646809 -0.228376 -0.0806842 0.0600537 -0.228348 -0.0817703 0.0600891 -0.228257 -0.0828524 0.0606391 -0.228622 -0.0827505 0.0606023 -0.228491 -0.083423 0.0613761 -0.227999 -0.0837916 0.0625857 -0.228116 -0.0835931 0.0616548 -0.228359 -0.0831828 0.0642142 -0.228493 -0.0835927 0.0633749 -0.228949 -0.0835267 0.0625777 -0.228823 -0.0833899 0.0615292 -0.22914 -0.0832852 0.061721 -0.229098 -0.0818146 0.0602764 -0.229458 -0.081812 0.0605161 -0.229184 -0.0807184 0.0602484 -0.228346 -0.0837426 0.0623171 -0.228653 -0.0836691 0.0624436 -0.228981 -0.0827553 0.0607569 -0.228717 -0.081791 0.060135 -0.22772 -0.0816012 0.0652738 -0.228238 -0.0815877 0.0651968 -0.228414 -0.0815765 0.0651328 -0.22873 -0.0815458 0.0649583 -0.229157 -0.0820234 0.0643773 -0.229399 -0.0817836 0.0639773 -0.227747 -0.0825917 0.0648825 -0.22827 -0.0824851 0.0648546 -0.22877 -0.0834377 0.0634376 -0.229023 -0.0832302 0.0634806 -0.229212 -0.0833181 0.0627117 -0.229321 -0.0827017 0.060984 -0.229759 -0.0817797 0.0608448 -0.228766 -0.0615861 0.0652909 -0.229741 -0.0616664 0.0635614 -0.229939 -0.0614997 0.062547 -0.229986 -0.0622336 0.0629567 -0.23002 -0.0626448 0.0629102 -0.230111 -0.0627397 0.0620887 -0.229157 -0.0618321 0.0649721 -0.229365 -0.0624383 0.0646983 -0.229445 -0.0618695 0.0644082 -0.229255 -0.0613856 0.0646174 -0.229463 -0.0618214 0.0643512 -0.229401 -0.0611036 0.0641348 -0.229578 -0.0616588 0.0640139 -0.229023 -0.0605743 0.0641475 -0.229577 -0.061018 0.0635854 -0.229967 -0.0619503 0.0618169 -0.229611 -0.0610867 0.061906 -0.229759 -0.061867 0.0614315 -0.229764 -0.0611474 0.0630319 -0.229821 -0.0612744 0.0622229 -0.230069 -0.0620558 0.0622229 -0.230023 -0.0627813 0.0617288 -0.228717 -0.0618138 0.0607235 -0.228349 -0.0618536 0.0606699 -0.228142 -0.0601827 0.0621466 -0.228491 -0.0602585 0.0620577 -0.229184 -0.0628916 0.0607736 -0.227842 -0.0603624 0.0646131 -0.227826 -0.0604618 0.064761 -0.228046 -0.059978 0.0629034 -0.227983 -0.0599682 0.0634148 -0.228206 -0.060103 0.0639913 -0.227966 -0.0599832 0.0635578 -0.228087 -0.0605671 0.0648639 -0.227819 -0.0605074 0.0648222 -0.227748 -0.0612748 0.0654985 -0.22827 -0.0613994 0.0654759 -0.228993 -0.0623691 0.0652967 -0.228359 -0.0606651 0.0648777 -0.228493 -0.0602061 0.0640632 -0.22914 -0.0604163 0.0623939 -0.228823 -0.0603005 0.0622086 -0.229321 -0.060955 0.0616246 -0.229458 -0.0618153 0.0611053 -0.229098 -0.0617986 0.0608661 -0.228622 -0.0608838 0.0612465 -0.228981 -0.0608881 0.0614012 -0.228653 -0.0600754 0.0631373 -0.228346 -0.0599946 0.0630154 -0.22873 -0.0623429 0.0655239 -0.229376 -0.0622092 0.0646412 -0.228869 -0.0609715 0.0648089 -0.228771 -0.0603646 0.0641167 -0.228949 -0.0602254 0.063263 -0.229212 -0.0604415 0.0633846 -0.229416 -0.0606053 0.0626032 -0.229809 -0.0628287 0.0613185 -0.229511 -0.0628663 0.0609924 -0.23002 -0.0810906 0.0623668 -0.229463 -0.0819974 0.0637568 -0.229497 -0.0820592 0.063652 -0.229803 -0.0820324 0.0627999 -0.22969 -0.0616393 0.0636992 -0.229692 -0.0625415 0.0638042 -0.229885 -0.0618766 0.0631895 -0.23002 -0.0688013 0.0633224 -0.229365 -0.0719403 0.065105 -0.229365 -0.0766886 0.0647932 -0.23002 -0.074969 0.0631407 -0.229692 -0.0812463 0.0632532 -0.229365 -0.081402 0.0641397 -0.22772 -0.0623061 0.0658421 -0.228993 -0.0815062 0.064733 -0.228993 -0.0767498 0.0653925 -0.229365 -0.067182 0.0650733 -0.228993 -0.0671562 0.0656751 -0.228993 -0.0719581 0.0657071 -0.228414 -0.0671388 0.0660807 -0.228414 -0.0623226 0.0657 -0.228238 -0.0623151 0.0657645 -0.22772 -0.0671327 0.0662237 -0.228414 -0.07197 0.0661129 -0.228414 -0.076791 0.0657964 -0.22772 -0.0719742 0.066256 -0.22772 -0.0768055 0.0659388 -0.224773 -0.0828816 0.0601376 -0.224573 -0.0681134 0.0616565 -0.224773 -0.0839576 0.0652251 -0.224773 -0.0760027 0.0664174 -0.224573 -0.0759849 0.0662182 -0.224573 -0.0679684 0.0664543 -0.224773 -0.059951 0.0659322 -0.224573 -0.0589566 0.0653236 -0.224773 -0.0580484 0.0645926 -0.224573 -0.0839162 0.0650294 -0.224773 -0.0858915 0.0634873 -0.224573 -0.0854878 0.063899 -0.224573 -0.0857677 0.0621847 -0.224573 -0.0841635 0.0603996 -0.224773 -0.0842255 0.0602094 -0.224773 -0.0853535 0.0609436 -0.224573 -0.0855751 0.0616261 -0.224773 -0.0806496 0.0598567 -0.224773 -0.0755399 0.061238 -0.224773 -0.0718123 0.0607583 -0.224773 -0.0681194 0.0614566 -0.224573 -0.0599808 0.0657345 -0.222873 -0.0589458 0.065316 -0.222827 -0.0583845 0.064755 -0.224573 -0.0582246 0.0644979 -0.224573 -0.0579394 0.0634319 -0.222426 -0.082923 0.0603333 -0.224573 -0.0848177 0.0607306 -0.224573 -0.0858178 0.0627735 -0.222721 -0.0858178 0.0627734 -0.224573 -0.0852048 0.0610772 -0.222606 -0.0855752 0.0616261 -0.22259 -0.0854999 0.0614845 -0.224573 -0.0850237 0.0644665 -0.222877 -0.0848565 0.0646037 -0.222822 -0.0854879 0.0638988 -0.224573 -0.0857014 0.0634253 -0.222807 -0.0855852 0.0637158 -0.222751 -0.0857838 0.0630941 -0.222899 -0.0759849 0.0662182 -0.222899 -0.0599808 0.0657345 -0.224573 -0.0606959 0.060988 -0.224573 -0.0755577 0.0614372 -0.224573 -0.082923 0.0603333 -0.220853 -0.0598518 0.0634348 -0.220833 -0.0594047 0.0628599 -0.220725 -0.0598826 0.0625984 -0.220781 -0.060346 0.0633104 -0.221161 -0.0590135 0.0622047 -0.220951 -0.0591904 0.0625281 -0.221035 -0.0597211 0.0618006 -0.220826 -0.0597911 0.0621888 -0.220978 -0.0590996 0.063261 -0.220939 -0.0596714 0.0636447 -0.221391 -0.0592709 0.064581 -0.222559 -0.058443 0.0647989 -0.2228 -0.0581969 0.0644449 -0.222469 -0.0580493 0.0639996 -0.222077 -0.0596918 0.0610909 -0.222498 -0.0588827 0.0614531 -0.22215 -0.0588325 0.0615383 -0.222515 -0.0587142 0.0615943 -0.222751 -0.0580026 0.0639131 -0.222705 -0.0579394 0.0634319 -0.222363 -0.057978 0.0631159 -0.222663 -0.0579652 0.0630033 -0.222252 -0.0582428 0.0622565 -0.222617 -0.0580824 0.0625421 -0.222575 -0.0582694 0.0621449 -0.221904 -0.0583069 0.0641341 -0.222055 -0.0580548 0.0632406 -0.221602 -0.0583895 0.0625981 -0.221919 -0.0582798 0.0624088 -0.22129 -0.0606336 0.0614016 -0.222182 -0.0581501 0.0640751 -0.221791 -0.0588318 0.0616931 -0.221695 -0.0596719 0.0612329 -0.221618 -0.0606664 0.0611836 -0.22123 -0.0598735 0.0644844 -0.221469 -0.0596321 0.0648831 -0.22186 -0.0593749 0.0651933 -0.221626 -0.0600626 0.0651915 -0.221889 -0.0600285 0.0654176 -0.221131 -0.0589832 0.0637207 -0.221283 -0.0586799 0.0636191 -0.221564 -0.0590507 0.0646828 -0.221777 -0.0588497 0.0647582 -0.222206 -0.0600021 0.065593 -0.222287 -0.0585406 0.0648162 -0.222357 -0.0591815 0.0653717 -0.221652 -0.0585158 0.0641721 -0.22176 -0.0582007 0.0633714 -0.221496 -0.0584129 0.0635003 -0.221451 -0.0588912 0.0619188 -0.221326 -0.0585717 0.0628138 -0.221335 -0.0596805 0.0614726 -0.224973 -0.0623061 0.0658421 -0.224773 -0.0601928 0.0647192 -0.224973 -0.060462 0.0647613 -0.224773 -0.0597773 0.0635208 -0.224773 -0.0606006 0.0611887 -0.224973 -0.0607416 0.0613306 -0.224973 -0.0608723 0.0612091 -0.224773 -0.0616765 0.0605169 -0.224773 -0.0816358 0.0654707 -0.224773 -0.082866 0.0649337 -0.224773 -0.0851574 0.0646153 -0.224773 -0.0839915 0.0625798 -0.224773 -0.0859633 0.0621433 -0.224773 -0.082943 0.0604543 -0.224773 -0.0610331 0.0608358 -0.224773 -0.0607257 0.0607903 -0.224773 -0.0586135 0.0614158 -0.224773 -0.0599228 0.0622608 -0.224773 -0.0837139 0.0638931 -0.224773 -0.0679623 0.0666542 -0.224773 -0.0610872 0.0656185 -0.224773 -0.0588415 0.0654872 -0.224773 -0.0577395 0.0634378 -0.224773 -0.0579517 0.0623297 -0.224773 -0.0629373 0.0603785 -0.224973 -0.0718182 0.0609583 -0.224773 -0.0279487 0.051972 -0.224773 -0.0269708 0.0500157 -0.224773 -0.050245 0.0634678 -0.224773 -0.0521292 0.0622267 -0.224573 -0.0515588 0.0591579 -0.224773 -0.0507045 0.058419 -0.224773 -0.0523337 0.0599798 -0.224773 -0.0372606 0.0521802 -0.224773 -0.031434 0.0480994 -0.224773 -0.048912 0.0570597 -0.222877 -0.0274179 0.0510021 -0.222827 -0.0271807 0.0501693 -0.224573 -0.0274229 0.0510122 -0.222816 -0.0271707 0.0500098 -0.222436 -0.0512717 0.0589226 -0.222445 -0.0514806 0.0590862 -0.224573 -0.0520847 0.0599006 -0.222498 -0.0520551 0.0598376 -0.224573 -0.0521464 0.0600499 -0.224573 -0.0522887 0.0611085 -0.222606 -0.052293 0.0610548 -0.222704 -0.052018 0.062017 -0.224573 -0.0502183 0.0632696 -0.224573 -0.0510809 0.0629795 -0.224573 -0.0512187 0.0628953 -0.222807 -0.0512568 0.0628696 -0.222751 -0.0517397 0.0624305 -0.224573 -0.0519576 0.062124 -0.222721 -0.0519295 0.0621697 -0.222899 -0.0491546 0.0631727 -0.224573 -0.0491546 0.0631727 -0.224573 -0.0416915 0.0602366 -0.224573 -0.0346309 0.0564328 -0.224573 -0.0371554 0.0523503 -0.224573 -0.043712 0.0558826 -0.222426 -0.043712 0.0558826 -0.221254 -0.0287912 0.0509153 -0.221497 -0.0285116 0.051266 -0.221159 -0.0285433 0.0503786 -0.220853 -0.0291116 0.0497595 -0.220795 -0.0294082 0.0497918 -0.220951 -0.0289921 0.0486436 -0.221161 -0.0290005 0.0482751 -0.221131 -0.0282163 0.0495728 -0.221283 -0.0280044 0.0493332 -0.220978 -0.028547 0.0492329 -0.220833 -0.0290118 0.0490381 -0.220826 -0.0296819 0.0486501 -0.220725 -0.0295564 0.0490506 -0.220691 -0.0301173 0.0492523 -0.221391 -0.0280353 0.0504617 -0.222559 -0.0272094 0.0502365 -0.222734 -0.0273299 0.0490768 -0.222382 -0.0281221 0.0517545 -0.222899 -0.0280734 0.0518156 -0.222513 -0.0290611 0.0475936 -0.222448 -0.0301397 0.0476078 -0.222077 -0.0301449 0.0476497 -0.222426 -0.0310659 0.0480626 -0.222363 -0.0276482 0.0485465 -0.222663 -0.0276934 0.0484426 -0.222621 -0.0279916 0.0481308 -0.222182 -0.0273176 0.0494632 -0.222055 -0.0276523 0.0486929 -0.22176 -0.0277133 0.0488791 -0.221602 -0.0282635 0.0483038 -0.221451 -0.0290376 0.0479663 -0.221335 -0.0299443 0.0479746 -0.222469 -0.0272681 0.0493474 -0.222252 -0.0283073 0.0479346 -0.221919 -0.0282631 0.048085 -0.22215 -0.0291771 0.0476075 -0.221791 -0.029099 0.0477411 -0.221695 -0.0300566 0.0477627 -0.221469 -0.0281971 0.050904 -0.221626 -0.0284157 0.0513863 -0.221889 -0.0282732 0.0515651 -0.221564 -0.0277938 0.0504398 -0.22186 -0.0278193 0.0510439 -0.222357 -0.0275626 0.0511018 -0.222206 -0.0281626 0.0517037 -0.222287 -0.0272853 0.0503002 -0.221777 -0.027582 0.0504046 -0.221904 -0.027424 0.0495927 -0.221652 -0.0275859 0.0497301 -0.221496 -0.0278326 0.0490969 -0.221326 -0.0283134 0.0485817 -0.221035 -0.0298154 0.0482789 -0.222381 -0.0491789 0.0630984 -0.221496 -0.0515578 0.0618773 -0.221131 -0.0509491 0.061819 -0.220781 -0.0499145 0.060842 -0.221241 -0.0497304 0.0621104 -0.221274 -0.0506883 0.0621995 -0.221183 -0.0500209 0.0620359 -0.220981 -0.0503607 0.0615628 -0.221326 -0.0517232 0.0611927 -0.221161 -0.0516012 0.060451 -0.220951 -0.0512981 0.0606607 -0.221035 -0.05115 0.0597726 -0.220878 -0.0503347 0.0612573 -0.220833 -0.0509578 0.0608613 -0.220978 -0.0510508 0.061356 -0.220725 -0.0506479 0.0604134 -0.220826 -0.0509134 0.0600883 -0.22259 -0.0522986 0.0608945 -0.222049 -0.0506298 0.0586481 -0.222077 -0.0514942 0.0591514 -0.222822 -0.051081 0.0629794 -0.222363 -0.0521189 0.0617283 -0.222663 -0.0521808 0.0616334 -0.222827 -0.0510204 0.0630126 -0.222877 -0.0501818 0.0632742 -0.222287 -0.0508535 0.0629973 -0.222182 -0.0515353 0.0625093 -0.222055 -0.0519944 0.0618055 -0.22176 -0.0518054 0.0618571 -0.221919 -0.0521656 0.0609614 -0.221451 -0.0518387 0.0602502 -0.221695 -0.0514484 0.0592873 -0.221618 -0.0505812 0.0587972 -0.22215 -0.0520617 0.0599363 -0.221791 -0.051993 0.060075 -0.222252 -0.0522669 0.0608417 -0.222469 -0.0516592 0.062487 -0.222559 -0.0509485 0.0630257 -0.22186 -0.0499385 0.0629604 -0.222357 -0.0500313 0.0632066 -0.221889 -0.049254 0.0628681 -0.221469 -0.0498477 0.0625679 -0.221777 -0.0506031 0.0628069 -0.221391 -0.0503061 0.0624597 -0.221652 -0.0511648 0.0624322 -0.221904 -0.0513686 0.0624918 -0.221602 -0.0519828 0.0610814 -0.221335 -0.0513333 0.0594977 -0.220992 -0.0504112 0.0593186 -0.22129 -0.0505128 0.0590068 -0.221626 -0.0349197 0.0559658 -0.221254 -0.0350029 0.0553083 -0.221254 -0.0352365 0.0554535 -0.221626 -0.0419226 0.0597385 -0.222899 -0.0346309 0.0564328 -0.221626 -0.0493248 0.0626507 -0.222206 -0.049199 0.0630367 -0.222206 -0.0347062 0.0563111 -0.222206 -0.0417517 0.0601067 -0.222899 -0.0416915 0.0602366 -0.221618 -0.0436288 0.0560619 -0.220691 -0.0501708 0.0600558 -0.221618 -0.0370514 0.0525185 -0.220992 -0.0433979 0.0565595 -0.220683 -0.0300756 0.0493046 -0.220781 -0.0429675 0.0581255 -0.220992 -0.0367629 0.052985 -0.220691 -0.0363551 0.0536444 -0.220778 -0.050283 0.0597118 -0.220691 -0.0430715 0.0572628 -0.222426 -0.0506425 0.0586092 -0.220778 -0.0303429 0.0489694 -0.220992 -0.0306007 0.0486461 -0.22129 -0.0308052 0.0483896 -0.221618 -0.0309426 0.0482172 -0.222049 -0.0310403 0.0480947 -0.222426 -0.0371554 0.0523503 -0.221018 -0.0291965 0.0504071 -0.221019 -0.0286837 0.049998 -0.220939 -0.0288504 0.0498512 -0.220781 -0.0296017 0.0498989 -0.221056 -0.0286262 0.0500835 -0.221018 -0.049713 0.06146 -0.221254 -0.0495115 0.062078 -0.221098 -0.0502322 0.061859 -0.220806 -0.0501709 0.0609975 -0.220854 -0.0503012 0.061176 -0.220781 -0.0427234 0.0580129 -0.221254 -0.0424251 0.059307 -0.220781 -0.0359202 0.0543478 -0.221254 -0.0421762 0.0591921 -0.220781 -0.0356912 0.0542055 -0.22123 -0.0286055 0.0506794 -0.224573 -0.0271707 0.0500098 -0.222518 -0.0290012 0.0476074 -0.224573 -0.029008 0.0476058 -0.222575 -0.028386 0.0478513 -0.224573 -0.0300898 0.0475962 -0.222498 -0.0292631 0.0475588 -0.224573 -0.0273834 0.0489491 -0.224773 -0.0272012 0.0488665 -0.224573 -0.0280403 0.0480895 -0.224773 -0.0301331 0.0474009 -0.228251 -0.0504476 0.0588934 -0.228348 -0.0497663 0.0578213 -0.224973 -0.0488435 0.0572476 -0.228376 -0.0488435 0.0572476 -0.224973 -0.050348 0.0586406 -0.224773 -0.0498718 0.057646 -0.224973 -0.0497359 0.0577927 -0.224973 -0.0300334 0.0530715 -0.224773 -0.0289976 0.0520761 -0.224973 -0.031917 0.0483113 -0.224773 -0.03194 0.0481126 -0.224973 -0.0305601 0.0485119 -0.224973 -0.0299356 0.0488921 -0.224773 -0.0507843 0.0596533 -0.224973 -0.0482995 0.0623621 -0.224773 -0.0293246 0.0492449 -0.224773 -0.0289612 0.0474113 -0.224773 -0.0279129 0.0479354 -0.224773 -0.0304806 0.0483284 -0.224773 -0.0496037 0.062048 -0.224773 -0.0513287 0.0630623 -0.224773 -0.0504918 0.0609975 -0.224773 -0.0524879 0.0611266 -0.224773 -0.0516972 0.0590135 -0.224773 -0.05053 0.0585578 -0.224773 -0.0287818 0.0506167 -0.224773 -0.027244 0.0511017 -0.224773 -0.0416073 0.060418 -0.224773 -0.0469591 0.0624148 -0.224773 -0.0490926 0.0633629 -0.224773 -0.048327 0.0625602 -0.224973 -0.0331926 0.048816 -0.224773 -0.0333118 0.0486554 -0.224973 -0.040713 0.053598 -0.224773 -0.0408079 0.0534219 -0.228376 -0.0381304 0.0521254 -0.224773 -0.0299142 0.0532321 -0.224773 -0.0381044 0.05844 -0.227747 -0.048081 0.0623832 -0.224973 -0.0489938 0.0621668 -0.22781 -0.0489943 0.0621666 -0.224973 -0.0494866 0.0618859 -0.227868 -0.0495287 0.0618549 -0.224973 -0.0499084 0.0615065 -0.228009 -0.0503072 0.0609193 -0.224973 -0.0503124 0.060909 -0.224973 -0.0505844 0.0596592 -0.228167 -0.0505844 0.0596592 -0.228362 -0.0325138 0.0484515 -0.224973 -0.0291637 0.0499319 -0.227983 -0.0292223 0.0498004 -0.224973 -0.0294852 0.0493642 -0.228046 -0.0294865 0.0493624 -0.228142 -0.0300422 0.0488094 -0.228168 -0.0302283 0.0486843 -0.224973 -0.0311081 0.0483423 -0.228275 -0.0311839 0.0483287 -0.22772 -0.0300334 0.0530715 -0.224973 -0.0291811 0.0519967 -0.227819 -0.0289855 0.0512889 -0.224973 -0.0289767 0.0512134 -0.224973 -0.0289805 0.0506397 -0.230023 -0.0325015 0.0497469 -0.229809 -0.0377452 0.0527645 -0.228752 -0.0488294 0.0572861 -0.228376 -0.0433635 0.0549446 -0.229184 -0.0432782 0.055123 -0.228376 -0.040713 0.053598 -0.229184 -0.0380283 0.0522947 -0.229809 -0.0430416 0.0556179 -0.228376 -0.0331926 0.048816 -0.228752 -0.0331681 0.0488489 -0.230023 -0.0484463 0.0583368 -0.230111 -0.0373451 0.0534286 -0.23002 -0.0423504 0.0570634 -0.230111 -0.0427072 0.0563174 -0.224973 -0.0381993 0.058264 -0.22772 -0.0425419 0.0604049 -0.224973 -0.0470276 0.0622269 -0.229497 -0.0482351 0.0610513 -0.229938 -0.048524 0.0598672 -0.229939 -0.0492252 0.0596424 -0.229764 -0.0493229 0.0602344 -0.229919 -0.048558 0.0599347 -0.230069 -0.0488732 0.0591034 -0.229809 -0.0485878 0.0579487 -0.229759 -0.0493966 0.0584805 -0.229967 -0.0491495 0.0587877 -0.230111 -0.0483222 0.0586771 -0.228766 -0.0479186 0.0620567 -0.229157 -0.0478415 0.0616615 -0.229463 -0.0481292 0.0611112 -0.229821 -0.0495719 0.0594537 -0.229212 -0.0497955 0.0608665 -0.229577 -0.0491902 0.0607874 -0.229401 -0.0488675 0.0612398 -0.229023 -0.0493349 0.0614884 -0.227924 -0.0499082 0.0615067 -0.228206 -0.0498261 0.0615602 -0.228087 -0.0490208 0.0621316 -0.227758 -0.0482992 0.0623622 -0.22827 -0.0480027 0.0623058 -0.228352 -0.049697 0.0577574 -0.228046 -0.0504254 0.0606444 -0.228275 -0.0503553 0.0586568 -0.228359 -0.0489271 0.0621 -0.22877 -0.0495361 0.0615549 -0.228823 -0.0504489 0.0598783 -0.22914 -0.0502624 0.059992 -0.229184 -0.0487757 0.0574334 -0.228493 -0.0497017 0.0615781 -0.228346 -0.0503604 0.060737 -0.228653 -0.0502335 0.0608097 -0.228491 -0.0505541 0.0597622 -0.228981 -0.0502854 0.0588922 -0.228622 -0.0503586 0.0587558 -0.228717 -0.0497614 0.0578714 -0.229098 -0.0497111 0.0580057 -0.22969 -0.048584 0.0606105 -0.229639 -0.0485256 0.0607383 -0.229255 -0.0483995 0.0615445 -0.228414 -0.0470766 0.0620924 -0.228869 -0.048684 0.0619013 -0.228949 -0.0500431 0.0608547 -0.229416 -0.0499996 0.0600943 -0.229321 -0.0501255 0.059062 -0.229611 -0.0498817 0.0592545 -0.229458 -0.049589 0.058212 -0.229511 -0.0487003 0.0576404 -0.22873 -0.0302243 0.0528143 -0.229939 -0.0309826 0.0498146 -0.229986 -0.0314133 0.0505364 -0.230069 -0.0316262 0.049812 -0.23002 -0.0317927 0.0507017 -0.230111 -0.0322856 0.0500377 -0.229445 -0.0303722 0.0516113 -0.229577 -0.0300461 0.0504731 -0.229401 -0.0298456 0.0509917 -0.229764 -0.030435 0.0500584 -0.229416 -0.0301799 0.0494161 -0.229611 -0.0309454 0.0490531 -0.229821 -0.0309495 0.0494213 -0.229741 -0.0306197 0.0507765 -0.229967 -0.0317378 0.0494076 -0.228349 -0.0322276 0.048366 -0.228346 -0.0294449 0.0494677 -0.227924 -0.0290503 0.050269 -0.228087 -0.0290164 0.0513549 -0.227842 -0.0289646 0.0510353 -0.227826 -0.0289767 0.0512131 -0.227748 -0.029312 0.0522583 -0.228238 -0.03008 0.0530088 -0.228414 -0.0301187 0.0529566 -0.229157 -0.0300579 0.0520811 -0.228359 -0.0290944 0.0514157 -0.228949 -0.029521 0.0497975 -0.22914 -0.0301208 0.0491404 -0.228653 -0.0294539 0.0496137 -0.229321 -0.030972 0.0487435 -0.229098 -0.0320818 0.0485084 -0.229184 -0.0330747 0.0489748 -0.228717 -0.0321663 0.0483925 -0.228622 -0.0310994 0.0483804 -0.228981 -0.0310258 0.0485165 -0.228491 -0.0301523 0.0487703 -0.228823 -0.0301132 0.048922 -0.228493 -0.0291042 0.0504809 -0.228206 -0.0290508 0.0503671 -0.228766 -0.0296855 0.0522341 -0.22827 -0.0294313 0.052301 -0.229365 -0.0307197 0.052147 -0.229255 -0.0298485 0.0515506 -0.228869 -0.0293941 0.0515094 -0.228771 -0.0292147 0.0506065 -0.229023 -0.0293809 0.050738 -0.229212 -0.0296473 0.0500109 -0.229759 -0.0318584 0.0490322 -0.229458 -0.0319767 0.0487239 -0.229809 -0.0327477 0.0494152 -0.229511 -0.0329434 0.0491517 -0.230009 -0.0482475 0.0595622 -0.23002 -0.0480388 0.059454 -0.229803 -0.0486379 0.0603 -0.229692 -0.0477305 0.0602996 -0.22969 -0.0305273 0.0508822 -0.229578 -0.0303869 0.0511646 -0.229376 -0.0305499 0.051983 -0.229463 -0.0303591 0.051538 -0.229692 -0.0312562 0.0514243 -0.229885 -0.0309877 0.0505595 -0.23002 -0.0369183 0.0541369 -0.229365 -0.0346404 0.0548436 -0.23002 -0.0395995 0.0556658 -0.229365 -0.0430134 0.0593544 -0.229365 -0.0474221 0.0611451 -0.229399 -0.0478338 0.0611953 -0.22772 -0.0340225 0.0558152 -0.228238 -0.0470544 0.0621534 -0.22873 -0.0471374 0.0619259 -0.228993 -0.0472157 0.061711 -0.228993 -0.0384597 0.0577806 -0.229365 -0.0387454 0.0572502 -0.228993 -0.0303607 0.0526306 -0.228993 -0.0343172 0.0553519 -0.228414 -0.0340993 0.0556945 -0.228414 -0.0382672 0.058138 -0.228993 -0.0427667 0.059904 -0.22772 -0.0381993 0.058264 -0.228414 -0.0426005 0.0602743 -0.22772 -0.0470276 0.0622269 -0.224773 -0.0504093 0.058322 -0.224573 -0.0506425 0.0586092 -0.224773 -0.0437962 0.0557011 -0.224573 -0.0310659 0.0480626 -0.224773 -0.0311906 0.0479063 -0.224773 -0.0345257 0.0566029 -0.224573 -0.0280734 0.0518156 -0.222851 -0.00732501 0.0222771 -0.224573 -0.00723528 0.0230015 -0.222885 -0.00723528 0.0230015 -0.222664 -0.00875765 0.0206967 -0.224573 -0.0080616 0.0211179 -0.224573 -0.0102615 0.0206143 -0.224573 -0.0103687 0.020646 -0.222448 -0.0112949 0.0211982 -0.224573 -0.0118683 0.0220539 -0.224573 -0.0112358 0.0211434 -0.224773 -0.00911323 0.0203836 -0.224573 -0.00745949 0.0219157 -0.224773 -0.00727826 0.0218311 -0.224573 -0.0081478 0.0210466 -0.224573 -0.00915331 0.0205795 -0.228349 -0.0231775 0.0398336 -0.224973 -0.0231174 0.0396571 -0.224973 -0.0226716 0.0388971 -0.224773 -0.0233043 0.039586 -0.230111 -0.0146232 0.0298406 -0.230023 -0.0122694 0.0242303 -0.229184 -0.0157819 0.0292002 -0.228752 -0.0226402 0.0389235 -0.229511 -0.0223512 0.0391656 -0.229184 -0.0225201 0.0390241 -0.229184 -0.0189143 0.0342745 -0.228376 -0.0190773 0.0341627 -0.228376 -0.0159549 0.0291046 -0.229809 -0.0220997 0.0393764 -0.228376 -0.0133333 0.0237697 -0.228752 -0.0132957 0.0237859 -0.230111 -0.0178226 0.0350233 -0.229809 -0.0184619 0.0345848 -0.229809 -0.0153018 0.0294655 -0.22772 -0.0156356 0.0384806 -0.224973 -0.0186094 0.0423013 -0.22772 -0.0186094 0.0423013 -0.229939 -0.0218048 0.041162 -0.229497 -0.0202429 0.041887 -0.229938 -0.0210851 0.041006 -0.229919 -0.0210809 0.0410814 -0.229764 -0.0215934 0.0417235 -0.230023 -0.021783 0.0396418 -0.229759 -0.0225342 0.0402414 -0.229611 -0.0225673 0.0411542 -0.229821 -0.0221994 0.0411718 -0.229967 -0.0221666 0.0403839 -0.230069 -0.0217694 0.0405192 -0.230111 -0.0215054 0.0398744 -0.229463 -0.0201212 0.0418859 -0.229416 -0.0222495 0.0419405 -0.229023 -0.0209768 0.0428155 -0.229401 -0.0206963 0.0423665 -0.228346 -0.0222406 0.0426775 -0.227939 -0.021583 0.043076 -0.227874 -0.0210207 0.0432218 -0.227815 -0.0204029 0.0432386 -0.228087 -0.0203832 0.0432155 -0.229577 -0.021202 0.0421361 -0.229255 -0.0201387 0.0423963 -0.228869 -0.0202067 0.0428476 -0.228357 -0.0231195 0.0396628 -0.228304 -0.0232894 0.0405212 -0.228717 -0.0231546 0.0398963 -0.228024 -0.0222018 0.0427404 -0.228046 -0.0223433 0.0426298 -0.228491 -0.0228958 0.0419302 -0.228493 -0.0212496 0.0430766 -0.228653 -0.0220944 0.042677 -0.228823 -0.0227466 0.0419781 -0.228981 -0.0230981 0.0410423 -0.229321 -0.0228747 0.0411094 -0.229458 -0.022835 0.0401051 -0.228206 -0.0213663 0.0431232 -0.228622 -0.0232297 0.0409608 -0.229098 -0.023044 0.0399874 -0.228414 -0.0187191 0.0422094 -0.22827 -0.0194144 0.0428572 -0.228766 -0.0194661 0.0425995 -0.229157 -0.0195969 0.0422187 -0.228993 -0.0190303 0.0419487 -0.227765 -0.019746 0.0430938 -0.228359 -0.0203178 0.0431412 -0.22877 -0.0211178 0.0429736 -0.228949 -0.021907 0.0426208 -0.229212 -0.0216867 0.0425072 -0.22914 -0.0225282 0.0419833 -0.22772 -0.00846964 0.0258755 -0.229577 -0.00977992 0.0236315 -0.230069 -0.0114788 0.0238491 -0.23002 -0.0111781 0.0247028 -0.229376 -0.00946124 0.0251911 -0.229255 -0.00907004 0.0244659 -0.229463 -0.0095185 0.0247102 -0.229023 -0.00907135 0.0235283 -0.229401 -0.00934692 0.0239803 -0.229578 -0.00972925 0.0244007 -0.229821 -0.0110881 0.0231724 -0.229967 -0.0117776 0.0235547 -0.229759 -0.0120698 0.0232898 -0.229809 -0.0126485 0.0240662 -0.22969 -0.00999204 0.0242265 -0.229741 -0.0101249 0.0241811 -0.229764 -0.010324 0.0234668 -0.229939 -0.0109201 0.0235295 -0.230111 -0.011937 0.0243742 -0.228622 -0.0117384 0.0223459 -0.228275 -0.0118375 0.0223434 -0.228168 -0.010832 0.0221735 -0.228491 -0.0107233 0.0222099 -0.228717 -0.0126563 0.0228898 -0.228362 -0.0129278 0.0231147 -0.228142 -0.0106084 0.0221888 -0.228346 -0.0097619 0.0224602 -0.228046 -0.00985057 0.0223899 -0.227983 -0.00940277 0.0226371 -0.227924 -0.00901951 0.0229569 -0.228087 -0.00844729 0.0238803 -0.227842 -0.00856214 0.0235777 -0.227819 -0.00845351 0.0238077 -0.22827 -0.00833345 0.0249071 -0.228238 -0.00854137 0.0258444 -0.229157 -0.00898609 0.02503 -0.228359 -0.00848436 0.023972 -0.228771 -0.0089932 0.0233313 -0.228493 -0.00896028 0.0231673 -0.228949 -0.00966288 0.0227839 -0.228653 -0.0096967 0.0225912 -0.229321 -0.0114465 0.0225966 -0.228981 -0.0116066 0.022427 -0.229511 -0.0129497 0.0239358 -0.229098 -0.0125252 0.0229479 -0.229184 -0.0131519 0.0238482 -0.228823 -0.0106135 0.0223218 -0.228206 -0.00897091 0.0230421 -0.228766 -0.00858705 0.0249763 -0.228414 -0.00860098 0.0258186 -0.228869 -0.00869711 0.024203 -0.229212 -0.00966563 0.0230318 -0.229416 -0.0104243 0.022783 -0.22914 -0.0105109 0.0225147 -0.229611 -0.0112687 0.0228514 -0.229458 -0.0123264 0.023082 -0.23002 -0.0171406 0.0354911 -0.230009 -0.0209982 0.0406037 -0.23002 -0.0208716 0.0404056 -0.229692 -0.0201818 0.0409837 -0.229399 -0.0198234 0.041811 -0.229639 -0.020651 0.0417612 -0.22969 -0.0207655 0.0416797 -0.229803 -0.0209674 0.0414378 -0.229445 -0.00949318 0.0247803 -0.229365 -0.00952632 0.025418 -0.229692 -0.0103522 0.0250604 -0.229986 -0.0109322 0.02437 -0.229885 -0.0105521 0.0241772 -0.23002 -0.0138994 0.0302406 -0.229365 -0.0115734 0.0297136 -0.23002 -0.015457 0.0329052 -0.229365 -0.0139251 0.0338504 -0.229365 -0.0165692 0.0378066 -0.228238 -0.0186693 0.0422511 -0.228414 -0.0157517 0.0383968 -0.22873 -0.0188549 0.0420956 -0.229365 -0.019492 0.0415617 -0.228993 -0.0134125 0.0341668 -0.228993 -0.00897352 0.0256573 -0.228993 -0.0110393 0.0299922 -0.22873 -0.00876361 0.0257482 -0.228414 -0.0106794 0.03018 -0.228414 -0.0130671 0.03438 -0.228993 -0.0160808 0.0381592 -0.22772 -0.0105525 0.0302462 -0.22772 -0.0129453 0.0344552 -0.224773 -0.0190738 0.0350342 -0.224573 -0.0149981 0.0288119 -0.224773 -0.0198298 0.0443177 -0.224773 -0.0148197 0.0380246 -0.224573 -0.00740019 0.0238078 -0.224773 -0.0235015 0.0445138 -0.224773 -0.0209578 0.0450518 -0.224573 -0.0217433 0.0449798 -0.224573 -0.0222603 0.0449279 -0.224773 -0.0242356 0.0433858 -0.224573 -0.0241117 0.0420832 -0.224773 -0.0243074 0.0420419 -0.224773 -0.0151743 0.0287172 -0.224773 -0.0234893 0.0405153 -0.224773 -0.0228249 0.0387687 -0.224773 -0.0135169 0.0236902 -0.224773 -0.0126003 0.0225342 -0.222899 -0.00740019 0.0238078 -0.222426 -0.0235488 0.0409758 -0.222436 -0.0239371 0.0415618 -0.224573 -0.0235488 0.0409758 -0.224573 -0.0241521 0.0428153 -0.222721 -0.0228831 0.0447028 -0.224573 -0.0233678 0.044365 -0.224573 -0.0237554 0.043919 -0.224573 -0.0240455 0.0433238 -0.224573 -0.0199785 0.044184 -0.222899 -0.0199785 0.044184 -0.224573 -0.0210198 0.0448617 -0.222827 -0.0216743 0.0449782 -0.222822 -0.0217435 0.0449798 -0.222807 -0.0219507 0.0449726 -0.224573 -0.022883 0.0447029 -0.224573 -0.0149833 0.0379096 -0.224573 -0.0107706 0.0310852 -0.222426 -0.0149981 0.0288119 -0.224573 -0.0189102 0.0351492 -0.221254 -0.00847204 0.0233871 -0.222623 -0.00915326 0.0205795 -0.222252 -0.00954325 0.0205637 -0.222584 -0.00955442 0.0205322 -0.222683 -0.00857324 0.0207781 -0.222742 -0.0080617 0.0211178 -0.222559 -0.0074415 0.0220082 -0.222841 -0.00737448 0.0221225 -0.222776 -0.00779865 0.0213847 -0.220853 -0.00932733 0.0225463 -0.220833 -0.00960161 0.0218716 -0.220795 -0.00956809 0.0227226 -0.221161 -0.0099734 0.0212052 -0.220826 -0.010376 0.0218707 -0.220978 -0.00910175 0.021808 -0.220939 -0.0090553 0.0224951 -0.221131 -0.00864538 0.021937 -0.220951 -0.00978185 0.0215201 -0.220725 -0.0100671 0.0221548 -0.220683 -0.0103897 0.0226343 -0.221652 -0.00802075 0.0217579 -0.221496 -0.00855109 0.0213329 -0.222513 -0.0103686 0.020646 -0.222505 -0.0104769 0.0206836 -0.222426 -0.0118683 0.0220539 -0.222077 -0.0112772 0.0212358 -0.222049 -0.0118301 0.0220689 -0.221904 -0.00794925 0.021558 -0.222055 -0.00859695 0.0208929 -0.22176 -0.00855665 0.0210847 -0.221919 -0.00942979 0.0206719 -0.221602 -0.00932075 0.0208615 -0.222469 -0.00793686 0.0212676 -0.222182 -0.00792191 0.0213927 -0.222363 -0.00866657 0.0207641 -0.22215 -0.01046 0.0207154 -0.221791 -0.0103256 0.020792 -0.221695 -0.0111442 0.0212895 -0.221469 -0.00796314 0.0230802 -0.22186 -0.00756595 0.0230125 -0.221391 -0.0080442 0.0226163 -0.221564 -0.00784595 0.0224765 -0.221283 -0.0085817 0.0216235 -0.22288 -0.00723536 0.0228575 -0.222357 -0.00731474 0.0229343 -0.222287 -0.00747537 0.0221014 -0.221777 -0.00768019 0.0223401 -0.221326 -0.00922506 0.0211272 -0.221451 -0.0101599 0.0209564 -0.221335 -0.0109409 0.0214169 -0.221035 -0.0106772 0.0216159 -0.22129 -0.011479 0.0222067 -0.220781 -0.021802 0.0425455 -0.220833 -0.0226958 0.0430838 -0.220878 -0.0219582 0.0431152 -0.221274 -0.0217933 0.044108 -0.221098 -0.0215686 0.0435851 -0.221131 -0.0222094 0.0439089 -0.221326 -0.023193 0.0437535 -0.221161 -0.0234583 0.0430502 -0.220826 -0.0230438 0.0423922 -0.220978 -0.022529 0.0435588 -0.220951 -0.0230909 0.0430803 -0.220725 -0.0226514 0.042541 -0.222445 -0.0240361 0.0418079 -0.222077 -0.0240154 0.0418712 -0.222498 -0.0241579 0.0427459 -0.222252 -0.0238394 0.0437214 -0.22259 -0.0238404 0.043783 -0.222606 -0.0237554 0.043919 -0.222469 -0.0224905 0.0448424 -0.222559 -0.0216056 0.0449536 -0.222663 -0.023369 0.044364 -0.222704 -0.0230362 0.0446148 -0.222363 -0.0232679 0.0444152 -0.222751 -0.0225883 0.0448338 -0.222877 -0.0208173 0.0447854 -0.222357 -0.0207208 0.0446517 -0.222381 -0.0200367 0.0441317 -0.221626 -0.0203869 0.043817 -0.22186 -0.0207636 0.0443921 -0.222287 -0.0215375 0.0448815 -0.221904 -0.0222363 0.0447013 -0.22176 -0.022932 0.04437 -0.221919 -0.0236918 0.0437744 -0.22129 -0.0232377 0.0412553 -0.221618 -0.0234018 0.0411079 -0.221695 -0.0239078 0.041966 -0.22215 -0.0241143 0.0428347 -0.221791 -0.0239855 0.0429205 -0.222055 -0.0231215 0.0444198 -0.222182 -0.0223719 0.0447998 -0.222206 -0.020085 0.0440883 -0.221469 -0.0208811 0.0440067 -0.221241 -0.0210083 0.0435519 -0.221391 -0.0213322 0.0441422 -0.221777 -0.0214159 0.0445914 -0.221652 -0.0220896 0.0445478 -0.221496 -0.0227074 0.0442637 -0.221602 -0.0234734 0.043787 -0.221451 -0.0237643 0.042995 -0.221035 -0.0234066 0.0422371 -0.221335 -0.0237028 0.0420906 -0.222206 -0.0151004 0.0378273 -0.221254 -0.011655 0.0302974 -0.221626 -0.0112542 0.0308252 -0.221626 -0.0079113 0.0236072 -0.221497 -0.00805447 0.023551 -0.221626 -0.0154325 0.0375939 -0.222206 -0.00753342 0.0237555 -0.221889 -0.00769848 0.0236907 -0.222382 -0.00747298 0.0237792 -0.222899 -0.0107706 0.0310852 -0.221889 -0.0202169 0.0439698 -0.222206 -0.0108966 0.0310174 -0.222899 -0.0149833 0.0379096 -0.220691 -0.0224171 0.0419928 -0.220781 -0.00968215 0.0229121 -0.220781 -0.0129297 0.0299242 -0.220691 -0.0176654 0.0360242 -0.220691 -0.0104519 0.0226099 -0.220781 -0.0169889 0.0364998 -0.220691 -0.013658 0.0295325 -0.220992 -0.0182997 0.0355784 -0.220992 -0.0229938 0.0414745 -0.220778 -0.0226862 0.041751 -0.222426 -0.0189102 0.0351492 -0.221618 -0.0187484 0.0352629 -0.222049 -0.0235183 0.0410032 -0.220778 -0.0107888 0.0224777 -0.220992 -0.0111736 0.0223266 -0.220992 -0.0143409 0.0291653 -0.221618 -0.014824 0.0289055 -0.221618 -0.0116842 0.0221262 -0.220781 -0.0128025 0.0296864 -0.221018 -0.00907709 0.0231496 -0.221159 -0.00852567 0.0227983 -0.221056 -0.00874497 0.0225842 -0.221019 -0.00883753 0.0225389 -0.221254 -0.020835 0.0434144 -0.221183 -0.0212972 0.0436327 -0.220806 -0.0219462 0.0428083 -0.220854 -0.0219698 0.0430281 -0.220981 -0.021828 0.0433928 -0.220781 -0.0171439 0.0367194 -0.221018 -0.0213185 0.0429799 -0.221254 -0.0160835 0.0374714 -0.221254 -0.0159253 0.0372474 -0.221254 -0.0117847 0.0305399 -0.22123 -0.0084291 0.0230899 -0.224973 -0.00846964 0.0258755 -0.224973 -0.00848363 0.0237379 -0.224773 -0.00807032 0.0244955 -0.224773 -0.00861314 0.0231238 -0.224973 -0.00877373 0.023243 -0.224973 -0.0133333 0.0237697 -0.224973 -0.0124811 0.0226948 -0.224773 -0.0121687 0.0222698 -0.224973 -0.0112056 0.0221901 -0.224973 -0.0104747 0.0222072 -0.224773 -0.0112285 0.0219914 -0.224773 -0.00976913 0.0222072 -0.224773 -0.0231876 0.0418779 -0.224773 -0.0234905 0.0406104 -0.224973 -0.0225725 0.042413 -0.224773 -0.0222751 0.0429339 -0.224973 -0.0221604 0.04277 -0.224773 -0.0195871 0.0432474 -0.224973 -0.0204023 0.0432385 -0.224973 -0.0209475 0.0432314 -0.224773 -0.0236976 0.0408421 -0.224773 -0.0209707 0.04343 -0.224773 -0.0103137 0.0204212 -0.224773 -0.00802393 0.0208896 -0.224773 -0.0120545 0.0219808 -0.224773 -0.0113692 0.0209944 -0.224773 -0.0223017 0.0451236 -0.224773 -0.00703537 0.0230074 -0.224773 -0.00721402 0.0238809 -0.224773 -0.00828611 0.0259549 -0.224773 -0.0105944 0.0311799 -0.224773 -0.0127751 0.0345603 -0.224773 -0.0176254 0.0315662 -0.228376 -0.0226716 0.0388971 -0.224973 -0.0174552 0.0316712 -0.228376 -0.0174552 0.0316712 -0.224973 -0.0129453 0.0344552 -0.224773 -0.0184561 0.0424298 -0.224973 -0.0215827 0.0430761 -0.224973 -0.0196611 0.0430616 -0.227747 -0.0194435 0.0429635 -0.227721 -0.0187164 0.0424215 -0.228085 -0.0225725 0.0424131 -0.224973 -0.0230088 0.0417882 -0.228178 -0.0230167 0.0417725 -0.224973 -0.0231719 0.0413833 -0.228275 -0.0232763 0.0408734 -0.224973 -0.0232894 0.0405212 -0.228349 -0.0127226 0.0228975 -0.224973 -0.00928631 0.0227217 -0.224973 -0.00984859 0.0223907 -0.224973 -0.011765 0.0223172 -0.224973 -0.008269 0.0245185 -0.227748 -0.00825152 0.0248105 -0.227826 -0.00848374 0.0237377 -0.224573 -0.00921183 -0.0186288 -0.222517 -0.00916117 -0.0186098 -0.222663 -0.00760169 -0.0185842 -0.222737 -0.00692773 -0.018929 -0.224573 -0.00688093 -0.0189641 -0.22288 -0.00595368 -0.0206524 -0.224573 -0.00594516 -0.0207958 -0.222899 -0.00899851 -0.0290735 -0.224573 -0.0128023 -0.0361341 -0.222899 -0.0128023 -0.0361341 -0.224573 -0.0211724 -0.0396991 -0.222426 -0.0211724 -0.0396991 -0.222426 -0.0168848 -0.0336096 -0.224573 -0.0133525 -0.027053 -0.220978 -0.0200022 -0.042218 -0.220833 -0.0201969 -0.0417532 -0.220826 -0.020585 -0.0410831 -0.220951 -0.0205915 -0.0417729 -0.221035 -0.0209562 -0.0409496 -0.221019 -0.0192371 -0.0420813 -0.221326 -0.0206534 -0.0424516 -0.220725 -0.0201845 -0.0412086 -0.220691 -0.0199828 -0.0406477 -0.220683 -0.0199305 -0.0406894 -0.221283 -0.0199019 -0.0427606 -0.221159 -0.0188565 -0.0422217 -0.221391 -0.0187734 -0.0427297 -0.221564 -0.0187953 -0.0429712 -0.221469 -0.0183311 -0.0425679 -0.222469 -0.0198877 -0.043497 -0.222889 -0.0179342 -0.0431719 -0.222448 -0.0216273 -0.0406253 -0.222077 -0.0215854 -0.0406201 -0.222606 -0.0212053 -0.0426495 -0.222575 -0.0213838 -0.042379 -0.222519 -0.0216251 -0.0417739 -0.22215 -0.0216275 -0.041588 -0.22288 -0.01816 -0.0433095 -0.222559 -0.0189986 -0.0435557 -0.222721 -0.0202884 -0.0433806 -0.222363 -0.0206886 -0.0431168 -0.222623 -0.0210935 -0.0427856 -0.222252 -0.0213005 -0.0424577 -0.222287 -0.0189348 -0.0434797 -0.222182 -0.0197719 -0.0434474 -0.22176 -0.020356 -0.0430517 -0.221695 -0.0214724 -0.0407084 -0.221618 -0.0210178 -0.0398224 -0.22129 -0.0208455 -0.0399598 -0.222055 -0.0205422 -0.0431127 -0.221919 -0.02115 -0.0425019 -0.221791 -0.0214939 -0.041666 -0.222049 -0.0211404 -0.0397247 -0.221497 -0.017969 -0.0422534 -0.221626 -0.0178488 -0.0423493 -0.22186 -0.0181911 -0.0429458 -0.221131 -0.0196622 -0.0425487 -0.221056 -0.0191516 -0.0421389 -0.221777 -0.0188305 -0.043183 -0.222357 -0.0181333 -0.0432024 -0.222206 -0.0175314 -0.0426024 -0.222382 -0.0174806 -0.0426429 -0.221904 -0.0196424 -0.043341 -0.221652 -0.019505 -0.0431792 -0.221496 -0.0201382 -0.0429324 -0.221602 -0.0209313 -0.0425015 -0.221451 -0.0212687 -0.0417274 -0.221161 -0.02096 -0.0417645 -0.221335 -0.0212605 -0.0408207 -0.222895 -0.0059685 -0.0212077 -0.222899 -0.00606233 -0.0216104 -0.220781 -0.00839305 -0.0208505 -0.220691 -0.00917928 -0.0205942 -0.220806 -0.00823755 -0.0205942 -0.220725 -0.00882166 -0.0201171 -0.221469 -0.00666717 -0.0209174 -0.221626 -0.00658436 -0.0214402 -0.221391 -0.00677536 -0.0204589 -0.221274 -0.00703555 -0.0200768 -0.221131 -0.00741605 -0.0198159 -0.220981 -0.0076723 -0.0204043 -0.220978 -0.00787903 -0.0197143 -0.221326 -0.00804239 -0.0190418 -0.221161 -0.00878412 -0.0191638 -0.220778 -0.00952323 -0.020482 -0.220833 -0.00837378 -0.0198072 -0.220951 -0.00857437 -0.0194669 -0.220826 -0.00914675 -0.0198517 -0.222575 -0.008505 -0.0184719 -0.222625 -0.00798117 -0.0184941 -0.222498 -0.00939744 -0.01871 -0.22215 -0.00929876 -0.0187033 -0.222446 -0.0101243 -0.0192568 -0.222426 -0.0106259 -0.0201225 -0.222049 -0.0105869 -0.0201352 -0.222077 -0.0100837 -0.0192708 -0.221618 -0.0104379 -0.0201838 -0.222832 -0.00619481 -0.0197985 -0.222559 -0.0062094 -0.0198166 -0.222469 -0.00674807 -0.0191058 -0.222357 -0.00602843 -0.0207337 -0.222885 -0.00594516 -0.0207958 -0.222381 -0.00613668 -0.0215861 -0.22186 -0.00627463 -0.0208265 -0.221904 -0.00674326 -0.0193964 -0.221919 -0.0082737 -0.0185994 -0.221791 -0.00916008 -0.018772 -0.221695 -0.0099478 -0.0193166 -0.221335 -0.00973738 -0.0194318 -0.22129 -0.0102283 -0.0202522 -0.222252 -0.00839337 -0.0184981 -0.222055 -0.0074296 -0.0187706 -0.222363 -0.00750676 -0.0186461 -0.222182 -0.00672575 -0.0192298 -0.222287 -0.00623774 -0.0199116 -0.222206 -0.0061984 -0.021566 -0.221889 -0.00636702 -0.021511 -0.221777 -0.00642819 -0.0201619 -0.221652 -0.00680283 -0.0196003 -0.22176 -0.007378 -0.0189597 -0.221496 -0.00735773 -0.0192072 -0.221602 -0.00815363 -0.0187822 -0.221451 -0.00898491 -0.0189263 -0.221035 -0.00946243 -0.019615 -0.221626 -0.0132693 -0.0358453 -0.222206 -0.00912833 -0.0290133 -0.221254 -0.0183198 -0.0419738 -0.221254 -0.0139267 -0.0357621 -0.222206 -0.012924 -0.0360588 -0.221626 -0.00949657 -0.0288424 -0.221889 -0.01767 -0.0424919 -0.220781 -0.0148873 -0.0348448 -0.220781 -0.0193362 -0.0411633 -0.220781 -0.0150296 -0.0350738 -0.220691 -0.0155906 -0.0344099 -0.220778 -0.0202657 -0.0404221 -0.220781 -0.0111096 -0.0277976 -0.220691 -0.0119723 -0.0276935 -0.220992 -0.0162501 -0.0340021 -0.220992 -0.0126756 -0.0273671 -0.220992 -0.00991643 -0.0203538 -0.222426 -0.0133525 -0.027053 -0.220992 -0.020589 -0.0401643 -0.221618 -0.0167166 -0.0337136 -0.221618 -0.0131732 -0.0271362 -0.221018 -0.018828 -0.0415685 -0.220939 -0.0193839 -0.0419147 -0.220853 -0.0194755 -0.0416535 -0.220795 -0.0194432 -0.0413568 -0.22123 -0.0185557 -0.0421596 -0.221018 -0.00777506 -0.021052 -0.221241 -0.00712464 -0.0210346 -0.221254 -0.00715708 -0.0212535 -0.221183 -0.00719846 -0.0207454 -0.220854 -0.00805903 -0.0204638 -0.220878 -0.00797776 -0.0204303 -0.221098 -0.00737604 -0.0205328 -0.221254 -0.00992808 -0.0283399 -0.220781 -0.0112222 -0.0280416 -0.221254 -0.010043 -0.0285888 -0.221254 -0.0137816 -0.0355285 -0.224773 -0.00574525 -0.0207899 -0.224973 -0.0209402 -0.0392301 -0.228288 -0.0209265 -0.0394322 -0.228132 -0.0203756 -0.0407886 -0.227973 -0.019361 -0.0415765 -0.224973 -0.0196808 -0.0414086 -0.224973 -0.019086 -0.0416801 -0.227939 -0.0190863 -0.04168 -0.227833 -0.018098 -0.041795 -0.224973 -0.0178982 -0.0417727 -0.224973 -0.0171686 -0.0415525 -0.22772 -0.0161636 -0.0407316 -0.224773 -0.0184543 -0.0419974 -0.224773 -0.0170839 -0.0417336 -0.224973 -0.0184429 -0.0417977 -0.224773 -0.0197857 -0.0415789 -0.224973 -0.0201132 -0.0410764 -0.224973 -0.0205855 -0.0404783 -0.224973 -0.00922573 -0.0201935 -0.224773 -0.0113284 -0.0206451 -0.224973 -0.00995634 -0.0202194 -0.224973 -0.007148 -0.0216044 -0.224973 -0.0080091 -0.0206372 -0.224773 -0.00852137 -0.020152 -0.224773 -0.00731344 -0.0209989 -0.224773 -0.00999094 -0.0200225 -0.224773 -0.0108161 -0.0200605 -0.224773 -0.00587218 -0.0216724 -0.224773 -0.00685675 -0.0187339 -0.224773 -0.00669081 -0.0223364 -0.224773 -0.00682032 -0.0238059 -0.224773 -0.0126321 -0.0362393 -0.224773 -0.016003 -0.0408509 -0.224773 -0.0183459 -0.0436156 -0.224773 -0.0196833 -0.0437664 -0.224773 -0.0207587 -0.0405784 -0.224773 -0.0217162 -0.0421454 -0.224773 -0.0158132 -0.0299572 -0.224773 -0.0121753 -0.021853 -0.224973 -0.0119874 -0.0219215 -0.228376 -0.0142905 -0.0274015 -0.224973 -0.0156371 -0.030052 -0.228376 -0.0171097 -0.0326346 -0.224973 -0.0109711 -0.0325657 -0.224973 -0.00700822 -0.0237374 -0.224773 -0.010795 -0.0326606 -0.224973 -0.0111999 -0.0207984 -0.227734 -0.00685196 -0.0229812 -0.224973 -0.0068878 -0.022371 -0.224973 -0.00746673 -0.0211274 -0.224973 -0.00858989 -0.0203399 -0.224973 -0.0105073 -0.0203793 -0.228168 -0.00958357 -0.0201809 -0.224973 -0.0204191 -0.0375725 -0.228357 -0.0208214 -0.0383638 -0.228349 -0.0208691 -0.0385374 -0.224973 -0.0208193 -0.0383573 -0.230111 -0.0191974 -0.0384794 -0.228752 -0.0119489 -0.0219356 -0.228376 -0.0119874 -0.0219215 -0.229184 -0.0141121 -0.0274868 -0.229184 -0.0169404 -0.0327367 -0.228376 -0.0156371 -0.030052 -0.229511 -0.0200834 -0.0378216 -0.230111 -0.010558 -0.0224429 -0.229511 -0.0115947 -0.0220648 -0.229809 -0.0136172 -0.0277234 -0.230111 -0.0158064 -0.0334199 -0.229809 -0.0164705 -0.0330198 -0.23002 -0.00978105 -0.0227262 -0.230111 -0.0129177 -0.0280579 -0.22772 -0.0109711 -0.0325657 -0.224973 -0.0161636 -0.0407316 -0.228109 -0.00908375 -0.020212 -0.22969 -0.00862462 -0.022181 -0.229639 -0.00849682 -0.0222394 -0.229463 -0.00812388 -0.0226359 -0.230009 -0.00967283 -0.0225175 -0.229919 -0.0093004 -0.022207 -0.228949 -0.00838033 -0.0207219 -0.228493 -0.00765693 -0.0210633 -0.228653 -0.00842534 -0.0205315 -0.227747 -0.00685182 -0.022684 -0.229255 -0.00769058 -0.0223655 -0.228869 -0.0073338 -0.022081 -0.229577 -0.00844763 -0.0215748 -0.229401 -0.00799523 -0.0218975 -0.229023 -0.00774665 -0.0214302 -0.22877 -0.00768018 -0.0212289 -0.228359 -0.00713504 -0.0218379 -0.228346 -0.00849806 -0.0204046 -0.229759 -0.0107546 -0.0213684 -0.229809 -0.0112864 -0.0221772 -0.229184 -0.0118017 -0.0219893 -0.228251 -0.0103407 -0.0203171 -0.228622 -0.0104793 -0.0204064 -0.228491 -0.00947286 -0.0202109 -0.228823 -0.00935673 -0.0203161 -0.228981 -0.0103429 -0.0204796 -0.22914 -0.00924303 -0.0205026 -0.229321 -0.0101731 -0.0206395 -0.229416 -0.00914079 -0.0207654 -0.229967 -0.0104473 -0.0216155 -0.229611 -0.00998058 -0.0208834 -0.229458 -0.0110231 -0.021176 -0.229098 -0.0112294 -0.0210539 -0.228717 -0.0113637 -0.0210037 -0.228348 -0.0114137 -0.0209987 -0.228268 -0.0105071 -0.0203792 -0.228238 -0.00708165 -0.0237106 -0.22827 -0.00692927 -0.0227623 -0.228766 -0.00717834 -0.0228464 -0.229157 -0.00757352 -0.0229235 -0.229399 -0.00803982 -0.0229312 -0.227819 -0.00711393 -0.0216721 -0.228087 -0.00710344 -0.0217442 -0.22795 -0.0079001 -0.0207153 -0.228046 -0.00859069 -0.0203396 -0.228206 -0.00767488 -0.0209389 -0.229212 -0.00836859 -0.0209695 -0.229764 -0.00900064 -0.0214421 -0.229821 -0.00978139 -0.0211931 -0.229939 -0.00959263 -0.0215398 -0.230069 -0.0101316 -0.0218918 -0.230023 -0.0108983 -0.0223187 -0.229577 -0.018762 -0.0407189 -0.229939 -0.0194204 -0.0397824 -0.229986 -0.0186986 -0.0393517 -0.228993 -0.0166044 -0.0404044 -0.229463 -0.0176971 -0.0404059 -0.229401 -0.0182434 -0.0409195 -0.229023 -0.0184971 -0.0413841 -0.22969 -0.0183528 -0.0402377 -0.229416 -0.019819 -0.0405851 -0.230023 -0.0194882 -0.0382635 -0.229764 -0.0191767 -0.0403301 -0.229821 -0.0198138 -0.0398155 -0.230069 -0.019423 -0.0391388 -0.229967 -0.0198274 -0.0390272 -0.228622 -0.0208547 -0.0396656 -0.228275 -0.0209064 -0.0395811 -0.228224 -0.020772 -0.0400842 -0.228491 -0.0204648 -0.0406127 -0.228159 -0.0205086 -0.0406033 -0.228304 -0.0209402 -0.0392301 -0.228752 -0.0203862 -0.0375969 -0.228717 -0.0208425 -0.0385987 -0.228376 -0.0204191 -0.0375725 -0.228085 -0.0201132 -0.0410764 -0.228346 -0.0197674 -0.0413201 -0.228046 -0.0198726 -0.0412785 -0.227819 -0.0179462 -0.0417795 -0.22827 -0.0169341 -0.0413338 -0.227748 -0.0169768 -0.041453 -0.228359 -0.0178193 -0.0416706 -0.228493 -0.0187542 -0.0416608 -0.228653 -0.0196214 -0.0413111 -0.22914 -0.0200947 -0.0406442 -0.228981 -0.0207186 -0.0397392 -0.229184 -0.0202603 -0.0376903 -0.229098 -0.0207267 -0.0386832 -0.228823 -0.0203131 -0.0406519 -0.228206 -0.018868 -0.0417142 -0.228087 -0.0178802 -0.0417486 -0.228766 -0.017001 -0.0410796 -0.229255 -0.0176845 -0.0409165 -0.229157 -0.017154 -0.0407071 -0.228869 -0.0177257 -0.0413709 -0.228771 -0.0186286 -0.0415503 -0.228949 -0.0194376 -0.0412441 -0.229212 -0.0192242 -0.0411177 -0.229611 -0.020182 -0.0398196 -0.229321 -0.0204916 -0.039793 -0.229759 -0.0202029 -0.0389066 -0.229809 -0.0198199 -0.0380173 -0.229458 -0.0205112 -0.0387883 -0.229938 -0.00936785 -0.022241 -0.229692 -0.00893552 -0.0230345 -0.229803 -0.00893509 -0.0221271 -0.229497 -0.00818374 -0.0225299 -0.229376 -0.017252 -0.0402151 -0.229365 -0.0170881 -0.0400453 -0.229445 -0.0176237 -0.0403928 -0.229578 -0.0180705 -0.0403782 -0.23002 -0.0185334 -0.0389724 -0.229692 -0.0178107 -0.0395088 -0.229885 -0.0186756 -0.0397773 -0.229741 -0.0184586 -0.0401453 -0.23002 -0.0150981 -0.0338467 -0.229365 -0.0143915 -0.0361246 -0.23002 -0.0135693 -0.0311655 -0.23002 -0.0121717 -0.0284146 -0.228238 -0.0162263 -0.0406851 -0.228414 -0.0162785 -0.0406463 -0.228414 -0.0135406 -0.0366657 -0.228414 -0.00896076 -0.0281645 -0.228993 -0.00752406 -0.0235493 -0.228993 -0.00933111 -0.0279983 -0.229365 -0.00808999 -0.0233429 -0.229365 -0.00988067 -0.0277516 -0.229365 -0.0119848 -0.0320196 -0.22873 -0.0164208 -0.0405407 -0.228993 -0.0138832 -0.0364479 -0.228993 -0.0114545 -0.0323053 -0.228414 -0.0110971 -0.0324978 -0.22873 -0.00730916 -0.0236276 -0.228414 -0.00714268 -0.0236884 -0.22772 -0.0134198 -0.0367425 -0.22772 -0.00883019 -0.0282231 -0.22772 -0.00700822 -0.0237374 -0.224773 -0.0109131 -0.0203557 -0.224573 -0.0106259 -0.0201225 -0.224573 -0.0168848 -0.0336096 -0.224773 -0.0211357 -0.039331 -0.224573 -0.00606233 -0.0216104 -0.224573 -0.00899851 -0.0290735 -0.224773 -0.00881709 -0.0291577 -0.224573 -0.0174195 -0.0426916 -0.224773 -0.0213288 -0.0395744 -0.224573 -0.0216692 -0.0408378 -0.224773 -0.0218669 -0.040808 -0.224773 -0.0209169 -0.0432282 -0.224573 -0.018419 -0.0434294 -0.224773 -0.0172631 -0.0428163 -0.224573 -0.0191344 -0.0435899 -0.224573 -0.0196535 -0.0435686 -0.224773 -0.00605696 -0.01963 -0.224573 -0.00623289 -0.0197251 -0.224573 -0.00697117 -0.018898 -0.224773 -0.00797396 -0.0182929 -0.224573 -0.00800243 -0.0184909 -0.224573 -0.00910661 -0.0185908 -0.224773 -0.00917015 -0.0184012 -0.224773 -0.0101901 -0.0190355 -0.224573 -0.010198 -0.0193423 -0.224573 -0.0100481 -0.0191763 -0.224773 -0.0210101 -0.0382974 -0.224773 -0.0135339 -0.0269688 -0.224773 -0.0170549 -0.0335044 -0.224773 -0.0205797 -0.0374532 -0.224773 -0.0211401 -0.039236 -0.222899 -0.0174195 -0.0426916 -0.222827 -0.0190658 -0.0435843 -0.224573 -0.0212054 -0.0426494 -0.224573 -0.0207922 -0.0430719 -0.222663 -0.0207925 -0.0430716 -0.224573 -0.0202884 -0.0433806 -0.222736 -0.0201406 -0.0434419 -0.222503 -0.0216663 -0.0415711 -0.224573 -0.02153 -0.0420723 -0.224573 -0.0216664 -0.041571 0.0200674 0.141947 0.0257356 0.0206687 0.142012 0.0255498 0.0200394 0.142012 0.0256424 0.0200927 0.141735 0.0258198 0.0206687 0.14185 0.0257122 0.0206687 0.141885 0.0256949 0.0206687 0.141947 0.0256472 0.019553 0.14185 0.0260477 0.0200862 0.14185 0.0257979 0.0194002 0.142035 0.0258165 0.0191319 0.141735 0.026455 0.0191144 0.14185 0.0264404 0.019101 0.141885 0.0264293 0.0195171 0.141947 0.0259934 0.0190644 0.141947 0.0263988 0.0194635 0.142012 0.0259123 0.0168268 0.14185 0.0215579 0.0184814 0.141735 0.0220326 0.019101 0.141885 0.0226408 0.0184592 0.141885 0.0220661 0.0190167 0.141995 0.022711 0.0183987 0.141995 0.0221577 0.0189014 0.142035 0.022807 0.0183159 0.142035 0.0222828 0.0168268 0.141947 0.0216229 0.0176791 0.141885 0.0217006 0.0176475 0.141995 0.0218058 0.0206687 0.141995 0.025585 0.0289849 0.141995 0.025585 0.0289849 0.141735 0.025735 0.0194223 0.141885 0.0229502 0.0192636 0.142035 0.0231559 0.0193552 0.141995 0.0230372 0.0196929 0.142035 0.0234178 0.0197565 0.141995 0.023282 0.0201688 0.142035 0.0235801 0.0198031 0.141885 0.0231825 0.0202014 0.141995 0.0234337 0.0206687 0.141995 0.023485 0.0202253 0.141885 0.0233265 0.0206687 0.141885 0.0233752 0.0194468 0.141735 0.0229184 0.0198201 0.141735 0.0231461 0.020234 0.141735 0.0232872 0.0306369 0.141995 0.026359 0.0299607 0.142035 0.0256523 0.0298971 0.141995 0.0257881 0.0294848 0.142035 0.02549 0.0302984 0.141995 0.0260329 0.0302313 0.141885 0.0261198 0.0294522 0.141995 0.0256364 0.0298505 0.141885 0.0258876 0.0294283 0.141885 0.0257436 0.0289849 0.141885 0.0256949 0.0302068 0.141735 0.0261517 0.0298335 0.141735 0.025924 0.0206687 0.142035 0.023635 0.0289849 0.141995 0.023485 0.0309177 0.141885 0.0267968 0.0305526 0.141885 0.0264293 0.0305217 0.141735 0.026455 0.0313211 0.141735 0.0271298 0.0313413 0.141885 0.0270951 0.0328268 0.141735 0.027535 0.0313964 0.141995 0.0270001 0.0318104 0.141885 0.0273149 0.0323299 0.141995 0.0273414 0.0323107 0.141885 0.0274495 0.0328268 0.141885 0.0274948 0.0309885 0.141995 0.0267129 0.0318482 0.141995 0.0272117 0.032356 0.142035 0.0271937 0.0328268 0.141995 0.027385 0.0328268 0.142035 0.027235 0.0294283 0.141885 0.0233265 0.0289849 0.141885 0.0233752 0.0299607 0.142035 0.0234178 0.0298971 0.141995 0.023282 0.03039 0.142035 0.0231559 0.0302984 0.141995 0.0230372 0.0306369 0.141995 0.022711 0.0294522 0.141995 0.0234337 0.0298505 0.141885 0.0231825 0.0305526 0.141885 0.0226408 0.0298335 0.141735 0.0231461 0.0302313 0.141885 0.0229502 0.0302068 0.141735 0.0229184 0.0305217 0.141735 0.022615 0.0366687 0.14185 0.0257122 0.0362253 0.141885 0.0257436 0.0362014 0.141995 0.0256364 0.0352636 0.142035 0.0259142 0.0350167 0.141995 0.026359 0.0366687 0.141885 0.0256949 0.0357565 0.141995 0.0257881 0.0358031 0.141885 0.0258876 0.0353552 0.141995 0.0260329 0.036234 0.141735 0.0257828 0.0354223 0.141885 0.0261198 0.035101 0.141885 0.0264293 0.0349014 0.142035 0.022807 0.0343987 0.141995 0.0221577 0.0344592 0.141885 0.0220661 0.0344814 0.141735 0.0220326 0.035101 0.141885 0.0226408 0.0336791 0.141885 0.0217006 0.0328268 0.141735 0.021535 0.0319629 0.141735 0.0216621 0.0311944 0.141885 0.0220661 0.0311722 0.141735 0.0220326 0.0328268 0.141885 0.0215752 0.0336475 0.141995 0.0218058 0.0320061 0.141995 0.0218058 0.0319745 0.141885 0.0217006 0.0312549 0.141995 0.0221577 0.0328268 0.141995 0.021685 0.0328268 0.142035 0.021835 0.0320493 0.142035 0.0219494 0.0307522 0.142035 0.022807 0.0366687 0.142012 0.0255498 0.0449849 0.142035 0.025435 0.0449849 0.141995 0.025585 0.0366687 0.141995 0.025585 0.0449849 0.141947 0.0256472 0.0366687 0.141947 0.0256472 0.0449849 0.141885 0.0256949 0.0449849 0.141735 0.025735 0.0351319 0.141735 0.022615 0.0350167 0.141995 0.022711 0.0353552 0.141995 0.0230372 0.0357565 0.141995 0.023282 0.0361688 0.142035 0.0235801 0.0362014 0.141995 0.0234337 0.0358031 0.141885 0.0231825 0.0354468 0.141735 0.0229184 0.0354223 0.141885 0.0229502 0.0358201 0.141735 0.0231461 0.0362253 0.141885 0.0233265 0.036234 0.141735 0.0232872 0.0462313 0.141885 0.0261198 0.0466369 0.141995 0.026359 0.0462984 0.141995 0.0260329 0.0458971 0.141995 0.0257881 0.0454848 0.142035 0.02549 0.0459607 0.142035 0.0256523 0.0467522 0.142035 0.026263 0.0449849 0.142012 0.0255498 0.0454522 0.141995 0.0256364 0.0465217 0.141735 0.026455 0.0458505 0.141885 0.0258876 0.0462068 0.141735 0.0261517 0.0454283 0.141885 0.0257436 0.0449849 0.14185 0.0257122 0.0449849 0.142012 0.0235202 0.0366687 0.141995 0.023485 0.0449849 0.141947 0.0234229 0.0366687 0.141947 0.0234229 0.0366687 0.141885 0.0233752 0.0449849 0.14185 0.0233579 0.0366687 0.141735 0.023335 0.0469177 0.141885 0.0267968 0.0465526 0.141885 0.0264293 0.0473211 0.141735 0.0271298 0.0469885 0.141995 0.0267129 0.0473413 0.141885 0.0270951 0.0478104 0.141885 0.0273149 0.0478482 0.141995 0.0272117 0.0483107 0.141885 0.0274495 0.0488268 0.141995 0.027385 0.0470853 0.142035 0.0265983 0.0473964 0.141995 0.0270001 0.0474717 0.142035 0.0268704 0.0478997 0.142035 0.0270709 0.0483299 0.141995 0.0273414 0.0456142 0.142012 0.0234277 0.0455862 0.141947 0.0233345 0.0455674 0.14185 0.0232722 0.0465217 0.141735 0.022615 0.0465392 0.14185 0.0226297 0.046088 0.141735 0.0230034 0.0461006 0.14185 0.0230224 0.0461365 0.141947 0.0230766 0.0465892 0.141947 0.0226713 0.0461901 0.142012 0.0231578 0.0467522 0.142035 0.022807 0.0526687 0.141947 0.0256472 0.0526687 0.142035 0.025435 0.0526687 0.141885 0.0256949 0.0516929 0.142035 0.0256523 0.0522014 0.141995 0.0256364 0.0522253 0.141885 0.0257436 0.0517565 0.141995 0.0257881 0.0518031 0.141885 0.0258876 0.0513552 0.141995 0.0260329 0.0510644 0.141947 0.0263988 0.051101 0.141885 0.0264293 0.0514223 0.141885 0.0261198 0.052234 0.141735 0.0257828 0.0518201 0.141735 0.025924 0.0514468 0.141735 0.0261517 0.0511144 0.14185 0.0264404 0.0511319 0.141735 0.026455 0.0504592 0.141885 0.0220661 0.0496907 0.141735 0.0216621 0.0488268 0.141885 0.0215752 0.0479629 0.141735 0.0216621 0.0471722 0.141735 0.0220326 0.0471944 0.141885 0.0220661 0.0465526 0.141885 0.0226408 0.0496791 0.141885 0.0217006 0.0496475 0.141995 0.0218058 0.0479745 0.141885 0.0217006 0.0488268 0.141995 0.021685 0.0466369 0.141995 0.022711 0.0503987 0.141995 0.0221577 0.0503159 0.142035 0.0222828 0.0480061 0.141995 0.0218058 0.0472549 0.141995 0.0221577 0.0480493 0.142035 0.0219494 0.0526687 0.142012 0.0255498 0.0609849 0.141995 0.025585 0.0526687 0.141995 0.025585 0.0609849 0.141947 0.0256472 0.0609849 0.141885 0.0256949 0.0526687 0.14185 0.0257122 0.0526687 0.141735 0.025735 0.0609849 0.141735 0.025735 0.0511319 0.141735 0.022615 0.051101 0.141885 0.0226408 0.0513552 0.141995 0.0230372 0.0509014 0.142035 0.022807 0.0510167 0.141995 0.022711 0.0516929 0.142035 0.0234178 0.0521688 0.142035 0.0235801 0.0526687 0.141995 0.023485 0.0514223 0.141885 0.0229502 0.0517565 0.141995 0.023282 0.0518031 0.141885 0.0231825 0.0522014 0.141995 0.0234337 0.0522253 0.141885 0.0233265 0.0526687 0.141885 0.0233752 0.0625892 0.141947 0.0263988 0.0622313 0.141885 0.0261198 0.0622984 0.141995 0.0260329 0.0609849 0.142012 0.0255498 0.0614522 0.141995 0.0256364 0.0618971 0.141995 0.0257881 0.0619607 0.142035 0.0256523 0.0622068 0.141735 0.0261517 0.0618335 0.141735 0.025924 0.0618505 0.141885 0.0258876 0.0614283 0.141885 0.0257436 0.0614196 0.141735 0.0257828 0.0609849 0.14185 0.0257122 0.0609849 0.142035 0.023635 0.0526687 0.142035 0.023635 0.0609849 0.141947 0.0234229 0.0526687 0.141947 0.0234229 0.0609849 0.14185 0.0233579 0.0609849 0.141735 0.023335 0.0625217 0.141735 0.026455 0.0625392 0.14185 0.0264404 0.0625526 0.141885 0.0264293 0.0632207 0.141947 0.0269642 0.0626369 0.141995 0.026359 0.0633377 0.142035 0.0267873 0.0627522 0.142035 0.026263 0.062664 0.142012 0.0263365 0.0632743 0.142012 0.026883 0.0631848 0.14185 0.0270185 0.0639882 0.141947 0.0273238 0.0648268 0.141735 0.027535 0.0639695 0.14185 0.0273861 0.0640162 0.142012 0.0272306 0.0640493 0.142035 0.0271207 0.0648268 0.142035 0.027235 0.0616472 0.142035 0.0235376 0.0609849 0.142012 0.0235202 0.0615674 0.14185 0.0232722 0.0621006 0.14185 0.0230224 0.0615862 0.141947 0.0233345 0.0621901 0.142012 0.0231578 0.0622534 0.142035 0.0232536 0.0616142 0.142012 0.0234277 0.0621364 0.141947 0.0230766 0.062088 0.141735 0.0230034 0.018135 0.149043 0.0247448 0.0177497 0.149347 0.023792 0.0165461 0.149463 0.0233152 0.0164852 0.149453 0.0234178 0.0171063 0.149463 0.0233151 0.0170496 0.14946 0.0233896 0.0176077 0.149386 0.0236523 0.0163153 0.149435 0.0234815 0.0159918 0.149373 0.0237003 0.0162799 0.149438 0.0234058 0.0158425 0.149345 0.0237393 0.0154679 0.149063 0.0241356 0.0154674 0.149026 0.0241248 0.0154763 0.149101 0.0241491 0.0154932 0.149137 0.0241647 0.0159714 0.149286 0.0234244 0.0174048 0.1494 0.0233239 0.0168254 0.149434 0.0231951 0.0171317 0.14935 0.0231675 0.0168253 0.149358 0.0231339 0.0165292 0.149425 0.023228 0.0182073 0.148973 0.0247329 0.0178871 0.149272 0.023652 0.0181604 0.149137 0.0241646 0.0178992 0.149234 0.0236306 0.0181773 0.149101 0.024149 0.0179035 0.149194 0.0236154 0.017901 0.149154 0.0236064 0.0178755 0.149161 0.0235777 0.0176816 0.149286 0.0234238 0.0176567 0.149359 0.0234774 0.0178107 0.149345 0.0237387 0.0180672 0.14921 0.0242139 0.017841 0.14933 0.0237083 0.0154463 0.148973 0.0247329 0.0155183 0.149169 0.0241815 0.0155186 0.149043 0.0247448 0.0156588 0.149218 0.0242384 0.0157859 0.149305 0.0236791 0.0159963 0.149359 0.023478 0.0158121 0.14933 0.0237088 0.0162623 0.149424 0.0233639 0.0157496 0.149193 0.023616 0.0157539 0.149234 0.0236312 0.015766 0.149272 0.0236526 0.0155863 0.14921 0.0242141 0.0181856 0.149063 0.0241355 0.018234 0.148971 0.0243458 0.0174218 0.149326 0.023266 0.0165205 0.14935 0.0231677 0.0168268 0.149274 0.023115 0.0165474 0.149267 0.0231428 0.0181749 0.149013 0.0247408 0.0181352 0.149169 0.0241814 0.0178672 0.149305 0.0236785 0.0174692 0.149237 0.0232687 0.0173723 0.149438 0.0234051 0.0173898 0.149424 0.0233633 0.0171231 0.149425 0.0232279 0.0168254 0.149471 0.0232844 0.0162474 0.1494 0.0233246 0.0162303 0.149325 0.0232667 0.0155667 0.148755 0.0251897 0.017971 0.148927 0.0251793 0.0182317 0.148913 0.0247182 0.0180811 0.148788 0.0251941 0.0180878 0.148755 0.0251875 0.0182038 0.148835 0.0248815 0.0178755 0.148675 0.0254924 0.0180689 0.148821 0.0251979 0.0177614 0.148713 0.02559 0.0158773 0.148649 0.0255909 0.0156263 0.148882 0.0251972 0.0155854 0.148821 0.0251999 0.015894 0.148712 0.0255917 0.0163263 0.148639 0.0258535 0.017313 0.148697 0.0258265 0.018028 0.148882 0.0251954 0.0168023 0.148743 0.0258146 0.0163883 0.148769 0.0257331 0.0162232 0.148793 0.0256545 0.0156159 0.149071 0.0247411 0.0157442 0.148946 0.0251555 0.0159669 0.148817 0.0255428 0.0180377 0.149071 0.0247411 0.0179102 0.148947 0.0251537 0.0176442 0.148841 0.0254996 0.0176884 0.148817 0.0255412 0.0174259 0.148792 0.0256572 0.0169059 0.148744 0.0258122 0.0155733 0.148787 0.0251961 0.0154219 0.148913 0.0247182 0.0154335 0.148949 0.0247273 0.0163164 0.148578 0.0258601 0.0168268 0.148552 0.025955 0.0168284 0.148613 0.0259456 0.0173301 0.148639 0.0258524 0.0154787 0.149013 0.0247408 0.0156832 0.148926 0.025181 0.0159254 0.148772 0.0255752 0.0163652 0.148742 0.0257848 0.0168282 0.148716 0.02587 0.0163433 0.148697 0.0258275 0.0168283 0.148671 0.0259162 0.017291 0.148743 0.0257838 0.01773 0.148772 0.0255736 0.0336077 0.149386 0.0236523 0.0337497 0.149347 0.023792 0.0339591 0.149248 0.0241366 0.0325461 0.149463 0.0233152 0.033337 0.149435 0.0234809 0.0322799 0.149438 0.0234058 0.0318425 0.149345 0.0237393 0.0319918 0.149373 0.0237003 0.0315186 0.149043 0.0247448 0.0315057 0.149054 0.0240144 0.0314674 0.149026 0.0241248 0.0314174 0.148879 0.0247086 0.0314763 0.149101 0.0241491 0.0314219 0.148913 0.0247182 0.0314932 0.149137 0.0241647 0.031778 0.149161 0.0235778 0.0317496 0.149193 0.023616 0.0319075 0.149192 0.023453 0.0319714 0.149286 0.0234244 0.0334048 0.1494 0.0233239 0.0331231 0.149425 0.0232279 0.0328253 0.149358 0.0231339 0.0322303 0.149325 0.0232667 0.0342073 0.148973 0.0247329 0.0338871 0.149272 0.023652 0.0341604 0.149137 0.0241646 0.0341773 0.149101 0.024149 0.0341856 0.149063 0.0241355 0.0339845 0.149128 0.0237128 0.033901 0.149154 0.0236064 0.0339035 0.149194 0.0236154 0.0338755 0.149161 0.0235777 0.0338992 0.149234 0.0236306 0.0338672 0.149305 0.0236785 0.0340672 0.14921 0.0242139 0.0338107 0.149345 0.0237387 0.033841 0.14933 0.0237083 0.0314463 0.148973 0.0247329 0.0314787 0.149013 0.0247408 0.0318121 0.14933 0.0237088 0.0322623 0.149424 0.0233639 0.0323153 0.149435 0.0234815 0.0317521 0.149154 0.0236069 0.0314679 0.149063 0.0241356 0.0317539 0.149234 0.0236312 0.031766 0.149272 0.0236526 0.0317859 0.149305 0.0236791 0.0315183 0.149169 0.0241815 0.0315863 0.14921 0.0242141 0.0331317 0.14935 0.0231675 0.0334692 0.149237 0.0232687 0.0325205 0.14935 0.0231677 0.0325474 0.149267 0.0231428 0.032357 0.149254 0.0231951 0.0322315 0.149242 0.0232459 0.0341749 0.149013 0.0247408 0.0341352 0.149169 0.0241814 0.0336567 0.149359 0.0234774 0.0336816 0.149286 0.0234238 0.0334218 0.149326 0.023266 0.0336812 0.149205 0.0234011 0.0333723 0.149438 0.0234051 0.0333898 0.149424 0.0233633 0.0331063 0.149463 0.0233151 0.0328254 0.149471 0.0232844 0.0328254 0.149434 0.0231951 0.0325292 0.149425 0.023228 0.0322474 0.1494 0.0233246 0.0319963 0.149359 0.023478 0.0315667 0.148755 0.0251897 0.034135 0.149043 0.0247448 0.0340689 0.148821 0.0251979 0.0342317 0.148913 0.0247182 0.0340811 0.148788 0.0251941 0.0333301 0.148639 0.0258524 0.0337782 0.14865 0.0255892 0.0318773 0.148649 0.0255909 0.0315733 0.148787 0.0251961 0.031679 0.148707 0.0253709 0.0317781 0.148675 0.0254923 0.0323263 0.148639 0.0258535 0.0321882 0.148593 0.0258033 0.0316263 0.148882 0.0251972 0.0318941 0.148712 0.0255917 0.0328283 0.148671 0.0259162 0.033313 0.148697 0.0258265 0.0337614 0.148713 0.02559 0.0323652 0.148742 0.0257848 0.0323883 0.148769 0.0257331 0.0316832 0.148926 0.025181 0.0318379 0.1489 0.0253078 0.032011 0.148841 0.0255011 0.0319669 0.148817 0.0255428 0.0322232 0.148793 0.0256545 0.0336884 0.148817 0.0255412 0.0332678 0.148769 0.0257321 0.0328282 0.148716 0.02587 0.0328023 0.148743 0.0258146 0.0314498 0.148835 0.0248814 0.0315854 0.148821 0.0251999 0.0314335 0.148949 0.0247273 0.0323164 0.148578 0.0258601 0.032905 0.148553 0.0259529 0.0328284 0.148613 0.0259456 0.03334 0.148578 0.025859 0.0335241 0.148601 0.0257721 0.0319254 0.148772 0.0255752 0.0323433 0.148697 0.0258275 0.033291 0.148743 0.0257838 0.03373 0.148772 0.0255736 0.033971 0.148927 0.0251793 0.034028 0.148882 0.0251954 0.0494048 0.1494 0.0233239 0.0498755 0.149161 0.0235777 0.0496812 0.149205 0.0234011 0.0499591 0.149248 0.0241366 0.0499947 0.149218 0.0242383 0.0488255 0.149466 0.0233689 0.0491063 0.149463 0.0233151 0.0490496 0.14946 0.0233896 0.0493723 0.149438 0.0234051 0.049337 0.149435 0.0234809 0.0496077 0.149386 0.0236523 0.0475186 0.149043 0.0247448 0.0476159 0.149071 0.0247411 0.0474674 0.149026 0.0241248 0.0474679 0.149063 0.0241356 0.0474219 0.148913 0.0247182 0.0474335 0.148949 0.0247273 0.0475183 0.149169 0.0241815 0.0479714 0.149286 0.0234244 0.0477496 0.149193 0.023616 0.0488254 0.149434 0.0231951 0.0491317 0.14935 0.0231675 0.0485205 0.14935 0.0231677 0.0482474 0.1494 0.0233246 0.0501773 0.149101 0.024149 0.0501604 0.149137 0.0241646 0.0501856 0.149063 0.0241355 0.049901 0.149154 0.0236064 0.0499035 0.149194 0.0236154 0.0498992 0.149234 0.0236306 0.0496816 0.149286 0.0234238 0.0498871 0.149272 0.023652 0.0497497 0.149347 0.023792 0.0500672 0.14921 0.0242139 0.049841 0.14933 0.0237083 0.0474463 0.148973 0.0247329 0.0474787 0.149013 0.0247408 0.0475863 0.14921 0.0242141 0.0477022 0.149253 0.0241176 0.0477859 0.149305 0.0236791 0.0478121 0.14933 0.0237088 0.0482799 0.149438 0.0234058 0.0483153 0.149435 0.0234815 0.0477521 0.149154 0.0236069 0.0477539 0.149234 0.0236312 0.047766 0.149272 0.0236526 0.0474763 0.149101 0.0241491 0.0474932 0.149137 0.0241647 0.0478425 0.149345 0.0237393 0.0502039 0.14901 0.0241887 0.0502362 0.148879 0.0247086 0.0494218 0.149326 0.023266 0.0494692 0.149237 0.0232687 0.0488253 0.149358 0.0231339 0.0488268 0.149274 0.023115 0.048357 0.149254 0.0231951 0.0501352 0.149169 0.0241814 0.0498672 0.149305 0.0236785 0.0496567 0.149359 0.0234774 0.0493898 0.149424 0.0233633 0.0498107 0.149345 0.0237387 0.0491231 0.149425 0.0232279 0.0488254 0.149471 0.0232844 0.0485461 0.149463 0.0233152 0.0485292 0.149425 0.023228 0.0482623 0.149424 0.0233639 0.0479963 0.149359 0.023478 0.0482303 0.149325 0.0232667 0.0474498 0.148835 0.0248814 0.050135 0.149043 0.0247448 0.0502317 0.148913 0.0247182 0.0502073 0.148973 0.0247329 0.0499838 0.148711 0.0253581 0.0502038 0.148835 0.0248815 0.0500811 0.148788 0.0251941 0.0497614 0.148713 0.02559 0.0483164 0.148578 0.0258601 0.0475854 0.148821 0.0251999 0.0475667 0.148755 0.0251897 0.047679 0.148707 0.0253709 0.0478773 0.148649 0.0255909 0.0483263 0.148639 0.0258535 0.0481882 0.148593 0.0258033 0.047894 0.148712 0.0255917 0.0488284 0.148613 0.0259456 0.0493301 0.148639 0.0258524 0.0501749 0.149013 0.0247408 0.0500689 0.148821 0.0251979 0.0488023 0.148743 0.0258146 0.0483652 0.148742 0.0257848 0.0483883 0.148769 0.0257331 0.0477442 0.148946 0.0251555 0.0478379 0.1489 0.0253078 0.048011 0.148841 0.0255011 0.0482232 0.148793 0.0256545 0.049971 0.148927 0.0251793 0.0494259 0.148792 0.0256572 0.0475733 0.148787 0.0251961 0.048905 0.148553 0.0259529 0.04934 0.148578 0.025859 0.0476832 0.148926 0.025181 0.0479669 0.148817 0.0255428 0.0476263 0.148882 0.0251972 0.0479254 0.148772 0.0255752 0.0483433 0.148697 0.0258275 0.0488283 0.148671 0.0259162 0.0488282 0.148716 0.02587 0.049291 0.148743 0.0257838 0.049313 0.148697 0.0258265 0.0496884 0.148817 0.0255412 0.0497301 0.148772 0.0255736 0.050028 0.148882 0.0251954 0.0661862 0.149026 0.0241246 0.0653898 0.149424 0.0233633 0.0659845 0.149128 0.0237128 0.0660672 0.14921 0.0242139 0.0659947 0.149218 0.0242383 0.0645461 0.149463 0.0233152 0.0648254 0.149471 0.0232844 0.0651063 0.149463 0.0233151 0.0648255 0.149466 0.0233689 0.0650496 0.14946 0.0233896 0.0653723 0.149438 0.0234051 0.065337 0.149435 0.0234809 0.0639918 0.149373 0.0237003 0.0634335 0.148949 0.0247273 0.0634219 0.148913 0.0247182 0.0639714 0.149286 0.0234244 0.0637539 0.149234 0.0236312 0.0648254 0.149434 0.0231951 0.0648253 0.149358 0.0231339 0.0645205 0.14935 0.0231677 0.0662073 0.148973 0.0247329 0.0658871 0.149272 0.023652 0.0661856 0.149063 0.0241355 0.0661773 0.149101 0.024149 0.0659035 0.149194 0.0236154 0.0658992 0.149234 0.0236306 0.0656816 0.149286 0.0234238 0.0661604 0.149137 0.0241646 0.0657497 0.149347 0.023792 0.0658107 0.149345 0.0237387 0.0634787 0.149013 0.0247408 0.0635183 0.149169 0.0241815 0.0635863 0.14921 0.0242141 0.0635186 0.149043 0.0247448 0.0636588 0.149218 0.0242384 0.0637859 0.149305 0.0236791 0.0638121 0.14933 0.0237088 0.0642623 0.149424 0.0233639 0.0642799 0.149438 0.0234058 0.0643153 0.149435 0.0234815 0.0644852 0.149453 0.0234178 0.0637496 0.149193 0.023616 0.0634679 0.149063 0.0241356 0.0634763 0.149101 0.0241491 0.063766 0.149272 0.0236526 0.0634932 0.149137 0.0241647 0.0638425 0.149345 0.0237393 0.0662317 0.148913 0.0247182 0.0662362 0.148879 0.0247086 0.0654692 0.149237 0.0232687 0.0651317 0.14935 0.0231675 0.0648268 0.149274 0.023115 0.0645474 0.149267 0.0231428 0.0642315 0.149242 0.0232459 0.0661352 0.149169 0.0241814 0.065841 0.14933 0.0237083 0.0658672 0.149305 0.0236785 0.0654048 0.1494 0.0233239 0.0656567 0.149359 0.0234774 0.0654218 0.149326 0.023266 0.0651231 0.149425 0.0232279 0.0645292 0.149425 0.023228 0.0642474 0.1494 0.0233246 0.0639963 0.149359 0.023478 0.0642303 0.149325 0.0232667 0.0639717 0.149204 0.0234017 0.066135 0.149043 0.0247448 0.0660377 0.149071 0.0247411 0.0662038 0.148835 0.0248815 0.0660878 0.148755 0.0251875 0.0660811 0.148788 0.0251941 0.0643263 0.148639 0.0258535 0.0643164 0.148578 0.0258601 0.0638773 0.148649 0.0255909 0.063894 0.148712 0.0255917 0.0634463 0.148973 0.0247329 0.0636263 0.148882 0.0251972 0.0635854 0.148821 0.0251999 0.0639254 0.148772 0.0255752 0.0657301 0.148772 0.0255736 0.0657614 0.148713 0.02559 0.066028 0.148882 0.0251954 0.0660689 0.148821 0.0251979 0.0648023 0.148743 0.0258146 0.0643652 0.148742 0.0257848 0.0637442 0.148946 0.0251555 0.0636832 0.148926 0.025181 0.0639669 0.148817 0.0255428 0.064011 0.148841 0.0255011 0.065971 0.148927 0.0251793 0.0659102 0.148947 0.0251537 0.0658216 0.148902 0.0252995 0.0652678 0.148769 0.0257321 0.0649059 0.148744 0.0258122 0.0634174 0.148879 0.0247086 0.0635733 0.148787 0.0251961 0.0648268 0.148552 0.025955 0.0648284 0.148613 0.0259456 0.064905 0.148553 0.0259529 0.0653301 0.148639 0.0258524 0.06534 0.148578 0.025859 0.0655241 0.148601 0.0257721 0.0643433 0.148697 0.0258275 0.0648282 0.148716 0.02587 0.0648283 0.148671 0.0259162 0.065291 0.148743 0.0257838 0.065313 0.148697 0.0258265 0.0656884 0.148817 0.0255412 0.0661749 0.149013 0.0247408 0.0639035 0.149347 0.0237925 0.0637022 0.149253 0.0241176 0.0648268 0.149071 0.0247411 0.0659591 0.149248 0.0241366 0.0656077 0.149386 0.0236523 0.0654259 0.148792 0.0256572 0.0656442 0.148841 0.0254996 0.0636159 0.149071 0.0247411 0.0638379 0.1489 0.0253078 0.0642232 0.148793 0.0256545 0.0643883 0.148769 0.0257331 0.0657782 0.14865 0.0255892 0.0658749 0.142035 0.0254931 0.0658755 0.148675 0.0254924 0.0659838 0.148711 0.0253581 0.066234 0.148971 0.0243458 0.065901 0.149154 0.0236064 0.0656812 0.149205 0.0234011 0.0652958 0.142035 0.0231947 0.0651308 0.149266 0.0231481 0.0648268 0.142035 0.023115 0.0484852 0.149453 0.0234178 0.0479918 0.149373 0.0237003 0.0479034 0.149347 0.0237925 0.0476588 0.149218 0.0242384 0.0500377 0.149071 0.0247411 0.0488268 0.149071 0.0247411 0.0492678 0.148769 0.0257321 0.0496442 0.148841 0.0254996 0.0498216 0.148902 0.0252995 0.0499102 0.148947 0.0251537 0.0489059 0.148744 0.0258122 0.0497782 0.14865 0.0255892 0.0495241 0.148601 0.0257721 0.0502038 0.142035 0.024882 0.0500878 0.148755 0.0251875 0.0498755 0.148675 0.0254924 0.0499845 0.149128 0.0237128 0.0501862 0.149026 0.0241246 0.050234 0.148971 0.0243458 0.0492958 0.142035 0.0231947 0.0491308 0.149266 0.0231481 0.0488268 0.142035 0.023115 0.0324852 0.149453 0.0234178 0.0319034 0.149347 0.0237925 0.0317022 0.149253 0.0241176 0.0316588 0.149218 0.0242384 0.0316159 0.149071 0.0247411 0.0339947 0.149218 0.0242383 0.0328268 0.149071 0.0247411 0.0330496 0.14946 0.0233896 0.0328255 0.149466 0.0233689 0.0334259 0.148792 0.0256572 0.0336442 0.148841 0.0254996 0.0338216 0.148902 0.0252995 0.0339102 0.148947 0.0251537 0.0340377 0.149071 0.0247411 0.0317442 0.148946 0.0251555 0.0329059 0.148744 0.0258122 0.0328268 0.142035 0.025955 0.0332958 0.142035 0.0258754 0.0342038 0.148835 0.0248815 0.0340878 0.148755 0.0251875 0.0339838 0.148711 0.0253581 0.0338749 0.142035 0.0254931 0.0338755 0.148675 0.0254924 0.0342362 0.148879 0.0247086 0.034234 0.148971 0.0243458 0.0341862 0.149026 0.0241246 0.0342039 0.14901 0.0241887 0.0331308 0.149266 0.0231481 0.0328268 0.142035 0.023115 0.0456472 0.142035 0.0235376 0.0449849 0.142035 0.023635 0.0143708 0.142035 0.0234134 0.0141543 0.142035 0.0241508 0.0141543 0.142035 0.0249193 0.0154498 0.142035 0.024882 0.0294848 0.142035 0.0235801 0.0307522 0.142035 0.026263 0.03039 0.142035 0.0259142 0.0662038 0.142035 0.024882 0.0662038 0.142035 0.0241881 0.0614848 0.142035 0.02549 0.0182038 0.142035 0.0241881 0.0477787 0.142035 0.0254931 0.04639 0.142035 0.0259142 0.0361688 0.142035 0.02549 0.0521688 0.142035 0.02549 0.0634498 0.142035 0.0241881 0.06239 0.142035 0.0259142 0.0643578 0.142035 0.0258754 0.0648268 0.142035 0.025955 0.0652958 0.142035 0.0258754 0.0655875 0.142035 0.0271257 0.0662865 0.142035 0.0268064 0.0163578 0.142035 0.0231947 0.0153671 0.142035 0.0222637 0.0147863 0.142035 0.0227669 0.0178749 0.142035 0.023577 0.0172958 0.142035 0.0231947 0.0176043 0.142035 0.0219494 0.0168268 0.142035 0.023115 0.0168268 0.142035 0.021835 0.0289849 0.142035 0.025435 0.0206687 0.142035 0.025435 0.0289849 0.142035 0.023635 0.0183159 0.142035 0.0267873 0.0178749 0.142035 0.0254931 0.0189014 0.142035 0.026263 0.0200064 0.142035 0.0255325 0.0157787 0.142035 0.0254931 0.0147863 0.142035 0.0263032 0.0153671 0.142035 0.0268064 0.0160661 0.142035 0.0271257 0.0168268 0.142035 0.027235 0.0176043 0.142035 0.0271207 0.0172958 0.142035 0.0258754 0.0356929 0.142035 0.0234178 0.0356929 0.142035 0.0256523 0.0342038 0.142035 0.024882 0.0668673 0.142035 0.0227669 0.0658749 0.142035 0.023577 0.0648268 0.142035 0.021835 0.0338749 0.142035 0.023577 0.0366687 0.142035 0.025435 0.0310853 0.142035 0.0265983 0.0323578 0.142035 0.0258754 0.0473377 0.142035 0.0222828 0.0462534 0.142035 0.0232536 0.0502038 0.142035 0.0241881 0.0512636 0.142035 0.0231559 0.0609849 0.142035 0.025435 0.0483578 0.142035 0.0258754 0.048356 0.142035 0.0271937 0.0488268 0.142035 0.027235 0.0488268 0.142035 0.025955 0.0492958 0.142035 0.0258754 0.0317787 0.142035 0.023577 0.0313377 0.142035 0.0222828 0.0314498 0.142035 0.0241881 0.0342038 0.142035 0.0241881 0.0366687 0.142035 0.023635 0.0349014 0.142035 0.026263 0.0337539 0.142035 0.0270709 0.0341819 0.142035 0.0268704 0.0498749 0.142035 0.023577 0.0496043 0.142035 0.0219494 0.0488268 0.142035 0.021835 0.0503159 0.142035 0.0267873 0.0498749 0.142035 0.0254931 0.0509014 0.142035 0.026263 0.0512636 0.142035 0.0259142 0.0352636 0.142035 0.0231559 0.0332958 0.142035 0.0231947 0.0343159 0.142035 0.0222828 0.0336043 0.142035 0.0219494 0.0323578 0.142035 0.0231947 0.0314717 0.142035 0.0268704 0.0318997 0.142035 0.0270709 0.0493499 0.140835 0.0274891 0.0191319 0.140835 0.022615 0.0336907 0.140835 0.0216621 0.0191319 0.140835 0.026455 0.0351319 0.140835 0.022615 0.0313211 0.140835 0.0271298 0.0323037 0.140835 0.0274891 0.0351319 0.140835 0.026455 0.0639629 0.140835 0.027408 0.0631722 0.140835 0.0220326 0.0206687 0.140835 0.025735 0.0198201 0.140835 0.0231461 0.0458335 0.140835 0.025924 0.0449849 0.140835 0.023335 0.0366687 0.140835 0.025735 0.0366687 0.140835 0.023335 0.0358201 0.140835 0.025924 0.0471722 0.140835 0.0220326 0.0511319 0.140835 0.022615 0.0305217 0.140835 0.022615 0.0311722 0.140835 0.0220326 0.0319629 0.140835 0.0216621 0.0298335 0.140835 0.025924 0.0483037 0.140835 0.0274891 0.0488268 0.140835 0.021535 0.0609849 0.140835 0.023335 0.0526687 0.140835 0.025735 0.0518201 0.140835 0.0231461 0.0518201 0.140835 0.025924 0.0156787 0.140835 0.0273067 0.0659748 0.140835 0.0273067 0.0669481 0.140835 0.0224137 0.0138268 0.140835 0.024535 0.0147055 0.140835 0.0266564 0.0184814 0.140835 0.0270375 0.0176907 0.140835 0.027408 0.0168268 0.140835 0.027535 0.0195656 0.141735 0.0260667 0.0198201 0.141735 0.025924 0.0198201 0.140835 0.025924 0.0206687 0.141735 0.025735 0.0289849 0.140835 0.025735 0.0294196 0.141735 0.0257828 0.0347618 0.141735 0.0268276 0.0343325 0.140835 0.0271298 0.0333499 0.140835 0.0274891 0.0333499 0.141735 0.0274891 0.0323037 0.141735 0.0274891 0.0317966 0.141735 0.0273526 0.0305217 0.140835 0.026455 0.0308918 0.141735 0.0268276 0.0366687 0.141735 0.025735 0.0354468 0.141735 0.0261517 0.0358201 0.141735 0.025924 0.0449849 0.140835 0.025735 0.0454196 0.141735 0.0257828 0.0458335 0.141735 0.025924 0.0511319 0.140835 0.026455 0.0503325 0.140835 0.0271298 0.0504814 0.141735 0.0270375 0.0488268 0.141735 0.027535 0.0483037 0.141735 0.0274891 0.0473211 0.140835 0.0271298 0.0477966 0.141735 0.0273526 0.0465217 0.140835 0.026455 0.0468918 0.141735 0.0268276 0.0609849 0.140835 0.025735 0.0625217 0.140835 0.026455 0.0618335 0.140835 0.025924 0.0625217 0.140835 0.022615 0.0625217 0.141735 0.022615 0.0639629 0.140835 0.0216621 0.0639629 0.141735 0.0216621 0.0618335 0.141735 0.0231461 0.0618335 0.140835 0.0231461 0.0615609 0.141735 0.0232503 0.0526687 0.141735 0.023335 0.0514468 0.141735 0.0229184 0.0526687 0.140835 0.023335 0.052234 0.141735 0.0232872 0.0518201 0.141735 0.0231461 0.0465217 0.140835 0.022615 0.0479629 0.140835 0.0216621 0.0449849 0.141735 0.023335 0.0455609 0.141735 0.0232503 0.0458335 0.140835 0.0231461 0.0458335 0.141735 0.0231461 0.0358201 0.140835 0.0231461 0.0289849 0.140835 0.023335 0.0294196 0.141735 0.0232872 0.0298335 0.140835 0.0231461 0.0289849 0.141735 0.023335 0.0206687 0.141735 0.023335 0.0206687 0.140835 0.023335 0.0168255 0.149466 0.0233689 0.0159035 0.149347 0.0237925 0.0157022 0.149253 0.0241176 0.0168268 0.149071 0.0247411 0.0179947 0.149218 0.0242383 0.0179591 0.149248 0.0241366 0.017337 0.149435 0.0234809 0.0172678 0.148769 0.0257321 0.0178216 0.148902 0.0252995 0.0158379 0.1489 0.0253078 0.016011 0.148841 0.0255011 0.016905 0.148553 0.0259529 0.0175241 0.148601 0.0257721 0.01734 0.148578 0.025859 0.0179838 0.148711 0.0253581 0.0182038 0.142035 0.024882 0.0177782 0.14865 0.0255892 0.0182362 0.148879 0.0247086 0.0179845 0.149128 0.0237128 0.0181862 0.149026 0.0241246 0.0182039 0.14901 0.0241887 0.0176812 0.149205 0.0234011 0.0171308 0.149266 0.0231481 0.0157781 0.148675 0.0254923 0.015679 0.148707 0.0253709 0.0168268 0.142035 0.025955 0.0163578 0.142035 0.0258754 0.0161882 0.148593 0.0258033 0.0162315 0.149242 0.0232459 0.016357 0.149254 0.0231951 0.0155057 0.149054 0.0240144 0.0157521 0.149154 0.0236069 0.015778 0.149161 0.0235778 0.0159075 0.149192 0.023453 0.0159717 0.149204 0.0234017 0.0154498 0.148835 0.0248814 0.0154174 0.148879 0.0247086 0.0154498 0.142035 0.0241881 0.0154497 0.14901 0.0241885 0.0157787 0.142035 0.023577 0.0336907 0.141735 0.0216621 0.0328268 0.140835 0.021535 0.0344814 0.140835 0.0220326 0.0488268 0.141735 0.021535 0.0496907 0.140835 0.0216621 0.0504814 0.141735 0.0220326 0.0504814 0.140835 0.0220326 0.065672 0.141735 0.0216566 0.0648268 0.140835 0.021535 0.0664487 0.141735 0.0220113 0.0659748 0.140835 0.0217634 0.0675984 0.141735 0.023387 0.0675984 0.140835 0.023387 0.0678268 0.140835 0.024535 0.0677963 0.141735 0.0241081 0.0677963 0.141735 0.024962 0.0675984 0.140835 0.0256831 0.0675557 0.141735 0.0257813 0.0670941 0.141735 0.0264996 0.0669481 0.140835 0.0266564 0.0669481 0.141735 0.0266564 0.0659748 0.141735 0.0273067 0.0648268 0.140835 0.027535 0.0639629 0.141735 0.027408 0.0631722 0.141735 0.0270375 0.0631722 0.140835 0.0270375 0.0168268 0.141735 0.021535 0.0176907 0.141735 0.0216621 0.0176907 0.140835 0.0216621 0.0191319 0.141735 0.022615 0.0184814 0.140835 0.0220326 0.0159816 0.141735 0.0274135 0.0156787 0.141735 0.0273067 0.0140552 0.140835 0.0256831 0.0145596 0.141735 0.0264996 0.0138573 0.141735 0.024962 0.0138268 0.141735 0.024535 0.0140552 0.140835 0.023387 0.0147055 0.140835 0.0224137 0.0156787 0.140835 0.0217634 0.0147055 0.141735 0.0224137 0.0168268 0.140835 0.021535 0.0156787 0.141735 0.0217634 0.0314498 0.142035 0.024882 0.0328268 0.148552 0.025955 0.0317787 0.142035 0.0254931 0.0328268 0.149274 0.023115 0.0319717 0.149204 0.0234017 0.0314498 0.14901 0.0241885 0.0488268 0.148552 0.025955 0.0477781 0.148675 0.0254923 0.0485474 0.149267 0.0231428 0.0482315 0.149242 0.0232459 0.0475057 0.149054 0.0240144 0.0477787 0.142035 0.023577 0.047778 0.149161 0.0235778 0.0483578 0.142035 0.0231947 0.0479075 0.149192 0.023453 0.0479717 0.149204 0.0234017 0.0474498 0.142035 0.024882 0.0474498 0.142035 0.0241881 0.0474174 0.148879 0.0247086 0.0474497 0.14901 0.0241885 0.0634498 0.142035 0.024882 0.0634498 0.148835 0.0248814 0.0637787 0.142035 0.0254931 0.0641882 0.148593 0.0258033 0.0637781 0.148675 0.0254923 0.063679 0.148707 0.0253709 0.0635667 0.148755 0.0251897 0.0634674 0.149026 0.0241248 0.0635057 0.149054 0.0240144 0.0637521 0.149154 0.0236069 0.0637787 0.142035 0.023577 0.0639075 0.149192 0.023453 0.0643578 0.142035 0.0231947 0.0656198 0.142012 0.0272358 0.0664487 0.141735 0.0270588 0.0664364 0.14185 0.0270396 0.0656656 0.14185 0.0273916 0.065672 0.141735 0.0274135 0.0648268 0.14185 0.0275122 0.0670768 0.14185 0.0264847 0.0675984 0.141735 0.0256831 0.0677737 0.14185 0.0249587 0.0678268 0.141735 0.024535 0.0675349 0.14185 0.0232983 0.0675557 0.141735 0.0232888 0.0670941 0.141735 0.0225705 0.0669481 0.141735 0.0224137 0.0659748 0.141735 0.0217634 0.0656656 0.14185 0.0216785 0.0648268 0.141947 0.0274472 0.0675349 0.14185 0.0257718 0.0674758 0.141947 0.0257448 0.0677093 0.141947 0.0241206 0.0677737 0.14185 0.0241113 0.0674758 0.141947 0.0233253 0.0670768 0.14185 0.0225854 0.0664364 0.14185 0.0220305 0.0648268 0.141885 0.0215752 0.0648268 0.142012 0.0273498 0.0656472 0.141947 0.0273292 0.0664012 0.141947 0.0269849 0.0670276 0.141947 0.0264421 0.0673872 0.142012 0.0257044 0.0677093 0.141947 0.0249495 0.067613 0.142012 0.0241345 0.0673872 0.142012 0.0233657 0.0670276 0.141947 0.022628 0.0669541 0.142012 0.0226917 0.0663486 0.142012 0.0221671 0.0664012 0.141947 0.0220852 0.0656472 0.141947 0.0217409 0.0656198 0.142012 0.0218343 0.0648268 0.141995 0.021685 0.0648268 0.142012 0.0217202 0.0663486 0.142012 0.026903 0.0669541 0.142012 0.0263783 0.0668673 0.142035 0.0263032 0.0672828 0.142035 0.0256567 0.067613 0.142012 0.0249356 0.0674993 0.142035 0.0249193 0.0674993 0.142035 0.0241508 0.0672828 0.142035 0.0234134 0.0662865 0.142035 0.0222637 0.0655875 0.142035 0.0219444 0.0648268 0.141735 0.021535 0.0648268 0.14185 0.0215579 0.0631722 0.141735 0.0220326 0.0631944 0.141885 0.0220661 0.0640061 0.141995 0.0218058 0.0648268 0.141947 0.0216229 0.0639745 0.141885 0.0217006 0.0640493 0.142035 0.0219494 0.0625392 0.14185 0.0226297 0.0625526 0.141885 0.0226408 0.0625892 0.141947 0.0226713 0.0626369 0.141995 0.022711 0.062664 0.142012 0.0227336 0.0632549 0.141995 0.0221577 0.0633377 0.142035 0.0222828 0.0627522 0.142035 0.022807 0.0496841 0.14185 0.0273861 0.0493499 0.141735 0.0274891 0.0496907 0.141735 0.027408 0.0488268 0.14185 0.0275122 0.0488268 0.141885 0.0274948 0.0488268 0.141947 0.0274472 0.0496374 0.142012 0.0272306 0.0504688 0.14185 0.0270185 0.0496654 0.141947 0.0273238 0.0496043 0.142035 0.0271207 0.0504329 0.141947 0.0269642 0.0510167 0.141995 0.026359 0.0503793 0.142012 0.026883 0.0338432 0.141885 0.0273149 0.033857 0.141735 0.0273526 0.0343123 0.141885 0.0270951 0.0343325 0.141735 0.0271298 0.0347359 0.141885 0.0267968 0.0351319 0.141735 0.026455 0.0333429 0.141885 0.0274495 0.0333237 0.141995 0.0273414 0.0346651 0.141995 0.0267129 0.0332976 0.142035 0.0271937 0.0338054 0.141995 0.0272117 0.0342572 0.141995 0.0270001 0.0345683 0.142035 0.0265983 0.0176907 0.141735 0.027408 0.0168268 0.14185 0.0275122 0.0184814 0.141735 0.0270375 0.0168268 0.141885 0.0274948 0.0176475 0.141995 0.0272643 0.0168268 0.142012 0.0273498 0.0176791 0.141885 0.0273695 0.0184592 0.141885 0.027004 0.0190167 0.141995 0.026359 0.0183987 0.141995 0.0269124 0.015988 0.14185 0.0273916 0.0152049 0.141735 0.0220113 0.015988 0.14185 0.0216785 0.0159816 0.141735 0.0216566 0.0145596 0.141735 0.0225705 0.0140979 0.141735 0.0232888 0.0140552 0.141735 0.023387 0.0138799 0.14185 0.0241113 0.0138573 0.141735 0.0241081 0.0140552 0.141735 0.0256831 0.0140979 0.141735 0.0257813 0.0141187 0.14185 0.0257718 0.0147055 0.141735 0.0266564 0.0152172 0.14185 0.0270396 0.0152049 0.141735 0.0270588 0.0160064 0.141947 0.0217409 0.0168268 0.141885 0.0215752 0.0152172 0.14185 0.0220305 0.0152524 0.141947 0.0220852 0.0145768 0.14185 0.0225854 0.014626 0.141947 0.022628 0.0141187 0.14185 0.0232983 0.0141778 0.141947 0.0233253 0.0139443 0.141947 0.0241206 0.0138799 0.14185 0.0249587 0.0139443 0.141947 0.0249495 0.0141778 0.141947 0.0257448 0.0145768 0.14185 0.0264847 0.0152524 0.141947 0.0269849 0.0160064 0.141947 0.0273292 0.0168268 0.141735 0.027535 0.0168268 0.141947 0.0274472 0.0168268 0.141995 0.027385 0.015305 0.142012 0.0221671 0.0142664 0.142012 0.0233657 0.0140406 0.142012 0.0249356 0.0142664 0.142012 0.0257044 0.0146995 0.142012 0.0263783 0.014626 0.141947 0.0264421 0.0168268 0.141995 0.021685 0.0160338 0.142012 0.0218343 0.0160661 0.142035 0.0219444 0.0146995 0.142012 0.0226917 0.0140406 0.142012 0.0241345 0.0143708 0.142035 0.0256567 0.015305 0.142012 0.026903 0.0160338 0.142012 0.0272358 0.189434 0.0595434 -0.084765 0.188581 0.0579815 -0.084765 0.2066 0.0581546 -0.084765 0.230273 0.0579815 -0.084765 0.187454 0.0528 -0.084765 0.196413 0.0647678 -0.084765 0.208169 0.0614128 -0.084765 0.231273 0.0545751 -0.084765 0.230895 0.056314 -0.084765 0.194745 0.0641459 -0.084765 0.2066 0.0594453 -0.084765 0.191759 0.0622265 -0.084765 0.212254 0.0581546 -0.084765 0.228353 0.0609681 -0.084765 0.2314 0.0448 -0.084765 0.2314 0.0528 -0.084765 0.209427 0.0359 -0.084765 0.199927 0.0323268 -0.084765 0.2066 0.0394453 -0.084765 0.189434 0.0380565 -0.084765 0.191759 0.0353734 -0.084765 0.208169 0.0361871 -0.084765 0.196413 0.0328321 -0.084765 0.2066 0.0381546 -0.084765 0.187581 0.0430248 -0.084765 0.204258 0.0506811 -0.084765 0.224108 0.0641459 -0.084765 0.211694 0.0606081 -0.084765 0.218927 0.0652731 -0.084765 0.220702 0.0651461 -0.084765 0.211694 0.0406081 -0.084765 0.212962 0.0445867 -0.084765 0.21364 0.0452646 -0.084765 0.222441 0.0328321 -0.084765 0.224108 0.033454 -0.084765 0.205214 0.0452646 -0.084765 0.211308 0.0436316 -0.084765 0.205214 0.0523353 -0.084765 0.205891 0.0530132 -0.084765 0.209427 0.0559 -0.084765 0.207546 0.0539683 -0.084765 0.209427 0.0433 -0.084765 0.207159 0.0406081 -0.084765 0.210685 0.0561871 -0.084765 0.211308 0.0539683 -0.084765 0.212254 0.0381546 -0.084765 0.22942 0.0380565 -0.084765 0.208472 0.0433835 -0.084765 0.206677 0.0440368 -0.084765 0.212177 0.0535631 -0.084765 0.212962 0.0530132 -0.084765 0.21364 0.0523353 -0.084765 0.21419 0.05155 -0.084765 0.230273 0.0396184 -0.084765 0.212254 0.0394453 -0.084765 0.214595 0.0469188 -0.084765 0.207669 0.0590504 -0.113265 0.192594 0.0551826 -0.113265 0.19926 0.050991 -0.113265 0.224379 0.0393478 -0.113265 0.225165 0.0402678 -0.113265 0.22626 0.0424173 -0.113265 0.219371 0.0457546 -0.113265 0.226542 0.0435938 -0.113265 0.226637 0.0528 -0.113265 0.217234 0.055671 -0.113265 0.223459 0.0590379 -0.113265 0.218283 0.0542528 -0.113265 0.219077 0.0526777 -0.113265 0.21596 0.0568915 -0.113265 0.221309 0.0601331 -0.113265 0.199927 0.0605105 -0.113265 0.193057 0.0563005 -0.113265 0.199777 0.0526777 -0.113265 0.200571 0.0542528 -0.113265 0.193689 0.0573321 -0.113265 0.219817 0.0492413 -0.113265 0.225797 0.0563005 -0.113265 0.192594 0.0424173 -0.113265 0.199036 0.0492413 -0.113265 0.192216 0.0528 -0.113265 0.193689 0.0402678 -0.113265 0.20014 0.0441178 -0.113265 0.194475 0.0393478 -0.113265 0.195395 0.038562 -0.113265 0.203603 0.0401835 -0.113265 0.205143 0.0393232 -0.113265 0.217788 0.0426158 -0.113265 0.221309 0.0374668 -0.113265 0.218927 0.0370894 -0.113265 0.215251 0.0401835 -0.113265 0.202231 0.0412916 -0.113265 0.186954 0.0488 -0.0852911 0.188222 0.0528 -0.109474 0.188366 0.054631 -0.109474 0.188447 0.0550835 -0.109474 0.187204 0.0553308 -0.0852911 0.188795 0.056417 -0.109474 0.18748 0.0564547 -0.0852911 0.187942 0.0577643 -0.0852911 0.188127 0.0581889 -0.0852911 0.190194 0.0593029 -0.109474 0.189014 0.0598134 -0.0852911 0.190457 0.05968 -0.109474 0.190123 0.0612951 -0.0852911 0.192913 0.0637131 -0.0852911 0.19165 0.0610767 -0.109474 0.198096 0.0643609 -0.109474 0.197643 0.0642801 -0.109474 0.196272 0.0652469 -0.0852911 0.19631 0.0639321 -0.109474 0.194613 0.0632292 -0.109474 0.220773 0.0656403 -0.0852911 0.220758 0.0643609 -0.109474 0.22121 0.0642801 -0.109474 0.222582 0.0652469 -0.0852911 0.227422 0.0626039 -0.0852911 0.22984 0.0598134 -0.0852911 0.228731 0.0612951 -0.0852911 0.227204 0.0610767 -0.109474 0.230488 0.054631 -0.109474 0.231374 0.0564547 -0.0852911 0.230912 0.0577643 -0.0852911 0.229356 0.0581139 -0.109474 0.228659 0.0593029 -0.109474 0.231767 0.0429538 -0.0852911 0.230059 0.0411829 -0.109474 0.230912 0.0398356 -0.0852911 0.230727 0.039411 -0.0852911 0.228659 0.038297 -0.109474 0.228731 0.0363048 -0.0852911 0.22594 0.0338869 -0.0852911 0.227422 0.0349961 -0.0852911 0.2281 0.0356271 -0.0852911 0.218927 0.0330949 -0.109474 0.220773 0.0319596 -0.0852911 0.220758 0.033239 -0.109474 0.222582 0.032353 -0.0852911 0.224241 0.0343707 -0.109474 0.225807 0.0353304 -0.109474 0.199927 0.0330949 -0.109474 0.199927 0.0318275 -0.0852911 0.198096 0.033239 -0.109474 0.198081 0.0319596 -0.0852911 0.197643 0.0333198 -0.109474 0.19631 0.0336678 -0.109474 0.196272 0.032353 -0.0852911 0.194613 0.0343707 -0.109474 0.193424 0.0350676 -0.109474 0.193047 0.0353304 -0.109474 0.19165 0.0365232 -0.109474 0.187204 0.0422692 -0.0852911 0.187942 0.0398356 -0.0852911 0.189113 0.0403206 -0.109474 0.188127 0.039411 -0.0852911 0.189498 0.039486 -0.109474 0.190194 0.038297 -0.109474 0.190457 0.0379199 -0.109474 0.188222 0.0448 -0.109474 0.186954 0.0448 -0.0852911 0.188222 0.0488 -0.109474 0.231869 0.0448 -0.0850919 0.231869 0.0528 -0.0850919 0.231899 0.0448 -0.0852911 0.231468 0.0546032 -0.0848056 0.231345 0.0564462 -0.0850919 0.23165 0.0553308 -0.0852911 0.231767 0.0546461 -0.0852911 0.231899 0.0528 -0.0852911 0.230727 0.0581889 -0.0852911 0.229814 0.059797 -0.0850919 0.228708 0.0612753 -0.0850919 0.2281 0.0619728 -0.0852911 0.22594 0.0637131 -0.0852911 0.225924 0.0636876 -0.0850919 0.224316 0.0646001 -0.0852911 0.224303 0.0645726 -0.0850919 0.223891 0.0647849 -0.0852911 0.221458 0.0655231 -0.0852911 0.220769 0.0656104 -0.0850919 0.218927 0.0657422 -0.0850919 0.231763 0.0528 -0.0849208 0.231632 0.0546267 -0.0849208 0.231737 0.0546418 -0.0850919 0.230699 0.0581763 -0.0850919 0.231243 0.0564162 -0.0849208 0.227402 0.062581 -0.0850919 0.228627 0.0612056 -0.0849208 0.224259 0.0644758 -0.0849208 0.222573 0.0652179 -0.0850919 0.222543 0.0651158 -0.0849208 0.231597 0.0528 -0.0848056 0.230603 0.0581321 -0.0849208 0.229725 0.0597395 -0.0849208 0.227332 0.0625006 -0.0849208 0.225866 0.0635981 -0.0849208 0.225777 0.063459 -0.0848056 0.22073 0.0653415 -0.0848056 0.220754 0.0655051 -0.0849208 0.231084 0.0563696 -0.0848056 0.230452 0.0580635 -0.0848056 0.229586 0.0596501 -0.0848056 0.22942 0.0595434 -0.084765 0.228503 0.0610974 -0.0848056 0.227224 0.0623757 -0.0848056 0.227095 0.0622265 -0.084765 0.22567 0.063293 -0.084765 0.22419 0.0643254 -0.0848056 0.222496 0.0649572 -0.0848056 0.222441 0.0647678 -0.084765 0.22073 0.0322584 -0.0848056 0.218927 0.0321295 -0.0848056 0.218927 0.0319642 -0.0849208 0.223891 0.032815 -0.0852911 0.222573 0.032382 -0.0850919 0.221458 0.0320768 -0.0852911 0.224316 0.0329998 -0.0852911 0.225924 0.0339123 -0.0850919 0.22984 0.0377865 -0.0852911 0.230699 0.0394236 -0.0850919 0.231374 0.0411452 -0.0852911 0.23165 0.0422692 -0.0852911 0.231737 0.0429581 -0.0850919 0.220769 0.0319895 -0.0850919 0.224259 0.0331241 -0.0849208 0.224303 0.0330273 -0.0850919 0.225866 0.0340018 -0.0849208 0.227402 0.0350189 -0.0850919 0.228627 0.0363943 -0.0849208 0.228708 0.0363246 -0.0850919 0.229814 0.0378029 -0.0850919 0.230603 0.0394678 -0.0849208 0.231345 0.0411537 -0.0850919 0.220754 0.0320948 -0.0849208 0.222543 0.0324841 -0.0849208 0.22419 0.0332745 -0.0848056 0.227332 0.0350993 -0.0849208 0.227224 0.0352242 -0.0848056 0.228503 0.0365026 -0.0848056 0.229725 0.0378604 -0.0849208 0.230452 0.0395365 -0.0848056 0.231084 0.0412303 -0.0848056 0.231243 0.0411837 -0.0849208 0.231632 0.0429732 -0.0849208 0.231468 0.0429968 -0.0848056 0.231763 0.0448 -0.0849208 0.220702 0.0324538 -0.084765 0.222496 0.0326427 -0.0848056 0.225777 0.0341409 -0.0848056 0.22567 0.0343069 -0.084765 0.227095 0.0353734 -0.084765 0.228353 0.0366318 -0.084765 0.229586 0.0379498 -0.0848056 0.230895 0.0412859 -0.084765 0.231597 0.0448 -0.0848056 0.231273 0.0430248 -0.084765 0.199927 0.0654704 -0.0848056 0.218927 0.0654704 -0.0848056 0.218927 0.0656358 -0.0849208 0.199927 0.0656358 -0.0849208 0.218927 0.0657724 -0.0852911 0.199927 0.0657724 -0.0852911 0.218927 0.0323268 -0.084765 0.199927 0.0319642 -0.0849208 0.199927 0.0318578 -0.0850919 0.218927 0.0318578 -0.0850919 0.218927 0.0318275 -0.0852911 0.199927 0.0652731 -0.084765 0.198124 0.0653415 -0.0848056 0.194962 0.0647849 -0.0852911 0.196281 0.0652179 -0.0850919 0.197396 0.0655231 -0.0852911 0.198081 0.0656403 -0.0852911 0.199927 0.0657422 -0.0850919 0.19455 0.0645726 -0.0850919 0.194538 0.0646001 -0.0852911 0.19293 0.0636876 -0.0850919 0.191432 0.0626039 -0.0852911 0.191451 0.062581 -0.0850919 0.190146 0.0612753 -0.0850919 0.190754 0.0619728 -0.0852911 0.188154 0.0581763 -0.0850919 0.187509 0.0564462 -0.0850919 0.187116 0.0546418 -0.0850919 0.187086 0.0546461 -0.0852911 0.186954 0.0528 -0.0852911 0.186985 0.0528 -0.0850919 0.198085 0.0656104 -0.0850919 0.1981 0.0655051 -0.0849208 0.191521 0.0625006 -0.0849208 0.190226 0.0612056 -0.0849208 0.189039 0.059797 -0.0850919 0.187222 0.0546267 -0.0849208 0.196357 0.0649572 -0.0848056 0.196311 0.0651158 -0.0849208 0.194595 0.0644758 -0.0849208 0.194663 0.0643254 -0.0848056 0.192987 0.0635981 -0.0849208 0.193077 0.063459 -0.0848056 0.191629 0.0623757 -0.0848056 0.189129 0.0597395 -0.0849208 0.190351 0.0610974 -0.0848056 0.188251 0.0581321 -0.0849208 0.18777 0.0563696 -0.0848056 0.187611 0.0564162 -0.0849208 0.187385 0.0546032 -0.0848056 0.198152 0.0651461 -0.084765 0.193183 0.063293 -0.084765 0.1905 0.0609681 -0.084765 0.189268 0.0596501 -0.0848056 0.188401 0.0580635 -0.0848056 0.187959 0.056314 -0.084765 0.187581 0.0545751 -0.084765 0.187256 0.0448 -0.0848056 0.187222 0.0429732 -0.0849208 0.18748 0.0411452 -0.0852911 0.187509 0.0411537 -0.0850919 0.187086 0.0429538 -0.0852911 0.187116 0.0429581 -0.0850919 0.189014 0.0377865 -0.0852911 0.190146 0.0363246 -0.0850919 0.190123 0.0363048 -0.0852911 0.191451 0.0350189 -0.0850919 0.190754 0.0356271 -0.0852911 0.191432 0.0349961 -0.0852911 0.19293 0.0339123 -0.0850919 0.192913 0.0338869 -0.0852911 0.194538 0.0329998 -0.0852911 0.194962 0.032815 -0.0852911 0.197396 0.0320768 -0.0852911 0.198085 0.0319895 -0.0850919 0.187611 0.0411837 -0.0849208 0.188251 0.0394678 -0.0849208 0.188154 0.0394236 -0.0850919 0.189039 0.0378029 -0.0850919 0.189129 0.0378604 -0.0849208 0.19455 0.0330273 -0.0850919 0.194595 0.0331241 -0.0849208 0.196281 0.032382 -0.0850919 0.196311 0.0324841 -0.0849208 0.187385 0.0429968 -0.0848056 0.18777 0.0412303 -0.0848056 0.188401 0.0395365 -0.0848056 0.189268 0.0379498 -0.0848056 0.190226 0.0363943 -0.0849208 0.191521 0.0350993 -0.0849208 0.192987 0.0340018 -0.0849208 0.194663 0.0332745 -0.0848056 0.196357 0.0326427 -0.0848056 0.1981 0.0320948 -0.0849208 0.198124 0.0322584 -0.0848056 0.199927 0.0321295 -0.0848056 0.187959 0.0412859 -0.084765 0.188581 0.0396184 -0.084765 0.190351 0.0365026 -0.0848056 0.191629 0.0352242 -0.0848056 0.1905 0.0366318 -0.084765 0.193183 0.0343069 -0.084765 0.193077 0.0341409 -0.0848056 0.194745 0.033454 -0.084765 0.198152 0.0324538 -0.084765 0.187454 0.0488 -0.084765 0.187256 0.0528 -0.0848056 0.187091 0.0528 -0.0849208 0.186985 0.0488 -0.0850919 0.187454 0.0448 -0.084765 0.187256 0.0488 -0.0848056 0.187091 0.0448 -0.0849208 0.187091 0.0488 -0.0849208 0.186985 0.0448 -0.0850919 0.218927 0.0619927 -0.11298 0.218927 0.0632639 -0.112166 0.218927 0.0639027 -0.111385 0.199927 0.0639027 -0.111385 0.218927 0.0643253 -0.110468 0.199927 0.0643253 -0.110468 0.189658 0.0580324 -0.110468 0.199927 0.061512 -0.113138 0.198721 0.0604155 -0.113265 0.199927 0.0619927 -0.11298 0.191641 0.0554921 -0.113138 0.190749 0.0557819 -0.112763 0.189975 0.0560335 -0.112166 0.190603 0.0575505 -0.112166 0.190034 0.0578405 -0.111385 0.192311 0.0540061 -0.113265 0.191322 0.0541628 -0.113138 0.198124 0.0641835 -0.110468 0.199927 0.0641431 -0.11094 0.199927 0.0632639 -0.112166 0.199927 0.0624497 -0.112763 0.195176 0.0621234 -0.112166 0.194886 0.0626925 -0.111385 0.191215 0.0528 -0.113138 0.190396 0.0543095 -0.112763 0.189592 0.0544369 -0.112166 0.190277 0.0528 -0.112763 0.189463 0.0528 -0.112166 0.188824 0.0528 -0.111385 0.189367 0.0562309 -0.111385 0.188965 0.0563615 -0.110468 0.188961 0.0545368 -0.111385 0.188584 0.0528 -0.11094 0.199927 0.064505 -0.109474 0.196496 0.0633593 -0.111385 0.196693 0.0627518 -0.112166 0.19819 0.063766 -0.111385 0.19829 0.0631351 -0.112166 0.196945 0.0619774 -0.112763 0.198417 0.0623309 -0.112763 0.197235 0.0610856 -0.113138 0.197544 0.0601331 -0.113265 0.198564 0.0614047 -0.113138 0.196365 0.0637613 -0.110468 0.195447 0.063614 -0.109474 0.193047 0.0622695 -0.109474 0.193424 0.0625323 -0.109474 0.193152 0.0621242 -0.110468 0.194694 0.0630692 -0.110468 0.194255 0.0606068 -0.112763 0.195546 0.061398 -0.112763 0.194806 0.0598481 -0.113138 0.195395 0.0590379 -0.113265 0.195972 0.0605624 -0.113138 0.196426 0.0596701 -0.113265 0.193766 0.0589603 -0.113138 0.193103 0.0596234 -0.112763 0.193776 0.0612655 -0.112166 0.193401 0.0617822 -0.111385 0.192076 0.0606508 -0.111385 0.194475 0.0582521 -0.113265 0.192879 0.0579208 -0.113138 0.192528 0.0601991 -0.112166 0.190945 0.059326 -0.111385 0.191777 0.0609496 -0.110468 0.190603 0.0595744 -0.110468 0.189498 0.0581139 -0.109474 0.191461 0.0589505 -0.112166 0.191329 0.0571809 -0.112763 0.19212 0.0584719 -0.112763 0.192164 0.0567551 -0.113138 0.189113 0.0572793 -0.109474 0.188543 0.0546029 -0.110468 0.225807 0.0622695 -0.109474 0.226542 0.0540061 -0.113265 0.227532 0.0541628 -0.113138 0.227639 0.0528 -0.113138 0.228458 0.0543095 -0.112763 0.218927 0.0605105 -0.113265 0.218927 0.061512 -0.113138 0.218927 0.0624497 -0.112763 0.220564 0.0631351 -0.112166 0.229893 0.0545368 -0.111385 0.23027 0.0528 -0.11094 0.23003 0.0528 -0.111385 0.228577 0.0528 -0.112763 0.230632 0.0528 -0.109474 0.23031 0.0546029 -0.110468 0.230059 0.056417 -0.109474 0.230407 0.0550835 -0.109474 0.229262 0.0544369 -0.112166 0.228104 0.0557819 -0.112763 0.22626 0.0551826 -0.113265 0.229196 0.0580324 -0.110468 0.229741 0.0572793 -0.109474 0.229888 0.0563615 -0.110468 0.228819 0.0578405 -0.111385 0.229486 0.0562309 -0.111385 0.22825 0.0575505 -0.112166 0.228879 0.0560335 -0.112166 0.227525 0.0571809 -0.112763 0.227212 0.0554921 -0.113138 0.228396 0.05968 -0.109474 0.228251 0.0595744 -0.110468 0.227909 0.059326 -0.111385 0.226734 0.0584719 -0.112763 0.226689 0.0567551 -0.113138 0.225975 0.0579208 -0.113138 0.225165 0.0573321 -0.113265 0.224379 0.0582521 -0.113265 0.227392 0.0589505 -0.112166 0.225087 0.0589603 -0.113138 0.224048 0.0598481 -0.113138 0.224599 0.0606068 -0.112763 0.22575 0.0596234 -0.112763 0.226326 0.0601991 -0.112166 0.225077 0.0612655 -0.112166 0.226778 0.0606508 -0.111385 0.227076 0.0609496 -0.110468 0.225453 0.0617822 -0.111385 0.225701 0.0621242 -0.110468 0.224241 0.0632292 -0.109474 0.22543 0.0625323 -0.109474 0.223677 0.0621234 -0.112166 0.222544 0.0639321 -0.109474 0.223406 0.063614 -0.109474 0.222488 0.0637613 -0.110468 0.224159 0.0630692 -0.110468 0.223967 0.0626925 -0.111385 0.22216 0.0627518 -0.112166 0.223308 0.061398 -0.112763 0.222882 0.0605624 -0.113138 0.222427 0.0596701 -0.113265 0.220664 0.063766 -0.111385 0.222358 0.0633593 -0.111385 0.220436 0.0623309 -0.112763 0.22029 0.0614047 -0.113138 0.221909 0.0619774 -0.112763 0.220133 0.0604155 -0.113265 0.221619 0.0610856 -0.113138 0.218927 0.0641431 -0.11094 0.22073 0.0641835 -0.110468 0.218927 0.064505 -0.109474 0.192216 0.0488 -0.113265 0.190734 0.0488 -0.11298 0.190734 0.0528 -0.11298 0.188401 0.0528 -0.110468 0.230632 0.0448 -0.109474 0.230452 0.0528 -0.110468 0.23027 0.0448 -0.11094 0.23003 0.0448 -0.111385 0.229391 0.0528 -0.112166 0.22812 0.0528 -0.11298 0.22812 0.0448 -0.11298 0.191215 0.0448 -0.113138 0.190734 0.0448 -0.11298 0.189463 0.0488 -0.112166 0.188584 0.0488 -0.11094 0.229356 0.039486 -0.109474 0.228251 0.0380255 -0.110468 0.222488 0.0338387 -0.110468 0.226637 0.0448 -0.113265 0.220133 0.0371844 -0.113265 0.227532 0.0434371 -0.113138 0.227639 0.0448 -0.113138 0.228577 0.0448 -0.112763 0.22073 0.0334165 -0.110468 0.220564 0.0344648 -0.112166 0.218927 0.0351502 -0.112763 0.218927 0.0356072 -0.11298 0.222544 0.0336678 -0.109474 0.22121 0.0333198 -0.109474 0.222358 0.0342407 -0.111385 0.22216 0.0348482 -0.112166 0.220664 0.0338339 -0.111385 0.221909 0.0356225 -0.112763 0.220436 0.035269 -0.112763 0.22029 0.0361952 -0.113138 0.223406 0.0339859 -0.109474 0.223677 0.0354765 -0.112166 0.222882 0.0370375 -0.113138 0.221619 0.0365143 -0.113138 0.22543 0.0350676 -0.109474 0.225701 0.0354757 -0.110468 0.224159 0.0345308 -0.110468 0.223967 0.0349074 -0.111385 0.225077 0.0363345 -0.112166 0.223308 0.036202 -0.112763 0.224599 0.0369931 -0.112763 0.223459 0.038562 -0.113265 0.222427 0.0379298 -0.113265 0.225087 0.0386396 -0.113138 0.224048 0.0377518 -0.113138 0.225453 0.0358177 -0.111385 0.227076 0.0366503 -0.110468 0.227204 0.0365232 -0.109474 0.22575 0.0379765 -0.112763 0.226326 0.0374008 -0.112166 0.227392 0.0386494 -0.112166 0.226778 0.0369492 -0.111385 0.227909 0.0382739 -0.111385 0.228396 0.0379199 -0.109474 0.229196 0.0395675 -0.110468 0.22825 0.0400494 -0.112166 0.226734 0.039128 -0.112763 0.227525 0.0404191 -0.112763 0.225975 0.0396792 -0.113138 0.229888 0.0412384 -0.110468 0.229741 0.0403206 -0.109474 0.229486 0.041369 -0.111385 0.228819 0.0397594 -0.111385 0.228104 0.041818 -0.112763 0.227212 0.0421078 -0.113138 0.226689 0.0408448 -0.113138 0.225797 0.0412995 -0.113265 0.230407 0.0425164 -0.109474 0.229893 0.0430631 -0.111385 0.228879 0.0415664 -0.112166 0.229262 0.043163 -0.112166 0.228458 0.0432904 -0.112763 0.229391 0.0448 -0.112166 0.23031 0.042997 -0.110468 0.230452 0.0448 -0.110468 0.230488 0.0429689 -0.109474 0.196365 0.0338387 -0.110468 0.188366 0.0429689 -0.109474 0.192216 0.0448 -0.113265 0.192311 0.0435938 -0.113265 0.191322 0.0434371 -0.113138 0.199927 0.0370894 -0.113265 0.199927 0.0356072 -0.11298 0.19829 0.0344648 -0.112166 0.188584 0.0448 -0.11094 0.188824 0.0448 -0.111385 0.189463 0.0448 -0.112166 0.190277 0.0448 -0.112763 0.193057 0.0412995 -0.113265 0.191641 0.0421078 -0.113138 0.191329 0.0404191 -0.112763 0.190603 0.0400494 -0.112166 0.189367 0.041369 -0.111385 0.188543 0.042997 -0.110468 0.188401 0.0448 -0.110468 0.188965 0.0412384 -0.110468 0.188447 0.0425164 -0.109474 0.188961 0.0430631 -0.111385 0.189975 0.0415664 -0.112166 0.189592 0.043163 -0.112166 0.190749 0.041818 -0.112763 0.190396 0.0432904 -0.112763 0.189658 0.0395675 -0.110468 0.188795 0.0411829 -0.109474 0.190945 0.0382739 -0.111385 0.190034 0.0397594 -0.111385 0.192879 0.0396792 -0.113138 0.192164 0.0408448 -0.113138 0.193766 0.0386396 -0.113138 0.19212 0.039128 -0.112763 0.191461 0.0386494 -0.112166 0.192528 0.0374008 -0.112166 0.192076 0.0369492 -0.111385 0.190603 0.0380255 -0.110468 0.193103 0.0379765 -0.112763 0.193776 0.0363345 -0.112166 0.191777 0.0366503 -0.110468 0.193152 0.0354757 -0.110468 0.193401 0.0358177 -0.111385 0.194886 0.0349074 -0.111385 0.195546 0.036202 -0.112763 0.194255 0.0369931 -0.112763 0.194806 0.0377518 -0.113138 0.195447 0.0339859 -0.109474 0.194694 0.0345308 -0.110468 0.195176 0.0354765 -0.112166 0.196945 0.0356225 -0.112763 0.195972 0.0370375 -0.113138 0.197235 0.0365143 -0.113138 0.196426 0.0379298 -0.113265 0.198124 0.0334165 -0.110468 0.19819 0.0338339 -0.111385 0.196496 0.0342407 -0.111385 0.196693 0.0348482 -0.112166 0.198417 0.035269 -0.112763 0.198564 0.0361952 -0.113138 0.198721 0.0371844 -0.113265 0.197544 0.0374668 -0.113265 0.199927 0.034336 -0.112166 0.199927 0.0332746 -0.110468 0.218927 0.0360879 -0.113138 0.199927 0.0360879 -0.113138 0.199927 0.0351502 -0.112763 0.218927 0.034336 -0.112166 0.199927 0.0336972 -0.111385 0.199927 0.0334569 -0.11094 0.218927 0.0336972 -0.111385 0.218927 0.0334569 -0.11094 0.218927 0.0332746 -0.110468 0.215239 0.0427355 -0.111265 0.214131 0.0418405 -0.111265 0.213627 0.0415253 -0.090065 0.215366 0.0428603 -0.111265 0.216701 0.0446 -0.111265 0.216701 0.0446 -0.090065 0.216927 0.0450182 -0.111265 0.217759 0.047733 -0.111265 0.217541 0.0466259 -0.090065 0.217541 0.0466259 -0.111265 0.217638 0.0505697 -0.111265 0.217827 0.0488 -0.111265 0.217827 0.0488 -0.090065 0.217541 0.050974 -0.111265 0.216701 0.053 -0.111265 0.216701 0.053 -0.090065 0.215732 0.0543496 -0.111265 0.213523 0.0561333 -0.111265 0.214704 0.0553355 -0.111265 0.210846 0.0570791 -0.111265 0.209427 0.0572 -0.111265 0.208007 0.0570791 -0.111265 0.207253 0.0569137 -0.090065 0.206628 0.0567201 -0.111265 0.205227 0.0560746 -0.090065 0.203487 0.0547397 -0.090065 0.20415 0.0553355 -0.111265 0.201313 0.050974 -0.090065 0.201034 0.0491565 -0.111265 0.201313 0.0466259 -0.090065 0.201027 0.0488 -0.090065 0.202152 0.0446 -0.090065 0.201926 0.0450182 -0.111265 0.201395 0.0463402 -0.111265 0.201313 0.0466259 -0.111265 0.202673 0.043805 -0.111265 0.203487 0.0428603 -0.090065 0.207253 0.0406862 -0.090065 0.205967 0.0411456 -0.111265 0.205227 0.0415253 -0.090065 0.209427 0.0404 -0.090065 0.208714 0.0404302 -0.111265 0.20731 0.040671 -0.111265 0.20401 0.049755 -0.090065 0.203927 0.0488 -0.090065 0.214595 0.0506811 -0.090065 0.215366 0.0547397 -0.090065 0.206677 0.0535631 -0.090065 0.205891 0.0530132 -0.090065 0.205214 0.0523353 -0.090065 0.204664 0.05155 -0.090065 0.202152 0.053 -0.090065 0.204258 0.0506811 -0.090065 0.209427 0.0572 -0.090065 0.20401 0.0478449 -0.090065 0.204664 0.04605 -0.090065 0.217541 0.050974 -0.090065 0.213627 0.0560746 -0.090065 0.211601 0.0569137 -0.090065 0.211308 0.0539683 -0.090065 0.211601 0.0406862 -0.090065 0.212962 0.0445867 -0.090065 0.215366 0.0428603 -0.090065 0.21364 0.0452646 -0.090065 0.214843 0.0478449 -0.090065 0.205214 0.0452646 -0.090065 0.205891 0.0445867 -0.090065 0.206677 0.0440368 -0.090065 0.207546 0.0436316 -0.090065 0.209427 0.0433 -0.090065 0.211308 0.0436316 -0.090065 0.207253 0.0569137 -0.111265 0.206578 0.0568637 -0.11203 0.20533 0.0561333 -0.111265 0.205227 0.0560746 -0.111265 0.204054 0.0554539 -0.11203 0.203487 0.0547397 -0.111265 0.203121 0.0543496 -0.111265 0.202274 0.0532041 -0.111265 0.202144 0.053284 -0.11203 0.202152 0.053 -0.111265 0.201633 0.051932 -0.111265 0.201313 0.050974 -0.111265 0.201067 0.0506017 -0.11203 0.201215 0.0505697 -0.111265 0.201027 0.0488 -0.111265 0.201095 0.047733 -0.111265 0.201249 0.0462957 -0.11203 0.202152 0.0446 -0.111265 0.202551 0.0437145 -0.11203 0.203487 0.0428603 -0.111265 0.203615 0.0427355 -0.111265 0.204723 0.0418405 -0.111265 0.205227 0.0415253 -0.111265 0.205904 0.0410069 -0.11203 0.209427 0.0404 -0.111265 0.211582 0.0405237 -0.11203 0.211543 0.040671 -0.111265 0.210139 0.0404302 -0.111265 0.212887 0.0411456 -0.111265 0.212949 0.0410069 -0.11203 0.213627 0.0415253 -0.111265 0.214216 0.0417143 -0.11203 0.216303 0.0437145 -0.11203 0.21618 0.043805 -0.111265 0.217459 0.0463402 -0.111265 0.21791 0.0477137 -0.11203 0.217971 0.0491629 -0.11203 0.217819 0.0491565 -0.111265 0.217221 0.051932 -0.111265 0.21658 0.0532041 -0.111265 0.215366 0.0547397 -0.111265 0.214799 0.0554539 -0.11203 0.213627 0.0560746 -0.111265 0.213598 0.0562662 -0.11203 0.212225 0.0567201 -0.111265 0.211601 0.0569137 -0.111265 0.212276 0.0568637 -0.11203 0.210872 0.0572292 -0.11203 0.215847 0.0544502 -0.11203 0.216172 0.0547366 -0.112679 0.217078 0.0535113 -0.112679 0.216709 0.053284 -0.11203 0.217362 0.0519887 -0.11203 0.217765 0.0521504 -0.112679 0.217787 0.0506017 -0.11203 0.218404 0.0491813 -0.112679 0.21834 0.0476586 -0.112679 0.217604 0.0462957 -0.11203 0.217063 0.0449497 -0.11203 0.216651 0.0434567 -0.112679 0.215644 0.0423126 -0.112679 0.214459 0.0413551 -0.112679 0.215344 0.0426256 -0.11203 0.211691 0.0401041 -0.112679 0.210152 0.0402785 -0.11203 0.210189 0.0398465 -0.112679 0.208702 0.0402785 -0.11203 0.207272 0.0405237 -0.11203 0.205726 0.0406119 -0.112679 0.204395 0.0413551 -0.112679 0.203209 0.0423126 -0.112679 0.204638 0.0417143 -0.11203 0.203509 0.0426256 -0.11203 0.20179 0.0449497 -0.11203 0.200514 0.0476586 -0.112679 0.200944 0.0477137 -0.11203 0.200882 0.0491629 -0.11203 0.201089 0.0521504 -0.112679 0.201491 0.0519887 -0.11203 0.201775 0.0535113 -0.112679 0.203007 0.0544502 -0.11203 0.203782 0.0557912 -0.112679 0.205256 0.0562662 -0.11203 0.207981 0.0572292 -0.11203 0.207908 0.0576565 -0.112679 0.209427 0.0577857 -0.112679 0.209427 0.0573522 -0.11203 0.211055 0.058296 -0.113113 0.210945 0.0576565 -0.112679 0.212636 0.0578842 -0.113113 0.21242 0.0572725 -0.112679 0.214126 0.0572111 -0.113113 0.213809 0.0566447 -0.112679 0.215072 0.0557912 -0.112679 0.216659 0.0551653 -0.113113 0.217631 0.0538515 -0.113113 0.218367 0.0523923 -0.113113 0.218845 0.0508298 -0.113113 0.218211 0.0506931 -0.112679 0.219053 0.0492089 -0.113113 0.218983 0.0475762 -0.113113 0.218639 0.0459787 -0.113113 0.21803 0.0444624 -0.113113 0.218019 0.0461687 -0.112679 0.21745 0.0447545 -0.112679 0.214822 0.0408176 -0.113113 0.213128 0.0406119 -0.112679 0.211855 0.0394762 -0.113113 0.210244 0.0392 -0.113113 0.20861 0.0392 -0.113113 0.208665 0.0398465 -0.112679 0.207163 0.0401041 -0.112679 0.201681 0.0430709 -0.113113 0.202202 0.0434567 -0.112679 0.201403 0.0447545 -0.112679 0.200835 0.0461687 -0.112679 0.19987 0.0475762 -0.113113 0.199801 0.0492089 -0.113113 0.200449 0.0491813 -0.112679 0.200008 0.0508298 -0.113113 0.200487 0.0523923 -0.113113 0.200643 0.0506931 -0.112679 0.202681 0.0547366 -0.112679 0.203374 0.056296 -0.113113 0.205044 0.0566447 -0.112679 0.206433 0.0572725 -0.112679 0.206217 0.0578842 -0.113113 0.207799 0.058296 -0.113113 0.209427 0.0584346 -0.113113 0.211184 0.0590504 -0.113265 0.212891 0.0586059 -0.113265 0.214499 0.0578793 -0.113265 0.215479 0.056296 -0.113113 0.219593 0.050991 -0.113265 0.219743 0.047479 -0.113265 0.218713 0.0441178 -0.113265 0.217173 0.0430709 -0.113113 0.216093 0.0418442 -0.113113 0.216623 0.0412916 -0.113265 0.213711 0.0393232 -0.113265 0.213395 0.0400206 -0.113113 0.212047 0.0387355 -0.113265 0.210309 0.0384374 -0.113265 0.208545 0.0384374 -0.113265 0.206806 0.0387355 -0.113265 0.206999 0.0394762 -0.113113 0.205458 0.0400206 -0.113113 0.204032 0.0408176 -0.113113 0.20276 0.0418442 -0.113113 0.201065 0.0426158 -0.113265 0.200824 0.0444624 -0.113113 0.199483 0.0457546 -0.113265 0.200214 0.0459787 -0.113113 0.199111 0.047479 -0.113265 0.201223 0.0538515 -0.113113 0.20162 0.055671 -0.113265 0.202194 0.0551653 -0.113113 0.202893 0.0568915 -0.113265 0.204355 0.0578793 -0.113265 0.205962 0.0586059 -0.113265 0.204728 0.0572111 -0.113113 0.209427 0.0592 -0.113265 0.207717 0.0441015 -0.085265 0.207717 0.0441015 -0.089565 0.206927 0.0444698 -0.085265 0.206927 0.0444698 -0.089565 0.206213 0.0449697 -0.085265 0.206213 0.0449697 -0.089565 0.205597 0.045586 -0.089565 0.204728 0.0470899 -0.085265 0.205097 0.0463 -0.089565 0.204503 0.0479317 -0.085265 0.204503 0.0496682 -0.089565 0.204728 0.0505101 -0.085265 0.206213 0.0526302 -0.085265 0.208559 0.053724 -0.085265 0.209427 0.0538 -0.085265 0.209427 0.0538 -0.089565 0.210295 0.053724 -0.085265 0.210295 0.053724 -0.089565 0.211137 0.0534984 -0.085265 0.211927 0.0531301 -0.089565 0.211927 0.0531301 -0.085265 0.212641 0.0526302 -0.085265 0.214125 0.0505101 -0.089565 0.214427 0.0488 -0.085265 0.214427 0.0488 -0.089565 0.213257 0.045586 -0.089565 0.212641 0.0449697 -0.089565 0.208559 0.0438759 -0.085265 0.208781 0.0616273 -0.082265 0.207159 0.0606081 -0.084765 0.207159 0.0606081 -0.082265 0.206814 0.0575417 -0.082265 0.2066 0.0581546 -0.082265 0.207619 0.0565326 -0.082265 0.207159 0.0569918 -0.084765 0.207159 0.0569918 -0.082265 0.208169 0.0561871 -0.084765 0.209427 0.0559 -0.082265 0.211235 0.0565326 -0.082265 0.211694 0.0569918 -0.084765 0.211694 0.0569918 -0.082265 0.21204 0.0575417 -0.082265 0.212254 0.0594453 -0.084765 0.212254 0.0594453 -0.082265 0.212327 0.0588 -0.082265 0.210685 0.0614128 -0.084765 0.209427 0.0617 -0.082265 0.209427 0.0617 -0.084765 0.209427 0.0588 -0.081265 0.208602 0.0570881 -0.081265 0.209004 0.0569476 -0.081265 0.207715 0.0579756 -0.081265 0.208242 0.0573145 -0.081265 0.207574 0.0583772 -0.081265 0.208242 0.0602854 -0.081265 0.209004 0.0606523 -0.081265 0.211327 0.0588 -0.081265 0.211279 0.0592227 -0.081265 0.210912 0.0576153 -0.081265 0.211139 0.0579756 -0.081265 0.211279 0.0583772 -0.081265 0.210611 0.0573145 -0.081265 0.209427 0.0417 -0.084765 0.208169 0.0414128 -0.084765 0.207619 0.0410673 -0.082265 0.208169 0.0414128 -0.082265 0.207159 0.0406081 -0.082265 0.2066 0.0394453 -0.082265 0.207159 0.0369918 -0.084765 0.207619 0.0365326 -0.082265 0.208781 0.0359727 -0.082265 0.208169 0.0361871 -0.082265 0.209427 0.0359 -0.082265 0.210685 0.0361871 -0.084765 0.210072 0.0359727 -0.082265 0.21204 0.0375417 -0.082265 0.211694 0.0369918 -0.084765 0.211235 0.0365326 -0.082265 0.212254 0.0381546 -0.082265 0.21204 0.0400582 -0.082265 0.212327 0.0388 -0.082265 0.210685 0.0414128 -0.084765 0.211235 0.0410673 -0.082265 0.208781 0.0416273 -0.082265 0.210072 0.0416273 -0.082265 0.210685 0.0414128 -0.082265 0.209427 0.0369 -0.081265 0.207715 0.0379756 -0.081265 0.207527 0.0388 -0.081265 0.207941 0.0399846 -0.081265 0.209004 0.0406523 -0.081265 0.208602 0.0405118 -0.081265 0.210912 0.0399846 -0.081265 0.211139 0.0396243 -0.081265 0.211279 0.0383772 -0.081265 0.210251 0.0370881 -0.081265 0.209427 0.0388 -0.081265 0.210912 0.0376153 -0.081265 0.20985 0.0369476 -0.081265 0.210611 0.0373145 -0.081265 0.211303 0.0373036 -0.0813989 0.211139 0.0379756 -0.081265 0.211589 0.0377586 -0.0813989 0.211767 0.0382659 -0.0813989 0.211327 0.0388 -0.081265 0.211279 0.0392227 -0.081265 0.210923 0.0406764 -0.0813989 0.210611 0.0402854 -0.081265 0.210251 0.0405118 -0.081265 0.20985 0.0406523 -0.081265 0.209427 0.0412 -0.0813989 0.209427 0.0407 -0.081265 0.208385 0.0409623 -0.0813989 0.208242 0.0402854 -0.081265 0.207264 0.0398413 -0.0813989 0.207715 0.0396243 -0.081265 0.207574 0.0392227 -0.081265 0.207574 0.0383772 -0.081265 0.207087 0.0382659 -0.0813989 0.207264 0.0377586 -0.0813989 0.207941 0.0376153 -0.081265 0.20793 0.0369236 -0.0813989 0.208242 0.0373145 -0.081265 0.208602 0.0370881 -0.081265 0.208385 0.0366376 -0.0813989 0.208893 0.0364601 -0.0813989 0.209004 0.0369476 -0.081265 0.209427 0.0364 -0.0813989 0.209961 0.0364601 -0.0813989 0.210468 0.0366376 -0.0813989 0.211151 0.0366374 -0.081765 0.210923 0.0369236 -0.0813989 0.211919 0.0375998 -0.081765 0.212123 0.0381845 -0.081765 0.212193 0.0388 -0.081765 0.211827 0.0388 -0.0813989 0.211767 0.039334 -0.0813989 0.211919 0.0400001 -0.081765 0.211589 0.0405245 -0.081765 0.211589 0.0398413 -0.0813989 0.211303 0.0402963 -0.0813989 0.210627 0.0412921 -0.081765 0.210468 0.0409623 -0.0813989 0.209961 0.0411398 -0.0813989 0.209427 0.041566 -0.081765 0.208893 0.0411398 -0.0813989 0.20793 0.0406764 -0.0813989 0.207702 0.0409625 -0.081765 0.20755 0.0402963 -0.0813989 0.20673 0.0394155 -0.081765 0.207087 0.039334 -0.0813989 0.206661 0.0388 -0.081765 0.207027 0.0388 -0.0813989 0.20673 0.0381845 -0.081765 0.207264 0.0370754 -0.081765 0.20755 0.0373036 -0.0813989 0.207702 0.0366374 -0.081765 0.208811 0.0361033 -0.081765 0.210042 0.0361033 -0.081765 0.209427 0.0360339 -0.081765 0.210685 0.0361871 -0.082265 0.210627 0.0363079 -0.081765 0.211694 0.0369918 -0.082265 0.211589 0.0370754 -0.081765 0.212254 0.0394453 -0.082265 0.212123 0.0394155 -0.081765 0.211694 0.0406081 -0.082265 0.211151 0.0409625 -0.081765 0.210042 0.0414966 -0.081765 0.209427 0.0417 -0.082265 0.208811 0.0414966 -0.081765 0.208227 0.0412921 -0.081765 0.207264 0.0405245 -0.081765 0.206935 0.0400001 -0.081765 0.206814 0.0400582 -0.082265 0.206527 0.0388 -0.082265 0.2066 0.0381546 -0.082265 0.206814 0.0375417 -0.082265 0.206935 0.0375998 -0.081765 0.207159 0.0369918 -0.082265 0.208227 0.0363079 -0.081765 0.209427 0.0569 -0.081265 0.210468 0.0566376 -0.0813989 0.20985 0.0569476 -0.081265 0.210251 0.0570881 -0.081265 0.211589 0.0577586 -0.0813989 0.211827 0.0588 -0.0813989 0.211767 0.059334 -0.0813989 0.211139 0.0596243 -0.081265 0.210912 0.0599846 -0.081265 0.211303 0.0602963 -0.0813989 0.210923 0.0606764 -0.0813989 0.210611 0.0602854 -0.081265 0.210251 0.0605118 -0.081265 0.209961 0.0611398 -0.0813989 0.209427 0.0612 -0.0813989 0.20985 0.0606523 -0.081265 0.209427 0.0607 -0.081265 0.208893 0.0611398 -0.0813989 0.208385 0.0609623 -0.0813989 0.208602 0.0605118 -0.081265 0.207941 0.0599846 -0.081265 0.20755 0.0602963 -0.0813989 0.207264 0.0598413 -0.0813989 0.207715 0.0596243 -0.081265 0.207027 0.0588 -0.0813989 0.207574 0.0592227 -0.081265 0.207527 0.0588 -0.081265 0.207087 0.0582659 -0.0813989 0.207264 0.0577586 -0.0813989 0.20755 0.0573036 -0.0813989 0.207941 0.0576153 -0.081265 0.209427 0.0564 -0.0813989 0.209961 0.0564601 -0.0813989 0.211151 0.0566374 -0.081765 0.210923 0.0569236 -0.0813989 0.211589 0.0570754 -0.081765 0.211303 0.0573036 -0.0813989 0.211919 0.0575998 -0.081765 0.211767 0.0582659 -0.0813989 0.212193 0.0588 -0.081765 0.211919 0.0600001 -0.081765 0.211589 0.0598413 -0.0813989 0.211589 0.0605245 -0.081765 0.211151 0.0609625 -0.081765 0.210468 0.0609623 -0.0813989 0.210042 0.0614966 -0.081765 0.209427 0.061566 -0.081765 0.207702 0.0609625 -0.081765 0.20793 0.0606764 -0.0813989 0.207264 0.0605245 -0.081765 0.20673 0.0594155 -0.081765 0.207087 0.059334 -0.0813989 0.206661 0.0588 -0.081765 0.20673 0.0581845 -0.081765 0.207264 0.0570754 -0.081765 0.207702 0.0566374 -0.081765 0.20793 0.0569236 -0.0813989 0.208385 0.0566376 -0.0813989 0.208227 0.0563079 -0.081765 0.208893 0.0564601 -0.0813989 0.210042 0.0561033 -0.081765 0.210072 0.0559727 -0.082265 0.210627 0.0563079 -0.081765 0.210685 0.0561871 -0.082265 0.212254 0.0581546 -0.082265 0.212123 0.0581845 -0.081765 0.212123 0.0594155 -0.081765 0.21204 0.0600582 -0.082265 0.211694 0.0606081 -0.082265 0.211235 0.0610673 -0.082265 0.210685 0.0614128 -0.082265 0.210627 0.0612921 -0.081765 0.210072 0.0616273 -0.082265 0.208169 0.0614128 -0.082265 0.208811 0.0614966 -0.081765 0.208227 0.0612921 -0.081765 0.207619 0.0610673 -0.082265 0.206814 0.0600582 -0.082265 0.2066 0.0594453 -0.082265 0.206935 0.0600001 -0.081765 0.206527 0.0588 -0.082265 0.206935 0.0575998 -0.081765 0.208169 0.0561871 -0.082265 0.208781 0.0559727 -0.082265 0.208811 0.0561033 -0.081765 0.209427 0.0560339 -0.081765 0.210382 0.0433835 -0.090065 0.212177 0.0440368 -0.090065 0.213973 0.046175 -0.089998 0.21419 0.04605 -0.090065 0.214595 0.0469188 -0.090065 0.214927 0.0488 -0.090065 0.214597 0.0497116 -0.089998 0.214843 0.049755 -0.090065 0.21419 0.05155 -0.090065 0.21364 0.0523353 -0.090065 0.212962 0.0530132 -0.090065 0.212052 0.0533466 -0.089998 0.212177 0.0535631 -0.090065 0.211222 0.0537333 -0.089998 0.210382 0.0542164 -0.090065 0.209427 0.0543 -0.090065 0.208515 0.0539702 -0.089998 0.207631 0.0537333 -0.089998 0.208472 0.0542164 -0.090065 0.207546 0.0539683 -0.090065 0.20488 0.051425 -0.089998 0.204257 0.0497116 -0.089998 0.204258 0.0469188 -0.090065 0.20488 0.046175 -0.089998 0.206802 0.0442533 -0.089998 0.207631 0.0438666 -0.089998 0.208472 0.0433835 -0.090065 0.210338 0.0436297 -0.089998 0.211222 0.0438666 -0.089998 0.212052 0.0442533 -0.089998 0.212684 0.0449184 -0.089815 0.212801 0.0447782 -0.089998 0.213449 0.0454253 -0.089998 0.213308 0.045543 -0.089815 0.213815 0.0462665 -0.089815 0.214188 0.0470669 -0.089815 0.214417 0.0479201 -0.089815 0.21436 0.0470044 -0.089998 0.214597 0.0478883 -0.089998 0.214677 0.0488 -0.089998 0.214417 0.0496798 -0.089815 0.214188 0.050533 -0.089815 0.21436 0.0505956 -0.089998 0.213815 0.0513335 -0.089815 0.213308 0.052057 -0.089815 0.213973 0.051425 -0.089998 0.213449 0.0521746 -0.089998 0.212801 0.0528217 -0.089998 0.212684 0.0526815 -0.089815 0.21196 0.0531881 -0.089815 0.21116 0.0535614 -0.089815 0.210307 0.05379 -0.089815 0.210338 0.0539702 -0.089998 0.209427 0.05405 -0.089998 0.208547 0.05379 -0.089815 0.207694 0.0535614 -0.089815 0.206802 0.0533466 -0.089998 0.206052 0.0528217 -0.089998 0.205405 0.0521746 -0.089998 0.204665 0.050533 -0.089815 0.204493 0.0505956 -0.089998 0.204177 0.0488 -0.089998 0.204257 0.0478883 -0.089998 0.204493 0.0470044 -0.089998 0.205545 0.045543 -0.089815 0.205405 0.0454253 -0.089998 0.206052 0.0447782 -0.089998 0.206893 0.0444118 -0.089815 0.207694 0.0440385 -0.089815 0.208547 0.04381 -0.089815 0.208515 0.0436297 -0.089998 0.209427 0.04355 -0.089998 0.210307 0.04381 -0.089815 0.211137 0.0441015 -0.089565 0.21116 0.0440385 -0.089815 0.211927 0.0444698 -0.089565 0.21196 0.0444118 -0.089815 0.213757 0.0463 -0.089565 0.214125 0.0470899 -0.089565 0.214351 0.0479317 -0.089565 0.214494 0.0488 -0.089815 0.214351 0.0496682 -0.089565 0.213757 0.0513 -0.089565 0.213257 0.0520139 -0.089565 0.212641 0.0526302 -0.089565 0.211137 0.0534984 -0.089565 0.209427 0.0538669 -0.089815 0.208559 0.053724 -0.089565 0.207717 0.0534984 -0.089565 0.206927 0.0531301 -0.089565 0.206893 0.0531881 -0.089815 0.20617 0.0526815 -0.089815 0.206213 0.0526302 -0.089565 0.205597 0.0520139 -0.089565 0.205545 0.052057 -0.089815 0.205039 0.0513335 -0.089815 0.205097 0.0513 -0.089565 0.204728 0.0505101 -0.089565 0.204437 0.0496798 -0.089815 0.204427 0.0488 -0.089565 0.204503 0.0479317 -0.089565 0.20436 0.0488 -0.089815 0.204437 0.0479201 -0.089815 0.204728 0.0470899 -0.089565 0.204665 0.0470669 -0.089815 0.205039 0.0462665 -0.089815 0.20617 0.0449184 -0.089815 0.208559 0.0438759 -0.089565 0.209427 0.043733 -0.089815 0.209427 0.0438 -0.089565 0.210295 0.0438759 -0.089565 0.210382 0.0542164 -0.084765 0.211222 0.0537333 -0.084832 0.212052 0.0533466 -0.084832 0.213449 0.0521746 -0.084832 0.213973 0.051425 -0.084832 0.214595 0.0506811 -0.084765 0.21436 0.0505956 -0.084832 0.214843 0.049755 -0.084765 0.214927 0.0488 -0.084765 0.214597 0.0478883 -0.084832 0.214843 0.0478449 -0.084765 0.213973 0.046175 -0.084832 0.213449 0.0454253 -0.084832 0.21419 0.04605 -0.084765 0.212052 0.0442533 -0.084832 0.212177 0.0440368 -0.084765 0.211222 0.0438666 -0.084832 0.210382 0.0433835 -0.084765 0.207546 0.0436316 -0.084765 0.206802 0.0442533 -0.084832 0.206052 0.0447782 -0.084832 0.205891 0.0445867 -0.084765 0.20488 0.046175 -0.084832 0.204664 0.04605 -0.084765 0.204493 0.0470044 -0.084832 0.204258 0.0469188 -0.084765 0.20401 0.0478449 -0.084765 0.204177 0.0488 -0.084832 0.203927 0.0488 -0.084765 0.20401 0.049755 -0.084765 0.204664 0.05155 -0.084765 0.205405 0.0521746 -0.084832 0.206052 0.0528217 -0.084832 0.206677 0.0535631 -0.084765 0.206802 0.0533466 -0.084832 0.208472 0.0542164 -0.084765 0.209427 0.05405 -0.084832 0.209427 0.0543 -0.084765 0.210338 0.0539702 -0.084832 0.21116 0.0535614 -0.085015 0.21196 0.0531881 -0.085015 0.212801 0.0528217 -0.084832 0.213308 0.052057 -0.085015 0.214597 0.0497116 -0.084832 0.214677 0.0488 -0.084832 0.214188 0.0470669 -0.085015 0.21436 0.0470044 -0.084832 0.213308 0.045543 -0.085015 0.212801 0.0447782 -0.084832 0.212684 0.0449184 -0.085015 0.21116 0.0440385 -0.085015 0.210338 0.0436297 -0.084832 0.209427 0.04355 -0.084832 0.209427 0.043733 -0.085015 0.208547 0.04381 -0.085015 0.208515 0.0436297 -0.084832 0.207694 0.0440385 -0.085015 0.207631 0.0438666 -0.084832 0.20617 0.0449184 -0.085015 0.205405 0.0454253 -0.084832 0.204437 0.0479201 -0.085015 0.204257 0.0478883 -0.084832 0.204257 0.0497116 -0.084832 0.204437 0.0496798 -0.085015 0.204493 0.0505956 -0.084832 0.205039 0.0513335 -0.085015 0.20488 0.051425 -0.084832 0.205545 0.052057 -0.085015 0.20617 0.0526815 -0.085015 0.206893 0.0531881 -0.085015 0.207694 0.0535614 -0.085015 0.207631 0.0537333 -0.084832 0.208515 0.0539702 -0.084832 0.209427 0.0538669 -0.085015 0.210307 0.05379 -0.085015 0.212684 0.0526815 -0.085015 0.213257 0.0520139 -0.085265 0.213757 0.0513 -0.085265 0.213815 0.0513335 -0.085015 0.214188 0.050533 -0.085015 0.214125 0.0505101 -0.085265 0.214351 0.0496682 -0.085265 0.214417 0.0496798 -0.085015 0.214494 0.0488 -0.085015 0.214351 0.0479317 -0.085265 0.214417 0.0479201 -0.085015 0.214125 0.0470899 -0.085265 0.213757 0.0463 -0.085265 0.213815 0.0462665 -0.085015 0.213257 0.045586 -0.085265 0.212641 0.0449697 -0.085265 0.21196 0.0444118 -0.085015 0.211927 0.0444698 -0.085265 0.211137 0.0441015 -0.085265 0.210295 0.0438759 -0.085265 0.210307 0.04381 -0.085015 0.209427 0.0438 -0.085265 0.206893 0.0444118 -0.085015 0.205597 0.045586 -0.085265 0.205545 0.045543 -0.085015 0.205039 0.0462665 -0.085015 0.205097 0.0463 -0.085265 0.204665 0.0470669 -0.085015 0.204427 0.0488 -0.085265 0.204503 0.0496682 -0.085265 0.20436 0.0488 -0.085015 0.204665 0.050533 -0.085015 0.205097 0.0513 -0.085265 0.205597 0.0520139 -0.085265 0.206927 0.0531301 -0.085265 0.207717 0.0534984 -0.085265 0.208547 0.05379 -0.085015 -0.147873 -0.130564 -0.0448269 -0.147477 -0.131167 -0.0476819 -0.147477 -0.129749 -0.0471935 -0.146326 -0.129014 -0.0493286 -0.144534 -0.129848 -0.0515113 -0.139773 -0.127927 -0.0524856 -0.125148 -0.127927 -0.0524856 -0.106798 -0.127927 -0.0524856 -0.0797732 -0.127927 -0.0524856 -0.0750121 -0.12843 -0.0510229 -0.0732202 -0.129014 -0.0493286 -0.0732202 -0.130432 -0.0498169 -0.0732202 -0.141685 -0.012527 -0.0750121 -0.143687 -0.011321 -0.0750121 -0.142269 -0.0108326 -0.0772702 -0.144062 -0.0102331 -0.131173 -0.142772 -0.00936993 -0.0883732 -0.142772 -0.00936993 -0.106798 -0.142772 -0.00936993 -0.116748 -0.142772 -0.00936993 -0.139773 -0.144191 -0.00985828 -0.139773 -0.142772 -0.00936993 -0.142276 -0.144062 -0.0102331 -0.144534 -0.142269 -0.0108326 -0.144534 -0.143687 -0.011321 -0.147477 -0.142368 -0.0151503 -0.147873 -0.131982 -0.0453152 -0.147873 -0.137734 -0.0240018 -0.0786732 -0.140114 -0.0232347 -0.118248 -0.134367 -0.0399231 -0.105298 -0.134367 -0.0399231 -0.0801003 -0.139334 -0.0254976 -0.0768232 -0.13724 -0.0315789 -0.0721732 -0.134367 -0.0399231 -0.0772123 -0.136441 -0.0339017 -0.0783415 -0.135719 -0.0359972 -0.0801003 -0.135147 -0.0376602 -0.0872299 -0.139702 -0.0244299 -0.0898732 -0.140114 -0.0232347 -0.0847732 -0.139829 -0.024062 -0.0872299 -0.134779 -0.0387279 -0.0898732 -0.134367 -0.0399231 -0.0894461 -0.135147 -0.0376602 -0.0927232 -0.13724 -0.0315789 -0.113773 -0.134082 -0.0407504 -0.108529 -0.134584 -0.0392945 -0.10495 -0.138552 -0.0277689 -0.106442 -0.139309 -0.0255728 -0.105298 -0.140114 -0.0232347 -0.105298 -0.144444 -0.0106593 -0.111284 -0.144266 -0.0111767 -0.109773 -0.144387 -0.0108248 -0.108263 -0.144266 -0.0111767 -0.106734 -0.142953 -0.0149874 -0.107618 -0.142537 -0.0161978 -0.11104 -0.140271 -0.0227789 -0.108995 -0.142301 -0.0168813 -0.119017 -0.134584 -0.0392945 -0.125148 -0.140114 -0.0232347 -0.122597 -0.138552 -0.0277689 -0.121104 -0.139309 -0.0255728 -0.119017 -0.139897 -0.0238633 -0.111928 -0.142537 -0.0161978 -0.134773 -0.134652 -0.0390958 -0.13723 -0.134779 -0.0387279 -0.147373 -0.134367 -0.0399231 -0.142334 -0.136441 -0.0339017 -0.142334 -0.13804 -0.029256 -0.147373 -0.140114 -0.0232347 -0.139446 -0.139334 -0.0254976 -0.13723 -0.139702 -0.0244299 -0.129673 -0.140114 -0.0232347 -0.127212 -0.13804 -0.029256 -0.127212 -0.136441 -0.0339017 -0.128342 -0.135719 -0.0359972 -0.0774247 -0.130101 -0.0523123 -0.0725452 -0.13169 -0.0476986 -0.0807344 -0.130777 -0.0503498 -0.0829954 -0.130125 -0.0522437 -0.084551 -0.130125 -0.0522437 -0.132734 -0.130777 -0.0503498 -0.133618 -0.13036 -0.0515602 -0.139773 -0.12998 -0.052664 -0.133098 -0.131753 -0.0475145 -0.138812 -0.130777 -0.0503498 -0.147373 -0.133146 -0.0434688 -0.135773 -0.13221 -0.0461872 -0.145922 -0.131 -0.0497018 -0.139 -0.13128 -0.0488897 -0.132734 -0.142953 -0.0149874 -0.137928 -0.142537 -0.0161978 -0.147373 -0.142026 -0.0176798 -0.138812 -0.142953 -0.0149874 -0.138448 -0.14393 -0.0121521 -0.140893 -0.144474 -0.0105722 -0.139 -0.143456 -0.0135273 -0.135773 -0.144387 -0.0108248 -0.134263 -0.144266 -0.0111767 -0.129673 -0.144444 -0.0106593 -0.0783415 -0.138762 -0.0271606 -0.075306 -0.144028 -0.0118662 -0.0736247 -0.143481 -0.013456 -0.0725452 -0.142791 -0.0154592 -0.0864479 -0.14393 -0.0121521 -0.0837732 -0.144387 -0.0108248 -0.0797732 -0.144501 -0.0104938 -0.0898732 -0.144444 -0.0106593 -0.0786732 -0.144444 -0.0106593 -0.0852835 -0.144266 -0.0111767 -0.0810985 -0.14393 -0.0121521 -0.11104 -0.13421 -0.0403789 -0.0898732 -0.133146 -0.0434688 -0.0786732 -0.133146 -0.0434688 -0.0786732 -0.134367 -0.0399231 -0.105298 -0.12998 -0.052664 -0.110551 -0.130125 -0.0522437 -0.118248 -0.12998 -0.052664 -0.0898732 -0.12998 -0.052664 -0.106547 -0.13128 -0.0488897 -0.113 -0.13128 -0.0488897 -0.111284 -0.132089 -0.0465391 -0.105298 -0.133146 -0.0434688 -0.132547 -0.13128 -0.0488897 -0.129673 -0.133146 -0.0434688 -0.125148 -0.12998 -0.052664 -0.125148 -0.133146 -0.0434688 -0.125148 -0.144444 -0.0106593 -0.118248 -0.140114 -0.0232347 -0.118248 -0.144444 -0.0106593 -0.112812 -0.142953 -0.0149874 -0.105298 -0.144501 -0.0104938 -0.118248 -0.144501 -0.0104938 -0.129673 -0.144501 -0.0104938 -0.139773 -0.144501 -0.0104938 -0.118248 -0.133146 -0.0434688 -0.125148 -0.134367 -0.0399231 -0.129673 -0.134367 -0.0399231 -0.125148 -0.131255 -0.0428177 -0.132567 -0.133376 -0.0366586 -0.0801732 -0.131255 -0.0428177 -0.0716732 -0.131255 -0.0428177 -0.0716732 -0.130564 -0.0448269 -0.0720696 -0.129749 -0.0471935 -0.0772702 -0.128056 -0.0521107 -0.0716732 -0.140135 -0.0170286 -0.0720696 -0.14095 -0.014662 -0.0797732 -0.142772 -0.00936993 -0.0772702 -0.142643 -0.00974477 -0.135773 -0.142007 -0.0115919 -0.136648 -0.140944 -0.0146795 -0.134258 -0.141153 -0.0140739 -0.134898 -0.141931 -0.0118136 -0.136648 -0.141931 -0.0118136 -0.142276 -0.142643 -0.00974477 -0.137289 -0.141722 -0.0124192 -0.147873 -0.140135 -0.0170286 -0.137289 -0.141153 -0.0140739 -0.147477 -0.14095 -0.014662 -0.137523 -0.141438 -0.0132466 -0.146326 -0.141685 -0.012527 -0.137289 -0.129546 -0.0477816 -0.134258 -0.129546 -0.0477816 -0.142276 -0.128056 -0.0521107 -0.137523 -0.129261 -0.048609 -0.144534 -0.12843 -0.0510229 -0.136648 -0.128768 -0.0500419 -0.131173 -0.127927 -0.0524856 -0.120407 -0.136919 -0.0263705 -0.121973 -0.135349 -0.0309278 -0.109773 -0.142007 -0.0115919 -0.111289 -0.141153 -0.0140739 -0.116307 -0.137888 -0.023554 -0.113773 -0.138019 -0.0231745 -0.111239 -0.137888 -0.023554 -0.0903591 -0.1343 -0.0339771 -0.106798 -0.132965 -0.0378537 -0.107139 -0.13378 -0.035485 -0.136979 -0.137323 -0.025197 -0.134773 -0.137449 -0.0248292 -0.140359 -0.136399 -0.0278785 -0.128421 -0.134985 -0.0319868 -0.129187 -0.136399 -0.0278785 -0.131173 -0.137734 -0.0240018 -0.130627 -0.136958 -0.026256 -0.0889192 -0.133741 -0.0355995 -0.0883732 -0.132965 -0.0378537 -0.105975 -0.136174 -0.0285319 -0.107139 -0.136919 -0.0263705 -0.0903591 -0.136399 -0.0278785 -0.0847732 -0.137449 -0.0248292 -0.0716732 -0.137734 -0.0240018 -0.0784212 -0.134985 -0.0319868 -0.0806272 -0.133741 -0.0355995 -0.0716732 -0.132965 -0.0378537 -0.0791873 -0.1343 -0.0339771 -0.0784212 -0.135714 -0.0298687 -0.0801732 -0.137734 -0.0240018 -0.131173 -0.132965 -0.0378537 -0.147873 -0.132965 -0.0378537 -0.147873 -0.131255 -0.0428177 -0.131173 -0.131255 -0.0428177 -0.136648 -0.129755 -0.047176 -0.125148 -0.137734 -0.0240018 -0.118593 -0.137509 -0.0246552 -0.125148 -0.14239 -0.0104809 -0.108023 -0.129261 -0.048609 -0.108258 -0.129546 -0.0477816 -0.108898 -0.129755 -0.047176 -0.116748 -0.131255 -0.0428177 -0.110648 -0.129755 -0.047176 -0.125148 -0.132965 -0.0378537 -0.116307 -0.13281 -0.0383015 -0.116748 -0.127927 -0.0524856 -0.111289 -0.129546 -0.0477816 -0.110648 -0.128768 -0.0500419 -0.109773 -0.128692 -0.0502636 -0.108898 -0.128768 -0.0500419 -0.0828982 -0.129755 -0.047176 -0.0883732 -0.127927 -0.0524856 -0.0822577 -0.128976 -0.0494363 -0.0801732 -0.127927 -0.0524856 -0.0820232 -0.129261 -0.048609 -0.0822577 -0.129546 -0.0477816 -0.0883732 -0.131255 -0.0428177 -0.0828982 -0.128768 -0.0500419 -0.0852887 -0.141722 -0.0124192 -0.0883732 -0.14239 -0.0104809 -0.0883732 -0.137734 -0.0240018 -0.106798 -0.137734 -0.0240018 -0.0822577 -0.141153 -0.0140739 -0.131173 -0.14239 -0.0104809 -0.125148 -0.142772 -0.00936993 -0.116748 -0.14239 -0.0104809 -0.106798 -0.14239 -0.0104809 -0.0801732 -0.14239 -0.0104809 -0.0801732 -0.142772 -0.00936993 -0.111239 -0.13281 -0.0383015 -0.106798 -0.131255 -0.0428177 -0.0801732 -0.132965 -0.0378537 -0.137289 -0.142195 -0.012582 -0.13751 -0.141979 -0.0132099 -0.137523 -0.14191 -0.0134093 -0.137409 -0.141708 -0.0139961 -0.137289 -0.141625 -0.0142367 -0.136648 -0.141417 -0.0148423 -0.136192 -0.141357 -0.0150159 -0.135773 -0.140868 -0.0149012 -0.134898 -0.140944 -0.0146795 -0.134258 -0.141625 -0.0142367 -0.134023 -0.141438 -0.0132466 -0.134137 -0.141708 -0.0139961 -0.134023 -0.14191 -0.0134093 -0.134036 -0.141979 -0.0132099 -0.134258 -0.142195 -0.012582 -0.134258 -0.141722 -0.0124192 -0.134333 -0.142234 -0.0124694 -0.135773 -0.14248 -0.0117547 -0.133098 -0.14393 -0.0121521 -0.132547 -0.143456 -0.0135273 -0.134613 -0.141484 -0.0146479 -0.133618 -0.142537 -0.0161978 -0.134898 -0.141417 -0.0148423 -0.135354 -0.141357 -0.0150159 -0.135773 -0.141341 -0.015064 -0.134995 -0.142301 -0.0168813 -0.136551 -0.142301 -0.0168813 -0.136934 -0.141484 -0.0146479 -0.137213 -0.142234 -0.0124694 -0.136648 -0.142404 -0.0119764 -0.137284 -0.144266 -0.0111767 -0.136586 -0.142415 -0.0119442 -0.13496 -0.142415 -0.0119442 -0.134898 -0.142404 -0.0119764 -0.110648 -0.141931 -0.0118136 -0.110648 -0.142404 -0.0119764 -0.111213 -0.142234 -0.0124694 -0.111289 -0.141722 -0.0124192 -0.111409 -0.141708 -0.0139961 -0.111523 -0.141438 -0.0132466 -0.110648 -0.140944 -0.0146795 -0.111289 -0.141625 -0.0142367 -0.110934 -0.141484 -0.0146479 -0.110192 -0.141357 -0.0150159 -0.109773 -0.141341 -0.015064 -0.109354 -0.141357 -0.0150159 -0.109773 -0.140868 -0.0149012 -0.108898 -0.140944 -0.0146795 -0.108258 -0.141153 -0.0140739 -0.108023 -0.141438 -0.0132466 -0.108036 -0.141979 -0.0132099 -0.108258 -0.141722 -0.0124192 -0.108898 -0.141931 -0.0118136 -0.108898 -0.142404 -0.0119764 -0.107099 -0.14393 -0.0121521 -0.108333 -0.142234 -0.0124694 -0.108258 -0.142195 -0.012582 -0.106547 -0.143456 -0.0135273 -0.108023 -0.14191 -0.0134093 -0.108137 -0.141708 -0.0139961 -0.108258 -0.141625 -0.0142367 -0.108613 -0.141484 -0.0146479 -0.108898 -0.141417 -0.0148423 -0.110551 -0.142301 -0.0168813 -0.110648 -0.141417 -0.0148423 -0.111523 -0.14191 -0.0134093 -0.11151 -0.141979 -0.0132099 -0.113 -0.143456 -0.0135273 -0.112448 -0.14393 -0.0121521 -0.111289 -0.142195 -0.012582 -0.110586 -0.142415 -0.0119442 -0.109773 -0.14248 -0.0117547 -0.10896 -0.142415 -0.0119442 -0.0846482 -0.141931 -0.0118136 -0.0846482 -0.142404 -0.0119764 -0.0852134 -0.142234 -0.0124694 -0.0852887 -0.142195 -0.012582 -0.0855232 -0.141438 -0.0132466 -0.0852887 -0.141153 -0.0140739 -0.0849337 -0.141484 -0.0146479 -0.0846482 -0.140944 -0.0146795 -0.0837732 -0.140868 -0.0149012 -0.0846482 -0.141417 -0.0148423 -0.084192 -0.141357 -0.0150159 -0.0837732 -0.141341 -0.015064 -0.0828982 -0.140944 -0.0146795 -0.0822577 -0.141625 -0.0142367 -0.0820232 -0.141438 -0.0132466 -0.0822577 -0.141722 -0.0124192 -0.0828982 -0.141931 -0.0118136 -0.0828982 -0.142404 -0.0119764 -0.0837732 -0.142007 -0.0115919 -0.0822629 -0.144266 -0.0111767 -0.082333 -0.142234 -0.0124694 -0.0822577 -0.142195 -0.012582 -0.082036 -0.141979 -0.0132099 -0.0805469 -0.143456 -0.0135273 -0.0820232 -0.14191 -0.0134093 -0.0821369 -0.141708 -0.0139961 -0.0807344 -0.142953 -0.0149874 -0.0816181 -0.142537 -0.0161978 -0.0826127 -0.141484 -0.0146479 -0.0829954 -0.142301 -0.0168813 -0.0828982 -0.141417 -0.0148423 -0.0833544 -0.141357 -0.0150159 -0.084551 -0.142301 -0.0168813 -0.0859284 -0.142537 -0.0161978 -0.0852887 -0.141625 -0.0142367 -0.086812 -0.142953 -0.0149874 -0.0854095 -0.141708 -0.0139961 -0.0855232 -0.14191 -0.0134093 -0.0869995 -0.143456 -0.0135273 -0.0855104 -0.141979 -0.0132099 -0.0845865 -0.142415 -0.0119442 -0.0837732 -0.14248 -0.0117547 -0.0829599 -0.142415 -0.0119442 -0.137213 -0.130058 -0.0478318 -0.137523 -0.129734 -0.0487717 -0.137409 -0.129532 -0.0493585 -0.137289 -0.128976 -0.0494363 -0.137289 -0.129449 -0.0495991 -0.136648 -0.129241 -0.0502047 -0.135773 -0.128692 -0.0502636 -0.134898 -0.128768 -0.0500419 -0.134258 -0.128976 -0.0494363 -0.134023 -0.129261 -0.048609 -0.134023 -0.129734 -0.0487717 -0.134036 -0.129803 -0.0485723 -0.134258 -0.130019 -0.0479444 -0.134333 -0.130058 -0.0478318 -0.134898 -0.129755 -0.047176 -0.135773 -0.129831 -0.0469543 -0.13496 -0.130239 -0.0473066 -0.134137 -0.129532 -0.0493585 -0.134258 -0.129449 -0.0495991 -0.134613 -0.129308 -0.0500103 -0.134898 -0.129241 -0.0502047 -0.134995 -0.130125 -0.0522437 -0.135354 -0.129181 -0.0503783 -0.135773 -0.129164 -0.0504264 -0.136551 -0.130125 -0.0522437 -0.136192 -0.129181 -0.0503783 -0.137928 -0.13036 -0.0515602 -0.136934 -0.129308 -0.0500103 -0.13751 -0.129803 -0.0485723 -0.137289 -0.130019 -0.0479444 -0.138448 -0.131753 -0.0475145 -0.136648 -0.130228 -0.0473388 -0.137284 -0.132089 -0.0465391 -0.136586 -0.130239 -0.0473066 -0.134263 -0.132089 -0.0465391 -0.135773 -0.130304 -0.0471171 -0.134898 -0.130228 -0.0473388 -0.111213 -0.130058 -0.0478318 -0.111289 -0.130019 -0.0479444 -0.111523 -0.129261 -0.048609 -0.111523 -0.129734 -0.0487717 -0.111289 -0.128976 -0.0494363 -0.111289 -0.129449 -0.0495991 -0.110934 -0.129308 -0.0500103 -0.110648 -0.129241 -0.0502047 -0.110192 -0.129181 -0.0503783 -0.108613 -0.129308 -0.0500103 -0.108258 -0.128976 -0.0494363 -0.108137 -0.129532 -0.0493585 -0.108036 -0.129803 -0.0485723 -0.108258 -0.130019 -0.0479444 -0.108333 -0.130058 -0.0478318 -0.108898 -0.130228 -0.0473388 -0.10896 -0.130239 -0.0473066 -0.109773 -0.129831 -0.0469543 -0.107099 -0.131753 -0.0475145 -0.108023 -0.129734 -0.0487717 -0.108258 -0.129449 -0.0495991 -0.106734 -0.130777 -0.0503498 -0.108898 -0.129241 -0.0502047 -0.107618 -0.13036 -0.0515602 -0.108995 -0.130125 -0.0522437 -0.109354 -0.129181 -0.0503783 -0.109773 -0.129164 -0.0504264 -0.111928 -0.13036 -0.0515602 -0.112812 -0.130777 -0.0503498 -0.111409 -0.129532 -0.0493585 -0.11151 -0.129803 -0.0485723 -0.112448 -0.131753 -0.0475145 -0.110648 -0.130228 -0.0473388 -0.110586 -0.130239 -0.0473066 -0.109773 -0.13221 -0.0461872 -0.109773 -0.130304 -0.0471171 -0.108263 -0.132089 -0.0465391 -0.0846482 -0.129755 -0.047176 -0.0837732 -0.129831 -0.0469543 -0.0852887 -0.129546 -0.0477816 -0.0855232 -0.129261 -0.048609 -0.0852887 -0.128976 -0.0494363 -0.0852887 -0.129449 -0.0495991 -0.0846482 -0.128768 -0.0500419 -0.0849337 -0.129308 -0.0500103 -0.0837732 -0.128692 -0.0502636 -0.084192 -0.129181 -0.0503783 -0.0837732 -0.129164 -0.0504264 -0.0822577 -0.129449 -0.0495991 -0.0820232 -0.129734 -0.0487717 -0.082036 -0.129803 -0.0485723 -0.082333 -0.130058 -0.0478318 -0.0837732 -0.130304 -0.0471171 -0.0810985 -0.131753 -0.0475145 -0.0828982 -0.130228 -0.0473388 -0.0822577 -0.130019 -0.0479444 -0.0805469 -0.13128 -0.0488897 -0.0821369 -0.129532 -0.0493585 -0.0816181 -0.13036 -0.0515602 -0.0826127 -0.129308 -0.0500103 -0.0828982 -0.129241 -0.0502047 -0.0833544 -0.129181 -0.0503783 -0.0846482 -0.129241 -0.0502047 -0.0859284 -0.13036 -0.0515602 -0.086812 -0.130777 -0.0503498 -0.0854095 -0.129532 -0.0493585 -0.0869995 -0.13128 -0.0488897 -0.0855232 -0.129734 -0.0487717 -0.0864479 -0.131753 -0.0475145 -0.0855104 -0.129803 -0.0485723 -0.0852887 -0.130019 -0.0479444 -0.0852134 -0.130058 -0.0478318 -0.0852835 -0.132089 -0.0465391 -0.0846482 -0.130228 -0.0473388 -0.0845865 -0.130239 -0.0473066 -0.0837732 -0.13221 -0.0461872 -0.0822629 -0.132089 -0.0465391 -0.0829599 -0.130239 -0.0473066 -0.116083 -0.133261 -0.0385297 -0.113773 -0.13268 -0.038681 -0.118206 -0.133576 -0.037613 -0.118593 -0.13319 -0.0372003 -0.118593 -0.133662 -0.0373631 -0.120407 -0.13378 -0.035485 -0.121232 -0.134713 -0.0343114 -0.121572 -0.134997 -0.0334864 -0.12189 -0.135442 -0.0321939 -0.121572 -0.134524 -0.0333236 -0.12189 -0.136202 -0.0299871 -0.121973 -0.135822 -0.0310905 -0.11997 -0.13757 -0.0260132 -0.121572 -0.136174 -0.0285319 -0.116307 -0.138361 -0.0237168 -0.116083 -0.138384 -0.0236513 -0.113773 -0.138492 -0.0233373 -0.111463 -0.138384 -0.0236513 -0.111239 -0.138361 -0.0237168 -0.10934 -0.138068 -0.0245681 -0.108953 -0.137509 -0.0246552 -0.108953 -0.137982 -0.024818 -0.107576 -0.13757 -0.0260132 -0.107139 -0.137391 -0.0265333 -0.106314 -0.136931 -0.0278697 -0.105975 -0.136647 -0.0286947 -0.105657 -0.136202 -0.0299871 -0.105573 -0.135349 -0.0309278 -0.105975 -0.134997 -0.0334864 -0.108953 -0.133662 -0.0373631 -0.105975 -0.134524 -0.0333236 -0.107139 -0.134253 -0.0356478 -0.111239 -0.133283 -0.0384643 -0.108953 -0.13319 -0.0372003 -0.138919 -0.136958 -0.026256 -0.136979 -0.133849 -0.0368213 -0.136979 -0.133376 -0.0366586 -0.134773 -0.13325 -0.0370263 -0.138919 -0.133741 -0.0355995 -0.139991 -0.134588 -0.0346752 -0.140359 -0.1343 -0.0339771 -0.141125 -0.135458 -0.0321495 -0.141125 -0.134985 -0.0319868 -0.141125 -0.135714 -0.0298687 -0.141125 -0.136187 -0.0300315 -0.136979 -0.137795 -0.0253597 -0.136766 -0.137819 -0.0252904 -0.134773 -0.137922 -0.0249919 -0.13278 -0.137819 -0.0252904 -0.132567 -0.137323 -0.025197 -0.130982 -0.137521 -0.0261567 -0.128421 -0.135714 -0.0298687 -0.128323 -0.135822 -0.0310905 -0.129187 -0.1343 -0.0339771 -0.129555 -0.134588 -0.0346752 -0.129187 -0.134772 -0.0341398 -0.134773 -0.133722 -0.0371891 -0.130982 -0.134123 -0.0360244 -0.130627 -0.133741 -0.0355995 -0.130627 -0.134214 -0.0357623 -0.0889192 -0.137431 -0.0264187 -0.0867664 -0.133825 -0.0368906 -0.0869792 -0.133376 -0.0366586 -0.0885644 -0.134123 -0.0360244 -0.0889192 -0.134214 -0.0357623 -0.0899914 -0.134588 -0.0346752 -0.0912232 -0.135822 -0.0310905 -0.0911252 -0.134985 -0.0319868 -0.0899914 -0.137057 -0.0275059 -0.0903591 -0.136872 -0.0280412 -0.0911252 -0.135714 -0.0298687 -0.0909075 -0.136471 -0.029206 -0.0889192 -0.136958 -0.026256 -0.0869792 -0.137795 -0.0253597 -0.0867664 -0.137819 -0.0252904 -0.0869792 -0.137323 -0.025197 -0.0825672 -0.137323 -0.025197 -0.080982 -0.137521 -0.0261567 -0.0806272 -0.137431 -0.0264187 -0.0806272 -0.136958 -0.026256 -0.0791873 -0.136399 -0.0278785 -0.0786389 -0.136471 -0.029206 -0.0791873 -0.134772 -0.0341398 -0.0847732 -0.13325 -0.0370263 -0.0825672 -0.133376 -0.0366586 -0.0825672 -0.133849 -0.0368213 -0.080982 -0.134123 -0.0360244 -0.132317 -0.139702 -0.0244299 -0.132567 -0.137795 -0.0253597 -0.1301 -0.139334 -0.0254976 -0.130627 -0.137431 -0.0264187 -0.129555 -0.137057 -0.0275059 -0.128342 -0.138762 -0.0271606 -0.129187 -0.136872 -0.0280412 -0.128639 -0.136471 -0.029206 -0.128421 -0.136187 -0.0300315 -0.126823 -0.13724 -0.0315789 -0.128421 -0.135458 -0.0321495 -0.128639 -0.135173 -0.0329751 -0.1301 -0.135147 -0.0376602 -0.132317 -0.134779 -0.0387279 -0.132567 -0.133849 -0.0368213 -0.13278 -0.133825 -0.0368906 -0.136766 -0.133825 -0.0368906 -0.139446 -0.135147 -0.0376602 -0.138564 -0.134123 -0.0360244 -0.138919 -0.134214 -0.0357623 -0.140359 -0.134772 -0.0341398 -0.141205 -0.135719 -0.0359972 -0.140908 -0.135173 -0.0329751 -0.142723 -0.13724 -0.0315789 -0.141223 -0.135822 -0.0310905 -0.140908 -0.136471 -0.029206 -0.140359 -0.136872 -0.0280412 -0.139991 -0.137057 -0.0275059 -0.141205 -0.138762 -0.0271606 -0.138919 -0.137431 -0.0264187 -0.138564 -0.137521 -0.0261567 -0.134773 -0.139829 -0.024062 -0.108529 -0.139897 -0.0238633 -0.104172 -0.13769 -0.0302736 -0.104172 -0.136791 -0.0328841 -0.105573 -0.135822 -0.0310905 -0.105657 -0.135442 -0.0321939 -0.10495 -0.135929 -0.0353889 -0.106314 -0.134713 -0.0343114 -0.106442 -0.135172 -0.037585 -0.107576 -0.134074 -0.0361678 -0.10934 -0.133576 -0.037613 -0.111463 -0.133261 -0.0385297 -0.113773 -0.133153 -0.0388438 -0.116506 -0.13421 -0.0403789 -0.116307 -0.133283 -0.0384643 -0.11997 -0.134074 -0.0361678 -0.121104 -0.135172 -0.037585 -0.120407 -0.134253 -0.0356478 -0.122597 -0.135929 -0.0353889 -0.123374 -0.136791 -0.0328841 -0.123374 -0.13769 -0.0302736 -0.121572 -0.136647 -0.0286947 -0.121232 -0.136931 -0.0278697 -0.120407 -0.137391 -0.0265333 -0.118593 -0.137982 -0.024818 -0.118206 -0.138068 -0.0245681 -0.117602 -0.140142 -0.0231519 -0.116506 -0.140271 -0.0227789 -0.113773 -0.140399 -0.0224074 -0.079555 -0.137057 -0.0275059 -0.0791873 -0.136872 -0.0280412 -0.0772123 -0.13804 -0.029256 -0.0784212 -0.136187 -0.0300315 -0.0783232 -0.135822 -0.0310905 -0.0784212 -0.135458 -0.0321495 -0.0786389 -0.135173 -0.0329751 -0.079555 -0.134588 -0.0346752 -0.0806272 -0.134214 -0.0357623 -0.0823165 -0.134779 -0.0387279 -0.0847732 -0.134652 -0.0390958 -0.08278 -0.133825 -0.0368906 -0.0847732 -0.133722 -0.0371891 -0.0869792 -0.133849 -0.0368213 -0.0912049 -0.135719 -0.0359972 -0.0903591 -0.134772 -0.0341398 -0.0909075 -0.135173 -0.0329751 -0.0911252 -0.135458 -0.0321495 -0.0923341 -0.136441 -0.0339017 -0.0911252 -0.136187 -0.0300315 -0.0923341 -0.13804 -0.029256 -0.0912049 -0.138762 -0.0271606 -0.0894461 -0.139334 -0.0254976 -0.0885644 -0.137521 -0.0261567 -0.0847732 -0.137922 -0.0249919 -0.0823165 -0.139702 -0.0244299 -0.08278 -0.137819 -0.0252904 -0.0825672 -0.137795 -0.0253597 -0.129673 -0.12998 -0.052664 -0.0797732 -0.129345 -0.0529739 -0.147373 -0.132455 -0.045478 -0.147001 -0.13169 -0.0476986 -0.146326 -0.130432 -0.0498169 -0.14424 -0.130453 -0.0512916 -0.142122 -0.130101 -0.0523123 -0.142276 -0.129474 -0.0525991 -0.139773 -0.129345 -0.0529739 -0.0797732 -0.12998 -0.052664 -0.0772702 -0.129474 -0.0525991 -0.075306 -0.130453 -0.0512916 -0.0750121 -0.129848 -0.0515113 -0.0720696 -0.131167 -0.0476819 -0.0736247 -0.131 -0.0497018 -0.0716732 -0.131982 -0.0453152 -0.0721732 -0.132455 -0.045478 -0.0716732 -0.141554 -0.017517 -0.0721732 -0.140114 -0.0232347 -0.0721732 -0.133146 -0.0434688 -0.142122 -0.14438 -0.0108455 -0.14424 -0.144028 -0.0118662 -0.146326 -0.143104 -0.0130153 -0.145922 -0.143481 -0.013456 -0.147001 -0.142791 -0.0154592 -0.147873 -0.141554 -0.017517 -0.0721732 -0.142026 -0.0176798 -0.0720696 -0.142368 -0.0151503 -0.0732202 -0.143104 -0.0130153 -0.0774247 -0.14438 -0.0108455 -0.125148 -0.144501 -0.0104938 -0.0797732 -0.144191 -0.00985828 -0.0898732 -0.144501 -0.0104938 -0.238673 0.0672816 -0.0301395 -0.228673 0.0672816 -0.0301395 -0.228673 0.0746721 -0.0298926 -0.228673 0.0817691 -0.0278156 -0.228673 0.0970967 -0.0124275 -0.238673 0.094106 -0.0177693 -0.238673 0.0993635 0.00206901 -0.228673 0.0993635 0.00206901 -0.238673 0.0919167 0.0189811 -0.238673 0.0833409 0.025546 -0.238673 0.0690153 0.0287186 -0.228673 0.0763785 0.0280372 -0.228673 0.061714 0.0275474 -0.238673 0.0549333 0.0245973 -0.238673 0.0503104 0.0212025 -0.228673 0.0490993 0.0200536 -0.238673 0.0445786 0.0142018 -0.238673 0.0416552 0.0074095 -0.238673 0.0405127 0.000103622 -0.228673 0.0405127 0.000103622 -0.228673 0.0412231 -0.00725684 -0.228673 0.0437417 -0.0142094 -0.228673 0.0534665 -0.0251964 -0.238673 0.0534665 -0.0251964 -0.190673 0.0451006 0.0348471 -0.191424 0.0448585 0.0360734 -0.190673 0.0454514 0.034973 -0.190673 0.046108 0.0360366 -0.190673 0.0456087 0.0350736 -0.190673 0.0459222 0.0354168 -0.190673 0.043758 0.0354806 -0.190673 0.043609 0.0361102 -0.190673 0.0437168 0.0355645 -0.185973 0.043758 0.0354806 -0.190673 0.0440507 0.0351195 -0.185973 0.0442019 0.0350098 -0.190673 0.0442019 0.0350098 -0.190673 0.0445446 0.0348635 -0.190673 0.0448217 0.034824 -0.185973 0.0448217 0.034824 -0.190673 0.0459683 0.0354981 -0.190673 0.0700637 0.0438525 -0.185973 0.0700637 0.0438525 -0.185973 0.0701715 0.0433067 -0.190673 0.0709992 0.0426058 -0.190673 0.0715553 0.0425894 -0.185973 0.0709992 0.0426058 -0.185973 0.0720634 0.0428159 -0.190673 0.0720634 0.0428159 -0.190673 0.0724229 0.0432404 -0.190673 0.0701715 0.0433067 -0.190673 0.0705054 0.0428618 -0.191424 0.0713132 0.0438157 -0.185973 0.0961657 0.0339368 -0.190673 0.0966096 0.033466 -0.185973 0.0966096 0.033466 -0.190673 0.0983299 0.0338731 -0.190673 0.0985157 0.0344929 -0.190673 0.0972294 0.0332802 -0.190673 0.0961657 0.0339368 -0.190673 0.0960167 0.0345665 -0.190673 0.0978591 0.0334292 -0.190673 0.111704 0.0111694 -0.185973 0.111704 0.0111694 -0.190673 0.112148 0.0106986 -0.190673 0.112768 0.0105128 -0.185973 0.112148 0.0106986 -0.185973 0.112768 0.0105128 -0.190673 0.113397 0.0106618 -0.185973 0.113397 0.0106618 -0.190673 0.113868 0.0111057 -0.185973 0.110851 -0.016299 -0.190673 0.111185 -0.016744 -0.190673 0.111679 -0.017 -0.185973 0.111185 -0.016744 -0.185973 0.112235 -0.0170164 -0.190673 0.113103 -0.0163654 -0.190673 0.113242 -0.0158269 -0.185973 0.113242 -0.0158269 -0.190673 0.110851 -0.016299 -0.190673 0.112235 -0.0170164 -0.190673 0.112743 -0.0167899 -0.191424 0.111993 -0.0157901 -0.190673 0.094041 -0.0381962 -0.190673 0.0944848 -0.038667 -0.185973 0.0944848 -0.038667 -0.190673 0.0951046 -0.0388528 -0.185973 0.0951046 -0.0388528 -0.190673 0.0962051 -0.03826 -0.190673 0.0957343 -0.0387038 -0.185973 0.0674373 -0.0453088 -0.190673 0.0675451 -0.0458546 -0.185973 0.0675451 -0.0458546 -0.190673 0.067879 -0.0462996 -0.185973 0.067879 -0.0462996 -0.190673 0.0683729 -0.0465556 -0.185973 0.0683729 -0.0465556 -0.185973 0.0689289 -0.046572 -0.190673 0.069437 -0.0463454 -0.185973 0.069437 -0.0463454 -0.190673 0.0699362 -0.0453824 -0.185973 0.0697965 -0.0459209 -0.185973 0.0699362 -0.0453824 -0.190673 0.0689289 -0.046572 -0.190673 0.0697965 -0.0459209 -0.190673 0.0414842 -0.0360228 -0.190673 0.041592 -0.0365686 -0.185973 0.0416332 -0.0366525 -0.190673 0.0419259 -0.0370135 -0.185973 0.0420771 -0.0371233 -0.185973 0.0426969 -0.0373091 -0.190673 0.0429759 -0.0372859 -0.185973 0.0433266 -0.0371601 -0.190673 0.043484 -0.0370594 -0.185973 0.0437974 -0.0367162 -0.190673 0.0416332 -0.0366525 -0.190673 0.0420771 -0.0371233 -0.190673 0.0424198 -0.0372696 -0.190673 0.0438435 -0.0366349 -0.190673 0.0437974 -0.0367162 -0.190673 0.0433266 -0.0371601 -0.190673 0.0426969 -0.0373091 -0.185973 0.0263876 -0.0142461 -0.190673 0.0263876 -0.0142461 -0.190673 0.0265388 -0.0143559 -0.185973 0.0268815 -0.0145022 -0.190673 0.0274376 -0.0145186 -0.190673 0.0277883 -0.0143927 -0.185973 0.0274376 -0.0145186 -0.190673 0.0279457 -0.014292 -0.185973 0.0279457 -0.014292 -0.190673 0.0282591 -0.0139488 -0.190673 0.0284449 -0.013329 -0.190673 0.025946 -0.0132554 -0.190673 0.0271586 -0.0145417 -0.190673 0.0268815 -0.0145022 -0.190673 0.026095 -0.0138851 -0.190673 0.0269066 0.0136673 -0.185973 0.0269066 0.0136673 -0.190673 0.0273504 0.0131965 -0.190673 0.0279702 0.0130107 -0.185973 0.0285999 0.0131597 -0.185973 0.0290707 0.0136035 -0.185973 0.0292565 0.0142233 -0.190673 0.0292565 0.0142233 -0.190673 0.0290707 0.0136035 -0.190673 0.0285999 0.0131597 -0.229755 0.137219 0.00770279 -0.229763 0.137195 0.00771738 -0.229782 0.137152 0.00763476 -0.232755 0.128959 0.00729723 -0.229747 0.137235 0.0077498 -0.230996 0.134016 0.00569846 -0.231259 0.133385 0.00466305 -0.231376 0.133152 0.00352578 -0.229744 0.134728 0.0193461 -0.229776 0.134854 0.0186345 -0.229764 0.134897 0.0186064 -0.230964 0.131761 0.0175839 -0.231409 0.130762 0.0166384 -0.231706 0.130212 0.0155726 -0.231808 0.130072 0.015015 -0.231118 0.132992 0.0105873 -0.229744 0.137155 0.00841795 -0.229807 0.136571 0.0110235 -0.229776 0.136671 0.0109577 -0.229784 0.136636 0.0110256 -0.229764 0.136697 0.0110021 -0.230491 0.134741 0.0105898 -0.232755 0.111575 0.0418108 -0.231739 0.114013 0.0433275 -0.231928 0.114948 0.04162 -0.232755 0.114949 0.0382321 -0.231768 0.116452 0.0406291 -0.232755 0.118016 0.0343871 -0.229744 0.124691 0.0392735 -0.229784 0.121813 0.0427639 -0.229776 0.121877 0.0427226 -0.230491 0.12039 0.0414391 -0.229764 0.121878 0.0427741 -0.229749 0.121943 0.0427574 -0.229776 0.116466 0.0484627 -0.229764 0.116517 0.0484599 -0.229807 0.116466 0.0483435 -0.230491 0.115097 0.0470536 -0.230964 0.114313 0.0460063 -0.23136 0.113941 0.0448538 -0.231409 0.113919 0.0446876 -0.231533 0.113897 0.044237 -0.231706 0.113976 0.0434898 -0.231498 0.0906758 0.0587056 -0.232755 0.0954982 0.0530034 -0.23191 0.0883222 0.0582866 -0.232755 0.0863005 0.0564669 -0.229776 0.0931833 0.0628351 -0.230491 0.0925371 0.06098 -0.229807 0.0930766 0.0627819 -0.229744 0.0932901 0.0628881 -0.229776 0.0856267 0.0651003 -0.229744 0.0855666 0.0652034 -0.229744 0.0775837 0.0665896 -0.229807 0.0856865 0.0649972 -0.230491 0.0851458 0.0631956 -0.229764 0.0856726 0.0651236 -0.231409 0.0853091 0.0605579 -0.232755 0.0766581 0.0583694 -0.23136 0.0852449 0.0607127 -0.231706 0.0859572 0.0595489 -0.231808 0.0863702 0.0591491 -0.230658 0.0587241 0.0635233 -0.229784 0.0582094 0.0658709 -0.229776 0.0582773 0.065906 -0.229749 0.0582798 0.0659798 -0.229776 0.0506005 0.0640894 -0.229807 0.0507038 0.06403 -0.230491 0.0511364 0.0621995 -0.230964 0.0516511 0.0609965 -0.23136 0.0524637 0.0600988 -0.231739 0.0538214 0.0593981 -0.232755 0.0523433 0.0560632 -0.232755 0.0570965 0.0573272 -0.231928 0.0557673 0.0593534 -0.23189 0.0565936 0.0596493 -0.229776 0.0265124 0.0511124 -0.229764 0.0264609 0.0511127 -0.229744 0.020653 0.0457004 -0.229749 0.0207094 0.0457394 -0.229776 0.0207723 0.0457008 -0.229764 0.0207751 0.0457522 -0.229807 0.0208915 0.0457011 -0.229784 0.0208389 0.0457383 -0.231409 0.0245474 0.0431545 -0.232755 0.0310029 0.0441842 -0.231907 0.0271062 0.0437793 -0.232755 0.0274242 0.0408103 -0.231118 0.00977142 0.0208995 -0.229807 0.00423776 0.0149216 -0.229764 0.00411141 0.0149077 -0.229776 0.00413464 0.0148618 -0.229744 0.00350171 0.0123549 -0.230491 0.00603934 0.0143809 -0.230964 0.00733852 0.0142252 -0.23136 0.00852227 0.01448 -0.231706 0.00968608 0.0151923 -0.231907 0.0105807 0.0163646 -0.231808 0.0100859 0.0156053 -0.231739 0.00980799 0.0153055 -0.232755 0.012768 0.0155356 -0.231768 0.0109255 0.0187668 -0.230491 0.00825503 0.0217721 -0.229744 0.00656812 0.0231212 -0.229807 0.0064531 0.0223117 -0.229776 0.0063999 0.0224184 -0.229764 0.00635521 0.0223929 -0.229744 0.00634686 0.0225252 -0.229749 0.00633718 0.0224574 -0.232755 0.0108656 0.00589319 -0.229755 0.00339558 0.0116448 -0.230835 0.00609573 0.00986661 -0.230627 0.00558201 0.0102565 -0.230209 0.00452912 0.0109093 -0.229763 0.00342114 0.0116579 -0.232755 0.0162316 0.0247333 -0.232755 0.0211618 0.0332355 -0.230491 0.0221814 0.044332 -0.229744 0.0177609 0.0424233 -0.231482 0.0288363 0.0469333 -0.231118 0.0286727 0.0481112 -0.232755 0.0432305 0.052382 -0.229744 0.0419465 0.0609371 -0.232755 0.0477108 0.054411 -0.229744 0.066394 0.0669192 -0.232755 0.0717521 0.0587172 -0.229744 0.0990427 0.0604777 -0.232755 0.0998513 0.0507141 -0.229744 0.108727 0.0548622 -0.232755 0.104 0.0480732 -0.231118 0.118876 0.0405623 -0.229744 0.131702 0.0272885 -0.230491 0.132964 0.0180986 -0.233273 0.126126 -0.00241824 -0.233273 0.124866 -0.0127032 -0.230673 0.121738 -0.0225815 -0.233273 0.121738 -0.0225815 -0.230673 0.116849 -0.031717 -0.233273 0.116849 -0.031717 -0.230673 0.110364 -0.0397984 -0.233273 0.110364 -0.0397984 -0.233273 0.0935374 -0.0517435 -0.230673 0.0735324 -0.0568037 -0.233273 0.0837693 -0.0552005 -0.230673 0.0631751 -0.0564987 -0.233273 0.0631751 -0.0564987 -0.230673 0.0435027 -0.0502697 -0.230673 0.0348574 -0.0445579 -0.233273 0.0274088 -0.0373548 -0.236073 0.124866 -0.0127032 -0.236073 0.116849 -0.031717 -0.236073 0.110364 -0.0397984 -0.236673 0.116849 -0.031717 -0.236673 0.0631751 -0.0564987 -0.236073 0.0530503 -0.0542956 -0.236673 0.0530503 -0.0542956 -0.236673 0.0214106 -0.0289057 -0.236073 0.0170671 -0.0194983 -0.236673 0.0170671 -0.0194983 -0.228873 0.11618 -0.00212528 -0.228873 0.115027 -0.0111084 -0.228873 0.112144 -0.019694 -0.230473 0.112144 -0.019694 -0.228873 0.107641 -0.0275522 -0.230473 0.101692 -0.034381 -0.228873 0.0776751 -0.046323 -0.230473 0.0776751 -0.046323 -0.230473 0.0686397 -0.0469449 -0.228873 0.0596565 -0.0457922 -0.228873 0.0510709 -0.0429091 -0.230473 0.0363839 -0.0324573 -0.230473 0.0268147 -0.0171805 -0.228873 0.0244419 -0.00844007 -0.230473 0.0244419 -0.00844007 -0.237673 0.128824 -0.00249774 -0.233695 0.124566 0.0212777 -0.233695 0.1262 0.0166964 -0.233695 0.12745 0.0119958 -0.233695 0.122559 0.0257085 -0.237673 0.12181 0.0271467 -0.233695 0.116176 0.0357193 -0.233695 0.117485 0.0339984 -0.233695 0.12181 0.0271467 -0.233695 0.111116 0.04134 -0.237673 0.116176 0.0357193 -0.237673 0.109139 0.0431834 -0.237673 0.0917474 0.0539193 -0.237673 0.100913 0.0493121 -0.233695 0.0995212 0.0501449 -0.233695 0.0813913 0.056972 -0.233695 0.0819212 0.0568649 -0.233695 0.0861203 0.0558341 -0.233695 0.0907391 0.0543096 -0.233695 0.0917474 0.0539193 -0.233695 0.0765845 0.0577155 -0.233695 0.0614916 0.0574667 -0.237673 0.0614916 0.0574667 -0.233695 0.0515091 0.0551046 -0.233695 0.0420883 0.0510449 -0.233695 0.0479573 0.053801 -0.233695 0.0352366 0.0467201 -0.237673 0.0335157 0.045411 -0.237673 0.0260516 0.0383741 -0.233695 0.0278949 0.0403506 -0.233695 0.0199228 0.0301479 -0.233695 0.0217018 0.0328596 -0.237673 0.0199228 0.0301479 -0.233695 0.01237 0.0111562 -0.237673 0.0153157 0.0209825 -0.233695 0.0149254 0.0199742 -0.233695 0.0153157 0.0209825 -0.233695 0.0111755 0.000967798 -0.236873 0.123569 -0.022069 -0.237673 0.119056 -0.0310475 -0.236873 0.10574 -0.0459994 -0.236873 0.0973424 -0.0515184 -0.237673 0.0881138 -0.0554953 -0.237673 0.0783348 -0.0578093 -0.236873 0.0583218 -0.0572198 -0.236873 0.048696 -0.0543342 -0.237673 0.0397174 -0.049821 -0.237673 0.031659 -0.0438172 -0.236873 0.0192465 -0.0281075 -0.237673 0.0192465 -0.0281075 -0.236873 0.0152696 -0.0188788 -0.237673 0.0152696 -0.0188788 -0.237673 0.0129556 -0.0090998 -0.236873 0.0129556 -0.0090998 -0.230673 0.120478 -0.00225188 -0.230673 0.119892 0.00704876 -0.236673 0.117607 0.0160833 -0.230673 0.117607 0.0160833 -0.236673 0.101606 0.0386214 -0.236673 0.093831 0.0437584 -0.230673 0.093831 0.0437584 -0.230673 0.0852441 0.0473793 -0.230673 0.0761381 0.0493606 -0.236673 0.0761381 0.0493606 -0.230673 0.048831 0.045084 -0.236673 0.0407667 0.0404135 -0.236673 0.0278654 0.0270725 -0.236673 0.0234677 0.0188563 -0.230673 0.0206546 0.00997195 -0.236673 0.0206546 0.00997195 -0.238273 0.119837 -0.002233 -0.238273 0.119166 0.00751794 -0.236973 0.116605 0.0169506 -0.238273 0.116605 0.0169506 -0.236973 0.112254 0.0257024 -0.238273 0.112254 0.0257024 -0.236973 0.106278 0.0334371 -0.238273 0.0904281 0.0447167 -0.238273 0.0811625 0.0478281 -0.236973 0.071468 0.0490721 -0.236973 0.061717 0.0484009 -0.236973 0.0522844 0.0458403 -0.238273 0.0435326 0.0414887 -0.236973 0.0435326 0.0414887 -0.236973 0.0357978 0.0355132 -0.238273 0.0245183 0.0196632 -0.236973 0.0245183 0.0196632 -0.236973 0.0214068 0.0103976 -0.238273 0.0201628 0.000703061 -0.238173 0.116782 -0.0115114 -0.230673 0.113786 -0.0204315 -0.230673 0.102927 -0.0356907 -0.238173 0.109108 -0.0285959 -0.238173 0.102927 -0.0356907 -0.238173 0.0954807 -0.0414434 -0.230673 0.0779741 -0.048098 -0.238173 0.0779741 -0.048098 -0.230673 0.0503334 -0.0445511 -0.238173 0.0592535 -0.0475465 -0.238173 0.0503334 -0.0445511 -0.238173 0.042169 -0.039873 -0.230673 0.0350742 -0.033692 -0.238173 0.0293215 -0.0262457 -0.230673 0.0220208 0.000648333 -0.238173 0.022667 -0.0087391 -0.233695 0.128824 -0.00249774 -0.233299 0.128906 -0.00250015 -0.233695 0.127737 -0.0121563 -0.233695 0.12763 -0.0126862 -0.233695 0.126599 -0.0168853 -0.233299 0.125151 -0.021533 -0.233695 0.125075 -0.0215041 -0.233299 0.118365 -0.0344363 -0.233695 0.115356 -0.0382631 -0.233299 0.115419 -0.0383152 -0.233299 0.112163 -0.0419377 -0.233695 0.108566 -0.0452171 -0.233695 0.106484 -0.0469409 -0.233299 0.0965102 -0.0533973 -0.233299 0.0874856 -0.0570429 -0.233695 0.0827608 -0.0582148 -0.233299 0.0827785 -0.0582947 -0.233695 0.077973 -0.0590724 -0.233299 0.0779841 -0.0591534 -0.233695 0.0731308 -0.0595316 -0.233695 0.0682672 -0.0595895 -0.233695 0.0634154 -0.0592454 -0.233695 0.0580788 -0.0583949 -0.233299 0.0585928 -0.0585822 -0.233695 0.0492608 -0.0558396 -0.233299 0.049232 -0.0559161 -0.233695 0.0482525 -0.0554493 -0.233695 0.0447836 -0.0539388 -0.233299 0.0447486 -0.0540127 -0.233695 0.0404787 -0.0516749 -0.233695 0.0390871 -0.0508421 -0.233695 0.0325018 -0.0461215 -0.233299 0.0324497 -0.0461845 -0.233695 0.023824 -0.0372492 -0.233299 0.0224489 -0.0355766 -0.233695 0.0198063 -0.0314883 -0.233299 0.0197366 -0.031531 -0.233299 0.0173676 -0.0272752 -0.233299 0.0153582 -0.0228383 -0.233695 0.0141304 -0.0192559 -0.232967 0.129138 -0.00250698 -0.232755 0.129482 -0.00251711 -0.232755 0.129134 -0.00742313 -0.232967 0.128792 -0.00738461 -0.232755 0.128382 -0.0122837 -0.232755 0.127232 -0.0170655 -0.232967 0.126901 -0.0169712 -0.232755 0.123768 -0.0262633 -0.232755 0.121479 -0.0306163 -0.232755 0.118838 -0.0347655 -0.232967 0.112329 -0.0420998 -0.232967 0.108771 -0.0454541 -0.232755 0.108997 -0.0457141 -0.232755 0.105152 -0.048781 -0.232967 0.100887 -0.0512262 -0.232755 0.101067 -0.0515198 -0.232967 0.0966145 -0.0536045 -0.232967 0.0921602 -0.0556218 -0.232967 0.0875544 -0.0572644 -0.232755 0.0876566 -0.0575932 -0.232967 0.0780155 -0.0593832 -0.232755 0.0780622 -0.0597243 -0.232967 0.0731475 -0.0598449 -0.232967 0.068258 -0.0599031 -0.232967 0.0633803 -0.0595572 -0.232755 0.0584813 -0.0591475 -0.232755 0.0536994 -0.0579969 -0.232967 0.0491502 -0.0561332 -0.232755 0.0401486 -0.0522441 -0.232755 0.0284247 -0.0433407 -0.232967 0.0286652 -0.0430945 -0.232967 0.0253108 -0.0395365 -0.232967 0.0171604 -0.0273796 -0.232755 0.016853 -0.0275344 -0.232967 0.0122438 -0.0135938 -0.232755 0.0131718 -0.0184216 -0.233299 0.128562 -0.00735866 -0.233299 0.127817 -0.0121721 -0.232967 0.128045 -0.012217 -0.233299 0.126678 -0.0169077 -0.232967 0.125368 -0.0216147 -0.232967 0.123457 -0.0261158 -0.233299 0.123248 -0.0260164 -0.233299 0.120981 -0.0303273 -0.232967 0.121181 -0.0304436 -0.232967 0.118556 -0.0345688 -0.232967 0.115598 -0.038463 -0.233299 0.108619 -0.0452789 -0.233299 0.104812 -0.048316 -0.232967 0.104949 -0.0485032 -0.233299 0.100766 -0.0510283 -0.233299 0.0920733 -0.0554067 -0.232967 0.0828288 -0.0585211 -0.233299 0.0731351 -0.0596133 -0.233299 0.0682648 -0.0596712 -0.233299 0.0634063 -0.0593267 -0.232967 0.0585479 -0.0588098 -0.233299 0.0538573 -0.0574427 -0.232967 0.0537937 -0.0576658 -0.232967 0.0446492 -0.0542223 -0.233299 0.0404376 -0.0517456 -0.232967 0.0403213 -0.0519463 -0.233299 0.0363287 -0.0491302 -0.232967 0.0361961 -0.0493206 -0.232967 0.0323019 -0.0463633 -0.233299 0.0288272 -0.0429285 -0.233299 0.025486 -0.0393845 -0.232967 0.0222617 -0.0357137 -0.232967 0.0195387 -0.0316521 -0.232967 0.0151431 -0.0229252 -0.232967 0.0135005 -0.0183195 -0.233299 0.013722 -0.0182506 -0.233695 0.0125501 -0.0135258 -0.233299 0.0124703 -0.0135435 -0.233695 0.0117683 -0.00927329 -0.233695 0.0116926 -0.00873803 -0.232967 0.01092 -0.0039125 -0.232967 0.0113817 -0.00878054 -0.233299 0.0111516 -0.00390016 -0.233299 0.0116115 -0.00874911 -0.233695 0.0112333 -0.00389581 -0.233773 0.127625 -0.00246241 -0.233773 0.126455 -0.0124431 -0.235573 0.126958 -0.00967135 -0.235573 0.126455 -0.0124431 -0.233773 0.125222 -0.017319 -0.235573 0.125392 -0.0167398 -0.233773 0.121509 -0.0266568 -0.235573 0.123569 -0.022069 -0.235573 0.119679 -0.0300135 -0.233773 0.119056 -0.0310475 -0.233773 0.113052 -0.0391059 -0.235573 0.115622 -0.0360094 -0.235573 0.113052 -0.0391059 -0.233773 0.10574 -0.0459994 -0.235573 0.0994438 -0.0503289 -0.233773 0.101662 -0.0489422 -0.235573 0.0973424 -0.0515184 -0.233773 0.0928149 -0.0537083 -0.235573 0.0929996 -0.0536284 -0.233773 0.0881138 -0.0554953 -0.235573 0.0881138 -0.0554953 -0.235573 0.0861927 -0.0560941 -0.233773 0.0783348 -0.0578093 -0.235573 0.0719242 -0.0583829 -0.233773 0.0683025 -0.05839 -0.235573 0.0583218 -0.0572198 -0.233773 0.0583218 -0.0572198 -0.235573 0.0575347 -0.0570512 -0.233773 0.048696 -0.0543342 -0.233773 0.0441082 -0.0522736 -0.233773 0.0397174 -0.049821 -0.235573 0.0397174 -0.049821 -0.233773 0.0355572 -0.046995 -0.233773 0.031659 -0.0438172 -0.235573 0.0376897 -0.0485098 -0.233773 0.0280527 -0.0403117 -0.233773 0.0247656 -0.0365053 -0.235573 0.0247656 -0.0365053 -0.233773 0.0124463 -0.00409634 -0.235573 0.0137632 -0.0134516 -0.235573 0.0152696 -0.0188788 -0.233773 0.0138991 -0.0140398 -0.233773 0.0152696 -0.0188788 -0.235573 0.0157967 -0.0203999 -0.235573 0.018685 -0.0270386 -0.233773 0.0192465 -0.0281075 -0.235573 0.0223826 -0.0332628 -0.23585 0.0188499 -0.0269542 -0.235833 0.0125249 0.000928049 -0.23585 0.126775 -0.00964274 -0.23585 0.0159708 -0.0203368 -0.235785 0.0138489 -0.0134323 -0.23585 0.0139439 -0.0134109 -0.235785 0.122873 -0.0235216 -0.235785 0.115552 -0.0359556 -0.235785 0.119604 -0.0299689 -0.23585 0.115475 -0.0358961 -0.235873 0.115384 -0.0358259 -0.23585 0.110714 -0.0413187 -0.235785 0.110783 -0.0413874 -0.235785 0.10537 -0.0461785 -0.235785 0.0929646 -0.0535478 -0.235873 0.0992906 -0.050071 -0.23585 0.0993492 -0.0501697 -0.235688 0.0861863 -0.0560722 -0.235573 0.0791304 -0.0576873 -0.235873 0.0790829 -0.0573911 -0.23585 0.071918 -0.0581978 -0.235785 0.0646957 -0.0580822 -0.235873 0.0719142 -0.058083 -0.235785 0.0575537 -0.0569654 -0.235688 0.0505862 -0.0550236 -0.235688 0.0575397 -0.0570289 -0.235573 0.0505785 -0.0550451 -0.23585 0.0506409 -0.0548707 -0.235785 0.0506081 -0.0549623 -0.235688 0.0319756 -0.0440667 -0.235688 0.0268483 -0.0389595 -0.235873 0.0321584 -0.0438584 -0.23585 0.0320827 -0.0439447 -0.235873 0.0270558 -0.0387758 -0.23585 0.0269698 -0.0388519 -0.235785 0.0224552 -0.0332133 -0.235785 0.0187632 -0.0269985 -0.235688 0.0158182 -0.0203921 -0.235688 0.0187054 -0.0270281 -0.235723 0.127585 -0.00246122 -0.235688 0.127602 -0.00246173 -0.235785 0.125308 -0.0167155 -0.235785 0.126871 -0.00965778 -0.235688 0.12537 -0.0167335 -0.235688 0.126935 -0.00966782 -0.235573 0.122953 -0.0235564 -0.235688 0.122932 -0.0235474 -0.235873 0.126661 -0.009625 -0.23585 0.125214 -0.0166885 -0.235873 0.125104 -0.0166567 -0.23585 0.122783 -0.0234832 -0.235688 0.11966 -0.0300019 -0.235688 0.115604 -0.0359954 -0.235573 0.119056 -0.0310475 -0.235573 0.110845 -0.0414494 -0.235688 0.110829 -0.0414333 -0.23585 0.11952 -0.0299195 -0.235573 0.105424 -0.0462478 -0.235688 0.10541 -0.0462298 -0.23585 0.10531 -0.0461017 -0.235785 0.0993989 -0.0502534 -0.235688 0.0994321 -0.0503093 -0.235688 0.0929905 -0.0536074 -0.23585 0.0929257 -0.0534585 -0.23585 0.0861407 -0.0559164 -0.235785 0.086168 -0.0560098 -0.235688 0.0791268 -0.0576648 -0.235785 0.0791165 -0.0576006 -0.235573 0.0783348 -0.0578093 -0.235873 0.0928799 -0.0533533 -0.23585 0.0791011 -0.0575045 -0.235785 0.0719212 -0.058295 -0.235688 0.0646897 -0.0581469 -0.235688 0.0719234 -0.05836 -0.235573 0.0683025 -0.05839 -0.235573 0.0646876 -0.0581697 -0.23585 0.0647046 -0.0579853 -0.23585 0.0575748 -0.0568704 -0.235688 0.0439389 -0.0521625 -0.235573 0.048696 -0.0543342 -0.235573 0.0439285 -0.0521829 -0.23585 0.0440123 -0.0520177 -0.235785 0.0439683 -0.0521045 -0.235688 0.0377025 -0.0484909 -0.235785 0.037739 -0.0484371 -0.235573 0.0319605 -0.0440838 -0.235573 0.0268312 -0.0389746 -0.235873 0.0378579 -0.0482614 -0.23585 0.0377935 -0.0483565 -0.235785 0.0320185 -0.0440178 -0.235785 0.026897 -0.0389164 -0.235573 0.0192465 -0.0281075 -0.235688 0.0224015 -0.03325 -0.23585 0.0225356 -0.0331584 -0.235873 0.0226304 -0.0330937 -0.235785 0.0158793 -0.02037 -0.235688 0.0137855 -0.0134466 -0.235573 0.0126166 -0.00630325 -0.235573 0.0129556 -0.0090998 -0.235873 0.0140559 -0.0133856 -0.235785 0.0127041 -0.00629481 -0.235688 0.0126393 -0.00630105 -0.23585 0.0128009 -0.00628546 -0.235723 0.0124151 0.000931282 -0.233561 0.0124628 0.000929878 -0.233513 0.012596 -0.00408768 -0.233513 0.127109 -0.00746083 -0.233773 0.127258 -0.0074783 -0.233658 0.127602 -0.00246173 -0.233623 0.126415 -0.012435 -0.233623 0.125184 -0.0173075 -0.233623 0.123532 -0.0220541 -0.233773 0.123569 -0.022069 -0.233773 0.11623 -0.0352078 -0.233623 0.113022 -0.0390792 -0.233773 0.109547 -0.0427123 -0.233623 0.105715 -0.0459678 -0.233773 0.0973424 -0.0515184 -0.233623 0.092799 -0.0536714 -0.233623 0.0881012 -0.0554572 -0.233623 0.0832656 -0.0568267 -0.233623 0.078329 -0.0577695 -0.233773 0.0832748 -0.0568658 -0.233773 0.0733313 -0.0583186 -0.233623 0.0683037 -0.0583498 -0.233773 0.0632866 -0.0580228 -0.233623 0.0632913 -0.0579828 -0.233773 0.0534459 -0.0559871 -0.233623 0.0441262 -0.0522377 -0.233623 0.0316857 -0.0437872 -0.233773 0.0218227 -0.0324269 -0.233623 0.0192819 -0.0280884 -0.233773 0.0170566 -0.02358 -0.233623 0.0170935 -0.023564 -0.233623 0.0153078 -0.0188662 -0.233623 0.0139383 -0.0140306 -0.233623 0.0129954 -0.00909399 -0.233773 0.0129556 -0.0090998 -0.233623 0.0124864 -0.00409402 -0.233623 0.0124151 0.000931282 -0.233513 0.0131041 -0.00907811 -0.233513 0.0171944 -0.0235206 -0.233623 0.0218563 -0.0324048 -0.233513 0.0219481 -0.0323445 -0.233623 0.0247971 -0.0364804 -0.233623 0.0280819 -0.0402842 -0.233623 0.0355812 -0.0469628 -0.233623 0.0397385 -0.0497868 -0.233513 0.0397962 -0.0496933 -0.233623 0.0487108 -0.0542969 -0.233623 0.0534575 -0.0559486 -0.233513 0.053489 -0.0558434 -0.233623 0.05833 -0.0571804 -0.233513 0.0683069 -0.05824 -0.233623 0.073329 -0.0582785 -0.233513 0.0733227 -0.0581689 -0.233513 0.0832403 -0.0567198 -0.233513 0.0880667 -0.0553529 -0.233513 0.0927556 -0.0535706 -0.233623 0.0973234 -0.051483 -0.233513 0.0972713 -0.0513864 -0.233623 0.10164 -0.0489086 -0.233513 0.101579 -0.0488169 -0.233623 0.109519 -0.042683 -0.233623 0.116198 -0.0351838 -0.233513 0.11611 -0.0351182 -0.233623 0.119022 -0.0310264 -0.233623 0.121473 -0.0266387 -0.233513 0.118928 -0.0309687 -0.233513 0.125078 -0.0172759 -0.233623 0.127218 -0.00747362 -0.233496 0.12744 -0.00245695 -0.233513 0.126308 -0.0124127 -0.233513 0.12343 -0.0220135 -0.233513 0.121375 -0.0265894 -0.233473 0.118801 -0.0308899 -0.233473 0.109341 -0.042494 -0.233513 0.11294 -0.0390062 -0.233513 0.109444 -0.0426031 -0.233473 0.105554 -0.045764 -0.233513 0.105647 -0.0458817 -0.233473 0.101497 -0.0486915 -0.233473 0.0926962 -0.0534328 -0.233473 0.0880195 -0.0552105 -0.233473 0.0832057 -0.0565738 -0.233473 0.0782914 -0.0575124 -0.233513 0.0783131 -0.0576609 -0.233473 0.0633216 -0.0577248 -0.233513 0.0633041 -0.0578738 -0.233513 0.0583522 -0.0570729 -0.233473 0.0488068 -0.0540554 -0.233513 0.0487514 -0.0541948 -0.233513 0.0441755 -0.0521396 -0.233473 0.039875 -0.0495657 -0.233513 0.0356468 -0.0468747 -0.233513 0.0317588 -0.0437052 -0.233473 0.0318585 -0.0435932 -0.233513 0.0281618 -0.0402088 -0.233513 0.0248832 -0.0364123 -0.233513 0.0193786 -0.0280363 -0.233473 0.0195106 -0.0279652 -0.233513 0.015412 -0.0188317 -0.233513 0.0140451 -0.0140053 -0.233473 0.0127458 -0.00407901 -0.236073 0.0145262 -0.00945291 -0.236073 0.0214106 -0.0289057 -0.236073 0.0274088 -0.0373548 -0.236073 0.0348574 -0.0445579 -0.235873 0.0272571 -0.0374851 -0.235873 0.0347322 -0.0447139 -0.236073 0.0435027 -0.0502697 -0.235873 0.0434083 -0.050446 -0.236073 0.0631751 -0.0564987 -0.235873 0.0631508 -0.0566972 -0.236073 0.0735324 -0.0568037 -0.236073 0.0837693 -0.0552005 -0.236073 0.0935374 -0.0517435 -0.236073 0.102504 -0.0465505 -0.236073 0.121738 -0.0225815 -0.235873 0.125062 -0.0127457 -0.233473 0.126326 -0.00242413 -0.233473 0.125062 -0.0127457 -0.233473 0.117015 -0.0318272 -0.233273 0.102504 -0.0465505 -0.233473 0.0936212 -0.0519251 -0.233473 0.0838184 -0.0553944 -0.233273 0.0735324 -0.0568037 -0.233473 0.0735449 -0.0570034 -0.233273 0.0530503 -0.0542956 -0.233473 0.0529899 -0.0544863 -0.233273 0.0435027 -0.0502697 -0.233273 0.0348574 -0.0445579 -0.233473 0.0272571 -0.0374851 -0.233273 0.0214106 -0.0289057 -0.233273 0.0170671 -0.0194983 -0.233273 0.0145262 -0.00945291 -0.226573 0.0563366 0.0618912 -0.224773 0.0563366 0.0618912 -0.224773 0.054928 0.0611323 -0.224773 0.0541346 0.0613701 -0.226573 0.0541346 0.0613701 -0.226573 0.0535665 0.0619728 -0.224773 0.0533758 0.0627787 -0.226573 0.0542623 -0.0633554 -0.226573 0.0517681 -0.0603098 -0.23092 0.0521302 -0.060395 -0.23089 0.0526885 -0.0606271 -0.230657 0.0503325 -0.0604152 -0.230454 0.0497509 -0.0606764 -0.230138 0.049116 -0.0611723 -0.229996 0.0489005 -0.0614188 -0.226573 0.0491184 -0.0611699 -0.226573 0.0483899 -0.0624056 -0.229483 0.0483899 -0.0624056 -0.230738 0.0254268 -0.0447727 -0.2308 0.0253407 -0.044496 -0.226573 0.0243568 -0.0431511 -0.23092 0.0247093 -0.0434712 -0.226573 0.0252347 -0.0442425 -0.230773 0.0235931 -0.0427226 -0.230637 0.023074 -0.0425763 -0.230454 0.0225081 -0.0425252 -0.226573 0.0216801 -0.042646 -0.229996 0.0214004 -0.042743 -0.23087 0.00950208 -0.0158782 -0.23089 0.00950215 -0.0157039 -0.23092 0.009424 -0.0151043 -0.226573 0.0092319 -0.0145428 -0.230614 0.00839498 -0.0134614 -0.230773 0.0104601 0.0184458 -0.226573 0.0102591 0.0191442 -0.230579 0.0102573 0.0191484 -0.226573 0.00949892 0.0202065 -0.229996 0.00934607 0.0203345 -0.229996 0.0280219 0.0478346 -0.226573 0.0903356 0.06169 -0.226573 0.0900978 0.0608967 -0.226573 0.0886892 0.0601378 -0.226573 0.0878959 0.0603756 -0.224773 0.119076 0.0439481 -0.224773 0.118236 0.0425866 -0.226573 0.118839 0.0431548 -0.224773 0.11743 0.0423959 -0.226573 0.11743 0.0423959 -0.224773 0.116637 0.0426338 -0.224773 0.116069 0.0432364 -0.226573 0.116637 0.0426338 -0.224773 0.115878 0.0440424 -0.226573 0.134457 0.0129801 -0.224773 0.133095 0.0127112 -0.224773 0.134101 -0.0195484 -0.226573 0.134101 -0.0195484 -0.224773 0.133261 -0.0209099 -0.224773 0.132455 -0.0211006 -0.226573 0.133261 -0.0209099 -0.224773 0.131662 -0.0208628 -0.224773 0.131093 -0.0202602 -0.226573 0.131093 -0.0202602 -0.224773 0.116122 -0.0490826 -0.226573 0.115519 -0.0496508 -0.224773 0.115519 -0.0496508 -0.224773 0.114713 -0.0498415 -0.224773 0.11392 -0.0496037 -0.226573 0.114713 -0.0498415 -0.224773 0.113352 -0.049001 -0.226573 0.113352 -0.049001 -0.224773 0.0866241 -0.0643087 -0.226573 0.0866241 -0.0643087 -0.226573 0.0863863 -0.065102 -0.224773 0.0857837 -0.0656701 -0.224773 0.0849777 -0.0658609 -0.224773 0.0834255 -0.0642144 -0.224773 0.0515735 -0.0648367 -0.224773 0.0508618 -0.0648158 -0.226573 0.0498022 -0.0639185 -0.224773 0.0498022 -0.0639185 -0.224773 0.0496643 -0.0632199 -0.226573 0.0496643 -0.0632199 -0.224773 0.0238842 -0.0463656 -0.226573 0.0238842 -0.0463656 -0.226573 0.0224756 -0.0471245 -0.226573 0.0216823 -0.0468867 -0.226573 0.0211142 -0.046284 -0.224773 0.00810268 -0.015837 -0.226573 0.00810268 -0.015837 -0.224773 0.00786486 -0.0166303 -0.224773 0.00509478 -0.0165487 -0.224773 0.00490407 -0.0157427 -0.226573 0.00509478 -0.0165487 -0.226573 0.00490407 -0.0157427 -0.226573 0.00885935 0.0171309 -0.224773 0.00745076 0.0163721 -0.224773 0.0268391 0.0466651 -0.224773 0.0259986 0.0453036 -0.226573 0.0259986 0.0453036 -0.226573 0.0243993 0.0453508 -0.226573 0.0238311 0.0459534 -0.226374 0.0539201 -0.06699 -0.2263 0.0541069 -0.0671113 -0.228784 0.0535555 -0.0661879 -0.22876 0.0536447 -0.0666312 -0.226573 0.0536965 -0.0667301 -0.22875 0.0537568 -0.0668198 -0.228743 0.0539201 -0.0669899 -0.226361 0.0229733 -0.0501066 -0.228744 0.0229451 -0.050029 -0.22874 0.00459449 -0.020086 -0.226573 0.00617772 0.021598 -0.226573 0.00655759 0.0213852 -0.228792 0.0064344 0.0214311 -0.2288 0.00655759 0.0213852 -0.226324 0.00584517 0.0223725 -0.228793 0.0260613 0.0502229 -0.228774 0.0259071 0.0505214 -0.226573 0.0259244 0.0504717 -0.238273 0.0214068 0.0103976 -0.238273 0.0293775 0.0281437 -0.238473 0.0295405 0.0280277 -0.238273 0.0357978 0.0355132 -0.238273 0.0522844 0.0458403 -0.238473 0.0523555 0.0456534 -0.238273 0.061717 0.0484009 -0.238473 0.0617503 0.0482037 -0.238273 0.071468 0.0490721 -0.238473 0.0811177 0.0476332 -0.238473 0.0903461 0.0445343 -0.238273 0.0989086 0.0398575 -0.238273 0.106278 0.0334371 -0.238473 0.119637 -0.00222711 -0.236673 0.124866 -0.0127032 -0.236673 0.121738 -0.0225815 -0.236673 0.110364 -0.0397984 -0.236873 0.117015 -0.0318272 -0.236673 0.102504 -0.0465505 -0.236673 0.0935374 -0.0517435 -0.236873 0.10262 -0.0467136 -0.236673 0.0837693 -0.0552005 -0.236673 0.0735324 -0.0568037 -0.236673 0.0435027 -0.0502697 -0.236673 0.0348574 -0.0445579 -0.236673 0.0274088 -0.0373548 -0.236873 0.0347322 -0.0447139 -0.236873 0.0272571 -0.0374851 -0.236673 0.0145262 -0.00945291 -0.236673 0.0138743 0.0008883 -0.237673 0.126455 -0.0124431 -0.237873 0.126651 -0.0124836 -0.237673 0.123569 -0.022069 -0.237673 0.113052 -0.0391059 -0.237673 0.10574 -0.0459994 -0.237873 0.105864 -0.0461563 -0.237673 0.0973424 -0.0515184 -0.237873 0.0881766 -0.0556852 -0.237873 0.0682966 -0.0585899 -0.237673 0.0683025 -0.05839 -0.237673 0.0583218 -0.0572198 -0.237873 0.0582813 -0.0574156 -0.237673 0.048696 -0.0543342 -0.237873 0.0396124 -0.0499912 -0.237873 0.031526 -0.0439666 -0.237673 0.0247656 -0.0365053 -0.237673 0.012375 0.000932466 -0.237873 0.0127578 -0.00912871 -0.237673 0.0111755 0.000967798 -0.237673 0.01237 0.0111562 -0.237873 0.0125659 0.0111157 -0.237873 0.0155015 0.0209085 -0.237873 0.0262009 0.038241 -0.237873 0.0336397 0.0452541 -0.237673 0.0420883 0.0510449 -0.237673 0.0515091 0.0551046 -0.237873 0.0615206 0.0572688 -0.237673 0.0717327 0.0580595 -0.237673 0.0819212 0.0568649 -0.237873 0.0818807 0.0566691 -0.237873 0.0916735 0.0537335 -0.237873 0.100808 0.049142 -0.237873 0.109006 0.043034 -0.237873 0.121634 0.0270518 -0.237673 0.12587 0.0177259 -0.237673 0.128232 0.00774335 -0.228873 0.0268147 -0.0171805 -0.228673 0.0266277 -0.0172516 -0.228673 0.0306775 -0.0253963 -0.228873 0.030847 -0.0252901 -0.228873 0.0363839 -0.0324573 -0.228673 0.0362384 -0.0325945 -0.228873 0.0432127 -0.0384065 -0.228873 0.0686397 -0.0469449 -0.228673 0.0777083 -0.0465202 -0.228873 0.0864155 -0.0439503 -0.228873 0.0945251 -0.039918 -0.228673 0.0946313 -0.0400875 -0.228873 0.101692 -0.034381 -0.228673 0.112327 -0.019776 -0.228673 0.115222 -0.0111532 -0.228673 0.11638 -0.00213116 -0.230473 0.115027 -0.0111084 -0.230673 0.115222 -0.0111532 -0.230673 0.112327 -0.019776 -0.230473 0.107641 -0.0275522 -0.230673 0.107804 -0.0276682 -0.230673 0.101829 -0.0345265 -0.230473 0.0945251 -0.039918 -0.230673 0.0946313 -0.0400875 -0.230473 0.0864155 -0.0439503 -0.230673 0.0864866 -0.0441372 -0.230673 0.0777083 -0.0465202 -0.230673 0.0686338 -0.0471449 -0.230473 0.0596565 -0.0457922 -0.230473 0.0510709 -0.0429091 -0.230673 0.0509889 -0.0430916 -0.230473 0.0432127 -0.0384065 -0.230673 0.0362384 -0.0325945 -0.230673 0.0306775 -0.0253963 -0.230473 0.030847 -0.0252901 -0.230673 0.0266277 -0.0172516 -0.230473 0.02382 0.000595334 -0.238173 0.113786 -0.0204315 -0.238473 0.11406 -0.0205544 -0.238473 0.103133 -0.035909 -0.238173 0.0870551 -0.0456328 -0.238473 0.0871617 -0.0459132 -0.238173 0.0685867 -0.0487442 -0.238473 0.0685778 -0.049044 -0.238473 0.0591864 -0.0478389 -0.238173 0.0350742 -0.033692 -0.238173 0.0251321 -0.0178201 -0.238473 0.0290673 -0.0264049 -0.238473 0.0248517 -0.0179267 -0.238473 0.0223711 -0.00878894 -0.238473 0.0217209 0.000657166 -0.236673 0.0195219 0.000721942 -0.236973 0.0209477 0.00990817 -0.236973 0.0237441 0.0187398 -0.236973 0.0281157 0.0269072 -0.236973 0.0339136 0.0341322 -0.236673 0.0336979 0.0343408 -0.236673 0.048831 0.045084 -0.236973 0.0489567 0.0448116 -0.236673 0.0576161 0.0481931 -0.236673 0.066823 0.049635 -0.236973 0.0576897 0.0479022 -0.236973 0.0668419 0.0493356 -0.236673 0.0852441 0.0473793 -0.236973 0.0851535 0.0470932 -0.236973 0.0936894 0.0434939 -0.236973 0.108078 0.0319476 -0.236673 0.108305 0.0321431 -0.236673 0.1137 0.0245441 -0.236673 0.119892 0.00704876 -0.236973 0.119595 0.00700234 -0.230374 0.133281 -0.00848544 -0.22977 0.134694 0.00548434 -0.225073 0.134227 0.00504854 -0.225073 0.13375 0.00419067 -0.230272 0.133764 0.00423171 -0.230071 0.134122 0.00491496 -0.230374 0.0062776 0.00111207 -0.230374 0.00637446 -0.00474722 -0.225073 0.00637446 -0.00474722 -0.225073 0.00229707 -0.00938942 -0.225073 0.003119 0.0110268 -0.225073 0.00302456 0.0111708 -0.224773 0.00353724 0.0110495 -0.224773 0.00703706 0.00718499 -0.224773 0.0066914 0.0086458 -0.224773 0.00667387 -0.00472848 -0.219257 0.00649206 0.00110576 -0.224473 0.137095 -0.0132045 -0.224473 0.137078 -0.0133596 -0.224773 0.133422 -0.00263318 -0.224773 0.132983 -0.00844911 -0.224773 0.133465 0.00428425 -0.224773 0.134845 0.00593277 -0.224773 0.137257 0.00729539 -0.224473 0.137562 0.00720783 -0.224473 0.137673 0.00745981 -0.224773 0.137385 0.00754342 -0.224473 0.00229707 -0.00938942 -0.221193 0.00307813 0.0110826 -0.224473 0.0030891 0.0110668 -0.221157 0.00320403 0.0109319 -0.221111 0.00337965 0.0107942 -0.221524 0.00296238 0.0113111 -0.224473 0.00292807 0.0114313 -0.224473 0.133622 0.00345624 -0.21984 0.133644 0.00373228 -0.224473 0.133804 0.00434049 -0.224473 0.134279 0.00510886 -0.22022 0.134373 0.00520897 -0.219816 0.133269 -0.00860285 -0.224473 0.133281 -0.00848544 -0.224773 0.0254819 0.0454859 -0.219497 0.0254819 0.0454859 -0.224773 0.0249258 0.0455023 -0.219642 0.0249258 0.0455023 -0.224773 0.0244319 0.0457583 -0.219835 0.0244319 0.0457583 -0.220035 0.0240981 0.0462033 -0.224773 0.0240981 0.0462033 -0.220205 0.0239903 0.046749 -0.224773 0.00860762 0.0173961 -0.219434 0.00860762 0.0173961 -0.224773 0.00774002 0.0167451 -0.219517 0.00824812 0.0169716 -0.219672 0.00774002 0.0167451 -0.224773 0.00718396 0.0167615 -0.224773 0.00669007 0.0170175 -0.220067 0.00669007 0.0170175 -0.220228 0.00635618 0.0174624 -0.224773 0.00761313 -0.0163651 -0.219703 0.00725363 -0.0167897 -0.224773 0.00725363 -0.0167897 -0.224773 0.00569558 -0.0167438 -0.224773 0.00536169 -0.0162988 -0.219735 0.0236325 -0.0461005 -0.224773 0.023273 -0.046525 -0.224773 0.0227649 -0.0467515 -0.219937 0.023273 -0.046525 -0.224773 0.0217149 -0.0464791 -0.220333 0.0217149 -0.0464791 -0.220311 0.0213811 -0.0460341 -0.224773 0.0213811 -0.0460341 -0.224773 0.0515057 -0.0644934 -0.220284 0.0515057 -0.0644934 -0.224773 0.0504558 -0.064221 -0.224773 0.0501219 -0.063776 -0.220003 0.0500141 -0.0632303 -0.220336 0.0853131 -0.0654779 -0.220321 0.0856177 -0.065362 -0.220205 0.0860885 -0.0649182 -0.220276 0.0858837 -0.0651698 -0.224773 0.0856177 -0.065362 -0.224773 0.084988 -0.065511 -0.224773 0.0843682 -0.0653252 -0.224773 0.0839244 -0.0648544 -0.220003 0.0839244 -0.0648544 -0.220311 0.11587 -0.0488175 -0.224773 0.114446 -0.0494521 -0.219735 0.113618 -0.0487511 -0.224773 0.113511 -0.0482054 -0.224773 0.133612 -0.0200766 -0.224773 0.132744 -0.0207277 -0.220097 0.132744 -0.0207277 -0.224773 0.132188 -0.0207113 -0.219903 0.132188 -0.0207113 -0.219703 0.131694 -0.0204553 -0.224773 0.13136 -0.0200103 -0.224773 0.131253 -0.0194645 -0.219538 0.13136 -0.0200103 -0.224773 0.134746 0.0142231 -0.220321 0.134746 0.0142231 -0.224773 0.134247 0.0132601 -0.224773 0.133183 0.01305 -0.219672 0.133183 0.01305 -0.219517 0.132689 0.013306 -0.219434 0.132355 0.0137509 -0.224773 0.132247 0.0142967 -0.219442 0.132247 0.0142967 -0.224773 0.118587 0.04342 -0.224773 0.118227 0.0429954 -0.220035 0.118587 0.04342 -0.219835 0.118227 0.0429954 -0.224773 0.117719 0.0427689 -0.224773 0.117163 0.0427853 -0.224773 0.116669 0.0430413 -0.224773 0.116335 0.0434863 -0.224773 0.0898461 0.0611618 -0.224773 0.0894866 0.0607373 -0.224773 0.0889785 0.0605108 -0.219614 0.0894866 0.0607373 -0.21948 0.0889785 0.0605108 -0.219427 0.0884224 0.0605272 -0.224773 0.0879285 0.0607832 -0.224773 0.0875946 0.0612282 -0.224773 0.0874869 0.0617739 -0.224773 0.0560848 0.0621563 -0.224773 0.0557253 0.0617318 -0.219427 0.0552172 0.0615053 -0.224773 0.0546612 0.0615217 -0.219801 0.0538334 0.0622226 -0.224773 0.0537256 0.0627684 -0.220003 0.0537256 0.0627684 -0.186473 0.0287768 -0.00826596 -0.185973 0.0276183 0.000483447 -0.185973 0.0282849 -0.00835547 -0.185973 0.0349787 -0.0246663 -0.186473 0.0410587 -0.0310637 -0.185973 0.047728 -0.0368443 -0.186473 0.0731509 -0.0425463 -0.186473 0.0898725 -0.0376526 -0.185973 0.0819093 -0.0414581 -0.186473 0.0971076 -0.0327147 -0.185973 0.0901096 -0.0380927 -0.185973 0.097431 -0.033096 -0.186473 0.107759 -0.0189269 -0.185973 0.103554 -0.0266863 -0.185973 0.10821 -0.0191436 -0.185973 0.130161 0.00802527 -0.187973 0.13214 0.00831443 -0.187973 0.119275 0.0381681 -0.187973 0.0932071 0.0575897 -0.185973 0.0823162 0.0587745 -0.187973 0.071849 0.0620078 -0.187973 0.0402149 0.0545224 -0.185973 0.0411635 0.0527616 -0.187973 0.0310669 0.0485103 -0.185973 0.0323068 0.046941 -0.187973 0.0165617 0.0322228 -0.185973 0.0135037 0.0217031 -0.187973 0.00850193 0.0119564 -0.185973 0.0104605 0.0115512 -0.218289 0.132399 -0.00785151 -0.219218 0.132922 -0.0087564 -0.219017 0.132711 -0.00788691 -0.218289 0.132773 -0.00261404 -0.218685 0.13248 -0.00786074 -0.218289 0.131498 -0.0134863 -0.218685 0.128972 -0.0225927 -0.218289 0.128355 -0.0239721 -0.218289 0.126952 -0.0272281 -0.218685 0.124712 -0.0317609 -0.218289 0.123438 -0.0337527 -0.218685 0.122043 -0.0360586 -0.218289 0.121975 -0.0360127 -0.218685 0.119037 -0.0401279 -0.218289 0.115655 -0.0438863 -0.218289 0.112041 -0.0474168 -0.218289 0.108933 -0.0500403 -0.218685 0.104066 -0.0536197 -0.218289 0.108155 -0.0506453 -0.218289 0.099785 -0.0560523 -0.218685 0.099707 -0.0561871 -0.218289 0.0996683 -0.056115 -0.218685 0.0951557 -0.0583958 -0.218289 0.090415 -0.0601541 -0.218289 0.0855749 -0.061603 -0.218289 0.0705781 -0.0635623 -0.218685 0.0655224 -0.0634871 -0.218289 0.0681509 -0.0635377 -0.218289 0.0655282 -0.0634056 -0.218289 0.0572786 -0.062263 -0.218289 0.0555478 -0.0618794 -0.218685 0.0506567 -0.0605977 -0.218289 0.0506818 -0.0605199 -0.218685 0.0459096 -0.0588492 -0.218289 0.0467928 -0.0591197 -0.218685 0.0413184 -0.0567247 -0.218289 0.0459409 -0.0587736 -0.218289 0.0369559 -0.0541684 -0.218289 0.03277 -0.0513393 -0.218289 0.0282339 -0.0476631 -0.218685 0.0287714 -0.0482447 -0.218685 0.0250881 -0.0447768 -0.218289 0.0251465 -0.0447196 -0.218289 0.0217583 -0.0409718 -0.218685 0.0216955 -0.0410241 -0.218289 0.0207247 -0.0396981 -0.218289 0.0186824 -0.0369637 -0.218685 0.0158682 -0.032763 -0.218289 0.0147126 -0.03055 -0.218289 0.0115162 -0.023645 -0.218685 0.0114401 -0.0236748 -0.218289 0.0103804 -0.020497 -0.218685 0.00978797 -0.0188933 -0.218685 0.00852557 -0.0139944 -0.218289 0.00774213 -0.00899921 -0.218289 0.00722719 0.0010841 -0.218685 0.131708 -0.0128603 -0.218685 0.130536 -0.0177815 -0.218685 0.127026 -0.0272625 -0.219017 0.122235 -0.0361888 -0.218685 0.115715 -0.0439424 -0.219017 0.108345 -0.0508945 -0.218685 0.112096 -0.0474775 -0.218685 0.108205 -0.0507102 -0.219017 0.0998166 -0.0563915 -0.219017 0.0952485 -0.0586084 -0.218685 0.0904416 -0.0602314 -0.218685 0.0855952 -0.0616822 -0.218685 0.0806478 -0.0627387 -0.218685 0.0756316 -0.0633941 -0.218685 0.0705789 -0.0636441 -0.219017 0.0655059 -0.0637185 -0.219017 0.0604599 -0.0631535 -0.218685 0.0604949 -0.0629242 -0.218685 0.055529 -0.061959 -0.219017 0.0458207 -0.0590634 -0.218685 0.0369129 -0.054238 -0.218685 0.0327215 -0.0514052 -0.219017 0.0249224 -0.0449392 -0.218685 0.0186156 -0.0370109 -0.219017 0.0156685 -0.032881 -0.219017 0.0132627 -0.0284096 -0.218685 0.0134712 -0.028308 -0.219017 0.011224 -0.0237593 -0.219017 0.00956584 -0.0189601 -0.219017 0.00829878 -0.0140432 -0.218685 0.00766105 -0.00900993 -0.218685 0.00720001 -0.00397209 -0.219017 0.00691356 0.00109334 -0.219017 0.00696834 -0.00398392 -0.219017 0.00743108 -0.00904035 -0.219229 0.00708983 -0.00908548 -0.219229 0.00796227 -0.0141156 -0.219229 0.0129532 -0.0285604 -0.219017 0.018426 -0.0371446 -0.219229 0.0212529 -0.041393 -0.219017 0.0215173 -0.0411726 -0.219017 0.0286193 -0.0484198 -0.219017 0.032584 -0.051592 -0.219017 0.0367908 -0.0544352 -0.219017 0.0412126 -0.0569311 -0.219229 0.0410556 -0.0572374 -0.219017 0.0505853 -0.0608184 -0.219017 0.0554756 -0.0621848 -0.219229 0.0604078 -0.0634938 -0.219017 0.070581 -0.0638761 -0.219017 0.0756524 -0.0636251 -0.219017 0.0806871 -0.0629673 -0.219017 0.0856527 -0.0619069 -0.219017 0.090517 -0.0604508 -0.219229 0.0857381 -0.0622404 -0.219229 0.0999792 -0.0566949 -0.219017 0.104192 -0.0538147 -0.219229 0.104378 -0.054104 -0.219017 0.112251 -0.0476498 -0.219017 0.115883 -0.0441017 -0.219229 0.116133 -0.0443381 -0.219017 0.119218 -0.0402731 -0.219017 0.124914 -0.0318752 -0.219017 0.127237 -0.0273603 -0.219229 0.127549 -0.0275053 -0.219017 0.129189 -0.0226732 -0.219229 0.129512 -0.0227927 -0.219017 0.130759 -0.0178443 -0.219017 0.131935 -0.0129049 -0.219229 0.132273 -0.0129711 -0.219229 0.132912 -0.00907447 -0.187973 0.132773 -0.00261404 -0.218289 0.13214 0.00831443 -0.218289 0.126442 0.0267697 -0.218289 0.129349 0.0197656 -0.187973 0.125287 0.0290201 -0.187973 0.129619 0.018967 -0.218289 0.118212 0.039477 -0.218289 0.107181 0.0498456 -0.187973 0.111766 0.0461332 -0.218289 0.102988 0.0526733 -0.187973 0.102988 0.0526733 -0.218289 0.0939884 0.0572729 -0.218289 0.0932071 0.0575897 -0.218289 0.0868178 0.0597412 -0.187973 0.0827213 0.0607331 -0.218289 0.079402 0.0613272 -0.218289 0.071849 0.0620078 -0.187973 0.0609206 0.0613752 -0.187973 0.050268 0.0588546 -0.218289 0.02424 0.0422451 -0.187973 0.0231018 0.0410011 -0.218289 0.029758 0.0474473 -0.218289 0.0165617 0.0322228 -0.218289 0.0116453 0.0224421 -0.187973 0.0116453 0.0224421 -0.218289 0.00790775 0.00863704 -0.218289 0.00850193 0.0119564 -0.220802 0.135251 -0.0191071 -0.220328 0.133612 -0.0200766 -0.220249 0.133252 -0.0205011 -0.219229 0.13109 -0.0179375 -0.219434 0.131392 -0.0189261 -0.219678 0.132278 -0.0182715 -0.21947 0.133376 -0.0105057 -0.219319 0.133058 -0.00981697 -0.220077 0.133334 -0.0185681 -0.220776 0.136609 -0.012916 -0.220746 0.136534 -0.0128574 -0.22032 0.135464 -0.0121947 -0.219869 0.132816 -0.0182914 -0.219902 0.134411 -0.0115429 -0.219229 0.00662457 -0.00400148 -0.220319 0.00395526 -0.00810683 -0.220744 0.00284731 -0.0087047 -0.220097 0.00618947 -0.0169998 -0.219903 0.00674553 -0.0170162 -0.220249 0.00569558 -0.0167438 -0.220328 0.00536169 -0.0162988 -0.220321 0.00525392 -0.015753 -0.220228 0.00539362 -0.0152146 -0.220802 0.00280497 -0.0096522 -0.220067 0.00575313 -0.01479 -0.219901 0.00504501 -0.00751875 -0.219672 0.00681729 -0.0145799 -0.219869 0.00626123 -0.0145635 -0.219517 0.00731118 -0.0148359 -0.219538 0.00761313 -0.0163651 -0.219229 0.00923623 -0.0190594 -0.220802 0.00809654 -0.0283714 -0.219229 0.0109035 -0.0238847 -0.219229 0.0153722 -0.0330562 -0.220802 0.0132901 -0.0378883 -0.220126 0.0227649 -0.0467515 -0.219229 0.0246766 -0.0451801 -0.220268 0.0222088 -0.0467351 -0.219835 0.0217725 -0.0445254 -0.219229 0.0181447 -0.037343 -0.220802 0.0146128 -0.0398343 -0.220205 0.0212733 -0.0454884 -0.219642 0.0222806 -0.0442989 -0.220802 0.0215895 -0.0482053 -0.219229 0.0283936 -0.0486797 -0.220802 0.0278602 -0.0538535 -0.219229 0.0323799 -0.0518692 -0.219229 0.0366097 -0.054728 -0.220802 0.0298176 -0.05535 -0.219229 0.0456888 -0.0593814 -0.220802 0.0390842 -0.0610838 -0.220181 0.0501219 -0.063776 -0.219229 0.0504794 -0.061146 -0.219768 0.0501999 -0.0626105 -0.219562 0.0506707 -0.0621666 -0.219489 0.0509731 -0.0620513 -0.219442 0.0513004 -0.0620176 -0.219229 0.0553964 -0.0625197 -0.21997 0.0523733 -0.0638423 -0.220154 0.0520138 -0.0642669 -0.220802 0.0571626 -0.0673183 -0.220336 0.0509497 -0.064477 -0.220299 0.0504558 -0.064221 -0.219768 0.052513 -0.0633039 -0.219229 0.0654814 -0.0640619 -0.220802 0.0679383 -0.0685138 -0.219229 0.0705842 -0.0642203 -0.219229 0.0756832 -0.0639679 -0.219229 0.0807454 -0.0633066 -0.220802 0.0787668 -0.0679758 -0.220205 0.0843682 -0.0653252 -0.219587 0.0839151 -0.0636863 -0.219801 0.0861665 -0.0637526 -0.220003 0.0862743 -0.0642984 -0.220321 0.084988 -0.065511 -0.220276 0.0846637 -0.0654583 -0.219614 0.0858326 -0.0633076 -0.219229 0.0906289 -0.0607763 -0.220802 0.092034 -0.0648637 -0.219229 0.0953862 -0.0589238 -0.220802 0.102021 -0.0605044 -0.220802 0.108834 -0.0563175 -0.219229 0.108555 -0.0511679 -0.219937 0.113952 -0.0491961 -0.219562 0.113511 -0.0482054 -0.219229 0.112481 -0.0479055 -0.219452 0.11365 -0.0476669 -0.219497 0.114518 -0.0470159 -0.219642 0.115074 -0.0470322 -0.219835 0.115568 -0.0472883 -0.220802 0.119276 -0.0473059 -0.220205 0.11601 -0.048279 -0.220802 0.117194 -0.0494151 -0.220333 0.11551 -0.049242 -0.220268 0.115002 -0.0494685 -0.220126 0.114446 -0.0494521 -0.219229 0.119487 -0.0404886 -0.220802 0.124348 -0.0412679 -0.219229 0.12252 -0.036382 -0.219229 0.125213 -0.0320449 -0.186473 0.111882 -0.00199867 -0.186473 0.11071 -0.0106794 -0.213123 0.107759 -0.0189269 -0.186473 0.103158 -0.0263806 -0.213123 0.103158 -0.0263806 -0.213123 0.0898725 -0.0376526 -0.186473 0.0817688 -0.0409782 -0.186473 0.0643952 -0.0422884 -0.213123 0.0558844 -0.0402157 -0.186473 0.0558844 -0.0402157 -0.186473 0.0479906 -0.0364189 -0.213123 0.0410587 -0.0310637 -0.213123 0.0353917 -0.0243844 -0.186473 0.0353917 -0.0243844 -0.213123 0.0312372 -0.0166728 -0.186473 0.0312372 -0.0166728 -0.213123 0.0287768 -0.00826596 -0.186473 0.0281181 0.000468725 -0.187122 0.0913161 0.0248185 -0.187573 0.0919826 0.024473 -0.187573 0.0917666 0.024218 -0.187573 0.0911275 0.0240918 -0.187573 0.0908309 0.0242456 -0.187573 0.0479982 -0.0266541 -0.187573 0.0481987 -0.0269213 -0.187573 0.0901293 -0.0282197 -0.187573 0.0897511 -0.0283092 -0.187573 0.0905236 -0.0275809 -0.187573 0.0890228 -0.0275367 -0.187573 0.0495658 0.0256728 -0.187122 0.0502267 0.0260288 -0.185973 0.0218209 0.000654221 -0.185773 0.0299872 0.0264663 -0.185773 0.0358286 0.0335116 -0.185773 0.0428918 0.0393313 -0.185773 0.117171 -0.0116009 -0.185773 0.109434 -0.0288278 -0.185973 0.109271 -0.0287119 -0.185973 0.103064 -0.0358363 -0.185773 0.103201 -0.0359818 -0.185973 0.0955868 -0.0416129 -0.185973 0.0871261 -0.0458198 -0.185973 0.0685808 -0.0489441 -0.185773 0.0685749 -0.049144 -0.185773 0.059164 -0.0479364 -0.185973 0.0502515 -0.0447336 -0.185973 0.0420531 -0.040036 -0.185773 0.0347831 -0.0339664 -0.185973 0.0249452 -0.0178912 -0.185773 0.0222725 -0.00880555 -0.185973 0.0224697 -0.00877232 -0.184973 0.105179 0.0186893 -0.184973 0.105786 0.0175489 -0.184973 0.109756 0.00519278 -0.183973 0.117379 -0.00216061 -0.184973 0.118379 -0.00219005 -0.183973 0.116795 0.00678314 -0.184973 0.115477 0.0157992 -0.183973 0.114538 0.015457 -0.183973 0.110688 0.0235509 -0.183973 0.105383 0.0307753 -0.184973 0.0222725 -0.00880555 -0.183973 0.0425169 -0.0393842 -0.183973 0.0355108 -0.0332804 -0.184973 0.0289825 -0.026458 -0.183973 0.02983 -0.0259272 -0.184973 0.0780405 -0.0484924 -0.184973 0.059164 -0.0479364 -0.183973 0.0593879 -0.0469618 -0.183973 0.0554923 -0.0458902 -0.184973 0.0501695 -0.044916 -0.183973 0.0505792 -0.0440038 -0.184973 0.095693 -0.0417824 -0.184973 0.0871972 -0.0460067 -0.183973 0.0868419 -0.045072 -0.183973 0.0778744 -0.0475063 -0.184973 0.109434 -0.0288278 -0.183973 0.108619 -0.028248 -0.183973 0.102515 -0.0352542 -0.184973 0.114151 -0.0205954 -0.184963 0.0518743 -0.0302562 -0.184973 0.0518662 -0.0305149 -0.180823 0.0950716 0.00299845 -0.181366 0.0944849 0.00256554 -0.181561 0.0949034 0.00300341 -0.182042 0.0936372 0.00259051 -0.182152 0.0944318 0.0030173 -0.182042 0.0930811 0.00260689 -0.1818 0.0925801 0.00262165 -0.181366 0.0922334 0.00263186 -0.180823 0.0921097 0.00263551 -0.181366 0.0942184 -0.00648053 -0.1818 0.0941382 0.00257576 -0.182042 0.0933707 -0.00645556 -0.181366 0.0919669 -0.00641421 -0.1818 0.0938717 -0.00647032 -0.182042 0.0928146 -0.00643918 -0.1818 0.0923136 -0.00642442 -0.180823 0.0485918 0.00436759 -0.181906 0.047504 0.00394944 -0.182073 0.0468793 0.00396784 -0.182295 0.0477422 0.00439262 -0.182295 0.0460429 0.00444267 -0.181448 0.0457972 0.00399972 -0.180823 0.0456298 0.00400465 -0.181673 0.0454209 0.004461 -0.180823 0.0451933 0.0044677 -0.180823 0.0481287 0.00393104 -0.181448 0.0476949 -0.00511011 -0.181448 0.0479613 0.00393597 -0.181906 0.0472375 -0.00509664 -0.182042 0.0468909 -0.00508642 -0.181906 0.0462546 0.00398624 -0.1818 0.0458338 -0.00505529 -0.181366 0.0454871 -0.00504507 -0.1818 0.0473918 -0.00510118 -0.182073 0.0466128 -0.00507823 -0.181906 0.0459881 -0.00505983 -0.180823 0.0453634 -0.00504143 -0.181448 0.0455308 -0.00504636 -0.182042 0.0463348 -0.00507004 -0.180823 0.0465907 -0.00582898 -0.181366 0.0477385 -0.00511139 -0.180823 0.0684332 0.00378313 -0.181561 0.0686015 0.00377818 -0.181366 0.0689935 0.00331643 -0.181448 0.0690371 0.00331515 -0.1818 0.0693402 0.00330622 -0.182481 0.0697543 0.00374422 -0.182042 0.0698412 0.00329146 -0.182073 0.0701192 0.00328327 -0.182042 0.0703972 0.00327508 -0.182152 0.0711919 0.00370187 -0.181906 0.0707439 0.00326487 -0.1818 0.0708982 0.00326033 -0.181561 0.0716634 0.00368798 -0.180823 0.0713687 0.00324647 -0.180823 0.0711022 -0.00579961 -0.181366 0.0712449 0.00325011 -0.181448 0.0712013 0.0032514 -0.1818 0.0706318 -0.00578575 -0.182042 0.0701308 -0.00577099 -0.182042 0.0695747 -0.00575461 -0.181906 0.0694945 0.00330168 -0.1818 0.0690737 -0.00573986 -0.181366 0.0709785 -0.00579596 -0.182073 0.0698527 -0.0057628 -0.181366 0.068727 -0.00572964 -0.180823 0.0686033 -0.005726 -0.181448 0.0687707 -0.00573093 -0.181906 0.069228 -0.0057444 -0.181906 0.0704775 -0.00578121 -0.181448 0.0709348 -0.00579468 -0.186788 0.0286944 0.00045175 -0.186773 0.0288984 -0.00572729 -0.186788 0.0289744 -0.00571811 -0.186773 0.0351218 -0.0230691 -0.186788 0.032257 -0.0175905 -0.186832 0.0302334 -0.01176 -0.186773 0.0321871 -0.0176217 -0.186788 0.0301709 -0.0117773 -0.186897 0.103355 -0.0249749 -0.186832 0.10905 -0.0140817 -0.186788 0.103443 -0.0250385 -0.186832 0.0994052 -0.0297063 -0.186897 0.0993743 -0.0296759 -0.186773 0.103505 -0.0250835 -0.186832 0.0895682 -0.0370879 -0.186897 0.0895477 -0.0370497 -0.186773 0.0896353 -0.0372124 -0.186788 0.089599 -0.037145 -0.186832 0.0779925 -0.041242 -0.186897 0.0779841 -0.0411995 -0.186788 0.083958 -0.0396597 -0.186897 0.0718685 -0.0419378 -0.186773 0.0718769 -0.0421224 -0.186788 0.0718734 -0.0420459 -0.186832 0.0657066 -0.0417996 -0.186832 0.0596387 -0.0407014 -0.186773 0.0656919 -0.0419402 -0.186773 0.0596032 -0.0408382 -0.186788 0.0596224 -0.0407642 -0.186832 0.0538022 -0.038711 -0.186788 0.0537767 -0.0387707 -0.186973 0.0433749 -0.0322061 -0.186832 0.043337 -0.0322508 -0.186788 0.0432951 -0.0323003 -0.186832 0.0389421 -0.0279252 -0.186773 0.0482533 -0.0359934 -0.186788 0.0388933 -0.027968 -0.186832 0.035241 -0.022993 -0.186897 0.0352775 -0.0229696 -0.186973 0.0323698 -0.0175403 -0.186897 0.0323559 -0.0175465 -0.186788 0.110663 -0.00812437 -0.186832 0.111241 -0.00197978 -0.186897 0.111197 -0.0019785 -0.186832 0.110599 -0.00811282 -0.186897 0.109009 -0.0140677 -0.186973 0.11003 -0.0105138 -0.186897 0.110556 -0.0081051 -0.186973 0.103343 -0.024966 -0.186897 0.106591 -0.0197332 -0.186773 0.109184 -0.0141274 -0.186788 0.106687 -0.019783 -0.186788 0.109112 -0.0141027 -0.186832 0.106629 -0.0197531 -0.186832 0.10339 -0.0250004 -0.186973 0.0947282 -0.0337188 -0.186973 0.0993635 -0.0296652 -0.186773 0.106755 -0.0198182 -0.186788 0.0994515 -0.0297518 -0.186832 0.0947633 -0.0337657 -0.186897 0.0947373 -0.033731 -0.186773 0.0948482 -0.0338788 -0.186788 0.0948023 -0.0338176 -0.186832 0.083936 -0.0395987 -0.186897 0.0839214 -0.0395579 -0.186973 0.0718678 -0.0419226 -0.186973 0.0730982 -0.0418483 -0.186788 0.0780051 -0.0413056 -0.186832 0.0718705 -0.0419811 -0.186897 0.0657111 -0.0417564 -0.186973 0.0538252 -0.0386572 -0.186973 0.0561203 -0.0395566 -0.186897 0.0596496 -0.0406594 -0.186973 0.0596534 -0.0406446 -0.186788 0.0656999 -0.0418641 -0.186897 0.0538192 -0.0386712 -0.186897 0.0483503 -0.0358362 -0.186973 0.0483583 -0.0358232 -0.186788 0.0482935 -0.0359283 -0.186832 0.0483276 -0.0358731 -0.186897 0.0433651 -0.0322177 -0.186897 0.0389747 -0.0278967 -0.186973 0.0415422 -0.0305576 -0.186773 0.0388357 -0.0280183 -0.186788 0.0351863 -0.0230279 -0.186832 0.0323163 -0.0175641 -0.186897 0.0302752 -0.0117485 -0.186897 0.0290819 -0.00570514 -0.186832 0.0290388 -0.00571033 -0.186897 0.0288026 0.000448563 -0.186573 0.0293384 0.00913766 -0.186773 0.028368 0.000461364 -0.186773 0.0295327 0.00909033 -0.186573 0.0322858 0.0173753 -0.186573 0.0368816 0.0248201 -0.186573 0.0429247 0.0311467 -0.186773 0.0430541 0.0309942 -0.186573 0.0582451 0.0394003 -0.186773 0.050246 0.0359025 -0.186773 0.0583013 0.0392083 -0.186773 0.0755713 0.0405107 -0.186773 0.0840312 0.0384504 -0.186573 0.091983 0.0348464 -0.186773 0.091878 0.0346762 -0.186573 0.0989067 0.0294976 -0.186773 0.104402 0.0227135 -0.186573 0.111174 0.00672706 -0.186773 0.110977 0.00669126 -0.184973 0.0863511 -0.0315307 -0.186573 0.0863511 -0.0315307 -0.183973 0.0263078 0.0143102 -0.183973 0.0265104 0.0134539 -0.184073 0.0271666 0.0128986 -0.183973 0.027114 0.0128136 -0.184073 0.0279599 0.0126608 -0.183973 0.0294536 0.0133672 -0.183973 0.0297063 0.0142101 -0.185873 0.0265457 0.0136087 -0.185873 0.0265984 0.0135013 -0.184073 0.0265984 0.0135013 -0.185873 0.0276052 0.0127114 -0.185873 0.028317 0.0126904 -0.184073 0.0287659 0.0128515 -0.185873 0.0287659 0.0128515 -0.185873 0.0294275 0.0135238 -0.184073 0.0293685 0.0134197 -0.185973 0.0269084 0.0129628 -0.185873 0.026973 0.0130391 -0.185873 0.0271666 0.0128986 -0.185873 0.0279599 0.0126608 -0.185873 0.0289673 0.0129804 -0.185973 0.0295163 0.0134778 -0.185873 0.0293685 0.0134197 -0.183973 0.0282158 -0.014652 -0.184073 0.0281557 -0.014572 -0.184073 0.0275054 -0.0148619 -0.183973 0.0275248 -0.01496 -0.183973 0.0267685 -0.0149378 -0.184073 0.0271483 -0.0148915 -0.184073 0.0267936 -0.014841 -0.183973 0.0260968 -0.0145896 -0.184073 0.026355 -0.0146537 -0.183973 0.0254962 -0.0132422 -0.184073 0.0257341 -0.0139437 -0.183973 0.0256427 -0.0139844 -0.184073 0.0257868 -0.0140511 -0.184073 0.0286159 -0.0140286 -0.185873 0.0286159 -0.0140286 -0.184073 0.0285569 -0.0141327 -0.185873 0.0285569 -0.0141327 -0.185873 0.0281557 -0.014572 -0.184073 0.0279543 -0.0147008 -0.185873 0.0279543 -0.0147008 -0.185873 0.0275054 -0.0148619 -0.185873 0.0267936 -0.014841 -0.185873 0.026355 -0.0146537 -0.184073 0.0261614 -0.0145132 -0.185873 0.0261614 -0.0145132 -0.184073 0.0255961 -0.0132451 -0.185873 0.0255961 -0.0132451 -0.185873 0.0257341 -0.0139437 -0.185873 0.0257868 -0.0140511 -0.185973 0.0260968 -0.0145896 -0.185873 0.0271483 -0.0148915 -0.185973 0.0275248 -0.01496 -0.185973 0.0282158 -0.014652 -0.185873 0.0287947 -0.0133393 -0.184073 0.0412723 -0.0367111 -0.183973 0.0410344 -0.0360096 -0.183973 0.041181 -0.0367518 -0.183973 0.0416351 -0.0373569 -0.184073 0.0416997 -0.0372806 -0.185873 0.0418933 -0.0374211 -0.184073 0.0423319 -0.0376083 -0.185873 0.0426866 -0.0376589 -0.185873 0.0430437 -0.0376293 -0.184073 0.0430437 -0.0376293 -0.184073 0.043694 -0.0373394 -0.184073 0.0441542 -0.036796 -0.185873 0.0440952 -0.0369001 -0.184073 0.044333 -0.0361067 -0.185873 0.0411344 -0.0360125 -0.185873 0.0413251 -0.0368185 -0.185873 0.0416997 -0.0372806 -0.185873 0.0423319 -0.0376083 -0.185973 0.0418407 -0.0375062 -0.185873 0.043694 -0.0373394 -0.185873 0.0434926 -0.0374682 -0.184073 0.0672254 -0.0459971 -0.184073 0.0676528 -0.0465667 -0.184073 0.0689967 -0.0469153 -0.183973 0.0690161 -0.0470134 -0.184073 0.0696471 -0.0466254 -0.183973 0.0697071 -0.0467054 -0.184073 0.0701073 -0.046082 -0.185873 0.0686397 -0.0469449 -0.184073 0.068285 -0.0468944 -0.185873 0.0696471 -0.0466254 -0.184073 0.0702861 -0.0453927 -0.185873 0.0672782 -0.0461045 -0.185873 0.0676528 -0.0465667 -0.185873 0.0678463 -0.0467071 -0.185873 0.068285 -0.0468944 -0.185973 0.0686367 -0.0470449 -0.185873 0.0689967 -0.0469153 -0.185973 0.069493 -0.0468423 -0.185973 0.070386 -0.0453957 -0.185873 0.0700483 -0.0461861 -0.185873 0.0694456 -0.0467542 -0.183973 0.0959477 -0.0391 -0.183973 0.096588 -0.0384963 -0.185873 0.0935421 -0.0375562 -0.184073 0.0937328 -0.0383622 -0.184073 0.094301 -0.0389648 -0.185873 0.0941074 -0.0388244 -0.184073 0.0950943 -0.0392027 -0.185873 0.0954514 -0.0391731 -0.184073 0.0959003 -0.039012 -0.184073 0.0965029 -0.0384438 -0.185873 0.0965619 -0.0383397 -0.185873 0.0936801 -0.0382548 -0.185873 0.0937328 -0.0383622 -0.185973 0.0940428 -0.0389007 -0.185873 0.094301 -0.0389648 -0.185873 0.0947396 -0.0391521 -0.185973 0.0954707 -0.0392712 -0.185873 0.0950943 -0.0392027 -0.185873 0.0959003 -0.039012 -0.185873 0.0961017 -0.0388831 -0.185873 0.0967407 -0.0376505 -0.185873 0.0965029 -0.0384438 -0.183973 0.110294 -0.01574 -0.184073 0.110532 -0.0164415 -0.183973 0.110894 -0.0170874 -0.183973 0.112322 -0.0174579 -0.183973 0.113502 -0.0165725 -0.185873 0.110394 -0.015743 -0.185873 0.110959 -0.0170111 -0.184073 0.110959 -0.0170111 -0.185873 0.111152 -0.0171516 -0.185873 0.111946 -0.0173894 -0.184073 0.111591 -0.0173388 -0.184073 0.112303 -0.0173598 -0.185873 0.112752 -0.0171987 -0.184073 0.112953 -0.0170698 -0.184073 0.113413 -0.0165264 -0.185873 0.113354 -0.0166305 -0.184073 0.113592 -0.0158372 -0.185873 0.110584 -0.0165489 -0.185873 0.111591 -0.0173388 -0.185973 0.111943 -0.0174893 -0.185973 0.113439 -0.0166831 -0.185873 0.112953 -0.0170698 -0.185873 0.112303 -0.0173598 -0.183973 0.111308 0.010956 -0.183973 0.111912 0.0103157 -0.183973 0.113611 0.0102657 -0.184073 0.114166 0.0109218 -0.183973 0.114251 0.0108693 -0.184073 0.111205 0.0118094 -0.184073 0.111396 0.0110034 -0.185873 0.111396 0.0110034 -0.185873 0.111964 0.0104008 -0.185873 0.112757 0.010163 -0.184073 0.111964 0.0104008 -0.184073 0.112757 0.010163 -0.184073 0.113563 0.0103537 -0.185873 0.114166 0.0109218 -0.184073 0.114404 0.0117152 -0.185873 0.114404 0.0117152 -0.185873 0.113563 0.0103537 -0.185973 0.113611 0.0102657 -0.185973 0.111912 0.0103157 -0.185973 0.111308 0.010956 -0.183973 0.095567 0.0345797 -0.184073 0.0958576 0.0337708 -0.183973 0.0957696 0.0337234 -0.184073 0.0964258 0.0331682 -0.184073 0.0972191 0.0329304 -0.183973 0.0972162 0.0328304 -0.184073 0.0986277 0.0336892 -0.184073 0.0988655 0.0344826 -0.185873 0.0958048 0.0338782 -0.185873 0.0958576 0.0337708 -0.185873 0.0964258 0.0331682 -0.185873 0.0968644 0.0329809 -0.185873 0.0972191 0.0329304 -0.184073 0.0980251 0.0331211 -0.185873 0.0980251 0.0331211 -0.185873 0.0956669 0.0345768 -0.185973 0.0957135 0.0338375 -0.185873 0.0962322 0.0333087 -0.185973 0.0961676 0.0332323 -0.185873 0.0975762 0.03296 -0.185873 0.0982265 0.0332499 -0.185873 0.0986867 0.0337933 -0.185873 0.0986277 0.0336892 -0.183973 0.0696139 0.0438657 -0.184073 0.0698518 0.0431642 -0.183973 0.0697604 0.0431235 -0.184073 0.0702792 0.0425947 -0.184073 0.0709113 0.042267 -0.183973 0.0702145 0.0425184 -0.183973 0.0708862 0.0421702 -0.183973 0.0723335 0.0424559 -0.184073 0.0727336 0.0430793 -0.183973 0.0728224 0.0430333 -0.184073 0.0697138 0.0438628 -0.185873 0.0702792 0.0425947 -0.185873 0.0716231 0.042246 -0.184073 0.0716231 0.042246 -0.184073 0.0722735 0.0425359 -0.185973 0.0698165 0.0430094 -0.185873 0.0699046 0.0430568 -0.185973 0.0704202 0.0423691 -0.185873 0.0704727 0.0424542 -0.185973 0.0712631 0.0421164 -0.185873 0.0709113 0.042267 -0.185873 0.071266 0.0422164 -0.185973 0.0730124 0.0437656 -0.185873 0.0726746 0.0429752 -0.185973 0.0727597 0.0429227 -0.185973 0.0721194 0.0423191 -0.185873 0.0722735 0.0425359 -0.185873 0.072072 0.0424071 -0.183973 0.0431592 0.0361235 -0.184073 0.0434499 0.0353146 -0.183973 0.0433619 0.0352671 -0.183973 0.0439655 0.0346268 -0.184073 0.0448114 0.0344741 -0.183973 0.0448084 0.0343742 -0.184073 0.0456174 0.0346648 -0.184073 0.044018 0.0347119 -0.185873 0.0448114 0.0344741 -0.185873 0.0464578 0.0360263 -0.184073 0.04622 0.035233 -0.185873 0.04622 0.035233 -0.185873 0.0456174 0.0346648 -0.185873 0.044018 0.0347119 -0.185973 0.0433619 0.0352671 -0.185873 0.0434499 0.0353146 -0.185873 0.0432592 0.0361205 -0.185973 0.0755238 0.0407189 -0.186273 0.0910305 0.035417 -0.185773 0.0757231 0.0406919 -0.186573 0.0755981 0.0407089 -0.186573 0.0840986 0.0386387 -0.186273 0.0840986 0.0386387 -0.186273 0.0587182 0.0395357 -0.185973 0.0669275 0.0409721 -0.185873 0.0668272 0.0409646 -0.186573 0.0668528 0.0409665 -0.186273 0.066727 0.0409568 -0.185973 0.050957 0.0365015 -0.186573 0.0501512 0.0360786 -0.186573 0.0281681 0.000467253 -0.185973 0.0293384 0.00913766 -0.185973 0.091983 0.0348464 -0.186573 0.104567 0.0228263 -0.186573 0.108716 0.0151239 -0.185973 0.111832 -0.00199719 -0.186573 0.111832 -0.00199719 -0.184973 0.0298174 0.000418671 -0.184973 0.0318606 0.0119406 -0.186573 0.0327554 0.014364 -0.186573 0.0403744 0.0264079 -0.184973 0.117782 0.00694238 -0.185773 0.115477 0.0157992 -0.184973 0.111546 0.0240639 -0.185773 0.10613 0.0314407 -0.184973 0.10613 0.0314407 -0.185773 0.0994213 0.0376661 -0.185773 0.0247582 -0.0179622 -0.184973 0.0247582 -0.0179622 -0.185773 0.0289825 -0.026458 -0.184973 0.0347831 -0.0339664 -0.185773 0.0419371 -0.0401989 -0.184973 0.0419371 -0.0401989 -0.185773 0.0501695 -0.044916 -0.184973 0.0685749 -0.049144 -0.185773 0.0780405 -0.0484924 -0.185773 0.0871972 -0.0460067 -0.185773 0.095693 -0.0417824 -0.184973 0.103201 -0.0359818 -0.185773 0.114151 -0.0205954 -0.184973 0.117171 -0.0116009 -0.186973 0.111182 -0.00197806 -0.186973 0.110903 0.00417337 -0.187573 0.111182 -0.00197806 -0.186973 0.110534 0.0066107 -0.186973 0.108115 0.0148771 -0.187573 0.108115 0.0148771 -0.186973 0.10763 0.0160103 -0.187573 0.0984577 0.0290276 -0.187573 0.10403 0.0224599 -0.186973 0.10471 0.0214315 -0.186973 0.096625 0.0306762 -0.186973 0.0984577 0.0290276 -0.187573 0.0916416 0.0342933 -0.186973 0.0916416 0.0342933 -0.186973 0.0742872 0.0402114 -0.186973 0.0755111 0.0400648 -0.186973 0.0803465 0.0391147 -0.187573 0.0838796 0.0380267 -0.186973 0.0838796 0.0380267 -0.186973 0.0861747 0.0371272 -0.186973 0.0681321 0.0403927 -0.186973 0.0669017 0.0403184 -0.186973 0.0620187 0.0396546 -0.186973 0.0560837 0.0380136 -0.187573 0.0504595 0.0355063 -0.186973 0.0452717 0.0321889 -0.187573 0.0433452 0.030651 -0.186973 0.0406364 0.0281353 -0.187573 0.02997 0.00898385 -0.186973 0.0288178 0.000448115 -0.185973 0.0912035 0.0353159 -0.185973 0.0922719 0.0353144 -0.185973 0.0989067 0.0294976 -0.185973 0.0992865 0.0298954 -0.185973 0.104567 0.0228263 -0.185973 0.105021 0.0231363 -0.185973 0.108716 0.0151239 -0.185973 0.111174 0.00672706 -0.185973 0.111715 0.00682553 -0.185973 0.112382 -0.00201339 -0.185973 0.111196 -0.0107977 -0.185973 0.107714 -0.0189052 -0.185973 0.0970752 -0.0326766 -0.185973 0.0898487 -0.0376085 -0.185973 0.0731471 -0.0424965 -0.185973 0.0731885 -0.0430449 -0.185973 0.0644019 -0.0422389 -0.185973 0.0559013 -0.0401687 -0.185973 0.0643283 -0.0427839 -0.185973 0.055716 -0.0406865 -0.185973 0.0480169 -0.0363763 -0.185973 0.035433 -0.0243562 -0.185973 0.0407134 -0.0314253 -0.185973 0.0312835 -0.0166538 -0.185973 0.0307746 -0.0168626 -0.185973 0.028826 -0.00825701 -0.185973 0.0281681 0.000467253 -0.185973 0.0322858 0.0173753 -0.185973 0.0368816 0.0248201 -0.185973 0.0364463 0.0251563 -0.185973 0.0429247 0.0311467 -0.185973 0.0501512 0.0360786 -0.185973 0.0425689 0.0315661 -0.185973 0.0498903 0.0365628 -0.187573 0.0288178 0.000448115 -0.186973 0.0318848 -0.016407 -0.186973 0.0302899 -0.0117444 -0.186973 0.0294655 -0.00814064 -0.187573 0.0294655 -0.00814064 -0.186973 0.029097 -0.00570331 -0.186973 0.0352903 -0.0229614 -0.186973 0.0359699 -0.0239898 -0.186973 0.0389862 -0.0278867 -0.187573 0.0415422 -0.0305576 -0.187573 0.0483583 -0.0358232 -0.187573 0.0561203 -0.0395566 -0.186973 0.0644888 -0.0415947 -0.186973 0.0657127 -0.0417413 -0.187573 0.0644888 -0.0415947 -0.186973 0.0779812 -0.0411845 -0.186973 0.0839163 -0.0395435 -0.186973 0.0815722 -0.0403064 -0.187573 0.0966547 -0.032181 -0.186973 0.0895405 -0.0370363 -0.186973 0.102604 -0.0259526 -0.186973 0.0966547 -0.032181 -0.186973 0.106577 -0.0197262 -0.186973 0.107128 -0.0186235 -0.186973 0.108995 -0.0140628 -0.187573 0.107128 -0.0186235 -0.187573 0.11003 -0.0105138 -0.186973 0.110541 -0.00810239 -0.183973 0.091613 0.0289635 -0.183973 0.105035 0.023146 -0.183973 0.105071 0.0208553 -0.183973 0.0914185 0.0301178 -0.183973 0.0988134 0.0368721 -0.183973 0.0987628 0.035336 -0.183973 0.0989655 0.0344796 -0.183973 0.0987128 0.0336367 -0.183973 0.103457 0.0232779 -0.183973 0.0943289 0.0270307 -0.183973 0.0963732 0.0330831 -0.183973 0.0980725 0.033033 -0.183973 0.101949 0.0252484 -0.183973 0.0915274 0.0338115 -0.183973 0.0971122 0.0376287 -0.183973 0.0958196 0.0354226 -0.183973 0.109017 0.0124666 -0.183973 0.111105 0.0118123 -0.183973 0.106054 0.0191732 -0.183973 0.111358 0.0126553 -0.183973 0.112754 0.010063 -0.183973 0.110745 0.00534098 -0.183973 0.111998 0.0132589 -0.183973 0.112855 0.0134616 -0.183973 0.113697 0.0132089 -0.183973 0.114301 0.0125686 -0.183973 0.116197 -0.0113771 -0.183973 0.115739 -0.00211228 -0.183973 0.11044 -0.0164823 -0.183973 0.110176 -0.0098937 -0.183973 0.113013 -0.0171498 -0.183973 0.113239 -0.0201857 -0.183973 0.109522 -0.0269332 -0.183973 0.111566 -0.0174356 -0.183973 0.107663 -0.0174669 -0.183973 0.0951621 -0.0409349 -0.183973 0.0950914 -0.0393026 -0.183973 0.0934647 -0.0419495 -0.183973 0.0942484 -0.0390499 -0.183973 0.0936448 -0.0384096 -0.183973 0.0903188 -0.0361092 -0.183973 0.0850319 -0.0372027 -0.183973 0.085526 -0.0358765 -0.183973 0.0859023 -0.0337945 -0.183973 0.0922835 -0.0354187 -0.183973 0.0934422 -0.0375533 -0.183973 0.0841069 -0.0382737 -0.183973 0.0968407 -0.0376534 -0.183973 0.0985455 -0.0304734 -0.183973 0.103567 -0.0266967 -0.183973 0.070196 -0.046128 -0.183973 0.0686043 -0.0481444 -0.183973 0.0682598 -0.0469912 -0.183973 0.0675882 -0.046643 -0.183973 0.0346557 -0.0323489 -0.183973 0.0365819 -0.0248622 -0.183973 0.0412871 -0.0351666 -0.183973 0.0427838 -0.0343603 -0.183973 0.0393016 -0.0282432 -0.183973 0.043063 -0.0377274 -0.183973 0.043754 -0.0374194 -0.183973 0.052181 -0.0328012 -0.183973 0.0442303 -0.0352533 -0.183973 0.0671341 -0.0460378 -0.183973 0.0669875 -0.0452956 -0.183973 0.044243 -0.036842 -0.183973 0.0423068 -0.0377051 -0.183973 0.044433 -0.0361097 -0.183973 0.0528493 -0.0362547 -0.183973 0.0537096 -0.0373783 -0.183973 0.0549073 -0.0381321 -0.183973 0.0290021 -0.0048411 -0.183973 0.0280884 -0.0118457 -0.183973 0.0272455 -0.011593 -0.183973 0.0263891 -0.0117956 -0.183973 0.0232586 -0.00863942 -0.183973 0.0307567 -0.0133111 -0.183973 0.0288947 -0.0133423 -0.183973 0.0287047 -0.0140746 -0.183973 0.0349646 -0.0246759 -0.183973 0.025693 -0.0176069 -0.183973 0.0264943 0.0180505 -0.183973 0.0308139 0.0259037 -0.183973 0.0295037 0.0150664 -0.183973 0.0309119 0.0122567 -0.183973 0.0290546 0.00380858 -0.183973 0.0288133 0.0127635 -0.183973 0.027957 0.0125609 -0.183973 0.0430862 0.0285402 -0.183973 0.0473493 0.0284146 -0.183973 0.0380321 0.0252253 -0.183973 0.0365346 0.0328034 -0.183973 0.0364328 0.0251668 -0.183973 0.0280571 0.0159594 -0.183973 0.0485036 0.0286091 -0.183973 0.0494956 0.0292304 -0.183973 0.0456648 0.0345768 -0.183973 0.0463051 0.0351804 -0.183973 0.0438382 0.0374332 -0.183973 0.0434519 0.0385028 -0.183973 0.0451947 0.039158 -0.183973 0.0470453 0.0389533 -0.183973 0.0452854 0.0377189 -0.183973 0.0459571 0.0373707 -0.183973 0.0486027 0.037933 -0.183973 0.0464112 0.0367656 -0.183973 0.0828669 -0.0389557 -0.183973 0.0819141 -0.0414745 -0.183973 0.0557102 -0.0407026 -0.183973 0.0688134 -0.0410475 -0.187573 0.0505828 0.0253679 -0.187573 0.0917104 0.0254573 -0.187573 0.09096 0.0254794 -0.187573 0.0906773 0.0252128 -0.187573 0.0755111 0.0400648 -0.187573 0.0500813 0.0267653 -0.187573 0.0504152 0.0267555 -0.187573 0.0497761 0.0266293 -0.187573 0.0373959 0.0244227 -0.187573 0.0494763 0.0260509 -0.187573 0.0328716 0.0170935 -0.187573 0.0502046 0.0252785 -0.187573 0.0483278 -0.0256875 -0.187573 0.0493448 -0.0259924 -0.187573 0.0490782 -0.0257096 -0.187573 0.048706 -0.025598 -0.187573 0.0891123 -0.0279148 -0.187573 0.0893789 -0.0281976 -0.187573 0.0498324 0.02539 -0.187573 0.048045 -0.0259541 -0.187573 0.0318848 -0.016407 -0.187573 0.0359699 -0.0239898 -0.187573 0.0479335 -0.0263263 -0.187573 0.0508655 0.0256345 -0.187573 0.0891067 -0.0272133 -0.187573 0.0509771 0.0260067 -0.187573 0.0815722 -0.0403064 -0.187573 0.0895405 -0.0370363 -0.187573 0.0494342 -0.0263705 -0.187573 0.0584277 0.0387764 -0.187573 0.0669017 0.0403184 -0.187573 0.0920665 0.0247964 -0.187573 0.091977 0.0251745 -0.187573 0.0484953 -0.0270751 -0.187573 0.0488293 -0.0270849 -0.187573 0.0491344 -0.0269489 -0.187573 0.0730982 -0.0418483 -0.187573 0.0493503 -0.0266939 -0.187573 0.090412 -0.0279531 -0.187573 0.102604 -0.0259526 -0.187573 0.110534 0.0066107 -0.187573 0.0899617 -0.0268321 -0.187573 0.0902584 -0.0269859 -0.187573 0.0905657 0.0248406 -0.187573 0.0906304 0.0245128 -0.187573 0.0914615 0.024082 -0.184973 0.0428918 0.0393313 -0.184973 0.0299872 0.0264663 -0.184973 0.0255765 0.0184474 -0.185773 0.0255765 0.0184474 -0.185773 0.0227541 0.00974159 -0.184973 0.0227541 0.00974159 -0.185773 0.0216209 0.00066011 -0.184973 0.103655 -0.0227506 -0.186573 0.103655 -0.0227506 -0.186573 0.101174 0.024617 -0.186573 0.105786 0.0175489 -0.184973 0.10807 0.0121455 -0.184973 0.108821 0.00967362 -0.186573 0.108821 0.00967362 -0.186573 0.110145 0.0013382 -0.186573 0.109699 -0.00708992 -0.184973 0.109699 -0.00708992 -0.184973 0.110183 -0.00194861 -0.184973 0.110145 0.0013382 -0.186573 0.107504 -0.0152392 -0.184973 0.102918 -0.0238397 -0.184973 0.0978527 -0.0297523 -0.184973 0.0400467 -0.0275762 -0.186573 0.0357808 -0.021862 -0.184973 0.035109 -0.0207314 -0.184973 0.0299972 -0.00474217 -0.186573 0.0323558 -0.0148702 -0.183973 0.0748345 0.0444875 -0.183973 0.0746064 0.0454755 -0.183973 0.0722061 0.0452623 -0.183973 0.0739595 0.0317665 -0.183973 0.0743362 0.0321216 -0.183973 0.0734558 0.0316473 -0.183973 0.0716425 0.0421479 -0.183973 0.0698294 0.0466347 -0.183973 0.0698666 0.0447087 -0.183973 0.0679621 0.0319432 -0.183973 0.0674878 0.0328236 -0.186573 0.0306635 0.00752258 -0.186573 0.0298174 0.000418671 -0.186573 0.0510129 -0.0252665 -0.186573 0.0404893 -0.0280626 -0.186573 0.0460324 -0.0227349 -0.186573 0.0751871 0.0315963 -0.186573 0.0501815 0.0285028 -0.186573 0.0518426 -0.0299931 -0.186573 0.0431827 -0.0187856 -0.186573 0.0303428 -0.00734924 -0.186573 0.0942995 0.0260312 -0.186573 0.0684285 0.030795 -0.186573 0.0983231 -0.0292928 -0.186573 0.0864054 -0.0310112 -0.186573 0.0917426 -0.0345776 -0.186573 0.0674368 0.0310923 -0.186573 0.0360269 0.0207263 -0.186573 0.0957099 -0.0203329 -0.186573 0.100008 0.0255457 -0.186573 0.0985625 0.0259056 -0.186573 0.0963666 0.00195988 -0.186573 0.0875115 -0.0342382 -0.186573 0.0875119 -0.0263416 -0.186573 0.0899831 0.0303284 -0.186573 0.0781041 0.0352659 -0.186573 0.0626611 0.0357039 -0.186573 0.0576525 0.0343261 -0.186573 0.0768369 0.0347456 -0.186573 0.0667267 0.0318455 -0.186573 0.0664893 0.0327067 -0.186573 0.0518817 0.0314508 -0.186573 0.0661379 0.0340307 -0.186573 0.0652651 0.0350864 -0.185773 0.0698258 0.0476347 -0.186573 0.035433 -0.0243562 -0.186573 0.0410933 -0.0310276 -0.186573 0.0480169 -0.0363763 -0.185973 0.0410933 -0.0310276 -0.186573 0.0644019 -0.0422389 -0.185973 0.0817548 -0.0409302 -0.186573 0.103118 -0.02635 -0.185973 0.103118 -0.02635 -0.186573 0.107714 -0.0189052 -0.186573 0.110661 -0.0106676 -0.185973 0.110661 -0.0106676 -0.186773 0.108531 0.015048 -0.186773 0.109903 0.0102678 -0.186773 0.0987685 0.029353 -0.186773 0.0668679 0.0407671 -0.186773 0.0503646 0.0356824 -0.186773 0.0451517 0.0323488 -0.186773 0.0404939 0.0282755 -0.186773 0.0370398 0.0246978 -0.186773 0.0324661 0.0172886 -0.186773 0.0332449 0.0182883 -0.186773 0.0969458 -0.0325241 -0.186773 0.0432456 -0.0323587 -0.186773 0.0537467 -0.0388411 -0.186773 0.099506 -0.0298055 -0.186773 0.110467 -0.0106203 -0.186773 0.110738 -0.008138 -0.186773 0.111632 -0.00199131 -0.186773 0.111382 -0.00198395 -0.186773 0.0292618 0.00660806 -0.186773 0.0286179 0.000454003 -0.186773 0.0300971 -0.0117977 -0.186773 0.0816986 -0.0407383 -0.186773 0.0780199 -0.0413807 -0.186773 0.0839838 -0.0397318 -0.183973 0.0617309 -0.0402075 -0.175523 0.0617309 -0.0402075 -0.183973 0.0759331 -0.0406258 -0.175523 0.0963666 0.00195988 -0.185573 0.0868252 0.00324137 -0.18495 0.0891492 0.00317291 -0.179351 0.094222 0.00302348 -0.175523 0.0953965 0.00298889 -0.181561 0.0918414 0.00309361 -0.182152 0.0923129 0.00307972 -0.182481 0.0929943 0.00305965 -0.182481 0.0937505 0.00303737 -0.180923 0.0727813 0.00365505 -0.180723 0.0727813 0.00365505 -0.176073 0.0774293 0.00351814 -0.176696 0.0751053 0.0035866 -0.178398 0.073404 0.00363671 -0.180823 0.0718317 0.00368302 -0.179973 0.0686608 0.00377643 -0.184048 0.0679584 0.00379712 -0.182152 0.069073 0.00376429 -0.182481 0.0705106 0.00372194 -0.183248 0.073404 0.00363671 -0.179973 0.0919008 0.00309186 -0.178398 0.0908505 0.0031228 -0.179351 0.0925227 0.00307354 -0.176696 0.0891492 0.00317291 -0.18495 0.0751053 0.0035866 -0.18495 0.0651596 0.00387956 -0.180923 0.0674836 0.0038111 -0.178398 0.0668609 0.00382945 -0.176073 0.0628356 0.00394802 -0.175523 0.0679584 0.00379712 -0.176073 0.0534397 0.00422479 -0.175523 0.0448684 0.00447727 -0.179494 0.0458331 0.00444886 -0.180086 0.0484235 0.00437255 -0.179166 0.0465144 0.00442879 -0.182523 0.0468925 0.00441765 -0.184211 0.0501531 0.0043216 -0.180923 0.0487917 0.0043617 -0.181673 0.0483641 0.0043743 -0.180723 0.0487917 0.0043617 -0.186573 0.0448684 0.00447727 -0.185573 0.0534397 0.00422479 -0.186573 0.0679584 0.00379712 -0.185573 0.0628356 0.00394802 -0.175523 0.0431827 -0.0187856 -0.175523 0.0460324 -0.0227349 -0.186573 0.0489573 -0.0236117 -0.175523 0.0514271 -0.0265456 -0.184279 0.0521192 -0.0322882 -0.186573 0.0870231 -0.0275941 -0.175523 0.0896613 -0.0248107 -0.186573 0.0926327 -0.0241076 -0.175023 0.0956297 0.00241478 -0.175023 0.0958072 0.00222646 -0.175023 0.0448533 -0.0215171 -0.175023 0.0514501 -0.0250239 -0.175023 0.0444135 0.00374035 -0.175023 0.0443392 0.00349243 -0.175023 0.0448537 0.00397749 -0.175023 0.0436825 -0.0188003 -0.175023 0.0491009 -0.0231328 -0.175023 0.046176 -0.022256 -0.175023 0.0948388 -0.021787 -0.175023 0.0881467 -0.0249586 -0.175023 0.0846016 -0.036948 -0.175023 0.0827073 -0.0384819 -0.175023 0.086531 -0.0275052 -0.175023 0.0618335 -0.0397181 -0.175023 0.0550946 -0.0376685 -0.186073 0.0514359 0.0312955 -0.186573 0.0430568 0.0275406 -0.184973 0.0473199 0.027415 -0.186573 0.0473199 0.027415 -0.185773 0.075834 0.0444581 -0.184973 0.075834 0.0444581 -0.186191 0.0754964 0.0329965 -0.186073 0.0755081 0.0333945 -0.185773 0.066727 0.0409568 -0.184973 0.0664883 0.032853 -0.186073 0.0905278 0.033841 -0.186073 0.090419 0.0301472 -0.185773 0.0914686 0.0359355 -0.184973 0.0914686 0.0359355 -0.185773 0.092952 0.037334 -0.186073 0.0757172 0.0404908 -0.186073 0.0757179 0.0338221 -0.186073 0.0767087 0.0349 -0.186073 0.0835692 0.0386127 -0.186073 0.0667211 0.0407558 -0.186073 0.0663278 0.0340987 -0.186073 0.0587721 0.0393431 -0.186073 0.0527927 0.0324415 -0.186073 0.0515447 0.0349893 -0.186073 0.0654022 0.035233 -0.185773 0.0972948 0.0386119 -0.184973 0.0949705 0.0384926 -0.185773 0.0493303 0.038619 -0.184973 0.0493303 0.038619 -0.185773 0.0473835 0.0398943 -0.184973 0.0473835 0.0398943 -0.184973 0.0698258 0.0476347 -0.184973 0.0683559 0.0472439 -0.185773 0.0683559 0.0472439 -0.185773 0.0672666 0.0461824 -0.184973 0.0672666 0.0461824 -0.185773 0.074467 0.0470639 -0.185773 0.0730227 0.0475405 -0.186273 0.0664893 0.0327067 -0.184973 0.0667267 0.0318455 -0.186271 0.0664875 0.03278 -0.186265 0.0664883 0.032853 -0.184973 0.0674368 0.0310923 -0.184973 0.0684285 0.030795 -0.186265 0.0754844 0.032588 -0.186573 0.0754747 0.032442 -0.184973 0.0751871 0.0315963 -0.186573 0.0744338 0.0308862 -0.184973 0.0744338 0.0308862 -0.186573 0.0734264 0.0306478 -0.186273 0.0576525 0.0343261 -0.186573 0.0528847 0.0322639 -0.186573 0.0794728 0.0352087 -0.186573 0.0843915 0.0335384 -0.186273 0.0843915 0.0335384 -0.186273 0.0890297 0.0311992 -0.186573 0.0890297 0.0311992 -0.186573 0.0514271 -0.0265456 -0.186573 0.050147 -0.0242379 -0.175523 0.050147 -0.0242379 -0.175523 0.0489573 -0.0236117 -0.186573 0.0896613 -0.0248107 -0.186573 0.0884368 -0.0253658 -0.175523 0.0884368 -0.0253658 -0.175523 0.0435076 -0.0204864 -0.186573 0.0435076 -0.0204864 -0.186573 0.0445207 -0.0218905 -0.175523 0.0445207 -0.0218905 -0.186573 0.0941915 -0.0233536 -0.186573 0.0952856 -0.0220116 -0.175523 0.0941915 -0.0233536 -0.175523 0.0952856 -0.0220116 -0.175523 0.0828669 -0.0389557 -0.175523 0.0850319 -0.0372027 -0.175523 0.0524341 -0.0349018 -0.183973 0.0524341 -0.0349018 -0.175523 0.0528493 -0.0362547 -0.175523 0.0537096 -0.0373783 -0.175523 0.0549073 -0.0381321 -0.186573 0.0443647 0.00435808 -0.186573 0.043988 0.00400299 -0.186573 0.0438394 0.00350715 -0.175523 0.0438394 0.00350715 -0.186573 0.0962474 0.0024636 -0.186573 0.0958923 0.00284025 -0.186573 0.0953965 0.00298889 -0.184973 0.0905278 0.033841 -0.184973 0.0907899 0.0349818 -0.186173 0.0909764 0.0353329 -0.185773 0.0910305 0.035417 -0.186073 0.0909251 0.035247 -0.186073 0.0907899 0.0349818 -0.185773 0.0511356 0.0365922 -0.185773 0.0507289 0.0371356 -0.184973 0.0507289 0.0371356 -0.186073 0.0513502 0.0361436 -0.184973 0.0923161 0.0266257 -0.186573 0.0923161 0.0266257 -0.186573 0.0908958 0.0281323 -0.184973 0.0908958 0.0281323 -0.186273 0.0905147 0.0291518 -0.186073 0.0904173 0.0300026 -0.184973 0.0906783 0.0286082 -0.186573 0.0512817 0.0303074 -0.184973 0.0510865 0.0297744 -0.184973 0.0514359 0.0312955 -0.186073 0.051429 0.031151 -0.186573 0.0510865 0.0297744 -0.184973 0.0501815 0.0285028 -0.184973 0.0488589 0.0276743 -0.186573 0.0488589 0.0276743 -0.186273 0.0899877 0.0303221 -0.186573 0.0905147 0.0291518 -0.186273 0.0512817 0.0303074 -0.186273 0.0518768 0.0314447 -0.186273 0.0528847 0.0322639 -0.186273 0.0626611 0.0357039 -0.186573 0.0640307 0.0356805 -0.186273 0.0652781 0.0350762 -0.186273 0.0661492 0.0340086 -0.186273 0.0754747 0.032442 -0.186273 0.0758909 0.0337216 -0.186573 0.0759035 0.033743 -0.186273 0.0768233 0.0347361 -0.186273 0.0780959 0.0352645 -0.180723 0.0665541 -0.00736637 -0.180723 0.0668353 0.002181 -0.178698 0.0498853 0.00268029 -0.177216 0.0510858 -0.00691073 -0.180723 0.0490617 -0.00685111 -0.184665 0.051842 0.00262265 -0.180923 0.0490617 -0.00685111 -0.182473 0.0496511 0.00268719 -0.182948 0.0498853 0.00268029 -0.182948 0.049604 -0.00686708 -0.183787 0.0505286 0.00266134 -0.184973 0.0531099 -0.00697035 -0.184973 0.0533912 0.00257702 -0.182948 0.066293 0.00219698 -0.182473 0.0662459 -0.0073573 -0.183787 0.0653684 -0.00733145 -0.184431 0.0648112 0.00224062 -0.184973 0.0625058 -0.00724713 -0.176673 0.0627871 0.00230025 -0.177216 0.06453 -0.00730675 -0.178698 0.0660117 -0.0073504 -0.176673 0.0533912 0.00257702 -0.178698 0.0735936 -0.00757373 -0.178698 0.0738749 0.00197364 -0.177216 0.0753566 0.00192999 -0.182948 0.0738749 0.00197364 -0.184973 0.0773808 0.00187037 -0.180923 0.0908249 0.00147435 -0.182473 0.0902355 -0.00806395 -0.184665 0.0880446 -0.00799941 -0.184431 0.0888008 0.00153397 -0.176673 0.0867767 0.00159359 -0.177216 0.0888008 0.00153397 -0.176981 0.0880446 -0.00799941 -0.177859 0.0896392 0.00150927 -0.178698 0.0902826 0.00149032 -0.177859 0.089358 -0.0080381 -0.180723 0.0908249 0.00147435 -0.176673 0.0864954 -0.00795378 -0.175023 0.0439667 -0.0202885 -0.175523 0.0443647 0.00435808 -0.175023 0.0446018 0.00391789 -0.175523 0.043988 0.00400299 -0.175523 0.0510129 -0.0252665 -0.175023 0.0519236 -0.0264858 -0.175023 0.0504606 -0.0238485 -0.175023 0.0958668 0.0019746 -0.175523 0.0962474 0.0024636 -0.175523 0.0958923 0.00284025 -0.175023 0.0953818 0.0024891 -0.175023 0.0952102 -0.0203181 -0.175523 0.0957099 -0.0203329 -0.175023 0.0529305 -0.0348419 -0.175023 0.0532938 -0.0360257 -0.175023 0.0540466 -0.0370089 -0.175023 0.0938815 -0.0229613 -0.175523 0.0688134 -0.0410475 -0.175023 0.0688281 -0.0405477 -0.175523 0.0759331 -0.0406258 -0.175023 0.0758594 -0.0401313 -0.175023 0.0925176 -0.023621 -0.175523 0.0926327 -0.0241076 -0.175523 0.0841069 -0.0382737 -0.175023 0.0837923 -0.0378852 -0.175023 0.0895462 -0.0243241 -0.175523 0.0875119 -0.0263416 -0.175023 0.0870897 -0.0260738 -0.175523 0.0870231 -0.0275941 -0.175523 0.085526 -0.0358765 -0.175023 0.085034 -0.0357876 -0.185973 0.0457515 0.03752 -0.185873 0.0458925 0.0372944 -0.185873 0.0452603 0.0376221 -0.185873 0.0449056 0.0376727 -0.185873 0.0445485 0.0376431 -0.185873 0.0438982 0.0373532 -0.185973 0.0440522 0.0375701 -0.185873 0.0440996 0.037482 -0.184073 0.0464578 0.0360263 -0.185873 0.0462671 0.0368323 -0.185873 0.0456989 0.0374349 -0.184073 0.0438982 0.0373532 -0.184073 0.0432592 0.0361205 -0.185873 0.043497 0.0369139 -0.184073 0.0463199 0.0367249 -0.183973 0.0465578 0.0360234 -0.184073 0.0458925 0.0372944 -0.184073 0.0452603 0.0376221 -0.184073 0.0445485 0.0376431 -0.183973 0.0445292 0.0377412 -0.184073 0.043438 0.0368098 -0.183973 0.0433492 0.0368558 -0.185973 0.0728659 0.0445079 -0.185973 0.0724118 0.045113 -0.185873 0.0723471 0.0450367 -0.185873 0.0721536 0.0451772 -0.185873 0.0713603 0.045415 -0.185973 0.0717401 0.0454612 -0.185973 0.0702928 0.0451754 -0.185873 0.0703528 0.0450955 -0.185873 0.0697138 0.0438628 -0.185973 0.0696139 0.0438657 -0.185973 0.0698039 0.0445981 -0.185873 0.0729125 0.0437686 -0.185873 0.0727745 0.0444672 -0.184073 0.0727217 0.0445745 -0.185873 0.0727217 0.0445745 -0.184073 0.0721536 0.0451772 -0.185873 0.071715 0.0453644 -0.185873 0.0710032 0.0453854 -0.185873 0.0705543 0.0452243 -0.185873 0.0699517 0.0446561 -0.185873 0.0698927 0.0445521 -0.184073 0.0729125 0.0437686 -0.183973 0.0730124 0.0437656 -0.183973 0.0728098 0.044622 -0.184073 0.0713603 0.045415 -0.183973 0.0713632 0.045515 -0.184073 0.0705543 0.0452243 -0.183973 0.0705069 0.0453123 -0.184073 0.0699517 0.0446561 -0.185973 0.095567 0.0345797 -0.185873 0.0959047 0.0353701 -0.185873 0.0973133 0.036129 -0.185973 0.0973163 0.0362289 -0.185973 0.0981592 0.0359762 -0.185873 0.0988655 0.0344826 -0.185873 0.0986748 0.0352885 -0.185873 0.0981067 0.0358912 -0.184073 0.0981067 0.0358912 -0.185873 0.0965074 0.0359383 -0.184073 0.0959047 0.0353701 -0.184073 0.0956669 0.0345768 -0.184073 0.0986748 0.0352885 -0.183973 0.0981592 0.0359762 -0.184073 0.0973133 0.036129 -0.183973 0.0973163 0.0362289 -0.184073 0.0965074 0.0359383 -0.183973 0.0964599 0.0360263 -0.185973 0.114357 0.0124545 -0.185873 0.114213 0.0125211 -0.185873 0.113645 0.0131238 -0.185873 0.112852 0.0133616 -0.185873 0.112495 0.013332 -0.185973 0.111784 0.013122 -0.185873 0.111844 0.0130421 -0.185873 0.111384 0.0124986 -0.185873 0.111443 0.0126027 -0.185873 0.114266 0.0124138 -0.185873 0.113838 0.0129833 -0.185873 0.113206 0.013311 -0.184073 0.112852 0.0133616 -0.185873 0.112046 0.0131709 -0.185873 0.111205 0.0118094 -0.183973 0.114504 0.0117122 -0.184073 0.114213 0.0125211 -0.184073 0.113645 0.0131238 -0.184073 0.112046 0.0131709 -0.184073 0.111443 0.0126027 -0.185873 0.113592 -0.0158372 -0.185873 0.113454 -0.0151386 -0.185873 0.113027 -0.0145691 -0.185973 0.110973 -0.0144303 -0.185873 0.111234 -0.0143815 -0.185873 0.110572 -0.0150537 -0.185873 0.113401 -0.0150312 -0.185873 0.112833 -0.0144286 -0.185873 0.112395 -0.0142413 -0.185873 0.11204 -0.0141908 -0.184073 0.111234 -0.0143815 -0.185873 0.111683 -0.0142204 -0.185873 0.111033 -0.0145103 -0.185873 0.110631 -0.0149496 -0.184073 0.113401 -0.0150312 -0.183973 0.113692 -0.0158401 -0.183973 0.11349 -0.0149838 -0.184073 0.112833 -0.0144286 -0.183973 0.112886 -0.0143435 -0.184073 0.11204 -0.0141908 -0.183973 0.112043 -0.0140908 -0.183973 0.111187 -0.0142934 -0.183973 0.110546 -0.0148971 -0.184073 0.110631 -0.0149496 -0.184073 0.110394 -0.015743 -0.185973 0.0934422 -0.0375533 -0.185873 0.0937799 -0.0367629 -0.185973 0.0936948 -0.0367104 -0.185873 0.0943826 -0.0361948 -0.185973 0.0943351 -0.0361067 -0.185873 0.0951885 -0.0360041 -0.185973 0.0951915 -0.0359041 -0.185873 0.0959819 -0.0362419 -0.185873 0.09655 -0.0368445 -0.185973 0.096638 -0.0367971 -0.185973 0.0968407 -0.0376534 -0.184073 0.0967407 -0.0376505 -0.184073 0.0951885 -0.0360041 -0.184073 0.0935421 -0.0375562 -0.184073 0.0937799 -0.0367629 -0.184073 0.0941811 -0.0363236 -0.183973 0.0936322 -0.036821 -0.184073 0.0937209 -0.036867 -0.183973 0.0941211 -0.0362436 -0.184073 0.0943826 -0.0361948 -0.184073 0.0948315 -0.0360337 -0.183973 0.0948121 -0.0359356 -0.183973 0.0955683 -0.0359578 -0.183973 0.09624 -0.036306 -0.184073 0.0955432 -0.0360546 -0.184073 0.0959819 -0.0362419 -0.184073 0.0961754 -0.0363823 -0.184073 0.0966028 -0.0369519 -0.183973 0.0966941 -0.0369112 -0.184073 0.09655 -0.0368445 -0.185873 0.0702861 -0.0453927 -0.185873 0.0701481 -0.0446942 -0.185873 0.0700954 -0.0445868 -0.185873 0.0690886 -0.0437969 -0.185873 0.0687339 -0.0437463 -0.185973 0.0676664 -0.0439859 -0.185873 0.0679279 -0.043937 -0.185873 0.0670875 -0.0452985 -0.185873 0.0672663 -0.0446093 -0.185873 0.0673253 -0.0445052 -0.184073 0.0700954 -0.0445868 -0.185873 0.0697207 -0.0441246 -0.185873 0.0695272 -0.0439841 -0.185873 0.0683768 -0.0437759 -0.184073 0.0687339 -0.0437463 -0.184073 0.0679279 -0.043937 -0.185873 0.0677264 -0.0440659 -0.184073 0.0673253 -0.0445052 -0.183973 0.070386 -0.0453957 -0.183973 0.0701834 -0.0445394 -0.183973 0.0695797 -0.0438991 -0.184073 0.0695272 -0.0439841 -0.183973 0.0687368 -0.0436464 -0.183973 0.0678805 -0.043849 -0.183973 0.0672402 -0.0444527 -0.184073 0.0670875 -0.0452985 -0.185873 0.0413722 -0.0352192 -0.185973 0.0412871 -0.0351666 -0.185873 0.0427808 -0.0344603 -0.185873 0.044333 -0.0361067 -0.185873 0.0441423 -0.0353008 -0.185873 0.0435742 -0.0346981 -0.184073 0.0435742 -0.0346981 -0.185873 0.0419748 -0.034651 -0.184073 0.0413722 -0.0352192 -0.184073 0.0441423 -0.0353008 -0.184073 0.0427808 -0.0344603 -0.183973 0.0436267 -0.034613 -0.183973 0.0419274 -0.034563 -0.184073 0.0419748 -0.034651 -0.184073 0.0411344 -0.0360125 -0.185873 0.0258339 -0.0124518 -0.185973 0.0257489 -0.0123993 -0.185873 0.0264366 -0.0118836 -0.185973 0.0263891 -0.0117956 -0.185873 0.0272425 -0.0116929 -0.185873 0.0280359 -0.0119307 -0.185973 0.0280884 -0.0118457 -0.185873 0.028604 -0.0125334 -0.185973 0.0286921 -0.0124859 -0.184073 0.0287947 -0.0133393 -0.184073 0.028604 -0.0125334 -0.184073 0.0280359 -0.0119307 -0.183973 0.0286921 -0.0124859 -0.184073 0.0272425 -0.0116929 -0.184073 0.0264366 -0.0118836 -0.184073 0.0258339 -0.0124518 -0.183973 0.0257489 -0.0123993 -0.185973 0.0263078 0.0143102 -0.185873 0.0266455 0.0151006 -0.185873 0.0272482 0.0156687 -0.185973 0.0289 0.0157067 -0.185873 0.0296063 0.014213 -0.185873 0.0294156 0.015019 -0.184073 0.0296063 0.014213 -0.185873 0.0288475 0.0156216 -0.185873 0.0280541 0.0158594 -0.184073 0.0272482 0.0156687 -0.184073 0.0266455 0.0151006 -0.185873 0.0264077 0.0143072 -0.184073 0.0294156 0.015019 -0.184073 0.0288475 0.0156216 -0.184073 0.0280541 0.0158594 -0.183973 0.0289 0.0157067 -0.183973 0.0272007 0.0157568 -0.183973 0.0265604 0.0151531 -0.184073 0.0264077 0.0143072 -0.184973 0.0627871 0.00230025 -0.182703 0.0491455 0.00435128 -0.184431 0.051367 0.00263664 -0.185219 0.051661 0.00427718 -0.183248 0.0668609 0.00382945 -0.183787 0.0656496 0.00221593 -0.180723 0.0493429 0.00269627 -0.180923 0.0493429 0.00269627 -0.180923 0.0668353 0.002181 -0.177216 0.051367 0.00263664 -0.178398 0.0494144 0.00434336 -0.176696 0.0511157 0.00429325 -0.177216 0.0648112 0.00224062 -0.176696 0.0651596 0.00387956 -0.178698 0.066293 0.00219698 -0.180723 0.0674836 0.0038111 -0.184973 0.0867767 0.00159359 -0.185573 0.0774293 0.00351814 -0.184431 0.0753566 0.00192999 -0.180923 0.0733325 0.00198961 -0.182948 0.0902826 0.00149032 -0.183248 0.0908505 0.0031228 -0.183787 0.0896392 0.00150927 -0.180723 0.0733325 0.00198961 -0.180723 0.0914732 0.00310445 -0.180923 0.0914732 0.00310445 -0.176673 0.0773808 0.00187037 -0.176073 0.0868252 0.00324137 -0.184973 0.100008 0.0255457 -0.184973 0.0403744 0.0264079 -0.184973 0.0415922 0.0272665 -0.186573 0.0415922 0.0272665 -0.186573 0.090328 -0.0351009 -0.184973 0.0917426 -0.0345776 -0.184973 0.0902146 -0.0351147 -0.186573 0.0888246 -0.0349803 -0.184973 0.0886083 -0.0349062 -0.186573 0.0866326 -0.0330125 -0.184973 0.0866326 -0.0330125 -0.184973 0.0518426 -0.0299931 -0.186573 0.0516623 -0.0315932 -0.184973 0.0516623 -0.0315932 -0.184973 0.051498 -0.0319775 -0.184973 0.0505485 -0.0331494 -0.186573 0.0507847 -0.0329432 -0.184973 0.049194 -0.0338129 -0.186573 0.0493956 -0.0337575 -0.186573 0.0477889 -0.0338636 -0.186573 0.0463047 -0.0332392 -0.184973 0.0463047 -0.0332392 -0.186773 0.107534 -0.0188185 -0.186773 0.10296 -0.0262277 -0.186573 0.0970752 -0.0326766 -0.186773 0.0897539 -0.0374325 -0.186573 0.0898487 -0.0376085 -0.186573 0.0817548 -0.0409302 -0.186573 0.0731471 -0.0424965 -0.186773 0.0731321 -0.042297 -0.186773 0.0644286 -0.0420407 -0.186573 0.0559013 -0.0401687 -0.186773 0.0559687 -0.0399803 -0.186773 0.0481219 -0.0362061 -0.186773 0.0412314 -0.030883 -0.186773 0.0355982 -0.0242435 -0.186573 0.0312835 -0.0166538 -0.186573 0.028826 -0.00825701 -0.186773 0.0314685 -0.0165779 -0.186773 0.0290228 -0.0082212 -0.186773 0.111101 0.00419734 -0.186773 0.104878 0.0215392 -0.186773 0.101164 0.0264884 -0.186788 0.109829 0.0102474 -0.186788 0.107743 0.0160606 -0.186773 0.107813 0.0160918 -0.186897 0.0309906 0.0125378 -0.186973 0.0373959 0.0244227 -0.186973 0.036657 0.0234361 -0.186897 0.033409 0.0182032 -0.186832 0.0333705 0.0182232 -0.186832 0.0309495 0.0125518 -0.186832 0.0405947 0.0281763 -0.186788 0.0451976 0.0322876 -0.186788 0.0405484 0.0282219 -0.186832 0.0452366 0.0322357 -0.186897 0.0504522 0.0355198 -0.186973 0.0584277 0.0387764 -0.186788 0.056042 0.0381298 -0.186832 0.0620074 0.039712 -0.186832 0.0681295 0.0404512 -0.186773 0.068123 0.0405925 -0.186788 0.0743 0.0403342 -0.186832 0.0742933 0.0402696 -0.186773 0.0803967 0.0393083 -0.186788 0.0862232 0.0372408 -0.186832 0.0916724 0.0343431 -0.186788 0.0917064 0.0343983 -0.186773 0.0917466 0.0344635 -0.186788 0.0967048 0.0307704 -0.186832 0.101058 0.0263953 -0.186832 0.0966629 0.0307209 -0.186788 0.101107 0.026438 -0.186832 0.0287593 0.000449839 -0.186973 0.0294586 0.00657244 -0.186788 0.0293371 0.00659443 -0.186832 0.029401 0.00658288 -0.186897 0.0294436 0.00657516 -0.186973 0.0334225 0.0181962 -0.186973 0.0328716 0.0170935 -0.186973 0.031005 0.0125329 -0.186973 0.02997 0.00898385 -0.186773 0.0308157 0.0125974 -0.186788 0.0333129 0.0182531 -0.186788 0.0308881 0.0125727 -0.186832 0.0366096 0.0234705 -0.186897 0.0366447 0.023445 -0.186973 0.0504595 0.0355063 -0.186897 0.0452626 0.032201 -0.186897 0.0406256 0.0281459 -0.186973 0.0433452 0.030651 -0.186788 0.0365571 0.0235086 -0.186773 0.0364952 0.0235535 -0.186788 0.0504009 0.035615 -0.186832 0.0504317 0.0355579 -0.186832 0.0560639 0.0380687 -0.186897 0.0560785 0.0380279 -0.186897 0.0681314 0.0404079 -0.186897 0.0620158 0.0396695 -0.186773 0.0560161 0.0382018 -0.186788 0.0619948 0.0397757 -0.186773 0.06198 0.0398508 -0.186788 0.0681265 0.040516 -0.186897 0.0742888 0.0402265 -0.186897 0.0803503 0.0391294 -0.186897 0.0861807 0.0371412 -0.186773 0.074308 0.0404103 -0.186788 0.0803775 0.0392342 -0.186832 0.0803612 0.0391714 -0.186832 0.0861977 0.0371811 -0.186897 0.0916496 0.0343062 -0.186773 0.0862532 0.0373112 -0.186897 0.0966349 0.0306878 -0.186897 0.104722 0.0214397 -0.186973 0.10403 0.0224599 -0.186973 0.101014 0.0263567 -0.186897 0.101025 0.0263668 -0.186773 0.0967543 0.0308288 -0.186788 0.104814 0.021498 -0.186832 0.104759 0.021463 -0.186832 0.107684 0.0160342 -0.186897 0.107644 0.0160165 -0.186897 0.109725 0.0102185 -0.186973 0.10971 0.0102145 -0.186832 0.110961 0.00418039 -0.186832 0.109767 0.0102301 -0.186897 0.110918 0.0041752 -0.186788 0.111306 -0.00198169 -0.186788 0.111025 0.00418817 -0.180198 0.0687707 -0.00573093 -0.179573 0.0698527 -0.0057628 -0.180823 0.0698306 -0.00651355 -0.180823 0.0688697 0.00332008 -0.180198 0.0690371 0.00331515 -0.179741 0.069228 -0.0057444 -0.179741 0.0694945 0.00330168 -0.179741 0.0704775 -0.00578121 -0.179573 0.0701192 0.00328327 -0.179741 0.0707439 0.00326487 -0.180198 0.0709348 -0.00579468 -0.179351 0.0692828 0.00375811 -0.179123 0.0701325 0.00373308 -0.179351 0.0709821 0.00370805 -0.180198 0.0712013 0.0032514 -0.179973 0.0716041 0.00368973 -0.179741 0.0459881 -0.00505983 -0.179741 0.0472375 -0.00509664 -0.180823 0.0478623 -0.00511504 -0.179846 0.0473918 -0.00510118 -0.179605 0.0468909 -0.00508642 -0.179605 0.0463348 -0.00507004 -0.180198 0.0455308 -0.00504636 -0.179846 0.0458338 -0.00505529 -0.179605 0.0466013 0.00397603 -0.179573 0.0466128 -0.00507823 -0.179605 0.0471573 0.00395965 -0.179846 0.0476583 0.00394489 -0.180198 0.0476949 -0.00511011 -0.180281 0.0457536 0.004001 -0.180086 0.0453616 0.00446274 -0.179846 0.0461003 0.00399079 -0.179166 0.0472707 0.00440651 -0.179494 0.047952 0.00438644 -0.180281 0.048005 0.00393468 -0.179573 0.0930927 -0.00644737 -0.179741 0.0924679 -0.00642897 -0.180823 0.0930705 -0.00719812 -0.180823 0.0943421 -0.00648418 -0.180823 0.0918432 -0.00641057 -0.180198 0.0920106 -0.0064155 -0.180198 0.0922771 0.00263058 -0.179741 0.0927344 0.00261711 -0.179573 0.0933591 0.0025987 -0.179741 0.0937174 -0.00646577 -0.180198 0.0941747 -0.00647925 -0.180823 0.0916731 0.00309856 -0.179123 0.0933724 0.00304851 -0.179741 0.0939839 0.0025803 -0.180198 0.0944412 0.00256683 -0.179973 0.094844 0.00300516 -0.180823 0.0946086 0.0025619 -0.183973 0.067607 0.0323198 -0.183973 0.068458 0.0317945 -0.184973 0.0734264 0.0306478 -0.183973 0.0744848 0.0326174 -0.183973 0.0678375 0.0446936 -0.184973 0.0754844 0.032588 -0.183973 0.0688495 0.0463742 -0.183973 0.0681233 0.0456665 -0.184973 0.0668379 0.0447231 -0.184973 0.075492 0.0459401 -0.183973 0.0739231 0.0462247 -0.184973 0.074467 0.0470639 -0.183973 0.0729602 0.0465425 -0.184973 0.0730227 0.0475405 -0.184934 0.0519056 -0.030516 -0.183973 0.0457153 -0.034047 -0.184973 0.047686 -0.0338448 -0.183973 0.0474913 -0.0348257 -0.183973 0.0494301 -0.0347846 -0.183973 0.0511715 -0.0339316 -0.184973 0.0507847 -0.0329432 -0.184973 0.0357808 -0.021862 -0.183973 0.0349361 -0.0223975 -0.183973 0.0342411 -0.0212281 -0.184973 0.0323558 -0.0148702 -0.184973 0.0317092 -0.0130066 -0.184973 0.0303428 -0.00734924 -0.183973 0.0288177 0.000443056 -0.184973 0.0300484 0.00369757 -0.184973 0.0306635 0.00752258 -0.184973 0.0327554 0.014364 -0.183973 0.0344921 0.0201308 -0.183973 0.0361895 0.0227784 -0.184973 0.035354 0.0196236 -0.183973 0.0412032 0.0281877 -0.183973 0.0396374 0.0270839 -0.184973 0.0430568 0.0275406 -0.183973 0.0501743 0.0301841 -0.183973 0.0505451 0.0350187 -0.183973 0.0504363 0.031325 -0.184973 0.0515447 0.0349893 -0.184973 0.0513502 0.0361436 -0.183973 0.0504155 0.0357882 -0.183973 0.0500012 0.0364496 -0.184973 0.0450703 0.0401503 -0.184973 0.0358286 0.0335116 -0.183973 0.0237302 0.00952451 -0.184973 0.0216209 0.00066011 -0.183973 0.0226205 0.000630666 -0.184973 0.0994213 0.0376661 -0.184973 0.0972948 0.0386119 -0.183973 0.0952528 0.0375333 -0.184973 0.092952 0.037334 -0.183973 0.093638 0.0366064 -0.183973 0.0921545 0.0352079 -0.183973 0.0917021 0.0345721 -0.184973 0.090419 0.0301472 -0.184973 0.0915068 0.0272855 -0.183973 0.0922344 0.0279715 -0.183973 0.0931881 0.0272928 -0.184973 0.0927784 0.0263806 -0.184973 0.0985625 0.0259056 -0.184973 0.0942995 0.0260312 -0.184973 0.101174 0.024617 -0.183973 0.100451 0.0264424 -0.183973 0.098592 0.0269052 -0.183973 0.111182 -0.00197806 -0.184973 0.109201 -0.00967213 -0.184973 0.107504 -0.0152392 -0.183973 0.103737 -0.0244137 -0.184973 0.106749 -0.0170615 -0.183973 0.101962 -0.0267626 -0.183973 0.103643 -0.0245476 -0.184973 0.0983231 -0.0292928 -0.184973 0.0864054 -0.0310112 -0.183973 0.0882537 -0.0358412 -0.184973 0.0872679 -0.033997 -0.183973 0.0865303 -0.0346722 -0.18458 0.0861023 -0.032688 -0.184973 0.0864804 -0.0325816 -0.186073 0.0517218 0.0315711 -0.186073 0.0626216 0.0359 -0.186073 0.0575861 0.0345147 -0.186191 0.0665003 0.0332615 -0.186073 0.066512 0.0336595 -0.186073 0.0640854 0.035873 -0.186273 0.0640388 0.0356786 -0.186273 0.0757231 0.0406919 -0.186273 0.0836343 0.0388018 -0.186273 0.0511356 0.0365922 -0.186173 0.0511847 0.036505 -0.186073 0.0512308 0.0364162 -0.186273 0.0582451 0.0394003 -0.186271 0.0754809 0.0325151 -0.186273 0.0794728 0.0352087 -0.186073 0.0795237 0.0354021 -0.186073 0.0780608 0.0354614 -0.186073 0.089132 0.0313711 -0.186073 0.0844689 0.0337228 -0.186073 0.0901498 0.0304392 -0.185873 0.0756235 0.0407055 -0.185973 0.0755401 0.0412715 -0.185973 0.0730102 0.0473409 -0.185973 0.0743582 0.046896 -0.185773 0.075492 0.0459401 -0.185973 0.0670378 0.0447172 -0.185973 0.0684547 0.0470699 -0.185773 0.0668379 0.0447231 -0.185873 0.0510462 0.0365469 -0.185973 0.0506274 0.0369506 -0.185773 0.0450703 0.0401503 -0.185973 0.0473159 0.0397061 -0.185773 0.111546 0.0240639 -0.185973 0.10598 0.0313076 -0.185973 0.111375 0.0239613 -0.185973 0.115289 0.0157308 -0.185973 0.117585 0.00691053 -0.185773 0.117782 0.00694238 -0.185773 0.118379 -0.00219005 -0.185773 0.0949705 0.0384926 -0.185973 0.0992997 0.0375073 -0.185973 0.0916057 0.03579 -0.185973 0.091559 0.0357449 -0.185873 0.0911171 0.0353666 -0.187573 0.0495602 0.0263743 -0.187573 0.0509124 0.0263345 -0.187573 0.0507119 0.0266017 -0.187122 0.0897732 -0.0275588 -0.187573 0.0896278 -0.0268223 -0.187573 0.0893226 -0.0269583 -0.187573 0.0904589 -0.0272531 -0.187122 0.0486839 -0.0263484 -0.187573 0.0913382 0.0255689 -0.176673 0.0770995 -0.00767701 -0.184973 0.0770995 -0.00767701 -0.184431 0.0750754 -0.00761738 -0.177216 0.0750754 -0.00761738 -0.180723 0.0730513 -0.00755776 -0.180923 0.0730513 -0.00755776 -0.182948 0.0735936 -0.00757373 -0.179173 0.0902355 -0.00806395 -0.180723 0.0905437 -0.00807303 -0.180923 0.0905437 -0.00807303 -0.184973 0.0864954 -0.00795378 -0.183787 0.089358 -0.0080381 -0.176673 0.0625058 -0.00724713 -0.184665 0.064055 -0.00729276 -0.180923 0.0665541 -0.00736637 -0.178698 0.049604 -0.00686708 -0.176673 0.0531099 -0.00697035 -0.184431 0.0510858 -0.00691073 -0.213123 0.111882 -0.00199867 -0.213123 0.0971076 -0.0327147 -0.213123 0.11071 -0.0106794 -0.213123 0.108763 0.0151429 -0.213123 0.0281181 0.000468725 -0.213123 0.0479906 -0.0364189 -0.213123 0.0428924 0.0311848 -0.213123 0.036842 0.0248506 -0.213123 0.0322408 0.0173969 -0.213123 0.0292898 0.00914949 -0.213123 0.0817688 -0.0409782 -0.213123 0.0643952 -0.0422884 -0.213123 0.0731509 -0.0425463 -0.224773 0.0552172 0.0615053 -0.224773 0.0557339 0.061323 -0.224773 0.0562245 0.0626948 -0.224773 0.0560091 0.0639526 -0.224773 0.0557829 0.0636855 -0.224773 0.055289 0.0639416 -0.224773 0.0547329 0.0639579 -0.224773 0.0542248 0.0637314 -0.224773 0.0535546 0.063468 -0.224773 0.0538653 0.0633069 -0.224773 0.0535665 0.0619728 -0.224773 0.0538334 0.0622226 -0.224773 0.0541673 0.0617777 -0.224773 0.0884224 0.0605272 -0.224773 0.0894952 0.0603285 -0.224773 0.0900978 0.0608967 -0.224773 0.0903356 0.06169 -0.224773 0.0899858 0.0617003 -0.224773 0.0895441 0.062691 -0.224773 0.087776 0.0630169 -0.224773 0.0873158 0.0624735 -0.224773 0.0873277 0.0609783 -0.224773 0.0878959 0.0603756 -0.224773 0.0886892 0.0601378 -0.224773 0.116116 0.0448357 -0.224773 0.116367 0.0445705 -0.224773 0.116228 0.044032 -0.224773 0.118839 0.0431548 -0.224773 0.118285 0.0449492 -0.224773 0.132355 0.0137509 -0.224773 0.132035 0.0136084 -0.224773 0.133533 0.0155094 -0.224773 0.134337 0.0156214 -0.224773 0.134905 0.0150188 -0.224773 0.135096 0.0142128 -0.224773 0.134606 0.0136846 -0.224773 0.134917 0.0135235 -0.224773 0.134457 0.0129801 -0.224773 0.133739 0.0130336 -0.224773 0.133806 0.0126902 -0.224773 0.132689 0.013306 -0.224773 0.132463 0.0130389 -0.224773 0.131694 -0.0204553 -0.224773 0.133252 -0.0205011 -0.224773 0.133864 -0.0203418 -0.224773 0.13226 -0.018275 -0.224773 0.132192 -0.0179316 -0.224773 0.131542 -0.0182216 -0.224773 0.131082 -0.018765 -0.224773 0.130903 -0.0194542 -0.224773 0.113952 -0.0491961 -0.224773 0.115002 -0.0494685 -0.224773 0.11551 -0.049242 -0.224773 0.11587 -0.0488175 -0.224773 0.116359 -0.0482893 -0.224773 0.11601 -0.048279 -0.224773 0.115568 -0.0472883 -0.224773 0.114518 -0.0470159 -0.224773 0.1138 -0.0469624 -0.224773 0.11401 -0.0472424 -0.224773 0.113161 -0.0481951 -0.224773 0.113618 -0.0487511 -0.224773 0.0847827 -0.0630352 -0.224773 0.0854266 -0.0627128 -0.224773 0.0860588 -0.0630405 -0.224773 0.0861665 -0.0637526 -0.224773 0.0860885 -0.0649182 -0.224773 0.0863863 -0.065102 -0.224773 0.0841844 -0.065623 -0.224773 0.0836162 -0.0650204 -0.224773 0.0839151 -0.0636863 -0.224773 0.0509497 -0.064477 -0.224773 0.0502296 -0.0644881 -0.224773 0.0500141 -0.0632303 -0.224773 0.0505047 -0.0618585 -0.224773 0.0513004 -0.0620176 -0.224773 0.0513107 -0.0616678 -0.224773 0.0519202 -0.0622034 -0.224773 0.0523641 -0.0626742 -0.224773 0.0526722 -0.0625082 -0.224773 0.052513 -0.0633039 -0.224773 0.0528629 -0.0633142 -0.224773 0.0523733 -0.0638423 -0.224773 0.0526841 -0.0640034 -0.224773 0.0520138 -0.0642669 -0.224773 0.0522239 -0.0645468 -0.224773 0.0217725 -0.0445254 -0.224773 0.021413 -0.0449499 -0.224773 0.0209234 -0.0454781 -0.224773 0.0211142 -0.046284 -0.224773 0.0216823 -0.0468867 -0.224773 0.0224756 -0.0471245 -0.224773 0.0222088 -0.0467351 -0.224773 0.0232816 -0.0469338 -0.224773 0.0236325 -0.0461005 -0.224773 0.0237722 -0.045562 -0.224773 0.0241221 -0.0455723 -0.224773 0.0233305 -0.0445713 -0.224773 0.0228367 -0.0443152 -0.224773 0.0222806 -0.0442989 -0.224773 0.00575313 -0.01479 -0.224773 0.00539362 -0.0152146 -0.224773 0.00525392 -0.015753 -0.224773 0.00566293 -0.0171513 -0.224773 0.00645627 -0.0173892 -0.224773 0.00618947 -0.0169998 -0.224773 0.00674553 -0.0170162 -0.224773 0.00726223 -0.0171984 -0.224773 0.00775284 -0.0158266 -0.224773 0.00791197 -0.015031 -0.224773 0.00734383 -0.0144284 -0.224773 0.00731118 -0.0148359 -0.224773 0.00681729 -0.0145799 -0.224773 0.00825672 0.0165628 -0.224773 0.00885935 0.0171309 -0.224773 0.00824812 0.0169716 -0.224773 0.00909718 0.0179243 -0.224773 0.00890646 0.0187303 -0.224773 0.00815447 0.0190351 -0.224773 0.00753467 0.0192209 -0.224773 0.00754498 0.0195707 -0.224773 0.00673901 0.01938 -0.224773 0.00613638 0.0188118 -0.224773 0.00690501 0.0190719 -0.224773 0.00608927 0.0172125 -0.224773 0.00665742 0.0166099 -0.224773 0.00635618 0.0174624 -0.224773 0.0251926 0.0451129 -0.224773 0.02599 0.0457124 -0.224773 0.0266012 0.0458718 -0.224773 0.0263495 0.046137 -0.224773 0.0266483 0.0474711 -0.224773 0.0264892 0.0466754 -0.224773 0.0263402 0.0473051 -0.224773 0.0260802 0.0480737 -0.224773 0.0252765 0.0479617 -0.224773 0.0246469 0.0478127 -0.224773 0.0241761 0.0473688 -0.224773 0.0236404 0.0467594 -0.224773 0.0239903 0.046749 -0.224773 0.0238311 0.0459534 -0.224773 0.0243993 0.0453508 -0.186473 0.0322408 0.0173969 -0.186473 0.0428924 0.0311848 -0.213123 0.0501275 0.0361226 -0.186473 0.0582311 0.0394483 -0.186473 0.0668491 0.0410164 -0.213123 0.0582311 0.0394483 -0.213123 0.0668491 0.0410164 -0.186473 0.0756047 0.0407585 -0.213123 0.0756047 0.0407585 -0.213123 0.0841155 0.0386858 -0.213123 0.0920093 0.0348889 -0.213123 0.0989412 0.0295338 -0.213123 0.104608 0.0228545 -0.186473 0.104608 0.0228545 -0.213123 0.111223 0.00673601 -0.220228 0.134606 0.0136846 -0.219229 0.129971 0.0199808 -0.220205 0.134153 0.0153236 -0.220003 0.133533 0.0155094 -0.220276 0.134404 0.0151195 -0.220802 0.135479 0.0167457 -0.220336 0.134713 0.014548 -0.220802 0.136218 0.0137045 -0.220067 0.134247 0.0132601 -0.219365 0.133588 0.00480176 -0.219902 0.134933 0.00620297 -0.219869 0.133739 0.0130336 -0.220746 0.137131 0.00739015 -0.220744 0.00343109 0.0111137 -0.21961 0.00626774 0.00918234 -0.220319 0.00450194 0.0104517 -0.219229 0.00656949 0.00110347 -0.219229 0.00725719 0.00873555 -0.21927 0.00695274 0.00737255 -0.219389 0.00675632 0.00835138 -0.219562 0.132433 0.0149165 -0.219768 0.132904 0.0153604 -0.220802 0.133043 0.024129 -0.219229 0.124525 0.0316989 -0.220802 0.126637 0.0364687 -0.219229 0.118717 0.0398987 -0.219642 0.117719 0.0427689 -0.219429 0.116669 0.0430413 -0.219497 0.117163 0.0427853 -0.220126 0.117235 0.0452216 -0.220802 0.114278 0.0505536 -0.220268 0.117791 0.0452052 -0.220333 0.118285 0.0449492 -0.220311 0.118619 0.0445042 -0.220205 0.118727 0.0439584 -0.219452 0.116335 0.0434863 -0.219562 0.116228 0.044032 -0.219735 0.116367 0.0445705 -0.220802 0.112036 0.0524055 -0.220802 0.105482 0.056986 -0.219229 0.101132 0.0545316 -0.220154 0.0879861 0.0627369 -0.220336 0.0890502 0.0629471 -0.220181 0.089878 0.0622461 -0.219801 0.0898461 0.0611618 -0.219229 0.0942397 0.057881 -0.219465 0.0879285 0.0607832 -0.220181 0.0538653 0.0633069 -0.220299 0.0542248 0.0637314 -0.220336 0.0547329 0.0639579 -0.220802 0.0611023 0.0664286 -0.220802 0.0637161 0.0667233 -0.220802 0.0719297 0.0669877 -0.220802 0.0746124 0.0668581 -0.219229 0.0743183 0.0625459 -0.220802 0.0853895 0.065245 -0.219768 0.0874869 0.0617739 -0.219229 0.0844081 0.0610357 -0.219587 0.0875946 0.0612282 -0.219587 0.0560848 0.0621563 -0.219465 0.0557253 0.0617318 -0.219229 0.0566342 0.0612695 -0.219229 0.0540674 0.0606604 -0.21948 0.0546612 0.0615217 -0.219614 0.0541673 0.0617777 -0.220802 0.0529823 0.0648441 -0.220802 0.0505026 0.0641504 -0.219229 0.0492542 0.0592061 -0.219229 0.0444299 0.0573133 -0.219229 0.0203877 0.0388019 -0.220802 0.0170086 0.0414969 -0.220276 0.0240417 0.0470688 -0.220321 0.0241761 0.0473688 -0.220321 0.0246469 0.0478127 -0.220276 0.0249542 0.0479292 -0.220205 0.0252765 0.0479617 -0.220003 0.0258963 0.0477759 -0.219768 0.0263402 0.0473051 -0.220802 0.0331002 0.0560906 -0.219229 0.0293363 0.0479524 -0.220802 0.0244659 0.0494426 -0.219229 0.0273695 0.046241 -0.219452 0.0263495 0.046137 -0.219429 0.02599 0.0457124 -0.220802 0.0155736 0.0396321 -0.219229 0.011354 0.0234748 -0.219229 0.00768867 0.0112441 -0.219869 0.00718396 0.0167615 -0.220802 0.0034446 0.0120621 -0.220321 0.00624841 0.0180082 -0.220276 0.00664205 0.0188825 -0.219562 0.00859833 0.0185643 -0.219229 0.0104184 0.0210744 -0.219489 0.00871358 0.0182622 -0.224473 0.00466128 -0.020486 -0.224473 0.0088311 -0.0310376 -0.224473 0.0146913 -0.0407527 -0.22181 0.012897 -0.0381457 -0.22181 0.0146913 -0.0407527 -0.224473 0.0220799 -0.0493626 -0.22181 0.0275681 -0.0542215 -0.22181 0.0307928 -0.0566297 -0.224473 0.0307928 -0.0566297 -0.22181 0.0405892 -0.0623529 -0.224473 0.062327 -0.0685823 -0.22181 0.0736677 -0.0689163 -0.224473 0.0849071 -0.0673671 -0.224473 0.0957345 -0.0639773 -0.22181 0.0895052 -0.0661684 -0.22181 0.0788275 -0.0684417 -0.22181 0.114976 -0.0520991 -0.22181 0.109103 -0.0567026 -0.22181 0.0996838 -0.0622217 -0.224473 0.129281 -0.0345857 -0.224473 0.122859 -0.0439389 -0.22181 0.122859 -0.0439389 -0.22181 0.117522 -0.0497523 -0.22181 0.134781 -0.0222474 -0.22181 0.134065 -0.0242978 -0.22181 0.137703 0.00785948 -0.224473 0.135339 0.0189561 -0.224473 0.131169 0.0295077 -0.22181 0.131169 0.0295077 -0.22181 0.12703 0.0367268 -0.224473 0.125309 0.0392227 -0.22181 0.125309 0.0392227 -0.224473 0.109207 0.0550997 -0.22181 0.109207 0.0550997 -0.22181 0.10325 0.058838 -0.22181 0.0888016 0.0648442 -0.224473 0.0888016 0.0648442 -0.22181 0.0827958 0.0662748 -0.22181 0.0776729 0.0670523 -0.224473 0.0663322 0.0673864 -0.22181 0.0663322 0.0673864 -0.224473 0.0550928 0.0658371 -0.22181 0.0550928 0.0658371 -0.22181 0.0610407 0.0668944 -0.22181 0.0401965 0.0606339 -0.22181 0.0442654 0.0624473 -0.224473 0.017141 0.042409 -0.224473 0.00292211 0.0118297 -0.224473 0.00593539 0.0227678 -0.22181 0.00517736 0.0205914 -0.224473 0.0107191 0.0330557 -0.221642 0.137072 -0.0129612 -0.220802 0.00269942 -0.00881399 -0.221784 0.00228948 -0.00923361 -0.22181 0.00229707 -0.00938942 -0.221193 0.00249679 -0.00865287 -0.220802 0.111181 -0.0546009 -0.22181 0.105851 -0.0588406 -0.220802 0.0994794 -0.0617986 -0.22181 0.0957345 -0.0639773 -0.220802 0.0893709 -0.0657182 -0.22181 0.0849071 -0.0673671 -0.220802 0.0814773 -0.0675663 -0.220802 0.070624 -0.0685422 -0.22181 0.067924 -0.0689834 -0.22181 0.062327 -0.0685823 -0.220802 0.0597545 -0.0677663 -0.22181 0.0570736 -0.0677797 -0.220802 0.0491499 -0.0652586 -0.22181 0.0511983 -0.0663741 -0.22181 0.0465539 -0.0648614 -0.220802 0.0467154 -0.0644201 -0.22181 0.0366342 -0.0603031 -0.220802 0.0368639 -0.0598932 -0.22181 0.0220799 -0.0493626 -0.220802 0.0199347 -0.0464554 -0.22181 0.0195876 -0.0467721 -0.22181 0.0088311 -0.0310376 -0.220802 0.00906773 -0.0304536 -0.22181 0.00766743 -0.0285628 -0.22181 0.00466128 -0.020486 -0.22181 0.00403267 -0.0182687 -0.220802 0.00509757 -0.0203054 -0.220802 0.0044868 -0.0181482 -0.22181 0.124724 -0.0415487 -0.220802 0.126097 -0.0388079 -0.22181 0.129281 -0.0345857 -0.220802 0.13011 -0.0320844 -0.220802 0.131468 -0.0293266 -0.22181 0.130527 -0.0323015 -0.220802 0.134335 -0.0220996 -0.220802 0.136668 -0.0129903 -0.22181 0.135933 0.0168671 -0.22176 0.137707 0.0076434 -0.221685 0.00291756 0.0114867 -0.220802 0.137272 0.00751491 -0.221115 0.137434 0.00739209 -0.22181 0.135339 0.0189561 -0.22181 0.132278 0.0271541 -0.220802 0.13185 0.0269619 -0.220802 0.128239 0.03391 -0.22181 0.120323 0.0453402 -0.220802 0.12193 0.0427948 -0.220802 0.119976 0.0450228 -0.22181 0.11792 0.0478327 -0.22181 0.112328 0.052774 -0.220802 0.103021 0.0584277 -0.220802 0.0957687 0.0619257 -0.22181 0.0994107 0.0608229 -0.22181 0.0933211 0.0633769 -0.220802 0.0931606 0.0629354 -0.220802 0.0827077 0.0658133 -0.22181 0.0719431 0.0674574 -0.22181 0.0503674 0.0646004 -0.220802 0.0426883 0.0612691 -0.220802 0.0404017 0.0602112 -0.220802 0.0310581 0.0547119 -0.22181 0.0341491 0.0573107 -0.22181 0.0307882 0.0550965 -0.22181 0.0250236 0.0505691 -0.220802 0.0227109 0.0477932 -0.22181 0.0223831 0.0481298 -0.22181 0.017141 0.042409 -0.22181 0.0151963 0.0399121 -0.220802 0.0109209 0.0324587 -0.22181 0.0107191 0.0330557 -0.220802 0.00982885 0.0304374 -0.220802 0.00636029 0.0225619 -0.22181 0.00941174 0.0306537 -0.22181 0.00593539 0.0227678 -0.220802 0.00562361 0.0204443 -0.22181 0.00292211 0.0118297 -0.221803 0.00291059 0.0117514 -0.224773 0.136783 -0.0133042 -0.224473 0.134065 -0.0242978 -0.224773 0.133783 -0.0241943 -0.224773 0.12902 -0.034437 -0.224773 0.122627 -0.0437491 -0.224473 0.114976 -0.0520991 -0.224773 0.114779 -0.0518734 -0.224473 0.105851 -0.0588406 -0.224773 0.105693 -0.0585853 -0.224773 0.0956214 -0.0636994 -0.224773 0.0848416 -0.0670743 -0.224473 0.0736677 -0.0689163 -0.224473 0.0511983 -0.0663741 -0.224773 0.051281 -0.0660857 -0.224473 0.0405892 -0.0623529 -0.224773 0.0309652 -0.0563841 -0.224773 0.0149344 -0.0405769 -0.224773 0.00909997 -0.0309046 -0.224773 0.00259466 -0.00935151 -0.224773 0.00321696 0.0117743 -0.224473 0.0250236 0.0505691 -0.224773 0.0252213 0.0503435 -0.224473 0.0341491 0.0573107 -0.224473 0.0442654 0.0624473 -0.224773 0.0551583 0.0655444 -0.224773 0.0663483 0.0670868 -0.224473 0.0776729 0.0670523 -0.224773 0.0776392 0.0667542 -0.224473 0.0994107 0.0608229 -0.224773 0.0992815 0.0605522 -0.224473 0.11792 0.0478327 -0.224773 0.1309 0.0293746 -0.224473 0.137703 0.00785948 -0.218289 0.00728169 -0.00396792 -0.187973 0.00722719 0.0010841 -0.218289 0.00785976 -0.00984437 -0.218289 0.00860552 -0.0139772 -0.218289 0.00986628 -0.0188697 -0.187973 0.0103804 -0.020497 -0.218289 0.0135447 -0.0282722 -0.218289 0.0159386 -0.0327214 -0.187973 0.0207247 -0.0396981 -0.187973 0.0282339 -0.0476631 -0.218289 0.028825 -0.0481829 -0.187973 0.0370122 -0.0542032 -0.218289 0.0413557 -0.0566519 -0.187973 0.0572786 -0.062263 -0.187973 0.0467928 -0.0591197 -0.218289 0.0605073 -0.0628434 -0.187973 0.0681509 -0.0635377 -0.218289 0.080634 -0.0626581 -0.218289 0.0790794 -0.0629052 -0.218289 0.0756243 -0.0633126 -0.218289 0.089732 -0.0603845 -0.218289 0.095123 -0.0583208 -0.218289 0.104022 -0.053551 -0.218289 0.116898 -0.042531 -0.218289 0.118974 -0.0400767 -0.187973 0.123438 -0.0337527 -0.218289 0.124641 -0.0317206 -0.218289 0.128895 -0.0225643 -0.187973 0.128355 -0.0239721 -0.218289 0.130457 -0.0177594 -0.218289 0.131627 -0.0128446 -0.219229 0.0421768 0.0562682 -0.219229 0.0147034 0.0303671 -0.21902 0.00759401 0.00868455 -0.21902 0.0116688 0.0233447 -0.21902 0.00918803 0.0161379 -0.219229 0.00885981 0.0162291 -0.219229 0.0237606 0.0426958 -0.21902 0.0191336 0.0366037 -0.219229 0.0188591 0.0368053 -0.21902 0.0493656 0.0588842 -0.219229 0.0642091 0.0624282 -0.219229 0.0718684 0.0626655 -0.21902 0.0718584 0.062325 -0.219229 0.0795005 0.0619778 -0.219229 0.086994 0.0603752 -0.21902 0.0869028 0.060047 -0.219229 0.113461 0.0454744 -0.219229 0.111455 0.0472812 -0.219229 0.10757 0.0503759 -0.219229 0.103219 0.0533034 -0.21902 0.126727 0.0269088 -0.219229 0.127033 0.0270582 -0.219218 0.133284 0.00351482 -0.219229 0.132034 0.0126008 -0.219229 0.133193 0.0050259 -0.218688 0.118276 0.0395301 -0.21902 0.122978 0.0335448 -0.219229 0.123264 0.0337299 -0.21902 0.118456 0.0396804 -0.218289 0.111766 0.0461332 -0.21902 0.0642402 0.062089 -0.21902 0.0794495 0.061641 -0.21902 0.0941096 0.0575662 -0.218688 0.09402 0.0573494 -0.219229 0.035505 0.0524987 -0.21902 0.0356902 0.0522127 -0.218688 0.0297049 0.0475108 -0.218688 0.0241797 0.0423018 -0.218289 0.0231018 0.0410011 -0.218685 0.00714544 0.00108651 -0.218688 0.00941403 0.016075 -0.218289 0.132538 0.00496586 -0.218688 0.132855 -0.00261648 -0.218688 0.13262 0.00497341 -0.21902 0.13309 -0.00262339 -0.21902 0.132854 0.00499482 -0.218289 0.131391 0.0124622 -0.21902 0.131701 0.012529 -0.218289 0.129619 0.018967 -0.218688 0.131472 0.0124796 -0.219229 0.129023 0.0225416 -0.21902 0.129649 0.0198694 -0.218688 0.126516 0.026806 -0.218688 0.129427 0.0197927 -0.218289 0.125287 0.0290201 -0.218289 0.11301 0.044995 -0.218289 0.119275 0.0381681 -0.218289 0.122711 0.0333723 -0.218688 0.122781 0.0334173 -0.218688 0.113067 0.0450553 -0.21902 0.113227 0.0452262 -0.218289 0.100809 0.0539583 -0.21902 0.107369 0.0501013 -0.218688 0.10723 0.0499123 -0.21902 0.100965 0.0542348 -0.218688 0.10085 0.0540304 -0.218688 0.08684 0.059821 -0.218289 0.0827213 0.0607331 -0.218688 0.0794144 0.0614091 -0.218688 0.0718515 0.0620905 -0.218289 0.0642691 0.061773 -0.218688 0.0642616 0.0618554 -0.218688 0.0567554 0.0607071 -0.218289 0.0609206 0.0613752 -0.218289 0.0494693 0.0585843 -0.21902 0.056706 0.0609365 -0.218688 0.0494423 0.0586625 -0.218289 0.050268 0.0588546 -0.218289 0.0567728 0.0606262 -0.21902 0.0423261 0.0559621 -0.218688 0.042429 0.0557512 -0.218289 0.0424653 0.0556769 -0.218289 0.0310669 0.0485103 -0.218688 0.0358177 0.0520159 -0.218289 0.0358627 0.0519464 -0.218289 0.0402149 0.0545224 -0.21902 0.0295546 0.0476909 -0.21902 0.0240088 0.0424625 -0.218688 0.0193227 0.0364648 -0.218289 0.0193894 0.0364158 -0.21902 0.0150002 0.0301999 -0.218688 0.0152046 0.0300849 -0.218289 0.0152767 0.0300443 -0.218688 0.00782593 0.00864943 -0.218289 0.00949376 0.0160529 -0.218688 0.0118856 0.0232551 -0.218289 0.0119621 0.0232235 -0.187973 0.00785976 -0.00984437 -0.185973 0.0122791 -0.0198686 -0.187973 0.0147126 -0.03055 -0.185973 0.0164734 -0.0296014 -0.185973 0.0222939 -0.0384582 -0.185973 0.0380628 -0.0525014 -0.185973 0.0475319 -0.0572612 -0.185973 0.0576837 -0.0603045 -0.185973 0.0682098 -0.0615386 -0.187973 0.0790794 -0.0629052 -0.185973 0.0891035 -0.0584858 -0.187973 0.089732 -0.0603845 -0.187973 0.099785 -0.0560523 -0.185973 0.0988364 -0.0542916 -0.187973 0.108933 -0.0500403 -0.187973 0.116898 -0.042531 -0.185973 0.115405 -0.0412009 -0.185973 0.121736 -0.0327021 -0.187973 0.131498 -0.0134863 -0.185973 0.130774 -0.00255516 -0.186473 0.036842 0.0248506 -0.185973 0.0317902 0.0176137 -0.186473 0.0292898 0.00914949 -0.185973 0.028804 0.0092678 -0.185973 0.0668114 0.041515 -0.185973 0.0580906 0.0399281 -0.186473 0.0501275 0.0361226 -0.186473 0.0920093 0.0348889 -0.186473 0.0841155 0.0386858 -0.185973 0.0756716 0.041254 -0.186473 0.111223 0.00673601 -0.186473 0.108763 0.0151429 -0.185973 0.109225 0.0153327 -0.186473 0.0989412 0.0295338 -0.220284 0.055289 0.0639416 -0.220154 0.0557829 0.0636855 -0.224773 0.0561168 0.0632406 -0.21997 0.0561168 0.0632406 -0.219768 0.0562245 0.0626948 -0.224773 0.0876266 0.0623124 -0.21997 0.0876266 0.0623124 -0.224773 0.0879861 0.0627369 -0.224773 0.0884942 0.0629634 -0.220284 0.0884942 0.0629634 -0.224773 0.0890502 0.0629471 -0.220299 0.0895441 0.062691 -0.224773 0.089878 0.0622461 -0.220003 0.0899858 0.0617003 -0.224773 0.116727 0.0449951 -0.224773 0.117235 0.0452216 -0.219937 0.116727 0.0449951 -0.224773 0.117791 0.0452052 -0.224773 0.118619 0.0445042 -0.224773 0.118727 0.0439584 -0.219489 0.1323 0.0146208 -0.224773 0.132433 0.0149165 -0.224773 0.132904 0.0153604 -0.224773 0.134597 0.0148528 -0.224773 0.134153 0.0153236 -0.220321 0.134597 0.0148528 -0.219442 0.131253 -0.0194645 -0.224773 0.131392 -0.0189261 -0.224773 0.131752 -0.0185015 -0.219517 0.131752 -0.0185015 -0.224773 0.132816 -0.0182914 -0.224773 0.13331 -0.0185474 -0.220228 0.133644 -0.0189924 -0.224773 0.133644 -0.0189924 -0.224773 0.133752 -0.0195381 -0.220321 0.133752 -0.0195381 -0.224773 0.11365 -0.0476669 -0.219429 0.11401 -0.0472424 -0.224773 0.115074 -0.0470322 -0.224773 0.115902 -0.0477332 -0.220035 0.115902 -0.0477332 -0.224773 0.0837754 -0.0642247 -0.219768 0.0837754 -0.0642247 -0.224773 0.0842746 -0.0632617 -0.219465 0.0842746 -0.0632617 -0.219427 0.0847827 -0.0630352 -0.224773 0.0853387 -0.0630516 -0.21948 0.0853387 -0.0630516 -0.224773 0.0858326 -0.0633076 -0.224773 0.0862743 -0.0642984 -0.224773 0.0501999 -0.0626105 -0.224773 0.0506707 -0.0621666 -0.219426 0.0516227 -0.0620697 -0.219442 0.0519202 -0.0622034 -0.219489 0.0521746 -0.0624112 -0.219562 0.0523641 -0.0626742 -0.224773 0.0212733 -0.0454884 -0.220035 0.021413 -0.0449499 -0.219497 0.0228367 -0.0443152 -0.224773 0.0236644 -0.0450162 -0.219429 0.0233305 -0.0445713 -0.219452 0.0236644 -0.0450162 -0.219562 0.0237722 -0.045562 -0.224773 0.00626123 -0.0145635 -0.224773 0.00764507 -0.0152809 -0.219434 0.00764507 -0.0152809 -0.219442 0.00775284 -0.0158266 -0.220336 0.00630044 0.0183301 -0.224773 0.00624841 0.0180082 -0.220321 0.00643421 0.018628 -0.224773 0.00643421 0.018628 -0.220205 0.00690501 0.0190719 -0.220003 0.00753467 0.0192209 -0.219768 0.00815447 0.0190351 -0.224773 0.00859833 0.0185643 -0.224773 0.00874733 0.0179346 -0.219442 0.00874733 0.0179346 -0.220336 0.0243823 0.0476218 -0.224773 0.0258963 0.0477759 -0.219562 0.0264892 0.0466754 -0.224473 0.133722 -0.00264201 -0.224473 0.134496 -0.0110127 -0.219828 0.133262 -0.00885915 -0.220194 0.13386 -0.0104596 -0.224473 0.133625 0.00321728 -0.21982 0.133622 0.00345624 -0.220513 0.134496 -0.0110127 -0.220513 0.134987 0.00566866 -0.221356 0.137185 0.00685274 -0.219624 0.00637446 -0.00474722 -0.21972 0.00621821 -0.00581122 -0.224473 0.00577326 -0.00657848 -0.219949 0.00573238 -0.00662614 -0.220268 0.00501267 -0.0071986 -0.219624 0.00671918 0.0069555 -0.220069 0.0059374 0.00914742 -0.219828 0.00642865 0.00850097 -0.224473 0.00501267 -0.0071986 -0.220268 0.00550405 0.00948279 -0.221784 0.00290537 0.0116746 -0.224473 0.00250867 -0.00863774 -0.224473 0.00228948 -0.00923361 -0.224473 0.00232647 -0.00899207 -0.221685 0.00231276 -0.00904659 -0.224473 0.00235984 -0.00889351 -0.221152 0.00265267 -0.00849168 -0.221546 0.00235984 -0.00889351 -0.221761 0.137095 -0.0131456 -0.22181 0.137078 -0.0133596 -0.221398 0.136859 -0.0125301 -0.224473 0.13688 -0.0125551 -0.221393 0.137408 0.00701662 -0.224473 0.13771 0.00770367 -0.22164 0.137673 0.00745981 -0.221426 0.137596 0.00726717 -0.224473 0.00281477 -0.00838268 -0.224773 0.0027663 -0.00879751 -0.224773 0.00515496 -0.00746271 -0.224773 0.00295705 -0.00864679 -0.224773 0.00624723 -0.00643295 -0.224473 0.00624982 -0.00572062 -0.224473 0.00637446 -0.00474722 -0.224473 0.0062776 0.00111207 -0.224473 0.00671918 0.0069555 -0.224773 0.00701697 0.00691917 -0.224773 0.00566164 0.00973807 -0.224473 0.00622682 0.00881898 -0.224473 0.00665205 0.00793455 -0.224473 0.00550405 0.00948279 -0.224473 0.00337965 0.0107942 -0.224773 0.00328867 0.0113131 -0.224473 0.00290537 0.0116746 -0.224773 0.137405 0.00782157 -0.224473 0.134987 0.00566866 -0.224473 0.137185 0.00685274 -0.224773 0.132963 -0.00871493 -0.224473 0.133263 -0.00872376 -0.224473 0.133573 -0.0100335 -0.224773 0.133532 -0.0105276 -0.224773 0.136463 -0.0125794 -0.224473 0.137044 -0.0128609 -0.224773 0.136779 -0.0130254 -0.224473 0.13662 -0.0123241 -0.220776 0.137208 0.00744418 -0.22032 0.136023 0.00679165 -0.219602 0.134165 0.00562228 -0.21947 0.13384 0.00522904 -0.220081 0.134093 0.00487476 -0.219952 0.133842 0.004431 -0.219229 0.133292 0.00382702 -0.219829 0.133629 0.00359491 -0.219214 0.133013 -0.00792127 -0.219214 0.132951 -0.00844527 -0.219815 0.133281 -0.00848544 -0.219815 0.133722 -0.00264201 -0.219214 0.133391 -0.00263225 -0.219815 0.133625 0.00321728 -0.219214 0.133294 0.00319655 -0.21982 0.133263 -0.00872376 -0.21984 0.133269 -0.00900067 -0.219969 0.133453 -0.00978034 -0.220039 0.133574 -0.0100358 -0.219563 0.133586 -0.0108068 -0.22093 0.135549 -0.0116627 -0.221356 0.13662 -0.0123241 -0.220983 0.136766 -0.0129254 -0.221408 0.136911 -0.0125967 -0.221426 0.137006 -0.012762 -0.220998 0.00259804 -0.00873365 -0.221111 0.00281477 -0.00838268 -0.220774 0.00276961 -0.00875402 -0.220685 0.00392331 -0.00778547 -0.219719 0.00551507 -0.00720325 -0.21947 0.00613593 -0.00650083 -0.219627 0.00637918 -0.00495271 -0.219313 0.00650026 -0.00565928 -0.219257 0.0065886 -0.00473381 -0.219624 0.0062776 0.00111207 -0.219257 0.00693216 0.00692952 -0.219677 0.00669229 0.00775744 -0.219901 0.00555517 0.00980049 -0.220685 0.00445112 0.0101328 -0.220774 0.00335637 0.0111676 -0.220802 0.00328989 0.0112315 -0.220998 0.00318396 0.0111573 -0.228673 0.0991458 -0.00532244 -0.228673 0.0933451 -0.0187998 -0.228673 0.107804 -0.0276682 -0.228673 0.0881265 -0.0240389 -0.228673 0.0242447 -0.00847329 -0.228673 0.0600618 -0.0285406 -0.228673 0.0509889 -0.0430916 -0.228673 0.0430967 -0.0385694 -0.228673 0.0479101 -0.0203172 -0.228673 0.0833409 0.025546 -0.228673 0.0894651 0.0214017 -0.228673 0.0943662 0.0158645 -0.228673 0.103762 0.0310645 -0.228673 0.0977362 0.0092824 -0.228673 0.0416552 0.0074095 -0.228673 0.0445786 0.0142018 -0.228673 0.0276734 0.018246 -0.228673 0.0549333 0.0245973 -0.228673 0.0535133 0.0426073 -0.228673 0.0690153 0.0287186 -0.228673 0.0803882 0.0444572 -0.228673 0.089011 0.0415616 -0.228673 0.101829 -0.0345265 -0.228673 0.0864866 -0.0441372 -0.228673 0.0686338 -0.0471449 -0.228673 0.0596117 -0.0459871 -0.229747 0.00338224 0.0116927 -0.228737 0.00291074 0.0117527 -0.228737 0.00290537 0.0116746 -0.228744 0.00295181 0.0113426 -0.229767 0.00342199 0.0116038 -0.228756 0.00310525 0.0110447 -0.228775 0.00337965 0.0107942 -0.229782 0.00345851 0.0115729 -0.229201 0.00445117 0.0101327 -0.231382 0.00718557 0.0068986 -0.231316 0.00714609 0.00798911 -0.230265 0.00662984 0.00801357 -0.231129 0.0067751 0.0090041 -0.230374 0.00671918 0.0069555 -0.22962 0.00501267 -0.0071986 -0.229876 0.00551087 -0.00684934 -0.230014 0.00577118 -0.00658097 -0.230315 0.00630526 -0.00552667 -0.230627 0.00504496 -0.00797556 -0.228775 0.00281477 -0.00838268 -0.230209 0.00395547 -0.00856521 -0.229755 0.0027806 -0.00923273 -0.22874 0.00231286 -0.00904614 -0.228737 0.00228948 -0.00923361 -0.229747 0.136618 -0.0132226 -0.229201 0.135549 -0.0116627 -0.22962 0.134496 -0.0110127 -0.230209 0.135471 -0.0124392 -0.230369 0.133263 -0.00872376 -0.229997 0.133804 -0.0103903 -0.230835 0.133904 -0.0113966 -0.230627 0.134418 -0.0117864 -0.230627 0.134955 0.00644562 -0.231382 0.133157 0.00318793 -0.230133 0.134009 0.00474734 -0.22962 0.134987 0.00566866 -0.229201 0.136077 0.0062555 -0.230209 0.136044 0.00703527 -0.229767 0.137191 0.00766344 -0.228758 0.13745 0.00705963 -0.228738 0.137709 0.00766965 -0.229744 0.137237 0.0078001 -0.224773 0.137043 0.00711685 -0.225073 0.137185 0.00685274 -0.224773 0.137411 0.0077125 -0.225073 0.134987 0.00566866 -0.224773 0.133322 0.00346508 -0.225073 0.133622 0.00345624 -0.224773 0.133997 0.0052411 -0.225073 0.134008 0.00474542 -0.225073 0.133281 -0.00848544 -0.225073 0.133722 -0.00264201 -0.225073 0.133625 0.00321728 -0.224773 0.133326 0.00319854 -0.225073 0.133348 -0.00946449 -0.224773 0.133058 -0.00954113 -0.225073 0.133773 -0.0103489 -0.225073 0.134496 -0.0110127 -0.224773 0.134338 -0.011268 -0.224773 0.136795 -0.0131957 -0.225073 0.136911 -0.0125968 -0.224773 0.136666 -0.0127703 -0.225073 0.13662 -0.0123241 -0.225073 0.00281477 -0.00838268 -0.225073 0.00243812 -0.00873777 -0.224773 0.0026386 -0.00900437 -0.225073 0.00228948 -0.00923361 -0.224773 0.00258935 -0.00924244 -0.224773 0.00667828 -0.00499502 -0.225073 0.00501267 -0.0071986 -0.225073 0.00599195 -0.00627536 -0.225073 0.00624982 -0.00572062 -0.225073 0.00637841 -0.00498618 -0.225073 0.0062776 0.00111207 -0.224773 0.00657747 0.00110324 -0.225073 0.00290537 0.0116746 -0.224773 0.00320524 0.0116657 -0.225073 0.00235984 -0.00889351 -0.22875 0.00243815 -0.00873773 -0.225073 0.00254226 -0.00859799 -0.228758 0.00254996 -0.00858944 -0.225073 0.137673 0.00746213 -0.228745 0.137632 0.00734281 -0.225073 0.137491 0.0071078 -0.228764 0.136774 -0.0124407 -0.22875 0.136978 -0.0127063 -0.225073 0.137072 -0.0129612 -0.22874 0.137084 -0.0130244 -0.225073 0.137078 -0.0133596 -0.228737 0.137078 -0.0133596 -0.22962 0.00550405 0.00948279 -0.225073 0.00337965 0.0107942 -0.229201 0.00392336 -0.00778544 -0.225073 0.00673719 0.00719382 -0.230371 0.00673531 0.00714537 -0.225073 0.00665205 0.00793455 -0.225073 0.00642728 0.00850352 -0.229997 0.00619553 0.00886031 -0.225073 0.00550405 0.00948279 -0.225073 0.00671918 0.0069555 -0.230146 0.00601465 -0.00623789 -0.228775 0.137185 0.00685274 -0.228775 0.13662 -0.0123241 -0.230369 0.133622 0.00345624 -0.225073 0.133263 -0.00872376 -0.230265 0.13337 -0.00954351 -0.230374 0.133722 -0.00264201 -0.230374 0.133625 0.00321728 -0.236973 0.116256 -0.0202697 -0.236973 0.111884 -0.0284371 -0.236973 0.106086 -0.0356621 -0.236673 0.0992332 -0.0419434 -0.236973 0.0990596 -0.0416988 -0.236973 0.0823102 -0.0494322 -0.236673 0.0638619 -0.0508906 -0.236973 0.0638983 -0.0505928 -0.236673 0.0547558 -0.0489092 -0.236973 0.0548464 -0.0486232 -0.236673 0.0461689 -0.0452883 -0.236673 0.0383935 -0.0401513 -0.236973 0.0385813 -0.0399173 -0.236673 0.0262998 -0.0260741 -0.236973 0.0265595 -0.0259237 -0.236673 0.0223934 -0.0176133 -0.236973 0.0226762 -0.0175132 -0.236673 0.0201081 -0.0085787 -0.236973 0.0204045 -0.00853228 -0.236973 0.0198217 0.000713109 -0.238473 0.0306475 0.0272399 -0.238473 0.04436 0.0401677 -0.238473 0.061976 0.0468639 -0.238473 0.0980048 0.0385875 -0.238173 0.104926 0.0321621 -0.238473 0.105144 0.0323679 -0.238173 0.110678 0.0247157 -0.238173 0.114868 0.0162901 -0.238173 0.117333 0.00720916 -0.238173 0.117979 -0.00217827 -0.238473 0.117629 0.007259 -0.230473 0.0249727 0.00957846 -0.230673 0.0236201 0.000601223 -0.230673 0.0247778 0.00962324 -0.230473 0.0278558 0.0181641 -0.230673 0.0276734 0.018246 -0.230673 0.0321955 0.0261383 -0.230473 0.0454748 0.038388 -0.230673 0.0381705 0.0329966 -0.230673 0.0453686 0.0385575 -0.230673 0.0535133 0.0426073 -0.230473 0.0623249 0.044793 -0.230673 0.0622916 0.0449903 -0.230673 0.0713662 0.0456149 -0.230673 0.089011 0.0415616 -0.230473 0.103616 0.0309273 -0.230473 0.109153 0.0237602 -0.230673 0.103762 0.0310645 -0.230673 0.109322 0.0238664 -0.230473 0.113185 0.0156506 -0.230673 0.113372 0.0157216 -0.230673 0.11638 -0.00213116 -0.228873 0.115558 0.00691013 -0.228673 0.115755 0.00694335 -0.228673 0.113372 0.0157216 -0.228873 0.109153 0.0237602 -0.228673 0.109322 0.0238664 -0.228873 0.103616 0.0309273 -0.228873 0.0967872 0.0368765 -0.228673 0.0969032 0.0370395 -0.228873 0.0803434 0.0442623 -0.228673 0.0713662 0.0456149 -0.228673 0.0622916 0.0449903 -0.228873 0.0535844 0.0424203 -0.228873 0.0454748 0.038388 -0.228673 0.0453686 0.0385575 -0.228873 0.0383077 0.0328511 -0.228873 0.0323585 0.0260223 -0.228673 0.0381705 0.0329966 -0.228673 0.0321955 0.0261383 -0.228873 0.02382 0.000595334 -0.228673 0.0247778 0.00962324 -0.228673 0.0236201 0.000601223 -0.237673 0.12763 -0.0126862 -0.237873 0.128625 -0.00249185 -0.237673 0.124684 -0.0225124 -0.237873 0.124498 -0.0224385 -0.237673 0.120077 -0.0316778 -0.237873 0.119907 -0.0315728 -0.237673 0.113948 -0.039904 -0.237873 0.113799 -0.039771 -0.237673 0.106484 -0.0469409 -0.237673 0.0979116 -0.0525749 -0.237673 0.0884908 -0.0566345 -0.237873 0.088428 -0.0564447 -0.237673 0.0682672 -0.0595895 -0.237873 0.0682731 -0.0593895 -0.237673 0.0580788 -0.0583949 -0.237673 0.0482525 -0.0554493 -0.237873 0.0581193 -0.058199 -0.237873 0.0391922 -0.0506719 -0.237673 0.023824 -0.0372492 -0.237873 0.0183662 -0.0285817 -0.237873 0.0143203 -0.019193 -0.237673 0.0141304 -0.0192559 -0.237873 0.0119662 -0.00924438 -0.237673 0.0117683 -0.00927329 -0.237673 0.0135452 0.0109132 -0.237873 0.012175 0.000938354 -0.237673 0.0164307 0.020539 -0.237673 0.020944 0.0295176 -0.237873 0.0207738 0.0296226 -0.237673 0.0269477 0.037576 -0.237873 0.0341356 0.0446264 -0.237873 0.0518233 0.0541552 -0.237673 0.0616651 0.0562793 -0.237673 0.0716974 0.05686 -0.237873 0.0616362 0.0564772 -0.237873 0.0717033 0.0570599 -0.237673 0.0816781 0.0556898 -0.237873 0.100388 0.0484612 -0.237673 0.108341 0.0422873 -0.237673 0.115234 0.0349754 -0.237873 0.115391 0.0350993 -0.237873 0.120929 0.0266724 -0.237673 0.120753 0.0265775 -0.237673 0.12473 0.0173489 -0.237873 0.12492 0.0174117 -0.237873 0.127242 0.00759877 -0.236873 0.0149383 0.0112157 -0.236673 0.0231513 0.030187 -0.236673 0.0296364 0.0382684 -0.236873 0.0229844 0.0302973 -0.236873 0.0373803 0.0451837 -0.236673 0.0464625 0.0502136 -0.236673 0.0562306 0.0536706 -0.236873 0.0561816 0.0538645 -0.236873 0.066455 0.0554734 -0.236673 0.0768248 0.0549687 -0.236873 0.0768491 0.0551672 -0.236873 0.08701 0.0529564 -0.236873 0.0965916 0.0489161 -0.236673 0.0964973 0.0487397 -0.236673 0.105143 0.043028 -0.236873 0.105268 0.0431839 -0.236873 0.112743 0.0359552 -0.236873 0.125671 0.00795392 -0.236673 0.126126 -0.00241824 -0.236873 0.126326 -0.00242413 -0.238273 0.118593 -0.0119275 -0.238473 0.115299 -0.0211111 -0.238273 0.110622 -0.0296736 -0.238473 0.104065 -0.0368977 -0.238273 0.0877155 -0.0473703 -0.238273 0.0782829 -0.0499309 -0.238273 0.0685319 -0.0506021 -0.238473 0.0685378 -0.0504022 -0.238473 0.0496538 -0.0460642 -0.238273 0.0410913 -0.0413874 -0.238473 0.0412073 -0.0412245 -0.238273 0.0277463 -0.0272324 -0.238473 0.0338673 -0.0348299 -0.238273 0.0233947 -0.0184805 -0.238273 0.020834 -0.00904789 -0.238473 0.0210313 -0.00901466 -0.238473 0.0203628 0.000697172 -0.229744 0.11348 -0.0527614 -0.228737 0.0982479 -0.0628948 -0.229744 0.0953875 -0.063611 -0.228737 0.105851 -0.0588406 -0.228737 0.106345 -0.0585328 -0.229744 0.106094 -0.0581351 -0.228741 0.089235 -0.0661642 -0.229784 0.089323 -0.0656185 -0.22878 0.0885087 -0.0657108 -0.228739 0.0893636 -0.0661708 -0.229744 0.089503 -0.0656786 -0.228737 0.0896382 -0.0661286 -0.228737 0.113781 -0.0531218 -0.228764 0.114131 -0.0522192 -0.229784 0.113529 -0.052578 -0.228783 0.11403 -0.051899 -0.230491 0.0888636 -0.0637294 -0.229483 0.0879442 -0.0635708 -0.230491 0.112204 -0.0511551 -0.229807 0.113495 -0.0525234 -0.229483 0.112577 -0.0503001 -0.229996 0.0820542 -0.0638424 -0.230653 0.0812773 -0.0650665 -0.231113 0.0813494 -0.063769 -0.231495 0.081823 -0.0626163 -0.230773 0.0831329 -0.0619333 -0.231709 0.0863245 -0.0609726 -0.23181 0.0828248 -0.0615316 -0.230912 0.0840218 -0.0614342 -0.23092 0.0843393 -0.0613409 -0.2308 0.0855425 -0.0613065 -0.231741 0.0861655 -0.0609243 -0.230469 0.0866511 -0.0617406 -0.231413 0.0873922 -0.0615185 -0.230969 0.0883413 -0.062515 -0.230091 0.115844 -0.0454447 -0.231364 0.115605 -0.0447043 -0.23019 0.115624 -0.0453692 -0.231413 0.115439 -0.044683 -0.231741 0.114079 -0.0447817 -0.2308 0.113731 -0.0454243 -0.231928 0.112385 -0.0457127 -0.23191 0.111971 -0.046168 -0.230912 0.112478 -0.0462952 -0.230773 0.111958 -0.0471718 -0.230722 0.111886 -0.0473841 -0.230454 0.11176 -0.0482569 -0.231113 0.111331 -0.0496534 -0.2288 0.0825386 -0.0667827 -0.230491 0.117819 -0.045862 -0.229807 0.119108 -0.047231 -0.22874 0.0820533 -0.0678859 -0.229749 0.0817202 -0.0675098 -0.229764 0.0817671 -0.0674619 -0.228755 0.0824004 -0.0675634 -0.228764 0.0824912 -0.0673911 -0.229784 0.0817906 -0.0674009 -0.228783 0.0825642 -0.0670635 -0.228741 0.119358 -0.0477848 -0.229749 0.119291 -0.0472694 -0.22878 0.118502 -0.0477553 -0.229744 0.0736059 -0.0684491 -0.228737 0.0736677 -0.0689163 -0.228737 0.0543254 -0.0671906 -0.228737 0.062327 -0.0685823 -0.229744 0.0624163 -0.0681195 -0.229744 0.0634439 -0.0682273 -0.229744 0.0725736 -0.0684962 -0.229744 0.128635 -0.0347659 -0.228737 0.129281 -0.0345857 -0.228737 0.122859 -0.0439389 -0.228776 0.0535606 -0.0663224 -0.229784 0.0543075 -0.0665913 -0.228765 0.0536022 -0.0665209 -0.229764 0.0543273 -0.0666535 -0.229749 0.0543712 -0.0667041 -0.22874 0.0540015 -0.0670502 -0.229744 0.133653 -0.0240552 -0.229749 0.133663 -0.0239874 -0.22874 0.134155 -0.023887 -0.22875 0.134104 -0.0235559 -0.228755 0.134049 -0.0234251 -0.228783 0.133698 -0.0230333 -0.2288 0.133442 -0.0229151 -0.230491 0.131745 -0.0233021 -0.229807 0.133547 -0.0238416 -0.230653 0.0476157 -0.0620904 -0.231709 0.0540336 -0.0610686 -0.231113 0.0483268 -0.0610028 -0.231495 0.0493133 -0.0602413 -0.230773 0.0507893 -0.0603048 -0.230912 0.0518086 -0.060317 -0.23191 0.0516656 -0.0598149 -0.231928 0.0522666 -0.0599453 -0.2308 0.0531894 -0.0609668 -0.231907 0.0528588 -0.0601785 -0.231808 0.0536297 -0.0606791 -0.230738 0.0534023 -0.0611633 -0.231741 0.05392 -0.0609473 -0.230969 0.055009 -0.0634127 -0.230469 0.0539325 -0.061897 -0.231364 0.05475 -0.06223 -0.230091 0.0542281 -0.0628067 -0.229847 0.0542623 -0.0633554 -0.229624 0.13307 -0.0165556 -0.230969 0.132648 -0.0157559 -0.231364 0.131465 -0.0160149 -0.230091 0.132042 -0.0165369 -0.231709 0.130304 -0.0167313 -0.230598 0.130795 -0.0170342 -0.231808 0.129914 -0.0171352 -0.2308 0.130202 -0.0175756 -0.23089 0.129862 -0.0180764 -0.231907 0.129414 -0.0179061 -0.231928 0.12918 -0.0184983 -0.23092 0.12963 -0.0186347 -0.23191 0.12905 -0.0190994 -0.230912 0.129552 -0.0189563 -0.231766 0.129077 -0.0203086 -0.231495 0.129476 -0.0214516 -0.230454 0.129911 -0.021014 -0.229996 0.130654 -0.0218644 -0.231113 0.130238 -0.0224381 -0.229483 0.131641 -0.022375 -0.229744 0.0467098 -0.0644181 -0.229749 0.0467776 -0.0644277 -0.228756 0.0473544 -0.0648068 -0.229784 0.046893 -0.0643686 -0.2288 0.0478498 -0.0642073 -0.228748 0.136114 -0.0169599 -0.228762 0.135828 -0.0171368 -0.229784 0.135826 -0.0164575 -0.229807 0.135762 -0.0164515 -0.228739 0.136325 -0.0166985 -0.229744 0.135968 -0.0163317 -0.229744 0.0409572 -0.0620077 -0.228737 0.0465483 -0.0648593 -0.228737 0.0405892 -0.0623529 -0.229744 0.0312731 -0.0563921 -0.228737 0.0307928 -0.0566297 -0.229744 0.0305911 -0.0559111 -0.228737 0.0303179 -0.0562933 -0.228737 0.0232125 -0.050454 -0.229784 0.0234967 -0.049926 -0.228757 0.0228985 -0.0496965 -0.229764 0.0234828 -0.0499898 -0.229749 0.0234955 -0.0500556 -0.229749 0.136745 0.0109552 -0.22875 0.136911 0.0115493 -0.228756 0.136785 0.0116443 -0.228764 0.136626 0.0117263 -0.228783 0.136298 0.0117992 -0.2288 0.136018 0.0117736 -0.230123 0.0216771 -0.0426468 -0.231113 0.0211115 -0.0420959 -0.230653 0.0199519 -0.0426822 -0.229483 0.0204648 -0.0433423 -0.231766 0.0235363 -0.042155 -0.230912 0.0244698 -0.0432428 -0.23181 0.0237869 -0.042255 -0.23191 0.024597 -0.0427365 -0.231928 0.0250522 -0.04315 -0.23089 0.0250768 -0.0439513 -0.230848 0.0252357 -0.0442447 -0.231808 0.0258659 -0.044467 -0.23049 0.0255214 -0.0456135 -0.231533 0.0261032 -0.0457662 -0.230008 0.025246 -0.0467837 -0.231364 0.0260606 -0.0463703 -0.230969 0.0256935 -0.0475241 -0.229813 0.0250364 -0.0471628 -0.230091 0.131616 0.016597 -0.23136 0.130864 0.0167713 -0.230469 0.130976 0.0158861 -0.230598 0.130785 0.0155431 -0.231739 0.130163 0.0154135 -0.2308 0.130542 0.0147775 -0.231907 0.130023 0.01411 -0.231928 0.130118 0.0134677 -0.23092 0.130576 0.0135744 -0.23191 0.130301 0.0128933 -0.231768 0.130926 0.0118572 -0.231498 0.131841 0.0110645 -0.230454 0.132009 0.0116545 -0.230658 0.134288 0.0105109 -0.229807 0.134795 0.0185312 -0.2288 0.134636 0.0176124 -0.229744 0.0180035 -0.0442451 -0.22875 0.0182106 -0.0448849 -0.229749 0.0180574 -0.0442874 -0.228756 0.0183674 -0.0449041 -0.228764 0.0185457 -0.0448958 -0.229784 0.0181869 -0.0442939 -0.228783 0.0188659 -0.0447951 -0.229807 0.0182416 -0.0442598 -0.228748 0.135354 0.0182667 -0.22878 0.134946 0.0177438 -0.229784 0.134853 0.0185581 -0.229749 0.134919 0.0186697 -0.229744 0.134914 0.0187381 -0.228737 0.0146913 -0.0407527 -0.229744 0.0153093 -0.0408035 -0.228737 0.0122321 -0.0371097 -0.229744 0.121996 0.0427151 -0.228737 0.125309 0.0392227 -0.229744 0.12737 0.0353295 -0.228737 0.127768 0.0355797 -0.229744 0.130535 0.0297257 -0.229784 0.00514646 -0.020088 -0.2288 0.00536379 -0.0191423 -0.228762 0.00480562 -0.0195004 -0.228753 0.00470059 -0.0196663 -0.229744 0.00508632 -0.020268 -0.228737 0.00463634 -0.0204032 -0.228737 0.122357 0.0430165 -0.22875 0.121789 0.0433549 -0.228764 0.121454 0.0433658 -0.228783 0.121134 0.0432652 -0.229807 0.121758 0.0427299 -0.2288 0.120904 0.0431027 -0.231113 0.00699589 -0.0121144 -0.230653 0.00569846 -0.0120424 -0.230491 0.00525873 -0.0121197 -0.231808 0.00992772 -0.016545 -0.23077 0.00942938 -0.016452 -0.231928 0.00988157 -0.0149976 -0.230912 0.00933073 -0.0147868 -0.230773 0.00883161 -0.0138979 -0.231766 0.00906627 -0.013378 -0.231495 0.00814858 -0.012588 -0.230454 0.00799065 -0.0131845 -0.229996 0.00692248 -0.0128193 -0.230473 0.00902984 -0.0174076 -0.231413 0.00924641 -0.0181572 -0.231364 0.00914471 -0.0182907 -0.230969 0.00824993 -0.0191063 -0.229927 0.00808045 -0.0183419 -0.229483 0.115419 0.0461781 -0.229624 0.11521 0.04596 -0.230091 0.11468 0.0450787 -0.230598 0.114487 0.0437507 -0.231808 0.114134 0.042937 -0.231907 0.114544 0.0421288 -0.23089 0.114923 0.0424214 -0.23191 0.115393 0.0412141 -0.230773 0.116407 0.0411927 -0.231498 0.117641 0.0404001 -0.229996 0.1186 0.0412131 -0.230658 0.120037 0.0411444 -0.22875 0.00308912 -0.0130792 -0.229784 0.00336407 -0.0125556 -0.228764 0.00337386 -0.0132562 -0.228783 0.00370148 -0.0133292 -0.229749 0.116504 0.0485256 -0.228762 0.117092 0.0480577 -0.22878 0.11699 0.047737 -0.229784 0.116503 0.048396 -0.2288 0.116788 0.0474684 -0.228739 0.116961 0.0487073 -0.229744 0.116465 0.048582 -0.229744 0.101637 0.0591789 -0.228737 0.101856 0.0595944 -0.228737 0.109682 0.0547634 -0.229744 0.109409 0.0543811 -0.228737 0.116787 0.0489241 -0.229749 0.00406085 0.0148637 -0.22878 0.00450085 0.0156789 -0.229784 0.00417365 0.0149275 -0.229744 0.00403157 0.0148017 -0.229749 0.0932224 0.0628978 -0.228756 0.0926455 0.0632769 -0.229764 0.0931578 0.0628798 -0.228783 0.0922683 0.0629333 -0.229784 0.0931069 0.0628387 -0.2288 0.0921501 0.0626774 -0.230658 0.00868675 0.021614 -0.229483 0.00835931 0.0208451 -0.230809 0.00982574 0.016079 -0.230892 0.0101474 0.0165642 -0.231928 0.0108196 0.0169684 -0.230916 0.0102986 0.0168962 -0.23092 0.01037 0.0171048 -0.23191 0.0109484 0.0175573 -0.23181 0.0109621 0.0185117 -0.230454 0.0100885 0.0194841 -0.231498 0.0105294 0.0199109 -0.230614 0.00924835 0.015535 -0.231481 0.008906 0.014654 -0.230464 0.00885309 0.0152949 -0.231409 0.0086771 0.0145441 -0.230327 0.00851452 0.0151489 -0.230107 0.00799436 0.0150128 -0.229976 0.00769628 0.014978 -0.230964 0.0849902 0.0618965 -0.229624 0.0857906 0.0623051 -0.230091 0.0857719 0.0612767 -0.230598 0.0862692 0.0600303 -0.231739 0.0860705 0.059427 -0.230738 0.0865976 0.0596333 -0.2308 0.0868105 0.0594368 -0.231907 0.0871296 0.0586543 -0.231928 0.0877333 0.0584154 -0.231768 0.0895318 0.0583095 -0.230883 0.0885384 0.0587437 -0.230773 0.0892107 0.0587749 -0.231118 0.0916644 0.0594636 -0.230658 0.0923789 0.0605482 -0.229483 0.0858627 0.0625986 -0.22874 0.00584517 0.0223725 -0.228753 0.00592433 0.0219521 -0.228756 0.00595486 0.0218868 -0.229784 0.00639629 0.022342 -0.228772 0.00615561 0.0216184 -0.228748 0.0861949 0.0653489 -0.22878 0.0864438 0.0647341 -0.229784 0.0856924 0.0650613 -0.2288 0.0864028 0.0644003 -0.229749 0.0856287 0.0651741 -0.228739 0.0859335 0.0655599 -0.229744 0.0100561 0.0308718 -0.228737 0.00964059 0.0310911 -0.229744 0.0113648 0.033236 -0.229744 0.0148539 0.0386439 -0.228737 0.017141 0.042409 -0.229744 0.0583433 0.0660053 -0.228737 0.0856745 0.0656607 -0.229744 0.076556 0.0666974 -0.229744 0.0674263 0.0669663 -0.228762 0.0211773 0.0463273 -0.22878 0.021498 0.0462254 -0.228739 0.0205277 0.0461963 -0.22874 0.0579466 0.066356 -0.228743 0.0578461 0.0662917 -0.229764 0.0582329 0.0659319 -0.228776 0.0574479 0.0656466 -0.228784 0.0574349 0.0655125 -0.2288 0.0217666 0.0460229 -0.229807 0.0582115 0.0658065 -0.2288 0.0574614 0.0652528 -0.229483 0.0274226 0.0487702 -0.230658 0.0280906 0.0492724 -0.230429 0.0282385 0.0467979 -0.231498 0.0288349 0.0468761 -0.23049 0.0282384 0.0466239 -0.231768 0.0286058 0.0456873 -0.23181 0.02851 0.045448 -0.230842 0.027889 0.0453047 -0.23191 0.0280209 0.0446283 -0.231928 0.0276149 0.0441828 -0.230859 0.026588 0.0440323 -0.231808 0.0262979 0.0433691 -0.231739 0.0259074 0.0432485 -0.230642 0.0256332 0.0437382 -0.231706 0.0257452 0.0432113 -0.23032 0.0246917 0.0437627 -0.230127 0.024235 0.0438855 -0.23136 0.0243812 0.0431764 -0.230964 0.0232287 0.0435476 -0.229946 0.0524457 0.0611184 -0.230135 0.052703 0.0607726 -0.23191 0.0563417 0.0595363 -0.231907 0.055125 0.0592584 -0.231808 0.0542199 0.0593073 -0.230761 0.054272 0.0598152 -0.231706 0.0536624 0.059447 -0.231481 0.0528062 0.0598534 -0.231409 0.0525966 0.0599967 -0.231768 0.0573777 0.060161 -0.231498 0.0581705 0.061076 -0.231118 0.0586476 0.0622267 -0.230491 0.0586452 0.0639763 -0.229847 0.0579738 0.0626433 -0.230318 0.0577419 0.0615719 -0.230475 0.0575508 0.0611935 -0.230491 0.0277958 0.0496252 -0.229807 0.0265051 0.0509934 -0.2288 0.0261323 0.0501388 -0.229483 0.0520557 0.0620408 -0.229744 0.0265199 0.0512315 -0.229749 0.0264776 0.0511776 -0.22874 0.026001 0.0513368 -0.228757 0.0258604 0.0508542 -0.229784 0.0264711 0.0510481 -0.228748 0.0509683 0.0645888 -0.229749 0.0505653 0.0641543 -0.229764 0.0506286 0.0641325 -0.229784 0.0506769 0.0640885 -0.2288 0.0516226 0.0638712 -0.228741 0.0507649 0.0646342 -0.228739 0.0506363 0.0646408 -0.228737 0.0262185 0.0515919 -0.229744 0.0504969 0.0641487 -0.229744 0.0446124 0.062081 -0.228737 0.041752 0.0613649 -0.229744 0.0346145 0.0570452 -0.228737 0.0341491 0.0573107 -0.229744 0.0339054 0.0566052 -0.228737 0.0336552 0.0570029 -0.22636 0.0259603 0.0512615 -0.226573 0.00403482 0.0155385 -0.22654 0.00592432 0.0219521 -0.226354 0.00374505 0.0152766 -0.226324 0.00459449 -0.020086 -0.226273 0.00276682 -0.0125024 -0.226294 0.00282341 -0.0127018 -0.226354 0.00291569 -0.0128788 -0.226543 0.00470058 -0.0196664 -0.226273 0.0220799 -0.0493626 -0.226354 0.0179602 -0.044798 -0.226573 0.0228982 -0.0497407 -0.226296 0.0230722 -0.0502898 -0.226354 0.0469487 -0.0649186 -0.226273 0.0511983 -0.0663741 -0.226273 0.0817374 -0.0679981 -0.226273 0.0849071 -0.0673671 -0.226573 0.0823923 -0.0675754 -0.226573 0.0888633 -0.0660442 -0.226294 0.0894351 -0.0661673 -0.226273 0.114976 -0.0520991 -0.226294 0.113926 -0.0529732 -0.226354 0.114033 -0.0528047 -0.226354 0.119358 -0.0477848 -0.226354 0.134154 -0.0238162 -0.226354 0.137084 0.0113489 -0.226273 0.11792 0.0478327 -0.226273 0.122357 0.0430165 -0.226294 0.116922 0.0487675 -0.226273 0.0934516 0.0633294 -0.226294 0.0932507 0.06338 -0.226354 0.0930512 0.0633886 -0.226273 0.0888016 0.0648442 -0.226294 0.0858698 0.0655926 -0.226573 0.0258627 0.0508984 -0.226573 0.0258604 0.0508542 -0.228753 0.0258666 0.0509399 -0.226296 0.0260693 0.051437 -0.226573 0.0214351 0.0462551 -0.228748 0.0208412 0.0463172 -0.226573 0.0210242 0.0463368 -0.226354 0.0206423 0.0462549 -0.228741 0.0206423 0.0462549 -0.226294 0.0204675 0.0461576 -0.226573 0.00404729 0.0155458 -0.228762 0.00417218 0.0156068 -0.2288 0.0048347 0.0156378 -0.228748 0.00388612 0.01543 -0.228741 0.00374506 0.0152766 -0.228739 0.00367505 0.0151686 -0.226294 0.00364234 0.0151049 -0.228737 0.00357429 0.0149096 -0.228756 0.00321531 -0.0131743 -0.226573 0.00320156 -0.0131654 -0.22874 0.00287899 -0.0128183 -0.2288 0.00398219 -0.0133036 -0.228748 0.00464627 -0.0197966 -0.22878 0.00505421 -0.0192737 -0.226273 0.0176431 -0.0445465 -0.226294 0.0177918 -0.0446908 -0.22874 0.0178981 -0.0447639 -0.226573 0.0183366 -0.0449023 -0.2288 0.0190962 -0.0446326 -0.226573 0.0187516 -0.0448449 -0.228762 0.0229077 -0.0495875 -0.226573 0.0228985 -0.0496965 -0.226573 0.0229858 -0.0493162 -0.22878 0.0230097 -0.0492669 -0.226573 0.0232121 -0.0489983 -0.226294 0.0467492 -0.06491 -0.226573 0.0473398 -0.0648143 -0.22875 0.047209 -0.0648686 -0.22874 0.0468779 -0.0649201 -0.228764 0.0475047 -0.0647105 -0.228783 0.0477316 -0.0644632 -0.226573 0.0476575 -0.0645635 -0.226573 0.0535555 -0.0661879 -0.2288 0.0535971 -0.0659302 -0.228737 0.0817374 -0.0679981 -0.226294 0.0819367 -0.0679415 -0.22875 0.0823142 -0.0676758 -0.226354 0.0821138 -0.0678492 -0.226573 0.0825501 -0.0671873 -0.226573 0.0885483 -0.065768 -0.2288 0.0883773 -0.0654011 -0.228762 0.0887355 -0.0659594 -0.228748 0.0890317 -0.0661187 -0.226354 0.089235 -0.0661642 -0.226273 0.0896382 -0.0661286 -0.228755 0.114138 -0.0524139 -0.22875 0.11412 -0.0525543 -0.22874 0.113999 -0.0528668 -0.228762 0.118823 -0.0478573 -0.226573 0.118976 -0.0478668 -0.228748 0.119159 -0.0478471 -0.228739 0.119472 -0.0477263 -0.226294 0.119532 -0.0476875 -0.228737 0.119689 -0.0475524 -0.226273 0.119689 -0.0475524 -0.226294 0.134145 -0.0240157 -0.226573 0.134049 -0.0234251 -0.228764 0.133945 -0.0232603 -0.226573 0.133442 -0.0229151 -0.226573 0.135953 -0.0170758 -0.226573 0.135568 -0.0172031 -0.22878 0.135499 -0.0172088 -0.226573 0.135965 -0.0170684 -0.228741 0.136255 -0.0168066 -0.226354 0.136255 -0.0168065 -0.226294 0.136358 -0.0166348 -0.22874 0.137121 0.0112883 -0.226573 0.136422 0.0117852 -0.226573 0.136798 0.0116354 -0.226294 0.137176 0.0111718 -0.226573 0.135279 0.0180984 -0.228762 0.135194 0.0179705 -0.226573 0.135003 0.0177834 -0.228741 0.135399 0.0184701 -0.226354 0.135399 0.0184701 -0.228739 0.135406 0.0185986 -0.226294 0.135402 0.0186701 -0.228737 0.135364 0.0188733 -0.226273 0.135364 0.0188733 -0.226294 0.122208 0.0431609 -0.228756 0.121633 0.0433741 -0.226573 0.121248 0.043315 -0.226573 0.121649 0.0433733 -0.226354 0.12204 0.0432681 -0.22874 0.122102 0.043234 -0.226573 0.120904 0.0431027 -0.226573 0.117102 0.0481963 -0.226573 0.116788 0.0474684 -0.228748 0.117082 0.0483938 -0.228741 0.11702 0.0485927 -0.226354 0.11702 0.0485927 -0.228737 0.0934516 0.0633294 -0.226573 0.0926601 0.0632843 -0.22875 0.0927909 0.0633387 -0.226573 0.0926731 0.0632907 -0.22874 0.093122 0.0633902 -0.228764 0.0924953 0.0631806 -0.226573 0.0923424 0.0630336 -0.228762 0.0863718 0.0650628 -0.226573 0.0863108 0.0651877 -0.226573 0.0864381 0.0648035 -0.228741 0.0860415 0.0654899 -0.226354 0.0860415 0.0654899 -0.226573 0.0236404 0.0467594 -0.224773 0.0238783 0.0475527 -0.224773 0.0244809 0.0481208 -0.224773 0.0252869 0.0483116 -0.224773 0.00589856 0.0180185 -0.226573 0.00673901 0.01938 -0.226573 0.00754498 0.0195707 -0.226573 0.00833832 0.0193329 -0.224773 0.00833832 0.0193329 -0.226573 0.00909718 0.0179243 -0.224773 0.00514189 -0.0149494 -0.224773 0.00574452 -0.0143813 -0.224773 0.00655049 -0.0141905 -0.226573 0.00655049 -0.0141905 -0.226573 0.00791197 -0.015031 -0.226573 0.0211613 -0.0446847 -0.224773 0.0211613 -0.0446847 -0.224773 0.0217639 -0.0441166 -0.224773 0.0225699 -0.0439259 -0.224773 0.0233632 -0.0441637 -0.226573 0.0225699 -0.0439259 -0.224773 0.0239313 -0.0447663 -0.226573 0.0233632 -0.0441637 -0.226573 0.0239313 -0.0447663 -0.224773 0.0499021 -0.0624266 -0.226573 0.0505047 -0.0618585 -0.224773 0.052104 -0.0619056 -0.226573 0.052104 -0.0619056 -0.226573 0.0526722 -0.0625082 -0.224773 0.0836044 -0.0635252 -0.224773 0.0840645 -0.0629818 -0.226573 0.0840645 -0.0629818 -0.224773 0.0847149 -0.0626919 -0.226573 0.0847149 -0.0626919 -0.226573 0.0864862 -0.0636101 -0.224773 0.0864862 -0.0636101 -0.226573 0.113161 -0.0481951 -0.226573 0.11334 -0.0475058 -0.224773 0.11334 -0.0475058 -0.224773 0.11445 -0.0466725 -0.226573 0.1138 -0.0469624 -0.224773 0.115162 -0.0466935 -0.224773 0.115794 -0.0470212 -0.226573 0.115162 -0.0466935 -0.226573 0.115794 -0.0470212 -0.224773 0.116222 -0.0475907 -0.226573 0.116359 -0.0482893 -0.226573 0.130903 -0.0194542 -0.224773 0.132904 -0.0179526 -0.226573 0.132904 -0.0179526 -0.224773 0.133536 -0.0182803 -0.224773 0.133963 -0.0188499 -0.226573 0.133963 -0.0188499 -0.224773 0.131897 0.014307 -0.226573 0.131897 0.014307 -0.224773 0.132135 0.0151004 -0.224773 0.132738 0.0156685 -0.224773 0.133544 0.0158592 -0.226573 0.133544 0.0158592 -0.226573 0.134905 0.0150188 -0.224773 0.116718 0.0454038 -0.226573 0.116718 0.0454038 -0.224773 0.117524 0.0455945 -0.224773 0.118318 0.0453567 -0.226573 0.118318 0.0453567 -0.224773 0.118886 0.0447541 -0.226573 0.118886 0.0447541 -0.226573 0.119076 0.0439481 -0.224773 0.087137 0.0617842 -0.226573 0.087137 0.0617842 -0.224773 0.0884264 0.0633068 -0.224773 0.0891381 0.0632858 -0.224773 0.0897703 0.0629581 -0.224773 0.0901977 0.0623886 -0.226573 0.0897703 0.0629581 -0.226573 0.0921501 0.0626774 -0.226573 0.0864028 0.0644003 -0.226573 0.0858627 0.0625986 -0.226573 0.0857735 0.0612664 -0.230469 0.0860675 0.060367 -0.226573 0.0862711 0.0600275 -0.230912 0.0881914 0.058787 -0.226573 0.0885359 0.0587438 -0.23092 0.0878697 0.058865 -0.226573 0.087257 0.0591272 -0.23089 0.0873114 0.0590971 -0.226573 0.0898545 0.0589533 -0.230598 0.0898591 0.0589551 -0.230454 0.0902491 0.0591464 -0.229996 0.0910994 0.0598889 -0.229483 0.09161 0.0608757 -0.226573 0.0884264 0.0633068 -0.226573 0.087776 0.0630169 -0.226573 0.0891381 0.0632858 -0.226573 0.0863034 0.0652002 -0.226573 0.0901977 0.0623886 -0.226573 0.09161 0.0608757 -0.226573 0.0894952 0.0603285 -0.226573 0.0909516 0.0597141 -0.226573 0.0873277 0.0609783 -0.226573 0.0873158 0.0624735 -0.229483 0.0230569 0.0446543 -0.226573 0.0230569 0.0446543 -0.229959 0.023882 0.0440371 -0.226573 0.0242371 0.0438848 -0.226573 0.0256384 0.0437388 -0.226573 0.0269518 0.0442488 -0.230779 0.0261696 0.04386 -0.23046 0.025066 0.0437173 -0.230904 0.0269509 0.0442481 -0.23092 0.0273726 0.0446025 -0.230773 0.0280434 0.0456448 -0.226573 0.0278876 0.045302 -0.226573 0.0244809 0.0481208 -0.226573 0.0238783 0.0475527 -0.226573 0.0210387 0.0463369 -0.226573 0.0252869 0.0483116 -0.226573 0.0261323 0.0501388 -0.226573 0.0260802 0.0480737 -0.226573 0.0266483 0.0474711 -0.226573 0.0274226 0.0487702 -0.226573 0.028044 0.0477782 -0.226573 0.0268391 0.0466651 -0.226573 0.0282384 0.0466239 -0.226573 0.0266012 0.0458718 -0.226573 0.0251926 0.0451129 -0.226573 0.0217666 0.0460229 -0.229483 0.00663643 0.0150977 -0.226573 0.00663643 0.0150977 -0.226573 0.0101483 0.0165659 -0.226573 0.0104966 0.0178831 -0.23087 0.0104966 0.0178831 -0.226573 0.00594426 0.0219081 -0.226573 0.00613638 0.0188118 -0.226573 0.00665742 0.0166099 -0.226573 0.0048347 0.0156378 -0.226573 0.00589856 0.0180185 -0.226573 0.00608927 0.0172125 -0.226573 0.00443149 0.0156732 -0.226573 0.00835931 0.0208451 -0.226573 0.00890646 0.0187303 -0.226573 0.00825672 0.0165628 -0.226573 0.00925328 0.0155386 -0.226573 0.00799625 0.0150131 -0.226573 0.00745076 0.0163721 -0.229483 0.00581258 -0.0128705 -0.226573 0.00719418 -0.0187092 -0.229483 0.00719418 -0.0187092 -0.230079 0.00836142 -0.0181452 -0.226573 0.00836324 -0.0181438 -0.230323 0.00878775 -0.0177345 -0.226573 0.00918379 -0.0171372 -0.226573 0.00950208 -0.0158782 -0.226573 0.00318954 -0.0131573 -0.226573 0.00472074 -0.0196283 -0.226573 0.00514189 -0.0149494 -0.226573 0.00357759 -0.0133151 -0.226573 0.00574452 -0.0143813 -0.226573 0.00645627 -0.0173892 -0.226573 0.00536379 -0.0191423 -0.226573 0.00566293 -0.0171513 -0.226573 0.0049741 -0.0193308 -0.226573 0.00398219 -0.0133036 -0.226573 0.00581258 -0.0128705 -0.226573 0.00717503 -0.012866 -0.226573 0.00734383 -0.0144284 -0.226573 0.00839895 -0.0134646 -0.226573 0.00786486 -0.0166303 -0.226573 0.00726223 -0.0171984 -0.226573 0.0190962 -0.0446326 -0.2288 0.0232121 -0.0489983 -0.229483 0.0245807 -0.047708 -0.226573 0.0245807 -0.047708 -0.230278 0.0254509 -0.0461776 -0.226573 0.018351 -0.0449032 -0.226573 0.0209234 -0.0454781 -0.226573 0.0232816 -0.0469338 -0.226573 0.0217639 -0.0441166 -0.226573 0.0204648 -0.0433423 -0.226573 0.0230791 -0.0425772 -0.226573 0.0255214 -0.0456135 -0.226573 0.0241221 -0.0455723 -0.226573 0.0252594 -0.0467543 -0.229483 0.0541373 -0.0641285 -0.226573 0.0515735 -0.0648367 -0.226573 0.0522239 -0.0645468 -0.226573 0.0536447 -0.0666313 -0.226573 0.0473268 -0.0648207 -0.226573 0.0502296 -0.0644881 -0.226573 0.0508618 -0.0648158 -0.226573 0.0478498 -0.0642073 -0.226573 0.0499021 -0.0624266 -0.226573 0.0503374 -0.0604136 -0.226573 0.0513107 -0.0616678 -0.226573 0.0530835 -0.0608821 -0.226573 0.0539828 -0.0619998 -0.226573 0.0528629 -0.0633142 -0.226573 0.0526841 -0.0640034 -0.226573 0.0541373 -0.0641285 -0.226573 0.0535971 -0.0659302 -0.229483 0.0821055 -0.0649524 -0.226573 0.0883773 -0.0654011 -0.229624 0.0878599 -0.0632806 -0.230091 0.087362 -0.0623806 -0.226573 0.0872077 -0.0622036 -0.23019 0.0872093 -0.0622053 -0.230738 0.0858252 -0.0613703 -0.23089 0.0849389 -0.0612628 -0.226573 0.084334 -0.0613422 -0.230722 0.0829644 -0.0620811 -0.230454 0.0824194 -0.0627743 -0.230189 0.08215 -0.063404 -0.226573 0.0888507 -0.0660371 -0.226573 0.0849777 -0.0658609 -0.226573 0.0857837 -0.0656701 -0.226573 0.0824004 -0.0675634 -0.226573 0.0841844 -0.065623 -0.226573 0.0836162 -0.0650204 -0.226573 0.0825386 -0.0667827 -0.226573 0.0834255 -0.0642144 -0.226573 0.0821055 -0.0649524 -0.226573 0.0836044 -0.0635252 -0.226573 0.0821512 -0.0634001 -0.226573 0.0829669 -0.0620787 -0.226573 0.0854266 -0.0627128 -0.226573 0.0858863 -0.0613879 -0.226573 0.0860588 -0.0630405 -0.226573 0.0879442 -0.0635708 -0.2288 0.113868 -0.0516687 -0.226573 0.112577 -0.0503001 -0.2288 0.118233 -0.0475529 -0.229483 0.116943 -0.0461842 -0.226573 0.116943 -0.0461842 -0.229624 0.116725 -0.0459751 -0.226573 0.115622 -0.0453685 -0.230469 0.114908 -0.0452458 -0.226573 0.114069 -0.0453228 -0.230738 0.114008 -0.0453381 -0.23089 0.113186 -0.0456882 -0.226573 0.112702 -0.0460593 -0.23092 0.112706 -0.0460556 -0.230189 0.111842 -0.048937 -0.229996 0.111978 -0.0493645 -0.226573 0.114137 -0.0524283 -0.226573 0.116122 -0.0490826 -0.226573 0.114138 -0.0524139 -0.226573 0.11408 -0.0520133 -0.226573 0.11392 -0.0496037 -0.226573 0.113868 -0.0516687 -0.226573 0.111841 -0.048933 -0.226573 0.111887 -0.0473807 -0.226573 0.11445 -0.0466725 -0.226573 0.116222 -0.0475907 -0.226573 0.118233 -0.0475529 -0.226573 0.118565 -0.0477851 -0.226573 0.118961 -0.0478669 -0.2288 0.135165 -0.0171678 -0.229483 0.133363 -0.0166277 -0.226573 0.133363 -0.0166277 -0.226573 0.132031 -0.0165385 -0.230469 0.131132 -0.0168325 -0.226573 0.130792 -0.0170361 -0.230738 0.130398 -0.0173626 -0.230883 0.129509 -0.0193034 -0.226573 0.129892 -0.018022 -0.230773 0.12954 -0.0199757 -0.226573 0.129718 -0.0206195 -0.230598 0.12972 -0.0206241 -0.226573 0.131641 -0.022375 -0.226573 0.134056 -0.0234381 -0.226573 0.133864 -0.0203418 -0.226573 0.133798 -0.0231074 -0.226573 0.132455 -0.0211006 -0.226573 0.131662 -0.0208628 -0.226573 0.130479 -0.0217166 -0.226573 0.129509 -0.0193009 -0.226573 0.131082 -0.018765 -0.226573 0.131542 -0.0182216 -0.226573 0.132192 -0.0179316 -0.226573 0.133536 -0.0182803 -0.226573 0.135165 -0.0171678 -0.229483 0.134187 0.0113405 -0.226573 0.134187 0.0113405 -0.226573 0.134636 0.0176124 -0.229483 0.132806 0.0171793 -0.226573 0.132806 0.0171793 -0.229624 0.132516 0.017095 -0.226573 0.131607 0.0165905 -0.230738 0.130605 0.0150602 -0.226573 0.130497 0.014236 -0.230883 0.130805 0.0129346 -0.230912 0.130669 0.0132568 -0.23089 0.130498 0.0141739 -0.230773 0.131168 0.0123679 -0.230598 0.131649 0.0118966 -0.226573 0.132852 0.0113299 -0.229996 0.133077 0.0112893 -0.226573 0.134917 0.0135235 -0.226573 0.135096 0.0142128 -0.226573 0.134337 0.0156214 -0.226573 0.135272 0.0180858 -0.226573 0.13681 0.0116274 -0.226573 0.136018 0.0117736 -0.226573 0.133806 0.0126902 -0.226573 0.133095 0.0127112 -0.226573 0.132463 0.0130389 -0.226573 0.132035 0.0136084 -0.226573 0.131645 0.0118996 -0.226573 0.130804 0.0129368 -0.226573 0.132135 0.0151004 -0.226573 0.130783 0.01554 -0.226573 0.132738 0.0156685 -0.229483 0.119535 0.0418124 -0.226573 0.119535 0.0418124 -0.226573 0.115419 0.0461781 -0.226573 0.114676 0.045069 -0.230469 0.114481 0.0441431 -0.230738 0.114573 0.0432427 -0.230912 0.11553 0.0417129 -0.226573 0.115807 0.0415032 -0.23092 0.115291 0.0419412 -0.2308 0.114659 0.042966 -0.230883 0.115809 0.0415018 -0.230598 0.117059 0.0410246 -0.230454 0.117492 0.0409953 -0.226573 0.117054 0.0410253 -0.226573 0.118384 0.0411356 -0.226273 0.0550928 0.0658371 -0.226273 0.0582625 0.0664682 -0.228737 0.0582625 0.0664682 -0.2263 0.0580392 0.0664016 -0.226374 0.0578461 0.0662917 -0.226573 0.0576076 0.0660454 -0.226573 0.0575501 0.0659498 -0.228753 0.0576334 0.0660816 -0.226573 0.0574349 0.0655125 -0.228764 0.0575107 0.065866 -0.226573 0.0511492 0.0645071 -0.226573 0.0514516 0.0642381 -0.22878 0.0514912 0.0641808 -0.228762 0.0512645 0.0644295 -0.226573 0.0511366 0.0645142 -0.226354 0.0507649 0.0646342 -0.226294 0.0505649 0.0646373 -0.228737 0.0503617 0.0645986 -0.226573 0.0535546 0.063468 -0.226573 0.0540148 0.0640114 -0.224773 0.0540148 0.0640114 -0.224773 0.0546651 0.0643013 -0.224773 0.0553769 0.0642803 -0.226573 0.0546651 0.0643013 -0.226573 0.0553769 0.0642803 -0.224773 0.0564364 0.0633831 -0.224773 0.0565744 0.0626845 -0.229483 0.0578945 0.0634224 -0.226573 0.0574614 0.0652528 -0.226573 0.0516226 0.0638712 -0.226573 0.0527045 0.0607708 -0.230008 0.0525236 0.0610024 -0.229751 0.0522412 0.0614964 -0.226573 0.0520557 0.0620408 -0.230317 0.0530198 0.0604563 -0.230461 0.0533286 0.0602238 -0.230906 0.0552552 0.0597447 -0.230829 0.0546133 0.0597535 -0.226573 0.0538665 0.059944 -0.230652 0.0538623 0.0599456 -0.23069 0.0571253 0.0606396 -0.230802 0.0567546 0.0603164 -0.230886 0.0562728 0.0600268 -0.226573 0.0552789 0.059747 -0.230918 0.0558326 0.0598568 -0.226573 0.0575942 0.0612686 -0.230009 0.0579412 0.0622821 -0.226573 0.0560091 0.0639526 -0.226573 0.0564364 0.0633831 -0.226573 0.0565744 0.0626845 -0.226573 0.0578945 0.0634224 -0.226573 0.0579738 0.0626433 -0.226573 0.0557339 0.061323 -0.226573 0.0566227 0.0602246 -0.226573 0.054928 0.0611323 -0.226573 0.0533758 0.0627787 -0.233273 0.0138743 0.0008883 -0.233473 0.0149383 0.0112157 -0.233273 0.0182616 0.0210516 -0.233473 0.0229844 0.0302973 -0.233473 0.0294926 0.0384075 -0.233273 0.0296364 0.0382684 -0.233273 0.037496 0.0450206 -0.233473 0.0373803 0.0451837 -0.233273 0.0464625 0.0502136 -0.233473 0.0561816 0.0538645 -0.233473 0.066455 0.0554734 -0.233273 0.0768248 0.0549687 -0.233273 0.0869496 0.0527657 -0.233473 0.08701 0.0529564 -0.233273 0.0964973 0.0487397 -0.233273 0.112591 0.0358249 -0.233273 0.118589 0.0273757 -0.233273 0.125474 0.00792297 -0.235873 0.126326 -0.00242413 -0.235873 0.118762 0.027476 -0.236073 0.105143 0.043028 -0.236073 0.0964973 0.0487397 -0.235873 0.0561816 0.0538645 -0.236073 0.0296364 0.0382684 -0.235873 0.0294926 0.0384075 -0.236073 0.0151337 0.0111732 -0.233561 0.0171272 0.0219917 -0.233496 0.0824251 0.0553405 -0.233513 0.0125249 0.000928049 -0.233496 0.0172166 0.0219532 -0.233473 0.020579 0.0283314 -0.233513 0.127475 -0.00245799 -0.233561 0.127296 0.00476486 -0.233561 0.0753043 0.0565522 -0.233496 0.0752953 0.0564553 -0.233473 0.0824003 0.0552284 -0.233658 0.0146294 0.0152036 -0.233561 0.0146919 0.0151855 -0.233496 0.0147854 0.0151586 -0.233658 0.124182 0.0188622 -0.233773 0.120753 0.0265775 -0.233496 0.12115 0.0254242 -0.233561 0.117545 0.0316834 -0.233658 0.117598 0.03172 -0.233496 0.11303 0.0373219 -0.233561 0.113103 0.0373864 -0.233658 0.102297 0.046961 -0.233658 0.108024 0.0425367 -0.233773 0.10231 0.0469799 -0.233773 0.100282 0.048291 -0.233473 0.107841 0.0423284 -0.233561 0.102261 0.0469071 -0.233496 0.102206 0.0468265 -0.233561 0.0960316 0.0505746 -0.233658 0.0960611 0.0506326 -0.233473 0.102142 0.0467314 -0.233496 0.0959876 0.0504878 -0.233561 0.0893918 0.0534324 -0.233658 0.0894137 0.0534936 -0.233658 0.0824602 0.055499 -0.233773 0.0816781 0.0556898 -0.233658 0.0608731 0.0561349 -0.233561 0.0470354 0.0520179 -0.233561 0.0538319 0.0544799 -0.233658 0.0405678 0.0487793 -0.233496 0.0470742 0.0519286 -0.233658 0.0345903 0.0446998 -0.233773 0.0291551 0.0399194 -0.233496 0.0346901 0.0445717 -0.233473 0.0347606 0.0444812 -0.233473 0.0293677 0.0397077 -0.233496 0.0292863 0.0397887 -0.233561 0.0244476 0.0344257 -0.233496 0.0245246 0.0343662 -0.233658 0.0203402 0.028472 -0.233773 0.0170465 0.0220264 -0.233658 0.0170674 0.0220174 -0.233773 0.0164307 0.020539 -0.233561 0.127537 -0.00245982 -0.233623 0.127585 -0.00246122 -0.233496 0.127199 0.00475551 -0.233561 0.126151 0.0119023 -0.233658 0.126214 0.0119167 -0.233658 0.127361 0.00477111 -0.233773 0.124203 0.01887 -0.233773 0.127044 0.00756986 -0.233473 0.127085 0.00474449 -0.233496 0.126056 0.0118809 -0.233561 0.124121 0.01884 -0.233496 0.124029 0.0188069 -0.233658 0.121295 0.0254982 -0.233561 0.121237 0.0254686 -0.233658 0.113152 0.0374295 -0.233773 0.113169 0.0374447 -0.233496 0.117464 0.0316285 -0.233473 0.11737 0.0315638 -0.233496 0.107917 0.0424147 -0.233561 0.107981 0.0424878 -0.233773 0.0913039 0.0528043 -0.233473 0.0959357 0.0503854 -0.233496 0.089359 0.0533408 -0.233561 0.0824462 0.0554355 -0.233473 0.0752847 0.056341 -0.233496 0.0680819 0.0566678 -0.233561 0.0680787 0.0567651 -0.233658 0.0753102 0.056617 -0.233773 0.0538072 0.0545642 -0.233773 0.0616651 0.0562793 -0.233773 0.0680757 0.0568529 -0.233658 0.0680765 0.0568301 -0.233773 0.0716974 0.05686 -0.233496 0.0608988 0.0559745 -0.233561 0.0608834 0.0560706 -0.233658 0.0538136 0.0545423 -0.233773 0.0518861 0.0539654 -0.233658 0.0470094 0.0520775 -0.233473 0.0538915 0.0542763 -0.233496 0.0538592 0.0543865 -0.233561 0.040601 0.0487234 -0.233773 0.0345763 0.0447178 -0.233496 0.0406507 0.0486397 -0.233561 0.0346303 0.0446485 -0.233658 0.0291713 0.0399033 -0.233561 0.0292174 0.0398574 -0.233658 0.0243961 0.0344655 -0.233773 0.0269477 0.037576 -0.233473 0.0246155 0.034296 -0.233496 0.0204801 0.0283896 -0.233561 0.0203962 0.028439 -0.233773 0.0135452 0.0109132 -0.233658 0.0130647 0.00813788 -0.233473 0.0133385 0.00809506 -0.233496 0.0132251 0.0081128 -0.233561 0.0131289 0.00812783 -0.233773 0.012375 0.000932466 -0.233773 0.0130421 0.00814141 -0.235785 0.0124628 0.000929878 -0.235833 0.127404 0.00255773 -0.235785 0.127537 -0.00245982 -0.235723 0.127004 0.00756405 -0.235573 0.127044 0.00756986 -0.235573 0.118177 0.0308969 -0.235573 0.115234 0.0349754 -0.235723 0.108314 0.0422572 -0.235573 0.104443 0.0454651 -0.235573 0.100282 0.048291 -0.235723 0.100261 0.0482568 -0.235723 0.0958737 0.0507077 -0.235573 0.0958917 0.0507437 -0.235723 0.0816699 0.0556505 -0.235573 0.0816781 0.0556898 -0.235723 0.0767086 0.0564529 -0.235573 0.0716974 0.05686 -0.235723 0.0616709 0.0562396 -0.235723 0.0567344 0.0552967 -0.235573 0.0616651 0.0562793 -0.235723 0.0518987 0.0539272 -0.235573 0.047185 0.0521784 -0.235723 0.0426765 0.0499531 -0.235573 0.0426575 0.0499885 -0.235723 0.0342845 0.0444379 -0.235573 0.0342596 0.0444694 -0.235723 0.0269777 0.0375492 -0.235573 0.0269477 0.037576 -0.235723 0.0238022 0.0336538 -0.235723 0.0209782 0.0294964 -0.235573 0.020944 0.0295176 -0.235723 0.0135845 0.010905 -0.235573 0.0127422 0.00594836 -0.235723 0.0127821 0.00594368 -0.235833 0.0149215 0.015746 -0.235723 0.0148163 0.0157775 -0.235723 0.0164681 0.0205242 -0.235833 0.0165701 0.0204836 -0.235723 0.0185272 0.0251088 -0.235833 0.0210716 0.0294388 -0.235833 0.0270598 0.0374762 -0.235723 0.0304808 0.0411531 -0.235833 0.0305561 0.0410732 -0.235833 0.0343526 0.0443517 -0.235723 0.0383601 0.0473787 -0.235723 0.0472009 0.0521415 -0.235833 0.0519332 0.053823 -0.235833 0.0616868 0.0561309 -0.235723 0.0666709 0.0567486 -0.235723 0.0716962 0.0568199 -0.235833 0.071693 0.0567101 -0.235833 0.0766958 0.0563438 -0.235833 0.0816477 0.0555429 -0.235723 0.0865425 0.0544187 -0.235723 0.0912891 0.0527669 -0.235833 0.0958244 0.0506096 -0.235833 0.100204 0.0481634 -0.235833 0.104353 0.0453448 -0.235723 0.104419 0.0454328 -0.235723 0.111918 0.0387542 -0.235723 0.115203 0.0349504 -0.235723 0.118144 0.0308748 -0.235833 0.118052 0.0308145 -0.235723 0.120718 0.0265584 -0.235833 0.122806 0.0219906 -0.235723 0.122906 0.0220341 -0.235723 0.124692 0.0173362 -0.235723 0.126062 0.0125006 -0.235833 0.125955 0.0124753 -0.235833 0.126896 0.00754817 -0.235723 0.127513 0.00256408 -0.235833 0.127475 -0.00245799 -0.235873 0.127325 -0.00245357 -0.23585 0.12744 -0.00245695 -0.235873 0.126747 0.00752648 -0.235873 0.124445 0.0172546 -0.235833 0.124588 0.0173017 -0.235833 0.120621 0.0265064 -0.235873 0.114999 0.0347894 -0.235833 0.115117 0.0348824 -0.235833 0.111838 0.0386789 -0.235873 0.108141 0.0420632 -0.235833 0.108241 0.0421752 -0.235873 0.104264 0.0452245 -0.235873 0.100125 0.0480358 -0.235873 0.095757 0.0504756 -0.235873 0.0911931 0.0525255 -0.235833 0.0912485 0.0526649 -0.235833 0.0865109 0.0543135 -0.235873 0.0766784 0.0561949 -0.235873 0.0716886 0.0565602 -0.235833 0.0666772 0.0566389 -0.235873 0.0617085 0.0559825 -0.235833 0.0567596 0.0551899 -0.235873 0.0473037 0.0519029 -0.235833 0.0472443 0.0520406 -0.235833 0.0427286 0.0498564 -0.235833 0.0384205 0.0472869 -0.235873 0.030659 0.040964 -0.235833 0.0238902 0.0335882 -0.235873 0.0211992 0.02936 -0.235873 0.0187594 0.0249921 -0.235833 0.0186254 0.0250594 -0.235833 0.0136921 0.0108828 -0.235873 0.0130401 0.00591342 -0.235833 0.0128912 0.00593089 -0.235873 0.127254 0.00254907 -0.235873 0.125671 0.00795392 -0.235873 0.0575996 -0.0567583 -0.235873 0.0212376 -0.0290059 -0.235873 0.10262 -0.0467136 -0.235873 0.105239 -0.0460111 -0.235873 0.110507 -0.0399374 -0.235873 0.110632 -0.0412377 -0.235873 0.117015 -0.0318272 -0.235873 0.119421 -0.0298613 -0.235873 0.121923 -0.0226592 -0.235873 0.122678 -0.0234378 -0.235873 0.0647152 -0.057871 -0.235873 0.0735449 -0.0570034 -0.235873 0.0838184 -0.0553944 -0.235873 0.0936212 -0.0519251 -0.235873 0.0861084 -0.0558062 -0.235873 0.0440642 -0.0519153 -0.235873 0.0529899 -0.0544863 -0.235873 0.0506796 -0.0547626 -0.235873 0.0160788 -0.0202977 -0.235873 0.0168786 -0.019565 -0.235873 0.0129152 -0.00627443 -0.235873 0.0126748 0.000923632 -0.235873 0.0143286 -0.00948386 -0.235873 0.0136744 0.000894189 -0.235873 0.0149383 0.0112157 -0.235873 0.0138389 0.0108524 -0.235873 0.123121 0.0180351 -0.235873 0.122668 0.0219313 -0.235873 0.125809 0.0124408 -0.235873 0.0189521 -0.0269018 -0.235873 0.0150652 0.0157029 -0.235873 0.0463787 0.0503952 -0.235873 0.0240105 0.0334986 -0.235873 0.0229844 0.0302973 -0.235873 0.0180773 0.0211293 -0.235873 0.0167095 0.0204281 -0.235873 0.0768491 0.0551672 -0.235873 0.0816173 0.055396 -0.235873 0.0864679 0.0541698 -0.235873 0.105268 0.0431839 -0.235873 0.0427998 0.0497244 -0.235873 0.0385028 0.0471616 -0.235873 0.0344456 0.044234 -0.235873 0.0373803 0.0451837 -0.235873 0.0271718 0.0373765 -0.235873 0.0567942 0.0550439 -0.235873 0.0519804 0.0536806 -0.235873 0.066455 0.0554734 -0.235873 0.0666859 0.0564892 -0.235873 0.0965916 0.0489161 -0.235873 0.08701 0.0529564 -0.235873 0.120489 0.0264352 -0.235873 0.117927 0.0307322 -0.235873 0.112743 0.0359552 -0.235873 0.111729 0.038576 -0.233473 0.127325 -0.00245357 -0.233473 0.12696 -0.00744336 -0.233473 0.0126748 0.000923632 -0.233473 0.0136744 0.000894189 -0.233473 0.126161 -0.0123823 -0.233473 0.124935 -0.0172329 -0.233473 0.123921 0.0187678 -0.233473 0.123121 0.0180351 -0.233473 0.125671 0.00795392 -0.233473 0.125944 0.0118557 -0.233473 0.060917 0.0558612 -0.233473 0.0680858 0.0565531 -0.233473 0.0148957 0.0151268 -0.233473 0.0180773 0.0211293 -0.233473 0.0132525 -0.00905643 -0.233473 0.0141911 -0.0139707 -0.233473 0.0143286 -0.00948386 -0.233473 0.112743 0.0359552 -0.233473 0.112944 0.0372458 -0.233473 0.118762 0.027476 -0.233473 0.121048 0.0253719 -0.233473 0.0463787 0.0503952 -0.233473 0.04712 0.0518233 -0.233473 0.0250009 -0.0363193 -0.233473 0.0220734 -0.0322621 -0.233473 0.0212376 -0.0290059 -0.233473 0.0168786 -0.019565 -0.233473 0.0173321 -0.0234612 -0.233473 0.0155544 -0.0187846 -0.233473 0.0357364 -0.0467544 -0.233473 0.0347322 -0.0447139 -0.233473 0.0282709 -0.0401059 -0.233473 0.0442429 -0.0520056 -0.233473 0.0434083 -0.050446 -0.233473 0.017322 0.0219078 -0.233473 0.0407094 0.048541 -0.233473 0.0768491 0.0551672 -0.233473 0.0893204 0.0532327 -0.233473 0.0965916 0.0489161 -0.233473 0.105268 0.0431839 -0.233473 0.0631508 -0.0566972 -0.233473 0.0583826 -0.056926 -0.233473 0.0535321 -0.0556998 -0.233473 0.073314 -0.0580191 -0.233473 0.0683114 -0.0580901 -0.233473 0.110507 -0.0399374 -0.233473 0.10262 -0.0467136 -0.233473 0.0972002 -0.0512543 -0.233473 0.115989 -0.0350285 -0.233473 0.112828 -0.0389064 -0.233473 0.121923 -0.0226592 -0.233473 0.12329 -0.0219581 -0.233473 0.121241 -0.026522 -0.235573 0.086554 0.0544572 -0.235573 0.0913039 0.0528043 -0.235573 0.012375 0.000932466 -0.235573 0.0135452 0.0109132 -0.235573 0.0147778 0.0157891 -0.233773 0.0146075 0.0152099 -0.235573 0.0164307 0.020539 -0.233773 0.0203205 0.0284836 -0.235573 0.0184913 0.0251268 -0.233773 0.0608695 0.0561574 -0.235573 0.0567251 0.0553358 -0.235573 0.0518861 0.0539654 -0.233773 0.0470003 0.0520984 -0.235573 0.0383381 0.0474123 -0.233773 0.0426575 0.0499885 -0.233773 0.0405561 0.048799 -0.235573 0.0304532 0.0411823 -0.235573 0.0237699 0.0336778 -0.233773 0.0243781 0.0344794 -0.233773 0.020944 0.0295176 -0.233773 0.0824652 0.0555213 -0.235573 0.0767133 0.0564928 -0.233773 0.0753123 0.0566397 -0.235573 0.0666686 0.0567887 -0.233773 0.117617 0.0317329 -0.233773 0.115234 0.0349754 -0.235573 0.111947 0.0387818 -0.235573 0.108341 0.0422873 -0.233773 0.108039 0.0425539 -0.233773 0.0960714 0.050653 -0.233773 0.0894214 0.0535151 -0.235573 0.127625 -0.00246241 -0.235573 0.127554 0.0025664 -0.233773 0.127383 0.00477331 -0.233773 0.126237 0.0119217 -0.235573 0.126101 0.0125099 -0.235573 0.12473 0.0173489 -0.233773 0.12473 0.0173489 -0.235573 0.122943 0.02205 -0.233773 0.121315 0.0255086 -0.235573 0.120753 0.0265775 -0.233695 0.0115195 0.00581957 -0.233299 0.0110937 0.000970206 -0.233695 0.012263 0.0106264 -0.233695 0.0134009 0.0153553 -0.233299 0.0148488 0.020003 -0.233695 0.0168261 0.0244514 -0.233299 0.0167522 0.0244864 -0.233695 0.0190901 0.0287563 -0.233299 0.0216347 0.0329063 -0.233695 0.0246435 0.0367332 -0.233695 0.0260516 0.0383741 -0.233695 0.0314341 0.0436872 -0.233299 0.0313805 0.043749 -0.233299 0.0351883 0.0467861 -0.233695 0.0335157 0.045411 -0.233695 0.0392766 0.0494286 -0.233299 0.0434897 0.0518674 -0.233695 0.0435265 0.0517943 -0.233695 0.0525386 0.0554349 -0.233299 0.0525143 0.055513 -0.233299 0.0572214 0.0567647 -0.233695 0.0572391 0.0566849 -0.233695 0.0620269 0.0575424 -0.233299 0.0668648 0.0580834 -0.233695 0.0668691 0.0580017 -0.233695 0.0717327 0.0580595 -0.233695 0.0952163 0.0524089 -0.233299 0.0995623 0.0502157 -0.233695 0.100913 0.0493121 -0.233695 0.103625 0.0475332 -0.233695 0.107498 0.0445915 -0.233695 0.109139 0.0431834 -0.233299 0.111173 0.0413986 -0.233695 0.114452 0.0378009 -0.233695 0.120194 0.0299584 -0.233299 0.120263 0.0300011 -0.233299 0.124642 0.0213084 -0.233695 0.12587 0.0177259 -0.232967 0.0112077 0.00585467 -0.232755 0.0105178 0.000987172 -0.232755 0.0116174 0.0107537 -0.232967 0.0146317 0.0200848 -0.232755 0.0143096 0.0202061 -0.232967 0.0165426 0.0245858 -0.232755 0.0185209 0.0290864 -0.232967 0.0244016 0.0369331 -0.232755 0.0241363 0.0371524 -0.232967 0.0350513 0.0469733 -0.232967 0.0391128 0.0496963 -0.232755 0.0348479 0.047251 -0.232755 0.0389331 0.0499898 -0.232967 0.0478397 0.0540919 -0.232967 0.0619844 0.0578533 -0.232755 0.0619378 0.0581943 -0.232967 0.0668524 0.058315 -0.232755 0.0668341 0.0586587 -0.232967 0.081452 0.0572798 -0.232755 0.0815187 0.0576176 -0.232967 0.0862062 0.0561359 -0.232967 0.0908497 0.0546032 -0.232755 0.090971 0.0549254 -0.232755 0.107917 0.0450986 -0.232967 0.114689 0.0380065 -0.232967 0.120461 0.0301222 -0.232755 0.120755 0.0303019 -0.232755 0.123147 0.0260045 -0.232755 0.125176 0.0215242 -0.232967 0.124857 0.0213953 -0.232967 0.126499 0.0167895 -0.232755 0.126828 0.0168917 -0.232967 0.127756 0.0120639 -0.232755 0.128092 0.0121385 -0.232967 0.0108619 0.000977036 -0.233299 0.0114382 0.00582872 -0.233299 0.0121827 0.0106422 -0.232967 0.0119551 0.0106871 -0.233299 0.0133222 0.0153777 -0.232967 0.0130991 0.0154413 -0.233299 0.0190193 0.0287973 -0.232967 0.0188186 0.0289137 -0.232967 0.0214443 0.0330389 -0.233299 0.0245804 0.0367853 -0.233299 0.0278364 0.0404077 -0.232967 0.0276705 0.0405698 -0.232967 0.0312284 0.0439242 -0.233299 0.0392339 0.0494984 -0.232967 0.0433854 0.0520745 -0.233299 0.0479266 0.0538768 -0.232967 0.0524455 0.0557345 -0.232967 0.0571711 0.0569912 -0.233299 0.0620158 0.0576235 -0.233299 0.0717351 0.0581413 -0.232967 0.071742 0.0583731 -0.232967 0.0766196 0.0580273 -0.233299 0.0765936 0.0577968 -0.233299 0.0814071 0.0570523 -0.233299 0.0861427 0.0559128 -0.233299 0.0907679 0.0543862 -0.233299 0.0952514 0.0524828 -0.232967 0.0953507 0.0526924 -0.232967 0.0996786 0.0504163 -0.233299 0.103671 0.0476003 -0.232967 0.103804 0.0477907 -0.233299 0.10755 0.0446546 -0.232967 0.107698 0.0448333 -0.232967 0.111335 0.0415645 -0.233299 0.114514 0.0378545 -0.233299 0.117551 0.0340467 -0.232967 0.117738 0.0341837 -0.233299 0.122632 0.0257453 -0.232967 0.122839 0.0258496 -0.233299 0.128388 0.00721917 -0.232967 0.128618 0.00725059 -0.233299 0.126278 0.0167207 -0.233695 0.128232 0.00774335 -0.233299 0.12753 0.0120136 -0.232755 0.129424 0.00240087 -0.233299 0.128848 0.00237022 -0.233695 0.128767 0.00236587 -0.233695 0.128307 0.00720809 -0.232967 0.12908 0.00238256 -0.230673 0.0430967 -0.0385694 -0.230673 0.042169 -0.039873 -0.230673 0.0293215 -0.0262457 -0.230673 0.0242447 -0.00847329 -0.230673 0.0251321 -0.0178201 -0.230673 0.022667 -0.0087391 -0.230673 0.0262138 0.0189016 -0.230673 0.0370729 0.0341608 -0.230673 0.0445193 0.0399135 -0.230673 0.0529448 0.0441029 -0.230673 0.0803882 0.0444572 -0.230673 0.0969032 0.0370395 -0.230673 0.0978309 0.0383431 -0.230673 0.104926 0.0321621 -0.230673 0.110678 0.0247157 -0.230673 0.114868 0.0162901 -0.230673 0.115755 0.00694335 -0.230673 0.117333 0.00720916 -0.230673 0.117979 -0.00217827 -0.230673 0.116782 -0.0115114 -0.230673 0.109108 -0.0285959 -0.230673 0.0954807 -0.0414434 -0.230673 0.0870551 -0.0456328 -0.230673 0.0685867 -0.0487442 -0.230673 0.0592535 -0.0475465 -0.230673 0.0596117 -0.0459871 -0.230673 0.0232184 0.00998145 -0.238173 0.0220208 0.000648333 -0.238173 0.0232184 0.00998145 -0.230673 0.0308919 0.027066 -0.238173 0.0262138 0.0189016 -0.238173 0.0308919 0.027066 -0.238173 0.0370729 0.0341608 -0.238173 0.0445193 0.0399135 -0.238173 0.0529448 0.0441029 -0.230673 0.0620258 0.046568 -0.238173 0.0620258 0.046568 -0.230673 0.0714133 0.0472142 -0.238173 0.0714133 0.0472142 -0.230673 0.0807464 0.0460166 -0.238173 0.0807464 0.0460166 -0.230673 0.0896665 0.0430212 -0.238173 0.0896665 0.0430212 -0.238173 0.0978309 0.0383431 -0.238473 0.0987926 0.0396945 -0.238473 0.106133 0.0332999 -0.238473 0.110933 0.024875 -0.238473 0.115148 0.0163967 -0.238473 0.112084 0.0255963 -0.238473 0.116418 0.0168795 -0.238473 0.118969 0.00748472 -0.238473 0.118279 -0.00218711 -0.238473 0.117074 -0.0115786 -0.238473 0.118398 -0.0118828 -0.238473 0.109352 -0.0287698 -0.238473 0.110459 -0.0295577 -0.238473 0.0956399 -0.0416976 -0.238473 0.0963612 -0.0428491 -0.238473 0.0876445 -0.0471833 -0.238473 0.0782496 -0.0497337 -0.238473 0.0780239 -0.0483938 -0.238473 0.0588822 -0.0491632 -0.238473 0.0502105 -0.0448248 -0.238473 0.0419951 -0.0401174 -0.238473 0.0348559 -0.0338978 -0.238473 0.0279158 -0.0271262 -0.238473 0.0235816 -0.0184095 -0.238473 0.022926 0.0100486 -0.238473 0.0216018 0.0103528 -0.238473 0.0259402 0.0190245 -0.238473 0.0247007 0.0195812 -0.238473 0.0368671 0.0343791 -0.238473 0.035935 0.0353677 -0.238473 0.0436387 0.0413192 -0.238473 0.0528382 0.0443833 -0.238473 0.0714221 0.0475141 -0.238473 0.0808135 0.046309 -0.238473 0.0714621 0.0488722 -0.238473 0.0897894 0.0432948 -0.238273 0.0337217 -0.0349671 -0.236973 0.0277463 -0.0272324 -0.238273 0.0495718 -0.0462467 -0.238273 0.0588374 -0.0493581 -0.236973 0.0588374 -0.0493581 -0.236973 0.0685319 -0.0506021 -0.236973 0.0877155 -0.0473703 -0.238273 0.0964674 -0.0430186 -0.238273 0.104202 -0.0370432 -0.236973 0.104202 -0.0370432 -0.238273 0.115482 -0.0211931 -0.236973 0.110622 -0.0296736 -0.236973 0.115482 -0.0211931 -0.236973 0.118593 -0.0119275 -0.236973 0.119837 -0.002233 -0.236973 0.0293775 0.0281437 -0.236973 0.0409403 0.0401689 -0.236973 0.0761016 0.0490628 -0.236973 0.0811625 0.0478281 -0.236973 0.0904281 0.0447167 -0.236973 0.0989086 0.0398575 -0.236973 0.101419 0.0383874 -0.236973 0.11344 0.0243938 -0.236973 0.117324 0.0159832 -0.236973 0.119166 0.00751794 -0.236973 0.120178 -0.00224305 -0.236973 0.119052 -0.0114381 -0.236973 0.0964674 -0.0430186 -0.236973 0.0910432 -0.0463415 -0.236973 0.0782829 -0.0499309 -0.236973 0.073158 -0.0508655 -0.236973 0.0495718 -0.0462467 -0.236973 0.0463105 -0.0450238 -0.236973 0.0410913 -0.0413874 -0.236973 0.0337217 -0.0349671 -0.236973 0.031922 -0.0334775 -0.236973 0.0233947 -0.0184805 -0.236973 0.020834 -0.00904789 -0.236973 0.0201628 0.000703061 -0.230673 0.0201081 -0.0085787 -0.230673 0.0223934 -0.0176133 -0.236673 0.0316945 -0.033673 -0.236673 0.0731769 -0.0511649 -0.230673 0.0731769 -0.0511649 -0.230673 0.0823838 -0.049723 -0.236673 0.0823838 -0.049723 -0.236673 0.091169 -0.0466139 -0.236673 0.106302 -0.0358707 -0.236673 0.112135 -0.0286025 -0.236673 0.116532 -0.0203863 -0.236673 0.119345 -0.0115019 -0.230673 0.119345 -0.0115019 -0.236673 0.120478 -0.00225188 -0.230673 0.0316945 -0.033673 -0.230673 0.0274088 -0.0373548 -0.230673 0.0214106 -0.0289057 -0.230673 0.0262998 -0.0260741 -0.230673 0.0170671 -0.0194983 -0.230673 0.0195219 0.000721942 -0.230673 0.0145262 -0.00945291 -0.230673 0.0138743 0.0008883 -0.230673 0.0234677 0.0188563 -0.230673 0.0278654 0.0270725 -0.230673 0.0182616 0.0210516 -0.230673 0.0336979 0.0343408 -0.230673 0.0407667 0.0404135 -0.230673 0.0576161 0.0481931 -0.230673 0.0562306 0.0536706 -0.230673 0.066823 0.049635 -0.230673 0.0664676 0.0552738 -0.230673 0.0768248 0.0549687 -0.230673 0.0869496 0.0527657 -0.230673 0.101606 0.0386214 -0.230673 0.0964973 0.0487397 -0.230673 0.108305 0.0321431 -0.230673 0.1137 0.0245441 -0.230673 0.122933 0.0179683 -0.230673 0.126126 -0.00241824 -0.230673 0.116532 -0.0203863 -0.230673 0.124866 -0.0127032 -0.230673 0.112135 -0.0286025 -0.230673 0.106302 -0.0358707 -0.230673 0.0992332 -0.0419434 -0.230673 0.102504 -0.0465505 -0.230673 0.091169 -0.0466139 -0.230673 0.0935374 -0.0517435 -0.230673 0.0837693 -0.0552005 -0.230673 0.0638619 -0.0508906 -0.230673 0.0547558 -0.0489092 -0.230673 0.0530503 -0.0542956 -0.230673 0.0461689 -0.0452883 -0.230673 0.0383935 -0.0401513 -0.236873 0.0463787 0.0503952 -0.236873 0.0716974 0.05686 -0.236873 0.0913039 0.0528043 -0.236873 0.108341 0.0422873 -0.236873 0.115234 0.0349754 -0.236873 0.118762 0.027476 -0.236873 0.123121 0.0180351 -0.236873 0.12473 0.0173489 -0.236873 0.127625 -0.00246241 -0.236873 0.125062 -0.0127457 -0.236873 0.126455 -0.0124431 -0.236873 0.121923 -0.0226592 -0.236873 0.110507 -0.0399374 -0.236873 0.119056 -0.0310475 -0.236873 0.113052 -0.0391059 -0.236873 0.0936212 -0.0519251 -0.236873 0.0881138 -0.0554953 -0.236873 0.0838184 -0.0553944 -0.236873 0.0783348 -0.0578093 -0.236873 0.0735449 -0.0570034 -0.236873 0.0683025 -0.05839 -0.236873 0.0631508 -0.0566972 -0.236873 0.0529899 -0.0544863 -0.236873 0.0434083 -0.050446 -0.236873 0.0397174 -0.049821 -0.236873 0.031659 -0.0438172 -0.236873 0.0247656 -0.0365053 -0.236873 0.0212376 -0.0290059 -0.236873 0.0168786 -0.019565 -0.236873 0.0143286 -0.00948386 -0.236873 0.0136744 0.000894189 -0.236873 0.0135452 0.0109132 -0.236873 0.0180773 0.0211293 -0.236873 0.0294926 0.0384075 -0.236873 0.0269477 0.037576 -0.236873 0.0342596 0.0444694 -0.236873 0.0426575 0.0499885 -0.236873 0.012375 0.000932466 -0.236873 0.0164307 0.020539 -0.236873 0.020944 0.0295176 -0.237673 0.0342596 0.0444694 -0.237673 0.0426575 0.0499885 -0.236873 0.0518861 0.0539654 -0.237673 0.0518861 0.0539654 -0.236873 0.0616651 0.0562793 -0.236873 0.0816781 0.0556898 -0.237673 0.0913039 0.0528043 -0.236873 0.100282 0.048291 -0.237673 0.100282 0.048291 -0.236873 0.120753 0.0265775 -0.236873 0.127044 0.00756986 -0.237673 0.127044 0.00756986 -0.237673 0.127625 -0.00246241 -0.237873 0.0783637 -0.0580072 -0.237873 0.0784794 -0.0587988 -0.237873 0.0486221 -0.05452 -0.237873 0.0483264 -0.0552634 -0.237873 0.0309939 -0.044564 -0.237873 0.0246086 -0.0366293 -0.237873 0.0239809 -0.0371253 -0.237873 0.0190704 -0.0282023 -0.237873 0.0150797 -0.0189417 -0.237873 0.0113754 0.000961909 -0.237873 0.0133493 0.0109537 -0.237873 0.0162449 0.0206129 -0.237873 0.0267984 0.037709 -0.237873 0.020093 0.0300428 -0.237873 0.0425626 0.0501645 -0.237873 0.0421832 0.0508688 -0.237873 0.0515719 0.0549147 -0.237873 0.0717268 0.0578596 -0.237873 0.0817186 0.0558857 -0.237873 0.0913778 0.0529901 -0.237873 0.108474 0.0424366 -0.237873 0.116019 0.0355953 -0.237873 0.12568 0.0176631 -0.237873 0.128034 0.00771443 -0.237873 0.127825 -0.0024683 -0.237873 0.127434 -0.0126457 -0.237873 0.123755 -0.0221429 -0.237873 0.119226 -0.0311526 -0.237873 0.113202 -0.0392389 -0.237873 0.10636 -0.046784 -0.237873 0.0978167 -0.0523988 -0.237873 0.0974373 -0.0516945 -0.233695 0.0138001 -0.0182264 -0.233695 0.0181901 -0.0286766 -0.233695 0.0174407 -0.0272384 -0.233695 0.015434 -0.0228077 -0.237673 0.0181901 -0.0286766 -0.233695 0.0225149 -0.0355283 -0.233695 0.0308609 -0.0447133 -0.233695 0.0288844 -0.04287 -0.237673 0.0308609 -0.0447133 -0.233695 0.0255478 -0.0393309 -0.237673 0.0390871 -0.0508421 -0.233695 0.0363754 -0.0490631 -0.233695 0.0538797 -0.0573641 -0.233695 0.0586086 -0.058502 -0.233695 0.0785083 -0.0589967 -0.237673 0.0785083 -0.0589967 -0.233695 0.0920427 -0.0553309 -0.233695 0.0884908 -0.0566345 -0.233695 0.0874614 -0.0569648 -0.233695 0.0964734 -0.0533243 -0.233695 0.104763 -0.04825 -0.233695 0.100723 -0.0509586 -0.233695 0.0979116 -0.0525749 -0.233695 0.112105 -0.0418805 -0.233695 0.113948 -0.039904 -0.233695 0.118298 -0.0343895 -0.233695 0.124684 -0.0225124 -0.233695 0.123174 -0.0259813 -0.233695 0.12091 -0.0302863 -0.233695 0.120077 -0.0316778 -0.233695 0.12848 -0.00734951 -0.228873 0.0249727 0.00957846 -0.228873 0.0278558 0.0181641 -0.230473 0.0323585 0.0260223 -0.230473 0.0383077 0.0328511 -0.230473 0.0535844 0.0424203 -0.228873 0.0623249 0.044793 -0.228873 0.0713603 0.045415 -0.230473 0.0713603 0.045415 -0.230473 0.0803434 0.0442623 -0.228873 0.088929 0.0413792 -0.230473 0.088929 0.0413792 -0.230473 0.0967872 0.0368765 -0.228873 0.113185 0.0156506 -0.230473 0.115558 0.00691013 -0.230473 0.11618 -0.00212528 -0.236073 0.0138743 0.0008883 -0.236673 0.0151337 0.0111732 -0.236673 0.0182616 0.0210516 -0.236073 0.0182616 0.0210516 -0.236073 0.0231513 0.030187 -0.236073 0.037496 0.0450206 -0.236673 0.037496 0.0450206 -0.236073 0.0464625 0.0502136 -0.236073 0.0562306 0.0536706 -0.236073 0.0664676 0.0552738 -0.236673 0.0664676 0.0552738 -0.236073 0.0768248 0.0549687 -0.236073 0.0869496 0.0527657 -0.236673 0.0869496 0.0527657 -0.236673 0.112591 0.0358249 -0.236073 0.112591 0.0358249 -0.236073 0.118589 0.0273757 -0.236673 0.118589 0.0273757 -0.236073 0.122933 0.0179683 -0.236673 0.122933 0.0179683 -0.236073 0.125474 0.00792297 -0.236673 0.125474 0.00792297 -0.236073 0.126126 -0.00241824 -0.230673 0.0151337 0.0111732 -0.233273 0.0151337 0.0111732 -0.230673 0.0231513 0.030187 -0.230673 0.0296364 0.0382684 -0.233273 0.0231513 0.030187 -0.230673 0.037496 0.0450206 -0.230673 0.0464625 0.0502136 -0.233273 0.0562306 0.0536706 -0.233273 0.0664676 0.0552738 -0.230673 0.105143 0.043028 -0.233273 0.105143 0.043028 -0.230673 0.112591 0.0358249 -0.230673 0.118589 0.0273757 -0.233273 0.122933 0.0179683 -0.230673 0.125474 0.00792297 -0.226573 0.117524 0.0455945 -0.226573 0.11702 0.0477999 -0.226573 0.117102 0.0482108 -0.226573 0.118236 0.0425866 -0.226573 0.116069 0.0432364 -0.226573 0.115878 0.0440424 -0.226573 0.114891 0.0424746 -0.226573 0.114487 0.0437473 -0.226573 0.116116 0.0448357 -0.226573 0.121663 0.0433723 -0.225073 0.137703 0.00785948 -0.224773 0.135051 0.0188694 -0.225073 0.135339 0.0189561 -0.225073 0.131169 0.0295077 -0.225073 0.125309 0.0392227 -0.224773 0.125066 0.0390469 -0.224773 0.117709 0.0476191 -0.224773 0.109035 0.0548542 -0.224773 0.088719 0.0645558 -0.225073 0.0888016 0.0648442 -0.225073 0.0776729 0.0670523 -0.225073 0.0663322 0.0673864 -0.225073 0.0550928 0.0658371 -0.224773 0.0443785 0.0621695 -0.225073 0.0341491 0.0573107 -0.224773 0.0343067 0.0570554 -0.224773 0.0173733 0.0422192 -0.225073 0.017141 0.042409 -0.225073 0.0107191 0.0330557 -0.224773 0.0109796 0.0329071 -0.225073 0.00593539 0.0227678 -0.225073 0.00292211 0.0118297 -0.224773 0.00621699 0.0226644 -0.224773 0.00494848 -0.0203993 -0.225073 0.0220799 -0.0493626 -0.224773 0.0222906 -0.049149 -0.224773 0.0407185 -0.0620822 -0.225073 0.0511983 -0.0663741 -0.225073 0.062327 -0.0685823 -0.224773 0.0623607 -0.0682842 -0.225073 0.0736677 -0.0689163 -0.224773 0.0736516 -0.0686168 -0.225073 0.0849071 -0.0673671 -0.225073 0.0957345 -0.0639773 -0.225073 0.114976 -0.0520991 -0.225073 0.129281 -0.0345857 -0.229744 0.13677 0.0108917 -0.228737 0.136426 -0.0164396 -0.229744 0.136616 -0.0132729 -0.229744 0.00338389 0.011743 -0.229744 0.00322967 -0.0124216 -0.229744 0.00284474 -0.00994789 -0.229744 0.00276315 -0.00933005 -0.229747 0.00276447 -0.00927974 -0.229763 0.00280535 -0.00924732 -0.229767 0.00280937 -0.00919339 -0.229782 0.00284765 -0.0091647 -0.230996 0.00598414 -0.00722854 -0.231382 0.00674724 0.00109824 -0.231382 0.00684339 -0.00471787 -0.232755 0.0105763 -0.00393081 -0.231376 0.00684808 -0.00505589 -0.231259 0.00661445 -0.00619316 -0.229744 0.00527211 -0.020876 -0.229749 0.00508066 -0.0201997 -0.229764 0.00510248 -0.0201363 -0.229776 0.00514555 -0.0201645 -0.229807 0.00520494 -0.0200611 -0.231709 0.00979229 -0.0170895 -0.231741 0.00984059 -0.0169305 -0.231907 0.00997576 -0.0156271 -0.23191 0.00969406 -0.0144119 -0.232755 0.0119078 -0.0136685 -0.232755 0.0110406 -0.00882717 -0.23181 0.00923331 -0.0135899 -0.229807 0.00342844 -0.0125534 -0.229776 0.00332902 -0.0124876 -0.229764 0.00330307 -0.0125321 -0.229749 0.00325517 -0.0124852 -0.231741 0.0259832 -0.0448444 -0.232755 0.0250508 -0.0397621 -0.231907 0.0254485 -0.043648 -0.232755 0.021984 -0.035917 -0.230491 0.0196098 -0.0429691 -0.229764 0.0181223 -0.044304 -0.229776 0.0181226 -0.0442526 -0.229776 0.0235342 -0.0499926 -0.229744 0.0235346 -0.0501119 -0.229807 0.0235339 -0.0498734 -0.232755 0.0320826 -0.0466286 -0.231413 0.0260819 -0.0462038 -0.231709 0.0260209 -0.0450063 -0.232755 0.0490289 -0.0564553 -0.231766 0.0504563 -0.0598416 -0.23181 0.0507233 -0.0598029 -0.230491 0.0474628 -0.0625099 -0.229807 0.0469233 -0.0643118 -0.229776 0.0468166 -0.064365 -0.229764 0.0468421 -0.0644097 -0.229744 0.0544333 -0.0667334 -0.229807 0.0543134 -0.0665272 -0.230491 0.0548541 -0.0647256 -0.229776 0.0543732 -0.0666303 -0.231413 0.0546853 -0.0620752 -0.231481 0.054581 -0.0618589 -0.230491 0.0813547 -0.0655062 -0.229807 0.0817884 -0.0673365 -0.229776 0.0817226 -0.0674359 -0.229744 0.0816566 -0.0675353 -0.229807 0.0892961 -0.06556 -0.229776 0.0893995 -0.0656194 -0.229749 0.0894346 -0.0656843 -0.229764 0.0893713 -0.0656624 -0.231364 0.0875257 -0.0616202 -0.231481 0.0871937 -0.0613834 -0.231808 0.08578 -0.0608372 -0.231907 0.0848621 -0.0607892 -0.231928 0.0842326 -0.0608834 -0.23191 0.0836469 -0.0610709 -0.23189 0.0834066 -0.0611791 -0.232755 0.0829034 -0.0588571 -0.231766 0.082613 -0.0616987 -0.229776 0.113488 -0.0526424 -0.229764 0.113539 -0.0526426 -0.229749 0.113522 -0.0527076 -0.230653 0.111917 -0.050813 -0.229776 0.119228 -0.0472308 -0.229744 0.119347 -0.0472303 -0.229764 0.119225 -0.0472822 -0.229784 0.119161 -0.0472682 -0.230969 0.116759 -0.0450714 -0.232755 0.115864 -0.0386824 -0.231709 0.114241 -0.0447441 -0.232755 0.112576 -0.0423402 -0.231808 0.113702 -0.0448991 -0.231907 0.112883 -0.0453164 -0.229749 0.135939 -0.0163937 -0.231413 0.13131 -0.0160796 -0.229776 0.135865 -0.0163917 -0.229764 0.135889 -0.0164376 -0.230491 0.133961 -0.0159108 -0.231741 0.130182 -0.0168449 -0.232755 0.12569 -0.021736 -0.230653 0.131325 -0.0231492 -0.229784 0.133604 -0.023872 -0.229776 0.1336 -0.0239483 -0.229764 0.133645 -0.0239228 -0.231382 0.133253 -0.00262818 -0.231382 0.132814 -0.00842854 -0.231316 0.132854 -0.0095191 -0.231129 0.133225 -0.0105341 -0.229763 0.136579 -0.0131878 -0.229755 0.136604 -0.0131747 -0.229782 0.136541 -0.0131029 -0.229744 0.136498 -0.0138849 -0.229767 0.136578 -0.0131338 -0.229744 0.133432 -0.0246512 -0.229744 0.129944 -0.0324017 -0.229744 0.125146 -0.0401738 -0.229744 0.122239 -0.0439532 -0.231766 0.11139 -0.0472286 -0.231495 0.111165 -0.0484183 -0.229744 0.105385 -0.0585752 -0.232755 0.0967694 -0.0539119 -0.232755 0.0922891 -0.055941 -0.229744 0.0980534 -0.0624671 -0.232755 0.0731658 -0.0601887 -0.232755 0.0682478 -0.0602471 -0.232755 0.0633418 -0.0598993 -0.232755 0.0445017 -0.0545333 -0.229744 0.0383632 -0.0607088 -0.232755 0.0359995 -0.0496031 -0.230491 0.0249029 -0.0485836 -0.231495 0.0223466 -0.0419297 -0.232755 0.0192451 -0.0318318 -0.229744 0.0126298 -0.0368595 -0.229744 0.00946509 -0.0312556 -0.232755 0.0148239 -0.0230541 -0.229744 0.00829784 -0.0288185 -0.230491 0.00703551 -0.0196286 -0.228737 0.0674084 0.0674358 -0.228737 0.0663322 0.0673864 -0.228737 0.135339 0.0189561 -0.226273 0.0203109 0.0460225 -0.228737 0.0203109 0.0460225 -0.226273 0.00357429 0.0149096 -0.228737 0.00292211 0.0118297 -0.226273 0.0262185 0.0515919 -0.225073 0.0250236 0.0505691 -0.226273 0.0250236 0.0505691 -0.228737 0.0994107 0.0608229 -0.225073 0.0994107 0.0608229 -0.226273 0.0856745 0.0656607 -0.225073 0.11792 0.0478327 -0.228737 0.137703 0.00785948 -0.228737 0.137233 0.0109725 -0.226273 0.137233 0.0109725 -0.228737 0.13213 0.027483 -0.228737 0.131169 0.0295077 -0.226273 0.116787 0.0489241 -0.225073 0.109207 0.0550997 -0.228737 0.109207 0.0550997 -0.228737 0.0766014 0.067165 -0.228737 0.0776729 0.0670523 -0.225073 0.0442654 0.0624473 -0.228737 0.0442654 0.0624473 -0.226273 0.0503617 0.0645986 -0.228737 0.0144716 0.0389171 -0.228737 0.00590563 0.0226867 -0.228737 0.00593539 0.0227678 -0.226273 0.00590563 0.0226867 -0.228737 0.0107191 0.0330557 -0.226273 0.136426 -0.0164396 -0.225073 0.122859 -0.0439389 -0.226273 0.113781 -0.0531218 -0.225073 0.105851 -0.0588406 -0.226273 0.0543254 -0.0671906 -0.225073 0.0405892 -0.0623529 -0.226273 0.0465483 -0.0648593 -0.228737 0.0176431 -0.0445465 -0.225073 0.0146913 -0.0407527 -0.226273 0.0232125 -0.050454 -0.228737 0.00229707 -0.00938942 -0.228737 0.00276682 -0.0125024 -0.226273 0.00463634 -0.0204032 -0.225073 0.00466128 -0.020486 -0.228737 0.00466128 -0.020486 -0.228737 0.00787013 -0.0290129 -0.225073 0.0088311 -0.0310376 -0.228737 0.0088311 -0.0310376 -0.225073 0.0307928 -0.0566297 -0.228737 0.0381439 -0.0611243 -0.228737 0.0633985 -0.068695 -0.228737 0.0725915 -0.0689657 -0.228737 0.0957345 -0.0639773 -0.228737 0.134094 -0.0242166 -0.226273 0.134094 -0.0242166 -0.228737 0.134065 -0.0242978 -0.225073 0.134065 -0.0242978 -0.228737 0.130359 -0.032621 -0.228737 0.125528 -0.040447 -0.185973 0.101937 0.0509715 -0.185973 0.0508964 0.0569558 -0.185973 0.067438 0.0460792 -0.185973 0.0612097 0.0593962 -0.185973 0.0930892 0.0371885 -0.185973 0.0753148 0.0458472 -0.185973 0.0950269 0.0383007 -0.185973 0.092468 0.0557313 -0.185973 0.0717901 0.0600087 -0.185973 0.0698266 0.0474347 -0.185973 0.0669438 0.0415247 -0.185973 0.0842839 0.0391566 -0.185973 0.0756341 0.044464 -0.185973 0.0972582 0.0384153 -0.185973 0.110436 0.0446396 -0.185973 0.117706 0.0369282 -0.185973 0.123527 0.0280715 -0.185973 0.127721 0.0183386 -0.185973 0.129539 -0.0130812 -0.185973 0.118179 -0.00218416 -0.185973 0.116976 -0.0115562 -0.185973 0.126496 -0.023233 -0.185973 0.113969 -0.0205135 -0.185973 0.107693 -0.048471 -0.185973 0.0787902 -0.0609262 -0.185973 0.0780073 -0.0482952 -0.185973 0.0592088 -0.0477415 -0.185973 0.0295641 -0.0461696 -0.185973 0.0349287 -0.0338292 -0.185973 0.029152 -0.0263518 -0.185973 0.00983874 -0.00955522 -0.185973 0.00922632 0.00102521 -0.185973 0.0229493 0.00969817 -0.185973 0.0257601 0.018368 -0.185973 0.0301526 0.0263538 -0.185973 0.0182635 0.0311722 -0.185973 0.0245954 0.0396709 -0.185973 0.0359698 0.0333699 -0.185973 0.0430038 0.0391656 -0.185973 0.0450952 0.0399518 -0.185973 0.0491848 0.0384818 -0.185973 0.0505833 0.0369984 -0.190673 0.0280438 0.0155096 -0.190673 0.0277649 0.0154865 -0.190673 0.0268973 0.0148354 -0.191424 0.028007 0.0142601 -0.190673 0.0283209 0.0154701 -0.190673 0.0286636 0.0153238 -0.190673 0.0291487 0.0147691 -0.190673 0.0291075 0.014853 -0.190673 0.0288148 0.0152141 -0.185973 0.0274142 0.0153606 -0.190673 0.0274142 0.0153606 -0.190673 0.0272568 0.0152599 -0.185973 0.0269434 0.0149167 -0.190673 0.0269434 0.0149167 -0.185973 0.0267576 0.0142969 -0.190673 0.0267576 0.0142969 -0.185973 0.0275801 0.0126146 -0.185973 0.0279702 0.0130107 -0.185973 0.0283363 0.0125923 -0.185973 0.0290274 0.0129004 -0.185973 0.0297063 0.0142101 -0.185973 0.0291075 0.014853 -0.185973 0.0295037 0.0150664 -0.185973 0.0286636 0.0153238 -0.185973 0.0280438 0.0155096 -0.185973 0.0280571 0.0159594 -0.185973 0.0272007 0.0157568 -0.185973 0.0265604 0.0151531 -0.185973 0.0264543 0.0135679 -0.185973 0.0273504 0.0131965 -0.190673 0.0282959 -0.0126994 -0.191424 0.0271954 -0.0132922 -0.190673 0.0261318 -0.0126356 -0.185973 0.0282959 -0.0126994 -0.190673 0.0283371 -0.0127833 -0.190673 0.0280032 -0.0123383 -0.185973 0.027852 -0.0122286 -0.190673 0.027852 -0.0122286 -0.185973 0.0272322 -0.0120428 -0.190673 0.0275093 -0.0120823 -0.190673 0.0272322 -0.0120428 -0.190673 0.0269533 -0.0120659 -0.185973 0.0266026 -0.0121918 -0.190673 0.0266026 -0.0121918 -0.190673 0.0264452 -0.0122924 -0.190673 0.0260857 -0.012717 -0.185973 0.025946 -0.0132554 -0.185973 0.0283052 -0.0138675 -0.185973 0.0284449 -0.013329 -0.185973 0.0288947 -0.0133423 -0.185973 0.0272455 -0.011593 -0.185973 0.0261318 -0.0126356 -0.185973 0.0254962 -0.0132422 -0.185973 0.0260537 -0.0138012 -0.185973 0.0256427 -0.0139844 -0.185973 0.0267685 -0.0149378 -0.185973 0.0287047 -0.0140746 -0.190673 0.0438342 -0.0354668 -0.190673 0.0435415 -0.0351057 -0.190673 0.0433903 -0.0349959 -0.191424 0.0427337 -0.0360596 -0.190673 0.04167 -0.035403 -0.190673 0.0419835 -0.0350598 -0.190673 0.0430476 -0.0348497 -0.185973 0.0439832 -0.0360964 -0.190673 0.0439832 -0.0360964 -0.185973 0.0438754 -0.0355507 -0.185973 0.0435415 -0.0351057 -0.190673 0.0427705 -0.0348102 -0.190673 0.0424916 -0.0348333 -0.190673 0.0421408 -0.0349591 -0.185973 0.0419835 -0.0350598 -0.185973 0.041624 -0.0354843 -0.185973 0.0424916 -0.0348333 -0.185973 0.0430476 -0.0348497 -0.185973 0.0436267 -0.034613 -0.185973 0.0442303 -0.0352533 -0.185973 0.044433 -0.0361097 -0.185973 0.0441803 -0.0369526 -0.185973 0.04354 -0.0375562 -0.185973 0.0426836 -0.0377589 -0.185973 0.0412371 -0.0368659 -0.185973 0.0410344 -0.0360096 -0.185973 0.0414842 -0.0360228 -0.185973 0.0419274 -0.034563 -0.185973 0.0427838 -0.0343603 -0.190673 0.0693434 -0.044282 -0.190673 0.0697872 -0.0447528 -0.190673 0.0676231 -0.044689 -0.191424 0.0686868 -0.0453456 -0.190673 0.0680939 -0.0442452 -0.185973 0.0693434 -0.044282 -0.190673 0.0687236 -0.0440962 -0.190673 0.0674373 -0.0453088 -0.185973 0.0697854 -0.0440483 -0.185973 0.0702395 -0.0446534 -0.185973 0.0697872 -0.0447528 -0.185973 0.0701333 -0.0462386 -0.185973 0.0677938 -0.0467922 -0.185973 0.0671901 -0.0461519 -0.185973 0.0669875 -0.0452956 -0.185973 0.0671775 -0.0445633 -0.185973 0.0676231 -0.044689 -0.185973 0.0680939 -0.0442452 -0.185973 0.0683574 -0.0436778 -0.185973 0.0687236 -0.0440962 -0.185973 0.0691137 -0.0437001 -0.190673 0.0962419 -0.0370105 -0.190673 0.093892 -0.0375666 -0.191424 0.0951414 -0.0376034 -0.190673 0.0943912 -0.0366035 -0.190673 0.0954553 -0.0363934 -0.190673 0.095798 -0.0365397 -0.190673 0.0963909 -0.0376402 -0.190673 0.0962831 -0.0370944 -0.190673 0.0959492 -0.0366494 -0.190673 0.0951782 -0.0363539 -0.190673 0.0948993 -0.036377 -0.185973 0.0951782 -0.0363539 -0.190673 0.0945486 -0.0365029 -0.190673 0.0940778 -0.0369468 -0.190673 0.0940317 -0.0370281 -0.185973 0.093892 -0.0375666 -0.185973 0.0947145 -0.0392489 -0.185973 0.0957343 -0.0387038 -0.185973 0.0961618 -0.0389631 -0.185973 0.0962051 -0.03826 -0.185973 0.0966507 -0.0383857 -0.185973 0.0963909 -0.0376402 -0.185973 0.0962419 -0.0370105 -0.185973 0.095798 -0.0365397 -0.185973 0.0960344 -0.0361568 -0.185973 0.0945486 -0.0365029 -0.185973 0.0940778 -0.0369468 -0.185973 0.094041 -0.0381962 -0.185973 0.0935887 -0.0382955 -0.190673 0.112649 -0.0147264 -0.190673 0.110743 -0.0157533 -0.190673 0.1114 -0.0146896 -0.190673 0.113093 -0.0151972 -0.185973 0.112649 -0.0147264 -0.190673 0.11203 -0.0145406 -0.190673 0.110929 -0.0151335 -0.185973 0.113091 -0.0144927 -0.185973 0.113546 -0.0150979 -0.185973 0.113692 -0.0158401 -0.185973 0.113093 -0.0151972 -0.185973 0.113103 -0.0163654 -0.185973 0.112799 -0.0172867 -0.185973 0.11203 -0.0145406 -0.185973 0.11242 -0.0141446 -0.185973 0.111664 -0.0141223 -0.185973 0.1114 -0.0146896 -0.185973 0.110929 -0.0151335 -0.185973 0.110743 -0.0157533 -0.185973 0.110484 -0.0150077 -0.185973 0.110294 -0.01574 -0.185973 0.110496 -0.0165964 -0.185973 0.1111 -0.0172367 -0.185973 0.111679 -0.017 -0.185973 0.112743 -0.0167899 -0.191424 0.112804 0.0117623 -0.190673 0.114054 0.0117255 -0.190673 0.111555 0.0117991 -0.190673 0.112054 0.0127621 -0.190673 0.111741 0.0124189 -0.190673 0.112841 0.0130117 -0.190673 0.113946 0.0122712 -0.185973 0.113905 0.0123551 -0.190673 0.113905 0.0123551 -0.190673 0.113612 0.0127162 -0.190673 0.113461 0.012826 -0.190673 0.113118 0.0129722 -0.185973 0.112841 0.0130117 -0.190673 0.112562 0.0129886 -0.190673 0.112212 0.0128628 -0.185973 0.111555 0.0117991 -0.190673 0.111695 0.0123376 -0.185973 0.113903 0.0130596 -0.185973 0.113231 0.0134078 -0.185973 0.112475 0.0134301 -0.185973 0.112212 0.0128628 -0.185973 0.111295 0.0125447 -0.185973 0.111741 0.0124189 -0.185973 0.111105 0.0118123 -0.185973 0.112754 0.010063 -0.185973 0.113868 0.0111057 -0.185973 0.114251 0.0108693 -0.185973 0.114504 0.0117122 -0.185973 0.114054 0.0117255 -0.185973 0.113461 0.012826 -0.191424 0.0972662 0.0345297 -0.190673 0.0961565 0.0351049 -0.190673 0.0984079 0.0350386 -0.185973 0.0984079 0.0350386 -0.190673 0.098074 0.0354836 -0.190673 0.0975801 0.0357396 -0.185973 0.0975801 0.0357396 -0.190673 0.0970241 0.035756 -0.185973 0.0970241 0.035756 -0.190673 0.096516 0.0355295 -0.185973 0.096516 0.0355295 -0.185973 0.0961565 0.0351049 -0.185973 0.0960167 0.0345665 -0.185973 0.0958196 0.0354226 -0.185973 0.0964599 0.0360263 -0.185973 0.0972294 0.0332802 -0.185973 0.0968393 0.0328841 -0.185973 0.0975955 0.0328619 -0.185973 0.0978591 0.0334292 -0.185973 0.0982865 0.0331699 -0.185973 0.0983299 0.0338731 -0.185973 0.0987755 0.0337473 -0.185973 0.0985157 0.0344929 -0.185973 0.0989655 0.0344796 -0.185973 0.0987628 0.035336 -0.185973 0.098074 0.0354836 -0.190673 0.0719698 0.0448794 -0.190673 0.0724136 0.0444085 -0.190673 0.0702495 0.0444723 -0.190673 0.0725626 0.0437789 -0.185973 0.0724136 0.0444085 -0.185973 0.0719698 0.0448794 -0.190673 0.07135 0.0450651 -0.190673 0.0707203 0.0449162 -0.185973 0.0707203 0.0449162 -0.185973 0.0702495 0.0444723 -0.185973 0.0725626 0.0437789 -0.185973 0.0724229 0.0432404 -0.185973 0.0715553 0.0425894 -0.185973 0.0705054 0.0428618 -0.185973 0.0709838 0.0454835 -0.185973 0.07135 0.0450651 -0.185973 0.0449086 0.0377727 -0.185973 0.0456663 0.0370273 -0.185973 0.0460002 0.0365824 -0.185973 0.0463551 0.0368797 -0.185973 0.0465578 0.0360234 -0.185973 0.0463051 0.0351804 -0.185973 0.0459222 0.0354168 -0.185973 0.0456648 0.0345768 -0.185973 0.0454514 0.034973 -0.185973 0.0448084 0.0343742 -0.185973 0.0439655 0.0346268 -0.185973 0.0431592 0.0361235 -0.185973 0.043609 0.0361102 -0.185973 0.0434119 0.0369664 -0.185973 0.0437487 0.0366487 -0.185973 0.0441082 0.0370732 -0.185973 0.046108 0.0360366 -0.190673 0.0456663 0.0370273 -0.190673 0.0455151 0.0371371 -0.185973 0.0451724 0.0372834 -0.190673 0.0448953 0.0373229 -0.185973 0.0446163 0.0372997 -0.190673 0.0441082 0.0370732 -0.190673 0.0437948 0.03673 -0.190673 0.0451724 0.0372834 -0.190673 0.0446163 0.0372997 -0.190673 0.0442656 0.0371739 -0.190673 0.045959 0.0366663 -0.238073 0.124436 0.00776051 -0.238073 0.121943 0.017618 -0.237873 0.122132 0.0176847 -0.238073 0.117681 0.0268495 -0.237873 0.117854 0.0269497 -0.238073 0.111795 0.0351406 -0.237873 0.111946 0.035271 -0.238073 0.104485 0.042209 -0.237873 0.104611 0.042365 -0.238073 0.0866327 0.0517647 -0.237873 0.086693 0.0519553 -0.237873 0.056439 0.0528465 -0.238073 0.0469027 0.0492603 -0.237873 0.0468189 0.0494419 -0.237873 0.0379881 0.0443275 -0.238073 0.0303912 0.0375385 -0.238073 0.0240274 0.0296082 -0.237873 0.0238605 0.0297185 -0.238073 0.0192291 0.0206436 -0.238073 0.0161597 0.01095 -0.237873 0.0190448 0.0207213 -0.237873 0.0159643 0.0109925 -0.237473 0.125671 0.00795392 -0.237473 0.123121 0.0180351 -0.237473 0.118762 0.027476 -0.237473 0.112743 0.0359552 -0.237273 0.112895 0.0360855 -0.237473 0.105268 0.0431839 -0.237473 0.0965916 0.0489161 -0.237273 0.096686 0.0490924 -0.237473 0.08701 0.0529564 -0.237473 0.0768491 0.0551672 -0.237473 0.0561816 0.0538645 -0.237473 0.0463787 0.0503952 -0.237473 0.0294926 0.0384075 -0.237473 0.0229844 0.0302973 -0.237273 0.0293489 0.0385465 -0.237273 0.0228176 0.0304075 -0.237473 0.0180773 0.0211293 -0.237473 0.0149383 0.0112157 -0.237273 0.0134745 0.000900077 -0.237273 0.0127748 0.000920688 -0.237473 0.0131535 -0.00907088 -0.237273 0.0133514 -0.00904197 -0.237273 0.0195987 -0.0279177 -0.237273 0.0250794 -0.0362573 -0.237473 0.031792 -0.0436678 -0.237273 0.0488438 -0.0539625 -0.237473 0.0583623 -0.0570239 -0.237273 0.0584029 -0.0568281 -0.237473 0.0783059 -0.0576114 -0.237273 0.0879881 -0.0551156 -0.237273 0.112753 -0.0388399 -0.237273 0.123198 -0.0219211 -0.237473 0.123383 -0.021995 -0.237273 0.126063 -0.0123621 -0.237473 0.127425 -0.00245652 -0.237873 0.0173228 0.000786719 -0.238073 0.017737 -0.00895005 -0.238073 0.0201309 -0.018414 -0.238073 0.024223 -0.0272769 -0.237873 0.0300257 -0.0351066 -0.238073 0.0450363 -0.0474043 -0.238073 0.0635701 -0.0532728 -0.238073 0.0733279 -0.0535602 -0.237873 0.0635945 -0.0530742 -0.238073 0.092175 -0.0487929 -0.237873 0.0920912 -0.0486113 -0.237873 0.100507 -0.0437373 -0.238073 0.100623 -0.0439004 -0.237873 0.107883 -0.0374001 -0.238073 0.108027 -0.0375391 -0.237873 0.121495 -0.0119696 -0.237873 0.122677 -0.00231666 -0.238073 0.121374 0.00728085 -0.237873 0.121571 0.0073118 -0.238073 0.119021 0.0165838 -0.238073 0.114998 0.0252959 -0.238073 0.109443 0.0331205 -0.237873 0.109595 0.0332509 -0.238073 0.102545 0.0397913 -0.238073 0.0945389 0.0450809 -0.237873 0.10267 0.0399472 -0.237873 0.0857573 0.049 -0.238073 0.0763204 0.0508495 -0.238073 0.0667286 0.051132 -0.237873 0.0667161 0.0513316 -0.237873 0.0571992 0.0498412 -0.238073 0.0266138 0.0278994 -0.237873 0.0324759 0.0355225 -0.238073 0.0220855 0.0194391 -0.238473 0.0117683 -0.00927329 -0.238473 0.0181901 -0.0286766 -0.238473 0.023824 -0.0372492 -0.238273 0.0309939 -0.044564 -0.238273 0.0483264 -0.0552634 -0.238273 0.0682731 -0.0593895 -0.238473 0.0785083 -0.0589967 -0.238273 0.0784794 -0.0587988 -0.238473 0.0884908 -0.0566345 -0.238473 0.0979116 -0.0525749 -0.238273 0.10636 -0.046784 -0.238473 0.106484 -0.0469409 -0.238473 0.113948 -0.039904 -0.238273 0.113799 -0.039771 -0.238273 0.124498 -0.0224385 -0.238473 0.128824 -0.00249774 -0.238273 0.128625 -0.00249185 -0.238673 0.0635575 -0.0326827 -0.238673 0.0625024 -0.0312766 -0.238673 0.0609418 -0.0304676 -0.238873 0.0592234 -0.030612 -0.238673 0.057579 -0.0311316 -0.238673 0.0426598 -0.0212968 -0.238673 0.0446496 -0.020826 -0.238873 0.045475 -0.0211445 -0.238873 0.0482816 -0.0248847 -0.238673 0.0480107 -0.0229009 -0.238673 0.0466081 -0.0214131 -0.238873 0.0465031 -0.0215833 -0.238673 0.0398888 -0.00894059 -0.238873 0.0393656 -0.00729741 -0.238873 0.0383639 -0.00596254 -0.238873 0.035214 -0.00514533 -0.238673 0.0369325 -0.00500087 -0.238673 0.0351753 -0.00494912 -0.238873 0.0326112 -0.00709845 -0.238673 0.0319922 -0.00870799 -0.238673 0.0400817 0.0108935 -0.238673 0.0390266 0.0122996 -0.238673 0.0357087 0.0131604 -0.238873 0.0342232 0.0122846 -0.238873 0.0331447 0.011011 -0.238873 0.0327256 0.0093956 -0.238673 0.0329671 0.0111031 -0.238673 0.0424838 0.0265196 -0.238673 0.0452255 0.0285769 -0.238873 0.0452642 0.0283807 -0.238873 0.0461011 0.0284501 -0.238673 0.0485433 0.0277161 -0.238873 0.0479605 0.0278927 -0.238873 0.0494157 0.0262286 -0.238673 0.0499389 0.0245854 -0.238673 0.0495984 0.02631 -0.238873 0.049292 0.0264803 -0.238873 0.0581923 0.0334049 -0.238673 0.0595699 0.0364539 -0.238673 0.0629326 0.0371179 -0.238873 0.064364 0.0361563 -0.238873 0.0653657 0.0348214 -0.238873 0.065242 0.0350731 -0.238673 0.0835276 0.0346345 -0.238673 0.082125 0.0361222 -0.238673 0.0801664 0.0367093 -0.238873 0.0768591 0.0347309 -0.238673 0.0919598 0.0250622 -0.238673 0.0930959 0.0264037 -0.238873 0.0932159 0.0262438 -0.238873 0.0936881 0.0265457 -0.238873 0.0955771 0.0269927 -0.238673 0.0964586 0.0270678 -0.238673 0.0980193 0.0262587 -0.238673 0.0990744 0.0248527 -0.238873 0.099215 0.0231339 -0.238873 0.0988917 0.0247712 -0.238873 0.0987681 0.0250229 -0.238873 0.107485 0.00882123 -0.238873 0.106483 0.0101561 -0.238673 0.101689 0.0104538 -0.238673 0.100553 0.00911223 -0.238673 0.100165 -0.00874026 -0.238873 0.101747 -0.00751373 -0.238673 0.107003 -0.00894171 -0.238873 0.105949 -0.00795337 -0.238673 0.105601 -0.00745396 -0.238873 0.104468 -0.0071853 -0.238873 0.0902609 -0.0261213 -0.238873 0.09068 -0.0245058 -0.238873 0.0917585 -0.0232322 -0.238673 0.0906481 -0.0241568 -0.238873 0.0932828 -0.0225527 -0.238873 0.0941197 -0.0224833 -0.238673 0.0941256 -0.0222834 -0.238673 0.0960841 -0.0228705 -0.238873 0.094951 -0.0226019 -0.238673 0.0974867 -0.0243583 -0.238873 0.0973107 -0.0244531 -0.238673 0.0745525 -0.0330066 -0.238873 0.0748683 -0.0328546 -0.238873 0.0773328 -0.0311455 -0.238673 0.0772941 -0.0309493 -0.238873 0.0781697 -0.0310761 -0.238873 0.079001 -0.0311946 -0.238873 0.0818077 -0.0349349 -0.241473 0.0601621 0.0365959 -0.241673 0.0600672 0.036772 -0.241473 0.0639104 0.0364855 -0.241673 0.0654181 0.0351679 -0.241673 0.0426295 0.0267766 -0.241473 0.0442121 0.0280031 -0.241673 0.0441172 0.0281792 -0.241473 0.0479605 0.0278927 -0.241473 0.049292 0.0264803 -0.241473 0.049739 0.0245913 -0.241473 0.0402223 0.00917477 -0.241673 0.0365902 0.0132335 -0.241473 0.0397753 0.0110638 -0.241473 0.0365843 0.0130336 -0.241473 0.0357475 0.0129642 -0.241673 0.0346005 0.0127627 -0.241673 0.0325256 0.00940149 -0.241473 0.0342232 0.0122846 -0.241673 0.0331128 0.0113601 -0.241673 0.039418 -0.00695087 -0.241473 0.0368822 -0.00519447 -0.241473 0.0360509 -0.00507592 -0.241673 0.0360568 -0.004876 -0.241473 0.0321921 -0.00871388 -0.241473 0.0327495 -0.00685448 -0.241673 0.0340671 -0.00534682 -0.241473 0.0341619 -0.0055229 -0.241473 0.041204 -0.0230484 -0.241473 0.0438068 -0.0210953 -0.241473 0.045475 -0.0211445 -0.241673 0.0455252 -0.0209509 -0.241673 0.0634273 -0.0324176 -0.241673 0.0638981 -0.0344073 -0.241473 0.0636982 -0.0344014 -0.241473 0.0632512 -0.0325124 -0.241473 0.0576991 -0.0312916 -0.241473 0.0748683 -0.0328546 -0.241673 0.0746981 -0.0327496 -0.241473 0.0762807 -0.031523 -0.241673 0.0801341 -0.0314633 -0.241473 0.0974343 -0.0247048 -0.241473 0.0973107 -0.0244531 -0.241673 0.0974867 -0.0243583 -0.241473 0.0964327 -0.0233699 -0.241473 0.0959791 -0.0230407 -0.241473 0.0932828 -0.0225527 -0.241473 0.0922307 -0.0229303 -0.241473 0.09068 -0.0245058 -0.241473 0.0908183 -0.0242619 -0.241673 0.0995777 -0.0106988 -0.241473 0.100197 -0.00908929 -0.241473 0.1028 -0.00713616 -0.241673 0.101155 -0.00765572 -0.241473 0.104468 -0.0071853 -0.241673 0.102761 -0.00693995 -0.241673 0.104518 -0.00699171 -0.241473 0.105949 -0.00795337 -0.241473 0.106951 -0.00928825 -0.241673 0.107134 -0.00920682 -0.241473 0.105001 0.0109242 -0.241473 0.106483 0.0101561 -0.241473 0.106029 0.0104853 -0.241673 0.106134 0.0106555 -0.241473 0.103333 0.0109733 -0.241473 0.100311 0.00740476 -0.241473 0.102281 0.0105957 -0.241673 0.102186 0.0107718 -0.241673 0.0915184 0.0233606 -0.241673 0.0989441 0.0251178 -0.241673 0.0826028 0.0357754 -0.241473 0.0809919 0.0363909 -0.241673 0.0810421 0.0365845 -0.241473 0.0801605 0.0365094 -0.241473 0.0782716 0.0360624 -0.241473 0.0777994 0.0357605 -0.241673 0.0776793 0.0359205 -0.241473 0.0763017 0.0328715 -0.241473 0.0767209 0.0344869 -0.241673 0.0761018 0.0328774 -0.241473 0.0768591 0.0347309 -0.241373 0.110807 -0.0107031 -0.241673 0.111682 -0.00199278 -0.241673 0.107579 -0.0188402 -0.241373 0.107849 -0.0189702 -0.241373 0.103237 -0.0264417 -0.241373 0.0643818 -0.0423875 -0.241373 0.0479381 -0.0365039 -0.241373 0.0353091 -0.0244408 -0.241373 0.0280182 0.00047167 -0.238673 0.0314222 -0.0165969 -0.238973 0.0311447 -0.0167108 -0.238673 0.0411969 -0.0309191 -0.238973 0.0409897 -0.031136 -0.238673 0.0394077 -0.0291023 -0.238973 0.0353091 -0.0244408 -0.238673 0.0897776 -0.0374765 -0.238673 0.0644219 -0.0420902 -0.238973 0.0731584 -0.042646 -0.238973 0.0643818 -0.0423875 -0.238973 0.0971723 -0.032791 -0.238673 0.0983029 -0.0313891 -0.238673 0.101984 -0.0275214 -0.238673 0.103 -0.0262583 -0.238973 0.103237 -0.0264417 -0.238973 0.107849 -0.0189702 -0.238673 0.111682 -0.00199278 -0.241473 0.0336897 -0.00582485 -0.238873 0.0336897 -0.00582485 -0.241473 0.035214 -0.00514533 -0.238873 0.0368822 -0.00519447 -0.241473 0.0379103 -0.00563331 -0.241473 0.0383639 -0.00596254 -0.241473 0.0392419 -0.00704573 -0.241473 0.0396889 -0.0089347 -0.238873 0.0413423 -0.0228045 -0.238873 0.0422825 -0.0217748 -0.241473 0.0422825 -0.0217748 -0.238873 0.0427547 -0.0214729 -0.238873 0.0438068 -0.0210953 -0.238873 0.0446437 -0.0210259 -0.241473 0.0469567 -0.0219125 -0.238873 0.0469567 -0.0219125 -0.241473 0.0479583 -0.0232474 -0.238873 0.0478346 -0.0229957 -0.241473 0.0562014 -0.0341806 -0.241473 0.0567588 -0.0323212 -0.238873 0.0566205 -0.0325652 -0.238873 0.0576991 -0.0312916 -0.241473 0.0581712 -0.0309896 -0.241473 0.0592234 -0.030612 -0.241473 0.0600602 -0.0305426 -0.241473 0.0608915 -0.0306612 -0.238873 0.0608915 -0.0306612 -0.241473 0.0619196 -0.0311 -0.238873 0.0623732 -0.0314292 -0.241473 0.0623732 -0.0314292 -0.238873 0.0633749 -0.0327641 -0.238873 0.0636982 -0.0344014 -0.238873 0.07473 -0.0330986 -0.238873 0.0758085 -0.031825 -0.238873 0.0762807 -0.031523 -0.241473 0.0781697 -0.0310761 -0.238873 0.0800291 -0.0316335 -0.241473 0.0800291 -0.0316335 -0.238873 0.0804827 -0.0319627 -0.238873 0.0813607 -0.0330459 -0.241473 0.0813607 -0.0330459 -0.238873 0.0814844 -0.0332976 -0.241473 0.0818077 -0.0349349 -0.241473 0.0902609 -0.0261213 -0.238873 0.0908183 -0.0242619 -0.241473 0.0917585 -0.0232322 -0.238873 0.0922307 -0.0229303 -0.241473 0.0941197 -0.0224833 -0.238873 0.0959791 -0.0230407 -0.241473 0.094951 -0.0226019 -0.238873 0.0964327 -0.0233699 -0.238873 0.0974343 -0.0247048 -0.238873 0.0997776 -0.0107047 -0.238873 0.100335 -0.00884532 -0.238873 0.101275 -0.00781569 -0.241473 0.101275 -0.00781569 -0.238873 0.1028 -0.00713616 -0.238873 0.103636 -0.00706676 -0.238873 0.105496 -0.00762415 -0.238873 0.106827 -0.00903656 -0.241473 0.100868 0.00926416 -0.238873 0.10073 0.00902019 -0.241473 0.101809 0.0102938 -0.238873 0.101809 0.0102938 -0.238873 0.103333 0.0109733 -0.241473 0.10417 0.0110427 -0.238873 0.105001 0.0109242 -0.241473 0.107361 0.00907291 -0.241473 0.107808 0.00718394 -0.238873 0.0921374 0.0249702 -0.241473 0.0917183 0.0233548 -0.241473 0.0922757 0.0252141 -0.238873 0.0922757 0.0252141 -0.241473 0.0936881 0.0265457 -0.238873 0.0947402 0.0269233 -0.238873 0.0964084 0.0268742 -0.241473 0.0955771 0.0269927 -0.238873 0.0974365 0.0264353 -0.241473 0.0974365 0.0264353 -0.241473 0.0987681 0.0250229 -0.238873 0.0978901 0.0261061 -0.238873 0.0782716 0.0360624 -0.241473 0.0793237 0.03644 -0.238873 0.0801605 0.0365094 -0.241473 0.0820199 0.035952 -0.238873 0.0820199 0.035952 -0.241473 0.0824735 0.0356228 -0.238873 0.0833515 0.0345396 -0.238873 0.0837985 0.0326506 -0.241473 0.0834752 0.0342879 -0.241473 0.0833515 0.0345396 -0.241473 0.0581923 0.0334049 -0.238873 0.0586114 0.0350203 -0.238873 0.0587497 0.0352643 -0.241473 0.0587497 0.0352643 -0.238873 0.0596899 0.0362939 -0.238873 0.0601621 0.0365959 -0.238873 0.0612142 0.0369735 -0.238873 0.0620511 0.0370429 -0.241473 0.0620511 0.0370429 -0.238873 0.0628824 0.0369243 -0.238873 0.0639104 0.0364855 -0.241473 0.065242 0.0350731 -0.238873 0.065689 0.0331841 -0.238873 0.0422423 0.0248121 -0.238873 0.0426614 0.0264276 -0.238873 0.0427997 0.0266715 -0.238873 0.0437399 0.0277012 -0.241473 0.0427997 0.0266715 -0.238873 0.0442121 0.0280031 -0.241473 0.0461011 0.0284501 -0.238873 0.0469324 0.0283316 -0.238873 0.048414 0.0275635 -0.241473 0.033283 0.011255 -0.238873 0.0357475 0.0129642 -0.241473 0.0346954 0.0125866 -0.241473 0.0374157 0.012915 -0.238873 0.0374157 0.012915 -0.241473 0.0384437 0.0124762 -0.238873 0.0388973 0.0121469 -0.241473 0.0388973 0.0121469 -0.238873 0.039899 0.0108121 -0.241673 0.0434127 -0.0150884 -0.241673 0.0417083 -0.0132805 -0.239023 0.0381672 -0.0154721 -0.241673 0.0369104 -0.0131391 -0.241673 0.0351025 -0.0148436 -0.239023 0.0370379 -0.0173016 -0.241673 0.0344488 -0.016597 -0.241673 0.034389 -0.0172236 -0.239023 0.0373574 -0.0162356 -0.238673 0.0392502 -0.0152158 -0.239023 0.0392502 -0.0152158 -0.239023 0.0403163 -0.0155354 -0.239023 0.0410797 -0.0163452 -0.238673 0.041336 -0.0174282 -0.239023 0.041336 -0.0174282 -0.239023 0.0497856 -0.0294181 -0.241673 0.0475306 -0.0280261 -0.241673 0.0493385 -0.0263217 -0.241673 0.0517564 -0.0257495 -0.238673 0.049466 -0.0304841 -0.239023 0.049466 -0.0304841 -0.238673 0.0505954 -0.0286547 -0.239023 0.0505954 -0.0286547 -0.239023 0.0516784 -0.0283984 -0.239023 0.0527444 -0.028718 -0.238673 0.0535079 -0.0295277 -0.239023 0.0535079 -0.0295277 -0.239023 0.0671399 -0.0346204 -0.239023 0.0690327 -0.0336007 -0.239023 0.0700988 -0.0339203 -0.241673 0.0714908 -0.0316653 -0.241673 0.0731952 -0.0334732 -0.239023 0.0711185 -0.0358131 -0.238673 0.0671399 -0.0346204 -0.238673 0.0679497 -0.033857 -0.239023 0.0679497 -0.033857 -0.238673 0.0690327 -0.0336007 -0.239023 0.0708622 -0.0347301 -0.241673 0.0949845 -0.0190085 -0.239023 0.0987627 -0.0172571 -0.241673 0.0975059 -0.0149241 -0.239023 0.0998457 -0.0170008 -0.239023 0.100912 -0.0173204 -0.241673 0.0999238 -0.0143519 -0.238673 0.0979529 -0.0180205 -0.239023 0.0976334 -0.0190865 -0.239023 0.0979529 -0.0180205 -0.238673 0.0998457 -0.0170008 -0.238673 0.101675 -0.0181301 -0.239023 0.101675 -0.0181301 -0.241673 0.102708 0.00243028 -0.241673 0.105126 0.00300241 -0.239023 0.106114 3.39907e-05 -0.239023 0.106878 -0.000775794 -0.241673 0.109211 0.000481059 -0.239023 0.107134 -0.00185881 -0.238673 0.103155 -0.000666148 -0.239023 0.103155 -0.000666148 -0.238673 0.103965 9.72949e-05 -0.239023 0.103965 9.72949e-05 -0.239023 0.105048 0.000353563 -0.238673 0.105048 0.000353563 -0.238673 0.106114 3.39907e-05 -0.238673 0.106878 -0.000775794 -0.239023 0.100876 0.017984 -0.239023 0.101942 0.0176645 -0.241673 0.103334 0.0199194 -0.239023 0.102706 0.0168547 -0.238673 0.0989835 0.0169643 -0.238673 0.0997933 0.0177278 -0.239023 0.0989835 0.0169643 -0.239023 0.0997933 0.0177278 -0.238673 0.101942 0.0176645 -0.238673 0.102706 0.0168547 -0.241673 0.0662326 0.0343612 -0.239023 0.0721598 0.0360494 -0.241673 0.0735518 0.0383043 -0.239023 0.0731796 0.0341565 -0.239023 0.0688814 0.0342832 -0.239023 0.069201 0.0353492 -0.238673 0.0700108 0.0361127 -0.239023 0.0700108 0.0361127 -0.239023 0.0710938 0.0363689 -0.238673 0.0729233 0.0352396 -0.238673 0.0731796 0.0341565 -0.239023 0.0729233 0.0352396 -0.239023 0.0534633 0.0321971 -0.241673 0.0511235 0.0342738 -0.239023 0.0545294 0.0318775 -0.239023 0.0552928 0.0310678 -0.241673 0.0559214 0.0341325 -0.239023 0.0512509 0.0301113 -0.238673 0.0523803 0.0319408 -0.239023 0.0515705 0.0311774 -0.239023 0.0523803 0.0319408 -0.241673 0.0354196 0.0177612 -0.239023 0.038927 0.0193396 -0.239023 0.0407574 0.019701 -0.239023 0.0416069 0.0192607 -0.238673 0.0380684 0.0176832 -0.238673 0.0383087 0.0186094 -0.239023 0.0383087 0.0186094 -0.238673 0.038927 0.0193396 -0.238673 0.039801 0.0197292 -0.239023 0.039801 0.0197292 -0.238673 0.0407574 0.019701 -0.238673 0.0421812 0.0184953 -0.239023 0.0421812 0.0184953 -0.240173 0.0246392 -0.00840684 -0.239373 0.0344063 -0.0230606 -0.239373 0.0311447 -0.0167108 -0.239373 0.0307406 -0.0156882 -0.239373 0.0285836 -0.00774233 -0.240173 0.0365294 -0.0323201 -0.240173 0.0310165 -0.025184 -0.239373 0.0353091 -0.0244408 -0.239373 0.0558508 -0.0403099 -0.239373 0.0527917 -0.0390778 -0.240173 0.0511528 -0.0427267 -0.240173 0.0433287 -0.0382435 -0.239373 0.0687633 -0.0427468 -0.240173 0.0686455 -0.046745 -0.239373 0.0769773 -0.0421814 -0.239373 0.0899199 -0.0377406 -0.239373 0.0922956 -0.0363586 -0.239373 0.0971723 -0.032791 -0.240173 0.101555 -0.0342355 -0.239373 0.103237 -0.0264417 -0.240173 0.107479 -0.0274363 -0.239373 0.10422 -0.025117 -0.240173 0.111962 -0.0196121 -0.239373 0.110934 -0.0101681 -0.240173 0.0667286 0.051132 -0.240173 0.0536555 0.0422334 -0.240173 0.0398984 0.0416366 -0.240173 0.0384449 0.0327056 -0.240173 0.0326196 0.0353835 -0.240173 0.0266138 0.0278994 -0.240173 0.0220855 0.0194391 -0.240173 0.0191889 0.0102909 -0.240173 0.0180225 0.000766108 -0.240173 0.0270016 -0.0171095 -0.240173 0.0209793 -0.0181137 -0.240173 0.0305567 -0.0346505 -0.240173 0.0597013 -0.0455973 -0.240173 0.0776418 -0.0461258 -0.240173 0.0827516 -0.0511772 -0.240173 0.0863444 -0.0437633 -0.240173 0.094419 -0.0397485 -0.240173 0.10738 -0.0369134 -0.240173 0.113386 -0.0294293 -0.240173 0.114832 -0.0110636 -0.240173 0.11598 -0.00211939 -0.240173 0.115361 0.0068769 -0.240173 0.121374 0.00728085 -0.240173 0.112998 0.0155795 -0.240173 0.109443 0.0331205 -0.240173 0.0856969 0.0488093 -0.240173 0.0713544 0.0452151 -0.238073 0.0191889 0.0102909 -0.238073 0.0326196 0.0353835 -0.238073 0.0398984 0.0416366 -0.238073 0.0482022 0.0464458 -0.240173 0.0482022 0.0464458 -0.240173 0.0572483 0.0496473 -0.238073 0.0572483 0.0496473 -0.240173 0.0763204 0.0508495 -0.238073 0.0856969 0.0488093 -0.240173 0.0945389 0.0450809 -0.240173 0.102545 0.0397913 -0.240173 0.114998 0.0252959 -0.240173 0.119021 0.0165838 -0.237873 0.119209 0.0166505 -0.237873 0.115171 0.0253961 -0.237873 0.109974 0.0335767 -0.237873 0.102983 0.0403372 -0.237873 0.0948692 0.045698 -0.237873 0.0946333 0.0452572 -0.237873 0.0763447 0.051048 -0.237873 0.0666846 0.0518306 -0.237873 0.0481183 0.0466274 -0.237873 0.0479087 0.0470813 -0.237873 0.0397826 0.0417997 -0.237873 0.0394932 0.0422074 -0.237873 0.026447 0.0280096 -0.237873 0.0219012 0.0195168 -0.237873 0.0189934 0.0103334 -0.237873 0.0184286 -0.00884174 -0.237873 0.0179346 -0.0089191 -0.237873 0.0248288 -0.0269261 -0.237873 0.0203194 -0.0183472 -0.237873 0.030405 -0.0347808 -0.237873 0.0243961 -0.0271766 -0.237873 0.0370166 -0.0418671 -0.237873 0.0373295 -0.0414772 -0.237873 0.0453667 -0.0467872 -0.237873 0.0451307 -0.047228 -0.237873 0.0542426 -0.0505299 -0.237873 0.0540917 -0.0510066 -0.237873 0.0733153 -0.0533606 -0.237873 0.0829233 -0.0518558 -0.237873 0.100217 -0.0433296 -0.237873 0.107524 -0.0370525 -0.237873 0.113553 -0.0295396 -0.237873 0.11397 -0.0298152 -0.237873 0.118559 -0.0212411 -0.237873 0.122177 -0.00230194 -0.238073 0.0171229 0.000792607 -0.238073 0.029874 -0.035237 -0.238073 0.0368914 -0.0420231 -0.239973 0.0540313 -0.0511972 -0.238073 0.0540313 -0.0511972 -0.239973 0.0635701 -0.0532728 -0.239973 0.0733279 -0.0535602 -0.238073 0.0829723 -0.0520497 -0.239973 0.092175 -0.0487929 -0.239973 0.108027 -0.0375391 -0.239973 0.118744 -0.0213188 -0.238073 0.114137 -0.0299254 -0.238073 0.118744 -0.0213188 -0.238073 0.12169 -0.0120122 -0.239973 0.0161597 0.01095 -0.239973 0.0171229 0.000792607 -0.239973 0.017737 -0.00895005 -0.239973 0.0149238 0.000857384 -0.239973 0.0201309 -0.018414 -0.239973 0.024223 -0.0272769 -0.239973 0.029874 -0.035237 -0.239973 0.0368914 -0.0420231 -0.239973 0.0450363 -0.0474043 -0.239973 0.0633027 -0.0554564 -0.239973 0.0829723 -0.0520497 -0.239973 0.0835118 -0.0541826 -0.239973 0.0930972 -0.0507902 -0.239973 0.100623 -0.0439004 -0.239973 0.114137 -0.0299254 -0.239973 0.120771 -0.0221736 -0.239973 0.12169 -0.0120122 -0.239973 0.122877 -0.00232255 -0.239973 0.124436 0.00776051 -0.239973 0.121943 0.017618 -0.239973 0.115777 0.0257469 -0.239973 0.117681 0.0268495 -0.239973 0.111795 0.0351406 -0.239973 0.104485 0.042209 -0.239973 0.103108 0.0404932 -0.239973 0.0960018 0.047814 -0.239973 0.0949636 0.0458744 -0.239973 0.0859686 0.0496673 -0.239973 0.0866327 0.0517647 -0.239973 0.066672 0.0520302 -0.239973 0.0570276 0.0505198 -0.239973 0.0478249 0.0472629 -0.239973 0.0393774 0.0423705 -0.239973 0.0319727 0.0360091 -0.239973 0.0303912 0.0375385 -0.239973 0.0258629 0.0283955 -0.239973 0.0212562 0.0197888 -0.239973 0.0192291 0.0206436 -0.239973 0.0240274 0.0296082 -0.239973 0.0381039 0.0441644 -0.238073 0.0381039 0.0441644 -0.239973 0.0469027 0.0492603 -0.238073 0.0564881 0.0526526 -0.239973 0.0564881 0.0526526 -0.238073 0.0665336 0.0542259 -0.239973 0.0665336 0.0542259 -0.238073 0.0766972 0.0539265 -0.239973 0.0766972 0.0539265 -0.238073 0.0960018 0.047814 -0.238073 0.125076 -0.00238733 -0.237873 0.066521 0.0544255 -0.237873 0.066455 0.0554734 -0.237873 0.0561816 0.0538645 -0.237873 0.0302474 0.0376775 -0.237873 0.0147239 0.000863273 -0.237873 0.0136744 0.000894189 -0.237873 0.0143286 -0.00948386 -0.237873 0.0153659 -0.00932139 -0.237873 0.0221462 -0.0284797 -0.237873 0.0212376 -0.0290059 -0.237873 0.0347322 -0.0447139 -0.237873 0.0434083 -0.050446 -0.237873 0.0631508 -0.0566972 -0.237873 0.0735449 -0.0570034 -0.237873 0.0835609 -0.0543765 -0.237873 0.0838184 -0.0553944 -0.237873 0.10262 -0.0467136 -0.237873 0.116139 -0.0312484 -0.237873 0.120955 -0.0222513 -0.237873 0.117015 -0.0318272 -0.237873 0.121923 -0.0226592 -0.237873 0.124036 -0.0125224 -0.237873 0.125062 -0.0127457 -0.237873 0.124634 0.00779145 -0.237873 0.123121 0.0180351 -0.237873 0.112743 0.0359552 -0.237873 0.0960961 0.0479903 -0.237873 0.0965916 0.0489161 -0.237873 0.08701 0.0529564 -0.237873 0.0767215 0.054125 -0.237873 0.0768491 0.0551672 -0.237873 0.0149383 0.0112157 -0.237873 0.0180773 0.0211293 -0.237873 0.0229844 0.0302973 -0.237873 0.0294926 0.0384075 -0.237473 0.0373803 0.0451837 -0.237873 0.0373803 0.0451837 -0.237873 0.0463787 0.0503952 -0.237473 0.066455 0.0554734 -0.237873 0.105268 0.0431839 -0.237873 0.118762 0.027476 -0.237873 0.125671 0.00795392 -0.237473 0.126326 -0.00242413 -0.237873 0.126326 -0.00242413 -0.237273 0.031925 -0.0435185 -0.237273 0.034607 -0.0448699 -0.237273 0.0399275 -0.0494806 -0.237273 0.0433139 -0.0506223 -0.237273 0.0631265 -0.0568957 -0.237273 0.0683143 -0.0579901 -0.237273 0.078277 -0.0574135 -0.237273 0.0838674 -0.0555883 -0.237273 0.0971527 -0.0511663 -0.237273 0.105492 -0.0456855 -0.237273 0.117182 -0.0319375 -0.237273 0.118716 -0.0308374 -0.237273 0.126525 -0.00243002 -0.237273 0.127225 -0.00245063 -0.237273 0.125869 0.00798486 -0.237273 0.12331 0.0181018 -0.237273 0.124351 0.0172232 -0.237273 0.118935 0.0275762 -0.237273 0.120401 0.0263878 -0.237273 0.114921 0.0347274 -0.237273 0.105393 0.0433399 -0.237273 0.100072 0.0479507 -0.237273 0.0911561 0.0524326 -0.237273 0.0870704 0.053147 -0.237273 0.0768734 0.0553658 -0.237273 0.0716856 0.0564602 -0.237273 0.061723 0.0558835 -0.237273 0.0664424 0.055673 -0.237273 0.0561325 0.0540584 -0.237273 0.0428472 0.0496363 -0.237273 0.0462949 0.0505767 -0.237273 0.0372645 0.0453468 -0.237273 0.0345076 0.0441556 -0.237273 0.0272464 0.03731 -0.237273 0.0212843 0.0293074 -0.237273 0.017893 0.021207 -0.237273 0.0147429 0.0112583 -0.237273 0.0168024 0.0203912 -0.237273 0.014131 -0.0095148 -0.237273 0.0156494 -0.0187531 -0.238273 0.0154595 -0.018816 -0.237473 0.0154595 -0.018816 -0.238273 0.0194226 -0.0280126 -0.237473 0.0194226 -0.0280126 -0.237473 0.0249225 -0.0363813 -0.238273 0.0249225 -0.0363813 -0.237473 0.0398225 -0.0496508 -0.237473 0.0487699 -0.0541484 -0.237473 0.0683084 -0.0581901 -0.238273 0.0783059 -0.0576114 -0.238273 0.088051 -0.0553054 -0.237473 0.088051 -0.0553054 -0.237473 0.0972476 -0.0513423 -0.237473 0.105616 -0.0458425 -0.238273 0.112903 -0.0389729 -0.237473 0.112903 -0.0389729 -0.237473 0.118886 -0.0309424 -0.238273 0.123383 -0.021995 -0.237473 0.126259 -0.0124026 -0.238273 0.100177 0.0481208 -0.238273 0.09123 0.0526184 -0.238273 0.0716915 0.0566601 -0.238273 0.061694 0.0560814 -0.238273 0.0615206 0.0572688 -0.238273 0.051949 0.0537755 -0.238273 0.0515719 0.0549147 -0.238273 0.0427523 0.0498124 -0.238273 0.0336397 0.0452541 -0.238273 0.020093 0.0300428 -0.238273 0.0113754 0.000961909 -0.238273 0.0125749 0.000926577 -0.238273 0.0119662 -0.00924438 -0.238273 0.0131535 -0.00907088 -0.238273 0.0143203 -0.019193 -0.238273 0.0183662 -0.0285817 -0.238273 0.031792 -0.0436678 -0.238273 0.0239809 -0.0371253 -0.238273 0.0398225 -0.0496508 -0.238273 0.0391922 -0.0506719 -0.238273 0.0487699 -0.0541484 -0.238273 0.0583623 -0.0570239 -0.238273 0.0683084 -0.0581901 -0.238273 0.0581193 -0.058199 -0.238273 0.088428 -0.0564447 -0.238273 0.0978167 -0.0523988 -0.238273 0.0972476 -0.0513423 -0.238273 0.105616 -0.0458425 -0.238273 0.118886 -0.0309424 -0.238273 0.119907 -0.0315728 -0.238273 0.127434 -0.0126457 -0.238273 0.126259 -0.0124026 -0.238273 0.127425 -0.00245652 -0.238273 0.12454 0.017286 -0.238273 0.120577 0.0264827 -0.238273 0.116019 0.0355953 -0.238273 0.115077 0.0348514 -0.238273 0.108208 0.0421379 -0.238973 0.0117683 -0.00927329 -0.238973 0.0181901 -0.0286766 -0.238473 0.0141304 -0.0192559 -0.238473 0.0308609 -0.0447133 -0.238973 0.0308609 -0.0447133 -0.238473 0.0390871 -0.0508421 -0.238473 0.0482525 -0.0554493 -0.238973 0.0580788 -0.0583949 -0.238473 0.0580788 -0.0583949 -0.238973 0.0682672 -0.0595895 -0.238473 0.0682672 -0.0595895 -0.238973 0.0884908 -0.0566345 -0.238973 0.106484 -0.0469409 -0.238973 0.113948 -0.039904 -0.238473 0.120077 -0.0316778 -0.238973 0.124684 -0.0225124 -0.238473 0.124684 -0.0225124 -0.238973 0.12763 -0.0126862 -0.238473 0.12763 -0.0126862 -0.238973 0.128824 -0.00249774 -0.238973 0.120077 -0.0316778 -0.241173 0.111671 -0.0378756 -0.238973 0.0979116 -0.0525749 -0.241173 0.0875325 -0.053739 -0.238973 0.0785083 -0.0589967 -0.241173 0.068357 -0.0565408 -0.241173 0.0586966 -0.0554081 -0.238973 0.0482525 -0.0554493 -0.238973 0.0390871 -0.0508421 -0.238973 0.023824 -0.0372492 -0.238973 0.0141304 -0.0192559 -0.241173 0.0208752 -0.02723 -0.238973 0.0111755 0.000967798 -0.241173 0.0147862 -0.00883233 -0.241173 0.119125 0.0257001 -0.241173 0.111321 0.00675392 -0.241173 0.125776 -0.00240794 -0.241173 0.107849 -0.0189702 -0.241173 0.0283293 0.0363456 -0.241173 0.0428277 0.0312611 -0.241173 0.0435349 0.0483598 -0.241173 0.058203 0.0395442 -0.241173 0.0524674 0.0522091 -0.241173 0.0619326 0.0544488 -0.241173 0.0716429 0.0550108 -0.241173 0.0920618 0.034974 -0.241173 0.0990103 0.0296061 -0.241173 0.0311447 -0.0167108 -0.241173 0.0170259 -0.0182975 -0.241173 0.0286785 -0.00828386 -0.241173 0.0280182 0.00047167 -0.241173 0.0142242 0.000877994 -0.241173 0.0321507 0.0174403 -0.241173 0.0153568 0.0105384 -0.241173 0.0558508 -0.0403099 -0.241173 0.0479381 -0.0365039 -0.241173 0.0493796 -0.0526152 -0.241173 0.0406892 -0.0482468 -0.241173 0.0328894 -0.0424356 -0.241173 0.0262171 -0.0353584 -0.241173 0.124643 -0.0120683 -0.241173 0.12185 -0.0213853 -0.241173 0.117482 -0.0300757 -0.241173 0.103237 -0.0264417 -0.241173 0.0971723 -0.032791 -0.241173 0.104593 -0.0445478 -0.241173 0.096465 -0.0498897 -0.241173 0.0817969 -0.0410742 -0.241173 0.0780673 -0.0559787 -0.241373 0.0286785 -0.00828386 -0.241373 0.0311447 -0.0167108 -0.241173 0.0353091 -0.0244408 -0.241373 0.0409897 -0.031136 -0.241173 0.0409897 -0.031136 -0.241373 0.0558508 -0.0403099 -0.241173 0.0643818 -0.0423875 -0.241373 0.0731584 -0.042646 -0.241173 0.0731584 -0.042646 -0.241373 0.0817969 -0.0410742 -0.241373 0.0899199 -0.0377406 -0.241173 0.0899199 -0.0377406 -0.241373 0.0971723 -0.032791 -0.241173 0.110807 -0.0107031 -0.241173 0.111982 -0.00200161 -0.238973 0.0286785 -0.00828386 -0.239373 0.0286785 -0.00828386 -0.238973 0.0479381 -0.0365039 -0.239373 0.0394399 -0.0295761 -0.239373 0.0409897 -0.031136 -0.239373 0.0605968 -0.0416988 -0.238973 0.0558508 -0.0403099 -0.239373 0.0456479 -0.0349845 -0.239373 0.0479381 -0.0365039 -0.239373 0.0643818 -0.0423875 -0.239373 0.0731584 -0.042646 -0.238973 0.0817969 -0.0410742 -0.239373 0.0817969 -0.0410742 -0.239373 0.0849232 -0.0400243 -0.238973 0.0899199 -0.0377406 -0.239373 0.0988111 -0.031325 -0.239373 0.107849 -0.0189702 -0.239373 0.111982 -0.00200161 -0.238973 0.111982 -0.00200161 -0.238973 0.110807 -0.0107031 -0.239373 0.110807 -0.0107031 -0.239373 0.108313 -0.0179732 -0.238673 0.0933451 -0.0187998 -0.238673 0.0970967 -0.0124275 -0.238673 0.0600618 -0.0285406 -0.238673 0.0403163 -0.0155354 -0.238673 0.0397386 -0.0201067 -0.238673 0.0399435 -0.02967 -0.238673 0.0469826 0.0285251 -0.238673 0.0402273 -0.00351888 -0.238673 0.040441 0.00373664 -0.238673 0.0374659 0.0131086 -0.238673 0.0404222 0.00916888 -0.238673 0.0343991 0.00592402 -0.238673 0.0341031 0.0124446 -0.238673 0.0407516 0.0142821 -0.238673 0.0390881 0.0157904 -0.238673 0.0383247 0.0166002 -0.238673 0.032421 0.0173103 -0.238673 0.0370003 0.0247284 -0.238673 0.0409296 0.0203245 -0.238673 0.0439158 0.0213406 -0.238673 0.0420424 0.024818 -0.238673 0.0410485 0.0292468 -0.238673 0.0436199 0.0278611 -0.238673 0.0411287 0.0293239 -0.238673 0.041697 0.0298591 -0.238673 0.0464046 0.0296216 -0.238673 0.0464923 0.0325971 -0.238673 0.0502223 0.0359465 -0.238673 0.0644933 0.0363089 -0.238673 0.0598658 0.0299333 -0.238673 0.0584632 0.0314211 -0.238673 0.0567883 0.0322938 -0.238673 0.0569303 0.0388339 -0.238673 0.0584338 0.0351124 -0.238673 0.0582873 0.0392563 -0.238673 0.0611754 0.0371697 -0.238673 0.0691377 0.0332001 -0.238673 0.0688814 0.0342832 -0.238673 0.069201 0.0353492 -0.238673 0.0761018 0.0328774 -0.238673 0.076689 0.0348359 -0.238673 0.0781767 0.0362385 -0.238673 0.0721598 0.0360494 -0.238673 0.0710938 0.0363689 -0.238673 0.100074 0.028122 -0.238673 0.108071 0.0162503 -0.238673 0.10702 -0.0160409 -0.238673 0.108756 -0.0161551 -0.238673 0.107579 -0.0188402 -0.238673 0.0983212 -0.0313721 -0.238673 0.0936124 -0.0305725 -0.238673 0.0486841 -0.0366052 -0.238673 0.0497223 -0.0315672 -0.238673 0.0515518 -0.0326965 -0.238673 0.0526348 -0.0324403 -0.238673 0.0446569 -0.02971 -0.238673 0.0480957 -0.0362487 -0.238673 0.0411721 -0.0226994 -0.238673 0.0399166 -0.0140643 -0.238673 0.0370379 -0.0173016 -0.238673 0.0378139 -0.0123018 -0.238673 0.0304052 -0.0138471 -0.238673 0.0381672 -0.0154721 -0.238673 0.0373574 -0.0162356 -0.238673 0.0338656 -0.0121855 -0.238673 0.0289736 -0.00823015 -0.238673 0.0324337 -0.00700641 -0.238673 0.0335697 -0.00566488 -0.238673 0.0384931 -0.00580991 -0.238673 0.0395482 -0.00721598 -0.238673 0.0393017 -0.0108992 -0.238673 0.0678401 -0.0375793 -0.238673 0.0689061 -0.0378989 -0.238673 0.0654983 -0.0303239 -0.238673 0.0731358 -0.0423469 -0.238673 0.0817127 -0.0407862 -0.238673 0.0711185 -0.0358131 -0.238673 0.0756885 -0.031665 -0.238673 0.0708622 -0.0347301 -0.238673 0.0790512 -0.031001 -0.238673 0.0700988 -0.0339203 -0.238673 0.0860225 -0.0309285 -0.238673 0.0806119 -0.0318101 -0.238673 0.081667 -0.0332161 -0.238673 0.0857935 -0.0387001 -0.238673 0.0820076 -0.0349407 -0.238673 0.0979576 -0.026348 -0.238673 0.0982299 -0.0307085 -0.238673 0.0881265 -0.0240389 -0.238673 0.0921358 -0.0227542 -0.238673 0.0938737 -0.0217014 -0.238673 0.0975161 -0.0280496 -0.238673 0.0963801 -0.0293911 -0.238673 0.0947745 -0.0301068 -0.238673 0.0914566 -0.0292461 -0.238673 0.102534 -0.00535423 -0.238673 0.103642 -0.00686684 -0.238673 0.110516 -0.0106321 -0.238673 0.107474 -0.0109314 -0.238673 0.0991458 -0.00532244 -0.238673 0.0999182 -0.0124234 -0.238673 0.0986692 -0.015795 -0.238673 0.104291 -0.0146903 -0.238673 0.102224 -0.0158997 -0.238673 0.106612 0.0103087 -0.238673 0.107855 0.0123054 -0.238673 0.107667 0.00890266 -0.238673 0.103059 0.0124467 -0.238673 0.095343 0.0281801 -0.238673 0.100056 0.02814 -0.238673 0.095326 0.027601 -0.238673 0.099415 0.023128 -0.238673 0.0988278 0.0211695 -0.238673 0.0973401 0.0197669 -0.238673 0.0894651 0.0214017 -0.238673 0.0933918 0.0198832 -0.238673 0.0919892 0.0213709 -0.238673 0.0915184 0.0233606 -0.238673 0.0877531 0.0278241 -0.238673 0.0835569 0.0309432 -0.238673 0.0808153 0.0288859 -0.238673 0.0774975 0.0297467 -0.238673 0.0764424 0.0311527 -0.238673 0.0655484 0.0349028 -0.238673 0.0673337 0.0319832 -0.238673 0.067246 0.0290077 -0.238673 0.0493518 0.0226269 -0.238673 0.0490993 0.0200536 -0.238673 0.0490515 -0.0215354 -0.238673 0.046904 -0.0279337 -0.238673 0.044674 -0.0291309 -0.238673 0.0435413 -0.0285977 -0.238673 0.0419806 -0.0277887 -0.238673 0.0393322 -0.0290205 -0.238673 0.040585 -0.024658 -0.238673 0.0638981 -0.0344073 -0.238673 0.0618232 -0.0377685 -0.238673 0.0598335 -0.0382393 -0.238673 0.0559518 -0.0400274 -0.238673 0.0578749 -0.0376522 -0.238673 0.054724 -0.0377849 -0.238673 0.0546221 -0.0395259 -0.238673 0.0509725 -0.0378708 -0.238673 0.0652694 -0.0380956 -0.238673 0.0564723 -0.0361644 -0.238673 0.0560015 -0.0341747 -0.238673 0.056443 -0.0324731 -0.238673 0.0591846 -0.0304158 -0.238673 0.0410797 -0.0163452 -0.238673 0.0479101 -0.0203172 -0.238673 0.0449353 -0.0202598 -0.238673 0.0355569 -0.0242717 -0.238673 0.0497856 -0.0294181 -0.238673 0.0484815 -0.0248906 -0.238673 0.0480401 -0.0265922 -0.238673 0.0516784 -0.0283984 -0.238673 0.0987627 -0.0172571 -0.238673 0.100912 -0.0173204 -0.238673 0.101691 -0.0201393 -0.238673 0.101073 -0.0208695 -0.238673 0.102046 -0.0219421 -0.238673 0.100199 -0.0212591 -0.238673 0.0988712 -0.0308539 -0.238673 0.0984912 -0.0218374 -0.238673 0.098393 -0.0207906 -0.238673 0.0976334 -0.0190865 -0.238673 0.0995042 0.0125514 -0.238673 0.0977362 0.0092824 -0.238673 0.103237 0.0184891 -0.238673 0.0989202 0.0148153 -0.238673 0.0943662 0.0158645 -0.238673 0.0986639 0.0158983 -0.238673 0.0950646 0.0187299 -0.238673 0.0999435 0.027465 -0.238673 0.103504 0.0240624 -0.238673 0.0996822 0.0185938 -0.238673 0.100876 0.017984 -0.238673 0.102962 0.0157717 -0.238673 0.103294 0.0111695 -0.238673 0.105051 0.0111178 -0.238673 0.102642 0.0147056 -0.238673 0.101833 0.0139422 -0.238673 0.10075 0.0136859 -0.238673 0.0567006 0.0293184 -0.238673 0.0552928 0.0310678 -0.238673 0.0545294 0.0318775 -0.238673 0.0534633 0.0321971 -0.238673 0.0507459 0.0324718 -0.238673 0.0552295 0.0289187 -0.238673 0.0506412 0.0289173 -0.238673 0.0522707 0.0282185 -0.238673 0.0515072 0.0290283 -0.238673 0.0506582 0.0294963 -0.238673 0.0512509 0.0301113 -0.238673 0.0515705 0.0311774 -0.238673 0.061714 0.0275474 -0.238673 0.0566836 0.0287393 -0.238673 0.0544197 0.0281552 -0.238673 0.0461262 0.0201714 -0.238673 0.0478641 0.0212243 -0.238673 0.0416069 0.0192607 -0.238673 0.0527444 -0.028718 -0.238673 0.05497 -0.0294342 -0.238673 0.0654599 -0.0299135 -0.238673 0.0549529 -0.0300133 -0.238673 0.0746721 -0.0298926 -0.238673 0.0817691 -0.0278156 -0.238673 0.090061 -0.0261154 -0.238673 0.101985 0.00393318 -0.238673 0.101653 -0.00733766 -0.238673 0.0555491 0.0299847 -0.238673 0.0763785 0.0280372 -0.238673 0.0423665 0.0175566 -0.238673 0.042047 0.0164906 -0.238673 0.0412231 -0.00725684 -0.238673 0.0437417 -0.0142094 -0.238673 0.0489105 -0.0298353 -0.238673 0.0489276 -0.0292562 -0.238673 0.0969782 -0.0325622 -0.238673 0.0935953 -0.0311516 -0.238673 0.0860395 -0.0303494 -0.238673 0.106814 -0.00292486 -0.238673 0.107331 -0.00549551 -0.238673 0.104921 -0.00394457 -0.238673 0.108008 0.00717805 -0.238673 0.107544 0.00176001 -0.238673 0.102748 0.00190129 -0.238673 0.103092 -0.00281522 -0.238673 0.0463876 0.0290426 -0.238673 0.0839984 0.0326448 -0.238673 0.0878578 0.0313786 -0.238673 0.0954307 0.0311555 -0.238673 0.0877702 0.0284032 -0.238673 0.0947015 0.0271195 -0.238973 0.111321 0.00675392 -0.239373 0.111416 0.00621239 -0.239373 0.109259 0.0141583 -0.238973 0.108855 0.0151808 -0.239373 0.105594 0.0215306 -0.239373 0.104691 0.0229108 -0.239373 0.0920618 0.034974 -0.238973 0.0920618 0.034974 -0.238973 0.0668415 0.0411161 -0.239373 0.0841492 0.0387799 -0.238973 0.0841492 0.0387799 -0.238973 0.0756181 0.0408576 -0.239373 0.0794031 0.0401689 -0.239373 0.0756181 0.0408576 -0.239373 0.0712366 0.0412168 -0.238973 0.058203 0.0395442 -0.239373 0.05008 0.0362106 -0.238973 0.0428277 0.0312611 -0.239373 0.0411888 0.0297951 -0.239373 0.0357804 0.0235871 -0.239373 0.0316871 0.0164433 -0.239373 0.0280182 0.00047167 -0.239373 0.0290661 0.00863815 -0.238973 0.0291927 0.00917315 -0.241373 0.111321 0.00675392 -0.241173 0.108855 0.0151808 -0.241173 0.104691 0.0229108 -0.241173 0.0841492 0.0387799 -0.241173 0.0756181 0.0408576 -0.241173 0.0668415 0.0411161 -0.241173 0.05008 0.0362106 -0.241373 0.0428277 0.0312611 -0.241173 0.0367629 0.0249118 -0.241173 0.0291927 0.00917315 -0.238973 0.01237 0.0111562 -0.238973 0.0153157 0.0209825 -0.241173 0.0181498 0.0198554 -0.241173 0.0225182 0.0285458 -0.241173 0.0354065 0.0430179 -0.238973 0.0717327 0.0580595 -0.241173 0.0813033 0.0538782 -0.241173 0.0906203 0.0510852 -0.238973 0.100913 0.0493121 -0.241173 0.0993107 0.0467168 -0.238973 0.109139 0.0431834 -0.241173 0.107111 0.0409057 -0.241173 0.113783 0.0338284 -0.238973 0.116176 0.0357193 -0.238973 0.12587 0.0177259 -0.241173 0.122974 0.0167676 -0.238973 0.128232 0.00774335 -0.241173 0.125214 0.00730239 -0.238473 0.12587 0.0177259 -0.238973 0.12181 0.0271467 -0.238473 0.116176 0.0357193 -0.238473 0.109139 0.0431834 -0.238473 0.100913 0.0493121 -0.238973 0.0917474 0.0539193 -0.238973 0.0819212 0.0568649 -0.238473 0.0917474 0.0539193 -0.238473 0.0819212 0.0568649 -0.238473 0.0717327 0.0580595 -0.238973 0.0614916 0.0574667 -0.238473 0.0614916 0.0574667 -0.238973 0.0515091 0.0551046 -0.238973 0.0420883 0.0510449 -0.238973 0.0335157 0.045411 -0.238473 0.0335157 0.045411 -0.238973 0.0260516 0.0383741 -0.238473 0.0260516 0.0383741 -0.238973 0.0199228 0.0301479 -0.238473 0.0153157 0.0209825 -0.238473 0.01237 0.0111562 -0.238273 0.126846 0.00754094 -0.237473 0.126846 0.00754094 -0.237473 0.12454 0.017286 -0.237473 0.120577 0.0264827 -0.237473 0.108208 0.0421379 -0.237473 0.09123 0.0526184 -0.238273 0.0816376 0.055494 -0.237473 0.0716915 0.0566601 -0.237473 0.061694 0.0560814 -0.237473 0.051949 0.0537755 -0.238273 0.0343836 0.0443125 -0.237473 0.0343836 0.0443125 -0.238273 0.0270971 0.037443 -0.237473 0.0270971 0.037443 -0.238273 0.0211141 0.0294125 -0.237473 0.0211141 0.0294125 -0.238273 0.0166166 0.0204651 -0.238273 0.013741 0.0108726 -0.237473 0.013741 0.0108726 -0.237473 0.125062 -0.0127457 -0.237473 0.110507 -0.0399374 -0.237873 0.110507 -0.0399374 -0.237473 0.10262 -0.0467136 -0.237473 0.0838184 -0.0553944 -0.237873 0.0936212 -0.0519251 -0.237473 0.0735449 -0.0570034 -0.237473 0.0631508 -0.0566972 -0.237473 0.0529899 -0.0544863 -0.237873 0.0529899 -0.0544863 -0.237473 0.0272571 -0.0374851 -0.237873 0.0272571 -0.0374851 -0.237473 0.0168786 -0.019565 -0.237473 0.0143286 -0.00948386 -0.237873 0.0168786 -0.019565 -0.239973 0.125076 -0.00238733 -0.238073 0.12384 -0.0124799 -0.239973 0.12384 -0.0124799 -0.238073 0.109609 -0.0390684 -0.239973 0.115973 -0.0311382 -0.239973 0.109609 -0.0390684 -0.238073 0.101896 -0.0456943 -0.239973 0.101896 -0.0456943 -0.238073 0.0835118 -0.0541826 -0.239973 0.0734663 -0.0557558 -0.238073 0.0633027 -0.0554564 -0.238073 0.0533672 -0.0532946 -0.238073 0.0439982 -0.0493439 -0.239973 0.0533672 -0.0532946 -0.239973 0.0439982 -0.0493439 -0.238073 0.0355145 -0.043739 -0.239973 0.0355145 -0.043739 -0.239973 0.0282052 -0.0366706 -0.239973 0.0223192 -0.0283795 -0.238073 0.018057 -0.019148 -0.239973 0.018057 -0.019148 -0.239973 0.0155635 -0.00929045 -0.238073 0.0149238 0.000857384 -0.238073 0.122877 -0.00232255 -0.239973 0.122263 0.00742011 -0.239973 0.119869 0.016884 -0.238073 0.119869 0.016884 -0.238073 0.115777 0.0257469 -0.239973 0.110126 0.033707 -0.238073 0.0859686 0.0496673 -0.239973 0.0764298 0.0517428 -0.238073 0.0764298 0.0517428 -0.238073 0.066672 0.0520302 -0.238073 0.0258629 0.0283955 -0.238073 0.0212562 0.0197888 -0.239973 0.0183094 0.0104822 -0.238073 0.0183094 0.0104822 -0.240173 0.121977 -0.00229605 -0.240173 0.120811 -0.0118208 -0.240173 0.117914 -0.0209691 -0.240173 0.100102 -0.0431666 -0.240173 0.0917977 -0.0479757 -0.238073 0.0732713 -0.052662 -0.240173 0.0732713 -0.052662 -0.240173 0.0636795 -0.0523794 -0.240173 0.054303 -0.0503392 -0.238073 0.045461 -0.0466108 -0.240173 0.045461 -0.0466108 -0.240173 0.0374547 -0.0413212 -0.240173 0.0250018 -0.0268258 -0.238073 0.0186262 -0.00881079 -0.240173 0.0186262 -0.00881079 -0.238073 0.0180225 0.000766108 -0.239373 0.108855 0.0151808 -0.239373 0.111321 0.00675392 -0.239373 0.094352 0.0334546 -0.239373 0.0990103 0.0296061 -0.240173 0.10347 0.0307901 -0.239373 0.10056 0.0280462 -0.240173 0.108983 0.023654 -0.240173 0.0888471 0.0411967 -0.239373 0.0872082 0.0375479 -0.240173 0.0966713 0.0367136 -0.240173 0.0802986 0.0440674 -0.239373 0.0668415 0.0411161 -0.240173 0.0623581 0.0445958 -0.239373 0.0630226 0.0406514 -0.239373 0.058203 0.0395442 -0.239373 0.0550767 0.0384944 -0.240173 0.045581 0.0382185 -0.239373 0.0477044 0.0348287 -0.239373 0.0428277 0.0312611 -0.239373 0.0367629 0.0249118 -0.240173 0.0325214 0.0259063 -0.239373 0.0321507 0.0174403 -0.240173 0.0280382 0.0180822 -0.239373 0.0291927 0.00917315 -0.240173 0.0251676 0.00953368 -0.240173 0.0240199 0.000589445 -0.239023 0.0423665 0.0175566 -0.239023 0.042047 0.0164906 -0.238673 0.0412372 0.0157271 -0.238673 0.0401542 0.0154708 -0.239023 0.0401542 0.0154708 -0.239023 0.0380684 0.0176832 -0.241673 0.0450154 0.0174786 -0.239023 0.0412372 0.0157271 -0.241673 0.042494 0.0133941 -0.241673 0.0376961 0.0135355 -0.239023 0.0390881 0.0157904 -0.239023 0.0383247 0.0166002 -0.239023 0.0555491 0.0299847 -0.239023 0.0552295 0.0289187 -0.239023 0.0544197 0.0281552 -0.238673 0.0533367 0.027899 -0.239023 0.0533367 0.027899 -0.239023 0.0515072 0.0290283 -0.241673 0.0574845 0.0275267 -0.241673 0.0556766 0.0258223 -0.239023 0.0522707 0.0282185 -0.241673 0.0532587 0.0252501 -0.238673 0.07286 0.0330905 -0.239023 0.07286 0.0330905 -0.238673 0.0720502 0.0323271 -0.239023 0.0720502 0.0323271 -0.238673 0.0709672 0.0320708 -0.239023 0.0709672 0.0320708 -0.238673 0.0699011 0.0323904 -0.241673 0.0751149 0.0316985 -0.241673 0.0733071 0.0299941 -0.239023 0.0699011 0.0323904 -0.241673 0.0708892 0.0294219 -0.241673 0.0685091 0.0301354 -0.241673 0.0668047 0.0319433 -0.239023 0.0691377 0.0332001 -0.239023 0.102962 0.0157717 -0.239023 0.102642 0.0147056 -0.238673 0.0996836 0.0140055 -0.239023 0.0996836 0.0140055 -0.239023 0.101833 0.0139422 -0.241673 0.104897 0.0133136 -0.239023 0.10075 0.0136859 -0.239023 0.0989202 0.0148153 -0.239023 0.0986639 0.0158983 -0.238673 0.107134 -0.00185881 -0.238673 0.106004 -0.0036883 -0.238673 0.103855 -0.003625 -0.239023 0.103855 -0.003625 -0.238673 0.102836 -0.0017322 -0.239023 0.102836 -0.0017322 -0.239023 0.106814 -0.00292486 -0.239023 0.106004 -0.0036883 -0.241673 0.109069 -0.00431686 -0.241673 0.104843 -0.00659342 -0.239023 0.104921 -0.00394457 -0.239023 0.103092 -0.00281522 -0.238673 0.101932 -0.0192132 -0.239023 0.101932 -0.0192132 -0.239023 0.101691 -0.0201393 -0.239023 0.101073 -0.0208695 -0.238673 0.0992425 -0.021231 -0.238673 0.0978187 -0.0200253 -0.241673 0.10458 -0.0192912 -0.239023 0.100199 -0.0212591 -0.241673 0.102663 -0.0229891 -0.239023 0.0992425 -0.021231 -0.239023 0.098393 -0.0207906 -0.241673 0.0966805 -0.0228129 -0.239023 0.0978187 -0.0200253 -0.238673 0.0707989 -0.0368792 -0.239023 0.0707989 -0.0368792 -0.238673 0.0699891 -0.0376426 -0.239023 0.0699891 -0.0376426 -0.238673 0.0670766 -0.0367695 -0.238673 0.0668204 -0.0356865 -0.239023 0.0670766 -0.0367695 -0.239023 0.0668204 -0.0356865 -0.241673 0.0737673 -0.0358911 -0.239023 0.0689061 -0.0378989 -0.239023 0.0678401 -0.0375793 -0.241673 0.0664481 -0.0398342 -0.241673 0.0647436 -0.0380264 -0.241673 0.0641715 -0.0356085 -0.238673 0.0537641 -0.0306108 -0.239023 0.0537641 -0.0306108 -0.238673 0.0534446 -0.0316768 -0.239023 0.0526348 -0.0324403 -0.238673 0.0504857 -0.0323769 -0.239023 0.0534446 -0.0316768 -0.239023 0.0515518 -0.0326965 -0.239023 0.0504857 -0.0323769 -0.241673 0.0490937 -0.0346319 -0.239023 0.0497223 -0.0315672 -0.241673 0.0473893 -0.032824 -0.238673 0.0410164 -0.0184943 -0.238673 0.0402067 -0.0192577 -0.239023 0.0402067 -0.0192577 -0.238673 0.0391236 -0.019514 -0.239023 0.0391236 -0.019514 -0.238673 0.0380576 -0.0191944 -0.239023 0.0380576 -0.0191944 -0.238673 0.0372941 -0.0183846 -0.239023 0.0372941 -0.0183846 -0.241673 0.0439849 -0.0175062 -0.239023 0.0410164 -0.0184943 -0.241673 0.0432714 -0.0198863 -0.238873 0.0396649 0.00731538 -0.241473 0.0396649 0.00731538 -0.238873 0.0382525 0.00598379 -0.238873 0.0363635 0.00553681 -0.238873 0.0345041 0.00609421 -0.241473 0.0363635 0.00553681 -0.241473 0.0345041 0.00609421 -0.238873 0.0331725 0.00750662 -0.241473 0.0327256 0.0093956 -0.238873 0.049739 0.0245913 -0.241473 0.0482414 0.0217023 -0.238873 0.0482414 0.0217023 -0.238873 0.0477692 0.0214003 -0.238873 0.0467171 0.0210228 -0.238873 0.0450489 0.0210719 -0.238873 0.0440208 0.0215108 -0.238873 0.0435673 0.02184 -0.241473 0.0435673 0.02184 -0.238873 0.0426893 0.0229232 -0.241473 0.065689 0.0331841 -0.241473 0.0652699 0.0315687 -0.238873 0.0651316 0.0313247 -0.241473 0.0641914 0.0302951 -0.238873 0.0626671 0.0296155 -0.238873 0.0618302 0.0295461 -0.238873 0.0609989 0.0296647 -0.238873 0.0595172 0.0304327 -0.238873 0.0586392 0.0315159 -0.241473 0.0585156 0.0317676 -0.241473 0.0832411 0.0307912 -0.238873 0.0833794 0.0310352 -0.238873 0.0807766 0.0290821 -0.241473 0.0818287 0.0294597 -0.241473 0.0807766 0.0290821 -0.241473 0.0799397 0.0290127 -0.238873 0.0791084 0.0291312 -0.241473 0.0791084 0.0291312 -0.241473 0.0776267 0.0298993 -0.241473 0.0767487 0.0309825 -0.238873 0.0776267 0.0298993 -0.238873 0.0986576 0.0212745 -0.241473 0.0986576 0.0212745 -0.241473 0.0972452 0.0199429 -0.238873 0.0953562 0.019496 -0.241473 0.0953562 0.019496 -0.238873 0.0934969 0.0200534 -0.238873 0.0921653 0.0214658 -0.238873 0.0917183 0.0233548 -0.238873 0.105838 0.00399295 -0.241473 0.105838 0.00399295 -0.238873 0.10209 0.00410337 -0.241473 0.103949 0.00354598 -0.238873 0.100311 0.00740476 -0.238873 0.107274 -0.0109255 -0.241473 0.107274 -0.0109255 -0.238873 0.105777 -0.0138146 -0.241473 0.105305 -0.0141165 -0.241473 0.101556 -0.0140061 -0.238873 0.0973385 -0.0279575 -0.238873 0.09626 -0.0292311 -0.241473 0.0957878 -0.0295331 -0.238873 0.0957878 -0.0295331 -0.238873 0.0915859 -0.0290934 -0.241473 0.0920395 -0.0294227 -0.238873 0.0907079 -0.0280102 -0.238873 0.0905842 -0.0277586 -0.241473 0.0779489 -0.0385728 -0.241473 0.0771175 -0.0384543 -0.238873 0.0760895 -0.0380154 -0.241473 0.0760895 -0.0380154 -0.241473 0.0747579 -0.036603 -0.238873 0.0747579 -0.036603 -0.238873 0.0631408 -0.0362608 -0.238873 0.0617284 -0.0375924 -0.241473 0.0631408 -0.0362608 -0.241473 0.0617284 -0.0375924 -0.238873 0.0598394 -0.0380394 -0.238873 0.05798 -0.037482 -0.241473 0.0598394 -0.0380394 -0.238873 0.0566484 -0.0360696 -0.238873 0.0478625 -0.0265001 -0.241473 0.0482816 -0.0248847 -0.241473 0.0477242 -0.0267441 -0.238873 0.0463118 -0.0280757 -0.241473 0.0444228 -0.0285227 -0.238873 0.0452597 -0.0284532 -0.238873 0.0421099 -0.027636 -0.241473 0.0412319 -0.0265528 -0.241473 0.0407849 -0.0246639 -0.241473 0.0391315 -0.0107941 -0.241473 0.0358301 -0.0125727 -0.238873 0.0358301 -0.0125727 -0.238873 0.0326391 -0.0106029 -0.241473 0.0339707 -0.0120153 -0.241473 0.0326391 -0.0106029 -0.238873 0.0321921 -0.00871388 -0.238673 0.111026 0.00670021 -0.238673 0.104443 0.0227417 -0.238973 0.104691 0.0229108 -0.238673 0.108578 0.0150669 -0.238673 0.100592 0.0275723 -0.238973 0.0990103 0.0296061 -0.238673 0.0668641 0.040817 -0.238673 0.075578 0.0405603 -0.238673 0.0840481 0.0384975 -0.238673 0.0919042 0.0347187 -0.238673 0.098803 0.0293892 -0.238973 0.05008 0.0362106 -0.238673 0.0430217 0.0310323 -0.238973 0.0367629 0.0249118 -0.238673 0.0312439 0.0146251 -0.238973 0.0321507 0.0174403 -0.238673 0.0294842 0.00910216 -0.238973 0.0280182 0.00047167 -0.238673 0.028318 0.000462837 -0.241673 0.028318 0.000462837 -0.241673 0.0294842 0.00910216 -0.241373 0.0291927 0.00917315 -0.241373 0.0321507 0.0174403 -0.241673 0.0370003 0.0247284 -0.241373 0.0367629 0.0249118 -0.241673 0.0413029 0.0294901 -0.241673 0.0502223 0.0359465 -0.241373 0.05008 0.0362106 -0.241373 0.0990103 0.0296061 -0.241373 0.0920618 0.034974 -0.241673 0.0919042 0.0347187 -0.241373 0.0841492 0.0387799 -0.241373 0.0756181 0.0408576 -0.241673 0.075578 0.0405603 -0.241673 0.0668641 0.040817 -0.241373 0.0668415 0.0411161 -0.241673 0.0662545 0.0407665 -0.241373 0.058203 0.0395442 -0.241673 0.098803 0.0293892 -0.241373 0.104691 0.0229108 -0.241673 0.104443 0.0227417 -0.241673 0.110981 0.00694384 -0.241373 0.108855 0.0151808 -0.241673 0.108578 0.0150669 -0.241373 0.111982 -0.00200161 -0.241673 0.0765726 0.0308876 -0.241673 0.0779753 0.0293999 -0.241473 0.0780803 0.0295701 -0.241473 0.0837985 0.0326506 -0.241673 0.0839984 0.0326448 -0.241473 0.0823009 0.0297616 -0.241673 0.0819235 0.0292836 -0.241473 0.099215 0.0231339 -0.241673 0.0988278 0.0211695 -0.241673 0.0973401 0.0197669 -0.241473 0.0934969 0.0200534 -0.241673 0.0919892 0.0213709 -0.241473 0.0921653 0.0214658 -0.241473 0.10725 0.00532454 -0.241673 0.107421 0.00521948 -0.241673 0.103943 0.00334606 -0.241473 0.10209 0.00410337 -0.241473 0.100758 0.00551578 -0.241473 0.106717 -0.0127849 -0.241673 0.105399 -0.0142926 -0.241473 0.103416 -0.0145635 -0.241673 0.101451 -0.0141763 -0.241473 0.100225 -0.0125937 -0.241473 0.0997776 -0.0107047 -0.241473 0.0977576 -0.0263421 -0.241473 0.0972002 -0.0282015 -0.241473 0.0938989 -0.0299801 -0.241673 0.0958827 -0.0297091 -0.241673 0.093893 -0.03018 -0.241673 0.0905318 -0.0281051 -0.241473 0.0907079 -0.0280102 -0.241673 0.090061 -0.0261154 -0.241673 0.074111 -0.0347081 -0.241473 0.0743109 -0.034714 -0.241673 0.0744515 -0.0364328 -0.241473 0.0746342 -0.0363513 -0.241473 0.0756359 -0.0376862 -0.241673 0.0755066 -0.0378388 -0.241673 0.0770673 -0.0386479 -0.241473 0.0787857 -0.0385034 -0.241673 0.0788245 -0.0386996 -0.241473 0.0798378 -0.0381258 -0.241673 0.0804301 -0.0379838 -0.241673 0.0820076 -0.0349407 -0.241473 0.0813885 -0.0365503 -0.241473 0.0812503 -0.0367942 -0.241473 0.08031 -0.0378239 -0.241673 0.0618232 -0.0377685 -0.241473 0.05798 -0.037482 -0.241673 0.0578749 -0.0376522 -0.241473 0.0566484 -0.0360696 -0.241673 0.0564723 -0.0361644 -0.241673 0.0484815 -0.0248906 -0.241673 0.0478944 -0.0268491 -0.241473 0.0463118 -0.0280757 -0.241473 0.0425634 -0.0279653 -0.241673 0.0398888 -0.00894059 -0.241473 0.0377191 -0.0121257 -0.241673 0.032463 -0.0106977 -0.241473 0.0382525 0.00598379 -0.241673 0.0398351 0.00721032 -0.241673 0.0363576 0.0053369 -0.241673 0.0343991 0.00592402 -0.241473 0.0331725 0.00750662 -0.241473 0.0493199 0.0229759 -0.241673 0.0483614 0.0215423 -0.241473 0.0467171 0.0210228 -0.241673 0.0467558 0.0208266 -0.241473 0.0450489 0.0210719 -0.241673 0.0449987 0.0208783 -0.241473 0.0425656 0.0231749 -0.241673 0.0423829 0.0230934 -0.241473 0.0422423 0.0248121 -0.241673 0.0654475 0.0314766 -0.241473 0.0626671 0.0296155 -0.241673 0.0627058 0.0294193 -0.241473 0.0609989 0.0296647 -0.241473 0.0595172 0.0304327 -0.241673 0.0583329 0.0316862 -0.238873 0.0743109 -0.034714 -0.238673 0.074111 -0.0347081 -0.238673 0.0745818 -0.0366979 -0.238673 0.0759844 -0.0381856 -0.238673 0.077943 -0.0387727 -0.238873 0.0779489 -0.0385728 -0.238873 0.0798378 -0.0381258 -0.238673 0.0799327 -0.0383019 -0.238873 0.0812503 -0.0367942 -0.238673 0.0814204 -0.0368993 -0.238873 0.0977576 -0.0263421 -0.238873 0.0972002 -0.0282015 -0.238873 0.0947357 -0.0299106 -0.238873 0.0938989 -0.0299801 -0.238873 0.0930675 -0.0298615 -0.238873 0.0920395 -0.0294227 -0.238673 0.0930173 -0.0300551 -0.238673 0.0904015 -0.02784 -0.238873 0.106855 -0.012541 -0.238673 0.107033 -0.012633 -0.238873 0.103416 -0.0145635 -0.238873 0.106717 -0.0127849 -0.238873 0.105305 -0.0141165 -0.238673 0.105897 -0.0139745 -0.238873 0.104252 -0.0144941 -0.238873 0.102584 -0.014445 -0.238673 0.102534 -0.0146385 -0.238873 0.101556 -0.0140061 -0.238673 0.100973 -0.0138295 -0.238873 0.101103 -0.0136769 -0.238873 0.100101 -0.012342 -0.238673 0.0995777 -0.0106988 -0.238873 0.100225 -0.0125937 -0.238673 0.100111 0.00741065 -0.238873 0.100758 0.00551578 -0.238673 0.100582 0.00542093 -0.238873 0.103949 0.00354598 -0.238673 0.103943 0.00334606 -0.238673 0.105933 0.00381688 -0.238873 0.10725 0.00532454 -0.238673 0.107421 0.00521948 -0.238873 0.107808 0.00718394 -0.238673 0.0953504 0.0192961 -0.238873 0.0972452 0.0199429 -0.238873 0.0763017 0.0328715 -0.238873 0.076625 0.0312342 -0.238673 0.0790582 0.0289376 -0.238873 0.0823009 0.0297616 -0.238673 0.0824209 0.0296016 -0.238673 0.0658889 0.0331782 -0.238673 0.0638141 0.029817 -0.238673 0.0653018 0.0312196 -0.238873 0.0641914 0.0302951 -0.238873 0.0637192 0.0299931 -0.238673 0.0618243 0.0293462 -0.238673 0.0579924 0.0334108 -0.238873 0.0599708 0.0301035 -0.238873 0.0491816 0.0227319 -0.238873 0.0458802 0.0209534 -0.238673 0.0458743 0.0207534 -0.238673 0.0425132 0.0228283 -0.238673 0.0325256 0.00940149 -0.238673 0.0329965 0.00741177 -0.238673 0.0363576 0.0053369 -0.238673 0.0383474 0.00580772 -0.238673 0.0398351 0.00721032 -0.238873 0.0402223 0.00917477 -0.238673 0.032463 -0.0106977 -0.238873 0.0339707 -0.0120153 -0.238873 0.0377191 -0.0121257 -0.238673 0.0358242 -0.0127726 -0.238873 0.0391315 -0.0107941 -0.238873 0.0396889 -0.0089347 -0.238873 0.0477242 -0.0267441 -0.238873 0.046784 -0.0277737 -0.238673 0.0452984 -0.0286495 -0.238873 0.0444228 -0.0285227 -0.238873 0.0435915 -0.0284041 -0.238873 0.0425634 -0.0279653 -0.238873 0.0407849 -0.0246639 -0.238873 0.0411082 -0.0263012 -0.238673 0.0409255 -0.0263826 -0.238873 0.0412319 -0.0265528 -0.238873 0.0562014 -0.0341806 -0.238673 0.063311 -0.0363659 -0.238473 0.128232 0.00774335 -0.238273 0.128034 0.00771443 -0.238273 0.12568 0.0176631 -0.238473 0.12181 0.0271467 -0.238273 0.121634 0.0270518 -0.238273 0.109006 0.043034 -0.238273 0.100808 0.049142 -0.238273 0.0916735 0.0537335 -0.238273 0.0818807 0.0566691 -0.238273 0.0717268 0.0578596 -0.238473 0.0515091 0.0551046 -0.238273 0.0421832 0.0508688 -0.238473 0.0420883 0.0510449 -0.238273 0.0262009 0.038241 -0.238473 0.0199228 0.0301479 -0.238273 0.0155015 0.0209085 -0.238273 0.0125659 0.0111157 -0.238473 0.0111755 0.000967798 -0.237873 0.0178226 0.000771997 -0.238073 0.0209793 -0.0181137 -0.237873 0.0207908 -0.0181804 -0.238073 0.0250018 -0.0268258 -0.238073 0.0305567 -0.0346505 -0.238073 0.0374547 -0.0413212 -0.238073 0.054303 -0.0503392 -0.238073 0.0636795 -0.0523794 -0.237873 0.0636552 -0.0525779 -0.237873 0.0732839 -0.0528616 -0.238073 0.0827516 -0.0511772 -0.237873 0.0828007 -0.0513711 -0.238073 0.0917977 -0.0479757 -0.237873 0.0918816 -0.0481573 -0.238073 0.100102 -0.0431666 -0.238073 0.10738 -0.0369134 -0.238073 0.113386 -0.0294293 -0.238073 0.117914 -0.0209691 -0.237873 0.118099 -0.0210468 -0.238073 0.120811 -0.0118208 -0.238073 0.121977 -0.00229605 -0.237873 0.121006 -0.0118633 -0.238073 0.122263 0.00742011 -0.237873 0.122065 0.00738916 -0.237873 0.11968 0.0168173 -0.237873 0.115604 0.0256467 -0.238073 0.110126 0.033707 -0.238073 0.103108 0.0404932 -0.238073 0.0949636 0.0458744 -0.237873 0.0859082 0.0494766 -0.237873 0.0764055 0.0515443 -0.238073 0.0570276 0.0505198 -0.237873 0.0570766 0.0503259 -0.238073 0.0478249 0.0472629 -0.238073 0.0393774 0.0423705 -0.238073 0.0319727 0.0360091 -0.237873 0.0321164 0.0358701 -0.237873 0.0260298 0.0282852 -0.237873 0.0214405 0.0197111 -0.237873 0.0185049 0.0104397 -0.237273 0.126648 0.00751203 -0.237473 0.115077 0.0348514 -0.237273 0.108075 0.0419885 -0.237473 0.100177 0.0481208 -0.237273 0.0815971 0.0552981 -0.237473 0.0816376 0.055494 -0.237473 0.0427523 0.0498124 -0.237273 0.0520118 0.0535856 -0.237473 0.0166166 0.0204651 -0.237273 0.0139369 0.0108321 -0.237473 0.0125749 0.000926577 -0.237473 0.0136744 0.000894189 -0.237273 0.01669 -0.0196317 -0.237273 0.0210645 -0.0291061 -0.237473 0.0212376 -0.0290059 -0.237273 0.0271054 -0.0376155 -0.237473 0.0347322 -0.0447139 -0.237473 0.0434083 -0.050446 -0.237273 0.0529295 -0.054677 -0.237273 0.0735575 -0.057203 -0.237473 0.0936212 -0.0519251 -0.237273 0.093705 -0.0521067 -0.237273 0.102735 -0.0468767 -0.237273 0.110651 -0.0400764 -0.237473 0.117015 -0.0318272 -0.237473 0.121923 -0.0226592 -0.237273 0.122107 -0.0227369 -0.237273 0.125257 -0.0127882 -0.238073 0.0155635 -0.00929045 -0.237873 0.0178684 -0.0192147 -0.238073 0.0223192 -0.0283795 -0.238073 0.0282052 -0.0366706 -0.237873 0.0280535 -0.0368009 -0.237873 0.0353893 -0.043895 -0.237873 0.0439038 -0.0495203 -0.237873 0.0533069 -0.0534853 -0.238073 0.0734663 -0.0557558 -0.237873 0.0632784 -0.055655 -0.237873 0.0734789 -0.0559554 -0.238073 0.0930972 -0.0507902 -0.237873 0.0931811 -0.0509718 -0.237873 0.102012 -0.0458574 -0.237873 0.109752 -0.0392075 -0.238073 0.115973 -0.0311382 -0.238073 0.120771 -0.0221736 -0.237873 0.125276 -0.00239321 -0.241673 0.0982916 0.0117505 -0.241673 0.0995275 0.00727344 -0.241673 0.0470859 -0.0217599 -0.241673 0.110486 -0.0107546 -0.241673 0.105921 -0.0187341 -0.241673 0.0858236 -0.037681 -0.241673 0.0411969 -0.0309191 -0.241673 0.111026 0.00670021 -0.241673 0.106916 0.0150586 -0.241673 0.107537 0.00916777 -0.241673 0.0752563 0.0364964 -0.241673 0.0687539 0.0384456 -0.241673 0.0711718 0.0390178 -0.241673 0.0834113 0.0306862 -0.241673 0.0940289 0.0285689 -0.241673 0.0840481 0.0384975 -0.241673 0.0836579 0.0343694 -0.241673 0.0792849 0.0366362 -0.241673 0.0765433 0.0345789 -0.241673 0.0758284 0.0340785 -0.241673 0.0658889 0.0331782 -0.241673 0.0659319 0.0293966 -0.241673 0.0643114 0.0301351 -0.241673 0.066946 0.0367412 -0.241673 0.0640155 0.0366557 -0.241673 0.0620569 0.0372428 -0.241673 0.0579924 0.0334108 -0.241673 0.0576258 0.0323246 -0.241673 0.0414384 0.0239922 -0.241673 0.0392876 0.022329 -0.241673 0.0373365 0.0214592 -0.241673 0.035956 0.019829 -0.241673 0.0400761 0.012822 -0.241673 0.0385488 0.0126464 -0.241673 0.0359917 0.0153433 -0.241673 0.032421 0.0173103 -0.241673 0.0404222 0.00916888 -0.241673 0.0409968 0.00899756 -0.241673 0.0329965 0.00741177 -0.241673 0.0325793 -0.00674943 -0.241673 0.0319922 -0.00870799 -0.241673 0.0289736 -0.00823015 -0.241673 0.0405887 -0.0048551 -0.241673 0.0408805 0.00504927 -0.241673 0.0383474 0.00580772 -0.241673 0.0314222 -0.0165969 -0.241673 0.0338656 -0.0121855 -0.241673 0.0358242 -0.0127726 -0.241673 0.0393283 -0.012567 -0.241673 0.0378139 -0.0123018 -0.241673 0.0393017 -0.0108992 -0.241673 0.0380154 -0.00546313 -0.241673 0.0520308 -0.0366856 -0.241673 0.0559518 -0.0400274 -0.241673 0.0644219 -0.0420902 -0.241673 0.0598335 -0.0382393 -0.241673 0.063975 -0.0370374 -0.241673 0.0731358 -0.0423469 -0.241673 0.0688281 -0.0405477 -0.241673 0.106079 -0.00780075 -0.241673 0.107474 -0.0109314 -0.241673 0.110586 -0.00691699 -0.241673 0.106887 -0.01289 -0.241673 0.100428 0.0277484 -0.241673 0.0999692 0.0222681 -0.241673 0.099415 0.023128 -0.241673 0.0933918 0.0198832 -0.241673 0.0975415 0.0266055 -0.241673 0.095583 0.0271926 -0.241673 0.0877584 0.0280027 -0.241673 0.0935932 0.0267218 -0.241673 0.0921055 0.0253192 -0.241673 0.104176 0.0112426 -0.241673 0.10309 0.0116092 -0.241673 0.100672 0.0110371 -0.241673 0.100582 0.00542093 -0.241673 0.100111 0.00741065 -0.241673 0.100698 0.00936921 -0.241673 0.101985 0.00393318 -0.241673 0.106564 0.00311445 -0.241673 0.105933 0.00381688 -0.241673 0.108008 0.00717805 -0.241673 0.111004 0.00682422 -0.241673 0.108601 0.015011 -0.241673 0.100712 -0.0238589 -0.241673 0.106018 -0.0217797 -0.241673 0.104044 -0.0213589 -0.241673 0.10341 -0.0147634 -0.241673 0.104008 -0.0168733 -0.241673 0.102304 -0.0150654 -0.241673 0.100019 -0.00899725 -0.241673 0.0922827 -0.0307121 -0.241673 0.0860343 -0.0305281 -0.241673 0.0861925 -0.0251578 -0.241673 0.0906481 -0.0241568 -0.241673 0.0863986 -0.0181591 -0.241673 0.0919344 -0.0295928 -0.241673 0.0666929 -0.031524 -0.241673 0.064885 -0.0332284 -0.241673 0.0761859 -0.031347 -0.241673 0.0815367 -0.032951 -0.241673 0.0691108 -0.0309519 -0.241673 0.071246 -0.0399756 -0.241673 0.0730539 -0.0382712 -0.241673 0.0817127 -0.0407862 -0.241673 0.0815661 -0.0366423 -0.241673 0.0897776 -0.0374765 -0.241673 0.0969782 -0.0325622 -0.241673 0.0984033 -0.0308924 -0.241673 0.103 -0.0262583 -0.241673 0.0602374 -0.0297682 -0.241673 0.0600661 -0.0303427 -0.241673 0.0580764 -0.0308135 -0.241673 0.063311 -0.0363659 -0.241673 0.0398725 -0.0291683 -0.241673 0.0424584 -0.0281354 -0.241673 0.0349612 -0.0196415 -0.241673 0.0355569 -0.0242717 -0.241673 0.0366656 -0.0214494 -0.241673 0.0390456 -0.0221628 -0.241673 0.0410558 -0.0266477 -0.241673 0.040585 -0.024658 -0.241673 0.0400307 -0.023798 -0.241673 0.0410264 -0.0229564 -0.241673 0.0414635 -0.0215907 -0.241673 0.0421625 -0.0216149 -0.241673 0.0437681 -0.0208991 -0.241673 0.0523997 -0.0241623 -0.241673 0.048141 -0.023166 -0.241673 0.0541364 -0.026463 -0.241673 0.0414829 0.0296598 -0.241673 0.0420455 0.0301775 -0.241673 0.0494975 0.0228839 -0.241673 0.0538075 0.0236278 -0.241673 0.0508787 0.0259636 -0.241673 0.0499389 0.0245854 -0.241673 0.0494681 0.0265752 -0.241673 0.0491742 0.0277715 -0.241673 0.0480655 0.0280629 -0.241673 0.0469669 0.0292043 -0.241673 0.0461069 0.02865 -0.241673 0.0415966 0.0293625 -0.241673 0.0420424 0.024818 -0.241673 0.0414229 0.0222661 -0.241673 0.043438 0.0216874 -0.241673 0.0433194 0.021283 -0.241673 0.0446016 0.0195743 -0.241673 0.0444169 -0.0287226 -0.241673 0.0452428 -0.0293265 -0.241673 0.0464067 -0.0282517 -0.241673 0.0468172 -0.0304061 -0.241673 0.0480957 -0.0362487 -0.241673 0.0514737 -0.0353454 -0.241673 0.0560015 -0.0341747 -0.241673 0.0538916 -0.0347732 -0.241673 0.0556995 -0.0330688 -0.241673 0.0565886 -0.0322161 -0.241673 0.056413 -0.0306888 -0.241673 0.0558409 -0.0282709 -0.241673 0.0985615 -0.0255221 -0.241673 0.0973704 -0.0283065 -0.241673 0.0979576 -0.026348 -0.241673 0.098577 -0.023796 -0.241673 0.0960841 -0.0228705 -0.241673 0.0953983 -0.0211043 -0.241673 0.092647 -0.0183431 -0.241673 0.095698 -0.0166285 -0.241673 0.110878 0.00298738 -0.241673 0.110516 -0.0106321 -0.241673 0.100759 -0.00407207 -0.241673 0.0991195 -0.00657921 -0.241673 0.100187 -0.00165417 -0.241673 0.102463 -0.00587996 -0.241673 0.107261 -0.00602129 -0.241673 0.106272 -0.00678992 -0.241673 0.109783 -0.00193683 -0.241673 0.107506 0.00228895 -0.241673 0.0994112 0.00332516 -0.241673 0.1009 0.000725851 -0.241673 0.0443019 0.0150986 -0.241673 0.0466026 0.0168353 -0.241673 0.0463671 0.00883937 -0.241673 0.059388 0.0302801 -0.241673 0.0581979 0.0299067 -0.241673 0.0609487 0.0294711 -0.241673 0.0618034 0.0233923 -0.241673 0.0585795 0.0353694 -0.241673 0.0582873 0.0392563 -0.241673 0.0535413 0.034846 -0.241673 0.0430217 0.0310323 -0.241673 0.0493156 0.0325694 -0.241673 0.046989 0.0299546 -0.241673 0.0486021 0.0301894 -0.241673 0.0486922 0.0291119 -0.241673 0.0960151 0.0159763 -0.241673 0.0936424 0.0154496 -0.241673 0.0953504 0.0192961 -0.241673 0.0967285 0.0183563 -0.241673 0.0985364 0.0200608 -0.241673 0.100954 0.0206329 -0.241673 0.105039 0.0181115 -0.241673 0.105611 0.0156936 -0.241673 0.100258 0.0279285 -0.241673 0.100127 0.0276383 -0.241673 0.0997273 0.0284784 -0.241673 0.0940068 0.0278186 -0.241673 0.0799338 0.0288128 -0.241673 0.0877805 0.028753 -0.241673 0.045959 -0.00501329 -0.241673 0.0462508 0.00489108 -0.241673 0.0399514 0.0111586 -0.241673 0.0965872 0.0135584 -0.241673 0.0932906 0.00350545 -0.241673 0.100049 -0.0126886 -0.241673 0.0456072 -0.0169575 -0.241673 0.0529577 -0.00521945 -0.241673 0.0533658 0.00863321 -0.241673 0.0536013 0.0166291 -0.241673 0.0934069 0.00745374 -0.241673 0.0871585 0.00763779 -0.241673 0.0870422 0.0036895 -0.241673 0.0929989 -0.00639892 -0.241673 0.0921358 -0.0227542 -0.241673 0.0941256 -0.0222834 -0.241673 0.0532495 0.00468492 -0.241673 0.0526059 -0.0171636 -0.241673 0.0603956 -0.0243979 -0.241673 0.0619615 0.0287626 -0.241673 0.0659098 0.0286463 -0.241673 0.0615972 0.0163936 -0.241673 0.0613617 0.00839768 -0.241673 0.0653099 0.00828138 -0.241673 0.0612454 0.00444939 -0.241673 0.0651936 0.00433309 -0.241673 0.0609536 -0.00545498 -0.241673 0.0606018 -0.0173992 -0.241673 0.0643439 -0.0245142 -0.241673 0.0620247 -0.0309298 -0.241673 0.0641857 -0.0298845 -0.241673 0.0876002 0.0226324 -0.241673 0.0657516 0.023276 -0.241673 0.0655455 0.0162773 -0.241673 0.087394 0.0156337 -0.241673 0.0649019 -0.00557128 -0.241673 0.0645501 -0.0175155 -0.241673 0.0867505 -0.00621487 -0.241673 0.0781756 -0.0308762 -0.23002 0.0626447 0.0629102 -0.229938 0.0620258 0.0630621 -0.229919 0.0619652 0.0631072 -0.22969 0.0616391 0.0636996 -0.229578 0.0821398 0.0634106 -0.229445 0.0819526 0.0638166 -0.229692 0.0812462 0.0632532 -0.229885 0.0818738 0.0626005 -0.229741 0.0821055 0.0629594 -0.23002 0.0749689 0.0631407 -0.23002 0.0718868 0.0633058 -0.23002 0.0688013 0.0633224 -0.229365 0.0671819 0.0650733 -0.229365 0.0624382 0.0646983 -0.229692 0.0625415 0.0638042 -0.229399 0.0620477 0.0645586 -0.228414 0.0815764 0.0651328 -0.228238 0.062315 0.0657645 -0.228993 0.0623691 0.0652967 -0.228993 0.071958 0.0657071 -0.229365 0.0719403 0.065105 -0.229365 0.0766885 0.0647932 -0.228993 0.0767497 0.0653925 -0.22873 0.0815457 0.0649583 -0.228414 0.0767909 0.0657964 -0.228414 0.0719699 0.0661129 -0.228993 0.0671561 0.0656751 -0.228414 0.0671388 0.0660807 -0.22873 0.0623428 0.0655239 -0.22772 0.0768054 0.0659388 -0.224573 0.0606958 0.060988 -0.224573 0.0755576 0.0614372 -0.224773 0.0755398 0.061238 -0.224773 0.0825773 0.0602012 -0.224773 0.0679622 0.0666542 -0.224773 0.0760026 0.0664174 -0.224573 0.0759848 0.0662182 -0.224773 0.0839575 0.0652251 -0.224573 0.0855751 0.0616261 -0.224573 0.0848176 0.0607306 -0.224773 0.0859632 0.0621433 -0.224573 0.0858178 0.0627735 -0.224773 0.0858915 0.0634873 -0.224773 0.0851573 0.0646153 -0.224573 0.0857013 0.0634253 -0.224573 0.0596568 0.06106 -0.224773 0.0586134 0.0614158 -0.224773 0.0579517 0.0623297 -0.224573 0.0581352 0.062409 -0.224573 0.0579393 0.0634319 -0.224773 0.0629372 0.0603785 -0.224773 0.0681193 0.0614566 -0.224773 0.0718122 0.0607583 -0.224773 0.0818613 0.0599058 -0.224573 0.0841634 0.0603996 -0.224573 0.0829229 0.0603333 -0.222889 0.0845762 0.0647845 -0.224573 0.0850236 0.0644665 -0.222827 0.085452 0.0639577 -0.222736 0.0858063 0.0629331 -0.224573 0.0854877 0.063899 -0.224573 0.0857676 0.0621847 -0.222663 0.0857675 0.0621844 -0.222721 0.0858178 0.0627735 -0.224573 0.0852047 0.0610772 -0.222519 0.0849805 0.0608584 -0.222575 0.0854133 0.0613454 -0.222606 0.0855751 0.0616262 -0.222623 0.0856467 0.0617871 -0.222426 0.0829229 0.0603333 -0.222448 0.0839547 0.0603418 -0.222503 0.0848178 0.0607307 -0.224573 0.0587461 0.0615654 -0.222705 0.0579393 0.0634319 -0.222899 0.0679683 0.0664543 -0.224573 0.0679683 0.0664543 -0.222899 0.0759848 0.0662182 -0.222899 0.0839162 0.0650294 -0.224573 0.0839162 0.0650294 -0.224573 0.0681133 0.0616565 -0.222426 0.0681133 0.0616565 -0.22123 0.0839497 0.0637752 -0.221159 0.0841401 0.0635342 -0.220725 0.0838295 0.061893 -0.220778 0.0831629 0.0614679 -0.220691 0.0832377 0.061822 -0.220951 0.0845164 0.0617821 -0.220992 0.0830773 0.0610634 -0.220978 0.0846502 0.0625083 -0.221326 0.0851509 0.0620308 -0.220833 0.084322 0.0621259 -0.220826 0.0838968 0.0614787 -0.221652 0.0852866 0.0633835 -0.221283 0.0850903 0.0628412 -0.221496 0.0853498 0.0627069 -0.221391 0.0845569 0.0638361 -0.221469 0.0842141 0.064159 -0.221564 0.0847827 0.0639248 -0.222382 0.0839 0.0649529 -0.222077 0.0839313 0.0603769 -0.22288 0.0848004 0.0646443 -0.222469 0.0857422 0.0631839 -0.222252 0.0854464 0.0614552 -0.22176 0.085554 0.0625657 -0.222055 0.085692 0.0624265 -0.221919 0.0854184 0.0616094 -0.221618 0.0829638 0.0605268 -0.222182 0.085646 0.0632652 -0.222363 0.0857613 0.0622975 -0.221791 0.0848253 0.0609274 -0.22215 0.0848154 0.060773 -0.222049 0.0829314 0.0603734 -0.221695 0.0839595 0.0605175 -0.221889 0.0838498 0.0647159 -0.221131 0.0847935 0.0629604 -0.221777 0.0849878 0.0639882 -0.22186 0.0844892 0.0644535 -0.222206 0.0838865 0.0648894 -0.222559 0.0853962 0.064005 -0.222357 0.0846927 0.0646202 -0.222287 0.0852998 0.0640279 -0.221904 0.0854929 0.0633333 -0.221602 0.0853201 0.0618048 -0.221451 0.0847793 0.0611562 -0.221161 0.084674 0.0614488 -0.221335 0.083965 0.0607573 -0.221035 0.0839438 0.061087 -0.222877 0.059017 0.0653648 -0.221131 0.0589832 0.0637201 -0.220806 0.0600471 0.0633345 -0.220725 0.0598824 0.0625985 -0.220854 0.0598505 0.0634357 -0.221254 0.0601522 0.0645959 -0.221391 0.0592709 0.064581 -0.221183 0.0597157 0.06433 -0.221274 0.0590458 0.0641772 -0.221326 0.0585719 0.0628133 -0.220978 0.0590998 0.0632607 -0.221161 0.0590133 0.0622048 -0.220951 0.0591903 0.0625282 -0.220778 0.060523 0.0621349 -0.220833 0.0594046 0.06286 -0.220691 0.0604691 0.0624926 -0.220826 0.0597908 0.062189 -0.222575 0.0582697 0.0621443 -0.222602 0.058137 0.0624049 -0.222252 0.0582431 0.0622558 -0.222515 0.0587125 0.0615957 -0.222498 0.0588825 0.0614532 -0.222444 0.0597676 0.0610301 -0.222049 0.0606897 0.0610286 -0.221618 0.0606664 0.0611836 -0.222663 0.0579653 0.0630021 -0.222363 0.0579781 0.0631147 -0.222751 0.0580024 0.0639125 -0.222559 0.058443 0.0647991 -0.222827 0.0583846 0.0647552 -0.222357 0.0591817 0.0653719 -0.222381 0.0599923 0.0656572 -0.222206 0.060002 0.065593 -0.221469 0.0596322 0.0648832 -0.22186 0.059375 0.0651934 -0.221777 0.0588498 0.0647583 -0.222182 0.0581498 0.0640745 -0.221904 0.0583067 0.0641336 -0.222055 0.0580548 0.0632395 -0.221919 0.05828 0.0624082 -0.221695 0.0596714 0.0612331 -0.222077 0.0596914 0.061091 -0.22215 0.0588323 0.0615384 -0.221791 0.0588316 0.0616932 -0.222469 0.058049 0.063999 -0.222287 0.0585406 0.0648163 -0.221241 0.0599421 0.0645268 -0.221652 0.0585156 0.0641716 -0.221496 0.0584129 0.0634995 -0.22176 0.0582007 0.0633704 -0.221602 0.0583897 0.0625975 -0.221451 0.058891 0.0619189 -0.221035 0.0597207 0.0618007 -0.221335 0.0596801 0.0614728 -0.220992 0.0605846 0.061726 -0.221626 0.0759359 0.0656713 -0.221254 0.0836779 0.0639029 -0.221626 0.0838025 0.0644922 -0.221497 0.0837707 0.0643418 -0.221254 0.0758823 0.0650713 -0.221626 0.0679849 0.0659055 -0.222206 0.075972 0.0660756 -0.221626 0.0600625 0.0651915 -0.221889 0.0600284 0.0654176 -0.222206 0.0679726 0.0663113 -0.221618 0.0681073 0.0618542 -0.220781 0.0677737 0.0639953 -0.220781 0.0760351 0.0637519 -0.221618 0.0755752 0.0616342 -0.220683 0.0832516 0.0618873 -0.220691 0.075693 0.0629528 -0.22129 0.0606335 0.0614016 -0.220691 0.0680673 0.0631774 -0.222426 0.0606958 0.060988 -0.220992 0.075624 0.0621805 -0.22129 0.0830094 0.0607425 -0.220992 0.0680908 0.0624024 -0.222426 0.0755576 0.0614372 -0.220939 0.0841019 0.0629251 -0.220853 0.0839095 0.0627261 -0.220795 0.0836298 0.062622 -0.220781 0.0834089 0.062631 -0.221056 0.0841983 0.0632333 -0.221019 0.0841851 0.0631311 -0.221254 0.067729 0.0652945 -0.221098 0.0596061 0.0640772 -0.220781 0.0603459 0.0633104 -0.221018 0.0602491 0.0639531 -0.220878 0.0597842 0.0634933 -0.220981 0.059624 0.0637547 -0.220781 0.0680423 0.064004 -0.221254 0.0680031 0.0653034 -0.220781 0.0757666 0.0637765 -0.221254 0.0761562 0.0650463 -0.221018 0.0835434 0.0632669 -0.222808 0.0582447 0.0645348 -0.2228 0.0581987 0.0644485 -0.224573 0.0582245 0.0644979 -0.224573 0.0589565 0.0653236 -0.222899 0.0599807 0.0657345 -0.224773 0.0580483 0.0645926 -0.224573 0.0599807 0.0657345 -0.224773 0.0588414 0.0654872 -0.227841 0.0834621 0.0639453 -0.22798 0.0837915 0.0627424 -0.224973 0.0837915 0.0625857 -0.224973 0.082745 0.0647744 -0.22772 0.0816012 0.0652738 -0.227753 0.0826946 0.0648118 -0.224773 0.0839914 0.0625798 -0.224973 0.0835334 0.0638068 -0.224773 0.0837139 0.0638931 -0.224773 0.082866 0.0649337 -0.224773 0.0816358 0.0654707 -0.224773 0.082943 0.0604543 -0.224773 0.0836986 0.0614029 -0.224973 0.0818109 0.0600994 -0.224773 0.0614778 0.0605942 -0.224973 0.0615572 0.0607778 -0.224773 0.061033 0.0608358 -0.224973 0.0604824 0.06163 -0.224773 0.0603218 0.0615108 -0.224773 0.0599947 0.064342 -0.224973 0.0610305 0.0653374 -0.224773 0.0609113 0.065498 -0.224973 0.0604619 0.0647613 -0.224773 0.0607256 0.0607903 -0.224773 0.0577394 0.0634378 -0.224773 0.059779 0.0628826 -0.224773 0.0596 0.0608683 -0.224773 0.0599509 0.0659322 -0.224773 0.0622831 0.0660408 -0.224773 0.0828815 0.0601376 -0.224773 0.0842254 0.0602094 -0.224773 0.0853534 0.0609436 -0.224773 0.0806495 0.0598567 -0.228376 0.0688452 0.0609742 -0.224973 0.0629142 0.0605771 -0.224973 0.0718181 0.0609583 -0.228376 0.0718181 0.0609583 -0.224973 0.0806841 0.0600537 -0.224773 0.0719801 0.0664559 -0.227734 0.06156 0.0656429 -0.227819 0.0605071 0.064822 -0.224973 0.0601783 0.0642625 -0.224973 0.0599776 0.0629056 -0.224973 0.0599831 0.063558 -0.22795 0.0600041 0.0636904 -0.224973 0.0608722 0.0612091 -0.228251 0.0607419 0.0613302 -0.224973 0.0601317 0.0622715 -0.228109 0.0600847 0.0624068 -0.228046 0.0599777 0.0629047 -0.228268 0.060872 0.0612093 -0.224973 0.0828166 0.0606094 -0.224973 0.0835192 0.0614914 -0.228046 0.0837523 0.0622031 -0.230111 0.0749048 0.0623162 -0.229184 0.0688415 0.0611719 -0.229184 0.0748022 0.0609963 -0.228376 0.0747868 0.0607992 -0.228376 0.0806841 0.0600537 -0.229809 0.0688312 0.0617203 -0.229511 0.0628662 0.0609924 -0.228752 0.0806912 0.0600941 -0.229184 0.0807184 0.0602484 -0.229809 0.0808133 0.0607887 -0.230111 0.0627396 0.0620887 -0.230111 0.0688167 0.0624955 -0.230023 0.0627812 0.0617288 -0.229809 0.0748447 0.0615432 -0.23002 0.0810905 0.0623668 -0.224973 0.0816012 0.0652738 -0.224973 0.0719742 0.066256 -0.22772 0.0719742 0.066256 -0.22772 0.0671326 0.0662237 -0.224973 0.0623061 0.0658421 -0.229803 0.0617301 0.0633979 -0.229577 0.0610178 0.0635862 -0.229463 0.0618213 0.0643511 -0.229255 0.0613854 0.0646173 -0.229497 0.0617535 0.0642501 -0.229764 0.061147 0.0630323 -0.230009 0.0624097 0.0629134 -0.228949 0.0602253 0.0632641 -0.22877 0.0603647 0.0641172 -0.227747 0.0612942 0.0655098 -0.229157 0.0618318 0.064972 -0.22827 0.061399 0.0654757 -0.229639 0.061634 0.06384 -0.229401 0.0611036 0.0641352 -0.228869 0.0609712 0.0648088 -0.229023 0.0605744 0.064148 -0.228359 0.0606648 0.0648775 -0.228493 0.0602063 0.0640638 -0.228206 0.0601031 0.063992 -0.228168 0.0602808 0.061946 -0.229809 0.0628286 0.0613185 -0.229184 0.0628915 0.0607736 -0.228752 0.0629095 0.0606179 -0.228376 0.0629142 0.0605771 -0.229321 0.060955 0.0616245 -0.22914 0.0604159 0.0623946 -0.229416 0.060605 0.0626038 -0.229611 0.0610867 0.0619059 -0.229821 0.0612744 0.0622228 -0.229759 0.0618672 0.0614313 -0.229458 0.0618156 0.0611052 -0.229098 0.0617989 0.060866 -0.228981 0.0608882 0.0614011 -0.228717 0.0618141 0.0607234 -0.228348 0.0618321 0.0606764 -0.228622 0.0608838 0.0612464 -0.228275 0.0609312 0.0611594 -0.22772 0.0623061 0.0658421 -0.228414 0.0623225 0.0657 -0.228766 0.0615858 0.0652907 -0.228087 0.0605669 0.0648637 -0.228346 0.0599944 0.0630167 -0.228491 0.060258 0.0620584 -0.228653 0.0600752 0.0631386 -0.228823 0.0603 0.0622094 -0.229212 0.0604414 0.0633856 -0.229939 0.0614997 0.0625469 -0.229967 0.0619505 0.0618168 -0.230069 0.062056 0.0622228 -0.229511 0.0807565 0.0604654 -0.229577 0.0827542 0.0629452 -0.229986 0.0815037 0.0623891 -0.230069 0.081638 0.0616461 -0.229365 0.0814019 0.0641397 -0.229255 0.082448 0.063997 -0.229463 0.0819972 0.0637569 -0.229401 0.0827012 0.0634986 -0.228993 0.0815062 0.064733 -0.229157 0.0820231 0.0643774 -0.228869 0.0828727 0.0641638 -0.22969 0.0821407 0.0630953 -0.229764 0.0825925 0.0624002 -0.229416 0.0831084 0.0619403 -0.230023 0.0808847 0.0611956 -0.229939 0.0822122 0.0619369 -0.229821 0.0824181 0.0616001 -0.229967 0.0817195 0.0612346 -0.230111 0.0809474 0.0615523 -0.228135 0.0835311 0.0615157 -0.228168 0.0833931 0.0612645 -0.228256 0.0828543 0.0606406 -0.228491 0.0834225 0.0613753 -0.228275 0.0826981 0.0605183 -0.228622 0.0827505 0.0606023 -0.228353 0.081661 0.0600649 -0.227863 0.08356 0.0637494 -0.228087 0.0832796 0.0641949 -0.227999 0.0837915 0.0625857 -0.228206 0.0836916 0.0632965 -0.227924 0.0837359 0.063209 -0.227819 0.0833368 0.0641498 -0.229098 0.0818149 0.0602765 -0.229458 0.0818123 0.0605163 -0.228981 0.0827553 0.060757 -0.228653 0.0836688 0.0624423 -0.228493 0.0835928 0.0633743 -0.22827 0.0824847 0.0648548 -0.228766 0.0822875 0.0646811 -0.228717 0.0817913 0.0601351 -0.228346 0.0837423 0.0623159 -0.228823 0.0833895 0.0615285 -0.228359 0.0831826 0.0642144 -0.227748 0.0826105 0.0648701 -0.228238 0.0815876 0.0651968 -0.229376 0.0816272 0.0640692 -0.229023 0.0832302 0.0634801 -0.228771 0.0834377 0.063437 -0.228949 0.0835265 0.0625766 -0.229212 0.0833179 0.0627107 -0.22914 0.0832848 0.0617203 -0.229611 0.0825868 0.0612727 -0.229321 0.0827017 0.0609841 -0.229759 0.0817799 0.0608449 -0.224573 0.0437119 0.0558826 -0.224573 0.0506424 0.0586092 -0.224573 0.0491545 0.0631727 -0.222889 0.0498486 0.0632906 -0.22288 0.0501129 0.0632814 -0.222827 0.0510205 0.0630125 -0.224573 0.0519293 0.0621699 -0.222736 0.0518396 0.0623023 -0.222503 0.0520847 0.0599008 -0.224573 0.0522929 0.0610548 -0.222575 0.0522931 0.0607308 -0.222606 0.0522928 0.0610549 -0.222623 0.0522744 0.0612301 -0.222899 0.0416914 0.0602366 -0.222899 0.0491545 0.0631727 -0.224573 0.0416914 0.0602366 -0.224773 0.0333117 0.0486554 -0.224773 0.0437961 0.0557011 -0.224773 0.0504092 0.058322 -0.224773 0.0498717 0.057646 -0.222877 0.0274235 0.0510137 -0.224573 0.0274228 0.0510122 -0.224773 0.0272439 0.0511017 -0.224573 0.0280733 0.0518156 -0.228167 0.0505843 0.0596592 -0.224973 0.0505843 0.0596592 -0.224973 0.0503123 0.060909 -0.22784 0.0492961 0.0620113 -0.227924 0.0499087 0.0615061 -0.224973 0.0494866 0.0618859 -0.22781 0.048994 0.0621666 -0.224973 0.0489937 0.0621668 -0.227748 0.0481035 0.0623819 -0.224973 0.0482994 0.0623621 -0.224773 0.046959 0.0624148 -0.224973 0.0470275 0.0622269 -0.224773 0.0483269 0.0625602 -0.224773 0.0504917 0.0609975 -0.224973 0.0499084 0.0615065 -0.224973 0.0407129 0.053598 -0.228376 0.0433634 0.0549446 -0.224773 0.0381044 0.05844 -0.224973 0.0331925 0.048816 -0.224973 0.0300333 0.0530715 -0.22795 0.0291156 0.0500571 -0.228376 0.0331925 0.048816 -0.228348 0.0322057 0.0483609 -0.228268 0.0311078 0.0483423 -0.224973 0.031917 0.0483113 -0.224973 0.031108 0.0483423 -0.228251 0.0309347 0.048382 -0.224973 0.03056 0.0485119 -0.224973 0.0299356 0.0488921 -0.228168 0.0302275 0.0486847 -0.224973 0.0488434 0.0572476 -0.228349 0.04975 0.057806 -0.228282 0.050319 0.0585792 -0.229184 0.0380282 0.0522947 -0.228376 0.0381303 0.0521254 -0.228376 0.0407129 0.053598 -0.229184 0.0432781 0.055123 -0.229809 0.0327477 0.0494152 -0.229184 0.0487756 0.0574334 -0.230023 0.0325014 0.0497469 -0.230111 0.037345 0.0534286 -0.229511 0.0329433 0.0491516 -0.229809 0.0430415 0.0556179 -0.229809 0.0377451 0.0527645 -0.230111 0.0427071 0.0563174 -0.23002 0.0317926 0.0507017 -0.23002 0.0395987 0.0556654 -0.22772 0.0425418 0.0604049 -0.224973 0.0381992 0.058264 -0.228109 0.0298272 0.0489857 -0.228622 0.0310995 0.0483804 -0.22969 0.030527 0.0508826 -0.229497 0.0303507 0.0514165 -0.229463 0.030359 0.0515379 -0.229939 0.0309826 0.0498146 -0.230069 0.0316264 0.0498121 -0.230111 0.0322855 0.0500377 -0.229919 0.0311056 0.0505326 -0.229803 0.0307566 0.0506668 -0.229764 0.0304345 0.0500587 -0.22877 0.0292145 0.0506071 -0.229255 0.0298484 0.0515505 -0.228766 0.0296852 0.0522338 -0.22827 0.029431 0.0523007 -0.229639 0.0304523 0.0510016 -0.229577 0.0300457 0.0504737 -0.229023 0.0293807 0.0507385 -0.229401 0.0298454 0.050992 -0.228869 0.029394 0.0515092 -0.228493 0.029104 0.0504816 -0.228359 0.0290943 0.0514155 -0.228206 0.0290505 0.0503678 -0.229967 0.031738 0.0494077 -0.229759 0.0318587 0.0490323 -0.229458 0.031977 0.0487239 -0.229184 0.0330746 0.0489748 -0.229098 0.0320821 0.0485085 -0.228752 0.033168 0.0488489 -0.229321 0.0309721 0.0487435 -0.229611 0.0309454 0.049053 -0.229416 0.0301793 0.0494165 -0.229821 0.0309495 0.0494213 -0.228981 0.0310259 0.0485165 -0.228717 0.0321666 0.0483926 -0.22772 0.0300333 0.0530715 -0.227734 0.0294868 0.052526 -0.22873 0.0302242 0.0528143 -0.229157 0.0300576 0.0520809 -0.228993 0.0303606 0.0526306 -0.227747 0.0293232 0.0522778 -0.227819 0.0289854 0.0512886 -0.228087 0.0290163 0.0513546 -0.228046 0.0294856 0.0493635 -0.228346 0.0294441 0.0494688 -0.228491 0.0301515 0.0487707 -0.228653 0.0294531 0.0496147 -0.228823 0.0301124 0.0489225 -0.228949 0.0295203 0.0497985 -0.22914 0.0301201 0.0491408 -0.229212 0.0296467 0.0500117 -0.229416 0.0499995 0.0600936 -0.229939 0.0492252 0.0596425 -0.23002 0.0480387 0.059454 -0.229157 0.0478412 0.0616615 -0.229376 0.0476523 0.0611967 -0.229401 0.0488677 0.0612395 -0.229463 0.048129 0.0611112 -0.229578 0.0484256 0.0608826 -0.229577 0.0491904 0.0607868 -0.229212 0.0497958 0.0608656 -0.229023 0.0493352 0.061488 -0.229821 0.0495718 0.0594538 -0.229611 0.0498816 0.0592546 -0.229967 0.0491496 0.058788 -0.230023 0.0484462 0.0583368 -0.22969 0.0485841 0.06061 -0.229764 0.0493228 0.060234 -0.230069 0.0488733 0.0591036 -0.230111 0.0483221 0.0586771 -0.228752 0.0488294 0.0572861 -0.228376 0.0488434 0.0572476 -0.228362 0.0495045 0.0576016 -0.228622 0.0503586 0.058756 -0.228491 0.0505541 0.0597614 -0.228119 0.0505647 0.0600681 -0.228061 0.0504655 0.0605255 -0.227962 0.0501072 0.0612557 -0.228414 0.0470766 0.0620924 -0.228766 0.0479182 0.0620567 -0.228359 0.0489268 0.0621001 -0.228493 0.0497021 0.0615777 -0.228949 0.0500435 0.0608537 -0.22914 0.0502623 0.0599913 -0.229098 0.0497113 0.058006 -0.228717 0.0497616 0.0578717 -0.228981 0.0502854 0.0588923 -0.228823 0.0504489 0.0598775 -0.228346 0.0503608 0.0607358 -0.228653 0.0502339 0.0608086 -0.228206 0.0498265 0.0615597 -0.228087 0.0490205 0.0621317 -0.22827 0.0480022 0.0623058 -0.22873 0.0471373 0.0619259 -0.229255 0.0483993 0.0615445 -0.228869 0.0486837 0.0619013 -0.228771 0.0495364 0.0615545 -0.229321 0.0501255 0.0590621 -0.229759 0.0493968 0.0584807 -0.229809 0.0485877 0.0579487 -0.229458 0.0495892 0.0582123 -0.229511 0.0487002 0.0576404 -0.229365 0.0430133 0.0593544 -0.230009 0.0315874 0.0505869 -0.229938 0.0311806 0.0505239 -0.229399 0.0304513 0.0518308 -0.229445 0.0480605 0.0611406 -0.229692 0.0477304 0.0602996 -0.229986 0.0483855 0.0596799 -0.229885 0.0486003 0.060048 -0.229741 0.0486215 0.0604747 -0.23002 0.0423504 0.0570634 -0.23002 0.0369182 0.0541369 -0.229692 0.0312561 0.0514243 -0.228238 0.0470543 0.0621534 -0.22772 0.0470275 0.0622269 -0.228414 0.0301186 0.0529566 -0.229365 0.0307196 0.052147 -0.229365 0.0346403 0.0548436 -0.229365 0.0387453 0.0572502 -0.228993 0.0472157 0.061711 -0.229365 0.047422 0.0611451 -0.228993 0.0427666 0.059904 -0.228993 0.0384596 0.0577806 -0.228414 0.0382671 0.058138 -0.228993 0.0343171 0.0553519 -0.228414 0.0426004 0.0602743 -0.22772 0.0381992 0.058264 -0.22772 0.0340225 0.0558152 -0.228414 0.0340992 0.0556945 -0.228238 0.0300799 0.0530088 -0.224773 0.0311905 0.0479063 -0.224573 0.0371553 0.0523503 -0.224773 0.0372605 0.0521802 -0.224773 0.0507044 0.058419 -0.224573 0.0516836 0.0592868 -0.224773 0.0518324 0.0591531 -0.224573 0.0520846 0.0599006 -0.224573 0.0522465 0.0603943 -0.224573 0.0521803 0.0616349 -0.224573 0.0503951 0.063239 -0.224773 0.0504365 0.0634347 -0.224573 0.0510808 0.0629795 -0.224573 0.0515026 0.0626761 -0.224773 0.0516363 0.0628249 -0.224573 0.0310658 0.0480626 -0.224573 0.0300897 0.0475962 -0.224773 0.0301331 0.0474009 -0.224573 0.0273833 0.0489491 -0.224773 0.0272011 0.0488665 -0.224573 0.0271706 0.0500098 -0.224573 0.0346308 0.0564328 -0.224773 0.0416072 0.060418 -0.221497 0.0493724 0.0625045 -0.22123 0.0498107 0.0621034 -0.220978 0.0510508 0.0613564 -0.220853 0.0503005 0.0611747 -0.220795 0.0501103 0.0609447 -0.220725 0.0506478 0.0604132 -0.220778 0.0502829 0.0597118 -0.221035 0.0511497 0.0597724 -0.220992 0.0504111 0.0593186 -0.221019 0.0503367 0.0616632 -0.220951 0.051298 0.0606606 -0.220833 0.0509578 0.0608612 -0.220826 0.0509131 0.0600881 -0.221159 0.0500961 0.0619898 -0.221469 0.0498478 0.0625679 -0.221391 0.0503061 0.0624597 -0.222357 0.0500316 0.0632066 -0.222382 0.0491788 0.0630984 -0.222426 0.0506424 0.0586092 -0.222519 0.0521618 0.0600928 -0.222448 0.0515318 0.0591324 -0.222559 0.0509486 0.0630256 -0.222363 0.0521185 0.0617294 -0.222721 0.0519294 0.0621698 -0.222663 0.0521804 0.0616345 -0.221904 0.0513681 0.0624922 -0.221602 0.0519827 0.0610821 -0.221335 0.0513329 0.0594974 -0.222469 0.0516587 0.0624875 -0.222182 0.0515348 0.0625098 -0.222055 0.0519939 0.0618065 -0.222252 0.0522669 0.0608424 -0.221919 0.0521655 0.0609621 -0.22215 0.0520615 0.0599362 -0.221791 0.0519929 0.0600748 -0.222077 0.0514939 0.0591511 -0.221695 0.0514481 0.059287 -0.22186 0.0499387 0.0629605 -0.221131 0.0509488 0.0618196 -0.221564 0.0504573 0.0626494 -0.221283 0.0512655 0.0618647 -0.221777 0.0506032 0.0628068 -0.222206 0.0491989 0.0630367 -0.222287 0.0508536 0.0629973 -0.221652 0.0511643 0.0624326 -0.22176 0.0518049 0.061858 -0.221496 0.0515574 0.0618782 -0.221326 0.0517231 0.0611933 -0.221451 0.0518386 0.06025 -0.221161 0.0516012 0.0604508 -0.22129 0.0505128 0.0590068 -0.220781 0.0427233 0.0580129 -0.220691 0.0301172 0.0492523 -0.220781 0.0499144 0.060842 -0.220683 0.05015 0.0601193 -0.220992 0.0367628 0.052985 -0.220691 0.0501708 0.0600558 -0.220691 0.0430714 0.0572628 -0.22129 0.0308051 0.0483896 -0.220992 0.0306006 0.0486461 -0.220691 0.0363551 0.0536444 -0.221618 0.0370513 0.0525185 -0.222426 0.0371553 0.0523503 -0.220992 0.0433978 0.0565595 -0.221618 0.0505811 0.0587972 -0.221618 0.0436287 0.0560619 -0.222426 0.0437119 0.0558826 -0.222049 0.0506297 0.0586481 -0.221626 0.0284156 0.0513863 -0.221254 0.0495115 0.062078 -0.221626 0.0493247 0.0626507 -0.221626 0.0419225 0.0597385 -0.221254 0.0421761 0.0591921 -0.221254 0.0352364 0.0554535 -0.222206 0.0417516 0.0601067 -0.222899 0.0346308 0.0564328 -0.221254 0.0350035 0.0553088 -0.221626 0.0349196 0.0559658 -0.221889 0.0282731 0.051565 -0.221889 0.0492539 0.0628681 -0.222206 0.0347061 0.0563111 -0.222381 0.028122 0.0517545 -0.222899 0.0280733 0.0518156 -0.221326 0.0283138 0.0485814 -0.220781 0.0296016 0.0498989 -0.220725 0.0295561 0.0490506 -0.220833 0.0290116 0.0490382 -0.221274 0.0280424 0.0499995 -0.221183 0.0285461 0.0504668 -0.221496 0.0278331 0.0490961 -0.221131 0.0282166 0.0495724 -0.220978 0.0285473 0.0492328 -0.220951 0.0289919 0.0486437 -0.221035 0.029815 0.0482789 -0.220778 0.0303427 0.0489695 -0.220878 0.0290237 0.0497764 -0.220826 0.0296816 0.0486501 -0.222252 0.0283078 0.0479342 -0.22251 0.0291064 0.0475842 -0.22215 0.0291768 0.0476076 -0.222443 0.0302561 0.0476394 -0.222426 0.0310658 0.0480626 -0.222049 0.0310403 0.0480947 -0.222077 0.0301445 0.0476496 -0.222751 0.027271 0.0492486 -0.222363 0.0276488 0.0485455 -0.222827 0.0271806 0.0501695 -0.222357 0.0275627 0.0511021 -0.222206 0.0281625 0.0517037 -0.221469 0.0281971 0.0509041 -0.221777 0.027582 0.0504047 -0.221904 0.027424 0.0495922 -0.222055 0.0276529 0.048692 -0.221695 0.0300562 0.0477626 -0.221335 0.0299438 0.0479746 -0.221618 0.0309425 0.0482172 -0.221791 0.0290988 0.0477412 -0.221919 0.0282636 0.0480846 -0.222182 0.0273177 0.0494626 -0.222469 0.0272681 0.0493468 -0.222287 0.0272852 0.0503004 -0.222559 0.0272093 0.0502367 -0.22186 0.0278193 0.0510442 -0.221254 0.0287912 0.0509153 -0.221241 0.0286437 0.0507504 -0.221391 0.0280353 0.0504618 -0.221652 0.0275859 0.0497296 -0.22176 0.0277138 0.0488782 -0.221161 0.0290003 0.0482752 -0.221602 0.0282639 0.0483034 -0.221451 0.0290374 0.0479664 -0.221018 0.0497129 0.06146 -0.220939 0.0503676 0.0614432 -0.221056 0.0502969 0.0617583 -0.220806 0.0293308 0.0497704 -0.221018 0.0291964 0.0504071 -0.220854 0.02911 0.0497597 -0.220981 0.0287543 0.0499228 -0.221098 0.0285776 0.050193 -0.220781 0.0356918 0.0542059 -0.220781 0.0359201 0.0543478 -0.220781 0.0429681 0.0581259 -0.221254 0.0424258 0.0593073 -0.222498 0.0292629 0.0475588 -0.224573 0.0290079 0.0476058 -0.222575 0.0283866 0.0478509 -0.224573 0.0280402 0.0480895 -0.222613 0.0280514 0.0480803 -0.222816 0.0271706 0.0500098 -0.222726 0.0273623 0.0489968 -0.222663 0.0276941 0.0484416 -0.224773 0.05053 0.0585578 -0.224773 0.0507842 0.0596533 -0.224773 0.0489119 0.0570597 -0.224973 0.0497358 0.0577927 -0.224973 0.0503479 0.0586406 -0.224773 0.0319399 0.0481126 -0.224773 0.0314339 0.0480994 -0.224773 0.0304805 0.0483284 -0.224773 0.0293245 0.0492449 -0.224973 0.0294851 0.0493642 -0.224973 0.029181 0.0519967 -0.224773 0.0289975 0.0520761 -0.224973 0.0289766 0.0512134 -0.224973 0.0289804 0.0506397 -0.224973 0.0291636 0.0499319 -0.224773 0.0287817 0.0506167 -0.224773 0.0269707 0.0500157 -0.224773 0.0279128 0.0479354 -0.224773 0.0289611 0.0474113 -0.224773 0.0279486 0.051972 -0.224773 0.0299141 0.0532321 -0.224773 0.0345256 0.0566029 -0.224773 0.0490926 0.0633629 -0.224773 0.0496036 0.062048 -0.224773 0.0523704 0.0616969 -0.224773 0.0524422 0.0603529 -0.224773 0.0408078 0.0534219 -0.224773 0.114151 0.0449994 -0.224773 0.112807 0.0449277 -0.224573 0.11358 0.045083 -0.224573 0.114089 0.0451896 -0.224573 0.114684 0.0454797 -0.224573 0.114949 0.0492565 -0.224773 0.115817 0.0482773 -0.224773 0.115889 0.0469334 -0.224573 0.115468 0.0463521 -0.224573 0.0920032 0.0578993 -0.224773 0.0927458 0.0571806 -0.224773 0.0918621 0.0577576 -0.224573 0.0914664 0.0587122 -0.224573 0.0912968 0.0596715 -0.224773 0.0912806 0.0586382 -0.224773 0.0932991 0.0566348 -0.224773 0.0944551 0.0557182 -0.224773 0.102331 0.0516097 -0.224773 0.105799 0.0501613 -0.224773 0.111375 0.0457446 -0.224773 0.109534 0.0464102 -0.222426 0.111741 0.0456862 -0.222889 0.115398 0.0487144 -0.22288 0.115522 0.0484809 -0.224573 0.115627 0.0482153 -0.222827 0.115743 0.0475605 -0.224573 0.115693 0.0469748 -0.224573 0.115745 0.0474917 -0.222663 0.11513 0.045867 -0.224573 0.11513 0.0458673 -0.222575 0.114403 0.0453175 -0.222606 0.114684 0.0454798 -0.222623 0.114826 0.0455834 -0.222448 0.112639 0.0451777 -0.224573 0.112848 0.0451233 -0.222436 0.0922018 0.0577225 -0.222445 0.0920103 0.0578923 -0.222899 0.10185 0.0584645 -0.222899 0.108675 0.0542517 -0.222899 0.114949 0.0492565 -0.224573 0.111741 0.0456862 -0.224573 0.105914 0.0503249 -0.224573 0.0995768 0.054237 -0.224573 0.0928188 0.0573668 -0.221254 0.114179 0.0484001 -0.220939 0.114058 0.0473413 -0.220795 0.113497 0.0473149 -0.220725 0.113306 0.0465836 -0.220781 0.11331 0.0474331 -0.220826 0.113157 0.0461912 -0.221161 0.113815 0.0457767 -0.221035 0.113002 0.0458285 -0.220978 0.114324 0.0467062 -0.220951 0.113845 0.0461441 -0.220833 0.113849 0.0465391 -0.220691 0.112758 0.046818 -0.220683 0.112802 0.0468677 -0.221283 0.114872 0.0467744 -0.221496 0.115029 0.0465283 -0.221469 0.114772 0.0483538 -0.222287 0.115646 0.0476974 -0.222382 0.114897 0.0491984 -0.22215 0.113599 0.0451207 -0.222077 0.112636 0.0452198 -0.222049 0.111768 0.0457167 -0.222519 0.113785 0.0451122 -0.222503 0.11358 0.045083 -0.222736 0.115538 0.046496 -0.222469 0.115608 0.0467452 -0.222721 0.115468 0.046352 -0.222363 0.115181 0.0459681 -0.22176 0.115136 0.0463039 -0.222055 0.115185 0.0461144 -0.221602 0.114552 0.045762 -0.221919 0.11454 0.0455436 -0.221791 0.113685 0.0452495 -0.221695 0.112731 0.0453274 -0.221451 0.11376 0.0454707 -0.222182 0.115565 0.0468637 -0.222252 0.114487 0.045396 -0.221618 0.111873 0.0458333 -0.22186 0.115157 0.0484713 -0.221056 0.114295 0.04756 -0.221131 0.114674 0.0470261 -0.221391 0.114907 0.0479027 -0.221564 0.115147 0.0478667 -0.221777 0.115356 0.047819 -0.222357 0.115417 0.0485139 -0.222206 0.114853 0.0491501 -0.222559 0.115718 0.0476293 -0.221904 0.115466 0.0469993 -0.221652 0.115313 0.0471459 -0.221326 0.114519 0.0460423 -0.221335 0.112855 0.0455323 -0.220992 0.112239 0.0462413 -0.222877 0.0935533 0.0619966 -0.221326 0.0918921 0.0600094 -0.221626 0.0943721 0.0613238 -0.220854 0.0933106 0.0599091 -0.220833 0.0926366 0.0596336 -0.220878 0.093282 0.0599922 -0.221241 0.0939355 0.0608083 -0.221183 0.093641 0.060751 -0.221274 0.0929845 0.0609536 -0.221131 0.0927017 0.0605891 -0.221652 0.0925225 0.061214 -0.221098 0.0934197 0.0605869 -0.220978 0.092573 0.0601329 -0.221161 0.0919701 0.0592618 -0.220992 0.0930915 0.0580614 -0.220951 0.0922851 0.0594534 -0.220725 0.0929196 0.0591682 -0.220826 0.0926355 0.0588593 -0.222363 0.0915285 0.0605674 -0.222583 0.0912968 0.0596715 -0.222077 0.0920005 0.0579582 -0.222495 0.0914981 0.0586363 -0.222426 0.0928188 0.0573668 -0.222663 0.0914612 0.0604763 -0.222357 0.0936995 0.0619203 -0.222206 0.0945204 0.0617017 -0.221469 0.0938453 0.0612719 -0.22186 0.0937777 0.0616691 -0.222287 0.0928665 0.0617598 -0.22176 0.0918492 0.0606775 -0.221919 0.0914368 0.0598046 -0.221335 0.0921816 0.0582944 -0.221695 0.0920542 0.0580912 -0.221791 0.0915569 0.0589096 -0.22215 0.0914802 0.0587752 -0.222252 0.0913286 0.0596911 -0.222055 0.0916574 0.0606371 -0.222182 0.0921572 0.0613127 -0.222469 0.0920321 0.0612977 -0.222559 0.0927734 0.0617937 -0.221391 0.0933813 0.0611909 -0.221777 0.0931052 0.0615549 -0.221904 0.0923226 0.0612854 -0.221496 0.0920975 0.0606832 -0.221602 0.0916264 0.0599137 -0.221451 0.0917213 0.0590754 -0.221035 0.0923807 0.0585581 -0.222206 0.101782 0.0583384 -0.221254 0.101063 0.0575797 -0.221497 0.114479 0.0487337 -0.221626 0.114582 0.0488481 -0.221626 0.108359 0.0538025 -0.221254 0.108012 0.0533097 -0.221889 0.114735 0.0490182 -0.221626 0.10159 0.0579809 -0.221889 0.0944556 0.0615366 -0.222206 0.108592 0.0541347 -0.222381 0.0945442 0.0617621 -0.222049 0.0928338 0.057405 -0.221618 0.0996705 0.0544111 -0.220781 0.100452 0.0564322 -0.220691 0.100297 0.0555771 -0.220691 0.106789 0.0515697 -0.220781 0.100689 0.0563054 -0.220778 0.112516 0.0465489 -0.221618 0.0928911 0.0575508 -0.22129 0.0929717 0.0577561 -0.220778 0.0932426 0.0584464 -0.220691 0.0933748 0.0587832 -0.222426 0.0995768 0.054237 -0.220992 0.106343 0.0509354 -0.22129 0.11202 0.0459973 -0.221618 0.106028 0.0504867 -0.220992 0.0999302 0.0548942 -0.222426 0.105914 0.0503249 -0.221019 0.114233 0.047478 -0.220853 0.113792 0.0472651 -0.221159 0.114395 0.0478497 -0.221018 0.113745 0.0479166 -0.221254 0.094152 0.060763 -0.220781 0.093677 0.0595529 -0.220806 0.0934302 0.0597232 -0.221018 0.0939145 0.060158 -0.220981 0.093274 0.0602987 -0.221254 0.101305 0.0574504 -0.220781 0.107265 0.0522462 -0.220781 0.107485 0.0520907 -0.221254 0.108237 0.0531511 -0.22123 0.114351 0.0481536 -0.222645 0.0913995 0.0602987 -0.222754 0.0919732 0.061272 -0.224573 0.0915992 0.0607689 -0.224573 0.0919836 0.0612826 -0.222808 0.0924673 0.0616625 -0.222836 0.0928211 0.0618357 -0.224573 0.0928213 0.0618358 -0.224573 0.0945727 0.0618349 -0.222899 0.0945727 0.0618349 -0.224773 0.0934238 0.0621866 -0.224573 0.0934447 0.0619877 -0.224773 0.0914245 0.0608662 -0.224573 0.0923732 0.0616035 -0.224773 0.092263 0.0617704 -0.227819 0.114007 0.0487844 -0.224973 0.114013 0.0485165 -0.224973 0.113782 0.0496798 -0.224973 0.113066 0.0506256 -0.227748 0.113739 0.0497713 -0.224773 0.114213 0.0485106 -0.224973 0.111886 0.0459963 -0.224773 0.113079 0.0463185 -0.224773 0.113896 0.0472855 -0.224773 0.11066 0.045833 -0.224773 0.0929721 0.0594659 -0.224973 0.0934597 0.056754 -0.224973 0.092955 0.0580295 -0.224973 0.0929721 0.0587604 -0.224973 0.0934866 0.0599488 -0.224973 0.0952834 0.0609661 -0.224773 0.0910969 0.0596774 -0.224773 0.0927563 0.0580065 -0.224773 0.111925 0.0458003 -0.224773 0.115279 0.0457336 -0.224773 0.113964 0.0497617 -0.224773 0.115083 0.0494053 -0.224773 0.10879 0.0544154 -0.224773 0.105325 0.0564599 -0.224773 0.0952604 0.0611648 -0.224773 0.0946458 0.0620211 -0.224773 0.0938887 0.0606219 -0.224973 0.0945346 0.0559017 -0.224973 0.102436 0.0517798 -0.228376 0.102436 0.0517798 -0.224773 0.113195 0.0507789 -0.224773 0.0967199 0.060949 -0.224973 0.0966404 0.0607654 -0.227734 0.0958947 0.0609659 -0.224973 0.0945029 0.0607514 -0.224973 0.0940079 0.0604613 -0.22795 0.093571 0.060053 -0.224973 0.0931556 0.0593865 -0.228376 0.0945346 0.0559017 -0.224973 0.0930821 0.05747 -0.228268 0.093082 0.0574703 -0.228251 0.0930299 0.0576401 -0.228168 0.0929384 0.0584039 -0.228046 0.0931553 0.0593857 -0.228221 0.112177 0.0460723 -0.228376 0.109662 0.0465635 -0.224973 0.109662 0.0465635 -0.228275 0.111639 0.0459588 -0.224973 0.110709 0.0460268 -0.228352 0.110539 0.0460764 -0.228168 0.112613 0.0462575 -0.224973 0.112959 0.0464782 -0.224973 0.113718 0.0473774 -0.227844 0.114013 0.0485165 -0.227988 0.113664 0.0472783 -0.228376 0.0998695 0.0532801 -0.229184 0.0946131 0.0560832 -0.228752 0.0945509 0.0559393 -0.229184 0.0999651 0.0534532 -0.229184 0.105039 0.0503208 -0.228376 0.104928 0.0501577 -0.229809 0.110141 0.0471354 -0.229809 0.10023 0.0539333 -0.229809 0.10535 0.0507731 -0.230111 0.105788 0.0514125 -0.230111 0.100606 0.0546119 -0.23002 0.103669 0.0537785 -0.23002 0.106256 0.0520945 -0.23002 0.111171 0.0483635 -0.224973 0.10522 0.0562898 -0.22772 0.10522 0.0562898 -0.228622 0.0931108 0.0574965 -0.229255 0.0952307 0.060165 -0.228869 0.0949677 0.0605379 -0.229577 0.0943968 0.0594558 -0.229463 0.0954751 0.0597165 -0.229401 0.0947456 0.0598884 -0.229639 0.0950573 0.0593676 -0.229497 0.0953658 0.059663 -0.230009 0.0952657 0.0581772 -0.229939 0.0942945 0.0583149 -0.229938 0.0950077 0.058498 -0.229919 0.0949777 0.0585673 -0.230069 0.0946142 0.0577561 -0.230111 0.0951391 0.057298 -0.229803 0.0949195 0.0589367 -0.228949 0.0935494 0.0595732 -0.228493 0.0939328 0.0602752 -0.228766 0.0957409 0.060648 -0.229023 0.0942937 0.0601641 -0.22877 0.0940967 0.0602423 -0.228359 0.0947367 0.0607506 -0.228206 0.0938075 0.0602647 -0.228346 0.0932257 0.0594743 -0.228109 0.092999 0.058901 -0.229809 0.0948311 0.0565865 -0.229511 0.0947007 0.0562854 -0.229098 0.0937131 0.0567095 -0.228823 0.0930868 0.0586224 -0.228981 0.0931919 0.0576283 -0.22914 0.0932797 0.0587249 -0.229967 0.0943198 0.0574572 -0.229759 0.094055 0.057165 -0.229821 0.0939373 0.0581468 -0.229611 0.0936163 0.0579662 -0.229458 0.0938471 0.0569083 -0.229321 0.0933616 0.0577884 -0.228717 0.093655 0.0565784 -0.228348 0.0936471 0.0565287 -0.22772 0.0966404 0.0607654 -0.228238 0.0966093 0.0606937 -0.22827 0.0956717 0.0609016 -0.228414 0.0965835 0.0606341 -0.22873 0.0965131 0.0604715 -0.229157 0.0957946 0.060249 -0.229399 0.0957749 0.0597831 -0.227747 0.095598 0.0609836 -0.227819 0.0945724 0.0607815 -0.228087 0.094645 0.0607877 -0.228491 0.0929749 0.0585126 -0.228653 0.0933567 0.0595395 -0.229212 0.0937972 0.0595703 -0.229416 0.093548 0.0588115 -0.229764 0.0942318 0.0589116 -0.230023 0.0949952 0.0569656 -0.22772 0.113066 0.0506256 -0.229577 0.112901 0.0480325 -0.229741 0.112346 0.0483691 -0.229939 0.111927 0.0474303 -0.230111 0.110639 0.0477297 -0.228993 0.112714 0.0502048 -0.229365 0.112327 0.0497431 -0.229445 0.112642 0.049188 -0.229401 0.113131 0.0485383 -0.229578 0.112601 0.0487428 -0.22969 0.112444 0.0484692 -0.229764 0.112488 0.0476414 -0.229821 0.111937 0.0470357 -0.229967 0.111149 0.0470685 -0.229611 0.111919 0.0466678 -0.230023 0.110407 0.0474521 -0.230069 0.111284 0.0474656 -0.228112 0.113006 0.0465146 -0.228491 0.112694 0.0463388 -0.228622 0.111726 0.0460054 -0.228717 0.110662 0.0460803 -0.228322 0.11105 0.0459633 -0.228257 0.111828 0.0459854 -0.228374 0.109888 0.046394 -0.228752 0.109688 0.0465949 -0.227924 0.113883 0.0477702 -0.228069 0.113268 0.0467515 -0.228087 0.11398 0.0488521 -0.228414 0.112974 0.050516 -0.228766 0.113364 0.0497692 -0.228869 0.113612 0.0490286 -0.228359 0.113906 0.0489175 -0.228653 0.113441 0.0471397 -0.22914 0.112748 0.0467065 -0.229321 0.111874 0.0463604 -0.228981 0.111807 0.046137 -0.229511 0.109931 0.0468839 -0.229184 0.109789 0.046715 -0.229098 0.110753 0.046191 -0.228346 0.113442 0.0469935 -0.228823 0.112742 0.046488 -0.228493 0.113841 0.0479848 -0.228206 0.113888 0.0478681 -0.22827 0.113622 0.049821 -0.22873 0.112861 0.0503801 -0.229157 0.112984 0.0496384 -0.229255 0.113161 0.0490965 -0.229023 0.11358 0.0482578 -0.228771 0.113738 0.0481167 -0.229212 0.113271 0.0475476 -0.228949 0.113385 0.0473272 -0.229416 0.112705 0.0469852 -0.229458 0.11087 0.0463999 -0.229759 0.111007 0.0467008 -0.23002 0.101006 0.0553356 -0.23002 0.0954677 0.0580569 -0.22969 0.0949916 0.0592434 -0.229376 0.112487 0.0495695 -0.229463 0.112651 0.0491139 -0.229986 0.11154 0.0481762 -0.229885 0.111966 0.0481742 -0.229692 0.111749 0.0490533 -0.229365 0.108572 0.0526658 -0.229692 0.0958253 0.0588828 -0.22772 0.109246 0.0535994 -0.228993 0.0964222 0.0602616 -0.229365 0.0961829 0.0597088 -0.229365 0.100479 0.0576617 -0.229365 0.104615 0.0553099 -0.228993 0.104932 0.0558225 -0.228993 0.108924 0.0531542 -0.228414 0.109162 0.0534834 -0.228414 0.105145 0.056168 -0.228414 0.100945 0.0585557 -0.228993 0.100757 0.0581958 -0.228238 0.113016 0.0505657 -0.22772 0.101011 0.0586826 -0.224773 0.0930347 0.0570664 -0.224773 0.0994821 0.0540608 -0.224773 0.111607 0.0455375 -0.224573 0.10185 0.0584645 -0.224573 0.108675 0.0542517 -0.224773 0.101945 0.0586406 -0.224573 0.118618 0.0408522 -0.222703 0.119547 0.041768 -0.222745 0.119945 0.0419421 -0.222807 0.120655 0.0420649 -0.224573 0.120517 0.0420581 -0.224573 0.121004 0.0420466 -0.222832 0.121004 0.0420466 -0.224573 0.12166 0.0418667 -0.222877 0.121779 0.0418115 -0.224573 0.119945 0.0419422 -0.224573 0.118305 0.0397361 -0.224773 0.118105 0.039742 -0.224573 0.119035 0.0413901 -0.224573 0.119418 0.0416915 -0.224973 0.133151 0.0212215 -0.227743 0.133151 0.0212215 -0.224973 0.132992 0.0222075 -0.230111 0.129442 0.0209129 -0.230023 0.129102 0.0207888 -0.228376 0.12289 0.0311047 -0.229184 0.125888 0.0259569 -0.228376 0.128013 0.0203916 -0.229511 0.128405 0.0205348 -0.229809 0.123529 0.0314898 -0.229184 0.12306 0.0312068 -0.229809 0.126383 0.0261935 -0.230111 0.127082 0.0265279 -0.230111 0.124194 0.03189 -0.23002 0.124902 0.0323168 -0.23002 0.127828 0.0268846 -0.22772 0.12658 0.0352125 -0.224973 0.123836 0.0392017 -0.22772 0.123836 0.0392017 -0.229401 0.121757 0.0393896 -0.228869 0.122274 0.039841 -0.229463 0.122303 0.038876 -0.229157 0.122846 0.0391773 -0.229497 0.122181 0.0388843 -0.229764 0.120824 0.0388005 -0.229939 0.12058 0.0382524 -0.230009 0.121352 0.0376476 -0.230111 0.120803 0.0369495 -0.228346 0.120234 0.0397909 -0.227747 0.123043 0.0399118 -0.229255 0.122315 0.0393866 -0.228766 0.122999 0.0395498 -0.228087 0.12212 0.0402187 -0.228359 0.12218 0.0401407 -0.228206 0.121133 0.0401845 -0.229577 0.121239 0.0391893 -0.229639 0.121767 0.0387827 -0.229023 0.121503 0.0398543 -0.22877 0.121372 0.0400205 -0.228493 0.121246 0.040131 -0.228126 0.119657 0.0392995 -0.228168 0.11945 0.0390075 -0.230023 0.120512 0.0367336 -0.229809 0.12018 0.0364873 -0.229759 0.119797 0.0373763 -0.229511 0.119917 0.0362917 -0.229458 0.119489 0.037258 -0.229184 0.11974 0.0361604 -0.229098 0.119273 0.0371528 -0.228752 0.119614 0.0360669 -0.228717 0.119158 0.0370683 -0.228376 0.119581 0.0360425 -0.228491 0.119536 0.0390835 -0.228823 0.119687 0.0391226 -0.22914 0.119906 0.0391149 -0.229611 0.119818 0.0382895 -0.229821 0.120186 0.0382855 -0.229967 0.120173 0.037497 -0.229321 0.119508 0.0382629 -0.228981 0.119281 0.0382091 -0.228348 0.119126 0.0370293 -0.228622 0.119145 0.0381355 -0.227734 0.123291 0.0397482 -0.228238 0.123774 0.0391551 -0.22827 0.123066 0.039804 -0.228414 0.123722 0.0391164 -0.228653 0.12038 0.0397819 -0.228949 0.120563 0.0397147 -0.229416 0.120181 0.0390557 -0.229212 0.120777 0.0395883 -0.230069 0.120577 0.0376086 -0.227726 0.133118 0.0217217 -0.229741 0.13124 0.0206135 -0.229939 0.130407 0.0200098 -0.230069 0.129869 0.0203617 -0.229986 0.130445 0.0208495 -0.229157 0.132426 0.0213938 -0.228993 0.132476 0.0220193 -0.229445 0.131906 0.0211745 -0.229255 0.132309 0.0208357 -0.229463 0.131876 0.021106 -0.229401 0.132004 0.0203673 -0.229577 0.131552 0.0200446 -0.229023 0.132253 0.0198998 -0.229578 0.131648 0.0208094 -0.22969 0.131375 0.0206509 -0.229611 0.13002 0.0193534 -0.229759 0.129246 0.0198382 -0.229764 0.130999 0.0199121 -0.229821 0.130219 0.0196632 -0.229967 0.129553 0.0200854 -0.228104 0.13095 0.0186877 -0.228491 0.130526 0.0186809 -0.228252 0.129644 0.0187922 -0.228622 0.129521 0.0188764 -0.228349 0.12857 0.019486 -0.228752 0.128051 0.0204056 -0.227834 0.132808 0.0199941 -0.227953 0.132078 0.0191693 -0.228346 0.131501 0.0188742 -0.228046 0.131408 0.0188092 -0.228087 0.132897 0.0202145 -0.22827 0.133071 0.0212328 -0.228869 0.132666 0.0205513 -0.228493 0.132343 0.0195329 -0.22914 0.130756 0.0189727 -0.228823 0.130642 0.0187861 -0.229184 0.128198 0.0204593 -0.228717 0.128637 0.0194734 -0.229098 0.128771 0.0195237 -0.228981 0.129657 0.0189496 -0.228653 0.131574 0.0190011 -0.228206 0.132325 0.0194085 -0.228359 0.132865 0.0203082 -0.228766 0.132822 0.0213168 -0.229376 0.131962 0.0215826 -0.228771 0.132319 0.0196986 -0.228949 0.131619 0.0191915 -0.229212 0.13163 0.0194392 -0.229416 0.130859 0.0192355 -0.229321 0.129827 0.0191095 -0.229458 0.128977 0.0196458 -0.229809 0.128714 0.0206473 -0.23002 0.121467 0.0374424 -0.229938 0.121289 0.0380544 -0.229919 0.121297 0.0381294 -0.229692 0.122189 0.0379789 -0.22969 0.121648 0.038708 -0.229803 0.121432 0.0384784 -0.229365 0.13191 0.0218129 -0.229692 0.131064 0.0215046 -0.23002 0.130219 0.0211962 -0.229885 0.130813 0.0206347 -0.23002 0.12643 0.0296363 -0.229365 0.122912 0.0385153 -0.229399 0.122596 0.0387837 -0.228238 0.132918 0.0221807 -0.22772 0.132992 0.0222075 -0.22772 0.13117 0.0266932 -0.22873 0.132691 0.0220977 -0.22873 0.123579 0.0390108 -0.228993 0.123396 0.0388744 -0.228993 0.126117 0.0349179 -0.229365 0.125609 0.0345947 -0.229365 0.128015 0.0304897 -0.228993 0.128545 0.0307754 -0.229365 0.130119 0.0262217 -0.228993 0.130669 0.0264683 -0.228414 0.128903 0.0309679 -0.228414 0.132857 0.0221584 -0.228414 0.131039 0.0266346 -0.22772 0.129029 0.0310358 -0.228414 0.126459 0.0351357 -0.224773 0.118864 0.0378011 -0.224573 0.118828 0.0381692 -0.224773 0.129087 0.0188258 -0.224573 0.131001 0.0275436 -0.224773 0.131183 0.0276278 -0.224773 0.129184 0.0185306 -0.224573 0.129374 0.0185926 -0.224773 0.129778 0.0175379 -0.224573 0.129923 0.0176762 -0.224573 0.130666 0.0171504 -0.224773 0.130745 0.0169014 -0.224773 0.131892 0.0167472 -0.224773 0.132992 0.0171059 -0.224773 0.133827 0.0179064 -0.224573 0.133938 0.0200804 -0.224573 0.133744 0.0181542 -0.224573 0.13366 0.0180164 -0.224773 0.118671 0.0380445 -0.224773 0.118238 0.038843 -0.224773 0.11891 0.0370844 -0.224773 0.122945 0.0319745 -0.224773 0.124187 0.0284272 -0.224773 0.126466 0.0254389 -0.222899 0.133938 0.0200804 -0.222889 0.134056 0.0193864 -0.224573 0.134034 0.0190167 -0.224573 0.132889 0.0172775 -0.222736 0.133067 0.0173953 -0.222663 0.132399 0.0170546 -0.224573 0.131873 0.0169464 -0.222503 0.130666 0.0171503 -0.222519 0.130858 0.0170732 -0.222575 0.131496 0.0169419 -0.224573 0.130815 0.0170887 -0.224573 0.118427 0.0389063 -0.222482 0.118305 0.0397361 -0.222899 0.122581 0.0411617 -0.224573 0.122581 0.0411617 -0.224573 0.127198 0.0346042 -0.224573 0.126647 0.0255231 -0.224573 0.123115 0.0320797 -0.222426 0.123115 0.0320797 -0.222426 0.118828 0.0381692 -0.220853 0.13194 0.0189345 -0.220978 0.132121 0.0181842 -0.220725 0.131178 0.0185872 -0.220826 0.130853 0.0183219 -0.221131 0.132585 0.0182862 -0.220951 0.131425 0.0179369 -0.220833 0.131626 0.0182772 -0.220691 0.130821 0.0190642 -0.220683 0.130884 0.0190849 -0.221283 0.13263 0.0179695 -0.221652 0.133198 0.0180706 -0.221496 0.132643 0.0176776 -0.221469 0.133333 0.0193872 -0.221564 0.133414 0.0187777 -0.222287 0.133762 0.0183814 -0.22288 0.134046 0.0191221 -0.222448 0.129897 0.0177032 -0.222077 0.129916 0.0177411 -0.222426 0.129374 0.0185926 -0.222606 0.13182 0.0169422 -0.22215 0.130701 0.0171735 -0.222827 0.133777 0.0182145 -0.222559 0.133791 0.0182864 -0.222469 0.133252 0.0175763 -0.222363 0.132494 0.0171165 -0.222721 0.132935 0.0173056 -0.222252 0.131607 0.0169681 -0.222623 0.131995 0.0169606 -0.221904 0.133257 0.0178669 -0.221919 0.131727 0.0170694 -0.221602 0.131847 0.0172523 -0.221791 0.13084 0.0172421 -0.221451 0.131015 0.0173964 -0.221335 0.130262 0.0179021 -0.221618 0.129562 0.0186539 -0.222182 0.133275 0.0177002 -0.222055 0.132571 0.017241 -0.222049 0.129413 0.0186053 -0.221695 0.130052 0.0177869 -0.22123 0.132868 0.0194243 -0.22186 0.133725 0.0192962 -0.221019 0.132428 0.0188983 -0.221391 0.133225 0.0189289 -0.222357 0.133972 0.0192034 -0.221777 0.133572 0.0186318 -0.22176 0.132623 0.0174301 -0.221326 0.131958 0.0175119 -0.221161 0.131216 0.0176338 -0.221035 0.130537 0.0180853 -0.220992 0.130084 0.0188239 -0.222381 0.122519 0.0411129 -0.222049 0.11886 0.0381947 -0.221131 0.120337 0.0410184 -0.221889 0.12233 0.0409619 -0.220691 0.120017 0.0391178 -0.220806 0.120535 0.0399042 -0.220725 0.119816 0.0396789 -0.220878 0.120541 0.0402113 -0.221274 0.120764 0.0411926 -0.221098 0.120958 0.0406574 -0.220981 0.120688 0.0404807 -0.220978 0.119998 0.0406877 -0.221326 0.119346 0.0409212 -0.221161 0.11904 0.0402347 -0.221035 0.119044 0.03942 -0.220833 0.119803 0.0402234 -0.220951 0.119409 0.0402431 -0.220826 0.119415 0.0395534 -0.220778 0.119734 0.0388922 -0.222602 0.118771 0.0410886 -0.222575 0.118616 0.0408484 -0.222541 0.118454 0.0404991 -0.222503 0.118334 0.0400418 -0.222077 0.118415 0.0390905 -0.22244 0.118425 0.0389128 -0.222559 0.121002 0.0420257 -0.222663 0.119207 0.0415409 -0.222641 0.119035 0.0413901 -0.22186 0.121809 0.0414157 -0.221777 0.12117 0.041653 -0.221904 0.120357 0.041811 -0.221335 0.118739 0.0392912 -0.22215 0.118372 0.0400582 -0.221695 0.118528 0.0391788 -0.221791 0.118506 0.0401362 -0.221919 0.11885 0.0409714 -0.222252 0.118699 0.0409272 -0.222363 0.11931 0.0415862 -0.222055 0.119457 0.0415821 -0.222182 0.120228 0.0419173 -0.222469 0.120112 0.0419668 -0.222287 0.121065 0.0419498 -0.222357 0.121867 0.0416723 -0.222206 0.122469 0.0410725 -0.221241 0.121515 0.0405913 -0.221469 0.121669 0.0410378 -0.221391 0.121227 0.0411997 -0.221652 0.120495 0.0416491 -0.221496 0.119861 0.0414019 -0.22176 0.119643 0.0415212 -0.221602 0.119068 0.0409711 -0.221451 0.118731 0.0401976 -0.220992 0.119411 0.0386344 -0.22129 0.119155 0.0384299 -0.221254 0.126074 0.0342315 -0.221626 0.133416 0.0199102 -0.221626 0.130503 0.0273125 -0.221497 0.133269 0.0198626 -0.221626 0.126731 0.0343154 -0.222206 0.130872 0.0274834 -0.222206 0.133802 0.0200361 -0.222382 0.133863 0.0200562 -0.222899 0.131001 0.0275436 -0.222899 0.127198 0.0346042 -0.221626 0.122151 0.0408194 -0.222206 0.127076 0.0345289 -0.221889 0.133633 0.0199811 -0.220781 0.120664 0.0396333 -0.220691 0.124409 0.0328799 -0.220992 0.12375 0.0324721 -0.220781 0.124971 0.0335432 -0.220781 0.125113 0.0333149 -0.220691 0.128028 0.0261636 -0.220778 0.130477 0.0189521 -0.221618 0.118982 0.0382924 -0.220992 0.127324 0.0258372 -0.22129 0.129772 0.0187222 -0.221618 0.126827 0.0256063 -0.221618 0.123283 0.0321837 -0.222426 0.126647 0.0255231 -0.220781 0.131607 0.0193206 -0.220781 0.128891 0.0262669 -0.220939 0.132208 0.0188674 -0.220795 0.13171 0.0191247 -0.221159 0.132755 0.0191389 -0.221056 0.132523 0.0189381 -0.221018 0.132225 0.019522 -0.221254 0.12168 0.0404438 -0.221183 0.121232 0.0406889 -0.220854 0.120525 0.040125 -0.221018 0.121172 0.0400386 -0.221254 0.126218 0.0339986 -0.220781 0.128778 0.0265117 -0.221254 0.129957 0.0270589 -0.221254 0.130072 0.0268092 -0.221254 0.132843 0.0197235 -0.224973 0.132841 0.0200527 -0.224973 0.132141 0.0192168 -0.224773 0.132159 0.0189809 -0.224973 0.130925 0.0186834 -0.224973 0.128013 0.0203916 -0.224773 0.127825 0.0203231 -0.224973 0.128506 0.0195561 -0.224773 0.128537 0.0192351 -0.224773 0.11942 0.0359233 -0.224973 0.119106 0.0371221 -0.224973 0.119107 0.0381269 -0.224973 0.119147 0.0383008 -0.224973 0.119695 0.039345 -0.224773 0.120562 0.0402311 -0.224773 0.123033 0.0401456 -0.224973 0.121978 0.0402584 -0.224773 0.129659 0.0185771 -0.224773 0.130957 0.018486 -0.224773 0.12174 0.0420501 -0.224773 0.120502 0.0422575 -0.224773 0.11931 0.0418603 -0.224773 0.119543 0.0394751 -0.224773 0.118444 0.0409511 -0.224773 0.118954 0.038352 -0.224773 0.134233 0.0189901 -0.224773 0.133017 0.0199586 -0.224773 0.133351 0.0212156 -0.224773 0.134128 0.0201424 -0.224773 0.13318 0.022276 -0.224773 0.127368 0.0347093 -0.224773 0.122737 0.0412864 -0.224773 0.121807 0.0404704 -0.224973 0.119581 0.0360425 -0.228376 0.124363 0.0285221 -0.224973 0.124363 0.0285221 -0.228376 0.12571 0.0258716 -0.224973 0.129029 0.0310358 -0.224773 0.129205 0.0311306 -0.224773 0.123997 0.0393209 -0.224973 0.12294 0.0399685 -0.227819 0.122054 0.0402496 -0.22795 0.120822 0.0401194 -0.224973 0.1218 0.0402705 -0.224973 0.120642 0.040048 -0.228046 0.120128 0.0397494 -0.228251 0.119147 0.0383003 -0.228109 0.119751 0.0394078 -0.228268 0.119107 0.0381272 -0.224973 0.128675 0.01938 -0.228275 0.129422 0.0188797 -0.224973 0.129603 0.0188069 -0.224973 0.129718 0.0187681 -0.228168 0.130416 0.0186509 -0.224973 0.132043 0.0191436 -0.227819 0.132886 0.0201424 -0.222436 0.128482 -0.0229741 -0.224573 0.128869 -0.0225843 -0.222445 0.128657 -0.0227753 -0.224573 0.129506 -0.0222202 -0.222704 0.131615 -0.0224113 -0.222663 0.131241 -0.0222262 -0.222606 0.13067 -0.0220802 -0.22259 0.130511 -0.0220652 -0.222498 0.129441 -0.022246 -0.224573 0.1326 -0.0253377 -0.222899 0.1326 -0.0253377 -0.222877 0.132762 -0.0243184 -0.222822 0.13252 -0.0234033 -0.224573 0.132242 -0.0229645 -0.224573 0.129229 -0.0326151 -0.224573 0.125017 -0.0394396 -0.222899 0.125017 -0.0394396 -0.222426 0.116451 -0.0425057 -0.224573 0.12109 -0.0366791 -0.224573 0.125002 -0.0303418 -0.222426 0.125002 -0.0303418 -0.221497 0.119499 -0.0452442 -0.220853 0.11803 -0.0445565 -0.220833 0.117304 -0.0446137 -0.220725 0.117349 -0.0440707 -0.220781 0.118198 -0.0440754 -0.220683 0.117633 -0.0435674 -0.220691 0.117583 -0.0435227 -0.221035 0.116593 -0.0437667 -0.220992 0.117006 -0.0430045 -0.221131 0.117791 -0.0454392 -0.220978 0.117471 -0.0450891 -0.220951 0.116909 -0.0446101 -0.220826 0.116956 -0.0439218 -0.221652 0.117911 -0.0460779 -0.221496 0.117293 -0.0457942 -0.221159 0.118615 -0.0451602 -0.222675 0.116723 -0.0459722 -0.222784 0.117768 -0.0464637 -0.222832 0.118395 -0.0465046 -0.22288 0.119246 -0.0462872 -0.222357 0.119279 -0.0461818 -0.222899 0.120021 -0.0457139 -0.22215 0.115886 -0.0443645 -0.222077 0.115985 -0.0434008 -0.222482 0.115837 -0.0440392 -0.222641 0.116469 -0.0457333 -0.222563 0.116028 -0.0450492 -0.222498 0.115842 -0.0442757 -0.221904 0.117764 -0.0462314 -0.222055 0.116879 -0.0459504 -0.221602 0.116527 -0.0453175 -0.221791 0.116014 -0.0444503 -0.221695 0.116092 -0.0434956 -0.221451 0.116236 -0.0445248 -0.221335 0.116297 -0.0436202 -0.222469 0.11751 -0.0463726 -0.222182 0.117629 -0.0463299 -0.222363 0.116733 -0.0459459 -0.222252 0.116161 -0.045252 -0.221919 0.116309 -0.045305 -0.222049 0.116482 -0.0425331 -0.22123 0.118919 -0.0451159 -0.221626 0.119613 -0.045347 -0.221469 0.119119 -0.0455368 -0.22186 0.119236 -0.0459222 -0.222206 0.119915 -0.0456183 -0.221056 0.118325 -0.0450602 -0.221391 0.118668 -0.0456722 -0.221283 0.117539 -0.0456366 -0.221777 0.118584 -0.0461214 -0.221564 0.118632 -0.0459121 -0.222865 0.11893 -0.0464076 -0.222559 0.118394 -0.0464835 -0.222287 0.118462 -0.0464115 -0.22176 0.117069 -0.0459005 -0.221326 0.116807 -0.045284 -0.221161 0.116542 -0.04458 -0.22129 0.116762 -0.0427852 -0.220725 0.129933 -0.0236846 -0.220854 0.130674 -0.0240756 -0.221254 0.131528 -0.024917 -0.221496 0.131448 -0.0228625 -0.221274 0.131719 -0.0237495 -0.221098 0.131352 -0.0241847 -0.221131 0.131354 -0.0234667 -0.220951 0.130218 -0.0230501 -0.220826 0.129624 -0.0234005 -0.221035 0.129323 -0.0231457 -0.220981 0.131064 -0.024039 -0.220978 0.130898 -0.023338 -0.220833 0.130399 -0.0234016 -0.222077 0.128723 -0.0227655 -0.22215 0.12954 -0.0222452 -0.222252 0.130456 -0.0220936 -0.222049 0.12817 -0.0235988 -0.222426 0.128132 -0.0235839 -0.222751 0.132011 -0.0227135 -0.222807 0.132421 -0.0232214 -0.222363 0.131332 -0.0222936 -0.222469 0.132063 -0.0227971 -0.222721 0.131762 -0.0225087 -0.222827 0.13255 -0.0234658 -0.222381 0.132527 -0.0253092 -0.222357 0.132685 -0.0244646 -0.221626 0.132089 -0.0251371 -0.22186 0.132434 -0.0245427 -0.221469 0.132037 -0.0246103 -0.221777 0.13232 -0.0238702 -0.221904 0.13205 -0.0230876 -0.22176 0.131442 -0.0226142 -0.222055 0.131402 -0.0224224 -0.221602 0.130679 -0.0223914 -0.221695 0.128856 -0.0228192 -0.221791 0.129674 -0.0223219 -0.221919 0.13057 -0.0222018 -0.222182 0.132078 -0.0229222 -0.222287 0.132525 -0.0236315 -0.222559 0.132559 -0.0235384 -0.221241 0.131573 -0.0247005 -0.221391 0.131956 -0.0241463 -0.221652 0.131979 -0.0232875 -0.221326 0.130774 -0.0226571 -0.221161 0.130027 -0.0227352 -0.221451 0.12984 -0.0224863 -0.220992 0.128826 -0.0238565 -0.221335 0.129059 -0.0229466 -0.221254 0.128345 -0.031828 -0.221254 0.119165 -0.0449443 -0.221254 0.124075 -0.0387774 -0.221626 0.128746 -0.0323551 -0.221889 0.119783 -0.0454998 -0.222382 0.119963 -0.0456617 -0.222899 0.129229 -0.0326151 -0.221889 0.132301 -0.0252206 -0.222206 0.132467 -0.0252855 -0.222206 0.129103 -0.0325474 -0.222206 0.1249 -0.0393573 -0.221626 0.124567 -0.0391238 -0.220691 0.129548 -0.0241398 -0.220691 0.122335 -0.0375542 -0.220691 0.126342 -0.0310625 -0.22129 0.128521 -0.0237367 -0.220778 0.129211 -0.0240076 -0.221618 0.125176 -0.0304355 -0.220778 0.117314 -0.0432808 -0.220992 0.1217 -0.0371083 -0.221618 0.116598 -0.0426379 -0.221618 0.128316 -0.0236561 -0.220992 0.125659 -0.0306952 -0.221618 0.121252 -0.0367929 -0.222426 0.12109 -0.0366791 -0.220781 0.122856 -0.03825 -0.220939 0.118106 -0.0448227 -0.220795 0.11808 -0.0442623 -0.221018 0.118682 -0.0445099 -0.221019 0.118243 -0.0449977 -0.221183 0.131517 -0.0244074 -0.220806 0.130488 -0.0241953 -0.220878 0.130757 -0.024047 -0.220781 0.130318 -0.024442 -0.220781 0.127197 -0.0312171 -0.221018 0.130923 -0.0246795 -0.220781 0.12707 -0.0314541 -0.220781 0.123011 -0.0380298 -0.221254 0.128215 -0.0320698 -0.221254 0.123916 -0.039002 -0.224573 0.116008 -0.043218 -0.22244 0.116006 -0.0432238 -0.228083 0.129871 -0.0238175 -0.228046 0.130151 -0.0239203 -0.224973 0.129674 -0.0237658 -0.224973 0.130764 -0.024291 -0.224973 0.130857 -0.0243698 -0.2278 0.131623 -0.025546 -0.227743 0.131747 -0.0264305 -0.228275 0.128162 -0.0238733 -0.224973 0.127388 -0.0243287 -0.228348 0.127294 -0.0244121 -0.224973 0.126667 -0.0252996 -0.224773 0.127259 -0.024176 -0.224973 0.128347 -0.0238112 -0.224973 0.128465 -0.0237793 -0.224773 0.130889 -0.0241354 -0.224973 0.131506 -0.0252455 -0.224773 0.131688 -0.0251619 -0.224973 0.119295 -0.0447784 -0.224973 0.118152 -0.0444881 -0.224773 0.117089 -0.0438515 -0.224973 0.116733 -0.04248 -0.224773 0.116597 -0.0414277 -0.224773 0.116566 -0.0426957 -0.224973 0.131747 -0.0264305 -0.224773 0.132937 -0.0240734 -0.224773 0.132399 -0.0228398 -0.224773 0.129718 -0.0235706 -0.224773 0.128417 -0.0235851 -0.224773 0.116302 -0.042372 -0.224773 0.115823 -0.0431436 -0.224773 0.116716 -0.0462189 -0.224773 0.118061 -0.0446661 -0.224773 0.11929 -0.0449783 -0.224773 0.120533 -0.0447262 -0.224773 0.12017 -0.0458476 -0.224773 0.121544 -0.0439597 -0.224773 0.12518 -0.0395546 -0.224773 0.131947 -0.0264364 -0.224773 0.117175 -0.0402986 -0.224973 0.117328 -0.0404271 -0.224773 0.122375 -0.0330961 -0.228376 0.124045 -0.0306345 -0.224973 0.122545 -0.0332012 -0.228376 0.117328 -0.0404271 -0.228376 0.120923 -0.0356926 -0.224973 0.13153 -0.0274054 -0.224773 0.127225 -0.0360902 -0.224773 0.131714 -0.0274849 -0.22772 0.13153 -0.0274054 -0.227726 0.131686 -0.0269253 -0.228362 0.116925 -0.0410832 -0.224973 0.116791 -0.0414769 -0.224973 0.116762 -0.0426559 -0.228168 0.117022 -0.0433785 -0.228142 0.117136 -0.0435716 -0.224973 0.117248 -0.0437306 -0.227966 0.118205 -0.0445145 -0.224973 0.120451 -0.044544 -0.227819 0.119549 -0.0447724 -0.227826 0.119473 -0.0447767 -0.224973 0.119473 -0.0447767 -0.227842 0.119295 -0.0447784 -0.230111 0.122177 -0.0365533 -0.230111 0.118495 -0.0414044 -0.229184 0.124218 -0.0307301 -0.228376 0.122545 -0.0332012 -0.229184 0.121086 -0.0358045 -0.229809 0.124698 -0.0309955 -0.228752 0.11736 -0.0404534 -0.229809 0.121538 -0.0361147 -0.23002 0.128822 -0.0262327 -0.230111 0.128063 -0.0259042 -0.230111 0.125377 -0.0313705 -0.23002 0.124543 -0.0344344 -0.23002 0.119128 -0.0419355 -0.22772 0.124364 -0.0400105 -0.224973 0.121391 -0.0438313 -0.224973 0.127055 -0.0359851 -0.22772 0.127055 -0.0359851 -0.22772 0.129448 -0.0317761 -0.229764 0.129677 -0.0249968 -0.229463 0.130481 -0.0262401 -0.229255 0.13093 -0.0259957 -0.230009 0.128942 -0.0260307 -0.229938 0.129263 -0.0257727 -0.229939 0.12908 -0.0250595 -0.229919 0.129332 -0.0257428 -0.230023 0.127731 -0.0257602 -0.229809 0.127351 -0.0255961 -0.229821 0.128912 -0.0247023 -0.229967 0.128222 -0.0250848 -0.230069 0.128521 -0.0253792 -0.229157 0.131014 -0.0265597 -0.229416 0.129576 -0.0243131 -0.229212 0.130335 -0.0245623 -0.229577 0.130221 -0.0251618 -0.227928 0.130954 -0.0244605 -0.228087 0.131553 -0.02541 -0.22969 0.130008 -0.0257566 -0.229401 0.130653 -0.0255106 -0.228376 0.126667 -0.0252996 -0.228752 0.126704 -0.0253159 -0.228717 0.127343 -0.02442 -0.228253 0.128388 -0.0237996 -0.227944 0.130857 -0.0243697 -0.228491 0.129278 -0.0237399 -0.228111 0.129647 -0.0237599 -0.228168 0.129169 -0.0237034 -0.228493 0.13104 -0.0246978 -0.22877 0.131007 -0.0248617 -0.228653 0.130304 -0.0241217 -0.228823 0.129387 -0.0238518 -0.228981 0.128393 -0.0239569 -0.22914 0.12949 -0.0240447 -0.229458 0.127673 -0.0246122 -0.229184 0.126848 -0.0253782 -0.229511 0.12705 -0.0254657 -0.228206 0.13103 -0.0245725 -0.228346 0.130239 -0.0239907 -0.228622 0.128261 -0.0238759 -0.229098 0.127474 -0.0244781 -0.228238 0.131459 -0.0273743 -0.228766 0.131413 -0.0265059 -0.22873 0.131236 -0.0272781 -0.229399 0.130548 -0.0265399 -0.22827 0.131667 -0.0264367 -0.228359 0.131516 -0.0255017 -0.228869 0.131303 -0.0257327 -0.229023 0.130929 -0.0250587 -0.228949 0.130338 -0.0243144 -0.229321 0.128553 -0.0241266 -0.229611 0.128731 -0.0243813 -0.229759 0.12793 -0.02482 -0.227748 0.120536 -0.0445036 -0.22772 0.121391 -0.0438313 -0.228766 0.120534 -0.0441293 -0.229986 0.118941 -0.0423045 -0.230069 0.118231 -0.0420494 -0.229365 0.120508 -0.0430917 -0.229463 0.119879 -0.0434158 -0.229577 0.118797 -0.0436656 -0.229401 0.119303 -0.0438963 -0.229212 0.118313 -0.0440365 -0.229255 0.119861 -0.0439263 -0.22969 0.119234 -0.0432093 -0.229764 0.118406 -0.043253 -0.229416 0.11775 -0.0434698 -0.229611 0.117433 -0.0426843 -0.229759 0.117466 -0.0417717 -0.230023 0.118217 -0.0411717 -0.229821 0.117801 -0.0427019 -0.229939 0.118195 -0.042692 -0.229967 0.117833 -0.0419142 -0.228349 0.116822 -0.0413639 -0.228275 0.116724 -0.0424035 -0.228717 0.116845 -0.0414266 -0.228087 0.119617 -0.0447454 -0.228046 0.117656 -0.0441589 -0.227983 0.118077 -0.0444484 -0.228206 0.118633 -0.044653 -0.227924 0.118535 -0.0446477 -0.228238 0.121331 -0.0437811 -0.228414 0.121281 -0.0437393 -0.228869 0.119794 -0.0443775 -0.228359 0.119682 -0.0446712 -0.228493 0.11875 -0.0446063 -0.228949 0.118092 -0.0441501 -0.228823 0.117253 -0.0435074 -0.229321 0.117125 -0.0426395 -0.229458 0.117165 -0.0416354 -0.229511 0.117649 -0.0406956 -0.229184 0.11748 -0.0405541 -0.229098 0.116956 -0.0415178 -0.228981 0.116902 -0.0425724 -0.228622 0.11677 -0.0424909 -0.228491 0.117104 -0.0434594 -0.228346 0.117758 -0.0442066 -0.228653 0.117905 -0.0442062 -0.22827 0.120586 -0.044387 -0.229157 0.120403 -0.0437485 -0.229023 0.119023 -0.0443453 -0.228771 0.118882 -0.0445034 -0.22914 0.117471 -0.0435126 -0.229809 0.1179 -0.0409064 -0.23002 0.126101 -0.0317705 -0.229692 0.129648 -0.0265903 -0.229497 0.130428 -0.0261308 -0.229639 0.130133 -0.0258224 -0.229803 0.129702 -0.0256845 -0.229692 0.119818 -0.0425136 -0.229376 0.120334 -0.0432515 -0.229445 0.119953 -0.0434071 -0.229578 0.119508 -0.0433662 -0.229885 0.118939 -0.0427307 -0.229741 0.119134 -0.0431109 -0.23002 0.122859 -0.037021 -0.229365 0.126075 -0.0353803 -0.229365 0.128427 -0.0312436 -0.228414 0.124248 -0.0399268 -0.228414 0.129321 -0.0317099 -0.228993 0.131026 -0.0271872 -0.229365 0.130474 -0.0269479 -0.229365 0.123431 -0.0393366 -0.228993 0.12097 -0.0434786 -0.22873 0.121145 -0.0436255 -0.228993 0.123919 -0.0396891 -0.228993 0.126587 -0.0356967 -0.228414 0.126933 -0.03591 -0.228993 0.128961 -0.0315222 -0.228414 0.131399 -0.0273485 -0.224773 0.127831 -0.0237997 -0.224773 0.124826 -0.0302471 -0.224773 0.11651 -0.0421404 -0.224573 0.116451 -0.0425057 -0.224773 0.132786 -0.0254108 -0.224773 0.129406 -0.0327099 -0.224773 0.115637 -0.0440333 -0.224573 0.115941 -0.0448093 -0.224773 0.115905 -0.0452602 -0.224573 0.116833 -0.0460566 -0.224573 0.118396 -0.0465045 -0.224773 0.11913 -0.0465513 -0.224773 0.117882 -0.0466855 -0.224573 0.131762 -0.0225087 -0.224573 0.132739 -0.0241032 -0.224573 0.13252 -0.0234035 -0.224773 0.131316 -0.0220406 -0.224573 0.131243 -0.0222268 -0.224573 0.13067 -0.0220802 -0.224773 0.129978 -0.0218898 -0.224573 0.128132 -0.0235839 -0.224773 0.127946 -0.0235108 -0.224773 0.128745 -0.0224279 -0.224573 0.130008 -0.0220876 -0.224773 0.126483 -0.0252201 -0.224773 0.120926 -0.0365641 -0.222663 0.116632 -0.0458947 -0.224573 0.116469 -0.0457333 -0.222745 0.117344 -0.0463379 -0.224573 0.117344 -0.046338 -0.224573 0.117909 -0.0464874 -0.224573 0.119061 -0.0463635 -0.224573 0.120021 -0.0457139 -0.222898 0.119896 -0.0458438 -0.224573 0.116084 -0.0451718 -0.224573 0.115837 -0.0440392 -0.230009 0.108413 -0.0521169 -0.229938 0.108819 -0.0520538 -0.229463 0.109641 -0.0530678 -0.229692 0.108744 -0.0529543 -0.229741 0.0913784 -0.0620047 -0.22969 0.0914159 -0.06214 -0.229445 0.0919394 -0.0626706 -0.229692 0.0922695 -0.0618295 -0.229365 0.0969866 -0.0608843 -0.229365 0.10536 -0.0563735 -0.229365 0.10928 -0.0536769 -0.228238 0.10992 -0.0545387 -0.228414 0.105901 -0.0572244 -0.228993 0.109639 -0.0541606 -0.228993 0.105683 -0.0568819 -0.228993 0.10154 -0.0593105 -0.229365 0.101255 -0.0587802 -0.229365 0.0925779 -0.062675 -0.22873 0.0928626 -0.0634558 -0.228993 0.0972333 -0.0614339 -0.22873 0.109776 -0.0543443 -0.228238 0.0929456 -0.0636834 -0.228414 0.0973995 -0.0618043 -0.228414 0.101733 -0.0596679 -0.224773 0.102739 -0.0537101 -0.224573 0.102845 -0.0538802 -0.224573 0.096288 -0.0574125 -0.224573 0.0893575 -0.0601391 -0.224773 0.112051 -0.0535019 -0.224573 0.105369 -0.0579628 -0.224573 0.0983085 -0.0617665 -0.224773 0.0983927 -0.0619479 -0.224573 0.0897103 -0.0647888 -0.224773 0.0909074 -0.0648928 -0.224573 0.0886633 -0.0643423 -0.224573 0.111927 -0.0495928 -0.224773 0.109852 -0.0489342 -0.224773 0.111009 -0.0489343 -0.224573 0.110806 -0.0490986 -0.224773 0.107846 -0.0496754 -0.224773 0.0962038 -0.0572311 -0.224773 0.090023 -0.0592785 -0.224573 0.0890969 -0.0646006 -0.2228 0.0886742 -0.0643504 -0.222836 0.0890966 -0.0646004 -0.224573 0.0882933 -0.063999 -0.224573 0.0879397 -0.0634635 -0.222685 0.0878958 -0.0633669 -0.224573 0.0878059 -0.0631214 -0.222426 0.108934 -0.0495926 -0.224573 0.108934 -0.0495926 -0.224573 0.109896 -0.0491292 -0.222498 0.110737 -0.0490887 -0.224573 0.110965 -0.0491293 -0.222606 0.111884 -0.0495597 -0.222663 0.112306 -0.0499716 -0.222704 0.112537 -0.0503186 -0.222721 0.112615 -0.0504765 -0.222899 0.111927 -0.0533455 -0.224573 0.112593 -0.0525105 -0.222877 0.112576 -0.0525436 -0.224573 0.112825 -0.0516306 -0.222807 0.11283 -0.0514233 -0.224573 0.11283 -0.0514692 -0.224573 0.112593 -0.0504279 -0.222751 0.112729 -0.0507785 -0.222899 0.105369 -0.0579628 -0.224573 0.111927 -0.0533455 -0.224573 0.0908454 -0.0647027 -0.222426 0.0893575 -0.0601391 -0.222426 0.096288 -0.0574125 -0.222426 0.102845 -0.0538802 -0.221497 0.0906275 -0.0640344 -0.221469 0.0901521 -0.0640979 -0.220795 0.0898897 -0.0624747 -0.220781 0.0900855 -0.062372 -0.221161 0.0883987 -0.0619807 -0.220951 0.0887019 -0.0621905 -0.220992 0.0895888 -0.0608486 -0.221131 0.0890511 -0.0633495 -0.220978 0.0889492 -0.0628864 -0.220826 0.0890868 -0.061618 -0.220833 0.0890421 -0.0623911 -0.220725 0.0893522 -0.0619431 -0.220691 0.0898292 -0.0615857 -0.220683 0.0898499 -0.0616493 -0.221283 0.0887344 -0.0633947 -0.221496 0.0884425 -0.0634081 -0.221056 0.089703 -0.0632882 -0.221159 0.0899038 -0.0635197 -0.221564 0.0895426 -0.0641793 -0.222469 0.0883412 -0.0640174 -0.222794 0.08861 -0.0643012 -0.222756 0.0882931 -0.0639988 -0.222382 0.0908211 -0.0646283 -0.222899 0.0908454 -0.0647027 -0.222049 0.0893702 -0.0601781 -0.222077 0.0885061 -0.0606811 -0.22215 0.0879384 -0.0614661 -0.222663 0.0878195 -0.0631645 -0.222583 0.0877025 -0.0623502 -0.222519 0.0878375 -0.0616243 -0.222498 0.087945 -0.0613674 -0.222287 0.0891464 -0.0645272 -0.221904 0.0886318 -0.0640222 -0.221919 0.0878344 -0.062492 -0.221602 0.0880172 -0.062612 -0.221791 0.088007 -0.0616048 -0.221451 0.0881613 -0.06178 -0.221335 0.088667 -0.0610274 -0.222182 0.0884652 -0.0640397 -0.222363 0.0878815 -0.0632593 -0.222252 0.087733 -0.0623724 -0.222055 0.088006 -0.0633364 -0.221695 0.0885518 -0.0608169 -0.221626 0.0906752 -0.0641806 -0.221019 0.0896632 -0.0631931 -0.221391 0.0896938 -0.0639897 -0.22186 0.0900612 -0.0644904 -0.222357 0.0899683 -0.0647366 -0.222874 0.0897442 -0.0647942 -0.222559 0.0890514 -0.0645555 -0.221777 0.0893967 -0.0643368 -0.22176 0.088195 -0.0633879 -0.221652 0.0888356 -0.0639625 -0.221326 0.0882768 -0.0627232 -0.221035 0.0888502 -0.0613023 -0.22129 0.0894872 -0.0605367 -0.220781 0.110398 -0.0514288 -0.220806 0.110669 -0.0513003 -0.220854 0.11089 -0.0512896 -0.220878 0.110976 -0.0513064 -0.221626 0.111584 -0.0529162 -0.221241 0.111356 -0.0522803 -0.221274 0.111958 -0.0515294 -0.221183 0.111454 -0.0519982 -0.221098 0.111422 -0.051723 -0.221131 0.111783 -0.0511023 -0.221391 0.111965 -0.0519917 -0.221326 0.111686 -0.0501113 -0.221161 0.111 -0.0498051 -0.220978 0.111453 -0.0507627 -0.220833 0.110988 -0.0505682 -0.220951 0.111008 -0.0501736 -0.220826 0.110318 -0.0501801 -0.220725 0.110444 -0.0505806 -0.222436 0.109542 -0.0492395 -0.222445 0.109793 -0.0491551 -0.22259 0.111754 -0.0494668 -0.222252 0.111692 -0.0494642 -0.222469 0.112732 -0.0508767 -0.222822 0.112825 -0.0516305 -0.222559 0.112791 -0.0517666 -0.222827 0.112819 -0.0516994 -0.22186 0.112181 -0.0525741 -0.221777 0.112418 -0.0519347 -0.222182 0.112682 -0.0509925 -0.22176 0.112286 -0.0504082 -0.221602 0.111736 -0.0498333 -0.221451 0.110963 -0.0494963 -0.221695 0.109944 -0.0492926 -0.221335 0.110056 -0.0495045 -0.222077 0.109855 -0.0491796 -0.22215 0.110823 -0.0491375 -0.221791 0.110901 -0.0492711 -0.222363 0.112351 -0.0500755 -0.221919 0.111736 -0.0496146 -0.222055 0.112347 -0.0502219 -0.222357 0.112437 -0.0526321 -0.222287 0.112715 -0.0518304 -0.221469 0.111803 -0.0524341 -0.221652 0.112414 -0.0512596 -0.221904 0.112576 -0.0511221 -0.221496 0.112167 -0.0506261 -0.221035 0.110185 -0.0498088 -0.221254 0.0975741 -0.0608373 -0.221626 0.0980774 -0.0612684 -0.221254 0.104763 -0.0569834 -0.222206 0.090801 -0.0645666 -0.221889 0.090746 -0.064398 -0.222899 0.0983085 -0.0617665 -0.221626 0.10508 -0.0574958 -0.222206 0.105294 -0.057841 -0.221889 0.111727 -0.053095 -0.222206 0.111837 -0.0532336 -0.222206 0.0982483 -0.0616367 -0.222381 0.111878 -0.0532844 -0.222049 0.10896 -0.0496246 -0.221618 0.109057 -0.0497472 -0.220781 0.10408 -0.0558777 -0.220781 0.0970318 -0.0596558 -0.220992 0.103237 -0.0545149 -0.220691 0.0969285 -0.0587927 -0.220778 0.089717 -0.0612417 -0.22129 0.109195 -0.0499196 -0.220992 0.109399 -0.050176 -0.220691 0.103645 -0.0551744 -0.220778 0.109657 -0.0504994 -0.220691 0.109883 -0.0507823 -0.221618 0.102949 -0.0540484 -0.220992 0.0966021 -0.0580894 -0.221618 0.0963712 -0.0575919 -0.221618 0.0894188 -0.0603271 -0.221018 0.090287 -0.06299 -0.220939 0.0896323 -0.0629732 -0.220853 0.0896995 -0.0627046 -0.22123 0.0901892 -0.0636333 -0.221254 0.111209 -0.0524453 -0.221254 0.104996 -0.0568387 -0.221018 0.110804 -0.051937 -0.220981 0.111246 -0.0514527 -0.220781 0.104308 -0.0557359 -0.220781 0.0972766 -0.0595428 -0.221254 0.0978238 -0.060722 -0.221254 0.0904884 -0.0636079 -0.224573 0.0877025 -0.0623502 -0.224573 0.0879282 -0.0614026 -0.222448 0.0884682 -0.0606624 -0.224573 0.0885119 -0.0606227 -0.222443 0.088549 -0.0605907 -0.224773 0.0875026 -0.0623443 -0.224973 0.111036 -0.0525517 -0.228046 0.110514 -0.0508934 -0.228252 0.109054 -0.049909 -0.224973 0.107884 -0.0498718 -0.228348 0.107794 -0.0498909 -0.228376 0.106807 -0.0503459 -0.224773 0.108566 -0.0496293 -0.224973 0.110809 -0.0513972 -0.224773 0.111236 -0.0525576 -0.224773 0.110991 -0.0513159 -0.224773 0.110233 -0.0503026 -0.224973 0.110104 -0.0504549 -0.224973 0.10906 -0.0499107 -0.224973 0.0908394 -0.063617 -0.224973 0.0906841 -0.0635293 -0.224773 0.0896714 -0.062815 -0.224973 0.0895519 -0.0604248 -0.224973 0.0896143 -0.0602577 -0.224773 0.091088 -0.0585897 -0.224773 0.110914 -0.0537918 -0.224773 0.108809 -0.0494362 -0.224773 0.112773 -0.0525973 -0.224773 0.11303 -0.0514692 -0.224773 0.112773 -0.0503411 -0.224773 0.112052 -0.0494364 -0.224773 0.109111 -0.0497173 -0.224773 0.0895907 -0.0598519 -0.224773 0.0892955 -0.059949 -0.224773 0.0893623 -0.0603612 -0.224773 0.0883795 -0.0604729 -0.224773 0.0877471 -0.0613177 -0.224773 0.0892368 -0.0616234 -0.224773 0.0877596 -0.0635504 -0.224773 0.0885434 -0.0645024 -0.224773 0.0896777 -0.0649861 -0.224773 0.0905799 -0.0637 -0.224773 0.0917825 -0.0641032 -0.224773 0.0930409 -0.0639447 -0.224773 0.101896 -0.05997 -0.224773 0.105474 -0.0581329 -0.224773 0.110086 -0.054762 -0.224973 0.0911565 -0.0587776 -0.224973 0.099287 -0.0551279 -0.224773 0.0991921 -0.0549519 -0.224973 0.106807 -0.0503459 -0.224773 0.106688 -0.0501853 -0.228376 0.0911565 -0.0587776 -0.224973 0.0929724 -0.0637568 -0.224973 0.101801 -0.0597939 -0.224973 0.109967 -0.0546015 -0.227747 0.110677 -0.0538078 -0.227757 0.11077 -0.0536327 -0.227819 0.111015 -0.0528186 -0.224973 0.110737 -0.0536993 -0.227844 0.111036 -0.0525517 -0.228362 0.0904788 -0.0591439 -0.228349 0.0902499 -0.0593359 -0.224973 0.0901662 -0.0594181 -0.228046 0.0895741 -0.0621731 -0.224973 0.0894352 -0.0615984 -0.227983 0.0897945 -0.0626347 -0.224973 0.0898393 -0.0627063 -0.224973 0.0918023 -0.0639042 -0.227748 0.0918964 -0.0639119 -0.227819 0.0909073 -0.0636512 -0.227826 0.0908391 -0.0636169 -0.227966 0.0898721 -0.0627557 -0.230111 0.0916778 -0.0602071 -0.230023 0.0915537 -0.0598668 -0.229184 0.0967218 -0.0566529 -0.229184 0.101972 -0.0538247 -0.228376 0.10187 -0.0536553 -0.228376 0.099287 -0.0551279 -0.228376 0.0966365 -0.0564746 -0.229809 0.107252 -0.0509451 -0.229809 0.102255 -0.0542945 -0.229511 0.107057 -0.0506816 -0.229184 0.0912243 -0.0589633 -0.229809 0.0969584 -0.0571478 -0.230111 0.107714 -0.0515677 -0.229809 0.0914122 -0.0594787 -0.230111 0.102655 -0.0549586 -0.23002 0.103082 -0.0556669 -0.23002 0.100401 -0.0571953 -0.230111 0.0972928 -0.0578473 -0.23002 0.0976496 -0.0585934 -0.23002 0.0919612 -0.060984 -0.22772 0.0929724 -0.0637568 -0.22772 0.0974581 -0.0619348 -0.22772 0.105977 -0.0573452 -0.22772 0.101801 -0.0597939 -0.228491 0.109848 -0.0503007 -0.228275 0.108816 -0.0498586 -0.229497 0.109649 -0.0529465 -0.229939 0.109017 -0.0513445 -0.229919 0.108894 -0.0520625 -0.229764 0.109565 -0.0515886 -0.229577 0.109954 -0.0520036 -0.23002 0.108207 -0.0522316 -0.228206 0.110949 -0.0518977 -0.22772 0.109967 -0.0546015 -0.228087 0.110984 -0.0528846 -0.228493 0.110896 -0.0520115 -0.22877 0.110785 -0.052137 -0.22827 0.110569 -0.0538306 -0.228359 0.110906 -0.0529454 -0.228869 0.110606 -0.0530391 -0.229023 0.110619 -0.0522685 -0.229212 0.110353 -0.0515417 -0.22811 0.110161 -0.050505 -0.230023 0.107498 -0.0512768 -0.229759 0.108141 -0.0505622 -0.229184 0.106925 -0.0505047 -0.228752 0.106832 -0.0503788 -0.228717 0.107833 -0.0499226 -0.228168 0.109772 -0.0502147 -0.228622 0.1089 -0.0499103 -0.228823 0.109888 -0.0504524 -0.22914 0.10988 -0.0506707 -0.229321 0.109028 -0.0502734 -0.229416 0.109821 -0.0509464 -0.229967 0.108262 -0.0509376 -0.229611 0.109054 -0.0505829 -0.229458 0.108023 -0.0502539 -0.229098 0.107918 -0.0500384 -0.228981 0.108974 -0.0500464 -0.229157 0.109942 -0.0536108 -0.229399 0.109549 -0.0533607 -0.229803 0.109243 -0.0521967 -0.22969 0.109473 -0.0524126 -0.229639 0.109548 -0.0525316 -0.229401 0.110155 -0.052522 -0.229255 0.110151 -0.0530804 -0.228766 0.110315 -0.0537638 -0.228414 0.109881 -0.0544865 -0.227953 0.110876 -0.0515628 -0.228346 0.110556 -0.0509987 -0.228653 0.110547 -0.0511447 -0.228949 0.11048 -0.0513284 -0.229821 0.10905 -0.0509512 -0.230069 0.108374 -0.051342 -0.229885 0.0913996 -0.061578 -0.229939 0.0907748 -0.0611725 -0.229986 0.0916144 -0.0612099 -0.229401 0.0911322 -0.0627695 -0.229463 0.0918709 -0.0626412 -0.229578 0.0915744 -0.0624126 -0.229212 0.0902041 -0.0623955 -0.229577 0.0908095 -0.0623167 -0.229764 0.0906771 -0.0617639 -0.229967 0.0908503 -0.0603179 -0.229759 0.0906032 -0.0600107 -0.229821 0.0904281 -0.0609837 -0.230069 0.0911266 -0.0606336 -0.228275 0.0896446 -0.0601869 -0.228622 0.0896413 -0.0602859 -0.228491 0.0894459 -0.0612913 -0.228168 0.0894159 -0.0611806 -0.228346 0.0896391 -0.0622658 -0.228752 0.0911706 -0.0588161 -0.227842 0.090684 -0.0635292 -0.228142 0.089418 -0.0614048 -0.227924 0.0900913 -0.0630361 -0.22827 0.0919977 -0.0638358 -0.228993 0.0927843 -0.063241 -0.228869 0.0913162 -0.0634313 -0.228771 0.0904635 -0.0630844 -0.228359 0.0910731 -0.0636301 -0.228493 0.0902978 -0.0631076 -0.228653 0.089766 -0.0623385 -0.228823 0.089551 -0.0614075 -0.22914 0.0897376 -0.0615212 -0.229321 0.0898745 -0.0605921 -0.229458 0.0904108 -0.0597422 -0.229098 0.0902886 -0.0595359 -0.229511 0.0912997 -0.0591703 -0.228717 0.0902384 -0.0594016 -0.228981 0.0897145 -0.0604222 -0.228206 0.0901734 -0.0630896 -0.228087 0.0909794 -0.0636617 -0.228766 0.0920817 -0.0635867 -0.228414 0.0929234 -0.0636223 -0.229157 0.0921587 -0.0631915 -0.229376 0.0923476 -0.0627266 -0.229255 0.0916006 -0.0630745 -0.229023 0.0906647 -0.063018 -0.228949 0.0899564 -0.0623836 -0.229416 0.0900004 -0.0616235 -0.229611 0.0901183 -0.0607846 -0.221496 0.081587 -0.0650294 -0.220806 0.0799528 -0.0648644 -0.220854 0.0801494 -0.0649656 -0.221469 0.0803677 -0.0664131 -0.221183 0.0802834 -0.0658611 -0.221098 0.0803938 -0.0656071 -0.221274 0.0809541 -0.0657071 -0.220978 0.0809001 -0.0647906 -0.221131 0.0810167 -0.0652501 -0.221326 0.081428 -0.0643432 -0.220951 0.0808096 -0.0640582 -0.220826 0.0802092 -0.0637189 -0.221035 0.0802792 -0.0633307 -0.220833 0.0805953 -0.06439 -0.220725 0.0801176 -0.0641285 -0.220778 0.0794769 -0.0636649 -0.22259 0.0818088 -0.0638188 -0.222252 0.0817568 -0.0637858 -0.222606 0.0818756 -0.0639646 -0.222049 0.0793102 -0.0625585 -0.222077 0.0803085 -0.062621 -0.222559 0.0815569 -0.066329 -0.222822 0.0816547 -0.0662283 -0.222363 0.0820219 -0.0646447 -0.222663 0.0820346 -0.0645321 -0.222827 0.0816154 -0.0662852 -0.222357 0.0808182 -0.0669018 -0.222381 0.0800076 -0.0671871 -0.22186 0.0806249 -0.0667233 -0.222287 0.0814593 -0.0663463 -0.221777 0.0811501 -0.0662882 -0.221904 0.0816932 -0.0656635 -0.22176 0.0817992 -0.0649003 -0.222055 0.0819451 -0.0647695 -0.221919 0.0817199 -0.0639381 -0.221791 0.0811684 -0.0632231 -0.221618 0.0793336 -0.0627135 -0.221695 0.0803285 -0.062763 -0.22215 0.0811676 -0.0630684 -0.222182 0.0818501 -0.0656045 -0.222469 0.0819509 -0.0655289 -0.222206 0.0799979 -0.0671229 -0.221241 0.0800578 -0.0660567 -0.221391 0.080729 -0.066111 -0.221652 0.0814843 -0.0657016 -0.221602 0.0816102 -0.0641274 -0.221161 0.0809866 -0.0637348 -0.221451 0.0811089 -0.0634489 -0.221335 0.0803198 -0.0630027 -0.22129 0.0793664 -0.0629316 -0.221889 0.0561501 -0.0662459 -0.221626 0.0561974 -0.0660222 -0.221497 0.0562292 -0.0658717 -0.221626 0.064064 -0.0672012 -0.221254 0.0638437 -0.0665762 -0.221626 0.072015 -0.0674355 -0.222206 0.0561134 -0.0664193 -0.222206 0.0640279 -0.0676056 -0.222382 0.0560999 -0.0664829 -0.221626 0.0799374 -0.0667215 -0.221889 0.0799715 -0.0669475 -0.222206 0.0720273 -0.0678412 -0.222899 0.0800192 -0.0672644 -0.221618 0.0718926 -0.0633841 -0.220781 0.079654 -0.0648403 -0.220691 0.0795308 -0.0640226 -0.220781 0.0639648 -0.0652818 -0.220683 0.0567483 -0.0634173 -0.220992 0.0643759 -0.0637105 -0.220781 0.0642333 -0.0653064 -0.220691 0.0643069 -0.0644827 -0.220781 0.0722262 -0.0655252 -0.220691 0.0719326 -0.0647074 -0.220778 0.056837 -0.0629979 -0.220992 0.0794153 -0.0632559 -0.222426 0.0718866 -0.0631865 -0.222426 0.0793041 -0.062518 -0.220992 0.0569226 -0.0625933 -0.220992 0.0719092 -0.0639324 -0.221618 0.0644247 -0.0631641 -0.222049 0.0570685 -0.0619034 -0.220939 0.055898 -0.064455 -0.221018 0.0564565 -0.0647969 -0.220853 0.0560904 -0.064256 -0.220781 0.056591 -0.064161 -0.221159 0.0558598 -0.0650641 -0.221254 0.0798477 -0.0661258 -0.221018 0.0797508 -0.0654831 -0.220878 0.0802157 -0.0650233 -0.220981 0.0803759 -0.0652847 -0.221254 0.0722709 -0.0668245 -0.221254 0.0719968 -0.0668333 -0.220781 0.0719576 -0.0655339 -0.221254 0.0641176 -0.0666012 -0.221254 0.056322 -0.0654328 -0.222663 0.0542324 -0.0637143 -0.224573 0.0541814 -0.0641406 -0.224573 0.0544373 -0.063131 -0.224573 0.0550967 -0.0623249 -0.222575 0.0545866 -0.0628753 -0.222515 0.0550631 -0.0623518 -0.222498 0.0552396 -0.0622208 -0.222448 0.0560452 -0.0618717 -0.224573 0.0560356 -0.061874 -0.224773 0.0539815 -0.0641348 -0.224773 0.0549731 -0.0621677 -0.224573 0.057077 -0.0618633 -0.224773 0.0559902 -0.0616792 -0.227999 0.0800386 -0.0648176 -0.228046 0.0800222 -0.0644347 -0.224973 0.0798313 -0.0637092 -0.224973 0.0791818 -0.0627873 -0.228168 0.0797191 -0.0634759 -0.228275 0.0790687 -0.0626893 -0.228348 0.0781678 -0.0622064 -0.224973 0.0770857 -0.0621071 -0.224773 0.0770627 -0.0619084 -0.224773 0.0782695 -0.0620288 -0.224973 0.0782078 -0.062219 -0.224973 0.0800386 -0.0648176 -0.224773 0.0800155 -0.0636314 -0.224773 0.0789669 -0.0623657 -0.228376 0.0770857 -0.0621071 -0.228376 0.0711547 -0.0625042 -0.224973 0.0681818 -0.0624882 -0.224773 0.0583641 -0.0670007 -0.224973 0.0776939 -0.0673721 -0.224973 0.0797091 -0.0660214 -0.227863 0.079739 -0.0659658 -0.227871 0.0797766 -0.065891 -0.224973 0.0593158 -0.0615836 -0.224973 0.0579493 -0.0617041 -0.228362 0.0585457 -0.061562 -0.228046 0.0562476 -0.063733 -0.224973 0.0572401 -0.0620943 -0.228275 0.0573018 -0.0620482 -0.224973 0.0566214 -0.0656162 -0.227748 0.0573894 -0.0664 -0.227819 0.0566631 -0.0656797 -0.227826 0.0566213 -0.0656159 -0.227842 0.0565308 -0.0654624 -0.224973 0.0562143 -0.0643868 -0.227983 0.0562077 -0.064243 -0.230111 0.0590525 -0.0630823 -0.229184 0.0771084 -0.0623035 -0.229184 0.0711584 -0.0627019 -0.228376 0.0681818 -0.0624882 -0.228376 0.0652131 -0.0623292 -0.229809 0.0771713 -0.0628484 -0.228752 0.0593087 -0.061624 -0.229184 0.0651978 -0.0625263 -0.229809 0.0711687 -0.0632503 -0.229809 0.0651552 -0.0630731 -0.229809 0.0591867 -0.0623186 -0.230111 0.0711832 -0.0640255 -0.230111 0.0650951 -0.0638461 -0.23002 0.065031 -0.0646706 -0.22772 0.0583988 -0.0668037 -0.22772 0.0631945 -0.0674687 -0.22772 0.0680258 -0.0677859 -0.224973 0.0680258 -0.0677859 -0.227924 0.0799463 -0.0654373 -0.229764 0.0788529 -0.0645623 -0.229463 0.0781786 -0.0658811 -0.230009 0.0775903 -0.0644433 -0.229938 0.0779741 -0.0645921 -0.229919 0.0780347 -0.0646371 -0.229803 0.0782698 -0.0649279 -0.230069 0.077944 -0.0637528 -0.229967 0.0780495 -0.0633467 -0.230023 0.0772187 -0.0632588 -0.229759 0.0781327 -0.0629613 -0.229821 0.0787255 -0.0637527 -0.229939 0.0785002 -0.0640768 -0.230111 0.0772603 -0.0636186 -0.23002 0.0773552 -0.0644401 -0.229416 0.079395 -0.0641337 -0.229577 0.0789821 -0.0651161 -0.229212 0.0795586 -0.0649155 -0.229401 0.0788963 -0.0656652 -0.229023 0.0794255 -0.0656779 -0.228346 0.0800055 -0.0645466 -0.227763 0.0789645 -0.0668711 -0.228087 0.079433 -0.0663937 -0.227819 0.0794928 -0.066352 -0.22969 0.0783608 -0.0652296 -0.229639 0.0783659 -0.06537 -0.229255 0.0786145 -0.0661472 -0.228717 0.0781858 -0.0622533 -0.228257 0.0792157 -0.0628191 -0.228491 0.0797419 -0.0635884 -0.228116 0.0798953 -0.0638766 -0.22877 0.0796352 -0.0656472 -0.228949 0.0797747 -0.064794 -0.228981 0.0791118 -0.062931 -0.22914 0.079584 -0.0639246 -0.229098 0.078201 -0.0623959 -0.228206 0.0798968 -0.0655219 -0.228493 0.0797936 -0.0655937 -0.228653 0.0799247 -0.0646685 -0.228823 0.0796999 -0.0637393 -0.228622 0.0791161 -0.0627763 -0.228752 0.0770904 -0.0621478 -0.227721 0.0778344 -0.0673521 -0.22827 0.0786009 -0.0670057 -0.228766 0.0784142 -0.0668207 -0.229157 0.0781681 -0.066502 -0.229399 0.0779523 -0.0660886 -0.228993 0.0776309 -0.0668266 -0.227747 0.0787057 -0.0670398 -0.228359 0.0793351 -0.0664074 -0.228869 0.0790287 -0.0663387 -0.229321 0.0790449 -0.0631545 -0.229611 0.0789132 -0.0634359 -0.229458 0.0781843 -0.0626351 -0.229511 0.0771337 -0.0625224 -0.229577 0.0572457 -0.0644751 -0.228766 0.0577124 -0.066211 -0.229741 0.0578944 -0.0644893 -0.229885 0.0581261 -0.0641304 -0.230069 0.0583619 -0.0631761 -0.228993 0.0584938 -0.0662629 -0.229365 0.058598 -0.0656696 -0.229255 0.0575519 -0.0655269 -0.229578 0.0578601 -0.0649405 -0.229401 0.0572988 -0.0650286 -0.229764 0.0574074 -0.0639301 -0.229611 0.0574132 -0.0628026 -0.229821 0.0575819 -0.06313 -0.230023 0.0591152 -0.0627255 -0.229939 0.0577877 -0.0634668 -0.229967 0.0582804 -0.0627645 -0.228349 0.0582515 -0.0616138 -0.228622 0.0572494 -0.0621323 -0.228168 0.0566068 -0.0627944 -0.228142 0.0564966 -0.0629896 -0.228346 0.0562576 -0.0638458 -0.229184 0.0592816 -0.0617784 -0.228717 0.0582086 -0.061665 -0.228376 0.0593158 -0.0615836 -0.228206 0.0563084 -0.0648264 -0.227924 0.056264 -0.064739 -0.228087 0.0567203 -0.0657248 -0.228238 0.0584123 -0.0667267 -0.22827 0.0575152 -0.0663847 -0.229157 0.0579768 -0.0659073 -0.228869 0.0571272 -0.0656937 -0.228359 0.0568173 -0.0657443 -0.228771 0.0565622 -0.0649669 -0.228493 0.0564071 -0.0649042 -0.229321 0.0572982 -0.062514 -0.229458 0.0581876 -0.0620462 -0.229098 0.058185 -0.0618064 -0.228981 0.0572446 -0.062287 -0.228491 0.0565774 -0.0629053 -0.228823 0.0566104 -0.0630585 -0.228653 0.0563311 -0.0639723 -0.228414 0.0584235 -0.0666627 -0.229023 0.0567697 -0.06501 -0.229212 0.056682 -0.0642406 -0.228949 0.0564734 -0.0641065 -0.229416 0.0568916 -0.0634703 -0.22914 0.0567151 -0.0632503 -0.229759 0.05822 -0.0623749 -0.229511 0.0592434 -0.0619954 -0.229692 0.0587537 -0.0647832 -0.229365 0.0633114 -0.0663232 -0.229497 0.0782465 -0.0657801 -0.22969 0.0578592 -0.0646252 -0.229376 0.0583727 -0.0655992 -0.229445 0.0580473 -0.0653465 -0.229463 0.0580027 -0.0652868 -0.23002 0.0589094 -0.0638968 -0.229986 0.0584962 -0.063919 -0.23002 0.0681131 -0.0648357 -0.23002 0.0711987 -0.0648523 -0.229692 0.0774585 -0.0653342 -0.229365 0.0775617 -0.0662282 -0.22873 0.0776571 -0.0670539 -0.228993 0.0728438 -0.0672051 -0.229365 0.072818 -0.0666032 -0.228993 0.0632502 -0.0669225 -0.229365 0.0680597 -0.0666349 -0.22873 0.0584542 -0.0664882 -0.228414 0.063209 -0.0673263 -0.228414 0.06803 -0.0676428 -0.228993 0.0680419 -0.0672371 -0.228414 0.0728612 -0.0676106 -0.228414 0.0776774 -0.0672299 -0.22772 0.0728673 -0.0677536 -0.228238 0.0776849 -0.0672944 -0.22772 0.0776939 -0.0673721 -0.224773 0.0718806 -0.0629866 -0.224573 0.0718866 -0.0631865 -0.224773 0.0571184 -0.0616676 -0.224573 0.0720316 -0.0679843 -0.224773 0.080049 -0.0674622 -0.224573 0.0640151 -0.0677481 -0.224573 0.0560838 -0.0665594 -0.224573 0.0550856 -0.0660889 -0.224773 0.054961 -0.0662454 -0.224573 0.0544034 -0.0652216 -0.224773 0.054222 -0.0653058 -0.224573 0.0820503 -0.0651243 -0.224773 0.0822327 -0.0645038 -0.224573 0.0800192 -0.0672644 -0.224773 0.0812826 -0.0669241 -0.224573 0.0816546 -0.0662284 -0.224773 0.0820819 -0.0658412 -0.224573 0.0820349 -0.0645336 -0.224573 0.0818756 -0.0639646 -0.224773 0.0792743 -0.0623202 -0.224773 0.0806117 -0.062471 -0.224573 0.0805386 -0.0626572 -0.224773 0.0816945 -0.0632702 -0.224773 0.0681877 -0.0622883 -0.224773 0.0644601 -0.062768 -0.222873 0.0550752 -0.0660807 -0.222827 0.0545479 -0.0654877 -0.222751 0.0542163 -0.0646247 -0.222705 0.0541814 -0.0641406 -0.224573 0.0793041 -0.062518 -0.222436 0.0800071 -0.0625162 -0.222445 0.0802671 -0.0625688 -0.222704 0.082061 -0.064948 -0.224573 0.0815381 -0.0633949 -0.222498 0.0811174 -0.0629831 -0.224573 0.0811721 -0.0630261 -0.224573 0.0811579 -0.0667677 -0.222877 0.0809829 -0.0668948 -0.224573 0.0818957 -0.0657682 -0.222807 0.0817626 -0.0660513 -0.222751 0.0819975 -0.0654424 -0.222721 0.0820503 -0.0651242 -0.222899 0.0720316 -0.0679843 -0.222899 0.0640151 -0.0677481 -0.222426 0.057077 -0.0618633 -0.224573 0.0644423 -0.0629672 -0.222426 0.0644423 -0.0629672 -0.22123 0.0560502 -0.0653052 -0.220795 0.0563701 -0.064152 -0.220833 0.0556779 -0.0636559 -0.220725 0.0561704 -0.0634229 -0.220691 0.0567622 -0.0633519 -0.221161 0.0553259 -0.0629788 -0.220951 0.0554835 -0.063312 -0.221035 0.0560561 -0.062617 -0.220826 0.0561031 -0.0630087 -0.221131 0.0552064 -0.0644904 -0.221283 0.0549096 -0.0643711 -0.220978 0.0553498 -0.0640383 -0.221326 0.054849 -0.0635608 -0.221652 0.0547133 -0.0649135 -0.221056 0.0558017 -0.0647632 -0.221391 0.055443 -0.0653661 -0.222469 0.0542577 -0.0647138 -0.2228 0.0543789 -0.065167 -0.222899 0.0560838 -0.0665594 -0.222077 0.0560687 -0.0619069 -0.22215 0.0551845 -0.0623029 -0.222252 0.0545535 -0.0629851 -0.222617 0.0543766 -0.0632608 -0.221904 0.054507 -0.0648632 -0.22176 0.0544459 -0.0640956 -0.221919 0.0545815 -0.0631394 -0.221602 0.0546798 -0.0633347 -0.221451 0.0552207 -0.0626862 -0.22129 0.0569905 -0.0622724 -0.222287 0.0547001 -0.0655579 -0.222182 0.0543539 -0.0647951 -0.222055 0.0543079 -0.0639565 -0.222363 0.0542386 -0.0638274 -0.221791 0.0551746 -0.0624573 -0.221695 0.0560404 -0.0620474 -0.221618 0.0570361 -0.0620567 -0.221469 0.0557858 -0.065689 -0.221019 0.0558148 -0.064661 -0.221564 0.0552172 -0.0654548 -0.22186 0.0555108 -0.0659834 -0.222559 0.0546037 -0.0655349 -0.222357 0.0553073 -0.0661502 -0.221777 0.0550121 -0.0655182 -0.221496 0.0546501 -0.0642368 -0.221335 0.0560349 -0.0622872 -0.224773 0.0570267 -0.0663781 -0.224773 0.0560502 -0.0637006 -0.224973 0.0583988 -0.0668037 -0.224973 0.0571552 -0.0662248 -0.224973 0.0563677 -0.0651016 -0.224773 0.0561798 -0.0651701 -0.224773 0.0593504 -0.0613867 -0.224773 0.0578808 -0.0615162 -0.224773 0.0574226 -0.0617311 -0.224973 0.0568262 -0.0624916 -0.224973 0.0564384 -0.0631113 -0.224973 0.0562472 -0.0637352 -0.224973 0.0788651 -0.0669409 -0.224773 0.0777168 -0.0675708 -0.224773 0.0566729 -0.0623631 -0.224773 0.0542587 -0.063041 -0.224773 0.0802386 -0.0648235 -0.224773 0.079317 -0.06264 -0.224773 0.0560424 -0.066755 -0.224773 0.0639973 -0.0679473 -0.224773 0.0680199 -0.0679858 -0.224773 0.0720377 -0.0681842 -0.224773 0.0789765 -0.067107 -0.224773 0.0798842 -0.0661182 -0.224573 0.025051 -0.0507865 -0.224573 0.0244489 -0.0499462 -0.224573 0.0242561 -0.0489307 -0.224773 0.0242651 -0.050025 -0.224573 0.0454272 -0.0633648 -0.224773 0.0487243 -0.0620808 -0.224773 0.0466915 -0.0637018 -0.224573 0.0473615 -0.0632853 -0.224573 0.0482562 -0.062527 -0.224573 0.0485448 -0.0602708 -0.224773 0.0488751 -0.0607434 -0.224573 0.0486847 -0.0614353 -0.224773 0.0455448 -0.0572481 -0.224773 0.0469652 -0.0585963 -0.224773 0.0405178 -0.0555908 -0.224773 0.0342008 -0.0516912 -0.224773 0.0304663 -0.0479401 -0.222827 0.0242568 -0.0490905 -0.222436 0.0477908 -0.0592466 -0.224573 0.0481806 -0.0596345 -0.222704 0.0483536 -0.0623796 -0.222663 0.0485387 -0.0620063 -0.224573 0.0485382 -0.0620077 -0.224573 0.0486773 -0.0607732 -0.22259 0.0486998 -0.0612756 -0.222445 0.0479896 -0.0594222 -0.224573 0.0466617 -0.063504 -0.222827 0.0472991 -0.0633148 -0.222822 0.0473616 -0.0632852 -0.224573 0.0478004 -0.0630073 -0.222807 0.0475436 -0.0631859 -0.222899 0.0313254 -0.0557817 -0.224573 0.0313254 -0.0557817 -0.222426 0.0282592 -0.0472162 -0.224573 0.0340858 -0.0518548 -0.224573 0.0404231 -0.0557669 -0.222426 0.0471811 -0.0588967 -0.221497 0.0255208 -0.0502637 -0.220795 0.0265026 -0.0488448 -0.220725 0.0266942 -0.0481135 -0.220978 0.0256759 -0.0482362 -0.220951 0.0261548 -0.0476741 -0.220833 0.0261512 -0.0480691 -0.220826 0.0268431 -0.0477212 -0.221283 0.0251283 -0.0483043 -0.221056 0.0257048 -0.0490899 -0.221391 0.0250927 -0.0494327 -0.22186 0.0248427 -0.0500012 -0.222663 0.0248702 -0.0473969 -0.222559 0.0242814 -0.0491592 -0.222816 0.0242561 -0.0489307 -0.222357 0.0245831 -0.0500439 -0.22215 0.0264004 -0.0466507 -0.222448 0.0273614 -0.0467076 -0.222077 0.0273642 -0.0467498 -0.222252 0.0255129 -0.046926 -0.222621 0.0251863 -0.0471033 -0.222055 0.0248145 -0.0476444 -0.221919 0.02546 -0.0470735 -0.221451 0.0262401 -0.0470007 -0.221618 0.0281271 -0.0473633 -0.221335 0.0271447 -0.0470623 -0.222469 0.0243923 -0.0482752 -0.222363 0.024819 -0.047498 -0.222182 0.024435 -0.0483937 -0.221791 0.0263147 -0.0467795 -0.221695 0.0272694 -0.0468574 -0.222049 0.0282318 -0.0472467 -0.22123 0.025649 -0.0496836 -0.221469 0.0252281 -0.0498837 -0.221019 0.0257672 -0.049008 -0.221131 0.0253257 -0.048556 -0.221564 0.0248528 -0.0493966 -0.221777 0.0246435 -0.049349 -0.222206 0.0251466 -0.05068 -0.222382 0.0251032 -0.0507283 -0.222877 0.0244445 -0.0499358 -0.222287 0.0243535 -0.0492274 -0.221904 0.0245336 -0.0485292 -0.22176 0.0248644 -0.0478339 -0.221652 0.0246871 -0.0486759 -0.221496 0.0249707 -0.0480583 -0.221602 0.0254475 -0.0472919 -0.221326 0.025481 -0.0475723 -0.221161 0.0261849 -0.0473067 -0.22129 0.0279797 -0.0475272 -0.221035 0.0269982 -0.0473584 -0.221326 0.0481078 -0.0615394 -0.221496 0.0479024 -0.0622131 -0.221131 0.0472982 -0.0621191 -0.22186 0.0462222 -0.063199 -0.220781 0.0463229 -0.0610829 -0.220806 0.0465697 -0.0612532 -0.220725 0.0470803 -0.0606982 -0.220833 0.0473633 -0.0611635 -0.220854 0.0466893 -0.0614391 -0.220878 0.0467179 -0.0615222 -0.221626 0.0456278 -0.0628537 -0.221391 0.0466186 -0.0627208 -0.221274 0.0470154 -0.0624836 -0.220981 0.0467259 -0.0618286 -0.220978 0.047427 -0.0616629 -0.220951 0.0477148 -0.0609833 -0.221161 0.0480298 -0.0607918 -0.220826 0.0473644 -0.0603893 -0.221035 0.0476192 -0.0600881 -0.220691 0.0466251 -0.0603131 -0.220778 0.0467573 -0.0599763 -0.222077 0.0479994 -0.0594881 -0.222498 0.0485189 -0.0602062 -0.22215 0.0485197 -0.0603051 -0.222606 0.0486847 -0.0614353 -0.222751 0.0480514 -0.0627761 -0.222363 0.0484714 -0.0620974 -0.222469 0.0479678 -0.0628277 -0.222721 0.0482562 -0.0625269 -0.222877 0.0464466 -0.0635265 -0.222381 0.0454558 -0.063292 -0.221469 0.0461546 -0.0628018 -0.222055 0.0483425 -0.0621671 -0.221451 0.0482786 -0.0606053 -0.221791 0.048443 -0.0604395 -0.22129 0.0470283 -0.059286 -0.221695 0.0479457 -0.0596211 -0.222252 0.0486713 -0.061221 -0.221919 0.0485631 -0.0613345 -0.222182 0.0478427 -0.0628427 -0.222559 0.0472266 -0.0633236 -0.222287 0.0471334 -0.0632897 -0.222357 0.0463004 -0.0634503 -0.221777 0.0468947 -0.0630849 -0.221652 0.0474774 -0.0627439 -0.221904 0.0476774 -0.0628154 -0.22176 0.0481508 -0.0622075 -0.221602 0.0483735 -0.0614436 -0.221335 0.0478184 -0.0598244 -0.221626 0.0384098 -0.0595108 -0.221254 0.0458479 -0.062293 -0.221626 0.025418 -0.0503781 -0.221626 0.0316411 -0.0553325 -0.221254 0.0386951 -0.0589803 -0.221254 0.0389369 -0.0591097 -0.221889 0.0252652 -0.0505481 -0.222899 0.025051 -0.0507865 -0.222899 0.0381498 -0.0599944 -0.221889 0.0455443 -0.0630665 -0.222206 0.0382176 -0.0598684 -0.222206 0.0454795 -0.0632316 -0.222206 0.0314077 -0.0556646 -0.222899 0.0454272 -0.0633648 -0.221618 0.0471088 -0.0590808 -0.220781 0.0266895 -0.048963 -0.220781 0.0327352 -0.0537762 -0.220992 0.0336566 -0.0524653 -0.220691 0.0397025 -0.057107 -0.220683 0.0271976 -0.0483976 -0.220691 0.0272422 -0.0483479 -0.220691 0.0332107 -0.0530996 -0.220992 0.0469084 -0.0595914 -0.222426 0.0340858 -0.0518548 -0.221618 0.0403295 -0.0559411 -0.222426 0.0404231 -0.0557669 -0.222049 0.0471661 -0.0589349 -0.220778 0.0274841 -0.0480788 -0.220992 0.0277605 -0.0477712 -0.220992 0.0400697 -0.0564241 -0.221618 0.0339721 -0.0520166 -0.220939 0.0259422 -0.0488712 -0.220853 0.0262084 -0.0487951 -0.221159 0.0256047 -0.0493796 -0.221241 0.0460645 -0.0623382 -0.221183 0.0463576 -0.0622816 -0.221098 0.0465802 -0.0621168 -0.221018 0.0460854 -0.0616879 -0.220781 0.0395478 -0.0579622 -0.220781 0.0393108 -0.0578353 -0.221254 0.0319876 -0.0548397 -0.220781 0.0325149 -0.0536206 -0.221254 0.0317629 -0.054681 -0.221254 0.0258206 -0.04993 -0.221018 0.0262551 -0.0494465 -0.224573 0.0245309 -0.0478843 -0.222734 0.02447 -0.0480087 -0.222513 0.0262855 -0.04663 -0.222518 0.0262249 -0.0466402 -0.222575 0.0255965 -0.0468474 -0.222498 0.0264892 -0.0466071 -0.224573 0.0262318 -0.046639 -0.224573 0.0273123 -0.0466931 -0.224573 0.0282592 -0.0472162 -0.224773 0.0240562 -0.0489248 -0.224773 0.0243539 -0.0477912 -0.224573 0.0252373 -0.0470649 -0.224773 0.0251191 -0.0469035 -0.228275 0.0468916 -0.0589274 -0.224973 0.0468852 -0.0589108 -0.224973 0.0463241 -0.0580283 -0.228352 0.0462873 -0.0579908 -0.224973 0.0470613 -0.0599415 -0.224773 0.0464684 -0.0578898 -0.224773 0.0259582 -0.051101 -0.224773 0.0268052 -0.0523089 -0.224973 0.0269337 -0.0521556 -0.224973 0.0261461 -0.0510324 -0.224973 0.0290943 -0.0475145 -0.224973 0.0282849 -0.0474978 -0.224773 0.0291289 -0.0473175 -0.224973 0.0270821 -0.0479777 -0.224973 0.0266047 -0.0484224 -0.224973 0.0467162 -0.0611732 -0.224773 0.04689 -0.061272 -0.224773 0.044637 -0.0627047 -0.224973 0.0446213 -0.0625053 -0.224973 0.0453258 -0.0623511 -0.224773 0.0261965 -0.0464421 -0.224773 0.0264514 -0.0482939 -0.224773 0.0283929 -0.0470674 -0.224773 0.0276593 -0.047447 -0.224773 0.027367 -0.0465007 -0.224773 0.0479251 -0.0631636 -0.224773 0.0258287 -0.0496314 -0.224773 0.0249173 -0.0509352 -0.224773 0.0346747 -0.0579899 -0.224773 0.0432801 -0.0624789 -0.224773 0.0459417 -0.0622685 -0.224773 0.0472612 -0.0599474 -0.224773 0.048337 -0.0595098 -0.224773 0.0470719 -0.0588388 -0.224773 0.0472542 -0.0587106 -0.224973 0.0375638 -0.0533098 -0.224773 0.0376688 -0.0531396 -0.224973 0.0454653 -0.0574317 -0.228376 0.0350723 -0.0516877 -0.224973 0.0433595 -0.0622954 -0.227758 0.044621 -0.0625054 -0.224973 0.0458344 -0.0620997 -0.227868 0.0458782 -0.0620712 -0.228009 0.0467104 -0.0611832 -0.224973 0.0462778 -0.0617458 -0.228046 0.0468446 -0.0609156 -0.224973 0.0303378 -0.0480934 -0.228349 0.029401 -0.0475874 -0.227983 0.0263165 -0.0488424 -0.228046 0.026606 -0.0484207 -0.228142 0.0271934 -0.0479014 -0.224973 0.0277278 -0.0476349 -0.22772 0.0269337 -0.0521556 -0.224973 0.0259882 -0.0502385 -0.224973 0.0260257 -0.049666 -0.227842 0.0259866 -0.05006 -0.227924 0.0261172 -0.0493001 -0.224973 0.0262503 -0.0489703 -0.230111 0.0342117 -0.0529425 -0.230111 0.0293605 -0.0492596 -0.230023 0.0295932 -0.048982 -0.229184 0.0400348 -0.0549831 -0.228376 0.0401304 -0.0548101 -0.229184 0.0453868 -0.0576131 -0.228376 0.0375638 -0.0533098 -0.229184 0.0349605 -0.0518507 -0.229511 0.0300693 -0.0484138 -0.230111 0.0393944 -0.0561418 -0.229809 0.0346502 -0.0523031 -0.229809 0.0397695 -0.0554632 -0.23002 0.0445322 -0.0595869 -0.230111 0.0448608 -0.058828 -0.23002 0.0389944 -0.0568656 -0.23002 0.0363305 -0.0553084 -0.23002 0.0337439 -0.0536244 -0.224973 0.0347798 -0.0578197 -0.22772 0.0347798 -0.0578197 -0.229463 0.0445248 -0.0612465 -0.229939 0.0457055 -0.0598448 -0.229803 0.0450804 -0.0604666 -0.229577 0.0456031 -0.0609857 -0.230069 0.0453858 -0.059286 -0.230023 0.0450047 -0.0584956 -0.229809 0.0451688 -0.0581165 -0.229967 0.0456801 -0.0589871 -0.229157 0.0442053 -0.0617789 -0.229611 0.0463836 -0.0594962 -0.229821 0.0460626 -0.0596768 -0.229416 0.0464519 -0.0603414 -0.229764 0.0457682 -0.0604415 -0.229212 0.0462027 -0.0611003 -0.229401 0.0452543 -0.0614184 -0.227924 0.0462776 -0.061746 -0.228087 0.0453549 -0.0623176 -0.22781 0.0453264 -0.0623509 -0.227747 0.0444019 -0.0625135 -0.22827 0.0443282 -0.0624316 -0.228376 0.0454653 -0.0574317 -0.228346 0.0467742 -0.0610043 -0.228491 0.047025 -0.0600426 -0.228167 0.0470613 -0.0599415 -0.228251 0.0469698 -0.059169 -0.228622 0.0468891 -0.0590264 -0.228348 0.0463528 -0.0580587 -0.22877 0.0459032 -0.0617722 -0.228949 0.0464506 -0.0611031 -0.228823 0.0469132 -0.0601523 -0.228981 0.046808 -0.0591582 -0.229321 0.0466383 -0.0593183 -0.228206 0.0461924 -0.0617946 -0.228493 0.0460672 -0.0618052 -0.228653 0.0466433 -0.0610694 -0.229098 0.0462868 -0.0582395 -0.228717 0.0463449 -0.0581084 -0.228752 0.045449 -0.0574693 -0.228414 0.0434164 -0.062164 -0.22873 0.0434868 -0.0620014 -0.229399 0.0442251 -0.061313 -0.22969 0.0450083 -0.0607734 -0.229255 0.0447692 -0.0616949 -0.228869 0.0450322 -0.0620679 -0.228766 0.044259 -0.062178 -0.228359 0.0452632 -0.0622806 -0.229023 0.0457062 -0.061694 -0.22914 0.0467202 -0.0602548 -0.229458 0.0461528 -0.0584383 -0.229511 0.0452992 -0.0578153 -0.229759 0.0459449 -0.0586949 -0.227748 0.0262614 -0.0513013 -0.229416 0.0272951 -0.0485151 -0.229212 0.0267284 -0.0490775 -0.229577 0.0270994 -0.0495624 -0.229939 0.0280729 -0.0489602 -0.229885 0.0280342 -0.0497041 -0.229986 0.0284604 -0.0497061 -0.23002 0.0288294 -0.0498934 -0.230069 0.0287156 -0.0489955 -0.229376 0.0275134 -0.0510994 -0.229255 0.0268387 -0.0506264 -0.229445 0.0273579 -0.0507179 -0.229401 0.0268686 -0.0500683 -0.22969 0.0275556 -0.0499992 -0.229821 0.028063 -0.0485656 -0.229741 0.027654 -0.0498991 -0.229764 0.0275119 -0.0491713 -0.229967 0.0288508 -0.0485984 -0.228362 0.0296817 -0.0476896 -0.228717 0.0293383 -0.0476103 -0.228275 0.0283614 -0.0474887 -0.228168 0.0273864 -0.0477875 -0.228491 0.0273056 -0.0478688 -0.228752 0.0303115 -0.0481248 -0.228376 0.0303378 -0.0480934 -0.228346 0.0265583 -0.0485234 -0.227826 0.0259882 -0.0502382 -0.227819 0.0259926 -0.0503144 -0.228087 0.0260195 -0.050382 -0.228359 0.0260938 -0.0504474 -0.228771 0.0262615 -0.0496466 -0.228653 0.0265587 -0.0486697 -0.22914 0.0272523 -0.0482364 -0.228823 0.0272576 -0.048018 -0.229321 0.0281254 -0.0478903 -0.229098 0.0292471 -0.047721 -0.229184 0.0302108 -0.0482449 -0.228622 0.028274 -0.0475354 -0.228981 0.0281925 -0.0476669 -0.228206 0.026112 -0.049398 -0.228493 0.0261586 -0.0495148 -0.228766 0.0266356 -0.0512992 -0.22827 0.0263779 -0.051351 -0.228414 0.0270256 -0.0520459 -0.22873 0.0271394 -0.0519101 -0.229157 0.0270164 -0.0511683 -0.228869 0.0263875 -0.0505585 -0.229023 0.0264197 -0.0497877 -0.228949 0.0266148 -0.0488571 -0.229611 0.0280806 -0.0481978 -0.229458 0.0291295 -0.0479299 -0.229759 0.0289933 -0.0482307 -0.229809 0.0298585 -0.0486654 -0.230009 0.0447342 -0.0597072 -0.229938 0.0449922 -0.0600279 -0.229919 0.0450222 -0.0600972 -0.229692 0.0441746 -0.0604128 -0.229497 0.0446341 -0.061193 -0.229639 0.0449426 -0.0608975 -0.229578 0.0273988 -0.0502727 -0.229365 0.0276732 -0.051273 -0.229692 0.0282513 -0.0505832 -0.229463 0.0273491 -0.0506439 -0.229365 0.0314284 -0.0541958 -0.229365 0.043817 -0.0612387 -0.228238 0.0269839 -0.0520957 -0.22772 0.0307544 -0.0551294 -0.228414 0.0308382 -0.0550133 -0.228993 0.0392428 -0.0597257 -0.228993 0.0435777 -0.0617915 -0.228993 0.0350682 -0.0573525 -0.229365 0.0395214 -0.0591916 -0.229365 0.0353846 -0.0568399 -0.228993 0.0310758 -0.0546842 -0.228993 0.0272863 -0.0517347 -0.228414 0.034855 -0.0576979 -0.228414 0.039055 -0.0600856 -0.228238 0.0433906 -0.0622236 -0.22772 0.0389888 -0.0602125 -0.22772 0.0433595 -0.0622954 -0.224573 0.0471811 -0.0588967 -0.224773 0.0286245 -0.0472745 -0.224573 0.0381498 -0.0599944 -0.224773 0.0453541 -0.063551 -0.224773 0.0380551 -0.0601706 -0.224773 0.0312103 -0.0559453 -0.224573 0.00594508 -0.0207958 -0.224573 0.00697108 -0.018898 -0.222742 0.00688095 -0.018964 -0.224573 0.00688084 -0.0189641 -0.222776 0.00660264 -0.0192149 -0.224573 0.00623281 -0.0197251 -0.222584 0.00840554 -0.0184672 -0.222513 0.00921166 -0.0186288 -0.224573 0.00921174 -0.0186288 -0.222505 0.00931749 -0.0186727 -0.224573 0.010048 -0.0191763 -0.222448 0.0101038 -0.0192345 -0.224573 0.0106258 -0.0201225 -0.222426 0.0106258 -0.0201225 -0.224773 0.00917007 -0.0184012 -0.224573 0.00910653 -0.0185908 -0.224573 0.00800235 -0.0184909 -0.228304 0.0209401 -0.0392301 -0.228349 0.0208689 -0.0385371 -0.224973 0.020419 -0.0375725 -0.224973 0.0208193 -0.0383573 -0.224773 0.0210101 -0.0382974 -0.230111 0.0105579 -0.0224429 -0.229511 0.0200833 -0.0378216 -0.228376 0.0142904 -0.0274015 -0.229809 0.0198198 -0.0380173 -0.228752 0.0119488 -0.0219356 -0.229184 0.014112 -0.0274868 -0.229184 0.0118016 -0.0219893 -0.229511 0.0115946 -0.0220648 -0.229809 0.0136171 -0.0277234 -0.230111 0.0191973 -0.0384794 -0.229809 0.0164705 -0.0330198 -0.229184 0.0169403 -0.0327367 -0.229809 0.0112863 -0.0221772 -0.23002 0.0185333 -0.0389724 -0.23002 0.0150981 -0.0338467 -0.230111 0.0158064 -0.0334199 -0.23002 0.0135696 -0.0311663 -0.230111 0.0129176 -0.0280579 -0.23002 0.00978096 -0.0227262 -0.224973 0.00700813 -0.0237374 -0.22772 0.010971 -0.0325657 -0.224973 0.010971 -0.0325657 -0.224973 0.0161635 -0.0407316 -0.22772 0.0161635 -0.0407316 -0.229939 0.0194204 -0.0397824 -0.229919 0.0187024 -0.0396593 -0.230069 0.0194229 -0.0391386 -0.230023 0.0194881 -0.0382635 -0.229611 0.020182 -0.0398195 -0.229759 0.0202027 -0.0389063 -0.229821 0.0198137 -0.0398154 -0.229967 0.0198273 -0.0390269 -0.230009 0.0186481 -0.0391775 -0.229463 0.0176971 -0.0404059 -0.229416 0.0198185 -0.0405857 -0.229212 0.0192233 -0.0411182 -0.229764 0.0191763 -0.0403305 -0.229577 0.0187613 -0.0407193 -0.228024 0.0197238 -0.0413814 -0.227874 0.0185164 -0.0417925 -0.228087 0.0178804 -0.0417486 -0.228206 0.0188672 -0.0417144 -0.227747 0.0169571 -0.0414417 -0.22827 0.0169343 -0.041334 -0.227765 0.0172514 -0.0415896 -0.229639 0.0182333 -0.0403126 -0.229255 0.0176845 -0.0409165 -0.229401 0.0182429 -0.0409195 -0.228869 0.0177258 -0.0413709 -0.228766 0.0170011 -0.0410797 -0.228376 0.020419 -0.0375725 -0.228357 0.020821 -0.0383632 -0.228622 0.0208546 -0.0396654 -0.228046 0.0198715 -0.0412793 -0.228346 0.0197662 -0.0413209 -0.228085 0.020113 -0.0410765 -0.228491 0.0204643 -0.0406134 -0.22877 0.0186279 -0.0415504 -0.228493 0.0187534 -0.0416609 -0.228653 0.0196202 -0.0413118 -0.228981 0.0207185 -0.039739 -0.229098 0.0207265 -0.0386828 -0.228823 0.0203125 -0.0406525 -0.228717 0.0208424 -0.0385983 -0.228752 0.0203861 -0.0375969 -0.229184 0.0202602 -0.0376903 -0.229157 0.0171541 -0.0407073 -0.228993 0.0166043 -0.0404044 -0.229399 0.0174042 -0.0403137 -0.228359 0.0178195 -0.0416707 -0.229023 0.0184964 -0.0413842 -0.228949 0.0194365 -0.0412447 -0.22914 0.0200942 -0.0406448 -0.229321 0.0204915 -0.0397929 -0.229458 0.020511 -0.0387879 -0.22772 0.00700813 -0.0237374 -0.228993 0.00752398 -0.0235493 -0.229939 0.00959245 -0.0215398 -0.229463 0.00812376 -0.0226359 -0.229578 0.00835236 -0.0223394 -0.229577 0.00844822 -0.0215745 -0.229401 0.00799544 -0.0218972 -0.229023 0.00774695 -0.0214298 -0.229255 0.00769046 -0.0223656 -0.22969 0.00862496 -0.0221809 -0.229764 0.00900104 -0.0214421 -0.229416 0.00914139 -0.0207654 -0.229611 0.00998037 -0.0208833 -0.229821 0.00978119 -0.0211931 -0.229967 0.010447 -0.0216153 -0.230023 0.0108982 -0.0223188 -0.230069 0.0101313 -0.0218917 -0.228717 0.0113633 -0.0210034 -0.228275 0.010578 -0.0204097 -0.228168 0.00958433 -0.0201809 -0.228142 0.00936014 -0.020183 -0.228376 0.0119874 -0.0219215 -0.228362 0.011621 -0.0212438 -0.227826 0.00714804 -0.0216042 -0.228206 0.00767531 -0.0209384 -0.227924 0.00772884 -0.0208563 -0.227819 0.00711374 -0.0216723 -0.227748 0.00685308 -0.0226614 -0.22827 0.00692918 -0.0227627 -0.229157 0.00757345 -0.0229238 -0.228766 0.00717826 -0.0228467 -0.228359 0.00713487 -0.0218381 -0.228771 0.00768053 -0.0212285 -0.228493 0.00765732 -0.0210628 -0.228949 0.00838128 -0.0207214 -0.228653 0.00842638 -0.020531 -0.22914 0.0092437 -0.0205026 -0.228981 0.0103427 -0.0204795 -0.229458 0.0110227 -0.0211758 -0.229098 0.011229 -0.0210536 -0.228622 0.010479 -0.0204063 -0.228491 0.00947361 -0.0202109 -0.228823 0.00935746 -0.0203161 -0.228346 0.00849917 -0.0204042 -0.228087 0.00710326 -0.0217444 -0.228414 0.00714259 -0.0236884 -0.228869 0.00733365 -0.0220812 -0.229212 0.00836943 -0.0209691 -0.229321 0.0101729 -0.0206395 -0.229759 0.0107543 -0.0213682 -0.229938 0.0187111 -0.0395843 -0.229803 0.0185682 -0.0400084 -0.229692 0.0178107 -0.0395088 -0.229497 0.0178185 -0.0404142 -0.22969 0.0183524 -0.040238 -0.229741 0.00876028 -0.0221434 -0.229376 0.00803829 -0.0231126 -0.229445 0.00809436 -0.0227044 -0.229986 0.00955506 -0.0223795 -0.229885 0.00918697 -0.0221646 -0.23002 0.0121716 -0.0284146 -0.229692 0.00893543 -0.0230345 -0.229365 0.00988059 -0.0277516 -0.229365 0.0143914 -0.0361246 -0.229365 0.017088 -0.0400453 -0.228238 0.00708157 -0.0237106 -0.22772 0.0088301 -0.0282231 -0.22873 0.00730908 -0.0236276 -0.228414 0.0162784 -0.0406463 -0.22873 0.0164207 -0.0405407 -0.228993 0.0114544 -0.0323053 -0.229365 0.0119847 -0.0320196 -0.228993 0.00933103 -0.0279983 -0.229365 0.00808991 -0.0233429 -0.228414 0.00896067 -0.0281645 -0.228993 0.0138831 -0.0364479 -0.228414 0.0135405 -0.0366657 -0.228414 0.011097 -0.0324978 -0.228238 0.0162262 -0.0406851 -0.22772 0.0134197 -0.0367425 -0.224773 0.0213287 -0.0395744 -0.224773 0.0170548 -0.0335044 -0.224573 0.0174194 -0.0426916 -0.224573 0.0128022 -0.0361341 -0.224773 0.0126321 -0.0362393 -0.224773 0.00881701 -0.0291577 -0.224573 0.0202883 -0.0433806 -0.224773 0.0209168 -0.0432282 -0.224773 0.0183458 -0.0436156 -0.224573 0.0196534 -0.0435686 -0.224773 0.0218668 -0.040808 -0.224773 0.0217161 -0.0421454 -0.224573 0.0216663 -0.041571 -0.224573 0.0215299 -0.0420723 -0.224773 0.0135339 -0.0269688 -0.224773 0.0205796 -0.0374532 -0.224773 0.02114 -0.039236 -0.224773 0.0114864 -0.020788 -0.224573 0.00606224 -0.0216104 -0.224573 0.0216691 -0.0408378 -0.224573 0.0207921 -0.0430719 -0.222663 0.0207934 -0.0430709 -0.224573 0.0212053 -0.0426494 -0.222606 0.0212053 -0.0426494 -0.22259 0.0212981 -0.0425186 -0.222498 0.0216762 -0.0415021 -0.222899 0.0174194 -0.0426916 -0.224573 0.0184189 -0.0434294 -0.222877 0.0182213 -0.0433414 -0.224573 0.0191343 -0.0435899 -0.222827 0.0190655 -0.0435843 -0.222822 0.0191345 -0.0435899 -0.222807 0.0193417 -0.0435949 -0.222899 0.00899842 -0.0290735 -0.222899 0.00606224 -0.0216104 -0.224573 0.00899842 -0.0290735 -0.224573 0.0133524 -0.027053 -0.222426 0.0133524 -0.027053 -0.224573 0.0168847 -0.0336096 -0.224573 0.0211723 -0.0396991 -0.221497 0.0067305 -0.0213925 -0.222623 0.0080023 -0.0184909 -0.222252 0.00839254 -0.0184981 -0.22215 0.00929882 -0.0187034 -0.222363 0.00750559 -0.0186465 -0.222664 0.00760047 -0.0185845 -0.222683 0.00741159 -0.018655 -0.222841 0.00613578 -0.0199265 -0.222287 0.00623773 -0.0199114 -0.222885 0.00594508 -0.0207958 -0.222357 0.00602836 -0.0207333 -0.221469 0.00666704 -0.0209172 -0.220978 0.00787856 -0.0197142 -0.220833 0.00837381 -0.0198072 -0.220725 0.0088218 -0.0201172 -0.220778 0.00952323 -0.020482 -0.220951 0.00857442 -0.0194669 -0.220826 0.00914692 -0.0198518 -0.221035 0.00946261 -0.0196152 -0.221131 0.00741539 -0.0198161 -0.220939 0.00779175 -0.0203973 -0.221496 0.00735682 -0.0192076 -0.22186 0.00627453 -0.0208262 -0.222077 0.0100839 -0.0192711 -0.221904 0.00674277 -0.0193968 -0.22176 0.00737698 -0.01896 -0.222055 0.0074285 -0.018771 -0.221919 0.00827291 -0.0185994 -0.221791 0.00916014 -0.018772 -0.221695 0.00994799 -0.0193169 -0.22129 0.0102282 -0.0202522 -0.222851 0.00607729 -0.0200779 -0.222559 0.0062094 -0.0198164 -0.222469 0.0067475 -0.0191062 -0.222182 0.00672522 -0.0192302 -0.221626 0.00658428 -0.0214402 -0.221391 0.00677527 -0.0204588 -0.221283 0.00737027 -0.0194994 -0.221564 0.00658559 -0.0203076 -0.221777 0.00642814 -0.0201617 -0.222206 0.00619832 -0.021566 -0.22288 0.00595363 -0.0206521 -0.221652 0.00680239 -0.0196006 -0.221602 0.00815289 -0.0187822 -0.221326 0.00804173 -0.0190418 -0.221451 0.00898497 -0.0189263 -0.221161 0.00878418 -0.0191638 -0.221335 0.00973758 -0.019432 -0.221496 0.0201389 -0.0429319 -0.220781 0.0193361 -0.0411633 -0.220806 0.0194646 -0.0414342 -0.220725 0.0201844 -0.0412088 -0.220854 0.0194753 -0.041655 -0.221391 0.0187732 -0.0427296 -0.221098 0.0190419 -0.0421874 -0.221131 0.0196626 -0.0425483 -0.221274 0.0192355 -0.0427226 -0.221652 0.0195054 -0.043179 -0.220981 0.0193122 -0.0420106 -0.220978 0.0200022 -0.0422176 -0.220951 0.0205913 -0.041773 -0.221161 0.0209598 -0.0417646 -0.220778 0.0202655 -0.0404222 -0.220878 0.0194585 -0.0417412 -0.220833 0.0201968 -0.0417533 -0.220826 0.0205849 -0.0410834 -0.222445 0.0216098 -0.0405585 -0.22215 0.0216274 -0.0415881 -0.222363 0.0206895 -0.0431161 -0.221618 0.0210177 -0.0398224 -0.222426 0.0211723 -0.0396991 -0.222436 0.0215254 -0.040307 -0.222704 0.0204464 -0.0433016 -0.222721 0.0202884 -0.0433805 -0.222751 0.0199864 -0.0434939 -0.222206 0.0175313 -0.0426024 -0.221469 0.0183309 -0.0425678 -0.221777 0.0188303 -0.0431829 -0.222287 0.0189346 -0.0434797 -0.221904 0.0196428 -0.0433409 -0.222055 0.020543 -0.043112 -0.221919 0.0211503 -0.0425013 -0.221451 0.0212686 -0.0417276 -0.221695 0.0214724 -0.0407088 -0.222077 0.0215854 -0.0406205 -0.221791 0.0214938 -0.0416662 -0.222252 0.0213008 -0.0424571 -0.222469 0.0198882 -0.0434968 -0.222182 0.0197724 -0.0434472 -0.222559 0.0189983 -0.0435556 -0.222357 0.0181329 -0.0432022 -0.22186 0.0181908 -0.0429456 -0.221254 0.0183197 -0.0419738 -0.22176 0.0203567 -0.0430511 -0.221326 0.0206536 -0.0424511 -0.221602 0.0209316 -0.042501 -0.221035 0.0209561 -0.0409499 -0.221335 0.0212604 -0.0408211 -0.221626 0.00949648 -0.0288424 -0.221626 0.0178487 -0.0423493 -0.221254 0.007157 -0.0212535 -0.221254 0.00992765 -0.0283391 -0.221889 0.00636691 -0.0215111 -0.222382 0.00613659 -0.0215861 -0.222206 0.00912825 -0.0290133 -0.221254 0.0139262 -0.0357614 -0.221626 0.0132692 -0.0358453 -0.221889 0.01767 -0.0424918 -0.222206 0.0129239 -0.0360588 -0.222899 0.0128022 -0.0361341 -0.222381 0.0174805 -0.0426429 -0.222049 0.0211403 -0.0397247 -0.220691 0.0199827 -0.0406477 -0.220683 0.00911567 -0.0206149 -0.220781 0.0111091 -0.0277968 -0.221618 0.0131731 -0.0271362 -0.220691 0.00917919 -0.0205942 -0.220691 0.0119722 -0.0276935 -0.22129 0.0208453 -0.0399599 -0.220992 0.01625 -0.0340021 -0.220992 0.0205889 -0.0401643 -0.220691 0.0155905 -0.0344099 -0.222426 0.0168847 -0.0336096 -0.221618 0.0167165 -0.0337136 -0.220992 0.00991634 -0.0203538 -0.220992 0.0126755 -0.0273671 -0.221618 0.0104378 -0.0201838 -0.222049 0.0105868 -0.0201352 -0.220781 0.00839297 -0.0208505 -0.221019 0.00757178 -0.0204282 -0.220853 0.00806029 -0.0204645 -0.220795 0.00829026 -0.0206547 -0.221159 0.00724519 -0.0206689 -0.221018 0.00777498 -0.021052 -0.221056 0.00747671 -0.020468 -0.221241 0.0184846 -0.0421212 -0.221183 0.0187667 -0.0422187 -0.221018 0.0188279 -0.0415685 -0.220781 0.015029 -0.0350731 -0.220781 0.0148872 -0.0348448 -0.221254 0.0137815 -0.0355285 -0.220781 0.0112221 -0.0280416 -0.221254 0.0100429 -0.0285888 -0.22123 0.00713163 -0.0209542 -0.224773 0.00706492 -0.0213449 -0.224973 0.00714791 -0.0216044 -0.224773 0.00914157 -0.0200018 -0.224973 0.0103401 -0.0203169 -0.224973 0.0113469 -0.0209312 -0.224973 0.0105072 -0.0203793 -0.224773 0.010913 -0.0203557 -0.224773 0.0211356 -0.039331 -0.224973 0.0201131 -0.0410764 -0.224973 0.0196807 -0.0414086 -0.224773 0.0197856 -0.0415789 -0.224973 0.0190859 -0.0416801 -0.224773 0.0160029 -0.0408509 -0.224973 0.0178981 -0.0417727 -0.224973 0.0184428 -0.0417977 -0.224773 0.0196832 -0.0437664 -0.224773 0.0207586 -0.0405784 -0.224773 0.010816 -0.0200605 -0.224773 0.0104037 -0.0201273 -0.224773 0.01019 -0.0190355 -0.224773 0.00797387 -0.0182929 -0.224773 0.00794997 -0.0204364 -0.224773 0.00685667 -0.0187339 -0.224773 0.00605687 -0.01963 -0.224773 0.00666173 -0.0225475 -0.224773 0.00574516 -0.0207899 -0.224773 0.00587209 -0.0216724 -0.224773 0.00682024 -0.0238059 -0.224773 0.017263 -0.0428163 -0.224773 0.0170838 -0.0417336 -0.224773 0.0184542 -0.0419974 -0.224773 0.0121752 -0.021853 -0.224973 0.0119874 -0.0219215 -0.224773 0.0158131 -0.0299572 -0.228376 0.0171096 -0.0326346 -0.224973 0.015637 -0.030052 -0.228376 0.015637 -0.030052 -0.224773 0.010795 -0.0326606 -0.227939 0.0190863 -0.04168 -0.227815 0.0178987 -0.0417728 -0.224973 0.0171685 -0.0415525 -0.227721 0.0162632 -0.0408579 -0.224973 0.0205855 -0.0404783 -0.228178 0.0205942 -0.0404631 -0.228275 0.0209063 -0.0395809 -0.224973 0.0207721 -0.0400837 -0.224973 0.0209401 -0.0392301 -0.228349 0.011429 -0.0210149 -0.228046 0.00859184 -0.0203391 -0.224973 0.00916656 -0.0202002 -0.227983 0.00813026 -0.0205596 -0.224973 0.00686075 -0.0225673 -0.224973 0.00723565 -0.0214491 -0.227842 0.00723572 -0.021449 -0.224973 0.00805858 -0.0206043 -0.227966 0.00800919 -0.0206371 -0.222446 0.0113165 0.0212192 -0.224573 0.0112357 0.0211434 -0.222517 0.010317 0.02063 -0.224573 0.00814771 0.0210466 -0.22288 0.00723526 0.0228579 -0.222885 0.0072352 0.0230015 -0.222899 0.00740011 0.0238078 -0.224573 0.00740011 0.0238078 -0.224573 0.0107705 0.0310852 -0.222899 0.0199784 0.044184 -0.222426 0.0189101 0.0351492 -0.224573 0.014998 0.0288119 -0.222426 0.014998 0.0288119 -0.224573 0.0118682 0.0220539 -0.22123 0.0210814 0.043586 -0.220978 0.0225288 0.0435591 -0.220853 0.0219699 0.0430266 -0.220833 0.0226959 0.0430837 -0.220725 0.0226514 0.0425408 -0.221161 0.0234582 0.0430501 -0.221035 0.0234065 0.0422368 -0.220992 0.0229937 0.0414745 -0.221131 0.0222089 0.0439093 -0.221326 0.0231927 0.043754 -0.220951 0.0230909 0.0430801 -0.220826 0.0230438 0.0423919 -0.221391 0.0213323 0.0441423 -0.221159 0.0213853 0.0436303 -0.221469 0.0208812 0.0440069 -0.22186 0.0207637 0.0443923 -0.222889 0.0205206 0.0446331 -0.222448 0.0240573 0.0418736 -0.222077 0.0240152 0.0418708 -0.222426 0.0235488 0.0409758 -0.222606 0.0237552 0.0439191 -0.222575 0.0239175 0.0436385 -0.222252 0.023839 0.0437221 -0.222519 0.0241228 0.0430203 -0.222503 0.024152 0.0428155 -0.222559 0.0216057 0.0449536 -0.222736 0.022739 0.0447727 -0.222721 0.022883 0.0447029 -0.222623 0.0236516 0.0440616 -0.222182 0.0223713 0.0448 -0.221904 0.0222357 0.0447014 -0.22176 0.0229311 0.0443706 -0.221602 0.023473 0.0437875 -0.221451 0.0237643 0.0429949 -0.221335 0.0237026 0.0420903 -0.222469 0.0224898 0.0448426 -0.222055 0.0231206 0.0444205 -0.222363 0.0232669 0.044416 -0.221919 0.0236914 0.043775 -0.221791 0.0239855 0.0429203 -0.22215 0.0241143 0.0428345 -0.221695 0.0239076 0.0419656 -0.221618 0.0234017 0.0411079 -0.221497 0.0205013 0.0437142 -0.221626 0.0203869 0.043817 -0.221019 0.021757 0.0434678 -0.221056 0.021675 0.0435302 -0.221283 0.0224606 0.0441067 -0.221564 0.0213683 0.0443821 -0.222206 0.0200849 0.0440883 -0.222357 0.0207211 0.0446519 -0.222287 0.0215376 0.0448815 -0.221777 0.021416 0.0445914 -0.221652 0.022089 0.0445479 -0.221496 0.0227066 0.0442643 -0.22129 0.0232377 0.0412553 -0.221496 0.00855181 0.0213326 -0.220806 0.00951174 0.0226653 -0.221254 0.00847195 0.0233871 -0.221274 0.00828137 0.0222196 -0.221098 0.00864811 0.0226548 -0.221131 0.00864586 0.0219368 -0.221326 0.00922555 0.0211271 -0.220978 0.00910205 0.021808 -0.220826 0.0103757 0.0218706 -0.220878 0.00924276 0.022517 -0.220833 0.00960141 0.0218717 -0.220951 0.00978163 0.0215202 -0.220725 0.0100668 0.0221547 -0.220778 0.0107886 0.0224777 -0.222252 0.00954391 0.0205637 -0.222575 0.00965381 0.0205309 -0.222363 0.00866755 0.0207636 -0.222498 0.0105587 0.0207161 -0.222077 0.0112768 0.0212356 -0.222357 0.00731466 0.0229346 -0.222832 0.00742571 0.0219913 -0.222469 0.00793724 0.0212672 -0.222737 0.00810618 0.0210802 -0.222663 0.00875867 0.0206962 -0.222625 0.00913219 0.020584 -0.222895 0.00728274 0.0234114 -0.221777 0.00768008 0.0223403 -0.222287 0.00747522 0.0221016 -0.221904 0.00794955 0.0215576 -0.221602 0.00932132 0.0208615 -0.221451 0.0101596 0.0209563 -0.221695 0.0111438 0.0212893 -0.22129 0.0114789 0.0222067 -0.221791 0.0103254 0.020792 -0.22215 0.0104598 0.0207153 -0.221919 0.00943042 0.0206719 -0.222055 0.00859786 0.0208924 -0.222182 0.00792225 0.0213923 -0.222559 0.00744134 0.0220084 -0.22186 0.0075659 0.0230128 -0.221469 0.00796311 0.0230804 -0.221391 0.00804413 0.0226164 -0.221652 0.00802101 0.0217576 -0.22176 0.00855747 0.0210842 -0.221161 0.00997317 0.0212052 -0.221035 0.0106769 0.0216158 -0.221335 0.0109406 0.0214166 -0.220992 0.0111736 0.0223266 -0.221889 0.0202168 0.0439698 -0.221254 0.0160839 0.0374721 -0.221626 0.0154324 0.0375939 -0.222382 0.0200366 0.0441317 -0.222899 0.0149832 0.0379096 -0.221254 0.0116553 0.0302981 -0.221626 0.00791122 0.0236072 -0.221626 0.0112541 0.0308252 -0.221889 0.00769842 0.0236907 -0.222206 0.00753333 0.0237555 -0.222206 0.0151003 0.0378273 -0.222899 0.0107705 0.0310852 -0.222206 0.0108965 0.0310174 -0.222381 0.0074729 0.0237792 -0.220781 0.0129296 0.0299242 -0.220781 0.0169888 0.0364998 -0.220691 0.0176653 0.0360242 -0.220781 0.0128028 0.0296872 -0.220691 0.0104518 0.0226099 -0.221618 0.0187483 0.0352629 -0.220691 0.0136579 0.0295325 -0.220683 0.0223673 0.0420374 -0.220691 0.022417 0.0419928 -0.220778 0.0226861 0.0417509 -0.220992 0.0143408 0.0291653 -0.221618 0.0148239 0.0289055 -0.222426 0.0118682 0.0220539 -0.222049 0.01183 0.0220689 -0.220992 0.0182996 0.0355784 -0.221618 0.0116841 0.0221262 -0.222049 0.0235183 0.0410032 -0.221018 0.0213184 0.0429799 -0.220939 0.0218937 0.0432927 -0.220795 0.0219201 0.0427324 -0.220781 0.0218019 0.0425455 -0.221241 0.00842669 0.0231705 -0.221183 0.00848335 0.0228774 -0.220854 0.00932586 0.0225457 -0.220981 0.0089363 0.0225091 -0.220781 0.00968206 0.0229121 -0.221018 0.00907701 0.0231496 -0.221254 0.0117846 0.0305399 -0.221254 0.0159253 0.0372474 -0.220781 0.0171443 0.0367201 -0.221254 0.0208349 0.0434144 -0.224773 0.00703528 0.0230074 -0.224973 0.0232893 0.0405212 -0.228275 0.0232762 0.0408736 -0.228288 0.0232875 0.0407238 -0.228132 0.0228175 0.0421102 -0.228046 0.0223442 0.0426289 -0.227973 0.021851 0.0429565 -0.224973 0.0221603 0.04277 -0.227939 0.0215829 0.043076 -0.227833 0.020603 0.043249 -0.22772 0.0186093 0.0423013 -0.224773 0.018456 0.0424298 -0.224973 0.0186093 0.0423013 -0.224973 0.019661 0.0430616 -0.224773 0.019587 0.0432474 -0.224973 0.0204022 0.0432385 -0.224973 0.0209475 0.0432314 -0.224973 0.0215826 0.0430761 -0.224973 0.0225725 0.042413 -0.224773 0.0231875 0.0418779 -0.224973 0.0230088 0.0417882 -0.224773 0.0234904 0.0406104 -0.224773 0.0228248 0.0387687 -0.224973 0.0231173 0.0396571 -0.224773 0.0233042 0.039586 -0.224773 0.0135168 0.0236902 -0.224973 0.012481 0.0226948 -0.224773 0.0126002 0.0225342 -0.224773 0.0121686 0.0222698 -0.224973 0.0117649 0.0223172 -0.224973 0.0104746 0.0222072 -0.224973 0.00848354 0.0237379 -0.224973 0.00877364 0.023243 -0.224973 0.00928622 0.0227217 -0.224773 0.0112284 0.0219914 -0.224773 0.00721394 0.0238809 -0.224773 0.00861306 0.0231238 -0.224773 0.00976904 0.0222072 -0.224773 0.0236975 0.0408421 -0.224773 0.0243073 0.0420419 -0.224773 0.0242355 0.0433858 -0.224773 0.022275 0.0429339 -0.224773 0.0223016 0.0451236 -0.224773 0.0209706 0.04343 -0.224773 0.0209577 0.0450518 -0.224773 0.0148196 0.0380246 -0.224773 0.012775 0.0345603 -0.224773 0.0105943 0.0311799 -0.224773 0.00807024 0.0244955 -0.224973 0.0226715 0.0388971 -0.224773 0.0176253 0.0315662 -0.224973 0.0133333 0.0237697 -0.228376 0.0226715 0.0388971 -0.224973 0.0174552 0.0316712 -0.228376 0.0190773 0.0341627 -0.224973 0.0129452 0.0344552 -0.224773 0.00828602 0.0259549 -0.224973 0.00826891 0.0245185 -0.227819 0.00845352 0.0238075 -0.228046 0.00984928 0.0223904 -0.224973 0.00984851 0.0223907 -0.228268 0.0117647 0.0223171 -0.224973 0.0112055 0.0221901 -0.228168 0.0108311 0.0221735 -0.228357 0.0231197 0.0396634 -0.228349 0.0231775 0.039834 -0.229184 0.0157818 0.0292002 -0.228376 0.0159549 0.0291046 -0.228376 0.0174552 0.0316712 -0.228752 0.0226401 0.0389235 -0.229184 0.0189142 0.0342745 -0.229184 0.02252 0.0390241 -0.229511 0.0223511 0.0391657 -0.230111 0.0146231 0.0298406 -0.229511 0.0129496 0.0239358 -0.229809 0.0184619 0.0345848 -0.229809 0.0153017 0.0294655 -0.229809 0.0220996 0.0393764 -0.230023 0.0217829 0.0396418 -0.230111 0.0119369 0.0243742 -0.23002 0.0154565 0.0329045 -0.230111 0.0178225 0.0350233 -0.224973 0.00846956 0.0258755 -0.228109 0.010334 0.022234 -0.228491 0.0107223 0.02221 -0.228251 0.0115949 0.0222649 -0.228622 0.0117385 0.0223459 -0.229497 0.00957197 0.0246009 -0.229919 0.0106677 0.0242128 -0.230009 0.0110577 0.0245008 -0.229577 0.00977918 0.0236319 -0.22877 0.00899271 0.0233318 -0.227734 0.00826906 0.0251298 -0.227747 0.00825143 0.0248331 -0.229255 0.00906998 0.0244658 -0.228766 0.00858694 0.024976 -0.228869 0.00869708 0.0242028 -0.228359 0.00848436 0.0239718 -0.22827 0.00833335 0.0249067 -0.229401 0.00934656 0.0239806 -0.229023 0.0090709 0.0235288 -0.228493 0.00895975 0.0231678 -0.228206 0.00897034 0.0230426 -0.230023 0.0122694 0.0242303 -0.229809 0.0126484 0.0240662 -0.229184 0.0131518 0.0238482 -0.229458 0.0123267 0.0230822 -0.229098 0.0125254 0.0229482 -0.228752 0.0132956 0.0237859 -0.228376 0.0133333 0.0237697 -0.228717 0.0126565 0.0228901 -0.228823 0.0106126 0.0223218 -0.228981 0.0116067 0.022427 -0.229416 0.0104235 0.0227831 -0.229759 0.01207 0.0232901 -0.229611 0.0112688 0.0228514 -0.229321 0.0114466 0.0225966 -0.228348 0.0127062 0.0228822 -0.22772 0.00846956 0.0258755 -0.228238 0.00854129 0.0258444 -0.22873 0.00876352 0.0257482 -0.229157 0.00898598 0.0250297 -0.228993 0.00897344 0.0256573 -0.229399 0.00945192 0.0250099 -0.228087 0.0084473 0.0238801 -0.22795 0.00918201 0.0228061 -0.228346 0.00976065 0.0224608 -0.228653 0.00969552 0.0225917 -0.228949 0.0096618 0.0227844 -0.22914 0.0105101 0.0225148 -0.229212 0.00966465 0.0230323 -0.229764 0.0103234 0.0234668 -0.229821 0.0110882 0.0231724 -0.229939 0.0109201 0.0235295 -0.229967 0.0117778 0.0235548 -0.230069 0.0114789 0.0238492 -0.228766 0.0194658 0.0425994 -0.229885 0.0210608 0.0412008 -0.229986 0.0210588 0.0407746 -0.230069 0.0217694 0.0405194 -0.23002 0.0208715 0.0404056 -0.230111 0.0215053 0.0398744 -0.229365 0.0194919 0.0415617 -0.229401 0.0206966 0.0423664 -0.229577 0.0212025 0.0421356 -0.229578 0.0204922 0.0418362 -0.22969 0.0207657 0.0416794 -0.229764 0.0215936 0.0417231 -0.229611 0.0225672 0.0411543 -0.229759 0.0225342 0.0402417 -0.229741 0.0208659 0.0415809 -0.229939 0.0218047 0.0411621 -0.229821 0.0221993 0.0411719 -0.229967 0.0221665 0.0403842 -0.228622 0.0232296 0.040961 -0.228224 0.0231716 0.0413838 -0.228159 0.0229393 0.0419175 -0.228304 0.0232893 0.0405212 -0.228717 0.0231547 0.0398967 -0.228206 0.0213669 0.043123 -0.228346 0.0222415 0.0426767 -0.228085 0.0225724 0.042413 -0.227819 0.0204506 0.0432424 -0.228087 0.0203829 0.0432154 -0.22827 0.0194139 0.0428571 -0.227748 0.0194636 0.0429736 -0.228238 0.0186692 0.0422511 -0.228993 0.0190302 0.0419487 -0.229157 0.0195966 0.0422186 -0.228359 0.0203175 0.0431412 -0.228493 0.0212502 0.0430764 -0.22914 0.0225285 0.0419827 -0.228823 0.022747 0.0419774 -0.228981 0.023098 0.0410425 -0.229321 0.0228746 0.0411096 -0.229098 0.023044 0.0399878 -0.228491 0.0228961 0.0419294 -0.228653 0.0220953 0.0426763 -0.229376 0.0196655 0.0417216 -0.229255 0.0201385 0.0423963 -0.228869 0.0202064 0.0428475 -0.229023 0.0209772 0.0428153 -0.228771 0.0211183 0.0429735 -0.228949 0.0219078 0.0426201 -0.229212 0.0216874 0.0425066 -0.229416 0.0222498 0.0419399 -0.229458 0.022835 0.0401055 -0.23002 0.0138994 0.0302406 -0.229938 0.010737 0.0242428 -0.23002 0.0111781 0.0247028 -0.229463 0.00951845 0.0247102 -0.229639 0.0098674 0.0242924 -0.229692 0.0103521 0.0250604 -0.22969 0.00999155 0.0242266 -0.229803 0.0102983 0.0241545 -0.229445 0.020047 0.0418771 -0.229463 0.0201211 0.0418859 -0.229692 0.0201817 0.0409837 -0.23002 0.0171405 0.0354911 -0.229365 0.0165692 0.0378066 -0.229365 0.013925 0.0338504 -0.229365 0.0115733 0.0297136 -0.22772 0.0156356 0.0384806 -0.229365 0.00952624 0.025418 -0.228993 0.0110392 0.0299922 -0.228993 0.0134125 0.0341668 -0.228993 0.0160807 0.0381592 -0.22873 0.0188549 0.0420956 -0.228414 0.013067 0.03438 -0.228414 0.0086009 0.0258186 -0.228414 0.018719 0.0422094 -0.228414 0.0157516 0.0383968 -0.22772 0.0129452 0.0344552 -0.228414 0.0106793 0.03018 -0.22772 0.0105524 0.0302462 -0.224773 0.0151742 0.0287172 -0.224773 0.0190737 0.0350342 -0.224573 0.0189101 0.0351492 -0.224573 0.0149832 0.0379096 -0.224573 0.0235488 0.0409758 -0.224773 0.0235014 0.0445138 -0.224773 0.0198297 0.0443177 -0.224573 0.0072352 0.0230015 -0.224773 0.00727818 0.0218311 -0.224573 0.00745941 0.0219157 -0.224773 0.00802384 0.0208896 -0.224573 0.00806152 0.0211179 -0.224773 0.00911315 0.0203836 -0.224573 0.00915323 0.0205795 -0.224773 0.0103136 0.0204212 -0.224573 0.0102614 0.0206143 -0.224573 0.0103686 0.020646 -0.224573 0.0113951 0.0213002 -0.224773 0.0120544 0.0219808 -0.224773 0.0113691 0.0209944 -0.224773 0.0234892 0.0405153 -0.224573 0.0199784 0.044184 -0.224573 0.0210197 0.0448617 -0.22288 0.0207541 0.0447572 -0.224573 0.0222602 0.0449279 -0.222827 0.0216745 0.0449782 -0.224573 0.0217432 0.0449798 -0.224573 0.0233677 0.044365 -0.224573 0.0228829 0.0447029 -0.222663 0.023368 0.0443648 -0.224573 0.0237553 0.043919 -0.224573 0.0241117 0.0420832 -0.224573 0.024152 0.0428153 -0.224573 0.0240454 0.0433238 0.432478 0.02175 -0.07799 0.431395 0.022375 -0.076765 0.431228 0.023 -0.07799 0.431395 0.023625 -0.07799 0.432478 0.02425 -0.07799 0.433103 0.0240825 -0.07799 0.43356 0.023625 -0.076765 0.43356 0.023625 -0.07799 0.433728 0.023 -0.076765 0.43356 0.022375 -0.076765 0.431395 -0.023625 -0.076765 0.431853 -0.0240826 -0.07799 0.431395 -0.023625 -0.07799 0.431395 -0.022375 -0.076765 0.431395 -0.022375 -0.07799 0.432478 -0.02175 -0.07799 0.433103 -0.0219175 -0.076765 0.433728 -0.023 -0.076765 0.43356 -0.022375 -0.07799 0.433728 -0.023 -0.07799 0.43356 -0.023625 -0.076765 0.433103 -0.0240826 -0.07799 0.456786 0.0272721 -0.0815692 0.455613 0.0309849 -0.081752 0.456005 0.029668 -0.081636 0.456297 0.0284351 -0.0814621 0.45626 0.0279169 -0.081252 0.456559 0.0272375 -0.0814158 0.457144 0.0260159 -0.0816458 0.457422 0.0260164 -0.0816582 0.456975 0.0286555 -0.0816905 0.457307 0.0273547 -0.0816652 0.457045 0.0273127 -0.0816541 0.456869 0.0260152 -0.0815516 0.456504 0.0285013 -0.0816 0.456047 0.0286479 -0.0812962 0.455295 0.0307272 -0.0816644 0.454522 0.0315345 -0.0816766 0.454512 0.0320767 -0.0817606 0.454582 0.0310064 -0.0814231 0.453615 0.0322129 -0.0816785 0.456633 0.0260143 -0.0813824 0.456634 0.0250009 -0.0813848 0.456869 0.0250017 -0.0815538 0.457143 0.0250025 -0.0816483 0.453441 0.0319248 -0.0814444 0.451904 0.0333915 -0.0817389 0.451802 0.0330025 -0.0816682 0.453825 0.0325566 -0.0817577 0.456463 0.025 -0.0811657 0.457143 0.0239865 -0.0816507 0.445233 0.0321437 -0.0817621 0.446031 0.031807 -0.0814433 0.44568 0.0315519 -0.0814398 0.446798 0.0326227 -0.0816749 0.449827 0.0336693 -0.0817287 0.449827 0.0332649 -0.081661 0.445477 0.0318209 -0.0816792 0.448278 0.0331034 -0.0816657 0.448343 0.0327684 -0.0814409 0.456933 0.0221198 -0.0816739 0.453827 0.0174508 -0.081765 0.455895 0.0205523 -0.081514 0.456065 0.0213741 -0.0813068 0.456473 0.022222 -0.0814454 0.456635 0.023985 -0.0813872 0.455026 0.0189612 -0.0816718 0.456276 0.0203561 -0.0817121 0.456075 0.0204602 -0.0816386 0.456688 0.0221749 -0.0815911 0.457182 0.0220626 -0.0816886 0.454813 0.0192379 -0.0814168 0.45687 0.0239858 -0.081556 0.444357 0.0307309 -0.0816736 0.443139 0.0285355 -0.0816568 0.442713 0.028689 -0.081765 0.443054 0.027282 -0.0814976 0.442609 0.0260566 -0.0817047 0.442851 0.027316 -0.0816452 0.443645 0.0296893 -0.0816669 0.443949 0.0295147 -0.0813876 0.453619 0.0177853 -0.0816843 0.449827 0.0167162 -0.0816898 0.451798 0.0169828 -0.0816888 0.443133 0.0260566 -0.081265 0.44291 0.0260566 -0.081531 0.442609 0.025 -0.0817047 0.442267 0.0260566 -0.081765 0.442408 0.0224611 -0.081765 0.444737 0.01884 -0.0816776 0.445482 0.0176786 -0.081765 0.446907 0.0168999 -0.081765 0.447932 0.0165681 -0.081765 0.44291 0.0239433 -0.081531 0.443074 0.0225847 -0.0815004 0.442609 0.0239433 -0.0817047 0.442872 0.0225472 -0.0816465 0.448406 0.0168555 -0.0816893 0.447278 0.0175216 -0.0814639 0.447053 0.0172575 -0.0816873 0.443394 0.0218571 -0.0813411 0.443566 0.0213249 -0.08136 0.443235 0.0211929 -0.0816593 0.443862 0.0199462 -0.0816698 0.445812 0.0179317 -0.0816834 0.446029 0.0181882 -0.0814487 0.44291 0.025 -0.081531 0.442267 0.0239433 -0.081765 0.4518 0.0138174 -0.0816892 0.451731 0.0134974 -0.0814698 0.453662 0.0131853 -0.0816865 0.449827 0.0144142 -0.081765 0.448075 0.0138627 -0.0816893 0.446857 0.0139441 -0.081765 0.444633 0.0128609 -0.081765 0.441206 0.00865068 -0.081765 0.443216 0.0116914 -0.081765 0.443506 0.0114034 -0.0816777 0.441796 0.00790532 -0.0813483 0.441515 0.00673575 -0.0813149 0.442415 0.0100389 -0.0816699 0.441954 0.0083589 -0.0813609 0.441621 0.00848363 -0.0816595 0.441017 0.00505658 -0.081631 0.441157 0.0068033 -0.0816467 0.441227 0.00505658 -0.08147 0.441359 0.00676514 -0.0815009 0.449827 0.0140337 -0.0816898 0.446389 0.0133615 -0.0816873 0.444853 0.0125325 -0.0816834 0.446541 0.0130675 -0.0814632 0.443767 0.0111838 -0.0814276 0.443748 0.0111634 -0.0814272 0.458534 0.00752304 -0.0815795 0.45914 0.00497305 -0.0815531 0.457319 0.00901045 -0.0812662 0.457162 0.00968507 -0.0814693 0.45769 0.00858065 -0.0814114 0.458059 0.00740488 -0.0813563 0.454769 0.0125505 -0.0816809 0.457343 0.00978665 -0.0815918 0.457325 0.0106478 -0.0817001 0.457745 0.0100199 -0.0816739 0.455752 0.0112909 -0.081408 0.45576 0.0117641 -0.0816657 0.456628 0.0108314 -0.0816351 0.457015 0.00960483 -0.0813061 0.456898 0.00980442 -0.0813194 0.457894 0.00866017 -0.0815445 0.458282 0.0074593 -0.0815015 0.458572 0.0049719 -0.0814554 0.441017 0.00399996 -0.081631 0.458328 0.00497105 -0.0812844 0.458573 0.00400137 -0.0814575 0.458855 0.00400194 -0.0815493 0.458855 0.00497259 -0.0815471 0.45914 0.00400232 -0.0815557 0.441383 0.00399996 -0.081265 0.458329 0.00400068 -0.0812866 0.458573 0.00302902 -0.0814591 0.458855 0.00302945 -0.0815511 0.442396 -0.00274683 -0.081765 0.440692 0.00111962 -0.081765 0.442406 -0.00202494 -0.0816698 0.445025 -0.00424525 -0.0814483 0.446382 -0.00535864 -0.0816873 0.446972 -0.00523063 -0.0814659 0.441227 0.00294333 -0.08147 0.441358 0.00124475 -0.0815007 0.441954 -0.000358237 -0.0813608 0.440987 -4.66491e-05 -0.081765 0.441618 -0.000477189 -0.0816594 0.441569 0.000973774 -0.0813231 0.441156 0.00120681 -0.0816466 0.441017 0.00294333 -0.081631 0.448183 -0.00555009 -0.0814704 0.442595 -0.00166936 -0.0813944 0.4435 -0.00339716 -0.0816776 0.444838 -0.00452268 -0.0816834 0.448064 -0.00586057 -0.0816893 0.447281 -0.00607067 -0.081765 0.449827 -0.00603379 -0.0816898 0.458155 0.00302792 -0.0810648 0.45833 0.00302848 -0.0812883 0.458483 0.00157578 -0.0814837 0.45875 0.00153788 -0.0815674 0.459017 0.00149837 -0.0815741 0.45914 0.00302975 -0.0815577 0.458251 0.00160746 -0.0813283 0.453662 -0.00518535 -0.0816865 0.451789 -0.00581987 -0.0816892 0.449827 -0.00641426 -0.081765 0.457498 -0.00151784 -0.0815891 0.456491 -0.00300129 -0.0816452 0.457965 0.000208163 -0.0813847 0.456259 -0.00386693 -0.0817461 0.455188 -0.00424771 -0.081677 0.458423 7.44809e-05 -0.0816024 0.45818 0.000146443 -0.0815253 0.457314 -0.00142194 -0.0814646 0.456576 -0.00230915 -0.0813586 0.453616 -0.0322129 -0.0816785 0.454676 -0.0313978 -0.0816764 0.455026 -0.0316336 -0.0817594 0.455548 -0.0303966 -0.0816565 0.453441 -0.0319251 -0.0814444 0.45656 -0.0283214 -0.0815948 0.457415 -0.0263533 -0.0816579 0.45706 -0.0272175 -0.081653 0.456798 -0.0283926 -0.0816734 0.456135 -0.0294168 -0.0816283 0.456799 -0.0271795 -0.0815674 0.456571 -0.0271472 -0.0814129 0.456349 -0.0282599 -0.0814546 0.456188 -0.0282008 -0.0812687 0.455799 -0.0292566 -0.0813344 0.453826 -0.0325562 -0.0817577 0.449827 -0.033265 -0.081661 0.451804 -0.033002 -0.0816682 0.456463 -0.025 -0.0811657 0.456633 -0.0260144 -0.0813824 0.456869 -0.0260153 -0.0815516 0.457144 -0.026016 -0.0816458 0.457422 -0.0260165 -0.0816582 0.448192 -0.0334971 -0.0817353 0.448271 -0.0331021 -0.0816657 0.446633 -0.0329885 -0.08175 0.445469 -0.0318145 -0.0816792 0.444038 -0.031 -0.081765 0.446796 -0.032622 -0.0816749 0.446932 -0.0323128 -0.0814459 0.456634 -0.025001 -0.0813848 0.456869 -0.0250018 -0.0815538 0.457143 -0.0250025 -0.0816483 0.45687 -0.0239859 -0.081556 0.44327 -0.0299047 -0.081765 0.443644 -0.0296896 -0.0816669 0.44285 -0.0273125 -0.0816452 0.443053 -0.0272786 -0.0814975 0.442609 -0.0260567 -0.0817047 0.443949 -0.0295151 -0.0813874 0.444357 -0.0307309 -0.0816736 0.44314 -0.0285378 -0.0816568 0.443571 -0.0286892 -0.0813604 0.443477 -0.0284191 -0.081351 0.443209 -0.0272525 -0.0813094 0.456934 -0.0221255 -0.0816738 0.45742 -0.0239871 -0.0816646 0.456689 -0.0221805 -0.081591 0.457143 -0.0239866 -0.0816507 0.456055 -0.0213459 -0.0813084 0.455897 -0.0205562 -0.0815139 0.455752 -0.0206293 -0.0813502 0.455029 -0.0189649 -0.0816718 0.456077 -0.0204642 -0.0816385 0.455868 -0.0193081 -0.0817501 0.456482 -0.0202532 -0.0817305 0.457183 -0.0220685 -0.0816885 0.454648 -0.0190583 -0.0814234 0.453619 -0.0177853 -0.0816843 0.456635 -0.0239851 -0.0813872 0.456474 -0.0222274 -0.0814452 0.455244 -0.0197811 -0.0813938 0.443133 -0.0260567 -0.081265 0.44291 -0.0260567 -0.081531 0.44291 -0.025 -0.081531 0.449827 -0.0170429 -0.0814721 0.451908 -0.016616 -0.081765 0.449827 -0.0163358 -0.081765 0.453444 -0.0180687 -0.0814516 0.451807 -0.0169855 -0.0816888 0.442609 -0.025 -0.0817047 0.44291 -0.0239434 -0.081531 0.442609 -0.0239434 -0.0817047 0.442267 -0.025 -0.081765 0.442267 -0.0239434 -0.081765 0.449827 -0.0167163 -0.0816898 0.448416 -0.0168537 -0.0816893 0.448345 -0.0164787 -0.081765 0.447058 -0.0172552 -0.0816874 0.447143 -0.0168083 -0.081765 0.445604 -0.0175949 -0.081765 0.44351 -0.0197067 -0.081765 0.442822 -0.0210206 -0.081765 0.442874 -0.0225384 -0.0816466 0.443076 -0.0225761 -0.0815005 0.447446 -0.017458 -0.0814653 0.442465 -0.0221848 -0.081765 0.443133 -0.0239434 -0.081265 0.445824 -0.0179232 -0.0816834 0.444743 -0.0188341 -0.0816776 0.44387 -0.0199343 -0.0816698 0.44416 -0.0201263 -0.0813984 0.443238 -0.0211867 -0.0816593 0.420704 0.0192 -0.0621073 0.422073 0.0194877 -0.0621073 0.420704 0.01882 -0.061765 0.418693 0.01882 -0.061765 0.416036 0.0204784 -0.0621073 0.417218 0.0195362 -0.0621073 0.415739 0.0202413 -0.061765 0.418693 0.0192 -0.0621073 0.428677 0.0435922 -0.0621073 0.426083 0.0388652 -0.061765 0.426399 0.0386523 -0.0621073 0.423374 0.0346276 -0.061765 0.422828 0.0332311 -0.0621073 0.418754 0.0280757 -0.0621073 0.415734 0.0249521 -0.061765 0.431835 0.0512334 -0.0621073 0.433371 0.0519799 -0.061765 0.430017 0.0487579 -0.0621073 0.430324 0.0504376 -0.061765 0.433371 0.0516 -0.0621073 0.455224 0.0519799 -0.0575365 0.447508 0.0519799 -0.0602669 0.4468 0.0519799 -0.0604577 0.445936 0.0516 -0.0610249 0.443511 0.0519799 -0.0611697 0.442762 0.0519799 -0.0612903 0.442362 0.0516 -0.0616939 0.439441 0.0519799 -0.0616452 0.43535 0.0519799 -0.0617639 0.463067 0.0519799 -0.0544314 0.475487 0.0370155 -0.0521693 0.474296 0.0406277 -0.0522373 0.475325 0.0388521 -0.0518524 0.470156 0.0473112 -0.0527578 0.471054 0.0468087 -0.0523041 0.47253 0.044819 -0.0520949 0.471505 0.0456916 -0.0525352 0.472746 0.0438076 -0.0523768 0.470087 0.0473844 -0.0527706 0.469112 0.0487809 -0.0526709 0.467335 0.049739 -0.0533939 0.466247 0.0508152 -0.0533974 0.464609 0.0512862 -0.0542118 0.472635 0.03275 -0.052396 0.473029 0.03275 -0.0522819 0.473858 0.0327686 -0.0519559 0.474961 0.0341675 -0.0521983 0.475157 0.0338221 -0.0518618 0.475612 0.0345617 -0.0518377 0.475416 0.0350494 -0.0521728 0.475886 0.0353863 -0.0518252 0.475461 0.035191 -0.0521706 0.475839 0.0371123 -0.0518273 0.473927 0.02475 -0.0522582 0.477669 0.0216223 -0.051776 0.477552 0.0223118 -0.0517778 0.474389 0.0248971 -0.0520494 0.47731 0.022961 -0.051782 0.476486 0.0240729 -0.0518029 0.476949 0.0235572 -0.0517898 0.475597 0.0243352 -0.0521388 0.475781 0.0242275 -0.05213 0.47593 0.0244963 -0.0518234 0.474874 0.0246276 -0.0521815 0.474729 0.0246641 -0.0521917 0.474637 0.0249996 -0.0518948 0.477393 0.0211466 -0.0520826 0.474768 0.0168134 -0.051886 0.474024 0.0169405 -0.0521425 0.4772 0.0185202 -0.0517842 0.476675 0.0183098 -0.0520978 0.475945 0.0176381 -0.052123 0.47582 0.017557 -0.0521285 0.475388 0.0173313 -0.0521502 0.475498 0.0170435 -0.0518434 0.474909 0.0171647 -0.0521795 0.477281 0.019445 -0.0520845 0.477527 0.0192042 -0.0517782 0.473527 0.01705 -0.0522949 0.474215 0.00365598 -0.0520803 0.473623 0.00349996 -0.0522851 0.473633 0.00354003 -0.0522447 0.477864 0.000827776 -0.0517734 0.477119 0.00188779 -0.0520871 0.477305 0.00216675 -0.0517821 0.476631 0.00250414 -0.0520988 0.476842 0.00272745 -0.0517925 0.476365 0.00274378 -0.0521071 0.47537 0.00330189 -0.0521514 0.474427 0.00371833 -0.0519959 0.47463 0.00378839 -0.0518953 0.477936 9.9958e-05 -0.0517726 0.477936 -0.000100042 -0.0517726 0.474427 -0.00371841 -0.0519959 0.474934 -0.00374114 -0.0518753 0.476011 -0.00299425 -0.0521203 0.476136 -0.0029133 -0.0521153 0.476844 -0.00272565 -0.0517925 0.476867 -0.002242 -0.0520926 0.477309 -0.00216155 -0.051782 0.476958 -0.00212437 -0.0520905 0.477652 -0.00152169 -0.0517762 0.477427 -0.0012486 -0.0520817 0.477474 -0.00110721 -0.052081 0.477627 -0.000100042 -0.052079 0.474215 -0.00365607 -0.0520803 0.474227 -0.00350004 -0.0522327 0.473527 -0.01705 -0.0522953 0.474033 -0.01705 -0.0522495 0.474024 -0.0169406 -0.052143 0.475249 -0.0172748 -0.0521584 0.474582 -0.0167792 -0.0518987 0.475388 -0.0173314 -0.0521505 0.47623 -0.017855 -0.0521122 0.47616 -0.0174124 -0.0518142 0.476738 -0.017912 -0.0517954 0.476965 -0.018728 -0.052091 0.477199 -0.018517 -0.0517842 0.477527 -0.0192018 -0.0517782 0.477038 -0.018859 -0.0520894 0.477237 -0.0193109 -0.0520856 0.47737 -0.0197952 -0.0520834 0.477426 -0.0206813 -0.0520825 0.477703 -0.0211665 -0.0517755 0.477393 -0.0211467 -0.052083 0.477735 -0.0207027 -0.0517751 0.474847 -0.0246349 -0.0521838 0.475757 -0.0242422 -0.0521315 0.476613 -0.023489 -0.0520998 0.475936 -0.0244936 -0.0518231 0.476954 -0.0235527 -0.0517897 0.477312 -0.0229592 -0.051782 0.47767 -0.0216224 -0.051776 0.473948 -0.0247503 -0.0522565 0.47397 -0.0247512 -0.0522538 0.473927 -0.02475 -0.0522586 0.422073 -0.0194877 -0.062145 0.420704 -0.0192 -0.062145 0.415768 -0.0202649 -0.061765 0.415045 -0.0217638 -0.061765 0.415043 -0.0234282 -0.061765 0.415763 -0.0249287 -0.061765 0.422828 -0.0332311 -0.062145 0.423462 -0.034686 -0.061765 0.426183 -0.0389685 -0.061765 0.426399 -0.0386524 -0.062145 0.427116 -0.0399938 -0.062145 0.430017 -0.048758 -0.062145 0.430355 -0.0504154 -0.061765 0.430631 -0.0502127 -0.062145 0.431835 -0.0512334 -0.062145 0.431681 -0.0515389 -0.061765 0.434327 -0.0516 -0.062145 0.43973 -0.0516 -0.0620062 0.454495 -0.0519424 -0.0578293 0.453013 -0.0516 -0.0588178 0.463182 -0.0516 -0.0547938 0.44675 -0.0519424 -0.0604708 0.444972 -0.0516 -0.0612781 0.444995 -0.0519424 -0.0608851 0.436443 -0.0519424 -0.0617555 0.463054 -0.0519424 -0.0544359 0.473676 -0.0420434 -0.0523264 0.474124 -0.0418234 -0.0519334 0.475529 -0.0380661 -0.0518418 0.472965 -0.0440399 -0.0520443 0.472335 -0.0450383 -0.0521192 0.471344 -0.0459064 -0.0526015 0.470871 -0.0465002 -0.052676 0.470157 -0.0473098 -0.0528008 0.465039 -0.051406 -0.053765 0.464634 -0.0515971 -0.0538954 0.475576 -0.0345775 -0.0518395 0.475384 -0.0349596 -0.0522138 0.475847 -0.035394 -0.0518269 0.475594 -0.0359796 -0.0522034 0.475924 -0.0362524 -0.0518236 0.474811 -0.0339739 -0.0522474 0.475125 -0.0338453 -0.0518637 0.474073 -0.0333132 -0.0523037 0.473947 -0.0332339 -0.0523148 0.472891 -0.0328212 -0.0524272 0.473034 -0.0328541 -0.0524099 0.431627 -0.0101 -0.062065 0.431327 -0.00850317 -0.061765 0.464627 -0.0355 -0.0647624 0.464627 0.0409 -0.0647624 0.464071 0.0436935 -0.0647624 0.46012 0.0476443 -0.0647624 0.457327 0.0482 -0.0647624 0.462477 -0.039224 -0.0647624 0.464311 -0.0378 -0.0644624 0.442327 0.0482 -0.0647624 0.460327 -0.0398 -0.0647624 0.439533 0.0476443 -0.0647624 0.439418 0.0479214 -0.0644624 0.436953 0.046274 -0.0644624 0.435582 0.0436935 -0.0647624 0.439327 -0.0401 -0.0644624 0.436074 -0.0387527 -0.0644624 0.437177 -0.039224 -0.0647624 0.435354 -0.0371456 -0.0647624 0.435603 -0.03765 -0.0647624 0.459011 0.033684 -0.071145 0.459223 0.0338962 -0.070845 0.454627 0.0355 -0.071145 0.454627 -0.0358 -0.070845 0.457114 -0.0353053 -0.070845 0.459223 -0.0338962 -0.070845 0.460355 -0.0316727 -0.071145 0.461127 -0.0293 -0.070845 0.445027 0.0358 -0.070845 0.442654 0.035028 -0.071145 0.442539 0.0353052 -0.070845 0.440643 0.033684 -0.071145 0.439022 0.0317874 -0.070845 0.438527 -0.0293 -0.070845 0.439299 -0.0316727 -0.071145 0.439022 -0.0317875 -0.070845 0.440431 -0.0338962 -0.070845 0.442654 -0.0350281 -0.071145 0.442539 -0.0353053 -0.070845 0.438827 -0.0293 -0.071145 0.460624 -0.0474994 -0.0644624 0.461651 -0.046046 -0.0644624 0.461012 -0.0427824 -0.0647624 0.461881 -0.0442811 -0.0644624 0.46126 -0.0426132 -0.0644624 0.458204 -0.0413 -0.0647624 0.457327 -0.0482 -0.0647624 0.442327 -0.0485 -0.0644624 0.441449 -0.0413 -0.0647624 0.440617 -0.0483052 -0.0644624 0.441449 -0.041 -0.0644624 0.439862 -0.0416934 -0.0647624 0.439722 -0.0414281 -0.0644624 0.437773 -0.0442811 -0.0644624 0.438282 -0.0459368 -0.0647624 0.438003 -0.046046 -0.0644624 0.422027 -0.0101 -0.054065 0.422616 -0.0195 -0.054065 0.426427 -0.0217 -0.054065 0.424377 -0.0208507 -0.053765 0.426427 -0.0214 -0.053765 0.423528 -0.0072009 -0.053765 0.423316 -0.00698877 -0.054065 0.422362 -0.00841623 -0.054065 0.422327 -0.0101 -0.053765 0.427227 -0.0214 -0.053765 0.426427 -0.00600004 -0.053765 0.429427 -0.0211106 -0.054065 0.431037 -0.0195 -0.054065 0.430777 -0.01935 -0.053765 0.431037 -0.00790004 -0.054065 0.429427 -0.00628953 -0.054065 0.429277 -0.00654934 -0.053765 0.430927 -0.0173 -0.053765 0.430627 -0.0173 -0.054065 0.430627 -0.0101 -0.054065 0.428927 -0.00715556 -0.054065 0.427227 -0.021 -0.053765 0.428927 -0.0202445 -0.054065 0.429077 -0.0205043 -0.053765 0.426427 -0.00670004 -0.054065 0.427227 -0.00640004 -0.053765 0.425126 -0.00695885 -0.054065 0.424023 -0.00769588 -0.054065 0.423811 -0.00748375 -0.053765 0.423286 -0.00879892 -0.054065 0.423027 -0.0101 -0.054065 0.422727 -0.0173 -0.053765 0.423482 -0.019 -0.054065 0.424727 -0.0202445 -0.054065 0.424577 -0.0205043 -0.053765 0.423027 -0.0173 -0.054065 0.422727 -0.0101 -0.053765 0.424743 0.021365 -0.054065 0.422362 0.0189838 -0.054065 0.431627 0.0173 -0.054065 0.431292 0.0189838 -0.054065 0.431015 0.018869 -0.053765 0.430126 0.0201991 -0.053765 0.428911 0.021365 -0.054065 0.431627 0.0101 -0.054065 0.431327 0.0101 -0.053765 0.422876 0.00804996 -0.053765 0.424227 0.00628945 -0.054065 0.424377 0.00654925 -0.053765 0.429427 0.00628945 -0.054065 0.429277 0.00654925 -0.053765 0.427227 0.00569996 -0.054065 0.426427 0.021 -0.053765 0.425126 0.0204411 -0.054065 0.424023 0.0197041 -0.054065 0.425011 0.0207183 -0.053765 0.423811 0.0199163 -0.053765 0.423027 0.0173 -0.054065 0.422727 0.0173 -0.053765 0.426427 0.0207 -0.054065 0.423027 0.0101 -0.054065 0.424727 0.00715547 -0.054065 0.424577 0.00689566 -0.053765 0.430627 0.0173 -0.054065 0.430368 0.0186011 -0.054065 0.428528 0.0204411 -0.054065 0.429843 0.0199163 -0.053765 0.427227 0.00669996 -0.054065 0.426427 0.00639996 -0.053765 0.430927 0.0173 -0.053765 0.429077 0.00689566 -0.053765 0.430431 0.00824996 -0.053765 0.430627 0.0101 -0.054065 0.468927 -0.01245 -0.042735 0.469486 -0.0137512 -0.043035 0.469208 -0.013866 -0.042735 0.472627 -0.01615 -0.042735 0.470927 -0.00515556 -0.043035 0.469682 -0.00640004 -0.043035 0.470777 -0.00489575 -0.042735 0.469227 -0.00810004 -0.043035 0.472627 -0.01585 -0.043035 0.473027 -0.01585 -0.043035 0.473027 -0.00440004 -0.042735 0.476427 -0.01245 -0.043035 0.475431 -0.0148542 -0.043035 0.475971 -0.01415 -0.043035 0.476231 -0.0143 -0.042735 0.474443 -0.00468169 -0.042735 0.475431 -0.00569588 -0.043035 0.476168 -0.00679892 -0.043035 0.476445 -0.00668411 -0.042735 0.475971 -0.00640004 -0.043035 0.476727 -0.01245 -0.042735 0.472627 -0.00350004 -0.043035 0.469374 -0.00484735 -0.043035 0.470477 -0.00437613 -0.042735 0.468327 -0.00810004 -0.042735 0.477327 -0.00810004 -0.042735 0.468027 -0.01245 -0.043035 0.477627 -0.00810004 -0.043035 0.477627 -0.01245 -0.043035 0.468327 -0.01245 -0.042735 0.468654 -0.0140956 -0.042735 0.469374 -0.0157027 -0.043035 0.475177 -0.016174 -0.042735 0.476279 -0.0157027 -0.043035 0.477011 -0.01475 -0.043035 0.473027 -0.01705 -0.043035 0.472627 -0.01705 -0.043035 0.469227 0.00809996 -0.043035 0.469227 0.01245 -0.043035 0.469682 0.00639996 -0.043035 0.470927 0.00515547 -0.043035 0.470777 0.00489566 -0.042735 0.470777 0.0156543 -0.042735 0.473027 0.00439996 -0.042735 0.476727 0.00809996 -0.042735 0.475971 0.00639996 -0.043035 0.476727 0.01245 -0.042735 0.474727 0.0153944 -0.043035 0.473027 0.01585 -0.043035 0.476427 0.01245 -0.043035 0.468903 0.0146 -0.042735 0.475177 0.0161739 -0.042735 0.475327 0.0164337 -0.043035 0.473027 0.01705 -0.043035 0.473027 0.01675 -0.042735 0.468327 0.00809996 -0.042735 0.468027 0.00809996 -0.043035 0.468643 0.00579996 -0.043035 0.470327 0.00411624 -0.043035 0.473027 0.00379996 -0.042735 0.475327 0.00411624 -0.043035 0.476751 0.00594996 -0.042735 0.476279 0.00484727 -0.043035 0.477011 0.00579996 -0.043035 0.472627 0.00349996 -0.043035 0.408099 -0.0152609 -0.0634806 0.414645 -0.0134392 -0.062965 0.41348 -0.015409 -0.0663002 0.41347 -0.0154598 -0.0662267 0.414045 -0.0140773 -0.0642514 0.413289 -0.0145219 -0.062965 0.414012 -0.0139499 -0.062965 0.411368 -0.0167918 -0.0638361 0.41147 -0.0158035 -0.063045 0.409209 -0.0165936 -0.0635643 0.409489 -0.0157968 -0.062965 0.413146 -0.0148669 -0.0633982 0.413079 -0.0161125 -0.0652174 0.413615 -0.0146226 -0.0640488 0.409665 -0.017135 -0.0638739 0.413315 -0.0158284 -0.0656733 0.413018 -0.0161669 -0.0651262 0.411153 -0.0177184 -0.0648834 0.412027 -0.0173972 -0.0651884 0.412016 -0.0166687 -0.0641721 0.41225 -0.0165949 -0.0643344 0.410662 -0.0168204 -0.0636168 0.408493 -0.0172478 -0.0646057 0.412855 -0.0168404 -0.0663002 0.411655 -0.0178412 -0.0663002 0.412652 -0.0170425 -0.0658548 0.41062 -0.0181653 -0.0663002 0.410135 -0.0182 -0.0663002 0.409378 -0.0180211 -0.0655185 0.410206 -0.0179414 -0.0650014 0.410889 -0.0169774 -0.0638001 0.404312 -0.0173956 -0.0702994 0.404925 -0.0178375 -0.0705656 0.405694 -0.0177721 -0.0689043 0.405616 -0.0181107 -0.0708655 0.405107 -0.017253 -0.0685178 0.404662 -0.016596 -0.068225 0.405679 -0.0163741 -0.0666481 0.406081 -0.017114 -0.0669812 0.406643 -0.0177079 -0.0674461 0.406373 -0.0180948 -0.0693508 0.407309 -0.0180794 -0.067997 0.408799 -0.0176058 -0.0649212 0.407929 -0.0160307 -0.0640243 0.406327 -0.0182 -0.0711739 0.40406 -0.017334 -0.0711739 0.403513 -0.016626 -0.0706204 0.399994 -0.00960846 -0.070102 0.401193 -0.0109799 -0.0687166 0.400877 -0.0113225 -0.0696138 0.402989 -0.0148977 -0.068997 0.401773 -0.0131009 -0.0694762 0.40251 -0.0148162 -0.0705481 0.402666 -0.0149047 -0.0697494 0.403102 -0.0157916 -0.0700945 0.403305 -0.0163582 -0.0711739 0.401362 -0.00543556 -0.071051 0.402398 -0.00508418 -0.0706398 0.402166 -0.00511072 -0.071051 0.402227 -0.00509536 -0.071051 0.399973 -0.00986585 -0.0707603 0.403027 -0.00500004 -0.071051 0.402708 -0.00502139 -0.0708429 0.401883 -0.00519838 -0.071051 0.400314 -0.00635109 -0.071051 0.401234 -0.0055602 -0.0705223 0.399629 -0.00827887 -0.071051 0.399747 -0.00750463 -0.071051 0.400211 -0.00889727 -0.0692109 0.399681 -0.00882305 -0.0706213 0.399774 -0.00756819 -0.0705124 0.400679 -0.00647873 -0.0695164 0.400317 -0.00642813 -0.0704778 0.400124 -0.00663055 -0.071051 0.40148 -0.00903461 -0.0675936 0.400251 -0.00915175 -0.069237 0.406318 -0.00880522 -0.0631369 0.406529 -0.00802094 -0.062965 0.407911 -0.00612233 -0.062965 0.408383 -0.00583698 -0.062965 0.408737 -0.00566286 -0.062965 0.41109 -0.00504915 -0.062965 0.407255 -0.00500004 -0.0667247 0.410113 -0.00520912 -0.062965 0.409902 -0.00525944 -0.062965 0.400803 -0.00627821 -0.0695976 0.401254 -0.00574065 -0.0698921 0.402394 -0.00508515 -0.0706374 0.406433 -0.00526854 -0.0656857 0.400181 -0.00839568 -0.0691909 0.40145 -0.00764625 -0.0676654 0.402691 -0.0075814 -0.0663767 0.401647 -0.00690863 -0.0678357 0.400254 -0.00763523 -0.0692386 0.400464 -0.00692203 -0.0693759 0.405187 -0.00749558 -0.0641822 0.401976 -0.00623292 -0.0681211 0.405647 -0.00615816 -0.0647374 0.402879 -0.00685951 -0.0665689 0.403185 -0.00620066 -0.0668818 0.40359 -0.00566092 -0.0672951 0.404058 -0.00527778 -0.0677725 0.402415 -0.00567837 -0.0685024 0.404544 -0.00500004 -0.0691936 0.402926 -0.00528475 -0.0689452 0.405187 0.0074955 -0.0641822 0.406502 0.00856866 -0.062965 0.402879 0.00685943 -0.0665689 0.402708 0.0050213 -0.0708429 0.403955 0.00499996 -0.0698375 0.403027 0.00499996 -0.071051 0.409116 0.00550565 -0.062965 0.409904 0.00525898 -0.062965 0.405647 0.00615808 -0.0647374 0.406981 0.00699982 -0.062965 0.40708 0.00687228 -0.062965 0.401647 0.00690855 -0.0678357 0.40145 0.00764616 -0.0676654 0.400254 0.00763514 -0.0692386 0.400211 0.00889719 -0.0692109 0.4066 0.00773792 -0.062965 0.402926 0.00528467 -0.0689452 0.402415 0.00567829 -0.0685024 0.406433 0.00526846 -0.0656857 0.405095 0.00499996 -0.0686411 0.404058 0.00527769 -0.0677725 0.40359 0.00566083 -0.0672951 0.400679 0.00647864 -0.0695164 0.403532 0.00890873 -0.0654996 0.402691 0.00758131 -0.0663767 0.401976 0.00623284 -0.0681211 0.403185 0.00620057 -0.0668818 0.40801 0.00605664 -0.062965 0.400005 0.00995814 -0.071051 0.400317 0.00642805 -0.0704778 0.399774 0.00756811 -0.0705124 0.401234 0.00556012 -0.0705223 0.401279 0.00548353 -0.071051 0.400124 0.00663047 -0.071051 0.401883 0.00519829 -0.071051 0.402227 0.00509527 -0.071051 0.402398 0.0050841 -0.0706398 0.402743 0.00501184 -0.071051 0.401254 0.00574057 -0.0698921 0.402394 0.00508506 -0.0706374 0.400803 0.00627813 -0.0695976 0.400464 0.00692195 -0.0693759 0.400181 0.0083956 -0.0691909 0.399681 0.00882296 -0.0706213 0.399993 0.00961087 -0.0701076 0.403101 0.0157908 -0.0700987 0.402921 0.0156128 -0.0707849 0.402667 0.0149079 -0.0697552 0.401082 0.0120481 -0.0705107 0.399973 0.00986578 -0.0707603 0.403417 0.0158891 -0.0694366 0.402991 0.0149016 -0.0689983 0.401775 0.013108 -0.069482 0.400879 0.0113291 -0.0696188 0.401196 0.010985 -0.0687157 0.400251 0.00915167 -0.069237 0.40406 0.017334 -0.0711739 0.403511 0.0166244 -0.0706237 0.405113 0.0179761 -0.0711739 0.406327 0.0182 -0.0711739 0.404925 0.0178374 -0.0705656 0.408007 0.0182 -0.0685619 0.408493 0.0172477 -0.0646057 0.406649 0.0177075 -0.0674375 0.408799 0.0176057 -0.0649212 0.407315 0.0180792 -0.0679889 0.406088 0.0171131 -0.0669723 0.40638 0.0180946 -0.0693383 0.410135 0.0182 -0.0663002 0.405616 0.0181106 -0.0708655 0.404312 0.0173955 -0.0702994 0.405702 0.0177714 -0.0688908 0.403823 0.0168271 -0.0700869 0.405115 0.0172517 -0.0685035 0.409209 0.0165935 -0.0635643 0.407929 0.0160306 -0.0640243 0.410889 0.0169773 -0.0638001 0.412652 0.0170424 -0.0658548 0.413018 0.0161668 -0.0651262 0.413315 0.0158283 -0.0656733 0.412027 0.0173971 -0.0651884 0.411572 0.0178814 -0.0663002 0.411153 0.0177183 -0.0648834 0.411134 0.01805 -0.0663002 0.409378 0.018021 -0.0655185 0.41062 0.0181652 -0.0663002 0.409665 0.017135 -0.0638739 0.410206 0.0179413 -0.0650014 0.411368 0.0167917 -0.0638361 0.408099 0.0152608 -0.0634806 0.410662 0.0168203 -0.0636168 0.410125 0.0159736 -0.062965 0.4094 0.0166452 -0.0635407 0.409408 0.0157561 -0.062965 0.411681 0.0156124 -0.062965 0.410779 0.0159398 -0.062965 0.41147 0.0158035 -0.063045 0.412016 0.0166686 -0.0641721 0.41225 0.0165949 -0.0643344 0.413146 0.0148668 -0.0633982 0.413615 0.0146225 -0.0640488 0.41347 0.0154597 -0.0662267 0.413079 0.0161124 -0.0652174 0.402987 0.0169498 -0.077765 0.402343 0.016575 -0.0777216 0.399665 0.0123094 -0.0777237 0.398889 0.0094787 -0.077765 0.402546 0.0164128 -0.077765 0.400871 0.0145148 -0.0777225 0.399895 0.0122023 -0.077765 0.3982 0.00507466 -0.077765 0.397944 3.18794e-07 -0.0777309 0.400505 0.0147468 -0.0773689 0.401931 0.0169041 -0.0771069 0.403538 0.0186844 -0.0772636 0.403633 0.0185956 -0.0774802 0.397727 0.00499375 -0.0776137 0.397957 0.00498175 -0.077729 0.398206 0.00747435 -0.0777271 0.398536 0.0100197 -0.0775971 0.398767 0.00994968 -0.0777252 0.400661 0.0146479 -0.0775848 0.403888 0.0182 -0.0777497 0.397537 -2.6936e-08 -0.0774478 0.397544 0.00500321 -0.0774305 0.397792 0.00754051 -0.0774127 0.397973 0.0075116 -0.0776054 0.399443 0.0124129 -0.0775901 0.402003 0.0168466 -0.0773609 0.402148 0.0167313 -0.077581 0.397422 -4.19903e-08 -0.0772374 0.397434 0.00500896 -0.0772109 0.398359 0.0100732 -0.0773949 0.399275 0.0124908 -0.0773802 0.398682 0.011337 -0.0771456 0.399187 0.0125319 -0.0771353 0.399876 -0.0121618 -0.077765 0.398356 -0.0068092 -0.077765 0.398749 -0.00989103 -0.0777253 0.39819 -0.00488022 -0.077765 0.397414 -0.0045282 -0.0772158 0.39778 -0.00746426 -0.0774132 0.398682 -0.0113374 -0.0771457 0.398981 -0.0120738 -0.0771393 0.401994 -0.0168346 -0.0773609 0.400124 -0.0143067 -0.077122 0.401473 -0.0163129 -0.07711 0.403576 -0.0186543 -0.0773642 0.400488 -0.0147207 -0.0773691 0.399423 -0.0123712 -0.0775902 0.399256 -0.0124487 -0.0773804 0.398341 -0.0100131 -0.0773953 0.397961 -0.00743602 -0.0776056 0.397722 -0.00490307 -0.0776139 0.39754 -0.00491198 -0.0774311 0.397718 1.26879e-07 -0.0776217 0.403795 -0.018366 -0.0776907 0.403679 -0.0185382 -0.0775562 0.402138 -0.0167193 -0.0775811 0.402334 -0.0165631 -0.0777216 0.400645 -0.014622 -0.0775849 0.400855 -0.0144892 -0.0777225 0.399646 -0.0122683 -0.0777237 0.398518 -0.00996027 -0.0775973 0.398195 -0.00739966 -0.0777272 0.397953 -0.00489179 -0.0777291 0.405824 0.0186935 -0.082571 0.405521 0.0186941 -0.0820693 0.405748 0.0182 -0.082003 0.404742 0.0186963 -0.080606 0.404646 0.0186966 -0.0804038 0.405032 0.0182 -0.0806833 0.404852 0.0182 -0.0803077 0.403907 0.0186998 -0.0785634 0.403757 0.0184265 -0.0776545 0.410211 0.0182 -0.0853537 0.410511 0.0185417 -0.0856968 0.408865 0.0182 -0.085001 0.407623 0.0182 -0.0843588 0.407081 0.0186696 -0.0842493 0.411598 0.0185 -0.085765 0.422327 0.0185 -0.085765 0.425423 0.0181103 -0.085765 0.434527 0.00599996 -0.085465 0.428183 0.0167026 -0.085465 0.428327 0.0169658 -0.085765 0.429498 0.01587 -0.085465 0.43393 0.00976996 -0.085465 0.432822 0.0122208 -0.085465 0.431012 0.0149896 -0.085765 0.430804 0.0147738 -0.085465 0.434827 -4.19898e-08 -0.085765 0.434527 -0.00600004 -0.085465 0.429498 -0.01587 -0.085465 0.43308 -0.0123738 -0.085765 0.432822 -0.0122208 -0.085465 0.434827 -0.00600004 -0.085765 0.434093 -0.00922518 -0.085465 0.422327 -0.0182 -0.085465 0.428327 -0.0169659 -0.085765 0.425423 -0.0181104 -0.085765 0.411598 -0.0182 -0.085465 0.406437 -0.0186925 -0.0835083 0.407169 -0.0186665 -0.0843269 0.408856 -0.0182 -0.0849975 0.408632 -0.0186129 -0.0852092 0.411598 -0.0185 -0.085765 0.406627 -0.0182 -0.0833775 0.405032 -0.0182 -0.0806833 0.406078 -0.0186931 -0.0829708 0.404871 -0.0182 -0.0803487 0.404246 -0.0186983 -0.0794816 0.404013 -0.0186994 -0.0788671 0.40406 -0.017334 -0.077465 0.405113 -0.0179762 -0.077465 0.403038 -0.0164957 -0.077765 0.399738 -0.0100957 -0.077765 0.399867 -0.00647442 -0.077765 0.401215 -0.00517399 -0.077765 0.403027 -0.00500004 -0.077465 0.430445 -0.00698411 -0.077765 0.430727 -0.00840004 -0.077765 0.430427 -0.00840004 -0.077465 0.429971 -0.00670004 -0.077465 0.428727 -0.00545556 -0.077465 0.43 -0.0150898 -0.077465 0.404065 0.0173389 -0.077465 0.403038 0.0164956 -0.077765 0.405127 0.0179814 -0.077465 0.403305 0.0163581 -0.077465 0.399329 0.00826809 -0.077765 0.400005 0.00995814 -0.077465 0.428877 0.00519566 -0.077765 0.427027 0.00469996 -0.077765 0.429971 0.00669996 -0.077465 0.430231 0.00654996 -0.077765 0.429508 0.0158628 -0.0775328 0.43 0.0150897 -0.077465 0.430427 0.0134397 -0.077465 0.408523 0.00194996 -0.077765 0.411727 0.00349996 -0.077465 0.409877 0.00330425 -0.077765 0.417927 0.00379996 -0.077765 0.408327 9.9958e-05 -0.077465 0.419627 0.00304444 -0.077465 0.408523 -0.00195004 -0.077765 0.408027 -0.000100042 -0.077765 0.411727 -0.00380004 -0.077765 0.410027 -0.00304453 -0.077465 0.409877 -0.00330434 -0.077765 0.409323 -0.00250421 -0.077465 0.408782 -0.00180004 -0.077465 0.421627 9.9958e-05 -0.077765 0.421627 -0.000100042 -0.077765 0.417927 -0.00380004 -0.077765 0.421345 -0.00151597 -0.077765 0.420331 -0.00250421 -0.077465 0.419228 -0.00324123 -0.077465 0.413089 0.0170286 -0.077765 0.419353 0.0140013 -0.077465 0.419114 0.014183 -0.077765 0.418053 0.0133092 -0.077765 0.418321 0.0131107 -0.077465 0.418186 0.0130401 -0.077465 0.416714 0.013 -0.077765 0.416713 0.0127 -0.077465 0.415378 0.0133203 -0.077765 0.414084 0.0140232 -0.077465 0.414325 0.0142029 -0.077765 0.421984 0.0182 -0.077765 0.422046 0.0179021 -0.077465 0.423308 0.0181451 -0.077465 0.419968 0.0153819 -0.077465 0.419674 0.0154381 -0.077765 0.421935 0.0181807 -0.077765 0.423308 -0.0181451 -0.077465 0.414087 -0.0140197 -0.077465 0.415385 -0.0133167 -0.077765 0.41348 -0.015409 -0.077465 0.428321 -0.0254 -0.081765 0.427978 -0.023 -0.081465 0.428321 -0.0206 -0.081765 0.428581 -0.02075 -0.081465 0.430228 -0.0191029 -0.081465 0.432478 0.0185 -0.081465 0.428321 0.0206 -0.081765 0.428581 0.02525 -0.081465 0.432478 0.0275 -0.081465 0.435827 -0.0558011 -0.0698973 0.436127 -0.0558559 -0.069087 0.435827 -0.056166 -0.0691311 0.435847 -0.0574353 -0.0659783 0.436232 -0.0580288 -0.0629093 0.436061 -0.0584438 -0.0620355 0.435827 -0.0432862 -0.0833761 0.436127 -0.044926 -0.0820883 0.435827 -0.0467954 -0.0811463 0.436127 -0.0466132 -0.080908 0.435827 -0.0469425 -0.0810331 0.435827 -0.0532587 -0.0742439 0.436127 -0.0543501 -0.071965 0.436127 -0.0555319 -0.069765 0.434033 -0.0332839 -0.0857438 0.432949 -0.0316693 -0.0857644 0.435345 -0.0364645 -0.085504 0.43547 -0.0357925 -0.0852732 0.435789 -0.0369654 -0.0851168 0.435872 -0.037359 -0.0850509 0.436102 -0.0391701 -0.0846515 0.435744 -0.0385776 -0.085116 0.436127 -0.04 -0.0844119 0.435827 -0.040091 -0.0846978 0.429248 -0.0284091 -0.085765 0.426605 -0.0242303 -0.085465 0.427593 -0.0264838 -0.085465 0.427013 -0.025478 -0.085465 0.428524 -0.0184865 -0.085465 0.429402 -0.0178485 -0.085465 0.428327 -0.0182608 -0.085765 0.43538 -0.00944618 -0.085765 0.435827 -0.00600004 -0.085765 0.435827 -4.19898e-08 -0.085765 0.429402 0.0178484 -0.085465 0.431977 0.0154401 -0.085765 0.434328 0.012812 -0.085465 0.434067 0.0126639 -0.085765 0.43567 0.00952267 -0.085465 0.43538 0.00944609 -0.085765 0.435827 0.00599996 -0.085765 0.428524 0.0184864 -0.085465 0.428327 0.0182607 -0.085765 0.426605 0.0242302 -0.085465 0.426178 0.023 -0.085765 0.42674 0.0256018 -0.085765 0.427013 0.0254779 -0.085465 0.426478 0.023 -0.085465 0.426605 0.0217697 -0.085465 0.432613 0.0308 -0.085465 0.436127 0.04 -0.0844119 0.435959 0.0378572 -0.0849571 0.435829 0.0371464 -0.0850873 0.435009 0.0345593 -0.08538 0.434421 0.0333532 -0.0854374 0.433942 0.0325476 -0.0854559 0.433601 0.0325785 -0.0857578 0.432389 0.031 -0.085765 0.435827 0.0540312 -0.0730691 0.436127 0.0530114 -0.0740739 0.436127 0.0499668 -0.077864 0.435827 0.051792 -0.076218 0.435827 0.0508015 -0.0773937 0.436127 0.0483566 -0.0794509 0.436127 0.0466132 -0.080908 0.435827 0.0467953 -0.0811463 0.436209 0.0582984 -0.0620127 0.436149 0.0583759 -0.0619504 0.435827 0.0561772 -0.0691067 0.435844 0.0573552 -0.0662072 0.435546 0.0585137 -0.0621266 0.436061 0.0584437 -0.0620355 0.435032 0.0582202 -0.0617646 0.434327 0.0585133 -0.0621285 0.434327 0.0582201 -0.061765 0.433083 0.0582201 -0.061765 0.429525 0.0563983 -0.0620747 0.429389 0.0552158 -0.061765 0.429118 0.0553702 -0.0620556 0.429947 0.0565151 -0.061765 0.430601 0.0572677 -0.061765 0.430409 0.0574955 -0.0620969 0.432961 0.0585116 -0.0621276 0.431902 0.0583353 -0.0621184 0.431764 0.0579751 -0.061765 0.431604 0.0582303 -0.062115 0.430658 0.057699 -0.0621014 0.406013 0.00757858 -0.061765 0.411514 0.0213319 -0.0618917 0.409608 0.0183338 -0.0618681 0.409828 0.0182623 -0.061765 0.406791 0.0113 -0.061765 0.406642 0.0114852 -0.0618362 0.411957 0.0219655 -0.0618974 0.413304 0.0237945 -0.0619151 0.414184 0.0245027 -0.061765 0.414701 0.0255854 -0.0619338 0.42043 0.0326372 -0.062009 0.422391 0.0352314 -0.0620315 0.424132 0.0378048 -0.0620484 0.423648 0.0365126 -0.061765 0.425628 0.0403947 -0.0620592 0.427242 0.0431931 -0.061765 0.427887 0.0460701 -0.0620614 0.428393 0.0468279 -0.061765 0.428992 0.054439 -0.062039 0.428965 -0.0535928 -0.062041 0.428869 -0.051902 -0.0620457 0.429051 -0.0506307 -0.061765 0.428412 -0.0469068 -0.061765 0.428121 -0.0469764 -0.0620596 0.427633 -0.0452036 -0.0620627 0.426589 -0.0424 -0.0620631 0.426996 -0.043388 -0.0620636 0.425197 -0.0395972 -0.0620565 0.423683 -0.0365644 -0.061765 0.423419 -0.0367078 -0.0620419 0.423035 -0.0361442 -0.0620381 0.417383 -0.0288799 -0.0619698 0.411338 -0.021076 -0.0618894 0.411969 -0.0215538 -0.061765 0.409884 -0.0183572 -0.061765 0.408338 -0.0159348 -0.0618535 0.40766 -0.0144102 -0.0618462 0.407184 -0.0131702 -0.0618414 0.406632 -0.0114495 -0.0618361 0.406819 -0.0113959 -0.061765 0.40637 -0.0104531 -0.0618338 0.405727 -0.0067971 -0.0618286 0.405486 -0.00312953 -0.0618271 0.40564 -4.2042e-08 -0.061765 0.405457 -4.19898e-08 -0.0618269 0.431662 -0.0582528 -0.0621157 0.43114 -0.0580112 -0.062109 0.430904 -0.05787 -0.0621055 0.430231 -0.0573292 -0.0620933 0.430373 -0.0570478 -0.061765 0.429002 -0.0546565 -0.0620428 0.429291 -0.0544318 -0.061765 0.433083 -0.0582202 -0.061765 0.434327 -0.0585134 -0.0621285 0.435966 -0.0582211 -0.0617605 0.434766 -0.0585134 -0.0621284 0.435156 -0.0585135 -0.0621279 0.435147 -0.0582203 -0.0617644 0.435969 -0.0585144 -0.062124 0.435562 -0.0582206 -0.061763 0.436058 -0.0582992 -0.0618563 0.436149 -0.058376 -0.0619504 0.436209 -0.0582985 -0.0620127 0.436268 -0.0582211 -0.0620748 0.436752 -0.0542208 -0.0617509 0.436335 -0.0545098 -0.0617569 0.436552 -0.0547122 -0.0621166 0.436943 -0.054461 -0.0621217 0.436307 -0.0551473 -0.0620932 0.436061 -0.0549379 -0.0617597 0.451217 -0.0546522 -0.0590783 0.44661 -0.054689 -0.0608758 0.444885 -0.0546048 -0.0612782 0.440525 -0.0544557 -0.0619314 0.437257 -0.0544115 -0.0621127 0.438213 -0.0541279 -0.0617101 0.477594 -0.0338843 -0.0517771 0.478218 -0.0313929 -0.0521424 0.476661 -0.0391109 -0.0521737 0.477205 -0.0372168 -0.0521582 0.477365 -0.0365644 -0.0521546 0.47562 -0.0411057 -0.0518373 0.473281 -0.0461537 -0.052403 0.473808 -0.0447556 -0.0519604 0.470847 -0.0485933 -0.0523382 0.468755 -0.0504274 -0.0527496 0.469081 -0.0505992 -0.0530819 0.468114 -0.0508904 -0.0528996 0.468509 -0.0510227 -0.0532107 0.467864 -0.0510603 -0.0529611 0.465998 -0.0525418 -0.0538742 0.465579 -0.0523769 -0.0535965 0.464394 -0.0532782 -0.0543746 0.464174 -0.0530087 -0.0540478 0.463415 -0.0533029 -0.0543084 0.461145 -0.0540135 -0.0551457 0.462 -0.0541153 -0.0552135 0.460478 -0.0541792 -0.0554054 0.459262 -0.0547576 -0.0562682 0.457525 -0.054695 -0.0565963 0.45663 -0.0547796 -0.0569632 0.456795 -0.0550751 -0.057262 0.454208 -0.0548052 -0.0579439 0.479366 -0.0167579 -0.0521382 0.479517 -0.000347294 -0.051765 0.479808 -0.000347592 -0.0521379 0.479808 0.000173762 -0.0521379 0.479517 0.000347274 -0.051765 0.479419 0.00786943 -0.0517651 0.479293 0.0181415 -0.0521382 0.478725 0.0256953 -0.0521396 0.454209 0.0548052 -0.0579433 0.456692 0.0547749 -0.0569379 0.462476 0.0539709 -0.0550392 0.461459 0.0542668 -0.0554152 0.461704 0.0538603 -0.0549325 0.464719 0.0531413 -0.0542688 0.465668 0.0523326 -0.0535694 0.468413 0.0510904 -0.0532331 0.469502 0.0498333 -0.0525887 0.47018 0.049686 -0.0528587 0.472269 0.047498 -0.052524 0.471003 0.0484331 -0.0523124 0.472683 0.0469753 -0.0524713 0.472287 0.0469578 -0.0521252 0.473548 0.0457592 -0.0523754 0.476909 0.0382991 -0.0521661 0.476619 0.038218 -0.0517988 0.476215 0.0404109 -0.0521903 0.475337 0.042534 -0.0522342 0.474774 0.0429914 -0.0518856 0.475036 0.0431621 -0.0522529 0.477923 0.0313702 -0.0517727 0.478304 0.0304102 -0.052142 0.437249 0.0541202 -0.0617408 0.441592 0.0544824 -0.0618188 0.445295 0.0546237 -0.0611898 0.448223 0.0547756 -0.0604291 0.446405 0.0543881 -0.0605586 0.45096 0.054638 -0.0591697 0.453313 0.054762 -0.0582951 0.436178 0.0547095 -0.0617586 0.436336 0.054509 -0.0617569 0.436506 0.0547642 -0.0621143 0.43677 0.0545396 -0.0621221 0.436996 0.0541446 -0.0617464 0.437078 0.0544263 -0.062119 0.437257 0.0544114 -0.0621127 0.436058 0.0582991 -0.0618563 0.436268 0.0582211 -0.0620748 0.435966 0.0582211 -0.0617605 0.436437 -0.0535775 -0.0657419 0.436146 -0.0542324 -0.0659896 0.436446 -0.0548447 -0.0621103 0.436776 -0.0533669 -0.065666 0.436664 -0.0546108 -0.0621204 0.436215 -0.0538961 -0.0658612 0.436194 -0.0521746 -0.069592 0.437127 -0.0522361 -0.0680825 0.437127 -0.0516139 -0.0692865 0.437127 -0.0465728 -0.0760451 0.436756 -0.0493925 -0.0728978 0.436756 -0.0466227 -0.0760958 0.436756 -0.0516763 -0.0693205 0.436416 -0.0451991 -0.0776858 0.436194 -0.047021 -0.0765 0.436416 -0.0467809 -0.0762563 0.436194 -0.0498481 -0.073236 0.436127 -0.0500234 -0.0736053 0.436416 -0.0435067 -0.0789499 0.436194 -0.0454168 -0.0779497 0.436127 -0.0472747 -0.0767575 0.436194 -0.0436975 -0.0792339 0.436127 -0.0420177 -0.0806546 0.436194 -0.0418506 -0.0803341 0.436416 -0.0416923 -0.0800308 0.436416 -0.0518742 -0.0694283 0.436416 -0.0495734 -0.0730321 0.436756 -0.0450557 -0.077512 0.436756 -0.043381 -0.0787629 0.437127 -0.0433413 -0.0787038 0.436756 -0.0415881 -0.079831 0.433515 -0.03143 -0.0820579 0.4354 -0.0330378 -0.0817488 0.434575 -0.0334901 -0.0823782 0.433282 -0.0316081 -0.082765 0.435417 -0.03563 -0.0826185 0.433388 -0.0315267 -0.082265 0.43694 -0.0374369 -0.0812737 0.43601 -0.0353389 -0.0816841 0.435072 -0.033213 -0.0818158 0.435684 -0.0354697 -0.0819036 0.436012 -0.037721 -0.0818836 0.435474 -0.0355736 -0.0822457 0.434771 -0.033378 -0.0820377 0.433679 -0.0313041 -0.0818989 0.436197 -0.0398711 -0.0812111 0.436229 -0.0376116 -0.0815475 0.43642 -0.0397523 -0.0808936 0.436759 -0.0396743 -0.080685 0.436569 -0.0375094 -0.0813324 0.429658 -0.0277223 -0.0818989 0.429914 -0.027293 -0.081765 0.431336 -0.028258 -0.081765 0.431032 -0.0286547 -0.0818989 0.432288 -0.0297399 -0.0818989 0.433338 -0.0315655 -0.0823969 0.430809 -0.0289451 -0.082265 0.432033 -0.0300026 -0.082265 0.42947 -0.0280365 -0.082265 0.428502 -0.0273129 -0.082265 0.429402 -0.0281516 -0.082765 0.427702 -0.026406 -0.082265 0.427105 -0.0253544 -0.082265 0.426982 -0.0254082 -0.082765 0.426612 -0.023 -0.082265 0.426605 -0.0242303 -0.082765 0.426478 -0.023 -0.082765 0.426605 -0.0217698 -0.082765 0.426736 -0.0217973 -0.082265 0.426982 -0.0205919 -0.082765 0.427593 -0.0195163 -0.082765 0.428502 -0.0186872 -0.082265 0.42947 -0.0179636 -0.082265 0.42875 -0.0270438 -0.0818989 0.426736 -0.0242028 -0.082265 0.427095 -0.0218723 -0.0818989 0.42744 -0.0207926 -0.0818989 0.427105 -0.0206457 -0.082265 0.428 -0.0198066 -0.0818989 0.427702 -0.019594 -0.082265 0.42875 -0.0189563 -0.0818989 0.429089 -0.0266762 -0.081765 0.428407 -0.0259032 -0.081765 0.428 -0.0261935 -0.0818989 0.42744 -0.0252075 -0.0818989 0.427095 -0.0241277 -0.0818989 0.427478 -0.023 -0.081765 0.426978 -0.023 -0.0818989 0.427898 -0.0209932 -0.081765 0.428407 -0.0200969 -0.081765 0.429089 -0.0193239 -0.081765 0.436627 -0.00600004 -0.0818989 0.437004 -0.00790488 -0.081765 0.436145 -0.00779342 -0.082265 0.435568 -0.0113995 -0.0818989 0.436031 -0.0115883 -0.081765 0.434763 -0.0130589 -0.0818989 0.436508 -0.00784053 -0.0818989 0.436153 -0.00965039 -0.0818989 0.435229 -0.0112613 -0.082265 0.434445 -0.0128782 -0.082265 0.433751 -0.0146008 -0.0818989 0.432288 -0.0157437 -0.082265 0.430951 -0.0169446 -0.082265 0.432549 -0.0159996 -0.0818989 0.431177 -0.0172321 -0.0818989 0.429658 -0.0182778 -0.0818989 0.429402 -0.0178485 -0.082765 0.433459 -0.0143806 -0.082265 0.432192 -0.01565 -0.082765 0.434328 -0.0128121 -0.082765 0.435105 -0.0112107 -0.082765 0.435799 -0.00955696 -0.082265 0.436127 -0.00600004 -0.082765 0.436203 -0.00600004 -0.0823823 0.436203 0.00599996 -0.0823823 0.436261 -0.00600004 -0.082265 0.436261 0.00599996 -0.082265 0.43642 0.00599996 -0.0820579 0.43642 -0.00600004 -0.0820579 0.436627 0.00599996 -0.0818989 0.436744 -0.00600004 -0.0818411 0.436744 0.00599996 -0.0818411 0.437127 -0.00600004 -0.081765 0.429658 0.0182777 -0.0818989 0.432549 0.0159995 -0.0818989 0.432907 0.0163492 -0.081765 0.434151 0.0149014 -0.081765 0.435568 0.0113995 -0.0818989 0.436031 0.0115883 -0.081765 0.436153 0.00965031 -0.0818989 0.436636 0.00977794 -0.081765 0.437004 0.00790479 -0.081765 0.436508 0.00784044 -0.0818989 0.435799 0.00955687 -0.082265 0.434763 0.0130588 -0.0818989 0.435229 0.0112612 -0.082265 0.433751 0.0146007 -0.0818989 0.433459 0.0143806 -0.082265 0.431177 0.0172321 -0.0818989 0.430951 0.0169446 -0.082265 0.436145 0.00779333 -0.082265 0.43567 0.00952267 -0.082765 0.434445 0.0128781 -0.082265 0.432288 0.0157436 -0.082265 0.433352 0.0143 -0.082765 0.430868 0.0168393 -0.082765 0.428502 0.0273128 -0.082265 0.427702 0.026406 -0.082265 0.427105 0.0253543 -0.082265 0.426478 0.023 -0.082765 0.426605 0.0217697 -0.082765 0.428502 0.0186871 -0.082265 0.42875 0.0270437 -0.0818989 0.428 0.0261934 -0.0818989 0.42744 0.0252074 -0.0818989 0.426736 0.0242027 -0.082265 0.427095 0.0241277 -0.0818989 0.426612 0.023 -0.082265 0.426736 0.0217972 -0.082265 0.426978 0.023 -0.0818989 0.427105 0.0206456 -0.082265 0.427702 0.019594 -0.082265 0.42744 0.0207925 -0.0818989 0.428 0.0198065 -0.0818989 0.42947 0.0179635 -0.082265 0.429658 0.0277222 -0.0818989 0.427898 0.0250068 -0.081765 0.427095 0.0218723 -0.0818989 0.427584 0.0219748 -0.081765 0.428407 0.0200968 -0.081765 0.42875 0.0189562 -0.0818989 0.429089 0.0193238 -0.081765 0.429914 0.018707 -0.081765 0.433282 0.0316081 -0.082765 0.433342 0.0315618 -0.0823823 0.429441 0.0280861 -0.0823823 0.429402 0.0281515 -0.082765 0.431557 0.0296386 -0.0823823 0.431506 0.0296955 -0.082765 0.42947 0.0280364 -0.082265 0.431701 0.0294768 -0.0820579 0.429552 0.0279 -0.0820579 0.431917 0.0292345 -0.0818411 0.429718 0.0276215 -0.0818411 0.433515 0.03143 -0.0820579 0.436013 0.0377323 -0.0818809 0.435954 0.0378232 -0.0822473 0.435475 0.0355739 -0.0822457 0.436231 0.0376228 -0.0815449 0.436194 0.0398733 -0.0812174 0.435077 0.0332221 -0.0818155 0.436942 0.0374485 -0.0812711 0.436571 0.0375207 -0.0813298 0.43601 0.0353392 -0.0816841 0.43458 0.033499 -0.082378 0.434521 0.0335392 -0.0827483 0.435684 0.0354699 -0.0819036 0.434776 0.0333869 -0.0820374 0.433772 0.0312327 -0.0818411 0.434076 0.031 -0.081765 0.436127 0.049442 -0.0743534 0.436127 0.0501258 -0.0734682 0.436194 0.0418398 -0.08034 0.436416 0.0416817 -0.0800365 0.436756 0.0396746 -0.0806859 0.436416 0.0397535 -0.0808969 0.436127 0.0407578 -0.0812523 0.436194 0.043674 -0.0792496 0.436127 0.0456214 -0.0782489 0.436416 0.0451744 -0.0777056 0.436416 0.0434836 -0.0789653 0.436756 0.0433582 -0.0787781 0.436756 0.0415777 -0.0798367 0.437127 0.0461039 -0.0764949 0.436194 0.047002 -0.0765187 0.436194 0.0453918 -0.0779698 0.436756 0.0466041 -0.076114 0.436756 0.0450312 -0.0775316 0.437127 0.0489044 -0.0734207 0.436416 0.0495612 -0.0730484 0.436416 0.0467621 -0.0762747 0.436756 0.0493804 -0.072914 0.437127 0.0465542 -0.0760633 0.436756 0.0516762 -0.0693205 0.436194 0.0498358 -0.0732526 0.436127 0.0524919 -0.069765 0.437145 0.0532991 -0.0656454 0.436776 0.0533668 -0.065666 0.436328 0.0550798 -0.0620973 0.436146 0.0542323 -0.0659896 0.436416 0.0518741 -0.0694283 0.436437 0.0535774 -0.0657419 0.436215 0.053896 -0.0658612 0.436194 0.0521745 -0.069592 0.415714 0.0177537 -0.061765 0.414702 0.016 -0.061765 0.415298 0.015175 -0.06214 0.414973 0.0149875 -0.061765 0.415902 0.0174289 -0.06214 0.415077 0.016 -0.073765 0.415298 0.016825 -0.06214 0.415077 0.016 -0.06214 0.415298 0.015175 -0.073765 0.415902 0.014571 -0.06214 0.416727 0.016 -0.0747564 0.415298 0.016825 -0.073765 0.415902 0.0174289 -0.073765 0.416727 0.01435 -0.073765 0.415902 0.014571 -0.073765 0.416727 -0.013975 -0.061765 0.415902 -0.0145711 -0.06214 0.415714 -0.0142463 -0.061765 0.414973 -0.0149875 -0.061765 0.415077 -0.016 -0.06214 0.415298 -0.016825 -0.06214 0.414973 -0.0170125 -0.061765 0.415902 -0.017429 -0.06214 0.415298 -0.015175 -0.073765 0.415298 -0.015175 -0.06214 0.415902 -0.017429 -0.073765 0.416727 -0.01765 -0.073765 0.416727 -0.01765 -0.06214 0.415077 -0.016 -0.073765 0.415902 -0.0145711 -0.073765 0.415298 -0.016825 -0.073765 0.410135 -0.0182 -0.077465 0.411638 -0.0178496 -0.077465 0.411134 -0.0180501 -0.0663002 0.411572 -0.0178815 -0.0663002 0.412849 -0.016848 -0.077465 0.423687 -0.0181239 -0.062965 0.423687 -0.0181239 -0.077465 0.423687 0.0181238 -0.062965 0.41348 0.0154089 -0.0663002 0.412855 0.0168404 -0.0663002 0.412849 0.0168479 -0.077465 0.411655 0.0178411 -0.0663002 0.411638 0.0178495 -0.077465 0.410135 0.0182 -0.077465 0.413889 -0.014315 -0.0646531 0.415251 -0.0130483 -0.077465 0.420361 -0.016982 -0.077765 0.411771 -0.0181187 -0.077765 0.413089 -0.0170287 -0.077765 0.414327 -0.0141997 -0.077765 0.413775 -0.0154627 -0.077765 0.419968 0.0153819 -0.062965 0.41348 0.0154089 -0.077465 0.413889 0.0143149 -0.0646531 0.415108 0.0131241 -0.077465 0.415108 0.0131241 -0.062965 0.415243 0.0130523 -0.077465 0.416713 0.0127 -0.062965 0.413775 0.0154626 -0.077765 0.420453 0.0170987 -0.077765 0.411771 0.0181186 -0.077765 0.411595 0.0182 -0.077765 0.432478 -0.024525 -0.078265 0.431715 -0.0243207 -0.078265 0.431157 -0.0237625 -0.078265 0.431228 -0.023 -0.07799 0.430953 -0.023 -0.078265 0.431853 -0.0219175 -0.07799 0.431853 0.0219174 -0.07799 0.431395 0.022375 -0.07799 0.431715 0.0216793 -0.078265 0.430953 0.023 -0.078265 0.431853 0.0240825 -0.07799 0.431715 0.0243206 -0.078265 0.434728 0.0268971 -0.078265 0.433798 0.0237625 -0.078265 0.436375 0.02525 -0.078265 0.434003 0.023 -0.078265 0.436375 0.02075 -0.078265 0.433798 0.0222375 -0.078265 0.43324 0.0216793 -0.078265 0.432478 0.021475 -0.078265 0.431157 0.0222375 -0.078265 0.427978 0.023 -0.078265 0.431157 0.0237625 -0.078265 0.430228 0.0268971 -0.078265 0.432478 0.0275 -0.078265 0.430228 0.0191028 -0.078265 0.430228 0.0191028 -0.081465 0.428581 0.02075 -0.078265 0.428581 0.02075 -0.081465 0.427978 0.023 -0.081465 0.428581 0.02525 -0.078265 0.430228 0.0268971 -0.081465 0.435996 -0.0201943 -0.078265 0.434003 -0.023 -0.078265 0.433798 -0.0237625 -0.078265 0.435996 -0.0258057 -0.078265 0.43443 -0.0270544 -0.078265 0.430228 -0.0268972 -0.078265 0.428581 -0.02525 -0.078265 0.427978 -0.023 -0.078265 0.431157 -0.0222375 -0.078265 0.428581 -0.02075 -0.078265 0.431715 -0.0216794 -0.078265 0.430228 -0.0191029 -0.078265 0.432478 -0.021475 -0.078265 0.432478 -0.0185 -0.078265 0.43324 -0.0216794 -0.078265 0.433798 -0.0222375 -0.078265 0.432478 -0.0275 -0.078265 0.432478 -0.0275 -0.081465 0.430228 -0.0268972 -0.081465 0.428581 -0.02525 -0.081465 0.429402 0.0281515 -0.085465 0.431939 0.0300986 -0.082765 0.435958 0.0378471 -0.0849591 0.435417 0.0356303 -0.0826185 0.436127 -0.04 -0.0815559 0.435952 -0.0378118 -0.08225 0.434516 -0.0335303 -0.0827485 0.434841 -0.0341843 -0.0854022 0.43443 -0.0333697 -0.0854368 0.433865 -0.0324294 -0.0854576 0.432613 -0.0308 -0.085465 0.431939 -0.0300987 -0.082765 0.430727 -0.0290513 -0.082765 0.434328 -0.0128121 -0.085465 0.433352 -0.0143001 -0.082765 0.432192 -0.01565 -0.085465 0.430868 -0.0168394 -0.082765 0.43567 -0.00952276 -0.082765 0.436012 -0.00777617 -0.082765 0.43567 -0.00952276 -0.085465 0.436127 -0.00600004 -0.085465 0.428411 -0.0185887 -0.082765 0.427593 -0.0195163 -0.085465 0.427013 -0.0205221 -0.085465 0.426605 -0.0217698 -0.085465 0.426478 -0.023 -0.085465 0.428524 -0.0275136 -0.085465 0.427593 -0.0264838 -0.082765 0.429402 -0.0281516 -0.085465 0.428411 -0.0274114 -0.082765 0.435105 0.0112107 -0.082765 0.436127 0.00599996 -0.085465 0.436012 0.00777609 -0.082765 0.436127 0.00599996 -0.082765 0.434328 0.012812 -0.082765 0.432192 0.0156499 -0.082765 0.429402 0.0178484 -0.082765 0.432192 0.0156499 -0.085465 0.428411 0.0185886 -0.082765 0.427593 0.0195162 -0.082765 0.426982 0.0205918 -0.082765 0.427593 0.0195162 -0.085465 0.427013 0.020522 -0.085465 0.426605 0.0242302 -0.082765 0.426982 0.0254081 -0.082765 0.427593 0.0264837 -0.082765 0.428411 0.0274113 -0.082765 0.427593 0.0264837 -0.085465 0.428524 0.0275135 -0.085465 0.447762 0.0308991 -0.0797817 0.448487 0.0311046 -0.0797733 0.444976 0.0289413 -0.0799458 0.44593 0.0298865 -0.0798577 0.446548 0.0303209 -0.0798215 0.443734 0.0263907 -0.079265 0.44494 0.0288968 -0.079265 0.443616 0.0242969 -0.0804283 0.443587 0.0246479 -0.0804798 0.44494 0.0211031 -0.079265 0.443734 0.0236092 -0.079265 0.444189 0.0223026 -0.0800939 0.443733 0.0236099 -0.0803052 0.447088 0.0193821 -0.079799 0.447115 0.0193689 -0.079265 0.449827 -0.01875 -0.079765 0.44494 -0.0211032 -0.079265 0.447115 -0.019369 -0.079265 0.446548 -0.0196791 -0.0798215 0.447115 -0.019369 -0.0797981 0.443954 -0.022861 -0.0801788 0.443734 -0.0236093 -0.079265 0.444268 -0.0221427 -0.0800718 0.444976 -0.0210587 -0.0799458 0.443616 -0.024297 -0.0804283 0.443741 -0.0235767 -0.0802995 0.443616 -0.0257031 -0.0804283 0.443577 -0.025 -0.080497 0.44489 -0.0288331 -0.0799569 0.443733 -0.0263901 -0.0803052 0.448354 -0.031074 -0.0797743 0.447115 -0.0306311 -0.079265 0.446441 -0.0302538 -0.0798269 0.44494 -0.0288969 -0.079265 0.442372 0.00109635 -0.0801483 0.442436 0.000938491 -0.079265 0.446765 0.011391 -0.0797883 0.446765 0.011391 -0.079265 0.445181 0.0105126 -0.0798391 0.446168 0.0111142 -0.0798026 0.442436 0.00706143 -0.079265 0.441827 0.00399996 -0.079265 0.443741 -0.00119225 -0.0799311 0.447182 -0.00355028 -0.0797816 0.446765 -0.00339106 -0.0797883 0.446765 -0.00339108 -0.079265 0.448307 -0.00385432 -0.0797724 0.449827 -0.00400004 -0.079265 0.441383 0.00505658 -0.081265 0.441835 0.00435481 -0.0804834 0.441827 0.00399996 -0.080497 0.441858 0.00470896 -0.0804425 0.442135 0.00619924 -0.0802374 0.442534 0.00728807 -0.0801039 0.443286 0.00860588 -0.0799775 0.442705 0.0098466 -0.0813986 0.44403 0.00951317 -0.0799074 0.443154 0.0104808 -0.0814128 0.447585 0.0116793 -0.0797771 0.44526 0.0124011 -0.0814512 0.447898 0.0134919 -0.0814697 0.448724 0.0119236 -0.0797702 0.441835 0.00364511 -0.0804834 0.448125 -0.00553918 -0.0814703 0.445798 -0.00291147 -0.0798143 0.444836 -0.00225204 -0.0798561 0.44417 -0.00165679 -0.079897 0.444461 -0.00382095 -0.0814402 0.443742 -0.00315728 -0.081427 0.441383 0.00294333 -0.081265 0.443054 -0.000257725 -0.0800075 0.441949 -0.000344367 -0.0813605 0.442031 0.00220482 -0.0802911 0.441858 0.00329095 -0.0804425 0.457795 0.00470896 -0.0804425 0.458152 0.00497017 -0.0810605 0.457819 0.00435481 -0.0804834 0.449827 0.012 -0.079765 0.449827 0.0137071 -0.0814721 0.451471 0.01355 -0.0814705 0.451347 0.0118542 -0.0797724 0.453521 0.0128859 -0.0814601 0.453856 0.0109114 -0.0798143 0.454582 0.0122741 -0.0814466 0.454818 0.010252 -0.0798561 0.458073 0.00633927 -0.0811113 0.4566 0.00825764 -0.0800075 0.457887 0.007365 -0.0811627 0.457623 0.0057951 -0.0802911 0.458154 0.00399996 -0.0810629 0.457795 0.00329095 -0.0804425 0.458076 0.00162971 -0.0811228 0.457797 0.000254003 -0.0811976 0.457519 0.00180068 -0.0802374 0.45712 0.000711846 -0.0801039 0.457629 -0.000274536 -0.0812304 0.457164 -0.00134653 -0.0812992 0.455879 -0.00316238 -0.0814045 0.455624 -0.00151326 -0.0799074 0.454982 -0.00398143 -0.0814381 0.454558 -0.00429093 -0.0814473 0.454473 -0.00251272 -0.0798391 0.45172 -0.00549972 -0.0814698 0.449827 -0.00570715 -0.0814721 0.449827 -0.00400004 -0.079765 0.450929 -0.00392373 -0.0797702 0.452069 -0.00367939 -0.0797771 0.453521 -0.00488594 -0.0814601 0.443133 -0.025 -0.081265 0.443587 -0.024648 -0.0804798 0.443587 -0.0253521 -0.0804798 0.446011 -0.0182009 -0.0814484 0.445294 -0.0187728 -0.0814347 0.44593 -0.0201135 -0.0798577 0.444887 -0.0191783 -0.0814244 0.444541 -0.0216654 -0.0800117 0.443535 -0.0214095 -0.081357 0.443231 -0.0226051 -0.0813143 0.448476 -0.0171752 -0.0814704 0.448487 -0.0188954 -0.0797733 0.447762 -0.0191009 -0.0797817 0.446029 -0.0181882 -0.0814487 0.449095 -0.0312071 -0.0797692 0.448337 -0.0327673 -0.0814409 0.447088 -0.0306179 -0.079799 0.445396 -0.0294082 -0.0799006 0.445672 -0.0315458 -0.0814397 0.444618 -0.030511 -0.0814162 0.444189 -0.0276974 -0.0800939 0.443907 -0.0270034 -0.0802011 0.450558 -0.018793 -0.0797692 0.4513 -0.018926 -0.0797743 0.451721 -0.0173019 -0.0814683 0.453212 -0.0197463 -0.0798269 0.454777 -0.0191974 -0.0814183 0.454763 -0.0211669 -0.0799569 0.456256 -0.022028 -0.0812677 0.45592 -0.02361 -0.0803052 0.456037 -0.024297 -0.0804283 0.456464 -0.0239842 -0.0811685 0.456037 -0.0257031 -0.0804283 0.454677 -0.0289414 -0.0799458 0.455113 -0.0283347 -0.0800117 0.455699 -0.0271391 -0.0801788 0.456461 -0.0260135 -0.0811628 0.455258 -0.0301924 -0.0813881 0.454436 -0.0311504 -0.0814277 0.453723 -0.0298866 -0.0798577 0.449827 -0.0329217 -0.0814366 0.451719 -0.0326724 -0.0814427 0.451167 -0.0311046 -0.0797733 0.443133 0.0239433 -0.081265 0.443133 0.025 -0.081265 0.443587 0.025352 -0.0804798 0.443577 0.025 -0.080497 0.449095 0.0187929 -0.0797692 0.448467 0.017177 -0.0814704 0.448354 0.018926 -0.0797743 0.446441 0.0197462 -0.0798269 0.445999 0.018209 -0.0814482 0.445396 0.0205918 -0.0799006 0.445145 0.0189129 -0.0814312 0.444518 0.019616 -0.0814128 0.44489 0.0211669 -0.0799569 0.443571 0.0213114 -0.0813604 0.443907 0.0229966 -0.0802011 0.443616 0.025703 -0.0804283 0.443741 0.0264233 -0.0802995 0.447115 0.030631 -0.0797981 0.446934 0.0323134 -0.0814459 0.444618 0.0305109 -0.0814162 0.443476 0.0284169 -0.0813509 0.444541 0.0283346 -0.0800117 0.444268 0.0278573 -0.0800718 0.44321 0.0272558 -0.0813095 0.443954 0.027139 -0.0801788 0.456037 0.0242969 -0.0804283 0.455699 0.0228609 -0.0801788 0.455385 0.0221426 -0.0800718 0.456306 0.0222568 -0.0812544 0.455113 0.0216653 -0.0800117 0.45575 0.0206255 -0.0813504 0.453444 0.0180686 -0.0814516 0.449827 0.0170429 -0.0814721 0.449827 0.01875 -0.079765 0.451712 0.0172994 -0.0814684 0.451891 0.0191008 -0.0797817 0.452539 0.019369 -0.0797981 0.456464 0.0239841 -0.0811685 0.456067 0.0246479 -0.0804798 0.456067 0.025352 -0.0804798 0.449827 0.0329216 -0.0814366 0.449827 0.03125 -0.079765 0.455758 0.0293418 -0.0813396 0.455024 0.030508 -0.0814037 0.452566 0.0306178 -0.079799 0.452065 0.0308354 -0.0797851 0.451717 0.0326729 -0.0814427 0.456461 0.0260134 -0.0811628 0.456457 0.0264636 -0.0811817 0.456037 0.025703 -0.0804283 0.45592 0.02639 -0.0803052 0.455747 0.0270033 -0.0802011 0.431835 0.0512334 -0.0644624 0.430631 0.0502126 -0.0621073 0.415377 0.0233523 -0.0644624 0.415379 0.0218402 -0.0644624 0.415377 0.0233523 -0.0621073 0.415379 0.0218402 -0.0621073 0.416036 0.0204784 -0.0644624 0.418693 0.0192 -0.0644624 0.417218 -0.0195363 -0.0644624 0.417218 -0.0195363 -0.062145 0.416036 -0.0204785 -0.062145 0.415379 -0.0218403 -0.0644624 0.415377 -0.0233524 -0.0644624 0.415379 -0.0218403 -0.062145 0.415377 -0.0233524 -0.062145 0.416031 -0.0247157 -0.062145 0.430017 -0.048758 -0.0644624 0.431835 -0.0512334 -0.0644624 0.423199 0.0202897 -0.0644624 0.422065 0.0194843 -0.0644624 0.420704 0.0192 -0.0644624 0.420704 -0.0192 -0.0644624 0.422065 -0.0194844 -0.0644624 0.418693 -0.0192 -0.062145 0.418614 -0.0279045 -0.062145 0.423741 -0.0344881 -0.062145 0.426399 -0.0386524 -0.0644624 0.428905 -0.0442505 -0.062145 0.428677 -0.0435923 -0.062145 0.428904 0.0442486 -0.0621073 0.426399 0.0386523 -0.0644624 0.427952 0.0417656 -0.0644624 0.427108 0.039978 -0.0621073 0.416031 0.0247156 -0.0621073 0.417927 -0.00350004 -0.062965 0.420331 -0.00250421 -0.062965 0.408327 9.9958e-05 -0.062965 0.410027 0.00304444 -0.062965 0.408586 -0.00140117 -0.062965 0.421327 -0.000100042 -0.062965 0.421327 9.9958e-05 -0.062965 0.420331 0.00250412 -0.062965 0.421068 0.00140108 -0.062965 0.417927 0.00349996 -0.062965 0.417927 0.00349996 -0.077465 0.420331 0.00250412 -0.077465 0.419228 0.00324115 -0.062965 0.420871 0.00179996 -0.077465 0.421327 -0.000100042 -0.077465 0.421327 9.9958e-05 -0.077465 0.421068 -0.00140117 -0.062965 0.421068 -0.00140117 -0.077465 0.419228 -0.00324123 -0.062965 0.411727 -0.00350004 -0.062965 0.417927 -0.00350004 -0.077465 0.411727 -0.00350004 -0.077465 0.410426 -0.00324123 -0.062965 0.409323 -0.00250421 -0.062965 0.408327 -0.000100042 -0.062965 0.408327 -0.000100042 -0.077465 0.408782 0.00179996 -0.077465 0.408782 0.00179996 -0.062965 0.411727 0.00349996 -0.062965 0.410027 0.00304444 -0.077465 0.406533 -0.008799 -0.062965 0.421796 -0.0177905 -0.062965 0.4206 -0.0168006 -0.062965 0.419355 -0.014005 -0.062965 0.430005 -0.0150808 -0.062965 0.423308 -0.0181451 -0.062965 0.429971 -0.00670004 -0.062965 0.428727 -0.00545556 -0.062965 0.41203 -0.00500004 -0.062965 0.41532 -0.0130149 -0.062965 0.413317 -0.0145003 -0.062965 0.407438 -0.00649452 -0.062965 0.410952 -0.0159 -0.062965 0.410214 -0.0159808 -0.062965 0.407116 -0.0112316 -0.062965 0.412453 -0.0151421 -0.062965 0.406794 -0.00729134 -0.062965 0.412698 -0.0149685 -0.062965 0.408947 -0.0154244 -0.062965 0.408423 -0.0147276 -0.062965 0.411964 -0.0154561 -0.062965 0.408325 -0.0145257 -0.062965 0.408018 -0.0138054 -0.062965 0.402105 -0.0129079 -0.0686131 0.401589 -0.0108822 -0.0681399 0.403417 -0.015889 -0.0694365 0.403823 -0.0168271 -0.0700869 0.402509 -0.0130343 -0.0681426 0.405277 -0.0152733 -0.0663008 0.404149 -0.0131603 -0.066303 0.403335 -0.00891832 -0.0656816 0.403271 -0.0109709 -0.0662979 0.428328 -0.00525885 -0.077465 0.430427 -0.00840004 -0.062965 0.430168 -0.00709892 -0.077465 0.429431 -0.00599588 -0.077465 0.430427 -0.0134398 -0.062965 0.430427 -0.0134398 -0.077465 0.428843 -0.0163143 -0.077465 0.406327 -0.0182 -0.077465 0.405113 -0.0179762 -0.0711739 0.403305 -0.0163582 -0.077465 0.400824 -0.0115473 -0.0705981 0.400005 -0.00995823 -0.077465 0.401573 -0.0129998 -0.0704179 0.402589 -0.0149708 -0.0705832 0.400005 -0.00995823 -0.071051 0.399629 -0.00827887 -0.077465 0.400124 -0.00663055 -0.077465 0.401362 -0.00543556 -0.077465 0.401279 -0.00548362 -0.071051 0.401267 -0.00549061 -0.071051 0.402743 -0.00501192 -0.071051 0.402454 -0.00504862 -0.071051 0.427027 -0.00500004 -0.062965 0.427027 -0.00500004 -0.077465 0.414011 0.0139508 -0.062965 0.413245 0.014556 -0.062965 0.407813 0.0061913 -0.062965 0.413085 0.0146798 -0.062965 0.407897 0.00613229 -0.062965 0.414645 0.0134392 -0.062965 0.430168 0.00709883 -0.062965 0.419526 0.0142522 -0.062965 0.428328 0.00525877 -0.062965 0.418321 0.0131107 -0.062965 0.41052 0.00512807 -0.062965 0.428843 0.0163142 -0.062965 0.4206 0.0168005 -0.062965 0.430427 0.00839996 -0.062965 0.426097 0.0176028 -0.062965 0.412698 0.0149688 -0.062965 0.412456 0.0151399 -0.062965 0.406713 0.0074498 -0.062965 0.408762 0.0152292 -0.062965 0.408325 0.0145257 -0.062965 0.411783 0.0155584 -0.062965 0.40467 0.0165938 -0.0682101 0.405277 0.0152732 -0.0663008 0.402108 0.0129148 -0.0686135 0.406533 0.00879891 -0.062965 0.406692 0.00957259 -0.062965 0.407417 0.0121949 -0.062965 0.404149 0.0131602 -0.0663031 0.401568 0.00902764 -0.0674913 0.403271 0.0109708 -0.066298 0.401589 0.0108821 -0.06814 0.402509 0.0130343 -0.0681426 0.405685 0.0163727 -0.0666389 0.430005 0.0150807 -0.062965 0.430427 0.00839996 -0.077465 0.430427 0.0134397 -0.062965 0.429431 0.0059958 -0.062965 0.429431 0.0059958 -0.077465 0.428727 0.00545547 -0.077465 0.427027 0.00499996 -0.062965 0.41203 0.00499996 -0.062965 0.409505 0.00499996 -0.0649234 0.407279 0.00499996 -0.0667052 0.427027 0.00499996 -0.077465 0.402166 0.00511064 -0.071051 0.401362 0.00543548 -0.077465 0.403027 0.00499996 -0.077465 0.402454 0.00504854 -0.071051 0.400314 0.006351 -0.071051 0.401267 0.00549053 -0.071051 0.401362 0.00543548 -0.071051 0.400124 0.00663047 -0.077465 0.399629 0.00827878 -0.077465 0.399629 0.00827878 -0.071051 0.399747 0.00750454 -0.071051 0.401669 0.0131854 -0.0704115 0.402417 0.0146367 -0.070513 0.403305 0.0163581 -0.0711739 0.468088 0.0274082 -0.0434957 0.468088 0.0255107 -0.0453932 0.468088 0.0262707 -0.0442558 0.468134 0.02875 -0.043135 0.468261 0.0273089 -0.0432559 0.468134 0.02515 -0.046735 0.468261 0.0252709 -0.0452939 0.468261 0.0249843 -0.046735 0.468521 0.0272425 -0.0430957 0.468261 0.0260872 -0.0440722 0.468827 0.0272192 -0.0430395 0.468521 0.0259646 -0.0439496 0.468827 0.0259215 -0.0439065 0.468521 0.0251107 -0.0452275 0.468521 0.0248109 -0.046735 0.468027 0.03035 -0.0439637 0.468134 0.0312955 -0.0441894 0.468134 0.0318676 -0.044935 0.468027 0.0310127 -0.0444722 0.468027 0.0315212 -0.045135 0.468134 0.0322273 -0.0458032 0.468027 0.0318409 -0.0459067 0.468427 0.0325101 -0.0457274 0.468427 0.0315026 -0.0439823 0.468134 0.03055 -0.0436173 0.468427 0.0306964 -0.0433637 0.468134 0.0296817 -0.0432576 0.468427 0.0297575 -0.0429748 0.468027 0.02875 -0.043535 0.468261 0.02875 -0.0429693 0.468427 0.02875 -0.0428421 0.468521 0.02875 -0.0427959 0.468827 0.03275 -0.046735 0.468427 0.0321212 -0.0447886 0.468827 0.0297852 -0.0428713 0.474492 0.030191 -0.0432559 0.474666 0.0300917 -0.0434957 0.474727 0.02875 -0.043535 0.474727 0.0299745 -0.0437786 0.474233 0.0302574 -0.0430957 0.474492 0.0314127 -0.0440722 0.474233 0.0315353 -0.0439496 0.473927 0.0302807 -0.0430395 0.473927 0.03075 -0.0432709 0.474233 0.0323892 -0.0452275 0.474666 0.0312292 -0.0442558 0.474727 0.0317064 -0.0455104 0.474666 0.0319892 -0.0453932 0.474666 0.0322561 -0.046735 0.474492 0.032229 -0.0452939 0.473927 0.02475 -0.046735 0.47462 0.0273723 -0.043409 0.474727 0.0275254 -0.0437786 0.47462 0.0262044 -0.0441894 0.47462 0.025424 -0.0453573 0.474727 0.02555 -0.046735 0.474327 0.0248571 -0.046735 0.47462 0.02875 -0.043135 0.474492 0.02875 -0.0429693 0.474327 0.02875 -0.0428421 0.473927 0.0250544 -0.0452042 0.474327 0.0251535 -0.0452453 0.474327 0.0259973 -0.0439823 0.474327 0.0272602 -0.0431385 0.474233 0.02875 -0.0427959 0.474233 -0.0259647 -0.0439496 0.474727 -0.02875 -0.043535 0.474492 -0.027309 -0.0432559 0.474327 -0.02875 -0.0428421 0.474727 -0.0275255 -0.0437786 0.474666 -0.0274083 -0.0434957 0.474492 -0.0260873 -0.0440722 0.474233 -0.02875 -0.0427959 0.474233 -0.0272426 -0.0430957 0.473927 -0.0272193 -0.0430395 0.474233 -0.0251108 -0.0452275 0.474666 -0.0262708 -0.0442558 0.474727 -0.0257936 -0.0455104 0.474727 -0.0264873 -0.0444722 0.474666 -0.0255108 -0.0453932 0.474492 -0.025271 -0.0452939 0.474492 -0.0249844 -0.046735 0.474233 -0.0248109 -0.046735 0.474492 -0.0325157 -0.046735 0.47462 -0.0312956 -0.0441894 0.474727 -0.0299746 -0.0437786 0.474727 -0.0310128 -0.0444722 0.47462 -0.032076 -0.0453573 0.474727 -0.03195 -0.046735 0.474327 -0.0323465 -0.0452453 0.474327 -0.0326429 -0.046735 0.474327 -0.0315027 -0.0439823 0.47462 -0.02875 -0.043135 0.47462 -0.0301277 -0.043409 0.474492 -0.02875 -0.0429693 0.474327 -0.0302398 -0.0431385 0.473927 -0.0315785 -0.0439065 0.473927 -0.0302808 -0.0430395 0.468088 -0.0300918 -0.0434957 0.468027 -0.02875 -0.043535 0.468427 -0.02875 -0.0428421 0.468261 -0.0301911 -0.0432559 0.468521 -0.0302575 -0.0430957 0.468521 -0.02875 -0.0427959 0.468088 -0.0312293 -0.0442558 0.468261 -0.0322291 -0.0452939 0.468261 -0.0314128 -0.0440722 0.468521 -0.0315354 -0.0439496 0.468088 -0.0319893 -0.0453932 0.468088 -0.0322562 -0.046735 0.468521 -0.0323893 -0.0452275 0.468261 -0.0325157 -0.046735 0.468427 -0.0248572 -0.046735 0.468134 -0.0252727 -0.0458032 0.468134 -0.0278183 -0.0432576 0.468027 -0.0279218 -0.043644 0.468027 -0.02715 -0.0439637 0.468134 -0.02695 -0.0436173 0.468027 -0.0264873 -0.0444722 0.468134 -0.0256323 -0.044935 0.468027 -0.0259788 -0.045135 0.468027 -0.0256591 -0.0459067 0.468027 -0.02555 -0.046735 0.468427 -0.0253788 -0.0447886 0.468427 -0.0259974 -0.0439823 0.468134 -0.0262045 -0.0441894 0.468427 -0.0268036 -0.0433637 0.468134 -0.02875 -0.043135 0.468261 -0.02875 -0.0429693 0.468427 -0.0277425 -0.0429748 0.468827 -0.0248863 -0.0456997 0.468427 -0.0249899 -0.0457274 0.468827 -0.0252859 -0.044735 0.468827 -0.0259216 -0.0439065 0.468827 -0.02675 -0.0432709 0.426427 -0.00670004 -0.061765 0.425126 -0.00695885 -0.061765 0.428927 -0.00715556 -0.061765 0.430627 -0.0173 -0.061765 0.427227 -0.0207 -0.061765 0.423027 -0.0101 -0.061765 0.424727 -0.0202445 -0.061765 0.427227 -0.0207 -0.054065 0.426427 -0.0207 -0.054065 0.426427 -0.0207 -0.061765 0.423482 -0.019 -0.061765 0.423027 -0.0173 -0.061765 0.423286 -0.00879892 -0.061765 0.424023 -0.00769588 -0.061765 0.427227 -0.00670004 -0.054065 0.427227 -0.00670004 -0.061765 0.430171 -0.00840004 -0.054065 0.430171 -0.00840004 -0.061765 0.430627 -0.0101 -0.061765 0.430171 -0.019 -0.054065 0.430171 -0.019 -0.061765 0.428927 -0.0202445 -0.061765 0.426427 -0.00570004 -0.054065 0.424743 -0.00603497 -0.054065 0.422362 -0.00841623 -0.061765 0.427227 -0.00570004 -0.054065 0.427227 -0.00570004 -0.061765 0.431627 -0.0101 -0.054065 0.431551 -0.00928764 -0.0619893 0.427227 -0.0217 -0.054065 0.422876 -0.0198981 -0.0620711 0.422027 -0.0173 -0.054065 0.422523 -0.0193293 -0.061765 0.422616 -0.0195 -0.061876 0.423199 -0.0202898 -0.062145 0.424227 -0.0211106 -0.054065 0.425011 -0.00668169 -0.053765 0.424858 -0.00631214 -0.053765 0.423008 -0.00868411 -0.053765 0.422639 -0.00853104 -0.053765 0.422327 -0.0173 -0.053765 0.423223 -0.01915 -0.053765 0.422876 -0.01935 -0.053765 0.426427 -0.021 -0.053765 0.429277 -0.0208507 -0.053765 0.430431 -0.01915 -0.053765 0.431327 -0.0173 -0.053765 0.430927 -0.0101 -0.053765 0.431327 -0.0101 -0.053765 0.430777 -0.00805004 -0.053765 0.430431 -0.00825004 -0.053765 0.429077 -0.00689575 -0.053765 0.427227 -0.00600004 -0.053765 0.426427 -0.00640004 -0.053765 0.430368 0.0186011 -0.061765 0.428528 0.0204411 -0.061765 0.430627 0.0173 -0.061765 0.427227 0.0207 -0.061765 0.424023 0.0197041 -0.061765 0.423482 0.00839996 -0.061765 0.426427 0.00669996 -0.061765 0.427227 0.00669996 -0.061765 0.430627 0.0101 -0.061765 0.423027 0.0173 -0.061765 0.426427 0.0207 -0.061765 0.423286 0.0186011 -0.061765 0.430171 0.00839996 -0.054065 0.428927 0.00715547 -0.054065 0.430171 0.00839996 -0.061765 0.428927 0.00715547 -0.061765 0.426427 0.00669996 -0.054065 0.424727 0.00715547 -0.061765 0.423482 0.00839996 -0.054065 0.423027 0.0101 -0.061765 0.423286 0.0186011 -0.054065 0.425126 0.0204411 -0.061765 0.427227 0.0207 -0.054065 0.429631 0.0197041 -0.054065 0.429631 0.0197041 -0.061765 0.426427 0.0217 -0.054065 0.430338 0.0204112 -0.054065 0.427227 0.0217 -0.0644624 0.427227 0.0217 -0.054065 0.431551 0.00928755 -0.0619893 0.431292 0.00841615 -0.061765 0.431037 0.00789996 -0.054065 0.430338 0.00698869 -0.054065 0.430338 0.00698869 -0.061765 0.428911 0.00603489 -0.061765 0.426427 0.00569996 -0.054065 0.426427 0.00569996 -0.061765 0.427227 0.00569996 -0.061765 0.422027 0.0101 -0.054065 0.422616 0.00789996 -0.054065 0.424227 0.00628945 -0.061765 0.422027 0.0101 -0.061765 0.422027 0.0173 -0.054065 0.423199 0.0202897 -0.0621073 0.422799 0.0197898 -0.0620126 0.423316 0.0204112 -0.054065 0.422492 0.0192698 -0.061765 0.422027 0.0173 -0.061765 0.426427 0.0217 -0.0644624 0.426427 0.0214 -0.053765 0.424858 0.0210879 -0.053765 0.423528 0.0201991 -0.053765 0.423008 0.0187159 -0.053765 0.422639 0.018869 -0.053765 0.422327 0.0173 -0.053765 0.422327 0.0101 -0.053765 0.422727 0.0101 -0.053765 0.423223 0.00824996 -0.053765 0.427227 0.00639996 -0.053765 0.426427 0.00599996 -0.053765 0.427227 0.00599996 -0.053765 0.430777 0.00804996 -0.053765 0.430927 0.0101 -0.053765 0.430645 0.0187159 -0.053765 0.431327 0.0173 -0.053765 0.428643 0.0207183 -0.053765 0.428796 0.0210879 -0.053765 0.427227 0.021 -0.053765 0.427227 0.0214 -0.053765 0.457327 -0.0482 -0.070845 0.440684 -0.0480129 -0.0647624 0.442327 -0.0482 -0.070845 0.442327 -0.0482 -0.0647624 0.438642 -0.0427824 -0.070845 0.438642 -0.0427824 -0.0647624 0.438071 -0.0443151 -0.0647624 0.438282 -0.0459368 -0.070845 0.439226 -0.0472724 -0.0647624 0.439226 -0.0472724 -0.070845 0.458969 -0.0480129 -0.0647624 0.460428 -0.0472724 -0.070845 0.461371 -0.0459368 -0.070845 0.460428 -0.0472724 -0.0647624 0.461371 -0.0459368 -0.0647624 0.461582 -0.0443151 -0.0647624 0.459792 -0.0416934 -0.0647624 0.441449 -0.0413 -0.070845 0.440684 -0.0480129 -0.070845 0.458204 -0.0413 -0.070845 0.458969 -0.0480129 -0.070845 0.461012 -0.0427824 -0.070845 0.461582 -0.0443151 -0.070845 0.459792 -0.0416934 -0.070845 0.438071 -0.0443151 -0.070845 0.439862 -0.0416934 -0.070845 0.463194 0.0514622 -0.0591922 0.464085 0.0514597 -0.0570337 0.462333 0.0516 -0.05877 0.460995 0.0511414 -0.0644624 0.460048 0.0514886 -0.0642754 0.461025 0.0511406 -0.0644298 0.460855 0.0514791 -0.0633213 0.462922 0.0510746 -0.0617139 0.462151 0.0514676 -0.0612989 0.464609 0.0512862 -0.0566897 0.466761 0.050014 -0.0564475 0.46804 0.0491132 -0.0559136 0.468551 0.0487018 -0.0557254 0.470172 0.0472938 -0.0544293 0.47022 0.0471004 -0.0552156 0.471681 0.0452789 -0.0549035 0.472981 0.0433957 -0.0538998 0.474009 0.0413102 -0.0537997 0.474739 0.0391298 -0.0545899 0.474834 0.0391814 -0.0537451 0.475386 0.036975 -0.0545578 0.474179 0.0333858 -0.0537079 0.472548 0.032768 -0.0537079 0.473477 0.0329994 -0.0537079 0.473005 0.032847 -0.0537079 0.473699 0.0330989 -0.0537079 0.475432 0.0355456 -0.05457 0.475016 0.0344011 -0.0544592 0.474788 0.0340578 -0.0543984 0.47205 0.0352449 -0.0644624 0.47364 0.0347767 -0.0597417 0.473234 0.0340606 -0.0596059 0.472183 0.0361907 -0.0644624 0.473864 0.0355512 -0.0598168 0.472177 0.0363421 -0.0644624 0.473817 0.036982 -0.0598009 0.468827 0.03275 -0.0636676 0.469755 0.0329036 -0.0640676 0.475202 0.0347724 -0.0545088 0.472996 0.0328516 -0.0539205 0.47355 0.0330508 -0.0540682 0.472018 0.0330514 -0.0591988 0.474155 0.0334184 -0.0542295 0.472675 0.0334703 -0.0594188 0.474219 0.0334688 -0.0542466 0.47007 0.0330766 -0.0644624 0.45978 -0.0516 -0.0632533 0.460048 -0.0514886 -0.0642754 0.460855 -0.0514792 -0.0633213 0.462151 -0.0514677 -0.0612989 0.462317 -0.0516 -0.0588053 0.463182 -0.0516 -0.0566897 0.464085 -0.0514598 -0.0570337 0.463194 -0.0514622 -0.0591922 0.462922 -0.0510747 -0.0617139 0.46154 -0.0511196 -0.0638146 0.464924 -0.0510439 -0.057353 0.475487 -0.0370156 -0.0537079 0.474014 -0.0412984 -0.0537993 0.472986 -0.0433868 -0.0538992 0.468409 -0.0489373 -0.0549767 0.468552 -0.0487014 -0.0557252 0.466528 -0.0502631 -0.0557401 0.464609 -0.0512863 -0.0566897 0.475386 -0.0369751 -0.0545578 0.473864 -0.0355513 -0.0598168 0.471926 -0.0349032 -0.0644624 0.47364 -0.0347767 -0.0597417 0.468827 -0.03275 -0.0636676 0.469755 -0.0329037 -0.0640676 0.472996 -0.0328517 -0.0539205 0.472018 -0.0330515 -0.0591988 0.470693 -0.03275 -0.0587487 0.472675 -0.0334704 -0.0594188 0.474155 -0.0334185 -0.0542295 0.475432 -0.0355457 -0.05457 0.475202 -0.0347725 -0.0545088 0.475016 -0.0344012 -0.0544592 0.473234 -0.0340606 -0.0596059 0.469698 -0.032935 -0.0644624 0.468761 -0.0327473 -0.0644624 0.471715 -0.0400123 -0.0628502 0.470152 -0.0423908 -0.06399 0.463248 -0.0508143 -0.0619555 0.47207 -0.0369858 -0.0644624 0.473126 -0.0374469 -0.0614192 0.473703 -0.0386269 -0.0586655 0.47393 -0.0412291 -0.0546382 0.472287 -0.0411944 -0.0599736 0.472923 -0.0432875 -0.0547287 0.469948 -0.047392 -0.0552875 0.470225 -0.0470949 -0.0552143 0.469006 -0.0456999 -0.0617488 0.471686 -0.0452724 -0.0549027 0.466767 -0.0500104 -0.0564449 0.473817 -0.036982 -0.0598009 0.474741 -0.0391228 -0.0545897 0.470779 -0.0406589 -0.0644624 0.470714 -0.0435534 -0.0610096 0.469029 -0.0439647 -0.0644624 0.467183 -0.0476291 -0.0621665 0.464804 -0.0487735 -0.0644624 0.462962 -0.0500927 -0.0644624 0.465262 -0.0493359 -0.0622413 0.464008 -0.0510535 -0.0595519 0.465691 -0.0501135 -0.0589481 0.467656 -0.0484913 -0.058898 0.472558 -0.032769 -0.0537079 0.472863 -0.0328156 -0.0537079 0.473469 -0.0329963 -0.0537079 0.473674 -0.0330868 -0.0537079 0.474904 -0.0340909 -0.0522413 0.475487 -0.0370156 -0.0522086 0.475529 -0.0354666 -0.0537079 0.475529 -0.0354666 -0.0522065 0.464609 -0.0512863 -0.0542566 0.466151 -0.0504874 -0.0537714 0.46762 -0.0495389 -0.0533639 0.468055 -0.0492157 -0.0532543 0.469434 -0.0480382 -0.054638 0.470177 -0.0472882 -0.0544279 0.469434 -0.0480382 -0.0529424 0.471707 -0.0454149 -0.0540896 0.472249 -0.044617 -0.0524768 0.47235 -0.0444593 -0.0524644 0.473171 -0.0430454 -0.0523733 0.473676 -0.0420434 -0.0538275 0.47409 -0.0411224 -0.0522926 0.474836 -0.0391743 -0.053745 0.474977 -0.03875 -0.0522342 0.464475 -0.0513448 -0.054305 0.46425 -0.051428 -0.0543871 0.463911 -0.051521 -0.0545134 0.465262 0.0493357 -0.0622415 0.465691 0.0501133 -0.0589484 0.463248 0.0508141 -0.0619557 0.472287 0.0411943 -0.0599738 0.47207 0.0369858 -0.0644624 0.473703 0.0386267 -0.0586657 0.470167 0.0419605 -0.0644624 0.471715 0.0400122 -0.0628503 0.464924 0.0510439 -0.057353 0.464008 0.0510535 -0.0595519 0.470714 0.0435533 -0.0610098 0.469948 0.0473919 -0.0552874 0.473925 0.0412407 -0.0546386 0.472918 0.0432963 -0.0547293 0.470152 0.0423907 -0.0639901 0.469245 0.0436179 -0.0644624 0.469006 0.0456997 -0.061749 0.467183 0.047629 -0.0621667 0.461295 0.0510034 -0.0644624 0.46154 0.0511195 -0.0638146 0.475487 0.0370155 -0.0537079 0.475504 0.0369487 -0.0537079 0.475531 0.0354757 -0.0537079 0.475599 0.0361742 -0.052164 0.475594 0.036323 -0.0521642 0.474892 0.0340743 -0.0537079 0.474217 0.0334141 -0.0537079 0.47487 0.0340467 -0.0522041 0.47415 0.0333657 -0.0522576 0.473699 0.0330987 -0.0522989 0.473199 0.0329006 -0.0537079 0.472969 0.0328384 -0.0537079 0.47322 0.0329068 -0.0523495 0.472853 0.0328135 -0.0537079 0.472199 0.03275 -0.0524819 0.472199 0.03275 -0.0537079 0.475217 0.0379797 -0.052182 0.473817 0.0417405 -0.0522738 0.473676 0.0420433 -0.0538275 0.473676 0.0420431 -0.0522857 0.466522 0.0502667 -0.0557428 0.471702 0.0454215 -0.0540905 0.469434 0.0480381 -0.054638 0.468408 0.0489377 -0.054977 0.469703 0.0477766 -0.0528443 0.468085 0.049193 -0.0532028 0.465468 0.0508631 -0.0539346 0.466462 0.0503031 -0.0536358 0.463335 0.0515965 -0.0546933 0.463562 0.0515787 -0.0546049 0.463907 0.0515217 -0.0544722 0.473635 0.0225076 -0.0644624 0.475465 0.0215771 -0.060196 0.472995 0.0235329 -0.0644624 0.475178 0.0227715 -0.060097 0.472117 0.0242344 -0.0644624 0.474442 0.0238441 -0.0598437 0.473376 0.0245375 -0.0594764 0.47397 0.02475 -0.0535086 0.475158 0.0245188 -0.0538333 0.476207 0.0238359 -0.0541198 0.476828 0.0231919 -0.0535086 0.477049 0.0227912 -0.0535086 0.476937 0.0227985 -0.0543191 0.477361 0.0215993 -0.0535086 0.477275 0.0211268 -0.0544003 0.477394 0.0211403 -0.053506 0.477306 0.0206683 -0.0543982 0.474148 0.0170519 -0.0535035 0.474247 0.0170567 -0.0535035 0.474207 0.0170544 -0.0535035 0.474217 0.0170549 -0.0535035 0.474644 0.0171052 -0.0535035 0.475388 0.0173314 -0.0535035 0.476426 0.0181243 -0.0541575 0.47714 0.0193589 -0.0543527 0.477237 0.0193108 -0.0535035 0.474725 0.0171211 -0.0535035 0.475283 0.0173065 -0.0538452 0.475848 0.0206623 -0.0592466 0.472627 0.01705 -0.05818 0.474244 0.017057 -0.0535611 0.474033 0.01705 -0.0535035 0.475302 0.0206434 -0.0608453 0.471976 0.0170037 -0.061377 0.472236 0.0172964 -0.0644624 0.47398 0.0182 -0.062201 0.473037 0.0173688 -0.0617988 0.473833 0.0172965 -0.0585795 0.474549 0.0193592 -0.0624793 0.474968 0.0181092 -0.0589551 0.47568 0.0193464 -0.0591908 0.472274 -0.0173206 -0.0644624 0.471615 -0.0169719 -0.0644624 0.473842 -0.019484 -0.0644624 0.474549 -0.0193593 -0.0624793 0.47398 -0.0182001 -0.062201 0.472639 -0.01759 -0.0644624 0.473198 -0.0181641 -0.0644624 0.475682 -0.0193545 -0.0591917 0.474979 -0.0181222 -0.0589589 0.473037 -0.0173689 -0.0617988 0.47714 -0.0193589 -0.0543527 0.476426 -0.0181244 -0.0541575 0.473856 -0.0173061 -0.0585869 0.473361 -0.01705 -0.0558511 0.477427 -0.0206607 -0.0535035 0.477306 -0.0206684 -0.0543982 0.477275 -0.0211269 -0.0544003 0.475597 -0.0243352 -0.0535086 0.475158 -0.0245189 -0.0538333 0.477242 -0.0215853 -0.0544024 0.473449 -0.0229028 -0.0644624 0.471217 -0.0246073 -0.0644624 0.474442 -0.0238442 -0.0598432 0.473376 -0.0245376 -0.0594759 0.471469 -0.0245291 -0.0644624 0.473787 -0.0220021 -0.0644624 0.473822 -0.0218064 -0.0644624 0.475178 -0.0227716 -0.0600966 0.476207 -0.023836 -0.0541198 0.476937 -0.0227986 -0.0543191 0.475465 -0.0215772 -0.0601955 0.474434 -0.0205427 -0.0631894 0.473847 -0.0215732 -0.0644624 0.475848 -0.0206624 -0.0592466 0.474207 -0.0170545 -0.0535035 0.474148 -0.017052 -0.0535035 0.474294 -0.0170601 -0.0535035 0.474282 -0.0170591 -0.0522276 0.474334 -0.0170633 -0.0535035 0.474381 -0.0170679 -0.0535035 0.475388 -0.0173314 -0.0535035 0.476343 -0.0179546 -0.0521083 0.477426 -0.0206813 -0.0535035 0.477237 -0.0193109 -0.0535035 0.476828 -0.023192 -0.0520941 0.476828 -0.023192 -0.0535086 0.477049 -0.0227913 -0.0535086 0.477171 -0.0224949 -0.0520867 0.477218 -0.0223536 -0.0520859 0.475882 -0.0241611 -0.0521259 0.476295 -0.0238308 -0.0535086 0.476704 -0.0233712 -0.0520973 0.475597 -0.0243353 -0.0521392 0.47397 -0.02475 -0.0535086 0.477361 -0.0215994 -0.0535086 0.477361 -0.0215994 -0.0520835 0.477378 -0.0213607 -0.0535072 0.477394 -0.0211404 -0.053506 0.477242 0.0215852 -0.0544024 0.473925 0.0204426 -0.0644624 0.475906 0.0241448 -0.0521245 0.475597 0.0243351 -0.0535086 0.476721 0.0233473 -0.0520964 0.476295 0.0238307 -0.0535086 0.47663 0.0234666 -0.0520989 0.477181 0.022467 -0.0520862 0.476828 0.0231919 -0.0520937 0.477427 0.0206606 -0.0535035 0.477426 0.0206812 -0.0520822 0.477433 0.0204271 -0.0520821 0.477234 0.0193036 -0.0520853 0.476767 0.0184276 -0.0520954 0.476518 0.018129 -0.0535035 0.474381 0.0170678 -0.0535035 0.474033 0.01705 -0.0522491 0.474334 0.0170633 -0.0535035 0.474294 0.01706 -0.0535035 0.474279 0.0170589 -0.0535035 0.477426 0.0206812 -0.0535035 0.477409 0.0209199 -0.0535048 0.477361 0.0215993 -0.0520831 0.477242 -0.00140199 -0.0560444 0.475602 -0.00135968 -0.0611993 0.476535 -0.00250484 -0.0558383 0.473463 -0.00350004 -0.0576653 0.475475 -0.00324158 -0.05553 0.477627 -5.49101e-08 -0.0551666 0.477491 -0.000100938 -0.0561168 0.47583 -0.000100853 -0.0612804 0.474485 -0.00109025 -0.0644624 0.474395 -0.0013523 -0.0644624 0.474892 -0.00250449 -0.0609465 0.473907 -0.00221004 -0.0644624 0.47488 -0.00251641 -0.0609425 0.473852 -0.00324131 -0.0605768 0.472899 -0.00310632 -0.0644624 0.473784 -0.00327025 -0.0605526 0.472627 -0.00350004 -0.0601407 0.477491 3.40874e-06 -0.0561169 0.473463 0.00349996 -0.0576653 0.475602 0.0013596 -0.0611993 0.477242 0.00140191 -0.0560444 0.47488 0.00251632 -0.0609425 0.476535 0.00250475 -0.0558383 0.475475 0.00324149 -0.05553 0.47272 0.00320936 -0.0644624 0.471925 0.00353486 -0.0644624 0.472627 0.00349996 -0.0601407 0.471648 0.00360519 -0.0644624 0.474617 0.000185458 -0.0644624 0.473149 0.00293983 -0.0644624 0.473784 0.00327016 -0.0605526 0.47372 0.00243203 -0.0644624 0.476125 1.51001e-05 -0.060436 0.476152 3.38605e-06 -0.0603582 0.477491 -4.19898e-08 -0.0561169 0.474617 -4.19898e-08 -0.0644624 0.47583 0.000100769 -0.0612804 0.474617 -0.000185542 -0.0644624 0.474617 -9.27896e-05 -0.0644624 0.476153 -3.1744e-08 -0.0603557 0.476631 -0.00250423 -0.0520988 0.477627 -0.000100902 -0.0551665 0.477368 -0.00140117 -0.0551665 0.476631 -0.00250421 -0.0551665 0.475528 -0.00324123 -0.0551665 0.4751 -0.00338594 -0.0521675 0.474227 -0.00350004 -0.0551665 0.475228 0.00334911 -0.0521596 0.476246 0.00283566 -0.0521113 0.477037 0.00201359 -0.0520888 0.477627 9.9958e-05 -0.0551665 0.477627 9.9958e-05 -0.052079 0.477512 0.000975738 -0.0520805 0.468827 0.02475 -0.046735 0.468827 0.0250544 -0.0452042 0.473927 0.0259215 -0.0439065 0.473927 0.0272192 -0.0430395 0.473927 0.02875 -0.042735 0.468827 0.02875 -0.042735 0.468827 0.0322141 -0.044735 0.473927 0.0324455 -0.0452042 0.468827 0.0326137 -0.0456997 0.468827 0.03075 -0.0432709 0.468827 0.0315784 -0.0439065 0.473927 0.0315784 -0.0439065 0.473927 0.0322141 -0.044735 0.473927 -0.02875 -0.042735 0.468827 -0.02875 -0.042735 0.468827 -0.0302808 -0.0430395 0.468827 -0.0315785 -0.0439065 0.468827 -0.0324456 -0.0452042 0.468827 -0.03275 -0.046735 0.473927 -0.0324456 -0.0452042 0.468827 -0.0277148 -0.0428713 0.473927 -0.02675 -0.0432709 0.473927 -0.0259216 -0.0439065 0.473927 -0.0252859 -0.044735 0.473927 -0.0250545 -0.0452042 0.474352 -0.0271 -0.046735 0.474352 -0.0273211 -0.04591 0.474352 -0.027925 -0.045306 0.474727 -0.0277375 -0.0449813 0.474727 -0.02875 -0.04471 0.474727 -0.0305037 -0.0457225 0.474352 -0.030179 -0.04591 0.474352 -0.0304 -0.046735 0.468027 -0.0273211 -0.04591 0.468027 -0.02875 -0.045085 0.468027 -0.029575 -0.045306 0.474352 -0.02875 -0.045085 0.474352 -0.029575 -0.045306 0.474727 0.030775 -0.046735 0.474352 0.02875 -0.045085 0.474727 0.0297625 -0.0449813 0.474727 0.02875 -0.04471 0.474352 0.027925 -0.045306 0.474727 0.0277375 -0.0449813 0.474727 0.0269963 -0.0457225 0.474352 0.0301789 -0.04591 0.474352 0.029575 -0.045306 0.468027 0.02875 -0.045085 0.468027 0.027925 -0.045306 0.474352 0.027321 -0.04591 0.474352 0.0271 -0.046735 0.469227 0.00809996 -0.057735 0.474328 0.00495877 -0.057735 0.475431 0.0056958 -0.057735 0.469682 0.01415 -0.057735 0.472627 0.00469996 -0.057735 0.470927 0.00515547 -0.057735 0.475971 0.01415 -0.057735 0.476427 0.00809996 -0.057735 0.476427 0.01245 -0.057735 0.473027 0.01585 -0.057735 0.469682 0.00639996 -0.057735 0.472627 0.00469996 -0.043035 0.473027 0.00469996 -0.057735 0.473027 0.00469996 -0.043035 0.474727 0.00515547 -0.043035 0.475431 0.0056958 -0.043035 0.476168 0.00679883 -0.057735 0.476427 0.00809996 -0.043035 0.475971 0.01415 -0.043035 0.474727 0.0153944 -0.057735 0.472627 0.01585 -0.057735 0.472627 0.01585 -0.043035 0.470927 0.0153944 -0.057735 0.470927 0.0153944 -0.043035 0.469227 0.01245 -0.057735 0.469682 0.01415 -0.043035 0.472627 -0.00470004 -0.057735 0.470223 -0.0148542 -0.057735 0.474328 -0.0155912 -0.057735 0.469227 -0.00810004 -0.057735 0.469227 -0.01245 -0.057735 0.469227 -0.01245 -0.043035 0.469486 -0.0137512 -0.057735 0.470223 -0.0148542 -0.043035 0.471326 -0.0155912 -0.057735 0.471326 -0.0155912 -0.043035 0.472627 -0.01585 -0.057735 0.473027 -0.01585 -0.057735 0.474727 -0.0153945 -0.043035 0.475431 -0.0148542 -0.057735 0.476168 -0.0137512 -0.057735 0.476427 -0.01245 -0.057735 0.476427 -0.00810004 -0.043035 0.476427 -0.00810004 -0.057735 0.475971 -0.00640004 -0.057735 0.473027 -0.00470004 -0.043035 0.474328 -0.00495885 -0.043035 0.473027 -0.00470004 -0.057735 0.474727 -0.00515556 -0.057735 0.474727 -0.00515556 -0.043035 0.472627 -0.00470004 -0.043035 0.470927 -0.00515556 -0.057735 0.469682 -0.00640004 -0.057735 0.471035 -0.0167657 -0.0644624 0.468377 -0.0142104 -0.043035 0.469374 -0.0157027 -0.0644624 0.470866 -0.0166999 -0.043035 0.471976 -0.0170038 -0.061377 0.473027 -0.01705 -0.0523469 0.472627 -0.01705 -0.05818 0.474033 -0.01705 -0.0535035 0.477627 -0.01245 -0.0517766 0.476941 -0.0148665 -0.05179 0.477277 -0.0142104 -0.0517826 0.473746 -0.0169935 -0.0522193 0.474311 -0.0168671 -0.0520354 0.475327 -0.0164338 -0.043035 0.472627 -0.00440004 -0.042735 0.472627 -0.00380004 -0.042735 0.469423 -0.00625004 -0.042735 0.468903 -0.00595004 -0.042735 0.468927 -0.00810004 -0.042735 0.47001 -0.0150663 -0.042735 0.469586 -0.0154906 -0.042735 0.471211 -0.0158684 -0.042735 0.470981 -0.0164227 -0.042735 0.472627 -0.01675 -0.042735 0.473027 -0.01615 -0.042735 0.474877 -0.0156543 -0.042735 0.473027 -0.01675 -0.042735 0.476751 -0.0146 -0.042735 0.477327 -0.01245 -0.042735 0.476727 -0.00810004 -0.042735 0.476999 -0.0064545 -0.042735 0.476067 -0.00505948 -0.042735 0.475643 -0.00548375 -0.042735 0.474672 -0.00412736 -0.042735 0.473027 -0.00380004 -0.042735 0.470327 -0.00411633 -0.043035 0.468027 -0.00810004 -0.043035 0.468311 -0.0065079 -0.0644624 0.468643 -0.00580004 -0.043035 0.473027 -0.00350004 -0.043035 0.474787 -0.0038502 -0.043035 0.473633 -0.00354012 -0.0522447 0.473027 -0.00350004 -0.0523458 0.477627 -0.00810004 -0.0517766 0.477277 -0.0063397 -0.043035 0.476279 -0.00484735 -0.043035 0.476851 -0.00554376 -0.0517923 0.476619 -0.00522706 -0.0517988 0.473623 -0.00350004 -0.0522851 0.468027 0.00809996 -0.0644624 0.469374 0.00484727 -0.043035 0.471035 0.00378428 -0.0644624 0.474227 0.00349996 -0.0522327 0.477531 0.00716373 -0.0517781 0.475652 0.00432265 -0.0518358 0.473027 0.00349996 -0.0523458 0.473027 0.00349996 -0.043035 0.477627 0.00809996 -0.043035 0.477627 0.01245 -0.0517766 0.472627 0.01615 -0.042735 0.472627 0.01675 -0.042735 0.470477 0.0161739 -0.042735 0.469423 0.0143 -0.042735 0.468327 0.01245 -0.042735 0.468927 0.01245 -0.042735 0.468927 0.00809996 -0.042735 0.469423 0.00624996 -0.042735 0.468903 0.00594996 -0.042735 0.470477 0.00437605 -0.042735 0.472627 0.00439996 -0.042735 0.472627 0.00379996 -0.042735 0.474877 0.00489566 -0.042735 0.475177 0.00437605 -0.042735 0.476231 0.00624996 -0.042735 0.477327 0.00809996 -0.042735 0.477327 0.01245 -0.042735 0.476231 0.0143 -0.042735 0.476751 0.0146 -0.042735 0.474877 0.0156543 -0.042735 0.473027 0.01615 -0.042735 0.468027 0.01245 -0.0644624 0.468027 0.01245 -0.043035 0.468643 0.01475 -0.043035 0.469374 0.0157026 -0.043035 0.469374 0.0157026 -0.0644624 0.470327 0.0164337 -0.043035 0.47431 0.0168672 -0.0520352 0.475791 0.0161271 -0.0518294 0.475467 0.0163493 -0.051845 0.474787 0.0166998 -0.0518847 0.47458 0.0167797 -0.0518988 0.476619 0.0153229 -0.0517988 0.476279 0.0157026 -0.043035 0.476851 0.0150062 -0.0517923 0.477368 0.0139723 -0.0517809 0.477011 0.01475 -0.043035 0.477627 0.01245 -0.043035 0.473361 0.01705 -0.0558511 0.473027 0.01705 -0.0523465 0.472627 0.01705 -0.043035 0.468827 -0.02475 -0.0644624 0.472269 -0.02475 -0.0590583 0.468027 -0.02555 -0.0644624 0.468134 -0.02515 -0.046735 0.468827 -0.02475 -0.046735 0.468427 -0.0248572 -0.0644624 0.468521 -0.0326891 -0.046735 0.468261 -0.0325157 -0.0644624 0.468088 -0.0322562 -0.0644624 0.472199 -0.03275 -0.0537079 0.472199 -0.03275 -0.0525199 0.473927 -0.03275 -0.046735 0.473581 -0.03275 -0.0520472 0.473728 -0.03275 -0.0519676 0.473856 -0.03275 -0.0519561 0.472987 -0.03275 -0.0523145 0.473349 -0.03275 -0.0521621 0.473927 -0.02475 -0.046735 0.474175 -0.0247894 -0.0521918 0.474552 -0.0250512 -0.0519008 0.474526 -0.0250196 -0.0519027 0.474415 -0.0249164 -0.0520262 0.474666 -0.0252439 -0.046735 0.474727 -0.02555 -0.046735 0.474708 -0.0321237 -0.05189 0.47462 -0.03235 -0.046735 0.474666 -0.0322562 -0.0518929 0.474606 -0.0323724 -0.051897 0.474428 -0.0325739 -0.0519099 0.474192 -0.0327048 -0.051928 0.474727 -0.0269963 -0.0477475 0.474727 -0.02875 -0.04876 0.474727 -0.0317065 -0.0455104 0.474727 -0.0297625 -0.0449813 0.474727 -0.0269963 -0.0457225 0.472269 0.02475 -0.0590582 0.47397 0.02475 -0.0522546 0.47462 0.02515 -0.046735 0.474726 0.0255082 -0.0518888 0.47462 0.0251499 -0.0518961 0.474525 0.0250189 -0.0519028 0.473948 0.0247502 -0.0522561 0.474182 0.0247919 -0.0521878 0.474329 0.0248586 -0.0520983 0.474727 0.03195 -0.0518887 0.474727 0.0305037 -0.0457225 0.474727 0.0297625 -0.0484887 0.474727 0.02875 -0.04876 0.474727 0.0310127 -0.0444722 0.474727 0.02555 -0.0518887 0.474727 0.0269963 -0.0477475 0.474727 0.026725 -0.046735 0.474727 0.0257935 -0.0455104 0.474727 0.0264872 -0.0444722 0.474233 0.0326891 -0.046735 0.474233 0.0326891 -0.0519248 0.473927 0.03275 -0.046735 0.474105 0.0327299 -0.0519351 0.474492 0.0325156 -0.046735 0.474552 0.0324488 -0.0519008 0.474727 0.03195 -0.046735 0.474682 0.0322143 -0.0518918 0.473856 0.03275 -0.0519561 0.470693 0.03275 -0.0587487 0.47382 0.03275 -0.0519593 0.468427 0.0248571 -0.0644624 0.468427 0.0248571 -0.046735 0.468088 0.0252438 -0.046735 0.468027 0.03195 -0.046735 0.468134 0.03235 -0.046735 0.468261 0.0325156 -0.046735 0.468427 0.0326428 -0.046735 0.439327 -0.0398 -0.070845 0.437681 -0.0394727 -0.0647624 0.437177 -0.039224 -0.070845 0.436286 -0.0385406 -0.0647624 0.435603 -0.03765 -0.070845 0.460327 -0.0398 -0.070845 0.439327 -0.0398 -0.0647624 0.464051 -0.03765 -0.0647624 0.464051 -0.03765 -0.070845 0.464627 0.0409 -0.070845 0.457327 0.0482 -0.070845 0.462489 0.0460618 -0.0647624 0.462489 0.0460618 -0.070845 0.464071 0.0436935 -0.070845 0.435027 0.0409 -0.0647624 0.437165 0.0460618 -0.0647624 0.437165 0.0460618 -0.070845 0.435027 -0.0355 -0.0647624 0.462477 -0.039224 -0.070845 0.445027 -0.0358 -0.070845 0.435027 -0.0355 -0.070845 0.438527 0.0293 -0.070845 0.440431 0.0338962 -0.070845 0.435027 0.0409 -0.070845 0.435582 0.0436935 -0.070845 0.439533 0.0476443 -0.070845 0.442327 0.0482 -0.070845 0.454627 0.0358 -0.070845 0.46012 0.0476443 -0.070845 0.457114 0.0353052 -0.070845 0.460632 0.0317874 -0.070845 0.461127 0.0293 -0.070845 0.464627 -0.0355 -0.070845 0.460632 -0.0317875 -0.070845 0.454627 -0.0355 -0.071145 0.454627 -0.0355 -0.079265 0.445027 -0.0355 -0.071145 0.445027 -0.0355 -0.079265 0.439299 -0.0316727 -0.079265 0.440643 -0.0336841 -0.079265 0.440643 -0.0336841 -0.071145 0.442654 -0.0350281 -0.079265 0.445027 0.0355 -0.079265 0.442654 0.035028 -0.079265 0.445027 0.0355 -0.071145 0.440643 0.033684 -0.079265 0.439299 0.0316726 -0.071145 0.438827 0.0293 -0.079265 0.438827 0.0293 -0.071145 0.460827 0.0293 -0.071145 0.460355 0.0316726 -0.071145 0.459011 0.033684 -0.079265 0.456999 0.035028 -0.071145 0.456999 -0.0350281 -0.079265 0.456999 -0.0350281 -0.071145 0.459011 -0.0336841 -0.071145 0.460827 -0.0293 -0.071145 0.455484 0.00965681 -0.079265 0.447115 0.030631 -0.079265 0.449827 -0.01875 -0.079265 0.452888 -0.00339108 -0.079265 0.460355 0.0316726 -0.079265 0.449827 -0.03125 -0.079265 0.454713 -0.0288969 -0.079265 0.449827 0.03125 -0.079265 0.454627 0.0355 -0.079265 0.456999 0.035028 -0.079265 0.457218 0.00706143 -0.079265 0.439299 0.0316726 -0.079265 0.460827 0.0293 -0.079265 0.457827 0.00399996 -0.079265 0.44417 -0.0016569 -0.079265 0.438827 -0.0293 -0.079265 0.443734 -0.0263908 -0.079265 0.459011 -0.0336841 -0.079265 0.460355 -0.0316727 -0.079265 0.45592 -0.0263908 -0.079265 0.460827 -0.0293 -0.079265 0.455484 -0.0016569 -0.079265 0.452539 -0.019369 -0.079265 0.44417 0.00965681 -0.079265 0.449827 0.012 -0.079265 0.468311 -0.0140422 -0.0644624 0.469563 -0.0430819 -0.0644624 0.467574 -0.0459871 -0.0644624 0.471253 -0.0168401 -0.0644624 0.468311 0.0140421 -0.0644624 0.43903 -0.0474994 -0.0644624 0.430631 -0.0502127 -0.0644624 0.459932 -0.0414281 -0.0644624 0.462627 -0.0394838 -0.0644624 0.426427 -0.0217 -0.0644624 0.424227 -0.0211106 -0.0644624 0.465927 -0.0477788 -0.0644624 0.460995 -0.0511415 -0.0644624 0.459037 -0.0483052 -0.0644624 0.460321 -0.0513844 -0.0644624 0.457327 -0.0485 -0.0644624 0.433371 -0.0516 -0.0644624 0.423199 -0.0202898 -0.0644624 0.469374 -0.00484735 -0.0644624 0.469374 0.00484727 -0.0644624 0.468311 0.00650782 -0.0644624 0.472548 -0.0175164 -0.0644624 0.427952 -0.0417657 -0.0644624 0.428677 -0.0435923 -0.0644624 0.416036 -0.0204785 -0.0644624 0.473054 0.00300647 -0.0644624 0.471444 0.0245377 -0.0644624 0.470985 0.0246633 -0.0644624 0.473887 0.0210079 -0.0644624 0.470151 0.02475 -0.0644624 0.468827 0.02475 -0.0644624 0.470151 -0.02475 -0.0644624 0.471448 -0.0169063 -0.0644624 0.468134 0.02515 -0.0644624 0.418693 -0.0192 -0.0644624 0.416031 -0.0247157 -0.0644624 0.472664 -0.00323879 -0.0644624 0.471648 -0.00360528 -0.0644624 0.474617 9.27057e-05 -0.0644624 0.468521 -0.0326891 -0.0644624 0.471035 0.0167656 -0.0644624 0.471253 0.01684 -0.0644624 0.471137 0.0246283 -0.0644624 0.468027 0.02555 -0.0644624 0.464927 0.0409 -0.0644624 0.472092 0.00348253 -0.0644624 0.473586 0.0226257 -0.0644624 0.429427 -0.0211106 -0.0644624 0.422828 -0.0332311 -0.0644624 0.427227 -0.0217 -0.0644624 0.463192 0.0499467 -0.0644624 0.460235 0.0479214 -0.0644624 0.471756 -0.0380483 -0.0644624 0.473304 -0.0231386 -0.0644624 0.473887 -0.021008 -0.0644624 0.473925 -0.0204426 -0.0644624 0.473806 -0.0193486 -0.0644624 0.464927 -0.0355 -0.0644624 0.468134 -0.02515 -0.0644624 0.473847 0.0215732 -0.0644624 0.472672 0.0238452 -0.0644624 0.473338 -0.0183552 -0.0644624 0.45943 0.051556 -0.0644624 0.457327 0.0485 -0.0644624 0.458618 0.0516 -0.0644624 0.442327 0.0485 -0.0644624 0.473701 -0.00245315 -0.0644624 0.471035 -0.00378436 -0.0644624 0.474471 0.00113671 -0.0644624 0.474427 0.00126765 -0.0644624 0.472464 0.0174531 -0.0644624 0.473206 0.0181754 -0.0644624 0.473397 0.0184449 -0.0644624 0.472394 -0.024059 -0.0644624 0.472637 -0.0238742 -0.0644624 0.434727 0.0409 -0.0644624 0.435305 0.0438084 -0.0644624 0.433371 0.0516 -0.0644624 0.458204 -0.041 -0.0644624 0.460327 -0.0401 -0.0644624 0.437566 -0.0397499 -0.0644624 0.438394 -0.0426132 -0.0644624 0.435077 -0.0372604 -0.0644624 0.468088 0.0322561 -0.0644624 0.468261 0.0325156 -0.0644624 0.468521 0.0326891 -0.0644624 0.473894 0.0022265 -0.0644624 0.472176 -0.0359322 -0.0644624 0.471355 -0.0340034 -0.0644624 0.470671 -0.0334064 -0.0644624 0.473805 0.0193424 -0.0644624 0.473871 0.0196169 -0.0644624 0.430017 0.0487579 -0.0644624 0.430631 0.0502126 -0.0644624 0.462701 0.046274 -0.0644624 0.466341 0.0473684 -0.0644624 0.464969 0.0486376 -0.0644624 0.417218 0.0195362 -0.0644624 0.428677 0.0435922 -0.0644624 0.422828 0.0332311 -0.0644624 0.424743 0.021365 -0.0644624 0.423316 0.0204112 -0.0644624 0.416031 0.0247156 -0.0644624 0.464348 0.0438084 -0.0644624 0.467886 0.0455938 -0.0644624 0.428911 0.021365 -0.0644624 0.430338 0.0204112 -0.0644624 0.431292 0.0189838 -0.0644624 0.434727 -0.0355 -0.0644624 0.431627 -0.0173 -0.0644624 0.431037 -0.0195 -0.0644624 0.471233 0.0395457 -0.0644624 0.468761 0.0327472 -0.0644624 0.470671 0.0334063 -0.0644624 0.47142 0.0340793 -0.0644624 0.47152 0.0342046 -0.0644624 0.471987 0.0350561 -0.0644624 0.431627 -0.0173 -0.054065 0.431627 0.0101 -0.062065 0.431627 0.0173 -0.0644624 0.433371 -0.0516 -0.062145 0.440575 -0.0516 -0.0619371 0.461337 -0.0516 -0.0608274 0.44658 -0.0516 -0.0609065 0.449718 -0.0516 -0.0599936 0.458618 -0.0516 -0.0644624 0.449734 0.0516 -0.0599487 0.439882 0.0516 -0.0619573 0.434327 0.0516 -0.0621073 0.463182 0.0516 -0.0566897 0.463182 0.0516 -0.0547538 0.454197 0.0516 -0.0583163 0.461323 0.0516 -0.0608539 0.460358 0.0516 -0.0624639 0.451962 0.0516 -0.0591722 0.459405 0.0516 -0.0636985 0.425077 -0.00216511 -0.07724 0.423827 -4.19898e-08 -0.07724 0.424162 0.00124996 -0.07724 0.426327 0.00249996 -0.07724 0.426327 -0.00250004 -0.067765 0.426327 -0.00250004 -0.07724 0.424162 -0.00125004 -0.067765 0.424162 -0.00125004 -0.07724 0.426327 0.00249996 -0.067765 0.425077 0.00216502 -0.07724 0.425077 -0.00216511 -0.067765 0.425077 0.00216502 -0.067765 0.423827 -4.19898e-08 -0.067765 0.424162 0.00124996 -0.067765 0.402077 -0.00216511 -0.07724 0.401162 -0.00125004 -0.07724 0.400707 -0.00151254 -0.077765 0.400827 -4.19898e-08 -0.07724 0.400302 -4.19898e-08 -0.077765 0.401162 -0.00125004 -0.067765 0.400827 -4.19898e-08 -0.067765 0.401162 0.00124996 -0.067765 0.401162 0.00124996 -0.07724 0.402077 0.00216502 -0.07724 0.403327 0.00249996 -0.07724 0.402077 -0.00216511 -0.067765 0.402077 0.00216502 -0.067765 0.403327 -4.19898e-08 -0.0662628 0.426097 -0.0176029 -0.062965 0.43393 -0.00977005 -0.085465 0.432197 -0.013171 -0.077765 0.432197 -0.013171 -0.085465 0.430804 -0.0147739 -0.085465 0.428183 -0.0167027 -0.085465 0.429508 -0.0158628 -0.0775328 0.428843 -0.0163143 -0.062965 0.423497 -0.0181438 -0.0774688 0.425349 -0.0178198 -0.085465 0.426097 -0.0176029 -0.085465 0.434527 -4.19898e-08 -0.085465 0.423687 0.0181238 -0.077465 0.425349 0.0178197 -0.085465 0.422327 0.0182 -0.0776566 0.426097 0.0176028 -0.085465 0.428843 0.0163142 -0.077465 0.432197 0.0131709 -0.085465 0.43393 0.00976996 -0.077765 0.434527 0.00599996 -0.077765 0.434093 0.00922509 -0.085465 0.429248 0.028409 -0.085765 0.435679 -0.0380692 -0.0852292 0.431109 -0.0399503 -0.084742 0.432389 -0.031 -0.085765 0.428327 -0.0332984 -0.0857434 0.434735 -0.0347021 -0.085679 0.430422 -0.0375444 -0.0853325 0.435825 -0.0398655 -0.0847681 0.435827 -0.0427615 -0.0836367 0.431818 -0.044605 -0.0826403 0.435827 -0.0450872 -0.0823414 0.435827 -0.0501856 -0.0780694 0.432017 -0.048583 -0.0796506 0.432143 -0.050784 -0.0774135 0.432387 -0.0539959 -0.0731253 0.435827 -0.0507839 -0.0774136 0.432484 -0.0551308 -0.0711921 0.435827 -0.054258 -0.0727035 0.435929 -0.058303 -0.0630385 0.433083 -0.0585134 -0.0621285 0.432827 -0.0576519 -0.0653305 0.435832 -0.0569255 -0.0673558 0.435969 0.0585143 -0.062124 0.435933 0.0583245 -0.0629504 0.432564 0.0559297 -0.0696326 0.432491 0.0552095 -0.0710466 0.433083 0.0585133 -0.0621285 0.435156 0.0585134 -0.0621279 0.432657 0.0566806 -0.0679588 0.435829 0.0566066 -0.068135 0.435827 0.055801 -0.0698973 0.432122 0.0504676 -0.0777649 0.435827 0.0485585 -0.0796728 0.431939 0.0468185 -0.0811286 0.435827 0.0470255 -0.0809684 0.435827 0.0450871 -0.0823414 0.435827 0.0432861 -0.0833761 0.431659 0.0430488 -0.0834962 0.435827 0.0430504 -0.0834954 0.435827 0.0400909 -0.0846978 0.430907 0.0391301 -0.0849777 0.435802 0.0392625 -0.0849422 0.435575 0.0374567 -0.0853484 0.435174 0.0358867 -0.0855748 0.43044 0.0375945 -0.0853232 0.434871 0.0350344 -0.0856549 0.434547 0.0342785 -0.0857044 0.405831 -0.00761995 -0.0618294 0.405345 -0.0143957 -0.0639213 0.409718 -0.0185229 -0.0618694 0.411767 -0.0216967 -0.0618949 0.413176 -0.0236256 -0.0619134 0.420402 -0.0326023 -0.0620087 0.4209 -0.0334652 -0.0629635 0.419681 -0.0316947 -0.0619997 0.426895 -0.0430205 -0.0646382 0.425168 -0.0395345 -0.0645148 0.427945 -0.0462825 -0.062061 0.428028 -0.046634 -0.064781 0.428532 -0.0490396 -0.0620543 0.428765 -0.0535917 -0.0647592 0.404589 -0.0200653 -0.0719465 0.4023 -0.0178073 -0.073765 0.404909 -0.0205113 -0.073765 0.407691 -0.0228775 -0.0719783 0.401906 -0.0171263 -0.0719106 0.399473 -0.0138678 -0.073765 0.396978 -0.00365946 -0.0717798 0.397347 -0.00725152 -0.0718072 0.398243 -0.0107196 -0.071838 0.397981 -0.0106173 -0.073765 0.403036 -0.00369157 -0.0637905 0.40333 -0.00735084 -0.0638187 0.400387 -0.00734114 -0.0666032 0.404071 -0.010936 -0.0638621 0.401217 -0.0109032 -0.0666543 0.407135 -0.0177028 -0.0639917 0.409363 -0.0208721 -0.0640663 0.411928 -0.0239442 -0.0641398 0.41929 -0.0321937 -0.0672073 0.413854 -0.0266834 -0.0656024 0.41303 -0.0263965 -0.0670571 0.4284 -0.0491993 -0.0678818 0.428594 -0.0503001 -0.0649176 0.426544 -0.0419337 -0.0675486 0.415202 -0.0262106 -0.0619405 0.414706 -0.0269664 -0.0642097 0.415576 -0.0272348 -0.0628539 0.409954 -0.0235224 -0.0669776 0.420358 -0.0330496 -0.0643438 0.419821 -0.03262 -0.0657513 0.422942 -0.0362169 -0.0644194 0.426088 -0.0407862 -0.0705877 0.428183 -0.04787 -0.0708319 0.42791 -0.046334 -0.073765 0.425521 -0.0396707 -0.073765 0.425871 -0.0403068 -0.073765 0.400449 -0.0141407 -0.0700173 0.402574 -0.0172834 -0.0700805 0.406093 -0.0204237 -0.0684529 0.405222 -0.0202485 -0.0701443 0.409052 -0.0233025 -0.0685303 0.412256 -0.0261158 -0.068602 0.415568 -0.029183 -0.073765 0.419857 -0.0328347 -0.073765 0.411061 -0.0256163 -0.0720053 0.411578 -0.025852 -0.0702574 0.408272 -0.0230851 -0.0702038 0.399765 -0.0140173 -0.0718732 0.398935 -0.010801 -0.0699611 0.398048 -0.00729236 -0.069916 0.397689 -0.00367331 -0.0698807 0.398755 -0.00368345 -0.0681423 0.400057 -0.00368974 -0.0665697 0.399101 -0.0073221 -0.0681775 0.399965 -0.0108617 -0.0682279 0.402641 -0.0143124 -0.0667239 0.401444 -0.0142386 -0.0682946 0.404635 -0.0175345 -0.0668064 0.403517 -0.0174196 -0.0683723 0.407111 -0.0205878 -0.0668931 0.418301 -0.0314177 -0.0703535 0.422157 -0.0352477 -0.0672927 0.421373 -0.0343499 -0.0704087 0.424629 -0.0384871 -0.067403 0.424022 -0.0374638 -0.0704838 0.427791 -0.0455357 -0.0677188 0.427466 -0.0442802 -0.070712 0.397275 -0.00790526 -0.0747422 0.396727 -0.00357897 -0.073765 0.397241 -0.00794642 -0.073765 0.400815 -0.0159421 -0.073765 0.400075 -0.0148596 -0.073765 0.400116 -0.0148137 -0.0751985 0.3984 -0.0115454 -0.0750699 0.398588 -0.0121322 -0.073765 0.404041 -0.0196689 -0.073765 0.40907 -0.0240941 -0.073765 0.423341 -0.0365164 -0.073765 0.424758 -0.0384382 -0.073765 0.426529 -0.0416733 -0.073765 0.424775 -0.0384129 -0.0747846 0.42741 -0.0441371 -0.073765 0.427021 -0.0429189 -0.073765 0.426552 -0.0416428 -0.0748925 0.427727 -0.045251 -0.0752031 0.428063 -0.0464022 -0.0770204 0.428136 -0.0478014 -0.0753279 0.427764 -0.041718 -0.0809193 0.427944 -0.0432936 -0.0798656 0.42094 -0.0320443 -0.0807999 0.42381 -0.0334563 -0.083336 0.425819 -0.0376712 -0.0805695 0.418097 -0.0294847 -0.0810511 0.404815 -0.0186962 -0.0807555 0.405542 -0.0186942 -0.0821049 0.406371 -0.0194688 -0.0821753 0.410989 -0.0226474 -0.0835046 0.412114 -0.0245525 -0.0816538 0.404666 -0.0186967 -0.0804453 0.402522 -0.0176204 -0.0771038 0.402462 -0.0176647 -0.0766489 0.403489 -0.0187009 -0.0770995 0.405042 -0.0203895 -0.0764863 0.403661 -0.0187012 -0.077765 0.403667 -0.0187012 -0.0777846 0.400267 -0.0146976 -0.0766818 0.398575 -0.0114144 -0.0765453 0.398146 -0.00969993 -0.0771614 0.397474 -0.00775945 -0.0762096 0.397659 -0.00737422 -0.0771869 0.39695 -0.00374132 -0.0756793 0.397345 -0.00347182 -0.0770805 0.427491 -0.0409673 -0.0807129 0.411332 -0.0250865 -0.0788487 0.422859 -0.0352277 -0.0777917 0.423555 -0.0347473 -0.0806255 0.42675 -0.0392592 -0.080609 0.396672 -4.19898e-08 -0.073765 0.396754 -0.00388557 -0.0742111 0.4109 -0.0254008 -0.075926 0.405542 -0.0200331 -0.0793864 0.416992 -0.030265 -0.0752869 0.417363 -0.0299887 -0.07823 0.419875 -0.0327994 -0.0750221 0.420227 -0.0325354 -0.0779719 0.422509 -0.0354905 -0.0748414 0.425146 -0.038137 -0.0777279 0.426926 -0.0413648 -0.0778347 0.42799 -0.0450431 -0.0781829 0.427558 -0.0431413 -0.0779752 0.427485 -0.0321223 -0.0857627 0.422327 -0.0185 -0.085765 0.428327 -0.0277393 -0.085765 0.426548 -0.031 -0.085765 0.422243 -0.0268691 -0.085765 0.42674 -0.0256019 -0.085765 0.426178 -0.023 -0.085765 0.417828 -0.0233574 -0.085765 0.42674 -0.0203982 -0.085765 0.413854 0.0266833 -0.0656024 0.41303 0.0263964 -0.0670571 0.397148 -4.19898e-08 -0.0710186 0.428888 0.0521634 -0.0620449 0.428102 0.0468984 -0.0620598 0.428524 0.0489855 -0.0620544 0.426955 0.0432833 -0.0620636 0.406989 0.0126062 -0.0618395 0.408115 0.0154578 -0.0618511 0.406488 0.0109231 -0.0618348 0.406012 0.00875237 -0.0618308 0.40564 0.00592424 -0.061828 0.40333 0.00735075 -0.0638187 0.405526 0.00423404 -0.0618273 0.405458 0.0008468 -0.0618269 0.408272 0.023085 -0.0702038 0.411061 0.0256162 -0.0720053 0.404041 0.0196689 -0.073765 0.404589 0.0200652 -0.0719465 0.4023 0.0178072 -0.073765 0.401906 0.0171262 -0.0719106 0.400075 0.0148595 -0.073765 0.399473 0.0138678 -0.073765 0.396978 0.00365938 -0.0717798 0.397981 0.0106172 -0.073765 0.398588 0.0121321 -0.073765 0.396727 0.00357888 -0.073765 0.397347 0.00725144 -0.0718072 0.398243 0.0107195 -0.071838 0.398935 0.0108009 -0.0699611 0.399765 0.0140172 -0.0718732 0.400449 0.0141406 -0.0700173 0.409363 0.020872 -0.0640663 0.407111 0.0205877 -0.0668931 0.407135 0.0177027 -0.0639917 0.405345 0.0143957 -0.0639213 0.402641 0.0143123 -0.0667239 0.404071 0.0109359 -0.0638621 0.401217 0.0109031 -0.0666543 0.403036 0.00369149 -0.0637905 0.401269 -4.19898e-08 -0.0652987 0.411928 0.0239441 -0.0641398 0.414706 0.0269663 -0.0642097 0.415576 0.0272347 -0.0628539 0.4209 0.0334652 -0.0629635 0.420358 0.0330495 -0.0643438 0.419821 0.0326199 -0.0657513 0.4234 0.0366795 -0.0620417 0.427466 0.0442802 -0.070712 0.426529 0.0416733 -0.073765 0.428224 0.0489001 -0.073765 0.428183 0.0478699 -0.0708319 0.42741 0.044137 -0.073765 0.407691 0.0228774 -0.0719783 0.40907 0.024094 -0.073765 0.415568 0.0291829 -0.073765 0.421373 0.0343498 -0.0704087 0.423341 0.0365164 -0.073765 0.426088 0.0407861 -0.0705877 0.425871 0.0403067 -0.073765 0.400057 0.00368966 -0.0665697 0.398755 0.00368336 -0.0681423 0.400387 0.00734105 -0.0666032 0.399965 0.0108616 -0.0682279 0.403517 0.0174195 -0.0683723 0.406093 0.0204237 -0.0684529 0.404635 0.0175344 -0.0668064 0.409954 0.0235223 -0.0669776 0.422942 0.0362168 -0.0644194 0.424629 0.038487 -0.067403 0.425168 0.0395345 -0.0645148 0.426895 0.0430204 -0.0646382 0.427791 0.0455356 -0.0677188 0.428028 0.0466339 -0.064781 0.428556 0.0522785 -0.0679192 0.428594 0.0503 -0.0649176 0.428754 0.0535409 -0.0648991 0.398604 -4.19898e-08 -0.0682722 0.397689 0.00367323 -0.0698807 0.398048 0.00729228 -0.069916 0.399101 0.00732201 -0.0681775 0.401444 0.0142385 -0.0682946 0.402574 0.0172833 -0.0700805 0.405222 0.0202484 -0.0701443 0.409052 0.0233024 -0.0685303 0.411578 0.0258519 -0.0702574 0.412256 0.0261157 -0.068602 0.418301 0.0314176 -0.0703535 0.41929 0.0321936 -0.0672073 0.424022 0.0374638 -0.0704838 0.422157 0.0352476 -0.0672927 0.426544 0.0419336 -0.0675486 0.4284 0.0491992 -0.0678818 0.427491 0.040967 -0.0807144 0.406437 0.0186924 -0.0835083 0.412114 0.0245521 -0.0816553 0.415648 0.0262135 -0.0835219 0.420941 0.0320439 -0.0808014 0.426242 0.0369592 -0.082881 0.426751 0.0392589 -0.0806106 0.426966 0.0385387 -0.0824496 0.428014 0.0449715 -0.0784558 0.427949 0.0433768 -0.0798022 0.42791 0.046334 -0.073765 0.427021 0.0429188 -0.073765 0.419857 0.0328347 -0.073765 0.422509 0.0354902 -0.0748464 0.424758 0.0384381 -0.073765 0.425521 0.0396706 -0.073765 0.404909 0.0205112 -0.073765 0.398401 0.011545 -0.0750757 0.400117 0.0148133 -0.0752043 0.396755 0.00388522 -0.0742169 0.397241 0.00794633 -0.073765 0.397276 0.00790481 -0.074748 0.397154 -4.19898e-08 -0.0765011 0.397346 0.00347087 -0.0770843 0.397474 0.00775872 -0.0762144 0.397687 0.00755729 -0.0771839 0.398262 0.0101028 -0.0771573 0.398576 0.0114138 -0.0765502 0.403661 0.0187012 -0.077765 0.405043 0.0203891 -0.0764912 0.403489 0.0187008 -0.0770995 0.402463 0.0176642 -0.0766538 0.400425 0.0147975 -0.0771187 0.427775 0.0417865 -0.0808783 0.426927 0.0413643 -0.0778379 0.425819 0.0376709 -0.080571 0.420227 0.0325349 -0.0779751 0.423556 0.0347469 -0.080627 0.417364 0.0299882 -0.0782332 0.418098 0.0294843 -0.0810526 0.406372 0.0194684 -0.0821768 0.396754 3.81129e-08 -0.0749115 0.396951 0.00374052 -0.0756841 0.400268 0.014697 -0.0766867 0.400815 0.015942 -0.073765 0.405542 0.0200325 -0.0793896 0.411333 0.0250859 -0.0788519 0.410901 0.0254004 -0.0759309 0.416992 0.0302647 -0.0752919 0.422859 0.0352272 -0.0777949 0.419875 0.0327991 -0.0750272 0.425146 0.0381364 -0.0777311 0.424775 0.0384126 -0.0747896 0.426552 0.0416425 -0.0748975 0.427559 0.0431408 -0.0779784 0.427728 0.0452507 -0.0752082 0.427991 0.0450427 -0.0781862 0.428327 0.0332983 -0.0857434 0.427485 0.0321222 -0.0857627 0.428327 0.0321551 -0.0857621 0.418849 0.0241406 -0.085765 0.42674 0.0203981 -0.085765 0.428327 0.0277392 -0.085765 0.42371 0.028157 -0.085765 0.428327 0.031 -0.085765 0.431086 0.0557086 -0.0694374 0.429689 0.0566673 -0.0620799 0.430231 0.0573291 -0.0620933 0.429575 0.0530876 -0.0723939 0.432212 0.0517034 -0.0763279 0.43235 0.0535071 -0.0738773 0.430785 0.0515495 -0.0760982 0.430924 0.0537979 -0.0729182 0.43239 0.0540312 -0.0730691 0.431313 0.0572265 -0.0657147 0.429308 0.0559482 -0.0620662 0.429069 0.0551374 -0.0648249 0.429956 0.0564088 -0.0653295 0.432847 0.057742 -0.065047 0.432787 0.0574593 -0.0659083 0.429727 0.0549289 -0.0689807 0.42884 0.0537154 -0.0683439 0.428683 0.0519753 -0.0716414 0.428389 0.050717 -0.0709006 0.432564 -0.0559298 -0.0696326 0.432149 -0.0584032 -0.0621209 0.430924 -0.053798 -0.0729182 0.432341 -0.0533964 -0.0740421 0.430785 -0.0515496 -0.0760982 0.429463 -0.0509484 -0.0755143 0.428683 -0.0519754 -0.0716414 0.428224 -0.0489002 -0.073765 0.428992 -0.0544391 -0.062039 0.429069 -0.0551375 -0.0648249 0.429229 -0.0557395 -0.0620623 0.429333 -0.056008 -0.0620673 0.429898 -0.0569566 -0.0620856 0.43007 -0.0571606 -0.0620898 0.432408 -0.054258 -0.0727035 0.432693 -0.0569256 -0.0673556 0.432634 -0.0565123 -0.0683556 0.431313 -0.0572265 -0.0657147 0.431086 -0.0557087 -0.0694374 0.429727 -0.054929 -0.0689807 0.429956 -0.0564089 -0.0653295 0.428571 -0.0523939 -0.0676721 0.428389 -0.0507111 -0.070911 0.42884 -0.0537155 -0.0683439 0.429575 -0.0530876 -0.0723939 0.428144 0.0479236 -0.0751643 0.42943 0.0497894 -0.0769588 0.428562 0.0499868 -0.0746696 0.429463 0.0509483 -0.0755143 0.430727 0.0503299 -0.0775426 0.432166 0.0510963 -0.0770556 0.432212 -0.0517035 -0.0763279 0.432112 -0.0503145 -0.0779313 0.428519 -0.0487865 -0.076268 0.428562 -0.0499869 -0.0746696 0.432023 0.0487255 -0.0795195 0.428523 0.0489198 -0.0761011 0.430627 0.0467258 -0.0809201 0.431827 0.0447218 -0.0825693 0.430557 0.0446957 -0.0823413 0.431574 0.0424284 -0.0837929 0.431127 0.0400275 -0.0847179 0.429352 0.0380099 -0.0850648 0.429488 0.0353301 -0.0856302 0.430671 0.0486066 -0.0793084 0.429359 0.044435 -0.0817396 0.43035 0.0425311 -0.0835288 0.428854 0.0403808 -0.0838039 0.429961 0.0402706 -0.0844459 0.428477 0.0358935 -0.0854057 0.428316 0.0383354 -0.084443 0.427392 0.0339705 -0.0855547 0.429407 0.0481424 -0.0787294 0.429394 0.0463432 -0.0803386 0.42848 0.0457155 -0.0794581 0.429191 0.0424502 -0.0828901 0.428294 0.0421837 -0.0819514 0.427513 0.0363977 -0.0848205 0.426738 0.0367663 -0.0839327 0.428068 0.0465182 -0.0768919 0.428495 0.0473917 -0.0778622 0.428449 0.0439645 -0.0808368 0.427981 0.0403308 -0.0828627 0.427451 0.0401393 -0.0817788 0.427488 0.0385167 -0.0835225 0.425309 0.0354132 -0.0831387 0.430668 -0.0484656 -0.07944 0.429406 -0.0480074 -0.0788612 0.430721 -0.0501785 -0.07771 0.429427 -0.0496452 -0.0771267 0.430624 -0.0465984 -0.0810186 0.431945 -0.0469425 -0.0810331 0.428493 -0.047266 -0.0779932 0.428011 -0.0448678 -0.0785505 0.431934 -0.0466886 -0.0812275 0.429393 -0.046222 -0.0804365 0.428479 -0.0456029 -0.079555 0.431559 -0.0423288 -0.0838384 0.431621 -0.0427603 -0.0836373 0.43055 -0.0445846 -0.0824103 0.429354 -0.0443324 -0.0818067 0.428284 -0.0421068 -0.0819937 0.428445 -0.0438719 -0.0809021 0.430337 -0.0424373 -0.0835732 0.42884 -0.040315 -0.0838286 0.42918 -0.0423643 -0.0829335 0.430751 -0.0385703 -0.0851177 0.429336 -0.0379636 -0.0850745 0.428302 -0.0382938 -0.0844533 0.429945 -0.0401983 -0.0844701 0.427475 -0.0384798 -0.0835331 0.427968 -0.0402721 -0.0828878 0.426954 -0.0385061 -0.0824604 0.427438 -0.0400873 -0.0818041 0.428467 -0.0358721 -0.0854081 0.427504 -0.0363779 -0.0848235 0.426233 -0.0369425 -0.0828847 0.429477 -0.0353074 -0.0856322 0.426729 -0.0367481 -0.0839362 0.426548 0.031 -0.085765 0.425777 0.0351019 -0.0841613 0.424907 0.0324717 -0.0851029 0.426499 0.0346021 -0.0850102 0.427392 -0.0339706 -0.0855547 0.426499 -0.0346022 -0.0850102 0.42425 -0.0330615 -0.0843083 0.425777 -0.035102 -0.0841613 0.425309 -0.0354133 -0.0831387 0.408639 0.0207133 -0.0835032 0.407369 0.0186592 -0.0844896 0.407475 0.0186553 -0.0845692 0.408396 0.0186216 -0.0851059 0.409135 0.018594 -0.0853936 0.417185 0.0242003 -0.0856218 0.422362 0.0269705 -0.085765 0.421671 0.0277816 -0.0856206 0.425709 0.031752 -0.0856031 0.409038 0.0202503 -0.0844204 0.410989 0.0226474 -0.0835046 0.416019 0.0257266 -0.0844322 0.420025 0.0297119 -0.0835049 0.422429 0.0310958 -0.0843849 0.42201 0.0315342 -0.0834474 0.42381 0.0334562 -0.083336 0.42425 0.0330614 -0.0843083 0.411369 0.0221684 -0.0844213 0.41655 0.0250314 -0.0851655 0.420421 0.0292468 -0.0844214 0.423038 0.0304585 -0.0851437 0.410295 0.0187911 -0.0856205 0.40961 0.0195864 -0.0851601 0.411913 0.0214817 -0.0851605 0.412565 0.0206593 -0.0856206 0.42099 0.0285801 -0.0851606 0.423772 0.0296907 -0.0856167 0.411013 -0.0185226 -0.0857455 0.424518 -0.0289106 -0.085765 0.417185 -0.0242004 -0.0856218 0.412565 -0.0206594 -0.0856206 0.414782 -0.0210371 -0.085765 0.408183 -0.0186295 -0.085002 0.410018 -0.0185606 -0.0856185 0.410295 -0.0187912 -0.0856205 0.411913 -0.0214818 -0.0851605 0.42099 -0.0285801 -0.0851606 0.421671 -0.0277816 -0.0856206 0.423772 -0.0296908 -0.0856167 0.425709 -0.0317521 -0.0856031 0.40961 -0.0195865 -0.0851601 0.41655 -0.0250315 -0.0851655 0.411369 -0.0221685 -0.0844213 0.420421 -0.0292469 -0.0844214 0.423038 -0.0304586 -0.0851437 0.422429 -0.0310959 -0.0843849 0.424907 -0.0324718 -0.0851029 0.409038 -0.0202504 -0.0844204 0.408639 -0.0207133 -0.0835032 0.416019 -0.0257267 -0.0844322 0.415648 -0.0262136 -0.0835219 0.420025 -0.029712 -0.0835049 0.42201 -0.0315343 -0.0834474 0.436127 0.0555318 -0.069765 0.436127 0.05435 -0.071965 0.436127 0.04 -0.0815559 0.436127 0.0420067 -0.0806606 0.436127 0.043149 -0.0831092 0.436127 0.0449259 -0.0820883 0.436127 0.0445636 -0.0790687 0.436127 0.0482526 -0.075742 0.436127 0.051558 -0.0760303 0.436268 -0.0554382 -0.0620748 0.436148 -0.0571717 -0.0658275 0.436143 -0.0570421 -0.0661967 0.436127 -0.052492 -0.069765 0.436146 0.0571184 -0.0659808 0.436268 0.0554381 -0.0620748 0.464419 -0.0308365 -0.0789127 0.477978 -0.0333485 -0.0521445 0.477702 -0.0349801 -0.0521483 0.464689 -0.0531544 -0.0542786 0.464155 -0.0527781 -0.057805 0.454485 -0.048534 -0.0738752 0.45792 -0.0548274 -0.0580621 0.460136 -0.054524 -0.056476 0.460667 -0.0544664 -0.0557171 0.462196 -0.0537529 -0.0572631 0.476003 -0.0409685 -0.0521995 0.475223 -0.0427777 -0.052241 0.473858 -0.0432511 -0.0563737 0.474837 -0.0435554 -0.0522663 0.474007 -0.0450365 -0.0523321 0.477196 -0.0362746 -0.0531284 0.463932 -0.0356274 -0.0786522 0.466774 -0.0320114 -0.0767974 0.455943 -0.0342172 -0.0816498 0.454423 -0.0363072 -0.0814794 0.455912 -0.0384743 -0.0809285 0.45383 -0.0396485 -0.0806191 0.454325 -0.043985 -0.0782486 0.472101 -0.039495 -0.0656898 0.466811 -0.0427009 -0.0723457 0.470257 -0.0455301 -0.0627872 0.471553 -0.0334187 -0.0699339 0.473324 -0.0373254 -0.0644455 0.472187 -0.0348437 -0.0682558 0.470968 -0.0369592 -0.0696427 0.46902 -0.037485 -0.0725905 0.466201 -0.0411795 -0.0742327 0.476368 -0.0346105 -0.0574407 0.475396 -0.0370676 -0.0588732 0.474289 -0.0393881 -0.0601375 0.469653 -0.0389772 -0.0707998 0.466585 -0.0522302 -0.0537052 0.466014 -0.0516165 -0.0581095 0.4654 -0.0503644 -0.0634035 0.463637 -0.0516593 -0.0630972 0.463074 -0.0498852 -0.0680129 0.4614 -0.0511256 -0.0674037 0.459799 -0.0530599 -0.064133 0.457912 -0.0538796 -0.0629767 0.457869 -0.0531271 -0.0653144 0.455907 -0.0544868 -0.0615597 0.463823 -0.045962 -0.0727406 0.467856 -0.0452914 -0.06806 0.468715 -0.0472936 -0.0632379 0.472105 -0.047696 -0.0525461 0.472496 -0.0452528 -0.0571186 0.454153 -0.0545542 -0.0615038 0.457911 -0.0544436 -0.0605668 0.459895 -0.0537177 -0.061681 0.461613 -0.052048 -0.065012 0.460002 -0.0541941 -0.0591309 0.461993 -0.0533407 -0.0599399 0.462374 -0.0540028 -0.0550763 0.461802 -0.0527824 -0.0625238 0.455834 -0.054934 -0.0591856 0.467778 -0.0502776 -0.0581832 0.469449 -0.0487681 -0.0580353 0.461133 -0.0500218 -0.0696927 0.459675 -0.0522105 -0.0664988 0.457748 -0.0521977 -0.0675718 0.455925 -0.0538596 -0.0638691 0.455867 -0.0530611 -0.0661006 0.47079 -0.0491154 -0.0527489 0.471024 -0.0470923 -0.0576765 0.467094 -0.048907 -0.0634474 0.466304 -0.0469647 -0.0683332 0.464708 -0.0484974 -0.068321 0.46273 -0.0487318 -0.0703046 0.460785 -0.0487517 -0.0718636 0.459204 -0.0499869 -0.0709447 0.459486 -0.05118 -0.0687756 0.457528 -0.0511098 -0.0697298 0.455712 -0.0521067 -0.0682379 0.453936 -0.0525927 -0.067326 0.461894 -0.0309367 -0.0803989 0.458741 -0.0309672 -0.0814395 0.457515 -0.0321079 -0.0816166 0.457353 -0.0365805 -0.0812078 0.453826 -0.0374547 -0.0812684 0.462578 -0.0308845 -0.0800591 0.460374 -0.0327778 -0.0809316 0.461491 -0.0351859 -0.0801984 0.458854 -0.0346658 -0.0812026 0.45575 -0.0422273 -0.0793254 0.454507 -0.0403673 -0.0803238 0.453831 -0.0421677 -0.0794324 0.463314 -0.0393716 -0.0778941 0.456776 -0.0439779 -0.0780662 0.455305 -0.0455916 -0.0769153 0.453825 -0.0476854 -0.0748779 0.455037 -0.0498217 -0.0721451 0.456095 -0.0471106 -0.0753797 0.456716 -0.0485469 -0.073656 0.457611 -0.0456318 -0.0765742 0.458282 -0.047193 -0.0748711 0.45905 -0.0441195 -0.0774319 0.459761 -0.0457835 -0.0757615 0.46045 -0.0425859 -0.0779363 0.461189 -0.0443278 -0.0763082 0.461864 -0.0410141 -0.0780822 0.462619 -0.0428089 -0.0765041 0.46477 -0.0376562 -0.0774033 0.467589 -0.0340202 -0.0755968 0.468334 -0.0358394 -0.0741918 0.470874 -0.0318488 -0.0714414 0.457153 -0.040473 -0.0800489 0.45819 -0.0423499 -0.0788717 0.458553 -0.0387312 -0.0804211 0.460001 -0.0369704 -0.0804615 0.459578 -0.0407228 -0.0793195 0.460997 -0.0390743 -0.0794123 0.462461 -0.0373741 -0.079179 0.462985 -0.0333938 -0.0796557 0.475396 -0.0326458 -0.0613832 0.474426 -0.0350431 -0.0630049 0.473266 -0.030629 -0.0671097 0.473293 -0.0326317 -0.0666577 0.465523 -0.039502 -0.0759235 0.464739 -0.0428732 -0.0746283 0.464071 -0.0412016 -0.0763675 0.457188 -0.0498859 -0.0717659 0.453874 -0.0512011 -0.07002 0.475101 -0.0410879 -0.0554536 0.473056 -0.0415734 -0.0612213 0.471707 -0.0436218 -0.0621098 0.46935 -0.0434839 -0.0675163 0.470771 -0.0415494 -0.0667198 0.468261 -0.0408936 -0.0717074 0.465326 -0.0443919 -0.0726957 0.463268 -0.0444588 -0.0747157 0.462314 -0.0474118 -0.0724658 0.461806 -0.0459392 -0.0744758 0.460334 -0.0473328 -0.0738952 0.458809 -0.0486513 -0.0729845 0.455441 -0.051019 -0.0702601 0.453915 -0.0522357 -0.0680823 0.454325 0.0439846 -0.0782489 0.465524 0.0395012 -0.0759235 0.466812 0.0427001 -0.0723458 0.453827 0.0461039 -0.0764949 0.467754 0.0515332 -0.0533935 0.467779 0.050277 -0.0581836 0.476698 0.0389959 -0.0521725 0.47747 0.0361052 -0.0521524 0.477988 0.0332801 -0.0521444 0.460136 0.0545238 -0.0564765 0.462196 0.0537526 -0.0572635 0.464155 0.0527777 -0.0578054 0.454319 0.0551031 -0.0582574 0.455441 0.0510188 -0.0702604 0.455712 0.0521065 -0.0682382 0.454026 0.0537091 -0.0645127 0.455925 0.0538594 -0.0638695 0.453829 0.042534 -0.079218 0.453829 0.0436756 -0.0784742 0.455305 0.0455912 -0.0769156 0.455943 0.0342163 -0.0816499 0.464995 0.0308224 -0.07848 0.466284 0.0307917 -0.0773735 0.468534 0.0307422 -0.0749324 0.473636 0.0306183 -0.0663004 0.476368 0.034609 -0.0574402 0.473859 0.0432501 -0.0563737 0.472497 0.0452519 -0.0571186 0.474848 0.0435353 -0.0522656 0.470698 0.0492045 -0.0527649 0.46945 0.0487675 -0.0580355 0.471024 0.0470916 -0.0576766 0.474289 0.0393869 -0.0601373 0.470257 0.0455293 -0.0627873 0.477196 0.0362731 -0.0531279 0.475102 0.0410867 -0.0554534 0.475396 0.0326443 -0.0613825 0.474431 0.0305933 -0.0644373 0.473324 0.0373242 -0.0644451 0.470969 0.0369581 -0.0696424 0.472187 0.0348425 -0.0682554 0.470237 0.0403282 -0.068836 0.470771 0.0415484 -0.0667197 0.466952 0.0377121 -0.0751924 0.454485 0.0485337 -0.0738754 0.453871 0.0511434 -0.0701182 0.455037 0.0498214 -0.0721454 0.464071 0.0412008 -0.0763677 0.464739 0.0428725 -0.0746284 0.453827 0.0349498 -0.0816482 0.454423 0.0363064 -0.0814795 0.455912 0.0384736 -0.0809287 0.454506 0.0403667 -0.080324 0.453829 0.0415337 -0.0797792 0.460334 0.0473323 -0.0738955 0.461806 0.0459387 -0.0744761 0.46045 0.0425853 -0.0779366 0.46119 0.0443272 -0.0763085 0.461864 0.0410134 -0.0780824 0.461492 0.035185 -0.0801984 0.456953 0.0309925 -0.0816882 0.455627 0.0309964 -0.081752 0.457515 0.032107 -0.0816166 0.45575 0.0422268 -0.0793257 0.456776 0.0439775 -0.0780665 0.453827 0.0477103 -0.07485 0.461993 0.0533404 -0.0599403 0.460002 0.0541939 -0.0591314 0.458877 0.0548237 -0.056422 0.461117 0.030921 -0.0807338 0.460375 0.0327769 -0.0809316 0.458553 0.0387305 -0.0804212 0.459578 0.0407222 -0.0793197 0.459051 0.0441189 -0.0774322 0.458282 0.0471926 -0.0748715 0.456716 0.0485466 -0.0736563 0.458809 0.0486509 -0.0729849 0.457188 0.0498855 -0.0717663 0.457748 0.0521974 -0.0675722 0.457869 0.0531268 -0.0653147 0.459675 0.0522102 -0.0664992 0.455907 0.0544866 -0.06156 0.457912 0.0538794 -0.062977 0.455867 0.0530608 -0.0661009 0.457528 0.0511095 -0.0697301 0.456095 0.0471103 -0.07538 0.457611 0.0456313 -0.0765745 0.45819 0.0423494 -0.078872 0.457153 0.0404724 -0.0800491 0.458854 0.034665 -0.0812027 0.457353 0.0365797 -0.0812079 0.461133 0.0500214 -0.0696931 0.4614 0.0511252 -0.0674041 0.461803 0.0527821 -0.0625242 0.463075 0.0498847 -0.0680133 0.463637 0.0516589 -0.0630976 0.464708 0.0484969 -0.0683214 0.463269 0.0444582 -0.074716 0.46477 0.0376553 -0.0774033 0.466774 0.0320104 -0.0767972 0.455834 0.0549339 -0.059186 0.457061 0.0550534 -0.0571544 0.45792 0.0548272 -0.0580625 0.465326 0.0443912 -0.0726959 0.462314 0.0474113 -0.0724662 0.463823 0.0459614 -0.0727409 0.46262 0.0428083 -0.0765043 0.463315 0.0393708 -0.0778942 0.462461 0.0373733 -0.079179 0.463932 0.0356265 -0.0786522 0.462985 0.0333929 -0.0796556 0.462982 0.0308738 -0.0798372 0.467094 0.0489064 -0.0634477 0.467856 0.0452907 -0.0680602 0.468716 0.047293 -0.0632381 0.469351 0.043483 -0.0675164 0.467361 0.0440703 -0.0702809 0.469654 0.0389762 -0.0707996 0.470875 0.0318475 -0.0714409 0.461894 0.0309357 -0.0803988 0.460997 0.0390736 -0.0794125 0.460002 0.0369696 -0.0804616 0.459761 0.045783 -0.0757618 0.460785 0.0487512 -0.0718639 0.459204 0.0499865 -0.0709451 0.459486 0.0511796 -0.068776 0.459799 0.0530596 -0.0641334 0.459895 0.0537174 -0.0616814 0.457911 0.0544434 -0.0605672 0.455234 0.0551286 -0.0578925 0.465783 0.0526497 -0.053938 0.466014 0.0516161 -0.0581098 0.465401 0.0503639 -0.0634039 0.466304 0.0469641 -0.0683334 0.468261 0.0408927 -0.0717074 0.467589 0.0340191 -0.0755965 0.468334 0.0358384 -0.0741916 0.469648 0.0338837 -0.0729366 0.471976 0.0306641 -0.0696765 0.473293 0.0326304 -0.0666571 0.472778 0.0361403 -0.0664205 0.472101 0.0394939 -0.0656896 0.473056 0.0415724 -0.0612212 0.471708 0.0436209 -0.0621098 0.437127 0.0449858 -0.0774763 0.453838 0.0494957 -0.072637 0.437127 0.0493231 -0.0728714 0.437127 0.0516138 -0.0692865 0.437176 0.0537937 -0.0642596 0.43821 0.054419 -0.062082 0.453892 0.0517448 -0.0690429 0.453934 0.0525821 -0.0673502 0.442017 0.0544949 -0.0617658 0.454035 0.0537936 -0.0642599 0.454154 0.0545647 -0.0614601 0.45218 0.0549954 -0.0590887 0.437127 0.042534 -0.079218 0.437127 0.0396497 -0.0806193 0.453829 0.0394065 -0.080708 0.437114 0.0390695 -0.0808239 0.453828 0.0372477 -0.0813143 0.453827 0.0354299 -0.0816009 0.448199 0.0334984 -0.0817352 0.436437 0.0354255 -0.0816014 0.446635 0.0329892 -0.0817499 0.435405 0.0330471 -0.0817486 0.436365 0.0352145 -0.0816234 0.451906 -0.0333909 -0.0817389 0.445224 -0.0321369 -0.0817622 0.449827 -0.0336694 -0.0817287 0.436365 -0.0352142 -0.0816234 0.453825 -0.0351292 -0.0816317 0.437073 -0.0384575 -0.0810136 0.453829 -0.0384609 -0.0810115 0.437127 -0.0396497 -0.0806193 0.453831 -0.0416942 -0.079694 0.437127 -0.042168 -0.079433 0.45383 -0.0436884 -0.0784649 0.453828 -0.0459227 -0.0766627 0.437127 -0.0459227 -0.0766627 0.437127 -0.0493422 -0.0728458 0.453838 -0.0494663 -0.0726771 0.453859 -0.0505959 -0.0710172 0.443745 -0.0545561 -0.0614991 0.454319 -0.0551032 -0.0582574 0.453442 -0.0550607 -0.0586049 0.449896 -0.0548695 -0.0599008 0.437145 -0.0532991 -0.0656454 0.454029 -0.0537153 -0.0644944 0.437203 -0.0540641 -0.0633941 0.45407 -0.0540638 -0.0633943 0.401215 0.00517391 -0.077765 0.403327 0.00302496 -0.077765 0.401814 0.00261968 -0.077765 0.423707 0.00151246 -0.077765 0.421131 0.00194996 -0.077765 0.423302 -4.19898e-08 -0.077765 0.430727 0.0134397 -0.077765 0.432197 0.0131709 -0.077765 0.430262 0.0152353 -0.077765 0.430227 0.0152963 -0.077765 0.400707 0.00151246 -0.077765 0.398175 4.35047e-07 -0.077765 0.398154 -0.00197926 -0.077765 0.398435 -0.00736228 -0.077765 0.399329 -0.00826818 -0.077765 0.399192 -0.0104578 -0.077765 0.411727 0.00379996 -0.077765 0.403027 0.00469996 -0.077765 0.399867 0.00647434 -0.077765 0.398446 0.00743604 -0.077765 0.404867 -0.0182 -0.077765 0.404101 -0.0182 -0.077765 0.40386 -0.0175576 -0.077765 0.402537 -0.0164011 -0.077765 0.404639 -0.00272547 -0.077765 0.405692 -0.0018861 -0.077765 0.406276 -0.000673168 -0.077765 0.424814 -0.00261977 -0.077765 0.419343 -0.0035184 -0.077765 0.423707 -0.00151254 -0.077765 0.420543 -0.00271634 -0.077765 0.429643 -0.00578375 -0.077765 0.430727 0.00839996 -0.077765 0.403866 0.0175629 -0.077765 0.404101 0.0182 -0.077765 0.401006 -0.0142464 -0.077765 0.401814 -0.00261977 -0.077765 0.403027 -0.00470004 -0.077765 0.399738 0.0100956 -0.077765 0.400432 0.013264 -0.077765 0.419777 0.00330425 -0.077765 0.424814 0.00261968 -0.077765 0.426327 0.00302496 -0.077765 0.427639 0.00272539 -0.077765 0.428692 0.00188601 -0.077765 0.429276 0.000673084 -0.077765 0.406276 0.000673084 -0.077765 0.408027 9.9958e-05 -0.077765 0.403327 -0.00302504 -0.077765 0.427027 -0.00470004 -0.077765 0.428443 -0.00498169 -0.077765 0.426327 -0.00302504 -0.077765 0.430227 -0.0152964 -0.077765 0.430262 -0.0152354 -0.077765 0.43393 -0.00977005 -0.077765 0.430727 -0.0134398 -0.077765 0.434527 -0.00600004 -0.077765 0.427639 -0.00272547 -0.077765 0.468027 -0.00810004 -0.0644624 0.468027 -0.01245 -0.0644624 0.468027 0.027321 -0.04591 0.468027 0.0271 -0.046735 0.468027 0.02555 -0.046735 0.468027 0.0301789 -0.04591 0.468027 0.0257935 -0.0455104 0.468027 0.0264872 -0.0444722 0.468027 0.03195 -0.0644624 0.468027 0.02875 -0.048385 0.468027 0.0275254 -0.0437786 0.468027 0.029575 -0.045306 0.468027 0.0295782 -0.043644 0.468027 -0.03195 -0.046735 0.468027 -0.0304 -0.046735 0.468027 -0.030179 -0.04756 0.468027 -0.03195 -0.0644624 0.468027 -0.029575 -0.0481639 0.468027 -0.0273211 -0.04756 0.468027 -0.027925 -0.045306 0.468027 -0.030179 -0.04591 0.468027 -0.0317065 -0.0455104 0.468027 -0.0310128 -0.0444722 0.468027 -0.0299746 -0.0437786 0.448186 -0.0544834 -0.0600723 0.450666 -0.0519424 -0.0592729 0.465935 -0.0521973 -0.0534893 0.466983 -0.0503191 -0.0531908 0.468081 -0.0495581 -0.0529076 0.469741 -0.0481466 -0.0525405 0.46965 -0.0497083 -0.0525587 0.473927 0.03275 -0.05195 0.47583 0.0405707 -0.0518277 0.474833 0.0402409 -0.0518817 0.476684 0.0379941 -0.0517969 0.475963 0.0362533 -0.051822 0.477342 0.0352717 -0.0517814 0.477452 0.0347011 -0.0517794 0.474352 0.0326273 -0.0519155 0.474542 0.0332033 -0.0519016 0.47801 0.0303889 -0.0517718 0.475309 0.0248077 -0.0518533 0.474667 0.0252464 -0.0518928 0.47868 0.0228961 -0.0517668 0.477702 0.0211663 -0.0517755 0.477735 0.0207026 -0.0517751 0.477709 0.0199439 -0.0517754 0.47463 -0.00378848 -0.0518953 0.475467 -0.00420068 -0.051845 0.474766 -0.0168124 -0.0518861 0.475631 0.00353086 -0.0518368 0.474787 0.00385007 -0.0518847 0.47493 0.00374186 -0.0518756 0.479142 0.0153874 -0.0517654 0.476738 0.0179138 -0.0517953 0.477627 0.00809996 -0.0517766 0.477482 0.0135969 -0.0517789 0.477435 0.00678486 -0.0517797 0.476275 0.00318966 -0.05181 0.476968 0.00572743 -0.0517894 0.476753 0.00540209 -0.0517949 0.475963 0.00455897 -0.051822 0.477651 0.00152466 -0.0517763 0.479517 -4.0559e-08 -0.051765 0.477865 -0.000823806 -0.0517734 0.479499 -0.00344147 -0.051765 0.477368 -0.00657774 -0.0517809 0.477482 -0.00695306 -0.0517789 0.47752 -0.0134366 -0.0517783 0.47742 -0.0138144 -0.05178 0.474787 -0.0166999 -0.0518847 0.47561 -0.0162564 -0.0518379 0.475496 -0.017042 -0.0518435 0.475923 -0.0160236 -0.0518237 0.476722 -0.0151894 -0.0517958 0.475791 -0.00442294 -0.0518294 0.47628 -0.0031862 -0.0518098 0.475634 -0.00352968 -0.0518367 0.476163 0.0174149 -0.0518141 0.474643 -0.0249994 -0.0518945 0.479198 -0.0141803 -0.0517653 0.477709 -0.0199421 -0.0517754 0.478619 -0.0236317 -0.0517671 0.477554 -0.0223068 -0.0517777 0.476488 -0.0240721 -0.0518028 0.475311 -0.0248076 -0.0518532 0.474682 -0.0252857 -0.0518918 0.474727 -0.02555 -0.0518887 0.474727 -0.03195 -0.0518887 0.47801 -0.0303902 -0.0517718 0.477839 -0.0321433 -0.0517737 0.474515 -0.0332327 -0.0519035 0.477283 -0.0355604 -0.0517825 0.475801 -0.0371028 -0.051829 0.476423 -0.0388634 -0.0518049 0.475866 -0.040475 -0.0518261 0.4746 -0.0407224 -0.0518974 0.474467 -0.0435905 -0.051907 0.472601 -0.0465496 -0.0520863 0.471245 -0.0465114 -0.0522736 0.472416 -0.0467929 -0.0521089 0.470339 -0.0475438 -0.0524269 0.473927 -0.03275 -0.05195 0.473782 -0.0327753 -0.0519627 0.475053 0.0424126 -0.051868 0.47343 0.043304 -0.0519958 0.473625 0.0450526 -0.0519771 0.473239 0.0456493 -0.0520151 0.464662 0.0516312 -0.0538863 0.470778 0.0486633 -0.0523499 0.468159 0.0495534 -0.0528887 0.467661 0.0511939 -0.0530121 0.455982 0.0548166 -0.0572283 0.464188 0.0530031 -0.0540433 0.459129 0.0519799 -0.055943 0.459174 0.0544501 -0.0559249 0.451406 0.0519799 -0.0590107 0.449628 0.0519799 -0.0596234 0.449691 0.0545673 -0.0596028 0.444995 0.0519799 -0.0608851 0.444995 0.0543193 -0.060885 0.444899 0.0519799 -0.0609053 0.443631 0.0542608 -0.0611489 0.440463 0.0541631 -0.0615657 0.436753 0.0542202 -0.0617509 0.43653 0.0543431 -0.0617544 0.436062 0.0549367 -0.0617597 0.43599 0.0551828 -0.0617603 0.435966 0.0554381 -0.0617605 0.434327 0.0519799 -0.061765 0.458771 -0.0545201 -0.0560878 0.458285 -0.0519424 -0.0562856 0.462093 -0.0519424 -0.0547865 0.455122 -0.0548308 -0.0575777 0.4496 -0.0519424 -0.0596324 0.445337 -0.0543354 -0.0608107 0.444995 -0.0543194 -0.0608851 0.444894 -0.0519424 -0.0609062 0.443492 -0.0519424 -0.061173 0.442736 -0.0519424 -0.0612941 0.435966 -0.0554382 -0.0617605 0.434327 -0.0519424 -0.061765 0.437249 -0.0541203 -0.0617408 0.438556 -0.0519424 -0.061695 0.439369 -0.0519424 -0.0616499 0.438683 -0.0541331 -0.0616889 0.441593 -0.0541915 -0.0614477 0.442057 -0.0542053 -0.0613897 0.44327 0.0299044 -0.081765 0.444038 0.031 -0.081765 0.428407 0.0259031 -0.081765 0.429089 0.0266761 -0.081765 0.430078 0.0271569 -0.081765 0.429914 0.0272929 -0.081765 0.432478 0.0278 -0.081765 0.432171 0.0289488 -0.081765 0.434878 0.0271569 -0.081765 0.430078 0.018843 -0.081765 0.430078 -0.0188431 -0.081765 0.429914 -0.0187071 -0.081765 0.428321 0.0254 -0.081765 0.427584 0.0240251 -0.081765 0.427478 0.023 -0.081765 0.431487 0.0176248 -0.081765 0.427584 -0.0219749 -0.081765 0.451898 0.0166132 -0.081765 0.453827 0.0135367 -0.081765 0.45188 0.0141908 -0.081765 0.449827 0.0163357 -0.081765 0.442383 0.0273945 -0.081765 0.436635 0.0254 -0.081765 0.427898 0.0209932 -0.081765 0.427678 0.023 -0.081765 0.427898 -0.0250068 -0.081765 0.427678 -0.023 -0.081765 0.427584 -0.0240252 -0.081765 0.430078 -0.027157 -0.081765 0.442381 0.0107281 -0.081765 0.442267 0.025 -0.081765 0.442739 0.021238 -0.081765 0.443506 0.019712 -0.081765 0.444137 0.0188855 -0.081765 0.448004 0.0142375 -0.081765 0.43623 -0.0259928 -0.081765 0.434076 -0.031 -0.081765 0.432478 -0.0278 -0.081765 0.432636 -0.0293812 -0.081765 0.442382 -0.0273908 -0.081765 0.442713 -0.0286878 -0.081765 0.437157 -0.0219319 -0.081765 0.443209 -0.00368487 -0.081765 0.451869 -0.00619332 -0.081765 0.436635 0.0206 -0.081765 0.434878 0.018843 -0.081765 0.444181 0.0125375 -0.081765 0.453827 -0.00553682 -0.081765 0.444818 -0.0182023 -0.081765 0.442267 -0.0260567 -0.081765 0.43456 -0.0186754 -0.081765 0.444567 -0.00481664 -0.081765 0.446235 -0.00571618 -0.081765 0.440995 0.00807023 -0.081765 0.435198 0.0133056 -0.081765 0.440517 0.00505658 -0.081765 0.440694 0.00689096 -0.081765 0.435198 -0.0133057 -0.081765 0.440517 0.00294333 -0.081765 0.440517 0.00399996 -0.081765 0.437127 0.00599996 -0.081765 0.431487 -0.0176249 -0.081765 0.432907 -0.0163493 -0.081765 0.434151 -0.0149015 -0.081765 0.442051 -0.00225946 -0.081765 0.436636 -0.00977803 -0.081765 0.473567 0.0232853 -0.0677299 0.479808 -4.19898e-08 -0.0521378 0.458788 0.00758893 -0.0815857 0.45943 -4.29135e-08 -0.0815242 0.462621 -3.32824e-08 -0.0807915 0.46184 0.00769571 -0.0809856 0.459411 0.00769766 -0.0815067 0.476401 0.00781492 -0.0629274 0.471391 -3.13567e-08 -0.0733037 0.471389 -3.14207e-08 -0.073307 0.468043 0.00770684 -0.0772265 0.468586 -3.8066e-08 -0.0768335 0.466141 -5.16038e-08 -0.0789657 0.464069 0.00769264 -0.0801083 0.479808 0.000347572 -0.0521379 0.477593 0.0304524 -0.0549155 0.477629 0.0232942 -0.0569738 0.476747 0.030499 -0.0578614 0.475795 0.0232932 -0.0624755 0.47309 0.0306341 -0.0674811 0.474145 0.0306026 -0.0651284 0.475238 0.0305646 -0.0623584 0.470271 0.030704 -0.07254 0.466774 0.0307805 -0.0768997 0.456965 0.021335 -0.0817046 0.459307 0.0155621 -0.0814698 0.467862 0.0155599 -0.0769961 0.46596 0.0155476 -0.0786537 0.463906 0.0155471 -0.0799606 0.458971 0.0309631 -0.081391 0.45742 0.023987 -0.0816646 0.457421 0.025003 -0.0816614 0.456408 0.0298875 -0.0817248 0.455332 0.0186769 -0.0817592 0.455831 0.019259 -0.081751 0.456479 0.020249 -0.0817306 0.455185 0.0127503 -0.0817613 0.456042 0.0120687 -0.0817488 0.456724 0.0155453 -0.0817246 0.470851 0.0232748 -0.0725769 0.473933 0.0156562 -0.067984 0.469607 0.0155805 -0.0750408 0.458674 0.00797626 -0.0815968 0.461695 0.015556 -0.0808951 0.466133 0.00769593 -0.0788505 0.469796 0.00772304 -0.0752891 0.47139 0.00774196 -0.0731054 0.471193 0.0156054 -0.0728514 0.474142 0.00778055 -0.0682294 0.478271 0.00784294 -0.0573767 0.476181 0.0157 -0.0627017 0.478037 0.0157335 -0.0571729 0.479631 0.0105749 -0.052138 0.474142 -0.00778071 -0.0682294 0.479772 -0.00481645 -0.0521379 0.478037 -0.0157338 -0.0571729 0.47856 -0.0274377 -0.0521405 0.478303 -0.0304117 -0.0521433 0.476893 -3.7816e-08 -0.0618723 0.474219 -3.47405e-08 -0.0683091 0.47139 -0.00774212 -0.0731054 0.468043 -0.00770701 -0.0772265 0.464088 -5.80777e-08 -0.0801861 0.464069 -0.00769281 -0.0801083 0.46571 -4.42492e-08 -0.0792613 0.466133 -0.0076961 -0.0788505 0.458667 -4.19898e-08 -0.0816115 0.456724 -0.0155456 -0.0817246 0.455434 -0.00456865 -0.0817596 0.45682 -0.00327889 -0.0817294 0.45804 -0.00149794 -0.0816643 0.455335 -0.0186808 -0.0817592 0.453827 -0.0174509 -0.081765 0.457421 -0.025003 -0.0816614 0.456947 -0.0212855 -0.0817057 0.455634 -0.0309944 -0.0817518 0.45645 -0.030994 -0.0817218 0.455902 -0.0306515 -0.0817446 0.456699 -0.0293295 -0.0817089 0.457202 -0.0278766 -0.0816734 0.460817 -0.0309278 -0.0808489 0.461695 -0.0155562 -0.0808951 0.459307 -0.0155623 -0.0814698 0.463906 -0.0155473 -0.0799606 0.467981 -0.0307534 -0.0755967 0.466211 -0.0307928 -0.0774409 0.471411 -0.0306777 -0.0706873 0.471193 -0.0156057 -0.0728514 0.470407 -0.030701 -0.0723314 0.469727 -0.0307159 -0.0733415 0.476181 -0.0157003 -0.0627016 0.473933 -0.0156565 -0.067984 0.477593 -0.0304544 -0.0549141 0.476771 -0.0304975 -0.0577836 0.475064 -0.0305701 -0.062824 0.469796 -0.0077232 -0.0752894 0.469606 -0.0155808 -0.0750411 0.467862 -0.0155602 -0.0769961 0.46596 -0.0155478 -0.0786537 0.463337 -0.0308647 -0.0796283 0.479808 -0.00017382 -0.0521379 0.478271 -0.00784311 -0.0573767 0.476401 -0.00781509 -0.0629274 0.475795 -0.0232935 -0.0624755 0.477629 -0.0232945 -0.0569738 0.474138 -0.0306023 -0.0651445 0.436127 -4.19898e-08 -0.085465 0.436127 -0.0530115 -0.0740739 0.436127 -0.0515581 -0.0760303 0.436127 -0.0499669 -0.077864 0.436127 -0.0469337 -0.0770875 0.436127 -0.0483567 -0.0794509 0.436127 -0.0456468 -0.0782285 0.436127 -0.0436809 -0.0796785 0.436127 -0.0431491 -0.0831092 0.429248 -0.017591 -0.085765 0.431012 -0.0149897 -0.085765 0.434382 -0.00930448 -0.085765 0.434067 -0.012664 -0.085765 0.431977 -0.0154402 -0.085765 0.428327 -0.031 -0.085765 0.434827 0.00599996 -0.085765 0.434382 0.0093044 -0.085765 0.43308 0.0123737 -0.085765 0.429248 0.0175909 -0.085765 0.407081 0.0182 -0.0698009 0.422154 0.0182 -0.0777075 0.422327 0.0182 -0.085465 0.403892 0.0182 -0.077765 0.403994 0.0182 -0.0777612 0.404867 0.0182 -0.077765 0.406327 0.0182 -0.077465 0.406627 0.0182 -0.0833775 0.406274 0.0182 -0.0828511 0.411598 0.0182 -0.085465 0.410207 -0.0182 -0.0853532 0.422327 -0.0182 -0.0776566 0.407074 -0.0182 -0.0698122 0.408001 -0.0182 -0.0685693 0.411595 -0.0182 -0.077765 0.407619 -0.0182 -0.084356 0.404419 -0.0182 -0.0793077 0.403994 -0.0182 -0.0777612 0.404075 -0.0182 -0.0783585 0.403892 -0.0182 -0.077765 0.403888 -0.0182 -0.0777497 0.415714 -0.0177537 -0.061765 0.434327 -0.0582202 -0.061765 0.431768 -0.0579766 -0.061765 0.431037 -0.00790004 -0.061765 0.429585 -0.0558337 -0.061765 0.433371 -0.0519424 -0.061765 0.430576 -0.0572448 -0.061765 0.405692 -0.00383748 -0.061765 0.406025 -0.0076599 -0.061765 0.422211 -0.0191744 -0.061765 0.414702 -0.016 -0.061765 0.40812 -0.0149594 -0.061765 0.416727 0.018025 -0.061765 0.422362 0.0189838 -0.061765 0.41848 0.0149875 -0.061765 0.422616 0.00789996 -0.061765 0.416727 0.013975 -0.061765 0.41848 -0.0149875 -0.061765 0.429679 -0.0488141 -0.061765 0.42858 -0.0443586 -0.061765 0.427276 -0.0432789 -0.061765 0.414973 0.0170125 -0.061765 0.408093 0.0148972 -0.061765 0.415714 0.0142463 -0.061765 0.405691 0.00380486 -0.061765 0.422226 0.0191398 -0.061765 0.417054 0.0191938 -0.061765 0.417739 0.0177537 -0.061765 0.411893 0.0214468 -0.061765 0.431327 0.00850309 -0.061765 0.423316 -0.00698877 -0.061765 0.416727 -0.018025 -0.061765 0.41707 -0.0192278 -0.061765 0.418693 -0.0188577 -0.061765 0.429427 -0.00628953 -0.061765 0.424743 -0.00603497 -0.061765 0.426427 -0.00570004 -0.061765 0.417739 0.0142463 -0.061765 0.425655 -0.0398078 -0.061765 0.426811 -0.0401488 -0.061765 0.421462 -0.0334844 -0.061765 0.416662 -0.0275607 -0.061765 0.423226 -0.0343557 -0.061765 0.418349 -0.0281211 -0.061765 0.420704 -0.0188577 -0.061765 0.418752 -0.016 -0.061765 0.422027 -0.0173 -0.061765 0.422027 -0.0101 -0.061765 0.431664 0.0515724 -0.061765 0.429291 0.0544317 -0.061765 0.429642 0.0488202 -0.061765 0.429048 0.0506056 -0.061765 0.428544 0.0443686 -0.061765 0.42677 0.0401502 -0.061765 0.425633 0.0397671 -0.061765 0.415008 0.0217553 -0.061765 0.415006 0.0234364 -0.061765 0.41659 0.027474 -0.061765 0.421406 0.0334125 -0.061765 0.418459 0.0283161 -0.061765 0.423286 0.0345034 -0.061765 0.404577 0.00216502 -0.067765 0.405492 0.00124996 -0.067765 0.404577 -0.00216511 -0.067765 0.405492 -0.00125004 -0.067765 0.403327 0.00249996 -0.067765 0.404411 0.00225238 -0.07724 0.404577 0.00216502 -0.07724 0.405764 0.00055626 -0.07724 0.405827 -4.19898e-08 -0.067765 0.405827 -4.19898e-08 -0.07724 0.405764 -0.000556344 -0.07724 0.405492 -0.00125004 -0.07724 0.403327 -0.00250004 -0.067765 0.404577 -0.00216511 -0.07724 0.403327 -0.00250004 -0.07724 0.404411 -0.00225246 -0.07724 0.405281 -0.00155877 -0.07724 0.405492 0.00124996 -0.07724 0.405692 0.00188601 -0.077765 0.404639 0.00272539 -0.077765 0.405281 0.00155868 -0.07724 0.426327 -4.19898e-08 -0.0662628 0.428827 -4.19898e-08 -0.067765 0.428492 -0.00125004 -0.067765 0.427577 0.00216502 -0.067765 0.427577 0.00216502 -0.07724 0.428281 0.00155868 -0.07724 0.428492 0.00124996 -0.067765 0.428492 0.00124996 -0.07724 0.427577 -0.00216511 -0.067765 0.427411 -0.00225246 -0.07724 0.427577 -0.00216511 -0.07724 0.428692 -0.0018861 -0.077765 0.428281 -0.00155877 -0.07724 0.428492 -0.00125004 -0.07724 0.429276 -0.000673168 -0.077765 0.428764 -0.000556344 -0.07724 0.428827 -4.19898e-08 -0.07724 0.428764 0.00055626 -0.07724 0.427411 0.00225238 -0.07724 0.468027 0.027321 -0.04756 0.468027 0.027925 -0.0481639 0.474352 0.027321 -0.04756 0.474352 0.02875 -0.048385 0.468027 0.029575 -0.0481639 0.468027 0.0301789 -0.04756 0.468027 0.0304 -0.046735 0.474352 0.0304 -0.046735 0.474352 0.027925 -0.0481639 0.474727 0.0277375 -0.0484887 0.474352 0.029575 -0.0481639 0.474352 0.0301789 -0.04756 0.474727 0.0305037 -0.0477475 0.474352 -0.030179 -0.04756 0.468027 -0.02875 -0.048385 0.474352 -0.02875 -0.048385 0.468027 -0.027925 -0.0481639 0.474352 -0.027925 -0.0481639 0.468027 -0.0271 -0.046735 0.474352 -0.0273211 -0.04756 0.474727 -0.030775 -0.046735 0.474727 -0.0305037 -0.0477475 0.474352 -0.029575 -0.0481639 0.474727 -0.0297625 -0.0484887 0.474727 -0.0277375 -0.0484887 0.474727 -0.026725 -0.046735 0.474227 0.00349996 -0.0551665 0.475528 0.00324115 -0.0551665 0.476631 0.00250412 -0.0551665 0.477368 0.00140108 -0.0551665 0.477491 0.000100854 -0.0561168 0.474247 -0.0170568 -0.0535035 0.474244 -0.0170571 -0.0535611 0.474217 -0.017055 -0.0535035 0.474279 -0.0170589 -0.0535035 0.474644 -0.0171053 -0.0535035 0.474725 -0.0171211 -0.0535035 0.475283 -0.0173066 -0.0538452 0.476518 -0.0181291 -0.0535035 0.473201 -0.0329012 -0.0537079 0.473006 -0.0328473 -0.0537079 0.472955 -0.0328353 -0.0537079 0.474178 -0.0333853 -0.0537079 0.474219 -0.0334688 -0.0542466 0.47488 -0.0340596 -0.0537079 0.474788 -0.0340578 -0.0543984 0.475097 -0.0343716 -0.0537079 0.475504 -0.0369488 -0.0537079 0.47355 -0.0330509 -0.0540682 0.457819 0.00364511 -0.0804834 0.457281 0.00690356 -0.0801483 0.457827 0.00399996 -0.080497 0.455913 0.00919217 -0.0799311 0.452888 0.011391 -0.0797883 0.455484 0.00965671 -0.079897 0.452471 0.0115502 -0.0797816 0.452888 0.011391 -0.079265 0.453486 -0.00311433 -0.0798026 0.452888 -0.00339106 -0.0797883 0.457218 0.000938491 -0.079265 0.456368 -0.000605964 -0.0799775 0.456067 -0.0253521 -0.0804798 0.456067 -0.024648 -0.0804798 0.456077 -0.025 -0.080497 0.45592 -0.0236093 -0.079265 0.455465 -0.0223027 -0.0800939 0.455747 -0.0229967 -0.0802011 0.452566 -0.0193822 -0.079799 0.454713 -0.0211032 -0.079265 0.454257 -0.0205918 -0.0799006 0.452539 -0.0306311 -0.079265 0.451891 -0.0308992 -0.0797817 0.449827 -0.03125 -0.079765 0.453105 -0.030321 -0.0798215 0.452539 -0.030631 -0.0797981 0.455913 -0.0264234 -0.0802995 0.455385 -0.0278574 -0.0800718 0.456077 0.025 -0.080497 0.45592 0.0236092 -0.079265 0.454763 0.0288331 -0.0799569 0.455465 0.0276973 -0.0800939 0.45592 0.0263907 -0.079265 0.454713 0.0288968 -0.079265 0.454257 0.0294082 -0.0799006 0.4513 0.031074 -0.0797743 0.453212 0.0302537 -0.0798269 0.452539 0.030631 -0.079265 0.450558 0.031207 -0.0797692 0.449827 0.01875 -0.079265 0.451167 0.0188954 -0.0797733 0.454713 0.0211031 -0.079265 0.454677 0.0210586 -0.0799458 0.453723 0.0201134 -0.0798577 0.452539 0.0193689 -0.079265 0.453105 0.019679 -0.0798215 0.455913 0.0235766 -0.0802995 0.43443 -0.0189457 -0.078265 0.432478 -0.0185 -0.081465 0.436865 -0.0219987 -0.078265 0.436865 -0.0240014 -0.078265 0.436865 -0.0240014 -0.081465 0.435996 -0.0258057 -0.081465 0.434728 0.0268971 -0.081465 0.436375 0.02525 -0.081465 0.436978 0.023 -0.078265 0.436375 0.02075 -0.081465 0.434728 0.0191028 -0.078265 0.432478 0.0185 -0.078265 0.432478 0.024525 -0.078265 0.43324 0.0243206 -0.078265 0.433728 0.023 -0.07799 0.43356 0.022375 -0.07799 0.433103 0.0219174 -0.07799 0.433103 -0.0219175 -0.07799 0.43356 -0.023625 -0.07799 0.432478 -0.02425 -0.07799 0.43324 -0.0243207 -0.078265 0.416727 -0.0127 -0.062965 0.418194 -0.0130442 -0.062965 0.419355 -0.014005 -0.077465 0.419968 -0.015382 -0.062965 0.419968 -0.015382 -0.077465 0.423308 0.0181451 -0.062965 0.421796 0.0177904 -0.062965 0.420685 0.0169078 -0.077465 0.4206 -0.0168006 -0.077465 0.418156 -0.016825 -0.073765 0.417552 -0.017429 -0.073765 0.417552 -0.0145711 -0.073765 0.416727 -0.01435 -0.073765 0.416727 -0.016 -0.0747564 0.418377 -0.016 -0.073765 0.418156 -0.015175 -0.073765 0.417552 -0.017429 -0.06214 0.417552 -0.0145711 -0.06214 0.416727 -0.01435 -0.06214 0.417739 -0.0177537 -0.061765 0.418156 -0.016825 -0.06214 0.41848 -0.0170125 -0.061765 0.418377 -0.016 -0.06214 0.418156 -0.015175 -0.06214 0.417739 -0.0142463 -0.061765 0.417552 0.014571 -0.073765 0.418156 0.016825 -0.073765 0.418377 0.016 -0.073765 0.416727 0.01435 -0.06214 0.417552 0.014571 -0.06214 0.418156 0.015175 -0.073765 0.418156 0.015175 -0.06214 0.418377 0.016 -0.06214 0.417552 0.0174289 -0.073765 0.416727 0.01765 -0.073765 0.417552 0.0174289 -0.06214 0.418752 0.016 -0.061765 0.418156 0.016825 -0.06214 0.41848 0.0170125 -0.061765 0.416727 0.01765 -0.06214 0.436978 0.023 -0.081465 0.437278 0.023 -0.081765 0.434728 0.0191028 -0.081465 0.432478 0.0182 -0.081765 0.43443 -0.0189457 -0.081465 0.432478 -0.0182 -0.081765 0.435996 -0.0201943 -0.081465 0.43623 -0.0200073 -0.081765 0.436865 -0.0219987 -0.081465 0.437157 -0.0240681 -0.081765 0.43443 -0.0270544 -0.081465 0.43456 -0.0273247 -0.081765 0.416727 -0.013 -0.077765 0.416727 -0.0127 -0.077465 0.418194 -0.0130442 -0.077465 0.418061 -0.0133129 -0.077765 0.419116 -0.0141864 -0.077765 0.419674 -0.0154381 -0.077765 0.421984 -0.0182 -0.077765 0.421663 -0.0180592 -0.077765 0.423308 -0.0181605 -0.0774803 0.422154 -0.0182 -0.0777075 0.421796 -0.0177905 -0.077465 0.43356 -0.022375 -0.076765 0.431853 -0.0219175 -0.076765 0.432478 -0.02175 -0.076765 0.431853 -0.0240826 -0.076765 0.432478 -0.02425 -0.076765 0.433103 -0.0240826 -0.076765 0.431228 -0.023 -0.076765 0.431395 0.023625 -0.076765 0.431228 0.023 -0.076765 0.431853 0.0240825 -0.076765 0.432478 0.02425 -0.076765 0.433103 0.0240825 -0.076765 0.431853 0.0219174 -0.076765 0.432478 0.02175 -0.076765 0.433103 0.0219174 -0.076765 -0.15519 0.0382 -0.088465 -0.14459 -0.0317 -0.084765 -0.144908 -0.0337087 -0.084765 -0.146493 -0.0362962 -0.0890164 -0.145298 -0.034651 -0.0890164 -0.149127 -0.0378966 -0.088465 -0.149081 -0.0378819 -0.084765 -0.148309 -0.0375753 -0.0890073 -0.148276 -0.0375596 -0.0890249 -0.148268 -0.0375556 -0.0890214 -0.148261 -0.0375523 -0.0890164 -0.150097 -0.0381237 -0.088465 -0.15519 -0.0382 -0.084765 -0.157595 -0.0377387 -0.0886092 -0.157915 -0.0376009 -0.088939 -0.15797 -0.0375753 -0.0890073 -0.158011 -0.0375556 -0.0890214 -0.157198 -0.0378819 -0.084765 -0.157376 -0.0378214 -0.0885001 -0.157152 -0.0378966 -0.088465 -0.159786 -0.0362962 -0.0890164 -0.161371 -0.0337087 -0.084765 -0.16169 -0.0317 -0.0890164 -0.16169 0.027071 -0.084765 -0.16169 0.0317 -0.084765 -0.16169 -0.0267138 -0.0861255 -0.16169 -0.0265376 -0.086765 -0.16169 0.0258488 -0.0874724 -0.16169 -0.0258489 -0.0874724 -0.16169 -0.0246213 -0.088367 -0.16169 0.0265313 -0.0867715 -0.16169 0.0242159 -0.0885115 -0.16169 0.0317 -0.0890164 -0.16169 -0.0213874 -0.0887572 -0.16169 0.0221094 -0.0887515 -0.160448 0.0355206 -0.084765 -0.161371 0.0337086 -0.0890164 -0.160448 0.0355206 -0.0890164 -0.157595 0.0377386 -0.0886092 -0.157915 0.0376008 -0.088939 -0.157955 0.0375823 -0.0889902 -0.157996 0.0375629 -0.0890251 -0.157198 0.0378818 -0.084765 -0.158018 0.0375522 -0.0890164 -0.156183 0.0381237 -0.088465 -0.15519 0.0382 -0.084765 -0.150097 0.0381237 -0.088465 -0.148309 0.0375752 -0.0890073 -0.149081 0.0378818 -0.084765 -0.147269 0.0369586 -0.084765 -0.146493 0.0362962 -0.0890164 -0.144908 0.0337086 -0.0890164 -0.144908 0.0337086 -0.084765 -0.14459 0.0317 -0.084765 -0.14459 0.0317 -0.0890164 -0.14459 -0.027071 -0.084765 -0.14459 0.0267137 -0.0861255 -0.14459 0.0265375 -0.086765 -0.14459 -0.0317 -0.0890164 -0.14459 0.0258488 -0.0874724 -0.14459 0.0246212 -0.088367 -0.14459 -0.0258489 -0.0874724 -0.14459 0.0234117 -0.0886727 -0.14459 0.0221094 -0.0887515 -0.159941 0.0317 -0.090765 -0.14854 0.0319 -0.090765 -0.146338 0.0317 -0.090765 -0.159941 -0.0317 -0.090765 -0.157651 -0.0310026 -0.090765 -0.147946 -0.0352633 -0.090765 -0.147476 0.034785 -0.090765 -0.14854 0.0357092 -0.090765 -0.147077 0.0342452 -0.090765 -0.146759 0.0336547 -0.090765 -0.159752 0.0330252 -0.090765 -0.15774 0.0319 -0.090765 -0.156964 -0.0293444 -0.090765 -0.147476 -0.034785 -0.090765 -0.158333 0.0352632 -0.090765 -0.152242 -0.0273884 -0.090765 -0.149315 0.0293443 -0.090765 -0.146338 -0.0317 -0.090765 -0.14889 -0.0301397 -0.090765 -0.149887 -0.0286474 -0.090765 -0.156392 0.0286473 -0.090765 -0.155695 -0.0280753 -0.090765 -0.15774 -0.0357093 -0.090765 -0.15774 -0.0319 -0.090765 -0.158803 -0.034785 -0.090765 -0.152242 0.0273883 -0.090765 -0.15314 0.0273 -0.090765 -0.15314 -0.0273 -0.090765 -0.154037 0.0273883 -0.090765 -0.154037 -0.0273884 -0.090765 -0.1549 -0.0276502 -0.090765 -0.160448 -0.0355206 -0.084765 -0.15901 -0.0369587 -0.084765 -0.16169 -0.027071 -0.084765 -0.16169 -0.0317 -0.084765 -0.161501 -0.0261963 -0.084765 -0.161664 -0.026745 -0.084765 -0.16024 0.0244361 -0.084765 -0.161371 0.0337086 -0.084765 -0.15901 0.0369586 -0.084765 -0.15729 0.0232 -0.084765 -0.161116 0.0256241 -0.084765 -0.150032 -0.00505776 -0.084765 -0.156147 0.0259577 -0.084765 -0.154265 0.0299514 -0.084765 -0.154882 0.0268031 -0.084765 -0.156993 0.0246924 -0.084765 -0.14459 0.027071 -0.084765 -0.156247 -0.00505776 -0.084765 -0.151191 0.033025 -0.084765 -0.145831 0.0355206 -0.084765 -0.152015 0.0338485 -0.084765 -0.15109 0.0382 -0.084765 -0.15314 0.03415 -0.084765 -0.154265 0.0338485 -0.084765 -0.146039 0.0244361 -0.084765 -0.15949 -0.00805004 -0.084765 -0.152015 0.0299514 -0.084765 -0.144615 0.0267452 -0.084765 -0.151191 0.030775 -0.084765 -0.15314 0.02965 -0.084765 -0.15289 0.0271 -0.084765 -0.15339 0.0271 -0.084765 -0.149186 0.00419242 -0.084765 -0.14889 0.00269996 -0.084765 -0.14889 -0.00230004 -0.084765 -0.149186 -0.00379251 -0.084765 -0.145163 0.0256241 -0.084765 -0.144778 0.0261965 -0.084765 -0.157093 0.00419242 -0.084765 -0.15729 0.0142 -0.084765 -0.149286 0.0246924 -0.084765 -0.14899 0.0232 -0.084765 -0.157215 -0.00805004 -0.084765 -0.15279 -0.00620004 -0.084765 -0.15349 -0.00620004 -0.084765 -0.151297 0.00630309 -0.084765 -0.150132 0.0114422 -0.084765 -0.15279 0.00659996 -0.084765 -0.15289 0.0103 -0.084765 -0.15349 0.00659996 -0.084765 -0.15339 0.0103 -0.084765 -0.154882 0.0105968 -0.084765 -0.154982 0.00630309 -0.084765 -0.147269 -0.0369587 -0.084765 -0.152015 -0.0338486 -0.084765 -0.15109 -0.0382 -0.084765 -0.145831 -0.0355206 -0.084765 -0.151191 -0.033025 -0.084765 -0.15089 -0.0319 -0.084765 -0.151191 -0.030775 -0.084765 -0.145163 -0.0256242 -0.084765 -0.156843 -0.0246925 -0.084765 -0.155088 -0.033025 -0.084765 -0.149436 -0.0246925 -0.084765 -0.14679 -0.00805004 -0.084765 -0.15304 -0.00990004 -0.084765 -0.14679 -0.0215525 -0.084765 -0.14914 -0.0138 -0.084765 -0.146599 -0.0230434 -0.084765 -0.15314 -0.02965 -0.084765 -0.152015 -0.0299515 -0.084765 -0.150282 -0.0259578 -0.084765 -0.145053 -0.0257493 -0.084765 -0.14889 0.00269996 -0.074963 -0.150032 0.00545767 -0.074963 -0.150032 0.00545767 -0.084765 -0.15279 0.00659996 -0.074963 -0.15349 0.00659996 -0.074963 -0.156247 0.00545767 -0.084765 -0.15739 0.00269996 -0.084765 -0.15739 -0.00230004 -0.084765 -0.15739 -0.00230004 -0.074963 -0.157093 -0.00379251 -0.084765 -0.157093 -0.00379251 -0.074963 -0.154982 -0.00590317 -0.084765 -0.154982 -0.00590317 -0.074963 -0.151297 -0.00590317 -0.074963 -0.151297 -0.00590317 -0.084765 -0.149186 -0.00379251 -0.074963 -0.15279 -0.00540004 -0.072765 -0.14969 0.00269996 -0.072765 -0.15349 0.00579996 -0.072765 -0.154676 0.00556398 -0.072765 -0.154676 -0.00516407 -0.072765 -0.150598 0.00489199 -0.072765 -0.151603 0.00556398 -0.072765 -0.15279 0.00579996 -0.072765 -0.15659 0.00269996 -0.072765 -0.15349 -0.00540004 -0.072765 -0.14899 0.0232 -0.074963 -0.149286 0.0246924 -0.074963 -0.150132 0.0259577 -0.084765 -0.150132 0.0259577 -0.074963 -0.151397 0.0268031 -0.084765 -0.151397 0.0268031 -0.074963 -0.15289 0.0271 -0.074963 -0.154882 0.0268031 -0.074963 -0.156993 0.0127075 -0.084765 -0.156147 0.0114422 -0.084765 -0.156147 0.0114422 -0.074963 -0.151397 0.0105968 -0.084765 -0.15289 0.0103 -0.074963 -0.151397 0.0105968 -0.074963 -0.150132 0.0114422 -0.074963 -0.149286 0.0127075 -0.084765 -0.149286 0.0127075 -0.074963 -0.14899 0.0142 -0.084765 -0.15339 0.0111 -0.072765 -0.150698 0.0120079 -0.072765 -0.151703 0.0113359 -0.072765 -0.14979 0.0142 -0.072765 -0.15289 0.0263 -0.072765 -0.150698 0.025392 -0.072765 -0.149436 -0.0123076 -0.084765 -0.150282 -0.0110423 -0.084765 -0.150282 -0.0110423 -0.074963 -0.151547 -0.0101969 -0.074963 -0.151547 -0.0101969 -0.084765 -0.15304 -0.00990004 -0.074963 -0.15324 -0.00990004 -0.074963 -0.15324 -0.00990004 -0.084765 -0.154732 -0.0101969 -0.084765 -0.155997 -0.0110423 -0.084765 -0.156843 -0.0123076 -0.084765 -0.155997 -0.0110423 -0.074963 -0.156843 -0.0123076 -0.074963 -0.15714 -0.0138 -0.084765 -0.15714 -0.0232 -0.074963 -0.15714 -0.0232 -0.084765 -0.155997 -0.0259578 -0.084765 -0.154732 -0.0268032 -0.084765 -0.154732 -0.0268032 -0.074963 -0.15324 -0.0271 -0.084765 -0.15304 -0.0271 -0.084765 -0.15304 -0.0271 -0.074963 -0.151547 -0.0268032 -0.084765 -0.149436 -0.0246925 -0.074963 -0.14914 -0.0232 -0.084765 -0.14914 -0.0138 -0.074963 -0.150176 -0.0243864 -0.072765 -0.14994 -0.0232 -0.072765 -0.15324 -0.0107 -0.072765 -0.15304 -0.0107 -0.072765 -0.154426 -0.010936 -0.072765 -0.150176 -0.0126137 -0.072765 -0.150848 -0.011608 -0.072765 -0.151853 -0.010936 -0.072765 -0.154426 -0.0260641 -0.072765 -0.15324 -0.0263 -0.072765 -0.156104 -0.0243864 -0.072765 -0.148336 -0.0367419 -0.0900203 -0.147666 -0.0355815 -0.0905892 -0.145914 -0.0317 -0.0905892 -0.145965 -0.0324291 -0.0905892 -0.144765 -0.0317 -0.0894407 -0.144843 -0.0326894 -0.0894407 -0.146719 -0.0344725 -0.0905892 -0.145973 -0.0354174 -0.0894407 -0.147153 -0.0350605 -0.0905892 -0.148336 0.0367418 -0.0900203 -0.147153 0.0350604 -0.0905892 -0.146618 0.0361719 -0.0894407 -0.145965 0.032429 -0.0905892 -0.158907 -0.0368165 -0.0894407 -0.159126 -0.0350605 -0.0905892 -0.159661 -0.036172 -0.0894407 -0.157967 -0.0360673 -0.0905892 -0.160314 -0.0324291 -0.0905892 -0.15956 -0.0344725 -0.0905892 -0.157943 0.0367418 -0.0900203 -0.157923 0.037403 -0.0894407 -0.159661 0.0361719 -0.0894407 -0.158613 0.0355814 -0.0905892 -0.160314 0.032429 -0.0905892 -0.160306 0.0354173 -0.0894407 -0.160365 -0.0317 -0.0905892 -0.161514 -0.0317 -0.0894407 -0.160121 -0.0324017 -0.0907193 -0.160171 -0.0317 -0.0907193 -0.159894 -0.0323693 -0.090765 -0.159752 -0.0330252 -0.090765 -0.15952 -0.0336547 -0.090765 -0.159202 -0.0342453 -0.090765 -0.15973 -0.0337492 -0.0907193 -0.158333 -0.0352633 -0.090765 -0.16016 -0.0331436 -0.0905892 -0.159973 -0.0330893 -0.0907193 -0.159396 -0.0343683 -0.0907193 -0.159907 -0.0338293 -0.0905892 -0.158978 -0.0349341 -0.0907193 -0.158613 -0.0355815 -0.0905892 -0.158485 -0.0354355 -0.0907193 -0.157867 -0.0359103 -0.0907157 -0.160365 0.0317 -0.0905892 -0.157863 0.0359029 -0.0907193 -0.158485 0.0354354 -0.0907193 -0.158803 0.034785 -0.090765 -0.159202 0.0342452 -0.090765 -0.15952 0.0336547 -0.090765 -0.159973 0.0330892 -0.0907193 -0.159894 0.0323692 -0.090765 -0.160121 0.0324016 -0.0907193 -0.160171 0.0317 -0.0907193 -0.158978 0.034934 -0.0907193 -0.159126 0.0350604 -0.0905892 -0.159396 0.0343682 -0.0907193 -0.15956 0.0344725 -0.0905892 -0.15973 0.0337491 -0.0907193 -0.159907 0.0338292 -0.0905892 -0.16016 0.0331435 -0.0905892 -0.147794 -0.0354355 -0.0907193 -0.14854 -0.0357093 -0.090765 -0.148412 -0.0359103 -0.0907157 -0.148416 -0.035903 -0.0907193 -0.147077 -0.0342453 -0.090765 -0.14655 -0.0337492 -0.0907193 -0.146759 -0.0336547 -0.090765 -0.146527 -0.0330252 -0.090765 -0.146158 -0.0324017 -0.0907193 -0.146385 -0.0323693 -0.090765 -0.147301 -0.0349341 -0.0907193 -0.146883 -0.0343683 -0.0907193 -0.146372 -0.0338293 -0.0905892 -0.146306 -0.0330893 -0.0907193 -0.146119 -0.0331436 -0.0905892 -0.146108 -0.0317 -0.0907193 -0.146108 0.0317 -0.0907193 -0.146158 0.0324016 -0.0907193 -0.146385 0.0323692 -0.090765 -0.146527 0.0330252 -0.090765 -0.146883 0.0343682 -0.0907193 -0.147946 0.0352632 -0.090765 -0.147301 0.034934 -0.0907193 -0.145914 0.0317 -0.0905892 -0.146306 0.0330892 -0.0907193 -0.146119 0.0331435 -0.0905892 -0.14655 0.0337491 -0.0907193 -0.146372 0.0338292 -0.0905892 -0.146719 0.0344725 -0.0905892 -0.147794 0.0354354 -0.0907193 -0.147666 0.0355814 -0.0905892 -0.158017 0.0375528 -0.0890233 -0.158015 0.0375535 -0.0890299 -0.158014 0.0375539 -0.0890326 -0.157979 0.0375203 -0.089246 -0.158011 0.0375554 -0.0890393 -0.158005 0.0375579 -0.089045 -0.158907 0.0368164 -0.0894407 -0.159753 0.0362639 -0.089246 -0.160825 0.0345711 -0.0894407 -0.160411 0.0354937 -0.089246 -0.161204 0.0336543 -0.0894407 -0.161564 0.0327096 -0.089246 -0.161436 0.0326893 -0.0894407 -0.158983 0.0369216 -0.089246 -0.15901 0.0369586 -0.0890164 -0.159786 0.0362962 -0.0890164 -0.16094 0.0346302 -0.089246 -0.160981 0.0346509 -0.0890164 -0.161328 0.0336945 -0.089246 -0.16161 0.0327168 -0.0890164 -0.161644 0.0317 -0.089246 -0.161514 0.0317 -0.0894407 -0.161644 -0.0317 -0.089246 -0.15801 -0.0375558 -0.0890404 -0.158983 -0.0369217 -0.089246 -0.157999 -0.0375608 -0.0890488 -0.158012 -0.0375549 -0.0890372 -0.15901 -0.0369587 -0.0890164 -0.158017 -0.0375528 -0.0890233 -0.158018 -0.0375523 -0.0890164 -0.160448 -0.0355206 -0.0890164 -0.160981 -0.034651 -0.0890164 -0.161371 -0.0337087 -0.0890164 -0.16094 -0.0346302 -0.089246 -0.16161 -0.0327169 -0.0890164 -0.161564 -0.0327097 -0.089246 -0.157978 -0.0375179 -0.0892525 -0.161436 -0.0326894 -0.0894407 -0.161204 -0.0336543 -0.0894407 -0.161328 -0.0336945 -0.089246 -0.160825 -0.0345712 -0.0894407 -0.160306 -0.0354174 -0.0894407 -0.160411 -0.0354938 -0.089246 -0.159753 -0.0362639 -0.089246 -0.147296 0.0369216 -0.089246 -0.1483 0.0375203 -0.089246 -0.148281 0.0375607 -0.0890488 -0.148269 0.0375557 -0.0890404 -0.148264 0.0375535 -0.0890299 -0.148263 0.037553 -0.0890255 -0.147269 0.0369586 -0.0890164 -0.145831 0.0355206 -0.0890164 -0.145298 0.0346509 -0.0890164 -0.145339 0.0346302 -0.089246 -0.14467 0.0327168 -0.0890164 -0.144715 0.0327096 -0.089246 -0.147372 0.0368164 -0.0894407 -0.144843 0.0326893 -0.0894407 -0.145075 0.0336543 -0.0894407 -0.144951 0.0336945 -0.089246 -0.145455 0.0345711 -0.0894407 -0.145973 0.0354173 -0.0894407 -0.145868 0.0354937 -0.089246 -0.146526 0.0362639 -0.089246 -0.144635 0.0317 -0.089246 -0.144765 0.0317 -0.0894407 -0.147372 -0.0368165 -0.0894407 -0.1483 -0.0375204 -0.089246 -0.148265 -0.037554 -0.0890326 -0.148262 -0.0375528 -0.0890233 -0.148264 -0.0375536 -0.0890299 -0.147296 -0.0369217 -0.089246 -0.148301 -0.0375179 -0.0892525 -0.146618 -0.036172 -0.0894407 -0.145455 -0.0345712 -0.0894407 -0.145075 -0.0336543 -0.0894407 -0.145339 -0.0346302 -0.089246 -0.144951 -0.0336945 -0.089246 -0.147269 -0.0369587 -0.0890164 -0.146526 -0.0362639 -0.089246 -0.145868 -0.0354938 -0.089246 -0.145831 -0.0355206 -0.0890164 -0.144908 -0.0337087 -0.0890164 -0.144715 -0.0327097 -0.089246 -0.14467 -0.0327169 -0.0890164 -0.144635 -0.0317 -0.089246 -0.152015 -0.0299515 -0.088765 -0.154555 -0.0284817 -0.088765 -0.154265 -0.0299515 -0.088765 -0.153861 -0.0282711 -0.088765 -0.155195 -0.0288236 -0.088765 -0.155756 -0.0292837 -0.088765 -0.152418 -0.0282711 -0.088765 -0.151724 -0.0284817 -0.088765 -0.151084 -0.0288236 -0.088765 -0.155088 -0.030775 -0.088765 -0.15684 -0.0369667 -0.088765 -0.15539 -0.0319 -0.088765 -0.156768 -0.0311782 -0.088765 -0.157062 -0.0376106 -0.088765 -0.156972 -0.0374878 -0.088765 -0.14944 -0.0369667 -0.088765 -0.150063 -0.0298444 -0.088765 -0.149721 -0.0304841 -0.088765 -0.151191 -0.030775 -0.088765 -0.149511 -0.0311782 -0.088765 -0.15089 -0.0319 -0.088765 -0.14944 -0.0319 -0.088765 -0.151191 -0.033025 -0.088765 -0.152015 -0.0338486 -0.088765 -0.15314 -0.03415 -0.088765 -0.154265 -0.0338486 -0.088765 -0.156137 -0.0378273 -0.088765 -0.15714 -0.0319 -0.090165 -0.157063 -0.0311197 -0.090165 -0.156465 -0.0296778 -0.090165 -0.156465 -0.0296778 -0.089065 -0.155968 -0.0290716 -0.090165 -0.155968 -0.0290716 -0.089065 -0.155362 -0.0285742 -0.089065 -0.15467 -0.0282045 -0.089065 -0.15467 -0.0282045 -0.090165 -0.15314 -0.0279 -0.090165 -0.152359 -0.0279769 -0.090165 -0.151609 -0.0282045 -0.090165 -0.149814 -0.0296778 -0.089065 -0.150311 -0.0290716 -0.090165 -0.149444 -0.0303693 -0.090165 -0.149216 -0.0311197 -0.089065 -0.14914 -0.0319 -0.089065 -0.149216 -0.0311197 -0.090165 -0.14914 -0.0363696 -0.089596 -0.155088 0.030775 -0.088765 -0.156842 0.0370642 -0.088765 -0.156137 0.0378272 -0.088765 -0.156972 0.0374877 -0.088765 -0.151191 0.030775 -0.088765 -0.155088 0.033025 -0.088765 -0.15684 0.0369666 -0.088765 -0.15314 0.03415 -0.088765 -0.156558 0.030484 -0.088765 -0.156768 0.0311781 -0.088765 -0.152015 0.0299514 -0.088765 -0.15089 0.0319 -0.088765 -0.149721 0.030484 -0.088765 -0.150523 0.0292837 -0.088765 -0.152015 0.0338485 -0.088765 -0.14944 0.0369666 -0.088765 -0.150142 0.0378272 -0.088765 -0.15314 0.0282 -0.088765 -0.15314 0.02965 -0.088765 -0.153861 0.0282711 -0.088765 -0.14914 0.0319 -0.090165 -0.149216 0.0311196 -0.089065 -0.149216 0.0311196 -0.090165 -0.149444 0.0303692 -0.089065 -0.149444 0.0303692 -0.090165 -0.150917 0.0285741 -0.090165 -0.151609 0.0282044 -0.090165 -0.152359 0.0279768 -0.089065 -0.15314 0.0279 -0.090165 -0.15392 0.0279768 -0.089065 -0.155362 0.0285741 -0.089065 -0.155362 0.0285741 -0.090165 -0.155968 0.0290715 -0.089065 -0.156835 0.0303692 -0.089065 -0.156835 0.0303692 -0.090165 -0.157063 0.0311196 -0.090165 -0.14914 0.0357092 -0.090165 -0.14914 0.0319 -0.089065 -0.14914 0.0363695 -0.089596 -0.15714 0.0363695 -0.089596 -0.159888 -0.0213874 -0.0870254 -0.15949 -0.0215525 -0.084765 -0.16027 -0.0234675 -0.087046 -0.15968 -0.0230434 -0.084765 -0.160642 -0.0242699 -0.0870443 -0.16024 -0.0244362 -0.084765 -0.16116 -0.0254056 -0.0857706 -0.161116 -0.0256242 -0.084765 -0.16116 0.0254055 -0.0857706 -0.161215 0.025116 -0.0870348 -0.15968 0.0230433 -0.084765 -0.15949 0.0215524 -0.084765 -0.146039 -0.0244362 -0.084765 -0.145637 -0.0242699 -0.0870443 -0.146009 -0.0234675 -0.087046 -0.14679 0.0215524 -0.084765 -0.145119 0.0254055 -0.0857706 -0.146599 0.0230433 -0.084765 -0.145637 0.0242698 -0.0870443 -0.161679 -0.0268618 -0.084765 -0.161553 -0.0260116 -0.085935 -0.161446 -0.0260836 -0.084765 -0.161215 -0.0251161 -0.0870348 -0.161571 0.0263706 -0.084765 -0.161612 0.0265024 -0.084765 -0.16169 0.0267137 -0.0861255 -0.161313 0.025865 -0.084765 -0.161226 0.0257492 -0.084765 -0.161553 0.0260115 -0.085935 -0.16169 0.0265375 -0.086765 -0.161689 0.0264919 -0.0867734 -0.16156 0.0257593 -0.0869108 -0.144966 -0.0258651 -0.084765 -0.144708 -0.0263707 -0.084765 -0.144667 -0.0265025 -0.084765 -0.14459 -0.0267138 -0.0861255 -0.145119 -0.0254056 -0.0857706 -0.14486 -0.0254345 -0.086973 -0.145064 -0.0251161 -0.0870348 -0.144727 -0.0260116 -0.085935 -0.144833 0.0260835 -0.084765 -0.1446 0.0268623 -0.084765 -0.14459 0.0264919 -0.0867734 -0.144623 0.0261361 -0.0868397 -0.14472 0.0257593 -0.0869108 -0.144727 0.0260115 -0.085935 -0.145064 0.025116 -0.0870348 -0.144761 -0.0253791 -0.0873718 -0.144646 -0.0257348 -0.0872612 -0.144623 -0.02614 -0.0868389 -0.144718 -0.0257631 -0.0869101 -0.14459 -0.0264916 -0.0867735 -0.14459 -0.0265297 -0.0867699 -0.14459 -0.0264908 -0.086794 -0.144967 -0.0250372 -0.0874176 -0.144868 -0.0249566 -0.0876336 -0.146391 -0.0213874 -0.0870254 -0.14577 -0.0233776 -0.0876399 -0.144952 -0.0233514 -0.0881958 -0.14532 -0.0232081 -0.0880714 -0.145046 -0.0213874 -0.0882592 -0.144845 -0.0244493 -0.0879665 -0.144974 -0.0230859 -0.0882186 -0.146143 -0.0213874 -0.087625 -0.145658 -0.0213874 -0.0880675 -0.145664 -0.0213874 -0.0880636 -0.14614 -0.0213874 -0.0876282 -0.145664 0.0213873 -0.0880636 -0.14614 0.0213873 -0.0876282 -0.146391 0.0213873 -0.0870254 -0.144845 0.0244492 -0.0879665 -0.144868 0.0249565 -0.0876336 -0.145032 0.0221004 -0.0882549 -0.145383 0.02303 -0.0880713 -0.144882 0.0240884 -0.0880749 -0.145658 0.0213873 -0.0880675 -0.146143 0.0213873 -0.087625 -0.14584 0.0231829 -0.0876397 -0.146082 0.0232639 -0.0870455 -0.144967 0.0250371 -0.0874176 -0.144761 0.025379 -0.0873718 -0.14459 0.0265296 -0.0867699 -0.144647 0.0257308 -0.0872636 -0.14471 0.0253374 -0.0875005 -0.144654 0.0256786 -0.0872955 -0.14486 0.0254344 -0.086973 -0.161674 0.0261266 -0.0870199 -0.161656 0.0261361 -0.0868397 -0.16169 0.0265296 -0.0867699 -0.161689 0.0264911 -0.0867938 -0.161419 0.0254344 -0.086973 -0.161518 0.025379 -0.0873718 -0.161411 0.0249565 -0.0876336 -0.160197 0.0232639 -0.0870455 -0.161234 0.0213873 -0.0882592 -0.161327 0.0233513 -0.0881958 -0.160439 0.0231829 -0.0876397 -0.160615 0.0213873 -0.0880636 -0.160896 0.02303 -0.0880713 -0.160642 0.0242698 -0.0870443 -0.161312 0.0250371 -0.0874176 -0.160136 -0.0213874 -0.087625 -0.159888 0.0213873 -0.0870254 -0.160139 -0.0213874 -0.0876282 -0.160136 0.0213873 -0.087625 -0.160615 -0.0213874 -0.0880636 -0.160139 0.0213873 -0.0876282 -0.160622 -0.0213874 -0.0880675 -0.160622 0.0213873 -0.0880675 -0.160959 -0.0232081 -0.0880714 -0.161434 -0.0244493 -0.0879665 -0.160509 -0.0233776 -0.0876399 -0.161312 -0.0250372 -0.0874176 -0.161411 -0.0249566 -0.0876336 -0.161569 -0.0253376 -0.0875005 -0.161689 -0.0265096 -0.0867701 -0.16169 -0.0265297 -0.0867699 -0.161689 -0.0265091 -0.0867826 -0.161658 -0.026149 -0.0868373 -0.161675 -0.0261398 -0.0870118 -0.161482 -0.0248988 -0.0877498 -0.161564 -0.0257716 -0.0869085 -0.161419 -0.0254346 -0.086973 -0.161518 -0.0253792 -0.0873718 -0.161673 0.0257608 -0.0873809 -0.161625 0.0256786 -0.0872955 -0.161632 0.0257308 -0.0872636 -0.161569 0.0253374 -0.0875005 -0.161593 0.0249637 -0.0878394 -0.161465 0.0213873 -0.0883396 -0.161247 0.0221004 -0.0882549 -0.161292 0.0229067 -0.0882298 -0.161397 0.0240884 -0.0880749 -0.161399 0.0241037 -0.0880711 -0.161434 0.0244492 -0.0879665 -0.161482 0.0248987 -0.0877498 -0.161472 0.0221019 -0.0883389 -0.161632 0.0221052 -0.0885183 -0.161644 0.0233854 -0.0884656 -0.161515 0.023364 -0.0882963 -0.161551 0.0241191 -0.0881803 -0.161654 0.0241638 -0.0883331 -0.16157 0.0244932 -0.088069 -0.16169 0.0213873 -0.0887572 -0.16169 0.0234117 -0.0886727 -0.161659 0.024553 -0.0882082 -0.16169 0.0246212 -0.088367 -0.161635 0.0250031 -0.0878937 -0.16169 0.0251368 -0.0880781 -0.161234 -0.0213874 -0.0882592 -0.16163 0.0213873 -0.08852 -0.161465 -0.0213874 -0.0883396 -0.16163 -0.0213874 -0.08852 -0.161632 -0.0221053 -0.0885183 -0.16169 -0.0221095 -0.0887515 -0.16169 -0.0234118 -0.0886727 -0.16169 -0.024216 -0.0885115 -0.16169 -0.0251369 -0.0880781 -0.161644 -0.0233855 -0.0884656 -0.161654 -0.0241639 -0.0883331 -0.161515 -0.0233641 -0.0882963 -0.161551 -0.0241192 -0.0881803 -0.161659 -0.0245531 -0.0882082 -0.161247 -0.0221005 -0.0882549 -0.161472 -0.022102 -0.0883389 -0.161305 -0.0230859 -0.0882186 -0.161327 -0.0233514 -0.0881958 -0.161397 -0.0240885 -0.0880749 -0.16157 -0.0244933 -0.088069 -0.161593 -0.0249638 -0.0878394 -0.161634 -0.0257439 -0.0872557 -0.161625 -0.0256786 -0.0872955 -0.16169 -0.0265314 -0.0867715 -0.161635 -0.0250032 -0.0878937 -0.161665 -0.0250459 -0.0879525 -0.161673 -0.0257609 -0.0873809 -0.14459 0.0264911 -0.0867938 -0.144606 0.0257608 -0.0873809 -0.144605 0.0261266 -0.0870199 -0.144797 0.0248987 -0.0877498 -0.14459 0.0265313 -0.0867715 -0.144644 0.0250031 -0.0878937 -0.14459 0.0251368 -0.0880781 -0.144988 0.0229067 -0.0882298 -0.144807 0.0221019 -0.0883389 -0.145046 0.0213873 -0.0882592 -0.144647 0.0221052 -0.0885183 -0.144635 0.0233854 -0.0884656 -0.14459 0.0242159 -0.0885115 -0.144764 0.023364 -0.0882963 -0.14488 0.0241037 -0.0880711 -0.144728 0.0241191 -0.0881803 -0.144952 0.0233513 -0.0881958 -0.14462 0.024553 -0.0882082 -0.144625 0.0241638 -0.0883331 -0.144709 0.0244932 -0.088069 -0.144686 0.0249637 -0.0878394 -0.14459 0.0213873 -0.0887572 -0.14459 -0.0213874 -0.0887572 -0.144649 -0.0213874 -0.08852 -0.144649 0.0213873 -0.08852 -0.144815 0.0213873 -0.0883396 -0.14462 -0.0245531 -0.0882082 -0.144815 -0.0213874 -0.0883396 -0.145032 -0.0221005 -0.0882549 -0.144728 -0.0241192 -0.0881803 -0.144882 -0.0240885 -0.0880749 -0.144647 -0.0221053 -0.0885183 -0.144807 -0.022102 -0.0883389 -0.144764 -0.0233641 -0.0882963 -0.144709 -0.0244933 -0.088069 -0.144644 -0.0250032 -0.0878937 -0.14459 -0.0221095 -0.0887515 -0.144635 -0.0233855 -0.0884656 -0.14459 -0.0234118 -0.0886727 -0.14459 -0.024216 -0.0885115 -0.144625 -0.0241639 -0.0883331 -0.14459 -0.0246213 -0.088367 -0.144614 -0.0250459 -0.0879525 -0.144654 -0.0256786 -0.0872955 -0.144605 -0.0261306 -0.0870175 -0.144606 -0.0257609 -0.0873809 -0.14459 -0.0265314 -0.0867715 -0.14459 -0.0265376 -0.086765 -0.14459 -0.0251369 -0.0880781 -0.14471 -0.0253375 -0.0875005 -0.144686 -0.0249638 -0.0878394 -0.144797 -0.0248988 -0.0877498 -0.14856 -0.0375623 -0.0892735 -0.14856 -0.0376193 -0.0890488 -0.148556 -0.0376194 -0.0890488 -0.14856 -0.0374221 -0.0894618 -0.148635 -0.0374172 -0.0894563 -0.14905 -0.0373052 -0.0891515 -0.14905 -0.0372315 -0.0892505 -0.148893 -0.0373452 -0.0893765 -0.148841 -0.0374893 -0.0892389 -0.148841 -0.037368 -0.0894018 -0.148871 -0.0360319 -0.0905473 -0.148619 -0.0367618 -0.090043 -0.148595 -0.0360946 -0.0906216 -0.14914 -0.0369667 -0.089065 -0.149072 -0.036552 -0.0898039 -0.14914 -0.0357093 -0.090165 -0.148356 -0.0374031 -0.0894407 -0.1486 -0.0360942 -0.0906212 -0.148885 -0.0366934 -0.089965 -0.148874 -0.0360306 -0.0905458 -0.149074 -0.0372026 -0.0892184 -0.148312 -0.0360673 -0.0905892 -0.148595 -0.0357093 -0.0907624 -0.148595 -0.0359144 -0.0907261 -0.149068 -0.0357093 -0.0904489 -0.149059 -0.0357093 -0.090465 -0.148871 -0.035881 -0.0906348 -0.148871 -0.0357093 -0.0906652 -0.14884 -0.0357093 -0.0906846 -0.149068 -0.0358068 -0.0904317 -0.149069 -0.0358914 -0.0903808 -0.14914 -0.0319 -0.090165 -0.14884 -0.0319 -0.0906846 -0.14854 -0.0319 -0.090765 -0.149059 -0.0319 -0.090465 -0.149814 -0.0296778 -0.090165 -0.150917 -0.0285742 -0.090165 -0.152344 -0.0278981 -0.090465 -0.15314 -0.0278197 -0.090465 -0.15392 -0.0279769 -0.090165 -0.154701 -0.0281303 -0.090465 -0.155362 -0.0285742 -0.090165 -0.155407 -0.0285073 -0.090465 -0.156025 -0.0290148 -0.090465 -0.156835 -0.0303693 -0.090165 -0.156909 -0.0303385 -0.090465 -0.157142 -0.031104 -0.090465 -0.149138 -0.031104 -0.090465 -0.148922 -0.0310612 -0.0906846 -0.149167 -0.0302545 -0.0906846 -0.14937 -0.0303385 -0.090465 -0.149747 -0.0296331 -0.090465 -0.150254 -0.0290148 -0.090465 -0.150873 -0.0285073 -0.090465 -0.151578 -0.0281303 -0.090465 -0.153936 -0.0278981 -0.090465 -0.154785 -0.0279274 -0.0906846 -0.15618 -0.0288595 -0.0906846 -0.156532 -0.0296331 -0.090465 -0.148628 -0.0310026 -0.090765 -0.149564 -0.0295111 -0.0906846 -0.149315 -0.0293444 -0.090765 -0.150099 -0.0288595 -0.0906846 -0.150751 -0.0283247 -0.0906846 -0.150584 -0.0280753 -0.090765 -0.151494 -0.0279274 -0.0906846 -0.151379 -0.0276502 -0.090765 -0.152301 -0.0276827 -0.0906846 -0.15314 -0.0276 -0.0906846 -0.153978 -0.0276827 -0.0906846 -0.155529 -0.0283247 -0.0906846 -0.156392 -0.0286474 -0.090765 -0.156715 -0.0295111 -0.0906846 -0.157389 -0.0301397 -0.090765 -0.157112 -0.0302545 -0.0906846 -0.157357 -0.0310612 -0.0906846 -0.157211 -0.0357093 -0.0904489 -0.15722 -0.0319 -0.090465 -0.157408 -0.0357093 -0.0906652 -0.15744 -0.0319 -0.0906846 -0.157863 -0.035903 -0.0907193 -0.157684 -0.0357093 -0.0907624 -0.157408 -0.035881 -0.0906348 -0.157684 -0.0359144 -0.0907261 -0.15744 -0.0357093 -0.0906846 -0.15722 -0.0357093 -0.090465 -0.157211 -0.0358068 -0.0904317 -0.15714 -0.0363696 -0.089596 -0.15714 -0.0369667 -0.089065 -0.157943 -0.0367419 -0.0900203 -0.157719 -0.0374221 -0.0894618 -0.157438 -0.037368 -0.0894018 -0.157395 -0.0366934 -0.089965 -0.157229 -0.0372315 -0.0892505 -0.157141 -0.0370497 -0.0890488 -0.15714 -0.0357093 -0.090165 -0.15721 -0.0358914 -0.0903808 -0.157207 -0.036552 -0.0898039 -0.157405 -0.0360306 -0.0905458 -0.15766 -0.0367618 -0.090043 -0.157679 -0.0360942 -0.0906212 -0.157684 -0.0360946 -0.0906216 -0.157923 -0.0374031 -0.0894407 -0.157979 -0.0375204 -0.089246 -0.157228 -0.037332 -0.0890488 -0.157229 -0.037334 -0.0890488 -0.157644 -0.0374172 -0.0894563 -0.157719 -0.0375623 -0.0892734 -0.157438 -0.0374894 -0.0892388 -0.157386 -0.0373452 -0.0893765 -0.157229 -0.0373052 -0.0891515 -0.157205 -0.0372026 -0.0892184 -0.157228 0.037332 -0.0890488 -0.157205 0.0372025 -0.0892184 -0.157229 0.0373051 -0.0891515 -0.157229 0.0373339 -0.0890488 -0.157438 0.0374893 -0.0892389 -0.157439 0.0375386 -0.0890488 -0.157978 0.0375178 -0.0892525 -0.157999 0.0375607 -0.0890488 -0.157719 0.0375622 -0.0892735 -0.157386 0.0373451 -0.0893765 -0.157438 0.0373679 -0.0894018 -0.157644 0.0374171 -0.0894563 -0.157967 0.0360672 -0.0905892 -0.15721 0.0358913 -0.0903808 -0.157395 0.0366933 -0.089965 -0.157405 0.0360305 -0.0905458 -0.157719 0.037422 -0.0894618 -0.15766 0.0367617 -0.090043 -0.15714 0.0369666 -0.089065 -0.157207 0.0365519 -0.0898039 -0.157229 0.0372315 -0.0892505 -0.15774 0.0357092 -0.090765 -0.157867 0.0359102 -0.0907157 -0.15744 0.0357092 -0.0906846 -0.157684 0.0357092 -0.0907624 -0.157684 0.0360945 -0.0906216 -0.157679 0.0360942 -0.0906212 -0.157684 0.0359143 -0.0907261 -0.157211 0.0357092 -0.0904489 -0.157408 0.0358809 -0.0906348 -0.15722 0.0357092 -0.090465 -0.157408 0.0357092 -0.0906652 -0.157408 0.0360318 -0.0905473 -0.157211 0.0358067 -0.0904317 -0.15714 0.0357092 -0.090165 -0.157142 0.0311039 -0.090465 -0.15714 0.0319 -0.090165 -0.15722 0.0319 -0.090465 -0.156532 0.029633 -0.090465 -0.156465 0.0296777 -0.090165 -0.155968 0.0290715 -0.090165 -0.156025 0.0290147 -0.090465 -0.155407 0.0285072 -0.090465 -0.154701 0.0281302 -0.090465 -0.15467 0.0282044 -0.090165 -0.15392 0.0279768 -0.090165 -0.153936 0.027898 -0.090465 -0.152359 0.0279768 -0.090165 -0.152344 0.027898 -0.090465 -0.151578 0.0281302 -0.090465 -0.150873 0.0285072 -0.090465 -0.150311 0.0290715 -0.090165 -0.150254 0.0290147 -0.090465 -0.149814 0.0296777 -0.090165 -0.149138 0.0311039 -0.090465 -0.149059 0.0319 -0.090465 -0.15744 0.0319 -0.0906846 -0.156909 0.0303385 -0.090465 -0.157357 0.0310611 -0.0906846 -0.157112 0.0302544 -0.0906846 -0.15314 0.0276 -0.0906846 -0.15314 0.0278196 -0.090465 -0.150751 0.0283246 -0.0906846 -0.150099 0.0288594 -0.0906846 -0.149747 0.029633 -0.090465 -0.14937 0.0303385 -0.090465 -0.149564 0.029511 -0.0906846 -0.149167 0.0302544 -0.0906846 -0.14884 0.0319 -0.0906846 -0.157651 0.0310025 -0.090765 -0.157389 0.0301396 -0.090765 -0.156715 0.029511 -0.0906846 -0.156964 0.0293443 -0.090765 -0.15618 0.0288594 -0.0906846 -0.155529 0.0283246 -0.0906846 -0.155695 0.0280752 -0.090765 -0.154785 0.0279273 -0.0906846 -0.1549 0.0276501 -0.090765 -0.153978 0.0276826 -0.0906846 -0.152301 0.0276826 -0.0906846 -0.151494 0.0279273 -0.0906846 -0.151379 0.0276501 -0.090765 -0.150584 0.0280752 -0.090765 -0.149887 0.0286473 -0.090765 -0.14889 0.0301396 -0.090765 -0.148922 0.0310611 -0.0906846 -0.148628 0.0310025 -0.090765 -0.149068 0.0357092 -0.0904489 -0.149059 0.0357092 -0.090465 -0.148871 0.0357092 -0.0906652 -0.148595 0.0357092 -0.0907624 -0.148416 0.0359029 -0.0907193 -0.149068 0.0358067 -0.0904317 -0.148874 0.0360305 -0.0905458 -0.1486 0.0360942 -0.0906212 -0.148595 0.0359143 -0.0907261 -0.148412 0.0359102 -0.0907157 -0.14884 0.0357092 -0.0906846 -0.148871 0.0358809 -0.0906348 -0.149072 0.0365519 -0.0898039 -0.14914 0.0369666 -0.089065 -0.148356 0.037403 -0.0894407 -0.14856 0.037422 -0.0894618 -0.148619 0.0367617 -0.090043 -0.148841 0.0373679 -0.0894018 -0.14905 0.0372315 -0.0892505 -0.149069 0.0358913 -0.0903808 -0.148885 0.0366933 -0.089965 -0.148595 0.0360945 -0.0906216 -0.148312 0.0360672 -0.0905892 -0.14856 0.0376192 -0.0890488 -0.148301 0.0375179 -0.0892525 -0.14856 0.0375622 -0.0892734 -0.14905 0.0373051 -0.0891515 -0.148635 0.0374171 -0.0894563 -0.148841 0.0374893 -0.0892388 -0.148893 0.0373451 -0.0893765 -0.149074 0.0372025 -0.0892184 -0.149325 0.0369666 -0.0887878 -0.149437 0.0370642 -0.088765 -0.14929 0.0369666 -0.0888052 -0.14918 0.0369666 -0.088915 -0.149162 0.0369666 -0.0889502 -0.149227 0.0369666 -0.0888528 -0.148336 0.037585 -0.0890361 -0.148303 0.0375711 -0.0890435 -0.148274 0.0375579 -0.089045 -0.14884 0.0375386 -0.0890488 -0.148556 0.0376193 -0.0890488 -0.148443 0.037618 -0.089002 -0.149183 0.0374122 -0.0888025 -0.148863 0.0375778 -0.0889057 -0.14905 0.0373339 -0.0890488 -0.149051 0.037332 -0.0890488 -0.149138 0.0370496 -0.0890488 -0.14909 0.0373555 -0.0889057 -0.149165 0.0370509 -0.088939 -0.14899 0.0376197 -0.0888046 -0.149183 0.0370518 -0.0889057 -0.149231 0.0370542 -0.0888472 -0.149292 0.0370571 -0.0888025 -0.149307 0.0374877 -0.088765 -0.149326 0.0370588 -0.0887863 -0.149256 0.0311274 -0.088915 -0.149814 0.0296777 -0.089065 -0.15034 0.0291 -0.088915 -0.150311 0.0290715 -0.089065 -0.150917 0.0285741 -0.089065 -0.151609 0.0282044 -0.089065 -0.152367 0.0280162 -0.088915 -0.15314 0.0279 -0.089065 -0.15467 0.0282044 -0.089065 -0.154655 0.0282416 -0.088915 -0.15534 0.0286075 -0.088915 -0.15594 0.0291 -0.088915 -0.156465 0.0296777 -0.089065 -0.157063 0.0311196 -0.089065 -0.14918 0.0319 -0.088915 -0.149481 0.0303846 -0.088915 -0.149938 0.029761 -0.0888052 -0.149847 0.0297 -0.088915 -0.15094 0.0286075 -0.088915 -0.151666 0.028343 -0.0888052 -0.151624 0.0282416 -0.088915 -0.15314 0.0279402 -0.088915 -0.15314 0.02805 -0.0888052 -0.153912 0.0280162 -0.088915 -0.154613 0.028343 -0.0888052 -0.155862 0.0291776 -0.0888052 -0.156432 0.0297 -0.088915 -0.156798 0.0303846 -0.088915 -0.157023 0.0311274 -0.088915 -0.14944 0.0319 -0.088765 -0.14929 0.0319 -0.0888052 -0.149364 0.0311489 -0.0888052 -0.149511 0.0311781 -0.088765 -0.149583 0.0304266 -0.0888052 -0.150063 0.0298443 -0.088765 -0.150417 0.0291776 -0.0888052 -0.151084 0.0288235 -0.088765 -0.151724 0.0284816 -0.088765 -0.151001 0.0286988 -0.0888052 -0.152388 0.0281239 -0.0888052 -0.152418 0.0282711 -0.088765 -0.153891 0.0281239 -0.0888052 -0.154555 0.0284816 -0.088765 -0.155195 0.0288235 -0.088765 -0.155279 0.0286988 -0.0888052 -0.155756 0.0292837 -0.088765 -0.156216 0.0298443 -0.088765 -0.156341 0.029761 -0.0888052 -0.156696 0.0304266 -0.0888052 -0.156916 0.0311489 -0.0888052 -0.149134 0.0378748 -0.0885798 -0.148273 0.0375578 -0.0890399 -0.148265 0.0375539 -0.0890326 -0.148262 0.0375528 -0.0890233 -0.148261 0.0375522 -0.0890164 -0.148685 0.0376425 -0.088915 -0.148558 0.0376373 -0.0889615 -0.148843 0.0376873 -0.0887991 -0.148487 0.0376352 -0.0889552 -0.148517 0.0376321 -0.0889762 -0.148422 0.0376169 -0.0889866 -0.148355 0.0375933 -0.0890183 -0.148365 0.0375957 -0.0890276 -0.1483 0.0375703 -0.0890381 -0.148286 0.0375635 -0.0890451 -0.148894 0.0376285 -0.0888371 -0.149072 0.0376142 -0.0887826 -0.149217 0.0376105 -0.088765 -0.148285 0.0375635 -0.0890401 -0.148297 0.0375693 -0.0890327 -0.148329 0.0375831 -0.0890289 -0.148344 0.0375903 -0.0890089 -0.148788 0.0377271 -0.0887453 -0.148983 0.0377737 -0.0886855 -0.149029 0.0377041 -0.0887493 -0.148274 0.0375585 -0.0890349 -0.148275 0.037559 -0.0890299 -0.148284 0.0375631 -0.0890301 -0.148284 0.0375633 -0.0890351 -0.148322 0.0375808 -0.0890217 -0.148402 0.0376136 -0.088971 -0.148382 0.0376082 -0.088955 -0.148458 0.037634 -0.0889332 -0.14843 0.0376286 -0.0889105 -0.148939 0.0378144 -0.0885989 -0.149139 0.0378582 -0.088615 -0.148268 0.0375555 -0.0890214 -0.148265 0.0375541 -0.0890268 -0.148276 0.0375595 -0.0890249 -0.148283 0.0375629 -0.0890251 -0.148294 0.0375682 -0.0890273 -0.148316 0.0375782 -0.0890145 -0.148292 0.037567 -0.0890219 -0.148334 0.0375866 -0.0889996 -0.148324 0.0375823 -0.0889902 -0.148364 0.0376008 -0.088939 -0.148733 0.0377447 -0.0886802 -0.148403 0.0376189 -0.0888875 -0.148684 0.0377386 -0.0886092 -0.148904 0.0378213 -0.0885001 -0.157117 0.0369666 -0.0889502 -0.15714 0.0319 -0.089065 -0.157099 0.0369666 -0.088915 -0.157099 0.0319 -0.088915 -0.15684 0.0319 -0.088765 -0.156954 0.0369666 -0.0887878 -0.15699 0.0369666 -0.0888052 -0.15699 0.0319 -0.0888052 -0.149183 0.03772 -0.0887421 -0.149127 0.0378965 -0.088465 -0.150119 0.0379754 -0.0887248 -0.149172 0.0377535 -0.0887248 -0.150103 0.0380839 -0.088615 -0.149153 0.0378128 -0.0886771 -0.15109 0.0381771 -0.0885798 -0.156953 0.0370588 -0.0887863 -0.157052 0.0369666 -0.0888528 -0.157096 0.0370518 -0.0889057 -0.157141 0.0370496 -0.0890488 -0.15109 0.0379 -0.088765 -0.15109 0.0380148 -0.0887421 -0.15109 0.03805 -0.0887248 -0.15519 0.0380148 -0.0887421 -0.15109 0.0381121 -0.0886771 -0.15519 0.0381121 -0.0886771 -0.15109 0.0381598 -0.088615 -0.15519 0.0381598 -0.088615 -0.15109 0.0382 -0.088465 -0.157289 0.0376197 -0.0888046 -0.157062 0.0376105 -0.088765 -0.157976 0.0375711 -0.0890435 -0.157723 0.0376193 -0.0890488 -0.157914 0.0375957 -0.0890276 -0.157721 0.0376373 -0.0889615 -0.157719 0.0376192 -0.0890488 -0.157416 0.0375778 -0.0889057 -0.157114 0.0370509 -0.088939 -0.157048 0.0370542 -0.0888472 -0.157189 0.0373555 -0.0889057 -0.157096 0.0374122 -0.0888025 -0.156987 0.0370571 -0.0888025 -0.15616 0.0379754 -0.0887248 -0.15519 0.0379 -0.088765 -0.156176 0.0380839 -0.088615 -0.15519 0.0381771 -0.0885798 -0.15519 0.03805 -0.0887248 -0.157126 0.0378128 -0.0886771 -0.157145 0.0378748 -0.0885798 -0.158004 0.037559 -0.0890299 -0.157995 0.0375631 -0.0890301 -0.157993 0.0375635 -0.0890451 -0.157943 0.037585 -0.0890361 -0.157857 0.0376169 -0.0889866 -0.157836 0.037618 -0.089002 -0.157763 0.0376321 -0.0889762 -0.157437 0.0376873 -0.0887991 -0.157594 0.0376425 -0.088915 -0.157792 0.0376352 -0.0889552 -0.158003 0.0375595 -0.0890249 -0.157987 0.037567 -0.0890219 -0.157963 0.0375782 -0.0890145 -0.15797 0.0375752 -0.0890073 -0.157945 0.0375866 -0.0889996 -0.157897 0.0376082 -0.088955 -0.157876 0.0376189 -0.0888875 -0.157546 0.0377447 -0.0886802 -0.157376 0.0378213 -0.0885001 -0.157152 0.0378965 -0.088465 -0.15734 0.0378144 -0.0885989 -0.158005 0.0375585 -0.0890349 -0.157995 0.0375633 -0.0890351 -0.157982 0.0375693 -0.0890327 -0.157985 0.0375682 -0.0890273 -0.157935 0.0375903 -0.0890089 -0.157877 0.0376136 -0.088971 -0.157849 0.0376286 -0.0889105 -0.15714 0.0378582 -0.088615 -0.158011 0.0375555 -0.0890214 -0.158016 0.037553 -0.0890255 -0.158014 0.0375541 -0.0890268 -0.158006 0.0375578 -0.0890399 -0.157994 0.0375635 -0.0890401 -0.157979 0.0375703 -0.0890381 -0.157957 0.0375808 -0.0890217 -0.15795 0.0375831 -0.0890289 -0.157924 0.0375933 -0.0890183 -0.157821 0.037634 -0.0889332 -0.157491 0.0377271 -0.0887453 -0.157297 0.0377737 -0.0886855 -0.157107 0.0377535 -0.0887248 -0.157386 0.0376286 -0.0888374 -0.15725 0.0377041 -0.0887493 -0.157207 0.0376142 -0.0887826 -0.157096 0.03772 -0.0887421 -0.156842 -0.0370643 -0.088765 -0.156954 -0.0369667 -0.0887878 -0.156953 -0.0370589 -0.0887863 -0.15699 -0.0369667 -0.0888052 -0.157048 -0.0370542 -0.0888472 -0.157099 -0.0369667 -0.088915 -0.157117 -0.0369667 -0.0889502 -0.157099 -0.0319 -0.088915 -0.157052 -0.0369667 -0.0888528 -0.15699 -0.0319 -0.0888052 -0.157836 -0.0376181 -0.089002 -0.157723 -0.0376194 -0.0890488 -0.157943 -0.0375851 -0.0890361 -0.157976 -0.0375712 -0.0890435 -0.157594 -0.0376426 -0.088915 -0.157719 -0.0376193 -0.0890488 -0.157763 -0.0376322 -0.0889762 -0.157096 -0.0374123 -0.0888025 -0.157439 -0.0375387 -0.0890488 -0.157189 -0.0373556 -0.0889057 -0.157114 -0.037051 -0.088939 -0.157416 -0.0375779 -0.0889057 -0.157096 -0.0370519 -0.0889057 -0.156987 -0.0370572 -0.0888025 -0.15714 -0.0319 -0.089065 -0.157063 -0.0311197 -0.089065 -0.156432 -0.0297001 -0.088915 -0.156835 -0.0303693 -0.089065 -0.15392 -0.0279769 -0.089065 -0.15314 -0.0279402 -0.088915 -0.152367 -0.0280163 -0.088915 -0.15314 -0.0279 -0.089065 -0.152359 -0.0279769 -0.089065 -0.151609 -0.0282045 -0.089065 -0.150917 -0.0285742 -0.089065 -0.15034 -0.0291 -0.088915 -0.150311 -0.0290716 -0.089065 -0.149444 -0.0303693 -0.089065 -0.149256 -0.0311275 -0.088915 -0.14918 -0.0319 -0.088915 -0.157023 -0.0311275 -0.088915 -0.156696 -0.0304267 -0.0888052 -0.156798 -0.0303847 -0.088915 -0.155279 -0.0286989 -0.0888052 -0.15594 -0.0291 -0.088915 -0.15534 -0.0286076 -0.088915 -0.154655 -0.0282417 -0.088915 -0.153891 -0.028124 -0.0888052 -0.15314 -0.02805 -0.0888052 -0.153912 -0.0280163 -0.088915 -0.152388 -0.028124 -0.0888052 -0.151624 -0.0282417 -0.088915 -0.151001 -0.0286989 -0.0888052 -0.15094 -0.0286076 -0.088915 -0.149583 -0.0304267 -0.0888052 -0.149847 -0.0297001 -0.088915 -0.149481 -0.0303847 -0.088915 -0.149364 -0.0311489 -0.0888052 -0.15684 -0.0319 -0.088765 -0.156916 -0.0311489 -0.0888052 -0.156558 -0.0304841 -0.088765 -0.156216 -0.0298444 -0.088765 -0.156341 -0.0297611 -0.0888052 -0.155862 -0.0291777 -0.0888052 -0.154613 -0.0283431 -0.0888052 -0.15314 -0.0282 -0.088765 -0.151666 -0.0283431 -0.0888052 -0.150523 -0.0292837 -0.088765 -0.150417 -0.0291777 -0.0888052 -0.149938 -0.0297611 -0.0888052 -0.14929 -0.0319 -0.0888052 -0.158005 -0.037558 -0.089045 -0.158015 -0.0375536 -0.0890299 -0.157721 -0.0376374 -0.0889615 -0.157802 -0.0376354 -0.088948 -0.157864 -0.0376161 -0.0889814 -0.157914 -0.0375958 -0.0890276 -0.157993 -0.0375636 -0.0890451 -0.157386 -0.0376287 -0.0888374 -0.157455 -0.0377029 -0.0887827 -0.157289 -0.0376198 -0.0888046 -0.157207 -0.0376142 -0.0887826 -0.158005 -0.0375581 -0.0890383 -0.157994 -0.0375635 -0.0890384 -0.15798 -0.03757 -0.0890363 -0.157952 -0.0375824 -0.0890265 -0.157928 -0.0375925 -0.0890152 -0.157942 -0.037588 -0.0890027 -0.15784 -0.0376309 -0.0889181 -0.157266 -0.0377301 -0.0887311 -0.157326 -0.0378045 -0.0886297 -0.157107 -0.0377536 -0.0887248 -0.158016 -0.0375533 -0.0890279 -0.158004 -0.0375589 -0.0890316 -0.158003 -0.0375596 -0.0890249 -0.157995 -0.0375633 -0.0890318 -0.157996 -0.037563 -0.0890251 -0.157987 -0.0375671 -0.0890219 -0.157984 -0.0375687 -0.0890291 -0.157961 -0.0375792 -0.0890169 -0.157955 -0.0375824 -0.0889902 -0.15789 -0.0376103 -0.0889604 -0.157528 -0.0377415 -0.0887029 -0.157876 -0.037619 -0.0888875 -0.149162 -0.0369667 -0.0889502 -0.15519 -0.0379 -0.088765 -0.15714 -0.0378583 -0.088615 -0.15616 -0.0379755 -0.0887248 -0.15519 -0.03805 -0.0887248 -0.15519 -0.0381122 -0.0886771 -0.156176 -0.038084 -0.088615 -0.15519 -0.0381599 -0.088615 -0.156183 -0.0381237 -0.088465 -0.15519 -0.0382 -0.088465 -0.149325 -0.0369667 -0.0887878 -0.149292 -0.0370572 -0.0888025 -0.14929 -0.0369667 -0.0888052 -0.149227 -0.0369667 -0.0888528 -0.149231 -0.0370542 -0.0888472 -0.149183 -0.0370519 -0.0889057 -0.14918 -0.0369667 -0.088915 -0.15109 -0.0379 -0.088765 -0.15109 -0.0381122 -0.0886771 -0.14899 -0.0376198 -0.0888046 -0.149072 -0.0376142 -0.0887826 -0.148274 -0.037558 -0.089045 -0.148281 -0.0375608 -0.0890488 -0.148286 -0.0375636 -0.0890451 -0.148365 -0.0375958 -0.0890276 -0.149165 -0.037051 -0.088939 -0.148443 -0.0376181 -0.089002 -0.148517 -0.0376322 -0.0889762 -0.148558 -0.0376374 -0.0889615 -0.148685 -0.0376426 -0.088915 -0.14884 -0.0375387 -0.0890488 -0.14905 -0.037334 -0.0890488 -0.148863 -0.0375779 -0.0889057 -0.14909 -0.0373556 -0.0889057 -0.149051 -0.037332 -0.0890488 -0.149138 -0.0370497 -0.0890488 -0.149183 -0.0374123 -0.0888025 -0.149326 -0.0370589 -0.0887863 -0.149307 -0.0374878 -0.088765 -0.149437 -0.0370643 -0.088765 -0.150142 -0.0378273 -0.088765 -0.150125 -0.0379407 -0.0887421 -0.15109 -0.0380148 -0.0887421 -0.15011 -0.0380369 -0.0886771 -0.15109 -0.0381772 -0.0885798 -0.15109 -0.0382 -0.088465 -0.149217 -0.0376106 -0.088765 -0.149183 -0.0377201 -0.0887421 -0.1501 -0.0381012 -0.0885798 -0.149134 -0.0378748 -0.0885798 -0.148894 -0.0376286 -0.0888371 -0.148274 -0.0375585 -0.0890349 -0.148269 -0.0375558 -0.0890404 -0.148303 -0.0375712 -0.0890435 -0.148336 -0.0375851 -0.0890361 -0.148422 -0.0376169 -0.0889866 -0.148487 -0.0376353 -0.0889552 -0.148275 -0.0375591 -0.0890299 -0.148283 -0.037563 -0.0890251 -0.148284 -0.0375632 -0.0890301 -0.148292 -0.0375671 -0.0890219 -0.148294 -0.0375683 -0.0890273 -0.148324 -0.0375824 -0.0889902 -0.148364 -0.0376009 -0.088939 -0.148403 -0.037619 -0.0888875 -0.14843 -0.0376286 -0.0889105 -0.148733 -0.0377448 -0.0886802 -0.148316 -0.0375783 -0.0890145 -0.148334 -0.0375867 -0.0889996 -0.148402 -0.0376137 -0.088971 -0.148382 -0.0376083 -0.088955 -0.148458 -0.0376341 -0.0889332 -0.148263 -0.037553 -0.0890255 -0.148265 -0.0375542 -0.0890268 -0.148273 -0.0375579 -0.0890399 -0.148284 -0.0375634 -0.0890351 -0.148285 -0.0375635 -0.0890401 -0.148297 -0.0375694 -0.0890327 -0.1483 -0.0375703 -0.0890381 -0.148322 -0.0375809 -0.0890217 -0.148344 -0.0375904 -0.0890089 -0.148329 -0.0375831 -0.0890289 -0.148355 -0.0375934 -0.0890183 -0.148843 -0.0376873 -0.0887991 -0.148983 -0.0377738 -0.0886855 -0.148788 -0.0377272 -0.0887453 -0.148684 -0.0377387 -0.0886092 -0.149153 -0.0378128 -0.0886771 -0.149029 -0.0377042 -0.0887493 -0.148939 -0.0378145 -0.0885989 -0.148904 -0.0378214 -0.0885001 -0.151191 0.033025 -0.088765 -0.15089 0.0319 -0.084765 -0.154265 0.0299514 -0.088765 -0.155088 0.030775 -0.084765 -0.15539 0.0319 -0.084765 -0.15539 0.0319 -0.088765 -0.155088 0.033025 -0.084765 -0.154265 0.0338485 -0.088765 -0.15314 -0.03415 -0.084765 -0.154265 -0.0338486 -0.084765 -0.155088 -0.033025 -0.088765 -0.15539 -0.0319 -0.084765 -0.155088 -0.030775 -0.084765 -0.154265 -0.0299515 -0.084765 -0.15314 -0.02965 -0.088765 -0.15649 0.0142 -0.072765 -0.15729 0.0232 -0.074963 -0.15729 0.0142 -0.074963 -0.154576 0.026064 -0.072765 -0.155582 0.025392 -0.072765 -0.156147 0.0259577 -0.074963 -0.156254 0.0243863 -0.072765 -0.156993 0.0246924 -0.074963 -0.15649 0.0232 -0.072765 -0.156993 0.0127075 -0.074963 -0.156254 0.0130136 -0.072765 -0.155582 0.0120079 -0.072765 -0.154882 0.0105968 -0.074963 -0.154576 0.0113359 -0.072765 -0.15339 0.0263 -0.072765 -0.15339 0.0271 -0.074963 -0.15339 0.0103 -0.074963 -0.14979 0.0232 -0.072765 -0.150026 0.0243863 -0.072765 -0.151703 0.026064 -0.072765 -0.15289 0.0111 -0.072765 -0.150026 0.0130136 -0.072765 -0.14899 0.0142 -0.074963 -0.15659 -0.00230004 -0.072765 -0.154982 0.00630309 -0.074963 -0.156247 0.00545767 -0.074963 -0.155682 0.00489199 -0.072765 -0.157093 0.00419242 -0.074963 -0.156354 0.00388628 -0.072765 -0.15739 0.00269996 -0.074963 -0.156247 -0.00505776 -0.074963 -0.156354 -0.00348636 -0.072765 -0.155682 -0.00449207 -0.072765 -0.15349 -0.00620004 -0.074963 -0.149186 0.00419242 -0.074963 -0.149926 0.00388628 -0.072765 -0.151297 0.00630309 -0.074963 -0.15279 -0.00620004 -0.074963 -0.151603 -0.00516407 -0.072765 -0.150598 -0.00449207 -0.072765 -0.150032 -0.00505776 -0.074963 -0.149926 -0.00348636 -0.072765 -0.14969 -0.00230004 -0.072765 -0.14889 -0.00230004 -0.074963 -0.15634 -0.0138 -0.072765 -0.15714 -0.0138 -0.074963 -0.154732 -0.0101969 -0.074963 -0.155432 -0.011608 -0.072765 -0.156104 -0.0126137 -0.072765 -0.15634 -0.0232 -0.072765 -0.156843 -0.0246925 -0.074963 -0.155432 -0.0253921 -0.072765 -0.155997 -0.0259578 -0.074963 -0.15324 -0.0271 -0.074963 -0.149436 -0.0123076 -0.074963 -0.15304 -0.0263 -0.072765 -0.151853 -0.0260641 -0.072765 -0.151547 -0.0268032 -0.074963 -0.150282 -0.0259578 -0.074963 -0.150848 -0.0253921 -0.072765 -0.14914 -0.0232 -0.074963 -0.14994 -0.0138 -0.072765 0.0408268 0.148835 0.00800953 0.0391735 0.151835 0.00784669 0.0391735 0.148835 0.00784669 0.0375838 0.151835 0.00736444 0.0361186 0.151835 0.00658132 0.0348344 0.151835 0.00552741 0.0337805 0.148835 0.00424321 0.0325152 0.151835 0.00118833 0.0323523 0.148835 -0.000464957 0.0325152 0.151835 -0.00211825 0.0325152 0.148835 -0.00211825 0.0329974 0.151835 -0.003708 0.0329974 0.148835 -0.003708 0.0337805 0.151835 -0.00517313 0.0348344 0.151835 -0.00645732 0.0361186 0.151835 -0.00751123 0.0361186 0.148835 -0.00751123 0.0375838 0.151835 -0.00829436 0.0375838 0.148835 -0.00829436 0.0391735 0.151835 -0.0087766 0.0408268 0.151835 -0.00893944 0.0408268 0.148835 -0.00893944 0.0424801 0.148835 -0.0087766 0.0424801 0.151835 -0.0087766 0.045535 0.151835 -0.00751123 0.0468192 0.148835 -0.00645732 0.0478731 0.151835 -0.00517313 0.0486562 0.151835 -0.003708 0.0486562 0.148835 -0.003708 0.0493013 0.148835 -0.000464957 0.0486562 0.151835 0.00277809 0.0478731 0.151835 0.00424321 0.0478731 0.148835 0.00424321 0.045535 0.151835 0.00658132 0.0468192 0.148835 0.00552741 0.045535 0.148835 0.00658132 0.0440698 0.151835 0.00736444 0.0440698 0.148835 0.00736444 0.0424801 0.151835 0.00784669 0.0440698 0.151835 -0.00829436 0.0491384 0.151835 -0.00211825 0.0468192 0.151835 -0.00645732 0.0491384 0.151835 0.00118833 0.0493013 0.151835 -0.000464957 0.0468192 0.151835 0.00552741 0.0408268 0.151835 -0.000464957 0.0408268 0.151835 0.00800953 0.0329974 0.151835 0.00277809 0.0337805 0.151835 0.00424321 0.0323523 0.151835 -0.000464957 0.0526371 0.148835 0.000513671 0.0491384 0.148835 -0.00211825 0.0478731 0.148835 -0.00517313 0.0290165 0.148835 0.000513671 0.0325152 0.148835 0.00118833 0.0329974 0.148835 0.00277809 0.0309057 0.148835 0.00601679 0.0348344 0.148835 0.00552741 0.0321079 0.148835 0.00756135 0.0481057 0.148835 0.00888696 0.0495457 0.148835 0.00756135 0.0516794 0.148835 0.00429544 0.0486562 0.148835 0.00277809 0.0491384 0.148835 0.00118833 0.0351865 0.148835 -0.0108874 0.0348344 0.148835 -0.00645732 0.0337805 0.148835 -0.00517313 0.0309057 0.148835 -0.00694671 0.0293387 0.148835 -0.00337415 0.0290165 0.148835 -0.00144359 0.045535 0.148835 -0.00751123 0.0440698 0.148835 -0.00829436 0.0464671 0.148835 -0.0108874 0.0446747 0.148835 -0.0116736 0.0391735 0.148835 -0.0087766 0.0408268 0.148835 -0.0123157 0.0388762 0.148835 -0.0121541 0.0369789 0.148835 -0.0116736 0.0361186 0.148835 0.00658132 0.0335479 0.148835 0.00888696 0.0351865 0.148835 0.00995748 0.0375838 0.148835 0.00736444 0.0369789 0.148835 0.0107437 0.0424801 0.148835 0.00784669 0.0335479 0.145835 -0.00981687 0.0335479 0.148835 -0.00981687 0.0321079 0.145835 -0.00849126 0.0321079 0.148835 -0.00849126 0.0299742 0.145835 -0.00522535 0.0299742 0.148835 -0.00522535 0.0293387 0.148835 0.00244423 0.0299742 0.148835 0.00429544 0.0309057 0.145835 0.00601679 0.0321079 0.145835 0.00756135 0.0335479 0.145835 0.00888696 0.0388762 0.145835 0.0112242 0.0388762 0.148835 0.0112242 0.0408268 0.148835 0.0113858 0.0427774 0.148835 0.0112242 0.0446747 0.148835 0.0107437 0.0446747 0.145835 0.0107437 0.0464671 0.145835 0.00995748 0.0464671 0.148835 0.00995748 0.0495457 0.145835 0.00756135 0.0507479 0.145835 0.00601679 0.0507479 0.148835 0.00601679 0.0523149 0.148835 0.00244423 0.0526371 0.145835 -0.00144359 0.0526371 0.148835 -0.00144359 0.0523149 0.145835 -0.00337415 0.0523149 0.148835 -0.00337415 0.0516794 0.148835 -0.00522535 0.0507479 0.148835 -0.00694671 0.0495457 0.145835 -0.00849126 0.0495457 0.148835 -0.00849126 0.0481057 0.148835 -0.00981687 0.0446747 0.145835 -0.0116736 0.0427774 0.145835 -0.0121541 0.0427774 0.148835 -0.0121541 0.0419537 0.145835 -0.00430293 0.0464671 0.145835 -0.0108874 0.0429894 0.145835 -0.00382997 0.0481057 0.145835 -0.00981687 0.0408268 0.145835 -0.00446496 0.0388762 0.145835 -0.0121541 0.0408268 0.145835 -0.0123157 0.0351865 0.145835 -0.0108874 0.0369789 0.145835 -0.0116736 0.0293387 0.145835 -0.00337415 0.0371883 0.145835 -0.00212662 0.0309057 0.145835 -0.00694671 0.0369789 0.145835 0.0107437 0.0351865 0.145835 0.00995748 0.0438498 0.145835 0.00215449 0.0481057 0.145835 0.00888696 0.0429894 0.145835 0.00290006 0.0447861 0.145835 0.000104302 0.0526371 0.145835 0.000513671 0.0523149 0.145835 0.00244423 0.0516794 0.145835 0.00429544 0.0507479 0.145835 -0.00694671 0.0516794 0.145835 -0.00522535 0.0444653 0.145835 -0.00212662 0.0371883 0.145835 0.0011967 0.0290165 0.145835 0.000513671 0.0290165 0.145835 -0.00144359 0.0299742 0.145835 0.00429544 0.0293387 0.145835 0.00244423 0.0427774 0.145835 0.0112242 0.0408268 0.145835 0.0113858 0.0373624 0.143335 -0.000963059 0.0374686 0.143335 -0.00145102 0.0440105 0.143335 -0.00191891 0.0381817 0.143335 -0.00275697 0.0385348 0.143335 -0.00311008 0.0393728 0.143335 -0.00364867 0.0398407 0.143335 -0.00382318 0.0443268 0.143335 -0.000464957 0.0442912 0.143335 3.31449e-05 0.0373624 0.143335 3.31449e-05 0.0408268 0.143335 0.00303504 0.0398407 0.143335 0.00289327 0.0374686 0.143335 0.000521107 0.0408268 0.143335 -0.00396496 0.0413249 0.143335 -0.00392933 0.0422808 0.143335 -0.00364867 0.0437712 0.143335 0.00142729 0.0434719 0.143335 0.00182706 0.0431188 0.143335 0.00218017 0.042719 0.143335 0.00247943 0.0422808 0.143335 0.00271875 0.0418129 0.143335 0.00289327 0.0385348 0.143335 0.00218017 0.0378824 0.143335 0.00142729 0.0434719 0.143335 -0.00275697 0.0437712 0.143335 -0.0023572 0.0408268 0.143402 -0.00421496 0.0419537 0.143835 -0.00430293 0.0419349 0.143585 -0.00423866 0.0424606 0.143585 -0.00404255 0.0429531 0.143585 -0.00377362 0.0434024 0.143585 -0.00343733 0.0437992 0.143585 -0.00304053 0.0438498 0.143835 -0.0030844 0.0447861 0.143835 -0.00103422 0.0447598 0.143585 -0.000464957 0.0448268 0.143835 -0.000464957 0.0441918 0.143835 0.00169761 0.0438498 0.143835 0.00215449 0.0429894 0.143835 0.00290006 0.0413865 0.143585 0.00342802 0.0408268 0.143835 0.00353504 0.0413865 0.143585 -0.00435794 0.0428542 0.143402 -0.00361966 0.0432825 0.143402 -0.00329902 0.0436609 0.143402 -0.00292068 0.0441355 0.143585 -0.0025913 0.0439815 0.143402 -0.00249236 0.0442379 0.143402 -0.00202276 0.0444044 0.143585 -0.00209879 0.0446005 0.143585 -0.00157301 0.0444249 0.143402 -0.00152145 0.0447198 0.143585 -0.00102468 0.0445768 0.143402 -0.000464957 0.0447198 0.143585 9.4769e-05 0.0446005 0.143585 0.000643101 0.0442379 0.143402 0.00109285 0.0444044 0.143585 0.00116888 0.0441355 0.143585 0.00166139 0.0437992 0.143585 0.00211062 0.0434024 0.143585 0.00250742 0.0429531 0.143585 0.0028437 0.0424606 0.143585 0.00311264 0.0423846 0.143402 0.00294616 0.0419349 0.143585 0.00330874 0.0408268 0.143585 0.00346806 0.0413605 0.143402 0.00324687 0.0413605 0.143402 -0.00417679 0.0418833 0.143402 -0.00406306 0.0418129 0.143335 -0.00382318 0.0423846 0.143402 -0.00387608 0.042719 0.143335 -0.00340934 0.0431188 0.143335 -0.00311008 0.044185 0.143335 -0.00145102 0.0445386 0.143402 -0.000998638 0.0442912 0.143335 -0.000963059 0.0445386 0.143402 6.87236e-05 0.0444249 0.143402 0.00059154 0.044185 0.143335 0.000521107 0.0440105 0.143335 0.000988996 0.0439815 0.143402 0.00156245 0.0436609 0.143402 0.00199077 0.0432825 0.143402 0.0023691 0.0428542 0.143402 0.00268974 0.0418833 0.143402 0.00313314 0.0413249 0.143335 0.00299942 0.0402931 0.143402 0.00324687 0.0408268 0.143402 0.00328504 0.0402671 0.143585 0.00342802 0.0402575 0.143835 0.00349433 0.0391651 0.143835 0.00317357 0.039193 0.143585 0.00311264 0.0382074 0.143835 0.00255804 0.0378038 0.143835 0.00215449 0.0372492 0.143585 0.00116888 0.0369888 0.143835 0.000661973 0.0368675 0.143835 0.000104302 0.0368675 0.143835 -0.00103422 0.0369338 0.143585 -0.00102468 0.0370531 0.143585 -0.00157301 0.0374618 0.143835 -0.00262752 0.0378544 0.143585 -0.00304053 0.039193 0.143585 -0.00404255 0.0396999 0.143835 -0.00430293 0.0408268 0.143835 -0.00446496 0.0397187 0.143585 0.00330874 0.0387005 0.143585 0.0028437 0.0383711 0.143402 0.0023691 0.0382512 0.143585 0.00250742 0.0378544 0.143585 0.00211062 0.0379927 0.143402 0.00199077 0.0375181 0.143585 0.00166139 0.0374157 0.143402 0.00109285 0.0370531 0.143585 0.000643101 0.0372287 0.143402 0.00059154 0.0369338 0.143585 9.4769e-05 0.037115 0.143402 6.87236e-05 0.0370768 0.143402 -0.000464957 0.0368938 0.143585 -0.000464957 0.037115 0.143402 -0.000998638 0.0372492 0.143585 -0.00209879 0.0375181 0.143585 -0.0025913 0.0379927 0.143402 -0.00292068 0.0382512 0.143585 -0.00343733 0.0383711 0.143402 -0.00329902 0.0387005 0.143585 -0.00377362 0.0397187 0.143585 -0.00423866 0.0397703 0.143402 -0.00406306 0.0402671 0.143585 -0.00435794 0.0408268 0.143585 -0.00439797 0.0403287 0.143335 0.00299942 0.0397703 0.143402 0.00313314 0.0393728 0.143335 0.00271875 0.039269 0.143402 0.00294616 0.0389346 0.143335 0.00247943 0.0387994 0.143402 0.00268974 0.0381817 0.143335 0.00182706 0.0376721 0.143402 0.00156245 0.0376431 0.143335 0.000988996 0.0373268 0.143335 -0.000464957 0.0372287 0.143402 -0.00152145 0.0376431 0.143335 -0.00191891 0.0374157 0.143402 -0.00202276 0.0376721 0.143402 -0.00249236 0.0378824 0.143335 -0.0023572 0.0387994 0.143402 -0.00361966 0.0389346 0.143335 -0.00340934 0.039269 0.143402 -0.00387608 0.0403287 0.143335 -0.00392933 0.0402931 0.143402 -0.00417679 0.0396999 0.145835 0.00337301 0.0396999 0.143835 0.00337301 0.0386642 0.145835 0.00290006 0.0386642 0.143835 0.00290006 0.0378038 0.145835 0.00215449 0.0374618 0.143835 0.00169761 0.0371883 0.143835 0.0011967 0.0368675 0.145835 0.000104302 0.0368268 0.143835 -0.000464957 0.0368675 0.145835 -0.00103422 0.0369888 0.143835 -0.00159189 0.0371883 0.143835 -0.00212662 0.0378038 0.145835 -0.0030844 0.0378038 0.143835 -0.0030844 0.0386642 0.145835 -0.00382997 0.0382074 0.143835 -0.00348796 0.0386642 0.143835 -0.00382997 0.0391651 0.143835 -0.00410349 0.0396999 0.145835 -0.00430293 0.0402575 0.143835 -0.00442424 0.0413961 0.143835 -0.00442424 0.0424885 0.143835 -0.00410349 0.0429894 0.143835 -0.00382997 0.0434462 0.143835 -0.00348796 0.0438498 0.145835 -0.0030844 0.0441918 0.143835 -0.00262752 0.0444653 0.143835 -0.00212662 0.0446648 0.143835 -0.00159189 0.0447861 0.145835 -0.00103422 0.0447861 0.143835 0.000104302 0.0446648 0.143835 0.000661973 0.0444653 0.143835 0.0011967 0.0444653 0.145835 0.0011967 0.0434462 0.143835 0.00255804 0.0424885 0.143835 0.00317357 0.0419537 0.143835 0.00337301 0.0413961 0.143835 0.00349433 0.0419537 0.145835 0.00337301 0.0408268 0.145835 0.00353504 -0.202273 -0.0652732 -0.084765 -0.210515 -0.0414129 -0.084765 -0.189927 -0.0545751 -0.084765 -0.208238 -0.0530133 -0.084765 -0.208946 -0.0594454 -0.084765 -0.208946 -0.0581547 -0.084765 -0.197092 -0.064146 -0.084765 -0.232619 -0.0579816 -0.084765 -0.233746 -0.0488 -0.084765 -0.214041 -0.0406082 -0.084765 -0.19553 -0.034307 -0.084765 -0.200498 -0.0651462 -0.084765 -0.213031 -0.0614129 -0.084765 -0.221273 -0.0652732 -0.084765 -0.223048 -0.0651462 -0.084765 -0.224787 -0.0647679 -0.084765 -0.2146 -0.0594454 -0.084765 -0.229441 -0.0622266 -0.084765 -0.2307 -0.0366319 -0.084765 -0.224787 -0.0328322 -0.084765 -0.214041 -0.0369919 -0.084765 -0.19178 -0.0380566 -0.084765 -0.208946 -0.0394454 -0.084765 -0.192847 -0.0366319 -0.084765 -0.209892 -0.0539684 -0.084765 -0.210818 -0.0542165 -0.084765 -0.211773 -0.0543 -0.084765 -0.221273 -0.0323269 -0.084765 -0.2146 -0.0381547 -0.084765 -0.190305 -0.0563141 -0.084765 -0.206605 -0.0506812 -0.084765 -0.20701 -0.05155 -0.084765 -0.209506 -0.0569919 -0.084765 -0.216536 -0.05155 -0.084765 -0.21719 -0.0497551 -0.084765 -0.21719 -0.047845 -0.084765 -0.208946 -0.0381547 -0.084765 -0.206357 -0.047845 -0.084765 -0.206273 -0.0488 -0.084765 -0.233241 -0.0563141 -0.084765 -0.216942 -0.0469189 -0.084765 -0.213031 -0.0414129 -0.084765 -0.215986 -0.0452647 -0.084765 -0.212728 -0.0433836 -0.084765 -0.211773 -0.0433 -0.084765 -0.209892 -0.0436317 -0.084765 -0.213654 -0.0539684 -0.084765 -0.214041 -0.0569919 -0.084765 -0.215309 -0.0530133 -0.084765 -0.194658 -0.0435938 -0.113265 -0.202123 -0.0449223 -0.113265 -0.201383 -0.0483587 -0.113265 -0.206701 -0.0397207 -0.113265 -0.226725 -0.0582522 -0.113265 -0.194563 -0.0448 -0.113265 -0.201457 -0.050121 -0.113265 -0.194563 -0.0528 -0.113265 -0.201829 -0.0518454 -0.113265 -0.194658 -0.0540062 -0.113265 -0.202487 -0.0534822 -0.113265 -0.21958 -0.041929 -0.113265 -0.224774 -0.0596702 -0.113265 -0.218969 -0.0563084 -0.113265 -0.197741 -0.0385621 -0.113265 -0.202917 -0.0433472 -0.113265 -0.202273 -0.0370895 -0.113265 -0.213531 -0.0385496 -0.113265 -0.215238 -0.0389941 -0.113265 -0.221273 -0.0370895 -0.113265 -0.222479 -0.0371845 -0.113265 -0.223656 -0.0374669 -0.113265 -0.197741 -0.059038 -0.113265 -0.196821 -0.0582522 -0.113265 -0.195403 -0.0563005 -0.113265 -0.201067 -0.0371845 -0.113265 -0.203966 -0.041929 -0.113265 -0.228606 -0.0551827 -0.113265 -0.222089 -0.050121 -0.113265 -0.228889 -0.0540062 -0.113265 -0.228984 -0.0528 -0.113265 -0.222164 -0.0483587 -0.113265 -0.228984 -0.0488 -0.113265 -0.22194 -0.046609 -0.113265 -0.210891 -0.0591626 -0.113265 -0.198773 -0.0596702 -0.113265 -0.199891 -0.0601332 -0.113265 -0.203412 -0.0549842 -0.113265 -0.201067 -0.0604156 -0.113265 -0.204577 -0.0563084 -0.113265 -0.205949 -0.0574165 -0.113265 -0.232978 -0.0448 -0.109474 -0.233258 -0.0398357 -0.0852911 -0.231702 -0.0394861 -0.109474 -0.231077 -0.0363049 -0.0852911 -0.228287 -0.0338869 -0.0852911 -0.228153 -0.0353305 -0.109474 -0.221273 -0.0318276 -0.0852911 -0.221273 -0.033095 -0.109474 -0.223104 -0.0332391 -0.109474 -0.224928 -0.0323531 -0.0852911 -0.226238 -0.0328151 -0.0852911 -0.227776 -0.0350677 -0.109474 -0.200442 -0.0332391 -0.109474 -0.19999 -0.0333199 -0.109474 -0.198656 -0.0336679 -0.109474 -0.199742 -0.0320769 -0.0852911 -0.197794 -0.033986 -0.109474 -0.196959 -0.0343708 -0.109474 -0.196884 -0.0329999 -0.0852911 -0.19526 -0.0338869 -0.0852911 -0.192469 -0.0363049 -0.0852911 -0.1931 -0.0356272 -0.0852911 -0.189433 -0.0429539 -0.0852911 -0.189826 -0.0411453 -0.0852911 -0.191141 -0.041183 -0.109474 -0.190473 -0.0394111 -0.0852911 -0.191459 -0.0403207 -0.109474 -0.190568 -0.0528 -0.109474 -0.189301 -0.0528 -0.0852911 -0.189433 -0.0546462 -0.0852911 -0.18955 -0.0553308 -0.0852911 -0.189826 -0.0564548 -0.0852911 -0.191844 -0.058114 -0.109474 -0.192541 -0.059303 -0.109474 -0.19136 -0.0598135 -0.0852911 -0.192469 -0.0612952 -0.0852911 -0.1931 -0.0619729 -0.0852911 -0.193996 -0.0610768 -0.109474 -0.200427 -0.0656404 -0.0852911 -0.200442 -0.064361 -0.109474 -0.199742 -0.0655232 -0.0852911 -0.198618 -0.065247 -0.0852911 -0.19999 -0.0642802 -0.109474 -0.197794 -0.0636141 -0.109474 -0.197309 -0.064785 -0.0852911 -0.196959 -0.0632293 -0.109474 -0.19526 -0.0637131 -0.0852911 -0.202273 -0.0645051 -0.109474 -0.221273 -0.0645051 -0.109474 -0.221273 -0.0657725 -0.0852911 -0.223104 -0.064361 -0.109474 -0.223804 -0.0655232 -0.0852911 -0.224928 -0.065247 -0.0852911 -0.226238 -0.064785 -0.0852911 -0.226587 -0.0632293 -0.109474 -0.226662 -0.0646002 -0.0852911 -0.227776 -0.0625324 -0.109474 -0.229768 -0.0626039 -0.0852911 -0.230743 -0.0596801 -0.109474 -0.231077 -0.0612952 -0.0852911 -0.232978 -0.0528 -0.109474 -0.233996 -0.0553308 -0.0852911 -0.232753 -0.0550836 -0.109474 -0.232405 -0.0564171 -0.109474 -0.233073 -0.058189 -0.0852911 -0.231702 -0.058114 -0.109474 -0.231006 -0.059303 -0.109474 -0.232978 -0.0488 -0.109474 -0.1898 -0.0528 -0.084765 -0.189437 -0.0528 -0.0849208 -0.189603 -0.0448 -0.0848056 -0.189331 -0.0528 -0.0850919 -0.1898 -0.0448 -0.084765 -0.189437 -0.0448 -0.0849208 -0.189463 -0.0429582 -0.0850919 -0.190288 -0.0398357 -0.0852911 -0.189855 -0.0411538 -0.0850919 -0.18955 -0.0422692 -0.0852911 -0.189331 -0.0448 -0.0850919 -0.189301 -0.0448 -0.0852911 -0.190501 -0.0394237 -0.0850919 -0.19136 -0.0377866 -0.0852911 -0.192492 -0.0363247 -0.0850919 -0.200431 -0.0319896 -0.0850919 -0.193798 -0.035019 -0.0850919 -0.193778 -0.0349961 -0.0852911 -0.196897 -0.0330274 -0.0850919 -0.197309 -0.0328151 -0.0852911 -0.198627 -0.0323821 -0.0850919 -0.198618 -0.0323531 -0.0852911 -0.200427 -0.0319597 -0.0852911 -0.202273 -0.0318276 -0.0852911 -0.189568 -0.0429733 -0.0849208 -0.190597 -0.0394679 -0.0849208 -0.191475 -0.0378605 -0.0849208 -0.191386 -0.037803 -0.0850919 -0.192573 -0.0363944 -0.0849208 -0.193868 -0.0350994 -0.0849208 -0.195334 -0.0340019 -0.0849208 -0.195276 -0.0339124 -0.0850919 -0.202273 -0.0318578 -0.0850919 -0.189732 -0.0429968 -0.0848056 -0.189957 -0.0411838 -0.0849208 -0.190116 -0.0412304 -0.0848056 -0.190748 -0.0395365 -0.0848056 -0.193976 -0.0352243 -0.0848056 -0.195423 -0.034141 -0.0848056 -0.196941 -0.0331242 -0.0849208 -0.198657 -0.0324842 -0.0849208 -0.198704 -0.0326428 -0.0848056 -0.200446 -0.0320949 -0.0849208 -0.189927 -0.0430249 -0.084765 -0.190305 -0.041286 -0.084765 -0.190927 -0.0396185 -0.084765 -0.191614 -0.0379499 -0.0848056 -0.192697 -0.0365026 -0.0848056 -0.194105 -0.0353735 -0.084765 -0.19701 -0.0332746 -0.0848056 -0.197092 -0.0334541 -0.084765 -0.198759 -0.0328322 -0.084765 -0.200498 -0.0324539 -0.084765 -0.20047 -0.0322585 -0.0848056 -0.202273 -0.0321296 -0.0848056 -0.202273 -0.0323269 -0.084765 -0.202273 -0.0654705 -0.0848056 -0.200446 -0.0655052 -0.0849208 -0.202273 -0.0656358 -0.0849208 -0.202273 -0.0657422 -0.0850919 -0.196897 -0.0645727 -0.0850919 -0.198627 -0.065218 -0.0850919 -0.200431 -0.0656105 -0.0850919 -0.196884 -0.0646002 -0.0852911 -0.193778 -0.0626039 -0.0852911 -0.189855 -0.0564463 -0.0850919 -0.190473 -0.058189 -0.0852911 -0.190288 -0.0577644 -0.0852911 -0.196941 -0.0644759 -0.0849208 -0.195276 -0.0636877 -0.0850919 -0.195334 -0.0635982 -0.0849208 -0.193798 -0.0625811 -0.0850919 -0.192492 -0.0612754 -0.0850919 -0.191386 -0.0597971 -0.0850919 -0.191475 -0.0597396 -0.0849208 -0.190501 -0.0581764 -0.0850919 -0.189957 -0.0564163 -0.0849208 -0.189463 -0.0546419 -0.0850919 -0.198657 -0.0651159 -0.0849208 -0.19701 -0.0643255 -0.0848056 -0.193868 -0.0625007 -0.0849208 -0.193976 -0.0623758 -0.0848056 -0.192573 -0.0612057 -0.0849208 -0.191614 -0.0596502 -0.0848056 -0.190597 -0.0581322 -0.0849208 -0.189568 -0.0546268 -0.0849208 -0.20047 -0.0653416 -0.0848056 -0.198704 -0.0649573 -0.0848056 -0.198759 -0.0647679 -0.084765 -0.195423 -0.0634591 -0.0848056 -0.19553 -0.0632931 -0.084765 -0.194105 -0.0622266 -0.084765 -0.192697 -0.0610974 -0.0848056 -0.192847 -0.0609682 -0.084765 -0.19178 -0.0595435 -0.084765 -0.190748 -0.0580636 -0.0848056 -0.190927 -0.0579816 -0.084765 -0.190116 -0.0563697 -0.0848056 -0.189732 -0.0546032 -0.0848056 -0.189603 -0.0528 -0.0848056 -0.221273 -0.0321296 -0.0848056 -0.221273 -0.0319642 -0.0849208 -0.202273 -0.0319642 -0.0849208 -0.221273 -0.0318578 -0.0850919 -0.221273 -0.0656358 -0.0849208 -0.202273 -0.0657725 -0.0852911 -0.223076 -0.0322585 -0.0848056 -0.2231 -0.0320949 -0.0849208 -0.223115 -0.0319896 -0.0850919 -0.22665 -0.0330274 -0.0850919 -0.224919 -0.0323821 -0.0850919 -0.223804 -0.0320769 -0.0852911 -0.223119 -0.0319597 -0.0852911 -0.226662 -0.0329999 -0.0852911 -0.229749 -0.035019 -0.0850919 -0.229768 -0.0349961 -0.0852911 -0.230446 -0.0356272 -0.0852911 -0.233996 -0.0422692 -0.0852911 -0.232186 -0.0377866 -0.0852911 -0.233073 -0.0394111 -0.0852911 -0.233046 -0.0394237 -0.0850919 -0.233691 -0.0411538 -0.0850919 -0.23372 -0.0411453 -0.0852911 -0.234114 -0.0429539 -0.0852911 -0.234246 -0.0448 -0.0852911 -0.224889 -0.0324842 -0.0849208 -0.226605 -0.0331242 -0.0849208 -0.22827 -0.0339124 -0.0850919 -0.230974 -0.0363944 -0.0849208 -0.231054 -0.0363247 -0.0850919 -0.232161 -0.037803 -0.0850919 -0.232949 -0.0394679 -0.0849208 -0.234084 -0.0429582 -0.0850919 -0.234109 -0.0448 -0.0849208 -0.224843 -0.0326428 -0.0848056 -0.226537 -0.0332746 -0.0848056 -0.228213 -0.0340019 -0.0849208 -0.228123 -0.034141 -0.0848056 -0.229571 -0.0352243 -0.0848056 -0.229679 -0.0350994 -0.0849208 -0.232071 -0.0378605 -0.0849208 -0.230849 -0.0365026 -0.0848056 -0.232799 -0.0395365 -0.0848056 -0.233589 -0.0411838 -0.0849208 -0.23343 -0.0412304 -0.0848056 -0.233978 -0.0429733 -0.0849208 -0.233815 -0.0429968 -0.0848056 -0.223048 -0.0324539 -0.084765 -0.226455 -0.0334541 -0.084765 -0.228017 -0.034307 -0.084765 -0.229441 -0.0353735 -0.084765 -0.231932 -0.0379499 -0.0848056 -0.231766 -0.0380566 -0.084765 -0.232619 -0.0396185 -0.084765 -0.233241 -0.041286 -0.084765 -0.233619 -0.0430249 -0.084765 -0.233815 -0.0546032 -0.0848056 -0.233944 -0.0528 -0.0848056 -0.234215 -0.0528 -0.0850919 -0.233258 -0.0577644 -0.0852911 -0.233691 -0.0564463 -0.0850919 -0.23372 -0.0564548 -0.0852911 -0.234114 -0.0546462 -0.0852911 -0.234084 -0.0546419 -0.0850919 -0.234246 -0.0528 -0.0852911 -0.232186 -0.0598135 -0.0852911 -0.232161 -0.0597971 -0.0850919 -0.230446 -0.0619729 -0.0852911 -0.229749 -0.0625811 -0.0850919 -0.228287 -0.0637131 -0.0852911 -0.22827 -0.0636877 -0.0850919 -0.22665 -0.0645727 -0.0850919 -0.224919 -0.065218 -0.0850919 -0.223119 -0.0656404 -0.0852911 -0.223115 -0.0656105 -0.0850919 -0.233978 -0.0546268 -0.0849208 -0.233589 -0.0564163 -0.0849208 -0.233046 -0.0581764 -0.0850919 -0.232949 -0.0581322 -0.0849208 -0.232071 -0.0597396 -0.0849208 -0.231054 -0.0612754 -0.0850919 -0.228213 -0.0635982 -0.0849208 -0.226605 -0.0644759 -0.0849208 -0.224889 -0.0651159 -0.0849208 -0.2231 -0.0655052 -0.0849208 -0.221273 -0.0657422 -0.0850919 -0.231932 -0.0596502 -0.0848056 -0.230974 -0.0612057 -0.0849208 -0.229679 -0.0625007 -0.0849208 -0.229571 -0.0623758 -0.0848056 -0.226537 -0.0643255 -0.0848056 -0.233746 -0.0528 -0.084765 -0.233619 -0.0545751 -0.084765 -0.23343 -0.0563697 -0.0848056 -0.232799 -0.0580636 -0.0848056 -0.231766 -0.0595435 -0.084765 -0.2307 -0.0609682 -0.084765 -0.230849 -0.0610974 -0.0848056 -0.228123 -0.0634591 -0.0848056 -0.228017 -0.0632931 -0.084765 -0.226455 -0.064146 -0.084765 -0.224843 -0.0649573 -0.0848056 -0.223076 -0.0653416 -0.0848056 -0.221273 -0.0654705 -0.0848056 -0.233746 -0.0448 -0.084765 -0.233944 -0.0488 -0.0848056 -0.233944 -0.0448 -0.0848056 -0.234215 -0.0448 -0.0850919 -0.234246 -0.0488 -0.0852911 -0.234109 -0.0488 -0.0849208 -0.234109 -0.0528 -0.0849208 -0.234215 -0.0488 -0.0850919 -0.202273 -0.033095 -0.109474 -0.221273 -0.0332747 -0.110468 -0.221273 -0.0334569 -0.11094 -0.202273 -0.0334569 -0.11094 -0.221273 -0.0336973 -0.111385 -0.202273 -0.0343361 -0.112166 -0.221273 -0.0343361 -0.112166 -0.202273 -0.0356073 -0.11298 -0.232087 -0.0403207 -0.109474 -0.231006 -0.0382971 -0.109474 -0.22489 -0.0336679 -0.109474 -0.223076 -0.0334166 -0.110468 -0.221273 -0.036088 -0.113138 -0.221273 -0.0356073 -0.11298 -0.222783 -0.0352691 -0.112763 -0.228143 -0.0412995 -0.113265 -0.229559 -0.0421079 -0.113138 -0.230451 -0.0418181 -0.112763 -0.231225 -0.0415665 -0.112166 -0.231166 -0.0397595 -0.111385 -0.228606 -0.0424174 -0.113265 -0.228889 -0.0435938 -0.113265 -0.229878 -0.0434372 -0.113138 -0.230804 -0.0432905 -0.112763 -0.231608 -0.0431631 -0.112166 -0.22301 -0.033834 -0.111385 -0.221273 -0.0351503 -0.112763 -0.228984 -0.0448 -0.113265 -0.230466 -0.0448 -0.11298 -0.231737 -0.0448 -0.112166 -0.232239 -0.0430632 -0.111385 -0.232376 -0.0448 -0.111385 -0.231542 -0.0395676 -0.110468 -0.232234 -0.0412385 -0.110468 -0.231833 -0.0413691 -0.111385 -0.232657 -0.0429971 -0.110468 -0.224835 -0.0338387 -0.110468 -0.223557 -0.0333199 -0.109474 -0.22291 -0.0344649 -0.112166 -0.224255 -0.0356226 -0.112763 -0.223965 -0.0365144 -0.113138 -0.222636 -0.0361953 -0.113138 -0.226587 -0.0343708 -0.109474 -0.225753 -0.033986 -0.109474 -0.226314 -0.0349075 -0.111385 -0.224704 -0.0342407 -0.111385 -0.226024 -0.0354766 -0.112166 -0.224507 -0.0348482 -0.112166 -0.224774 -0.0379299 -0.113265 -0.226506 -0.0345308 -0.110468 -0.225654 -0.036202 -0.112763 -0.225228 -0.0370376 -0.113138 -0.225805 -0.0385621 -0.113265 -0.226394 -0.0377519 -0.113138 -0.226725 -0.0393479 -0.113265 -0.226945 -0.0369932 -0.112763 -0.227434 -0.0386397 -0.113138 -0.228672 -0.0374009 -0.112166 -0.227424 -0.0363345 -0.112166 -0.227799 -0.0358178 -0.111385 -0.228048 -0.0354758 -0.110468 -0.229423 -0.0366504 -0.110468 -0.227511 -0.0402679 -0.113265 -0.228321 -0.0396792 -0.113138 -0.228097 -0.0379766 -0.112763 -0.22908 -0.0391281 -0.112763 -0.229739 -0.0386495 -0.112166 -0.230255 -0.038274 -0.111385 -0.229124 -0.0369492 -0.111385 -0.230597 -0.0380256 -0.110468 -0.22955 -0.0365233 -0.109474 -0.230743 -0.03792 -0.109474 -0.230597 -0.0400495 -0.112166 -0.229871 -0.0404191 -0.112763 -0.229036 -0.0408449 -0.113138 -0.232405 -0.041183 -0.109474 -0.232753 -0.0425165 -0.109474 -0.232834 -0.042969 -0.109474 -0.232799 -0.0448 -0.110468 -0.195393 -0.0353305 -0.109474 -0.191844 -0.0394861 -0.109474 -0.20091 -0.0361953 -0.113138 -0.193561 -0.0448 -0.113138 -0.193668 -0.0434372 -0.113138 -0.198318 -0.0370376 -0.113138 -0.197233 -0.0349075 -0.111385 -0.199891 -0.0374669 -0.113265 -0.199581 -0.0365144 -0.113138 -0.199291 -0.0356226 -0.112763 -0.200764 -0.0352691 -0.112763 -0.19904 -0.0348482 -0.112166 -0.19089 -0.0429971 -0.110468 -0.191307 -0.0430632 -0.111385 -0.191938 -0.0431631 -0.112166 -0.191809 -0.0448 -0.112166 -0.192742 -0.0432905 -0.112763 -0.19494 -0.0424174 -0.113265 -0.195403 -0.0412995 -0.113265 -0.194511 -0.0408449 -0.113138 -0.192321 -0.0415665 -0.112166 -0.192381 -0.0397595 -0.111385 -0.202273 -0.036088 -0.113138 -0.200636 -0.0344649 -0.112166 -0.202273 -0.0351503 -0.112763 -0.200536 -0.033834 -0.111385 -0.202273 -0.0336973 -0.111385 -0.197041 -0.0345308 -0.110468 -0.198842 -0.0342407 -0.111385 -0.20047 -0.0334166 -0.110468 -0.202273 -0.0332747 -0.110468 -0.190712 -0.042969 -0.109474 -0.190568 -0.0448 -0.109474 -0.191312 -0.0412385 -0.110468 -0.190793 -0.0425165 -0.109474 -0.191714 -0.0413691 -0.111385 -0.193096 -0.0418181 -0.112763 -0.193988 -0.0421079 -0.113138 -0.192541 -0.0382971 -0.109474 -0.192949 -0.0380256 -0.110468 -0.192004 -0.0395676 -0.110468 -0.193291 -0.038274 -0.111385 -0.193808 -0.0386495 -0.112166 -0.19295 -0.0400495 -0.112166 -0.194466 -0.0391281 -0.112763 -0.193675 -0.0404191 -0.112763 -0.196035 -0.0402679 -0.113265 -0.196821 -0.0393479 -0.113265 -0.195225 -0.0396792 -0.113138 -0.196113 -0.0386397 -0.113138 -0.19545 -0.0379766 -0.112763 -0.192804 -0.03792 -0.109474 -0.194874 -0.0374009 -0.112166 -0.194422 -0.0369492 -0.111385 -0.196123 -0.0363345 -0.112166 -0.194124 -0.0366504 -0.110468 -0.195747 -0.0358178 -0.111385 -0.195499 -0.0354758 -0.110468 -0.193996 -0.0365233 -0.109474 -0.19577 -0.0350677 -0.109474 -0.197523 -0.0354766 -0.112166 -0.196601 -0.0369932 -0.112763 -0.197892 -0.036202 -0.112763 -0.197152 -0.0377519 -0.113138 -0.198773 -0.0379299 -0.113265 -0.198712 -0.0338387 -0.110468 -0.229985 -0.0448 -0.113138 -0.230923 -0.0448 -0.112763 -0.231737 -0.0488 -0.112166 -0.232616 -0.0488 -0.11094 -0.232616 -0.0448 -0.11094 -0.19308 -0.0528 -0.11298 -0.192623 -0.0528 -0.112763 -0.19308 -0.0448 -0.11298 -0.191809 -0.0528 -0.112166 -0.192623 -0.0448 -0.112763 -0.19117 -0.0448 -0.111385 -0.190748 -0.0528 -0.110468 -0.19093 -0.0448 -0.11094 -0.190748 -0.0448 -0.110468 -0.230466 -0.0488 -0.11298 -0.230923 -0.0528 -0.112763 -0.231737 -0.0528 -0.112166 -0.232799 -0.0528 -0.110468 -0.232376 -0.0528 -0.111385 -0.190793 -0.0550836 -0.109474 -0.191141 -0.0564171 -0.109474 -0.191312 -0.0563616 -0.110468 -0.192804 -0.0596801 -0.109474 -0.192949 -0.0595745 -0.110468 -0.19577 -0.0625324 -0.109474 -0.198656 -0.0639322 -0.109474 -0.193668 -0.0541629 -0.113138 -0.20091 -0.0614048 -0.113138 -0.202273 -0.0615121 -0.113138 -0.193561 -0.0528 -0.113138 -0.192742 -0.0543096 -0.112763 -0.200536 -0.0637661 -0.111385 -0.200764 -0.062331 -0.112763 -0.202273 -0.0624498 -0.112763 -0.202273 -0.0643254 -0.110468 -0.20047 -0.0641835 -0.110468 -0.200636 -0.0631352 -0.112166 -0.199291 -0.0619775 -0.112763 -0.199581 -0.0610857 -0.113138 -0.198712 -0.0637613 -0.110468 -0.198842 -0.0633593 -0.111385 -0.197523 -0.0621235 -0.112166 -0.19904 -0.0627518 -0.112166 -0.198318 -0.0605625 -0.113138 -0.197041 -0.0630692 -0.110468 -0.195747 -0.0617823 -0.111385 -0.197233 -0.0626926 -0.111385 -0.196601 -0.0606069 -0.112763 -0.197892 -0.061398 -0.112763 -0.197152 -0.0598482 -0.113138 -0.19545 -0.0596235 -0.112763 -0.196123 -0.0612655 -0.112166 -0.195499 -0.0621243 -0.110468 -0.195393 -0.0622696 -0.109474 -0.194124 -0.0609497 -0.110468 -0.196113 -0.0589604 -0.113138 -0.195225 -0.0579209 -0.113138 -0.194874 -0.0601992 -0.112166 -0.194422 -0.0606508 -0.111385 -0.193291 -0.0593261 -0.111385 -0.192004 -0.0580325 -0.110468 -0.192381 -0.0578406 -0.111385 -0.193808 -0.0589506 -0.112166 -0.194466 -0.058472 -0.112763 -0.196035 -0.0573322 -0.113265 -0.191459 -0.0572794 -0.109474 -0.193096 -0.055782 -0.112763 -0.19295 -0.0575506 -0.112166 -0.193675 -0.0571809 -0.112763 -0.19494 -0.0551827 -0.113265 -0.194511 -0.0567552 -0.113138 -0.19089 -0.054603 -0.110468 -0.191307 -0.0545369 -0.111385 -0.191714 -0.056231 -0.111385 -0.191938 -0.054437 -0.112166 -0.192321 -0.0560336 -0.112166 -0.193988 -0.0554922 -0.113138 -0.19117 -0.0528 -0.111385 -0.19093 -0.0528 -0.11094 -0.190712 -0.0546311 -0.109474 -0.225753 -0.0636141 -0.109474 -0.231542 -0.0580325 -0.110468 -0.229985 -0.0528 -0.113138 -0.229878 -0.0541629 -0.113138 -0.230466 -0.0528 -0.11298 -0.225228 -0.0605625 -0.113138 -0.223965 -0.0610857 -0.113138 -0.225654 -0.061398 -0.112763 -0.224255 -0.0619775 -0.112763 -0.226024 -0.0621235 -0.112166 -0.224507 -0.0627518 -0.112166 -0.226506 -0.0630692 -0.110468 -0.223656 -0.0601332 -0.113265 -0.222479 -0.0604156 -0.113265 -0.230804 -0.0543096 -0.112763 -0.228143 -0.0563005 -0.113265 -0.229036 -0.0567552 -0.113138 -0.229871 -0.0571809 -0.112763 -0.231225 -0.0560336 -0.112166 -0.231833 -0.056231 -0.111385 -0.222636 -0.0614048 -0.113138 -0.222783 -0.062331 -0.112763 -0.22291 -0.0631352 -0.112166 -0.221273 -0.063264 -0.112166 -0.221273 -0.0639028 -0.111385 -0.224704 -0.0633593 -0.111385 -0.223076 -0.0641835 -0.110468 -0.22301 -0.0637661 -0.111385 -0.232834 -0.0546311 -0.109474 -0.232657 -0.054603 -0.110468 -0.232616 -0.0528 -0.11094 -0.232239 -0.0545369 -0.111385 -0.231608 -0.054437 -0.112166 -0.230451 -0.055782 -0.112763 -0.229559 -0.0554922 -0.113138 -0.232087 -0.0572794 -0.109474 -0.232234 -0.0563616 -0.110468 -0.230255 -0.0593261 -0.111385 -0.231166 -0.0578406 -0.111385 -0.230597 -0.0575506 -0.112166 -0.229739 -0.0589506 -0.112166 -0.227511 -0.0573322 -0.113265 -0.228321 -0.0579209 -0.113138 -0.227434 -0.0589604 -0.113138 -0.22908 -0.058472 -0.112763 -0.230597 -0.0595745 -0.110468 -0.229124 -0.0606508 -0.111385 -0.22955 -0.0610768 -0.109474 -0.225805 -0.059038 -0.113265 -0.228097 -0.0596235 -0.112763 -0.228672 -0.0601992 -0.112166 -0.227424 -0.0612655 -0.112166 -0.228048 -0.0621243 -0.110468 -0.229423 -0.0609497 -0.110468 -0.228153 -0.0622696 -0.109474 -0.226314 -0.0626926 -0.111385 -0.227799 -0.0617823 -0.111385 -0.226945 -0.0606069 -0.112763 -0.226394 -0.0598482 -0.113138 -0.22489 -0.0639322 -0.109474 -0.223557 -0.0642802 -0.109474 -0.224835 -0.0637613 -0.110468 -0.221273 -0.0643254 -0.110468 -0.202273 -0.0641431 -0.11094 -0.221273 -0.0641431 -0.11094 -0.202273 -0.0639028 -0.111385 -0.202273 -0.063264 -0.112166 -0.221273 -0.0624498 -0.112763 -0.202273 -0.0619928 -0.11298 -0.221273 -0.0619928 -0.11298 -0.221273 -0.0615121 -0.113138 -0.202273 -0.0605106 -0.113265 -0.221273 -0.0605106 -0.113265 -0.211061 -0.0571698 -0.111265 -0.209599 -0.0569138 -0.090065 -0.209657 -0.056929 -0.111265 -0.207069 -0.0557595 -0.111265 -0.207573 -0.0560747 -0.090065 -0.20502 -0.053795 -0.111265 -0.205834 -0.0547397 -0.090065 -0.204499 -0.053 -0.111265 -0.204499 -0.053 -0.090065 -0.204273 -0.0525818 -0.111265 -0.203659 -0.0509741 -0.111265 -0.203741 -0.0512598 -0.111265 -0.203562 -0.0470303 -0.111265 -0.203659 -0.046626 -0.090065 -0.203381 -0.0484435 -0.111265 -0.203373 -0.0488 -0.111265 -0.203441 -0.049867 -0.111265 -0.203979 -0.045668 -0.111265 -0.207573 -0.0415254 -0.090065 -0.205834 -0.0428603 -0.090065 -0.205834 -0.0428603 -0.111265 -0.205468 -0.0432504 -0.111265 -0.208975 -0.0408799 -0.111265 -0.207677 -0.0414667 -0.111265 -0.210354 -0.0405209 -0.111265 -0.209599 -0.0406863 -0.090065 -0.211773 -0.0404 -0.090065 -0.213947 -0.0406863 -0.111265 -0.213947 -0.0406863 -0.090065 -0.21587 -0.0414667 -0.111265 -0.21705 -0.0422645 -0.111265 -0.215973 -0.0415254 -0.111265 -0.218079 -0.0432504 -0.111265 -0.217713 -0.0428603 -0.090065 -0.219887 -0.046626 -0.090065 -0.220173 -0.0488 -0.090065 -0.220166 -0.0484435 -0.111265 -0.219985 -0.0470303 -0.111265 -0.219887 -0.046626 -0.111265 -0.220105 -0.049867 -0.111265 -0.219048 -0.053 -0.090065 -0.219887 -0.0509741 -0.090065 -0.219887 -0.0509741 -0.111265 -0.217713 -0.0547397 -0.090065 -0.215233 -0.0564544 -0.111265 -0.215973 -0.0560747 -0.111265 -0.211773 -0.0572 -0.090065 -0.211773 -0.0572 -0.111265 -0.213947 -0.0569138 -0.090065 -0.211773 -0.0433 -0.090065 -0.21719 -0.047845 -0.090065 -0.203373 -0.0488 -0.090065 -0.206357 -0.0497551 -0.090065 -0.206273 -0.0488 -0.090065 -0.208238 -0.0445868 -0.090065 -0.215973 -0.0415254 -0.090065 -0.213654 -0.0436317 -0.090065 -0.214523 -0.0440369 -0.090065 -0.219048 -0.0446 -0.090065 -0.215986 -0.0452647 -0.090065 -0.216536 -0.04605 -0.090065 -0.21719 -0.0497551 -0.090065 -0.206357 -0.047845 -0.090065 -0.206605 -0.0469189 -0.090065 -0.204499 -0.0446 -0.090065 -0.20701 -0.04605 -0.090065 -0.211773 -0.0543 -0.090065 -0.20756 -0.0523354 -0.090065 -0.20701 -0.05155 -0.090065 -0.206605 -0.0506812 -0.090065 -0.203659 -0.0509741 -0.090065 -0.216536 -0.05155 -0.090065 -0.215973 -0.0560747 -0.090065 -0.212728 -0.0542165 -0.090065 -0.210818 -0.0542165 -0.090065 -0.209023 -0.0535632 -0.090065 -0.213193 -0.0405209 -0.111265 -0.214622 -0.0407363 -0.11203 -0.214572 -0.0408799 -0.111265 -0.217713 -0.0428603 -0.111265 -0.218193 -0.0431498 -0.11203 -0.218926 -0.0443959 -0.111265 -0.219048 -0.0446 -0.111265 -0.219056 -0.044316 -0.11203 -0.219709 -0.0456113 -0.11203 -0.219567 -0.045668 -0.111265 -0.220133 -0.0469983 -0.11203 -0.220318 -0.0484371 -0.11203 -0.220173 -0.0488 -0.111265 -0.219951 -0.0513043 -0.11203 -0.219805 -0.0512598 -0.111265 -0.219274 -0.0525818 -0.111265 -0.219048 -0.053 -0.111265 -0.218649 -0.0538855 -0.11203 -0.218527 -0.053795 -0.111265 -0.217713 -0.0547397 -0.111265 -0.217585 -0.0548645 -0.111265 -0.216477 -0.0557595 -0.111265 -0.216562 -0.0558857 -0.11203 -0.215296 -0.0565931 -0.11203 -0.212486 -0.0571698 -0.111265 -0.21389 -0.056929 -0.111265 -0.212498 -0.0573215 -0.11203 -0.213928 -0.0570763 -0.11203 -0.209618 -0.0570763 -0.11203 -0.207573 -0.0560747 -0.111265 -0.206984 -0.0558857 -0.11203 -0.208313 -0.0564544 -0.111265 -0.205961 -0.0548645 -0.111265 -0.205834 -0.0547397 -0.111265 -0.20329 -0.0498863 -0.11203 -0.203659 -0.046626 -0.111265 -0.204499 -0.0446 -0.111265 -0.20462 -0.0443959 -0.111265 -0.204491 -0.044316 -0.11203 -0.206401 -0.0421461 -0.11203 -0.206496 -0.0422645 -0.111265 -0.207602 -0.0413338 -0.11203 -0.207573 -0.0415254 -0.111265 -0.208924 -0.0407363 -0.11203 -0.209599 -0.0406863 -0.111265 -0.213219 -0.0403708 -0.11203 -0.211773 -0.0404 -0.111265 -0.210328 -0.0403708 -0.11203 -0.205028 -0.0428634 -0.112679 -0.205353 -0.0431498 -0.11203 -0.204122 -0.0440887 -0.112679 -0.203838 -0.0456113 -0.11203 -0.203413 -0.0469983 -0.11203 -0.202989 -0.0469069 -0.112679 -0.202796 -0.0484187 -0.112679 -0.203229 -0.0484371 -0.11203 -0.203596 -0.0513043 -0.11203 -0.204137 -0.0526503 -0.11203 -0.204897 -0.0538855 -0.11203 -0.205856 -0.0549744 -0.11203 -0.206741 -0.0562449 -0.112679 -0.208251 -0.0565931 -0.11203 -0.211011 -0.0577535 -0.112679 -0.211048 -0.0573215 -0.11203 -0.214037 -0.0574959 -0.112679 -0.216805 -0.0562449 -0.112679 -0.217991 -0.0552874 -0.112679 -0.217691 -0.0549744 -0.11203 -0.218998 -0.0541433 -0.112679 -0.219797 -0.0528455 -0.112679 -0.21941 -0.0526503 -0.11203 -0.220686 -0.0499414 -0.112679 -0.220256 -0.0498863 -0.11203 -0.220557 -0.0469069 -0.112679 -0.220111 -0.0454496 -0.112679 -0.219425 -0.0440887 -0.112679 -0.218519 -0.0428634 -0.112679 -0.217146 -0.0421461 -0.11203 -0.215944 -0.0413338 -0.11203 -0.211773 -0.0402478 -0.11203 -0.211773 -0.0398143 -0.112679 -0.210145 -0.039304 -0.113113 -0.210255 -0.0399435 -0.112679 -0.20878 -0.0403275 -0.112679 -0.207391 -0.0409553 -0.112679 -0.206128 -0.0418088 -0.112679 -0.203569 -0.0437485 -0.113113 -0.203435 -0.0454496 -0.112679 -0.202833 -0.0452077 -0.113113 -0.202355 -0.0467702 -0.113113 -0.202147 -0.0483911 -0.113113 -0.20286 -0.0499414 -0.112679 -0.203181 -0.0514313 -0.112679 -0.20375 -0.0528455 -0.112679 -0.20317 -0.0531376 -0.113113 -0.204549 -0.0541433 -0.112679 -0.205556 -0.0552874 -0.112679 -0.206378 -0.0567824 -0.113113 -0.208072 -0.0569881 -0.112679 -0.207805 -0.0575794 -0.113113 -0.209345 -0.0581238 -0.113113 -0.209509 -0.0574959 -0.112679 -0.210956 -0.0584 -0.113113 -0.21259 -0.0584 -0.113113 -0.214201 -0.0581238 -0.113113 -0.212535 -0.0577535 -0.112679 -0.215474 -0.0569881 -0.112679 -0.217168 -0.0567824 -0.113113 -0.220986 -0.0516213 -0.113113 -0.22133 -0.0500238 -0.113113 -0.220365 -0.0514313 -0.112679 -0.221399 -0.0483911 -0.113113 -0.220751 -0.0484187 -0.112679 -0.220713 -0.0452077 -0.113113 -0.219006 -0.0424347 -0.113113 -0.217418 -0.0418088 -0.112679 -0.216156 -0.0409553 -0.112679 -0.214767 -0.0403275 -0.112679 -0.214983 -0.0397158 -0.113113 -0.213401 -0.039304 -0.113113 -0.213292 -0.0399435 -0.112679 -0.211773 -0.0391654 -0.113113 -0.208309 -0.0389941 -0.113265 -0.208564 -0.0397158 -0.113113 -0.207074 -0.0403889 -0.113113 -0.20524 -0.0407085 -0.113265 -0.205721 -0.041304 -0.113113 -0.204541 -0.0424347 -0.113113 -0.201607 -0.046609 -0.113265 -0.202217 -0.0500238 -0.113113 -0.202561 -0.0516213 -0.113113 -0.204027 -0.0545291 -0.113113 -0.205107 -0.0557558 -0.113113 -0.207489 -0.0582768 -0.113265 -0.209153 -0.0588645 -0.113265 -0.212655 -0.0591626 -0.113265 -0.214394 -0.0588645 -0.113265 -0.215742 -0.0575794 -0.113113 -0.216057 -0.0582768 -0.113265 -0.217597 -0.0574165 -0.113265 -0.21844 -0.0557558 -0.113113 -0.219519 -0.0545291 -0.113113 -0.220135 -0.0549842 -0.113265 -0.22106 -0.0534822 -0.113265 -0.220376 -0.0531376 -0.113113 -0.221717 -0.0518454 -0.113265 -0.221192 -0.0467702 -0.113113 -0.221423 -0.0449223 -0.113265 -0.220629 -0.0433472 -0.113265 -0.219977 -0.0437485 -0.113113 -0.217826 -0.041304 -0.113113 -0.218307 -0.0407085 -0.113265 -0.216845 -0.0397207 -0.113265 -0.216472 -0.0403889 -0.113113 -0.211773 -0.0384 -0.113265 -0.210016 -0.0385496 -0.113265 -0.212641 -0.0537241 -0.089565 -0.213483 -0.0534985 -0.085265 -0.214273 -0.0531302 -0.085265 -0.214987 -0.0526303 -0.085265 -0.216103 -0.0513 -0.085265 -0.216472 -0.0505101 -0.085265 -0.216697 -0.0496683 -0.085265 -0.216697 -0.0496683 -0.089565 -0.216773 -0.0488 -0.089565 -0.216697 -0.0479318 -0.089565 -0.216103 -0.0463 -0.089565 -0.215603 -0.0455861 -0.085265 -0.212641 -0.043876 -0.085265 -0.211773 -0.0438 -0.085265 -0.211773 -0.0438 -0.089565 -0.210063 -0.0441016 -0.089565 -0.208559 -0.0449698 -0.089565 -0.207443 -0.0463 -0.085265 -0.207075 -0.0470899 -0.085265 -0.206773 -0.0488 -0.089565 -0.207443 -0.0513 -0.089565 -0.207943 -0.052014 -0.089565 -0.208559 -0.0526303 -0.089565 -0.209273 -0.0531302 -0.085265 -0.210905 -0.0537241 -0.089565 -0.211773 -0.0538 -0.089565 -0.212419 -0.0359728 -0.082265 -0.213581 -0.0365327 -0.082265 -0.213031 -0.0361872 -0.084765 -0.213031 -0.0361872 -0.082265 -0.214386 -0.0375418 -0.082265 -0.214673 -0.0388 -0.082265 -0.2146 -0.0394454 -0.084765 -0.2146 -0.0394454 -0.082265 -0.211773 -0.0417 -0.084765 -0.211773 -0.0417 -0.082265 -0.209965 -0.0410674 -0.082265 -0.211128 -0.0416273 -0.082265 -0.209506 -0.0406082 -0.084765 -0.208873 -0.0388 -0.082265 -0.20916 -0.0400583 -0.082265 -0.209506 -0.0369919 -0.084765 -0.20916 -0.0375418 -0.082265 -0.208946 -0.0381547 -0.082265 -0.211773 -0.0359 -0.084765 -0.211128 -0.0359728 -0.082265 -0.210515 -0.0361872 -0.084765 -0.210515 -0.0361872 -0.082265 -0.212958 -0.0402855 -0.081265 -0.212598 -0.0405119 -0.081265 -0.212196 -0.0406524 -0.081265 -0.213626 -0.0392228 -0.081265 -0.213485 -0.0396244 -0.081265 -0.213259 -0.0376154 -0.081265 -0.210949 -0.0370882 -0.081265 -0.211773 -0.0388 -0.081265 -0.210061 -0.0396244 -0.081265 -0.209921 -0.0392228 -0.081265 -0.213031 -0.0561872 -0.084765 -0.214041 -0.0569919 -0.082265 -0.2146 -0.0581547 -0.084765 -0.2146 -0.0594454 -0.082265 -0.214673 -0.0588 -0.082265 -0.213581 -0.0610674 -0.082265 -0.214041 -0.0606082 -0.084765 -0.214386 -0.0600583 -0.082265 -0.213031 -0.0614129 -0.082265 -0.211773 -0.0617 -0.084765 -0.211773 -0.0617 -0.082265 -0.212419 -0.0616273 -0.082265 -0.210515 -0.0614129 -0.084765 -0.209965 -0.0610674 -0.082265 -0.210515 -0.0614129 -0.082265 -0.211128 -0.0616273 -0.082265 -0.209506 -0.0606082 -0.084765 -0.209506 -0.0606082 -0.082265 -0.208946 -0.0594454 -0.082265 -0.20916 -0.0575418 -0.082265 -0.208946 -0.0581547 -0.082265 -0.211773 -0.0559 -0.084765 -0.211773 -0.0559 -0.082265 -0.210515 -0.0561872 -0.082265 -0.210515 -0.0561872 -0.084765 -0.211773 -0.0607 -0.081265 -0.213485 -0.0596244 -0.081265 -0.213673 -0.0588 -0.081265 -0.213626 -0.0592228 -0.081265 -0.212958 -0.0573146 -0.081265 -0.213485 -0.0579757 -0.081265 -0.212196 -0.0569477 -0.081265 -0.212598 -0.0570882 -0.081265 -0.211773 -0.0588 -0.081265 -0.21135 -0.0569477 -0.081265 -0.210288 -0.0576154 -0.081265 -0.210061 -0.0596244 -0.081265 -0.211239 -0.0611399 -0.0813989 -0.21135 -0.0606524 -0.081265 -0.210949 -0.0605119 -0.081265 -0.210589 -0.0602855 -0.081265 -0.210277 -0.0606764 -0.0813989 -0.210288 -0.0599847 -0.081265 -0.209611 -0.0598414 -0.0813989 -0.209921 -0.0592228 -0.081265 -0.209433 -0.058266 -0.0813989 -0.209873 -0.0588 -0.081265 -0.209921 -0.0583773 -0.081265 -0.210061 -0.0579757 -0.081265 -0.210589 -0.0573146 -0.081265 -0.210949 -0.0570882 -0.081265 -0.210732 -0.0566377 -0.0813989 -0.211239 -0.0564602 -0.0813989 -0.211773 -0.0569 -0.081265 -0.211773 -0.0564 -0.0813989 -0.21327 -0.0569236 -0.0813989 -0.213259 -0.0576154 -0.081265 -0.21365 -0.0573037 -0.0813989 -0.213936 -0.0577587 -0.0813989 -0.213626 -0.0583773 -0.081265 -0.213259 -0.0599847 -0.081265 -0.21327 -0.0606764 -0.0813989 -0.212958 -0.0602855 -0.081265 -0.212598 -0.0605119 -0.081265 -0.212307 -0.0611399 -0.0813989 -0.212196 -0.0606524 -0.081265 -0.211773 -0.0612 -0.0813989 -0.210732 -0.0609624 -0.0813989 -0.210049 -0.0609626 -0.081765 -0.209611 -0.0605246 -0.081765 -0.209897 -0.0602964 -0.0813989 -0.209281 -0.0600002 -0.081765 -0.209433 -0.0593341 -0.0813989 -0.209373 -0.0588 -0.0813989 -0.209281 -0.0575999 -0.081765 -0.209611 -0.0577587 -0.0813989 -0.209611 -0.0570755 -0.081765 -0.209897 -0.0573037 -0.0813989 -0.210049 -0.0566375 -0.081765 -0.210277 -0.0569236 -0.0813989 -0.211158 -0.0561034 -0.081765 -0.211773 -0.056034 -0.081765 -0.212389 -0.0561034 -0.081765 -0.212307 -0.0564602 -0.0813989 -0.212815 -0.0566377 -0.0813989 -0.213936 -0.0570755 -0.081765 -0.214265 -0.0575999 -0.081765 -0.21447 -0.0581845 -0.081765 -0.214113 -0.058266 -0.0813989 -0.214173 -0.0588 -0.0813989 -0.21447 -0.0594155 -0.081765 -0.214113 -0.0593341 -0.0813989 -0.214265 -0.0600002 -0.081765 -0.213936 -0.0598414 -0.0813989 -0.21365 -0.0602964 -0.0813989 -0.213498 -0.0609626 -0.081765 -0.212815 -0.0609624 -0.0813989 -0.211158 -0.0614967 -0.081765 -0.210573 -0.0612921 -0.081765 -0.20916 -0.0600583 -0.082265 -0.209077 -0.0594155 -0.081765 -0.208873 -0.0588 -0.082265 -0.209007 -0.0588 -0.081765 -0.209077 -0.0581845 -0.081765 -0.209506 -0.0569919 -0.082265 -0.209965 -0.0565327 -0.082265 -0.210573 -0.0563079 -0.081765 -0.211128 -0.0559728 -0.082265 -0.212419 -0.0559728 -0.082265 -0.213031 -0.0561872 -0.082265 -0.212973 -0.0563079 -0.081765 -0.213498 -0.0566375 -0.081765 -0.213581 -0.0565327 -0.082265 -0.214386 -0.0575418 -0.082265 -0.2146 -0.0581547 -0.082265 -0.214539 -0.0588 -0.081765 -0.214041 -0.0606082 -0.082265 -0.213936 -0.0605246 -0.081765 -0.212973 -0.0612921 -0.081765 -0.212389 -0.0614967 -0.081765 -0.211773 -0.0615661 -0.081765 -0.211239 -0.0411399 -0.0813989 -0.21135 -0.0406524 -0.081265 -0.210949 -0.0405119 -0.081265 -0.210589 -0.0402855 -0.081265 -0.210288 -0.0399847 -0.081265 -0.209897 -0.0402964 -0.0813989 -0.209611 -0.0398414 -0.0813989 -0.209433 -0.0393341 -0.0813989 -0.209373 -0.0388 -0.0813989 -0.209433 -0.038266 -0.0813989 -0.209873 -0.0388 -0.081265 -0.209921 -0.0383773 -0.081265 -0.209611 -0.0377587 -0.0813989 -0.210061 -0.0379757 -0.081265 -0.210288 -0.0376154 -0.081265 -0.210277 -0.0369236 -0.0813989 -0.210589 -0.0373146 -0.081265 -0.211239 -0.0364602 -0.0813989 -0.21135 -0.0369477 -0.081265 -0.211773 -0.0369 -0.081265 -0.212196 -0.0369477 -0.081265 -0.212598 -0.0370882 -0.081265 -0.212958 -0.0373146 -0.081265 -0.21327 -0.0369236 -0.0813989 -0.213485 -0.0379757 -0.081265 -0.213626 -0.0383773 -0.081265 -0.213673 -0.0388 -0.081265 -0.21365 -0.0402964 -0.0813989 -0.213259 -0.0399847 -0.081265 -0.21327 -0.0406764 -0.0813989 -0.212815 -0.0409624 -0.0813989 -0.212307 -0.0411399 -0.0813989 -0.211773 -0.0407 -0.081265 -0.210732 -0.0409624 -0.0813989 -0.210049 -0.0409626 -0.081765 -0.210277 -0.0406764 -0.0813989 -0.209611 -0.0405246 -0.081765 -0.209281 -0.0400002 -0.081765 -0.209007 -0.0388 -0.081765 -0.209077 -0.0381845 -0.081765 -0.209281 -0.0375999 -0.081765 -0.209611 -0.0370755 -0.081765 -0.209897 -0.0373037 -0.0813989 -0.210732 -0.0366377 -0.0813989 -0.211773 -0.036034 -0.081765 -0.212389 -0.0361034 -0.081765 -0.211773 -0.0364 -0.0813989 -0.212307 -0.0364602 -0.0813989 -0.212973 -0.0363079 -0.081765 -0.212815 -0.0366377 -0.0813989 -0.213498 -0.0366375 -0.081765 -0.21365 -0.0373037 -0.0813989 -0.213936 -0.0370755 -0.081765 -0.213936 -0.0377587 -0.0813989 -0.21447 -0.0381845 -0.081765 -0.214113 -0.038266 -0.0813989 -0.214173 -0.0388 -0.0813989 -0.214113 -0.0393341 -0.0813989 -0.213936 -0.0398414 -0.0813989 -0.213936 -0.0405246 -0.081765 -0.213498 -0.0409626 -0.081765 -0.212389 -0.0414967 -0.081765 -0.211773 -0.0412 -0.0813989 -0.211158 -0.0414967 -0.081765 -0.210573 -0.0412921 -0.081765 -0.210515 -0.0414129 -0.082265 -0.209506 -0.0406082 -0.082265 -0.209077 -0.0394155 -0.081765 -0.208946 -0.0394454 -0.082265 -0.209506 -0.0369919 -0.082265 -0.209965 -0.0365327 -0.082265 -0.210049 -0.0366375 -0.081765 -0.210573 -0.0363079 -0.081765 -0.211773 -0.0359 -0.082265 -0.211158 -0.0361034 -0.081765 -0.214041 -0.0369919 -0.082265 -0.214265 -0.0375999 -0.081765 -0.2146 -0.0381547 -0.082265 -0.214539 -0.0388 -0.081765 -0.21447 -0.0394155 -0.081765 -0.214265 -0.0400002 -0.081765 -0.214386 -0.0400583 -0.082265 -0.214041 -0.0406082 -0.082265 -0.213581 -0.0410674 -0.082265 -0.212973 -0.0412921 -0.081765 -0.213031 -0.0414129 -0.082265 -0.212419 -0.0416273 -0.082265 -0.211773 -0.0415661 -0.081765 -0.209892 -0.0539684 -0.090065 -0.209148 -0.0533467 -0.089998 -0.208238 -0.0530133 -0.090065 -0.208399 -0.0528218 -0.089998 -0.207751 -0.0521747 -0.089998 -0.206603 -0.0497117 -0.089998 -0.20684 -0.0470044 -0.089998 -0.20756 -0.0452647 -0.090065 -0.209148 -0.0442534 -0.089998 -0.209023 -0.0440369 -0.090065 -0.209978 -0.0438667 -0.089998 -0.209892 -0.0436317 -0.090065 -0.210862 -0.0436298 -0.089998 -0.210818 -0.0433836 -0.090065 -0.211773 -0.04355 -0.089998 -0.212685 -0.0436298 -0.089998 -0.212728 -0.0433836 -0.090065 -0.213569 -0.0438667 -0.089998 -0.215795 -0.0454254 -0.089998 -0.215309 -0.0445868 -0.090065 -0.21632 -0.046175 -0.089998 -0.216707 -0.0470044 -0.089998 -0.216942 -0.0469189 -0.090065 -0.216943 -0.0497117 -0.089998 -0.217273 -0.0488 -0.090065 -0.216942 -0.0506812 -0.090065 -0.216707 -0.0505956 -0.089998 -0.215986 -0.0523354 -0.090065 -0.215309 -0.0530133 -0.090065 -0.214523 -0.0535632 -0.090065 -0.214398 -0.0533467 -0.089998 -0.213569 -0.0537334 -0.089998 -0.213654 -0.0539684 -0.090065 -0.212685 -0.0539703 -0.089998 -0.211773 -0.05405 -0.089998 -0.210893 -0.0537901 -0.089815 -0.210862 -0.0539703 -0.089998 -0.21004 -0.0535615 -0.089815 -0.209978 -0.0537334 -0.089998 -0.207892 -0.052057 -0.089815 -0.207227 -0.051425 -0.089998 -0.207385 -0.0513335 -0.089815 -0.20684 -0.0505956 -0.089998 -0.206783 -0.0496799 -0.089815 -0.206706 -0.0488 -0.089815 -0.206523 -0.0488 -0.089998 -0.206783 -0.0479202 -0.089815 -0.207012 -0.047067 -0.089815 -0.206603 -0.0478884 -0.089998 -0.207385 -0.0462665 -0.089815 -0.207227 -0.046175 -0.089998 -0.207892 -0.045543 -0.089815 -0.207751 -0.0454254 -0.089998 -0.208399 -0.0447783 -0.089998 -0.208516 -0.0449185 -0.089815 -0.21004 -0.0440386 -0.089815 -0.210893 -0.04381 -0.089815 -0.211773 -0.0437331 -0.089815 -0.214398 -0.0442534 -0.089998 -0.21503 -0.0449185 -0.089815 -0.215148 -0.0447783 -0.089998 -0.215655 -0.045543 -0.089815 -0.216535 -0.047067 -0.089815 -0.216943 -0.0478884 -0.089998 -0.217023 -0.0488 -0.089998 -0.216763 -0.0496799 -0.089815 -0.215655 -0.052057 -0.089815 -0.21632 -0.051425 -0.089998 -0.215795 -0.0521747 -0.089998 -0.215148 -0.0528218 -0.089998 -0.211773 -0.053867 -0.089815 -0.210063 -0.0534985 -0.089565 -0.20924 -0.0531882 -0.089815 -0.209273 -0.0531302 -0.089565 -0.208516 -0.0526816 -0.089815 -0.207075 -0.0505101 -0.089565 -0.207012 -0.0505331 -0.089815 -0.206849 -0.0496683 -0.089565 -0.206849 -0.0479318 -0.089565 -0.207075 -0.0470899 -0.089565 -0.207443 -0.0463 -0.089565 -0.207943 -0.0455861 -0.089565 -0.20924 -0.0444119 -0.089815 -0.209273 -0.0444699 -0.089565 -0.210905 -0.043876 -0.089565 -0.212641 -0.043876 -0.089565 -0.213483 -0.0441016 -0.089565 -0.212653 -0.04381 -0.089815 -0.213506 -0.0440386 -0.089815 -0.214273 -0.0444699 -0.089565 -0.214307 -0.0444119 -0.089815 -0.214987 -0.0449698 -0.089565 -0.215603 -0.0455861 -0.089565 -0.216161 -0.0462665 -0.089815 -0.216472 -0.0470899 -0.089565 -0.216763 -0.0479202 -0.089815 -0.21684 -0.0488 -0.089815 -0.216535 -0.0505331 -0.089815 -0.216472 -0.0505101 -0.089565 -0.216161 -0.0513335 -0.089815 -0.216103 -0.0513 -0.089565 -0.215603 -0.052014 -0.089565 -0.214987 -0.0526303 -0.089565 -0.21503 -0.0526816 -0.089815 -0.214273 -0.0531302 -0.089565 -0.214307 -0.0531882 -0.089815 -0.213483 -0.0534985 -0.089565 -0.213506 -0.0535615 -0.089815 -0.212653 -0.0537901 -0.089815 -0.210818 -0.0433836 -0.084765 -0.210862 -0.0436298 -0.084832 -0.209023 -0.0440369 -0.084765 -0.208399 -0.0447783 -0.084832 -0.208238 -0.0445868 -0.084765 -0.20756 -0.0452647 -0.084765 -0.207227 -0.046175 -0.084832 -0.20701 -0.04605 -0.084765 -0.20684 -0.0470044 -0.084832 -0.206605 -0.0469189 -0.084765 -0.206603 -0.0497117 -0.084832 -0.20684 -0.0505956 -0.084832 -0.206357 -0.0497551 -0.084765 -0.20756 -0.0523354 -0.084765 -0.207751 -0.0521747 -0.084832 -0.208399 -0.0528218 -0.084832 -0.209148 -0.0533467 -0.084832 -0.209023 -0.0535632 -0.084765 -0.212728 -0.0542165 -0.084765 -0.214398 -0.0533467 -0.084832 -0.214523 -0.0535632 -0.084765 -0.215148 -0.0528218 -0.084832 -0.21632 -0.051425 -0.084832 -0.215986 -0.0523354 -0.084765 -0.216707 -0.0505956 -0.084832 -0.216942 -0.0506812 -0.084765 -0.217023 -0.0488 -0.084832 -0.217273 -0.0488 -0.084765 -0.216943 -0.0478884 -0.084832 -0.216707 -0.0470044 -0.084832 -0.216536 -0.04605 -0.084765 -0.21632 -0.046175 -0.084832 -0.215795 -0.0454254 -0.084832 -0.215148 -0.0447783 -0.084832 -0.215309 -0.0445868 -0.084765 -0.214523 -0.0440369 -0.084765 -0.213654 -0.0436317 -0.084765 -0.213569 -0.0438667 -0.084832 -0.212685 -0.0436298 -0.084832 -0.20924 -0.0444119 -0.085015 -0.209978 -0.0438667 -0.084832 -0.209148 -0.0442534 -0.084832 -0.208516 -0.0449185 -0.085015 -0.207385 -0.0462665 -0.085015 -0.207751 -0.0454254 -0.084832 -0.207012 -0.047067 -0.085015 -0.206603 -0.0478884 -0.084832 -0.206523 -0.0488 -0.084832 -0.206706 -0.0488 -0.085015 -0.207012 -0.0505331 -0.085015 -0.207892 -0.052057 -0.085015 -0.207227 -0.051425 -0.084832 -0.208516 -0.0526816 -0.085015 -0.209978 -0.0537334 -0.084832 -0.210862 -0.0539703 -0.084832 -0.211773 -0.05405 -0.084832 -0.212653 -0.0537901 -0.085015 -0.212685 -0.0539703 -0.084832 -0.213506 -0.0535615 -0.085015 -0.213569 -0.0537334 -0.084832 -0.214307 -0.0531882 -0.085015 -0.215655 -0.052057 -0.085015 -0.216161 -0.0513335 -0.085015 -0.215795 -0.0521747 -0.084832 -0.216943 -0.0497117 -0.084832 -0.216535 -0.047067 -0.085015 -0.214398 -0.0442534 -0.084832 -0.213506 -0.0440386 -0.085015 -0.212653 -0.04381 -0.085015 -0.211773 -0.04355 -0.084832 -0.210893 -0.04381 -0.085015 -0.210905 -0.043876 -0.085265 -0.21004 -0.0440386 -0.085015 -0.210063 -0.0441016 -0.085265 -0.209273 -0.0444699 -0.085265 -0.208559 -0.0449698 -0.085265 -0.207943 -0.0455861 -0.085265 -0.207892 -0.045543 -0.085015 -0.206849 -0.0479318 -0.085265 -0.206783 -0.0479202 -0.085015 -0.206773 -0.0488 -0.085265 -0.206783 -0.0496799 -0.085015 -0.206849 -0.0496683 -0.085265 -0.207075 -0.0505101 -0.085265 -0.207443 -0.0513 -0.085265 -0.207385 -0.0513335 -0.085015 -0.207943 -0.052014 -0.085265 -0.208559 -0.0526303 -0.085265 -0.20924 -0.0531882 -0.085015 -0.210063 -0.0534985 -0.085265 -0.21004 -0.0535615 -0.085015 -0.210893 -0.0537901 -0.085015 -0.210905 -0.0537241 -0.085265 -0.211773 -0.0538 -0.085265 -0.211773 -0.053867 -0.085015 -0.212641 -0.0537241 -0.085265 -0.21503 -0.0526816 -0.085015 -0.215603 -0.052014 -0.085265 -0.216535 -0.0505331 -0.085015 -0.216763 -0.0496799 -0.085015 -0.216773 -0.0488 -0.085265 -0.21684 -0.0488 -0.085015 -0.216697 -0.0479318 -0.085265 -0.216763 -0.0479202 -0.085015 -0.216472 -0.0470899 -0.085265 -0.216161 -0.0462665 -0.085015 -0.216103 -0.0463 -0.085265 -0.214987 -0.0449698 -0.085265 -0.215655 -0.045543 -0.085015 -0.21503 -0.0449185 -0.085015 -0.214273 -0.0444699 -0.085265 -0.214307 -0.0444119 -0.085015 -0.213483 -0.0441016 -0.085265 -0.211773 -0.0437331 -0.085015 -0.210515 0.0361871 -0.084765 -0.202273 0.0323268 -0.084765 -0.208946 0.0381546 -0.084765 -0.2146 0.0581546 -0.084765 -0.19553 0.063293 -0.084765 -0.190927 0.0579815 -0.084765 -0.209023 0.0440368 -0.084765 -0.194105 0.0353734 -0.084765 -0.2146 0.0381546 -0.084765 -0.228017 0.0343069 -0.084765 -0.214041 0.0569918 -0.084765 -0.233619 0.0545751 -0.084765 -0.211773 0.0617 -0.084765 -0.202273 0.0652731 -0.084765 -0.198759 0.0647678 -0.084765 -0.209892 0.0436316 -0.084765 -0.210818 0.0433835 -0.084765 -0.211773 0.0433 -0.084765 -0.2307 0.0366318 -0.084765 -0.2146 0.0394453 -0.084765 -0.208946 0.0581546 -0.084765 -0.19178 0.0595434 -0.084765 -0.208946 0.0594453 -0.084765 -0.194105 0.0622265 -0.084765 -0.1898 0.0448 -0.084765 -0.189927 0.0545751 -0.084765 -0.210515 0.0561871 -0.084765 -0.20756 0.0523353 -0.084765 -0.20701 0.05155 -0.084765 -0.206357 0.0478449 -0.084765 -0.189927 0.0430248 -0.084765 -0.213031 0.0361871 -0.084765 -0.221273 0.0323268 -0.084765 -0.228017 0.063293 -0.084765 -0.2146 0.0594453 -0.084765 -0.231766 0.0595434 -0.084765 -0.223048 0.0651461 -0.084765 -0.224787 0.0647678 -0.084765 -0.206357 0.049755 -0.084765 -0.190305 0.0412859 -0.084765 -0.208946 0.0394453 -0.084765 -0.206605 0.0469188 -0.084765 -0.20756 0.0452646 -0.084765 -0.233241 0.0412859 -0.084765 -0.212728 0.0542164 -0.084765 -0.211773 0.0543 -0.084765 -0.210818 0.0542164 -0.084765 -0.213031 0.0414128 -0.084765 -0.213654 0.0436316 -0.084765 -0.216942 0.0506811 -0.084765 -0.215986 0.0523353 -0.084765 -0.213031 0.0561871 -0.084765 -0.215309 0.0530132 -0.084765 -0.214523 0.0535631 -0.084765 -0.214523 0.0440368 -0.084765 -0.231766 0.0380565 -0.084765 -0.215986 0.0452646 -0.084765 -0.21719 0.0478449 -0.084765 -0.227511 0.0402678 -0.113265 -0.22106 0.0441178 -0.113265 -0.220135 0.0426158 -0.113265 -0.196035 0.0402678 -0.113265 -0.202487 0.0441178 -0.113265 -0.195403 0.0412995 -0.113265 -0.19494 0.0424173 -0.113265 -0.201829 0.0457546 -0.113265 -0.194563 0.0448 -0.113265 -0.201457 0.047479 -0.113265 -0.203966 0.055671 -0.113265 -0.198773 0.0596701 -0.113265 -0.197741 0.0590379 -0.113265 -0.196821 0.0582521 -0.113265 -0.196035 0.0573321 -0.113265 -0.226725 0.0393478 -0.113265 -0.194563 0.0528 -0.113265 -0.201383 0.0492413 -0.113265 -0.201607 0.050991 -0.113265 -0.216845 0.0578793 -0.113265 -0.221273 0.0605105 -0.113265 -0.218307 0.0568915 -0.113265 -0.223656 0.0601331 -0.113265 -0.228143 0.0412995 -0.113265 -0.221717 0.0457546 -0.113265 -0.222089 0.047479 -0.113265 -0.228984 0.0488 -0.113265 -0.202273 0.0370894 -0.113265 -0.205949 0.0401835 -0.113265 -0.201067 0.0371844 -0.113265 -0.204577 0.0412916 -0.113265 -0.203412 0.0426158 -0.113265 -0.228606 0.0551826 -0.113265 -0.228143 0.0563005 -0.113265 -0.220629 0.0542528 -0.113265 -0.225805 0.0590379 -0.113265 -0.222479 0.0371844 -0.113265 -0.221273 0.0370894 -0.113265 -0.214394 0.0387355 -0.113265 -0.232978 0.0528 -0.109474 -0.234114 0.0546461 -0.0852911 -0.232753 0.0550835 -0.109474 -0.233996 0.0553308 -0.0852911 -0.232405 0.056417 -0.109474 -0.233258 0.0577643 -0.0852911 -0.233073 0.0581889 -0.0852911 -0.231006 0.0593029 -0.109474 -0.232186 0.0598134 -0.0852911 -0.22955 0.0610767 -0.109474 -0.229768 0.0626039 -0.0852911 -0.231077 0.0612951 -0.0852911 -0.221273 0.0657724 -0.0852911 -0.223119 0.0656403 -0.0852911 -0.223104 0.0643609 -0.109474 -0.224928 0.0652469 -0.0852911 -0.22489 0.0639321 -0.109474 -0.226238 0.0647849 -0.0852911 -0.228287 0.0637131 -0.0852911 -0.228153 0.0622695 -0.109474 -0.202273 0.064505 -0.109474 -0.200427 0.0656403 -0.0852911 -0.198656 0.0639321 -0.109474 -0.198618 0.0652469 -0.0852911 -0.196959 0.0632292 -0.109474 -0.19577 0.0625323 -0.109474 -0.19526 0.0637131 -0.0852911 -0.193778 0.0626039 -0.0852911 -0.192469 0.0612951 -0.0852911 -0.193996 0.0610767 -0.109474 -0.1931 0.0619728 -0.0852911 -0.189433 0.0546461 -0.0852911 -0.190568 0.0528 -0.109474 -0.190712 0.054631 -0.109474 -0.190793 0.0550835 -0.109474 -0.189826 0.0564547 -0.0852911 -0.192541 0.0593029 -0.109474 -0.189301 0.0448 -0.0852911 -0.190712 0.0429689 -0.109474 -0.189433 0.0429538 -0.0852911 -0.190793 0.0425164 -0.109474 -0.191141 0.0411829 -0.109474 -0.191459 0.0403206 -0.109474 -0.189826 0.0411452 -0.0852911 -0.190288 0.0398356 -0.0852911 -0.190473 0.039411 -0.0852911 -0.192541 0.038297 -0.109474 -0.193996 0.0365232 -0.109474 -0.193778 0.0349961 -0.0852911 -0.1931 0.0356271 -0.0852911 -0.192469 0.0363048 -0.0852911 -0.200427 0.0319596 -0.0852911 -0.200442 0.033239 -0.109474 -0.198656 0.0336678 -0.109474 -0.197794 0.0339859 -0.109474 -0.196884 0.0329998 -0.0852911 -0.196959 0.0343707 -0.109474 -0.202273 0.0330949 -0.109474 -0.221273 0.0318275 -0.0852911 -0.224928 0.032353 -0.0852911 -0.226238 0.032815 -0.0852911 -0.226587 0.0343707 -0.109474 -0.227776 0.0350676 -0.109474 -0.229768 0.0349961 -0.0852911 -0.232186 0.0377865 -0.0852911 -0.231077 0.0363048 -0.0852911 -0.22955 0.0365232 -0.109474 -0.232978 0.0448 -0.109474 -0.232087 0.0403206 -0.109474 -0.234246 0.0488 -0.0852911 -0.1898 0.0528 -0.084765 -0.189331 0.0528 -0.0850919 -0.189331 0.0448 -0.0850919 -0.189855 0.0564462 -0.0850919 -0.18955 0.0553308 -0.0852911 -0.189463 0.0546418 -0.0850919 -0.189301 0.0528 -0.0852911 -0.190288 0.0577643 -0.0852911 -0.190473 0.0581889 -0.0852911 -0.19136 0.0598134 -0.0852911 -0.192492 0.0612753 -0.0850919 -0.193798 0.062581 -0.0850919 -0.199742 0.0655231 -0.0852911 -0.195276 0.0636876 -0.0850919 -0.196884 0.0646001 -0.0852911 -0.196897 0.0645726 -0.0850919 -0.197309 0.0647849 -0.0852911 -0.200431 0.0656104 -0.0850919 -0.189437 0.0528 -0.0849208 -0.190501 0.0581763 -0.0850919 -0.190597 0.0581321 -0.0849208 -0.191386 0.059797 -0.0850919 -0.191475 0.0597395 -0.0849208 -0.193868 0.0625006 -0.0849208 -0.195334 0.0635981 -0.0849208 -0.196941 0.0644758 -0.0849208 -0.198627 0.0652179 -0.0850919 -0.198657 0.0651158 -0.0849208 -0.200446 0.0655051 -0.0849208 -0.189603 0.0528 -0.0848056 -0.189568 0.0546267 -0.0849208 -0.189957 0.0564162 -0.0849208 -0.191614 0.0596501 -0.0848056 -0.192573 0.0612056 -0.0849208 -0.19701 0.0643254 -0.0848056 -0.20047 0.0653415 -0.0848056 -0.189732 0.0546032 -0.0848056 -0.190116 0.0563696 -0.0848056 -0.190305 0.056314 -0.084765 -0.190748 0.0580635 -0.0848056 -0.192847 0.0609681 -0.084765 -0.192697 0.0610974 -0.0848056 -0.193976 0.0623757 -0.0848056 -0.195423 0.063459 -0.0848056 -0.198704 0.0649572 -0.0848056 -0.197092 0.0641459 -0.084765 -0.200498 0.0651461 -0.084765 -0.202273 0.0321295 -0.0848056 -0.200431 0.0319895 -0.0850919 -0.197309 0.032815 -0.0852911 -0.198618 0.032353 -0.0852911 -0.198627 0.032382 -0.0850919 -0.199742 0.0320768 -0.0852911 -0.202273 0.0318578 -0.0850919 -0.202273 0.0318275 -0.0852911 -0.196897 0.0330273 -0.0850919 -0.195276 0.0339123 -0.0850919 -0.19526 0.0338869 -0.0852911 -0.18955 0.0422692 -0.0852911 -0.192492 0.0363246 -0.0850919 -0.19136 0.0377865 -0.0852911 -0.198657 0.0324841 -0.0849208 -0.195334 0.0340018 -0.0849208 -0.193798 0.0350189 -0.0850919 -0.191386 0.0378029 -0.0850919 -0.190501 0.0394236 -0.0850919 -0.189855 0.0411537 -0.0850919 -0.189957 0.0411837 -0.0849208 -0.189463 0.0429581 -0.0850919 -0.200446 0.0320948 -0.0849208 -0.20047 0.0322584 -0.0848056 -0.198704 0.0326427 -0.0848056 -0.196941 0.0331241 -0.0849208 -0.193868 0.0350993 -0.0849208 -0.193976 0.0352242 -0.0848056 -0.192573 0.0363943 -0.0849208 -0.192697 0.0365026 -0.0848056 -0.191475 0.0378604 -0.0849208 -0.191614 0.0379498 -0.0848056 -0.190597 0.0394678 -0.0849208 -0.190748 0.0395365 -0.0848056 -0.189568 0.0429732 -0.0849208 -0.189437 0.0448 -0.0849208 -0.189603 0.0448 -0.0848056 -0.200498 0.0324538 -0.084765 -0.198759 0.0328321 -0.084765 -0.19701 0.0332745 -0.0848056 -0.195423 0.0341409 -0.0848056 -0.197092 0.033454 -0.084765 -0.19553 0.0343069 -0.084765 -0.192847 0.0366318 -0.084765 -0.19178 0.0380565 -0.084765 -0.190927 0.0396184 -0.084765 -0.190116 0.0412303 -0.0848056 -0.189732 0.0429968 -0.0848056 -0.202273 0.0654704 -0.0848056 -0.202273 0.0656358 -0.0849208 -0.221273 0.0654704 -0.0848056 -0.202273 0.0657422 -0.0850919 -0.202273 0.0657724 -0.0852911 -0.221273 0.0321295 -0.0848056 -0.202273 0.0319642 -0.0849208 -0.221273 0.0319642 -0.0849208 -0.221273 0.0656358 -0.0849208 -0.2231 0.0655051 -0.0849208 -0.223115 0.0656104 -0.0850919 -0.22665 0.0645726 -0.0850919 -0.224919 0.0652179 -0.0850919 -0.223804 0.0655231 -0.0852911 -0.221273 0.0657422 -0.0850919 -0.226662 0.0646001 -0.0852911 -0.230446 0.0619728 -0.0852911 -0.232161 0.059797 -0.0850919 -0.233691 0.0564462 -0.0850919 -0.23372 0.0564547 -0.0852911 -0.234084 0.0546418 -0.0850919 -0.22827 0.0636876 -0.0850919 -0.226605 0.0644758 -0.0849208 -0.228213 0.0635981 -0.0849208 -0.229749 0.062581 -0.0850919 -0.231054 0.0612753 -0.0850919 -0.230974 0.0612056 -0.0849208 -0.233046 0.0581763 -0.0850919 -0.232949 0.0581321 -0.0849208 -0.233978 0.0546267 -0.0849208 -0.234215 0.0528 -0.0850919 -0.224889 0.0651158 -0.0849208 -0.224843 0.0649572 -0.0848056 -0.226537 0.0643254 -0.0848056 -0.228123 0.063459 -0.0848056 -0.229679 0.0625006 -0.0849208 -0.230849 0.0610974 -0.0848056 -0.232071 0.0597395 -0.0849208 -0.231932 0.0596501 -0.0848056 -0.232799 0.0580635 -0.0848056 -0.233589 0.0564162 -0.0849208 -0.234109 0.0528 -0.0849208 -0.233815 0.0546032 -0.0848056 -0.221273 0.0652731 -0.084765 -0.223076 0.0653415 -0.0848056 -0.226455 0.0641459 -0.084765 -0.229571 0.0623757 -0.0848056 -0.229441 0.0622265 -0.084765 -0.2307 0.0609681 -0.084765 -0.232619 0.0579815 -0.084765 -0.23343 0.0563696 -0.0848056 -0.233241 0.056314 -0.084765 -0.233944 0.0528 -0.0848056 -0.233046 0.0394236 -0.0850919 -0.23372 0.0411452 -0.0852911 -0.234084 0.0429581 -0.0850919 -0.233996 0.0422692 -0.0852911 -0.234215 0.0448 -0.0850919 -0.234114 0.0429538 -0.0852911 -0.234246 0.0448 -0.0852911 -0.233258 0.0398356 -0.0852911 -0.233073 0.039411 -0.0852911 -0.231054 0.0363246 -0.0850919 -0.230446 0.0356271 -0.0852911 -0.228287 0.0338869 -0.0852911 -0.22827 0.0339123 -0.0850919 -0.226662 0.0329998 -0.0852911 -0.224919 0.032382 -0.0850919 -0.223804 0.0320768 -0.0852911 -0.223119 0.0319596 -0.0852911 -0.223115 0.0319895 -0.0850919 -0.233691 0.0411537 -0.0850919 -0.232949 0.0394678 -0.0849208 -0.232161 0.0378029 -0.0850919 -0.232071 0.0378604 -0.0849208 -0.230974 0.0363943 -0.0849208 -0.229749 0.0350189 -0.0850919 -0.22665 0.0330273 -0.0850919 -0.226605 0.0331241 -0.0849208 -0.224889 0.0324841 -0.0849208 -0.221273 0.0318578 -0.0850919 -0.2231 0.0320948 -0.0849208 -0.233978 0.0429732 -0.0849208 -0.233589 0.0411837 -0.0849208 -0.232799 0.0395365 -0.0848056 -0.231932 0.0379498 -0.0848056 -0.229679 0.0350993 -0.0849208 -0.229571 0.0352242 -0.0848056 -0.228213 0.0340018 -0.0849208 -0.226537 0.0332745 -0.0848056 -0.224843 0.0326427 -0.0848056 -0.233815 0.0429968 -0.0848056 -0.23343 0.0412303 -0.0848056 -0.233619 0.0430248 -0.084765 -0.232619 0.0396184 -0.084765 -0.230849 0.0365026 -0.0848056 -0.229441 0.0353734 -0.084765 -0.228123 0.0341409 -0.0848056 -0.226455 0.033454 -0.084765 -0.224787 0.0328321 -0.084765 -0.223076 0.0322584 -0.0848056 -0.223048 0.0324538 -0.084765 -0.233746 0.0528 -0.084765 -0.234246 0.0528 -0.0852911 -0.233746 0.0448 -0.084765 -0.233746 0.0488 -0.084765 -0.233944 0.0488 -0.0848056 -0.233944 0.0448 -0.0848056 -0.234109 0.0488 -0.0849208 -0.234109 0.0448 -0.0849208 -0.234215 0.0488 -0.0850919 -0.221273 0.064505 -0.109474 -0.202273 0.0643253 -0.110468 -0.221273 0.0641431 -0.11094 -0.202273 0.0639027 -0.111385 -0.221273 0.0639027 -0.111385 -0.221273 0.0632639 -0.112166 -0.221273 0.0624497 -0.112763 -0.202273 0.0632639 -0.112166 -0.202273 0.0624497 -0.112763 -0.221273 0.0619927 -0.11298 -0.221273 0.061512 -0.113138 -0.232087 0.0572793 -0.109474 -0.230597 0.0595744 -0.110468 -0.225753 0.063614 -0.109474 -0.222479 0.0604155 -0.113265 -0.230804 0.0543095 -0.112763 -0.230923 0.0528 -0.112763 -0.231608 0.0544369 -0.112166 -0.22301 0.063766 -0.111385 -0.22291 0.0631351 -0.112166 -0.222783 0.0623309 -0.112763 -0.221273 0.0643253 -0.110468 -0.224835 0.0637613 -0.110468 -0.223557 0.0642801 -0.109474 -0.224704 0.0633593 -0.111385 -0.223076 0.0641835 -0.110468 -0.224507 0.0627518 -0.112166 -0.222636 0.0614047 -0.113138 -0.226587 0.0632292 -0.109474 -0.226314 0.0626925 -0.111385 -0.226024 0.0621234 -0.112166 -0.224255 0.0619774 -0.112763 -0.223965 0.0610856 -0.113138 -0.225228 0.0605624 -0.113138 -0.224774 0.0596701 -0.113265 -0.227776 0.0625323 -0.109474 -0.226506 0.0630692 -0.110468 -0.227799 0.0617822 -0.111385 -0.227424 0.0612655 -0.112166 -0.225654 0.061398 -0.112763 -0.226394 0.0598481 -0.113138 -0.226725 0.0582521 -0.113265 -0.226945 0.0606068 -0.112763 -0.228672 0.0601991 -0.112166 -0.228048 0.0621242 -0.110468 -0.229423 0.0609496 -0.110468 -0.227434 0.0589603 -0.113138 -0.228097 0.0596234 -0.112763 -0.229124 0.0606508 -0.111385 -0.229739 0.0589505 -0.112166 -0.230743 0.05968 -0.109474 -0.231702 0.0581139 -0.109474 -0.231542 0.0580324 -0.110468 -0.230255 0.059326 -0.111385 -0.229036 0.0567551 -0.113138 -0.22908 0.0584719 -0.112763 -0.228321 0.0579208 -0.113138 -0.227511 0.0573321 -0.113265 -0.231166 0.0578405 -0.111385 -0.231833 0.0562309 -0.111385 -0.230597 0.0575505 -0.112166 -0.230451 0.0557819 -0.112763 -0.229871 0.0571809 -0.112763 -0.232657 0.0546029 -0.110468 -0.232234 0.0563615 -0.110468 -0.231225 0.0560335 -0.112166 -0.229878 0.0541628 -0.113138 -0.228889 0.0540061 -0.113265 -0.229559 0.0554921 -0.113138 -0.232376 0.0528 -0.111385 -0.232239 0.0545368 -0.111385 -0.232834 0.054631 -0.109474 -0.232799 0.0528 -0.110468 -0.195393 0.0622695 -0.109474 -0.191844 0.0581139 -0.109474 -0.19089 0.0546029 -0.110468 -0.202273 0.0605105 -0.113265 -0.193561 0.0528 -0.113138 -0.194658 0.0540061 -0.113265 -0.193668 0.0541628 -0.113138 -0.19308 0.0528 -0.11298 -0.20091 0.0614047 -0.113138 -0.202273 0.061512 -0.113138 -0.202273 0.0619927 -0.11298 -0.200636 0.0631351 -0.112166 -0.191938 0.0544369 -0.112166 -0.195403 0.0563005 -0.113265 -0.193988 0.0554921 -0.113138 -0.192321 0.0560335 -0.112166 -0.191714 0.0562309 -0.111385 -0.19295 0.0575505 -0.112166 -0.19093 0.0528 -0.11094 -0.191307 0.0545368 -0.111385 -0.193096 0.0557819 -0.112763 -0.192742 0.0543095 -0.112763 -0.19494 0.0551826 -0.113265 -0.191312 0.0563615 -0.110468 -0.191459 0.0572793 -0.109474 -0.191141 0.056417 -0.109474 -0.192004 0.0580324 -0.110468 -0.193291 0.059326 -0.111385 -0.192381 0.0578405 -0.111385 -0.193808 0.0589505 -0.112166 -0.193675 0.0571809 -0.112763 -0.194511 0.0567551 -0.113138 -0.195225 0.0579208 -0.113138 -0.196113 0.0589603 -0.113138 -0.194466 0.0584719 -0.112763 -0.19545 0.0596234 -0.112763 -0.192949 0.0595744 -0.110468 -0.192804 0.05968 -0.109474 -0.197152 0.0598481 -0.113138 -0.196123 0.0612655 -0.112166 -0.194874 0.0601991 -0.112166 -0.194422 0.0606508 -0.111385 -0.194124 0.0609496 -0.110468 -0.195499 0.0621242 -0.110468 -0.195747 0.0617822 -0.111385 -0.197523 0.0621234 -0.112166 -0.196601 0.0606068 -0.112763 -0.198318 0.0605624 -0.113138 -0.197794 0.063614 -0.109474 -0.198712 0.0637613 -0.110468 -0.197041 0.0630692 -0.110468 -0.198842 0.0633593 -0.111385 -0.197233 0.0626925 -0.111385 -0.199291 0.0619774 -0.112763 -0.197892 0.061398 -0.112763 -0.200442 0.0643609 -0.109474 -0.19999 0.0642801 -0.109474 -0.200536 0.063766 -0.111385 -0.19904 0.0627518 -0.112166 -0.200764 0.0623309 -0.112763 -0.199581 0.0610856 -0.113138 -0.201067 0.0604155 -0.113265 -0.199891 0.0601331 -0.113265 -0.202273 0.0641431 -0.11094 -0.20047 0.0641835 -0.110468 -0.228984 0.0528 -0.113265 -0.229985 0.0528 -0.113138 -0.230466 0.0528 -0.11298 -0.231737 0.0528 -0.112166 -0.232616 0.0488 -0.11094 -0.232616 0.0528 -0.11094 -0.19308 0.0448 -0.11298 -0.192623 0.0528 -0.112763 -0.192623 0.0448 -0.112763 -0.191809 0.0528 -0.112166 -0.19117 0.0528 -0.111385 -0.19117 0.0448 -0.111385 -0.19093 0.0448 -0.11094 -0.190748 0.0448 -0.110468 -0.190568 0.0448 -0.109474 -0.190748 0.0528 -0.110468 -0.229985 0.0448 -0.113138 -0.230923 0.0448 -0.112763 -0.230466 0.0488 -0.11298 -0.231737 0.0488 -0.112166 -0.231737 0.0448 -0.112166 -0.232376 0.0448 -0.111385 -0.232978 0.0488 -0.109474 -0.192804 0.0379199 -0.109474 -0.193668 0.0434371 -0.113138 -0.202273 0.0360879 -0.113138 -0.200764 0.035269 -0.112763 -0.193561 0.0448 -0.113138 -0.191938 0.043163 -0.112166 -0.191809 0.0448 -0.112166 -0.200536 0.0338339 -0.111385 -0.202273 0.0334569 -0.11094 -0.200636 0.0344648 -0.112166 -0.202273 0.0336972 -0.111385 -0.202273 0.034336 -0.112166 -0.20047 0.0334165 -0.110468 -0.19999 0.0333198 -0.109474 -0.198842 0.0342407 -0.111385 -0.199891 0.0374668 -0.113265 -0.20091 0.0361952 -0.113138 -0.198712 0.0338387 -0.110468 -0.197523 0.0354765 -0.112166 -0.197892 0.036202 -0.112763 -0.19904 0.0348482 -0.112166 -0.199291 0.0356225 -0.112763 -0.199581 0.0365143 -0.113138 -0.198773 0.0379298 -0.113265 -0.195393 0.0353304 -0.109474 -0.195499 0.0354757 -0.110468 -0.19577 0.0350676 -0.109474 -0.197041 0.0345308 -0.110468 -0.197233 0.0349074 -0.111385 -0.198318 0.0370375 -0.113138 -0.197741 0.038562 -0.113265 -0.196821 0.0393478 -0.113265 -0.197152 0.0377518 -0.113138 -0.196601 0.0369931 -0.112763 -0.196123 0.0363345 -0.112166 -0.195747 0.0358177 -0.111385 -0.194422 0.0369492 -0.111385 -0.194124 0.0366503 -0.110468 -0.196113 0.0386396 -0.113138 -0.19545 0.0379765 -0.112763 -0.194874 0.0374008 -0.112166 -0.194466 0.039128 -0.112763 -0.193291 0.0382739 -0.111385 -0.192949 0.0380255 -0.110468 -0.191844 0.039486 -0.109474 -0.192004 0.0395675 -0.110468 -0.193808 0.0386494 -0.112166 -0.193675 0.0404191 -0.112763 -0.194511 0.0408448 -0.113138 -0.195225 0.0396792 -0.113138 -0.191312 0.0412384 -0.110468 -0.191714 0.041369 -0.111385 -0.192381 0.0397594 -0.111385 -0.19295 0.0400494 -0.112166 -0.193096 0.041818 -0.112763 -0.193988 0.0421078 -0.113138 -0.192321 0.0415664 -0.112166 -0.192742 0.0432904 -0.112763 -0.194658 0.0435938 -0.113265 -0.191307 0.0430631 -0.111385 -0.19089 0.042997 -0.110468 -0.22489 0.0336678 -0.109474 -0.231702 0.039486 -0.109474 -0.228984 0.0448 -0.113265 -0.228889 0.0435938 -0.113265 -0.221273 0.0360879 -0.113138 -0.221273 0.0356072 -0.11298 -0.222783 0.035269 -0.112763 -0.22291 0.0344648 -0.112166 -0.232657 0.042997 -0.110468 -0.232616 0.0448 -0.11094 -0.231608 0.043163 -0.112166 -0.230466 0.0448 -0.11298 -0.232834 0.0429689 -0.109474 -0.232799 0.0448 -0.110468 -0.232405 0.0411829 -0.109474 -0.232234 0.0412384 -0.110468 -0.232753 0.0425164 -0.109474 -0.232239 0.0430631 -0.111385 -0.231225 0.0415664 -0.112166 -0.230804 0.0432904 -0.112763 -0.229559 0.0421078 -0.113138 -0.229878 0.0434371 -0.113138 -0.231542 0.0395675 -0.110468 -0.231833 0.041369 -0.111385 -0.230451 0.041818 -0.112763 -0.228606 0.0424173 -0.113265 -0.231006 0.038297 -0.109474 -0.230597 0.0380255 -0.110468 -0.231166 0.0397594 -0.111385 -0.230597 0.0400494 -0.112166 -0.229739 0.0386494 -0.112166 -0.229871 0.0404191 -0.112763 -0.229036 0.0408448 -0.113138 -0.228321 0.0396792 -0.113138 -0.227434 0.0386396 -0.113138 -0.22908 0.039128 -0.112763 -0.228672 0.0374008 -0.112166 -0.230255 0.0382739 -0.111385 -0.229124 0.0369492 -0.111385 -0.229423 0.0366503 -0.110468 -0.230743 0.0379199 -0.109474 -0.225805 0.038562 -0.113265 -0.228097 0.0379765 -0.112763 -0.227424 0.0363345 -0.112166 -0.227799 0.0358177 -0.111385 -0.228048 0.0354757 -0.110468 -0.228153 0.0353304 -0.109474 -0.226024 0.0354765 -0.112166 -0.226945 0.0369931 -0.112763 -0.225228 0.0370375 -0.113138 -0.226394 0.0377518 -0.113138 -0.225753 0.0339859 -0.109474 -0.226506 0.0345308 -0.110468 -0.226314 0.0349074 -0.111385 -0.225654 0.036202 -0.112763 -0.224255 0.0356225 -0.112763 -0.223656 0.0374668 -0.113265 -0.224774 0.0379298 -0.113265 -0.223557 0.0333198 -0.109474 -0.224835 0.0338387 -0.110468 -0.224704 0.0342407 -0.111385 -0.224507 0.0348482 -0.112166 -0.223965 0.0365143 -0.113138 -0.222636 0.0361952 -0.113138 -0.221273 0.034336 -0.112166 -0.221273 0.0336972 -0.111385 -0.22301 0.0338339 -0.111385 -0.223076 0.0334165 -0.110468 -0.223104 0.033239 -0.109474 -0.202273 0.0332746 -0.110468 -0.221273 0.0330949 -0.109474 -0.221273 0.0332746 -0.110468 -0.221273 0.0334569 -0.11094 -0.202273 0.0351502 -0.112763 -0.202273 0.0356072 -0.11298 -0.221273 0.0351502 -0.112763 -0.211061 0.0404302 -0.111265 -0.207069 0.0418405 -0.111265 -0.205834 0.0428603 -0.111265 -0.20502 0.043805 -0.111265 -0.204499 0.0446 -0.090065 -0.203373 0.0488 -0.090065 -0.203441 0.047733 -0.111265 -0.203659 0.0466259 -0.111265 -0.203659 0.050974 -0.111265 -0.203373 0.0488 -0.111265 -0.203979 0.051932 -0.111265 -0.204499 0.053 -0.111265 -0.206496 0.0553355 -0.111265 -0.205468 0.0543496 -0.111265 -0.209599 0.0569137 -0.090065 -0.208975 0.0567201 -0.111265 -0.207677 0.0561333 -0.111265 -0.211773 0.0572 -0.111265 -0.213947 0.0569137 -0.090065 -0.215973 0.0560746 -0.090065 -0.218079 0.0543496 -0.111265 -0.219048 0.053 -0.090065 -0.219985 0.0505697 -0.111265 -0.219887 0.050974 -0.090065 -0.219274 0.0450182 -0.111265 -0.219805 0.0463402 -0.111265 -0.219887 0.0466259 -0.111265 -0.218527 0.043805 -0.111265 -0.217713 0.0428603 -0.111265 -0.217713 0.0428603 -0.090065 -0.217585 0.0427355 -0.111265 -0.215233 0.0411456 -0.111265 -0.211773 0.0404 -0.090065 -0.212486 0.0404302 -0.111265 -0.213947 0.0406862 -0.090065 -0.21389 0.040671 -0.111265 -0.215309 0.0530132 -0.090065 -0.217713 0.0547397 -0.090065 -0.215986 0.0523353 -0.090065 -0.21719 0.049755 -0.090065 -0.220173 0.0488 -0.090065 -0.219887 0.0466259 -0.090065 -0.210818 0.0542164 -0.090065 -0.211773 0.0572 -0.090065 -0.212728 0.0542164 -0.090065 -0.213654 0.0539683 -0.090065 -0.209892 0.0436316 -0.090065 -0.207573 0.0415253 -0.090065 -0.205834 0.0428603 -0.090065 -0.217273 0.0488 -0.090065 -0.21719 0.0478449 -0.090065 -0.216942 0.0469188 -0.090065 -0.219048 0.0446 -0.090065 -0.212728 0.0433835 -0.090065 -0.209599 0.0406862 -0.090065 -0.215973 0.0415253 -0.090065 -0.215309 0.0445867 -0.090065 -0.203659 0.0466259 -0.090065 -0.206605 0.0469188 -0.090065 -0.206357 0.0478449 -0.090065 -0.206273 0.0488 -0.090065 -0.206357 0.049755 -0.090065 -0.203659 0.050974 -0.090065 -0.206605 0.0506811 -0.090065 -0.204499 0.053 -0.090065 -0.20701 0.05155 -0.090065 -0.20756 0.0523353 -0.090065 -0.205834 0.0547397 -0.090065 -0.207573 0.0560746 -0.090065 -0.209023 0.0535631 -0.090065 -0.213947 0.0569137 -0.111265 -0.214572 0.0567201 -0.111265 -0.214622 0.0568637 -0.11203 -0.215944 0.0562662 -0.11203 -0.21587 0.0561333 -0.111265 -0.215973 0.0560746 -0.111265 -0.21705 0.0553355 -0.111265 -0.217713 0.0547397 -0.111265 -0.218193 0.0544502 -0.11203 -0.218926 0.0532041 -0.111265 -0.219056 0.053284 -0.11203 -0.219048 0.053 -0.111265 -0.219709 0.0519887 -0.11203 -0.219567 0.051932 -0.111265 -0.219887 0.050974 -0.111265 -0.220166 0.0491565 -0.111265 -0.220133 0.0506017 -0.11203 -0.220318 0.0491629 -0.11203 -0.220173 0.0488 -0.111265 -0.220105 0.047733 -0.111265 -0.219048 0.0446 -0.111265 -0.216477 0.0418405 -0.111265 -0.215973 0.0415253 -0.111265 -0.215296 0.0410069 -0.11203 -0.211773 0.0404 -0.111265 -0.211048 0.0402785 -0.11203 -0.208313 0.0411456 -0.111265 -0.209618 0.0405237 -0.11203 -0.209657 0.040671 -0.111265 -0.206984 0.0417143 -0.11203 -0.207573 0.0415253 -0.111265 -0.205961 0.0427355 -0.111265 -0.205856 0.0426256 -0.11203 -0.204897 0.0437145 -0.11203 -0.204499 0.0446 -0.111265 -0.204273 0.0450182 -0.111265 -0.203741 0.0463402 -0.111265 -0.203381 0.0491565 -0.111265 -0.203562 0.0505697 -0.111265 -0.20462 0.0532041 -0.111265 -0.205834 0.0547397 -0.111265 -0.207573 0.0560746 -0.111265 -0.207602 0.0562662 -0.11203 -0.208924 0.0568637 -0.11203 -0.209599 0.0569137 -0.111265 -0.213193 0.0570791 -0.111265 -0.213219 0.0572292 -0.11203 -0.211773 0.0573522 -0.11203 -0.210354 0.0570791 -0.111265 -0.210328 0.0572292 -0.11203 -0.20878 0.0572725 -0.112679 -0.206401 0.0554539 -0.11203 -0.205028 0.0547366 -0.112679 -0.205353 0.0544502 -0.11203 -0.204491 0.053284 -0.11203 -0.203838 0.0519887 -0.11203 -0.203435 0.0521504 -0.112679 -0.203413 0.0506017 -0.11203 -0.202989 0.0506931 -0.112679 -0.202796 0.0491813 -0.112679 -0.203229 0.0491629 -0.11203 -0.20329 0.0477137 -0.11203 -0.203596 0.0462957 -0.11203 -0.204137 0.0449497 -0.11203 -0.204549 0.0434567 -0.112679 -0.205556 0.0423126 -0.112679 -0.206741 0.0413551 -0.112679 -0.208251 0.0410069 -0.11203 -0.211011 0.0398465 -0.112679 -0.212498 0.0402785 -0.11203 -0.213928 0.0405237 -0.11203 -0.215474 0.0406119 -0.112679 -0.216805 0.0413551 -0.112679 -0.217991 0.0423126 -0.112679 -0.216562 0.0417143 -0.11203 -0.217691 0.0426256 -0.11203 -0.218998 0.0434567 -0.112679 -0.218649 0.0437145 -0.11203 -0.21941 0.0449497 -0.11203 -0.219797 0.0447545 -0.112679 -0.219951 0.0462957 -0.11203 -0.220256 0.0477137 -0.11203 -0.220557 0.0506931 -0.112679 -0.219425 0.0535113 -0.112679 -0.217418 0.0557912 -0.112679 -0.217146 0.0554539 -0.11203 -0.214767 0.0572725 -0.112679 -0.210255 0.0576565 -0.112679 -0.208564 0.0578842 -0.113113 -0.207391 0.0566447 -0.112679 -0.206128 0.0557912 -0.112679 -0.203569 0.0538515 -0.113113 -0.204122 0.0535113 -0.112679 -0.202355 0.0508298 -0.113113 -0.202147 0.0492089 -0.113113 -0.20286 0.0476586 -0.112679 -0.202561 0.0459787 -0.113113 -0.203181 0.0461687 -0.112679 -0.20317 0.0444624 -0.113113 -0.20375 0.0447545 -0.112679 -0.205107 0.0418442 -0.113113 -0.206378 0.0408176 -0.113113 -0.208072 0.0406119 -0.112679 -0.209345 0.0394762 -0.113113 -0.210956 0.0392 -0.113113 -0.209509 0.0401041 -0.112679 -0.212535 0.0398465 -0.112679 -0.214037 0.0401041 -0.112679 -0.214201 0.0394762 -0.113113 -0.215742 0.0400206 -0.113113 -0.219519 0.0430709 -0.113113 -0.220365 0.0461687 -0.112679 -0.220986 0.0459787 -0.113113 -0.22133 0.0475762 -0.113113 -0.221399 0.0492089 -0.113113 -0.220686 0.0476586 -0.112679 -0.220751 0.0491813 -0.112679 -0.221192 0.0508298 -0.113113 -0.220713 0.0523923 -0.113113 -0.220111 0.0521504 -0.112679 -0.219977 0.0538515 -0.113113 -0.218519 0.0547366 -0.112679 -0.216156 0.0566447 -0.112679 -0.213292 0.0576565 -0.112679 -0.213401 0.058296 -0.113113 -0.211773 0.0577857 -0.112679 -0.210145 0.058296 -0.113113 -0.208309 0.0586059 -0.113265 -0.206701 0.0578793 -0.113265 -0.207074 0.0572111 -0.113113 -0.20524 0.0568915 -0.113265 -0.205721 0.056296 -0.113113 -0.204541 0.0551653 -0.113113 -0.202917 0.0542528 -0.113265 -0.202123 0.0526777 -0.113265 -0.202833 0.0523923 -0.113113 -0.202217 0.0475762 -0.113113 -0.204027 0.0430709 -0.113113 -0.207805 0.0400206 -0.113113 -0.207489 0.0393232 -0.113265 -0.209153 0.0387355 -0.113265 -0.210891 0.0384374 -0.113265 -0.212655 0.0384374 -0.113265 -0.21259 0.0392 -0.113113 -0.216057 0.0393232 -0.113265 -0.217597 0.0401835 -0.113265 -0.217168 0.0408176 -0.113113 -0.21844 0.0418442 -0.113113 -0.218969 0.0412916 -0.113265 -0.220376 0.0444624 -0.113113 -0.222164 0.0492413 -0.113265 -0.22194 0.050991 -0.113265 -0.221423 0.0526777 -0.113265 -0.21958 0.055671 -0.113265 -0.219006 0.0551653 -0.113113 -0.217826 0.056296 -0.113113 -0.216472 0.0572111 -0.113113 -0.215238 0.0586059 -0.113265 -0.213531 0.0590504 -0.113265 -0.214983 0.0578842 -0.113113 -0.211773 0.0592 -0.113265 -0.211773 0.0584346 -0.113113 -0.210016 0.0590504 -0.113265 -0.212641 0.0438759 -0.089565 -0.213483 0.0441015 -0.089565 -0.215603 0.045586 -0.085265 -0.216103 0.0463 -0.089565 -0.216103 0.0463 -0.085265 -0.216472 0.0470899 -0.085265 -0.216697 0.0479317 -0.089565 -0.216773 0.0488 -0.085265 -0.216773 0.0488 -0.089565 -0.216697 0.0496682 -0.085265 -0.216472 0.0505101 -0.085265 -0.216697 0.0496682 -0.089565 -0.216472 0.0505101 -0.089565 -0.216103 0.0513 -0.089565 -0.215603 0.0520139 -0.085265 -0.215603 0.0520139 -0.089565 -0.214273 0.0531301 -0.089565 -0.213483 0.0534984 -0.085265 -0.212641 0.053724 -0.085265 -0.211773 0.0538 -0.085265 -0.211773 0.0538 -0.089565 -0.210905 0.053724 -0.085265 -0.210063 0.0534984 -0.085265 -0.209273 0.0531301 -0.085265 -0.209273 0.0531301 -0.089565 -0.208559 0.0526302 -0.085265 -0.207943 0.0520139 -0.085265 -0.207943 0.0520139 -0.089565 -0.207443 0.0513 -0.089565 -0.206849 0.0496682 -0.085265 -0.206849 0.0496682 -0.089565 -0.206773 0.0488 -0.085265 -0.206773 0.0488 -0.089565 -0.206849 0.0479317 -0.089565 -0.207443 0.0463 -0.089565 -0.207943 0.045586 -0.089565 -0.208559 0.0449697 -0.089565 -0.209273 0.0444698 -0.089565 -0.210063 0.0441015 -0.085265 -0.211773 0.0438 -0.085265 -0.211773 0.0438 -0.089565 -0.213581 0.0610673 -0.082265 -0.213031 0.0614128 -0.084765 -0.214041 0.0606081 -0.084765 -0.2146 0.0594453 -0.082265 -0.214386 0.0575417 -0.082265 -0.2146 0.0581546 -0.082265 -0.214041 0.0569918 -0.082265 -0.212419 0.0559727 -0.082265 -0.213031 0.0561871 -0.082265 -0.211773 0.0559 -0.084765 -0.211773 0.0559 -0.082265 -0.209506 0.0569918 -0.084765 -0.209965 0.0565326 -0.082265 -0.209506 0.0569918 -0.082265 -0.208946 0.0581546 -0.082265 -0.208946 0.0594453 -0.082265 -0.210515 0.0614128 -0.084765 -0.209506 0.0606081 -0.084765 -0.209506 0.0606081 -0.082265 -0.20916 0.0600582 -0.082265 -0.212419 0.0616273 -0.082265 -0.211128 0.0616273 -0.082265 -0.210515 0.0614128 -0.082265 -0.212196 0.0569476 -0.081265 -0.213626 0.0583772 -0.081265 -0.213485 0.0579756 -0.081265 -0.213485 0.0596243 -0.081265 -0.213626 0.0592227 -0.081265 -0.211773 0.0588 -0.081265 -0.213673 0.0588 -0.081265 -0.212958 0.0602854 -0.081265 -0.21135 0.0606523 -0.081265 -0.212196 0.0606523 -0.081265 -0.212598 0.0605118 -0.081265 -0.210061 0.0596243 -0.081265 -0.210288 0.0599846 -0.081265 -0.210061 0.0579756 -0.081265 -0.21135 0.0569476 -0.081265 -0.210949 0.0570881 -0.081265 -0.211773 0.0417 -0.084765 -0.214041 0.0406081 -0.084765 -0.214673 0.0388 -0.082265 -0.2146 0.0394453 -0.082265 -0.214386 0.0375417 -0.082265 -0.214041 0.0369918 -0.084765 -0.211773 0.0359 -0.084765 -0.213031 0.0361871 -0.082265 -0.209965 0.0365326 -0.082265 -0.211128 0.0359727 -0.082265 -0.209506 0.0369918 -0.084765 -0.209506 0.0406081 -0.084765 -0.208873 0.0388 -0.082265 -0.210515 0.0414128 -0.084765 -0.209506 0.0406081 -0.082265 -0.211773 0.0417 -0.082265 -0.211128 0.0416273 -0.082265 -0.209965 0.0410673 -0.082265 -0.21135 0.0369476 -0.081265 -0.211773 0.0388 -0.081265 -0.213485 0.0379756 -0.081265 -0.213259 0.0376153 -0.081265 -0.212958 0.0373145 -0.081265 -0.213673 0.0388 -0.081265 -0.212958 0.0402854 -0.081265 -0.213259 0.0399846 -0.081265 -0.213485 0.0396243 -0.081265 -0.21135 0.0406523 -0.081265 -0.211773 0.0407 -0.081265 -0.210288 0.0399846 -0.081265 -0.209873 0.0388 -0.081265 -0.210949 0.0370881 -0.081265 -0.210589 0.0373145 -0.081265 -0.210288 0.0376153 -0.081265 -0.211773 0.0369 -0.081265 -0.209611 0.0377586 -0.0813989 -0.210061 0.0379756 -0.081265 -0.209921 0.0383772 -0.081265 -0.209921 0.0392227 -0.081265 -0.209433 0.039334 -0.0813989 -0.210061 0.0396243 -0.081265 -0.209897 0.0402963 -0.0813989 -0.210277 0.0406764 -0.0813989 -0.210589 0.0402854 -0.081265 -0.210949 0.0405118 -0.081265 -0.211773 0.0412 -0.0813989 -0.212307 0.0411398 -0.0813989 -0.212196 0.0406523 -0.081265 -0.212598 0.0405118 -0.081265 -0.21327 0.0406764 -0.0813989 -0.213626 0.0392227 -0.081265 -0.214173 0.0388 -0.0813989 -0.213626 0.0383772 -0.081265 -0.213936 0.0377586 -0.0813989 -0.21365 0.0373036 -0.0813989 -0.21327 0.0369236 -0.0813989 -0.212598 0.0370881 -0.081265 -0.212307 0.0364601 -0.0813989 -0.211773 0.0364 -0.0813989 -0.212196 0.0369476 -0.081265 -0.211239 0.0364601 -0.0813989 -0.210732 0.0366376 -0.0813989 -0.210049 0.0366374 -0.081765 -0.210277 0.0369236 -0.0813989 -0.209897 0.0373036 -0.0813989 -0.209281 0.0375998 -0.081765 -0.209433 0.0382659 -0.0813989 -0.209373 0.0388 -0.0813989 -0.209611 0.0398413 -0.0813989 -0.209611 0.0405245 -0.081765 -0.210049 0.0409625 -0.081765 -0.210573 0.0412921 -0.081765 -0.210732 0.0409623 -0.0813989 -0.211239 0.0411398 -0.0813989 -0.213498 0.0409625 -0.081765 -0.212815 0.0409623 -0.0813989 -0.214265 0.0400001 -0.081765 -0.21365 0.0402963 -0.0813989 -0.213936 0.0398413 -0.0813989 -0.214113 0.039334 -0.0813989 -0.214539 0.0388 -0.081765 -0.214113 0.0382659 -0.0813989 -0.213498 0.0366374 -0.081765 -0.212973 0.0363079 -0.081765 -0.212815 0.0366376 -0.0813989 -0.211773 0.0360339 -0.081765 -0.211158 0.0361033 -0.081765 -0.210515 0.0361871 -0.082265 -0.210573 0.0363079 -0.081765 -0.209506 0.0369918 -0.082265 -0.209611 0.0370754 -0.081765 -0.20916 0.0375417 -0.082265 -0.209077 0.0381845 -0.081765 -0.208946 0.0381546 -0.082265 -0.208946 0.0394453 -0.082265 -0.209007 0.0388 -0.081765 -0.20916 0.0400582 -0.082265 -0.209077 0.0394155 -0.081765 -0.209281 0.0400001 -0.081765 -0.210515 0.0414128 -0.082265 -0.211158 0.0414966 -0.081765 -0.211773 0.041566 -0.081765 -0.212419 0.0416273 -0.082265 -0.212389 0.0414966 -0.081765 -0.212973 0.0412921 -0.081765 -0.213031 0.0414128 -0.082265 -0.213581 0.0410673 -0.082265 -0.214041 0.0406081 -0.082265 -0.214386 0.0400582 -0.082265 -0.213936 0.0405245 -0.081765 -0.21447 0.0394155 -0.081765 -0.21447 0.0381845 -0.081765 -0.2146 0.0381546 -0.082265 -0.214265 0.0375998 -0.081765 -0.213936 0.0370754 -0.081765 -0.214041 0.0369918 -0.082265 -0.213581 0.0365326 -0.082265 -0.212389 0.0361033 -0.081765 -0.212419 0.0359727 -0.082265 -0.211773 0.0359 -0.082265 -0.211239 0.0564601 -0.0813989 -0.210732 0.0566376 -0.0813989 -0.210277 0.0569236 -0.0813989 -0.210589 0.0573145 -0.081265 -0.209897 0.0573036 -0.0813989 -0.210288 0.0576153 -0.081265 -0.209921 0.0583772 -0.081265 -0.209433 0.0582659 -0.0813989 -0.209873 0.0588 -0.081265 -0.209921 0.0592227 -0.081265 -0.210589 0.0602854 -0.081265 -0.210732 0.0609623 -0.0813989 -0.210949 0.0605118 -0.081265 -0.211239 0.0611398 -0.0813989 -0.211773 0.0607 -0.081265 -0.212815 0.0609623 -0.0813989 -0.21365 0.0602963 -0.0813989 -0.213259 0.0599846 -0.081265 -0.214113 0.059334 -0.0813989 -0.213936 0.0577586 -0.0813989 -0.213259 0.0576153 -0.081265 -0.212958 0.0573145 -0.081265 -0.212598 0.0570881 -0.081265 -0.211773 0.0564 -0.0813989 -0.211773 0.0569 -0.081265 -0.211158 0.0561033 -0.081765 -0.210573 0.0563079 -0.081765 -0.209611 0.0570754 -0.081765 -0.209611 0.0577586 -0.0813989 -0.209077 0.0581845 -0.081765 -0.209007 0.0588 -0.081765 -0.209373 0.0588 -0.0813989 -0.209433 0.059334 -0.0813989 -0.209077 0.0594155 -0.081765 -0.209611 0.0598413 -0.0813989 -0.209611 0.0605245 -0.081765 -0.209897 0.0602963 -0.0813989 -0.210573 0.0612921 -0.081765 -0.210277 0.0606764 -0.0813989 -0.211773 0.0612 -0.0813989 -0.212389 0.0614966 -0.081765 -0.212307 0.0611398 -0.0813989 -0.213498 0.0609625 -0.081765 -0.21327 0.0606764 -0.0813989 -0.213936 0.0605245 -0.081765 -0.213936 0.0598413 -0.0813989 -0.214539 0.0588 -0.081765 -0.214173 0.0588 -0.0813989 -0.214113 0.0582659 -0.0813989 -0.213936 0.0570754 -0.081765 -0.21365 0.0573036 -0.0813989 -0.21327 0.0569236 -0.0813989 -0.212973 0.0563079 -0.081765 -0.212815 0.0566376 -0.0813989 -0.212307 0.0564601 -0.0813989 -0.211773 0.0560339 -0.081765 -0.211128 0.0559727 -0.082265 -0.210515 0.0561871 -0.082265 -0.210049 0.0566374 -0.081765 -0.20916 0.0575417 -0.082265 -0.209281 0.0575998 -0.081765 -0.208873 0.0588 -0.082265 -0.209281 0.0600001 -0.081765 -0.209965 0.0610673 -0.082265 -0.210049 0.0609625 -0.081765 -0.211158 0.0614966 -0.081765 -0.211773 0.0617 -0.082265 -0.211773 0.061566 -0.081765 -0.212973 0.0612921 -0.081765 -0.213031 0.0614128 -0.082265 -0.214041 0.0606081 -0.082265 -0.214386 0.0600582 -0.082265 -0.214265 0.0600001 -0.081765 -0.21447 0.0594155 -0.081765 -0.214673 0.0588 -0.082265 -0.21447 0.0581845 -0.081765 -0.214265 0.0575998 -0.081765 -0.213581 0.0565326 -0.082265 -0.213498 0.0566374 -0.081765 -0.212389 0.0561033 -0.081765 -0.211773 0.0433 -0.090065 -0.210862 0.0436297 -0.089998 -0.210818 0.0433835 -0.090065 -0.209978 0.0438666 -0.089998 -0.209148 0.0442533 -0.089998 -0.209023 0.0440368 -0.090065 -0.208238 0.0445867 -0.090065 -0.207751 0.0454253 -0.089998 -0.20756 0.0452646 -0.090065 -0.207227 0.046175 -0.089998 -0.20701 0.04605 -0.090065 -0.206523 0.0488 -0.089998 -0.206603 0.0497116 -0.089998 -0.207227 0.051425 -0.089998 -0.208238 0.0530132 -0.090065 -0.208399 0.0528217 -0.089998 -0.209148 0.0533466 -0.089998 -0.209892 0.0539683 -0.090065 -0.210862 0.0539702 -0.089998 -0.211773 0.0543 -0.090065 -0.214523 0.0535631 -0.090065 -0.214398 0.0533466 -0.089998 -0.216536 0.05155 -0.090065 -0.216707 0.0505956 -0.089998 -0.216942 0.0506811 -0.090065 -0.216943 0.0497116 -0.089998 -0.216943 0.0478883 -0.089998 -0.216707 0.0470044 -0.089998 -0.21632 0.046175 -0.089998 -0.216536 0.04605 -0.090065 -0.215986 0.0452646 -0.090065 -0.214523 0.0440368 -0.090065 -0.213654 0.0436316 -0.090065 -0.212685 0.0436297 -0.089998 -0.211773 0.04355 -0.089998 -0.210893 0.04381 -0.089815 -0.208516 0.0449184 -0.089815 -0.208399 0.0447782 -0.089998 -0.207385 0.0462665 -0.089815 -0.20684 0.0470044 -0.089998 -0.206783 0.0479201 -0.089815 -0.206706 0.0488 -0.089815 -0.206603 0.0478883 -0.089998 -0.206783 0.0496798 -0.089815 -0.20684 0.0505956 -0.089998 -0.207012 0.050533 -0.089815 -0.207385 0.0513335 -0.089815 -0.207892 0.052057 -0.089815 -0.208516 0.0526815 -0.089815 -0.207751 0.0521746 -0.089998 -0.21004 0.0535614 -0.089815 -0.209978 0.0537333 -0.089998 -0.210893 0.05379 -0.089815 -0.211773 0.0538669 -0.089815 -0.211773 0.05405 -0.089998 -0.212653 0.05379 -0.089815 -0.212685 0.0539702 -0.089998 -0.213569 0.0537333 -0.089998 -0.21503 0.0526815 -0.089815 -0.215148 0.0528217 -0.089998 -0.215795 0.0521746 -0.089998 -0.216161 0.0513335 -0.089815 -0.21632 0.051425 -0.089998 -0.216535 0.050533 -0.089815 -0.216763 0.0496798 -0.089815 -0.21684 0.0488 -0.089815 -0.217023 0.0488 -0.089998 -0.216763 0.0479201 -0.089815 -0.216535 0.0470669 -0.089815 -0.215795 0.0454253 -0.089998 -0.215148 0.0447782 -0.089998 -0.214398 0.0442533 -0.089998 -0.213569 0.0438666 -0.089998 -0.210063 0.0441015 -0.089565 -0.21004 0.0440385 -0.089815 -0.20924 0.0444118 -0.089815 -0.207892 0.045543 -0.089815 -0.207075 0.0470899 -0.089565 -0.207012 0.0470669 -0.089815 -0.207075 0.0505101 -0.089565 -0.208559 0.0526302 -0.089565 -0.20924 0.0531881 -0.089815 -0.210063 0.0534984 -0.089565 -0.210905 0.053724 -0.089565 -0.212641 0.053724 -0.089565 -0.213483 0.0534984 -0.089565 -0.213506 0.0535614 -0.089815 -0.214987 0.0526302 -0.089565 -0.214307 0.0531881 -0.089815 -0.215655 0.052057 -0.089815 -0.216472 0.0470899 -0.089565 -0.215603 0.045586 -0.089565 -0.216161 0.0462665 -0.089815 -0.214987 0.0449697 -0.089565 -0.215655 0.045543 -0.089815 -0.21503 0.0449184 -0.089815 -0.214273 0.0444698 -0.089565 -0.214307 0.0444118 -0.089815 -0.213506 0.0440385 -0.089815 -0.212653 0.04381 -0.089815 -0.211773 0.043733 -0.089815 -0.210905 0.0438759 -0.089565 -0.209978 0.0537333 -0.084832 -0.209892 0.0539683 -0.084765 -0.209148 0.0533466 -0.084832 -0.209023 0.0535631 -0.084765 -0.208399 0.0528217 -0.084832 -0.208238 0.0530132 -0.084765 -0.206605 0.0506811 -0.084765 -0.206603 0.0497116 -0.084832 -0.206523 0.0488 -0.084832 -0.206273 0.0488 -0.084765 -0.206603 0.0478883 -0.084832 -0.20701 0.04605 -0.084765 -0.208238 0.0445867 -0.084765 -0.209978 0.0438666 -0.084832 -0.210862 0.0436297 -0.084832 -0.211773 0.04355 -0.084832 -0.212685 0.0436297 -0.084832 -0.212728 0.0433835 -0.084765 -0.213569 0.0438666 -0.084832 -0.214398 0.0442533 -0.084832 -0.215148 0.0447782 -0.084832 -0.215309 0.0445867 -0.084765 -0.216536 0.04605 -0.084765 -0.21632 0.046175 -0.084832 -0.216942 0.0469188 -0.084765 -0.217273 0.0488 -0.084765 -0.21719 0.049755 -0.084765 -0.216536 0.05155 -0.084765 -0.21632 0.051425 -0.084832 -0.215795 0.0521746 -0.084832 -0.215148 0.0528217 -0.084832 -0.214398 0.0533466 -0.084832 -0.213654 0.0539683 -0.084765 -0.213569 0.0537333 -0.084832 -0.212685 0.0539702 -0.084832 -0.211773 0.05405 -0.084832 -0.210862 0.0539702 -0.084832 -0.20924 0.0531881 -0.085015 -0.208516 0.0526815 -0.085015 -0.207892 0.052057 -0.085015 -0.207751 0.0521746 -0.084832 -0.207227 0.051425 -0.084832 -0.207385 0.0513335 -0.085015 -0.207012 0.050533 -0.085015 -0.20684 0.0505956 -0.084832 -0.206783 0.0496798 -0.085015 -0.206783 0.0479201 -0.085015 -0.20684 0.0470044 -0.084832 -0.207012 0.0470669 -0.085015 -0.207227 0.046175 -0.084832 -0.207751 0.0454253 -0.084832 -0.207892 0.045543 -0.085015 -0.208399 0.0447782 -0.084832 -0.209148 0.0442533 -0.084832 -0.20924 0.0444118 -0.085015 -0.213506 0.0440385 -0.085015 -0.214307 0.0444118 -0.085015 -0.21503 0.0449184 -0.085015 -0.215655 0.045543 -0.085015 -0.215795 0.0454253 -0.084832 -0.216535 0.0470669 -0.085015 -0.216707 0.0470044 -0.084832 -0.216943 0.0478883 -0.084832 -0.217023 0.0488 -0.084832 -0.216535 0.050533 -0.085015 -0.216943 0.0497116 -0.084832 -0.216707 0.0505956 -0.084832 -0.216161 0.0513335 -0.085015 -0.21503 0.0526815 -0.085015 -0.214307 0.0531881 -0.085015 -0.213506 0.0535614 -0.085015 -0.210893 0.05379 -0.085015 -0.21004 0.0535614 -0.085015 -0.207443 0.0513 -0.085265 -0.207075 0.0505101 -0.085265 -0.206706 0.0488 -0.085015 -0.206849 0.0479317 -0.085265 -0.207075 0.0470899 -0.085265 -0.207443 0.0463 -0.085265 -0.207385 0.0462665 -0.085015 -0.207943 0.045586 -0.085265 -0.208516 0.0449184 -0.085015 -0.208559 0.0449697 -0.085265 -0.209273 0.0444698 -0.085265 -0.21004 0.0440385 -0.085015 -0.210893 0.04381 -0.085015 -0.210905 0.0438759 -0.085265 -0.212641 0.0438759 -0.085265 -0.211773 0.043733 -0.085015 -0.212653 0.04381 -0.085015 -0.213483 0.0441015 -0.085265 -0.214273 0.0444698 -0.085265 -0.214987 0.0449697 -0.085265 -0.216161 0.0462665 -0.085015 -0.216697 0.0479317 -0.085265 -0.216763 0.0479201 -0.085015 -0.21684 0.0488 -0.085015 -0.216763 0.0496798 -0.085015 -0.216103 0.0513 -0.085265 -0.215655 0.052057 -0.085015 -0.214987 0.0526302 -0.085265 -0.214273 0.0531301 -0.085265 -0.212653 0.05379 -0.085015 -0.211773 0.0538669 -0.085015 -0.0675825 0.143273 -0.0210931 -0.0694015 0.143125 -0.0221433 -0.0684982 0.142983 -0.0230074 -0.0655732 0.14088 -0.0328656 -0.0646103 0.14103 -0.0323097 -0.065587 0.139676 -0.0367512 -0.0657127 0.141233 -0.0315606 -0.0705732 0.135478 -0.0466066 -0.0717732 0.136156 -0.0452849 -0.0699177 0.135276 -0.046985 -0.0717732 0.135484 -0.0466066 -0.0817732 0.135549 -0.0466066 -0.0817732 0.135796 -0.0461301 -0.0802923 0.134703 -0.0481544 -0.0811732 0.134989 -0.0476458 -0.0805732 0.13554 -0.0466066 -0.0805732 0.13579 -0.0461233 -0.0920541 0.134807 -0.0481544 -0.0917732 0.135642 -0.0466066 -0.0905732 0.135847 -0.0461888 -0.0878923 0.134766 -0.0481544 -0.102054 0.134926 -0.0481544 -0.101773 0.135764 -0.0466066 -0.101173 0.135196 -0.0476458 -0.112054 0.135071 -0.0481544 -0.111773 0.135913 -0.0466066 -0.111173 0.135341 -0.0476458 -0.110573 0.135894 -0.0466066 -0.124454 0.13529 -0.0481544 -0.120292 0.135212 -0.0481544 -0.117892 0.135169 -0.0481544 -0.131773 0.136297 -0.0466066 -0.132054 0.135445 -0.0481544 -0.132245 0.135449 -0.0481544 -0.13414 0.135593 -0.0479732 -0.130292 0.135407 -0.0481544 -0.127892 0.135358 -0.0481544 -0.130513 0.136251 -0.0466411 -0.141173 0.139462 -0.0404867 -0.140145 0.139094 -0.0412788 -0.14208 0.139706 -0.0399629 -0.140573 0.137995 -0.0436903 -0.141681 0.144085 -0.0248967 -0.141773 0.144037 -0.0251709 -0.142245 0.143113 -0.0295586 -0.140748 0.143533 -0.0275217 -0.141059 0.143099 -0.029469 -0.140726 0.144412 -0.0229077 -0.135573 0.144614 -0.0206258 -0.136773 0.144652 -0.0206258 -0.136659 0.144494 -0.0216134 -0.137889 0.144362 -0.0226558 -0.140573 0.14365 -0.026937 -0.126773 0.144688 -0.0182072 -0.126166 0.144592 -0.0187948 -0.125573 0.14462 -0.0184624 -0.12552 0.144573 -0.0187984 -0.115573 0.144388 -0.0182072 -0.115573 0.144347 -0.0185153 -0.116773 0.144417 -0.0182072 -0.105573 0.144161 -0.0182072 -0.105573 0.144116 -0.0185604 -0.0967732 0.143995 -0.0182072 -0.0968251 0.143903 -0.0189257 -0.0961691 0.143891 -0.0189279 -0.0867732 0.143791 -0.0186235 -0.0868249 0.143748 -0.0189551 -0.0855732 0.143775 -0.0186266 -0.0855215 0.143731 -0.0189584 -0.0755732 0.143722 -0.0182072 -0.0767732 0.143677 -0.0186457 -0.0768247 0.143634 -0.0189768 -0.0667648 0.143131 -0.0220066 -0.141173 0.140393 -0.0404867 -0.079313 0.136843 -0.0473342 -0.0905732 0.13621 -0.0466066 -0.0905732 0.13563 -0.0466066 -0.0978923 0.136586 -0.0481544 -0.107892 0.135008 -0.0481544 -0.107892 0.136723 -0.0481544 -0.120573 0.13621 -0.0466066 -0.118694 0.137153 -0.0476918 -0.12846 0.137271 -0.0478267 -0.130073 0.136461 -0.0468953 -0.131773 0.136369 -0.0466066 -0.131447 0.137347 -0.0478036 -0.131173 0.135713 -0.0476458 -0.130835 0.137313 -0.0478414 -0.12377 0.137212 -0.0477597 -0.121773 0.13621 -0.0466066 -0.121173 0.135514 -0.0476458 -0.121312 0.137183 -0.0477262 -0.122054 0.135244 -0.0481544 -0.122054 0.136963 -0.0481544 -0.114454 0.136827 -0.0481544 -0.111773 0.13621 -0.0466066 -0.104454 0.134958 -0.0481544 -0.0944541 0.134833 -0.0481544 -0.0931914 0.136922 -0.0474254 -0.0844541 0.136447 -0.0481544 -0.0844541 0.134736 -0.0481544 -0.0817732 0.13621 -0.0466066 -0.140573 0.139744 -0.0415259 -0.140573 0.139657 -0.0436903 -0.064748 0.138551 -0.0398084 -0.0650359 0.140225 -0.0396422 -0.141773 0.144501 -0.0292861 -0.142245 0.144657 -0.0295586 -0.141773 0.143165 -0.0292861 -0.142245 0.14276 -0.0309443 -0.0648934 0.142897 -0.0310875 -0.0646103 0.142582 -0.0323097 -0.141773 0.145564 -0.0251709 -0.135573 0.146263 -0.0197316 -0.135573 0.144881 -0.0187772 -0.115573 0.1459 -0.0182136 -0.106773 0.144186 -0.0182072 -0.106773 0.145693 -0.0182538 -0.0955732 0.143925 -0.0185975 -0.0955732 0.143975 -0.0182072 -0.0955732 0.145476 -0.018296 -0.0955732 0.145487 -0.0182072 -0.0855732 0.143828 -0.0182072 -0.0755732 0.14508 -0.0194025 -0.0755732 0.143863 -0.0196397 -0.0755732 0.143201 -0.0196818 -0.0767732 0.143732 -0.0182072 -0.0699177 0.136968 -0.046985 -0.111173 0.137049 -0.0476458 -0.110292 0.135044 -0.0481544 -0.102054 0.13664 -0.0481544 -0.100292 0.136616 -0.0481544 -0.0911732 0.136783 -0.0476458 -0.0902923 0.134789 -0.0481544 -0.0911732 0.135079 -0.0476458 -0.0811732 0.136692 -0.0476458 -0.0744519 0.134666 -0.0481531 -0.136773 0.146364 -0.019291 -0.136773 0.14617 -0.0206258 -0.136773 0.144849 -0.019291 -0.124578 0.143749 -0.0196502 -0.124573 0.143745 -0.0196511 -0.125121 0.144268 -0.019383 -0.125522 0.146128 -0.0184924 -0.125572 0.146167 -0.0182072 -0.125376 0.14448 -0.019097 -0.125126 0.145826 -0.0190769 -0.124573 0.145299 -0.019349 -0.124971 0.144131 -0.019492 -0.126826 0.144611 -0.0187911 -0.126773 0.144655 -0.0184555 -0.126773 0.145932 -0.0182072 -0.126775 0.146201 -0.0182072 -0.127374 0.145758 -0.0191753 -0.126971 0.144526 -0.0190894 -0.127769 0.145398 -0.0193298 -0.127773 0.143839 -0.0196328 -0.119166 0.119692 0.0704519 -0.130013 0.148668 -0.0193497 -0.0011732 0.11941 0.0704519 -0.0011732 0.130682 0.0594922 0.0579503 0.130687 0.0594922 0.231927 0.0882446 0.0841758 0.231927 0.0911219 0.0836281 0.116804 0.0913809 -0.085084 0.231927 0.0914689 -0.085084 0.231927 0.0894451 -0.0854914 0.231927 0.0817483 -0.0865199 0.231927 0.0810718 -0.0865717 0.171451 0.0778575 -0.0867338 0.231927 0.106089 -0.0803144 0.182959 0.113034 -0.0767487 0.184861 0.111395 -0.0776729 0.188642 0.11013 -0.0783522 0.231927 0.106771 -0.080007 0.200734 0.110153 -0.0783524 0.212827 0.110164 -0.0783525 0.219434 0.114167 -0.0761172 0.231927 0.113012 -0.0767955 0.231928 0.120284 -0.0720273 0.22163 0.117662 -0.0738882 0.222593 0.11987 -0.072333 0.22363 0.123737 -0.0693052 0.231928 0.127005 -0.0664 0.223827 0.12614 -0.0672035 0.231929 0.129185 -0.0642597 0.231929 0.13489 -0.0577034 0.223827 0.145308 -0.0393672 0.231931 0.143882 -0.0427372 0.23193 0.14154 -0.0474715 0.223827 0.141584 -0.0473942 0.223827 0.148065 -0.0309281 0.231931 0.147495 -0.0329722 0.223365 0.150362 -0.0192563 0.221725 0.150805 -0.0159163 0.218618 0.151117 -0.0130092 0.185471 0.150998 -0.0118138 0.18217 0.150798 -0.0134585 0.185789 0.151011 0.010193 0.175767 0.151311 -0.000587542 0.212824 0.151257 -0.0113478 0.200727 0.1512 -0.0113476 0.216453 0.151211 0.0104381 0.231932 0.150631 0.0157604 0.223827 0.149856 0.0209046 0.231931 0.147522 0.031351 0.223827 0.14531 0.037832 0.223827 0.141604 0.0458284 0.216575 0.111421 0.0761552 0.2208 0.116153 0.073354 0.222488 0.119593 0.0710049 0.231927 0.108265 0.0777749 0.231928 0.122559 0.0687402 0.231929 0.129058 0.0628597 0.223827 0.131621 0.0601188 0.23193 0.13922 0.0499423 0.188642 0.11013 0.0768222 0.186798 0.110427 0.0766644 0.184728 0.111487 0.0760925 0.182035 0.114101 0.074587 0.179838 0.117573 0.072358 0.231927 0.100162 0.0811223 0.173574 0.0799652 0.0851131 0.171101 0.0775028 0.0852133 0.176693 0.0810719 0.0850416 0.168979 0.0766122 0.0852295 -0.178487 0.0810408 0.0850439 -0.119151 0.0910376 0.0836281 -0.172625 0.0769124 0.0852252 -0.171657 0.0766308 0.0852292 -0.119157 0.106129 0.0786237 -0.185305 0.113034 0.0752188 -0.187208 0.111395 0.076143 -0.234273 0.100162 0.0811223 -0.234274 0.106448 0.0786237 -0.221352 0.113644 0.0748977 -0.22178 0.114167 0.0745872 -0.22494 0.11987 0.0708031 -0.234274 0.122559 0.0687402 -0.234274 0.120346 0.0704519 -0.226173 0.147525 0.031351 -0.226173 0.145308 0.0378372 -0.234277 0.143405 0.0422427 -0.226173 0.141584 0.0458643 -0.226173 0.137556 0.0525028 -0.234276 0.134782 0.0563134 -0.226173 0.132255 0.0593961 -0.234275 0.129058 0.0628597 -0.234278 0.148719 0.0266884 -0.234278 0.150631 0.0157604 -0.220964 0.151117 0.0114792 -0.234279 0.151598 0.00443326 -0.215171 0.151257 0.00981782 -0.203074 0.1512 0.00981762 -0.187345 0.150978 0.0104383 -0.188135 0.151011 -0.0117229 -0.188629 0.151028 -0.0116022 -0.178113 0.151311 -0.000587542 -0.215171 0.151257 -0.0113478 -0.21833 0.151223 -0.0118147 -0.234278 0.150846 -0.0155491 -0.2242 0.150783 -0.0160989 -0.222019 0.151044 -0.0137573 -0.225885 0.150264 -0.0199121 -0.226173 0.149856 -0.0224346 -0.226173 0.148025 -0.0310826 -0.234278 0.147495 -0.0329722 -0.234277 0.143882 -0.0427372 -0.234276 0.13489 -0.0577034 -0.226173 0.137011 -0.0548225 -0.225698 0.122343 -0.0704446 -0.225205 0.120621 -0.0717767 -0.234274 0.120284 -0.0720273 -0.234274 0.106771 -0.080007 -0.189145 0.110427 -0.0781944 -0.187074 0.111487 -0.0776224 -0.184807 0.113585 -0.0764252 -0.190988 0.11013 -0.0783522 -0.17465 0.0787226 -0.0867038 -0.175504 0.0795875 -0.0866637 -0.175921 0.0799652 -0.0866431 -0.177387 0.0807871 -0.0865915 -0.179039 0.0810719 -0.0865716 -0.119151 0.0913809 -0.085084 -0.234273 0.0894451 -0.0854914 -0.206656 0.0810718 -0.0865717 -0.0518732 0.145084 -0.03254 -0.0603484 0.139494 -0.0474715 -0.050568 0.141693 -0.0426556 -0.0486252 0.140209 -0.0459912 -0.0479483 0.139809 -0.0468225 -0.045153 0.138516 -0.0493386 -0.0564223 0.147411 -0.0201267 -0.0548724 0.147335 -0.0206717 -0.0541228 0.147335 -0.0206717 -0.0518732 0.147115 -0.0221879 -0.0526232 0.147227 -0.0214302 -0.0528803 0.147323 -0.0207559 -0.0569803 0.147495 -0.0195014 -0.0573054 0.147595 -0.0187197 -0.0573709 0.147666 -0.0181448 -0.0604235 0.14784 -0.0166991 -0.0573708 0.14861 -0.00602286 -0.0526232 0.147138 0.0205067 -0.0525907 0.147217 0.0199709 -0.0518732 0.145295 0.0301766 -0.0541228 0.147249 0.0197482 -0.0518732 0.144995 0.031351 -0.0548724 0.147249 0.0197482 -0.0561797 0.147303 0.0193748 -0.0568152 0.147383 0.0188102 -0.0572281 0.147483 0.0180635 -0.060423 0.1478 0.0155212 -0.0508982 0.141784 0.0409062 -0.0514153 0.142463 0.0392013 -0.0603473 0.139336 0.0462535 -0.0603916 0.145004 0.031351 -0.0602967 0.130687 0.0594922 -0.0404379 0.136903 0.0506509 -0.0437091 0.137679 0.0493201 -0.0454278 0.13829 0.0482239 0.11683 0.13113 0.0594922 0.129521 0.140346 0.0459798 0.126721 0.13893 0.0484777 0.133442 0.14452 0.0366212 0.13271 0.14305 0.0403639 0.130189 0.140776 0.0451682 0.17577 0.147192 0.031351 0.135728 0.148642 0.019762 0.134229 0.148475 0.0205204 0.133482 0.147319 0.0267079 0.134485 0.148588 0.0198462 0.166162 0.151038 0.00359757 0.167403 0.151104 0.0022224 0.175768 0.150287 0.0155212 0.168123 0.151148 0.000512391 0.168241 0.151156 -0.00134165 0.160892 0.150879 0.00444484 0.138977 0.149333 0.0155212 0.159287 0.150871 0.00352617 0.138974 0.150168 0.00552876 0.157388 0.150884 0.000396156 0.157266 0.150886 -0.000764971 0.15731 0.150885 -0.00146293 0.162245 0.1509 -0.00628189 0.165779 0.151019 -0.00540402 0.167135 0.151089 -0.00413812 0.175768 0.150331 -0.0166991 0.133484 0.146659 -0.0311029 0.134672 0.148694 -0.0207169 0.134978 0.148709 -0.0206849 0.13348 0.148427 -0.0222015 0.134229 0.148569 -0.0214436 0.136995 0.148783 -0.0206307 0.138834 0.149077 -0.019002 0.132515 0.143064 -0.0418472 0.11683 0.131353 -0.0607537 0.118004 0.137514 -0.052134 -0.17004 0.151122 -0.00323679 -0.168952 0.15106 -0.00473699 -0.162109 0.150871 -0.00540659 -0.160479 0.150876 0.00221964 -0.119203 0.148695 -0.0166991 -0.160753 0.150874 -0.0041435 -0.159889 0.150882 -0.00249934 -0.119205 0.149604 -0.000587542 -0.119203 0.148654 0.0155212 -0.165169 0.150914 0.00477683 -0.168592 0.151042 0.00353027 -0.169809 0.151108 0.00212762 -0.170495 0.15115 0.000398351 -0.170617 0.151158 -0.000764971 -0.0651865 0.146238 -0.0274935 -0.0697444 0.147272 -0.0214737 -0.0729444 0.147502 -0.0199906 -0.0692727 0.13991 -0.0466893 -0.0669562 0.140833 -0.0447048 -0.0603924 0.145093 -0.03254 -0.0644279 0.143456 -0.038047 -0.0733258 0.139092 -0.0483548 -0.0602978 0.130907 -0.0607537 -0.133883 0.13974 -0.0487367 -0.17812 0.141272 -0.0474715 -0.139929 0.141802 -0.04497 -0.163803 0.150886 -0.00614712 -0.178114 0.150331 -0.0166991 -0.132178 0.148709 -0.0195344 -0.132994 0.14871 -0.0197087 -0.136021 0.148632 -0.0209153 -0.136673 0.148593 -0.0213099 -0.139515 0.14827 -0.0238563 -0.141591 0.147635 -0.0275779 -0.178117 0.147289 -0.03254 -0.142181 0.146973 -0.0306117 -0.142333 0.145888 -0.0345775 -0.142358 0.144584 -0.0384802 0.182413 0.150819 0.0117556 0.177627 0.149522 0.0209023 0.178089 0.150029 0.0177207 0.17763 0.145032 0.0378247 0.175774 0.141104 0.0462535 0.177634 0.137345 0.052494 0.116825 0.12571 0.0652914 0.11682 0.119968 -0.0717694 0.116825 0.125961 -0.0665795 0.177638 0.125999 -0.0672016 0.125313 0.138755 -0.0502654 0.127058 0.139414 -0.0491539 0.175778 0.132206 -0.0607537 0.177635 0.136801 -0.0548186 0.175774 0.141272 -0.0474715 0.177632 0.141356 -0.0473575 0.179596 0.150469 -0.0161032 0.179325 0.150415 -0.0165145 0.177911 0.149927 -0.0199285 0.17577 0.147289 -0.03254 -0.178114 0.150287 0.0155212 -0.178125 0.131976 0.0594922 -0.179975 0.147713 0.029559 -0.179975 0.147221 0.031351 -0.181227 0.11975 -0.0723452 -0.179973 0.149522 -0.0224322 -0.137629 0.140729 -0.0470292 -0.179983 0.132079 -0.0609214 -0.179983 0.131451 0.0601123 -0.119176 0.13113 0.0594922 -0.17812 0.141104 0.0462535 -0.178117 0.147192 0.031351 -0.163346 0.15088 0.00448269 -0.0604351 0.14871 -0.000587542 -0.119196 0.145755 0.031351 -0.119187 0.139944 0.0462535 -0.179985 0.125999 0.0656716 -0.119171 0.12571 0.0652914 -0.180461 0.122224 0.0689135 -0.119177 0.131353 -0.0607537 -0.119171 0.125961 -0.0665795 -0.179985 0.125999 -0.0672016 -0.178125 0.132206 -0.0607537 0.178115 0.122224 -0.0704434 0.116811 0.106446 -0.080007 -0.0011732 0.0913431 -0.085084 -0.182184 0.117573 -0.0738879 -0.0011732 0.130902 -0.0607537 -0.0011732 0.119683 -0.0717694 -0.119166 0.119968 -0.0717694 0.0219727 0.076967 -0.0867542 -0.172668 0.0771383 -0.0867511 -0.119157 0.106446 -0.080007 -0.0011732 0.106306 -0.080007 0.0579514 0.130907 -0.0607537 0.175778 0.131976 0.0594922 0.11682 0.119692 0.0704519 0.116811 0.106129 0.0786237 0.116804 0.0910376 0.0836281 -0.0011732 0.105992 0.0786237 -0.0011732 0.0910013 0.0836281 -0.0239868 0.0766122 0.0852294 -0.171326 0.0766122 0.0852295 -0.136506 0.13682 -0.0357679 -0.140429 0.142906 -0.0400122 -0.136017 0.136019 -0.0380956 -0.140214 0.142602 -0.0407198 -0.139042 0.141571 -0.0429062 -0.138552 0.141262 -0.0435059 -0.134622 0.135339 -0.0400689 -0.136561 0.140327 -0.0451868 -0.133349 0.139461 -0.0465617 -0.132535 0.134885 -0.0413875 -0.130073 0.139151 -0.0469407 -0.130073 0.134726 -0.0418505 -0.0737588 0.13881 -0.0461695 -0.0707226 0.13939 -0.0450609 -0.0703187 0.13951 -0.0448265 -0.066528 0.141634 -0.0401097 -0.0696402 0.13682 -0.0357679 -0.0680665 0.140442 -0.042902 -0.0683401 0.140298 -0.0432127 -0.140508 0.145978 -0.0304602 -0.0661668 0.142508 -0.0377266 -0.0662356 0.143701 -0.0338981 -0.1319 0.147122 -0.0211917 -0.13259 0.147133 -0.0213344 -0.13516 0.147124 -0.0223296 -0.13329 0.141238 -0.0229361 -0.135717 0.147107 -0.0226567 -0.139976 0.14648 -0.0279158 -0.136506 0.139425 -0.0282038 -0.0668795 0.145088 -0.0278261 -0.0666964 0.144985 -0.0284321 -0.0731694 0.145916 -0.0217038 -0.0728567 0.141238 -0.0229361 -0.0707864 0.145785 -0.0228286 -0.0760732 0.141519 -0.0221212 -0.130073 0.141519 -0.0221212 -0.140573 0.138996 -0.0415259 -0.120573 0.136068 -0.0466066 -0.121773 0.136091 -0.0466066 -0.100573 0.135748 -0.0466066 -0.100573 0.13621 -0.0466066 -0.101773 0.135932 -0.0462862 -0.101773 0.13621 -0.0466066 -0.0917732 0.13621 -0.0466066 -0.0705732 0.137165 -0.0466066 -0.0705732 0.136991 -0.0454882 -0.0717732 0.137171 -0.0466066 -0.141173 0.143013 -0.0303253 -0.141173 0.142889 -0.0303253 -0.139333 0.145789 -0.0234896 -0.139701 0.145719 -0.0239544 -0.0655732 0.141039 -0.0328656 -0.0655732 0.139698 -0.036759 -0.0655732 0.139256 -0.0379463 -0.0655732 0.139418 -0.0379463 -0.140573 0.145703 -0.0242054 -0.140573 0.144178 -0.0242054 0.132027 0.145885 -0.021965 0.132027 0.145204 -0.030738 -0.0503732 0.143599 0.0263043 -0.0503732 0.141332 0.034924 0.132027 0.145788 0.021035 0.132027 0.144001 0.029702 0.128655 0.139468 -0.0449669 0.129116 0.139096 -0.0444001 0.129559 0.140128 -0.0437919 0.121507 0.136285 -0.0494144 0.122253 0.136423 -0.0492008 0.125032 0.137167 -0.0479752 0.124631 0.137453 -0.0481981 0.125029 0.137602 -0.0479768 0.128719 0.138848 -0.0448921 0.130151 0.14063 -0.0428545 0.130152 0.139841 -0.0428532 0.131145 0.141681 -0.040745 0.132013 0.142415 -0.0364862 0.131355 0.141033 -0.0401401 0.132027 0.143724 -0.035854 0.118027 0.135965 -0.049854 0.0384794 0.135369 -0.049854 -0.0363732 0.135369 -0.049854 -0.0363732 0.135649 -0.049854 -0.0383395 0.135448 -0.0497152 -0.0397315 0.135601 -0.0494452 -0.0405818 0.136071 -0.0492064 -0.0430226 0.136303 -0.0481741 -0.0435401 0.1369 -0.0478804 -0.0442808 0.136711 -0.0474069 -0.0443033 0.137195 -0.0473914 -0.0477237 0.138357 -0.0440495 -0.0494946 0.139776 -0.0407354 -0.0503732 0.141527 -0.035854 -0.0503563 0.141103 0.0356108 -0.0382799 0.135375 0.0487936 -0.0398562 0.135276 0.0484839 -0.0400446 0.135615 0.0484341 -0.0438395 0.136237 0.046767 -0.046278 0.137836 0.0448182 -0.0443147 0.136405 0.0464537 -0.0462782 0.137253 0.044818 -0.0469978 0.138271 0.0440409 -0.0479095 0.138908 0.0428558 -0.0496807 0.13975 0.0392726 -0.0499596 0.141063 0.0383018 0.118027 0.135864 0.048924 -0.0363732 0.13502 0.048924 -0.0363732 0.135288 0.048924 0.118027 0.135609 0.048924 0.119802 0.135708 0.0488111 0.121146 0.136166 0.0485722 0.121283 0.135897 0.0485402 0.122215 0.136384 0.0482829 0.125162 0.13731 0.0469696 0.124559 0.136676 0.0473069 0.125904 0.137626 0.0464976 0.129356 0.138967 0.0431491 0.130813 0.141026 0.0406253 0.132027 0.143524 0.034924 -0.0558733 0.147047 0.00599107 -0.0558733 0.146042 0.00603205 -0.0558733 0.146177 -0.017965 -0.0558733 0.145168 -0.017965 -0.0533732 0.145849 -0.018965 -0.0541232 0.145849 -0.018965 -0.0548733 0.145849 -0.018965 0.137527 0.147617 0.00542466 0.137527 0.148671 0.00545944 0.137527 0.14776 -0.000589589 0.137527 0.148709 -0.00610243 0.137527 0.147651 -0.00617093 0.135027 0.147135 0.018035 0.136527 0.146395 0.018035 0.135777 0.14716 0.018035 0.136527 0.147185 0.018035 0.135777 0.14725 -0.018965 0.136527 0.146479 -0.018965 0.136527 0.147275 -0.018965 -0.140573 0.140115 -0.0426985 -0.0604115 0.143848 -0.0265893 -0.175504 0.0794831 0.0826358 0.23193 0.145528 -0.0307314 0.23193 0.142883 -0.0386952 -0.234275 0.131942 -0.0574021 -0.234274 0.127093 -0.0628213 -0.234273 0.145528 0.0291995 -0.234273 0.142882 0.0371669 -0.0493279 0.139357 0.0402321 0.116875 0.135638 -0.0503724 -0.0603376 0.135063 -0.0503912 -0.0469973 0.137926 -0.0449715 0.1758 0.136735 -0.0503369 0.125978 0.137512 -0.0473768 0.125503 0.137332 -0.0476904 0.130992 0.140612 -0.0411372 0.137502 0.146617 -0.0181884 0.137451 0.146594 -0.0183476 0.132027 0.144927 -0.027241 0.134038 0.146374 -0.0191326 0.133163 0.146278 -0.0196146 0.133641 0.146253 -0.0198916 0.132255 0.146072 -0.0208172 0.166586 0.148596 -0.00318733 0.167293 0.148635 -0.000764982 0.167173 0.148628 -0.00179817 0.175812 0.147646 -0.0179606 0.16275 0.148449 -0.00526476 0.161262 0.148421 -0.00499652 0.159948 0.14841 -0.00425146 0.158293 0.148413 -0.000764971 0.158547 0.148411 0.000724544 0.158896 0.148409 0.00148503 0.137527 0.146568 0.017035 0.159279 0.148409 0.00204613 0.160408 0.148412 0.00305079 0.161805 0.14843 0.00362518 0.175812 0.147598 0.0167777 0.165991 0.148567 0.00240124 0.134413 0.146316 0.0180984 0.133526 0.146074 0.0195365 0.13153 0.141032 0.0386219 0.132027 0.142426 0.034924 0.175804 0.140666 0.041588 0.175807 0.143863 0.0336377 0.132027 0.142845 0.0336642 0.125898 0.137154 0.0465017 0.128612 0.138486 0.0440867 0.131135 0.140517 0.0398399 -0.0405875 0.135397 0.0482747 -0.0474454 0.137902 0.0434918 -0.0470559 0.137671 0.0439728 -0.0603364 0.134891 0.0491533 -0.0603641 0.138758 0.0416451 -0.0603892 0.141733 0.0336929 -0.0557172 0.145024 0.0175716 -0.0548733 0.144963 0.018035 -0.0604107 0.143783 0.0254025 -0.050453 0.144634 0.0203475 -0.0503732 0.144528 0.021035 -0.0558733 0.146201 -0.00058934 -0.0518049 0.144983 -0.0194075 -0.0518732 0.144839 -0.0204665 -0.0527408 0.145032 -0.0190324 -0.0533732 0.145041 -0.018965 -0.0548733 0.145041 -0.018965 -0.055256 0.145051 -0.0188888 -0.0558733 0.146109 -0.00594794 -0.0604424 0.14621 -0.000589341 -0.0498736 0.140234 -0.0395605 -0.0503732 0.142945 -0.0307919 -0.163692 0.148422 -0.00502576 -0.16739 0.148524 -0.00466208 -0.167984 0.14855 -0.00425231 -0.168978 0.148599 -0.00311343 -0.168656 0.148582 0.00204315 -0.16739 0.148524 0.00313214 -0.178158 0.147598 0.0167777 -0.161943 0.148409 0.00240226 -0.161075 0.14841 0.00116599 -0.119274 0.147105 -0.000589484 -0.160665 0.148413 -0.000288214 -0.189343 0.108596 0.0747986 -0.217083 0.108727 0.074751 -0.19099 0.108333 0.074935 -0.221018 0.111852 0.0730489 -0.219301 0.110072 0.0740432 -0.234274 0.120993 0.0667914 -0.234274 0.113921 0.0718077 -0.223893 0.116927 0.069831 -0.225173 0.123212 0.064935 -0.225173 0.125991 0.0623822 -0.234275 0.131942 0.0558721 -0.234273 0.133033 0.0544874 -0.225173 0.134788 0.0521083 -0.234274 0.127376 0.0610043 -0.225173 0.139331 0.0447761 -0.234273 0.137537 0.0479057 -0.225173 0.142815 0.0373427 -0.234273 0.138356 0.04652 -0.234275 0.138355 0.0465213 -0.224413 0.147954 0.0169103 -0.234273 0.147257 0.0212321 -0.234273 0.147497 0.0198464 -0.223621 0.148161 0.0153839 -0.234277 0.149161 0.00252363 -0.234277 0.149204 -0.000762801 -0.187162 0.148367 0.0114965 -0.188867 0.148442 0.0109629 -0.234277 0.148 0.0165578 -0.234273 0.148416 0.0132646 -0.218469 0.148621 0.0112938 -0.234277 0.149112 0.00403353 -0.17816 0.148812 -0.000589761 -0.215173 0.148667 0.010735 -0.234273 0.148564 0.011879 -0.234277 0.149116 0.00390928 -0.181559 0.147567 0.017408 -0.183215 0.147986 0.0144461 -0.18099 0.144991 0.0301046 -0.17815 0.140666 0.041588 -0.178146 0.136552 0.0490992 -0.178143 0.13158 0.0560651 -0.17814 0.125819 0.0623877 -0.18099 0.123083 0.064935 -0.119161 0.10439 0.0766673 -0.185085 0.111866 0.0730057 -0.119169 0.111853 0.0727702 -0.11918 0.11878 0.0679963 -0.234273 0.14916 0.00252592 -0.234273 0.14916 -0.00405587 -0.234277 0.149116 -0.00543922 -0.234273 0.148564 -0.0134089 -0.225173 0.146528 -0.0265343 -0.234273 0.147257 -0.022762 -0.225173 0.147348 -0.022265 -0.224606 0.147881 -0.018945 -0.234273 0.147497 -0.0213764 -0.234276 0.145141 -0.032117 -0.234273 0.145528 -0.0307295 -0.234276 0.144093 -0.0354265 -0.225173 0.14241 -0.0398598 -0.234273 0.138356 -0.04805 -0.234275 0.137536 -0.0494369 -0.225173 0.136989 -0.0503288 -0.225173 0.134703 -0.0537572 -0.234273 0.133033 -0.0560174 -0.225173 0.13201 -0.0573197 -0.234273 0.131941 -0.057403 -0.234274 0.122874 -0.0667567 -0.234274 0.116114 -0.0719161 -0.223215 0.115374 -0.072409 -0.221079 0.111928 -0.074535 -0.189074 0.10869 -0.0762798 -0.19099 0.108333 -0.076465 -0.215173 0.108366 -0.076465 -0.234273 0.11392 -0.0733379 -0.216819 0.108634 -0.0763287 -0.234273 0.105073 -0.0780299 -0.11917 0.112143 -0.0741246 -0.181485 0.119284 -0.0695727 -0.184027 0.113356 -0.073643 -0.187691 0.148394 -0.0128248 -0.178158 0.147646 -0.0179606 -0.182537 0.147858 -0.0169215 0.231928 0.12529 -0.0645806 0.222827 0.134788 -0.0536382 0.222827 0.136989 -0.0503288 0.231929 0.137536 -0.0494369 0.231927 0.138356 -0.04805 0.231929 0.138355 -0.0480513 0.222827 0.139331 -0.0463061 0.23193 0.142117 -0.0405439 0.231927 0.142314 -0.0400825 0.221488 0.148115 -0.0172658 0.222827 0.147348 -0.022265 0.231927 0.145141 -0.0321151 0.23193 0.147029 -0.0240064 0.23193 0.147258 -0.0227599 0.231927 0.147497 -0.0213764 0.231927 0.147265 -0.0227175 0.184816 0.148367 -0.0130264 0.221275 0.148161 -0.0169138 0.231931 0.148415 -0.0147968 0.217827 0.148545 -0.0136051 0.231931 0.148564 -0.0134112 0.175814 0.148812 -0.000589761 0.178643 0.147031 -0.022265 0.178643 0.14085 -0.0428049 0.175804 0.140812 -0.042806 0.178643 0.142149 -0.0398587 0.175807 0.143972 -0.0348402 0.132027 0.142629 -0.035854 0.17581 0.146174 -0.0265416 0.137148 0.14653 -0.0187483 0.178643 0.134507 -0.0537527 0.178643 0.129195 -0.0604259 0.175794 0.126065 -0.0636769 0.178643 0.123083 -0.066465 0.216955 0.110072 -0.0755732 0.213145 0.108376 -0.0764599 0.188643 0.108333 -0.076465 0.116815 0.104699 -0.0780581 0.221546 0.116927 -0.0713609 0.219782 0.113415 -0.0736501 0.231927 0.124438 -0.0653705 0.222332 0.119392 -0.0695721 0.231927 0.116114 -0.0719161 0.182791 0.1118 0.073044 0.183617 0.110861 0.07358 0.214472 0.108634 0.0747987 0.184509 0.110027 0.0740406 0.186728 0.10869 0.0747499 0.217876 0.110939 0.0735669 0.231927 0.11392 0.071808 0.181681 0.113356 0.0721131 0.17581 0.146103 0.0253544 0.231931 0.148415 0.0132668 0.231931 0.149161 0.00252363 0.231927 0.148416 0.0132646 0.22061 0.148278 0.0144559 0.231927 0.148564 0.011879 0.218083 0.148529 0.0122278 0.231927 0.149116 0.00391157 0.231931 0.149112 0.00403353 0.212827 0.148667 0.010735 0.231927 0.14916 0.00252592 0.214978 0.14865 0.0109691 0.182419 0.148187 0.0129082 0.231931 0.148 0.0165578 0.231927 0.147257 0.0212321 0.222827 0.147348 0.020735 0.231927 0.145141 0.0305851 0.231927 0.145528 0.0291995 0.222827 0.146455 0.0253471 0.23193 0.142883 0.0371653 0.231927 0.142314 0.0385526 0.222827 0.138577 0.0461365 0.222827 0.140956 0.0415795 0.231929 0.137097 0.0486217 0.231929 0.133034 0.0544864 0.222827 0.129358 0.0588981 0.231928 0.127376 0.0610043 0.231928 0.131791 0.0560582 0.231927 0.131941 0.0558731 0.231927 0.123663 0.064538 0.221632 0.11715 0.0696753 0.231928 0.120993 0.0667914 0.220868 0.115374 0.0708791 -0.178487 0.0808974 0.0825477 -0.234273 0.099345 0.0787597 -0.234273 0.0963264 0.0797305 -0.234273 0.0880028 0.0816808 -0.178902 0.0809257 0.0825457 -0.206656 0.0809276 0.0825457 -0.219669 0.0809277 0.0825457 -0.173447 0.0774543 0.0827137 -0.0011732 0.0797781 0.0826193 -0.119149 0.0797812 0.0826193 0.173574 0.0798506 0.0826156 0.171101 0.0774543 0.0827137 0.170853 0.0772359 0.0827187 0.168979 0.0765877 0.0827296 0.231927 0.0880028 0.0816808 0.17504 0.0806504 0.0825651 0.116804 0.0882478 0.0816273 0.116808 0.0964867 0.0796336 0.212827 0.108366 -0.076465 0.231927 0.105073 -0.0780299 0.116808 0.0968117 -0.0810628 0.231927 0.0887018 -0.0830865 0.231927 0.0815462 -0.0840281 0.176693 0.0809276 -0.0840755 0.173157 0.0794831 -0.0841658 0.170629 0.0772251 -0.0842488 -0.175504 0.0794831 -0.0841658 -0.219669 0.0809277 -0.0840756 -0.234273 0.0815462 -0.0840281 -0.234273 0.0887018 -0.0830865 -0.206656 0.0809276 -0.0840756 -0.177387 0.0806504 -0.084095 -0.178902 0.0809257 -0.0840756 -0.119161 0.104699 -0.0780581 -0.234273 0.0970058 -0.0810547 -0.119155 0.0968117 -0.0810628 -0.179039 0.0809276 -0.0840755 -0.121167 0.146004 -0.018516 -0.116825 0.145889 -0.018538 -0.106773 0.145699 -0.0182072 -0.115573 0.1459 -0.0182072 -0.0967732 0.145497 -0.0182919 -0.0911697 0.145363 -0.0186379 -0.0867732 0.145356 -0.0182072 -0.0868237 0.1453 -0.0186498 -0.119267 0.146023 -0.0179838 -0.105573 0.145674 -0.0182072 -0.101169 0.145536 -0.0186051 -0.0755732 0.145233 -0.0182072 -0.0732171 0.145012 -0.0197646 -0.0736036 0.145028 -0.0196696 -0.0675825 0.144788 -0.0210931 -0.0604281 0.145172 -0.0179957 -0.0701327 0.144803 -0.0211007 -0.0689995 0.144675 -0.0219112 -0.0556512 0.145089 -0.0185933 -0.0668448 0.144664 -0.0219067 -0.0667648 0.144648 -0.0220066 -0.0668458 0.14429 -0.0242459 -0.135573 0.146396 -0.0187772 -0.133419 0.146308 -0.0189156 -0.130043 0.146264 -0.0184665 -0.126825 0.146166 -0.0184851 -0.142245 0.144312 -0.0309443 -0.141892 0.144695 -0.0293549 -0.141773 0.14487 -0.02858 -0.178154 0.143972 -0.0348402 -0.142117 0.142226 -0.0376293 -0.14208 0.141327 -0.0399629 -0.17815 0.140812 -0.042806 -0.124454 0.13701 -0.0481544 -0.119221 0.135638 -0.0503724 -0.130292 0.137129 -0.0481544 -0.132054 0.137167 -0.0481544 -0.13414 0.137313 -0.0479732 -0.13334 0.137548 -0.0475113 -0.141595 0.140585 -0.0417004 -0.0760732 0.136829 -0.0473184 -0.0778923 0.136397 -0.0481544 -0.104454 0.136673 -0.0481544 -0.0820541 0.136427 -0.0481544 -0.0724351 0.137082 -0.0467886 -0.0920541 0.136519 -0.0481544 -0.0990681 0.136965 -0.0474755 -0.101173 0.136902 -0.0476458 -0.110292 0.13676 -0.0481544 -0.112054 0.136788 -0.0481544 -0.108897 0.137051 -0.0475745 -0.103349 0.137001 -0.0475163 -0.117892 0.136887 -0.0481544 -0.120292 0.13693 -0.0481544 -0.12104 0.13718 -0.0477226 -0.064748 0.14016 -0.0398084 -0.0603651 0.138895 -0.0428631 -0.0646163 0.140648 -0.0384988 -0.0647933 0.140685 -0.0383966 -0.0659208 0.139363 -0.041808 -0.0649859 0.143265 -0.0295261 -0.0648292 0.14255 -0.0324361 -0.0647228 0.141091 -0.0372385 -0.0603902 0.141834 -0.0348953 -0.0656956 0.143901 -0.0264037 -0.0603075 0.130181 0.0561124 -0.0602783 0.124688 0.0624255 -0.16514 0.14845 0.00373503 -0.119267 0.145978 0.0168012 -0.178156 0.146103 0.0253544 -0.178153 0.143863 0.0336377 -0.119235 0.139413 0.0416255 -0.119221 0.135462 0.0491345 -0.119206 0.130662 0.0560959 -0.11915 0.0882478 0.0816273 -0.119154 0.0964867 0.0796336 -0.0011732 0.111638 0.0727763 -0.0011732 0.118478 0.0680059 -0.119193 0.125077 0.0624123 -0.119248 0.142465 0.0336739 -0.119259 0.144581 0.0253861 -0.0604275 0.14513 0.0168134 -0.0767732 0.145244 -0.0182072 -0.0855732 0.14534 -0.0182072 -0.0855227 0.145283 -0.0186531 -0.0602795 0.124923 -0.0637151 -0.0011732 0.13038 -0.0573745 -0.119151 0.0885843 -0.0830962 -0.0011732 0.0885549 -0.0830965 -0.0011732 0.104558 -0.0780615 -0.0011732 0.111924 -0.0741309 -0.119181 0.119046 -0.0693168 -0.119207 0.130871 -0.0573577 -0.0603087 0.130386 -0.0573743 -0.0744519 0.136376 -0.0481531 -0.178143 0.131796 -0.0573267 -0.178147 0.136735 -0.0503369 0.116847 0.125316 -0.0637018 0.175797 0.131796 -0.0573267 0.0579912 0.135063 -0.0503912 0.116861 0.130871 -0.0573577 0.116834 0.119046 -0.0693168 0.0579331 0.124923 -0.0637151 0.116823 0.112143 -0.0741246 -0.0011732 0.11874 -0.0693266 -0.0011732 0.0967351 -0.0810641 0.116804 0.0885843 -0.0830962 0.116802 0.0801247 -0.0841289 -0.0011732 0.0801211 -0.0841289 -0.119149 0.0801247 -0.0841289 -0.171676 0.0769329 -0.0842544 -0.173549 0.077581 -0.0842405 -0.172668 0.0770996 -0.0842514 -0.18175 0.147641 -0.01844 -0.181249 0.147403 -0.0200011 -0.178156 0.146174 -0.0265416 -0.18099 0.147031 -0.022265 -0.18099 0.142542 -0.0388892 -0.18099 0.139097 -0.0463041 -0.18099 0.129296 -0.0603134 -0.17814 0.126065 -0.0636769 -0.18099 0.123083 -0.066465 -0.119193 0.125316 -0.0637018 -0.0011732 0.124918 -0.0637153 0.0579622 0.130386 -0.0573743 -0.0011732 0.135057 -0.0503914 0.100939 0.135699 -0.049854 0.11686 0.130662 0.0560959 0.116846 0.125077 0.0624123 0.0555665 0.135023 0.048924 0.05799 0.134891 0.0491533 0.116874 0.135462 0.0491345 0.0579611 0.130181 0.0561124 0.175794 0.125819 0.0623877 0.116834 0.11878 0.0679963 0.175797 0.13158 0.0560651 0.1758 0.136552 0.0490992 0.178643 0.134591 0.0521031 0.178643 0.145227 0.0292403 0.116802 0.0797812 0.0826193 -0.0011732 0.0882199 0.0816276 0.116814 0.10439 0.0766673 -0.0011732 0.0964123 0.0796349 -0.0011732 0.104251 0.0766705 0.116823 0.111853 0.0727702 0.0579319 0.124688 0.0624255 -0.0011732 0.124683 0.0624257 -0.0011732 0.130176 0.0561126 -0.0011732 0.134885 0.0491535 -0.234277 0.146279 0.026145 -0.234276 0.142315 0.038551 -0.234276 0.141204 0.0410486 -0.234274 0.1116 0.0731933 -0.234273 0.0809277 -0.0840756 -0.234274 0.124438 -0.0653711 -0.237524 0.118161 -0.0694051 -0.237523 0.0809365 -0.0832017 -0.240773 0.0875329 -0.0766924 -0.240735 0.0810217 0.0767252 -0.239902 0.0874498 0.0784782 -0.239902 0.0809619 0.079284 -0.234273 0.0809277 0.0825457 -0.237524 0.114291 0.0705433 -0.237524 0.126753 0.0603948 -0.234275 0.131791 0.0560582 -0.236773 0.136916 0.0479634 -0.237524 0.136357 0.0481613 -0.236773 0.132446 0.0544297 -0.234274 0.124438 0.0638411 -0.236773 0.142367 0.0371092 -0.236773 0.144603 0.0306429 -0.237525 0.143532 0.0328307 -0.237525 0.14824 0.00400012 -0.234277 0.148564 0.0118812 -0.236773 0.147906 0.0133224 -0.236773 0.148662 0.00246819 -0.236773 0.148662 -0.00399813 -0.234277 0.149038 -0.00721268 -0.236773 0.147906 -0.0148523 -0.237525 0.147496 -0.0151589 -0.237525 0.146172 -0.0238446 -0.236773 0.146999 -0.0213186 -0.234277 0.147029 -0.0240064 -0.236773 0.136916 -0.0494933 -0.237524 0.136837 -0.0489091 -0.234889 0.132189 -0.0570474 -0.236773 0.132446 -0.0559597 -0.237523 0.0967493 -0.0802225 -0.237523 0.104719 -0.0772341 -0.234274 0.111515 -0.0747721 -0.234273 0.1116 -0.0747235 -0.237524 0.124693 -0.0639465 -0.234274 0.12529 -0.0645806 -0.234276 0.141604 -0.0417085 -0.234276 0.142117 -0.0405439 -0.237525 0.141317 -0.0401992 -0.234276 0.142315 -0.0400809 -0.236773 0.142367 -0.0386391 -0.237523 0.106926 0.0746778 -0.234273 0.107307 0.0754611 -0.237523 0.0990602 0.0779367 -0.237523 0.0878546 0.0808226 -0.237523 0.0809365 0.0816717 -0.237523 0.096078 0.0788959 -0.239902 0.0982822 0.0756883 -0.239902 0.113005 0.0685412 -0.237524 0.120448 0.0661124 -0.237524 0.132293 0.0540202 -0.237525 0.140414 0.0406794 -0.239903 0.138259 0.0396719 -0.237525 0.145428 0.0259555 -0.239903 0.143106 0.0254383 -0.237525 0.14731 0.015142 -0.239903 0.144951 0.0148378 -0.239903 0.145791 -0.00704536 -0.237525 0.148167 -0.0071678 -0.239903 0.145133 -0.0148837 -0.237525 0.144211 -0.0321896 -0.239903 0.143834 -0.0234032 -0.239903 0.141929 -0.0315158 -0.237525 0.140809 -0.0413498 -0.239903 0.139131 -0.0392586 -0.239903 0.138641 -0.0403708 -0.237524 0.132048 -0.0558667 -0.237524 0.126474 -0.0622084 -0.239903 0.123061 -0.0622151 -0.239902 0.116747 -0.0674918 -0.237523 0.111083 -0.0740154 -0.239902 0.0960483 -0.0779489 -0.239902 0.0881173 -0.0798895 -0.237523 0.0885452 -0.0822298 -0.237523 0.0814758 -0.0831601 -0.239902 0.0812835 -0.0807887 -0.239794 0.0809599 -0.0809954 -0.240619 0.0809829 -0.0789641 -0.239902 0.103753 -0.0750601 -0.239902 0.109905 -0.0719487 -0.240773 0.102433 -0.0720904 -0.240773 0.108295 -0.0691255 -0.240773 0.114815 -0.0648783 -0.239903 0.124783 -0.0605348 -0.239903 0.130171 -0.0544044 -0.239903 0.134801 -0.0476785 -0.240773 0.136147 -0.0379739 -0.240773 0.140642 -0.0228005 -0.239903 0.145863 0.00390901 -0.240773 0.142617 0.00378457 -0.240773 0.141729 0.0144224 -0.239903 0.141273 0.0320847 -0.240773 0.138188 0.0310659 -0.239903 0.134337 0.0469046 -0.239903 0.130409 0.0525684 -0.240773 0.131578 0.0451882 -0.239903 0.125053 0.0587306 -0.239903 0.118957 0.0642578 -0.239902 0.105886 0.0725379 -0.240773 0.104466 0.0696149 -0.240773 0.0972195 0.072617 -0.239902 0.0953994 0.0766155 -0.240773 0.0944724 0.0735006 0.234427 0.122037 0.0652839 0.235177 0.114291 0.0705433 0.23193 0.146279 0.026145 0.231931 0.148564 0.0118812 0.234427 0.148662 -0.00399813 0.235177 0.0809365 0.0816717 0.237556 0.0874498 0.0784782 0.238427 0.0868968 0.0752755 0.238389 0.0810217 0.0767252 0.23743 0.0809595 -0.081024 0.237556 0.0812835 -0.0807887 0.234427 0.120072 -0.0684149 0.234427 0.113061 -0.0732802 0.233271 0.11265 -0.0739472 0.234427 0.142367 -0.0386391 0.234427 0.144603 -0.0321728 0.235179 0.146172 -0.0238446 0.234427 0.146999 -0.0213186 0.234427 0.148662 0.00246819 0.235179 0.148167 -0.0071678 0.231931 0.149038 -0.00721268 0.235179 0.145428 0.0259555 0.235179 0.14731 0.015142 0.234427 0.142367 0.0371092 0.23193 0.142315 0.038551 0.231929 0.141204 0.0410486 0.234427 0.136916 0.0479634 0.235178 0.136357 0.0481613 0.234427 0.132446 0.0544297 0.231928 0.131942 0.0558721 0.235178 0.126753 0.0603948 0.23416 0.122379 0.06513 0.233145 0.112577 0.0724903 0.234427 0.113061 0.0717502 0.231927 0.0970058 -0.0810547 0.235177 0.104719 -0.0772341 0.235177 0.111083 -0.0740154 0.231927 0.111515 -0.0747721 0.231928 0.127093 -0.0628213 0.235178 0.132048 -0.0558667 0.235178 0.136837 -0.0489091 0.235178 0.140809 -0.0413498 0.231929 0.141604 -0.0417085 0.235178 0.141317 -0.0401992 0.23193 0.142315 -0.0400809 0.238427 0.0875329 -0.0766924 0.238427 0.0950908 -0.0748432 0.237556 0.0960483 -0.0779489 0.237556 0.103753 -0.0750601 0.237556 0.109905 -0.0719487 0.237556 0.123061 -0.0622151 0.238427 0.120832 -0.0598501 0.237556 0.124783 -0.0605348 0.238427 0.122473 -0.0582488 0.238427 0.127608 -0.0524071 0.238427 0.13202 -0.0459977 0.238427 0.135679 -0.0390338 0.237556 0.138641 -0.0403708 0.238427 0.136147 -0.0379739 0.237557 0.141929 -0.0315158 0.238427 0.138813 -0.0305956 0.237557 0.143834 -0.0234032 0.238427 0.140642 -0.0228005 0.238427 0.142546 -0.00687815 0.237557 0.145791 -0.00704536 0.237557 0.145863 0.00390901 0.238427 0.141729 0.0144224 0.238427 0.139934 0.0247321 0.237556 0.141273 0.0320847 0.238427 0.138188 0.0310659 0.237556 0.138259 0.0396719 0.237556 0.134337 0.0469046 0.238427 0.127834 0.0505855 0.238427 0.122731 0.0564575 0.237556 0.125053 0.0587306 0.238427 0.116922 0.0617246 0.237556 0.118957 0.0642578 0.238427 0.11125 0.0658064 0.237556 0.113005 0.0685412 0.238427 0.104466 0.0696149 0.237556 0.105886 0.0725379 0.238427 0.0972195 0.072617 0.235997 0.0809423 0.0811085 0.237556 0.0953994 0.0766155 0.237556 0.0982822 0.0756883 0.235177 0.0990602 0.0779367 0.235177 0.106926 0.0746778 0.235177 0.120448 0.0661124 0.237556 0.130409 0.0525684 0.235178 0.132293 0.0540202 0.235178 0.140414 0.0406794 0.235179 0.143532 0.0328307 0.237557 0.143106 0.0254383 0.237557 0.144951 0.0148378 0.235179 0.14824 0.00400012 0.237557 0.145133 -0.0148837 0.235179 0.147496 -0.0151589 0.235179 0.144211 -0.0321896 0.237556 0.139131 -0.0392586 0.237556 0.134801 -0.0476785 0.237556 0.130171 -0.0544044 0.235178 0.126474 -0.0622084 0.237556 0.116747 -0.0674918 0.235177 0.124693 -0.0639465 0.235177 0.118161 -0.0694051 0.237556 0.0881173 -0.0798895 0.235177 0.0967493 -0.0802225 0.235177 0.0885452 -0.0822298 0.235177 0.0814758 -0.0831601 0.235979 0.0809421 -0.082653 0.235177 0.0809365 -0.0832017 0.231927 0.1116 0.0731936 0.231927 0.107307 0.0754611 0.235177 0.096078 0.0788959 0.231927 0.099345 0.0787597 0.231927 0.0963264 0.0797305 0.235177 0.0878546 0.0808226 0.234088 0.0809314 0.0821747 -0.241773 0.101185 0.0616179 -0.242273 0.112336 0.0549995 -0.242273 0.120241 0.0482731 -0.241773 0.122052 0.0464115 -0.241773 0.12999 0.0361574 -0.242273 0.12999 0.0361574 -0.242273 0.135869 0.0245991 -0.241773 0.135869 0.0245991 -0.241773 0.1407 -0.000764971 -0.242273 0.1407 -0.000764971 -0.241773 0.139481 -0.013675 -0.241773 0.138318 -0.0187365 -0.242273 0.139481 -0.013675 -0.242273 0.138318 -0.0187365 -0.241773 0.135869 -0.0261291 -0.242273 0.135869 -0.0261291 -0.242273 0.131338 -0.0354675 -0.241773 0.122052 -0.0479415 -0.242273 0.12999 -0.0376873 -0.241773 0.112336 -0.0565294 -0.242273 0.112336 -0.0565294 -0.242273 0.105794 -0.0607534 -0.241773 0.101185 -0.0631478 -0.242273 0.101185 -0.0631478 0.239427 0.0889926 0.066033 0.239427 0.101185 0.0616179 0.239927 0.105794 0.0592235 0.239427 0.105794 0.0592235 0.239927 0.112336 0.0549995 0.239927 0.120241 0.0482731 0.239427 0.120241 0.0482731 0.239427 0.12999 0.0361574 0.239927 0.135869 0.0245991 0.239427 0.135869 0.0245991 0.239427 0.138318 0.0172066 0.239927 0.139481 0.0121451 0.239927 0.1407 -0.000764971 0.239927 0.138318 -0.0187365 0.239927 0.131338 -0.0354675 0.239927 0.12999 -0.0376873 0.239427 0.131338 -0.0354675 0.239927 0.122052 -0.0479415 0.239927 0.120241 -0.049803 0.239927 0.105794 -0.0607534 0.239427 0.101185 -0.0631478 0.239927 0.101185 -0.0631478 0.239927 0.0889926 -0.0675629 0.239427 0.0889926 -0.0675629 -0.240773 0.0868968 0.0752755 -0.240773 0.0854077 0.0688443 -0.240773 0.135316 0.0382957 -0.240773 0.138813 -0.0305956 -0.240773 0.13202 -0.0459977 -0.240773 0.135679 -0.0390338 -0.240773 0.112925 -0.0573376 -0.240773 0.120832 -0.0598501 -0.240773 0.122473 -0.0582488 -0.240773 0.127608 -0.0524071 -0.240773 0.0811227 -0.077541 -0.240773 0.0892432 -0.068531 -0.240773 0.0950908 -0.0748432 -0.240773 0.101613 -0.0640519 -0.240773 0.116922 0.0617246 -0.240773 0.101613 0.062522 -0.240773 0.11125 0.0658064 -0.240773 0.127834 0.0505855 -0.240773 0.122731 0.0564575 -0.240773 0.141906 -0.0145078 -0.240773 0.142546 -0.00687815 -0.240773 0.140464 0.0123322 -0.240773 0.139934 0.0247321 -0.240773 0.136799 0.0249667 -0.243273 0.0811227 0.0760111 -0.243273 0.0849771 0.0691837 -0.243273 0.0867354 0.0753032 -0.243273 0.0892432 0.0670011 -0.243273 0.101613 0.062522 -0.243273 0.130835 0.0366925 -0.243273 0.136799 0.0249667 -0.243273 0.13526 0.0384148 -0.243273 0.112925 -0.0573376 -0.243273 0.122782 -0.0486252 -0.243273 0.132088 -0.0458848 -0.243273 0.112925 0.0558077 -0.243273 0.122782 0.0470953 -0.243273 0.0972195 0.072617 -0.243273 0.104347 0.0696722 -0.243273 0.116922 0.0617246 -0.243273 0.0825587 -0.0735352 -0.243273 0.0877912 -0.0766447 -0.243273 0.0892432 -0.068531 -0.243273 0.0952165 -0.0748043 -0.243273 0.102433 -0.0720904 -0.243273 0.101613 -0.0640519 -0.243273 0.108523 -0.068995 -0.243273 0.120832 -0.0598501 -0.243273 0.142605 0.00406714 -0.243273 0.142566 -0.00649037 -0.243273 0.140464 -0.0138621 -0.243273 0.141906 -0.0145078 -0.243273 0.136799 -0.0264967 -0.243227 0.0810385 -0.0784635 -0.243227 0.0810385 0.0769336 -0.238773 0.0816509 -0.0853181 -0.238773 0.0810631 0.0838333 -0.237246 0.0810682 -0.0860654 -0.234273 0.0978853 -0.0833995 -0.238773 0.0975277 -0.0822479 -0.234273 0.0914689 -0.085084 -0.234273 0.0817483 -0.0865199 -0.238775 0.133936 -0.0569656 -0.234275 0.129185 -0.0642597 -0.234275 0.127005 -0.0664 -0.238774 0.126177 -0.0655221 -0.238774 0.119566 -0.0710588 -0.238774 0.112411 -0.0757502 -0.234274 0.113012 -0.0767955 -0.234274 0.106089 -0.0803144 -0.238773 0.105599 -0.0792125 -0.234277 0.14154 -0.0474715 -0.234276 0.1398 -0.0505247 -0.234277 0.144533 -0.0412522 -0.238776 0.146337 -0.0326331 -0.234278 0.149502 -0.0243832 -0.238776 0.148315 -0.02416 -0.238776 0.150349 -0.00686598 -0.234279 0.151555 -0.00692418 -0.238776 0.150391 0.00438414 -0.238776 0.149433 0.0156043 -0.238776 0.147541 0.026426 -0.234278 0.147522 0.031351 -0.238776 0.145495 0.033788 -0.238775 0.142313 0.0417293 -0.234277 0.14664 0.0341711 -0.234277 0.141371 0.0462535 -0.238775 0.138195 0.0493049 -0.234276 0.13922 0.0499423 -0.238774 0.121804 0.0678 -0.234274 0.115861 0.0735407 -0.234274 0.108265 0.0777749 -0.238773 0.0963778 0.0810648 -0.234273 0.0967166 0.082222 -0.243273 0.114921 -0.0648001 -0.242068 0.117602 -0.0684135 -0.242068 0.123918 -0.0631247 -0.243273 0.122751 -0.057967 -0.242068 0.125967 -0.061113 -0.242068 0.131329 -0.0549512 -0.243273 0.127769 -0.0521999 -0.242068 0.135943 -0.0482043 -0.243273 0.135679 -0.0390338 -0.243273 0.136252 -0.0377275 -0.243273 0.138858 -0.030444 -0.242068 0.140392 -0.0394894 -0.243273 0.140657 -0.0227197 -0.242068 0.146374 -0.0150282 -0.242068 0.147059 -0.0067072 -0.243273 0.141706 0.0145965 -0.242068 0.146167 0.0151783 -0.243273 0.139934 0.0247321 -0.243273 0.138105 0.0313149 -0.242068 0.142371 0.0327426 -0.242068 0.139332 0.0403283 -0.243273 0.131578 0.0451882 -0.243273 0.127674 0.0507931 -0.243273 0.122638 0.0565514 -0.242068 0.125848 0.0597052 -0.242068 0.11974 0.0652321 -0.243273 0.111029 0.0659477 -0.242068 0.113445 0.069744 -0.242067 0.098691 0.0768696 -0.242067 0.0954524 0.0779032 -0.243273 0.0941883 0.0735844 -0.243086 0.0810159 0.0778524 -0.242067 0.08749 0.0797395 -0.238773 0.0880424 0.0829871 -0.238773 0.0997682 0.0799827 -0.242068 0.106306 0.0737234 -0.238773 0.10774 0.0766892 -0.238774 0.115213 0.0725232 -0.238774 0.128197 0.0620141 -0.238775 0.133829 0.0555734 -0.242068 0.131227 0.0535528 -0.242068 0.135398 0.0475648 -0.242068 0.144325 0.02571 -0.242068 0.1471 0.00425014 -0.238776 0.149646 -0.0154094 -0.242068 0.145078 -0.0235512 -0.242068 0.143175 -0.0317078 -0.238775 0.143423 -0.0407794 -0.242068 0.13978 -0.0408851 -0.238775 0.142782 -0.0422406 -0.238775 0.138766 -0.0499025 -0.238774 0.128323 -0.0634162 -0.242068 0.110767 -0.0728951 -0.242067 0.104261 -0.0762023 -0.242067 0.0965508 -0.0791019 -0.238773 0.0892235 -0.0843062 -0.242067 0.0886181 -0.081068 -0.242067 0.0813845 -0.0820347 -0.239884 0.0810575 -0.0846044 -0.234273 0.0911219 0.0836281 -0.234273 0.0882446 0.0841758 0.169329 0.07595 -0.0857544 0.0219727 0.07595 -0.0857543 0.238427 0.0944724 0.0735006 0.238427 0.0892432 0.0670011 0.238427 0.101613 0.062522 0.238427 0.141906 -0.0145078 0.238427 0.136799 0.0249667 0.238427 0.142617 0.00378457 0.238427 0.131578 0.0451882 0.238427 0.135316 0.0382957 0.238427 0.112925 0.0558077 0.238427 0.0892432 -0.068531 0.238427 0.102433 -0.0720904 0.238427 0.108295 -0.0691255 0.238427 0.101613 -0.0640519 0.238427 0.114815 -0.0648783 0.238427 0.122782 -0.0486252 0.238427 0.112925 -0.0573376 0.238427 0.130835 -0.0382224 0.168979 0.0756 0.0842295 0.0226401 0.0756 0.0837295 0.168979 0.0756 0.0837295 0.240927 0.0811227 0.0760111 0.240927 0.0820438 0.0729731 0.240927 0.0849771 0.0691837 0.240927 0.0941883 0.0735844 0.240927 0.101613 0.062522 0.240927 0.112925 0.0558077 0.240927 0.114921 -0.0648001 0.240927 0.116922 0.0617246 0.240927 0.0972195 0.072617 0.240927 0.0892432 -0.068531 0.240927 0.122782 0.0470953 0.240927 0.127674 0.0507931 0.240927 0.142566 -0.00649037 0.240927 0.1417 -0.000764971 0.240927 0.140464 0.0123322 0.240927 0.141706 0.0145965 0.240927 0.139934 0.0247321 0.240927 0.138105 0.0313149 0.240927 0.140657 -0.0227197 0.240927 0.141906 -0.0145078 0.240927 0.138858 -0.030444 0.240927 0.132088 -0.0458848 0.240927 0.120832 -0.0598501 0.240927 0.122751 -0.057967 0.240927 0.122782 -0.0486252 0.236427 0.0997682 0.0799827 0.237538 0.0810575 0.0830744 0.239721 0.08749 0.0797395 0.236427 0.0810631 0.0838333 0.236427 0.0810631 -0.0853633 0.236427 0.0816509 -0.0853181 0.236427 0.0892235 -0.0843062 0.231927 0.0978853 -0.0833995 0.236428 0.126177 -0.0655221 0.236428 0.133936 -0.0569656 0.23193 0.1398 -0.0505247 0.231931 0.144533 -0.0412522 0.236429 0.143423 -0.0407794 0.231932 0.149502 -0.0243832 0.231932 0.150846 -0.0155491 0.231932 0.151555 -0.00692418 0.23643 0.150349 -0.00686598 0.231932 0.151598 0.00443326 0.231932 0.148719 0.0266884 0.231931 0.14664 0.0341711 0.236429 0.145495 0.033788 0.23193 0.143405 0.0422427 0.236429 0.142313 0.0417293 0.231929 0.134782 0.0563134 0.236428 0.133829 0.0555734 0.231928 0.126554 0.0652914 0.236428 0.128197 0.0620141 0.231928 0.115861 0.0735407 0.231927 0.106448 0.0786237 0.236427 0.10774 0.0766892 0.231927 0.0967166 0.082222 0.236427 0.0880424 0.0829871 0.236427 0.0963778 0.0810648 0.239721 0.098691 0.0768696 0.239721 0.106306 0.0737234 0.239721 0.113445 0.069744 0.236427 0.115213 0.0725232 0.239721 0.11974 0.0652321 0.236427 0.121804 0.0678 0.239721 0.125848 0.0597052 0.239721 0.131227 0.0535528 0.236429 0.138195 0.0493049 0.239722 0.142371 0.0327426 0.23643 0.147541 0.026426 0.23643 0.149433 0.0156043 0.239722 0.1471 0.00425014 0.23643 0.150391 0.00438414 0.239722 0.147059 -0.0067072 0.23643 0.149646 -0.0154094 0.239722 0.145078 -0.0235512 0.23643 0.148315 -0.02416 0.236429 0.146337 -0.0326331 0.239722 0.140392 -0.0394894 0.239722 0.135943 -0.0482043 0.236429 0.142782 -0.0422406 0.236429 0.138766 -0.0499025 0.239721 0.125967 -0.061113 0.236428 0.128323 -0.0634162 0.239721 0.117602 -0.0684135 0.236427 0.119566 -0.0710588 0.236427 0.112411 -0.0757502 0.239721 0.110767 -0.0728951 0.239721 0.104261 -0.0762023 0.236427 0.105599 -0.0792125 0.239721 0.0965508 -0.0791019 0.236427 0.0975277 -0.0822479 0.239721 0.0813845 -0.0820347 0.239721 0.0886181 -0.081068 0.240927 0.0877912 -0.0766447 0.240927 0.0952165 -0.0748043 0.240927 0.102433 -0.0720904 0.240927 0.108523 -0.068995 0.239721 0.123918 -0.0631247 0.239721 0.131329 -0.0549512 0.240927 0.127769 -0.0521999 0.239722 0.13978 -0.0408851 0.240927 0.135679 -0.0390338 0.240927 0.136252 -0.0377275 0.239722 0.143175 -0.0317078 0.239722 0.146374 -0.0150282 0.240927 0.142605 0.00406714 0.239722 0.146167 0.0151783 0.239722 0.144325 0.02571 0.239722 0.139332 0.0403283 0.240927 0.13526 0.0384148 0.239722 0.135398 0.0475648 0.240927 0.131578 0.0451882 0.240927 0.122638 0.0565514 0.240927 0.111029 0.0659477 0.240927 0.104347 0.0696722 0.239721 0.0954524 0.0779032 0.240927 0.0867354 0.0753032 0.172158 0.0771215 -0.085234 0.172158 0.0771215 -0.0857342 0.176693 0.08 -0.0850729 0.20431 0.08 -0.085073 0.176693 0.08 -0.0855742 0.231927 0.08 -0.085073 0.231927 0.08 -0.0855743 0.234404 0.08 -0.0846509 0.237022 0.08 -0.0837369 0.236603 0.08 -0.0834327 0.238277 0.08 -0.0815546 0.173864 0.0788284 0.0841351 0.171808 0.0767715 0.0837134 0.238297 0.08 0.0799917 0.2387 0.08 0.0802913 0.236623 0.08 0.081886 0.23457 0.08 0.0835941 -0.176211 0.0788284 -0.0851644 -0.176211 0.0788284 -0.0856651 -0.240644 0.08 -0.0815216 -0.23897 0.08 -0.083416 -0.239261 0.08 -0.0838246 -0.236767 0.08 -0.0846452 -0.234273 0.08 -0.085073 -0.234273 0.08 -0.0855743 -0.206656 0.08 -0.085073 -0.179039 0.08 -0.0850729 -0.206656 0.08 0.083543 -0.206656 0.08 0.0840443 -0.234273 0.08 0.0835431 -0.237037 0.08 0.0835506 -0.239368 0.08 0.082207 -0.241126 0.08 0.0801617 -0.174154 0.0767715 0.0837134 -0.175183 0.0778001 0.0836812 -0.177717 0.0797752 -0.0855939 -0.176544 0.0791264 -0.0856447 -0.177717 0.0797752 -0.0850927 -0.176211 0.0788284 0.0841351 -0.179039 0.08 0.0840442 -0.179039 0.08 0.0835429 -0.178597 0.0799754 0.0840464 -0.177306 0.079605 0.0835771 0.174198 0.0791265 0.083614 0.17496 0.079605 -0.0856081 0.17496 0.079605 -0.085107 0.169772 0.0759745 -0.085254 -0.171326 0.0756 0.0842295 -0.171768 0.0756245 0.0837293 -0.171768 0.0756245 0.0842293 -0.173059 0.0759949 0.0842253 -0.173059 0.0759949 0.0837253 -0.174504 0.0771215 -0.085234 -0.174504 0.0771215 -0.0857342 -0.174174 0.0768261 -0.0857403 -0.172999 0.0761754 -0.0852512 -0.172999 0.0761754 -0.0857513 -0.241773 0.0889926 -0.0675629 -0.242273 0.0848083 -0.0695737 -0.241729 0.0800331 -0.0782888 -0.241773 0.0801339 -0.077392 -0.242273 0.0801339 -0.077392 -0.242273 0.0817004 -0.0730221 0.23976 0.08 -0.07918 0.239427 0.0801339 -0.077392 0.239927 0.0801339 -0.077392 0.239427 0.0817004 -0.0730221 0.239927 0.0811386 -0.0740778 0.239927 0.0817004 -0.0730221 0.239427 0.0843386 -0.069944 0.239927 0.0843386 -0.069944 0.239427 0.0848083 -0.0695737 -0.242107 0.08 0.07765 -0.241729 0.0800331 0.0767588 -0.242273 0.0811386 0.0725479 -0.241773 0.0817004 0.0714921 -0.241773 0.0848083 0.0680437 -0.242273 0.0889926 0.066033 0.239427 0.0843386 0.068414 0.239927 0.0889926 0.066033 0.239886 0.0800331 0.0767582 0.239249 0.08 0.07765 0.239383 0.0800331 0.0767588 0.239427 0.0811386 0.0725479 0.169772 0.0759745 -0.0857541 0.169329 0.0760277 -0.086141 0.169704 0.0766001 -0.0866828 0.169329 0.0765791 -0.086683 0.169661 0.0769856 -0.0867539 0.169329 0.0769669 -0.0867542 0.169764 0.0760519 -0.0861407 0.171032 0.0764167 -0.0861358 0.16974 0.0762718 -0.0864672 0.170797 0.0769168 -0.0866779 0.170629 0.0772672 -0.0867485 0.171062 0.076345 -0.0857487 0.172108 0.0771823 -0.0861215 0.170938 0.0766178 -0.0864625 -0.171676 0.07595 -0.0857544 -0.171676 0.0760277 -0.086141 -0.171676 0.0762489 -0.0864674 -0.171676 0.0765791 -0.086683 0.0219727 0.0765791 -0.086683 -0.171676 0.0769669 -0.0867542 0.0219727 0.0760277 -0.086141 0.0219727 0.0762489 -0.0864674 0.169329 0.0762489 -0.0864674 0.172963 0.0780387 -0.0860937 0.172811 0.0782039 -0.0864215 0.171956 0.0773441 -0.0864484 0.171725 0.0775815 -0.0866636 0.173818 0.0788949 -0.086056 0.173011 0.0779751 -0.0857046 0.173667 0.0790635 -0.0863846 0.172579 0.0784445 -0.0866361 0.173434 0.0793074 -0.0865985 0.173157 0.0795875 -0.0866637 0.172304 0.0787226 -0.0867038 -0.17413 0.076891 -0.0861276 -0.173791 0.0773286 -0.0866697 -0.173549 0.0776329 -0.0867399 -0.173995 0.0770677 -0.0864544 -0.172976 0.0762497 -0.0861382 -0.172905 0.0764593 -0.0864648 -0.172796 0.0767718 -0.0866803 0.176184 0.0806393 -0.0865193 0.176221 0.0802926 -0.0863081 0.176245 0.0800584 -0.0859754 0.176251 0.0799754 -0.0855764 0.17614 0.0810408 -0.0865738 0.174934 0.0796836 -0.0860041 0.174526 0.0805714 -0.086606 0.174698 0.0802099 -0.0865476 0.174842 0.0798969 -0.0863354 0.173864 0.0788284 -0.0856651 -0.175358 0.0779751 -0.0857046 -0.176165 0.0788949 -0.086056 -0.175781 0.0793074 -0.0865985 -0.174454 0.0771823 -0.0861215 -0.17531 0.0780387 -0.0860937 -0.174302 0.0773441 -0.0864484 -0.174071 0.0775815 -0.0866636 -0.175158 0.0782039 -0.0864215 -0.173797 0.0778575 -0.0867338 -0.174926 0.0784445 -0.0866361 0.176693 0.0800831 -0.0859734 0.20431 0.0800831 -0.0859735 0.20431 0.0803187 -0.0863063 0.176693 0.0803187 -0.0863062 0.20431 0.0806676 -0.0865174 0.176693 0.0806677 -0.0865173 0.176693 0.0810719 -0.0865716 0.20431 0.08 -0.0855743 0.231927 0.0806676 -0.0865175 0.20431 0.0810718 -0.0865717 -0.176372 0.0793839 -0.086367 -0.176013 0.0790635 -0.0863846 -0.176505 0.0791981 -0.0860374 -0.176166 0.0796541 -0.0865803 -0.177698 0.0798559 -0.0859913 -0.179039 0.0806677 -0.0865173 -0.177518 0.0804073 -0.0865349 -0.179039 0.0803187 -0.0863062 -0.177628 0.0800788 -0.0863232 -0.179039 0.0800831 -0.0859734 0.234828 0.0800827 -0.0854542 0.234943 0.0803173 -0.0857661 0.231927 0.0800831 -0.0859735 0.231927 0.0803187 -0.0863064 0.235017 0.0806648 -0.0859644 0.235036 0.0810678 -0.0860165 0.23469 0.08 -0.0850805 0.237486 0.0803132 -0.0842967 0.237621 0.080657 -0.0844603 0.237275 0.0800816 -0.0840417 0.239581 0.0806445 -0.082173 0.237659 0.0810567 -0.0845058 0.240139 0.0800776 -0.0792581 0.23878 0.08 -0.0816917 0.239115 0.0800799 -0.0818934 0.239397 0.0803068 -0.0820628 0.240669 0.0806284 -0.0793678 0.240739 0.0810159 -0.0793823 0.239636 0.0810391 -0.0822062 -0.234273 0.0800831 -0.0859735 -0.206656 0.0800831 -0.0859735 -0.206656 0.0803187 -0.0863063 -0.179039 0.08 -0.0855742 -0.206656 0.08 -0.0855743 -0.206656 0.0806676 -0.0865174 0.239886 0.0800331 -0.0782881 0.24027 0.0801077 -0.0783325 0.240458 0.0802985 -0.0793242 0.240595 0.0803254 -0.0783815 0.240809 0.0806526 -0.0784276 0.240851 0.0807443 -0.077484 0.240927 0.0811227 -0.077541 0.24088 0.0810385 -0.0784635 -0.237228 0.080665 -0.0860131 -0.241379 0.08008 -0.0820294 -0.241658 0.0803072 -0.0822043 -0.241839 0.0806453 -0.0823178 -0.243016 0.0806284 -0.0793678 -0.241893 0.0810402 -0.0823519 -0.241046 0.08 -0.0818213 -0.239508 0.0800817 -0.0841339 -0.239847 0.0806575 -0.0845584 -0.237048 0.0800827 -0.0854999 -0.237158 0.0803174 -0.0858136 -0.239715 0.0803135 -0.0843926 -0.238773 0.0810631 -0.0853633 -0.236916 0.08 -0.085124 -0.234273 0.0803187 -0.0863064 -0.234273 0.0806676 -0.0865175 -0.234273 0.0810718 -0.0865717 0.240309 0.0802092 -0.0774034 0.240634 0.0819518 -0.0731724 0.240634 0.0804235 -0.0774357 0.240927 0.0825587 -0.0735352 0.240309 0.0817658 -0.0730611 0.240309 0.084854 -0.0696346 0.240851 0.0851783 -0.0700678 0.240851 0.0822303 -0.0733388 0.240927 0.0854077 -0.0703742 0.240851 0.0891473 -0.0681605 0.240634 0.0849839 -0.0698081 0.239927 0.0848083 -0.0695737 -0.242656 0.0802092 -0.0774034 -0.242616 0.0801077 -0.0783325 -0.243156 0.0806526 -0.0784276 -0.242107 0.08 -0.07918 -0.242232 0.0800331 -0.0782881 -0.242485 0.0800776 -0.0792581 -0.242805 0.0802985 -0.0793242 -0.242941 0.0803254 -0.0783815 -0.243086 0.0810159 -0.0793823 0.240427 0.0890261 0.0661627 0.240309 0.101218 0.0616867 0.240309 0.0890116 0.0661067 0.239927 0.101185 0.0616179 0.240309 0.112381 0.055061 0.239927 0.138318 0.0172066 0.239927 0.122052 0.0464115 0.240309 0.122108 0.0464636 0.239927 0.12999 0.0361574 0.240309 0.130054 0.0361981 0.239927 0.131338 0.0339376 0.240309 0.139556 0.0121593 0.239927 0.139481 -0.013675 0.240309 0.140776 -0.000764971 0.239927 0.135869 -0.0261291 0.240309 0.130054 -0.037728 0.240309 0.112381 -0.0565909 0.239927 0.112336 -0.0565294 0.240793 0.0891179 0.066517 0.240634 0.10131 0.0618827 0.240634 0.130238 0.0363141 0.240309 0.13594 0.0246271 0.240634 0.139769 0.0121999 0.240309 0.139556 -0.0136893 0.240309 0.13594 -0.0261571 0.240634 0.136141 -0.0262367 0.240634 0.130238 -0.037844 0.240309 0.122108 -0.0479935 0.240634 0.122266 -0.0481417 0.240309 0.101218 -0.0632166 0.240309 0.0890116 -0.0676366 0.240634 0.089066 -0.0678465 0.240851 0.101449 0.062176 0.240634 0.112509 0.0552362 0.240851 0.1127 0.0554984 0.240634 0.122266 0.0466118 0.240634 0.136141 0.0247068 0.240851 0.136443 0.0248261 0.240634 0.140993 -0.000764971 0.240634 0.139769 -0.0137298 0.240851 0.140088 -0.0137905 0.240851 0.136443 -0.026356 0.240851 0.130512 -0.0380176 0.240851 0.122503 -0.0483636 0.240851 0.1127 -0.0570283 0.240634 0.112509 -0.0567661 0.240634 0.10131 -0.0634126 0.240851 0.101449 -0.0637059 0.240927 0.0892432 0.0670011 0.240851 0.122503 0.0468336 0.240851 0.130512 0.0364877 0.240927 0.130835 0.0366925 0.240927 0.136799 0.0249667 0.240851 0.140088 0.0122606 0.240851 0.141317 -0.000764971 0.240927 0.140464 -0.0138621 0.240927 0.136799 -0.0264967 0.240927 0.130835 -0.0382224 0.240927 0.112925 -0.0573376 0.240927 0.101613 -0.0640519 -0.24298 0.0804235 -0.0774357 -0.24298 0.0819518 -0.0731724 -0.243197 0.0807443 -0.077484 -0.243273 0.0811227 -0.077541 -0.242656 0.0817658 -0.0730611 -0.243197 0.0822303 -0.0733388 -0.243197 0.0851783 -0.0700678 -0.242656 0.084854 -0.0696346 -0.242656 0.0890116 -0.0676366 -0.24298 0.089066 -0.0678465 -0.24298 0.0849839 -0.0698081 -0.243273 0.0854077 -0.0703742 0.240793 0.0846578 0.0687988 0.240427 0.0844241 0.0685171 0.240851 0.0891473 0.0666306 0.240793 0.0815912 0.0727605 0.240634 0.089066 0.0663165 0.240793 0.0806283 0.0759366 0.240427 0.0812599 0.0726048 0.240427 0.0802664 0.0758821 0.240309 0.0802092 0.0758734 0.239927 0.0843386 0.068414 0.239927 0.0811386 0.0725479 -0.242273 0.120241 -0.049803 -0.242273 0.122052 -0.0479415 -0.242656 0.122108 -0.0479935 -0.243197 0.140088 0.0122606 -0.243273 0.1417 -0.000764971 -0.243273 0.140464 0.0123322 -0.243197 0.0891473 0.0666306 -0.243139 0.0891179 0.066517 -0.243197 0.130512 0.0364877 -0.243197 0.136443 0.0248261 -0.242656 0.139556 0.0121593 -0.242656 0.13594 0.0246271 -0.24298 0.139769 0.0121999 -0.243197 0.140088 -0.0137905 -0.243197 0.141317 -0.000764971 -0.24298 0.140993 -0.000764971 -0.242273 0.101185 0.0616179 -0.242656 0.0890116 0.0661067 -0.24298 0.10131 0.0618827 -0.243197 0.101449 0.062176 -0.243197 0.1127 0.0554984 -0.242656 0.101218 0.0616867 -0.242273 0.105794 0.0592235 -0.242273 0.122052 0.0464115 -0.242656 0.122108 0.0464636 -0.24298 0.122266 0.0466118 -0.242656 0.112381 0.055061 -0.24298 0.112509 0.0552362 -0.243197 0.122503 0.0468336 -0.24298 0.130238 0.0363141 -0.24298 0.136141 0.0247068 -0.242656 0.130054 0.0361981 -0.242656 0.139556 -0.0136893 -0.242656 0.140776 -0.000764971 -0.242273 0.139481 0.0121451 -0.242273 0.138318 0.0172066 -0.242273 0.131338 0.0339376 -0.243197 0.136443 -0.026356 -0.24298 0.139769 -0.0137298 -0.242656 0.13594 -0.0261571 -0.242656 0.130054 -0.037728 -0.24298 0.130238 -0.037844 -0.24298 0.136141 -0.0262367 -0.243197 0.130512 -0.0380176 -0.243273 0.130835 -0.0382224 -0.243197 0.122503 -0.0483636 -0.24298 0.122266 -0.0481417 -0.243197 0.1127 -0.0570283 -0.242656 0.112381 -0.0565909 -0.24298 0.112509 -0.0567661 -0.243197 0.101449 -0.0637059 -0.24298 0.10131 -0.0634126 -0.243197 0.0891473 -0.0681605 -0.242656 0.101218 -0.0632166 -0.242273 0.0889926 -0.0675629 0.239927 0.0801339 0.0758621 0.240851 0.0807443 0.0759541 0.24088 0.0810385 0.0769336 0.240595 0.0803254 0.0768516 0.240634 0.0804235 0.0759057 0.240139 0.0800776 0.0777282 0.24027 0.0801077 0.0768026 0.240458 0.0802985 0.0777942 0.240669 0.0806284 0.0778379 0.240809 0.0806526 0.0768976 -0.242273 0.0843386 0.068414 -0.242773 0.0890261 0.0661627 -0.242273 0.0801339 0.0758621 -0.242773 0.0812599 0.0726048 -0.242773 0.0844241 0.0685171 -0.24298 0.089066 0.0663165 -0.242773 0.0802664 0.0758821 -0.24298 0.0804235 0.0759057 -0.243139 0.0815912 0.0727605 -0.243197 0.0807443 0.0759541 -0.243139 0.0846578 0.0687988 -0.243273 0.0820438 0.0729731 0.2349 0.0810682 0.0845355 0.239721 0.0810379 0.0805318 0.240739 0.0810159 0.0778524 0.23976 0.08 0.07765 0.239311 0.0803072 0.0806743 0.239492 0.0806453 0.0807879 0.237162 0.0800817 0.0826039 0.239032 0.08008 0.0804995 0.237501 0.0806575 0.0830285 0.239547 0.0810402 0.0808219 0.234701 0.0800827 0.08397 0.236914 0.08 0.0822947 0.237368 0.0803135 0.0828626 0.234882 0.080665 0.0844832 0.231927 0.0803187 0.0847764 0.234812 0.0803174 0.0842837 0.231927 0.0810718 0.0850418 -0.242805 0.0802985 0.0777942 -0.243156 0.0806526 0.0768976 -0.242616 0.0801077 0.0768026 -0.242941 0.0803254 0.0768516 -0.243016 0.0806284 0.0778379 -0.243139 0.0806283 0.0759366 -0.242232 0.0800331 0.0767582 -0.242656 0.0802092 0.0758734 0.231927 0.08 0.0840444 0.20431 0.0800831 0.0844436 0.231927 0.0800831 0.0844436 0.20431 0.0803187 0.0847764 0.20431 0.0806676 0.0849875 0.231927 0.0806676 0.0849875 0.176693 0.08 0.0840442 0.176693 0.0800831 0.0844435 0.20431 0.08 0.0840443 0.176693 0.0803187 0.0847763 0.20431 0.0810718 0.0850418 -0.240005 0.0810567 0.0829758 -0.234273 0.08 0.0840444 -0.23729 0.0803173 0.0842361 -0.234273 0.0800831 0.0844436 -0.237382 0.0810678 0.0844866 -0.237175 0.0800827 0.0839243 -0.237363 0.0806648 0.0844345 -0.241462 0.0800799 0.0803634 -0.239621 0.0800816 0.0825118 -0.239832 0.0803132 0.0827668 -0.241983 0.0810391 0.0806762 -0.239968 0.080657 0.0829304 -0.242485 0.0800776 0.0777282 -0.241744 0.0803068 0.0805329 -0.241927 0.0806445 0.080643 0.173157 0.0795875 0.0851338 0.173818 0.0788949 0.084526 0.17504 0.0807871 0.0850616 0.173819 0.0796541 0.0850504 0.174025 0.0793839 0.084837 0.175371 0.0797752 0.0840639 0.174159 0.0791981 0.0845075 0.174198 0.0791264 0.0841148 0.176693 0.0806677 0.0849874 0.175172 0.0804073 0.0850049 0.175282 0.0800788 0.0847932 0.175352 0.0798559 0.0844613 -0.206656 0.0800831 0.0844436 -0.206656 0.0806676 0.0849875 -0.179039 0.0806677 0.0849874 -0.206656 0.0810718 0.0850418 -0.234273 0.0803187 0.0847764 -0.206656 0.0803187 0.0847764 -0.234273 0.0806676 0.0849875 -0.234273 0.0810718 0.0850418 0.172636 0.0780276 0.0848978 0.173667 0.0790635 0.0848546 0.172129 0.0785453 0.0851808 0.173434 0.0793074 0.0850686 0.171808 0.0767715 0.0842136 0.172836 0.0778001 0.0841815 0.171757 0.0768312 0.0846001 0.172788 0.0778632 0.0845703 0.171374 0.0772276 0.0851421 0.172404 0.0782676 0.0851126 -0.179039 0.0810719 0.0850416 -0.179039 0.0803187 0.0847763 -0.178568 0.0802926 0.0847782 -0.178591 0.0800584 0.0844455 -0.179039 0.0800831 0.0844435 -0.177045 0.0802099 0.0850176 -0.178531 0.0806393 0.0849894 -0.177281 0.0796836 0.0844742 -0.176873 0.0805714 0.085076 -0.175781 0.0793074 0.0850686 -0.177189 0.0798969 0.0848054 -0.176165 0.0788949 0.084526 -0.177306 0.079605 0.0840781 0.171433 0.0765401 0.084605 0.171605 0.0769915 0.0849266 0.170853 0.0772783 0.0852183 0.171478 0.0764762 0.0842186 0.170208 0.0761075 0.0849392 0.1701 0.0764184 0.085155 0.171298 0.0767154 0.0849314 0.171094 0.0769749 0.085147 0.170303 0.0758254 0.0842273 0.170279 0.0758991 0.0846131 0.168979 0.0756773 0.084615 0.168979 0.0762258 0.0851569 0.169972 0.0767835 0.0852272 -0.174154 0.0767715 0.0842136 -0.175134 0.0778632 0.0845703 -0.174104 0.0768312 0.0846001 -0.173951 0.0769915 0.0849266 -0.174475 0.0785453 0.0851808 -0.175183 0.0778001 0.0841815 -0.174982 0.0780276 0.0848978 -0.176013 0.0790635 0.0848546 -0.175504 0.0795875 0.0851338 -0.174751 0.0782676 0.0851126 -0.0239868 0.0756773 0.084615 -0.0239868 0.0758972 0.0849409 0.168979 0.0758972 0.0849409 -0.171326 0.0756773 0.084615 -0.0239868 0.0756 0.0842295 -0.171326 0.0758972 0.0849409 -0.0239868 0.0762258 0.0851569 -0.17176 0.0757014 0.0846148 -0.171326 0.0762258 0.0851569 -0.172934 0.0762658 0.0849376 -0.171736 0.0759201 0.0849408 -0.172793 0.0765633 0.0851533 -0.1717 0.0762467 0.0851567 -0.173028 0.076066 0.0846114 -0.17372 0.0772276 0.0851421 -0.173447 0.0775028 0.0852133 0.169329 0.0764401 -0.084394 0.169329 0.0760811 -0.0847592 0.170843 0.0767823 -0.0843891 0.169661 0.076951 -0.0842541 0.169716 0.0764614 -0.0843937 0.171002 0.0764609 -0.0847542 0.171062 0.076345 -0.0852486 0.169756 0.0761047 -0.084759 0.1718 0.0774542 -0.0843751 0.172058 0.0772067 -0.0847401 0.173864 0.0788284 -0.0851644 0.17291 0.0780564 -0.0847127 0.172652 0.0782995 -0.0843483 0.173011 0.0779751 -0.0852042 0.171451 0.0777996 -0.0842344 0.172304 0.0786414 -0.084205 -0.0253188 0.07595 -0.0852543 0.169329 0.07595 -0.0852543 -0.0253188 0.0764401 -0.084394 -0.0253188 0.0769328 -0.0842544 0.169329 0.0769329 -0.0842544 -0.0253188 0.0760811 -0.0847592 0.176233 0.0800966 -0.0845959 0.176193 0.0804311 -0.0842339 0.17614 0.0808974 -0.0840777 0.176251 0.0799754 -0.0850751 0.174893 0.079711 -0.0846244 0.173761 0.078906 -0.0846755 0.173504 0.0791445 -0.0843116 0.174736 0.0800147 -0.0842617 0.174526 0.0804406 -0.0841092 -0.173797 0.0777996 -0.0842344 -0.173858 0.0771987 -0.0843811 -0.174086 0.0769231 -0.0847461 -0.172832 0.0766354 -0.0843914 -0.174174 0.0768261 -0.0852401 -0.171676 0.0764401 -0.084394 -0.171676 0.0760811 -0.0847592 -0.171676 0.07595 -0.0852543 -0.172953 0.0762979 -0.0847565 0.20431 0.0809276 -0.0840756 0.20431 0.0804588 -0.0842321 0.217322 0.0809277 -0.0840756 0.231927 0.0804588 -0.0842321 0.231927 0.0809277 -0.0840756 0.176693 0.0801221 -0.0845939 0.20431 0.0801221 -0.084594 0.176693 0.0804587 -0.084232 -0.175256 0.0780564 -0.0847127 -0.174405 0.0772067 -0.0847401 -0.174146 0.0774542 -0.0843751 -0.17465 0.0786414 -0.084205 -0.175358 0.0779751 -0.0852042 -0.174998 0.0782995 -0.0843483 0.238766 0.0801311 -0.0790731 0.237554 0.0804768 -0.081102 0.234074 0.0809313 -0.0837095 0.236074 0.0804669 -0.0827719 0.234125 0.0804608 -0.0838561 0.234245 0.0801227 -0.0841979 0.237863 0.0801273 -0.0812953 0.236301 0.0801245 -0.0830553 0.231927 0.0801221 -0.084594 -0.176544 0.0791265 -0.0851439 -0.176452 0.0792145 -0.0846572 -0.176108 0.078906 -0.0846755 -0.176225 0.0794781 -0.0842938 -0.17585 0.0791445 -0.0843116 -0.177666 0.079888 -0.0846116 -0.177546 0.0802059 -0.0842493 -0.175921 0.0798506 -0.0841455 -0.179039 0.0801221 -0.0845939 0.238389 0.0810217 -0.0782551 0.238273 0.0809829 -0.0789641 0.238409 0.0804902 -0.0789943 0.238686 0.0803249 -0.0782353 0.238564 0.0802869 -0.0790286 0.239006 0.0801104 -0.0782539 0.239383 0.0800331 -0.0782888 0.239249 0.08 -0.07918 0.238503 0.0807443 -0.077484 0.238469 0.0806445 -0.0782357 0.23872 0.0804235 -0.0774357 -0.206656 0.0801221 -0.084594 -0.179039 0.0804587 -0.084232 -0.206656 0.0804588 -0.0842321 0.239044 0.084854 -0.0696346 0.239427 0.0811386 -0.0740778 0.238427 0.0811227 -0.077541 0.239044 0.0802092 -0.0774034 0.239044 0.0817658 -0.0730611 0.23872 0.0819518 -0.0731724 0.238503 0.0822303 -0.0733388 0.238427 0.0825587 -0.0735352 0.23872 0.0849839 -0.0698081 0.238503 0.0851783 -0.0700678 0.238503 0.0891473 -0.0681605 0.238427 0.0854077 -0.0703742 -0.236434 0.0809314 -0.0837046 -0.234273 0.0801221 -0.084594 -0.234273 0.0804588 -0.0842321 -0.236486 0.0804609 -0.0838511 -0.238344 0.0809423 -0.0826385 -0.238439 0.080467 -0.082757 -0.239919 0.080477 -0.0810727 -0.236607 0.0801227 -0.0841926 -0.238667 0.0801245 -0.0830396 -0.240755 0.0804902 -0.0789943 -0.240228 0.0801273 -0.0812644 -0.241595 0.08 -0.07918 0.239427 0.112336 -0.0565294 0.239427 0.120241 -0.049803 0.239427 0.112336 0.0549995 0.238427 0.140464 0.0123322 0.238427 0.1417 -0.000764971 0.238503 0.136443 0.0248261 0.238503 0.140088 0.0122606 0.23872 0.136141 0.0247068 0.23872 0.089066 0.0663165 0.238427 0.130835 0.0366925 0.238503 0.130512 0.0364877 0.23872 0.130238 0.0363141 0.239044 0.139556 0.0121593 0.238503 0.141317 -0.000764971 0.23872 0.140993 -0.000764971 0.23872 0.139769 -0.0137298 0.239044 0.140776 -0.000764971 0.239044 0.0890116 0.0661067 0.238927 0.0890261 0.0661627 0.238503 0.101449 0.062176 0.23872 0.10131 0.0618827 0.239044 0.101218 0.0616867 0.23872 0.112509 0.0552362 0.239044 0.122108 0.0464636 0.23872 0.122266 0.0466118 0.239044 0.112381 0.055061 0.238503 0.1127 0.0554984 0.238427 0.122782 0.0470953 0.238503 0.122503 0.0468336 0.239427 0.122052 0.0464115 0.23872 0.139769 0.0121999 0.239044 0.130054 0.0361981 0.239044 0.13594 0.0246271 0.239044 0.139556 -0.0136893 0.239427 0.139481 -0.013675 0.239427 0.1407 -0.000764971 0.239427 0.139481 0.0121451 0.239427 0.131338 0.0339376 0.238427 0.140464 -0.0138621 0.238427 0.136799 -0.0264967 0.238503 0.140088 -0.0137905 0.23872 0.136141 -0.0262367 0.239044 0.13594 -0.0261571 0.239427 0.138318 -0.0187365 0.239427 0.135869 -0.0261291 0.23872 0.130238 -0.037844 0.238503 0.130512 -0.0380176 0.238503 0.136443 -0.026356 0.238503 0.122503 -0.0483636 0.239044 0.130054 -0.037728 0.239427 0.12999 -0.0376873 0.239044 0.122108 -0.0479935 0.239427 0.122052 -0.0479415 0.23872 0.122266 -0.0481417 0.239044 0.112381 -0.0565909 0.239044 0.101218 -0.0632166 0.239427 0.105794 -0.0607534 0.23872 0.10131 -0.0634126 0.23872 0.112509 -0.0567661 0.238503 0.1127 -0.0570283 0.238503 0.101449 -0.0637059 0.23872 0.089066 -0.0678465 0.239044 0.0890116 -0.0676366 -0.240735 0.0810217 -0.0782551 -0.240907 0.0806283 -0.0774665 -0.240874 0.080529 -0.0782334 -0.241237 0.0801679 -0.0782457 -0.241273 0.0802664 -0.077412 -0.241112 0.0801311 -0.0790731 0.238927 0.0844241 0.0685171 0.238561 0.0891179 0.066517 0.238427 0.0849771 0.0691837 0.238503 0.0891473 0.0666306 0.238561 0.0846578 0.0687988 0.238427 0.0820438 0.0729731 0.239427 0.0801339 0.0758621 0.238927 0.0802664 0.0758821 0.238927 0.0812599 0.0726048 0.238561 0.0815912 0.0727605 0.238427 0.0811227 0.0760111 -0.240907 0.0815912 -0.0742904 -0.241273 0.0812599 -0.0741348 -0.240773 0.0820438 -0.074503 -0.240773 0.0849771 -0.0707136 -0.240907 0.0846578 -0.0703288 -0.241273 0.0890261 -0.0676926 -0.241773 0.0811386 -0.0740778 -0.241273 0.0844241 -0.0700471 -0.241773 0.0843386 -0.069944 -0.241391 0.0890116 -0.0676366 0.238527 0.080529 0.0767035 0.238561 0.0806283 0.0759366 0.23889 0.0801679 0.0767158 0.238766 0.0801311 0.0775431 -0.241066 0.089066 -0.0678465 -0.240907 0.0891179 -0.068047 -0.241066 0.10131 0.0618827 -0.241773 0.120241 0.0482731 -0.241773 0.105794 0.0592235 -0.241391 0.101218 0.0616867 -0.241773 0.112336 0.0549995 -0.241391 0.122108 0.0464636 -0.241391 0.130054 0.0361981 -0.241773 0.131338 0.0339376 -0.241773 0.131338 -0.0354675 -0.241391 0.13594 -0.0261571 -0.241773 0.138318 0.0172066 -0.241773 0.139481 0.0121451 -0.241391 0.140776 -0.000764971 -0.241773 0.105794 -0.0607534 -0.241773 0.12999 -0.0376873 -0.241391 0.130054 -0.037728 -0.241391 0.122108 -0.0479935 -0.241773 0.120241 -0.049803 -0.241391 0.112381 -0.0565909 -0.241391 0.112381 0.055061 -0.241066 0.112509 0.0552362 -0.241391 0.13594 0.0246271 -0.241066 0.139769 0.0121999 -0.241391 0.139556 0.0121593 -0.241066 0.140993 -0.000764971 -0.241391 0.139556 -0.0136893 -0.241066 0.139769 -0.0137298 -0.241391 0.101218 -0.0632166 -0.241066 0.10131 -0.0634126 -0.240849 0.1127 0.0554984 -0.241066 0.122266 0.0466118 -0.241066 0.130238 0.0363141 -0.241066 0.136141 0.0247068 -0.240849 0.140088 0.0122606 -0.240849 0.140088 -0.0137905 -0.241066 0.136141 -0.0262367 -0.241066 0.130238 -0.037844 -0.240849 0.130512 -0.0380176 -0.241066 0.122266 -0.0481417 -0.241066 0.112509 -0.0567661 -0.240849 0.1127 -0.0570283 -0.240849 0.101449 -0.0637059 -0.240773 0.122782 -0.0486252 -0.240849 0.122503 -0.0483636 -0.240773 0.130835 -0.0382224 -0.240773 0.136799 -0.0264967 -0.240849 0.136443 -0.026356 -0.240773 0.140464 -0.0138621 -0.240849 0.141317 -0.000764971 -0.240773 0.1417 -0.000764971 -0.240849 0.136443 0.0248261 -0.240773 0.130835 0.0366925 -0.240849 0.130512 0.0364877 -0.240773 0.122782 0.0470953 -0.240849 0.122503 0.0468336 -0.240773 0.112925 0.0558077 -0.240849 0.101449 0.062176 0.231927 0.0809277 0.0825457 0.231927 0.08 0.0835431 0.23414 0.0804609 0.0823212 0.236093 0.080467 0.081227 0.238273 0.0809829 0.0774342 0.238409 0.0804902 0.0774643 0.237556 0.0809619 0.079284 0.237573 0.080477 0.0795427 0.237448 0.0809599 0.0794654 0.231927 0.0801221 0.0830641 0.23426 0.0801227 0.0826627 0.23442 0.08 0.0831153 0.23632 0.0801245 0.0815097 0.237882 0.0801273 0.0797344 -0.240773 0.0892432 0.0670011 -0.240849 0.0891473 0.0666306 -0.240849 0.0851783 0.0685379 -0.241066 0.089066 0.0663165 -0.241391 0.0890116 0.0661067 -0.241773 0.0889926 0.066033 -0.241391 0.084854 0.0681047 -0.240773 0.0825587 0.0720053 -0.241066 0.0849839 0.0682782 -0.241066 0.0819518 0.0716424 -0.241391 0.0817658 0.0715312 -0.240849 0.0822303 0.0718089 -0.240849 0.0807443 0.0759541 -0.241066 0.0804235 0.0759057 -0.241391 0.0802092 0.0758734 0.217322 0.0809277 0.0825457 0.231927 0.0804588 0.0827022 0.20431 0.0801221 0.0830641 0.176693 0.08 0.0835429 0.176693 0.0801221 0.083064 0.20431 0.0804588 0.0827021 0.176693 0.0804587 0.082702 0.176693 0.0809276 0.0825455 0.20431 0.08 0.083543 0.20431 0.0809276 0.0825457 -0.241595 0.08 0.07765 -0.241352 0.0801104 0.076724 -0.240619 0.0809829 0.0774342 -0.241032 0.0803249 0.0767054 -0.240698 0.0806055 0.0774517 -0.240755 0.0804902 0.0774643 -0.240911 0.0802869 0.0774987 -0.240773 0.0811227 0.0760111 -0.240815 0.0806445 0.0767058 -0.241773 0.0801339 0.0758621 0.173864 0.0788284 0.0836345 0.173157 0.0794831 0.0826358 0.17532 0.079888 0.0830817 0.174105 0.0792145 0.0831273 0.173878 0.0794781 0.0827638 0.175371 0.0797752 0.0835628 0.1752 0.0802059 0.0827193 -0.241112 0.0801311 0.0775431 -0.239776 0.0809595 0.079494 -0.238325 0.0809421 0.081123 -0.239901 0.0804768 0.0795721 -0.238421 0.0804669 0.0812419 -0.23642 0.0809313 0.0821796 -0.238647 0.0801245 0.0815254 -0.236472 0.0804608 0.0823262 -0.234273 0.0804588 0.0827022 -0.241226 0.0800745 0.0775683 -0.240623 0.08 0.0800246 -0.240209 0.0801273 0.0797653 -0.238949 0.08 0.0819028 -0.236592 0.0801227 0.082668 -0.236751 0.08 0.0831209 -0.234273 0.0801221 0.0830641 0.172836 0.0778001 0.0836812 0.173761 0.078906 0.0831455 0.172735 0.0778822 0.0831892 0.173504 0.0791445 0.0827816 0.172477 0.0781262 0.0828246 0.172129 0.0784688 0.0826819 -0.206656 0.0801221 0.0830641 -0.206656 0.0804588 0.0827021 -0.179039 0.0809276 0.0825455 0.171451 0.0771076 0.0828533 0.171391 0.0765746 0.0832233 0.171709 0.0768582 0.0832184 0.171478 0.0764762 0.0837185 0.171162 0.0768521 0.0828581 0.170257 0.0759489 0.0832312 0.170303 0.0758254 0.0837272 0.169972 0.0767544 0.0827273 0.170136 0.0762883 0.0828658 -0.17854 0.0804311 0.082704 -0.179039 0.0801221 0.083064 -0.179039 0.0804587 0.082702 -0.178597 0.0799754 0.0835451 -0.17724 0.079711 0.0830944 -0.17858 0.0800966 0.0830659 -0.176873 0.0804406 0.0825792 -0.176211 0.0788284 0.0836345 -0.176108 0.078906 0.0831455 -0.177082 0.0800147 0.0827318 0.0226401 0.0757319 0.0832331 0.0226401 0.0760929 0.0828676 -0.171326 0.0760929 0.0828676 0.168979 0.0757319 0.0832331 0.168979 0.0760929 0.0828676 0.0226401 0.0765876 0.0827296 -0.17585 0.0791445 0.0827816 -0.174475 0.0784688 0.0826819 -0.175082 0.0778822 0.0831892 -0.174055 0.0768582 0.0832184 -0.173797 0.0771076 0.0828533 -0.174824 0.0781262 0.0828246 -0.171326 0.0765877 0.0827296 -0.171712 0.0761142 0.0828674 -0.171753 0.0757555 0.0832329 -0.171326 0.0757319 0.0832331 -0.171326 0.0756 0.0837295 -0.172625 0.0768798 0.0827254 -0.171657 0.0766058 0.0827293 -0.172999 0.0761119 0.0832295 -0.17284 0.0764353 0.0828642 0.212827 0.108366 0.074935 0.200735 0.109692 0.074935 0.188643 0.109669 0.074935 0.222656 0.121018 0.0667728 0.221488 0.116779 0.0699336 0.220075 0.115612 0.0718239 0.217962 0.112557 0.0735156 0.218732 0.111928 0.0730051 0.216235 0.110944 0.0743364 0.216319 0.109581 0.0743055 0.214067 0.109867 0.0748578 0.188643 0.108333 0.074935 0.188321 0.108342 0.0749298 0.185085 0.111007 0.0742806 0.183609 0.112383 0.0735757 0.179917 0.116851 0.0698198 0.179138 0.119284 0.0680428 0.178643 0.123083 0.064935 0.214736 0.108727 -0.076281 0.214502 0.110001 -0.0763237 0.218672 0.111852 -0.0745789 0.221706 0.11928 -0.0710658 0.179075 0.121599 -0.0693724 0.178816 0.120887 -0.068314 0.179844 0.11704 -0.0712171 0.180602 0.115291 -0.0724097 0.186997 0.108596 -0.0763285 0.18515 0.109536 -0.075835 0.182739 0.111866 -0.0745356 0.185207 0.110916 -0.0758559 0.183477 0.112533 -0.0750271 -0.186856 0.110027 -0.0755706 -0.187141 0.111238 -0.0756948 -0.189314 0.109961 -0.0763235 -0.190668 0.108342 -0.0764598 -0.185138 0.1118 -0.074574 -0.182264 0.116851 -0.0713497 -0.182117 0.119158 -0.071078 -0.181171 0.12295 -0.0683619 -0.203081 0.109692 -0.076465 -0.225173 0.123212 -0.066465 -0.225003 0.121018 -0.0683027 -0.224741 0.121719 -0.069372 -0.223978 0.11715 -0.0712053 -0.222422 0.115612 -0.0733539 -0.218581 0.110944 -0.0758664 -0.218665 0.109581 -0.0758355 -0.181162 0.120887 0.066784 -0.182191 0.11704 0.0696871 -0.182328 0.116688 0.0699336 -0.183737 0.11554 0.07182 -0.182948 0.115291 0.0708797 -0.185941 0.110884 0.0735671 -0.185823 0.112533 0.0734971 -0.187496 0.109536 0.0743051 -0.189723 0.109835 0.0748545 -0.215491 0.108376 0.07493 -0.216848 0.110001 0.0747937 -0.215173 0.109703 0.074935 -0.215173 0.108366 0.074935 -0.219022 0.111289 0.0741648 -0.22079 0.113137 0.0732085 -0.222128 0.113415 0.0721201 -0.22118 0.113653 0.0729301 -0.224052 0.11928 0.0695359 -0.224678 0.119392 0.0680422 0.178643 0.142542 0.0373593 0.178643 0.1441 0.0374616 0.178643 0.139097 0.0447741 0.178643 0.140452 0.0453977 0.178643 0.129296 0.0587835 0.178643 0.131321 0.0587394 0.215698 0.150227 0.0111561 0.216125 0.150215 0.0112945 0.217827 0.148545 0.0120749 0.221488 0.148115 0.0157369 0.222455 0.149345 0.0180348 0.22226 0.147881 0.0174151 0.222565 0.149275 0.0184598 0.222827 0.14887 0.020735 0.222827 0.123212 0.064935 0.222827 0.125466 0.064935 0.222827 0.130873 0.0594545 0.222827 0.134703 0.0522273 0.222827 0.147058 0.029297 0.222827 0.14241 0.0383299 0.222827 0.140723 0.0453552 0.222827 0.145276 0.0301255 0.222827 0.144187 0.0336293 0.188643 0.148491 0.010735 0.200735 0.150204 0.010735 0.212827 0.150261 0.010735 0.182993 0.149823 0.0124839 0.181571 0.149666 0.0136647 0.178643 0.147031 0.020735 0.179064 0.14904 0.017865 0.178903 0.147403 0.0184711 0.180191 0.147858 0.0153915 0.180864 0.149558 0.0144512 0.179404 0.147641 0.0169101 0.188643 0.150083 0.010735 0.185344 0.148394 0.0112948 0.186061 0.150014 0.0110741 0.222827 0.123212 -0.066465 0.222827 0.126239 -0.0636713 0.222827 0.131499 -0.0602714 0.222827 0.129454 -0.0603213 0.222827 0.142815 -0.0388727 0.222827 0.144297 -0.0348319 0.222827 0.146528 -0.0265343 0.222827 0.145523 -0.0307619 0.222407 0.149372 -0.0193982 0.222563 0.147724 -0.0199835 0.219047 0.148457 -0.0144353 0.220614 0.149863 -0.0159916 0.212827 0.148667 -0.012265 0.216123 0.148621 -0.0128237 0.217827 0.150138 -0.0136048 0.200735 0.150204 -0.012265 0.185772 0.150002 -0.0126861 0.188643 0.148491 -0.012265 0.186521 0.148442 -0.0124928 0.182772 0.149803 -0.0141699 0.184816 0.149954 -0.0130263 0.180433 0.149476 -0.0165556 0.183405 0.148275 -0.0137468 0.181571 0.149666 -0.0151948 0.179011 0.14901 -0.019576 0.180868 0.147986 -0.015976 0.179213 0.147567 -0.0189379 0.178643 0.146746 -0.030836 0.178643 0.144092 -0.0390135 0.178643 0.144991 -0.0316345 0.178643 0.138341 -0.0476801 0.178643 0.13598 -0.0542484 -0.19099 0.150083 -0.012265 -0.203081 0.150204 -0.012265 -0.215173 0.148667 -0.012265 -0.18534 0.149823 -0.0140138 -0.18141 0.14904 -0.0193949 -0.181558 0.149113 -0.0189411 -0.183918 0.149666 -0.0151947 -0.183211 0.149558 -0.0159811 -0.182907 0.149502 -0.0163765 -0.19099 0.148491 -0.012265 -0.188856 0.150031 -0.0124952 -0.184765 0.148187 -0.0144381 -0.188407 0.150014 -0.0126041 -0.218045 0.150227 -0.0126861 -0.217324 0.14865 -0.0124991 -0.219001 0.148602 -0.0130264 -0.221041 0.150079 -0.0141677 -0.222956 0.148278 -0.0159859 -0.220429 0.148529 -0.0137577 -0.221398 0.150049 -0.0144383 -0.223625 0.149741 -0.0169198 -0.224911 0.149275 -0.0199898 -0.225173 0.14887 -0.022265 -0.18099 0.145227 -0.0307702 -0.18099 0.146796 -0.0306436 -0.18099 0.1441 -0.0389916 -0.18099 0.140452 -0.0469276 -0.18099 0.134591 -0.053633 -0.18099 0.136517 -0.0534644 -0.18099 0.131321 -0.0602693 -0.225173 0.14438 -0.0389956 -0.225173 0.129358 -0.060428 -0.225173 0.125466 -0.066465 -0.225173 0.126239 -0.0636713 -0.225173 0.144297 -0.0348319 -0.225173 0.145276 -0.0316554 -0.225173 0.147058 -0.0308269 -0.225173 0.141104 -0.0427974 -0.225173 0.140723 -0.0468851 -0.225173 0.138577 -0.0476664 -0.225173 0.136191 -0.0542494 -0.18099 0.147031 0.020735 -0.18099 0.146746 0.029306 -0.18099 0.129195 0.0588959 -0.18099 0.13598 0.0527184 -0.18099 0.134507 0.0522228 -0.18099 0.138341 0.0461501 -0.18099 0.140474 0.0453574 -0.18099 0.140703 0.0415869 -0.18099 0.142149 0.0383287 -0.225173 0.140704 0.0453906 -0.225173 0.129454 0.0587913 -0.225173 0.144187 0.0336293 -0.225173 0.144378 0.0374708 -0.225173 0.147348 0.020735 -0.225173 0.14887 0.020735 -0.225173 0.146455 0.0253471 -0.225173 0.145523 0.0292319 -0.225173 0.147098 0.0291445 -0.224753 0.149372 0.0178683 -0.224607 0.149444 0.0174186 -0.224909 0.147724 0.0184535 -0.221394 0.148457 0.0129053 -0.222245 0.149962 0.0136647 -0.223262 0.149812 0.0148557 -0.220439 0.150122 0.0122336 -0.19099 0.148491 0.010735 -0.188118 0.150002 0.0111561 -0.185751 0.148275 0.0122168 -0.187162 0.149954 0.0114964 -0.187689 0.149982 0.0112954 -0.18278 0.149476 0.0150257 -0.183918 0.149666 0.0136648 -0.184762 0.149767 0.0129109 -0.185118 0.149803 0.0126399 -0.181248 0.148938 0.0184765 -0.236773 0.111103 0.0717502 -0.235618 0.11265 0.0724173 -0.236123 0.132447 0.054805 -0.234274 0.13 0.0558725 -0.236773 0.141288 0.0371092 -0.234274 0.140683 0.0385518 -0.234277 0.147258 0.02123 -0.236773 0.146895 -0.0148523 -0.234277 0.148564 -0.0134112 -0.23427 0.147055 -0.0134061 -0.236773 0.144603 -0.0321728 -0.236773 0.14356 -0.0321728 -0.234276 0.145528 -0.0307314 -0.23427 0.143975 -0.0307263 -0.236773 0.135739 -0.0494933 -0.234275 0.138355 -0.0480513 -0.236773 0.120471 -0.0668138 -0.234272 0.122184 -0.0653695 -0.236507 0.122379 -0.06666 -0.235491 0.112577 -0.0740203 -0.236773 0.113061 -0.0732802 -0.234272 0.120543 -0.0667554 -0.235573 0.121784 -0.0675067 -0.235573 0.112275 -0.0725873 -0.235573 0.114859 -0.0725873 -0.234271 0.135778 -0.0494333 -0.235573 0.135301 -0.0501862 -0.234273 0.142314 -0.0400825 -0.236773 0.141287 -0.0386391 -0.234273 0.145141 -0.0321151 -0.235573 0.143035 -0.0379463 -0.234276 0.142883 -0.0386952 -0.234273 0.142882 -0.0386969 -0.23427 0.145732 -0.0227651 -0.234277 0.147258 -0.0227599 -0.236773 0.145983 -0.0213186 -0.234277 0.148415 -0.0147968 -0.23427 0.145974 -0.0213794 -0.234271 0.147615 -0.00544358 -0.235573 0.147677 -0.00330531 -0.234277 0.149161 -0.00405357 -0.235573 0.147486 0.0190959 -0.234277 0.148415 0.0132668 -0.234276 0.145528 0.0292014 -0.234276 0.142883 0.0371653 -0.235573 0.141566 0.0364164 -0.234276 0.145141 0.030587 -0.234274 0.143576 0.0305861 -0.234273 0.145141 0.0305851 -0.236773 0.135738 0.0479634 -0.235573 0.131718 0.0537369 -0.234274 0.122183 0.0638411 -0.236773 0.122037 0.0652839 -0.234633 0.124195 0.0640482 -0.235573 0.112276 0.0710574 -0.235573 0.119607 0.0659767 -0.236773 0.122037 -0.0668138 -0.236773 0.115202 -0.0719235 -0.236773 0.1111 -0.0732802 -0.235573 0.131718 -0.0552668 -0.235573 0.133438 -0.0552668 -0.235573 0.144782 -0.0328656 -0.235573 0.146815 -0.0155451 -0.235573 0.146097 -0.0206258 -0.235573 0.147486 -0.0206258 -0.236773 0.14766 -0.00399813 -0.235573 0.149047 -0.00330531 -0.236773 0.146999 0.0197887 -0.236773 0.145984 0.0197887 -0.235573 0.146099 0.0190959 -0.235573 0.146818 0.0140152 -0.235573 0.143035 0.0364164 -0.235573 0.135299 0.0486562 -0.236773 0.113604 0.0702355 -0.236773 0.113061 0.0717502 -0.236773 0.120469 0.0652839 -0.236773 0.120072 0.0668849 0.231927 0.108474 0.0731936 0.231927 0.124438 0.0638405 0.231927 0.122875 0.0652262 0.231925 0.129998 0.0558751 0.232543 0.132189 0.0555174 0.234427 0.135738 0.0479634 0.231929 0.138355 0.0465213 0.231927 0.133033 0.0544874 0.231927 0.137537 0.0479057 0.231929 0.137536 0.0479069 0.233227 0.136921 0.0486562 0.231922 0.140681 0.0385572 0.234427 0.141288 0.0371092 0.23193 0.145528 0.0292014 0.233227 0.141566 0.0364164 0.231922 0.141263 0.0371717 0.231927 0.142882 0.0371669 0.231921 0.143578 0.0305794 0.23193 0.145141 0.030587 0.23192 0.145732 0.0212387 0.23193 0.147258 0.02123 0.234427 0.147906 0.0133224 0.23193 0.147497 0.0198443 0.231919 0.146907 0.0132574 0.233227 0.146818 0.0140152 0.231931 0.149116 0.00390928 0.234427 0.147661 0.00246819 0.231931 0.149116 -0.00543922 0.233227 0.149047 -0.00330531 0.231927 0.148416 -0.0147946 0.23193 0.147497 -0.0213743 0.231919 0.145973 -0.0213834 0.233227 0.146097 -0.0206258 0.233227 0.147486 -0.0206258 0.234427 0.141287 -0.0386391 0.231921 0.14068 -0.0400876 0.23193 0.145141 -0.032117 0.231927 0.142882 -0.0386969 0.231921 0.141263 -0.0387021 0.233227 0.141565 -0.0379463 0.234427 0.131175 -0.0559597 0.233777 0.132447 -0.0563349 0.231928 0.131942 -0.0574021 0.232792 0.130414 -0.0569035 0.231924 0.131128 -0.0560202 0.233227 0.131718 -0.0552668 0.231925 0.122185 -0.065369 0.232286 0.124195 -0.0655781 0.231927 0.1116 -0.0747235 0.234427 0.1111 -0.0732802 0.233227 0.114859 -0.0725873 0.234427 0.115202 0.0703935 0.234427 0.111103 0.0717502 0.234427 0.131175 0.0544297 0.233227 0.133438 0.0537369 0.234427 0.144603 0.0306429 0.234427 0.146999 0.0197887 0.233227 0.146099 0.0190959 0.233227 0.147486 0.0190959 0.234427 0.147906 -0.0148523 0.234427 0.146895 -0.0148523 0.234427 0.14356 -0.0321728 0.234427 0.136916 -0.0494933 0.234427 0.132446 -0.0559597 0.233227 0.133438 -0.0552668 0.233227 0.136921 -0.0501862 0.234427 0.113599 -0.0717682 0.234427 0.122037 -0.0668138 0.233227 0.112275 -0.0725873 0.233227 0.119609 -0.0675067 -0.234273 0.108473 -0.0747235 -0.234273 0.111001 -0.073338 -0.236773 0.118171 -0.0686138 -0.235573 0.119609 -0.0675067 -0.236773 0.131175 -0.0559597 -0.235573 0.14335 -0.0328656 -0.235573 0.141565 -0.0379463 -0.234272 0.14766 0.00252693 -0.234272 0.147616 0.00391234 -0.236773 0.147661 0.00246819 -0.235573 0.147677 0.00177537 -0.236773 0.146899 0.0133224 -0.234274 0.146907 0.0132658 -0.235573 0.143349 0.0313357 -0.236773 0.143557 0.0306429 -0.236773 0.131175 0.0544297 -0.234274 0.108475 0.0731933 -0.234274 0.12054 0.0652266 0.233227 0.119607 0.0659767 0.231926 0.122184 0.0638396 0.233227 0.112276 0.0710574 0.234427 0.118166 0.0670856 0.234427 0.120469 0.0652839 0.231923 0.13662 0.0465165 0.233227 0.135299 0.0486562 0.233227 0.131718 0.0537369 0.231924 0.131128 0.0544896 0.233227 0.143349 0.0313357 0.234427 0.143557 0.0306429 0.231919 0.147058 0.0118717 0.234427 0.146899 0.0133224 0.234427 0.145984 0.0197887 0.233227 0.147677 -0.00330531 0.234427 0.14766 -0.00399813 0.233227 0.147677 0.00177537 0.231918 0.14766 0.00253373 0.231918 0.147616 0.00391934 0.234427 0.145983 -0.0213186 0.233227 0.146815 -0.0155451 0.231919 0.146905 -0.014787 0.231919 0.147055 -0.0134013 0.233227 0.14335 -0.0328656 0.23192 0.14358 -0.0321091 0.233227 0.135301 -0.0501862 0.231923 0.136621 -0.048046 0.234427 0.135739 -0.0494933 0.231928 0.130416 -0.0569013 0.231927 0.108473 -0.0747236 0.231926 0.120543 -0.066755 0.234427 0.120471 -0.0668138 0.231929 0.133034 -0.0560164 0.231929 0.135374 -0.0527908 0.233227 0.143035 -0.0379463 0.23193 0.144093 -0.0354265 0.233227 0.144782 -0.0328656 0.231931 0.148362 -0.0152598 0.233227 0.148197 -0.0155451 0.231931 0.149161 -0.00405357 0.231931 0.149204 -0.000762801 0.233227 0.149047 0.00177537 0.233227 0.148197 0.0140152 0.233227 0.143035 0.0364164 0.233227 0.144782 0.0313357 0.23193 0.144089 0.0339075 0.233227 0.114859 0.0710574 0.233227 0.121784 0.0659767 -0.234274 0.122874 0.0652267 -0.235573 0.121784 0.0659767 -0.235573 0.114859 0.0710574 -0.234275 0.137536 0.0479069 -0.235573 0.136921 0.0486562 -0.234275 0.137097 0.0486217 -0.234275 0.133034 0.0544864 -0.235573 0.133438 0.0537369 -0.234276 0.144089 0.0339075 -0.235573 0.144782 0.0313357 -0.235573 0.148197 0.0140152 -0.234277 0.147497 0.0198443 -0.235573 0.149047 0.00177537 -0.235573 0.148197 -0.0155451 -0.234277 0.147497 -0.0213743 -0.234277 0.148362 -0.0152598 -0.234275 0.133034 -0.0560164 -0.235573 0.136921 -0.0501862 -0.234275 0.135374 -0.0527908 0.233227 0.121784 -0.0675067 0.231927 0.11392 -0.0733379 0.137304 0.147475 -0.0185944 0.137372 0.146571 -0.0184995 0.136857 0.146498 -0.0189091 0.136734 0.147301 -0.0189433 0.137527 0.146648 -0.017965 0.137469 0.14652 0.017369 0.137234 0.147354 0.0177417 0.137371 0.147428 0.0175708 0.136734 0.146405 0.0180134 0.136856 0.147233 0.0179793 0.137048 0.146434 0.0178884 0.137304 0.146474 0.0176648 -0.0558162 0.145127 -0.018298 -0.0557973 0.146058 -0.0183474 -0.0558471 0.146107 -0.0181925 -0.0550852 0.145044 -0.0189423 -0.0552563 0.145876 -0.0188887 -0.0553973 0.145061 -0.0188167 -0.055084 0.145773 0.0180126 -0.0552021 0.14497 0.0179794 -0.0554939 0.144992 0.0178191 -0.0556509 0.145896 0.0176638 -0.0557972 0.145044 0.0174176 -0.0557973 0.14598 0.0174175 -0.0558161 0.145996 0.0173683 -0.0558471 0.145064 0.0172624 -0.0558733 0.145093 0.017035 -0.0558733 0.146103 0.017035 -0.0505452 0.145617 0.0200339 -0.0533732 0.144962 0.018035 -0.0527454 0.145759 0.0181015 -0.052387 0.14494 0.0182018 -0.0518729 0.144908 0.0184371 -0.051512 0.144874 0.0186821 -0.050843 0.14477 0.0194232 -0.0510434 0.145683 0.0191451 -0.050775 0.144754 0.0195352 -0.0523874 0.145837 -0.0191316 -0.0515128 0.145803 -0.0196115 -0.0512518 0.145787 -0.0198437 -0.0508436 0.14575 -0.0203522 -0.0510419 0.144893 -0.0200769 -0.0505447 0.144768 -0.0209651 -0.0506015 0.145717 -0.020817 -0.0503732 0.14462 -0.021965 -0.0503732 0.145632 -0.021965 0.132027 0.146946 -0.021965 0.132104 0.145994 -0.0212901 0.1322 0.147028 -0.0209608 0.132493 0.146148 -0.0203595 0.13347 0.147168 -0.0194006 0.134414 0.147211 -0.0190283 0.135027 0.146429 -0.018965 0.135027 0.147226 -0.018965 0.135027 0.146345 0.018035 0.133527 0.14708 0.018437 0.13347 0.146232 0.0184705 0.1322 0.145955 0.0200309 0.132027 0.146849 0.021035 0.132429 0.146039 0.0195354 0.132429 0.146976 0.0195351 0.132701 0.146108 0.0191407 -0.0504466 0.143018 -0.0359929 -0.0505742 0.143291 -0.0360788 -0.0506099 0.143061 -0.0371687 -0.0506597 0.143417 -0.0361183 -0.0509915 0.143733 -0.0362178 -0.0518732 0.144006 -0.0363037 -0.0514097 0.143936 -0.0362817 -0.0513636 0.143575 -0.0373941 -0.0509419 0.143376 -0.0372976 -0.0518325 0.143637 -0.0374486 -0.0502142 0.142073 -0.0408334 -0.0504011 0.142659 -0.0370204 -0.0503365 0.142213 -0.0368676 -0.0511096 0.142279 -0.041206 -0.0500976 0.141685 -0.0424457 -0.0506353 0.142253 -0.0410412 -0.0496827 0.141514 -0.0421927 -0.0498938 0.141759 -0.040606 -0.0492028 0.140783 -0.041678 -0.0491943 0.140309 -0.041477 -0.04971 0.141347 -0.0403845 -0.0496835 0.140882 -0.0401939 -0.0481839 0.140251 -0.0456692 -0.0474027 0.139359 -0.0446401 -0.0493722 0.141201 -0.0419263 -0.0474395 0.138854 -0.0444293 -0.0468282 0.138462 -0.0451649 -0.0467803 0.138976 -0.0453742 -0.047529 0.139796 -0.0449454 -0.0471523 0.13973 -0.046075 -0.0478015 0.140107 -0.0453044 -0.047295 0.139459 -0.0475265 -0.0434649 0.137462 -0.0480627 -0.0435224 0.137935 -0.0484192 -0.0447983 0.13863 -0.0488839 -0.0405209 0.136666 -0.0493585 -0.0405466 0.13716 -0.0497266 -0.0437036 0.138245 -0.0488938 -0.04398 0.138344 -0.0494116 -0.039514 0.135883 -0.0494971 -0.0406544 0.13747 -0.0502485 -0.0408261 0.137543 -0.0508361 -0.0396936 0.137363 -0.0511469 -0.0363732 0.13708 -0.0509024 -0.0395637 0.137295 -0.0505428 -0.0363732 0.136263 -0.0499854 -0.039483 0.136985 -0.0500102 -0.0394655 0.136486 -0.0496404 -0.04423 0.137746 -0.0475816 -0.0468936 0.139419 -0.0456921 -0.0442984 0.138213 -0.0479323 -0.0444981 0.138523 -0.0483899 -0.0475208 0.139866 -0.0464699 -0.044308 0.138215 -0.0498913 -0.0410327 0.137368 -0.0513901 -0.0398505 0.137176 -0.0517187 -0.0363732 0.136938 -0.052122 0.0552976 0.137142 -0.0515275 -0.0363732 0.137139 -0.0515274 0.055298 0.136772 -0.0503565 -0.0363732 0.13677 -0.0503565 0.0552986 0.136266 -0.0499854 0.0552979 0.13694 -0.0521221 0.118001 0.137722 -0.0515385 0.0552977 0.137082 -0.0509024 0.118007 0.137357 -0.0503607 0.118016 0.13685 -0.0499865 0.118027 0.136233 -0.049854 0.0552993 0.135652 -0.049854 -0.0504874 0.146199 -0.0220503 -0.0503732 0.144752 -0.0271448 -0.0508125 0.146681 -0.0221226 -0.0505742 0.145489 -0.0272846 -0.0503732 0.142575 -0.035854 -0.0511232 0.146028 -0.0273869 -0.0511232 0.143815 -0.0362435 -0.0518732 0.146225 -0.0274244 0.132754 0.144945 -0.0362554 0.118002 0.137666 -0.0509104 0.119864 0.137775 -0.0507906 0.119864 0.136351 -0.0497329 0.121679 0.136631 -0.0493691 0.121612 0.137229 -0.0495204 0.124545 0.138018 -0.0483808 0.120038 0.137633 -0.0519979 0.11994 0.137834 -0.051411 0.121861 0.138101 -0.0510243 0.122047 0.137918 -0.0515875 0.126209 0.1381 -0.0472139 0.129525 0.140617 -0.0440104 0.131615 0.142374 -0.0392231 0.119822 0.136962 -0.049871 0.119822 0.137466 -0.0502454 0.121624 0.137725 -0.0498938 0.126127 0.138643 -0.0474138 0.128602 0.139972 -0.0451846 0.129654 0.141044 -0.0443099 0.13133 0.142549 -0.0411853 0.131159 0.142141 -0.0409471 0.131651 0.142823 -0.0394098 0.131837 0.143225 -0.039615 0.132098 0.144157 -0.0359963 0.132221 0.144425 -0.0360846 0.124585 0.138493 -0.048746 0.126389 0.139412 -0.0482231 0.12619 0.139104 -0.0477681 0.12871 0.140408 -0.0455052 0.121712 0.138033 -0.0504255 0.124747 0.138801 -0.0492353 0.125003 0.138893 -0.0497704 0.128966 0.140717 -0.0458851 0.126694 0.139521 -0.0487096 0.129333 0.140857 -0.0462728 0.129929 0.141353 -0.044652 0.132048 0.143038 -0.0416621 0.131638 0.14286 -0.0414329 0.132153 0.143537 -0.0398169 0.132626 0.144863 -0.0362285 0.12893 0.140321 -0.0475324 0.129763 0.140808 -0.046616 0.130315 0.141506 -0.0449928 0.130762 0.141481 -0.0452888 0.132567 0.143726 -0.0399942 0.133034 0.143771 -0.040128 0.133487 0.145148 -0.0363222 -0.0504531 0.145683 -0.0212773 -0.0511232 0.146916 -0.0221581 -0.0513428 0.147068 -0.0216915 -0.050863 0.14675 -0.0215315 -0.0505742 0.146373 -0.0220764 -0.0509104 0.146347 -0.0204808 -0.0511776 0.146843 -0.0207228 -0.0505498 0.146263 -0.0213857 -0.0516005 0.147157 -0.0210377 -0.0519131 0.147167 -0.0218404 -0.0517458 0.146917 -0.0200638 -0.0520612 0.147226 -0.0205066 -0.052443 0.147289 -0.0209984 -0.0521084 0.147235 -0.0213728 -0.0522251 0.145833 -0.0191934 -0.0524045 0.146456 -0.0192672 -0.0515518 0.146413 -0.019747 -0.0525065 0.146964 -0.0196313 -0.0533731 0.147334 -0.0206717 -0.0526751 0.147271 -0.0201589 0.132304 0.144549 -0.0361252 0.132752 0.14645 -0.0310506 0.133033 0.14507 -0.0362962 0.133485 0.146283 -0.03254 0.132137 0.147502 -0.0220538 0.132221 0.14592 -0.0309175 0.13275 0.148213 -0.0221673 0.13245 0.147977 -0.0221296 0.13222 0.147673 -0.0220811 -0.0548724 0.147287 -0.0200375 -0.0541229 0.14698 -0.0194801 -0.0548726 0.146981 -0.0194801 -0.054123 0.14647 -0.0190998 -0.0548729 0.146471 -0.0190998 -0.0533731 0.147287 -0.0200375 -0.0541228 0.147287 -0.0200375 -0.0533732 0.14698 -0.0194801 -0.0533732 0.14647 -0.0190998 0.134403 0.147831 -0.0191681 0.132905 0.147125 -0.0198437 0.135006 0.14785 -0.0191012 0.133629 0.148279 -0.0198883 0.133483 0.147776 -0.0195455 0.132975 0.148192 -0.0204892 0.132745 0.147697 -0.0202133 0.132569 0.148087 -0.021269 0.1327 0.147105 -0.0200711 0.13228 0.147602 -0.0210853 0.132255 0.14704 -0.020817 0.13498 0.148665 -0.0200471 0.134545 0.148646 -0.0200957 0.1342 0.14865 -0.020905 0.133816 0.148587 -0.0212439 0.133566 0.148509 -0.0216937 0.133021 0.148406 -0.0214829 0.133353 0.148505 -0.0208528 0.133883 0.148588 -0.0203694 0.13445 0.14834 -0.0195466 -0.0566219 0.147466 -0.0181206 -0.0563118 0.147229 -0.018092 -0.0562591 0.147174 -0.0184224 -0.0559872 0.146746 -0.0180337 -0.0567976 0.147552 -0.018131 -0.0560739 0.146921 -0.0180548 -0.0557863 0.146602 -0.0186241 -0.0557169 0.146008 -0.0185018 -0.0555808 0.145951 -0.0186717 -0.0555336 0.146532 -0.018883 -0.0554936 0.145925 -0.0187493 -0.0552189 0.146487 -0.0190448 -0.055202 0.145869 -0.0189094 -0.0559459 0.146686 -0.0182881 -0.0560538 0.147097 -0.0188595 -0.0557275 0.147035 -0.0191969 -0.0553205 0.146995 -0.0194082 -0.0567374 0.147494 -0.0185742 -0.0560419 0.147346 -0.0196368 -0.056475 0.147412 -0.019169 -0.0556937 0.147355 -0.0205313 -0.0554887 0.147302 -0.019935 0.135739 0.148385 -0.0194853 0.13499 0.148361 -0.0194852 0.135756 0.147875 -0.0191012 0.136477 0.148758 -0.0206854 0.135728 0.148733 -0.0206852 0.135729 0.14869 -0.0200473 0.136506 0.1479 -0.0191013 -0.0558733 0.147111 -0.00596934 -0.0560738 0.147795 0.00602585 -0.0560738 0.14786 -0.00599607 -0.0566219 0.148344 0.00605133 -0.0566218 0.148408 -0.00601566 -0.0573709 0.147591 0.0172213 -0.0573708 0.148545 0.00606069 0.138292 0.14897 -0.0187942 0.136489 0.14841 -0.0194853 0.136723 0.14792 -0.0190832 0.136479 0.148715 -0.0200474 0.13677 0.148429 -0.0194614 0.137451 0.147573 -0.0183476 0.137552 0.148165 -0.0184131 0.137351 0.148066 -0.0187323 0.137234 0.147442 -0.0186716 0.137049 0.147373 -0.0188181 0.137469 0.147592 -0.0182989 0.137527 0.147707 -0.017965 0.137209 0.148482 -0.0193029 0.137062 0.14798 -0.0189622 0.137582 0.148559 -0.0190028 0.137841 0.148649 -0.0185871 0.13772 0.148437 -0.0180596 0.136867 0.148735 -0.0200101 0.137463 0.148792 -0.0197814 0.137959 0.148874 -0.0193614 0.138248 0.148979 -0.0181299 0.137781 0.148856 -0.0203146 0.13842 0.148959 -0.0197491 -0.0560739 0.146847 0.0171281 -0.0548724 0.147204 0.0191122 -0.0555808 0.145869 0.0177417 -0.0553965 0.145818 0.0178872 -0.0550936 0.146394 0.0181485 -0.0548729 0.146387 0.0181706 -0.0548726 0.146898 0.0185526 -0.0551584 0.146904 0.0185238 -0.0554265 0.146431 0.0180235 -0.0555891 0.146937 0.0183605 -0.0557089 0.146496 0.0177934 -0.055954 0.146994 0.0180602 -0.0559053 0.14658 0.0174768 -0.056207 0.14707 0.0176481 -0.0559872 0.146672 0.0171062 -0.0552666 0.14721 0.019071 -0.0563447 0.147308 0.0184194 -0.0566729 0.147388 0.0178547 -0.0563118 0.147155 0.0171666 -0.0553988 0.147258 0.0196915 -0.0558558 0.147245 0.0188389 -0.0566219 0.147391 0.0171963 0.137636 0.148265 -0.0180373 0.138977 0.149194 -0.0181578 0.138247 0.149989 -0.0061532 0.138247 0.14995 0.00551869 0.138974 0.150207 -0.00616184 0.138418 0.149067 -0.0181414 0.137719 0.149443 -0.00613155 0.137949 0.148742 -0.0180991 0.138977 0.149114 0.0172347 0.138248 0.148899 0.0172058 0.137949 0.148662 0.0171739 0.137719 0.149405 0.00549342 -0.0533731 0.147203 0.0191122 -0.0541229 0.146898 0.0185526 -0.054123 0.146387 0.0181706 -0.0533732 0.146387 0.0181706 -0.0541232 0.145764 0.018035 -0.0541228 0.147203 0.0191122 -0.0548733 0.145764 0.018035 0.137527 0.147628 0.017035 0.13772 0.148357 0.017133 0.137636 0.148186 0.0171099 0.137594 0.148117 0.0173641 0.137501 0.147549 0.0172595 0.137451 0.14749 0.0174176 0.13743 0.148013 0.017705 0.137148 0.147318 0.0178191 0.13691 0.147246 0.0179587 0.137895 0.148599 0.0175039 0.137684 0.148504 0.0179474 0.137171 0.147921 0.0179642 0.136852 0.147851 0.0181223 0.13735 0.148421 0.0182856 0.136938 0.148358 0.0184925 0.138092 0.148821 0.0182589 0.137096 0.148664 0.0190239 0.138358 0.148921 0.0176577 0.138913 0.149034 0.0178023 0.138588 0.148912 0.0185891 0.138029 0.148801 0.0192167 0.137653 0.148732 0.0187283 0.1373 0.148715 0.0196216 0.136479 0.148626 0.0191225 -0.0533732 0.145764 0.018035 -0.0528201 0.146891 0.0186131 -0.0533732 0.146897 0.0185526 -0.0530593 0.147244 0.0197818 -0.0533731 0.147249 0.0197482 -0.0518083 0.145732 0.0184755 -0.0518377 0.146347 0.0186128 -0.0527554 0.146381 0.0182374 -0.0520001 0.146853 0.0189519 -0.0522668 0.147161 0.0194329 -0.0529278 0.147197 0.0191608 -0.0522083 0.147167 0.0203093 -0.0517358 0.147096 0.0199155 -0.0513438 0.146784 0.0195515 -0.0507751 0.145654 0.0195351 -0.0511232 0.146824 0.0212338 -0.0514011 0.147009 0.0205472 -0.0509334 0.146693 0.0203338 -0.0519592 0.1471 0.0207585 -0.0510991 0.146285 0.0192792 -0.0506319 0.146202 0.020153 -0.0504874 0.146107 0.0211228 0.136478 0.148666 0.0197623 0.135739 0.148297 0.0185579 0.136489 0.148322 0.018558 0.136506 0.14781 0.018172 0.13498 0.148576 0.0191221 0.135729 0.148601 0.0191223 0.13499 0.148273 0.0185578 0.135756 0.147786 0.018172 -0.0505742 0.143098 0.035155 -0.0503732 0.14554 0.021035 -0.0503732 0.143839 0.0298168 -0.0504466 0.142825 0.0350668 -0.0505742 0.146281 0.0211498 -0.0508125 0.146588 0.0211973 -0.0505742 0.144567 0.0299967 -0.0518732 0.147022 0.0212645 -0.0512992 0.14691 0.021247 -0.0511232 0.1451 0.0301284 0.132105 0.146905 0.0203566 0.132961 0.148275 0.0207872 0.132195 0.147474 0.0204739 0.13275 0.148115 0.0212432 0.132551 0.147573 0.0195661 0.132496 0.147955 0.0206251 0.133519 0.148385 0.0209353 0.133713 0.148467 0.0204646 0.133214 0.148379 0.0201318 0.132804 0.148064 0.019815 0.132495 0.146986 0.0194258 0.134039 0.147106 0.0182022 0.133188 0.147659 0.0188294 0.133165 0.147055 0.0186825 0.135006 0.147761 0.018172 0.134122 0.148231 0.0187159 0.134978 0.148617 0.0197618 0.134048 0.148537 0.0200889 0.133671 0.14847 0.0195988 0.133366 0.14816 0.0191534 0.134281 0.148538 0.0192479 0.134036 0.147724 0.0183452 -0.038257 0.136493 0.0493048 -0.0363732 0.136721 0.0499809 -0.0383062 0.136801 0.0498499 -0.0383866 0.13686 0.0504703 -0.0445515 0.136974 0.0462869 -0.0429992 0.136375 0.0472568 -0.0399875 0.136216 0.0485832 -0.0382477 0.135988 0.0489309 -0.0363732 0.135904 0.0490566 -0.0429213 0.136945 0.047436 -0.0478806 0.139404 0.0430705 -0.0494926 0.140398 0.0398109 -0.0499977 0.14152 0.0384869 -0.0503732 0.142384 0.034924 -0.0400079 0.136714 0.0489556 -0.0429704 0.137423 0.0477993 -0.0444765 0.137523 0.0464827 -0.0469504 0.138783 0.0442545 -0.0480166 0.139836 0.043368 -0.0495104 0.140865 0.0400104 -0.0401022 0.137023 0.0494873 -0.0445473 0.137987 0.046835 -0.0447531 0.138297 0.0472901 -0.0470661 0.139224 0.0445731 -0.0482997 0.140146 0.0437095 -0.0496879 0.141279 0.0402471 -0.0501902 0.141928 0.0386912 -0.050516 0.142241 0.0388926 -0.0511232 0.14362 0.035324 -0.0402543 0.13709 0.0500867 -0.0431386 0.137732 0.0482883 -0.0473289 0.139534 0.0449529 -0.0450624 0.138403 0.047778 -0.0477027 0.13967 0.0453415 -0.0486931 0.140295 0.0440505 -0.0500046 0.141592 0.0404939 -0.0514097 0.143741 0.0353633 -0.0384841 0.136658 0.0510573 -0.0433988 0.137822 0.048824 -0.0481362 0.139615 0.0456856 -0.0491455 0.140264 0.0443465 -0.0504241 0.141767 0.0407224 -0.0509398 0.142426 0.039069 -0.0518732 0.143811 0.0353859 0.133485 0.146189 0.031351 0.132027 0.145851 0.0263995 0.132137 0.147404 0.0211264 0.13222 0.146573 0.0265511 0.13222 0.147575 0.0211545 0.13245 0.147879 0.0212044 0.13292 0.148203 0.0212577 0.13348 0.148328 0.0212783 0.132751 0.147108 0.0266636 0.132221 0.144224 0.0351607 0.103174 0.137071 0.0499858 0.118001 0.137351 0.0506203 0.103179 0.136763 0.0494335 0.103194 0.135637 0.048924 0.103176 0.136913 0.051212 0.103174 0.137124 0.0506159 0.039784 0.136412 0.049431 0.039784 0.135904 0.0490566 0.103185 0.136255 0.0490573 0.039784 0.135288 0.048924 -0.0363732 0.136568 0.0512047 -0.0363732 0.136776 0.0506092 0.039784 0.136568 0.0512047 0.039784 0.136776 0.0506092 -0.0363732 0.136412 0.049431 0.039784 0.136721 0.0499809 0.132248 0.143938 0.0363199 0.132046 0.143544 0.0361628 0.133488 0.144944 0.0354044 0.131985 0.143108 0.0360012 0.131321 0.141666 0.0393144 0.131341 0.142122 0.0395158 0.130814 0.141492 0.0408378 0.12904 0.139437 0.0435675 0.128436 0.139015 0.0442861 0.125817 0.138174 0.0466973 0.12214 0.13698 0.0484411 0.121083 0.136771 0.0487205 0.128992 0.139935 0.04379 0.128377 0.139523 0.0445068 0.125072 0.137869 0.0471609 0.122154 0.137473 0.0488173 0.118016 0.136483 0.0490578 0.118007 0.136992 0.0494352 0.131517 0.142527 0.039747 0.130975 0.141904 0.0410968 0.131277 0.142213 0.041372 0.129108 0.140367 0.0441062 0.12848 0.139962 0.0448354 0.126066 0.138945 0.0475239 0.125874 0.138638 0.047058 0.125118 0.13834 0.0475269 0.12109 0.137271 0.0490978 0.132754 0.144742 0.0353359 0.132571 0.14425 0.036457 0.132982 0.144451 0.0365609 0.131829 0.142837 0.0399823 0.129373 0.140675 0.0444741 0.12975 0.140817 0.0448445 0.12873 0.140269 0.0452266 0.129094 0.140404 0.0456265 0.126364 0.139048 0.0480228 0.125293 0.138646 0.0480093 0.122256 0.13778 0.049347 0.121165 0.137578 0.0496383 0.118002 0.137299 0.049989 0.132241 0.143018 0.0401958 0.132149 0.142397 0.0418447 0.131684 0.142384 0.0416314 0.125568 0.138741 0.0485316 0.122428 0.137848 0.0499397 0.1259 0.138608 0.0490107 0.12264 0.137665 0.0504937 0.121295 0.137639 0.0502479 0.121456 0.137444 0.0508203 0.118005 0.137137 0.0512166 -0.131173 0.137176 -0.0476458 -0.121173 0.137113 -0.0476458 -0.131773 0.136324 -0.0465552 -0.13526 0.13791 -0.0469191 -0.138478 0.138954 -0.0450345 -0.137519 0.135184 -0.0397514 -0.14049 0.139404 -0.040582 -0.140653 0.139575 -0.0401863 -0.141742 0.141239 -0.0401583 -0.0760732 0.133784 -0.0438162 -0.113542 0.137098 -0.0476279 -0.121773 0.136136 -0.0465217 -0.110573 0.13621 -0.0466066 -0.120573 0.136122 -0.0465054 -0.111773 0.136025 -0.0463942 -0.110573 0.136013 -0.0463802 -0.0830696 0.136861 -0.0473551 -0.0892071 0.136896 -0.0473953 -0.0805732 0.13621 -0.0466066 -0.0917732 0.135855 -0.0461981 -0.100573 0.135921 -0.0462745 -0.0674751 0.136584 -0.0356865 -0.065798 0.138995 -0.0386604 -0.0659189 0.138817 -0.0391324 -0.0656904 0.139542 -0.0413731 -0.0681296 0.135512 -0.0387976 -0.0727829 0.133997 -0.0431973 -0.0717732 0.136589 -0.0458273 -0.0699934 0.134604 -0.0414351 -0.0705732 0.136422 -0.044728 -0.0678789 0.138291 -0.0442588 -0.0705732 0.137434 -0.0460718 -0.0717732 0.137188 -0.0465731 -0.138671 0.139188 -0.0281224 -0.140573 0.145501 -0.0252998 -0.135317 0.144583 -0.0207739 -0.136153 0.141168 -0.0223739 -0.133192 0.145522 -0.0197249 -0.126195 0.143792 -0.0196419 -0.128454 0.145414 -0.0193266 -0.117773 0.143559 -0.0196874 -0.104573 0.14325 -0.0197473 -0.107773 0.144871 -0.0194322 -0.11119 0.144949 -0.0194171 -0.0977732 0.144671 -0.0194711 -0.0845732 0.142918 -0.0198118 -0.0777732 0.144394 -0.019525 -0.0861828 0.142939 -0.0198078 -0.0945732 0.143064 -0.0197835 -0.0877732 0.14296 -0.0198036 -0.0760732 0.142826 -0.0198297 -0.0755732 0.14282 -0.0198431 -0.0686271 0.140588 -0.0240576 -0.0717742 0.141612 -0.0210819 -0.0658867 0.143985 -0.0259513 -0.0678355 0.144499 -0.0230052 -0.068069 0.144539 -0.0227596 -0.141107 0.142877 -0.0303638 -0.141987 0.144342 -0.0307954 -0.138671 0.136584 -0.0356865 0.165043 0.148524 0.00313214 0.162365 0.149902 -0.00524457 0.160907 0.149876 -0.00485069 0.160543 0.149873 -0.00466209 0.160543 0.148413 -0.00466209 0.159661 0.149872 -0.00399612 0.158955 0.148409 -0.00311364 0.16669 0.148602 0.00148507 0.166583 0.150105 0.00166061 0.166859 0.148611 0.00116321 0.167268 0.148634 -0.000291791 0.167172 0.150149 0.000272171 0.167269 0.150156 -0.0012332 0.167069 0.150141 -0.00216616 0.16669 0.148602 -0.00301499 0.16669 0.150113 -0.00301506 0.165571 0.148547 -0.004305 0.166364 0.15009 -0.00350378 0.165255 0.15002 -0.00453166 0.165043 0.148524 -0.00466208 0.164243 0.148494 -0.00502512 0.162793 0.149913 -0.00526497 0.164239 0.149968 0.00349635 0.164762 0.148513 0.00328132 0.163313 0.148464 0.00370492 0.162793 0.14845 0.00373503 0.161259 0.14988 0.00346532 0.160543 0.149873 0.00313215 0.159946 0.149871 0.00271943 0.158394 0.148412 -0.00171085 0.158293 0.149886 -0.000764971 0.158953 0.149877 0.00158108 0.160543 0.148413 0.00313215 -0.166669 0.148497 -0.00499706 -0.16739 0.150008 -0.00466208 -0.16289 0.149873 0.00313215 -0.161242 0.148409 0.00148503 -0.16064 0.149886 -0.00076497 -0.16064 0.148413 -0.000764971 -0.160759 0.148412 -0.00179623 -0.160665 0.149886 -0.0012409 -0.161242 0.148409 -0.00301497 -0.161242 0.149878 -0.00301497 -0.161348 0.148409 -0.00318794 -0.162363 0.14841 -0.00430653 -0.16289 0.148413 -0.00466209 -0.165183 0.148451 -0.00526476 -0.16514 0.149913 -0.00526497 -0.165574 0.149928 -0.00524391 -0.16289 0.148413 0.00313215 -0.163171 0.148416 0.0032816 -0.163693 0.149881 0.00349605 -0.164622 0.148439 0.00370512 -0.166669 0.149972 0.00346709 -0.166131 0.148478 0.00362434 -0.169167 0.150122 -0.00277195 -0.169539 0.14863 -0.00170957 -0.169604 0.150155 -0.00132888 -0.16964 0.148635 -0.000764971 -0.169386 0.148621 0.000722974 -0.16964 0.150158 -0.000764971 -0.169539 0.15015 0.000179578 -0.169037 0.148602 0.00148508 -0.168978 0.150108 0.00158365 -0.167983 0.150043 0.00272255 -0.167529 0.14853 0.00304818 -0.0760732 0.133876 -0.0420157 -0.130073 0.133594 -0.0428345 -0.130073 0.133876 -0.0420157 -0.137217 0.139679 -0.0251619 -0.136939 0.136111 -0.0355237 -0.137805 0.138715 -0.0279596 -0.137805 0.136111 -0.0355237 -0.136769 0.134852 -0.0391792 -0.134928 0.13453 -0.0401143 -0.132701 0.134046 -0.0415215 -0.133939 0.133931 -0.0418551 -0.0683412 0.136111 -0.0355237 -0.0692072 0.138715 -0.0279596 -0.0726402 0.140651 -0.0223374 -0.0760732 0.140951 -0.0214676 -0.133032 0.141041 -0.0212053 -0.135541 0.140495 -0.0227901 -0.0760644 0.143627 -0.0189781 -0.0760664 0.14349 -0.0193678 -0.0755732 0.143621 -0.0189901 -0.0755732 0.143522 -0.0193117 -0.0755732 0.143322 -0.0195824 -0.0755732 0.143043 -0.0197715 -0.0769244 0.143215 -0.0196673 -0.0773961 0.143195 -0.0196829 -0.0769283 0.142834 -0.0198281 -0.0760695 0.143207 -0.0196688 -0.0769212 0.143498 -0.0193663 -0.0767732 0.145227 -0.0183443 -0.0769655 0.145101 -0.0189695 -0.0768505 0.145174 -0.0187474 -0.0773734 0.144767 -0.0193675 -0.0772155 0.144904 -0.0192528 -0.076968 0.143547 -0.0192749 -0.0770696 0.145023 -0.0191079 -0.0777732 0.142842 -0.0198266 -0.0777687 0.142847 -0.0198257 -0.0773963 0.144746 -0.0193814 -0.0772199 0.143348 -0.0195581 -0.0768236 0.145186 -0.0186716 -0.0845776 0.144474 -0.0195093 -0.08495 0.144831 -0.019365 -0.0811706 0.145231 -0.0186631 -0.0811814 0.14443 -0.019518 -0.0811768 0.144811 -0.0193565 -0.0777687 0.144398 -0.0195241 -0.081173 0.145094 -0.0190542 -0.0845776 0.142923 -0.019811 -0.0845732 0.14447 -0.0195102 -0.0855732 0.145325 -0.0183252 -0.085381 0.145195 -0.0189511 -0.0851259 0.143436 -0.0195415 -0.0853784 0.143641 -0.0192566 -0.0851304 0.144992 -0.019236 -0.0849719 0.143299 -0.0196534 -0.0861701 0.143739 -0.0189568 -0.0861774 0.143319 -0.019647 -0.0872205 0.143463 -0.0195361 -0.0873961 0.143311 -0.0196602 -0.0869684 0.143662 -0.0192533 -0.0861729 0.143602 -0.0193462 -0.0867732 0.145341 -0.0183221 -0.0869659 0.145216 -0.0189477 -0.0868505 0.145288 -0.0187251 -0.0873735 0.144883 -0.0193449 -0.0877732 0.144512 -0.019502 -0.0877687 0.142965 -0.0198028 -0.0870696 0.145138 -0.0190855 -0.0945776 0.14462 -0.0194809 -0.0945732 0.144616 -0.0194818 -0.0911781 0.144943 -0.0193309 -0.0953806 0.145344 -0.0189226 -0.0911729 0.145226 -0.0190288 -0.0911844 0.144562 -0.0194923 -0.0877687 0.144517 -0.0195011 -0.0873962 0.144863 -0.0193586 -0.0872161 0.145019 -0.0192307 -0.0955213 0.14388 -0.01893 -0.0955225 0.145433 -0.0186246 -0.095125 0.143583 -0.0195134 -0.09495 0.144978 -0.0193363 -0.095378 0.14379 -0.0192283 -0.0951296 0.145139 -0.0192079 -0.0945776 0.143068 -0.0197827 -0.0949717 0.143446 -0.0196249 -0.0961728 0.143754 -0.0193171 -0.0961787 0.143471 -0.0196176 -0.0961858 0.143091 -0.0197782 -0.0977687 0.143123 -0.019772 -0.096969 0.143817 -0.0192239 -0.0967732 0.143946 -0.0185934 -0.096824 0.145456 -0.0186203 -0.0973736 0.145041 -0.0193144 -0.0977732 0.143119 -0.0197728 -0.0973962 0.145021 -0.019328 -0.097396 0.143468 -0.0196296 -0.0972214 0.143619 -0.0195064 -0.0970695 0.145294 -0.0190551 -0.0968505 0.145444 -0.0186949 -0.10495 0.145167 -0.0192997 -0.104578 0.144807 -0.0194446 -0.101179 0.145116 -0.0192974 -0.101173 0.145399 -0.0189956 -0.10538 0.145534 -0.0188865 -0.0969664 0.145371 -0.0189183 -0.105522 0.145624 -0.0185883 -0.101187 0.144735 -0.0194587 -0.0977687 0.144676 -0.0194702 -0.0972169 0.145175 -0.0192009 -0.105124 0.143771 -0.0194777 -0.104971 0.143634 -0.0195885 -0.105573 0.145667 -0.0182588 -0.105521 0.14407 -0.0188939 -0.105377 0.143979 -0.0191923 -0.105129 0.145328 -0.019172 -0.104573 0.144803 -0.0194455 -0.106173 0.143947 -0.0192801 -0.104578 0.143255 -0.0197464 -0.107222 0.143815 -0.019469 -0.10618 0.143664 -0.0195802 -0.106189 0.143284 -0.0197407 -0.107396 0.143666 -0.0195911 -0.107769 0.143323 -0.0197332 -0.107773 0.143318 -0.0197341 -0.106168 0.144084 -0.0188913 -0.106824 0.145652 -0.018583 -0.106773 0.144141 -0.0185554 -0.10697 0.144013 -0.0191868 -0.106967 0.145567 -0.018881 -0.106825 0.144098 -0.0188886 -0.10685 0.14564 -0.0186567 -0.107396 0.145219 -0.0192894 -0.107769 0.144876 -0.0194313 -0.111173 0.145613 -0.0189546 -0.114573 0.145031 -0.0194012 -0.11495 0.145396 -0.0192551 -0.115379 0.145765 -0.0188425 -0.111168 0.14575 -0.0185644 -0.114578 0.145035 -0.0194003 -0.111181 0.14533 -0.019256 -0.107374 0.145239 -0.019276 -0.107218 0.145372 -0.0191634 -0.10707 0.145492 -0.0190167 -0.115521 0.144301 -0.01885 -0.115522 0.145856 -0.0185443 -0.115127 0.145557 -0.0191283 -0.114578 0.143482 -0.0197023 -0.115123 0.143999 -0.0194342 -0.115377 0.144209 -0.0191485 -0.116167 0.144318 -0.0188469 -0.114573 0.143477 -0.0197032 -0.116181 0.143897 -0.019535 -0.114971 0.143862 -0.0195442 -0.117396 0.143905 -0.0195447 -0.116192 0.143518 -0.0196953 -0.117769 0.143563 -0.0196865 -0.116173 0.14418 -0.0192352 -0.116826 0.144335 -0.0188437 -0.116773 0.144378 -0.0185094 -0.117069 0.14573 -0.0189704 -0.117374 0.145478 -0.0192296 -0.117224 0.144052 -0.0194238 -0.117219 0.14561 -0.019118 -0.11697 0.144249 -0.019142 -0.117769 0.145117 -0.0193845 -0.121173 0.145867 -0.0189057 -0.124578 0.145304 -0.0193481 -0.121193 0.145204 -0.0193675 -0.12495 0.145666 -0.0192025 -0.116968 0.145804 -0.018836 -0.11685 0.145877 -0.0186105 -0.125379 0.146036 -0.0187908 -0.117773 0.145112 -0.0193854 -0.117396 0.145459 -0.0192428 -0.121182 0.145584 -0.0192066 -0.127225 0.14433 -0.0193709 -0.126182 0.144171 -0.0194819 -0.127396 0.144184 -0.0194903 -0.127769 0.143844 -0.0196319 -0.126172 0.144454 -0.0191826 -0.12685 0.146155 -0.0185564 -0.128431 0.146077 -0.0188653 -0.126969 0.146082 -0.0187832 -0.127773 0.145394 -0.0193306 -0.127396 0.145739 -0.0191883 -0.127221 0.145888 -0.0190649 -0.127069 0.146009 -0.0189162 -0.130073 0.145464 -0.0193169 -0.128441 0.145795 -0.0191659 -0.128424 0.146215 -0.018476 -0.135573 0.145602 -0.0206258 -0.135573 0.145895 -0.0204387 -0.133677 0.146169 -0.0193886 -0.133536 0.145522 -0.0198244 -0.135538 0.145489 -0.020646 -0.133588 0.145893 -0.0196706 -0.133317 0.146172 -0.0192841 -0.133791 0.146305 -0.0190247 -0.135573 0.146112 -0.0201682 -0.13005 0.146127 -0.0188557 -0.13006 0.145844 -0.0191563 -0.133237 0.145894 -0.0195695 -0.0760732 0.133594 -0.0428345 -0.0760732 0.133557 -0.0433509 -0.0702523 0.134342 -0.0410712 -0.0684678 0.135212 -0.038546 -0.0729229 0.133761 -0.0427584 -0.0731143 0.133785 -0.042278 -0.0706058 0.134331 -0.0406933 -0.0689297 0.135148 -0.0383215 -0.130073 0.133557 -0.0433509 -0.0683412 0.138715 -0.0279596 -0.0678411 0.136238 -0.0355674 -0.0678411 0.138842 -0.0280032 -0.138448 0.136332 -0.0355999 -0.138305 0.136238 -0.0355674 -0.137066 0.134854 -0.0393605 -0.137326 0.134969 -0.0395592 -0.134372 0.134159 -0.042727 -0.134261 0.133971 -0.0424576 -0.130073 0.133784 -0.0438162 -0.130073 0.133606 -0.0435185 -0.13411 0.133891 -0.0421548 -0.130073 0.133539 -0.0431776 -0.0674751 0.139188 -0.0281224 -0.068944 0.140182 -0.0241114 -0.0760732 0.141663 -0.0201172 -0.0719572 0.141163 -0.0212625 -0.069377 0.139974 -0.0243042 -0.0722072 0.140896 -0.0216283 -0.138147 0.136168 -0.0355434 -0.138305 0.138842 -0.0280032 -0.0760732 0.141233 -0.0206488 -0.0760732 0.141401 -0.0203451 -0.130073 0.141522 -0.0202197 -0.0760732 0.141522 -0.0202197 -0.130073 0.141663 -0.0201172 -0.0760732 0.141987 -0.0199927 -0.130073 0.141987 -0.0199927 -0.130073 0.141401 -0.0203451 -0.130073 0.141233 -0.0206488 -0.133364 0.141774 -0.0206116 -0.138017 0.140259 -0.0250113 -0.137679 0.139868 -0.0250246 -0.133223 0.141318 -0.0208122 -0.135894 0.140737 -0.0224994 -0.169036 0.150489 0.00163293 -0.166985 0.150971 0.00444719 -0.168351 0.150969 0.00322935 -0.170127 0.151068 0.00031825 -0.16739 0.150008 0.00313213 -0.165184 0.149915 0.00373481 -0.161282 0.150267 0.00170287 -0.161348 0.149876 0.00165857 -0.162314 0.150264 0.00284007 -0.162364 0.149871 0.002777 -0.161242 0.149878 0.00148503 -0.160759 0.149884 0.000267009 -0.160683 0.150274 0.000286273 -0.160866 0.149883 -0.00217331 -0.161573 0.149874 -0.00350837 -0.162681 0.149872 -0.00453394 -0.167054 0.150378 -0.00492424 -0.167034 0.14999 -0.0048469 -0.164042 0.150281 -0.00521202 -0.164067 0.149887 -0.00513517 -0.162636 0.150265 -0.00460069 -0.16289 0.149873 -0.00466209 -0.168278 0.150061 -0.00399004 -0.169037 0.150113 -0.00301503 -0.16923 0.150502 -0.00281454 -0.170201 0.151073 -0.00141171 -0.170574 0.151155 -0.0014595 -0.169701 0.151042 -0.00306581 -0.168686 0.150986 -0.00445952 -0.167431 0.150989 -0.00579225 -0.165647 0.150926 -0.00628112 -0.162325 0.150808 -0.00507513 -0.160261 0.150815 -0.00237649 -0.160032 0.150818 -0.00130961 -0.159643 0.150886 -0.00135107 -0.16014 0.150816 0.000415953 -0.159759 0.150884 0.00050591 -0.16081 0.15081 0.00200763 -0.161721 0.150871 0.00359707 -0.163474 0.150818 0.00410746 -0.165167 0.15085 0.0043815 -0.169485 0.15103 0.00192709 -0.169214 0.150812 0.00175346 -0.169817 0.15085 0.000248723 -0.167269 0.15092 -0.00543719 -0.163983 0.15061 -0.00543293 -0.16561 0.150862 -0.00588819 -0.163898 0.150824 -0.00576231 -0.162511 0.150594 -0.00479129 -0.161332 0.150594 -0.00369717 -0.161065 0.150808 -0.00390323 -0.160364 0.150603 -0.00127399 -0.161093 0.150596 0.00182573 -0.161965 0.150807 0.00328585 -0.163585 0.150604 0.00378629 -0.165169 0.150636 0.00404281 -0.166748 0.150689 0.00376106 -0.169611 0.150528 0.000200092 -0.169887 0.150855 -0.00137023 -0.169417 0.150825 -0.00291765 -0.168321 0.150445 -0.00405503 -0.168464 0.15077 -0.00421996 -0.167136 0.150705 -0.00513187 -0.165571 0.150319 -0.00532453 -0.165584 0.150648 -0.00555138 -0.16151 0.150266 -0.00355817 -0.160791 0.150272 -0.00219949 -0.160578 0.1506 -0.00227099 -0.160587 0.150275 -0.00124981 -0.160465 0.150602 0.000338677 -0.162174 0.150593 0.00301927 -0.163663 0.150274 0.00357092 -0.165175 0.150307 0.00381508 -0.166683 0.150361 0.00354607 -0.168021 0.150427 0.00279172 -0.166855 0.150903 0.00407812 -0.16815 0.150753 0.00296981 -0.169677 0.150533 -0.00134118 0.158886 0.150268 0.00162403 0.158073 0.150876 0.00212421 0.158408 0.15081 0.00191903 0.159895 0.150264 0.00278156 0.162746 0.149912 0.00373478 0.165569 0.150038 0.0027772 0.165605 0.150424 0.0028472 0.165043 0.150008 0.00313213 0.16669 0.150113 0.00148507 0.167293 0.150158 -0.000764949 0.167342 0.150534 -0.00124342 0.167138 0.150519 -0.00219635 0.162349 0.150294 -0.00532383 0.163877 0.150342 -0.00521425 0.163871 0.149952 -0.00513407 0.165043 0.150008 -0.00466207 0.158896 0.149878 -0.00301497 0.158768 0.149879 -0.00277731 0.157771 0.150817 0.000313978 0.157847 0.150879 -0.00324318 0.158939 0.150871 -0.00474421 0.159213 0.150807 -0.00446066 0.160462 0.150875 -0.00579671 0.160629 0.150812 -0.00543702 0.164086 0.150951 -0.00614588 0.166833 0.151012 -0.00390356 0.167639 0.15106 -0.00237168 0.167997 0.15114 -0.00249069 0.167084 0.151026 0.00201518 0.165926 0.150965 0.00329174 0.164413 0.1509 0.00411139 0.164537 0.150967 0.00448321 0.162716 0.150847 0.00438134 0.162711 0.150911 0.00477678 0.158029 0.150603 -0.00137113 0.157698 0.150817 -0.00141356 0.158497 0.150598 -0.00291646 0.158198 0.150812 -0.00306737 0.159448 0.150593 -0.00421767 0.160773 0.150599 -0.00512912 0.162284 0.150837 -0.00588782 0.163994 0.150885 -0.0057638 0.165569 0.150948 -0.00507788 0.165396 0.150733 -0.00479695 0.167867 0.151074 -0.00130198 0.167552 0.150856 -0.00126753 0.167757 0.151067 0.000424414 0.166816 0.150809 0.0018358 0.164313 0.150685 0.00379203 0.162725 0.150634 0.0040426 0.158316 0.150274 0.000195501 0.158097 0.150602 0.000243382 0.158251 0.150275 -0.00134235 0.158698 0.150269 -0.00281438 0.159606 0.150264 -0.0040541 0.160871 0.150269 -0.00492259 0.162321 0.150624 -0.00555038 0.163921 0.150671 -0.0054359 0.165285 0.150406 -0.00460493 0.166416 0.150472 -0.00356034 0.166581 0.150795 -0.0037007 0.167338 0.150842 -0.00226844 0.167243 0.150527 0.000294667 0.167448 0.150849 0.000348059 0.166641 0.150486 0.00171135 0.16573 0.150749 0.00302803 0.164252 0.150358 0.00357561 0.162735 0.150304 0.0038149 0.161227 0.150273 0.00353965 0.161146 0.150603 0.00375347 0.159751 0.150593 0.00295787 0.161028 0.150816 0.00407232 0.159537 0.150807 0.00322008 0.158694 0.150596 0.00174298 0.158393 0.149885 0.000177887 0.158329 0.149886 -0.00133173 -0.0703032 0.135067 -0.0386877 -0.0726402 0.134175 -0.0411459 -0.0760732 0.134153 -0.0417182 -0.0692072 0.136111 -0.0355237 -0.0694105 0.136152 -0.0355378 -0.0704488 0.13521 -0.0386479 -0.0760732 0.134726 -0.0418505 -0.0760732 0.134511 -0.0417057 -0.072878 0.134636 -0.040869 -0.0760732 0.134357 -0.0416786 -0.070127 0.134993 -0.0387697 -0.0727419 0.134273 -0.0409935 -0.072826 0.134436 -0.0408955 -0.0705389 0.135397 -0.0386574 -0.0728888 0.134837 -0.0409186 -0.0694572 0.136174 -0.0355456 -0.0696402 0.136347 -0.0356051 -0.0696827 0.136438 -0.0356362 -0.0705577 0.135596 -0.0387144 -0.0728567 0.135006 -0.0410356 -0.0705021 0.135773 -0.0388092 -0.130073 0.133983 -0.0418375 -0.0760732 0.133983 -0.0418375 -0.130073 0.134153 -0.0417182 -0.0760732 0.13402 -0.0418011 -0.130073 0.134253 -0.0416877 -0.0760732 0.134253 -0.0416877 -0.130073 0.134357 -0.0416786 -0.130073 0.13456 -0.0417253 -0.0760732 0.13456 -0.0417253 -0.0695787 0.136267 -0.0355776 -0.0696402 0.138952 -0.028041 -0.0697072 0.139188 -0.0281224 -0.0697072 0.136584 -0.0356865 -0.0697044 0.136633 -0.0357036 -0.130073 0.13402 -0.0418011 -0.132623 0.134148 -0.041358 -0.134665 0.134772 -0.0399197 -0.134592 0.134966 -0.0399088 -0.132559 0.134314 -0.0412508 -0.132519 0.134515 -0.0412186 -0.130073 0.134511 -0.0417057 -0.136417 0.135255 -0.0380081 -0.136736 0.136152 -0.0355378 -0.136229 0.135322 -0.0379486 -0.136568 0.136267 -0.0355776 -0.135977 0.135641 -0.0379485 -0.136442 0.136633 -0.0357036 -0.136073 0.135458 -0.0379275 -0.134784 0.134618 -0.0399924 -0.135957 0.13584 -0.038008 -0.134577 0.135167 -0.0399616 -0.135644 0.135773 -0.0388092 -0.13251 0.134717 -0.041267 -0.13329 0.135006 -0.0410356 -0.0727652 0.140644 -0.0225639 -0.0760732 0.140925 -0.021674 -0.0760732 0.140933 -0.0217258 -0.070127 0.139833 -0.0247136 -0.0703436 0.139856 -0.0248536 -0.0694572 0.138779 -0.0279814 -0.0705601 0.140224 -0.0251128 -0.0696402 0.139425 -0.0282038 -0.0705021 0.139999 -0.0249997 -0.0728902 0.140983 -0.0229096 -0.0705021 0.140472 -0.0251625 -0.0728567 0.140766 -0.0227734 -0.0760732 0.141261 -0.0221032 -0.136689 0.138779 -0.0279814 -0.136464 0.136438 -0.0356362 -0.136506 0.138952 -0.028041 -0.136464 0.139042 -0.0280721 -0.130073 0.140951 -0.0214676 -0.0760732 0.140986 -0.0218728 -0.130073 0.140986 -0.0218728 -0.0760732 0.141046 -0.0219585 -0.0760732 0.141123 -0.0220297 -0.130073 0.141123 -0.0220297 -0.130073 0.141261 -0.0221032 -0.0760732 0.141311 -0.0221176 -0.136939 0.138715 -0.0279596 -0.13329 0.140766 -0.0227734 -0.130073 0.141046 -0.0219585 -0.133381 0.140644 -0.0225639 -0.133506 0.140651 -0.0223374 -0.130073 0.140933 -0.0217258 -0.130073 0.140925 -0.021674 -0.136568 0.138872 -0.0280135 -0.133256 0.140983 -0.0229096 -0.130073 0.141311 -0.0221176 -0.136019 0.139833 -0.0247136 -0.135803 0.139856 -0.0248536 -0.135644 0.139999 -0.0249997 -0.136439 0.139188 -0.0281224 -0.135586 0.140224 -0.0251128 -0.135644 0.140472 -0.0251625 -0.0760732 0.13869 -0.0464114 -0.076062 0.138951 -0.0486548 -0.0760646 0.139174 -0.0478921 -0.0732051 0.138877 -0.0460406 -0.0730793 0.139271 -0.04671 -0.0704881 0.139789 -0.0456711 -0.0677099 0.140862 -0.0433808 -0.0667878 0.141349 -0.0408183 -0.0663699 0.141798 -0.0411715 -0.0657186 0.143014 -0.0378983 -0.0736566 0.139202 -0.0468466 -0.0735043 0.139302 -0.047615 -0.0701462 0.139922 -0.0463433 -0.0700661 0.139911 -0.0454225 -0.0696998 0.140051 -0.046075 -0.0679963 0.140714 -0.0437104 -0.0657998 0.142049 -0.0415083 -0.0660974 0.142095 -0.0404207 -0.0655131 0.142364 -0.040705 -0.0728918 0.139374 -0.047467 -0.0726719 0.139171 -0.0481944 -0.0697471 0.13977 -0.046979 -0.0675133 0.140901 -0.0442312 -0.0666371 0.141002 -0.0443246 -0.0672112 0.141058 -0.0438771 -0.065149 0.14207 -0.0417866 -0.0648473 0.142408 -0.0409275 -0.0651145 0.143343 -0.0380096 -0.10305 0.139113 -0.0488616 -0.130036 0.139392 -0.0492187 -0.103056 0.139342 -0.0480957 -0.130044 0.139631 -0.0484475 -0.130058 0.139546 -0.0476445 -0.103074 0.138859 -0.0466055 -0.0760685 0.139082 -0.0471027 -0.103064 0.139252 -0.0473014 -0.0644962 0.14468 -0.0341153 -0.0651832 0.144559 -0.0341045 -0.0659806 0.145215 -0.0301054 -0.0657875 0.144219 -0.0340291 -0.0664281 0.144685 -0.0300151 -0.140851 0.143361 -0.0403028 -0.141111 0.144139 -0.0383034 -0.140627 0.143047 -0.0410513 -0.136811 0.140723 -0.0457838 -0.135908 0.140098 -0.04557 -0.13287 0.139382 -0.0466738 -0.133465 0.139854 -0.0472418 -0.132966 0.139775 -0.0473608 -0.141424 0.143639 -0.040558 -0.141189 0.143307 -0.0413563 -0.139401 0.141986 -0.0433663 -0.139906 0.142191 -0.0438309 -0.138889 0.141671 -0.0440017 -0.13613 0.140492 -0.0461901 -0.137185 0.140864 -0.0464289 -0.136467 0.140621 -0.0468675 -0.133125 0.13987 -0.0481364 -0.142079 0.143707 -0.0407478 -0.141835 0.143353 -0.0415985 -0.140493 0.142158 -0.0442407 -0.139369 0.141859 -0.0445122 -0.136869 0.140466 -0.0475024 -0.133653 0.139952 -0.048007 -0.133321 0.139651 -0.0488775 -0.065376 0.145564 -0.0301449 -0.0662618 0.145553 -0.0284362 -0.0680511 0.145444 -0.0254927 -0.0684078 0.145511 -0.0250063 -0.0680552 0.146166 -0.0248462 -0.0703026 0.145745 -0.0231639 -0.0730351 0.146664 -0.0214006 -0.0734743 0.145927 -0.021613 -0.0760657 0.146746 -0.0209315 -0.0656644 0.14594 -0.028363 -0.0664538 0.145671 -0.027799 -0.0658638 0.146072 -0.027683 -0.0676815 0.146086 -0.025355 -0.0671502 0.146542 -0.0250765 -0.0700389 0.146451 -0.0229217 -0.0701781 0.147024 -0.0220952 -0.0705449 0.1465 -0.0225721 -0.0733534 0.146678 -0.0213062 -0.0731663 0.147234 -0.0207332 -0.0760595 0.147312 -0.0203298 -0.0646882 0.145691 -0.0301287 -0.0649805 0.146096 -0.0282219 -0.0665326 0.146747 -0.0246966 -0.0669474 0.146847 -0.0241108 -0.0675437 0.146634 -0.0245326 -0.0696413 0.146966 -0.0224706 -0.0691721 0.147209 -0.0218814 -0.0728271 0.147218 -0.0208349 -0.0725802 0.147484 -0.0201016 -0.141365 0.145613 -0.0345155 -0.141214 0.146686 -0.0305945 -0.140678 0.143652 -0.0381202 -0.140657 0.144921 -0.0343211 -0.140939 0.14649 -0.0305616 -0.141693 0.144463 -0.0384282 -0.141387 0.144324 -0.0383741 -0.0760556 0.147586 -0.0195508 -0.103076 0.146379 -0.0211766 -0.0760732 0.145985 -0.0212531 -0.103038 0.147979 -0.0194778 -0.130048 0.147827 -0.0207226 -0.103046 0.147704 -0.0202554 -0.10306 0.147138 -0.0208557 -0.130073 0.147069 -0.0210424 -0.130027 0.148392 -0.0201247 -0.13195 0.147872 -0.0208756 -0.132669 0.147878 -0.0210231 -0.137847 0.146961 -0.0244241 -0.138162 0.146922 -0.0247809 -0.138484 0.147567 -0.0246081 -0.140024 0.147203 -0.027014 -0.139634 0.146614 -0.0270833 -0.132048 0.148432 -0.0202908 -0.135349 0.147837 -0.0220549 -0.135651 0.148367 -0.0215578 -0.136266 0.148332 -0.021922 -0.13593 0.14781 -0.0223949 -0.138155 0.147615 -0.0242358 -0.138611 0.148094 -0.0238884 -0.14057 0.147622 -0.0268433 -0.140382 0.14705 -0.0278848 -0.140943 0.147451 -0.0277674 -0.132811 0.148435 -0.0204497 -0.139151 0.148331 -0.0234302 -0.138957 0.148038 -0.0242851 -0.141204 0.14782 -0.0265929 -0.215173 0.1105 -0.0780687 -0.215173 0.110682 -0.077668 -0.215173 0.110674 -0.0772279 -0.216327 0.110282 -0.0764949 -0.216537 0.11033 -0.0782664 -0.218922 0.111421 -0.0776851 -0.218673 0.111667 -0.077451 -0.220822 0.113057 -0.07677 -0.223147 0.116153 -0.0748839 -0.222829 0.116255 -0.0747404 -0.224834 0.119593 -0.0725348 -0.224527 0.119641 -0.0724341 -0.226173 0.12614 -0.0672035 -0.216426 0.11065 -0.0779909 -0.216336 0.110821 -0.0775985 -0.218468 0.111784 -0.0771028 -0.220522 0.113234 -0.0765761 -0.225408 0.122358 -0.0703754 -0.225143 0.122316 -0.0702425 -0.225914 0.126117 -0.0671783 -0.22027 0.113303 -0.0762752 -0.218344 0.111753 -0.0767023 -0.220105 0.113254 -0.0759153 -0.222554 0.116272 -0.074505 -0.224253 0.119622 -0.0722578 -0.224041 0.119537 -0.0720246 -0.224928 0.122221 -0.0700578 -0.225466 0.125942 -0.0669872 -0.216285 0.11081 -0.0771643 -0.216281 0.110618 -0.0767714 -0.218322 0.111579 -0.0763201 -0.222356 0.116202 -0.0742088 -0.222263 0.116055 -0.0738907 -0.224782 0.122081 -0.0698379 -0.218406 0.111292 -0.076024 -0.220126 0.112849 -0.0752473 -0.220055 0.113094 -0.0755534 -0.223913 0.119395 -0.0717595 -0.223884 0.119212 -0.0714907 -0.225307 0.125803 -0.0668342 -0.224718 0.121908 -0.0696022 -0.215173 0.109703 -0.076465 -0.216414 0.109867 -0.0763877 -0.220309 0.112557 -0.0750456 -0.222286 0.115849 -0.0735927 -0.223956 0.119007 -0.0712468 -0.19099 0.109669 -0.076465 -0.190987 0.11064 -0.0772275 -0.20308 0.110489 -0.0780686 -0.203081 0.110153 -0.0783524 -0.215173 0.110132 -0.0765618 -0.215173 0.110478 -0.0768337 -0.203081 0.110121 -0.0765618 -0.20308 0.110467 -0.0768336 -0.20308 0.110663 -0.0772277 -0.20308 0.110671 -0.0776678 -0.215173 0.110164 -0.0783525 -0.225791 0.147951 -0.0310632 -0.225791 0.131564 -0.0615982 -0.225673 0.126049 -0.0671045 -0.225207 0.12564 -0.0666561 -0.226173 0.131621 -0.0616487 -0.225791 0.141537 -0.0473224 -0.226173 0.141604 -0.0473584 -0.226173 0.14531 -0.039362 -0.226173 0.147623 -0.03254 -0.225791 0.145239 -0.0393341 -0.225466 0.131402 -0.0614542 -0.225466 0.136771 -0.0546547 -0.225791 0.136948 -0.0547789 -0.225466 0.141346 -0.0472198 -0.225466 0.145038 -0.0392547 -0.225791 0.149781 -0.0224217 -0.225466 0.149567 -0.0223849 -0.225249 0.131159 -0.0612387 -0.225249 0.14106 -0.0470662 -0.225249 0.144736 -0.0391358 -0.225249 0.147428 -0.0309248 -0.225466 0.147741 -0.0310077 -0.225249 0.149248 -0.0223299 -0.225173 0.130873 -0.0609844 -0.225249 0.136505 -0.0544687 -0.185371 0.113077 -0.074737 -0.181172 0.123135 -0.0685804 -0.180855 0.125662 -0.0668343 -0.180939 0.123444 -0.0689927 -0.180695 0.125802 -0.0669871 -0.180466 0.123596 -0.0692638 -0.180185 0.123594 -0.0693167 -0.180245 0.125976 -0.0671772 -0.182151 0.119545 -0.0715866 -0.181092 0.123304 -0.0687966 -0.181807 0.119774 -0.0720759 -0.180724 0.123544 -0.0691528 -0.182184 0.119363 -0.0713208 -0.183093 0.117427 -0.0729926 -0.18202 0.119688 -0.0718474 -0.181533 0.119796 -0.0722478 -0.185152 0.113853 -0.0746801 -0.182987 0.117011 -0.0724614 -0.183095 0.117232 -0.0727056 -0.185139 0.114236 -0.0753324 -0.182983 0.117572 -0.0732878 -0.182776 0.117649 -0.0735557 -0.182499 0.117649 -0.0737641 -0.184984 0.113585 -0.0744605 -0.185608 0.113591 -0.0752552 -0.185207 0.114082 -0.0749859 -0.185114 0.113745 -0.0762425 -0.184959 0.114294 -0.0756682 -0.184693 0.114246 -0.0759433 -0.184381 0.114101 -0.0761169 -0.187432 0.111007 -0.0758106 -0.185546 0.113355 -0.0749489 -0.187692 0.111635 -0.0762689 -0.185548 0.113748 -0.0756089 -0.185375 0.113802 -0.0759557 -0.189424 0.110366 -0.0764383 -0.187608 0.111351 -0.0759719 -0.189476 0.110884 -0.0771095 -0.187667 0.111808 -0.0766496 -0.189407 0.110899 -0.077539 -0.187538 0.111841 -0.077047 -0.187329 0.111727 -0.0773914 -0.190989 0.110098 -0.0765618 -0.189481 0.110695 -0.0767179 -0.190988 0.110444 -0.0768335 -0.190987 0.110648 -0.0776674 -0.190988 0.110466 -0.0780682 -0.18929 0.110736 -0.0779249 -0.225208 0.149963 -0.0200247 -0.224886 0.149715 -0.0195959 -0.224802 0.149345 -0.0195647 -0.223457 0.150156 -0.0165402 -0.223379 0.149791 -0.0165503 -0.222245 0.149962 -0.0151948 -0.221458 0.150412 -0.0143988 -0.22552 0.150179 -0.0199846 -0.225097 0.150032 -0.0195834 -0.223891 0.150421 -0.0168357 -0.221792 0.150946 -0.0140332 -0.221413 0.150976 -0.0137432 -0.218679 0.151112 -0.0123036 -0.221228 0.150755 -0.0139762 -0.218576 0.150891 -0.0125813 -0.218226 0.151125 -0.0121554 -0.2188 0.151211 -0.0119681 -0.221627 0.151074 -0.0134573 -0.223898 0.150689 -0.0162976 -0.22447 0.150733 -0.0165085 -0.224159 0.15064 -0.0166937 -0.225405 0.150249 -0.0195291 -0.225765 0.150335 -0.0194409 -0.215171 0.151159 -0.0117043 -0.218136 0.150904 -0.0124377 -0.215172 0.150938 -0.0120008 -0.224994 0.149646 -0.0200265 -0.223704 0.150106 -0.0169148 -0.223639 0.15047 -0.0164518 -0.221596 0.150726 -0.0142573 -0.221099 0.150442 -0.0141245 -0.218503 0.150578 -0.0127632 -0.218072 0.15059 -0.0126231 -0.215172 0.150736 -0.0121445 -0.215172 0.150624 -0.0121966 -0.219 0.150196 -0.0130263 -0.218471 0.150215 -0.0128244 -0.180361 0.149452 -0.0224203 -0.179975 0.147764 -0.0308939 -0.179975 0.147318 -0.03254 -0.180362 0.147694 -0.0308759 -0.180692 0.144764 -0.03925 -0.180366 0.137284 -0.0539827 -0.180693 0.14108 -0.0472623 -0.180694 0.137105 -0.0538618 -0.179977 0.145032 -0.0393547 -0.180363 0.144965 -0.0393284 -0.180365 0.14127 -0.0473639 -0.179979 0.141335 -0.0473983 -0.179981 0.137345 -0.0540239 -0.180368 0.132023 -0.060873 -0.180487 0.125909 -0.0671041 -0.180912 0.148918 -0.0223296 -0.180691 0.147485 -0.0308219 -0.180912 0.147169 -0.0307402 -0.180912 0.14446 -0.0391316 -0.180694 0.131859 -0.060732 -0.18099 0.148537 -0.022265 -0.180912 0.140792 -0.0471089 -0.180913 0.136836 -0.0536796 -0.180913 0.131612 -0.0605199 -0.180955 0.125498 -0.0666562 -0.18099 0.125323 -0.066465 -0.215171 0.151098 -0.011812 -0.215173 0.150261 -0.012265 -0.203074 0.1512 -0.0113476 -0.190984 0.150559 -0.0121444 -0.190981 0.150761 -0.0120006 -0.203078 0.15068 -0.0121444 -0.203075 0.151041 -0.0118119 -0.190977 0.15108 -0.0113471 -0.18175 0.149193 -0.0184391 -0.190979 0.150921 -0.0118117 -0.185203 0.150853 -0.0129952 -0.188709 0.15093 -0.011951 -0.188779 0.15071 -0.0122404 -0.188231 0.150914 -0.0120678 -0.185397 0.150758 -0.0132984 -0.184969 0.150723 -0.0135792 -0.188831 0.150395 -0.0124305 -0.188316 0.150693 -0.0123536 -0.185566 0.150538 -0.0135464 -0.18528 0.150189 -0.0139705 -0.185743 0.149858 -0.0137519 -0.185687 0.150223 -0.0137049 -0.188377 0.150379 -0.012541 -0.183133 0.149925 -0.0159651 -0.182956 0.15024 -0.0158626 -0.182706 0.150459 -0.0156881 -0.18515 0.150503 -0.0138186 -0.182417 0.150551 -0.0154663 -0.18476 0.150819 -0.0132856 -0.182644 0.150185 -0.0162734 -0.182083 0.150495 -0.0159046 -0.181472 0.149485 -0.0189651 -0.182827 0.149869 -0.016366 -0.180954 0.15002 -0.0188606 -0.182383 0.150404 -0.016112 -0.180598 0.150104 -0.0187475 -0.181324 0.149413 -0.0194248 -0.18126 0.149803 -0.0189369 -0.180691 0.149239 -0.0223842 -0.18111 0.149731 -0.019408 -0.180798 0.149947 -0.0193469 -0.180436 0.150029 -0.0192506 -0.224412 0.149522 0.0169093 -0.215171 0.151159 0.0101744 -0.217472 0.151141 0.0104279 -0.215172 0.150736 0.0106145 -0.217551 0.15124 0.0100802 -0.218036 0.15123 0.0102004 -0.220772 0.151019 0.01178 -0.221401 0.15109 0.0117665 -0.21786 0.150911 0.0108288 -0.217941 0.151132 0.0105439 -0.220607 0.150798 0.0120265 -0.221195 0.150992 0.0120577 -0.217404 0.15092 0.0107164 -0.217357 0.150607 0.0109063 -0.22049 0.150485 0.0121849 -0.220836 0.150094 0.0124927 -0.220891 0.150458 0.0124475 -0.217802 0.150597 0.011016 -0.217777 0.150234 0.01108 -0.217336 0.150243 0.0109717 -0.215173 0.150261 0.010735 -0.215172 0.150624 0.0106666 -0.221016 0.150771 0.0122956 -0.223454 0.150761 0.0141686 -0.223739 0.150857 0.0139495 -0.222961 0.149863 0.0144617 -0.223035 0.150228 0.0144438 -0.223208 0.150542 0.0143413 -0.224071 0.150805 0.0143863 -0.223339 0.150177 0.0148432 -0.223518 0.150491 0.0147507 -0.225199 0.150346 0.0173387 -0.223774 0.150711 0.014591 -0.224691 0.149812 0.0174415 -0.225048 0.150058 0.0178805 -0.225354 0.150275 0.0178207 -0.224899 0.150128 0.0174135 -0.225711 0.150362 0.0177263 -0.225551 0.150434 0.0172278 -0.225466 0.149567 0.020855 -0.224837 0.149742 0.0178972 -0.225791 0.149781 0.0208917 -0.226173 0.149856 0.0209046 -0.215171 0.151098 0.0102821 -0.203078 0.15068 0.0106145 -0.203081 0.150204 0.010735 -0.190985 0.150447 0.0106666 -0.19099 0.150083 0.010735 -0.190979 0.150921 0.0102817 -0.203075 0.151041 0.010282 -0.215172 0.150938 0.0104708 -0.226173 0.148065 0.0293981 -0.225249 0.149248 0.0207999 -0.225791 0.141517 0.0458282 -0.225791 0.137493 0.05246 -0.225791 0.147992 0.0293788 -0.225791 0.145237 0.0378094 -0.225466 0.137313 0.052338 -0.225791 0.132197 0.0593463 -0.225466 0.125942 0.0654572 -0.225466 0.147782 0.0293239 -0.225466 0.145036 0.0377299 -0.225249 0.141041 0.0455719 -0.225466 0.141326 0.0457256 -0.225249 0.137045 0.0521555 -0.225466 0.132034 0.0592044 -0.225249 0.125724 0.0652177 -0.225249 0.147468 0.0292416 -0.225249 0.144734 0.0376111 -0.225249 0.131788 0.058992 -0.225173 0.136729 0.0519403 -0.225173 0.131499 0.0587415 -0.180361 0.149452 0.0208904 -0.181358 0.14901 0.018046 -0.182451 0.149791 0.0153937 -0.182534 0.149422 0.0153968 -0.184697 0.150133 0.0128735 -0.185057 0.150168 0.0125988 -0.180257 0.149927 0.0183986 -0.180743 0.149918 0.0180109 -0.180378 0.149999 0.0179214 -0.181987 0.150325 0.0151718 -0.181672 0.150415 0.0149846 -0.181942 0.150469 0.0145732 -0.184124 0.150762 0.0122289 -0.182248 0.150378 0.014774 -0.184516 0.150798 0.0119286 -0.187817 0.150998 0.0102839 -0.180691 0.149239 0.0208543 -0.180628 0.149847 0.0184721 -0.18226 0.150107 0.015315 -0.184354 0.150667 0.012507 -0.184733 0.150703 0.0122165 -0.184922 0.150483 0.0124508 -0.187467 0.150882 0.0107752 -0.187923 0.150901 0.0106258 -0.190977 0.15108 0.00981718 -0.190981 0.150761 0.0104706 -0.190984 0.150559 0.0106144 -0.180945 0.149631 0.0185127 -0.181163 0.149312 0.0185142 -0.181272 0.149383 0.0180783 -0.181057 0.149702 0.018066 -0.182513 0.15016 0.0149295 -0.182699 0.149844 0.0150176 -0.184555 0.150447 0.0127323 -0.187574 0.150661 0.0110537 -0.188017 0.150681 0.0109089 -0.188085 0.150366 0.0110942 -0.187652 0.150347 0.0112355 -0.226173 0.12614 0.0656735 -0.225976 0.123737 0.0677752 -0.225791 0.126088 0.0656173 -0.225696 0.123737 0.067722 -0.225439 0.123685 0.0676107 -0.225225 0.123585 0.0674506 -0.224994 0.123095 0.0668201 -0.225173 0.125466 0.064935 -0.223985 0.119483 0.0697789 -0.224993 0.123278 0.0670386 -0.225073 0.123446 0.0672546 -0.224634 0.119915 0.0707056 -0.224018 0.119665 0.0700448 -0.223179 0.11766 0.0717578 -0.224148 0.119807 0.0703055 -0.223385 0.117737 0.0720258 -0.224361 0.119893 0.0705337 -0.223977 0.117662 0.0723582 -0.223176 0.117101 0.0709308 -0.223068 0.117322 0.0711753 -0.220955 0.114147 0.0734563 -0.223069 0.117516 0.0714625 -0.221023 0.114301 0.0738029 -0.223662 0.117738 0.0722343 -0.220551 0.11365 0.0737275 -0.22101 0.11392 0.0731502 -0.22061 0.113807 0.0740814 -0.221203 0.114359 0.0741387 -0.221468 0.114312 0.0744138 -0.21873 0.111056 0.0742812 -0.218552 0.111399 0.0744428 -0.220614 0.113415 0.0734209 -0.218468 0.111682 0.0747402 -0.218492 0.111855 0.075121 -0.21862 0.111887 0.0755185 -0.21883 0.111774 0.0758629 -0.220784 0.113861 0.0744283 -0.221044 0.113804 0.074715 -0.216737 0.110406 0.0749087 -0.216683 0.110923 0.0755804 -0.216751 0.110938 0.0760099 -0.21687 0.110775 0.0763958 -0.217016 0.110466 0.0766651 -0.219085 0.111535 0.0760936 -0.215173 0.110478 0.0753038 -0.216678 0.110734 0.0751886 -0.215173 0.110674 0.0756979 -0.215173 0.110682 0.076138 -0.215173 0.1105 0.0765388 -0.215173 0.110164 0.0768226 -0.180913 0.125582 0.0652177 -0.180695 0.125802 0.0654571 -0.18099 0.125323 0.064935 -0.180955 0.125498 0.0651262 -0.179981 0.136801 0.0532886 -0.180366 0.136741 0.0532467 -0.179979 0.141356 0.0458275 -0.180363 0.144956 0.0378207 -0.179977 0.145023 0.037847 -0.180362 0.147643 0.0295408 -0.179973 0.149522 0.0209023 -0.180694 0.131233 0.05992 -0.180368 0.131395 0.0600632 -0.180694 0.136563 0.0531234 -0.180693 0.141101 0.0456917 -0.180365 0.141292 0.0457932 -0.180912 0.140814 0.0455385 -0.180692 0.144755 0.0377422 -0.180691 0.147435 0.0294862 -0.180912 0.147119 0.0294037 -0.180913 0.130989 0.0597047 -0.180913 0.136296 0.0529378 -0.18099 0.130701 0.0594505 -0.180912 0.144451 0.0376237 -0.18099 0.144092 0.0374836 -0.180912 0.148918 0.0207997 -0.18099 0.148537 0.020735 -0.215173 0.110132 0.0750319 -0.20308 0.110467 0.0753037 -0.20308 0.110663 0.0756978 -0.20308 0.110671 0.0761378 -0.203081 0.109692 0.074935 -0.203081 0.110121 0.0750319 -0.190987 0.110648 0.0761375 -0.20308 0.110489 0.0765386 -0.190988 0.11013 0.0768222 -0.203081 0.110153 0.0768225 -0.190988 0.110444 0.0753035 -0.190987 0.11064 0.0756975 -0.19099 0.109669 0.074935 -0.189852 0.110778 0.075631 -0.186023 0.11323 0.0743662 -0.181901 0.119539 0.0707152 -0.181017 0.122198 0.0687122 -0.182114 0.119454 0.0704825 -0.181233 0.122103 0.0685278 -0.187788 0.111726 0.0751617 -0.189855 0.110585 0.0752383 -0.187811 0.111551 0.07478 -0.183801 0.116131 0.072674 -0.183895 0.115984 0.0723562 -0.182242 0.119311 0.0702178 -0.190989 0.110098 0.0750318 -0.18981 0.11025 0.0749619 -0.187728 0.111264 0.074484 -0.186075 0.11307 0.074005 -0.186004 0.112824 0.0736991 -0.182272 0.119127 0.0699493 -0.181445 0.121789 0.0680725 -0.187553 0.110916 0.0743259 -0.183873 0.115777 0.0720584 -0.182201 0.118921 0.0697059 -0.190988 0.110466 0.0765383 -0.189595 0.110299 0.0767324 -0.18301 0.116082 0.0733486 -0.183327 0.116184 0.0732052 -0.181319 0.11951 0.0709913 -0.181422 0.121599 0.0678424 -0.18138 0.121962 0.068308 -0.180369 0.125948 0.0656166 -0.180752 0.12224 0.0688448 -0.181626 0.119559 0.0708911 -0.183603 0.116201 0.07297 -0.185858 0.113279 0.0747253 -0.185605 0.11321 0.0750254 -0.187662 0.111757 0.0755617 -0.187457 0.11164 0.0759092 -0.189799 0.11079 0.0760649 -0.189708 0.110619 0.076457 0.188641 0.110466 -0.0780682 0.187249 0.110299 -0.0782624 0.188641 0.110648 -0.0776674 0.188641 0.11064 -0.0772275 0.188641 0.110444 -0.0768335 0.188643 0.109669 -0.076465 0.187463 0.11025 -0.0764918 0.183259 0.11321 -0.0765553 0.180663 0.116082 -0.0748786 0.180981 0.116184 -0.0747351 0.17928 0.119559 -0.072421 0.178973 0.11951 -0.0725213 0.187362 0.110619 -0.0779869 0.185111 0.11164 -0.0774392 0.181256 0.116201 -0.0744999 0.178406 0.12224 -0.0703747 0.178671 0.122198 -0.0702422 0.177898 0.125976 -0.0671772 0.187453 0.11079 -0.0775948 0.185316 0.111757 -0.0770916 0.183512 0.113279 -0.0762552 0.185441 0.111726 -0.0766916 0.179768 0.119454 -0.0720124 0.179555 0.119539 -0.0722451 0.178887 0.122103 -0.0700577 0.178349 0.125802 -0.0669871 0.187505 0.110778 -0.077161 0.185464 0.111551 -0.0763099 0.183728 0.11307 -0.0755349 0.183677 0.11323 -0.0758961 0.181454 0.116131 -0.0742039 0.178508 0.125662 -0.0668343 0.188642 0.110098 -0.0765618 0.187509 0.110585 -0.0767683 0.183658 0.112824 -0.0752291 0.181549 0.115984 -0.0738861 0.181526 0.115777 -0.0735884 0.179896 0.119311 -0.0717477 0.179926 0.119127 -0.0714793 0.179098 0.121789 -0.0696024 0.179033 0.121962 -0.0698379 0.187377 0.109835 -0.0763845 0.185381 0.111264 -0.0760139 0.181391 0.11554 -0.0733499 0.179855 0.118921 -0.0712358 0.212827 0.109703 -0.076465 0.212827 0.110132 -0.0765618 0.212826 0.110478 -0.0768337 0.212826 0.110674 -0.0772279 0.212826 0.110682 -0.077668 0.200735 0.109692 -0.076465 0.200734 0.110121 -0.0765618 0.200734 0.110467 -0.0768336 0.200734 0.110663 -0.0772277 0.200734 0.110671 -0.0776678 0.200734 0.110489 -0.0780686 0.177627 0.149522 -0.0224322 0.178021 0.131395 -0.0615931 0.178609 0.125498 -0.0666562 0.178643 0.125323 -0.066465 0.177637 0.131451 -0.0616422 0.17802 0.136741 -0.0547766 0.17763 0.145023 -0.0393769 0.177629 0.147318 -0.03254 0.178016 0.147643 -0.0310707 0.177628 0.147713 -0.0310889 0.17814 0.125909 -0.0671041 0.178348 0.131233 -0.0614499 0.178346 0.141101 -0.0472216 0.178018 0.141292 -0.0473232 0.178017 0.144956 -0.0393506 0.178015 0.149452 -0.0224203 0.178345 0.147435 -0.0310162 0.178566 0.130989 -0.0612347 0.178347 0.136563 -0.0546533 0.178566 0.140814 -0.0470684 0.178346 0.144755 -0.0392722 0.178566 0.144451 -0.0391537 0.178566 0.147119 -0.0309336 0.178565 0.148918 -0.0223296 0.178643 0.130701 -0.0609804 0.178566 0.136296 -0.0544677 0.178643 0.140474 -0.0468873 0.178643 0.148537 -0.022265 0.216675 0.111289 -0.0756947 0.218444 0.113137 -0.0747385 0.222858 0.12062 -0.0717777 0.222288 0.119915 -0.0722355 0.222647 0.123278 -0.0685685 0.222827 0.125466 -0.066465 0.222861 0.12564 -0.0666561 0.222961 0.125803 -0.0668342 0.222879 0.123585 -0.0689805 0.223092 0.123685 -0.0691407 0.22335 0.123737 -0.0692519 0.222648 0.123095 -0.0683501 0.222726 0.123446 -0.0687845 0.222014 0.119893 -0.0720636 0.221639 0.119483 -0.0713089 0.220722 0.117322 -0.0727052 0.220723 0.117516 -0.0729924 0.220833 0.11766 -0.0732878 0.221672 0.119665 -0.0715747 0.221802 0.119807 -0.0718354 0.221039 0.117737 -0.0735558 0.221316 0.117738 -0.0737642 0.22083 0.117101 -0.0724607 0.218664 0.11392 -0.0746801 0.219122 0.114312 -0.0759437 0.218267 0.113415 -0.0749508 0.218833 0.113653 -0.07446 0.218609 0.114147 -0.0749862 0.218264 0.113807 -0.0756113 0.218676 0.114301 -0.0753329 0.218856 0.114359 -0.0756687 0.219005 0.113644 -0.0764276 0.216121 0.111682 -0.0762701 0.218204 0.11365 -0.0752574 0.216145 0.111855 -0.076651 0.216274 0.111887 -0.0770485 0.218437 0.113861 -0.0759582 0.218698 0.113804 -0.076245 0.216739 0.111535 -0.0776236 0.21439 0.110406 -0.0764387 0.216383 0.111056 -0.0758111 0.214332 0.110734 -0.0767186 0.216205 0.111399 -0.0759728 0.214405 0.110938 -0.0775399 0.216484 0.111774 -0.0773928 0.214337 0.110923 -0.0771104 0.212826 0.1105 -0.0780687 0.214523 0.110775 -0.0779258 0.214669 0.110466 -0.078195 0.178344 0.149239 -0.0223842 0.178281 0.149847 -0.020002 0.178816 0.149312 -0.0200442 0.178902 0.148938 -0.0200064 0.180187 0.149422 -0.0169267 0.182351 0.150133 -0.0144034 0.182416 0.149767 -0.0144408 0.18271 0.150168 -0.0141287 0.17871 0.149702 -0.0195959 0.179641 0.150325 -0.0167018 0.179914 0.150107 -0.016845 0.180166 0.15016 -0.0164595 0.182008 0.150667 -0.0140369 0.182387 0.150703 -0.0137465 0.182576 0.150483 -0.0139807 0.18512 0.150882 -0.0123051 0.184998 0.150978 -0.0119682 0.181777 0.150762 -0.0137589 0.179902 0.150378 -0.016304 0.178397 0.149918 -0.0195409 0.178032 0.149999 -0.0194513 0.188631 0.15108 -0.0113471 0.185577 0.150901 -0.0121558 0.185671 0.150681 -0.0124389 0.178599 0.149631 -0.0200426 0.178926 0.149383 -0.0196082 0.180105 0.149791 -0.0169237 0.182208 0.150447 -0.0142622 0.180352 0.149844 -0.0165475 0.185228 0.150661 -0.0125836 0.185739 0.150366 -0.0126241 0.185305 0.150347 -0.0127654 0.185343 0.149982 -0.0128254 0.223444 0.149781 -0.0224217 0.223827 0.149856 -0.0224346 0.223444 0.147992 -0.0309088 0.223827 0.147623 -0.03254 0.223444 0.145237 -0.0393393 0.22312 0.149567 -0.0223849 0.22312 0.145036 -0.0392599 0.223444 0.141517 -0.0473582 0.223444 0.137493 -0.0539899 0.22312 0.137313 -0.053868 0.223827 0.137556 -0.0540327 0.223827 0.132255 -0.060926 0.223444 0.132197 -0.0608762 0.223568 0.126117 -0.0671783 0.223327 0.126049 -0.0671045 0.22312 0.132034 -0.0607343 0.22312 0.125942 -0.0669872 0.22312 0.147782 -0.0308538 0.222903 0.147468 -0.0307715 0.22312 0.141326 -0.0472555 0.222903 0.137045 -0.0536855 0.222827 0.14887 -0.022265 0.222827 0.147098 -0.0306744 0.222903 0.144734 -0.039141 0.222827 0.144378 -0.0390008 0.222903 0.141041 -0.0471018 0.222827 0.140704 -0.0469205 0.222827 0.136729 -0.0534702 0.222903 0.131788 -0.0605219 0.188633 0.150921 -0.0118117 0.188632 0.150982 -0.0117039 0.200729 0.151041 -0.0118119 0.200731 0.15068 -0.0121444 0.188635 0.150761 -0.0120006 0.188637 0.150559 -0.0121444 0.188639 0.150447 -0.0121965 0.188643 0.150083 -0.012265 0.212826 0.150736 -0.0121445 0.212825 0.150938 -0.0120008 0.21499 0.150243 -0.0125016 0.212827 0.150261 -0.012265 0.212825 0.151098 -0.011812 0.215204 0.15124 -0.0116102 0.215125 0.151141 -0.0119578 0.215595 0.151132 -0.0120739 0.21569 0.15123 -0.0117303 0.218426 0.151019 -0.01331 0.219055 0.15109 -0.0132964 0.221107 0.150761 -0.0156985 0.221393 0.150857 -0.0154795 0.218848 0.150992 -0.0135877 0.220861 0.150542 -0.0158713 0.215058 0.15092 -0.0122463 0.21501 0.150607 -0.0124362 0.215513 0.150911 -0.0123587 0.215456 0.150597 -0.012546 0.21826 0.150798 -0.0135564 0.218144 0.150485 -0.0137149 0.21867 0.150771 -0.0138256 0.218545 0.150458 -0.0139775 0.220689 0.150228 -0.0159737 0.220916 0.149812 -0.0163856 0.220993 0.150177 -0.0163732 0.218489 0.150094 -0.0140226 0.218092 0.150122 -0.0137635 0.215431 0.150234 -0.01261 0.223204 0.150434 -0.0187578 0.221427 0.150711 -0.0161209 0.221172 0.150491 -0.0162806 0.222853 0.150346 -0.0188687 0.222552 0.150128 -0.0189435 0.221488 0.149693 -0.0172665 0.222345 0.149812 -0.0189714 0.222261 0.149444 -0.0189486 0.222701 0.150058 -0.0194104 0.223007 0.150275 -0.0193506 0.222491 0.149742 -0.0194271 0.222903 0.149248 -0.0223299 0.179404 0.149193 0.0169092 0.180561 0.149502 0.0148466 0.188631 0.15108 0.00981718 0.186283 0.151028 0.0100723 0.188633 0.150921 0.0102817 0.188637 0.150559 0.0106144 0.188632 0.150982 0.0101739 0.183051 0.150758 0.0117684 0.182857 0.150853 0.0114653 0.182622 0.150723 0.0120493 0.186362 0.15093 0.0104211 0.185885 0.150914 0.0105379 0.182804 0.150503 0.0122887 0.186433 0.15071 0.0107104 0.186484 0.150395 0.0109005 0.186031 0.150379 0.011011 0.185969 0.150693 0.0108237 0.18322 0.150538 0.0120165 0.183397 0.149858 0.0122219 0.183341 0.150223 0.012175 0.18651 0.150031 0.0109652 0.180786 0.149925 0.0144351 0.18061 0.15024 0.0143326 0.182934 0.150189 0.0124406 0.180359 0.150459 0.0141582 0.18007 0.150551 0.0139364 0.180298 0.150185 0.0147435 0.180037 0.150404 0.0145821 0.179212 0.149113 0.0174111 0.179126 0.149485 0.0174351 0.180481 0.149869 0.014836 0.178608 0.15002 0.0173307 0.178252 0.150104 0.0172176 0.179736 0.150495 0.0143747 0.178978 0.149413 0.0178949 0.178763 0.149731 0.0178781 0.178914 0.149803 0.017407 0.178643 0.148537 0.020735 0.178565 0.148918 0.0207997 0.178015 0.149452 0.0208904 0.178452 0.149947 0.017817 0.212826 0.150624 0.0106666 0.200727 0.1512 0.00981762 0.200729 0.151041 0.010282 0.188635 0.150761 0.0104706 0.188639 0.150447 0.0106666 0.200731 0.15068 0.0106145 0.178344 0.149239 0.0208543 0.178016 0.147694 0.029346 0.177628 0.147764 0.029364 0.177629 0.147221 0.031351 0.177632 0.141335 0.0458684 0.178018 0.14127 0.045834 0.177636 0.132079 0.0593915 0.178021 0.132023 0.0593431 0.177638 0.125999 0.0656716 0.178023 0.125948 0.0656166 0.178345 0.147485 0.029292 0.178017 0.144965 0.0377985 0.178346 0.14108 0.0457323 0.17802 0.137284 0.0524528 0.178347 0.137105 0.0523318 0.178348 0.131859 0.059202 0.178349 0.125802 0.0654571 0.178346 0.144764 0.0377201 0.178566 0.140792 0.045579 0.178566 0.136836 0.0521497 0.178566 0.147169 0.0292103 0.178643 0.146796 0.0291136 0.178566 0.14446 0.0376017 0.178566 0.131612 0.0589899 0.178643 0.136517 0.0519344 0.178567 0.125582 0.0652177 0.178643 0.125323 0.064935 0.223444 0.149781 0.0208917 0.222903 0.149248 0.0207999 0.222648 0.149646 0.0184966 0.222539 0.149715 0.0180659 0.221488 0.149693 0.0157359 0.221278 0.149741 0.0153898 0.221033 0.149791 0.0150204 0.219051 0.150049 0.0129083 0.218695 0.150079 0.0126377 0.223538 0.150264 0.0183822 0.223418 0.150335 0.0179109 0.223058 0.150249 0.0179992 0.222123 0.150733 0.0149785 0.221853 0.150783 0.0145689 0.221552 0.150689 0.0147676 0.219673 0.151044 0.0122273 0.219281 0.151074 0.0119273 0.215984 0.151223 0.0102847 0.223173 0.150179 0.0184547 0.221812 0.15064 0.0151637 0.221545 0.150421 0.0153058 0.221292 0.15047 0.0149219 0.219446 0.150946 0.0125033 0.219067 0.150976 0.0122132 0.218882 0.150755 0.0124463 0.216333 0.151112 0.0107737 0.21623 0.150891 0.0110514 0.215879 0.151125 0.0106254 0.212824 0.151257 0.00981782 0.212825 0.151098 0.0102821 0.212825 0.150938 0.0104708 0.222861 0.149963 0.0184947 0.22275 0.150032 0.0180534 0.221358 0.150106 0.0153848 0.221111 0.150156 0.0150102 0.21925 0.150726 0.0127274 0.219112 0.150412 0.0128689 0.216157 0.150578 0.0112333 0.215789 0.150904 0.0109078 0.212826 0.150736 0.0106145 0.217827 0.150138 0.012075 0.218752 0.150442 0.0125946 0.215726 0.15059 0.0110931 0.177839 0.123594 0.0677868 0.17812 0.123596 0.0677339 0.178592 0.123444 0.0674628 0.178825 0.12295 0.066832 0.179186 0.119796 0.0707179 0.178378 0.123544 0.0676229 0.179461 0.119774 0.0705459 0.178746 0.123304 0.0672666 0.179804 0.119545 0.0700567 0.178825 0.123135 0.0670505 0.179982 0.118577 0.0699329 0.179771 0.119158 0.069548 0.182792 0.114236 0.0738025 0.180747 0.117427 0.0714626 0.180748 0.117232 0.0711757 0.18246 0.113585 0.0748953 0.182346 0.114246 0.0744133 0.183028 0.113802 0.0744258 0.182612 0.114294 0.0741382 0.18286 0.114082 0.073456 0.183202 0.113748 0.0740789 0.17888 0.11975 0.0708153 0.180153 0.117649 0.0722341 0.18043 0.117649 0.0720257 0.179674 0.119688 0.0703175 0.180636 0.117572 0.0717578 0.179838 0.119363 0.0697908 0.180641 0.117011 0.0709315 0.182806 0.113853 0.0731502 0.183024 0.113077 0.073207 0.182637 0.113585 0.0729305 0.185262 0.111351 0.0744419 0.187135 0.110695 0.075188 0.187129 0.110884 0.0755796 0.188641 0.110648 0.0761375 0.187061 0.110899 0.076009 0.186943 0.110736 0.076395 0.182768 0.113745 0.0747125 0.184982 0.111727 0.0758615 0.185192 0.111841 0.0755171 0.185321 0.111808 0.0751196 0.183262 0.113591 0.0737253 0.185345 0.111635 0.074739 0.1832 0.113355 0.073419 0.187077 0.110366 0.0749083 0.186967 0.109961 0.0747936 0.223444 0.147951 0.0295332 0.223444 0.126088 0.0656173 0.222861 0.12564 0.0651262 0.223444 0.131564 0.0600682 0.223827 0.137011 0.0532926 0.223444 0.136948 0.0532489 0.223444 0.141537 0.0457924 0.223827 0.147525 0.031351 0.223827 0.148025 0.0295527 0.22312 0.131402 0.0599242 0.22312 0.136771 0.0531247 0.223444 0.145239 0.0378042 0.22312 0.149567 0.020855 0.222903 0.131159 0.0597087 0.22312 0.141346 0.0456898 0.222903 0.14106 0.0455363 0.222903 0.144736 0.0376059 0.22312 0.145038 0.0377247 0.22312 0.147741 0.0294778 0.222903 0.147428 0.0293948 0.222903 0.136505 0.0529388 0.222827 0.136191 0.0527195 0.222827 0.14438 0.0374657 0.200734 0.110121 0.0750319 0.188642 0.110098 0.0750318 0.200734 0.110467 0.0753037 0.188641 0.110444 0.0753035 0.188641 0.11064 0.0756975 0.188641 0.110466 0.0765383 0.200734 0.110153 0.0768225 0.212826 0.110682 0.076138 0.200734 0.110663 0.0756978 0.200734 0.110671 0.0761378 0.200734 0.110489 0.0765386 0.212827 0.110164 0.0768226 0.212827 0.110132 0.0750319 0.212826 0.110674 0.0756979 0.213938 0.11081 0.0756344 0.215998 0.111753 0.0751723 0.217923 0.113303 0.0747453 0.217759 0.113254 0.0743853 0.22001 0.116202 0.0726789 0.222582 0.122221 0.0685279 0.212826 0.110478 0.0753038 0.219916 0.116055 0.0723608 0.221694 0.119537 0.0704947 0.213935 0.110618 0.0752415 0.215975 0.111579 0.0747902 0.217708 0.113094 0.0740235 0.219939 0.115849 0.0720627 0.221567 0.119395 0.0702295 0.212827 0.109703 0.074935 0.213981 0.110282 0.074965 0.216059 0.111292 0.0744941 0.21778 0.112849 0.0737174 0.221537 0.119212 0.0699607 0.221609 0.119007 0.0697169 0.214191 0.11033 0.0767365 0.216327 0.111667 0.0759211 0.218476 0.113057 0.0752401 0.218176 0.113234 0.0750462 0.220483 0.116255 0.0732104 0.222181 0.119641 0.0709042 0.223061 0.122358 0.0688454 0.223352 0.122343 0.0689147 0.223827 0.12614 0.0656735 0.222395 0.121719 0.0678421 0.222903 0.125724 0.0652177 0.222372 0.121908 0.0680723 0.222436 0.122081 0.0683079 0.22312 0.125942 0.0654572 0.222797 0.122316 0.0687126 0.221906 0.119622 0.0707278 0.220207 0.116272 0.0729751 0.216122 0.111784 0.0755729 0.21399 0.110821 0.0760686 0.21408 0.11065 0.076461 0.212826 0.1105 0.0765388 -0.133447 0.137237 -0.048082 -0.141756 0.139152 -0.0412432 -0.0646103 0.14139 -0.0309241 -0.0646103 0.142936 -0.0309241 -0.0646163 0.13905 -0.0384988 -0.0733152 0.134706 -0.0480702 -0.0728246 0.134745 -0.0479936 -0.0715755 0.136612 -0.0476828 -0.0699967 0.135254 -0.0470265 -0.234273 0.123663 -0.0660679 -0.234271 0.131128 -0.0560192 -0.234271 0.129998 -0.0574047 -0.234273 0.137537 -0.0494356 -0.234271 0.13662 -0.0480476 -0.23427 0.141264 -0.0386998 -0.23427 0.140681 -0.0400854 -0.23427 0.143579 -0.032112 -0.234273 0.148416 -0.0147946 -0.23427 0.146905 -0.0147917 -0.234271 0.14766 -0.00405778 -0.234273 0.149116 -0.00544151 -0.234273 0.149116 0.00391157 -0.234274 0.147057 0.0118798 -0.234275 0.145976 0.0198448 -0.234275 0.145866 0.0204872 -0.234275 0.145734 0.0212305 -0.234273 0.147265 0.0211876 -0.234274 0.14397 0.0292003 -0.234273 0.142314 0.0385526 -0.234274 0.141265 0.0371661 -0.234274 0.135775 0.0479061 -0.234274 0.136617 0.0465205 -0.234273 0.131941 0.0558731 -0.234274 0.13113 0.0544868 -0.234273 0.112354 0.0727564 -0.234274 0.111002 0.0718076 -0.132245 0.137171 -0.0481544 -0.127892 0.137079 -0.0481544 -0.114454 0.135111 -0.0481544 -0.100292 0.134903 -0.0481544 -0.0978923 0.134873 -0.0481544 -0.0944541 0.136546 -0.0481544 -0.0902923 0.136501 -0.0481544 -0.0878923 0.136478 -0.0481544 -0.0820541 0.134716 -0.0481544 -0.0802923 0.136413 -0.0481544 -0.0778923 0.134686 -0.0481544 0.231927 0.111001 0.071808 0.231926 0.120542 0.0652253 0.231923 0.135777 0.0479023 0.231927 0.138356 0.04652 0.231921 0.143972 0.0291933 0.231919 0.145974 0.0198532 0.231927 0.147497 0.0198464 0.231927 0.14916 -0.00405587 0.231927 0.149116 -0.00544151 0.231918 0.14766 -0.00406371 0.231918 0.147615 -0.00544934 0.231927 0.148564 -0.0134089 0.231927 0.147257 -0.022762 0.231919 0.145732 -0.0227689 0.23192 0.143976 -0.0307233 0.231927 0.145528 -0.0307295 0.231923 0.135778 -0.0494319 0.231927 0.137537 -0.0494356 0.231927 0.133033 -0.0560174 0.231927 0.131941 -0.057403 0.231924 0.129997 -0.0574056 0.231927 0.122875 -0.0667561 0.231927 0.112651 -0.0741106 0.231927 0.111 -0.0733382 -0.116773 0.14593 -0.0182076 -0.0967732 0.145507 -0.0182072 -0.0867732 0.143844 -0.0182072 -0.125573 0.144653 -0.0182072 -0.125573 0.145932 -0.0182072 -0.140726 0.145935 -0.0229077 0.238674 0.081116 -0.028059 0.228674 0.0738523 -0.0294446 0.228674 0.0664722 -0.0289803 0.238674 0.048134 -0.0173425 0.228674 0.048134 -0.0173425 0.238674 0.0445716 -0.0108625 0.228674 0.0445716 -0.0108625 0.238674 0.0427326 -0.00370019 0.228674 0.0427326 -0.00370019 0.238674 0.048134 0.0173368 0.228674 0.0445716 0.0108568 0.228674 0.0531959 0.0227273 0.238674 0.0531959 0.0227273 0.228674 0.0594395 0.0266895 0.228674 0.0664722 0.0289746 0.238674 0.081116 0.0280533 0.228674 0.0878069 0.0249048 0.238674 0.097851 0.0142089 0.228674 0.100573 0.00733349 0.238674 0.1015 -2.85742e-06 0.238674 0.100573 -0.00733921 0.238674 0.097851 -0.0142146 0.228674 0.100573 -0.00733921 0.238674 0.0878069 -0.0249105 0.190674 0.0992977 0.0354543 0.185974 0.0988402 0.0349968 0.190674 0.0988402 0.0349968 0.190674 0.0982152 0.0348293 0.190674 0.0975902 0.0349968 0.185974 0.0982152 0.0348293 0.185974 0.0975902 0.0349968 0.190674 0.0971326 0.0354543 0.190674 0.0969652 0.0360793 0.190674 0.07325 0.0445971 0.190674 0.0730825 0.0439721 0.190674 0.072625 0.0435146 0.185974 0.0730825 0.0439721 0.185974 0.072625 0.0435146 0.190674 0.071375 0.0435146 0.185974 0.071375 0.0435146 0.190674 0.0709174 0.0439721 0.185974 0.0709174 0.0439721 0.190674 0.072 0.0433471 0.190674 0.0468673 0.0354543 0.190674 0.0464097 0.0349968 0.185974 0.0464097 0.0349968 0.190674 0.0457847 0.0348293 0.185974 0.0457847 0.0348293 0.190674 0.0447022 0.0354543 0.185974 0.0447022 0.0354543 0.190674 0.0445347 0.0360793 0.191425 0.0457847 0.0360793 0.190674 0.0470347 0.0360793 0.190674 0.0451597 0.0349968 0.185974 0.0306654 0.0131543 0.190674 0.0295828 0.0125293 0.190674 0.0289578 0.0126968 0.185974 0.0289578 0.0126968 0.190674 0.0283328 0.0137793 0.185974 0.0283328 0.0137793 0.191425 0.0295828 0.0137793 0.190674 0.0302078 0.0126968 0.190674 0.0306654 0.0131543 0.190674 0.0285003 0.0131543 0.190674 0.0308328 -0.013785 0.185974 0.0306654 -0.01441 0.190674 0.0295828 -0.015035 0.185974 0.0289578 -0.0148675 0.190674 0.0302078 -0.0148675 0.190674 0.0306654 -0.01441 0.191425 0.0295828 -0.013785 0.190674 0.0285003 -0.01441 0.190674 0.0289578 -0.0148675 0.185974 0.0468673 -0.03671 0.190674 0.0468673 -0.03671 0.190674 0.0457847 -0.037335 0.190674 0.0451597 -0.0371675 0.185974 0.0451597 -0.0371675 0.190674 0.0447022 -0.03671 0.191425 0.0457847 -0.036085 0.190674 0.0464097 -0.0371675 0.190674 0.0445347 -0.036085 0.190674 0.07325 -0.0446029 0.190674 0.0730825 -0.0452279 0.190674 0.072625 -0.0456854 0.190674 0.072 -0.0458529 0.185974 0.072 -0.0458529 0.191425 0.072 -0.0446029 0.190674 0.0709174 -0.0452279 0.190674 0.071375 -0.0456854 0.185974 0.0994652 -0.036085 0.185974 0.0992977 -0.03671 0.190674 0.0988402 -0.0371675 0.185974 0.0988402 -0.0371675 0.185974 0.0982152 -0.037335 0.190674 0.0975902 -0.0371675 0.190674 0.0971326 -0.03671 0.185974 0.0971326 -0.03671 0.190674 0.0982152 -0.037335 0.190674 0.0992977 -0.03671 0.190674 0.115042 -0.0148675 0.185974 0.115042 -0.0148675 0.190674 0.114417 -0.015035 0.190674 0.113792 -0.0148675 0.185974 0.113792 -0.0148675 0.190674 0.1155 -0.01441 0.190674 0.113335 -0.01441 0.190674 0.113167 -0.013785 0.185974 0.1155 0.0131543 0.190674 0.115042 0.0126968 0.185974 0.115042 0.0126968 0.190674 0.113792 0.0126968 0.185974 0.114417 0.0125293 0.190674 0.113167 0.0137793 0.190674 0.1155 0.0131543 0.191425 0.114417 0.0137793 0.190674 0.113335 0.0131543 0.190674 0.114417 0.0125293 0.229764 0.00508423 0.0104543 0.229768 0.00508667 0.0104002 0.229783 0.00512408 0.0103704 0.23021 0.00621378 0.0097386 0.229745 0.00504449 0.0105382 0.229748 0.00504433 0.0104879 0.230628 0.00728543 0.00911713 0.232756 0.0133036 0.00979183 0.232756 0.012492 -2.85742e-06 0.232756 0.0126952 0.00491127 0.229745 0.00789232 0.0220053 0.229777 0.00774487 0.0212978 0.229765 0.00770099 0.0212709 0.229785 0.00774352 0.0212214 0.231361 0.0116783 0.0193188 0.231411 0.011777 0.019182 0.23174 0.0123394 0.0179401 0.231809 0.0124184 0.0175391 0.231769 0.0114721 0.0144078 0.231911 0.012127 0.015425 0.232756 0.0143129 0.0146055 0.231908 0.0124406 0.0166329 0.231499 0.0105341 0.0136423 0.231119 0.00936987 0.0131993 0.229745 0.00514424 0.0111534 0.230659 0.00807158 0.013161 0.230492 0.00762112 0.0132532 0.229777 0.00570309 0.0136778 0.231809 0.0291718 0.0449797 0.232756 0.0316963 0.0437786 0.23174 0.0293038 0.0453665 0.231911 0.0278623 0.0432945 0.231769 0.0267866 0.042741 0.232756 0.0282185 0.0403008 0.230659 0.0232183 0.0433616 0.230492 0.0228743 0.0436666 0.229777 0.0214255 0.0449934 0.229745 0.0185119 0.0416286 0.229745 0.0213063 0.0449894 0.229777 0.0270037 0.0505716 0.232756 0.0354494 0.0469573 0.231411 0.0294378 0.0467232 0.231499 0.0530841 0.0600507 0.232756 0.0480959 0.054493 0.231769 0.054216 0.0596211 0.232756 0.0526777 0.0562808 0.231929 0.0560168 0.059674 0.229777 0.0506993 0.0642522 0.229765 0.0507261 0.0642961 0.22975 0.0506621 0.0643161 0.229765 0.0582741 0.0663186 0.230492 0.0587439 0.064376 0.229745 0.0664027 0.0675458 0.229777 0.0583193 0.066294 0.231411 0.0585031 0.0617442 0.232756 0.0622053 0.0586935 0.231361 0.0585722 0.0618981 0.23174 0.0577087 0.0606362 0.232756 0.0817946 0.0586935 0.230659 0.0851638 0.0639255 0.230492 0.085256 0.064376 0.229777 0.0856806 0.066294 0.229745 0.0856175 0.0663953 0.229777 0.0933006 0.0642522 0.229745 0.0934059 0.0643084 0.229765 0.0932738 0.0642961 0.229785 0.0932242 0.0642536 0.230492 0.0927093 0.0623789 0.231411 0.0911848 0.0602201 0.232756 0.0913222 0.0562808 0.231707 0.0901044 0.0597023 0.232756 0.0866083 0.0576842 0.231929 0.0879965 0.0596704 0.231769 0.0864106 0.060525 0.229777 0.116996 0.0505716 0.22975 0.117033 0.0506357 0.230659 0.115364 0.0487788 0.229745 0.109768 0.0562797 0.229785 0.117036 0.0505061 0.229745 0.122694 0.0449894 0.229777 0.122574 0.0449934 0.229765 0.122573 0.0450448 0.229808 0.122455 0.0449971 0.231361 0.118894 0.0425764 0.231769 0.114744 0.0452105 0.232756 0.108551 0.0469573 0.231809 0.116982 0.0428253 0.231908 0.116187 0.0432592 0.231929 0.11569 0.0436774 0.231811 0.114833 0.0449685 0.232756 0.128284 0.0193194 0.229777 0.138297 0.0136778 0.22975 0.138371 0.0136776 0.229808 0.138196 0.0137406 0.230492 0.136379 0.0132532 0.230965 0.135076 0.0131358 0.231361 0.133901 0.0134249 0.232756 0.129687 0.0146055 0.23174 0.132639 0.0142884 0.231707 0.132758 0.0141708 0.231908 0.131898 0.0153698 0.231929 0.131677 0.0159803 0.229765 0.136299 0.021271 0.230492 0.134382 0.0207065 0.229808 0.136199 0.0211927 0.229745 0.136311 0.021403 0.229777 0.136255 0.0212978 0.232756 0.131305 0.00491127 0.231383 0.135013 0.0058079 0.23113 0.135485 0.0079004 0.229745 0.138856 0.0111534 0.230836 0.13619 0.00874253 0.23021 0.137786 0.0097386 0.229764 0.138916 0.0104543 0.229768 0.138913 0.0104002 0.230659 0.133945 0.0205611 0.229745 0.136108 0.0220053 0.232756 0.126496 0.0239012 0.229745 0.132849 0.0298552 0.232756 0.121818 0.0325449 0.231119 0.114748 0.0476353 0.232756 0.100323 0.0523328 0.229745 0.101858 0.0608465 0.232756 0.0769141 0.0593019 0.231119 0.0852021 0.0626272 0.229745 0.0775972 0.0675458 0.232756 0.072 0.0595051 0.229745 0.0674331 0.0676233 0.232756 0.0670858 0.0593019 0.231119 0.0521183 0.0608374 0.232756 0.0436773 0.0523328 0.232756 0.0394522 0.0498152 0.229745 0.0349277 0.0567404 0.229745 0.0342319 0.0562797 0.229808 0.027 0.0504524 0.229745 0.0157174 0.0377652 0.232756 0.0196643 0.0283198 0.229745 0.0123891 0.0322569 0.232756 0.0157163 0.0193194 0.229808 0.00780119 0.0211927 0.230674 0.016806 -0.0103204 0.233274 0.016806 -0.0103204 0.230674 0.0196416 -0.0202866 0.230674 0.0242603 -0.029562 0.230674 0.0305046 -0.0378309 0.233274 0.0242603 -0.029562 0.233274 0.0305046 -0.0378309 0.230674 0.038162 -0.0448115 0.230674 0.0469717 -0.0502663 0.233274 0.0469717 -0.0502663 0.230674 0.0668191 -0.0559133 0.233274 0.0566338 -0.0540094 0.230674 0.0771808 -0.0559133 0.233274 0.0873661 -0.0540094 0.233274 0.0970282 -0.0502663 0.230674 0.11974 -0.029562 0.233274 0.11974 -0.029562 0.233274 0.124358 -0.0202866 0.230674 0.127194 -0.0103204 0.236674 0.0196416 -0.0202866 0.236674 0.0242603 -0.029562 0.236074 0.038162 -0.0448115 0.236674 0.0305046 -0.0378309 0.236674 0.038162 -0.0448115 0.236674 0.0469717 -0.0502663 0.236674 0.0668191 -0.0559133 0.236074 0.0771808 -0.0559133 0.236674 0.0771808 -0.0559133 0.236074 0.0873661 -0.0540094 0.236074 0.0970282 -0.0502663 0.236674 0.0970282 -0.0502663 0.236674 0.124358 -0.0202866 0.236074 0.127194 -0.0103204 0.236674 0.127194 -0.0103204 0.228874 0.0258 -2.85742e-06 0.228874 0.0293167 -0.0176828 0.230474 0.0335861 -0.0256702 0.228874 0.0335861 -0.0256702 0.230474 0.0393316 -0.0326712 0.228874 0.0463326 -0.0384168 0.230474 0.0463326 -0.0384168 0.230474 0.05432 -0.0426861 0.228874 0.0629868 -0.0453151 0.228874 0.072 -0.0462029 0.230474 0.0629868 -0.0453151 0.230474 0.072 -0.0462029 0.230474 0.0810131 -0.0453151 0.230474 0.0896799 -0.0426861 0.228874 0.0976673 -0.0384168 0.228874 0.104668 -0.0326712 0.230474 0.104668 -0.0326712 0.230474 0.114683 -0.0176828 0.228874 0.117312 -0.00901603 0.230474 0.1182 -2.85742e-06 0.237674 0.014044 0.0102163 0.233696 0.01315 -2.85742e-06 0.237674 0.016699 0.020125 0.233696 0.016699 0.020125 0.233696 0.014044 0.0102163 0.237674 0.0210344 0.0294221 0.233696 0.0287026 0.0398552 0.237674 0.0269182 0.0378252 0.233696 0.0269182 0.0378252 0.233696 0.0398121 0.0492644 0.233696 0.0358535 0.0464381 0.233696 0.0528914 0.0556585 0.233696 0.0483602 0.0538904 0.233696 0.0439905 0.0517542 0.237674 0.042575 0.0509627 0.233696 0.0575531 0.0570463 0.237674 0.072 0.0588471 0.233696 0.0623136 0.0580445 0.233696 0.0617808 0.0579531 0.233696 0.0816863 0.0580445 0.237674 0.0921278 0.0552981 0.237674 0.101425 0.0509627 0.233696 0.104188 0.0492644 0.237674 0.109828 0.0450789 0.233696 0.121267 0.032185 0.237674 0.117082 0.0378252 0.233696 0.129956 0.0102163 0.237674 0.127301 0.020125 0.237674 0.129956 0.0102163 0.236874 0.0220736 -0.0288279 0.236874 0.0278375 -0.0370596 0.237674 0.0278375 -0.0370596 0.236874 0.043175 -0.0499292 0.236874 0.0522825 -0.0541761 0.237674 0.0522825 -0.0541761 0.237674 0.072 -0.0576529 0.236874 0.0820108 -0.056777 0.237674 0.0820108 -0.056777 0.237674 0.100825 -0.0499292 0.236874 0.116162 -0.0370596 0.236874 0.121926 -0.0288279 0.237674 0.116162 -0.0370596 0.237674 0.126173 -0.0197203 0.236874 0.126173 -0.0197203 0.237674 0.128774 -0.0100137 0.230674 0.0223598 0.00927649 0.236674 0.0249101 0.0182398 0.230674 0.0249101 0.0182398 0.230674 0.03468 0.0340188 0.230674 0.0494902 0.0452029 0.236674 0.05818 0.0485693 0.230674 0.05818 0.0485693 0.236674 0.0673404 0.0502817 0.230674 0.0673404 0.0502817 0.230674 0.0766595 0.0502817 0.236674 0.102433 0.040297 0.236674 0.10932 0.0340188 0.236674 0.11909 0.0182398 0.236674 0.12164 0.00927649 0.236674 0.1225 -2.85742e-06 0.236974 0.0221412 -2.85742e-06 0.238274 0.0221412 -2.85742e-06 0.236974 0.0230992 0.0097241 0.238274 0.0230992 0.0097241 0.236974 0.0259365 0.0190773 0.238274 0.0305439 0.0276972 0.238274 0.0367445 0.0352526 0.236974 0.0305439 0.0276972 0.238274 0.0529198 0.0460606 0.238274 0.062273 0.0488979 0.236974 0.062273 0.0488979 0.238274 0.072 0.0498559 0.236974 0.072 0.0498559 0.236974 0.0910801 0.0460606 0.238274 0.0997 0.0414532 0.236974 0.113456 0.0276972 0.238274 0.113456 0.0276972 0.236974 0.118063 0.0190773 0.238274 0.118063 0.0190773 0.236974 0.120901 0.0097241 0.230674 0.024 -2.85742e-06 0.238174 0.024 -2.85742e-06 0.230674 0.0249223 -0.00936719 0.238174 0.0249223 -0.00936719 0.238174 0.0276537 -0.0183717 0.230674 0.0320894 -0.0266702 0.230674 0.0380588 -0.033944 0.230674 0.0536312 -0.0443491 0.238174 0.0453326 -0.0399134 0.238174 0.072 -0.0480029 0.230674 0.0903688 -0.0443491 0.238174 0.0903688 -0.0443491 0.230674 0.11191 -0.0266702 0.238174 0.11191 -0.0266702 0.230674 0.119078 -0.00936719 0.238174 0.12 -2.85742e-06 0.233696 0.013351 -0.00486265 0.233696 0.0139526 -0.00968925 0.233696 0.014044 -0.0102221 0.233696 0.0149508 -0.0144497 0.2333 0.0148715 -0.0144698 0.233696 0.0163386 -0.0191114 0.233696 0.016699 -0.0201307 0.233696 0.0181067 -0.0236426 0.233696 0.0202429 -0.0280124 0.233696 0.0210344 -0.0294279 0.233696 0.0287026 -0.0398609 0.233696 0.0341719 -0.0450846 0.233696 0.0358535 -0.0464438 0.2333 0.0358033 -0.0465083 0.233696 0.042575 -0.0509685 0.233696 0.0439905 -0.0517599 0.233696 0.0483602 -0.0538961 0.2333 0.0483273 -0.053971 0.233696 0.0518721 -0.0553038 0.233696 0.0617808 -0.0579588 0.2333 0.0575331 -0.0571313 0.233696 0.0623136 -0.0580502 0.2333 0.0623001 -0.0581309 0.233696 0.0671402 -0.0586519 0.233696 0.072 -0.0588529 0.233696 0.0816863 -0.0580502 0.2333 0.0816998 -0.0581309 0.233696 0.0911085 -0.0556642 0.2333 0.0864669 -0.0571313 0.2333 0.0911351 -0.0557416 0.233696 0.0921278 -0.0553038 0.2333 0.0956726 -0.053971 0.233696 0.100009 -0.0517599 0.2333 0.100048 -0.0518318 0.233696 0.101425 -0.0509685 0.233696 0.108146 -0.0464438 0.2333 0.111913 -0.0433604 0.233696 0.111858 -0.0433002 0.233696 0.115297 -0.0398609 0.233696 0.117082 -0.0378309 0.233696 0.118441 -0.0361493 0.233696 0.121267 -0.0321908 0.2333 0.121336 -0.0322355 0.2333 0.123829 -0.0280513 0.233696 0.122966 -0.0294279 0.233696 0.123757 -0.0280124 0.2333 0.125968 -0.0236755 0.232968 0.0128362 -2.85742e-06 0.232968 0.0130383 -0.00488856 0.232968 0.0160419 -0.0192133 0.232968 0.0178194 -0.0237687 0.232756 0.0221819 -0.0325506 0.232968 0.0253114 -0.036342 0.232756 0.0282185 -0.0403065 0.232968 0.0319294 -0.043531 0.232968 0.0356608 -0.0466914 0.232756 0.0354494 -0.046963 0.232968 0.0396404 -0.0495328 0.232756 0.0480959 -0.0544987 0.232756 0.0573916 -0.0576899 0.232968 0.0574761 -0.0573562 0.232756 0.072 -0.0595108 0.232968 0.0768857 -0.0589645 0.232968 0.081738 -0.0583597 0.232968 0.0865238 -0.0573562 0.232756 0.0866083 -0.0576899 0.232968 0.0912104 -0.055961 0.232968 0.0957658 -0.0541834 0.232968 0.100159 -0.0520358 0.232756 0.100323 -0.0523386 0.232968 0.108339 -0.0466914 0.232756 0.108551 -0.046963 0.232968 0.11207 -0.043531 0.232968 0.115528 -0.0400734 0.232756 0.11896 -0.0365534 0.232968 0.12153 -0.0323624 0.232756 0.121818 -0.0325506 0.232756 0.124336 -0.0283255 0.232756 0.126496 -0.0239069 0.232968 0.126181 -0.0237687 0.232968 0.127958 -0.0192133 0.232968 0.129353 -0.0145267 0.232756 0.129687 -0.0146112 0.2333 0.0130682 -2.85742e-06 0.2333 0.0132695 -0.00486941 0.2333 0.0138719 -0.00970271 0.232968 0.0136431 -0.00974089 0.232968 0.0146466 -0.0145267 0.2333 0.0162613 -0.019138 0.2333 0.0180318 -0.0236755 0.2333 0.020171 -0.0280513 0.232968 0.019967 -0.0281617 0.2333 0.0226642 -0.0322355 0.232968 0.02247 -0.0323624 0.2333 0.0254945 -0.0361995 0.2333 0.0286424 -0.0399163 0.232968 0.0284718 -0.0400734 0.2333 0.0320865 -0.0433604 0.2333 0.0397673 -0.0493386 0.232968 0.0438411 -0.0520358 0.2333 0.0439515 -0.0518318 0.232968 0.0482341 -0.0541834 0.2333 0.0528648 -0.0557416 0.232968 0.0527895 -0.055961 0.232968 0.0622619 -0.0583597 0.2333 0.0671334 -0.0587334 0.232968 0.0671143 -0.0589645 0.2333 0.072 -0.0589346 0.232968 0.072 -0.0591666 0.2333 0.0768665 -0.0587334 0.2333 0.104233 -0.0493386 0.232968 0.104359 -0.0495328 0.2333 0.108197 -0.0465083 0.2333 0.115357 -0.0399163 0.232968 0.118688 -0.036342 0.2333 0.118505 -0.0361995 0.232968 0.124033 -0.0281617 0.2333 0.127739 -0.019138 0.2333 0.129128 -0.0144698 0.233696 0.127661 -0.0191114 0.233696 0.129956 -0.0102221 0.2333 0.130128 -0.00970271 0.232968 0.130357 -0.00974089 0.2333 0.13073 -0.00486941 0.232756 0.131305 -0.00491699 0.232756 0.131508 -2.85742e-06 0.232968 0.130962 -0.00488856 0.233696 0.13085 -2.85742e-06 0.233774 0.0152258 -0.0100137 0.235574 0.0152258 -0.0100137 0.235574 0.0161611 -0.0143398 0.233774 0.0178267 -0.0197203 0.233774 0.0183983 -0.0212252 0.235574 0.0183983 -0.0212252 0.235574 0.0253601 -0.0338887 0.233774 0.0278375 -0.0370596 0.235574 0.0278375 -0.0370596 0.233774 0.0299749 -0.039467 0.235574 0.0299749 -0.039467 0.235574 0.0349433 -0.0441653 0.235574 0.0352525 -0.0444229 0.235574 0.0411095 -0.0486784 0.235574 0.043175 -0.0499292 0.235574 0.0474538 -0.0521661 0.233774 0.0522825 -0.0541761 0.233774 0.0541851 -0.0548313 0.233774 0.0611974 -0.0566317 0.235574 0.0541851 -0.0548313 0.235574 0.0611974 -0.0566317 0.233774 0.072 -0.0576529 0.235574 0.0683801 -0.0575391 0.235574 0.072 -0.0576529 0.233774 0.0820108 -0.056777 0.235574 0.0820108 -0.056777 0.233774 0.0898148 -0.0548313 0.235574 0.0898148 -0.0548313 0.233774 0.0917174 -0.0541761 0.233774 0.0965461 -0.0521661 0.235574 0.100825 -0.0499292 0.233774 0.109057 -0.0441653 0.233774 0.114025 -0.039467 0.235574 0.109057 -0.0441653 0.235574 0.114025 -0.039467 0.233774 0.116162 -0.0370596 0.235574 0.116162 -0.0370596 0.235574 0.11864 -0.0338887 0.233774 0.122519 -0.027776 0.235574 0.122519 -0.027776 0.235574 0.125602 -0.0212252 0.233774 0.125602 -0.0212252 0.233774 0.126173 -0.0197203 0.233774 0.127839 -0.0143398 0.235574 0.127839 -0.0143398 0.233774 0.12965 -2.85742e-06 0.235574 0.129195 -0.00722832 0.235786 0.12552 -0.0211929 0.235874 0.01465 -2.85742e-06 0.235851 0.0145352 -2.85742e-06 0.235851 0.0612321 -0.0564498 0.235834 0.0145 -2.85742e-06 0.235786 0.0215579 -0.0277336 0.235851 0.0216432 -0.0276867 0.235874 0.0217438 -0.0276314 0.235786 0.0612139 -0.0565454 0.235786 0.0683856 -0.0574514 0.235874 0.0683989 -0.0572397 0.235689 0.127817 -0.0143342 0.235851 0.127659 -0.0142938 0.235851 0.125429 -0.0211571 0.235874 0.127548 -0.0142652 0.235574 0.0214809 -0.027776 0.235786 0.0162462 -0.014318 0.235851 0.0163405 -0.0142938 0.235689 0.0299916 -0.0394514 0.235874 0.0354437 -0.0441918 0.235874 0.0412703 -0.0484251 0.235851 0.0412088 -0.048522 0.235786 0.0474912 -0.0520866 0.235786 0.0542123 -0.0547477 0.235574 0.0619891 -0.056777 0.235689 0.0898077 -0.0548095 0.235689 0.0827982 -0.0566093 0.235786 0.0756143 -0.0574514 0.235851 0.0827678 -0.0564498 0.235689 0.102878 -0.0486591 0.235851 0.0897576 -0.0546551 0.235786 0.0965087 -0.0520866 0.235574 0.108747 -0.0444229 0.235874 0.108556 -0.0441918 0.235851 0.11389 -0.0393402 0.235786 0.113961 -0.0394068 0.235689 0.118621 -0.0338753 0.235874 0.113806 -0.0392616 0.235786 0.118569 -0.033837 0.235689 0.12558 -0.0212168 0.235574 0.126173 -0.0197203 0.235689 0.0148272 -0.00722546 0.235689 0.0143728 -2.85742e-06 0.235851 0.0149883 -0.00720511 0.235786 0.0148917 -0.00721731 0.235574 0.0148045 -0.00722832 0.235689 0.0184196 -0.0212168 0.235574 0.0178267 -0.0197203 0.235689 0.0161833 -0.0143342 0.235851 0.0185705 -0.0211571 0.235786 0.01848 -0.0211929 0.235689 0.0215009 -0.027765 0.235574 0.0220736 -0.0288279 0.235851 0.02551 -0.0337798 0.235786 0.030039 -0.0394068 0.235786 0.0254312 -0.033837 0.235689 0.0253786 -0.0338753 0.235689 0.035267 -0.0444053 0.235874 0.0256028 -0.0337123 0.235851 0.0301099 -0.0393402 0.235786 0.0353085 -0.0443552 0.235851 0.0353705 -0.0442802 0.235786 0.0411566 -0.0486042 0.235689 0.0411218 -0.0486591 0.235689 0.0474635 -0.0521455 0.235689 0.0541922 -0.0548095 0.235574 0.0522825 -0.0541761 0.235874 0.0475815 -0.0518947 0.235851 0.0475326 -0.0519986 0.235851 0.0542424 -0.0546551 0.235689 0.0612017 -0.0566093 0.235851 0.0683917 -0.0573543 0.235689 0.0683815 -0.0575163 0.235574 0.0828025 -0.0566317 0.235689 0.0756184 -0.0575163 0.235574 0.0756198 -0.0575391 0.235874 0.075601 -0.0572397 0.235851 0.0756082 -0.0573543 0.235786 0.0897876 -0.0547477 0.235786 0.082786 -0.0565454 0.235574 0.10289 -0.0486784 0.235689 0.0965364 -0.0521455 0.235574 0.0965461 -0.0521661 0.235574 0.0917174 -0.0541761 0.235851 0.0964673 -0.0519986 0.235786 0.102843 -0.0486042 0.235786 0.108691 -0.0443552 0.235689 0.114008 -0.0394514 0.235689 0.108733 -0.0444053 0.235851 0.102791 -0.048522 0.235851 0.108629 -0.0442802 0.235689 0.122499 -0.027765 0.235574 0.121926 -0.0288279 0.235851 0.11849 -0.0337798 0.235874 0.118397 -0.0337123 0.235851 0.122357 -0.0276867 0.235786 0.122442 -0.0277336 0.235689 0.129173 -0.00722546 0.235574 0.128774 -0.0100137 0.235786 0.129108 -0.00721731 0.235786 0.127754 -0.014318 0.235834 0.1295 -2.85742e-06 0.235851 0.129012 -0.00720511 0.235786 0.129562 -2.85742e-06 0.235574 0.12965 -2.85742e-06 0.233774 0.0756198 -0.0575391 0.233497 0.0185705 -0.0211571 0.233497 0.125429 -0.0211571 0.233497 0.122357 -0.0276867 0.233497 0.129465 -2.85742e-06 0.233474 0.125323 -0.0211148 0.233474 0.127548 -0.0142652 0.233474 0.0186773 -0.0211148 0.233474 0.0217438 -0.0276314 0.233514 0.1295 -2.85742e-06 0.233497 0.129012 -0.00720511 0.233562 0.118569 -0.033837 0.233659 0.0161833 -0.0143342 0.233562 0.01848 -0.0211929 0.233659 0.127817 -0.0143342 0.233659 0.122499 -0.027765 0.233774 0.10289 -0.0486784 0.233659 0.108733 -0.0444053 0.233474 0.108556 -0.0441918 0.233497 0.108629 -0.0442802 0.233562 0.102843 -0.0486042 0.233659 0.0965364 -0.0521455 0.233562 0.0965087 -0.0520866 0.233474 0.10273 -0.0484251 0.233497 0.102791 -0.048522 0.233562 0.0897876 -0.0547477 0.233774 0.0828025 -0.0566317 0.233659 0.0827982 -0.0566093 0.233497 0.0827678 -0.0564498 0.233497 0.0756082 -0.0573543 0.233562 0.0683856 -0.0574514 0.233474 0.075601 -0.0572397 0.233562 0.0612139 -0.0565454 0.233659 0.0612017 -0.0566093 0.233497 0.0612321 -0.0564498 0.233474 0.0612536 -0.056337 0.233497 0.0542424 -0.0546551 0.233562 0.0542123 -0.0547477 0.233562 0.0474912 -0.0520866 0.233497 0.0475326 -0.0519986 0.233659 0.0411218 -0.0486591 0.233562 0.0411566 -0.0486042 0.233774 0.0352525 -0.0444229 0.233774 0.0349433 -0.0441653 0.233474 0.0412703 -0.0484251 0.233497 0.0353705 -0.0442802 0.233497 0.0301099 -0.0393402 0.233562 0.030039 -0.0394068 0.233562 0.0254312 -0.033837 0.233562 0.0215579 -0.0277336 0.233562 0.129108 -0.00721731 0.233659 0.129173 -0.00722546 0.233774 0.129195 -0.00722832 0.233562 0.127754 -0.014318 0.233774 0.128774 -0.0100137 0.233659 0.12558 -0.0212168 0.233497 0.127659 -0.0142938 0.233562 0.12552 -0.0211929 0.233562 0.122442 -0.0277336 0.233774 0.121926 -0.0288279 0.233659 0.118621 -0.0338753 0.233774 0.11864 -0.0338887 0.233497 0.11849 -0.0337798 0.233497 0.11389 -0.0393402 0.233562 0.113961 -0.0394068 0.233774 0.108747 -0.0444229 0.233659 0.114008 -0.0394514 0.233474 0.113806 -0.0392616 0.233562 0.108691 -0.0443552 0.233659 0.102878 -0.0486591 0.233774 0.100825 -0.0499292 0.233659 0.0898077 -0.0548095 0.233474 0.0964184 -0.0518947 0.233497 0.0964673 -0.0519986 0.233497 0.0897576 -0.0546551 0.233659 0.0756184 -0.0575163 0.233474 0.0897221 -0.054546 0.233562 0.082786 -0.0565454 0.233562 0.0756143 -0.0574514 0.233774 0.0619891 -0.056777 0.233774 0.0683801 -0.0575391 0.233659 0.0683815 -0.0575163 0.233474 0.0683989 -0.0572397 0.233497 0.0683917 -0.0573543 0.233659 0.0541922 -0.0548095 0.233774 0.0411095 -0.0486784 0.233659 0.0474635 -0.0521455 0.233774 0.043175 -0.0499292 0.233774 0.0474538 -0.0521661 0.233474 0.0542778 -0.054546 0.233659 0.035267 -0.0444053 0.233659 0.0299916 -0.0394514 0.233474 0.0475815 -0.0518947 0.233497 0.0412088 -0.048522 0.233562 0.0353085 -0.0443552 0.233774 0.0214809 -0.027776 0.233659 0.0215009 -0.027765 0.233774 0.0220736 -0.0288279 0.233659 0.0253786 -0.0338753 0.233774 0.0253601 -0.0338887 0.233474 0.0301936 -0.0392616 0.233474 0.0256028 -0.0337123 0.233497 0.0216432 -0.0276867 0.233497 0.02551 -0.0337798 0.233659 0.0184196 -0.0212168 0.233659 0.0148272 -0.00722546 0.233774 0.0148045 -0.00722832 0.233497 0.0149883 -0.00720511 0.233497 0.0163405 -0.0142938 0.233562 0.0162462 -0.014318 0.233774 0.0161611 -0.0143398 0.233474 0.0151022 -0.00719072 0.233562 0.0144378 -2.85742e-06 0.233562 0.0148917 -0.00721731 0.235874 0.12835 -2.85742e-06 0.235874 0.12739 -0.0103571 0.236074 0.124358 -0.0202866 0.236074 0.11974 -0.029562 0.235874 0.124545 -0.0203588 0.236074 0.113495 -0.0378309 0.236074 0.105838 -0.0448115 0.235874 0.0971173 -0.0504453 0.236074 0.0668191 -0.0559133 0.236074 0.0566338 -0.0540094 0.235874 0.056579 -0.0542017 0.236074 0.0469717 -0.0502663 0.235874 0.0468826 -0.0504453 0.236074 0.0305046 -0.0378309 0.235874 0.0303568 -0.0379656 0.236074 0.0242603 -0.029562 0.235874 0.0240902 -0.0296673 0.236074 0.0196416 -0.0202866 0.236074 0.016806 -0.0103204 0.233474 0.0166094 -0.0103571 0.233274 0.0196416 -0.0202866 0.233274 0.038162 -0.0448115 0.233274 0.0668191 -0.0559133 0.233274 0.0771808 -0.0559133 0.233474 0.0771993 -0.0561125 0.233474 0.0874209 -0.0542017 0.233274 0.105838 -0.0448115 0.233274 0.113495 -0.0378309 0.233474 0.11991 -0.0296673 0.233274 0.127194 -0.0103204 0.233474 0.124545 -0.0203588 0.229848 0.0858879 0.0630238 0.226574 0.0872879 0.0630238 0.224774 0.0875023 0.0622238 0.226574 0.0875023 0.0622238 0.226574 0.0888879 0.0614238 0.224774 0.0888879 0.0614238 0.224774 0.0902735 0.0622238 0.226574 0.0862269 -0.0616443 0.230092 0.0859383 -0.0624821 0.226574 0.0884963 -0.0600552 0.230801 0.0870307 -0.0606735 0.226574 0.0871672 -0.0605721 0.226574 0.089914 -0.0602104 0.230653 0.0899188 -0.0602122 0.226574 0.0910997 -0.0610027 0.230739 0.115258 -0.0453039 0.230801 0.115352 -0.0450298 0.230921 0.116014 -0.0440241 0.230891 0.115632 -0.0444932 0.230774 0.117151 -0.0433087 0.230638 0.117675 -0.0431777 0.226574 0.117669 -0.0431785 0.229997 0.119342 -0.0433937 0.230871 0.132027 -0.0168908 0.230921 0.132127 -0.0161196 0.226574 0.132336 -0.0155639 0.226574 0.1332 -0.0145107 0.230615 0.133204 -0.0145076 0.230455 0.133617 -0.0142428 0.226574 0.135803 -0.013993 0.230455 0.132482 0.0184735 0.226574 0.132301 0.0181387 0.226574 0.13425 0.0197829 0.229484 0.13425 0.0197829 0.226574 0.115139 0.0461359 0.224774 0.053512 0.0630238 0.226574 0.0537264 0.0622238 0.224774 0.054312 0.0616382 0.224774 0.055112 0.0614238 0.226574 0.055112 0.0614238 0.224774 0.055912 0.0616382 0.226574 0.0564977 0.0622238 0.224774 0.056712 0.0630238 0.226574 0.056712 0.0630238 0.226574 0.0242612 0.0461359 0.224774 0.0244756 0.0453359 0.224774 0.0250612 0.0447502 0.224774 0.0258612 0.0445359 0.224774 0.0266612 0.0447502 0.224774 0.0272469 0.0453359 0.226574 0.0272469 0.0453359 0.224774 0.00758766 0.0160851 0.226574 0.0081733 0.0154994 0.224774 0.0089733 0.0152851 0.224774 0.0097733 0.0154994 0.224774 0.0105733 0.0168851 0.224774 0.0073733 -0.0168908 0.226574 0.0073733 -0.0168908 0.224774 0.0081733 -0.0182764 0.226574 0.00758766 -0.0176908 0.226574 0.0081733 -0.0182764 0.224774 0.0089733 -0.0184908 0.226574 0.0089733 -0.0184908 0.224774 0.0103589 -0.0176908 0.224774 0.0258612 -0.0477416 0.226574 0.0258612 -0.0477416 0.224774 0.0272469 -0.0469416 0.226574 0.0272469 -0.0469416 0.226574 0.053512 -0.0630295 0.226574 0.0537264 -0.0638295 0.226574 0.054312 -0.0644152 0.224774 0.055912 -0.0644152 0.226574 0.055912 -0.0644152 0.224774 0.0564977 -0.0638295 0.224774 0.056712 -0.0630295 0.224774 0.0888879 -0.0646295 0.226574 0.0880879 -0.0644152 0.226574 0.0888879 -0.0646295 0.226574 0.0896879 -0.0644152 0.224774 0.0902735 -0.0638295 0.226574 0.0904879 -0.0630295 0.224774 0.116753 -0.0469416 0.224774 0.117339 -0.0475272 0.224774 0.118139 -0.0477416 0.224774 0.118939 -0.0475272 0.226574 0.118939 -0.0475272 0.224774 0.119524 -0.0469416 0.226574 0.119524 -0.0469416 0.224774 0.133641 -0.0176908 0.226574 0.134227 -0.0182764 0.226574 0.135827 -0.0182764 0.226574 0.136412 -0.0176908 0.224774 0.136627 -0.0168908 0.226574 0.133427 0.0168851 0.226574 0.133641 0.0160851 0.224774 0.135827 0.0154994 0.224774 0.136627 0.0168851 0.224774 0.116753 0.0453359 0.224774 0.117339 0.0447502 0.226574 0.117339 0.0447502 0.226574 0.118139 0.0445359 0.224774 0.118939 0.0447502 0.226574 0.118939 0.0447502 0.226574 0.119524 0.0453359 0.228741 0.0860398 -0.0667304 0.228738 0.0857119 -0.0668612 0.228777 0.086502 -0.0660159 0.226574 0.086511 -0.0658816 0.228767 0.0864545 -0.0662131 0.226574 0.0863541 -0.0664194 0.228761 0.0864112 -0.0663172 0.228751 0.0862911 -0.0665073 0.228744 0.0861251 -0.0666709 0.226362 0.117553 -0.0507077 0.226274 0.117304 -0.0510479 0.226325 0.136808 -0.0212413 0.226574 0.136695 0.0207744 0.228757 0.136684 0.0207534 0.226574 0.136453 0.0204713 0.228773 0.136476 0.020491 0.226574 0.136067 0.0202697 0.228754 0.136717 0.0208177 0.226541 0.136717 0.0208177 0.226574 0.117347 0.0495872 0.226574 0.117565 0.0499138 0.228775 0.117584 0.049963 0.238274 0.121859 -2.85742e-06 0.238274 0.120901 0.0097241 0.238474 0.120705 0.00968508 0.238474 0.117879 0.0190007 0.238474 0.11329 0.0275861 0.238274 0.107255 0.0352526 0.238474 0.107114 0.0351112 0.238474 0.0995889 0.0412869 0.238474 0.0910035 0.0458758 0.238274 0.0910801 0.0460606 0.238274 0.0817269 0.0488979 0.238474 0.072 0.0496559 0.238474 0.062312 0.0487017 0.238474 0.0529964 0.0458758 0.238274 0.0442999 0.0414532 0.238474 0.0307102 0.0275861 0.238274 0.0259365 0.0190773 0.238474 0.0232954 0.00968508 0.236674 0.016806 -0.0103204 0.236874 0.0240902 -0.0296673 0.236874 0.0468826 -0.0504453 0.236674 0.0566338 -0.0540094 0.236874 0.0668006 -0.0561125 0.236874 0.0771993 -0.0561125 0.236674 0.0873661 -0.0540094 0.236874 0.0874209 -0.0542017 0.236874 0.0971173 -0.0504453 0.236674 0.105838 -0.0448115 0.236674 0.113495 -0.0378309 0.236874 0.113643 -0.0379656 0.236674 0.11974 -0.029562 0.236874 0.11991 -0.0296673 0.236874 0.124545 -0.0203588 0.236874 0.12739 -0.0103571 0.237674 0.0152258 -0.0100137 0.237874 0.01415 -2.85742e-06 0.237674 0.0178267 -0.0197203 0.237874 0.0176387 -0.0197887 0.237674 0.0220736 -0.0288279 0.237874 0.0219004 -0.0289279 0.237674 0.0349433 -0.0441653 0.237874 0.0348147 -0.0443185 0.237674 0.043175 -0.0499292 0.237874 0.043075 -0.0501024 0.237874 0.0522141 -0.0543641 0.237674 0.0619891 -0.056777 0.237874 0.072 -0.0578529 0.237674 0.0917174 -0.0541761 0.237874 0.0917858 -0.0543641 0.237674 0.109057 -0.0441653 0.237674 0.121926 -0.0288279 0.237874 0.116316 -0.0371881 0.237874 0.1221 -0.0289279 0.237874 0.126361 -0.0197887 0.237874 0.128971 -0.0100484 0.237874 0.13065 -2.85742e-06 0.237674 0.13085 -2.85742e-06 0.237874 0.129759 0.0101816 0.237674 0.122966 0.0294221 0.237874 0.116928 0.0376966 0.237874 0.109699 0.0449256 0.237874 0.0920594 0.0551101 0.237674 0.0822192 0.0579531 0.237674 0.0617808 0.0579531 0.237674 0.0518721 0.0552981 0.237674 0.0341719 0.0450789 0.237874 0.0343005 0.0449256 0.237874 0.0212076 0.0293221 0.237874 0.01335 -2.85742e-06 0.228874 0.1182 -2.85742e-06 0.228674 0.117508 -0.00905505 0.228874 0.114683 -0.0176828 0.228874 0.110414 -0.0256702 0.228674 0.0977784 -0.038583 0.228874 0.0896799 -0.0426861 0.228674 0.0897565 -0.0428709 0.228874 0.0810131 -0.0453151 0.228674 0.0629478 -0.0455113 0.228874 0.05432 -0.0426861 0.228874 0.0393316 -0.0326712 0.228674 0.0291319 -0.0177594 0.228874 0.0266877 -0.00901603 0.228674 0.0264915 -0.00905505 0.230674 0.0264915 -0.00905505 0.230474 0.0266877 -0.00901603 0.230474 0.0293167 -0.0176828 0.230674 0.0334198 -0.0257813 0.230674 0.0391902 -0.0328126 0.230674 0.0462215 -0.038583 0.230674 0.0542434 -0.0428709 0.230674 0.0629478 -0.0455113 0.230674 0.072 -0.0464029 0.230674 0.0810521 -0.0455113 0.230674 0.0897565 -0.0428709 0.230474 0.0976673 -0.0384168 0.230474 0.110414 -0.0256702 0.230474 0.117312 -0.00901603 0.238474 0.024628 -0.00942572 0.238174 0.0320894 -0.0266702 0.238174 0.0380588 -0.033944 0.238474 0.03184 -0.0268369 0.238474 0.0378467 -0.0341561 0.238174 0.0536312 -0.0443491 0.238474 0.0451659 -0.0401628 0.238474 0.0535163 -0.0446262 0.238174 0.0626356 -0.0470806 0.238474 0.072 -0.0483029 0.238174 0.0813643 -0.0470806 0.238474 0.0814228 -0.0473748 0.238174 0.0986673 -0.0399134 0.238474 0.0904836 -0.0446262 0.238474 0.098834 -0.0401628 0.238174 0.105941 -0.033944 0.238174 0.116346 -0.0183717 0.238174 0.119078 -0.00936719 0.236674 0.114936 0.026582 0.236974 0.114681 0.026424 0.236974 0.102252 0.0400576 0.236674 0.0945097 0.0452029 0.236674 0.0858199 0.0485693 0.236674 0.0766595 0.0502817 0.236974 0.0766318 0.049983 0.236974 0.0673681 0.049983 0.236974 0.0582621 0.0482808 0.236674 0.0494902 0.0452029 0.236674 0.0415669 0.040297 0.236674 0.03468 0.0340188 0.236974 0.0349017 0.0338167 0.236674 0.029064 0.026582 0.236974 0.0293191 0.026424 0.236974 0.0251899 0.0181315 0.236674 0.0223598 0.00927649 0.230376 0.0085193 -0.00585676 0.229621 0.00723028 0.00834145 0.225074 0.00723028 0.00834145 0.225074 0.00842337 0.00682769 0.230134 0.00818082 0.00739174 0.225074 0.00797228 0.00769921 0.225074 0.13575 -2.85742e-06 0.225074 0.139298 0.00995576 0.225074 0.139198 0.00981298 0.224774 0.139038 0.0101058 0.224774 0.135558 0.00753979 0.224774 0.13662 0.00860126 0.225074 0.135577 0.00682769 0.225074 0.135818 0.00738979 0.225074 0.13547 -0.0060955 0.225074 0.135481 -0.00585676 0.225074 0.13942 -0.010617 0.224774 0.139123 -0.0105703 0.231383 0.0087198 -2.85742e-06 0.224474 0.00456819 -0.0104615 0.224774 0.00487671 -0.0105703 0.224474 0.00853028 -0.0060955 0.224474 0.00837719 0.0069688 0.224774 0.00883028 0.00608979 0.224774 0.00871104 0.00691283 0.224774 0.00521819 0.00984955 0.224474 0.00470216 0.00995576 0.224774 0.00488909 0.010286 0.224474 0.00459863 0.0102109 0.224474 0.139432 -0.0104615 0.221811 0.13942 -0.010617 0.224474 0.13923 0.0098537 0.224474 0.138932 0.00958974 0.221785 0.139432 0.0104558 0.224474 0.13575 -2.85742e-06 0.219625 0.13575 -2.85742e-06 0.21983 0.00852657 0.00622862 0.219953 0.00833818 0.00707062 0.224474 0.00818195 0.00738979 0.220221 0.00783097 0.00786388 0.224474 0.00723028 0.00834145 0.219821 0.00853028 -0.0060955 0.219817 0.00852746 -0.00597446 0.224474 0.0085193 -0.00585676 0.219563 0.116889 0.0461359 0.21943 0.117359 0.0451586 0.219498 0.117861 0.0449172 0.224774 0.118417 0.0449172 0.219643 0.118417 0.0449172 0.224774 0.119265 0.0455935 0.220036 0.119265 0.0455935 0.219518 0.134247 0.0159078 0.224774 0.134247 0.0159078 0.219673 0.134748 0.0156664 0.224774 0.135806 0.0159078 0.224774 0.136153 0.0163427 0.220229 0.136153 0.0163427 0.224774 0.136277 0.0168851 0.220322 0.136277 0.0168851 0.219539 0.1339 -0.0174332 0.224774 0.134247 -0.0178681 0.219704 0.134247 -0.0178681 0.224774 0.134748 -0.0181095 0.22025 0.135806 -0.0178681 0.22033 0.136153 -0.0174332 0.220337 0.119022 -0.0470257 0.220322 0.118764 -0.0472241 0.219563 0.116889 -0.0461416 0.219769 0.117056 -0.0467666 0.224774 0.117514 -0.0472241 0.224774 0.118139 -0.0473916 0.220206 0.118139 -0.0473916 0.224774 0.118764 -0.0472241 0.224774 0.119221 -0.0467666 0.220322 0.119221 -0.0467666 0.220206 0.119389 -0.0461416 0.224774 0.0877617 -0.0635719 0.224774 0.0881085 -0.0640068 0.224774 0.0886097 -0.0642482 0.224774 0.0891661 -0.0642482 0.224774 0.0896673 -0.0640068 0.2203 0.0896673 -0.0640068 0.224774 0.0900141 -0.0635719 0.220322 0.054487 -0.0641121 0.224774 0.0540295 -0.0636545 0.220206 0.0540295 -0.0636545 0.220337 0.0547881 -0.0642368 0.220322 0.055112 -0.0642795 0.224774 0.055112 -0.0642795 0.220206 0.055737 -0.0641121 0.220004 0.0561945 -0.0636545 0.220277 0.0246532 -0.0464627 0.224774 0.0252362 -0.0472241 0.220277 0.02554 -0.0473496 0.220206 0.0258612 -0.0473916 0.224774 0.0258612 -0.0473916 0.224774 0.0264862 -0.0472241 0.220004 0.0264862 -0.0472241 0.219769 0.0269438 -0.0467666 0.224774 0.0077233 -0.0168908 0.224774 0.00784709 -0.0174332 0.224774 0.00819394 -0.0178681 0.22025 0.00819394 -0.0178681 0.224774 0.00869515 -0.0181095 0.220098 0.00869515 -0.0181095 0.224774 0.00925145 -0.0181095 0.224774 0.0100995 -0.0174332 0.219539 0.0100995 -0.0174332 0.224774 0.0102233 -0.0168908 0.224774 0.0077233 0.0168851 0.220229 0.00784709 0.0163427 0.224774 0.00819394 0.0159078 0.224774 0.00925145 0.0156664 0.224774 0.00975266 0.0159078 0.219518 0.00975266 0.0159078 0.224774 0.0100995 0.0163427 0.219435 0.0100995 0.0163427 0.224774 0.0102233 0.0168851 0.220206 0.0246112 0.0461359 0.224774 0.0246112 0.0461359 0.224774 0.024735 0.0455935 0.219643 0.0255831 0.0449172 0.224774 0.0255831 0.0449172 0.219453 0.0269875 0.0455935 0.224774 0.0269875 0.0455935 0.224774 0.0271112 0.0461359 0.224774 0.053862 0.0630238 0.224774 0.0539858 0.0624814 0.219802 0.0539858 0.0624814 0.219428 0.0553902 0.0618051 0.224774 0.0553902 0.0618051 0.219466 0.0558914 0.0620465 0.224774 0.0562382 0.0624814 0.224774 0.0876379 0.0630238 0.219769 0.0876379 0.0630238 0.224774 0.0877617 0.0624814 0.224774 0.0891661 0.0618051 0.224774 0.0896673 0.0620465 0.186474 0.1139 -2.85742e-06 0.186474 0.112984 -0.00871436 0.185974 0.113473 -0.00881831 0.185974 0.106302 -0.024925 0.186474 0.100037 -0.0311406 0.185974 0.100371 -0.0315122 0.186474 0.0849478 -0.0398521 0.185974 0.0851023 -0.0403277 0.185974 0.0588976 -0.0403277 0.186474 0.0590521 -0.0398521 0.186474 0.05105 -0.0362893 0.185974 0.0508 -0.0367223 0.186474 0.0381021 -0.0246311 0.185974 0.0332656 -0.0172485 0.187974 0.00919996 -2.85742e-06 0.187974 0.010154 0.0109022 0.185974 0.0148666 0.020792 0.185974 0.0193456 0.0303971 0.185974 0.0329185 0.0465726 0.185974 0.0416 0.0526515 0.187974 0.0610949 0.0618431 0.185974 0.0614421 0.0598735 0.185974 0.072 0.0607971 0.187974 0.0829051 0.0618431 0.187974 0.0934788 0.0590098 0.187974 0.112367 0.0481047 0.185974 0.118575 0.0390786 0.187974 0.131013 0.021476 0.185974 0.129133 0.020792 0.219219 0.00886944 -0.00613814 0.219215 0.00884965 -0.00582629 0.218689 0.0091172 -2.85742e-06 0.218686 0.00933797 -0.00525589 0.218686 0.00996303 -0.010276 0.21829 0.0100437 -0.0102627 0.218686 0.0124111 -0.0200847 0.21829 0.0129873 -0.0214817 0.218686 0.0142182 -0.0248099 0.218686 0.0163993 -0.0293744 0.21829 0.0176136 -0.0314029 0.218686 0.0189403 -0.0337488 0.21829 0.0190093 -0.033705 0.218686 0.0218247 -0.0379049 0.21829 0.025095 -0.0417612 0.21829 0.0286035 -0.0453966 0.21829 0.032393 -0.0487381 0.218686 0.0323414 -0.0488016 0.218686 0.0363924 -0.0518317 0.21829 0.0406 -0.0543893 0.21829 0.0451932 -0.056794 0.21829 0.0498451 -0.0587651 0.218686 0.0498163 -0.0588416 0.21829 0.0546405 -0.0603559 0.218686 0.0546179 -0.0604345 0.21829 0.0595482 -0.061556 0.218686 0.0645267 -0.062439 0.21829 0.072 -0.0628029 0.218686 0.0746288 -0.0628297 0.21829 0.0796607 -0.0623339 0.21829 0.0829051 -0.0618488 0.21829 0.0846464 -0.0615163 0.218686 0.0943697 -0.0587712 0.21829 0.0895503 -0.0603007 0.21829 0.0943406 -0.0586947 0.218686 0.0990214 -0.0567828 0.21829 0.111761 -0.0486126 0.218686 0.111813 -0.0486759 0.21829 0.11554 -0.0452591 0.21829 0.119037 -0.0416126 0.21829 0.120108 -0.0403699 0.218686 0.119098 -0.0416668 0.21829 0.122229 -0.0376969 0.21829 0.125097 -0.0335372 0.21829 0.127621 -0.0291604 0.218686 0.12986 -0.024627 0.21829 0.131013 -0.0214817 0.21829 0.133846 -0.010908 0.218686 0.134069 -0.0100797 0.21829 0.133988 -0.0100666 0.218686 0.134678 -0.00505766 0.219021 0.00888264 -2.85742e-06 0.219018 0.0107645 -0.0152858 0.218686 0.0109896 -0.0152297 0.219018 0.0121912 -0.0201588 0.219018 0.0161942 -0.0294828 0.219018 0.0187446 -0.0338733 0.219018 0.0216396 -0.0380447 0.219018 0.0283867 -0.0456234 0.218686 0.0250339 -0.0418156 0.219018 0.0321951 -0.0489816 0.218686 0.028547 -0.0454557 0.219018 0.0405584 -0.0547274 0.218686 0.040674 -0.0545263 0.218686 0.0451583 -0.056868 0.218686 0.0595319 -0.0616362 0.219018 0.0695609 -0.0630695 0.218686 0.0695699 -0.0628377 0.219018 0.0746385 -0.0630614 0.218686 0.0796706 -0.062415 0.219018 0.0847096 -0.0618237 0.218686 0.0846629 -0.0615964 0.218686 0.0895731 -0.0603792 0.219018 0.103614 -0.0546277 0.218686 0.103498 -0.0544269 0.218686 0.107771 -0.0517188 0.219018 0.115757 -0.0454852 0.218686 0.115596 -0.045318 0.219018 0.119272 -0.0418205 0.219018 0.12248 -0.0378852 0.219018 0.125362 -0.0337047 0.218686 0.122295 -0.037746 0.218686 0.125166 -0.0335808 0.219018 0.127899 -0.0293061 0.218686 0.127693 -0.0291984 0.219018 0.131872 -0.0199695 0.218686 0.131652 -0.0198962 0.218686 0.133058 -0.0150366 0.219018 0.133283 -0.0150921 0.219018 0.134909 -0.0050763 0.21923 0.135458 -2.85742e-06 0.21923 0.135253 -0.00510397 0.219018 0.134298 -0.0101169 0.21923 0.134638 -0.0101721 0.21923 0.133618 -0.0151744 0.219018 0.130073 -0.0247178 0.21923 0.128204 -0.0294659 0.21923 0.125653 -0.0338885 0.21923 0.115996 -0.0457332 0.219018 0.11196 -0.0488555 0.219018 0.107903 -0.0519095 0.21923 0.103787 -0.0549256 0.219018 0.0991211 -0.0569923 0.21923 0.099269 -0.0573031 0.219018 0.0944522 -0.058988 0.21923 0.0945746 -0.0593097 0.219018 0.089638 -0.0606019 0.21923 0.0897342 -0.0609324 0.219018 0.0796989 -0.0626453 0.21923 0.0746529 -0.0634054 0.219018 0.0644992 -0.0626693 0.21923 0.0644583 -0.0630111 0.219018 0.0594859 -0.0618636 0.21923 0.0594177 -0.0622009 0.219018 0.0545537 -0.0606574 0.219018 0.0497344 -0.0590587 0.21923 0.0544586 -0.0609882 0.21923 0.049613 -0.0593808 0.21923 0.0449123 -0.057389 0.219018 0.0450592 -0.0570778 0.21923 0.0360662 -0.0523066 0.219018 0.0362611 -0.0520229 0.21923 0.0281488 -0.0458722 0.219018 0.0248606 -0.0419698 0.21923 0.0246035 -0.0421987 0.21923 0.0184541 -0.0340581 0.21923 0.0158898 -0.0296435 0.219018 0.014005 -0.0249014 0.21923 0.011865 -0.0202688 0.219018 0.00973417 -0.0103139 0.21923 0.00939457 -0.0103702 0.219018 0.00910681 -0.00527527 0.21829 0.00965784 0.00756685 0.21829 0.0132809 0.0222663 0.187974 0.0129873 0.021476 0.21829 0.0110248 0.0150262 0.187974 0.0176136 0.0313971 0.187974 0.0238924 0.0403642 0.187974 0.0316329 0.0481047 0.21829 0.0238924 0.0403642 0.21829 0.0363255 0.0516805 0.21829 0.0303559 0.0470036 0.21829 0.0428153 0.0556038 0.187974 0.0406 0.0543835 0.21829 0.0497308 0.0587162 0.187974 0.0505211 0.0590098 0.21829 0.0569709 0.0609723 0.187974 0.072 0.0627971 0.21829 0.087029 0.0609723 0.187974 0.1034 0.0543835 0.21829 0.119006 0.0416412 0.187974 0.120108 0.0403642 0.21829 0.120108 0.0403642 0.187974 0.126386 0.0313971 0.21829 0.126386 0.0313971 0.21829 0.123683 0.0356716 0.21829 0.130719 0.0222663 0.187974 0.1348 -2.85742e-06 0.21829 0.134342 0.00756685 0.187974 0.133846 0.0109022 0.21829 0.132975 0.0150262 0.21923 0.00887099 -0.0064564 0.220206 0.00789077 -0.0162658 0.220322 0.0077233 -0.0168908 0.22033 0.00784709 -0.0174332 0.219443 0.0102233 -0.0168908 0.219427 0.0101808 -0.0165675 0.21923 0.0104306 -0.0153692 0.219769 0.0089733 -0.0156408 0.220321 0.00622812 -0.00950017 0.220803 0.00623702 -0.0164158 0.220004 0.0083483 -0.0158083 0.220803 0.00500039 -0.0102599 0.220777 0.00506229 -0.0101874 0.219903 0.00729996 -0.00887967 0.219471 0.00836435 -0.00787337 0.219258 0.135535 -2.85742e-06 0.219258 0.135267 -0.00583705 0.219471 0.135667 -0.00761663 0.220098 0.135305 -0.0181095 0.219904 0.134748 -0.0181095 0.220803 0.136299 -0.0214458 0.220322 0.136277 -0.0168908 0.220803 0.138904 -0.0108647 0.220004 0.135652 -0.0158083 0.219902 0.136728 -0.00866623 0.219443 0.133944 -0.0162658 0.219443 0.133777 -0.0168908 0.21923 0.132199 -0.0200784 0.21923 0.13039 -0.0248526 0.21923 0.128204 -0.0294659 0.220803 0.133064 -0.02942 0.220803 0.132032 -0.0314727 0.220803 0.127592 -0.0387799 0.220004 0.117514 -0.0472241 0.220803 0.118993 -0.048848 0.220277 0.11846 -0.0473495 0.220277 0.119347 -0.046463 0.21923 0.122756 -0.0380918 0.219836 0.118918 -0.0451643 0.220036 0.119265 -0.0455992 0.219643 0.118417 -0.0449229 0.21923 0.11953 -0.0420486 0.219498 0.117861 -0.0449229 0.21923 0.112178 -0.0491219 0.220803 0.112558 -0.0543091 0.21923 0.108099 -0.0521926 0.220803 0.103381 -0.0600811 0.220803 0.101126 -0.0612058 0.220803 0.0934002 -0.064316 0.219443 0.0888879 -0.0617795 0.219971 0.0877617 -0.0635719 0.220155 0.0881085 -0.0640068 0.220803 0.0828722 -0.0669054 0.220286 0.0886097 -0.0642482 0.220337 0.0891661 -0.0642482 0.220182 0.0900141 -0.0635719 0.219769 0.0899704 -0.0624045 0.219563 0.0878054 -0.0624045 0.21923 0.0847789 -0.0621608 0.21923 0.0797409 -0.0629869 0.220803 0.0720659 -0.067783 0.21923 0.0695476 -0.0634134 0.220803 0.061258 -0.0669264 0.21923 0.0594177 -0.0622009 0.220004 0.053862 -0.0630295 0.220803 0.0507249 -0.0643575 0.220277 0.0542268 -0.0639121 0.220803 0.0585607 -0.0664373 0.220277 0.0554377 -0.0642363 0.219769 0.056362 -0.0630295 0.219588 0.0562382 -0.0624872 0.219466 0.0558914 -0.0620522 0.219428 0.0553902 -0.0618109 0.219481 0.0548339 -0.0618109 0.219615 0.0543327 -0.0620522 0.220803 0.0480882 -0.0634251 0.21923 0.0403869 -0.0550259 0.220803 0.0315474 -0.0543879 0.220206 0.0246112 -0.0461416 0.220322 0.0247787 -0.0467666 0.220337 0.0249774 -0.0470255 0.220803 0.0233935 -0.0472423 0.220322 0.0252362 -0.0472241 0.220803 0.0292521 -0.0526029 0.21923 0.031978 -0.0492487 0.219563 0.0271112 -0.0461416 0.21949 0.0270693 -0.0458206 0.219427 0.0267451 -0.0452577 0.21949 0.0261824 -0.0449335 0.220803 0.0164833 -0.038888 0.21923 0.0213649 -0.0382522 0.220803 0.0148071 -0.0363776 0.21923 0.0136887 -0.0250372 0.220803 0.00971711 -0.0267423 0.219904 0.00925145 -0.0181095 0.219704 0.00975266 -0.0178681 0.186474 0.0301 -2.85742e-06 0.213124 0.0301 -2.85742e-06 0.186474 0.0310156 -0.00871436 0.186474 0.0337224 -0.0170451 0.213124 0.0381021 -0.0246311 0.213124 0.0439634 -0.0311406 0.186474 0.0439634 -0.0311406 0.213124 0.05105 -0.0362893 0.186474 0.0676202 -0.0416733 0.213124 0.0676202 -0.0416733 0.186474 0.0763797 -0.0416733 0.186474 0.09295 -0.0362893 0.213124 0.0849478 -0.0398521 0.213124 0.100037 -0.0311406 0.213124 0.105898 -0.0246311 0.186474 0.105898 -0.0246311 0.213124 0.110278 -0.0170451 0.186474 0.110278 -0.0170451 0.187574 0.0514464 0.0254464 0.187574 0.051071 0.025547 0.187123 0.0514464 0.0261971 0.187574 0.0921782 -0.026853 0.187574 0.0933043 -0.0262029 0.187574 0.0929289 -0.026853 0.187574 0.051071 -0.026853 0.187574 0.0506957 -0.0262029 0.187574 0.0507962 -0.0265782 0.187574 0.0518217 -0.026853 0.187574 0.0925535 0.0254464 0.187574 0.0932037 0.0258218 0.185974 0.1202 -2.85742e-06 0.185974 0.116784 0.0178193 0.185974 0.10702 0.0331153 0.185774 0.02453 -0.00944523 0.185974 0.027469 -0.0184482 0.185774 0.0317568 -0.0268925 0.185974 0.0379174 -0.0340854 0.185774 0.0451104 -0.040246 0.185974 0.0452215 -0.0400797 0.185974 0.0535546 -0.0445339 0.185774 0.0625576 -0.0474729 0.185974 0.0625966 -0.0472767 0.185974 0.072 -0.0482029 0.185774 0.0814423 -0.0474729 0.185974 0.0814033 -0.0472767 0.185774 0.0905218 -0.0447186 0.185774 0.0988896 -0.040246 0.185974 0.0987784 -0.0400797 0.185774 0.112243 -0.0268925 0.185974 0.112077 -0.0267813 0.185774 0.116716 -0.0185247 0.185974 0.116531 -0.0184482 0.185774 0.11947 -0.00944523 0.183974 0.0392653 0.0250147 0.184974 0.0415872 0.026286 0.184974 0.0374089 0.0204788 0.184974 0.0367687 0.0193568 0.183974 0.033389 0.0143718 0.184974 0.0335031 0.0115742 0.184974 0.0324365 0.00712288 0.183974 0.0279592 0.0175234 0.184974 0.0312028 0.0260385 0.184974 0.043723 0.0392778 0.184974 0.11947 -0.00944523 0.183974 0.118489 -0.00925014 0.183974 0.1194 -2.85742e-06 0.183974 0.105517 -0.0335197 0.183974 0.111412 -0.0263369 0.184974 0.0534781 -0.0447186 0.183974 0.0627527 -0.0464921 0.183974 0.072 -0.0474029 0.183974 0.0812472 -0.0464921 0.184974 0.0814423 -0.0474729 0.184974 0.0905218 -0.0447186 0.184974 0.0317568 -0.0268925 0.183974 0.0538608 -0.0437947 0.184974 0.0272842 -0.0185247 0.183974 0.0282081 -0.0181421 0.183974 0.0246 -2.85742e-06 0.184964 0.0892494 -0.030015 0.181449 0.0476674 0.00404714 0.182296 0.0479 0.00449714 0.182524 0.04875 0.00449714 0.180824 0.05 0.00404714 0.181674 0.0502222 0.00449714 0.180824 0.0475 -0.00500286 0.181449 0.0476674 -0.00500286 0.181907 0.048125 -0.00500286 0.181907 0.048125 0.00404714 0.182074 0.04875 -0.00500286 0.182074 0.04875 0.00404714 0.181907 0.049375 0.00404714 0.181449 0.0498325 -0.00500286 0.181449 0.0498325 0.00404714 0.181907 0.049375 -0.00500286 0.181562 0.0937183 0.00449714 0.181802 0.0944706 0.00404714 0.182043 0.0949718 0.00404714 0.182043 0.0955281 0.00404714 0.182482 0.0948717 0.00449714 0.182482 0.0956282 0.00449714 0.182153 0.0963099 0.00449714 0.181367 0.0963762 0.00404714 0.181367 0.0941237 -0.00500286 0.180824 0.094 0.00404714 0.181367 0.0941237 0.00404714 0.181802 0.0944706 -0.00500286 0.181802 0.0960293 -0.00500286 0.181802 0.0960293 0.00404714 0.181367 0.0963762 -0.00500286 0.180824 0.094 -0.00500286 0.182043 0.0949718 -0.00500286 0.180824 0.0965 -0.00500286 0.180824 0.09525 -0.00575393 0.182043 0.0955281 -0.00500286 0.181367 0.0708737 0.00404714 0.181562 0.0704683 0.00449714 0.181802 0.0712206 0.00404714 0.182043 0.0717218 0.00404714 0.182482 0.0716217 0.00449714 0.181802 0.0727793 0.00404714 0.182153 0.0730599 0.00449714 0.180824 0.07075 -0.00500286 0.181367 0.0708737 -0.00500286 0.181802 0.0712206 -0.00500286 0.182043 0.0717218 -0.00500286 0.182043 0.0722781 -0.00500286 0.182043 0.0722781 0.00404714 0.181802 0.0727793 -0.00500286 0.181367 0.0731262 0.00404714 0.181367 0.0731262 -0.00500286 0.180824 0.07325 -0.00500286 0.180824 0.072 -0.00575393 0.186974 0.109638 -0.0167604 0.186874 0.109144 -0.0178905 0.186974 0.0763065 -0.0409772 0.186801 0.0750863 -0.0411874 0.186774 0.111561 -0.0122057 0.186774 0.0306 -2.85742e-06 0.186774 0.0416516 -0.028162 0.186774 0.0377937 -0.0233243 0.186801 0.0417249 -0.028094 0.186774 0.0461875 -0.0323707 0.186801 0.05135 -0.0357697 0.186774 0.0513 -0.0358563 0.186801 0.0569114 -0.0384479 0.186774 0.0568748 -0.038541 0.186774 0.0750938 -0.0412871 0.186774 0.0689061 -0.0412871 0.186801 0.0870885 -0.0384479 0.186801 0.09265 -0.0357697 0.186774 0.0978124 -0.0323707 0.186801 0.102275 -0.028094 0.186774 0.102348 -0.028162 0.186774 0.1093 -0.0179656 0.186874 0.0348559 -0.0178905 0.186774 0.0324392 -0.0122057 0.186801 0.0325348 -0.0121762 0.186874 0.0379368 -0.0232267 0.186874 0.0462955 -0.0322353 0.186801 0.0462498 -0.0322925 0.186874 0.0513866 -0.0357063 0.186874 0.0628261 -0.040196 0.186801 0.0628098 -0.0402674 0.186801 0.0689136 -0.0411874 0.186874 0.0926134 -0.0357063 0.186801 0.0977501 -0.0322925 0.186874 0.102221 -0.0280442 0.186801 0.0307 -2.85742e-06 0.186801 0.0311612 -0.0061583 0.186874 0.0312336 -0.00614739 0.186974 0.0308 -2.85742e-06 0.186874 0.0326048 -0.0121547 0.186974 0.0317003 -0.00856882 0.186974 0.0312601 -0.0061434 0.186974 0.0379589 -0.0232116 0.186974 0.0343619 -0.0167604 0.186801 0.0347899 -0.0179223 0.186801 0.0378763 -0.023268 0.186874 0.0417786 -0.0280442 0.186974 0.0417982 -0.028026 0.186974 0.0592685 -0.0391864 0.186874 0.0569381 -0.0383798 0.186974 0.0689211 -0.0410877 0.186874 0.0689191 -0.0411144 0.186974 0.0676934 -0.0409772 0.186874 0.0811738 -0.040196 0.186874 0.0750808 -0.0411144 0.186974 0.0811678 -0.0401699 0.186801 0.0811901 -0.0402674 0.186974 0.0995681 -0.0306204 0.186874 0.0977044 -0.0322353 0.186974 0.0976877 -0.0322143 0.186974 0.0926 -0.0356831 0.186874 0.0870618 -0.0383798 0.186974 0.10912 -0.0178789 0.186874 0.106063 -0.0232267 0.186974 0.106041 -0.0232116 0.186974 0.105331 -0.0242196 0.186801 0.106124 -0.023268 0.186801 0.10921 -0.0179223 0.186874 0.112766 -0.00614739 0.186801 0.112839 -0.0061583 0.186801 0.111465 -0.0121762 0.186874 0.111395 -0.0121547 0.186974 0.1123 -0.00856882 0.186774 0.105696 0.0244784 0.186574 0.105857 0.024596 0.186574 0.100003 0.0310978 0.186774 0.0763536 0.041419 0.186774 0.0676463 0.041419 0.186574 0.0676254 0.0416179 0.186574 0.0590676 0.0397989 0.186774 0.051175 0.0360671 0.186774 0.0441307 0.0309491 0.186574 0.0381426 0.024596 0.186574 0.0310645 0.00869825 0.186574 0.03015 -2.85742e-06 0.184974 0.05475 -0.0302738 0.184974 0.054711 -0.0297529 0.183974 0.116117 0.0137793 0.184074 0.114417 0.0121793 0.183974 0.114417 0.0120793 0.184074 0.113617 0.0123937 0.183974 0.113567 0.0123071 0.183974 0.112945 0.0129293 0.185874 0.116017 0.0137793 0.185874 0.115803 0.0129793 0.184074 0.115803 0.0129793 0.184074 0.115217 0.0123937 0.185874 0.114417 0.0121793 0.185874 0.113617 0.0123937 0.184074 0.113031 0.0129793 0.185874 0.113031 0.0129793 0.185974 0.112945 0.0129293 0.185874 0.115217 0.0123937 0.183974 0.116117 -0.013785 0.183974 0.114417 -0.015485 0.184074 0.113031 -0.014585 0.183974 0.112945 -0.014635 0.185874 0.115803 -0.014585 0.184074 0.115803 -0.014585 0.185874 0.114417 -0.015385 0.184074 0.115217 -0.0151707 0.184074 0.114417 -0.015385 0.185874 0.113617 -0.0151707 0.184074 0.113617 -0.0151707 0.185874 0.113031 -0.014585 0.184074 0.112817 -0.013785 0.185974 0.113567 -0.0152573 0.185874 0.115217 -0.0151707 0.184074 0.0990152 -0.0374707 0.184074 0.0982152 -0.037685 0.184074 0.0968295 -0.036885 0.184074 0.0966152 -0.036085 0.184074 0.0998152 -0.036085 0.185874 0.0990152 -0.0374707 0.184074 0.0996008 -0.036885 0.184074 0.0974152 -0.0374707 0.185874 0.0974152 -0.0374707 0.185874 0.0968295 -0.036885 0.185974 0.0967429 -0.036935 0.185974 0.0973652 -0.0375573 0.185874 0.0982152 -0.037685 0.185974 0.0982152 -0.037785 0.185974 0.0990652 -0.0375573 0.185874 0.0996008 -0.036885 0.183974 0.0737 -0.0446029 0.184074 0.072 -0.0462029 0.184074 0.0712 -0.0459885 0.184074 0.0706143 -0.0454029 0.183974 0.0705277 -0.0454529 0.184074 0.0704 -0.0446029 0.185874 0.0736 -0.0446029 0.184074 0.0733856 -0.0454029 0.184074 0.0728 -0.0459885 0.185874 0.0728 -0.0459885 0.185874 0.072 -0.0462029 0.185874 0.0706143 -0.0454029 0.185874 0.0712 -0.0459885 0.185974 0.07115 -0.0460751 0.185874 0.0733856 -0.0454029 0.185974 0.0737 -0.0446029 0.184074 0.0473847 -0.036085 0.183974 0.0474847 -0.036085 0.184074 0.0465847 -0.0374707 0.183974 0.0466347 -0.0375573 0.183974 0.0457847 -0.037785 0.184074 0.0443991 -0.036885 0.183974 0.0449347 -0.0375573 0.183974 0.0440847 -0.036085 0.184074 0.0471704 -0.036885 0.185874 0.0465847 -0.0374707 0.185874 0.0457847 -0.037685 0.184074 0.0457847 -0.037685 0.184074 0.0449847 -0.0374707 0.185874 0.0443991 -0.036885 0.185974 0.0443125 -0.036935 0.185874 0.0449847 -0.0374707 0.185974 0.0457847 -0.037785 0.185874 0.0471704 -0.036885 0.185974 0.047257 -0.036935 0.184074 0.0311828 -0.013785 0.183974 0.0312828 -0.013785 0.184074 0.0309685 -0.014585 0.184074 0.0303828 -0.0151707 0.184074 0.0295828 -0.015385 0.184074 0.0287828 -0.0151707 0.184074 0.0281972 -0.014585 0.184074 0.0279828 -0.013785 0.185874 0.0303828 -0.0151707 0.185874 0.0281972 -0.014585 0.185874 0.0287828 -0.0151707 0.185874 0.0295828 -0.015385 0.185874 0.0309685 -0.014585 0.185874 0.0311828 -0.013785 0.183974 0.0310551 0.0129293 0.184074 0.0303828 0.0123937 0.184074 0.0287828 0.0123937 0.183974 0.0295828 0.0120793 0.183974 0.0287328 0.0123071 0.183974 0.0281106 0.0129293 0.184074 0.0311828 0.0137793 0.185874 0.0309685 0.0129793 0.184074 0.0309685 0.0129793 0.185874 0.0295828 0.0121793 0.184074 0.0295828 0.0121793 0.185874 0.0281972 0.0129793 0.184074 0.0281972 0.0129793 0.184074 0.0279828 0.0137793 0.185974 0.0287328 0.0123071 0.185874 0.0287828 0.0123937 0.185874 0.0303828 0.0123937 0.185974 0.0304328 0.0123071 0.185874 0.0311828 0.0137793 0.184074 0.0473847 0.0360793 0.184074 0.0471704 0.0352793 0.183974 0.0474847 0.0360793 0.184074 0.0465847 0.0346937 0.184074 0.0457847 0.0344793 0.183974 0.0457847 0.0343793 0.185874 0.0473847 0.0360793 0.185874 0.0471704 0.0352793 0.185874 0.0465847 0.0346937 0.185874 0.0457847 0.0344793 0.184074 0.0449847 0.0346937 0.184074 0.0443991 0.0352793 0.184074 0.0441847 0.0360793 0.185974 0.0443125 0.0352293 0.185874 0.0443991 0.0352793 0.185874 0.0449847 0.0346937 0.185974 0.047257 0.0352293 0.183974 0.07285 0.0431249 0.184074 0.072 0.0429971 0.184074 0.0712 0.0432115 0.183974 0.0705277 0.0437471 0.184074 0.0733856 0.0437971 0.185874 0.0728 0.0432115 0.184074 0.0728 0.0432115 0.185874 0.072 0.0429971 0.184074 0.0706143 0.0437971 0.185874 0.0704 0.0445971 0.185874 0.0706143 0.0437971 0.185874 0.0712 0.0432115 0.185974 0.07115 0.0431249 0.185974 0.072 0.0428971 0.185874 0.0733856 0.0437971 0.185974 0.0737 0.0445971 0.184074 0.0990152 0.0346937 0.183974 0.0996874 0.0352293 0.183974 0.0990652 0.0346071 0.184074 0.0982152 0.0344793 0.183974 0.0973652 0.0346071 0.184074 0.0968295 0.0352793 0.184074 0.0966152 0.0360793 0.184074 0.0998152 0.0360793 0.184074 0.0996008 0.0352793 0.185874 0.0996008 0.0352793 0.185874 0.0982152 0.0344793 0.185874 0.0968295 0.0352793 0.184074 0.0974152 0.0346937 0.185974 0.0967429 0.0352293 0.185874 0.0974152 0.0346937 0.185974 0.0973652 0.0346071 0.185874 0.0990152 0.0346937 0.185974 0.0982152 0.0343793 0.185974 0.0996874 0.0352293 0.186274 0.0590676 0.0397989 0.185874 0.0519558 0.0367348 0.185974 0.0518679 0.0366867 0.186274 0.0520438 0.0367827 0.185874 0.0675999 0.0416152 0.186274 0.0675 0.0416045 0.186574 0.0763745 0.0416179 0.186274 0.0844634 0.0399482 0.186274 0.0765 0.0416045 0.185974 0.092132 0.0366867 0.185874 0.0920441 0.0367348 0.185774 0.0919561 0.0367827 0.186574 0.0849323 0.0397989 0.186574 0.092925 0.0362403 0.186574 0.110232 0.0170191 0.185974 0.110232 0.0170191 0.186574 0.112935 0.00869825 0.186574 0.11385 -2.85742e-06 0.185974 0.11385 -2.85742e-06 0.185974 0.051075 0.0362403 0.186574 0.051075 0.0362403 0.185974 0.0439968 0.0310978 0.186574 0.0439968 0.0310978 0.185974 0.0381426 0.024596 0.185974 0.0337681 0.0170191 0.186574 0.0337681 0.0170191 0.185974 0.03015 -2.85742e-06 0.184974 0.112066 0.00328142 0.184974 0.111563 0.00712288 0.186574 0.1122 -2.85742e-06 0.184974 0.110497 0.0115742 0.186574 0.111563 0.00712288 0.184974 0.107231 0.0193568 0.186574 0.102413 0.026286 0.184974 0.0244652 0.00910805 0.184974 0.0270301 0.0178932 0.185774 0.0270301 0.0178932 0.185774 0.0312028 0.0260385 0.184974 0.0368342 0.0332527 0.184974 0.116716 -0.0185247 0.184974 0.112243 -0.0268925 0.185774 0.106224 -0.0342268 0.184974 0.106224 -0.0342268 0.184974 0.0988896 -0.040246 0.185774 0.072 -0.0484029 0.184974 0.072 -0.0484029 0.184974 0.0625576 -0.0474729 0.185774 0.0534781 -0.0447186 0.184974 0.0451104 -0.040246 0.184974 0.037776 -0.0342268 0.185774 0.037776 -0.0342268 0.185774 0.0272842 -0.0185247 0.184974 0.02453 -0.00944523 0.185774 0.0236 -2.85742e-06 0.184974 0.0236 -2.85742e-06 0.186974 0.0312601 0.00613768 0.186974 0.0317003 0.0085631 0.186974 0.0326304 0.0121411 0.187574 0.0343619 0.0167547 0.186974 0.0343619 0.0167547 0.187574 0.0386685 0.0242139 0.186974 0.0417982 0.0280203 0.186974 0.0463122 0.0322086 0.186974 0.0444318 0.0306147 0.186974 0.0514 0.0356774 0.186974 0.0689211 0.0410819 0.187574 0.0676934 0.0409714 0.186974 0.0628321 0.0401642 0.187574 0.0592685 0.0391807 0.186974 0.0569479 0.0383491 0.186974 0.0750788 0.0410819 0.186974 0.0763065 0.0409714 0.186974 0.0811678 0.0401642 0.186974 0.0847315 0.0391807 0.186974 0.087052 0.0383491 0.187574 0.0847315 0.0391807 0.187574 0.0926 0.0356774 0.186974 0.0926 0.0356774 0.186974 0.0976877 0.0322086 0.186974 0.0995681 0.0306147 0.186974 0.102202 0.0280203 0.187574 0.105331 0.0242139 0.186974 0.105331 0.0242139 0.186974 0.106041 0.0232059 0.186974 0.11137 0.0121411 0.185974 0.0515253 0.0371259 0.185974 0.0508 0.0367166 0.185974 0.0310645 0.00869825 0.185974 0.0305265 0.0088126 0.185974 0.0296 -2.85742e-06 0.185974 0.0305265 -0.00881831 0.185974 0.0337681 -0.0170248 0.185974 0.0381426 -0.0246017 0.185974 0.0376976 -0.024925 0.185974 0.0439968 -0.0311035 0.185974 0.0436288 -0.0315122 0.185974 0.051075 -0.036246 0.185974 0.0590676 -0.0398046 0.185974 0.067568 -0.0421706 0.185974 0.076432 -0.0421706 0.185974 0.0849323 -0.0398046 0.185974 0.0932 -0.0367223 0.185974 0.105857 -0.0246017 0.185974 0.110734 -0.0172485 0.185974 0.110232 -0.0170248 0.185974 0.1144 -2.85742e-06 0.185974 0.112935 0.00869825 0.185974 0.113473 0.0088126 0.185974 0.105857 0.024596 0.185974 0.106302 0.0249192 0.185974 0.100003 0.0310978 0.185974 0.092925 0.0362403 0.185974 0.0677 0.0421785 0.185974 0.0763 0.0416256 0.186974 0.1132 -2.85742e-06 0.187574 0.109638 -0.0167604 0.186974 0.11137 -0.0121468 0.186974 0.11274 -0.0061434 0.186974 0.102202 -0.028026 0.187574 0.0995681 -0.0306204 0.186974 0.087052 -0.0383549 0.186974 0.0847315 -0.0391864 0.187574 0.0763065 -0.0409772 0.186974 0.0750788 -0.0410877 0.186974 0.0628321 -0.0401699 0.187574 0.0676934 -0.0409772 0.187574 0.0592685 -0.0391864 0.186974 0.0569479 -0.0383549 0.186974 0.0463122 -0.0322143 0.186974 0.0514 -0.0356831 0.186974 0.0386685 -0.0242196 0.186974 0.0444318 -0.0306204 0.186974 0.03488 -0.0178789 0.186974 0.0326304 -0.0121468 0.187574 0.0317003 -0.00856882 0.187574 0.0308 -2.85742e-06 0.183974 0.0376717 -0.0227847 0.183974 0.106316 0.0249293 0.183974 0.0851727 -0.0455357 0.183974 0.0588923 -0.0403439 0.183974 0.0325883 -0.0263369 0.183974 0.0375608 0.0325656 0.183974 0.0375804 0.0226407 0.183974 0.051098 0.0299971 0.183974 0.0515 0.0314971 0.183974 0.047257 0.0352293 0.183974 0.0513477 0.0359579 0.183974 0.047257 0.0369293 0.183974 0.0440847 0.0360793 0.183974 0.0443125 0.0352293 0.183974 0.0478858 0.0390223 0.183974 0.0457847 0.0377793 0.183974 0.0443072 0.0384662 0.183974 0.05 0.0288991 0.183974 0.0466347 0.0346071 0.183974 0.0485 0.0284971 0.183974 0.0442351 0.0284971 0.183974 0.0449347 0.0346071 0.183974 0.0254473 0.00891981 0.183974 0.0281106 0.0146293 0.183974 0.0308 -2.85742e-06 0.183974 0.0314524 0.00730014 0.183974 0.0304328 0.0123071 0.183974 0.0312828 0.0137793 0.183974 0.0365484 0.0209883 0.183974 0.0310551 0.0146293 0.183974 0.0376838 0.0249293 0.183974 0.0320457 0.0255004 0.183974 0.0287328 0.0152515 0.183974 0.0281106 -0.012935 0.183974 0.0310551 -0.014635 0.183974 0.0310551 -0.012935 0.183974 0.0304328 -0.0123128 0.183974 0.0295828 -0.012085 0.183974 0.0262414 -2.85742e-06 0.183974 0.0255107 -0.00925014 0.183974 0.0278828 -0.013785 0.183974 0.0281106 -0.014635 0.183974 0.0287328 -0.0152573 0.183974 0.0317247 -0.0249961 0.183974 0.0295828 -0.015485 0.183974 0.0304328 -0.0152573 0.183974 0.0443125 -0.035235 0.183974 0.0384831 -0.0335197 0.183974 0.0506492 -0.0347335 0.183974 0.047257 -0.035235 0.183974 0.0466347 -0.0346128 0.183974 0.0457847 -0.034385 0.183974 0.0376838 -0.024935 0.183974 0.0449347 -0.0346128 0.183974 0.0443125 -0.036935 0.183974 0.0456659 -0.0394145 0.183974 0.0473327 -0.0404786 0.183974 0.0527214 -0.0345265 0.183974 0.0554468 -0.0346421 0.183974 0.0544784 -0.0334087 0.183974 0.047257 -0.036935 0.183974 0.0559017 -0.0359822 0.183974 0.0567947 -0.03708 0.183974 0.072 -0.0429029 0.183974 0.07115 -0.0431306 0.183974 0.0705277 -0.0437529 0.183974 0.0703 -0.0446029 0.183974 0.07115 -0.0460751 0.183974 0.072 -0.0463029 0.183974 0.07285 -0.0460751 0.183974 0.0734722 -0.0454529 0.183974 0.0734722 -0.0437529 0.183974 0.106412 -0.0226584 0.183974 0.0967429 -0.036935 0.183974 0.0859858 -0.0377982 0.183974 0.098334 -0.0394145 0.183974 0.0990652 -0.0375573 0.183974 0.0996874 -0.036935 0.183974 0.0999152 -0.036085 0.183974 0.106399 -0.0326137 0.183974 0.0990652 -0.0346128 0.183974 0.101876 -0.028373 0.183974 0.0982152 -0.034385 0.183974 0.0952942 -0.0339855 0.183974 0.0982152 -0.037785 0.183974 0.0973652 -0.0375573 0.183974 0.0901392 -0.0437947 0.183974 0.0851076 -0.0403439 0.183974 0.0967429 -0.035235 0.183974 0.0880983 -0.0359822 0.183974 0.0885531 -0.0346421 0.183974 0.112717 -0.013785 0.183974 0.107141 -0.02151 0.183974 0.115267 -0.0152573 0.183974 0.115792 -0.0181421 0.183974 0.113567 -0.0152573 0.183974 0.106316 -0.024935 0.183974 0.115889 -0.014635 0.183974 0.115889 -0.012935 0.183974 0.1132 -7.91805e-06 0.183974 0.114417 -0.012085 0.183974 0.110857 -0.013699 0.183974 0.112945 -0.012935 0.183974 0.115889 0.0129293 0.183974 0.118553 0.00891981 0.183974 0.115267 0.0152515 0.183974 0.111954 0.0255004 0.183974 0.108108 0.0198384 0.183974 0.115267 0.0123071 0.183974 0.112717 0.0137793 0.183974 0.106439 0.0325656 0.183974 0.0943519 0.0287255 0.183974 0.0955 0.0284971 0.183974 0.104719 0.0250349 0.183974 0.0982152 0.0343793 0.183974 0.0999152 0.0360793 0.183974 0.09797 0.0391725 0.183974 0.0982152 0.0377793 0.183974 0.0973652 0.0375515 0.183974 0.0945273 0.0380483 0.183974 0.0967429 0.0369293 0.183974 0.0933786 0.0293758 0.183974 0.0927283 0.0303491 0.183974 0.0967429 0.0352293 0.183974 0.0925 0.0314971 0.183974 0.0648958 -0.0396717 0.183974 0.072 -0.0403029 0.187574 0.0521971 -0.0262029 0.187574 0.0520965 -0.0265782 0.187574 0.0520965 0.0258218 0.187574 0.0919034 0.0258218 0.187574 0.0518217 0.025547 0.187574 0.0919034 0.0265725 0.187574 0.0519144 -0.0256159 0.187574 0.0919034 -0.0265782 0.187574 0.0518217 0.0268473 0.187574 0.0514 0.0356774 0.187574 0.0444318 0.0306147 0.187574 0.0521971 0.0261971 0.187574 0.0918028 0.0261971 0.187574 0.0763065 0.0409714 0.187574 0.0514 -0.0356831 0.187574 0.0925535 0.0269479 0.187574 0.0995681 0.0306147 0.187574 0.0932037 0.0265725 0.187574 0.0933043 0.0261971 0.187574 0.109638 0.0167547 0.187574 0.105331 -0.0242196 0.187574 0.1123 -0.00856882 0.187574 0.1132 -2.85742e-06 0.187574 0.0932037 -0.0265782 0.187574 0.0926 -0.0356831 0.187574 0.0925535 -0.0269536 0.187574 0.0847315 -0.0391864 0.187574 0.0507962 0.0265725 0.187574 0.0506957 0.0261971 0.187574 0.0507962 0.0258218 0.187574 0.0317003 0.0085631 0.187574 0.0514464 -0.0269536 0.187574 0.0444318 -0.0306204 0.187574 0.0386685 -0.0242196 0.187574 0.0343619 -0.0167604 0.187574 0.0516134 -0.025471 0.187574 0.0921782 0.025547 0.187574 0.0921782 -0.0255527 0.187574 0.0925535 -0.0254521 0.187574 0.0929289 -0.0255527 0.187574 0.0929289 0.025547 0.187574 0.1123 0.0085631 0.185774 0.107166 0.0332527 0.184974 0.107166 0.0332527 0.185774 0.112797 0.0260385 0.184974 0.112797 0.0260385 0.185774 0.11697 0.0178932 0.185774 0.119535 0.00910805 0.185774 0.1204 -2.85742e-06 0.184974 0.1204 -2.85742e-06 0.186574 0.0415872 0.026286 0.186574 0.0367687 0.0193568 0.184974 0.0343261 0.0140229 0.186574 0.0335031 0.0115742 0.184974 0.0318 -2.85742e-06 0.186574 0.0319343 0.00328142 0.184974 0.0319343 0.00328142 0.184974 0.037712 -0.020988 0.184974 0.0347874 -0.0152103 0.184974 0.0340862 -0.0133666 0.186574 0.0321316 -0.00515616 0.184974 0.0325539 -0.00775193 0.184974 0.0492711 -0.0331607 0.186574 0.105583 -0.0220983 0.186574 0.111446 -0.00775193 0.184974 0.109914 -0.0133666 0.184974 0.109212 -0.0152103 0.183974 0.0705277 0.0454471 0.183974 0.0703 0.0445971 0.183974 0.07285 0.0460694 0.183974 0.068757 0.0463532 0.183974 0.0685 0.0334971 0.183974 0.07115 0.0431249 0.183974 0.072 0.0428971 0.183974 0.0695 0.0324971 0.183974 0.075 0.0326311 0.183974 0.0745 0.0324971 0.183974 0.0734722 0.0437471 0.183974 0.0755 0.0453724 0.183974 0.0737 0.0445971 0.183974 0.0752429 0.0463532 0.183974 0.073566 0.0473713 0.186574 0.0953102 -0.022669 0.186574 0.0968461 -0.0218694 0.186574 0.0898056 -0.0263191 0.186574 0.0947288 -0.0331607 0.186574 0.109674 0.0140229 0.186574 0.100694 -0.0281575 0.186574 0.0923608 -0.0234593 0.186574 0.0485 0.0274971 0.186574 0.097275 0.00449714 0.186574 0.0745 0.0314971 0.186574 0.0932268 -0.0337412 0.186574 0.0902594 -0.0327329 0.186574 0.098275 -0.0188053 0.186574 0.109212 -0.0152103 0.186574 0.037712 -0.020988 0.186574 0.0428491 -0.0276844 0.186574 0.106591 0.0204788 0.186574 0.0853753 0.0347094 0.186574 0.045725 0.00349714 0.186574 0.0340862 -0.0133666 0.186574 0.091625 0.0305049 0.186574 0.054425 -0.0317466 0.186574 0.0506697 -0.0337254 0.186574 0.0492711 -0.0331607 0.186574 0.054711 -0.0297529 0.186574 0.0804094 0.0362341 0.186574 0.0675053 0.0333509 0.186574 0.0635905 0.0362341 0.185774 0.0735991 0.0483707 0.184974 0.0735991 0.0483707 0.185974 0.112935 -0.00870396 0.186574 0.100003 -0.0311035 0.185974 0.100003 -0.0311035 0.186574 0.092925 -0.036246 0.186574 0.0849323 -0.0398046 0.185974 0.092925 -0.036246 0.185974 0.0763745 -0.0416236 0.186574 0.0676254 -0.0416236 0.185974 0.0676254 -0.0416236 0.186574 0.0590676 -0.0398046 0.185974 0.0310645 -0.00870396 0.186574 0.0310645 -0.00870396 0.186774 0.0998693 -0.0309548 0.186774 0.112938 -0.00617321 0.186774 0.110049 -0.0169434 0.186774 0.105696 -0.0244841 0.186774 0.106206 -0.0233243 0.186774 0.0927 -0.0358563 0.186774 0.0871251 -0.038541 0.186774 0.0848705 -0.0396144 0.186774 0.0812123 -0.0403649 0.186774 0.0627876 -0.0403649 0.186774 0.0346998 -0.0179656 0.186774 0.0339508 -0.0169434 0.186774 0.0310624 -0.00617321 0.186774 0.03035 -2.85742e-06 0.186774 0.11274 0.00865666 0.186774 0.111561 0.0122 0.186774 0.11365 -2.85742e-06 0.186774 0.112938 0.00616749 0.186774 0.0848705 0.0396086 0.186774 0.092825 0.0360671 0.186774 0.0871251 0.0385353 0.186774 0.0927 0.0358506 0.186774 0.0998693 0.0309491 0.186774 0.102348 0.0281563 0.186774 0.1093 0.0179599 0.186774 0.110049 0.0169377 0.186774 0.0312601 0.00865666 0.186774 0.0339508 0.0169377 0.186774 0.0383044 0.0244784 0.186774 0.0416516 0.0281563 0.186774 0.0461875 0.032365 0.186774 0.0513 0.0358506 0.186774 0.0627876 0.0403592 0.186774 0.0591294 0.0396086 0.186774 0.0750938 0.0412814 0.175524 0.0859858 -0.0377982 0.183974 0.0791041 -0.0396717 0.175524 0.072 -0.0403029 0.175524 0.0648958 -0.0396717 0.183974 0.0580141 -0.0377982 0.186574 0.045725 -0.0188053 0.175524 0.045725 0.00349714 0.182296 0.0496 0.00449714 0.175524 0.074175 0.00449714 0.179974 0.0734722 0.00449714 0.180824 0.0737 0.00449714 0.182482 0.0723782 0.00449714 0.184951 0.052975 0.00449714 0.181562 0.0735316 0.00449714 0.180087 0.0472183 0.00449714 0.180824 0.04705 0.00449714 0.181674 0.0472777 0.00449714 0.175524 0.046725 0.00449714 0.179495 0.04769 0.00449714 0.183249 0.0512729 0.00449714 0.178399 0.068727 0.00449714 0.179352 0.07115 0.00449714 0.176697 0.067025 0.00449714 0.179124 0.072 0.00449714 0.182153 0.07094 0.00449714 0.180824 0.0703 0.00449714 0.179167 0.0491282 0.00449714 0.177436 0.0520119 0.00449714 0.176428 0.0535205 0.00449714 0.176074 0.0647 0.00449714 0.18522 0.0664794 0.00449714 0.186574 0.046725 0.00449714 0.184049 0.074175 0.00449714 0.184951 0.076975 0.00449714 0.183249 0.0752729 0.00449714 0.178399 0.092727 0.00449714 0.177436 0.0760119 0.00449714 0.176428 0.0775205 0.00449714 0.179974 0.0967222 0.00449714 0.180824 0.09695 0.00449714 0.181562 0.0967816 0.00449714 0.180924 0.07465 0.00449714 0.176074 0.0887 0.00449714 0.175524 0.097275 0.00449714 0.179352 0.0944 0.00449714 0.184212 0.091988 0.00449714 0.182153 0.09419 0.00449714 0.182704 0.092996 0.00449714 0.180924 0.09335 0.00449714 0.18522 0.0904794 0.00449714 0.185574 0.0887 0.00449714 0.186574 0.074175 0.00449714 0.175524 0.098275 -0.0188053 0.186574 0.0892889 -0.0297529 0.184974 0.0892889 -0.0297529 0.184964 0.0892494 -0.030015 0.184935 0.0892105 -0.0302738 0.175524 0.0898056 -0.0263191 0.183974 0.088868 -0.0325499 0.183974 0.055132 -0.0325499 0.184581 0.0549646 -0.0314379 0.175524 0.0516391 -0.0234593 0.175524 0.0486897 -0.022669 0.186574 0.0516391 -0.0234593 0.186574 0.0486897 -0.022669 0.175024 0.0908512 -0.0236517 0.175024 0.0898275 -0.0247975 0.175024 0.0462919 0.00374714 0.175024 0.0488191 -0.022186 0.175024 0.0922314 -0.0229763 0.175024 0.097775 0.00349714 0.175024 0.0559413 -0.0345676 0.175024 0.072 -0.0398029 0.175024 0.0546887 -0.0262447 0.175024 0.0880587 -0.0345676 0.175024 0.0868793 -0.0367009 0.175024 0.0893112 -0.0262447 0.175024 0.0541725 -0.0247975 0.175024 0.0531487 -0.0236517 0.186574 0.0997649 0.0274971 0.184974 0.0955 0.0274971 0.186574 0.0955 0.0274971 0.185774 0.0675 0.0416045 0.184974 0.0675 0.0453724 0.186074 0.0675 0.0343039 0.186074 0.0675 0.0414033 0.186266 0.0765 0.0334971 0.185774 0.0765 0.0453724 0.185774 0.0765 0.0416045 0.186074 0.0765 0.0414033 0.186074 0.0765 0.0343039 0.184974 0.0765 0.0334971 0.184974 0.0525 0.0351925 0.184974 0.0516213 0.0373138 0.186074 0.0673028 0.0347375 0.186074 0.0635453 0.036429 0.186074 0.0525 0.0314971 0.186074 0.0525 0.0351925 0.186074 0.0521442 0.0366096 0.184974 0.0938202 0.0387554 0.186074 0.0776557 0.0358442 0.186074 0.0912223 0.031781 0.186074 0.0915 0.0314971 0.186074 0.0918557 0.0366096 0.186074 0.0917283 0.0363406 0.186074 0.0915 0.0351925 0.186074 0.0804547 0.036429 0.186074 0.0844039 0.0397572 0.185774 0.0458764 0.0401606 0.185774 0.0481962 0.0399729 0.184974 0.0481962 0.0399729 0.185774 0.0938202 0.0387554 0.184974 0.0958038 0.0399729 0.184974 0.0761144 0.0468436 0.185774 0.0689431 0.0479368 0.184974 0.0689431 0.0479368 0.184974 0.0704008 0.0483707 0.186574 0.0764946 0.0333509 0.186272 0.0764986 0.0334241 0.186574 0.076232 0.0324971 0.186574 0.0755 0.0317651 0.184974 0.0675 0.0334971 0.186266 0.0675 0.0334971 0.184974 0.0677679 0.0324971 0.186574 0.0676522 0.0327318 0.186574 0.0680857 0.0320829 0.186574 0.0687346 0.0316494 0.184974 0.0695 0.0314971 0.186574 0.0695 0.0314971 0.186574 0.0586247 0.0347094 0.186574 0.0902574 -0.0250528 0.175524 0.0902574 -0.0250528 0.186574 0.0911531 -0.0240502 0.175524 0.0911531 -0.0240502 0.186574 0.0528468 -0.0240502 0.186574 0.0537426 -0.0250528 0.186574 0.0541943 -0.0263191 0.175524 0.0537426 -0.0250528 0.186574 0.0979002 -0.0204957 0.186574 0.0471538 -0.0218694 0.175524 0.0471538 -0.0218694 0.186574 0.0460997 -0.0204957 0.175524 0.0460997 -0.0204957 0.175524 0.0580141 -0.0377982 0.175524 0.0559017 -0.0359822 0.183974 0.0872052 -0.03708 0.186574 0.097775 0.00436317 0.175524 0.097775 0.00436317 0.186574 0.098141 0.00399714 0.175524 0.098141 0.00399714 0.186574 0.098275 0.00349714 0.186574 0.0458589 0.00399714 0.175524 0.0458589 0.00399714 0.186574 0.046225 0.00436317 0.184974 0.0522716 0.0363406 0.186074 0.0522716 0.0363406 0.186274 0.0919561 0.0367827 0.184974 0.0923786 0.0373138 0.184974 0.0917283 0.0363406 0.186574 0.0519641 0.0294971 0.186274 0.0523749 0.0305049 0.184974 0.0519641 0.0294971 0.186574 0.0505 0.028033 0.184974 0.0505 0.028033 0.184974 0.0485 0.0274971 0.184974 0.0918044 0.0299664 0.186574 0.0918044 0.0299664 0.184974 0.0926715 0.0286687 0.186574 0.0926715 0.0286687 0.186574 0.0939692 0.0278016 0.186574 0.0539196 0.0325078 0.186574 0.052941 0.0316655 0.186574 0.0523749 0.0305049 0.186574 0.0910589 0.0316655 0.186274 0.0910637 0.0316593 0.186574 0.0900803 0.0325078 0.186574 0.0790397 0.036251 0.186274 0.0790316 0.0362493 0.186274 0.0777751 0.0356837 0.186574 0.0777884 0.0356936 0.186574 0.0768848 0.034664 0.186274 0.0768729 0.0346422 0.186574 0.0671151 0.034664 0.186274 0.0675053 0.0333509 0.186274 0.067127 0.0346422 0.186574 0.0662115 0.0356936 0.186574 0.0649602 0.036251 0.180724 0.07525 -0.00670286 0.180924 0.07525 -0.00670286 0.178699 0.0922074 -0.00670286 0.178699 0.0922074 0.00284866 0.177217 0.090725 -0.00670286 0.180924 0.09275 -0.00670286 0.180724 0.09275 0.00284866 0.184666 0.0902498 -0.00670286 0.183788 0.0915637 -0.00670286 0.183788 0.0915637 0.00284866 0.182474 0.0924417 0.00284866 0.182949 0.0757926 -0.00670286 0.180924 0.07525 0.00284866 0.184432 0.077275 -0.00670286 0.176674 0.0793 -0.00670286 0.176983 0.0777501 -0.00670286 0.17786 0.0764362 -0.00670286 0.176674 0.0793 0.00284866 0.180724 0.06875 0.00284866 0.178699 0.0682074 -0.00670286 0.177217 0.066725 0.00284866 0.177217 0.066725 -0.00670286 0.184666 0.0662498 -0.00670286 0.184974 0.0647 0.00284866 0.184666 0.0662498 0.00284866 0.183788 0.0675637 0.00284866 0.182474 0.0684417 -0.00670286 0.182474 0.0684417 0.00284866 0.184974 0.0553 0.00284866 0.180924 0.05125 0.00284866 0.182949 0.0517926 -0.00670286 0.184432 0.053275 -0.00670286 0.184432 0.053275 0.00284866 0.184974 0.0553 -0.00670286 0.176983 0.0537501 -0.00670286 0.17786 0.0524362 -0.00670286 0.17786 0.0524362 0.00284866 0.180724 0.05125 -0.00670286 0.180724 0.05125 0.00284866 0.176674 0.0553 0.00284866 0.175024 0.097775 -0.0188053 0.175524 0.098275 0.00349714 0.175024 0.097447 -0.0202844 0.175524 0.0979002 -0.0204957 0.175524 0.0968461 -0.0218694 0.175524 0.0953102 -0.022669 0.175024 0.0965247 -0.0214864 0.175024 0.097525 0.00393016 0.175024 0.097708 0.00374714 0.175024 0.0951808 -0.022186 0.175024 0.097275 0.00399714 0.175024 0.046725 0.00399714 0.175524 0.0923608 -0.0234593 0.175024 0.046475 0.00393016 0.175524 0.046225 0.00436317 0.175024 0.046225 0.00349714 0.175524 0.0885531 -0.0346421 0.175524 0.0880983 -0.0359822 0.175024 0.0876607 -0.0357402 0.175524 0.0872052 -0.03708 0.175024 0.0858123 -0.0373293 0.175024 0.0474752 -0.0214864 0.175024 0.0465529 -0.0202844 0.175524 0.045725 -0.0188053 0.175024 0.046225 -0.0188053 0.175524 0.0791041 -0.0396717 0.175024 0.079016 -0.0391796 0.175024 0.0649839 -0.0391796 0.175524 0.0567947 -0.03708 0.175024 0.0581876 -0.0373293 0.175024 0.0571206 -0.0367009 0.175024 0.0563392 -0.0357402 0.175524 0.0554468 -0.0346421 0.175524 0.0528468 -0.0240502 0.175024 0.0517685 -0.0229763 0.175524 0.0541943 -0.0263191 0.185974 0.0999152 0.0360793 0.185874 0.0996008 0.0368793 0.185974 0.0996874 0.0369293 0.185974 0.0990652 0.0375515 0.185874 0.0982152 0.0376793 0.185874 0.0966152 0.0360793 0.184074 0.0968295 0.0368793 0.185874 0.0968295 0.0368793 0.185874 0.0974152 0.0374649 0.184074 0.0974152 0.0374649 0.185874 0.0990152 0.0374649 0.184074 0.0996008 0.0368793 0.185874 0.0998152 0.0360793 0.183974 0.0965152 0.0360793 0.184074 0.0982152 0.0376793 0.184074 0.0990152 0.0374649 0.183974 0.0990652 0.0375515 0.183974 0.0996874 0.0369293 0.185874 0.0736 0.0445971 0.185874 0.0728 0.0459828 0.185974 0.0705277 0.0454471 0.184074 0.0704 0.0445971 0.185874 0.0706143 0.0453971 0.184074 0.0712 0.0459828 0.185874 0.0712 0.0459828 0.185874 0.072 0.0461971 0.184074 0.072 0.0461971 0.184074 0.0728 0.0459828 0.184074 0.0733856 0.0453971 0.185874 0.0733856 0.0453971 0.184074 0.0706143 0.0453971 0.183974 0.07115 0.0460694 0.183974 0.072 0.0462971 0.183974 0.0734722 0.0454471 0.184074 0.0736 0.0445971 0.185974 0.0466347 0.0375515 0.185874 0.0457847 0.0376793 0.185874 0.0449847 0.0374649 0.185974 0.0449347 0.0375515 0.185874 0.0443991 0.0368793 0.185874 0.0441847 0.0360793 0.185874 0.0465847 0.0374649 0.185874 0.0471704 0.0368793 0.184074 0.0465847 0.0374649 0.184074 0.0471704 0.0368793 0.184074 0.0443991 0.0368793 0.183974 0.0443125 0.0369293 0.184074 0.0449847 0.0374649 0.183974 0.0449347 0.0375515 0.184074 0.0457847 0.0376793 0.183974 0.0466347 0.0375515 0.185974 0.0310551 0.0146293 0.185874 0.0309685 0.0145793 0.185874 0.0295828 0.0153793 0.185974 0.0304328 0.0152515 0.185974 0.0295828 0.0154793 0.185974 0.0287328 0.0152515 0.185974 0.0281106 0.0146293 0.185874 0.0279828 0.0137793 0.185974 0.0278828 0.0137793 0.185874 0.0281972 0.0145793 0.185874 0.0287828 0.0151649 0.184074 0.0281972 0.0145793 0.185874 0.0303828 0.0151649 0.183974 0.0278828 0.0137793 0.184074 0.0287828 0.0151649 0.184074 0.0295828 0.0153793 0.183974 0.0295828 0.0154793 0.183974 0.0304328 0.0152515 0.184074 0.0303828 0.0151649 0.184074 0.0309685 0.0145793 0.185974 0.0310551 -0.012935 0.185874 0.0295828 -0.012185 0.185874 0.0287828 -0.0123994 0.185874 0.0281972 -0.012985 0.185974 0.0287328 -0.0123128 0.185974 0.0281106 -0.012935 0.185874 0.0279828 -0.013785 0.184074 0.0281972 -0.012985 0.184074 0.0295828 -0.012185 0.185874 0.0303828 -0.0123994 0.184074 0.0303828 -0.0123994 0.185874 0.0309685 -0.012985 0.184074 0.0309685 -0.012985 0.184074 0.0287828 -0.0123994 0.183974 0.0287328 -0.0123128 0.185874 0.0473847 -0.036085 0.185874 0.0471704 -0.035285 0.185974 0.0474847 -0.036085 0.185974 0.0466347 -0.0346128 0.185874 0.0449847 -0.0346994 0.185974 0.0443125 -0.035235 0.185874 0.0441847 -0.036085 0.185974 0.0440847 -0.036085 0.185874 0.0443991 -0.035285 0.184074 0.0443991 -0.035285 0.184074 0.0449847 -0.0346994 0.185874 0.0457847 -0.034485 0.185874 0.0465847 -0.0346994 0.184074 0.0441847 -0.036085 0.184074 0.0457847 -0.034485 0.184074 0.0465847 -0.0346994 0.184074 0.0471704 -0.035285 0.185974 0.0734722 -0.0437529 0.185874 0.072 -0.0430029 0.185974 0.072 -0.0429029 0.185974 0.07115 -0.0431306 0.185874 0.0704 -0.0446029 0.185874 0.0706143 -0.0438029 0.185874 0.0712 -0.0432172 0.184074 0.072 -0.0430029 0.185874 0.0728 -0.0432172 0.184074 0.0728 -0.0432172 0.185874 0.0733856 -0.0438029 0.184074 0.0736 -0.0446029 0.184074 0.0706143 -0.0438029 0.184074 0.0712 -0.0432172 0.183974 0.07285 -0.0431306 0.184074 0.0733856 -0.0438029 0.185974 0.0999152 -0.036085 0.185874 0.0990152 -0.0346994 0.185974 0.0990652 -0.0346128 0.185874 0.0982152 -0.034485 0.185974 0.0982152 -0.034385 0.185974 0.0973652 -0.0346128 0.185874 0.0966152 -0.036085 0.185874 0.0968295 -0.035285 0.185874 0.0974152 -0.0346994 0.184074 0.0974152 -0.0346994 0.184074 0.0990152 -0.0346994 0.185874 0.0996008 -0.035285 0.185874 0.0998152 -0.036085 0.183974 0.0965152 -0.036085 0.184074 0.0968295 -0.035285 0.184074 0.0982152 -0.034485 0.183974 0.0973652 -0.0346128 0.184074 0.0996008 -0.035285 0.183974 0.0996874 -0.035235 0.185974 0.115889 -0.012935 0.185874 0.115217 -0.0123994 0.185974 0.115267 -0.0123128 0.185874 0.113617 -0.0123994 0.185974 0.113567 -0.0123128 0.185874 0.112817 -0.013785 0.185874 0.113031 -0.012985 0.184074 0.113031 -0.012985 0.185874 0.114417 -0.012185 0.184074 0.114417 -0.012185 0.184074 0.115217 -0.0123994 0.185874 0.115803 -0.012985 0.185874 0.116017 -0.013785 0.184074 0.115803 -0.012985 0.184074 0.113617 -0.0123994 0.183974 0.113567 -0.0123128 0.183974 0.115267 -0.0123128 0.184074 0.116017 -0.013785 0.185874 0.115217 0.0151649 0.185874 0.113617 0.0151649 0.185874 0.113031 0.0145793 0.185974 0.112945 0.0146293 0.185974 0.112717 0.0137793 0.185874 0.112817 0.0137793 0.184074 0.113031 0.0145793 0.184074 0.113617 0.0151649 0.185874 0.114417 0.0153793 0.184074 0.115217 0.0151649 0.185874 0.115803 0.0145793 0.184074 0.116017 0.0137793 0.184074 0.112817 0.0137793 0.183974 0.112945 0.0146293 0.183974 0.113567 0.0152515 0.184074 0.114417 0.0153793 0.183974 0.114417 0.0154793 0.184074 0.115803 0.0145793 0.183974 0.115889 0.0146293 0.185574 0.0793 0.00449714 0.184974 0.0793 0.00284866 0.184974 0.0887 0.00284866 0.184666 0.0902498 0.00284866 0.180924 0.09275 0.00284866 0.182949 0.0757926 0.00284866 0.184432 0.077275 0.00284866 0.180724 0.07465 0.00449714 0.180724 0.09335 0.00449714 0.177217 0.090725 0.00284866 0.176674 0.0887 0.00284866 0.176697 0.091025 0.00449714 0.176983 0.0777501 0.00284866 0.17786 0.0764362 0.00284866 0.178945 0.0750039 0.00449714 0.179174 0.0755582 0.00284866 0.180724 0.07525 0.00284866 0.176074 0.0793 0.00449714 0.185574 0.0647 0.00449714 0.185574 0.0553 0.00449714 0.184212 0.067988 0.00449714 0.180924 0.06875 0.00284866 0.182704 0.068996 0.00449714 0.180924 0.05065 0.00449714 0.182949 0.0517926 0.00284866 0.180724 0.06935 0.00449714 0.180924 0.06935 0.00449714 0.178699 0.0682074 0.00284866 0.176674 0.0647 0.00284866 0.176983 0.0537501 0.00284866 0.179174 0.0515582 0.00284866 0.178945 0.0510039 0.00449714 0.180724 0.05065 0.00449714 0.176074 0.0553 0.00449714 0.184974 0.0442351 0.0274971 0.186574 0.0442351 0.0274971 0.184974 0.0427792 0.02718 0.186574 0.0427792 0.02718 0.184974 0.102413 0.026286 0.184974 0.101221 0.02718 0.186574 0.101221 0.02718 0.184974 0.0997649 0.0274971 0.186574 0.0521761 -0.0336491 0.186574 0.0535104 -0.032946 0.184974 0.053761 -0.032712 0.186574 0.05475 -0.0302738 0.186574 0.0894219 -0.0313576 0.184974 0.0894219 -0.0313576 0.184974 0.0904895 -0.032946 0.186574 0.091624 -0.0335877 0.184974 0.0918239 -0.0336491 0.186774 0.0312601 -0.00866238 0.186574 0.0337681 -0.0170248 0.186574 0.0381426 -0.0246017 0.186774 0.0383044 -0.0244841 0.186774 0.0441307 -0.0309548 0.186574 0.0439968 -0.0311035 0.186574 0.051075 -0.036246 0.186774 0.051175 -0.0360728 0.186774 0.0591294 -0.0396144 0.186774 0.0676463 -0.0414247 0.186574 0.0763745 -0.0416236 0.186774 0.0763536 -0.0414247 0.186774 0.092825 -0.0360728 0.186574 0.105857 -0.0246017 0.186574 0.110232 -0.0170248 0.186574 0.112935 -0.00870396 0.186774 0.11274 -0.00866238 0.186974 0.03488 0.0178732 0.186974 0.0676934 0.0409714 0.186874 0.0326048 0.012149 0.186801 0.106124 0.0232623 0.186774 0.0324392 0.0122 0.186774 0.106206 0.0233186 0.186801 0.09265 0.035764 0.186774 0.0978124 0.032365 0.186774 0.0812123 0.0403592 0.186774 0.0689061 0.0412814 0.186801 0.0689136 0.0411817 0.186774 0.0568748 0.0385353 0.186801 0.0462498 0.0322868 0.186801 0.0325348 0.0121705 0.186774 0.0346998 0.0179599 0.186801 0.0347899 0.0179165 0.186774 0.0377937 0.0233186 0.186874 0.111395 0.012149 0.186874 0.109144 0.0178848 0.186801 0.0870885 0.0384422 0.186801 0.0811901 0.0402617 0.186874 0.0750808 0.0411087 0.186801 0.0569114 0.0384422 0.186874 0.0513866 0.0357006 0.186801 0.05135 0.035764 0.186801 0.0417249 0.0280883 0.186874 0.0417786 0.0280385 0.186874 0.0379368 0.023221 0.186801 0.0378763 0.0232623 0.186774 0.1134 -2.85742e-06 0.186801 0.1133 -2.85742e-06 0.186874 0.112766 0.00614168 0.186874 0.113227 -2.85742e-06 0.186974 0.11274 0.00613768 0.186801 0.111465 0.0121705 0.186801 0.112839 0.00615259 0.186974 0.1123 0.0085631 0.186974 0.10912 0.0178732 0.186974 0.109638 0.0167547 0.186801 0.10921 0.0179165 0.186874 0.106063 0.023221 0.186874 0.102221 0.0280385 0.186801 0.0977501 0.0322868 0.186801 0.102275 0.0280883 0.186874 0.0811738 0.0401903 0.186874 0.0870618 0.0383741 0.186874 0.0926134 0.0357006 0.186874 0.0977044 0.0322296 0.186801 0.0750863 0.0411817 0.186874 0.0689191 0.0411087 0.186801 0.0628098 0.0402617 0.186874 0.0569381 0.0383741 0.186974 0.0592685 0.0391807 0.186874 0.0628261 0.0401903 0.186874 0.0462955 0.0322296 0.186974 0.0379589 0.0232059 0.186974 0.0386685 0.0242139 0.186874 0.0348559 0.0178848 0.186874 0.0312336 0.00614168 0.186774 0.0310624 0.00616749 0.186801 0.0311612 0.00615259 0.186874 0.0307732 -2.85742e-06 0.180199 0.0730825 -0.00500286 0.180199 0.0709174 -0.00500286 0.179574 0.072 -0.00500286 0.179742 0.071375 -0.00500286 0.179742 0.072625 -0.00500286 0.179742 0.072625 0.00404714 0.179742 0.071375 0.00404714 0.180824 0.07075 0.00404714 0.180824 0.07325 0.00404714 0.180199 0.0730825 0.00404714 0.179352 0.07285 0.00449714 0.179574 0.072 0.00404714 0.180199 0.0709174 0.00404714 0.179974 0.0705277 0.00449714 0.179742 0.094625 -0.00500286 0.180824 0.0965 0.00404714 0.180199 0.0963325 -0.00500286 0.179742 0.095875 -0.00500286 0.180199 0.0963325 0.00404714 0.179574 0.09525 -0.00500286 0.179574 0.09525 0.00404714 0.179742 0.094625 0.00404714 0.180199 0.0941674 -0.00500286 0.180199 0.0941674 0.00404714 0.179742 0.095875 0.00404714 0.179352 0.0961 0.00449714 0.179124 0.09525 0.00449714 0.179974 0.0937777 0.00449714 0.180824 0.09355 0.00449714 0.180824 0.05 -0.00500286 0.179606 0.0490281 -0.00500286 0.180282 0.0498762 -0.00500286 0.179847 0.0495293 -0.00500286 0.179847 0.0479706 -0.00500286 0.179606 0.0484718 -0.00500286 0.180824 0.04875 -0.00575393 0.179847 0.0495293 0.00404714 0.179606 0.0490281 0.00404714 0.179606 0.0484718 0.00404714 0.180282 0.0476237 -0.00500286 0.180824 0.0475 0.00404714 0.180824 0.05045 0.00449714 0.180087 0.0502816 0.00449714 0.180282 0.0498762 0.00404714 0.179495 0.0498099 0.00449714 0.179167 0.0483717 0.00449714 0.179847 0.0479706 0.00404714 0.180282 0.0476237 0.00404714 0.184974 0.076232 0.0324971 0.183974 0.075366 0.0329971 0.184974 0.0755 0.0317651 0.184974 0.0745 0.0314971 0.184974 0.0685 0.0317651 0.183974 0.069 0.0326311 0.184974 0.0680857 0.0320829 0.183974 0.0686339 0.0329971 0.183974 0.0755 0.0334971 0.183974 0.0685 0.0453724 0.184974 0.0750568 0.0479368 0.183974 0.0745379 0.047082 0.184974 0.0765 0.0453724 0.184974 0.0678855 0.0468436 0.183974 0.069462 0.047082 0.183974 0.0704339 0.0473713 0.184974 0.0892499 -0.0302738 0.18428 0.0889449 -0.0320389 0.184974 0.0895749 -0.0317466 0.183974 0.093496 -0.0347115 0.184974 0.0933302 -0.0337254 0.183974 0.0915593 -0.0346134 0.183974 0.0898437 -0.0337095 0.184974 0.0902594 -0.0327329 0.184974 0.0947288 -0.0331607 0.184974 0.101151 -0.0276844 0.183974 0.104694 -0.0250736 0.184974 0.105583 -0.0220983 0.184974 0.106288 -0.020988 0.184974 0.111446 -0.00775193 0.183974 0.11286 -0.00528436 0.184974 0.111868 -0.00515616 0.184974 0.1122 -2.85742e-06 0.183974 0.113062 0.00336312 0.183974 0.111454 0.0118622 0.184974 0.109674 0.0140229 0.183974 0.106489 0.0225348 0.183974 0.0997649 0.0284971 0.183974 0.101637 0.0280894 0.183974 0.103169 0.0269399 0.184974 0.0939692 0.0278016 0.184974 0.0915 0.0314971 0.183974 0.0925 0.0351925 0.184974 0.0915 0.0351925 0.183974 0.0926522 0.0359579 0.183974 0.0930857 0.0366067 0.183974 0.0961142 0.0390223 0.184974 0.0981235 0.0401606 0.183974 0.0996927 0.0384662 0.184974 0.100277 0.0392778 0.184974 0.11697 0.0178932 0.183974 0.116041 0.0175234 0.184974 0.119535 0.00910805 0.183974 0.0460299 0.0391725 0.184974 0.0458764 0.0401606 0.184974 0.0501797 0.0387554 0.183974 0.0494726 0.0380483 0.183974 0.0509142 0.0366067 0.183974 0.0515 0.0351925 0.184974 0.0525 0.0314971 0.183974 0.0408306 0.0269399 0.183974 0.0423632 0.0280894 0.184974 0.0321316 -0.00515616 0.183974 0.0315727 -0.00794469 0.183974 0.0338617 -0.0155886 0.184974 0.0384168 -0.0220983 0.183974 0.0392865 -0.0250482 0.183974 0.0375814 -0.022648 0.184974 0.0433058 -0.0281575 0.184974 0.0428491 -0.0276844 0.183974 0.042592 -0.0288579 0.183974 0.0487057 -0.0339855 0.184974 0.0507827 -0.0337425 0.184974 0.0523944 -0.0335814 0.184974 0.054425 -0.0317466 0.184974 0.0545898 -0.0313205 0.186074 0.0901775 0.0326826 0.186274 0.091625 0.0305049 0.186074 0.0915026 0.0313525 0.186274 0.0853753 0.0347094 0.186274 0.0900803 0.0325078 0.186074 0.0854472 0.034896 0.186274 0.0764946 0.0333509 0.186192 0.0765 0.0339058 0.186074 0.0766971 0.0347375 0.186074 0.0789907 0.0364451 0.186274 0.0804094 0.0362341 0.186274 0.0595365 0.0399482 0.186074 0.0595961 0.0397572 0.186174 0.0520955 0.0366969 0.186174 0.0919045 0.0366969 0.186274 0.0849323 0.0397989 0.186192 0.0675 0.0339058 0.186272 0.0675013 0.0334241 0.186274 0.0649683 0.0362493 0.186274 0.0662248 0.0356837 0.186074 0.0650092 0.0364451 0.186074 0.0663443 0.0358442 0.186274 0.0586247 0.0347094 0.186274 0.0635905 0.0362341 0.186074 0.0585527 0.034896 0.186074 0.0524973 0.0313525 0.186274 0.0529363 0.0316593 0.186074 0.0527776 0.031781 0.186274 0.0539196 0.0325078 0.186074 0.0538224 0.0326826 0.185774 0.0675 0.0453724 0.185974 0.0677 0.0416256 0.185974 0.0690469 0.0477658 0.185774 0.0678855 0.0468436 0.185774 0.0704008 0.0483707 0.185974 0.0735925 0.0481708 0.185974 0.0704075 0.0481708 0.185774 0.0761144 0.0468436 0.185974 0.0759401 0.0467456 0.185974 0.074953 0.0477658 0.185774 0.0750568 0.0479368 0.185874 0.0764 0.0416152 0.185974 0.0924747 0.0371259 0.185774 0.0923786 0.0373138 0.185974 0.0939617 0.038614 0.185974 0.10016 0.0391155 0.185774 0.100277 0.0392778 0.185974 0.0980928 0.039963 0.185774 0.0981235 0.0401606 0.185774 0.0958038 0.0399729 0.185974 0.0958658 0.0397828 0.185774 0.0368342 0.0332527 0.185974 0.0246616 0.0090704 0.185774 0.0244652 0.00910805 0.185774 0.0501797 0.0387554 0.185974 0.0459071 0.039963 0.185774 0.043723 0.0392778 0.185974 0.0514799 0.0371724 0.185774 0.0516213 0.0373138 0.185774 0.0520438 0.0367827 0.187574 0.0929289 0.0268473 0.187123 0.0925535 0.0261971 0.187574 0.0921782 0.0268473 0.187574 0.0512793 -0.025471 0.187574 0.0521227 -0.0258771 0.187574 0.05077 -0.0258771 0.187574 0.0509783 -0.0256159 0.187123 0.0514464 -0.0262029 0.187574 0.0932037 -0.0258275 0.187123 0.0925535 -0.0262029 0.187574 0.0918028 -0.0262029 0.187574 0.0919034 -0.0258275 0.187574 0.0520965 0.0265725 0.187574 0.0514464 0.0269479 0.187574 0.051071 0.0268473 0.176674 0.0553 -0.00670286 0.179174 0.0515582 -0.00670286 0.184974 0.0647 -0.00670286 0.183788 0.0675637 -0.00670286 0.180724 0.06875 -0.00670286 0.180924 0.06875 -0.00670286 0.176674 0.0647 -0.00670286 0.180924 0.05125 -0.00670286 0.184974 0.0887 -0.00670286 0.184974 0.0793 -0.00670286 0.176674 0.0887 -0.00670286 0.180724 0.09275 -0.00670286 0.179174 0.0755582 -0.00670286 0.182474 0.0924417 -0.00670286 0.213124 0.112984 0.00870864 0.213124 0.1139 -2.85742e-06 0.213124 0.112984 -0.00871436 0.213124 0.0310156 -0.00871436 0.213124 0.0590521 -0.0398521 0.213124 0.0763797 -0.0416733 0.213124 0.09295 -0.0362893 0.213124 0.0337224 -0.0170451 0.213124 0.09295 0.0362836 0.224774 0.0896673 0.0640011 0.224774 0.0902735 0.0638238 0.224774 0.0904879 0.0630238 0.224774 0.0900141 0.0635662 0.224774 0.0900141 0.0624814 0.224774 0.0896879 0.0616382 0.224774 0.0886097 0.0618051 0.224774 0.0880879 0.0616382 0.224774 0.0881085 0.0620465 0.224774 0.0880879 0.0644094 0.224774 0.0877617 0.0635662 0.224774 0.0886097 0.0642425 0.224774 0.0558914 0.0620465 0.224774 0.0548339 0.0618051 0.224774 0.0543327 0.0620465 0.224774 0.0537264 0.0622238 0.224774 0.0537264 0.0638238 0.224774 0.054312 0.0644094 0.224774 0.0564977 0.0622238 0.224774 0.056362 0.0630238 0.224774 0.0250819 0.0451586 0.224774 0.0242612 0.0461359 0.224774 0.0250612 0.0475215 0.224774 0.0266612 0.0475215 0.224774 0.0258612 0.0473859 0.224774 0.0269438 0.0467609 0.224774 0.0274612 0.0461359 0.224774 0.0266406 0.0451586 0.224774 0.0261394 0.0449172 0.224774 0.00869515 0.0156664 0.224774 0.0081733 0.0154994 0.224774 0.00784709 0.0163427 0.224774 0.0073733 0.0168851 0.224774 0.00758766 0.0176851 0.224774 0.00789077 0.0175101 0.224774 0.0095983 0.0179676 0.224774 0.0103589 0.0176851 0.224774 0.0100558 0.0175101 0.224774 0.0103589 0.0160851 0.224774 0.00975266 -0.0178681 0.224774 0.00758766 -0.0176908 0.224774 0.0081733 -0.0155052 0.224774 0.0097733 -0.0155052 0.224774 0.0095983 -0.0158083 0.224774 0.0105733 -0.0168908 0.224774 0.0097733 -0.0182764 0.224774 0.0269438 -0.0467666 0.224774 0.0271112 -0.0461416 0.224774 0.0274612 -0.0461416 0.224774 0.0269438 -0.0455166 0.224774 0.0264862 -0.045059 0.224774 0.0247787 -0.0455166 0.224774 0.0246112 -0.0461416 0.224774 0.0244756 -0.0453416 0.224774 0.0247787 -0.0467666 0.224774 0.0242612 -0.0461416 0.224774 0.0244756 -0.0469416 0.224774 0.0250612 -0.0475272 0.224774 0.0266612 -0.0475272 0.224774 0.0565536 -0.0623353 0.224774 0.0553902 -0.0618109 0.224774 0.055468 -0.0614696 0.224774 0.0539858 -0.0624872 0.224774 0.0541144 -0.0617786 0.224774 0.053862 -0.0630295 0.224774 0.053512 -0.0630295 0.224774 0.0537264 -0.0638295 0.224774 0.054487 -0.0641121 0.224774 0.054312 -0.0644152 0.224774 0.055112 -0.0646295 0.224774 0.055737 -0.0641121 0.224774 0.0561945 -0.0636545 0.224774 0.056362 -0.0630295 0.224774 0.0880879 -0.0644152 0.224774 0.0875023 -0.0638295 0.224774 0.0872879 -0.0630295 0.224774 0.0876379 -0.0630295 0.224774 0.0875023 -0.0622295 0.224774 0.0888879 -0.0614295 0.224774 0.0888879 -0.0617795 0.224774 0.0904879 -0.0630295 0.224774 0.0896879 -0.0644152 0.224774 0.118139 -0.0445416 0.224774 0.118939 -0.0447559 0.224774 0.119265 -0.0455992 0.224774 0.119739 -0.0461416 0.224774 0.116539 -0.0461416 0.224774 0.117056 -0.0467666 0.224774 0.116889 -0.0461416 0.224774 0.116753 -0.0453416 0.224774 0.117012 -0.0455992 0.224774 0.117339 -0.0447559 0.224774 0.135305 -0.0181095 0.224774 0.135027 -0.0184908 0.224774 0.134227 -0.0182764 0.224774 0.1339 -0.0174332 0.224774 0.135027 -0.0156408 0.224774 0.135652 -0.0158083 0.224774 0.136412 -0.0160908 0.224774 0.136277 -0.0168908 0.224774 0.136412 -0.0176908 0.224774 0.135827 -0.0182764 0.224774 0.136153 -0.0174332 0.224774 0.135806 -0.0178681 0.224774 0.135027 0.0152851 0.224774 0.135305 0.0156664 0.224774 0.134748 0.0156664 0.224774 0.134227 0.0154994 0.224774 0.133641 0.0160851 0.224774 0.1339 0.0163427 0.224774 0.133427 0.0168851 0.224774 0.133777 0.0168851 0.224774 0.133641 0.0176851 0.224774 0.134227 0.0182707 0.224774 0.135027 0.0184851 0.224774 0.135027 0.0181351 0.224774 0.136412 0.0176851 0.224774 0.135652 0.0179676 0.224774 0.136109 0.0175101 0.224774 0.136412 0.0160851 0.224774 0.118139 0.0445359 0.224774 0.117861 0.0449172 0.224774 0.117359 0.0451586 0.224774 0.117012 0.0455935 0.224774 0.116539 0.0461359 0.224774 0.117056 0.0467609 0.224774 0.117339 0.0475215 0.224774 0.118139 0.0477359 0.224774 0.118939 0.0475215 0.224774 0.119221 0.0467609 0.224774 0.119389 0.0461359 0.224774 0.119524 0.0453359 0.224774 0.118918 0.0451586 0.213124 0.110278 0.0170394 0.186474 0.100037 0.0311349 0.213124 0.105898 0.0246253 0.213124 0.100037 0.0311349 0.186474 0.09295 0.0362836 0.213124 0.0849478 0.0398464 0.186474 0.0763797 0.0416676 0.186474 0.0676202 0.0416676 0.213124 0.0763797 0.0416676 0.213124 0.0676202 0.0416676 0.186474 0.0590521 0.0398464 0.213124 0.0590521 0.0398464 0.186474 0.0439634 0.0311349 0.213124 0.05105 0.0362836 0.213124 0.0439634 0.0311349 0.213124 0.0381021 0.0246253 0.213124 0.0337224 0.0170394 0.186474 0.0337224 0.0170394 0.213124 0.0310156 0.00870864 0.219673 0.00925145 0.0156664 0.220277 0.00809143 0.017771 0.220803 0.00706474 0.0194282 0.220803 0.00623702 0.0164101 0.220777 0.00506233 0.0101816 0.220068 0.00819394 0.0159078 0.219471 0.00836395 0.00786826 0.21923 0.010386 0.0151836 0.219603 0.00805039 0.0082709 0.219903 0.00729996 0.00887395 0.21987 0.00869515 0.0156664 0.220321 0.00622812 0.00949446 0.220747 0.00513831 0.0101253 0.220803 0.139034 0.0100243 0.21939 0.135485 0.00724741 0.21923 0.134995 0.00764616 0.219902 0.136728 0.00866052 0.219271 0.135259 0.00627479 0.21923 0.0126657 0.0224997 0.219769 0.0095983 0.0179676 0.21923 0.0158107 0.0294875 0.220803 0.0109936 0.0295331 0.21923 0.0184541 0.0340524 0.220803 0.0148071 0.0363719 0.220803 0.0213753 0.045067 0.219769 0.0269438 0.0467609 0.220004 0.0264862 0.0472184 0.220322 0.0252362 0.0472184 0.220803 0.0233935 0.0472366 0.220337 0.0249776 0.04702 0.220277 0.0246533 0.0464573 0.220036 0.024735 0.0455935 0.219836 0.0250819 0.0451586 0.21943 0.0266406 0.0451586 0.21923 0.024501 0.0420776 0.219498 0.0261394 0.0449172 0.21923 0.0359517 0.052222 0.220803 0.0315474 0.0543822 0.220803 0.0382337 0.0587678 0.220803 0.0507249 0.0643518 0.220004 0.053862 0.0630238 0.219615 0.0543327 0.0620465 0.21923 0.0494974 0.0593314 0.219481 0.0548339 0.0618051 0.21923 0.0568135 0.0616111 0.219588 0.0562382 0.0624814 0.220803 0.0585607 0.0664316 0.220277 0.055438 0.0642305 0.220803 0.0828722 0.0668996 0.220155 0.0881085 0.0640011 0.21923 0.079649 0.0629924 0.220803 0.0720659 0.0677773 0.21923 0.0594177 0.0621952 0.219769 0.056362 0.0630238 0.219588 0.0877617 0.0624814 0.219466 0.0881085 0.0620465 0.21923 0.0897342 0.0609267 0.219428 0.0886097 0.0618051 0.219481 0.0891661 0.0618051 0.219615 0.0896673 0.0620465 0.220004 0.0901379 0.0630238 0.220803 0.0909421 0.0650767 0.219802 0.0900141 0.0624814 0.220803 0.0934002 0.0643103 0.21923 0.0945025 0.0593314 0.21923 0.099269 0.0572974 0.220803 0.101126 0.0612001 0.220803 0.110558 0.0557416 0.21923 0.11408 0.0474961 0.219453 0.117012 0.0455935 0.21923 0.119499 0.0420776 0.219836 0.118918 0.0451586 0.220803 0.120698 0.0471419 0.220206 0.119389 0.0461359 0.220337 0.119023 0.0470198 0.220322 0.118764 0.0472184 0.220206 0.118139 0.0473859 0.220803 0.118993 0.0488423 0.219769 0.117056 0.0467609 0.21923 0.115996 0.0457275 0.21923 0.122756 0.0380861 0.220803 0.126213 0.0406804 0.21923 0.128189 0.0294875 0.220803 0.133064 0.0294143 0.220068 0.135806 0.0159078 0.21987 0.135305 0.0156664 0.21923 0.134638 0.0101664 0.220803 0.138904 0.010859 0.220803 0.136973 0.0193018 0.220277 0.135909 0.0177706 0.220803 0.136299 0.0214401 0.21923 0.132199 0.0200727 0.219443 0.133777 0.0168851 0.219435 0.1339 0.0163427 0.224474 0.13942 -0.010617 0.224474 0.13673 -0.0216392 0.221811 0.133487 -0.0296239 0.224474 0.132251 -0.0320634 0.221811 0.127978 -0.0390487 0.224474 0.126107 -0.0416017 0.224474 0.109545 -0.0569977 0.224474 0.0995846 -0.06243 0.221811 0.0888617 -0.0661371 0.224474 0.0888617 -0.0661371 0.221811 0.0829475 -0.0673691 0.224474 0.0663271 -0.0680167 0.221811 0.0663271 -0.0680167 0.224474 0.0776728 -0.0680167 0.221811 0.0505775 -0.0648036 0.224474 0.0344547 -0.0569977 0.221811 0.0344547 -0.0569977 0.221811 0.0444153 -0.06243 0.224474 0.0178927 -0.0416017 0.221811 0.0160985 -0.0391576 0.221811 0.0178927 -0.0416017 0.221811 0.0230566 -0.0475698 0.224474 0.00458036 -0.010617 0.221811 0.00661461 -0.0195686 0.221811 0.00727027 -0.0216392 0.221811 0.0105707 -0.0297436 0.221811 0.011749 -0.0320634 0.221811 0.00458036 0.0106113 0.224474 0.00458036 0.0106113 0.221811 0.00661462 0.0195629 0.221811 0.00727027 0.0216335 0.224474 0.011749 0.0320577 0.221811 0.011749 0.0320577 0.221811 0.0160985 0.0391519 0.221811 0.0178927 0.041596 0.224474 0.0255316 0.0499847 0.221811 0.0344547 0.056992 0.221811 0.0405195 0.0605533 0.221811 0.0444153 0.0624243 0.221811 0.0505775 0.0647979 0.221811 0.0611836 0.0673846 0.221811 0.0663271 0.068011 0.224474 0.0663271 0.068011 0.221811 0.0720664 0.0682471 0.224474 0.0776728 0.068011 0.224474 0.0995846 0.0624243 0.221811 0.0935486 0.0647561 0.221811 0.0829475 0.0673634 0.221811 0.109545 0.056992 0.221811 0.0995846 0.0624243 0.221811 0.127978 0.039043 0.224474 0.126107 0.041596 0.221811 0.126107 0.041596 0.221811 0.121036 0.0474687 0.224474 0.13942 0.0106113 0.221811 0.13942 0.0106113 0.224474 0.132251 0.0320577 0.221643 0.00459804 -0.010219 0.221427 0.00467005 -0.0100218 0.220984 0.00490479 -0.0101921 0.221811 0.00458036 -0.010617 0.220999 0.139138 -0.00995265 0.221785 0.139432 -0.0104615 0.221686 0.139414 -0.0102739 0.220803 0.0382337 -0.0587735 0.221811 0.0405195 -0.060559 0.220803 0.0407362 -0.0601421 0.221811 0.0551382 -0.0661371 0.221811 0.0611835 -0.0673903 0.220803 0.0693806 -0.0677324 0.221811 0.0720664 -0.0682528 0.221811 0.0776728 -0.0680167 0.220803 0.0802682 -0.0672768 0.221811 0.0935486 -0.0647618 0.220803 0.090942 -0.0650824 0.221811 0.0995846 -0.06243 0.221811 0.103598 -0.0604976 0.221811 0.109545 -0.0569977 0.220803 0.110558 -0.0557473 0.221811 0.112839 -0.0546855 0.221811 0.118468 -0.0499904 0.221811 0.121036 -0.0474744 0.221811 0.126107 -0.0416017 0.220803 0.120698 -0.0471476 0.220803 0.126213 -0.0406861 0.221811 0.132251 -0.0320634 0.221811 0.13673 -0.0216392 0.221811 0.137423 -0.0194413 0.220803 0.136973 -0.0193075 0.220803 0.139034 -0.01003 0.221811 0.0312669 -0.0547649 0.221811 0.0255316 -0.0499904 0.220803 0.0213753 -0.0450727 0.220803 0.0109936 -0.0295388 0.220803 0.00706474 -0.0194339 0.221428 0.00467004 0.0100161 0.221641 0.00459863 0.0102109 0.220999 0.139138 0.00994694 0.221686 0.139414 0.0102684 0.221525 0.139364 0.0100941 0.221116 0.00483507 0.0101362 0.220803 0.00971711 0.0267366 0.221811 0.0105707 0.0297379 0.220803 0.0164834 0.0388823 0.221811 0.0230566 0.0475641 0.221811 0.0255316 0.0499847 0.220803 0.0292521 0.0525972 0.221811 0.031267 0.0547592 0.220803 0.0407362 0.0601364 0.220803 0.0480882 0.0634194 0.221811 0.0551382 0.0661314 0.220803 0.061258 0.0669207 0.220803 0.0693806 0.0677267 0.220803 0.0802682 0.0672711 0.221811 0.0776728 0.068011 0.221811 0.0888617 0.0661314 0.220803 0.103381 0.0600754 0.221811 0.103598 0.0604918 0.220803 0.112558 0.0543034 0.221811 0.112839 0.0546798 0.221811 0.118468 0.0499847 0.220803 0.127592 0.0387742 0.220803 0.132032 0.0314669 0.221811 0.132251 0.0320577 0.221811 0.133487 0.0296182 0.221811 0.13673 0.0216335 0.221811 0.137423 0.0194356 0.221804 0.139429 0.0105327 0.224474 0.00727027 -0.0216392 0.224474 0.011749 -0.0320634 0.224474 0.0255316 -0.0499904 0.224774 0.0346197 -0.0567472 0.224474 0.0444153 -0.06243 0.224774 0.0445366 -0.0621556 0.224474 0.0551382 -0.0661371 0.224774 0.0552124 -0.0658465 0.224774 0.0663521 -0.0677177 0.224774 0.0887876 -0.0658465 0.224774 0.0994633 -0.0621556 0.224774 0.10938 -0.0567472 0.224474 0.118468 -0.0499904 0.224474 0.13673 0.0216335 0.224774 0.125869 0.0414131 0.224474 0.118468 0.0499847 0.224474 0.109545 0.056992 0.224774 0.118264 0.049765 0.224474 0.0888617 0.0661314 0.224774 0.0776478 0.067712 0.224774 0.0663521 0.067712 0.224474 0.0551382 0.0661314 0.224774 0.0552124 0.0658407 0.224474 0.0444153 0.0624243 0.224774 0.0346197 0.0567415 0.224474 0.0344547 0.056992 0.224774 0.0257359 0.049765 0.224474 0.0178927 0.041596 0.224774 0.0120138 0.0319168 0.224474 0.00727027 0.0216335 0.21829 0.134597 -0.00505108 0.21829 0.132979 -0.015017 0.187974 0.131013 -0.0214817 0.21829 0.131574 -0.0198703 0.21829 0.129785 -0.0245949 0.21829 0.126386 -0.0314029 0.187974 0.120108 -0.0403699 0.21829 0.112367 -0.0481104 0.187974 0.1034 -0.0543893 0.21829 0.107725 -0.0516515 0.21829 0.103457 -0.0543561 0.21829 0.1034 -0.0543893 0.21829 0.0989863 -0.0567089 0.21829 0.0934788 -0.0590156 0.21829 0.0746254 -0.062748 0.21829 0.069573 -0.0627559 0.21829 0.0645365 -0.0623578 0.21829 0.0610949 -0.0618488 0.187974 0.0505211 -0.0590156 0.21829 0.0505211 -0.0590156 0.21829 0.0407147 -0.0544553 0.21829 0.0364388 -0.0517642 0.21829 0.0316329 -0.0481104 0.187974 0.0238924 -0.0403699 0.21829 0.0238924 -0.0403699 0.21829 0.02189 -0.0378556 0.187974 0.0176136 -0.0314029 0.21829 0.0164716 -0.0293362 0.187974 0.0129873 -0.0214817 0.21829 0.0142933 -0.0247776 0.21829 0.0124886 -0.0200586 0.187974 0.010154 -0.010908 0.21829 0.011069 -0.0152099 0.21829 0.00941947 -0.00524906 0.21829 0.010154 -0.010908 0.218686 0.134882 -2.85742e-06 0.21829 0.1348 -2.85742e-06 0.21829 0.0505211 0.0590098 0.21923 0.0403869 0.0550202 0.219018 0.135114 -2.85742e-06 0.219021 0.134657 0.00760509 0.21923 0.131334 0.0224997 0.21923 0.133614 0.0151836 0.21923 0.124225 0.0360454 0.219021 0.0943817 0.0590129 0.21923 0.0871864 0.0616111 0.219021 0.0796079 0.0626543 0.21923 0.072 0.0634551 0.21923 0.0695476 0.0634077 0.21923 0.0643509 0.0629924 0.21923 0.0299195 0.0474961 0.21923 0.031978 0.049243 0.219215 0.00884965 0.00582058 0.21923 0.00900466 0.00764616 0.219021 0.00934283 0.00760509 0.218689 0.0202485 0.0357186 0.219021 0.0200554 0.0358519 0.21923 0.0197751 0.0360454 0.218689 0.030301 0.0470656 0.218689 0.0870488 0.0610526 0.219021 0.072 0.0631145 0.219021 0.064392 0.0626543 0.218689 0.0644203 0.0624214 0.219021 0.056895 0.0612804 0.218689 0.0569511 0.0610526 0.218689 0.0497014 0.0587935 0.21923 0.108048 0.052222 0.219021 0.107855 0.0519417 0.219021 0.113854 0.0472411 0.218689 0.113699 0.0470656 0.219021 0.133283 0.0151021 0.219021 0.131016 0.0223789 0.21829 0.00919996 -2.85742e-06 0.218689 0.00957569 0.00757682 0.21829 0.010154 0.0109022 0.219215 0.00858172 -2.85742e-06 0.218689 0.0109445 0.015046 0.21829 0.0129873 0.021476 0.219021 0.0107167 0.0151021 0.218689 0.0132036 0.0222957 0.21923 0.0136887 0.0250315 0.219021 0.0129842 0.0223789 0.218689 0.01632 0.0292202 0.21829 0.0163933 0.0291818 0.219021 0.0161123 0.0293292 0.21829 0.0249935 0.0416412 0.218689 0.0249315 0.0416961 0.21829 0.0203166 0.0356716 0.21829 0.0176136 0.0313971 0.219021 0.024756 0.0418517 0.219021 0.0301454 0.0472411 0.21829 0.0316329 0.0481047 0.219021 0.0361452 0.0519417 0.218689 0.0427769 0.0556771 0.218689 0.0362785 0.0517486 0.21829 0.0406 0.0543835 0.21923 0.0425096 0.0561864 0.219021 0.0426679 0.0558848 0.219021 0.0496182 0.0590129 0.21829 0.0610949 0.0618431 0.21829 0.0644303 0.0623393 0.218689 0.072 0.0628799 0.21829 0.072 0.0627971 0.218689 0.0795796 0.0624214 0.21829 0.0795697 0.0623393 0.21829 0.0829051 0.0618431 0.219021 0.0871049 0.0612804 0.21829 0.0934788 0.0590098 0.219021 0.101332 0.0558848 0.218689 0.101223 0.0556771 0.218689 0.0942985 0.0587935 0.21829 0.0942691 0.0587162 0.21923 0.10149 0.0561864 0.218689 0.107721 0.0517486 0.21829 0.101185 0.0556038 0.21829 0.113644 0.0470036 0.21829 0.112367 0.0481047 0.21829 0.107674 0.0516805 0.21829 0.1034 0.0543835 0.219021 0.119244 0.0418517 0.218689 0.119068 0.0416961 0.21829 0.127607 0.0291818 0.219021 0.123944 0.0358519 0.218689 0.12768 0.0292202 0.218689 0.123751 0.0357186 0.219021 0.127888 0.0293292 0.218689 0.130796 0.0222957 0.218689 0.134424 0.00757682 0.21829 0.133846 0.0109022 0.218689 0.133055 0.015046 0.21829 0.131013 0.021476 0.187974 0.133846 -0.010908 0.185974 0.1328 -2.85742e-06 0.185974 0.131876 -0.0105607 0.187974 0.126386 -0.0314029 0.185974 0.129133 -0.0207977 0.185974 0.118575 -0.0390843 0.187974 0.112367 -0.0481104 0.185974 0.111081 -0.0465784 0.185974 0.1024 -0.0526572 0.185974 0.0927948 -0.0571362 0.187974 0.0934788 -0.0590156 0.187974 0.0829051 -0.0618488 0.187974 0.072 -0.0628029 0.185974 0.072 -0.0608029 0.187974 0.0610949 -0.0618488 0.185974 0.0614421 -0.0598792 0.187974 0.0406 -0.0543893 0.185974 0.0512051 -0.0571362 0.185974 0.0416 -0.0526572 0.187974 0.0316329 -0.0481104 0.185974 0.0329185 -0.0465784 0.185974 0.0254245 -0.0390843 0.185974 0.0121236 -0.0105607 0.185974 0.100371 0.0315065 0.186474 0.105898 0.0246253 0.186474 0.110278 0.0170394 0.186474 0.112984 0.00870864 0.185974 0.110734 0.0172428 0.186474 0.0849478 0.0398464 0.185974 0.0851023 0.0403219 0.185974 0.0932 0.0367166 0.185974 0.076432 0.0421649 0.185974 0.0588976 0.0403219 0.185974 0.067568 0.0421649 0.186474 0.0310156 0.00870864 0.185974 0.0332656 0.0172428 0.185974 0.0376976 0.0249192 0.186474 0.0381021 0.0246253 0.185974 0.0436288 0.0315065 0.186474 0.05105 0.0362836 0.224774 0.0901379 0.0630238 0.220182 0.0900141 0.0635662 0.2203 0.0896673 0.0640011 0.224774 0.0891661 0.0642425 0.220337 0.0891661 0.0642425 0.220286 0.0886097 0.0642425 0.224774 0.0881085 0.0640011 0.219971 0.0877617 0.0635662 0.220206 0.055737 0.0641063 0.220004 0.0561945 0.0636488 0.224774 0.0561945 0.0636488 0.224774 0.055737 0.0641063 0.220322 0.055112 0.0642738 0.224774 0.055112 0.0642738 0.220337 0.0547883 0.0642312 0.220322 0.054487 0.0641063 0.224774 0.054487 0.0641063 0.220277 0.0542267 0.0639062 0.220206 0.0540295 0.0636488 0.224774 0.0540295 0.0636488 0.219563 0.0271112 0.0461359 0.224774 0.0264862 0.0472184 0.220277 0.0255395 0.0473437 0.220206 0.0258612 0.0473859 0.220322 0.0247787 0.0467609 0.224774 0.0252362 0.0472184 0.224774 0.0247787 0.0467609 0.219443 0.0102233 0.0168851 0.21949 0.0101802 0.0172106 0.219563 0.0100558 0.0175101 0.224774 0.0089733 0.0181351 0.220004 0.0089733 0.0181351 0.224774 0.0083483 0.0179676 0.220206 0.0083483 0.0179676 0.220322 0.0077233 0.0168851 0.220337 0.00776595 0.0172088 0.220322 0.00789077 0.0175101 0.219443 0.0100558 -0.0162658 0.224774 0.0100558 -0.0162658 0.21949 0.0098555 -0.0160052 0.219563 0.0095983 -0.0158083 0.224774 0.0089733 -0.0156408 0.224774 0.0083483 -0.0158083 0.224774 0.00789077 -0.0162658 0.220277 0.00776666 -0.0165644 0.219443 0.0269438 -0.0455166 0.219443 0.0264862 -0.045059 0.219563 0.0258612 -0.0448916 0.224774 0.0258612 -0.0448916 0.224774 0.0252362 -0.045059 0.219769 0.0252362 -0.045059 0.220004 0.0247787 -0.0455166 0.224774 0.0562382 -0.0624872 0.224774 0.0558914 -0.0620522 0.224774 0.0548339 -0.0618109 0.224774 0.0543327 -0.0620522 0.219802 0.0539858 -0.0624872 0.220004 0.0901379 -0.0630295 0.224774 0.0901379 -0.0630295 0.224774 0.0899704 -0.0624045 0.224774 0.0895129 -0.061947 0.219563 0.0895129 -0.061947 0.21949 0.089214 -0.0618228 0.219427 0.0885642 -0.0618221 0.219443 0.0882629 -0.061947 0.224774 0.0882629 -0.061947 0.21949 0.0880025 -0.0621472 0.224774 0.0878054 -0.0624045 0.219769 0.0876379 -0.0630295 0.224774 0.119389 -0.0461416 0.224774 0.118918 -0.0451643 0.224774 0.118417 -0.0449229 0.224774 0.117861 -0.0449229 0.224774 0.117359 -0.0451643 0.21943 0.117359 -0.0451643 0.219453 0.117012 -0.0455992 0.220277 0.136234 -0.0165654 0.224774 0.136109 -0.0162658 0.220206 0.136109 -0.0162658 0.219769 0.135027 -0.0156408 0.224774 0.134402 -0.0158083 0.219563 0.134402 -0.0158083 0.21949 0.134145 -0.0160048 0.219427 0.133819 -0.0165671 0.224774 0.133944 -0.0162658 0.224774 0.133777 -0.0168908 0.220337 0.136234 0.0172084 0.220322 0.136109 0.0175101 0.220206 0.135652 0.0179676 0.224774 0.134402 0.0179676 0.220004 0.135027 0.0181351 0.219769 0.134402 0.0179676 0.219563 0.133944 0.0175101 0.224774 0.133944 0.0175101 0.21949 0.13382 0.0172115 0.220277 0.119347 0.046457 0.220322 0.119221 0.0467609 0.224774 0.118764 0.0472184 0.220277 0.11846 0.0473439 0.224774 0.118139 0.0473859 0.220004 0.117514 0.0472184 0.224774 0.117514 0.0472184 0.224774 0.116889 0.0461359 0.224474 0.00824996 -2.85742e-06 0.219816 0.00824996 -2.85742e-06 0.220514 0.00723028 -0.00834717 0.219829 0.00852676 -0.00623085 0.219841 0.00851553 -0.00637209 0.224474 0.0085193 0.00585104 0.224474 0.00853028 0.00608979 0.219816 0.0085193 0.00585104 0.220931 0.0061587 -0.00896585 0.224474 0.00506819 -0.00959545 0.224474 0.135481 -0.00585676 0.219628 0.13547 -0.00606202 0.219721 0.135605 -0.0069249 0.21995 0.136067 -0.00775377 0.22007 0.136327 0.00801899 0.224474 0.13677 0.00834145 0.219829 0.135817 0.00738728 0.219678 0.135531 0.00665184 0.224474 0.135481 0.00585104 0.219625 0.135481 0.00585104 0.220686 0.137841 -0.00896586 0.224474 0.13677 -0.00834717 0.224474 0.138932 -0.00959545 0.224474 0.139432 0.0104558 0.221804 0.139429 0.0105327 0.224474 0.13923 -0.00985942 0.221153 0.139091 -0.00970917 0.221112 0.138932 -0.00959545 0.224474 0.139402 -0.010219 0.224474 0.139371 -0.0101195 0.221547 0.139371 -0.0101195 0.221762 0.00456992 -0.0104026 0.221409 0.0047698 -0.00985934 0.224474 0.00480215 -0.00981869 0.221358 0.00506819 0.00958974 0.224474 0.00456819 0.0104558 0.221761 0.00457001 0.0103954 0.221394 0.0048498 0.00976013 0.224774 0.139132 -0.0104615 0.224774 0.13909 -0.0102221 0.224774 0.138782 -0.00985526 0.224774 0.13662 -0.00860698 0.224774 0.135558 -0.0075455 0.224474 0.136028 -0.00770493 0.224474 0.135577 -0.0068334 0.224774 0.13517 -0.0060955 0.224774 0.135182 -0.00582921 0.224774 0.13545 -2.85742e-06 0.224774 0.13517 0.00608979 0.224474 0.136028 0.00769921 0.224474 0.135577 0.00682769 0.224774 0.138782 0.00984955 0.224474 0.139402 0.0102132 0.224774 0.139123 0.0105646 0.224474 0.00506819 0.00958974 0.224474 0.00818195 -0.0073955 0.224774 0.00738028 -0.00860698 0.224774 0.00883028 -0.0060955 0.224774 0.00871104 -0.00691854 0.224774 0.00820789 -0.00789063 0.224474 0.00723028 -0.00834717 0.224474 0.0046285 -0.0101195 0.224774 0.00500928 -0.01004 0.220803 0.00500039 0.0102542 0.220514 0.00723028 0.00834145 0.220082 0.00810053 0.00752157 0.219841 0.00851553 0.00636638 0.219366 0.00860338 0.00743373 0.21923 0.00887099 0.00645069 0.219821 0.00853028 0.00608979 0.219219 0.00886964 0.0061384 0.219215 0.00880339 -0.00530071 0.219816 0.0085193 -0.00585676 0.219829 0.00852675 -0.00623085 0.219817 0.00852746 -0.00597446 0.21932 0.00870257 -0.00719426 0.21997 0.00830861 -0.00714601 0.22004 0.00818063 -0.00739778 0.219564 0.00814544 -0.00816807 0.220195 0.00788221 -0.00781305 0.220931 0.00615869 -0.00896585 0.221358 0.00506819 -0.00959545 0.220747 0.00513831 -0.010131 0.220777 0.00506229 -0.0101874 0.221399 0.00482326 -0.00979433 0.220775 0.138966 -0.00996796 0.220745 0.13889 -0.00991638 0.221194 0.139242 -0.00987488 0.22032 0.1378 -0.00928614 0.220686 0.137841 -0.00896586 0.220269 0.13677 -0.00834717 0.219721 0.136267 -0.00833703 0.219314 0.135328 -0.00676472 0.219625 0.135481 -0.00585676 0.219258 0.135267 0.00583134 0.219611 0.135997 0.00806362 0.220269 0.13677 0.00834145 0.220686 0.137841 0.00896015 0.221112 0.138932 0.00958974 0.22032 0.1378 0.00928043 0.220745 0.13889 0.00991066 0.220775 0.138966 0.00996229 0.221158 0.139111 0.00972218 0.221194 0.139242 0.00986917 0.228674 0.0810521 -0.0455113 0.228674 0.081116 -0.028059 0.228674 0.0878069 -0.0249105 0.228674 0.0935045 -0.020197 0.228674 0.0531959 -0.022733 0.228674 0.0594395 -0.0266953 0.228674 0.0542434 -0.0428709 0.228674 0.072 -0.0464029 0.228674 0.0391902 0.0328069 0.228674 0.0334198 0.0257756 0.228674 0.048134 0.0173368 0.228674 0.0291319 0.0177537 0.228674 0.0427326 0.00369447 0.228674 0.0264915 0.00904933 0.228674 0.0256 -2.85742e-06 0.228674 0.0334198 -0.0257813 0.228674 0.0391902 -0.0328126 0.228674 0.0462215 -0.038583 0.228674 0.097851 0.0142089 0.228674 0.0935045 0.0201913 0.228674 0.10481 -0.0328126 0.228674 0.097851 -0.0142146 0.228674 0.11058 -0.0257813 0.228674 0.114868 -0.0177594 0.228674 0.1015 -2.85742e-06 0.228674 0.117508 0.00904933 0.228674 0.081116 0.0280533 0.228674 0.0738523 0.0294389 0.228674 0.0810521 0.0455056 0.228674 0.0542434 0.0428652 0.229745 0.138955 0.0105382 0.229748 0.138956 0.0104879 0.228738 0.139432 0.0104558 0.229756 0.138941 0.0104404 0.228745 0.139376 0.0101253 0.228757 0.139213 0.00983205 0.229783 0.138876 0.0103704 0.228776 0.138932 0.00958974 0.229202 0.137841 0.00896012 0.230372 0.13547 0.0060413 0.231317 0.135084 0.00689677 0.229998 0.13606 0.00773961 0.229621 0.13677 0.00834145 0.230628 0.136714 0.00911713 0.231383 0.135013 -0.00581361 0.230376 0.135481 0.00585104 0.231383 0.13528 -2.85742e-06 0.230628 0.136714 -0.00912284 0.230147 0.135796 -0.00735738 0.230316 0.135527 -0.0066379 0.231377 0.134998 -0.00615135 0.229621 0.13677 -0.00834717 0.228759 0.13919 -0.00980992 0.228738 0.139432 -0.0104615 0.229745 0.138955 -0.0105439 0.228738 0.00458036 -0.010617 0.229748 0.00504433 -0.0104936 0.228741 0.00458446 -0.0102818 0.229768 0.00508667 -0.010406 0.228765 0.00491135 -0.00970745 0.229783 0.00512408 -0.0103762 0.229621 0.00723028 -0.00834717 0.231383 0.00898716 -0.00581361 0.23037 0.00853028 -0.0060955 0.231317 0.00891558 -0.00690253 0.23113 0.00851486 -0.00790615 0.230266 0.00839884 -0.00691173 0.230836 0.00781037 -0.00874827 0.230997 0.00820232 0.00834264 0.23037 0.00853028 0.00608979 0.231383 0.00898716 0.0058079 0.231377 0.0090018 0.00614547 0.23126 0.00880182 0.00728912 0.230273 0.00841074 0.00686911 0.230072 0.0080729 0.00756261 0.229771 0.00751817 0.00814857 0.228759 0.00480948 0.00980434 0.228746 0.00463641 0.0100927 0.229756 0.00505907 0.0104404 0.228739 0.00456877 0.0104217 0.228738 0.00458036 0.0106113 0.225074 0.00476974 0.0098537 0.224774 0.00500928 0.0100343 0.224774 0.00486819 0.0104558 0.224774 0.00487671 0.0105646 0.224774 0.00738028 0.00860126 0.224774 0.00881803 0.00582349 0.225074 0.0085193 0.00585104 0.225074 0.00853028 0.00608979 0.224774 0.00820789 0.00788491 0.225074 0.00818195 0.00738979 0.224774 0.00881803 -0.00582921 0.225074 0.0085193 -0.00585676 0.224774 0.00854996 -2.85742e-06 0.225074 0.00853028 -0.0060955 0.225074 0.00842337 -0.0068334 0.225074 0.00723028 -0.00834717 0.224774 0.00486819 -0.0104615 0.224774 0.00488909 -0.0102917 0.224774 0.00521819 -0.00985526 0.225074 0.139198 -0.00981869 0.224774 0.138968 -0.0100115 0.225074 0.139371 -0.0101195 0.225074 0.139432 -0.0104615 0.225074 0.13677 -0.00834717 0.225074 0.135818 -0.0073955 0.225074 0.135577 -0.0068334 0.224774 0.135182 0.00582349 0.225074 0.135481 0.00585104 0.224774 0.139132 0.0104558 0.228738 0.139429 0.010534 0.225074 0.139432 0.0104558 0.228741 0.139414 -0.0102734 0.225074 0.138932 -0.00959545 0.228776 0.138932 -0.00959545 0.225074 0.00458036 0.0106113 0.225074 0.00459804 0.0102132 0.225074 0.00506819 0.00958974 0.228776 0.00506819 -0.00959545 0.225074 0.00506819 -0.00959545 0.228751 0.00469905 -0.00996692 0.225074 0.00476974 -0.00985942 0.225074 0.00459804 -0.010219 0.225074 0.13677 0.00834145 0.225074 0.138932 0.00958974 0.229202 0.137841 -0.00896583 0.225074 0.13547 0.00608979 0.230266 0.135601 0.00690601 0.230376 0.13575 -2.85742e-06 0.229877 0.136282 -0.0079834 0.230376 0.135481 -0.00585676 0.230015 0.13603 -0.00770747 0.228776 0.00506819 0.00958974 0.229202 0.00615872 0.00896012 0.229202 0.00615872 -0.00896583 0.225074 0.00797228 -0.00770493 0.229998 0.00793978 -0.00774532 0.230376 0.00824996 -2.85742e-06 0.225074 0.00824996 -2.85742e-06 0.230376 0.0085193 0.00585104 0.236674 0.0215 -2.85742e-06 0.236974 0.0251899 -0.0181372 0.236674 0.0249101 -0.0182456 0.236974 0.0349017 -0.0338224 0.236674 0.0415669 -0.0403027 0.236974 0.0496239 -0.0449401 0.236674 0.05818 -0.0485751 0.236974 0.0582621 -0.0482865 0.236674 0.0766595 -0.0502874 0.236674 0.0945097 -0.0452086 0.236974 0.102252 -0.0400633 0.236674 0.10932 -0.0340245 0.236974 0.1222 -2.85742e-06 0.238474 0.119372 0.00942 0.238174 0.116346 0.0183659 0.238174 0.105941 0.0339383 0.238174 0.0986673 0.0399077 0.238474 0.0904836 0.0446205 0.238174 0.0813643 0.0470748 0.238474 0.0814228 0.0473691 0.238174 0.0320894 0.0266645 0.238174 0.0276537 0.0183659 0.238174 0.0249223 0.00936148 0.230674 0.1184 -2.85742e-06 0.230674 0.114868 0.0177537 0.230674 0.11058 0.0257756 0.230674 0.10481 0.0328069 0.230674 0.0897565 0.0428652 0.230474 0.0810131 0.0453094 0.230474 0.072 0.0461971 0.230474 0.0629868 0.0453094 0.230674 0.0629478 0.0455056 0.230474 0.05432 0.0426804 0.230674 0.0542434 0.0428652 0.230474 0.0463326 0.038411 0.230474 0.0393316 0.0326655 0.230674 0.0391902 0.0328069 0.230474 0.0293167 0.0176771 0.230674 0.0291319 0.0177537 0.230474 0.0266877 0.00901032 0.230474 0.0258 -2.85742e-06 0.228674 0.0462215 0.0385773 0.228874 0.0629868 0.0453094 0.228874 0.072 0.0461971 0.228674 0.0629478 0.0455056 0.228674 0.072 0.0463971 0.228874 0.0976673 0.038411 0.228674 0.0897565 0.0428652 0.228874 0.104668 0.0326655 0.228674 0.0977784 0.0385773 0.228674 0.10481 0.0328069 0.228674 0.11058 0.0257756 0.228874 0.114683 0.0176771 0.228674 0.114868 0.0177537 0.228674 0.1184 -2.85742e-06 0.237674 0.016699 -0.0201307 0.237874 0.0212076 -0.0293279 0.237674 0.0269182 -0.0378309 0.237674 0.0341719 -0.0450846 0.237874 0.042675 -0.0507952 0.237874 0.0519405 -0.0551158 0.237674 0.0617808 -0.0579588 0.237874 0.0618155 -0.0577618 0.237674 0.072 -0.0588529 0.237874 0.072 -0.0586529 0.237874 0.0821844 -0.0577618 0.237674 0.0921278 -0.0553038 0.237874 0.101325 -0.0507952 0.237874 0.122792 -0.0293279 0.237674 0.129956 -0.0102221 0.237874 0.129759 -0.0101873 0.237674 0.12965 -2.85742e-06 0.237874 0.12985 -2.85742e-06 0.237674 0.128774 0.010008 0.237874 0.1221 0.0289221 0.237674 0.109057 0.0441596 0.237674 0.100825 0.0499235 0.237874 0.109185 0.0443128 0.237874 0.100925 0.0500967 0.237674 0.0917174 0.0541704 0.237674 0.072 0.0576471 0.237674 0.0619891 0.0567713 0.237674 0.0522825 0.0541704 0.237874 0.043075 0.0500967 0.237674 0.043175 0.0499235 0.237874 0.0348147 0.0443128 0.237674 0.0278375 0.0370538 0.237874 0.0176387 0.019783 0.237874 0.0150288 0.0100427 0.237674 0.0152258 0.010008 0.236874 0.12835 -2.85742e-06 0.236674 0.127194 0.0103147 0.236874 0.12739 0.0103514 0.236874 0.124545 0.0203531 0.236674 0.124358 0.0202809 0.236674 0.113495 0.0378252 0.236874 0.11991 0.0296616 0.236874 0.113643 0.0379599 0.236874 0.105958 0.0449654 0.236874 0.0971173 0.0504396 0.236874 0.0771993 0.0561068 0.236674 0.0771808 0.0559076 0.236874 0.0668006 0.0561068 0.236674 0.0469717 0.0502606 0.236674 0.038162 0.0448058 0.236874 0.0380415 0.0449654 0.236674 0.0305046 0.0378252 0.236674 0.0242603 0.0295563 0.236674 0.0196416 0.0202809 0.236674 0.016806 0.0103147 0.236874 0.0166094 0.0103514 0.238474 0.0223412 -2.85742e-06 0.238274 0.0230992 -0.00972981 0.238474 0.0232954 -0.0096908 0.238274 0.0305439 -0.0277029 0.238474 0.0368859 -0.0351169 0.238274 0.0442999 -0.0414589 0.238474 0.0529964 -0.0458815 0.238474 0.062312 -0.0487074 0.238474 0.072 -0.0496616 0.238274 0.0817269 -0.0489036 0.238474 0.0816879 -0.0487074 0.238274 0.0997 -0.0414589 0.238474 0.0910035 -0.0458815 0.238474 0.0995889 -0.0412926 0.238474 0.107114 -0.0351169 0.238274 0.107255 -0.0352583 0.238274 0.113456 -0.0277029 0.238274 0.120901 -0.00972981 0.238474 0.117879 -0.0190064 0.238474 0.120705 -0.0096908 0.238474 0.121659 -2.85742e-06 0.228738 0.0504457 -0.0647599 0.228738 0.0444153 -0.06243 0.229745 0.044773 -0.0620741 0.228738 0.0419349 -0.061274 0.228738 0.0344547 -0.0569977 0.228738 0.0339701 -0.0566755 0.229745 0.0342319 -0.0562854 0.228763 0.051353 -0.0646174 0.228781 0.051587 -0.0643755 0.229765 0.0507262 -0.0643018 0.229785 0.0507757 -0.0642593 0.228801 0.0517274 -0.0640699 0.22975 0.0506622 -0.0643218 0.228738 0.0266958 -0.0510479 0.228741 0.026486 -0.0507866 0.228751 0.0263743 -0.0504707 0.22975 0.0269671 -0.0506415 0.228756 0.0263601 -0.0503298 0.228765 0.0263733 -0.0501354 0.228784 0.0264833 -0.0498183 0.229785 0.0269644 -0.0505118 0.228801 0.0266525 -0.0495929 0.230492 0.0283305 -0.0491285 0.229484 0.0279826 -0.0482629 0.229997 0.0580936 -0.0626981 0.231496 0.0583609 -0.0614793 0.231767 0.0575983 -0.0605388 0.23171 0.0539087 -0.0597041 0.230913 0.0561979 -0.0602329 0.231891 0.0568204 -0.059996 0.231911 0.0565833 -0.0598808 0.230921 0.0558833 -0.0601304 0.231929 0.0560034 -0.0596761 0.231908 0.0553769 -0.0595634 0.231742 0.0540701 -0.0596602 0.231482 0.0530288 -0.0600887 0.231414 0.0528265 -0.060218 0.230191 0.052989 -0.0609098 0.231365 0.0526891 -0.0603164 0.23097 0.0518484 -0.0611861 0.229625 0.052307 -0.0619655 0.230492 0.0512906 -0.0623846 0.229484 0.0237399 -0.0440203 0.229625 0.0239641 -0.0438176 0.231365 0.0251195 -0.0425805 0.230191 0.0250825 -0.0432444 0.23047 0.0258016 -0.0431422 0.230801 0.026973 -0.0433552 0.230891 0.0275096 -0.043635 0.231911 0.0287098 -0.0441504 0.230913 0.0281999 -0.0442626 0.231767 0.0292598 -0.0452277 0.230774 0.0286941 -0.0451542 0.231496 0.02945 -0.0464235 0.230455 0.0288595 -0.0462446 0.23019 0.028758 -0.046922 0.230654 0.0286273 -0.048795 0.229808 0.0582565 -0.0661984 0.229484 0.0580098 -0.063806 0.228801 0.057523 -0.0656228 0.229745 0.0583824 -0.066401 0.22975 0.0583196 -0.0663736 0.229765 0.0582741 -0.0663244 0.229785 0.0582525 -0.0662627 0.228765 0.0575524 -0.0662323 0.228743 0.0212793 -0.0455491 0.228801 0.0224099 -0.0453503 0.22975 0.0213615 -0.0450358 0.228738 0.0663271 -0.0680167 0.229745 0.0856175 -0.066401 0.228738 0.0776728 -0.0680167 0.228738 0.0765985 -0.0680978 0.229745 0.0775972 -0.0675515 0.229745 0.0765668 -0.067629 0.229745 0.00789232 -0.022011 0.228738 0.00727027 -0.0216392 0.228738 0.011749 -0.0320634 0.229745 0.0157174 -0.0377709 0.228738 0.0153273 -0.0380327 0.229745 0.0213063 -0.0449951 0.228738 0.0178927 -0.0416017 0.228785 0.086511 -0.0658816 0.229785 0.0857475 -0.0662627 0.229765 0.0857258 -0.0663243 0.22975 0.0856804 -0.0663735 0.229765 0.00770095 -0.0212767 0.229785 0.0077435 -0.0212271 0.228765 0.00741981 -0.0206056 0.229808 0.0857434 -0.0661984 0.229484 0.0859901 -0.063806 0.229808 0.00780119 -0.0211984 0.228801 0.00793291 -0.0202754 0.229997 0.0913043 -0.0612517 0.230654 0.0925688 -0.0619608 0.229484 0.0917857 -0.0622531 0.230774 0.0894492 -0.0600825 0.230455 0.0904762 -0.0604845 0.231115 0.0918901 -0.0608527 0.230135 0.091102 -0.0610052 0.231811 0.0895299 -0.0595827 0.230913 0.08843 -0.0600647 0.231911 0.0885877 -0.059567 0.230921 0.0881062 -0.0601331 0.230891 0.0875413 -0.0603487 0.231908 0.0873843 -0.0598953 0.231809 0.086599 -0.060373 0.230739 0.086812 -0.0608637 0.23171 0.0861831 -0.0607513 0.230492 0.085256 -0.0643817 0.23047 0.0862605 -0.0615814 0.231414 0.0855028 -0.0617374 0.23097 0.0851398 -0.0630649 0.231365 0.0101115 -0.013436 0.230191 0.0097475 -0.0139924 0.23171 0.0112515 -0.014186 0.230739 0.0111391 -0.0148149 0.231742 0.0113703 -0.0143038 0.231809 0.0116298 -0.0146019 0.230801 0.0113293 -0.0150336 0.230891 0.0116541 -0.0155442 0.231929 0.0123231 -0.015986 0.230921 0.0118697 -0.0161091 0.230913 0.0119381 -0.0164329 0.230774 0.0119203 -0.0174521 0.231767 0.0123735 -0.0177986 0.230455 0.0115183 -0.0184791 0.231115 0.0111501 -0.019893 0.229997 0.0107512 -0.0193072 0.230654 0.010042 -0.0205717 0.229484 0.00974976 -0.0197886 0.230492 0.00961822 -0.0207122 0.228801 0.0922725 -0.0640699 0.22975 0.0933378 -0.0643218 0.228757 0.0927501 -0.0646837 0.228765 0.0926027 -0.064583 0.228784 0.0923831 -0.0643292 0.229808 0.0931956 -0.0642016 0.228749 0.00543794 -0.0142441 0.22975 0.00562927 -0.0136833 0.229765 0.00567852 -0.0137287 0.228801 0.00638 -0.0144798 0.228738 0.00514157 -0.0137148 0.228738 0.0995846 -0.06243 0.229745 0.101858 -0.0608522 0.229745 0.109072 -0.0567461 0.228738 0.11003 -0.0566755 0.229785 0.117036 -0.0505118 0.228801 0.117347 -0.0495929 0.229765 0.117048 -0.050576 0.228758 0.11764 -0.0503 0.228745 0.117584 -0.050631 0.229745 0.116992 -0.0506965 0.228741 0.00526298 0.0140215 0.22975 0.0056292 0.0136775 0.229765 0.00567846 0.0137229 0.229785 0.00574012 0.0137446 0.229808 0.0058044 0.0137406 0.229808 0.117 -0.0504582 0.228801 0.00638 0.0144741 0.230124 0.119069 -0.0432894 0.229484 0.12026 -0.0440203 0.230654 0.120792 -0.0433755 0.230492 0.121126 -0.0436724 0.231115 0.11965 -0.0427553 0.230455 0.118242 -0.0431433 0.231496 0.118421 -0.0425528 0.230913 0.11626 -0.0438029 0.230849 0.115465 -0.0447817 0.231809 0.114828 -0.0449854 0.231742 0.1147 -0.0453592 0.231534 0.114553 -0.046277 0.231414 0.114561 -0.0467151 0.231365 0.114578 -0.0468833 0.230492 0.00961822 0.0207065 0.230965 0.0108055 0.0201565 0.230191 0.011093 0.0190081 0.23047 0.0115411 0.0184364 0.231707 0.0122948 0.0181016 0.230739 0.0118869 0.0175999 0.230801 0.0119423 0.0173155 0.231929 0.0123267 0.0159937 0.230913 0.0117699 0.0157992 0.23019 0.00974581 0.0139863 0.229997 0.0093047 0.0139034 0.228801 0.00793291 0.0202697 0.228741 0.122784 -0.0455168 0.22975 0.122639 -0.0450358 0.229765 0.122573 -0.0450505 0.229785 0.122509 -0.0450385 0.228784 0.121815 -0.0455195 0.22975 0.00768104 0.0213349 0.228763 0.00738544 0.0206441 0.228743 0.00719545 0.0211494 0.229745 0.00768871 0.021403 0.229745 0.122694 -0.0449951 0.228738 0.126107 -0.0416017 0.228738 0.128673 -0.0380327 0.228738 0.132251 -0.0320634 0.228738 0.133271 -0.0300679 0.228738 0.13673 -0.0216392 0.228738 0.136757 -0.0215571 0.228738 0.011749 0.0320577 0.229745 0.0111506 0.0298552 0.228738 0.0107288 0.0300622 0.228738 0.00727027 0.0216335 0.229785 0.136256 -0.0212271 0.228801 0.136067 -0.0202754 0.228781 0.136373 -0.0204158 0.229765 0.136299 -0.0212766 0.228754 0.136714 -0.0208187 0.228741 0.136808 -0.0212413 0.22975 0.0213614 0.04503 0.229765 0.0214268 0.0450448 0.229785 0.021491 0.0450327 0.229808 0.0215447 0.0449971 0.228784 0.0221845 0.0455138 0.229484 0.0237399 0.0440145 0.229997 0.134695 -0.0139092 0.231908 0.131561 -0.0166259 0.230891 0.132032 -0.0167166 0.230913 0.13223 -0.0158049 0.231811 0.132363 -0.0146114 0.230774 0.132755 -0.0149312 0.231742 0.131657 -0.0179327 0.230771 0.132082 -0.0174665 0.23171 0.131701 -0.0180941 0.231414 0.132215 -0.0191763 0.230324 0.132686 -0.0187673 0.23097 0.133183 -0.0201544 0.229928 0.133375 -0.0193953 0.230492 0.134382 -0.0207122 0.230492 0.0283305 0.0491228 0.230965 0.0290837 0.0480529 0.231361 0.0294207 0.046891 0.23047 0.0288606 0.0461954 0.231534 0.0294473 0.046272 0.231707 0.029346 0.0455286 0.230739 0.0287419 0.0452981 0.230801 0.0286476 0.0450241 0.231908 0.0287379 0.0441839 0.230891 0.0283678 0.0444875 0.231929 0.0283197 0.0436872 0.230913 0.0277402 0.0437972 0.230774 0.0268486 0.043303 0.231499 0.0255916 0.0425471 0.231119 0.0243618 0.0427456 0.229997 0.0246574 0.043388 0.229745 0.138398 -0.0136204 0.228751 0.138519 -0.0142819 0.228765 0.138229 -0.0144504 0.228784 0.1379 -0.0145137 0.229765 0.0269523 0.0505703 0.229785 0.0269644 0.0505061 0.22975 0.026967 0.0506356 0.22874 0.0265157 0.0508307 0.229745 0.0270077 0.0506908 0.229745 0.044773 0.0620684 0.228738 0.0444153 0.0624243 0.229745 0.0421419 0.0608465 0.228738 0.0419349 0.0612683 0.228738 0.0344547 0.056992 0.229765 0.138321 0.013723 0.229785 0.13826 0.0137446 0.229745 0.0505941 0.0643084 0.229785 0.0507757 0.0642536 0.229484 0.135803 0.0139873 0.228801 0.13762 0.0144741 0.229808 0.0508044 0.0641959 0.229484 0.0522142 0.0622473 0.228801 0.0517274 0.0640642 0.229997 0.133249 0.0193016 0.231119 0.13284 0.0198788 0.230921 0.13213 0.0161034 0.231911 0.131565 0.0165727 0.231811 0.13158 0.0175271 0.230871 0.132027 0.0168851 0.230774 0.13208 0.0174465 0.231769 0.131624 0.0177811 0.230581 0.132303 0.0181429 0.231499 0.132053 0.018913 0.231809 0.13237 0.0145962 0.23081 0.132644 0.0150621 0.23062 0.133192 0.0145113 0.230465 0.133593 0.0142497 0.231482 0.133521 0.0136106 0.231411 0.133747 0.013494 0.230328 0.133927 0.0140938 0.230112 0.134435 0.013944 0.229977 0.13474 0.0138988 0.230965 0.0588613 0.0630728 0.230092 0.0580616 0.0624763 0.23047 0.0577394 0.0615757 0.231707 0.0578263 0.0607555 0.230599 0.0575278 0.0612451 0.231809 0.0574009 0.0603673 0.231908 0.0566273 0.059895 0.230891 0.0564586 0.060343 0.230913 0.0555699 0.0600589 0.230884 0.0552217 0.0600258 0.231911 0.0554244 0.0595626 0.230455 0.0535237 0.0604788 0.229997 0.0526955 0.061246 0.230659 0.051436 0.0619427 0.230492 0.0512906 0.0623789 0.229808 0.0582565 0.0661927 0.22975 0.136319 0.021335 0.229785 0.136256 0.0212214 0.228793 0.136191 0.020312 0.228763 0.0575735 0.0662784 0.228781 0.0574918 0.065952 0.229785 0.0582525 0.066257 0.228801 0.057523 0.0656171 0.22975 0.0583195 0.0663678 0.228738 0.136757 0.0215514 0.228738 0.13673 0.0216335 0.228738 0.133271 0.0300622 0.229745 0.131611 0.0322569 0.228738 0.128673 0.038027 0.229745 0.128282 0.0377652 0.229745 0.125488 0.0416286 0.229745 0.0765668 0.0676233 0.228738 0.0776728 0.068011 0.229745 0.0583824 0.0663953 0.228738 0.0674015 0.068092 0.228743 0.122721 0.0455433 0.22975 0.122638 0.0450301 0.228781 0.121864 0.045539 0.228801 0.12159 0.0453446 0.229785 0.122509 0.0450327 0.22874 0.122834 0.0454814 0.22975 0.0856803 0.0663679 0.228741 0.0860244 0.0667341 0.228744 0.0861251 0.0666652 0.229765 0.0857258 0.0663186 0.229785 0.0857475 0.066257 0.228785 0.086511 0.0658759 0.229808 0.0857434 0.0661927 0.230492 0.121126 0.0436666 0.230492 0.115669 0.0491228 0.229997 0.115391 0.0473397 0.230429 0.115144 0.0463107 0.231483 0.11455 0.0464628 0.231499 0.11455 0.0464055 0.230774 0.115305 0.0451514 0.230849 0.115464 0.0447767 0.231911 0.115297 0.0441348 0.23086 0.116712 0.0434968 0.23174 0.117369 0.0426933 0.230638 0.117675 0.043172 0.231707 0.117531 0.0426511 0.230461 0.118224 0.0431371 0.231411 0.118726 0.0425593 0.230321 0.1186 0.0431715 0.230125 0.119068 0.0432834 0.230965 0.120056 0.0429134 0.229961 0.119417 0.0434219 0.229752 0.0915843 0.0617086 0.229484 0.0917857 0.0622473 0.229947 0.0913687 0.0613368 0.230965 0.0921593 0.0611916 0.231361 0.0913216 0.0603188 0.230462 0.0904599 0.0604686 0.230474 0.0904305 0.0604508 0.231482 0.0909711 0.060083 0.230654 0.0899181 0.0602062 0.23174 0.0899429 0.0596577 0.231809 0.0895419 0.0595787 0.230849 0.0890458 0.060028 0.231908 0.0886358 0.0595565 0.230919 0.0879461 0.0601755 0.231911 0.0874278 0.0598701 0.231891 0.0871793 0.0599905 0.230803 0.0870381 0.060662 0.231499 0.0856451 0.061463 0.230476 0.086268 0.0615622 0.230011 0.0859098 0.0626618 0.230319 0.0860882 0.0619461 0.229808 0.117 0.0504524 0.229808 0.0931956 0.0641959 0.229765 0.117048 0.0505703 0.228758 0.11764 0.0502943 0.228794 0.117421 0.0496692 0.22975 0.0933377 0.0643161 0.228763 0.0926469 0.0646117 0.228781 0.092413 0.0643698 0.228801 0.0922725 0.0640642 0.228743 0.0931522 0.0648016 0.229745 0.0992269 0.0620684 0.228738 0.102065 0.0612683 0.229745 0.109072 0.0567404 0.229745 0.116992 0.0506908 0.226274 0.118468 0.0499847 0.226574 0.138417 0.0143513 0.226355 0.138698 0.014081 0.226325 0.136808 0.0212356 0.226295 0.138796 0.0139063 0.226274 0.138858 0.0137091 0.226274 0.136757 -0.0215571 0.226274 0.138858 -0.0137148 0.226295 0.138796 -0.0139124 0.226355 0.138698 -0.0140867 0.226544 0.136714 -0.0208187 0.226274 0.123045 -0.045307 0.226297 0.117449 -0.050888 0.226274 0.118468 -0.0499904 0.226274 0.0935542 -0.0647599 0.226295 0.0933519 -0.0648046 0.226355 0.0931523 -0.0648074 0.226376 0.0861251 -0.0666709 0.226274 0.0888617 -0.0661371 0.226301 0.0859339 -0.0667878 0.226355 0.0579161 -0.0667014 0.226295 0.0506476 -0.0648046 0.226274 0.0551382 -0.0661371 0.226295 0.026556 -0.0508951 0.226274 0.0255316 -0.0499904 0.226574 0.0216586 -0.0456422 0.226295 0.0211074 -0.0454466 0.226355 0.00530145 -0.0140867 0.226355 0.00719545 -0.0211552 0.226295 0.00719819 -0.0213548 0.226274 0.00514157 -0.0137148 0.226355 0.00530145 0.014081 0.226355 0.00719545 0.0211495 0.226295 0.005204 0.0139067 0.226274 0.00514157 0.0137091 0.226295 0.00719824 0.0213495 0.226295 0.0211077 0.0454411 0.226355 0.0212793 0.0455433 0.226274 0.0255316 0.0499847 0.226355 0.0264538 0.0507178 0.226295 0.050648 0.0647989 0.226274 0.0551382 0.0661314 0.226355 0.0579161 0.0666957 0.226295 0.0580908 0.0667933 0.228754 0.117637 0.0503802 0.226297 0.117449 0.050883 0.228738 0.117304 0.0510422 0.228741 0.117514 0.0507808 0.226361 0.117552 0.0507043 0.226574 0.122327 0.045637 0.228763 0.122188 0.0456315 0.226574 0.121928 0.0455669 0.228749 0.122524 0.0456114 0.226574 0.122341 0.0456365 0.226355 0.122721 0.0455433 0.226295 0.122893 0.0454409 0.226274 0.136757 0.0215514 0.228741 0.136808 0.0212356 0.228763 0.138281 0.0144236 0.226574 0.138404 0.014359 0.228781 0.137955 0.0145053 0.226574 0.13762 0.0144741 0.228749 0.138562 0.0142384 0.228743 0.138698 0.014081 0.22874 0.138765 0.0139709 0.228738 0.138858 0.0137091 0.226574 0.138404 -0.0143647 0.228757 0.13839 -0.0143732 0.228741 0.138737 -0.0140272 0.226574 0.138417 -0.014357 0.228801 0.13762 -0.0144798 0.228749 0.136765 -0.0209504 0.228763 0.136614 -0.0206497 0.226574 0.136451 -0.0204753 0.228738 0.123045 -0.045307 0.226295 0.122892 -0.0454469 0.226574 0.122327 -0.0456427 0.228757 0.12231 -0.0456431 0.228751 0.122468 -0.0456285 0.226355 0.122721 -0.0455491 0.228765 0.122133 -0.0456295 0.226574 0.121928 -0.0455726 0.228801 0.12159 -0.0453503 0.228763 0.117634 -0.0501908 0.228781 0.117542 -0.0498673 0.226574 0.117564 -0.0499173 0.226574 0.117347 -0.0495929 0.228738 0.0935542 -0.0647599 0.228751 0.0928936 -0.0647497 0.228741 0.093223 -0.064811 0.228801 0.0864769 -0.0656228 0.226295 0.0580904 -0.0667988 0.228741 0.0579756 -0.0667398 0.228756 0.0576381 -0.0664072 0.228751 0.0577209 -0.0665221 0.226574 0.0576458 -0.0664194 0.228784 0.0574891 -0.0659027 0.226574 0.0512227 -0.0646984 0.226574 0.0512355 -0.0646916 0.226574 0.0517274 -0.0640699 0.228749 0.0510522 -0.0647679 0.228743 0.0508477 -0.0648074 0.22874 0.0507189 -0.0648102 0.226355 0.0508476 -0.0648074 0.226574 0.0264302 -0.0499311 0.226355 0.0264538 -0.0507236 0.226574 0.021673 -0.0456427 0.226574 0.0220717 -0.0455726 0.228763 0.0218119 -0.0456372 0.228781 0.0221354 -0.0455447 0.228749 0.0214762 -0.0456172 0.226355 0.0212793 -0.0455491 0.22874 0.0211664 -0.0454871 0.228756 0.00731122 -0.0207673 0.226574 0.00731121 -0.0207673 0.228751 0.00725308 -0.0208965 0.226574 0.00730445 -0.0207801 0.228741 0.00719185 -0.0212259 0.228784 0.00767364 -0.020386 0.226574 0.00757123 -0.0204571 0.226574 0.00793291 -0.0202754 0.226574 0.00558338 -0.014357 0.228763 0.00571867 -0.0144293 0.228781 0.00604508 -0.014511 0.226574 0.00638 -0.0144798 0.228743 0.00530146 -0.0140867 0.226295 0.00520384 -0.013912 0.22874 0.00523466 -0.0139766 0.228765 0.00577054 0.0144447 0.226574 0.00559563 0.014359 0.228757 0.00560964 0.0143675 0.228751 0.00548071 0.0142762 0.228784 0.00610016 0.014508 0.226574 0.00731121 0.0207616 0.228781 0.00762728 0.0204101 0.226574 0.00757123 0.0204514 0.228749 0.00723493 0.0209449 0.226574 0.00730445 0.0207744 0.22874 0.00719264 0.0212782 0.228738 0.00724291 0.0215514 0.228765 0.0218674 0.0456238 0.226574 0.0220717 0.0455669 0.228757 0.0216894 0.0456374 0.228751 0.0215321 0.0456228 0.228741 0.0212162 0.0455111 0.228801 0.0224099 0.0453446 0.228763 0.0263656 0.0501852 0.226574 0.0264302 0.0499254 0.228781 0.0264581 0.0498617 0.228749 0.0263857 0.0505209 0.228743 0.0264538 0.0507178 0.226295 0.0265562 0.0508897 0.228738 0.0504457 0.0647542 0.228741 0.0507769 0.0648053 0.226574 0.0515457 0.0644259 0.228757 0.0512499 0.064678 0.228751 0.0511064 0.064744 0.226574 0.0512355 0.0646859 0.226355 0.0508476 0.0648017 0.228765 0.0513972 0.0645773 0.228784 0.0516168 0.0643235 0.226574 0.0576381 0.0664015 0.226574 0.0574995 0.0660212 0.228749 0.0577587 0.0665592 0.226574 0.0576458 0.0664137 0.228743 0.0579161 0.0666956 0.22874 0.0580262 0.0667624 0.224774 0.119739 0.0461359 0.224774 0.119524 0.0469359 0.226574 0.118939 0.0475215 0.226574 0.117339 0.0475215 0.224774 0.116753 0.0469359 0.226574 0.136412 0.0176851 0.224774 0.135827 0.0182707 0.226574 0.136412 -0.0160908 0.224774 0.135827 -0.0155052 0.224774 0.135027 -0.0152908 0.224774 0.134227 -0.0155052 0.224774 0.133641 -0.0160908 0.224774 0.133427 -0.0168908 0.226574 0.133427 -0.0168908 0.224774 0.119524 -0.0453416 0.226574 0.119524 -0.0453416 0.226574 0.117339 -0.0447559 0.224774 0.0902735 -0.0622295 0.226574 0.0902735 -0.0622295 0.224774 0.0896879 -0.0616439 0.224774 0.0880879 -0.0616439 0.226574 0.0880879 -0.0616439 0.226574 0.0875023 -0.0622295 0.226574 0.0872879 -0.0630295 0.224774 0.0561096 -0.0617786 0.224774 0.054756 -0.0614696 0.226574 0.054756 -0.0614696 0.224774 0.0536705 -0.0623353 0.224774 0.0272469 -0.0453416 0.224774 0.0266612 -0.0447559 0.226574 0.0272469 -0.0453416 0.226574 0.0266612 -0.0447559 0.226574 0.0258612 -0.0445416 0.224774 0.0258612 -0.0445416 0.224774 0.0250612 -0.0447559 0.226574 0.0250612 -0.0447559 0.226574 0.0244756 -0.0453416 0.224774 0.0103589 -0.0160908 0.226574 0.0103589 -0.0160908 0.224774 0.0089733 -0.0152908 0.226574 0.0081733 -0.0155052 0.226574 0.00758766 -0.0160908 0.224774 0.00758766 -0.0160908 0.224774 0.0097733 0.0182707 0.226574 0.0097733 0.0182707 0.224774 0.0089733 0.0184851 0.226574 0.0089733 0.0184851 0.224774 0.0081733 0.0182707 0.226574 0.00758766 0.0176851 0.224774 0.0272469 0.0469359 0.226574 0.0272469 0.0469359 0.226574 0.0266612 0.0475215 0.224774 0.0258612 0.0477359 0.226574 0.0258612 0.0477359 0.224774 0.0244756 0.0469359 0.226574 0.0244756 0.0469359 0.224774 0.0564977 0.0638238 0.224774 0.055912 0.0644094 0.224774 0.055112 0.0646238 0.226574 0.055112 0.0646238 0.226574 0.054312 0.0644094 0.226574 0.0517274 0.0640642 0.229484 0.0580098 0.0638003 0.229625 0.0580732 0.0635048 0.230739 0.0571879 0.060858 0.226574 0.0565138 0.0603715 0.230801 0.0569692 0.0606678 0.230921 0.0558937 0.0601274 0.226574 0.0552242 0.0600259 0.230774 0.0545506 0.0600768 0.226574 0.0539123 0.0602741 0.230599 0.0539078 0.0602761 0.226574 0.0528381 0.0610669 0.226574 0.0512227 0.0646927 0.226574 0.0537264 0.0638238 0.226574 0.055912 0.0644094 0.226574 0.053512 0.0630238 0.226574 0.0522142 0.0622473 0.226574 0.054312 0.0616382 0.226574 0.055912 0.0616382 0.226574 0.0575258 0.0612423 0.226574 0.0580597 0.0624661 0.226574 0.0564977 0.0638238 0.226574 0.0580098 0.0638003 0.226574 0.057523 0.0656171 0.229484 0.116017 0.0482572 0.228801 0.117347 0.0495872 0.226574 0.12026 0.0440145 0.229484 0.12026 0.0440145 0.226574 0.117669 0.0431728 0.230903 0.116376 0.0437081 0.23078 0.117125 0.0433122 0.230921 0.115945 0.0440899 0.230491 0.115139 0.0461359 0.226574 0.119739 0.0461359 0.226574 0.119524 0.0469359 0.226574 0.117639 0.0503385 0.226574 0.116017 0.0482572 0.226574 0.115367 0.0472839 0.226574 0.116753 0.0469359 0.226574 0.116539 0.0461359 0.226574 0.116753 0.0453359 0.226574 0.115466 0.0447739 0.226574 0.116375 0.0437088 0.226574 0.119066 0.0432827 0.226574 0.12159 0.0453446 0.226574 0.11764 0.0502943 0.226574 0.118139 0.0477359 0.228801 0.136067 0.0202697 0.230895 0.132326 0.0155788 0.226574 0.132325 0.0155805 0.230917 0.132195 0.0158929 0.226574 0.135027 0.0184851 0.226574 0.135827 0.0154994 0.226574 0.138024 0.0144976 0.226574 0.136412 0.0160851 0.226574 0.134227 0.0182707 0.226574 0.133092 0.0191782 0.226574 0.133641 0.0176851 0.226574 0.132027 0.0168851 0.226574 0.134227 0.0154994 0.226574 0.133187 0.0145151 0.226574 0.135027 0.0152851 0.226574 0.134433 0.0139443 0.226574 0.135803 0.0139873 0.226574 0.135827 0.0182707 0.226574 0.136627 0.0168851 0.229484 0.135803 -0.013993 0.226574 0.13762 -0.0144798 0.229484 0.13425 -0.0197886 0.226574 0.133098 -0.0191889 0.23008 0.1331 -0.0191904 0.226574 0.132308 -0.0181587 0.230474 0.132454 -0.0184334 0.226574 0.132027 -0.0168908 0.226574 0.135027 -0.0152908 0.226574 0.134441 -0.0139484 0.226574 0.134227 -0.0155052 0.226574 0.133641 -0.0160908 0.226574 0.133641 -0.0176908 0.226574 0.136627 -0.0168908 0.226574 0.135027 -0.0184908 0.226574 0.13425 -0.0197886 0.226574 0.136067 -0.0202754 0.226574 0.136695 -0.0207801 0.226574 0.135827 -0.0155052 0.226574 0.138024 -0.0145033 0.229484 0.116017 -0.0482629 0.229814 0.115578 -0.0477045 0.226574 0.115367 -0.0472896 0.230009 0.11538 -0.0473193 0.230279 0.115193 -0.0467075 0.226574 0.115139 -0.0461416 0.230491 0.115139 -0.0461416 0.226574 0.122341 -0.0456422 0.226574 0.118139 -0.0477416 0.226574 0.117639 -0.0503442 0.226574 0.11764 -0.0503 0.226574 0.118939 -0.0447559 0.226574 0.119066 -0.0432884 0.226574 0.118139 -0.0445416 0.226574 0.116375 -0.0437145 0.226574 0.116753 -0.0453416 0.226574 0.115466 -0.0447796 0.226574 0.116539 -0.0461416 0.226574 0.116753 -0.0469416 0.226574 0.117339 -0.0475272 0.226574 0.116017 -0.0482629 0.226574 0.119739 -0.0461416 0.226574 0.12159 -0.0453503 0.226574 0.12026 -0.0440203 0.226574 0.0864769 -0.0656228 0.226574 0.0859901 -0.063806 0.226574 0.0858879 -0.0630295 0.229848 0.0858879 -0.0630295 0.226574 0.0927772 -0.0646984 0.226574 0.0902735 -0.0638295 0.226574 0.0875023 -0.0638295 0.226574 0.0864112 -0.0663172 0.226574 0.0917857 -0.0622531 0.226574 0.0896879 -0.0616439 0.226574 0.0888879 -0.0614295 0.226574 0.0927644 -0.0646916 0.226574 0.0924542 -0.0644316 0.226574 0.0922725 -0.0640699 0.229484 0.0522142 -0.0622531 0.226574 0.0522142 -0.0622531 0.226574 0.0529907 -0.0609082 0.230092 0.0528313 -0.0610806 0.23047 0.0535607 -0.0604618 0.226574 0.0543356 -0.0601317 0.230739 0.0543972 -0.0601159 0.230801 0.0546816 -0.0600605 0.230774 0.0570717 -0.060758 0.226574 0.0558885 -0.0601317 0.230891 0.0552863 -0.0600346 0.230723 0.0572358 -0.0609107 0.230455 0.0577601 -0.0616196 0.23019 0.0580108 -0.062257 0.226574 0.0580098 -0.0622531 0.226574 0.0580098 -0.063806 0.226574 0.055112 -0.0646295 0.226574 0.0576381 -0.0664072 0.226574 0.0574995 -0.0660269 0.226574 0.0564977 -0.0638295 0.226574 0.057523 -0.0656228 0.226574 0.056712 -0.0630295 0.226574 0.0565536 -0.0623353 0.226574 0.0561096 -0.0617786 0.226574 0.0572333 -0.0609082 0.226574 0.055468 -0.0614696 0.226574 0.0541144 -0.0617786 0.226574 0.0536705 -0.0623353 0.226574 0.0515457 -0.0644316 0.226574 0.0237399 -0.0440203 0.230092 0.0248605 -0.0433134 0.226574 0.0250848 -0.0432438 0.230739 0.026699 -0.0432609 0.226574 0.0266377 -0.0432438 0.226574 0.0279826 -0.0440203 0.230921 0.0279787 -0.0440164 0.230723 0.0287599 -0.0453685 0.226574 0.028759 -0.0453651 0.226574 0.028759 -0.046918 0.229997 0.0286091 -0.0473453 0.226574 0.0279826 -0.0482629 0.226574 0.0244756 -0.0469416 0.226574 0.0250612 -0.0475272 0.226574 0.0224099 -0.0453503 0.226574 0.0242612 -0.0461416 0.226574 0.0263606 -0.0503442 0.226574 0.0263601 -0.0503298 0.226574 0.0266612 -0.0475272 0.226574 0.0266525 -0.0495929 0.226574 0.0274612 -0.0461416 0.229484 0.00819684 -0.013993 0.229625 0.00849227 -0.0139296 0.230092 0.00952075 -0.0139412 0.226574 0.00974976 -0.013993 0.23047 0.0104214 -0.0142634 0.226574 0.0118711 -0.0161143 0.230723 0.0118702 -0.0176706 0.226574 0.0118711 -0.0176673 0.23019 0.0110917 -0.019015 0.226574 0.0097733 -0.0182764 0.226574 0.00974976 -0.0197886 0.226574 0.0103589 -0.0176908 0.226574 0.0110946 -0.0190121 0.226574 0.0105733 -0.0168908 0.226574 0.0110946 -0.0147695 0.226574 0.0097733 -0.0155052 0.226574 0.0089733 -0.0152908 0.226574 0.00819684 -0.013993 0.226574 0.00597592 -0.0145033 0.226574 0.00559563 -0.0143647 0.229484 0.00819684 0.0139873 0.226574 0.00819684 0.0139873 0.229484 0.00974976 0.0197829 0.229625 0.0100374 0.01969 0.230092 0.0109223 0.0191658 0.226574 0.0110946 0.0190064 0.230891 0.0119682 0.0167108 0.230921 0.0118725 0.0161138 0.226574 0.0118711 0.0161086 0.230774 0.0112448 0.0149254 0.230723 0.0110922 0.0147613 0.226574 0.0110946 0.0147638 0.230455 0.0103832 0.014237 0.226574 0.00558338 0.0143513 0.226574 0.00758766 0.0160851 0.226574 0.0073733 0.0168851 0.226574 0.00597592 0.0144976 0.226574 0.00638 0.0144741 0.226574 0.0089733 0.0152851 0.226574 0.00974976 0.0139873 0.226574 0.0097733 0.0154994 0.226574 0.0103589 0.0160851 0.226574 0.0081733 0.0182707 0.226574 0.0105733 0.0168851 0.226574 0.0118711 0.0176615 0.226574 0.0103589 0.0176851 0.226574 0.00974976 0.0197829 0.226574 0.00793291 0.0202697 0.228801 0.0266525 0.0495872 0.229484 0.0279826 0.0482572 0.226574 0.0279826 0.0482572 0.229625 0.0281852 0.048033 0.230092 0.0286894 0.0471365 0.226574 0.0288424 0.0458 0.230599 0.0288428 0.0458034 0.230884 0.0274552 0.0435944 0.230921 0.0279864 0.0440184 0.230599 0.0261922 0.0431542 0.230455 0.0257582 0.0431376 0.226574 0.0248704 0.0433042 0.226301 0.0859345 0.0667818 0.226376 0.0861251 0.0666652 0.226295 0.0933523 0.0647989 0.228738 0.0857119 0.0668555 0.228754 0.0863294 0.0664506 0.226574 0.0864112 0.0663115 0.228765 0.0864457 0.0662315 0.228777 0.0865019 0.0660104 0.226574 0.0924542 0.0644259 0.226574 0.0922725 0.0640642 0.228749 0.0929477 0.0647622 0.226355 0.0931523 0.0648017 0.22874 0.093281 0.0648045 0.224774 0.0896879 0.0644094 0.224774 0.0888879 0.0646238 0.226574 0.0896879 0.0644094 0.226574 0.0888879 0.0646238 0.224774 0.0875023 0.0638238 0.224774 0.0872879 0.0630238 0.229484 0.0859901 0.0638003 0.228801 0.0864769 0.0656171 0.226574 0.0864769 0.0656171 0.226574 0.0910997 0.060997 0.230009 0.0912874 0.0612232 0.226574 0.089914 0.0602047 0.230318 0.0907753 0.0606919 0.230136 0.0911013 0.0609987 0.230907 0.0885199 0.0600465 0.230762 0.0895048 0.0600879 0.226574 0.0884963 0.0600495 0.230887 0.0875111 0.0603584 0.226574 0.0858879 0.0630238 0.230691 0.086677 0.060996 0.226574 0.0902735 0.0638238 0.226574 0.0927644 0.0646859 0.226574 0.0927772 0.0646927 0.226574 0.0862269 0.0616386 0.226574 0.0880879 0.0616382 0.226574 0.0871672 0.0605663 0.226574 0.0896879 0.0616382 0.226574 0.0902735 0.0622238 0.226574 0.0904879 0.0630238 0.226574 0.0917857 0.0622473 0.226574 0.0863541 0.0664137 0.226574 0.0880879 0.0644094 0.226574 0.0875023 0.0638238 0.226574 0.086511 0.0658759 0.226574 0.0859901 0.0638003 0.233474 0.12835 -2.85742e-06 0.233474 0.11991 0.0296616 0.233274 0.105838 0.0448058 0.233474 0.0971173 0.0504396 0.233274 0.0873661 0.0540037 0.233474 0.0874209 0.054196 0.233274 0.0668191 0.0559076 0.233274 0.0566338 0.0540037 0.233474 0.0468826 0.0504396 0.233274 0.0469717 0.0502606 0.233274 0.0305046 0.0378252 0.233474 0.0380415 0.0449654 0.233474 0.0303568 0.0379599 0.233274 0.0242603 0.0295563 0.233474 0.0194551 0.0203531 0.235874 0.01565 -2.85742e-06 0.236074 0.016806 0.0103147 0.235874 0.0166094 0.0103514 0.235874 0.0194551 0.0203531 0.236074 0.0242603 0.0295563 0.235874 0.0240902 0.0296616 0.235874 0.0303568 0.0379599 0.235874 0.0380415 0.0449654 0.236074 0.0668191 0.0559076 0.236074 0.0873661 0.0540037 0.235874 0.0874209 0.054196 0.236074 0.105838 0.0448058 0.235874 0.0971173 0.0504396 0.235874 0.105958 0.0449654 0.236074 0.113495 0.0378252 0.236074 0.11974 0.0295563 0.236074 0.124358 0.0202809 0.235874 0.11991 0.0296616 0.235874 0.124545 0.0203531 0.235874 0.12739 0.0103514 0.236074 0.12815 -2.85742e-06 0.233514 0.0145 -2.85742e-06 0.233624 0.12961 -2.85742e-06 0.233659 0.129627 -2.85742e-06 0.233624 0.129391 0.00501817 0.233624 0.128735 0.010001 0.233624 0.127647 0.0149077 0.233774 0.127686 0.0149181 0.233774 0.126173 0.0197146 0.233774 0.124249 0.0243611 0.233624 0.121892 0.028802 0.233624 0.119191 0.0330408 0.233624 0.112736 0.0407334 0.233624 0.109031 0.0441288 0.233774 0.0963639 0.0522458 0.233624 0.0917037 0.0541327 0.233774 0.0917174 0.0541704 0.233624 0.0820038 0.0567317 0.233774 0.0820108 0.0567713 0.233624 0.077021 0.0573877 0.233774 0.0619891 0.0567713 0.233624 0.0522962 0.0541327 0.233774 0.0522825 0.0541704 0.233774 0.047636 0.0522458 0.233624 0.0349691 0.0441288 0.233774 0.0349433 0.0441596 0.233774 0.0278375 0.0370538 0.233774 0.0220736 0.0288221 0.233774 0.0197513 0.0243611 0.233624 0.0197877 0.0243441 0.233624 0.0163532 0.0149077 0.233624 0.0152654 0.010001 0.233774 0.0152258 0.010008 0.233774 0.0145693 0.00502167 0.233774 0.01435 -2.85742e-06 0.233624 0.0143902 -2.85742e-06 0.233624 0.0146094 0.00501817 0.233514 0.0153735 0.00998191 0.233624 0.0178644 0.0197009 0.233514 0.0179676 0.0196633 0.233624 0.0221084 0.028802 0.233514 0.0198873 0.0242977 0.233624 0.0248088 0.0330408 0.233514 0.0222035 0.0287471 0.233514 0.0248987 0.0329778 0.233624 0.0278683 0.037028 0.233624 0.0312637 0.0407334 0.233624 0.0389563 0.0471883 0.233514 0.0350397 0.0440447 0.233514 0.0390193 0.0470984 0.233624 0.0431951 0.0498887 0.233624 0.047653 0.0522094 0.233514 0.04325 0.0497936 0.233514 0.0523338 0.0540295 0.233624 0.0570894 0.0556439 0.233624 0.0619961 0.0567317 0.233514 0.0620152 0.0566236 0.233624 0.0669789 0.0573877 0.233624 0.072 0.057607 0.233514 0.072 0.0574971 0.233624 0.0869105 0.0556439 0.233514 0.0916661 0.0540295 0.233624 0.0963469 0.0522094 0.233624 0.100805 0.0498887 0.233624 0.105044 0.0471883 0.233514 0.104981 0.0470984 0.233514 0.112659 0.0406558 0.233624 0.116132 0.037028 0.233514 0.116048 0.0369574 0.233514 0.119101 0.0329778 0.233514 0.121796 0.0287471 0.233624 0.124212 0.0243441 0.233514 0.124113 0.0242977 0.233624 0.126135 0.0197009 0.233514 0.126032 0.0196633 0.233514 0.127541 0.0148792 0.233562 0.129562 -2.85742e-06 0.233514 0.129281 0.0050086 0.233474 0.127396 0.0148404 0.233514 0.128626 0.00998191 0.233474 0.125891 0.019612 0.233474 0.118978 0.0328918 0.233474 0.115933 0.036861 0.233514 0.10896 0.0440447 0.233514 0.10075 0.0497936 0.233514 0.0963005 0.0521098 0.233514 0.0868821 0.0555379 0.233474 0.0819587 0.0564759 0.233474 0.0769983 0.0571289 0.233514 0.0819847 0.0566236 0.233514 0.0770114 0.0572783 0.233474 0.072 0.0573471 0.233474 0.0670016 0.0571289 0.233514 0.0669885 0.0572783 0.233514 0.0571179 0.0555379 0.233474 0.0571567 0.055393 0.233474 0.0523851 0.0538885 0.233474 0.0477628 0.0519739 0.233514 0.0476994 0.0521098 0.233474 0.0391053 0.0469755 0.233474 0.0351361 0.0439298 0.233514 0.0313413 0.0406558 0.233514 0.0279524 0.0369574 0.233474 0.0250216 0.0328918 0.233474 0.0200232 0.0242343 0.233474 0.0181086 0.019612 0.233474 0.0166041 0.0148404 0.233474 0.0155212 0.00995587 0.233514 0.0164592 0.0148792 0.233474 0.0148682 0.00499552 0.233514 0.0147188 0.0050086 0.233474 0.01465 -2.85742e-06 0.235834 0.0147188 0.0050086 0.235574 0.01435 -2.85742e-06 0.235574 0.0145693 0.00502167 0.235724 0.0143902 -2.85742e-06 0.235724 0.0146094 0.00501817 0.235724 0.0152654 0.010001 0.235574 0.0152258 0.010008 0.235724 0.0163532 0.0149077 0.235724 0.0178644 0.0197009 0.235724 0.0221084 0.028802 0.235724 0.0248088 0.0330408 0.235724 0.0349691 0.0441288 0.235724 0.0389563 0.0471883 0.235574 0.0389333 0.0472213 0.235574 0.043175 0.0499235 0.235724 0.0431951 0.0498887 0.235574 0.047636 0.0522458 0.235724 0.0570894 0.0556439 0.235724 0.0619961 0.0567317 0.235724 0.0669789 0.0573877 0.235574 0.072 0.0576471 0.235574 0.0770245 0.0574278 0.235724 0.0820038 0.0567317 0.235724 0.0869105 0.0556439 0.235724 0.0917037 0.0541327 0.235724 0.0963469 0.0522094 0.235724 0.100805 0.0498887 0.235724 0.105044 0.0471883 0.235574 0.112765 0.0407618 0.235724 0.116132 0.037028 0.235574 0.116162 0.0370538 0.235574 0.119224 0.0330638 0.235724 0.121892 0.028802 0.235724 0.126135 0.0197009 0.235574 0.126173 0.0197146 0.235724 0.128735 0.010001 0.235574 0.127686 0.0149181 0.235574 0.128774 0.010008 0.235724 0.12961 -2.85742e-06 0.235574 0.129431 0.00502167 0.235724 0.129391 0.00501817 0.235724 0.127647 0.0149077 0.235834 0.126032 0.0196633 0.235724 0.124212 0.0243441 0.235724 0.119191 0.0330408 0.235724 0.112736 0.0407334 0.235834 0.112659 0.0406558 0.235724 0.109031 0.0441288 0.235834 0.10075 0.0497936 0.235834 0.0916661 0.0540295 0.235834 0.0819847 0.0566236 0.235724 0.077021 0.0573877 0.235724 0.072 0.057607 0.235834 0.072 0.0574971 0.235834 0.0669885 0.0572783 0.235834 0.0620152 0.0566236 0.235834 0.0571179 0.0555379 0.235724 0.0522962 0.0541327 0.235724 0.047653 0.0522094 0.235834 0.0523338 0.0540295 0.235834 0.0350397 0.0440447 0.235724 0.0312637 0.0407334 0.235834 0.0313413 0.0406558 0.235724 0.0278683 0.037028 0.235834 0.0222035 0.0287471 0.235724 0.0197877 0.0243441 0.235834 0.0164592 0.0148792 0.235834 0.0153735 0.00998191 0.235786 0.0144378 -2.85742e-06 0.235874 0.0148682 0.00499552 0.235834 0.0179676 0.0196633 0.235874 0.0181086 0.019612 0.235874 0.0200232 0.0242343 0.235834 0.0198873 0.0242977 0.235834 0.0248987 0.0329778 0.235874 0.0280673 0.036861 0.235874 0.0314474 0.0405497 0.235834 0.0279524 0.0369574 0.235834 0.0390193 0.0470984 0.235834 0.04325 0.0497936 0.235834 0.0476994 0.0521098 0.235874 0.0523851 0.0538885 0.235874 0.0571567 0.055393 0.235874 0.0620412 0.0564759 0.235874 0.0670016 0.0571289 0.235874 0.072 0.0573471 0.235874 0.0769983 0.0571289 0.235874 0.0819587 0.0564759 0.235834 0.0770114 0.0572783 0.235834 0.0868821 0.0555379 0.235834 0.0963005 0.0521098 0.235874 0.100675 0.0496637 0.235874 0.104895 0.0469755 0.235834 0.104981 0.0470984 0.235874 0.112553 0.0405497 0.235834 0.10896 0.0440447 0.235834 0.116048 0.0369574 0.235874 0.118978 0.0328918 0.235834 0.119101 0.0329778 0.235834 0.121796 0.0287471 0.235834 0.124113 0.0242977 0.235874 0.127396 0.0148404 0.235834 0.127541 0.0148792 0.235874 0.128479 0.00995587 0.235834 0.128626 0.00998191 0.235834 0.129281 0.0050086 0.235874 0.129132 0.00499552 0.235874 0.0151022 -0.00719072 0.235874 0.0964184 -0.0518947 0.235874 0.115933 0.036861 0.235874 0.121667 0.0286721 0.235874 0.123977 0.0242343 0.235874 0.125891 0.019612 0.235874 0.0186773 -0.0211148 0.235874 0.0194551 -0.0203588 0.235874 0.0166094 -0.0103571 0.235874 0.0164517 -0.0142652 0.235874 0.0301936 -0.0392616 0.235874 0.0542778 -0.054546 0.235874 0.0380415 -0.0449711 0.235874 0.0897221 -0.054546 0.235874 0.0874209 -0.0542017 0.235874 0.0827463 -0.056337 0.235874 0.0771993 -0.0561125 0.235874 0.0668006 -0.0561125 0.235874 0.0612536 -0.056337 0.235874 0.113643 -0.0379656 0.235874 0.105958 -0.0449711 0.235874 0.10273 -0.0484251 0.235874 0.12935 -2.85742e-06 0.235874 0.128898 -0.00719072 0.235874 0.11991 -0.0296673 0.235874 0.125323 -0.0211148 0.235874 0.122256 -0.0276314 0.235874 0.113643 0.0379599 0.235874 0.108864 0.0439298 0.235874 0.0916148 0.0538885 0.235874 0.0962371 0.0519739 0.235874 0.0391053 0.0469755 0.235874 0.0223334 0.0286721 0.235874 0.0166041 0.0148404 0.235874 0.0155212 0.00995587 0.235874 0.0868432 0.055393 0.235874 0.0668006 0.0561068 0.235874 0.0771993 0.0561068 0.235874 0.043325 0.0496637 0.235874 0.0468826 0.0504396 0.235874 0.056579 0.054196 0.235874 0.0477628 0.0519739 0.235874 0.0250216 0.0328918 0.235874 0.0351361 0.0439298 0.233474 0.113643 -0.0379656 0.233474 0.12739 0.0103514 0.233474 0.129132 0.00499552 0.233474 0.128479 0.00995587 0.233474 0.128898 -0.00719072 0.233474 0.12935 -2.85742e-06 0.233474 0.124545 0.0203531 0.233474 0.123977 0.0242343 0.233474 0.121667 0.0286721 0.233474 0.118397 -0.0337123 0.233474 0.122256 -0.0276314 0.233474 0.12739 -0.0103571 0.233474 0.01565 -2.85742e-06 0.233474 0.0166094 0.0103514 0.233474 0.105958 0.0449654 0.233474 0.104895 0.0469755 0.233474 0.0827463 -0.056337 0.233474 0.0971173 -0.0504453 0.233474 0.105958 -0.0449711 0.233474 0.0468826 -0.0504453 0.233474 0.056579 -0.0542017 0.233474 0.0303568 -0.0379656 0.233474 0.0380415 -0.0449711 0.233474 0.0354437 -0.0441918 0.233474 0.0164517 -0.0142652 0.233474 0.0194551 -0.0203588 0.233474 0.0240902 -0.0296673 0.233474 0.056579 0.054196 0.233474 0.112553 0.0405497 0.233474 0.113643 0.0379599 0.233474 0.108864 0.0439298 0.233474 0.0668006 -0.0561125 0.233474 0.0620412 0.0564759 0.233474 0.0668006 0.0561068 0.233474 0.0771993 0.0561068 0.233474 0.0868432 0.055393 0.233474 0.100675 0.0496637 0.233474 0.0962371 0.0519739 0.233474 0.0916148 0.0538885 0.233474 0.0240902 0.0296616 0.233474 0.0223334 0.0286721 0.233474 0.043325 0.0496637 0.233474 0.0314474 0.0405497 0.233474 0.0280673 0.036861 0.235574 0.0163143 0.0149181 0.235574 0.0178267 0.0197146 0.233774 0.0163143 0.0149181 0.233774 0.0178267 0.0197146 0.235574 0.0197513 0.0243611 0.235574 0.0220736 0.0288221 0.235574 0.0247758 0.0330638 0.233774 0.0247758 0.0330638 0.235574 0.0278375 0.0370538 0.235574 0.0312353 0.0407618 0.233774 0.0312353 0.0407618 0.235574 0.0349433 0.0441596 0.233774 0.0389333 0.0472213 0.233774 0.043175 0.0499235 0.235574 0.0522825 0.0541704 0.235574 0.057079 0.0556828 0.235574 0.0619891 0.0567713 0.233774 0.057079 0.0556828 0.235574 0.0669754 0.0574278 0.233774 0.0669754 0.0574278 0.233774 0.072 0.0576471 0.235574 0.0820108 0.0567713 0.233774 0.0770245 0.0574278 0.233774 0.0869209 0.0556828 0.235574 0.0869209 0.0556828 0.235574 0.0917174 0.0541704 0.235574 0.0963639 0.0522458 0.235574 0.100825 0.0499235 0.233774 0.100825 0.0499235 0.233774 0.105067 0.0472213 0.235574 0.105067 0.0472213 0.235574 0.109057 0.0441596 0.233774 0.109057 0.0441596 0.233774 0.112765 0.0407618 0.233774 0.116162 0.0370538 0.233774 0.119224 0.0330638 0.235574 0.121926 0.0288221 0.233774 0.121926 0.0288221 0.235574 0.124249 0.0243611 0.233774 0.128774 0.010008 0.233774 0.129431 0.00502167 0.233696 0.130649 0.00485694 0.233696 0.130047 0.00968353 0.233696 0.129049 0.014444 0.233696 0.127661 0.0191057 0.2333 0.129128 0.014464 0.233696 0.127301 0.020125 0.233696 0.125893 0.0236369 0.233696 0.123757 0.0280066 0.2333 0.125968 0.0236698 0.233696 0.122966 0.0294221 0.2333 0.118505 0.0361938 0.233696 0.118441 0.0361436 0.233696 0.117082 0.0378252 0.233696 0.115297 0.0398552 0.233696 0.111858 0.0432945 0.233696 0.109828 0.0450789 0.233696 0.108146 0.0464381 0.2333 0.108197 0.0465026 0.233696 0.101425 0.0509627 0.2333 0.100048 0.0518261 0.233696 0.100009 0.0517542 0.233696 0.0956397 0.0538904 0.2333 0.0911351 0.0557358 0.233696 0.0921278 0.0552981 0.233696 0.0911085 0.0556585 0.233696 0.0864468 0.0570463 0.233696 0.0822192 0.0579531 0.2333 0.0816998 0.0581252 0.233696 0.0768597 0.0586461 0.233696 0.072 0.0588471 0.2333 0.072 0.0589289 0.233696 0.0671402 0.0586461 0.2333 0.0623001 0.0581252 0.233696 0.0518721 0.0552981 0.233696 0.042575 0.0509627 0.2333 0.0397673 0.0493329 0.233696 0.0341719 0.0450789 0.2333 0.0358033 0.0465026 0.2333 0.0320865 0.0433547 0.233696 0.0321419 0.0432945 0.2333 0.0286424 0.0399106 0.233696 0.025559 0.0361436 0.233696 0.0227327 0.032185 0.2333 0.0226642 0.0322298 0.233696 0.0210344 0.0294221 0.233696 0.0202429 0.0280066 0.2333 0.020171 0.0280456 0.2333 0.0180318 0.0236698 0.233696 0.0181067 0.0236369 0.233696 0.0163386 0.0191057 0.232968 0.131164 -2.85742e-06 0.232968 0.130962 0.00488285 0.232968 0.130357 0.00973518 0.232756 0.130696 0.00979183 0.232968 0.129353 0.014521 0.232968 0.127958 0.0192076 0.232968 0.126181 0.023763 0.232756 0.124336 0.0283198 0.232968 0.12153 0.0323566 0.232756 0.11896 0.0365477 0.232968 0.11207 0.0435253 0.232756 0.115781 0.0403008 0.232756 0.112304 0.0437786 0.232968 0.100159 0.0520301 0.232756 0.104548 0.0498152 0.232968 0.0957658 0.0541777 0.232756 0.095904 0.054493 0.232968 0.0865238 0.0573505 0.232968 0.081738 0.058354 0.232968 0.0671143 0.0589588 0.232968 0.0622619 0.058354 0.232968 0.0574761 0.0573505 0.232756 0.0573916 0.0576842 0.232968 0.0438411 0.0520301 0.232968 0.0284718 0.0400677 0.232968 0.0253114 0.0363363 0.232756 0.0250398 0.0365477 0.232756 0.0221819 0.0325449 0.232968 0.0178194 0.023763 0.232756 0.0175041 0.0239012 0.232968 0.0160419 0.0192076 0.2333 0.130932 -2.85742e-06 0.2333 0.13073 0.00486369 0.2333 0.130128 0.009697 0.2333 0.127739 0.0191323 0.2333 0.123829 0.0280456 0.2333 0.121336 0.0322298 0.232968 0.124033 0.028156 0.232968 0.118688 0.0363363 0.2333 0.115357 0.0399106 0.232968 0.115528 0.0400677 0.2333 0.111913 0.0433547 0.232968 0.108339 0.0466857 0.2333 0.104233 0.0493329 0.232968 0.104359 0.0495271 0.2333 0.0956726 0.0539653 0.2333 0.0864669 0.0571256 0.232968 0.0912104 0.0559552 0.2333 0.0768665 0.0587276 0.232968 0.0768857 0.0589588 0.232968 0.072 0.0591609 0.2333 0.0671334 0.0587276 0.2333 0.0575331 0.0571256 0.2333 0.0528648 0.0557358 0.232968 0.0527895 0.0559552 0.232968 0.0482341 0.0541777 0.2333 0.0483273 0.0539653 0.2333 0.0439515 0.0518261 0.232968 0.0396404 0.0495271 0.232968 0.0356608 0.0466857 0.232968 0.0319294 0.0435253 0.2333 0.0254945 0.0361938 0.232968 0.02247 0.0323566 0.232968 0.019967 0.028156 0.2333 0.0162613 0.0191323 0.2333 0.0148715 0.014464 0.232968 0.0146466 0.014521 0.2333 0.0138719 0.009697 0.233696 0.0149508 0.014444 0.233696 0.0139526 0.00968353 0.232968 0.0136431 0.00973518 0.233696 0.013351 0.00485694 0.232968 0.0130383 0.00488285 0.2333 0.0132695 0.00486369 0.230674 0.0626356 -0.0470806 0.230674 0.072 -0.0480029 0.230674 0.0813643 -0.0470806 0.230674 0.0977784 -0.038583 0.230674 0.0986673 -0.0399134 0.230674 0.10481 -0.0328126 0.230674 0.105941 -0.033944 0.230674 0.11058 -0.0257813 0.230674 0.114868 -0.0177594 0.230674 0.116346 -0.0183717 0.230674 0.117508 -0.00905505 0.230674 0.12 -2.85742e-06 0.230674 0.117508 0.00904933 0.230674 0.119078 0.00936148 0.230674 0.11191 0.0266645 0.230674 0.0977784 0.0385773 0.230674 0.0986673 0.0399077 0.230674 0.0810521 0.0455056 0.230674 0.072 0.0463971 0.230674 0.072 0.0479971 0.230674 0.0536312 0.0443434 0.230674 0.0462215 0.0385773 0.230674 0.0453326 0.0399077 0.230674 0.0380588 0.0339383 0.230674 0.0334198 0.0257756 0.230674 0.0264915 0.00904933 0.230674 0.0256 -2.85742e-06 0.230674 0.0291319 -0.0177594 0.230674 0.0276537 -0.0183717 0.230674 0.0453326 -0.0399134 0.230674 0.116346 0.0183659 0.238174 0.119078 0.00936148 0.238174 0.11191 0.0266645 0.230674 0.105941 0.0339383 0.230674 0.0903688 0.0443434 0.238174 0.0903688 0.0443434 0.230674 0.0813643 0.0470748 0.238174 0.072 0.0479971 0.230674 0.0626356 0.0470748 0.238174 0.0626356 0.0470748 0.238174 0.0536312 0.0443434 0.238174 0.0453326 0.0399077 0.238174 0.0380588 0.0339383 0.230674 0.0320894 0.0266645 0.230674 0.0276537 0.0183659 0.230674 0.0249223 0.00936148 0.238474 0.0625771 0.0473691 0.238474 0.0535163 0.0446205 0.238474 0.0451659 0.0401571 0.238474 0.044411 0.0412869 0.238474 0.0378467 0.0341504 0.238474 0.03184 0.0268312 0.238474 0.0368859 0.0351112 0.238474 0.0273766 0.0184808 0.238474 0.0261213 0.0190007 0.238474 0.024628 0.00942 0.238474 0.0237 -2.85742e-06 0.238474 0.0273766 -0.0184865 0.238474 0.0261213 -0.0190064 0.238474 0.0307102 -0.0275918 0.238474 0.044411 -0.0412926 0.238474 0.0625771 -0.0473748 0.238474 0.106153 -0.0341561 0.238474 0.11216 -0.0268369 0.238474 0.11329 -0.0275918 0.238474 0.116623 -0.0184865 0.238474 0.119372 -0.00942572 0.238474 0.1203 -2.85742e-06 0.238474 0.116623 0.0184808 0.238474 0.11216 0.0268312 0.238474 0.106153 0.0341504 0.238474 0.098834 0.0401571 0.238474 0.072 0.0482971 0.238474 0.0816879 0.0487017 0.236974 0.120901 -0.00972981 0.236974 0.118063 -0.019083 0.238274 0.118063 -0.019083 0.236974 0.107255 -0.0352583 0.238274 0.0910801 -0.0460663 0.238274 0.072 -0.0498616 0.236974 0.072 -0.0498616 0.238274 0.062273 -0.0489036 0.238274 0.0529198 -0.0460663 0.238274 0.0367445 -0.0352583 0.236974 0.0367445 -0.0352583 0.238274 0.0259365 -0.019083 0.236974 0.0305439 -0.0277029 0.236974 0.0259365 -0.019083 0.236974 0.0293191 -0.0264298 0.236974 0.0417477 -0.0400633 0.236974 0.0442999 -0.0414589 0.236974 0.0529198 -0.0460663 0.236974 0.062273 -0.0489036 0.236974 0.0673681 -0.0499887 0.236974 0.0766318 -0.0499887 0.236974 0.0817269 -0.0489036 0.236974 0.0910801 -0.0460663 0.236974 0.0857378 -0.0482865 0.236974 0.0997 -0.0414589 0.236974 0.094376 -0.0449401 0.236974 0.109098 -0.0338224 0.236974 0.113456 -0.0277029 0.236974 0.114681 -0.0264298 0.236974 0.11881 -0.0181372 0.236974 0.121345 -0.00922708 0.236974 0.121859 -2.85742e-06 0.236974 0.121345 0.00922137 0.236974 0.11881 0.0181315 0.236974 0.109098 0.0338167 0.236974 0.107255 0.0352526 0.236974 0.0997 0.0414532 0.236974 0.094376 0.0449343 0.236974 0.0857378 0.0482808 0.236974 0.0817269 0.0488979 0.236974 0.0529198 0.0460606 0.236974 0.0442999 0.0414532 0.236974 0.0496239 0.0449343 0.236974 0.0367445 0.0352526 0.236974 0.0417477 0.0400576 0.236974 0.0226547 0.00922137 0.236974 0.0218 -2.85742e-06 0.236974 0.0226547 -0.00922708 0.236974 0.0230992 -0.00972981 0.230674 0.1225 -2.85742e-06 0.236674 0.12164 -0.00928221 0.236674 0.11909 -0.0182456 0.230674 0.11909 -0.0182456 0.230674 0.114936 -0.0265877 0.236674 0.114936 -0.0265877 0.230674 0.102433 -0.0403027 0.236674 0.102433 -0.0403027 0.230674 0.0945097 -0.0452086 0.236674 0.0858199 -0.0485751 0.236674 0.0673404 -0.0502874 0.236674 0.0494902 -0.0452086 0.230674 0.0415669 -0.0403027 0.236674 0.03468 -0.0340245 0.236674 0.029064 -0.0265877 0.230674 0.029064 -0.0265877 0.230674 0.0249101 -0.0182456 0.236674 0.0223598 -0.00928221 0.230674 0.0223598 -0.00928221 0.230674 0.105838 0.0448058 0.230674 0.0945097 0.0452029 0.230674 0.0858199 0.0485693 0.230674 0.0873661 0.0540037 0.230674 0.0668191 0.0559076 0.230674 0.0566338 0.0540037 0.230674 0.0469717 0.0502606 0.230674 0.0415669 0.040297 0.230674 0.0305046 0.0378252 0.230674 0.029064 0.026582 0.230674 0.0242603 0.0295563 0.230674 0.016806 0.0103147 0.230674 0.0215 -2.85742e-06 0.230674 0.03468 -0.0340245 0.230674 0.0494902 -0.0452086 0.230674 0.05818 -0.0485751 0.230674 0.0566338 -0.0540094 0.230674 0.0673404 -0.0502874 0.230674 0.0766595 -0.0502874 0.230674 0.0858199 -0.0485751 0.230674 0.0873661 -0.0540094 0.230674 0.0970282 -0.0502663 0.230674 0.105838 -0.0448115 0.230674 0.113495 -0.0378309 0.230674 0.10932 -0.0340245 0.230674 0.124358 -0.0202866 0.230674 0.12164 -0.00928221 0.230674 0.12815 -2.85742e-06 0.230674 0.12164 0.00927649 0.230674 0.11909 0.0182398 0.230674 0.124358 0.0202809 0.230674 0.114936 0.026582 0.230674 0.10932 0.0340188 0.230674 0.11974 0.0295563 0.230674 0.102433 0.040297 0.236874 0.0380415 -0.0449711 0.236874 0.056579 -0.0542017 0.236874 0.0619891 -0.056777 0.236874 0.072 -0.0576529 0.236874 0.0917174 -0.0541761 0.236874 0.100825 -0.0499292 0.236874 0.105958 -0.0449711 0.236874 0.109057 -0.0441653 0.236874 0.128774 -0.0100137 0.236874 0.12965 -2.85742e-06 0.236874 0.116162 0.0370538 0.236874 0.109057 0.0441596 0.236874 0.0874209 0.054196 0.236874 0.0820108 0.0567713 0.236874 0.056579 0.054196 0.236874 0.0619891 0.0567713 0.236874 0.0468826 0.0504396 0.236874 0.0522825 0.0541704 0.236874 0.0349433 0.0441596 0.236874 0.0303568 0.0379599 0.236874 0.0240902 0.0296616 0.236874 0.0278375 0.0370538 0.236874 0.0194551 0.0203531 0.236874 0.0152258 0.010008 0.236874 0.01565 -2.85742e-06 0.236874 0.0166094 -0.0103571 0.236874 0.01435 -2.85742e-06 0.236874 0.0152258 -0.0100137 0.236874 0.0194551 -0.0203588 0.236874 0.0178267 -0.0197203 0.236874 0.0303568 -0.0379656 0.236874 0.0349433 -0.0441653 0.236874 0.128774 0.010008 0.236874 0.126173 0.0197146 0.237674 0.126173 0.0197146 0.236874 0.121926 0.0288221 0.237674 0.121926 0.0288221 0.237674 0.116162 0.0370538 0.236874 0.100825 0.0499235 0.236874 0.0917174 0.0541704 0.237674 0.0820108 0.0567713 0.236874 0.072 0.0576471 0.236874 0.043175 0.0499235 0.237674 0.0349433 0.0441596 0.236874 0.0220736 0.0288221 0.236874 0.0178267 0.0197146 0.237674 0.0220736 0.0288221 0.237674 0.0178267 0.0197146 0.237674 0.01435 -2.85742e-06 0.237874 0.0917858 0.0543584 0.237874 0.101325 0.0507895 0.237874 0.0820455 0.0569683 0.237874 0.0821844 0.0577561 0.237874 0.072 0.0578471 0.237874 0.0619544 0.0569683 0.237874 0.072 0.0586471 0.237874 0.0618155 0.0577561 0.237874 0.0522141 0.0543584 0.237874 0.0519405 0.0551101 0.237874 0.042675 0.0507895 0.237874 0.0270715 0.0376966 0.237874 0.0276843 0.0371824 0.237874 0.0219004 0.0289221 0.237874 0.016887 0.0200566 0.237874 0.014241 0.0101816 0.237874 0.0150288 -0.0100484 0.237874 0.014241 -0.0101873 0.237874 0.016887 -0.0200623 0.237874 0.0276843 -0.0371881 0.237874 0.0270715 -0.0377024 0.237874 0.0343005 -0.0449314 0.237874 0.0619544 -0.056974 0.237874 0.0820455 -0.056974 0.237874 0.0920594 -0.0551158 0.237874 0.100925 -0.0501024 0.237874 0.109185 -0.0443185 0.237874 0.109699 -0.0449314 0.237874 0.116928 -0.0377024 0.237874 0.127113 -0.0200623 0.237874 0.128971 0.0100427 0.237874 0.126361 0.019783 0.237874 0.127113 0.0200566 0.237874 0.116316 0.0371824 0.237874 0.122792 0.0293221 0.233696 0.130047 -0.00968925 0.233696 0.130649 -0.00486265 0.233696 0.129049 -0.0144497 0.237674 0.127301 -0.0201307 0.233696 0.127301 -0.0201307 0.233696 0.125893 -0.0236426 0.237674 0.122966 -0.0294279 0.237674 0.117082 -0.0378309 0.237674 0.109828 -0.0450846 0.233696 0.109828 -0.0450846 0.233696 0.104188 -0.0492701 0.233696 0.0956397 -0.0538961 0.237674 0.101425 -0.0509685 0.237674 0.0822192 -0.0579588 0.233696 0.0822192 -0.0579588 0.233696 0.0864468 -0.0570521 0.233696 0.0768597 -0.0586519 0.237674 0.0518721 -0.0553038 0.233696 0.0528914 -0.0556642 0.233696 0.0575531 -0.0570521 0.233696 0.0398121 -0.0492701 0.237674 0.042575 -0.0509685 0.233696 0.0269182 -0.0378309 0.233696 0.0321419 -0.0433002 0.233696 0.025559 -0.0361493 0.233696 0.0227327 -0.0321908 0.237674 0.0210344 -0.0294279 0.237674 0.014044 -0.0102221 0.237674 0.01315 -2.85742e-06 0.230474 0.117312 0.00901032 0.228874 0.117312 0.00901032 0.230474 0.114683 0.0176771 0.228874 0.110414 0.0256645 0.230474 0.110414 0.0256645 0.230474 0.104668 0.0326655 0.230474 0.0976673 0.038411 0.228874 0.0896799 0.0426804 0.228874 0.0810131 0.0453094 0.230474 0.0896799 0.0426804 0.228874 0.05432 0.0426804 0.228874 0.0463326 0.038411 0.228874 0.0393316 0.0326655 0.228874 0.0335861 0.0256645 0.228874 0.0293167 0.0176771 0.230474 0.0335861 0.0256645 0.228874 0.0266877 0.00901032 0.236674 0.12815 -2.85742e-06 0.236074 0.127194 0.0103147 0.236674 0.11974 0.0295563 0.236674 0.105838 0.0448058 0.236074 0.0970282 0.0502606 0.236674 0.0970282 0.0502606 0.236074 0.0771808 0.0559076 0.236674 0.0873661 0.0540037 0.236074 0.0566338 0.0540037 0.236674 0.0668191 0.0559076 0.236074 0.0469717 0.0502606 0.236674 0.0566338 0.0540037 0.236074 0.038162 0.0448058 0.236074 0.0305046 0.0378252 0.236074 0.0196416 0.0202809 0.236074 0.01585 -2.85742e-06 0.236674 0.01585 -2.85742e-06 0.230674 0.127194 0.0103147 0.233274 0.12815 -2.85742e-06 0.233274 0.127194 0.0103147 0.233274 0.124358 0.0202809 0.233274 0.11974 0.0295563 0.230674 0.113495 0.0378252 0.233274 0.113495 0.0378252 0.230674 0.0970282 0.0502606 0.233274 0.0970282 0.0502606 0.230674 0.0771808 0.0559076 0.233274 0.0771808 0.0559076 0.230674 0.038162 0.0448058 0.233274 0.038162 0.0448058 0.233274 0.0196416 0.0202809 0.230674 0.0196416 0.0202809 0.233274 0.016806 0.0103147 0.230674 0.01585 -2.85742e-06 0.233274 0.01585 -2.85742e-06 0.226574 0.0263606 0.0503385 0.226574 0.0250612 0.0475215 0.226574 0.0250612 0.0447502 0.226574 0.0258612 0.0445359 0.226574 0.0266612 0.0447502 0.226574 0.0261971 0.0431547 0.226574 0.0274573 0.0435957 0.226574 0.0284014 0.0445398 0.226574 0.0274612 0.0461359 0.226574 0.0216586 0.0456365 0.226574 0.021673 0.045637 0.226574 0.0224099 0.0453446 0.226574 0.0244756 0.0453359 0.226574 0.0237399 0.0440145 0.226574 0.0286929 0.0471267 0.226574 0.0266525 0.0495872 0.226574 0.0263601 0.0503241 0.225074 0.00727027 0.0216335 0.224774 0.0075548 0.0215383 0.224774 0.0181305 0.0414131 0.224774 0.0445366 0.0621499 0.225074 0.0663271 0.068011 0.224774 0.0887876 0.0658407 0.224774 0.0994633 0.0621499 0.224774 0.10938 0.0567415 0.225074 0.118468 0.0499847 0.224774 0.131986 0.0319168 0.225074 0.13673 0.0216335 0.225074 0.13942 0.0106113 0.224774 0.136445 0.0215383 0.225074 0.13673 -0.0216392 0.224774 0.136445 -0.0215441 0.224774 0.131986 -0.0319225 0.224774 0.125869 -0.0414189 0.224774 0.118264 -0.0497707 0.225074 0.0888617 -0.0661371 0.224774 0.0776478 -0.0677177 0.225074 0.0776728 -0.0680167 0.225074 0.0663271 -0.0680167 0.225074 0.0551382 -0.0661371 0.224774 0.0257359 -0.0497707 0.225074 0.0255316 -0.0499904 0.225074 0.0178927 -0.0416017 0.224774 0.0181305 -0.0414189 0.225074 0.011749 -0.0320634 0.224774 0.0120138 -0.0319225 0.224774 0.0075548 -0.0215441 0.225074 0.00727027 -0.0216392 0.229745 0.00560183 0.0136147 0.229745 0.00560183 -0.0136204 0.229745 0.00514424 -0.0111591 0.229745 0.138398 0.0136147 0.228738 0.13942 0.0106113 0.228738 0.138858 -0.0137148 0.229764 0.138916 -0.01046 0.229756 0.138941 -0.0104461 0.229768 0.138913 -0.010406 0.23021 0.137786 -0.00974432 0.232756 0.130696 -0.00979755 0.229783 0.138876 -0.0103762 0.229748 0.138956 -0.0104936 0.230997 0.135798 -0.00834849 0.23126 0.135198 -0.007295 0.229808 0.136199 -0.0211984 0.229777 0.136255 -0.0213035 0.229745 0.136311 -0.0214088 0.22975 0.136319 -0.0213406 0.231365 0.132313 -0.0193137 0.231809 0.131582 -0.0175448 0.231929 0.131673 -0.0159994 0.231911 0.131878 -0.0154195 0.231767 0.132536 -0.0144045 0.231496 0.133476 -0.0136419 0.231115 0.134643 -0.0132025 0.230654 0.135942 -0.0131686 0.229808 0.138196 -0.0137463 0.229785 0.13826 -0.0137504 0.230492 0.136379 -0.0132589 0.229745 0.138856 -0.0111591 0.229777 0.138297 -0.0136835 0.229765 0.138321 -0.0137287 0.22975 0.138371 -0.0136832 0.23171 0.114657 -0.045521 0.232756 0.112304 -0.0437843 0.231929 0.11568 -0.0436929 0.231908 0.115269 -0.0441791 0.231767 0.117225 -0.042743 0.232756 0.115781 -0.0403065 0.231811 0.116971 -0.0428356 0.231911 0.116147 -0.043293 0.229777 0.122574 -0.0449991 0.229808 0.122455 -0.0450028 0.22975 0.117033 -0.0506413 0.23097 0.11491 -0.0480462 0.232756 0.104548 -0.0498209 0.231496 0.0909264 -0.0600625 0.231767 0.0897957 -0.0596293 0.232756 0.0913222 -0.0562865 0.230492 0.0927093 -0.0623846 0.229785 0.0932242 -0.0642593 0.229777 0.0933006 -0.0642579 0.229745 0.0992269 -0.0620741 0.229765 0.0932738 -0.0643019 0.229745 0.0934059 -0.0643141 0.229777 0.0856806 -0.0662997 0.232756 0.0769141 -0.0593076 0.231365 0.0854331 -0.0618913 0.231482 0.0856134 -0.0615243 0.231742 0.0863009 -0.0606325 0.232756 0.0817946 -0.0586992 0.231929 0.0879831 -0.0596797 0.232756 0.0670858 -0.0593076 0.230654 0.0588342 -0.0639444 0.230492 0.0587439 -0.0643817 0.229745 0.0664027 -0.0675515 0.229777 0.0583193 -0.0662997 0.229808 0.0508044 -0.0642016 0.229777 0.0506993 -0.0642579 0.229745 0.0505941 -0.0643141 0.231809 0.054458 -0.0595844 0.232756 0.0526777 -0.0562865 0.231811 0.0573914 -0.0603655 0.232756 0.0622053 -0.0586992 0.229745 0.0270077 -0.0506965 0.229765 0.0269523 -0.0505761 0.229808 0.027 -0.0504582 0.229777 0.0270037 -0.0505773 0.229777 0.0214255 -0.0449991 0.229765 0.0214268 -0.0450505 0.229808 0.0215447 -0.0450028 0.229785 0.021491 -0.0450385 0.23097 0.0239566 -0.0429133 0.231414 0.0252877 -0.0425639 0.23171 0.0264818 -0.04266 0.231742 0.0266436 -0.0427027 0.232756 0.0316963 -0.0437843 0.231929 0.0283099 -0.0436831 0.231908 0.0278237 -0.0432723 0.231809 0.0270174 -0.042831 0.229785 0.00574014 -0.0137504 0.231414 0.0102654 -0.0135057 0.229808 0.0058044 -0.0137463 0.229777 0.00570309 -0.0136835 0.230492 0.00762112 -0.0132589 0.23097 0.00893796 -0.0131427 0.232756 0.0133036 -0.00979755 0.232756 0.0143129 -0.0146112 0.231911 0.0124358 -0.0165906 0.232756 0.0157163 -0.0193251 0.231908 0.0121075 -0.0153872 0.231496 0.0119403 -0.0189293 0.229777 0.00774487 -0.0213035 0.229745 0.00768871 -0.0214088 0.22975 0.00768102 -0.0213407 0.232756 0.0126952 -0.00491699 0.229745 0.00504449 -0.0105439 0.229756 0.00505907 -0.0104461 0.230628 0.00728543 -0.00912284 0.23021 0.00621378 -0.00974432 0.229764 0.00508423 -0.01046 0.232756 0.0175041 -0.0239069 0.229745 0.0111506 -0.0298609 0.232756 0.0196643 -0.0283255 0.229745 0.0123891 -0.0322626 0.229745 0.0185119 -0.0416343 0.232756 0.0250398 -0.0365534 0.230492 0.0228743 -0.0436724 0.231115 0.0292475 -0.0476531 0.232756 0.0394522 -0.0498209 0.232756 0.0436773 -0.0523386 0.229745 0.0349277 -0.0567461 0.229745 0.0421419 -0.0608522 0.231115 0.0588004 -0.0626454 0.229745 0.0674331 -0.067629 0.232756 0.095904 -0.0544987 0.230492 0.115669 -0.0491285 0.229745 0.109768 -0.0562854 0.229777 0.116996 -0.0505773 0.229745 0.125488 -0.0416343 0.229745 0.128282 -0.0377709 0.229745 0.131611 -0.0322626 0.229745 0.132849 -0.0298609 0.229745 0.136108 -0.022011 0.232756 0.128284 -0.0193251 0.228738 0.0765985 0.068092 0.228738 0.123045 0.0453013 0.228738 0.126107 0.041596 0.226274 0.123045 0.0453013 0.228738 0.109545 0.056992 0.228738 0.11003 0.0566698 0.226274 0.117304 0.0510422 0.226274 0.0935542 0.0647542 0.226274 0.0857119 0.0668555 0.225074 0.0776728 0.068011 0.225074 0.0888617 0.0661314 0.226274 0.0888617 0.0661314 0.225074 0.0444153 0.0624243 0.226274 0.0504457 0.0647542 0.225074 0.0551382 0.0661314 0.226274 0.0266958 0.0510422 0.225074 0.0255316 0.0499847 0.228738 0.0266958 0.0510422 0.228738 0.0209549 0.0453013 0.225074 0.0178927 0.041596 0.226274 0.0209549 0.0453013 0.228738 0.00514157 0.0137091 0.226274 0.00724291 0.0215514 0.225074 0.011749 0.0320577 0.228738 0.0153273 0.038027 0.228738 0.0178927 0.041596 0.228738 0.0339701 0.0566698 0.225074 0.0344547 0.056992 0.228738 0.0663271 0.068011 0.226274 0.058288 0.0668555 0.228738 0.058288 0.0668555 0.225074 0.109545 0.056992 0.225074 0.0995846 0.0624243 0.228738 0.0995846 0.0624243 0.228738 0.0935542 0.0647542 0.225074 0.126107 0.041596 0.225074 0.132251 0.0320577 0.228738 0.132251 0.0320577 0.228738 0.0209549 -0.045307 0.226274 0.00724291 -0.0215571 0.225074 0.00458036 -0.010617 0.226274 0.0266958 -0.0510479 0.226274 0.0209549 -0.045307 0.225074 0.0444153 -0.06243 0.226274 0.058288 -0.0668612 0.228738 0.058288 -0.0668612 0.226274 0.0857119 -0.0668612 0.225074 0.118468 -0.0499904 0.228738 0.117304 -0.0510479 0.225074 0.126107 -0.0416017 0.228738 0.13942 -0.010617 0.225074 0.132251 -0.0320634 0.225074 0.109545 -0.0569977 0.228738 0.109545 -0.0569977 0.225074 0.0995846 -0.06243 0.228738 0.102065 -0.061274 0.228738 0.0674015 -0.0680978 0.225074 0.0344547 -0.0569977 0.226274 0.0504457 -0.0647599 0.228738 0.00724291 -0.0215571 0.228738 0.0107288 -0.0300679 0.185974 0.0763 0.0421785 0.185974 0.0825578 0.0598735 0.185974 0.0512051 0.0571305 0.185974 0.0680598 0.0467456 0.185974 0.0677 0.0453724 0.185974 0.0500383 0.038614 0.185974 0.0763 0.0453724 0.185974 0.0925201 0.0371724 0.185974 0.106083 -0.0340854 0.185974 0.0904453 -0.0445339 0.185974 0.0825578 -0.0598792 0.185974 0.0481341 0.0397828 0.185974 0.0438398 0.0391155 0.185974 0.0319231 -0.0267813 0.185974 0.0193456 -0.0304029 0.185974 0.0148666 -0.0207977 0.185974 0.0247261 -0.00940621 0.185974 0.0238 -2.85742e-06 0.185974 0.0112 -2.85742e-06 0.185974 0.0121236 0.010555 0.185974 0.0272159 0.0178193 0.185974 0.0313714 0.0259309 0.185974 0.0369795 0.0331153 0.185974 0.0254245 0.0390786 0.185974 0.124654 -0.0304029 0.185974 0.119274 -0.00940621 0.185974 0.131876 0.010555 0.185974 0.119338 0.0090704 0.185974 0.124654 0.0303971 0.185974 0.112629 0.0259309 0.185974 0.111081 0.0465726 0.185974 0.1024 0.0526515 0.185974 0.0927948 0.0571305 0.190674 0.114417 0.0150293 0.190674 0.113792 0.0148618 0.190674 0.115042 0.0148618 0.190674 0.113335 0.0144043 0.185974 0.113335 0.0144043 0.185974 0.113792 0.0148618 0.190674 0.1155 0.0144043 0.185974 0.1155 0.0144043 0.190674 0.115667 0.0137793 0.185974 0.113567 0.0152515 0.185974 0.114417 0.0150293 0.185974 0.115042 0.0148618 0.185974 0.114417 0.0154793 0.185974 0.115267 0.0152515 0.185974 0.115889 0.0146293 0.185974 0.115667 0.0137793 0.185974 0.116117 0.0137793 0.185974 0.115889 0.0129293 0.185974 0.115267 0.0123071 0.185974 0.114417 0.0120793 0.185974 0.113792 0.0126968 0.185974 0.113335 0.0131543 0.185974 0.113567 0.0123071 0.185974 0.113167 0.0137793 0.191425 0.114417 -0.013785 0.190674 0.114417 -0.012535 0.190674 0.115042 -0.0127025 0.190674 0.113335 -0.01316 0.190674 0.113792 -0.0127025 0.185974 0.114417 -0.012535 0.190674 0.1155 -0.01316 0.190674 0.115667 -0.013785 0.185974 0.115667 -0.013785 0.185974 0.114417 -0.012085 0.185974 0.115042 -0.0127025 0.185974 0.1155 -0.01316 0.185974 0.116117 -0.013785 0.185974 0.1155 -0.01441 0.185974 0.115889 -0.014635 0.185974 0.115267 -0.0152573 0.185974 0.114417 -0.015035 0.185974 0.114417 -0.015485 0.185974 0.113335 -0.01441 0.185974 0.113167 -0.013785 0.185974 0.112945 -0.014635 0.185974 0.112717 -0.013785 0.185974 0.113335 -0.01316 0.185974 0.113792 -0.0127025 0.185974 0.112945 -0.012935 0.191425 0.0982152 -0.036085 0.190674 0.0969652 -0.036085 0.190674 0.0971326 -0.03546 0.185974 0.0969652 -0.036085 0.190674 0.0975902 -0.0350025 0.190674 0.0982152 -0.034835 0.185974 0.0982152 -0.034835 0.190674 0.0988402 -0.0350025 0.185974 0.0988402 -0.0350025 0.190674 0.0992977 -0.03546 0.185974 0.0992977 -0.03546 0.190674 0.0994652 -0.036085 0.185974 0.0975902 -0.0371675 0.185974 0.0971326 -0.03546 0.185974 0.0965152 -0.036085 0.185974 0.0967429 -0.035235 0.185974 0.0975902 -0.0350025 0.185974 0.0996874 -0.035235 0.185974 0.0996874 -0.036935 0.190674 0.071375 -0.0435203 0.190674 0.0709174 -0.0439779 0.190674 0.07075 -0.0446029 0.185974 0.07075 -0.0446029 0.190674 0.072 -0.0433529 0.185974 0.072 -0.0433529 0.185974 0.072625 -0.0435203 0.190674 0.072625 -0.0435203 0.190674 0.0730825 -0.0439779 0.185974 0.071375 -0.0456854 0.185974 0.0709174 -0.0452279 0.185974 0.0705277 -0.0454529 0.185974 0.0709174 -0.0439779 0.185974 0.0703 -0.0446029 0.185974 0.0705277 -0.0437529 0.185974 0.071375 -0.0435203 0.185974 0.07285 -0.0431306 0.185974 0.0730825 -0.0439779 0.185974 0.07325 -0.0446029 0.185974 0.0730825 -0.0452279 0.185974 0.0734722 -0.0454529 0.185974 0.072625 -0.0456854 0.185974 0.07285 -0.0460751 0.185974 0.072 -0.0463029 0.190674 0.0451597 -0.0350025 0.190674 0.0447022 -0.03546 0.190674 0.0468673 -0.03546 0.185974 0.0445347 -0.036085 0.185974 0.0451597 -0.0350025 0.185974 0.0457847 -0.034835 0.190674 0.0457847 -0.034835 0.190674 0.0464097 -0.0350025 0.190674 0.0470347 -0.036085 0.185974 0.0468673 -0.03546 0.185974 0.0470347 -0.036085 0.185974 0.0449347 -0.0375573 0.185974 0.0447022 -0.03671 0.185974 0.0447022 -0.03546 0.185974 0.0449347 -0.0346128 0.185974 0.0457847 -0.034385 0.185974 0.0464097 -0.0350025 0.185974 0.047257 -0.035235 0.185974 0.0464097 -0.0371675 0.185974 0.0466347 -0.0375573 0.185974 0.0457847 -0.037335 0.190674 0.0302078 -0.0127025 0.190674 0.0283328 -0.013785 0.190674 0.0285003 -0.01316 0.190674 0.0289578 -0.0127025 0.190674 0.0295828 -0.012535 0.185974 0.0295828 -0.012535 0.185974 0.0302078 -0.0127025 0.190674 0.0306654 -0.01316 0.185974 0.0306654 -0.01316 0.185974 0.0308328 -0.013785 0.185974 0.0304328 -0.0123128 0.185974 0.0312828 -0.013785 0.185974 0.0310551 -0.014635 0.185974 0.0302078 -0.0148675 0.185974 0.0304328 -0.0152573 0.185974 0.0295828 -0.015035 0.185974 0.0295828 -0.015485 0.185974 0.0287328 -0.0152573 0.185974 0.0285003 -0.01441 0.185974 0.0281106 -0.014635 0.185974 0.0283328 -0.013785 0.185974 0.0278828 -0.013785 0.185974 0.0285003 -0.01316 0.185974 0.0289578 -0.0127025 0.185974 0.0295828 -0.012085 0.190674 0.0289578 0.0148618 0.190674 0.0308328 0.0137793 0.190674 0.0285003 0.0144043 0.185974 0.0289578 0.0148618 0.190674 0.0295828 0.0150293 0.185974 0.0295828 0.0150293 0.190674 0.0302078 0.0148618 0.190674 0.0306654 0.0144043 0.185974 0.0306654 0.0144043 0.185974 0.0310551 0.0129293 0.185974 0.0302078 0.0126968 0.185974 0.0295828 0.0125293 0.185974 0.0295828 0.0120793 0.185974 0.0285003 0.0131543 0.185974 0.0281106 0.0129293 0.185974 0.0285003 0.0144043 0.185974 0.0302078 0.0148618 0.185974 0.0308328 0.0137793 0.185974 0.0312828 0.0137793 0.190674 0.0451597 0.0371618 0.190674 0.0447022 0.0367043 0.190674 0.0464097 0.0371618 0.190674 0.0457847 0.0373293 0.185974 0.0457847 0.0373293 0.190674 0.0468673 0.0367043 0.185974 0.0464097 0.0371618 0.185974 0.0451597 0.0349968 0.185974 0.0449347 0.0346071 0.185974 0.0440847 0.0360793 0.185974 0.0445347 0.0360793 0.185974 0.0443125 0.0369293 0.185974 0.0447022 0.0367043 0.185974 0.0451597 0.0371618 0.185974 0.0457847 0.0377793 0.185974 0.047257 0.0369293 0.185974 0.0468673 0.0367043 0.185974 0.0470347 0.0360793 0.185974 0.0474847 0.0360793 0.185974 0.0468673 0.0354543 0.185974 0.0466347 0.0346071 0.185974 0.0457847 0.0343793 0.191425 0.072 0.0445971 0.190674 0.072 0.0458471 0.190674 0.07075 0.0445971 0.190674 0.0709174 0.0452221 0.185974 0.0709174 0.0452221 0.190674 0.071375 0.0456797 0.185974 0.072 0.0458471 0.190674 0.072625 0.0456797 0.185974 0.0730825 0.0452221 0.190674 0.0730825 0.0452221 0.185974 0.072 0.0462971 0.185974 0.07285 0.0460694 0.185974 0.072625 0.0456797 0.185974 0.0734722 0.0454471 0.185974 0.07325 0.0445971 0.185974 0.0734722 0.0437471 0.185974 0.07285 0.0431249 0.185974 0.072 0.0433471 0.185974 0.0705277 0.0437471 0.185974 0.07075 0.0445971 0.185974 0.0703 0.0445971 0.185974 0.071375 0.0456797 0.185974 0.07115 0.0460694 0.185974 0.0982152 0.0373293 0.185974 0.0973652 0.0375515 0.185974 0.0982152 0.0377793 0.185974 0.0988402 0.0371618 0.185974 0.0992977 0.0367043 0.185974 0.0994652 0.0360793 0.185974 0.0992977 0.0354543 0.185974 0.0990652 0.0346071 0.185974 0.0971326 0.0354543 0.185974 0.0965152 0.0360793 0.185974 0.0975902 0.0371618 0.185974 0.0967429 0.0369293 0.185974 0.0969652 0.0360793 0.190674 0.0975902 0.0371618 0.185974 0.0971326 0.0367043 0.190674 0.0971326 0.0367043 0.190674 0.0992977 0.0367043 0.190674 0.0994652 0.0360793 0.190674 0.0982152 0.0373293 0.190674 0.0988402 0.0371618 0.191425 0.0982152 0.0360793 0.238074 0.0178381 0.0101217 0.237874 0.0167 -2.85742e-06 0.238074 0.025153 0.0290036 0.238074 0.0312806 0.0371178 0.237874 0.0249829 0.0291088 0.237874 0.0311328 0.0372525 0.238074 0.0387948 0.0439679 0.237874 0.0386743 0.0441275 0.237874 0.0473506 0.0494997 0.238074 0.0569211 0.0529937 0.237874 0.0668975 0.0550612 0.237874 0.0771024 0.0550612 0.238074 0.0870788 0.0529937 0.237874 0.105326 0.0441275 0.238074 0.105205 0.0439679 0.238074 0.112719 0.0371178 0.237874 0.123566 0.0199738 0.237874 0.126358 0.0101585 0.237474 0.01565 -2.85742e-06 0.237474 0.0194551 0.0203531 0.237274 0.030209 0.0380946 0.237474 0.0380415 0.0449654 0.237274 0.037921 0.045125 0.237274 0.0467935 0.0506186 0.237274 0.0667822 0.0563059 0.237474 0.0771993 0.0561068 0.237474 0.0874209 0.054196 0.237274 0.0874756 0.0543884 0.237474 0.105958 0.0449654 0.237474 0.11991 0.0296616 0.237274 0.124731 0.0204254 0.237474 0.12739 0.0103514 0.237474 0.128577 -0.00997895 0.237474 0.125985 -0.0196519 0.237274 0.12158 -0.0286279 0.237474 0.121753 -0.0287279 0.237274 0.0915806 -0.0538003 0.237474 0.091649 -0.0539882 0.237274 0.0819413 -0.0563831 0.237474 0.0620239 -0.0565801 0.237274 0.0524193 -0.0538003 0.237474 0.043275 -0.049756 0.237274 0.0281439 -0.0368024 0.237274 0.02242 -0.0286279 0.238074 0.123999 -0.00972321 0.237874 0.121141 -0.0190403 0.238074 0.111094 -0.0356414 0.238074 0.0955795 -0.047357 0.238074 0.0864767 -0.0508834 0.238074 0.076881 -0.0526772 0.238074 0.0484204 -0.047357 0.237874 0.0485095 -0.047178 0.237874 0.0402411 -0.0420584 0.238074 0.0329064 -0.0356414 0.237874 0.0201973 -0.00968646 0.238074 0.0200007 -0.00972321 0.237874 0.0193 -2.85742e-06 0.238074 0.0208854 0.00955212 0.237874 0.0206888 0.00958887 0.238074 0.0235114 0.0187817 0.238074 0.0277887 0.0273716 0.238074 0.0335715 0.0350293 0.238074 0.040663 0.041494 0.238074 0.067202 0.0517753 0.238074 0.0862304 0.0500121 0.237874 0.0768164 0.0519745 0.238074 0.0951784 0.0465456 0.237874 0.110576 0.0351641 0.238074 0.116211 0.0273716 0.237874 0.116381 0.0274769 0.238074 0.120489 0.0187817 0.237874 0.1242 -2.85742e-06 0.238474 0.13085 -2.85742e-06 0.238474 0.127301 -0.0201307 0.238474 0.122966 -0.0294279 0.238274 0.127113 -0.0200623 0.238474 0.117082 -0.0378309 0.238274 0.116928 -0.0377024 0.238474 0.101425 -0.0509685 0.238274 0.0920594 -0.0551158 0.238474 0.072 -0.0588529 0.238274 0.072 -0.0586529 0.238274 0.042675 -0.0507952 0.238474 0.042575 -0.0509685 0.238474 0.0341719 -0.0450846 0.238274 0.0212076 -0.0293279 0.238274 0.014241 -0.0101873 0.238474 0.014044 -0.0102221 0.238274 0.01335 -2.85742e-06 0.238874 0.077811 -0.0319353 0.238874 0.0791836 -0.0305627 0.238874 0.0810586 -0.0300603 0.238874 0.0829336 -0.0305627 0.238674 0.0830336 -0.0303895 0.238874 0.0843062 -0.0319353 0.238674 0.0927987 -0.0247516 0.238674 0.0933279 -0.0227766 0.238874 0.0948737 -0.021504 0.238874 0.0986237 -0.021504 0.238674 0.0967487 -0.0208016 0.238674 0.0987237 -0.0213308 0.238674 0.100169 -0.0227766 0.238874 0.100499 -0.0247516 0.238874 0.102057 -0.00906152 0.238874 0.10256 -0.00718652 0.238874 0.103932 -0.00581393 0.238674 0.103832 -0.00564072 0.238874 0.105807 -0.00531152 0.238674 0.105807 -0.00511152 0.238674 0.107782 -0.00564072 0.238674 0.109228 -0.00708652 0.238674 0.101857 0.00905581 0.238674 0.102387 0.0110308 0.238874 0.103932 0.0123034 0.238674 0.105807 0.0130058 0.238874 0.105807 0.0128058 0.238674 0.107782 0.0124766 0.238674 0.109228 0.0110308 0.238674 0.0933279 0.0267209 0.238674 0.0987237 0.0281667 0.238874 0.077811 0.0356795 0.238874 0.0791836 0.0370521 0.238674 0.0790836 0.0372253 0.238674 0.0844794 0.0357795 0.238674 0.0589913 0.0338045 0.238874 0.0629413 0.0375545 0.238674 0.0629413 0.0377545 0.238674 0.0649163 0.0372253 0.238674 0.0663621 0.0357795 0.238874 0.0661889 0.0356795 0.238674 0.0433012 0.0247459 0.238874 0.0440036 0.0266209 0.238674 0.0438304 0.0267209 0.238674 0.0472512 0.0286959 0.238874 0.0491262 0.0279935 0.238674 0.0492262 0.0281667 0.238674 0.050672 0.0267209 0.238674 0.0512012 0.0247459 0.238874 0.0363176 0.0123034 0.238674 0.0347718 0.0110308 0.238874 0.0381926 0.0128058 0.238874 0.0400676 0.0123034 0.238874 0.0414401 0.0109308 0.238674 0.0401676 0.0124766 0.238874 0.0419426 0.00905581 0.238874 0.0358545 -0.00612966 0.238674 0.0373136 -0.00521056 0.238874 0.039027 -0.00540554 0.238674 0.0390715 -0.00521056 0.238874 0.0415712 -0.00743446 0.238674 0.0417514 -0.00734768 0.238874 0.0440036 -0.0228766 0.238674 0.0452762 -0.0213308 0.238874 0.0472512 -0.0210016 0.238674 0.0472512 -0.0208016 0.238874 0.0491262 -0.021504 0.238674 0.0492262 -0.0213308 0.238674 0.050672 -0.0227766 0.238874 0.0510012 -0.0247516 0.238674 0.0589913 -0.0338103 0.238874 0.0596937 -0.0319353 0.238674 0.0595205 -0.0318353 0.238874 0.0648163 -0.0305627 0.238874 0.0661889 -0.0319353 0.238674 0.0663621 -0.0318353 0.238674 0.0668913 -0.0338103 0.241474 0.0829336 0.0370521 0.241474 0.0791836 0.0370521 0.241674 0.0790836 0.0372253 0.241474 0.0773086 0.0338045 0.241474 0.100499 0.0247459 0.241674 0.100699 0.0247459 0.241474 0.0999963 0.0266209 0.241674 0.0987237 0.0281667 0.241474 0.0967487 0.0284959 0.241474 0.0948737 0.0279935 0.241674 0.0947737 0.0281667 0.241474 0.0935011 0.0266209 0.241474 0.109557 0.00905581 0.241674 0.109757 0.00905581 0.241674 0.109228 0.0110308 0.241474 0.109055 0.0109308 0.241474 0.107682 0.0123034 0.241674 0.107782 0.0124766 0.241674 0.102387 0.0110308 0.241474 0.10256 0.0109308 0.241474 0.109055 -0.00718652 0.241674 0.109228 -0.00708652 0.241474 0.107682 -0.00581393 0.241674 0.105807 -0.00511152 0.241674 0.103832 -0.00564072 0.241674 0.100699 -0.0247516 0.241674 0.0987237 -0.0213308 0.241674 0.0967487 -0.0208016 0.241474 0.0935011 -0.0228766 0.241674 0.0947737 -0.0213308 0.241674 0.0933279 -0.0227766 0.241674 0.0850086 -0.0338103 0.241474 0.0843062 -0.0319353 0.241674 0.0844794 -0.0318353 0.241674 0.0830336 -0.0303895 0.241474 0.0810586 -0.0300603 0.241674 0.0776378 -0.0318353 0.241474 0.0661889 -0.0319353 0.241674 0.0668913 -0.0338103 0.241474 0.0648163 -0.0305627 0.241674 0.0629413 -0.0298603 0.241474 0.0610663 -0.0305627 0.241674 0.0609663 -0.0303895 0.241474 0.0491262 -0.021504 0.241674 0.0492262 -0.0213308 0.241674 0.0472512 -0.0208016 0.241474 0.0440036 -0.0228766 0.241474 0.0419426 -0.00906152 0.241674 0.0421426 -0.00906152 0.241474 0.0405306 -0.00612966 0.241674 0.0406553 -0.00597329 0.241674 0.0390715 -0.00521056 0.241674 0.0357298 -0.00597329 0.241474 0.0348139 -0.00743446 0.241474 0.0414401 0.0109308 0.241474 0.0381926 0.0128058 0.241674 0.0401676 0.0124766 0.241474 0.034945 0.0109308 0.241474 0.0344426 0.00905581 0.241674 0.0347718 0.0110308 0.241674 0.0342426 0.00905581 0.241674 0.0512012 0.0247459 0.241674 0.050672 0.0267209 0.241674 0.0492262 0.0281667 0.241474 0.0472512 0.0284959 0.241674 0.0472512 0.0286959 0.241674 0.0452762 0.0281667 0.241674 0.0438304 0.0267209 0.241674 0.0433012 0.0247459 0.241474 0.0648163 0.0370521 0.241674 0.0663621 0.0357795 0.241674 0.0649163 0.0372253 0.241674 0.0629413 0.0377545 0.241474 0.0629413 0.0375545 0.241674 0.0609663 0.0372253 0.241474 0.0596937 0.0356795 0.241374 0.03 -2.85742e-06 0.241374 0.0309178 -0.00873515 0.241674 0.038264 -0.0245135 0.241374 0.0380212 -0.0246898 0.241674 0.0440972 -0.030992 0.241674 0.05115 -0.0361161 0.241674 0.0591139 -0.0396619 0.241374 0.0590212 -0.0399472 0.241674 0.0676411 -0.0414744 0.241374 0.0763902 -0.0417728 0.241374 0.0849787 -0.0399472 0.241374 0.093 -0.0363759 0.241674 0.084886 -0.0396619 0.241374 0.105979 -0.0246898 0.241374 0.110369 -0.0170858 0.241374 0.113082 -0.00873515 0.241374 0.114 -2.85742e-06 0.238974 0.105979 -0.0246898 0.238674 0.112789 -0.00867277 0.238674 0.101192 -0.0297803 0.238974 0.100103 -0.0312149 0.238674 0.101823 -0.0291491 0.238974 0.0849787 -0.0399472 0.238974 0.0438965 -0.0312149 0.238974 0.051 -0.0363759 0.238674 0.0591139 -0.0396619 0.238674 0.0676411 -0.0414744 0.238974 0.0676098 -0.0417728 0.238674 0.0392419 -0.025806 0.238674 0.038264 -0.0245135 0.238874 0.109055 -0.00718652 0.238874 0.107682 -0.00581393 0.241474 0.105807 -0.00531152 0.241474 0.103932 -0.00581393 0.241474 0.10256 -0.00718652 0.238874 0.0999963 -0.0228766 0.241474 0.0999963 -0.0228766 0.241474 0.0986237 -0.021504 0.238874 0.0967487 -0.0210016 0.241474 0.0967487 -0.0210016 0.241474 0.0948737 -0.021504 0.238874 0.0935011 -0.0228766 0.238874 0.0929987 -0.0247516 0.241474 0.0929987 -0.0247516 0.241474 0.0848086 -0.0338103 0.241474 0.0829336 -0.0305627 0.241474 0.0791836 -0.0305627 0.241474 0.077811 -0.0319353 0.238874 0.0773086 -0.0338103 0.238874 0.0629413 -0.0300603 0.241474 0.0629413 -0.0300603 0.238874 0.0610663 -0.0305627 0.241474 0.0596937 -0.0319353 0.241474 0.0591913 -0.0338103 0.238874 0.0504988 -0.0228766 0.241474 0.0510012 -0.0247516 0.241474 0.0504988 -0.0228766 0.241474 0.0472512 -0.0210016 0.238874 0.0453762 -0.021504 0.241474 0.0453762 -0.021504 0.238874 0.0435012 -0.0247516 0.241474 0.0415712 -0.00743446 0.238874 0.0405306 -0.00612966 0.241474 0.039027 -0.00540554 0.238874 0.0373581 -0.00540554 0.241474 0.0373581 -0.00540554 0.241474 0.0358545 -0.00612966 0.238874 0.0348139 -0.00743446 0.238874 0.0344426 -0.00906152 0.241474 0.0400676 0.0123034 0.241474 0.0363176 0.0123034 0.238874 0.034945 0.0109308 0.238874 0.0504988 0.0266209 0.241474 0.0504988 0.0266209 0.241474 0.0491262 0.0279935 0.238874 0.0472512 0.0284959 0.238874 0.0453762 0.0279935 0.241474 0.0453762 0.0279935 0.241474 0.0440036 0.0266209 0.241474 0.0435012 0.0247459 0.238874 0.0666913 0.0338045 0.238874 0.0648163 0.0370521 0.241474 0.0661889 0.0356795 0.238874 0.0610663 0.0370521 0.241474 0.0610663 0.0370521 0.238874 0.0596937 0.0356795 0.238874 0.0591913 0.0338045 0.238874 0.0843062 0.0356795 0.241474 0.0843062 0.0356795 0.238874 0.0829336 0.0370521 0.238874 0.0810586 0.0375545 0.241474 0.0810586 0.0375545 0.241474 0.077811 0.0356795 0.238874 0.100499 0.0247459 0.238874 0.0999963 0.0266209 0.238874 0.0986237 0.0279935 0.241474 0.0986237 0.0279935 0.238874 0.0967487 0.0284959 0.238874 0.0948737 0.0279935 0.238874 0.0935011 0.0266209 0.241474 0.0929987 0.0247459 0.238874 0.109557 0.00905581 0.238874 0.109055 0.0109308 0.238874 0.107682 0.0123034 0.241474 0.105807 0.0128058 0.238874 0.10256 0.0109308 0.241474 0.103932 0.0123034 0.239024 0.101236 -0.0156409 0.241674 0.102311 -0.0127029 0.241674 0.104711 -0.0133459 0.239024 0.104173 -0.0164279 0.241674 0.106468 -0.0151029 0.239024 0.104461 -0.0175029 0.241674 0.10707 -0.0168748 0.238674 0.102311 -0.0153529 0.239024 0.103386 -0.0156409 0.238674 0.101236 -0.0156409 0.239024 0.102311 -0.0153529 0.239024 0.100449 -0.0164279 0.238674 0.100449 -0.0164279 0.238674 0.100161 -0.0175029 0.241674 0.0936569 -0.0279137 0.241674 0.0895 -0.0255137 0.241674 0.0871 -0.0261568 0.241674 0.0847 -0.0303137 0.238674 0.09165 -0.0303137 0.239024 0.09165 -0.0303137 0.239024 0.0913619 -0.0292387 0.238674 0.090575 -0.0284518 0.239024 0.090575 -0.0284518 0.239024 0.0895 -0.0281637 0.238674 0.088425 -0.0284518 0.239024 0.088425 -0.0284518 0.238674 0.087638 -0.0292387 0.239024 0.087638 -0.0292387 0.238674 0.08735 -0.0303137 0.239024 0.0738619 -0.0339279 0.239024 0.073075 -0.0331409 0.239024 0.070138 -0.0339279 0.241674 0.0696 -0.0308459 0.238674 0.073075 -0.0331409 0.239024 0.072 -0.0328529 0.238674 0.070925 -0.0331409 0.239024 0.070925 -0.0331409 0.239024 0.06985 -0.0350029 0.241674 0.0464891 -0.0175029 0.239024 0.043551 -0.0164279 0.239024 0.0416891 -0.0153529 0.241674 0.0416891 -0.0127029 0.239024 0.0398271 -0.0164279 0.239024 0.0395391 -0.0175029 0.238674 0.0438391 -0.0175029 0.239024 0.0438391 -0.0175029 0.238674 0.043551 -0.0164279 0.239024 0.0427641 -0.0156409 0.238674 0.0406141 -0.0156409 0.239024 0.0406141 -0.0156409 0.241674 0.0394 0.00415406 0.241674 0.037 0.00479714 0.239024 0.035925 0.0018591 0.238674 0.0388619 0.00107214 0.239024 0.03915 -2.85742e-06 0.239024 0.0388619 0.00107214 0.239024 0.038075 0.0018591 0.238674 0.038075 0.0018591 0.238674 0.037 0.00214714 0.239024 0.037 0.00214714 0.239024 0.035138 0.00107214 0.238674 0.03485 -2.85742e-06 0.239024 0.03485 -2.85742e-06 0.241674 0.045846 0.0198971 0.241674 0.0440891 0.0216541 0.239024 0.0406141 0.0193591 0.241674 0.0416891 0.0222971 0.239024 0.0395391 0.0174971 0.238674 0.043551 0.0185721 0.239024 0.043551 0.0185721 0.239024 0.0427641 0.0193591 0.238674 0.0427641 0.0193591 0.239024 0.0416891 0.0196471 0.238674 0.0416891 0.0196471 0.238674 0.0406141 0.0193591 0.238674 0.0398271 0.0185721 0.239024 0.0398271 0.0185721 0.241674 0.0768 0.0349971 0.239024 0.0738619 0.0360721 0.241674 0.0761569 0.0373971 0.239024 0.073075 0.0368591 0.241674 0.0744 0.0391541 0.241674 0.072 0.0397971 0.241674 0.0696 0.0391541 0.241674 0.067843 0.0373971 0.238674 0.073075 0.0368591 0.239024 0.072 0.0371471 0.238674 0.070925 0.0368591 0.239024 0.070925 0.0368591 0.239024 0.070138 0.0360721 0.238674 0.06985 0.0349971 0.239024 0.06985 0.0349971 0.241674 0.0895 0.035108 0.239024 0.088425 0.03217 0.241674 0.085343 0.032708 0.239024 0.08735 0.030308 0.238674 0.0913619 0.031383 0.239024 0.0913619 0.031383 0.239024 0.090575 0.03217 0.238674 0.0895 0.032458 0.239024 0.0895 0.032458 0.239024 0.087638 0.031383 0.238674 0.08735 0.030308 0.239024 0.103651 0.0191781 0.241674 0.105304 0.0212499 0.241674 0.103379 0.0221768 0.241674 0.101243 0.0221768 0.239024 0.101832 0.0195932 0.239024 0.100374 0.01843 0.241674 0.0979862 0.0195798 0.238674 0.104461 0.0174971 0.239024 0.104461 0.0174971 0.238674 0.104248 0.01843 0.239024 0.104248 0.01843 0.239024 0.102789 0.0195932 0.238674 0.102789 0.0195932 0.238674 0.101832 0.0195932 0.238674 0.10097 0.0191781 0.239024 0.10097 0.0191781 0.240174 0.0809741 -0.045119 0.240174 0.117116 -0.00897701 0.240174 0.110248 -0.0255591 0.239374 0.110803 -0.0160756 0.239374 0.113082 -0.00873515 0.239374 0.0953339 -0.0349246 0.240174 0.104527 -0.0325298 0.239374 0.100103 -0.0312149 0.240174 0.0896034 -0.0425013 0.240174 0.0975562 -0.0382505 0.239374 0.093 -0.0363759 0.239374 0.0763902 -0.0417728 0.239374 0.072 -0.0420029 0.240174 0.072 -0.0460029 0.239374 0.0590212 -0.0399472 0.240174 0.0464437 -0.0382505 0.239374 0.051 -0.0363759 0.239374 0.048666 -0.0349246 0.239374 0.0370782 -0.0233368 0.239374 0.033631 -0.0170858 0.239374 0.0309178 -0.00873515 0.239374 0.030807 -0.00819665 0.240174 0.026 -2.85742e-06 0.240174 0.0767979 0.0517753 0.240174 0.0862304 0.0500121 0.240174 0.0951784 0.0465456 0.240174 0.116211 0.0273716 0.240174 0.114498 0.0176006 0.240174 0.120489 0.0187817 0.240174 0.124 -2.85742e-06 0.240174 0.114498 -0.0176063 0.240174 0.120489 -0.0187874 0.240174 0.103337 -0.0414998 0.240174 0.0951784 -0.0465513 0.240174 0.067202 -0.051781 0.240174 0.0630258 -0.045119 0.240174 0.0543965 -0.0425013 0.240174 0.0488216 -0.0465513 0.240174 0.039473 -0.0325298 0.240174 0.040663 -0.0414998 0.240174 0.0335715 -0.035035 0.240174 0.0337524 -0.0255591 0.240174 0.0295015 -0.0176063 0.240174 0.0268838 -0.00897701 0.240174 0.0208854 -0.00955783 0.240174 0.0235114 0.0187817 0.240174 0.0543965 0.0424956 0.240174 0.0488216 0.0465456 0.240174 0.0630258 0.0451133 0.240174 0.067202 0.0517753 0.238074 0.123115 0.00955212 0.240174 0.123115 0.00955212 0.238074 0.110428 0.0350293 0.240174 0.110428 0.0350293 0.238074 0.103337 0.041494 0.240174 0.103337 0.041494 0.238074 0.0767979 0.0517753 0.238074 0.0577695 0.0500121 0.238074 0.0488216 0.0465456 0.240174 0.0577695 0.0500121 0.240174 0.040663 0.041494 0.240174 0.0335715 0.0350293 0.240174 0.0277887 0.0273716 0.240174 0.0208854 0.00955212 0.237874 0.0768625 0.0524723 0.237874 0.0862852 0.0502044 0.237874 0.0952675 0.0467247 0.237874 0.086422 0.0506854 0.237874 0.103457 0.0416536 0.237874 0.116806 0.0277401 0.237874 0.120675 0.018854 0.237874 0.123311 0.00958887 0.237874 0.1247 -2.85742e-06 0.237874 0.123803 -0.00968646 0.237874 0.120675 -0.0188597 0.237874 0.116806 -0.0277458 0.237874 0.110576 -0.0351698 0.237874 0.110946 -0.0355066 0.237874 0.103457 -0.0416594 0.237874 0.103759 -0.0420584 0.237874 0.0952675 -0.0467304 0.237874 0.0862852 -0.0502102 0.237874 0.0954904 -0.047178 0.237874 0.086422 -0.0506911 0.237874 0.0768625 -0.052478 0.237874 0.0671835 -0.0519802 0.237874 0.0671374 -0.052478 0.237874 0.0577147 -0.0502102 0.237874 0.0575779 -0.0506911 0.237874 0.0334237 -0.0351698 0.237874 0.0330542 -0.0355066 0.237874 0.0271935 -0.0277458 0.237874 0.0276186 -0.0274826 0.237874 0.0233249 -0.0188597 0.237874 0.0228587 -0.0190403 0.237874 0.0206888 -0.00959458 0.237874 0.0198 -2.85742e-06 0.237874 0.0201973 0.00968074 0.237874 0.0228587 0.0190346 0.237874 0.0233249 0.018854 0.237874 0.0276186 0.0274769 0.237874 0.0334237 0.0351641 0.237874 0.0271935 0.0277401 0.237874 0.0330542 0.0355009 0.237874 0.0405424 0.0416536 0.237874 0.0402411 0.0420526 0.237874 0.0487324 0.0467247 0.237874 0.0577147 0.0502044 0.237874 0.0671835 0.0519745 0.239974 0.123999 -0.00972321 0.238074 0.121328 -0.0191125 0.239974 0.116976 -0.0278511 0.238074 0.116976 -0.0278511 0.239974 0.103879 -0.042218 0.239974 0.0955795 -0.047357 0.238074 0.103879 -0.042218 0.238074 0.067119 -0.0526772 0.238074 0.0575232 -0.0508834 0.239974 0.0401206 -0.042218 0.238074 0.0401206 -0.042218 0.239974 0.0329064 -0.0356414 0.239974 0.0270235 -0.0278511 0.238074 0.0270235 -0.0278511 0.239974 0.0226722 -0.0191125 0.238074 0.0226722 -0.0191125 0.239974 0.0200007 -0.00972321 0.239974 0.0312806 0.0371178 0.239974 0.0569211 0.0529937 0.239974 0.0575232 0.0508777 0.239974 0.067119 0.0526715 0.239974 0.103879 0.0422123 0.239974 0.105205 0.0439679 0.239974 0.116976 0.0278454 0.239974 0.118847 0.0290036 0.239974 0.123999 0.00971749 0.239974 0.1249 -2.85742e-06 0.239974 0.126162 -0.0101275 0.239974 0.121328 -0.0191125 0.239974 0.111094 -0.0356414 0.239974 0.112719 -0.0371235 0.239974 0.105205 -0.0439736 0.239974 0.0864767 -0.0508834 0.239974 0.0770839 -0.0548678 0.239974 0.076881 -0.0526772 0.239974 0.067119 -0.0526772 0.239974 0.0575232 -0.0508834 0.239974 0.0484204 -0.047357 0.239974 0.025153 -0.0290093 0.239974 0.0178381 -0.0101275 0.239974 0.0178381 0.0101217 0.239974 0.0206207 0.0199016 0.239974 0.126162 0.0101217 0.238074 0.126162 0.0101217 0.238074 0.123379 0.0199016 0.239974 0.123379 0.0199016 0.238074 0.118847 0.0290036 0.239974 0.112719 0.0371178 0.238074 0.0965601 0.0493206 0.239974 0.0965601 0.0493206 0.239974 0.0870788 0.0529937 0.239974 0.0770839 0.0548621 0.238074 0.0770839 0.0548621 0.238074 0.066916 0.0548621 0.239974 0.066916 0.0548621 0.238074 0.0474398 0.0493206 0.239974 0.0474398 0.0493206 0.239974 0.0387948 0.0439679 0.239974 0.025153 0.0290036 0.238074 0.0206207 0.0199016 0.238074 0.0169 -2.85742e-06 0.239974 0.0169 -2.85742e-06 0.237874 0.0166094 0.0103514 0.237874 0.0204342 0.0199738 0.237874 0.0194551 0.0203531 0.237874 0.0303568 0.0379599 0.237874 0.0380415 0.0449654 0.237874 0.0568664 0.0531861 0.237874 0.056579 0.054196 0.237874 0.0771993 0.0561068 0.237874 0.0871335 0.0531861 0.237874 0.0874209 0.054196 0.237874 0.0966493 0.0494997 0.237874 0.112867 0.0372525 0.237874 0.119017 0.0291088 0.237874 0.12739 0.0103514 0.237874 0.12835 -2.85742e-06 0.237874 0.126358 -0.0101642 0.237874 0.12739 -0.0103571 0.237874 0.124545 -0.0203588 0.237874 0.112867 -0.0372582 0.237874 0.105326 -0.0441332 0.237874 0.113643 -0.0379656 0.237874 0.0966493 -0.0495054 0.237874 0.0971173 -0.0504453 0.237874 0.0874209 -0.0542017 0.237874 0.0771993 -0.0561125 0.237874 0.0568664 -0.0531918 0.237874 0.056579 -0.0542017 0.237874 0.0473506 -0.0495054 0.237874 0.0386743 -0.0441332 0.237874 0.0311328 -0.0372582 0.237874 0.0249829 -0.0291146 0.237874 0.0240902 -0.0296673 0.237874 0.0166094 -0.0103571 0.237874 0.01565 -2.85742e-06 0.237874 0.0176415 0.0101585 0.237874 0.124545 0.0203531 0.237474 0.124545 0.0203531 0.237474 0.113643 0.0379599 0.237874 0.11991 0.0296616 0.237874 0.113643 0.0379599 0.237874 0.105958 0.0449654 0.237474 0.0971173 0.0504396 0.237874 0.0971173 0.0504396 0.237474 0.0668006 0.0561068 0.237874 0.0668006 0.0561068 0.237474 0.056579 0.054196 0.237474 0.0468826 0.0504396 0.237874 0.0468826 0.0504396 0.237474 0.0303568 0.0379599 0.237474 0.0240902 0.0296616 0.237874 0.0240902 0.0296616 0.237474 0.0166094 0.0103514 0.237274 0.115856 -0.0368024 0.237274 0.113791 -0.0381003 0.237274 0.1088 -0.0438589 0.237274 0.106079 -0.0451307 0.237274 0.100625 -0.0495828 0.237274 0.072 -0.0572529 0.237274 0.0620586 -0.0563831 0.237274 0.0667822 -0.0563116 0.237274 0.0565243 -0.0543941 0.237274 0.043375 -0.0495828 0.237274 0.0352004 -0.0438589 0.237274 0.0239202 -0.0297726 0.237274 0.0192687 -0.0204311 0.237274 0.0182026 -0.0195835 0.237274 0.01545 -2.85742e-06 0.237274 0.0156197 -0.00994422 0.237274 0.01475 -2.85742e-06 0.237274 0.0164128 0.0103882 0.237274 0.0192687 0.0204254 0.237274 0.0239202 0.0297669 0.237274 0.043375 0.0495771 0.237274 0.0565243 0.0543884 0.237274 0.072 0.0572471 0.237274 0.0772177 0.0563059 0.237274 0.0915806 0.0537945 0.237274 0.0972065 0.0506186 0.237274 0.106079 0.045125 0.237274 0.1088 0.0438532 0.237274 0.113791 0.0380946 0.237274 0.12008 0.0297669 0.237274 0.125797 0.0195778 0.237274 0.127587 0.0103882 0.237274 0.12855 -2.85742e-06 0.237274 0.127587 -0.0103939 0.237274 0.124731 -0.0204311 0.237274 0.12838 -0.00994422 0.237274 0.12008 -0.0297726 0.237274 0.125797 -0.0195835 0.237474 0.116009 -0.036931 0.238274 0.116009 -0.036931 0.237474 0.108928 -0.0440121 0.237474 0.100725 -0.049756 0.237474 0.081976 -0.0565801 0.237474 0.072 -0.0574529 0.237474 0.0523509 -0.0539882 0.238274 0.043275 -0.049756 0.238274 0.0350718 -0.0440121 0.237474 0.0350718 -0.0440121 0.238274 0.0279907 -0.036931 0.237474 0.0279907 -0.036931 0.238274 0.0222468 -0.0287279 0.237474 0.0222468 -0.0287279 0.237474 0.0180146 -0.0196519 0.237474 0.0154228 -0.00997895 0.238274 0.0618155 0.0577561 0.238274 0.072 0.0574471 0.238274 0.0821844 0.0577561 0.238274 0.091649 0.0539825 0.238274 0.0920594 0.0551101 0.238274 0.116928 0.0376966 0.238274 0.121753 0.0287221 0.238274 0.128577 0.00997323 0.238274 0.128577 -0.00997895 0.238274 0.129759 -0.0101873 0.238274 0.125985 -0.0196519 0.238274 0.121753 -0.0287279 0.238274 0.122792 -0.0293279 0.238274 0.108928 -0.0440121 0.238274 0.109699 -0.0449314 0.238274 0.100725 -0.049756 0.238274 0.101325 -0.0507952 0.238274 0.091649 -0.0539882 0.238274 0.081976 -0.0565801 0.238274 0.072 -0.0574529 0.238274 0.0821844 -0.0577618 0.238274 0.0620239 -0.0565801 0.238274 0.0618155 -0.0577618 0.238274 0.0523509 -0.0539882 0.238274 0.0519405 -0.0551158 0.238274 0.0343005 -0.0449314 0.238274 0.0270715 -0.0377024 0.238274 0.0180146 -0.0196519 0.238274 0.0154228 -0.00997895 0.238274 0.016887 -0.0200623 0.238274 0.01455 -2.85742e-06 0.238274 0.0222468 0.0287221 0.238274 0.0212076 0.0293221 0.238274 0.0343005 0.0449256 0.238274 0.0523509 0.0539825 0.238274 0.042675 0.0507895 0.238274 0.0519405 0.0551101 0.238474 0.129956 -0.0102221 0.238974 0.122966 -0.0294279 0.238974 0.117082 -0.0378309 0.238474 0.109828 -0.0450846 0.238974 0.0921278 -0.0553038 0.238474 0.0921278 -0.0553038 0.238974 0.0822192 -0.0579588 0.238474 0.0822192 -0.0579588 0.238474 0.0617808 -0.0579588 0.238474 0.0518721 -0.0553038 0.238974 0.042575 -0.0509685 0.238974 0.0341719 -0.0450846 0.238974 0.0269182 -0.0378309 0.238474 0.0269182 -0.0378309 0.238974 0.0210344 -0.0294279 0.238474 0.0210344 -0.0294279 0.238474 0.016699 -0.0201307 0.241174 0.0162 -2.85742e-06 0.238974 0.014044 -0.0102221 0.238974 0.016699 -0.0201307 0.241174 0.0361324 -0.0427481 0.241174 0.0441 -0.0483271 0.238974 0.0518721 -0.0553038 0.238974 0.0617808 -0.0579588 0.241174 0.0623104 -0.0549551 0.238974 0.072 -0.0588529 0.241174 0.0910847 -0.0524377 0.238974 0.101425 -0.0509685 0.238974 0.109828 -0.0450846 0.241174 0.107868 -0.0427481 0.241174 0.114745 -0.0358704 0.238974 0.127301 -0.0201307 0.238974 0.129956 -0.0102221 0.241174 0.126952 -0.00969243 0.238974 0.13085 -2.85742e-06 0.241174 0.0309178 0.00872943 0.241174 0.0623104 0.0549494 0.241174 0.051 0.0363702 0.241174 0.0529152 0.052432 0.241174 0.0441 0.0483214 0.241174 0.124435 -0.0190876 0.241174 0.114 -2.85742e-06 0.241174 0.113082 0.00872943 0.241174 0.110369 0.0170801 0.241174 0.105979 0.0246841 0.241174 0.120324 0.0278971 0.241174 0.114745 0.0358647 0.241174 0.107868 0.0427424 0.241174 0.093 0.0363702 0.241174 0.0999 0.0483214 0.241174 0.0763902 0.0417671 0.241174 0.072 0.0557971 0.241174 0.072 -0.0558029 0.241174 0.0763902 -0.0417728 0.241174 0.0816895 -0.0549551 0.241174 0.0849787 -0.0399472 0.241174 0.0999 -0.0483271 0.241174 0.100103 -0.0312149 0.241174 0.105979 -0.0246898 0.241174 0.120324 -0.0279029 0.241174 0.0170477 -0.00969243 0.241174 0.0195651 -0.0190876 0.241174 0.0236757 -0.0279029 0.241174 0.0292547 -0.0358704 0.241174 0.0676098 -0.0417728 0.241174 0.0529152 -0.0524377 0.241174 0.113082 -0.00873515 0.241174 0.110369 -0.0170858 0.241374 0.100103 -0.0312149 0.241174 0.093 -0.0363759 0.241374 0.0676098 -0.0417728 0.241174 0.0590212 -0.0399472 0.241374 0.051 -0.0363759 0.241174 0.051 -0.0363759 0.241374 0.0438965 -0.0312149 0.241174 0.0438965 -0.0312149 0.241174 0.0380212 -0.0246898 0.241374 0.033631 -0.0170858 0.241174 0.033631 -0.0170858 0.241174 0.0309178 -0.00873515 0.238974 0.114 -2.85742e-06 0.239374 0.113193 -0.00819665 0.238974 0.113082 -0.00873515 0.239374 0.110369 -0.0170858 0.239374 0.106922 -0.0233368 0.238974 0.110369 -0.0170858 0.239374 0.105979 -0.0246898 0.239374 0.101698 -0.0297013 0.238974 0.093 -0.0363759 0.239374 0.0880727 -0.0388058 0.239374 0.0849787 -0.0399472 0.239374 0.0801938 -0.0411958 0.238974 0.0763902 -0.0417728 0.239374 0.0676098 -0.0417728 0.239374 0.0638062 -0.0411958 0.238974 0.0590212 -0.0399472 0.239374 0.0559273 -0.0388058 0.239374 0.0438965 -0.0312149 0.239374 0.0423015 -0.0297013 0.238974 0.0380212 -0.0246898 0.239374 0.0380212 -0.0246898 0.238974 0.033631 -0.0170858 0.238974 0.0309178 -0.00873515 0.239374 0.03 -2.85742e-06 0.238974 0.03 -2.85742e-06 0.239374 0.033197 -0.0160756 0.238674 0.0345463 0.00362648 0.238674 0.0964798 -0.0202272 0.238674 0.0665001 0.0320907 0.238674 0.0416134 0.0110308 0.238674 0.0999027 -0.030992 0.238674 0.0339051 0.0169581 0.238674 0.0392419 0.0258003 0.238674 0.101823 0.0291434 0.238674 0.103832 0.00563501 0.238674 0.105807 0.00510581 0.238674 0.101679 0.00362648 0.238674 0.103832 0.0124766 0.238674 0.107782 0.00563501 0.238674 0.109757 0.00905581 0.238674 0.111192 0.0142394 0.238674 0.103386 0.0156352 0.238674 0.110095 0.0169581 0.238674 0.100169 0.0267209 0.238674 0.100699 0.0247459 0.238674 0.100308 0.023032 0.238674 0.0958697 0.0208949 0.238674 0.0964798 0.0202215 0.238674 0.101679 0.0202215 0.238674 0.0992115 0.0216576 0.238674 0.101745 0.0292229 0.238674 0.0964798 0.0296758 0.238674 0.0964798 0.0326526 0.238674 0.0999027 0.0309863 0.238674 0.0756293 0.0326526 0.238674 0.0776378 0.0357795 0.238674 0.0763588 0.0414687 0.238674 0.0862299 0.0391941 0.238674 0.0830336 0.0372253 0.238674 0.0810586 0.0377545 0.238674 0.070138 0.0339221 0.238674 0.0668913 0.0338045 0.238674 0.073075 0.0331352 0.238674 0.070925 0.0331352 0.238674 0.0738619 0.0339221 0.238674 0.07415 0.0349971 0.238674 0.0738619 0.0360721 0.238674 0.070138 0.0360721 0.238674 0.072 0.0371471 0.238674 0.0595205 0.0357795 0.238674 0.0609663 0.0372253 0.238674 0.0342426 -0.00906152 0.238674 0.0346337 -0.00734768 0.238674 0.0345463 -0.00363219 0.238674 0.0393445 -0.0202272 0.238674 0.0427898 -0.0297628 0.238674 0.0429006 -0.0291022 0.238674 0.0440972 -0.030992 0.238674 0.05115 -0.0361161 0.238674 0.0861793 -0.0374566 0.238674 0.0922513 -0.0364552 0.238674 0.0895 -0.0324637 0.238674 0.090575 -0.0321757 0.238674 0.0922243 -0.0296816 0.238674 0.09285 -0.0361161 0.238674 0.100169 -0.0267266 0.238674 0.100699 -0.0247516 0.238674 0.105736 -0.0245135 0.238674 0.104461 -0.0175029 0.238674 0.110095 -0.0169638 0.238674 0.111192 -0.0142452 0.238674 0.104173 -0.0164279 0.238674 0.103386 -0.0156409 0.238674 0.101679 -0.0141822 0.238674 0.109757 -0.00906152 0.238674 0.101857 -0.00906152 0.238674 0.1137 -2.85742e-06 0.238674 0.102387 -0.00708652 0.238674 0.102387 -0.0110365 0.238674 0.105807 -0.0130115 0.238674 0.109228 -0.0110365 0.238674 0.073075 -0.0368648 0.238674 0.0550963 -0.0374566 0.238674 0.0609663 -0.0372311 0.238674 0.072 -0.0371529 0.238674 0.0649163 -0.0372311 0.238674 0.0756293 -0.0374566 0.238674 0.0738619 -0.0339279 0.238674 0.072 -0.0328529 0.238674 0.0629413 -0.0298603 0.238674 0.0649163 -0.0303895 0.238674 0.070138 -0.0339279 0.238674 0.0663621 -0.0357853 0.238674 0.0550963 -0.0296816 0.238674 0.0609663 -0.0303895 0.238674 0.0595205 -0.0357853 0.238674 0.0422553 -0.0292286 0.238674 0.0429006 -0.0202272 0.238674 0.0433012 -0.0247516 0.238674 0.0438304 -0.0227766 0.238674 0.0475201 -0.0291022 0.238674 0.0401676 -0.0124823 0.238674 0.0406553 -0.00597329 0.238674 0.0357298 -0.00597329 0.238674 0.0416134 -0.0110365 0.238674 0.0347718 -0.0110365 0.238674 0.0328075 -0.0142452 0.238674 0.0312112 -0.00867277 0.238674 0.0381926 0.0130058 0.238674 0.0421426 0.00905581 0.238674 0.0401676 0.00563501 0.238674 0.0416134 0.00708081 0.238674 0.0393445 0.00362648 0.238674 0.0362176 0.00563501 0.238674 0.0381926 0.00510581 0.238674 0.0475201 0.0296758 0.238674 0.0429006 0.0290965 0.238674 0.0475201 0.0290965 0.238674 0.0452762 0.0281667 0.238674 0.0475201 0.0202215 0.238674 0.0452762 0.0213251 0.238674 0.0472512 0.0207959 0.238674 0.0506741 0.02038 0.238674 0.0492262 0.0213251 0.238674 0.0550963 0.0290965 0.238674 0.0550963 0.0326526 0.238674 0.0593825 0.0320907 0.238674 0.0620623 0.0299536 0.238674 0.0756293 0.0296758 0.238674 0.0771086 0.0338045 0.238674 0.0776378 0.0318295 0.238674 0.0654041 0.0307163 0.238674 0.0790836 0.0303837 0.238674 0.0844794 0.0318295 0.238674 0.0931899 0.023032 0.238674 0.0935045 -0.020197 0.238674 0.0947737 -0.0213308 0.238674 0.0923278 -0.0213811 0.238674 0.0987237 -0.0281724 0.238674 0.101745 -0.0292286 0.238674 0.0947737 -0.0281724 0.238674 0.0922243 -0.0291022 0.238674 0.0763588 -0.0414744 0.238674 0.084886 -0.0396619 0.238674 0.0862299 -0.0391998 0.238674 0.0830336 -0.0372311 0.238674 0.0899267 -0.0376529 0.238674 0.0738619 -0.0360779 0.238674 0.07415 -0.0350029 0.238674 0.0756293 -0.0296816 0.238674 0.0771086 -0.0338103 0.238674 0.0844794 -0.0318353 0.238674 0.0850086 -0.0338103 0.238674 0.0810586 -0.0298603 0.238674 0.0861793 -0.0296816 0.238674 0.0790836 -0.0303895 0.238674 0.0776378 -0.0318353 0.238674 0.101679 -0.0202272 0.238674 0.101236 -0.0193648 0.238674 0.0933279 -0.0267266 0.238674 0.0474037 -0.01629 0.238674 0.0395391 -0.0175029 0.238674 0.0427641 -0.0156409 0.238674 0.0429006 -0.0141822 0.238674 0.0416891 -0.0153529 0.238674 0.0398271 -0.0164279 0.238674 0.0393445 -0.0141822 0.238674 0.0345463 -0.0141822 0.238674 0.0339051 -0.0169638 0.238674 0.0416891 -0.0196529 0.238674 0.0475201 -0.0202272 0.238674 0.0427641 -0.0193648 0.238674 0.0429006 0.0141765 0.238674 0.0445716 0.0108568 0.238674 0.0427641 0.0156352 0.238674 0.0438391 0.0174971 0.238674 0.0429006 0.0202215 0.238674 0.0416891 0.0153471 0.238674 0.0393445 0.0202215 0.238674 0.0395391 0.0174971 0.238674 0.0393445 0.0141765 0.238674 0.0398271 0.0164221 0.238674 0.0861793 0.0326526 0.238674 0.087638 0.031383 0.238674 0.088425 0.03217 0.238674 0.09165 0.030308 0.238674 0.0922243 0.0326526 0.238674 0.090575 0.03217 0.238674 0.087638 0.029233 0.238674 0.088425 0.0284461 0.238674 0.0878069 0.0249048 0.238674 0.0923278 0.0213754 0.238674 0.0895 0.028158 0.238674 0.100374 0.01843 0.238674 0.0935045 0.0201913 0.238674 0.0942859 0.0216576 0.238674 0.100161 0.0174971 0.238674 0.103651 0.0191781 0.238674 0.105736 0.0245078 0.238674 0.0895 -0.0281637 0.238674 0.0861793 -0.0291022 0.238674 0.0756798 -0.0292724 0.238674 0.0738523 -0.0294446 0.238674 0.0664722 -0.0289803 0.238674 0.0594395 -0.0266953 0.238674 0.0531959 -0.022733 0.238674 0.050672 -0.0267266 0.238674 0.0861793 0.0296758 0.238674 0.0861793 0.0290965 0.238674 0.0738523 0.0294389 0.238674 0.0664722 0.0289746 0.238674 0.0594395 0.0266895 0.238674 0.101679 0.0141765 0.238674 0.100573 0.00733349 0.238674 0.101679 -0.00363219 0.238674 0.0913619 -0.0292387 0.238674 0.0964798 -0.0296816 0.238674 0.0964798 -0.0291022 0.238674 0.0475201 -0.0296816 0.238674 0.0428076 -0.0297803 0.238674 0.0550963 -0.0291022 0.238674 0.0427326 0.00369447 0.238674 0.0393445 -0.00363219 0.238674 0.038937 -0.000935707 0.238674 0.035925 0.0018591 0.238674 0.035138 0.00107214 0.238674 0.0362176 0.0124766 0.238674 0.0342426 0.00905581 0.238674 0.0345463 0.0141765 0.238674 0.0312112 0.00866706 0.238674 0.0303 -2.85742e-06 0.238674 0.0350629 -0.000935707 0.238674 0.0356595 -0.0016838 0.238674 0.0365215 -0.00209895 0.238674 0.0383405 -0.0016838 0.238674 0.09285 0.0361104 0.238674 0.0922243 0.0296758 0.238674 0.0964798 0.0290965 0.238674 0.0922243 0.0290965 0.238674 0.0967487 0.0286959 0.238674 0.0947737 0.0281667 0.238674 0.0475201 0.0326526 0.238674 0.0550963 0.0296758 0.238974 0.0309178 0.00872943 0.239374 0.030807 0.00819094 0.239374 0.033631 0.0170801 0.238974 0.051 0.0363702 0.239374 0.0380212 0.0246841 0.238974 0.0438965 0.0312092 0.239374 0.0423015 0.0296956 0.239374 0.051 0.0363702 0.239374 0.0559273 0.0388001 0.238974 0.0590212 0.0399415 0.239374 0.0590212 0.0399415 0.239374 0.0638062 0.0411901 0.238974 0.0676098 0.0417671 0.239374 0.0676098 0.0417671 0.239374 0.072 0.0419971 0.239374 0.0801938 0.0411901 0.239374 0.100103 0.0312092 0.239374 0.106922 0.0233311 0.239374 0.110369 0.0170801 0.241174 0.03 -2.85742e-06 0.241374 0.0309178 0.00872943 0.241374 0.033631 0.0170801 0.241374 0.0380212 0.0246841 0.241174 0.033631 0.0170801 0.241174 0.0380212 0.0246841 0.241374 0.0438965 0.0312092 0.241174 0.0438965 0.0312092 0.241174 0.0590212 0.0399415 0.241374 0.0676098 0.0417671 0.241174 0.0676098 0.0417671 0.241374 0.0763902 0.0417671 0.241174 0.0849787 0.0399415 0.241374 0.093 0.0363702 0.241174 0.100103 0.0312092 0.241374 0.113082 0.00872943 0.241174 0.1278 -2.85742e-06 0.241174 0.126952 0.00968671 0.241174 0.124435 0.0190819 0.238974 0.127301 0.020125 0.238974 0.122966 0.0294221 0.238974 0.109828 0.0450789 0.238974 0.101425 0.0509627 0.241174 0.0910847 0.052432 0.241174 0.0816895 0.0549494 0.238974 0.0822192 0.0579531 0.238974 0.0617808 0.0579531 0.238974 0.0518721 0.0552981 0.241174 0.0361324 0.0427424 0.241174 0.0292547 0.0358647 0.238974 0.0210344 0.0294221 0.241174 0.0236757 0.0278971 0.238974 0.016699 0.020125 0.238974 0.014044 0.0102163 0.241174 0.0195651 0.0190819 0.238974 0.01315 -2.85742e-06 0.241174 0.0170477 0.00968671 0.238474 0.01315 -2.85742e-06 0.238474 0.014044 0.0102163 0.238474 0.016699 0.020125 0.238974 0.0269182 0.0378252 0.238974 0.0341719 0.0450789 0.238474 0.042575 0.0509627 0.238974 0.042575 0.0509627 0.238474 0.0518721 0.0552981 0.238974 0.072 0.0588471 0.238974 0.0921278 0.0552981 0.238474 0.0921278 0.0552981 0.238474 0.101425 0.0509627 0.238974 0.117082 0.0378252 0.238474 0.117082 0.0378252 0.238474 0.122966 0.0294221 0.238474 0.127301 0.020125 0.238974 0.129956 0.0102163 0.237474 0.01455 -2.85742e-06 0.238274 0.0154228 0.00997323 0.237474 0.0154228 0.00997323 0.238274 0.0180146 0.0196462 0.237474 0.0222468 0.0287221 0.238274 0.0279907 0.0369253 0.237474 0.0350718 0.0440064 0.238274 0.0350718 0.0440064 0.238274 0.043275 0.0497503 0.238274 0.0620239 0.0565743 0.237474 0.0523509 0.0539825 0.237474 0.0620239 0.0565743 0.238274 0.081976 0.0565743 0.237474 0.091649 0.0539825 0.238274 0.100725 0.0497503 0.237474 0.100725 0.0497503 0.237474 0.108928 0.0440064 0.238274 0.108928 0.0440064 0.237474 0.116009 0.0369253 0.238274 0.116009 0.0369253 0.238274 0.125985 0.0196462 0.238274 0.12945 -2.85742e-06 0.237474 0.0166094 -0.0103571 0.237474 0.0194551 -0.0203588 0.237874 0.0194551 -0.0203588 0.237474 0.0303568 -0.0379656 0.237874 0.0303568 -0.0379656 0.237474 0.0380415 -0.0449711 0.237874 0.0380415 -0.0449711 0.237474 0.0468826 -0.0504453 0.237474 0.056579 -0.0542017 0.237874 0.0468826 -0.0504453 0.237474 0.0668006 -0.0561125 0.237874 0.0668006 -0.0561125 0.237474 0.0771993 -0.0561125 0.237874 0.105958 -0.0449711 0.237474 0.113643 -0.0379656 0.237874 0.11991 -0.0296673 0.237474 0.124545 -0.0203588 0.237474 0.12739 -0.0103571 0.237474 0.12835 -2.85742e-06 0.239974 0.0206207 -0.0199073 0.238074 0.0387948 -0.0439736 0.239974 0.0312806 -0.0371235 0.239974 0.0387948 -0.0439736 0.239974 0.0474398 -0.0493264 0.238074 0.0569211 -0.0529995 0.239974 0.0569211 -0.0529995 0.239974 0.066916 -0.0548678 0.238074 0.0770839 -0.0548678 0.238074 0.0870788 -0.0529995 0.239974 0.0870788 -0.0529995 0.238074 0.0965601 -0.0493264 0.239974 0.0965601 -0.0493264 0.238074 0.105205 -0.0439736 0.239974 0.118847 -0.0290093 0.238074 0.123379 -0.0199073 0.239974 0.123379 -0.0199073 0.239974 0.1271 -2.85742e-06 0.239974 0.0191 -2.85742e-06 0.239974 0.0200007 0.00971749 0.239974 0.0226722 0.0191068 0.239974 0.0270235 0.0278454 0.239974 0.0329064 0.0356356 0.239974 0.0401206 0.0422123 0.238074 0.0401206 0.0422123 0.239974 0.0484204 0.0473513 0.239974 0.076881 0.0526715 0.239974 0.0864767 0.0508777 0.239974 0.0955795 0.0473513 0.239974 0.111094 0.0356356 0.238074 0.111094 0.0356356 0.239974 0.121328 0.0191068 0.238074 0.123999 0.00971749 0.238074 0.1249 -2.85742e-06 0.238074 0.02 -2.85742e-06 0.240174 0.02 -2.85742e-06 0.238074 0.0208854 -0.00955783 0.240174 0.0235114 -0.0187874 0.238074 0.0277887 -0.0273773 0.240174 0.0277887 -0.0273773 0.238074 0.040663 -0.0414998 0.238074 0.0488216 -0.0465513 0.238074 0.0577695 -0.0500178 0.240174 0.0577695 -0.0500178 0.240174 0.0767979 -0.051781 0.240174 0.0862304 -0.0500178 0.238074 0.0951784 -0.0465513 0.240174 0.110428 -0.035035 0.238074 0.116211 -0.0273773 0.240174 0.116211 -0.0273773 0.238074 0.120489 -0.0187874 0.238074 0.123115 -0.00955783 0.240174 0.123115 -0.00955783 0.240174 0.0268838 0.0089713 0.239374 0.0370782 0.0233311 0.240174 0.0295015 0.0176006 0.239374 0.033197 0.0160698 0.239374 0.0309178 0.00872943 0.239374 0.048666 0.0349189 0.239374 0.0438965 0.0312092 0.240174 0.039473 0.0325241 0.240174 0.0337524 0.0255534 0.240174 0.0464437 0.0382447 0.240174 0.072 0.0459971 0.239374 0.0763902 0.0417671 0.240174 0.0809741 0.0451133 0.239374 0.0849787 0.0399415 0.239374 0.0880727 0.0388001 0.239374 0.093 0.0363702 0.240174 0.0896034 0.0424956 0.239374 0.0953339 0.0349189 0.240174 0.0975562 0.0382447 0.240174 0.104527 0.0325241 0.239374 0.101698 0.0296956 0.239374 0.105979 0.0246841 0.240174 0.110248 0.0255534 0.239374 0.110803 0.0160698 0.239374 0.113082 0.00872943 0.240174 0.117116 0.0089713 0.240174 0.118 -2.85742e-06 0.239374 0.113193 0.00819094 0.239374 0.114 -2.85742e-06 0.238674 0.100449 0.0164221 0.238674 0.101236 0.0156352 0.238674 0.102311 0.0153471 0.238674 0.104173 0.0164221 0.239024 0.103386 0.0156352 0.239024 0.104173 0.0164221 0.239024 0.100161 0.0174971 0.239024 0.100449 0.0164221 0.241674 0.0975108 0.0174971 0.241674 0.0981539 0.0150971 0.241674 0.0999108 0.0133402 0.239024 0.101236 0.0156352 0.239024 0.102311 0.0153471 0.241674 0.102311 0.0126971 0.239024 0.0895 0.028158 0.238674 0.090575 0.0284461 0.238674 0.0913619 0.029233 0.239024 0.09165 0.030308 0.239024 0.087638 0.029233 0.239024 0.088425 0.0284461 0.241674 0.0895 0.025508 0.239024 0.090575 0.0284461 0.239024 0.0913619 0.029233 0.241674 0.0919 0.0261511 0.241674 0.0936569 0.027908 0.239024 0.070138 0.0339221 0.239024 0.070925 0.0331352 0.238674 0.072 0.0328471 0.239024 0.073075 0.0331352 0.239024 0.0738619 0.0339221 0.239024 0.072 0.0328471 0.239024 0.07415 0.0349971 0.241674 0.0761569 0.0325971 0.238674 0.0406141 0.0156352 0.239024 0.0427641 0.0156352 0.238674 0.043551 0.0164221 0.239024 0.043551 0.0164221 0.239024 0.0398271 0.0164221 0.241674 0.0375321 0.0150971 0.239024 0.0406141 0.0156352 0.241674 0.0392891 0.0133402 0.239024 0.0416891 0.0153471 0.241674 0.0416891 0.0126971 0.239024 0.0438391 0.0174971 0.239024 0.0350629 -0.000935707 0.239024 0.0356595 -0.0016838 0.239024 0.0365215 -0.00209895 0.238674 0.0374784 -0.00209895 0.239024 0.038937 -0.000935707 0.238674 0.03915 -2.85742e-06 0.241674 0.0322 -2.85742e-06 0.241674 0.0326753 -0.0020855 0.239024 0.0374784 -0.00209895 0.241674 0.0359319 -0.00468251 0.241674 0.0380681 -0.00468251 0.239024 0.0383405 -0.0016838 0.239024 0.039752 -0.0184357 0.238674 0.0398271 -0.0185779 0.239024 0.0398271 -0.0185779 0.238674 0.0406141 -0.0193648 0.239024 0.0406141 -0.0193648 0.239024 0.0412106 -0.019599 0.239024 0.0421675 -0.019599 0.239024 0.043551 -0.0185779 0.238674 0.043551 -0.0185779 0.241674 0.0460137 -0.0195855 0.239024 0.0436262 -0.0184357 0.239024 0.0430296 -0.0191838 0.241674 0.0446818 -0.0212556 0.239024 0.0427641 -0.0193648 0.239024 0.0416891 -0.0196529 0.241674 0.040621 -0.0221825 0.239024 0.0403486 -0.0191838 0.241674 0.0368891 -0.0175029 0.238674 0.06985 -0.0350029 0.238674 0.070138 -0.0360779 0.238674 0.070925 -0.0368648 0.239024 0.072 -0.0371529 0.239024 0.073075 -0.0368648 0.239024 0.07415 -0.0350029 0.241674 0.0672 -0.0350029 0.239024 0.070138 -0.0360779 0.239024 0.070925 -0.0368648 0.241674 0.0696 -0.0391598 0.241674 0.0744 -0.0391598 0.239024 0.0738619 -0.0360779 0.238674 0.087638 -0.0313887 0.239024 0.08735 -0.0303137 0.238674 0.088425 -0.0321757 0.239024 0.088425 -0.0321757 0.239024 0.090575 -0.0321757 0.238674 0.0913619 -0.0313887 0.239024 0.0913619 -0.0313887 0.239024 0.087638 -0.0313887 0.239024 0.0895 -0.0324637 0.241674 0.0919 -0.0344707 0.241674 0.0936569 -0.0327137 0.238674 0.100449 -0.0185779 0.239024 0.101236 -0.0193648 0.238674 0.102311 -0.0196529 0.238674 0.103386 -0.0193648 0.239024 0.103386 -0.0193648 0.238674 0.104173 -0.0185779 0.239024 0.104173 -0.0185779 0.239024 0.100161 -0.0175029 0.239024 0.100449 -0.0185779 0.239024 0.102311 -0.0196529 0.241674 0.104711 -0.0216598 0.241674 0.106468 -0.0199029 0.238874 0.102057 0.00905581 0.241474 0.102057 0.00905581 0.238874 0.10256 0.00718081 0.241474 0.103932 0.00580821 0.241474 0.105807 0.00530581 0.238874 0.105807 0.00530581 0.238874 0.107682 0.00580821 0.238874 0.109055 0.00718081 0.238874 0.0929987 0.0247459 0.238874 0.0933701 0.0231188 0.241474 0.0933701 0.0231188 0.238874 0.0944106 0.021814 0.238874 0.0959142 0.0210899 0.238874 0.0975832 0.0210899 0.238874 0.0990868 0.021814 0.238874 0.100127 0.0231188 0.241474 0.100127 0.0231188 0.241474 0.0791836 0.030557 0.241474 0.0829336 0.030557 0.238874 0.0843062 0.0319295 0.238874 0.0848086 0.0338045 0.241474 0.0848086 0.0338045 0.241474 0.0591913 0.0338045 0.238874 0.0595627 0.0321775 0.238874 0.0606032 0.0308727 0.241474 0.0595627 0.0321775 0.241474 0.0606032 0.0308727 0.238874 0.0621068 0.0301486 0.241474 0.0621068 0.0301486 0.238874 0.0637757 0.0301486 0.241474 0.0637757 0.0301486 0.238874 0.0652794 0.0308727 0.241474 0.0663199 0.0321775 0.238874 0.0435012 0.0247459 0.238874 0.0440036 0.0228709 0.241474 0.0440036 0.0228709 0.241474 0.0453762 0.0214983 0.238874 0.0472512 0.0209959 0.241474 0.0491262 0.0214983 0.241474 0.0504988 0.0228709 0.241474 0.0510012 0.0247459 0.238874 0.0344426 0.00905581 0.241474 0.034945 0.00718081 0.238874 0.0363176 0.00580821 0.241474 0.0363176 0.00580821 0.238874 0.0381926 0.00530581 0.241474 0.0400676 0.00580821 0.241474 0.0344426 -0.00906152 0.241474 0.034945 -0.0109365 0.241474 0.0363176 -0.0123091 0.238874 0.0414401 -0.0109365 0.238874 0.0419426 -0.00906152 0.241474 0.0435012 -0.0247516 0.241474 0.0440036 -0.0266266 0.241474 0.0453762 -0.0279992 0.241474 0.0491262 -0.0279992 0.241474 0.0504988 -0.0266266 0.238874 0.0596937 -0.0356853 0.238874 0.0610663 -0.0370579 0.238874 0.0629413 -0.0375603 0.241474 0.0629413 -0.0375603 0.238874 0.0648163 -0.0370579 0.238874 0.0661889 -0.0356853 0.241474 0.0648163 -0.0370579 0.241474 0.0666913 -0.0338103 0.238874 0.0791836 -0.0370579 0.241474 0.0829336 -0.0370579 0.238874 0.0843062 -0.0356853 0.238874 0.0848086 -0.0338103 0.241474 0.0935011 -0.0266266 0.241474 0.0948737 -0.0279992 0.238874 0.0967487 -0.0285016 0.241474 0.100499 -0.0247516 0.238874 0.10256 -0.0109365 0.241474 0.102057 -0.00906152 0.241474 0.103932 -0.0123091 0.238874 0.105807 -0.0128115 0.241474 0.105807 -0.0128115 0.238874 0.107682 -0.0123091 0.238874 0.109055 -0.0109365 0.238874 0.109557 -0.00906152 0.241474 0.109055 -0.0109365 0.238674 0.038264 0.0245078 0.238974 0.0380212 0.0246841 0.238674 0.0344468 0.0181259 0.238974 0.033631 0.0170801 0.238674 0.0422553 0.0292229 0.238974 0.0763902 0.0417671 0.238674 0.0676411 0.0414687 0.238674 0.0591139 0.0396562 0.238674 0.05115 0.0361104 0.238674 0.0440972 0.0309863 0.238674 0.0428076 0.0297746 0.238674 0.0427898 0.0297571 0.238974 0.093 0.0363702 0.238974 0.0849787 0.0399415 0.238674 0.084886 0.0396562 0.238674 0.101192 0.0297746 0.238974 0.100103 0.0312092 0.238974 0.105979 0.0246841 0.238974 0.110369 0.0170801 0.238674 0.112789 0.00866706 0.238974 0.113082 0.00872943 0.241374 0.110369 0.0170801 0.241674 0.110095 0.0169581 0.241374 0.105979 0.0246841 0.241674 0.0999027 0.0309863 0.241374 0.100103 0.0312092 0.241674 0.100853 0.0301032 0.241674 0.1014 0.0295691 0.241374 0.051 0.0363702 0.241674 0.05115 0.0361104 0.241674 0.0591139 0.0396562 0.241374 0.0590212 0.0399415 0.241374 0.0849787 0.0399415 0.241674 0.0769667 0.0414003 0.241674 0.084886 0.0396562 0.241674 0.0425994 0.0295691 0.241674 0.0424245 0.0293941 0.241674 0.0312112 0.00866706 0.241674 0.0604785 0.0307163 0.241674 0.0620623 0.0299536 0.241474 0.0652794 0.0308727 0.241674 0.0654041 0.0307163 0.241474 0.0666913 0.0338045 0.241474 0.0472512 0.0209959 0.241674 0.0492262 0.0213251 0.241674 0.0347718 0.00708081 0.241674 0.0362176 0.00563501 0.241474 0.0381926 0.00530581 0.241674 0.0381926 0.00510581 0.241474 0.0414401 0.00718081 0.241674 0.0401676 0.00563501 0.241474 0.0419426 0.00905581 0.241474 0.0381926 -0.0128115 0.241474 0.0400676 -0.0123091 0.241474 0.0414401 -0.0109365 0.241674 0.0416134 -0.0110365 0.241674 0.0433012 -0.0247516 0.241674 0.0438304 -0.0267266 0.241474 0.0472512 -0.0285016 0.241674 0.0492262 -0.0281724 0.241474 0.0596937 -0.0356853 0.241474 0.0610663 -0.0370579 0.241674 0.0629413 -0.0377603 0.241474 0.0661889 -0.0356853 0.241674 0.0663621 -0.0357853 0.241474 0.0773086 -0.0338103 0.241674 0.0771086 -0.0338103 0.241474 0.077811 -0.0356853 0.241474 0.0791836 -0.0370579 0.241674 0.0776378 -0.0357853 0.241674 0.0790836 -0.0372311 0.241474 0.0810586 -0.0375603 0.241674 0.0830336 -0.0372311 0.241474 0.0843062 -0.0356853 0.241474 0.0967487 -0.0285016 0.241474 0.0986237 -0.0279992 0.241674 0.0967487 -0.0287016 0.241674 0.0987237 -0.0281724 0.241474 0.0999963 -0.0266266 0.241674 0.100169 -0.0267266 0.241674 0.101857 -0.00906152 0.241474 0.10256 -0.0109365 0.241474 0.107682 -0.0123091 0.241674 0.105807 -0.0130115 0.241474 0.109557 -0.00906152 0.241674 0.109757 -0.00906152 0.241474 0.10256 0.00718081 0.241674 0.103832 0.00563501 0.241674 0.105807 0.00510581 0.241474 0.107682 0.00580821 0.241674 0.107782 0.00563501 0.241474 0.109055 0.00718081 0.241674 0.109228 0.00708081 0.241674 0.0927987 0.0247459 0.241674 0.0942859 0.0216576 0.241474 0.0944106 0.021814 0.241474 0.0959142 0.0210899 0.241474 0.0975832 0.0210899 0.241474 0.0990868 0.021814 0.241674 0.100308 0.023032 0.241474 0.077811 0.0319295 0.241474 0.0810586 0.0300545 0.241674 0.0790836 0.0303837 0.241474 0.0843062 0.0319295 0.238874 0.0666913 -0.0338103 0.238674 0.0629413 -0.0377603 0.238874 0.0591913 -0.0338103 0.238674 0.0512012 -0.0247516 0.238874 0.0504988 -0.0266266 0.238874 0.0491262 -0.0279992 0.238674 0.0492262 -0.0281724 0.238874 0.0472512 -0.0285016 0.238874 0.0453762 -0.0279992 0.238674 0.0472512 -0.0287016 0.238674 0.0452762 -0.0281724 0.238874 0.0440036 -0.0266266 0.238674 0.0438304 -0.0267266 0.238674 0.0421426 -0.00906152 0.238874 0.0400676 -0.0123091 0.238874 0.0381926 -0.0128115 0.238674 0.0381926 -0.0130115 0.238674 0.0362176 -0.0124823 0.238874 0.0363176 -0.0123091 0.238874 0.034945 -0.0109365 0.238874 0.0414401 0.00718081 0.238874 0.0400676 0.00580821 0.238874 0.034945 0.00718081 0.238674 0.0347718 0.00708081 0.238874 0.0510012 0.0247459 0.238874 0.0504988 0.0228709 0.238674 0.050672 0.0227709 0.238874 0.0491262 0.0214983 0.238874 0.0453762 0.0214983 0.238674 0.0438304 0.0227709 0.238874 0.0663199 0.0321775 0.238674 0.0638203 0.0299536 0.238674 0.0604785 0.0307163 0.238674 0.0850086 0.0338045 0.238874 0.0829336 0.030557 0.238674 0.0830336 0.0303837 0.238874 0.0810586 0.0300545 0.238874 0.0791836 0.030557 0.238674 0.0810586 0.0298545 0.238874 0.077811 0.0319295 0.238874 0.0773086 0.0338045 0.238674 0.0976277 0.0208949 0.238674 0.0927987 0.0247459 0.238674 0.109228 0.00708081 0.238874 0.103932 0.00580821 0.238674 0.102387 0.00708081 0.238674 0.107782 -0.0124823 0.238874 0.103932 -0.0123091 0.238674 0.103832 -0.0124823 0.238874 0.0999963 -0.0266266 0.238874 0.0986237 -0.0279992 0.238874 0.0948737 -0.0279992 0.238674 0.0967487 -0.0287016 0.238874 0.0935011 -0.0266266 0.238874 0.0829336 -0.0370579 0.238674 0.0844794 -0.0357853 0.238874 0.0810586 -0.0375603 0.238674 0.0810586 -0.0377603 0.238674 0.0790836 -0.0372311 0.238874 0.077811 -0.0356853 0.238674 0.0776378 -0.0357853 0.238274 0.014241 0.0101816 0.238274 0.016887 0.0200566 0.238474 0.0210344 0.0294221 0.238474 0.0269182 0.0378252 0.238274 0.0270715 0.0376966 0.238474 0.0341719 0.0450789 0.238474 0.0617808 0.0579531 0.238474 0.072 0.0588471 0.238274 0.072 0.0586471 0.238474 0.0822192 0.0579531 0.238274 0.101325 0.0507895 0.238274 0.109699 0.0449256 0.238474 0.109828 0.0450789 0.238274 0.122792 0.0293221 0.238274 0.127113 0.0200566 0.238474 0.129956 0.0102163 0.238274 0.129759 0.0101816 0.238274 0.13065 -2.85742e-06 0.238074 0.124 -2.85742e-06 0.237874 0.123311 -0.00959458 0.237874 0.116381 -0.0274826 0.238074 0.110428 -0.035035 0.238074 0.103337 -0.0414998 0.238074 0.0862304 -0.0500178 0.238074 0.0767979 -0.051781 0.237874 0.0768164 -0.0519802 0.238074 0.067202 -0.051781 0.237874 0.0487324 -0.0467304 0.238074 0.0335715 -0.035035 0.237874 0.0405424 -0.0416594 0.238074 0.0235114 -0.0187874 0.238074 0.0191 -2.85742e-06 0.238074 0.0200007 0.00971749 0.238074 0.0226722 0.0191068 0.238074 0.0270235 0.0278454 0.238074 0.0329064 0.0356356 0.238074 0.0484204 0.0473513 0.237874 0.0485095 0.0471722 0.237874 0.0575779 0.0506854 0.238074 0.0575232 0.0508777 0.238074 0.067119 0.0526715 0.237874 0.0671374 0.0524723 0.238074 0.076881 0.0526715 0.238074 0.0864767 0.0508777 0.237874 0.0954904 0.0471722 0.238074 0.0955795 0.0473513 0.238074 0.103879 0.0422123 0.237874 0.103759 0.0420526 0.237874 0.110946 0.0355009 0.238074 0.116976 0.0278454 0.238074 0.121328 0.0191068 0.237874 0.121141 0.0190346 0.237874 0.123803 0.00968074 0.237474 0.0180146 0.0196462 0.237274 0.0156197 0.0099385 0.237274 0.0182026 0.0195778 0.237274 0.02242 0.0286221 0.237474 0.0279907 0.0369253 0.237274 0.0281439 0.0367967 0.237274 0.0352004 0.0438532 0.237474 0.043275 0.0497503 0.237274 0.0524193 0.0537945 0.237474 0.072 0.0574471 0.237274 0.0620586 0.0563774 0.237474 0.081976 0.0565743 0.237274 0.0819413 0.0563774 0.237274 0.100625 0.0495771 0.237274 0.115856 0.0367967 0.237474 0.121753 0.0287221 0.237274 0.12158 0.0286221 0.237474 0.125985 0.0196462 0.237474 0.128577 0.00997323 0.237274 0.12838 0.0099385 0.237474 0.12945 -2.85742e-06 0.237274 0.12925 -2.85742e-06 0.237474 0.11991 -0.0296673 0.237474 0.105958 -0.0449711 0.237474 0.0971173 -0.0504453 0.237274 0.0972065 -0.0506243 0.237274 0.0874756 -0.0543941 0.237474 0.0874209 -0.0542017 0.237274 0.0772177 -0.0563116 0.237274 0.0467935 -0.0506243 0.237274 0.037921 -0.0451307 0.237474 0.0240902 -0.0296673 0.237274 0.030209 -0.0381003 0.237274 0.0164128 -0.0103939 0.238074 0.1271 -2.85742e-06 0.238074 0.126162 -0.0101275 0.237874 0.1273 -2.85742e-06 0.237874 0.123566 -0.0199795 0.238074 0.118847 -0.0290093 0.237874 0.119017 -0.0291146 0.238074 0.112719 -0.0371235 0.237874 0.0871335 -0.0531918 0.237874 0.0771024 -0.055067 0.238074 0.066916 -0.0548678 0.237874 0.0668975 -0.055067 0.238074 0.0474398 -0.0493264 0.238074 0.0312806 -0.0371235 0.238074 0.025153 -0.0290093 0.238074 0.0206207 -0.0199073 0.237874 0.0204342 -0.0199795 0.238074 0.0178381 -0.0101275 0.237874 0.0176415 -0.0101642 0.241674 0.045846 0.0150971 0.241674 0.0312376 -0.00879606 0.241674 0.0339051 -0.0169638 0.241674 0.0550963 -0.036437 0.241674 0.105736 -0.0245135 0.241674 0.0339051 0.0169581 0.241674 0.0312112 -0.00867277 0.241674 0.0744 0.0308402 0.241674 0.0696 0.0308402 0.241674 0.0672 0.0349971 0.241674 0.0676411 0.0414687 0.241674 0.0763588 0.0414687 0.241674 0.0668913 0.0338045 0.241674 0.067843 0.0325971 0.241674 0.0665001 0.0320907 0.241674 0.0589913 0.0338045 0.241674 0.0595205 0.0357795 0.241674 0.0593825 0.0320907 0.241674 0.0550963 0.0300258 0.241674 0.0488451 0.0300258 0.241674 0.0440972 0.0309863 0.241674 0.0769543 0.0300258 0.241674 0.0776378 0.0357795 0.241674 0.0771086 0.0338045 0.241674 0.0776378 0.0318295 0.241674 0.0810586 0.0377545 0.241674 0.0830336 0.0372253 0.241674 0.0844794 0.0318295 0.241674 0.0830336 0.0303837 0.241674 0.0810586 0.0298545 0.241674 0.101278 0.0239026 0.241674 0.101575 0.0293941 0.241674 0.105736 0.0245078 0.241674 0.103832 0.0124766 0.241674 0.104711 0.0133402 0.241674 0.105807 0.0130058 0.241674 0.106468 0.0150971 0.241674 0.107111 0.0174971 0.241674 0.106635 0.0195798 0.241674 0.112789 0.00866706 0.241674 0.102387 0.00708081 0.241674 0.107782 -0.00564072 0.241674 0.112789 -0.00867277 0.241674 0.109228 -0.0110365 0.241674 0.0999108 -0.0133459 0.241674 0.101278 -0.00495719 0.241674 0.102387 -0.00708652 0.241674 0.1137 -2.85742e-06 0.241674 0.110095 -0.0169638 0.241674 0.107782 -0.0124823 0.241674 0.103832 -0.0124823 0.241674 0.102387 -0.0110365 0.241674 0.0844794 -0.0357853 0.241674 0.0810586 -0.0377603 0.241674 0.0763588 -0.0414744 0.241674 0.0769543 -0.036437 0.241674 0.072 -0.0398029 0.241674 0.0427219 -0.0239083 0.241674 0.0346337 -0.00734768 0.241674 0.0342426 -0.00906152 0.241674 0.0347718 -0.0110365 0.241674 0.0355658 -0.0169066 0.241674 0.0472512 0.0207959 0.241674 0.0427219 0.0292752 0.241674 0.0427219 0.0239026 0.241674 0.0338806 0.0169028 0.241674 0.0362176 0.0124766 0.241674 0.0381926 0.0130058 0.241674 0.0416134 0.00708081 0.241674 0.0421426 0.00905581 0.241674 0.0440891 0.0133402 0.241674 0.0416134 0.0110308 0.241674 0.0312376 0.00879035 0.241674 0.0312634 0.00890925 0.241674 0.0427572 -0.0221825 0.241674 0.0386963 -0.0212556 0.241674 0.0353792 -0.019948 0.241674 0.0373644 -0.0195855 0.241674 0.0362176 -0.0124823 0.241674 0.0381926 -0.0130115 0.241674 0.0375321 -0.0151029 0.241674 0.0392891 -0.0133459 0.241674 0.0373136 -0.00521056 0.241674 0.0417514 -0.00734768 0.241674 0.050672 -0.0267266 0.241674 0.0512012 -0.0247516 0.241674 0.0550963 -0.0169066 0.241674 0.050672 -0.0227766 0.241674 0.0488451 -0.0292809 0.241674 0.0595205 -0.0318353 0.241674 0.0744 -0.0308459 0.241674 0.0761569 -0.0326029 0.241674 0.0768 -0.0350029 0.241674 0.0761569 -0.0374029 0.241674 0.072 -0.0302029 0.241674 0.0649163 -0.0303895 0.241674 0.0663621 -0.0318353 0.241674 0.067843 -0.0326029 0.241674 0.067843 -0.0374029 0.241674 0.0649163 -0.0372311 0.241674 0.0609663 -0.0372311 0.241674 0.0595205 -0.0357853 0.241674 0.0589913 -0.0338103 0.241674 0.0790836 -0.0303895 0.241674 0.0810586 -0.0298603 0.241674 0.0999027 -0.030992 0.241674 0.101278 -0.0292809 0.241674 0.101278 -0.0239083 0.241674 0.0947737 -0.0281724 0.241674 0.0933279 -0.0267266 0.241674 0.0919 -0.0261568 0.241674 0.0927987 -0.0247516 0.241674 0.0889037 -0.0239083 0.241674 0.101278 0.0292752 0.241674 0.0959054 0.0292752 0.241674 0.0967487 0.0286959 0.241674 0.0889037 0.0239026 0.241674 0.0933279 0.0267209 0.241674 0.0941782 0.0292337 0.241674 0.0931899 0.023032 0.241674 0.100169 0.0267209 0.241674 0.0993181 0.0212499 0.241674 0.0992115 0.0216576 0.241674 0.0976277 0.0208949 0.241674 0.0943 -0.0303137 0.241674 0.0959054 -0.0292809 0.241674 0.09285 -0.0361161 0.241674 0.0889037 -0.036437 0.241674 0.0895 -0.0351137 0.241674 0.0871 -0.0344707 0.241674 0.085343 -0.0327137 0.241674 0.085343 -0.0279137 0.241674 0.0809043 -0.0292809 0.241674 0.0472512 -0.0287016 0.241674 0.0452762 -0.0281724 0.241674 0.0427219 -0.0292809 0.241674 0.0438304 -0.0227766 0.241674 0.0452762 -0.0213308 0.241674 0.0488451 -0.0169066 0.241674 0.045846 -0.0151029 0.241674 0.0488451 -0.00495719 0.241674 0.03125 0.00495148 0.241674 0.0303 -2.85742e-06 0.241674 0.03125 -0.00495719 0.241674 0.0427219 0.00495148 0.241674 0.0346 0.00415406 0.241674 0.0355658 0.00495148 0.241674 0.032843 0.00239714 0.241674 0.0413246 -0.0020855 0.241674 0.0418 -2.85742e-06 0.241674 0.0411569 0.00239714 0.241674 0.0399927 -0.00375565 0.241674 0.0355658 -0.00495719 0.241674 0.0340072 -0.00375565 0.241674 0.0959054 0.0169008 0.241674 0.0871 0.0261511 0.241674 0.0847 0.030308 0.241674 0.0850086 0.0338045 0.241674 0.0871 0.034465 0.241674 0.0844794 0.0357795 0.241674 0.09285 0.0361104 0.241674 0.0919 0.034465 0.241674 0.0936569 0.032708 0.241674 0.0959054 0.0300258 0.241674 0.0943 0.030308 0.241674 0.0355658 0.0169008 0.241674 0.0368891 0.0174971 0.241674 0.0375321 0.0198971 0.241674 0.038264 0.0245078 0.241674 0.0392891 0.0216541 0.241674 0.0438304 0.0227709 0.241674 0.0452762 0.0213251 0.241674 0.0464891 0.0174971 0.241674 0.107111 -0.0175029 0.241674 0.102311 -0.0223029 0.241674 0.100169 -0.0227766 0.241674 0.0999108 -0.0216598 0.241674 0.0981539 -0.0199029 0.241674 0.0959054 -0.0169066 0.241674 0.0975108 -0.0175029 0.241674 0.0431466 0.0301032 0.241674 0.0488451 0.0292752 0.241674 0.0981539 -0.0151029 0.241674 0.0959054 0.00495148 0.241674 0.101278 0.00495148 0.241674 0.0959054 0.00890148 0.241674 0.101278 0.00890148 0.241674 0.101857 0.00905581 0.241674 0.0427219 0.00890148 0.241674 0.0488451 0.00495148 0.241674 0.0427219 -0.00495719 0.241674 0.0440891 -0.0133459 0.241674 0.0401676 -0.0124823 0.241674 0.0889037 -0.0169066 0.241674 0.0889037 -0.00495719 0.241674 0.0889037 0.00495148 0.241674 0.0959054 -0.00495719 0.241674 0.0889037 0.0169008 0.241674 0.0958697 0.0208949 0.241674 0.050672 0.0227709 0.241674 0.0488451 0.0169008 0.241674 0.0550963 0.00890148 0.241674 0.0550963 0.00495148 0.241674 0.0488451 0.00890148 0.241674 0.0889037 0.00890148 0.241674 0.0809043 -0.00495719 0.241674 0.0769543 -0.0292809 0.241674 0.0769543 -0.0239083 0.241674 0.0809043 -0.0239083 0.241674 0.0809043 -0.0169066 0.241674 0.0769543 0.00495148 0.241674 0.0809043 0.00495148 0.241674 0.0769543 0.0169008 0.241674 0.0809043 0.00890148 0.241674 0.0809043 0.0169008 0.241674 0.0769543 0.0239026 0.241674 0.0809043 0.0239026 0.241674 0.0769543 0.0292752 0.241674 0.0809043 0.0292752 0.241674 0.085343 0.027908 0.241674 0.072 0.0301971 0.241674 0.0638203 0.0299536 0.241674 0.0550963 0.0292752 0.241674 0.0550963 0.0239026 0.241674 0.0769543 0.00890148 0.241674 0.0550963 0.0169008 0.241674 0.0769543 -0.00495719 0.241674 0.0550963 -0.00495719 0.241674 0.0769543 -0.0169066 0.241674 0.0550963 -0.0239083 0.241674 0.0550963 -0.0292809 0.229366 0.0672446 0.0657239 0.230021 0.0750851 0.0640214 0.229498 0.0821572 0.0647413 0.229694 0.0813564 0.0643187 0.229446 0.061954 0.0649026 0.229987 0.0623607 0.0634625 0.229886 0.061997 0.0636847 0.229694 0.0626435 0.0643187 0.230021 0.0689148 0.0640214 0.230021 0.0720004 0.0640957 0.229366 0.072 0.0658957 0.228239 0.0623595 0.0662715 0.228731 0.0623943 0.0660318 0.228239 0.0816404 0.0662715 0.228994 0.0815727 0.0658055 0.228994 0.0767988 0.0663247 0.229366 0.0814859 0.0652094 0.229366 0.0767554 0.0657239 0.228994 0.0672011 0.0663247 0.228994 0.0624273 0.0658055 0.228994 0.072 0.0664981 0.228415 0.0816311 0.0662072 0.228415 0.0623688 0.0662072 0.228415 0.0671718 0.0667296 0.228415 0.072 0.066904 0.227721 0.0671615 0.0668723 0.227721 0.072 0.0670471 0.228415 0.0768281 0.0667296 0.224574 0.0831183 0.0614494 0.224774 0.0612231 0.0613072 0.224574 0.0608816 0.0614494 0.224774 0.0609172 0.0612526 0.224774 0.0840085 0.0663696 0.224574 0.06799 0.0671275 0.224574 0.060027 0.0661728 0.224774 0.067978 0.0673271 0.224774 0.0599914 0.0663696 0.224774 0.0597613 0.0613052 0.224574 0.0598146 0.0614979 0.224574 0.0580568 0.06392 0.224574 0.0590447 0.0657535 0.224574 0.0584229 0.065089 0.224774 0.0589272 0.0659153 0.224774 0.0581654 0.0650444 0.224774 0.0842101 0.0612975 0.224774 0.0852124 0.0618157 0.224774 0.0859008 0.0627097 0.224774 0.08086 0.0609061 0.224774 0.0757118 0.0621364 0.224774 0.0682881 0.0621364 0.224774 0.072 0.0615471 0.224774 0.0631399 0.0609061 0.224574 0.0583415 0.0649495 0.222664 0.0580927 0.0633834 0.222623 0.0582021 0.062982 0.222504 0.0589993 0.0619025 0.224574 0.0588743 0.0620046 0.222576 0.0584221 0.0625344 0.224574 0.058247 0.062869 0.222427 0.0608816 0.0614494 0.222449 0.0598513 0.0614881 0.224574 0.0589994 0.0619024 0.224574 0.084159 0.0614908 0.222499 0.0849446 0.061861 0.224574 0.0850842 0.0619692 0.224574 0.0857196 0.0627944 0.224574 0.0839729 0.0661728 0.224574 0.0760099 0.0671275 0.2229 0.06799 0.0671275 0.224574 0.0682762 0.062336 0.222427 0.0682762 0.062336 0.224574 0.0757237 0.062336 0.222427 0.0757237 0.062336 0.222427 0.0831183 0.0614494 0.221231 0.0599566 0.0649201 0.220979 0.0592191 0.0636744 0.220834 0.0595359 0.0632825 0.220796 0.0602424 0.063758 0.220782 0.0604635 0.0637605 0.220952 0.0593314 0.0629445 0.220827 0.0599418 0.062623 0.220779 0.0606751 0.0625906 0.220726 0.0600213 0.0630351 0.220692 0.0606107 0.0629467 0.220684 0.0605988 0.0630125 0.221498 0.0585256 0.0638934 0.221057 0.0596922 0.0643857 0.22147 0.0597036 0.0653115 0.22289 0.0593601 0.0659474 0.222078 0.059875 0.0615227 0.22252 0.0588409 0.0620344 0.222881 0.0591318 0.0658138 0.222828 0.0584603 0.0651467 0.22256 0.0585174 0.0651923 0.222737 0.0580759 0.0641322 0.22247 0.0581474 0.0643818 0.222722 0.0580598 0.0639738 0.222607 0.0582686 0.0628198 0.222288 0.0586145 0.0652124 0.221905 0.058401 0.0645238 0.222183 0.058246 0.0644602 0.221761 0.0583173 0.0637583 0.221696 0.0598508 0.0616641 0.221619 0.0608464 0.061644 0.222364 0.0581022 0.0634963 0.222056 0.0581753 0.0636233 0.222253 0.0583922 0.0626451 0.221921 0.0584247 0.0627985 0.221792 0.0589975 0.0620993 0.222151 0.0590029 0.0619446 0.221861 0.0594373 0.0656139 0.222207 0.0600525 0.0660319 0.221132 0.0590892 0.0641305 0.221392 0.0593514 0.0649989 0.221565 0.0591283 0.0650941 0.221284 0.058789 0.06402 0.221778 0.0589252 0.0651636 0.222383 0.060041 0.0660958 0.222358 0.0592388 0.0657866 0.221653 0.0586087 0.0645679 0.221603 0.0585288 0.0629909 0.221327 0.0587046 0.0632118 0.221452 0.0590503 0.0623267 0.221162 0.0591641 0.062616 0.221036 0.0598833 0.0622329 0.221336 0.0598524 0.0619039 0.220782 0.0835364 0.0637605 0.220807 0.0838358 0.0637758 0.220726 0.0839788 0.0630353 0.220834 0.0844641 0.0632826 0.220879 0.0841033 0.0639268 0.221627 0.0838751 0.0656324 0.221132 0.0849106 0.0641299 0.221275 0.0848615 0.0645886 0.221497 0.0854742 0.0638925 0.221392 0.0846484 0.0649989 0.221099 0.0842985 0.0645051 0.22102 0.0842976 0.0642828 0.220827 0.0840583 0.0626232 0.221162 0.0848359 0.0626162 0.220993 0.0832512 0.0621838 0.220982 0.0842711 0.0641833 0.220979 0.0847806 0.0636741 0.220952 0.0846685 0.0629446 0.220692 0.0833892 0.0629467 0.222576 0.0855774 0.0625337 0.222604 0.0857181 0.0627911 0.222516 0.0851186 0.0619984 0.222151 0.0849972 0.0619447 0.222445 0.0840473 0.0614641 0.22205 0.0831256 0.0614898 0.222078 0.0841253 0.0615228 0.222664 0.085907 0.0633823 0.222364 0.0858975 0.0634952 0.222706 0.0859456 0.0638111 0.222752 0.0858967 0.0642933 0.22256 0.0854824 0.0651925 0.222809 0.0856724 0.0649232 0.222878 0.0849245 0.0657754 0.222207 0.0839474 0.0660319 0.221861 0.0845623 0.0656141 0.222288 0.0853853 0.0652126 0.221905 0.085599 0.0645232 0.222056 0.0858245 0.0636222 0.221761 0.0856825 0.0637573 0.221603 0.0854708 0.0629903 0.221452 0.0849497 0.0623268 0.221336 0.0841479 0.0619041 0.221291 0.0831928 0.061861 0.221696 0.0841495 0.0616642 0.221792 0.0850025 0.0620994 0.222253 0.0856073 0.0626445 0.22192 0.0855749 0.0627979 0.22247 0.0858526 0.0643811 0.222183 0.0857541 0.0644596 0.222358 0.0847608 0.0657868 0.22189 0.0839158 0.0658574 0.22147 0.0842961 0.0653116 0.221778 0.0850746 0.0651637 0.221653 0.0853913 0.0645675 0.221327 0.0852951 0.0632113 0.221036 0.0841169 0.062233 0.221627 0.0680227 0.0665794 0.221255 0.0677841 0.0659611 0.221627 0.0601248 0.0656324 0.221498 0.0601522 0.0654811 0.221255 0.0759413 0.0659781 0.2229 0.060027 0.0661728 0.2229 0.0760099 0.0671275 0.221627 0.0759772 0.0665794 0.222207 0.0760014 0.0669846 0.22189 0.0600841 0.0658574 0.222207 0.0679985 0.0669846 0.222383 0.083959 0.0660958 0.2229 0.0839729 0.0661728 0.220692 0.0681855 0.0638549 0.220993 0.0757682 0.0630809 0.220692 0.0758145 0.0638549 0.220779 0.0833248 0.0625907 0.220993 0.0607487 0.0621838 0.220993 0.0682317 0.0630809 0.221291 0.0608071 0.061861 0.221619 0.0831535 0.061644 0.221619 0.0757355 0.0625334 0.221619 0.0682644 0.0625334 0.22205 0.0608743 0.0614898 0.221019 0.0603478 0.0644001 0.22094 0.0597794 0.0640748 0.220854 0.0599658 0.0638702 0.22116 0.0597592 0.0646848 0.221057 0.0596922 0.0643857 0.22102 0.0597023 0.0642831 0.221255 0.0837679 0.0650397 0.221184 0.0841956 0.0647623 0.221242 0.0839759 0.0649645 0.220855 0.0840353 0.0638711 0.221019 0.0836522 0.0644001 0.220782 0.0761321 0.0646638 0.221255 0.0762149 0.0659612 0.220782 0.0758638 0.0646804 0.220782 0.0681361 0.0646804 0.220782 0.067867 0.0646637 0.221255 0.0680586 0.0659781 0.221255 0.060232 0.0650397 0.221231 0.0599566 0.0649201 0.222828 0.0855395 0.0651469 0.224574 0.0856919 0.064885 0.222801 0.0857163 0.0648349 0.224574 0.0859456 0.0638111 0.224574 0.0849845 0.0657319 0.224774 0.0858708 0.0649745 0.224774 0.0851044 0.065892 0.227864 0.0603453 0.0648828 0.224974 0.0600797 0.0637264 0.227749 0.0613282 0.0659755 0.224774 0.0598797 0.0637264 0.224974 0.0603736 0.0649394 0.224974 0.0611902 0.0658834 0.224774 0.061074 0.0660461 0.224974 0.060996 0.0617223 0.224974 0.0603196 0.0626246 0.224774 0.0619301 0.0609909 0.224774 0.0823251 0.0610788 0.224974 0.0829485 0.0616756 0.224974 0.0833506 0.0620849 0.224774 0.0840906 0.0633162 0.224974 0.0834632 0.0652141 0.224974 0.083732 0.0647073 0.224974 0.0839064 0.0639973 0.224774 0.0830827 0.0612526 0.224774 0.0827768 0.0613072 0.224774 0.0839178 0.0647813 0.224774 0.0861456 0.0638111 0.224774 0.0835076 0.061961 0.224774 0.058063 0.0627905 0.224774 0.057857 0.0639291 0.224774 0.0601958 0.065031 0.224774 0.072 0.0672471 0.224774 0.0760219 0.0673271 0.224774 0.0830357 0.0659638 0.224774 0.0608651 0.061571 0.224774 0.0587426 0.061854 0.224774 0.0601377 0.0625414 0.224974 0.072 0.0617471 0.224974 0.0808888 0.061104 0.224974 0.0631111 0.061104 0.228377 0.0690278 0.0616756 0.228377 0.072 0.0617471 0.224774 0.0623194 0.0665467 0.224774 0.0816805 0.0665467 0.224974 0.0829118 0.0658068 0.22782 0.0834198 0.0652762 0.224974 0.0837199 0.0627158 0.224974 0.0838926 0.063345 0.228252 0.0830817 0.0617922 0.22811 0.0837707 0.0628487 0.228349 0.0819724 0.0611711 0.224974 0.0822511 0.0612646 0.228377 0.0631111 0.061104 0.228354 0.0621351 0.061144 0.224974 0.0619862 0.0611828 0.228169 0.060439 0.062394 0.228135 0.0603081 0.0626501 0.230112 0.0628921 0.0626098 0.22981 0.0689919 0.062421 0.228753 0.0808947 0.0611446 0.228377 0.0749721 0.0616756 0.229185 0.0749816 0.0618731 0.229185 0.0809172 0.0612997 0.229185 0.0690183 0.0618731 0.228753 0.0631052 0.0611446 0.230024 0.0810557 0.0622513 0.22981 0.075008 0.062421 0.230112 0.0689546 0.0631954 0.230021 0.0812268 0.0634281 0.230112 0.0811078 0.0626098 0.230112 0.0750453 0.0631954 0.230021 0.0627731 0.0634281 0.224974 0.0816517 0.0663488 0.227721 0.0816517 0.0663488 0.227721 0.0768384 0.0668723 0.224974 0.072 0.0670471 0.224974 0.0623482 0.0663488 0.229402 0.0828034 0.0646072 0.229804 0.0821555 0.0638887 0.229256 0.0825359 0.0650974 0.229465 0.0820923 0.0648442 0.229939 0.0818499 0.0635618 0.23007 0.0817951 0.0627237 0.23001 0.0814619 0.0634244 0.22992 0.0819119 0.063605 0.229578 0.0828729 0.0640559 0.229213 0.0834433 0.0638384 0.229024 0.0833327 0.0646044 0.228654 0.0838019 0.0635807 0.228347 0.0838792 0.0634565 0.227735 0.0823915 0.0661278 0.227748 0.0826533 0.0659869 0.229158 0.0821001 0.0654651 0.228767 0.0823554 0.0657765 0.22887 0.0829555 0.0652766 0.228271 0.0825476 0.0659559 0.22836 0.0832638 0.0653363 0.229691 0.0822553 0.0641876 0.22964 0.0822645 0.0643278 0.228771 0.0835414 0.0645675 0.228494 0.0836982 0.0645095 0.228269 0.0829487 0.0616758 0.228276 0.0828881 0.0616276 0.229968 0.0818886 0.0623148 0.22981 0.0809962 0.0618425 0.22976 0.0819604 0.061927 0.229512 0.0809489 0.0615177 0.229459 0.0820025 0.0615995 0.228377 0.0808888 0.061104 0.228718 0.0819927 0.0612178 0.228169 0.0835613 0.0623947 0.228623 0.082938 0.0617132 0.229141 0.0834396 0.0628472 0.228982 0.0829382 0.0618679 0.229417 0.0832567 0.0630618 0.229612 0.0827546 0.0623784 0.229322 0.0828779 0.0620933 0.229099 0.0820121 0.0613599 0.228731 0.0816056 0.0660318 0.2294 0.0818722 0.0650583 0.228088 0.0833613 0.0653196 0.228207 0.0837992 0.0644346 0.227951 0.0838894 0.0641295 0.228047 0.0838925 0.0633441 0.228492 0.0835874 0.0625065 0.228824 0.0835499 0.0626586 0.22895 0.0836557 0.0637107 0.229765 0.0827275 0.0635061 0.22994 0.0823607 0.0630313 0.229822 0.0825763 0.0627007 0.227721 0.0623482 0.0663488 0.23007 0.0622046 0.0627238 0.229158 0.0619 0.0654652 0.229464 0.0619076 0.0648443 0.229402 0.0611964 0.0646069 0.229256 0.0614642 0.0650975 0.229579 0.061755 0.0645023 0.229691 0.0617447 0.0641872 0.229578 0.0611271 0.0640552 0.229765 0.0612727 0.0635057 0.229822 0.0614235 0.0627008 0.22976 0.0620391 0.0619272 0.230024 0.0629443 0.0622513 0.229742 0.0617759 0.0640503 0.22994 0.0616392 0.0630314 0.229968 0.062111 0.0623149 0.228047 0.0601076 0.0633428 0.228257 0.0609592 0.0617546 0.228623 0.0610618 0.0617133 0.228276 0.0611117 0.0616277 0.228718 0.0620068 0.061218 0.229185 0.0630827 0.0612997 0.228 0.0600797 0.0637264 0.228347 0.0601209 0.0634553 0.227981 0.0600844 0.0638839 0.227925 0.0601536 0.0643479 0.228207 0.0602005 0.064434 0.227842 0.0604494 0.0650765 0.22782 0.0605803 0.0652764 0.228088 0.0606388 0.0653198 0.227754 0.0612417 0.0659193 0.229512 0.063051 0.0615177 0.229459 0.0619971 0.0615996 0.228982 0.0610616 0.061868 0.229322 0.0611219 0.0620934 0.229141 0.0605607 0.0628465 0.22836 0.0607363 0.0653365 0.22887 0.0610445 0.0652767 0.228767 0.0616448 0.0657766 0.229099 0.0619874 0.06136 0.228824 0.0604504 0.0626579 0.228492 0.0604129 0.0625057 0.228655 0.0601981 0.0635795 0.228494 0.0603015 0.0645088 0.228271 0.0614527 0.0659561 0.229366 0.062514 0.0652094 0.229377 0.0622867 0.0651456 0.228772 0.0604584 0.0645669 0.229024 0.060667 0.0646039 0.229213 0.0605567 0.0638374 0.22895 0.0603443 0.0637095 0.229417 0.0607435 0.0630612 0.229612 0.0612453 0.0623785 0.22981 0.0630037 0.0618425 0.222427 0.0930973 0.0587756 0.224574 0.0999445 0.0558461 0.224574 0.106394 0.0521223 0.224574 0.0936585 0.0634215 0.222828 0.0928491 0.0631882 0.224574 0.0926476 0.0630768 0.224574 0.0918863 0.0623276 0.224574 0.0916365 0.06026 0.222607 0.0915196 0.0612689 0.224574 0.0921975 0.0593511 0.222449 0.0922244 0.0593242 0.222504 0.0916937 0.0601091 0.2229 0.115457 0.0513204 0.2229 0.109038 0.0561287 0.224574 0.109038 0.0561287 0.2229 0.0947189 0.0632934 0.224574 0.0947189 0.0632934 0.224774 0.111483 0.0477329 0.224774 0.102775 0.053301 0.224774 0.099855 0.0556672 0.224774 0.0938393 0.0577901 0.222878 0.116082 0.0505005 0.224574 0.116083 0.0504983 0.224774 0.116265 0.0505824 0.224974 0.0931863 0.0598235 0.227841 0.0945441 0.062137 0.224974 0.0943491 0.0620168 0.227811 0.0948497 0.0622829 0.224974 0.0948501 0.0622831 0.224974 0.0968172 0.0622853 0.227749 0.0957471 0.062472 0.224974 0.0955498 0.0624579 0.224774 0.0929863 0.0598235 0.224974 0.093495 0.0610647 0.224974 0.0939164 0.06165 0.228377 0.105413 0.0519262 0.224974 0.102875 0.0534742 0.224774 0.0968912 0.0624711 0.224774 0.105625 0.0582374 0.224974 0.113534 0.0526335 0.227748 0.114221 0.0518193 0.22782 0.114529 0.0508206 0.224974 0.114536 0.0507451 0.224974 0.113973 0.0489116 0.228047 0.113973 0.048911 0.224974 0.114311 0.0494697 0.224974 0.114515 0.0501717 0.228377 0.110251 0.0484729 0.228252 0.112495 0.0479724 0.224974 0.112874 0.0480914 0.22811 0.113619 0.0485429 0.224974 0.113509 0.0484531 0.228363 0.0942044 0.0577355 0.22835 0.0939657 0.0579464 0.224974 0.0939795 0.0579328 0.224974 0.0933926 0.0587983 0.229512 0.11051 0.048801 0.229185 0.110374 0.0486281 0.228753 0.110277 0.048505 0.229185 0.10552 0.0520925 0.228377 0.102875 0.0534742 0.228377 0.100265 0.0548983 0.228377 0.0948555 0.0573617 0.22981 0.110714 0.0490587 0.229185 0.100356 0.0550741 0.229185 0.0949286 0.0575454 0.22981 0.100607 0.0555618 0.22981 0.105817 0.0525537 0.230112 0.100962 0.0562511 0.22981 0.0951317 0.0580549 0.230112 0.106236 0.0532058 0.230021 0.10134 0.0569863 0.227721 0.101247 0.060332 0.227721 0.0968172 0.0622853 0.227721 0.105525 0.0580641 0.227721 0.109628 0.0554935 0.224974 0.105525 0.0580641 0.228169 0.113211 0.0482544 0.228269 0.112321 0.047938 0.229402 0.113661 0.0505494 0.229804 0.112741 0.0502511 0.22964 0.113055 0.0505769 0.229498 0.113168 0.0509886 0.22994 0.11249 0.049406 0.229939 0.112313 0.0501207 0.230112 0.111194 0.0496673 0.23001 0.111908 0.0501958 0.230021 0.111706 0.0503165 0.229765 0.113045 0.0496338 0.229213 0.113831 0.0495637 0.229578 0.113446 0.0500372 0.22895 0.113951 0.0493468 0.228771 0.11428 0.050146 0.228654 0.114013 0.0491612 0.229256 0.113674 0.0511077 0.22887 0.114127 0.051053 0.228271 0.114114 0.0518453 0.228088 0.1145 0.0508874 0.229024 0.114118 0.0502823 0.228494 0.114387 0.0500173 0.22836 0.114424 0.0509506 0.228207 0.114437 0.049902 0.230024 0.110969 0.049383 0.229459 0.111464 0.0483451 0.228718 0.111264 0.0480195 0.228824 0.113333 0.0484886 0.228982 0.112408 0.0481097 0.229141 0.113332 0.0487071 0.229417 0.113281 0.0489844 0.229612 0.112504 0.0486436 0.22976 0.111591 0.0486498 0.229822 0.112511 0.0490118 0.229322 0.112469 0.048335 0.229099 0.111352 0.0481328 0.228623 0.112331 0.0479758 0.228349 0.111223 0.0479892 0.227721 0.113534 0.0526335 0.228239 0.113486 0.0525722 0.227735 0.114065 0.0520722 0.228767 0.113858 0.051786 0.228415 0.113446 0.0525212 0.228731 0.113336 0.052382 0.229158 0.113481 0.051644 0.228994 0.113194 0.0522025 0.229366 0.112821 0.0517296 0.227951 0.114363 0.0495927 0.228347 0.114017 0.049015 0.228492 0.11329 0.0483381 0.229968 0.111723 0.0490215 0.23007 0.111846 0.0494224 0.230021 0.0957247 0.0595434 0.23007 0.0948802 0.0592178 0.228994 0.0966139 0.0617752 0.229464 0.0956833 0.0612025 0.229213 0.09401 0.0610061 0.229402 0.0949487 0.0613526 0.229579 0.0953801 0.0609828 0.229578 0.0946128 0.0609095 0.229691 0.0952137 0.060715 0.229612 0.0938768 0.0593984 0.229822 0.0941923 0.0595883 0.229968 0.0945947 0.0589104 0.229765 0.0944641 0.0603608 0.22994 0.0945444 0.0597668 0.230112 0.0954186 0.0587752 0.230024 0.0952846 0.0584387 0.228753 0.0948706 0.0573997 0.227925 0.0939161 0.0616497 0.228718 0.0939561 0.0580125 0.228283 0.0934193 0.058737 0.228168 0.0931863 0.0598235 0.22812 0.0932174 0.0602284 0.228062 0.0933306 0.0606859 0.228207 0.0939997 0.0617008 0.227963 0.0937084 0.0614028 0.228271 0.0958452 0.0623929 0.229158 0.0959872 0.0617441 0.228767 0.0959218 0.0621414 0.22887 0.0951521 0.0620086 0.228772 0.0942895 0.061687 0.22895 0.093762 0.0610015 0.228982 0.0934625 0.0590481 0.229099 0.0940103 0.0581452 0.228623 0.0933853 0.0589139 0.228492 0.0932196 0.0599247 0.228824 0.0933281 0.0600377 0.228347 0.0934414 0.060893 0.228655 0.0935704 0.060962 0.228494 0.0941246 0.0617151 0.22836 0.094915 0.0622145 0.228088 0.0948222 0.0622489 0.229377 0.0961623 0.0612739 0.229256 0.0954259 0.0616436 0.229024 0.0944888 0.0616147 0.229417 0.0937836 0.0602404 0.229141 0.0935179 0.0601459 0.229322 0.0936274 0.0592131 0.22976 0.0943386 0.0586105 0.229459 0.0941384 0.0583479 0.229512 0.0950102 0.05775 0.23001 0.111908 0.0501958 0.22992 0.112388 0.0501272 0.2294 0.11308 0.0514056 0.229465 0.113164 0.0511101 0.229691 0.112977 0.0504601 0.229742 0.0951722 0.0605808 0.229366 0.096391 0.0612156 0.229446 0.0957526 0.0612299 0.229694 0.0960578 0.0603795 0.229987 0.0953848 0.0597794 0.229886 0.0951809 0.0601537 0.229366 0.104949 0.0570669 0.230021 0.10405 0.0555079 0.230021 0.106684 0.0539012 0.229366 0.108982 0.0545405 0.229694 0.112264 0.0510231 0.228731 0.0966986 0.0619877 0.228994 0.101008 0.0598379 0.229366 0.100745 0.0592959 0.228994 0.10525 0.0575886 0.228994 0.10932 0.0550391 0.228415 0.0967642 0.0621523 0.228239 0.0967882 0.0622126 0.228415 0.101185 0.0602032 0.228415 0.105453 0.0579402 0.228415 0.109547 0.0553751 0.224574 0.112355 0.0476572 0.224774 0.106284 0.0519554 0.224574 0.0930973 0.0587756 0.224774 0.092055 0.0592108 0.224574 0.0916938 0.0601089 0.224774 0.0914472 0.0601954 0.224774 0.0913269 0.0613463 0.224574 0.0915254 0.0613223 0.224574 0.0927878 0.0631569 0.224774 0.113268 0.0469683 0.224574 0.114398 0.0471399 0.224774 0.11444 0.0469442 0.224774 0.115503 0.0474371 0.224574 0.116306 0.0494888 0.224774 0.116506 0.0494888 0.224574 0.115457 0.0513204 0.224774 0.109148 0.0562957 0.224574 0.102092 0.0601387 0.22116 0.093743 0.0621387 0.220979 0.09277 0.0615337 0.220834 0.0928484 0.0610359 0.220854 0.0935147 0.0613299 0.220796 0.093698 0.0610945 0.220726 0.0931451 0.060579 0.220827 0.0928703 0.0602618 0.221036 0.0926245 0.0599532 0.221284 0.0925704 0.0620481 0.22094 0.0934554 0.0616003 0.220952 0.0925024 0.0608454 0.220692 0.0936114 0.0602077 0.220684 0.0936339 0.0602706 0.221778 0.0932601 0.0629703 0.221498 0.092279 0.0620701 0.221327 0.0920931 0.0613904 0.221565 0.0934013 0.0628086 0.222358 0.0938432 0.0633531 0.22289 0.0940287 0.0634316 0.222383 0.0946925 0.0632198 0.222576 0.0915098 0.0609449 0.22252 0.0916225 0.0603025 0.222151 0.0917179 0.0601438 0.222881 0.0937642 0.0634301 0.22256 0.0929213 0.0631991 0.222737 0.0920089 0.0625018 0.222364 0.0917138 0.0619379 0.222722 0.0919157 0.0623726 0.222664 0.0916491 0.0618449 0.222623 0.0915431 0.0614426 0.222288 0.0930155 0.063168 0.221452 0.09195 0.0604509 0.221696 0.092312 0.0594768 0.22247 0.0921956 0.0626821 0.222183 0.0923202 0.0627008 0.222253 0.0915393 0.0610557 0.222056 0.0918405 0.0620113 0.221921 0.0916441 0.0611723 0.221792 0.0917906 0.0602804 0.222078 0.0922622 0.0593424 0.22205 0.0931112 0.0588142 0.22147 0.0940082 0.0627092 0.22189 0.0946106 0.0629918 0.221132 0.0928856 0.0619936 0.221392 0.0935468 0.0626146 0.221861 0.0939288 0.0631043 0.221653 0.0926882 0.0626127 0.221905 0.0924863 0.0626783 0.221761 0.092031 0.0620572 0.221603 0.0918304 0.0612869 0.221162 0.0921932 0.0606446 0.221336 0.0924332 0.0596838 0.220782 0.107688 0.0540826 0.220692 0.100625 0.0572068 0.220779 0.0934891 0.0598671 0.220692 0.107232 0.0533923 0.221291 0.112625 0.0479764 0.220993 0.106805 0.0527452 0.222427 0.106394 0.0521223 0.221619 0.106503 0.0522874 0.222427 0.112355 0.0476572 0.220993 0.0933494 0.0594779 0.220993 0.100278 0.0565134 0.221291 0.0932386 0.0591692 0.221619 0.0931641 0.0589617 0.221619 0.112483 0.0478081 0.221619 0.100033 0.0560229 0.222427 0.0999445 0.0558461 0.221627 0.108735 0.0556704 0.221255 0.114713 0.0504417 0.221627 0.0945334 0.0627766 0.221627 0.101847 0.0596477 0.221498 0.0944815 0.0626318 0.221255 0.101577 0.059109 0.222207 0.0946705 0.0631587 0.2229 0.102092 0.0601387 0.222207 0.102028 0.0600107 0.22189 0.11525 0.0510759 0.222207 0.108959 0.0560093 0.222207 0.115364 0.0512112 0.222383 0.115406 0.0512608 0.220726 0.113893 0.0486003 0.220834 0.114437 0.0485719 0.221184 0.114944 0.0499876 0.221275 0.115434 0.0495042 0.22147 0.115306 0.050413 0.221627 0.115102 0.0509014 0.221132 0.115247 0.0490824 0.221497 0.115617 0.0485951 0.22102 0.114793 0.0495214 0.220979 0.114907 0.0487527 0.221327 0.115121 0.0480947 0.220827 0.113756 0.0482037 0.221036 0.113612 0.0478365 0.220993 0.112837 0.0482267 0.220982 0.11472 0.0494485 0.220952 0.114445 0.048177 0.220692 0.113338 0.0488184 0.220779 0.113104 0.0485423 0.222511 0.1143 0.0471214 0.222151 0.11423 0.0471467 0.22205 0.112381 0.0476885 0.222444 0.113152 0.0472101 0.222078 0.113264 0.0472172 0.222752 0.116183 0.0487309 0.222817 0.116306 0.0494888 0.222576 0.115027 0.0473667 0.222253 0.115108 0.0474476 0.222614 0.115369 0.0475866 0.222664 0.115736 0.0479368 0.222727 0.116085 0.0484828 0.222828 0.1163 0.0496487 0.222358 0.115946 0.0505922 0.221778 0.115906 0.0498957 0.221905 0.11604 0.0490789 0.222183 0.116143 0.0489462 0.22192 0.115157 0.0475967 0.221696 0.113355 0.0473276 0.221792 0.114312 0.047278 0.222364 0.115785 0.0480393 0.222056 0.115785 0.0481858 0.22247 0.116189 0.048829 0.22256 0.116274 0.0497168 0.222288 0.1162 0.0497827 0.221861 0.115688 0.0505419 0.221242 0.114855 0.0502725 0.221392 0.115455 0.0499661 0.221653 0.115882 0.049221 0.221761 0.115729 0.0483738 0.221603 0.115163 0.0478154 0.221162 0.114426 0.0478088 0.221452 0.11438 0.0475013 0.221336 0.113474 0.0475361 0.220782 0.0938907 0.060986 0.220782 0.100754 0.0580665 0.221019 0.0941103 0.0615978 0.221231 0.0940316 0.0622438 0.221057 0.0935354 0.0619132 0.22102 0.0934928 0.0618193 0.220807 0.114139 0.0493131 0.220855 0.11436 0.049296 0.220879 0.114447 0.0493101 0.221019 0.114293 0.0499456 0.221099 0.114905 0.0497134 0.220782 0.113872 0.0494495 0.220782 0.107912 0.0539341 0.221255 0.108632 0.0550162 0.221255 0.108404 0.0551676 0.220782 0.100995 0.0579464 0.221255 0.101331 0.0592315 0.221255 0.0943299 0.0622096 0.224574 0.113317 0.0471622 0.222499 0.114142 0.0471005 0.224574 0.11538 0.047595 0.224574 0.116062 0.0484348 0.224974 0.0948555 0.0573617 0.224774 0.0933219 0.0584816 0.224774 0.110127 0.0483158 0.224974 0.111511 0.0479308 0.224774 0.111988 0.0477048 0.224974 0.112321 0.047938 0.224974 0.114355 0.051534 0.224774 0.112226 0.0475046 0.224774 0.11413 0.0487877 0.224774 0.114713 0.0501429 0.224774 0.116242 0.048347 0.224774 0.112948 0.0479056 0.224774 0.0930298 0.0585873 0.224774 0.0932082 0.0587209 0.224774 0.11454 0.0516081 0.224774 0.115586 0.0514731 0.224774 0.113658 0.0527905 0.224774 0.102182 0.0603176 0.224774 0.0947865 0.0634816 0.224774 0.0955281 0.0626568 0.224774 0.0936377 0.0636204 0.224774 0.0925425 0.063247 0.224774 0.0942369 0.0621824 0.224774 0.0917178 0.0624353 0.224774 0.0933183 0.0611584 0.224774 0.0947814 0.0571759 0.224974 0.110251 0.0484729 0.224774 0.0305571 0.0469304 0.224574 0.028697 0.0475374 0.224774 0.0292158 0.0470417 0.224574 0.0305214 0.0471272 0.224574 0.0297885 0.0471084 0.224574 0.0292834 0.0472299 0.224774 0.0281099 0.0478087 0.224574 0.0282626 0.047938 0.224574 0.0278353 0.0502996 0.224574 0.0276959 0.0495798 0.224574 0.0277325 0.0490615 0.224574 0.0517336 0.0592839 0.224574 0.0522941 0.0600806 0.224774 0.0524776 0.0600011 0.224774 0.0526918 0.0610345 0.224774 0.0492185 0.0571759 0.224774 0.0377158 0.0519554 0.224774 0.0327298 0.047772 0.22289 0.0280784 0.0507918 0.224574 0.0285433 0.0513204 0.224574 0.0279391 0.0484325 0.222828 0.0276995 0.0496485 0.222737 0.0278738 0.0485777 0.222504 0.0297883 0.0471084 0.22252 0.0295853 0.0471434 0.222607 0.0286969 0.0475375 0.222437 0.0515306 0.0591135 0.222496 0.0522605 0.0600065 0.222584 0.0524918 0.0610345 0.224574 0.034962 0.0561287 0.2229 0.0285433 0.0513204 0.222427 0.031645 0.0476572 0.222427 0.0440554 0.0558461 0.222427 0.0509026 0.0587756 0.22147 0.0286938 0.0504129 0.220979 0.0290928 0.0487528 0.220726 0.0301071 0.0486003 0.221162 0.0295743 0.0478088 0.220952 0.029555 0.0481769 0.220993 0.0311628 0.0482267 0.220827 0.0302444 0.0482037 0.221132 0.0287522 0.0490829 0.22094 0.0293778 0.0493797 0.221327 0.0288785 0.048095 0.220834 0.0295631 0.0485718 0.221653 0.0281174 0.0492215 0.22116 0.0290553 0.0498979 0.222358 0.0280538 0.0505919 0.222078 0.0307366 0.0472174 0.222576 0.0289726 0.047367 0.222253 0.0288914 0.047448 0.222151 0.0297704 0.0471467 0.222449 0.0307335 0.0471755 0.222881 0.0279475 0.050562 0.22256 0.0277262 0.0497166 0.22247 0.027811 0.0488296 0.222722 0.0279391 0.0484324 0.222664 0.0282628 0.0479377 0.222623 0.0285582 0.0476447 0.221921 0.0288428 0.0475971 0.221792 0.0296884 0.0472779 0.222183 0.0278572 0.0489468 0.222364 0.0282146 0.0480402 0.222056 0.0282144 0.0481867 0.221696 0.030645 0.0473277 0.22205 0.0316185 0.0476885 0.221619 0.0315173 0.0478081 0.221861 0.028312 0.0505416 0.221627 0.0288981 0.0509014 0.222207 0.0286358 0.0512112 0.221392 0.0285451 0.049966 0.221284 0.0285475 0.0488371 0.221565 0.0283043 0.049937 0.222288 0.0278002 0.0497825 0.221778 0.0280937 0.0498955 0.221905 0.0279596 0.0490794 0.221761 0.0282699 0.0483746 0.221498 0.0283827 0.0485958 0.221603 0.0288367 0.0478157 0.221452 0.0296204 0.0475012 0.221336 0.0305265 0.0475362 0.221036 0.0303887 0.0478365 0.221392 0.050453 0.0626145 0.220782 0.0501092 0.060986 0.220692 0.0503886 0.0602077 0.220726 0.0508549 0.0605792 0.220834 0.0511515 0.061036 0.220855 0.0504859 0.0613313 0.220879 0.050517 0.0614135 0.221275 0.0508426 0.0623657 0.221627 0.0494665 0.0627766 0.221255 0.04967 0.0622096 0.221653 0.0513121 0.0626124 0.221099 0.0503968 0.0620119 0.221132 0.0511145 0.0619931 0.221162 0.0518067 0.0606448 0.221036 0.0513756 0.0599535 0.220979 0.0512298 0.0615333 0.220982 0.050534 0.0617196 0.220952 0.0514975 0.0608455 0.220827 0.0511298 0.0602621 0.222253 0.0524606 0.061055 0.222446 0.0517263 0.0592771 0.221619 0.0508358 0.0589617 0.222078 0.051738 0.0593426 0.22256 0.0510784 0.0631992 0.222358 0.0501563 0.0633531 0.222207 0.0493294 0.0631587 0.221861 0.0500708 0.0631042 0.22147 0.0499916 0.0627092 0.221778 0.0507396 0.0629703 0.222183 0.0516801 0.0627003 0.221603 0.0521695 0.0612862 0.221452 0.05205 0.0604511 0.221792 0.0522094 0.0602805 0.221696 0.0516882 0.0594771 0.222151 0.0522821 0.0601439 0.22192 0.0523558 0.0611716 0.222364 0.0522866 0.0619368 0.222056 0.0521598 0.0620103 0.22247 0.0518047 0.0626817 0.222288 0.0509843 0.0631681 0.221905 0.051514 0.0626779 0.221497 0.0517213 0.0620693 0.221761 0.0519693 0.0620563 0.221327 0.0519068 0.0613898 0.221336 0.0515669 0.0596841 0.221291 0.0507613 0.0591692 0.221498 0.0289975 0.050784 0.221255 0.035367 0.0550157 0.221255 0.0355962 0.0551676 0.2229 0.034962 0.0561287 0.222383 0.0285938 0.0512608 0.2229 0.0419075 0.0601387 0.221627 0.0421532 0.0596477 0.22189 0.0493893 0.0629917 0.222207 0.0419716 0.0600107 0.22189 0.0287504 0.0510759 0.221627 0.0352644 0.0556704 0.222207 0.0350409 0.0560093 0.222383 0.0493074 0.0632198 0.2229 0.049281 0.0632934 0.22205 0.0508887 0.0588142 0.220782 0.0432451 0.0580662 0.221619 0.0374967 0.0522874 0.220993 0.0437215 0.0565134 0.220684 0.0306186 0.0488694 0.220692 0.0306618 0.0488184 0.220692 0.0433745 0.0572068 0.220692 0.0367676 0.0533923 0.220993 0.0506505 0.0594779 0.220779 0.0505108 0.0598672 0.220779 0.0308956 0.0485423 0.220993 0.0371946 0.0527452 0.221291 0.0313748 0.0479764 0.221619 0.0439669 0.0560229 0.222427 0.0376056 0.0521223 0.220782 0.0301274 0.0494495 0.221019 0.0297074 0.0499456 0.22094 0.0293778 0.0493797 0.220854 0.0296416 0.0492958 0.220796 0.0299371 0.0493369 0.221231 0.0291086 0.0502004 0.221057 0.0291468 0.0496054 0.22102 0.0292068 0.0495216 0.221255 0.0426682 0.0592311 0.221099 0.0503968 0.0620119 0.221184 0.0501791 0.0621832 0.221242 0.0498878 0.0622485 0.220807 0.0503608 0.061149 0.220879 0.050517 0.0614135 0.220982 0.050534 0.0617196 0.22102 0.0505072 0.061819 0.221019 0.0498896 0.0615978 0.220782 0.0430045 0.0579464 0.221255 0.0424228 0.059109 0.220782 0.0363122 0.0540826 0.220782 0.0360874 0.0539336 0.221255 0.0292874 0.0504417 0.224574 0.0524918 0.0610345 0.222645 0.0524084 0.0616615 0.224574 0.0522219 0.0621403 0.222664 0.0523512 0.0618438 0.222755 0.0518647 0.0626521 0.222809 0.0513797 0.0630596 0.222837 0.051032 0.0632426 0.224574 0.0510317 0.0632428 0.224574 0.050413 0.0634129 0.222878 0.0503038 0.0634251 0.224774 0.0504398 0.0636111 0.224574 0.0518527 0.0626651 0.224574 0.0514728 0.0629974 0.22782 0.0294706 0.0508208 0.227721 0.0304655 0.0526335 0.224774 0.029257 0.0505532 0.224974 0.0297224 0.0517091 0.224974 0.0304655 0.0526335 0.224974 0.0304505 0.0484847 0.224774 0.0314643 0.0477766 0.224974 0.029457 0.0505532 0.224974 0.0337486 0.0484729 0.224774 0.0338725 0.0483158 0.224974 0.0315094 0.0479715 0.224774 0.0320119 0.0477048 0.224974 0.0507905 0.0601731 0.224774 0.050401 0.058058 0.224974 0.0502439 0.0581819 0.224774 0.050678 0.0584816 0.224774 0.0509839 0.0594132 0.224974 0.0503111 0.0613761 0.224974 0.0471828 0.0622853 0.224774 0.0485739 0.0626438 0.224974 0.0485451 0.0624459 0.224774 0.0499291 0.0620608 0.224974 0.0498052 0.0619038 0.224774 0.0492134 0.0634816 0.224774 0.0515878 0.0631609 0.224774 0.0523994 0.0622324 0.224774 0.0508112 0.0608783 0.224774 0.0518704 0.059138 0.224774 0.0317743 0.0475046 0.224774 0.0471087 0.0624711 0.224774 0.038375 0.0582374 0.224774 0.0303416 0.0527905 0.224774 0.027647 0.0503672 0.224774 0.0295424 0.0517964 0.224774 0.0275357 0.0490259 0.224774 0.029538 0.0493193 0.224774 0.0303255 0.0483286 0.224774 0.041225 0.053301 0.224974 0.0491445 0.0573617 0.224974 0.041125 0.0534742 0.224974 0.038475 0.0580641 0.22782 0.0492503 0.0622404 0.224974 0.049319 0.0622083 0.227951 0.0502303 0.0614822 0.224974 0.0506254 0.0608043 0.228269 0.0506425 0.0588868 0.224974 0.0506425 0.0588865 0.228169 0.0508136 0.0598157 0.224974 0.050786 0.059442 0.22811 0.0507679 0.0603136 0.228222 0.0312204 0.0480559 0.228258 0.0315669 0.0479588 0.228377 0.0337486 0.0484729 0.228323 0.0323438 0.0479138 0.228353 0.032858 0.0480118 0.224974 0.0326861 0.0479672 0.228169 0.0307894 0.0482539 0.22807 0.0301497 0.0487668 0.227845 0.029457 0.0505532 0.227925 0.0295653 0.0498033 0.224974 0.0297183 0.0494059 0.230112 0.032806 0.0496673 0.229185 0.0436442 0.0550741 0.228753 0.0491293 0.0573997 0.228377 0.0437347 0.0548983 0.228377 0.041125 0.0534742 0.228377 0.0385868 0.0519262 0.22981 0.0488683 0.0580549 0.22981 0.0433931 0.0555618 0.229185 0.0384798 0.0520925 0.22981 0.038183 0.0525537 0.230112 0.0430382 0.0562511 0.22981 0.0332863 0.0490587 0.230112 0.0485813 0.0587752 0.230021 0.039951 0.0555083 0.230112 0.0377635 0.0532058 0.227721 0.0471828 0.0622853 0.229402 0.0490509 0.0613528 0.229158 0.0480129 0.0617442 0.229498 0.0484243 0.0611458 0.22994 0.0494555 0.0597667 0.22992 0.04878 0.0600391 0.23007 0.0491195 0.0592175 0.229765 0.0495358 0.0603613 0.229578 0.0493868 0.0609101 0.229213 0.0499895 0.061007 0.228771 0.0497099 0.0616874 0.228494 0.0498748 0.0617156 0.228347 0.050558 0.0608942 0.227748 0.0482311 0.0624726 0.229256 0.0485742 0.0616436 0.228271 0.0481551 0.0623929 0.22836 0.0490852 0.0622144 0.228088 0.0491779 0.0622488 0.228207 0.0499997 0.0617013 0.229691 0.0487861 0.0607154 0.229024 0.0495108 0.0616151 0.22887 0.048848 0.0620086 0.229512 0.0489897 0.05775 0.22976 0.049661 0.0586102 0.229185 0.0490713 0.0575454 0.229099 0.0499894 0.0581449 0.228718 0.0500436 0.0580122 0.228377 0.0491445 0.0573617 0.228349 0.0500494 0.0579616 0.228252 0.0506994 0.0590541 0.228492 0.0507803 0.0599255 0.228623 0.0506145 0.0589138 0.228824 0.0506718 0.0600385 0.229417 0.0502162 0.0602411 0.229612 0.0501231 0.0593982 0.229822 0.0498076 0.0595882 0.229968 0.049405 0.0589101 0.229459 0.0498612 0.0583476 0.229322 0.0503725 0.059213 0.228982 0.0505374 0.0590479 0.228239 0.0472117 0.0622126 0.227735 0.0479339 0.0624637 0.228415 0.0472357 0.0621523 0.228767 0.0480784 0.0621414 0.228731 0.0473013 0.0619877 0.228994 0.047386 0.0617752 0.228047 0.0506257 0.0608035 0.228654 0.050429 0.0609631 0.22895 0.0502374 0.0610025 0.229141 0.0504819 0.0601467 0.230024 0.0487153 0.0584387 0.228239 0.0305139 0.0525722 0.229213 0.0301697 0.0495628 0.229742 0.0311191 0.0503567 0.229886 0.0314934 0.0501507 0.229366 0.0311787 0.0517296 0.229377 0.0310138 0.0515607 0.229256 0.0303255 0.0511078 0.229402 0.030339 0.050549 0.229464 0.0308362 0.0511102 0.229578 0.0305547 0.0500366 0.229024 0.029882 0.0502818 0.229579 0.0308749 0.0507378 0.229691 0.0310236 0.0504597 0.229417 0.0307196 0.048984 0.229822 0.0314887 0.0490119 0.229612 0.0314954 0.0486436 0.22976 0.0324086 0.0486497 0.229968 0.032277 0.0490214 0.230024 0.0330304 0.049383 0.229765 0.0309556 0.0496335 0.22994 0.0315102 0.049406 0.23007 0.0321536 0.0494224 0.228114 0.0304044 0.0485225 0.228492 0.030711 0.0483376 0.228623 0.0316692 0.0479758 0.228276 0.0317552 0.0479266 0.228375 0.0335181 0.0483102 0.228753 0.0337232 0.048505 0.228207 0.0295629 0.0499013 0.227989 0.0297692 0.0493053 0.227749 0.0297688 0.0518002 0.229158 0.0305191 0.0516442 0.228655 0.029988 0.0491601 0.229141 0.0306686 0.0487066 0.228824 0.0306674 0.0484881 0.229512 0.0334896 0.048801 0.229185 0.0336261 0.0486281 0.228718 0.0327353 0.0480194 0.229099 0.0326474 0.0481327 0.228982 0.0315916 0.0481097 0.228347 0.0299833 0.0490139 0.228494 0.029613 0.0500167 0.22836 0.0295756 0.0509508 0.228088 0.0294995 0.0508877 0.228271 0.0298863 0.0518456 0.228415 0.0305541 0.0525212 0.228767 0.0301424 0.0517862 0.22887 0.0298725 0.0510532 0.228772 0.0297197 0.0501454 0.22895 0.0300497 0.0493459 0.229322 0.0315311 0.048335 0.229459 0.032536 0.048345 0.229366 0.0350183 0.0545405 0.230021 0.0482752 0.0595434 0.230021 0.0426597 0.0569863 0.23001 0.0484806 0.0596577 0.229939 0.048748 0.0599707 0.229694 0.0479421 0.0603795 0.229804 0.0488491 0.0604066 0.229465 0.0483167 0.0612025 0.22964 0.048724 0.0608414 0.229694 0.0317363 0.0510231 0.229446 0.0308472 0.0511839 0.229987 0.0319194 0.0501402 0.230021 0.0322938 0.0503165 0.230021 0.037316 0.0539012 0.229366 0.0390507 0.0570669 0.229366 0.047609 0.0612156 0.2294 0.048019 0.0612778 0.229366 0.0432549 0.0592959 0.228994 0.0308056 0.0522025 0.228994 0.0346802 0.0550391 0.228731 0.0306639 0.052382 0.228994 0.0387495 0.0575886 0.228415 0.0385465 0.0579402 0.228994 0.0429921 0.0598379 0.227721 0.0343721 0.0554935 0.228415 0.0344524 0.0553751 0.227721 0.038475 0.0580641 0.228415 0.042815 0.0602032 0.227721 0.0427526 0.060332 0.224774 0.0509702 0.0585873 0.224574 0.0509026 0.0587756 0.224574 0.0440554 0.0558461 0.224574 0.0376056 0.0521223 0.224774 0.0441449 0.0556672 0.224574 0.031645 0.0476572 0.224574 0.049281 0.0632934 0.224574 0.0419075 0.0601387 0.224774 0.041818 0.0603176 0.224774 0.0348519 0.0562957 0.224774 0.0284141 0.0514731 0.224574 0.0249083 0.0419029 0.222504 0.0248886 0.0422093 0.222664 0.0240603 0.0437335 0.224574 0.0246284 0.0430278 0.222603 0.0244819 0.0432685 0.222704 0.0237263 0.0439709 0.224574 0.0238539 0.0438902 0.222808 0.0226276 0.0442999 0.224574 0.0227655 0.0442891 0.224574 0.0222786 0.0442919 0.224574 0.0216172 0.0441314 0.224574 0.0233341 0.0441564 0.224774 0.022787 0.044488 0.224574 0.0242273 0.0435777 0.224974 0.00971184 0.0248143 0.230112 0.0132219 0.0234158 0.229185 0.0199046 0.0335173 0.228753 0.0234921 0.0382739 0.228377 0.0185229 0.0308721 0.229185 0.016923 0.0283529 0.228377 0.0146354 0.0228526 0.228753 0.0145974 0.0228678 0.230024 0.0226141 0.0389667 0.22981 0.0194434 0.0338141 0.230112 0.015746 0.0289589 0.22981 0.0164353 0.028604 0.22981 0.0139422 0.0231289 0.230112 0.0223298 0.0391911 0.230112 0.0187913 0.0342336 0.227721 0.0116651 0.0292445 0.227721 0.0193636 0.0415316 0.228492 0.023659 0.0412868 0.229578 0.0219599 0.0414428 0.229498 0.0210085 0.0411656 0.23001 0.0218013 0.0399051 0.22994 0.0225911 0.0404869 0.230021 0.0216806 0.0397033 0.229024 0.0217148 0.0421152 0.22895 0.0226503 0.0419481 0.227735 0.0199249 0.0420618 0.228271 0.0201518 0.042111 0.228088 0.0211097 0.0424976 0.229256 0.0208894 0.0416716 0.229158 0.0203531 0.0414781 0.22964 0.0214202 0.0410518 0.229402 0.0214477 0.0416582 0.22887 0.0209441 0.0421247 0.228771 0.0218511 0.0422775 0.228494 0.0219798 0.0423843 0.22836 0.0210465 0.0424215 0.228347 0.0229821 0.0420145 0.22981 0.0229384 0.0387108 0.229968 0.0229756 0.0397198 0.22976 0.0233473 0.0395881 0.229512 0.0231961 0.0385075 0.229185 0.023369 0.038371 0.229099 0.0238643 0.0393493 0.228718 0.0239776 0.0392614 0.228377 0.0235243 0.0382485 0.228623 0.0240213 0.0403278 0.228982 0.0238874 0.0404053 0.229322 0.0236621 0.0404658 0.229822 0.0229853 0.0405083 0.229459 0.023652 0.0394607 0.229612 0.0233535 0.0405016 0.228349 0.0240079 0.0392205 0.228269 0.0240591 0.0403184 0.228731 0.0196151 0.0413332 0.228767 0.0202111 0.0418549 0.229366 0.0202675 0.0408184 0.227748 0.0201778 0.0422181 0.22782 0.0211765 0.0425266 0.227951 0.0224044 0.0423599 0.228207 0.0220951 0.0424344 0.228047 0.0230861 0.0419699 0.228654 0.0228359 0.0420098 0.228824 0.0235085 0.0413304 0.229141 0.02329 0.0413291 0.229417 0.0230127 0.0412781 0.229213 0.0224334 0.041828 0.229765 0.0223633 0.0410419 0.23007 0.0225747 0.0398433 0.227727 0.00957104 0.0243325 0.227721 0.00971184 0.0248143 0.229742 0.0114163 0.0231694 0.22994 0.0122303 0.0225416 0.229886 0.0118434 0.0231781 0.230021 0.0124537 0.0237219 0.229366 0.0107815 0.0243881 0.229446 0.0107672 0.0237498 0.229402 0.0106445 0.0229459 0.229578 0.0110876 0.02261 0.229256 0.0103535 0.0234231 0.229579 0.0110143 0.0233773 0.229822 0.0124088 0.0221895 0.230024 0.0135584 0.0232818 0.229765 0.0116363 0.0224613 0.229968 0.0130867 0.0225919 0.23007 0.0127793 0.0228774 0.228169 0.0121822 0.0211835 0.228105 0.0116488 0.021236 0.228492 0.0120724 0.0212167 0.228253 0.0129574 0.021302 0.22835 0.0140517 0.0219639 0.228347 0.0111041 0.0214386 0.227954 0.0105354 0.0217506 0.228047 0.0111948 0.0213709 0.228271 0.00960422 0.0238424 0.228767 0.00985567 0.023919 0.229158 0.010253 0.0239844 0.22887 0.00998845 0.0231493 0.22836 0.0097826 0.0229121 0.228494 0.010282 0.0221218 0.228772 0.0103101 0.0222867 0.22895 0.0109956 0.0217592 0.228655 0.0110351 0.0215676 0.229141 0.0118512 0.0215151 0.228824 0.0119594 0.0213253 0.229459 0.0136492 0.0221356 0.229099 0.0138519 0.0220075 0.229185 0.0144517 0.0229258 0.228718 0.0139846 0.0219532 0.228623 0.0130832 0.0213825 0.228982 0.012949 0.0214597 0.228207 0.0102963 0.0219969 0.228088 0.00974824 0.0228194 0.228415 0.0098448 0.0247614 0.228731 0.0100094 0.0246958 0.229024 0.0103824 0.0224859 0.229213 0.010991 0.0220071 0.229417 0.0117567 0.0217808 0.229612 0.0125987 0.021874 0.229322 0.012784 0.0216246 0.22976 0.0133866 0.0223358 0.229512 0.0142471 0.0230074 0.229939 0.0218764 0.0403098 0.22992 0.0218699 0.040385 0.229804 0.021746 0.0407379 0.229694 0.020974 0.0402608 0.229465 0.020887 0.0411609 0.22964 0.0214202 0.0410518 0.229691 0.021537 0.0409737 0.229691 0.0112821 0.0232109 0.229377 0.0107232 0.0241594 0.229464 0.0107946 0.0236805 0.229694 0.0116176 0.024055 0.229987 0.0122177 0.023382 0.230021 0.0150108 0.0293374 0.230021 0.0164892 0.0320468 0.230021 0.0180959 0.0346811 0.229366 0.0174566 0.0369788 0.2294 0.0205915 0.0410773 0.228239 0.0194249 0.0414832 0.228415 0.0194759 0.041443 0.228994 0.0197946 0.0411915 0.228994 0.0144085 0.0332476 0.229366 0.0149302 0.0329464 0.229366 0.0127012 0.0287422 0.228994 0.0102219 0.0246111 0.228994 0.0121592 0.029005 0.228415 0.0117939 0.0291821 0.228415 0.0140569 0.0334506 0.228994 0.016958 0.0373169 0.228239 0.00978446 0.0247854 0.228415 0.016622 0.0375447 0.227721 0.013933 0.0335221 0.227721 0.0165036 0.037625 0.224774 0.0200417 0.0342813 0.224774 0.0135155 0.0213191 0.224574 0.016151 0.0279417 0.224574 0.0206767 0.0434538 0.224574 0.0118584 0.0300896 0.224774 0.0157014 0.0371452 0.224774 0.0134098 0.0210269 0.224574 0.0132215 0.0210945 0.224574 0.0117371 0.0196337 0.224574 0.0106748 0.0195226 0.224774 0.00956176 0.019715 0.224574 0.00857565 0.0216557 0.224774 0.00837673 0.0216349 0.224574 0.00884016 0.020785 0.224574 0.00966952 0.0198835 0.224574 0.0247617 0.0410771 0.224774 0.0249495 0.0410082 0.224774 0.0242923 0.0399852 0.224774 0.0186961 0.0307721 0.224774 0.0163299 0.0278522 0.224774 0.0140768 0.0217121 0.222828 0.00880893 0.0208463 0.224574 0.00892033 0.0206447 0.222737 0.00949531 0.0200061 0.222664 0.0101522 0.0196463 0.22252 0.0116946 0.0196197 0.222576 0.0110522 0.019507 0.222607 0.0107282 0.0195168 0.222623 0.0105545 0.0195403 0.222427 0.0132215 0.0210945 0.222449 0.0126729 0.0202216 0.224574 0.012646 0.0201947 0.224574 0.0118882 0.0196909 0.222504 0.011888 0.0196909 0.222441 0.0247641 0.0410835 0.224574 0.0158684 0.0370351 0.2229 0.0118584 0.0300896 0.2229 0.00870373 0.0227161 0.224574 0.00870373 0.0227161 0.222427 0.016151 0.0279417 0.222427 0.0198748 0.0343915 0.224574 0.0198748 0.0343915 0.224574 0.0243399 0.0403521 0.221231 0.00975333 0.0220288 0.220834 0.0109612 0.0208456 0.220796 0.0109026 0.0216952 0.220726 0.0114181 0.0211423 0.221162 0.0113525 0.0201904 0.220952 0.0111517 0.0204995 0.220779 0.01213 0.0214863 0.220979 0.0104634 0.0207672 0.22094 0.0103968 0.0214526 0.220827 0.0117353 0.0208674 0.221778 0.00902682 0.0212573 0.221498 0.009927 0.0202762 0.221057 0.0100839 0.0215326 0.22147 0.00928786 0.0220053 0.221392 0.00938255 0.021544 0.221565 0.0091885 0.0213985 0.222881 0.00856695 0.0217614 0.222358 0.00864404 0.0218404 0.22289 0.00856547 0.0220259 0.22256 0.00879801 0.0209185 0.22247 0.00931496 0.0201928 0.222722 0.00962451 0.0199129 0.222253 0.0109414 0.0195365 0.221905 0.00931879 0.0204835 0.221761 0.00993987 0.0200282 0.221921 0.0108248 0.0196413 0.221452 0.0115462 0.0199471 0.221336 0.0123133 0.0204304 0.221696 0.0125203 0.0203091 0.221619 0.0130354 0.0211613 0.221291 0.0128279 0.0212358 0.222183 0.00929634 0.0203174 0.222364 0.0100592 0.019711 0.222056 0.00998579 0.0198377 0.221792 0.0117167 0.0197878 0.222151 0.0118533 0.0197151 0.222078 0.0126547 0.0202594 0.221627 0.00922053 0.0225306 0.22102 0.0101778 0.02149 0.221132 0.0100035 0.0208828 0.221284 0.00994904 0.0205675 0.221861 0.00889284 0.021926 0.222383 0.00877733 0.0226897 0.222288 0.00882912 0.0210126 0.221653 0.00938438 0.0206854 0.221603 0.0107102 0.0198276 0.221327 0.0106067 0.0200903 0.221036 0.0120439 0.0206217 0.220993 0.0125192 0.0213466 0.2229 0.0206767 0.0434538 0.222427 0.0243399 0.0403521 0.221184 0.0220095 0.0429414 0.220807 0.022684 0.0421366 0.220855 0.0227011 0.042357 0.220879 0.022687 0.0424438 0.221275 0.0224929 0.0434313 0.221099 0.0222837 0.042902 0.221653 0.0227761 0.0438796 0.221392 0.022031 0.0434519 0.22102 0.0224757 0.0427901 0.221132 0.0229147 0.0432445 0.220979 0.0232444 0.0429039 0.220827 0.0237934 0.041753 0.221162 0.0241883 0.0424229 0.220779 0.0234548 0.0411015 0.220982 0.0225486 0.0427173 0.220834 0.0234252 0.0424341 0.220952 0.0238201 0.0424422 0.220726 0.0233968 0.0418902 0.220692 0.0231787 0.0413353 0.222642 0.0242273 0.0435777 0.222364 0.0239578 0.0437818 0.222576 0.0246304 0.0430239 0.222253 0.0245495 0.0431051 0.222542 0.0247824 0.04267 0.22205 0.0243086 0.0403786 0.222078 0.0247798 0.0412609 0.222483 0.0249083 0.0419029 0.222746 0.0233344 0.0441563 0.22256 0.0222803 0.0442709 0.222833 0.0222789 0.0442919 0.222878 0.0214966 0.0440793 0.222383 0.0207363 0.0434033 0.22147 0.0215841 0.0433032 0.221778 0.0221014 0.0439033 0.222288 0.0222144 0.0441969 0.221905 0.0229182 0.0440373 0.222183 0.0230509 0.0441398 0.222056 0.0238113 0.0437821 0.221792 0.0247191 0.0423088 0.221336 0.024461 0.041471 0.221696 0.0246695 0.0413524 0.222151 0.0248504 0.0422269 0.22192 0.0244004 0.0431537 0.22247 0.0231681 0.0441859 0.222358 0.0214049 0.0439432 0.221861 0.0214552 0.0436849 0.222207 0.0207859 0.0433613 0.221497 0.023402 0.0436139 0.221761 0.0236233 0.0437266 0.221327 0.0239024 0.0431181 0.221603 0.0241817 0.0431598 0.221452 0.0244958 0.0423768 0.221036 0.0241606 0.0416087 0.221291 0.0240207 0.0406223 0.221255 0.0215554 0.0427097 0.221627 0.0210957 0.043099 0.221498 0.00936529 0.0224786 0.221255 0.0127656 0.0293281 0.22189 0.00900534 0.0226078 0.221627 0.0123494 0.0298439 0.221627 0.0163267 0.0367327 0.221255 0.0168295 0.0364009 0.222207 0.0119864 0.0300255 0.222207 0.00883844 0.0226677 0.22189 0.0209212 0.0432467 0.222207 0.0159878 0.0369562 0.2229 0.0158684 0.0370351 0.221619 0.024189 0.0404798 0.220782 0.018063 0.035909 0.220684 0.0117265 0.0216311 0.220782 0.0140507 0.0289926 0.221619 0.0159742 0.0280302 0.220993 0.0192519 0.0348025 0.220692 0.0117894 0.0216085 0.220782 0.0179145 0.0356849 0.220692 0.0186048 0.0352295 0.220692 0.0147903 0.0286226 0.220993 0.0237704 0.0408343 0.221619 0.0197097 0.0345004 0.220993 0.0154837 0.0282756 0.22205 0.0131829 0.0211084 0.220782 0.0139306 0.0287512 0.22094 0.0103968 0.0214526 0.220854 0.0106672 0.0215118 0.221019 0.0103993 0.0221075 0.220782 0.0110111 0.0218879 0.221231 0.00975334 0.0220288 0.22116 0.00985844 0.0217401 0.221057 0.0100839 0.0215326 0.221255 0.0169809 0.0366294 0.221019 0.0220515 0.0422897 0.221242 0.0217246 0.0428523 0.220782 0.0225476 0.0418697 0.220807 0.022684 0.0421366 0.220879 0.022687 0.0424438 0.220982 0.0225486 0.0427173 0.221099 0.0222837 0.042902 0.221255 0.0128881 0.0295743 0.221255 0.0097875 0.0223271 0.224774 0.0096204 0.0225672 0.224974 0.0116743 0.021231 0.224974 0.0128826 0.0212801 0.224774 0.0129361 0.0210874 0.224974 0.0129994 0.0213154 0.224774 0.0148212 0.0227786 0.224974 0.0141172 0.0220321 0.224974 0.0139433 0.021861 0.224974 0.023544 0.0415063 0.224774 0.0240915 0.040945 0.224974 0.0240663 0.0395086 0.224774 0.0242642 0.0394798 0.224974 0.0240591 0.0403181 0.224774 0.0232094 0.0421274 0.224774 0.0218542 0.0427104 0.224974 0.0204631 0.0423519 0.224974 0.021252 0.0425331 0.224974 0.0218254 0.0425125 0.224774 0.0244925 0.0402228 0.224774 0.0215429 0.0443171 0.224774 0.020524 0.043583 0.224774 0.023966 0.0440558 0.224774 0.024805 0.0431215 0.224774 0.0251083 0.0419029 0.224774 0.0116366 0.0210345 0.224774 0.0127863 0.0200522 0.224774 0.0118017 0.0194444 0.224774 0.020389 0.0425377 0.224774 0.0116795 0.0301791 0.224774 0.00952605 0.0248884 0.224774 0.00851549 0.0227837 0.224774 0.00932364 0.0238335 0.224774 0.00875014 0.0205397 0.224774 0.0104489 0.0215646 0.224774 0.0106508 0.0193241 0.224974 0.0185229 0.0308721 0.224974 0.0235243 0.0382485 0.224774 0.0236813 0.0381246 0.228377 0.0200709 0.0334103 0.228377 0.0170988 0.0282624 0.224974 0.013933 0.0335221 0.224774 0.0137597 0.0336221 0.224774 0.0192066 0.0416555 0.224974 0.0193636 0.0415316 0.224974 0.0230855 0.0419704 0.224974 0.0225274 0.0423085 0.228252 0.0240247 0.0404917 0.224974 0.0239057 0.0408709 0.228169 0.0237427 0.0412084 0.22811 0.0234542 0.0416167 0.224974 0.0146354 0.0228526 0.228276 0.0131822 0.0213829 0.224974 0.0105699 0.0217238 0.224974 0.0104745 0.0217999 0.224974 0.00952364 0.0238335 0.227744 0.00952364 0.0238335 0.22782 0.00975659 0.022747 0.224974 0.00979958 0.0226561 0.227835 0.00983003 0.0225966 0.222427 0.0132215 -0.0211002 0.224574 0.0132215 -0.0211002 0.222446 0.0127201 -0.0202765 0.224574 0.0118882 -0.0196967 0.222664 0.0101533 -0.0196516 0.222607 0.0107283 -0.0195225 0.224574 0.0107284 -0.0195225 0.224574 0.0113899 -0.0195494 0.222499 0.011952 -0.0197244 0.224574 0.00884016 -0.0207907 0.222823 0.00884026 -0.0207905 0.224574 0.00962448 -0.0199187 0.2229 0.00870373 -0.0227218 0.2229 0.0158684 -0.0370408 0.224574 0.0158684 -0.0370408 0.222427 0.0243399 -0.0403578 0.224574 0.0198748 -0.0343972 0.222427 0.016151 -0.0279474 0.224574 0.016151 -0.0279474 0.221231 0.0217967 -0.0428942 0.220979 0.0232443 -0.04291 0.220726 0.0233968 -0.0418957 0.220779 0.0234548 -0.0411072 0.22094 0.0226174 -0.042625 0.220952 0.0238202 -0.0424478 0.220827 0.0237934 -0.0417584 0.220834 0.0234253 -0.0424397 0.220692 0.0231787 -0.041341 0.221778 0.0221016 -0.0439091 0.221284 0.02316 -0.0434553 0.221498 0.0234013 -0.0436201 0.221327 0.0239021 -0.0431244 0.221057 0.0223917 -0.042856 0.22116 0.0220992 -0.0429475 0.221565 0.0220601 -0.0436985 0.222746 0.0233343 -0.044162 0.222676 0.0239672 -0.0438143 0.222881 0.0214351 -0.0440553 0.222866 0.0217483 -0.0441852 0.222785 0.0229079 -0.0442751 0.22247 0.0231675 -0.0441918 0.222358 0.0214052 -0.0439491 0.222383 0.0207363 -0.043409 0.222899 0.0207989 -0.0435935 0.2229 0.0206767 -0.0434595 0.222253 0.0245491 -0.0431115 0.222499 0.0248966 -0.042145 0.222441 0.0247638 -0.0410887 0.222364 0.0239569 -0.0437882 0.222642 0.0242273 -0.0435835 0.222056 0.0238104 -0.0437884 0.221921 0.0244 -0.04316 0.221761 0.0236225 -0.0437329 0.221603 0.0241814 -0.0431661 0.221696 0.0246694 -0.0413578 0.221452 0.0244959 -0.0423824 0.221336 0.0244609 -0.0414763 0.221619 0.024189 -0.0404856 0.222183 0.0230503 -0.0441457 0.222151 0.0248504 -0.0422324 0.221792 0.0247192 -0.0423144 0.222078 0.0247797 -0.0412662 0.22205 0.0243086 -0.0403843 0.22147 0.0215842 -0.043309 0.222207 0.0207859 -0.043367 0.221132 0.0229142 -0.0432506 0.221392 0.0220311 -0.0434577 0.221861 0.0214555 -0.0436908 0.22256 0.0222805 -0.0442767 0.222288 0.0222146 -0.0442027 0.221905 0.0229177 -0.0440432 0.221653 0.0227756 -0.0438854 0.221162 0.0241883 -0.0424285 0.221036 0.0241606 -0.0416141 0.222878 0.00857201 -0.021699 0.222383 0.00877734 -0.0226954 0.221132 0.010004 -0.0208883 0.22189 0.00900536 -0.0226135 0.220807 0.0108481 -0.021642 0.220726 0.0114179 -0.0211479 0.220855 0.0106658 -0.0215169 0.220879 0.0105836 -0.0214859 0.221184 0.0098139 -0.0218237 0.221099 0.00998516 -0.021606 0.221275 0.00963138 -0.0211602 0.220979 0.0104638 -0.020773 0.221327 0.0106073 -0.020096 0.220952 0.0111516 -0.0205053 0.220827 0.011735 -0.020873 0.220834 0.0109611 -0.0208514 0.220779 0.0121299 -0.021492 0.222437 0.0128898 -0.0204805 0.222151 0.0118532 -0.0197207 0.222591 0.0108877 -0.0195122 0.222253 0.0109421 -0.0195422 0.222752 0.0093695 -0.020116 0.222808 0.00894442 -0.0206123 0.222364 0.0100603 -0.0197162 0.22247 0.00931544 -0.0201981 0.222705 0.00977399 -0.019826 0.222722 0.00962461 -0.0199187 0.222828 0.00880883 -0.0208522 0.221861 0.00889286 -0.021932 0.221905 0.00931919 -0.0204888 0.222183 0.00929677 -0.0203227 0.221761 0.00994078 -0.0200335 0.221603 0.0107109 -0.0198333 0.221792 0.0117166 -0.0197934 0.221696 0.01252 -0.0203146 0.221336 0.012313 -0.0204359 0.221291 0.0128279 -0.0212415 0.221619 0.0130354 -0.021167 0.222078 0.0126545 -0.0202648 0.22192 0.0108255 -0.019647 0.222056 0.0099868 -0.019843 0.22256 0.00879792 -0.0209244 0.222288 0.00882905 -0.0210185 0.222358 0.00864403 -0.0218465 0.221255 0.0097875 -0.0223328 0.22147 0.00928791 -0.0220113 0.221392 0.00938256 -0.0215499 0.221778 0.00902679 -0.0212632 0.221653 0.00938473 -0.0206908 0.221497 0.00992781 -0.0202815 0.221162 0.0113523 -0.0201961 0.221452 0.011546 -0.0199528 0.221036 0.0120436 -0.0206272 0.220993 0.0125192 -0.0213523 0.221627 0.0123494 -0.0298496 0.221498 0.0212131 -0.0430053 0.221255 0.0215554 -0.0427155 0.221627 0.0210957 -0.0431047 0.221627 0.0163267 -0.0367384 0.221255 0.0168295 -0.0364066 0.221255 0.0128881 -0.02958 0.222207 0.0159878 -0.036962 0.22189 0.0209212 -0.0432525 0.2229 0.0118584 -0.0300953 0.221627 0.00922053 -0.0225363 0.222207 0.00883844 -0.0226735 0.222207 0.0119864 -0.0300312 0.220692 0.0117894 -0.0216143 0.220782 0.0139309 -0.0287577 0.221619 0.0197097 -0.0345061 0.220684 0.0231277 -0.0413842 0.220692 0.0147903 -0.0286283 0.220692 0.0186048 -0.0352352 0.220993 0.0192519 -0.0348082 0.222427 0.0198748 -0.0343972 0.22205 0.0131829 -0.0211141 0.220993 0.0237704 -0.04084 0.221291 0.0240207 -0.040628 0.220993 0.0154837 -0.0282813 0.221619 0.0159742 -0.0280359 0.220782 0.0180635 -0.0359154 0.221019 0.0220515 -0.0422954 0.220854 0.0227013 -0.0423613 0.220796 0.0226602 -0.0420657 0.220782 0.0225476 -0.0418754 0.221231 0.0217967 -0.0428942 0.221057 0.0223917 -0.042856 0.22102 0.0224755 -0.042796 0.221255 0.012766 -0.0293346 0.221242 0.00974864 -0.022115 0.220807 0.0108481 -0.021642 0.221019 0.0103993 -0.0221132 0.220982 0.0102775 -0.0214689 0.22102 0.0101781 -0.0214956 0.221099 0.00998516 -0.021606 0.220782 0.0110111 -0.0218936 0.220782 0.0140507 -0.0289983 0.220782 0.0179145 -0.0356906 0.221255 0.0169814 -0.0366359 0.224574 0.0247617 -0.0410828 0.224774 0.0249495 -0.041014 0.224974 0.0116743 -0.0212367 0.224974 0.0105699 -0.0217296 0.227945 0.0104746 -0.0218055 0.224974 0.0104745 -0.0218056 0.224974 0.00979958 -0.0226618 0.227929 0.0103728 -0.0218951 0.224974 0.00952364 -0.0238392 0.228112 0.0117024 -0.0212314 0.228254 0.0129601 -0.0213086 0.224974 0.0129994 -0.0213211 0.224974 0.0139433 -0.0218667 0.224774 0.0140768 -0.0217178 0.224774 0.0129361 -0.0210931 0.224974 0.0128826 -0.0212858 0.224774 0.0096204 -0.0225729 0.224774 0.0232094 -0.0421331 0.224974 0.0218254 -0.0425182 0.224774 0.0236813 -0.0381303 0.224774 0.0242923 -0.0399909 0.224774 0.00851549 -0.0227894 0.224774 0.0135155 -0.0213248 0.224774 0.0104489 -0.0215703 0.224774 0.0100843 -0.0194639 0.224774 0.0116366 -0.0210403 0.224774 0.0114255 -0.0193526 0.224774 0.0240915 -0.0409507 0.224774 0.0244925 -0.0402285 0.224774 0.0215429 -0.0443228 0.224774 0.0218542 -0.0427161 0.224774 0.020389 -0.0425434 0.224774 0.0137597 -0.0336279 0.224774 0.00952605 -0.0248941 0.224774 0.00932364 -0.0238392 0.224974 0.0146354 -0.0228584 0.224974 0.0185229 -0.0308779 0.224774 0.0192066 -0.0416612 0.224974 0.00971184 -0.02482 0.227721 0.00971184 -0.02482 0.228363 0.0239085 -0.0389219 0.224974 0.0235243 -0.0382542 0.224974 0.0240663 -0.0395143 0.224974 0.0225274 -0.0423142 0.227984 0.0226564 -0.0422522 0.224974 0.0230855 -0.0419761 0.224974 0.023544 -0.041512 0.228047 0.0230872 -0.0419748 0.224974 0.0239057 -0.0408766 0.224974 0.0240591 -0.0403238 0.228276 0.0240705 -0.0402476 0.224974 0.0204631 -0.0423576 0.224974 0.021252 -0.0425388 0.227843 0.0214295 -0.0425457 0.229512 0.0142471 -0.0230131 0.228753 0.0145974 -0.0228735 0.228377 0.0170988 -0.0282681 0.228377 0.0185229 -0.0308779 0.229185 0.016923 -0.0283587 0.229185 0.0199046 -0.033523 0.228377 0.0200709 -0.033416 0.22981 0.0164353 -0.0286097 0.22981 0.0139422 -0.0231346 0.228377 0.0235243 -0.0382542 0.229185 0.023369 -0.0383767 0.22981 0.0194434 -0.0338198 0.229512 0.0231961 -0.0385132 0.22981 0.0229384 -0.0387165 0.230112 0.0132219 -0.0234215 0.230112 0.015746 -0.0289646 0.230112 0.0187913 -0.0342393 0.230021 0.0150108 -0.0293432 0.230021 0.0180959 -0.0346868 0.230021 0.0216806 -0.0397091 0.224974 0.0193636 -0.0415374 0.227721 0.013933 -0.0335279 0.227721 0.0116651 -0.0292502 0.224974 0.013933 -0.0335279 0.22994 0.0122304 -0.0225473 0.23007 0.0127796 -0.0228833 0.230024 0.0135584 -0.0232875 0.229968 0.013087 -0.0225978 0.22976 0.0133869 -0.0223418 0.229822 0.0124089 -0.0221952 0.23001 0.0123394 -0.0235222 0.230021 0.0124537 -0.0237276 0.228767 0.00985566 -0.0239244 0.229158 0.0102529 -0.0239899 0.229612 0.0125989 -0.0218797 0.229417 0.011756 -0.0217866 0.229765 0.0116358 -0.0224671 0.229213 0.0109901 -0.0220133 0.228207 0.0102958 -0.0220031 0.22836 0.00978268 -0.0229176 0.227744 0.00952364 -0.0238392 0.227801 0.00967331 -0.022961 0.229578 0.011087 -0.022616 0.229256 0.0103535 -0.0234286 0.229402 0.0106443 -0.0229519 0.22887 0.00998851 -0.0231548 0.228377 0.0146354 -0.0228584 0.228718 0.0139849 -0.0219593 0.228349 0.0140355 -0.0219535 0.228276 0.0131823 -0.0213887 0.228623 0.0130833 -0.0213883 0.228169 0.0121814 -0.0211892 0.228047 0.0111936 -0.0213771 0.228083 0.0114739 -0.0212832 0.228771 0.0103097 -0.0222929 0.228824 0.0119586 -0.0213311 0.229322 0.0127841 -0.0216303 0.229099 0.0138522 -0.0220135 0.229185 0.0144517 -0.0229315 0.229459 0.0136495 -0.0221416 0.228494 0.0102815 -0.022128 0.228654 0.011034 -0.0215738 0.228347 0.0111029 -0.0214449 0.228492 0.0120716 -0.0212225 0.228982 0.0129492 -0.0214654 0.227727 0.00957019 -0.0243355 0.228271 0.00960422 -0.0238477 0.228415 0.0098448 -0.0247671 0.228731 0.0100094 -0.0247015 0.228088 0.00974834 -0.0228249 0.229024 0.010382 -0.0224921 0.22895 0.0109946 -0.0217655 0.229141 0.0118504 -0.0215209 0.227721 0.0193636 -0.0415374 0.228731 0.0196151 -0.0413389 0.229886 0.0218464 -0.0405095 0.229987 0.0218569 -0.0400834 0.230112 0.0223298 -0.0391968 0.229256 0.0208893 -0.0416773 0.229464 0.0208869 -0.0411666 0.229402 0.0214481 -0.0416638 0.229024 0.0217153 -0.0421208 0.229578 0.0219605 -0.0414481 0.229691 0.0215374 -0.0409792 0.229765 0.0223636 -0.0410472 0.229612 0.0233535 -0.0405074 0.229968 0.0229757 -0.0397258 0.230024 0.0226141 -0.0389724 0.22994 0.0225911 -0.0404927 0.229822 0.0229852 -0.0405142 0.23007 0.0225747 -0.0398493 0.22835 0.0240024 -0.0392056 0.228169 0.0237432 -0.0412134 0.228143 0.0236231 -0.0414036 0.228718 0.0239777 -0.0392676 0.228753 0.0234921 -0.0382796 0.228347 0.0229832 -0.0420195 0.227925 0.0221938 -0.0424375 0.227827 0.0212523 -0.0425389 0.22782 0.0211763 -0.0425323 0.228271 0.0201515 -0.0421165 0.227749 0.0201969 -0.042234 0.228239 0.0194249 -0.0414889 0.229158 0.0203529 -0.0414837 0.228767 0.0202109 -0.0418605 0.22887 0.0209439 -0.0421303 0.22836 0.0210463 -0.0424272 0.228772 0.0218517 -0.0422831 0.229459 0.0236521 -0.0394668 0.229099 0.0238644 -0.0393554 0.228982 0.0238874 -0.0404112 0.228623 0.0240213 -0.0403336 0.228492 0.0236595 -0.0412918 0.228824 0.023509 -0.0413354 0.228207 0.0220958 -0.0424399 0.228655 0.022837 -0.0420148 0.228494 0.0219804 -0.0423898 0.228088 0.0211094 -0.0425033 0.229366 0.0202675 -0.0408241 0.229213 0.0224343 -0.0418331 0.22895 0.0226512 -0.0419531 0.229141 0.0232905 -0.0413342 0.229417 0.0230131 -0.0412832 0.229322 0.0236621 -0.0404717 0.22976 0.0233474 -0.0395942 0.229694 0.0116176 -0.0240607 0.229939 0.0120264 -0.0232548 0.22992 0.011958 -0.0232228 0.2294 0.0107193 -0.0239838 0.229465 0.0107946 -0.0236861 0.229498 0.0108513 -0.0235785 0.22964 0.0111557 -0.0232789 0.229691 0.0112817 -0.0232168 0.229804 0.0115905 -0.0231537 0.229742 0.0216404 -0.0408837 0.229377 0.0204364 -0.040989 0.229446 0.0208132 -0.0411557 0.229579 0.0212593 -0.0411279 0.229694 0.020974 -0.0402666 0.230021 0.0164888 -0.0320518 0.229366 0.0127012 -0.0287479 0.229366 0.0107815 -0.0243939 0.228994 0.0102219 -0.0246168 0.229366 0.0149302 -0.0329521 0.228994 0.016958 -0.0373226 0.228994 0.0197946 -0.0411972 0.229366 0.0174566 -0.0369845 0.228994 0.0144085 -0.0332533 0.228415 0.016622 -0.0375504 0.228994 0.0121592 -0.0290107 0.228415 0.0140569 -0.0334563 0.228415 0.0117939 -0.0291878 0.228415 0.0194759 -0.0414487 0.227721 0.0165036 -0.0376307 0.228239 0.00978445 -0.0247911 0.224774 0.0163299 -0.0278579 0.224574 0.0243399 -0.0403578 0.224574 0.0118584 -0.0300953 0.224774 0.0116795 -0.0301848 0.224774 0.0157014 -0.0371509 0.224774 0.024805 -0.0431272 0.224774 0.0251083 -0.0419087 0.224574 0.0247825 -0.0426755 0.224774 0.023966 -0.0440616 0.224774 0.020524 -0.0435888 0.224574 0.0222786 -0.0442976 0.224774 0.022787 -0.0444937 0.224574 0.00870373 -0.0227218 0.224774 0.00840417 -0.0214481 0.224574 0.00860097 -0.0214837 0.224774 0.00897839 -0.0202309 0.224574 0.00913102 -0.0203601 0.224574 0.0101518 -0.0196521 0.224774 0.0134098 -0.0210327 0.224574 0.0125135 -0.0200794 0.224774 0.0126427 -0.0199268 0.224774 0.0148212 -0.0227843 0.224774 0.0186961 -0.0307779 0.224774 0.0200417 -0.034287 0.224774 0.0242642 -0.0394855 0.222664 0.0240594 -0.04374 0.224574 0.0238539 -0.0438959 0.224574 0.0233341 -0.0441621 0.224574 0.0227655 -0.0442948 0.222833 0.0222789 -0.0442977 0.224574 0.0216172 -0.0441371 0.224574 0.0206767 -0.0434595 0.224574 0.0242273 -0.0435834 0.224574 0.0246284 -0.0430335 0.222564 0.0246886 -0.0429118 0.224574 0.0249083 -0.0419087 0.222483 0.0249083 -0.0419087 0.230021 0.0322938 -0.0503222 0.229939 0.0316873 -0.0501265 0.229498 0.0308315 -0.0509943 0.229694 0.0317363 -0.0510288 0.229691 0.0310234 -0.0504658 0.229366 0.047609 -0.0612213 0.229446 0.0482473 -0.0612356 0.229464 0.0483166 -0.0612083 0.229694 0.0479421 -0.0603852 0.229987 0.0486151 -0.0597851 0.229886 0.048819 -0.0601594 0.230021 0.037316 -0.0539069 0.228239 0.0472117 -0.0622184 0.227721 0.0471828 -0.062291 0.228731 0.0473013 -0.0619934 0.228239 0.0305139 -0.0525779 0.229366 0.0311787 -0.0517353 0.229366 0.0350183 -0.0545462 0.229366 0.0390507 -0.0570727 0.228994 0.047386 -0.0617809 0.229366 0.0432549 -0.0593016 0.228994 0.0429921 -0.0598436 0.228994 0.0387495 -0.0575943 0.228415 0.0385465 -0.0579459 0.228415 0.0344524 -0.0553808 0.228994 0.0346802 -0.0550448 0.228731 0.0306639 -0.0523878 0.228415 0.0305541 -0.0525269 0.228415 0.042815 -0.0602089 0.227721 0.0427526 -0.0603377 0.227721 0.038475 -0.0580699 0.224774 0.0320119 -0.0477105 0.224574 0.031645 -0.0476629 0.224574 0.034962 -0.0561344 0.224574 0.0419075 -0.0601444 0.224574 0.049281 -0.0632991 0.224774 0.0523994 -0.0622382 0.224574 0.050413 -0.0634186 0.224774 0.0492134 -0.0634873 0.224774 0.0504398 -0.0636168 0.224574 0.0510317 -0.0632485 0.224774 0.0515878 -0.0631666 0.224574 0.0279022 -0.0504719 0.224774 0.0277858 -0.0482981 0.224774 0.0295903 -0.0469438 0.224574 0.0306967 -0.0471714 0.224774 0.030747 -0.0469778 0.224774 0.0441449 -0.0556729 0.224774 0.0327298 -0.0477778 0.224774 0.0338725 -0.0483216 0.224774 0.0377158 -0.0519611 0.224774 0.0502628 -0.0579015 0.224574 0.0514728 -0.0630031 0.222795 0.051528 -0.062963 0.222757 0.0518529 -0.0626707 0.224574 0.0518527 -0.0626709 0.224574 0.0522219 -0.062146 0.222664 0.0523508 -0.0618506 0.224574 0.0523657 -0.0618079 0.222446 0.0307989 -0.0472003 0.224574 0.0297885 -0.0471141 0.224574 0.0296291 -0.04714 0.222591 0.0288298 -0.0474546 0.222607 0.028697 -0.0475432 0.224574 0.0286536 -0.047575 0.222664 0.0282636 -0.0479425 0.222705 0.0280223 -0.0482832 0.222722 0.0279392 -0.0484381 0.222828 0.0276995 -0.0496545 0.222823 0.0276959 -0.0495854 0.224574 0.0276959 -0.0495855 0.224574 0.0276952 -0.049424 0.222808 0.027697 -0.0493789 0.222752 0.027817 -0.0487366 0.224574 0.0279634 -0.0483901 0.224574 0.0285433 -0.0513262 0.2229 0.0419075 -0.0601444 0.2229 0.049281 -0.0632991 0.224574 0.0440554 -0.0558518 0.224574 0.0376056 -0.052128 0.222427 0.0376056 -0.052128 0.221255 0.04967 -0.0622153 0.220834 0.0511515 -0.0610416 0.220796 0.0503019 -0.0611002 0.220782 0.0501092 -0.0609917 0.220692 0.0503886 -0.0602134 0.221162 0.0518067 -0.0606504 0.220952 0.0514976 -0.0608511 0.220979 0.0512299 -0.0615394 0.22094 0.0505445 -0.0616061 0.220827 0.0511297 -0.0602675 0.220726 0.0508548 -0.0605847 0.221653 0.0513117 -0.0626184 0.221327 0.0519068 -0.0613961 0.22147 0.0499918 -0.062715 0.222837 0.051032 -0.0632484 0.222801 0.0514592 -0.0630125 0.222383 0.0493074 -0.0632255 0.22205 0.0508887 -0.0588199 0.222444 0.0516975 -0.0592564 0.222078 0.0517377 -0.0593481 0.222686 0.052269 -0.0620499 0.222364 0.0522861 -0.0619436 0.222584 0.0524918 -0.0610402 0.22252 0.052378 -0.0603099 0.222151 0.052282 -0.0601495 0.222449 0.0517755 -0.0593299 0.222183 0.0516797 -0.0627065 0.222056 0.0521594 -0.062017 0.221792 0.0522093 -0.0602861 0.221696 0.051688 -0.0594826 0.221619 0.0508358 -0.0589674 0.221336 0.0515667 -0.0596895 0.22247 0.0518043 -0.0626879 0.222253 0.0524606 -0.0610614 0.221921 0.0523558 -0.061178 0.221498 0.0495185 -0.0626375 0.221627 0.0494665 -0.0627823 0.221861 0.0500711 -0.06311 0.22189 0.0493893 -0.0629975 0.221057 0.0504645 -0.0619189 0.221132 0.0511143 -0.0619994 0.221284 0.0514296 -0.0620538 0.221392 0.0504531 -0.0626203 0.221565 0.0505986 -0.0628143 0.222358 0.0501567 -0.0633588 0.222875 0.0503761 -0.0634233 0.22256 0.0510786 -0.0632048 0.222288 0.0509845 -0.0631737 0.221778 0.0507398 -0.062976 0.221905 0.0515136 -0.062684 0.221761 0.0519689 -0.0620629 0.221498 0.0517209 -0.0620758 0.221603 0.0521695 -0.0612926 0.221452 0.05205 -0.0604567 0.221036 0.0513754 -0.0599589 0.2229 0.0285433 -0.0513262 0.222383 0.0285938 -0.0512665 0.221132 0.0287526 -0.0490881 0.220807 0.0298605 -0.0493188 0.220855 0.0296401 -0.0493017 0.220879 0.0295533 -0.0493159 0.221275 0.0285658 -0.0495099 0.221099 0.0290951 -0.0497191 0.221497 0.0283832 -0.0486008 0.221392 0.0285452 -0.0499718 0.22102 0.029207 -0.0495271 0.221327 0.028879 -0.0481004 0.221162 0.0295742 -0.0478145 0.220779 0.0308956 -0.0485481 0.220979 0.0290932 -0.0487584 0.220982 0.0292798 -0.0494542 0.220952 0.0295549 -0.0481827 0.220834 0.029563 -0.0485776 0.220726 0.0301069 -0.048606 0.220827 0.0302441 -0.0482094 0.222499 0.0298577 -0.0471062 0.222151 0.0297702 -0.0471524 0.222364 0.0282153 -0.048045 0.221619 0.0315173 -0.0478138 0.222078 0.0307362 -0.047223 0.22205 0.0316185 -0.0476942 0.222437 0.0310479 -0.0472921 0.22256 0.0277262 -0.0497225 0.222878 0.0279178 -0.0505062 0.221778 0.0280938 -0.0499014 0.222288 0.0278002 -0.0497884 0.222056 0.028215 -0.0481915 0.221603 0.0288373 -0.0478211 0.221452 0.0296203 -0.047507 0.221696 0.0306447 -0.0473333 0.221291 0.0313748 -0.0479821 0.221792 0.0296883 -0.0472837 0.222253 0.028892 -0.0474533 0.22192 0.0288434 -0.0476024 0.22247 0.0278112 -0.0488347 0.222183 0.0278573 -0.0489519 0.222358 0.0280539 -0.0505979 0.221861 0.0283122 -0.0505476 0.222207 0.0286358 -0.0512169 0.22189 0.0287504 -0.0510816 0.221242 0.0291448 -0.0502782 0.22147 0.0286939 -0.0504187 0.221653 0.0281175 -0.0492267 0.221905 0.0279598 -0.0490846 0.221761 0.0282705 -0.0483795 0.221036 0.0303884 -0.0478422 0.221336 0.0305261 -0.0475419 0.221627 0.0288981 -0.0509071 0.221255 0.042669 -0.0592372 0.221627 0.0421532 -0.0596534 0.221255 0.0424228 -0.0591147 0.221627 0.0352644 -0.0556761 0.222207 0.0419716 -0.0600164 0.222207 0.0493294 -0.0631644 0.221255 0.0353677 -0.0550219 0.222207 0.0350409 -0.056015 0.2229 0.034962 -0.0561344 0.220782 0.0301274 -0.0494553 0.220692 0.0306618 -0.0488242 0.220684 0.050366 -0.0602763 0.220692 0.0367676 -0.053398 0.220782 0.0363122 -0.0540883 0.220692 0.0433745 -0.0572125 0.220779 0.0505108 -0.0598728 0.220993 0.0371946 -0.0527509 0.220993 0.0311628 -0.0482324 0.222427 0.031645 -0.0476629 0.220993 0.0506505 -0.0594837 0.221291 0.0507613 -0.0591749 0.220993 0.0437215 -0.0565192 0.221619 0.0374967 -0.0522931 0.221619 0.0439669 -0.0560286 0.222427 0.0440554 -0.0558518 0.222427 0.0509026 -0.0587813 0.220854 0.0504853 -0.0613356 0.221019 0.0498896 -0.0616035 0.22116 0.050257 -0.0621444 0.22102 0.0505071 -0.061825 0.221255 0.0292874 -0.0504474 0.221184 0.0290557 -0.0499933 0.221019 0.0297074 -0.0499513 0.220807 0.0298605 -0.0493188 0.221099 0.0290951 -0.0497191 0.220782 0.0360881 -0.0539398 0.221255 0.0355962 -0.0551733 0.220782 0.0430045 -0.0579521 0.220782 0.0432459 -0.0580722 0.221231 0.0499683 -0.0622495 0.224574 0.0524918 -0.0610402 0.222499 0.0522783 -0.0600507 0.224574 0.0522941 -0.0600863 0.224574 0.0517336 -0.0592896 0.224774 0.0526918 -0.0610402 0.224574 0.0509026 -0.0587813 0.224774 0.0518704 -0.0591437 0.224974 0.029457 -0.0505589 0.227954 0.0296466 -0.0495744 0.224974 0.0297183 -0.0494116 0.228112 0.0303925 -0.0485383 0.228169 0.0307887 -0.0482601 0.224974 0.0304505 -0.0484905 0.224974 0.0315094 -0.0479772 0.228253 0.0315167 -0.0479755 0.228377 0.0337486 -0.0484786 0.224974 0.0337486 -0.0484786 0.224974 0.0326861 -0.0479729 0.224774 0.029257 -0.0505589 0.224774 0.029538 -0.049325 0.224774 0.0303255 -0.0483343 0.224774 0.0314643 -0.0477823 0.224974 0.0471828 -0.062291 0.224774 0.048362 -0.0626723 0.224974 0.048348 -0.0624728 0.224974 0.049319 -0.0622141 0.224974 0.0494768 -0.0621309 0.224974 0.0507819 -0.0602376 0.224974 0.0506425 -0.0588923 0.224774 0.050678 -0.0584873 0.224974 0.0297224 -0.0517148 0.224774 0.0295424 -0.0518021 0.224774 0.0277195 -0.0505533 0.224774 0.0274953 -0.0494181 0.224774 0.0285335 -0.047415 0.224774 0.0317743 -0.0475103 0.224774 0.0509796 -0.0602685 0.224774 0.0505101 -0.0614467 0.224774 0.0495759 -0.0623047 0.224774 0.041818 -0.0603233 0.224774 0.0471087 -0.0624768 0.224774 0.038375 -0.0582431 0.224774 0.0348519 -0.0563014 0.224774 0.0284141 -0.0514788 0.224774 0.0509702 -0.058593 0.224774 0.0508913 -0.0590032 0.224774 0.0524776 -0.0600068 0.224774 0.0492185 -0.0571816 0.224974 0.041125 -0.0534799 0.224774 0.041225 -0.0533067 0.224974 0.0491445 -0.0573674 0.228377 0.0437347 -0.054904 0.224974 0.038475 -0.0580699 0.224774 0.0303416 -0.0527962 0.227721 0.0304655 -0.0526392 0.227748 0.029779 -0.051825 0.22782 0.0294705 -0.0508263 0.227845 0.029457 -0.0505589 0.224974 0.0501155 -0.0580367 0.22835 0.0500342 -0.0579522 0.224974 0.0506999 -0.0590611 0.227984 0.0503918 -0.0612636 0.22782 0.0492501 -0.0622462 0.227843 0.0494761 -0.0621313 0.224974 0.0503454 -0.0613332 0.230112 0.0430382 -0.0562568 0.230021 0.0482752 -0.0595491 0.22981 0.0433931 -0.0555675 0.229185 0.0384798 -0.0520982 0.228753 0.0337232 -0.0485107 0.228377 0.0385868 -0.0519319 0.228377 0.041125 -0.0534799 0.228377 0.0491445 -0.0573674 0.22981 0.038183 -0.0525594 0.228753 0.0491293 -0.0574055 0.229185 0.0436442 -0.0550798 0.230024 0.0330304 -0.0493887 0.230024 0.0487153 -0.0584444 0.230112 0.0377635 -0.0532115 0.230021 0.0399503 -0.0555136 0.230021 0.0426597 -0.0569921 0.227721 0.0343721 -0.0554992 0.224974 0.0304655 -0.0526392 0.228623 0.0316693 -0.0479815 0.229465 0.0308362 -0.0511159 0.22994 0.0315102 -0.0494117 0.22992 0.0316121 -0.0501329 0.229765 0.0309552 -0.0496395 0.23001 0.032092 -0.0502015 0.229158 0.030519 -0.0516497 0.2294 0.0309198 -0.0514113 0.229578 0.0305543 -0.0500429 0.229024 0.0298819 -0.0502881 0.229402 0.0303389 -0.0505551 0.22887 0.0298724 -0.0510588 0.227758 0.0296903 -0.0516463 0.22836 0.0295756 -0.0509563 0.228494 0.0296128 -0.050023 0.228771 0.0297196 -0.0501517 0.228654 0.0299873 -0.0491669 0.228088 0.0294995 -0.0508931 0.228271 0.0298861 -0.051851 0.229213 0.0301691 -0.0495694 0.228492 0.0307103 -0.0483438 0.228047 0.0300272 -0.0489167 0.22981 0.0332863 -0.0490644 0.22976 0.032409 -0.0486555 0.229512 0.0334896 -0.0488067 0.229185 0.0336261 -0.0486338 0.229099 0.0326478 -0.0481385 0.228718 0.0327357 -0.0480252 0.228982 0.0315918 -0.0481154 0.229322 0.0315313 -0.0483407 0.229417 0.030719 -0.0489901 0.229459 0.0325364 -0.0483508 0.229612 0.0314955 -0.0486493 0.228349 0.0327766 -0.0479949 0.228276 0.0317553 -0.0479323 0.228994 0.0308056 -0.0522082 0.229804 0.0312592 -0.0502568 0.22964 0.0309453 -0.0505826 0.229256 0.0303255 -0.0511134 0.228767 0.0301422 -0.0517917 0.228207 0.0295627 -0.0499077 0.228347 0.0299826 -0.0490207 0.228824 0.0306667 -0.0484943 0.22895 0.030049 -0.0493525 0.229141 0.030668 -0.0487128 0.229822 0.0314888 -0.0490175 0.229968 0.0322773 -0.0490272 0.23007 0.0321538 -0.0494281 0.230112 0.032806 -0.0496731 0.227749 0.0482528 -0.0624777 0.228767 0.0480781 -0.0621471 0.229742 0.0488277 -0.0605865 0.22994 0.0494555 -0.0597725 0.229886 0.048819 -0.0601594 0.23007 0.0491197 -0.0592235 0.230112 0.0485813 -0.0587809 0.229402 0.0490512 -0.0613583 0.229579 0.0486198 -0.0609885 0.229024 0.0495112 -0.0616204 0.229691 0.0487862 -0.0607207 0.229765 0.0495358 -0.0603665 0.229578 0.0493871 -0.0609152 0.229417 0.0502163 -0.0602462 0.229822 0.0498076 -0.059594 0.229612 0.0501231 -0.0594041 0.22976 0.0496613 -0.0586162 0.229968 0.0494052 -0.0589161 0.228363 0.0498111 -0.0577535 0.228276 0.0506142 -0.0588206 0.228623 0.0506146 -0.0589197 0.228169 0.0508136 -0.0598206 0.228143 0.0508048 -0.0600454 0.227925 0.0500839 -0.0616554 0.227827 0.0493192 -0.0622139 0.228047 0.0506262 -0.060808 0.228207 0.0500002 -0.0617065 0.227967 0.0503112 -0.0613816 0.228088 0.0491777 -0.0622546 0.228271 0.0481547 -0.0623986 0.22836 0.049085 -0.0622202 0.228772 0.0497104 -0.0616927 0.228494 0.0498753 -0.0617208 0.22895 0.0502379 -0.0610072 0.229322 0.0503725 -0.0592188 0.229099 0.0499896 -0.058151 0.229185 0.0490713 -0.0575511 0.228718 0.0500439 -0.0580182 0.228982 0.0505374 -0.0590538 0.228492 0.0507804 -0.0599304 0.228824 0.0506718 -0.0600434 0.228347 0.0505585 -0.0608987 0.228655 0.0504295 -0.0609677 0.228415 0.0472357 -0.062158 0.229377 0.0478377 -0.0612797 0.229158 0.0480127 -0.0617499 0.229256 0.048574 -0.0616493 0.22887 0.0488478 -0.0620144 0.229213 0.04999 -0.0610118 0.229141 0.050482 -0.0601516 0.229459 0.0498615 -0.0583536 0.22981 0.0488683 -0.0580606 0.229512 0.0489897 -0.0577557 0.221497 0.0585257 -0.0638983 0.221242 0.060024 -0.0649702 0.220692 0.0606107 -0.0629524 0.220855 0.0599646 -0.0638768 0.220879 0.0598966 -0.0639325 0.220982 0.0597288 -0.0641891 0.221184 0.0598043 -0.064768 0.221275 0.0591385 -0.0645943 0.221099 0.0597014 -0.0645108 0.221132 0.0590893 -0.0641356 0.220952 0.0593314 -0.0629503 0.220827 0.0599416 -0.0626289 0.221162 0.059164 -0.0626219 0.221036 0.059883 -0.0622387 0.220979 0.0592194 -0.0636798 0.220834 0.0595358 -0.0632883 0.220726 0.0600211 -0.063041 0.222499 0.0590554 -0.0618667 0.222151 0.0590027 -0.0619504 0.222253 0.0583926 -0.0626502 0.222607 0.0582686 -0.0628255 0.222078 0.0598746 -0.0615285 0.22205 0.0608743 -0.0614955 0.222752 0.0581033 -0.064299 0.222823 0.0584228 -0.0650946 0.222664 0.0580929 -0.063388 0.222722 0.0580599 -0.0639794 0.221627 0.0601248 -0.0656382 0.22147 0.0597038 -0.0653173 0.221861 0.0594376 -0.0656198 0.221905 0.0584009 -0.064529 0.222183 0.0582458 -0.0644653 0.222056 0.0581754 -0.0636279 0.221761 0.0583174 -0.063763 0.221792 0.0589974 -0.0621051 0.221452 0.0590502 -0.0623325 0.221696 0.0598505 -0.0616699 0.221336 0.059852 -0.0619098 0.22192 0.0584251 -0.0628036 0.222364 0.0581024 -0.0635009 0.22247 0.0581473 -0.0643869 0.22256 0.0585175 -0.0651982 0.222288 0.0586146 -0.0652183 0.222358 0.0592391 -0.0657925 0.221778 0.0589253 -0.0651694 0.221392 0.0593515 -0.0650046 0.221653 0.0586086 -0.0645732 0.221327 0.0587048 -0.063217 0.221603 0.0585291 -0.062996 0.221498 0.0838477 -0.0654868 0.221627 0.0759772 -0.0665851 0.221627 0.0680227 -0.0665851 0.221255 0.0759413 -0.0659838 0.222383 0.083959 -0.0661015 0.2229 0.0760099 -0.0671332 0.22189 0.0600841 -0.0658631 0.222207 0.0679985 -0.0669903 0.222207 0.0600525 -0.0660376 0.222207 0.0760014 -0.0669903 0.2229 0.06799 -0.0671332 0.222383 0.060041 -0.0661015 0.221619 0.0608464 -0.0616497 0.220782 0.0758638 -0.0646861 0.220684 0.0834011 -0.0630182 0.220782 0.0678679 -0.0646695 0.220692 0.0681855 -0.0638606 0.220692 0.0758145 -0.0638606 0.221291 0.0608071 -0.0618667 0.220993 0.0607487 -0.0621895 0.220779 0.0606751 -0.0625964 0.222427 0.0608816 -0.0614552 0.220779 0.0833248 -0.0625963 0.220993 0.0757682 -0.0630867 0.221619 0.0831535 -0.0616497 0.220993 0.0682317 -0.0630867 0.221619 0.0682644 -0.0625391 0.221619 0.0757355 -0.0625391 0.222427 0.0831183 -0.0614552 0.220782 0.0761329 -0.0646695 0.22102 0.0842977 -0.0642888 0.22094 0.0842206 -0.0640805 0.221231 0.0840433 -0.0649258 0.221019 0.0836522 -0.0644058 0.22116 0.0842407 -0.0646905 0.221057 0.0843077 -0.0643914 0.221255 0.060232 -0.0650454 0.220807 0.0601641 -0.0637815 0.22102 0.0597023 -0.0642886 0.221019 0.0603478 -0.0644058 0.220782 0.0604635 -0.0637662 0.221255 0.067785 -0.0659669 0.221255 0.0680586 -0.0659838 0.220782 0.0681361 -0.0646861 0.221255 0.0762158 -0.0659668 0.222576 0.0855778 -0.0625401 0.224574 0.0831183 -0.0614552 0.224574 0.0859456 -0.0638168 0.224574 0.0857196 -0.0628001 0.224774 0.0859008 -0.0627154 0.224574 0.0850842 -0.0619749 0.224574 0.084159 -0.0614965 0.224774 0.0842101 -0.0613032 0.228258 0.0609611 -0.0617587 0.224974 0.0631111 -0.0611097 0.224774 0.0619301 -0.0609966 0.224974 0.0619862 -0.0611886 0.224774 0.0601377 -0.0625471 0.224974 0.0603196 -0.0626303 0.224974 0.060996 -0.061728 0.224774 0.0608651 -0.0615767 0.228377 0.0631111 -0.0611097 0.228377 0.0690278 -0.0616813 0.224974 0.072 -0.0617529 0.224774 0.0816805 -0.0665525 0.224974 0.0623482 -0.0663545 0.227748 0.0613466 -0.0659926 0.224974 0.0603736 -0.0649451 0.227864 0.0603453 -0.0648886 0.228 0.0600797 -0.0637321 0.227872 0.0603096 -0.0648119 0.224974 0.0808888 -0.0611097 0.228363 0.0816591 -0.0611108 0.224974 0.0820644 -0.0612039 0.228169 0.0835609 -0.0623997 0.228047 0.0838923 -0.0633485 0.224974 0.083742 -0.0627767 0.227721 0.0816517 -0.0663545 0.22782 0.0834197 -0.0652821 0.224974 0.0839118 -0.0639438 0.227967 0.0839063 -0.0640028 0.230112 0.0811078 -0.0626155 0.229185 0.0630827 -0.0613054 0.229185 0.0690183 -0.0618788 0.229185 0.0749816 -0.0618788 0.228377 0.072 -0.0617529 0.228377 0.0749721 -0.0616813 0.229512 0.063051 -0.0615234 0.228753 0.0808947 -0.0611503 0.22981 0.0809962 -0.0618482 0.230024 0.0629443 -0.062257 0.230112 0.0689546 -0.0632011 0.22981 0.0689919 -0.0624267 0.230112 0.0750453 -0.0632011 0.22981 0.075008 -0.0624267 0.230024 0.0810557 -0.062257 0.230112 0.0628921 -0.0626155 0.230021 0.0689148 -0.0640271 0.230021 0.0750851 -0.0640271 0.230021 0.0812268 -0.0634338 0.224974 0.0816517 -0.0663545 0.224974 0.072 -0.0670529 0.227721 0.0623482 -0.0663545 0.227721 0.0671615 -0.0668781 0.227721 0.072 -0.0670529 0.227722 0.0622075 -0.0663303 0.229498 0.0618428 -0.064747 0.229256 0.0614641 -0.0651031 0.229939 0.06215 -0.0635675 0.229765 0.0612724 -0.0635118 0.22976 0.0620395 -0.0619328 0.229822 0.0614236 -0.0627064 0.22994 0.0616392 -0.063037 0.229968 0.0621113 -0.0623205 0.23007 0.0622048 -0.0627294 0.23001 0.062538 -0.0634301 0.230021 0.0627731 -0.0634338 0.229158 0.0618998 -0.0654709 0.2294 0.0621277 -0.065064 0.228347 0.0601208 -0.0634622 0.227764 0.0610922 -0.0658158 0.228088 0.0606386 -0.0653254 0.22782 0.0605801 -0.0652819 0.228207 0.0602007 -0.0644404 0.229691 0.0617447 -0.0641933 0.229578 0.061127 -0.0640616 0.229402 0.0611965 -0.064613 0.22964 0.0617354 -0.0643336 0.228767 0.0616445 -0.0657822 0.228753 0.0631052 -0.0611503 0.228718 0.0620072 -0.0612236 0.228349 0.0620275 -0.0611769 0.228623 0.0610619 -0.0617189 0.228276 0.0611118 -0.0616333 0.228492 0.0604125 -0.0625122 0.227925 0.0601537 -0.0643543 0.228047 0.0601074 -0.0633498 0.228117 0.0602506 -0.0627958 0.228169 0.0604386 -0.0624005 0.228494 0.0603017 -0.0645152 0.228654 0.060198 -0.0635865 0.228824 0.06045 -0.0626643 0.229141 0.0605604 -0.0628529 0.229322 0.061122 -0.062099 0.228982 0.0610617 -0.0618736 0.22836 0.0607361 -0.065342 0.229099 0.0619878 -0.0613656 0.228239 0.0623595 -0.0662772 0.228271 0.0614524 -0.0659616 0.228994 0.0624273 -0.0658112 0.228771 0.0604585 -0.0645732 0.22887 0.0610444 -0.0652823 0.229024 0.0606672 -0.0646102 0.22895 0.0603442 -0.0637164 0.229213 0.0605567 -0.0638442 0.229417 0.0607432 -0.0630675 0.229612 0.0612453 -0.0623841 0.229459 0.0619974 -0.0616052 0.22981 0.0630037 -0.0618482 0.229578 0.0828729 -0.0640609 0.22994 0.0823607 -0.0630371 0.229886 0.0820029 -0.0636904 0.229987 0.0816392 -0.0634682 0.229402 0.0828035 -0.0646126 0.229213 0.0834432 -0.0638431 0.229765 0.0827272 -0.0635114 0.229822 0.0825764 -0.0627065 0.229417 0.0832564 -0.0630669 0.229612 0.0827547 -0.0623842 0.229968 0.0818889 -0.0623206 0.22976 0.0819608 -0.0619329 0.23007 0.0817953 -0.0627296 0.22835 0.0819517 -0.0611713 0.228276 0.0828882 -0.0616334 0.228143 0.0836657 -0.0625988 0.228492 0.083587 -0.0625114 0.228718 0.0819931 -0.0612237 0.228377 0.0808888 -0.0611097 0.228207 0.0837994 -0.0644397 0.227843 0.0835579 -0.0650696 0.227827 0.0834634 -0.0652196 0.228347 0.083879 -0.063461 0.227984 0.0839171 -0.0638603 0.227925 0.0838463 -0.0643536 0.227749 0.0826717 -0.0659812 0.228655 0.0838018 -0.0635852 0.229185 0.0809172 -0.0613054 0.229099 0.0820125 -0.0613657 0.228623 0.0829381 -0.061719 0.228982 0.0829383 -0.0618737 0.228824 0.0835495 -0.0626636 0.228494 0.0836984 -0.0645145 0.228088 0.0833612 -0.0653256 0.22836 0.0832637 -0.0653422 0.228271 0.0825472 -0.0659618 0.228415 0.0816311 -0.0662129 0.228767 0.0823552 -0.0657823 0.229377 0.0817132 -0.0651513 0.229158 0.0820999 -0.065471 0.229256 0.0825358 -0.0651032 0.229024 0.0833329 -0.0646096 0.22887 0.0829554 -0.0652825 0.228772 0.0835416 -0.0645726 0.22895 0.0836556 -0.0637152 0.229141 0.0834392 -0.0628522 0.229322 0.082878 -0.0620991 0.229459 0.0820028 -0.0616053 0.229512 0.0809489 -0.0615234 0.229366 0.0814859 -0.0652151 0.22992 0.0620881 -0.0636107 0.229465 0.0619076 -0.0648499 0.229804 0.0618444 -0.0638945 0.229742 0.082224 -0.064056 0.229694 0.0813564 -0.0643244 0.229691 0.0822552 -0.0641929 0.229446 0.0820459 -0.0649083 0.229464 0.0820923 -0.06485 0.229579 0.0822449 -0.064508 0.230021 0.0719995 -0.0641014 0.229366 0.072 -0.0659014 0.229366 0.0672446 -0.0657296 0.229694 0.0626435 -0.0643244 0.228415 0.0623688 -0.0662129 0.228731 0.0623943 -0.0660376 0.229366 0.062514 -0.0652151 0.228994 0.0672011 -0.0663304 0.228994 0.0767988 -0.0663304 0.228994 0.0815727 -0.0658112 0.229366 0.0767554 -0.0657296 0.228731 0.0816056 -0.0660375 0.228415 0.0768281 -0.0667353 0.228994 0.072 -0.0665038 0.228239 0.0816404 -0.0662772 0.227721 0.0768384 -0.0668781 0.228415 0.072 -0.0669097 0.228415 0.0671718 -0.0667353 0.224574 0.0608816 -0.0614552 0.224774 0.0612231 -0.0613129 0.224574 0.0682762 -0.0623417 0.224774 0.0682881 -0.0621421 0.224574 0.0760099 -0.0671332 0.224574 0.0839729 -0.0661785 0.224774 0.0760219 -0.0673328 0.224574 0.0856919 -0.0648907 0.224774 0.0858708 -0.0649802 0.224774 0.0861456 -0.0638168 0.224574 0.0584229 -0.0650948 0.224574 0.0581954 -0.0646276 0.224774 0.0580072 -0.0646952 0.224574 0.0580927 -0.0633895 0.224574 0.0582686 -0.0628254 0.224774 0.059576 -0.0613697 0.224574 0.0586227 -0.0622659 0.224774 0.0631399 -0.0609118 0.224774 0.072 -0.0615529 0.224774 0.08086 -0.0609118 0.224774 0.0757118 -0.0621421 0.224774 0.0821243 -0.0610131 0.224574 0.0849845 -0.0657376 0.222801 0.0857184 -0.0648361 0.222437 0.0601791 -0.0614326 0.222446 0.0599175 -0.0614776 0.224574 0.0596435 -0.0615579 0.224574 0.0589994 -0.0619081 0.224574 0.0580598 -0.0639795 0.222705 0.0580544 -0.0638037 0.222591 0.0583394 -0.0626823 0.224574 0.0589034 -0.0656484 0.222878 0.0590754 -0.0657811 0.222828 0.0584604 -0.0651526 0.222808 0.0583205 -0.0649153 0.2229 0.060027 -0.0661785 0.224574 0.060027 -0.0661785 0.224574 0.06799 -0.0671332 0.2229 0.0839729 -0.0661785 0.224574 0.0757237 -0.0623417 0.222427 0.0757237 -0.0623417 0.222427 0.0682762 -0.0623417 0.221231 0.0840433 -0.0649258 0.221255 0.0837679 -0.0650454 0.220854 0.0840341 -0.063876 0.220979 0.0847808 -0.0636801 0.220796 0.0837576 -0.0637637 0.220782 0.0835364 -0.0637662 0.220952 0.0846685 -0.0629502 0.221284 0.0852109 -0.0640257 0.221132 0.0849107 -0.0641362 0.22094 0.0842206 -0.0640805 0.221327 0.0852954 -0.0632175 0.220827 0.0840581 -0.0626287 0.220834 0.0844641 -0.0632882 0.220726 0.0839787 -0.0630408 0.220692 0.0833892 -0.0629524 0.221778 0.0850747 -0.0651693 0.222752 0.0858965 -0.0642997 0.22247 0.0858525 -0.0643875 0.222881 0.0848681 -0.0658196 0.22256 0.0854825 -0.065198 0.222874 0.0849958 -0.0657291 0.222828 0.0855396 -0.0651525 0.222078 0.084125 -0.0615284 0.222449 0.0841486 -0.0614938 0.222499 0.0849444 -0.0618666 0.222151 0.0849971 -0.0619503 0.222253 0.0856077 -0.0626508 0.222516 0.085117 -0.0620028 0.222706 0.0859456 -0.0638168 0.222364 0.0858977 -0.0635021 0.222664 0.0859072 -0.0633892 0.222618 0.0857764 -0.0629317 0.222288 0.0853854 -0.0652182 0.222183 0.0857539 -0.0644659 0.221905 0.0855989 -0.0645295 0.222056 0.0858246 -0.063629 0.221792 0.0850024 -0.062105 0.221921 0.0855752 -0.0628042 0.22205 0.0831256 -0.0614955 0.221696 0.0841491 -0.0616698 0.22147 0.0842963 -0.0653172 0.221627 0.0838751 -0.0656382 0.22189 0.0839158 -0.0658631 0.221057 0.0843077 -0.0643914 0.221392 0.0846485 -0.0650046 0.221565 0.0848716 -0.0650999 0.221861 0.0845626 -0.0656196 0.222207 0.0839474 -0.0660376 0.222358 0.0847611 -0.0657923 0.221653 0.0853912 -0.0645737 0.221761 0.0856826 -0.063764 0.221498 0.0854743 -0.0638991 0.221603 0.0854711 -0.0629966 0.221162 0.0848358 -0.0626218 0.221452 0.0849496 -0.0623324 0.221336 0.0841475 -0.0619096 0.221036 0.0841166 -0.0622386 0.221291 0.0831928 -0.0618667 0.220993 0.0832512 -0.0621895 0.224974 0.0827517 -0.0659293 0.224774 0.0828636 -0.0660952 0.224974 0.0834632 -0.0652198 0.224974 0.0835584 -0.0650689 0.224774 0.0841111 -0.0639598 0.224974 0.0830827 -0.0617989 0.224974 0.0829485 -0.0616813 0.224774 0.0827768 -0.0613129 0.224774 0.0623194 -0.0665525 0.224974 0.0611902 -0.0658891 0.224774 0.061074 -0.0660519 0.224974 0.0600797 -0.0637321 0.224774 0.0598797 -0.0637321 0.224774 0.0587742 -0.0658011 0.224774 0.0601958 -0.0650367 0.224774 0.0578959 -0.0633539 0.224774 0.0584701 -0.0621367 0.224774 0.0609172 -0.0612583 0.224774 0.0830827 -0.0612583 0.224774 0.0832195 -0.061653 0.224774 0.0839286 -0.0627046 0.224774 0.0852124 -0.0618214 0.224774 0.0599914 -0.0663753 0.224774 0.067978 -0.0673328 0.224774 0.072 -0.0672529 0.224774 0.0840085 -0.0663753 0.224774 0.083731 -0.0651698 0.224774 0.0851044 -0.0658977 0.224774 0.115586 -0.0514788 0.224574 0.116306 -0.0494945 0.224774 0.0936377 -0.0636261 0.224774 0.0913269 -0.061352 0.224774 0.0930298 -0.058593 0.224574 0.0921975 -0.0593568 0.224574 0.0916938 -0.0601146 0.224574 0.0916365 -0.0602657 0.224574 0.0915254 -0.061328 0.224774 0.111273 -0.0477771 0.224774 0.0947814 -0.0571816 0.224774 0.099855 -0.0556729 0.224774 0.102775 -0.0533067 0.224574 0.115457 -0.0513262 0.224574 0.116083 -0.050504 0.222878 0.116088 -0.0504937 0.222828 0.1163 -0.0496542 0.224574 0.0930973 -0.0587813 0.222446 0.0922737 -0.0592828 0.222705 0.0918231 -0.0622288 0.224574 0.0936585 -0.0634272 0.224574 0.0927878 -0.0631627 0.222828 0.0928493 -0.063194 0.224574 0.0926476 -0.0630825 0.222823 0.0927876 -0.0631626 0.224574 0.0918863 -0.0623333 0.222752 0.0921131 -0.0626333 0.224574 0.0947189 -0.0632991 0.224574 0.102092 -0.0601444 0.224574 0.109038 -0.0561344 0.2229 0.115457 -0.0513262 0.222427 0.112355 -0.0476629 0.224574 0.106394 -0.052128 0.222427 0.0930973 -0.0587813 0.220979 0.114907 -0.0487585 0.220834 0.114437 -0.0485775 0.220796 0.114063 -0.0493426 0.220782 0.113872 -0.0494553 0.220993 0.112837 -0.0482324 0.22094 0.114622 -0.0493855 0.220952 0.114445 -0.0481826 0.220827 0.113756 -0.0482094 0.220726 0.113893 -0.048606 0.221327 0.115121 -0.0481007 0.221057 0.114853 -0.0496111 0.221392 0.115455 -0.0499717 0.221565 0.115696 -0.0499427 0.22147 0.115306 -0.0504186 0.222364 0.115785 -0.0480459 0.222288 0.1162 -0.0497882 0.22256 0.116274 -0.0497223 0.222664 0.115737 -0.0479434 0.222514 0.114345 -0.0471351 0.222519 0.114405 -0.047147 0.222253 0.115109 -0.0474537 0.222576 0.115027 -0.0473728 0.222056 0.115786 -0.0481924 0.221761 0.11573 -0.0483803 0.221921 0.115157 -0.0476028 0.221452 0.114379 -0.047507 0.221792 0.114311 -0.0472837 0.221696 0.113355 -0.0473334 0.221336 0.113473 -0.0475419 0.221619 0.112483 -0.0478138 0.22247 0.116189 -0.0488353 0.222183 0.116143 -0.0489525 0.222151 0.11423 -0.0471524 0.222078 0.113263 -0.0472231 0.22205 0.112381 -0.0476942 0.221231 0.114891 -0.0502061 0.22102 0.114793 -0.0495273 0.221132 0.115248 -0.0490886 0.221284 0.115452 -0.0488428 0.221778 0.115906 -0.0499013 0.222358 0.115946 -0.0505976 0.221861 0.115688 -0.0505473 0.221653 0.115883 -0.0492272 0.221905 0.11604 -0.0490851 0.221498 0.115617 -0.0486015 0.221603 0.115163 -0.0478214 0.221162 0.114426 -0.0478145 0.221291 0.112625 -0.0479821 0.221036 0.113611 -0.0478423 0.2229 0.0947189 -0.0632991 0.22189 0.0946106 -0.0629975 0.221627 0.0945334 -0.0627823 0.221242 0.0941121 -0.0622542 0.220726 0.093145 -0.0605849 0.220879 0.093483 -0.0614192 0.221275 0.0931573 -0.0623714 0.221099 0.0936031 -0.0620177 0.22147 0.0940084 -0.0627149 0.221132 0.0928854 -0.0619988 0.221653 0.0926879 -0.0626181 0.221392 0.093547 -0.0626203 0.221327 0.0920931 -0.0613955 0.220827 0.0928701 -0.0602678 0.220982 0.093466 -0.0617253 0.220979 0.0927701 -0.061539 0.220952 0.0925024 -0.0608512 0.220834 0.0928484 -0.0610417 0.220779 0.0934891 -0.0598729 0.222078 0.0922619 -0.0593483 0.222499 0.0917215 -0.0600508 0.222591 0.0915093 -0.0611152 0.222253 0.0915393 -0.0610607 0.222607 0.0915196 -0.0612745 0.22205 0.0931112 -0.0588199 0.222437 0.0924776 -0.059113 0.22256 0.0929215 -0.0632049 0.222808 0.0926094 -0.0630584 0.222364 0.0917133 -0.0619426 0.222664 0.0916487 -0.0618495 0.22247 0.0921952 -0.0626874 0.222722 0.0919158 -0.0623782 0.222358 0.0938436 -0.0633588 0.222878 0.0936961 -0.0634308 0.222383 0.0946925 -0.0632255 0.222207 0.0946705 -0.0631644 0.222288 0.0930156 -0.0631738 0.221778 0.0932603 -0.062976 0.222183 0.0923198 -0.062706 0.221761 0.0920306 -0.062062 0.221452 0.0919499 -0.0604568 0.221792 0.0917905 -0.0602862 0.221619 0.0931641 -0.0589674 0.221696 0.0923117 -0.0594828 0.222151 0.0917178 -0.0601496 0.22192 0.0916441 -0.0611773 0.222056 0.0918401 -0.062016 0.221861 0.0939291 -0.06311 0.221905 0.0924859 -0.0626836 0.221497 0.0922786 -0.062075 0.221162 0.0921932 -0.0606505 0.221603 0.0918304 -0.061292 0.221336 0.092433 -0.0596898 0.221036 0.0926243 -0.0599592 0.221627 0.108735 -0.0556761 0.221627 0.115102 -0.0509071 0.221498 0.115002 -0.0507897 0.221255 0.108404 -0.0551733 0.222383 0.115406 -0.0512665 0.222207 0.115364 -0.0512169 0.2229 0.109038 -0.0561344 0.222207 0.108959 -0.056015 0.221627 0.101847 -0.0596534 0.222207 0.102028 -0.0600164 0.22189 0.11525 -0.0510816 0.2229 0.102092 -0.0601444 0.220782 0.107688 -0.0540883 0.220692 0.107232 -0.053398 0.220782 0.100755 -0.0580719 0.220692 0.0936114 -0.0602134 0.220684 0.113381 -0.0488751 0.220993 0.100278 -0.0565192 0.220692 0.113338 -0.0488242 0.220692 0.100625 -0.0572125 0.220782 0.100995 -0.0579521 0.220779 0.113104 -0.048548 0.221291 0.0932386 -0.0591749 0.220993 0.0933494 -0.0594837 0.222427 0.0999445 -0.0558518 0.221619 0.100033 -0.0560286 0.220993 0.106805 -0.0527509 0.221619 0.106503 -0.0522931 0.222427 0.106394 -0.052128 0.220782 0.107912 -0.0539393 0.221019 0.114293 -0.0499513 0.220854 0.114358 -0.0493015 0.22116 0.114945 -0.0499036 0.221019 0.0941103 -0.0616035 0.221255 0.0943299 -0.0622153 0.221255 0.101332 -0.0592369 0.221184 0.0938208 -0.0621889 0.220782 0.0938907 -0.0609917 0.220807 0.0936391 -0.0611547 0.220855 0.093514 -0.061337 0.220982 0.093466 -0.0617253 0.22102 0.0934927 -0.0618247 0.221255 0.101577 -0.0591147 0.221255 0.108633 -0.0550214 0.221255 0.114713 -0.0504474 0.222817 0.116306 -0.0494945 0.222735 0.116119 -0.048566 0.224574 0.114398 -0.0471457 0.222622 0.115429 -0.0476401 0.222499 0.114142 -0.0471062 0.222449 0.113266 -0.0471812 0.224574 0.116062 -0.0484405 0.224574 0.11538 -0.0476007 0.224774 0.115503 -0.0474429 0.224574 0.113317 -0.0471679 0.224774 0.11444 -0.0469499 0.224774 0.113268 -0.046974 0.224574 0.112355 -0.0476629 0.224774 0.112226 -0.0475103 0.228276 0.0933858 -0.0588205 0.224974 0.0939795 -0.0579385 0.228353 0.0940174 -0.057902 0.224974 0.0948555 -0.0573674 0.224774 0.0938393 -0.0577958 0.224774 0.0932082 -0.0587266 0.224974 0.0933926 -0.058804 0.224774 0.114743 -0.0505736 0.224974 0.114543 -0.0505725 0.224974 0.110251 -0.0484786 0.224974 0.112321 -0.0479437 0.224774 0.111988 -0.0477105 0.224974 0.0931863 -0.0598292 0.224774 0.0933183 -0.0611641 0.224774 0.0968912 -0.0624768 0.224974 0.0948501 -0.0622888 0.224974 0.0939164 -0.0616557 0.224774 0.0942369 -0.0621881 0.224774 0.0925425 -0.0632527 0.224774 0.0917178 -0.0624411 0.224774 0.112541 -0.0477837 0.224774 0.0914472 -0.0602011 0.224774 0.092055 -0.0592165 0.224774 0.0929863 -0.0598292 0.224774 0.113681 -0.0483399 0.224774 0.116242 -0.0483527 0.224774 0.116506 -0.0494945 0.224774 0.114467 -0.0493356 0.224774 0.114454 -0.0518087 0.224774 0.116265 -0.0505881 0.224774 0.113658 -0.0527962 0.224774 0.105625 -0.0582431 0.224774 0.109148 -0.0563014 0.224774 0.102182 -0.0603233 0.224774 0.0947865 -0.0634873 0.224774 0.0955281 -0.0626625 0.224774 0.110127 -0.0483216 0.224974 0.102875 -0.0534799 0.228377 0.102875 -0.0534799 0.224974 0.105525 -0.0580699 0.224974 0.0968172 -0.062291 0.227748 0.0957688 -0.0624783 0.224974 0.0955498 -0.0624636 0.227759 0.0955501 -0.0624637 0.224974 0.0943491 -0.0620225 0.227925 0.0939166 -0.0616559 0.224974 0.093495 -0.0610705 0.228363 0.110919 -0.0480943 0.224974 0.111317 -0.0479723 0.22835 0.111203 -0.0480004 0.224974 0.112496 -0.0479784 0.224974 0.113556 -0.0484956 0.228047 0.113972 -0.0489157 0.227967 0.114311 -0.0494753 0.224974 0.114275 -0.051721 0.224974 0.114536 -0.0507508 0.227827 0.114536 -0.0507505 0.224974 0.114286 -0.0494214 0.227843 0.114543 -0.0505733 0.228377 0.0948555 -0.0573674 0.229512 0.0950102 -0.0577557 0.229185 0.0949286 -0.0575511 0.228377 0.100265 -0.054904 0.229185 0.10552 -0.0520982 0.228377 0.105413 -0.0519319 0.22981 0.100607 -0.0555675 0.22981 0.0951317 -0.0580606 0.228377 0.110251 -0.0484786 0.229185 0.110374 -0.0486338 0.22981 0.105817 -0.0525594 0.230024 0.0952846 -0.0584444 0.229185 0.100356 -0.0550798 0.22981 0.110714 -0.0490644 0.230021 0.0957247 -0.0595491 0.230021 0.10134 -0.0569921 0.230112 0.100962 -0.0562568 0.230112 0.106236 -0.0532115 0.230021 0.111706 -0.0503222 0.227721 0.105525 -0.0580699 0.224974 0.113534 -0.0526392 0.227721 0.109628 -0.0554992 0.227721 0.113534 -0.0526392 0.229465 0.0956832 -0.0612082 0.229256 0.0954257 -0.0616493 0.229939 0.0952519 -0.0599764 0.22994 0.0945444 -0.0597724 0.229578 0.0946131 -0.0609159 0.23007 0.0948804 -0.0592233 0.229968 0.0945949 -0.0589158 0.22976 0.0943389 -0.058616 0.229822 0.0941923 -0.0595939 0.23001 0.0955193 -0.0596634 0.230112 0.0954186 -0.0587809 0.229158 0.095987 -0.0617499 0.229765 0.0944642 -0.060367 0.229213 0.0940104 -0.0610127 0.229402 0.094949 -0.0613586 0.229024 0.0944892 -0.0616208 0.228088 0.094822 -0.0622545 0.227869 0.0943062 -0.0619928 0.228207 0.0940002 -0.061707 0.227811 0.0948495 -0.0622886 0.227721 0.0968172 -0.062291 0.228271 0.0958448 -0.0623986 0.228753 0.0948706 -0.0574055 0.228349 0.0939506 -0.0579673 0.22801 0.0935004 -0.0610805 0.228047 0.0933742 -0.0608092 0.228168 0.0931863 -0.0598292 0.228252 0.0933008 -0.0590589 0.22836 0.0949147 -0.0622201 0.228654 0.0935709 -0.0609689 0.228824 0.0933282 -0.0600442 0.228982 0.0934625 -0.0590537 0.228494 0.0941251 -0.0617213 0.228347 0.093442 -0.0608999 0.228492 0.0932196 -0.0599312 0.228623 0.0933854 -0.0589195 0.228718 0.0939564 -0.0580179 0.229099 0.0940106 -0.0581507 0.228415 0.0967642 -0.062158 0.2294 0.0959809 -0.0612836 0.229366 0.096391 -0.0612213 0.229804 0.0951508 -0.0604124 0.229691 0.0952139 -0.0607211 0.22964 0.095276 -0.0608471 0.228767 0.0959215 -0.0621472 0.228239 0.0967882 -0.0622184 0.22887 0.0951519 -0.0620143 0.228771 0.09429 -0.0616932 0.22895 0.0937626 -0.0610082 0.229141 0.093518 -0.0601524 0.229417 0.0937837 -0.0602468 0.229612 0.0938768 -0.0594039 0.229322 0.0936274 -0.0592187 0.229459 0.0941387 -0.0583533 0.229987 0.11208 -0.0501459 0.230112 0.111194 -0.0496731 0.229256 0.113674 -0.0511135 0.229579 0.113125 -0.0507435 0.229213 0.11383 -0.0495685 0.229402 0.113661 -0.0505547 0.229024 0.114118 -0.0502875 0.229691 0.112976 -0.0504655 0.229578 0.113445 -0.0500423 0.229765 0.113044 -0.0496392 0.229417 0.11328 -0.0489897 0.229822 0.112511 -0.0490176 0.229612 0.112504 -0.0486494 0.22976 0.111591 -0.0486554 0.230024 0.11097 -0.0493887 0.22994 0.11249 -0.0494117 0.23007 0.111846 -0.0494281 0.229968 0.111723 -0.0490271 0.228718 0.111265 -0.0480251 0.228276 0.112245 -0.0479324 0.228623 0.112331 -0.0479815 0.228169 0.11321 -0.0482597 0.228143 0.113401 -0.0483797 0.228347 0.114017 -0.0490197 0.228753 0.110277 -0.0485107 0.227925 0.114435 -0.049809 0.228088 0.1145 -0.0508934 0.227984 0.114249 -0.0493465 0.228207 0.114437 -0.049907 0.22782 0.114529 -0.0508265 0.227749 0.114231 -0.0518059 0.228239 0.113486 -0.0525779 0.22887 0.114127 -0.0510589 0.228772 0.11428 -0.0501511 0.22836 0.114424 -0.0509565 0.228824 0.113333 -0.0484939 0.229099 0.111353 -0.0481384 0.229459 0.111464 -0.0483507 0.228982 0.112408 -0.0481154 0.228492 0.113289 -0.0483433 0.228655 0.114012 -0.0491659 0.228494 0.114387 -0.0500224 0.228271 0.114114 -0.0518513 0.228767 0.113858 -0.0517919 0.229377 0.112986 -0.0515664 0.229158 0.113481 -0.0516499 0.22895 0.11395 -0.0493516 0.229141 0.113331 -0.0487124 0.229322 0.112469 -0.0483407 0.229512 0.11051 -0.0488067 0.22992 0.0952199 -0.0600448 0.229694 0.0960578 -0.0603852 0.229498 0.0955756 -0.0611515 0.229742 0.112881 -0.0503625 0.229446 0.113153 -0.0511897 0.229366 0.112821 -0.0517353 0.229464 0.113164 -0.0511159 0.229694 0.112264 -0.0510288 0.229886 0.112507 -0.0501564 0.230021 0.106684 -0.0539069 0.230021 0.104049 -0.055514 0.229366 0.100745 -0.0593016 0.228415 0.101185 -0.0602089 0.228994 0.0966139 -0.0617809 0.228994 0.101008 -0.0598436 0.229366 0.104949 -0.0570727 0.229366 0.108982 -0.0545462 0.228994 0.113194 -0.0522082 0.228731 0.113336 -0.0523878 0.228994 0.10932 -0.0550448 0.228994 0.10525 -0.0575943 0.228731 0.0966986 -0.0619934 0.228415 0.113446 -0.0525269 0.228415 0.109547 -0.0553808 0.228415 0.105453 -0.0579459 0.227721 0.101247 -0.0603377 0.224774 0.0933219 -0.0584873 0.224574 0.0999445 -0.0558518 0.224774 0.106284 -0.0519611 0.224574 0.135181 -0.0208323 0.222886 0.135437 -0.021911 0.222665 0.133848 -0.019652 0.224574 0.134468 -0.0199838 0.224574 0.134556 -0.0200525 0.222624 0.133449 -0.0195466 0.224574 0.132342 -0.0196139 0.224574 0.132236 -0.0196488 0.222514 0.132236 -0.0196488 0.222506 0.132127 -0.0196902 0.224574 0.131384 -0.0201714 0.224774 0.132284 -0.0194225 0.224774 0.133483 -0.0193495 0.224574 0.133449 -0.0195466 0.224774 0.13536 -0.0207424 0.224774 0.134587 -0.0198232 0.228358 0.120051 -0.0390328 0.224774 0.119706 -0.0398958 0.224774 0.119864 -0.0389614 0.224974 0.120052 -0.039027 0.224974 0.120476 -0.0382542 0.224774 0.120319 -0.0381303 0.230112 0.130778 -0.0234215 0.229185 0.127077 -0.0283587 0.228377 0.120476 -0.0382542 0.228377 0.123929 -0.033416 0.229185 0.124095 -0.033523 0.228377 0.126901 -0.0282681 0.22981 0.124557 -0.0338198 0.228753 0.129403 -0.0228735 0.229185 0.129548 -0.0229315 0.229512 0.129753 -0.0230131 0.230112 0.125209 -0.0342393 0.230024 0.121386 -0.0389724 0.22981 0.127565 -0.0286097 0.230024 0.130442 -0.0232875 0.230112 0.12167 -0.0391968 0.230112 0.128254 -0.0289646 0.224974 0.130067 -0.0335279 0.227721 0.127496 -0.0376307 0.224974 0.134288 -0.02482 0.229498 0.122991 -0.0411713 0.23001 0.122199 -0.0399108 0.22992 0.12213 -0.0403908 0.229578 0.12204 -0.0414485 0.23007 0.121425 -0.039849 0.22981 0.121061 -0.0387165 0.229968 0.121024 -0.0397255 0.22976 0.120653 -0.0395938 0.22994 0.121409 -0.0404926 0.229256 0.123111 -0.0416774 0.229822 0.121015 -0.040514 0.229765 0.121637 -0.0410476 0.229402 0.122552 -0.0416639 0.228025 0.121058 -0.042082 0.228207 0.121905 -0.0424401 0.228271 0.123848 -0.0421167 0.227816 0.122871 -0.042527 0.229804 0.122254 -0.0407436 0.22964 0.12258 -0.0410576 0.228767 0.123789 -0.0418606 0.22887 0.123056 -0.0421304 0.228753 0.120508 -0.0382796 0.228305 0.119906 -0.0398958 0.22835 0.119998 -0.0392052 0.228492 0.120341 -0.0412925 0.228179 0.120215 -0.0411384 0.228494 0.12202 -0.04239 0.228771 0.122149 -0.0422832 0.228654 0.121164 -0.0420155 0.229322 0.120338 -0.0404715 0.229099 0.120136 -0.039355 0.229459 0.120348 -0.0394665 0.228347 0.121018 -0.0420202 0.228824 0.120491 -0.0413361 0.228982 0.120113 -0.0404111 0.228623 0.119979 -0.0403335 0.228718 0.120022 -0.0392672 0.229185 0.120631 -0.0383767 0.227722 0.124533 -0.0416607 0.228415 0.124524 -0.0414487 0.228731 0.124385 -0.0413389 0.229158 0.123647 -0.0414838 0.228994 0.124205 -0.0411972 0.228088 0.12289 -0.0425033 0.22836 0.122953 -0.0424272 0.229024 0.122285 -0.042121 0.229213 0.121566 -0.0418337 0.22895 0.12135 -0.0419538 0.229141 0.12071 -0.0413349 0.229417 0.120987 -0.0412838 0.229612 0.120646 -0.0405073 0.229512 0.120804 -0.0385132 0.227721 0.134288 -0.02482 0.228731 0.13399 -0.0247015 0.229987 0.131782 -0.0233877 0.23007 0.131221 -0.0228831 0.229377 0.133277 -0.0241652 0.229446 0.133233 -0.0237555 0.229464 0.133205 -0.0236862 0.229402 0.133355 -0.0229516 0.229024 0.133618 -0.0224917 0.229256 0.133646 -0.0234288 0.229578 0.132912 -0.0226157 0.229765 0.132364 -0.022467 0.229417 0.132243 -0.0217865 0.229822 0.131591 -0.0221952 0.22976 0.130613 -0.0223415 0.229968 0.130913 -0.0225977 0.22981 0.130058 -0.0231346 0.22994 0.13177 -0.0225473 0.228718 0.130015 -0.021959 0.228623 0.130917 -0.0213882 0.228169 0.131818 -0.0211892 0.228363 0.129751 -0.0221918 0.228088 0.134252 -0.0228251 0.227843 0.134128 -0.0225267 0.228047 0.132805 -0.0213766 0.228347 0.132896 -0.0214443 0.227984 0.133261 -0.021611 0.228207 0.133704 -0.0220026 0.227967 0.133379 -0.0216916 0.22782 0.134243 -0.0227527 0.228239 0.134215 -0.0247911 0.228767 0.134144 -0.0239247 0.229158 0.133747 -0.0239901 0.22887 0.134011 -0.023155 0.228494 0.133718 -0.0221275 0.229141 0.132149 -0.0215208 0.228655 0.132965 -0.0215733 0.228824 0.132041 -0.021331 0.229322 0.131216 -0.0216303 0.228982 0.131051 -0.0214654 0.229099 0.130148 -0.0220132 0.228492 0.131928 -0.0212225 0.22836 0.134217 -0.0229179 0.228271 0.134396 -0.0238481 0.228772 0.13369 -0.0222924 0.229213 0.133009 -0.0220129 0.22895 0.133004 -0.021765 0.229612 0.131401 -0.0218797 0.229459 0.130351 -0.0221413 0.230021 0.125904 -0.0346868 0.230021 0.122319 -0.0397091 0.229939 0.122124 -0.0403155 0.229694 0.123026 -0.0402666 0.229465 0.123113 -0.0411666 0.229691 0.122463 -0.0409794 0.229691 0.132718 -0.0232166 0.229579 0.132986 -0.023383 0.229377 0.133277 -0.0241652 0.229694 0.132382 -0.0240607 0.229886 0.132156 -0.0231838 0.229742 0.132584 -0.0231751 0.230021 0.131546 -0.0237276 0.230021 0.128989 -0.0293432 0.229366 0.131299 -0.0287479 0.230021 0.127511 -0.0320525 0.229366 0.12907 -0.0329521 0.229366 0.126543 -0.0369845 0.2294 0.123408 -0.041083 0.227721 0.132335 -0.0292502 0.228415 0.134155 -0.0247671 0.228239 0.124575 -0.0414889 0.228994 0.127042 -0.0373226 0.229366 0.123732 -0.0408241 0.228994 0.129591 -0.0332533 0.228994 0.131841 -0.0290107 0.228994 0.133778 -0.0246168 0.229366 0.133218 -0.0243939 0.228415 0.129943 -0.0334563 0.228415 0.132206 -0.0291878 0.227721 0.130067 -0.0335279 0.228415 0.127378 -0.0375504 0.224774 0.119708 -0.0399909 0.224774 0.123958 -0.034287 0.224574 0.124125 -0.0343972 0.224574 0.127849 -0.0279474 0.224774 0.12767 -0.0278579 0.224774 0.13232 -0.0301848 0.224574 0.132142 -0.0300953 0.224774 0.135637 -0.021911 0.224574 0.122469 -0.0441006 0.224574 0.121583 -0.0443069 0.224774 0.121415 -0.0445075 0.224774 0.119412 -0.0434693 0.224774 0.119507 -0.0402285 0.224574 0.119137 -0.0423737 0.224574 0.119572 -0.0433492 0.224774 0.129899 -0.0217401 0.224774 0.125304 -0.0307779 0.224574 0.135437 -0.021911 0.224574 0.135296 -0.0227218 0.224574 0.11966 -0.0403578 0.222437 0.119289 -0.0409549 0.224574 0.119169 -0.0413061 0.224574 0.119111 -0.0422143 0.222591 0.119452 -0.043173 0.222664 0.11994 -0.0437393 0.224574 0.120387 -0.0440394 0.224574 0.121421 -0.0443076 0.222823 0.121582 -0.0443069 0.222808 0.121376 -0.0443058 0.2229 0.128132 -0.0370408 0.224574 0.123323 -0.0434595 0.224574 0.128132 -0.0370408 0.224574 0.130778 -0.0211002 0.222427 0.124125 -0.0343972 0.221231 0.134247 -0.0220345 0.221498 0.134635 -0.0224843 0.222852 0.135326 -0.0211886 0.222585 0.133048 -0.019511 0.222253 0.133059 -0.0195422 0.222364 0.133941 -0.0197167 0.222684 0.134035 -0.0197284 0.22256 0.135202 -0.0209242 0.222842 0.135272 -0.0210364 0.222777 0.134827 -0.0203115 0.222743 0.134556 -0.0200525 0.222288 0.135171 -0.0210184 0.222358 0.135356 -0.0218461 0.22147 0.134712 -0.0220111 0.220854 0.133333 -0.0215176 0.220796 0.133097 -0.0217009 0.220684 0.132273 -0.0216368 0.220779 0.13187 -0.021492 0.221036 0.131956 -0.0206274 0.220827 0.132265 -0.0208732 0.221132 0.133996 -0.0208885 0.22094 0.133603 -0.0214584 0.22102 0.133822 -0.0214957 0.220979 0.133536 -0.0207729 0.220834 0.133039 -0.0208513 0.220952 0.132848 -0.0205053 0.220726 0.132582 -0.021148 0.221778 0.134973 -0.021263 0.221653 0.134616 -0.0206911 0.221284 0.134051 -0.0205733 0.221392 0.134617 -0.0215497 0.22116 0.134141 -0.0217459 0.221565 0.134811 -0.0214042 0.222449 0.131326 -0.0202287 0.222056 0.134014 -0.0198434 0.221792 0.132283 -0.0197935 0.221452 0.132454 -0.0199529 0.221336 0.131687 -0.0204361 0.221619 0.130964 -0.021167 0.22247 0.134685 -0.0201985 0.222183 0.134704 -0.0203231 0.221921 0.133175 -0.019647 0.222151 0.132147 -0.0197208 0.222078 0.131345 -0.0202651 0.221696 0.13148 -0.0203149 0.22205 0.130817 -0.0211141 0.221861 0.135107 -0.0219317 0.22189 0.134995 -0.0226135 0.221057 0.133916 -0.0215383 0.222207 0.135161 -0.0226735 0.222881 0.135433 -0.0217671 0.221905 0.134681 -0.0204892 0.221761 0.13406 -0.0200339 0.221498 0.134073 -0.0202819 0.221327 0.133393 -0.020096 0.221603 0.13329 -0.0198333 0.221162 0.132647 -0.0201961 0.221132 0.121085 -0.0432502 0.221861 0.122545 -0.0436906 0.22189 0.123079 -0.0432524 0.220982 0.121451 -0.0427231 0.221627 0.122904 -0.0431047 0.221255 0.122444 -0.0427155 0.221275 0.121507 -0.043437 0.221497 0.120598 -0.0436196 0.221392 0.121969 -0.0434576 0.22102 0.121524 -0.0427958 0.221327 0.120097 -0.0431239 0.221162 0.119812 -0.0424286 0.221036 0.119839 -0.0416144 0.220779 0.120545 -0.0411072 0.220979 0.120756 -0.0429096 0.220834 0.120575 -0.0424398 0.220952 0.12018 -0.0424479 0.220827 0.120207 -0.0417587 0.220726 0.120603 -0.0418959 0.220692 0.120821 -0.041341 0.222446 0.119197 -0.0412039 0.222078 0.11922 -0.0412666 0.222499 0.119103 -0.0421451 0.222151 0.11915 -0.0422326 0.22205 0.119691 -0.0403843 0.222752 0.120734 -0.0441858 0.222607 0.11954 -0.0433059 0.222364 0.120042 -0.0437875 0.222705 0.12028 -0.0439805 0.222722 0.120435 -0.0440636 0.222828 0.121652 -0.0443033 0.22256 0.12172 -0.0442766 0.222878 0.122503 -0.044085 0.22147 0.122416 -0.0433089 0.221778 0.121899 -0.0439091 0.222288 0.121786 -0.0442026 0.222183 0.120949 -0.0441455 0.222056 0.120189 -0.0437878 0.22192 0.1196 -0.0431594 0.221603 0.119818 -0.0431655 0.221792 0.119281 -0.0423145 0.221452 0.119504 -0.0423825 0.221336 0.119539 -0.0414767 0.221696 0.11933 -0.0413582 0.222253 0.11945 -0.0431108 0.22247 0.120832 -0.0441916 0.222358 0.122595 -0.0439489 0.221653 0.121224 -0.0438853 0.221905 0.121082 -0.044043 0.221761 0.120377 -0.0437324 0.221291 0.119979 -0.040628 0.221255 0.134212 -0.0223328 0.221627 0.134779 -0.0225363 0.221255 0.131234 -0.0293338 0.221255 0.131112 -0.02958 0.221255 0.12717 -0.0364066 0.222383 0.135223 -0.0226954 0.222207 0.132014 -0.0300312 0.2229 0.135296 -0.0227218 0.2229 0.132142 -0.0300953 0.221627 0.127673 -0.0367384 0.222207 0.123214 -0.043367 0.222383 0.123264 -0.043409 0.221627 0.13165 -0.0298496 0.222207 0.128012 -0.036962 0.2229 0.123323 -0.0434595 0.220782 0.121452 -0.0418754 0.220782 0.132989 -0.0218936 0.220993 0.128516 -0.0282813 0.220782 0.129949 -0.0289983 0.220692 0.132211 -0.0216143 0.220782 0.125937 -0.0359147 0.220692 0.12921 -0.0286283 0.221619 0.119811 -0.0404856 0.220993 0.12023 -0.04084 0.220692 0.125395 -0.0352352 0.222427 0.11966 -0.0403578 0.220993 0.131481 -0.0213523 0.221291 0.131172 -0.0212415 0.221619 0.128026 -0.0280359 0.220993 0.124748 -0.0348082 0.221619 0.12429 -0.0345061 0.222427 0.127849 -0.0279474 0.222427 0.130778 -0.0211002 0.220782 0.130069 -0.0287569 0.221019 0.133601 -0.0221132 0.221184 0.12199 -0.0429471 0.221242 0.122275 -0.042858 0.220807 0.121316 -0.0421424 0.221019 0.121948 -0.0422954 0.220855 0.121299 -0.0423628 0.220879 0.121313 -0.0424495 0.221099 0.121716 -0.0429077 0.221255 0.127019 -0.0366351 0.220782 0.126085 -0.0356906 0.224774 0.134669 -0.0236409 0.224974 0.13447 -0.0236548 0.224974 0.134128 -0.022526 0.224774 0.133444 -0.0214927 0.224974 0.13333 -0.0216574 0.224774 0.130484 -0.0213248 0.224774 0.122309 -0.0427351 0.224774 0.123687 -0.0425118 0.224974 0.123608 -0.0423282 0.224974 0.122872 -0.0425269 0.224974 0.121687 -0.0423993 0.224774 0.12255 -0.0442833 0.224774 0.120048 -0.0412489 0.224774 0.118975 -0.0412559 0.224774 0.120295 -0.044217 0.224774 0.120991 -0.0422776 0.224774 0.118941 -0.0424125 0.224774 0.13059 -0.0210327 0.224774 0.131 -0.0211115 0.224774 0.131246 -0.0200265 0.224774 0.132266 -0.0210233 0.224774 0.134302 -0.0224269 0.224774 0.135484 -0.0227894 0.224774 0.128298 -0.0371509 0.224774 0.124793 -0.0416612 0.224774 0.123476 -0.0435888 0.224774 0.129179 -0.0227843 0.224974 0.125477 -0.0308779 0.228377 0.125477 -0.0308779 0.224774 0.134474 -0.0248941 0.224774 0.13024 -0.0336279 0.228047 0.120914 -0.0419756 0.224974 0.120678 -0.0417657 0.224974 0.121101 -0.0421104 0.22794 0.121687 -0.0423992 0.227875 0.122253 -0.0425284 0.224974 0.122327 -0.0425358 0.227766 0.123524 -0.042363 0.224974 0.124636 -0.0415374 0.227748 0.123822 -0.0422238 0.227721 0.124636 -0.0415374 0.228086 0.120678 -0.0417658 0.224974 0.120224 -0.041154 0.224974 0.120049 -0.040754 0.228276 0.119929 -0.0402475 0.224974 0.119906 -0.0398958 0.228377 0.129364 -0.0228584 0.224974 0.129364 -0.0228584 0.224974 0.130034 -0.0218874 0.22835 0.129949 -0.0219686 0.224974 0.130889 -0.0213604 0.228276 0.130818 -0.0213886 0.224974 0.131058 -0.0213029 0.228143 0.132042 -0.021198 0.224974 0.132235 -0.0212209 0.227749 0.134475 -0.02375 0.227827 0.134211 -0.0226836 0.224974 0.134211 -0.0226839 0.227925 0.133653 -0.021919 0.222427 0.130778 0.0210945 0.222499 0.132048 0.0197187 0.224574 0.132236 0.0196431 0.222518 0.132287 0.0196256 0.222576 0.132947 0.019507 0.224574 0.133449 0.0195408 0.222738 0.134511 0.0200109 0.224574 0.134468 0.0199781 0.224574 0.134556 0.0200468 0.222833 0.135217 0.0209019 0.222881 0.135433 0.0217617 0.2229 0.135296 0.0227161 0.224574 0.135296 0.0227161 0.224574 0.128132 0.0370351 0.224574 0.123323 0.0434538 0.224574 0.124125 0.0343915 0.222427 0.124125 0.0343915 0.222427 0.127849 0.0279417 0.221255 0.122444 0.0427097 0.221231 0.122203 0.0428885 0.220979 0.120756 0.0429043 0.220782 0.121452 0.0418697 0.220692 0.120821 0.0413353 0.220952 0.12018 0.0424421 0.220827 0.120207 0.0417527 0.220993 0.12023 0.0408343 0.220779 0.120545 0.0411015 0.221284 0.12084 0.0434496 0.22094 0.121383 0.0426193 0.22102 0.121524 0.0427903 0.220834 0.120575 0.042434 0.220726 0.120603 0.04189 0.221498 0.120599 0.0436144 0.221392 0.121969 0.043452 0.222358 0.122595 0.0439433 0.22289 0.122795 0.0439187 0.222383 0.123264 0.0434033 0.222151 0.11915 0.0422267 0.222576 0.11937 0.0430245 0.22256 0.121719 0.0442709 0.22247 0.120832 0.0441861 0.222722 0.120435 0.044058 0.222253 0.119451 0.0431057 0.222607 0.11954 0.0433002 0.222183 0.12095 0.0441399 0.222056 0.120189 0.0437827 0.221761 0.120377 0.0437272 0.221603 0.119819 0.0431604 0.221792 0.119281 0.0423087 0.221452 0.119504 0.0423767 0.221619 0.119811 0.0404798 0.222364 0.120043 0.0437825 0.221921 0.1196 0.0431543 0.222078 0.11922 0.0412605 0.221696 0.119331 0.0413521 0.22205 0.119691 0.0403786 0.22147 0.122416 0.0433033 0.221498 0.122787 0.0429996 0.221627 0.122904 0.043099 0.22189 0.123079 0.0432467 0.221132 0.121086 0.0432449 0.221057 0.121608 0.0428503 0.221778 0.121898 0.0439034 0.221565 0.12194 0.0436928 0.221861 0.122544 0.0436851 0.222288 0.121785 0.0441969 0.221905 0.121082 0.0440375 0.221653 0.121224 0.0438797 0.221327 0.120098 0.0431186 0.221162 0.119812 0.0424228 0.221036 0.119839 0.0416084 0.221336 0.119539 0.0414706 0.221291 0.119979 0.0406223 0.220807 0.133152 0.0216363 0.220879 0.133416 0.0214801 0.221184 0.134186 0.021818 0.221275 0.134369 0.0211545 0.221255 0.134212 0.0223271 0.22102 0.133822 0.0214899 0.221132 0.133996 0.0208826 0.220979 0.133536 0.0207673 0.221327 0.133393 0.0200903 0.220952 0.132848 0.0204996 0.220779 0.13187 0.0214863 0.220982 0.133722 0.0214631 0.220834 0.133039 0.0208456 0.220726 0.132582 0.0211422 0.220692 0.132211 0.0216085 0.220827 0.132265 0.0208673 0.222151 0.132147 0.019715 0.222447 0.131305 0.0202439 0.222886 0.135437 0.0219053 0.222358 0.135356 0.0218408 0.22256 0.135202 0.0209187 0.222664 0.133847 0.0196459 0.222626 0.13347 0.0195446 0.222896 0.135402 0.0223164 0.22147 0.134712 0.0220055 0.222288 0.135171 0.0210128 0.221761 0.134059 0.0200278 0.222056 0.134013 0.0198373 0.22192 0.133174 0.0196413 0.221603 0.133289 0.0198276 0.221452 0.132454 0.0199471 0.221792 0.132283 0.0197877 0.221696 0.13148 0.0203089 0.222078 0.131345 0.0202591 0.222253 0.133058 0.0195365 0.222364 0.13394 0.0197105 0.222183 0.134703 0.020317 0.22247 0.134684 0.0201924 0.221861 0.135107 0.0219263 0.22189 0.134995 0.0226078 0.221242 0.134251 0.0221093 0.221392 0.134617 0.0215441 0.221778 0.134973 0.0212575 0.221653 0.134615 0.020685 0.221905 0.134681 0.0204831 0.221497 0.134072 0.0202758 0.221162 0.132648 0.0201904 0.221036 0.131956 0.0206215 0.221336 0.131687 0.0204302 0.221291 0.131172 0.0212358 0.222207 0.132014 0.0300255 0.221627 0.134779 0.0225306 0.221627 0.127673 0.0367327 0.221255 0.131112 0.0295743 0.222207 0.123214 0.0433613 0.2229 0.123323 0.0434538 0.222207 0.128012 0.0369562 0.2229 0.128132 0.0370351 0.2229 0.132142 0.0300896 0.221627 0.13165 0.0298439 0.222207 0.135161 0.0226677 0.222383 0.135223 0.0226897 0.220782 0.132989 0.0218879 0.220782 0.126085 0.0356849 0.220684 0.120872 0.0413785 0.220692 0.125395 0.0352295 0.220993 0.124748 0.0348025 0.220993 0.131481 0.0213466 0.220692 0.12921 0.0286226 0.22205 0.130817 0.0211084 0.221619 0.12429 0.0345004 0.221619 0.130964 0.0211613 0.220993 0.128516 0.0282756 0.221619 0.128026 0.0280302 0.220854 0.121299 0.0423555 0.221019 0.121948 0.0422897 0.220796 0.12134 0.04206 0.221231 0.122203 0.0428885 0.22116 0.121901 0.0429418 0.221057 0.121608 0.0428503 0.221255 0.131234 0.0293289 0.221099 0.134015 0.0216003 0.220855 0.133334 0.0215112 0.220782 0.130069 0.028752 0.221019 0.133601 0.0221075 0.220782 0.129949 0.0289926 0.221255 0.12717 0.0364009 0.220782 0.125936 0.0359097 0.221255 0.127018 0.0366301 0.228086 0.120678 0.0417599 0.224974 0.120678 0.04176 0.224974 0.120224 0.0411482 0.22816 0.120298 0.0412777 0.227975 0.121415 0.0422816 0.224974 0.121101 0.0421047 0.224974 0.121687 0.0423936 0.224974 0.122327 0.0425301 0.22782 0.122824 0.0425265 0.227749 0.123803 0.0422283 0.224774 0.123687 0.0425061 0.224974 0.124636 0.0415316 0.224774 0.122309 0.0427294 0.224974 0.123608 0.0423225 0.224974 0.122872 0.0425212 0.224774 0.120991 0.0422718 0.224774 0.120048 0.0412432 0.224774 0.119706 0.0398901 0.224974 0.120476 0.0382485 0.224974 0.119906 0.0398901 0.224774 0.119864 0.0389557 0.224974 0.132176 0.0212067 0.224774 0.130061 0.0215961 0.224974 0.130185 0.0217532 0.224774 0.130484 0.0213191 0.224774 0.134474 0.0248884 0.224974 0.134449 0.023452 0.224774 0.134647 0.0234232 0.224974 0.133907 0.0221919 0.224774 0.132881 0.0211859 0.224774 0.134064 0.022068 0.224774 0.131416 0.0210132 0.224774 0.128298 0.0371452 0.224774 0.124793 0.0416555 0.224774 0.12237 0.0443501 0.224774 0.120319 0.0381246 0.224974 0.125477 0.0308721 0.224774 0.125304 0.0307721 0.224974 0.129364 0.0228526 0.228377 0.129364 0.0228526 0.228377 0.126901 0.0282624 0.228377 0.125477 0.0308721 0.224774 0.13024 0.0336221 0.224974 0.134288 0.0248143 0.227721 0.134288 0.0248143 0.224974 0.134211 0.0226781 0.22782 0.134243 0.0227468 0.227951 0.133485 0.0217668 0.224974 0.132807 0.0213717 0.224974 0.133379 0.021686 0.228349 0.129964 0.0219477 0.228269 0.13089 0.0213546 0.224974 0.130889 0.0213546 0.224974 0.131445 0.0212111 0.228252 0.131057 0.0212977 0.228169 0.131819 0.0211835 0.22811 0.132316 0.0212292 0.228047 0.132806 0.0213714 0.228358 0.12005 0.0390277 0.224974 0.120052 0.0390213 0.230021 0.122319 0.0397033 0.229185 0.129548 0.0229258 0.228753 0.129403 0.0228678 0.228377 0.123929 0.0334103 0.22981 0.127565 0.028604 0.22981 0.130058 0.0231289 0.229185 0.124095 0.0335173 0.22981 0.124557 0.0338141 0.230112 0.128254 0.0289589 0.229512 0.129753 0.0230074 0.229185 0.127077 0.0283529 0.22981 0.121061 0.0387108 0.230024 0.121386 0.0389667 0.230112 0.125209 0.0342336 0.227721 0.127496 0.037625 0.227721 0.130067 0.0335221 0.224974 0.130067 0.0335221 0.227721 0.132335 0.0292445 0.229256 0.133646 0.0234229 0.22992 0.132042 0.0232171 0.22994 0.131769 0.0225416 0.23001 0.131661 0.0235165 0.230021 0.131546 0.0237219 0.229578 0.132913 0.0226103 0.229213 0.13301 0.0220076 0.22895 0.133005 0.0217597 0.22887 0.134011 0.0231491 0.228271 0.134396 0.023842 0.22836 0.134217 0.0229119 0.228207 0.133704 0.0219974 0.22964 0.132844 0.0232731 0.229402 0.133356 0.0229462 0.229024 0.133618 0.0224863 0.228771 0.13369 0.0222872 0.228494 0.133718 0.0221223 0.228347 0.132897 0.0214391 0.22976 0.130613 0.0223361 0.229099 0.130148 0.0220077 0.228718 0.130015 0.0219535 0.228492 0.131928 0.0212168 0.228623 0.130917 0.0213826 0.228982 0.131051 0.0214597 0.229417 0.132244 0.0217809 0.229612 0.131401 0.021874 0.229459 0.13035 0.0221359 0.229322 0.131216 0.0216246 0.227735 0.134467 0.0240632 0.228239 0.134215 0.0247854 0.228731 0.13399 0.0246958 0.228767 0.134144 0.0239187 0.229158 0.133747 0.0239842 0.228994 0.133778 0.0246111 0.227748 0.134475 0.023766 0.228088 0.134252 0.0228192 0.228654 0.132966 0.0215681 0.228824 0.132041 0.0213253 0.229141 0.132149 0.0215152 0.229765 0.132364 0.0224613 0.229822 0.131591 0.0221895 0.229968 0.130913 0.0225921 0.230024 0.130441 0.0232818 0.23007 0.13122 0.0228776 0.230112 0.130778 0.0234158 0.228239 0.124575 0.0414832 0.228718 0.120022 0.0392618 0.229417 0.120987 0.0412775 0.229742 0.12236 0.040878 0.229987 0.122143 0.0400777 0.229256 0.123111 0.0416716 0.229446 0.123187 0.0411499 0.229464 0.123113 0.0411609 0.229578 0.122039 0.0414424 0.229213 0.121566 0.0418274 0.229402 0.122552 0.0416581 0.229612 0.120646 0.0405017 0.22994 0.121409 0.0404869 0.229765 0.121636 0.0410415 0.229822 0.121015 0.0405084 0.23007 0.121425 0.0398435 0.229968 0.121024 0.0397201 0.230112 0.12167 0.0391911 0.228347 0.121017 0.0420138 0.228133 0.120424 0.0414638 0.228276 0.119929 0.0402419 0.228623 0.119979 0.0403279 0.228492 0.12034 0.0412861 0.228225 0.120049 0.0407488 0.22835 0.119997 0.0391998 0.228305 0.119906 0.0398901 0.228289 0.119914 0.040095 0.229185 0.120631 0.038371 0.228753 0.120508 0.0382739 0.228377 0.120476 0.0382485 0.228207 0.121904 0.0424342 0.228047 0.120913 0.0419691 0.22794 0.121687 0.0423935 0.227834 0.12267 0.0425376 0.228415 0.124524 0.041443 0.228767 0.123789 0.0418547 0.228494 0.122019 0.0423841 0.228655 0.121163 0.0420091 0.228824 0.120491 0.0413297 0.229459 0.120348 0.0394611 0.229099 0.120136 0.0393497 0.228982 0.120113 0.0404055 0.228088 0.12289 0.0424976 0.22836 0.122954 0.0424215 0.228271 0.123848 0.0421108 0.228731 0.124385 0.0413332 0.229366 0.123732 0.0408184 0.229158 0.123647 0.041478 0.229024 0.122285 0.0421151 0.22887 0.123056 0.0421246 0.228772 0.122148 0.0422774 0.22895 0.121349 0.0419474 0.229141 0.120709 0.0413285 0.229322 0.120338 0.040466 0.22976 0.120653 0.0395885 0.229512 0.120804 0.0385075 0.229939 0.131974 0.0232491 0.229465 0.133205 0.0236804 0.229498 0.133149 0.0235728 0.229694 0.132382 0.024055 0.229691 0.132718 0.023211 0.229804 0.132409 0.023148 0.229691 0.122463 0.0409735 0.229377 0.123564 0.0409833 0.229579 0.122741 0.0411222 0.229694 0.123026 0.0402608 0.229886 0.122154 0.0405037 0.230021 0.125904 0.0346811 0.230021 0.127511 0.032046 0.229366 0.12907 0.0329464 0.230021 0.128989 0.0293374 0.229366 0.131299 0.0287422 0.229366 0.133218 0.0243881 0.2294 0.133281 0.0239781 0.227721 0.124636 0.0415316 0.228994 0.131841 0.029005 0.228994 0.127042 0.0373169 0.229366 0.126543 0.0369788 0.228994 0.124205 0.0411915 0.228415 0.127378 0.0375447 0.228994 0.129591 0.0332476 0.228415 0.129943 0.0334506 0.228415 0.134155 0.0247614 0.228415 0.132206 0.0291821 0.224574 0.130778 0.0210945 0.224574 0.127849 0.0279417 0.224774 0.123958 0.0342813 0.224774 0.119708 0.0399852 0.224774 0.135484 0.0227837 0.224574 0.132142 0.0300896 0.224774 0.13232 0.0301791 0.224774 0.119507 0.0402228 0.224774 0.119044 0.0427813 0.224574 0.11966 0.0403521 0.224774 0.118933 0.04144 0.224574 0.11913 0.0414757 0.224574 0.119111 0.0422086 0.224574 0.11954 0.0433001 0.224574 0.119941 0.0437346 0.224774 0.119812 0.0438872 0.224574 0.120435 0.044058 0.224774 0.121029 0.0444614 0.224774 0.123476 0.043583 0.224574 0.121583 0.0443012 0.224574 0.121064 0.0442646 0.224774 0.135637 0.0219053 0.224574 0.135437 0.0219053 0.224774 0.13536 0.0207367 0.224574 0.135181 0.0208266 0.224774 0.134587 0.0198175 0.224774 0.133483 0.0193438 0.224574 0.132342 0.0196082 0.224774 0.132284 0.0194168 0.224774 0.13059 0.0210269 0.224574 0.131229 0.0203272 0.224574 0.131384 0.0201657 0.224774 0.131246 0.0200208 0.224774 0.129179 0.0227786 0.224774 0.12767 0.0278522 0.224574 0.122302 0.0441618 0.222881 0.122565 0.0440496 0.222828 0.121651 0.0442976 0.222623 0.119648 0.0434389 0.222664 0.11994 0.0437343 0.222737 0.120581 0.0441233 0.22252 0.119146 0.0424118 0.224574 0.119233 0.0427137 0.222427 0.11966 0.0403521 0.222449 0.119178 0.0412636 0.222504 0.119111 0.0422088 -0.22586 -0.0328 0.0773679 -0.224686 -0.0328 0.0773679 -0.225273 -0.0328 0.077435 -0.225273 -0.0248 0.077435 0.236527 -0.023539 0.077235 0.236527 0.0529175 0.0578429 0.236527 0.048 0.0773679 0.236527 -0.048 0.0773679 0.236527 0.0798 0.0773679 0.236527 0.0798 0.0637069 0.236527 0.0797011 0.0624366 0.236527 -0.0793164 0.0611976 0.236527 -0.0677507 0.0600033 0.236527 -0.0557858 0.0581034 0.236527 -0.0793164 -0.0627276 0.236527 -0.0790795 -0.0624235 0.236527 -0.00576541 0.0575572 0.236527 -0.078953 -0.0623412 0.236527 -0.0797012 -0.0639665 0.236527 -0.0788239 -0.0623076 0.236527 -0.0507965 0.0577419 0.236527 -0.0487965 0.0577094 0.236527 -0.0068478 0.0564748 0.236527 -0.0147851 0.0441492 0.236527 -0.0136722 0.0460768 0.236527 -0.00700004 0.0335288 0.236527 -0.00700004 0.0557094 0.236527 -0.0136722 0.0483027 0.236527 0.00599996 0.0574415 0.236527 -0.0159231 0.077235 0.236527 -0.0483 -0.0772953 0.236527 0.012626 0.0127562 0.236527 0.00266827 0.0228363 0.236527 0.012626 -0.0142866 0.236527 0.0169142 -0.0556792 0.236527 0.0331 -0.0772953 0.236527 0.0173477 -0.0550303 0.236527 -0.000964162 0.0219342 0.236527 0.0129743 0.0120797 0.236527 0.0130965 0.0117316 0.236527 0.013145 0.0112081 0.236527 0.0131221 0.0110419 0.236527 0.000964078 0.0219342 0.236527 0.01195 -0.000764971 0.236527 0.00699996 0.0557094 0.236527 0.0138529 0.0455442 0.236527 0.0127348 -0.0140313 0.236527 0.00266827 -0.0243663 0.236527 0.0131221 -0.0125719 0.236527 0.000964078 -0.0234641 0.236527 -0.00266836 -0.0243663 0.236527 -0.0524626 -0.0584636 0.236527 -0.0175 -0.0515371 0.236527 -0.0677507 -0.0615333 0.236527 -0.0128754 -0.0138066 0.236527 -0.0127349 -0.0140313 0.236527 0.0175 -0.054265 0.236527 0.0384546 -0.0516132 0.236527 0.0175 -0.0515371 0.236527 0.0170873 -0.0491693 0.236527 0.0266446 -0.0414311 0.236527 -0.0129286 0.012176 0.236527 -0.0158982 -0.0470806 0.236527 0.0235389 0.077235 0.236527 0.0223997 0.0573821 0.236527 0.00673201 0.0567094 0.236527 0.014785 0.0502303 0.236527 0.0131325 -0.0130797 0.236527 -0.0131326 0.0115498 0.236527 -0.0131293 0.0115717 0.236527 -0.0129867 0.0120518 0.236527 -0.0126317 0.0128823 0.236527 -0.00375248 0.0244309 0.236527 -0.0266447 -0.0414311 0.236527 -0.0170874 -0.0491693 0.236527 -0.0126261 -0.0142861 0.236527 0.0790794 -0.0624235 0.236527 0.0789529 -0.0623412 0.236527 0.0798 -0.0652368 0.236527 0.0654 -0.0772953 0.236527 -0.0131222 0.0110419 0.236527 -0.00266836 0.0228363 0.236527 -0.01195 -0.000764971 0.236527 -0.0131222 -0.0125719 0.236527 -0.0130965 -0.0132616 0.236527 0.0218875 0.0364789 0.236527 -0.0166073 0.0245824 0.236527 0.0214985 0.0333003 0.236527 0.0218534 0.0339948 0.236527 -0.0208837 0.0380506 0.236527 -0.0212953 0.0375843 0.236527 -0.0220836 0.0353369 -0.238873 -0.0214986 0.0333003 -0.238873 -0.0257 -0.0772953 -0.238873 -0.0165 -0.055997 -0.238873 -0.0574047 0.0583774 -0.238873 -0.055423 0.0580599 -0.238873 0.0235389 0.0773679 -0.238873 0.015923 0.077235 -0.238873 -0.0529176 0.0578429 -0.238873 -0.048 0.0773679 -0.238873 -0.0519631 0.057789 -0.238873 0.0529177 0.0578429 -0.238873 0.055065 0.0580207 -0.238873 0.00641417 0.0571236 -0.238873 -0.0793164 0.0611976 -0.238873 -0.023539 0.077235 -0.238873 -0.0797012 0.0624366 -0.238873 -0.078953 0.0608113 -0.238873 -0.0790795 0.0608935 -0.238873 0.0789529 0.0608113 -0.238873 0.0797011 0.0624366 -0.238873 0.0788238 0.0607776 -0.238873 0.0798 0.0637069 -0.238873 0.0584073 0.0586158 -0.238873 0.0557857 0.0581034 -0.238873 0.014525 -0.0772953 -0.238873 0.0162653 -0.0561127 -0.238873 -0.0126261 0.0127562 -0.238873 -0.0159231 0.077235 -0.238873 -0.00600004 0.0574415 -0.238873 -0.00796159 0.077235 -0.238873 0.0790794 -0.0624235 -0.238873 -0.0147851 0.0502303 -0.238873 0.00699996 0.0557094 -0.238873 0.0175 -0.054265 -0.238873 0.0175 -0.0515371 -0.238873 0.0384546 -0.0516132 -0.238873 0.0170873 -0.0491693 -0.238873 0.0654 -0.0772953 -0.238873 0.0677506 -0.0615333 -0.238873 0.0788238 -0.0623076 -0.238873 0.0797011 -0.0639665 -0.238873 0.012626 0.0127566 -0.238873 -0.0126724 -0.0141365 -0.238873 -0.012626 -0.0142866 -0.238873 0.0130965 -0.0132616 -0.238873 0.0131285 -0.0131065 -0.238873 -0.0212953 0.0375843 -0.238873 0.01195 -0.000764971 -0.238873 0.00266827 0.0228363 -0.238873 0.0126723 0.0126066 -0.238873 -0.00375248 -0.0259609 -0.238873 0.00893486 -0.0370328 -0.238873 0.0037524 -0.0259609 -0.238873 0.012626 -0.0142861 -0.238873 0.0210047 0.05645 -0.238873 0.0240452 0.0577094 -0.238873 0.0235389 0.077235 -0.238873 -0.00375248 0.0244309 -0.238873 -0.00631979 0.0305187 -0.238873 -0.0166073 0.0245824 -0.238873 -0.0147851 0.0441492 -0.238873 -0.0127349 0.0125013 -0.238873 -0.0130965 0.0117316 -0.238873 -0.00266836 0.0228363 -0.238873 -0.0131222 0.0110419 -0.238873 -0.0172321 -0.055265 -0.238873 0.0131221 0.0110419 -0.238873 0.0126317 0.0128823 -0.238873 -0.0131326 -0.0130797 -0.238873 -0.0131293 -0.0131017 -0.238873 -0.0175 -0.0515371 -0.238873 -0.0178067 -0.0285844 -0.238873 -0.0129772 -0.0136033 -0.238873 -0.078953 -0.0623412 -0.238873 -0.0677507 -0.0615333 -0.238873 -0.0483 -0.0772953 -0.238873 0.0166073 0.0245824 -0.238873 0.00631971 0.0305187 -0.238873 0.0219283 0.0342167 -0.238873 0.0208836 0.0380506 -0.238873 0.0212952 0.0375843 0.187518 -0.00368065 -0.0772953 0.185818 -0.014525 -0.0772953 -0.194934 0.0317 -0.0772953 -0.19369 0.0329444 -0.0772953 -0.201556 0.0331 -0.0772953 0.192588 0.0317 -0.0772953 0.193468 0.0331 -0.0772953 0.186699 0.0283 -0.0772953 0.186243 0.03 -0.0772953 0.191343 0.0270555 -0.0772953 0.185818 0.014525 -0.0772953 0.189643 0.0266 -0.0772953 0.185818 0.0654 -0.0772953 0.187943 0.0329444 -0.0772953 0.191343 0.0329444 -0.0772953 -0.188309 -0.00212504 -0.0772953 -0.188165 -0.014525 -0.0772953 -0.189865 -0.00368065 -0.0772953 -0.19199 -0.00425004 -0.0772953 -0.201556 -0.014525 -0.0772953 -0.194115 -0.00368065 -0.0772953 -0.19567 0.00212496 -0.0772953 -0.194115 0.00368057 -0.0772953 -0.188165 0.014525 -0.0772953 -0.19199 0.00424996 -0.0772953 -0.177765 -0.014525 -0.0772953 -0.188165 0.0331 -0.0772953 -0.18859 0.03 -0.0772953 -0.201556 0.014525 -0.0772953 -0.165944 0.0613547 -0.0772953 0.159143 0.0632 -0.0772953 0.161554 0.0627204 -0.0772953 -0.177765 0.014525 -0.0772953 -0.177765 0.0331 -0.0772953 -0.16779 -0.0569 -0.0772953 -0.166946 -0.06005 -0.0772953 0.164599 -0.06005 -0.0772953 0.182846 -0.0898 -0.0772953 0.162293 -0.062356 -0.0772953 0.163598 0.0613547 -0.0772953 0.165443 0.0569 -0.0772953 0.185818 0.0331 -0.0772953 0.165443 0.0331 -0.0772953 -0.227701 0.0328 -0.0772953 -0.238873 0.0331 -0.0772953 -0.227701 0.0248 -0.0772953 -0.222884 0.014525 -0.0772953 0.220538 -0.0328 -0.0772953 0.227216 0.014525 -0.0772953 0.225355 0.0248 -0.0772953 0.220538 0.0328 -0.0772953 0.220499 0.0248 -0.0772953 0.209883 0.0804257 -0.0772953 0.213364 0.0798 -0.0772953 0.19921 0.0654 -0.0772953 0.227216 -0.0483 -0.0772953 0.225355 -0.0248 -0.0772953 0.227216 -0.0257 -0.0772953 0.19921 -0.0483 -0.0772953 0.207927 -0.0676 -0.0772953 0.220538 -0.0483 -0.0772953 0.225355 -0.0328 -0.0772953 0.209627 -0.0680556 -0.0772953 0.220538 -0.0798 -0.0772953 0.213364 -0.0798 -0.0772953 0.209883 -0.0804257 -0.0772953 0.207927 -0.0744 -0.0772953 0.206227 -0.0739445 -0.0772953 0.165443 -0.0483 -0.0772953 0.185818 -0.0483 -0.0772953 0.165443 -0.0569 -0.0772953 0.193468 -0.0483 -0.0772953 0.204982 -0.0693 -0.0772953 -0.206873 -0.071 -0.0772953 -0.208573 -0.0739445 -0.0772953 -0.210273 -0.0744 -0.0772953 -0.211973 -0.0739445 -0.0772953 -0.218259 -0.0798 -0.0772953 -0.213673 -0.071 -0.0772953 -0.218259 -0.0483 -0.0772953 -0.211973 -0.0680556 -0.0772953 -0.210273 -0.0676 -0.0772953 -0.201556 -0.0483 -0.0772953 -0.188165 -0.0483 -0.0772953 -0.185192 -0.0898 -0.0772953 -0.177765 -0.0898 -0.0772953 -0.222884 0.0798 -0.0772953 -0.222884 0.0654 -0.0772953 -0.218259 0.0798 -0.0772953 -0.206873 0.071 -0.0772953 -0.207329 0.0693 -0.0772953 -0.211973 0.0680555 -0.0772953 -0.213673 0.071 -0.0772953 -0.215711 0.0798 -0.0772953 -0.210273 0.0744 -0.0772953 -0.212229 0.0804257 -0.0772953 -0.207721 0.0821 -0.0772953 -0.201556 0.0821 -0.0772953 -0.185192 0.0898 -0.0772953 0.193468 0.0865222 -0.0772953 0.19921 0.0821 -0.0772953 0.182846 0.0898 -0.0772953 0.224827 -0.00425004 -0.0772953 0.226952 -0.00368065 -0.0772953 0.220538 -0.014525 -0.0772953 0.221146 -0.00212504 -0.0772953 0.221146 0.00212496 -0.0772953 0.222702 0.00368057 -0.0772953 0.236527 0.014525 -0.0772953 0.229077 -4.19898e-08 -0.0772953 0.193893 -4.19898e-08 -0.0772953 0.19921 -0.014525 -0.0772953 0.193468 -0.014525 -0.0772953 0.191768 -0.00368065 -0.0772953 0.189643 0.00424996 -0.0772953 0.191768 0.00368057 -0.0772953 0.236527 -0.014525 -0.0772953 0.227216 -0.014525 -0.0772953 0.236527 -0.0257 -0.0772953 0.236527 -0.0798 -0.0772953 0.193468 0.014525 -0.0772953 0.19921 0.014525 -0.0772953 0.19921 0.0331 -0.0772953 0.220499 0.0328 -0.0772953 0.220538 0.0331 -0.0772953 0.220538 0.0654 -0.0772953 0.227216 0.0331 -0.0772953 0.227216 0.0654 -0.0772953 0.193043 -0.03 -0.0772953 0.189643 -0.0334 -0.0772953 0.186699 -0.0317 -0.0772953 0.186243 -0.03 -0.0772953 0.185818 -0.0257 -0.0772953 0.191343 -0.0270556 -0.0772953 0.19921 -0.0257 -0.0772953 0.193468 -0.0257 -0.0772953 0.220538 0.014525 -0.0772953 0.165443 -0.0257 -0.0772953 -0.188309 0.00212496 -0.0772953 -0.19029 -0.0329445 -0.0772953 -0.19199 -0.0334 -0.0772953 -0.19369 -0.0270556 -0.0772953 -0.19029 -0.0270556 -0.0772953 -0.189045 -0.0283 -0.0772953 -0.16779 -0.0483 -0.0772953 -0.177765 -0.0483 -0.0772953 -0.18859 -0.03 -0.0772953 -0.189045 -0.0317 -0.0772953 -0.201556 0.0654 -0.0772953 -0.177765 0.0654 -0.0772953 -0.188165 0.0821 -0.0772953 -0.177765 0.0821 -0.0772953 0.185818 0.0821 -0.0772953 0.193468 0.0654 -0.0772953 0.193468 0.0821 -0.0772953 -0.227701 -0.0248 -0.0772953 -0.222884 -0.0328 -0.0772953 -0.222884 -0.0483 -0.0772953 -0.218259 -0.0257 -0.0772953 -0.201556 -0.0257 -0.0772953 -0.218259 -0.014525 -0.0772953 -0.188165 -0.0257 -0.0772953 -0.177765 -0.0257 -0.0772953 -0.16779 -0.0257 -0.0772953 -0.218259 0.014525 -0.0772953 -0.238873 -0.014525 -0.0772953 -0.231423 -4.19898e-08 -0.0772953 -0.225048 0.00368057 -0.0772953 -0.19624 -4.19898e-08 -0.0772953 -0.222884 -0.014525 -0.0772953 -0.225048 -0.00368065 -0.0772953 -0.227173 0.00424996 -0.0772953 -0.19029 0.0329444 -0.0772953 -0.188165 0.0654 -0.0772953 -0.218259 0.0654 -0.0772953 -0.218259 0.0331 -0.0772953 -0.222884 0.0331 -0.0772953 0.209883 -0.0804257 0.0773679 -0.16779 0.0569 0.0773679 0.165443 -4.19898e-08 0.0773679 0.178701 0.00635471 0.0773679 0.165443 0.048 0.0773679 0.193892 0.048 0.0773679 0.23002 0.048 0.0773679 0.223514 0.0248 0.0773679 0.23002 0.0221976 0.0773679 0.23002 0.0798 0.0773679 0.186328 0.0891743 0.0773679 -0.13819 0.048 0.0773679 -0.16731 0.0593109 0.0773679 -0.215711 0.0798 0.0773679 -0.188674 0.0891743 0.0773679 -0.196238 0.048 0.0773679 -0.238873 0.048 0.0773679 -0.224686 0.0328 0.0773679 -0.22586 0.0328 0.0773679 -0.22586 0.0248 0.0773679 -0.190304 0.013526 0.0773679 -0.224686 0.0248 0.0773679 -0.16779 0.048 0.0773679 -0.184844 -0.011014 0.0773679 -0.16779 -0.048 0.0773679 -0.181048 -0.00635479 0.0773679 -0.17969 -0.000500042 0.0773679 -0.224686 -0.0248 0.0773679 -0.196238 -0.048 0.0773679 -0.22586 -0.0248 0.0773679 -0.212229 -0.0804257 0.0773679 -0.16779 -0.0569 0.0773679 0.162293 -0.062356 0.0773679 0.165443 -0.0569 0.0773679 0.165443 -0.048 0.0773679 0.193892 -0.048 0.0773679 0.213364 -0.0798 0.0773679 0.236527 -0.0798 0.0773679 0.23002 -0.048 0.0773679 0.223514 -0.0328 0.0773679 0.22234 -0.0328 0.0773679 0.177343 -4.19898e-08 0.0773679 0.223514 -0.0248 0.0773679 0.22234 -0.0248 0.0773679 0.182498 -0.011014 0.0773679 0.178701 -0.00635479 0.0773679 0.177343 -0.000500042 0.0773679 0.164599 0.06005 0.0773679 0.182846 0.0898 0.0773679 -0.13669 0.0632 0.0773679 -0.13819 -4.19898e-08 0.0773679 -0.13669 0.048 0.0773679 -0.13969 -0.0632 0.0773679 -0.13819 -0.048 0.0773679 -0.13969 -0.048 0.0773679 -0.13969 0.048 0.0773679 -0.225273 0.0248 0.077435 -0.225273 0.0328 0.077435 0.222927 -0.0328 0.077435 0.222927 -0.0248 0.077435 0.223514 0.0328 0.0773679 0.222927 0.0328 0.077435 0.222927 0.0248 0.077435 0.22234 0.0248 0.0773679 0.22234 0.0328 0.0773679 0.224647 0.0328 -0.0783146 0.222306 0.0328 -0.0788898 0.225355 0.0328 -0.0772953 0.222306 0.0248 -0.0788898 0.220538 0.0248 -0.0772953 0.221207 0.0328 -0.0783146 0.221207 0.0248 -0.0783146 0.223547 0.0328 -0.0788898 0.223547 0.0248 -0.0788898 0.224647 0.0248 -0.0783146 0.221207 -0.0328 -0.0783146 0.222306 -0.0328 -0.0788898 0.223547 -0.0328 -0.0788898 0.224647 -0.0328 -0.0783146 0.220538 -0.0248 -0.0772953 0.223547 -0.0248 -0.0788898 0.221207 -0.0248 -0.0783146 0.224647 -0.0248 -0.0783146 0.222306 -0.0248 -0.0788898 0.220499 -0.0328 -0.0772953 0.220499 -0.0248 -0.0772953 -0.225894 0.0328 -0.0788898 -0.222884 0.0328 -0.0772953 -0.226993 0.0328 -0.0783146 -0.222845 0.0248 -0.0772953 -0.225894 0.0248 -0.0788898 -0.222884 0.0248 -0.0772953 -0.223553 0.0248 -0.0783146 -0.226993 0.0248 -0.0783146 -0.224653 0.0328 -0.0788898 -0.224653 0.0248 -0.0788898 -0.223553 0.0328 -0.0783146 -0.222845 0.0328 -0.0772953 -0.227701 -0.0328 -0.0772953 -0.222845 -0.0328 -0.0772953 -0.224653 -0.0248 -0.0788898 -0.222884 -0.0248 -0.0772953 -0.222845 -0.0248 -0.0772953 -0.223553 -0.0328 -0.0783146 -0.223553 -0.0248 -0.0783146 -0.224653 -0.0328 -0.0788898 -0.225894 -0.0328 -0.0788898 -0.225894 -0.0248 -0.0788898 -0.226993 -0.0248 -0.0783146 -0.226993 -0.0328 -0.0783146 0.236527 -0.0240453 0.0577094 0.236586 -0.0483559 0.0577094 -0.185192 0.0898 0.0773679 -0.13819 0.0898 0.0773679 -0.185192 0.0898 0.077935 0.182846 0.0898 0.077935 -0.13819 -0.0898 0.0773679 -0.219073 -0.0793 -0.082131 -0.220173 -0.0788 -0.082265 -0.220173 -0.0796661 -0.081765 -0.220173 0.0793 -0.082131 -0.219073 0.0793 -0.082131 -0.219073 0.0788 -0.082265 0.236527 -0.0798 -0.081265 0.216727 0.0791826 -0.0821889 0.217827 0.0793 -0.082131 0.216727 0.0793 -0.082131 0.216727 0.0795071 -0.0819721 0.216727 0.0797238 -0.0816477 0.217827 0.079666 -0.081765 0.216727 0.079666 -0.081765 0.228027 0.079666 0.082235 0.236527 0.0793 0.0826011 0.228027 0.0793 0.0826011 0.216727 -0.0796661 0.082235 0.217827 -0.0793 0.0826011 0.217827 -0.0796661 0.082235 -0.220173 0.0795071 0.0824421 -0.230373 -0.0797239 0.0821177 -0.238873 -0.0796661 0.082235 -0.230373 -0.0791827 0.0826589 -0.238873 -0.0793 0.0826011 -0.219336 0.0195111 0.078935 -0.219336 0.0195111 0.081735 -0.238873 -0.023539 0.0773679 -0.239136 -0.0235931 0.077235 -0.190304 -0.0135261 0.0773679 -0.219336 -0.0195112 0.078935 0.215427 0.0715 0.078935 0.215427 0.0785 0.078935 0.215427 -0.0785 0.081735 0.215427 -0.0715 0.078935 0.215427 -0.0785 0.078935 -0.217773 0.0785 0.081735 -0.217773 -0.0715 0.078935 -0.217773 -0.0785 0.078935 -0.219336 0.0195111 -0.081265 -0.239136 0.0235931 -0.077765 -0.190304 0.013526 -0.077765 -0.190304 -0.0135261 -0.079265 -0.201131 -0.0157582 -0.079265 -0.219336 -0.0195112 -0.079265 0.215427 0.0771 -0.079265 0.215427 0.0785 -0.081265 0.215427 0.0483 -0.079265 0.215427 -0.0207844 -0.081265 -0.217773 -0.0785 -0.081265 0.189643 -0.00425004 -0.0772953 0.189643 -0.00425004 -0.077765 0.187518 -0.00368065 -0.077765 0.185963 -0.00212504 -0.0772953 0.185963 -0.00212504 -0.077765 0.185393 -4.19898e-08 -0.0772953 0.185393 -4.19898e-08 -0.077765 0.185963 0.00212496 -0.0772953 0.187518 0.00368057 -0.077765 0.187518 0.00368057 -0.0772953 0.189643 0.00424996 -0.077765 0.193324 0.00212496 -0.0772953 0.193324 0.00212496 -0.077765 0.193893 -4.19898e-08 -0.077765 0.193324 -0.00212504 -0.0772953 0.224827 -0.00425004 -0.077765 0.222702 -0.00368065 -0.0772953 0.222702 -0.00368065 -0.077765 0.221146 -0.00212504 -0.077765 0.220577 -4.19898e-08 -0.0772953 0.222702 0.00368057 -0.077765 0.224827 0.00424996 -0.077765 0.224827 0.00424996 -0.0772953 0.226952 0.00368057 -0.0772953 0.226952 0.00368057 -0.077765 0.228507 0.00212496 -0.0772953 0.228507 0.00212496 -0.077765 0.229077 -4.19898e-08 -0.077765 0.228507 -0.00212504 -0.0772953 0.228507 -0.00212504 -0.077765 0.226952 -0.00368065 -0.077765 0.236586 0.0483558 0.0577094 0.236827 0.04487 0.0577094 0.164943 -0.079934 -0.079265 0.215427 -0.0207844 -0.079265 0.165443 -4.19898e-08 -0.079265 0.165443 -0.0569 -0.079265 0.132943 -0.0632 -0.079265 0.159143 -0.0632 -0.079265 -0.0902896 -0.0632 -0.079265 -0.16149 -0.0632 -0.079265 -0.16779 -4.19898e-08 -0.079265 -0.17819 -0.0771 -0.079265 -0.1639 0.0627204 -0.079265 -0.16149 0.0632 -0.079265 -0.17819 0.0483 -0.079265 0.163598 0.0613547 -0.079265 0.165443 0.0569 -0.079265 0.164964 0.0593109 -0.079265 0.215906 0.0197766 -0.079265 0.216989 0.0195111 -0.079265 0.213364 0.0788 -0.079265 0.175843 0.0771 -0.079265 0.198785 0.0483 -0.079265 0.215427 0.0207843 -0.079265 -0.17819 0.0771 -0.079265 -0.211881 0.0794882 -0.079265 -0.201131 0.0771 -0.079265 -0.208573 0.0739444 -0.079265 -0.210273 0.0744 -0.079265 -0.217773 0.0771 -0.079265 -0.208573 0.0680555 -0.079265 -0.207329 0.0693 -0.079265 -0.206873 0.071 -0.079265 -0.207329 0.0727 -0.079265 -0.217773 0.0483 -0.079265 -0.219336 0.0195111 -0.079265 -0.217773 0.0207843 -0.079265 -0.217899 0.0202265 -0.079265 -0.218252 0.0197766 -0.079265 -0.19199 0.0334 -0.079265 -0.189045 0.0317 -0.079265 -0.189045 0.0283 -0.079265 -0.181048 0.00635471 -0.079265 -0.17969 0.000499958 -0.079265 -0.17819 -4.19898e-08 -0.079265 -0.19539 0.03 -0.079265 -0.201131 0.0157582 -0.079265 -0.194934 0.0283 -0.079265 -0.189045 -0.0283 -0.079265 -0.201131 -0.0771 -0.079265 -0.19539 -0.03 -0.079265 -0.194934 -0.0283 -0.079265 -0.16779 0.0483 -0.079265 -0.18859 -0.03 -0.079265 -0.19029 -0.0329445 -0.079265 -0.184844 -0.011014 -0.079265 -0.181048 -0.00635479 -0.079265 -0.206873 -0.071 -0.079265 -0.207329 -0.0693 -0.079265 -0.211973 -0.0680556 -0.079265 -0.217773 -0.0771 -0.079265 -0.217773 -0.0785 -0.079265 -0.211881 -0.0794883 -0.079265 -0.188326 -0.0882369 -0.079265 0.18598 -0.0882369 -0.079265 0.182846 -0.0888 -0.079265 0.215427 -0.0771 -0.079265 0.213364 -0.0788 -0.079265 0.215427 -0.0785 -0.079265 0.204982 -0.0693 -0.079265 0.204527 -0.071 -0.079265 0.206227 -0.0739445 -0.079265 0.215906 -0.0197767 -0.079265 0.216418 -0.0195218 -0.079265 0.207927 -0.0676 -0.079265 0.206227 -0.0680556 -0.079265 0.215553 -0.0202266 -0.079265 0.191343 -0.0329445 -0.079265 0.186699 -0.0283 -0.079265 0.175843 -4.19898e-08 -0.079265 0.175843 -0.0771 -0.079265 0.164599 -0.06005 -0.079265 0.198785 -0.0771 -0.079265 0.178701 -0.00635479 -0.079265 0.189643 -0.0266 -0.079265 0.191343 -0.0270556 -0.079265 0.192588 -0.0283 -0.079265 0.193043 -0.03 -0.079265 0.186699 -0.0317 -0.079265 0.187943 -0.0329445 -0.079265 0.189643 -0.0334 -0.079265 0.189643 0.0334 -0.079265 0.187943 0.0329444 -0.079265 0.187943 0.0270555 -0.079265 0.178701 0.00635471 -0.079265 0.177343 0.000499958 -0.079265 0.191343 0.0270555 -0.079265 0.192588 0.0283 -0.079265 0.198785 0.0157582 -0.079265 0.175843 0.0483 -0.079265 0.186243 0.03 -0.079265 0.186699 0.0283 -0.079265 0.191343 0.0329444 -0.079265 0.198785 0.0771 -0.079265 0.175843 0.0888 -0.079265 0.165367 0.0841826 -0.079265 0.16515 0.0845071 -0.079265 0.164826 0.0847238 -0.079265 0.164943 0.0799339 -0.079265 0.165309 0.0803 -0.079265 0.165443 0.0808 -0.079265 0.145443 0.0838 -0.079265 0.145736 0.0800929 -0.079265 0.14606 0.0798761 -0.079265 0.132943 0.0771 -0.079265 0.146443 0.0798 -0.079265 0.0879432 -0.0632 -0.079265 0.16515 -0.0845072 -0.079265 0.165367 -0.0841827 -0.079265 0.145577 -0.0803 -0.079265 0.145443 -0.0808 -0.079265 0.145577 -0.0843 -0.079265 0.165443 -0.0808 -0.079265 0.145943 -0.0846661 -0.079265 0.146443 -0.0848 -0.079265 0.175843 -0.0868 -0.079265 0.165443 -0.0838 -0.079265 0.209535 -0.0794883 -0.079265 0.120309 0.0843 -0.079265 0.101443 0.0848 -0.079265 0.100943 0.084666 -0.079265 0.100443 0.0838 -0.079265 0.100943 0.0799339 -0.079265 0.101443 0.0798 -0.079265 0.119443 0.0798 -0.079265 0.119943 0.0799339 -0.079265 0.120443 0.0838 -0.079265 0.120443 -0.0838 -0.079265 0.120309 -0.0803 -0.079265 0.119943 -0.079934 -0.079265 0.132943 -0.0771 -0.079265 0.10106 -0.0798762 -0.079265 0.100736 -0.0800929 -0.079265 0.101443 -0.0848 -0.079265 0.119943 -0.0846661 -0.079265 0.100519 -0.0804174 -0.079265 0.0879432 -0.0771 -0.079265 0.100443 -0.0808 -0.079265 0.100577 -0.0843 -0.079265 0.0564432 0.0798 -0.079265 0.0744432 0.0798 -0.079265 0.0879432 0.0771 -0.079265 0.075367 0.0841826 -0.079265 0.0298258 0.0847238 -0.079265 -0.0011732 0.0771 -0.079265 0.0555771 0.0803 -0.079265 0.0753092 0.0803 -0.079265 0.0754432 0.0808 -0.079265 0.0879432 0.0888 -0.079265 0.0748258 0.0847238 -0.079265 0.0744432 0.0848 -0.079265 0.0109432 0.084666 -0.079265 0.0104432 0.0808 -0.079265 0.0303092 0.0803 -0.079265 0.0564432 0.0848 -0.079265 0.0294432 0.0798 -0.079265 0.0554432 0.0838 -0.079265 0.0114432 0.0798 -0.079265 0.0554432 0.0808 -0.079265 0.0753092 -0.0803 -0.079265 0.0299432 -0.079934 -0.079265 0.0294432 -0.0798 -0.079265 0.0114432 -0.0798 -0.079265 0.0754432 -0.0838 -0.079265 0.0754432 -0.0808 -0.079265 0.0749432 -0.079934 -0.079265 0.0110605 -0.0847239 -0.079265 0.0559432 -0.079934 -0.079265 0.0304432 -0.0838 -0.079265 0.0304432 -0.0808 -0.079265 0.0105193 -0.0841827 -0.079265 0.0879432 -0.0868 -0.079265 0.0749432 -0.0846661 -0.079265 0.0114432 -0.0848 -0.079265 0.0554432 -0.0838 -0.079265 0.0554432 -0.0808 -0.079265 -0.0322896 0.084666 -0.079265 -0.0011732 0.0888 -0.079265 -0.0134069 0.0847238 -0.079265 -0.0327896 0.0838 -0.079265 -0.0324967 0.0800929 -0.079265 -0.0127896 0.0808 -0.079265 -0.0128657 0.0841826 -0.079265 -0.0322896 -0.079934 -0.079265 -0.0317896 -0.0798 -0.079265 -0.0011732 -0.0771 -0.079265 -0.0137896 -0.0798 -0.079265 -0.0327896 -0.0808 -0.079265 -0.0326556 -0.0843 -0.079265 -0.0127896 -0.0808 -0.079265 -0.0128657 -0.0804174 -0.079265 -0.0011732 -0.0868 -0.079265 -0.0452896 0.0888 -0.079265 -0.0587896 0.0848 -0.079265 -0.0902896 0.0771 -0.079265 -0.0777896 0.0838 -0.079265 -0.0776556 0.0803 -0.079265 -0.0772896 0.0799339 -0.079265 -0.0452896 0.0771 -0.079265 -0.0582896 0.0799339 -0.079265 -0.0577896 0.0808 -0.079265 -0.0579235 0.0843 -0.079265 -0.0776556 -0.0843 -0.079265 -0.0452896 -0.0771 -0.079265 -0.0902896 -0.0771 -0.079265 -0.0777896 -0.0808 -0.079265 -0.0587896 -0.0848 -0.079265 -0.0584069 -0.0847239 -0.079265 -0.0452896 -0.0868 -0.079265 -0.10329 0.084666 -0.079265 -0.122497 0.0800929 -0.079265 -0.122656 0.0843 -0.079265 -0.12279 0.0838 -0.079265 -0.13529 0.0771 -0.079265 -0.0902896 0.0888 -0.079265 -0.10329 -0.079934 -0.079265 -0.10379 -0.0798 -0.079265 -0.13529 -0.0771 -0.079265 -0.0902896 -0.0868 -0.079265 -0.10279 -0.0808 -0.079265 -0.147866 0.0841826 -0.079265 -0.17819 0.0888 -0.079265 -0.167713 0.0804173 -0.079265 -0.167172 0.0798761 -0.079265 -0.16679 0.0798 -0.079265 -0.13529 0.0888 -0.079265 0.0879432 0.0632 -0.079265 -0.0011732 0.0632 -0.079265 -0.0452896 0.0632 -0.079265 -0.14829 -0.079934 -0.079265 -0.16729 -0.079934 -0.079265 -0.16779 -0.0808 -0.079265 -0.17819 -0.0868 -0.079265 -0.16679 -0.0848 -0.079265 -0.14829 -0.0846661 -0.079265 -0.147924 -0.0843 -0.079265 -0.13529 -0.0868 -0.079265 -0.14779 -0.0808 -0.079265 0.132943 -0.0888 -0.079265 0.132943 -0.0868 -0.079265 0.0879432 -0.0888 -0.079265 -0.0902896 -0.0888 -0.079265 -0.201131 0.0483 -0.079265 0.216456 0.0206556 0.082735 0.216537 0.0205518 0.082735 0.216787 0.0204905 0.082735 0.236587 0.0245725 0.082735 0.236796 0.0247342 0.082735 0.236827 0.0248663 0.082735 0.236787 0.07865 0.082735 0.216577 0.0787598 0.082735 0.236677 0.0787598 0.082735 0.236527 0.0788 0.082735 0.228027 0.0788 0.082735 0.216427 0.0207843 0.082735 0.236789 0.0235931 -0.077765 0.236789 0.0235931 -0.081265 0.187958 0.013526 -0.079265 0.182498 0.0110139 -0.079265 0.177343 0.000499958 -0.077765 0.177343 -0.000500042 -0.077765 0.177343 -4.19898e-08 -0.079265 0.177343 -0.000500042 -0.079265 0.177343 0.000499958 0.078935 0.236527 0.0240452 0.0577094 0.236827 0.0240452 0.0577094 0.236527 0.0208836 0.0380506 0.236827 0.014785 0.0441492 0.236527 0.0138529 0.0488353 0.236527 0.0135256 0.0471898 0.236827 0.0138529 0.0488353 0.236827 0.0135256 0.0471898 0.236527 0.014785 0.0441492 0.236827 0.0138529 0.0455442 0.236827 0.0210047 0.05645 0.236527 0.0210047 0.05645 0.237827 0.06744 0.0644458 0.237827 0.0785 0.081735 0.237827 0.04487 0.0587094 0.237827 0.0248663 0.081735 0.237827 -0.0674401 0.0644458 0.237827 -0.0248664 0.081735 0.237827 -0.0248664 0.076235 0.237827 -0.0477381 0.0599359 0.237827 -0.0160327 0.0390255 0.237827 -0.0194305 0.0380896 0.237827 -0.0100723 0.0201683 0.237827 -0.00995049 0.0264364 0.237827 -0.00800004 0.0557094 0.237827 -0.00800004 0.0444236 0.237827 -0.014078 0.0434421 0.237827 0.0140779 0.0434421 0.237827 0.0158524 0.0406068 0.237827 0.0160326 0.0390255 0.237827 -0.00759812 0.0572094 0.237827 0.0248663 0.076235 0.237827 -0.00500004 0.0587094 0.237827 0.00799996 0.0444236 0.237827 0.00799996 0.0557094 0.237827 0.00694583 0.0140851 0.237827 -0.0202976 0.0571571 0.237827 -0.014078 0.0509374 0.237827 -0.0127062 0.0485615 0.237827 -0.00630709 0.0145312 0.237827 -0.00658126 0.0142433 0.237827 -0.0082739 0.0138028 0.237827 0.012929 0.049218 0.237827 0.0140779 0.0509374 0.237827 0.0202976 0.0571571 0.237827 0.00759803 0.0572094 0.237827 0.022017 0.058306 0.237827 0.00658118 0.0142433 0.237827 0.00618226 0.0153003 0.254327 0.00716335 0.0130165 0.250498 0.011719 0.0120481 0.25212 0.0101329 0.0123853 0.249746 0.0121818 0.0119498 0.238736 0.00908514 0.012608 0.254129 0.00801085 0.0128363 0.238827 0.0080659 0.0128246 0.237827 -0.0785 -0.081265 0.237827 0.06744 -0.0659758 0.237827 0.0248663 -0.076765 0.237827 0.0510342 -0.0626817 0.237827 -0.0160327 -0.0405554 0.237827 0.0159141 -0.0390977 0.237827 0.0180284 -0.048831 0.237827 -0.0138448 -0.0306182 0.237827 -0.00995049 -0.0279664 0.237827 -0.00694592 -0.015615 0.237827 0.018098 -0.055765 0.237827 0.0155 -0.057265 0.237827 -0.0248664 -0.076765 0.237827 -0.0360023 -0.0553305 0.237827 -0.0180285 -0.048831 0.237827 -0.0158513 -0.0421459 0.237827 -0.0159033 -0.0417657 0.237827 0.00630701 -0.0160611 0.237827 0.0233289 -0.0444041 0.237827 0.015851 -0.0421365 0.237827 0.0293145 -0.0502745 0.237827 0.0360022 -0.0553305 0.237827 0.0166692 -0.046444 0.237827 -0.0432821 -0.0594891 0.237827 -0.0180981 -0.055765 0.237827 -0.0185 -0.054265 0.237827 -0.0185 -0.0515371 0.237827 -0.00630709 -0.0160611 0.237827 -0.00616673 -0.016433 0.237827 -0.00618235 -0.0168303 0.237827 0.00694583 -0.015615 0.254214 0.00781102 -0.0144087 0.253741 0.00854682 -0.0142524 0.238827 0.0080659 -0.0143546 0.237525 0.012111 -0.0223496 0.237525 0.0594679 -0.0631792 0.237525 0.0515827 -0.0610619 0.236527 0.0677506 -0.0615333 0.236527 0.0524625 -0.0584636 0.237525 0.0369439 -0.0539031 0.237525 0.0304312 -0.0489793 0.236527 0.0178066 -0.0285844 0.236527 0.0126317 -0.0144122 0.236994 0.0113761 -0.014679 0.236994 0.0113761 0.013149 0.236527 0.0126317 0.0128823 0.236752 0.0216204 0.0345674 0.236527 0.0166073 0.0245824 0.237525 0.017149 0.0315454 0.236971 0.0529651 0.0583839 0.236527 0.0584073 0.0586158 0.236527 0.0574046 0.0583774 0.23706 0.0130799 0.0108293 0.191216 0.0715 0.078935 0.18598 -0.0882369 0.078935 0.132943 -0.0868 0.078935 0.164599 -0.06005 0.078935 0.191216 -0.0715 0.078935 0.182498 -0.011014 0.078935 0.165443 -0.0569 0.078935 0.165443 0.0569 0.078935 0.162293 0.0623559 0.078935 0.0879432 0.0632 0.078935 0.0429432 0.0715 0.078935 0.0429432 0.0632 0.078935 -0.0011732 0.0632 0.078935 -0.0452896 0.0632 0.078935 -0.0902896 0.0632 0.078935 -0.0902896 0.0715 0.078935 -0.16731 0.0593109 0.078935 -0.165944 0.0613547 0.078935 -0.190304 -0.0135261 0.078935 -0.217899 -0.0202266 0.078935 -0.217773 -0.0207844 0.078935 -0.190304 0.013526 0.078935 -0.16779 0.0569 0.078935 -0.184844 -0.011014 0.078935 -0.16779 -0.0569 0.078935 -0.217773 0.0207843 0.078935 -0.13529 0.0632 0.078935 0.159143 -0.0632 0.078935 0.132943 -0.0632 0.078935 0.0879432 -0.0632 0.078935 -0.0011732 -0.0632 0.078935 -0.0902896 -0.0632 0.078935 -0.13529 -0.0715 0.078935 0.216418 0.0195217 0.078935 0.215553 -0.0202266 0.078935 0.187958 -0.0135261 0.078935 0.209535 -0.0794883 0.078935 0.213364 -0.0788 0.078935 0.164943 -0.0846661 0.078935 0.146443 -0.0848 0.078935 0.145577 -0.0803 0.078935 0.145443 -0.0838 0.078935 0.165443 -0.0808 0.078935 0.165443 -0.0838 0.078935 0.145943 -0.079934 0.078935 0.132943 -0.0715 0.078935 0.146443 -0.0798 0.078935 0.164943 -0.079934 0.078935 -0.14879 -0.0848 0.078935 -0.16729 -0.0846661 0.078935 -0.147924 -0.0803 0.078935 -0.167656 -0.0843 0.078935 -0.188326 -0.0882369 0.078935 -0.16779 -0.0838 0.078935 -0.16729 -0.079934 0.078935 -0.148082 0.0845071 0.078935 -0.167497 0.0845071 0.078935 -0.185192 0.0888 0.078935 -0.147866 0.0841826 0.078935 -0.167172 0.0847238 0.078935 -0.13529 0.0888 0.078935 -0.188326 0.0882368 0.078935 -0.16779 0.0808 0.078935 -0.211881 0.0794882 0.078935 -0.217773 0.0715 0.078935 -0.217773 0.0785 0.078935 0.164443 0.0798 0.078935 0.145736 0.0800929 0.078935 0.145443 0.0808 0.078935 0.145577 0.0843 0.078935 0.146443 0.0848 0.078935 0.164443 0.0848 0.078935 0.182846 0.0888 0.078935 0.165367 0.0841826 0.078935 0.165443 0.0838 0.078935 0.209535 0.0794882 0.078935 0.165443 0.0808 0.078935 0.164943 0.0799339 0.078935 0.187958 0.013526 0.078935 0.215427 0.0207843 0.078935 0.213364 0.0788 0.078935 -0.12229 0.084666 0.078935 -0.13529 0.0715 0.078935 -0.12279 0.0808 0.078935 -0.122656 0.0843 0.078935 -0.0902896 0.0888 0.078935 -0.102924 0.0843 0.078935 -0.10279 0.0838 0.078935 -0.10329 -0.0846661 0.078935 -0.10379 -0.0848 0.078935 -0.13529 -0.0868 0.078935 -0.12229 -0.079934 0.078935 -0.12179 -0.0798 0.078935 -0.0902896 -0.0715 0.078935 -0.10329 -0.079934 0.078935 -0.0902896 -0.0868 0.078935 -0.10279 -0.0808 0.078935 -0.10279 -0.0838 0.078935 -0.0587896 0.0798 0.078935 -0.0776556 0.0803 0.078935 -0.0777896 0.0808 0.078935 -0.0772896 0.084666 0.078935 -0.0587896 0.0848 0.078935 -0.0582896 0.084666 0.078935 -0.0577896 0.0838 0.078935 -0.0777896 -0.0838 0.078935 -0.0767896 -0.0798 0.078935 -0.0587896 -0.0798 0.078935 -0.0582896 -0.079934 0.078935 -0.0577896 -0.0808 0.078935 -0.0321722 0.0798761 0.078935 -0.0128657 0.0841826 0.078935 -0.0011732 0.0888 0.078935 -0.0127896 0.0808 0.078935 -0.0129235 0.0803 0.078935 -0.0452896 0.0715 0.078935 -0.0327896 0.0808 0.078935 -0.0452896 0.0888 0.078935 -0.0317896 0.0848 0.078935 -0.0137896 0.0798 0.078935 -0.0132896 -0.0846661 0.078935 -0.0129235 -0.0843 0.078935 -0.0127896 -0.0838 0.078935 -0.0452896 -0.0868 0.078935 -0.0452896 -0.0715 0.078935 -0.0326556 -0.0803 0.078935 -0.0011732 -0.0715 0.078935 -0.0128657 -0.0804174 0.078935 -0.0127896 -0.0808 0.078935 0.0105771 0.0843 0.078935 -0.0011732 0.0715 0.078935 0.0303092 0.0803 0.078935 0.0114432 0.0798 0.078935 0.0110605 0.0798761 0.078935 0.0104432 0.0808 0.078935 0.0104432 0.0838 0.078935 0.0114432 0.0848 0.078935 0.0429432 0.0888 0.078935 0.0301503 0.0845071 0.078935 0.0298258 -0.0798762 0.078935 0.0301503 -0.0800929 0.078935 -0.0011732 -0.0868 0.078935 0.0299432 -0.0846661 0.078935 0.0105193 -0.0841827 0.078935 0.0104432 -0.0838 0.078935 0.0104432 -0.0808 0.078935 0.0105771 -0.0803 0.078935 0.0109432 -0.079934 0.078935 0.0114432 -0.0798 0.078935 0.0429432 -0.0868 0.078935 0.0555193 0.0841826 0.078935 0.0557361 0.0845071 0.078935 0.0559432 0.0799339 0.078935 0.0555771 0.0803 0.078935 0.0564432 0.0848 0.078935 0.0753092 0.0803 0.078935 0.0753092 -0.0803 0.078935 0.0879432 -0.0868 0.078935 0.0554432 -0.0838 0.078935 0.0429432 -0.0715 0.078935 0.0879432 -0.0715 0.078935 0.0564432 -0.0798 0.078935 0.0753092 -0.0843 0.078935 0.0749432 -0.0846661 0.078935 0.0744432 -0.0848 0.078935 0.100943 0.084666 0.078935 0.119943 0.0799339 0.078935 0.132943 0.0715 0.078935 0.119443 0.0798 0.078935 0.0879432 0.0715 0.078935 0.0879432 0.0888 0.078935 0.100443 0.0838 0.078935 0.100577 0.0843 0.078935 0.101443 0.0848 0.078935 0.119943 0.084666 0.078935 0.132943 0.0888 0.078935 0.120443 0.0838 0.078935 0.119443 -0.0848 0.078935 0.119943 -0.079934 0.078935 0.100577 -0.0843 0.078935 0.100443 -0.0838 0.078935 0.100577 -0.0803 0.078935 0.100943 -0.079934 0.078935 0.101443 -0.0798 0.078935 0.0429432 -0.0888 0.078935 0.132943 -0.0888 0.078935 0.221146 0.00212496 -0.077765 0.187958 -0.0135261 -0.077765 0.182498 -0.011014 -0.077765 0.178701 -0.00635479 -0.077765 0.185963 0.00212496 -0.077765 0.178701 0.00635471 -0.077765 0.182498 0.0110139 -0.077765 0.191768 0.00368057 -0.077765 0.187958 0.013526 -0.077765 0.236827 0.0236014 -0.077765 0.220577 -4.19898e-08 -0.077765 0.193324 -0.00212504 -0.077765 0.191768 -0.00368065 -0.077765 0.236527 0.0788238 -0.0623076 0.237496 0.0788224 -0.0649771 0.237525 0.0675593 -0.0642698 0.237525 0.078818 -0.0650571 0.236527 0.0677506 0.0600033 0.237525 0.0675593 0.0627399 0.228027 0.0798 0.082735 0.228027 0.0798 0.081735 0.217827 0.0798 0.081735 0.216727 0.0798 0.081735 0.220538 0.0798 -0.0772953 0.216727 0.0798 -0.078265 0.236527 0.0798 -0.081265 0.227216 0.0798 -0.0772953 0.228027 0.0798 -0.081265 0.228027 0.0798 -0.082265 0.186328 0.0891743 -0.0772953 0.19921 0.0843897 -0.0772953 0.209883 0.0804257 -0.078265 0.205375 0.0821 -0.0772953 0.236827 0.0155 -0.056265 0.236527 -0.00500004 0.0577094 0.236827 0.00499996 0.0577094 0.249806 0.00699996 0.0335288 0.236527 0.00699996 0.0335288 0.254327 0.0037524 0.0244309 0.254327 0.00568622 0.0291524 0.254255 0.00600524 0.0298497 0.254327 -0.00266836 0.0228363 0.254327 -0.000964162 0.0219342 0.254327 0.000964078 0.0219342 0.254327 0.00266827 0.0228363 0.236527 0.0037524 0.0244309 0.254327 0.00266827 -0.0243663 0.236527 -0.000964162 -0.0234641 0.254327 -0.00266836 -0.0243663 0.254102 0.00624891 -0.0318996 0.236527 0.0037524 -0.0259609 0.237055 0.0124166 -0.0425069 0.236527 0.00893486 -0.0370328 0.236527 0.0158981 -0.0470806 0.236827 0.0132137 -0.0436222 0.252327 0.00720751 -0.0338482 0.178701 0.00635471 0.078935 0.177343 0.000499958 0.0773679 0.182498 0.0110139 0.078935 0.182498 0.0110139 0.0773679 0.236789 0.0235931 0.081735 0.236789 0.0235931 0.077235 0.236527 0.0235389 0.0773679 0.187958 0.013526 0.0773679 0.236827 -0.00796159 0.077235 0.236527 -0.00796159 0.077235 0.236527 -4.19898e-08 0.077235 0.236527 0.0079615 0.077235 0.236527 0.015923 0.077235 0.216427 0.0207843 -0.082265 0.217827 0.0788 -0.082265 0.216727 0.0788 -0.082265 0.216427 0.0785 -0.082265 0.236677 0.0787598 -0.082265 0.255327 0.008398 -0.0293981 0.255327 0.00333535 -0.0236213 0.255327 0.00570732 -0.000764971 0.255327 0.00653001 -0.0136587 0.255327 0.00419244 0.0145829 0.255327 0.00120511 0.0209637 0.255327 0.00333535 0.0220913 0.255327 0.00469051 0.0240846 0.255327 -0.0046906 -0.0256145 0.255327 -0.00695552 -0.0135683 0.255327 -0.0057074 -0.000764971 0.255327 -0.00120519 -0.0224936 0.255327 -0.00419252 -0.0161129 0.255327 -0.00333544 -0.0236213 0.255327 -0.00839808 0.0278681 0.255327 -0.00423939 0.0157746 0.255327 -0.00333544 0.0220913 0.255327 -0.00419252 0.0145829 0.245562 0.0126387 -0.0354464 0.253361 0.0104084 -0.0313107 0.238827 0.00903454 -0.0283678 0.238827 0.00521079 -0.0170674 0.252327 0.0107884 0.0305353 0.253453 0.0103598 0.0296826 0.189643 0.0266 -0.079265 0.187943 0.0270555 -0.0772953 0.186699 0.0317 -0.0772953 0.186699 0.0317 -0.079265 0.189643 0.0334 -0.0772953 0.192588 0.0317 -0.079265 0.193043 0.03 -0.0772953 0.193043 0.03 -0.079265 0.192588 0.0283 -0.0772953 0.246062 0.0121531 -0.03673 0.246062 0.0121531 0.0352001 0.236827 0.0170873 -0.0491693 0.236527 0.00631971 0.0305187 0.236527 0.0162653 -0.0561127 0.236827 0.0169142 -0.0556792 0.236527 0.0155 -0.056265 0.236827 0.0165 -0.055997 0.236827 0.00599996 0.0574415 0.236527 0.00499996 0.0577094 0.236827 0.00673201 0.0567094 0.254448 0.00782864 -0.000764971 0.251205 0.012205 -0.0124642 0.251205 0.0110713 -0.000764971 0.250232 0.0117216 -0.000764971 0.249084 0.01195 -0.000764971 0.249084 0.0130656 0.0107563 0.255327 0.00695544 0.0120383 0.254448 0.00903275 -0.0131379 0.254669 0.00879079 -0.013188 0.255098 0.00685537 -0.000764971 0.255031 0.00822797 0.0117746 0.237748 0.0466861 0.0585472 0.237525 0.0484822 0.0583916 0.237827 0.047738 0.0599359 0.237827 0.0574136 0.0629569 0.237525 0.0577952 0.0612899 0.237827 0.0785036 0.0652039 0.237802 0.0786152 0.064724 0.237827 0.0105022 -0.0229294 0.237827 0.0138448 -0.0306182 0.237525 0.0153661 -0.0298372 0.237525 0.0195528 -0.0368466 0.237827 0.0181439 -0.0378158 0.237525 0.0246022 -0.0432624 0.237525 0.0440333 -0.0579528 0.237827 0.043282 -0.0594891 0.237827 0.0591313 -0.0648558 0.237802 0.0786152 -0.066254 0.237729 0.0787161 -0.0657757 0.237827 0.00827381 0.0138028 0.237525 0.0206764 0.0368977 0.237827 0.0193924 0.0380383 0.237827 0.0156755 0.0324133 0.237827 0.0125577 0.0264355 0.237525 0.0141128 0.0257239 0.237827 0.0100723 0.0201683 0.237525 0.0116923 0.0196207 0.254327 0.00600861 -0.0149534 0.238827 0.00546027 -0.0155291 0.254327 0.00521079 -0.0170674 0.254327 0.00517954 0.014743 0.238827 0.00546027 0.0139992 0.254327 0.00546027 0.0139992 0.236655 0.0797936 -0.0653183 0.237827 0.0785 -0.081265 0.237486 0.0793771 -0.0659725 0.237446 0.0794192 -0.081265 0.23703 0.0796986 -0.0655668 0.236527 0.0798 -0.0772953 0.23703 0.0796986 0.0640369 0.237446 0.0794192 0.081735 0.237653 0.07915 0.081735 0.237827 0.0785147 0.065207 0.186328 0.0891743 -0.078265 0.213364 0.0798 -0.078265 0.186328 0.0891743 0.077935 0.209883 0.0804257 0.077935 0.213364 0.0798 0.0773679 0.209883 0.0804257 0.0773679 0.236527 0.0212952 0.0375843 0.254984 0.00916851 -0.0310472 0.254119 0.00979692 -0.0323414 0.254657 0.00766381 -0.0325326 0.252827 0.010276 -0.0332998 0.252827 0.010276 0.0317698 0.254657 0.00946335 0.0301299 0.254656 0.00764753 0.0310115 0.255327 0.008398 0.0278681 0.255046 0.00909652 0.0293662 0.254969 0.00738453 0.0304227 0.238553 0.0146076 -0.0405746 0.238497 0.0128301 -0.0415112 0.238036 0.0151409 -0.0412681 0.237829 0.0157733 -0.0420521 0.237827 0.0158512 -0.0421459 0.237829 0.0157733 0.0405221 0.238036 0.0151409 0.0397382 0.238225 0.00821718 0.0426585 0.239327 0.00837786 0.0413528 0.253752 0.0103972 0.0299312 0.254006 0.0102916 0.0302095 0.252791 0.0105937 0.0315385 0.254234 0.00973551 0.0306869 0.254768 0.00969227 0.0289768 0.254176 0.0100592 0.030475 0.254973 0.00943066 0.0291799 0.254709 0.00924044 0.0274889 0.254102 0.00985619 0.0286411 0.254462 0.00984166 0.0287876 0.245928 0.0126838 0.034622 0.239327 0.0142196 0.0385198 0.245562 0.0126387 0.0339164 0.245762 0.0127411 0.0342555 0.25252 0.0108716 0.0308691 0.252684 0.0108032 0.0312218 0.246034 0.0124764 0.0349552 0.255327 0.00423931 0.0157746 0.255251 0.00874695 0.027711 0.255251 0.00461108 0.0156838 0.255034 0.00904278 0.0275778 0.254327 0.00930986 0.0274576 0.254327 0.00521079 0.0155375 0.237966 0.0154867 0.0394593 0.237981 0.0154561 0.0394903 0.238563 0.0149799 0.0378073 0.238358 0.015149 0.0384761 0.238517 0.0149302 0.0387886 0.238553 0.0146076 0.0390447 0.239307 0.0145478 0.0382611 0.239203 0.0147525 0.0379113 0.239033 0.0147977 0.0375316 0.255034 0.00492625 0.0156069 0.254709 0.00513684 0.0155555 0.255034 0.00489042 0.0146961 0.255251 0.00457018 0.0146442 0.254709 0.0051044 0.0147308 0.254709 0.00539582 0.0139587 0.255327 0.00461353 0.0134672 0.255327 0.00543605 0.0126036 0.255251 0.00493757 0.0136708 0.255034 0.00521227 0.0138434 0.255034 0.00584091 0.0131833 0.254709 0.00596503 0.0133611 0.254327 0.00600861 0.0134235 0.255327 0.00653001 0.0121288 0.255251 0.00565516 0.0129174 0.23812 0.0149197 0.0370268 0.237837 0.0157654 0.0402169 0.237844 0.0157199 0.0402106 0.238099 0.0153481 0.0389898 0.238316 0.0151743 0.0383952 0.237897 0.0156644 0.0390063 0.237845 0.0158452 0.0390157 0.237831 0.0158112 0.0402231 0.238827 0.0146755 0.0371885 0.238444 0.0147389 0.0371465 0.237879 0.015604 0.0376472 0.237827 0.0158512 0.0406159 0.237828 0.0158571 0.0402294 0.237827 0.0159032 0.0402358 0.237827 0.0159141 0.0375677 0.237827 0.0155093 0.0366364 0.238268 0.0151109 0.0377737 0.238032 0.0153266 0.0377184 0.237983 0.0154967 0.0389975 0.237827 0.015848 0.0406062 0.237827 0.0158502 0.0406065 0.255251 0.00660957 0.0125031 0.255193 0.00705939 0.0125274 0.255034 0.00667702 0.0128204 0.254827 0.00713549 0.0128854 0.254709 0.00672209 0.0130324 0.254327 0.00673792 0.0131069 0.238827 0.00903454 0.0268379 0.238327 0.0147872 0.0371145 0.238327 0.00915724 0.0267841 0.237961 0.0150924 0.0369125 0.237903 0.0151902 0.0368477 0.238327 0.00534094 0.0155057 0.237961 0.00949247 0.0266372 0.237827 0.0099504 0.0264364 0.255308 0.00727976 0.0119711 0.254315 0.00737935 0.0129706 0.254811 0.00740549 0.0128283 0.255034 0.00710245 0.01273 0.254578 0.00819425 0.0126615 0.254908 0.00827366 0.0122732 0.255175 0.00736904 0.0124626 0.254092 0.00886297 0.0125201 0.254351 0.0090406 0.0121127 0.254448 0.00903275 0.0116079 0.237827 0.00616664 0.0149031 0.237827 0.00630701 0.0145312 0.237961 0.00567309 0.0148231 0.237961 0.0062949 0.0138334 0.237961 0.00569653 0.0154189 0.238327 0.00531179 0.0147645 0.237961 0.00588364 0.0142652 0.238327 0.00608532 0.0135333 0.238327 0.00676577 0.013238 0.238827 0.00521079 0.0155375 0.238827 0.00517954 0.014743 0.238327 0.00557371 0.0140705 0.238827 0.00600861 0.0134235 0.238827 0.00673792 0.0131069 0.253741 0.00854682 0.0127224 0.252729 0.0106266 0.0117757 0.252827 0.0106189 0.0112711 0.25085 0.012035 0.0118459 0.252471 0.010449 0.012183 0.251205 0.012205 0.0109342 0.237903 0.00819425 0.0134285 0.237961 0.00684188 0.013596 0.238327 0.00809376 0.0129557 0.238444 0.00808173 0.0128991 0.250333 0.0118634 0.0120174 0.250872 0.0124192 0.0113956 0.251108 0.0122127 0.0114388 0.250643 0.0122151 0.0118079 0.250958 0.0124219 0.0108894 0.249084 0.0122921 0.0119263 0.24991 0.0126119 0.011724 0.250031 0.0128742 0.0113005 0.250077 0.0129 0.0107906 0.237751 0.00912378 0.0136249 0.238358 0.00903592 0.0126965 0.237961 0.00816986 0.0133137 0.23812 0.0081268 0.0131111 0.238038 0.00902598 0.012921 0.237825 0.00905684 0.013247 0.238104 0.00996093 0.0125002 0.238465 0.0100734 0.0123979 0.249084 0.0127492 0.011695 0.23764 0.0127492 0.011695 0.249084 0.0130318 0.0112676 0.237267 0.0113257 0.0124332 0.237934 0.0115015 0.0120944 0.237186 0.0124335 0.0119739 0.236962 0.0125158 0.0120622 0.236689 0.0126364 0.0122649 0.237573 0.011389 0.0121966 0.237799 0.00989754 0.0127367 0.237595 0.00989298 0.0130712 0.237525 0.00994795 0.0134525 0.237064 0.0113211 0.0127677 0.236527 0.0127348 0.0125013 0.23764 0.0122921 0.0119263 0.236666 0.0131072 0.0114829 0.236858 0.012886 0.0118261 0.237273 0.0128035 0.011699 0.237316 0.0123898 0.0119442 0.237181 0.0130529 0.011296 0.23764 0.0130318 0.0112676 0.23764 0.0130656 0.0107563 0.236695 0.0218344 0.0347583 0.236529 0.0215041 0.0333218 0.237035 0.0211742 0.0375467 0.236582 0.0219416 0.0362117 0.237095 0.0213392 0.0358007 0.236919 0.0217082 0.0360068 0.236527 0.0220837 0.0352383 0.236586 0.0211637 0.0377463 0.236688 0.0208836 0.0380506 0.237376 0.0209975 0.037239 0.237654 0.0203867 0.0371889 0.237512 0.0207016 0.0375574 0.237327 0.0200427 0.038702 0.23716 0.0208827 0.0378712 0.236827 0.0201375 0.0387967 0.237327 0.0146903 0.0440545 0.237693 0.0197839 0.0384432 0.237693 0.0144314 0.0437957 0.237827 0.0194304 0.0380896 0.237693 0.0133909 0.0453529 0.237327 0.0137291 0.045493 0.236827 0.014785 0.0502303 0.237327 0.0137291 0.0488866 0.237327 0.0133916 0.0471898 0.237693 0.0130256 0.0471898 0.237693 0.0133909 0.0490266 0.237693 0.0144314 0.0505839 0.237827 0.012929 0.0451615 0.237827 0.0125256 0.0471898 0.237327 0.0209099 0.0565447 0.237327 0.0146903 0.0503251 0.237209 0.0240452 0.0577855 0.237327 0.0223484 0.0575059 0.236827 0.0223997 0.0573821 0.237693 0.0206511 0.0568035 0.237693 0.0222083 0.0578441 0.237534 0.0240452 0.0580023 0.237693 0.0240452 0.0582094 0.237827 0.0240452 0.0587094 0.237751 0.04487 0.0583267 0.237751 0.0240452 0.0583267 0.237693 0.04487 0.0582094 0.237534 0.04487 0.0580023 0.237327 0.04487 0.0578434 0.237327 0.0240452 0.0578434 0.236764 0.0466169 0.0577094 0.237318 0.0484543 0.0580357 0.237569 0.0466735 0.0581185 0.237209 0.04487 0.0577855 0.237215 0.0466486 0.0578175 0.236527 0.0554229 0.0580599 0.236762 0.0529418 0.0580317 0.236527 0.0487965 0.0577094 0.236986 0.0484096 0.0577946 0.236527 0.051963 0.057789 0.236527 0.0551146 0.058026 0.252327 0.0107884 -0.0320653 0.245762 0.0127411 -0.0357855 0.25252 0.0108716 -0.032399 0.245928 0.0126838 -0.0361519 0.252791 0.0105937 -0.0330684 0.239033 0.0147977 -0.0390615 0.239203 0.0147525 -0.0394412 0.239307 0.0145478 -0.039791 0.246034 0.0124764 -0.0364851 0.254657 0.00946335 -0.0316599 0.254052 0.00991276 -0.0302902 0.254912 0.00950131 -0.030858 0.254408 0.00990398 -0.0304484 0.25471 0.00975952 -0.0306477 0.255034 0.00904278 -0.0291078 0.255193 0.00885393 -0.0291928 0.254062 0.0101198 -0.0321271 0.253652 0.0104509 -0.031569 0.253898 0.0103495 -0.0318558 0.252684 0.0108032 -0.0327517 0.238517 0.0149302 -0.0403186 0.237981 0.0154561 -0.0410202 0.237844 0.0157199 -0.0417406 0.237827 0.015848 -0.0421361 0.239327 0.0142196 -0.0400497 0.238358 0.015149 -0.040006 0.238563 0.0149799 -0.0393372 0.255327 0.00423931 -0.0173045 0.255251 0.00874695 -0.029241 0.255193 0.00472505 -0.017186 0.254327 0.00930986 -0.0289875 0.254709 0.00924044 -0.0290188 0.254827 0.00918769 -0.0290425 0.254827 0.00508063 -0.0170992 0.238099 0.0153481 -0.0405197 0.237937 0.0155258 -0.0411188 0.237829 0.0158418 -0.0417573 0.237834 0.0157806 -0.0417489 0.237827 0.0159032 -0.0417657 0.237858 0.0157839 -0.0405425 0.23822 0.0152472 -0.0401723 0.237951 0.0155508 -0.0405303 0.237827 0.0160326 -0.0405554 0.238827 0.0146755 -0.0387184 0.238327 0.0147872 -0.0386445 0.237961 0.0150924 -0.0384424 0.238181 0.0151744 -0.0392874 0.23792 0.0155064 -0.0392022 0.255327 0.00543605 -0.0141336 0.255251 0.00660957 -0.014033 0.255193 0.00572233 -0.0145435 0.255327 0.00461353 -0.0149971 0.255193 0.00468599 -0.0161929 0.255327 0.00419244 -0.0161129 0.255193 0.0050369 -0.0152631 0.254827 0.00534683 -0.0154578 0.254709 0.00672209 -0.0145624 0.254827 0.00593191 -0.0148436 0.254827 0.00671007 -0.0145058 0.255193 0.00663396 -0.0141478 0.254327 0.00673792 -0.0146368 0.254327 0.00546027 -0.0155291 0.254327 0.00517954 -0.016273 0.254827 0.00504729 -0.0162515 0.238327 0.00534094 -0.0170356 0.237961 0.00569653 -0.0169488 0.237827 0.0099504 -0.0279664 0.238327 0.00915724 -0.0283141 0.237961 0.00949247 -0.0281671 0.237827 0.0155093 -0.0381664 0.255327 0.00695544 -0.0135683 0.255251 0.007035 -0.0139426 0.255034 0.00667702 -0.0143504 0.254827 0.00713549 -0.0144154 0.254709 0.00714752 -0.014472 0.254327 0.00716335 -0.0145464 0.23812 0.00679882 -0.0149233 0.237827 0.00658118 -0.0157733 0.237961 0.0062949 -0.0153634 0.237827 0.00616664 -0.016433 0.237961 0.00588364 -0.0157951 0.237827 0.00618226 -0.0168303 0.237961 0.00567309 -0.016353 0.238327 0.00608532 -0.0150633 0.238327 0.00557371 -0.0156004 0.238327 0.00531179 -0.0162944 0.238827 0.00673792 -0.0146368 0.238827 0.00600861 -0.0149534 0.238827 0.00517954 -0.016273 0.254351 0.0090406 -0.0136426 0.255158 0.00792793 -0.0133667 0.25503 0.00798752 -0.013863 0.254562 0.00881009 -0.0136909 0.255193 0.00705939 -0.0140573 0.255034 0.00710245 -0.0142599 0.253888 0.00838568 -0.0142866 0.254277 0.00866199 -0.0140925 0.254684 0.00794476 -0.0142442 0.237961 0.00684188 -0.0151259 0.238444 0.00808173 -0.014429 0.238327 0.00676577 -0.0147679 0.250498 0.011719 -0.0135781 0.25085 0.012035 -0.0133759 0.251108 0.0122127 -0.0129687 0.25212 0.0101329 -0.0139152 0.254092 0.00886297 -0.01405 0.252471 0.010449 -0.013713 0.252729 0.0106266 -0.0133057 0.252827 0.0106189 -0.012801 0.237751 0.00912378 -0.0151548 0.237825 0.00905684 -0.014777 0.237525 0.00994795 -0.0149824 0.238038 0.00902598 -0.0144509 0.238358 0.00903592 -0.0142265 0.237827 0.00827381 -0.0153327 0.237903 0.00819425 -0.0149584 0.23812 0.0081268 -0.0146411 0.238736 0.00908514 -0.0141379 0.249305 0.0122801 -0.0134588 0.249084 0.0122921 -0.0134563 0.249416 0.0130476 -0.01229 0.249084 0.0130656 -0.0122863 0.249951 0.0120989 -0.0134973 0.24936 0.0127343 -0.0132281 0.250324 0.0127558 -0.0128552 0.250384 0.0127756 -0.0123462 0.2494 0.0130147 -0.0128011 0.250165 0.0125086 -0.0132758 0.2366 0.0126853 -0.0139034 0.236527 0.0126723 -0.0141365 0.237595 0.00989298 -0.0146012 0.237064 0.0113211 -0.0142977 0.237799 0.00989754 -0.0142666 0.237267 0.0113257 -0.0139631 0.238104 0.00996093 -0.0140301 0.237573 0.011389 -0.0137266 0.238465 0.0100734 -0.0139279 0.237934 0.0115015 -0.0136243 0.23764 0.0130656 -0.0122863 0.249084 0.0130318 -0.0127975 0.23764 0.0130318 -0.0127975 0.249084 0.0127492 -0.0132249 0.23764 0.0127492 -0.0132249 0.236527 0.0129771 -0.0136033 0.237054 0.013063 -0.0128554 0.236527 0.0131292 -0.0131017 0.236527 0.0131281 -0.0131089 0.23674 0.0129153 -0.0134229 0.237171 0.0128215 -0.013247 0.236863 0.012556 -0.01365 0.236527 0.0129286 -0.013706 0.23764 0.0122921 -0.0134563 0.237228 0.0124191 -0.0134927 0.236902 0.0130891 -0.0124061 0.237827 0.00499996 0.0587094 0.237693 0.00499996 0.0582094 0.237693 0.00624996 0.0578745 0.237327 0.00499996 0.0578434 0.236827 0.00699996 0.0557094 0.237327 0.00713393 0.0557094 0.237327 0.00606695 0.0575575 0.237327 0.00684803 0.0567764 0.237827 0.00649996 0.0583075 0.237693 0.00716502 0.0569594 0.237693 0.00749996 0.0557094 0.237209 0.00707608 0.0444236 0.237534 0.00729285 0.0444236 0.237534 0.00729285 0.0557094 0.237751 0.00761727 0.0444236 0.238005 0.00814817 0.0432192 0.237358 0.00699996 0.0422106 0.236827 0.00699996 0.0444236 0.238223 0.00777346 0.0426575 0.239081 0.00711743 0.0409694 0.238051 0.00737435 0.0425686 0.237742 0.0070984 0.0424091 0.239364 0.00789808 0.0414109 0.239275 0.00744224 0.0412722 0.250254 0.00744224 0.0342274 0.25006 0.00711743 0.0339246 0.238827 0.00699996 0.0405736 0.251044 0.00696695 0.0328498 0.252327 0.00686824 0.0321772 0.251466 0.00744025 0.0334936 0.252727 0.0073663 0.0327628 0.252827 0.00822732 0.0327634 0.251281 0.00711176 0.0332224 0.250343 0.00789808 0.0343661 0.250306 0.00837786 0.034308 0.251561 0.00788147 0.0336048 0.251544 0.00834014 0.033532 0.254112 0.00792086 0.0317303 0.254077 0.00751932 0.0318245 0.253355 0.00668128 0.0314407 0.254041 0.00631971 0.0305187 0.253918 0.00713773 0.0318018 0.254698 0.00669801 0.0306297 0.252549 0.00703701 0.0325233 0.253663 0.00684146 0.0316661 0.252826 0.00779105 0.0328485 0.255237 0.00699487 0.029599 0.255251 0.00624892 0.0288986 0.254631 0.00610507 0.0298833 0.254827 0.00580834 0.0290973 0.255034 0.0059532 0.029032 0.255193 0.00614198 0.0289468 0.254397 0.00644985 0.0306143 0.254899 0.00702628 0.0305624 0.25495 0.00632831 0.0298474 0.255163 0.00664084 0.0297476 0.254709 0.0057556 0.0291211 0.255327 0.00659775 0.0287412 0.254827 -0.00387817 0.0243845 0.254827 -0.00275773 0.0227365 0.255327 -0.00120519 0.0209637 0.255193 -0.00108468 0.0214489 0.255193 0.00300181 0.0224638 0.255193 0.00422146 0.0242578 0.255193 -0.00422154 0.0242578 0.255034 -0.00402725 0.0243295 0.255193 -0.0030019 0.0224638 0.254827 -0.000996453 0.0218042 0.254827 0.000996369 0.0218042 0.255193 0.00108459 0.0214489 0.254827 0.00275764 0.0227365 0.254327 -0.00375248 0.0244309 0.254827 0.00387808 0.0243845 0.254327 0.0037524 -0.0259609 0.255251 0.00111287 -0.022865 0.255251 0.00308007 -0.0239064 0.255327 0.00120511 -0.0224936 0.255034 0.00286366 -0.0241481 0.255034 0.00103467 -0.0231799 0.255251 -0.00111295 -0.022865 0.255034 -0.00286374 -0.0241481 0.255251 -0.00308016 -0.0239064 0.255251 -0.0043316 -0.0257471 0.255034 -0.00402725 -0.0258594 0.254827 0.00387808 -0.0259145 0.255193 0.00422146 -0.0257877 0.254709 0.00382381 -0.0259345 0.254709 0.00271905 -0.0243096 0.255034 -0.00103476 -0.0231799 0.254709 -0.000982509 -0.0233903 0.254709 0.000982425 -0.0233903 0.254327 0.000964078 -0.0234641 0.254327 -0.000964162 -0.0234641 0.254709 -0.00271914 -0.0243096 0.254709 -0.00382389 -0.0259345 0.255327 0.00659775 -0.0302711 0.255327 0.00469051 -0.0256145 0.255251 0.00624892 -0.0304285 0.255251 0.00433151 -0.0257471 0.255193 0.00614198 -0.0304767 0.255034 0.0059532 -0.0305619 0.255034 0.00402717 -0.0258594 0.254827 0.00580834 -0.0306273 0.254173 0.00757271 -0.0332153 0.254975 0.00693959 -0.0319107 0.252786 0.00810814 -0.0342816 0.252827 0.00847603 -0.0341727 0.254234 0.00793601 -0.0330898 0.252757 0.00798239 -0.0342888 0.253452 0.00676704 -0.032971 0.254464 0.00637221 -0.0319814 0.255046 0.00729696 -0.031769 0.25477 0.0066148 -0.0319853 0.254004 0.00722318 -0.0332368 0.253751 0.00694035 -0.033151 0.254327 0.00568622 -0.0306824 0.254709 0.0057556 -0.0306511 0.245563 0.00910569 -0.0373283 0.252516 0.00742288 -0.0341063 0.252574 0.00751908 -0.0341703 0.252677 0.00773877 -0.0342584 0.246063 0.0103481 -0.0376049 0.239243 0.0119476 -0.0410569 0.245986 0.00987285 -0.0377267 0.238827 0.0111906 -0.0406997 0.245804 0.0094216 -0.0376262 0.239327 0.0124044 -0.04093 0.238371 0.0123914 -0.0416858 0.238089 0.0119918 -0.0416834 0.239062 0.0115092 -0.0409737 0.23772 0.0117268 -0.0415045 0.237513 0.0126108 -0.0425658 0.237693 0.0136178 -0.0433277 0.237998 0.013381 -0.0422329 0.237856 0.0129616 -0.0424661 0.237327 0.013322 -0.0435433 0.237827 0.0140218 -0.0430331 0.237693 0.0162837 -0.0467623 0.237327 0.0160014 -0.0469953 0.236827 0.0158981 -0.0470806 0.236827 0.0175 -0.0515371 0.237327 0.0176339 -0.0515371 0.237693 0.0175579 -0.0490002 0.237327 0.0172134 -0.049124 0.237534 0.0177929 -0.0515371 0.237827 0.0185 -0.0515371 0.237209 0.0175761 -0.054265 0.237209 0.0175761 -0.0515371 0.237327 0.0176339 -0.054265 0.237693 0.018 -0.0515371 0.237534 0.0177929 -0.054265 0.237693 0.018 -0.054265 0.237751 0.0181173 -0.054265 0.237751 0.0181173 -0.0515371 0.237827 0.0185 -0.054265 0.237327 0.017348 -0.055332 0.237693 0.017665 -0.055515 0.236827 0.017232 -0.055265 0.236827 0.0175 -0.054265 0.237327 0.0165669 -0.056113 0.237693 0.01675 -0.05643 0.237827 0.017 -0.056863 0.237327 -0.0155 -0.0563989 0.237327 0.0155 -0.0563989 0.237693 0.0155 -0.056765 0.236781 0.0797748 -0.0653983 0.237796 0.0787358 -0.0662865 0.237827 0.0785 -0.0667492 0.237827 0.0785036 -0.0667338 0.237827 0.0785073 -0.0667349 0.237705 0.0789568 -0.0658341 0.237165 0.079595 -0.0652454 0.237623 0.0791818 -0.0659011 0.237775 0.0788543 -0.06632 0.237739 0.0789691 -0.0663541 0.237827 0.0785147 -0.0667369 0.237827 0.078511 -0.0667359 0.23699 0.0796699 -0.0650686 0.237333 0.0793137 -0.064944 0.237079 0.0796358 -0.0651583 0.237431 0.0792529 -0.0651234 0.237383 0.0792851 -0.0650351 0.236527 0.0797011 -0.0639665 0.236527 0.0793163 -0.0627276 0.237466 0.0788238 -0.0648957 0.237827 0.0785 0.0652192 0.237827 0.0785073 0.0652049 0.237827 0.078511 0.065206 0.237796 0.0787358 0.0647565 0.237775 0.0788543 0.0647901 0.237705 0.0789568 0.0643042 0.237486 0.0793771 0.0644425 0.237739 0.0789691 0.0648242 0.237165 0.079595 0.0637154 0.237623 0.0791818 0.0643711 0.237729 0.0787161 0.0642458 0.236781 0.0797748 0.0638684 0.237079 0.0796358 0.0636283 0.237383 0.0792851 0.0635051 0.237431 0.0792529 0.0635935 0.237496 0.0788224 0.0634472 0.237525 0.078818 0.0635272 0.236655 0.0797936 0.0637884 0.23699 0.0796699 0.0635386 0.237333 0.0793137 0.0634141 0.237466 0.0788238 0.0633657 0.236527 0.0788238 0.0607776 0.236527 0.0789529 0.0608113 0.236527 0.0790794 0.0608935 0.236527 0.0793163 0.0611976 0.21591 0.0795111 -0.078968 0.216057 0.0796144 -0.0788452 0.216721 0.0798 -0.0782697 0.215572 0.0790968 -0.0792199 0.215427 0.0785 -0.079265 0.215526 0.0789974 -0.081265 0.215462 0.0788 -0.079265 0.215427 0.0207843 -0.081265 0.215553 0.0202265 -0.081265 0.215553 0.0202265 -0.079265 0.215906 0.0197766 -0.081265 0.216418 0.0195217 -0.079265 0.216418 0.0195217 -0.081265 0.237124 0.0237114 -0.0777199 0.237323 0.0238386 -0.081265 0.237369 0.0238764 -0.0776049 0.237753 0.0244353 -0.0771413 0.237694 0.024294 -0.081265 0.237694 0.024294 0.081735 0.236827 0.0236014 0.077235 0.237323 0.0238386 0.081735 0.237124 0.0237114 0.07719 0.237369 0.0238764 0.077075 0.237641 0.024197 0.0768153 0.216989 0.0195111 0.078935 0.216418 0.0195217 0.081735 0.215906 0.0197766 0.081735 0.215906 0.0197766 0.078935 0.215553 0.0202265 0.081735 0.215553 0.0202265 0.078935 0.215462 0.0788 0.078935 0.215601 0.07915 0.081735 0.215572 0.0790968 0.07889 0.215737 0.0793426 0.078775 0.216077 0.0796258 0.081735 0.216727 0.0798 0.077935 0.216721 0.0798 0.0779398 0.236774 0.0236676 -0.0816477 0.237827 0.0248663 -0.081265 0.237693 0.0248663 -0.081765 0.237574 0.024353 -0.081765 0.237241 0.0239445 -0.081765 0.237017 0.0242339 -0.082131 0.236688 0.0240828 -0.082131 0.236827 0.0248663 -0.082265 0.237245 0.0245141 -0.082131 0.236796 0.0247342 -0.082265 0.236711 0.0246291 -0.082265 0.236665 0.0241977 -0.0821889 0.236587 0.0245725 -0.082265 0.216787 0.0204905 -0.082265 0.216888 0.0200008 -0.082131 0.23673 0.0238799 -0.0819721 0.216962 0.0196423 -0.081765 0.236762 0.0237243 -0.081765 0.216974 0.0195857 -0.0816477 0.216989 0.0195111 -0.081265 0.236827 0.0785 -0.082265 0.237327 0.0248663 -0.082131 0.21693 0.019798 -0.0819721 0.216449 0.0196518 -0.081765 0.215674 0.020284 -0.081765 0.21599 0.0198804 -0.081765 0.216221 0.0201642 -0.082131 0.215561 0.0207843 -0.081765 0.216865 0.0201157 -0.0821889 0.216536 0.0200073 -0.082131 0.216655 0.020493 -0.082265 0.216537 0.0205518 -0.082265 0.216004 0.020441 -0.082131 0.216456 0.0206556 -0.082265 0.215927 0.0207843 -0.082131 0.237537 0.079083 -0.081765 0.236527 0.079666 -0.081765 0.237177 0.0796258 -0.081265 0.23711 0.0795098 -0.081765 0.23722 0.0789 -0.082131 0.236927 0.0791928 -0.082131 0.237653 0.07915 -0.081265 0.237693 0.0785 -0.081765 0.237327 0.0785 -0.082131 0.236787 0.07865 -0.082265 0.21572 0.0785 -0.0819721 0.215927 0.0785 -0.082131 0.216044 0.0785 -0.0821889 0.236527 0.0788 -0.082265 0.236527 0.0793 -0.082131 0.228027 0.0793 -0.082131 0.216727 0.0798 -0.081265 0.216229 0.079701 -0.081265 0.215808 0.0794192 -0.081265 0.215503 0.0785 -0.0816477 0.215561 0.0785 -0.081765 0.215596 0.0789683 -0.0816477 0.215796 0.0788854 -0.0819721 0.215861 0.0793654 -0.0816477 0.216258 0.0796307 -0.0816477 0.216096 0.0787612 -0.0821889 0.216015 0.0792121 -0.0819721 0.216244 0.0789827 -0.0821889 0.216341 0.0794304 -0.0819721 0.216466 0.0791307 -0.0821889 0.21645 0.0786148 -0.082265 0.216515 0.0787121 -0.082265 0.216612 0.0787771 -0.082265 0.216467 0.07865 0.082735 0.215927 0.0785 0.0826011 0.216034 0.0789 0.0826011 0.215561 0.0785 0.082235 0.215717 0.079083 0.082235 0.215427 0.0785 0.081735 0.215808 0.0794192 0.081735 0.216327 0.0791928 0.0826011 0.216727 0.0788 0.082735 0.216144 0.0795098 0.082235 0.216727 0.079666 0.082235 0.216427 0.0785 0.082735 0.215561 0.0207843 0.082235 0.216727 0.0793 0.0826011 0.217827 0.0788 0.082735 0.216655 0.020493 0.082735 0.216536 0.0200073 0.0826011 0.216449 0.0196518 0.082235 0.21599 0.0198804 0.082235 0.216221 0.0201642 0.0826011 0.216004 0.020441 0.0826011 0.215927 0.0207843 0.0826011 0.215674 0.020284 0.082235 0.215427 0.0207843 0.081735 0.237177 0.0796258 0.081735 0.236527 0.079666 0.082235 0.23711 0.0795098 0.082235 0.236527 0.0798 0.081735 0.23722 0.0789 0.0826011 0.236927 0.0791928 0.0826011 0.237327 0.0785 0.0826011 0.237537 0.079083 0.082235 0.237693 0.0785 0.082235 0.216989 0.0195111 0.081735 0.236762 0.0237243 0.082235 0.216962 0.0196423 0.082235 0.236688 0.0240828 0.0826011 0.216888 0.0200008 0.0826011 0.237693 0.0248663 0.082235 0.236827 0.0785 0.082735 0.237327 0.0248663 0.0826011 0.236711 0.0246291 0.082735 0.237245 0.0245141 0.0826011 0.237574 0.024353 0.082235 0.237017 0.0242339 0.0826011 0.237241 0.0239445 0.082235 0.237827 -0.0248609 0.0762398 0.237641 -0.024197 0.0768153 0.237753 -0.0244354 0.0766114 0.237753 0.0244353 0.0766114 0.236827 0.015923 0.077235 0.237212 0.0237617 0.0771577 0.236827 0.0079615 0.077235 0.236827 -0.0159231 0.077235 0.237538 0.0240492 0.0769381 0.237212 -0.0237618 0.0771577 0.237124 -0.0237115 0.07719 0.236827 -4.19898e-08 0.077235 0.237538 -0.0240493 0.0769381 0.237827 0.0248609 0.0762398 0.237827 0.0248609 -0.0767697 0.237641 0.024197 -0.0773452 0.237538 -0.0240493 -0.077468 0.237212 -0.0237618 -0.0776877 0.237124 -0.0237115 -0.0777199 0.237212 0.0237617 -0.0776877 0.237753 -0.0244354 -0.0771413 0.237538 0.0240492 -0.077468 0.237641 -0.024197 -0.0773452 0.237827 -0.0248609 -0.0767697 0.217827 -0.0788 0.082735 0.236827 -0.0248664 0.082735 0.228027 -0.0788 0.082735 0.236827 -0.0785 0.082735 0.216427 -0.0207844 0.082735 0.216427 -0.0785 0.082735 0.216727 -0.0788 0.082735 0.236739 -0.0787122 0.082735 0.236789 -0.0235931 -0.077765 0.216989 -0.0195112 -0.079265 0.198785 -0.0157582 -0.079265 0.182498 -0.011014 -0.079265 0.187958 -0.0135261 -0.079265 0.236527 -0.0175 -0.054265 0.236527 -0.0223998 0.0573821 0.236827 -0.0147851 0.0441492 0.236527 -0.0147851 0.0502303 0.236527 -0.0210047 0.05645 0.250498 -0.0117191 0.0120481 0.254327 -0.00716343 0.0130165 0.238827 -0.006738 0.0131069 0.237934 -0.0115016 0.0120944 0.238465 -0.0100735 0.0123979 0.249746 -0.0121819 0.0119498 0.238736 -0.00908523 0.012608 0.23764 -0.0122921 -0.0134563 0.249305 -0.0122802 -0.0134588 0.237934 -0.0115016 -0.0136243 0.238827 -0.006738 -0.0146368 0.253741 -0.0085469 -0.0142524 0.238827 -0.00806598 -0.0143546 0.237525 -0.0153662 -0.0298372 0.237525 -0.0195529 -0.0368466 0.236527 -0.0178067 -0.0285844 0.237525 -0.0246022 -0.0432624 0.237525 -0.0304312 -0.0489793 0.237525 -0.036944 -0.0539031 0.236527 -0.0384546 -0.0516132 0.237525 -0.059468 -0.0631792 0.237525 -0.0141129 0.0257239 0.236529 -0.0215042 0.0333218 0.236994 -0.0113762 0.013149 0.237525 -0.00994803 0.0134525 0.237525 -0.0484823 0.0583916 0.237525 -0.0577953 0.0612899 0.236527 -0.0584074 0.0586158 0.23706 -0.01308 0.0108293 0.249084 -0.0130657 0.0107563 0.249084 -0.0130657 -0.0122863 0.237525 -0.0675593 -0.0642698 0.237525 -0.0788181 -0.0650571 0.228027 -0.0798 0.081735 0.23002 -0.0798 0.0773679 0.216727 -0.0798 0.077935 0.217827 -0.0798 0.081735 0.216727 -0.0798 0.081735 0.216727 -0.0798 -0.081265 0.217827 -0.0798 -0.081265 0.227216 -0.0798 -0.0772953 0.19921 -0.0843897 -0.0772953 0.238827 -0.00700004 0.0405736 0.236827 -0.00700004 0.0444236 0.254041 -0.00631979 0.0305187 0.23772 -0.0117269 -0.0415045 0.237055 -0.0124167 -0.0425069 0.254327 -0.00375248 -0.0259609 0.236527 -0.00375248 -0.0259609 0.252327 -0.0072076 -0.0338482 0.236527 -0.00893494 -0.0370328 0.238827 -0.0111907 -0.0406997 0.178701 -0.00635479 0.078935 0.216989 -0.0195112 0.078935 0.187958 -0.0135261 0.0773679 0.23002 -0.0221976 0.0773679 0.236527 -0.023539 0.0773679 0.216427 -0.0207844 -0.082265 0.228027 -0.0798 -0.082265 0.217827 -0.0798 -0.082265 0.236827 -0.0248664 -0.082265 0.216456 -0.0206557 -0.082265 0.216655 -0.020493 -0.082265 0.236827 -0.0785 -0.082265 0.236677 -0.0787598 -0.082265 0.216467 -0.07865 -0.082265 0.216727 -0.0788 -0.082265 0.217827 -0.0788 -0.082265 0.254052 -0.00991284 -0.0302902 0.253361 -0.0104085 -0.0313107 0.254327 -0.00521087 -0.0170674 0.238827 -0.00521087 -0.0170674 0.245562 -0.0126387 0.0339164 0.254327 -0.00930994 0.0274576 0.238827 -0.00521087 0.0155375 0.254327 -0.00521087 0.0155375 0.210871 -0.0693 -0.0772953 0.209627 -0.0680556 -0.079265 0.210871 -0.0693 -0.079265 0.211327 -0.071 -0.0772953 0.211327 -0.071 -0.079265 0.210871 -0.0727 -0.079265 0.210871 -0.0727 -0.0772953 0.209627 -0.0739445 -0.0772953 0.209627 -0.0739445 -0.079265 0.207927 -0.0744 -0.079265 0.204982 -0.0727 -0.0772953 0.204982 -0.0727 -0.079265 0.204527 -0.071 -0.0772953 0.206227 -0.0680556 -0.0772953 0.189643 -0.0266 -0.0772953 0.192588 -0.0283 -0.0772953 0.192588 -0.0317 -0.0772953 0.192588 -0.0317 -0.079265 0.191343 -0.0329445 -0.0772953 0.187943 -0.0329445 -0.0772953 0.186699 -0.0283 -0.0772953 0.186243 -0.03 -0.079265 0.187943 -0.0270556 -0.0772953 0.187943 -0.0270556 -0.079265 0.246062 -0.0121532 -0.03673 0.246063 -0.0103482 -0.0376049 0.251544 -0.00834022 0.033532 0.252827 -0.010276 0.0317698 0.236827 -0.0158982 -0.0470806 0.236827 -0.0175 -0.0515371 0.252327 -0.00686832 0.0321772 0.236527 -0.00631979 0.0305187 0.249806 -0.00700004 0.0335288 0.236827 -0.0155 -0.056265 0.236527 -0.0155 -0.056265 0.236527 -0.0165 -0.055997 0.236527 -0.0172321 -0.055265 0.236827 -0.00700004 0.0557094 0.236827 -0.00641426 0.0571236 0.236527 -0.00641426 0.0571236 0.236827 -0.00600004 0.0574415 0.252827 -0.010619 -0.012801 0.251205 -0.0110714 -0.000764971 0.252827 -0.010619 0.0112711 0.251205 -0.0122051 0.0109342 0.251205 -0.0122051 -0.0124642 0.249084 -0.01195 -0.000764971 0.250232 -0.0117217 -0.000764971 0.250077 -0.0129001 0.0107906 0.250958 -0.012422 0.0108894 0.255098 -0.00685545 -0.000764971 0.254448 -0.00782872 -0.000764971 0.255308 -0.00727984 0.0119711 0.237827 -0.0574137 0.0629569 0.237525 -0.0675593 0.0627399 0.237751 -0.00912387 -0.0151548 0.237525 -0.0121111 -0.0223496 0.237827 -0.0105023 -0.0229294 0.237827 -0.018144 -0.0378158 0.237827 -0.023329 -0.0444041 0.237827 -0.0293146 -0.0502745 0.237525 -0.0440334 -0.0579528 0.237525 -0.0515828 -0.0610619 0.237827 -0.0510343 -0.0626817 0.237827 -0.0591313 -0.0648558 0.237827 -0.0674401 -0.0659758 0.237827 -0.0785037 -0.0667338 0.237802 -0.0786153 -0.066254 0.237827 -0.0125578 0.0264355 0.237525 -0.0116924 0.0196207 0.237827 -0.0156756 0.0324133 0.237525 -0.0171491 0.0315454 0.238827 -0.00546035 -0.0155291 0.238827 -0.0060087 -0.0149534 0.238827 -0.0060087 0.0134235 0.254327 -0.0060087 0.0134235 0.254327 -0.00546035 0.0139992 0.254327 -0.00517962 0.014743 0.238827 -0.00517962 0.014743 0.236655 -0.0797937 -0.0653183 0.23703 -0.0796987 -0.0655668 0.237486 -0.0793772 -0.0659725 0.237653 -0.07915 -0.081265 0.237827 -0.0785148 -0.0667369 0.236655 -0.0797937 0.0637884 0.237827 -0.0785148 0.065207 0.237827 -0.0785 0.081735 0.237728 -0.0789975 0.081735 0.237446 -0.0794193 0.081735 0.237486 -0.0793772 0.0644425 0.23703 -0.0796987 0.0640369 0.186328 -0.0891743 -0.0772953 0.209883 -0.0804257 -0.078265 0.186328 -0.0891743 0.0773679 0.182846 -0.0898 0.077935 0.182846 -0.0898 0.0773679 0.213364 -0.0798 0.077935 0.236586 -0.0211638 0.0377463 0.255327 -0.00839808 -0.0293981 0.254984 -0.0091686 -0.0310472 0.255327 -0.00659783 -0.0302711 0.254234 -0.0079361 -0.0330898 0.254969 -0.00738462 0.0304227 0.254112 -0.00792095 0.0317303 0.239327 -0.0142196 -0.0400497 0.238553 -0.0146077 -0.0405746 0.237998 -0.0133811 -0.0422329 0.237827 -0.0140219 -0.0430331 0.238036 -0.015141 0.0397382 0.238553 -0.0146077 0.0390447 0.254176 -0.0100593 0.030475 0.253752 -0.0103973 0.0299312 0.254006 -0.0102917 0.0302095 0.252791 -0.0105938 0.0315385 0.254234 -0.0097356 0.0306869 0.254973 -0.00943075 0.0291799 0.253453 -0.0103599 0.0296826 0.254102 -0.00985628 0.0286411 0.254462 -0.00984174 0.0287876 0.255046 -0.00909661 0.0293662 0.254768 -0.00969235 0.0289768 0.254827 -0.00918777 0.0275126 0.239327 -0.0142196 0.0385198 0.245762 -0.0127412 0.0342555 0.238827 -0.0146755 0.0371885 0.246062 -0.0121532 0.0352001 0.246034 -0.0124765 0.0349552 0.252684 -0.0108033 0.0312218 0.25252 -0.0108717 0.0308691 0.245928 -0.0126839 0.034622 0.252327 -0.0107885 0.0305353 0.255251 -0.00874704 0.027711 0.255193 -0.00472513 0.015656 0.255193 -0.00885401 0.0276629 0.254709 -0.00924053 0.0274889 0.254827 -0.00508072 0.0155692 0.255034 -0.00904286 0.0275778 0.237981 -0.0154562 0.0394903 0.238099 -0.0153482 0.0389898 0.238517 -0.0149303 0.0387886 0.239033 -0.0147977 0.0375316 0.239203 -0.0147526 0.0379113 0.237827 -0.0158496 0.0406064 0.237829 -0.0157734 0.0405221 0.237844 -0.0157199 0.0402106 0.237966 -0.0154867 0.0394593 0.239307 -0.0145479 0.0382611 0.238358 -0.0151491 0.0384761 0.238316 -0.0151743 0.0383952 0.254327 -0.006738 0.0131069 0.254827 -0.00593199 0.0133136 0.254827 -0.00671015 0.0129759 0.255327 -0.00653009 0.0121288 0.255327 -0.00543613 0.0126036 0.255193 -0.00572242 0.0130135 0.255193 -0.00503699 0.0137332 0.255327 -0.00461362 0.0134672 0.255193 -0.00468607 0.014663 0.254827 -0.00534691 0.0139279 0.254827 -0.00504738 0.0147216 0.237951 -0.0155509 0.0390004 0.237827 -0.0158513 0.0406159 0.237827 -0.0158525 0.0406068 0.237834 -0.0157807 0.0402189 0.238563 -0.0149799 0.0378073 0.238181 -0.0151745 0.0377574 0.237858 -0.0157839 0.0390125 0.237829 -0.0158419 0.0402273 0.237827 -0.0159033 0.0402358 0.23792 -0.0155064 0.0376723 0.237827 -0.0159142 0.0375677 0.254827 -0.00713558 0.0128854 0.255193 -0.00705948 0.0125274 0.255193 -0.00663405 0.0126178 0.255327 -0.00695552 0.0120383 0.237961 -0.00569661 0.0154189 0.237827 -0.00618235 0.0153003 0.238827 -0.00903463 0.0268379 0.238327 -0.00915733 0.0267841 0.238327 -0.0147873 0.0371145 0.237961 -0.00949256 0.0266372 0.237961 -0.0150925 0.0369125 0.237827 -0.0155094 0.0366364 0.254811 -0.00740557 0.0128283 0.254315 -0.00737943 0.0129706 0.255031 -0.00822806 0.0117746 0.255175 -0.00736913 0.0124626 0.254578 -0.00819433 0.0126615 0.254129 -0.00801094 0.0128363 0.254448 -0.00903283 0.0116079 0.254351 -0.00904068 0.0121127 0.254908 -0.00827374 0.0122732 0.254092 -0.00886305 0.0125201 0.253741 -0.0085469 0.0127224 0.237961 -0.00629498 0.0138334 0.237827 -0.00616673 0.0149031 0.238327 -0.00608541 0.0135333 0.237961 -0.00588372 0.0142652 0.237961 -0.00567317 0.0148231 0.238327 -0.0055738 0.0140705 0.238327 -0.00531187 0.0147645 0.238827 -0.00546035 0.0139992 0.238327 -0.00534102 0.0155057 0.252471 -0.0104491 0.012183 0.25212 -0.010133 0.0123853 0.252729 -0.0106267 0.0117757 0.25085 -0.0120351 0.0118459 0.238327 -0.00676586 0.013238 0.237961 -0.00684196 0.013596 0.237827 -0.00694592 0.0140851 0.251108 -0.0122128 0.0114388 0.250333 -0.0118635 0.0120174 0.250872 -0.0124193 0.0113956 0.24991 -0.0126119 0.011724 0.250643 -0.0122152 0.0118079 0.249084 -0.0130319 0.0112676 0.250031 -0.0128743 0.0113005 0.249084 -0.0122921 0.0119263 0.238827 -0.00806598 0.0128246 0.237751 -0.00912387 0.0136249 0.237903 -0.00819433 0.0134285 0.238444 -0.00808181 0.0128991 0.238327 -0.00809384 0.0129557 0.238358 -0.00903601 0.0126965 0.238038 -0.00902607 0.012921 0.23812 -0.00812688 0.0131111 0.237825 -0.00905693 0.013247 0.237961 -0.00816994 0.0133137 0.237799 -0.00989763 0.0127367 0.237595 -0.00989307 0.0130712 0.249084 -0.0127493 0.011695 0.23764 -0.0122921 0.0119263 0.237267 -0.0113257 0.0124332 0.237573 -0.0113891 0.0121966 0.236527 -0.012626 0.0127566 0.236527 -0.0126724 0.0126066 0.237064 -0.0113212 0.0127677 0.238104 -0.00996101 0.0125002 0.236666 -0.0131072 0.0114829 0.237181 -0.013053 0.011296 0.236527 -0.0129773 0.0120732 0.236689 -0.0126365 0.0122649 0.236527 -0.0127349 0.0125013 0.23764 -0.0130657 0.0107563 0.23764 -0.0130319 0.0112676 0.236858 -0.0128861 0.0118261 0.23764 -0.0127493 0.011695 0.237316 -0.0123899 0.0119442 0.237273 -0.0128036 0.011699 0.237186 -0.0124336 0.0119739 0.236962 -0.0125159 0.0120622 0.236527 -0.0218616 0.0365537 0.236736 -0.021839 0.0362763 0.23668 -0.0218556 0.0347464 0.237035 -0.0211743 0.0375467 0.236527 -0.0214986 0.0333003 0.236527 -0.0219283 0.0342167 0.236752 -0.0216205 0.0345674 0.236919 -0.0217083 0.0360068 0.237095 -0.0213393 0.0358007 0.237525 -0.0206764 0.0368977 0.236688 -0.0208837 0.0380506 0.237049 -0.0209007 0.0379312 0.23716 -0.0208827 0.0378712 0.237358 -0.0208128 0.0377267 0.237376 -0.0209976 0.037239 0.237209 -0.0200837 0.0387429 0.236827 -0.0201376 0.0387967 0.237654 -0.0203868 0.0371889 0.23757 -0.0206328 0.0374667 0.237512 -0.0207017 0.0375574 0.237693 -0.0144315 0.0437957 0.237534 -0.014578 0.0439421 0.237751 -0.0197011 0.0383602 0.237534 -0.0199305 0.0385896 0.237327 -0.0146903 0.0503251 0.237327 -0.0135428 0.0483374 0.236827 -0.0136722 0.0483027 0.237327 -0.0135428 0.0460422 0.236827 -0.0136722 0.0460768 0.237327 -0.0146903 0.0440545 0.237693 -0.0131892 0.0484321 0.237751 -0.0143486 0.0506668 0.237693 -0.0131892 0.0459474 0.237827 -0.0127062 0.045818 0.237693 -0.0144315 0.0505839 0.237751 -0.0205682 0.0568865 0.237693 -0.0206512 0.0568035 0.237534 -0.014578 0.0504374 0.237534 -0.0207976 0.0566571 0.237209 -0.0147313 0.0502842 0.237209 -0.0209509 0.0565038 0.236827 -0.0210047 0.05645 0.236827 -0.0147851 0.0502303 0.237327 -0.0223485 0.0575059 0.237693 -0.0222084 0.0578441 0.236827 -0.0240453 0.0577094 0.236827 -0.0223998 0.0573821 0.237327 -0.02091 0.0565447 0.237827 -0.0220171 0.058306 0.236827 -0.04487 0.0577094 0.237327 -0.0240453 0.0578434 0.237693 -0.0240453 0.0582094 0.237327 -0.04487 0.0578434 0.237827 -0.0240453 0.0587094 0.237827 -0.04487 0.0587094 0.237693 -0.04487 0.0582094 0.237748 -0.0466862 0.0585472 0.237569 -0.0466736 0.0581185 0.237215 -0.0466487 0.0578175 0.236764 -0.046617 0.0577094 0.236986 -0.0484097 0.0577946 0.236527 -0.0574047 0.0583774 0.236971 -0.0529652 0.0583839 0.236527 -0.0550651 0.0580207 0.236527 -0.0529178 0.0578429 0.236762 -0.0529419 0.0580317 0.236527 -0.0519826 0.05779 0.237318 -0.0484544 0.0580357 0.246034 -0.0124765 -0.0364851 0.245928 -0.0126839 -0.0361519 0.25252 -0.0108717 -0.032399 0.252327 -0.0107885 -0.0320653 0.239307 -0.0145479 -0.039791 0.239203 -0.0147526 -0.0394412 0.245762 -0.0127412 -0.0357855 0.245562 -0.0126387 -0.0354464 0.254709 -0.00924053 -0.0290188 0.254827 -0.00918777 -0.0290425 0.254912 -0.0095014 -0.030858 0.255034 -0.00904286 -0.0291078 0.25471 -0.00975961 -0.0306477 0.254408 -0.00990406 -0.0304484 0.252827 -0.010276 -0.0332998 0.254119 -0.009797 -0.0323414 0.252791 -0.0105938 -0.0330684 0.252684 -0.0108033 -0.0327517 0.254062 -0.0101199 -0.0321271 0.253898 -0.0103496 -0.0318558 0.253652 -0.010451 -0.031569 0.23822 -0.0152473 -0.0401723 0.237981 -0.0154562 -0.0410202 0.238036 -0.015141 -0.0412681 0.237937 -0.0155259 -0.0411188 0.237844 -0.0157199 -0.0417406 0.237829 -0.0157734 -0.0420521 0.238517 -0.0149303 -0.0403186 0.238358 -0.0151491 -0.040006 0.238563 -0.0149799 -0.0393372 0.239033 -0.0147977 -0.0390615 0.238827 -0.0146755 -0.0387184 0.255193 -0.00472513 -0.017186 0.255327 -0.00423939 -0.0173045 0.255251 -0.00874704 -0.029241 0.254327 -0.00930994 -0.0289875 0.255193 -0.00885401 -0.0291928 0.237827 -0.0158496 -0.0421363 0.238099 -0.0153482 -0.0405197 0.238181 -0.0151745 -0.0392874 0.238327 -0.0147873 -0.0386445 0.237951 -0.0155509 -0.0405303 0.237829 -0.0158419 -0.0417573 0.237834 -0.0157807 -0.0417489 0.237827 -0.0158525 -0.0421367 0.237858 -0.0157839 -0.0405425 0.23792 -0.0155064 -0.0392022 0.237827 -0.0159142 -0.0390977 0.237961 -0.0150925 -0.0384424 0.237827 -0.0155094 -0.0381664 0.254827 -0.00508072 -0.0170992 0.255251 -0.00660966 -0.014033 0.255193 -0.00503699 -0.0152631 0.255327 -0.00543613 -0.0141336 0.255327 -0.00461362 -0.0149971 0.254827 -0.00504738 -0.0162515 0.255193 -0.00468607 -0.0161929 0.255193 -0.00572242 -0.0145435 0.255034 -0.00667711 -0.0143504 0.254827 -0.00593199 -0.0148436 0.254827 -0.00671015 -0.0145058 0.254327 -0.00517962 -0.016273 0.254827 -0.00534691 -0.0154578 0.254327 -0.00546035 -0.0155291 0.254327 -0.0060087 -0.0149534 0.254709 -0.00672218 -0.0145624 0.254327 -0.006738 -0.0146368 0.238827 -0.00903463 -0.0283678 0.238327 -0.00915733 -0.0283141 0.237961 -0.00949256 -0.0281671 0.237961 -0.00569661 -0.0169488 0.255193 -0.00663405 -0.0141478 0.255251 -0.00703509 -0.0139426 0.255327 -0.00653009 -0.0136587 0.237961 -0.00567317 -0.016353 0.237827 -0.00658126 -0.0157733 0.238327 -0.00534102 -0.0170356 0.237961 -0.00588372 -0.0157951 0.238327 -0.0055738 -0.0156004 0.238327 -0.00608541 -0.0150633 0.237961 -0.00629498 -0.0153634 0.238327 -0.00531187 -0.0162944 0.238827 -0.00517962 -0.016273 0.253888 -0.00838577 -0.0142866 0.254092 -0.00886305 -0.01405 0.254327 -0.00716343 -0.0145464 0.254214 -0.00781111 -0.0144087 0.254277 -0.00866207 -0.0140925 0.254562 -0.00881018 -0.0136909 0.254351 -0.00904068 -0.0136426 0.254709 -0.00714761 -0.014472 0.254684 -0.00794484 -0.0142442 0.254827 -0.00713558 -0.0144154 0.255034 -0.00710254 -0.0142599 0.25503 -0.0079876 -0.013863 0.255193 -0.00705948 -0.0140573 0.254669 -0.00879087 -0.013188 0.255158 -0.00792801 -0.0133667 0.238444 -0.00808181 -0.014429 0.238327 -0.00676586 -0.0147679 0.23812 -0.00812688 -0.0146411 0.23812 -0.0067989 -0.0149233 0.237961 -0.00684196 -0.0151259 0.237903 -0.00819433 -0.0149584 0.25212 -0.010133 -0.0139152 0.254448 -0.00903283 -0.0131379 0.252729 -0.0106267 -0.0133057 0.252471 -0.0104491 -0.013713 0.238465 -0.0100735 -0.0139279 0.238104 -0.00996101 -0.0140301 0.237799 -0.00989763 -0.0142666 0.237825 -0.00905693 -0.014777 0.237595 -0.00989307 -0.0146012 0.237525 -0.00994803 -0.0149824 0.238736 -0.00908523 -0.0141379 0.238358 -0.00903601 -0.0142265 0.238038 -0.00902607 -0.0144509 0.237827 -0.0082739 -0.0153327 0.249416 -0.0130477 -0.01229 0.249084 -0.0130319 -0.0127975 0.24936 -0.0127344 -0.0132281 0.249084 -0.0127493 -0.0132249 0.249084 -0.0122921 -0.0134563 0.250165 -0.0125087 -0.0132758 0.2494 -0.0130147 -0.0128011 0.249951 -0.012099 -0.0134973 0.251108 -0.0122128 -0.0129687 0.250384 -0.0127756 -0.0123462 0.250324 -0.0127559 -0.0128552 0.25085 -0.0120351 -0.0133759 0.250498 -0.0117191 -0.0135781 0.236527 -0.0126317 -0.0144122 0.236994 -0.0113762 -0.014679 0.237064 -0.0113212 -0.0142977 0.2366 -0.0126854 -0.0139034 0.237267 -0.0113257 -0.0139631 0.237228 -0.0124192 -0.0134927 0.237573 -0.0113891 -0.0137266 0.23764 -0.0130657 -0.0122863 0.236863 -0.0125561 -0.01365 0.23674 -0.0129153 -0.0134229 0.236527 -0.0129746 -0.0136091 0.236902 -0.0130892 -0.0124061 0.237054 -0.0130631 -0.0128554 0.236527 -0.0131281 -0.0131094 0.237171 -0.0128216 -0.013247 0.23764 -0.0130319 -0.0127975 0.23764 -0.0127493 -0.0132249 0.236827 -0.00673209 0.0567094 0.237327 -0.00684812 0.0567764 0.237693 -0.00716511 0.0569594 0.236827 -0.00500004 0.0577094 0.237327 -0.00606703 0.0575575 0.237327 -0.00500004 0.0578434 0.237693 -0.00625004 0.0578745 0.237693 -0.00500004 0.0582094 0.237827 -0.00650004 0.0583075 0.237693 -0.00750004 0.0557094 0.237751 -0.00761736 0.0444236 0.237534 -0.00729294 0.0444236 0.237327 -0.00713402 0.0557094 0.237742 -0.00709848 0.0424091 0.238225 -0.00821726 0.0426585 0.238223 -0.00777355 0.0426575 0.238051 -0.00737443 0.0425686 0.237209 -0.00707616 0.0444236 0.237327 -0.00713402 0.0444236 0.237693 -0.00750004 0.0444236 0.237358 -0.00700004 0.0422106 0.239081 -0.00711751 0.0409694 0.239275 -0.00744232 0.0412722 0.239327 -0.00837794 0.0413528 0.25006 -0.00711751 0.0339246 0.250254 -0.00744232 0.0342274 0.239364 -0.00789817 0.0414109 0.250306 -0.00837794 0.034308 0.251466 -0.00744033 0.0334936 0.251281 -0.00711185 0.0332224 0.252727 -0.00736639 0.0327628 0.252549 -0.0070371 0.0325233 0.250343 -0.00789817 0.0343661 0.251561 -0.00788156 0.0336048 0.251044 -0.00696703 0.0328498 0.254077 -0.00751941 0.0318245 0.254899 -0.00702637 0.0305624 0.254698 -0.00669809 0.0306297 0.253663 -0.00684155 0.0316661 0.253355 -0.00668136 0.0314407 0.252827 -0.00822741 0.0327634 0.252826 -0.00779113 0.0328485 0.253918 -0.00713781 0.0318018 0.255163 -0.00664092 0.0297476 0.255327 -0.00659783 0.0287412 0.25495 -0.0063284 0.0298474 0.255034 -0.00595328 0.029032 0.254631 -0.00610516 0.0298833 0.255237 -0.00699495 0.029599 0.254397 -0.00644993 0.0306143 0.254255 -0.00600533 0.0298497 0.254327 -0.0056863 0.0291524 0.254709 -0.00575569 0.0291211 0.255251 -0.006249 0.0288986 0.255327 -0.0046906 0.0240846 0.254709 -0.00575569 -0.0306511 0.255034 -0.00595328 -0.0305619 0.252827 -0.00847611 -0.0341727 0.254004 -0.00722327 -0.0332368 0.254173 -0.00757279 -0.0332153 0.254464 -0.0063723 -0.0319814 0.254102 -0.00624899 -0.0318996 0.253751 -0.00694044 -0.033151 0.253452 -0.00676712 -0.032971 0.255046 -0.00729704 -0.031769 0.255251 -0.006249 -0.0304285 0.254975 -0.00693968 -0.0319107 0.25477 -0.00661488 -0.0319853 0.254327 -0.0056863 -0.0306824 0.245804 -0.00942168 -0.0376262 0.252786 -0.00810823 -0.0342816 0.245986 -0.00987293 -0.0377267 0.252574 -0.00751917 -0.0341703 0.252677 -0.00773885 -0.0342584 0.252757 -0.00798248 -0.0342888 0.245563 -0.00910577 -0.0373283 0.239062 -0.0115092 -0.0409737 0.238371 -0.0123915 -0.0416858 0.238497 -0.0128302 -0.0415112 0.239243 -0.0119477 -0.0410569 0.239327 -0.0124045 -0.04093 0.237513 -0.0126109 -0.0425658 0.238089 -0.0119919 -0.0416834 0.237856 -0.0129617 -0.0424661 0.236827 -0.0132138 -0.0436222 0.237693 -0.0136178 -0.0433277 0.237827 -0.0166693 -0.046444 0.237693 -0.0162837 -0.0467623 0.237209 -0.0159569 -0.0470322 0.237327 -0.0133221 -0.0435433 0.237327 -0.0160015 -0.0469953 0.237209 -0.0175762 -0.0515371 0.236827 -0.0170874 -0.0491693 0.237209 -0.017159 -0.0491436 0.237327 -0.017634 -0.0515371 0.237693 -0.018 -0.0515371 0.237534 -0.0177929 -0.0515371 0.237534 -0.017363 -0.0490702 0.237751 -0.0176683 -0.0489605 0.237534 -0.016124 -0.0468942 0.237751 -0.0163742 -0.0466876 0.237751 -0.0181174 -0.0515371 0.237693 -0.018 -0.054265 0.236827 -0.0175 -0.054265 0.236827 -0.0165 -0.055997 0.237327 -0.016567 -0.056113 0.237693 -0.0155 -0.056765 0.237827 -0.0155 -0.057265 0.236827 -0.0172321 -0.055265 0.237327 -0.0173481 -0.055332 0.237693 -0.01675 -0.05643 0.237693 -0.0176651 -0.055515 0.237827 -0.017 -0.056863 0.237327 -0.017634 -0.054265 0.237827 -0.0785 -0.0667492 0.237827 -0.0785074 -0.0667349 0.237729 -0.0787162 -0.0657757 0.237796 -0.0787359 -0.0662865 0.237705 -0.0789569 -0.0658341 0.237623 -0.0791819 -0.0659011 0.237739 -0.0789691 -0.0663541 0.237775 -0.0788544 -0.06632 0.237827 -0.0785111 -0.0667359 0.237165 -0.079595 -0.0652454 0.237383 -0.0792852 -0.0650351 0.23699 -0.07967 -0.0650686 0.237431 -0.079253 -0.0651234 0.237496 -0.0788224 -0.0649771 0.237079 -0.0796359 -0.0651583 0.236781 -0.0797748 -0.0653983 0.236527 -0.0798 -0.0652368 0.237466 -0.0788239 -0.0648957 0.237333 -0.0793138 -0.064944 0.237775 -0.0788544 0.0647901 0.237827 -0.0785074 0.0652049 0.237796 -0.0787359 0.0647565 0.237827 -0.0785 0.0652192 0.237827 -0.0785037 0.0652039 0.237802 -0.0786153 0.064724 0.237729 -0.0787162 0.0642458 0.237705 -0.0789569 0.0643042 0.237623 -0.0791819 0.0643711 0.237739 -0.0789691 0.0648242 0.237827 -0.0785111 0.065206 0.237496 -0.0788224 0.0634472 0.237525 -0.0788181 0.0635272 0.237431 -0.079253 0.0635935 0.237079 -0.0796359 0.0636283 0.237165 -0.079595 0.0637154 0.236781 -0.0797748 0.0638684 0.237466 -0.0788239 0.0633657 0.237333 -0.0793138 0.0634141 0.237383 -0.0792852 0.0635051 0.23699 -0.07967 0.0635386 0.236527 -0.0798 0.0637069 0.236527 -0.0790795 0.0608935 0.236527 -0.078953 0.0608113 0.236527 -0.0788239 0.0607776 0.236527 -0.0797012 0.0624366 0.215462 -0.0788 -0.079265 0.215808 -0.0794193 -0.081265 0.215737 -0.0793427 -0.0791049 0.216235 -0.0797035 -0.0786937 0.215906 -0.0197767 -0.081265 0.237827 -0.0248664 -0.081265 0.236827 -0.0236015 -0.077765 0.237369 -0.0238765 -0.0776049 0.237323 -0.0238387 -0.081265 0.237694 -0.0242941 -0.081265 0.236789 -0.0235931 0.077235 0.236827 -0.0236015 0.077235 0.237323 -0.0238387 0.081735 0.237369 -0.0238765 0.077075 0.215427 -0.0207844 0.078935 0.215553 -0.0202266 0.081735 0.215906 -0.0197767 0.081735 0.216418 -0.0195218 0.081735 0.215906 -0.0197767 0.078935 0.216418 -0.0195218 0.078935 0.21591 -0.0795112 0.0786381 0.216077 -0.0796259 0.081735 0.216296 -0.0797265 0.0783114 0.215737 -0.0793427 0.078775 0.215601 -0.07915 0.081735 0.215462 -0.0788 0.078935 0.236762 -0.0237244 -0.081765 0.237241 -0.0239446 -0.081765 0.236688 -0.0240828 -0.082131 0.237574 -0.0243531 -0.081765 0.237017 -0.024234 -0.082131 0.237245 -0.0245142 -0.082131 0.236711 -0.0246292 -0.082265 0.236796 -0.0247343 -0.082265 0.237693 -0.0248664 -0.081765 0.216974 -0.0195858 -0.0816477 0.236789 -0.0235931 -0.081265 0.216962 -0.0196424 -0.081765 0.216888 -0.0200009 -0.082131 0.236587 -0.0245725 -0.082265 0.216865 -0.0201158 -0.0821889 0.237693 -0.0785 -0.081765 0.237327 -0.0248664 -0.082131 0.216044 -0.0207844 -0.0821889 0.216989 -0.0195112 -0.081265 0.216418 -0.0195218 -0.081265 0.215621 -0.0202592 -0.0816477 0.215553 -0.0202266 -0.081265 0.215503 -0.0207844 -0.0816477 0.215817 -0.0203523 -0.0819721 0.215954 -0.0198357 -0.0816477 0.216436 -0.0195957 -0.0816477 0.21693 -0.0197981 -0.0819721 0.216487 -0.0198062 -0.0819721 0.21611 -0.0204915 -0.0821889 0.216091 -0.0200037 -0.0819721 0.216564 -0.0201214 -0.0821889 0.216537 -0.0205519 -0.082265 0.216296 -0.0202552 -0.0821889 0.216787 -0.0204906 -0.082265 0.237327 -0.0785 -0.082131 0.23722 -0.0789 -0.082131 0.237446 -0.0794193 -0.081265 0.237537 -0.0790831 -0.081765 0.236787 -0.07865 -0.082265 0.237177 -0.0796259 -0.081265 0.23711 -0.0795098 -0.081765 0.236527 -0.0796661 -0.081765 0.236927 -0.0791929 -0.082131 0.236527 -0.0793 -0.082131 0.236527 -0.0788 -0.082265 0.216427 -0.0785 -0.082265 0.21572 -0.0785 -0.0819721 0.21572 -0.0207844 -0.0819721 0.215561 -0.0785 -0.081765 0.217827 -0.0793 -0.082131 0.215601 -0.07915 -0.081265 0.216727 -0.0796661 -0.081765 0.216727 -0.0793 -0.082131 0.216327 -0.0791929 -0.082131 0.216077 -0.0796259 -0.081265 0.216144 -0.0795098 -0.081765 0.216577 -0.0787598 -0.082265 0.215427 -0.0785 -0.081265 0.215717 -0.0790831 -0.081765 0.216034 -0.0789 -0.082131 0.215927 -0.0785 -0.082131 0.216727 -0.0793 0.0826011 0.216577 -0.0787598 0.082735 0.216327 -0.0791929 0.0826011 0.215808 -0.0794193 0.081735 0.216144 -0.0795098 0.082235 0.216467 -0.07865 0.082735 0.216034 -0.0789 0.0826011 0.215717 -0.0790831 0.082235 0.215503 -0.0207844 0.0821177 0.215561 -0.0207844 0.082235 0.21572 -0.0207844 0.0824421 0.215561 -0.0785 0.082235 0.215927 -0.0785 0.0826011 0.236527 -0.0788 0.082735 0.236527 -0.0793 0.0826011 0.236527 -0.0796661 0.082235 0.236527 -0.0798 0.081735 0.216655 -0.020493 0.082735 0.216296 -0.0202552 0.0826589 0.216537 -0.0205519 0.082735 0.216044 -0.0207844 0.0826589 0.216456 -0.0206557 0.082735 0.215817 -0.0203523 0.0824421 0.215927 -0.0207844 0.0826011 0.21611 -0.0204915 0.0826589 0.216091 -0.0200037 0.0824421 0.216487 -0.0198062 0.0824421 0.215427 -0.0207844 0.081735 0.216787 -0.0204906 0.082735 0.216865 -0.0201158 0.0826589 0.216564 -0.0201214 0.0826589 0.216888 -0.0200009 0.0826011 0.21693 -0.0197981 0.0824421 0.216962 -0.0196424 0.082235 0.215621 -0.0202592 0.0821177 0.215954 -0.0198357 0.0821177 0.216436 -0.0195957 0.0821177 0.216974 -0.0195858 0.0821177 0.216989 -0.0195112 0.081735 0.237327 -0.0785 0.0826011 0.236804 -0.0786148 0.082735 0.237266 -0.0788062 0.0826011 0.237092 -0.0790657 0.0826011 0.236642 -0.0787772 0.082735 0.236833 -0.0792391 0.0826011 0.236973 -0.0795773 0.082235 0.237604 -0.0789463 0.082235 0.237351 -0.0793245 0.082235 0.237024 -0.0797011 0.081735 0.236587 -0.0245725 0.082735 0.236762 -0.0237244 0.082235 0.237209 -0.0785 0.0826589 0.237327 -0.0248664 0.0826011 0.237534 -0.0785 0.0824421 0.237693 -0.0248664 0.082235 0.237693 -0.0785 0.082235 0.237751 -0.0785 0.0821177 0.236688 -0.0240828 0.0826011 0.237017 -0.024234 0.0826011 0.236789 -0.0235931 0.081735 0.236711 -0.0246292 0.082735 0.236796 -0.0247343 0.082735 0.237245 -0.0245142 0.0826011 0.237241 -0.0239446 0.082235 0.237209 -0.0248664 0.0826589 0.237534 -0.0248664 0.0824421 0.237574 -0.0243531 0.082235 0.237694 -0.0242941 0.081735 0.237751 -0.0248664 0.0821177 -0.19199 -0.00425004 -0.077765 -0.19567 -0.00212504 -0.0772953 -0.19624 -4.19898e-08 -0.077765 -0.194115 0.00368057 -0.077765 -0.189865 0.00368057 -0.0772953 -0.189865 0.00368057 -0.077765 -0.188309 0.00212496 -0.077765 -0.18774 -4.19898e-08 -0.0772953 -0.188309 -0.00212504 -0.077765 -0.227173 -0.00425004 -0.077765 -0.229298 -0.00368065 -0.0772953 -0.230854 -0.00212504 -0.0772953 -0.230854 -0.00212504 -0.077765 -0.230854 0.00212496 -0.0772953 -0.230854 0.00212496 -0.077765 -0.229298 0.00368057 -0.0772953 -0.223493 0.00212496 -0.0772953 -0.222923 -4.19898e-08 -0.0772953 -0.222923 -4.19898e-08 -0.077765 -0.223493 -0.00212504 -0.0772953 -0.227173 -0.00425004 -0.0772953 -0.238873 -0.0240453 0.0577094 -0.239173 -0.04487 0.0577094 -0.218773 0.0785 0.082735 -0.218813 0.07865 0.082735 -0.219134 0.0204905 0.082735 -0.219002 0.020493 0.082735 -0.239057 0.0246291 0.082735 -0.219073 0.0788 0.082735 -0.239133 0.07865 0.082735 -0.218923 0.0787598 0.082735 -0.218773 0.0207843 0.082735 -0.220173 0.0788 0.082735 -0.239173 0.0785 0.082735 -0.184844 0.0110139 -0.079265 -0.184844 0.0110139 -0.077765 -0.190304 0.013526 -0.079265 -0.17969 -4.19898e-08 -0.079265 -0.17969 0.000499958 -0.077765 -0.17969 -0.000500042 0.078935 -0.17969 -4.19898e-08 0.0773679 -0.17969 0.000499958 0.0773679 -0.238873 0.0223997 0.0573821 -0.239173 0.0223997 0.0573821 -0.239173 0.0201375 0.0387967 -0.238873 0.014785 0.0441492 -0.238873 0.0138529 0.0455442 -0.239173 0.0138529 0.0455442 -0.238873 0.0135256 0.0471898 -0.238873 0.0138529 0.0488353 -0.239173 0.0138529 0.0488353 -0.238873 0.014785 0.0502303 -0.239173 0.014785 0.0502303 -0.240173 -0.04487 0.0587094 -0.240173 0.047738 0.0599359 -0.240173 0.0248663 0.081735 -0.240173 0.0574136 0.0629569 -0.240173 0.06744 0.0644458 -0.240173 -0.0674401 0.0644458 -0.240173 0.0160326 0.0390255 -0.240173 -0.0158513 0.0406159 -0.240173 -0.014078 0.0434421 -0.240173 -0.0193925 0.0380383 -0.240173 -0.0159142 0.0375677 -0.240173 -0.0125578 0.0264355 -0.240173 -0.00992233 0.0263721 -0.240173 0.00799996 0.0444236 -0.240173 0.012929 0.0451615 -0.240173 0.0140779 0.0434421 -0.240173 -0.014078 0.0509374 -0.240173 -0.0220171 0.058306 -0.240173 -0.0240453 0.0587094 -0.240173 0.0100723 0.0201683 -0.240173 0.0125577 0.0264355 -0.240173 0.00992225 0.0263721 -0.240173 0.0248663 0.076235 -0.240173 0.00759803 0.0572094 -0.240173 0.012929 0.049218 -0.240173 0.00649996 0.0583075 -0.240173 0.00499996 0.0587094 -0.240173 -0.00500004 0.0587094 -0.240173 -0.00618235 0.0153003 -0.256673 0.00673792 0.0131069 -0.241173 0.00673792 0.0131069 -0.256673 0.00716335 0.0130165 -0.24028 0.0115015 0.0120944 -0.241082 0.00908514 0.012608 -0.25268 0.0118634 0.0120174 -0.254466 0.0101329 0.0123853 -0.256087 0.00854682 0.0127224 -0.240173 -0.0432821 -0.0594891 -0.240173 -0.0510343 -0.0626817 -0.240173 -0.0248664 -0.081265 -0.240173 -0.0674401 -0.0659758 -0.240173 -0.0785 -0.081265 -0.240173 0.0591313 -0.0648558 -0.240173 -0.0155094 -0.0381664 -0.240173 -0.0360023 -0.0553305 -0.240173 -0.0155 -0.057265 -0.240173 0.00992225 -0.027902 -0.240173 0.0138448 -0.0306182 -0.240173 0.0155093 -0.0381664 -0.240173 0.0248663 -0.076765 -0.240173 0.017 -0.056863 -0.240173 0.0185 -0.054265 -0.240173 0.0185 -0.0515371 -0.240173 0.0166692 -0.046444 -0.240173 0.0180284 -0.048831 -0.240173 -0.00630709 -0.0160611 -0.240173 -0.00616673 -0.016433 -0.240173 -0.00694592 -0.015615 -0.240173 -0.0082739 -0.0153327 -0.240173 -0.0160327 -0.0405554 -0.240173 -0.023329 -0.0444041 -0.240173 -0.0293146 -0.0502745 -0.240173 -0.0158525 -0.0421367 -0.240173 -0.0158513 -0.0421459 -0.240173 -0.0140219 -0.0430331 -0.240173 -0.0180981 -0.055765 -0.240173 0.0158512 -0.0421459 -0.240173 0.0233289 -0.0444041 -0.240173 0.015851 -0.0421365 -0.240173 0.00616664 -0.016433 -0.240173 0.00630701 -0.0160611 -0.240173 0.00694583 -0.015615 -0.251431 0.0122921 -0.0134563 -0.256673 0.00673792 -0.0146368 -0.251651 0.0122801 -0.0134588 -0.241082 0.00908514 -0.0141379 -0.254466 0.0101329 -0.0139152 -0.252845 0.011719 -0.0135781 -0.25656 0.00781102 -0.0144087 -0.256235 0.00838568 -0.0142866 -0.241173 0.0080659 -0.0143546 -0.256087 0.00854682 -0.0142524 -0.23934 0.0113761 -0.014679 -0.238873 0.0126317 -0.0144122 -0.239872 0.0246022 -0.0432624 -0.238873 0.0178066 -0.0285844 -0.239872 0.0195528 -0.0368466 -0.239872 0.00994795 -0.0149824 -0.239872 0.0304312 -0.0489793 -0.238873 0.0266446 -0.0414311 -0.239872 0.0369439 -0.0539031 -0.238873 0.0524625 -0.0584636 -0.239872 0.0594679 -0.0631792 -0.239872 0.0206764 0.0368977 -0.238873 0.0214985 0.0333003 -0.238876 0.0215041 0.0333218 -0.239872 0.0141128 0.0257239 -0.23934 0.0113761 0.013149 -0.239317 0.0529651 0.0583839 -0.238873 0.0677506 0.0600033 -0.238873 0.0574046 0.0583774 -0.239407 0.0130799 0.0108293 -0.251431 0.0130656 0.0107563 -0.239986 0.0130656 0.0107563 -0.251431 0.0130656 -0.0122863 -0.238873 0.0131221 -0.0125719 -0.19199 0.00424996 -0.077765 -0.19567 0.00212496 -0.077765 -0.227173 0.00424996 -0.077765 -0.225048 0.00368057 -0.077765 -0.223493 0.00212496 -0.077765 -0.229298 0.00368057 -0.077765 -0.231423 -4.19898e-08 -0.077765 -0.239173 -0.0236015 -0.077765 -0.229298 -0.00368065 -0.077765 -0.181048 0.00635471 -0.077765 -0.18774 -4.19898e-08 -0.077765 -0.17969 -0.000500042 -0.077765 -0.181048 -0.00635479 -0.077765 -0.189865 -0.00368065 -0.077765 -0.184844 -0.011014 -0.077765 -0.190304 -0.0135261 -0.077765 -0.194115 -0.00368065 -0.077765 -0.239136 -0.0235931 -0.077765 -0.19567 -0.00212504 -0.077765 -0.225048 -0.00368065 -0.077765 -0.223493 -0.00212504 -0.077765 -0.239872 0.0675593 -0.0642698 -0.239843 0.0788224 -0.0649771 -0.239872 0.078818 -0.0650571 -0.239813 0.0788238 0.0633657 -0.239872 0.0675593 0.0627399 -0.212229 0.0804257 0.0773679 -0.212229 0.0804257 0.077935 -0.238873 0.0798 0.0773679 -0.220173 0.0798 0.081735 -0.220173 0.0798 0.082735 -0.215711 0.0798 -0.078265 -0.219073 0.0798 -0.078265 -0.238873 0.0798 -0.0772953 -0.188674 0.0891743 -0.0772953 -0.238873 0.0155 -0.056265 -0.239173 0.0155 -0.056265 -0.238873 -0.0155 -0.056265 -0.238873 0.00699996 0.0335288 -0.256601 0.00600524 0.0298497 -0.238873 0.0037524 0.0244309 -0.256673 0.00266827 0.0228363 -0.238873 0.000964078 0.0219342 -0.256673 0.000964078 0.0219342 -0.238873 -0.000964162 0.0219342 -0.238873 -0.00266836 -0.0243663 -0.256673 -0.00266836 -0.0243663 -0.238873 -0.000964162 -0.0234641 -0.238873 0.000964078 -0.0234641 -0.256673 -0.000964162 -0.0234641 -0.256673 0.000964078 -0.0234641 -0.238873 0.00266827 -0.0243663 -0.238873 0.0158981 -0.0470806 -0.239402 0.0124166 -0.0425069 -0.240066 0.0117268 -0.0415045 -0.247909 0.00910569 -0.0373283 -0.184844 0.0110139 0.0773679 -0.181048 0.00635471 0.078935 -0.181048 0.00635471 0.0773679 -0.239136 0.0235931 0.077235 -0.239173 -0.0236015 0.077235 -0.239173 -0.00796159 0.077235 -0.238873 -4.19898e-08 0.077235 -0.238873 0.0079615 0.077235 -0.239173 0.0079615 0.077235 -0.220173 0.0798 -0.082265 -0.230373 0.0788 -0.082265 -0.218884 0.0205518 -0.082265 -0.219134 0.0204905 -0.082265 -0.239057 0.0246291 -0.082265 -0.239173 0.0248663 -0.082265 -0.238873 0.0788 -0.082265 -0.220173 0.0788 -0.082265 -0.218773 0.0785 -0.082265 -0.218773 0.0207843 -0.082265 -0.257673 0.00419244 -0.0161129 -0.257673 0.00423931 -0.0173045 -0.257673 0.00653001 0.0121288 -0.257673 0.00543605 0.0126036 -0.257673 -0.00695552 0.0120383 -0.257673 -0.00423939 0.0157746 -0.257673 0.00120511 -0.0224936 -0.257673 -0.00120519 -0.0224936 -0.257673 -0.00653009 -0.0136587 -0.257673 0.00469051 0.0240846 -0.257673 0.008398 0.0278681 -0.257673 0.00419244 0.0145829 -0.257673 0.00461353 0.0134672 -0.257673 -0.0057074 -0.000764971 -0.257673 -0.00333544 0.0220913 -0.257673 0.00543605 -0.0141336 -0.257673 -0.00839808 -0.0293981 -0.257673 -0.00333544 -0.0236213 -0.257673 -0.00543613 -0.0141336 -0.256673 0.00930986 -0.0289875 -0.241173 0.0146755 -0.0387184 -0.254673 0.0107884 -0.0320653 -0.241173 0.00900597 0.0267726 -0.256448 0.00985619 0.0286411 -0.256673 0.00521079 0.0155375 -0.210273 0.0676 -0.0772953 -0.211973 0.0680555 -0.079265 -0.213218 0.0693 -0.0772953 -0.213218 0.0693 -0.079265 -0.213218 0.0727 -0.0772953 -0.213673 0.071 -0.079265 -0.213218 0.0727 -0.079265 -0.211973 0.0739444 -0.0772953 -0.211973 0.0739444 -0.079265 -0.208573 0.0739444 -0.0772953 -0.207329 0.0727 -0.0772953 -0.208573 0.0680555 -0.0772953 -0.210273 0.0676 -0.079265 -0.19199 0.0266 -0.079265 -0.19369 0.0270555 -0.0772953 -0.19369 0.0270555 -0.079265 -0.194934 0.0283 -0.0772953 -0.19539 0.03 -0.0772953 -0.194934 0.0317 -0.079265 -0.19199 0.0334 -0.0772953 -0.19369 0.0329444 -0.079265 -0.19029 0.0329444 -0.079265 -0.189045 0.0317 -0.0772953 -0.18859 0.03 -0.079265 -0.189045 0.0283 -0.0772953 -0.19029 0.0270555 -0.0772953 -0.19029 0.0270555 -0.079265 -0.19199 0.0266 -0.0772953 -0.241673 0.0142196 -0.0400497 -0.248409 0.0103481 -0.0376049 -0.248409 0.0121531 0.0352001 -0.241673 0.00837786 0.0413528 -0.238873 0.0169142 -0.0556792 -0.238873 0.0173477 -0.0550303 -0.239173 0.00699996 0.0557094 -0.238873 0.00684772 0.0564748 -0.238873 0.00576532 0.0575572 -0.238873 0.00499996 0.0577094 -0.256795 0.00903275 -0.0131379 -0.256795 0.00782864 -0.000764971 -0.253552 0.0110713 -0.000764971 -0.251762 0.0130476 -0.01229 -0.25273 0.0127756 -0.0123462 -0.252579 0.0117216 -0.000764971 -0.251431 0.01195 -0.000764971 -0.253552 0.012205 0.0109342 -0.257445 0.00685537 -0.000764971 -0.257016 0.00879079 -0.013188 -0.257504 0.00792793 -0.0133667 -0.257673 0.00695544 -0.0135683 -0.257673 0.00570732 -0.000764971 -0.257673 0.00695544 0.0120383 -0.239872 0.0484822 0.0583916 -0.239872 0.0577952 0.0612899 -0.240173 0.0785 0.0652192 -0.240097 0.00912378 -0.0151548 -0.239872 0.012111 -0.0223496 -0.240173 0.0105022 -0.0229294 -0.239872 0.0153661 -0.0298372 -0.240173 0.0181439 -0.0378158 -0.240173 0.0293145 -0.0502745 -0.240173 0.0360022 -0.0553305 -0.239872 0.0440333 -0.0579528 -0.240173 0.043282 -0.0594891 -0.239872 0.0515827 -0.0610619 -0.240173 0.0510342 -0.0626817 -0.240173 0.06744 -0.0659758 -0.240148 0.0786152 -0.066254 -0.240075 0.0787161 -0.0657757 -0.240097 0.00912378 0.0136249 -0.239872 0.0116923 0.0196207 -0.240173 0.0156755 0.0324133 -0.239872 0.017149 0.0315454 -0.241173 0.00521079 -0.0170674 -0.256673 0.00521079 -0.0170674 -0.241173 0.00517954 -0.016273 -0.241173 0.00546027 -0.0155291 -0.256673 0.00546027 -0.0155291 -0.241173 0.00673792 -0.0146368 -0.241173 0.00600861 0.0134235 -0.256673 0.00600861 0.0134235 -0.256673 0.00546027 0.0139992 -0.241173 0.00517954 0.014743 -0.256673 0.00517954 0.014743 -0.239128 0.0797748 -0.0653983 -0.239002 0.0797936 -0.0653183 -0.239833 0.0793771 -0.0659725 -0.240086 0.0789691 -0.0663541 -0.240074 0.0789974 -0.081265 -0.240173 0.0785147 -0.0667369 -0.239999 0.07915 0.081735 -0.240086 0.0789691 0.0648242 -0.239833 0.0793771 0.0644425 -0.239523 0.0796258 0.081735 -0.239377 0.0796986 0.0640369 -0.212229 0.0804257 -0.078265 -0.257673 0.00659775 -0.0302711 -0.255173 0.010276 -0.0332998 -0.25658 0.00793601 -0.0330898 -0.255173 0.00847603 -0.0341727 -0.257316 0.00738453 0.0304227 -0.257583 0.00699487 0.029599 -0.257673 0.00659775 0.0287412 -0.256458 0.00792086 0.0317303 -0.255173 0.010276 0.0317698 -0.241673 0.0124044 -0.04093 -0.240843 0.0128301 -0.0415112 -0.240382 0.0151409 -0.0412681 -0.240173 0.0140218 -0.0430331 -0.240176 0.0157733 0.0405221 -0.240571 0.00821718 0.0426585 -0.241673 0.0142196 0.0385198 -0.256099 0.0103972 0.0299312 -0.25658 0.00973551 0.0306869 -0.257319 0.00943066 0.0291799 -0.255799 0.0103598 0.0296826 -0.256673 0.00930986 0.0274576 -0.257056 0.00924044 0.0274889 -0.257173 0.00918769 0.0275126 -0.256809 0.00984166 0.0287876 -0.256353 0.0102916 0.0302095 -0.256522 0.0100592 0.030475 -0.257392 0.00909652 0.0293662 -0.257597 0.00874695 0.027711 -0.257115 0.00969227 0.0289768 -0.241653 0.0145478 0.0382611 -0.241549 0.0147525 0.0379113 -0.248108 0.0127411 0.0342555 -0.247909 0.0126387 0.0339164 -0.255138 0.0105937 0.0315385 -0.25503 0.0108032 0.0312218 -0.248381 0.0124764 0.0349552 -0.248275 0.0126838 0.034622 -0.254867 0.0108716 0.0308691 -0.254673 0.0107884 0.0305353 -0.257673 0.00423931 0.0157746 -0.257539 0.00885393 0.0276629 -0.25738 0.00904278 0.0275778 -0.257173 0.00508063 0.0155692 -0.240899 0.0146076 0.0390447 -0.240382 0.0151409 0.0397382 -0.240328 0.0154561 0.0394903 -0.240863 0.0149302 0.0387886 -0.240909 0.0149799 0.0378073 -0.241379 0.0147977 0.0375316 -0.240662 0.0151743 0.0383952 -0.240173 0.015848 0.0406062 -0.240704 0.015149 0.0384761 -0.257539 0.00663396 0.0126178 -0.257539 0.00572233 0.0130135 -0.257539 0.0050369 0.0137332 -0.257539 0.00468599 0.014663 -0.257173 0.00534683 0.0139279 -0.257539 0.00472505 0.015656 -0.257173 0.00671007 0.0129759 -0.257173 0.00593191 0.0133136 -0.257173 0.00504729 0.0147216 -0.240445 0.0153481 0.0389898 -0.240173 0.0158502 0.0406065 -0.240173 0.0158512 0.0406159 -0.240313 0.0154867 0.0394593 -0.24019 0.0157199 0.0402106 -0.240329 0.0154967 0.0389975 -0.240183 0.0157654 0.0402169 -0.240173 0.0159141 0.0375677 -0.240191 0.0158452 0.0390157 -0.240226 0.015604 0.0376472 -0.240173 0.0159032 0.0402358 -0.240378 0.0153266 0.0377184 -0.240244 0.0156644 0.0390063 -0.240178 0.0158112 0.0402231 -0.240174 0.0158571 0.0402294 -0.240173 0.0158524 0.0406068 -0.241173 0.0146755 0.0371885 -0.240614 0.0151109 0.0377737 -0.240466 0.0149197 0.0370268 -0.240249 0.0151902 0.0368477 -0.257056 0.00672209 0.0130324 -0.257056 0.00714752 0.012942 -0.25738 0.00667702 0.0128204 -0.257597 0.007035 0.0124126 -0.257597 0.00660957 0.0125031 -0.240173 0.00618226 0.0153003 -0.240173 0.0155093 0.0366364 -0.240249 0.0095716 0.0265254 -0.240466 0.00927434 0.0266553 -0.240791 0.0147389 0.0371465 -0.240673 0.00534094 0.0155057 -0.241173 0.00521079 0.0155375 -0.240791 0.00907572 0.0267422 -0.256661 0.00737935 0.0129706 -0.257173 0.00713549 0.0128854 -0.25738 0.00710245 0.01273 -0.257539 0.00705939 0.0125274 -0.257655 0.00727976 0.0119711 -0.257377 0.00822797 0.0117746 -0.257521 0.00736904 0.0124626 -0.256925 0.00819425 0.0126615 -0.257157 0.00740549 0.0128283 -0.256795 0.00903275 0.0116079 -0.256697 0.0090406 0.0121127 -0.256439 0.00886297 0.0125201 -0.257254 0.00827366 0.0122732 -0.256476 0.00801085 0.0128363 -0.240307 0.00569653 0.0154189 -0.240173 0.00658118 0.0142433 -0.240173 0.00630701 0.0145312 -0.240173 0.00616664 0.0149031 -0.240307 0.00567309 0.0148231 -0.240307 0.0062949 0.0138334 -0.240307 0.00588364 0.0142652 -0.240466 0.00549533 0.015468 -0.240673 0.00608532 0.0135333 -0.240673 0.00557371 0.0140705 -0.241173 0.00546027 0.0139992 -0.240673 0.00531179 0.0147645 -0.255076 0.0106266 0.0117757 -0.255173 0.0106189 0.0112711 -0.253196 0.012035 0.0118459 -0.254817 0.010449 0.012183 -0.240791 0.00808173 0.0128991 -0.240673 0.00676577 0.013238 -0.240307 0.00684188 0.013596 -0.240307 0.00816986 0.0133137 -0.240249 0.00819425 0.0134285 -0.240173 0.00694583 0.0140851 -0.240173 0.00827381 0.0138028 -0.253304 0.0124219 0.0108894 -0.25299 0.0122151 0.0118079 -0.253454 0.0122127 0.0114388 -0.252845 0.011719 0.0120481 -0.253218 0.0124192 0.0113956 -0.252093 0.0121818 0.0119498 -0.252423 0.0129 0.0107906 -0.252377 0.0128742 0.0113005 -0.251431 0.0127492 0.011695 -0.252257 0.0126119 0.011724 -0.241173 0.0080659 0.0128246 -0.240673 0.00809376 0.0129557 -0.240466 0.0081268 0.0131111 -0.240811 0.0100734 0.0123979 -0.240705 0.00903592 0.0126965 -0.240385 0.00902598 0.012921 -0.239942 0.00989298 0.0130712 -0.240171 0.00905684 0.013247 -0.239986 0.0130318 0.0112676 -0.251431 0.0130318 0.0112676 -0.239986 0.0127492 0.011695 -0.251431 0.0122921 0.0119263 -0.239986 0.0122921 0.0119263 -0.239663 0.0123898 0.0119442 -0.239614 0.0113257 0.0124332 -0.239919 0.011389 0.0121966 -0.23941 0.0113211 0.0127677 -0.238873 0.0127348 0.0125013 -0.239872 0.00994795 0.0134525 -0.240145 0.00989754 0.0127367 -0.240451 0.00996093 0.0125002 -0.238873 0.0129866 0.0120518 -0.238873 0.0131292 0.0115717 -0.238873 0.0131325 0.0115498 -0.239035 0.0126364 0.0122649 -0.238873 0.0129772 0.0120732 -0.238873 0.0129286 0.012176 -0.239527 0.0130529 0.011296 -0.239012 0.0131072 0.0114829 -0.23962 0.0128035 0.011699 -0.239205 0.012886 0.0118261 -0.239532 0.0124335 0.0119739 -0.239308 0.0125158 0.0120622 -0.238873 0.0220835 0.0353369 -0.238873 0.0218615 0.0365537 -0.239381 0.0211742 0.0375467 -0.239082 0.021839 0.0362763 -0.239722 0.0209975 0.037239 -0.239027 0.0218555 0.0347464 -0.239098 0.0216204 0.0345674 -0.239442 0.0213392 0.0358007 -0.239265 0.0217082 0.0360068 -0.24 0.0203867 0.0371889 -0.238932 0.0211637 0.0377463 -0.239035 0.0208836 0.0380506 -0.239507 0.0208827 0.0378712 -0.239673 0.0200427 0.038702 -0.239858 0.0207016 0.0375574 -0.240173 0.0194304 0.0380896 -0.240039 0.0144314 0.0437957 -0.240039 0.0197839 0.0384432 -0.239673 0.0146903 0.0440545 -0.239173 0.014785 0.0441492 -0.240173 0.0140779 0.0509374 -0.239673 0.0137291 0.0488866 -0.239673 0.0133916 0.0471898 -0.239173 0.0135256 0.0471898 -0.239673 0.0137291 0.045493 -0.240039 0.0133909 0.0490266 -0.240039 0.0130256 0.0471898 -0.240039 0.0133909 0.0453529 -0.240173 0.0125256 0.0471898 -0.240173 0.0202976 0.0571571 -0.240039 0.0144314 0.0505839 -0.23988 0.0145779 0.0504374 -0.239556 0.0209508 0.0565038 -0.239673 0.0146903 0.0503251 -0.239556 0.0240452 0.0577855 -0.23988 0.0240452 0.0580023 -0.23988 0.0222876 0.0576527 -0.240173 0.022017 0.058306 -0.240097 0.0221634 0.0579524 -0.240097 0.0240452 0.0583267 -0.239173 0.0210047 0.05645 -0.239556 0.0223706 0.0574524 -0.23988 0.0207976 0.0566571 -0.240097 0.0205682 0.0568865 -0.239173 0.04487 0.0577094 -0.239173 0.0240452 0.0577094 -0.239673 0.0240452 0.0578434 -0.240039 0.04487 0.0582094 -0.240039 0.0240452 0.0582094 -0.240173 0.04487 0.0587094 -0.240173 0.0240452 0.0587094 -0.238932 0.0483558 0.0577094 -0.239979 0.046678 0.058217 -0.23973 0.0484631 0.058116 -0.23911 0.0466169 0.0577094 -0.239454 0.0466411 0.0577707 -0.239556 0.04487 0.0577855 -0.239673 0.04487 0.0578434 -0.239756 0.0466623 0.0579471 -0.239511 0.0484336 0.0578977 -0.240095 0.0466861 0.0585472 -0.240097 0.04487 0.0583267 -0.23988 0.04487 0.0580023 -0.238873 0.0487965 0.0577094 -0.239332 0.0484096 0.0577946 -0.238873 0.0519825 0.05779 -0.238873 0.0507965 0.0577419 -0.239108 0.0529418 0.0580317 -0.239664 0.0484543 0.0580357 -0.248409 0.0121531 -0.03673 -0.255138 0.0105937 -0.0330684 -0.248275 0.0126838 -0.0361519 -0.254867 0.0108716 -0.032399 -0.241653 0.0145478 -0.039791 -0.248381 0.0124764 -0.0364851 -0.241549 0.0147525 -0.0394412 -0.248108 0.0127411 -0.0357855 -0.247909 0.0126387 -0.0354464 -0.257259 0.00950131 -0.030858 -0.25733 0.00916851 -0.0310472 -0.257056 0.00924044 -0.0290188 -0.256399 0.00991276 -0.0302902 -0.257673 0.008398 -0.0293981 -0.257539 0.00885393 -0.0291928 -0.257056 0.00975952 -0.0306477 -0.256465 0.00979692 -0.0323414 -0.256409 0.0101198 -0.0321271 -0.256245 0.0103495 -0.0318558 -0.255707 0.0104084 -0.0313107 -0.256755 0.00990398 -0.0304484 -0.25503 0.0108032 -0.0327517 -0.255998 0.0104509 -0.031569 -0.240284 0.0155258 -0.0411188 -0.240176 0.0157733 -0.0420521 -0.240863 0.0149302 -0.0403186 -0.240899 0.0146076 -0.0405746 -0.240328 0.0154561 -0.0410202 -0.240704 0.015149 -0.040006 -0.241379 0.0147977 -0.0390615 -0.257597 0.00874695 -0.029241 -0.257539 0.00472505 -0.017186 -0.257173 0.00918769 -0.0290425 -0.25738 0.00904278 -0.0291078 -0.24019 0.0157199 -0.0417406 -0.240445 0.0153481 -0.0405197 -0.240566 0.0152472 -0.0401723 -0.240909 0.0149799 -0.0393372 -0.240673 0.0147872 -0.0386445 -0.240528 0.0151744 -0.0392874 -0.240266 0.0155064 -0.0392022 -0.240297 0.0155508 -0.0405303 -0.240205 0.0157839 -0.0405425 -0.240175 0.0158418 -0.0417573 -0.240181 0.0157806 -0.0417489 -0.240173 0.015848 -0.0421361 -0.240173 0.0159032 -0.0417657 -0.240173 0.0160326 -0.0405554 -0.240173 0.0159141 -0.0390977 -0.257173 0.00508063 -0.0170992 -0.257673 0.00653001 -0.0136587 -0.257539 0.00572233 -0.0145435 -0.257539 0.0050369 -0.0152631 -0.257539 0.00468599 -0.0161929 -0.257673 0.00461353 -0.0149971 -0.257173 0.00593191 -0.0148436 -0.257173 0.00671007 -0.0145058 -0.257056 0.00672209 -0.0145624 -0.256673 0.00517954 -0.016273 -0.257173 0.00504729 -0.0162515 -0.257173 0.00534683 -0.0154578 -0.256673 0.00600861 -0.0149534 -0.240173 0.00618226 -0.0168303 -0.240307 0.00569653 -0.0169488 -0.240791 0.00907572 -0.0282721 -0.240673 0.00534094 -0.0170356 -0.241173 0.00900597 -0.0283026 -0.240249 0.0095716 -0.0280553 -0.240307 0.0150924 -0.0384424 -0.240466 0.0149197 -0.0385567 -0.240466 0.00927434 -0.0281853 -0.25738 0.00667702 -0.0143504 -0.257539 0.00663396 -0.0141478 -0.257597 0.007035 -0.0139426 -0.257597 0.00660957 -0.014033 -0.240466 0.00679882 -0.0149233 -0.240307 0.00567309 -0.016353 -0.240307 0.00588364 -0.0157951 -0.240173 0.00658118 -0.0157733 -0.240466 0.00549533 -0.0169979 -0.240307 0.0062949 -0.0153634 -0.240673 0.00557371 -0.0156004 -0.240673 0.00531179 -0.0162944 -0.240673 0.00608532 -0.0150633 -0.241173 0.00600861 -0.0149534 -0.256697 0.0090406 -0.0136426 -0.256909 0.00881009 -0.0136909 -0.256673 0.00716335 -0.0145464 -0.257056 0.00714752 -0.014472 -0.256623 0.00866199 -0.0140925 -0.257173 0.00713549 -0.0144154 -0.257031 0.00794476 -0.0142442 -0.25738 0.00710245 -0.0142599 -0.257539 0.00705939 -0.0140573 -0.257376 0.00798752 -0.013863 -0.240673 0.00676577 -0.0147679 -0.240791 0.00808173 -0.014429 -0.240249 0.00819425 -0.0149584 -0.240307 0.00684188 -0.0151259 -0.253552 0.012205 -0.0124642 -0.253454 0.0122127 -0.0129687 -0.253196 0.012035 -0.0133759 -0.255173 0.0106189 -0.012801 -0.255076 0.0106266 -0.0133057 -0.256439 0.00886297 -0.01405 -0.254817 0.010449 -0.013713 -0.240811 0.0100734 -0.0139279 -0.240705 0.00903592 -0.0142265 -0.240145 0.00989754 -0.0142666 -0.240171 0.00905684 -0.014777 -0.239942 0.00989298 -0.0146012 -0.240466 0.0081268 -0.0146411 -0.240385 0.00902598 -0.0144509 -0.240173 0.00827381 -0.0153327 -0.251431 0.0130318 -0.0127975 -0.251706 0.0127343 -0.0132281 -0.251431 0.0127492 -0.0132249 -0.25267 0.0127558 -0.0128552 -0.251747 0.0130147 -0.0128011 -0.252512 0.0125086 -0.0132758 -0.252297 0.0120989 -0.0134973 -0.238947 0.0126853 -0.0139034 -0.24028 0.0115015 -0.0136243 -0.240451 0.00996093 -0.0140301 -0.239919 0.011389 -0.0137266 -0.239614 0.0113257 -0.0139631 -0.23941 0.0113211 -0.0142977 -0.239986 0.0122921 -0.0134563 -0.239986 0.0130318 -0.0127975 -0.238873 0.0127348 -0.0140313 -0.23921 0.012556 -0.01365 -0.238873 0.0129745 -0.0136091 -0.238873 0.0128753 -0.0138066 -0.239574 0.0124191 -0.0134927 -0.239087 0.0129153 -0.0134229 -0.239517 0.0128215 -0.013247 -0.2394 0.013063 -0.0128554 -0.238873 0.013145 -0.0127381 -0.239986 0.0130656 -0.0122863 -0.239248 0.0130891 -0.0124061 -0.239986 0.0127492 -0.0132249 -0.240039 0.00499996 0.0582094 -0.239673 -0.00500004 0.0578434 -0.239173 0.00641417 0.0571236 -0.239173 0.00673201 0.0567094 -0.239673 0.00713393 0.0557094 -0.23988 0.00729285 0.0557094 -0.239673 0.00684803 0.0567764 -0.240039 0.00716502 0.0569594 -0.240173 0.00799996 0.0557094 -0.239673 0.00606695 0.0575575 -0.240039 0.00624996 0.0578745 -0.239173 0.00599996 0.0574415 -0.239173 0.00499996 0.0577094 -0.239673 0.00499996 0.0578434 -0.240097 0.00761727 0.0444236 -0.240039 0.00749996 0.0557094 -0.239173 0.00699996 0.0444236 -0.239704 0.00699996 0.0422106 -0.240088 0.0070984 0.0424091 -0.239556 0.00707608 0.0444236 -0.240397 0.00737435 0.0425686 -0.23988 0.00729285 0.0444236 -0.241427 0.00711743 0.0409694 -0.240569 0.00777346 0.0426575 -0.241173 0.00699996 0.0405736 -0.2526 0.00744224 0.0342274 -0.241621 0.00744224 0.0412722 -0.24171 0.00789808 0.0414109 -0.255173 0.00779105 0.0328485 -0.252652 0.00837786 0.034308 -0.25389 0.00834014 0.033532 -0.252689 0.00789808 0.0343661 -0.253907 0.00788147 0.0336048 -0.253813 0.00744025 0.0334936 -0.252406 0.00711743 0.0339246 -0.252152 0.00699996 0.0335288 -0.253627 0.00711176 0.0332224 -0.25339 0.00696695 0.0328498 -0.256265 0.00713773 0.0318018 -0.257045 0.00669801 0.0306297 -0.256009 0.00684146 0.0316661 -0.255701 0.00668128 0.0314407 -0.256387 0.00631971 0.0305187 -0.255173 0.00822732 0.0327634 -0.256423 0.00751932 0.0318245 -0.255074 0.0073663 0.0327628 -0.254895 0.00703701 0.0325233 -0.254673 0.00686824 0.0321772 -0.256673 0.00568622 0.0291524 -0.257509 0.00664084 0.0297476 -0.257539 0.00614198 0.0289468 -0.257297 0.00632831 0.0298474 -0.257246 0.00702628 0.0305624 -0.256743 0.00644985 0.0306143 -0.256978 0.00610507 0.0298833 -0.256673 0.0037524 0.0244309 -0.257056 0.0057556 0.0291211 -0.257173 0.00580834 0.0290973 -0.25738 0.0059532 0.029032 -0.257173 0.00387808 0.0243845 -0.257597 0.00624892 0.0288986 -0.257539 0.00422146 0.0242578 -0.257673 0.00333535 0.0220913 -0.257539 0.00300181 0.0224638 -0.257673 0.00120511 0.0209637 -0.257673 -0.00120519 0.0209637 -0.257539 0.00108459 0.0214489 -0.257173 0.000996369 0.0218042 -0.257173 -0.000996453 0.0218042 -0.257539 -0.00108468 0.0214489 -0.257539 -0.0030019 0.0224638 -0.257539 -0.00422154 0.0242578 -0.257173 0.00275764 0.0227365 -0.256673 -0.000964162 0.0219342 -0.257173 -0.00275773 0.0227365 -0.256673 -0.00266836 0.0228363 -0.257173 -0.00387817 0.0243845 -0.256673 -0.00375248 -0.0259609 -0.25738 -0.00286374 -0.0241481 -0.257673 -0.0046906 -0.0256145 -0.257597 -0.00308016 -0.0239064 -0.257597 -0.00111295 -0.022865 -0.257673 0.00333535 -0.0236213 -0.257673 0.00469051 -0.0256145 -0.25738 -0.00103476 -0.0231799 -0.257597 0.00111287 -0.022865 -0.25738 0.00103467 -0.0231799 -0.257597 0.00308007 -0.0239064 -0.25738 0.00286366 -0.0241481 -0.257056 -0.00271914 -0.0243096 -0.257056 0.000982425 -0.0233903 -0.257056 0.00271905 -0.0243096 -0.257056 -0.000982509 -0.0233903 -0.256673 0.00266827 -0.0243663 -0.256673 0.0037524 -0.0259609 -0.257056 0.00382381 -0.0259345 -0.25738 0.00402717 -0.0258594 -0.257597 0.00433151 -0.0257471 -0.254673 0.00720751 -0.0338482 -0.255799 0.00676704 -0.032971 -0.256097 0.00694035 -0.033151 -0.254921 0.00751908 -0.0341703 -0.255024 0.00773877 -0.0342584 -0.25652 0.00757271 -0.0332153 -0.255103 0.00798239 -0.0342888 -0.257392 0.00729696 -0.031769 -0.25635 0.00722318 -0.0332368 -0.257117 0.0066148 -0.0319853 -0.257597 0.00624892 -0.0304285 -0.257321 0.00693959 -0.0319107 -0.25738 0.0059532 -0.0305619 -0.257056 0.0057556 -0.0306511 -0.256673 0.00568622 -0.0306824 -0.25681 0.00637221 -0.0319814 -0.256448 0.00624891 -0.0318996 -0.24815 0.0094216 -0.0376262 -0.248332 0.00987285 -0.0377267 -0.255133 0.00810814 -0.0342816 -0.240436 0.0119918 -0.0416834 -0.241173 0.0111906 -0.0406997 -0.241408 0.0115092 -0.0409737 -0.240717 0.0123914 -0.0416858 -0.241589 0.0119476 -0.0410569 -0.239859 0.0126108 -0.0425658 -0.240345 0.013381 -0.0422329 -0.240202 0.0129616 -0.0424661 -0.240097 0.0163741 -0.0466876 -0.240039 0.0136178 -0.0433277 -0.240039 0.0162837 -0.0467623 -0.23988 0.0161239 -0.0468942 -0.239173 0.0132137 -0.0436222 -0.239673 0.0160014 -0.0469953 -0.239673 0.013322 -0.0435433 -0.239556 0.017159 -0.0491436 -0.239173 0.0158981 -0.0470806 -0.239556 0.0159568 -0.0470322 -0.239556 0.0175761 -0.0515371 -0.239173 0.0170873 -0.0491693 -0.23988 0.0177929 -0.0515371 -0.23988 0.017363 -0.0490702 -0.240097 0.0176683 -0.0489605 -0.240097 0.0181173 -0.0515371 -0.23988 0.0177929 -0.054265 -0.239673 0.0176339 -0.054265 -0.239173 0.0175 -0.0515371 -0.240039 0.018 -0.054265 -0.240039 0.017665 -0.055515 -0.239173 0.0165 -0.055997 -0.239173 0.0169142 -0.0556792 -0.239173 0.017232 -0.055265 -0.239673 0.017348 -0.055332 -0.239173 0.0175 -0.054265 -0.239673 0.0165669 -0.056113 -0.240039 0.01675 -0.05643 -0.240173 0.0155 -0.057265 -0.240173 0.018098 -0.055765 -0.240039 -0.0155 -0.056765 -0.240039 0.0155 -0.056765 -0.239673 -0.0155 -0.0563989 -0.239673 0.0155 -0.0563989 -0.240173 0.0785073 -0.0667349 -0.240173 0.0785036 -0.0667338 -0.240143 0.0787358 -0.0662865 -0.240173 0.0785 -0.0667492 -0.240173 0.078511 -0.0667359 -0.240122 0.0788543 -0.06632 -0.239377 0.0796986 -0.0655668 -0.239511 0.079595 -0.0652454 -0.239969 0.0791818 -0.0659011 -0.240052 0.0789568 -0.0658341 -0.239337 0.0796699 -0.0650686 -0.238873 0.0798 -0.0652368 -0.239777 0.0792529 -0.0651234 -0.239729 0.0792851 -0.0650351 -0.239426 0.0796358 -0.0651583 -0.238873 0.0789529 -0.0623412 -0.239813 0.0788238 -0.0648957 -0.238873 0.0793163 -0.0627276 -0.23968 0.0793137 -0.064944 -0.240173 0.078511 0.065206 -0.240173 0.0785073 0.0652049 -0.240122 0.0788543 0.0647901 -0.239969 0.0791818 0.0643711 -0.240173 0.0785036 0.0652039 -0.240143 0.0787358 0.0647565 -0.240148 0.0786152 0.064724 -0.240075 0.0787161 0.0642458 -0.240052 0.0789568 0.0643042 -0.240173 0.0785147 0.065207 -0.239843 0.0788224 0.0634472 -0.239729 0.0792851 0.0635051 -0.239872 0.078818 0.0635272 -0.239777 0.0792529 0.0635935 -0.239426 0.0796358 0.0636283 -0.239511 0.079595 0.0637154 -0.239002 0.0797936 0.0637884 -0.239128 0.0797748 0.0638684 -0.23968 0.0793137 0.0634141 -0.239337 0.0796699 0.0635386 -0.238873 0.0793163 0.0611976 -0.238873 0.0790794 0.0608935 -0.217773 0.0785 -0.079265 -0.217947 0.07915 -0.081265 -0.217948 0.0791515 -0.0792011 -0.218083 0.0793426 -0.0791049 -0.219073 0.0798 -0.081265 -0.218404 0.0796144 -0.0788452 -0.218256 0.0795111 -0.078968 -0.218764 0.0195217 -0.079265 -0.24004 0.024294 -0.081265 -0.239988 0.024197 -0.0773452 -0.240173 0.0248663 -0.081265 -0.240173 0.0248609 -0.0767697 -0.23947 0.0237114 -0.0777199 -0.239669 0.0238386 -0.081265 -0.239173 0.0236014 -0.077765 -0.239559 0.0237617 -0.0776877 -0.239136 0.0235931 0.081735 -0.239173 0.0236014 0.077235 -0.239669 0.0238386 0.081735 -0.24004 0.024294 0.081735 -0.240173 0.0248609 0.0762398 -0.239988 0.024197 0.0768153 -0.217899 0.0202265 0.081735 -0.217899 0.0202265 0.078935 -0.218252 0.0197766 0.078935 -0.218764 0.0195217 0.081735 -0.218764 0.0195217 0.078935 -0.217948 0.0791515 0.0788712 -0.218404 0.0796144 0.0785153 -0.219073 0.0798 0.081735 -0.217808 0.0788 0.078935 -0.239109 0.0237243 -0.081765 -0.238934 0.0245725 -0.082265 -0.239363 0.0242339 -0.082131 -0.239587 0.0239445 -0.081765 -0.239592 0.0245141 -0.082131 -0.23992 0.024353 -0.081765 -0.239143 0.0247342 -0.082265 -0.239136 0.0235931 -0.081265 -0.219309 0.0196423 -0.081765 -0.219277 0.019798 -0.0819721 -0.239035 0.0240828 -0.082131 -0.240173 0.0785 -0.081265 -0.240039 0.0248663 -0.081765 -0.239673 0.0248663 -0.082131 -0.239173 0.0785 -0.082265 -0.218782 0.0195956 -0.0816477 -0.218764 0.0195217 -0.081265 -0.218252 0.0197766 -0.081265 -0.217899 0.0202265 -0.081265 -0.217773 0.0207843 -0.081265 -0.218273 0.0207843 -0.082131 -0.218066 0.0207843 -0.0819721 -0.217968 0.0202591 -0.0816477 -0.2183 0.0198356 -0.0816477 -0.218437 0.0200036 -0.0819721 -0.218391 0.0207843 -0.0821889 -0.21932 0.0195857 -0.0816477 -0.219235 0.0200008 -0.082131 -0.218164 0.0203522 -0.0819721 -0.218457 0.0204914 -0.0821889 -0.218834 0.0198062 -0.0819721 -0.219211 0.0201157 -0.0821889 -0.218802 0.0206556 -0.082265 -0.218642 0.0202551 -0.0821889 -0.219002 0.020493 -0.082265 -0.218911 0.0201213 -0.0821889 -0.240039 0.0785 -0.081765 -0.23995 0.0789462 -0.081765 -0.239792 0.0794192 -0.081265 -0.239698 0.0793245 -0.081765 -0.239371 0.079701 -0.081265 -0.238873 0.0798 -0.081265 -0.239673 0.0785 -0.082131 -0.239612 0.0788061 -0.082131 -0.239319 0.0795772 -0.081765 -0.23915 0.0786148 -0.082265 -0.239439 0.0790656 -0.082131 -0.239085 0.0787121 -0.082265 -0.239179 0.0792391 -0.082131 -0.238988 0.0787771 -0.082265 -0.238873 0.0793 -0.082131 -0.217907 0.0207843 -0.081765 -0.217849 0.0207843 -0.0816477 -0.238873 0.079666 -0.081765 -0.219073 0.079666 -0.081765 -0.21849 0.0795098 -0.081765 -0.218673 0.0791928 -0.082131 -0.218923 0.0787598 -0.082265 -0.218423 0.0796258 -0.081265 -0.218063 0.079083 -0.081765 -0.217773 0.0785 -0.081265 -0.217907 0.0785 -0.081765 -0.21838 0.0789 -0.082131 -0.218273 0.0785 -0.082131 -0.218813 0.07865 -0.082265 -0.219073 0.0793 0.0826011 -0.219073 0.079666 0.082235 -0.21849 0.0795098 0.082235 -0.219073 0.0795071 0.0824421 -0.218673 0.0791928 0.0826011 -0.21838 0.0789 0.0826011 -0.218423 0.0796258 0.081735 -0.217947 0.07915 0.081735 -0.218063 0.079083 0.082235 -0.217907 0.0785 0.082235 -0.218273 0.0207843 0.0826011 -0.218391 0.0207843 0.0826589 -0.218273 0.0785 0.0826011 -0.230373 0.0788 0.082735 -0.238873 0.0793 0.0826011 -0.230373 0.0795071 0.0824421 -0.230373 0.0797238 0.0821177 -0.218457 0.0204914 0.0826589 -0.218884 0.0205518 0.082735 -0.218802 0.0206556 0.082735 -0.218066 0.0207843 0.0824421 -0.218164 0.0203522 0.0824421 -0.218642 0.0202551 0.0826589 -0.218911 0.0201213 0.0826589 -0.218437 0.0200036 0.0824421 -0.217849 0.0207843 0.0821177 -0.217907 0.0207843 0.082235 -0.219235 0.0200008 0.0826011 -0.219277 0.019798 0.0824421 -0.218834 0.0198062 0.0824421 -0.217968 0.0202591 0.0821177 -0.218782 0.0195956 0.0821177 -0.217773 0.0207843 0.081735 -0.2183 0.0198356 0.0821177 -0.218252 0.0197766 0.081735 -0.239023 0.0787598 0.082735 -0.239566 0.0789 0.0826011 -0.240039 0.0785 0.082235 -0.239883 0.079083 0.082235 -0.239792 0.0794192 0.081735 -0.239456 0.0795098 0.082235 -0.238873 0.0788 0.082735 -0.239273 0.0791928 0.0826011 -0.238873 0.0795071 0.0824421 -0.238873 0.079666 0.082235 -0.238873 0.0798 0.081735 -0.219211 0.0201157 0.0826589 -0.219309 0.0196423 0.082235 -0.239109 0.0237243 0.082235 -0.21932 0.0195857 0.0821177 -0.239673 0.0248663 0.0826011 -0.239673 0.0785 0.0826011 -0.240039 0.0248663 0.082235 -0.240173 0.0785 0.081735 -0.238934 0.0245725 0.082735 -0.239035 0.0240828 0.0826011 -0.239587 0.0239445 0.082235 -0.239143 0.0247342 0.082735 -0.239363 0.0242339 0.0826011 -0.239592 0.0245141 0.0826011 -0.239173 0.0248663 0.082735 -0.23992 0.024353 0.082235 -0.239173 -0.0159231 0.077235 -0.239559 -0.0237618 0.0771577 -0.239173 0.015923 0.077235 -0.239884 -0.0240493 0.0769381 -0.239559 0.0237617 0.0771577 -0.23947 0.0237114 0.07719 -0.239173 -4.19898e-08 0.077235 -0.239716 0.0238764 0.077075 -0.239988 -0.024197 0.0768153 -0.239884 0.0240492 0.0769381 -0.2401 0.0244353 0.0766114 -0.2401 -0.0244354 -0.0771413 -0.240173 -0.0248664 -0.076765 -0.239988 -0.024197 -0.0773452 -0.2401 0.0244353 -0.0771413 -0.239716 0.0238764 -0.0776049 -0.239884 0.0240492 -0.077468 -0.239559 -0.0237618 -0.0776877 -0.230373 -0.0788 0.082735 -0.220173 -0.0788 0.082735 -0.239133 -0.07865 0.082735 -0.239143 -0.0247343 0.082735 -0.239173 -0.0248664 0.082735 -0.239173 -0.0785 0.082735 -0.238873 -0.0788 0.082735 -0.219134 -0.0204906 0.082735 -0.219002 -0.020493 0.082735 -0.17969 -0.000500042 -0.079265 -0.239173 -0.0175 -0.054265 -0.238873 -0.0223998 0.0573821 -0.239173 -0.0223998 0.0573821 -0.238873 -0.0210047 0.05645 -0.238873 -0.0136722 0.0483027 -0.238873 -0.0136722 0.0460768 -0.239173 -0.0136722 0.0460768 -0.239173 -0.0147851 0.0502303 -0.24028 -0.0115016 0.0120944 -0.251431 -0.0122921 0.0119263 -0.241082 -0.00908523 0.012608 -0.25268 -0.0118635 0.0120174 -0.256661 -0.00737943 0.0129706 -0.241173 -0.00806598 0.0128246 -0.256087 -0.0085469 0.0127224 -0.252845 -0.0117191 -0.0135781 -0.240811 -0.0100735 -0.0139279 -0.25656 -0.00781111 -0.0144087 -0.239872 -0.059468 -0.0631792 -0.239872 -0.0121111 -0.0223496 -0.238873 -0.0524626 -0.0584636 -0.238873 -0.0384546 -0.0516132 -0.238873 -0.0266447 -0.0414311 -0.239872 -0.0304312 -0.0489793 -0.239872 -0.0195529 -0.0368466 -0.238873 -0.0126317 -0.0144122 -0.239872 -0.0171491 0.0315454 -0.239872 -0.0116924 0.0196207 -0.239872 -0.0141129 0.0257239 -0.238873 -0.0677507 0.0600033 -0.238873 -0.0584074 0.0586158 -0.239317 -0.0529652 0.0583839 -0.239248 -0.0130892 -0.0124061 -0.238873 -0.0131222 -0.0125719 -0.238873 -0.01195 -0.000764971 -0.251431 -0.0130657 0.0107563 -0.239407 -0.01308 0.0108293 -0.239813 -0.0788239 -0.0648957 -0.238873 -0.0788239 0.0607776 -0.239843 -0.0788224 0.0634472 -0.230373 -0.0798 0.081735 -0.219073 -0.0798 0.077935 -0.215711 -0.0798 0.0773679 -0.220173 -0.0798 -0.081265 -0.230373 -0.0798 -0.082265 -0.220173 -0.0798 -0.082265 -0.219073 -0.0798 -0.081265 -0.222884 -0.0798 -0.0772953 -0.219073 -0.0798 -0.078265 -0.215711 -0.0798 -0.0772953 -0.241173 -0.00700004 0.0405736 -0.239173 -0.00700004 0.0557094 -0.238873 -0.00700004 0.0335288 -0.256673 -0.00375248 0.0244309 -0.256673 -0.0056863 -0.0306824 -0.238873 -0.0158982 -0.0470806 -0.241173 -0.0111907 -0.0406997 -0.238873 -0.00893494 -0.0370328 -0.247909 -0.00910577 -0.0373283 -0.254673 -0.0072076 -0.0338482 -0.255799 -0.00676712 -0.032971 -0.181048 -0.00635479 0.078935 -0.230373 -0.0788 -0.082265 -0.218923 -0.0787598 -0.082265 -0.218773 -0.0785 -0.082265 -0.219073 -0.0788 -0.082265 -0.218773 -0.0207844 -0.082265 -0.239173 -0.0785 -0.082265 -0.238873 -0.0788 -0.082265 -0.247909 -0.0126387 -0.0354464 -0.255707 -0.0104085 -0.0313107 -0.256673 -0.00930994 -0.0289875 -0.256673 -0.00521087 -0.0170674 -0.255799 -0.0103599 0.0296826 -0.256448 -0.00985628 0.0286411 -0.241173 -0.00900606 0.0267726 -0.256673 -0.00930994 0.0274576 -0.208573 -0.0680556 -0.0772953 -0.207329 -0.0693 -0.0772953 -0.208573 -0.0680556 -0.079265 -0.207329 -0.0727 -0.0772953 -0.207329 -0.0727 -0.079265 -0.208573 -0.0739445 -0.079265 -0.210273 -0.0744 -0.079265 -0.211973 -0.0739445 -0.079265 -0.213218 -0.0727 -0.0772953 -0.213218 -0.0727 -0.079265 -0.213673 -0.071 -0.079265 -0.213218 -0.0693 -0.0772953 -0.213218 -0.0693 -0.079265 -0.210273 -0.0676 -0.079265 -0.19199 -0.0266 -0.079265 -0.19029 -0.0270556 -0.079265 -0.189045 -0.0317 -0.079265 -0.19199 -0.0334 -0.079265 -0.19369 -0.0329445 -0.0772953 -0.19369 -0.0329445 -0.079265 -0.194934 -0.0317 -0.0772953 -0.19539 -0.03 -0.0772953 -0.194934 -0.0317 -0.079265 -0.194934 -0.0283 -0.0772953 -0.19199 -0.0266 -0.0772953 -0.19369 -0.0270556 -0.079265 -0.255173 -0.00847611 -0.0341727 -0.248409 -0.0103482 -0.0376049 -0.241673 -0.00837794 0.0413528 -0.252652 -0.00837794 0.034308 -0.248409 -0.0121532 0.0352001 -0.255173 -0.010276 0.0317698 -0.25389 -0.00834022 0.033532 -0.238873 -0.0170874 -0.0491693 -0.256387 -0.00631979 0.0305187 -0.254673 -0.00686832 0.0321772 -0.255701 -0.00668136 0.0314407 -0.239173 -0.0172321 -0.055265 -0.238873 -0.0175 -0.054265 -0.239173 -0.0155 -0.056265 -0.239173 -0.00500004 0.0577094 -0.238873 -0.00500004 0.0577094 -0.239173 -0.00673209 0.0567094 -0.238873 -0.00673209 0.0567094 -0.238873 -0.00700004 0.0557094 -0.253552 -0.0110714 -0.000764971 -0.253304 -0.012422 0.0108894 -0.253552 -0.0122051 0.0109342 -0.251431 -0.01195 -0.000764971 -0.25273 -0.0127756 -0.0123462 -0.252579 -0.0117217 -0.000764971 -0.257655 -0.00727984 0.0119711 -0.256795 -0.00903283 -0.0131379 -0.257016 -0.00879087 -0.013188 -0.256795 -0.00782872 -0.000764971 -0.257445 -0.00685545 -0.000764971 -0.257377 -0.00822806 0.0117746 -0.256795 -0.00903283 0.0116079 -0.240173 -0.0477381 0.0599359 -0.239872 -0.0484823 0.0583916 -0.240173 -0.0574137 0.0629569 -0.239872 -0.0577953 0.0612899 -0.239872 -0.0675593 0.0627399 -0.240173 -0.0785037 0.0652039 -0.240173 -0.0105023 -0.0229294 -0.240173 -0.0138448 -0.0306182 -0.239872 -0.0153662 -0.0298372 -0.240173 -0.018144 -0.0378158 -0.239872 -0.0246022 -0.0432624 -0.239872 -0.036944 -0.0539031 -0.239872 -0.0440334 -0.0579528 -0.239872 -0.0515828 -0.0610619 -0.240173 -0.0591313 -0.0648558 -0.239872 -0.0675593 -0.0642698 -0.240075 -0.0787162 -0.0657757 -0.240173 -0.0100723 0.0201683 -0.24 -0.0203868 0.0371889 -0.240173 -0.0156756 0.0324133 -0.239872 -0.00994803 0.0134525 -0.241173 -0.006738 -0.0146368 -0.241173 -0.00546035 -0.0155291 -0.241173 -0.00517962 -0.016273 -0.256673 -0.00517962 -0.016273 -0.241173 -0.00517962 0.014743 -0.256673 -0.00546035 0.0139992 -0.240173 -0.0785 -0.0667492 -0.240173 -0.0785148 -0.0667369 -0.239523 -0.0796259 -0.081265 -0.239377 -0.0796987 -0.0655668 -0.238873 -0.0798 -0.0772953 -0.239002 -0.0797937 -0.0653183 -0.238873 -0.0798 0.081735 -0.239128 -0.0797748 0.0638684 -0.238873 -0.0798 0.0773679 -0.239002 -0.0797937 0.0637884 -0.239377 -0.0796987 0.0640369 -0.239999 -0.07915 0.081735 -0.188674 -0.0891743 -0.0772953 -0.212229 -0.0804257 -0.0772953 -0.185192 -0.0898 0.0773679 -0.188674 -0.0891743 0.0773679 -0.238873 -0.0208837 0.0380506 -0.238932 -0.0211638 0.0377463 -0.257673 -0.00659783 -0.0302711 -0.257673 -0.00659783 0.0287412 -0.25658 -0.0097356 0.0306869 -0.241673 -0.0142196 -0.0400497 -0.240345 -0.0133811 -0.0422329 -0.240176 -0.0157734 -0.0420521 -0.240571 -0.00821726 0.0426585 -0.240382 -0.015141 0.0397382 -0.256522 -0.0100593 0.030475 -0.255138 -0.0105938 0.0315385 -0.25503 -0.0108033 0.0312218 -0.256353 -0.0102917 0.0302095 -0.256809 -0.00984174 0.0287876 -0.257392 -0.00909661 0.0293662 -0.257673 -0.00839808 0.0278681 -0.257597 -0.00874704 0.027711 -0.257539 -0.00885401 0.0276629 -0.257319 -0.00943075 0.0291799 -0.256099 -0.0103973 0.0299312 -0.257056 -0.00924053 0.0274889 -0.257173 -0.00918777 0.0275126 -0.257115 -0.00969235 0.0289768 -0.241173 -0.0146755 0.0371885 -0.248275 -0.0126839 0.034622 -0.248381 -0.0124765 0.0349552 -0.241653 -0.0145479 0.0382611 -0.254673 -0.0107885 0.0305353 -0.247909 -0.0126387 0.0339164 -0.254867 -0.0108717 0.0308691 -0.248108 -0.0127412 0.0342555 -0.25738 -0.00904286 0.0275778 -0.240704 -0.0151491 0.0384761 -0.240662 -0.0151743 0.0383952 -0.240445 -0.0153482 0.0389898 -0.240328 -0.0154562 0.0394903 -0.240313 -0.0154867 0.0394593 -0.240863 -0.0149303 0.0387886 -0.240575 -0.0148903 0.039416 -0.240176 -0.0157734 0.0405221 -0.240899 -0.0146077 0.0390447 -0.241673 -0.0142196 0.0385198 -0.241549 -0.0147526 0.0379113 -0.241379 -0.0147977 0.0375316 -0.256673 -0.00521087 0.0155375 -0.257539 -0.00468607 0.014663 -0.257539 -0.00472513 0.015656 -0.257673 -0.00419252 0.0145829 -0.257673 -0.00461362 0.0134672 -0.257539 -0.00503699 0.0137332 -0.257673 -0.00543613 0.0126036 -0.257539 -0.00572242 0.0130135 -0.257173 -0.00508072 0.0155692 -0.257173 -0.00534691 0.0139279 -0.257539 -0.00663405 0.0126178 -0.257173 -0.00593199 0.0133136 -0.257173 -0.00671015 0.0129759 -0.257173 -0.00504738 0.0147216 -0.256673 -0.00517962 0.014743 -0.256673 -0.0060087 0.0134235 -0.240297 -0.0155509 0.0390004 -0.24019 -0.0157199 0.0402106 -0.240909 -0.0149799 0.0378073 -0.240528 -0.0151745 0.0377574 -0.240673 -0.0147873 0.0371145 -0.240466 -0.0149198 0.0370268 -0.240266 -0.0155064 0.0376723 -0.240205 -0.0157839 0.0390125 -0.240181 -0.0157807 0.0402189 -0.240175 -0.0158419 0.0402273 -0.240173 -0.0158496 0.0406064 -0.240173 -0.0158525 0.0406068 -0.240173 -0.0159033 0.0402358 -0.240173 -0.0160327 0.0390255 -0.257539 -0.00705948 0.0125274 -0.257673 -0.00653009 0.0121288 -0.257173 -0.00713558 0.0128854 -0.256673 -0.006738 0.0131069 -0.240173 -0.0155094 0.0366364 -0.240307 -0.0150925 0.0369125 -0.240249 -0.00581058 0.0153911 -0.240249 -0.00957169 0.0265254 -0.240307 -0.00569661 0.0154189 -0.240673 -0.00534102 0.0155057 -0.241173 -0.00521087 0.0155375 -0.240466 -0.00927443 0.0266553 -0.240791 -0.0090758 0.0267422 -0.256673 -0.00716343 0.0130165 -0.256925 -0.00819433 0.0126615 -0.257157 -0.00740557 0.0128283 -0.257521 -0.00736913 0.0124626 -0.256476 -0.00801094 0.0128363 -0.257254 -0.00827374 0.0122732 -0.240673 -0.00531187 0.0147645 -0.240173 -0.00616673 0.0149031 -0.240173 -0.00630709 0.0145312 -0.240307 -0.00588372 0.0142652 -0.240173 -0.00658126 0.0142433 -0.240173 -0.00694592 0.0140851 -0.240307 -0.00684196 0.013596 -0.240307 -0.00567317 0.0148231 -0.240466 -0.00549541 0.015468 -0.240673 -0.00608541 0.0135333 -0.240307 -0.00629498 0.0138334 -0.240791 -0.00528482 0.0155194 -0.240673 -0.0055738 0.0140705 -0.241173 -0.00546035 0.0139992 -0.241173 -0.0060087 0.0134235 -0.254466 -0.010133 0.0123853 -0.254817 -0.0104491 0.012183 -0.256439 -0.00886305 0.0125201 -0.256697 -0.00904068 0.0121127 -0.255173 -0.010619 0.0112711 -0.255076 -0.0106267 0.0117757 -0.240173 -0.0082739 0.0138028 -0.240466 -0.00812688 0.0131111 -0.240673 -0.00676586 0.013238 -0.240673 -0.00809384 0.0129557 -0.240791 -0.00808181 0.0128991 -0.241173 -0.006738 0.0131069 -0.25299 -0.0122152 0.0118079 -0.252845 -0.0117191 0.0120481 -0.253196 -0.0120351 0.0118459 -0.253454 -0.0122128 0.0114388 -0.252257 -0.0126119 0.011724 -0.253218 -0.0124193 0.0113956 -0.252423 -0.0129001 0.0107906 -0.252093 -0.0121819 0.0119498 -0.252377 -0.0128743 0.0113005 -0.240705 -0.00903601 0.0126965 -0.240171 -0.00905693 0.013247 -0.240249 -0.00819433 0.0134285 -0.240307 -0.00816994 0.0133137 -0.240097 -0.00912387 0.0136249 -0.239942 -0.00989307 0.0130712 -0.240385 -0.00902607 0.012921 -0.240451 -0.00996101 0.0125002 -0.239986 -0.0127493 0.011695 -0.251431 -0.0127493 0.011695 -0.239986 -0.0130319 0.0112676 -0.251431 -0.0130319 0.0112676 -0.239986 -0.0130657 0.0107563 -0.238873 -0.0126317 0.0128823 -0.23934 -0.0113762 0.013149 -0.239614 -0.0113257 0.0124332 -0.239035 -0.0126365 0.0122649 -0.239986 -0.0122921 0.0119263 -0.239532 -0.0124336 0.0119739 -0.239919 -0.0113891 0.0121966 -0.240811 -0.0100735 0.0123979 -0.240145 -0.00989763 0.0127367 -0.23941 -0.0113212 0.0127677 -0.23962 -0.0128036 0.011699 -0.239205 -0.0128861 0.0118261 -0.239308 -0.0125159 0.0120622 -0.239663 -0.0123899 0.0119442 -0.238873 -0.0129744 0.0120797 -0.239012 -0.0131072 0.0114829 -0.239527 -0.013053 0.011296 -0.238873 -0.013145 0.0112081 -0.238873 -0.0218535 0.0339948 -0.238876 -0.0215042 0.0333218 -0.239381 -0.0211743 0.0375467 -0.238928 -0.0219417 0.0362117 -0.239872 -0.0206764 0.0368977 -0.238873 -0.0218876 0.0364789 -0.239265 -0.0217083 0.0360068 -0.239722 -0.0209976 0.037239 -0.239442 -0.0213393 0.0358007 -0.239098 -0.0216205 0.0345674 -0.239042 -0.0218345 0.0347583 -0.238873 -0.0220838 0.0352383 -0.239507 -0.0208827 0.0378712 -0.239704 -0.0208128 0.0377267 -0.239035 -0.0208837 0.0380506 -0.239173 -0.0201376 0.0387967 -0.23988 -0.0199305 0.0385896 -0.239858 -0.0207017 0.0375574 -0.239916 -0.0206328 0.0374667 -0.240097 -0.0197011 0.0383602 -0.239556 -0.0200837 0.0387429 -0.239173 -0.0147851 0.0441492 -0.239673 -0.0200428 0.038702 -0.240039 -0.019784 0.0384432 -0.240039 -0.0144315 0.0437957 -0.240173 -0.0194305 0.0380896 -0.240039 -0.0131892 0.0484321 -0.239556 -0.0147313 0.0502842 -0.239673 -0.0146903 0.0503251 -0.239673 -0.0146903 0.0440545 -0.239673 -0.0135428 0.0460422 -0.239173 -0.0136722 0.0483027 -0.239673 -0.0135428 0.0483374 -0.240039 -0.0131892 0.0459474 -0.240173 -0.0127062 0.045818 -0.240173 -0.0127062 0.0485615 -0.239673 -0.02091 0.0565447 -0.23988 -0.014578 0.0504374 -0.240039 -0.0144315 0.0505839 -0.240097 -0.0205682 0.0568865 -0.240097 -0.0143486 0.0506668 -0.239173 -0.0210047 0.05645 -0.239556 -0.0209509 0.0565038 -0.239673 -0.0223485 0.0575059 -0.23988 -0.0207976 0.0566571 -0.240039 -0.0206512 0.0568035 -0.240173 -0.0202976 0.0571571 -0.240039 -0.0222084 0.0578441 -0.240039 -0.0240453 0.0582094 -0.239673 -0.0240453 0.0578434 -0.240039 -0.04487 0.0582094 -0.239173 -0.0240453 0.0577094 -0.238932 -0.0483559 0.0577094 -0.239562 -0.0466487 0.0578175 -0.239915 -0.0466736 0.0581185 -0.240095 -0.0466862 0.0585472 -0.23911 -0.046617 0.0577094 -0.239673 -0.04487 0.0578434 -0.238873 -0.0551147 0.058026 -0.239108 -0.0529419 0.0580317 -0.239664 -0.0484544 0.0580357 -0.238873 -0.0487965 0.0577094 -0.239332 -0.0484097 0.0577946 -0.248108 -0.0127412 -0.0357855 -0.25503 -0.0108033 -0.0327517 -0.248381 -0.0124765 -0.0364851 -0.248409 -0.0121532 -0.03673 -0.241549 -0.0147526 -0.0394412 -0.248275 -0.0126839 -0.0361519 -0.257003 -0.00946344 -0.0316599 -0.256465 -0.009797 -0.0323414 -0.25733 -0.0091686 -0.0310472 -0.257597 -0.00874704 -0.029241 -0.257539 -0.00885401 -0.0291928 -0.257056 -0.00924053 -0.0290188 -0.25738 -0.00904286 -0.0291078 -0.256399 -0.00991284 -0.0302902 -0.256245 -0.0103496 -0.0318558 -0.256755 -0.00990406 -0.0304484 -0.257056 -0.00975961 -0.0306477 -0.256409 -0.0101199 -0.0321271 -0.257259 -0.0095014 -0.030858 -0.254673 -0.0107885 -0.0320653 -0.254867 -0.0108717 -0.032399 -0.255998 -0.010451 -0.031569 -0.255138 -0.0105938 -0.0330684 -0.255173 -0.010276 -0.0332998 -0.240863 -0.0149303 -0.0403186 -0.24019 -0.0157199 -0.0417406 -0.240328 -0.0154562 -0.0410202 -0.241379 -0.0147977 -0.0390615 -0.240909 -0.0149799 -0.0393372 -0.240445 -0.0153482 -0.0405197 -0.240704 -0.0151491 -0.040006 -0.240382 -0.015141 -0.0412681 -0.240173 -0.0158496 -0.0421363 -0.240899 -0.0146077 -0.0405746 -0.241653 -0.0145479 -0.039791 -0.257173 -0.00918777 -0.0290425 -0.240566 -0.0152473 -0.0401723 -0.240181 -0.0157807 -0.0417489 -0.240284 -0.0155259 -0.0411188 -0.240175 -0.0158419 -0.0417573 -0.240173 -0.0159142 -0.0390977 -0.240266 -0.0155064 -0.0392022 -0.240205 -0.0157839 -0.0405425 -0.240528 -0.0151745 -0.0392874 -0.240297 -0.0155509 -0.0405303 -0.240173 -0.0159033 -0.0417657 -0.240673 -0.0147873 -0.0386445 -0.257539 -0.00572242 -0.0145435 -0.257673 -0.00461362 -0.0149971 -0.257539 -0.00503699 -0.0152631 -0.257673 -0.00419252 -0.0161129 -0.257539 -0.00468607 -0.0161929 -0.257673 -0.00423939 -0.0173045 -0.257539 -0.00472513 -0.017186 -0.257173 -0.00593199 -0.0148436 -0.256673 -0.0060087 -0.0149534 -0.256673 -0.00546035 -0.0155291 -0.257173 -0.00534691 -0.0154578 -0.257173 -0.00504738 -0.0162515 -0.257173 -0.00508072 -0.0170992 -0.241173 -0.00903463 -0.0283678 -0.240673 -0.00534102 -0.0170356 -0.240173 -0.00618235 -0.0168303 -0.241173 -0.0146755 -0.0387184 -0.240673 -0.00915733 -0.0283141 -0.240307 -0.00949256 -0.0281671 -0.240307 -0.0150925 -0.0384424 -0.240173 -0.00995049 -0.0279664 -0.257597 -0.00660966 -0.014033 -0.257539 -0.00705948 -0.0140573 -0.257539 -0.00663405 -0.0141478 -0.25738 -0.00667711 -0.0143504 -0.257173 -0.00671015 -0.0145058 -0.257056 -0.00672218 -0.0145624 -0.256673 -0.006738 -0.0146368 -0.257056 -0.00714761 -0.014472 -0.240173 -0.00658126 -0.0157733 -0.240249 -0.00578898 -0.0163718 -0.240307 -0.00569661 -0.0169488 -0.240249 -0.00636215 -0.0154595 -0.240466 -0.0061764 -0.0151936 -0.240249 -0.00598306 -0.0158575 -0.240466 -0.00570836 -0.0156849 -0.240466 -0.00549541 -0.0169979 -0.240791 -0.00605228 -0.0150158 -0.240791 -0.00552481 -0.0155696 -0.240466 -0.00546874 -0.0163198 -0.240791 -0.00525476 -0.0162851 -0.240791 -0.00528482 -0.0170493 -0.241173 -0.0060087 -0.0149534 -0.241173 -0.00521087 -0.0170674 -0.256439 -0.00886305 -0.01405 -0.256909 -0.00881018 -0.0136909 -0.256697 -0.00904068 -0.0136426 -0.257376 -0.0079876 -0.013863 -0.257673 -0.00695552 -0.0135683 -0.257597 -0.00703509 -0.0139426 -0.257504 -0.00792801 -0.0133667 -0.256087 -0.0085469 -0.0142524 -0.25738 -0.00710254 -0.0142599 -0.257031 -0.00794484 -0.0142442 -0.257173 -0.00713558 -0.0144154 -0.256623 -0.00866207 -0.0140925 -0.256235 -0.00838577 -0.0142866 -0.256673 -0.00716343 -0.0145464 -0.240249 -0.00686635 -0.0152407 -0.240466 -0.0067989 -0.0149233 -0.240466 -0.00812688 -0.0146411 -0.240791 -0.00675383 -0.0147113 -0.254466 -0.010133 -0.0139152 -0.253196 -0.0120351 -0.0133759 -0.255076 -0.0106267 -0.0133057 -0.253454 -0.0122128 -0.0129687 -0.255173 -0.010619 -0.012801 -0.253552 -0.0122051 -0.0124642 -0.254817 -0.0104491 -0.013713 -0.240097 -0.00912387 -0.0151548 -0.239872 -0.00994803 -0.0149824 -0.240171 -0.00905693 -0.014777 -0.240145 -0.00989763 -0.0142666 -0.240705 -0.00903601 -0.0142265 -0.240451 -0.00996101 -0.0140301 -0.240249 -0.00819433 -0.0149584 -0.240385 -0.00902607 -0.0144509 -0.240791 -0.00808181 -0.014429 -0.241173 -0.00806598 -0.0143546 -0.241082 -0.00908523 -0.0141379 -0.251651 -0.0122802 -0.0134588 -0.251431 -0.0122921 -0.0134563 -0.251762 -0.0130477 -0.01229 -0.252297 -0.012099 -0.0134973 -0.251706 -0.0127344 -0.0132281 -0.25267 -0.0127559 -0.0128552 -0.251747 -0.0130147 -0.0128011 -0.252512 -0.0125087 -0.0132758 -0.239574 -0.0124192 -0.0134927 -0.24028 -0.0115016 -0.0136243 -0.23941 -0.0113212 -0.0142977 -0.238947 -0.0126854 -0.0139034 -0.239614 -0.0113257 -0.0139631 -0.238873 -0.0127349 -0.0140313 -0.23934 -0.0113762 -0.014679 -0.239942 -0.00989307 -0.0146012 -0.239919 -0.0113891 -0.0137266 -0.251431 -0.0130657 -0.0122863 -0.251431 -0.0130319 -0.0127975 -0.239986 -0.0130319 -0.0127975 -0.251431 -0.0127493 -0.0132249 -0.239986 -0.0127493 -0.0132249 -0.239986 -0.0122921 -0.0134563 -0.2394 -0.0130631 -0.0128554 -0.238873 -0.0131282 -0.0131089 -0.239087 -0.0129153 -0.0134229 -0.239517 -0.0128216 -0.013247 -0.23921 -0.0125561 -0.01365 -0.238873 -0.0129286 -0.013706 -0.239986 -0.0130657 -0.0122863 -0.239173 -0.00600004 0.0574415 -0.239673 -0.00606703 0.0575575 -0.240039 -0.00500004 0.0582094 -0.240039 -0.00625004 0.0578745 -0.239673 -0.00684812 0.0567764 -0.240173 -0.00650004 0.0583075 -0.240039 -0.00716511 0.0569594 -0.240173 -0.00759812 0.0572094 -0.240173 -0.00800004 0.0557094 -0.239673 -0.00713402 0.0557094 -0.239556 -0.00707616 0.0444236 -0.239673 -0.00713402 0.0444236 -0.240039 -0.00750004 0.0557094 -0.240097 -0.00761736 0.0444236 -0.240039 -0.00750004 0.0444236 -0.23988 -0.00729294 0.0444236 -0.239173 -0.00700004 0.0444236 -0.239704 -0.00700004 0.0422106 -0.240173 -0.00800004 0.0444236 -0.240569 -0.00777355 0.0426575 -0.240397 -0.00737443 0.0425686 -0.241427 -0.00711751 0.0409694 -0.240088 -0.00709848 0.0424091 -0.24171 -0.00789817 0.0414109 -0.241621 -0.00744232 0.0412722 -0.2526 -0.00744232 0.0342274 -0.254895 -0.0070371 0.0325233 -0.253907 -0.00788156 0.0336048 -0.255173 -0.00822741 0.0327634 -0.252152 -0.00700004 0.0335288 -0.25339 -0.00696703 0.0328498 -0.252406 -0.00711751 0.0339246 -0.253627 -0.00711185 0.0332224 -0.252689 -0.00789817 0.0343661 -0.253813 -0.00744033 0.0334936 -0.257246 -0.00702637 0.0305624 -0.255074 -0.00736639 0.0327628 -0.256009 -0.00684155 0.0316661 -0.256265 -0.00713781 0.0318018 -0.255173 -0.00779113 0.0328485 -0.256423 -0.00751941 0.0318245 -0.256458 -0.00792095 0.0317303 -0.257583 -0.00699495 0.029599 -0.257539 -0.00614207 0.0289468 -0.257509 -0.00664092 0.0297476 -0.256978 -0.00610516 0.0298833 -0.257173 -0.00580842 0.0290973 -0.25738 -0.00595328 0.029032 -0.256743 -0.00644993 0.0306143 -0.256601 -0.00600533 0.0298497 -0.257045 -0.00669809 0.0306297 -0.257297 -0.0063284 0.0298474 -0.257316 -0.00738462 0.0304227 -0.256673 -0.0056863 0.0291524 -0.257056 -0.00575569 0.0291211 -0.257597 -0.006249 0.0288986 -0.257673 -0.0046906 0.0240846 -0.257056 -0.00382389 -0.0259345 -0.257056 -0.00575569 -0.0306511 -0.25738 -0.00402725 -0.0258594 -0.25738 -0.00595328 -0.0305619 -0.257597 -0.0043316 -0.0257471 -0.257597 -0.006249 -0.0304285 -0.257003 -0.00766389 -0.0325326 -0.257392 -0.00729704 -0.031769 -0.25658 -0.0079361 -0.0330898 -0.255103 -0.00798248 -0.0342888 -0.256097 -0.00694044 -0.033151 -0.254921 -0.00751917 -0.0341703 -0.255024 -0.00773885 -0.0342584 -0.25635 -0.00722327 -0.0332368 -0.256448 -0.00624899 -0.0318996 -0.25681 -0.0063723 -0.0319814 -0.257117 -0.00661488 -0.0319853 -0.25652 -0.00757279 -0.0332153 -0.257321 -0.00693968 -0.0319107 -0.254863 -0.00742297 -0.0341063 -0.248332 -0.00987293 -0.0377267 -0.255133 -0.00810823 -0.0342816 -0.24815 -0.00942168 -0.0376262 -0.240843 -0.0128302 -0.0415112 -0.241673 -0.0124045 -0.04093 -0.241589 -0.0119477 -0.0410569 -0.240717 -0.0123915 -0.0416858 -0.239402 -0.0124167 -0.0425069 -0.240066 -0.0117269 -0.0415045 -0.240436 -0.0119919 -0.0416834 -0.241408 -0.0115092 -0.0409737 -0.240039 -0.0136178 -0.0433277 -0.240202 -0.0129617 -0.0424661 -0.23988 -0.0134505 -0.0434497 -0.239859 -0.0126109 -0.0425658 -0.240173 -0.0166693 -0.046444 -0.240097 -0.0163742 -0.0466876 -0.240039 -0.0162837 -0.0467623 -0.239673 -0.0133221 -0.0435433 -0.239173 -0.0132138 -0.0436222 -0.239173 -0.0158982 -0.0470806 -0.239556 -0.0159569 -0.0470322 -0.239173 -0.0170874 -0.0491693 -0.239673 -0.0160015 -0.0469953 -0.240039 -0.0175579 -0.0490002 -0.23988 -0.016124 -0.0468942 -0.239673 -0.0172135 -0.049124 -0.239673 -0.017634 -0.0515371 -0.240173 -0.0180285 -0.048831 -0.239173 -0.0175 -0.0515371 -0.239673 -0.017634 -0.054265 -0.240039 -0.018 -0.0515371 -0.240039 -0.018 -0.054265 -0.240173 -0.0185 -0.0515371 -0.239673 -0.0173481 -0.055332 -0.240039 -0.0176651 -0.055515 -0.240173 -0.0185 -0.054265 -0.239173 -0.0165 -0.055997 -0.239673 -0.016567 -0.056113 -0.240039 -0.01675 -0.05643 -0.240173 -0.017 -0.056863 -0.239511 -0.079595 -0.0652454 -0.240173 -0.0785074 -0.0667349 -0.240173 -0.0785111 -0.0667359 -0.240122 -0.0788544 -0.06632 -0.240143 -0.0787359 -0.0662865 -0.240173 -0.0785037 -0.0667338 -0.240148 -0.0786153 -0.066254 -0.239872 -0.0788181 -0.0650571 -0.239777 -0.079253 -0.0651234 -0.240052 -0.0789569 -0.0658341 -0.239969 -0.0791819 -0.0659011 -0.239833 -0.0793772 -0.0659725 -0.240086 -0.0789691 -0.0663541 -0.238873 -0.0798 -0.0652368 -0.239337 -0.07967 -0.0650686 -0.239426 -0.0796359 -0.0651583 -0.239729 -0.0792852 -0.0650351 -0.239128 -0.0797748 -0.0653983 -0.239843 -0.0788224 -0.0649771 -0.238873 -0.0790795 -0.0624235 -0.238873 -0.0788239 -0.0623076 -0.238873 -0.0797012 -0.0639665 -0.238873 -0.0793164 -0.0627276 -0.23968 -0.0793138 -0.064944 -0.240173 -0.0785 0.0652192 -0.240148 -0.0786153 0.064724 -0.240075 -0.0787162 0.0642458 -0.240173 -0.0785111 0.065206 -0.240173 -0.0785074 0.0652049 -0.240143 -0.0787359 0.0647565 -0.240052 -0.0789569 0.0643042 -0.240122 -0.0788544 0.0647901 -0.239833 -0.0793772 0.0644425 -0.240086 -0.0789691 0.0648242 -0.239969 -0.0791819 0.0643711 -0.240173 -0.0785148 0.065207 -0.239872 -0.0788181 0.0635272 -0.239426 -0.0796359 0.0636283 -0.239511 -0.079595 0.0637154 -0.239729 -0.0792852 0.0635051 -0.239777 -0.079253 0.0635935 -0.238873 -0.0798 0.0637069 -0.239813 -0.0788239 0.0633657 -0.23968 -0.0793138 0.0634141 -0.239337 -0.07967 0.0635386 -0.218642 -0.0797265 -0.0786413 -0.219068 -0.0798 -0.0782697 -0.218423 -0.0796259 -0.081265 -0.218083 -0.0793427 -0.0791049 -0.217947 -0.07915 -0.081265 -0.217808 -0.0788 -0.079265 -0.217918 -0.0790969 -0.0792199 -0.217773 -0.0207844 -0.079265 -0.217899 -0.0202266 -0.079265 -0.218252 -0.0197767 -0.079265 -0.218764 -0.0195218 -0.079265 -0.218764 -0.0195218 -0.081265 -0.23947 -0.0237115 -0.0777199 -0.24004 -0.0242941 -0.081265 -0.239884 -0.0240493 -0.077468 -0.239669 -0.0238387 -0.081265 -0.239716 -0.0238765 -0.0776049 -0.240173 -0.0248609 -0.0767697 -0.240173 -0.0248664 0.081735 -0.2401 -0.0244354 0.0766114 -0.240173 -0.0248609 0.0762398 -0.240173 -0.0248664 0.076235 -0.239669 -0.0238387 0.081735 -0.23947 -0.0237115 0.07719 -0.239716 -0.0238765 0.077075 -0.219336 -0.0195112 0.081735 -0.218764 -0.0195218 0.078935 -0.218252 -0.0197767 0.078935 -0.217773 -0.0785 0.081735 -0.217872 -0.0789975 0.081735 -0.21805 -0.0793017 0.0788001 -0.218083 -0.0793427 0.078775 -0.218404 -0.0796145 0.0785153 -0.218503 -0.0796683 0.0784311 -0.239673 -0.0248664 -0.082131 -0.239592 -0.0245142 -0.082131 -0.239173 -0.0248664 -0.082265 -0.23992 -0.0243531 -0.081765 -0.239587 -0.0239446 -0.081765 -0.239363 -0.024234 -0.082131 -0.239143 -0.0247343 -0.082265 -0.239109 -0.0237244 -0.081765 -0.239057 -0.0246292 -0.082265 -0.219134 -0.0204906 -0.082265 -0.238934 -0.0245725 -0.082265 -0.239035 -0.0240828 -0.082131 -0.239136 -0.0235931 -0.081265 -0.239673 -0.0785 -0.082131 -0.240039 -0.0785 -0.081765 -0.240039 -0.0248664 -0.081765 -0.219235 -0.0200009 -0.082131 -0.219309 -0.0196424 -0.081765 -0.219336 -0.0195112 -0.081265 -0.218796 -0.0196519 -0.081765 -0.218252 -0.0197767 -0.081265 -0.217899 -0.0202266 -0.081265 -0.218568 -0.0201643 -0.082131 -0.218337 -0.0198805 -0.081765 -0.21802 -0.0202841 -0.081765 -0.218273 -0.0207844 -0.082131 -0.219002 -0.020493 -0.082265 -0.218883 -0.0200074 -0.082131 -0.218884 -0.0205519 -0.082265 -0.218351 -0.0204411 -0.082131 -0.218802 -0.0206557 -0.082265 -0.239792 -0.0794193 -0.081265 -0.239456 -0.0795098 -0.081765 -0.239273 -0.0791929 -0.082131 -0.239883 -0.0790831 -0.081765 -0.239566 -0.0789 -0.082131 -0.239023 -0.0787598 -0.082265 -0.239999 -0.07915 -0.081265 -0.239133 -0.07865 -0.082265 -0.217773 -0.0207844 -0.081265 -0.217907 -0.0207844 -0.081765 -0.238873 -0.0793 -0.082131 -0.238873 -0.0796661 -0.081765 -0.230373 -0.0798 -0.081265 -0.238873 -0.0798 -0.081265 -0.21849 -0.0795098 -0.081765 -0.217907 -0.0785 -0.081765 -0.218273 -0.0785 -0.082131 -0.21838 -0.0789 -0.082131 -0.218154 -0.0794193 -0.081265 -0.218063 -0.0790831 -0.081765 -0.218673 -0.0791929 -0.082131 -0.218813 -0.07865 -0.082265 -0.219073 -0.0796661 -0.081765 -0.218773 -0.0785 0.082735 -0.218796 -0.0786148 0.082735 -0.218391 -0.0785 0.0826589 -0.218442 -0.0787613 0.0826589 -0.218273 -0.0785 0.0826011 -0.217907 -0.0785 0.082235 -0.218861 -0.0787122 0.082735 -0.218143 -0.0788854 0.0824421 -0.218361 -0.0792122 0.0824421 -0.217942 -0.0789684 0.0821177 -0.218154 -0.0794193 0.081735 -0.21859 -0.0789828 0.0826589 -0.218812 -0.0791308 0.0826589 -0.218208 -0.0793655 0.0821177 -0.218576 -0.0797011 0.081735 -0.218958 -0.0787772 0.082735 -0.219073 -0.0788 0.082735 -0.219073 -0.0795071 0.0824421 -0.218688 -0.0794305 0.0824421 -0.219073 -0.0797239 0.0821177 -0.218605 -0.0796308 0.0821177 -0.218773 -0.0207844 0.082735 -0.218066 -0.0785 0.0824421 -0.217773 -0.0207844 0.081735 -0.217849 -0.0785 0.0821177 -0.219073 -0.0798 0.081735 -0.220173 -0.0798 0.081735 -0.220173 -0.0791827 0.0826589 -0.219073 -0.0791827 0.0826589 -0.218883 -0.0200074 0.0826011 -0.218884 -0.0205519 0.082735 -0.218802 -0.0206557 0.082735 -0.218568 -0.0201643 0.0826011 -0.218796 -0.0196519 0.082235 -0.21802 -0.0202841 0.082235 -0.218351 -0.0204411 0.0826011 -0.218273 -0.0207844 0.0826011 -0.218764 -0.0195218 0.081735 -0.218337 -0.0198805 0.082235 -0.218252 -0.0197767 0.081735 -0.217899 -0.0202266 0.081735 -0.217907 -0.0207844 0.082235 -0.239556 -0.0785 0.0826589 -0.239023 -0.0787598 0.082735 -0.238873 -0.0795071 0.0824421 -0.239273 -0.0791929 0.0826011 -0.239456 -0.0795098 0.082235 -0.239523 -0.0796259 0.081735 -0.239566 -0.0789 0.0826011 -0.239883 -0.0790831 0.082235 -0.239792 -0.0794193 0.081735 -0.240097 -0.0785 0.0821177 -0.240173 -0.0785 0.081735 -0.239136 -0.0235931 0.081735 -0.239109 -0.0237244 0.082235 -0.219309 -0.0196424 0.082235 -0.219235 -0.0200009 0.0826011 -0.238934 -0.0245725 0.082735 -0.240039 -0.0785 0.082235 -0.240039 -0.0248664 0.082235 -0.23988 -0.0785 0.0824421 -0.239673 -0.0248664 0.0826011 -0.239673 -0.0785 0.0826011 -0.239556 -0.0248664 0.0826589 -0.239592 -0.0245142 0.0826011 -0.23988 -0.0248664 0.0824421 -0.240097 -0.0248664 0.0821177 -0.239057 -0.0246292 0.082735 -0.239587 -0.0239446 0.082235 -0.23992 -0.0243531 0.082235 -0.24004 -0.0242941 0.081735 -0.239363 -0.024234 0.0826011 -0.239035 -0.0240828 0.0826011 0.159143 -0.0632 -0.0772953 -0.0011732 -0.0632 -0.079265 -0.0452896 -0.0632 -0.079265 -0.16149 -0.0632 -0.0772953 -0.13529 -0.0632 -0.079265 0.159143 0.0632 -0.079265 -0.13529 0.0632 -0.079265 -0.0902896 0.0632 -0.079265 0.132943 0.0632 -0.079265 0.165443 -0.014525 -0.0772953 0.165443 0.014525 -0.0772953 0.165443 0.0483 -0.079265 -0.16779 -4.19898e-08 0.0773679 -0.16779 0.0569 -0.0772953 -0.16779 0.0331 -0.0772953 -0.16779 0.014525 -0.0772953 -0.16779 -0.014525 -0.0772953 -0.16149 0.0632 0.0773679 -0.13969 0.0632 0.0773679 0.159143 0.0632 0.078935 0.132943 0.0632 0.078935 -0.13669 -0.0632 0.0773679 -0.13669 -0.0632 0.078735 -0.13529 -0.0632 0.078935 -0.13969 -0.0632 0.078735 0.0429432 -0.0632 0.078935 0.159143 -0.0632 0.0773679 -0.0452896 -0.0632 0.078935 -0.165944 0.0613547 0.0773679 -0.1639 0.0627204 0.078935 -0.1639 0.0627204 0.0773679 -0.16149 0.0632 0.078935 -0.16731 0.0593109 -0.0772953 -0.16779 0.0569 -0.079265 -0.16731 0.0593109 -0.079265 -0.1639 0.0627204 -0.0772953 -0.165944 0.0613547 -0.079265 -0.16149 0.0632 -0.0772953 0.165443 0.0569 0.0773679 0.159143 0.0632 0.0773679 0.164599 0.06005 0.078935 0.162293 0.0623559 0.0773679 0.161554 0.0627204 -0.079265 0.164964 0.0593109 -0.0772953 -0.177765 0.0898 -0.0772953 -0.14879 0.0848 0.078935 -0.16679 0.0848 0.080635 -0.16779 0.0838 0.078935 -0.16679 0.0798 0.078935 -0.14879 0.0798 0.078935 -0.14779 0.0808 0.078935 -0.14779 0.0838 0.080635 -0.148295 0.0842949 0.080935 -0.14879 0.0845 0.080935 -0.167436 0.0840678 0.080935 -0.167057 0.0844467 0.080935 -0.16749 0.0808 0.080935 -0.16714 0.0801937 0.080935 -0.16679 0.0801 0.080935 -0.16749 0.0838 0.080935 -0.0317896 0.0848 0.080635 -0.0327896 0.0838 0.078935 -0.0127896 0.0838 0.080635 -0.0321396 0.0801937 0.080935 -0.0130896 0.0808 0.080935 -0.0130896 0.0838 0.080935 -0.0323958 0.08415 0.080935 -0.0324896 0.0838 0.080935 -0.0767896 0.0848 0.080635 -0.0767896 0.0848 0.078935 -0.0767896 0.0798 0.078935 -0.0581833 0.08045 0.080935 -0.0773958 0.08415 0.080935 -0.0773958 0.08045 0.080935 -0.0771396 0.0801937 0.080935 -0.0774896 0.0838 0.080935 -0.12179 0.0848 0.080635 -0.12179 0.0848 0.078935 -0.12279 0.0808 0.080635 -0.12179 0.0798 0.078935 -0.10279 0.0808 0.078935 -0.103295 0.080305 0.080935 -0.10309 0.0808 0.080935 -0.12249 0.0808 0.080935 -0.10344 0.0844062 0.080935 -0.12214 0.0844062 0.080935 -0.12179 0.0845 0.080935 -0.122396 0.08415 0.080935 -0.12249 0.0838 0.080935 -0.10379 0.0845 0.080935 -0.122436 0.0805321 0.080935 -0.122285 0.080305 0.080935 -0.103522 0.0801532 0.080935 -0.12179 0.0801 0.080935 0.0294432 0.0798 0.078935 0.0301432 0.0808 0.080935 0.0300494 0.08045 0.080935 0.0301432 0.0838 0.080935 0.0300899 0.0840678 0.080935 0.0108369 0.08415 0.080935 0.0111753 0.0801532 0.080935 0.0107432 0.0808 0.080935 0.0754432 0.0808 0.078935 0.0754432 0.0838 0.080635 0.0744432 0.0848 0.078935 0.0554432 0.0838 0.080635 0.0564432 0.0798 0.078935 0.0744432 0.0798 0.078935 0.0744432 0.0801 0.080935 0.0557432 0.0808 0.080935 0.0564432 0.0801 0.080935 0.120443 0.0838 0.080635 0.119443 0.0848 0.078935 0.119443 0.0798 0.080635 0.120049 0.08415 0.080935 0.119793 0.0801937 0.080935 0.100837 0.08045 0.080935 0.100743 0.0808 0.080935 0.101443 0.0801 0.080935 0.100837 0.08415 0.080935 0.100743 0.0838 0.080935 0.119443 0.0845 0.080935 0.119443 0.0801 0.080935 0.146443 0.0848 0.080635 0.145443 0.0808 0.080635 0.146443 0.0798 0.078935 0.165443 0.0838 0.080635 0.164711 0.0844467 0.080935 0.165143 0.0808 0.080935 0.146093 0.0844062 0.080935 0.145837 0.08415 0.080935 0.164443 0.0845 0.080935 0.146443 0.0801 0.080935 0.145743 0.0808 0.080935 0.146175 0.0801532 0.080935 -0.167656 0.0803 0.078935 -0.167656 0.0803 0.080635 -0.16729 0.0799339 0.078935 -0.14829 0.0799339 0.078935 -0.147924 0.0803 0.078935 -0.14829 0.0799339 0.080635 -0.16679 0.0848 0.078935 -0.167713 0.0841826 0.078935 -0.14779 0.0838 0.078935 -0.148082 0.0845071 0.080635 -0.148407 0.0847238 0.078935 -0.14879 0.0848 0.080635 -0.122713 0.0804173 0.078935 -0.122497 0.0800929 0.078935 -0.122172 0.0798761 0.078935 -0.122497 0.0800929 0.080635 -0.10379 0.0798 0.078935 -0.10379 0.0798 0.080635 -0.103407 0.0798761 0.080635 -0.103407 0.0798761 0.078935 -0.103082 0.0800929 0.078935 -0.103082 0.0800929 0.080635 -0.102866 0.0804173 0.078935 -0.102866 0.0804173 0.080635 -0.12279 0.0838 0.078935 -0.122656 0.0843 0.080635 -0.10329 0.084666 0.078935 -0.10329 0.084666 0.080635 -0.10379 0.0848 0.078935 -0.0772896 0.0799339 0.080635 -0.0772896 0.0799339 0.078935 -0.0767896 0.0798 0.080635 -0.0587896 0.0798 0.080635 -0.0582896 0.0799339 0.078935 -0.0579235 0.0803 0.078935 -0.0579235 0.0803 0.080635 -0.0577896 0.0808 0.078935 -0.0776556 0.0843 0.078935 -0.0777896 0.0838 0.078935 -0.0577896 0.0838 0.080635 -0.0579235 0.0843 0.078935 -0.0582896 0.084666 0.080635 -0.0327896 0.0808 0.080635 -0.0327134 0.0804173 0.078935 -0.0324967 0.0800929 0.078935 -0.0317896 0.0798 0.078935 -0.0137896 0.0798 0.080635 -0.0132896 0.0799339 0.080635 -0.0132896 0.0799339 0.078935 -0.0129235 0.0803 0.080635 -0.0322896 0.084666 0.080635 -0.0322896 0.084666 0.078935 -0.0326556 0.0843 0.078935 -0.0326556 0.0843 0.080635 -0.0127896 0.0838 0.078935 -0.0130825 0.0845071 0.078935 -0.0128657 0.0841826 0.080635 -0.0134069 0.0847238 0.080635 -0.0134069 0.0847238 0.078935 -0.0137896 0.0848 0.078935 0.0114432 0.0848 0.080635 0.0109432 0.084666 0.078935 0.0109432 0.084666 0.080635 0.0105771 0.0843 0.080635 0.0104432 0.0808 0.080635 0.0105193 0.0804173 0.080635 0.0105193 0.0804173 0.078935 0.0107361 0.0800929 0.078935 0.0107361 0.0800929 0.080635 0.0114432 0.0798 0.080635 0.0299432 0.0799339 0.078935 0.0304432 0.0808 0.078935 0.0304432 0.0808 0.080635 0.0304432 0.0838 0.080635 0.0304432 0.0838 0.078935 0.030367 0.0841826 0.078935 0.030367 0.0841826 0.080635 0.0301503 0.0845071 0.080635 0.0298258 0.0847238 0.080635 0.0298258 0.0847238 0.078935 0.0294432 0.0848 0.078935 0.0294432 0.0848 0.080635 0.0564432 0.0848 0.080635 0.0560605 0.0847238 0.078935 0.0559432 0.084666 0.080635 0.0555771 0.0843 0.080635 0.0554432 0.0838 0.078935 0.0554432 0.0808 0.078935 0.0555771 0.0803 0.080635 0.0749432 0.0799339 0.078935 0.0744432 0.0798 0.080635 0.0753092 0.0803 0.080635 0.0754432 0.0838 0.078935 0.075367 0.0841826 0.080635 0.075367 0.0841826 0.078935 0.0751503 0.0845071 0.078935 0.0748258 0.0847238 0.078935 0.0751503 0.0845071 0.080635 0.0748258 0.0847238 0.080635 0.101443 0.0848 0.080635 0.100943 0.084666 0.080635 0.100443 0.0808 0.080635 0.100443 0.0808 0.078935 0.100577 0.0803 0.080635 0.100577 0.0803 0.078935 0.100943 0.0799339 0.078935 0.101443 0.0798 0.078935 0.120309 0.0803 0.078935 0.120309 0.0803 0.080635 0.120443 0.0808 0.078935 0.120309 0.0843 0.078935 0.145519 0.0804173 0.078935 0.145736 0.0800929 0.080635 0.14606 0.0798761 0.078935 0.164443 0.0798 0.080635 0.165309 0.0803 0.078935 0.145943 0.084666 0.078935 0.145443 0.0838 0.078935 0.16515 0.0845071 0.080635 0.16515 0.0845071 0.078935 0.164826 0.0847238 0.078935 0.164826 0.0847238 0.080635 0.164443 0.0848 0.080635 -0.167172 0.0847238 0.080635 -0.16679 0.0845 0.080935 -0.167497 0.0845071 0.080635 -0.167285 0.0842949 0.080935 -0.167713 0.0841826 0.080635 -0.16779 0.0838 0.080635 -0.14809 0.0838 0.080935 -0.147866 0.0841826 0.080635 -0.148143 0.0840678 0.080935 -0.148407 0.0847238 0.080635 -0.148522 0.0844467 0.080935 -0.16779 0.0808 0.080635 -0.14809 0.0808 0.080935 -0.16729 0.0799339 0.080635 -0.167396 0.08045 0.080935 -0.16679 0.0798 0.080635 -0.14879 0.0801 0.080935 -0.14879 0.0798 0.080635 -0.14844 0.0801937 0.080935 -0.147924 0.0803 0.080635 -0.14779 0.0808 0.080635 -0.148183 0.08045 0.080935 -0.12229 0.084666 0.080635 -0.12279 0.0838 0.080635 -0.10279 0.0838 0.080635 -0.10309 0.0838 0.080935 -0.103183 0.08415 0.080935 -0.102924 0.0843 0.080635 -0.10379 0.0848 0.080635 -0.122713 0.0804173 0.080635 -0.122057 0.0801532 0.080935 -0.122172 0.0798761 0.080635 -0.103143 0.0805321 0.080935 -0.10279 0.0808 0.080635 -0.10379 0.0801 0.080935 -0.12179 0.0798 0.080635 -0.0767896 0.0845 0.080935 -0.0587896 0.0848 0.080635 -0.0587896 0.0845 0.080935 -0.0772896 0.084666 0.080635 -0.0771396 0.0844062 0.080935 -0.0776556 0.0843 0.080635 -0.0777896 0.0838 0.080635 -0.0579235 0.0843 0.080635 -0.0581833 0.08415 0.080935 -0.0584396 0.0844062 0.080935 -0.0580896 0.0838 0.080935 -0.0777896 0.0808 0.080635 -0.0774896 0.0808 0.080935 -0.0776556 0.0803 0.080635 -0.0582896 0.0799339 0.080635 -0.0584396 0.0801937 0.080935 -0.0577896 0.0808 0.080635 -0.0580896 0.0808 0.080935 -0.0587896 0.0801 0.080935 -0.0767896 0.0801 0.080935 -0.0137896 0.0848 0.080635 -0.0137896 0.0845 0.080935 -0.0317896 0.0845 0.080935 -0.0321396 0.0844062 0.080935 -0.0327896 0.0838 0.080635 -0.0131428 0.0840678 0.080935 -0.0130825 0.0845071 0.080635 -0.0132946 0.0842949 0.080935 -0.0135217 0.0844467 0.080935 -0.0324896 0.0808 0.080935 -0.0127896 0.0808 0.080635 -0.0326556 0.0803 0.080635 -0.0323958 0.08045 0.080935 -0.0324967 0.0800929 0.080635 -0.0322896 0.0799339 0.080635 -0.0134396 0.0801937 0.080935 -0.0131833 0.08045 0.080935 -0.0137896 0.0801 0.080935 -0.0317896 0.0798 0.080635 -0.0317896 0.0801 0.080935 0.0114432 0.0845 0.080935 0.0110932 0.0844062 0.080935 0.0104432 0.0838 0.080635 0.0107432 0.0838 0.080935 0.0299381 0.0842949 0.080935 0.029711 0.0844467 0.080935 0.0294432 0.0845 0.080935 0.0107964 0.0805321 0.080935 0.0109482 0.080305 0.080935 0.0110605 0.0798761 0.080635 0.0294432 0.0801 0.080935 0.0299432 0.0799339 0.080635 0.0297932 0.0801937 0.080935 0.0303092 0.0803 0.080635 0.0294432 0.0798 0.080635 0.0114432 0.0801 0.080935 0.0744432 0.0848 0.080635 0.0564432 0.0845 0.080935 0.0560932 0.0844062 0.080935 0.0557361 0.0845071 0.080635 0.0558369 0.08415 0.080935 0.0750899 0.0840678 0.080935 0.0749381 0.0842949 0.080935 0.074711 0.0844467 0.080935 0.0744432 0.0845 0.080935 0.0557432 0.0838 0.080935 0.0751432 0.0838 0.080935 0.0754432 0.0808 0.080635 0.0554432 0.0808 0.080635 0.0559432 0.0799339 0.080635 0.0558369 0.08045 0.080935 0.0560932 0.0801937 0.080935 0.0564432 0.0798 0.080635 0.0747932 0.0801937 0.080935 0.0749432 0.0799339 0.080635 0.0750494 0.08045 0.080935 0.0751432 0.0808 0.080935 0.101443 0.0845 0.080935 0.119443 0.0848 0.080635 0.101093 0.0844062 0.080935 0.100577 0.0843 0.080635 0.100443 0.0838 0.080635 0.120143 0.0838 0.080935 0.120309 0.0843 0.080635 0.119943 0.084666 0.080635 0.119793 0.0844062 0.080935 0.120143 0.0808 0.080935 0.120443 0.0808 0.080635 0.101093 0.0801937 0.080935 0.100943 0.0799339 0.080635 0.119943 0.0799339 0.080635 0.120049 0.08045 0.080935 0.101443 0.0798 0.080635 0.146443 0.0845 0.080935 0.145943 0.084666 0.080635 0.145577 0.0843 0.080635 0.145443 0.0838 0.080635 0.165367 0.0841826 0.080635 0.16509 0.0840678 0.080935 0.164938 0.0842949 0.080935 0.145743 0.0838 0.080935 0.165143 0.0838 0.080935 0.145519 0.0804173 0.080635 0.145796 0.0805321 0.080935 0.145948 0.080305 0.080935 0.14606 0.0798761 0.080635 0.164943 0.0799339 0.080635 0.164793 0.0801937 0.080935 0.165309 0.0803 0.080635 0.165049 0.08045 0.080935 0.165443 0.0808 0.080635 0.146443 0.0798 0.080635 0.164443 0.0801 0.080935 -0.14879 0.0848 -0.080965 -0.14879 0.0848 -0.079265 -0.14779 0.0838 -0.079265 -0.16679 0.0798 -0.080965 -0.16779 0.0808 -0.080965 -0.14879 0.0845 -0.081265 -0.16714 0.0844062 -0.081265 -0.16749 0.0808 -0.081265 -0.16679 0.0845 -0.081265 -0.16679 0.0801 -0.081265 -0.14844 0.0801937 -0.081265 -0.14879 0.0801 -0.081265 -0.0317896 0.0848 -0.079265 -0.0137896 0.0848 -0.079265 -0.0127896 0.0808 -0.080965 -0.0137896 0.0798 -0.080965 -0.0317896 0.0798 -0.079265 -0.0327896 0.0808 -0.079265 -0.0135217 0.0844467 -0.081265 -0.0317896 0.0845 -0.081265 -0.0134396 0.0801937 -0.081265 -0.0137896 0.0801 -0.081265 -0.0324896 0.0808 -0.081265 -0.0767896 0.0848 -0.079265 -0.0767896 0.0798 -0.079265 -0.0777896 0.0808 -0.079265 -0.0767896 0.0845 -0.081265 -0.0580896 0.0838 -0.081265 -0.0774896 0.0808 -0.081265 -0.0771396 0.0801937 -0.081265 -0.0767896 0.0801 -0.081265 -0.0587896 0.0801 -0.081265 -0.0581833 0.08045 -0.081265 -0.12179 0.0848 -0.079265 -0.10379 0.0848 -0.079265 -0.10279 0.0838 -0.079265 -0.122057 0.0801532 -0.081265 -0.122285 0.080305 -0.081265 -0.122396 0.08415 -0.081265 -0.12249 0.0838 -0.081265 -0.10344 0.0801937 -0.081265 -0.10379 0.0801 -0.081265 -0.10309 0.0838 -0.081265 -0.12179 0.0801 -0.081265 -0.12249 0.0808 -0.081265 -0.12179 0.0845 -0.081265 0.0304432 0.0808 -0.080965 0.0304432 0.0838 -0.079265 0.0104432 0.0838 -0.080965 0.0114432 0.0848 -0.080965 0.0114432 0.0848 -0.079265 0.0294432 0.0848 -0.080965 0.0294432 0.0848 -0.079265 0.0301432 0.0838 -0.081265 0.0109482 0.080305 -0.081265 0.0301432 0.0808 -0.081265 0.0107432 0.0808 -0.081265 0.0294432 0.0845 -0.081265 0.0114432 0.0845 -0.081265 0.0754432 0.0808 -0.080965 0.0564432 0.0798 -0.080965 0.074711 0.0844467 -0.081265 0.0744432 0.0845 -0.081265 0.0558369 0.08045 -0.081265 0.0564432 0.0801 -0.081265 0.0564432 0.0845 -0.081265 0.0751432 0.0838 -0.081265 0.0747932 0.0801937 -0.081265 0.120443 0.0808 -0.079265 0.100443 0.0808 -0.079265 0.100443 0.0838 -0.080965 0.100837 0.08045 -0.081265 0.100743 0.0808 -0.081265 0.119443 0.0801 -0.081265 0.100743 0.0838 -0.081265 0.120049 0.08415 -0.081265 0.120143 0.0838 -0.081265 0.165443 0.0838 -0.079265 0.165443 0.0808 -0.080965 0.146443 0.0798 -0.080965 0.145443 0.0808 -0.079265 0.164443 0.0801 -0.081265 0.146175 0.0801532 -0.081265 0.145837 0.08415 -0.081265 0.145743 0.0838 -0.081265 0.145743 0.0808 -0.081265 0.164793 0.0801937 -0.081265 0.165143 0.0808 -0.081265 0.164443 0.0845 -0.081265 0.165143 0.0838 -0.081265 0.16509 0.0840678 -0.081265 -0.167172 0.0798761 -0.080965 -0.167497 0.0800929 -0.079265 -0.167497 0.0800929 -0.080965 -0.16779 0.0808 -0.079265 -0.14779 0.0808 -0.079265 -0.147924 0.0803 -0.079265 -0.14779 0.0808 -0.080965 -0.14829 0.0799339 -0.079265 -0.14829 0.0799339 -0.080965 -0.14879 0.0798 -0.079265 -0.16779 0.0838 -0.080965 -0.16779 0.0838 -0.079265 -0.167656 0.0843 -0.079265 -0.167656 0.0843 -0.080965 -0.16729 0.084666 -0.080965 -0.16729 0.084666 -0.079265 -0.16679 0.0848 -0.079265 -0.148407 0.0847238 -0.079265 -0.148082 0.0845071 -0.079265 -0.12179 0.0798 -0.079265 -0.122172 0.0798761 -0.079265 -0.12179 0.0798 -0.080965 -0.122172 0.0798761 -0.080965 -0.122713 0.0804173 -0.079265 -0.12279 0.0808 -0.079265 -0.122713 0.0804173 -0.080965 -0.10279 0.0808 -0.079265 -0.102924 0.0803 -0.080965 -0.102924 0.0803 -0.079265 -0.10329 0.0799339 -0.079265 -0.10379 0.0798 -0.079265 -0.122656 0.0843 -0.080965 -0.12229 0.084666 -0.079265 -0.10379 0.0848 -0.080965 -0.102924 0.0843 -0.079265 -0.0772896 0.0799339 -0.080965 -0.0776556 0.0803 -0.080965 -0.0579235 0.0803 -0.079265 -0.0579235 0.0803 -0.080965 -0.0587896 0.0798 -0.079265 -0.0777896 0.0838 -0.080965 -0.0776556 0.0843 -0.079265 -0.0772896 0.084666 -0.079265 -0.0776556 0.0843 -0.080965 -0.0582896 0.084666 -0.079265 -0.0577896 0.0838 -0.079265 -0.0321722 0.0798761 -0.079265 -0.0327134 0.0804173 -0.079265 -0.0327134 0.0804173 -0.080965 -0.0129235 0.0803 -0.079265 -0.0129235 0.0803 -0.080965 -0.0132896 0.0799339 -0.079265 -0.0137896 0.0798 -0.079265 -0.0327896 0.0838 -0.080965 -0.0326556 0.0843 -0.079265 -0.0326556 0.0843 -0.080965 -0.0322896 0.084666 -0.080965 -0.0137896 0.0848 -0.080965 -0.0134069 0.0847238 -0.080965 -0.0130825 0.0845071 -0.080965 -0.0130825 0.0845071 -0.079265 -0.0128657 0.0841826 -0.080965 -0.0127896 0.0838 -0.079265 0.0104432 0.0838 -0.079265 0.0105771 0.0843 -0.079265 0.0110605 0.0798761 -0.079265 0.0107361 0.0800929 -0.079265 0.0105193 0.0804173 -0.079265 0.0107361 0.0800929 -0.080965 0.0105193 0.0804173 -0.080965 0.0304432 0.0808 -0.079265 0.0299432 0.0799339 -0.080965 0.0299432 0.0799339 -0.079265 0.0294432 0.0798 -0.080965 0.0299432 0.084666 -0.080965 0.0301503 0.0845071 -0.079265 0.030367 0.0841826 -0.079265 0.0301503 0.0845071 -0.080965 0.0554432 0.0838 -0.080965 0.0555771 0.0843 -0.079265 0.0559432 0.084666 -0.079265 0.0559432 0.0799339 -0.079265 0.0555771 0.0803 -0.080965 0.0749432 0.0799339 -0.079265 0.0749432 0.0799339 -0.080965 0.0744432 0.0848 -0.080965 0.0751503 0.0845071 -0.079265 0.0751503 0.0845071 -0.080965 0.0754432 0.0838 -0.079265 0.0754432 0.0838 -0.080965 0.100577 0.0843 -0.079265 0.101443 0.0798 -0.080965 0.100577 0.0803 -0.079265 0.100443 0.0808 -0.080965 0.120309 0.0803 -0.079265 0.119943 0.0799339 -0.080965 0.119443 0.0848 -0.079265 0.119443 0.0848 -0.080965 0.119943 0.084666 -0.080965 0.119943 0.084666 -0.079265 0.120309 0.0843 -0.080965 0.145519 0.0804173 -0.079265 0.145519 0.0804173 -0.080965 0.165309 0.0803 -0.080965 0.164443 0.0798 -0.079265 0.145577 0.0843 -0.079265 0.145943 0.084666 -0.079265 0.146443 0.0848 -0.079265 0.146443 0.0848 -0.080965 0.164443 0.0848 -0.080965 0.164443 0.0848 -0.079265 0.165367 0.0841826 -0.080965 0.165443 0.0838 -0.080965 -0.16679 0.0848 -0.080965 -0.167396 0.08415 -0.081265 -0.148407 0.0847238 -0.080965 -0.148082 0.0845071 -0.080965 -0.148522 0.0844467 -0.081265 -0.147866 0.0841826 -0.080965 -0.148295 0.0842949 -0.081265 -0.148143 0.0840678 -0.081265 -0.16749 0.0838 -0.081265 -0.14779 0.0838 -0.080965 -0.14809 0.0838 -0.081265 -0.167057 0.0801532 -0.081265 -0.167285 0.080305 -0.081265 -0.167713 0.0804173 -0.080965 -0.167436 0.0805321 -0.081265 -0.147924 0.0803 -0.080965 -0.14809 0.0808 -0.081265 -0.148183 0.08045 -0.081265 -0.14879 0.0798 -0.080965 -0.12229 0.084666 -0.080965 -0.12214 0.0844062 -0.081265 -0.12179 0.0848 -0.080965 -0.10379 0.0845 -0.081265 -0.10344 0.0844062 -0.081265 -0.10329 0.084666 -0.080965 -0.102924 0.0843 -0.080965 -0.103183 0.08415 -0.081265 -0.10279 0.0838 -0.080965 -0.12279 0.0838 -0.080965 -0.10309 0.0808 -0.081265 -0.122497 0.0800929 -0.080965 -0.122436 0.0805321 -0.081265 -0.12279 0.0808 -0.080965 -0.10279 0.0808 -0.080965 -0.103183 0.08045 -0.081265 -0.10329 0.0799339 -0.080965 -0.10379 0.0798 -0.080965 -0.0587896 0.0845 -0.081265 -0.0774896 0.0838 -0.081265 -0.0772896 0.084666 -0.080965 -0.0773958 0.08415 -0.081265 -0.0771396 0.0844062 -0.081265 -0.0767896 0.0848 -0.080965 -0.0587896 0.0848 -0.080965 -0.0582896 0.084666 -0.080965 -0.0584396 0.0844062 -0.081265 -0.0581833 0.08415 -0.081265 -0.0579235 0.0843 -0.080965 -0.0577896 0.0838 -0.080965 -0.0767896 0.0798 -0.080965 -0.0773958 0.08045 -0.081265 -0.0777896 0.0808 -0.080965 -0.0577896 0.0808 -0.080965 -0.0580896 0.0808 -0.081265 -0.0584396 0.0801937 -0.081265 -0.0582896 0.0799339 -0.080965 -0.0587896 0.0798 -0.080965 -0.0317896 0.0848 -0.080965 -0.0137896 0.0845 -0.081265 -0.0324896 0.0838 -0.081265 -0.0323958 0.08415 -0.081265 -0.0321396 0.0844062 -0.081265 -0.0132946 0.0842949 -0.081265 -0.0131428 0.0840678 -0.081265 -0.0130896 0.0808 -0.081265 -0.0127896 0.0838 -0.080965 -0.0130896 0.0838 -0.081265 -0.0317896 0.0801 -0.081265 -0.0321722 0.0798761 -0.080965 -0.0320574 0.0801532 -0.081265 -0.0322845 0.080305 -0.081265 -0.0324967 0.0800929 -0.080965 -0.0324363 0.0805321 -0.081265 -0.0327896 0.0808 -0.080965 -0.0131833 0.08045 -0.081265 -0.0132896 0.0799339 -0.080965 -0.0317896 0.0798 -0.080965 0.0105771 0.0843 -0.080965 0.0108369 0.08415 -0.081265 0.0109432 0.084666 -0.080965 0.0110932 0.0844062 -0.081265 0.0297932 0.0844062 -0.081265 0.0300494 0.08415 -0.081265 0.0303092 0.0843 -0.080965 0.0304432 0.0838 -0.080965 0.0107432 0.0838 -0.081265 0.0114432 0.0798 -0.080965 0.0110605 0.0798761 -0.080965 0.0111753 0.0801532 -0.081265 0.0104432 0.0808 -0.080965 0.0107964 0.0805321 -0.081265 0.0303092 0.0803 -0.080965 0.0300494 0.08045 -0.081265 0.0297932 0.0801937 -0.081265 0.0294432 0.0801 -0.081265 0.0114432 0.0801 -0.081265 0.0564432 0.0848 -0.080965 0.0558369 0.08415 -0.081265 0.0555771 0.0843 -0.080965 0.0559432 0.084666 -0.080965 0.0560932 0.0844062 -0.081265 0.0748258 0.0847238 -0.080965 0.0749381 0.0842949 -0.081265 0.075367 0.0841826 -0.080965 0.0750899 0.0840678 -0.081265 0.0557432 0.0808 -0.081265 0.0557432 0.0838 -0.081265 0.0751432 0.0808 -0.081265 0.0559432 0.0799339 -0.080965 0.0560932 0.0801937 -0.081265 0.0554432 0.0808 -0.080965 0.0753092 0.0803 -0.080965 0.0750494 0.08045 -0.081265 0.0744432 0.0798 -0.080965 0.0744432 0.0801 -0.081265 0.101443 0.0845 -0.081265 0.119443 0.0845 -0.081265 0.101443 0.0848 -0.080965 0.100577 0.0843 -0.080965 0.100837 0.08415 -0.081265 0.100943 0.084666 -0.080965 0.101093 0.0844062 -0.081265 0.119793 0.0844062 -0.081265 0.120443 0.0838 -0.080965 0.120143 0.0808 -0.081265 0.100943 0.0799339 -0.080965 0.101093 0.0801937 -0.081265 0.100577 0.0803 -0.080965 0.120443 0.0808 -0.080965 0.120049 0.08045 -0.081265 0.120309 0.0803 -0.080965 0.119793 0.0801937 -0.081265 0.119443 0.0798 -0.080965 0.101443 0.0801 -0.081265 0.145443 0.0838 -0.080965 0.145577 0.0843 -0.080965 0.145943 0.084666 -0.080965 0.146093 0.0844062 -0.081265 0.146443 0.0845 -0.081265 0.164826 0.0847238 -0.080965 0.164711 0.0844467 -0.081265 0.16515 0.0845071 -0.080965 0.164938 0.0842949 -0.081265 0.145443 0.0808 -0.080965 0.146443 0.0801 -0.081265 0.14606 0.0798761 -0.080965 0.145736 0.0800929 -0.080965 0.145948 0.080305 -0.081265 0.145796 0.0805321 -0.081265 0.165049 0.08045 -0.081265 0.164943 0.0799339 -0.080965 0.164443 0.0798 -0.080965 -0.16149 -0.0632 0.078935 -0.16149 -0.0632 0.0773679 -0.16464 -0.062356 0.078935 -0.166946 -0.06005 0.078935 -0.16464 -0.062356 0.0773679 -0.166946 -0.06005 0.0773679 -0.16464 -0.062356 -0.0772953 -0.16464 -0.062356 -0.079265 -0.166946 -0.06005 -0.079265 -0.16779 -0.0569 -0.079265 0.162293 -0.062356 0.078935 0.164599 -0.06005 0.0773679 0.162293 -0.062356 -0.079265 -0.16679 -0.0848 0.078935 -0.16779 -0.0838 0.080635 -0.16679 -0.0798 0.078935 -0.14879 -0.0798 0.078935 -0.14779 -0.0838 0.078935 -0.14879 -0.0845 0.080935 -0.14879 -0.0801 0.080935 -0.148183 -0.08045 0.080935 -0.14809 -0.0808 0.080935 -0.14809 -0.0838 0.080935 -0.148183 -0.08415 0.080935 -0.14844 -0.0844063 0.080935 -0.16714 -0.0844063 0.080935 -0.16749 -0.0838 0.080935 -0.16679 -0.0845 0.080935 -0.16749 -0.0808 0.080935 -0.0137896 -0.0848 0.078935 -0.0137896 -0.0848 0.080635 -0.0317896 -0.0848 0.078935 -0.0327896 -0.0838 0.078935 -0.0327896 -0.0838 0.080635 -0.0327896 -0.0808 0.078935 -0.0317896 -0.0798 0.078935 -0.0127896 -0.0838 0.080635 -0.0130896 -0.0838 0.080935 -0.0131428 -0.0805322 0.080935 -0.0137896 -0.0801 0.080935 -0.0323958 -0.08045 0.080935 -0.0587896 -0.0848 0.078935 -0.0767896 -0.0848 0.080635 -0.0767896 -0.0798 0.080635 -0.0577896 -0.0808 0.080635 -0.0587896 -0.0801 0.080935 -0.0587896 -0.0845 0.080935 -0.0767896 -0.0845 0.080935 -0.0767896 -0.0801 0.080935 -0.0773958 -0.08045 0.080935 -0.0581833 -0.08045 0.080935 -0.0584396 -0.0801938 0.080935 -0.12179 -0.0848 0.078935 -0.10379 -0.0848 0.080635 -0.12279 -0.0838 0.080635 -0.12179 -0.0798 0.080635 -0.10379 -0.0798 0.080635 -0.12179 -0.0801 0.080935 -0.12214 -0.0844063 0.080935 -0.10344 -0.0801938 0.080935 -0.10309 -0.0808 0.080935 -0.10344 -0.0844063 0.080935 0.0294432 -0.0848 0.080635 0.0114432 -0.0848 0.078935 0.0104432 -0.0838 0.080635 0.0294432 -0.0798 0.078935 0.029711 -0.0801533 0.080935 0.0109482 -0.084295 0.080935 0.0294432 -0.0801 0.080935 0.0294432 -0.0845 0.080935 0.0108369 -0.08045 0.080935 0.0300899 -0.0805322 0.080935 0.0114432 -0.0845 0.080935 0.0301432 -0.0808 0.080935 0.0554432 -0.0808 0.078935 0.0564432 -0.0798 0.080635 0.0744432 -0.0798 0.078935 0.0557432 -0.0808 0.080935 0.0564432 -0.0801 0.080935 0.0564432 -0.0845 0.080935 0.0557964 -0.0840679 0.080935 0.0750494 -0.08045 0.080935 0.0744432 -0.0801 0.080935 0.0751432 -0.0838 0.080935 0.0744432 -0.0845 0.080935 0.120443 -0.0838 0.078935 0.101443 -0.0848 0.078935 0.100443 -0.0808 0.078935 0.100443 -0.0838 0.080635 0.119443 -0.0798 0.078935 0.101093 -0.0801938 0.080935 0.100837 -0.08045 0.080935 0.120049 -0.08045 0.080935 0.119443 -0.0801 0.080935 0.120143 -0.0838 0.080935 0.119443 -0.0845 0.080935 0.119793 -0.0844063 0.080935 0.101443 -0.0845 0.080935 0.164443 -0.0848 0.080635 0.145443 -0.0838 0.080635 0.165443 -0.0808 0.080635 0.164443 -0.0801 0.080935 0.165143 -0.0808 0.080935 0.165143 -0.0838 0.080935 0.164443 -0.0845 0.080935 0.145837 -0.08415 0.080935 0.146093 -0.0844063 0.080935 0.146443 -0.0845 0.080935 0.145743 -0.0838 0.080935 0.145743 -0.0808 0.080935 -0.16729 -0.079934 0.080635 -0.167656 -0.0803 0.080635 -0.167656 -0.0803 0.078935 -0.16779 -0.0808 0.078935 -0.14779 -0.0808 0.078935 -0.14779 -0.0808 0.080635 -0.14829 -0.079934 0.078935 -0.16729 -0.0846661 0.080635 -0.14829 -0.0846661 0.078935 -0.147924 -0.0843 0.078935 -0.14829 -0.0846661 0.080635 -0.147924 -0.0843 0.080635 -0.12229 -0.079934 0.080635 -0.122656 -0.0803 0.078935 -0.12279 -0.0808 0.078935 -0.102924 -0.0803 0.078935 -0.10379 -0.0798 0.078935 -0.12279 -0.0838 0.078935 -0.122656 -0.0843 0.080635 -0.122656 -0.0843 0.078935 -0.12229 -0.0846661 0.078935 -0.10329 -0.0846661 0.080635 -0.102924 -0.0843 0.078935 -0.0772896 -0.079934 0.078935 -0.0772896 -0.079934 0.080635 -0.0776556 -0.0803 0.078935 -0.0776556 -0.0803 0.080635 -0.0777896 -0.0808 0.078935 -0.0777896 -0.0808 0.080635 -0.0579235 -0.0803 0.078935 -0.0582896 -0.079934 0.080635 -0.0777896 -0.0838 0.080635 -0.0776556 -0.0843 0.078935 -0.0772896 -0.0846661 0.078935 -0.0767896 -0.0848 0.078935 -0.0772896 -0.0846661 0.080635 -0.0582896 -0.0846661 0.078935 -0.0582896 -0.0846661 0.080635 -0.0579235 -0.0843 0.078935 -0.0577896 -0.0838 0.078935 -0.0322896 -0.079934 0.078935 -0.0326556 -0.0803 0.080635 -0.0127896 -0.0808 0.080635 -0.0130825 -0.0800929 0.078935 -0.0134069 -0.0798762 0.078935 -0.0134069 -0.0798762 0.080635 -0.0137896 -0.0798 0.078935 -0.0137896 -0.0798 0.080635 -0.0326556 -0.0843 0.078935 -0.0322896 -0.0846661 0.078935 -0.0322896 -0.0846661 0.080635 0.0107361 -0.0845072 0.078935 0.0110605 -0.0847239 0.078935 0.0110605 -0.0847239 0.080635 0.0114432 -0.0848 0.080635 0.0304432 -0.0808 0.078935 0.030367 -0.0804174 0.078935 0.0301503 -0.0800929 0.080635 0.0298258 -0.0798762 0.080635 0.0294432 -0.0848 0.078935 0.0299432 -0.0846661 0.080635 0.0303092 -0.0843 0.080635 0.0303092 -0.0843 0.078935 0.0304432 -0.0838 0.078935 0.0554432 -0.0838 0.080635 0.0555193 -0.0841827 0.078935 0.0557361 -0.0845072 0.078935 0.0557361 -0.0845072 0.080635 0.0560605 -0.0847239 0.078935 0.0564432 -0.0848 0.078935 0.0559432 -0.079934 0.078935 0.0559432 -0.079934 0.080635 0.0555771 -0.0803 0.078935 0.0754432 -0.0808 0.078935 0.0749432 -0.079934 0.078935 0.0749432 -0.079934 0.080635 0.0744432 -0.0848 0.080635 0.0753092 -0.0843 0.080635 0.0754432 -0.0838 0.078935 0.100943 -0.0846661 0.080635 0.100943 -0.0846661 0.078935 0.101443 -0.0798 0.080635 0.100577 -0.0803 0.080635 0.120443 -0.0808 0.078935 0.120309 -0.0803 0.078935 0.120443 -0.0808 0.080635 0.120309 -0.0803 0.080635 0.119443 -0.0848 0.080635 0.119943 -0.0846661 0.078935 0.120309 -0.0843 0.078935 0.145443 -0.0808 0.078935 0.165309 -0.0803 0.078935 0.165309 -0.0803 0.080635 0.164443 -0.0798 0.078935 0.164443 -0.0798 0.080635 0.145577 -0.0843 0.078935 0.145577 -0.0843 0.080635 0.145943 -0.0846661 0.078935 0.164443 -0.0848 0.078935 0.165309 -0.0843 0.078935 0.165309 -0.0843 0.080635 0.165443 -0.0838 0.080635 -0.16679 -0.0848 0.080635 -0.14879 -0.0848 0.080635 -0.167656 -0.0843 0.080635 -0.167396 -0.08415 0.080935 -0.14779 -0.0838 0.080635 -0.16714 -0.0801938 0.080935 -0.16779 -0.0808 0.080635 -0.167396 -0.08045 0.080935 -0.147924 -0.0803 0.080635 -0.14844 -0.0801938 0.080935 -0.14829 -0.079934 0.080635 -0.14879 -0.0798 0.080635 -0.16679 -0.0801 0.080935 -0.16679 -0.0798 0.080635 -0.12179 -0.0845 0.080935 -0.122396 -0.08415 0.080935 -0.12229 -0.0846661 0.080635 -0.12179 -0.0848 0.080635 -0.10379 -0.0845 0.080935 -0.102924 -0.0843 0.080635 -0.10279 -0.0838 0.080635 -0.103183 -0.08415 0.080935 -0.10309 -0.0838 0.080935 -0.12249 -0.0838 0.080935 -0.10279 -0.0808 0.080635 -0.122656 -0.0803 0.080635 -0.12214 -0.0801938 0.080935 -0.122396 -0.08045 0.080935 -0.12279 -0.0808 0.080635 -0.12249 -0.0808 0.080935 -0.103183 -0.08045 0.080935 -0.102924 -0.0803 0.080635 -0.10329 -0.079934 0.080635 -0.10379 -0.0801 0.080935 -0.0774896 -0.0838 0.080935 -0.0776556 -0.0843 0.080635 -0.0773958 -0.08415 0.080935 -0.0771396 -0.0844063 0.080935 -0.0587896 -0.0848 0.080635 -0.0584396 -0.0844063 0.080935 -0.0579235 -0.0843 0.080635 -0.0577896 -0.0838 0.080635 -0.0581833 -0.08415 0.080935 -0.0774896 -0.0808 0.080935 -0.0580896 -0.0808 0.080935 -0.0580896 -0.0838 0.080935 -0.0771396 -0.0801938 0.080935 -0.0579235 -0.0803 0.080635 -0.0587896 -0.0798 0.080635 -0.0317896 -0.0845 0.080935 -0.0137896 -0.0845 0.080935 -0.0324896 -0.0838 0.080935 -0.0323958 -0.08415 0.080935 -0.0326556 -0.0843 0.080635 -0.0321396 -0.0844063 0.080935 -0.0317896 -0.0848 0.080635 -0.0134396 -0.0844063 0.080935 -0.0132896 -0.0846661 0.080635 -0.0129235 -0.0843 0.080635 -0.0131833 -0.08415 0.080935 -0.0324896 -0.0808 0.080935 -0.0327896 -0.0808 0.080635 -0.0322896 -0.079934 0.080635 -0.0321396 -0.0801938 0.080935 -0.0130896 -0.0808 0.080935 -0.0128657 -0.0804174 0.080635 -0.0132946 -0.0803051 0.080935 -0.0130825 -0.0800929 0.080635 -0.0135217 -0.0801533 0.080935 -0.0317896 -0.0801 0.080935 -0.0317896 -0.0798 0.080635 0.0107432 -0.0838 0.080935 0.0105193 -0.0841827 0.080635 0.0107964 -0.0840679 0.080935 0.0107361 -0.0845072 0.080635 0.0111753 -0.0844468 0.080935 0.0297932 -0.0844063 0.080935 0.0300494 -0.08415 0.080935 0.0301432 -0.0838 0.080935 0.0104432 -0.0808 0.080635 0.0304432 -0.0838 0.080635 0.0114432 -0.0801 0.080935 0.0114432 -0.0798 0.080635 0.0109432 -0.079934 0.080635 0.0105771 -0.0803 0.080635 0.0110932 -0.0801938 0.080935 0.0107432 -0.0808 0.080935 0.0304432 -0.0808 0.080635 0.030367 -0.0804174 0.080635 0.0299381 -0.0803051 0.080935 0.0294432 -0.0798 0.080635 0.0555193 -0.0841827 0.080635 0.0559482 -0.084295 0.080935 0.0560605 -0.0847239 0.080635 0.0561753 -0.0844468 0.080935 0.0564432 -0.0848 0.080635 0.0749432 -0.0846661 0.080635 0.0747932 -0.0844063 0.080935 0.0750494 -0.08415 0.080935 0.0754432 -0.0838 0.080635 0.0557432 -0.0838 0.080935 0.0751432 -0.0808 0.080935 0.0560932 -0.0801938 0.080935 0.0558369 -0.08045 0.080935 0.0555771 -0.0803 0.080635 0.0554432 -0.0808 0.080635 0.0754432 -0.0808 0.080635 0.0753092 -0.0803 0.080635 0.0747932 -0.0801938 0.080935 0.0744432 -0.0798 0.080635 0.100743 -0.0838 0.080935 0.100577 -0.0843 0.080635 0.100837 -0.08415 0.080935 0.101093 -0.0844063 0.080935 0.101443 -0.0848 0.080635 0.119943 -0.0846661 0.080635 0.120309 -0.0843 0.080635 0.120049 -0.08415 0.080935 0.100743 -0.0808 0.080935 0.100443 -0.0808 0.080635 0.120443 -0.0838 0.080635 0.100943 -0.079934 0.080635 0.120143 -0.0808 0.080935 0.119943 -0.079934 0.080635 0.119793 -0.0801938 0.080935 0.101443 -0.0801 0.080935 0.119443 -0.0798 0.080635 0.145943 -0.0846661 0.080635 0.146443 -0.0848 0.080635 0.164793 -0.0844063 0.080935 0.164943 -0.0846661 0.080635 0.165049 -0.08415 0.080935 0.146443 -0.0801 0.080935 0.145943 -0.079934 0.080635 0.146093 -0.0801938 0.080935 0.145577 -0.0803 0.080635 0.145837 -0.08045 0.080935 0.145443 -0.0808 0.080635 0.164943 -0.079934 0.080635 0.165049 -0.08045 0.080935 0.164793 -0.0801938 0.080935 0.146443 -0.0798 0.080635 -0.14879 -0.0848 -0.079265 -0.14779 -0.0838 -0.079265 -0.14879 -0.0798 -0.079265 -0.14879 -0.0798 -0.080965 -0.16779 -0.0808 -0.080965 -0.16749 -0.0808 -0.081265 -0.14844 -0.0801938 -0.081265 -0.148183 -0.08045 -0.081265 -0.14809 -0.0808 -0.081265 -0.16714 -0.0801938 -0.081265 -0.14844 -0.0844063 -0.081265 -0.0317896 -0.0848 -0.080965 -0.0137896 -0.0848 -0.080965 -0.0131833 -0.08045 -0.081265 -0.0137896 -0.0801 -0.081265 -0.0130896 -0.0808 -0.081265 -0.0323958 -0.08415 -0.081265 -0.0324896 -0.0838 -0.081265 -0.0131833 -0.08415 -0.081265 -0.0767896 -0.0848 -0.079265 -0.0767896 -0.0848 -0.080965 -0.0577896 -0.0808 -0.079265 -0.0577896 -0.0808 -0.080965 -0.0587896 -0.0798 -0.079265 -0.0767896 -0.0798 -0.079265 -0.0587896 -0.0798 -0.080965 -0.0777896 -0.0838 -0.079265 -0.0771396 -0.0801938 -0.081265 -0.0774896 -0.0808 -0.081265 -0.0581833 -0.08045 -0.081265 -0.0767896 -0.0801 -0.081265 -0.0771396 -0.0844063 -0.081265 -0.0587896 -0.0845 -0.081265 -0.0774896 -0.0838 -0.081265 -0.10279 -0.0838 -0.080965 -0.10279 -0.0808 -0.080965 -0.12179 -0.0798 -0.079265 -0.12279 -0.0808 -0.079265 -0.10344 -0.0844063 -0.081265 -0.12214 -0.0844063 -0.081265 -0.122396 -0.08415 -0.081265 -0.12214 -0.0801938 -0.081265 -0.12249 -0.0838 -0.081265 -0.10379 -0.0801 -0.081265 -0.10309 -0.0808 -0.081265 -0.10379 -0.0845 -0.081265 0.0304432 -0.0838 -0.080965 0.0294432 -0.0798 -0.080965 0.0297932 -0.0801938 -0.081265 0.0294432 -0.0801 -0.081265 0.0301432 -0.0808 -0.081265 0.0300494 -0.08045 -0.081265 0.0301432 -0.0838 -0.081265 0.0111753 -0.0844468 -0.081265 0.0294432 -0.0845 -0.081265 0.0754432 -0.0838 -0.080965 0.0744432 -0.0798 -0.080965 0.0564432 -0.0798 -0.079265 0.0554432 -0.0808 -0.080965 0.0564432 -0.0848 -0.079265 0.0564432 -0.0848 -0.080965 0.0557964 -0.0840679 -0.081265 0.0561753 -0.0844468 -0.081265 0.0744432 -0.0845 -0.081265 0.0750494 -0.08415 -0.081265 0.0747932 -0.0844063 -0.081265 0.0751432 -0.0838 -0.081265 0.0751432 -0.0808 -0.081265 0.0557432 -0.0808 -0.081265 0.0747932 -0.0801938 -0.081265 0.0564432 -0.0801 -0.081265 0.120443 -0.0808 -0.079265 0.120443 -0.0808 -0.080965 0.119443 -0.0798 -0.080965 0.101443 -0.0798 -0.080965 0.119443 -0.0848 -0.079265 0.100743 -0.0808 -0.081265 0.100743 -0.0838 -0.081265 0.120143 -0.0808 -0.081265 0.100948 -0.0803051 -0.081265 0.164443 -0.0848 -0.079265 0.146443 -0.0848 -0.080965 0.164443 -0.0798 -0.079265 0.146443 -0.0798 -0.079265 0.164443 -0.0798 -0.080965 0.145443 -0.0838 -0.079265 0.145743 -0.0838 -0.081265 0.164443 -0.0845 -0.081265 0.165049 -0.08045 -0.081265 0.145743 -0.0808 -0.081265 0.146093 -0.0801938 -0.081265 0.165143 -0.0808 -0.081265 -0.167656 -0.0803 -0.079265 -0.167656 -0.0803 -0.080965 -0.16679 -0.0798 -0.079265 -0.147924 -0.0803 -0.079265 -0.16679 -0.0848 -0.080965 -0.16729 -0.0846661 -0.079265 -0.167656 -0.0843 -0.079265 -0.16779 -0.0838 -0.079265 -0.16779 -0.0838 -0.080965 -0.14779 -0.0838 -0.080965 -0.14829 -0.0846661 -0.080965 -0.122656 -0.0803 -0.079265 -0.122656 -0.0803 -0.080965 -0.12229 -0.079934 -0.079265 -0.12229 -0.079934 -0.080965 -0.102924 -0.0803 -0.079265 -0.102924 -0.0803 -0.080965 -0.12179 -0.0848 -0.080965 -0.12179 -0.0848 -0.079265 -0.12229 -0.0846661 -0.079265 -0.122656 -0.0843 -0.079265 -0.122656 -0.0843 -0.080965 -0.12279 -0.0838 -0.079265 -0.12279 -0.0838 -0.080965 -0.10279 -0.0838 -0.079265 -0.102924 -0.0843 -0.079265 -0.102924 -0.0843 -0.080965 -0.10329 -0.0846661 -0.079265 -0.10379 -0.0848 -0.079265 -0.10379 -0.0848 -0.080965 -0.0776556 -0.0803 -0.079265 -0.0776556 -0.0803 -0.080965 -0.0772896 -0.079934 -0.079265 -0.0582896 -0.079934 -0.079265 -0.0579235 -0.0803 -0.080965 -0.0579235 -0.0803 -0.079265 -0.0772896 -0.0846661 -0.079265 -0.0772896 -0.0846661 -0.080965 -0.0776556 -0.0843 -0.080965 -0.0777896 -0.0838 -0.080965 -0.0577896 -0.0838 -0.079265 -0.0579235 -0.0843 -0.080965 -0.0578657 -0.0841827 -0.079265 -0.0580825 -0.0845072 -0.079265 -0.0327896 -0.0808 -0.080965 -0.0326556 -0.0803 -0.079265 -0.0322896 -0.079934 -0.080965 -0.0137896 -0.0798 -0.080965 -0.0134069 -0.0798762 -0.079265 -0.0130825 -0.0800929 -0.079265 -0.0132896 -0.079934 -0.080965 -0.0129235 -0.0803 -0.080965 -0.0127896 -0.0808 -0.080965 -0.0317896 -0.0848 -0.079265 -0.0322896 -0.0846661 -0.079265 -0.0326556 -0.0843 -0.080965 -0.0327896 -0.0838 -0.079265 -0.0127896 -0.0838 -0.079265 -0.0129235 -0.0843 -0.079265 -0.0132896 -0.0846661 -0.079265 -0.0137896 -0.0848 -0.079265 0.0114432 -0.0848 -0.080965 0.0107361 -0.0845072 -0.079265 0.0107361 -0.0845072 -0.080965 0.0104432 -0.0838 -0.079265 0.0104432 -0.0838 -0.080965 0.0104432 -0.0808 -0.080965 0.0104432 -0.0808 -0.079265 0.0105771 -0.0803 -0.079265 0.0109432 -0.079934 -0.079265 0.0114432 -0.0798 -0.080965 0.0303092 -0.0803 -0.079265 0.0304432 -0.0808 -0.080965 0.030367 -0.0841827 -0.079265 0.0301503 -0.0845072 -0.080965 0.0301503 -0.0845072 -0.079265 0.0298258 -0.0847239 -0.079265 0.0294432 -0.0848 -0.079265 0.0298258 -0.0847239 -0.080965 0.0294432 -0.0848 -0.080965 0.0560605 -0.0847239 -0.079265 0.0557361 -0.0845072 -0.079265 0.0555193 -0.0841827 -0.079265 0.0555193 -0.0841827 -0.080965 0.0555771 -0.0803 -0.079265 0.0555771 -0.0803 -0.080965 0.0744432 -0.0798 -0.079265 0.0749432 -0.079934 -0.080965 0.0753092 -0.0803 -0.080965 0.0753092 -0.0843 -0.079265 0.0744432 -0.0848 -0.079265 0.101443 -0.0848 -0.080965 0.100943 -0.0846661 -0.079265 0.100943 -0.0846661 -0.080965 0.100577 -0.0843 -0.080965 0.100443 -0.0838 -0.079265 0.100443 -0.0808 -0.080965 0.100519 -0.0804174 -0.080965 0.100736 -0.0800929 -0.080965 0.10106 -0.0798762 -0.080965 0.101443 -0.0798 -0.079265 0.119443 -0.0798 -0.079265 0.119943 -0.079934 -0.080965 0.120309 -0.0803 -0.080965 0.120443 -0.0838 -0.080965 0.120309 -0.0843 -0.079265 0.119943 -0.0846661 -0.080965 0.145943 -0.079934 -0.079265 0.145577 -0.0803 -0.080965 0.145943 -0.079934 -0.080965 0.164943 -0.079934 -0.080965 0.165309 -0.0803 -0.079265 0.165309 -0.0803 -0.080965 0.145577 -0.0843 -0.080965 0.165367 -0.0841827 -0.080965 0.16515 -0.0845072 -0.080965 0.164826 -0.0847239 -0.079265 -0.14879 -0.0848 -0.080965 -0.16679 -0.0845 -0.081265 -0.16729 -0.0846661 -0.080965 -0.16714 -0.0844063 -0.081265 -0.167396 -0.08415 -0.081265 -0.167656 -0.0843 -0.080965 -0.147924 -0.0843 -0.080965 -0.148183 -0.08415 -0.081265 -0.14879 -0.0845 -0.081265 -0.16749 -0.0838 -0.081265 -0.14779 -0.0808 -0.080965 -0.14809 -0.0838 -0.081265 -0.167396 -0.08045 -0.081265 -0.16729 -0.079934 -0.080965 -0.16679 -0.0801 -0.081265 -0.14879 -0.0801 -0.081265 -0.14829 -0.079934 -0.080965 -0.147924 -0.0803 -0.080965 -0.16679 -0.0798 -0.080965 -0.12229 -0.0846661 -0.080965 -0.12179 -0.0845 -0.081265 -0.10309 -0.0838 -0.081265 -0.103183 -0.08415 -0.081265 -0.10329 -0.0846661 -0.080965 -0.12279 -0.0808 -0.080965 -0.12249 -0.0808 -0.081265 -0.122396 -0.08045 -0.081265 -0.12179 -0.0801 -0.081265 -0.10379 -0.0798 -0.080965 -0.10329 -0.079934 -0.080965 -0.10344 -0.0801938 -0.081265 -0.103183 -0.08045 -0.081265 -0.12179 -0.0798 -0.080965 -0.0767896 -0.0845 -0.081265 -0.0773958 -0.08415 -0.081265 -0.0577896 -0.0838 -0.080965 -0.0580896 -0.0838 -0.081265 -0.0581833 -0.08415 -0.081265 -0.0580825 -0.0845072 -0.080965 -0.0582896 -0.0846661 -0.080965 -0.0584396 -0.0844063 -0.081265 -0.0587896 -0.0848 -0.080965 -0.0580896 -0.0808 -0.081265 -0.0777896 -0.0808 -0.080965 -0.0773958 -0.08045 -0.081265 -0.0772896 -0.079934 -0.080965 -0.0767896 -0.0798 -0.080965 -0.0587896 -0.0801 -0.081265 -0.0582896 -0.079934 -0.080965 -0.0584396 -0.0801938 -0.081265 -0.0317896 -0.0845 -0.081265 -0.0137896 -0.0845 -0.081265 -0.0322896 -0.0846661 -0.080965 -0.0321396 -0.0844063 -0.081265 -0.0327896 -0.0838 -0.080965 -0.0130896 -0.0838 -0.081265 -0.0129235 -0.0843 -0.080965 -0.0132896 -0.0846661 -0.080965 -0.0134396 -0.0844063 -0.081265 -0.0127896 -0.0838 -0.080965 -0.0324896 -0.0808 -0.081265 -0.0326556 -0.0803 -0.080965 -0.0323958 -0.08045 -0.081265 -0.0321396 -0.0801938 -0.081265 -0.0317896 -0.0798 -0.080965 -0.0317896 -0.0801 -0.081265 -0.0134396 -0.0801938 -0.081265 -0.0130825 -0.0800929 -0.080965 0.0114432 -0.0845 -0.081265 0.0110605 -0.0847239 -0.080965 0.0109482 -0.084295 -0.081265 0.0107964 -0.0840679 -0.081265 0.0105193 -0.0841827 -0.080965 0.0300899 -0.0840679 -0.081265 0.030367 -0.0841827 -0.080965 0.0299381 -0.084295 -0.081265 0.029711 -0.0844468 -0.081265 0.0107432 -0.0838 -0.081265 0.0107432 -0.0808 -0.081265 0.0105771 -0.0803 -0.080965 0.0108369 -0.08045 -0.081265 0.0109432 -0.079934 -0.080965 0.0110932 -0.0801938 -0.081265 0.0299432 -0.079934 -0.080965 0.0303092 -0.0803 -0.080965 0.0114432 -0.0801 -0.081265 0.0564432 -0.0845 -0.081265 0.0744432 -0.0848 -0.080965 0.0560605 -0.0847239 -0.080965 0.0557361 -0.0845072 -0.080965 0.0559482 -0.084295 -0.081265 0.0753092 -0.0843 -0.080965 0.0749432 -0.0846661 -0.080965 0.0554432 -0.0838 -0.080965 0.0557432 -0.0838 -0.081265 0.0754432 -0.0808 -0.080965 0.0558369 -0.08045 -0.081265 0.0559432 -0.079934 -0.080965 0.0560932 -0.0801938 -0.081265 0.0750494 -0.08045 -0.081265 0.0564432 -0.0798 -0.080965 0.0744432 -0.0801 -0.081265 0.119443 -0.0845 -0.081265 0.101443 -0.0845 -0.081265 0.101093 -0.0844063 -0.081265 0.100837 -0.08415 -0.081265 0.120309 -0.0843 -0.080965 0.120049 -0.08415 -0.081265 0.119793 -0.0844063 -0.081265 0.119443 -0.0848 -0.080965 0.100443 -0.0838 -0.080965 0.120143 -0.0838 -0.081265 0.100796 -0.0805322 -0.081265 0.101175 -0.0801533 -0.081265 0.119793 -0.0801938 -0.081265 0.120049 -0.08045 -0.081265 0.119443 -0.0801 -0.081265 0.101443 -0.0801 -0.081265 0.146443 -0.0845 -0.081265 0.145943 -0.0846661 -0.080965 0.146093 -0.0844063 -0.081265 0.145837 -0.08415 -0.081265 0.145443 -0.0838 -0.080965 0.165143 -0.0838 -0.081265 0.165443 -0.0838 -0.080965 0.16509 -0.0840679 -0.081265 0.164938 -0.084295 -0.081265 0.164711 -0.0844468 -0.081265 0.164826 -0.0847239 -0.080965 0.164443 -0.0848 -0.080965 0.145443 -0.0808 -0.080965 0.145837 -0.08045 -0.081265 0.146443 -0.0798 -0.080965 0.146443 -0.0801 -0.081265 0.164443 -0.0801 -0.081265 0.164793 -0.0801938 -0.081265 0.165443 -0.0808 -0.080965 -0.13969 0.0632 0.078735 -0.13969 -4.19898e-08 0.0773679 -0.13669 -0.048 0.0773679 -0.13669 -4.19898e-08 0.0773679 -0.13669 0.0632 0.078735 -0.218256 -0.0795112 -0.078968 -0.218404 -0.0796145 -0.0788452 -0.215711 -0.0797239 -0.0786477 -0.215711 -0.0788 -0.079265 -0.215711 -0.0791827 -0.0791889 -0.215711 -0.0795071 -0.0789721 -0.212127 -0.0801512 -0.0789721 -0.212182 -0.0803002 -0.078765 -0.212203 -0.0803544 -0.0786477 -0.215711 -0.0798 -0.078265 -0.212014 -0.0798471 -0.0791889 -0.212055 -0.079957 -0.079131 -0.188674 -0.0891743 -0.078265 -0.212229 -0.0804257 -0.078265 -0.185192 -0.0898 -0.078265 -0.188628 -0.0890488 -0.078765 -0.1885 -0.0887056 -0.079131 0.182846 -0.0896661 -0.078765 0.182846 -0.0897239 -0.0786477 -0.185192 -0.0888 -0.079265 -0.17819 -0.0888 -0.079265 -0.185192 -0.0893 -0.079131 -0.13529 -0.0888 -0.079265 -0.0452896 -0.0888 -0.079265 -0.0011732 -0.0888 -0.079265 -0.185192 -0.0896661 -0.078765 0.182846 -0.0895071 -0.0789721 0.182846 -0.0893 -0.079131 0.175843 -0.0888 -0.079265 0.182846 -0.0891827 -0.0791889 0.186301 -0.089103 -0.0786477 0.182846 -0.0898 -0.078265 0.186281 -0.0890488 -0.078765 0.186226 -0.0888998 -0.0789721 0.186154 -0.0887056 -0.079131 0.186113 -0.0885957 -0.0791889 0.209668 -0.0798471 -0.0791889 0.186328 -0.0891743 -0.078265 0.209709 -0.079957 -0.079131 0.209781 -0.0801512 -0.0789721 0.209856 -0.0803544 -0.0786477 0.213364 -0.0797239 -0.0786477 0.209836 -0.0803002 -0.078765 0.213364 -0.0798 -0.078265 0.216721 -0.0798 -0.0782697 0.216727 -0.0798 -0.078265 0.215572 -0.0790969 -0.0792199 0.213364 -0.0795071 -0.0789721 0.21591 -0.0795112 -0.078968 0.216057 -0.0796145 -0.0788452 0.213364 -0.0791827 -0.0791889 -0.215711 0.079666 -0.078765 -0.218642 0.0797264 -0.0786413 -0.219068 0.0798 -0.0782697 -0.217918 0.0790968 -0.0792199 -0.215711 0.0788 -0.079265 -0.217808 0.0788 -0.079265 -0.215711 0.0793 -0.079131 -0.215711 0.0795071 -0.0789721 -0.212182 0.0803001 -0.078765 -0.188628 0.0890487 -0.078765 -0.212055 0.0799569 -0.079131 -0.188674 0.0891743 -0.078265 -0.185192 0.0897238 -0.0786477 -0.185192 0.089666 -0.078765 -0.185192 0.0888 -0.079265 -0.188326 0.0882368 -0.079265 -0.1885 0.0887055 -0.079131 -0.185192 0.0893 -0.079131 0.132943 0.0888 -0.079265 -0.185192 0.0891826 -0.0791889 0.182846 0.0893 -0.079131 0.182846 0.0895071 -0.0789721 -0.185192 0.0895071 -0.0789721 0.182846 0.089666 -0.078765 0.182846 0.0897238 -0.0786477 -0.185192 0.0898 -0.078265 0.182846 0.0898 -0.078265 0.186154 0.0887055 -0.079131 0.182846 0.0891826 -0.0791889 0.18598 0.0882368 -0.079265 0.182846 0.0888 -0.079265 0.209709 0.0799569 -0.079131 0.209836 0.0803001 -0.078765 0.186281 0.0890487 -0.078765 0.209535 0.0794882 -0.079265 0.213364 0.0793 -0.079131 0.215737 0.0793426 -0.0791049 0.213364 0.0795071 -0.0789721 0.213364 0.079666 -0.078765 0.216296 0.0797264 -0.0786413 -0.218083 0.0793426 0.078775 -0.215711 0.0795071 0.0786421 -0.217918 0.0790968 0.07889 -0.218256 0.0795111 0.0786381 -0.218642 0.0797264 0.0783114 -0.215711 0.0798 0.077935 -0.219073 0.0798 0.077935 -0.219068 0.0798 0.0779398 -0.212182 0.0803001 0.078435 -0.215711 0.079666 0.078435 -0.215711 0.0793 0.0788011 -0.215711 0.0788 0.078935 -0.188648 0.0891029 0.0783177 -0.188572 0.0888997 0.0786421 -0.212055 0.0799569 0.0788011 -0.188459 0.0885956 0.0788589 -0.1885 0.0887055 0.0788011 -0.185192 0.0895071 0.0786421 -0.185192 0.0897238 0.0783177 -0.188628 0.0890487 0.078435 -0.188674 0.0891743 0.077935 -0.185192 0.0891826 0.0788589 0.182846 0.0893 0.0788011 0.182846 0.089666 0.078435 0.182846 0.0895071 0.0786421 0.186281 0.0890487 0.078435 0.18598 0.0882368 0.078935 0.209668 0.079847 0.0788589 0.209709 0.0799569 0.0788011 0.209781 0.0801511 0.0786421 0.186154 0.0887055 0.0788011 0.209856 0.0803543 0.0783177 0.213364 0.079666 0.078435 0.209836 0.0803001 0.078435 0.213364 0.0791826 0.0788589 0.216157 0.0796682 0.0784311 0.213364 0.0798 0.077935 0.213364 0.0797238 0.0783177 0.213364 0.0793 0.0788011 0.215703 0.0793016 0.0788001 0.213364 0.0795071 0.0786421 0.216057 0.0796144 0.0785153 0.213364 -0.0793 0.0788011 0.215572 -0.0790969 0.07889 0.213364 -0.0795071 0.0786421 0.216057 -0.0796145 0.0785153 0.216721 -0.0798 0.0779398 0.209836 -0.0803002 0.078435 0.213364 -0.0796661 0.078435 0.209709 -0.079957 0.0788011 0.186328 -0.0891743 0.077935 0.209883 -0.0804257 0.077935 0.186281 -0.0890488 0.078435 0.186154 -0.0887056 0.0788011 0.182846 -0.0896661 0.078435 0.182846 -0.0893 0.0788011 0.182846 -0.0888 0.078935 0.0879432 -0.0888 0.078935 -0.185192 -0.0898 0.077935 -0.185192 -0.0893 0.0788011 -0.0011732 -0.0888 0.078935 -0.0452896 -0.0888 0.078935 -0.0902896 -0.0888 0.078935 -0.13529 -0.0888 0.078935 -0.185192 -0.0888 0.078935 -0.1885 -0.0887056 0.0788011 -0.188648 -0.089103 0.0783177 -0.185192 -0.0896661 0.078435 -0.188459 -0.0885957 0.0788589 -0.212014 -0.0798471 0.0788589 -0.188572 -0.0888998 0.0786421 -0.188628 -0.0890488 0.078435 -0.212203 -0.0803544 0.0783177 -0.188674 -0.0891743 0.077935 -0.212229 -0.0804257 0.077935 -0.212182 -0.0803002 0.078435 -0.212127 -0.0801512 0.0786421 -0.215711 -0.0788 0.078935 -0.212055 -0.079957 0.0788011 -0.211881 -0.0794883 0.078935 -0.215711 -0.0798 0.077935 -0.219068 -0.0798 0.0779398 -0.217808 -0.0788 0.078935 -0.217918 -0.0790969 0.07889 -0.215711 -0.0793 0.0788011 -0.215711 -0.0796661 0.078435 -0.220173 -0.0797239 0.0821177 -0.220173 -0.0795071 0.0824421 -0.220173 -0.0798 0.082735 -0.230373 -0.0795071 0.0824421 -0.230373 -0.0798 0.082735 -0.230373 0.0798 0.081735 -0.230373 0.0798 0.082735 -0.230373 0.0791826 0.0826589 -0.220173 0.0797238 0.0821177 -0.220173 0.0791826 0.0826589 0.228027 -0.0796661 0.082235 0.228027 -0.0793 0.0826011 0.228027 -0.0798 0.082735 0.217827 -0.0798 0.082735 0.217827 0.079666 0.082235 0.217827 0.0793 0.0826011 0.217827 0.0798 0.082735 0.228027 0.079666 -0.081765 0.228027 0.0788 -0.082265 0.217827 0.0798 -0.082265 0.217827 0.0798 -0.081265 0.217827 -0.0796661 -0.081765 0.228027 -0.0788 -0.082265 0.228027 -0.0793 -0.082131 0.228027 -0.0796661 -0.081765 0.228027 -0.0798 -0.081265 -0.230373 0.0798 -0.082265 -0.230373 0.0793 -0.082131 -0.230373 0.079666 -0.081765 -0.230373 0.0798 -0.081265 -0.220173 0.0798 -0.081265 -0.220173 0.079666 -0.081765 -0.230373 -0.0796661 -0.081765 -0.230373 -0.0793 -0.082131 -0.220173 -0.0793 -0.082131 -0.438473 -0.031 -0.082265 -0.454072 -0.031 -0.082265 -0.451241 -0.02325 -0.082265 -0.451559 -0.0269044 -0.082265 -0.441701 -0.0187016 -0.082265 -0.445175 -0.0152283 -0.082265 -0.451241 -0.00400004 -0.082265 -0.451241 -0.00273209 -0.082265 -0.448173 -0.00600004 -0.082265 -0.448173 -4.19898e-08 -0.082265 -0.447405 0.0108515 -0.082265 -0.463326 0.00535773 -0.082265 -0.463973 0.0179683 -0.082265 -0.445175 0.0152282 -0.082265 -0.459738 0.00599658 -0.082265 -0.457719 0.0057163 -0.082265 -0.45662 0.00535773 -0.082265 -0.45611 0.0178758 -0.082265 -0.454348 0.00399129 -0.082265 -0.453775 0.00346653 -0.082265 -0.454334 0.0195578 -0.082265 -0.455012 0.0187708 -0.082265 -0.453078 0.0273756 -0.082265 -0.441701 0.0187015 -0.082265 -0.453018 0.0268765 -0.082265 -0.452991 0.025 -0.082265 -0.453212 0.0219427 -0.082265 -0.468401 -0.000725102 -0.0821497 -0.478038 -0.0156505 -0.0776603 -0.468626 -0.00400004 -0.0821278 -0.469996 -4.35158e-08 -0.0819699 -0.465858 -0.0309974 -0.0822501 -0.469549 -0.0309656 -0.0818033 -0.467979 -0.0277725 -0.0821103 -0.468267 -0.0268513 -0.0820773 -0.468579 -0.0244259 -0.082047 -0.476141 -0.0308226 -0.0783047 -0.469881 -0.0155652 -0.0819031 -0.47745 -4.46233e-08 -0.0787044 -0.477642 -0.00787838 -0.0784019 -0.476766 -0.015568 -0.0787748 -0.473518 -0.0155618 -0.0807781 -0.46861 -0.0136251 -0.0821004 -0.468211 -4.19545e-08 -0.0821642 -0.46742 0.00180743 -0.0822112 -0.466927 0.0025593 -0.0822314 -0.463973 0.00506396 -0.082265 -0.465143 0.0189918 -0.0822623 -0.468699 0.015561 -0.0820813 -0.465617 0.0195748 -0.0822573 -0.466449 0.0211119 -0.082237 -0.466924 0.025 -0.082211 -0.468448 0.0309822 -0.082029 -0.466891 0.0269088 -0.0822102 -0.466144 0.0295617 -0.0822422 -0.46515 0.0309987 -0.0822615 -0.476938 -3.71996e-08 -0.0791082 -0.476461 0.0155662 -0.0790117 -0.474698 0.0155613 -0.0801772 -0.473682 -4.28748e-08 -0.0809799 -0.470821 0.0155657 -0.0817034 -0.472818 0.0155627 -0.0810748 -0.476408 0.0308169 -0.0780706 -0.454362 -0.0312529 -0.0822649 -0.45795 -0.0330059 -0.0822497 -0.459973 -0.0332291 -0.082244 -0.462258 -0.0329442 -0.082251 -0.463973 -0.0343661 -0.0821934 -0.440922 -0.0390776 -0.0813473 -0.440274 -0.0371225 -0.0818501 -0.463973 -0.0427491 -0.0796722 -0.44159 -0.0431081 -0.0794518 -0.441676 -0.0448903 -0.0781951 -0.463973 -0.0451168 -0.078015 -0.441781 -0.0473465 -0.075975 -0.441806 -0.0478065 -0.0754883 -0.463984 -0.0498878 -0.0729478 -0.442063 -0.0513711 -0.0707145 -0.464027 -0.0518952 -0.0698117 -0.442348 -0.0537617 -0.0658355 -0.443504 -0.0558475 -0.0552832 -0.464453 -0.05557 -0.0585609 -0.442931 -0.0554326 -0.0595495 -0.442543 -0.0545995 -0.0633443 -0.467455 -0.0339193 -0.0820567 -0.475836 -0.0452414 -0.0723422 -0.463971 -0.0476197 -0.0756882 -0.464127 -0.0536663 -0.0660792 -0.466919 -0.0538194 -0.0653223 -0.46694 -0.054812 -0.0620307 -0.464269 -0.0548866 -0.0622714 -0.466829 -0.0557642 -0.0549696 -0.466864 -0.0554413 -0.0586037 -0.464732 -0.0559262 -0.0536123 -0.467122 -0.0565955 -0.037799 -0.468547 -0.0561643 -0.0446484 -0.466902 -0.0561539 -0.0472719 -0.4751 -0.051766 -0.0621504 -0.473795 -0.0533121 -0.0591727 -0.478547 -0.041228 -0.0722201 -0.476912 -0.0329073 -0.0774031 -0.464653 -0.0319256 -0.0822618 -0.465328 -0.0367779 -0.0818852 -0.466765 -0.0448237 -0.0780787 -0.478896 -0.0346084 -0.0748442 -0.47805 -0.0356904 -0.0755844 -0.478817 -0.0379631 -0.0737585 -0.47607 -0.038245 -0.0768253 -0.474909 -0.0354339 -0.0787045 -0.473528 -0.0322205 -0.0801142 -0.473006 -0.0308924 -0.0804755 -0.469635 -0.0311486 -0.0817802 -0.471404 -0.0347398 -0.0809268 -0.470773 -0.040248 -0.0796984 -0.474024 -0.0406556 -0.0775306 -0.472934 -0.0453059 -0.0751377 -0.474271 -0.049189 -0.0691165 -0.476518 -0.047069 -0.0692379 -0.477934 -0.0428431 -0.071827 -0.477071 -0.0407023 -0.0745181 -0.475015 -0.0431031 -0.0751258 -0.472837 -0.0378831 -0.0794901 -0.469287 -0.0372788 -0.0812011 -0.472831 -0.0540305 -0.0577065 -0.469929 -0.0551199 -0.0565857 -0.469791 -0.0546195 -0.0602819 -0.472552 -0.0533657 -0.0614516 -0.472276 -0.0523825 -0.0650258 -0.469523 -0.0525879 -0.0671363 -0.471492 -0.049334 -0.0715901 -0.469206 -0.0510363 -0.0702982 -0.468672 -0.0491908 -0.0732208 -0.468781 -0.042543 -0.0792378 -0.465283 -0.0423436 -0.0798764 -0.463973 -0.0400285 -0.0810099 -0.470879 -0.0552745 -0.0525729 -0.469686 -0.0537921 -0.0637913 -0.46673 -0.0524914 -0.0684469 -0.466319 -0.0508832 -0.0713499 -0.467873 -0.0471052 -0.0758395 -0.46564 -0.0490554 -0.0739703 -0.463975 -0.046113 -0.0771653 -0.464652 -0.0470519 -0.0762638 -0.47632 -0.0496458 -0.0651816 -0.474744 -0.0506342 -0.065718 -0.471947 -0.0510338 -0.0684143 -0.473685 -0.0474048 -0.0722743 -0.470847 -0.0473245 -0.0745021 -0.471975 -0.0429162 -0.0776408 -0.469956 -0.0450502 -0.0770809 -0.467263 -0.0398036 -0.0808739 -0.463973 -0.0372881 -0.0818168 -0.463973 0.0136726 -0.085765 -0.462157 0.00971399 -0.085765 -0.45798 0.0130311 -0.085765 -0.454848 0.014276 -0.085765 -0.444668 0.0110514 -0.085765 -0.453753 0.0150776 -0.085765 -0.450999 0.031 -0.085765 -0.438473 0.031 -0.085765 -0.438473 0.0177575 -0.085765 -0.451723 0.0174816 -0.085765 -0.441807 0.0153338 -0.085765 -0.450393 0.0224641 -0.085765 -0.450393 0.025 -0.085765 -0.450393 0.0275359 -0.085765 -0.445673 0.00599996 -0.085765 -0.449554 0.00310027 -0.085765 -0.450595 0.0050033 -0.085765 -0.451639 0.0063162 -0.085765 -0.45326 0.00776065 -0.085765 -0.456618 0.00943135 -0.085765 -0.44542 0.00857515 -0.085765 -0.458201 0.009783 -0.085765 -0.470727 0.00188127 -0.0853968 -0.471123 -4.19898e-08 -0.0853316 -0.468883 0.0189161 -0.0855679 -0.469114 0.0155781 -0.0855566 -0.465844 0.00831914 -0.0857564 -0.465522 0.0145562 -0.0857595 -0.466815 0.00765558 -0.0857351 -0.472295 0.0309896 -0.0846207 -0.46891 0.0309976 -0.0854996 -0.473832 0.0309838 -0.0839761 -0.469541 0.0238032 -0.0854432 -0.46954 0.0250081 -0.0854334 -0.4811 0.0247475 -0.0788321 -0.481546 0.0309276 -0.0777412 -0.478574 0.0157073 -0.0817982 -0.480091 0.0106542 -0.0807992 -0.478078 0.0309592 -0.0812472 -0.477026 0.0309666 -0.0820666 -0.474099 0.0156474 -0.0843308 -0.476424 0.0156785 -0.0832198 -0.476852 -4.19898e-08 -0.0833332 -0.479718 -0.0157229 -0.0808645 -0.471182 -0.0243939 -0.0850871 -0.471178 -0.0255221 -0.0850696 -0.471204 -0.000823643 -0.0853168 -0.473514 -4.19898e-08 -0.0847557 -0.471231 -0.00165123 -0.0853106 -0.471231 -0.00282765 -0.0853077 -0.473487 -0.0156392 -0.0845593 -0.476779 -0.0156834 -0.0830127 -0.479164 -0.0309506 -0.0802891 -0.476377 -0.0309708 -0.0825225 -0.473248 -0.0309863 -0.0842407 -0.471186 -0.0232653 -0.0851042 -0.471213 -0.0136363 -0.085228 -0.441438 -0.0156889 -0.085765 -0.445673 -4.19898e-08 -0.085765 -0.449075 -0.0289853 -0.085765 -0.448643 -0.02325 -0.085765 -0.448643 -0.00400004 -0.085765 -0.473998 -0.0566556 -0.0614177 -0.481546 -0.0309277 -0.0777412 -0.4816 -0.0370343 -0.0764271 -0.47989 -0.0345088 -0.0791306 -0.481618 -0.0354612 -0.0768948 -0.479897 -0.0428134 -0.0756663 -0.480872 -0.0447381 -0.0727762 -0.48076 -0.045042 -0.0726632 -0.479873 -0.0487094 -0.0698237 -0.479249 -0.0504269 -0.0682248 -0.476628 -0.0549996 -0.0624236 -0.476743 -0.0536413 -0.0660116 -0.467226 -0.058989 -0.0582414 -0.467131 -0.0592854 -0.0544919 -0.467097 -0.0596664 -0.0469892 -0.464306 -0.0584919 -0.0622271 -0.467306 -0.0574246 -0.0655479 -0.466762 -0.0544412 -0.0722005 -0.463996 -0.0535983 -0.0737403 -0.465192 -0.0504307 -0.0777749 -0.463974 -0.0503454 -0.077898 -0.463975 -0.0510716 -0.0770844 -0.466542 -0.0350456 -0.0855756 -0.46522 -0.0358329 -0.0855621 -0.478857 -0.0402485 -0.0783387 -0.481095 -0.0373645 -0.07696 -0.476085 -0.034003 -0.082467 -0.47846 -0.0312665 -0.0809066 -0.46993 -0.0309959 -0.0853076 -0.471574 -0.0330436 -0.0847884 -0.468976 -0.0359625 -0.0851632 -0.471045 -0.0395585 -0.0838164 -0.472696 -0.042784 -0.0817995 -0.476475 -0.043012 -0.0791374 -0.474981 -0.0481639 -0.0763605 -0.475742 -0.0503388 -0.0731375 -0.478984 -0.0496995 -0.0698207 -0.479841 -0.048808 -0.0697381 -0.478329 -0.0478113 -0.0732081 -0.477505 -0.0455853 -0.0763353 -0.477607 -0.0373211 -0.0806231 -0.475192 -0.0400745 -0.0815448 -0.473585 -0.0367526 -0.0834657 -0.466202 -0.0453241 -0.0821001 -0.465417 -0.0406931 -0.084463 -0.464316 -0.0423216 -0.0838399 -0.463973 -0.0480138 -0.0801558 -0.470755 -0.0585754 -0.0562515 -0.470714 -0.0580829 -0.0600889 -0.474604 -0.0569893 -0.0585098 -0.470475 -0.0560823 -0.0675271 -0.473787 -0.0556654 -0.0652241 -0.473477 -0.0543108 -0.0689062 -0.473011 -0.0525873 -0.0724087 -0.47234 -0.05052 -0.0756763 -0.471413 -0.0481357 -0.0786489 -0.467675 -0.0480148 -0.0798747 -0.467375 -0.0438865 -0.0828406 -0.468717 -0.0596916 -0.0442116 -0.467312 -0.0583986 -0.0619451 -0.470644 -0.0572759 -0.0638658 -0.46714 -0.0560876 -0.0689859 -0.470143 -0.054515 -0.0710138 -0.469598 -0.0526205 -0.0742702 -0.466127 -0.0525418 -0.0751439 -0.46879 -0.0504439 -0.0772434 -0.476315 -0.0521659 -0.0696688 -0.473985 -0.0456472 -0.0792735 -0.470176 -0.0454464 -0.0812521 -0.468572 -0.0424373 -0.0833787 -0.466556 -0.0390772 -0.0848841 -0.463973 -0.0457619 -0.0818952 -0.442185 -0.0490219 -0.0792415 -0.463973 -0.0484568 -0.0797648 -0.44226 -0.0503454 -0.077898 -0.442312 -0.0510975 -0.0770543 -0.464017 -0.0545814 -0.0721638 -0.464057 -0.0557344 -0.0700322 -0.464155 -0.0573091 -0.066337 -0.442927 -0.0574262 -0.0660047 -0.443015 -0.0578343 -0.0647476 -0.464166 -0.0574261 -0.0660049 -0.443434 -0.058899 -0.0600361 -0.464487 -0.0591251 -0.0582848 -0.464418 -0.0589477 -0.0597077 -0.463973 -0.0404559 -0.0845779 -0.46201 -0.036834 -0.0854513 -0.441366 -0.0404538 -0.0845786 -0.455668 -0.0362388 -0.0855333 -0.440802 -0.0382502 -0.0851904 -0.440667 -0.0378301 -0.0852779 -0.439723 -0.0355123 -0.0856134 -0.438473 -0.0321552 -0.0857621 -0.450232 -0.0316863 -0.0857644 -0.438473 -0.031 -0.085765 -0.432473 -0.0217 -0.074265 -0.420191 -0.020362 -0.074265 -0.414486 0.0147782 -0.074265 -0.416924 0.0174425 -0.074265 -0.420625 0.0207205 -0.074265 -0.448173 0.00599996 -0.074265 -0.41065 -0.00620887 -0.074265 -0.447405 -0.0108516 -0.074265 -0.445175 -0.0152283 -0.074265 -0.441701 -0.0187016 -0.074265 -0.437325 0.0209315 -0.074265 -0.445175 0.0152282 -0.074265 -0.417586 -0.0180761 -0.074265 -0.416611 -0.0171323 -0.074265 -0.410346 0.000132619 -0.074265 -0.410658 0.00626788 -0.074265 -0.412209 -0.0112672 -0.074265 -0.411772 -0.0103107 -0.074265 -0.41119 -0.00867624 -0.074265 -0.410838 0.00727218 -0.074265 -0.412329 0.0115045 -0.074265 -0.432473 -0.0217 -0.082265 -0.437325 -0.0209316 -0.082265 -0.437325 -0.0209316 -0.074265 -0.438473 -0.0205083 -0.082265 -0.447405 -0.0108516 -0.082265 -0.448173 -0.00600004 -0.074265 -0.448173 0.00599996 -0.082265 -0.447405 0.0108515 -0.074265 -0.441701 0.0187015 -0.074265 -0.438473 0.0205082 -0.082265 -0.437325 0.0209315 -0.082265 -0.433285 -0.0280657 -0.082265 -0.421838 -0.0217 -0.074265 -0.428955 0.0245012 -0.082265 -0.432473 0.0217 -0.082265 -0.421838 0.0217 -0.074265 -0.432473 0.0217 -0.074265 -0.43827 -0.0335059 -0.0822353 -0.437408 -0.0323574 -0.0822602 -0.436253 -0.031 -0.082265 -0.438473 0.031 -0.082265 -0.424524 -0.0220819 -0.0805776 -0.424055 -0.0217 -0.0806177 -0.422171 -0.0217 -0.0765105 -0.420036 -0.0202425 -0.0737651 -0.414265 -0.014499 -0.074265 -0.41518 -0.015617 -0.073765 -0.41369 -0.0137258 -0.074265 -0.414192 -0.014417 -0.0737649 -0.410838 -0.00727227 -0.074265 -0.411351 -0.00922858 -0.0737652 -0.410388 -0.00324573 -0.074265 -0.410346 -4.19907e-08 -0.074265 -0.429615 -0.027781 -0.075056 -0.433692 -0.0315319 -0.0737798 -0.43267 -0.0304916 -0.0748312 -0.432392 -0.0302765 -0.0737774 -0.427809 -0.0263774 -0.0737696 -0.43554 -0.0334773 -0.0746729 -0.435225 -0.0331573 -0.0737826 -0.439285 -0.0390054 -0.0737911 -0.43808 -0.0368548 -0.074619 -0.441902 -0.049238 -0.0738063 -0.44147 -0.045537 -0.0738017 -0.441381 -0.045074 -0.0738005 -0.440082 -0.040745 -0.0737942 -0.438473 -0.0338008 -0.0822236 -0.439215 -0.0349834 -0.0821472 -0.425283 -0.0217 -0.082265 -0.430637 -0.0271067 -0.0800286 -0.428955 -0.0245013 -0.082265 -0.42379 -0.0225437 -0.0781208 -0.429948 -0.0275425 -0.0775598 -0.432975 -0.0302565 -0.077312 -0.433647 -0.0298261 -0.0798126 -0.4365 -0.032798 -0.0797048 -0.439089 -0.0361979 -0.0797994 -0.441117 -0.0403688 -0.0803471 -0.441403 -0.0413962 -0.0804089 -0.440469 -0.0405466 -0.0772807 -0.441208 -0.0427723 -0.0775902 -0.440857 -0.0428417 -0.0748951 -0.441409 -0.045064 -0.075139 -0.422785 -0.0217 -0.0782997 -0.423392 -0.0228102 -0.0756033 -0.435829 -0.0332267 -0.0771241 -0.440104 -0.0407207 -0.0747343 -0.438392 -0.0365916 -0.0770496 -0.439511 -0.0384825 -0.0771105 -0.44022 -0.0381914 -0.0799935 -0.410392 0.00333382 -0.074265 -0.410318 -3.82582e-07 -0.0737642 -0.411264 0.00891914 -0.074265 -0.411772 0.0103107 -0.074265 -0.413865 0.0139687 -0.074265 -0.414191 0.0144167 -0.0737649 -0.417586 0.0180761 -0.074265 -0.416544 0.0170757 -0.0737648 -0.417584 0.0180842 -0.073765 -0.4365 0.032798 -0.0797048 -0.436253 0.031 -0.082265 -0.433647 0.0298261 -0.0798126 -0.433285 0.0280656 -0.082265 -0.430637 0.0271067 -0.0800286 -0.425283 0.0217 -0.082265 -0.424524 0.0220819 -0.0805776 -0.423713 0.0217 -0.0800803 -0.43827 0.0335058 -0.0822353 -0.441117 0.0403689 -0.0803471 -0.440274 0.0371222 -0.0818501 -0.44022 0.0381915 -0.0799935 -0.439215 0.0349832 -0.0821472 -0.441409 0.045064 -0.075139 -0.441381 0.045074 -0.0738005 -0.43808 0.0368548 -0.074619 -0.439285 0.0390055 -0.0737911 -0.440082 0.040745 -0.0737942 -0.436619 0.0348332 -0.0737852 -0.423392 0.0228102 -0.0756033 -0.430381 0.0284896 -0.0737742 -0.42379 0.0225437 -0.0781208 -0.439089 0.0361979 -0.0797994 -0.439511 0.0384825 -0.0771106 -0.440469 0.0405466 -0.0772807 -0.441403 0.0413959 -0.080409 -0.441806 0.0478064 -0.0754883 -0.440857 0.0428417 -0.0748952 -0.422985 0.0217 -0.0787401 -0.422195 0.0217 -0.0766001 -0.429948 0.0275425 -0.0775598 -0.432975 0.0302565 -0.077312 -0.429615 0.0277809 -0.075056 -0.435829 0.0332267 -0.0771241 -0.43267 0.0304916 -0.0748312 -0.43554 0.0334773 -0.0746729 -0.438392 0.0365916 -0.0770496 -0.440104 0.0407208 -0.0747343 -0.441208 0.0427724 -0.0775902 -0.43095 -0.023236 -0.058235 -0.433792 -0.0284439 -0.058235 -0.450746 -0.0579037 -0.00832143 -0.450731 -0.053392 -0.00849024 -0.449996 -0.0530214 -0.0169799 -0.449362 -0.0573017 -0.0221089 -0.447059 -0.0522103 -0.0355559 -0.444396 -0.0528691 -0.0491893 -0.443006 -0.0522166 -0.0573371 -0.442487 -0.0543996 -0.0640089 -0.442157 -0.0523706 -0.0689274 -0.442243 -0.0530911 -0.067439 -0.423184 -4.19419e-08 -0.0604654 -0.428428 -0.0202715 -0.0594281 -0.428237 -0.0169859 -0.058235 -0.426788 -0.0170588 -0.0596518 -0.426328 -0.00867942 -0.058235 -0.425488 -0.013816 -0.0598204 -0.424565 -0.0105113 -0.0599344 -0.432425 -0.0267374 -0.0588455 -0.429757 -0.0258851 -0.0623158 -0.436642 -0.0334764 -0.058235 -0.437263 -0.0358628 -0.0613747 -0.437413 -0.034904 -0.058235 -0.439309 -0.039576 -0.0612331 -0.442466 -0.0483094 -0.0573716 -0.443763 -0.0559262 -0.0536123 -0.444318 -0.0513901 -0.0490814 -0.443933 -0.0508369 -0.0507841 -0.443001 -0.0486512 -0.0542636 -0.423323 -0.022878 -0.0737645 -0.417558 -0.0178503 -0.071765 -0.417584 -0.0180843 -0.073765 -0.416544 -0.0170759 -0.0737648 -0.412542 -0.0119252 -0.0737652 -0.411763 -0.0103203 -0.0737649 -0.411802 -0.00972412 -0.0721069 -0.411004 -0.00676967 -0.0721521 -0.410664 -0.00641928 -0.0737649 -0.417561 -0.015943 -0.0683061 -0.416121 -0.0155625 -0.0700605 -0.414198 -0.0101728 -0.0686234 -0.411911 -0.00689728 -0.0704323 -0.410361 -0.00321169 -0.073765 -0.410662 -0.00354432 -0.0721551 -0.410578 -4.09622e-08 -0.072232 -0.424902 -0.0198087 -0.0629751 -0.419223 -0.0162809 -0.0666056 -0.422887 -0.016783 -0.063218 -0.417341 -0.013381 -0.0667916 -0.415201 -0.00707602 -0.0669385 -0.412842 -3.92418e-08 -0.0688122 -0.411564 -0.00358348 -0.0704366 -0.413029 -0.00361455 -0.0686739 -0.441964 -0.0487173 -0.0697609 -0.44066 -0.0423186 -0.0737974 -0.438067 -0.0368818 -0.0737887 -0.437488 -0.0360152 -0.0737871 -0.440918 -0.0434944 -0.0612267 -0.441543 -0.0444538 -0.0574716 -0.443212 -0.0557021 -0.0573348 -0.434175 -0.0320479 -0.07136 -0.430381 -0.0284897 -0.0737742 -0.434901 -0.0323604 -0.061627 -0.438505 -0.0380306 -0.0649524 -0.440444 -0.0420677 -0.0650946 -0.441993 -0.047539 -0.0613373 -0.442239 -0.0504481 -0.0656434 -0.442545 -0.0515859 -0.0615043 -0.442399 -0.0540214 -0.0651362 -0.411422 -3.94693e-08 -0.0705633 -0.412746 -0.00996275 -0.0703745 -0.413141 -0.0124985 -0.0720141 -0.414148 -0.0128258 -0.070246 -0.415065 -0.0151887 -0.0718924 -0.420535 -0.0205127 -0.0716453 -0.418615 -0.0182444 -0.0698479 -0.423858 -0.0232072 -0.071538 -0.424773 -0.0236529 -0.0694338 -0.430859 -0.0288955 -0.0713863 -0.431551 -0.029468 -0.0691363 -0.436619 -0.0348333 -0.0737852 -0.437608 -0.0363238 -0.0691173 -0.423768 -0.00362112 -0.0600344 -0.424011 -0.0071201 -0.0600011 -0.419186 -0.00364174 -0.0635341 -0.419459 -0.00713424 -0.0635274 -0.420131 -0.010481 -0.0634852 -0.421276 -0.013689 -0.0633867 -0.427174 -0.0247551 -0.0656999 -0.432356 -0.0290484 -0.0619552 -0.430202 -0.0277335 -0.0653828 -0.414882 -0.00363373 -0.0669382 -0.413368 -0.00700415 -0.0686723 -0.415994 -0.0103249 -0.0668985 -0.415602 -0.0131347 -0.0685019 -0.42156 -0.0190928 -0.0663455 -0.421541 -0.0209251 -0.0696333 -0.433203 -0.0308958 -0.0651262 -0.434764 -0.0327203 -0.069078 -0.436026 -0.0343081 -0.06497 -0.439851 -0.0403048 -0.0692744 -0.441681 -0.0462813 -0.0653563 -0.441297 -0.0445214 -0.0695169 -0.464621 0.0469947 -0.0763217 -0.474737 0.0506144 -0.0657721 -0.476507 0.0470391 -0.0692957 -0.473483 0.0321181 -0.0801486 -0.464934 0.0312272 -0.0822629 -0.466346 0.030998 -0.0822341 -0.478831 0.0376572 -0.0738774 -0.476878 0.0328255 -0.077447 -0.478265 0.0431516 -0.0710622 -0.477381 0.0468863 -0.0681402 -0.476469 0.0493231 -0.0655746 -0.472271 0.0523644 -0.0650796 -0.473231 0.0538216 -0.0579362 -0.474065 0.0530378 -0.0597734 -0.469927 0.0551157 -0.0566262 -0.471295 0.0550761 -0.0536073 -0.466901 0.0561527 -0.0472946 -0.467059 0.0566131 -0.037461 -0.466829 0.0557617 -0.0550099 -0.464732 0.0559262 -0.0536123 -0.464485 0.0556424 -0.0579357 -0.464296 0.0550267 -0.0616846 -0.464158 0.0540378 -0.06509 -0.466918 0.0537985 -0.0653796 -0.464044 0.052319 -0.0690266 -0.466724 0.0524613 -0.068508 -0.464143 0.0538817 -0.0655189 -0.478568 0.041052 -0.0723161 -0.477917 0.0428028 -0.0718849 -0.47705 0.0406503 -0.0745747 -0.478023 0.0356253 -0.0756349 -0.474122 0.0308667 -0.0798189 -0.469117 0.0309726 -0.0819023 -0.469571 0.0310242 -0.0817978 -0.471357 0.0346397 -0.0809608 -0.472801 0.0378022 -0.0795367 -0.469238 0.037185 -0.0812364 -0.471948 0.0428528 -0.0776982 -0.472915 0.0452549 -0.0751985 -0.475821 0.0452012 -0.0724019 -0.474262 0.04916 -0.069175 -0.476943 0.0481678 -0.0668718 -0.478079 0.0441382 -0.0703849 -0.474995 0.0430512 -0.0751845 -0.473997 0.0405903 -0.0775853 -0.476043 0.0381791 -0.0768777 -0.474874 0.0353514 -0.0787495 -0.47177 0.0309206 -0.0810667 -0.472828 0.0540247 -0.0577473 -0.472549 0.053355 -0.0614994 -0.469789 0.0546109 -0.0603289 -0.469684 0.0537763 -0.0638442 -0.469519 0.0525631 -0.0671945 -0.467849 0.0470504 -0.0759004 -0.470829 0.0472758 -0.0745644 -0.469931 0.0449902 -0.0771403 -0.463973 0.0396993 -0.081134 -0.467212 0.039718 -0.0809136 -0.468177 0.0562825 -0.0430009 -0.468724 0.0561058 -0.0454016 -0.466865 0.0554353 -0.0586495 -0.46694 0.0547994 -0.0620825 -0.469198 0.0510016 -0.0703599 -0.466307 0.050844 -0.0714124 -0.468657 0.049146 -0.0732836 -0.46562 0.0490072 -0.0740318 -0.46673 0.0447585 -0.078134 -0.465233 0.0422662 -0.0799225 -0.463973 0.0424143 -0.0798681 -0.47536 0.0513795 -0.0627725 -0.471941 0.0510064 -0.0684729 -0.471482 0.0492962 -0.0716518 -0.473671 0.0473653 -0.0723353 -0.468745 0.0424711 -0.07929 -0.470736 0.0401709 -0.0797474 -0.465257 0.0366744 -0.0819064 -0.46739 0.0338034 -0.0820727 -0.463991 0.050364 -0.0722762 -0.442063 0.0513711 -0.0707143 -0.441901 0.049238 -0.0738061 -0.44216 0.0523928 -0.0688842 -0.442348 0.0537616 -0.0658355 -0.442487 0.0543996 -0.0640086 -0.442543 0.0545994 -0.0633446 -0.443504 0.0558474 -0.0552836 -0.443142 0.0556508 -0.0578562 -0.440922 0.0390773 -0.0813473 -0.44159 0.0431079 -0.0794519 -0.463973 0.0451489 -0.0779891 -0.441676 0.0448902 -0.0781951 -0.463975 0.0461129 -0.0771653 -0.463974 0.048051 -0.0752194 -0.441781 0.0473464 -0.075975 -0.462654 0.0327315 -0.0822551 -0.461363 0.033098 -0.0822475 -0.463973 0.0339844 -0.082215 -0.463973 0.036949 -0.0818832 -0.455012 0.0312291 -0.0822649 -0.438473 0.0338007 -0.0822236 -0.455804 0.0319094 -0.0822635 -0.41518 0.0156169 -0.073765 -0.44147 0.045537 -0.0738017 -0.442243 0.0530911 -0.0674387 -0.442931 0.0554325 -0.0595499 -0.443006 0.0522165 -0.0573371 -0.445916 0.0564422 -0.0417924 -0.444496 0.0515608 -0.0482579 -0.444811 0.0517211 -0.0467584 -0.447841 0.0568895 -0.0315491 -0.45007 0.0575489 -0.0164446 -0.444396 0.052869 -0.0491893 -0.442466 0.0483093 -0.0573716 -0.443179 0.0491383 -0.0536869 -0.43641 0.0330556 -0.058235 -0.436642 0.0334753 -0.058235 -0.428428 0.0202714 -0.0594281 -0.432425 0.0267373 -0.0588455 -0.420535 0.0205126 -0.0716453 -0.42156 0.0190928 -0.0663455 -0.422887 0.0167829 -0.063218 -0.425488 0.0138159 -0.0598204 -0.421276 0.013689 -0.0633867 -0.424565 0.0105112 -0.0599344 -0.427046 0.0128685 -0.058235 -0.412542 0.0119249 -0.0737652 -0.411763 0.0103202 -0.0737649 -0.411802 0.00972403 -0.0721069 -0.414148 0.0128258 -0.070246 -0.415602 0.0131346 -0.0685019 -0.414198 0.0101728 -0.0686234 -0.417341 0.0133809 -0.0667916 -0.420131 0.010481 -0.0634852 -0.415994 0.0103248 -0.0668985 -0.424011 0.00712002 -0.0600011 -0.411004 0.00676959 -0.0721521 -0.410361 0.0032114 -0.073765 -0.413368 0.00700406 -0.0686723 -0.411564 0.00358339 -0.0704366 -0.413029 0.00361447 -0.0686739 -0.415201 0.00707594 -0.0669385 -0.411351 0.00922834 -0.0737652 -0.410664 0.00641902 -0.0737649 -0.412746 0.00996267 -0.0703745 -0.411911 0.0068972 -0.0704323 -0.419459 0.00713416 -0.0635274 -0.413141 0.0124984 -0.0720141 -0.416121 0.0155624 -0.0700605 -0.417561 0.0159429 -0.0683061 -0.419223 0.0162808 -0.0666056 -0.410662 0.00354424 -0.0721551 -0.414882 0.00363364 -0.0669382 -0.415588 -4.29144e-08 -0.0663006 -0.419186 0.00364166 -0.0635341 -0.423768 0.00362104 -0.0600344 -0.441297 0.0445214 -0.0695169 -0.44066 0.0423186 -0.0737974 -0.438068 0.0368818 -0.0737887 -0.440444 0.0420676 -0.0650946 -0.442545 0.0515858 -0.0615043 -0.441681 0.0462813 -0.0653563 -0.442239 0.050448 -0.0656434 -0.441993 0.047539 -0.0613373 -0.441543 0.0444538 -0.0574716 -0.437488 0.0360152 -0.0737871 -0.435225 0.0331573 -0.0737826 -0.434175 0.0320478 -0.07136 -0.433692 0.0315318 -0.0737798 -0.432356 0.0290484 -0.0619552 -0.434901 0.0323603 -0.061627 -0.434764 0.0327202 -0.069078 -0.438505 0.0380305 -0.0649524 -0.437608 0.0363237 -0.0691173 -0.439851 0.0403047 -0.0692744 -0.441964 0.0487172 -0.0697609 -0.432392 0.0302765 -0.0737774 -0.430859 0.0288954 -0.0713863 -0.42781 0.0263775 -0.0737696 -0.423323 0.022878 -0.0737645 -0.420036 0.0202422 -0.0737651 -0.421541 0.020925 -0.0696333 -0.423858 0.0232071 -0.071538 -0.431551 0.0294679 -0.0691363 -0.430202 0.0277335 -0.0653828 -0.429757 0.025885 -0.0623158 -0.424902 0.0198087 -0.0629751 -0.415065 0.0151886 -0.0718924 -0.417558 0.0178503 -0.071765 -0.418615 0.0182443 -0.0698479 -0.424773 0.0236528 -0.0694338 -0.427174 0.024755 -0.0656999 -0.426788 0.0170587 -0.0596518 -0.433203 0.0308957 -0.0651262 -0.437263 0.0358628 -0.0613747 -0.436026 0.0343081 -0.06497 -0.439309 0.0395759 -0.0612331 -0.440918 0.0434943 -0.0612267 -0.478849 -0.0307698 -0.0755156 -0.481595 -5.32762e-08 -0.0686099 -0.481523 -0.00765386 -0.0710688 -0.479373 -0.00782485 -0.0764811 -0.481582 -0.00757297 -0.0684844 -0.480766 -0.00774272 -0.0739013 -0.481503 -0.0152729 -0.0705742 -0.480831 -0.0154216 -0.0732836 -0.47927 -4.63731e-08 -0.076768 -0.479583 -0.0155587 -0.0757815 -0.481426 -0.0302464 -0.067001 -0.478038 0.0156511 -0.0776602 -0.477642 0.00787835 -0.0784019 -0.47885 0.0307686 -0.0755155 -0.479583 0.0155594 -0.0757815 -0.480928 0.0305288 -0.0714966 -0.480831 0.0154222 -0.0732836 -0.481503 0.0152736 -0.0705742 -0.481523 0.00765383 -0.0710688 -0.479373 0.00782481 -0.0764811 -0.480732 -4.81533e-08 -0.0741536 -0.480766 0.00774269 -0.0739013 -0.481529 -5.06666e-08 -0.0712661 -0.480929 0.0399361 -0.0622747 -0.470326 0.0559618 -0.0427364 -0.473315 0.0542822 -0.0542671 -0.470072 0.0556159 -0.050299 -0.474597 0.0531645 -0.0576388 -0.472667 0.0542558 -0.0567087 -0.474847 0.0521136 -0.0615565 -0.475949 0.0514349 -0.0611987 -0.478052 0.0482617 -0.0640558 -0.478867 0.0454539 -0.0670878 -0.479473 0.0421511 -0.0696873 -0.478748 0.0391196 -0.0732707 -0.478897 0.0343904 -0.0748981 -0.477393 0.0479373 -0.0306649 -0.477593 0.0453703 -0.0305334 -0.478547 0.0471215 -0.0413591 -0.470234 0.0563046 -0.031774 -0.472423 0.0552728 -0.0424557 -0.476702 0.0504448 -0.0308451 -0.47914 0.0465824 -0.0468522 -0.479474 0.044316 -0.0484315 -0.478969 0.0481599 -0.059645 -0.480529 0.0427037 -0.0646091 -0.481371 0.0334709 -0.0686048 -0.481416 0.0303777 -0.0690872 -0.4812 0.0370889 -0.064847 -0.481259 0.0365042 -0.0675368 -0.481396 0.0324756 -0.0667129 -0.480937 0.0407847 -0.0629753 -0.480829 0.0406669 -0.0613154 -0.477806 0.0504809 -0.0472551 -0.478645 0.0486123 -0.0470425 -0.479344 0.0475329 -0.0526574 -0.47975 0.045725 -0.0523861 -0.480066 0.0450034 -0.0551947 -0.480128 0.0453722 -0.0585018 -0.48107 0.0392901 -0.0658958 -0.480809 0.0417215 -0.0637632 -0.48049 0.0437518 -0.0612549 -0.480125 0.0449611 -0.0619679 -0.479141 0.0482248 -0.0559898 -0.479735 0.0466265 -0.0555785 -0.478639 0.0492644 -0.0529523 -0.475852 0.052868 -0.0419403 -0.471518 0.0553822 -0.0483275 -0.472293 0.0549521 -0.0511996 -0.477068 0.0505232 -0.0607387 -0.47345 0.0546094 -0.0480402 -0.475175 0.0535179 -0.0477579 -0.476395 0.052247 -0.0536081 -0.474932 0.0533981 -0.0539464 -0.475971 0.0522403 -0.0572669 -0.477222 0.0510863 -0.0568532 -0.480099 0.0436837 -0.065474 -0.4805 0.0407826 -0.0678441 -0.479843 0.0384398 -0.0717396 -0.480764 0.0375102 -0.0696953 -0.479982 0.0345168 -0.0731293 -0.479998 0.0306704 -0.0737729 -0.480891 0.0340142 -0.0709309 -0.477102 0.051202 -0.041721 -0.478007 0.0492692 -0.0415282 -0.480299 0.0430427 -0.056276 -0.48038 0.04397 -0.0579728 -0.472395 0.0553998 -0.031509 -0.474192 0.0541151 -0.0312657 -0.474282 0.0542339 -0.0421867 -0.47664 0.0521306 -0.0474938 -0.477646 0.0508547 -0.0532717 -0.478294 0.0497318 -0.0564203 -0.478092 0.0494208 -0.0602122 -0.47958 0.0461516 -0.0626962 -0.479656 0.0467901 -0.0590659 -0.480673 0.0425807 -0.0605879 -0.4474 0.0597276 0.0334541 -0.449362 0.0573016 -0.0221089 -0.450593 0.0578001 -0.0106932 -0.450746 0.0579036 -0.00832143 -0.443763 0.0559262 -0.0536123 -0.450004 0.0589879 0.0165136 -0.47958 -0.0461544 -0.0626926 -0.477704 -0.045324 -0.0315858 -0.47886 -0.0312113 -0.0754674 -0.478748 -0.0391263 -0.0732678 -0.478264 -0.0431573 -0.0710585 -0.478039 -0.0443332 -0.0702438 -0.475852 -0.0528682 -0.041939 -0.477806 -0.0504812 -0.0472533 -0.47664 -0.052131 -0.0474919 -0.480098 -0.0436874 -0.0654706 -0.478091 -0.049423 -0.0602085 -0.470325 -0.055962 -0.0427352 -0.468709 -0.056659 -0.0319486 -0.472423 -0.055273 -0.0424545 -0.471518 -0.0553825 -0.0483256 -0.472292 -0.0549526 -0.0511973 -0.474595 -0.053166 -0.0576353 -0.47597 -0.0522418 -0.0572634 -0.478866 -0.0454581 -0.067084 -0.478137 -0.0461774 -0.0677561 -0.478051 -0.0482649 -0.0640518 -0.478877 -0.0472705 -0.0634003 -0.477067 -0.0505255 -0.0607349 -0.477221 -0.0510878 -0.0568498 -0.481164 -0.0375831 -0.0645026 -0.48107 -0.0392941 -0.065893 -0.481371 -0.0334762 -0.0686035 -0.481416 -0.0303778 -0.0690872 -0.480928 -0.0305289 -0.0714966 -0.479982 -0.0345234 -0.0731276 -0.479998 -0.0306705 -0.0737729 -0.481259 -0.0365088 -0.0675346 -0.480499 -0.0407872 -0.067841 -0.479473 -0.0421563 -0.0696839 -0.479843 -0.038446 -0.0717369 -0.480891 -0.0340202 -0.0709293 -0.480764 -0.0375157 -0.0696929 -0.48138 -0.0331408 -0.0665632 -0.481296 -0.0354408 -0.0657629 -0.47704 -0.0494685 -0.0307677 -0.476139 -0.0516394 -0.0309555 -0.477102 -0.0512022 -0.0417198 -0.479344 -0.0475336 -0.0526548 -0.478639 -0.0492653 -0.0529496 -0.479734 -0.0466276 -0.0555755 -0.480809 -0.0417245 -0.06376 -0.480489 -0.0437541 -0.0612517 -0.479655 -0.046792 -0.0590625 -0.478968 -0.048162 -0.0596414 -0.478294 -0.0497333 -0.056417 -0.474932 -0.053399 -0.0539435 -0.473449 -0.0546098 -0.0480383 -0.478007 -0.0492695 -0.0415269 -0.478645 -0.0486126 -0.0470407 -0.480066 -0.0450043 -0.0551918 -0.48038 -0.0439714 -0.0579698 -0.46966 -0.0557737 -0.0489604 -0.472337 -0.0544808 -0.0559864 -0.473314 -0.054283 -0.0542642 -0.475947 -0.0514373 -0.0611948 -0.477151 -0.049105 -0.0646171 -0.477299 -0.0471454 -0.0678968 -0.479533 -0.0446181 -0.0663106 -0.478547 -0.0471217 -0.0413579 -0.47914 -0.0465827 -0.0468504 -0.479158 -0.0445566 -0.0454243 -0.47983 -0.0439509 -0.0518135 -0.47975 -0.0457256 -0.0523836 -0.480517 -0.0422983 -0.0583549 -0.480127 -0.0453739 -0.0584987 -0.479141 -0.0482262 -0.0559867 -0.477646 -0.0508557 -0.053269 -0.476395 -0.0522479 -0.0536053 -0.475175 -0.0535183 -0.047756 -0.474281 -0.0542341 -0.0421855 -0.478642 0.044874 -0.0405107 -0.481582 0.00757294 -0.0684844 -0.481546 0.0151399 -0.0681438 -0.468966 0.048845 0.0515465 -0.468631 0.0485162 0.0547378 -0.4687 -0.0486243 0.0540813 -0.468969 -0.0488459 0.0515204 -0.469435 -0.0487596 0.0470914 -0.481546 -0.0151393 -0.0681438 -0.481133 0.0379599 -0.0642151 -0.481041 0.0389599 -0.0633339 -0.481426 0.0302463 -0.0670011 -0.481321 0.0348803 -0.0660031 -0.480584 0.0420142 -0.0589869 -0.479958 0.0437699 -0.0530303 -0.467196 0.0403871 0.0683892 -0.466876 0.0294574 0.0714371 -0.466893 0.0339259 0.0712757 -0.467078 -0.0388319 0.0695084 -0.467252 -0.041017 0.0678567 -0.467488 -0.0432112 0.0656111 -0.467762 -0.0451455 0.0630075 -0.480228 -0.0432301 -0.0556061 -0.48077 -0.0410406 -0.0607553 -0.480984 -0.0394797 -0.0627977 -0.450004 -0.058988 0.0165136 -0.450733 -0.0586165 0.00800564 -0.457998 -0.0602487 0.0453877 -0.466152 -0.0568598 -0.0322305 -0.450593 -0.0578001 -0.0106932 -0.45007 -0.057549 -0.0164446 -0.445916 -0.0564423 -0.0417924 -0.447841 -0.0568895 -0.0315491 -0.44513 -0.0602487 0.0453877 -0.4474 -0.0597276 0.0334541 -0.447911 -0.0596043 0.0306287 -0.477593 -0.0453704 -0.0305334 -0.477517 -0.0470026 -0.0306116 -0.47486 -0.0534444 -0.031167 -0.473218 -0.0548886 -0.0314009 -0.462649 -0.0595052 0.0459091 -0.460361 -0.0600784 0.0456436 -0.471206 -0.055965 -0.0316577 -0.466153 0.0568602 -0.0322182 -0.457998 0.0602486 0.0453877 -0.467779 0.0567839 -0.0320512 -0.462675 0.0594957 0.0459122 -0.464691 0.0585209 0.0461666 -0.466376 0.0571772 0.0464025 -0.467714 0.0554837 0.046617 -0.47563 0.0524657 -0.0310443 -0.468685 0.0534596 0.0468074 -0.469263 0.0511502 0.0469689 -0.441167 -0.0417435 0.0793798 -0.410396 -0.0034917 0.073735 -0.41038 -0.0037229 0.073235 -0.411465 -0.00984114 0.0732352 -0.410724 -0.00696032 0.073235 -0.411151 -0.00879289 0.073735 -0.410676 -0.00655603 0.073735 -0.412144 -0.0114811 0.073735 -0.414455 -0.0152438 0.073235 -0.413593 -0.0140322 0.073735 -0.413207 -0.0134348 0.073735 -0.41273 -0.0126457 0.0732352 -0.423288 -0.023694 0.0732345 -0.420534 -0.0214014 0.0732351 -0.417558 -0.0186832 0.073735 -0.417553 -0.0186874 0.073235 -0.416901 -0.0180351 0.0732349 -0.423647 -0.0217 0.081735 -0.430431 -0.0282892 0.0795722 -0.437604 -0.0341475 0.0816067 -0.435484 -0.0318165 0.0817183 -0.432963 -0.0294575 0.081735 -0.439226 -0.0364334 0.0813282 -0.44022 -0.0383547 0.0809224 -0.44019 -0.039467 0.0790774 -0.441436 -0.0469506 0.0732713 -0.441375 -0.0464979 0.0743444 -0.440604 -0.0436662 0.0732673 -0.440815 -0.0442517 0.0741357 -0.440038 -0.0421161 0.0732639 -0.439208 -0.0402853 0.073261 -0.437387 -0.0372138 0.0732567 -0.432637 -0.0316324 0.0742345 -0.435093 -0.0342601 0.0732523 -0.427529 -0.0271412 0.0732391 -0.430532 -0.029706 0.0732444 -0.438026 -0.0381886 0.0732585 -0.440059 -0.0421044 0.0740068 -0.441653 -0.0463897 0.0770699 -0.423358 -0.0236509 0.0750509 -0.429582 -0.0288248 0.0744847 -0.432892 -0.031435 0.0767541 -0.435754 -0.0344759 0.0764802 -0.438329 -0.0378993 0.0762798 -0.435504 -0.0347112 0.0740427 -0.438039 -0.0381726 0.0739466 -0.439461 -0.039821 0.0762683 -0.424362 -0.0230945 0.0801156 -0.423716 -0.0234509 0.0776106 -0.429862 -0.0286403 0.0770443 -0.433445 -0.0310591 0.0792918 -0.43633 -0.0340508 0.0790485 -0.439001 -0.037468 0.078963 -0.440441 -0.0419286 0.0763832 -0.44149 -0.0434129 0.0789393 -0.44163 -0.0457572 0.0775144 -0.441198 -0.0442068 0.0766783 -0.430934 -0.0277089 0.081735 -0.432473 -0.0217 0.081735 -0.438473 -0.0294575 0.081735 -0.415658 0.0166892 0.073735 -0.41516 0.0161088 0.073735 -0.413457 0.013827 0.073735 -0.413207 0.0134343 0.073735 -0.411118 0.00867015 0.073735 -0.411465 0.00984261 0.0732352 -0.411759 0.0105926 0.073735 -0.412065 0.0113101 0.073735 -0.410725 0.0069619 0.073235 -0.41038 0.00372476 0.073235 -0.410346 -4.117e-08 0.073735 -0.435503 0.0347098 0.0740428 -0.429581 0.0288238 0.0744848 -0.427527 0.0271389 0.0732391 -0.423287 0.0236933 0.0732345 -0.420893 0.0217 0.073735 -0.435092 0.0342585 0.0732523 -0.440814 0.0442495 0.0741355 -0.440058 0.0421024 0.0740067 -0.440037 0.0421141 0.0732639 -0.44163 0.0457572 0.0775144 -0.441197 0.0442045 0.0766779 -0.440189 0.039465 0.0790772 -0.430934 0.0277089 0.081735 -0.43043 0.0282883 0.0795723 -0.433444 0.031058 0.0792919 -0.43946 0.0398191 0.0762683 -0.441783 0.0491882 0.0747688 -0.441374 0.0464955 0.0743442 -0.44044 0.0419265 0.076383 -0.421219 0.0217 0.0762025 -0.421667 0.0217 0.077758 -0.423357 0.0236502 0.075051 -0.429861 0.0286394 0.0770444 -0.432636 0.0316312 0.0742346 -0.432891 0.0314339 0.0767542 -0.435753 0.0344746 0.0764802 -0.438038 0.038171 0.0739466 -0.423715 0.0234501 0.0776106 -0.424362 0.0230937 0.0801157 -0.436329 0.0340495 0.0790486 -0.439 0.0374663 0.078963 -0.438328 0.0378977 0.0762798 -0.441166 0.0417412 0.0793794 -0.441475 0.0432685 0.0790159 -0.441092 0.0409991 0.080062 -0.438473 0.0294574 0.081735 -0.423647 0.0217 0.081735 -0.432473 0.0217 0.081735 -0.432963 0.0294574 0.081735 -0.438473 0.0205082 0.081735 -0.445175 0.0152282 0.081735 -0.448173 0.00599996 0.081735 -0.430237 -0.0252305 0.0588231 -0.442279 -0.0531991 0.0652032 -0.439896 -0.0429272 0.057705 -0.429713 -0.0221434 0.057705 -0.432366 -0.0287334 0.0584978 -0.432201 -0.0274504 0.057705 -0.44359 -0.0541115 0.0517527 -0.44361 -0.0565659 0.0529329 -0.444408 -0.0603613 0.0493051 -0.450973 -0.0582554 -0.000264971 -0.450815 -0.0540406 0.00636548 -0.448498 -0.0549433 0.0270396 -0.449222 -0.0592521 0.0225614 -0.446906 -0.0553295 0.0358846 -0.444974 -0.0557458 0.0455498 -0.441587 -0.0477932 0.0570022 -0.441789 -0.0484574 0.0567418 -0.442458 -0.0517855 0.0570559 -0.443221 -0.0595987 0.056747 -0.442972 -0.0524147 0.0540037 -0.431076 -0.0302242 0.0708142 -0.436663 -0.0359824 0.0578092 -0.434984 -0.0344799 0.0610767 -0.432222 -0.031265 0.0732471 -0.437842 -0.0381657 0.0685291 -0.442012 -0.0510115 0.0692755 -0.442713 -0.058327 0.0610527 -0.442558 -0.0548128 0.0611339 -0.44178 -0.0488797 0.0648696 -0.4406 -0.044486 0.0645454 -0.439403 -0.0421716 0.0606901 -0.438692 -0.0402386 0.0643485 -0.437358 -0.0382207 0.060812 -0.432413 -0.0309356 0.0614425 -0.430342 -0.0292867 0.0647909 -0.429774 -0.0275504 0.0618537 -0.442946 -0.0590402 0.0589119 -0.442983 -0.0559256 0.0570684 -0.442041 -0.0505727 0.0609086 -0.441547 -0.0476918 0.0571143 -0.440995 -0.0463179 0.0607336 -0.44102 -0.0460272 0.0574864 -0.410318 -4.19898e-08 0.073235 -0.410991 -0.00701506 0.071684 -0.410579 -4.33278e-08 0.0717001 -0.41064 -0.00366476 0.071692 -0.412701 -0.0103723 0.0699548 -0.411809 -0.0100984 0.0716329 -0.413179 -0.0130024 0.0715329 -0.415138 -0.0158205 0.0714011 -0.418696 -0.0190679 0.0693659 -0.416157 -0.0162476 0.0696055 -0.414141 -0.0133736 0.0698112 -0.414083 -0.0106277 0.0682472 -0.411839 -0.00716872 0.070024 -0.411478 -0.00371834 0.0700368 -0.412809 -4.27033e-08 0.0683163 -0.412861 -0.00376541 0.0683214 -0.413219 -0.0073069 0.0683099 -0.417211 -0.0140568 0.066427 -0.415533 -0.0137402 0.0681064 -0.417545 -0.0166977 0.0678832 -0.414645 -0.00380178 0.0666152 -0.418884 -0.00384673 0.0632331 -0.419172 -0.00754833 0.0632215 -0.414985 -0.00741391 0.0666061 -0.415813 -0.0108329 0.0665529 -0.419152 -0.0171216 0.0662125 -0.42155 -0.0200982 0.0659117 -0.424298 -0.0230686 0.0655467 -0.421665 -0.0218922 0.0691192 -0.417666 -0.0186101 0.0712595 -0.420677 -0.0214038 0.0711223 -0.424031 -0.0242357 0.070996 -0.424937 -0.0247717 0.0688855 -0.427194 -0.0242745 0.062254 -0.42828 -0.0217689 0.0591075 -0.424805 -0.0210566 0.0626043 -0.422728 -0.0178263 0.0628759 -0.421061 -0.014525 0.0630625 -0.419873 -0.0111066 0.0631721 -0.423749 -0.00760995 0.059682 -0.423505 -0.00386348 0.059711 -0.424315 -0.0112525 0.0596182 -0.426351 -0.00947844 0.057705 -0.425262 -0.0148102 0.0595058 -0.428263 -0.0182711 0.057705 -0.426597 -0.0183056 0.0593362 -0.427273 -0.0261124 0.0651584 -0.431779 -0.0309251 0.0685355 -0.433373 -0.0326588 0.0645014 -0.435008 -0.0343662 0.0684722 -0.436215 -0.036292 0.0643392 -0.440039 -0.0423297 0.0687237 -0.441414 -0.0466963 0.0690069 -0.442111 -0.0538257 0.0694836 -0.438473 -0.035288 0.0814927 -0.438473 -0.0333324 0.0816619 -0.427273 0.0261123 0.0651584 -0.44361 0.0565658 0.0529329 -0.450973 0.0582554 -0.000264971 -0.450733 0.0586165 0.00800564 -0.450731 0.0541098 0.00795085 -0.450592 0.058711 0.0101716 -0.450585 0.0542068 0.0101733 -0.449998 0.0544803 0.0164372 -0.449222 0.059252 0.0225614 -0.44505 0.0557353 0.0451816 -0.44513 0.0602486 0.0453877 -0.444024 0.0549776 0.0499321 -0.442983 0.0559255 0.0570684 -0.442111 0.0538256 0.0694836 -0.442012 0.0510114 0.0692755 -0.4423 0.0559177 0.0662112 -0.442558 0.0548127 0.0611339 -0.442946 0.0590402 0.0589119 -0.423116 -4.3082e-08 0.0599878 -0.426174 0.0076193 0.057705 -0.42713 0.0141558 0.057705 -0.42828 0.0217688 0.0591075 -0.432366 0.0287333 0.0584978 -0.434657 0.0321158 0.057705 -0.438165 0.0389441 0.057705 -0.44021 0.0437467 0.057705 -0.430532 0.029706 0.0732444 -0.439403 0.0421716 0.0606901 -0.436215 0.0362919 0.0643392 -0.437358 0.0382206 0.060812 -0.433373 0.0326588 0.0645014 -0.431779 0.030925 0.0685355 -0.430342 0.0292866 0.0647909 -0.438025 0.0381869 0.0732585 -0.439207 0.0402836 0.073261 -0.440039 0.0423296 0.0687237 -0.440603 0.0436642 0.0732673 -0.441436 0.0469485 0.0732712 -0.441888 0.0506987 0.0732758 -0.441934 0.0513225 0.0726008 -0.4406 0.044486 0.0645454 -0.438692 0.0402386 0.0643485 -0.440418 0.0443111 0.0576917 -0.442279 0.053199 0.0652032 -0.44178 0.0488796 0.0648696 -0.442458 0.0517854 0.0570559 -0.441547 0.0476917 0.0571143 -0.440995 0.0463178 0.0607336 -0.442041 0.0505726 0.0609086 -0.441414 0.0466962 0.0690069 -0.412861 0.00376532 0.0683214 -0.416157 0.0162475 0.0696055 -0.414141 0.0133735 0.0698112 -0.414083 0.0106276 0.0682472 -0.412701 0.0103722 0.0699548 -0.411839 0.00716864 0.070024 -0.413219 0.00730682 0.0683099 -0.431076 0.0302241 0.0708142 -0.424031 0.0242356 0.070996 -0.420537 0.0214036 0.0732351 -0.417552 0.0186868 0.073235 -0.416903 0.0180369 0.0732349 -0.417666 0.01861 0.0712595 -0.415138 0.0158204 0.0714011 -0.414456 0.0152454 0.073235 -0.413179 0.0130023 0.0715329 -0.412731 0.0126472 0.0732352 -0.411809 0.0100983 0.0716329 -0.410991 0.00701497 0.071684 -0.420677 0.0214037 0.0711223 -0.432221 0.0312633 0.0732471 -0.435008 0.0343661 0.0684722 -0.437386 0.0372121 0.0732567 -0.437842 0.0381656 0.0685291 -0.429774 0.0275503 0.0618537 -0.436663 0.0359823 0.0578092 -0.415813 0.0108328 0.0665529 -0.415533 0.0137402 0.0681064 -0.417545 0.0166976 0.0678832 -0.419152 0.0171215 0.0662125 -0.418696 0.0190678 0.0693659 -0.421665 0.0218921 0.0691192 -0.424298 0.0230685 0.0655467 -0.424937 0.0247716 0.0688855 -0.432413 0.0309355 0.0614425 -0.434984 0.0344798 0.0610767 -0.429958 0.0227208 0.057705 -0.430237 0.0252304 0.0588231 -0.426597 0.0183055 0.0593362 -0.422728 0.0178262 0.0628759 -0.425262 0.0148101 0.0595058 -0.424315 0.0112525 0.0596182 -0.419873 0.0111065 0.0631721 -0.423749 0.00760987 0.059682 -0.419172 0.00754825 0.0632215 -0.423505 0.0038634 0.059711 -0.418884 0.00384665 0.0632331 -0.41064 0.00366467 0.071692 -0.411422 -4.34485e-08 0.0700323 -0.411478 0.00371826 0.0700368 -0.414645 0.00380169 0.0666152 -0.415561 -4.18574e-08 0.0657925 -0.414985 0.00741382 0.0666061 -0.417211 0.0140567 0.066427 -0.421061 0.0145249 0.0630625 -0.424805 0.0210565 0.0626043 -0.42155 0.0200981 0.0659117 -0.427194 0.0242744 0.062254 -0.437604 0.0341474 0.0816067 -0.435484 0.0318164 0.0817183 -0.455456 -0.0353165 0.0814893 -0.440994 -0.0406037 0.0802144 -0.441109 -0.0410706 0.0800335 -0.45567 -0.0457003 0.0775536 -0.441783 -0.0491883 0.0747688 -0.455795 -0.0482866 0.0755732 -0.441888 -0.0507012 0.0732732 -0.441934 -0.0513225 0.0726009 -0.4423 -0.0559178 0.0662112 -0.442567 -0.0577016 0.062618 -0.456824 -0.0583265 0.061054 -0.457206 -0.0598622 0.0554153 -0.457472 -0.0603043 0.0515125 -0.443769 -0.0601852 0.053068 -0.457845 -0.0603122 0.0469203 -0.455439 -0.0294575 0.081735 -0.448173 -0.00600004 0.081735 -0.455439 -4.19898e-08 0.081735 -0.438473 -0.0205083 0.081735 -0.441701 -0.0187016 0.081735 -0.444408 0.0603612 0.0493051 -0.457657 0.0603608 0.0490783 -0.443769 0.0601851 0.053068 -0.457365 0.0601868 0.053048 -0.443221 0.0595986 0.056747 -0.442713 0.0583269 0.0610527 -0.442567 0.0577015 0.062618 -0.4566 0.0569578 0.064241 -0.456343 0.0549582 0.0678086 -0.45609 0.052427 0.0713146 -0.455881 0.0496828 0.074301 -0.455483 0.0381224 0.0809804 -0.44043 0.0388661 0.0807844 -0.455505 0.0396636 0.0805426 -0.455533 0.0411528 0.0799996 -0.441653 0.0463896 0.0770699 -0.438473 0.0324681 0.0817004 -0.439357 0.0366538 0.0812902 -0.438473 0.0352879 0.0814927 -0.455454 0.0350591 0.0815195 -0.455439 0.0294574 0.081735 -0.457638 0.0294574 0.0815617 -0.461619 0.0294574 0.0801538 -0.463277 -4.19898e-08 0.0789402 -0.464657 -4.19898e-08 0.0774185 -0.464657 0.0294574 0.0774185 -0.466473 -4.19898e-08 0.0736064 -0.466473 0.0294574 0.0736064 -0.466876 -4.19898e-08 0.0714371 -0.457638 -0.0294575 0.0815617 -0.457638 -4.19898e-08 0.0815617 -0.459722 -4.19898e-08 0.0810335 -0.461619 -4.19898e-08 0.0801538 -0.464657 -0.0294575 0.0774185 -0.46573 -4.19898e-08 0.0756235 -0.46573 -0.0294575 0.0756235 -0.466876 -0.0294575 0.0714371 -0.469435 0.0487595 0.0470914 -0.468512 0.0482764 0.0558703 -0.467373 0.051955 0.0594354 -0.468263 0.0506114 0.0564066 -0.468319 0.0477423 0.0577008 -0.467125 0.0509072 0.0618691 -0.46667 0.0482344 0.0663248 -0.468171 0.0535637 0.0515796 -0.467198 0.0555521 0.0515352 -0.466919 0.0552792 0.0543509 -0.468766 0.0513023 0.0515753 -0.468514 0.0510872 0.0539933 -0.467903 0.053314 0.0542084 -0.467635 0.0527747 0.0568578 -0.462227 0.0595376 0.0511416 -0.459721 0.0598582 0.0541922 -0.461677 0.0585982 0.0576377 -0.459464 0.0592115 0.0575609 -0.459214 0.0582133 0.0608168 -0.458976 0.0569407 0.0638482 -0.463366 0.0385623 0.0779458 -0.462006 0.0457117 0.0755626 -0.46406 0.0493547 0.0704571 -0.46262 0.0523031 0.0687643 -0.457657 0.0352684 0.0813203 -0.457716 0.039544 0.0803979 -0.460275 0.0489534 0.0739958 -0.458147 0.0494419 0.0742836 -0.457976 0.0467869 0.0765544 -0.459931 0.0431945 0.0782486 -0.457828 0.0435452 0.0786673 -0.45558 0.0430786 0.0791147 -0.459807 0.0393182 0.0799126 -0.46164 0.0350492 0.0799275 -0.461708 0.0389887 0.0790896 -0.461838 0.0426792 0.0775145 -0.460093 0.0463535 0.0762043 -0.462195 0.0482246 0.073439 -0.460475 0.0511923 0.0716469 -0.4624 0.050398 0.0711703 -0.463098 0.0554195 0.063557 -0.464759 0.0541908 0.0631539 -0.465021 0.0553784 0.0604023 -0.465299 0.0563165 0.0574601 -0.463923 0.0582678 0.0544172 -0.46587 0.0572238 0.0514458 -0.466492 0.0341939 0.0734305 -0.466944 0.0361863 0.0707825 -0.467049 0.0383718 0.0697871 -0.466802 0.0413903 0.0704372 -0.467398 0.0424469 0.0664667 -0.467662 0.0444987 0.0639581 -0.463277 0.0294574 0.0789402 -0.46575 0.0344482 0.0754334 -0.464744 0.0380475 0.0765051 -0.46487 0.0411999 0.0751673 -0.465932 0.040267 0.0736036 -0.466088 0.0426871 0.0720493 -0.465034 0.0438595 0.0734638 -0.466265 0.0447666 0.0702952 -0.465422 0.0480818 0.069521 -0.465639 0.0498228 0.0673326 -0.46573 0.0294574 0.0756235 -0.465813 0.0374561 0.0747996 -0.466549 0.0368054 0.0728774 -0.466657 0.039238 0.071832 -0.467352 0.0464641 0.0651518 -0.466969 0.0432767 0.0688326 -0.467784 0.0489225 0.0610119 -0.467973 0.0463202 0.0609969 -0.468073 0.0467927 0.0600447 -0.460376 0.060076 0.0456453 -0.459977 0.060136 0.0509305 -0.457114 0.0595878 0.0567954 -0.456852 0.0584744 0.0606473 -0.464206 0.0585587 0.0513142 -0.461953 0.0592492 0.0543412 -0.463637 0.0576256 0.0576033 -0.46336 0.0566521 0.0606836 -0.461408 0.0576044 0.0608232 -0.461154 0.056343 0.0637904 -0.460689 0.053149 0.0691623 -0.45875 0.0554406 0.0666706 -0.458537 0.0537069 0.0693356 -0.458334 0.0517204 0.0718765 -0.455723 0.0468916 0.0766981 -0.455609 0.044058 0.0785812 -0.466639 0.0546915 0.0572109 -0.465586 0.0569378 0.0544202 -0.466366 0.0538043 0.0599845 -0.466109 0.0526781 0.0625884 -0.46428 0.0511876 0.0681506 -0.46522 0.0461102 0.0715704 -0.463854 0.0472707 0.0726252 -0.463665 0.0448749 0.0746429 -0.463497 0.0420099 0.0764803 -0.464677 0.0346797 0.077215 -0.463297 0.0348816 0.0787245 -0.459722 0.0294574 0.0810335 -0.459742 0.035179 0.0807986 -0.455439 0.0311945 0.0817287 -0.46428 -0.0511876 0.0681506 -0.456703 -0.0576283 0.0627883 -0.456957 -0.0589771 0.0591222 -0.459464 -0.0592116 0.0575609 -0.457085 -0.0594907 0.0572191 -0.459977 -0.0601361 0.0509305 -0.462227 -0.0595376 0.0511416 -0.459721 -0.0598583 0.0541922 -0.459214 -0.0582134 0.0608168 -0.467352 -0.0464642 0.0651518 -0.467903 -0.0533141 0.0542084 -0.467635 -0.0527747 0.0568578 -0.467125 -0.0509072 0.0618691 -0.468263 -0.0506115 0.0564066 -0.467784 -0.0489226 0.0610119 -0.468387 -0.0479518 0.0570539 -0.46487 -0.0412 0.0751673 -0.463497 -0.0420099 0.0764803 -0.465034 -0.0438596 0.0734638 -0.46406 -0.0493548 0.0704571 -0.463854 -0.0472708 0.0726252 -0.467373 -0.0519551 0.0594354 -0.46667 -0.0482345 0.0663248 -0.466265 -0.0447667 0.0702952 -0.466802 -0.0413903 0.0704372 -0.46575 -0.0344483 0.0754334 -0.464677 -0.0346798 0.077215 -0.465813 -0.0374562 0.0747996 -0.464744 -0.0380476 0.0765051 -0.465932 -0.0402671 0.0736036 -0.466088 -0.0426872 0.0720493 -0.467198 -0.0555522 0.0515352 -0.466919 -0.0552792 0.0543509 -0.466639 -0.0546916 0.0572109 -0.465021 -0.0553785 0.0604023 -0.466366 -0.0538044 0.0599845 -0.466109 -0.0526782 0.0625884 -0.464759 -0.0541909 0.0631539 -0.465639 -0.0498229 0.0673326 -0.465422 -0.0480819 0.069521 -0.46522 -0.0461102 0.0715704 -0.459722 -0.0294575 0.0810335 -0.455447 -0.0338541 0.0816307 -0.456175 -0.0533586 0.070122 -0.45875 -0.0554406 0.0666706 -0.458537 -0.053707 0.0693356 -0.458334 -0.0517205 0.0718765 -0.455962 -0.0508512 0.0731156 -0.455578 -0.0430264 0.0791415 -0.457828 -0.0435453 0.0786673 -0.457716 -0.0395441 0.0803979 -0.455511 -0.0400345 0.0804187 -0.45547 -0.0369454 0.0812367 -0.464657 -0.0585418 0.0461622 -0.464206 -0.0585588 0.0513142 -0.461953 -0.0592493 0.0543412 -0.463923 -0.0582679 0.0544172 -0.461677 -0.0585983 0.0576377 -0.461408 -0.0576044 0.0608232 -0.46336 -0.0566522 0.0606836 -0.461154 -0.0563431 0.0637904 -0.460689 -0.0531491 0.0691623 -0.4624 -0.0503981 0.0711703 -0.460475 -0.0511924 0.0716469 -0.460275 -0.0489535 0.0739958 -0.462195 -0.0482246 0.073439 -0.462006 -0.0457118 0.0755626 -0.459931 -0.0431946 0.0782486 -0.459742 -0.0351791 0.0807986 -0.46164 -0.0350493 0.0799275 -0.461619 -0.0294575 0.0801538 -0.457657 -0.0352685 0.0813203 -0.459807 -0.0393183 0.0799126 -0.460093 -0.0463536 0.0762043 -0.457976 -0.046787 0.0765544 -0.458147 -0.0494419 0.0742836 -0.458976 -0.0569408 0.0638482 -0.456424 -0.0556464 0.0666846 -0.46768 -0.0555391 0.0466109 -0.468171 -0.0535637 0.0515796 -0.468657 -0.0535372 0.046801 -0.468766 -0.0513024 0.0515753 -0.469247 -0.0512509 0.0469629 -0.469033 -0.0488591 0.0509071 -0.468514 -0.0510873 0.0539933 -0.468512 -0.0482765 0.0558703 -0.468071 -0.0467841 0.0600632 -0.467673 -0.0445734 0.0638529 -0.466969 -0.0432767 0.0688326 -0.466657 -0.0392381 0.071832 -0.466549 -0.0368055 0.0728774 -0.466966 -0.0367433 0.0705804 -0.466903 -0.0345767 0.071181 -0.46634 -0.0572135 0.0463971 -0.46587 -0.0572239 0.0514458 -0.465586 -0.0569379 0.0544202 -0.463637 -0.0576257 0.0576033 -0.465299 -0.0563165 0.0574601 -0.463098 -0.0554196 0.063557 -0.46262 -0.0523032 0.0687643 -0.463665 -0.044875 0.0746429 -0.461838 -0.0426793 0.0775145 -0.461708 -0.0389888 0.0790896 -0.463366 -0.0385623 0.0779458 -0.463277 -0.0294575 0.0789402 -0.463297 -0.0348817 0.0787245 -0.466492 -0.034194 0.0734305 -0.466473 -0.0294575 0.0736064 -0.466893 -0.033926 0.0712757 -0.466877 -0.0315694 0.071423 -0.421105 -0.0217 0.0756501 -0.421774 -0.0217 0.0780542 -0.422262 -0.0217 0.0792284 -0.419847 -0.0207971 0.073735 -0.420893 -0.0217 0.073735 -0.448173 -0.00600004 0.073735 -0.410346 -0.000133166 0.073735 -0.418093 0.0191983 0.073735 -0.432473 0.0217 0.073735 -0.414169 -0.0148507 0.073735 -0.416458 -0.0175648 0.073735 -0.447405 -0.0108516 0.073735 -0.445175 0.0152282 0.073735 -0.441701 0.0187015 0.073735 -0.448173 0.00599996 0.073735 -0.411759 -0.010593 0.073735 -0.410822 0.00739727 0.073735 -0.410431 0.00418539 0.073735 -0.422824 0.0217 0.0803476 -0.437325 0.0209315 0.081735 -0.437325 0.0209315 0.073735 -0.441701 0.0187015 0.081735 -0.447405 0.0108515 0.073735 -0.447405 0.0108515 0.081735 -0.448173 -4.19898e-08 0.081735 -0.447405 -0.0108516 0.081735 -0.445175 -0.0152283 0.081735 -0.445175 -0.0152283 0.073735 -0.441701 -0.0187016 0.073735 -0.437325 -0.0209316 0.073735 -0.437325 -0.0209316 0.081735 -0.432473 -0.0217 0.073735 -0.440665 0.0420032 -0.0580182 -0.442069 0.0459006 -0.0565284 -0.438911 0.0472907 -0.0555556 -0.442784 0.0480297 -0.0549043 -0.443598 0.0501686 -0.0521585 -0.443838 0.0506627 -0.0511879 -0.440254 0.0506627 -0.051188 -0.44411 0.0511213 -0.0500161 -0.433413 -0.0352094 -0.058235 -0.430779 0.0228984 -0.058235 -0.428197 0.0168718 -0.058235 -0.434753 0.0375952 -0.058235 -0.437047 0.0342203 -0.058235 -0.43937 0.0388978 -0.058235 -0.427025 0.0249589 -0.058235 -0.434179 0.0291217 -0.058235 -0.428362 -0.0271317 -0.058235 -0.423582 -0.0184585 -0.058235 -0.427056 -0.0129126 -0.058235 -0.422149 -0.0147356 -0.058235 -0.421139 -0.0108759 -0.058235 -0.420528 -0.00644448 -0.058235 -0.426033 -0.00478932 -0.058235 -0.42602 0.00443975 -0.058235 -0.420399 0.00422169 -0.058235 -0.426332 0.00871718 -0.058235 -0.420715 0.00826652 -0.058235 -0.42143 0.0121932 -0.058235 -0.439734 -0.0397326 -0.058235 -0.441163 -0.0433111 -0.057689 -0.437493 -0.0434699 -0.0576382 -0.441484 -0.0441995 -0.0573726 -0.441914 -0.0454412 -0.0567902 -0.442412 -0.046926 -0.0558399 -0.442784 -0.0480295 -0.0549046 -0.439173 -0.048029 -0.054905 -0.439854 -0.0498122 -0.0527467 -0.443414 -0.0497395 -0.0528578 -0.443838 -0.0506629 -0.0511878 -0.447359 -0.053994 0.00529689 -0.450579 -0.0542104 0.0102536 -0.444811 -0.0517212 -0.0467584 -0.445285 -0.0526489 -0.02551 -0.450587 -0.0532961 -0.010687 -0.447239 -0.0534023 -0.00825492 -0.44505 -0.0557354 0.0451816 -0.449747 -0.0545721 0.0185379 -0.441343 -0.0557465 0.0457968 -0.441471 -0.0557354 0.0451816 -0.443195 -0.0530821 0.0532451 -0.439384 -0.0524145 0.0540039 -0.439014 -0.0512462 0.055073 -0.442213 -0.0498956 0.05601 -0.438511 -0.0496089 0.0561758 -0.438148 -0.048456 0.0567424 -0.440848 -0.0555006 0.0481236 -0.444095 -0.0550902 0.0496202 -0.444024 -0.0549777 0.0499321 -0.444557 0.055608 0.0475244 -0.444175 0.0552061 0.0492663 -0.440978 0.0556082 0.0475234 -0.440444 0.0549776 0.0499321 -0.44367 0.0542938 0.0514287 -0.443283 0.0533293 0.0529283 -0.442972 0.0524147 0.0540036 -0.44276 0.0517406 0.0546548 -0.441731 0.0482658 0.0568216 -0.447239 0.0540998 0.00772201 -0.449214 0.0547432 0.0224583 -0.445715 0.0527707 -0.0227196 -0.449722 0.0529218 -0.0192588 -0.450957 0.0536574 -0.00241037 -0.450973 0.0537511 -0.000264971 -0.447197 0.0552624 0.0343501 -0.446039 0.0546317 0.0199055 -0.446763 0.0521431 -0.0370938 -0.448427 0.0525414 -0.0279704 -0.427081 -0.0139335 0.057705 -0.421427 -0.0129235 0.057705 -0.423807 -0.0201452 0.057705 -0.426265 -0.0251799 0.057705 -0.435215 -0.0331611 0.057705 -0.429007 -0.029979 0.057705 -0.437803 -0.0381873 0.057705 -0.434546 -0.0396802 0.057705 -0.42638 0.00973182 0.057705 -0.430555 0.032581 0.057705 -0.428778 0.0295917 0.057705 -0.4265 0.0256113 0.057705 -0.428326 0.0184639 0.057705 -0.422853 0.0177436 0.057705 -0.420848 0.00978462 0.057705 -0.425989 0.00342149 0.057705 -0.420413 0.00484307 0.057705 -0.42597 -4.19898e-08 0.057705 -0.426023 -0.00480743 0.057705 -0.437142 0.0172713 -0.077765 -0.437142 0.0172713 -0.084765 -0.438019 0.0168668 -0.084765 -0.4411 0.0146267 -0.077765 -0.443745 0.0106687 -0.084765 -0.444439 0.00838006 -0.084765 -0.414884 -0.0186178 -0.077765 -0.414884 0.0186177 -0.077765 -0.414407 0.0181221 -0.077765 -0.410087 0.0119149 -0.077765 -0.409139 0.00926594 -0.077765 -0.415375 0.0182601 -0.077765 -0.408439 0.00333414 -0.077765 -0.408461 9.72813e-07 -0.077765 -0.410367 -0.0125069 -0.077765 -0.415135 -0.0183797 -0.077765 -0.41217 -0.0154534 -0.077765 -0.432473 0.0182 -0.077765 -0.408448 -0.00396151 -0.077765 -0.41545 -0.0182372 -0.077765 -0.415259 -0.0183082 -0.077765 -0.409142 -0.00927739 -0.077765 -0.443745 0.0106687 -0.077765 -0.444673 -0.00600004 -0.077765 -0.444673 0.00599996 -0.077765 -0.444673 -4.19898e-08 -0.084765 -0.444216 -0.00930979 -0.084765 -0.442877 -0.0123713 -0.084765 -0.443745 -0.0106688 -0.077765 -0.443745 -0.0106688 -0.084765 -0.438019 -0.0168669 -0.084765 -0.437142 -0.0172714 -0.077765 -0.4411 -0.0146267 -0.077765 -0.440759 -0.0149549 -0.084765 -0.4411 -0.0146267 -0.084765 -0.437142 -0.0172714 -0.084765 -0.435325 -0.0178621 -0.084765 -0.433882 0.0281808 -0.085765 -0.429852 0.0248081 -0.085765 -0.432473 0.0182 -0.084765 -0.415731 0.0182 -0.077765 -0.41593 0.0182 -0.0783743 -0.422345 0.0182 -0.0847609 -0.420745 0.0182 -0.0845235 -0.416967 0.0182 -0.080726 -0.414731 0.0188826 -0.0777205 -0.414631 0.0195082 -0.0773552 -0.413819 0.0186767 -0.0773542 -0.414778 0.0199067 -0.07692 -0.407492 0.00334245 -0.0770864 -0.414775 0.0199032 -0.0769249 -0.413689 0.0187998 -0.076924 -0.411522 0.0159264 -0.0773623 -0.407649 0.00649675 -0.0770449 -0.407851 0.00647413 -0.0774189 -0.414077 0.0184332 -0.0776564 -0.41079 0.0148577 -0.0773665 -0.409687 0.0120955 -0.0776634 -0.409368 0.0122394 -0.0773795 -0.408391 0.00946739 -0.077397 -0.40819 0.00643627 -0.0776743 -0.407701 0.00334061 -0.0774406 -0.407733 -2.79473e-08 -0.0774507 -0.411808 0.015718 -0.0776586 -0.41217 0.0154533 -0.077765 -0.411086 0.0146662 -0.0776598 -0.411461 0.0144238 -0.077765 -0.408725 0.00937744 -0.0776683 -0.408603 0.00639002 -0.077765 -0.408036 0.00333767 -0.0776803 -0.408065 4.27777e-07 -0.077683 -0.433882 -0.0281809 -0.085765 -0.432473 -0.0192 -0.085765 -0.411522 -0.0159264 -0.0773623 -0.414775 -0.0199033 -0.0769249 -0.411808 -0.015718 -0.0776586 -0.409972 -0.0127028 -0.0776625 -0.408682 -0.00701109 -0.077765 -0.408267 -0.00706976 -0.077673 -0.408043 -0.00397102 -0.0776792 -0.408728 -0.00938918 -0.0776683 -0.408394 -0.00947936 -0.077397 -0.409658 -0.0128585 -0.0773761 -0.407708 -0.00397889 -0.0774366 -0.407729 -0.00714592 -0.0770358 -0.407929 -0.00711764 -0.0774141 -0.409489 -0.0129422 -0.0769645 -0.416967 -0.0182 -0.080726 -0.41593 -0.0182 -0.0783743 -0.432473 -0.0182 -0.077765 -0.415731 -0.0182 -0.077765 -0.421007 -0.0182 -0.0845899 -0.420239 -0.0182 -0.0843588 -0.418433 -0.0182 -0.0830699 -0.419098 -0.0182 -0.0837411 -0.438473 -0.0332984 -0.0857434 -0.436694 -0.031 -0.085765 -0.438226 0.0467904 -0.0765825 -0.410221 0.0148592 -0.073765 -0.41261 0.0176636 -0.0766602 -0.416313 0.0216588 -0.073765 -0.421047 0.0254 -0.0759374 -0.420962 0.025475 -0.073765 -0.427139 0.0302643 -0.0752984 -0.432655 0.0354899 -0.074853 -0.435727 0.0397763 -0.073765 -0.434904 0.038438 -0.073765 -0.434537 0.0379029 -0.073765 -0.438371 0.0489001 -0.073765 -0.437084 0.0413566 -0.0778962 -0.43804 0.0426973 -0.0802953 -0.437658 0.0409525 -0.0808248 -0.435994 0.0376516 -0.0806788 -0.436458 0.0370933 -0.0828499 -0.435455 0.0354132 -0.0831387 -0.433733 0.0347256 -0.0807338 -0.428278 0.029461 -0.0811583 -0.427634 0.0276335 -0.0835251 -0.433956 0.0334562 -0.083336 -0.434739 0.0344243 -0.083249 -0.422297 0.0245276 -0.0817603 -0.411375 0.0160341 -0.0769389 -0.410635 0.0149579 -0.0769467 -0.408735 0.0121321 -0.073765 -0.410415 0.0146964 -0.0766931 -0.408723 0.011413 -0.0765565 -0.409195 0.0123174 -0.0769707 -0.410452 0.014669 -0.076949 -0.407521 -4.19901e-08 -0.0771059 -0.437695 0.0405704 -0.0815604 -0.435304 0.0381283 -0.0777891 -0.408201 0.0095184 -0.0770036 -0.407622 0.00775786 -0.0762207 -0.407421 0.00790607 -0.0747275 -0.407099 0.00373958 -0.0756903 -0.4069 0.00388614 -0.0741963 -0.41519 0.0203885 -0.0764976 -0.415702 0.020023 -0.0794469 -0.421492 0.0250772 -0.0789096 -0.427522 0.0299801 -0.0782913 -0.433017 0.0352193 -0.0778531 -0.434922 0.0384124 -0.0747962 -0.436699 0.0416422 -0.074904 -0.437874 0.0452504 -0.0752147 -0.438144 0.0450376 -0.0782458 -0.438151 0.0446745 -0.0787241 -0.463973 0.0488999 -0.0793564 -0.465178 0.050402 -0.0778067 -0.466118 0.0525182 -0.0751764 -0.466757 0.0544226 -0.0722325 -0.464054 0.0556809 -0.0701386 -0.464156 0.0573131 -0.0663252 -0.467137 0.0560739 -0.0690163 -0.464166 0.0574279 -0.065999 -0.467313 0.0583934 -0.0619691 -0.464732 0.0594228 -0.053765 -0.467097 0.0596661 -0.0469946 -0.470184 0.0592297 -0.0491396 -0.470714 0.0580795 -0.060109 -0.470755 0.0585738 -0.0562669 -0.47277 0.0581593 -0.0550728 -0.47663 0.0549968 -0.0624279 -0.476741 0.0536326 -0.0660361 -0.476311 0.0521529 -0.0696968 -0.481456 0.0401856 -0.075215 -0.479873 0.0344693 -0.0791561 -0.478438 0.0312175 -0.0809288 -0.471671 0.0309916 -0.0848363 -0.471539 0.0329832 -0.0848036 -0.463973 0.0404716 -0.0845726 -0.463973 0.0362169 -0.085536 -0.466522 0.0390221 -0.0849017 -0.481082 0.0373332 -0.0769875 -0.481557 0.0384286 -0.0759359 -0.474582 0.0309804 -0.0836005 -0.46894 0.0359038 -0.085178 -0.467651 0.0333373 -0.0855984 -0.475173 0.0400339 -0.081573 -0.474972 0.0481395 -0.0763924 -0.476462 0.0429798 -0.0791679 -0.475736 0.0503205 -0.073168 -0.478322 0.0477925 -0.0732379 -0.478979 0.049686 -0.069848 -0.479249 0.0504259 -0.0682258 -0.480753 0.045023 -0.0726918 -0.479887 0.0427885 -0.0756958 -0.477496 0.0455603 -0.0763662 -0.478844 0.0402164 -0.0783677 -0.47759 0.0372806 -0.0806499 -0.476061 0.0339529 -0.0824897 -0.473559 0.0367025 -0.083489 -0.46735 0.0438435 -0.0828679 -0.468547 0.042392 -0.0834049 -0.465384 0.0406407 -0.084483 -0.464283 0.0422722 -0.0838625 -0.475397 0.0563153 -0.0600087 -0.473997 0.0566511 -0.061438 -0.473474 0.0542986 -0.0689344 -0.470643 0.0572693 -0.0638902 -0.470473 0.0560713 -0.0675552 -0.469591 0.0525992 -0.0743026 -0.4714 0.048106 -0.0786816 -0.468779 0.0504169 -0.0772762 -0.466178 0.0452837 -0.0821285 -0.467131 0.0592845 -0.0545069 -0.467226 0.0589867 -0.0582611 -0.467305 0.0574154 -0.0655755 -0.470139 0.054499 -0.0710446 -0.467659 0.0479817 -0.0799062 -0.463973 0.0484567 -0.0797648 -0.478403 0.0522652 -0.0662228 -0.473786 0.0556576 -0.0652486 -0.473006 0.0525699 -0.0724396 -0.473971 0.0456158 -0.0793053 -0.472332 0.0504968 -0.0757088 -0.472678 0.0427445 -0.0818292 -0.470158 0.0454095 -0.0812829 -0.471019 0.0395099 -0.0838406 -0.438473 0.0332983 -0.0857434 -0.451837 0.0327072 -0.085756 -0.439723 0.0355122 -0.0856134 -0.44137 0.0404697 -0.0845732 -0.456501 0.0364207 -0.0855099 -0.441409 0.0406622 -0.0845067 -0.442069 0.0464452 -0.0814092 -0.463973 0.0457776 -0.0818844 -0.463973 0.0479513 -0.0802095 -0.442186 0.0490603 -0.0792048 -0.442258 0.0503144 -0.0779313 -0.442359 0.0517034 -0.0763279 -0.463976 0.0514223 -0.0766701 -0.442307 0.0510239 -0.0771395 -0.463974 0.0503595 -0.077882 -0.442261 0.0503598 -0.0778822 -0.463998 0.0537022 -0.0735814 -0.464017 0.0545845 -0.0721582 -0.442605 0.0548577 -0.071684 -0.464487 0.0591247 -0.0582861 -0.464418 0.0589482 -0.0597017 -0.464304 0.0584811 -0.0622715 -0.479923 -0.00797133 -0.0810544 -0.482817 -0.0234613 -0.0766021 -0.480864 -0.0216901 -0.0793629 -0.47967 -4.19898e-08 -0.0814108 -0.479826 -0.00612773 -0.0811952 -0.48016 -4.23227e-08 -0.0809876 -0.482091 -4.40652e-08 -0.0788397 -0.484115 -0.015509 -0.0744899 -0.485076 -5.32762e-08 -0.0682441 -0.484992 -5.01213e-08 -0.0717746 -0.484784 -4.9137e-08 -0.0728952 -0.484989 -0.00768328 -0.071559 -0.484019 -0.00779676 -0.0751921 -0.482951 -4.5154e-08 -0.0775339 -0.484907 -0.0302464 -0.0666352 -0.485027 -0.0151393 -0.067778 -0.484947 -0.030387 -0.0688516 -0.484974 -0.0153204 -0.071024 -0.484205 -0.0232177 -0.0735534 -0.483866 -0.0306873 -0.0737035 -0.482231 -0.00789704 -0.0785002 -0.482518 -0.0156782 -0.0776845 -0.484115 0.0155097 -0.0744898 -0.484974 0.015321 -0.0710239 -0.484907 0.0302463 -0.0666352 -0.482518 0.0156788 -0.0776844 -0.481012 0.0236499 -0.0790328 -0.482231 0.00789701 -0.0785002 -0.484019 0.00779673 -0.075192 -0.48397 -4.68954e-08 -0.075483 -0.4846 0.0305385 -0.0712798 -0.484896 0.0304251 -0.0694587 -0.482817 0.0234618 -0.076602 -0.483094 0.0307895 -0.0754003 -0.484267 0.0306163 -0.0725425 -0.485024 0.015638 -0.0677498 -0.484989 0.00768325 -0.071559 -0.479923 0.0079713 -0.0810544 -0.483344 0.0439071 -0.0517645 -0.471133 0.0593646 -0.0428742 -0.478099 0.0540948 -0.061942 -0.484243 0.0343256 -0.0718882 -0.484278 0.030614 -0.0725054 -0.481618 0.0354533 -0.0768969 -0.482808 0.0308204 -0.0759177 -0.483086 0.0349627 -0.0746836 -0.48159 0.0374733 -0.0762801 -0.481773 0.0471003 -0.0681335 -0.480873 0.0447317 -0.0727802 -0.481027 0.0438539 -0.0733198 -0.482934 0.0392738 -0.0731532 -0.479873 0.0487093 -0.0698237 -0.47841 0.0522527 -0.0662375 -0.474086 0.0573686 -0.0575443 -0.474781 0.0574448 -0.054578 -0.473503 0.0582289 -0.0514167 -0.471176 0.0588721 -0.0517242 -0.466153 0.0603569 -0.0323709 -0.467807 0.0599431 -0.0405214 -0.468451 0.0597672 -0.0431801 -0.473455 0.0587937 -0.0315455 -0.473767 0.058636 -0.0315059 -0.477568 0.05566 -0.0309793 -0.476949 0.0563195 -0.0310726 -0.479441 0.0528591 -0.0306621 -0.480093 0.0530121 -0.0415541 -0.478408 0.0552575 -0.0418649 -0.481986 0.047689 -0.041038 -0.481943 0.0497608 -0.0468151 -0.481291 0.0504531 -0.0412757 -0.480838 0.0522238 -0.0471239 -0.482908 0.0480732 -0.0592232 -0.48344 0.0460489 -0.0622409 -0.483809 0.0416486 -0.0685846 -0.484852 0.0336364 -0.0689317 -0.484735 0.0368104 -0.0678127 -0.483199 0.0462504 -0.0521109 -0.482675 0.0485974 -0.0524978 -0.483847 0.0444094 -0.0577779 -0.483093 0.0476074 -0.0554821 -0.482582 0.0471387 -0.0465429 -0.481754 0.0508602 -0.0529144 -0.482322 0.0496837 -0.0560367 -0.483518 0.0462409 -0.0584856 -0.48391 0.044492 -0.0613212 -0.483895 0.0435839 -0.0649912 -0.484254 0.0423225 -0.0639063 -0.484107 0.0380903 -0.0705551 -0.47985 0.0487786 -0.0697636 -0.479567 0.0528968 -0.0613473 -0.480782 0.0502876 -0.0648897 -0.480895 0.0514638 -0.060681 -0.479827 0.0534052 -0.0571478 -0.476889 0.0562899 -0.0541933 -0.475843 0.0571552 -0.0510658 -0.47505 0.0577196 -0.0481621 -0.477326 0.056278 -0.0478101 -0.469711 0.0600331 -0.0319909 -0.472553 0.058721 -0.0485029 -0.478195 0.0549129 -0.0576632 -0.476398 0.0561248 -0.0581285 -0.479598 0.051392 -0.0656314 -0.47794 0.0531019 -0.0651847 -0.484768 0.0356173 -0.0653144 -0.484534 0.0397453 -0.0661087 -0.484422 0.0410933 -0.0628683 -0.484614 0.0379599 -0.0638493 -0.484331 0.0405172 -0.0611597 -0.484149 0.0429584 -0.0604387 -0.483524 0.0454937 -0.0549547 -0.483381 0.0438554 -0.0521196 -0.482501 0.0433967 -0.070926 -0.483348 0.0448314 -0.0660844 -0.482745 0.0475713 -0.063165 -0.482024 0.0498368 -0.0599643 -0.478806 0.0547787 -0.0537781 -0.481222 0.0516416 -0.0565989 -0.48045 0.0529479 -0.0533465 -0.477975 0.0556764 -0.0506971 -0.479282 0.0544255 -0.0474597 -0.476292 0.0570988 -0.042197 -0.473831 0.0584759 -0.0425377 -0.484898 -0.030424 -0.0694406 -0.4743 -0.0583436 -0.0314376 -0.476292 -0.057099 -0.0421958 -0.471133 -0.0593648 -0.042873 -0.466152 -0.0603565 -0.0323831 -0.470458 -0.0591359 -0.0499075 -0.47277 -0.0581594 -0.0550728 -0.476397 -0.0561266 -0.0581247 -0.478408 -0.0522566 -0.066233 -0.478393 -0.0522852 -0.066199 -0.479597 -0.0513958 -0.065627 -0.477987 -0.0530204 -0.06529 -0.475536 -0.0561841 -0.0602758 -0.480812 -0.0480508 -0.0690151 -0.481134 -0.0431537 -0.073725 -0.481456 -0.040193 -0.0752117 -0.481607 -0.0366544 -0.0765486 -0.483069 -0.0307925 -0.0754484 -0.484865 -0.0329984 -0.0662322 -0.477967 -0.0551803 -0.0309167 -0.478408 -0.0552577 -0.0418637 -0.473813 -0.0586123 -0.0315002 -0.478805 -0.0547798 -0.0537753 -0.481221 -0.0516432 -0.0565955 -0.482024 -0.0498391 -0.0599606 -0.48263 -0.0460222 -0.0671408 -0.482744 -0.0475745 -0.0631612 -0.472553 -0.0587214 -0.048501 -0.473503 -0.0582295 -0.0514144 -0.475843 -0.0571558 -0.0510634 -0.47478 -0.0574457 -0.054575 -0.478097 -0.0540976 -0.0619378 -0.48078 -0.0502912 -0.0648855 -0.470122 -0.0599478 -0.0319442 -0.473831 -0.0584761 -0.0425364 -0.477326 -0.0562784 -0.0478083 -0.47505 -0.05772 -0.0481602 -0.477975 -0.0556771 -0.0506948 -0.476887 -0.056291 -0.0541904 -0.478194 -0.0549147 -0.0576595 -0.479566 -0.0528994 -0.0613432 -0.479826 -0.0534069 -0.0571442 -0.480894 -0.0514663 -0.0606771 -0.481772 -0.047105 -0.0681294 -0.481845 -0.0490047 -0.0640547 -0.4825 -0.0434025 -0.0709223 -0.482934 -0.0392806 -0.0731502 -0.484107 -0.0380962 -0.0705525 -0.483086 -0.03497 -0.0746817 -0.484243 -0.034332 -0.0718865 -0.484267 -0.0306164 -0.0725423 -0.4848 -0.0349385 -0.0656139 -0.484735 -0.0368153 -0.0678105 -0.480932 -0.0478048 -0.0302876 -0.481986 -0.0476892 -0.0410368 -0.481489 -0.0451908 -0.0341122 -0.483165 -0.0441192 -0.0500634 -0.483907 -0.0426429 -0.057119 -0.483847 -0.0444109 -0.0577748 -0.47936 -0.0530191 -0.0306775 -0.480093 -0.0530123 -0.0415529 -0.481291 -0.0504533 -0.0412745 -0.481943 -0.0497611 -0.0468133 -0.482674 -0.0485983 -0.0524952 -0.482322 -0.0496852 -0.0560335 -0.483093 -0.0476087 -0.055479 -0.483909 -0.0444945 -0.0613178 -0.482581 -0.047139 -0.0465411 -0.483199 -0.046251 -0.0521084 -0.483523 -0.0454947 -0.0549518 -0.483518 -0.0462427 -0.0584824 -0.484235 -0.0411346 -0.0602397 -0.484254 -0.0423257 -0.0639031 -0.484533 -0.0397494 -0.0661058 -0.479282 -0.0544259 -0.0474578 -0.480838 -0.0522242 -0.047122 -0.481753 -0.0508611 -0.0529117 -0.48045 -0.0529489 -0.0533437 -0.482908 -0.0480753 -0.0592197 -0.483348 -0.0448355 -0.0660807 -0.483808 -0.0416537 -0.0685813 -0.484852 -0.0336419 -0.0689304 -0.438151 -0.0446527 -0.0787436 -0.438144 -0.0450377 -0.0782458 -0.438225 -0.0467593 -0.0766186 -0.428278 -0.0294611 -0.0811583 -0.433733 -0.0347257 -0.0807338 -0.436458 -0.0370934 -0.0828499 -0.435455 -0.0354133 -0.0831387 -0.437987 -0.0422461 -0.0805938 -0.435994 -0.0376517 -0.0806788 -0.438328 -0.0484235 -0.0744684 -0.438291 -0.0479237 -0.0751643 -0.437874 -0.0452505 -0.0752147 -0.43808 -0.0464687 -0.073765 -0.437228 -0.0430925 -0.073765 -0.435727 -0.0397764 -0.073765 -0.436699 -0.0416422 -0.074904 -0.434904 -0.0384381 -0.073765 -0.430528 -0.0333299 -0.073765 -0.434537 -0.037903 -0.073765 -0.407622 -0.00775795 -0.0762207 -0.410221 -0.0148593 -0.073765 -0.411834 -0.0170771 -0.073765 -0.41519 -0.0203886 -0.0764976 -0.416313 -0.0216589 -0.073765 -0.420962 -0.025475 -0.073765 -0.423907 -0.0277617 -0.073765 -0.427139 -0.0302644 -0.0752984 -0.427103 -0.0303086 -0.073765 -0.40718 -0.00679634 -0.073765 -0.407301 -4.19898e-08 -0.0765011 -0.407499 -0.00398379 -0.0770787 -0.408205 -0.00953049 -0.0770034 -0.408723 -0.0114131 -0.0765565 -0.410415 -0.0146965 -0.0766931 -0.41261 -0.0176637 -0.0766602 -0.411375 -0.0160342 -0.0769389 -0.422297 -0.0245277 -0.0817603 -0.427634 -0.0276336 -0.0835251 -0.43804 -0.0426974 -0.0802953 -0.437084 -0.0413567 -0.0778962 -0.437658 -0.0409526 -0.0808248 -0.435304 -0.0381284 -0.0777891 -0.433017 -0.0352194 -0.0778531 -0.427522 -0.0299802 -0.0782913 -0.421492 -0.0250773 -0.0789096 -0.416321 -0.0198824 -0.0810697 -0.420343 -0.0220127 -0.0835034 -0.407421 -0.00790615 -0.0747275 -0.408735 -0.0121322 -0.073765 -0.4069 -0.00388622 -0.0741963 -0.407099 -0.00373966 -0.0756903 -0.406851 -1.36059e-07 -0.0744897 -0.415702 -0.0200231 -0.0794469 -0.421047 -0.0254 -0.0759374 -0.432655 -0.03549 -0.074853 -0.434922 -0.0384124 -0.0747962 -0.412899 -0.00737027 -0.0643186 -0.425404 -0.022136 -0.058235 -0.444405 -0.0564035 -0.0308715 -0.442368 -0.0559515 -0.0416848 -0.442966 -0.0520921 -0.0382632 -0.438973 -0.0485412 -0.0569464 -0.439505 -0.0520987 -0.0569078 -0.438823 -0.0470418 -0.0557521 -0.431904 -0.0340874 -0.0610018 -0.424653 -0.0244207 -0.060906 -0.41903 -0.0144383 -0.0608061 -0.417045 -4.19898e-08 -0.0607328 -0.420347 -0.00113852 -0.058235 -0.439028 -0.0540863 -0.0632765 -0.439728 -0.0553402 -0.0568799 -0.440379 -0.0508863 -0.0506616 -0.440738 -0.0513904 -0.0490805 -0.407249 -0.00721787 -0.073765 -0.410163 -0.0141035 -0.0711098 -0.412315 -0.0172313 -0.0711592 -0.40903 -0.00733578 -0.0684936 -0.408637 -4.19898e-08 -0.0684341 -0.406821 -0.00124688 -0.073765 -0.415003 -0.0201846 -0.0712077 -0.416104 -0.0204364 -0.0687638 -0.411402 -0.0142556 -0.0686094 -0.408631 -0.0107814 -0.0710644 -0.409906 -0.0108784 -0.0685437 -0.40773 -0.00728767 -0.0710261 -0.407558 -4.19898e-08 -0.0703474 -0.417329 -0.00733972 -0.0607573 -0.417957 -0.0109325 -0.0607785 -0.413663 -0.0109615 -0.0643645 -0.414976 -0.0144206 -0.0644274 -0.416818 -0.0177183 -0.0645021 -0.420546 -0.017846 -0.0608383 -0.422449 -0.0211658 -0.0608723 -0.419108 -0.020871 -0.0645811 -0.417531 -0.0206677 -0.0665726 -0.415067 -0.0175969 -0.0664856 -0.410836 -0.00736251 -0.066282 -0.409889 -4.19898e-08 -0.0668536 -0.438437 -0.0485753 -0.0696408 -0.437792 -0.0449342 -0.0694936 -0.436489 -0.0413689 -0.0693392 -0.435997 -0.0407621 -0.06108 -0.435279 -0.0394452 -0.0650564 -0.437029 -0.0429429 -0.0651888 -0.438163 -0.0465721 -0.0653413 -0.439027 -0.0514362 -0.0612532 -0.438716 -0.0502521 -0.0654862 -0.43861 -0.0514677 -0.0695416 -0.438479 -0.0478105 -0.0611949 -0.438105 -0.0450464 -0.0569864 -0.437781 -0.0441987 -0.0573729 -0.428908 -0.0317886 -0.0690362 -0.43191 -0.0347828 -0.06911 -0.434492 -0.0379687 -0.0692076 -0.424587 -0.0269218 -0.0647327 -0.427047 -0.0276393 -0.0609385 -0.427513 -0.0299187 -0.0648031 -0.429507 -0.0308511 -0.06097 -0.434107 -0.0373816 -0.061037 -0.411663 -0.0109368 -0.0663331 -0.413081 -0.0143595 -0.0664029 -0.413499 -0.0174349 -0.0686854 -0.423415 -0.0265175 -0.0667375 -0.422332 -0.0261215 -0.0689079 -0.421464 -0.0257639 -0.0712901 -0.427558 -0.0258353 -0.058235 -0.42174 -0.023922 -0.0646588 -0.430371 -0.0329669 -0.0648741 -0.433011 -0.0361255 -0.0649544 -0.436798 -0.0418241 -0.0580513 -0.437475 -0.0442426 -0.0611339 -0.450171 -0.060897 -0.0200037 -0.451431 -0.0615992 -0.00391884 -0.451473 -0.0617512 -0.000439448 -0.457998 -0.0637453 0.045235 -0.464732 -0.0594229 -0.053765 -0.465218 -0.0597592 -0.0460628 -0.444257 -0.0594229 -0.053765 -0.446296 -0.0599097 -0.0426152 -0.469248 -0.0601165 -0.0320429 -0.461964 -0.0633361 0.0456698 -0.463933 -0.0627628 0.0459017 -0.47185 -0.0594601 -0.0317423 -0.476396 -0.0568374 -0.031153 -0.478779 -0.0540342 -0.0307822 -0.468761 -0.0597372 0.0465413 -0.479131 -0.0534432 -0.0307197 -0.470973 -0.0568319 0.0469006 -0.480367 -0.0505143 -0.0304638 -0.472382 -0.0532774 0.0472039 -0.472592 0.0488596 0.0505374 -0.481074 0.0453703 -0.0301676 -0.472915 0.0487595 0.0474572 -0.482551 0.0446162 -0.0442197 -0.485076 0.000498937 -0.0682436 -0.470932 -0.0429031 0.0663322 -0.470595 -0.039353 0.0695298 -0.470373 -0.033926 0.0716415 -0.470414 -0.0358313 0.0712591 -0.470888 0.042525 0.0667489 -0.471154 0.0445733 0.0642188 -0.471398 0.0460361 0.0618902 -0.482196 -0.0448329 -0.0408446 -0.481074 -0.0453704 -0.0301676 -0.470358 -0.0316828 0.0717863 -0.47245 -0.0488459 0.0518863 -0.472303 -0.0487616 0.0532874 -0.471993 -0.0482765 0.0562361 -0.470357 0.0294574 0.071803 -0.470373 0.0339259 0.0716415 -0.470798 0.0416925 0.0675982 -0.470393 0.0350463 0.0714569 -0.470423 0.0361188 0.0711705 -0.470549 0.0386766 0.0699709 -0.483904 0.0426518 -0.0570946 -0.48417 0.0414991 -0.0596208 -0.484636 0.0376939 -0.0640545 -0.483628 0.0434188 -0.0544704 -0.484845 0.033705 -0.0660438 -0.48335 0.0438986 -0.0518242 -0.485063 0.00757294 -0.0681186 -0.484614 -0.0379631 -0.0638467 -0.485063 -0.00757297 -0.0681186 -0.483344 -0.0439076 -0.051762 -0.4838 -0.0429851 -0.0561014 -0.484574 -0.0384138 -0.0634718 -0.48441 -0.0399385 -0.061906 -0.480834 0.0484802 -0.0303269 -0.480701 0.0491942 -0.0303717 -0.48018 0.051094 -0.0305084 -0.472542 0.0525833 0.0472511 -0.471937 0.0547216 0.0470941 -0.470246 0.0579835 0.046774 -0.471282 0.0562479 0.0469587 -0.466964 0.0612145 0.0462879 -0.474653 0.0581318 -0.0313915 -0.475919 0.0572377 -0.0312202 -0.468462 0.0600227 0.0464975 -0.479068 0.0535544 -0.0307312 -0.471274 0.0596469 -0.0318106 -0.463933 0.0627627 0.0459017 -0.468577 0.0602141 -0.0321174 -0.449724 0.0627482 0.0223978 -0.447931 0.0632176 0.0331485 -0.45124 0.0621076 0.00772708 -0.451473 0.0617511 -0.000439448 -0.450171 0.0608969 -0.0200037 -0.42434 0.0200808 -0.058235 -0.422449 0.0211657 -0.0608723 -0.424653 0.0244207 -0.060906 -0.427047 0.0276393 -0.0609385 -0.429507 0.030851 -0.06097 -0.436869 0.0419856 -0.0580216 -0.435836 0.0397325 -0.058235 -0.434107 0.0373815 -0.061037 -0.437781 0.0441985 -0.057373 -0.438105 0.0450463 -0.0569864 -0.438973 0.0485411 -0.0569464 -0.439511 0.0489503 -0.0539182 -0.439173 0.0480291 -0.0549049 -0.447432 0.0576036 -0.00364687 -0.44732 0.0534687 -0.00673235 -0.446725 0.0531222 -0.0146674 -0.439461 0.0550786 -0.0589822 -0.43861 0.0514676 -0.0695416 -0.410163 0.0141034 -0.0711098 -0.419108 0.0208709 -0.0645811 -0.406818 -4.19898e-08 -0.073765 -0.406821 0.00124679 -0.073765 -0.407313 -4.19898e-08 -0.0709651 -0.40718 0.00679626 -0.073765 -0.407249 0.00721778 -0.073765 -0.41903 0.0144382 -0.0608061 -0.417957 0.0109324 -0.0607785 -0.412899 0.00737018 -0.0643186 -0.414976 0.0144205 -0.0644274 -0.413663 0.0109614 -0.0643645 -0.414526 -4.19898e-08 -0.0626636 -0.410836 0.00736243 -0.066282 -0.43808 0.0464686 -0.073765 -0.438437 0.0485752 -0.0696408 -0.438275 0.0455101 -0.0567526 -0.438479 0.0478104 -0.0611949 -0.440856 0.0515091 -0.0485397 -0.440466 0.0510267 -0.0502899 -0.439728 0.0553401 -0.0568799 -0.439946 0.0500231 -0.0524078 -0.439505 0.0520986 -0.0569078 -0.43191 0.0347827 -0.06911 -0.436489 0.0413689 -0.0693392 -0.437228 0.0430924 -0.073765 -0.43882 0.0530978 -0.0660495 -0.438716 0.050252 -0.0654862 -0.437792 0.0449341 -0.0694936 -0.434492 0.0379686 -0.0692076 -0.430371 0.0329669 -0.0648741 -0.416104 0.0204363 -0.0687638 -0.413499 0.0174348 -0.0686854 -0.409906 0.0108783 -0.0685437 -0.408631 0.0107813 -0.0710644 -0.40773 0.00728758 -0.0710261 -0.40903 0.00733569 -0.0684936 -0.411834 0.017077 -0.073765 -0.412315 0.0172313 -0.0711592 -0.415003 0.0201845 -0.0712077 -0.421464 0.0257638 -0.0712901 -0.423907 0.0277616 -0.073765 -0.427103 0.0303085 -0.073765 -0.430528 0.0333298 -0.073765 -0.420346 -4.19898e-08 -0.058235 -0.417329 0.00733964 -0.0607573 -0.420546 0.0178459 -0.0608383 -0.416818 0.0177182 -0.0645021 -0.42174 0.0239219 -0.0646588 -0.424587 0.0269217 -0.0647327 -0.427513 0.0299187 -0.0648031 -0.432114 0.0330584 -0.058235 -0.439027 0.0514361 -0.0612532 -0.438163 0.046572 -0.0653413 -0.437029 0.0429428 -0.0651888 -0.437475 0.0442425 -0.0611339 -0.435997 0.040762 -0.06108 -0.435279 0.0394451 -0.0650564 -0.431904 0.0340873 -0.0610018 -0.433011 0.0361255 -0.0649544 -0.428908 0.0317885 -0.0690362 -0.423415 0.0265174 -0.0667375 -0.422332 0.0261214 -0.0689079 -0.417531 0.0206676 -0.0665726 -0.415067 0.0175968 -0.0664856 -0.413081 0.0143594 -0.0664029 -0.411402 0.0142555 -0.0686094 -0.411663 0.0109367 -0.0663331 -0.40947 -4.19898e-08 -0.0673391 -0.444673 0.00599996 0.077235 -0.440759 0.0149548 0.084235 -0.443745 0.0106687 0.077235 -0.444216 0.0093097 0.084235 -0.4411 0.0146267 0.077235 -0.434853 0.0179655 0.084235 -0.444673 -4.19898e-08 0.084235 -0.444673 -0.00600004 0.077235 -0.444673 -0.00600004 0.084235 -0.435325 -0.0178621 0.084235 -0.438019 -0.0168669 0.084235 -0.439647 -0.0158678 0.084235 -0.442617 -0.012778 0.084235 -0.4411 -0.0146267 0.077235 -0.443745 -0.0106688 0.077235 -0.443745 -0.0106688 0.084235 -0.411784 0.0153585 0.077235 -0.413163 0.0172447 0.077235 -0.413163 -0.0172448 0.077235 -0.410969 -0.0140269 0.077235 -0.414645 -0.0183044 0.077235 -0.409412 -0.0104678 0.077235 -0.408793 -0.00792382 0.077235 -0.40846 -1.9304e-06 0.077235 -0.437142 0.0172713 0.077235 -0.437142 -0.0172714 0.077235 -0.432473 -0.0182 0.077235 -0.432473 0.0182 0.077235 -0.433477 0.0294574 0.085235 -0.423765 0.0213602 0.085235 -0.428155 0.0249803 0.085235 -0.414063 0.0190046 0.0771244 -0.414141 0.0198729 0.0763894 -0.414036 0.0191014 0.0770751 -0.412392 0.0178614 0.0763964 -0.410963 0.0159015 0.0764104 -0.408514 0.010185 0.0768633 -0.410296 0.0127217 0.077235 -0.409261 0.00996993 0.077235 -0.408847 0.0100891 0.0771373 -0.409093 0.00934352 0.077235 -0.40859 0.00644797 0.077235 -0.408436 0.00332401 0.077235 -0.408176 0.00649112 0.0771444 -0.408033 0.00332662 0.0771503 -0.412809 0.0175275 0.0771268 -0.412533 0.017749 0.0768255 -0.41141 0.0156058 0.0771289 -0.409897 0.012909 0.0771326 -0.411115 0.0158005 0.0768331 -0.40958 0.0130578 0.0768462 -0.408677 0.00944765 0.0771385 -0.408341 0.00953169 0.0768677 -0.407837 0.00652645 0.0768889 -0.407699 0.00332878 0.0769104 -0.408064 -1.01441e-06 0.0771534 -0.407794 0.00779538 0.0764979 -0.407635 0.00654755 0.0765149 -0.407489 0.00333014 0.076556 -0.407521 -4.19896e-08 0.0765779 -0.415106 0.0182 0.077235 -0.41606 0.0182 0.0798582 -0.420808 0.0182 0.0842133 -0.41807 0.0182 0.0831824 -0.418157 0.0182 0.083253 -0.438473 0.0294574 0.085235 -0.441438 0.0156888 0.085235 -0.443449 -0.0133336 0.085235 -0.44542 -0.00857523 0.085235 -0.435559 -0.0188344 0.085235 -0.438473 -0.0177576 0.085235 -0.432473 -0.0192 0.085235 -0.423765 -0.0213603 0.085235 -0.432473 -0.0182 0.084235 -0.419859 -0.0182 0.0840571 -0.414131 -0.0188353 0.0771911 -0.414141 -0.019873 0.0763894 -0.414006 -0.0194577 0.0768291 -0.410275 -0.0144177 0.0768394 -0.408484 -0.0107633 0.0764603 -0.407715 -0.0045138 0.076903 -0.407733 -2.48016e-07 0.0769217 -0.408038 -0.00805455 0.0768779 -0.408668 -0.0107046 0.07686 -0.410582 -0.0142451 0.0771307 -0.412533 -0.0177491 0.0768255 -0.408459 -0.00448846 0.077235 -0.408051 -0.00450234 0.0771482 -0.408377 -0.00799594 0.0771414 -0.408999 -0.0105991 0.0771364 -0.414295 -0.0185788 0.077235 -0.412809 -0.0175276 0.0771268 -0.415368 0.0198507 0.0801691 -0.407392 0.00817757 0.073235 -0.435906 0.038988 0.0797748 -0.438035 0.0439007 0.0793712 -0.437264 0.0402434 0.081442 -0.438143 0.0465328 0.0773365 -0.438141 0.046455 0.0774041 -0.43813 0.0464548 0.0773243 -0.437691 0.0445184 0.0771456 -0.438259 0.0492197 0.0746057 -0.438145 0.0466143 0.0772652 -0.437163 0.0444122 0.073235 -0.437806 0.0466698 0.073235 -0.435803 0.0413239 0.073235 -0.436633 0.0429759 0.0741447 -0.436611 0.0429924 0.073235 -0.434842 0.0396668 0.074075 -0.427855 0.0320102 0.073235 -0.427031 0.0312438 0.0746338 -0.420931 0.0261787 0.0752871 -0.417649 0.0235323 0.073235 -0.414501 0.0205863 0.073235 -0.412538 0.0184411 0.073235 -0.406837 0.00254085 0.073235 -0.407611 0.00791315 0.0756799 -0.409409 0.0131379 0.0764347 -0.408688 0.0116627 0.0759745 -0.408326 0.0102388 0.0764666 -0.408151 0.00957941 0.0764747 -0.415559 0.0206542 0.0787291 -0.414437 0.0198694 0.0776001 -0.414143 0.0198765 0.0763845 -0.41253 0.01812 0.0760318 -0.433531 0.0360395 0.0798891 -0.427946 0.0306574 0.0803806 -0.421966 0.0255183 0.0809962 -0.421356 0.0241815 0.0827308 -0.406904 0.00394192 0.0737606 -0.407109 0.00380993 0.0752048 -0.407411 0.00804225 0.0742343 -0.410356 0.0150469 0.0760826 -0.408148 0.0109606 0.073235 -0.415091 0.0209535 0.0758588 -0.432888 0.0364473 0.0770742 -0.432566 0.0366572 0.0741582 -0.435218 0.0394239 0.0769742 -0.437045 0.0427102 0.0770322 -0.43783 0.0466509 0.0744013 -0.416326 0.02017 0.0815051 -0.421302 0.025939 0.0781879 -0.427339 0.0310429 0.0775543 -0.437684 0.0423049 0.0798485 -0.43806 0.044234 0.0791409 -0.439746 0.0372796 0.0847338 -0.440873 0.0400618 0.0840822 -0.455506 0.0407687 0.0838636 -0.441493 0.042457 0.0832483 -0.455599 0.0454243 0.0818289 -0.45564 0.0468063 0.0810115 -0.442064 0.0483629 0.0799621 -0.455728 0.0491338 0.0793899 -0.442232 0.0514866 0.0774104 -0.45625 0.0569754 0.0710907 -0.456194 0.0563724 0.0719335 -0.442522 0.0553162 0.0733061 -0.442338 0.0528639 0.076073 -0.455886 0.0521977 0.0767376 -0.456645 0.0604343 0.0650813 -0.456431 0.0587273 0.0683494 -0.443749 0.0630612 0.0572951 -0.457068 0.0628289 0.0583057 -0.444527 0.0638008 0.0516739 -0.457129 0.0630609 0.0572959 -0.457302 0.063553 0.0544211 -0.445628 0.0637453 0.045235 -0.457494 0.0638159 0.0513682 -0.455881 0.0521146 0.0768181 -0.464918 0.0580405 0.0649957 -0.47245 0.0488458 0.0518863 -0.472198 0.0518749 0.0519569 -0.471683 0.0511656 0.0569036 -0.46234 0.059269 0.0653017 -0.462098 0.0576446 0.0683138 -0.459315 0.0583955 0.0684592 -0.465186 0.0593908 0.0618723 -0.459541 0.0600413 0.0653703 -0.45978 0.0614441 0.0620379 -0.456699 0.0608093 0.0642496 -0.456851 0.0617635 0.0618442 -0.456262 0.0571059 0.0709023 -0.469549 0.0564826 0.0579674 -0.468029 0.0593736 0.0550111 -0.467729 0.058688 0.0583104 -0.465472 0.0604667 0.0585042 -0.465767 0.0611839 0.0550062 -0.46315 0.0624907 0.0548991 -0.460289 0.0632744 0.0546992 -0.465297 0.0621819 0.0460705 -0.466059 0.0615124 0.0516207 -0.467438 0.0576631 0.0614916 -0.462597 0.060658 0.062053 -0.462869 0.0617615 0.0585443 -0.460031 0.0625521 0.0584375 -0.466029 0.0463116 0.0767867 -0.463623 0.0440505 0.080195 -0.463797 0.047439 0.0780244 -0.455439 0.030847 0.0852323 -0.460906 0.0355618 0.0840769 -0.455452 0.0351469 0.0850304 -0.455456 0.0357396 0.0849636 -0.463991 0.0502069 0.0756959 -0.46145 0.0511756 0.0764315 -0.464202 0.05258 0.0732299 -0.468995 0.05433 0.0636815 -0.470344 0.0519837 0.0627214 -0.470601 0.0530787 0.0601856 -0.458538 0.0488551 0.0793214 -0.455659 0.0473693 0.0806482 -0.458898 0.0543199 0.0741514 -0.461652 0.0536356 0.0738593 -0.464666 0.0564633 0.0678949 -0.466911 0.0548718 0.0672028 -0.455866 0.051866 0.0770561 -0.45871 0.0518092 0.0767993 -0.464428 0.0546511 0.0706272 -0.46667 0.0531436 0.0697985 -0.455462 0.0366703 0.084835 -0.458218 0.0356783 0.0847507 -0.460973 0.0402947 0.0830648 -0.463415 0.0353893 0.0829243 -0.463487 0.0398564 0.0819764 -0.46564 0.0351641 0.0813094 -0.468911 0.0345886 0.0769285 -0.468978 0.0378137 0.0762493 -0.469869 0.0342617 0.0743453 -0.467492 0.0348936 0.0792835 -0.467471 0.0294574 0.0794993 -0.463394 0.0294574 0.0831702 -0.47019 0.0417326 0.0712437 -0.470041 0.0395103 0.0726827 -0.471992 0.0482737 0.056247 -0.471554 0.0467927 0.0604106 -0.470361 0.0436688 0.0695979 -0.4677 0.0420624 0.0770385 -0.469657 0.0475026 0.0694871 -0.467874 0.0449468 0.0751981 -0.468068 0.0473586 0.0731762 -0.466227 0.0489206 0.0745994 -0.469269 0.0433989 0.0733231 -0.470753 0.0469268 0.0658383 -0.469454 0.0455832 0.0714842 -0.468279 0.0494563 0.0710031 -0.4611 0.0447358 0.0811655 -0.465713 0.0392828 0.0804402 -0.465852 0.0431496 0.0788047 -0.469105 0.0408322 0.074968 -0.467564 0.0385928 0.0785051 -0.469929 0.0369779 0.0737699 -0.457998 0.0637453 0.045235 -0.460546 0.0635848 0.0511078 -0.461554 0.0634214 0.0456229 -0.468967 0.0595291 0.0465721 -0.459101 0.0564976 0.0713711 -0.461869 0.0557756 0.0711522 -0.467166 0.0563762 0.0644503 -0.469263 0.0555306 0.0609212 -0.470874 0.053939 0.0574905 -0.455533 0.042456 0.083248 -0.458389 0.0451924 0.0817039 -0.458277 0.0405893 0.0836907 -0.461264 0.048292 0.0788724 -0.466441 0.0511715 0.0722679 -0.468505 0.0513023 0.0686913 -0.469874 0.0492005 0.0673513 -0.471432 0.0504116 0.0593196 -0.471193 0.0494366 0.0616144 -0.47194 0.0516541 0.0544296 -0.471433 0.0547714 0.0519694 -0.471154 0.0545076 0.0547139 -0.469844 0.057118 0.0549119 -0.470136 0.0574152 0.0519179 -0.468325 0.0596927 0.0518006 -0.463428 0.0628161 0.0513861 -0.470357 -4.19898e-08 0.071803 -0.469851 0.0294574 0.0745251 -0.468891 -4.19899e-08 0.0771266 -0.468891 0.0294574 0.0771266 -0.467471 -4.19899e-08 0.0794993 -0.465619 0.0294574 0.0815412 -0.460886 -4.19899e-08 0.0843341 -0.460886 0.0294574 0.0843341 -0.458199 -4.19899e-08 0.0850165 -0.458199 0.0294574 0.0850165 -0.455439 0.0294574 0.085235 -0.470357 -0.0294575 0.071803 -0.469851 -4.19899e-08 0.0745251 -0.468891 -0.0294575 0.0771266 -0.467471 -0.0294575 0.0794993 -0.465619 -4.19899e-08 0.0815412 -0.463394 -4.19899e-08 0.0831702 -0.458199 -0.0294575 0.0850165 -0.455439 -0.0294575 0.085235 -0.455439 -4.19898e-08 0.085235 -0.465619 -0.0294575 0.0815412 -0.463428 -0.0628162 0.0513861 -0.456699 -0.0608094 0.0642496 -0.456851 -0.0617635 0.0618442 -0.456881 -0.0619305 0.0613666 -0.460031 -0.0625522 0.0584375 -0.457295 -0.0635377 0.0545388 -0.457546 -0.0638445 0.050588 -0.457739 -0.0638464 0.0480221 -0.470136 -0.0574152 0.0519179 -0.468325 -0.0596928 0.0518006 -0.469844 -0.0571181 0.0549119 -0.468029 -0.0593737 0.0550111 -0.467729 -0.0586881 0.0583104 -0.469263 -0.0555307 0.0609212 -0.469549 -0.0564827 0.0579674 -0.471154 -0.0545077 0.0547139 -0.471683 -0.0511656 0.0569036 -0.470874 -0.0539391 0.0574905 -0.471432 -0.0504117 0.0593196 -0.470601 -0.0530788 0.0601856 -0.471193 -0.0494367 0.0616144 -0.471154 -0.0445734 0.0642188 -0.471231 -0.0450763 0.0634797 -0.471554 -0.0467928 0.0604106 -0.471756 -0.0475956 0.0584831 -0.47194 -0.0516542 0.0544296 -0.467166 -0.0563763 0.0644503 -0.468995 -0.0543301 0.0636815 -0.466227 -0.0489207 0.0745994 -0.466029 -0.0463117 0.0767867 -0.467564 -0.0385928 0.0785051 -0.46564 -0.0351642 0.0813094 -0.469851 -0.0294575 0.0745251 -0.468911 -0.0345887 0.0769285 -0.469105 -0.0408323 0.074968 -0.469454 -0.0455833 0.0714842 -0.470646 -0.0400149 0.069048 -0.470361 -0.0436689 0.0695979 -0.47019 -0.0417327 0.0712437 -0.470041 -0.0395104 0.0726827 -0.470517 -0.0381496 0.070279 -0.469929 -0.036978 0.0737699 -0.469869 -0.0342618 0.0743453 -0.467492 -0.0348937 0.0792835 -0.468978 -0.0378137 0.0762493 -0.4677 -0.0420625 0.0770385 -0.467874 -0.0449469 0.0751981 -0.469269 -0.043399 0.0733231 -0.468068 -0.0473587 0.0731762 -0.468279 -0.0494564 0.0710031 -0.469657 -0.0475026 0.0694871 -0.458218 -0.0356784 0.0847507 -0.455456 -0.0357397 0.0849636 -0.458538 -0.0488552 0.0793214 -0.455728 -0.0491339 0.0793899 -0.458389 -0.0451925 0.0817039 -0.455576 -0.0445375 0.0822997 -0.455886 -0.0521981 0.0767373 -0.45871 -0.0518093 0.0767993 -0.456431 -0.0587273 0.0683494 -0.459315 -0.0583956 0.0684592 -0.459101 -0.0564977 0.0713711 -0.467296 -0.0609806 0.0463331 -0.465655 -0.0620005 0.046116 -0.462869 -0.0617616 0.0585443 -0.462597 -0.0606581 0.062053 -0.464666 -0.0564634 0.0678949 -0.464202 -0.0525801 0.0732299 -0.463797 -0.047439 0.0780244 -0.46145 -0.0511757 0.0764315 -0.460973 -0.0402948 0.0830648 -0.463415 -0.0353894 0.0829243 -0.460886 -0.0294575 0.0843341 -0.46315 -0.0624908 0.0548991 -0.460546 -0.0635849 0.0511078 -0.460289 -0.0632745 0.0546992 -0.45978 -0.0614442 0.0620379 -0.46234 -0.0592691 0.0653017 -0.459541 -0.0600413 0.0653703 -0.462098 -0.0576447 0.0683138 -0.461869 -0.0557757 0.0711522 -0.461652 -0.0536357 0.0738593 -0.458898 -0.0543199 0.0741514 -0.461264 -0.0482921 0.0788724 -0.4611 -0.0447358 0.0811655 -0.460906 -0.0355619 0.0840769 -0.458277 -0.0405894 0.0836907 -0.471937 -0.0547217 0.0470941 -0.471433 -0.0547715 0.0519694 -0.472198 -0.051875 0.0519569 -0.472791 -0.0510485 0.0473442 -0.472915 -0.0487596 0.0474572 -0.470753 -0.0469268 0.0658383 -0.468505 -0.0513023 0.0686913 -0.469874 -0.0492006 0.0673513 -0.470344 -0.0519838 0.0627214 -0.467438 -0.0576632 0.0614916 -0.466059 -0.0615125 0.0516207 -0.465767 -0.061184 0.0550062 -0.465472 -0.0604668 0.0585042 -0.465186 -0.0593909 0.0618723 -0.464918 -0.0580406 0.0649957 -0.466911 -0.0548719 0.0672028 -0.46667 -0.0531437 0.0697985 -0.466441 -0.0511716 0.0722679 -0.464428 -0.0546511 0.0706272 -0.463991 -0.050207 0.0756959 -0.465852 -0.0431497 0.0788047 -0.463623 -0.0440506 0.080195 -0.463487 -0.0398565 0.0819764 -0.465713 -0.0392829 0.0804402 -0.463394 -0.0294575 0.0831702 -0.442338 -0.052864 0.076073 -0.45606 -0.0547526 0.0739933 -0.442691 -0.0576043 0.0701604 -0.456262 -0.0571061 0.0709021 -0.456422 -0.0586427 0.0684939 -0.456636 -0.0603699 0.0652193 -0.457129 -0.0630609 0.0572961 -0.444527 -0.0638009 0.0516739 -0.445628 -0.0637453 0.045235 -0.442285 -0.0521977 0.0767377 -0.455881 -0.0521147 0.0768181 -0.455757 -0.0497647 0.0788948 -0.45564 -0.0468066 0.0810113 -0.4419 -0.0453564 0.0818665 -0.441857 -0.0448957 0.0821148 -0.455506 -0.0407689 0.0838636 -0.440873 -0.0400619 0.0840822 -0.455483 -0.0389938 0.0843704 -0.438473 -0.0294575 0.085235 -0.455445 -0.0335606 0.0851565 -0.439746 -0.0372797 0.0847338 -0.438521 -0.0351444 0.0850302 -0.455452 -0.035147 0.0850304 -0.438473 -0.0350714 0.0850376 -0.438473 -0.0322709 0.0852082 -0.43783 -0.046651 0.0744013 -0.414502 -0.0205877 0.073235 -0.407068 -4.80416e-08 0.07522 -0.407301 -4.19898e-08 0.0759712 -0.406837 -0.00254093 0.073235 -0.406904 -0.003942 0.0737606 -0.406887 -0.00395366 0.073235 -0.407392 -0.00817766 0.073235 -0.408149 -0.0109614 0.073235 -0.409312 -0.0136769 0.073235 -0.412538 -0.0184412 0.073235 -0.420931 -0.0261788 0.0752871 -0.417649 -0.0235324 0.073235 -0.427031 -0.0312439 0.0746338 -0.432799 -0.0369626 0.073235 -0.437806 -0.0466699 0.073235 -0.436633 -0.0429759 0.0741447 -0.438352 -0.0503285 0.073235 -0.43825 -0.0490874 0.0747603 -0.438109 -0.0482581 0.073235 -0.43806 -0.044234 0.0791409 -0.435906 -0.0389881 0.0797748 -0.437264 -0.0402435 0.081442 -0.436549 -0.0386538 0.0820105 -0.435524 -0.0370313 0.0823777 -0.433531 -0.0360396 0.0798891 -0.427946 -0.0306574 0.0803806 -0.433874 -0.0350402 0.0825998 -0.430988 -0.03224 0.0826717 -0.417426 -0.0205258 0.0828239 -0.421356 -0.0241816 0.0827308 -0.421966 -0.0255184 0.0809962 -0.425803 -0.0278739 0.0826826 -0.408688 -0.0116628 0.0759745 -0.410113 -0.0145087 0.0764219 -0.410356 -0.015047 0.0760826 -0.412392 -0.0178615 0.0763964 -0.41253 -0.0181201 0.0760318 -0.407841 -0.00808867 0.076494 -0.407109 -0.00381001 0.0752048 -0.407507 -0.00452087 0.0765418 -0.407411 -0.00804234 0.0742343 -0.407611 -0.00791324 0.0756799 -0.414143 -0.0198766 0.0763845 -0.415091 -0.0209536 0.0758588 -0.427339 -0.031043 0.0775543 -0.432888 -0.0364474 0.0770742 -0.432566 -0.0366572 0.0741582 -0.434842 -0.0396669 0.074075 -0.437045 -0.0427103 0.0770322 -0.437691 -0.0445185 0.0771456 -0.43813 -0.0464549 0.0773243 -0.438141 -0.0464554 0.0774038 -0.438143 -0.0465325 0.0773368 -0.415368 -0.0198508 0.0801691 -0.415559 -0.0206543 0.0787291 -0.421302 -0.0259391 0.0781879 -0.416326 -0.0201701 0.0815051 -0.435218 -0.039424 0.0769742 -0.437684 -0.0423049 0.0798485 -0.4378 -0.0421993 0.0804462 -0.409506 -4.19898e-08 0.0667664 -0.408926 -0.00760658 0.0681338 -0.43469 -0.0397282 0.0687216 -0.434156 -0.0396748 0.060701 -0.437831 -0.0474934 0.0571052 -0.424541 -0.0258531 0.0605901 -0.426982 -0.0292801 0.0606169 -0.432 -0.0350369 0.057705 -0.438954 -0.051977 0.0567135 -0.440084 -0.0596419 0.053888 -0.440461 -0.0550059 0.0498563 -0.441063 -0.0599485 0.0480782 -0.445851 -0.0546909 0.0212584 -0.447246 -0.0581146 0.00767416 -0.446815 -0.0543399 0.0132205 -0.439555 -0.0529228 0.0534381 -0.439049 -0.0570945 0.062606 -0.437163 -0.0444123 0.073235 -0.406818 -4.19898e-08 0.073235 -0.434433 -0.0390955 0.073235 -0.432111 -0.0363591 0.0686267 -0.427855 -0.0320103 0.073235 -0.435805 -0.0413271 0.073235 -0.436611 -0.0429925 0.073235 -0.437538 -0.0469947 0.0608031 -0.436655 -0.0433089 0.0688567 -0.43717 -0.0452735 0.0647699 -0.437903 -0.0470384 0.0690128 -0.439039 -0.0546275 0.060928 -0.438521 -0.0507868 0.0608684 -0.438259 -0.0490996 0.0649257 -0.438759 -0.0529598 0.0650668 -0.43849 -0.0508267 0.0691543 -0.407253 -0.00742775 0.073235 -0.408512 -4.19898e-08 0.0680882 -0.407703 -0.00752777 0.0706001 -0.40862 -0.0111416 0.0706333 -0.41383 -4.19898e-08 0.0626877 -0.410175 -0.0145836 0.0706732 -0.41016 -0.0151791 0.073235 -0.409826 -0.011283 0.0681769 -0.410654 -0.00766526 0.0659554 -0.412657 -0.00770657 0.0640086 -0.417035 -0.00774806 0.060456 -0.41151 -0.011389 0.0659991 -0.413488 -0.0181025 0.0683005 -0.411354 -0.0147918 0.0682347 -0.416132 -0.0212381 0.0683653 -0.414994 -0.0183411 0.066133 -0.414802 -0.0150881 0.0641038 -0.418789 -0.015257 0.0605007 -0.420715 -0.0087691 0.057705 -0.412354 -0.0178328 0.0707155 -0.437308 -0.0460098 0.0574897 -0.435441 -0.0415647 0.064633 -0.436063 -0.0432842 0.060745 -0.433162 -0.038033 0.0645328 -0.429089 -0.0331903 0.0685644 -0.421591 -0.0267535 0.0708132 -0.419165 -0.0242523 0.0684235 -0.415071 -0.0209108 0.0707548 -0.412965 -0.0149583 0.0660608 -0.413451 -0.0114648 0.0640479 -0.417684 -0.0115464 0.060475 -0.4204 -0.0044855 0.057705 -0.43049 -0.0346722 0.0644629 -0.427588 -0.0314336 0.0644078 -0.431922 -0.0361574 0.0606687 -0.429486 -0.032704 0.0606422 -0.421713 -0.0250837 0.0642991 -0.420344 -0.0188686 0.0605305 -0.42229 -0.0223925 0.060561 -0.436424 -0.0437468 0.057705 -0.422443 -0.0272071 0.0684734 -0.424612 -0.0282564 0.0643555 -0.417505 -0.0215593 0.066206 -0.41669 -0.0185485 0.0641695 -0.41903 -0.0218652 0.0642365 -0.438859 0.0558332 0.0651538 -0.445766 0.0587638 0.0219975 -0.445303 0.054849 0.0248806 -0.446554 0.0584869 0.015859 -0.447246 0.0581145 0.00767416 -0.440084 0.0596418 0.053888 -0.440123 0.0543674 0.0512909 -0.440585 0.0599216 0.0507951 -0.441063 0.0599485 0.0480782 -0.4417 0.0598043 0.0446591 -0.443011 0.0554032 0.0375751 -0.438138 0.0484234 0.0567562 -0.438774 0.0504647 0.0556483 -0.439205 0.0518592 0.0545474 -0.439384 0.0524146 0.0540037 -0.43852 0.0507829 0.0608684 -0.43673 0.0445001 0.0576814 -0.434155 0.0396718 0.060701 -0.43192 0.0361548 0.0606687 -0.434301 0.0392014 0.057705 -0.426981 0.0292781 0.0606168 -0.4245 0.0216879 0.057705 -0.421615 0.0137102 0.057705 -0.417035 0.00774742 0.060456 -0.437902 0.0470345 0.0690126 -0.438489 0.0508225 0.0691542 -0.438527 0.0523388 0.0706582 -0.438953 0.0519731 0.0567135 -0.421589 0.0267517 0.0708132 -0.438108 0.0482541 0.073235 -0.436654 0.0433053 0.0688565 -0.434433 0.0390954 0.073235 -0.434688 0.0397251 0.0687215 -0.432799 0.0369626 0.073235 -0.429087 0.033188 0.0685644 -0.438759 0.0529555 0.0650667 -0.438258 0.0490956 0.0649256 -0.430488 0.0346697 0.0644628 -0.432108 0.0363565 0.0686267 -0.407563 -4.19898e-08 0.0698069 -0.407273 -4.19898e-08 0.0705495 -0.406887 0.00395357 0.073235 -0.407253 0.00742714 0.073235 -0.407703 0.00752716 0.0706001 -0.40862 0.0111407 0.0706333 -0.410175 0.0145826 0.0706732 -0.409312 0.0136769 0.073235 -0.412353 0.0178316 0.0707155 -0.41016 0.015179 0.073235 -0.41507 0.0209094 0.0707548 -0.42229 0.0223909 0.060561 -0.420343 0.0188672 0.0605305 -0.416689 0.0185472 0.0641695 -0.418789 0.0152558 0.0605007 -0.417684 0.0115455 0.060475 -0.416734 -4.19898e-08 0.0604375 -0.413487 0.0181013 0.0683004 -0.411354 0.0147907 0.0682347 -0.408926 0.00760595 0.0681338 -0.409825 0.0112821 0.0681768 -0.417504 0.0215579 0.066206 -0.416131 0.0212367 0.0683653 -0.419164 0.0242507 0.0684235 -0.439039 0.0546232 0.0609279 -0.439049 0.0570944 0.062606 -0.437537 0.0469911 0.060803 -0.437169 0.0452699 0.0647698 -0.436061 0.0432809 0.0607449 -0.435439 0.0415614 0.0646329 -0.43316 0.0380302 0.0645327 -0.429484 0.0327016 0.0606422 -0.427586 0.0314315 0.0644078 -0.42454 0.0258513 0.06059 -0.424611 0.0282544 0.0643555 -0.419029 0.0218637 0.0642365 -0.422441 0.0272053 0.0684734 -0.421712 0.025082 0.0642991 -0.414993 0.0183399 0.066133 -0.412964 0.0149572 0.0660608 -0.414802 0.015087 0.0641038 -0.411509 0.0113881 0.0659991 -0.41345 0.0114639 0.0640479 -0.410654 0.00766462 0.0659554 -0.412657 0.00770593 0.0640086 -0.418855 0.0195499 0.0847158 -0.418045 0.0199105 0.0840931 -0.417426 0.0205257 0.0828239 -0.417628 0.0197167 0.0839257 -0.417525 0.0197304 0.0838316 -0.421917 0.0235247 0.0840456 -0.422764 0.0225332 0.0849257 -0.419062 0.0195213 0.0848044 -0.421335 0.0192 0.085235 -0.420726 0.0192873 0.085206 -0.426345 0.0272076 0.0840209 -0.432436 0.0306216 0.0849175 -0.427172 0.0261895 0.084919 -0.43156 0.0316009 0.0840153 -0.425803 0.0278738 0.0826826 -0.434502 0.0344943 0.0839385 -0.430988 0.0322399 0.0826717 -0.436579 0.0325831 0.0851985 -0.437254 0.0359524 0.084646 -0.436218 0.0366403 0.0837124 -0.435453 0.0336306 0.084852 -0.433874 0.0350401 0.0825998 -0.441994 0.0468054 0.0810116 -0.440227 0.0453048 0.081473 -0.4419 0.0453563 0.0818665 -0.440199 0.0448788 0.0817121 -0.441857 0.0448956 0.0821148 -0.441085 0.040762 0.0838658 -0.438473 0.0350713 0.0850376 -0.438521 0.0351443 0.0850302 -0.439277 0.0400451 0.0837713 -0.44071 0.039575 0.0842199 -0.440299 0.0481795 0.0795876 -0.439926 0.0426504 0.0828077 -0.438842 0.0445258 0.0807385 -0.439417 0.0404841 0.0836323 -0.438426 0.0379708 0.0843057 -0.437304 0.038453 0.0833501 -0.438063 0.0442841 0.0791056 -0.438896 0.0475538 0.0786225 -0.438863 0.0449061 0.0805048 -0.438622 0.0425593 0.0818183 -0.4378 0.0421992 0.0804462 -0.438188 0.0406641 0.0826524 -0.437379 0.0405738 0.0812958 -0.438066 0.04028 0.082795 -0.436549 0.0386537 0.0820105 -0.435524 0.0370312 0.0823777 -0.440352 0.0512484 0.0769897 -0.438873 0.0515808 0.0745049 -0.439729 0.0522869 0.0752718 -0.442285 0.0521977 0.0767376 -0.44039 0.0525884 0.0756272 -0.438881 0.051525 0.0745958 -0.438915 0.0504284 0.0759752 -0.438431 0.0507657 0.0736696 -0.439705 0.0544959 0.0724681 -0.438352 0.0503284 0.073235 -0.438697 0.0543072 0.0677621 -0.43898 0.0555979 0.0686255 -0.440919 0.0527418 0.0758241 -0.442652 0.0571058 0.0709022 -0.442691 0.0576043 0.0701604 -0.443287 0.0618654 0.0615553 -0.443058 0.0608093 0.0642493 -0.443037 0.0606818 0.0645381 -0.441496 0.0604458 0.0643049 -0.441758 0.0616255 0.061311 -0.442096 0.0625462 0.0581869 -0.443612 0.0627941 0.0584463 -0.444039 0.0634655 0.0550557 -0.442536 0.0632019 0.0547869 -0.443036 0.0635179 0.0514049 -0.442023 0.0613091 0.044655 -0.440399 0.0611349 0.0541558 -0.439644 0.0590465 0.0569929 -0.439602 0.0596372 0.0603922 -0.439306 0.0581939 0.0598587 -0.438837 0.0535169 0.0716257 -0.439841 0.0566802 0.0693863 -0.439334 0.0585011 0.0632575 -0.440194 0.0596792 0.0638548 -0.439949 0.0605187 0.0574006 -0.440907 0.0614227 0.0509303 -0.440998 0.0551274 0.073058 -0.441145 0.0573856 0.0699259 -0.440463 0.0608427 0.0609024 -0.44081 0.0617473 0.0578198 -0.441259 0.0623841 0.0544712 -0.441767 0.0626839 0.0511441 -0.444144 0.0634371 0.044966 -0.444697 0.0638444 0.0505869 -0.44288 0.0625829 0.0447626 -0.443997 0.0592344 0.0325995 -0.446077 0.0602837 0.0219764 -0.446865 0.0600091 0.015827 -0.444309 0.0607525 0.0325905 -0.445165 0.0620407 0.0326915 -0.446938 0.0615731 0.0220449 -0.447729 0.0613002 0.0158664 -0.447554 0.0596406 0.00762505 -0.446436 0.0629056 0.0328873 -0.44842 0.0609348 0.00761785 -0.448218 0.062438 0.0221928 -0.45053 0.0624743 0.0161257 -0.449015 0.0621655 0.0159712 -0.449714 0.0618009 0.00765367 -0.447473 0.0577549 -0.000264971 -0.448645 0.0605806 -0.000388345 -0.447735 0.0591337 -0.00372107 -0.447778 0.0592842 -0.00033174 -0.447027 0.0572589 -0.0114257 -0.447328 0.0587898 -0.0115164 -0.446204 0.0569112 -0.0193216 -0.446502 0.0584424 -0.0194267 -0.445957 0.0568298 -0.0211726 -0.446255 0.058361 -0.0212806 -0.444405 0.0564034 -0.0308715 -0.442368 0.0559514 -0.0416848 -0.440309 0.055568 -0.0529608 -0.448192 0.0600862 -0.0116413 -0.447362 0.059738 -0.0195933 -0.447114 0.0596565 -0.0214557 -0.4447 0.057935 -0.030991 -0.442669 0.0574766 -0.0418094 -0.440641 0.0570597 -0.0530794 -0.449942 0.0614469 -0.000426167 -0.448602 0.0604304 -0.00379883 -0.449487 0.0609503 -0.0117814 -0.44865 0.0606001 -0.0197959 -0.4484 0.0605181 -0.0216711 -0.445553 0.05923 -0.0311993 -0.446832 0.0600903 -0.0314647 -0.443521 0.0587643 -0.0420299 -0.441504 0.0583116 -0.0532731 -0.4499 0.0612962 -0.00386828 -0.451431 0.0615992 -0.00391884 -0.451015 0.06125 -0.0119152 -0.44992 0.0608144 -0.0218939 -0.448343 0.0603842 -0.0317465 -0.444794 0.0596185 -0.0423128 -0.446296 0.0599096 -0.0426152 -0.442772 0.0591398 -0.0535134 -0.442582 0.0545845 -0.0721583 -0.441075 0.0546291 -0.0714686 -0.43961 0.0509483 -0.0755145 -0.438913 0.0527942 -0.070309 -0.438732 0.0500262 -0.0747034 -0.441928 0.0586305 -0.0598172 -0.444257 0.0594228 -0.053765 -0.440647 0.0578124 -0.0595407 -0.439782 0.0565664 -0.0592478 -0.443434 0.0588989 -0.0600361 -0.441487 0.0575773 -0.0645411 -0.442927 0.0574281 -0.0659988 -0.443015 0.0578342 -0.0647476 -0.439778 0.0539044 -0.0709857 -0.439028 0.0540862 -0.0632765 -0.439328 0.0555482 -0.0637447 -0.439112 0.0545177 -0.0666539 -0.440191 0.0567744 -0.0641889 -0.439975 0.0557099 -0.0672027 -0.442812 0.0567394 -0.0678171 -0.441275 0.0564906 -0.0676115 -0.440396 0.0507232 -0.076742 -0.438324 0.0483653 -0.0745515 -0.438972 0.0503633 -0.0749939 -0.438951 0.0497586 -0.075803 -0.440422 0.0513831 -0.0759262 -0.440879 0.0515353 -0.076083 -0.440374 0.0500318 -0.0775402 -0.438935 0.0491224 -0.0765981 -0.438282 0.0478013 -0.0753279 -0.438918 0.0479889 -0.0778799 -0.442037 0.0457769 -0.0818848 -0.440304 0.046262 -0.0810332 -0.441887 0.0437526 -0.0831292 -0.439813 0.0409062 -0.0840475 -0.441812 0.0430972 -0.083472 -0.438902 0.0456283 -0.0800723 -0.438829 0.0433612 -0.081698 -0.437987 0.0422461 -0.0805938 -0.438498 0.0408737 -0.0830041 -0.437265 0.0389649 -0.082295 -0.43717 0.0386917 -0.0823968 -0.436151 0.034946 -0.0844871 -0.440345 0.0488068 -0.0788248 -0.440198 0.0437367 -0.0827063 -0.440141 0.0431367 -0.0830346 -0.438781 0.0428342 -0.0820116 -0.438055 0.0389762 -0.0837236 -0.437955 0.0386523 -0.0838216 -0.437201 0.0368067 -0.0842451 -0.440802 0.0382501 -0.0851904 -0.439304 0.0387239 -0.0847455 -0.439188 0.0383483 -0.084838 -0.438351 0.0362497 -0.0852186 -0.440667 0.03783 -0.0852779 -0.437612 0.0320975 -0.0857625 -0.437213 0.0342019 -0.0854035 -0.436694 0.031 -0.085765 -0.436419 0.033069 -0.0854477 -0.435565 0.0320131 -0.085466 -0.435409 0.0338867 -0.0845644 -0.422594 0.0192 -0.085765 -0.418815 0.0197333 -0.0845773 -0.422612 0.0192145 -0.085765 -0.421692 0.0203488 -0.0854888 -0.420899 0.0213265 -0.0846986 -0.428955 0.0259509 -0.0854918 -0.432891 0.0292677 -0.0854847 -0.428181 0.0269377 -0.0847095 -0.420343 0.0220126 -0.0835034 -0.431444 0.0308536 -0.0834728 -0.432038 0.0302023 -0.0846832 -0.434604 0.0328748 -0.0846139 -0.418045 -0.0199106 0.0840931 -0.428155 -0.0249804 0.085235 -0.422764 -0.0225333 0.0849257 -0.433477 -0.0294575 0.085235 -0.41901 -0.0195285 0.0847832 -0.421917 -0.0235248 0.0840456 -0.426345 -0.0272077 0.0840209 -0.427172 -0.0261895 0.084919 -0.432436 -0.0306216 0.0849175 -0.417664 -0.0197119 0.0839575 -0.43156 -0.031601 0.0840153 -0.436579 -0.0325832 0.0851985 -0.436218 -0.0366404 0.0837124 -0.437254 -0.0359524 0.084646 -0.434502 -0.0344944 0.0839385 -0.435453 -0.0336307 0.084852 -0.440358 -0.0514336 0.0768111 -0.438912 -0.0502809 0.0761293 -0.438146 -0.0466221 0.0772584 -0.438896 -0.0475623 0.0786157 -0.442221 -0.0513247 0.0775587 -0.440348 -0.0510896 0.0771409 -0.438063 -0.0442842 0.0791056 -0.440199 -0.0448789 0.0817121 -0.440227 -0.0453049 0.081473 -0.440299 -0.0481886 0.0795809 -0.441994 -0.0468055 0.0810116 -0.442064 -0.0483722 0.0799555 -0.438863 -0.0449062 0.0805048 -0.438035 -0.0439008 0.0793712 -0.438622 -0.0425594 0.0818183 -0.437379 -0.0405738 0.0812958 -0.438066 -0.0402801 0.082795 -0.438842 -0.0445259 0.0807385 -0.438188 -0.0406642 0.0826524 -0.439926 -0.0426505 0.0828077 -0.439277 -0.0400452 0.0837713 -0.44071 -0.0395751 0.0842199 -0.439417 -0.0404841 0.0836323 -0.441085 -0.0407621 0.0838658 -0.441493 -0.0424571 0.0832483 -0.438426 -0.0379709 0.0843057 -0.437304 -0.0384531 0.0833501 -0.438636 -0.0512401 0.0741523 -0.438309 -0.0498626 0.0738271 -0.43892 -0.051133 0.0751803 -0.438938 -0.0516549 0.0745848 -0.440586 -0.0526527 0.0757085 -0.441987 -0.0528687 0.076046 -0.440367 -0.052021 0.0762181 -0.442291 -0.0522808 0.0766566 -0.442245 -0.0516757 0.0772351 -0.438919 -0.0506002 0.0757932 -0.43827 -0.0493737 0.0744234 -0.44039 -0.0525882 0.0756277 -0.440998 -0.0551275 0.073058 -0.439416 -0.0520839 0.0750471 -0.442522 -0.0553162 0.0733061 -0.438837 -0.053517 0.0716257 -0.438527 -0.0523388 0.0706582 -0.442652 -0.0571059 0.0709022 -0.443037 -0.0606819 0.0645381 -0.443058 -0.0608094 0.0642493 -0.443287 -0.0618654 0.0615553 -0.443612 -0.0627941 0.0584463 -0.442096 -0.0625463 0.0581869 -0.438697 -0.0543073 0.0677621 -0.438859 -0.0558333 0.0651538 -0.439949 -0.0605188 0.0574006 -0.439306 -0.058194 0.0598587 -0.439644 -0.0590466 0.0569929 -0.440907 -0.0614228 0.0509303 -0.443749 -0.0630613 0.0572951 -0.444039 -0.0634656 0.0550557 -0.442536 -0.0632019 0.0547869 -0.443036 -0.0635179 0.0514049 -0.439705 -0.0544959 0.0724681 -0.441145 -0.0573857 0.0699259 -0.440194 -0.0596793 0.0638548 -0.441496 -0.0604459 0.0643049 -0.441758 -0.0616255 0.061311 -0.44081 -0.0617474 0.0578198 -0.441259 -0.0623842 0.0544712 -0.439841 -0.0566803 0.0693863 -0.43898 -0.055598 0.0686255 -0.439334 -0.0585012 0.0632575 -0.440463 -0.0608428 0.0609024 -0.439602 -0.0596373 0.0603922 -0.440399 -0.061135 0.0541558 -0.441767 -0.062684 0.0511441 -0.4417 -0.0598044 0.0446591 -0.440585 -0.0599216 0.0507951 -0.447931 -0.0632176 0.0331485 -0.44288 -0.062583 0.0447626 -0.442023 -0.0613091 0.044655 -0.444144 -0.0634372 0.044966 -0.449724 -0.0627483 0.0223978 -0.45053 -0.0624744 0.0161257 -0.45124 -0.0621077 0.00772708 -0.446436 -0.0629057 0.0328873 -0.448218 -0.0624381 0.0221928 -0.449015 -0.0621656 0.0159712 -0.447729 -0.0613003 0.0158664 -0.449714 -0.061801 0.00765367 -0.445165 -0.0620407 0.0326915 -0.444309 -0.0607525 0.0325905 -0.446938 -0.0615732 0.0220449 -0.447554 -0.0596407 0.00762505 -0.44842 -0.0609349 0.00761785 -0.447778 -0.0592842 -0.00033174 -0.443997 -0.0592345 0.0325995 -0.446077 -0.0602838 0.0219764 -0.445766 -0.0587639 0.0219975 -0.446554 -0.058487 0.015859 -0.446865 -0.0600091 0.015827 -0.447473 -0.057755 -0.000264971 -0.449942 -0.061447 -0.000426167 -0.449487 -0.0609504 -0.0117814 -0.451015 -0.0612501 -0.0119152 -0.44992 -0.0608144 -0.0218939 -0.448343 -0.0603843 -0.0317465 -0.4484 -0.0605182 -0.0216711 -0.446832 -0.0600903 -0.0314647 -0.444794 -0.0596186 -0.0423128 -0.448645 -0.0605807 -0.000388345 -0.448602 -0.0604305 -0.00379883 -0.4499 -0.0612963 -0.00386828 -0.44865 -0.0606001 -0.0197959 -0.445553 -0.0592301 -0.0311993 -0.448192 -0.0600863 -0.0116413 -0.447362 -0.0597381 -0.0195933 -0.446502 -0.0584425 -0.0194267 -0.447114 -0.0596565 -0.0214557 -0.443521 -0.0587643 -0.0420299 -0.447735 -0.0591337 -0.00372107 -0.447432 -0.0576037 -0.00364687 -0.447027 -0.057259 -0.0114257 -0.447328 -0.0587899 -0.0115164 -0.446255 -0.0583611 -0.0212806 -0.446204 -0.0569113 -0.0193216 -0.445957 -0.0568299 -0.0211726 -0.4447 -0.0579351 -0.030991 -0.442669 -0.0574767 -0.0418094 -0.43961 -0.0509484 -0.0755145 -0.438972 -0.0503634 -0.0749939 -0.442359 -0.0517035 -0.0763279 -0.442581 -0.0545813 -0.0721638 -0.441075 -0.0546292 -0.0714686 -0.441275 -0.0564906 -0.0676115 -0.442772 -0.0591399 -0.0535134 -0.441928 -0.0586306 -0.0598172 -0.441487 -0.0575774 -0.0645411 -0.442812 -0.0567394 -0.0678171 -0.442605 -0.0548578 -0.071684 -0.440647 -0.0578125 -0.0595407 -0.441504 -0.0583117 -0.0532731 -0.438913 -0.0527942 -0.070309 -0.439778 -0.0539045 -0.0709857 -0.439975 -0.05571 -0.0672027 -0.439112 -0.0545178 -0.0666539 -0.440191 -0.0567744 -0.0641889 -0.439782 -0.0565665 -0.0592478 -0.440641 -0.0570598 -0.0530794 -0.440309 -0.0555681 -0.0529608 -0.439461 -0.0550787 -0.0589822 -0.439328 -0.0555483 -0.0637447 -0.43882 -0.0530979 -0.0660495 -0.438371 -0.0489002 -0.073765 -0.438732 -0.0500263 -0.0747034 -0.440398 -0.0507948 -0.0766561 -0.440422 -0.0513832 -0.0759262 -0.440879 -0.0515353 -0.076083 -0.438953 -0.0498244 -0.0757177 -0.438938 -0.0492602 -0.0764308 -0.440378 -0.0501813 -0.0773724 -0.442268 -0.0504677 -0.0777649 -0.442228 -0.0498218 -0.07845 -0.440361 -0.049551 -0.0780636 -0.440345 -0.0487693 -0.0788618 -0.440304 -0.0462354 -0.0810534 -0.442068 -0.0464176 -0.0814295 -0.442037 -0.0457612 -0.0818957 -0.441887 -0.0437526 -0.0831292 -0.440198 -0.0437368 -0.0827063 -0.441812 -0.0430973 -0.083472 -0.440141 -0.0431368 -0.0830346 -0.441409 -0.0406623 -0.0845067 -0.439188 -0.0383484 -0.084838 -0.438351 -0.0362498 -0.0852186 -0.438918 -0.0479541 -0.0779168 -0.439813 -0.0409063 -0.0840475 -0.438781 -0.0428342 -0.0820116 -0.439304 -0.038724 -0.0847455 -0.438927 -0.0486784 -0.0771203 -0.438258 -0.0474063 -0.0758387 -0.438902 -0.0456038 -0.0800922 -0.438829 -0.0433613 -0.081698 -0.438498 -0.0408738 -0.0830041 -0.437695 -0.0405705 -0.0815604 -0.437265 -0.038965 -0.082295 -0.438055 -0.0389763 -0.0837236 -0.437955 -0.0386524 -0.0838216 -0.43717 -0.0386918 -0.0823968 -0.437201 -0.0368068 -0.0842451 -0.436151 -0.0349461 -0.0844871 -0.436419 -0.0330691 -0.0854477 -0.437612 -0.0320976 -0.0857625 -0.437213 -0.034202 -0.0854035 -0.434739 -0.0344244 -0.083249 -0.435565 -0.0320132 -0.085466 -0.435409 -0.0338868 -0.0845644 -0.428181 -0.0269378 -0.0847095 -0.420899 -0.0213266 -0.0846986 -0.431444 -0.0308537 -0.0834728 -0.433956 -0.0334563 -0.083336 -0.428955 -0.025951 -0.0854918 -0.432038 -0.0302024 -0.0846832 -0.434604 -0.0328748 -0.0846139 -0.420791 -0.0194577 -0.0855315 -0.421692 -0.0203489 -0.0854888 -0.422612 -0.0192146 -0.085765 -0.429852 -0.0248082 -0.085765 -0.432891 -0.0292678 -0.0854847 -0.414386 -0.0185956 0.077615 -0.414441 -0.0184332 0.077235 -0.414724 -0.0183044 0.0775178 -0.414207 -0.0190129 0.0776662 -0.414059 -0.0190177 0.0771182 -0.414036 -0.0191015 0.0770751 -0.415106 -0.0182 0.077235 -0.414754 -0.0182596 0.077235 -0.415151 -0.0182 0.0773951 -0.414437 -0.0198695 0.0776001 -0.414226 -0.0194693 0.0776609 -0.415339 -0.0185877 0.0801819 -0.415659 -0.0183022 0.0800385 -0.41606 -0.0182 0.0798582 -0.416593 -0.0194305 0.0829459 -0.415177 -0.01945 0.0802547 -0.415167 -0.0189982 0.0802593 -0.417053 -0.0183 0.0826673 -0.416762 -0.0198314 0.0828434 -0.416755 -0.0185797 0.082848 -0.417938 -0.0182876 0.0836012 -0.417732 -0.018535 0.0838686 -0.419207 -0.0182718 0.0842455 -0.419772 -0.0182653 0.0844017 -0.419697 -0.0184526 0.0847014 -0.41659 -0.0189835 0.0829476 -0.419097 -0.0184767 0.0845447 -0.421335 -0.0182 0.084235 -0.419334 -0.0182 0.0838962 -0.418188 -0.0182 0.0832769 -0.417425 -0.0182 0.0824413 -0.421335 -0.018249 0.084544 -0.421335 -0.018391 0.0848228 -0.419643 -0.0187375 0.0849169 -0.421335 -0.0187 0.0851011 -0.417606 -0.0188989 0.0840324 -0.419022 -0.0187855 0.0847508 -0.417582 -0.0193155 0.0840639 -0.418991 -0.0191537 0.0848343 -0.419617 -0.0190827 0.0850202 -0.419622 -0.0194433 0.0849978 -0.421335 -0.0186123 0.085044 -0.432473 -0.0184929 0.0849421 -0.432473 -0.018334 0.084735 -0.421335 -0.018334 0.084735 -0.421335 -0.0192 0.085235 -0.421335 -0.018891 0.0851861 -0.437142 -0.0172714 0.084235 -0.432473 -0.0182762 0.0846177 -0.435343 -0.0179361 0.0846177 -0.438053 -0.0169347 0.0846177 -0.435393 -0.0181468 0.0849421 -0.438152 -0.0171278 0.0849421 -0.432473 -0.0188174 0.0851589 -0.432473 -0.0187 0.0851011 -0.435469 -0.0184623 0.0851589 -0.438299 -0.0174167 0.0851589 -0.43808 -0.0169862 0.084735 -0.438246 -0.0173122 0.0851011 -0.439726 -0.0159762 0.084735 -0.441195 -0.0147215 0.084735 -0.4411 -0.0146267 0.084235 -0.442729 -0.0128524 0.084735 -0.444439 -0.00838014 0.084235 -0.44457 -0.00840628 0.084735 -0.439941 -0.0162722 0.0851011 -0.443033 -0.0130558 0.0851011 -0.443868 -0.01072 0.084735 -0.444929 -0.00847769 0.0851011 -0.440235 -0.0166766 0.085235 -0.441807 -0.0153339 0.085235 -0.441453 -0.0149803 0.0851011 -0.444206 -0.0108601 0.0851011 -0.444668 -0.0110515 0.085235 -0.444807 -0.00600004 0.084735 -0.444966 -0.00600004 0.0849421 -0.445291 -4.19898e-08 0.0851589 -0.445173 -0.00600004 0.0851011 -0.445673 -4.19898e-08 0.085235 -0.445673 -0.00600004 0.085235 -0.444749 -4.19898e-08 0.0846177 -0.444966 -4.19898e-08 0.0849421 -0.445291 0.00599996 0.0851589 -0.445673 0.00599996 0.085235 -0.438299 0.0174166 0.0851589 -0.444749 0.00599996 0.0846177 -0.444289 0.00933035 0.0846177 -0.442877 0.0123712 0.084235 -0.442942 0.012411 0.0846177 -0.443745 0.0106687 0.084235 -0.444673 0.00599996 0.084235 -0.4411 0.0146267 0.084235 -0.44081 0.0150107 0.0846177 -0.444966 0.00599996 0.0849421 -0.444498 0.00938916 0.0849421 -0.440958 0.0151698 0.0849421 -0.438053 0.0169346 0.0846177 -0.44481 0.00947717 0.0851589 -0.443127 0.0125242 0.0849421 -0.443404 0.0126936 0.0851589 -0.441178 0.0154079 0.0851589 -0.445178 0.00958099 0.085235 -0.44373 0.0128934 0.085235 -0.438473 0.0177575 0.085235 -0.437142 0.0172713 0.084235 -0.438019 0.0168668 0.084235 -0.43808 0.0169861 0.084735 -0.438152 0.0171277 0.0849421 -0.438246 0.0173121 0.0851011 -0.435048 0.0189463 0.085235 -0.432473 0.0182 0.084235 -0.434879 0.0180969 0.084735 -0.434951 0.0184559 0.0851011 -0.432473 0.0192 0.085235 -0.414878 0.0182246 0.077235 -0.415151 0.0182 0.0773951 -0.414724 0.0183043 0.0775178 -0.414226 0.0194692 0.0776609 -0.414006 0.0194576 0.0768291 -0.414645 0.0183043 0.077235 -0.414556 0.0183524 0.077235 -0.414386 0.0185955 0.077615 -0.414295 0.0185788 0.077235 -0.414207 0.0190128 0.0776662 -0.414131 0.0188352 0.0771911 -0.415339 0.0185876 0.0801819 -0.415167 0.0189981 0.0802593 -0.417425 0.0182 0.0824413 -0.415659 0.0183021 0.0800385 -0.416755 0.0185796 0.082848 -0.41659 0.0189834 0.0829476 -0.416593 0.0194304 0.0829459 -0.415177 0.0194499 0.0802547 -0.421335 0.0182489 0.084544 -0.421335 0.0182 0.084235 -0.421335 0.0183909 0.0848228 -0.432473 0.0183339 0.084735 -0.432473 0.0187 0.0851011 -0.421335 0.0187 0.0851011 -0.420739 0.0186554 0.0850491 -0.421335 0.0183339 0.084735 -0.421335 0.0188909 0.0851861 -0.420781 0.0182545 0.0845377 -0.419254 0.0182711 0.0842613 -0.419378 0.0182 0.0839121 -0.419202 0.0182 0.0838456 -0.417805 0.0182893 0.0834989 -0.420757 0.018412 0.0848268 -0.419063 0.0182734 0.084195 -0.419148 0.0184746 0.0845607 -0.418944 0.018483 0.0844931 -0.417903 0.018288 0.0835754 -0.417053 0.0182999 0.0826673 -0.421335 0.0186122 0.085044 -0.419075 0.0187813 0.0847678 -0.418863 0.0187978 0.0846961 -0.417567 0.0189021 0.0840031 -0.417694 0.0185366 0.083841 -0.417455 0.0189113 0.0839156 -0.417586 0.0185415 0.0837587 -0.419044 0.0191476 0.0848531 -0.418832 0.0191718 0.0847741 -0.417543 0.0193199 0.0840331 -0.420728 0.0189582 0.0851802 -0.417433 0.0193327 0.0839414 -0.416762 0.0198313 0.0828434 -0.414671 0.0190509 -0.077655 -0.414646 0.0191538 -0.0776028 -0.415029 0.0194991 -0.078689 -0.415254 0.0198978 -0.0786105 -0.415169 0.018608 -0.0786401 -0.415059 0.0184358 -0.077765 -0.415259 0.0183081 -0.077765 -0.416321 0.0198823 -0.0810697 -0.41612 0.0194827 -0.0811769 -0.416098 0.0190232 -0.0811887 -0.414998 0.0190358 -0.0786996 -0.416571 0.0183058 -0.0809365 -0.415503 0.0183078 -0.0785232 -0.41765 0.0194671 -0.0836327 -0.417787 0.0185946 -0.0835348 -0.41626 0.0186011 -0.0811025 -0.422594 0.0183909 -0.0853528 -0.422313 0.0189219 -0.0857209 -0.422335 0.0182514 -0.0850774 -0.422312 0.0192405 -0.0857595 -0.420491 0.0194999 -0.085443 -0.420479 0.0191296 -0.085485 -0.42017 0.019545 -0.0853299 -0.418734 0.0193354 -0.0846977 -0.418574 0.0193548 -0.0845821 -0.418665 0.0197538 -0.0844566 -0.417828 0.0198674 -0.0835048 -0.422594 0.0186122 -0.085574 -0.422318 0.018632 -0.0855835 -0.420505 0.018769 -0.0853933 -0.420151 0.0191677 -0.0853877 -0.420178 0.018795 -0.0853069 -0.418752 0.0189132 -0.0846705 -0.418589 0.0189273 -0.0845612 -0.417636 0.0190112 -0.0836434 -0.418866 0.0185425 -0.0845005 -0.418708 0.0185499 -0.0843978 -0.422594 0.0182761 -0.0851477 -0.422325 0.0184006 -0.0853614 -0.420647 0.0182695 -0.0848767 -0.420563 0.0184684 -0.0851807 -0.420247 0.0184815 -0.0850992 -0.420347 0.018273 -0.0847949 -0.419055 0.0182896 -0.0842182 -0.420465 0.0182 -0.0844387 -0.419285 0.0182 -0.0838742 -0.418909 0.0182916 -0.0841217 -0.418072 0.018304 -0.0833293 -0.419155 0.0182 -0.0837837 -0.418433 0.0182 -0.0830699 -0.422594 0.0182 -0.084765 -0.422594 0.0182489 -0.085074 -0.432473 0.0184929 -0.0854721 -0.432473 0.0192 -0.085765 -0.422594 0.0188909 -0.085716 -0.435343 0.017936 -0.0851477 -0.435325 0.017862 -0.084765 -0.432473 0.0182761 -0.0851477 -0.435393 0.0181468 -0.0854721 -0.432473 0.0188173 -0.0856889 -0.435469 0.0184622 -0.0856889 -0.438246 0.0173121 -0.085631 -0.435559 0.0188343 -0.085765 -0.439726 0.0159761 -0.085265 -0.43808 0.0169861 -0.085265 -0.438053 0.0169346 -0.0851477 -0.438152 0.0171277 -0.0854721 -0.438299 0.0174166 -0.0856889 -0.439647 0.0158677 -0.084765 -0.441195 0.0147214 -0.085265 -0.4411 0.0146267 -0.084765 -0.442617 0.0127779 -0.084765 -0.442729 0.0128523 -0.085265 -0.44457 0.0084062 -0.085265 -0.441453 0.0149802 -0.085631 -0.443033 0.0130557 -0.085631 -0.443868 0.01072 -0.085265 -0.444206 0.01086 -0.085631 -0.444807 0.00599996 -0.085265 -0.445173 0.00599996 -0.085631 -0.440235 0.0166766 -0.085765 -0.439941 0.0162721 -0.085631 -0.443449 0.0133335 -0.085765 -0.444929 0.0084776 -0.085631 -0.444673 0.00599996 -0.084765 -0.445173 -4.19898e-08 -0.085631 -0.444807 -4.19898e-08 -0.085265 -0.445291 -0.00600004 -0.0856889 -0.444673 -0.00600004 -0.084765 -0.444749 -0.00600004 -0.0851477 -0.444289 -0.00933044 -0.0851477 -0.444807 -0.00600004 -0.085265 -0.445173 -0.00600004 -0.085631 -0.444966 -0.00600004 -0.0854721 -0.444498 -0.00938925 -0.0854721 -0.445673 -0.00600004 -0.085765 -0.44481 -0.00947726 -0.0856889 -0.442942 -0.012411 -0.0851477 -0.443404 -0.0126937 -0.0856889 -0.445178 -0.00958108 -0.085765 -0.443127 -0.0125242 -0.0854721 -0.44373 -0.0128935 -0.085765 -0.441178 -0.015408 -0.0856889 -0.44081 -0.0150108 -0.0851477 -0.438152 -0.0171278 -0.0854721 -0.440958 -0.0151699 -0.0854721 -0.438299 -0.0174167 -0.0856889 -0.438473 -0.0177576 -0.085765 -0.438053 -0.0169347 -0.0851477 -0.435469 -0.0184623 -0.0856889 -0.435343 -0.0179361 -0.0851477 -0.435393 -0.0181468 -0.0854721 -0.432473 -0.0188174 -0.0856889 -0.435559 -0.0188344 -0.085765 -0.414998 -0.0190359 -0.0786996 -0.415503 -0.0183079 -0.0785232 -0.414631 -0.0195083 -0.0773552 -0.414778 -0.0199068 -0.07692 -0.414731 -0.0188827 -0.0777205 -0.414671 -0.019051 -0.077655 -0.415029 -0.0194991 -0.078689 -0.414646 -0.0191539 -0.0776028 -0.41626 -0.0186012 -0.0811025 -0.415169 -0.0186081 -0.0786401 -0.415254 -0.0198979 -0.0786105 -0.418072 -0.0183041 -0.0833293 -0.416571 -0.0183059 -0.0809365 -0.416098 -0.0190232 -0.0811887 -0.41765 -0.0194672 -0.0836327 -0.417828 -0.0198675 -0.0835048 -0.41612 -0.0194828 -0.0811769 -0.422594 -0.0182 -0.084765 -0.432473 -0.0182 -0.084765 -0.422594 -0.018391 -0.0853528 -0.432473 -0.0182762 -0.0851477 -0.432473 -0.0184929 -0.0854721 -0.418599 -0.0197629 -0.0843998 -0.418502 -0.0193635 -0.0845274 -0.417636 -0.0190113 -0.0836434 -0.418516 -0.0189337 -0.0845093 -0.417787 -0.0185947 -0.0835348 -0.418638 -0.0185533 -0.084349 -0.419885 -0.0191988 -0.0852941 -0.419912 -0.0188165 -0.0852226 -0.419912 -0.0195813 -0.0852235 -0.420784 -0.0190945 -0.085559 -0.420808 -0.0187454 -0.0854578 -0.422594 -0.0192 -0.085765 -0.422594 -0.018891 -0.085716 -0.422594 -0.0186123 -0.085574 -0.422594 -0.0182762 -0.0851477 -0.419989 -0.0184925 -0.0850198 -0.420857 -0.0184566 -0.0852416 -0.418844 -0.0182926 -0.0840761 -0.420104 -0.018276 -0.0847165 -0.420927 -0.0182664 -0.0849389 -0.422594 -0.018249 -0.085074 -0.459973 0.01675 -0.082265 -0.458745 0.0168555 -0.082265 -0.456857 0.0140854 -0.0854632 -0.451405 0.020627 -0.0853164 -0.451674 0.019534 -0.0853455 -0.453484 0.0210902 -0.082265 -0.451843 0.0190508 -0.085358 -0.452397 0.017881 -0.0853864 -0.454767 0.0190287 -0.082265 -0.452988 0.0169817 -0.0854066 -0.453712 0.0161362 -0.0854244 -0.454233 0.0156443 -0.0854342 -0.455236 0.0148945 -0.0854482 -0.456549 0.017611 -0.082265 -0.45729 0.017259 -0.082265 -0.45818 0.0169719 -0.082265 -0.451259 0.0275359 -0.085265 -0.452991 0.0262679 -0.082265 -0.452991 0.023732 -0.082265 -0.466923 0.0262443 -0.0822092 -0.468499 0.0261971 -0.084939 -0.462615 0.0172424 -0.082265 -0.461762 0.016971 -0.082265 -0.461955 0.0137536 -0.0854694 -0.464934 0.0187721 -0.0822635 -0.466382 0.0163432 -0.0853804 -0.46727 0.017575 -0.0852943 -0.466925 0.0237541 -0.0822127 -0.466707 0.0219452 -0.0822259 -0.468016 0.0192095 -0.0851671 -0.463043 0.0325634 -0.0822577 -0.465143 0.0346285 -0.0852831 -0.463972 0.0320301 -0.082263 -0.465805 0.0340984 -0.0852851 -0.464157 0.0318983 -0.0822637 -0.466176 0.0337414 -0.085279 -0.468002 0.0306977 -0.0851028 -0.466361 0.0290975 -0.0822346 -0.466837 0.0273638 -0.0822128 -0.46838 0.02908 -0.0849933 -0.468494 0.0273943 -0.0849301 -0.459973 0.033229 -0.082244 -0.460875 0.0331723 -0.0822456 -0.458175 0.033011 -0.0822496 -0.459551 0.0361227 -0.0851473 -0.453557 0.0290882 -0.082265 -0.453784 0.0295649 -0.082265 -0.454793 0.031 -0.082265 -0.453738 0.0338086 -0.085359 -0.455237 0.0314444 -0.0822648 -0.454307 0.0343003 -0.0853345 -0.455121 0.0348603 -0.085294 -0.457331 0.0327469 -0.0822549 -0.456758 0.0356202 -0.0852159 -0.470074 -0.02325 -0.084635 -0.468583 -0.02325 -0.0820539 -0.466167 0.00345438 -0.0822513 -0.470112 -0.000116394 -0.0848846 -0.46979 0.00163365 -0.0849863 -0.468016 0.000564813 -0.0821777 -0.469552 0.00241639 -0.0850429 -0.459973 0.00920707 -0.0854721 -0.461987 0.00577331 -0.082265 -0.462904 0.00551515 -0.082265 -0.464041 0.0084208 -0.085461 -0.465456 0.00769397 -0.0854415 -0.464859 0.00454453 -0.0822641 -0.465596 0.00398696 -0.0822595 -0.468627 -0.00278944 -0.0821293 -0.470181 -0.00400004 -0.0848205 -0.451241 -0.024518 -0.082265 -0.459973 0.00599996 -0.082265 -0.458306 0.00908263 -0.0854711 -0.45679 0.00542423 -0.082265 -0.455906 0.00842096 -0.0854611 -0.454961 0.0079726 -0.0854541 -0.455044 0.00451653 -0.082265 -0.453695 0.00716629 -0.0854417 -0.452475 0.00610121 -0.0854244 -0.452194 0.00580278 -0.0854193 -0.452973 0.00254438 -0.082265 -0.451235 0.00456735 -0.085397 -0.452466 0.00179112 -0.082265 -0.449509 -0.00146414 -0.085265 -0.45147 -0.000709747 -0.082265 -0.44997 0.00187918 -0.0853424 -0.451661 -4.19898e-08 -0.082265 -0.451883 0.000621021 -0.082265 -0.450226 0.00261927 -0.0853583 -0.449509 -0.02325 -0.085265 -0.449509 -0.0257859 -0.085265 -0.451365 -0.0259989 -0.082265 -0.451708 -0.032456 -0.0853958 -0.449661 -0.0278055 -0.0853129 -0.449867 -0.0287641 -0.0853344 -0.451883 -0.0278711 -0.082265 -0.45229 -0.0287328 -0.082265 -0.450564 -0.0306428 -0.0853742 -0.452766 -0.0295072 -0.082265 -0.450905 -0.0312829 -0.0853862 -0.459973 -0.036131 -0.0851459 -0.457838 -0.0359509 -0.0851732 -0.456998 -0.0327395 -0.082255 -0.456622 -0.0326003 -0.0822572 -0.455239 -0.031893 -0.0822636 -0.453053 -0.0338169 -0.0853654 -0.453775 -0.0307166 -0.082265 -0.460216 -0.0332256 -0.0822441 -0.463721 -0.0355493 -0.0852253 -0.463325 -0.0326003 -0.0822572 -0.463972 -0.0323101 -0.0822607 -0.464857 -0.03508 -0.0852586 -0.466049 -0.0343564 -0.0852604 -0.466163 -0.0306956 -0.0822411 -0.467097 -0.0295226 -0.0821924 -0.46755 -0.0287461 -0.0821546 -0.470055 -0.0255063 -0.0846033 -0.468431 -0.026077 -0.0820584 -0.458258 0.00940385 -0.0856886 -0.456729 0.00906108 -0.0856873 -0.456822 0.00874836 -0.0854662 -0.454621 0.00861291 -0.085765 -0.454806 0.00826454 -0.085684 -0.450949 0.004762 -0.0856683 -0.449967 0.00292425 -0.0856585 -0.451944 0.00603394 -0.0856745 -0.453497 0.00743608 -0.0856806 -0.450292 0.00278572 -0.0853617 -0.449192 0.00212758 -0.085765 -0.44963 0.00198773 -0.0856531 -0.449572 -0.000101844 -0.0852979 -0.44952 -0.000782581 -0.0852817 -0.449212 -5.81837e-05 -0.0856404 -0.448732 -4.19898e-08 -0.085765 -0.449156 -0.000760513 -0.0856358 -0.448643 -0.00146414 -0.085765 -0.448665 -0.000730759 -0.085765 -0.462028 0.00901696 -0.0854702 -0.463726 0.00854455 -0.085463 -0.463839 0.0088519 -0.0856864 -0.462087 0.00933656 -0.0856884 -0.463973 0.00921655 -0.085765 -0.459973 0.00953149 -0.0856889 -0.459973 0.00991417 -0.085765 -0.449509 -0.00400004 -0.085265 -0.449143 -0.00400004 -0.085631 -0.449143 -0.00146414 -0.085631 -0.470736 -4.82333e-05 -0.0853232 -0.470047 0.00169522 -0.085242 -0.469403 0.002822 -0.0850744 -0.467438 0.0060306 -0.0853406 -0.467906 0.00584235 -0.0855108 -0.467724 0.00569965 -0.0853146 -0.468479 0.00465673 -0.0852277 -0.466341 0.00706512 -0.0854111 -0.47027 0.00315511 -0.0854629 -0.469946 0.00302355 -0.0854471 -0.469206 0.00510911 -0.0855863 -0.468938 0.00493538 -0.0855621 -0.468353 0.00621346 -0.0856579 -0.466642 0.00743598 -0.0857009 -0.465701 0.00808813 -0.0857209 -0.465569 0.00787441 -0.0856133 -0.466479 0.0072338 -0.08559 -0.468122 0.00601904 -0.0856289 -0.468687 0.00477925 -0.0854383 -0.469645 0.00290779 -0.0853121 -0.470374 0.00178165 -0.0853852 -0.448969 -0.00400004 -0.0857105 -0.448969 -0.02325 -0.0857105 -0.449143 -0.02325 -0.085631 -0.449299 -0.02325 -0.0855197 -0.449299 -0.00400004 -0.0855197 -0.470172 -0.000882747 -0.0848523 -0.470185 -0.00164921 -0.0848271 -0.470455 -0.00165007 -0.0851306 -0.470806 -0.000848507 -0.0853084 -0.470381 -8.90901e-05 -0.0851663 -0.470443 -0.000869311 -0.0851449 -0.448643 -0.0257859 -0.085765 -0.470452 -0.0040018 -0.0851245 -0.470824 -0.00282697 -0.0852986 -0.470822 -0.00400326 -0.0852949 -0.47123 -0.00400419 -0.0853036 -0.470183 -0.00282463 -0.0848243 -0.470454 -0.00282591 -0.0851281 -0.470825 -0.00165078 -0.0853012 -0.449286 -0.0257859 -0.085531 -0.448985 -0.0257859 -0.0857047 -0.44938 -0.0289002 -0.0857137 -0.450226 -0.029869 -0.0853582 -0.449653 -0.0288238 -0.0855651 -0.449442 -0.0278454 -0.0855546 -0.449856 -0.031 -0.085765 -0.449158 -0.0278972 -0.0857109 -0.448838 -0.0279552 -0.085765 -0.450251 -0.0308009 -0.085662 -0.470418 -0.0136299 -0.0850585 -0.470757 -0.0232621 -0.0851182 -0.47014 -0.0136252 -0.0847497 -0.470797 -0.0136339 -0.0852276 -0.450368 -0.0307418 -0.0855843 -0.450606 -0.0314625 -0.0856652 -0.450124 -0.0308646 -0.0857187 -0.45111 -0.0329534 -0.0857516 -0.45144 -0.0326804 -0.085661 -0.452566 -0.0344379 -0.0856955 -0.452835 -0.0341006 -0.085619 -0.453986 -0.0349242 -0.085567 -0.453763 -0.0353025 -0.0856326 -0.457701 -0.0367943 -0.0854573 -0.459973 -0.0369943 -0.0854265 -0.459973 -0.036529 -0.0853898 -0.452491 -0.033316 -0.0853833 -0.454165 -0.0346032 -0.085318 -0.455819 -0.0358133 -0.0854825 -0.455939 -0.03545 -0.0852372 -0.457778 -0.0363397 -0.0854168 -0.470347 -0.0255132 -0.084922 -0.470065 -0.0243782 -0.0846193 -0.470362 -0.0232567 -0.0849516 -0.470355 -0.024385 -0.0849369 -0.470752 -0.0243906 -0.0851031 -0.461888 -0.0359868 -0.0851681 -0.463878 -0.036059 -0.0855099 -0.463973 -0.0363489 -0.0855192 -0.461941 -0.0363774 -0.0854116 -0.469433 -0.0295367 -0.0848276 -0.470191 -0.0276114 -0.0849625 -0.469901 -0.0275706 -0.0846727 -0.470746 -0.0255188 -0.0850878 -0.470572 -0.0276721 -0.0851094 -0.470978 -0.0277424 -0.0850884 -0.465085 -0.0355585 -0.0855495 -0.46399 -0.0354549 -0.0852352 -0.467602 -0.0332963 -0.0854047 -0.46783 -0.0335007 -0.0855191 -0.463833 -0.0359176 -0.0854703 -0.463791 -0.0357837 -0.0854088 -0.46496 -0.0352994 -0.085445 -0.466191 -0.0345549 -0.0854535 -0.46741 -0.0331308 -0.0851977 -0.469025 -0.030611 -0.0849454 -0.468094 -0.0322705 -0.0851242 -0.469283 -0.030708 -0.0851866 -0.468313 -0.0324125 -0.0853421 -0.469599 -0.0308423 -0.0853129 -0.468575 -0.0325935 -0.0854605 -0.46885 -0.0327925 -0.0854655 -0.466361 -0.0347923 -0.085562 -0.46807 -0.0337221 -0.0855288 -0.451052 0.0205573 -0.0856457 -0.451259 0.0224641 -0.085265 -0.450893 0.0224641 -0.085631 -0.450587 0.0204658 -0.085765 -0.450902 0.019275 -0.085765 -0.451336 0.0194207 -0.0856539 -0.452098 0.0177034 -0.0856654 -0.452382 0.0165125 -0.085765 -0.452717 0.0167714 -0.085671 -0.454016 0.0153877 -0.0856785 -0.455059 0.0146131 -0.0856824 -0.456613 0.0134126 -0.085765 -0.458055 0.0134079 -0.0856882 -0.459973 0.0128357 -0.085765 -0.459973 0.0132184 -0.0856889 -0.456746 0.0137776 -0.0856865 -0.458119 0.0137268 -0.0854698 -0.450719 0.025 -0.0857105 -0.460943 0.0128816 -0.085765 -0.460907 0.0132628 -0.0856888 -0.462104 0.0130596 -0.085765 -0.462024 0.0134355 -0.0856881 -0.459973 0.0135429 -0.0854721 -0.460877 0.0135858 -0.0854718 -0.463812 0.0140294 -0.0856852 -0.451259 0.025 -0.085265 -0.451049 0.025 -0.0855197 -0.450735 0.0275359 -0.0857047 -0.464319 0.0141361 -0.0857287 -0.465362 0.0147787 -0.085723 -0.466972 0.0158253 -0.0857236 -0.467994 0.017148 -0.085661 -0.466754 0.01602 -0.0856893 -0.467725 0.0173119 -0.0856314 -0.469339 0.0205176 -0.0854987 -0.468557 0.0190326 -0.0855455 -0.468973 0.0205844 -0.0854813 -0.469541 0.0225982 -0.0854527 -0.469141 0.0225964 -0.0854367 -0.464442 0.0138995 -0.0857648 -0.465214 0.0149842 -0.0856131 -0.46878 0.0225937 -0.0852653 -0.463677 0.0143292 -0.0854587 -0.464204 0.0143556 -0.0856227 -0.464107 0.0145419 -0.0854546 -0.465088 0.015157 -0.085438 -0.466552 0.0161978 -0.0855715 -0.467475 0.0174592 -0.0855049 -0.468256 0.0191345 -0.0854063 -0.468638 0.0206411 -0.085329 -0.46838 0.0206797 -0.0850629 -0.450905 0.0294801 -0.0857114 -0.450589 0.0295428 -0.085765 -0.451425 0.030842 -0.0856558 -0.451407 0.0293809 -0.0853166 -0.451036 0.0275359 -0.085531 -0.451188 0.0294241 -0.0855564 -0.468509 0.0237952 -0.084957 -0.468515 0.0225905 -0.0849658 -0.468776 0.0237986 -0.0852575 -0.469139 0.0238014 -0.0854287 -0.468772 0.0250034 -0.0852494 -0.454256 0.0352635 -0.085636 -0.459519 0.0369849 -0.085428 -0.459973 0.0361309 -0.0851459 -0.457599 0.0358621 -0.0851851 -0.454942 0.0351859 -0.0855445 -0.459537 0.0365202 -0.0853912 -0.457518 0.0362449 -0.0854294 -0.457414 0.0366925 -0.0854722 -0.456645 0.035989 -0.0854616 -0.454718 0.0355689 -0.0856079 -0.454095 0.0345952 -0.0855892 -0.452205 0.032471 -0.0856593 -0.451289 0.0308925 -0.0857159 -0.45155 0.0307955 -0.0855737 -0.45383 0.0349441 -0.0856618 -0.45248 0.0336058 -0.0857339 -0.453078 0.0330944 -0.0853784 -0.452812 0.0333261 -0.0856455 -0.452499 0.032279 -0.0853814 -0.451758 0.0307186 -0.0853521 -0.468504 0.025 -0.084948 -0.46954 0.0262053 -0.0854235 -0.469137 0.0250063 -0.0854205 -0.468768 0.0262006 -0.0852413 -0.469135 0.0262035 -0.0854122 -0.469133 0.0274005 -0.0854041 -0.46954 0.0274022 -0.0854138 -0.461876 0.0359608 -0.0851716 -0.46194 0.0363492 -0.0854154 -0.462022 0.0368032 -0.0854559 -0.459973 0.0365289 -0.0853898 -0.459973 0.0369943 -0.0854265 -0.468648 0.0291183 -0.0852696 -0.46857 0.0308784 -0.0854883 -0.468999 0.0291733 -0.0854225 -0.469381 0.0292368 -0.0854292 -0.468764 0.0273977 -0.0852334 -0.467597 0.0322505 -0.0854301 -0.467374 0.0321293 -0.0852058 -0.468161 0.0325746 -0.0855727 -0.467869 0.0324048 -0.0855572 -0.467387 0.0331445 -0.0855811 -0.46636 0.0347332 -0.0856135 -0.465614 0.0353166 -0.0856009 -0.465439 0.0350648 -0.0855838 -0.463859 0.0359347 -0.0855243 -0.468253 0.0307739 -0.08535 -0.46714 0.0329671 -0.085459 -0.466155 0.0344993 -0.0855953 -0.465277 0.034828 -0.0854745 -0.463805 0.035797 -0.0854838 -0.466937 0.0328242 -0.0852451 -0.465964 0.0342806 -0.0854822 -0.463755 0.0356669 -0.0854215 -0.463672 0.0354388 -0.0852369 -0.0967732 -0.143847 -0.0193371 -0.0967732 -0.143806 -0.0196394 -0.105573 -0.143975 -0.0196065 -0.106773 -0.144 -0.0196015 -0.115573 -0.144247 -0.0192591 -0.126773 -0.144554 -0.0191994 -0.135573 -0.14483 -0.0191456 -0.0761732 -0.143248 -0.021665 -0.0775732 -0.143347 -0.0210877 -0.0764636 -0.143225 -0.0218327 -0.071634 -0.141509 -0.0305913 -0.0717732 -0.141818 -0.0292861 -0.0717732 -0.141972 -0.0285864 -0.0830276 -0.135175 -0.0473308 -0.0823225 -0.135173 -0.0473226 -0.0891947 -0.135192 -0.0474025 -0.093233 -0.135208 -0.0474494 -0.0917732 -0.135642 -0.0466066 -0.0905732 -0.13563 -0.0466066 -0.103438 -0.135269 -0.047568 -0.100573 -0.135748 -0.0466066 -0.0989974 -0.135239 -0.0475164 -0.111173 -0.135341 -0.0476458 -0.1088 -0.135313 -0.0476303 -0.110573 -0.135894 -0.0466066 -0.110573 -0.136013 -0.0463802 -0.118603 -0.135412 -0.0477442 -0.121173 -0.135514 -0.0476458 -0.120573 -0.136068 -0.0466066 -0.121773 -0.136091 -0.0466066 -0.123849 -0.135475 -0.0478052 -0.148487 -0.139718 -0.0403215 -0.147904 -0.140406 -0.038599 -0.139575 -0.135853 -0.0477337 -0.140573 -0.136501 -0.0466066 -0.148832 -0.142748 -0.0316768 -0.134055 -0.135619 -0.0479237 -0.130758 -0.13557 -0.0478854 -0.131883 -0.136265 -0.0466699 -0.0724922 -0.141728 -0.0297012 -0.0719403 -0.142848 -0.0293826 -0.071634 -0.142993 -0.0305913 -0.0714848 -0.142228 -0.0336056 -0.138345 -0.137454 -0.047893 -0.139649 -0.133573 -0.0428948 -0.148914 -0.142385 -0.0376841 -0.147772 -0.140156 -0.0392195 -0.144569 -0.135175 -0.0382431 -0.147602 -0.13991 -0.0398105 -0.147973 -0.140745 -0.0416492 -0.146583 -0.13974 -0.0437942 -0.142649 -0.134198 -0.0410793 -0.145682 -0.139266 -0.0447341 -0.140573 -0.136997 -0.0466066 -0.141773 -0.137564 -0.0466066 -0.141773 -0.136949 -0.0458206 -0.142287 -0.13808 -0.046903 -0.143528 -0.138428 -0.0462945 -0.0755771 -0.134758 -0.0394521 -0.0729154 -0.138495 -0.0400491 -0.0805732 -0.136475 -0.0466066 -0.0817732 -0.135817 -0.0460891 -0.0805732 -0.135893 -0.0459226 -0.0732124 -0.138236 -0.040695 -0.0742182 -0.138445 -0.0439056 -0.0761208 -0.137747 -0.0454408 -0.0786185 -0.133768 -0.0423278 -0.0779154 -0.137307 -0.0463755 -0.0723309 -0.13958 -0.0412039 -0.0724176 -0.141402 -0.0310437 -0.0727391 -0.138678 -0.0395826 -0.147935 -0.142959 -0.0308093 -0.148771 -0.143109 -0.0303265 -0.148487 -0.141318 -0.0403215 -0.0755198 -0.144703 -0.0220423 -0.0867732 -0.143651 -0.0196693 -0.0855732 -0.143677 -0.0193701 -0.0805732 -0.13554 -0.0466066 -0.0955732 -0.143826 -0.0193411 -0.115573 -0.145762 -0.0192591 -0.136773 -0.144827 -0.0194407 -0.138244 -0.135698 -0.0479511 -0.142287 -0.13638 -0.046903 -0.17812 -0.141517 -0.0470089 0.116805 -0.0920735 -0.0849295 -0.179132 -0.0810719 -0.0865716 -0.206703 -0.0810719 -0.0865717 -0.119151 -0.0920735 -0.0849295 -0.176966 -0.0805715 -0.086606 -0.119158 -0.107041 -0.0797264 -0.190988 -0.11013 -0.0783522 -0.217016 -0.110466 -0.078195 -0.234274 -0.10764 -0.0796033 -0.221351 -0.113644 -0.0764278 -0.22178 -0.114167 -0.0761172 -0.234274 -0.115274 -0.07544 -0.234274 -0.121643 -0.0709947 -0.225976 -0.123736 -0.0693056 -0.226173 -0.12614 -0.0672035 -0.234275 -0.134057 -0.0587618 -0.226173 -0.132254 -0.0609269 -0.234276 -0.138595 -0.0524589 -0.225712 -0.150362 -0.0192567 -0.234278 -0.150759 -0.016274 -0.234278 -0.150451 -0.0186165 -0.234278 -0.148456 -0.0293564 -0.226173 -0.145308 -0.0393683 -0.234277 -0.14626 -0.0368073 -0.234277 -0.1429 -0.0448267 -0.223739 -0.150857 -0.0154795 -0.203074 -0.151201 -0.0113476 -0.190977 -0.15108 -0.0113471 -0.184759 -0.150819 0.0117559 -0.178113 -0.15131 -0.000207253 -0.188135 -0.151011 0.0101931 -0.203074 -0.151201 0.00981762 -0.215171 -0.151257 0.00981782 -0.21833 -0.151224 0.0102846 -0.2188 -0.151211 0.0104381 -0.221627 -0.151074 0.0119271 -0.234279 -0.151614 0.00402353 -0.2242 -0.150784 0.0145686 -0.225764 -0.150335 0.0179105 -0.234278 -0.148156 0.0290376 -0.226173 -0.148025 0.0295516 -0.226173 -0.147445 0.0316236 -0.226173 -0.145311 0.0378299 -0.234276 -0.141258 0.0464605 -0.226173 -0.14126 0.0464605 -0.226173 -0.137012 0.0532916 -0.234275 -0.12476 0.0669013 -0.226173 -0.12614 0.0656735 -0.220822 -0.113057 0.0752401 -0.234274 -0.106364 0.0786613 -0.215173 -0.110164 0.0768226 -0.203081 -0.110153 0.0768225 -0.234273 -0.0910793 0.0836371 -0.119151 -0.0909955 0.0836371 -0.119157 -0.106047 0.0786613 -0.175597 -0.0795876 0.0851338 -0.17354 -0.0775029 0.0852133 -0.171418 -0.0766123 0.0852295 -0.173292 -0.0772784 0.0852183 0.231927 -0.087447 0.084307 0.116804 -0.0909955 0.0836371 0.171193 -0.0775029 0.0852133 0.116811 -0.106047 0.0786613 0.231927 -0.0950463 0.08269 0.187249 -0.110299 0.0767324 0.212827 -0.110164 0.0768226 0.231927 -0.106364 0.0786613 0.219005 -0.113644 0.0748979 0.231927 -0.11124 0.0762535 0.222593 -0.119871 0.0708031 0.231928 -0.12476 0.0669013 0.223827 -0.12614 0.0656735 0.231929 -0.135951 0.0547666 0.223827 -0.132254 0.059397 0.23193 -0.141258 0.0464605 0.223827 -0.141584 0.0458643 0.223827 -0.145308 0.0378383 0.231931 -0.144575 0.039625 0.231931 -0.145448 0.0374716 0.231931 -0.147442 0.0316236 0.223827 -0.147445 0.0316236 0.223827 -0.148065 0.0294004 0.231931 -0.148156 0.0290376 0.223827 -0.149856 0.0209046 0.223365 -0.150362 0.0177267 0.231932 -0.150619 0.0158506 0.231932 -0.151125 0.0113866 0.231932 -0.151614 0.00402353 0.221393 -0.150857 0.0139495 0.21569 -0.15123 0.0102005 0.215204 -0.15124 0.0100802 0.212824 -0.151257 0.00981782 0.200727 -0.151201 0.00981762 0.185471 -0.150998 0.0102838 0.184998 -0.150978 0.0104383 0.175767 -0.15131 -0.000207253 0.216453 -0.151211 -0.0119681 0.223418 -0.150335 -0.0194405 0.231932 -0.150451 -0.0186165 0.223827 -0.149856 -0.0224346 0.223827 -0.148025 -0.0310815 0.223827 -0.147753 -0.0320815 0.23193 -0.1429 -0.0448267 0.23193 -0.138595 -0.0524589 0.223827 -0.137012 -0.0548216 0.231928 -0.128232 -0.0652172 0.223827 -0.12614 -0.0672035 0.231928 -0.121643 -0.0709947 0.223352 -0.122343 -0.0704442 0.231928 -0.115274 -0.07544 0.231927 -0.10764 -0.0796033 0.222488 -0.119593 -0.0725348 0.220801 -0.116154 -0.0748837 0.188642 -0.11013 -0.0783522 0.184728 -0.111487 -0.0776224 0.182035 -0.114101 -0.0761169 0.116811 -0.107041 -0.0797264 0.231927 -0.0995113 -0.0828742 0.231927 -0.0921692 -0.0849295 0.173667 -0.0799652 -0.0866431 0.231927 -0.0882038 -0.0857127 -0.148997 -0.147153 -0.0306795 -0.148383 -0.147844 -0.0275504 -0.146944 -0.148354 -0.0247014 -0.146428 -0.148464 -0.0239999 -0.119203 -0.148744 -0.016274 -0.136708 -0.148885 -0.0193095 -0.13994 -0.148935 -0.0197277 -0.143948 -0.140681 -0.0474178 -0.146372 -0.141733 -0.0454425 -0.148319 -0.143143 -0.0424775 -0.149159 -0.144741 -0.0385403 -0.149142 -0.146056 -0.0346419 -0.139548 -0.139676 -0.0490933 -0.0602996 -0.131259 -0.0603182 -0.0715308 -0.142429 -0.040954 -0.0727786 -0.141349 -0.0436034 -0.0732639 -0.141057 -0.0442747 -0.0603499 -0.139724 -0.0470089 -0.0754534 -0.140099 -0.0463703 -0.0809588 -0.147617 -0.0196835 -0.0767041 -0.147353 -0.0212871 -0.074284 -0.147024 -0.023314 -0.0722861 -0.146485 -0.026385 -0.0604241 -0.147886 -0.016274 -0.0603936 -0.14521 -0.0320815 -0.0711733 -0.14471 -0.0341267 0.175768 -0.150383 -0.016274 0.167403 -0.151105 -0.00375234 0.160892 -0.150879 -0.00597478 0.159287 -0.150871 -0.00505611 0.158073 -0.150876 -0.00365415 0.116856 -0.148744 -0.016274 0.116859 -0.149603 -0.000207253 0.116856 -0.148615 0.0158506 0.164086 -0.150951 0.00461594 0.165779 -0.151019 0.00387407 0.167997 -0.151141 0.000960753 -0.169481 -0.151089 -0.00413812 -0.168509 -0.151038 0.00359757 -0.170344 -0.151141 -0.00249069 -0.119202 -0.148615 0.0158506 -0.160419 -0.150876 0.00212421 -0.159612 -0.150886 -0.000764971 -0.183009 -0.116082 -0.0748783 -0.185305 -0.113034 -0.0767487 -0.179977 -0.145024 -0.0393748 -0.178117 -0.147417 -0.0320815 -0.179975 -0.147446 -0.0320815 -0.181672 -0.150415 -0.0165145 -0.178114 -0.150383 -0.016274 -0.180598 -0.150104 0.0172176 -0.179973 -0.149522 0.0209023 -0.178114 -0.150245 0.0158506 -0.179975 -0.147142 0.0316236 -0.179977 -0.145032 0.0378258 -0.179979 -0.141335 0.0458684 -0.180185 -0.123594 0.0677872 -0.179985 -0.125999 0.0656716 -0.179983 -0.132079 0.0593923 0.179596 -0.150469 0.0145729 0.175768 -0.150245 0.0158506 0.11682 -0.119583 0.0705352 0.178114 -0.122225 0.0689131 0.180663 -0.116082 0.0733484 0.182959 -0.113034 0.0752188 0.177635 -0.136802 0.0532877 0.177633 -0.141015 0.0464605 0.17577 -0.147113 0.0316236 0.11682 -0.120448 -0.0713945 0.179736 -0.150495 -0.015905 0.18007 -0.150551 -0.0154663 0.178089 -0.150029 -0.019251 0.177628 -0.147763 -0.0308962 0.17763 -0.145032 -0.0393557 0.17577 -0.147417 -0.0320815 0.177636 -0.132593 -0.0603182 0.175778 -0.132575 -0.0603182 -0.00117319 -0.0920323 -0.0849295 -0.136733 -0.139479 -0.0493296 -0.119177 -0.131711 -0.0603182 -0.119172 -0.126381 -0.06617 -0.00117319 -0.139717 -0.0470089 -0.00117319 -0.145202 -0.0320815 -0.0604351 -0.148709 -0.000207253 -0.00117319 -0.147876 -0.016274 -0.0604225 -0.147763 0.0158506 -0.00117319 -0.148699 -0.000207253 -0.00117319 -0.147753 0.0158506 -0.0603909 -0.144932 0.0316236 -0.0603466 -0.139231 0.0464605 -0.00117319 -0.139224 0.0464605 -0.119196 -0.145681 0.0316236 -0.119205 -0.149603 -0.000207253 -0.0827504 -0.147656 -0.0195378 -0.109733 -0.148123 -0.0194512 -0.166883 -0.150967 0.00448321 -0.165057 -0.150911 0.00477678 -0.178117 -0.147113 0.0316236 -0.119187 -0.139836 0.0464605 -0.17812 -0.140992 0.0464605 -0.119176 -0.131011 0.0596339 -0.178125 -0.131853 0.0596339 -0.119171 -0.125594 0.0654027 -0.119166 -0.119583 0.0705352 -0.0602961 -0.13057 0.0596339 -0.00117319 -0.0909594 0.0836371 0.0217332 -0.0766123 0.0852294 0.175774 -0.140992 0.0464605 0.11684 -0.139836 0.0464605 0.11685 -0.145681 0.0316236 0.160462 -0.150875 0.00426677 0.164537 -0.150967 -0.00601316 0.162711 -0.150911 -0.00630672 0.175774 -0.141517 -0.0470089 0.11685 -0.145968 -0.0320815 0.116831 -0.131711 -0.0603182 0.175778 -0.131853 0.0596339 0.116825 -0.125594 0.0654027 0.0579497 -0.13057 0.0596339 0.11683 -0.131011 0.0596339 0.0580002 -0.139231 0.0464605 0.0580777 -0.147886 -0.016274 0.0580472 -0.14521 -0.0320815 0.0580036 -0.139724 -0.0470089 0.116841 -0.14034 -0.0470089 -0.0251327 -0.0777273 -0.0867374 -0.00117319 -0.106895 -0.0797264 0.116825 -0.126381 -0.06617 -0.00117319 -0.105911 0.0786613 -0.00117319 -0.119302 0.0705352 -0.00117319 -0.130565 0.0596339 0.0580445 -0.144932 0.0316236 -0.00117319 -0.144923 0.0316236 0.0580762 -0.147763 0.0158506 0.0580887 -0.148709 -0.000207253 -0.00117319 -0.131254 -0.0603182 0.0579533 -0.131259 -0.0603182 -0.00117319 -0.120157 -0.0713945 -0.119167 -0.120448 -0.0713945 -0.178124 -0.132575 -0.0603182 -0.144601 -0.144594 -0.0225729 -0.118694 -0.137154 -0.0476918 -0.113542 -0.137098 -0.0476279 -0.120573 -0.136122 -0.0465054 -0.121773 -0.13621 -0.0466066 -0.136773 -0.137383 -0.0479553 -0.130501 -0.136247 -0.0466485 -0.121773 -0.136136 -0.0465217 -0.100573 -0.135922 -0.0462745 -0.101773 -0.135932 -0.0462862 -0.0892071 -0.136896 -0.0473953 -0.0830276 -0.13684 -0.0473308 -0.0990681 -0.136966 -0.0474755 -0.0931914 -0.136922 -0.0474254 -0.0917732 -0.135855 -0.0461981 -0.147986 -0.142587 -0.0321652 -0.145083 -0.138716 -0.0279596 -0.135573 -0.144787 -0.0194485 -0.116773 -0.145792 -0.0192532 -0.125573 -0.144476 -0.019509 -0.116773 -0.144236 -0.0195558 -0.126773 -0.144511 -0.0195021 -0.126773 -0.146069 -0.0191994 -0.135573 -0.146346 -0.0191456 -0.0967732 -0.145361 -0.0193371 -0.115573 -0.144205 -0.0195617 -0.0855732 -0.14519 -0.0193702 -0.0855732 -0.143636 -0.0196724 -0.0955732 -0.143785 -0.0196434 -0.136773 -0.141421 -0.0201029 -0.143636 -0.144701 -0.0217442 -0.139486 -0.146435 -0.0194303 -0.138963 -0.146432 -0.0193248 -0.136773 -0.146386 -0.0191378 -0.145024 -0.146169 -0.0223288 -0.145785 -0.146063 -0.0230952 -0.14445 -0.139751 -0.024953 -0.147802 -0.145555 -0.0261657 -0.148083 -0.145427 -0.0268474 -0.0717732 -0.143191 -0.0292861 -0.0717732 -0.143506 -0.0285864 -0.0744638 -0.138716 -0.0279596 -0.0749774 -0.139652 -0.0252403 -0.0735714 -0.144343 -0.0241819 -0.0765669 -0.143238 -0.0217543 -0.0793715 -0.145047 -0.0199104 -0.0798972 -0.141254 -0.0205885 -0.0827732 -0.145156 -0.0193769 -0.0761959 -0.137056 -0.0358493 -0.0732149 -0.141656 -0.040133 -0.0827732 -0.138721 -0.0464461 -0.0794845 -0.135202 -0.0412351 -0.0796136 -0.138946 -0.0459921 -0.0771663 -0.139487 -0.0449459 -0.0765774 -0.139676 -0.0445711 -0.0761959 -0.139661 -0.0282852 -0.0729171 -0.143731 -0.0339086 -0.0794845 -0.141516 -0.0228994 -0.077077 -0.140732 -0.0251757 -0.0782096 -0.14589 -0.022387 -0.0736615 -0.145171 -0.027547 -0.0739322 -0.145274 -0.0268996 -0.0753547 -0.145598 -0.0246809 -0.0756543 -0.145643 -0.0243456 -0.136773 -0.139241 -0.0470448 -0.136773 -0.147286 -0.0210002 -0.147 -0.146555 -0.0286294 -0.142469 -0.140732 -0.0251757 -0.141424 -0.141175 -0.0238877 -0.140062 -0.141516 -0.0228994 -0.139907 -0.147365 -0.021454 -0.136773 -0.141802 -0.0220662 -0.136773 -0.134915 -0.0420683 -0.139172 -0.139419 -0.0468616 -0.140062 -0.135202 -0.0412351 -0.139848 -0.13952 -0.0467241 -0.142469 -0.135986 -0.0389588 -0.145034 -0.141221 -0.0439049 -0.142448 -0.140139 -0.0457821 -0.143351 -0.139661 -0.0282852 -0.14746 -0.145091 -0.03438 -0.0761732 -0.144366 -0.021665 -0.0817732 -0.136265 -0.0466066 -0.0917732 -0.13621 -0.0466066 -0.0905732 -0.13621 -0.0466066 -0.0905732 -0.135847 -0.0461888 -0.101773 -0.13621 -0.0466066 -0.111773 -0.13621 -0.0466066 -0.111773 -0.136026 -0.0463942 -0.120573 -0.13621 -0.0466066 -0.145321 -0.144686 -0.022157 -0.141773 -0.136529 -0.0466066 -0.140573 -0.136697 -0.0462413 -0.120955 -0.13544 -0.0477715 -0.0817732 -0.135549 -0.0466066 -0.0827732 -0.136712 -0.0471839 -0.100573 -0.13621 -0.0466066 -0.103349 -0.137001 -0.0475163 -0.101773 -0.135764 -0.0466066 -0.108897 -0.137052 -0.0475745 -0.110573 -0.13621 -0.0466066 -0.111773 -0.135913 -0.0466066 -0.1214 -0.135445 -0.0477767 -0.121312 -0.137183 -0.0477262 -0.121173 -0.137114 -0.0476458 -0.131173 -0.137114 -0.0476458 -0.131173 -0.135713 -0.0476458 -0.128406 -0.135536 -0.0478581 -0.134034 -0.137345 -0.0479116 -0.131605 -0.135582 -0.0478953 0.23976 -0.08 -0.07918 0.236623 -0.08 -0.083416 0.236914 -0.08 -0.0838246 0.231927 -0.08 -0.085073 0.204356 -0.08 0.083543 0.204356 -0.08 0.0840443 0.231927 -0.08 0.0835431 0.231927 -0.08 0.0840444 0.236623 -0.08 0.081886 0.23457 -0.08 0.0835941 0.2387 -0.08 0.0802913 0.239249 -0.08 0.07765 -0.242107 -0.08 0.07765 -0.237037 -0.08 0.0835506 -0.206703 -0.08 0.083543 -0.234273 -0.08 0.0840444 -0.179132 -0.08 0.0835429 -0.206703 -0.08 0.0840443 -0.206703 -0.08 -0.085073 -0.179132 -0.08 -0.0855742 -0.206703 -0.08 -0.0855743 -0.237037 -0.08 -0.0850805 -0.241595 -0.08 -0.07918 -0.240773 -0.101613 -0.0640519 -0.240773 -0.116116 -0.0638918 -0.240773 -0.122782 -0.0486252 -0.240773 -0.112925 0.0558077 -0.240773 -0.0820438 -0.074503 -0.240773 -0.0868608 -0.0768117 -0.240773 -0.094422 -0.0750455 -0.240773 -0.131029 -0.047586 -0.240773 -0.112925 -0.0573376 -0.240773 -0.122005 -0.058717 -0.240773 -0.142605 0.004079 -0.240773 -0.142561 -0.00658596 -0.240773 -0.136799 -0.0264967 -0.240773 -0.141563 -0.0171891 -0.240773 -0.130835 -0.0382224 -0.240773 -0.122782 0.0470953 -0.240773 -0.118758 0.0601933 -0.240773 -0.0811228 0.0760111 -0.240773 -0.086034 0.0754186 -0.240773 -0.141047 0.0190044 -0.240773 -0.132805 0.0431337 -0.240773 -0.136965 0.0344546 -0.240773 -0.139399 0.0269529 -0.240773 -0.0924651 0.0740636 -0.240773 -0.0892433 0.0670011 -0.237523 -0.0869178 0.080978 -0.240619 -0.080983 0.0774342 -0.239902 -0.0809619 0.079284 -0.234275 -0.133766 0.0535169 -0.234275 -0.129178 0.0590952 -0.234274 -0.123011 0.0651087 -0.237524 -0.122441 0.0644499 -0.237524 -0.11574 0.069588 -0.237523 -0.109639 0.0732872 -0.237523 -0.101924 0.0768768 -0.234273 -0.102243 0.0776869 -0.237523 -0.0938992 0.079507 -0.234273 -0.094121 0.0803491 -0.234273 -0.0870545 0.081838 -0.234273 -0.0809277 0.0825457 -0.237525 -0.137689 0.0459309 -0.234275 -0.138445 0.0463641 -0.234276 -0.140849 0.0417972 -0.234276 -0.143016 0.0368277 -0.237525 -0.144847 0.0283663 -0.237525 -0.146596 0.0199411 -0.234277 -0.147456 0.0200862 -0.234277 -0.148636 0.0111489 -0.237525 -0.147768 0.011066 -0.234277 -0.1491 0.00434408 -0.237525 -0.148228 0.00430851 -0.237525 -0.148182 -0.00686176 -0.234277 -0.149053 -0.0069045 -0.237525 -0.147137 -0.0179672 -0.237525 -0.145177 -0.028572 -0.237525 -0.143174 -0.0354186 -0.237525 -0.139934 -0.043217 -0.234275 -0.136494 -0.0511053 -0.234274 -0.126579 -0.0633358 -0.237523 -0.10633 -0.076494 -0.234273 -0.0987156 -0.0805042 -0.234273 -0.0962711 -0.081277 -0.237523 -0.0960233 -0.0804421 -0.234273 -0.0879632 -0.0832176 -0.237523 -0.0878155 -0.0823593 -0.23642 -0.0809314 -0.0837095 -0.237523 -0.0809366 -0.0832017 -0.239902 -0.087412 -0.0800146 -0.237523 -0.0984385 -0.0796786 -0.237524 -0.113732 -0.0724282 -0.239902 -0.10531 -0.0743446 -0.237524 -0.119573 -0.0683341 -0.239902 -0.112466 -0.0704143 -0.239902 -0.118112 -0.0664565 -0.237524 -0.125966 -0.0627167 -0.237524 -0.131605 -0.05643 -0.237524 -0.135761 -0.0506335 -0.239903 -0.133761 -0.0493453 -0.239903 -0.137794 -0.0421759 -0.239903 -0.142863 -0.0280187 -0.239903 -0.145806 -0.00674517 -0.239903 -0.1454 0.0108397 -0.239903 -0.13999 0.0356408 -0.237525 -0.142205 0.0365094 -0.237525 -0.141471 0.0383089 -0.239903 -0.13928 0.0373803 -0.239903 -0.135625 0.0447486 -0.237524 -0.133067 0.0529976 -0.237524 -0.128533 0.0585088 -0.239903 -0.126774 0.0569074 -0.239903 -0.120884 0.0626508 -0.239902 -0.10105 0.0746638 -0.239902 -0.0865443 0.0786283 -0.239902 -0.0932931 0.0772063 -0.240773 -0.099857 0.0716408 -0.240773 -0.106965 0.068334 -0.239902 -0.108508 0.0711937 -0.240773 -0.112585 0.0649264 -0.239902 -0.114406 0.0676177 -0.239903 -0.131156 0.0515798 -0.240773 -0.124371 0.0547201 -0.240773 -0.128547 0.0496434 -0.240773 -0.136289 0.036112 -0.239903 -0.142544 0.0277689 -0.239903 -0.144251 0.0195451 -0.240773 -0.142165 0.0105308 -0.239903 -0.145851 0.00421149 -0.239903 -0.14478 -0.0176383 -0.240773 -0.139703 -0.0272629 -0.239903 -0.140926 -0.0346374 -0.240773 -0.137857 -0.0335704 -0.240773 -0.134873 -0.040754 -0.239903 -0.129743 -0.054949 -0.240773 -0.1272 -0.052926 -0.239903 -0.124292 -0.0610262 -0.240773 -0.110735 -0.0676634 -0.240773 -0.103917 -0.0714085 -0.239902 -0.0976812 -0.0774232 -0.239902 -0.0953466 -0.0781612 -0.240773 -0.0966468 -0.0743422 -0.240735 -0.0810218 -0.0782551 -0.240773 -0.0811228 -0.077541 -0.243273 -0.101613 0.062522 -0.243273 -0.086034 0.0754186 -0.243273 -0.0849771 0.0691837 -0.243273 -0.0892433 0.0670011 -0.243273 -0.140464 -0.0138621 -0.243273 -0.134815 -0.0408721 -0.243273 -0.121912 -0.0588094 -0.243273 -0.118857 0.0601072 -0.243273 -0.116116 -0.0638918 -0.243273 -0.128703 0.0494321 -0.243273 -0.122782 0.0470953 -0.243273 -0.136289 0.036112 -0.243273 -0.0866995 -0.0768393 -0.243273 -0.0854077 -0.0703742 -0.243273 -0.0941361 -0.0751297 -0.243273 -0.0892433 -0.068531 -0.243273 -0.0966468 -0.0743422 -0.243273 -0.103798 -0.0714648 -0.243273 -0.101613 -0.0640519 -0.243273 -0.110513 -0.0678027 -0.243273 -0.130835 0.0366925 -0.243273 -0.142547 -0.00687297 -0.243273 -0.136799 0.0249667 -0.243273 -0.139439 0.0267984 -0.243273 -0.0811228 0.0760111 -0.240005 -0.0810568 0.0829758 -0.234273 -0.087447 0.084307 -0.234273 -0.0810719 0.0850418 -0.243086 -0.081016 -0.0793823 -0.241983 -0.0810391 -0.0822062 -0.234273 -0.0950463 0.08269 -0.234274 -0.11124 0.0762535 -0.234273 -0.1033 0.0799573 -0.234274 -0.117876 0.0722121 -0.238774 -0.117196 0.071216 -0.238774 -0.130134 0.0599659 -0.234275 -0.131027 0.060778 -0.234277 -0.144575 0.039625 -0.234276 -0.140689 0.0474765 -0.234276 -0.135951 0.0547666 -0.234278 -0.147442 0.0316236 -0.238776 -0.144323 0.0370352 -0.234277 -0.145448 0.0374716 -0.238776 -0.150329 -0.00727368 -0.238776 -0.150407 0.00397828 -0.234279 -0.151125 0.0113866 -0.238776 -0.149923 0.0112718 -0.234278 -0.150619 0.0158506 -0.234278 -0.149936 0.0204134 -0.234278 -0.14775 -0.0320815 -0.238776 -0.149255 -0.0184478 -0.234279 -0.151535 -0.00733578 -0.238776 -0.145121 -0.0364064 -0.238775 -0.141816 -0.0442964 -0.234277 -0.141788 -0.0470089 -0.234275 -0.128232 -0.0652172 -0.238773 -0.0991276 -0.0817311 -0.238773 -0.0963194 -0.0826118 -0.234273 -0.0995113 -0.0828742 -0.234273 -0.0966572 -0.0837693 -0.243273 -0.0927187 0.0739962 -0.243273 -0.0999792 0.0715924 -0.242067 -0.10164 0.0757747 -0.243273 -0.106965 0.068334 -0.243273 -0.112802 0.0647788 -0.242068 -0.121808 0.0635039 -0.242068 -0.127698 0.0577487 -0.243273 -0.124371 0.0547201 -0.242068 -0.132326 0.0520989 -0.243273 -0.13287 0.0430194 -0.242068 -0.136779 0.0452475 -0.243273 -0.137057 0.0342182 -0.242068 -0.141252 0.0358445 -0.243273 -0.141061 0.0189218 -0.243273 -0.142165 0.0105308 -0.242068 -0.145497 0.0196674 -0.242068 -0.146644 0.0109585 -0.243273 -0.14262 0.00368627 -0.242068 -0.147116 0.00385484 -0.243273 -0.141539 -0.0173592 -0.242068 -0.144078 -0.0283093 -0.243273 -0.139703 -0.0272629 -0.243273 -0.137771 -0.0338181 -0.242068 -0.142014 -0.0353123 -0.243273 -0.131029 -0.047586 -0.242068 -0.134811 -0.050022 -0.243273 -0.127036 -0.053131 -0.242068 -0.125071 -0.062013 -0.242067 -0.0953966 -0.0794495 -0.242067 -0.0874517 -0.0812759 -0.242067 -0.0980791 -0.0786082 -0.238773 -0.107125 -0.0785128 -0.238774 -0.114636 -0.0744166 -0.242068 -0.105719 -0.0755339 -0.242068 -0.112893 -0.0716212 -0.238774 -0.120903 -0.0700428 -0.242068 -0.11888 -0.067443 -0.238774 -0.127384 -0.0643583 -0.238775 -0.133116 -0.058007 -0.242068 -0.130546 -0.055946 -0.238775 -0.137581 -0.0518056 -0.242068 -0.138857 -0.0428489 -0.238776 -0.147282 -0.0290755 -0.242068 -0.145993 -0.0179877 -0.242068 -0.147039 -0.00710429 -0.238776 -0.148746 0.0202133 -0.238776 -0.146987 0.0287372 -0.242068 -0.143796 0.0279177 -0.242068 -0.140431 0.0378681 -0.238775 -0.143464 0.0391538 -0.238775 -0.139641 0.0468788 -0.238775 -0.13498 0.0540514 -0.238774 -0.123969 0.0659907 -0.242068 -0.115339 0.0684953 -0.238774 -0.110667 0.0751924 -0.242068 -0.109102 0.0722936 -0.238773 -0.102855 0.0788365 -0.238773 -0.0947344 0.0815252 -0.242067 -0.0938825 0.0783431 -0.238773 -0.0872577 0.0831162 -0.242067 -0.0867405 0.0798628 -0.241983 -0.0810391 0.0806762 -0.234273 -0.0921692 -0.0849295 -0.238773 -0.0880023 -0.0845238 -0.234273 -0.0882038 -0.0857127 -0.237382 -0.0810679 -0.0860165 0.235177 -0.0809366 -0.0832017 0.237556 -0.0809619 -0.080814 0.235997 -0.0809424 0.0811085 0.237448 -0.0809599 0.0794654 0.231927 -0.094121 0.0803491 0.235177 -0.101924 0.0768768 0.235177 -0.11574 0.069588 0.231927 -0.116228 0.0703094 0.235177 -0.122441 0.0644499 0.235178 -0.133067 0.0529976 0.235178 -0.137689 0.0459309 0.231929 -0.138445 0.0463641 0.231929 -0.140849 0.0417972 0.235178 -0.141471 0.0383089 0.23193 -0.142273 0.0386492 0.23193 -0.145691 0.0285853 0.23193 -0.144098 0.0338822 0.235178 -0.142205 0.0365094 0.23193 -0.143016 0.0368277 0.235179 -0.144847 0.0283663 0.235179 -0.146596 0.0199411 0.235179 -0.147768 0.011066 0.235179 -0.148228 0.00430851 0.235179 -0.145177 -0.028572 0.235179 -0.143174 -0.0354186 0.23193 -0.143997 -0.0357049 0.235178 -0.139934 -0.043217 0.238427 -0.086034 0.0754186 0.237556 -0.0932931 0.0772063 0.238427 -0.099857 0.0716408 0.238427 -0.112585 0.0649264 0.238427 -0.124371 0.0547201 0.238427 -0.128547 0.0496434 0.237556 -0.131156 0.0515798 0.238427 -0.132805 0.0431337 0.238427 -0.136289 0.036112 0.238427 -0.139399 0.0269529 0.237557 -0.144251 0.0195451 0.237557 -0.1454 0.0108397 0.238427 -0.142165 0.0105308 0.238427 -0.142605 0.004079 0.237557 -0.145851 0.00421149 0.238427 -0.141563 -0.0171891 0.237557 -0.14478 -0.0176383 0.238427 -0.134873 -0.040754 0.238427 -0.1272 -0.052926 0.238427 -0.122005 -0.058717 0.237556 -0.124292 -0.0610262 0.238427 -0.110735 -0.0676634 0.237556 -0.118112 -0.0664565 0.237556 -0.112466 -0.0704143 0.238427 -0.103917 -0.0714085 0.238427 -0.094422 -0.0750455 0.237556 -0.0953466 -0.0781612 0.237556 -0.087412 -0.0800146 0.237448 -0.0809599 -0.0809954 0.235997 -0.0809424 -0.0826385 0.235177 -0.0960233 -0.0804421 0.237556 -0.0976812 -0.0774232 0.235177 -0.0984385 -0.0796786 0.237556 -0.10531 -0.0743446 0.235177 -0.10633 -0.076494 0.235177 -0.113732 -0.0724282 0.235177 -0.119573 -0.0683341 0.237556 -0.129743 -0.054949 0.237556 -0.133761 -0.0493453 0.237556 -0.137794 -0.0421759 0.237556 -0.140926 -0.0346374 0.237557 -0.142863 -0.0280187 0.235179 -0.147137 -0.0179672 0.237557 -0.145806 -0.00674517 0.235179 -0.148182 -0.00686176 0.237557 -0.142544 0.0277689 0.237556 -0.13999 0.0356408 0.237556 -0.13928 0.0373803 0.237556 -0.135625 0.0447486 0.235178 -0.128533 0.0585088 0.237556 -0.126774 0.0569074 0.237556 -0.120884 0.0626508 0.237556 -0.114406 0.0676177 0.237556 -0.108508 0.0711937 0.235177 -0.109639 0.0732872 0.237556 -0.10105 0.0746638 0.237556 -0.0865443 0.0786283 0.235177 -0.0938992 0.079507 0.235177 -0.0869178 0.080978 0.235177 -0.0809366 0.0816717 0.231929 -0.137264 -0.0498832 0.235178 -0.135761 -0.0506335 0.231929 -0.136494 -0.0511053 0.235178 -0.131605 -0.05643 0.231928 -0.132287 -0.0569725 0.235178 -0.125966 -0.0627167 0.231927 -0.0987156 -0.0805042 0.235177 -0.0878155 -0.0823593 0.238427 -0.0849771 0.0691837 0.238427 -0.0924651 0.0740636 0.238427 -0.0825588 -0.0735352 0.238427 -0.0811228 -0.077541 0.238427 -0.0868608 -0.0768117 0.238427 -0.0966468 -0.0743422 0.238427 -0.106965 0.068334 0.238427 -0.101613 0.062522 0.238427 -0.118758 0.0601933 0.238427 -0.122782 0.0470953 0.238427 -0.137857 -0.0335704 0.238427 -0.136799 -0.0264967 0.238427 -0.139703 -0.0272629 0.238427 -0.131029 -0.047586 0.238427 -0.122782 -0.0486252 0.238427 -0.116116 -0.0638918 0.238427 -0.136799 0.0249667 0.238427 -0.130835 0.0366925 0.238427 -0.136965 0.0344546 0.238427 -0.142561 -0.00658596 0.238427 -0.141047 0.0190044 0.169072 -0.0756 0.0837295 -0.0250792 -0.0756 0.0837295 0.240739 -0.081016 -0.0793823 0.239721 -0.0874517 -0.0812759 0.2349 -0.0810682 -0.0860654 0.236427 -0.0872577 0.0831162 0.236427 -0.0810632 0.0838333 0.237538 -0.0810575 0.0830744 0.239721 -0.0867405 0.0798628 0.231927 -0.0910793 0.0836371 0.231927 -0.1033 0.0799573 0.236427 -0.110667 0.0751924 0.231928 -0.117876 0.0722121 0.236427 -0.117196 0.071216 0.231929 -0.131027 0.060778 0.236428 -0.13498 0.0540514 0.23193 -0.140689 0.0474765 0.236429 -0.139641 0.0468788 0.236429 -0.143464 0.0391538 0.23643 -0.149923 0.0112718 0.231932 -0.149936 0.0204134 0.231932 -0.151535 -0.00733578 0.231932 -0.150759 -0.016274 0.23643 -0.149255 -0.0184478 0.231931 -0.148456 -0.0293564 0.236429 -0.147282 -0.0290755 0.231931 -0.14775 -0.0320815 0.231931 -0.14626 -0.0368073 0.236429 -0.145121 -0.0364064 0.236429 -0.141816 -0.0442964 0.231929 -0.134057 -0.0587618 0.236428 -0.127384 -0.0643583 0.236427 -0.114636 -0.0744166 0.236427 -0.107125 -0.0785128 0.231927 -0.0966572 -0.0837693 0.236427 -0.0880023 -0.0845238 0.237538 -0.0810575 -0.0846044 0.236427 -0.0963194 -0.0826118 0.236427 -0.0991276 -0.0817311 0.239721 -0.0980791 -0.0786082 0.236427 -0.120903 -0.0700428 0.239721 -0.130546 -0.055946 0.236428 -0.133116 -0.058007 0.239722 -0.134811 -0.050022 0.236428 -0.137581 -0.0518056 0.239722 -0.142014 -0.0353123 0.239722 -0.145993 -0.0179877 0.23643 -0.150329 -0.00727368 0.23643 -0.150407 0.00397828 0.23643 -0.148746 0.0202133 0.236429 -0.146987 0.0287372 0.239722 -0.143796 0.0279177 0.239722 -0.141252 0.0358445 0.236429 -0.144323 0.0370352 0.236428 -0.130134 0.0599659 0.236428 -0.123969 0.0659907 0.239721 -0.10164 0.0757747 0.236427 -0.102855 0.0788365 0.236427 -0.0947344 0.0815252 0.239721 -0.0938825 0.0783431 0.240927 -0.106965 0.068334 0.239721 -0.109102 0.0722936 0.239721 -0.115339 0.0684953 0.240927 -0.118857 0.0601072 0.239721 -0.121808 0.0635039 0.240927 -0.124371 0.0547201 0.239721 -0.127698 0.0577487 0.239721 -0.132326 0.0520989 0.239722 -0.136779 0.0452475 0.239722 -0.140431 0.0378681 0.240927 -0.13287 0.0430194 0.240927 -0.136289 0.036112 0.239722 -0.145497 0.0196674 0.240927 -0.141061 0.0189218 0.239722 -0.146644 0.0109585 0.240927 -0.14262 0.00368627 0.239722 -0.147116 0.00385484 0.239722 -0.147039 -0.00710429 0.240927 -0.141539 -0.0173592 0.239722 -0.144078 -0.0283093 0.240927 -0.139703 -0.0272629 0.240927 -0.137771 -0.0338181 0.239722 -0.138857 -0.0428489 0.239721 -0.125071 -0.062013 0.239721 -0.11888 -0.067443 0.239721 -0.112893 -0.0716212 0.239721 -0.105719 -0.0755339 0.240927 -0.0966468 -0.0743422 0.239721 -0.0953966 -0.0794495 0.240927 -0.0941361 -0.0751297 0.240927 -0.0866995 -0.0768393 0.24088 -0.0810386 -0.0784635 0.240927 -0.086034 0.0754186 0.240927 -0.0892433 0.0670011 0.240927 -0.0927187 0.0739962 0.240927 -0.101613 0.062522 0.240927 -0.0999792 0.0715924 0.240927 -0.112802 0.0647788 0.240927 -0.116116 -0.0638918 0.240927 -0.134815 -0.0408721 0.240927 -0.131029 -0.047586 0.240927 -0.127036 -0.053131 0.240927 -0.121912 -0.0588094 0.240927 -0.139439 0.0267984 0.240927 -0.137057 0.0342182 0.240927 -0.128703 0.0494321 0.240927 -0.130835 0.0366925 0.240927 -0.0892433 -0.068531 0.240927 -0.101613 -0.0640519 0.240927 -0.103798 -0.0714648 0.240927 -0.110513 -0.0678027 0.240927 -0.142165 0.0105308 0.240927 -0.1417 -0.000764971 0.240927 -0.142547 -0.00687297 0.240927 -0.136799 -0.0264967 0.173479 -0.0783501 -0.0851879 0.173479 -0.0783501 -0.0856884 -0.0251327 -0.0767 -0.0857378 0.0237859 -0.0767 -0.0852376 0.171901 -0.0767716 0.0837134 0.173957 -0.0788285 0.0841351 -0.175825 -0.0783501 -0.0851879 -0.175825 -0.0783501 -0.0856884 -0.175275 -0.0778002 0.0841815 -0.111173 -0.137049 -0.0476458 -0.111194 -0.135335 -0.0476581 -0.111194 -0.137043 -0.0476581 -0.19099 -0.150083 -0.012265 -0.188119 -0.150002 -0.012686 -0.187691 -0.148394 -0.0128248 -0.187689 -0.149982 -0.0128254 -0.184765 -0.148187 -0.0144381 -0.181249 -0.147403 -0.0200011 -0.181248 -0.148938 -0.0200064 -0.181358 -0.14901 -0.0195756 -0.182537 -0.147858 -0.0169215 -0.182329 -0.149372 -0.0172657 -0.18278 -0.149476 -0.0165553 -0.215173 -0.148667 -0.012265 -0.225173 -0.148871 -0.022265 -0.225173 -0.147348 -0.022265 -0.223262 -0.149812 -0.0163859 -0.223835 -0.148115 -0.0172668 -0.224754 -0.149372 -0.0193986 -0.222956 -0.148278 -0.0159859 -0.217336 -0.150243 -0.0125016 -0.217324 -0.14865 -0.0124991 -0.220173 -0.148545 -0.0136048 -0.220173 -0.150138 -0.0136048 -0.220439 -0.150122 -0.0137635 -0.225173 -0.145275 -0.0316576 -0.225173 -0.147097 -0.0306767 -0.225173 -0.140704 -0.0469205 -0.225173 -0.134702 -0.053759 -0.225173 -0.136728 -0.0534721 -0.18099 -0.146746 -0.0308349 -0.18099 -0.139097 -0.0463041 -0.18099 -0.134591 -0.0536321 -0.18099 -0.135981 -0.0542475 -0.18099 -0.130703 -0.0609787 -0.18099 -0.125323 -0.066465 -0.18099 -0.126496 -0.063272 -0.216848 -0.110002 -0.0763237 -0.215173 -0.109703 -0.076465 -0.218665 -0.109582 -0.0758355 -0.225003 -0.121017 -0.0683031 -0.22441 -0.11842 -0.0702964 -0.223215 -0.115374 -0.0724093 -0.221079 -0.111928 -0.074535 -0.22118 -0.113653 -0.07446 -0.219022 -0.111289 -0.0756947 -0.19099 -0.108333 -0.076465 -0.215173 -0.108366 -0.076465 -0.203081 -0.109692 -0.076465 -0.181421 -0.121599 -0.069372 -0.182201 -0.118921 -0.0712358 -0.181485 -0.119285 -0.0695723 -0.184027 -0.113357 -0.0736427 -0.185138 -0.1118 -0.074574 -0.185963 -0.110861 -0.0751099 -0.186856 -0.110027 -0.0755706 -0.189723 -0.109835 -0.0763845 -0.189074 -0.10869 -0.0762798 0.178643 -0.129298 0.0587818 0.178643 -0.130703 0.0594488 0.178643 -0.140474 0.0453574 0.178643 -0.142543 0.0373572 0.178643 -0.146746 0.0293049 0.185344 -0.148394 0.0112948 0.182772 -0.149803 0.0126397 0.185343 -0.149982 0.0112954 0.180433 -0.149476 0.0150254 0.182419 -0.148187 0.0129082 0.178902 -0.148938 0.0184765 0.178903 -0.147403 0.0184711 0.179404 -0.149193 0.0169098 0.179404 -0.147641 0.0169101 0.180191 -0.147858 0.0153915 0.212827 -0.148667 0.010735 0.212827 -0.150261 0.010735 0.222827 -0.148871 0.020735 0.22226 -0.147881 0.0174151 0.221488 -0.149693 0.0157365 0.22061 -0.148278 0.0144559 0.217827 -0.148545 0.0120749 0.215431 -0.150234 0.0110801 0.217827 -0.150138 0.0120749 0.218092 -0.150122 0.0122336 0.222827 -0.125466 0.064935 0.222827 -0.131498 0.0587423 0.222827 -0.129357 0.0588989 0.222827 -0.134702 0.0522291 0.222827 -0.138577 0.0461365 0.222827 -0.144377 0.0374719 0.222827 -0.147348 0.020735 0.178643 -0.125323 0.064935 0.179138 -0.119285 0.0680424 0.18168 -0.113357 0.0721128 0.183477 -0.112533 0.0734971 0.187377 -0.109835 0.0748545 0.186728 -0.10869 0.0747499 0.216683 -0.109852 0.0741616 0.216319 -0.109582 0.0743055 0.222647 -0.123094 0.0668205 0.222064 -0.11842 0.0687664 0.221706 -0.11928 0.0695359 0.220868 -0.115374 0.0708794 0.218833 -0.113653 0.0729301 0.218443 -0.113137 0.0732087 0.216383 -0.111056 0.0742812 0.188643 -0.109669 0.074935 0.200735 -0.109692 0.074935 0.212827 -0.109703 0.074935 -0.19099 -0.108333 0.074935 -0.19099 -0.109669 0.074935 -0.189343 -0.108596 0.0747986 -0.189314 -0.109962 0.0747936 -0.187432 -0.111007 0.0742806 -0.185956 -0.112383 0.0735757 -0.185941 -0.110884 0.0735671 -0.185371 -0.113076 0.0732072 -0.185085 -0.111866 0.0730057 -0.184984 -0.113585 0.0729305 -0.182949 -0.11529 0.07088 -0.182328 -0.118577 0.0699329 -0.181171 -0.12295 0.0668323 -0.182117 -0.119158 0.069548 -0.225173 -0.123212 0.064935 -0.224678 -0.119393 0.0680418 -0.223893 -0.116927 0.069831 -0.222422 -0.115613 0.0718237 -0.222129 -0.113416 0.0721198 -0.220309 -0.112557 0.0735156 -0.215491 -0.108376 0.07493 -0.2202 -0.110916 0.0735799 -0.225173 -0.129456 0.0587897 -0.225173 -0.125466 0.064935 -0.225173 -0.134788 0.0521073 -0.225173 -0.145523 0.0292308 -0.224909 -0.147724 0.0184535 -0.215173 -0.150261 0.010735 -0.215173 -0.148667 0.010735 -0.218044 -0.150227 0.011156 -0.218469 -0.148621 0.0112938 -0.221394 -0.148457 0.0129053 -0.221041 -0.150079 0.0126375 -0.224911 -0.149276 0.0184598 -0.224413 -0.149522 0.01691 -0.224413 -0.147954 0.0169103 -0.223621 -0.148162 0.0153839 -0.223379 -0.149791 0.0150201 -0.203081 -0.150204 0.010735 -0.19099 -0.148491 0.010735 -0.188867 -0.148442 0.0109629 -0.181559 -0.147567 0.017408 -0.182907 -0.149502 0.0148469 -0.181558 -0.149113 0.0174111 -0.18141 -0.14904 0.0178654 -0.18534 -0.149824 0.0124841 -0.183211 -0.149558 0.0144512 -0.187162 -0.148367 0.0114965 -0.188407 -0.150014 0.0110742 -0.187162 -0.149955 0.0114965 -0.185751 -0.148275 0.0122168 -0.185743 -0.149858 0.0122219 -0.18099 -0.14499 0.0301068 -0.18099 -0.142148 0.0383298 -0.18099 -0.134505 0.0522246 -0.18099 -0.136515 0.0519363 -0.18099 -0.129195 0.0588968 -0.18099 -0.123083 0.064935 0.212827 -0.108366 -0.076465 0.200735 -0.109692 -0.076465 0.188643 -0.108333 -0.076465 0.186997 -0.108596 -0.0763285 0.186967 -0.109962 -0.0763235 0.183609 -0.112383 -0.0751056 0.183024 -0.113076 -0.0747371 0.182637 -0.113585 -0.0744605 0.179982 -0.116688 -0.0714636 0.222827 -0.123212 -0.066465 0.222332 -0.119393 -0.0695717 0.221609 -0.119007 -0.0712468 0.221546 -0.116927 -0.0713609 0.219782 -0.113416 -0.0736498 0.218672 -0.111852 -0.0745789 0.216235 -0.110944 -0.0758664 0.216955 -0.110072 -0.0755732 0.214736 -0.108727 -0.076281 0.214067 -0.109867 -0.0763877 0.222827 -0.125466 -0.066465 0.222827 -0.129456 -0.0603196 0.222827 -0.130875 -0.0609828 0.222827 -0.136192 -0.0542485 0.222827 -0.140723 -0.0468851 0.222827 -0.145523 -0.0307608 0.217827 -0.150138 -0.013605 0.216123 -0.148621 -0.0128237 0.221275 -0.148162 -0.0169138 0.218695 -0.150079 -0.0141674 0.222563 -0.147724 -0.0199835 0.221488 -0.149693 -0.0172658 0.221278 -0.149741 -0.0169198 0.188643 -0.148491 -0.012265 0.212827 -0.148667 -0.012265 0.212827 -0.150261 -0.012265 0.178643 -0.147031 -0.022265 0.18056 -0.149502 -0.0163769 0.179213 -0.147567 -0.0189379 0.179064 -0.14904 -0.0193953 0.182993 -0.149824 -0.0140141 0.186061 -0.150014 -0.0126042 0.184816 -0.149955 -0.0130264 0.183397 -0.149858 -0.0137519 0.178643 -0.14499 -0.0316367 0.178643 -0.138341 -0.0476801 0.178643 -0.1441 -0.0389926 0.178643 -0.140452 -0.0469276 0.178643 -0.129195 -0.0604267 0.178643 -0.136515 -0.0534662 0.178643 -0.13132 -0.0602702 -0.241773 -0.112337 0.0549995 -0.242273 -0.120241 0.0482731 -0.242273 -0.122053 0.0464115 -0.242273 -0.12999 0.0361574 -0.241773 -0.12999 0.0361574 -0.242273 -0.131338 0.0339376 -0.241773 -0.131338 0.0339376 -0.241773 -0.135869 0.0245991 -0.242273 -0.139482 0.0121451 -0.242273 -0.1407 -0.000764971 -0.242273 -0.139482 -0.013675 -0.241773 -0.139482 -0.013675 -0.242273 -0.138319 -0.0187365 -0.241773 -0.138319 -0.0187365 -0.242273 -0.135869 -0.0261291 -0.241773 -0.135869 -0.0261291 -0.242273 -0.131338 -0.0354675 -0.241773 -0.131338 -0.0354675 -0.241773 -0.12999 -0.0376873 -0.241773 -0.122053 -0.0479415 -0.242273 -0.120241 -0.049803 -0.242273 -0.112337 -0.0565294 -0.241773 -0.105794 -0.0607534 -0.242273 -0.101185 -0.0631478 -0.242273 -0.0889926 -0.0675629 -0.241773 -0.101185 -0.0631478 0.239427 -0.101185 0.0616179 0.239927 -0.101185 0.0616179 0.239927 -0.120241 0.0482731 0.239427 -0.122053 0.0464115 0.239927 -0.122053 0.0464115 0.239427 -0.12999 0.0361574 0.239927 -0.12999 0.0361574 0.239427 -0.131338 0.0339376 0.239927 -0.131338 0.0339376 0.239927 -0.135869 0.0245991 0.239927 -0.139482 0.0121451 0.239427 -0.139482 0.0121451 0.239927 -0.1407 -0.000764971 0.239427 -0.1407 -0.000764971 0.239927 -0.139482 -0.013675 0.239427 -0.138319 -0.0187365 0.239927 -0.131338 -0.0354675 0.239927 -0.122053 -0.0479415 0.239927 -0.120241 -0.049803 0.239927 -0.105794 -0.0607534 0.239427 -0.101185 -0.0631478 -0.172962 -0.0767247 -0.0852371 -0.172518 -0.0767 -0.0857378 -0.172962 -0.0767247 -0.0857373 -0.174252 -0.0770952 -0.0857292 -0.179132 -0.08 -0.0850729 -0.17869 -0.0799755 -0.0855764 -0.177399 -0.079605 -0.085107 -0.176304 -0.0788285 -0.0851644 -0.176304 -0.0788285 -0.0856651 0.175255 -0.0796955 -0.0850995 0.175464 -0.0797753 -0.0855939 0.174291 -0.0791266 -0.0851439 0.171901 -0.0767716 0.0842136 0.170603 -0.0759045 0.0837263 0.169515 -0.0756246 0.0842293 0.170805 -0.075995 0.0842253 0.175053 -0.079605 0.0835771 0.175053 -0.079605 0.0840781 0.173957 -0.0788285 0.0836345 -0.174247 -0.0767716 0.0842136 -0.173917 -0.0764763 0.0837185 -0.172742 -0.0758255 0.0837272 -0.176304 -0.0788285 0.0836345 -0.17781 -0.0797753 0.0835628 -0.177601 -0.0796955 0.0835695 -0.241729 -0.0800332 -0.0782888 -0.242232 -0.0800332 -0.0782881 -0.241773 -0.080134 -0.077392 -0.241773 -0.0811387 -0.0740778 -0.242273 -0.0848084 -0.0695737 -0.241773 -0.0843387 -0.069944 -0.241773 -0.0848084 0.0680437 -0.242273 -0.0889926 0.066033 -0.241595 -0.08 0.07765 -0.241773 -0.080134 0.0758621 -0.242273 -0.080134 0.0758621 -0.242273 -0.0811387 0.0725479 0.239927 -0.0811387 -0.0740778 0.239886 -0.0800332 -0.0782881 0.239249 -0.08 -0.07918 0.239927 -0.080134 -0.077392 0.239427 -0.080134 0.0758621 0.239427 -0.0811387 0.0725479 0.239427 -0.0843387 0.068414 0.239927 -0.0848084 0.0680437 -0.174252 -0.0770952 -0.0852289 -0.172946 -0.0768532 -0.0847451 -0.172518 -0.0768295 -0.0847455 -0.172518 -0.0767 -0.0852376 -0.172905 -0.0772057 -0.0843804 -0.17419 -0.0772088 -0.0847372 -0.174049 -0.0770045 -0.085231 -0.17464 -0.0785394 -0.0842091 -0.174988 -0.078197 -0.0843521 -0.173819 -0.077965 -0.0842294 -0.174032 -0.0775261 -0.0843726 -0.175246 -0.0779534 -0.0847166 -0.175347 -0.0778716 -0.0852083 -0.175723 -0.0784298 -0.0846976 -0.176201 -0.0789061 -0.0846755 -0.175465 -0.0786709 -0.0843334 -0.175943 -0.0791446 -0.0843116 -0.175118 -0.0790113 -0.084189 0.0237859 -0.0768295 -0.0847455 -0.172518 -0.0771843 -0.0843809 0.170172 -0.0771843 -0.0843809 0.0237859 -0.0771843 -0.0843808 0.0237859 -0.0776726 -0.084238 -0.17869 -0.0799755 -0.0850751 -0.178633 -0.0804312 -0.0842339 -0.179132 -0.0804588 -0.084232 -0.177333 -0.0797111 -0.0846244 -0.178673 -0.0800967 -0.0845959 -0.177175 -0.0800148 -0.0842617 0.172293 -0.0785394 -0.0842091 0.17258 -0.0776698 -0.0847251 0.172641 -0.078197 -0.0843521 0.172353 -0.0779414 -0.0843605 0.171496 -0.0769253 -0.0852328 0.17267 -0.0775758 -0.0852167 0.171165 -0.0778394 -0.0842333 0.171328 -0.0773792 -0.0843763 0.170172 -0.0768295 -0.0847455 0.170172 -0.0767 -0.0852376 0.171448 -0.0770458 -0.0847409 -0.206703 -0.0801222 -0.084594 -0.234273 -0.08 -0.085073 -0.206703 -0.0804588 -0.0842321 -0.234273 -0.0801222 -0.084594 -0.234273 -0.0804589 -0.0842321 -0.179132 -0.0801222 -0.0845939 -0.206703 -0.0809277 -0.0840756 0.173001 -0.0778716 -0.0852083 0.173377 -0.0784298 -0.0846976 0.172899 -0.0779534 -0.0847166 0.173119 -0.0786709 -0.0843334 0.172772 -0.0790113 -0.084189 0.173854 -0.0789061 -0.0846755 0.173596 -0.0791446 -0.0843116 -0.234273 -0.0809277 -0.0840756 -0.239901 -0.0804769 -0.081102 -0.240755 -0.0804902 -0.0789943 -0.241112 -0.0801312 -0.0790731 -0.239902 -0.0809619 -0.0808139 -0.239776 -0.0809596 -0.081024 -0.238325 -0.0809422 -0.082653 -0.240209 -0.0801274 -0.0812953 -0.238421 -0.080467 -0.0827719 -0.236592 -0.0801228 -0.0841979 -0.236472 -0.0804609 -0.0838561 -0.240623 -0.08 -0.0815546 -0.238949 -0.08 -0.0834327 -0.238647 -0.0801245 -0.0830553 -0.236751 -0.08 -0.0846509 0.174198 -0.0792146 -0.0846572 0.173957 -0.0788285 -0.0851644 0.17325 -0.0794832 -0.0841658 0.175413 -0.0798881 -0.0846116 0.175293 -0.080206 -0.0842493 0.175133 -0.0806505 -0.0840951 0.173971 -0.0794782 -0.0842938 0.175464 -0.0797753 -0.0850927 0.176786 -0.0801222 -0.0845939 0.176786 -0.0804588 -0.084232 0.176786 -0.0809277 -0.0840755 -0.240619 -0.080983 -0.0789641 -0.241273 -0.0802665 -0.077412 -0.240874 -0.0805291 -0.0782334 -0.241237 -0.080168 -0.0782457 0.204356 -0.0801222 -0.084594 0.176786 -0.08 -0.0850729 0.204356 -0.0809277 -0.0840756 0.204356 -0.08 -0.085073 0.231927 -0.0801222 -0.084594 0.231927 -0.0804589 -0.0842321 0.204356 -0.0804588 -0.0842321 -0.240907 -0.0891179 -0.068047 -0.240907 -0.0846579 -0.0703288 -0.241273 -0.0844242 -0.0700471 -0.240773 -0.0849771 -0.0707136 -0.240907 -0.0815913 -0.0742904 -0.240907 -0.0806284 -0.0774665 -0.241273 -0.08126 -0.0741348 0.238564 -0.0802869 -0.0790286 0.237882 -0.0801274 -0.0812644 0.234088 -0.0809314 -0.0837046 0.236093 -0.0804671 -0.082757 0.238273 -0.080983 -0.0789641 0.237573 -0.0804771 -0.0810727 0.23414 -0.0804609 -0.0838511 0.238409 -0.0804902 -0.0789943 0.23442 -0.08 -0.0846452 0.23426 -0.0801228 -0.0841926 0.23632 -0.0801246 -0.0830396 0.238297 -0.08 -0.0815216 -0.241273 -0.101243 -0.063269 -0.241773 -0.0889926 -0.0675629 -0.241773 -0.120241 -0.049803 -0.241273 -0.0890262 -0.0676926 -0.241773 -0.112337 -0.0565294 -0.241773 -0.1407 -0.000764971 -0.241773 -0.139482 0.0121451 -0.241273 -0.139613 0.0121701 -0.241773 -0.138319 0.0172066 -0.241273 -0.135994 0.0246484 -0.241773 -0.122053 0.0464115 -0.241273 -0.130103 0.0362291 -0.241273 -0.12215 0.0465031 -0.241773 -0.120241 0.0482731 -0.241773 -0.105794 0.0592235 -0.241773 -0.101185 0.0616179 -0.241273 -0.101243 0.061739 -0.241391 -0.0890117 0.0661067 -0.240907 -0.101399 -0.0635999 -0.241273 -0.112415 -0.0566377 -0.240907 -0.112631 -0.0569335 -0.241273 -0.12215 -0.0480331 -0.241273 -0.130103 -0.037759 -0.240907 -0.130413 -0.0379549 -0.240907 -0.136334 -0.0263129 -0.241273 -0.135994 -0.0261783 -0.241273 -0.139613 -0.0137001 -0.241273 -0.140834 -0.000764971 -0.240907 -0.130413 0.0364249 -0.240907 -0.122417 0.0467534 -0.241273 -0.112415 0.0551078 -0.240773 -0.0892433 -0.068531 -0.240907 -0.122417 -0.0482833 -0.240907 -0.139973 -0.0137686 -0.240773 -0.140464 -0.0138621 -0.240773 -0.1417 -0.000764971 -0.240907 -0.1412 -0.000764971 -0.240907 -0.139973 0.0122386 -0.240773 -0.140464 0.0123322 -0.240907 -0.136334 0.0247829 -0.240773 -0.136799 0.0249667 -0.240773 -0.130835 0.0366925 -0.240907 -0.112631 0.0554036 -0.240907 -0.101399 0.0620699 -0.240773 -0.101613 0.062522 -0.240907 -0.0891179 0.066517 0.238686 -0.080325 -0.0782353 0.239006 -0.0801105 -0.0782539 0.23872 -0.0804236 -0.0774357 0.239383 -0.0800332 -0.0782888 0.238389 -0.0810218 -0.0782551 0.238469 -0.0806446 -0.0782357 0.238766 -0.0801312 -0.0790731 -0.240773 -0.0825588 0.0720053 -0.240849 -0.0807444 0.0759541 -0.241066 -0.0819519 0.0716424 -0.241391 -0.0802093 0.0758734 -0.241773 -0.0817005 0.0714921 -0.240849 -0.0822304 0.0718089 -0.241066 -0.084984 0.0682782 -0.241391 -0.0817658 0.0715312 -0.241773 -0.0889926 0.066033 -0.241391 -0.0848541 0.0681047 -0.241273 -0.0890262 0.0661627 -0.241066 -0.089066 0.0663165 -0.240849 -0.0851784 0.0685379 -0.240773 -0.0854077 0.0688443 0.239044 -0.0890117 -0.0676366 0.239044 -0.0848541 -0.0696346 0.238927 -0.0890262 -0.0676926 0.238503 -0.0891473 -0.0681605 0.239427 -0.0848084 -0.0695737 0.239427 -0.0817005 -0.0730221 0.239044 -0.0817658 -0.0730611 0.23872 -0.084984 -0.0698081 0.23872 -0.0819519 -0.0731724 0.238503 -0.0851784 -0.0700678 0.238427 -0.0854077 -0.0703742 0.239427 -0.080134 -0.077392 0.239044 -0.0802093 -0.0774034 0.238503 -0.0807444 -0.077484 0.238503 -0.0822304 -0.0733388 -0.241729 -0.0800332 0.0767588 -0.241066 -0.0804236 0.0759057 -0.241032 -0.080325 0.0767054 -0.241352 -0.0801105 0.076724 -0.240735 -0.0810218 0.0767252 -0.240698 -0.0806056 0.0774517 -0.240815 -0.0806446 0.0767058 -0.240911 -0.0802869 0.0774987 0.239427 -0.112337 0.0549995 0.238427 -0.0892433 -0.068531 0.238427 -0.112925 -0.0573376 0.238561 -0.101399 -0.0635999 0.238427 -0.101613 -0.0640519 0.238561 -0.136334 0.0247829 0.238561 -0.139973 0.0122386 0.238427 -0.140464 0.0123322 0.238427 -0.1417 -0.000764971 0.238427 -0.140464 -0.0138621 0.238561 -0.139973 -0.0137686 0.238427 -0.130835 -0.0382224 0.238561 -0.122417 -0.0482833 0.238927 -0.140834 -0.000764971 0.238561 -0.1412 -0.000764971 0.238561 -0.130413 0.0364249 0.238927 -0.130103 0.0362291 0.239427 -0.0889926 -0.0675629 0.238927 -0.101243 -0.063269 0.23872 -0.089066 -0.0678465 0.238561 -0.0891179 -0.068047 0.238561 -0.112631 -0.0569335 0.238927 -0.112415 -0.0566377 0.239427 -0.105794 -0.0607534 0.239427 -0.131338 -0.0354675 0.239427 -0.12999 -0.0376873 0.239427 -0.122053 -0.0479415 0.238927 -0.12215 -0.0480331 0.239427 -0.120241 -0.049803 0.239427 -0.112337 -0.0565294 0.238561 -0.130413 -0.0379549 0.238561 -0.136334 -0.0263129 0.238927 -0.135994 -0.0261783 0.238927 -0.130103 -0.037759 0.239427 -0.135869 -0.0261291 0.239427 -0.139482 -0.013675 0.238927 -0.139613 -0.0137001 0.238927 -0.139613 0.0121701 0.239427 -0.138319 0.0172066 0.239427 -0.120241 0.0482731 0.238927 -0.135994 0.0246484 0.239427 -0.135869 0.0245991 0.238561 -0.122417 0.0467534 0.238427 -0.112925 0.0558077 0.238927 -0.12215 0.0465031 0.239427 -0.105794 0.0592235 0.238561 -0.101399 0.0620699 0.238927 -0.112415 0.0551078 0.238561 -0.112631 0.0554036 0.238427 -0.0892433 0.0670011 0.238561 -0.0891179 0.066517 0.238927 -0.101243 0.061739 0.238927 -0.0890262 0.0661627 -0.240623 -0.08 0.0800246 -0.241226 -0.0800745 0.0775683 -0.239776 -0.0809596 0.079494 -0.239901 -0.0804769 0.0795721 -0.240755 -0.0804902 0.0774643 -0.241112 -0.0801312 0.0775431 -0.238949 -0.08 0.0819028 -0.240209 -0.0801274 0.0797653 -0.237523 -0.0809366 0.0816717 -0.238421 -0.080467 0.0812419 -0.238325 -0.0809422 0.081123 -0.234273 -0.08 0.0835431 -0.236751 -0.08 0.0831209 -0.238647 -0.0801245 0.0815254 -0.236592 -0.0801228 0.082668 -0.236472 -0.0804609 0.0823262 -0.23642 -0.0809314 0.0821796 0.238927 -0.08126 0.0726048 0.238427 -0.0811228 0.0760111 0.238561 -0.0815913 0.0727605 0.238427 -0.0820438 0.0729731 0.238927 -0.0844242 0.0685171 0.238561 -0.0846579 0.0687988 0.239427 -0.0889926 0.066033 -0.206703 -0.0804588 0.0827021 -0.234273 -0.0804589 0.0827022 -0.234273 -0.0801222 0.0830641 -0.206703 -0.0801222 0.0830641 0.238273 -0.080983 0.0774342 0.239383 -0.0800332 0.0767588 0.238389 -0.0810218 0.0767252 0.238561 -0.0806284 0.0759366 0.238527 -0.0805291 0.0767035 0.238927 -0.0802665 0.0758821 0.23889 -0.080168 0.0767158 -0.176637 -0.0791266 0.083614 -0.176545 -0.0792146 0.0831273 -0.176201 -0.0789061 0.0831455 -0.175597 -0.0794832 0.0826358 -0.177759 -0.0798881 0.0830817 -0.176318 -0.0794782 0.0827638 -0.176013 -0.0798507 0.0826156 -0.179132 -0.0801222 0.083064 -0.179132 -0.0804588 0.082702 -0.177639 -0.080206 0.0827193 0.231927 -0.0801222 0.0830641 0.23442 -0.08 0.0831153 0.234088 -0.0809314 0.0821747 0.231927 -0.0809277 0.0825457 0.231927 -0.0804589 0.0827022 0.23414 -0.0804609 0.0823212 0.237573 -0.0804771 0.0795427 0.238297 -0.08 0.0799917 0.237882 -0.0801274 0.0797344 0.23426 -0.0801228 0.0826627 0.23632 -0.0801246 0.0815097 0.236093 -0.0804671 0.081227 0.238766 -0.0801312 0.0775431 0.238409 -0.0804902 0.0774643 0.237556 -0.0809619 0.079284 -0.174247 -0.0767716 0.0837134 -0.174148 -0.0768583 0.0832184 -0.174917 -0.0781263 0.0828246 -0.17389 -0.0771077 0.0828533 -0.175275 -0.0778002 0.0836812 -0.175174 -0.0778823 0.0831892 -0.175943 -0.0791446 0.0827816 -0.174568 -0.0784689 0.0826819 0.176786 -0.0804588 0.082702 0.176786 -0.0801222 0.083064 0.204356 -0.0809277 0.0825457 0.204356 -0.0804588 0.0827021 0.204356 -0.0801222 0.0830641 -0.172411 -0.0767545 0.0827273 -0.172576 -0.0762884 0.0828658 -0.173602 -0.0768522 0.0828581 -0.172697 -0.0759489 0.0832312 -0.17383 -0.0765747 0.0832233 -0.171418 -0.0765877 0.0827296 -0.171418 -0.0756 0.0837295 0.176786 -0.08 0.0835429 0.176786 -0.0809277 0.0825455 0.176344 -0.0799755 0.0835451 0.176326 -0.0800967 0.0830659 0.174986 -0.0797111 0.0830944 0.174829 -0.0800148 0.0827318 0.176286 -0.0804312 0.082704 0.176233 -0.0808974 0.0825477 0.173596 -0.0791446 0.0827816 0.17325 -0.0794832 0.0826358 0.169072 -0.075732 0.0832331 0.169072 -0.076093 0.0828676 -0.171418 -0.075732 0.0832331 -0.0250792 -0.075732 0.0832331 -0.171418 -0.076093 0.0828676 -0.0250792 -0.0760929 0.0828676 0.173854 -0.0789061 0.0831455 0.172929 -0.0778002 0.0836812 0.171544 -0.0771077 0.0828533 0.172828 -0.0778823 0.0831892 0.17257 -0.0781263 0.0828246 0.170805 -0.075995 0.0837253 0.169404 -0.0766059 0.0827293 0.169515 -0.0756246 0.0837293 0.170587 -0.0764353 0.0828642 0.169459 -0.0761143 0.0828674 0.169499 -0.0757556 0.0832329 0.170745 -0.076112 0.0832295 0.170372 -0.0768799 0.0827254 0.171802 -0.0768583 0.0832184 -0.172518 -0.0767788 -0.0861268 -0.172518 -0.0770026 -0.0864545 -0.172894 -0.0773573 -0.0866688 -0.172851 -0.0777459 -0.0867369 -0.172518 -0.0773363 -0.0866693 -0.17413 -0.0773724 -0.0864461 -0.172954 -0.0768031 -0.0861263 -0.17293 -0.0770256 -0.086454 -0.173819 -0.0780276 -0.0867287 -0.175299 -0.0779349 -0.0860976 -0.174223 -0.0771685 -0.0861183 -0.175147 -0.0780997 -0.0864252 -0.174915 -0.0783399 -0.08664 -0.173987 -0.0776746 -0.0866608 0.170172 -0.0767788 -0.0861268 0.170172 -0.0773363 -0.0866693 0.170172 -0.0777272 -0.0867374 -0.0251327 -0.0767788 -0.0861267 -0.0251327 -0.0770026 -0.0864544 -0.0251327 -0.0773363 -0.0866693 -0.172518 -0.0777272 -0.0867374 -0.175347 -0.0778716 -0.0857087 -0.175778 -0.078415 -0.0860784 -0.175627 -0.0785817 -0.0864065 -0.175118 -0.0791027 -0.0866874 -0.17464 -0.0786178 -0.0867079 -0.176106 -0.0790636 -0.0863846 -0.175873 -0.0793074 -0.0865985 -0.175394 -0.0788237 -0.0866208 0.172627 -0.0776428 -0.0861061 0.173001 -0.0778716 -0.0857087 0.172952 -0.0779349 -0.0860976 0.172493 -0.0778224 -0.0864339 0.172289 -0.0780863 -0.0866486 0.172569 -0.0783399 -0.08664 0.172293 -0.0786178 -0.0867079 0.171496 -0.0769253 -0.085733 0.17267 -0.0775758 -0.0857171 0.171473 -0.077001 -0.0861221 0.171165 -0.0778985 -0.0867326 0.172045 -0.0783929 -0.0867164 0.170172 -0.0767 -0.0857378 0.170172 -0.0770026 -0.0864545 0.171402 -0.0772134 -0.0864499 0.171293 -0.0775291 -0.0866646 -0.178661 -0.0802927 -0.0863081 -0.179132 -0.0803188 -0.0863063 -0.179132 -0.0800832 -0.0859734 -0.17858 -0.0810409 -0.0865738 -0.178624 -0.0806394 -0.0865193 -0.177374 -0.0796837 -0.0860041 -0.178684 -0.0800584 -0.0859754 -0.175597 -0.0795876 -0.0866637 -0.177138 -0.08021 -0.0865476 -0.177281 -0.0798969 -0.0863354 -0.176258 -0.078895 -0.086056 -0.177399 -0.079605 -0.0856081 0.17376 -0.0790636 -0.0863846 0.172772 -0.0791027 -0.0866874 0.17325 -0.0795876 -0.0866637 0.173432 -0.078415 -0.0860784 0.1728 -0.0780997 -0.0864252 0.17328 -0.0785817 -0.0864065 0.173048 -0.0788237 -0.0866208 -0.206703 -0.0806677 -0.0865174 -0.179132 -0.0806677 -0.0865173 -0.234273 -0.08 -0.0855743 -0.234273 -0.0800832 -0.0859735 -0.206703 -0.0800832 -0.0859735 -0.206703 -0.0803188 -0.0863063 0.173912 -0.0796542 -0.0865803 0.173527 -0.0793074 -0.0865985 0.174118 -0.079384 -0.086367 0.174291 -0.0791265 -0.0856447 0.173911 -0.078895 -0.086056 0.173957 -0.0788285 -0.0856651 0.175133 -0.0807871 -0.0865915 0.175265 -0.0804073 -0.0865349 0.174252 -0.0791981 -0.0860374 0.176786 -0.0806677 -0.0865173 0.175375 -0.0800789 -0.0863232 0.175445 -0.079856 -0.0859913 0.176786 -0.08 -0.0855742 -0.240005 -0.0810568 -0.0845058 -0.23729 -0.0803173 -0.0857661 -0.234273 -0.0803188 -0.0863064 -0.234273 -0.0806677 -0.0865175 -0.234273 -0.0810719 -0.0865717 -0.237175 -0.0800828 -0.0854542 -0.239832 -0.0803133 -0.0842967 -0.237363 -0.0806649 -0.0859644 -0.239968 -0.0806571 -0.0844603 -0.238773 -0.0810632 -0.0853633 -0.239368 -0.08 -0.0837369 -0.241462 -0.08008 -0.0818934 -0.239621 -0.0800817 -0.0840417 -0.241744 -0.0803069 -0.0820628 -0.242107 -0.08 -0.07918 -0.241126 -0.08 -0.0816917 -0.242485 -0.0800777 -0.0792581 -0.242805 -0.0802986 -0.0793242 -0.241927 -0.0806446 -0.082173 -0.243016 -0.0806284 -0.0793678 0.231927 -0.08 -0.0855743 0.204356 -0.0803188 -0.0863063 0.231927 -0.0803188 -0.0863064 0.204356 -0.0810719 -0.0865717 0.231927 -0.0810719 -0.0865717 0.176786 -0.0800832 -0.0859734 0.204356 -0.08 -0.0855743 0.204356 -0.0800832 -0.0859735 0.176786 -0.0803188 -0.0863063 0.204356 -0.0806677 -0.0865174 0.176786 -0.0810719 -0.0865716 -0.242616 -0.0801078 -0.0783325 -0.242273 -0.080134 -0.077392 -0.243197 -0.0807444 -0.077484 -0.242941 -0.0803255 -0.0783815 -0.243156 -0.0806527 -0.0784276 -0.243227 -0.0810386 -0.0784635 0.239721 -0.081038 -0.0820618 0.239547 -0.0810403 -0.0823519 0.239032 -0.0800801 -0.0820294 0.239311 -0.0803073 -0.0822043 0.239492 -0.0806454 -0.0823178 0.2387 -0.08 -0.0818213 0.23457 -0.08 -0.085124 0.237162 -0.0800818 -0.0841339 0.237368 -0.0803136 -0.0843926 0.237501 -0.0806576 -0.0845584 0.236427 -0.0810632 -0.0853633 0.231927 -0.0800832 -0.0859735 0.234701 -0.0800828 -0.0854999 0.234812 -0.0803175 -0.0858136 0.234882 -0.0806651 -0.0860131 0.231927 -0.0806677 -0.0865175 -0.242656 -0.0848541 -0.0696346 -0.242656 -0.0890117 -0.0676366 -0.243139 -0.0891179 -0.068047 -0.243197 -0.0851784 -0.0700678 -0.242656 -0.0817658 -0.0730611 -0.24298 -0.084984 -0.0698081 -0.242273 -0.0817005 -0.0730221 -0.242656 -0.0802093 -0.0774034 -0.24298 -0.0819519 -0.0731724 -0.243197 -0.0822304 -0.0733388 -0.24298 -0.0804236 -0.0774357 -0.243273 -0.0825588 -0.0735352 -0.243273 -0.0811228 -0.077541 0.240809 -0.0806527 -0.0784276 0.240309 -0.0802093 -0.0774034 0.240595 -0.0803255 -0.0783815 0.240793 -0.0806284 -0.0774665 0.240139 -0.0800777 -0.0792581 0.24027 -0.0801078 -0.0783325 0.240458 -0.0802986 -0.0793242 0.240669 -0.0806284 -0.0793678 -0.242273 -0.112337 0.0549995 -0.243197 -0.0891473 -0.0681605 -0.243273 -0.122782 -0.0486252 -0.243139 -0.112631 -0.0569335 -0.243273 -0.112925 -0.0573376 -0.243273 -0.140464 0.0123322 -0.243273 -0.1417 -0.000764971 -0.243139 -0.139973 -0.0137686 -0.243273 -0.136799 -0.0264967 -0.243273 -0.130835 -0.0382224 -0.243139 -0.122417 -0.0482833 -0.242773 -0.12215 -0.0480331 -0.243139 -0.130413 -0.0379549 -0.243139 -0.136334 0.0247829 -0.243139 -0.139973 0.0122386 -0.243139 -0.1412 -0.000764971 -0.243139 -0.136334 -0.0263129 -0.242773 -0.12215 0.0465031 -0.243139 -0.101399 -0.0635999 -0.242773 -0.0890262 -0.0676926 -0.24298 -0.089066 -0.0678465 -0.242773 -0.112415 -0.0566377 -0.242773 -0.101243 -0.063269 -0.242273 -0.12999 -0.0376873 -0.242273 -0.122053 -0.0479415 -0.242273 -0.105794 -0.0607534 -0.242773 -0.130103 -0.037759 -0.242773 -0.135994 -0.0261783 -0.242773 -0.139613 -0.0137001 -0.242773 -0.140834 -0.000764971 -0.242773 -0.139613 0.0121701 -0.243139 -0.130413 0.0364249 -0.242773 -0.130103 0.0362291 -0.242273 -0.135869 0.0245991 -0.242773 -0.135994 0.0246484 -0.242273 -0.138319 0.0172066 -0.243273 -0.112925 0.0558077 -0.243139 -0.122417 0.0467534 -0.243139 -0.112631 0.0554036 -0.242273 -0.105794 0.0592235 -0.242773 -0.112415 0.0551078 -0.243139 -0.101399 0.0620699 -0.243139 -0.0891179 0.066517 -0.242773 -0.101243 0.061739 -0.242273 -0.101185 0.0616179 0.240793 -0.0891179 -0.068047 0.240927 -0.0849771 -0.0707136 0.240793 -0.0846579 -0.0703288 0.240927 -0.0811228 -0.077541 0.240851 -0.0807444 -0.077484 0.240927 -0.0820438 -0.074503 0.240427 -0.0844242 -0.0700471 0.240427 -0.0890262 -0.0676926 0.240793 -0.0815913 -0.0742904 0.240634 -0.0804236 -0.0774357 0.240427 -0.0802665 -0.077412 0.239927 -0.0843387 -0.069944 0.240427 -0.08126 -0.0741348 -0.242656 -0.0802093 0.0758734 -0.242773 -0.08126 0.0726048 -0.24298 -0.0804236 0.0759057 -0.243139 -0.0806284 0.0759366 -0.243197 -0.0807444 0.0759541 -0.243139 -0.0815913 0.0727605 -0.243273 -0.0820438 0.0729731 -0.242273 -0.0843387 0.068414 -0.242773 -0.0844242 0.0685171 -0.243139 -0.0846579 0.0687988 -0.242773 -0.0890262 0.0661627 0.240793 -0.0891179 0.066517 0.239927 -0.0889926 -0.0675629 0.239927 -0.101185 -0.0631478 0.239927 -0.112337 -0.0565294 0.240427 -0.12215 -0.0480331 0.239927 -0.12999 -0.0376873 0.240427 -0.135994 -0.0261783 0.239927 -0.135869 -0.0261291 0.239927 -0.138319 -0.0187365 0.240427 -0.135994 0.0246484 0.240427 -0.140834 -0.000764971 0.239927 -0.138319 0.0172066 0.240427 -0.139613 0.0121701 0.239927 -0.105794 0.0592235 0.240427 -0.12215 0.0465031 0.239927 -0.112337 0.0549995 0.240793 -0.101399 -0.0635999 0.240427 -0.101243 -0.063269 0.240427 -0.112415 -0.0566377 0.240793 -0.122417 -0.0482833 0.240427 -0.130103 -0.037759 0.240793 -0.136334 -0.0263129 0.240427 -0.139613 -0.0137001 0.240793 -0.139973 -0.0137686 0.240793 -0.1412 -0.000764971 0.240427 -0.130103 0.0362291 0.240793 -0.122417 0.0467534 0.240427 -0.112415 0.0551078 0.240793 -0.112631 0.0554036 0.240427 -0.101243 0.061739 0.240634 -0.089066 0.0663165 0.240793 -0.112631 -0.0569335 0.240927 -0.112925 -0.0573376 0.240927 -0.122782 -0.0486252 0.240793 -0.130413 -0.0379549 0.240927 -0.130835 -0.0382224 0.240927 -0.140464 -0.0138621 0.240793 -0.139973 0.0122386 0.240793 -0.136334 0.0247829 0.240927 -0.140464 0.0123322 0.240927 -0.136799 0.0249667 0.240793 -0.130413 0.0364249 0.240927 -0.122782 0.0470953 0.240927 -0.112925 0.0558077 0.240793 -0.101399 0.0620699 -0.243227 -0.0810386 0.0769336 -0.243156 -0.0806527 0.0768976 -0.242773 -0.0802665 0.0758821 -0.242941 -0.0803255 0.0768516 -0.242232 -0.0800332 0.0767582 -0.242485 -0.0800777 0.0777282 -0.242805 -0.0802986 0.0777942 -0.242616 -0.0801078 0.0768026 -0.243016 -0.0806284 0.0778379 -0.243086 -0.081016 0.0778524 0.240927 -0.0811228 0.0760111 0.240851 -0.0807444 0.0759541 0.240634 -0.0804236 0.0759057 0.240309 -0.0802093 0.0758734 0.239927 -0.080134 0.0758621 0.239927 -0.0817005 0.0714921 0.240927 -0.0825588 0.0720053 0.240927 -0.0854077 0.0688443 0.240851 -0.0851784 0.0685379 0.240851 -0.0822304 0.0718089 0.240634 -0.0819519 0.0716424 0.240309 -0.0817658 0.0715312 0.240309 -0.0848541 0.0681047 0.239927 -0.0889926 0.066033 0.240309 -0.0890117 0.0661067 0.240427 -0.0890262 0.0661627 0.240634 -0.084984 0.0682782 -0.238773 -0.0810632 0.0838333 -0.237382 -0.0810679 0.0844866 -0.237363 -0.0806649 0.0844345 -0.234273 -0.0806677 0.0849875 -0.234273 -0.0803188 0.0847764 -0.234273 -0.0800832 0.0844436 -0.23729 -0.0803173 0.0842361 -0.239621 -0.0800817 0.0825118 -0.237175 -0.0800828 0.0839243 -0.239968 -0.0806571 0.0829304 -0.239832 -0.0803133 0.0827668 -0.241462 -0.08008 0.0803634 -0.241126 -0.08 0.0801617 -0.239368 -0.08 0.082207 -0.241927 -0.0806446 0.080643 -0.241744 -0.0803069 0.0805329 0.23976 -0.08 0.07765 0.24027 -0.0801078 0.0768026 0.240595 -0.0803255 0.0768516 0.240139 -0.0800777 0.0777282 0.239886 -0.0800332 0.0767582 0.240809 -0.0806527 0.0768976 0.24088 -0.0810386 0.0769336 -0.206703 -0.0806677 0.0849875 -0.179132 -0.0810719 0.0850416 -0.206703 -0.0800832 0.0844436 -0.206703 -0.0810719 0.0850418 -0.206703 -0.0803188 0.0847764 0.240739 -0.081016 0.0778524 0.240669 -0.0806284 0.0778379 0.239547 -0.0810403 0.0808219 0.239721 -0.081038 0.0805318 0.239492 -0.0806454 0.0807879 0.240458 -0.0802986 0.0777942 0.236914 -0.08 0.0822947 0.239032 -0.0800801 0.0804995 0.239311 -0.0803073 0.0806743 0.237162 -0.0800818 0.0826039 0.2349 -0.0810682 0.0845355 0.237501 -0.0806576 0.0830285 0.234882 -0.0806651 0.0844832 0.234701 -0.0800828 0.08397 0.234812 -0.0803175 0.0842837 0.237368 -0.0803136 0.0828626 0.231927 -0.0806677 0.0849875 -0.176013 -0.0799652 0.0851131 -0.176465 -0.079384 0.084837 -0.176598 -0.0791981 0.0845075 -0.176637 -0.0791265 0.0841148 -0.177721 -0.0800789 0.0847932 -0.176259 -0.0796542 0.0850504 -0.177791 -0.079856 0.0844613 -0.17781 -0.0797753 0.0840639 -0.179132 -0.0806677 0.0849874 -0.17748 -0.0807871 0.0850616 -0.177611 -0.0804073 0.0850049 -0.179132 -0.0803188 0.0847763 -0.179132 -0.0800832 0.0844435 -0.179132 -0.08 0.0840442 0.204356 -0.0810719 0.0850418 0.231927 -0.0810719 0.0850418 0.231927 -0.0803188 0.0847764 0.231927 -0.0800832 0.0844436 0.176786 -0.0810719 0.0850416 0.204356 -0.0806677 0.0849875 0.176786 -0.0803188 0.0847763 0.176786 -0.0800832 0.0844435 0.204356 -0.0803188 0.0847764 0.204356 -0.0800832 0.0844436 -0.175227 -0.0778633 0.0845703 -0.176304 -0.0788285 0.0841351 -0.176258 -0.078895 0.084526 -0.175075 -0.0780277 0.0848978 -0.174843 -0.0782677 0.0851126 -0.176106 -0.0790636 0.0848546 -0.174568 -0.0785454 0.0851808 -0.175873 -0.0793074 0.0850686 -0.174197 -0.0768313 0.0846001 -0.174044 -0.0769916 0.0849266 0.176786 -0.0806677 0.0849874 0.176314 -0.0802927 0.0847782 0.176344 -0.0799755 0.0840464 0.176786 -0.08 0.0840442 0.176233 -0.0810409 0.0850439 0.176277 -0.0806394 0.0849894 0.174935 -0.0798969 0.0848054 0.175027 -0.0796837 0.0844742 0.176338 -0.0800584 0.0844455 0.174619 -0.0805715 0.085076 0.173527 -0.0793074 0.0850686 0.174791 -0.08021 0.0850176 -0.173917 -0.0764763 0.0842186 -0.173534 -0.076975 0.085147 -0.173813 -0.0772277 0.0851421 -0.172742 -0.0758255 0.0842273 -0.173872 -0.0765402 0.084605 -0.172539 -0.0764184 0.085155 -0.173738 -0.0767155 0.0849314 -0.172411 -0.0767836 0.0852272 -0.171418 -0.0756773 0.084615 -0.172718 -0.0758992 0.0846131 -0.172647 -0.0761076 0.0849392 -0.171418 -0.0762258 0.0851569 0.172929 -0.0778002 0.0841815 0.172729 -0.0780277 0.0848978 0.171698 -0.0769916 0.0849266 0.171467 -0.0772277 0.0851421 0.172222 -0.0785454 0.0851808 0.173911 -0.078895 0.084526 0.172881 -0.0778633 0.0845703 0.17376 -0.0790636 0.0848546 0.172497 -0.0782677 0.0851126 0.17325 -0.0795876 0.0851338 -0.171418 -0.0756 0.0842295 0.0217332 -0.0756773 0.084615 -0.171418 -0.0758973 0.0849409 0.0217332 -0.0762259 0.0851569 0.0217332 -0.0756 0.0842295 0.169072 -0.0758973 0.0849409 0.0217332 -0.0758973 0.0849409 0.169072 -0.0762258 0.0851569 0.169072 -0.0766123 0.0852295 0.169072 -0.0756 0.0842295 0.169072 -0.0756773 0.084615 0.169447 -0.0762468 0.0851567 0.169507 -0.0757015 0.0846148 0.169483 -0.0759202 0.0849408 0.169404 -0.0766309 0.0852292 0.17185 -0.0768313 0.0846001 0.170774 -0.0760661 0.0846114 0.170681 -0.0762658 0.0849376 0.170539 -0.0765634 0.0851533 0.170372 -0.0769125 0.0852252 -0.12104 -0.13718 -0.0477226 -0.136742 -0.139721 -0.0485567 -0.136756 -0.139638 -0.047751 -0.139249 -0.139813 -0.0475561 -0.139382 -0.139904 -0.0483421 -0.142939 -0.140303 -0.0455157 -0.145359 -0.141628 -0.0444217 -0.145352 -0.141403 -0.0435635 -0.146732 -0.142443 -0.0414575 -0.147065 -0.142824 -0.0406104 -0.147481 -0.143271 -0.0409339 -0.147909 -0.144298 -0.0383605 -0.139953 -0.139914 -0.0474102 -0.140127 -0.140009 -0.0481832 -0.142661 -0.140534 -0.0464115 -0.143173 -0.140698 -0.046129 -0.145826 -0.141806 -0.0449584 -0.145692 -0.141813 -0.0440601 -0.146175 -0.142001 -0.0445703 -0.147685 -0.143121 -0.0421845 -0.147133 -0.142878 -0.0418301 -0.148048 -0.143536 -0.0412283 -0.140341 -0.13979 -0.0489202 -0.142987 -0.140658 -0.0471007 -0.143377 -0.140495 -0.0477471 -0.143527 -0.14083 -0.0467957 -0.146739 -0.141943 -0.0450268 -0.148698 -0.143585 -0.0414582 -0.148493 -0.144621 -0.0384872 -0.109763 -0.139314 -0.0473733 -0.109775 -0.13892 -0.0466758 -0.109747 -0.139171 -0.0489365 -0.109753 -0.139403 -0.0481695 -0.147474 -0.14381 -0.0381748 -0.14817 -0.145783 -0.0345778 -0.148186 -0.144483 -0.0384323 -0.147318 -0.146159 -0.0305225 -0.149062 -0.146792 -0.0320811 -0.0720145 -0.14265 -0.0400366 -0.0730486 -0.141893 -0.0395201 -0.0726092 -0.142366 -0.0397961 -0.0742884 -0.140742 -0.0423136 -0.0747049 -0.140493 -0.0428635 -0.0769197 -0.139888 -0.0455483 -0.0794742 -0.13934 -0.0466575 -0.0800611 -0.138883 -0.0461114 -0.0827672 -0.139113 -0.0471383 -0.0727835 -0.142118 -0.0404452 -0.0721979 -0.142387 -0.0407307 -0.0733825 -0.141382 -0.0432058 -0.0739088 -0.14117 -0.0427563 -0.074345 -0.140915 -0.0433395 -0.0763043 -0.140079 -0.0451507 -0.0759108 -0.140228 -0.0457806 -0.0765617 -0.140025 -0.0462094 -0.0799409 -0.139277 -0.046784 -0.0827621 -0.139204 -0.0479285 -0.0713379 -0.142712 -0.0402121 -0.0738423 -0.141112 -0.0438318 -0.0761444 -0.139878 -0.0468327 -0.0792676 -0.139445 -0.0474084 -0.0790256 -0.139245 -0.0481288 -0.0797626 -0.139379 -0.0475453 -0.0795538 -0.139172 -0.0482772 -0.0827587 -0.13898 -0.0486918 -0.148026 -0.146868 -0.0306603 -0.14799 -0.147496 -0.0285634 -0.147418 -0.14711 -0.0286345 -0.146765 -0.146686 -0.0278947 -0.145503 -0.14705 -0.0254889 -0.145852 -0.147678 -0.0253486 -0.145055 -0.147124 -0.0248991 -0.145383 -0.147766 -0.024733 -0.143268 -0.148002 -0.0227521 -0.14303 -0.147309 -0.0229984 -0.142436 -0.147335 -0.0226008 -0.140008 -0.148104 -0.0211483 -0.139507 -0.147361 -0.0213412 -0.139592 -0.148104 -0.0210316 -0.147172 -0.147258 -0.027863 -0.147734 -0.14766 -0.0277434 -0.146355 -0.148132 -0.0250738 -0.143635 -0.148514 -0.0223064 -0.142647 -0.148039 -0.0223384 -0.140186 -0.148656 -0.0205882 -0.139744 -0.148659 -0.0204627 -0.136746 -0.148044 -0.0206808 -0.148647 -0.147668 -0.0284246 -0.145863 -0.148234 -0.0244189 -0.144078 -0.148771 -0.021728 -0.143384 -0.148823 -0.02125 -0.14298 -0.148562 -0.0218641 -0.140412 -0.148931 -0.0198647 -0.0726595 -0.145248 -0.0301173 -0.0724679 -0.14425 -0.0340402 -0.0731083 -0.144718 -0.0300263 -0.0711065 -0.143484 -0.0380577 -0.0717946 -0.143372 -0.0380203 -0.0718619 -0.14459 -0.0341161 -0.0724003 -0.143043 -0.0379087 -0.0728496 -0.142537 -0.0377363 -0.136723 -0.148608 -0.0200836 -0.109777 -0.146522 -0.0211487 -0.0827554 -0.147381 -0.0203166 -0.109742 -0.147847 -0.0202282 -0.0827635 -0.146816 -0.020918 -0.0827732 -0.146055 -0.0212395 -0.109758 -0.147282 -0.020828 -0.0812765 -0.146024 -0.0213593 -0.0806816 -0.146007 -0.0214725 -0.0812019 -0.146782 -0.021043 -0.0777074 -0.145855 -0.0226737 -0.0753268 -0.146317 -0.0241563 -0.0732394 -0.145762 -0.0275067 -0.0810897 -0.147345 -0.0204508 -0.0805812 -0.146761 -0.0211608 -0.0779997 -0.146618 -0.0221128 -0.0774748 -0.146575 -0.0224116 -0.0771215 -0.147102 -0.0219233 -0.0748461 -0.146801 -0.0237945 -0.0750132 -0.146263 -0.0245067 -0.0735231 -0.145881 -0.0268285 -0.0726521 -0.146169 -0.0273715 -0.0720532 -0.145598 -0.0301571 -0.0804278 -0.147321 -0.0205777 -0.0802473 -0.147591 -0.0198218 -0.0776792 -0.147153 -0.0216021 -0.0773 -0.147408 -0.020938 -0.0745151 -0.146739 -0.0241695 -0.0739337 -0.146957 -0.0237188 -0.0729484 -0.146304 -0.0266489 -0.0719773 -0.146339 -0.0271593 -0.0713636 -0.145723 -0.0301408 -0.0771931 -0.140237 -0.0250762 -0.0761959 -0.138716 -0.0279596 -0.0795515 -0.141005 -0.0228463 -0.0827732 -0.141387 -0.0220589 -0.0827732 -0.141286 -0.0220301 -0.0794845 -0.14057 -0.0225738 -0.0827732 -0.14101 -0.0218832 -0.077077 -0.139786 -0.0248501 -0.0827732 -0.140857 -0.0217406 -0.0827732 -0.140737 -0.0215693 -0.0767601 -0.1395 -0.0245579 -0.076073 -0.138556 -0.0279045 -0.076327 -0.139454 -0.0242779 -0.0775099 -0.139956 -0.0228203 -0.0793015 -0.140327 -0.0221549 -0.0757366 -0.13572 -0.0353891 -0.0758298 -0.138369 -0.0278404 -0.0762809 -0.136292 -0.0355859 -0.0762809 -0.138896 -0.0280218 -0.0763298 -0.139188 -0.0281224 -0.0827732 -0.140615 -0.0211717 -0.0827732 -0.14063 -0.0212753 -0.136773 -0.14063 -0.0212753 -0.136773 -0.140737 -0.0215693 -0.136773 -0.140857 -0.0217406 -0.0827732 -0.141802 -0.0220662 -0.0827732 -0.13397 -0.0417428 -0.0827732 -0.134178 -0.0417245 -0.0827732 -0.133504 -0.0419697 -0.0790515 -0.13354 -0.0414559 -0.0827732 -0.133215 -0.0423988 -0.0792549 -0.133736 -0.041151 -0.077077 -0.135986 -0.0389588 -0.0795488 -0.134864 -0.0410012 -0.079527 -0.134461 -0.0409021 -0.0771507 -0.135235 -0.0386552 -0.0794231 -0.134062 -0.0409551 -0.0769706 -0.13486 -0.0386363 -0.0766793 -0.134575 -0.0387157 -0.0771883 -0.135633 -0.0387693 -0.0763243 -0.136683 -0.0357206 -0.076073 -0.135951 -0.0354687 -0.076327 -0.134427 -0.0388799 -0.0753298 -0.135638 -0.035361 -0.136773 -0.141387 -0.0220589 -0.136773 -0.141286 -0.0220301 -0.136773 -0.14101 -0.0218832 -0.143217 -0.139188 -0.0281224 -0.142353 -0.140237 -0.0250762 -0.142469 -0.139786 -0.0248501 -0.136773 -0.140615 -0.0211717 -0.143266 -0.138896 -0.0280218 -0.142786 -0.1395 -0.0245579 -0.143473 -0.138556 -0.0279045 -0.140495 -0.140341 -0.0217019 -0.142036 -0.139956 -0.0228203 -0.139995 -0.141005 -0.0228463 -0.140062 -0.14057 -0.0225738 -0.140245 -0.140327 -0.0221549 -0.0827732 -0.133429 -0.0420424 -0.0827732 -0.13377 -0.0418039 -0.136773 -0.13397 -0.0417428 -0.136773 -0.134178 -0.0417245 -0.0827732 -0.134486 -0.0417789 -0.136773 -0.134486 -0.0417789 -0.0827732 -0.134583 -0.0418181 -0.136773 -0.134583 -0.0418181 -0.0827732 -0.134915 -0.0420683 -0.144217 -0.138243 -0.0277968 -0.14381 -0.13572 -0.0353891 -0.143717 -0.138369 -0.0278404 -0.143351 -0.138716 -0.0279596 -0.143222 -0.136683 -0.0357206 -0.139998 -0.134864 -0.0410012 -0.143351 -0.137056 -0.0358493 -0.143266 -0.136292 -0.0355859 -0.143473 -0.135951 -0.0354687 -0.136773 -0.13377 -0.0418039 -0.140292 -0.133736 -0.041151 -0.136773 -0.133504 -0.0419697 -0.142867 -0.134575 -0.0387157 -0.141424 -0.135542 -0.0402468 -0.142358 -0.135633 -0.0387693 -0.142396 -0.135235 -0.0386552 -0.140019 -0.134461 -0.0409021 -0.142576 -0.13486 -0.0386363 -0.140123 -0.134062 -0.0409551 -0.140495 -0.13354 -0.0414559 -0.136773 -0.133429 -0.0420424 -0.0827732 -0.133179 -0.0429152 -0.0788015 -0.133525 -0.041909 -0.075894 -0.134472 -0.0391599 -0.136773 -0.133215 -0.0423988 -0.0827732 -0.133406 -0.0433804 -0.136773 -0.133179 -0.0429152 -0.136773 -0.133406 -0.0433804 -0.0748298 -0.135765 -0.0354046 -0.0744638 -0.136111 -0.0355237 -0.144217 -0.135638 -0.035361 -0.144226 -0.13487 -0.0380041 -0.143219 -0.134427 -0.0388799 -0.142036 -0.133925 -0.0403375 -0.139523 -0.133339 -0.042451 -0.145083 -0.136111 -0.0355237 -0.14239 -0.133936 -0.0407154 -0.0753298 -0.138243 -0.0277968 -0.0753208 -0.139265 -0.0252409 -0.0748298 -0.138369 -0.0278404 -0.0790515 -0.140341 -0.0217019 -0.0827732 -0.140666 -0.020759 -0.0827732 -0.140956 -0.0203298 -0.0800239 -0.140796 -0.020794 -0.0771564 -0.140198 -0.0225296 -0.0768976 -0.140628 -0.0224041 -0.0827732 -0.141097 -0.0202274 -0.0827732 -0.141421 -0.0201029 -0.144717 -0.135765 -0.0354046 -0.136773 -0.140666 -0.020759 -0.0827732 -0.140834 -0.0204552 -0.136773 -0.141097 -0.0202274 -0.136773 -0.140956 -0.0203298 -0.136773 -0.140834 -0.0204552 -0.14239 -0.140198 -0.0225296 -0.143219 -0.139454 -0.0242779 -0.144717 -0.138369 -0.0278404 -0.139953 -0.141215 -0.020701 -0.139813 -0.140759 -0.0209015 -0.142649 -0.140628 -0.0224041 -0.144112 -0.139359 -0.0249662 0.165043 -0.148524 -0.00466209 0.162365 -0.149902 0.00371463 0.159661 -0.149872 0.00246618 0.165569 -0.150038 -0.00430714 0.165991 -0.148567 -0.00393118 0.16669 -0.148602 -0.00301501 0.166583 -0.150105 -0.00319055 0.16669 -0.150113 -0.00301501 0.167293 -0.150158 -0.000764992 0.167268 -0.148634 -0.00123815 0.167269 -0.150156 -0.000296743 0.167069 -0.150141 0.000636215 0.166364 -0.15009 0.00197384 0.165571 -0.148547 0.00277506 0.165255 -0.15002 0.00300171 0.164243 -0.148494 0.00349518 0.16275 -0.148449 0.00373482 0.164239 -0.149968 -0.00502629 0.162793 -0.14845 -0.00526497 0.161259 -0.14988 -0.00499526 0.160543 -0.148413 -0.00466209 0.158896 -0.149878 0.00148503 0.158768 -0.149879 0.00124737 0.158394 -0.148412 0.000180908 0.158293 -0.148413 -0.000764971 0.158293 -0.149887 -0.000764971 0.158547 -0.148411 -0.00225449 0.158393 -0.149885 -0.00170783 0.158896 -0.14841 -0.00301497 0.158953 -0.149877 -0.00311102 0.160408 -0.148412 -0.00458073 0.159946 -0.149871 -0.00424938 -0.165096 -0.148449 -0.00526476 -0.16289 -0.149873 -0.00466209 -0.16739 -0.150008 0.00313213 -0.167915 -0.150038 0.0027772 -0.168337 -0.148567 0.00240124 -0.169037 -0.148602 0.00148507 -0.16893 -0.150105 0.00166061 -0.169037 -0.150113 0.00148507 -0.169518 -0.150149 0.000272171 -0.169615 -0.148634 -0.000291791 -0.16964 -0.148635 -0.000764982 -0.169416 -0.150141 -0.00216616 -0.168932 -0.148596 -0.00318733 -0.167918 -0.148547 -0.004305 -0.16739 -0.150008 -0.00466207 -0.166217 -0.149952 -0.00513407 -0.16514 -0.149914 -0.00526497 -0.164712 -0.149902 -0.00524457 -0.16739 -0.148524 0.00313214 -0.167109 -0.148513 0.00328132 -0.166586 -0.149968 0.00349635 -0.165092 -0.149912 0.00373478 -0.165659 -0.148464 0.00370492 -0.163605 -0.14988 0.00346532 -0.16514 -0.14845 0.00373503 -0.164151 -0.14843 0.00362518 -0.162292 -0.149871 0.00271943 -0.161115 -0.149879 -0.00277731 -0.160675 -0.149886 -0.00133173 -0.16074 -0.148412 -0.00171085 -0.160675 -0.148413 -0.000204022 -0.160739 -0.149885 0.000177887 -0.161242 -0.14841 0.00148503 -0.161299 -0.149877 0.00158108 -0.161883 -0.150807 0.00322008 -0.161633 -0.150871 0.00352617 -0.160755 -0.15081 0.00191903 -0.159735 -0.150884 0.000396156 -0.16289 -0.149873 0.00313215 -0.162241 -0.150264 0.00278156 -0.166598 -0.150358 0.00357561 -0.168987 -0.150486 0.00171135 -0.167951 -0.150424 0.0028472 -0.169589 -0.150527 0.000294667 -0.16964 -0.150158 -0.000764949 -0.169615 -0.150156 -0.0012332 -0.169037 -0.150113 -0.00301506 -0.16871 -0.15009 -0.00350378 -0.163254 -0.149876 -0.00485069 -0.166224 -0.150342 -0.00521425 -0.167632 -0.150406 -0.00460493 -0.167602 -0.15002 -0.00453166 -0.163217 -0.150269 -0.00492259 -0.162008 -0.149872 -0.00399612 -0.161242 -0.149878 -0.00301497 -0.161045 -0.150269 -0.00281438 -0.159656 -0.150886 -0.00146293 -0.160044 -0.150818 -0.00141356 -0.160193 -0.150879 -0.00324318 -0.16156 -0.150807 -0.00446066 -0.162975 -0.150812 -0.00543702 -0.161285 -0.150871 -0.00474421 -0.162809 -0.150875 -0.00579671 -0.164592 -0.1509 -0.00628189 -0.166433 -0.150951 -0.00614588 -0.168126 -0.151019 -0.00540402 -0.169179 -0.151012 -0.00390356 -0.169986 -0.15106 -0.00237168 -0.170588 -0.151156 -0.00134165 -0.170103 -0.151067 0.000424414 -0.170469 -0.151148 0.000512391 -0.16975 -0.151105 0.0022224 -0.165063 -0.150847 0.00438134 -0.163374 -0.150817 0.00407232 -0.160117 -0.150817 0.000313978 -0.160544 -0.150812 -0.00306737 -0.161795 -0.150593 -0.00421767 -0.163119 -0.150599 -0.00512912 -0.164631 -0.150837 -0.00588782 -0.166341 -0.150885 -0.0057638 -0.167916 -0.150948 -0.00507788 -0.167742 -0.150733 -0.00479695 -0.169898 -0.150856 -0.00126753 -0.170214 -0.151074 -0.00130198 -0.169794 -0.150849 0.000348059 -0.16943 -0.151027 0.00201518 -0.169163 -0.150809 0.0018358 -0.166659 -0.150685 0.00379203 -0.168273 -0.150965 0.00329174 -0.16676 -0.1509 0.00411139 -0.160663 -0.150274 0.000195501 -0.160444 -0.150602 0.000243382 -0.160597 -0.150275 -0.00134235 -0.160375 -0.150603 -0.00137113 -0.160844 -0.150598 -0.00291646 -0.161952 -0.150264 -0.0040541 -0.164696 -0.150294 -0.00532383 -0.164667 -0.150624 -0.00555038 -0.166267 -0.150671 -0.0054359 -0.168762 -0.150472 -0.00356034 -0.168927 -0.150796 -0.0037007 -0.169484 -0.15052 -0.00219635 -0.169684 -0.150842 -0.00226844 -0.169689 -0.150534 -0.00124342 -0.168077 -0.150749 0.00302803 -0.165072 -0.150634 0.0040426 -0.165082 -0.150304 0.0038149 -0.163574 -0.150273 0.00353965 -0.163493 -0.150603 0.00375347 -0.161233 -0.150268 0.00162403 -0.163239 -0.150879 0.00444484 -0.161041 -0.150596 0.00174298 -0.162097 -0.150593 0.00295787 -0.16064 -0.149887 -0.000764971 0.160543 -0.149873 -0.00466209 0.162735 -0.150304 -0.00534484 0.162746 -0.149912 -0.00526472 0.164252 -0.150358 -0.00510555 0.165043 -0.150008 -0.00466207 0.166641 -0.150486 -0.00324129 0.167172 -0.150149 -0.00180211 0.167342 -0.150534 -0.000286525 0.16669 -0.150113 0.00148512 0.167138 -0.15052 0.000666412 0.166416 -0.150472 0.0020304 0.160907 -0.149876 0.00332075 0.162349 -0.150294 0.00379388 0.162793 -0.149914 0.00373503 0.163871 -0.149952 0.00360413 0.163877 -0.150342 0.00368431 0.165043 -0.150008 0.00313213 0.160543 -0.149873 0.00313215 0.159606 -0.150264 0.00252416 0.158251 -0.150275 -0.000187596 0.157388 -0.150884 -0.0019261 0.157266 -0.150886 -0.000764971 0.157698 -0.150818 -0.000116385 0.15731 -0.150886 -6.70086e-05 0.157847 -0.150879 0.00171323 0.159213 -0.150807 0.00293072 0.158939 -0.150871 0.00321427 0.160629 -0.150812 0.00390708 0.162245 -0.1509 0.00475195 0.163994 -0.150885 0.00423385 0.165569 -0.150948 0.00354793 0.167135 -0.151089 0.00260817 0.168241 -0.151156 -0.000188293 0.167867 -0.151074 -0.000227962 0.167084 -0.151027 -0.00354512 0.168123 -0.151148 -0.00204233 0.164413 -0.1509 -0.00564133 0.166162 -0.151038 -0.00512751 0.162716 -0.150847 -0.00591128 0.159537 -0.150807 -0.00475002 0.158694 -0.150596 -0.00327292 0.158408 -0.15081 -0.00344897 0.157771 -0.150817 -0.00184392 0.158497 -0.150598 0.00138652 0.158198 -0.150812 0.00153743 0.159448 -0.150593 0.00268773 0.162321 -0.150624 0.00402044 0.162284 -0.150837 0.00435788 0.163921 -0.150671 0.00390596 0.165396 -0.150733 0.00326701 0.166581 -0.150796 0.00217076 0.166833 -0.151012 0.00237362 0.167639 -0.15106 0.000841742 0.167757 -0.151067 -0.00195436 0.16573 -0.150749 -0.00455797 0.165926 -0.150965 -0.00482168 0.158097 -0.150602 -0.00177332 0.158029 -0.150603 -0.000158809 0.158698 -0.150269 0.00128444 0.160871 -0.150269 0.00339265 0.160773 -0.150599 0.00359918 0.165285 -0.150406 0.00307499 0.167338 -0.150842 0.000738502 0.167552 -0.150856 -0.000262407 0.167243 -0.150527 -0.00182461 0.167448 -0.150849 -0.001878 0.166816 -0.150809 -0.00336575 0.165605 -0.150424 -0.00437715 0.164313 -0.150685 -0.00532197 0.162725 -0.150634 -0.00557254 0.161227 -0.150273 -0.00506959 0.161146 -0.150603 -0.00528341 0.159895 -0.150264 -0.00431151 0.161028 -0.150817 -0.00560226 0.159751 -0.150593 -0.00448781 0.158886 -0.150268 -0.00315397 0.158316 -0.150274 -0.00172544 0.158329 -0.149886 -0.000198211 0.212826 -0.1105 -0.0780687 0.214191 -0.11033 -0.0782664 0.21408 -0.110651 -0.0779909 0.216575 -0.111421 -0.0776851 0.218476 -0.113057 -0.07677 0.220483 -0.116255 -0.0747401 0.222181 -0.119641 -0.0724341 0.223061 -0.122358 -0.070375 0.212826 -0.110682 -0.077668 0.216122 -0.111785 -0.0771028 0.216327 -0.111667 -0.077451 0.218176 -0.113234 -0.0765761 0.217923 -0.113303 -0.0762752 0.220208 -0.116272 -0.0745047 0.221906 -0.119622 -0.0722578 0.212826 -0.110675 -0.0772279 0.21399 -0.110822 -0.0775985 0.213938 -0.11081 -0.0771643 0.22001 -0.116203 -0.0742086 0.222797 -0.122316 -0.0702421 0.213935 -0.110618 -0.0767714 0.215998 -0.111753 -0.0767023 0.215975 -0.111579 -0.0763201 0.217759 -0.113254 -0.0759153 0.219917 -0.116055 -0.0738905 0.221694 -0.119537 -0.0720246 0.222582 -0.122221 -0.0700574 0.222436 -0.122081 -0.0698375 0.22312 -0.125942 -0.0669872 0.212827 -0.110132 -0.0765618 0.213981 -0.110282 -0.0764949 0.217708 -0.113094 -0.0755534 0.216059 -0.111292 -0.076024 0.21994 -0.11585 -0.0735924 0.221567 -0.119395 -0.0717595 0.221537 -0.119212 -0.0714907 0.222372 -0.121909 -0.0696019 0.21778 -0.112849 -0.0752473 0.217962 -0.112557 -0.0750456 0.220076 -0.115613 -0.0733536 0.222395 -0.12172 -0.0693717 0.222861 -0.12564 -0.0666561 0.223827 -0.145311 -0.0393598 0.223827 -0.141604 -0.0473584 0.223827 -0.131623 -0.061647 0.223444 -0.131566 -0.0615965 0.223568 -0.126117 -0.0671783 0.223444 -0.14524 -0.039332 0.223444 -0.141537 -0.0473224 0.223327 -0.12605 -0.0671045 0.22312 -0.131404 -0.0614525 0.223444 -0.136949 -0.0547779 0.22312 -0.145039 -0.0392525 0.223444 -0.147951 -0.0310621 0.22312 -0.147742 -0.0310066 0.223444 -0.149781 -0.0224217 0.222961 -0.125803 -0.0668342 0.22312 -0.136772 -0.0546537 0.222903 -0.136506 -0.0544678 0.22312 -0.141346 -0.0472198 0.222903 -0.131161 -0.061237 0.222903 -0.14106 -0.0470662 0.222903 -0.144737 -0.0391337 0.222827 -0.144381 -0.0389935 0.222903 -0.147428 -0.0309237 0.222827 -0.147058 -0.0308258 0.200734 -0.110468 -0.0768336 0.200734 -0.110663 -0.0772277 0.188641 -0.110648 -0.0776674 0.188641 -0.110466 -0.0780682 0.212827 -0.109703 -0.076465 0.200734 -0.110121 -0.0765618 0.212826 -0.110479 -0.0768337 0.200734 -0.110671 -0.0776678 0.200734 -0.110489 -0.0780686 0.212827 -0.110164 -0.0783525 0.200734 -0.110153 -0.0783524 0.22312 -0.149567 -0.0223849 0.222903 -0.149248 -0.0223299 0.222827 -0.148871 -0.022265 0.222565 -0.149276 -0.0199898 0.222648 -0.149646 -0.0200265 0.222455 -0.149346 -0.0195644 0.221358 -0.150106 -0.0169148 0.221033 -0.149791 -0.01655 0.219051 -0.150049 -0.0144383 0.223173 -0.15018 -0.0199846 0.221812 -0.15064 -0.0166937 0.221545 -0.150421 -0.0168357 0.221552 -0.150689 -0.0162972 0.219446 -0.150946 -0.0140332 0.215983 -0.151224 -0.0118145 0.216333 -0.151112 -0.0123036 0.219066 -0.150976 -0.0137429 0.219281 -0.151074 -0.013457 0.219673 -0.151044 -0.0137573 0.221853 -0.150784 -0.0160985 0.223058 -0.150249 -0.0195287 0.222123 -0.150733 -0.0165085 0.223538 -0.150264 -0.0199121 0.212825 -0.151159 -0.0117043 0.215879 -0.151125 -0.0121553 0.212825 -0.151098 -0.011812 0.212825 -0.150938 -0.0120008 0.222861 -0.149963 -0.0200247 0.22275 -0.150032 -0.019583 0.222539 -0.149715 -0.0195955 0.221292 -0.15047 -0.0164515 0.221111 -0.150156 -0.0165399 0.21925 -0.150726 -0.0142573 0.219112 -0.150412 -0.0143988 0.218882 -0.150756 -0.013976 0.218752 -0.150442 -0.0141243 0.21623 -0.150891 -0.0125813 0.215789 -0.150904 -0.0124376 0.212826 -0.150736 -0.0121445 0.212826 -0.150624 -0.0121966 0.216157 -0.150578 -0.0127632 0.216125 -0.150215 -0.0128244 0.215726 -0.150591 -0.0126229 0.215698 -0.150227 -0.012686 0.178825 -0.12295 -0.0683623 0.178643 -0.125323 -0.066465 0.178825 -0.123134 -0.0685808 0.178746 -0.123303 -0.0687969 0.178508 -0.125662 -0.0668343 0.178349 -0.125802 -0.0669871 0.178592 -0.123444 -0.0689931 0.17812 -0.123595 -0.0692643 0.177839 -0.123594 -0.0693171 0.17888 -0.11975 -0.0723452 0.179186 -0.119796 -0.0722478 0.178378 -0.123544 -0.0691532 0.179461 -0.119774 -0.0720759 0.179804 -0.119546 -0.0715866 0.179838 -0.119363 -0.0713208 0.179982 -0.118577 -0.0714629 0.179771 -0.119158 -0.071078 0.18043 -0.117649 -0.073556 0.182612 -0.114294 -0.0756682 0.182792 -0.114236 -0.0753324 0.180747 -0.117427 -0.0729929 0.182346 -0.114246 -0.0759433 0.183202 -0.113748 -0.075609 0.18286 -0.114082 -0.0749859 0.183262 -0.113591 -0.0752554 0.182806 -0.113853 -0.0746801 0.179838 -0.117573 -0.0738882 0.180153 -0.117649 -0.0737644 0.179674 -0.119688 -0.0718474 0.180636 -0.117571 -0.0732881 0.180749 -0.117232 -0.0727059 0.180641 -0.11701 -0.0724617 0.186798 -0.110427 -0.0781944 0.185262 -0.111351 -0.0759719 0.188642 -0.110098 -0.0765618 0.187135 -0.110695 -0.0767179 0.188641 -0.110444 -0.0768335 0.188641 -0.11064 -0.0772275 0.187129 -0.110884 -0.0771095 0.187061 -0.110899 -0.077539 0.186943 -0.110736 -0.0779249 0.182461 -0.113585 -0.0764254 0.182768 -0.113745 -0.0762427 0.183028 -0.113802 -0.0759559 0.184982 -0.111727 -0.0773914 0.185192 -0.111841 -0.077047 0.185321 -0.111808 -0.0766496 0.1832 -0.113355 -0.0749491 0.185345 -0.111635 -0.0762689 0.185085 -0.111007 -0.0758106 0.187077 -0.110366 -0.0764383 0.188643 -0.109669 -0.076465 0.200729 -0.151041 -0.0118119 0.200731 -0.15068 -0.0121444 0.188631 -0.15108 -0.0113471 0.200727 -0.151201 -0.0113476 0.212824 -0.151257 -0.0113478 0.200735 -0.150204 -0.012265 0.188637 -0.150559 -0.0121444 0.178016 -0.147694 -0.0308782 0.177629 -0.147446 -0.0320815 0.178017 -0.144964 -0.0393295 0.178018 -0.14127 -0.0473639 0.177632 -0.141335 -0.0473983 0.17802 -0.137283 -0.0539846 0.178021 -0.132022 -0.0608739 0.177634 -0.137344 -0.0540258 0.178345 -0.147485 -0.0308242 0.178346 -0.144763 -0.0392511 0.178346 -0.14108 -0.0472623 0.178347 -0.137104 -0.0538637 0.177636 -0.132079 -0.0609223 0.177638 -0.125999 -0.0672016 0.177898 -0.125977 -0.0671772 0.17814 -0.125909 -0.0671041 0.178348 -0.131858 -0.0607328 0.178566 -0.144459 -0.0391327 0.178566 -0.136834 -0.0536815 0.178566 -0.131612 -0.0605207 0.178643 -0.146795 -0.0306458 0.178566 -0.147169 -0.0307425 0.178566 -0.140792 -0.0471089 0.178609 -0.125498 -0.0666562 0.188633 -0.150921 -0.0118117 0.186283 -0.151028 -0.0116022 0.186362 -0.15093 -0.011951 0.188635 -0.150761 -0.0120006 0.188643 -0.150083 -0.012265 0.18651 -0.150031 -0.0124952 0.185789 -0.151011 -0.011723 0.182857 -0.150853 -0.0129952 0.183051 -0.150758 -0.0132984 0.182413 -0.150819 -0.0132858 0.178252 -0.150104 -0.0187475 0.177627 -0.149522 -0.0224322 0.186433 -0.15071 -0.0122404 0.185884 -0.150914 -0.012068 0.185969 -0.150693 -0.0123537 0.18322 -0.150538 -0.0135464 0.182622 -0.150724 -0.0135794 0.180359 -0.150459 -0.0156881 0.18061 -0.15024 -0.0158626 0.180037 -0.150404 -0.0161123 0.180297 -0.150185 -0.0162737 0.178608 -0.15002 -0.0188606 0.178914 -0.149803 -0.0189369 0.178452 -0.149947 -0.0193473 0.178763 -0.149731 -0.0194084 0.178015 -0.149452 -0.0224203 0.186484 -0.150396 -0.0124305 0.182804 -0.150503 -0.0138188 0.183341 -0.150223 -0.0137049 0.18048 -0.149869 -0.0163663 0.179126 -0.149486 -0.0189651 0.178344 -0.149239 -0.0223842 0.178565 -0.148918 -0.0223296 0.18603 -0.150379 -0.0125411 0.182934 -0.150189 -0.0139707 0.180786 -0.149925 -0.0159651 0.180864 -0.149558 -0.0159811 0.179212 -0.149113 -0.0189411 0.178978 -0.149413 -0.0194252 0.178643 -0.148537 -0.022265 0.215058 -0.15092 0.0107164 0.212825 -0.151159 0.0101744 0.215125 -0.151142 0.0104279 0.212825 -0.151098 0.0102821 0.212826 -0.150736 0.0106145 0.21499 -0.150243 0.0109717 0.21501 -0.150607 0.0109063 0.212826 -0.150624 0.0106666 0.215595 -0.151132 0.010544 0.218618 -0.151117 0.0114792 0.219055 -0.15109 0.0117667 0.218848 -0.150992 0.012058 0.221725 -0.150805 0.0143867 0.221428 -0.150711 0.0145913 0.212825 -0.150938 0.0104708 0.218426 -0.151019 0.01178 0.21826 -0.150798 0.0120265 0.221107 -0.150761 0.0141686 0.215514 -0.150911 0.0108289 0.21867 -0.150771 0.0122958 0.220689 -0.150228 0.0144438 0.220861 -0.150542 0.0143413 0.220916 -0.149812 0.014856 0.220614 -0.149863 0.0144617 0.218545 -0.150458 0.0124477 0.21849 -0.150094 0.0124929 0.218144 -0.150485 0.0121849 0.215456 -0.150597 0.0110161 0.223204 -0.150434 0.0172278 0.222853 -0.150346 0.0173387 0.221172 -0.150491 0.014751 0.220993 -0.150177 0.0148435 0.222552 -0.150128 0.0174135 0.222261 -0.149444 0.0174186 0.222491 -0.149742 0.0178975 0.222345 -0.149812 0.0174415 0.222407 -0.149372 0.0178686 0.222701 -0.150058 0.0178809 0.223007 -0.150275 0.0178211 0.223444 -0.149781 0.0208917 0.223444 -0.147991 0.0293811 0.223444 -0.141517 0.0458282 0.223827 -0.14126 0.0464605 0.223827 -0.137554 0.0525047 0.22312 -0.149567 0.020855 0.22312 -0.147781 0.0293261 0.223444 -0.145237 0.0378104 0.22312 -0.137312 0.0523399 0.223444 -0.137491 0.0524619 0.223444 -0.132197 0.0593471 0.22312 -0.132033 0.0592052 0.222903 -0.149248 0.0207999 0.222903 -0.147468 0.0292438 0.22312 -0.145035 0.037731 0.222903 -0.144733 0.0376121 0.22312 -0.141326 0.0457256 0.222903 -0.141041 0.0455719 0.222903 -0.131788 0.0589929 0.222827 -0.147097 0.0291467 0.222827 -0.140704 0.0453906 0.222903 -0.137044 0.0521574 0.222827 -0.136728 0.0519421 0.222903 -0.125724 0.0652177 0.188633 -0.150921 0.0102817 0.188631 -0.15108 0.00981718 0.200735 -0.150204 0.010735 0.188643 -0.150083 0.010735 0.200729 -0.151041 0.010282 0.200731 -0.15068 0.0106145 0.188635 -0.150761 0.0104706 0.188637 -0.150559 0.0106144 0.216675 -0.111289 0.0741648 0.223444 -0.126089 0.0656173 0.22312 -0.125942 0.0654572 0.222647 -0.123277 0.0670389 0.221639 -0.119483 0.0697789 0.222726 -0.123445 0.067255 0.221802 -0.119807 0.0703055 0.222014 -0.119893 0.0705337 0.222879 -0.123585 0.067451 0.223092 -0.123685 0.0676111 0.22335 -0.123737 0.0677224 0.22363 -0.123736 0.0677757 0.221672 -0.119665 0.0700448 0.220833 -0.117659 0.0717581 0.222288 -0.119915 0.0707056 0.22163 -0.117662 0.0723585 0.218664 -0.11392 0.0731502 0.22083 -0.117101 0.070931 0.220722 -0.117321 0.0711756 0.220723 -0.117515 0.0714628 0.221038 -0.117737 0.0720261 0.221315 -0.117737 0.0722346 0.218204 -0.11365 0.0737276 0.218609 -0.114147 0.0734563 0.218676 -0.114302 0.0738029 0.218264 -0.113807 0.0740815 0.218437 -0.11386 0.0744284 0.218856 -0.114359 0.0741387 0.219122 -0.114312 0.0744138 0.219434 -0.114167 0.0745872 0.216205 -0.111399 0.0744428 0.218267 -0.113415 0.073421 0.216121 -0.111682 0.0747402 0.216274 -0.111887 0.0755185 0.216484 -0.111774 0.0758629 0.218697 -0.113803 0.0747152 0.214502 -0.110002 0.0747937 0.21439 -0.110406 0.0749087 0.214337 -0.110923 0.0755804 0.216145 -0.111855 0.075121 0.214405 -0.110938 0.0760099 0.216739 -0.111535 0.0760936 0.212827 -0.110132 0.0750319 0.214332 -0.110734 0.0751886 0.212826 -0.110479 0.0753038 0.212826 -0.110682 0.076138 0.214523 -0.110775 0.0763958 0.214669 -0.110466 0.0766651 0.177911 -0.149927 0.0183986 0.178643 -0.148537 0.020735 0.178926 -0.149383 0.0180779 0.179012 -0.14901 0.0180457 0.178015 -0.149452 0.0208904 0.178281 -0.149847 0.0184721 0.178032 -0.149999 0.0179209 0.179325 -0.150415 0.0149846 0.181777 -0.150762 0.0122289 0.179902 -0.150378 0.0147737 0.18217 -0.150798 0.0119284 0.18512 -0.150882 0.0107752 0.185577 -0.150902 0.0106257 0.178397 -0.149918 0.0180106 0.178599 -0.149631 0.0185127 0.17871 -0.149702 0.0180656 0.179641 -0.150325 0.0151718 0.182008 -0.150667 0.012507 0.180167 -0.15016 0.0149292 0.182387 -0.150703 0.0122163 0.185671 -0.150681 0.0109088 0.178816 -0.149312 0.0185142 0.179914 -0.150107 0.015315 0.180105 -0.149791 0.0153937 0.182208 -0.150448 0.0127323 0.182576 -0.150483 0.0124505 0.185228 -0.150661 0.0110537 0.180353 -0.149844 0.0150172 0.180187 -0.149422 0.0153968 0.182351 -0.150133 0.0128735 0.182416 -0.149767 0.0129109 0.182711 -0.150168 0.0125985 0.185305 -0.150347 0.0112355 0.185739 -0.150367 0.0110941 0.185772 -0.150002 0.011156 0.188639 -0.150447 0.0106666 0.200734 -0.110121 0.0750319 0.200734 -0.110468 0.0753037 0.200734 -0.110663 0.0756978 0.212826 -0.110675 0.0756979 0.200734 -0.110671 0.0761378 0.200734 -0.110489 0.0765386 0.212826 -0.1105 0.0765388 0.200734 -0.110153 0.0768225 0.188642 -0.110098 0.0750318 0.188641 -0.110444 0.0753035 0.188641 -0.11064 0.0756975 0.188641 -0.110466 0.0765383 0.188642 -0.11013 0.0768222 0.178023 -0.125948 0.0656166 0.178609 -0.125498 0.0651262 0.177637 -0.131453 0.0601106 0.177638 -0.125999 0.0656716 0.177632 -0.141356 0.0458275 0.178018 -0.141292 0.0457932 0.17763 -0.145024 0.0378448 0.178017 -0.144957 0.0378185 0.177629 -0.147142 0.0316236 0.178016 -0.147644 0.0295397 0.177628 -0.147713 0.0295578 0.177627 -0.149522 0.0209023 0.178348 -0.131235 0.0599183 0.178021 -0.131397 0.0600615 0.178347 -0.136564 0.0531224 0.17802 -0.136742 0.0532457 0.178346 -0.144756 0.0377401 0.178345 -0.147435 0.0294851 0.178566 -0.136297 0.0529369 0.178346 -0.141101 0.0456917 0.178566 -0.144452 0.0376216 0.178566 -0.14712 0.0294026 0.178344 -0.149239 0.0208543 0.178566 -0.130991 0.059703 0.178643 -0.135981 0.0527175 0.178566 -0.140814 0.0455385 0.178643 -0.144093 0.0374815 0.178565 -0.148918 0.0207997 0.187453 -0.11079 0.0760649 0.185316 -0.111757 0.0755617 0.187505 -0.110778 0.075631 0.185441 -0.111726 0.0751617 0.183677 -0.11323 0.0743662 0.179768 -0.119454 0.0704825 0.178671 -0.122199 0.0687119 0.187509 -0.110585 0.0752383 0.181454 -0.116132 0.0726737 0.185464 -0.111551 0.07478 0.185381 -0.111265 0.074484 0.183728 -0.11307 0.074005 0.181548 -0.115984 0.0723559 0.179896 -0.119311 0.0702178 0.179926 -0.119127 0.0699493 0.179098 -0.12179 0.0680721 0.187463 -0.11025 0.0749619 0.185207 -0.110916 0.0743259 0.183658 -0.112824 0.0736991 0.181526 -0.115778 0.0720582 0.181391 -0.11554 0.0718197 0.179855 -0.118921 0.0697059 0.179075 -0.121599 0.0678421 0.185111 -0.11164 0.0759092 0.184861 -0.111395 0.076143 0.18098 -0.116185 0.0732049 0.178973 -0.11951 0.0709913 0.178567 -0.125582 0.0652177 0.179033 -0.121963 0.0683076 0.178349 -0.125802 0.0654571 0.178886 -0.122104 0.0685274 0.178405 -0.122241 0.0688444 0.179555 -0.119539 0.0707152 0.181256 -0.116202 0.0729697 0.17928 -0.119559 0.0708911 0.183512 -0.113279 0.0747253 0.183259 -0.11321 0.0750254 0.188641 -0.110648 0.0761375 0.187362 -0.110619 0.076457 -0.190978 -0.150982 0.0101739 -0.190977 -0.15108 0.00981718 -0.188831 -0.150396 0.0109005 -0.188856 -0.150031 0.0109652 -0.188377 -0.150379 0.0110111 -0.188629 -0.151028 0.0100723 -0.188709 -0.15093 0.0104211 -0.185203 -0.150853 0.0114653 -0.185397 -0.150758 0.0117684 -0.182417 -0.150551 0.0139364 -0.184968 -0.150724 0.0120495 -0.182706 -0.150459 0.0141582 -0.182082 -0.150495 0.014375 -0.182383 -0.150404 0.0145824 -0.180436 -0.150029 0.0177211 -0.188779 -0.15071 0.0107104 -0.188231 -0.150914 0.010538 -0.188315 -0.150693 0.0108238 -0.185566 -0.150538 0.0120165 -0.182644 -0.150185 0.0147438 -0.180954 -0.15002 0.0173307 -0.18126 -0.149803 0.017407 -0.180798 -0.149947 0.0178174 -0.185687 -0.150223 0.012175 -0.18515 -0.150503 0.0122889 -0.182956 -0.15024 0.0143326 -0.183133 -0.149925 0.0144351 -0.182827 -0.149869 0.0148363 -0.181472 -0.149486 0.0174351 -0.18111 -0.149731 0.0178785 -0.180691 -0.149239 0.0208543 -0.18528 -0.150189 0.0124408 -0.181324 -0.149413 0.0178953 -0.18099 -0.148537 0.020735 -0.180361 -0.149452 0.0208904 -0.180912 -0.148918 0.0207997 -0.180691 -0.147485 0.0292942 -0.179975 -0.147763 0.0293662 -0.180362 -0.147694 0.0293483 -0.180363 -0.144964 0.0377995 -0.180365 -0.14127 0.045834 -0.179979 -0.141015 0.0464605 -0.179981 -0.137344 0.0524959 -0.180368 -0.132022 0.059344 -0.180692 -0.144763 0.0377211 -0.180366 -0.137283 0.0524547 -0.180694 -0.137104 0.0523337 -0.180369 -0.125948 0.0656166 -0.180695 -0.125802 0.0654571 -0.180912 -0.144459 0.0376027 -0.180912 -0.140792 0.045579 -0.180693 -0.14108 0.0457323 -0.180913 -0.136834 0.0521516 -0.180913 -0.131612 0.0589908 -0.180694 -0.131858 0.0592029 -0.18099 -0.146795 0.0291159 -0.180912 -0.147169 0.0292126 -0.18099 -0.1441 0.0374627 -0.18099 -0.140452 0.0453977 -0.18099 -0.13132 0.0587402 -0.18099 -0.125323 0.064935 -0.215172 -0.150624 0.0106666 -0.203078 -0.15068 0.0106145 -0.203075 -0.151041 0.010282 -0.190979 -0.150921 0.0102817 -0.190981 -0.150761 0.0104706 -0.215172 -0.150938 0.0104708 -0.19099 -0.150083 0.010735 -0.190985 -0.150447 0.0106666 -0.190984 -0.150559 0.0106144 -0.180913 -0.125582 0.0652177 -0.180939 -0.123444 0.0674632 -0.181227 -0.11975 0.0708153 -0.180466 -0.123595 0.0677343 -0.181533 -0.119796 0.0707179 -0.180724 -0.123544 0.0676233 -0.181807 -0.119774 0.0705459 -0.181092 -0.123303 0.067267 -0.182151 -0.119546 0.0700567 -0.181172 -0.123134 0.0670509 -0.182184 -0.119363 0.0697908 -0.184381 -0.114101 0.074587 -0.184693 -0.114246 0.0744133 -0.184959 -0.114294 0.0741382 -0.182983 -0.117571 0.0717581 -0.185139 -0.114236 0.0738025 -0.185207 -0.114082 0.073456 -0.185152 -0.113853 0.0731502 -0.184807 -0.113585 0.0748955 -0.185114 -0.113745 0.0747127 -0.185375 -0.113802 0.0744259 -0.185548 -0.113748 0.0740791 -0.182184 -0.117573 0.0723583 -0.182499 -0.117649 0.0722345 -0.182776 -0.117649 0.0720261 -0.18202 -0.119688 0.0703175 -0.183093 -0.117427 0.0714629 -0.182987 -0.11701 0.0709318 -0.183095 -0.117232 0.071176 -0.187074 -0.111487 0.0760925 -0.189145 -0.110427 0.0766644 -0.187538 -0.111841 0.0755171 -0.187667 -0.111808 0.0751196 -0.189481 -0.110695 0.075188 -0.189476 -0.110884 0.0755796 -0.190987 -0.110648 0.0761375 -0.189407 -0.110899 0.076009 -0.18929 -0.110736 0.076395 -0.187329 -0.111727 0.0758615 -0.185609 -0.113591 0.0737254 -0.185546 -0.113355 0.0734191 -0.187692 -0.111635 0.074739 -0.187608 -0.111351 0.0744419 -0.189424 -0.110366 0.0749083 -0.190989 -0.110098 0.0750318 -0.22552 -0.15018 0.0184547 -0.225249 -0.149248 0.0207999 -0.224994 -0.149646 0.0184966 -0.225885 -0.150264 0.0183822 -0.225405 -0.150249 0.0179988 -0.22447 -0.150733 0.0149785 -0.221792 -0.150946 0.0125033 -0.222019 -0.151044 0.0122273 -0.218679 -0.151112 0.0107737 -0.225097 -0.150032 0.018053 -0.224159 -0.15064 0.0151637 -0.223891 -0.150421 0.0153058 -0.223898 -0.150689 0.0147673 -0.221413 -0.150976 0.012213 -0.218225 -0.151125 0.0106253 -0.218576 -0.150891 0.0110514 -0.215171 -0.151098 0.0102821 -0.218135 -0.150904 0.0109077 -0.225208 -0.149963 0.0184947 -0.224886 -0.149715 0.0180655 -0.223638 -0.15047 0.0149216 -0.221596 -0.150726 0.0127274 -0.221458 -0.150412 0.0128689 -0.221228 -0.150756 0.0124461 -0.215172 -0.150736 0.0106145 -0.224802 -0.149346 0.0180344 -0.223704 -0.150106 0.0153848 -0.223625 -0.149741 0.0153898 -0.223457 -0.150156 0.0150099 -0.221398 -0.150049 0.0129083 -0.221098 -0.150442 0.0125943 -0.218503 -0.150578 0.0112333 -0.218471 -0.150215 0.0112945 -0.218072 -0.150591 0.011093 -0.190988 -0.110444 0.0753035 -0.190987 -0.11064 0.0756975 -0.20308 -0.110663 0.0756978 -0.20308 -0.110489 0.0765386 -0.190988 -0.110466 0.0765383 -0.190988 -0.11013 0.0768222 -0.203081 -0.109692 0.074935 -0.215173 -0.110479 0.0753038 -0.203081 -0.110121 0.0750319 -0.20308 -0.110468 0.0753037 -0.215173 -0.110675 0.0756979 -0.215173 -0.110682 0.076138 -0.20308 -0.110671 0.0761378 -0.226173 -0.149856 0.0209046 -0.225791 -0.149781 0.0208917 -0.225173 -0.130875 0.0594528 -0.225207 -0.12564 0.0651262 -0.226173 -0.131623 0.0601171 -0.225791 -0.126089 0.0656173 -0.225791 -0.131566 0.0600665 -0.226173 -0.141604 0.0458284 -0.225791 -0.141537 0.0457924 -0.225466 -0.131404 0.0599225 -0.225466 -0.136772 0.0531238 -0.225791 -0.136949 0.053248 -0.225791 -0.14524 0.037802 -0.225466 -0.147742 0.0294767 -0.225791 -0.147951 0.0295321 -0.225249 -0.131161 0.059707 -0.225249 -0.136506 0.0529379 -0.225249 -0.14106 0.0455363 -0.225466 -0.141346 0.0456898 -0.225249 -0.144737 0.0376038 -0.225466 -0.145039 0.0377226 -0.225466 -0.149567 0.020855 -0.225173 -0.136192 0.0527186 -0.225173 -0.140723 0.0453552 -0.225173 -0.144381 0.0374636 -0.225249 -0.147428 0.0293937 -0.225173 -0.147058 0.0292959 -0.225173 -0.148871 0.020735 -0.215173 -0.1105 0.0765388 -0.215173 -0.109703 0.074935 -0.215173 -0.110132 0.0750319 -0.216336 -0.110822 0.0760686 -0.216285 -0.11081 0.0756344 -0.218344 -0.111753 0.0751723 -0.220105 -0.113254 0.0743853 -0.222554 -0.116272 0.0729748 -0.222357 -0.116203 0.0726786 -0.224253 -0.119622 0.0707278 -0.224041 -0.119537 0.0704947 -0.218322 -0.111579 0.0747902 -0.220055 -0.113094 0.0740235 -0.223913 -0.119395 0.0702295 -0.216281 -0.110618 0.0752415 -0.222263 -0.116055 0.0723606 -0.222286 -0.11585 0.0720625 -0.224718 -0.121909 0.0680719 -0.216327 -0.110282 0.074965 -0.216414 -0.109867 0.0748578 -0.218406 -0.111292 0.0744941 -0.218581 -0.110944 0.0743364 -0.220126 -0.112849 0.0737174 -0.223884 -0.119212 0.0699607 -0.223956 -0.119007 0.0697169 -0.216537 -0.11033 0.0767365 -0.218922 -0.111421 0.0761552 -0.218673 -0.111667 0.0759211 -0.223147 -0.116154 0.0733537 -0.220522 -0.113234 0.0750462 -0.224834 -0.119593 0.0710049 -0.224527 -0.119641 0.0709042 -0.225698 -0.122343 0.0689143 -0.224741 -0.12172 0.0678417 -0.225249 -0.125724 0.0652177 -0.225466 -0.125942 0.0654572 -0.224782 -0.122081 0.0683075 -0.224929 -0.122221 0.0685275 -0.225143 -0.122316 0.0687122 -0.225408 -0.122358 0.068845 -0.22283 -0.116255 0.0732102 -0.22027 -0.113303 0.0747453 -0.218468 -0.111785 0.0755729 -0.216426 -0.110651 0.076461 -0.189595 -0.110299 -0.0782624 -0.190988 -0.110466 -0.0780682 -0.190987 -0.110648 -0.0776674 -0.19099 -0.109669 -0.076465 -0.189708 -0.110619 -0.0779869 -0.187208 -0.111395 -0.0776729 -0.187457 -0.11164 -0.0774392 -0.181319 -0.11951 -0.0725213 -0.181626 -0.119559 -0.072421 -0.180752 -0.122241 -0.0703743 -0.180461 -0.122225 -0.070443 -0.179985 -0.125999 -0.0672016 -0.189799 -0.11079 -0.0775948 -0.185605 -0.11321 -0.0765553 -0.183327 -0.116185 -0.0747349 -0.183603 -0.116202 -0.0744997 -0.189852 -0.110778 -0.077161 -0.187788 -0.111726 -0.0766916 -0.187662 -0.111757 -0.0770916 -0.185858 -0.113279 -0.0762552 -0.181901 -0.119539 -0.0722451 -0.181017 -0.122199 -0.0702418 -0.181233 -0.122104 -0.0700574 -0.187811 -0.111551 -0.0763099 -0.186023 -0.11323 -0.0758961 -0.183801 -0.116132 -0.0742037 -0.182114 -0.119454 -0.0720124 -0.182242 -0.119311 -0.0717477 -0.18138 -0.121963 -0.0698376 -0.189855 -0.110585 -0.0767683 -0.18981 -0.11025 -0.0764918 -0.187728 -0.111265 -0.0760139 -0.186075 -0.11307 -0.0755349 -0.183895 -0.115984 -0.0738859 -0.181444 -0.12179 -0.0696021 -0.180955 -0.125498 -0.0666562 -0.187553 -0.110916 -0.0758559 -0.185823 -0.112533 -0.0750271 -0.186004 -0.112824 -0.0752291 -0.183872 -0.115778 -0.0735881 -0.183737 -0.11554 -0.0733497 -0.182272 -0.119127 -0.0714793 -0.180245 -0.125977 -0.0671772 -0.180695 -0.125802 -0.0669871 -0.180694 -0.131235 -0.0614482 -0.180855 -0.125662 -0.0668343 -0.179979 -0.141356 -0.0473575 -0.180366 -0.136742 -0.0547757 -0.179981 -0.136802 -0.0548176 -0.180368 -0.131397 -0.0615914 -0.179983 -0.131453 -0.0616405 -0.180362 -0.147644 -0.0310696 -0.179975 -0.147713 -0.0310878 -0.180361 -0.149452 -0.0224203 -0.180487 -0.125909 -0.0671041 -0.180365 -0.141292 -0.0473232 -0.180363 -0.144957 -0.0393485 -0.180691 -0.147435 -0.031015 -0.180694 -0.136564 -0.0546524 -0.180693 -0.141101 -0.0472216 -0.180692 -0.144756 -0.03927 -0.180912 -0.14712 -0.0309325 -0.180913 -0.130991 -0.061233 -0.180913 -0.136297 -0.0544668 -0.18099 -0.140474 -0.0468873 -0.180912 -0.140814 -0.0470684 -0.180912 -0.144452 -0.0391516 -0.18099 -0.144093 -0.0390114 -0.18099 -0.148537 -0.022265 -0.203081 -0.110121 -0.0765618 -0.20308 -0.110468 -0.0768336 -0.215173 -0.110479 -0.0768337 -0.215173 -0.110675 -0.0772279 -0.20308 -0.110489 -0.0780686 -0.215173 -0.110682 -0.077668 -0.215173 -0.1105 -0.0780687 -0.190989 -0.110098 -0.0765618 -0.190988 -0.110444 -0.0768335 -0.190987 -0.11064 -0.0772275 -0.20308 -0.110663 -0.0772277 -0.20308 -0.110671 -0.0776678 -0.203081 -0.110153 -0.0783524 -0.180628 -0.149847 -0.020002 -0.180691 -0.149239 -0.0223842 -0.180945 -0.149631 -0.0200426 -0.181163 -0.149312 -0.0200442 -0.181272 -0.149383 -0.0196078 -0.182534 -0.149422 -0.0169267 -0.184762 -0.149767 -0.0144408 -0.181057 -0.149702 -0.0195955 -0.184354 -0.150667 -0.0140369 -0.182513 -0.15016 -0.0164591 -0.184922 -0.150483 -0.0139805 -0.187924 -0.150902 -0.0121557 -0.188017 -0.150681 -0.0124388 -0.187817 -0.150998 -0.0118137 -0.187467 -0.150882 -0.0123051 -0.187345 -0.150978 -0.0119682 -0.184733 -0.150703 -0.0137462 -0.184516 -0.150798 -0.0134583 -0.184124 -0.150762 -0.0137589 -0.182248 -0.150378 -0.0163036 -0.181943 -0.150469 -0.0161028 -0.181987 -0.150325 -0.0167018 -0.180743 -0.149918 -0.0195405 -0.180378 -0.149999 -0.0194509 -0.180257 -0.149927 -0.0199285 -0.179973 -0.149522 -0.0224322 -0.180912 -0.148918 -0.0223296 -0.182451 -0.149791 -0.0169237 -0.18226 -0.150107 -0.016845 -0.184555 -0.150448 -0.0142622 -0.182699 -0.149844 -0.0165472 -0.184697 -0.150133 -0.0144034 -0.187574 -0.150661 -0.0125836 -0.187652 -0.150347 -0.0127654 -0.185119 -0.149803 -0.0141697 -0.185989 -0.149877 -0.013605 -0.185057 -0.150168 -0.0141285 -0.188085 -0.150367 -0.012624 -0.190985 -0.150447 -0.0121965 -0.22079 -0.113137 -0.0747386 -0.225173 -0.125466 -0.066465 -0.224993 -0.123277 -0.0685689 -0.225207 -0.12564 -0.0666561 -0.225307 -0.125803 -0.0668342 -0.225225 -0.123585 -0.0689809 -0.225439 -0.123685 -0.0691411 -0.225466 -0.125942 -0.0669872 -0.225673 -0.12605 -0.0671045 -0.225696 -0.123737 -0.0692523 -0.224994 -0.123094 -0.0683504 -0.223985 -0.119483 -0.0713089 -0.225072 -0.123445 -0.0687849 -0.224634 -0.119915 -0.0722355 -0.224052 -0.11928 -0.0710658 -0.224018 -0.119665 -0.0715747 -0.224148 -0.119807 -0.0718354 -0.224361 -0.119893 -0.0720636 -0.223976 -0.117662 -0.0738885 -0.22494 -0.119871 -0.072333 -0.223176 -0.117101 -0.072461 -0.220955 -0.114147 -0.0749862 -0.223068 -0.117321 -0.0727055 -0.223069 -0.117515 -0.0729927 -0.223179 -0.117659 -0.0732881 -0.221203 -0.114359 -0.0756687 -0.223385 -0.117737 -0.0735561 -0.223662 -0.117737 -0.0737646 -0.220614 -0.113415 -0.074951 -0.22101 -0.11392 -0.0746801 -0.22055 -0.11365 -0.0752576 -0.22061 -0.113807 -0.0756115 -0.220783 -0.11386 -0.0759584 -0.221023 -0.114302 -0.0753329 -0.221468 -0.114312 -0.0759437 -0.218468 -0.111682 -0.0762701 -0.218492 -0.111855 -0.076651 -0.21883 -0.111774 -0.0773928 -0.221044 -0.113803 -0.0762452 -0.219085 -0.111535 -0.0776236 -0.21873 -0.111056 -0.0758111 -0.216737 -0.110406 -0.0764387 -0.218552 -0.111399 -0.0759728 -0.21862 -0.111887 -0.0770485 -0.21687 -0.110775 -0.0779258 -0.215173 -0.110132 -0.0765618 -0.216678 -0.110734 -0.0767186 -0.216683 -0.110923 -0.0771104 -0.216751 -0.110938 -0.0775399 -0.215173 -0.110164 -0.0783525 -0.190979 -0.150921 -0.0118117 -0.203075 -0.151041 -0.0118119 -0.190981 -0.150761 -0.0120006 -0.203078 -0.15068 -0.0121444 -0.190984 -0.150559 -0.0121444 -0.203081 -0.150204 -0.012265 -0.215171 -0.151257 -0.0113478 -0.190978 -0.150982 -0.0117039 -0.215172 -0.150938 -0.0120008 -0.226173 -0.149856 -0.0224346 -0.225466 -0.149567 -0.0223849 -0.225466 -0.147781 -0.0308561 -0.226173 -0.148065 -0.0309304 -0.225791 -0.147991 -0.030911 -0.225791 -0.145237 -0.0393404 -0.226173 -0.147753 -0.0320815 -0.225791 -0.141517 -0.0473582 -0.226173 -0.141584 -0.0473942 -0.226173 -0.137554 -0.0540346 -0.225791 -0.132197 -0.0608771 -0.226173 -0.132776 -0.0603182 -0.225466 -0.141326 -0.0472555 -0.225466 -0.137312 -0.0538699 -0.225791 -0.137491 -0.0539918 -0.225914 -0.126117 -0.0671783 -0.225249 -0.149248 -0.0223299 -0.225249 -0.147468 -0.0307738 -0.225466 -0.145035 -0.0392609 -0.225466 -0.132033 -0.0607352 -0.225249 -0.131788 -0.0605228 -0.225173 -0.144377 -0.0390018 -0.225249 -0.144733 -0.0391421 -0.225249 -0.141041 -0.0471018 -0.225249 -0.137044 -0.0536874 -0.225173 -0.131498 -0.0602723 -0.217472 -0.151142 -0.0119578 -0.215173 -0.150261 -0.012265 -0.215172 -0.150736 -0.0121445 -0.215171 -0.151098 -0.011812 -0.217551 -0.15124 -0.0116102 -0.218037 -0.15123 -0.0117304 -0.217942 -0.151132 -0.012074 -0.220772 -0.151019 -0.01331 -0.220964 -0.151117 -0.0130092 -0.221401 -0.15109 -0.0132967 -0.221195 -0.150992 -0.0135879 -0.223454 -0.150761 -0.0156985 -0.217404 -0.15092 -0.0122463 -0.223774 -0.150711 -0.0161213 -0.217357 -0.150607 -0.0124362 -0.21786 -0.150911 -0.0123588 -0.217803 -0.150597 -0.0125461 -0.220607 -0.150798 -0.0135564 -0.221017 -0.150771 -0.0138258 -0.223208 -0.150542 -0.0158713 -0.223518 -0.150491 -0.016281 -0.223339 -0.150177 -0.0163735 -0.223834 -0.149693 -0.0172665 -0.223035 -0.150228 -0.0159737 -0.222961 -0.149863 -0.0159916 -0.220836 -0.150094 -0.0140228 -0.220891 -0.150458 -0.0139777 -0.22049 -0.150485 -0.0137149 -0.217778 -0.150234 -0.0126101 -0.224071 -0.150805 -0.0159166 -0.225551 -0.150434 -0.0187578 -0.225199 -0.150346 -0.0188687 -0.224607 -0.149444 -0.0189486 -0.224691 -0.149812 -0.0189714 -0.224899 -0.150128 -0.0189435 -0.224838 -0.149742 -0.0194275 -0.225048 -0.150058 -0.0194108 -0.225791 -0.149781 -0.0224217 -0.225354 -0.150275 -0.019351 -0.0715622 -0.142736 -0.0318609 -0.0714385 -0.141817 -0.0351025 -0.0718882 -0.14002 -0.0400738 -0.0718882 -0.138479 -0.0400738 -0.0754519 -0.137993 -0.0449796 -0.0723309 -0.13802 -0.0412039 -0.0727509 -0.139258 -0.0420001 -0.0727508 -0.139316 -0.0419998 -0.073051 -0.139061 -0.0424763 -0.0728566 -0.139242 -0.0421749 -0.0741414 -0.138523 -0.0438265 -0.0769485 -0.137546 -0.045921 -0.0804956 -0.136954 -0.0471375 -0.0798771 -0.137007 -0.0470085 -0.0798771 -0.135323 -0.0470085 -0.0867732 -0.143693 -0.0193671 -0.0867732 -0.145206 -0.0193671 -0.0955732 -0.14534 -0.0193411 -0.105573 -0.144016 -0.0193041 -0.106773 -0.144042 -0.0192991 -0.116773 -0.144278 -0.0192532 -0.125573 -0.144519 -0.0192063 -0.142299 -0.138089 -0.0468979 -0.142839 -0.138232 -0.0466536 -0.143046 -0.138283 -0.0465511 -0.14175 -0.137959 -0.0471166 -0.144673 -0.138842 -0.0455608 -0.144671 -0.13883 -0.0455619 -0.145607 -0.139244 -0.0448026 -0.148323 -0.141135 -0.0408124 -0.147973 -0.140768 -0.0416485 -0.148773 -0.141816 -0.039101 -0.148773 -0.140228 -0.039101 -0.0876224 -0.136886 -0.0473842 -0.103438 -0.136975 -0.047568 -0.0989974 -0.136943 -0.0475164 -0.118603 -0.137123 -0.0477442 -0.128406 -0.137252 -0.0478581 -0.111153 -0.135334 -0.0476576 -0.136773 -0.14487 -0.0191378 -0.0771883 -0.144892 -0.0208655 -0.0761408 -0.144782 -0.0215526 -0.0771883 -0.143376 -0.0208655 -0.0755198 -0.143185 -0.0220423 -0.113644 -0.135359 -0.0476866 -0.113644 -0.137068 -0.0476866 -0.14449 -0.146297 -0.021443 -0.144347 -0.14479 -0.0213337 -0.145321 -0.146207 -0.022157 -0.0721189 -0.1438 -0.0271324 -0.0604129 -0.14393 -0.0261444 0.116803 -0.0797717 0.0826198 0.174619 -0.0804406 0.0825792 0.116805 -0.0882134 0.0816334 0.171193 -0.0774544 0.0827137 0.172222 -0.0784689 0.0826819 0.169072 -0.0765877 0.0827296 -0.17354 -0.0774544 0.0827137 -0.173292 -0.077236 0.0827187 -0.206703 -0.0809277 0.0825457 -0.17748 -0.0806505 0.0825651 -0.217083 -0.108727 0.074751 -0.119161 -0.104312 0.076702 -0.179132 -0.0809277 0.0825455 -0.119151 -0.0882134 0.0816334 -0.215173 -0.108366 0.074935 -0.219301 -0.110072 0.0740432 -0.221018 -0.111852 0.0730489 -0.234274 -0.110052 0.0740537 -0.234274 -0.116228 0.0703094 -0.225173 -0.139331 0.0447761 -0.225173 -0.136689 0.0492731 -0.234275 -0.136687 0.0492732 -0.234276 -0.142273 0.0386492 -0.225173 -0.142815 0.0373406 -0.234276 -0.144098 0.0338822 -0.225173 -0.147348 0.020735 -0.234277 -0.145691 0.0285853 -0.234277 -0.147925 0.0170922 -0.183215 -0.147986 0.0144461 -0.185989 -0.148293 -0.0136052 -0.19099 -0.148491 -0.012265 -0.234277 -0.148077 -0.0175316 -0.234277 -0.149203 -0.000214427 -0.220429 -0.148529 -0.0137577 -0.224606 -0.147881 -0.018945 -0.234277 -0.148 -0.0180878 -0.234277 -0.146025 -0.0287749 -0.234276 -0.143997 -0.0357049 -0.225173 -0.14241 -0.0398609 -0.234276 -0.140717 -0.0435984 -0.225173 -0.138577 -0.0476664 -0.234275 -0.132287 -0.0569725 -0.225173 -0.129357 -0.0604288 -0.234274 -0.120108 -0.0690216 -0.225173 -0.123212 -0.066465 -0.234274 -0.114196 -0.0731655 -0.223978 -0.11715 -0.0712053 -0.219029 -0.109852 -0.0756916 -0.234273 -0.106704 -0.0772808 -0.216819 -0.108634 -0.0763287 -0.190668 -0.108342 -0.0764598 -0.119171 -0.112667 -0.0738021 -0.179132 -0.0809277 -0.0840755 -0.17858 -0.0808974 -0.0840777 -0.175597 -0.0794832 -0.0841658 -0.119149 -0.0808509 -0.0840804 -0.176966 -0.0804406 -0.0841092 -0.172851 -0.0776909 -0.0842375 -0.172518 -0.0776727 -0.084238 0.116803 -0.0808509 -0.0840804 0.173667 -0.0798507 -0.0841455 0.172045 -0.0783205 -0.0842174 0.170172 -0.0776727 -0.084238 0.231927 -0.0809277 -0.0840756 0.231927 -0.106704 -0.0772808 0.182739 -0.111866 -0.0745356 0.183595 -0.110884 -0.0750971 0.213145 -0.108376 -0.0764599 0.18515 -0.109536 -0.075835 0.231927 -0.0879632 -0.0832176 0.231927 -0.0962711 -0.081277 0.116805 -0.0892699 -0.0829667 0.116816 -0.105282 -0.0777908 0.231927 -0.114196 -0.0731655 0.231928 -0.120108 -0.0690216 0.231928 -0.126579 -0.0633358 0.222827 -0.134788 -0.0536373 0.231929 -0.141312 -0.0423455 0.231929 -0.140717 -0.0435984 0.222827 -0.139331 -0.0463061 0.222827 -0.142815 -0.0388706 0.23193 -0.146025 -0.0287749 0.222827 -0.147348 -0.022265 0.231931 -0.148 -0.0180878 0.221488 -0.148115 -0.0172658 0.231931 -0.148077 -0.0175316 0.231931 -0.149053 -0.0069045 0.219047 -0.148457 -0.0144353 0.217827 -0.148545 -0.0136051 0.175815 -0.148811 -0.000214227 0.186521 -0.148442 -0.0124928 0.184816 -0.148367 -0.0130264 0.183405 -0.148275 -0.0137468 0.188643 -0.148491 0.010735 0.214978 -0.14865 0.0109691 0.231931 -0.149203 -0.000214427 0.218083 -0.148529 0.0122278 0.231931 -0.1491 0.00434408 0.231931 -0.148636 0.0111489 0.221488 -0.148115 0.0157369 0.23193 -0.147456 0.0200862 0.222827 -0.14241 0.038331 0.222827 -0.144101 0.0338821 0.222827 -0.145275 0.0301277 0.23193 -0.14639 0.0256376 0.231929 -0.133766 0.0535169 0.231929 -0.136687 0.0492732 0.231928 -0.129178 0.0590952 0.222827 -0.123212 0.064935 0.231928 -0.123011 0.0651087 0.222656 -0.121017 0.0667732 0.221632 -0.11715 0.0696753 0.214472 -0.108634 0.0747987 0.231927 -0.110052 0.0740537 0.218732 -0.111928 0.0730051 0.212827 -0.108366 0.074935 0.188643 -0.108333 0.074935 0.188321 -0.108342 0.0749298 0.182791 -0.1118 0.073044 0.184509 -0.110027 0.0740406 0.231927 -0.0870545 0.081838 0.116815 -0.104312 0.076702 0.231927 -0.102243 0.0776869 -0.182329 -0.14781 -0.0172657 -0.17816 -0.147703 -0.0175368 -0.18099 -0.142543 -0.0388871 -0.18099 -0.145227 -0.0307691 -0.18099 -0.129298 -0.0603118 -0.178145 -0.132137 -0.0568969 -0.182264 -0.116851 -0.0713497 -0.119182 -0.119507 -0.0689488 -0.18099 -0.123083 -0.066465 0.178643 -0.147031 0.020735 0.178643 -0.145227 0.0292392 0.175801 -0.136438 0.0492812 0.178643 -0.139097 0.0447741 0.178643 -0.134591 0.0521021 -0.182328 -0.116688 0.0699336 -0.187496 -0.109536 0.0743051 -0.181162 -0.120887 0.0667844 -0.182191 -0.117041 0.0696871 -0.11917 -0.111759 0.0728271 -0.178154 -0.143778 0.0338905 -0.18099 -0.138341 0.0461501 -0.178151 -0.140562 0.0418057 -0.178148 -0.136438 0.0492812 -0.18099 -0.147031 0.020735 0.179844 -0.117041 -0.0712171 0.180602 -0.11529 -0.07241 0.178816 -0.120887 -0.0683144 0.178643 -0.123083 -0.066465 0.178643 -0.142148 -0.0398597 0.175802 -0.137009 -0.0498913 0.178643 -0.134505 -0.0537546 0.175798 -0.132137 -0.0568969 0.175795 -0.126473 -0.0632728 0.180868 -0.147986 -0.015976 0.175811 -0.146266 -0.0260973 -0.169519 -0.148629 -0.00179817 -0.169037 -0.148602 -0.00301499 -0.16739 -0.148524 -0.00466208 -0.166589 -0.148494 -0.00502512 -0.16289 -0.148413 -0.00466209 -0.162294 -0.14841 -0.00425146 -0.161301 -0.148409 -0.00311364 -0.16064 -0.148413 -0.000764971 -0.160893 -0.148411 0.000724544 -0.161626 -0.148409 0.00204613 -0.162754 -0.148412 0.00305079 -0.16289 -0.148413 0.00313215 -0.178161 -0.148811 -0.000214227 -0.169206 -0.148611 0.00116321 0.116922 -0.146076 -0.0175595 0.159279 -0.148409 -0.00357607 0.163313 -0.148464 -0.00523487 0.164762 -0.148513 -0.00481127 0.166859 -0.148611 -0.00269315 0.167293 -0.148635 -0.000764959 0.167173 -0.148629 0.000268229 0.16669 -0.148602 0.00148505 0.166586 -0.148596 0.00165739 0.175813 -0.147553 0.0170977 0.165043 -0.148524 0.00313214 0.161262 -0.148421 0.00346658 0.160543 -0.148413 0.00313215 0.159948 -0.14841 0.00272152 0.116928 -0.147104 -0.000213361 0.158955 -0.148409 0.0015837 -0.111153 -0.137043 -0.0476576 -0.1088 -0.13702 -0.0476303 -0.0823225 -0.136872 -0.0473226 -0.0891947 -0.136892 -0.0474025 -0.0603397 -0.135322 -0.0499459 -0.0761185 -0.137777 -0.0454392 -0.146385 -0.139643 -0.0440212 -0.178148 -0.137009 -0.0498913 -0.144304 -0.138702 -0.0458179 -0.14257 -0.138159 -0.046779 -0.12846 -0.137271 -0.0478267 -0.12377 -0.137213 -0.0477597 -0.137231 -0.137393 -0.0479553 -0.138244 -0.137419 -0.0479511 -0.123849 -0.137189 -0.0478052 -0.131605 -0.1373 -0.0478953 -0.134055 -0.137338 -0.0479237 -0.130758 -0.137287 -0.0478854 -0.130799 -0.137301 -0.0478616 -0.131567 -0.137311 -0.0478733 -0.1214 -0.137158 -0.0477767 -0.120955 -0.137152 -0.0477715 -0.148094 -0.140885 -0.0413845 -0.148832 -0.144304 -0.0316768 -0.178152 -0.141021 -0.0423541 -0.178155 -0.144119 -0.0343909 -0.178158 -0.146266 -0.0260973 -0.18099 -0.147031 -0.022265 -0.148771 -0.144657 -0.0303265 -0.148756 -0.144731 -0.0300309 -0.125573 -0.146033 -0.0192063 -0.119268 -0.146076 -0.0175595 -0.142736 -0.14636 -0.0206736 -0.144036 -0.146271 -0.0215132 -0.163609 -0.148421 -0.00499652 -0.144347 -0.146309 -0.0213337 -0.07416 -0.144475 -0.0234108 -0.0771941 -0.144891 -0.0208688 -0.105573 -0.14553 -0.0193041 -0.106773 -0.145556 -0.0192991 -0.0737824 -0.138698 -0.0434329 -0.060367 -0.139091 -0.0424112 -0.0721475 -0.139812 -0.0407857 -0.0719903 -0.139974 -0.0403757 -0.0603918 -0.141969 -0.0344456 -0.0714053 -0.14112 -0.0372485 -0.119162 -0.105282 -0.0777908 -0.0011732 -0.112442 -0.0738086 -0.119156 -0.0974494 -0.0808601 -0.0011732 -0.0973682 -0.0808616 -0.119152 -0.0892699 -0.0829667 -0.093233 -0.13691 -0.0474494 -0.119223 -0.135902 -0.049927 -0.119209 -0.131201 -0.0569282 -0.119195 -0.125712 -0.063298 -0.178142 -0.126473 -0.0632728 -0.0602818 -0.125313 -0.0633116 -0.0602782 -0.124576 0.0625393 -0.0011732 -0.124571 0.0625394 -0.0603072 -0.130068 0.0562593 -0.0011732 -0.130062 0.0562595 -0.0011732 -0.134777 0.0493353 -0.0603637 -0.138661 0.0418627 -0.0603889 -0.141655 0.0339459 -0.0011732 -0.138654 0.041863 -0.0011732 -0.143719 0.0256936 -0.0604274 -0.145089 0.0171339 -0.0011732 -0.146199 -0.000212908 -0.0011732 -0.145214 -0.0175714 -0.0011732 -0.14196 -0.0344459 -0.0011732 -0.139083 -0.0424114 -0.0603109 -0.13071 -0.056945 -0.0011732 -0.0797687 0.0826198 -0.0011732 -0.0881857 0.0816337 -0.119155 -0.0964292 0.0796512 -0.0011732 -0.104174 0.0767053 -0.119221 -0.135352 0.0493164 -0.0603361 -0.134783 0.0493351 -0.119235 -0.139314 0.0418431 -0.119248 -0.142384 0.0339269 -0.119259 -0.144523 0.0256768 -0.0604105 -0.143728 0.0256934 -0.119275 -0.147104 -0.000213361 -0.0604428 -0.146209 -0.000212913 -0.0604291 -0.145224 -0.0175712 -0.119267 -0.145936 0.0171215 -0.178159 -0.147553 0.0170977 -0.178157 -0.146041 0.0256449 -0.119207 -0.130547 0.0562429 -0.178144 -0.131461 0.0562122 0.179917 -0.116851 0.0698198 0.116834 -0.118673 0.0680798 0.178643 -0.123083 0.064935 0.116847 -0.124963 0.0625262 0.175795 -0.125702 0.0625017 0.175798 -0.131461 0.0562122 0.116875 -0.135352 0.0493164 0.116889 -0.139314 0.0418431 0.116902 -0.142384 0.0339269 0.175805 -0.140562 0.0418057 0.175808 -0.143778 0.0338905 0.116913 -0.144523 0.0256768 0.116921 -0.145936 0.0171215 0.175811 -0.146041 0.0256449 0.161805 -0.14843 -0.00515512 0.175813 -0.147703 -0.0175368 0.116914 -0.144733 -0.0261283 0.175809 -0.144119 -0.0343909 0.175805 -0.141021 -0.0423541 0.116877 -0.135902 -0.049927 0.116862 -0.131201 -0.0569282 0.116848 -0.125712 -0.063298 0.0579354 -0.125313 -0.0633116 0.0579645 -0.13071 -0.056945 0.0579933 -0.135322 -0.0499459 0.11689 -0.139754 -0.0423915 0.0580206 -0.139091 -0.0424112 0.116903 -0.142708 -0.0344269 0.058081 -0.145089 0.0171339 0.0580641 -0.143728 0.0256934 0.0580173 -0.138661 0.0418627 0.11686 -0.130547 0.0562429 0.116824 -0.111759 0.0728271 -0.0011732 -0.111544 0.0728332 -0.0011732 -0.0963552 0.0796525 0.116809 -0.0964292 0.0796512 -0.119149 -0.0797717 0.0826198 -0.0250792 -0.0765877 0.0827296 -0.178141 -0.125702 0.0625017 -0.119193 -0.124963 0.0625262 -0.119181 -0.118673 0.0680798 -0.0011732 -0.118372 0.0680894 0.0579318 -0.124576 0.0625393 0.0579608 -0.130068 0.0562593 0.0579897 -0.134783 0.0493351 0.0580425 -0.141655 0.0339459 -0.0011732 -0.141646 0.0339461 -0.0011732 -0.145079 0.017134 0.0580964 -0.146209 -0.000212913 0.0580827 -0.145224 -0.0175712 0.0580665 -0.14393 -0.0261444 -0.0011732 -0.143921 -0.0261446 0.0580454 -0.141969 -0.0344456 -0.0011732 -0.135316 -0.0499461 -0.0011732 -0.130705 -0.0569452 -0.0011732 -0.125308 -0.0633118 -0.0011732 -0.119195 -0.0689588 0.116836 -0.119507 -0.0689488 -0.0011732 -0.105136 -0.0777944 0.116825 -0.112667 -0.0738021 0.116809 -0.0974494 -0.0808601 -0.0011732 -0.0892374 -0.0829671 -0.0011732 -0.080846 -0.0840804 -0.450682 0.0274411 0.00774297 -0.449657 0.013772 0.0158062 -0.449805 0.0275608 0.0157225 -0.450799 0.0540551 0.00669952 -0.442528 0.0509677 0.0552893 -0.441512 0.0475515 0.0570859 -0.441829 0.0485912 0.0566837 -0.440545 0.0446605 0.0576702 -0.441207 0.0465928 0.0573626 -0.441968 0.0481548 0.0550325 -0.440906 0.0444775 0.0552325 -0.442702 0.0486067 0.0520013 -0.436 0.0346415 0.057705 -0.436331 0.0338319 0.0560536 -0.438036 0.0373087 0.0557575 -0.442828 0.0451626 0.0490698 -0.441823 0.0449621 0.0522331 -0.443529 0.0487961 0.0488577 -0.444779 0.0524812 0.0455095 -0.444393 0.0488383 0.0456416 -0.443356 0.052291 0.0518041 -0.439583 0.0408618 0.0554794 -0.444348 0.0416219 0.0424629 -0.444472 0.0345631 0.0390141 -0.445395 0.0416344 0.0388705 -0.446055 0.0488077 0.0387843 -0.447624 0.0486799 0.0311923 -0.449375 0.0546941 0.0213343 -0.449989 0.0413815 0.0156264 -0.43982 0.0344475 0.0497629 -0.441534 0.034497 0.0462987 -0.443109 0.034527 0.04268 -0.444939 0.0276269 0.0353743 -0.448328 0.0276382 0.0236576 -0.447924 0.0138181 0.0238286 -0.448888 0.0137975 0.0198292 -0.450646 -4.05616e-08 0.00773204 -0.426077 0.00358558 0.0576345 -0.426007 0.00426724 0.057705 -0.448317 -4.30752e-08 0.0220208 -0.445224 -6.9768e-08 0.0316242 -0.443342 -4.16489e-08 0.0358981 -0.44127 -4.6616e-08 0.0398368 -0.441612 0.00695623 0.0393295 -0.43929 0.00697112 0.0431744 -0.433196 0.00703327 0.051001 -0.429618 0.00357114 0.0545134 -0.42597 -4.36267e-08 0.057705 -0.426789 0.0124664 0.057705 -0.426677 0.0104983 0.057534 -0.430134 0.0105013 0.054387 -0.433479 0.0104716 0.050931 -0.433935 0.0138836 0.050839 -0.436648 0.0104339 0.0471262 -0.448824 0.0415366 0.0234562 -0.446776 0.0346105 0.0313831 -0.44727 0.0416228 0.0312682 -0.446367 0.0416366 0.0351321 -0.445241 0.0488371 0.0422996 -0.443186 0.0416055 0.0459525 -0.440735 0.0413548 0.0524874 -0.441957 0.0415576 0.0492948 -0.438061 0.0342678 0.0530269 -0.435139 0.0273798 0.0535461 -0.432779 0.0270734 0.0566338 -0.431103 0.0237629 0.0568915 -0.428786 0.0197806 0.057705 -0.428345 0.0171744 0.0572958 -0.437491 0.0172608 0.046993 -0.438128 0.0206718 0.0468939 -0.440546 0.0206776 0.0430646 -0.443785 0.0138368 0.0355319 -0.441911 0.0138344 0.0393391 -0.436996 0.013854 0.0470698 -0.434578 0.0172775 0.050721 -0.430701 0.0138963 0.054284 -0.431503 0.0172644 0.0541479 -0.427365 0.0138578 0.0574354 -0.427619 0.0161307 0.057705 -0.426263 0.00708073 0.0575972 -0.429785 0.00706681 0.0544612 -0.436438 0.00699647 0.0471659 -0.439694 0.0138377 0.0431554 -0.443559 0.00694739 0.0355305 -0.445217 0.00694034 0.0317122 -0.445387 0.0138377 0.0316866 -0.44676 0.0138321 0.0277863 -0.447358 0.0276536 0.0275953 -0.45079 -3.44295e-08 0.00573113 -0.450973 0.0270368 -0.000264971 -0.450973 0.0272985 -0.000264971 -0.45072 0.0411795 0.00773482 -0.448589 0.0345787 0.0235543 -0.44574 0.0207313 0.0316143 -0.446232 0.0276494 0.0315068 -0.444266 0.0207172 0.0354767 -0.443462 0.0275927 0.0391666 -0.442555 0.0206963 0.0392837 -0.441756 0.0275567 0.0428975 -0.439733 0.0275312 0.0466291 -0.437484 0.0274999 0.0502076 -0.435403 0.0206727 0.050576 -0.433763 0.023993 0.0537765 -0.432535 0.0206268 0.0539785 -0.429605 0.0204712 0.0571142 -0.439278 -0.00696933 0.043193 -0.436278 -4.16671e-08 0.0472601 -0.433382 -5.85538e-08 0.0506842 -0.445211 -0.00693848 0.0317255 -0.426002 -0.00407596 0.057705 -0.42624 -0.00707885 0.0576167 -0.426653 -0.0104954 0.0575536 -0.427342 -0.0138536 0.0574552 -0.427478 -0.015602 0.057705 -0.428613 -0.0192985 0.057705 -0.428323 -0.0171689 0.0573156 -0.434339 -0.0315223 0.057705 -0.436659 -0.0359065 0.057705 -0.44021 -0.0437468 0.057705 -0.44196 -0.0481361 0.0550524 -0.442123 -0.049588 0.0561874 -0.443117 -0.0528536 0.0535195 -0.444774 -0.0524657 0.0455265 -0.445236 -0.0488228 0.0423161 -0.4449 -0.0557451 0.0459077 -0.449211 -0.0547441 0.0224765 -0.448034 -0.0550619 0.0297569 -0.44762 -0.0486662 0.031206 -0.448822 -0.0415249 0.0234666 -0.449988 -0.04137 0.0156333 -0.450113 -0.0544345 0.0153854 -0.438022 -0.0372935 0.0557771 -0.439571 -0.0408452 0.0554989 -0.440724 -0.0413406 0.0525071 -0.440896 -0.0444598 0.0552521 -0.442694 -0.0485903 0.052021 -0.443522 -0.0487811 0.0488765 -0.43972 -0.0275233 0.0466487 -0.4431 -0.0345169 0.0426976 -0.444341 -0.0416097 0.04248 -0.446051 -0.0487936 0.0388001 -0.444386 -0.0488238 0.0456591 -0.44335 -0.0522735 0.0518238 -0.447921 -0.0138143 0.023839 -0.449447 -3.16938e-08 0.0168093 -0.449619 -3.72052e-08 0.0158487 -0.430154 -5.97272e-08 0.0539895 -0.436421 -0.00699475 0.0471869 -0.443552 -0.00694553 0.0355453 -0.445381 -0.0138339 0.0317 -0.446896 6.49077e-09 0.0269846 -0.448325 -0.0276304 0.023668 -0.448886 -0.0137937 0.0198379 -0.449804 -0.027553 0.0157295 -0.449656 -0.0137682 0.0158132 -0.450275 -2.51995e-08 0.0113739 -0.450682 -0.0274334 0.00774644 -0.430112 -0.0104986 0.0544071 -0.433917 -0.01388 0.0508594 -0.43068 -0.0138925 0.0543041 -0.435386 -0.0206669 0.0505962 -0.441814 -0.0449468 0.0522528 -0.439806 -0.034437 0.0497826 -0.437469 -0.0274918 0.0502276 -0.433744 -0.0239855 0.0537966 -0.432515 -0.0206206 0.0539987 -0.436315 -0.0338182 0.0560732 -0.438047 -0.0342562 0.0530468 -0.435122 -0.0273709 0.0535662 -0.432759 -0.0270631 0.0566537 -0.431083 -0.0237542 0.0569114 -0.429583 -0.0204642 0.0571341 -0.431483 -0.0172594 0.0541681 -0.440535 -0.0206718 0.0430828 -0.446362 -0.0416245 0.0351471 -0.44539 -0.0416222 0.0388866 -0.444933 -0.027619 0.0353894 -0.444465 -0.0345531 0.0390305 -0.443454 -0.0275847 0.0391831 -0.441745 -0.0275487 0.0429154 -0.438113 -0.020666 0.046914 -0.437475 -0.0172561 0.0470133 -0.43698 -0.0138503 0.0470904 -0.441902 -0.0138306 0.0393556 -0.441603 -0.00695439 0.039346 -0.444259 -0.0207113 0.0354918 -0.43456 -0.0172728 0.0507413 -0.441523 -0.0344869 0.0463178 -0.443177 -0.0415932 0.0459709 -0.442819 -0.0451487 0.0490888 -0.441947 -0.0415448 0.049314 -0.442668 -0.0514381 0.0549161 -0.43902 -4.40189e-08 0.0434763 -0.443778 -0.0138329 0.0355468 -0.445735 -0.0207255 0.0316279 -0.446227 -0.0276415 0.0315205 -0.446756 -0.0138282 0.0277983 -0.447355 -0.0276458 0.0276074 -0.450973 -0.0135211 -0.000264971 -0.450973 -0.0272908 -0.000264971 -0.429596 -0.00357034 0.0545333 -0.426053 -0.00358471 0.0576539 -0.429764 -0.00706508 0.0544812 -0.43346 -0.010469 0.0509515 -0.433177 -0.0070316 0.0510215 -0.436632 -0.0104312 0.047147 -0.439682 -0.0138339 0.0431738 -0.442546 -0.0206904 0.0393002 -0.446771 -0.0346006 0.0313968 -0.447266 -0.0416109 0.0312819 -0.448587 -0.034569 0.0235646 -0.45072 -0.0411679 0.00773827 -0.449993 -0.040105 -0.0161239 -0.444393 -0.0514697 -0.0487334 -0.445121 -0.0517867 -0.0452579 -0.443329 -0.04821 -0.0521896 -0.443222 -0.0492524 -0.0535408 -0.441284 -0.0436432 -0.0575799 -0.43947 -0.0376352 -0.0558799 -0.437922 -0.0343485 -0.0561588 -0.436231 -0.0311425 -0.056451 -0.431762 -0.0247915 -0.058235 -0.429665 -0.0188669 -0.0574933 -0.426427 -0.00655526 -0.0579839 -0.434798 -0.0159424 -0.0509654 -0.426831 -0.00970536 -0.0579168 -0.437188 -0.0128511 -0.0473261 -0.430343 -0.00968436 -0.0547082 -0.433759 -0.00967588 -0.0511451 -0.434188 -0.0128191 -0.0510684 -0.438273 -0.0191603 -0.0471635 -0.444963 -0.0260363 -0.0357315 -0.444301 -0.0195252 -0.0358615 -0.44165 -0.00652441 -0.0397848 -0.441954 -0.0129685 -0.0397586 -0.443598 -0.00655132 -0.0359725 -0.443826 -0.013043 -0.0359449 -0.445429 -0.013118 -0.0320895 -0.446919 -6.69139e-08 -0.0274445 -0.448345 -0.0264926 -0.0240878 -0.449814 -0.026708 -0.0161879 -0.450274 -5.30159e-08 -0.0119148 -0.444777 -0.0487352 -0.0458973 -0.442662 -0.0447866 -0.0523854 -0.440684 -0.0380531 -0.052861 -0.440949 -0.0350355 -0.0498617 -0.439418 -0.0347497 -0.0531223 -0.439851 -0.0317648 -0.05008 -0.438033 -0.0315053 -0.0533885 -0.437585 -0.0253525 -0.050495 -0.435175 -0.0251707 -0.0538951 -0.432653 -0.0189754 -0.0543156 -0.43166 -0.0158922 -0.0544794 -0.428466 -0.0176225 -0.058235 -0.429919 -0.0211139 -0.058235 -0.428446 -0.0158412 -0.0576747 -0.432747 -0.0249269 -0.0570193 -0.440808 -0.0409901 -0.0556256 -0.441775 -0.0414 -0.0526125 -0.443116 -0.0321755 -0.0429973 -0.441572 -0.0319726 -0.0465932 -0.441787 -0.0256765 -0.0432354 -0.444481 -0.03239 -0.0393303 -0.443484 -0.0258557 -0.0395159 -0.442591 -0.0193949 -0.0396675 -0.440604 -0.0192697 -0.0434261 -0.439768 -0.0129018 -0.0435409 -0.447379 -0.0263607 -0.0280047 -0.44679 -0.0328076 -0.031755 -0.446255 -0.0262077 -0.031889 -0.4457 -0.0326043 -0.035578 -0.4454 -0.039024 -0.0391547 -0.448829 -0.03982 -0.0239173 -0.448599 -0.0331469 -0.0239995 -0.441892 -0.0444094 -0.0554091 -0.444388 -0.0453327 -0.046003 -0.446074 -0.0457612 -0.0390372 -0.445777 -0.0423799 -0.0390861 -0.447639 -0.0461539 -0.0315414 -0.44728 -0.0394582 -0.0316295 -0.449136 -0.0527362 -0.0235117 -0.449372 -0.0528075 -0.0218775 -0.45027 -0.0531347 -0.0143843 -0.450799 -0.0534467 -0.00723753 -0.450973 -0.0270421 -0.000264971 -0.450685 -0.0268831 -0.00823979 -0.450656 -0.0134334 -0.0082301 -0.445253 -2.81954e-08 -0.0320813 -0.445262 -0.006581 -0.0321257 -0.439367 -0.00650506 -0.0435819 -0.438907 -2.85066e-08 -0.0441755 -0.436662 -0.00649794 -0.0474043 -0.436247 -5.45456e-08 -0.04783 -0.433497 -0.00650502 -0.0511995 -0.43305 -4.44813e-08 -0.0515771 -0.430008 -0.00652493 -0.0547782 -0.426241 -0.00332461 -0.0580262 -0.427371 -0.0141812 -0.058235 -0.427499 -0.0127954 -0.0578157 -0.430888 -0.0128026 -0.0546101 -0.435585 -0.0190665 -0.050835 -0.439822 -0.0255112 -0.0469096 -0.442418 -0.0352586 -0.0464286 -0.44319 -0.0385852 -0.0462715 -0.443854 -0.0419437 -0.0461284 -0.444344 -0.0388012 -0.0427648 -0.445774 -0.0196508 -0.0320069 -0.4468 -0.0131865 -0.0281829 -0.447958 -0.0132459 -0.0242281 -0.448913 -0.0132983 -0.0202416 -0.449449 -4.89544e-08 -0.017332 -0.449674 -0.0133458 -0.016239 -0.443096 0.0489128 -0.053963 -0.426 0.00376409 -0.058235 -0.441247 0.0435402 -0.0576149 -0.44053 0.0416591 -0.0580793 -0.442308 0.0466138 -0.0560659 -0.443318 0.0481957 -0.0522323 -0.447633 0.0461432 -0.0315716 -0.448825 0.0398112 -0.0239402 -0.430415 0.0221606 -0.058235 -0.431075 0.0218805 -0.0573174 -0.434147 0.0128162 -0.0511154 -0.429959 0.00652397 -0.0548252 -0.427448 0.0127929 -0.0578604 -0.430841 0.0128 -0.0546569 -0.430294 0.00968267 -0.0547551 -0.426188 0.00332425 -0.0580703 -0.429769 -4.33691e-08 -0.054886 -0.438242 0.0191554 -0.0472076 -0.44058 0.0192646 -0.0434668 -0.442572 0.0193898 -0.0397048 -0.444287 0.0195201 -0.0358955 -0.446245 0.0262012 -0.0319196 -0.42962 0.0188614 -0.057538 -0.428398 0.0158373 -0.0577195 -0.431614 0.0158884 -0.0545259 -0.437155 0.0128481 -0.0473708 -0.433716 0.00967397 -0.0511924 -0.436627 0.00649662 -0.0474496 -0.43934 0.00650357 -0.0436231 -0.441629 0.00652284 -0.0398222 -0.445417 0.0131148 -0.03212 -0.44525 0.00657942 -0.0321562 -0.448326 -4.1612e-08 -0.0225151 -0.446791 0.0131834 -0.0282101 -0.445763 0.0196459 -0.0320375 -0.443811 0.0130398 -0.0359789 -0.441934 0.0129652 -0.039796 -0.439742 0.0128986 -0.0435819 -0.434758 0.0159386 -0.051012 -0.435548 0.0190616 -0.0508812 -0.432611 0.0189705 -0.0543618 -0.437553 0.0253454 -0.0505402 -0.449639 -4.44548e-08 -0.0162618 -0.450684 0.0268777 -0.00824763 -0.447371 0.0263545 -0.0280317 -0.449812 0.0267023 -0.0162035 -0.44834 0.0264866 -0.0241111 -0.449671 0.0133429 -0.0162548 -0.450098 0.0530617 -0.0160549 -0.449991 0.0400967 -0.0161394 -0.448594 0.0331395 -0.0240227 -0.441966 0.0455953 -0.0567053 -0.444767 0.0487225 -0.0459362 -0.442649 0.0447726 -0.0524282 -0.441879 0.0443936 -0.0554539 -0.442609 0.0475152 -0.0553689 -0.439394 0.034738 -0.0531663 -0.438005 0.0314948 -0.053433 -0.4424 0.035249 -0.0464703 -0.440927 0.0350252 -0.0499051 -0.444331 0.0387909 -0.0428035 -0.440664 0.0380404 -0.0529045 -0.443174 0.0385747 -0.0463126 -0.443841 0.0419325 -0.0461688 -0.445767 0.0423692 -0.0391221 -0.445389 0.039014 -0.039191 -0.447273 0.0394488 -0.0316598 -0.446065 0.0457499 -0.039073 -0.444376 0.0453207 -0.0460427 -0.441759 0.0413866 -0.0526556 -0.440791 0.0409744 -0.0556698 -0.43945 0.0376201 -0.0559238 -0.437897 0.0343344 -0.0562026 -0.45065 -4.27591e-08 -0.00820951 -0.450656 0.0134306 -0.00823796 -0.450789 -4.79811e-08 -0.00627926 -0.450973 0.0135184 -0.000264971 -0.450973 -4.19898e-08 -0.000264971 -0.42678 0.00970383 -0.0579614 -0.426375 0.00655444 -0.0580282 -0.433454 0.00650387 -0.0512471 -0.441243 -4.73787e-08 -0.0404128 -0.443366 -3.58933e-08 -0.0363778 -0.443582 0.00654972 -0.0360064 -0.436202 0.0311299 -0.0564949 -0.432709 0.0249178 -0.0570637 -0.435139 0.0251629 -0.0539406 -0.439826 0.0317555 -0.0501241 -0.44155 0.0319638 -0.0466354 -0.443099 0.0321668 -0.0430368 -0.439796 0.0255043 -0.0469528 -0.441767 0.0256695 -0.0432756 -0.443467 0.0258488 -0.039553 -0.444467 0.0323814 -0.039367 -0.445689 0.032596 -0.0356118 -0.446781 0.0327995 -0.0317854 -0.44495 0.0260296 -0.0357654 -0.448909 0.0132954 -0.0202613 -0.447952 0.0132429 -0.0242516 -0.436718 0.041643 -0.0580819 -0.441173 0.0433396 -0.05768 -0.43747 0.0434146 -0.0576561 -0.439627 0.0492522 -0.0535409 -0.439424 0.0487185 -0.0541882 -0.442511 0.0472224 -0.0556106 -0.438757 0.0468555 -0.0558923 -0.441347 0.0438177 -0.0575182 -0.438161 0.0452011 -0.0569165 -0.444033 0.0510037 -0.0503533 -0.440388 0.0509011 -0.050624 -0.428534 0.0178061 -0.058235 -0.428761 0.0183996 -0.058235 -0.424041 0.0194603 -0.058235 -0.426182 0.0235255 -0.058235 -0.439734 0.0397325 -0.058235 -0.437719 0.0354893 -0.058235 -0.433965 0.0361663 -0.058235 -0.431634 0.0322878 -0.058235 -0.435465 0.0313738 -0.058235 -0.429656 0.029172 -0.058235 -0.43285 0.0267765 -0.058235 -0.437832 -0.0357077 -0.058235 -0.43066 -0.0307475 -0.058235 -0.434692 -0.0300182 -0.058235 -0.432106 -0.0254275 -0.058235 -0.422762 -0.0164731 -0.058235 -0.421714 -0.0132868 -0.058235 -0.42661 -0.0106639 -0.058235 -0.426157 -0.00693271 -0.058235 -0.422625 0.0161078 -0.058235 -0.427433 0.0144087 -0.058235 -0.426663 0.0109733 -0.058235 -0.426197 0.00741014 -0.058235 -0.420579 0.00702965 -0.058235 -0.420379 0.00357922 -0.058235 -0.425969 -4.2946e-08 -0.058235 -0.440814 -0.0514699 -0.0487325 -0.443494 -0.049932 -0.0525574 -0.439434 -0.0487442 -0.0541591 -0.438921 -0.0473189 -0.0555327 -0.438671 -0.046613 -0.0560666 -0.442506 -0.0472067 -0.0556232 -0.438298 -0.0455732 -0.0567177 -0.437624 -0.0437975 -0.0575255 -0.44052 -0.0416365 -0.058083 -0.435836 -0.0397326 -0.058235 -0.445516 -0.0527132 -0.0240379 -0.446544 -0.0530485 -0.0163575 -0.447305 -0.0534555 -0.0070374 -0.442874 -0.0520718 -0.0387286 -0.447616 -0.0523403 -0.0325782 -0.446389 -0.05206 -0.0389991 -0.441232 -0.0517212 -0.0467584 -0.447449 -0.0538618 0.00226976 -0.450973 -0.0537512 -0.000264971 -0.447162 -0.0541535 0.00895138 -0.450703 -0.0541303 0.00841827 -0.444526 -0.0550503 0.0294898 -0.446632 -0.0553915 0.0373046 -0.443849 -0.0552129 0.0332143 -0.440903 -0.0456819 0.057548 -0.441518 -0.0475724 0.0570789 -0.438415 -0.049298 0.0563439 -0.442605 -0.0512268 0.0550885 -0.438925 -0.0509598 0.0552953 -0.44448 -0.055548 0.0478806 -0.444232 -0.0552819 0.0490128 -0.440652 -0.0552819 0.0490128 -0.444019 -0.0549686 0.049956 -0.443397 -0.0536362 0.0525021 -0.439475 -0.0526888 0.0537076 -0.444633 0.0556569 0.0471708 -0.443747 0.0544594 0.0511122 -0.439288 0.0521183 0.0543025 -0.442841 0.0520031 0.0544132 -0.438241 0.0487453 0.0566144 -0.44234 0.0503295 0.0557383 -0.43758 0.0467656 0.0573191 -0.436867 0.0448467 0.0576545 -0.436424 0.0437467 0.057705 -0.446344 0.0554557 0.038777 -0.445533 0.0547846 0.0234061 -0.447732 0.0551358 0.0314497 -0.450271 0.0543672 0.0138459 -0.446556 0.054449 0.0157198 -0.447304 0.0540466 0.00650494 -0.450932 0.053604 -0.00363271 -0.450744 0.0534017 -0.00826587 -0.442874 0.0520717 -0.0387298 -0.450606 0.053308 -0.0104137 -0.449167 0.0527453 -0.0233013 -0.445525 0.0527156 -0.0239804 -0.447942 0.0524189 -0.0307762 -0.446474 0.0520786 -0.03857 -0.431748 -0.0265509 0.057705 -0.423536 -0.0195001 0.057705 -0.438527 0.0397192 0.057705 -0.432159 0.0353127 0.057705 -0.426837 0.0262227 0.057705 -0.43195 0.026955 0.057705 -0.430244 0.0233727 0.057705 -0.425084 0.0229021 0.057705 -0.438653 -0.0399967 0.057705 -0.42669 -0.011896 0.057705 -0.426209 -0.00805278 0.057705 -0.426294 0.0089571 0.057705 -0.420449 0.00559873 0.057705 -0.423569 0.0195799 0.057705 -0.444503 -4.19898e-08 -0.0232931 -0.428673 0.016502 -0.0526145 -0.421817 0.0136514 -0.058235 -0.42893 0.0280313 -0.058235 -0.429749 0.0261844 -0.0555702 -0.426748 0.0197945 -0.0556549 -0.44743 0.0536011 -0.00370049 -0.447473 0.0268755 -0.000264971 -0.439893 0.0499021 -0.0526053 -0.43983 0.0486834 -0.0519952 -0.438449 0.0452304 -0.0552866 -0.440105 0.0262889 -0.0385914 -0.439256 0.0197402 -0.0385593 -0.437332 0.019712 -0.0421519 -0.435078 0.0197056 -0.0457144 -0.429646 0.0197528 -0.0525593 -0.428164 0.0229994 -0.0556125 -0.434021 0.0131674 -0.0457419 -0.432479 0.0197209 -0.0492206 -0.43111 0.0131915 -0.0493014 -0.427916 0.0132397 -0.0526669 -0.447187 0.0268863 -0.00807421 -0.446192 0.0133618 -0.0158386 -0.444506 0.0132953 -0.0235899 -0.447155 -4.19898e-08 -0.00800633 -0.443792 0.0396491 -0.0312155 -0.445116 0.0332535 -0.0235756 -0.444873 0.0266001 -0.0235789 -0.446326 0.0267448 -0.015854 -0.439203 0.045459 -0.0520759 -0.437434 0.0420348 -0.0553457 -0.441232 0.0517211 -0.0467584 -0.440904 0.0457362 -0.0455962 -0.440401 0.0424778 -0.0456141 -0.440894 0.0392945 -0.0422011 -0.438372 0.0422552 -0.0521512 -0.434717 0.0356865 -0.0554434 -0.436157 0.0358524 -0.0522785 -0.438242 0.0327224 -0.0456588 -0.439045 0.0359725 -0.0456448 -0.436179 0.0388562 -0.0553974 -0.437349 0.0390551 -0.0522181 -0.439774 0.0392239 -0.0456302 -0.441054 0.0328354 -0.0386222 -0.442248 0.032933 -0.0349578 -0.432099 0.0262184 -0.052447 -0.434419 0.0262216 -0.0491371 -0.436589 0.032698 -0.0490547 -0.447466 -4.19898e-08 -0.00140605 -0.443708 0.0522588 -0.0344428 -0.444351 0.0524105 -0.0309698 -0.445337 0.0399027 -0.0235722 -0.446455 0.0530144 -0.0171385 -0.447099 0.0533089 -0.0103927 -0.446497 0.0401291 -0.0158756 -0.44716 0.0134343 -0.00803818 -0.433468 0.0294353 -0.0523912 -0.433106 0.0325214 -0.0554863 -0.434842 0.0326461 -0.0523355 -0.436572 0.0262207 -0.0456863 -0.439729 0.032762 -0.0421845 -0.438464 0.02624 -0.0421685 -0.441547 0.026359 -0.0349332 -0.43865 0.0131753 -0.0385267 -0.436527 0.0131634 -0.0421355 -0.433505 0.00659975 -0.0457662 -0.43043 0.00662484 -0.0493709 -0.427382 0.00996312 -0.0527147 -0.442573 0.0459816 -0.0386913 -0.444137 0.0462641 -0.0312264 -0.442289 0.0426847 -0.0386715 -0.44193 0.039395 -0.0386538 -0.443322 0.0330427 -0.0312066 -0.442813 0.0264404 -0.0311978 -0.440469 0.0131988 -0.0348803 -0.442032 0.0132296 -0.0311782 -0.438361 0.00659024 -0.0384963 -0.438457 -4.19898e-08 -0.0382312 -0.43614 0.00658893 -0.0421205 -0.436892 -4.19898e-08 -0.0408574 -0.432348 -4.19898e-08 -0.0470801 -0.427054 0.0066651 -0.0527569 -0.421044 0.0103876 -0.058235 -0.447473 -4.19898e-08 -0.000264971 -0.4321 -0.0262185 -0.0524456 -0.42975 -0.0261845 -0.0555688 -0.439936 -0.0500012 -0.0524443 -0.442573 -0.0459817 -0.0386902 -0.444137 -0.0462642 -0.0312254 -0.446797 -0.053154 -0.013943 -0.420362 -0.00279765 -0.058235 -0.420588 -0.00712313 -0.058235 -0.429656 -0.0291721 -0.058235 -0.436179 -0.0388564 -0.055396 -0.433841 -0.035948 -0.058235 -0.440904 -0.0457363 -0.045595 -0.43983 -0.0486836 -0.0519938 -0.427918 -0.0132398 -0.0526655 -0.427383 -0.00996318 -0.0527133 -0.427056 -0.00666516 -0.0527555 -0.426984 -4.19898e-08 -0.052698 -0.424107 -0.0196 -0.058235 -0.426749 -0.0197945 -0.0556535 -0.428165 -0.0229995 -0.0556111 -0.428674 -0.016502 -0.0526131 -0.434022 -0.0131675 -0.0457406 -0.438362 -0.00659032 -0.0384952 -0.438651 -0.0131754 -0.0385256 -0.436528 -0.0131634 -0.0421342 -0.431111 -0.0131916 -0.0493 -0.430431 -0.00662491 -0.0493695 -0.433506 -0.00659982 -0.0457649 -0.436141 -0.00658902 -0.0421193 -0.444506 -0.0132954 -0.0235892 -0.444874 -0.0266002 -0.0235782 -0.445116 -0.0332536 -0.0235749 -0.443792 -0.0396492 -0.0312145 -0.446497 -0.0401292 -0.0158751 -0.446326 -0.0267449 -0.0158535 -0.445337 -0.0399028 -0.0235715 -0.443323 -0.0330428 -0.0312056 -0.438449 -0.0452306 -0.0552851 -0.437349 -0.0390553 -0.0522167 -0.439045 -0.0359726 -0.0456436 -0.441547 -0.0263591 -0.0349322 -0.43442 -0.0262217 -0.0491358 -0.436572 -0.0262208 -0.045685 -0.438242 -0.0327225 -0.0456575 -0.439729 -0.0327621 -0.0421833 -0.442248 -0.0329331 -0.0349568 -0.441054 -0.0328355 -0.0386211 -0.43659 -0.0326981 -0.0490533 -0.434843 -0.0326463 -0.0523341 -0.437435 -0.042035 -0.0553442 -0.438373 -0.0422553 -0.0521498 -0.439203 -0.0454591 -0.0520746 -0.440401 -0.0424779 -0.0456129 -0.44229 -0.0426848 -0.0386704 -0.443914 -0.0523065 -0.0333521 -0.447473 -0.0537512 -0.000264971 -0.447187 -0.0268864 -0.00807397 -0.447473 -0.0272006 -0.000264971 -0.447473 -0.0270369 -0.000264971 -0.447473 -0.0135184 -0.000264971 -0.425718 -0.0227067 -0.058235 -0.429647 -0.0197529 -0.052558 -0.43248 -0.019721 -0.0492192 -0.438465 -0.0262401 -0.0421673 -0.435079 -0.0197057 -0.0457131 -0.437333 -0.0197121 -0.0421507 -0.440106 -0.026289 -0.0385903 -0.439257 -0.0197403 -0.0385582 -0.441776 -4.19898e-08 -0.0313427 -0.433107 -0.0325216 -0.0554849 -0.433469 -0.0294354 -0.0523898 -0.436157 -0.0358525 -0.0522771 -0.434717 -0.0356866 -0.0554419 -0.439774 -0.039224 -0.0456289 -0.440895 -0.0392947 -0.0421999 -0.44193 -0.0393951 -0.0386527 -0.442813 -0.0264405 -0.0311969 -0.44047 -0.0131989 -0.0348792 -0.442032 -0.0132296 -0.0311773 -0.446192 -0.0133619 -0.0158381 -0.44716 -0.0134344 -0.00803794 -0.446328 -4.19898e-08 -0.0148337 -0.446873 -4.19898e-08 -0.0108705 -0.420579 -0.00745713 0.057705 -0.437181 -0.0456662 0.0575505 -0.433787 -0.0382274 0.057705 -0.43534 -0.0412966 0.057705 -0.435684 -0.0420386 0.057705 -0.431548 -0.0342623 0.057705 -0.428229 -0.0247415 0.055084 -0.427895 -0.0280836 0.057705 -0.429823 -0.0281818 0.0550494 -0.42226 -0.016 0.057705 -0.426802 -0.0212819 0.0551193 -0.429657 -0.021296 0.0520441 -0.427365 -0.0107268 0.0522019 -0.421816 -0.0144848 0.057705 -0.44656 -0.0544476 0.015687 -0.4465 -0.041272 0.0153173 -0.445667 -0.0547458 0.0225164 -0.442857 -0.0554376 0.03836 -0.439237 -0.0490682 0.0515532 -0.439815 -0.0536361 0.0525022 -0.439954 -0.0539829 0.0519678 -0.440385 -0.0548774 0.0501896 -0.438496 -0.0487349 0.0548035 -0.437494 -0.045292 0.0548592 -0.437393 -0.0421579 0.0517042 -0.433188 -0.0350287 0.0549819 -0.43625 -0.0418659 0.0549066 -0.436604 -0.0352204 0.0485457 -0.438601 -0.0421838 0.0484296 -0.438259 -0.0350985 0.0451555 -0.439803 -0.0420755 0.0451021 -0.431504 -0.0316087 0.0550156 -0.434891 -0.0352355 0.0518234 -0.434406 -0.028237 0.0486547 -0.440134 -0.0279281 0.0380878 -0.442576 -0.0488608 0.0382863 -0.44195 -0.0418595 0.0382138 -0.444138 -0.0486335 0.0307617 -0.443799 -0.0416788 0.0307382 -0.441081 -0.0348862 0.0381497 -0.44177 -0.0489636 0.0417517 -0.440933 -0.0490613 0.0450408 -0.441268 -0.0557384 0.0461544 -0.440071 -0.0491355 0.0482906 -0.440928 -0.0419589 0.0417149 -0.439767 -0.0349798 0.0416825 -0.443331 -0.0347332 0.0307175 -0.44282 -0.0277924 0.0306974 -0.421043 -0.0110095 0.057705 -0.427034 -0.00717293 0.0522453 -0.420379 -0.00380252 0.057705 -0.426917 -4.19898e-08 0.0522294 -0.43031 -0.00712287 0.048969 -0.446325 -0.0275084 0.0153266 -0.444497 -0.0138235 0.0230963 -0.444874 -0.027657 0.0230571 -0.442034 -0.0139058 0.0306549 -0.442361 -0.0208515 0.0306766 -0.436549 -0.0140483 0.0415884 -0.435039 -0.021127 0.0452575 -0.432427 -0.0212278 0.0487643 -0.428672 -0.0177838 0.0520996 -0.438683 -0.0139951 0.0379608 -0.438403 -0.00700042 0.0378982 -0.436164 -0.00703134 0.0415581 -0.433952 -0.0141127 0.0453083 -0.427906 -0.0142615 0.0521529 -0.43102 -0.0141916 0.0488722 -0.43341 -0.00707151 0.0453561 -0.441859 -4.19898e-08 0.0306102 -0.441879 -0.00695373 0.0306329 -0.442201 -4.19898e-08 0.0297491 -0.446186 -0.0137435 0.0153425 -0.447153 -4.19898e-08 0.00750275 -0.447381 -4.19898e-08 0.0039099 -0.447223 -0.0410413 0.00757215 -0.447187 -0.0273536 0.00754587 -0.445344 -0.0414864 0.0230224 -0.438498 -0.0280124 0.0416514 -0.439285 -0.0209693 0.0380248 -0.436564 -0.0281195 0.0452064 -0.437359 -0.0210402 0.04162 -0.432134 -0.0282857 0.051933 -0.425281 -0.0232955 0.057705 -0.440135 0.0279309 0.0380874 -0.421395 0.0127786 0.057705 -0.43785 0.0475509 0.0570861 -0.437496 0.0452965 0.0548585 -0.444138 0.0486383 0.0307613 -0.447223 0.0410454 0.00757205 -0.447473 0.0537511 -0.000264971 -0.437395 0.042162 0.0517035 -0.438498 0.0280152 0.0416509 -0.439768 0.0349833 0.041682 -0.43826 0.035102 0.0451549 -0.436565 0.0281222 0.0452058 -0.432136 0.0282884 0.0519323 -0.43319 0.0350322 0.0549812 -0.4438 0.041683 0.0307378 -0.442576 0.0488657 0.0382859 -0.440929 0.0419631 0.0417144 -0.439804 0.0420797 0.0451015 -0.440072 0.0491403 0.0482899 -0.439238 0.0490731 0.0515524 -0.439735 0.0534242 0.0528006 -0.438497 0.0487398 0.0548028 -0.446795 0.0543486 0.0134218 -0.434892 0.0352389 0.0518227 -0.438603 0.0421879 0.0484289 -0.436606 0.0352238 0.0485451 -0.441951 0.0418637 0.0382133 -0.441082 0.0348896 0.0381492 -0.443331 0.0347366 0.0307171 -0.44468 -4.19898e-08 0.0221096 -0.446186 0.0137448 0.0153423 -0.446149 -4.19898e-08 0.0153692 -0.446512 -4.19898e-08 0.013104 -0.444497 0.0138249 0.023096 -0.446325 0.0275111 0.0153263 -0.444874 0.0276598 0.0230568 -0.4465 0.041276 0.0153171 -0.445344 0.0414905 0.0230221 -0.443738 0.0552386 0.0338045 -0.441771 0.0489685 0.0417512 -0.441471 0.0557353 0.0451816 -0.440934 0.0490661 0.0450403 -0.441053 0.055657 0.0471698 -0.440629 0.0552515 0.0491169 -0.4402 0.0545289 0.0509723 -0.427035 0.00717356 0.0522447 -0.427366 0.0107278 0.0522014 -0.420346 -4.19898e-08 0.057705 -0.430086 -4.19898e-08 0.049093 -0.434984 -4.19898e-08 0.0431568 -0.438403 0.00700104 0.0378978 -0.441879 0.00695435 0.0306325 -0.426803 0.021284 0.0551187 -0.42823 0.0247439 0.0550834 -0.438683 0.0139964 0.0379603 -0.43655 0.0140497 0.0415879 -0.436165 0.00703197 0.0415576 -0.433411 0.00707213 0.0453555 -0.433952 0.0141141 0.0453077 -0.430311 0.0071235 0.0489684 -0.431021 0.0141929 0.0488715 -0.428673 0.0177855 0.052099 -0.427907 0.0142628 0.0521523 -0.422328 0.0162146 0.057705 -0.447187 0.0273563 0.00754578 -0.447473 0.0397758 -0.000264971 -0.438834 -4.19898e-08 0.0370192 -0.442034 0.0139071 0.0306545 -0.442361 0.0208535 0.0306762 -0.44282 0.0277951 0.0306971 -0.439286 0.0209714 0.0380243 -0.437359 0.0210422 0.0416195 -0.43504 0.021129 0.0452569 -0.432428 0.0212299 0.0487637 -0.434407 0.0282398 0.048654 -0.429658 0.021298 0.0520435 -0.429825 0.0281846 0.0550488 -0.431506 0.0316118 0.055015 -0.434671 0.0399263 0.057705 -0.436252 0.0418701 0.0549059 -0.437018 -0.0170561 -0.077765 -0.436673 -0.00330004 -0.077765 -0.443729 -0.0103453 -0.077765 -0.438323 -0.00285793 -0.077765 -0.43332 -0.0179558 -0.077765 -0.406452 -0.0132389 -0.077765 -0.439531 0.00164996 -0.077765 -0.444673 0.00559996 -0.077765 -0.438323 0.00285784 -0.077765 -0.433815 -0.00165004 -0.077765 -0.435023 -0.00285793 -0.077765 -0.415323 0.00285784 -0.077765 -0.435023 0.00285784 -0.077765 -0.43332 0.0179557 -0.077765 -0.436673 0.00329996 -0.077765 -0.441041 0.0143681 -0.077765 -0.413673 0.00329996 -0.077765 -0.224315 -0.00165004 -0.077765 -0.17999 -0.000500042 -0.077765 -0.18869 -4.19898e-08 -0.077765 -0.19034 -0.00285793 -0.077765 -0.180742 -0.0048583 -0.077765 -0.189132 0.00164996 -0.077765 -0.180742 0.00485822 -0.077765 -0.182912 0.00871205 -0.077765 -0.19034 0.00285784 -0.077765 -0.186248 0.0116154 -0.077765 -0.19199 0.00329996 -0.077765 -0.412023 -0.00285793 -0.077765 -0.410815 -0.00165004 -0.077765 -0.378158 -0.0101716 -0.077765 -0.410373 -4.19898e-08 -0.077765 -0.227173 -0.00330004 -0.077765 -0.264844 -0.0169784 -0.077765 -0.292936 -0.0124221 -0.077765 -0.349722 -0.00901101 -0.077765 -0.378158 0.0101715 -0.077765 -0.349722 0.00901093 -0.077765 -0.321272 0.0097622 -0.077765 -0.230031 0.00164996 -0.077765 -0.230473 -4.19898e-08 -0.077765 -0.227173 0.00329996 -0.077765 -0.224315 0.00164996 -0.077765 -0.19529 -4.19898e-08 -0.077765 -0.194847 -0.00165004 -0.077765 -0.223873 -4.19898e-08 -0.077765 -0.19364 -0.00285793 -0.077765 -0.19199 -0.00330004 -0.077765 -0.251167 -0.0240128 -0.084765 -0.251167 -0.0240128 -0.081765 -0.247173 -0.0245 -0.084765 -0.311985 -0.0144362 -0.081765 -0.311985 -0.0144362 -0.084765 -0.342757 -0.0130183 -0.081765 -0.342757 -0.0130183 -0.084765 -0.404198 -0.0169616 -0.081765 -0.37786 -0.0141606 -0.081765 -0.37355 -0.0138616 -0.084765 -0.37355 -0.0138616 -0.081765 -0.40589 -0.0171824 -0.0817483 -0.404198 -0.0169616 -0.084765 -0.419277 -0.018 -0.084765 -0.444673 -0.00560004 -0.077765 -0.444673 0.00559996 -0.084765 -0.419277 0.018 -0.0804563 -0.419277 0.018 -0.084765 -0.404198 0.0169615 -0.084765 -0.37786 0.0141605 -0.081765 -0.37355 0.0138615 -0.081765 -0.342757 0.0130182 -0.081765 -0.342757 0.0130182 -0.084765 -0.265616 0.0209029 -0.081765 -0.251167 0.0240127 -0.084765 -0.293444 0.0163897 -0.081765 -0.243167 0.0241179 -0.084765 -0.247173 0.0245 -0.0813113 -0.190365 0.0132322 -0.077765 -0.238262 0.0231066 -0.077765 -0.190365 0.0132322 -0.084765 -0.243167 0.0241179 -0.0799742 -0.17999 0.000499958 -0.084765 -0.17999 0.000499958 -0.077765 -0.17999 -0.000500042 -0.084765 -0.182912 -0.00871213 -0.077765 -0.180742 -0.0048583 -0.084765 -0.182912 -0.00871213 -0.084765 -0.186248 -0.0116155 -0.077765 -0.190365 -0.0132323 -0.077765 -0.238262 -0.0231067 -0.077765 -0.243167 -0.024118 -0.0799742 -0.439873 0.00554252 -0.085765 -0.440334 0.013661 -0.085765 -0.442216 0.00319996 -0.085765 -0.443073 -4.19898e-08 -0.085765 -0.443673 -0.00560004 -0.085765 -0.439873 -0.0055426 -0.085765 -0.432273 0.017 -0.085765 -0.433473 0.00554252 -0.085765 -0.419277 0.017 -0.085765 -0.420073 -4.19898e-08 -0.085765 -0.430273 -4.19898e-08 -0.085765 -0.419216 0.00319996 -0.085765 -0.419216 -0.00320004 -0.085765 -0.416873 -0.0055426 -0.085765 -0.186767 0.0107604 -0.085765 -0.183687 0.00808035 -0.085765 -0.419277 -0.017 -0.085765 -0.436673 -0.00640004 -0.085765 -0.440334 -0.0136611 -0.085765 -0.413673 -0.00640004 -0.085765 -0.233573 -4.19898e-08 -0.085765 -0.232716 -0.00320004 -0.085765 -0.227173 0.00639996 -0.085765 -0.230373 0.00554252 -0.085765 -0.25094 0.023039 -0.085765 -0.232716 0.00319996 -0.085765 -0.311903 0.0134395 -0.085765 -0.342748 0.0120183 -0.085765 -0.373614 0.0128636 -0.085765 -0.408131 0.00319996 -0.085765 -0.404335 0.0159709 -0.085765 -0.410473 0.00554252 -0.085765 -0.311903 -0.0134396 -0.085765 -0.342748 -0.0120184 -0.085765 -0.408131 -0.00320004 -0.085765 -0.410473 -0.0055426 -0.085765 -0.181684 0.00452297 -0.085765 -0.186447 -0.00320004 -0.085765 -0.197532 0.00319996 -0.085765 -0.19199 -0.00640004 -0.085765 -0.186767 -0.0107604 -0.085765 -0.197532 -0.00320004 -0.085765 -0.19839 -4.19898e-08 -0.085765 -0.221631 -0.00320004 -0.085765 -0.230373 -0.0055426 -0.085765 -0.432273 -0.018 -0.084765 -0.432273 -0.018 -0.0780212 -0.437018 -0.0170561 -0.084765 -0.441041 -0.0143682 -0.077765 -0.441041 -0.0143682 -0.084765 -0.443729 -0.0103453 -0.084765 -0.432273 0.018 -0.084765 -0.437018 0.0170561 -0.077765 -0.441041 0.0143681 -0.084765 -0.443729 0.0103452 -0.077765 -0.19364 -0.00285793 -0.082665 -0.19529 -4.19898e-08 -0.082665 -0.194847 0.00164996 -0.077765 -0.19364 0.00285784 -0.077765 -0.194847 0.00164996 -0.082665 -0.19364 0.00285784 -0.082665 -0.19199 0.00329996 -0.082665 -0.19034 0.00285784 -0.082665 -0.18869 -4.19898e-08 -0.082665 -0.189132 -0.00165004 -0.077765 -0.19199 -0.00330004 -0.082665 -0.194847 -0.00165004 -0.082665 -0.19519 -0.0055426 -0.085765 -0.19519 0.00554252 -0.085765 -0.19199 0.00639996 -0.085765 -0.18879 0.00554252 -0.085765 -0.189132 0.00164996 -0.082665 -0.186447 0.00319996 -0.085765 -0.18559 -4.19898e-08 -0.085765 -0.189132 -0.00165004 -0.082665 -0.19034 -0.00285793 -0.082665 -0.18879 -0.0055426 -0.085765 -0.228823 -0.00285793 -0.077765 -0.230031 -0.00165004 -0.077765 -0.228823 -0.00285793 -0.082665 -0.230031 -0.00165004 -0.082665 -0.230473 -4.19898e-08 -0.082665 -0.230031 0.00164996 -0.082665 -0.228823 0.00285784 -0.077765 -0.225523 0.00285784 -0.077765 -0.225523 0.00285784 -0.082665 -0.223873 -4.19898e-08 -0.082665 -0.224315 -0.00165004 -0.082665 -0.225523 -0.00285793 -0.077765 -0.227173 -0.00330004 -0.082665 -0.228823 0.00285784 -0.082665 -0.227173 0.00329996 -0.082665 -0.223973 0.00554252 -0.085765 -0.224315 0.00164996 -0.082665 -0.221631 0.00319996 -0.085765 -0.220773 -4.19898e-08 -0.085765 -0.225523 -0.00285793 -0.082665 -0.223973 -0.0055426 -0.085765 -0.227173 -0.00640004 -0.085765 -0.413673 -0.00330004 -0.077765 -0.415323 -0.00285793 -0.077765 -0.415323 -0.00285793 -0.082665 -0.416531 -0.00165004 -0.077765 -0.416531 -0.00165004 -0.082665 -0.416973 -4.19898e-08 -0.082665 -0.416973 -4.19898e-08 -0.077765 -0.416531 0.00164996 -0.077765 -0.416531 0.00164996 -0.082665 -0.412023 0.00285784 -0.077765 -0.410815 0.00164996 -0.077765 -0.412023 0.00285784 -0.082665 -0.410815 0.00164996 -0.082665 -0.410373 -4.19898e-08 -0.082665 -0.412023 -0.00285793 -0.082665 -0.420073 -4.19898e-08 -0.085765 -0.415323 0.00285784 -0.082665 -0.416873 0.00554252 -0.085765 -0.413673 0.00639996 -0.085765 -0.413673 0.00329996 -0.082665 -0.407273 -4.19898e-08 -0.085765 -0.410815 -0.00165004 -0.082665 -0.413673 -0.00330004 -0.082665 -0.439531 -0.00165004 -0.077765 -0.438323 -0.00285793 -0.082665 -0.439973 -4.19898e-08 -0.077765 -0.439973 -4.19898e-08 -0.082665 -0.438323 0.00285784 -0.082665 -0.433815 0.00164996 -0.077765 -0.433373 -4.19898e-08 -0.077765 -0.433373 -4.19898e-08 -0.082665 -0.439531 -0.00165004 -0.082665 -0.442216 -0.00320004 -0.085765 -0.439531 0.00164996 -0.082665 -0.436673 0.00329996 -0.082665 -0.435023 0.00285784 -0.082665 -0.436673 0.00639996 -0.085765 -0.433815 0.00164996 -0.082665 -0.431131 0.00319996 -0.085765 -0.431131 -0.00320004 -0.085765 -0.433815 -0.00165004 -0.082665 -0.435023 -0.00285793 -0.082665 -0.433473 -0.0055426 -0.085765 -0.436673 -0.00330004 -0.082665 -0.373614 -0.0128637 -0.085765 -0.281401 -0.0181076 -0.084765 -0.281245 -0.0171198 -0.085765 -0.404335 -0.015971 -0.085765 -0.243369 -0.0231386 -0.085765 -0.24716 -0.0235001 -0.085765 -0.25094 -0.0230391 -0.085765 -0.190567 -0.0122529 -0.085765 -0.243167 -0.024118 -0.084765 -0.432273 -0.017 -0.085765 -0.436636 -0.0161323 -0.085765 -0.442805 -0.00996263 -0.085765 -0.444673 -0.00560004 -0.084765 -0.18099 -0.000500042 -0.085765 -0.181684 -0.00452305 -0.085765 -0.183687 -0.00808043 -0.085765 -0.186248 -0.0116155 -0.084765 -0.190365 -0.0132323 -0.084765 -0.18099 0.000499958 -0.085765 -0.443673 0.00559996 -0.085765 -0.443729 0.0103452 -0.084765 -0.442805 0.00996255 -0.085765 -0.437018 0.0170561 -0.084765 -0.436636 0.0161322 -0.085765 -0.186248 0.0116154 -0.084765 -0.182912 0.00871205 -0.084765 -0.180742 0.00485822 -0.084765 -0.190567 0.0122528 -0.085765 -0.247173 0.0245 -0.084765 -0.24716 0.0235 -0.085765 -0.243369 0.0231385 -0.085765 -0.281401 0.0181075 -0.084765 -0.311985 0.0144361 -0.084765 -0.281245 0.0171197 -0.085765 -0.37355 0.0138615 -0.084765 -0.412591 0.0177966 -0.081357 -0.432273 0.018 -0.0780212 -0.404198 0.0169615 -0.081765 -0.406452 0.0132388 -0.077765 -0.251167 0.0240127 -0.081765 -0.264844 0.0169783 -0.077765 -0.281401 0.0181075 -0.081765 -0.292936 0.012422 -0.077765 -0.311985 0.0144361 -0.081765 -0.321511 0.013755 -0.081765 -0.349693 0.0130108 -0.081765 -0.419277 -0.018 -0.0804563 -0.247173 -0.0245 -0.0813113 -0.412591 -0.0177967 -0.081357 -0.349693 -0.0130109 -0.081765 -0.321272 -0.00976229 -0.077765 -0.321511 -0.0137551 -0.081765 -0.293444 -0.0163898 -0.081765 -0.281401 -0.0181076 -0.081765 -0.265616 -0.020903 -0.081765 -0.13919 -0.03426 -0.083265 -0.13919 -0.03426 -0.084465 0.156943 0.03306 -0.083265 0.156943 0.03306 -0.084465 0.156943 0.02865 -0.083265 0.156943 0.02865 -0.084465 -0.13919 0.02865 -0.083265 -0.13919 0.02745 -0.083265 -0.13919 0.02745 -0.084465 -0.13919 0.02304 -0.083265 0.156943 0.02304 -0.084465 -0.13919 0.01743 -0.083265 0.156943 0.01743 -0.084465 0.156943 0.01623 -0.083265 0.156943 0.01623 -0.084465 -0.13919 0.01062 -0.083265 0.156943 0.00620996 -0.084465 -0.13919 0.00620996 -0.084465 -0.13919 0.00500996 -0.084465 0.156943 0.00500996 -0.083265 0.156943 0.00500996 -0.084465 -0.13919 0.000599958 -0.084465 -0.13919 -0.000600042 -0.084465 0.156943 -0.02184 -0.083265 -0.13919 -0.02184 -0.083265 -0.13919 -0.02184 -0.084465 0.156943 -0.02745 -0.083265 0.156943 -0.01062 -0.084465 0.156943 -0.00621004 -0.083265 -0.13919 -0.00621004 -0.084465 0.159143 -0.0589 -0.084465 0.159143 -0.0592 -0.084465 0.159143 -0.0589 -0.083265 -0.16149 -0.0589 -0.084465 0.159143 -0.04207 -0.083265 0.159143 -0.04208 -0.083265 -0.16149 -0.04208 -0.083265 -0.16149 -0.04207 -0.083265 0.159143 -0.04769 -0.083265 0.159143 -0.03646 -0.084465 0.159143 -0.03646 -0.083265 0.159143 -0.02525 -0.084465 0.159143 -0.01963 -0.084465 0.159143 -0.01964 -0.084465 0.159143 -0.01964 -0.083265 0.159143 0.00280996 -0.083265 0.159143 0.00279996 -0.083265 0.159143 0.01963 -0.084465 0.159143 0.02525 -0.083265 0.159143 0.03086 -0.084465 0.159143 0.04207 -0.084465 -0.16149 0.04208 -0.084465 -0.16149 0.04208 -0.083265 0.159143 0.03647 -0.084465 0.159143 0.03646 -0.083265 0.159143 0.04768 -0.084465 0.159143 0.05329 -0.084465 0.159143 0.0533 -0.083265 -0.16149 0.05329 -0.083265 -0.16149 0.0533 -0.084465 -0.16149 0.0533 -0.083265 -0.120178 -0.076 -0.083265 -0.17284 -0.076 -0.083265 0.170493 -0.076 -0.084465 -0.0606758 -0.076 -0.083265 0.170493 0.076 -0.084465 -0.17284 0.076 -0.083265 -0.0606758 0.076 -0.083265 -0.0011732 0.076 -0.083265 0.0583294 0.076 -0.083265 0.117832 0.076 -0.083265 0.186525 0.0282 -0.083265 0.186043 0.03 -0.083265 0.185659 0.0277 -0.084265 0.185659 0.0323 -0.084265 0.187843 0.0331176 -0.083265 0.187343 0.0339837 -0.084265 0.189643 0.0346 -0.084265 0.191443 0.0331176 -0.083265 0.192761 0.0318 -0.083265 0.194243 0.03 -0.084265 0.186043 -0.03 -0.083265 0.186525 -0.0282 -0.083265 0.187843 -0.0268824 -0.083265 0.191943 -0.0260163 -0.084265 0.191443 -0.0268824 -0.083265 0.193627 -0.0277 -0.084265 0.189643 -0.0336 -0.083265 0.191943 -0.0339838 -0.084265 -0.195107 0.0282 -0.083265 -0.195973 0.0277 -0.084265 -0.19379 0.0331176 -0.083265 -0.19199 0.0346 -0.084265 -0.19019 0.0331176 -0.083265 -0.188006 0.0323 -0.084265 -0.188872 0.0282 -0.083265 -0.18739 0.03 -0.084265 -0.19019 0.0268823 -0.083265 -0.18969 0.0260162 -0.084265 -0.195107 -0.0318 -0.083265 -0.19659 -0.03 -0.084265 -0.195107 -0.0282 -0.083265 -0.19379 -0.0268824 -0.083265 -0.19199 -0.0264 -0.083265 -0.19019 -0.0268824 -0.083265 -0.188006 -0.0277 -0.084265 -0.18839 -0.03 -0.083265 -0.18739 -0.03 -0.084265 -0.188872 -0.0318 -0.083265 -0.19019 -0.0331177 -0.083265 -0.18969 -0.0339838 -0.084265 -0.19429 -0.0339838 -0.084265 0.204809 0.0692 -0.083265 0.204327 0.071 -0.083265 0.203943 0.0687 -0.084265 0.204809 0.0728 -0.083265 0.206127 0.0741177 -0.083265 0.207927 0.0756 -0.084265 0.211044 0.0728 -0.083265 0.211911 0.0733 -0.084265 0.211911 0.0687 -0.084265 0.207927 0.0674 -0.083265 0.206127 0.0678823 -0.083265 -0.213391 0.0692 -0.083265 -0.214257 0.0687 -0.084265 -0.213391 0.0728 -0.083265 -0.214257 0.0733 -0.084265 -0.212573 0.0749837 -0.084265 -0.207156 0.0728 -0.083265 -0.206289 0.0733 -0.084265 -0.206673 0.071 -0.083265 -0.207156 0.0692 -0.083265 -0.208473 0.0678823 -0.083265 0.206127 -0.0741177 -0.083265 0.205627 -0.0749838 -0.084265 0.204809 -0.0728 -0.083265 0.204327 -0.071 -0.083265 0.203327 -0.071 -0.084265 0.204809 -0.0692 -0.083265 0.203943 -0.0687 -0.084265 0.206127 -0.0678824 -0.083265 0.205627 -0.0670163 -0.084265 0.207927 -0.0674 -0.083265 0.207927 -0.0664 -0.084265 0.210227 -0.0670163 -0.084265 0.211911 -0.0687 -0.084265 0.211044 -0.0692 -0.083265 0.211527 -0.071 -0.083265 0.211911 -0.0733 -0.084265 0.209727 -0.0741177 -0.083265 0.210227 -0.0749838 -0.084265 0.207927 -0.0756 -0.084265 -0.213873 -0.071 -0.083265 -0.214257 -0.0687 -0.084265 -0.213391 -0.0692 -0.083265 -0.212073 -0.0678824 -0.083265 -0.212573 -0.0670163 -0.084265 -0.207973 -0.0670163 -0.084265 -0.206673 -0.071 -0.083265 -0.207156 -0.0728 -0.083265 -0.206289 -0.0733 -0.084265 -0.208473 -0.0741177 -0.083265 -0.207973 -0.0749838 -0.084265 -0.210273 -0.0756 -0.084265 -0.128433 0.0678823 -0.083265 -0.128933 0.0670162 -0.084265 -0.129751 0.0692 -0.083265 -0.130233 0.071 -0.083265 -0.129751 0.0728 -0.083265 -0.128933 0.0749837 -0.084265 -0.126633 0.0756 -0.084265 -0.124333 0.0749837 -0.084265 -0.122649 0.0733 -0.084265 -0.122033 0.071 -0.084265 -0.122649 0.0687 -0.084265 -0.124333 0.0670162 -0.084265 -0.0452932 0.0670162 -0.084265 -0.0469769 0.0687 -0.084265 -0.0469769 0.0733 -0.084265 -0.0447932 0.0741177 -0.083265 -0.0452932 0.0749837 -0.084265 -0.0429932 0.0756 -0.084265 -0.0406932 0.0749837 -0.084265 -0.0411932 0.0741177 -0.083265 -0.0398755 0.0728 -0.083265 -0.0393932 0.071 -0.083265 -0.0390095 0.0733 -0.084265 -0.0383932 0.071 -0.084265 -0.0398755 0.0692 -0.083265 -0.0390095 0.0687 -0.084265 -0.0411932 0.0678823 -0.083265 -0.0406932 0.0670162 -0.084265 0.0375291 0.0692 -0.083265 0.0370468 0.071 -0.083265 0.0375291 0.0728 -0.083265 0.0388468 0.0741177 -0.083265 0.0383468 0.0749837 -0.084265 0.0429468 0.0749837 -0.084265 0.0424468 0.0741177 -0.083265 0.0446305 0.0733 -0.084265 0.0437645 0.0728 -0.083265 0.0446305 0.0687 -0.084265 0.0406468 0.0664 -0.084265 0.0406468 0.0674 -0.083265 0.121169 0.0692 -0.083265 0.120687 0.071 -0.083265 0.119687 0.071 -0.084265 0.121169 0.0728 -0.083265 0.120303 0.0733 -0.084265 0.121987 0.0749837 -0.084265 0.124287 0.0746 -0.083265 0.124287 0.0756 -0.084265 0.128271 0.0733 -0.084265 0.128887 0.071 -0.084265 0.128271 0.0687 -0.084265 0.126087 0.0678823 -0.083265 0.126587 0.0670162 -0.084265 0.124287 0.0664 -0.084265 0.122487 -0.0741177 -0.083265 0.120303 -0.0733 -0.084265 0.120687 -0.071 -0.083265 0.121169 -0.0692 -0.083265 0.120303 -0.0687 -0.084265 0.121987 -0.0670163 -0.084265 0.128271 -0.0687 -0.084265 0.127887 -0.071 -0.083265 0.126087 -0.0741177 -0.083265 0.124287 -0.0756 -0.084265 0.121987 -0.0749838 -0.084265 0.0375291 -0.0728 -0.083265 0.0370468 -0.071 -0.083265 0.0375291 -0.0692 -0.083265 0.0366631 -0.0687 -0.084265 0.0383468 -0.0670163 -0.084265 0.0429468 -0.0670163 -0.084265 0.0437645 -0.0692 -0.083265 0.0452468 -0.071 -0.084265 0.0442468 -0.071 -0.083265 0.0437645 -0.0728 -0.083265 0.0424468 -0.0741177 -0.083265 0.0388468 -0.0741177 -0.083265 0.0406468 -0.0756 -0.084265 0.0383468 -0.0749838 -0.084265 -0.0475932 -0.071 -0.084265 -0.0452932 -0.0670163 -0.084265 -0.0429932 -0.0674 -0.083265 -0.0411932 -0.0678824 -0.083265 -0.0406932 -0.0670163 -0.084265 -0.0398755 -0.0692 -0.083265 -0.0390095 -0.0687 -0.084265 -0.0398755 -0.0728 -0.083265 -0.0390095 -0.0733 -0.084265 -0.0411932 -0.0741177 -0.083265 -0.0406932 -0.0749838 -0.084265 -0.128933 -0.0749838 -0.084265 -0.129751 -0.0728 -0.083265 -0.130233 -0.071 -0.083265 -0.130617 -0.0687 -0.084265 -0.128933 -0.0670163 -0.084265 -0.124833 -0.0678824 -0.083265 -0.122649 -0.0687 -0.084265 -0.123033 -0.071 -0.083265 -0.122033 -0.071 -0.084265 -0.123516 -0.0728 -0.083265 -0.126633 -0.0746 -0.083265 -0.124333 -0.0749838 -0.084265 -0.126633 -0.0756 -0.084265 0.159143 0.0592 -0.083265 0.159143 0.0589 -0.084465 0.156943 0.04989 -0.083265 0.156943 0.03867 -0.083265 -0.15929 0.03987 -0.083265 -0.15929 0.04428 -0.084465 -0.15929 0.04548 -0.083265 0.156943 -0.04428 -0.084465 0.156943 -0.04989 -0.083265 -0.15929 -0.04989 -0.083265 -0.15929 -0.04989 -0.084465 -0.15929 -0.0555 -0.084465 0.209427 -0.0619 -0.084165 0.207877 -0.0614847 -0.083265 0.207877 -0.0614847 -0.084165 0.206742 -0.06035 -0.084165 0.206327 -0.0588 -0.084165 0.206742 -0.05725 -0.084165 0.209427 -0.0557 -0.084165 0.209427 -0.0557 -0.083265 0.210977 -0.0561154 -0.084165 0.212111 -0.05725 -0.084165 0.212527 -0.0588 -0.083265 0.212527 -0.0588 -0.084165 0.210977 -0.0614847 -0.083265 0.209427 -0.0619 -0.083265 0.209427 -0.0419 -0.083265 0.207877 -0.0414847 -0.083265 0.206742 -0.04035 -0.083265 0.207877 -0.0361154 -0.083265 0.209427 -0.0357 -0.083265 0.209427 -0.0357 -0.084165 0.210977 -0.0361154 -0.084165 0.212527 -0.0388 -0.083265 0.212527 -0.0388 -0.084165 0.212111 -0.04035 -0.083265 0.210977 -0.0414847 -0.084165 0.210977 -0.0414847 -0.083265 -0.211773 -0.0619 -0.083265 -0.214458 -0.06035 -0.084165 -0.214873 -0.0588 -0.084165 -0.214458 -0.05725 -0.083265 -0.213323 -0.0561154 -0.083265 -0.211773 -0.0557 -0.083265 -0.210223 -0.0561154 -0.083265 -0.209089 -0.05725 -0.083265 -0.209089 -0.05725 -0.084165 -0.208673 -0.0588 -0.084165 -0.209089 -0.06035 -0.083265 -0.210223 -0.0614847 -0.084165 -0.211773 -0.0419 -0.083265 -0.213323 -0.0414847 -0.083265 -0.211773 -0.0419 -0.084165 -0.214458 -0.04035 -0.083265 -0.213323 -0.0414847 -0.084165 -0.214458 -0.04035 -0.084165 -0.213323 -0.0361154 -0.083265 -0.213323 -0.0361154 -0.084165 -0.210223 -0.0361154 -0.083265 -0.210223 -0.0361154 -0.084165 -0.209089 -0.03725 -0.083265 -0.208673 -0.0388 -0.084165 -0.208673 -0.0388 -0.083265 0.207877 0.0561153 -0.083265 0.207877 0.0561153 -0.084165 0.206327 0.0588 -0.083265 0.206742 0.06035 -0.084165 0.209427 0.0619 -0.083265 0.209427 0.0619 -0.084165 0.210977 0.0614846 -0.083265 0.210977 0.0614846 -0.084165 0.212527 0.0588 -0.084165 0.209427 0.0557 -0.083265 0.210977 0.0561153 -0.084165 0.207877 0.0361153 -0.083265 0.209427 0.0357 -0.084165 0.206327 0.0388 -0.084165 0.207877 0.0414846 -0.083265 0.209427 0.0419 -0.083265 0.210977 0.0414846 -0.084165 0.212111 0.04035 -0.084165 0.212111 0.04035 -0.083265 0.212527 0.0388 -0.083265 0.212527 0.0388 -0.084165 0.212111 0.03725 -0.083265 0.212111 0.03725 -0.084165 0.210977 0.0361153 -0.084165 0.210977 0.0361153 -0.083265 -0.214458 0.05725 -0.083265 -0.214873 0.0588 -0.083265 -0.214873 0.0588 -0.084165 -0.214458 0.06035 -0.084165 -0.210223 0.0614846 -0.084165 -0.209089 0.06035 -0.083265 -0.208673 0.0588 -0.083265 -0.209089 0.05725 -0.083265 -0.209089 0.05725 -0.084165 -0.210223 0.0561153 -0.084165 -0.210223 0.0561153 -0.083265 -0.211773 0.0557 -0.083265 -0.211773 0.0557 -0.084165 -0.214458 0.03725 -0.084165 -0.214873 0.0388 -0.083265 -0.214458 0.04035 -0.083265 -0.214458 0.04035 -0.084165 -0.213323 0.0414846 -0.084165 -0.211773 0.0419 -0.083265 -0.210223 0.0414846 -0.083265 -0.210223 0.0414846 -0.084165 -0.209089 0.04035 -0.083265 -0.209089 0.04035 -0.084165 -0.208673 0.0388 -0.084165 -0.209089 0.03725 -0.084165 -0.211773 0.0357 -0.083265 -0.210223 0.0361153 -0.084165 -0.211773 0.0357 -0.084165 -0.175315 -0.0770252 -0.083265 -0.175315 -0.0770252 -0.084465 0.172968 -0.0770252 -0.083265 0.172968 -0.0770252 -0.084465 0.174857 -0.0789143 -0.083265 -0.174179 0.0762664 -0.083265 -0.17284 0.076 -0.084465 -0.174179 0.0762664 -0.084465 0.171833 0.0762664 -0.084465 0.171833 0.0762664 -0.083265 0.172968 0.0770251 -0.084465 0.172968 0.0770251 -0.083265 0.171833 -0.0762665 -0.083265 -0.14139 -0.03085 -0.084465 -0.14139 -0.01964 -0.083265 -0.14139 0.00279996 -0.084465 -0.14139 0.01403 -0.084465 -0.14139 0.02525 -0.084465 -0.14139 0.03086 -0.083265 -0.14139 0.03647 -0.083265 0.158848 0.00169996 -0.083265 0.158043 0.000894702 -0.083265 0.158043 0.000894702 -0.084465 0.159143 -0.00280004 -0.083265 0.158848 -0.00170004 -0.084465 0.158848 -0.00170004 -0.083265 0.156943 -0.000600042 -0.084465 0.156943 -0.000600042 -0.083265 0.159143 -0.00281004 -0.083265 0.158848 -0.00391004 -0.084465 0.158043 -0.0047153 -0.083265 0.158043 -0.0047153 -0.084465 0.159143 -0.00841004 -0.084465 0.158976 -0.00756814 -0.084465 0.158499 -0.00685441 -0.084465 0.158499 -0.00685441 -0.083265 0.156943 -0.00621004 -0.084465 -0.160131 0.0512574 -0.083265 -0.160131 0.0512574 -0.084465 -0.160845 0.0517343 -0.084465 -0.161322 0.0524481 -0.083265 -0.16149 0.05329 -0.084465 -0.15929 0.0555 -0.083265 -0.160131 0.0553325 -0.083265 -0.160845 0.0548556 -0.084465 -0.160845 0.0548556 -0.083265 -0.161322 0.0541419 -0.083265 0.158848 0.0544 -0.084465 0.156943 0.0555 -0.083265 0.158848 0.05219 -0.083265 0.158043 0.0513847 -0.083265 0.158043 0.0513847 -0.084465 -0.160131 0.0568674 -0.084465 -0.160131 0.0568674 -0.083265 -0.160845 0.0573443 -0.083265 -0.161322 0.0580581 -0.083265 -0.161322 0.0580581 -0.084465 -0.16149 0.0592 -0.083265 -0.161195 0.0603 -0.084465 -0.16039 0.0611052 -0.084465 -0.15929 0.0614 -0.083265 -0.15929 0.0614 -0.084465 0.156943 0.0614 -0.083265 0.157785 0.0612325 -0.083265 0.158976 0.0600419 -0.084465 0.159143 0.0589 -0.083265 0.158976 0.0580581 -0.083265 0.158499 0.0573443 -0.083265 0.157785 0.0568674 -0.083265 -0.160131 0.0456474 -0.084465 -0.160845 0.0461243 -0.083265 -0.160845 0.0461243 -0.084465 -0.161322 0.0468381 -0.083265 -0.161322 0.0468381 -0.084465 -0.16149 0.04768 -0.084465 -0.16039 0.0495952 -0.084465 -0.161195 0.04879 -0.083265 0.158976 0.0485319 -0.084465 0.158976 0.0485319 -0.083265 0.158499 0.0492456 -0.084465 0.157785 0.0497225 -0.084465 0.158848 0.04658 -0.084465 0.158499 0.0461243 -0.084465 0.158976 0.0468381 -0.083265 0.158043 0.0457747 -0.084465 0.158499 0.0461243 -0.083265 0.159143 0.03647 -0.083265 0.158976 0.0373119 -0.084465 0.158976 0.0373119 -0.083265 0.158499 0.0380256 -0.084465 0.157785 0.0385025 -0.084465 0.157785 0.0385025 -0.083265 0.157785 0.0344274 -0.083265 0.159143 0.04207 -0.083265 0.158848 0.04097 -0.083265 0.158848 0.04097 -0.084465 0.158043 0.0401647 -0.084465 -0.160845 0.0405143 -0.084465 -0.161322 0.0412281 -0.083265 -0.161322 0.0412281 -0.084465 -0.160845 0.0436356 -0.083265 0.159143 0.04208 -0.083265 0.158848 0.04318 -0.083265 0.158043 0.0439852 -0.083265 0.156943 0.04428 -0.084465 0.156943 0.04428 -0.083265 0.159143 0.03086 -0.083265 0.158976 0.0317019 -0.083265 0.158499 0.0324156 -0.084465 0.158499 0.0324156 -0.083265 0.157785 0.0328925 -0.084465 0.157785 0.0328925 -0.083265 0.159143 0.03085 -0.083265 0.159143 0.03085 -0.084465 0.158848 0.02975 -0.083265 0.159143 0.02525 -0.084465 0.158848 0.02635 -0.083265 0.158043 0.0271552 -0.084465 0.156943 0.02745 -0.084465 0.158043 0.0271552 -0.083265 0.158848 0.02414 -0.083265 0.159143 0.02524 -0.084465 0.158848 0.02414 -0.084465 0.158043 0.0233347 -0.084465 0.159143 0.01964 -0.083265 0.158976 0.0204819 -0.083265 0.158499 0.0211956 -0.083265 0.158499 0.0211956 -0.084465 0.157785 0.0216725 -0.084465 0.156943 0.02184 -0.084465 0.157785 0.0216725 -0.083265 0.158976 0.0187881 -0.083265 0.157785 0.0175974 -0.083265 0.158848 0.01513 -0.084465 0.158043 0.0159352 -0.084465 0.158976 0.0131781 -0.083265 0.158976 0.00926186 -0.084465 0.158499 0.00997559 -0.083265 0.159143 0.00840996 -0.084465 0.158976 0.00756805 -0.083265 0.158848 0.00730996 -0.084465 0.158499 0.00685432 -0.084465 0.158043 0.0065047 -0.084465 0.157785 0.00637742 -0.083265 0.156943 0.00620996 -0.083265 0.158976 0.00365186 -0.084465 0.158976 0.00365186 -0.083265 0.157785 0.00484249 -0.084465 0.157785 0.00484249 -0.083265 0.158043 -0.0103253 -0.084465 0.157785 -0.0104526 -0.083265 0.159143 -0.01402 -0.084465 0.159143 -0.01402 -0.083265 0.158848 -0.01292 -0.084465 0.158043 -0.0121148 -0.083265 0.158848 -0.01513 -0.083265 0.159143 -0.01403 -0.084465 0.158848 -0.01513 -0.084465 0.156943 -0.01623 -0.083265 0.158976 -0.0187881 -0.084465 0.158976 -0.0187881 -0.083265 0.157785 -0.0175975 -0.084465 0.157785 -0.0175975 -0.083265 0.158848 -0.02074 -0.084465 0.158499 -0.0211957 -0.084465 0.158499 -0.0211957 -0.083265 0.157785 -0.0216726 -0.083265 0.156943 -0.02184 -0.084465 0.159143 -0.02524 -0.084465 0.158976 -0.0243981 -0.084465 0.158848 -0.02414 -0.084465 0.158043 -0.0233348 -0.083265 0.158043 -0.0233348 -0.084465 0.158848 -0.02635 -0.083265 0.158043 -0.0271553 -0.083265 0.158043 -0.0271553 -0.084465 0.159143 -0.03085 -0.083265 0.158976 -0.0300081 -0.083265 0.158499 -0.0292944 -0.084465 0.157785 -0.0288175 -0.084465 0.158976 -0.0317019 -0.083265 0.158499 -0.0324157 -0.083265 0.156943 -0.03306 -0.084465 0.158043 -0.0345548 -0.084465 0.158848 -0.03536 -0.083265 0.158043 -0.0345548 -0.083265 0.158976 -0.0373119 -0.083265 0.159143 -0.03647 -0.084465 0.158976 -0.0373119 -0.084465 0.158499 -0.0380257 -0.083265 0.157785 -0.0385026 -0.083265 0.157785 -0.0385026 -0.084465 0.156943 -0.03867 -0.083265 -0.16039 -0.0495953 -0.083265 -0.15929 -0.04548 -0.084465 -0.160131 -0.0456475 -0.084465 -0.161322 -0.0468381 -0.084465 -0.16149 -0.04768 -0.084465 -0.161322 -0.0468381 -0.083265 -0.16149 -0.04768 -0.083265 0.159143 -0.04768 -0.083265 0.158043 -0.0457748 -0.083265 0.156943 -0.04548 -0.084465 0.159143 -0.04769 -0.084465 0.158976 -0.0485319 -0.084465 0.157785 -0.0497226 -0.083265 0.158848 -0.04318 -0.084465 0.158043 -0.0439853 -0.083265 0.157785 -0.0441126 -0.084465 0.158043 -0.0439853 -0.084465 0.158499 -0.0436357 -0.084465 -0.16039 -0.0439853 -0.083265 -0.15929 -0.04428 -0.084465 -0.16039 -0.0439853 -0.084465 -0.161195 -0.04318 -0.083265 -0.161195 -0.04318 -0.084465 -0.15929 -0.03987 -0.083265 -0.160845 -0.0405144 -0.084465 -0.160845 -0.0405144 -0.083265 -0.16149 -0.04207 -0.084465 0.158848 -0.04097 -0.084465 0.158848 -0.04097 -0.083265 0.158043 -0.0401648 -0.084465 0.156943 -0.03987 -0.083265 -0.160131 -0.0512575 -0.084465 -0.161322 -0.0524481 -0.084465 -0.161322 -0.0524481 -0.083265 0.159143 -0.05329 -0.083265 0.158848 -0.05219 -0.084465 0.158848 -0.05219 -0.083265 0.158043 -0.0513848 -0.083265 0.156943 -0.05109 -0.083265 0.158976 -0.0541419 -0.084465 0.158848 -0.0544 -0.083265 0.158848 -0.0544 -0.084465 0.158499 -0.0548557 -0.084465 0.156943 -0.0555 -0.083265 0.157785 -0.0553326 -0.084465 0.158043 -0.0552053 -0.084465 0.158976 -0.0600419 -0.083265 0.158976 -0.0600419 -0.084465 0.158499 -0.0607557 -0.083265 0.157785 -0.0612326 -0.083265 0.158499 -0.0607557 -0.084465 0.157785 -0.0612326 -0.084465 0.156943 -0.0614 -0.084465 -0.160131 -0.0568675 -0.084465 -0.15929 -0.0567 -0.083265 -0.160131 -0.0568675 -0.083265 -0.160845 -0.0573444 -0.083265 -0.160845 -0.0573444 -0.084465 -0.161322 -0.0580581 -0.083265 0.158848 -0.0578 -0.084465 0.158043 -0.0569948 -0.084465 0.156943 -0.0567 -0.084465 0.158043 -0.0569948 -0.083265 0.156943 -0.0567 -0.083265 -0.161195 -0.0544 -0.083265 -0.161195 -0.0544 -0.084465 -0.16149 -0.0533 -0.084465 -0.16039 -0.0611053 -0.083265 -0.15929 -0.0614 -0.084465 -0.16039 -0.0611053 -0.084465 -0.161195 -0.0603 -0.083265 -0.16149 -0.0592 -0.083265 -0.13919 0.03426 -0.083265 -0.141095 0.03536 -0.084465 -0.14139 0.03646 -0.083265 -0.14139 0.03646 -0.084465 -0.14029 -0.0345548 -0.084465 -0.14029 -0.0345548 -0.083265 -0.141095 -0.03536 -0.083265 -0.14139 -0.03646 -0.084465 -0.14139 -0.03646 -0.083265 -0.14029 -0.0383753 -0.083265 -0.141095 -0.03757 -0.084465 -0.14139 -0.03647 -0.084465 -0.14029 -0.0103253 -0.083265 -0.14139 -0.00842004 -0.083265 -0.14029 -0.00650479 -0.083265 -0.141095 -0.00731004 -0.084465 -0.141095 -0.00731004 -0.083265 -0.14139 -0.00841004 -0.084465 -0.14139 -0.00841004 -0.083265 -0.14029 -0.0327653 -0.083265 -0.141095 -0.03196 -0.083265 -0.13919 -0.02865 -0.084465 -0.14029 -0.0289448 -0.083265 -0.141095 -0.02975 -0.084465 -0.13919 -0.02745 -0.084465 -0.140031 -0.0272826 -0.084465 -0.140745 -0.0268057 -0.083265 -0.141222 -0.0260919 -0.083265 -0.13919 -0.02304 -0.083265 -0.141095 -0.02414 -0.084465 -0.14139 -0.02524 -0.084465 -0.14029 -0.0215453 -0.083265 -0.141095 -0.02074 -0.084465 -0.14029 -0.0177248 -0.084465 -0.13919 -0.01743 -0.083265 -0.14029 -0.0177248 -0.083265 -0.141095 -0.01853 -0.084465 -0.14139 -0.01963 -0.084465 -0.13919 -0.01623 -0.084465 -0.140745 -0.0155857 -0.083265 -0.140031 -0.0160626 -0.084465 -0.141222 -0.0148719 -0.084465 -0.141095 -0.01292 -0.084465 -0.14139 -0.01402 -0.083265 -0.13919 -0.00501004 -0.083265 -0.140031 -0.00484258 -0.083265 -0.140031 -0.00484258 -0.084465 -0.14139 -0.00281004 -0.083265 -0.141222 -0.00365195 -0.084465 -0.14139 -0.00281004 -0.084465 -0.13919 -0.000600042 -0.083265 -0.14029 -0.000894786 -0.084465 -0.141095 -0.00170004 -0.084465 -0.14029 -0.000894786 -0.083265 -0.140031 0.000767423 -0.083265 -0.140745 0.00124432 -0.084465 -0.141222 0.00195805 -0.083265 -0.141222 0.00195805 -0.084465 -0.14029 0.00471521 -0.084465 -0.141095 0.00390996 -0.083265 -0.14139 0.00280996 -0.084465 -0.14139 0.00280996 -0.083265 -0.13919 0.00620996 -0.083265 -0.14029 0.0065047 -0.083265 -0.14029 0.0065047 -0.084465 -0.14139 0.00840996 -0.083265 -0.13919 0.01062 -0.084465 -0.14029 0.0103252 -0.083265 -0.13919 0.01182 -0.084465 -0.140031 0.0119874 -0.084465 -0.140745 0.0124643 -0.083265 -0.140745 0.0124643 -0.084465 -0.141222 0.0131781 -0.083265 -0.14139 0.01402 -0.083265 -0.14139 0.01402 -0.084465 -0.14029 0.0159352 -0.084465 -0.141095 0.01513 -0.084465 -0.14029 0.0159352 -0.083265 -0.141095 0.01513 -0.083265 -0.14139 0.01403 -0.083265 -0.14029 0.0177247 -0.084465 -0.14029 0.0177247 -0.083265 -0.141095 0.01853 -0.084465 -0.14139 0.01963 -0.084465 -0.13919 0.02184 -0.083265 -0.14029 0.0215452 -0.083265 -0.141095 0.02074 -0.083265 -0.140031 0.0232074 -0.083265 -0.140031 0.0232074 -0.084465 -0.140745 0.0236843 -0.084465 -0.141222 0.0243981 -0.084465 -0.14139 0.02524 -0.083265 -0.141095 0.02635 -0.084465 -0.141095 0.02635 -0.083265 -0.140031 0.0288174 -0.083265 -0.140745 0.0292943 -0.083265 -0.14139 0.03085 -0.083265 -0.14029 0.0327652 -0.084465 -0.141095 0.03196 -0.083265 -0.141095 0.03757 -0.083265 -0.141095 0.03757 -0.084465 -0.14029 0.0383752 -0.083265 -0.14029 0.0383752 -0.084465 0.237227 -0.06445 -0.084765 0.172243 0.037935 -0.084765 0.144165 0.01683 -0.084765 0.0824668 0.00560996 -0.084765 -0.161455 0.04894 -0.084765 -0.239573 -0.037935 -0.084765 -0.215473 0.0388 -0.084765 -0.15929 0.04458 -0.084765 -0.209923 0.0420043 -0.084765 -0.160246 0.0443897 -0.084765 -0.161599 0.0430367 -0.084765 -0.208569 0.04065 -0.084765 -0.16179 0.04208 -0.084765 -0.161599 0.0411132 -0.084765 -0.239573 0.037935 -0.084765 -0.239573 0.03927 -0.084765 -0.141355 0.03772 -0.084765 -0.209923 0.0355957 -0.084765 -0.15519 0.0369 -0.084765 -0.15929 0.0617 -0.084765 -0.161057 0.0571322 -0.084765 -0.15929 0.0564 -0.084765 -0.208569 0.05695 -0.084765 -0.16054 0.061365 -0.084765 -0.161599 0.0579433 -0.084765 -0.16179 0.0589 -0.084765 -0.208569 0.06065 -0.084765 -0.239573 0.06445 -0.084765 -0.239573 0.0561 -0.084765 -0.215473 0.0588 -0.084765 -0.16179 0.05329 -0.084765 -0.209923 0.0555957 -0.084765 0.207577 0.0420043 -0.084765 0.237227 0.03927 -0.084765 0.237227 0.037935 -0.084765 0.212631 0.03695 -0.084765 0.206223 0.06065 -0.084765 0.213127 0.0588 -0.084765 0.237227 0.0561 -0.084765 0.209427 0.0625 -0.084765 0.206223 0.05695 -0.084765 0.207577 0.0555957 -0.084765 0.209427 0.0551 -0.084765 -0.15718 -0.0365042 -0.084765 -0.15519 -0.0369 -0.084765 -0.214977 -0.03695 -0.084765 -0.15109 -0.0369 -0.084765 -0.1491 -0.0365042 -0.084765 -0.141355 -0.03772 -0.084765 -0.147413 -0.035377 -0.084765 -0.14169 -0.03647 -0.084765 -0.213623 -0.0355957 -0.084765 -0.208569 -0.03695 -0.084765 -0.158867 -0.035377 -0.084765 -0.14044 -0.0386351 -0.084765 -0.209923 -0.0420043 -0.084765 -0.208569 -0.04065 -0.084765 -0.239573 -0.03927 -0.084765 -0.213623 -0.0420043 -0.084765 -0.208106 -0.0392949 -0.084765 -0.161455 -0.04333 -0.084765 -0.15929 -0.0558 -0.084765 -0.16179 -0.05329 -0.084765 -0.160246 -0.0565903 -0.084765 -0.16179 -0.0589 -0.084765 -0.213623 -0.0555957 -0.084765 -0.214977 -0.05695 -0.084765 -0.239573 -0.06445 -0.084765 -0.213623 -0.0620043 -0.084765 -0.215473 -0.0588 -0.084765 0.213127 -0.0388 -0.084765 0.209427 -0.0351 -0.084765 0.237227 -0.03485 -0.084765 0.211277 -0.0355957 -0.084765 0.212631 -0.03695 -0.084765 0.206223 -0.04065 -0.084765 0.212631 -0.04065 -0.084765 0.211277 -0.0420043 -0.084765 0.209427 -0.0425 -0.084765 0.172243 -0.04354 -0.084765 0.209427 -0.0551 -0.084765 0.237227 -0.0621 -0.084765 0.212631 -0.06065 -0.084765 0.237227 -0.0561 -0.084765 0.212631 -0.05695 -0.084765 0.205727 -0.0588 -0.084765 0.172243 -0.0621 -0.084765 -0.19659 -0.03 -0.084765 -0.195973 -0.0277 -0.084765 -0.239573 -0.0261898 -0.084765 -0.239298 -0.0250012 -0.084765 -0.239573 -0.03366 -0.084765 -0.239573 -0.03485 -0.084765 -0.19199 -0.0346 -0.084765 -0.15929 -0.0348978 -0.084765 -0.18969 -0.0339838 -0.084765 -0.159994 -0.03369 -0.084765 -0.188006 -0.0323 -0.084765 -0.18739 -0.03 -0.084765 -0.18969 -0.0260163 -0.084765 -0.19199 -0.0254 -0.084765 -0.195973 0.0277 -0.084765 -0.239298 0.0250012 -0.084765 -0.18969 0.0260162 -0.084765 -0.16039 0.02805 -0.084765 -0.16039 0.0317 -0.084765 -0.19199 0.0346 -0.084765 -0.239573 0.03485 -0.084765 -0.19429 0.0339837 -0.084765 -0.239573 0.03366 -0.084765 0.187343 -0.0260163 -0.084765 0.193627 -0.0277 -0.084765 0.236951 -0.0250012 -0.084765 0.191943 -0.0260163 -0.084765 0.185043 -0.03 -0.084765 0.185659 -0.0323 -0.084765 0.172243 -0.03366 -0.084765 0.172243 -0.03485 -0.084765 0.189643 -0.0346 -0.084765 0.237227 -0.03366 -0.084765 0.191943 -0.0339838 -0.084765 0.193627 -0.0323 -0.084765 0.194243 -0.03 -0.084765 0.185659 0.0277 -0.084765 0.187343 0.0260162 -0.084765 0.189643 0.0254 -0.084765 0.191943 0.0260162 -0.084765 0.191943 0.0339837 -0.084765 0.189643 0.0346 -0.084765 0.172243 0.03485 -0.084765 0.187343 0.0339837 -0.084765 0.185043 0.03 -0.084765 0.172243 0.02805 -0.084765 0.207262 -0.05005 -0.084765 0.208177 -0.0509651 -0.084765 0.237227 -0.04488 -0.084765 0.211927 -0.0488 -0.084765 0.211592 -0.04755 -0.084765 0.208177 -0.046635 -0.084765 0.172243 -0.05049 -0.084765 0.206927 -0.0488 -0.084765 -0.211773 -0.0513 -0.084765 -0.15929 -0.05019 -0.084765 -0.213938 -0.04755 -0.084765 -0.16054 -0.0498551 -0.084765 -0.161599 -0.0467233 -0.084765 -0.16179 -0.04768 -0.084765 0.207262 0.04755 -0.084765 0.209427 0.0463 -0.084765 0.211592 0.04755 -0.084765 0.237227 0.05049 -0.084765 0.172243 0.05049 -0.084765 -0.211773 0.0463 -0.084765 -0.210523 0.0466349 -0.084765 -0.209608 0.04755 -0.084765 -0.161599 0.0467233 -0.084765 -0.239573 0.05049 -0.084765 -0.209608 0.05005 -0.084765 -0.209273 0.0488 -0.084765 -0.16179 0.04769 -0.084765 -0.161057 0.0515222 -0.084765 -0.210523 0.050965 -0.084765 -0.161599 0.0523333 -0.084765 0.159253 -0.0601568 -0.084765 0.0824668 -0.0621 -0.084765 0.144165 -0.0617 -0.084765 0.156943 -0.0617 -0.084765 0.158711 -0.0609678 -0.084765 0.0824668 -0.0561 -0.084765 -0.15929 -0.0564 -0.084765 0.0824668 -0.0564 -0.084765 0.144165 -0.0561 -0.084765 0.156943 -0.0564 -0.084765 0.159253 -0.0542568 -0.084765 0.172243 -0.0532 -0.084765 0.172243 -0.0561 -0.084765 0.0824668 -0.0558 -0.084765 0.144165 -0.05049 -0.084765 0.0824668 -0.05049 -0.084765 -0.161057 -0.0515223 -0.084765 0.159443 -0.05329 -0.084765 0.159108 -0.05204 -0.084765 0.158193 -0.051125 -0.084765 0.159108 -0.04643 -0.084765 0.158193 -0.045515 -0.084765 0.159253 -0.0486468 -0.084765 0.159443 -0.04768 -0.084765 0.158711 -0.0494578 -0.084765 0.144165 -0.04488 -0.084765 0.0824668 -0.04488 -0.084765 0.0824668 -0.04518 -0.084765 -0.15929 -0.04518 -0.084765 -0.211773 -0.0463 -0.084765 -0.213023 -0.046635 -0.084765 0.172243 -0.03927 -0.084765 0.158193 -0.039905 -0.084765 0.159253 -0.0430368 -0.084765 0.205727 -0.0388 -0.084765 -0.211773 -0.0425 -0.084765 -0.239573 -0.04354 -0.084765 -0.239573 -0.04488 -0.084765 -0.16054 -0.0442451 -0.084765 0.1579 -0.0443897 -0.084765 0.158711 -0.0438478 -0.084765 0.144165 -0.03927 -0.084765 0.0824668 -0.03957 -0.084765 0.0824668 -0.03927 -0.084765 -0.15929 -0.03957 -0.084765 0.206223 -0.03695 -0.084765 -0.13919 -0.03897 -0.084765 0.0824668 -0.03897 -0.084765 0.144165 -0.03897 -0.084765 0.1579 -0.0387797 -0.084765 0.172243 -0.037935 -0.084765 0.158711 -0.0382378 -0.084765 0.159253 -0.0374268 -0.084765 0.144165 -0.03366 -0.084765 0.0824668 -0.03396 -0.084765 0.159443 -0.03646 -0.084765 0.158193 -0.034295 -0.084765 0.156943 -0.03396 -0.084765 0.158711 -0.0290823 -0.084765 0.158193 -0.0330251 -0.084765 0.1579 -0.0285403 -0.084765 -0.14044 -0.0330251 -0.084765 0.0824668 -0.03366 -0.084765 0.0824668 -0.03336 -0.084765 -0.14589 -0.02805 -0.084765 -0.14169 -0.03085 -0.084765 -0.14589 -0.0317 -0.084765 -0.141355 -0.03211 -0.084765 0.156943 -0.02835 -0.084765 -0.14044 -0.028685 -0.084765 -0.141355 -0.0296 -0.084765 0.144165 -0.02805 -0.084765 0.144165 -0.02775 -0.084765 0.172243 -0.02805 -0.084765 0.159108 -0.0265 -0.084765 0.0824668 -0.02805 -0.084765 -0.14169 -0.02525 -0.084765 0.144165 -0.02244 -0.084765 -0.14589 -0.02407 -0.084765 0.159443 -0.02525 -0.084765 0.172243 -0.02407 -0.084765 0.158711 -0.0178623 -0.084765 0.156943 -0.01713 -0.084765 0.172243 -0.01683 -0.084765 0.158193 -0.0218051 -0.084765 0.159443 -0.01964 -0.084765 -0.14589 -0.02244 -0.084765 0.0824668 -0.02244 -0.084765 -0.13919 -0.02214 -0.084765 0.0824668 -0.02214 -0.084765 0.0824668 -0.01713 -0.084765 0.144165 -0.01683 -0.084765 0.144165 -0.01653 -0.084765 0.156943 -0.01653 -0.084765 0.159443 -0.01402 -0.084765 0.159108 -0.01528 -0.084765 0.156943 -0.01092 -0.084765 0.158193 -0.0105851 -0.084765 0.159443 -0.00841004 -0.084765 -0.14169 -0.00842004 -0.084765 -0.14169 -0.00841004 -0.084765 -0.14169 -0.01403 -0.084765 -0.141499 -0.0149868 -0.084765 -0.14589 -0.01683 -0.084765 -0.140146 -0.0163397 -0.084765 0.0824668 -0.01683 -0.084765 0.0824668 -0.01653 -0.084765 -0.141355 -0.01277 -0.084765 -0.14044 -0.011855 -0.084765 -0.13919 -0.01152 -0.084765 0.0824668 -0.01092 -0.084765 0.144165 -0.00561004 -0.084765 0.144165 -0.00591004 -0.084765 0.0824668 -0.00591004 -0.084765 -0.13919 -0.00591004 -0.084765 0.159443 0.00840996 -0.084765 0.1579 0.0107297 -0.084765 0.156943 0.01092 -0.084765 -0.141355 0.00715996 -0.084765 -0.14044 0.00624489 -0.084765 -0.14169 0.00840996 -0.084765 -0.14589 0.00560996 -0.084765 -0.14169 0.00841996 -0.084765 0.144165 0.01122 -0.084765 0.144165 0.01092 -0.084765 0.0824668 0.01092 -0.084765 -0.14589 0.01122 -0.084765 -0.14044 0.010585 -0.084765 0.156943 0.01152 -0.084765 0.1579 0.0117103 -0.084765 0.172243 0.01122 -0.084765 0.159443 0.01402 -0.084765 0.159108 0.01528 -0.084765 -0.140957 0.0122522 -0.084765 -0.13919 0.01152 -0.084765 0.0824668 0.01122 -0.084765 0.144165 0.01152 -0.084765 -0.14169 0.01403 -0.084765 0.144165 0.01653 -0.084765 0.0824668 0.01653 -0.084765 0.0824668 0.01683 -0.084765 -0.141355 0.01528 -0.084765 0.158193 0.0230749 -0.084765 0.156943 0.02214 -0.084765 0.144165 0.02274 -0.084765 0.144165 0.02214 -0.084765 0.172243 0.02407 -0.084765 -0.14044 0.0174649 -0.084765 -0.14589 0.01683 -0.084765 -0.13919 0.01713 -0.084765 0.144165 0.01713 -0.084765 -0.141355 0.01838 -0.084765 -0.140146 0.0229303 -0.084765 0.0824668 0.02274 -0.084765 0.158711 0.0214077 -0.084765 0.159108 0.02399 -0.084765 0.159443 0.02524 -0.084765 0.159443 0.02525 -0.084765 -0.14169 0.02525 -0.084765 -0.14589 0.02407 -0.084765 -0.141499 0.0242832 -0.084765 -0.140957 0.0234722 -0.084765 0.144165 0.02775 -0.084765 0.0824668 0.02775 -0.084765 0.0824668 0.02805 -0.084765 -0.14589 0.02805 -0.084765 -0.14044 0.027415 -0.084765 0.158193 0.0286849 -0.084765 0.156943 0.02775 -0.084765 0.144165 0.02805 -0.084765 0.144165 0.02835 -0.084765 0.158711 0.0326277 -0.084765 0.1579 0.0331697 -0.084765 0.156943 0.03336 -0.084765 0.159443 0.03085 -0.084765 -0.140146 0.0285403 -0.084765 -0.13919 0.02835 -0.084765 0.0824668 0.02835 -0.084765 -0.146287 0.0336941 -0.084765 -0.14589 0.0317 -0.084765 -0.141355 0.03211 -0.084765 -0.14169 0.03085 -0.084765 0.144165 0.03336 -0.084765 0.144165 0.03366 -0.084765 0.0824668 0.03366 -0.084765 -0.14044 0.033025 -0.084765 0.172243 0.03366 -0.084765 0.156943 0.03396 -0.084765 -0.14169 0.03647 -0.084765 -0.14169 0.03646 -0.084765 0.0824668 0.03396 -0.084765 -0.208073 0.0388 -0.084765 -0.14044 0.038635 -0.084765 -0.13919 0.03897 -0.084765 0.0824668 0.03897 -0.084765 0.206223 0.03695 -0.084765 0.1579 0.0387797 -0.084765 0.156943 0.03897 -0.084765 0.144165 0.03897 -0.084765 0.159108 0.04333 -0.084765 0.159443 0.04208 -0.084765 0.0824668 0.03957 -0.084765 0.0824668 0.03927 -0.084765 0.144165 0.03957 -0.084765 0.144165 0.03927 -0.084765 0.156943 0.03957 -0.084765 0.172243 0.03927 -0.084765 0.158193 0.0399049 -0.084765 0.144165 0.04488 -0.084765 0.144165 0.04458 -0.084765 0.0824668 0.04458 -0.084765 -0.239573 0.04488 -0.084765 -0.211773 0.0425 -0.084765 0.1579 0.0499997 -0.084765 -0.161057 0.0459122 -0.084765 -0.160246 0.0453703 -0.084765 -0.15929 0.04518 -0.084765 0.0824668 0.04488 -0.084765 0.158193 0.0455149 -0.084765 0.172243 0.04574 -0.084765 0.159108 0.04643 -0.084765 0.144165 0.05019 -0.084765 0.144165 0.05049 -0.084765 0.156943 0.0558 -0.084765 0.172243 0.0532 -0.084765 0.159443 0.05329 -0.084765 0.159443 0.0533 -0.084765 0.172243 0.0561 -0.084765 -0.209988 0.0505501 -0.084765 0.0824668 0.05049 -0.084765 0.144165 0.05079 -0.084765 0.159108 0.05204 -0.084765 0.144165 0.0558 -0.084765 0.144165 0.0561 -0.084765 0.0824668 0.0561 -0.084765 -0.15929 0.0558 -0.084765 -0.161057 0.0550677 -0.084765 0.159108 0.05765 -0.084765 0.159443 0.0589 -0.084765 0.158193 0.0567349 -0.084765 0.1579 -0.00610034 -0.084765 0.156943 -0.00531004 -0.084765 0.144165 -4.19898e-08 -0.084765 0.172243 -0.00561004 -0.084765 -0.141499 -0.00376675 -0.084765 -0.140957 -0.00457781 -0.084765 -0.140146 -0.00511974 -0.084765 -0.13919 -0.00531004 -0.084765 0.0824668 -0.00561004 -0.084765 -0.14169 -0.00280004 -0.084765 -0.14589 -0.00561004 -0.084765 0.156943 -0.000300042 -0.084765 0.144165 -0.000300042 -0.084765 0.0824668 -0.000300042 -0.084765 -0.13919 -0.000300042 -0.084765 -0.14589 -4.19898e-08 -0.084765 -0.141355 -0.00155004 -0.084765 0.158711 0.00457773 -0.084765 0.144165 0.000299958 -0.084765 0.156943 0.000299958 -0.084765 0.159108 0.00154996 -0.084765 0.1579 0.00511966 -0.084765 0.156943 0.00530996 -0.084765 0.144165 0.00590996 -0.084765 0.159443 0.00279996 -0.084765 0.159443 0.00280996 -0.084765 0.172243 0.00560996 -0.084765 0.159253 0.00376667 -0.084765 -0.140146 0.000490259 -0.084765 0.0824668 -4.19898e-08 -0.084765 -0.14169 0.00280996 -0.084765 -0.141499 0.00184325 -0.084765 0.144165 0.00560996 -0.084765 -0.141355 0.00405996 -0.084765 -0.177967 -0.0790706 -0.084765 -0.238873 -0.0792 -0.084765 -0.239573 -0.0785 -0.084765 -0.126633 -0.0664 -0.084765 -0.207973 -0.0749838 -0.084765 -0.206289 -0.0733 -0.084765 -0.0390095 -0.0687 -0.084765 0.0383468 -0.0670163 -0.084765 0.0366631 -0.0687 -0.084765 -0.124333 -0.0670163 -0.084765 -0.0452932 -0.0670163 -0.084765 -0.122649 -0.0687 -0.084765 -0.0469769 -0.0687 -0.084765 -0.122649 -0.0733 -0.084765 -0.0475932 -0.071 -0.084765 -0.0469769 -0.0733 -0.084765 0.0446305 -0.0687 -0.084765 0.0429468 -0.0670163 -0.084765 0.0406468 -0.0664 -0.084765 -0.0429932 -0.0664 -0.084765 0.0824668 -0.06445 -0.084765 -0.210273 -0.0664 -0.084765 -0.212573 -0.0749838 -0.084765 -0.0452932 -0.0749838 -0.084765 -0.124333 -0.0749838 -0.084765 -0.130617 -0.0687 -0.084765 -0.210273 -0.0756 -0.084765 0.0383468 -0.0749838 -0.084765 -0.130617 -0.0733 -0.084765 -0.128933 -0.0749838 -0.084765 -0.126633 -0.0756 -0.084765 -0.0429932 -0.0756 -0.084765 0.119687 -0.071 -0.084765 0.128271 -0.0687 -0.084765 0.0452468 -0.071 -0.084765 0.120303 -0.0687 -0.084765 0.126587 -0.0670163 -0.084765 0.124287 -0.0664 -0.084765 0.120303 -0.0733 -0.084765 0.124287 -0.0756 -0.084765 0.126587 -0.0749838 -0.084765 0.128887 -0.071 -0.084765 0.237227 -0.0774 -0.084765 0.209427 -0.0625 -0.084765 0.205627 -0.0749838 -0.084765 0.211911 -0.0733 -0.084765 0.212527 -0.071 -0.084765 0.205627 -0.0670163 -0.084765 0.203943 -0.0687 -0.084765 0.17507 -0.0787021 -0.084765 0.176272 -0.0792 -0.084765 0.237133 -0.07885 -0.084765 0.236877 -0.0791063 -0.084765 0.236527 -0.0792 -0.084765 0.172243 -0.02244 -0.084765 0.187897 -0.0138199 -0.084765 0.172243 -4.19898e-08 -0.084765 0.177043 -4.19898e-08 -0.084765 0.177043 -0.000500042 -0.084765 0.178432 0.00648677 -0.084765 0.182314 0.011251 -0.084765 0.172243 0.01683 -0.084765 0.23618 0.0240553 -0.084765 0.207927 0.0756 -0.084765 0.212527 0.071 -0.084765 0.176272 0.0792 -0.084765 0.175621 0.0790706 -0.084765 0.237133 0.07885 -0.084765 0.237227 0.0785 -0.084765 0.144165 0.0757 -0.084765 0.156943 0.0617 -0.084765 0.172243 0.06445 -0.084765 0.203327 0.071 -0.084765 0.121987 0.0749837 -0.084765 0.0824668 0.0757 -0.084765 0.120303 0.0687 -0.084765 0.144165 0.06445 -0.084765 -0.126633 0.0756 -0.084765 -0.210273 0.0756 -0.084765 -0.238873 0.0792 -0.084765 -0.212573 0.0749837 -0.084765 -0.239223 0.0791062 -0.084765 -0.210273 0.0664 -0.084765 -0.212573 0.0670162 -0.084765 -0.130617 0.0733 -0.084765 -0.214257 0.0733 -0.084765 -0.214873 0.071 -0.084765 -0.124333 0.0749837 -0.084765 -0.175527 0.076813 -0.084765 -0.17284 0.0757 -0.084765 -0.128933 0.0749837 -0.084765 -0.0390095 0.0687 -0.084765 0.0366631 0.0733 -0.084765 0.0383468 0.0749837 -0.084765 -0.0383932 0.071 -0.084765 -0.0406932 0.0749837 -0.084765 -0.0429932 0.0756 -0.084765 -0.174294 0.0759892 -0.084765 -0.131233 0.071 -0.084765 -0.206289 0.0687 -0.084765 -0.205673 0.071 -0.084765 -0.0452932 0.0749837 -0.084765 -0.0469769 0.0733 -0.084765 -0.122033 0.071 -0.084765 -0.122649 0.0687 -0.084765 0.0366631 0.0687 -0.084765 0.0824668 0.06445 -0.084765 0.0446305 0.0687 -0.084765 0.0452468 0.071 -0.084765 0.0446305 0.0733 -0.084765 -0.124333 0.0670162 -0.084765 -0.126633 0.0664 -0.084765 -0.0429932 0.0664 -0.084765 -0.207973 0.0670162 -0.084765 -0.237418 0.0235453 -0.084765 -0.16039 0.02407 -0.084765 -0.16039 0.01683 -0.084765 -0.16039 0.01122 -0.084765 -0.16039 0.00560996 -0.084765 -0.17939 0.000499958 -0.084765 -0.16039 -4.19898e-08 -0.084765 -0.16039 -0.02407 -0.084765 -0.237418 -0.0235454 -0.084765 -0.16039 -0.01683 -0.084765 -0.190244 -0.0138199 -0.084765 -0.18466 -0.0112511 -0.084765 -0.17939 -4.19898e-08 -0.084765 0.237227 0.04488 -0.084765 0.209427 0.0425 -0.084765 0.172243 0.04488 -0.084765 0.209427 -0.0463 -0.084765 0.172243 -0.04488 -0.084765 -0.161455 -0.06045 -0.084765 -0.208569 -0.06065 -0.084765 0.144165 -0.0621 -0.084765 0.144165 -0.06445 -0.084765 0.172243 -0.06445 -0.084765 0.236527 -0.0795 -0.084465 0.176272 -0.0795 -0.080065 0.176272 -0.0795 -0.084465 0.235133 -0.0232516 -0.082565 -0.239873 -0.0261898 -0.084465 -0.239567 -0.0248692 -0.082565 -0.238711 -0.0238182 -0.084465 -0.214879 -0.0185924 -0.082565 -0.237479 -0.0232516 -0.084465 -0.216273 0.0795 -0.082565 0.213927 0.0795 -0.082565 0.213927 0.0795 -0.079565 0.176272 0.0795 -0.080065 -0.238873 0.0795 -0.084465 0.212533 0.0185923 -0.082565 0.212533 0.0185923 -0.079565 -0.237479 0.0232515 -0.082565 -0.237479 0.0232515 -0.084465 -0.238711 0.0238182 -0.082565 -0.239567 0.0248691 -0.082565 -0.238711 0.0238182 -0.084465 -0.239567 0.0248691 -0.084465 -0.239873 0.0261897 -0.082565 -0.239873 0.0785 -0.082565 0.182498 -0.011014 -0.079565 0.236364 -0.0238182 -0.082565 0.236364 -0.0238182 -0.084465 0.23722 -0.0248692 -0.084465 0.23722 -0.0248692 -0.082565 0.237527 -0.0261898 -0.082565 0.237527 -0.0785 -0.082565 -0.184844 -0.011014 -0.079565 -0.17969 -0.000500042 -0.079565 -0.17969 0.000499958 -0.079565 0.237527 0.0785 -0.082565 0.23722 0.0248691 -0.084465 0.23722 0.0248691 -0.082565 0.236364 0.0238182 -0.082565 0.235133 0.0232515 -0.082565 0.235133 0.0232515 -0.084465 0.182498 0.0110139 -0.079565 0.178701 0.00635471 -0.079565 0.177343 0.000499958 -0.084465 0.177343 0.000499958 -0.079565 -0.181048 0.00635471 -0.084465 -0.181048 0.00635471 -0.079565 -0.184844 0.0110139 -0.079565 -0.190304 0.013526 -0.084465 -0.216987 0.0792 -0.082265 -0.238873 0.0792 -0.082265 -0.217139 0.079 -0.082265 -0.239298 0.0250012 -0.082265 -0.239573 0.0785 -0.082265 -0.217273 0.0215305 -0.082265 0.213753 0.0191502 -0.082265 0.214641 0.0792 -0.082265 0.23618 0.0240553 -0.082265 0.235072 0.0235453 -0.082265 0.236951 0.0250012 -0.082265 0.236877 0.0791062 -0.082265 0.214927 0.0785 -0.082265 0.237227 0.0785 -0.082265 0.214927 0.0215305 -0.082265 -0.217273 -0.0215306 -0.082265 -0.217197 -0.0788827 -0.082265 -0.239223 -0.0791063 -0.082265 -0.238873 -0.0792 -0.082265 -0.239573 -0.0785 -0.082265 -0.217273 -0.0785 -0.082265 -0.239573 -0.0261898 -0.082265 -0.237418 -0.0235454 -0.082265 -0.216967 -0.02021 -0.082265 0.213753 -0.0191503 -0.082265 0.21462 -0.02021 -0.082265 0.237227 -0.0785 -0.082265 0.237022 -0.078995 -0.082265 0.23618 -0.0240554 -0.082265 0.214927 -0.0785 -0.082265 0.214641 -0.0792 -0.082265 0.189643 0.02775 -0.083265 0.188518 0.0280514 -0.079265 0.187695 0.028875 -0.079265 0.187393 0.03 -0.079265 0.187695 0.031125 -0.079265 0.189643 0.03225 -0.083265 0.190768 0.0319485 -0.083265 0.191592 0.031125 -0.079265 0.191592 0.031125 -0.083265 0.191893 0.03 -0.079265 0.191893 0.03 -0.083265 0.191592 0.028875 -0.079265 0.190768 0.0280514 -0.083265 0.187343 0.0260162 -0.084265 0.185043 0.03 -0.084265 0.185659 0.0323 -0.084765 0.191943 0.0339837 -0.084265 0.193627 0.0323 -0.084265 0.193627 0.0323 -0.084765 0.194243 0.03 -0.084765 0.193627 0.0277 -0.084265 0.193627 0.0277 -0.084765 0.191943 0.0260162 -0.084265 0.189643 0.0254 -0.084265 0.189643 -0.03225 -0.079265 0.189643 -0.03225 -0.083265 0.188518 -0.0319486 -0.083265 0.187695 -0.031125 -0.079265 0.187695 -0.028875 -0.079265 0.187393 -0.03 -0.083265 0.188518 -0.0280515 -0.079265 0.187695 -0.028875 -0.083265 0.188518 -0.0280515 -0.083265 0.190768 -0.0280515 -0.079265 0.189643 -0.02775 -0.083265 0.190768 -0.0280515 -0.083265 0.191592 -0.028875 -0.079265 0.191893 -0.03 -0.079265 0.191592 -0.031125 -0.079265 0.190768 -0.0319486 -0.079265 0.189643 -0.0346 -0.084265 0.187343 -0.0339838 -0.084265 0.187343 -0.0339838 -0.084765 0.185659 -0.0323 -0.084265 0.185043 -0.03 -0.084265 0.185659 -0.0277 -0.084265 0.185659 -0.0277 -0.084765 0.187343 -0.0260163 -0.084265 0.189643 -0.0254 -0.084765 0.189643 -0.0254 -0.084265 0.194243 -0.03 -0.084265 0.193627 -0.0323 -0.084265 -0.193115 0.0280514 -0.079265 -0.193938 0.028875 -0.079265 -0.193938 0.028875 -0.083265 -0.193938 0.031125 -0.079265 -0.19424 0.03 -0.083265 -0.193115 0.0319485 -0.083265 -0.19199 0.03225 -0.083265 -0.190865 0.0319485 -0.083265 -0.18974 0.03 -0.079265 -0.18974 0.03 -0.083265 -0.190865 0.0280514 -0.079265 -0.19429 0.0260162 -0.084265 -0.19429 0.0260162 -0.084765 -0.19659 0.03 -0.084265 -0.19659 0.03 -0.084765 -0.195973 0.0323 -0.084265 -0.195973 0.0323 -0.084765 -0.19429 0.0339837 -0.084265 -0.18969 0.0339837 -0.084265 -0.18969 0.0339837 -0.084765 -0.188006 0.0323 -0.084765 -0.18739 0.03 -0.084765 -0.188006 0.0277 -0.084265 -0.188006 0.0277 -0.084765 -0.19199 0.0254 -0.084265 -0.19199 0.0254 -0.084765 -0.193938 -0.031125 -0.079265 -0.19424 -0.03 -0.079265 -0.193938 -0.028875 -0.083265 -0.193115 -0.0280515 -0.083265 -0.190041 -0.028875 -0.079265 -0.18974 -0.03 -0.079265 -0.18974 -0.03 -0.083265 -0.195973 -0.0323 -0.084265 -0.19429 -0.0339838 -0.084765 -0.195973 -0.0323 -0.084765 -0.195973 -0.0277 -0.084265 -0.19429 -0.0260163 -0.084265 -0.19429 -0.0260163 -0.084765 -0.19199 -0.0254 -0.084265 -0.18969 -0.0260163 -0.084265 -0.188006 -0.0277 -0.084765 -0.188006 -0.0323 -0.084265 -0.19199 -0.0346 -0.084265 0.207927 0.06875 -0.083265 0.206802 0.0690514 -0.083265 0.205978 0.069875 -0.083265 0.205978 0.069875 -0.079265 0.205677 0.071 -0.079265 0.206802 0.0729485 -0.079265 0.207927 0.07325 -0.079265 0.209052 0.0729485 -0.079265 0.209875 0.072125 -0.079265 0.209875 0.072125 -0.083265 0.210177 0.071 -0.083265 0.209875 0.069875 -0.079265 0.209875 0.069875 -0.083265 0.209052 0.0690514 -0.083265 0.209052 0.0690514 -0.079265 0.207927 0.0664 -0.084265 0.207927 0.0664 -0.084765 0.205627 0.0670162 -0.084265 0.205627 0.0670162 -0.084765 0.203943 0.0687 -0.084765 0.203327 0.071 -0.084265 0.203943 0.0733 -0.084265 0.203943 0.0733 -0.084765 0.205627 0.0749837 -0.084265 0.205627 0.0749837 -0.084765 0.210227 0.0749837 -0.084265 0.210227 0.0749837 -0.084765 0.211911 0.0733 -0.084765 0.212527 0.071 -0.084265 0.211911 0.0687 -0.084765 0.210227 0.0670162 -0.084265 0.210227 0.0670162 -0.084765 -0.211398 0.0690514 -0.079265 -0.211398 0.0690514 -0.083265 -0.212222 0.069875 -0.083265 -0.212222 0.069875 -0.079265 -0.211398 0.0729485 -0.079265 -0.212222 0.072125 -0.083265 -0.210273 0.07325 -0.079265 -0.210273 0.07325 -0.083265 -0.208325 0.072125 -0.079265 -0.208325 0.072125 -0.083265 -0.209148 0.0690514 -0.079265 -0.210273 0.06875 -0.079265 -0.210273 0.06875 -0.083265 -0.210273 0.0664 -0.084265 -0.212573 0.0670162 -0.084265 -0.214873 0.071 -0.084265 -0.214257 0.0687 -0.084765 -0.210273 0.0756 -0.084265 -0.207973 0.0749837 -0.084265 -0.207973 0.0749837 -0.084765 -0.206289 0.0733 -0.084765 -0.205673 0.071 -0.084265 -0.206289 0.0687 -0.084265 -0.207973 0.0670162 -0.084265 0.207927 -0.07325 -0.083265 0.206802 -0.0729486 -0.083265 0.205978 -0.072125 -0.083265 0.205677 -0.071 -0.079265 0.205677 -0.071 -0.083265 0.206802 -0.0690515 -0.083265 0.206802 -0.0690515 -0.079265 0.209052 -0.0690515 -0.079265 0.207927 -0.06875 -0.083265 0.210177 -0.071 -0.079265 0.209875 -0.072125 -0.079265 0.210177 -0.071 -0.083265 0.209052 -0.0729486 -0.079265 0.207927 -0.0756 -0.084765 0.203943 -0.0733 -0.084765 0.203943 -0.0733 -0.084265 0.203327 -0.071 -0.084765 0.207927 -0.0664 -0.084765 0.210227 -0.0670163 -0.084765 0.211911 -0.0687 -0.084765 0.212527 -0.071 -0.084265 0.210227 -0.0749838 -0.084765 -0.211398 -0.0729486 -0.079265 -0.210273 -0.07325 -0.083265 -0.211398 -0.0729486 -0.083265 -0.210273 -0.06875 -0.079265 -0.209148 -0.0690515 -0.079265 -0.208325 -0.069875 -0.083265 -0.208325 -0.069875 -0.079265 -0.208023 -0.071 -0.079265 -0.208325 -0.072125 -0.079265 -0.209148 -0.0729486 -0.083265 -0.212573 -0.0749838 -0.084265 -0.214257 -0.0733 -0.084265 -0.214257 -0.0733 -0.084765 -0.214873 -0.071 -0.084265 -0.214873 -0.071 -0.084765 -0.214257 -0.0687 -0.084765 -0.212573 -0.0670163 -0.084765 -0.210273 -0.0664 -0.084265 -0.207973 -0.0670163 -0.084765 -0.206289 -0.0687 -0.084765 -0.206289 -0.0687 -0.084265 -0.205673 -0.071 -0.084265 -0.205673 -0.071 -0.084765 -0.127758 0.0690514 -0.079265 -0.128582 0.069875 -0.079265 -0.127758 0.0690514 -0.083265 -0.128582 0.069875 -0.083265 -0.128883 0.071 -0.083265 -0.128582 0.072125 -0.083265 -0.127758 0.0729485 -0.079265 -0.126633 0.07325 -0.083265 -0.124685 0.072125 -0.079265 -0.125508 0.0729485 -0.083265 -0.124685 0.072125 -0.083265 -0.124685 0.069875 -0.083265 -0.126633 0.06875 -0.083265 -0.126633 0.0664 -0.084265 -0.130617 0.0687 -0.084265 -0.128933 0.0670162 -0.084765 -0.130617 0.0687 -0.084765 -0.131233 0.071 -0.084265 -0.130617 0.0733 -0.084265 -0.122649 0.0733 -0.084765 -0.0449418 0.069875 -0.083265 -0.0449418 0.069875 -0.079265 -0.0452432 0.071 -0.083265 -0.0449418 0.072125 -0.083265 -0.0441182 0.0729485 -0.083265 -0.0429932 0.07325 -0.083265 -0.0429932 0.07325 -0.079265 -0.0410446 0.072125 -0.079265 -0.0410446 0.069875 -0.083265 -0.0418682 0.0690514 -0.079265 -0.0429932 0.06875 -0.079265 -0.0429932 0.06875 -0.083265 -0.0429932 0.0664 -0.084265 -0.0452932 0.0670162 -0.084765 -0.0469769 0.0687 -0.084765 -0.0475932 0.071 -0.084265 -0.0475932 0.071 -0.084765 -0.0390095 0.0733 -0.084765 -0.0406932 0.0670162 -0.084765 0.0395218 0.0690514 -0.083265 0.0386982 0.069875 -0.083265 0.0395218 0.0729485 -0.079265 0.0417718 0.0729485 -0.079265 0.0425954 0.069875 -0.079265 0.0428968 0.071 -0.083265 0.0425954 0.069875 -0.083265 0.0406468 0.06875 -0.083265 0.0406468 0.0664 -0.084765 0.0383468 0.0670162 -0.084265 0.0366631 0.0687 -0.084265 0.0383468 0.0670162 -0.084765 0.0360468 0.071 -0.084265 0.0360468 0.071 -0.084765 0.0366631 0.0733 -0.084265 0.0406468 0.0756 -0.084265 0.0406468 0.0756 -0.084765 0.0429468 0.0749837 -0.084765 0.0452468 0.071 -0.084265 0.0429468 0.0670162 -0.084265 0.0429468 0.0670162 -0.084765 0.122338 0.069875 -0.079265 0.123162 0.0690514 -0.083265 0.122037 0.071 -0.079265 0.122338 0.072125 -0.083265 0.123162 0.0729485 -0.083265 0.125412 0.0729485 -0.079265 0.126235 0.072125 -0.079265 0.126537 0.071 -0.079265 0.126235 0.069875 -0.079265 0.125412 0.0690514 -0.079265 0.126235 0.069875 -0.083265 0.125412 0.0690514 -0.083265 0.124287 0.06875 -0.083265 0.124287 0.0664 -0.084765 0.121987 0.0670162 -0.084265 0.120303 0.0687 -0.084265 0.121987 0.0670162 -0.084765 0.119687 0.071 -0.084765 0.120303 0.0733 -0.084765 0.124287 0.0756 -0.084765 0.126587 0.0749837 -0.084265 0.126587 0.0749837 -0.084765 0.128271 0.0733 -0.084765 0.128887 0.071 -0.084765 0.128271 0.0687 -0.084765 0.126587 0.0670162 -0.084765 0.123162 -0.0729486 -0.079265 0.123162 -0.0729486 -0.083265 0.122338 -0.072125 -0.079265 0.122338 -0.072125 -0.083265 0.122037 -0.071 -0.079265 0.122338 -0.069875 -0.079265 0.122037 -0.071 -0.083265 0.123162 -0.0690515 -0.079265 0.123162 -0.0690515 -0.083265 0.125412 -0.0690515 -0.079265 0.126537 -0.071 -0.079265 0.126235 -0.069875 -0.083265 0.126537 -0.071 -0.083265 0.126235 -0.072125 -0.079265 0.126235 -0.072125 -0.083265 0.125412 -0.0729486 -0.083265 0.124287 -0.07325 -0.083265 0.121987 -0.0749838 -0.084765 0.119687 -0.071 -0.084265 0.121987 -0.0670163 -0.084765 0.124287 -0.0664 -0.084265 0.126587 -0.0670163 -0.084265 0.128887 -0.071 -0.084265 0.128271 -0.0733 -0.084265 0.128271 -0.0733 -0.084765 0.126587 -0.0749838 -0.084265 0.0406468 -0.07325 -0.079265 0.0406468 -0.07325 -0.083265 0.0395218 -0.0729486 -0.083265 0.0386982 -0.072125 -0.079265 0.0386982 -0.072125 -0.083265 0.0383968 -0.071 -0.079265 0.0386982 -0.069875 -0.079265 0.0383968 -0.071 -0.083265 0.0386982 -0.069875 -0.083265 0.0395218 -0.0690515 -0.079265 0.0395218 -0.0690515 -0.083265 0.0406468 -0.06875 -0.083265 0.0406468 -0.06875 -0.079265 0.0417718 -0.0690515 -0.079265 0.0425954 -0.069875 -0.079265 0.0417718 -0.0690515 -0.083265 0.0428968 -0.071 -0.079265 0.0425954 -0.069875 -0.083265 0.0425954 -0.072125 -0.079265 0.0417718 -0.0729486 -0.079265 0.0425954 -0.072125 -0.083265 0.0406468 -0.0756 -0.084765 0.0366631 -0.0733 -0.084265 0.0366631 -0.0733 -0.084765 0.0360468 -0.071 -0.084265 0.0360468 -0.071 -0.084765 0.0406468 -0.0664 -0.084265 0.0446305 -0.0687 -0.084265 0.0446305 -0.0733 -0.084265 0.0429468 -0.0749838 -0.084265 0.0446305 -0.0733 -0.084765 0.0429468 -0.0749838 -0.084765 -0.0429932 -0.07325 -0.079265 -0.0452432 -0.071 -0.079265 -0.0449418 -0.072125 -0.083265 -0.0452432 -0.071 -0.083265 -0.0449418 -0.069875 -0.079265 -0.0441182 -0.0690515 -0.079265 -0.0449418 -0.069875 -0.083265 -0.0429932 -0.06875 -0.083265 -0.0418682 -0.0690515 -0.083265 -0.0407432 -0.071 -0.079265 -0.0407432 -0.071 -0.083265 -0.0410446 -0.072125 -0.083265 -0.0418682 -0.0729486 -0.079265 -0.0418682 -0.0729486 -0.083265 -0.0452932 -0.0749838 -0.084265 -0.0469769 -0.0733 -0.084265 -0.0469769 -0.0687 -0.084265 -0.0429932 -0.0664 -0.084265 -0.0406932 -0.0670163 -0.084765 -0.0383932 -0.071 -0.084265 -0.0383932 -0.071 -0.084765 -0.0390095 -0.0733 -0.084765 -0.0406932 -0.0749838 -0.084765 -0.0429932 -0.0756 -0.084265 -0.127758 -0.0729486 -0.079265 -0.128582 -0.072125 -0.083265 -0.128582 -0.069875 -0.079265 -0.127758 -0.0690515 -0.079265 -0.126633 -0.06875 -0.079265 -0.125508 -0.0690515 -0.079265 -0.124383 -0.071 -0.083265 -0.124685 -0.072125 -0.083265 -0.126633 -0.07325 -0.079265 -0.130617 -0.0733 -0.084265 -0.131233 -0.071 -0.084265 -0.131233 -0.071 -0.084765 -0.128933 -0.0670163 -0.084765 -0.126633 -0.0664 -0.084265 -0.124333 -0.0670163 -0.084265 -0.122033 -0.071 -0.084765 -0.122649 -0.0733 -0.084265 0.205097 -0.0463 -0.073765 0.204427 -0.0488 -0.079265 0.206927 -0.0444699 -0.073765 0.209427 -0.0438 -0.073765 0.209427 -0.0438 -0.079265 0.211927 -0.0444699 -0.073765 0.211927 -0.0444699 -0.079265 0.213757 -0.0463 -0.073765 0.213757 -0.0463 -0.079265 0.213757 -0.0513 -0.073765 0.211927 -0.0531302 -0.073765 0.211927 -0.0531302 -0.079265 0.211677 -0.0449029 -0.073265 0.209427 -0.0463 -0.073265 0.207262 -0.05005 -0.073265 0.204927 -0.0488 -0.073265 0.20553 -0.05105 -0.073265 0.210677 -0.0509651 -0.073265 0.211592 -0.05005 -0.073265 0.213324 -0.05105 -0.073265 0.213927 -0.0488 -0.073265 0.211592 -0.04755 -0.073265 0.206927 -0.0531302 -0.073765 0.207177 -0.0526972 -0.073265 0.205097 -0.0513 -0.073765 0.204427 -0.0488 -0.073765 0.20553 -0.04655 -0.073265 0.207177 -0.0449029 -0.073265 0.209427 -0.0443 -0.073265 0.213324 -0.04655 -0.073265 0.214427 -0.0488 -0.073765 0.211677 -0.0526972 -0.073265 0.209427 -0.0533 -0.073265 0.209427 -0.0538 -0.073765 0.209427 -0.0513 -0.073265 0.208177 -0.0509651 -0.073265 0.206927 -0.0488 -0.073265 0.207262 -0.04755 -0.073265 0.207262 -0.04755 -0.084765 0.208177 -0.046635 -0.073265 0.210677 -0.046635 -0.084765 0.210677 -0.046635 -0.073265 0.211927 -0.0488 -0.073265 0.211592 -0.05005 -0.084765 0.210677 -0.0509651 -0.084765 0.209427 -0.0513 -0.084765 0.207877 -0.0414847 -0.084165 0.207577 -0.0420043 -0.084765 0.206742 -0.04035 -0.084165 0.206327 -0.0388 -0.084165 0.206742 -0.03725 -0.084165 0.207877 -0.0361154 -0.084165 0.207577 -0.0355957 -0.084765 0.212111 -0.03725 -0.084165 0.212111 -0.04035 -0.084165 0.209427 -0.0419 -0.084165 0.207577 -0.0620043 -0.084765 0.206223 -0.06065 -0.084765 0.206223 -0.05695 -0.084765 0.207577 -0.0555957 -0.084765 0.207877 -0.0561154 -0.084165 0.211277 -0.0555957 -0.084765 0.212111 -0.06035 -0.084165 0.213127 -0.0588 -0.084765 0.210977 -0.0614847 -0.084165 0.211277 -0.0620043 -0.084765 -0.209523 -0.0449029 -0.073265 -0.211773 -0.0463 -0.073265 -0.213023 -0.046635 -0.073265 -0.213938 -0.04755 -0.073265 -0.214273 -0.0488 -0.073265 -0.216273 -0.0488 -0.073265 -0.214023 -0.0526972 -0.073265 -0.211773 -0.0533 -0.073265 -0.207876 -0.05105 -0.073265 -0.209608 -0.04755 -0.073265 -0.214273 -0.0531302 -0.073765 -0.216103 -0.0513 -0.073765 -0.214273 -0.0531302 -0.079265 -0.216773 -0.0488 -0.079265 -0.216773 -0.0488 -0.073765 -0.216103 -0.0463 -0.079265 -0.209273 -0.0444699 -0.079265 -0.207443 -0.0463 -0.073765 -0.206773 -0.0488 -0.073765 -0.207443 -0.0513 -0.079265 -0.209273 -0.0531302 -0.079265 -0.211773 -0.0538 -0.079265 -0.21567 -0.05105 -0.073265 -0.21567 -0.04655 -0.073265 -0.214023 -0.0449029 -0.073265 -0.216103 -0.0463 -0.073765 -0.214273 -0.0444699 -0.073765 -0.211773 -0.0443 -0.073265 -0.211773 -0.0438 -0.073765 -0.209273 -0.0444699 -0.073765 -0.207876 -0.04655 -0.073265 -0.207273 -0.0488 -0.073265 -0.209523 -0.0526972 -0.073265 -0.207443 -0.0513 -0.073765 -0.209273 -0.0531302 -0.073765 -0.211773 -0.0538 -0.073765 -0.209273 -0.0488 -0.084765 -0.209608 -0.05005 -0.084765 -0.209608 -0.05005 -0.073265 -0.209988 -0.0505502 -0.084765 -0.210523 -0.0509651 -0.084765 -0.210523 -0.0509651 -0.073265 -0.211773 -0.0513 -0.073265 -0.213023 -0.0509651 -0.084765 -0.213023 -0.0509651 -0.073265 -0.213938 -0.05005 -0.073265 -0.213938 -0.05005 -0.084765 -0.214273 -0.0488 -0.084765 -0.210523 -0.046635 -0.073265 -0.210523 -0.046635 -0.084765 -0.209608 -0.04755 -0.084765 -0.209273 -0.0488 -0.073265 -0.208073 -0.0388 -0.084765 -0.209089 -0.04035 -0.084165 -0.210223 -0.0414847 -0.084165 -0.214977 -0.04065 -0.084765 -0.214873 -0.0388 -0.084165 -0.214458 -0.03725 -0.084165 -0.215473 -0.0388 -0.084765 -0.211773 -0.0357 -0.084165 -0.211773 -0.0351 -0.084765 -0.209923 -0.0355957 -0.084765 -0.209089 -0.03725 -0.084165 -0.211773 -0.0551 -0.084765 -0.209923 -0.0555957 -0.084765 -0.210223 -0.0561154 -0.084165 -0.209335 -0.0560166 -0.084765 -0.208569 -0.05695 -0.084765 -0.209089 -0.06035 -0.084165 -0.208073 -0.0588 -0.084765 -0.209923 -0.0620043 -0.084765 -0.211773 -0.0619 -0.084165 -0.211773 -0.0625 -0.084765 -0.213323 -0.0614847 -0.084165 -0.214977 -0.06065 -0.084765 -0.214458 -0.05725 -0.084165 -0.213323 -0.0561154 -0.084165 -0.211773 -0.0557 -0.084165 0.209427 0.0513 -0.073265 0.208177 0.050965 -0.073265 0.207262 0.05005 -0.073265 0.206927 0.0488 -0.073265 0.207262 0.04755 -0.073265 0.20553 0.04655 -0.073265 0.207177 0.0449028 -0.073265 0.210677 0.0466349 -0.073265 0.211677 0.0449028 -0.073265 0.211592 0.04755 -0.073265 0.213324 0.04655 -0.073265 0.210677 0.050965 -0.073265 0.206927 0.0444698 -0.079265 0.205097 0.0463 -0.073765 0.204427 0.0488 -0.073765 0.204427 0.0488 -0.079265 0.205097 0.0513 -0.079265 0.206927 0.0531301 -0.079265 0.206927 0.0531301 -0.073765 0.209427 0.0538 -0.079265 0.209427 0.0538 -0.073765 0.211927 0.0531301 -0.073765 0.213757 0.0463 -0.073765 0.209427 0.0438 -0.073765 0.206927 0.0444698 -0.073765 0.204927 0.0488 -0.073265 0.20553 0.05105 -0.073265 0.207177 0.0526971 -0.073265 0.205097 0.0513 -0.073765 0.209427 0.0533 -0.073265 0.211677 0.0526971 -0.073265 0.213324 0.05105 -0.073265 0.213757 0.0513 -0.073765 0.213927 0.0488 -0.073265 0.214427 0.0488 -0.073765 0.211927 0.0444698 -0.073765 0.209427 0.0443 -0.073265 0.209427 0.0463 -0.073265 0.208177 0.0466349 -0.073265 0.208177 0.0466349 -0.084765 0.206927 0.0488 -0.084765 0.207262 0.05005 -0.084765 0.208177 0.050965 -0.084765 0.209427 0.0513 -0.084765 0.211592 0.05005 -0.073265 0.210677 0.050965 -0.084765 0.211592 0.05005 -0.084765 0.211927 0.0488 -0.073265 0.211927 0.0488 -0.084765 0.210677 0.0466349 -0.084765 0.207577 0.0355957 -0.084765 0.206742 0.03725 -0.084165 0.205727 0.0388 -0.084765 0.206742 0.04035 -0.084165 0.207877 0.0414846 -0.084165 0.206223 0.04065 -0.084765 0.209427 0.0419 -0.084165 0.211277 0.0420043 -0.084765 0.212631 0.04065 -0.084765 0.213127 0.0388 -0.084765 0.211277 0.0355957 -0.084765 0.207877 0.0361153 -0.084165 0.209427 0.0351 -0.084765 0.206742 0.05725 -0.084165 0.206327 0.0588 -0.084165 0.205727 0.0588 -0.084765 0.207877 0.0614846 -0.084165 0.207577 0.0620043 -0.084765 0.211277 0.0620043 -0.084765 0.212111 0.06035 -0.084165 0.212631 0.06065 -0.084765 0.212111 0.05725 -0.084165 0.212631 0.05695 -0.084765 0.211277 0.0555957 -0.084765 0.209427 0.0557 -0.084165 -0.214273 0.0444698 -0.079265 -0.216103 0.0463 -0.079265 -0.216773 0.0488 -0.079265 -0.214273 0.0531301 -0.073765 -0.214273 0.0531301 -0.079265 -0.211773 0.0538 -0.073765 -0.211773 0.0538 -0.079265 -0.209273 0.0531301 -0.079265 -0.209273 0.0531301 -0.073765 -0.207443 0.0513 -0.079265 -0.207443 0.0463 -0.073765 -0.209273 0.0444698 -0.073765 -0.209273 0.0444698 -0.079265 -0.211773 0.0438 -0.079265 -0.214273 0.0444698 -0.073765 -0.209523 0.0526971 -0.073265 -0.211773 0.0533 -0.073265 -0.213023 0.050965 -0.073265 -0.21567 0.05105 -0.073265 -0.214273 0.0488 -0.073265 -0.213938 0.04755 -0.073265 -0.21567 0.04655 -0.073265 -0.213023 0.0466349 -0.073265 -0.211773 0.0463 -0.073265 -0.214023 0.0449028 -0.073265 -0.211773 0.0443 -0.073265 -0.210523 0.0466349 -0.073265 -0.209523 0.0449028 -0.073265 -0.209273 0.0488 -0.073265 -0.207273 0.0488 -0.073265 -0.207876 0.05105 -0.073265 -0.211773 0.0438 -0.073765 -0.216103 0.0463 -0.073765 -0.216273 0.0488 -0.073265 -0.216773 0.0488 -0.073765 -0.216103 0.0513 -0.073765 -0.214023 0.0526971 -0.073265 -0.207443 0.0513 -0.073765 -0.206773 0.0488 -0.073765 -0.207876 0.04655 -0.073265 -0.210523 0.050965 -0.073265 -0.209608 0.05005 -0.073265 -0.209608 0.04755 -0.073265 -0.213023 0.0466349 -0.084765 -0.213938 0.04755 -0.084765 -0.213938 0.05005 -0.073265 -0.214273 0.0488 -0.084765 -0.213938 0.05005 -0.084765 -0.213023 0.050965 -0.084765 -0.211773 0.0513 -0.073265 -0.211773 0.0513 -0.084765 -0.208106 0.0392948 -0.084765 -0.208569 0.03695 -0.084765 -0.213323 0.0361153 -0.084165 -0.211773 0.0351 -0.084765 -0.213623 0.0355957 -0.084765 -0.214977 0.03695 -0.084765 -0.214873 0.0388 -0.084165 -0.214977 0.04065 -0.084765 -0.213623 0.0420043 -0.084765 -0.211773 0.0419 -0.084165 -0.209335 0.0560165 -0.084765 -0.213323 0.0561153 -0.084165 -0.211773 0.0551 -0.084765 -0.213623 0.0555957 -0.084765 -0.214458 0.05725 -0.084165 -0.214977 0.05695 -0.084765 -0.214977 0.06065 -0.084765 -0.213323 0.0614846 -0.084165 -0.213623 0.0620043 -0.084765 -0.211773 0.0619 -0.084165 -0.211773 0.0625 -0.084765 -0.209923 0.0620043 -0.084765 -0.209089 0.06035 -0.084165 -0.208673 0.0588 -0.084165 -0.208073 0.0588 -0.084765 -0.239873 -0.0785 -0.082565 -0.239739 -0.079 -0.084465 -0.239373 -0.0793661 -0.082565 -0.239739 0.079 -0.084465 -0.239873 0.0785 -0.084465 0.237027 0.079366 -0.082565 0.236527 0.0795 -0.084465 0.237393 0.079 -0.084465 0.237393 0.079 -0.082565 0.237451 -0.0788827 -0.082565 0.237393 -0.079 -0.084465 0.236527 -0.0795 -0.082565 0.236909 -0.0794239 -0.082565 0.237027 -0.0793661 -0.082565 0.237027 -0.0793661 -0.084465 0.214186 0.0794659 -0.0825309 0.214427 0.079366 -0.079565 0.214793 0.079 -0.079565 0.214793 0.079 -0.082265 0.214851 -0.0788827 -0.082265 0.214793 -0.079 -0.079565 0.214427 -0.0793661 -0.079565 0.214309 -0.0794239 -0.0824888 -0.216273 -0.0795 -0.082565 -0.216273 -0.0795 -0.079565 -0.216656 -0.0794239 -0.0824888 -0.216773 -0.0793661 -0.079565 -0.217273 0.0785 -0.082265 -0.216773 0.079366 -0.082431 -0.216273 0.0795 -0.079565 -0.216532 0.0794659 -0.0825309 -0.177204 -0.0789143 -0.084465 -0.177564 -0.0792 -0.083265 -0.178228 -0.0794616 -0.0801034 -0.177853 -0.0793478 -0.0802172 0.174857 -0.0789143 -0.084465 0.175506 -0.0793478 -0.084465 0.175497 -0.0793442 -0.0802209 0.175881 -0.0794616 -0.0801034 0.174857 0.0789142 -0.084465 0.175506 0.0793477 -0.084465 0.175881 0.0794615 -0.0801034 -0.178228 0.0794615 -0.0801034 -0.178618 0.0795 -0.080065 0.0824668 0.000299958 -0.084765 0.156943 0.000599958 -0.084465 0.159143 0.00279996 -0.084465 0.158848 0.00169996 -0.084465 0.158193 0.000634894 -0.084765 -0.13919 0.000299958 -0.084765 -0.140031 0.000767423 -0.084465 -0.140957 0.00103219 -0.084765 0.159143 0.00280996 -0.084465 -0.14169 0.00279996 -0.084765 0.158499 0.00436559 -0.084465 -0.141095 0.00390996 -0.084465 -0.14044 0.00497502 -0.084765 -0.13919 0.00530996 -0.084765 0.0824668 0.00530996 -0.084765 0.144165 0.00530996 -0.084765 0.0824668 -0.00531004 -0.084765 -0.13919 -0.00501004 -0.084465 0.144165 -0.00531004 -0.084765 0.156943 -0.00501004 -0.084465 0.159143 -0.00281004 -0.084465 0.159108 -0.00406004 -0.084765 0.158193 -0.00497511 -0.084765 -0.140745 -0.00436568 -0.084465 -0.14169 -0.00281004 -0.084765 0.159143 -0.00280004 -0.084465 0.159443 -0.00280004 -0.084765 0.159443 -0.00281004 -0.084765 -0.14139 -0.00280004 -0.084465 0.158043 -0.000894786 -0.084465 0.158193 -0.000634978 -0.084765 0.159108 -0.00155004 -0.084765 -0.14044 -0.000634978 -0.084765 0.0824668 0.0564 -0.084765 0.144165 0.0564 -0.084765 0.156943 0.0564 -0.084765 0.156943 0.0567 -0.084465 0.158848 0.0578 -0.084465 0.158499 0.0573443 -0.084465 0.158043 0.0569947 -0.084465 -0.15929 0.0567 -0.084465 -0.160246 0.0565903 -0.084765 -0.160845 0.0573443 -0.084465 -0.16149 0.0589 -0.084465 0.159443 0.0592 -0.084765 -0.16149 0.0592 -0.084465 0.157785 0.0612325 -0.084465 0.1579 0.0615097 -0.084765 0.158499 0.0607556 -0.084465 0.158711 0.0609677 -0.084765 0.159253 0.0601567 -0.084765 0.159143 0.0592 -0.084465 -0.16179 0.0592 -0.084765 -0.161455 0.06045 -0.084765 0.144165 0.0617 -0.084765 0.156943 0.0614 -0.084465 0.0824668 0.0617 -0.084765 0.0824668 0.05079 -0.084765 -0.15929 0.05109 -0.084465 0.156943 0.05079 -0.084765 0.158848 0.05219 -0.084465 0.158193 0.0511249 -0.084765 0.156943 0.05109 -0.084465 -0.15929 0.05079 -0.084765 -0.160246 0.0509803 -0.084765 -0.161322 0.0524481 -0.084465 0.158043 0.0552052 -0.084465 0.158193 0.055465 -0.084765 0.159108 0.05455 -0.084765 0.159143 0.0533 -0.084465 -0.16179 0.0533 -0.084765 -0.161322 0.0541419 -0.084465 -0.161599 0.0542567 -0.084765 -0.160131 0.0553325 -0.084465 -0.160246 0.0556097 -0.084765 -0.15929 0.0555 -0.084465 0.0824668 0.0558 -0.084765 0.156943 0.0555 -0.084465 -0.15929 0.04548 -0.084465 0.0824668 0.04518 -0.084765 0.156943 0.04548 -0.084465 0.144165 0.04518 -0.084765 0.156943 0.04518 -0.084765 -0.16179 0.04768 -0.084765 0.159143 0.04769 -0.084465 0.159443 0.04769 -0.084765 0.159443 0.04768 -0.084765 -0.16149 0.04769 -0.084465 0.156943 0.04989 -0.084465 0.158711 0.0494577 -0.084765 0.159253 0.0486467 -0.084765 -0.161195 0.04879 -0.084465 -0.16054 0.049855 -0.084765 -0.15929 0.05019 -0.084765 0.0824668 0.05019 -0.084765 -0.15929 0.04989 -0.084465 0.156943 0.05019 -0.084765 -0.15929 0.03987 -0.084465 0.156943 0.03987 -0.084465 0.159108 0.04082 -0.084765 -0.15929 0.03957 -0.084765 -0.160131 0.0400374 -0.084465 -0.160246 0.0397603 -0.084765 -0.161057 0.0403022 -0.084765 -0.16179 0.04207 -0.084765 0.159143 0.04208 -0.084465 0.159443 0.04207 -0.084765 -0.16149 0.04207 -0.084465 0.158043 0.0439852 -0.084465 0.158848 0.04318 -0.084465 0.158193 0.044245 -0.084765 -0.161322 0.0429219 -0.084465 -0.160845 0.0436356 -0.084465 -0.161057 0.0438477 -0.084765 -0.160131 0.0441125 -0.084465 0.156943 0.04458 -0.084765 0.156943 0.03426 -0.084465 0.144165 0.03396 -0.084765 0.158193 0.0342949 -0.084765 0.159143 0.03646 -0.084465 0.159443 0.03646 -0.084765 0.158848 0.03536 -0.084465 0.159108 0.03521 -0.084765 0.158499 0.0349043 -0.084465 0.158043 0.0345547 -0.084465 -0.13919 0.03426 -0.084465 -0.13919 0.03396 -0.084765 -0.14029 0.0345547 -0.084465 -0.14044 0.0342949 -0.084765 -0.141355 0.03521 -0.084765 -0.14139 0.03647 -0.084465 0.156943 0.03867 -0.084465 0.158711 0.0382377 -0.084765 0.159253 0.0374267 -0.084765 0.159443 0.03647 -0.084765 -0.13919 0.03867 -0.084465 -0.13919 0.02865 -0.084465 0.156943 0.02835 -0.084765 0.158848 0.02975 -0.084465 0.159108 0.0296 -0.084765 0.158043 0.0289447 -0.084465 -0.140031 0.0288174 -0.084465 -0.140745 0.0292943 -0.084465 -0.140957 0.0290822 -0.084765 -0.141222 0.0300081 -0.084465 -0.141499 0.0298932 -0.084765 -0.14139 0.03086 -0.084465 -0.14139 0.03085 -0.084465 0.158976 0.0317019 -0.084465 0.159253 0.0318167 -0.084765 0.159443 0.03086 -0.084765 -0.14169 0.03086 -0.084765 -0.141095 0.03196 -0.084465 -0.13919 0.03336 -0.084765 -0.13919 0.03306 -0.084465 0.0824668 0.03336 -0.084765 -0.13919 0.02304 -0.084465 0.156943 0.02274 -0.084765 -0.13919 0.02274 -0.084765 -0.14169 0.02524 -0.084765 -0.14139 0.02524 -0.084465 0.158193 0.027415 -0.084765 0.158848 0.02635 -0.084465 0.159108 0.0265 -0.084765 -0.141355 0.0265 -0.084765 -0.14029 0.0271552 -0.084465 -0.13919 0.02775 -0.084765 -0.13919 0.01743 -0.084465 0.0824668 0.01713 -0.084765 0.156943 0.01713 -0.084765 0.158043 0.0177247 -0.084465 0.158193 0.0174649 -0.084765 0.159443 0.01963 -0.084765 0.158848 0.01853 -0.084465 0.158499 0.0180743 -0.084465 0.159108 0.01838 -0.084765 0.159143 0.01964 -0.084465 -0.14169 0.01964 -0.084765 -0.14169 0.01963 -0.084765 0.1579 0.0219497 -0.084765 0.158976 0.0204819 -0.084465 0.159253 0.0205967 -0.084765 0.159443 0.01964 -0.084765 -0.14139 0.01964 -0.084465 -0.141095 0.02074 -0.084465 -0.141355 0.02089 -0.084765 -0.14044 0.021805 -0.084765 -0.14029 0.0215452 -0.084465 -0.13919 0.02184 -0.084465 0.0824668 0.02214 -0.084765 -0.13919 0.02214 -0.084765 0.0824668 0.01152 -0.084765 0.156943 0.01182 -0.084465 0.158976 0.0131781 -0.084465 0.158499 0.0124643 -0.084465 0.159253 0.0130632 -0.084765 0.157785 0.0119874 -0.084465 0.158711 0.0122522 -0.084765 -0.140146 0.0117103 -0.084765 -0.141222 0.0131781 -0.084465 -0.141499 0.0130632 -0.084765 -0.14169 0.01402 -0.084765 0.159143 0.01402 -0.084465 0.159443 0.01403 -0.084765 0.158193 0.016195 -0.084765 0.159143 0.01403 -0.084465 -0.14044 0.016195 -0.084765 -0.13919 0.01623 -0.084465 -0.13919 0.01653 -0.084765 0.156943 0.01653 -0.084765 -0.13919 0.00590996 -0.084765 0.0824668 0.00590996 -0.084765 0.156943 0.00590996 -0.084765 0.158193 0.00624489 -0.084765 0.159108 0.00715996 -0.084765 -0.141095 0.00730996 -0.084465 0.159443 0.00841996 -0.084765 -0.14139 0.00841996 -0.084465 -0.14139 0.00840996 -0.084465 0.157785 0.0104525 -0.084465 0.158499 0.00997559 -0.084465 0.158711 0.0101877 -0.084765 0.159143 0.00841996 -0.084465 0.159253 0.00937667 -0.084765 -0.141095 0.00951996 -0.084465 -0.141355 0.00966996 -0.084765 -0.14029 0.0103252 -0.084465 -0.13919 0.01092 -0.084765 0.156943 0.01062 -0.084465 -0.13919 -0.01092 -0.084765 -0.13919 -0.01062 -0.084465 0.144165 -0.01092 -0.084765 0.158848 -0.00952004 -0.084465 0.159108 -0.00967004 -0.084765 0.158499 -0.00997568 -0.084465 -0.14029 -0.0103253 -0.084465 -0.14044 -0.0105851 -0.084765 -0.141095 -0.00952004 -0.084465 -0.141355 -0.00967004 -0.084765 -0.14139 -0.00842004 -0.084465 0.159143 -0.00842004 -0.084465 0.159443 -0.00842004 -0.084765 0.157785 -0.00637751 -0.084465 0.158711 -0.00664228 -0.084765 0.159253 -0.00745333 -0.084765 -0.141355 -0.00716004 -0.084765 -0.14029 -0.00650479 -0.084465 -0.14044 -0.00624498 -0.084765 0.156943 -0.00591004 -0.084765 0.158193 -0.0161951 -0.084765 0.158043 -0.0159353 -0.084465 0.156943 -0.01623 -0.084465 -0.13919 -0.01653 -0.084765 -0.140745 -0.0155857 -0.084465 -0.140957 -0.0157978 -0.084765 -0.14139 -0.01403 -0.084465 0.159443 -0.01403 -0.084765 -0.14169 -0.01402 -0.084765 -0.14139 -0.01402 -0.084465 0.156943 -0.01152 -0.084765 0.158043 -0.0121148 -0.084465 0.158193 -0.011855 -0.084765 0.159108 -0.01277 -0.084765 -0.14029 -0.0121148 -0.084465 0.144165 -0.01152 -0.084765 0.156943 -0.01182 -0.084465 -0.13919 -0.01182 -0.084465 0.0824668 -0.01152 -0.084765 0.144165 -0.02214 -0.084765 0.156943 -0.02214 -0.084765 0.158043 -0.0215453 -0.084465 0.159108 -0.02089 -0.084765 -0.14029 -0.0215453 -0.084465 -0.14044 -0.0218051 -0.084765 -0.141355 -0.02089 -0.084765 -0.14169 -0.01964 -0.084765 0.159443 -0.01963 -0.084765 -0.14139 -0.01964 -0.084465 0.1579 -0.0173203 -0.084765 0.158499 -0.0180744 -0.084465 0.159253 -0.0186733 -0.084765 -0.14169 -0.01963 -0.084765 -0.141355 -0.01838 -0.084765 -0.13919 -0.01743 -0.084465 -0.14044 -0.017465 -0.084765 -0.13919 -0.01713 -0.084765 0.144165 -0.01713 -0.084765 0.156943 -0.01743 -0.084465 0.0824668 -0.02775 -0.084765 0.156943 -0.02775 -0.084765 0.158848 -0.02635 -0.084465 0.158193 -0.0274151 -0.084765 0.156943 -0.02745 -0.084465 -0.13919 -0.02775 -0.084765 -0.140146 -0.0275597 -0.084765 -0.140957 -0.0270178 -0.084765 -0.140745 -0.0268057 -0.084465 -0.141222 -0.0260919 -0.084465 -0.141499 -0.0262068 -0.084765 0.159443 -0.02524 -0.084765 -0.14139 -0.02525 -0.084465 0.159253 -0.0242833 -0.084765 0.158711 -0.0234723 -0.084765 0.158499 -0.0236844 -0.084465 0.1579 -0.0229303 -0.084765 0.157785 -0.0232075 -0.084465 -0.14169 -0.02524 -0.084765 -0.141355 -0.02399 -0.084765 -0.14029 -0.0233348 -0.084465 -0.14044 -0.023075 -0.084765 -0.13919 -0.02274 -0.084765 -0.13919 -0.02304 -0.084465 0.0824668 -0.02274 -0.084765 0.144165 -0.02274 -0.084765 0.156943 -0.02304 -0.084465 0.156943 -0.02274 -0.084765 -0.13919 -0.03306 -0.084465 0.144165 -0.03336 -0.084765 0.156943 -0.03336 -0.084765 0.158043 -0.0327653 -0.084465 0.159143 -0.03086 -0.084465 0.158848 -0.03196 -0.084465 0.159108 -0.03211 -0.084765 0.158499 -0.0324157 -0.084465 -0.13919 -0.03336 -0.084765 -0.14029 -0.0327653 -0.084465 -0.141095 -0.03196 -0.084465 -0.14139 -0.03086 -0.084465 -0.14169 -0.03086 -0.084765 0.159443 -0.03086 -0.084765 0.158976 -0.0300081 -0.084465 0.159253 -0.0298933 -0.084765 0.159143 -0.03085 -0.084465 0.159443 -0.03085 -0.084765 -0.14029 -0.0289448 -0.084465 -0.13919 -0.02835 -0.084765 0.0824668 -0.02835 -0.084765 0.144165 -0.02835 -0.084765 0.156943 -0.02865 -0.084465 -0.13919 -0.03867 -0.084465 0.156943 -0.03867 -0.084465 0.156943 -0.03897 -0.084765 0.159443 -0.03647 -0.084765 0.158499 -0.0380257 -0.084465 -0.14029 -0.0383753 -0.084465 0.158848 -0.03536 -0.084465 0.159108 -0.03521 -0.084765 -0.141095 -0.03536 -0.084465 -0.14169 -0.03646 -0.084765 -0.141355 -0.03521 -0.084765 -0.14044 -0.034295 -0.084765 0.156943 -0.03426 -0.084465 0.144165 -0.03396 -0.084765 -0.13919 -0.03396 -0.084765 -0.15929 -0.04458 -0.084765 0.0824668 -0.04458 -0.084765 0.144165 -0.04458 -0.084765 0.156943 -0.04458 -0.084765 0.159143 -0.04208 -0.084465 0.159443 -0.04208 -0.084765 0.158976 -0.0429219 -0.084465 -0.16149 -0.04208 -0.084465 -0.16179 -0.04208 -0.084765 0.159143 -0.04207 -0.084465 0.159443 -0.04207 -0.084765 -0.16179 -0.04207 -0.084765 0.156943 -0.03957 -0.084765 0.159108 -0.04082 -0.084765 -0.161599 -0.0411133 -0.084765 -0.161322 -0.0412281 -0.084465 -0.161057 -0.0403023 -0.084765 -0.160131 -0.0400375 -0.084465 -0.160246 -0.0397603 -0.084765 -0.15929 -0.03987 -0.084465 0.156943 -0.03987 -0.084465 0.144165 -0.03957 -0.084765 0.0824668 -0.05019 -0.084765 0.144165 -0.05019 -0.084765 0.159443 -0.04769 -0.084765 0.158499 -0.0492457 -0.084465 0.157785 -0.0497226 -0.084465 0.1579 -0.0499997 -0.084765 0.156943 -0.04989 -0.084465 0.156943 -0.05019 -0.084765 -0.16039 -0.0495953 -0.084465 -0.161195 -0.04879 -0.084465 -0.16149 -0.04769 -0.084465 -0.161455 -0.04894 -0.084765 0.159143 -0.04768 -0.084465 -0.16179 -0.04769 -0.084765 0.156943 -0.04518 -0.084765 0.158043 -0.0457748 -0.084465 0.158848 -0.04658 -0.084465 -0.160845 -0.0461244 -0.084465 -0.161057 -0.0459123 -0.084765 -0.160246 -0.0453703 -0.084765 0.144165 -0.04518 -0.084765 0.144165 -0.0558 -0.084765 0.156943 -0.0558 -0.084765 0.156943 -0.0555 -0.084465 0.1579 -0.0556097 -0.084765 0.158711 -0.0550678 -0.084765 0.159143 -0.0533 -0.084465 0.159443 -0.0533 -0.084765 -0.16039 -0.0552053 -0.084465 -0.16054 -0.0554651 -0.084765 -0.161455 -0.05455 -0.084765 -0.16179 -0.0533 -0.084765 0.156943 -0.05079 -0.084765 0.158043 -0.0513848 -0.084465 0.159143 -0.05329 -0.084465 -0.16149 -0.05329 -0.084465 -0.161599 -0.0523333 -0.084765 -0.160845 -0.0517344 -0.084465 -0.160246 -0.0509803 -0.084765 -0.15929 -0.05109 -0.084465 -0.15929 -0.05079 -0.084765 0.144165 -0.05079 -0.084765 0.0824668 -0.05079 -0.084765 0.156943 -0.05109 -0.084465 0.0824668 -0.0617 -0.084765 0.159443 -0.0592 -0.084765 0.1579 -0.0615097 -0.084765 -0.15929 -0.0617 -0.084765 -0.16054 -0.0613651 -0.084765 -0.161195 -0.0603 -0.084465 -0.16149 -0.0592 -0.084465 0.159443 -0.0589 -0.084765 -0.16179 -0.0592 -0.084765 0.158193 -0.056735 -0.084765 0.159108 -0.05765 -0.084765 -0.161599 -0.0579433 -0.084765 -0.161322 -0.0580581 -0.084465 -0.161057 -0.0571323 -0.084765 0.144165 -0.0564 -0.084765 -0.15929 -0.0567 -0.084465 -0.214879 0.0185923 -0.082565 -0.214879 0.0185923 -0.079565 -0.216099 0.0191502 -0.082265 -0.216111 0.019159 -0.079565 -0.216111 0.019159 -0.082265 -0.216967 0.0202099 -0.082265 -0.216111 -0.0191591 -0.082265 -0.216967 -0.02021 -0.079565 -0.216099 -0.0191503 -0.082265 -0.216111 -0.0191591 -0.079565 0.213764 0.019159 -0.082265 0.21462 0.0202099 -0.082265 0.21462 0.0202099 -0.079565 0.212533 -0.0185924 -0.082565 0.213764 -0.0191591 -0.082265 0.21462 -0.02021 -0.079565 0.214927 -0.0215306 -0.082265 -0.217273 0.0785 -0.079565 -0.216973 0.038025 -0.079265 -0.217273 0.0215305 -0.079565 -0.216973 0.0215305 -0.079265 -0.216273 0.0792 -0.079265 -0.216773 0.079366 -0.079565 -0.217139 0.079 -0.079565 -0.216879 0.07885 -0.079265 -0.216967 0.0202099 -0.079565 -0.216698 0.020342 -0.079265 -0.215927 0.0193961 -0.079265 0.212302 0.0792 -0.079265 0.213927 0.0792 -0.079265 -0.200506 0.0792 -0.079265 -0.0848132 0.0792 -0.079265 -0.190304 0.013526 -0.079565 0.214277 0.0791062 -0.079265 -0.17939 0.000499958 -0.079265 -0.180778 0.00648677 -0.079265 0.214927 0.0785 -0.079565 0.214627 0.065725 -0.079265 -0.17939 -4.19898e-08 -0.079265 0.213764 0.019159 -0.079565 0.212472 0.0188861 -0.079265 0.21358 0.0193961 -0.079265 0.214927 0.0215305 -0.079565 0.214627 0.0215305 -0.079265 -0.190304 -0.0135261 -0.079565 -0.181048 -0.00635479 -0.079565 -0.180778 -0.00648685 -0.079265 -0.17939 -0.000500042 -0.079265 0.187897 0.0138198 -0.079265 0.187958 0.013526 -0.079565 -0.190244 -0.0138199 -0.079265 -0.200506 -0.0159357 -0.079265 0.178432 0.00648677 -0.079265 -0.214818 -0.0188862 -0.079265 -0.214879 -0.0185924 -0.079565 -0.215927 -0.0193962 -0.079265 0.177343 -0.000500042 -0.079565 -0.217273 -0.0785 -0.079565 -0.216973 -0.038025 -0.079265 -0.217273 -0.0215306 -0.079565 0.178701 -0.00635479 -0.079565 0.182314 -0.0112511 -0.079265 0.187958 -0.0135261 -0.079565 -0.217139 -0.079 -0.079565 -0.21698 -0.0792072 -0.079565 -0.216623 -0.0791063 -0.079265 0.212533 -0.0185924 -0.079565 0.187897 -0.0138199 -0.079265 0.213927 -0.0792 -0.079265 0.213927 -0.0795 -0.079565 0.212302 -0.0792 -0.079265 0.205052 -0.0792 -0.079265 -0.178515 -0.0792 -0.079265 -0.207398 -0.0792 -0.079265 0.214927 -0.0215306 -0.079565 0.214627 -0.0215306 -0.079265 0.214351 -0.0203421 -0.079265 0.213764 -0.0191591 -0.079565 0.21358 -0.0193962 -0.079265 0.214277 -0.0791063 -0.079265 0.214634 -0.0792072 -0.079565 0.214533 -0.07885 -0.079265 0.214927 -0.0785 -0.079565 0.214627 -0.0785 -0.079265 0.214627 -0.065725 -0.079265 0.235072 -0.0235454 -0.082265 0.213174 -0.0188023 -0.082489 0.237227 -0.0261898 -0.082265 0.236951 -0.0250012 -0.082265 0.236795 -0.0791468 -0.082265 0.237234 -0.0792072 -0.082565 0.237393 -0.079 -0.082565 0.237174 -0.0787679 -0.082265 0.236527 -0.0792 -0.082265 0.214122 -0.0794808 -0.0825458 0.213927 -0.0795 -0.082565 0.213174 0.0188022 -0.082489 0.237227 0.0261897 -0.082265 0.237527 0.0261897 -0.082565 0.237133 0.07885 -0.082265 0.236527 0.0795 -0.082565 0.236527 0.0792 -0.082265 0.214427 0.079366 -0.082431 -0.216987 -0.0792 -0.082265 -0.216468 -0.0794808 -0.0825458 -0.238873 -0.0795 -0.082565 -0.239739 -0.079 -0.082565 -0.239479 -0.07885 -0.082265 -0.239873 -0.0261898 -0.082565 -0.238711 -0.0238182 -0.082565 -0.238527 -0.0240554 -0.082265 -0.239298 -0.0250012 -0.082265 -0.215521 -0.0188023 -0.082489 -0.237479 -0.0232516 -0.082565 -0.238873 0.0795 -0.082565 -0.239373 0.079366 -0.082565 -0.239739 0.079 -0.082565 -0.239223 0.0791062 -0.082265 -0.239479 0.07885 -0.082265 -0.239573 0.0261897 -0.082265 -0.238527 0.0240553 -0.082265 -0.237418 0.0235453 -0.082265 -0.215521 0.0188022 -0.082489 0.236527 0.0792 -0.084765 0.17507 0.078702 -0.084765 0.176272 0.0795 -0.084465 0.237027 0.079366 -0.084465 0.236877 0.0791062 -0.084765 0.17318 0.076813 -0.084765 0.237227 0.0261897 -0.084765 0.237227 0.02805 -0.084765 0.237527 0.0261897 -0.084465 0.237227 0.03366 -0.084765 0.237227 0.03485 -0.084765 0.237227 0.06445 -0.084765 0.237227 0.04574 -0.084765 0.237527 0.0785 -0.084465 0.237227 0.0532 -0.084765 0.171948 0.0759892 -0.084765 0.236951 0.0250012 -0.084765 0.236364 0.0238182 -0.084465 0.170493 0.0757 -0.084765 0.187897 0.0138198 -0.084765 0.235072 0.0235453 -0.084765 -0.175315 0.0770251 -0.084465 0.178701 0.00635471 -0.084465 0.182498 0.0110139 -0.084465 0.187958 0.013526 -0.084465 -0.177204 0.0789142 -0.084465 0.177043 0.000499958 -0.084765 0.177343 -0.000500042 -0.084465 -0.177853 0.0793477 -0.084465 -0.177967 0.0790706 -0.084765 -0.177416 0.078702 -0.084765 0.182498 -0.011014 -0.084465 0.182314 -0.0112511 -0.084765 0.178701 -0.00635479 -0.084465 0.178432 -0.00648685 -0.084765 -0.178618 0.0792 -0.084765 -0.178618 0.0795 -0.084465 0.235133 -0.0232516 -0.084465 0.235072 -0.0235454 -0.084765 0.187958 -0.0135261 -0.084465 -0.239573 0.0785 -0.084765 -0.239479 0.07885 -0.084765 -0.239373 0.079366 -0.084465 0.23618 -0.0240554 -0.084765 0.237227 -0.0261898 -0.084765 -0.239573 0.02805 -0.084765 -0.239873 0.0261897 -0.084465 -0.239573 0.0532 -0.084765 -0.239573 0.04574 -0.084765 0.237527 -0.0261898 -0.084465 0.237227 -0.02805 -0.084765 0.237227 -0.04354 -0.084765 0.237227 -0.03927 -0.084765 0.237227 -0.037935 -0.084765 0.237527 -0.0785 -0.084465 0.237227 -0.0532 -0.084765 0.237227 -0.05049 -0.084765 -0.238527 0.0240553 -0.084765 -0.239573 0.0261897 -0.084765 0.237227 -0.0785 -0.084765 -0.190244 0.0138198 -0.084765 -0.184844 0.0110139 -0.084465 -0.18466 0.011251 -0.084765 -0.180778 0.00648677 -0.084765 0.175621 -0.0790706 -0.084765 -0.17969 0.000499958 -0.084465 0.173767 -0.0774 -0.084765 0.17318 -0.076813 -0.084765 -0.17969 -0.000500042 -0.084465 -0.17939 -0.000500042 -0.084765 -0.181048 -0.00635479 -0.084465 -0.180778 -0.00648685 -0.084765 -0.184844 -0.011014 -0.084465 -0.190304 -0.0135261 -0.084465 0.171833 -0.0762665 -0.084465 0.171948 -0.0759893 -0.084765 0.144165 -0.0757 -0.084765 0.170493 -0.0757 -0.084765 0.0824668 -0.0757 -0.084765 -0.17284 -0.076 -0.084465 -0.239567 -0.0248692 -0.084465 -0.238527 -0.0240554 -0.084765 -0.174179 -0.0762665 -0.084465 -0.175527 -0.076813 -0.084765 -0.174294 -0.0759893 -0.084765 -0.17284 -0.0757 -0.084765 -0.239573 -0.02805 -0.084765 -0.239573 -0.0532 -0.084765 -0.239573 -0.0561 -0.084765 -0.239573 -0.05049 -0.084765 -0.239573 -0.0621 -0.084765 -0.239873 -0.0785 -0.084465 -0.239573 -0.0774 -0.084765 -0.177416 -0.0787021 -0.084765 -0.176114 -0.0774 -0.084765 -0.238873 -0.0795 -0.084465 -0.239373 -0.0793661 -0.084465 -0.239223 -0.0791063 -0.084765 -0.239479 -0.07885 -0.084765 -0.177853 -0.0793478 -0.084465 -0.178618 -0.0792 -0.084765 -0.178618 -0.0795 -0.084465 -0.178618 -0.0795 -0.080065 -0.177564 -0.0792 -0.080365 -0.177844 0.0793441 -0.0802209 -0.177564 0.0792 -0.080365 0.175506 0.0793477 -0.0802172 0.175218 0.0792 -0.083265 0.0583294 0.0792 -0.083265 0.175218 0.0792 -0.080365 -0.0011732 0.0792 -0.083265 -0.0606758 0.0792 -0.083265 -0.177564 0.0792 -0.083265 -0.120178 0.076 -0.083265 0.170493 0.076 -0.083265 0.117832 0.0792 -0.083265 0.174857 0.0789142 -0.083265 -0.120178 0.0792 -0.083265 -0.175315 0.0770251 -0.083265 -0.177204 0.0789142 -0.083265 0.175218 -0.0792 -0.083265 -0.0011732 -0.0792 -0.083265 0.0583294 -0.0792 -0.083265 0.175218 -0.0792 -0.080365 0.170493 -0.076 -0.083265 -0.174179 -0.0762665 -0.083265 -0.120178 -0.0792 -0.083265 -0.177204 -0.0789143 -0.083265 -0.0606758 -0.0792 -0.083265 -0.0011732 -0.076 -0.083265 0.0583294 -0.076 -0.083265 0.117832 -0.076 -0.083265 0.117832 -0.0792 -0.083265 0.158499 0.0380256 -0.083265 0.158499 0.0349043 -0.083265 0.158976 0.0356181 -0.083265 -0.14029 0.0345547 -0.083265 -0.141095 0.03536 -0.083265 0.156943 0.03426 -0.083265 -0.13919 0.03867 -0.083265 -0.13919 0.03306 -0.083265 -0.14029 0.0327652 -0.083265 -0.141222 0.0300081 -0.083265 0.158043 0.0289447 -0.083265 -0.140745 0.0236843 -0.083265 -0.141222 0.0243981 -0.083265 -0.14029 0.0271552 -0.083265 -0.14139 0.02525 -0.083265 0.156943 0.02745 -0.083265 0.156943 0.02304 -0.083265 0.158043 0.0233347 -0.083265 0.159143 0.02524 -0.083265 0.158499 0.0180743 -0.083265 0.159143 0.01963 -0.083265 0.156943 0.02184 -0.083265 -0.141095 0.01853 -0.083265 -0.14139 0.01964 -0.083265 0.156943 0.01743 -0.083265 -0.14139 0.01963 -0.083265 0.157785 0.0119874 -0.083265 0.158043 0.0159352 -0.083265 0.158848 0.01513 -0.083265 0.159143 0.01403 -0.083265 0.159143 0.01402 -0.083265 0.156943 0.01182 -0.083265 0.158499 0.0124643 -0.083265 -0.13919 0.01182 -0.083265 -0.140031 0.0119874 -0.083265 -0.13919 0.01623 -0.083265 0.156943 0.01062 -0.083265 -0.141095 0.00951996 -0.083265 0.159143 0.00841996 -0.083265 0.157785 0.0104525 -0.083265 0.158976 0.00926186 -0.083265 0.159143 0.00840996 -0.083265 0.158499 0.00685432 -0.083265 -0.141095 0.00730996 -0.083265 -0.14139 0.00841996 -0.083265 -0.14029 0.00471521 -0.083265 -0.14139 0.00279996 -0.083265 0.156943 0.000599958 -0.083265 0.158499 0.00436559 -0.083265 -0.13919 0.000599958 -0.083265 -0.13919 0.00500996 -0.083265 -0.140745 0.00124432 -0.083265 -0.140745 -0.00436568 -0.083265 -0.141095 -0.00170004 -0.083265 -0.14139 -0.00280004 -0.083265 -0.141222 -0.00365195 -0.083265 0.158848 -0.00391004 -0.083265 0.156943 -0.00501004 -0.083265 0.158043 -0.000894786 -0.083265 -0.141222 -0.0148719 -0.083265 -0.14139 -0.01403 -0.083265 -0.141095 -0.01292 -0.083265 -0.14029 -0.0121148 -0.083265 -0.13919 -0.01182 -0.083265 -0.140031 -0.0160626 -0.083265 -0.13919 -0.01623 -0.083265 0.156943 -0.01182 -0.083265 0.158043 -0.0159353 -0.083265 0.159143 -0.01403 -0.083265 0.158848 -0.01292 -0.083265 -0.14139 -0.01963 -0.083265 -0.141095 -0.01853 -0.083265 0.156943 -0.01743 -0.083265 0.159143 -0.01963 -0.083265 0.158499 -0.0180744 -0.083265 -0.141095 -0.02074 -0.083265 0.158976 -0.0204819 -0.083265 -0.14139 -0.02524 -0.083265 -0.141095 -0.02414 -0.083265 -0.14029 -0.0233348 -0.083265 0.158848 -0.02414 -0.083265 0.159143 -0.02524 -0.083265 0.156943 -0.02304 -0.083265 0.159143 -0.02525 -0.083265 -0.14139 -0.02525 -0.083265 -0.13919 -0.02745 -0.083265 -0.140031 -0.0272826 -0.083265 0.156943 -0.02865 -0.083265 0.158499 -0.0292944 -0.083265 0.156943 -0.03306 -0.083265 0.157785 -0.0288175 -0.083265 0.157785 -0.0328926 -0.083265 0.159143 -0.03086 -0.083265 -0.13919 -0.03306 -0.083265 -0.141095 -0.02975 -0.083265 -0.13919 -0.02865 -0.083265 -0.14139 -0.03085 -0.083265 -0.14139 -0.03086 -0.083265 0.158976 -0.00756814 -0.083265 0.157785 -0.00637751 -0.083265 0.158499 -0.00997568 -0.083265 0.158976 -0.00926195 -0.083265 0.159143 -0.00842004 -0.083265 0.159143 -0.00841004 -0.083265 -0.141095 -0.00952004 -0.083265 -0.13919 -0.01062 -0.083265 0.156943 -0.01062 -0.083265 -0.13919 -0.00621004 -0.083265 0.159143 -0.03647 -0.083265 0.156943 -0.03426 -0.083265 -0.13919 -0.03867 -0.083265 -0.14139 -0.03647 -0.083265 -0.141095 -0.03757 -0.083265 0.158848 -0.0578 -0.083265 0.159143 -0.0592 -0.083265 0.156943 -0.0614 -0.083265 -0.15929 -0.0614 -0.083265 -0.16149 -0.0589 -0.083265 -0.16039 -0.0552053 -0.083265 -0.15929 -0.0555 -0.083265 -0.16149 -0.0533 -0.083265 -0.160845 -0.0517344 -0.083265 -0.160131 -0.0512575 -0.083265 0.158043 -0.0552053 -0.083265 0.159143 -0.0533 -0.083265 -0.16149 -0.05329 -0.083265 -0.15929 -0.05109 -0.083265 0.156943 -0.04428 -0.083265 -0.15929 -0.04428 -0.083265 -0.161322 -0.0412281 -0.083265 -0.160131 -0.0400375 -0.083265 0.158043 -0.0401648 -0.083265 0.158848 -0.04318 -0.083265 0.158848 -0.04658 -0.083265 -0.15929 -0.04548 -0.083265 0.156943 -0.04548 -0.083265 0.158976 -0.0485319 -0.083265 0.158499 -0.0492457 -0.083265 -0.161195 -0.04879 -0.083265 -0.16149 -0.04769 -0.083265 -0.160845 -0.0461244 -0.083265 -0.160131 -0.0456475 -0.083265 -0.16149 0.04207 -0.083265 -0.160131 0.0400374 -0.083265 -0.160845 0.0405143 -0.083265 0.156943 0.03987 -0.083265 -0.160131 0.0441125 -0.083265 -0.161322 0.0429219 -0.083265 -0.15929 0.04428 -0.083265 0.158043 0.0401647 -0.083265 0.156943 0.04548 -0.083265 0.159143 0.04768 -0.083265 0.157785 0.0456474 -0.083265 -0.160131 0.0456474 -0.083265 -0.16149 0.04769 -0.083265 -0.16039 0.0495952 -0.083265 -0.15929 0.04989 -0.083265 -0.16149 0.04768 -0.083265 0.159143 0.04769 -0.083265 0.157785 0.0497225 -0.083265 0.158499 0.0492456 -0.083265 -0.161195 0.0603 -0.083265 0.158499 0.0607556 -0.083265 0.158976 0.0600419 -0.083265 -0.16149 0.0589 -0.083265 -0.16039 0.0611052 -0.083265 0.156943 0.0567 -0.083265 -0.15929 0.0567 -0.083265 -0.15929 0.05109 -0.083265 0.158043 0.0552052 -0.083265 0.158848 0.0544 -0.083265 -0.160845 0.0517343 -0.083265 0.159143 0.05329 -0.083265 0.156943 0.05109 -0.083265 -0.213323 0.0414846 -0.083265 -0.213323 0.0361153 -0.083265 -0.214458 0.03725 -0.083265 -0.210223 0.0361153 -0.083265 -0.211773 0.0388 -0.083265 -0.208673 0.0388 -0.083265 -0.209089 0.03725 -0.083265 -0.213323 0.0614846 -0.083265 -0.211773 0.0588 -0.083265 -0.211773 0.0619 -0.083265 -0.210223 0.0614846 -0.083265 -0.214458 0.06035 -0.083265 -0.213323 0.0561153 -0.083265 0.210977 0.0414846 -0.083265 0.206742 0.03725 -0.083265 0.209427 0.0388 -0.083265 0.206327 0.0388 -0.083265 0.206742 0.04035 -0.083265 0.209427 0.0357 -0.083265 0.206742 0.06035 -0.083265 0.207877 0.0614846 -0.083265 0.206742 0.05725 -0.083265 0.210977 0.0561153 -0.083265 0.212111 0.06035 -0.083265 0.209427 0.0588 -0.083265 0.212527 0.0588 -0.083265 0.212111 0.05725 -0.083265 -0.211773 -0.0388 -0.083265 -0.211773 -0.0357 -0.083265 -0.214873 -0.0388 -0.083265 -0.214458 -0.03725 -0.083265 -0.209089 -0.04035 -0.083265 -0.210223 -0.0414847 -0.083265 -0.211773 -0.0588 -0.083265 -0.214458 -0.06035 -0.083265 -0.214873 -0.0588 -0.083265 -0.210223 -0.0614847 -0.083265 -0.213323 -0.0614847 -0.083265 -0.208673 -0.0588 -0.083265 0.206742 -0.03725 -0.083265 0.210977 -0.0361154 -0.083265 0.206327 -0.0388 -0.083265 0.212111 -0.03725 -0.083265 0.209427 -0.0388 -0.083265 0.207877 -0.0561154 -0.083265 0.210977 -0.0561154 -0.083265 0.206742 -0.06035 -0.083265 0.206327 -0.0588 -0.083265 0.206742 -0.05725 -0.083265 0.212111 -0.06035 -0.083265 0.209427 -0.0588 -0.083265 0.212111 -0.05725 -0.083265 -0.125508 -0.0729486 -0.083265 -0.124833 -0.0741177 -0.083265 -0.126633 -0.07325 -0.083265 -0.127758 -0.0729486 -0.083265 -0.128433 -0.0741177 -0.083265 -0.128883 -0.071 -0.083265 -0.128582 -0.069875 -0.083265 -0.129751 -0.0692 -0.083265 -0.127758 -0.0690515 -0.083265 -0.128433 -0.0678824 -0.083265 -0.126633 -0.0674 -0.083265 -0.126633 -0.06875 -0.083265 -0.125508 -0.0690515 -0.083265 -0.124685 -0.069875 -0.083265 -0.123516 -0.0692 -0.083265 -0.0461109 -0.0728 -0.083265 -0.0465932 -0.071 -0.083265 -0.0441182 -0.0690515 -0.083265 -0.0461109 -0.0692 -0.083265 -0.0447932 -0.0678824 -0.083265 -0.0410446 -0.069875 -0.083265 -0.0393932 -0.071 -0.083265 -0.0429932 -0.07325 -0.083265 -0.0429932 -0.0746 -0.083265 -0.0441182 -0.0729486 -0.083265 -0.0447932 -0.0741177 -0.083265 0.0406468 -0.0746 -0.083265 0.0388468 -0.0678824 -0.083265 0.0406468 -0.0674 -0.083265 0.0424468 -0.0678824 -0.083265 0.0428968 -0.071 -0.083265 0.0417718 -0.0729486 -0.083265 0.124287 -0.0746 -0.083265 0.121169 -0.0728 -0.083265 0.122338 -0.069875 -0.083265 0.122487 -0.0678824 -0.083265 0.124287 -0.06875 -0.083265 0.124287 -0.0674 -0.083265 0.125412 -0.0690515 -0.083265 0.126087 -0.0678824 -0.083265 0.127404 -0.0692 -0.083265 0.127404 -0.0728 -0.083265 0.122338 0.069875 -0.083265 0.122037 0.071 -0.083265 0.124287 0.07325 -0.083265 0.122487 0.0741177 -0.083265 0.125412 0.0729485 -0.083265 0.126087 0.0741177 -0.083265 0.126235 0.072125 -0.083265 0.127404 0.0728 -0.083265 0.126537 0.071 -0.083265 0.127887 0.071 -0.083265 0.127404 0.0692 -0.083265 0.124287 0.0674 -0.083265 0.122487 0.0678823 -0.083265 0.0388468 0.0678823 -0.083265 0.0383968 0.071 -0.083265 0.0386982 0.072125 -0.083265 0.0395218 0.0729485 -0.083265 0.0406468 0.07325 -0.083265 0.0417718 0.0729485 -0.083265 0.0406468 0.0746 -0.083265 0.0425954 0.072125 -0.083265 0.0442468 0.071 -0.083265 0.0437645 0.0692 -0.083265 0.0417718 0.0690514 -0.083265 0.0424468 0.0678823 -0.083265 -0.0418682 0.0690514 -0.083265 -0.0441182 0.0690514 -0.083265 -0.0429932 0.0674 -0.083265 -0.0447932 0.0678823 -0.083265 -0.0461109 0.0692 -0.083265 -0.0465932 0.071 -0.083265 -0.0461109 0.0728 -0.083265 -0.0429932 0.0746 -0.083265 -0.0418682 0.0729485 -0.083265 -0.0410446 0.072125 -0.083265 -0.0407432 0.071 -0.083265 -0.124833 0.0678823 -0.083265 -0.126633 0.0674 -0.083265 -0.127758 0.0729485 -0.083265 -0.128433 0.0741177 -0.083265 -0.126633 0.0746 -0.083265 -0.124833 0.0741177 -0.083265 -0.123516 0.0728 -0.083265 -0.124383 0.071 -0.083265 -0.123033 0.071 -0.083265 -0.123516 0.0692 -0.083265 -0.125508 0.0690514 -0.083265 -0.212222 -0.072125 -0.083265 -0.213391 -0.0728 -0.083265 -0.212523 -0.071 -0.083265 -0.212222 -0.069875 -0.083265 -0.211398 -0.0690515 -0.083265 -0.210273 -0.06875 -0.083265 -0.210273 -0.0674 -0.083265 -0.209148 -0.0690515 -0.083265 -0.208473 -0.0678824 -0.083265 -0.207156 -0.0692 -0.083265 -0.208023 -0.071 -0.083265 -0.208325 -0.072125 -0.083265 -0.210273 -0.0746 -0.083265 -0.212073 -0.0741177 -0.083265 0.209875 -0.069875 -0.083265 0.209727 -0.0678824 -0.083265 0.209875 -0.072125 -0.083265 0.211044 -0.0728 -0.083265 0.209052 -0.0729486 -0.083265 0.207927 -0.0746 -0.083265 0.205978 -0.069875 -0.083265 0.209052 -0.0690515 -0.083265 -0.209148 0.0690514 -0.083265 -0.210273 0.0674 -0.083265 -0.212073 0.0678823 -0.083265 -0.212523 0.071 -0.083265 -0.213873 0.071 -0.083265 -0.211398 0.0729485 -0.083265 -0.212073 0.0741177 -0.083265 -0.210273 0.0746 -0.083265 -0.209148 0.0729485 -0.083265 -0.208473 0.0741177 -0.083265 -0.208023 0.071 -0.083265 -0.208325 0.069875 -0.083265 0.209727 0.0678823 -0.083265 0.205677 0.071 -0.083265 0.205978 0.072125 -0.083265 0.206802 0.0729485 -0.083265 0.207927 0.07325 -0.083265 0.207927 0.0746 -0.083265 0.209052 0.0729485 -0.083265 0.209727 0.0741177 -0.083265 0.211527 0.071 -0.083265 0.211044 0.0692 -0.083265 -0.19559 -0.03 -0.083265 -0.19199 -0.02775 -0.083265 -0.190865 -0.0280515 -0.083265 -0.190041 -0.028875 -0.083265 -0.188872 -0.0282 -0.083265 -0.190041 -0.031125 -0.083265 -0.190865 -0.0319486 -0.083265 -0.19199 -0.03225 -0.083265 -0.19199 -0.0336 -0.083265 -0.19379 -0.0331177 -0.083265 -0.193115 -0.0319486 -0.083265 -0.193938 -0.031125 -0.083265 -0.19424 -0.03 -0.083265 -0.193115 0.0280514 -0.083265 -0.19559 0.03 -0.083265 -0.193938 0.031125 -0.083265 -0.195107 0.0318 -0.083265 -0.19199 0.0336 -0.083265 -0.190041 0.031125 -0.083265 -0.188872 0.0318 -0.083265 -0.18839 0.03 -0.083265 -0.190041 0.028875 -0.083265 -0.190865 0.0280514 -0.083265 -0.19199 0.02775 -0.083265 -0.19199 0.0264 -0.083265 -0.19379 0.0268823 -0.083265 0.191592 -0.028875 -0.083265 0.192761 -0.0282 -0.083265 0.191893 -0.03 -0.083265 0.193243 -0.03 -0.083265 0.192761 -0.0318 -0.083265 0.191592 -0.031125 -0.083265 0.190768 -0.0319486 -0.083265 0.191443 -0.0331177 -0.083265 0.187695 -0.031125 -0.083265 0.187843 -0.0331177 -0.083265 0.186525 -0.0318 -0.083265 0.189643 -0.0264 -0.083265 0.191592 0.028875 -0.083265 0.192761 0.0282 -0.083265 0.191443 0.0268823 -0.083265 0.189643 0.0264 -0.083265 0.188518 0.0280514 -0.083265 0.187695 0.028875 -0.083265 0.187843 0.0268823 -0.083265 0.187393 0.03 -0.083265 0.187695 0.031125 -0.083265 0.186525 0.0318 -0.083265 0.188518 0.0319485 -0.083265 0.189643 0.0336 -0.083265 0.193243 0.03 -0.083265 -0.13989 -0.03647 -0.077265 -0.140057 -0.0373119 -0.073265 -0.141248 -0.0385026 -0.077265 -0.16379 -0.03867 -0.073265 -0.16489 -0.0383753 -0.073265 -0.16599 0.03647 -0.077265 -0.16599 -0.03647 -0.073265 -0.16489 0.0383752 -0.077265 -0.165695 0.03757 -0.077265 -0.16489 0.0383752 -0.073265 -0.165695 0.03757 -0.073265 -0.16599 0.03647 -0.073265 -0.14209 0.03867 -0.073265 -0.141248 0.0385025 -0.073265 -0.141248 0.0385025 -0.077265 -0.140534 0.0380256 -0.073265 -0.140534 0.0380256 -0.077265 -0.140057 0.0373119 -0.073265 -0.13989 0.03647 -0.073265 -0.140057 0.0373119 -0.077265 0.0702767 0.0624 -0.073265 -0.0249898 0.0624 -0.073265 -0.16149 -0.0624 -0.073265 -0.120256 0.042075 -0.073265 -0.16379 0.03867 -0.073265 -0.16599 -0.014025 -0.073265 -0.16699 -0.014025 -0.073265 -0.16599 -0.00841504 -0.073265 -0.16599 0.00280496 -0.073265 -0.16699 0.00280496 -0.073265 -0.16599 0.019635 -0.073265 -0.16699 0.019635 -0.073265 -0.16599 0.025245 -0.073265 -0.16599 0.036165 -0.073265 -0.16699 0.042075 -0.073265 -0.165695 -0.03757 -0.073265 -0.16699 -0.025245 -0.073265 -0.16599 -0.025245 -0.073265 -0.141248 -0.0385026 -0.073265 -0.13989 -0.025245 -0.073265 -0.13989 -0.03647 -0.073265 -0.140534 -0.0380257 -0.073265 -0.120256 -0.025245 -0.073265 -0.120256 -0.00841504 -0.073265 -0.13989 -0.00841504 -0.073265 -0.16424 0.0616631 -0.073265 -0.16699 0.0569 -0.073265 0.161893 0.0616631 -0.073265 0.159143 0.0624 -0.073265 0.163906 -0.05965 -0.073265 0.159143 -0.0624 -0.073265 -0.120256 0.047685 -0.073265 -0.16699 0.047685 -0.073265 -0.120256 0.0624 -0.073265 -0.16149 0.0624 -0.073265 -0.120256 -0.047685 -0.073265 -0.120256 -0.042075 -0.073265 -0.16699 -0.042075 -0.073265 -0.14209 -0.03867 -0.073265 -0.0726231 0.047685 -0.073265 -0.120256 0.036165 -0.073265 -0.120256 0.025245 -0.073265 -0.0726231 0.025245 -0.073265 -0.120256 0.019635 -0.073265 -0.120256 0.00280496 -0.073265 -0.0726231 -0.00841504 -0.073265 -0.120256 -0.014025 -0.073265 -0.0726231 -0.014025 -0.073265 -0.0726231 -0.025245 -0.073265 -0.120256 -0.03897 -0.073265 -0.0726231 -0.03897 -0.073265 -0.0726231 -0.042075 -0.073265 -0.0726231 0.042075 -0.073265 -0.0726231 0.036165 -0.073265 -0.0249898 0.042075 -0.073265 -0.0249898 0.036165 -0.073265 -0.0249898 0.025245 -0.073265 -0.0726231 0.019635 -0.073265 -0.0726231 0.00280496 -0.073265 -0.0249898 -0.014025 -0.073265 -0.0249898 -0.025245 -0.073265 -0.0249898 -0.03897 -0.073265 -0.0726231 -0.047685 -0.073265 -0.0726231 -0.0624 -0.073265 -0.0249898 -0.0624 -0.073265 -0.0249898 0.047685 -0.073265 0.0226434 0.036165 -0.073265 -0.0249898 0.019635 -0.073265 0.0226434 0.019635 -0.073265 -0.0249898 0.00280496 -0.073265 0.0226434 0.00280496 -0.073265 -0.0249898 -0.00841504 -0.073265 0.0226434 -0.00841504 -0.073265 0.0226434 -0.03897 -0.073265 -0.0249898 -0.042075 -0.073265 -0.0249898 -0.047685 -0.073265 0.0226434 -0.042075 -0.073265 0.0226434 -0.047685 -0.073265 0.0226434 0.047685 -0.073265 0.0702767 0.047685 -0.073265 0.0702767 0.042075 -0.073265 0.0226434 0.042075 -0.073265 0.0702767 0.025245 -0.073265 0.0226434 0.025245 -0.073265 0.0702767 -0.00841504 -0.073265 0.0226434 -0.014025 -0.073265 0.0702767 -0.014025 -0.073265 0.0226434 -0.025245 -0.073265 0.0226434 -0.0624 -0.073265 0.11791 0.047685 -0.073265 0.0702767 0.036165 -0.073265 0.0702767 0.019635 -0.073265 0.11791 0.019635 -0.073265 0.0702767 0.00280496 -0.073265 0.0702767 -0.025245 -0.073265 0.11791 -0.025245 -0.073265 0.0702767 -0.03897 -0.073265 0.11791 -0.042075 -0.073265 0.0702767 -0.042075 -0.073265 0.0702767 -0.047685 -0.073265 0.11791 -0.047685 -0.073265 0.0702767 -0.0624 -0.073265 0.164143 -0.042075 -0.073265 0.164143 -0.03897 -0.073265 0.11791 -0.03897 -0.073265 0.164143 -0.014025 -0.073265 0.11791 -0.014025 -0.073265 0.11791 -0.00841504 -0.073265 0.11791 0.00280496 -0.073265 0.164143 0.019635 -0.073265 0.164143 0.025245 -0.073265 0.11791 0.025245 -0.073265 0.11791 0.036165 -0.073265 0.164143 0.042075 -0.073265 0.11791 0.042075 -0.073265 0.164143 0.047685 -0.073265 0.11791 0.0624 -0.073265 0.164143 -0.047685 -0.073265 0.164643 -0.047685 -0.073265 0.164643 -0.042075 -0.073265 0.164643 -0.025245 -0.073265 0.164143 -0.025245 -0.073265 0.164643 -0.014025 -0.073265 0.164143 -0.00841504 -0.073265 0.164643 -0.00841504 -0.073265 0.164643 0.00280496 -0.073265 0.164143 0.00280496 -0.073265 0.164643 0.019635 -0.073265 0.164643 0.036165 -0.073265 0.164143 0.036165 -0.073265 0.164643 0.047685 -0.073265 0.163906 0.05965 -0.073265 -0.0726231 0.0624 -0.073265 0.0226434 0.0624 -0.073265 -0.16149 0.0627 -0.073565 -0.166513 0.0598 -0.073565 -0.166253 0.05965 -0.073265 -0.16729 -0.0569 -0.073565 -0.16699 -0.0569 -0.073265 -0.16699 0.025245 -0.073265 -0.16699 0.036165 -0.073265 -0.16699 -0.047685 -0.073265 -0.16699 -0.03897 -0.073265 -0.16699 -0.00841504 -0.073265 -0.166513 -0.0598 -0.073565 -0.166253 -0.05965 -0.073265 -0.16439 -0.061923 -0.073565 -0.16424 -0.0616632 -0.073265 0.159143 -0.0627 -0.073565 -0.120256 -0.0624 -0.073265 0.11791 -0.0624 -0.073265 -0.16149 -0.0627 -0.073565 0.162043 -0.061923 -0.073565 0.161893 -0.0616632 -0.073265 0.164643 0.0569 -0.073265 0.164943 0.0569 -0.073565 0.164643 0.042075 -0.073265 0.164643 0.025245 -0.073265 0.164943 -0.0569 -0.073565 0.164643 -0.03897 -0.073265 0.164643 -0.0569 -0.073265 0.164166 0.0598 -0.073565 0.162043 0.0619229 -0.073565 0.159143 0.0627 -0.073565 -0.0848132 0.0627 -0.079265 -0.16439 0.0619229 -0.073565 -0.16729 0.0569 -0.073565 -0.16729 0.038025 -0.079265 -0.16729 -4.19898e-08 -0.079265 -0.16729 -0.038025 -0.079265 -0.16729 -0.0569 -0.079265 -0.166513 -0.0598 -0.079265 -0.16439 -0.061923 -0.079265 0.159143 -0.0627 -0.079265 0.0824668 -0.0627 -0.079265 0.164166 -0.0598 -0.079265 0.164166 -0.0598 -0.073565 0.164943 -0.0569 -0.079265 0.164943 0.038025 -0.079265 0.164943 0.0569 -0.079265 0.205097 0.0463 -0.079265 0.209427 -0.0538 -0.079265 0.214427 -0.0488 -0.079265 -0.216973 -0.065725 -0.079265 -0.216103 -0.0513 -0.079265 -0.211773 -0.0438 -0.079265 -0.214273 -0.0444699 -0.079265 -0.200506 -0.038025 -0.079265 0.205052 0.065725 -0.079265 0.209427 0.0438 -0.079265 0.211927 0.0444698 -0.079265 0.213757 0.0463 -0.079265 0.214427 0.0488 -0.079265 0.213757 0.0513 -0.079265 -0.207443 0.0463 -0.079265 -0.216103 0.0513 -0.079265 -0.200506 0.065725 -0.079265 -0.216879 -0.07885 -0.079265 -0.216273 -0.0792 -0.079265 -0.19199 -0.03225 -0.079265 -0.193115 -0.0319486 -0.079265 -0.216698 -0.0203421 -0.079265 -0.216973 -0.0215306 -0.079265 -0.207398 -0.038025 -0.079265 -0.193938 -0.028875 -0.079265 -0.193115 -0.0280515 -0.079265 -0.18466 -0.0112511 -0.079265 -0.19199 -0.02775 -0.079265 -0.190865 -0.0280515 -0.079265 -0.190041 -0.031125 -0.079265 -0.190865 -0.0319486 -0.079265 -0.18466 0.011251 -0.079265 -0.200506 0.0159356 -0.079265 -0.19424 0.03 -0.079265 -0.193115 0.0319485 -0.079265 -0.19199 0.03225 -0.079265 -0.190865 0.0319485 -0.079265 -0.190041 0.031125 -0.079265 -0.190244 0.0138198 -0.079265 -0.19199 0.02775 -0.079265 -0.178515 0.038025 -0.079265 -0.190041 0.028875 -0.079265 -0.178515 -4.19898e-08 -0.079265 -0.206773 0.0488 -0.079265 -0.214818 0.0188861 -0.079265 -0.207398 0.038025 -0.079265 -0.208325 0.069875 -0.079265 -0.212222 0.072125 -0.079265 -0.212523 0.071 -0.079265 -0.216973 0.065725 -0.079265 -0.216623 0.0791062 -0.079265 -0.216973 0.0785 -0.079265 -0.209148 0.0729485 -0.079265 0.214533 0.07885 -0.079265 0.214627 0.0785 -0.079265 0.214351 0.020342 -0.079265 0.190768 0.0319485 -0.079265 0.205052 0.038025 -0.079265 0.212302 0.038025 -0.079265 0.214627 0.038025 -0.079265 0.205052 0.0173564 -0.079265 0.190768 0.0280514 -0.079265 0.189643 0.02775 -0.079265 0.182314 0.011251 -0.079265 0.189643 0.03225 -0.079265 0.177043 -4.19898e-08 -0.079265 0.177043 0.000499958 -0.079265 0.188518 0.0319485 -0.079265 0.205052 -0.0173565 -0.079265 0.205052 -0.038025 -0.079265 0.176168 -0.038025 -0.079265 0.188518 -0.0319486 -0.079265 0.187393 -0.03 -0.079265 0.178432 -0.00648685 -0.079265 0.177043 -0.000500042 -0.079265 0.189643 -0.02775 -0.079265 0.205097 -0.0463 -0.079265 0.206927 -0.0444699 -0.079265 0.214627 -0.038025 -0.079265 0.212472 -0.0188862 -0.079265 0.212302 -0.038025 -0.079265 0.162043 0.0619229 -0.079265 0.164166 0.0598 -0.079265 0.159143 0.0627 -0.079265 0.14574 0.0627 -0.079265 0.176168 0.065725 -0.079265 0.176168 0.038025 -0.079265 0.0824668 0.0627 -0.079265 0.0824668 0.065725 -0.079265 -0.16149 0.0627 -0.079265 -0.16439 0.0619229 -0.079265 -0.16729 0.0569 -0.079265 -0.166513 0.0598 -0.079265 -0.16149 -0.0627 -0.079265 -0.0848132 -0.0627 -0.079265 -0.0011732 -0.0627 -0.079265 0.162043 -0.061923 -0.079265 0.206927 -0.0531302 -0.079265 0.205097 -0.0513 -0.079265 0.164943 -0.038025 -0.079265 0.176168 -4.19898e-08 -0.079265 0.164943 -4.19898e-08 -0.079265 -0.209148 -0.0729486 -0.079265 -0.210273 -0.07325 -0.079265 -0.212222 -0.072125 -0.079265 -0.212523 -0.071 -0.079265 -0.212222 -0.069875 -0.079265 -0.207398 -0.065725 -0.079265 -0.211398 -0.0690515 -0.079265 -0.207398 0.0792 -0.079265 -0.208023 0.071 -0.079265 -0.207398 0.065725 -0.079265 -0.178515 -0.038025 -0.079265 -0.200506 0.038025 -0.079265 -0.207443 -0.0463 -0.079265 -0.206773 -0.0488 -0.079265 -0.178515 -0.065725 -0.079265 -0.200506 -0.065725 -0.079265 -0.178515 0.0792 -0.079265 -0.128883 0.071 -0.079265 -0.125508 0.0690514 -0.079265 -0.0848132 0.065725 -0.079265 -0.126633 0.06875 -0.079265 -0.178515 0.065725 -0.079265 -0.128582 0.072125 -0.079265 -0.126633 0.07325 -0.079265 -0.125508 0.0729485 -0.079265 -0.124383 0.071 -0.079265 -0.124685 0.069875 -0.079265 -0.125508 -0.0729486 -0.079265 -0.124685 -0.072125 -0.079265 -0.124383 -0.071 -0.079265 -0.128582 -0.072125 -0.079265 -0.128883 -0.071 -0.079265 -0.0848132 -0.065725 -0.079265 -0.124685 -0.069875 -0.079265 -0.0410446 0.069875 -0.079265 -0.0452432 0.071 -0.079265 -0.0441182 0.0690514 -0.079265 -0.0449418 0.072125 -0.079265 -0.0441182 0.0729485 -0.079265 -0.0418682 0.0729485 -0.079265 -0.0407432 0.071 -0.079265 -0.0011732 0.065725 -0.079265 -0.0410446 -0.069875 -0.079265 -0.0011732 -0.076225 -0.079265 -0.0410446 -0.072125 -0.079265 -0.0441182 -0.0729486 -0.079265 -0.0449418 -0.072125 -0.079265 -0.0429932 -0.06875 -0.079265 -0.0418682 -0.0690515 -0.079265 0.0417718 0.0690514 -0.079265 -0.0011732 0.0627 -0.079265 0.0406468 0.06875 -0.079265 0.0428968 0.071 -0.079265 0.0425954 0.072125 -0.079265 0.0406468 0.07325 -0.079265 -0.0011732 0.0792 -0.079265 0.0395218 0.0690514 -0.079265 0.0386982 0.069875 -0.079265 0.0383968 0.071 -0.079265 0.0386982 0.072125 -0.079265 0.0395218 -0.0729486 -0.079265 0.0824668 -0.065725 -0.079265 -0.0011732 -0.065725 -0.079265 0.14574 0.065725 -0.079265 0.124287 0.06875 -0.079265 0.0824668 0.0792 -0.079265 0.123162 0.0690514 -0.079265 0.122338 0.072125 -0.079265 0.123162 0.0729485 -0.079265 0.124287 0.07325 -0.079265 0.0824668 -0.076225 -0.079265 0.124287 -0.07325 -0.079265 0.14574 -0.0627 -0.079265 0.14574 -0.065725 -0.079265 0.124287 -0.06875 -0.079265 0.126235 -0.069875 -0.079265 0.14574 -0.076225 -0.079265 0.125412 -0.0729486 -0.079265 0.206802 0.0690514 -0.079265 0.205978 0.072125 -0.079265 0.205052 0.0792 -0.079265 0.207927 0.06875 -0.079265 0.176168 0.0792 -0.079265 0.14574 0.0792 -0.079265 0.210177 0.071 -0.079265 0.212302 0.065725 -0.079265 0.211927 0.0531301 -0.079265 0.207927 -0.07325 -0.079265 0.206802 -0.0729486 -0.079265 0.205978 -0.072125 -0.079265 0.176168 -0.076225 -0.079265 0.176168 -0.065725 -0.079265 0.207927 -0.06875 -0.079265 0.205052 -0.065725 -0.079265 0.205978 -0.069875 -0.079265 0.209875 -0.069875 -0.079265 0.212302 -0.076225 -0.079265 0.176168 -0.0792 -0.079265 0.205052 -0.076225 -0.079265 0.14574 -0.0792 -0.079265 0.0824668 -0.0792 -0.079265 -0.0011732 -0.0792 -0.079265 -0.0848132 -0.0792 -0.079265 -0.0848132 -0.076225 -0.079265 -0.178515 -0.076225 -0.079265 -0.200506 -0.076225 -0.079265 -0.200506 -0.0792 -0.079265 -0.207398 -0.076225 -0.079265 -0.216973 -0.076225 -0.079265 -0.216973 -0.0785 -0.079265 0.214627 -0.076225 -0.079265 0.212302 -0.065725 -0.079265 0.213757 -0.0513 -0.079265 -0.13989 0.036165 -0.073265 -0.13989 0.025245 -0.073265 -0.13989 -0.014025 -0.073265 -0.13989 0.00280496 -0.073265 -0.13989 0.019635 -0.073265 -0.148471 -0.0367631 -0.077265 -0.14209 -0.03867 -0.077265 -0.15519 -0.0374 -0.077265 -0.164165 -0.0329853 -0.077265 -0.165246 -0.0319846 -0.077265 -0.15519 0.0374 -0.077265 -0.148471 0.036763 -0.077265 -0.164815 0.0279007 -0.077265 -0.140795 0.00136498 -0.077265 -0.161112 -0.0338608 -0.077265 -0.16379 -0.03867 -0.077265 -0.162751 -0.033396 -0.077265 -0.16489 -0.0383753 -0.077265 -0.165484 -0.00136506 -0.077265 -0.16599 -0.03647 -0.077265 -0.14209 0.03867 -0.077265 -0.146438 0.0349946 -0.077265 -0.164625 -0.00246924 -0.077265 -0.164815 -0.0279008 -0.077265 -0.163377 -0.00310158 -0.077265 -0.13989 0.03647 -0.077265 -0.165695 -0.03757 -0.077265 -0.14273 -0.0271474 -0.077265 -0.140534 -0.0380257 -0.077265 -0.146438 -0.0349947 -0.077265 -0.145167 -0.0338608 -0.077265 -0.16579 -4.19898e-08 -0.077265 -0.159841 0.0349946 -0.077265 -0.162751 0.0333959 -0.077265 -0.161112 0.0338607 -0.077265 -0.141464 0.0279007 -0.077265 -0.165484 0.00136498 -0.077265 -0.14067 -0.0291412 -0.077265 -0.140057 -0.0373119 -0.077265 -0.141033 -0.0319846 -0.077265 -0.165764 0.0306058 -0.077265 -0.165246 0.0319846 -0.077265 -0.164165 0.0329853 -0.077265 -0.16379 0.03867 -0.077265 -0.162091 -0.00375368 -0.077265 -0.16355 -0.0271474 -0.077265 -0.161223 -0.025079 -0.077265 -0.162165 -0.0263624 -0.077265 -0.14539 -0.0235225 -0.077265 -0.144114 -0.0263624 -0.077265 -0.14539 -0.00630004 -0.077265 -0.145074 -0.00489237 -0.077265 -0.141033 0.0319846 -0.077265 -0.140515 0.0306058 -0.077265 -0.14067 0.0291411 -0.077265 -0.16355 0.0271474 -0.077265 -0.163377 0.0031015 -0.077265 -0.142902 0.0031015 -0.077265 -0.144114 0.0263623 -0.077265 -0.14539 -0.0151 -0.078465 -0.14539 -0.0235225 -0.078465 -0.145056 -0.025079 -0.078465 -0.145056 -0.025079 -0.077265 -0.14273 -0.0271474 -0.078465 -0.141464 -0.0279008 -0.077265 -0.14067 -0.0291412 -0.078465 -0.140515 -0.0306059 -0.077265 -0.140515 -0.0306059 -0.078465 -0.141033 -0.0319846 -0.078465 -0.142114 -0.0329853 -0.077265 -0.141409 -0.0324444 -0.078465 -0.142114 -0.0329853 -0.078465 -0.145455 -0.034036 -0.078465 -0.143529 -0.033396 -0.077265 -0.15109 -0.0374 -0.077265 -0.15519 -0.0374 -0.078465 -0.15109 -0.0374 -0.078465 -0.157808 -0.0367631 -0.077265 -0.159841 -0.0349947 -0.078465 -0.159841 -0.0349947 -0.077265 -0.161112 -0.0338608 -0.078465 -0.164165 -0.0329853 -0.078465 -0.165764 -0.0306059 -0.077265 -0.165609 -0.0291412 -0.077265 -0.165609 -0.0291412 -0.078465 -0.16089 -0.00630004 -0.078465 -0.16089 -0.00630004 -0.077265 -0.16089 -0.0235225 -0.077265 -0.161205 -0.00489237 -0.078465 -0.161205 -0.00489237 -0.077265 -0.163377 -0.00310158 -0.078465 -0.164625 -0.00246924 -0.078465 -0.165484 -0.00136506 -0.078465 -0.165484 0.00136498 -0.078465 -0.164625 0.00246916 -0.077265 -0.163377 0.0031015 -0.078465 -0.162091 0.0037536 -0.078465 -0.162091 0.0037536 -0.077265 -0.161205 0.00489228 -0.078465 -0.16089 0.00629996 -0.078465 -0.161205 0.00489228 -0.077265 -0.16089 0.0235224 -0.077265 -0.16089 0.00629996 -0.077265 -0.16089 0.0151 -0.078465 -0.161223 0.0250789 -0.077265 -0.162165 0.0263623 -0.077265 -0.162165 0.0263623 -0.078465 -0.16355 0.0271474 -0.078465 -0.165609 0.0291411 -0.077265 -0.165609 0.0291411 -0.078465 -0.165246 0.0319846 -0.078465 -0.157808 0.036763 -0.077265 -0.157808 0.036763 -0.078465 -0.15109 0.0374 -0.077265 -0.15109 0.0374 -0.078465 -0.146438 0.0349946 -0.078465 -0.145167 0.0338607 -0.077265 -0.145167 0.0338607 -0.078465 -0.143529 0.0333959 -0.077265 -0.142114 0.0329853 -0.077265 -0.142114 0.0329853 -0.078465 -0.141033 0.0319846 -0.078465 -0.140515 0.0306058 -0.078465 -0.14273 0.0271474 -0.077265 -0.14273 0.0271474 -0.078465 -0.144114 0.0263623 -0.078465 -0.145056 0.0250789 -0.077265 -0.145056 0.0250789 -0.078465 -0.14539 0.0235224 -0.077265 -0.14539 0.0151 -0.078465 -0.14539 0.00629996 -0.077265 -0.145074 0.00489228 -0.078465 -0.145074 0.00489228 -0.077265 -0.144189 0.0037536 -0.077265 -0.142902 0.0031015 -0.078465 -0.141654 0.00246916 -0.077265 -0.141422 0.00225826 -0.078465 -0.140795 0.00136498 -0.078465 -0.14049 -4.19898e-08 -0.077265 -0.140795 -0.00136506 -0.077265 -0.14049 -4.19898e-08 -0.078465 -0.141422 -0.00225834 -0.078465 -0.141654 -0.00246924 -0.077265 -0.142902 -0.00310158 -0.077265 -0.144189 -0.00375368 -0.078465 -0.144189 -0.00375368 -0.077265 -0.145074 -0.00489237 -0.078465 -0.14539 -0.00630004 -0.078465 -0.1491 -0.0365042 -0.078465 -0.147413 -0.035377 -0.078465 -0.146285 -0.03369 -0.084765 -0.14589 -0.0317 -0.078465 -0.14589 0.0151 -0.078465 -0.14589 -0.0151 -0.078465 -0.146586 0.0343 -0.078465 -0.15109 0.0369 -0.084765 -0.14849 0.0362033 -0.084765 -0.146586 0.0343 -0.084765 -0.15779 0.0362033 -0.084765 -0.159246 0.0349532 -0.084765 -0.159693 0.0343 -0.084765 -0.16039 -0.02805 -0.084765 -0.16039 -0.0317 -0.078465 -0.16039 -0.02244 -0.084765 -0.16039 -0.00561004 -0.084765 -0.16039 -0.0151 -0.078465 -0.16039 -0.0317 -0.084765 -0.159994 -0.03369 -0.078465 -0.158867 -0.035377 -0.078465 -0.163215 0.0312825 -0.078465 -0.16384 0.0302 -0.079265 -0.163672 0.030825 -0.078465 -0.16384 0.0302 -0.078465 -0.163672 0.029575 -0.079265 -0.163215 0.0291174 -0.079265 -0.161965 0.0291174 -0.078465 -0.161507 0.029575 -0.079265 -0.161507 0.030825 -0.079265 -0.161507 0.030825 -0.078465 -0.161965 0.0312825 -0.078465 -0.16259 0.03145 -0.079265 -0.14369 0.03145 -0.078465 -0.144315 0.0312825 -0.079265 -0.14494 0.0302 -0.079265 -0.144772 0.030825 -0.078465 -0.14494 0.0302 -0.078465 -0.14369 0.02895 -0.079265 -0.14369 0.02895 -0.078465 -0.143065 0.0291174 -0.078465 -0.14244 0.0302 -0.079265 -0.142607 0.030825 -0.079265 -0.14244 0.0302 -0.078465 -0.142607 0.030825 -0.078465 -0.143065 0.0312825 -0.079265 -0.14369 0.03145 -0.079265 -0.143065 0.0312825 -0.078465 -0.16259 0.00124996 -0.079265 -0.163215 0.00108249 -0.079265 -0.163672 0.000624958 -0.079265 -0.16384 -4.19898e-08 -0.079265 -0.163672 -0.000625042 -0.079265 -0.163215 -0.00108257 -0.079265 -0.161965 -0.00108257 -0.079265 -0.161507 -0.000625042 -0.079265 -0.161507 0.000624958 -0.078465 -0.161965 0.00108249 -0.079265 -0.161965 0.00108249 -0.078465 -0.16259 0.00124996 -0.078465 -0.144772 0.000624958 -0.078465 -0.144772 -0.000625042 -0.078465 -0.144315 -0.00108257 -0.078465 -0.14244 -4.19898e-08 -0.079265 -0.14244 -4.19898e-08 -0.078465 -0.142607 0.000624958 -0.079265 -0.143065 0.00108249 -0.078465 -0.163672 -0.029575 -0.078465 -0.163672 -0.030825 -0.078465 -0.16259 -0.03145 -0.079265 -0.161507 -0.030825 -0.079265 -0.16134 -0.0302 -0.079265 -0.161507 -0.030825 -0.078465 -0.16134 -0.0302 -0.078465 -0.161507 -0.029575 -0.079265 -0.161965 -0.0291175 -0.079265 -0.161507 -0.029575 -0.078465 -0.16259 -0.02895 -0.079265 -0.142607 -0.000625042 -0.078465 -0.141654 -0.00246924 -0.078465 -0.143065 -0.00108257 -0.078465 -0.142902 -0.00310158 -0.078465 -0.14369 -0.00125004 -0.078465 -0.142607 0.000624958 -0.078465 -0.141654 0.00246916 -0.078465 -0.14369 0.00124996 -0.078465 -0.144189 0.0037536 -0.078465 -0.144315 0.00108249 -0.078465 -0.145415 0.0151 -0.078465 -0.14539 0.00629996 -0.078465 -0.14494 -4.19898e-08 -0.078465 -0.142607 -0.030825 -0.078465 -0.14369 -0.03145 -0.078465 -0.143529 -0.033396 -0.078465 -0.145167 -0.0338608 -0.078465 -0.141464 -0.0279008 -0.078465 -0.144114 -0.0263624 -0.078465 -0.14494 -0.0302 -0.078465 -0.161965 -0.0312826 -0.078465 -0.162751 -0.033396 -0.078465 -0.16259 -0.03145 -0.078465 -0.163215 -0.0312826 -0.078465 -0.165246 -0.0319846 -0.078465 -0.165764 -0.0306059 -0.078465 -0.16384 -0.0302 -0.078465 -0.163215 -0.0291175 -0.078465 -0.164815 -0.0279008 -0.078465 -0.16355 -0.0271474 -0.078465 -0.162165 -0.0263624 -0.078465 -0.16259 -0.02895 -0.078465 -0.161223 -0.025079 -0.078465 -0.161965 -0.0291175 -0.078465 -0.16089 -0.0151 -0.078465 -0.16089 -0.0235225 -0.078465 -0.16134 -4.19898e-08 -0.078465 -0.163215 -0.00108257 -0.078465 -0.163672 -0.000625042 -0.078465 -0.16579 -4.19898e-08 -0.078465 -0.16384 -4.19898e-08 -0.078465 -0.163672 0.000624958 -0.078465 -0.164625 0.00246916 -0.078465 -0.163215 0.00108249 -0.078465 -0.16259 -0.00125004 -0.078465 -0.162091 -0.00375368 -0.078465 -0.161965 -0.00108257 -0.078465 -0.160865 0.0151 -0.078465 -0.161507 -0.000625042 -0.078465 -0.164815 0.0279007 -0.078465 -0.163215 0.0291174 -0.078465 -0.165764 0.0306058 -0.078465 -0.163672 0.029575 -0.078465 -0.164165 0.0329853 -0.078465 -0.162751 0.0333959 -0.078465 -0.16259 0.03145 -0.078465 -0.161112 0.0338607 -0.078465 -0.160824 0.0340359 -0.078465 -0.16134 0.0302 -0.078465 -0.161507 0.029575 -0.078465 -0.16089 0.0235224 -0.078465 -0.16259 0.02895 -0.078465 -0.161223 0.0250789 -0.078465 -0.16039 0.0317 -0.078465 -0.159841 0.0349946 -0.078465 -0.159693 0.0343 -0.078465 -0.15779 0.0362033 -0.078465 -0.15519 0.0374 -0.078465 -0.15519 0.0369 -0.078465 -0.15109 0.0369 -0.078465 -0.148471 0.036763 -0.078465 -0.14849 0.0362033 -0.078465 -0.145455 0.0340359 -0.078465 -0.14589 0.0317 -0.078465 -0.142607 0.029575 -0.078465 -0.144315 0.0312825 -0.078465 -0.144315 0.0291174 -0.078465 -0.144772 0.029575 -0.078465 -0.14539 0.0235224 -0.078465 -0.143529 0.0333959 -0.078465 -0.141464 0.0279007 -0.078465 -0.14067 0.0291411 -0.078465 -0.140795 -0.00136506 -0.078465 -0.145415 -0.0151 -0.078465 -0.146438 -0.0349947 -0.078465 -0.146285 -0.03369 -0.078465 -0.148471 -0.0367631 -0.078465 -0.15109 -0.0369 -0.078465 -0.15519 -0.0369 -0.078465 -0.157808 -0.0367631 -0.078465 -0.15718 -0.0365042 -0.078465 -0.160824 -0.034036 -0.078465 -0.160865 -0.0151 -0.078465 -0.16039 0.0151 -0.078465 -0.14369 -0.02895 -0.078465 -0.144315 -0.0291175 -0.078465 -0.144772 -0.029575 -0.078465 -0.14494 -0.0302 -0.079265 -0.144772 -0.030825 -0.079265 -0.144772 -0.030825 -0.078465 -0.144315 -0.0312826 -0.078465 -0.143065 -0.0312826 -0.079265 -0.143065 -0.0312826 -0.078465 -0.142607 -0.030825 -0.079265 -0.14244 -0.0302 -0.079265 -0.14244 -0.0302 -0.078465 -0.142607 -0.029575 -0.078465 -0.143065 -0.0291175 -0.078465 -0.14369 -0.02895 -0.079265 -0.143065 -0.0291175 -0.079265 -0.142607 -0.029575 -0.079265 -0.144315 -0.0312826 -0.079265 -0.14369 -0.03145 -0.079265 -0.144315 -0.0291175 -0.079265 -0.144772 -0.029575 -0.079265 -0.14369 -0.0302 -0.079265 -0.163215 -0.0291175 -0.079265 -0.161965 -0.0312826 -0.079265 -0.163215 -0.0312826 -0.079265 -0.163672 -0.029575 -0.079265 -0.16259 -0.0302 -0.079265 -0.16384 -0.0302 -0.079265 -0.163672 -0.030825 -0.079265 -0.14369 -4.19898e-08 -0.079265 -0.143065 0.00108249 -0.079265 -0.14369 0.00124996 -0.079265 -0.142607 -0.000625042 -0.079265 -0.144315 -0.00108257 -0.079265 -0.14369 -0.00125004 -0.079265 -0.143065 -0.00108257 -0.079265 -0.144315 0.00108249 -0.079265 -0.144772 0.000624958 -0.079265 -0.14494 -4.19898e-08 -0.079265 -0.144772 -0.000625042 -0.079265 -0.16259 -4.19898e-08 -0.079265 -0.16134 -4.19898e-08 -0.079265 -0.161507 0.000624958 -0.079265 -0.16259 -0.00125004 -0.079265 -0.143065 0.0291174 -0.079265 -0.142607 0.029575 -0.079265 -0.144772 0.029575 -0.079265 -0.144315 0.0291174 -0.079265 -0.144772 0.030825 -0.079265 -0.14369 0.0302 -0.079265 -0.161965 0.0312825 -0.079265 -0.16259 0.0302 -0.079265 -0.163215 0.0312825 -0.079265 -0.161965 0.0291174 -0.079265 -0.16134 0.0302 -0.079265 -0.16259 0.02895 -0.079265 -0.163672 0.030825 -0.079265 -0.161322 0.0524481 -0.078765 -0.16149 0.0533 -0.078765 -0.160131 0.0512574 -0.078765 -0.160845 0.0517343 -0.078765 0.159143 0.05329 -0.078765 0.156943 0.05109 -0.078765 0.159143 0.0533 -0.078765 -0.160845 0.0548556 -0.078765 -0.160131 0.0553325 -0.078765 -0.160131 0.0553325 -0.079265 -0.160845 0.0548556 -0.079265 -0.161322 0.0541419 -0.078765 0.159143 0.0533 -0.079265 0.158848 0.0544 -0.079265 0.158043 0.0552052 -0.079265 0.158848 0.0544 -0.078765 0.158043 0.0552052 -0.078765 0.156943 0.0555 -0.078765 -0.15929 0.0555 -0.078765 0.158848 0.05219 -0.078765 0.159143 0.05329 -0.079265 0.158043 0.0513847 -0.078765 0.158848 0.05219 -0.079265 -0.15929 0.05109 -0.078765 -0.15929 0.05109 -0.079265 -0.160131 0.0512574 -0.079265 -0.16149 0.05329 -0.078765 0.156943 0.05109 -0.079265 -0.16149 0.05329 -0.079265 -0.161322 0.0524481 -0.079265 -0.160845 0.0517343 -0.079265 -0.161322 0.0541419 -0.079265 -0.16149 0.0533 -0.079265 -0.15929 0.0555 -0.079265 0.158043 0.0513847 -0.079265 0.156943 0.0555 -0.079265 0.159143 0.0592 -0.078765 0.157785 0.0612325 -0.078765 0.156943 0.0614 -0.078765 -0.160131 0.0568674 -0.078765 -0.161195 0.0603 -0.078765 -0.15929 0.0614 -0.078765 -0.161322 0.0580581 -0.078765 0.156943 0.0567 -0.078765 0.158499 0.0607556 -0.078765 0.158499 0.0607556 -0.079265 0.158976 0.0600419 -0.078765 -0.16149 0.0592 -0.078765 -0.16039 0.0611052 -0.078765 -0.16039 0.0611052 -0.079265 -0.15929 0.0614 -0.079265 0.158976 0.0580581 -0.078765 0.158499 0.0573443 -0.078765 0.158499 0.0573443 -0.079265 0.157785 0.0568674 -0.078765 0.157785 0.0568674 -0.079265 -0.160845 0.0573443 -0.078765 -0.160131 0.0568674 -0.079265 -0.161322 0.0580581 -0.079265 -0.16149 0.0589 -0.078765 -0.15929 0.0567 -0.078765 -0.15929 0.0567 -0.079265 -0.16149 0.0592 -0.079265 0.159143 0.0589 -0.078765 0.157785 0.0612325 -0.079265 0.156943 0.0614 -0.079265 0.159143 0.0589 -0.079265 0.159143 0.0592 -0.079265 0.156943 0.0567 -0.079265 0.158976 0.0580581 -0.079265 -0.161195 0.0603 -0.079265 -0.16149 0.0589 -0.079265 -0.160845 0.0573443 -0.079265 0.158976 0.0600419 -0.079265 -0.15929 0.04548 -0.078765 -0.16149 0.04768 -0.078765 -0.161322 0.0468381 -0.078765 -0.15929 0.04989 -0.078765 0.158499 0.0461243 -0.078765 -0.16039 0.0495952 -0.079265 -0.16039 0.0495952 -0.078765 -0.161195 0.04879 -0.079265 -0.16149 0.04769 -0.079265 -0.161195 0.04879 -0.078765 0.158976 0.0485319 -0.079265 0.159143 0.04769 -0.078765 0.158976 0.0485319 -0.078765 0.158499 0.0492456 -0.078765 0.157785 0.0497225 -0.079265 0.157785 0.0497225 -0.078765 0.156943 0.04989 -0.078765 0.156943 0.04989 -0.079265 0.159143 0.04768 -0.078765 0.158976 0.0468381 -0.078765 0.159143 0.04768 -0.079265 0.158976 0.0468381 -0.079265 0.158499 0.0461243 -0.079265 0.157785 0.0456474 -0.078765 0.156943 0.04548 -0.078765 -0.160131 0.0456474 -0.078765 -0.160131 0.0456474 -0.079265 -0.160845 0.0461243 -0.078765 -0.160845 0.0461243 -0.079265 -0.161322 0.0468381 -0.079265 -0.16149 0.04768 -0.079265 -0.15929 0.04548 -0.079265 -0.16149 0.04769 -0.078765 0.158499 0.0492456 -0.079265 0.159143 0.04769 -0.079265 0.157785 0.0456474 -0.079265 0.156943 0.04548 -0.079265 -0.15929 0.04989 -0.079265 -0.160131 0.0441125 -0.078765 -0.15929 0.04428 -0.078765 -0.15929 0.03987 -0.078765 0.156943 0.03987 -0.078765 0.158043 0.0439852 -0.078765 -0.15929 0.04428 -0.079265 -0.160845 0.0436356 -0.078765 -0.161322 0.0429219 -0.078765 -0.16149 0.04208 -0.079265 -0.16149 0.04208 -0.078765 0.159143 0.04208 -0.078765 0.158848 0.04318 -0.078765 0.156943 0.04428 -0.078765 0.159143 0.04207 -0.078765 0.159143 0.04207 -0.079265 0.158848 0.04097 -0.078765 0.158043 0.0401647 -0.078765 0.158043 0.0401647 -0.079265 -0.160131 0.0400374 -0.078765 -0.15929 0.03987 -0.079265 -0.160131 0.0400374 -0.079265 -0.160845 0.0405143 -0.078765 -0.161322 0.0412281 -0.078765 0.156943 0.03987 -0.079265 -0.16149 0.04207 -0.079265 -0.16149 0.04207 -0.078765 0.159143 0.04208 -0.079265 -0.160845 0.0436356 -0.079265 -0.161322 0.0429219 -0.079265 -0.160131 0.0441125 -0.079265 -0.160845 0.0405143 -0.079265 -0.161322 0.0412281 -0.079265 0.158848 0.04097 -0.079265 0.156943 0.04428 -0.079265 0.158848 0.04318 -0.079265 0.158043 0.0439852 -0.079265 -0.160845 -0.0461244 -0.078765 -0.16039 -0.0495953 -0.078765 -0.16149 -0.04768 -0.078765 0.158043 -0.0457748 -0.078765 0.159143 -0.04768 -0.078765 0.156943 -0.04548 -0.078765 0.156943 -0.04989 -0.078765 0.158976 -0.0485319 -0.078765 0.158499 -0.0492457 -0.078765 -0.15929 -0.04548 -0.079265 -0.160131 -0.0456475 -0.079265 -0.15929 -0.04548 -0.078765 -0.160131 -0.0456475 -0.078765 -0.160845 -0.0461244 -0.079265 -0.161322 -0.0468381 -0.079265 -0.161322 -0.0468381 -0.078765 0.158848 -0.04658 -0.078765 0.158043 -0.0457748 -0.079265 0.157785 -0.0497226 -0.078765 0.157785 -0.0497226 -0.079265 -0.15929 -0.04989 -0.078765 -0.16039 -0.0495953 -0.079265 -0.161195 -0.04879 -0.078765 -0.16149 -0.04769 -0.078765 -0.15929 -0.04989 -0.079265 -0.16149 -0.04768 -0.079265 0.159143 -0.04769 -0.079265 0.159143 -0.04769 -0.078765 0.159143 -0.04768 -0.079265 0.156943 -0.04548 -0.079265 -0.161195 -0.04879 -0.079265 -0.16149 -0.04769 -0.079265 0.158848 -0.04658 -0.079265 0.158499 -0.0492457 -0.079265 0.158976 -0.0485319 -0.079265 0.156943 -0.04989 -0.079265 0.156943 -0.04428 -0.078765 -0.15929 -0.04428 -0.078765 -0.16149 -0.04208 -0.078765 0.158043 -0.0401648 -0.078765 0.156943 -0.03987 -0.078765 0.159143 -0.04207 -0.078765 0.159143 -0.04208 -0.078765 -0.160131 -0.0400375 -0.079265 -0.160131 -0.0400375 -0.078765 -0.160845 -0.0405144 -0.078765 -0.160845 -0.0405144 -0.079265 -0.161322 -0.0412281 -0.079265 -0.161322 -0.0412281 -0.078765 -0.16149 -0.04207 -0.079265 0.159143 -0.04207 -0.079265 0.158848 -0.04097 -0.079265 0.158848 -0.04097 -0.078765 -0.15929 -0.03987 -0.078765 -0.15929 -0.03987 -0.079265 0.158848 -0.04318 -0.078765 0.158043 -0.0439853 -0.078765 0.158043 -0.0439853 -0.079265 0.156943 -0.04428 -0.079265 -0.15929 -0.04428 -0.079265 -0.16039 -0.0439853 -0.078765 -0.16039 -0.0439853 -0.079265 -0.161195 -0.04318 -0.079265 -0.161195 -0.04318 -0.078765 -0.16149 -0.04207 -0.078765 -0.16149 -0.04208 -0.079265 0.158848 -0.04318 -0.079265 0.158043 -0.0401648 -0.079265 0.159143 -0.04208 -0.079265 0.156943 -0.03987 -0.079265 0.158848 -0.0544 -0.078765 -0.16039 -0.0552053 -0.078765 -0.161195 -0.0544 -0.078765 -0.16149 -0.0533 -0.078765 -0.15929 -0.0555 -0.078765 0.158043 -0.0513848 -0.078765 0.159143 -0.0533 -0.078765 0.156943 -0.0555 -0.078765 -0.160845 -0.0517344 -0.078765 -0.15929 -0.05109 -0.078765 -0.160845 -0.0517344 -0.079265 -0.160131 -0.0512575 -0.078765 -0.161322 -0.0524481 -0.078765 -0.161322 -0.0524481 -0.079265 0.158848 -0.05219 -0.078765 0.156943 -0.05109 -0.078765 -0.15929 -0.05109 -0.079265 0.158043 -0.0552053 -0.078765 0.158848 -0.0544 -0.079265 0.158043 -0.0552053 -0.079265 -0.15929 -0.0555 -0.079265 -0.16149 -0.05329 -0.079265 -0.16149 -0.05329 -0.078765 0.159143 -0.05329 -0.079265 0.159143 -0.05329 -0.078765 -0.161195 -0.0544 -0.079265 -0.16039 -0.0552053 -0.079265 -0.16149 -0.0533 -0.079265 0.156943 -0.0555 -0.079265 0.158848 -0.05219 -0.079265 0.158043 -0.0513848 -0.079265 0.156943 -0.05109 -0.079265 0.159143 -0.0533 -0.079265 -0.160131 -0.0512575 -0.079265 0.157785 -0.0612326 -0.078765 0.156943 -0.0614 -0.078765 -0.160845 -0.0573444 -0.078765 -0.15929 -0.0567 -0.078765 0.159143 -0.0592 -0.078765 0.158976 -0.0600419 -0.078765 0.158043 -0.0569948 -0.078765 0.158848 -0.0578 -0.078765 0.156943 -0.0567 -0.078765 0.158499 -0.0607557 -0.078765 -0.15929 -0.0567 -0.079265 -0.160131 -0.0568675 -0.079265 -0.160845 -0.0573444 -0.079265 -0.160131 -0.0568675 -0.078765 -0.161322 -0.0580581 -0.079265 -0.161322 -0.0580581 -0.078765 0.159143 -0.0589 -0.079265 0.158043 -0.0569948 -0.079265 -0.16039 -0.0611053 -0.079265 -0.16039 -0.0611053 -0.078765 -0.161195 -0.0603 -0.078765 -0.161195 -0.0603 -0.079265 0.158976 -0.0600419 -0.079265 0.158499 -0.0607557 -0.079265 -0.15929 -0.0614 -0.078765 -0.16149 -0.0589 -0.078765 -0.16149 -0.0592 -0.078765 0.159143 -0.0592 -0.079265 0.159143 -0.0589 -0.078765 0.158848 -0.0578 -0.079265 -0.16149 -0.0592 -0.079265 -0.15929 -0.0614 -0.079265 -0.16149 -0.0589 -0.079265 0.157785 -0.0612326 -0.079265 0.156943 -0.0567 -0.079265 0.156943 -0.0614 -0.079265 0.156943 -0.03867 -0.078765 0.158976 -0.0373119 -0.078765 0.158848 -0.03536 -0.078765 0.159143 -0.03646 -0.078765 0.159143 -0.03647 -0.078765 -0.14029 -0.0383753 -0.078765 -0.13919 -0.03426 -0.078765 -0.13919 -0.03867 -0.078765 0.156943 -0.03426 -0.078765 0.158976 -0.0373119 -0.079265 0.158499 -0.0380257 -0.078765 0.158499 -0.0380257 -0.079265 0.157785 -0.0385026 -0.078765 -0.14029 -0.0345548 -0.079265 -0.141095 -0.03536 -0.079265 -0.14029 -0.0345548 -0.078765 -0.14139 -0.03646 -0.079265 -0.141095 -0.03536 -0.078765 -0.13919 -0.03867 -0.079265 -0.141095 -0.03757 -0.078765 -0.141095 -0.03757 -0.079265 -0.14139 -0.03646 -0.078765 -0.14139 -0.03647 -0.078765 0.159143 -0.03646 -0.079265 0.158043 -0.0345548 -0.079265 0.158043 -0.0345548 -0.078765 -0.13919 -0.03426 -0.079265 0.158848 -0.03536 -0.079265 0.156943 -0.03426 -0.079265 0.159143 -0.03647 -0.079265 0.157785 -0.0385026 -0.079265 0.156943 -0.03867 -0.079265 -0.14139 -0.03647 -0.079265 -0.14029 -0.0383753 -0.079265 -0.14139 -0.00842004 -0.078765 -0.14139 -0.00841004 -0.078765 0.158976 -0.00756814 -0.078765 0.159143 -0.00841004 -0.078765 0.157785 -0.00637751 -0.078765 0.156943 -0.00621004 -0.078765 0.156943 -0.01062 -0.078765 -0.13919 -0.01062 -0.078765 0.159143 -0.00842004 -0.078765 0.158976 -0.00926195 -0.078765 -0.13919 -0.00621004 -0.078765 -0.14029 -0.00650479 -0.079265 -0.14029 -0.00650479 -0.078765 -0.141095 -0.00731004 -0.078765 -0.14029 -0.0103253 -0.079265 -0.14029 -0.0103253 -0.078765 -0.141095 -0.00952004 -0.079265 -0.141095 -0.00952004 -0.078765 -0.14139 -0.00842004 -0.079265 0.159143 -0.00842004 -0.079265 0.158499 -0.00997568 -0.078765 0.157785 -0.0104526 -0.078765 0.158976 -0.00756814 -0.079265 0.158499 -0.00685441 -0.079265 0.158499 -0.00685441 -0.078765 0.156943 -0.00621004 -0.079265 0.159143 -0.00841004 -0.079265 0.157785 -0.00637751 -0.079265 0.156943 -0.01062 -0.079265 -0.13919 -0.01062 -0.079265 -0.13919 -0.00621004 -0.079265 -0.141095 -0.00731004 -0.079265 -0.14139 -0.00841004 -0.079265 0.157785 -0.0104526 -0.079265 0.158499 -0.00997568 -0.079265 0.158976 -0.00926195 -0.079265 0.156943 -0.02865 -0.078765 0.158976 -0.0317019 -0.078765 -0.14029 -0.0289448 -0.078765 -0.14139 -0.03085 -0.078765 0.157785 -0.0288175 -0.078765 -0.141095 -0.03196 -0.078765 -0.13919 -0.03306 -0.078765 0.156943 -0.03306 -0.078765 0.158499 -0.0324157 -0.078765 0.157785 -0.0328926 -0.078765 0.157785 -0.0328926 -0.079265 0.159143 -0.03085 -0.078765 0.158976 -0.0300081 -0.079265 0.158976 -0.0300081 -0.078765 0.158499 -0.0292944 -0.079265 0.158499 -0.0292944 -0.078765 0.156943 -0.02865 -0.079265 0.159143 -0.03086 -0.078765 -0.141095 -0.02975 -0.079265 -0.141095 -0.02975 -0.078765 -0.14029 -0.0327653 -0.078765 -0.14029 -0.0327653 -0.079265 -0.14139 -0.03086 -0.078765 -0.14139 -0.03086 -0.079265 0.156943 -0.03306 -0.079265 -0.13919 -0.02865 -0.078765 0.159143 -0.03086 -0.079265 0.159143 -0.03085 -0.079265 -0.141095 -0.03196 -0.079265 -0.14029 -0.0289448 -0.079265 -0.13919 -0.02865 -0.079265 -0.14139 -0.03085 -0.079265 -0.13919 -0.03306 -0.079265 0.158976 -0.0317019 -0.079265 0.158499 -0.0324157 -0.079265 0.157785 -0.0288175 -0.079265 -0.141222 -0.0260919 -0.078765 0.158848 -0.02414 -0.078765 -0.14139 -0.02524 -0.078765 0.159143 -0.02524 -0.078765 0.156943 -0.02304 -0.078765 0.158043 -0.0271553 -0.078765 0.158848 -0.02635 -0.078765 0.158848 -0.02635 -0.079265 0.158043 -0.0271553 -0.079265 0.158043 -0.0233348 -0.078765 0.156943 -0.02304 -0.079265 0.159143 -0.02525 -0.078765 -0.13919 -0.02304 -0.078765 -0.14029 -0.0233348 -0.078765 -0.141095 -0.02414 -0.078765 -0.14139 -0.02524 -0.079265 -0.140031 -0.0272826 -0.078765 -0.140745 -0.0268057 -0.078765 -0.140745 -0.0268057 -0.079265 -0.14139 -0.02525 -0.078765 -0.141222 -0.0260919 -0.079265 -0.14139 -0.02525 -0.079265 -0.13919 -0.02745 -0.078765 0.156943 -0.02745 -0.078765 -0.13919 -0.02304 -0.079265 -0.140031 -0.0272826 -0.079265 -0.13919 -0.02745 -0.079265 0.158848 -0.02414 -0.079265 0.158043 -0.0233348 -0.079265 -0.14029 -0.0233348 -0.079265 -0.141095 -0.02414 -0.079265 0.156943 -0.02745 -0.079265 0.159143 -0.02525 -0.079265 0.159143 -0.02524 -0.079265 -0.141095 -0.02074 -0.078765 -0.14139 -0.01963 -0.078765 0.158499 -0.0180744 -0.078765 0.159143 -0.01963 -0.078765 -0.14029 -0.0177248 -0.078765 -0.13919 -0.01743 -0.078765 0.156943 -0.02184 -0.078765 0.159143 -0.01964 -0.078765 0.158976 -0.0204819 -0.078765 0.158976 -0.0204819 -0.079265 0.158499 -0.0211957 -0.078765 0.158499 -0.0211957 -0.079265 0.157785 -0.0216726 -0.078765 0.157785 -0.0216726 -0.079265 0.156943 -0.02184 -0.079265 0.158976 -0.0187881 -0.079265 0.158976 -0.0187881 -0.078765 0.158499 -0.0180744 -0.079265 0.157785 -0.0175975 -0.078765 -0.13919 -0.01743 -0.079265 -0.14029 -0.0177248 -0.079265 -0.14139 -0.01963 -0.079265 -0.141095 -0.01853 -0.078765 -0.13919 -0.02184 -0.078765 -0.14029 -0.0215453 -0.078765 -0.14029 -0.0215453 -0.079265 -0.141095 -0.02074 -0.079265 -0.14139 -0.01964 -0.078765 -0.14139 -0.01964 -0.079265 0.156943 -0.01743 -0.078765 0.156943 -0.01743 -0.079265 0.159143 -0.01964 -0.079265 -0.141095 -0.01853 -0.079265 -0.13919 -0.02184 -0.079265 0.157785 -0.0175975 -0.079265 0.159143 -0.01963 -0.079265 -0.141222 -0.0148719 -0.078765 0.158043 -0.0121148 -0.078765 0.159143 -0.01402 -0.078765 -0.14139 -0.01402 -0.078765 -0.13919 -0.01182 -0.078765 0.158848 -0.01513 -0.078765 0.158043 -0.0159353 -0.078765 -0.13919 -0.01623 -0.078765 0.159143 -0.01403 -0.079265 0.158848 -0.01513 -0.079265 0.158043 -0.0159353 -0.079265 0.158848 -0.01292 -0.078765 0.158043 -0.0121148 -0.079265 0.156943 -0.01182 -0.078765 0.159143 -0.01403 -0.078765 -0.14029 -0.0121148 -0.079265 -0.14029 -0.0121148 -0.078765 -0.141095 -0.01292 -0.078765 -0.140031 -0.0160626 -0.078765 -0.140745 -0.0155857 -0.079265 -0.140745 -0.0155857 -0.078765 -0.14139 -0.01403 -0.078765 -0.14139 -0.01402 -0.079265 -0.14139 -0.01403 -0.079265 0.156943 -0.01623 -0.078765 0.156943 -0.01182 -0.079265 -0.141095 -0.01292 -0.079265 0.158848 -0.01292 -0.079265 -0.141222 -0.0148719 -0.079265 0.156943 -0.01623 -0.079265 0.159143 -0.01402 -0.079265 -0.140031 -0.0160626 -0.079265 -0.13919 -0.01182 -0.079265 -0.13919 -0.01623 -0.079265 0.156943 -0.000600042 -0.078765 0.158848 -0.00170004 -0.078765 -0.13919 -0.000600042 -0.078765 -0.14139 -0.00280004 -0.078765 -0.140745 -0.00436568 -0.078765 -0.141222 -0.00365195 -0.078765 0.158848 -0.00391004 -0.078765 0.158043 -0.0047153 -0.078765 0.159143 -0.00281004 -0.078765 -0.13919 -0.00501004 -0.078765 -0.140031 -0.00484258 -0.078765 0.158043 -0.0047153 -0.079265 0.156943 -0.00501004 -0.078765 0.156943 -0.00501004 -0.079265 0.159143 -0.00280004 -0.079265 0.159143 -0.00280004 -0.078765 0.158848 -0.00170004 -0.079265 0.158043 -0.000894786 -0.079265 0.158043 -0.000894786 -0.078765 0.159143 -0.00281004 -0.079265 -0.14029 -0.000894786 -0.078765 -0.141095 -0.00170004 -0.078765 -0.14139 -0.00280004 -0.079265 -0.140031 -0.00484258 -0.079265 -0.14139 -0.00281004 -0.078765 -0.141222 -0.00365195 -0.079265 -0.14139 -0.00281004 -0.079265 -0.14029 -0.000894786 -0.079265 -0.141095 -0.00170004 -0.079265 -0.13919 -0.000600042 -0.079265 0.158848 -0.00391004 -0.079265 -0.13919 -0.00501004 -0.079265 0.156943 -0.000600042 -0.079265 -0.140745 -0.00436568 -0.079265 -0.140745 0.00124432 -0.078765 -0.14029 0.00471521 -0.078765 -0.14139 0.00280996 -0.078765 -0.13919 0.00500996 -0.078765 0.158499 0.00436559 -0.078765 0.156943 0.000599958 -0.078765 0.159143 0.00280996 -0.078765 -0.14139 0.00279996 -0.078765 0.159143 0.00279996 -0.078765 0.158848 0.00169996 -0.078765 0.158043 0.000894702 -0.078765 0.158043 0.000894702 -0.079265 0.156943 0.000599958 -0.079265 0.158976 0.00365186 -0.079265 0.158976 0.00365186 -0.078765 0.157785 0.00484249 -0.078765 0.156943 0.00500996 -0.079265 -0.14029 0.00471521 -0.079265 -0.141095 0.00390996 -0.078765 -0.140031 0.000767423 -0.078765 -0.141222 0.00195805 -0.078765 -0.140745 0.00124432 -0.079265 -0.141222 0.00195805 -0.079265 -0.14139 0.00280996 -0.079265 -0.13919 0.000599958 -0.078765 -0.13919 0.000599958 -0.079265 0.156943 0.00500996 -0.078765 0.158499 0.00436559 -0.079265 0.157785 0.00484249 -0.079265 -0.141095 0.00390996 -0.079265 -0.14139 0.00279996 -0.079265 0.158848 0.00169996 -0.079265 0.159143 0.00279996 -0.079265 0.159143 0.00280996 -0.079265 -0.13919 0.00500996 -0.079265 -0.140031 0.000767423 -0.079265 0.158976 0.00926186 -0.078765 0.159143 0.00841996 -0.078765 0.158499 0.00997559 -0.078765 0.157785 0.00637742 -0.078765 0.158976 0.00756805 -0.078765 -0.14139 0.00841996 -0.078765 -0.14139 0.00840996 -0.078765 0.159143 0.00840996 -0.078765 0.158499 0.00685432 -0.078765 0.158976 0.00756805 -0.079265 0.158499 0.00685432 -0.079265 0.156943 0.00620996 -0.078765 0.157785 0.00637742 -0.079265 0.158976 0.00926186 -0.079265 0.157785 0.0104525 -0.079265 0.157785 0.0104525 -0.078765 0.156943 0.01062 -0.078765 -0.14029 0.0103252 -0.079265 -0.141095 0.00951996 -0.079265 -0.14029 0.0103252 -0.078765 -0.141095 0.00951996 -0.078765 -0.14139 0.00841996 -0.079265 -0.14029 0.0065047 -0.078765 -0.141095 0.00730996 -0.078765 -0.14029 0.0065047 -0.079265 -0.141095 0.00730996 -0.079265 -0.14139 0.00840996 -0.079265 -0.13919 0.00620996 -0.078765 -0.13919 0.00620996 -0.079265 -0.13919 0.01062 -0.078765 0.156943 0.01062 -0.079265 0.159143 0.00840996 -0.079265 0.159143 0.00841996 -0.079265 -0.13919 0.01062 -0.079265 0.156943 0.00620996 -0.079265 0.158499 0.00997559 -0.079265 0.157785 0.0119874 -0.078765 -0.13919 0.01623 -0.078765 0.156943 0.01623 -0.078765 0.158848 0.01513 -0.078765 -0.140031 0.0119874 -0.078765 -0.14139 0.01402 -0.078765 -0.140745 0.0124643 -0.078765 -0.141222 0.0131781 -0.078765 0.159143 0.01402 -0.078765 0.158976 0.0131781 -0.078765 0.158976 0.0131781 -0.079265 0.158499 0.0124643 -0.078765 0.157785 0.0119874 -0.079265 0.156943 0.01182 -0.079265 0.159143 0.01403 -0.079265 0.158848 0.01513 -0.079265 0.158043 0.0159352 -0.078765 0.159143 0.01403 -0.078765 -0.14029 0.0159352 -0.079265 -0.14029 0.0159352 -0.078765 -0.141095 0.01513 -0.079265 -0.141095 0.01513 -0.078765 -0.14139 0.01403 -0.079265 -0.14139 0.01403 -0.078765 -0.13919 0.01182 -0.079265 -0.140745 0.0124643 -0.079265 -0.13919 0.01182 -0.078765 0.156943 0.01182 -0.078765 -0.14139 0.01402 -0.079265 -0.141222 0.0131781 -0.079265 0.158499 0.0124643 -0.079265 0.158043 0.0159352 -0.079265 0.156943 0.01623 -0.079265 0.159143 0.01402 -0.079265 -0.13919 0.01623 -0.079265 -0.140031 0.0119874 -0.079265 -0.13919 0.02184 -0.078765 0.158976 0.0204819 -0.078765 0.156943 0.02184 -0.078765 0.157785 0.0175974 -0.078765 0.159143 0.01963 -0.078765 0.158976 0.0187881 -0.078765 0.158499 0.0180743 -0.079265 0.158499 0.0180743 -0.078765 0.159143 0.01964 -0.078765 0.158499 0.0211956 -0.078765 0.157785 0.0216725 -0.078765 0.159143 0.01964 -0.079265 -0.14029 0.0215452 -0.079265 -0.14029 0.0215452 -0.078765 -0.141095 0.02074 -0.079265 -0.141095 0.02074 -0.078765 -0.14139 0.01964 -0.079265 -0.13919 0.01743 -0.079265 -0.14029 0.0177247 -0.078765 -0.14029 0.0177247 -0.079265 -0.141095 0.01853 -0.078765 -0.141095 0.01853 -0.079265 -0.14139 0.01963 -0.078765 -0.14139 0.01963 -0.079265 -0.14139 0.01964 -0.078765 -0.13919 0.01743 -0.078765 0.156943 0.01743 -0.078765 0.156943 0.02184 -0.079265 0.159143 0.01963 -0.079265 0.156943 0.01743 -0.079265 -0.13919 0.02184 -0.079265 0.158976 0.0187881 -0.079265 0.157785 0.0175974 -0.079265 0.158976 0.0204819 -0.079265 0.158499 0.0211956 -0.079265 0.157785 0.0216725 -0.079265 0.158848 0.02635 -0.078765 -0.141095 0.02635 -0.078765 -0.141222 0.0243981 -0.078765 0.158848 0.02414 -0.078765 0.159143 0.02524 -0.078765 0.159143 0.02525 -0.078765 0.156943 0.02304 -0.078765 -0.13919 0.02304 -0.078765 -0.140031 0.0232074 -0.078765 -0.13919 0.02745 -0.078765 0.159143 0.02524 -0.079265 0.158848 0.02414 -0.079265 0.158043 0.0233347 -0.078765 0.158043 0.0271552 -0.078765 -0.14029 0.0271552 -0.079265 -0.14029 0.0271552 -0.078765 -0.14139 0.02525 -0.079265 -0.140031 0.0232074 -0.079265 -0.140745 0.0236843 -0.078765 -0.140745 0.0236843 -0.079265 -0.141222 0.0243981 -0.079265 -0.14139 0.02524 -0.079265 -0.14139 0.02525 -0.078765 -0.14139 0.02524 -0.078765 0.156943 0.02304 -0.079265 0.156943 0.02745 -0.078765 -0.13919 0.02745 -0.079265 -0.141095 0.02635 -0.079265 0.158848 0.02635 -0.079265 0.158043 0.0233347 -0.079265 0.159143 0.02525 -0.079265 -0.13919 0.02304 -0.079265 0.156943 0.02745 -0.079265 0.158043 0.0271552 -0.079265 0.156943 0.02865 -0.078765 -0.13919 0.03306 -0.078765 -0.14139 0.03086 -0.078765 -0.140745 0.0292943 -0.078765 -0.141222 0.0300081 -0.078765 0.156943 0.03306 -0.078765 0.158043 0.0289447 -0.078765 0.158976 0.0317019 -0.078765 0.158848 0.02975 -0.078765 0.158043 0.0289447 -0.079265 0.159143 0.03086 -0.078765 0.158976 0.0317019 -0.079265 0.158499 0.0324156 -0.078765 0.157785 0.0328925 -0.079265 0.157785 0.0328925 -0.078765 0.159143 0.03085 -0.078765 0.159143 0.03086 -0.079265 -0.14029 0.0327652 -0.079265 -0.14029 0.0327652 -0.078765 -0.141095 0.03196 -0.079265 -0.14139 0.03086 -0.079265 -0.141095 0.03196 -0.078765 -0.13919 0.02865 -0.078765 -0.140031 0.0288174 -0.078765 -0.140745 0.0292943 -0.079265 -0.141222 0.0300081 -0.079265 -0.14139 0.03085 -0.079265 -0.14139 0.03085 -0.078765 -0.140031 0.0288174 -0.079265 -0.13919 0.03306 -0.079265 0.158848 0.02975 -0.079265 0.159143 0.03085 -0.079265 0.156943 0.02865 -0.079265 0.158499 0.0324156 -0.079265 0.156943 0.03306 -0.079265 -0.13919 0.02865 -0.079265 0.156943 0.03426 -0.078765 0.156943 0.03867 -0.078765 -0.14139 0.03646 -0.078765 -0.140031 0.0385025 -0.078765 -0.141222 0.0373119 -0.078765 0.158976 0.0373119 -0.078765 0.159143 0.03647 -0.078765 0.158976 0.0356181 -0.078765 0.159143 0.03646 -0.078765 0.159143 0.03646 -0.079265 0.158499 0.0349043 -0.078765 0.158499 0.0349043 -0.079265 0.157785 0.0344274 -0.079265 0.157785 0.0344274 -0.078765 -0.14139 0.03647 -0.079265 -0.140745 0.0380256 -0.078765 -0.140031 0.0385025 -0.079265 -0.13919 0.03867 -0.078765 -0.14029 0.0345547 -0.078765 -0.141095 0.03536 -0.078765 -0.14139 0.03646 -0.079265 -0.14139 0.03647 -0.078765 0.158976 0.0373119 -0.079265 0.158499 0.0380256 -0.079265 0.158499 0.0380256 -0.078765 0.157785 0.0385025 -0.079265 0.157785 0.0385025 -0.078765 0.156943 0.03867 -0.079265 -0.13919 0.03867 -0.079265 -0.13919 0.03426 -0.078765 0.159143 0.03647 -0.079265 0.156943 0.03426 -0.079265 0.158976 0.0356181 -0.079265 -0.13919 0.03426 -0.079265 -0.141095 0.03536 -0.079265 -0.14029 0.0345547 -0.079265 -0.140745 0.0380256 -0.079265 -0.141222 0.0373119 -0.079265 -0.163215 0.0312825 -0.083265 -0.163672 0.029575 -0.083265 -0.163672 0.030825 -0.083265 -0.161965 0.0291174 -0.083265 -0.16259 0.0302 -0.083265 -0.163215 0.0291174 -0.083265 -0.161965 0.0312825 -0.083265 -0.163672 0.030825 -0.083465 -0.16259 0.0302 -0.084216 -0.163672 0.029575 -0.083465 -0.161965 0.0291174 -0.083465 -0.163215 0.0291174 -0.083465 -0.16134 0.0302 -0.083465 -0.16259 0.03145 -0.083265 -0.163215 0.0312825 -0.083465 -0.16384 0.0302 -0.083465 -0.16384 0.0302 -0.083265 -0.16259 0.02895 -0.083465 -0.16259 0.02895 -0.083265 -0.161507 0.029575 -0.083465 -0.161507 0.029575 -0.083265 -0.161507 0.030825 -0.083465 -0.16134 0.0302 -0.083265 -0.161507 0.030825 -0.083265 -0.161965 0.0312825 -0.083465 -0.16259 0.03145 -0.083465 -0.143065 0.0312825 -0.083265 -0.143065 0.0291174 -0.083265 -0.14369 0.02895 -0.083265 -0.144315 0.0291174 -0.083265 -0.14369 0.0302 -0.083265 -0.142607 0.029575 -0.083265 -0.144772 0.030825 -0.083465 -0.14494 0.0302 -0.083465 -0.143065 0.0312825 -0.083465 -0.14244 0.0302 -0.083465 -0.14369 0.0302 -0.084216 -0.14369 0.03145 -0.083465 -0.144315 0.0312825 -0.083465 -0.144315 0.0312825 -0.083265 -0.144772 0.030825 -0.083265 -0.14494 0.0302 -0.083265 -0.144772 0.029575 -0.083465 -0.144772 0.029575 -0.083265 -0.144315 0.0291174 -0.083465 -0.14369 0.02895 -0.083465 -0.143065 0.0291174 -0.083465 -0.142607 0.029575 -0.083465 -0.14244 0.0302 -0.083265 -0.142607 0.030825 -0.083265 -0.142607 0.030825 -0.083465 -0.14369 0.03145 -0.083265 -0.163215 0.00108249 -0.083265 -0.16259 -4.19898e-08 -0.083265 -0.163672 -0.000625042 -0.083265 -0.161965 -0.00108257 -0.083265 -0.163215 -0.00108257 -0.083265 -0.161965 0.00108249 -0.083265 -0.161507 0.000624958 -0.083265 -0.16259 -4.19898e-08 -0.084216 -0.163215 0.00108249 -0.083465 -0.163672 0.000624958 -0.083465 -0.163215 -0.00108257 -0.083465 -0.16259 0.00124996 -0.083465 -0.163672 0.000624958 -0.083265 -0.16384 -4.19898e-08 -0.083465 -0.163672 -0.000625042 -0.083465 -0.16384 -4.19898e-08 -0.083265 -0.16259 -0.00125004 -0.083465 -0.16259 -0.00125004 -0.083265 -0.161965 -0.00108257 -0.083465 -0.161507 -0.000625042 -0.083465 -0.161507 -0.000625042 -0.083265 -0.16134 -4.19898e-08 -0.083465 -0.16134 -4.19898e-08 -0.083265 -0.161507 0.000624958 -0.083465 -0.161965 0.00108249 -0.083465 -0.16259 0.00124996 -0.083265 -0.144772 -0.000625042 -0.083265 -0.14494 -4.19898e-08 -0.083265 -0.144772 0.000624958 -0.083265 -0.14369 -0.00125004 -0.083265 -0.14369 -4.19898e-08 -0.083265 -0.143065 0.00108249 -0.083265 -0.142607 0.000624958 -0.083265 -0.14244 -4.19898e-08 -0.083265 -0.144772 0.000624958 -0.083465 -0.144315 0.00108249 -0.083465 -0.14369 -4.19898e-08 -0.084216 -0.14494 -4.19898e-08 -0.083465 -0.142607 -0.000625042 -0.083465 -0.14369 -0.00125004 -0.083465 -0.143065 -0.00108257 -0.083465 -0.144315 -0.00108257 -0.083465 -0.14369 0.00124996 -0.083465 -0.144315 0.00108249 -0.083265 -0.144772 -0.000625042 -0.083465 -0.144315 -0.00108257 -0.083265 -0.143065 -0.00108257 -0.083265 -0.142607 -0.000625042 -0.083265 -0.14244 -4.19898e-08 -0.083465 -0.142607 0.000624958 -0.083465 -0.143065 0.00108249 -0.083465 -0.14369 0.00124996 -0.083265 -0.161965 -0.0291175 -0.083265 -0.163672 -0.030825 -0.083265 -0.16384 -0.0302 -0.083265 -0.161965 -0.0312826 -0.083265 -0.16259 -0.0302 -0.083265 -0.161507 -0.030825 -0.083265 -0.163215 -0.0291175 -0.083465 -0.163672 -0.029575 -0.083465 -0.163215 -0.0312826 -0.083465 -0.163672 -0.030825 -0.083465 -0.16384 -0.0302 -0.083465 -0.161965 -0.0312826 -0.083465 -0.161507 -0.030825 -0.083465 -0.16259 -0.0302 -0.084216 -0.161965 -0.0291175 -0.083465 -0.163215 -0.0291175 -0.083265 -0.163672 -0.029575 -0.083265 -0.163215 -0.0312826 -0.083265 -0.16259 -0.03145 -0.083265 -0.16259 -0.03145 -0.083465 -0.16134 -0.0302 -0.083465 -0.16134 -0.0302 -0.083265 -0.161507 -0.029575 -0.083465 -0.161507 -0.029575 -0.083265 -0.16259 -0.02895 -0.083465 -0.16259 -0.02895 -0.083265 -0.143065 -0.0291175 -0.083265 -0.14369 -0.0302 -0.083265 -0.143065 -0.0312826 -0.083265 -0.14369 -0.03145 -0.083265 -0.144315 -0.0312826 -0.083265 -0.144315 -0.0291175 -0.083465 -0.144315 -0.0312826 -0.083465 -0.143065 -0.0291175 -0.083465 -0.142607 -0.030825 -0.083465 -0.14369 -0.0302 -0.084216 -0.144772 -0.029575 -0.083465 -0.144315 -0.0291175 -0.083265 -0.144772 -0.029575 -0.083265 -0.14494 -0.0302 -0.083465 -0.14494 -0.0302 -0.083265 -0.144772 -0.030825 -0.083465 -0.144772 -0.030825 -0.083265 -0.14369 -0.03145 -0.083465 -0.143065 -0.0312826 -0.083465 -0.142607 -0.030825 -0.083265 -0.14244 -0.0302 -0.083465 -0.14244 -0.0302 -0.083265 -0.142607 -0.029575 -0.083465 -0.142607 -0.029575 -0.083265 -0.14369 -0.02895 -0.083465 -0.14369 -0.02895 -0.083265 0.228674 -0.081116 0.0280533 0.238674 -0.0756799 0.0292667 0.238674 -0.0738524 0.0294389 0.228674 -0.0664723 0.0289746 0.228674 -0.053196 0.0227273 0.228674 -0.0445716 0.0108568 0.238674 -0.0445716 0.0108568 0.228674 -0.0427327 0.00369447 0.238674 -0.0427327 0.00369447 0.228674 -0.0445716 -0.0108625 0.228674 -0.053196 -0.022733 0.228674 -0.0594396 -0.0266953 0.238674 -0.0594396 -0.0266953 0.238674 -0.0664723 -0.0289803 0.238674 -0.0878069 -0.0249105 0.238674 -0.0935046 -0.020197 0.228674 -0.0935046 -0.020197 0.228674 -0.0978511 -0.0142146 0.238674 -0.100573 -0.00733921 0.228674 -0.100573 -0.00733921 0.238674 -0.1015 -2.85742e-06 0.238674 -0.0978511 0.0142089 0.228674 -0.100573 0.00733349 0.228674 -0.0978511 0.0142089 0.228674 -0.0935046 0.0201913 0.238674 -0.0923279 0.0213754 0.190674 -0.0994653 -0.036085 0.190674 -0.0971327 -0.03546 0.185974 -0.0994653 -0.036085 0.190674 -0.0992978 -0.03546 0.185974 -0.0992978 -0.03546 0.190674 -0.0988403 -0.0350025 0.190674 -0.0982153 -0.034835 0.190674 -0.0975903 -0.0350025 0.190674 -0.0969653 -0.036085 0.185974 -0.0971327 -0.03546 0.185974 -0.07325 -0.0446029 0.190674 -0.0730826 -0.0439779 0.185974 -0.0730826 -0.0439779 0.185974 -0.072625 -0.0435203 0.190674 -0.072 -0.0433529 0.190674 -0.072625 -0.0435203 0.190674 -0.07325 -0.0446029 0.190674 -0.07075 -0.0446029 0.190674 -0.0709175 -0.0439779 0.190674 -0.071375 -0.0435203 0.185974 -0.0470348 -0.036085 0.185974 -0.0468674 -0.03546 0.190674 -0.0464098 -0.0350025 0.190674 -0.0457848 -0.034835 0.185974 -0.0451598 -0.0350025 0.190674 -0.0447023 -0.03546 0.190674 -0.0445348 -0.036085 0.185974 -0.0447023 -0.03546 0.190674 -0.0468674 -0.03546 0.190674 -0.0451598 -0.0350025 0.190674 -0.0306655 -0.01316 0.190674 -0.0295829 -0.012535 0.185974 -0.0295829 -0.012535 0.190674 -0.0289579 -0.0127025 0.185974 -0.0289579 -0.0127025 0.190674 -0.0302079 -0.0127025 0.190674 -0.0285004 -0.01316 0.190674 -0.0283329 -0.013785 0.190674 -0.0306655 0.0144043 0.190674 -0.0302079 0.0148618 0.185974 -0.0302079 0.0148618 0.190674 -0.0295829 0.0150293 0.190674 -0.0289579 0.0148618 0.185974 -0.0289579 0.0148618 0.190674 -0.0285004 0.0144043 0.190674 -0.0283329 0.0137793 0.185974 -0.0470348 0.0360793 0.185974 -0.0465642 0.0370566 0.185974 -0.0455067 0.037298 0.190674 -0.0450055 0.0370566 0.185974 -0.0450055 0.0370566 0.190674 -0.0445348 0.0360793 0.190674 -0.046063 0.037298 0.190674 -0.0455067 0.037298 0.190674 -0.0465642 0.0370566 0.190674 -0.046911 0.0366217 0.191425 -0.0457848 0.0360793 0.190674 -0.0446586 0.0366217 0.190674 -0.0730826 0.0452221 0.185974 -0.072 0.0458471 0.190674 -0.0709175 0.0452221 0.185974 -0.071375 0.0456797 0.185974 -0.0709175 0.0452221 0.190674 -0.072 0.0458471 0.190674 -0.072625 0.0456797 0.190674 -0.071375 0.0456797 0.185974 -0.0994653 0.0360793 0.190674 -0.0988403 0.0371618 0.185974 -0.0992978 0.0367043 0.190674 -0.0982153 0.0373293 0.185974 -0.0988403 0.0371618 0.190674 -0.0971327 0.0367043 0.185974 -0.0971327 0.0367043 0.190674 -0.0992978 0.0367043 0.190674 -0.0969653 0.0360793 0.190674 -0.0975903 0.0371618 0.190674 -0.1155 0.0144043 0.185974 -0.1155 0.0144043 0.185974 -0.115042 0.0148618 0.190674 -0.114417 0.0150293 0.190674 -0.113792 0.0148618 0.190674 -0.115042 0.0148618 0.191425 -0.114417 0.0137793 0.190674 -0.113335 0.0144043 0.190674 -0.1155 -0.01316 0.185974 -0.115667 -0.013785 0.190674 -0.114417 -0.012535 0.185974 -0.113335 -0.01316 0.190674 -0.113167 -0.013785 0.185974 -0.113167 -0.013785 0.190674 -0.115042 -0.0127025 0.191425 -0.114417 -0.013785 0.190674 -0.115667 -0.013785 0.190674 -0.113792 -0.0127025 0.190674 -0.113335 -0.01316 0.230628 -0.00728551 -0.00912284 0.229748 -0.00504441 -0.0104936 0.229756 -0.00505915 -0.0104461 0.229764 -0.00508432 -0.01046 0.23021 -0.00621386 -0.00974432 0.229783 -0.00512417 -0.0103762 0.232756 -0.0133037 -0.00979755 0.229745 -0.00504457 -0.0105439 0.232756 -0.0124921 -2.85742e-06 0.232756 -0.0126953 -0.00491699 0.231377 -0.00900189 -0.00615118 0.229777 -0.00774495 -0.0213035 0.229785 -0.00774361 -0.0212271 0.231361 -0.0116784 -0.0193245 0.231707 -0.0122949 -0.0181073 0.232756 -0.0157164 -0.0193251 0.231809 -0.0124185 -0.0175448 0.231908 -0.0124407 -0.0166387 0.231911 -0.0121271 -0.0154307 0.231119 -0.00936995 -0.013205 0.229785 -0.0057402 -0.0137504 0.229777 -0.00570317 -0.0136835 0.230492 -0.00762121 -0.0132589 0.229745 -0.00514432 -0.0111591 0.23174 -0.0293039 -0.0453722 0.231809 -0.0291719 -0.0449854 0.232756 -0.0316964 -0.0437843 0.231499 -0.0255917 -0.0425528 0.229785 -0.0214911 -0.0450385 0.229765 -0.0214268 -0.0450505 0.229808 -0.0215447 -0.0450028 0.229777 -0.0214256 -0.0449991 0.22975 -0.0269671 -0.0506413 0.229785 -0.0269644 -0.0505118 0.231361 -0.0294208 -0.0468967 0.232756 -0.0354495 -0.046963 0.231499 -0.0530842 -0.0600564 0.231911 -0.0554244 -0.0595683 0.232756 -0.0573917 -0.0576899 0.230492 -0.0512907 -0.0623846 0.229777 -0.0506994 -0.0642579 0.229745 -0.0447731 -0.0620741 0.229777 -0.0583194 -0.0662997 0.232756 -0.0670859 -0.0593076 0.229745 -0.0664028 -0.0675515 0.229808 -0.0582566 -0.0661984 0.229765 -0.0582742 -0.0663243 0.231411 -0.0585032 -0.0617499 0.231707 -0.0578264 -0.0607612 0.23174 -0.0577088 -0.0606419 0.229777 -0.0856807 -0.0662997 0.229765 -0.0857259 -0.0663244 0.22975 -0.0856804 -0.0663736 0.229808 -0.0931956 -0.0642016 0.22975 -0.0933378 -0.0643218 0.229777 -0.0933007 -0.0642579 0.229765 -0.0932738 -0.0643018 0.229785 -0.0932243 -0.0642593 0.231482 -0.0909712 -0.0600887 0.231707 -0.0901045 -0.059708 0.232756 -0.0866084 -0.0576899 0.231769 -0.0864107 -0.0605307 0.232756 -0.0817947 -0.0586992 0.231499 -0.0856452 -0.0614687 0.229765 -0.117048 -0.0505761 0.231119 -0.114748 -0.0476411 0.229745 -0.109072 -0.0567461 0.230659 -0.115364 -0.0487845 0.229808 -0.117 -0.0504582 0.229745 -0.109768 -0.0562854 0.229785 -0.117036 -0.0505118 0.229777 -0.116996 -0.0505773 0.229777 -0.122575 -0.0449991 0.229808 -0.122455 -0.0450028 0.230492 -0.121126 -0.0436724 0.230965 -0.120056 -0.0429191 0.231769 -0.114744 -0.0452162 0.232756 -0.112304 -0.0437843 0.232756 -0.108551 -0.046963 0.232756 -0.104548 -0.0498209 0.232756 -0.115781 -0.0403065 0.231929 -0.11569 -0.0436831 0.229765 -0.138321 -0.0137287 0.229777 -0.138297 -0.0136835 0.230965 -0.135076 -0.0131416 0.231411 -0.133747 -0.0134997 0.231769 -0.131624 -0.0177868 0.229777 -0.136255 -0.0213035 0.229745 -0.136108 -0.022011 0.229745 -0.136311 -0.0214088 0.229765 -0.136299 -0.0212767 0.232756 -0.131305 -0.00491699 0.23113 -0.135485 -0.00790611 0.232756 -0.130696 -0.00979755 0.229745 -0.138856 -0.0111591 0.229745 -0.138956 -0.0105439 0.23021 -0.137786 -0.00974432 0.229764 -0.138916 -0.01046 0.229783 -0.138876 -0.0103762 0.229768 -0.138913 -0.010406 0.230659 -0.133946 -0.0205668 0.232756 -0.128284 -0.0193251 0.232756 -0.126496 -0.0239069 0.232756 -0.124336 -0.0283255 0.229745 -0.132849 -0.0298609 0.229745 -0.131611 -0.0322626 0.229745 -0.128283 -0.0377709 0.232756 -0.11896 -0.0365534 0.232756 -0.100323 -0.0523386 0.232756 -0.0959041 -0.0544987 0.231119 -0.0852022 -0.0626329 0.232756 -0.0769142 -0.0593076 0.229745 -0.0775973 -0.0675515 0.229745 -0.0674332 -0.067629 0.232756 -0.0436774 -0.0523386 0.229745 -0.042142 -0.0608522 0.230492 -0.0283305 -0.0491285 0.229745 -0.0349278 -0.0567461 0.229777 -0.0270038 -0.0505773 0.229808 -0.0270001 -0.0504582 0.229765 -0.0269524 -0.050576 0.231119 -0.0243619 -0.0427513 0.232756 -0.0250399 -0.0365534 0.232756 -0.022182 -0.0325506 0.232756 -0.0196643 -0.0283255 0.232756 -0.0175042 -0.0239069 0.229745 -0.0078924 -0.022011 0.230674 -0.0168061 0.0103147 0.230674 -0.0196417 0.0202809 0.233274 -0.0168061 0.0103147 0.230674 -0.0242603 0.0295563 0.233274 -0.0242603 0.0295563 0.233274 -0.0305047 0.0378252 0.233274 -0.0381621 0.0448058 0.230674 -0.0469718 0.0502606 0.233274 -0.0469718 0.0502606 0.233274 -0.0566339 0.0540037 0.233274 -0.0668192 0.0559076 0.230674 -0.0771809 0.0559076 0.230674 -0.0873662 0.0540037 0.233274 -0.0970282 0.0502606 0.233274 -0.105838 0.0448058 0.233274 -0.113495 0.0378252 0.233274 -0.11974 0.0295563 0.230674 -0.124358 0.0202809 0.230674 -0.12815 -2.85742e-06 0.236674 -0.01585 -2.85742e-06 0.236674 -0.0168061 0.0103147 0.236674 -0.0196417 0.0202809 0.236074 -0.0196417 0.0202809 0.236074 -0.0305047 0.0378252 0.236674 -0.0305047 0.0378252 0.236674 -0.0469718 0.0502606 0.236674 -0.0566339 0.0540037 0.236074 -0.0668192 0.0559076 0.236674 -0.0771809 0.0559076 0.236074 -0.0873662 0.0540037 0.236074 -0.0970282 0.0502606 0.236674 -0.105838 0.0448058 0.236674 -0.127194 0.0103147 0.236074 -0.127194 0.0103147 0.236074 -0.12815 -2.85742e-06 0.228874 -0.0266878 0.00901032 0.230474 -0.0293168 0.0176771 0.228874 -0.0393317 0.0326655 0.228874 -0.0543201 0.0426804 0.230474 -0.0629869 0.0453094 0.228874 -0.072 0.0461971 0.228874 -0.0976674 0.038411 0.230474 -0.08968 0.0426804 0.230474 -0.0976674 0.038411 0.228874 -0.110414 0.0256645 0.228874 -0.114683 0.0176771 0.230474 -0.110414 0.0256645 0.228874 -0.1182 -2.85742e-06 0.233696 -0.0149508 -0.0144497 0.233696 -0.013351 -0.00486265 0.233696 -0.0163387 -0.0191114 0.233696 -0.0227328 -0.0321908 0.233696 -0.0181068 -0.0236426 0.237674 -0.0166991 -0.0201307 0.233696 -0.0255591 -0.0361493 0.233696 -0.032142 -0.0433002 0.233696 -0.0287027 -0.0398609 0.237674 -0.0269183 -0.0378309 0.233696 -0.0269183 -0.0378309 0.233696 -0.0398121 -0.0492701 0.237674 -0.034172 -0.0450846 0.237674 -0.042575 -0.0509685 0.233696 -0.042575 -0.0509685 0.233696 -0.0483603 -0.0538961 0.233696 -0.0617808 -0.0579588 0.237674 -0.0617808 -0.0579588 0.237674 -0.0518722 -0.0553038 0.233696 -0.0671402 -0.0586519 0.233696 -0.0623136 -0.0580502 0.233696 -0.0816864 -0.0580502 0.237674 -0.072 -0.0588529 0.233696 -0.0911086 -0.0556642 0.233696 -0.0864469 -0.0570521 0.237674 -0.101425 -0.0509685 0.237674 -0.0921279 -0.0553038 0.233696 -0.0956398 -0.0538961 0.237674 -0.109828 -0.0450846 0.237674 -0.117082 -0.0378309 0.233696 -0.127301 -0.0201307 0.233696 -0.123757 -0.0280124 0.233696 -0.129956 -0.0102221 0.233696 -0.129049 -0.0144497 0.237674 -0.127301 -0.0201307 0.233696 -0.130047 -0.00968925 0.237674 -0.0278376 0.0370538 0.236874 -0.0349433 0.0441596 0.236874 -0.0619892 0.0567713 0.236874 -0.072 0.0576471 0.237674 -0.0619892 0.0567713 0.237674 -0.072 0.0576471 0.237674 -0.109057 0.0441596 0.236874 -0.121926 0.0288221 0.236874 -0.128774 0.010008 0.236674 -0.0223599 -0.00928221 0.230674 -0.041567 -0.0403027 0.236674 -0.041567 -0.0403027 0.236674 -0.0494903 -0.0452086 0.236674 -0.0581801 -0.0485751 0.230674 -0.0581801 -0.0485751 0.236674 -0.0673405 -0.0502874 0.230674 -0.0673405 -0.0502874 0.230674 -0.08582 -0.0485751 0.230674 -0.0945098 -0.0452086 0.236674 -0.102433 -0.0403027 0.230674 -0.10932 -0.0340245 0.236674 -0.10932 -0.0340245 0.236674 -0.114936 -0.0265877 0.230674 -0.114936 -0.0265877 0.236674 -0.11909 -0.0182456 0.230674 -0.11909 -0.0182456 0.236674 -0.12164 -0.00928221 0.230674 -0.12164 -0.00928221 0.236974 -0.0230993 -0.00972981 0.238274 -0.0230993 -0.00972981 0.238274 -0.030544 -0.0277029 0.236974 -0.0367446 -0.0352583 0.238274 -0.0443 -0.0414589 0.238274 -0.0622731 -0.0489036 0.238274 -0.072 -0.0498616 0.236974 -0.072 -0.0498616 0.238274 -0.081727 -0.0489036 0.236974 -0.081727 -0.0489036 0.238274 -0.0910802 -0.0460663 0.238274 -0.0997001 -0.0414589 0.236974 -0.0997001 -0.0414589 0.236974 -0.107255 -0.0352583 0.238274 -0.113456 -0.0277029 0.236974 -0.113456 -0.0277029 0.236974 -0.120901 -0.00972981 0.238274 -0.121859 -2.85742e-06 0.238174 -0.024 -2.85742e-06 0.238174 -0.0249223 0.00936148 0.230674 -0.0276538 0.0183659 0.238174 -0.0276538 0.0183659 0.230674 -0.0320895 0.0266645 0.238174 -0.0320895 0.0266645 0.238174 -0.0380589 0.0339383 0.230674 -0.0453327 0.0399077 0.238174 -0.0453327 0.0399077 0.238174 -0.0536312 0.0443434 0.230674 -0.0626357 0.0470748 0.238174 -0.0626357 0.0470748 0.238174 -0.072 0.0479971 0.230674 -0.0813644 0.0470748 0.230674 -0.0903688 0.0443434 0.230674 -0.0986674 0.0399077 0.238174 -0.0903688 0.0443434 0.230674 -0.105941 0.0339383 0.230674 -0.111911 0.0266645 0.230674 -0.12 -2.85742e-06 0.233696 -0.0140441 0.0102163 0.233696 -0.0149508 0.014444 0.233696 -0.0163387 0.0191057 0.2333 -0.0162613 0.0191323 0.233696 -0.0210344 0.0294221 0.2333 -0.0226643 0.0322298 0.233696 -0.0227328 0.032185 0.233696 -0.0255591 0.0361436 0.233696 -0.0287027 0.0398552 0.233696 -0.032142 0.0432945 0.233696 -0.034172 0.0450789 0.2333 -0.0358034 0.0465026 0.233696 -0.0398121 0.0492644 0.2333 -0.0397674 0.0493329 0.233696 -0.042575 0.0509627 0.233696 -0.0483603 0.0538904 0.233696 -0.0518722 0.0552981 0.233696 -0.0575532 0.0570463 0.233696 -0.0617808 0.0579531 0.233696 -0.0623136 0.0580445 0.2333 -0.0671335 0.0587276 0.2333 -0.072 0.0589289 0.233696 -0.072 0.0588471 0.233696 -0.0768598 0.0586461 0.2333 -0.0768666 0.0587276 0.2333 -0.0816999 0.0581252 0.233696 -0.0816864 0.0580445 0.2333 -0.0864669 0.0571256 0.2333 -0.0911352 0.0557358 0.233696 -0.0956398 0.0538904 0.2333 -0.0956727 0.0539653 0.233696 -0.10001 0.0517542 0.2333 -0.100048 0.0518261 0.2333 -0.104233 0.0493329 0.233696 -0.108146 0.0464381 0.2333 -0.111913 0.0433547 0.233696 -0.111858 0.0432945 0.233696 -0.115297 0.0398552 0.233696 -0.117082 0.0378252 0.2333 -0.115358 0.0399106 0.2333 -0.118506 0.0361938 0.233696 -0.121267 0.032185 0.2333 -0.121336 0.0322298 0.2333 -0.123829 0.0280456 0.233696 -0.125893 0.0236369 0.233696 -0.127301 0.020125 0.2333 -0.125968 0.0236698 0.2333 -0.127739 0.0191323 0.232968 -0.0136432 0.00973518 0.232968 -0.0146467 0.014521 0.232756 -0.014313 0.0146055 0.232968 -0.0160419 0.0192076 0.232756 -0.0175042 0.0239012 0.232968 -0.0199671 0.028156 0.232968 -0.0253115 0.0363363 0.232968 -0.0284718 0.0400677 0.232756 -0.0250399 0.0365477 0.232968 -0.0482342 0.0541777 0.232968 -0.0527896 0.0559552 0.232756 -0.0526778 0.0562808 0.232968 -0.0574762 0.0573505 0.232756 -0.0622054 0.0586935 0.232968 -0.072 0.0591609 0.232756 -0.0670859 0.0593019 0.232756 -0.0769142 0.0593019 0.232968 -0.0817381 0.058354 0.232968 -0.0865239 0.0573505 0.232756 -0.0817947 0.0586935 0.232968 -0.0912105 0.0559552 0.232756 -0.0913223 0.0562808 0.232968 -0.100159 0.0520301 0.232968 -0.10436 0.0495271 0.232756 -0.108551 0.0469573 0.232968 -0.12153 0.0323566 0.232968 -0.124033 0.028156 0.232756 -0.126496 0.0239012 0.232756 -0.129687 0.0146055 0.232968 -0.130357 0.00973518 0.232968 -0.0128363 -2.85742e-06 0.2333 -0.0132695 0.00486369 0.232968 -0.0130384 0.00488285 0.2333 -0.013872 0.009697 0.2333 -0.0148716 0.014464 0.2333 -0.0180319 0.0236698 0.232968 -0.0178194 0.023763 0.2333 -0.0201711 0.0280456 0.2333 -0.0254946 0.0361938 0.232968 -0.0224701 0.0323566 0.2333 -0.0286425 0.0399106 0.2333 -0.0320866 0.0433547 0.232968 -0.0319295 0.0435253 0.232968 -0.0356609 0.0466857 0.232968 -0.0396405 0.0495271 0.2333 -0.0439516 0.0518261 0.232968 -0.0438412 0.0520301 0.2333 -0.0483274 0.0539653 0.2333 -0.0528649 0.0557358 0.2333 -0.0575331 0.0571256 0.232968 -0.062262 0.058354 0.2333 -0.0623002 0.0581252 0.232968 -0.0671143 0.0589588 0.232968 -0.0768857 0.0589588 0.232968 -0.0957659 0.0541777 0.2333 -0.108197 0.0465026 0.232968 -0.108339 0.0466857 0.232968 -0.112071 0.0435253 0.232968 -0.115528 0.0400677 0.232968 -0.118689 0.0363363 0.232968 -0.126181 0.023763 0.232968 -0.127958 0.0192076 0.232968 -0.129353 0.014521 0.233696 -0.129049 0.014444 0.2333 -0.129129 0.014464 0.232756 -0.130696 0.00979183 0.232968 -0.130962 0.00488285 0.2333 -0.130731 0.00486369 0.2333 -0.130128 0.009697 0.233696 -0.130047 0.00968353 0.2333 -0.130932 -2.85742e-06 0.233696 -0.13085 -2.85742e-06 0.233774 -0.129431 0.00502167 0.233774 -0.124249 0.0243611 0.233774 -0.121926 0.0288221 0.233774 -0.119224 0.0330638 0.233774 -0.116163 0.0370538 0.233774 -0.112765 0.0407618 0.235574 -0.109057 0.0441596 0.233774 -0.105067 0.0472213 0.235574 -0.100825 0.0499235 0.235574 -0.096364 0.0522458 0.235574 -0.086921 0.0556828 0.235574 -0.0770246 0.0574278 0.235574 -0.072 0.0576471 0.233774 -0.072 0.0576471 0.235574 -0.0522826 0.0541704 0.233774 -0.0570791 0.0556828 0.235574 -0.0476361 0.0522458 0.233774 -0.0476361 0.0522458 0.233774 -0.043175 0.0499235 0.233774 -0.0389334 0.0472213 0.235574 -0.0312353 0.0407618 0.233774 -0.0349433 0.0441596 0.235574 -0.0278376 0.0370538 0.233774 -0.0278376 0.0370538 0.233774 -0.0247759 0.0330638 0.235574 -0.0197514 0.0243611 0.235574 -0.0178268 0.0197146 0.233774 -0.0197514 0.0243611 0.233774 -0.0163144 0.0149181 0.235574 -0.01435 -2.85742e-06 0.233774 -0.01435 -2.85742e-06 0.235834 -0.0145 -2.85742e-06 0.235786 -0.129562 -2.85742e-06 0.235724 -0.129391 0.00501817 0.235574 -0.129431 0.00502167 0.235574 -0.128774 0.010008 0.235574 -0.127686 0.0149181 0.235574 -0.126173 0.0197146 0.235574 -0.124249 0.0243611 0.235574 -0.121926 0.0288221 0.235574 -0.119224 0.0330638 0.235574 -0.116163 0.0370538 0.235574 -0.112765 0.0407618 0.235574 -0.105067 0.0472213 0.235724 -0.105044 0.0471883 0.235724 -0.100805 0.0498887 0.235724 -0.096347 0.0522094 0.235574 -0.0917175 0.0541704 0.235574 -0.0820109 0.0567713 0.235724 -0.072 0.057607 0.235574 -0.0669755 0.0574278 0.235574 -0.0619892 0.0567713 0.235574 -0.0570791 0.0556828 0.235724 -0.0522963 0.0541327 0.235574 -0.043175 0.0499235 0.235574 -0.0389334 0.0472213 0.235724 -0.0349692 0.0441288 0.235574 -0.0349433 0.0441596 0.235724 -0.0278684 0.037028 0.235724 -0.0248089 0.0330408 0.235574 -0.0247759 0.0330638 0.235574 -0.0220737 0.0288221 0.235724 -0.0178645 0.0197009 0.235574 -0.0163144 0.0149181 0.235574 -0.0152259 0.010008 0.235724 -0.0146095 0.00501817 0.235724 -0.0143902 -2.85742e-06 0.235574 -0.0145694 0.00502167 0.235834 -0.0147188 0.0050086 0.235724 -0.0152655 0.010001 0.235724 -0.0163532 0.0149077 0.235834 -0.0164593 0.0148792 0.235834 -0.0179677 0.0196633 0.235724 -0.0197878 0.0243441 0.235724 -0.0221085 0.028802 0.235834 -0.0248988 0.0329778 0.235834 -0.0279525 0.0369574 0.235724 -0.0312638 0.0407334 0.235724 -0.0389564 0.0471883 0.235724 -0.0431951 0.0498887 0.235834 -0.0476995 0.0521098 0.235724 -0.0476531 0.0522094 0.235834 -0.0523339 0.0540295 0.235724 -0.0570895 0.0556439 0.235724 -0.0619962 0.0567317 0.235724 -0.066979 0.0573877 0.235724 -0.0770211 0.0573877 0.235724 -0.0820039 0.0567317 0.235724 -0.0869106 0.0556439 0.235724 -0.0917038 0.0541327 0.235834 -0.0916662 0.0540295 0.235834 -0.10075 0.0497936 0.235724 -0.109031 0.0441288 0.235834 -0.10896 0.0440447 0.235724 -0.112736 0.0407334 0.235724 -0.116132 0.037028 0.235834 -0.112659 0.0406558 0.235724 -0.119191 0.0330408 0.235724 -0.121892 0.028802 0.235834 -0.121797 0.0287471 0.235724 -0.124212 0.0243441 0.235724 -0.126136 0.0197009 0.235724 -0.127647 0.0149077 0.235724 -0.128735 0.010001 0.235834 -0.128626 0.00998191 0.235834 -0.129281 0.0050086 0.235851 -0.129465 -2.85742e-06 0.235874 -0.129132 0.00499552 0.235874 -0.128479 0.00995587 0.235874 -0.127396 0.0148404 0.235874 -0.125891 0.019612 0.235834 -0.127541 0.0148792 0.235834 -0.126032 0.0196633 0.235834 -0.124113 0.0242977 0.235834 -0.119101 0.0329778 0.235874 -0.115933 0.036861 0.235834 -0.116048 0.0369574 0.235874 -0.108864 0.0439298 0.235834 -0.104981 0.0470984 0.235874 -0.100675 0.0496637 0.235834 -0.0963006 0.0521098 0.235834 -0.0868821 0.0555379 0.235874 -0.0868433 0.055393 0.235834 -0.0819848 0.0566236 0.235834 -0.0770115 0.0572783 0.235834 -0.072 0.0574971 0.235874 -0.0670017 0.0571289 0.235834 -0.0669886 0.0572783 0.235834 -0.0620153 0.0566236 0.235874 -0.0571568 0.055393 0.235874 -0.0523852 0.0538885 0.235834 -0.0571179 0.0555379 0.235874 -0.043325 0.0496637 0.235874 -0.0391054 0.0469755 0.235834 -0.04325 0.0497936 0.235834 -0.0390194 0.0470984 0.235834 -0.0350398 0.0440447 0.235874 -0.0351362 0.0439298 0.235834 -0.0313414 0.0406558 0.235874 -0.0223335 0.0286721 0.235834 -0.0222036 0.0287471 0.235834 -0.0198873 0.0242977 0.235874 -0.0166042 0.0148404 0.235874 -0.0155213 0.00995587 0.235874 -0.0148683 0.00499552 0.235834 -0.0153736 0.00998191 0.233562 -0.129562 -2.85742e-06 0.233514 -0.129281 0.0050086 0.233497 -0.0145352 -2.85742e-06 0.233562 -0.0144379 -2.85742e-06 0.233624 -0.0143902 -2.85742e-06 0.233624 -0.0146095 0.00501817 0.233774 -0.0145694 0.00502167 0.233624 -0.0163532 0.0149077 0.233774 -0.0152259 0.010008 0.233774 -0.0178268 0.0197146 0.233624 -0.0178645 0.0197009 0.233624 -0.0197878 0.0243441 0.233624 -0.0221085 0.028802 0.233624 -0.0248089 0.0330408 0.233774 -0.0220737 0.0288221 0.233624 -0.0278684 0.037028 0.233774 -0.0312353 0.0407618 0.233624 -0.0476531 0.0522094 0.233624 -0.0522963 0.0541327 0.233774 -0.0522826 0.0541704 0.233624 -0.0619962 0.0567317 0.233774 -0.0619892 0.0567713 0.233624 -0.066979 0.0573877 0.233774 -0.0669755 0.0574278 0.233624 -0.072 0.057607 0.233774 -0.0770246 0.0574278 0.233624 -0.0820039 0.0567317 0.233774 -0.0820109 0.0567713 0.233624 -0.0917038 0.0541327 0.233774 -0.086921 0.0556828 0.233774 -0.0917175 0.0541704 0.233774 -0.096364 0.0522458 0.233624 -0.100805 0.0498887 0.233624 -0.105044 0.0471883 0.233774 -0.100825 0.0499235 0.233624 -0.109031 0.0441288 0.233624 -0.112736 0.0407334 0.233774 -0.109057 0.0441596 0.233624 -0.126136 0.0197009 0.233774 -0.126173 0.0197146 0.233624 -0.127647 0.0149077 0.233624 -0.128735 0.010001 0.233774 -0.127686 0.0149181 0.233774 -0.128774 0.010008 0.233624 -0.12961 -2.85742e-06 0.233624 -0.129391 0.00501817 0.233514 -0.128626 0.00998191 0.233514 -0.127541 0.0148792 0.233624 -0.124212 0.0243441 0.233514 -0.126032 0.0196633 0.233624 -0.121892 0.028802 0.233624 -0.119191 0.0330408 0.233514 -0.119101 0.0329778 0.233624 -0.116132 0.037028 0.233514 -0.116048 0.0369574 0.233514 -0.10075 0.0497936 0.233514 -0.0963006 0.0521098 0.233624 -0.096347 0.0522094 0.233624 -0.0869106 0.0556439 0.233514 -0.0819848 0.0566236 0.233624 -0.0770211 0.0573877 0.233514 -0.072 0.0574971 0.233514 -0.0571179 0.0555379 0.233624 -0.0570895 0.0556439 0.233514 -0.0523339 0.0540295 0.233624 -0.0431951 0.0498887 0.233624 -0.0389564 0.0471883 0.233514 -0.04325 0.0497936 0.233514 -0.0390194 0.0470984 0.233624 -0.0349692 0.0441288 0.233514 -0.0350398 0.0440447 0.233624 -0.0312638 0.0407334 0.233514 -0.0248988 0.0329778 0.233514 -0.0198873 0.0242977 0.233624 -0.0152655 0.010001 0.233514 -0.0145 -2.85742e-06 0.233474 -0.0148683 0.00499552 0.233514 -0.0147188 0.0050086 0.233514 -0.0153736 0.00998191 0.233514 -0.0164593 0.0148792 0.233474 -0.0181087 0.019612 0.233514 -0.0179677 0.0196633 0.233514 -0.0222036 0.0287471 0.233474 -0.0280674 0.036861 0.233514 -0.0279525 0.0369574 0.233514 -0.0313414 0.0406558 0.233474 -0.0391054 0.0469755 0.233514 -0.0476995 0.0521098 0.233514 -0.0620153 0.0566236 0.233474 -0.0670017 0.0571289 0.233514 -0.0669886 0.0572783 0.233474 -0.0769984 0.0571289 0.233474 -0.0819588 0.0564759 0.233514 -0.0770115 0.0572783 0.233474 -0.0916149 0.0538885 0.233514 -0.0868821 0.0555379 0.233514 -0.0916662 0.0540295 0.233474 -0.0962372 0.0519739 0.233474 -0.100675 0.0496637 0.233514 -0.104981 0.0470984 0.233514 -0.10896 0.0440447 0.233474 -0.112553 0.0405497 0.233474 -0.115933 0.036861 0.233514 -0.112659 0.0406558 0.233474 -0.118978 0.0328918 0.233474 -0.123977 0.0242343 0.233514 -0.121797 0.0287471 0.233514 -0.124113 0.0242977 0.233474 -0.125891 0.019612 0.233474 -0.127396 0.0148404 0.233474 -0.129132 0.00499552 0.236074 -0.124358 0.0202809 0.235874 -0.11991 0.0296616 0.236074 -0.11974 0.0295563 0.236074 -0.113495 0.0378252 0.236074 -0.105838 0.0448058 0.236074 -0.0771809 0.0559076 0.236074 -0.0566339 0.0540037 0.235874 -0.0565791 0.054196 0.236074 -0.0469718 0.0502606 0.236074 -0.0381621 0.0448058 0.235874 -0.0303569 0.0379599 0.235874 -0.0240903 0.0296616 0.236074 -0.0242603 0.0295563 0.236074 -0.0168061 0.0103147 0.235874 -0.0194552 0.0203531 0.235874 -0.0166095 0.0103514 0.233274 -0.0196417 0.0202809 0.233474 -0.0166095 0.0103514 0.233474 -0.0303569 0.0379599 0.233474 -0.0668007 0.0561068 0.233274 -0.0771809 0.0559076 0.233274 -0.0873662 0.0540037 0.233474 -0.0971174 0.0504396 0.233474 -0.113643 0.0379599 0.233474 -0.11991 0.0296616 0.233274 -0.124358 0.0202809 0.233274 -0.127194 0.0103147 0.229848 -0.085888 -0.0630295 0.224774 -0.0875023 -0.0622295 0.224774 -0.088088 -0.0616439 0.224774 -0.088888 -0.0614295 0.226574 -0.088088 -0.0616439 0.226574 -0.088888 -0.0614295 0.224774 -0.089688 -0.0616439 0.226574 -0.089688 -0.0616439 0.224774 -0.0902736 -0.0622295 0.226574 -0.086477 -0.0656228 0.226574 -0.086227 0.0616386 0.226574 -0.0884964 0.0600495 0.230921 -0.0881063 0.0601274 0.226574 -0.0871673 0.0605663 0.230801 -0.0870308 0.0606678 0.226574 -0.089914 0.0602047 0.230135 -0.0911021 0.0609995 0.229997 -0.0913044 0.0612459 0.229484 -0.0917858 0.0622473 0.230913 -0.11626 0.0437972 0.230921 -0.116014 0.0440184 0.230891 -0.115632 0.0444875 0.230849 -0.115465 0.044776 0.230801 -0.115352 0.0450241 0.226574 -0.116375 0.0437088 0.226574 -0.117669 0.0431728 0.230638 -0.117675 0.043172 0.230124 -0.119069 0.0432837 0.229997 -0.119343 0.043388 0.230871 -0.132027 0.0168851 0.230921 -0.132128 0.0161138 0.230913 -0.13223 0.0157992 0.230774 -0.13208 -0.0174522 0.229997 -0.133249 -0.0193073 0.226574 -0.133092 -0.0191839 0.230429 -0.115144 -0.0463164 0.226574 -0.115367 -0.0472896 0.224774 -0.0537265 -0.0622295 0.226574 -0.0537265 -0.0622295 0.224774 -0.0543121 -0.0616439 0.226574 -0.0543121 -0.0616439 0.226574 -0.0551121 -0.0614295 0.224774 -0.0559121 -0.0616439 0.224774 -0.0564977 -0.0622295 0.226574 -0.0564977 -0.0622295 0.224774 -0.0567121 -0.0630295 0.224774 -0.0242613 -0.0461416 0.224774 -0.0244757 -0.0453416 0.224774 -0.0250613 -0.0447559 0.224774 -0.0258613 -0.0445416 0.226574 -0.0266613 -0.0447559 0.224774 -0.027247 -0.0453416 0.226574 -0.027247 -0.0453416 0.224774 -0.00817338 -0.0155052 0.226574 -0.00817338 -0.0155052 0.224774 -0.00977338 -0.0155052 0.224774 -0.010359 -0.0160908 0.224774 -0.0105734 -0.0168908 0.224774 -0.00758774 0.0176851 0.226574 -0.00737338 0.0168851 0.224774 -0.00817338 0.0182707 0.226574 -0.00817338 0.0182707 0.224774 -0.00977338 0.0182707 0.226574 -0.010359 0.0176851 0.224774 -0.0242613 0.0461359 0.226574 -0.0242613 0.0461359 0.226574 -0.0244757 0.0469359 0.224774 -0.0250613 0.0475215 0.224774 -0.0258613 0.0477359 0.226574 -0.0250613 0.0475215 0.226574 -0.0258613 0.0477359 0.224774 -0.0266613 0.0475215 0.226574 -0.027247 0.0469359 0.226574 -0.0274613 0.0461359 0.226574 -0.0535121 0.0630238 0.226574 -0.0537265 0.0638238 0.226574 -0.0543121 0.0644094 0.224774 -0.0551121 0.0646238 0.226574 -0.0551121 0.0646238 0.224774 -0.0559121 0.0644094 0.224774 -0.0564977 0.0638238 0.226574 -0.0875023 0.0638238 0.226574 -0.088088 0.0644094 0.224774 -0.088888 0.0646238 0.226574 -0.088888 0.0646238 0.224774 -0.090488 0.0630238 0.224774 -0.116539 0.0461359 0.226574 -0.116539 0.0461359 0.224774 -0.116753 0.0469359 0.224774 -0.117339 0.0475215 0.226574 -0.117339 0.0475215 0.224774 -0.118939 0.0475215 0.226574 -0.118939 0.0475215 0.224774 -0.119739 0.0461359 0.224774 -0.133641 0.0176851 0.224774 -0.134227 0.0182707 0.226574 -0.136412 0.0176851 0.224774 -0.136412 0.0176851 0.224774 -0.133427 -0.0168908 0.226574 -0.133641 -0.0160908 0.226574 -0.134227 -0.0155052 0.226574 -0.135027 -0.0152908 0.224774 -0.135827 -0.0155052 0.226574 -0.136412 -0.0160908 0.226574 -0.136627 -0.0168908 0.224774 -0.116753 -0.0453416 0.226574 -0.116539 -0.0461416 0.226574 -0.117339 -0.0447559 0.226574 -0.118139 -0.0445416 0.224774 -0.118939 -0.0447559 0.226574 -0.118939 -0.0447559 0.226574 -0.119524 -0.0453416 0.224774 -0.119739 -0.0461416 0.228744 -0.0861252 0.0666652 0.226376 -0.0861252 0.0666652 0.226301 -0.085934 0.0667821 0.228738 -0.085712 0.0668555 0.228777 -0.086502 0.0660102 0.226574 -0.0865111 0.0658759 0.228767 -0.0864546 0.0662074 0.226574 -0.0864112 0.0663115 0.228761 -0.0864113 0.0663115 0.228751 -0.0862912 0.0665016 0.226362 -0.117553 0.050702 0.226274 -0.117304 0.0510422 0.226574 -0.136696 -0.0207801 0.226574 -0.136453 -0.020477 0.228773 -0.136476 -0.0204967 0.226574 -0.136067 -0.0202754 0.226541 -0.136717 -0.0208235 0.228754 -0.136717 -0.0208234 0.226325 -0.136808 -0.0212413 0.228741 -0.136808 -0.0212413 0.226574 -0.117347 -0.0495929 0.228775 -0.117584 -0.0499687 0.226574 -0.117565 -0.0499195 0.238474 -0.121659 -2.85742e-06 0.238274 -0.120901 -0.00972981 0.238274 -0.118064 -0.019083 0.238474 -0.117879 -0.0190064 0.238274 -0.107255 -0.0352583 0.238474 -0.11329 -0.0275918 0.238474 -0.0910036 -0.0458815 0.238474 -0.0623121 -0.0487074 0.238274 -0.0529199 -0.0460663 0.238274 -0.0367446 -0.0352583 0.238474 -0.036886 -0.0351169 0.238474 -0.0261214 -0.0190064 0.238274 -0.0259366 -0.019083 0.236874 -0.01565 -2.85742e-06 0.236674 -0.0242603 0.0295563 0.236674 -0.0381621 0.0448058 0.236874 -0.0565791 0.054196 0.236674 -0.0668192 0.0559076 0.236874 -0.0771994 0.0561068 0.236674 -0.0873662 0.0540037 0.236674 -0.0970282 0.0502606 0.236874 -0.0874209 0.054196 0.236874 -0.0971174 0.0504396 0.236874 -0.105959 0.0449654 0.236674 -0.113495 0.0378252 0.236674 -0.11974 0.0295563 0.236874 -0.11991 0.0296616 0.236674 -0.124358 0.0202809 0.236874 -0.127391 0.0103514 0.236874 -0.12835 -2.85742e-06 0.237674 -0.0152259 0.010008 0.237674 -0.0178268 0.0197146 0.237674 -0.0220737 0.0288221 0.237874 -0.0219005 0.0289221 0.237674 -0.0349433 0.0441596 0.237674 -0.043175 0.0499235 0.237674 -0.0522826 0.0541704 0.237874 -0.043075 0.0500967 0.237674 -0.0820109 0.0567713 0.237674 -0.0917175 0.0541704 0.237874 -0.0820456 0.0569683 0.237874 -0.0917859 0.0543584 0.237674 -0.100825 0.0499235 0.237674 -0.116163 0.0370538 0.237674 -0.121926 0.0288221 0.237674 -0.126173 0.0197146 0.237874 -0.126361 0.019783 0.237674 -0.128774 0.010008 0.237674 -0.12965 -2.85742e-06 0.237674 -0.129956 -0.0102221 0.237874 -0.13065 -2.85742e-06 0.237874 -0.129759 -0.0101873 0.237874 -0.127113 -0.0200623 0.237674 -0.122966 -0.0294279 0.237674 -0.0822192 -0.0579588 0.237874 -0.0920595 -0.0551158 0.237874 -0.0618156 -0.0577618 0.237874 -0.0519406 -0.0551158 0.237874 -0.042675 -0.0507952 0.237674 -0.0210344 -0.0294279 0.237874 -0.0212077 -0.0293279 0.237874 -0.0168871 -0.0200623 0.237674 -0.0140441 -0.0102221 0.237874 -0.0142411 -0.0101873 0.228674 -0.1184 -2.85742e-06 0.228674 -0.117508 0.00904933 0.228874 -0.117312 0.00901032 0.228874 -0.104668 0.0326655 0.228674 -0.10481 0.0328069 0.228674 -0.0977785 0.0385773 0.228874 -0.08968 0.0426804 0.228674 -0.0897566 0.0428652 0.228874 -0.0810132 0.0453094 0.228674 -0.0810522 0.0455056 0.228874 -0.0629869 0.0453094 0.228674 -0.0542435 0.0428652 0.228874 -0.0463327 0.038411 0.228674 -0.0391903 0.0328069 0.228874 -0.0335861 0.0256645 0.228874 -0.0293168 0.0176771 0.230674 -0.0256 -2.85742e-06 0.230474 -0.0266878 0.00901032 0.230674 -0.0264916 0.00904933 0.230474 -0.0335861 0.0256645 0.230674 -0.0334199 0.0257756 0.230474 -0.0393317 0.0326655 0.230474 -0.0463327 0.038411 0.230474 -0.0543201 0.0426804 0.230474 -0.072 0.0461971 0.230474 -0.0810132 0.0453094 0.230674 -0.0977785 0.0385773 0.230474 -0.104668 0.0326655 0.230674 -0.10481 0.0328069 0.230674 -0.11058 0.0257756 0.230474 -0.114683 0.0176771 0.230474 -0.117312 0.00901032 0.230674 -0.117508 0.00904933 0.230474 -0.1182 -2.85742e-06 0.238474 -0.0273767 0.0184808 0.238474 -0.0378468 0.0341504 0.238474 -0.0625772 0.0473691 0.238174 -0.0813644 0.0470748 0.238474 -0.0814229 0.0473691 0.238474 -0.0904837 0.0446205 0.238174 -0.0986674 0.0399077 0.238174 -0.105941 0.0339383 0.238474 -0.11216 0.0268312 0.238174 -0.111911 0.0266645 0.238174 -0.116346 0.0183659 0.238174 -0.119078 0.00936148 0.238474 -0.119372 0.00942 0.236974 -0.121345 -0.00922708 0.236974 -0.109098 -0.0338224 0.236674 -0.0945098 -0.0452086 0.236674 -0.08582 -0.0485751 0.236674 -0.0766596 -0.0502874 0.236974 -0.0766319 -0.0499887 0.236974 -0.0673682 -0.0499887 0.236974 -0.049624 -0.0449401 0.236974 -0.0417478 -0.0400633 0.236674 -0.0346801 -0.0340245 0.236974 -0.0349018 -0.0338224 0.236674 -0.0290641 -0.0265877 0.236674 -0.0249102 -0.0182456 0.236974 -0.0226548 -0.00922708 0.236974 -0.0218 -2.85742e-06 0.225074 -0.00853037 0.00608979 0.230376 -0.00851938 0.00585104 0.229621 -0.00723037 -0.00834717 0.225074 -0.00853037 -0.0060955 0.23037 -0.00853037 -0.0060955 0.225074 -0.00842346 -0.0068334 0.230273 -0.00841082 -0.00687483 0.225074 -0.00818203 -0.0073955 0.225074 -0.00797236 -0.00770493 0.230072 -0.00807298 -0.00756832 0.225074 -0.139298 -0.00996148 0.228776 -0.138932 -0.00959545 0.224774 -0.139132 -0.0104615 0.224774 -0.139038 -0.0101115 0.225074 -0.135577 -0.0068334 0.224774 -0.13517 -0.0060955 0.224774 -0.135558 -0.0075455 0.225074 -0.13575 -2.85742e-06 0.225074 -0.135481 0.00585104 0.225074 -0.139432 0.0104558 0.225074 -0.13942 0.0106113 0.224774 -0.139132 0.0104558 0.224774 -0.139123 0.0105646 0.231383 -0.00871989 -2.85742e-06 0.219625 -0.135481 0.00585104 0.224474 -0.00851938 0.00585104 0.224774 -0.00881811 0.00582349 0.224774 -0.00871112 -0.00691854 0.224474 -0.00818203 -0.0073955 0.224774 -0.00820798 -0.00789063 0.224774 -0.00521827 -0.00985526 0.224474 -0.00462858 -0.0101195 0.221785 -0.139432 0.0104558 0.224474 -0.13923 -0.00985942 0.221158 -0.139111 -0.00972789 0.224474 -0.138932 -0.00959545 0.221785 -0.139432 -0.0104615 0.221686 -0.139414 -0.0102741 0.224474 -0.135481 0.00585104 0.224474 -0.00853037 -0.0060955 0.224474 -0.00837727 -0.00697451 0.220221 -0.00783105 -0.00786959 0.224474 -0.00853037 0.00608979 0.219817 -0.00852755 0.00596874 0.219816 -0.00851938 0.00585104 0.224774 -0.116889 -0.0461416 0.219453 -0.117013 -0.0455992 0.224774 -0.117359 -0.0451643 0.21943 -0.117359 -0.0451643 0.219498 -0.117861 -0.0449229 0.224774 -0.118417 -0.0449229 0.219643 -0.118417 -0.0449229 0.224774 -0.118918 -0.0451643 0.219836 -0.118918 -0.0451643 0.224774 -0.119265 -0.0455992 0.219443 -0.133777 -0.0168908 0.224774 -0.1339 -0.0163484 0.219435 -0.1339 -0.0163484 0.224774 -0.134247 -0.0159135 0.224774 -0.134749 -0.0156721 0.219518 -0.134247 -0.0159135 0.224774 -0.135305 -0.0156721 0.219673 -0.134749 -0.0156721 0.224774 -0.135806 -0.0159135 0.224774 -0.136153 -0.0163484 0.224774 -0.136277 -0.0168908 0.220229 -0.136153 -0.0163484 0.220322 -0.136277 -0.0168908 0.224774 -0.1339 0.0174274 0.219539 -0.1339 0.0174274 0.224774 -0.134247 0.0178624 0.219704 -0.134247 0.0178624 0.224774 -0.134749 0.0181037 0.219904 -0.134749 0.0181037 0.224774 -0.135305 0.0181037 0.220098 -0.135305 0.0181037 0.22025 -0.135806 0.0178624 0.22033 -0.136153 0.0174274 0.224774 -0.136277 0.0168851 0.219563 -0.116889 0.0461359 0.219769 -0.117056 0.0467609 0.224774 -0.117056 0.0467609 0.224774 -0.117514 0.0472184 0.220004 -0.117514 0.0472184 0.224774 -0.118139 0.0473859 0.220206 -0.118139 0.0473859 0.224774 -0.119221 0.0467609 0.220277 -0.119347 0.0464573 0.224774 -0.087638 0.0630238 0.219769 -0.087638 0.0630238 0.224774 -0.0877618 0.0635662 0.219971 -0.0877618 0.0635662 0.224774 -0.0881086 0.0640011 0.220155 -0.0881086 0.0640011 0.224774 -0.0886098 0.0642425 0.224774 -0.0891661 0.0642425 0.220337 -0.0891661 0.0642425 0.224774 -0.0896674 0.0640011 0.224774 -0.0538621 0.0630238 0.220277 -0.0542269 0.0639064 0.224774 -0.0540296 0.0636488 0.220322 -0.0551121 0.0642738 0.224774 -0.0551121 0.0642738 0.220277 -0.0554378 0.0642306 0.220206 -0.0557371 0.0641063 0.224774 -0.0557371 0.0641063 0.220004 -0.0561946 0.0636488 0.220322 -0.0247788 0.0467609 0.224774 -0.0252363 0.0472184 0.220322 -0.0252363 0.0472184 0.220277 -0.0255401 0.0473439 0.220206 -0.0258613 0.0473859 0.220004 -0.0264863 0.0472184 0.224774 -0.0269439 0.0467609 0.220322 -0.00772338 0.0168851 0.224774 -0.00784717 0.0174274 0.22033 -0.00784717 0.0174274 0.224774 -0.00819402 0.0178624 0.224774 -0.00869523 0.0181037 0.219704 -0.00975274 0.0178624 0.219539 -0.0100996 0.0174274 0.224774 -0.00784717 -0.0163484 0.220068 -0.00819402 -0.0159135 0.224774 -0.00869523 -0.0156721 0.219518 -0.00975274 -0.0159135 0.224774 -0.0102234 -0.0168908 0.219443 -0.0102234 -0.0168908 0.220206 -0.0246113 -0.0461416 0.224774 -0.0247351 -0.0455992 0.224774 -0.025082 -0.0451643 0.219643 -0.0255832 -0.0449229 0.219498 -0.0261395 -0.0449229 0.219453 -0.0269875 -0.0455992 0.224774 -0.0539859 -0.0624872 0.219802 -0.0539859 -0.0624872 0.219615 -0.0543327 -0.0620522 0.224774 -0.0548339 -0.0618109 0.224774 -0.0553902 -0.0618109 0.219466 -0.0558915 -0.0620522 0.224774 -0.0558915 -0.0620522 0.224774 -0.0562383 -0.0624872 0.219588 -0.0562383 -0.0624872 0.219588 -0.0877618 -0.0624872 0.224774 -0.0881086 -0.0620522 0.219466 -0.0881086 -0.0620522 0.224774 -0.0886098 -0.0618109 0.219428 -0.0886098 -0.0618109 0.224774 -0.0891661 -0.0618109 0.219481 -0.0891661 -0.0618109 0.224774 -0.0896674 -0.0620522 0.219615 -0.0896674 -0.0620522 0.224774 -0.0900142 -0.0624872 0.219802 -0.0900142 -0.0624872 0.185974 -0.113473 0.0088126 0.186474 -0.105898 0.0246253 0.185974 -0.110734 0.0172428 0.186474 -0.100037 0.0311349 0.185974 -0.100371 0.0315065 0.185974 -0.0932 0.0367166 0.186474 -0.09295 0.0362836 0.185974 -0.0851024 0.0403219 0.186474 -0.0763798 0.0416676 0.185974 -0.076432 0.0421649 0.185974 -0.0508 0.0367166 0.186474 -0.05105 0.0362836 0.186474 -0.0439635 0.0311349 0.185974 -0.0436289 0.0315065 0.185974 -0.0376977 0.0249192 0.185974 -0.0305266 0.0088126 0.186474 -0.0310157 0.00870864 0.185974 -0.0296 -2.85742e-06 0.187974 -0.00920004 -2.85742e-06 0.185974 -0.0112 -2.85742e-06 0.187974 -0.0129873 -0.0214817 0.185974 -0.0148667 -0.0207977 0.187974 -0.0176136 -0.0314029 0.185974 -0.0254245 -0.0390843 0.187974 -0.0238925 -0.0403699 0.185974 -0.0329186 -0.0465784 0.187974 -0.0505212 -0.0590156 0.185974 -0.0614422 -0.0598792 0.187974 -0.072 -0.0628029 0.187974 -0.0829052 -0.0618488 0.187974 -0.0934789 -0.0590156 0.185974 -0.0927949 -0.0571362 0.185974 -0.1024 -0.0526572 0.185974 -0.111082 -0.0465784 0.185974 -0.118576 -0.0390843 0.185974 -0.129133 -0.0207977 0.187974 -0.131013 -0.0214817 0.187974 -0.133846 -0.010908 0.187974 -0.1348 -2.85742e-06 0.219219 -0.00886953 0.00613242 0.218686 -0.00933806 0.00525018 0.21829 -0.0100438 0.0102569 0.21829 -0.0101541 0.0109022 0.218686 -0.0109897 0.0152239 0.21829 -0.011069 0.0152041 0.21829 -0.0129873 0.021476 0.218686 -0.0163994 0.0293687 0.21829 -0.0176136 0.0313971 0.21829 -0.0218901 0.0378499 0.218686 -0.0218248 0.0378992 0.218686 -0.025034 0.0418099 0.21829 -0.031633 0.0481047 0.21829 -0.032393 0.0487324 0.21829 -0.0364388 0.0517585 0.218686 -0.0363925 0.0518259 0.21829 -0.0406 0.0543835 0.21829 -0.0407148 0.0544496 0.218686 -0.0451583 0.0568623 0.21829 -0.0451932 0.0567883 0.218686 -0.0498163 0.0588359 0.218686 -0.0546179 0.0604288 0.21829 -0.0610949 0.0618431 0.218686 -0.059532 0.0616305 0.218686 -0.0645268 0.0624333 0.21829 -0.0645365 0.0623521 0.218686 -0.0746289 0.062824 0.21829 -0.0796608 0.0623281 0.218686 -0.0796707 0.0624093 0.21829 -0.0829052 0.0618431 0.218686 -0.084663 0.0615907 0.21829 -0.0846465 0.0615106 0.21829 -0.0943407 0.058689 0.21829 -0.103457 0.0543504 0.218686 -0.107771 0.051713 0.21829 -0.111761 0.0486069 0.218686 -0.111813 0.0486702 0.21829 -0.112367 0.0481047 0.218686 -0.119098 0.0416611 0.218686 -0.122295 0.0377403 0.21829 -0.12223 0.0376912 0.218686 -0.125166 0.0335751 0.218686 -0.12986 0.0246212 0.21829 -0.131013 0.021476 0.218686 -0.131652 0.0198904 0.21829 -0.132979 0.0150113 0.21829 -0.133846 0.0109022 0.218686 -0.134678 0.00505194 0.219021 -0.00888272 -2.85742e-06 0.219018 -0.00910689 0.00526956 0.219018 -0.00973425 0.0103082 0.218686 -0.00996311 0.0102703 0.219018 -0.0121913 0.0201531 0.218686 -0.0124111 0.020079 0.218686 -0.0142183 0.0248041 0.219018 -0.0161943 0.029477 0.219018 -0.0187446 0.0338676 0.218686 -0.0189404 0.0337431 0.219018 -0.0283868 0.0456176 0.218686 -0.0285471 0.04545 0.218686 -0.0323415 0.0487959 0.219018 -0.0321952 0.0489759 0.218686 -0.0406741 0.0545205 0.219018 -0.0450593 0.057072 0.219018 -0.059486 0.0618578 0.218686 -0.06957 0.062832 0.219018 -0.079699 0.0626396 0.219018 -0.089638 0.0605962 0.218686 -0.0895732 0.0603735 0.218686 -0.0943697 0.0587655 0.218686 -0.0990215 0.0567771 0.218686 -0.103498 0.0544212 0.219018 -0.107903 0.0519038 0.218686 -0.115597 0.0453123 0.219018 -0.125362 0.033699 0.219018 -0.127899 0.0293004 0.218686 -0.127693 0.0291927 0.218686 -0.133058 0.0150309 0.218686 -0.134069 0.010074 0.219018 -0.13491 0.00507059 0.218686 -0.134882 -2.85742e-06 0.219018 -0.134298 0.0101112 0.219018 -0.133283 0.0150863 0.219018 -0.131872 0.0199638 0.21923 -0.132199 0.0200727 0.219018 -0.130073 0.0247121 0.21923 -0.13039 0.0248469 0.21923 -0.128204 0.0294602 0.219018 -0.12248 0.0378795 0.21923 -0.125653 0.0338828 0.219018 -0.119272 0.0418148 0.21923 -0.11953 0.0420429 0.219018 -0.115757 0.0454795 0.219018 -0.11196 0.0488497 0.21923 -0.108099 0.0521869 0.219018 -0.103615 0.054622 0.21923 -0.103787 0.0549199 0.219018 -0.0991212 0.0569865 0.219018 -0.0944523 0.0589823 0.219018 -0.0847097 0.0618179 0.219018 -0.0746386 0.0630557 0.219018 -0.069561 0.0630638 0.21923 -0.0746529 0.0633996 0.219018 -0.0644992 0.0626636 0.21923 -0.0594178 0.0621952 0.219018 -0.0545538 0.0606517 0.21923 -0.0544587 0.0609825 0.219018 -0.0497345 0.059053 0.21923 -0.0496131 0.0593751 0.21923 -0.0449124 0.0573833 0.219018 -0.0405585 0.0547217 0.21923 -0.040387 0.0550202 0.219018 -0.0362612 0.0520171 0.219018 -0.0248607 0.0419641 0.21923 -0.0281489 0.0458665 0.21923 -0.0246036 0.042193 0.219018 -0.0216397 0.038039 0.21923 -0.0184542 0.0340524 0.219018 -0.0140051 0.0248957 0.21923 -0.0118651 0.020263 0.219018 -0.0107646 0.0152801 0.21923 -0.00939466 0.0103644 0.21829 -0.00920004 -2.85742e-06 0.21829 -0.0110249 -0.0150319 0.187974 -0.0101541 -0.010908 0.21829 -0.00965792 -0.00757256 0.21829 -0.0203167 -0.0356773 0.21829 -0.0176136 -0.0314029 0.21829 -0.0238925 -0.0403699 0.21829 -0.0249936 -0.041647 0.21829 -0.0303559 -0.0470093 0.187974 -0.031633 -0.0481104 0.187974 -0.0406 -0.0543893 0.21829 -0.0428154 -0.0556095 0.21829 -0.0406 -0.0543893 0.21829 -0.0505212 -0.0590156 0.21829 -0.056971 -0.060978 0.21829 -0.0610949 -0.0618488 0.21829 -0.0644303 -0.062345 0.187974 -0.0610949 -0.0618488 0.21829 -0.072 -0.0628029 0.21829 -0.0795697 -0.062345 0.21829 -0.0934789 -0.0590156 0.187974 -0.112367 -0.0481104 0.21829 -0.1034 -0.0543893 0.187974 -0.1034 -0.0543893 0.21829 -0.113644 -0.0470093 0.187974 -0.120108 -0.0403699 0.187974 -0.126386 -0.0314029 0.21829 -0.130719 -0.022272 0.220803 -0.0062371 0.0164101 0.22025 -0.00819402 0.0178624 0.220098 -0.00869523 0.0181037 0.219904 -0.00925153 0.0181037 0.219443 -0.0102234 0.0168851 0.21923 -0.0104306 0.0153635 0.21932 -0.00870265 0.00718854 0.219471 -0.00836443 0.00786765 0.220004 -0.00834838 0.0158026 0.220803 -0.00500047 0.0102542 0.220777 -0.00506237 0.0101817 0.219769 -0.00897338 0.0156351 0.219903 -0.00730004 0.00887395 0.219564 -0.00814552 0.00816236 0.219258 -0.135535 -2.85742e-06 0.21923 -0.135253 0.00509826 0.219258 -0.135267 0.00583134 0.219471 -0.135667 0.00761091 0.219902 -0.136728 0.00866052 0.220775 -0.138966 0.00996224 0.220803 -0.139034 0.0100243 0.21923 -0.134638 0.0101664 0.219769 -0.135027 0.0156351 0.21923 -0.133618 0.0151686 0.219443 -0.133777 0.0168851 0.220803 -0.136973 0.0193018 0.220322 -0.136277 0.0168851 0.220803 -0.138904 0.010859 0.220803 -0.133064 0.0294143 0.220803 -0.132032 0.0314669 0.21923 -0.122756 0.0380861 0.220803 -0.126213 0.0406804 0.21943 -0.117359 0.0451586 0.21923 -0.115996 0.0457275 0.220337 -0.119022 0.04702 0.220322 -0.118764 0.0472184 0.220803 -0.120698 0.0471419 0.220277 -0.11846 0.0473437 0.220322 -0.119221 0.0467609 0.21923 -0.112178 0.0491162 0.21923 -0.0992691 0.0572974 0.220803 -0.101126 0.0612001 0.21923 -0.0945747 0.059304 0.220803 -0.0934003 0.0643103 0.220803 -0.0909421 0.0650767 0.2203 -0.0896674 0.0640011 0.220182 -0.0900142 0.0635662 0.220004 -0.090138 0.0630238 0.219563 -0.089513 0.0619413 0.21949 -0.0892141 0.0618171 0.219443 -0.088888 0.0617738 0.21923 -0.0897342 0.0609267 0.219427 -0.0885643 0.0618164 0.21923 -0.084779 0.0621551 0.220286 -0.0886098 0.0642425 0.219563 -0.0878054 0.0623988 0.21923 -0.079741 0.0629812 0.21923 -0.0695477 0.0634077 0.220803 -0.0693807 0.0677267 0.21923 -0.0644583 0.0630054 0.220803 -0.0612581 0.0669207 0.220803 -0.0585608 0.0664316 0.219769 -0.0563621 0.0630238 0.219466 -0.0558915 0.0620465 0.219428 -0.0553902 0.0618051 0.219481 -0.0548339 0.0618051 0.220803 -0.050725 0.0643518 0.220004 -0.0538621 0.0630238 0.220206 -0.0540296 0.0636488 0.220322 -0.0544871 0.0641063 0.220337 -0.0547882 0.0642311 0.219802 -0.0539859 0.0624814 0.220803 -0.0480883 0.0634194 0.220803 -0.0407363 0.0601364 0.220803 -0.0382338 0.0587678 0.21923 -0.0360663 0.0523009 0.21949 -0.0261824 0.0449278 0.219563 -0.0258613 0.0448859 0.219769 -0.0269439 0.0467609 0.21923 -0.0319781 0.049243 0.219563 -0.0271113 0.0461359 0.220004 -0.0247788 0.0455109 0.220803 -0.0213754 0.045067 0.220206 -0.0246113 0.0461359 0.220803 -0.0233936 0.0472366 0.220277 -0.0246533 0.046457 0.220337 -0.0249775 0.0470198 0.220803 -0.0292521 0.0525972 0.21923 -0.021365 0.0382465 0.21923 -0.0158899 0.0296378 0.21923 -0.0136888 0.0250314 0.186474 -0.0337225 0.0170394 0.213124 -0.0337225 0.0170394 0.186474 -0.0381022 0.0246253 0.213124 -0.05105 0.0362836 0.186474 -0.0590522 0.0398464 0.186474 -0.0676203 0.0416676 0.213124 -0.0763798 0.0416676 0.186474 -0.0849479 0.0398464 0.213124 -0.105898 0.0246253 0.186474 -0.110278 0.0170394 0.213124 -0.110278 0.0170394 0.186474 -0.112984 0.00870864 0.187574 -0.0507963 -0.0258275 0.187574 -0.0518218 -0.0255527 0.187574 -0.0520966 -0.0258275 0.187574 -0.0514465 -0.0254521 0.187123 -0.0514465 -0.0262029 0.187574 -0.0925536 0.0269479 0.187574 -0.0919035 0.0265725 0.187123 -0.0925536 0.0261971 0.187574 -0.0510711 0.0268473 0.187574 -0.0507963 0.0265725 0.187123 -0.0514465 0.0261971 0.187574 -0.0520966 0.0265725 0.187574 -0.0919035 -0.0258275 0.187123 -0.0925536 -0.0262029 0.185774 -0.11697 -0.0178989 0.185974 -0.112629 -0.0259366 0.185774 -0.107166 -0.0332584 0.185974 -0.027469 0.0184425 0.185774 -0.0451104 0.0402403 0.185974 -0.0452216 0.040074 0.185774 -0.0534782 0.0447129 0.185774 -0.0625577 0.0474671 0.185974 -0.0814034 0.047271 0.185774 -0.0988896 0.0402403 0.185974 -0.0904454 0.0445281 0.185974 -0.0987785 0.040074 0.185774 -0.112243 0.0268867 0.185774 -0.116716 0.018519 0.185974 -0.112077 0.0267756 0.185774 -0.11947 0.00943951 0.185774 -0.1204 -2.85742e-06 0.185974 -0.1202 -2.85742e-06 0.183974 -0.0375804 -0.0226464 0.183974 -0.0365485 -0.020994 0.184974 -0.037409 -0.0204845 0.184974 -0.0367687 -0.0193625 0.184974 -0.0343262 -0.0140287 0.184974 -0.0335032 -0.01158 0.184974 -0.0236 -2.85742e-06 0.184974 -0.0244653 -0.00911376 0.183974 -0.0254474 -0.00892552 0.184974 -0.0270302 -0.0178989 0.183974 -0.0279593 -0.0175292 0.184974 -0.0368343 -0.0332584 0.183974 -0.0320458 -0.0255062 0.184974 -0.043723 -0.0392835 0.184974 -0.112243 0.0268867 0.183974 -0.118489 0.00924442 0.184974 -0.11947 0.00943951 0.183974 -0.105517 0.033514 0.183974 -0.106399 0.032608 0.184974 -0.106224 0.0342211 0.183974 -0.0627528 0.0464864 0.183974 -0.072 0.0473971 0.184974 -0.0814424 0.0474671 0.183974 -0.0851728 0.04553 0.183974 -0.0901392 0.043789 0.184974 -0.0377761 0.0342211 0.184974 -0.0451104 0.0402403 0.184974 -0.0317569 0.0268867 0.183974 -0.0282082 0.0181363 0.184974 -0.02453 0.00943951 0.183974 -0.0255108 0.00924442 0.184964 -0.0892495 0.0300093 0.180824 -0.04705 -0.00450286 0.181907 -0.048125 -0.00405286 0.182296 -0.0496 -0.00450286 0.180824 -0.0475 0.00499714 0.180824 -0.0475 -0.00405286 0.181449 -0.0476675 0.00499714 0.181449 -0.0476675 -0.00405286 0.181907 -0.049375 0.00499714 0.182074 -0.04875 -0.00405286 0.181907 -0.049375 -0.00405286 0.181449 -0.0498326 0.00499714 0.181449 -0.0498326 -0.00405286 0.182074 -0.04875 0.00499714 0.181907 -0.048125 0.00499714 0.180824 -0.09355 -0.00450286 0.181367 -0.0941238 -0.00405286 0.181802 -0.0944707 -0.00405286 0.182043 -0.0949719 -0.00405286 0.182043 -0.0955282 -0.00405286 0.182482 -0.0956283 -0.00450286 0.182153 -0.09631 -0.00450286 0.181802 -0.0960294 -0.00405286 0.181562 -0.0967817 -0.00450286 0.180824 -0.0965 -0.00405286 0.180824 -0.09695 -0.00450286 0.181802 -0.0944707 0.00499714 0.181802 -0.0960294 0.00499714 0.181367 -0.0963763 0.00499714 0.181367 -0.0963763 -0.00405286 0.181367 -0.0941238 0.00499714 0.182043 -0.0955282 0.00499714 0.182043 -0.0949719 0.00499714 0.180824 -0.09525 0.00574822 0.181562 -0.0735317 -0.00450286 0.181802 -0.0727794 -0.00405286 0.182153 -0.07306 -0.00450286 0.182482 -0.0723783 -0.00450286 0.181907 -0.072625 -0.00405286 0.182043 -0.0722782 -0.00405286 0.182074 -0.072 -0.00405286 0.182043 -0.0717219 -0.00405286 0.182482 -0.0716218 -0.00450286 0.181907 -0.071375 -0.00405286 0.181802 -0.0712207 -0.00405286 0.180824 -0.07075 -0.00405286 0.181367 -0.0708738 -0.00405286 0.181449 -0.0709175 -0.00405286 0.181562 -0.0704684 -0.00450286 0.180824 -0.07075 0.00499714 0.180824 -0.07325 0.00499714 0.181367 -0.0731263 -0.00405286 0.181449 -0.0730826 -0.00405286 0.181907 -0.071375 0.00499714 0.182074 -0.072 0.00499714 0.181449 -0.0709175 0.00499714 0.181449 -0.0730826 0.00499714 0.181907 -0.072625 0.00499714 0.180824 -0.072 0.00574822 0.186974 -0.0750789 0.0410819 0.186801 -0.10921 0.0179165 0.186774 -0.0812124 0.0403592 0.186801 -0.041725 0.0280883 0.186774 -0.0346999 0.0179599 0.186801 -0.05135 0.035764 0.186774 -0.0461876 0.032365 0.186774 -0.0513 0.0358506 0.186801 -0.0628099 0.0402617 0.186774 -0.0750939 0.0412814 0.186801 -0.0750864 0.0411817 0.186774 -0.0689062 0.0412814 0.186801 -0.0870886 0.0384422 0.186774 -0.0927 0.0358506 0.186801 -0.102275 0.0280883 0.186874 -0.0326048 0.012149 0.186801 -0.0325349 0.0121705 0.186801 -0.03479 0.0179165 0.186874 -0.034856 0.0178848 0.186974 -0.037959 0.0232059 0.186801 -0.0462499 0.0322868 0.186801 -0.0569115 0.0384422 0.186874 -0.0628262 0.0401903 0.186874 -0.0689192 0.0411087 0.186874 -0.0870619 0.0383741 0.186801 -0.09265 0.035764 0.186801 -0.0977502 0.0322868 0.186874 -0.106063 0.023221 0.186801 -0.106124 0.0232623 0.186801 -0.0307 -2.85742e-06 0.186874 -0.0307732 -2.85742e-06 0.186801 -0.0311613 0.00615259 0.186874 -0.0312337 0.00614168 0.186974 -0.0317004 0.0085631 0.186974 -0.0348801 0.0178732 0.186874 -0.0379369 0.023221 0.186801 -0.0378764 0.0232623 0.186874 -0.0417787 0.0280385 0.186974 -0.0417983 0.0280203 0.186874 -0.0462956 0.0322296 0.186974 -0.0592685 0.0391807 0.186974 -0.056948 0.0383491 0.186874 -0.0569382 0.0383741 0.186874 -0.0513866 0.0357006 0.186974 -0.0514 0.0356774 0.186974 -0.0689212 0.0410819 0.186974 -0.0676935 0.0409714 0.186974 -0.0628322 0.0401642 0.186801 -0.0689137 0.0411817 0.186874 -0.0750809 0.0411087 0.186801 -0.0811902 0.0402617 0.186874 -0.0811739 0.0401903 0.186874 -0.102221 0.0280385 0.186874 -0.0977045 0.0322296 0.186874 -0.0926134 0.0357006 0.186974 -0.0926 0.0356774 0.186974 -0.0870521 0.0383491 0.186974 -0.10912 0.0178732 0.186974 -0.106041 0.0232059 0.186974 -0.102202 0.0280203 0.186874 -0.109144 0.0178848 0.186974 -0.109638 0.0167547 0.186874 -0.111395 0.012149 0.186774 -0.111561 0.0122 0.186801 -0.111465 0.0121705 0.186974 -0.1123 0.0085631 0.186774 -0.112938 0.00616749 0.186801 -0.112839 0.00615259 0.186874 -0.112766 0.00614168 0.186874 -0.113227 -2.85742e-06 0.186974 -0.1132 -2.85742e-06 0.186574 -0.11385 -2.85742e-06 0.186774 -0.11274 -0.00866238 0.186774 -0.110049 -0.0169434 0.186574 -0.105857 -0.0246017 0.186574 -0.100003 -0.0311035 0.186774 -0.0998693 -0.0309548 0.186774 -0.092825 -0.0360728 0.186574 -0.0849324 -0.0398046 0.186774 -0.0848706 -0.0396144 0.186574 -0.0763746 -0.0416236 0.186774 -0.051175 -0.0360728 0.186774 -0.0441308 -0.0309548 0.186574 -0.0439969 -0.0311035 0.186574 -0.0381427 -0.0246017 0.186774 -0.0383045 -0.0244841 0.186774 -0.0339509 -0.0169434 0.186574 -0.0310646 -0.00870396 0.186574 -0.03015 -2.85742e-06 0.184974 -0.0547501 0.0302681 0.184974 -0.0547111 0.0297472 0.184074 -0.116017 -0.013785 0.184074 -0.115803 -0.012985 0.184074 -0.114417 -0.012185 0.183974 -0.114417 -0.012085 0.183974 -0.113567 -0.0123128 0.184074 -0.113032 -0.012985 0.183974 -0.112945 -0.012935 0.185874 -0.116017 -0.013785 0.185874 -0.115803 -0.012985 0.185874 -0.115217 -0.0123994 0.184074 -0.115217 -0.0123994 0.185874 -0.114417 -0.012185 0.185874 -0.113617 -0.0123994 0.184074 -0.113617 -0.0123994 0.185874 -0.113032 -0.012985 0.185974 -0.113567 -0.0123128 0.185974 -0.115889 -0.012935 0.183974 -0.115889 0.0146293 0.184074 -0.115217 0.0151649 0.184074 -0.114417 0.0153793 0.183974 -0.114417 0.0154793 0.184074 -0.112817 0.0137793 0.184074 -0.116017 0.0137793 0.185874 -0.115803 0.0145793 0.184074 -0.115803 0.0145793 0.184074 -0.113617 0.0151649 0.185874 -0.113032 0.0145793 0.184074 -0.113032 0.0145793 0.185874 -0.112817 0.0137793 0.185874 -0.113617 0.0151649 0.185874 -0.114417 0.0153793 0.185974 -0.113567 0.0152515 0.185874 -0.115217 0.0151649 0.185974 -0.115889 0.0146293 0.184074 -0.0990153 0.0374649 0.185874 -0.0996009 0.0368793 0.185874 -0.0990153 0.0374649 0.184074 -0.0996009 0.0368793 0.184074 -0.0982153 0.0376793 0.184074 -0.0974153 0.0374649 0.185874 -0.0968296 0.0368793 0.184074 -0.0968296 0.0368793 0.185974 -0.096743 0.0369293 0.185874 -0.0974153 0.0374649 0.185874 -0.0982153 0.0376793 0.185974 -0.0999153 0.0360793 0.184074 -0.0733857 0.0453971 0.184074 -0.0728 0.0459828 0.183974 -0.0734723 0.0454471 0.183974 -0.07285 0.0460694 0.184074 -0.072 0.0461971 0.184074 -0.0712 0.0459828 0.183974 -0.0705278 0.0454471 0.184074 -0.0704 0.0445971 0.185874 -0.0728 0.0459828 0.185874 -0.072 0.0461971 0.185874 -0.0706144 0.0453971 0.184074 -0.0706144 0.0453971 0.185874 -0.0704 0.0445971 0.185874 -0.0712 0.0459828 0.185874 -0.0733857 0.0453971 0.185974 -0.07285 0.0460694 0.185974 -0.0734723 0.0454471 0.184074 -0.0472264 0.0367735 0.184074 -0.0467824 0.0373302 0.184074 -0.0454288 0.0376392 0.183974 -0.0454065 0.0377367 0.184074 -0.0447872 0.0373302 0.183974 -0.0447249 0.0374084 0.183974 -0.0442532 0.0368169 0.183974 -0.0440848 0.0360793 0.185874 -0.0472264 0.0367735 0.185874 -0.0461409 0.0376392 0.184074 -0.0461409 0.0376392 0.185874 -0.0443433 0.0367735 0.184074 -0.0443433 0.0367735 0.185874 -0.0441848 0.0360793 0.185874 -0.0447872 0.0373302 0.185874 -0.0454288 0.0376392 0.185874 -0.0467824 0.0373302 0.183974 -0.0312829 0.0137793 0.183974 -0.0310552 0.0146293 0.183974 -0.0295829 0.0154793 0.183974 -0.0287329 0.0152515 0.183974 -0.0281107 0.0146293 0.184074 -0.0311829 0.0137793 0.184074 -0.0309686 0.0145793 0.184074 -0.0303829 0.0151649 0.185874 -0.0295829 0.0153793 0.184074 -0.0295829 0.0153793 0.184074 -0.0287829 0.0151649 0.184074 -0.0281973 0.0145793 0.185874 -0.0281973 0.0145793 0.185974 -0.0281107 0.0146293 0.185874 -0.0287829 0.0151649 0.185874 -0.0303829 0.0151649 0.185874 -0.0309686 0.0145793 0.185874 -0.0311829 0.0137793 0.184074 -0.0309686 -0.012985 0.183974 -0.0310552 -0.012935 0.183974 -0.0304329 -0.0123128 0.184074 -0.0295829 -0.012185 0.183974 -0.0295829 -0.012085 0.184074 -0.0279829 -0.013785 0.183974 -0.0278829 -0.013785 0.185874 -0.0303829 -0.0123994 0.184074 -0.0303829 -0.0123994 0.185874 -0.0295829 -0.012185 0.184074 -0.0287829 -0.0123994 0.185874 -0.0279829 -0.013785 0.184074 -0.0281973 -0.012985 0.185874 -0.0281973 -0.012985 0.185974 -0.0281107 -0.012935 0.185874 -0.0287829 -0.0123994 0.185974 -0.0295829 -0.012085 0.185874 -0.0309686 -0.012985 0.183974 -0.0474848 -0.036085 0.184074 -0.0471705 -0.035285 0.183974 -0.0472571 -0.035235 0.184074 -0.0465848 -0.0346994 0.183974 -0.0466348 -0.0346128 0.184074 -0.0457848 -0.034485 0.183974 -0.0457848 -0.034385 0.184074 -0.0449848 -0.0346994 0.184074 -0.0443992 -0.035285 0.185874 -0.0465848 -0.0346994 0.185874 -0.0449848 -0.0346994 0.185874 -0.0443992 -0.035285 0.185874 -0.0457848 -0.034485 0.185974 -0.0457848 -0.034385 0.185874 -0.0471705 -0.035285 0.185974 -0.0474848 -0.036085 0.183974 -0.0734723 -0.0437529 0.183974 -0.07285 -0.0431306 0.183974 -0.072 -0.0429029 0.184074 -0.072 -0.0430029 0.184074 -0.0712 -0.0432172 0.183974 -0.0705278 -0.0437529 0.183974 -0.0703 -0.0446029 0.184074 -0.0733857 -0.0438029 0.185874 -0.0728 -0.0432172 0.184074 -0.0728 -0.0432172 0.184074 -0.0706144 -0.0438029 0.185874 -0.0706144 -0.0438029 0.185974 -0.0705278 -0.0437529 0.185874 -0.0712 -0.0432172 0.185874 -0.072 -0.0430029 0.185974 -0.07115 -0.0431306 0.185874 -0.0733857 -0.0438029 0.183974 -0.0999153 -0.036085 0.184074 -0.0990153 -0.0346994 0.184074 -0.0982153 -0.034485 0.183974 -0.0973653 -0.0346128 0.184074 -0.0966153 -0.036085 0.185874 -0.0998153 -0.036085 0.185874 -0.0996009 -0.035285 0.184074 -0.0996009 -0.035285 0.184074 -0.0974153 -0.0346994 0.185874 -0.0968296 -0.035285 0.184074 -0.0968296 -0.035285 0.185874 -0.0974153 -0.0346994 0.185874 -0.0982153 -0.034485 0.185874 -0.0990153 -0.0346994 0.185974 -0.0996875 -0.035235 0.186574 -0.0590677 -0.0398046 0.185774 -0.0520439 -0.0367884 0.186274 -0.0520439 -0.0367884 0.185774 -0.0675 -0.0416102 0.186274 -0.0675 -0.0416102 0.186574 -0.0676255 -0.0416236 0.186274 -0.0765 -0.0416102 0.186274 -0.0844635 -0.0399539 0.186274 -0.0849324 -0.0398046 0.185974 -0.0763 -0.0416314 0.185974 -0.092925 -0.036246 0.185974 -0.0921321 -0.0366924 0.185874 -0.0920442 -0.0367405 0.185774 -0.0919562 -0.0367884 0.186274 -0.0919562 -0.0367884 0.186574 -0.092925 -0.036246 0.185974 -0.100003 -0.0311035 0.186574 -0.110232 -0.0170248 0.186574 -0.112936 -0.00870396 0.185974 -0.112936 -0.00870396 0.185974 -0.11385 -2.85742e-06 0.185974 -0.051075 -0.036246 0.186574 -0.051075 -0.036246 0.185974 -0.0439969 -0.0311035 0.185974 -0.0381427 -0.0246017 0.186574 -0.0337682 -0.0170248 0.184974 -0.110497 -0.01158 0.186574 -0.109674 -0.0140287 0.184974 -0.109674 -0.0140287 0.184974 -0.107231 -0.0193625 0.186574 -0.106591 -0.0204845 0.186574 -0.102413 -0.0262917 0.184974 -0.0312029 -0.0260442 0.184974 -0.1204 -2.85742e-06 0.184974 -0.116716 0.018519 0.185774 -0.106224 0.0342211 0.184974 -0.0988896 0.0402403 0.185774 -0.0905219 0.0447129 0.184974 -0.0905219 0.0447129 0.185774 -0.0814424 0.0474671 0.185774 -0.072 0.0483971 0.184974 -0.072 0.0483971 0.184974 -0.0625577 0.0474671 0.184974 -0.0534782 0.0447129 0.185774 -0.0377761 0.0342211 0.185774 -0.0317569 0.0268867 0.185774 -0.0272843 0.018519 0.184974 -0.0272843 0.018519 0.185774 -0.02453 0.00943951 0.185774 -0.0236 -2.85742e-06 0.186974 -0.0308 -2.85742e-06 0.186974 -0.0326304 -0.0121468 0.186974 -0.0317004 -0.00856882 0.186974 -0.0312602 -0.0061434 0.187574 -0.0386685 -0.0242196 0.186974 -0.0417983 -0.028026 0.186974 -0.0463123 -0.0322143 0.186974 -0.056948 -0.0383549 0.187574 -0.0514 -0.0356831 0.186974 -0.0592685 -0.0391864 0.187574 -0.0592685 -0.0391864 0.186974 -0.0750789 -0.0410877 0.187574 -0.0847315 -0.0391864 0.187574 -0.0763066 -0.0409772 0.186974 -0.0847315 -0.0391864 0.186974 -0.0811679 -0.0401699 0.186974 -0.105332 -0.0242196 0.186974 -0.0976878 -0.0322143 0.186974 -0.106041 -0.0232116 0.186974 -0.10912 -0.0178789 0.186974 -0.11137 -0.0121468 0.187574 -0.109638 -0.0167604 0.187574 -0.1123 -0.00856882 0.186974 -0.11274 -0.0061434 0.185974 -0.0508 -0.0367223 0.185974 -0.0436289 -0.0315122 0.185974 -0.0376977 -0.024925 0.185974 -0.0337682 -0.0170248 0.185974 -0.0332657 -0.0172485 0.185974 -0.0310646 -0.00870396 0.185974 -0.03015 -2.85742e-06 0.185974 -0.0332657 0.0172428 0.185974 -0.0337682 0.0170191 0.185974 -0.051075 0.0362403 0.185974 -0.0588977 0.0403219 0.185974 -0.067568 0.0421649 0.185974 -0.0849324 0.0397989 0.185974 -0.100003 0.0310978 0.185974 -0.106302 0.0249192 0.185974 -0.105857 0.024596 0.185974 -0.110232 0.0170191 0.185974 -0.112936 0.00869825 0.185974 -0.110232 -0.0170248 0.185974 -0.105857 -0.0246017 0.185974 -0.106302 -0.024925 0.187574 -0.1132 -2.85742e-06 0.186974 -0.11274 0.00613768 0.186974 -0.11137 0.0121411 0.187574 -0.109638 0.0167547 0.186974 -0.105332 0.0242139 0.186974 -0.0976878 0.0322086 0.187574 -0.0995682 0.0306147 0.186974 -0.0995682 0.0306147 0.187574 -0.0926 0.0356774 0.186974 -0.0763066 0.0409714 0.186974 -0.0811679 0.0401642 0.186974 -0.0847315 0.0391807 0.187574 -0.0676935 0.0409714 0.187574 -0.0592685 0.0391807 0.186974 -0.0463123 0.0322086 0.186974 -0.0444319 0.0306147 0.187574 -0.0444319 0.0306147 0.187574 -0.0386685 0.0242139 0.186974 -0.0386685 0.0242139 0.186974 -0.034362 0.0167547 0.186974 -0.0326304 0.0121411 0.187574 -0.034362 0.0167547 0.187574 -0.0317004 0.0085631 0.186974 -0.0312602 0.00613768 0.187574 -0.0308 -2.85742e-06 0.183974 -0.115889 -0.012935 0.183974 -0.0851077 0.0403382 0.183974 -0.0376839 -0.024935 0.183974 -0.0392653 -0.0250204 0.183974 -0.0443126 -0.035235 0.183974 -0.0510981 -0.0300029 0.183974 -0.0515 -0.0351982 0.183974 -0.0473165 -0.0368226 0.183974 -0.0478858 -0.039028 0.183974 -0.0449348 -0.0346128 0.183974 -0.0494726 -0.038054 0.183974 -0.0509143 -0.0366124 0.183974 -0.0513478 -0.0359636 0.183974 -0.04603 -0.0391782 0.183974 -0.0454065 -0.0377424 0.183974 -0.0447249 -0.0374141 0.183974 -0.0442532 -0.0368226 0.183974 -0.0375609 -0.0325713 0.183974 -0.0281107 -0.014635 0.183974 -0.0287329 -0.0123128 0.183974 -0.0281107 -0.012935 0.183974 -0.0314525 -0.00730585 0.183974 -0.0333891 -0.0143776 0.183974 -0.0312829 -0.013785 0.183974 -0.0304329 -0.0152573 0.183974 -0.0287329 0.0123071 0.183974 -0.0310552 0.0129293 0.183974 -0.0304329 0.0123071 0.183974 -0.0308 -2.85742e-06 0.183974 -0.0262415 -2.85742e-06 0.183974 -0.0246 -2.85742e-06 0.183974 -0.0304329 0.0152515 0.183974 -0.0466348 0.0346071 0.183974 -0.0425921 0.0288522 0.183974 -0.0376839 0.0249293 0.183974 -0.0449348 0.0346071 0.183974 -0.0317248 0.0249904 0.183974 -0.0325884 0.0263312 0.183974 -0.0443126 0.0352293 0.183974 -0.0527214 0.0345207 0.183974 -0.0538608 0.043789 0.183974 -0.0473328 0.0404729 0.183974 -0.0384832 0.033514 0.183974 -0.045666 0.0394088 0.183974 -0.0461631 0.0377367 0.183974 -0.0468448 0.0374084 0.183974 -0.0487058 0.0339798 0.183974 -0.0473165 0.0368169 0.183974 -0.0567948 0.0370743 0.183974 -0.0588924 0.0403382 0.183974 -0.0580142 0.0377925 0.183974 -0.07115 0.0431249 0.183974 -0.072 0.0428971 0.183974 -0.07115 0.0460694 0.183974 -0.072 0.0462971 0.183974 -0.0812473 0.0464864 0.183974 -0.0737 0.0445971 0.183974 -0.0734723 0.0437471 0.183974 -0.07285 0.0431249 0.183974 -0.106316 0.0249293 0.183974 -0.0990653 0.0375515 0.183974 -0.0996875 0.0369293 0.183974 -0.0999153 0.0360793 0.183974 -0.0859859 0.0377925 0.183974 -0.0982153 0.0377793 0.183974 -0.0983341 0.0394088 0.183974 -0.0973653 0.0375515 0.183974 -0.096743 0.0369293 0.183974 -0.0934961 0.0347058 0.183974 -0.0915594 0.0346077 0.183974 -0.0880983 0.0359764 0.183974 -0.112945 0.0146293 0.183974 -0.115267 0.0152515 0.183974 -0.111412 0.0263312 0.183974 -0.113567 0.0152515 0.183974 -0.115792 0.0181363 0.183974 -0.115889 0.0129293 0.183974 -0.1194 -2.85742e-06 0.183974 -0.113567 0.0123071 0.183974 -0.112945 0.0129293 0.183974 -0.116117 -0.013785 0.183974 -0.115267 -0.0152573 0.183974 -0.116041 -0.0175292 0.183974 -0.106489 -0.0225406 0.183974 -0.108108 -0.0198441 0.183974 -0.115267 -0.0123128 0.183974 -0.1132 2.20321e-06 0.183974 -0.114417 -0.015485 0.183974 -0.106316 -0.024935 0.183974 -0.112945 -0.014635 0.183974 -0.112717 -0.013785 0.183974 -0.113062 -0.00336884 0.183974 -0.0996875 -0.035235 0.183974 -0.106439 -0.0325713 0.183974 -0.111954 -0.0255062 0.183974 -0.094 -0.0289048 0.183974 -0.104719 -0.0250406 0.183974 -0.0990653 -0.0346128 0.183974 -0.0982153 -0.034385 0.183974 -0.101637 -0.0280951 0.183974 -0.099765 -0.0285029 0.183974 -0.096743 -0.035235 0.183974 -0.0925 -0.0315029 0.183974 -0.0965153 -0.036085 0.183974 -0.0979701 -0.0391782 0.183974 -0.0930858 -0.0366124 0.183974 -0.0648959 0.039666 0.183974 -0.0791042 0.039666 0.187574 -0.0507963 -0.0265782 0.187574 -0.0520966 0.0258218 0.187574 -0.0995682 -0.0306204 0.187574 -0.0510711 -0.026853 0.187574 -0.0676935 -0.0409772 0.187574 -0.0926 -0.0356831 0.187574 -0.0921783 -0.026853 0.187574 -0.0919035 -0.0265782 0.187574 -0.0921783 0.0268473 0.187574 -0.0518218 0.025547 0.187574 -0.0514465 0.0254464 0.187574 -0.0918029 -0.0262029 0.187574 -0.0921783 -0.0255527 0.187574 -0.0518218 -0.026853 0.187574 -0.0518218 0.0268473 0.187574 -0.0514465 0.0269479 0.187574 -0.0514 0.0356774 0.187574 -0.092929 0.025547 0.187574 -0.105332 0.0242139 0.187574 -0.105332 -0.0242196 0.187574 -0.0932038 -0.0258275 0.187574 -0.0521972 -0.0262029 0.187574 -0.0444319 -0.0306204 0.187574 -0.0506957 -0.0262029 0.187574 -0.0510711 -0.0255527 0.187574 -0.034362 -0.0167604 0.187574 -0.0317004 -0.00856882 0.187574 -0.0925536 -0.0254521 0.187574 -0.0925536 0.0254464 0.187574 -0.092929 -0.0255527 0.187574 -0.1123 0.0085631 0.187574 -0.0933043 0.0261971 0.187574 -0.0932038 0.0265725 0.187574 -0.092929 0.0268473 0.187574 -0.0847315 0.0391807 0.187574 -0.0521972 0.0261971 0.187574 -0.0763066 0.0409714 0.187574 -0.0506957 0.0261971 0.187574 -0.0510711 0.025547 0.184974 -0.100277 -0.0392835 0.185774 -0.100277 -0.0392835 0.184974 -0.107166 -0.0332584 0.185774 -0.112797 -0.0260442 0.184974 -0.112797 -0.0260442 0.185774 -0.119535 -0.00911376 0.184974 -0.0324366 -0.0071286 0.184974 -0.0318 -2.85742e-06 0.184974 -0.0319344 -0.00328714 0.184974 -0.0377121 0.0209823 0.184974 -0.0347875 0.0152046 0.186574 -0.0340863 0.0133609 0.184974 -0.032554 0.00774622 0.184974 -0.0321317 0.00515045 0.184974 -0.0384169 0.0220926 0.186574 -0.0428492 0.0276787 0.184974 -0.0433059 0.0281518 0.186574 -0.0492712 0.033155 0.184974 -0.0492712 0.033155 0.184974 -0.0947289 0.033155 0.186574 -0.105583 0.0220926 0.186574 -0.109213 0.0152046 0.184974 -0.109213 0.0152046 0.184974 -0.105583 0.0220926 0.186574 -0.111446 0.00774622 0.184974 -0.109914 0.0133609 0.183974 -0.0755 -0.0335029 0.183974 -0.0735661 -0.047377 0.183974 -0.070434 -0.047377 0.183974 -0.0694621 -0.0470877 0.183974 -0.0687571 -0.0463589 0.183974 -0.0685 -0.0453781 0.183974 -0.075 -0.0326368 0.183974 -0.0745 -0.0325029 0.183974 -0.068634 -0.0330029 0.183974 -0.0685 -0.0335029 0.183974 -0.069 -0.0326368 0.183974 -0.07115 -0.0431306 0.186574 -0.0377121 0.0209823 0.186574 -0.0471539 0.0218637 0.186574 -0.074175 -0.00450286 0.186574 -0.0485 -0.0275029 0.186574 -0.0442351 -0.0275029 0.186574 -0.045725 0.0187995 0.186574 -0.0460998 0.02049 0.186574 -0.0367687 -0.0193625 0.186574 -0.0335032 -0.01158 0.186574 -0.046225 -0.00436888 0.186574 -0.045725 -0.00350286 0.186574 -0.0319344 -0.00328714 0.186574 -0.0321317 0.00515045 0.186574 -0.111563 -0.0071286 0.186574 -0.1122 -2.85742e-06 0.186574 -0.0519641 -0.0295029 0.186574 -0.0675054 -0.0333566 0.186574 -0.0680858 -0.0320886 0.186574 -0.0687347 -0.0316551 0.186574 -0.097775 -0.00436888 0.186574 -0.0745 -0.0315029 0.186574 -0.0981411 -0.00400286 0.186574 -0.0755 -0.0317708 0.186574 -0.100694 0.0281518 0.186574 -0.089289 0.0297472 0.186574 -0.0902574 0.0250471 0.186574 -0.0923609 0.0234535 0.186574 -0.0979003 0.02049 0.186574 -0.0762321 -0.0325029 0.186574 -0.0764947 -0.0333566 0.186574 -0.0916251 -0.0305107 0.186574 -0.0539197 -0.0325135 0.186574 -0.091624 0.033582 0.186574 -0.0790398 -0.0362567 0.186574 -0.0649603 -0.0362567 0.186574 -0.0635906 -0.0362399 0.184974 -0.0704009 -0.0483764 0.186574 -0.112936 0.00869825 0.186574 -0.110232 0.0170191 0.186574 -0.092925 0.0362403 0.185974 -0.092925 0.0362403 0.186574 -0.0763746 0.0416179 0.185974 -0.0763746 0.0416179 0.185974 -0.0676255 0.0416179 0.186574 -0.0676255 0.0416179 0.185974 -0.0590677 0.0397989 0.186574 -0.0439969 0.0310978 0.185974 -0.0439969 0.0310978 0.185974 -0.0381427 0.024596 0.186574 -0.0337682 0.0170191 0.185974 -0.0310646 0.00869825 0.186574 -0.0310646 0.00869825 0.186774 -0.0871252 0.0385353 0.186774 -0.0848706 0.0396086 0.186774 -0.0339509 0.0169377 0.186774 -0.0312602 0.00865666 0.186774 -0.0763537 0.041419 0.186774 -0.0627877 0.0403592 0.186774 -0.0568749 0.0385353 0.186774 -0.0310624 0.00616749 0.186774 -0.0306 -2.85742e-06 0.186774 -0.0310624 -0.00617321 0.186774 -0.0312602 -0.00866238 0.186774 -0.0346999 -0.0179656 0.186774 -0.0377938 -0.0233243 0.186774 -0.0416517 -0.028162 0.186774 -0.0461876 -0.0323707 0.186774 -0.0513 -0.0358563 0.186774 -0.0591295 -0.0396144 0.186774 -0.0676464 -0.0414247 0.186774 -0.0416517 0.0281563 0.186774 -0.0377938 0.0233186 0.186774 -0.0324393 0.0122 0.186774 -0.0627877 -0.0403649 0.186774 -0.0763537 -0.0414247 0.186774 -0.0812124 -0.0403649 0.186774 -0.0927 -0.0358563 0.186774 -0.0978125 -0.0323707 0.186774 -0.102348 -0.028162 0.186774 -0.102348 0.0281563 0.186774 -0.0978125 0.032365 0.186774 -0.105696 -0.0244841 0.186774 -0.110049 0.0169377 0.186774 -0.1093 0.0179599 0.186774 -0.105696 0.0244784 0.186774 -0.106206 0.0233186 0.183974 -0.072 0.0402971 0.175524 -0.045725 -0.00350286 0.186574 -0.046725 -0.00450286 0.182524 -0.04875 -0.00450286 0.179352 -0.07285 -0.00450286 0.182296 -0.0479 -0.00450286 0.181674 -0.0472778 -0.00450286 0.179974 -0.0472778 -0.00450286 0.180824 -0.0737 -0.00450286 0.177436 -0.0679881 -0.00450286 0.179974 -0.0705278 -0.00450286 0.179352 -0.0479 -0.00450286 0.181674 -0.0502223 -0.00450286 0.183249 -0.051273 -0.00450286 0.180824 -0.05045 -0.00450286 0.182153 -0.0709401 -0.00450286 0.184212 -0.0679881 -0.00450286 0.179352 -0.07115 -0.00450286 0.176428 -0.0664795 -0.00450286 0.176074 -0.0647 -0.00450286 0.175524 -0.046725 -0.00450286 0.178399 -0.051273 -0.00450286 0.179974 -0.0502223 -0.00450286 0.179352 -0.0496 -0.00450286 0.176697 -0.052975 -0.00450286 0.176074 -0.0553 -0.00450286 0.18522 -0.0664795 -0.00450286 0.182482 -0.0948718 -0.00450286 0.184212 -0.0919881 -0.00450286 0.184049 -0.074175 -0.00450286 0.180724 -0.07465 -0.00450286 0.179124 -0.09525 -0.00450286 0.177436 -0.0919881 -0.00450286 0.179974 -0.0937778 -0.00450286 0.178945 -0.0929961 -0.00450286 0.181562 -0.0937184 -0.00450286 0.182153 -0.0941901 -0.00450286 0.176074 -0.0887 -0.00450286 0.175524 -0.074175 -0.00450286 0.179352 -0.0961 -0.00450286 0.179974 -0.0967223 -0.00450286 0.180724 -0.09335 -0.00450286 0.180924 -0.09335 -0.00450286 0.186574 -0.097275 -0.00450286 0.18522 -0.0904795 -0.00450286 0.185574 -0.0793 -0.00450286 0.184951 -0.076975 -0.00450286 0.175524 -0.098275 0.0187995 0.186574 -0.098275 0.0187995 0.175524 -0.0923609 0.0234535 0.184974 -0.089289 0.0297472 0.184964 -0.0892495 0.0300093 0.184935 -0.0892106 0.0302681 0.175524 -0.0898057 0.0263134 0.183974 -0.0554469 0.0346363 0.175524 -0.0541944 0.0263134 0.186574 -0.0547111 0.0297472 0.186574 -0.0541944 0.0263134 0.184581 -0.0549647 0.0314322 0.183974 -0.055132 0.0325442 0.186574 -0.0516392 0.0234535 0.175524 -0.0486898 0.0226632 0.175024 -0.046475 -0.00393587 0.175024 -0.046292 -0.00375286 0.175024 -0.046725 -0.00400286 0.175024 -0.0898275 0.0247918 0.175024 -0.0531488 0.0236459 0.175024 -0.0965248 0.0214807 0.175024 -0.097275 -0.00400286 0.175024 -0.097775 -0.00350286 0.175024 -0.097775 0.0187995 0.175024 -0.0922315 0.0229706 0.175024 -0.0951809 0.0221803 0.175024 -0.046225 -0.00350286 0.175024 -0.0517686 0.0229706 0.175024 -0.0488192 0.0221803 0.175024 -0.0559413 0.0345619 0.175024 -0.0581877 0.0373235 0.175024 -0.064984 0.0391739 0.175024 -0.072 0.0397971 0.175024 -0.0546888 0.026239 0.175024 -0.0893113 0.026239 0.175024 -0.0880587 0.0345619 0.186074 -0.0915 -0.0315029 0.184974 -0.0955 -0.0275029 0.186574 -0.0955 -0.0275029 0.184974 -0.0675 -0.0335029 0.186074 -0.0675 -0.0343097 0.185774 -0.0765 -0.0416102 0.185774 -0.0765 -0.0453781 0.186074 -0.0765 -0.0343097 0.185774 -0.0516214 -0.0373195 0.186074 -0.0675 -0.041409 0.186074 -0.0673029 -0.0347433 0.186074 -0.0595961 -0.039763 0.186074 -0.0585528 -0.0349017 0.186074 -0.0635453 -0.0364347 0.186074 -0.0524974 -0.0313582 0.186074 -0.0525 -0.0351982 0.186074 -0.0527777 -0.0317867 0.186074 -0.0521443 -0.0366153 0.185774 -0.0938203 -0.0387611 0.185774 -0.0923787 -0.0373195 0.186074 -0.0766972 -0.0347433 0.186074 -0.0765 -0.041409 0.186074 -0.0917284 -0.0363463 0.186074 -0.0915 -0.0351982 0.186074 -0.0844039 -0.039763 0.185774 -0.0458765 -0.0401663 0.185774 -0.0481962 -0.0399786 0.184974 -0.0481962 -0.0399786 0.185774 -0.0501798 -0.0387611 0.184974 -0.0938203 -0.0387611 0.184974 -0.0958038 -0.0399786 0.185774 -0.0981236 -0.0401663 0.185774 -0.0750569 -0.0479425 0.185774 -0.0761145 -0.0468494 0.184974 -0.0675 -0.0453781 0.185774 -0.0678856 -0.0468494 0.184974 -0.0678856 -0.0468494 0.186274 -0.0764947 -0.0333566 0.184974 -0.0762321 -0.0325029 0.186266 -0.0765 -0.0335029 0.186272 -0.0675014 -0.0334298 0.184974 -0.0680858 -0.0320886 0.186574 -0.0676523 -0.0327375 0.184974 -0.0685 -0.0317708 0.184974 -0.0695 -0.0315029 0.186574 -0.0695 -0.0315029 0.186274 -0.0853753 -0.0347151 0.186274 -0.0804095 -0.0362399 0.186574 -0.0853753 -0.0347151 0.186574 -0.0586247 -0.0347151 0.186274 -0.0586247 -0.0347151 0.186574 -0.0898057 0.0263134 0.175524 -0.0902574 0.0250471 0.186574 -0.0911532 0.0240445 0.186574 -0.0528469 0.0240445 0.175524 -0.0528469 0.0240445 0.186574 -0.0537426 0.0250471 0.186574 -0.0968462 0.0218637 0.175524 -0.0968462 0.0218637 0.186574 -0.0953103 0.0226632 0.175524 -0.0953103 0.0226632 0.186574 -0.0486898 0.0226632 0.175524 -0.0460998 0.02049 0.175524 -0.0580142 0.0377925 0.183974 -0.0559018 0.0359764 0.175524 -0.0554469 0.0346363 0.183974 -0.0885532 0.0346363 0.175524 -0.0880983 0.0359764 0.183974 -0.0872053 0.0370743 0.175524 -0.0872053 0.0370743 0.175524 -0.0859859 0.0377925 0.186574 -0.098275 -0.00350286 0.186574 -0.045859 -0.00400286 0.175524 -0.046225 -0.00436888 0.184974 -0.0525 -0.0351982 0.186074 -0.0522717 -0.0363463 0.186074 -0.0918558 -0.0366153 0.186274 -0.052375 -0.0305107 0.186074 -0.0525 -0.0315029 0.184974 -0.0519641 -0.0295029 0.186574 -0.0505 -0.0280388 0.186074 -0.0915027 -0.0313582 0.186574 -0.0918045 -0.0299721 0.184974 -0.0926716 -0.0286744 0.186574 -0.0926716 -0.0286744 0.184974 -0.0935 -0.0280388 0.186574 -0.0939693 -0.0278073 0.186574 -0.0529411 -0.0316712 0.186274 -0.0539197 -0.0325135 0.186574 -0.052375 -0.0305107 0.186574 -0.091059 -0.0316712 0.186274 -0.0910637 -0.031665 0.186574 -0.0900804 -0.0325135 0.186574 -0.0804095 -0.0362399 0.186574 -0.0777885 -0.0356993 0.186574 -0.0768849 -0.0346697 0.186274 -0.076873 -0.0346479 0.186574 -0.0671152 -0.0346697 0.186274 -0.0675054 -0.0333566 0.186574 -0.0662116 -0.0356993 0.186274 -0.0662249 -0.0356895 0.186274 -0.0649684 -0.0362551 0.180724 -0.09275 -0.00285437 0.17786 -0.0915638 0.00669714 0.176983 -0.0902499 -0.00285437 0.176674 -0.0887 -0.00285437 0.180924 -0.09275 -0.00285437 0.184666 -0.0902499 0.00669714 0.183788 -0.0915638 0.00669714 0.183788 -0.0915638 -0.00285437 0.182474 -0.0924418 0.00669714 0.184974 -0.0793 -0.00285437 0.180924 -0.07525 0.00669714 0.184432 -0.077275 0.00669714 0.176674 -0.0793 -0.00285437 0.178699 -0.0757926 0.00669714 0.180724 -0.07525 0.00669714 0.178699 -0.0757926 -0.00285437 0.176674 -0.0887 0.00669714 0.176674 -0.0793 0.00669714 0.180724 -0.06875 -0.00285437 0.179174 -0.0684418 0.00669714 0.176983 -0.0662499 0.00669714 0.176674 -0.0647 0.00669714 0.184666 -0.0662499 0.00669714 0.184974 -0.0647 -0.00285437 0.184666 -0.0662499 -0.00285437 0.183788 -0.0675638 0.00669714 0.183788 -0.0675638 -0.00285437 0.182474 -0.0684418 0.00669714 0.182474 -0.0684418 -0.00285437 0.184974 -0.0647 0.00669714 0.182949 -0.0517926 0.00669714 0.184432 -0.053275 -0.00285437 0.184974 -0.0553 0.00669714 0.184974 -0.0553 -0.00285437 0.180724 -0.05125 -0.00285437 0.180924 -0.05125 0.00669714 0.177217 -0.053275 0.00669714 0.177217 -0.053275 -0.00285437 0.180724 -0.05125 0.00669714 0.176674 -0.0647 -0.00285437 0.175524 -0.098275 -0.00350286 0.175524 -0.0979003 0.02049 0.175024 -0.0974471 0.0202787 0.175524 -0.097275 -0.00450286 0.175524 -0.097775 -0.00436888 0.175024 -0.097525 -0.00393587 0.175524 -0.0981411 -0.00400286 0.175024 -0.0977081 -0.00375286 0.175024 -0.0908513 0.0236459 0.175524 -0.0911532 0.0240445 0.175524 -0.045859 -0.00400286 0.175524 -0.045725 0.0187995 0.175524 -0.0885532 0.0346363 0.175024 -0.0876608 0.0357345 0.175024 -0.0868794 0.0366951 0.175024 -0.0858124 0.0373235 0.175524 -0.0471539 0.0218637 0.175024 -0.0474753 0.0214807 0.175024 -0.046553 0.0202787 0.175024 -0.046225 0.0187995 0.175524 -0.0791042 0.039666 0.175024 -0.0790161 0.0391739 0.175524 -0.072 0.0402971 0.175524 -0.0648959 0.039666 0.175524 -0.0516392 0.0234535 0.175024 -0.0571207 0.0366951 0.175524 -0.0567948 0.0370743 0.175524 -0.0559018 0.0359764 0.175024 -0.0563393 0.0357345 0.175524 -0.0537426 0.0250471 0.175024 -0.0541725 0.0247918 0.185974 -0.0999153 -0.036085 0.185974 -0.0997469 -0.0368226 0.185974 -0.0992752 -0.0374141 0.185874 -0.0985713 -0.0376449 0.185974 -0.0985935 -0.0377424 0.185874 -0.0978592 -0.0376449 0.185974 -0.097837 -0.0377424 0.185874 -0.0972177 -0.0373359 0.185874 -0.0966153 -0.036085 0.185974 -0.0965153 -0.036085 0.185874 -0.0967737 -0.0367792 0.184074 -0.0967737 -0.0367792 0.184074 -0.0972177 -0.0373359 0.184074 -0.0978592 -0.0376449 0.185874 -0.0992128 -0.0373359 0.184074 -0.0992128 -0.0373359 0.185874 -0.0996568 -0.0367792 0.183974 -0.0966836 -0.0368226 0.183974 -0.0971553 -0.0374141 0.184074 -0.0985713 -0.0376449 0.183974 -0.097837 -0.0377424 0.183974 -0.0985935 -0.0377424 0.183974 -0.0992752 -0.0374141 0.184074 -0.0996568 -0.0367792 0.184074 -0.0998153 -0.036085 0.183974 -0.0997469 -0.0368226 0.185874 -0.0736 -0.0446029 0.185974 -0.072 -0.0463029 0.185874 -0.0712 -0.0459885 0.185874 -0.0706144 -0.0454029 0.185974 -0.0705278 -0.0454529 0.185874 -0.0704 -0.0446029 0.184074 -0.0704 -0.0446029 0.184074 -0.0706144 -0.0454029 0.185874 -0.072 -0.0462029 0.185874 -0.0728 -0.0459885 0.184074 -0.0728 -0.0459885 0.185874 -0.0733857 -0.0454029 0.183974 -0.0705278 -0.0454529 0.184074 -0.0712 -0.0459885 0.183974 -0.07115 -0.0460751 0.183974 -0.072 -0.0463029 0.184074 -0.072 -0.0462029 0.183974 -0.07285 -0.0460751 0.184074 -0.0733857 -0.0454029 0.183974 -0.0734723 -0.0454529 0.184074 -0.0736 -0.0446029 0.183974 -0.0737 -0.0446029 0.185874 -0.0472264 -0.0367792 0.185874 -0.0467824 -0.0373359 0.185974 -0.0473165 -0.0368226 0.185974 -0.0468448 -0.0374141 0.185974 -0.0442532 -0.0368226 0.185874 -0.0441848 -0.036085 0.185874 -0.0443433 -0.0367792 0.184074 -0.0443433 -0.0367792 0.185874 -0.0447872 -0.0373359 0.184074 -0.0447872 -0.0373359 0.185874 -0.0454288 -0.0376449 0.184074 -0.0461409 -0.0376449 0.185874 -0.0461409 -0.0376449 0.184074 -0.0472264 -0.0367792 0.185874 -0.0473848 -0.036085 0.184074 -0.0441848 -0.036085 0.183974 -0.0440848 -0.036085 0.184074 -0.0454288 -0.0376449 0.183974 -0.0461631 -0.0377424 0.184074 -0.0467824 -0.0373359 0.183974 -0.0468448 -0.0374141 0.184074 -0.0473848 -0.036085 0.185974 -0.0312829 -0.013785 0.185974 -0.0295829 -0.015485 0.185974 -0.0278829 -0.013785 0.185874 -0.0281973 -0.014585 0.184074 -0.0281973 -0.014585 0.185874 -0.0287829 -0.0151707 0.185874 -0.0295829 -0.015385 0.185874 -0.0303829 -0.0151707 0.184074 -0.0303829 -0.0151707 0.185874 -0.0309686 -0.014585 0.185874 -0.0311829 -0.013785 0.184074 -0.0287829 -0.0151707 0.183974 -0.0287329 -0.0152573 0.184074 -0.0295829 -0.015385 0.183974 -0.0295829 -0.015485 0.184074 -0.0309686 -0.014585 0.183974 -0.0310552 -0.014635 0.184074 -0.0311829 -0.013785 0.185874 -0.0309686 0.0129793 0.185974 -0.0310552 0.0129293 0.185874 -0.0303829 0.0123937 0.185974 -0.0295829 0.0120793 0.185874 -0.0287829 0.0123937 0.185974 -0.0287329 0.0123071 0.185874 -0.0279829 0.0137793 0.185974 -0.0281107 0.0129293 0.185974 -0.0278829 0.0137793 0.185874 -0.0281973 0.0129793 0.184074 -0.0287829 0.0123937 0.185874 -0.0295829 0.0121793 0.184074 -0.0303829 0.0123937 0.184074 -0.0309686 0.0129793 0.184074 -0.0279829 0.0137793 0.183974 -0.0278829 0.0137793 0.183974 -0.0281107 0.0129293 0.184074 -0.0281973 0.0129793 0.184074 -0.0295829 0.0121793 0.183974 -0.0295829 0.0120793 0.185874 -0.0473848 0.0360793 0.185974 -0.0472571 0.0352293 0.185874 -0.0471705 0.0352793 0.185874 -0.0465848 0.0346937 0.185974 -0.0466348 0.0346071 0.185874 -0.0449848 0.0346937 0.185874 -0.0443992 0.0352793 0.184074 -0.0443992 0.0352793 0.185874 -0.0457848 0.0344793 0.184074 -0.0441848 0.0360793 0.184074 -0.0449848 0.0346937 0.184074 -0.0457848 0.0344793 0.183974 -0.0457848 0.0343793 0.184074 -0.0465848 0.0346937 0.184074 -0.0471705 0.0352793 0.184074 -0.0473848 0.0360793 0.183974 -0.0472571 0.0352293 0.183974 -0.0474848 0.0360793 0.185874 -0.0736 0.0445971 0.185874 -0.0728 0.0432115 0.185974 -0.0734723 0.0437471 0.185974 -0.07285 0.0431249 0.185974 -0.072 0.0428971 0.185974 -0.0703 0.0445971 0.185874 -0.0706144 0.0437971 0.184074 -0.0712 0.0432115 0.185874 -0.0712 0.0432115 0.185874 -0.072 0.0429971 0.184074 -0.072 0.0429971 0.185874 -0.0733857 0.0437971 0.183974 -0.0703 0.0445971 0.184074 -0.0706144 0.0437971 0.183974 -0.0705278 0.0437471 0.184074 -0.0728 0.0432115 0.184074 -0.0733857 0.0437971 0.184074 -0.0736 0.0445971 0.185874 -0.0996009 0.0352793 0.185974 -0.0996875 0.0352293 0.185974 -0.0990653 0.0346071 0.185874 -0.0966153 0.0360793 0.185974 -0.096743 0.0352293 0.185974 -0.0965153 0.0360793 0.184074 -0.0966153 0.0360793 0.185874 -0.0968296 0.0352793 0.185874 -0.0974153 0.0346937 0.185874 -0.0982153 0.0344793 0.184074 -0.0982153 0.0344793 0.185874 -0.0990153 0.0346937 0.185874 -0.0998153 0.0360793 0.184074 -0.0996009 0.0352793 0.184074 -0.0998153 0.0360793 0.184074 -0.0968296 0.0352793 0.183974 -0.0965153 0.0360793 0.183974 -0.096743 0.0352293 0.184074 -0.0974153 0.0346937 0.183974 -0.0973653 0.0346071 0.183974 -0.0982153 0.0343793 0.183974 -0.0990653 0.0346071 0.184074 -0.0990153 0.0346937 0.183974 -0.0996875 0.0352293 0.185974 -0.116117 0.0137793 0.185974 -0.115267 0.0123071 0.185974 -0.114417 0.0120793 0.185874 -0.113617 0.0123937 0.185874 -0.113032 0.0129793 0.184074 -0.113032 0.0129793 0.185874 -0.114417 0.0121793 0.185874 -0.115217 0.0123937 0.184074 -0.114417 0.0121793 0.185874 -0.115803 0.0129793 0.184074 -0.115217 0.0123937 0.185874 -0.116017 0.0137793 0.183974 -0.112717 0.0137793 0.184074 -0.113617 0.0123937 0.183974 -0.114417 0.0120793 0.184074 -0.115803 0.0129793 0.183974 -0.115267 0.0123071 0.183974 -0.116117 0.0137793 0.185874 -0.115217 -0.0151707 0.185974 -0.115267 -0.0152573 0.185974 -0.114417 -0.015485 0.185974 -0.112717 -0.013785 0.185874 -0.112817 -0.013785 0.184074 -0.112817 -0.013785 0.185874 -0.113032 -0.014585 0.184074 -0.113032 -0.014585 0.185874 -0.113617 -0.0151707 0.185874 -0.114417 -0.015385 0.184074 -0.115217 -0.0151707 0.185874 -0.115803 -0.014585 0.183974 -0.113567 -0.0152573 0.184074 -0.113617 -0.0151707 0.184074 -0.114417 -0.015385 0.184074 -0.115803 -0.014585 0.183974 -0.115889 -0.014635 0.184974 -0.0887 -0.00285437 0.185574 -0.0887 -0.00450286 0.184666 -0.0902499 -0.00285437 0.182474 -0.0924418 -0.00285437 0.182704 -0.0929961 -0.00450286 0.183249 -0.075273 -0.00450286 0.182949 -0.0757926 -0.00285437 0.184432 -0.077275 -0.00285437 0.180724 -0.07525 -0.00285437 0.180924 -0.07525 -0.00285437 0.180924 -0.07465 -0.00450286 0.179174 -0.0924418 -0.00285437 0.17786 -0.0915638 -0.00285437 0.176428 -0.0904795 -0.00450286 0.177217 -0.077275 -0.00285437 0.176074 -0.0793 -0.00450286 0.176697 -0.076975 -0.00450286 0.178399 -0.075273 -0.00450286 0.185574 -0.0647 -0.00450286 0.182704 -0.0689961 -0.00450286 0.182949 -0.0517926 -0.00285437 0.184951 -0.052975 -0.00450286 0.185574 -0.0553 -0.00450286 0.180924 -0.06935 -0.00450286 0.180924 -0.06875 -0.00285437 0.180924 -0.05125 -0.00285437 0.180724 -0.05065 -0.00450286 0.180924 -0.05065 -0.00450286 0.179174 -0.0684418 -0.00285437 0.180724 -0.06935 -0.00450286 0.178945 -0.0689961 -0.00450286 0.17786 -0.0675638 -0.00285437 0.176983 -0.0662499 -0.00285437 0.178699 -0.0517926 -0.00285437 0.176674 -0.0553 -0.00285437 0.186574 -0.0427793 -0.0271857 0.184974 -0.0415873 -0.0262917 0.186574 -0.0415873 -0.0262917 0.184974 -0.101221 -0.0271857 0.184974 -0.099765 -0.0275029 0.186574 -0.101221 -0.0271857 0.186574 -0.099765 -0.0275029 0.186574 -0.0506698 0.0337196 0.184974 -0.0523945 0.0335757 0.186574 -0.0521761 0.0336434 0.186574 -0.0535105 0.0329403 0.186574 -0.0544251 0.0317409 0.186574 -0.0547501 0.0302681 0.184974 -0.089422 0.0313519 0.184974 -0.089575 0.0317409 0.186574 -0.089422 0.0313519 0.184974 -0.0902595 0.0327272 0.186574 -0.0902595 0.0327272 0.184974 -0.0904896 0.0329403 0.186574 -0.0932269 0.0337354 0.186574 -0.0947289 0.033155 0.186774 -0.03035 -2.85742e-06 0.186574 -0.0381427 0.024596 0.186774 -0.0383045 0.0244784 0.186774 -0.0441308 0.0309491 0.186574 -0.051075 0.0362403 0.186574 -0.0590677 0.0397989 0.186774 -0.051175 0.0360671 0.186774 -0.0591295 0.0396086 0.186774 -0.0676464 0.041419 0.186574 -0.0849324 0.0397989 0.186774 -0.092825 0.0360671 0.186774 -0.0998693 0.0309491 0.186574 -0.100003 0.0310978 0.186574 -0.105857 0.024596 0.186774 -0.11274 0.00865666 0.186774 -0.11365 -2.85742e-06 0.186874 -0.034856 -0.0178905 0.186974 -0.0676935 -0.0409772 0.186874 -0.0689192 -0.0411144 0.186801 -0.03479 -0.0179223 0.186801 -0.0325349 -0.0121762 0.186801 -0.0311613 -0.0061583 0.186801 -0.102275 -0.028094 0.186774 -0.106206 -0.0233243 0.186774 -0.1093 -0.0179656 0.186801 -0.0977502 -0.0322925 0.186801 -0.09265 -0.0357697 0.186801 -0.0870886 -0.0384479 0.186774 -0.0871252 -0.038541 0.186801 -0.0811902 -0.0402674 0.186801 -0.0750864 -0.0411874 0.186774 -0.0689062 -0.0412871 0.186774 -0.0750939 -0.0412871 0.186774 -0.0568749 -0.038541 0.186801 -0.0462499 -0.0322925 0.186801 -0.041725 -0.028094 0.186801 -0.0378764 -0.023268 0.186774 -0.0324393 -0.0122057 0.186774 -0.112938 -0.00617321 0.186774 -0.111561 -0.0122057 0.186801 -0.10921 -0.0179223 0.186874 -0.109144 -0.0178905 0.186874 -0.0977045 -0.0322353 0.186874 -0.0926134 -0.0357063 0.186874 -0.0870619 -0.0383798 0.186874 -0.0750809 -0.0411144 0.186801 -0.0569115 -0.0384479 0.186874 -0.0513866 -0.0357063 0.186801 -0.05135 -0.0357697 0.186874 -0.0462956 -0.0322353 0.186874 -0.0417787 -0.0280442 0.186774 -0.1134 -2.85742e-06 0.186801 -0.1133 -2.85742e-06 0.186874 -0.112766 -0.00614739 0.186801 -0.111465 -0.0121762 0.186801 -0.112839 -0.0061583 0.186974 -0.1123 -0.00856882 0.186874 -0.111395 -0.0121547 0.186974 -0.109638 -0.0167604 0.186874 -0.106063 -0.0232267 0.186801 -0.106124 -0.023268 0.186874 -0.102221 -0.0280442 0.186974 -0.0995682 -0.0306204 0.186974 -0.102202 -0.028026 0.186874 -0.0811739 -0.040196 0.186974 -0.0870521 -0.0383549 0.186974 -0.0926 -0.0356831 0.186974 -0.0689212 -0.0410877 0.186974 -0.0763066 -0.0409772 0.186801 -0.0689137 -0.0411874 0.186874 -0.0628262 -0.040196 0.186801 -0.0628099 -0.0402674 0.186974 -0.0628322 -0.0401699 0.186974 -0.0514 -0.0356831 0.186874 -0.0569382 -0.0383798 0.186974 -0.0348801 -0.0178789 0.186974 -0.037959 -0.0232116 0.186874 -0.0379369 -0.0232267 0.186974 -0.0386685 -0.0242196 0.186974 -0.0444319 -0.0306204 0.186974 -0.034362 -0.0167604 0.186874 -0.0326048 -0.0121547 0.186874 -0.0312337 -0.00614739 0.180199 -0.0709175 0.00499714 0.180824 -0.07325 -0.00405286 0.180199 -0.0730826 0.00499714 0.180199 -0.0730826 -0.00405286 0.179742 -0.072625 0.00499714 0.179574 -0.072 0.00499714 0.179574 -0.072 -0.00405286 0.179742 -0.071375 0.00499714 0.180199 -0.0709175 -0.00405286 0.179742 -0.072625 -0.00405286 0.179974 -0.0734723 -0.00450286 0.179124 -0.072 -0.00450286 0.179742 -0.071375 -0.00405286 0.180824 -0.0703 -0.00450286 0.179742 -0.095875 0.00499714 0.179574 -0.09525 0.00499714 0.180824 -0.0965 0.00499714 0.180199 -0.0941675 0.00499714 0.180824 -0.094 0.00499714 0.179742 -0.094625 0.00499714 0.180199 -0.0963326 0.00499714 0.179742 -0.095875 -0.00405286 0.180199 -0.0963326 -0.00405286 0.179574 -0.09525 -0.00405286 0.179742 -0.094625 -0.00405286 0.179352 -0.0944 -0.00450286 0.180199 -0.0941675 -0.00405286 0.180824 -0.094 -0.00405286 0.180824 -0.04875 0.00574822 0.179742 -0.049375 0.00499714 0.180824 -0.05 0.00499714 0.180824 -0.05 -0.00405286 0.180199 -0.0498326 0.00499714 0.180199 -0.0498326 -0.00405286 0.179574 -0.04875 0.00499714 0.179742 -0.049375 -0.00405286 0.179742 -0.048125 -0.00405286 0.179742 -0.048125 0.00499714 0.180199 -0.0476675 0.00499714 0.179574 -0.04875 -0.00405286 0.179124 -0.04875 -0.00450286 0.180199 -0.0476675 -0.00405286 0.184974 -0.0765 -0.0335029 0.183974 -0.0753661 -0.0330029 0.184974 -0.0755 -0.0317708 0.184974 -0.0745 -0.0315029 0.183974 -0.0695 -0.0325029 0.184974 -0.067768 -0.0325029 0.184974 -0.0750569 -0.0479425 0.183974 -0.074538 -0.0470877 0.183974 -0.075243 -0.0463589 0.184974 -0.0761145 -0.0468494 0.184974 -0.0765 -0.0453781 0.183974 -0.0755 -0.0453781 0.184974 -0.0689432 -0.0479425 0.184974 -0.0735992 -0.0483764 0.18428 -0.0889449 0.0320332 0.184974 -0.08925 0.0302681 0.184974 -0.0933303 0.0337196 0.184974 -0.0918239 0.0336434 0.183974 -0.0898437 0.0337037 0.183974 -0.088868 0.0325442 0.183974 -0.0952943 0.0339798 0.183974 -0.101876 0.0283673 0.184974 -0.101151 0.0276787 0.183974 -0.104694 0.0250679 0.183974 -0.106412 0.0226527 0.183974 -0.107141 0.0215043 0.184974 -0.106288 0.0209823 0.183974 -0.110857 0.0136933 0.183974 -0.11286 0.00527864 0.184974 -0.111446 0.00774622 0.184974 -0.111868 0.00515045 0.184974 -0.1122 -2.85742e-06 0.184974 -0.112066 -0.00328714 0.184974 -0.111563 -0.0071286 0.183974 -0.111455 -0.011868 0.184974 -0.102413 -0.0262917 0.183974 -0.103169 -0.0269456 0.183974 -0.0955 -0.0285029 0.183974 -0.092902 -0.0300029 0.184974 -0.0920359 -0.0295029 0.184974 -0.0915 -0.0315029 0.184974 -0.0915 -0.0351982 0.183974 -0.0925 -0.0351982 0.184974 -0.0917284 -0.0363463 0.183974 -0.0926523 -0.0359636 0.184974 -0.0923787 -0.0373195 0.183974 -0.0945274 -0.038054 0.184974 -0.0981236 -0.0401663 0.183974 -0.0961142 -0.039028 0.183974 -0.0996928 -0.0384719 0.184974 -0.11697 -0.0178989 0.184974 -0.119535 -0.00911376 0.183974 -0.118553 -0.00892552 0.183974 -0.0443073 -0.0384719 0.184974 -0.0458765 -0.0401663 0.184974 -0.0501798 -0.0387611 0.184974 -0.0516214 -0.0373195 0.184974 -0.0522717 -0.0363463 0.184974 -0.0525 -0.0315029 0.183974 -0.0515 -0.0315029 0.184974 -0.0505 -0.0280388 0.183974 -0.05 -0.0289048 0.184974 -0.0485 -0.0275029 0.183974 -0.0485 -0.0285029 0.184974 -0.0442351 -0.0275029 0.183974 -0.0442351 -0.0285029 0.183974 -0.0408307 -0.0269456 0.184974 -0.0427793 -0.0271857 0.183974 -0.0423633 -0.0280951 0.183974 -0.0315727 0.00793898 0.183974 -0.0338618 0.0155829 0.184974 -0.0340863 0.0133609 0.183974 -0.0375815 0.0226423 0.183974 -0.0392866 0.0250425 0.183974 -0.0376718 0.0227789 0.184974 -0.0428492 0.0276787 0.183974 -0.0506493 0.0347278 0.184974 -0.0507828 0.0337368 0.184974 -0.0537611 0.0327063 0.183974 -0.0544785 0.033403 0.184974 -0.0544251 0.0317409 0.184974 -0.0545899 0.0313148 0.186074 -0.0901776 -0.0326883 0.186074 -0.0912224 -0.0317867 0.186274 -0.0916251 -0.0305107 0.186074 -0.0804547 -0.0364347 0.186074 -0.0854473 -0.0349017 0.186274 -0.0900804 -0.0325135 0.186272 -0.0764987 -0.0334298 0.186192 -0.0765 -0.0339115 0.186274 -0.0777752 -0.0356895 0.186274 -0.0790317 -0.0362551 0.186074 -0.0776557 -0.0358499 0.186074 -0.0789908 -0.0364508 0.186274 -0.0595366 -0.0399539 0.186274 -0.0590677 -0.0398046 0.186174 -0.0520955 -0.0367027 0.186174 -0.0919045 -0.0367027 0.186192 -0.0675 -0.0339115 0.186274 -0.0671271 -0.0346479 0.186266 -0.0675 -0.0335029 0.186074 -0.0650093 -0.0364508 0.186074 -0.0663444 -0.0358499 0.186074 -0.0538225 -0.0326883 0.186274 -0.0635906 -0.0362399 0.186274 -0.0529363 -0.031665 0.185874 -0.0676 -0.0416209 0.185974 -0.0677 -0.0416314 0.185974 -0.0704075 -0.0481765 0.185774 -0.0689432 -0.0479425 0.185774 -0.0675 -0.0453781 0.185774 -0.0735992 -0.0483764 0.185974 -0.0735926 -0.0481765 0.185774 -0.0704009 -0.0483764 0.185974 -0.0763 -0.0453781 0.185874 -0.0764001 -0.0416209 0.185974 -0.0924747 -0.0371316 0.185974 -0.0925201 -0.0371781 0.185774 -0.0958038 -0.0399786 0.185974 -0.0958659 -0.0397885 0.185774 -0.043723 -0.0392835 0.185774 -0.0368343 -0.0332584 0.185774 -0.0312029 -0.0260442 0.185974 -0.0313715 -0.0259366 0.185774 -0.0270302 -0.0178989 0.185974 -0.027216 -0.017825 0.185774 -0.0244653 -0.00911376 0.185974 -0.0481342 -0.0397885 0.185974 -0.0514799 -0.0371781 0.185974 -0.0500383 -0.0386197 0.185974 -0.051868 -0.0366924 0.185874 -0.0519559 -0.0367405 0.187574 -0.0925536 -0.0269536 0.187574 -0.092929 -0.026853 0.187574 -0.0933043 -0.0262029 0.187574 -0.0932038 -0.0265782 0.187574 -0.0507963 0.0258218 0.187574 -0.0932038 0.0258218 0.187574 -0.0919035 0.0258218 0.187574 -0.0918029 0.0261971 0.187574 -0.0921783 0.025547 0.187574 -0.0514465 -0.0269536 0.187574 -0.0520966 -0.0265782 0.180724 -0.06875 0.00669714 0.17786 -0.0675638 0.00669714 0.184432 -0.053275 0.00669714 0.180924 -0.06875 0.00669714 0.178699 -0.0517926 0.00669714 0.176674 -0.0553 0.00669714 0.176983 -0.0902499 0.00669714 0.180924 -0.09275 0.00669714 0.182949 -0.0757926 0.00669714 0.184974 -0.0793 0.00669714 0.184974 -0.0887 0.00669714 0.177217 -0.077275 0.00669714 0.180724 -0.09275 0.00669714 0.179174 -0.0924418 0.00669714 0.213124 -0.0310157 0.00870864 0.213124 -0.112984 0.00870864 0.213124 -0.100037 0.0311349 0.213124 -0.09295 0.0362836 0.213124 -0.0849479 0.0398464 0.213124 -0.0676203 0.0416676 0.213124 -0.05105 -0.0362893 0.213124 -0.1139 -2.85742e-06 0.213124 -0.0763798 -0.0416733 0.213124 -0.105898 -0.0246311 0.213124 -0.100037 -0.0311406 0.213124 -0.0849479 -0.0398521 0.213124 -0.0590522 0.0398464 0.213124 -0.0439635 0.0311349 0.213124 -0.0381022 0.0246253 0.224774 -0.0877618 -0.0624872 0.224774 -0.087288 -0.0630295 0.224774 -0.087638 -0.0630295 0.224774 -0.0874464 -0.0637237 0.224774 -0.0877618 -0.0635719 0.224774 -0.0885319 -0.0645894 0.224774 -0.0898856 -0.0642805 0.224774 -0.0896674 -0.0640068 0.224774 -0.0900142 -0.0635719 0.224774 -0.090488 -0.0630295 0.224774 -0.090138 -0.0630295 0.224774 -0.0551121 -0.0614295 0.224774 -0.0543327 -0.0620522 0.224774 -0.0535121 -0.0630295 0.224774 -0.0538621 -0.0630295 0.224774 -0.0543121 -0.0644152 0.224774 -0.0559121 -0.0644152 0.224774 -0.0551121 -0.0642795 0.224774 -0.0564977 -0.0638295 0.224774 -0.0561946 -0.0636545 0.224774 -0.0563621 -0.0630295 0.224774 -0.0261395 -0.0449229 0.224774 -0.0255832 -0.0449229 0.224774 -0.0246113 -0.0461416 0.224774 -0.0247351 -0.0466839 0.224774 -0.0248637 -0.0473925 0.224774 -0.025082 -0.0471189 0.224774 -0.0262174 -0.0477015 0.224774 -0.0268589 -0.0473925 0.224774 -0.0273029 -0.0468358 0.224774 -0.0274613 -0.0461416 0.224774 -0.0269875 -0.0466839 0.224774 -0.0271113 -0.0461416 0.224774 -0.0269875 -0.0455992 0.224774 -0.0266613 -0.0447559 0.224774 -0.0266407 -0.0451643 0.224774 -0.00975274 -0.0159135 0.224774 -0.00897338 -0.0152908 0.224774 -0.00925153 -0.0156721 0.224774 -0.00819402 -0.0159135 0.224774 -0.00758774 -0.0160908 0.224774 -0.00772338 -0.0168908 0.224774 -0.00737338 -0.0168908 0.224774 -0.00817338 -0.0182764 0.224774 -0.00789085 -0.0175158 0.224774 -0.00834838 -0.0179733 0.224774 -0.00897338 -0.0184908 0.224774 -0.00897338 -0.0181408 0.224774 -0.00959838 -0.0179733 0.224774 -0.0100559 -0.0175158 0.224774 -0.0100996 -0.0163484 0.224774 -0.00975274 0.0178624 0.224774 -0.00925153 0.0181037 0.224774 -0.00737338 0.0168851 0.224774 -0.00772338 0.0168851 0.224774 -0.00834838 0.0158026 0.224774 -0.00959838 0.0158026 0.224774 -0.0105734 0.0168851 0.224774 -0.0102234 0.0168851 0.224774 -0.010359 0.0176851 0.224774 -0.0100996 0.0174274 0.224774 -0.00897338 0.0184851 0.224774 -0.0271113 0.0461359 0.224774 -0.0274613 0.0461359 0.224774 -0.027247 0.0453359 0.224774 -0.0264863 0.0450533 0.224774 -0.0258613 0.0448859 0.224774 -0.0250613 0.0447502 0.224774 -0.0246113 0.0461359 0.224774 -0.0247788 0.0467609 0.224774 -0.0244757 0.0469359 0.224774 -0.0258613 0.0473859 0.224774 -0.0264863 0.0472184 0.224774 -0.027247 0.0469359 0.224774 -0.0553902 0.0618051 0.224774 -0.0559121 0.0616382 0.224774 -0.0564977 0.0622238 0.224774 -0.0562383 0.0624814 0.224774 -0.0563621 0.0630238 0.224774 -0.0561946 0.0636488 0.224774 -0.0544871 0.0641063 0.224774 -0.0543121 0.0644094 0.224774 -0.0537265 0.0638238 0.224774 -0.0535121 0.0630238 0.224774 -0.0539859 0.0624814 0.224774 -0.0543121 0.0616382 0.224774 -0.0551121 0.0614238 0.224774 -0.0548339 0.0618051 0.224774 -0.088088 0.0644094 0.224774 -0.0875023 0.0638238 0.224774 -0.087288 0.0630238 0.224774 -0.0875023 0.0622238 0.224774 -0.088088 0.0616382 0.224774 -0.0878054 0.0623988 0.224774 -0.089513 0.0619413 0.224774 -0.0902736 0.0638238 0.224774 -0.090138 0.0630238 0.224774 -0.0900142 0.0635662 0.224774 -0.089688 0.0644094 0.224774 -0.117861 0.0449172 0.224774 -0.118417 0.0449172 0.224774 -0.119524 0.0453359 0.224774 -0.119265 0.0455935 0.224774 -0.119389 0.0461359 0.224774 -0.119524 0.0469359 0.224774 -0.118764 0.0472184 0.224774 -0.118139 0.0477359 0.224774 -0.116889 0.0461359 0.224774 -0.117359 0.0451586 0.224774 -0.118139 0.0445359 0.224774 -0.135027 0.0184851 0.224774 -0.133641 0.0160851 0.224774 -0.134227 0.0154994 0.224774 -0.135027 0.0152851 0.224774 -0.135027 0.0156351 0.224774 -0.136412 0.0160851 0.224774 -0.136627 0.0168851 0.224774 -0.135827 0.0182707 0.224774 -0.136153 0.0174274 0.224774 -0.135806 0.0178624 0.224774 -0.135027 -0.0152908 0.224774 -0.134227 -0.0155052 0.224774 -0.133641 -0.0160908 0.224774 -0.133777 -0.0168908 0.224774 -0.133641 -0.0176908 0.224774 -0.133944 -0.0175158 0.224774 -0.135027 -0.0184908 0.224774 -0.135027 -0.0181408 0.224774 -0.135827 -0.0182764 0.224774 -0.135652 -0.0179733 0.224774 -0.136627 -0.0168908 0.224774 -0.136412 -0.0160908 0.224774 -0.118139 -0.0445416 0.224774 -0.117339 -0.0447559 0.224774 -0.117861 -0.0449229 0.224774 -0.117013 -0.0455992 0.224774 -0.116539 -0.0461416 0.224774 -0.117514 -0.0472241 0.224774 -0.118139 -0.0473916 0.224774 -0.118939 -0.0475272 0.224774 -0.119524 -0.0453416 0.186474 -0.112984 -0.00871436 0.213124 -0.112984 -0.00871436 0.213124 -0.110278 -0.0170451 0.186474 -0.105898 -0.0246311 0.186474 -0.0849479 -0.0398521 0.213124 -0.09295 -0.0362893 0.213124 -0.0676203 -0.0416733 0.213124 -0.0590522 -0.0398521 0.186474 -0.0439635 -0.0311406 0.213124 -0.0439635 -0.0311406 0.186474 -0.0381022 -0.0246311 0.213124 -0.0381022 -0.0246311 0.186474 -0.0337225 -0.0170451 0.213124 -0.0337225 -0.0170451 0.213124 -0.0310157 -0.00871436 0.186474 -0.0301 -2.85742e-06 0.213124 -0.0301 -2.85742e-06 0.220229 -0.00784717 -0.0163484 0.219435 -0.0100996 -0.0163484 0.21923 -0.0126658 -0.0225054 0.220803 -0.0062371 -0.0164158 0.220206 -0.00834838 -0.0179733 0.220277 -0.00809152 -0.0177767 0.220322 -0.00789085 -0.0175158 0.220777 -0.00506242 -0.0101873 0.21923 -0.010386 -0.0151893 0.219673 -0.00925153 -0.0156721 0.219903 -0.00730004 -0.00887967 0.21987 -0.00869523 -0.0156721 0.22032 -0.1378 -0.00928614 0.220745 -0.13889 -0.00991638 0.220803 -0.138904 -0.0108647 0.220803 -0.139034 -0.01003 0.21923 -0.134995 -0.00765187 0.21923 -0.134638 -0.0101721 0.219258 -0.135267 -0.00583705 0.219563 -0.0100559 -0.0175158 0.21923 -0.0136888 -0.0250372 0.220803 -0.0109937 -0.0295388 0.21923 -0.0245011 -0.0420833 0.21943 -0.0266407 -0.0451643 0.220803 -0.0233936 -0.0472423 0.220312 -0.0247351 -0.0466839 0.220036 -0.0247351 -0.0455992 0.219836 -0.025082 -0.0451643 0.21923 -0.0299196 -0.0475018 0.219736 -0.0269875 -0.0466839 0.21923 -0.0359518 -0.0522278 0.220803 -0.0315475 -0.0543879 0.220803 -0.0382338 -0.0587735 0.220803 -0.0407363 -0.0601421 0.220803 -0.0480883 -0.0634251 0.220206 -0.0557371 -0.0641121 0.220277 -0.0554381 -0.0642363 0.220277 -0.0542268 -0.0639119 0.220206 -0.0540296 -0.0636545 0.220004 -0.0538621 -0.0630295 0.21923 -0.0494975 -0.0593371 0.219481 -0.0548339 -0.0618109 0.21923 -0.0568136 -0.0616169 0.219428 -0.0553902 -0.0618109 0.220182 -0.0900142 -0.0635719 0.220803 -0.0909421 -0.0650824 0.220286 -0.0886098 -0.0642482 0.220803 -0.0828722 -0.0669054 0.21923 -0.0796491 -0.0629982 0.220803 -0.0802683 -0.0672768 0.220803 -0.072066 -0.067783 0.219769 -0.087638 -0.0630295 0.21923 -0.0871865 -0.0616169 0.21923 -0.0897342 -0.0609324 0.21923 -0.10149 -0.0561921 0.21923 -0.108048 -0.0522278 0.220337 -0.119023 -0.0470255 0.220322 -0.118764 -0.0472241 0.219769 -0.117056 -0.0467666 0.21923 -0.11408 -0.0475018 0.21923 -0.115996 -0.0457332 0.219563 -0.116889 -0.0461416 0.220803 -0.126213 -0.0406861 0.220036 -0.119265 -0.0455992 0.220206 -0.119389 -0.0461416 0.220803 -0.120698 -0.0471476 0.21923 -0.119499 -0.0420833 0.21923 -0.122756 -0.0380918 0.220803 -0.127592 -0.0387799 0.21923 -0.128189 -0.0294933 0.220803 -0.132032 -0.0314727 0.220803 -0.133064 -0.02942 0.220322 -0.136109 -0.0175158 0.220803 -0.136973 -0.0193075 0.220803 -0.136299 -0.0214458 0.21949 -0.13382 -0.0172173 0.21923 -0.132199 -0.0200784 0.21923 -0.133614 -0.0151893 0.21987 -0.135305 -0.0156721 0.220068 -0.135806 -0.0159135 0.224474 -0.13673 0.0216335 0.224474 -0.132251 0.0320577 0.221811 -0.126107 0.041596 0.221811 -0.121036 0.0474687 0.221811 -0.118468 0.0499847 0.221811 -0.11284 0.0546798 0.224474 -0.109545 0.056992 0.221811 -0.103598 0.0604919 0.221811 -0.0935486 0.0647561 0.224474 -0.0995847 0.0624243 0.221811 -0.0829476 0.0673634 0.224474 -0.0776729 0.068011 0.221811 -0.0663272 0.068011 0.224474 -0.0551383 0.0661314 0.221811 -0.0255317 0.0499847 0.221811 -0.031267 0.0547592 0.221811 -0.0405196 0.0605532 0.221811 -0.011749 0.0320577 0.224474 -0.0178928 0.041596 0.224474 -0.0255317 0.0499847 0.224474 -0.00727035 0.0216335 0.221811 -0.00727035 0.0216335 0.224474 -0.011749 0.0320577 0.221811 -0.00458044 -0.010617 0.221811 -0.00727035 -0.0216392 0.224474 -0.00727035 -0.0216392 0.221811 -0.011749 -0.0320634 0.224474 -0.011749 -0.0320634 0.221811 -0.0160986 -0.0391576 0.221811 -0.0178928 -0.0416017 0.224474 -0.0178928 -0.0416017 0.221811 -0.0255317 -0.0499904 0.224474 -0.0344548 -0.0569977 0.221811 -0.0405196 -0.060559 0.224474 -0.0444154 -0.06243 0.221811 -0.0551383 -0.0661371 0.221811 -0.0720665 -0.0682528 0.221811 -0.0776729 -0.0680167 0.221811 -0.118468 -0.0499904 0.224474 -0.109545 -0.0569977 0.221811 -0.109545 -0.0569977 0.221811 -0.103598 -0.0604976 0.224474 -0.0995847 -0.06243 0.221811 -0.0995847 -0.06243 0.221811 -0.132251 -0.0320634 0.221811 -0.126107 -0.0416017 0.221811 -0.121036 -0.0474744 0.221811 -0.137423 -0.0194413 0.224474 -0.13673 -0.0216392 0.221811 -0.13673 -0.0216392 0.221762 -0.00457001 0.0103969 0.221643 -0.00459813 0.0102132 0.220984 -0.00490488 0.0101864 0.221811 -0.0066147 0.0195629 0.221686 -0.139414 0.0102681 0.220999 -0.139138 0.00994694 0.221547 -0.139371 0.0101137 0.221194 -0.139242 0.00986917 0.220803 -0.0315474 0.0543822 0.221811 -0.0344548 0.056992 0.221811 -0.0444154 0.0624243 0.221811 -0.0505775 0.0647979 0.221811 -0.0551383 0.0661314 0.221811 -0.0611836 0.0673846 0.221811 -0.0720665 0.0682471 0.220803 -0.072066 0.0677773 0.221811 -0.0776729 0.068011 0.220803 -0.0802683 0.0672711 0.220803 -0.0828722 0.0668996 0.221811 -0.0888618 0.0661314 0.221811 -0.0995847 0.0624243 0.220803 -0.103381 0.0600754 0.221811 -0.109545 0.056992 0.220803 -0.110558 0.0557416 0.220803 -0.112558 0.0543034 0.220803 -0.118993 0.0488423 0.221811 -0.127978 0.039043 0.220803 -0.127592 0.0387742 0.221811 -0.132251 0.0320577 0.221811 -0.133487 0.0296182 0.221811 -0.13673 0.0216335 0.221811 -0.137423 0.0194356 0.220803 -0.136299 0.0214401 0.221811 -0.13942 0.0106113 0.221811 -0.0230567 0.047564 0.221811 -0.0178928 0.041596 0.220803 -0.0164834 0.0388823 0.221811 -0.0160986 0.0391519 0.220803 -0.0148071 0.0363719 0.220803 -0.0109937 0.0295331 0.221811 -0.0105708 0.0297378 0.220803 -0.00971719 0.0267366 0.220803 -0.00706482 0.0194282 0.221641 -0.00459871 -0.0102166 0.221525 -0.139364 -0.0100998 0.221811 -0.0066147 -0.0195686 0.220803 -0.00706483 -0.0194339 0.220803 -0.0097172 -0.0267423 0.221811 -0.0105708 -0.0297436 0.220803 -0.0148071 -0.0363776 0.220803 -0.0164834 -0.038888 0.220803 -0.0213754 -0.0450727 0.221811 -0.0230567 -0.0475698 0.220803 -0.0292521 -0.0526029 0.221811 -0.031267 -0.0547649 0.221811 -0.0344548 -0.0569977 0.221811 -0.0444154 -0.06243 0.221811 -0.0505776 -0.0648036 0.220803 -0.0585608 -0.0664373 0.220803 -0.050725 -0.0643575 0.221811 -0.0611836 -0.0673903 0.220803 -0.0693807 -0.0677324 0.220803 -0.0612581 -0.0669264 0.221811 -0.0663272 -0.0680167 0.221811 -0.0829476 -0.0673691 0.220803 -0.0934003 -0.064316 0.221811 -0.0888618 -0.0661371 0.220803 -0.101126 -0.0612058 0.221811 -0.0935487 -0.0647618 0.220803 -0.103381 -0.0600811 0.220803 -0.110558 -0.0557473 0.220803 -0.112558 -0.0543091 0.220803 -0.118993 -0.048848 0.221811 -0.11284 -0.0546855 0.221811 -0.127978 -0.0390487 0.221811 -0.133487 -0.0296239 0.221811 -0.13942 -0.010617 0.221804 -0.139429 -0.0105384 0.220999 -0.139138 -0.00995265 0.224774 -0.00487679 0.0105646 0.224474 -0.00458044 0.0106113 0.224774 -0.025736 0.049765 0.224474 -0.0344548 0.056992 0.224474 -0.0444154 0.0624243 0.224474 -0.0663272 0.068011 0.224774 -0.0552124 0.0658407 0.224774 -0.0663522 0.067712 0.224774 -0.0776479 0.067712 0.224474 -0.0888618 0.0661314 0.224474 -0.118468 0.0499847 0.224774 -0.118264 0.049765 0.224774 -0.125869 0.0414131 0.224474 -0.126107 0.041596 0.224774 -0.131986 0.0319168 0.224474 -0.13942 0.0106113 0.224474 -0.13942 -0.010617 0.224774 -0.136445 -0.0215441 0.224474 -0.132251 -0.0320634 0.224774 -0.131986 -0.0319225 0.224474 -0.126107 -0.0416017 0.224474 -0.118468 -0.0499904 0.224774 -0.10938 -0.0567472 0.224474 -0.0888618 -0.0661371 0.224474 -0.0776729 -0.0680167 0.224774 -0.0776479 -0.0677177 0.224474 -0.0663272 -0.0680167 0.224474 -0.0551383 -0.0661371 0.224774 -0.0552124 -0.0658465 0.224774 -0.0445367 -0.0621556 0.224774 -0.0346198 -0.0567472 0.224474 -0.0255317 -0.0499904 0.224774 -0.0181306 -0.0414189 0.224774 -0.00755488 -0.0215441 0.224474 -0.00458044 -0.010617 0.21829 -0.1034 0.0543835 0.187974 -0.1034 0.0543835 0.21829 -0.133988 0.0100609 0.187974 -0.133846 0.0109022 0.21829 -0.134597 0.00504537 0.21829 -0.1348 -2.85742e-06 0.21829 -0.131575 0.0198646 0.21829 -0.129785 0.0245892 0.187974 -0.126386 0.0313971 0.21829 -0.127621 0.0291547 0.21829 -0.126386 0.0313971 0.21829 -0.125097 0.0335315 0.21829 -0.119037 0.0416069 0.187974 -0.120108 0.0403642 0.21829 -0.120108 0.0403642 0.21829 -0.11554 0.0452534 0.21829 -0.107725 0.0516458 0.21829 -0.0989863 0.0567032 0.21829 -0.0934789 0.0590098 0.187974 -0.0934789 0.0590098 0.21829 -0.0895504 0.060295 0.21829 -0.072 0.0627971 0.21829 -0.0746254 0.0627422 0.21829 -0.0695731 0.0627502 0.187974 -0.072 0.0627971 0.187974 -0.0610949 0.0618431 0.21829 -0.0595482 0.0615503 0.187974 -0.0505212 0.0590098 0.21829 -0.0546405 0.0603502 0.21829 -0.0505212 0.0590098 0.187974 -0.0406 0.0543835 0.21829 -0.0498452 0.0587594 0.187974 -0.031633 0.0481047 0.21829 -0.0286036 0.0453909 0.21829 -0.025095 0.0417555 0.21829 -0.0238925 0.0403642 0.187974 -0.0238925 0.0403642 0.187974 -0.0176136 0.0313971 0.21829 -0.0190094 0.0336992 0.21829 -0.0164717 0.0293305 0.21829 -0.0142934 0.0247719 0.187974 -0.0129873 0.021476 0.21829 -0.0124886 0.0200529 0.21829 -0.00941955 0.00524334 0.219021 -0.119244 -0.0418574 0.219021 -0.0107168 -0.0151078 0.218689 -0.0109445 -0.0150517 0.219018 -0.135114 -2.85742e-06 0.21923 -0.135458 -2.85742e-06 0.21923 -0.131334 -0.0225054 0.21923 -0.0945026 -0.0593371 0.219021 -0.079608 -0.06266 0.21923 -0.072 -0.0634608 0.219021 -0.072 -0.0631202 0.21923 -0.0695477 -0.0634134 0.21923 -0.064351 -0.0629982 0.21923 -0.0594178 -0.0622009 0.219021 -0.0568951 -0.0612861 0.219021 -0.0301455 -0.0472469 0.21923 -0.0319781 -0.0492487 0.21923 -0.040387 -0.0550259 0.21923 -0.0158108 -0.0294933 0.219021 -0.00934292 -0.00761081 0.21923 -0.00900474 -0.00765187 0.219021 -0.0200555 -0.0358576 0.219021 -0.024756 -0.0418574 0.218689 -0.0249316 -0.0417018 0.21829 -0.031633 -0.0481104 0.218689 -0.0870489 -0.0610584 0.218689 -0.072 -0.0628856 0.219021 -0.0643921 -0.06266 0.218689 -0.0569512 -0.0610584 0.218689 -0.0497015 -0.0587993 0.219021 -0.107855 -0.0519474 0.218689 -0.119068 -0.0417018 0.21829 -0.119007 -0.041647 0.21829 -0.120108 -0.0403699 0.219021 -0.134657 -0.00761081 0.219021 -0.133283 -0.0151078 0.218689 -0.133056 -0.0150517 0.218689 -0.00911729 -2.85742e-06 0.219215 -0.0085818 -2.85742e-06 0.218689 -0.00957577 -0.00758254 0.21829 -0.0101541 -0.010908 0.219021 -0.0129843 -0.0223846 0.21829 -0.0129873 -0.0214817 0.219021 -0.0161124 -0.0293349 0.218689 -0.0132036 -0.0223014 0.218689 -0.0163201 -0.0292259 0.21829 -0.013281 -0.022272 0.21923 -0.0184542 -0.0340581 0.21829 -0.0163934 -0.0291875 0.218689 -0.0202485 -0.0357243 0.21923 -0.0197751 -0.0360511 0.218689 -0.0303011 -0.0470713 0.218689 -0.0362786 -0.0517543 0.219021 -0.0361453 -0.0519474 0.218689 -0.042777 -0.0556828 0.21829 -0.0363256 -0.0516862 0.21923 -0.0425096 -0.0561921 0.219021 -0.042668 -0.0558905 0.219021 -0.0496183 -0.0590186 0.21829 -0.0497309 -0.0587219 0.218689 -0.0644204 -0.0624271 0.218689 -0.0795797 -0.0624271 0.21829 -0.0829052 -0.0618488 0.219021 -0.087105 -0.0612861 0.219021 -0.0943817 -0.0590186 0.218689 -0.0942986 -0.0587993 0.21829 -0.0870291 -0.060978 0.21923 -0.0992691 -0.0573031 0.219021 -0.101332 -0.0558905 0.218689 -0.101223 -0.0556828 0.21829 -0.0942692 -0.0587219 0.218689 -0.107722 -0.0517543 0.21829 -0.101185 -0.0556095 0.218689 -0.113699 -0.0470713 0.21829 -0.112367 -0.0481104 0.21829 -0.107675 -0.0516862 0.219021 -0.113855 -0.0472469 0.21829 -0.126386 -0.0314029 0.21923 -0.124225 -0.0360511 0.219021 -0.123945 -0.0358576 0.218689 -0.12768 -0.0292259 0.218689 -0.123752 -0.0357243 0.21829 -0.123683 -0.0356773 0.219021 -0.131016 -0.0223846 0.219021 -0.127888 -0.0293349 0.218689 -0.130796 -0.0223014 0.21829 -0.127607 -0.0291875 0.21829 -0.134342 -0.00757256 0.218689 -0.134424 -0.00758254 0.21829 -0.133846 -0.010908 0.21829 -0.132975 -0.0150319 0.21829 -0.131013 -0.0214817 0.185974 -0.1328 -2.85742e-06 0.187974 -0.131013 0.021476 0.185974 -0.129133 0.020792 0.185974 -0.118576 0.0390786 0.187974 -0.112367 0.0481047 0.185974 -0.111082 0.0465726 0.185974 -0.1024 0.0526515 0.185974 -0.0927949 0.0571305 0.187974 -0.0829052 0.0618431 0.185974 -0.0825578 0.0598735 0.185974 -0.072 0.0607971 0.185974 -0.0512052 0.0571305 0.185974 -0.0416 0.0526515 0.185974 -0.0254245 0.0390786 0.187974 -0.0101541 0.0109022 0.185974 -0.1144 -2.85742e-06 0.185974 -0.113473 -0.00881831 0.186474 -0.1139 -2.85742e-06 0.185974 -0.110734 -0.0172485 0.186474 -0.110278 -0.0170451 0.185974 -0.100371 -0.0315122 0.186474 -0.100037 -0.0311406 0.185974 -0.0932 -0.0367223 0.186474 -0.09295 -0.0362893 0.185974 -0.0851024 -0.0403277 0.186474 -0.0763798 -0.0416733 0.186474 -0.0676203 -0.0416733 0.185974 -0.0677 -0.0421843 0.186474 -0.0590522 -0.0398521 0.185974 -0.067568 -0.0421706 0.186474 -0.0310157 -0.00871436 0.185974 -0.0305266 -0.00881831 0.186474 -0.05105 -0.0362893 0.220004 -0.090138 -0.0630295 0.2203 -0.0896674 -0.0640068 0.224774 -0.0891661 -0.0642482 0.220337 -0.0891661 -0.0642482 0.224774 -0.0886098 -0.0642482 0.220155 -0.0881086 -0.0640068 0.224774 -0.0881086 -0.0640068 0.219971 -0.0877618 -0.0635719 0.224774 -0.0557371 -0.0641121 0.220004 -0.0561946 -0.0636545 0.219769 -0.0563621 -0.0630295 0.220322 -0.0551121 -0.0642795 0.220337 -0.0547884 -0.0642369 0.224774 -0.0544871 -0.0641121 0.220322 -0.0544871 -0.0641121 0.224774 -0.0540296 -0.0636545 0.219563 -0.0271113 -0.0461416 0.224774 -0.0266407 -0.0471189 0.224774 -0.0261395 -0.0473602 0.219938 -0.0266407 -0.0471189 0.220127 -0.0261395 -0.0473602 0.224774 -0.0255832 -0.0473602 0.220269 -0.0255832 -0.0473602 0.220334 -0.025082 -0.0471189 0.21949 -0.0101803 -0.0172163 0.219769 -0.00959838 -0.0179733 0.220004 -0.00897338 -0.0181408 0.220322 -0.00772338 -0.0168908 0.220337 -0.00776603 -0.0172145 0.219427 -0.0101809 0.0165618 0.224774 -0.0100559 0.0162601 0.219443 -0.0100559 0.0162601 0.21949 -0.00985558 0.0159995 0.219563 -0.00959838 0.0158026 0.224774 -0.00897338 0.0156351 0.224774 -0.00789085 0.0162601 0.220277 -0.00776674 0.0165587 0.220206 -0.00789085 0.0162601 0.21949 -0.0270694 0.0458148 0.224774 -0.0269439 0.0455109 0.219443 -0.0269439 0.0455109 0.219427 -0.0267452 0.0452519 0.219443 -0.0264863 0.0450533 0.224774 -0.0252363 0.0450533 0.219769 -0.0252363 0.0450533 0.224774 -0.0247788 0.0455109 0.224774 -0.0558915 0.0620465 0.219588 -0.0562383 0.0624814 0.224774 -0.0543327 0.0620465 0.219615 -0.0543327 0.0620465 0.224774 -0.0899705 0.0623988 0.219769 -0.0899705 0.0623988 0.224774 -0.088888 0.0617738 0.219443 -0.088263 0.0619413 0.21949 -0.0880026 0.0621415 0.224774 -0.088263 0.0619413 0.220206 -0.119389 0.0461359 0.220036 -0.119265 0.0455935 0.224774 -0.118918 0.0451586 0.219836 -0.118918 0.0451586 0.219643 -0.118417 0.0449172 0.219498 -0.117861 0.0449172 0.224774 -0.117013 0.0455935 0.219453 -0.117013 0.0455935 0.220277 -0.136234 0.0165597 0.224774 -0.136109 0.0162601 0.220206 -0.136109 0.0162601 0.224774 -0.135652 0.0158026 0.220004 -0.135652 0.0158026 0.219563 -0.134402 0.0158026 0.21949 -0.134145 0.0159991 0.224774 -0.134402 0.0158026 0.219443 -0.133944 0.0162601 0.224774 -0.133944 0.0162601 0.219427 -0.133819 0.0165613 0.224774 -0.133777 0.0168851 0.220337 -0.136234 -0.0172141 0.224774 -0.136109 -0.0175158 0.220277 -0.135909 -0.0177763 0.220206 -0.135652 -0.0179733 0.220004 -0.135027 -0.0181408 0.224774 -0.134402 -0.0179733 0.219769 -0.134402 -0.0179733 0.219563 -0.133944 -0.0175158 0.220277 -0.119347 -0.0464627 0.224774 -0.119389 -0.0461416 0.220322 -0.119221 -0.0467666 0.224774 -0.119221 -0.0467666 0.224774 -0.118764 -0.0472241 0.220277 -0.11846 -0.0473496 0.220206 -0.118139 -0.0473916 0.220004 -0.117514 -0.0472241 0.224774 -0.117056 -0.0467666 0.224474 -0.00825004 -2.85742e-06 0.219816 -0.00825004 -2.85742e-06 0.220514 -0.00723037 0.00834145 0.219821 -0.00853037 0.00608979 0.219829 -0.00852684 0.00622513 0.219841 -0.00851561 0.00636637 0.22004 -0.00818071 0.00739207 0.220195 -0.0078823 0.00780733 0.220931 -0.00615878 0.00896013 0.220514 -0.00723037 -0.00834717 0.224474 -0.00723037 -0.00834717 0.219721 -0.135606 0.00691918 0.224474 -0.136028 0.00769921 0.219625 -0.135481 -0.00585676 0.219625 -0.13575 -2.85742e-06 0.224474 -0.13677 -0.00834717 0.22007 -0.136327 -0.00802471 0.224474 -0.136028 -0.00770493 0.219829 -0.135817 -0.007393 0.224474 -0.135577 -0.0068334 0.220686 -0.137841 0.00896015 0.221112 -0.138932 -0.00959545 0.220686 -0.137841 -0.00896586 0.220269 -0.13677 -0.00834717 0.221804 -0.139429 -0.0105384 0.224474 -0.139371 0.0101137 0.221153 -0.139091 0.00970346 0.224474 -0.00456827 0.0104558 0.221811 -0.00458044 0.0106113 0.224474 -0.00462858 0.0101137 0.224474 -0.00480223 0.00981298 0.221427 -0.00467013 0.0100161 0.224474 -0.00506827 0.00958974 0.221408 -0.00477281 -0.00985548 0.224474 -0.00506827 -0.00959545 0.221761 -0.0045701 -0.0104011 0.221428 -0.00467012 -0.0100218 0.224474 -0.00480223 -0.00981869 0.224474 -0.139432 0.0104558 0.224774 -0.138782 0.00984955 0.224774 -0.139038 0.0101058 0.224474 -0.13923 0.0098537 0.224474 -0.139402 0.0102132 0.224474 -0.138932 0.00958974 0.224774 -0.13662 0.00860126 0.224474 -0.13677 0.00834145 0.224774 -0.135558 0.00753979 0.224474 -0.135577 0.00682769 0.224774 -0.13517 0.00608979 0.224774 -0.135182 0.00582349 0.224774 -0.13545 -2.85742e-06 0.224474 -0.13575 -2.85742e-06 0.224474 -0.135481 -0.00585676 0.224774 -0.13662 -0.00860698 0.224774 -0.138782 -0.00985526 0.224474 -0.139402 -0.010219 0.224474 -0.139432 -0.0104615 0.224774 -0.139123 -0.0105703 0.224474 -0.00456827 -0.0104615 0.224774 -0.00486827 -0.0104615 0.224774 -0.00738037 -0.00860698 0.224474 -0.00851938 -0.00585676 0.224774 -0.00883037 -0.0060955 0.224774 -0.00855004 -2.85742e-06 0.224474 -0.00723037 0.00834145 0.224774 -0.00871112 0.00691283 0.224474 -0.00818203 0.00738979 0.224774 -0.00820798 0.00788491 0.224774 -0.00521827 0.00984955 0.224774 -0.00486827 0.0104558 0.221116 -0.00483515 -0.0101419 0.220747 -0.00513839 -0.010131 0.221358 -0.00506827 -0.00959545 0.220777 -0.00506242 -0.0101873 0.221394 -0.00484988 -0.00976584 0.220803 -0.00500047 -0.0102599 0.220321 -0.00622821 -0.00950017 0.219603 -0.00805048 -0.00827661 0.219471 -0.00836403 -0.00787397 0.220082 -0.00810062 -0.00752729 0.219953 -0.00833826 -0.00707634 0.219366 -0.00860346 -0.00743945 0.219841 -0.00851561 -0.00637209 0.219215 -0.00884974 -0.00582629 0.21923 -0.00887107 -0.00645641 0.21983 -0.00852666 -0.00623433 0.219219 -0.00886973 -0.00614411 0.219821 -0.00853037 -0.0060955 0.219816 -0.00851938 -0.00585676 0.219215 -0.00880348 0.00529499 0.219829 -0.00852684 0.00622513 0.219817 -0.00852754 0.00596874 0.219215 -0.00884974 0.00582058 0.21923 -0.00887107 0.00645069 0.21997 -0.00830869 0.00714029 0.220931 -0.00615878 0.00896014 0.220321 -0.00622821 0.00949446 0.221358 -0.00506827 0.00958974 0.220747 -0.00513839 0.0101253 0.220777 -0.00506237 0.0101817 0.221399 -0.00482335 0.00978862 0.221409 -0.00476988 0.00985363 0.221112 -0.138932 0.00958974 0.220745 -0.13889 0.00991066 0.220686 -0.137841 0.00896015 0.22032 -0.1378 0.00928043 0.219721 -0.136267 0.00833131 0.220269 -0.13677 0.00834145 0.21995 -0.136067 0.00774806 0.219314 -0.135328 0.00675901 0.219628 -0.13547 0.00605631 0.219271 -0.13526 -0.0062805 0.219678 -0.135531 -0.00665756 0.21939 -0.135485 -0.00725312 0.219611 -0.135998 -0.00806933 0.219902 -0.136728 -0.00866623 0.220775 -0.138966 -0.009968 0.221194 -0.139242 -0.00987488 0.228674 -0.11058 -0.0257813 0.228674 -0.0878069 -0.0249105 0.228674 -0.0977785 -0.038583 0.228674 -0.081116 -0.028059 0.228674 -0.0427327 -0.00370019 0.228674 -0.0256 -2.85742e-06 0.228674 -0.0264916 0.00904933 0.228674 -0.048134 0.0173368 0.228674 -0.029132 0.0177537 0.228674 -0.0334199 0.0257756 0.228674 -0.048134 -0.0173425 0.228674 -0.0264916 -0.00905505 0.228674 -0.0878069 0.0249048 0.228674 -0.0738524 -0.0294446 0.228674 -0.072 -0.0464029 0.228674 -0.0664723 -0.0289803 0.228674 -0.11058 0.0257756 0.228674 -0.114868 0.0177537 0.228674 -0.1015 -2.85742e-06 0.228674 -0.114868 -0.0177594 0.228674 -0.0462216 0.0385773 0.228674 -0.0594396 0.0266895 0.228674 -0.0629479 0.0455056 0.228674 -0.0738524 0.0294389 0.228674 -0.072 0.0463971 0.228738 -0.139429 -0.0105397 0.229748 -0.138956 -0.0104936 0.228738 -0.139432 -0.0104615 0.229756 -0.138941 -0.0104461 0.228745 -0.139376 -0.010131 0.228751 -0.139298 -0.00996146 0.228757 -0.139213 -0.00983777 0.229202 -0.137841 -0.00896583 0.230628 -0.136715 -0.00912284 0.231317 -0.135084 -0.00690249 0.230836 -0.13619 -0.00874824 0.230376 -0.13575 -2.85742e-06 0.231383 -0.13528 -2.85742e-06 0.231383 -0.135013 -0.00581361 0.230628 -0.136715 0.00911713 0.229621 -0.13677 0.00834145 0.230997 -0.135798 0.00834278 0.229877 -0.136282 0.00797768 0.230147 -0.135796 0.00735166 0.230316 -0.135527 0.00663219 0.231377 -0.134998 0.00614563 0.231383 -0.135013 0.0058079 0.229202 -0.137841 0.00896012 0.23021 -0.137786 0.0097386 0.228776 -0.138932 0.00958974 0.229783 -0.138876 0.0103704 0.228759 -0.13919 0.00980421 0.229756 -0.138941 0.0104404 0.228751 -0.139298 0.00995572 0.229748 -0.138956 0.0104879 0.228741 -0.00458455 0.0102761 0.229748 -0.00504441 0.0104879 0.229756 -0.00505915 0.0104404 0.228751 -0.00469913 0.00996121 0.229783 -0.00512417 0.0103704 0.229202 -0.00615881 0.00896012 0.23037 -0.00853037 0.00608979 0.230836 -0.00781045 0.00874255 0.230628 -0.00728551 0.00911713 0.230376 -0.00825004 -2.85742e-06 0.231383 -0.00898724 -0.00581361 0.230134 -0.0081809 -0.00739746 0.23126 -0.0088019 -0.00729484 0.230997 -0.00820241 -0.00834835 0.229771 -0.00751826 -0.00815429 0.229202 -0.00615881 -0.00896583 0.229768 -0.00508675 -0.010406 0.228759 -0.00480956 -0.00981005 0.228739 -0.00456885 -0.0104274 0.228738 -0.00458044 -0.010617 0.225074 -0.00476982 -0.00985942 0.224774 -0.00500936 -0.01004 0.224774 -0.00488917 -0.0102917 0.225074 -0.00459813 -0.010219 0.225074 -0.00458044 -0.010617 0.225074 -0.00506827 -0.00959545 0.224774 -0.00881811 -0.00582921 0.225074 -0.00851938 -0.00585676 0.224774 -0.00883037 0.00608979 0.225074 -0.00723037 0.00834145 0.224774 -0.00738037 0.00860126 0.224774 -0.00488917 0.010286 0.224774 -0.00500936 0.0100343 0.225074 -0.00476982 0.0098537 0.225074 -0.00506827 0.00958974 0.225074 -0.13677 0.00834145 0.225074 -0.13547 0.00608979 0.225074 -0.135481 -0.00585676 0.224774 -0.135182 -0.00582921 0.225074 -0.139432 -0.0104615 0.228738 -0.139432 0.0104558 0.228741 -0.139414 0.0102677 0.225074 -0.139298 0.00995576 0.225074 -0.138932 0.00958974 0.228746 -0.0046365 -0.0100985 0.228776 -0.00506827 -0.00959545 0.228776 -0.00506827 0.00958974 0.228765 -0.00491144 0.00970173 0.225074 -0.00459813 0.0102132 0.229621 -0.13677 -0.00834717 0.225074 -0.13677 -0.00834717 0.225074 -0.138932 -0.00959545 0.230372 -0.13547 -0.00604701 0.230266 -0.135601 -0.00691173 0.225074 -0.13547 -0.0060955 0.225074 -0.135818 -0.0073955 0.229998 -0.13606 -0.00774532 0.230376 -0.135481 -0.00585676 0.230376 -0.135481 0.00585104 0.225074 -0.135577 0.00682769 0.225074 -0.135818 0.00738979 0.230015 -0.13603 0.00770176 0.225074 -0.00723037 -0.00834717 0.230376 -0.00851938 -0.00585676 0.225074 -0.00842346 0.00682769 0.225074 -0.00797236 0.00769921 0.230266 -0.00839892 0.00690601 0.229998 -0.00793987 0.00773961 0.229621 -0.00723037 0.00834145 0.225074 -0.00851938 0.00585104 0.225074 -0.00825004 -2.85742e-06 0.236674 -0.0223599 0.00927649 0.236974 -0.0226548 0.00922137 0.236674 -0.0249102 0.0182398 0.236974 -0.0349018 0.0338167 0.236674 -0.041567 0.040297 0.236674 -0.0581801 0.0485693 0.236974 -0.0582622 0.0482808 0.236974 -0.0673682 0.049983 0.236674 -0.0673405 0.0502817 0.236674 -0.0766596 0.0502817 0.236974 -0.0766319 0.049983 0.236674 -0.0945098 0.0452029 0.236974 -0.0943761 0.0449343 0.236674 -0.102433 0.040297 0.236974 -0.109098 0.0338167 0.236674 -0.114936 0.026582 0.236674 -0.12164 0.00927649 0.236674 -0.1225 -2.85742e-06 0.238174 -0.12 -2.85742e-06 0.238474 -0.1203 -2.85742e-06 0.238174 -0.119078 -0.00936719 0.238474 -0.116623 -0.0184865 0.238174 -0.111911 -0.0266702 0.238474 -0.11216 -0.0268369 0.238174 -0.105941 -0.033944 0.238174 -0.0903688 -0.0443491 0.238474 -0.072 -0.0483029 0.238174 -0.072 -0.0480029 0.238474 -0.0535164 -0.0446262 0.238474 -0.0378468 -0.0341561 0.238474 -0.0318401 -0.0268369 0.238174 -0.0249223 -0.00936719 0.238474 -0.0246281 -0.00942572 0.230474 -0.117312 -0.00901603 0.230674 -0.117508 -0.00905505 0.230474 -0.110414 -0.0256702 0.230474 -0.104668 -0.0326712 0.230674 -0.0977785 -0.038583 0.230674 -0.0897566 -0.0428709 0.230674 -0.0810522 -0.0455113 0.230474 -0.072 -0.0462029 0.230674 -0.072 -0.0464029 0.230474 -0.0463327 -0.0384168 0.230674 -0.0542435 -0.0428709 0.230674 -0.0462216 -0.038583 0.230474 -0.0393317 -0.0326712 0.230674 -0.0391903 -0.0328126 0.230674 -0.0334199 -0.0257813 0.230674 -0.029132 -0.0177594 0.230474 -0.0266878 -0.00901603 0.230674 -0.0264916 -0.00905505 0.230474 -0.0258 -2.85742e-06 0.228874 -0.0266878 -0.00901603 0.228674 -0.029132 -0.0177594 0.228874 -0.0335861 -0.0256702 0.228674 -0.0334199 -0.0257813 0.228874 -0.0463327 -0.0384168 0.228674 -0.0391903 -0.0328126 0.228674 -0.0462216 -0.038583 0.228874 -0.0629869 -0.0453151 0.228674 -0.0542435 -0.0428709 0.228674 -0.0629479 -0.0455113 0.228674 -0.0810522 -0.0455113 0.228674 -0.0897566 -0.0428709 0.228874 -0.08968 -0.0426861 0.228674 -0.10481 -0.0328126 0.228874 -0.114683 -0.0176828 0.228674 -0.117508 -0.00905505 0.237674 -0.0140441 0.0102163 0.237874 -0.0142411 0.0101816 0.237674 -0.0269183 0.0378252 0.237874 -0.0212077 0.0293221 0.237874 -0.0270715 0.0376966 0.237874 -0.0519406 0.0551101 0.237674 -0.0617808 0.0579531 0.237874 -0.0618156 0.0577561 0.237674 -0.072 0.0588471 0.237874 -0.072 0.0586471 0.237874 -0.116929 0.0376966 0.237674 -0.122966 0.0294221 0.237874 -0.128971 -0.0100484 0.237674 -0.126173 -0.0197203 0.237674 -0.109057 -0.0441653 0.237874 -0.109185 -0.0443185 0.237674 -0.0917175 -0.0541761 0.237874 -0.072 -0.0578529 0.237674 -0.0522826 -0.0541761 0.237874 -0.0276844 -0.0371881 0.237674 -0.0178268 -0.0197203 0.237674 -0.0152259 -0.0100137 0.237874 -0.0176388 -0.0197887 0.237674 -0.01435 -2.85742e-06 0.237874 -0.01415 -2.85742e-06 0.236674 -0.127194 -0.0103204 0.236874 -0.11991 -0.0296673 0.236674 -0.105838 -0.0448115 0.236674 -0.0970282 -0.0502663 0.236674 -0.0873662 -0.0540094 0.236874 -0.0874209 -0.0542017 0.236874 -0.0771994 -0.0561125 0.236874 -0.0668007 -0.0561125 0.236674 -0.0469718 -0.0502663 0.236674 -0.0305047 -0.0378309 0.236874 -0.0303569 -0.0379656 0.236674 -0.0196417 -0.0202866 0.236674 -0.0168061 -0.0103204 0.238474 -0.0223413 -2.85742e-06 0.238274 -0.0230993 0.0097241 0.238474 -0.0232955 0.00968508 0.238274 -0.030544 0.0276972 0.238474 -0.0261214 0.0190007 0.238474 -0.0307103 0.0275861 0.238274 -0.0367446 0.0352526 0.238474 -0.036886 0.0351112 0.238474 -0.0444111 0.0412869 0.238274 -0.0443 0.0414532 0.238274 -0.0529199 0.0460606 0.238474 -0.081688 0.0487017 0.238274 -0.0910802 0.0460606 0.238474 -0.0910036 0.0458758 0.238274 -0.107255 0.0352526 0.238474 -0.11329 0.0275861 0.238274 -0.120901 0.0097241 0.228738 -0.0266959 0.0510422 0.228738 -0.041935 0.0612683 0.229745 -0.0447731 0.0620684 0.229745 -0.034232 0.0562797 0.228743 -0.0508478 0.0648016 0.228749 -0.0510523 0.0647622 0.22975 -0.0506623 0.0643161 0.228763 -0.0513531 0.0646117 0.229785 -0.0507758 0.0642536 0.229808 -0.0508045 0.0641959 0.229745 -0.0505941 0.0643084 0.229745 -0.0270078 0.0506908 0.22975 -0.0269671 0.0506357 0.228741 -0.0264861 0.0507809 0.228751 -0.0263744 0.050465 0.229765 -0.0269524 0.0505703 0.228756 -0.0263602 0.050324 0.228765 -0.0263734 0.0501297 0.229785 -0.0269644 0.0505061 0.229484 -0.0522143 0.0622473 0.229808 -0.0270001 0.0504524 0.228801 -0.0266526 0.0495872 0.229484 -0.0580099 0.0638003 0.230492 -0.058744 0.064376 0.230455 -0.0577601 0.0616139 0.231496 -0.058361 0.0614736 0.231811 -0.0573915 0.0603598 0.230774 -0.0570717 0.0607523 0.230913 -0.056198 0.0602272 0.231911 -0.0565834 0.0598751 0.231929 -0.0560035 0.0596704 0.231908 -0.055377 0.0595577 0.231809 -0.0544581 0.0595787 0.230739 -0.0543972 0.0601102 0.231742 -0.0540702 0.0596545 0.23047 -0.0535608 0.060456 0.230191 -0.0529891 0.0609041 0.231414 -0.0528265 0.0602123 0.230092 -0.0528314 0.0610749 0.23097 -0.0518485 0.0611804 0.230492 -0.0512907 0.0623789 0.230492 -0.0228744 0.0436666 0.229625 -0.0239641 0.0438119 0.230092 -0.0248606 0.0433077 0.231365 -0.0251196 0.0425748 0.231414 -0.0252878 0.0425582 0.230739 -0.026699 0.0432552 0.231809 -0.0270175 0.0428253 0.231908 -0.0278238 0.0432666 0.230891 -0.0275097 0.0436293 0.231929 -0.02831 0.0436774 0.230913 -0.0282 0.0442569 0.230884 -0.0284028 0.0445419 0.230599 -0.028843 0.0458049 0.230455 -0.0288596 0.0462389 0.231496 -0.0294501 0.0464178 0.231115 -0.0292476 0.0476474 0.229997 -0.0286092 0.0473396 0.229484 -0.0279826 0.0482572 0.229808 -0.0215447 0.0449971 0.228801 -0.02241 0.0453446 0.22975 -0.0583197 0.0663679 0.228738 -0.0582881 0.0668555 0.228751 -0.057721 0.0665164 0.229808 -0.0582566 0.0661927 0.229765 -0.0214269 0.0450448 0.228781 -0.0221355 0.045539 0.229785 -0.0214911 0.0450327 0.22874 -0.0211665 0.0454814 0.22975 -0.0213616 0.0450301 0.228738 -0.0663272 0.068011 0.229745 -0.0674332 0.0676233 0.228738 -0.0674016 0.068092 0.228738 -0.0765985 0.068092 0.228738 -0.0776729 0.068011 0.229745 -0.0775973 0.0675458 0.229745 -0.0765669 0.0676233 0.229745 -0.00768879 0.021403 0.228738 -0.00724299 0.0215514 0.228738 -0.0107289 0.0300622 0.229745 -0.0123892 0.0322569 0.228738 -0.0153274 0.038027 0.229745 -0.0213064 0.0449894 0.228738 -0.0178928 0.041596 0.228801 -0.086477 0.0656171 0.228785 -0.0865111 0.0658759 0.228741 -0.0860399 0.0667247 0.22975 -0.00768111 0.021335 0.229765 -0.00770104 0.021271 0.229785 -0.00774359 0.0212214 0.229484 -0.0859902 0.0638003 0.230654 -0.0925689 0.0619551 0.230492 -0.0927094 0.0623789 0.230653 -0.0899189 0.0602065 0.231496 -0.0909265 0.0600568 0.230455 -0.0904763 0.0604788 0.23171 -0.0861832 0.0607456 0.230739 -0.0868121 0.060858 0.231767 -0.0897958 0.0596236 0.230774 -0.0894493 0.0600768 0.230913 -0.0884301 0.060059 0.231811 -0.08953 0.059577 0.231929 -0.0879832 0.059674 0.230891 -0.0875414 0.060343 0.231742 -0.086301 0.0606268 0.230492 -0.0852561 0.064376 0.23047 -0.0862606 0.0615757 0.231365 -0.0854331 0.0618856 0.230092 -0.0859384 0.0624764 0.229848 -0.085888 0.0630238 0.231365 -0.0101116 0.0134302 0.230191 -0.00974759 0.0139867 0.23047 -0.0104215 0.0142577 0.231414 -0.0102655 0.0135 0.23171 -0.0112516 0.0141803 0.230739 -0.0111392 0.0148092 0.231809 -0.0116299 0.0145962 0.230801 -0.0113294 0.0150279 0.231908 -0.0121076 0.0153815 0.230891 -0.0116542 0.0155385 0.231929 -0.0123232 0.0159803 0.230921 -0.0118698 0.0161034 0.231767 -0.0123736 0.0177929 0.230774 -0.0119204 0.0174464 0.231496 -0.0119404 0.0189236 0.230455 -0.0115184 0.0184734 0.23019 -0.0110918 0.0190093 0.229997 -0.0107512 0.0193015 0.230492 -0.00961831 0.0207065 0.229808 -0.0931956 0.0641959 0.228765 -0.0926028 0.0645773 0.22975 -0.00562936 0.0136776 0.228763 -0.00571876 0.0144236 0.228781 -0.00604517 0.0145053 0.228801 -0.00638008 0.0144741 0.22874 -0.00523475 0.0139709 0.229745 -0.099227 0.0620684 0.228738 -0.0995847 0.0624243 0.229745 -0.101858 0.0608465 0.228738 -0.102065 0.0612683 0.229745 -0.109072 0.0567404 0.228738 -0.109545 0.056992 0.229745 -0.109768 0.0562797 0.229745 -0.116992 0.0506908 0.229785 -0.117036 0.0505061 0.228801 -0.117347 0.0495872 0.228763 -0.117634 0.050185 0.228758 -0.11764 0.0502943 0.22975 -0.117033 0.0506356 0.228745 -0.117584 0.0506253 0.228738 -0.117304 0.0510422 0.229745 -0.00560192 -0.0136204 0.228738 -0.00514165 -0.0137148 0.22975 -0.00562928 -0.0136832 0.229765 -0.00567854 -0.0137287 0.229808 -0.117 0.0504524 0.229808 -0.00580448 -0.0137463 0.230654 -0.120792 0.0433698 0.229484 -0.12026 0.0440145 0.230455 -0.118242 0.0431376 0.231767 -0.117225 0.0427373 0.230774 -0.117151 0.043303 0.231908 -0.11527 0.0441734 0.230739 -0.115258 0.0452981 0.230491 -0.115139 0.0461359 0.231534 -0.114553 0.0462713 0.231365 -0.114578 0.0468776 0.230009 -0.11538 0.0473136 0.230965 -0.0108056 -0.0201622 0.229625 -0.0100374 -0.0196958 0.230191 -0.0110931 -0.0190138 0.231411 -0.0117771 -0.0191877 0.23047 -0.0115412 -0.0184421 0.23174 -0.0123395 -0.0179458 0.230891 -0.0119683 -0.0167165 0.231929 -0.0123268 -0.0159994 0.231769 -0.0114722 -0.0144135 0.230774 -0.0112449 -0.0149311 0.231499 -0.0105342 -0.013648 0.229997 -0.00930479 -0.0139092 0.229484 -0.00819692 -0.013993 0.230659 -0.00807166 -0.0131667 0.230492 -0.00961831 -0.0207122 0.228765 -0.122133 0.0456238 0.228784 -0.121816 0.0455138 0.228743 -0.00719553 -0.0211552 0.229765 -0.00770107 -0.0212766 0.228781 -0.00762736 -0.0204159 0.228801 -0.00793299 -0.0202754 0.229808 -0.00780127 -0.0211984 0.22975 -0.00768112 -0.0213406 0.229745 -0.00768879 -0.0214088 0.229745 -0.125488 0.0416286 0.228738 -0.126107 0.041596 0.229745 -0.128283 0.0377652 0.228738 -0.132251 0.0320577 0.228738 -0.133271 0.0300622 0.229745 -0.136108 0.0220053 0.229745 -0.018512 -0.0416343 0.228738 -0.020955 -0.045307 0.228738 -0.0178928 -0.0416017 0.228738 -0.0153274 -0.0380327 0.229745 -0.0157175 -0.0377709 0.229745 -0.0123892 -0.0322626 0.229745 -0.0111507 -0.0298609 0.228801 -0.136067 0.0202697 0.229765 -0.136299 0.0212709 0.22975 -0.136319 0.0213349 0.228749 -0.136765 0.0209447 0.228741 -0.136808 0.0212356 0.228738 -0.136757 0.0215514 0.229745 -0.0213064 -0.0449951 0.22975 -0.0213614 -0.0450358 0.228751 -0.0215322 -0.0456285 0.228757 -0.0216895 -0.0456431 0.228765 -0.0218675 -0.0456295 0.228784 -0.0221846 -0.0455195 0.230492 -0.0228744 -0.0436724 0.229997 -0.134695 0.0139035 0.229484 -0.135803 0.0139873 0.230771 -0.132082 0.0174608 0.231908 -0.131561 0.0166202 0.230891 -0.132032 0.0167108 0.231811 -0.132363 0.0146057 0.231767 -0.132536 0.0143988 0.230774 -0.132755 0.0149254 0.230615 -0.133204 0.0145019 0.230455 -0.133617 0.014237 0.231742 -0.131657 0.017927 0.23171 -0.131701 0.0180884 0.230474 -0.132454 0.0184277 0.230324 -0.132686 0.0187616 0.231365 -0.132314 0.019308 0.229928 -0.133375 0.0193896 0.229484 -0.13425 0.0197829 0.230965 -0.0290838 -0.0480586 0.230092 -0.0286895 -0.0471422 0.231411 -0.0294379 -0.0467289 0.230191 -0.0287585 -0.0469203 0.231534 -0.0294473 -0.0462777 0.231707 -0.0293461 -0.0455343 0.230739 -0.028742 -0.0453038 0.231908 -0.028738 -0.0441896 0.231929 -0.0283198 -0.0436929 0.231911 -0.0278624 -0.0433002 0.230921 -0.0279865 -0.0440241 0.230774 -0.0268486 -0.0433087 0.231769 -0.0267867 -0.0427468 0.230455 -0.0257583 -0.0431433 0.23019 -0.0250809 -0.0432449 0.229997 -0.0246575 -0.0433937 0.230659 -0.0232184 -0.0433673 0.229484 -0.02374 -0.0440203 0.22975 -0.138371 0.0136775 0.228738 -0.138858 0.0137091 0.228741 -0.138737 0.0140215 0.228751 -0.138519 0.0142762 0.229808 -0.138196 0.0137406 0.228781 -0.0264582 -0.0498674 0.228801 -0.0266526 -0.0495929 0.229745 -0.0270078 -0.0506965 0.228738 -0.0444154 -0.06243 0.228738 -0.041935 -0.061274 0.229745 -0.034232 -0.0562854 0.22975 -0.138371 -0.0136833 0.229785 -0.13826 -0.0137504 0.228801 -0.13762 -0.0144798 0.229808 -0.138196 -0.0137463 0.229745 -0.138398 -0.0136204 0.228738 -0.138858 -0.0137148 0.229745 -0.0505941 -0.0643141 0.22975 -0.0506622 -0.0643218 0.229765 -0.0507262 -0.0643019 0.228757 -0.05125 -0.0646837 0.228765 -0.0513973 -0.064583 0.229785 -0.0507758 -0.0642593 0.228801 -0.0517275 -0.0640699 0.229484 -0.135803 -0.013993 0.229484 -0.0522143 -0.0622531 0.229808 -0.0508045 -0.0642016 0.231119 -0.13284 -0.0198845 0.231929 -0.131677 -0.015986 0.230917 -0.132196 -0.0158986 0.230921 -0.13213 -0.0161091 0.231911 -0.131565 -0.0165785 0.230871 -0.132027 -0.0168908 0.231811 -0.13158 -0.0175328 0.230581 -0.132303 -0.0181486 0.231499 -0.132054 -0.0189187 0.230455 -0.132482 -0.0184792 0.231908 -0.131898 -0.0153755 0.231809 -0.13237 -0.0146019 0.23081 -0.132644 -0.0150678 0.23174 -0.132639 -0.0142941 0.231707 -0.132758 -0.0141765 0.231482 -0.133521 -0.0136163 0.231361 -0.133901 -0.0134306 0.230112 -0.134435 -0.0139497 0.229977 -0.13474 -0.0139045 0.230492 -0.136379 -0.0132589 0.230492 -0.058744 -0.0643817 0.230965 -0.0588613 -0.0630785 0.229625 -0.0580733 -0.0635105 0.230092 -0.0580617 -0.062482 0.231361 -0.0585723 -0.0619038 0.230191 -0.0580105 -0.0622553 0.23047 -0.0577394 -0.0615814 0.231809 -0.057401 -0.060373 0.231908 -0.0566274 -0.0599007 0.230801 -0.0569693 -0.0606735 0.231929 -0.0560169 -0.0596797 0.230913 -0.05557 -0.0600647 0.231769 -0.0542161 -0.0596268 0.230455 -0.0535237 -0.0604845 0.231119 -0.0521184 -0.0608432 0.230659 -0.0514361 -0.0619484 0.230492 -0.134382 -0.0207122 0.22975 -0.136319 -0.0213407 0.228757 -0.136684 -0.0207591 0.229785 -0.136257 -0.0212271 0.229808 -0.136199 -0.0211984 0.228743 -0.0579162 -0.0667014 0.22975 -0.0583196 -0.0663735 0.228749 -0.0577588 -0.0665649 0.229785 -0.0582525 -0.0662627 0.228781 -0.0574919 -0.0659577 0.229745 -0.125488 -0.0416343 0.229745 -0.122694 -0.0449951 0.229745 -0.0856176 -0.066401 0.228738 -0.085712 -0.0668612 0.228738 -0.0776729 -0.0680167 0.228738 -0.0674016 -0.0680978 0.229745 -0.0583825 -0.066401 0.229745 -0.0765669 -0.067629 0.228749 -0.122524 -0.0456172 0.228763 -0.122188 -0.0456372 0.229765 -0.122573 -0.0450505 0.228801 -0.12159 -0.0453503 0.229785 -0.122509 -0.0450385 0.22975 -0.122639 -0.0450358 0.22874 -0.122834 -0.0454871 0.228741 -0.0860245 -0.0667398 0.228744 -0.0861252 -0.0666709 0.228765 -0.0864458 -0.0662372 0.228777 -0.086502 -0.0660161 0.229785 -0.0857475 -0.0662627 0.229808 -0.0857435 -0.0661984 0.228785 -0.0865111 -0.0658816 0.229484 -0.12026 -0.0440203 0.230492 -0.0852561 -0.0643817 0.229484 -0.0859902 -0.063806 0.229484 -0.116017 -0.0482629 0.229997 -0.115391 -0.0473454 0.231483 -0.11455 -0.0464685 0.231499 -0.11455 -0.0464112 0.230491 -0.115139 -0.0461416 0.230849 -0.115464 -0.0447824 0.231811 -0.114833 -0.0449742 0.231911 -0.115297 -0.0441405 0.230921 -0.115945 -0.0440956 0.23086 -0.116712 -0.0435025 0.231908 -0.116187 -0.0432649 0.231809 -0.116983 -0.042831 0.23174 -0.117369 -0.042699 0.230638 -0.117675 -0.0431777 0.230461 -0.118224 -0.0431428 0.231707 -0.117532 -0.0426568 0.231411 -0.118726 -0.042565 0.231361 -0.118894 -0.0425821 0.229752 -0.0915843 -0.0617143 0.230965 -0.0921594 -0.0611973 0.230492 -0.0927094 -0.0623846 0.229484 -0.0917858 -0.0622531 0.231361 -0.0913217 -0.0603245 0.230318 -0.0907754 -0.0606976 0.230462 -0.0904599 -0.0604743 0.231411 -0.0911849 -0.0602258 0.230654 -0.0899182 -0.060212 0.23174 -0.089943 -0.0596634 0.231809 -0.089542 -0.0595844 0.231908 -0.0886358 -0.0595622 0.231929 -0.0879966 -0.0596761 0.231911 -0.0874279 -0.0598758 0.230919 -0.0879462 -0.0601812 0.231891 -0.0871794 -0.0599962 0.230691 -0.0866771 -0.0610017 0.230659 -0.0851639 -0.0639312 0.230492 -0.11567 -0.0491285 0.228801 -0.117347 -0.0495929 0.229745 -0.116992 -0.0506965 0.22975 -0.117033 -0.0506415 0.228794 -0.117421 -0.0496749 0.228743 -0.0931523 -0.0648074 0.228749 -0.0929478 -0.0647679 0.228781 -0.092413 -0.0643755 0.228801 -0.0922726 -0.0640699 0.229745 -0.0934059 -0.0643141 0.229745 -0.099227 -0.0620741 0.228738 -0.0995847 -0.06243 0.229745 -0.101858 -0.0608522 0.228738 -0.109545 -0.0569977 0.226274 -0.117304 -0.0510479 0.226297 -0.117449 -0.0508887 0.226361 -0.117552 -0.05071 0.226274 -0.123045 -0.045307 0.226295 -0.138796 -0.013912 0.226274 -0.138858 -0.0137148 0.226274 -0.136757 0.0215514 0.226295 -0.138796 0.0139067 0.226325 -0.136808 0.0212356 0.226295 -0.122892 0.0454411 0.226355 -0.122721 0.0455433 0.226574 -0.117639 0.0503385 0.226274 -0.118468 0.0499847 0.226297 -0.117449 0.0508823 0.226574 -0.0863542 0.0664137 0.226274 -0.0888618 0.0661314 0.226274 -0.085712 0.0668555 0.226274 -0.0582881 0.0668555 0.226355 -0.0579162 0.0666957 0.226355 -0.0508477 0.0648017 0.226295 -0.0506477 0.0647989 0.226274 -0.0551383 0.0661314 0.226295 -0.026556 0.0508894 0.226574 -0.0263607 0.0503385 0.226295 -0.0211075 0.0454409 0.226295 -0.00520392 0.0139063 0.226355 -0.00530153 -0.0140867 0.226355 -0.00719553 -0.0211552 0.226295 -0.00719832 -0.0213552 0.226355 -0.0212793 -0.0455491 0.226274 -0.0255317 -0.0499904 0.226355 -0.0264538 -0.0507236 0.226295 -0.0265563 -0.0508954 0.226355 -0.0508477 -0.0648074 0.226574 -0.0512228 -0.0646984 0.226274 -0.0551383 -0.0661371 0.226295 -0.0580909 -0.066799 0.226574 -0.11764 -0.0503 0.228741 -0.117514 -0.0507865 0.228754 -0.117637 -0.0503859 0.228758 -0.11764 -0.0503 0.228738 -0.117304 -0.0510479 0.226574 -0.117639 -0.0503442 0.226574 -0.122341 -0.0456422 0.226574 -0.121928 -0.0455726 0.228781 -0.121865 -0.0455447 0.226574 -0.12159 -0.0453503 0.226355 -0.122721 -0.0455491 0.228743 -0.122721 -0.0455491 0.226295 -0.122893 -0.0454466 0.228738 -0.123045 -0.045307 0.228763 -0.138281 -0.0144293 0.228781 -0.137955 -0.014511 0.228749 -0.138562 -0.0142441 0.228743 -0.138699 -0.0140867 0.22874 -0.138765 -0.0139766 0.226355 -0.138699 -0.0140867 0.226274 -0.138858 0.0137091 0.228757 -0.13839 0.0143675 0.226574 -0.138024 0.0144976 0.226355 -0.138699 0.014081 0.228765 -0.138229 0.0144447 0.228784 -0.1379 0.014508 0.228801 -0.13762 0.0144741 0.226574 -0.13762 0.0144741 0.226544 -0.136715 0.020813 0.228754 -0.136715 0.020813 0.228763 -0.136614 0.020644 0.226574 -0.136451 0.0204696 0.228781 -0.136373 0.0204101 0.228738 -0.123045 0.0453013 0.228757 -0.122311 0.0456374 0.228751 -0.122468 0.0456228 0.228741 -0.122784 0.0455111 0.226574 -0.121928 0.0455669 0.228801 -0.12159 0.0453446 0.226574 -0.12159 0.0453446 0.226574 -0.117564 0.0499116 0.228781 -0.117542 0.0498616 0.228757 -0.0927501 0.064678 0.226574 -0.0927645 0.0646859 0.228751 -0.0928936 0.064744 0.226355 -0.0931524 0.0648017 0.228741 -0.0932231 0.0648053 0.226295 -0.093352 0.0647989 0.226574 -0.0924543 0.0644259 0.228784 -0.0923832 0.0643235 0.226295 -0.0580905 0.0667931 0.226574 -0.0574996 0.0660212 0.228756 -0.0576382 0.0664014 0.228741 -0.0579757 0.0667341 0.228765 -0.0575525 0.0662266 0.228784 -0.0574892 0.0658969 0.228801 -0.0575231 0.0656171 0.228781 -0.051587 0.0643698 0.228801 -0.0517275 0.0640642 0.22874 -0.050719 0.0648045 0.228738 -0.0504458 0.0647542 0.226274 -0.0504458 0.0647542 0.226574 -0.0263602 0.0503241 0.226355 -0.0264538 0.0507178 0.228784 -0.0264834 0.0498126 0.228763 -0.021812 0.0456315 0.226574 -0.0220718 0.0455669 0.228749 -0.0214763 0.0456114 0.228743 -0.0212794 0.0455433 0.226355 -0.0212793 0.0455433 0.228738 -0.020955 0.0453013 0.226295 -0.00719827 0.0213491 0.228765 -0.0074199 0.0205999 0.228756 -0.00731131 0.0207616 0.228751 -0.00725316 0.0208907 0.226574 -0.00730453 0.0207744 0.228741 -0.00719193 0.0212202 0.226355 -0.00719553 0.0211495 0.228784 -0.00767373 0.0203803 0.226574 -0.00757132 0.0204514 0.228801 -0.00793299 0.0202697 0.226574 -0.00793299 0.0202697 0.226574 -0.005976 0.0144976 0.226574 -0.00558347 0.0143513 0.228749 -0.00543802 0.0142384 0.228743 -0.00530155 0.014081 0.226355 -0.00530153 0.014081 0.226295 -0.00520409 -0.0139124 0.228765 -0.00577062 -0.0144504 0.228757 -0.00560973 -0.0143732 0.228751 -0.0054808 -0.0142819 0.226574 -0.00559572 -0.0143647 0.228741 -0.00526307 -0.0140272 0.226574 -0.00558347 -0.014357 0.226574 -0.005976 -0.0145033 0.228784 -0.00610025 -0.0145137 0.228801 -0.00638008 -0.0144798 0.226574 -0.0073113 -0.0207673 0.226574 -0.00757132 -0.0204571 0.228763 -0.00738553 -0.0206498 0.228749 -0.00723501 -0.0209506 0.226574 -0.00730453 -0.0207801 0.22874 -0.00719272 -0.0212839 0.226274 -0.020955 -0.045307 0.226295 -0.0211078 -0.0454469 0.226574 -0.0216731 -0.0456427 0.228741 -0.0212163 -0.0455168 0.226574 -0.0220718 -0.0455726 0.228801 -0.02241 -0.0453503 0.228763 -0.0263657 -0.0501909 0.226574 -0.0264303 -0.0499311 0.226574 -0.0263607 -0.0503442 0.228749 -0.0263857 -0.0505266 0.228743 -0.0264538 -0.0507235 0.22874 -0.0265158 -0.0508364 0.228738 -0.0504458 -0.0647599 0.228741 -0.050777 -0.064811 0.228751 -0.0511064 -0.0647497 0.226295 -0.0506481 -0.0648046 0.228784 -0.0516169 -0.0643292 0.226574 -0.0515458 -0.0644316 0.226574 -0.0574996 -0.0660269 0.228763 -0.0575736 -0.0662841 0.226574 -0.0575231 -0.0656228 0.228801 -0.0575231 -0.0656228 0.226574 -0.0576459 -0.0664194 0.226355 -0.0579162 -0.0667014 0.22874 -0.0580263 -0.0667682 0.228738 -0.0582881 -0.0668612 0.226274 -0.0582881 -0.0668612 0.224774 -0.119524 -0.0469416 0.226574 -0.119739 -0.0461416 0.226574 -0.119524 -0.0469416 0.224774 -0.118139 -0.0477416 0.224774 -0.117339 -0.0475272 0.226574 -0.117339 -0.0475272 0.224774 -0.116753 -0.0469416 0.226574 -0.116753 -0.0469416 0.224774 -0.136412 -0.0176908 0.226574 -0.136412 -0.0176908 0.226574 -0.135827 -0.0182764 0.224774 -0.134227 -0.0182764 0.226574 -0.135027 -0.0184908 0.226574 -0.134227 -0.0182764 0.226574 -0.136627 0.0168851 0.224774 -0.135827 0.0154994 0.226574 -0.135027 0.0152851 0.226574 -0.134227 0.0154994 0.224774 -0.133427 0.0168851 0.226574 -0.119739 0.0461359 0.224774 -0.118939 0.0447502 0.226574 -0.118939 0.0447502 0.226574 -0.118139 0.0445359 0.224774 -0.117339 0.0447502 0.224774 -0.116753 0.0453359 0.224774 -0.0902736 0.0622238 0.226574 -0.089688 0.0616382 0.224774 -0.089688 0.0616382 0.226574 -0.088888 0.0614238 0.224774 -0.088888 0.0614238 0.226574 -0.088088 0.0616382 0.224774 -0.0567121 0.0630238 0.226574 -0.0543121 0.0616382 0.224774 -0.0537265 0.0622238 0.226574 -0.0537265 0.0622238 0.226574 -0.027247 0.0453359 0.224774 -0.0266613 0.0447502 0.224774 -0.0258613 0.0445359 0.226574 -0.0250613 0.0447502 0.224774 -0.0244757 0.0453359 0.226574 -0.0105734 0.0168851 0.224774 -0.010359 0.0160851 0.226574 -0.00977338 0.0154994 0.224774 -0.00977338 0.0154994 0.224774 -0.00897338 0.0152851 0.224774 -0.00817338 0.0154994 0.226574 -0.00817338 0.0154994 0.224774 -0.00758774 0.0160851 0.226574 -0.0105734 -0.0168908 0.224774 -0.010359 -0.0176908 0.224774 -0.00977338 -0.0182764 0.226574 -0.010359 -0.0176908 0.226574 -0.00817338 -0.0182764 0.224774 -0.00758774 -0.0176908 0.226574 -0.0274613 -0.0461416 0.226574 -0.0273029 -0.0468358 0.224774 -0.0255053 -0.0477015 0.226574 -0.0255053 -0.0477015 0.224774 -0.0244198 -0.0468358 0.226574 -0.0244198 -0.0468358 0.226574 -0.0559121 -0.0644152 0.224774 -0.0551121 -0.0646295 0.226574 -0.0551121 -0.0646295 0.224774 -0.0537265 -0.0638295 0.226574 -0.0517275 -0.0640699 0.229484 -0.0580099 -0.063806 0.226574 -0.0580099 -0.0622531 0.226574 -0.0572334 -0.0609082 0.230739 -0.0571879 -0.0608637 0.230891 -0.0564586 -0.0603487 0.226574 -0.0558886 -0.0601317 0.230921 -0.0558938 -0.0601331 0.230774 -0.0545507 -0.0600825 0.230723 -0.0543323 -0.0601326 0.23019 -0.0529879 -0.0609111 0.229997 -0.0526956 -0.0612517 0.226574 -0.0522143 -0.0622531 0.226574 -0.0567121 -0.0630295 0.226574 -0.0512356 -0.0646916 0.226574 -0.0537265 -0.0638295 0.226574 -0.0543121 -0.0644152 0.226574 -0.0564977 -0.0638295 0.226574 -0.0580099 -0.063806 0.226574 -0.0576382 -0.0664072 0.226574 -0.0559121 -0.0616439 0.226574 -0.0543356 -0.0601317 0.226574 -0.0529908 -0.0609082 0.226574 -0.0535121 -0.0630295 0.226574 -0.116017 -0.0482629 0.229961 -0.119417 -0.0434276 0.226574 -0.119066 -0.0432884 0.230125 -0.119068 -0.0432891 0.230321 -0.1186 -0.0431772 0.230903 -0.116376 -0.0437138 0.23078 -0.117125 -0.0433179 0.226574 -0.117669 -0.0431785 0.226574 -0.116375 -0.0437145 0.226574 -0.115466 -0.0447796 0.230774 -0.115305 -0.0451571 0.226574 -0.118939 -0.0475272 0.226574 -0.122327 -0.0456427 0.226574 -0.118139 -0.0477416 0.226574 -0.115139 -0.0461416 0.226574 -0.116753 -0.0453416 0.226574 -0.12026 -0.0440203 0.229484 -0.13425 -0.0197886 0.228801 -0.136067 -0.0202754 0.226574 -0.13762 -0.0144798 0.226574 -0.135803 -0.013993 0.226574 -0.134433 -0.0139501 0.230328 -0.133927 -0.0140995 0.230895 -0.132326 -0.0155845 0.226574 -0.132325 -0.0155862 0.23062 -0.133192 -0.014517 0.230465 -0.133593 -0.0142554 0.226574 -0.132027 -0.0168908 0.226574 -0.138024 -0.0145033 0.226574 -0.138404 -0.0143647 0.226574 -0.138417 -0.014357 0.226574 -0.13425 -0.0197886 0.226574 -0.133641 -0.0176908 0.226574 -0.133427 -0.0168908 0.226574 -0.132301 -0.0181444 0.226574 -0.133187 -0.0145208 0.226574 -0.135827 -0.0155052 0.226574 -0.136067 0.0202697 0.23008 -0.1331 0.0191847 0.226574 -0.133098 0.0191832 0.226574 -0.132027 0.0168851 0.226574 -0.135827 0.0182707 0.226574 -0.136696 0.0207744 0.226574 -0.138417 0.0143513 0.226574 -0.136412 0.0160851 0.226574 -0.138404 0.014359 0.226574 -0.135803 0.0139873 0.226574 -0.135827 0.0154994 0.226574 -0.134441 0.0139427 0.226574 -0.1332 0.014505 0.226574 -0.133641 0.0160851 0.226574 -0.133427 0.0168851 0.226574 -0.132336 0.0155582 0.226574 -0.133641 0.0176851 0.226574 -0.134227 0.0182707 0.226574 -0.132308 0.0181529 0.226574 -0.135027 0.0184851 0.226574 -0.13425 0.0197829 0.226574 -0.117347 0.0495872 0.229484 -0.116017 0.0482572 0.226574 -0.116017 0.0482572 0.226574 -0.115367 0.0472839 0.229814 -0.115578 0.0476987 0.230279 -0.115193 0.0467018 0.226574 -0.122327 0.045637 0.226574 -0.122341 0.0456365 0.226574 -0.119524 0.0469359 0.226574 -0.118139 0.0477359 0.226574 -0.119524 0.0453359 0.226574 -0.12026 0.0440145 0.226574 -0.119066 0.0432827 0.226574 -0.117339 0.0447502 0.226574 -0.116753 0.0453359 0.226574 -0.115466 0.0447739 0.226574 -0.115139 0.0461359 0.226574 -0.116753 0.0469359 0.226574 -0.11764 0.0502943 0.226574 -0.0917858 0.0622473 0.228801 -0.0922726 0.0640642 0.226574 -0.086477 0.0656171 0.226574 -0.0859902 0.0638003 0.226574 -0.0875023 0.0622238 0.226574 -0.0902736 0.0622238 0.226574 -0.0910998 0.060997 0.226574 -0.090488 0.0630238 0.226574 -0.0922726 0.0640642 0.226574 -0.0902736 0.0638238 0.226574 -0.0927773 0.0646927 0.226574 -0.089688 0.0644094 0.226574 -0.087288 0.0630238 0.226574 -0.085888 0.0630238 0.226574 -0.0580099 0.0638003 0.226574 -0.0575231 0.0656171 0.229625 -0.0523071 0.0619598 0.226574 -0.0558886 0.060126 0.230801 -0.0546817 0.0600548 0.230921 -0.0558833 0.0601246 0.230891 -0.0552863 0.0600289 0.230723 -0.0572359 0.0609049 0.23019 -0.0580109 0.0622513 0.229997 -0.0580937 0.0626923 0.226574 -0.0580099 0.0622473 0.226574 -0.0512228 0.0646927 0.226574 -0.0567121 0.0630238 0.226574 -0.0564977 0.0622238 0.226574 -0.0572334 0.0609025 0.226574 -0.0559121 0.0616382 0.226574 -0.0543356 0.060126 0.226574 -0.0551121 0.0614238 0.226574 -0.0529908 0.0609025 0.226574 -0.0522143 0.0622473 0.226574 -0.0517275 0.0640642 0.226574 -0.0515458 0.0644259 0.226574 -0.0512356 0.0646859 0.226574 -0.0559121 0.0644094 0.226574 -0.0564977 0.0638238 0.226574 -0.0576459 0.0664137 0.226574 -0.0576382 0.0664015 0.226574 -0.02374 0.0440145 0.229484 -0.02374 0.0440145 0.23047 -0.0258017 0.0431365 0.230599 -0.0261938 0.0431543 0.230801 -0.0269731 0.0433495 0.226574 -0.0284015 0.0445398 0.230921 -0.0279788 0.0440107 0.230774 -0.0286942 0.0451485 0.226574 -0.02241 0.0453446 0.226574 -0.0216731 0.045637 0.226574 -0.0216587 0.0456365 0.226574 -0.0279826 0.0482572 0.226574 -0.028693 0.0471267 0.226574 -0.0288425 0.0458 0.226574 -0.0266613 0.0447502 0.226574 -0.0274574 0.0435957 0.226574 -0.0258613 0.0445359 0.226574 -0.0261972 0.0431547 0.226574 -0.0248705 0.0433042 0.226574 -0.0244757 0.0453359 0.226574 -0.0264303 0.0499254 0.226574 -0.0266613 0.0475215 0.226574 -0.0266526 0.0495872 0.229484 -0.00819692 0.0139873 0.229625 -0.00849235 0.0139239 0.230092 -0.00952083 0.0139355 0.230913 -0.0119382 0.0164272 0.226574 -0.0118712 0.0161086 0.230723 -0.0118703 0.0176649 0.229484 -0.00974984 0.0197829 0.226574 -0.00758774 0.0176851 0.226574 -0.00758774 0.0160851 0.226574 -0.00559572 0.014359 0.226574 -0.0073113 0.0207616 0.226574 -0.00897338 0.0184851 0.226574 -0.00977338 0.0182707 0.226574 -0.00974984 0.0197829 0.226574 -0.0110947 0.0190064 0.226574 -0.0118712 0.0176615 0.226574 -0.010359 0.0160851 0.226574 -0.0110947 0.0147638 0.226574 -0.00897338 0.0152851 0.226574 -0.00974984 0.0139873 0.226574 -0.00819692 0.0139873 0.226574 -0.00638008 0.0144741 0.226574 -0.00638008 -0.0144798 0.229484 -0.00974984 -0.0197886 0.230092 -0.0109223 -0.0191715 0.226574 -0.0118712 -0.0176673 0.230739 -0.011887 -0.0176056 0.230801 -0.0119423 -0.0173212 0.230913 -0.01177 -0.0158049 0.230921 -0.0118726 -0.0161196 0.226574 -0.0118712 -0.0161143 0.230723 -0.0110922 -0.014767 0.230455 -0.0103832 -0.0142427 0.23019 -0.00974589 -0.013992 0.226574 -0.00758774 -0.0160908 0.226574 -0.00737338 -0.0168908 0.226574 -0.00758774 -0.0176908 0.226574 -0.00897338 -0.0152908 0.226574 -0.00977338 -0.0155052 0.226574 -0.00819692 -0.013993 0.226574 -0.00974984 -0.013993 0.226574 -0.010359 -0.0160908 0.226574 -0.0110947 -0.0147695 0.226574 -0.0110947 -0.0190121 0.226574 -0.00977338 -0.0182764 0.226574 -0.00974984 -0.0197886 0.226574 -0.00793299 -0.0202754 0.226574 -0.00897338 -0.0184908 0.226574 -0.02374 -0.0440203 0.226574 -0.0266526 -0.0495929 0.229484 -0.0279826 -0.0482629 0.226574 -0.0279826 -0.0482629 0.229625 -0.0281853 -0.0480387 0.226574 -0.0287591 -0.046918 0.23047 -0.0288607 -0.0462011 0.226574 -0.0287591 -0.0453651 0.230801 -0.0286477 -0.0450298 0.230891 -0.0283679 -0.0444932 0.230913 -0.0277403 -0.0438029 0.226574 -0.0279826 -0.0440203 0.230723 -0.0266344 -0.0432429 0.226574 -0.0250849 -0.0432438 0.226376 -0.0861252 -0.0666709 0.226274 -0.0888618 -0.0661371 0.226274 -0.085712 -0.0668612 0.226301 -0.0859345 -0.0667876 0.226574 -0.0863542 -0.0664194 0.228754 -0.0863295 -0.0664563 0.228763 -0.092647 -0.0646174 0.226574 -0.0927645 -0.0646916 0.226574 -0.0922726 -0.0640699 0.226574 -0.0927773 -0.0646984 0.226355 -0.0931524 -0.0648074 0.22874 -0.0932811 -0.0648102 0.226295 -0.0933524 -0.0648046 0.224774 -0.0903295 -0.0637237 0.224774 -0.089244 -0.0645894 0.226574 -0.089244 -0.0645894 0.226574 -0.0885319 -0.0645894 0.224774 -0.0878904 -0.0642805 0.226574 -0.087288 -0.0630295 0.228801 -0.086477 -0.0656228 0.226574 -0.0859902 -0.063806 0.229947 -0.0913687 -0.0613426 0.226574 -0.0910998 -0.0610027 0.230136 -0.0911014 -0.0610044 0.230009 -0.0912875 -0.0612289 0.230907 -0.08852 -0.0600522 0.230849 -0.0890459 -0.0600337 0.226574 -0.089914 -0.0602104 0.230762 -0.0895049 -0.0600936 0.230474 -0.0904306 -0.0604565 0.230803 -0.0870382 -0.0606677 0.230887 -0.0875111 -0.0603641 0.226574 -0.0884964 -0.0600552 0.226574 -0.086227 -0.0616443 0.230011 -0.0859099 -0.0626675 0.230319 -0.0860882 -0.0619518 0.230476 -0.0862681 -0.0615679 0.226574 -0.0924543 -0.0644316 0.226574 -0.0903295 -0.0637237 0.226574 -0.0917858 -0.0622531 0.226574 -0.090488 -0.0630295 0.226574 -0.0902736 -0.0622295 0.226574 -0.0871673 -0.0605721 0.226574 -0.0875023 -0.0622295 0.226574 -0.085888 -0.0630295 0.226574 -0.0874464 -0.0637237 0.226574 -0.0878904 -0.0642805 0.226574 -0.0865111 -0.0658816 0.226574 -0.0864112 -0.0663172 0.226574 -0.0898856 -0.0642805 0.233274 -0.127194 -0.0103204 0.233474 -0.124545 -0.0203588 0.233474 -0.11991 -0.0296673 0.233474 -0.113643 -0.0379656 0.233274 -0.113495 -0.0378309 0.233474 -0.105959 -0.0449711 0.233474 -0.0971174 -0.0504453 0.233274 -0.0873662 -0.0540094 0.233274 -0.0668192 -0.0559133 0.233474 -0.0565791 -0.0542017 0.233274 -0.0469718 -0.0502663 0.233474 -0.0468827 -0.0504453 0.233274 -0.0305047 -0.0378309 0.233474 -0.0303569 -0.0379656 0.233474 -0.0240903 -0.0296673 0.233274 -0.0196417 -0.0202866 0.233474 -0.0194552 -0.0203588 0.236074 -0.01585 -2.85742e-06 0.235874 -0.0166095 -0.0103571 0.236074 -0.0242603 -0.029562 0.235874 -0.0240903 -0.0296673 0.236074 -0.0381621 -0.0448115 0.235874 -0.0303569 -0.0379656 0.236074 -0.0469718 -0.0502663 0.235874 -0.0468827 -0.0504453 0.236074 -0.0566339 -0.0540094 0.235874 -0.0565791 -0.0542017 0.236074 -0.0970282 -0.0502663 0.235874 -0.0971174 -0.0504453 0.235874 -0.105959 -0.0449711 0.236074 -0.124358 -0.0202866 0.235874 -0.124545 -0.0203588 0.236074 -0.127194 -0.0103204 0.235874 -0.127391 -0.0103571 0.233562 -0.021558 -0.0277336 0.233474 -0.128898 -0.00719072 0.233474 -0.01465 -2.85742e-06 0.233497 -0.0185706 -0.0211571 0.233497 -0.0612322 -0.0564498 0.233474 -0.0475816 -0.0518947 0.233474 -0.122256 -0.0276314 0.233497 -0.125429 -0.0211571 0.233659 -0.0253787 -0.0338753 0.233497 -0.0216432 -0.0276867 0.233497 -0.0683918 -0.0573543 0.233474 -0.068399 -0.0572397 0.233562 -0.12552 -0.0211929 0.233474 -0.125323 -0.0211148 0.233474 -0.127548 -0.0142652 0.233659 -0.0184197 -0.0212168 0.233774 -0.021481 -0.027776 0.233659 -0.0299916 -0.0394514 0.233562 -0.0300391 -0.0394068 0.233497 -0.0412089 -0.048522 0.233562 -0.0411567 -0.0486042 0.233562 -0.0474913 -0.0520866 0.233659 -0.0474636 -0.0521455 0.233497 -0.0475327 -0.0519986 0.233774 -0.0611975 -0.0566317 0.233659 -0.0827983 -0.0566093 0.233774 -0.0898149 -0.0548313 0.233659 -0.0898078 -0.0548095 0.233562 -0.0827861 -0.0565454 0.233562 -0.0756144 -0.0574514 0.233474 -0.0827464 -0.056337 0.233497 -0.0827679 -0.0564498 0.233562 -0.0897877 -0.0547477 0.233562 -0.0965088 -0.0520866 0.233474 -0.0897222 -0.054546 0.233497 -0.0964674 -0.0519986 0.233497 -0.0897576 -0.0546551 0.233562 -0.102843 -0.0486042 0.233659 -0.102878 -0.0486591 0.233659 -0.108733 -0.0444053 0.233497 -0.11389 -0.0393402 0.233562 -0.118569 -0.033837 0.233774 -0.0148046 -0.00722832 0.233659 -0.0143729 -2.85742e-06 0.233474 -0.0151023 -0.00719072 0.233497 -0.0149884 -0.00720511 0.233562 -0.0162463 -0.014318 0.233562 -0.0148918 -0.00721731 0.233659 -0.0148273 -0.00722546 0.233774 -0.0152259 -0.0100137 0.233659 -0.0161833 -0.0143342 0.233774 -0.0161612 -0.0143398 0.233474 -0.0164518 -0.0142652 0.233497 -0.0163406 -0.0142938 0.233562 -0.0184801 -0.0211929 0.233659 -0.021501 -0.027765 0.233497 -0.03011 -0.0393402 0.233497 -0.02551 -0.0337798 0.233562 -0.0254313 -0.033837 0.233774 -0.0278376 -0.0370596 0.233774 -0.0411096 -0.0486784 0.233774 -0.0352525 -0.0444229 0.233659 -0.0352671 -0.0444053 0.233774 -0.0349433 -0.0441653 0.233474 -0.0301937 -0.0392616 0.233562 -0.0353086 -0.0443552 0.233497 -0.0353706 -0.0442802 0.233659 -0.0411219 -0.0486591 0.233774 -0.0541852 -0.0548313 0.233659 -0.0541923 -0.0548095 0.233774 -0.043175 -0.0499292 0.233497 -0.0542424 -0.0546551 0.233562 -0.0542124 -0.0547477 0.233659 -0.0612018 -0.0566093 0.233562 -0.061214 -0.0565454 0.233659 -0.0683816 -0.0575163 0.233497 -0.0756083 -0.0573543 0.233562 -0.0683857 -0.0574514 0.233774 -0.0820109 -0.056777 0.233774 -0.0756199 -0.0575391 0.233659 -0.0756185 -0.0575163 0.233774 -0.072 -0.0576529 0.233474 -0.0756011 -0.0572397 0.233774 -0.100825 -0.0499292 0.233659 -0.0965365 -0.0521455 0.233474 -0.0964185 -0.0518947 0.233562 -0.108692 -0.0443552 0.233659 -0.114008 -0.0394514 0.233774 -0.114025 -0.039467 0.233497 -0.102791 -0.048522 0.233497 -0.108629 -0.0442802 0.233562 -0.113961 -0.0394068 0.233659 -0.118621 -0.0338753 0.233774 -0.116163 -0.0370596 0.233659 -0.122499 -0.027765 0.233474 -0.118397 -0.0337123 0.233497 -0.11849 -0.0337798 0.233497 -0.122357 -0.0276867 0.233562 -0.122442 -0.0277336 0.233659 -0.12558 -0.0212168 0.233774 -0.126173 -0.0197203 0.233497 -0.129012 -0.00720511 0.233497 -0.127659 -0.0142938 0.233562 -0.129108 -0.00721731 0.233562 -0.127754 -0.014318 0.233659 -0.127817 -0.0143342 0.233514 -0.1295 -2.85742e-06 0.233774 -0.12965 -2.85742e-06 0.233659 -0.129173 -0.00722546 0.233774 -0.129195 -0.00722832 0.235574 -0.0756199 -0.0575391 0.235851 -0.0216432 -0.0276867 0.235786 -0.0184801 -0.0211929 0.235874 -0.128898 -0.00719072 0.235851 -0.122357 -0.0276867 0.235851 -0.0185706 -0.0211571 0.235874 -0.0217439 -0.0276314 0.235834 -0.1295 -2.85742e-06 0.235786 -0.118569 -0.033837 0.235786 -0.122442 -0.0277336 0.235851 -0.11849 -0.0337798 0.235689 -0.0161833 -0.0143342 0.235851 -0.0163406 -0.0142938 0.235874 -0.0186774 -0.0211148 0.235786 -0.127754 -0.014318 0.235689 -0.122499 -0.027765 0.235574 -0.10289 -0.0486784 0.235689 -0.108733 -0.0444053 0.235851 -0.102791 -0.048522 0.235786 -0.102843 -0.0486042 0.235786 -0.0965088 -0.0520866 0.235874 -0.108556 -0.0441918 0.235874 -0.10273 -0.0484251 0.235689 -0.0898078 -0.0548095 0.235574 -0.0828026 -0.0566317 0.235689 -0.0827983 -0.0566093 0.235874 -0.0827464 -0.056337 0.235851 -0.0827679 -0.0564498 0.235851 -0.0756083 -0.0573543 0.235786 -0.0683857 -0.0574514 0.235689 -0.0612018 -0.0566093 0.235874 -0.0756011 -0.0572397 0.235851 -0.0683918 -0.0573543 0.235786 -0.061214 -0.0565454 0.235851 -0.0542424 -0.0546551 0.235786 -0.0474913 -0.0520866 0.235874 -0.0542779 -0.054546 0.235851 -0.0475327 -0.0519986 0.235689 -0.0411219 -0.0486591 0.235786 -0.0411567 -0.0486042 0.235851 -0.0353706 -0.0442802 0.235786 -0.0300391 -0.0394068 0.235786 -0.0254313 -0.033837 0.235851 -0.03011 -0.0393402 0.235786 -0.021558 -0.0277336 0.235689 -0.021501 -0.027765 0.235574 -0.0183984 -0.0212252 0.235574 -0.0178268 -0.0197203 0.235724 -0.12961 -2.85742e-06 0.235689 -0.129627 -2.85742e-06 0.235574 -0.129195 -0.00722832 0.235851 -0.129012 -0.00720511 0.235786 -0.129108 -0.00721731 0.235689 -0.129173 -0.00722546 0.235574 -0.122519 -0.027776 0.235689 -0.12558 -0.0212168 0.235689 -0.127817 -0.0143342 0.235574 -0.127839 -0.0143398 0.235874 -0.127548 -0.0142652 0.235851 -0.127659 -0.0142938 0.235786 -0.12552 -0.0211929 0.235851 -0.125429 -0.0211571 0.235689 -0.118621 -0.0338753 0.235574 -0.121926 -0.0288279 0.235786 -0.113961 -0.0394068 0.235574 -0.116163 -0.0370596 0.235574 -0.108748 -0.0444229 0.235689 -0.114008 -0.0394514 0.235851 -0.108629 -0.0442802 0.235851 -0.11389 -0.0393402 0.235786 -0.108692 -0.0443552 0.235689 -0.102878 -0.0486591 0.235689 -0.0965365 -0.0521455 0.235574 -0.0965462 -0.0521661 0.235851 -0.0964674 -0.0519986 0.235851 -0.0897576 -0.0546551 0.235786 -0.0897877 -0.0547477 0.235689 -0.0756185 -0.0575163 0.235574 -0.0820109 -0.056777 0.235786 -0.0756144 -0.0574514 0.235786 -0.0827861 -0.0565454 0.235689 -0.0683816 -0.0575163 0.235574 -0.0619892 -0.056777 0.235574 -0.0683802 -0.0575391 0.235851 -0.0612322 -0.0564498 0.235786 -0.0542124 -0.0547477 0.235689 -0.0541923 -0.0548095 0.235574 -0.0522826 -0.0541761 0.235689 -0.0474636 -0.0521455 0.235786 -0.0353086 -0.0443552 0.235689 -0.0352671 -0.0444053 0.235574 -0.0349433 -0.0441653 0.235874 -0.0412704 -0.0484251 0.235851 -0.0412089 -0.048522 0.235689 -0.0299916 -0.0394514 0.235574 -0.021481 -0.027776 0.235689 -0.0253787 -0.0338753 0.235574 -0.0253602 -0.0338887 0.235851 -0.02551 -0.0337798 0.235689 -0.0184197 -0.0212168 0.235851 -0.0149884 -0.00720511 0.235786 -0.0148918 -0.00721731 0.235786 -0.0162463 -0.014318 0.235574 -0.0161612 -0.0143398 0.235786 -0.0144379 -2.85742e-06 0.235689 -0.0148273 -0.00722546 0.235574 -0.0148046 -0.00722832 0.235874 -0.12835 -2.85742e-06 0.235874 -0.01565 -2.85742e-06 0.235874 -0.113643 -0.0379656 0.235874 -0.113806 -0.0392616 0.235874 -0.118397 -0.0337123 0.235874 -0.11991 -0.0296673 0.235874 -0.122256 -0.0276314 0.235874 -0.125323 -0.0211148 0.235874 -0.01465 -2.85742e-06 0.235874 -0.0151023 -0.00719072 0.235874 -0.0164518 -0.0142652 0.235874 -0.0194552 -0.0203588 0.235874 -0.0874209 0.054196 0.235874 -0.0612537 -0.056337 0.235874 -0.0668007 -0.0561125 0.235874 -0.068399 -0.0572397 0.235874 -0.0256029 -0.0337123 0.235874 -0.0301937 -0.0392616 0.235874 -0.0380416 -0.0449711 0.235874 -0.0668007 0.0561068 0.235874 -0.0620413 0.0564759 0.235874 -0.0819588 0.0564759 0.235874 -0.0771994 0.0561068 0.235874 -0.0769984 0.0571289 0.235874 -0.072 0.0573471 0.235874 -0.12935 -2.85742e-06 0.235874 -0.127391 0.0103514 0.235874 -0.0771994 -0.0561125 0.235874 -0.0874209 -0.0542017 0.235874 -0.0897222 -0.054546 0.235874 -0.0964185 -0.0518947 0.235874 -0.0250217 0.0328918 0.235874 -0.0200233 0.0242343 0.235874 -0.0181087 0.019612 0.235874 -0.104895 0.0469755 0.235874 -0.0971174 0.0504396 0.235874 -0.0962372 0.0519739 0.235874 -0.0916149 0.0538885 0.235874 -0.118978 0.0328918 0.235874 -0.124545 0.0203531 0.235874 -0.123977 0.0242343 0.235874 -0.121667 0.0286721 0.235874 -0.0354438 -0.0441918 0.235874 -0.0475816 -0.0518947 0.235874 -0.0477629 0.0519739 0.235874 -0.0468827 0.0504396 0.235874 -0.112553 0.0405497 0.235874 -0.113643 0.0379599 0.235874 -0.105959 0.0449654 0.235874 -0.0380416 0.0449654 0.235874 -0.0314475 0.0405497 0.235874 -0.0280674 0.036861 0.233474 -0.12935 -2.85742e-06 0.233474 -0.0166095 -0.0103571 0.233474 -0.12835 -2.85742e-06 0.233474 -0.0468827 0.0504396 0.233474 -0.0217439 -0.0276314 0.233474 -0.0186774 -0.0211148 0.233474 -0.127391 -0.0103571 0.233474 -0.0477629 0.0519739 0.233474 -0.0565791 0.054196 0.233474 -0.043325 0.0496637 0.233474 -0.0354438 -0.0441918 0.233474 -0.0256029 -0.0337123 0.233474 -0.128479 0.00995587 0.233474 -0.127391 0.0103514 0.233474 -0.0771994 0.0561068 0.233474 -0.072 0.0573471 0.233474 -0.0194552 0.0203531 0.233474 -0.0200233 0.0242343 0.233474 -0.0240903 0.0296616 0.233474 -0.0223335 0.0286721 0.233474 -0.0250217 0.0328918 0.233474 -0.0523852 0.0538885 0.233474 -0.0571568 0.055393 0.233474 -0.0620413 0.0564759 0.233474 -0.0314475 0.0405497 0.233474 -0.0380416 0.0449654 0.233474 -0.0351362 0.0439298 0.233474 -0.01565 -2.85742e-06 0.233474 -0.0155213 0.00995587 0.233474 -0.0166042 0.0148404 0.233474 -0.0612537 -0.056337 0.233474 -0.0542779 -0.054546 0.233474 -0.0412704 -0.0484251 0.233474 -0.0380416 -0.0449711 0.233474 -0.0868433 0.055393 0.233474 -0.0874209 0.054196 0.233474 -0.121667 0.0286721 0.233474 -0.124545 0.0203531 0.233474 -0.0874209 -0.0542017 0.233474 -0.0771994 -0.0561125 0.233474 -0.0668007 -0.0561125 0.233474 -0.113806 -0.0392616 0.233474 -0.108556 -0.0441918 0.233474 -0.10273 -0.0484251 0.233474 -0.104895 0.0469755 0.233474 -0.105959 0.0449654 0.233474 -0.108864 0.0439298 0.235574 -0.12965 -2.85742e-06 0.235574 -0.128774 -0.0100137 0.233774 -0.128774 -0.0100137 0.233774 -0.127839 -0.0143398 0.235574 -0.126173 -0.0197203 0.233774 -0.125602 -0.0212252 0.235574 -0.125602 -0.0212252 0.233774 -0.122519 -0.027776 0.233774 -0.121926 -0.0288279 0.233774 -0.11864 -0.0338887 0.235574 -0.11864 -0.0338887 0.235574 -0.114025 -0.039467 0.233774 -0.109057 -0.0441653 0.233774 -0.108748 -0.0444229 0.235574 -0.109057 -0.0441653 0.233774 -0.10289 -0.0486784 0.235574 -0.100825 -0.0499292 0.233774 -0.0965462 -0.0521661 0.233774 -0.0917175 -0.0541761 0.235574 -0.0917175 -0.0541761 0.233774 -0.0828026 -0.0566317 0.235574 -0.0898149 -0.0548313 0.235574 -0.072 -0.0576529 0.233774 -0.0683802 -0.0575391 0.233774 -0.0619892 -0.056777 0.235574 -0.0611975 -0.0566317 0.235574 -0.0541852 -0.0548313 0.233774 -0.0522826 -0.0541761 0.233774 -0.0474539 -0.0521661 0.235574 -0.0474539 -0.0521661 0.235574 -0.043175 -0.0499292 0.235574 -0.0411096 -0.0486784 0.235574 -0.0352525 -0.0444229 0.233774 -0.029975 -0.039467 0.235574 -0.029975 -0.039467 0.235574 -0.0278376 -0.0370596 0.233774 -0.0253602 -0.0338887 0.233774 -0.0220737 -0.0288279 0.235574 -0.0220737 -0.0288279 0.233774 -0.0183984 -0.0212252 0.233774 -0.0178268 -0.0197203 0.235574 -0.0152259 -0.0100137 0.233696 -0.130649 -0.00486265 0.2333 -0.130128 -0.00970271 0.2333 -0.129129 -0.0144698 0.233696 -0.127661 -0.0191114 0.233696 -0.125893 -0.0236426 0.2333 -0.125968 -0.0236755 0.233696 -0.122966 -0.0294279 0.233696 -0.121267 -0.0321908 0.233696 -0.118441 -0.0361493 0.2333 -0.121336 -0.0322355 0.2333 -0.118506 -0.0361995 0.233696 -0.117082 -0.0378309 0.233696 -0.115297 -0.0398609 0.233696 -0.111858 -0.0433002 0.2333 -0.111913 -0.0433604 0.233696 -0.109828 -0.0450846 0.233696 -0.108146 -0.0464438 0.2333 -0.108197 -0.0465083 0.233696 -0.104188 -0.0492701 0.233696 -0.101425 -0.0509685 0.233696 -0.10001 -0.0517599 0.233696 -0.0921279 -0.0553038 0.2333 -0.0864669 -0.0571313 0.233696 -0.0822192 -0.0579588 0.233696 -0.0768598 -0.0586519 0.233696 -0.072 -0.0588529 0.233696 -0.0575532 -0.0570521 0.233696 -0.0528915 -0.0556642 0.233696 -0.0518722 -0.0553038 0.233696 -0.0439905 -0.0517599 0.2333 -0.0483274 -0.053971 0.233696 -0.0358536 -0.0464438 0.233696 -0.034172 -0.0450846 0.2333 -0.0286425 -0.0399163 0.233696 -0.0210344 -0.0294279 0.233696 -0.020243 -0.0280124 0.233696 -0.0166991 -0.0201307 0.232968 -0.131164 -2.85742e-06 0.232756 -0.131508 -2.85742e-06 0.232968 -0.130357 -0.00974089 0.232968 -0.129353 -0.0145267 0.232756 -0.129687 -0.0146112 0.232968 -0.127958 -0.0192133 0.232968 -0.126181 -0.0237687 0.232756 -0.121818 -0.0325506 0.232968 -0.118689 -0.036342 0.232968 -0.115528 -0.0400734 0.232968 -0.108339 -0.0466914 0.232968 -0.0957659 -0.0541834 0.232968 -0.0912105 -0.055961 0.232756 -0.0913223 -0.0562865 0.232968 -0.0768857 -0.0589645 0.232968 -0.072 -0.0591666 0.232756 -0.072 -0.0595108 0.232968 -0.062262 -0.0583597 0.232756 -0.0622054 -0.0586992 0.232968 -0.0574762 -0.0573562 0.232756 -0.0526778 -0.0562865 0.232968 -0.0482342 -0.0541834 0.232756 -0.048096 -0.0544987 0.232968 -0.0396405 -0.0495328 0.232756 -0.0394523 -0.0498209 0.232968 -0.0356609 -0.0466914 0.232756 -0.0282186 -0.0403065 0.232968 -0.0199671 -0.0281617 0.232968 -0.0146467 -0.0145267 0.232756 -0.014313 -0.0146112 0.2333 -0.130731 -0.00486941 0.232968 -0.130962 -0.00488856 0.2333 -0.127739 -0.019138 0.2333 -0.123829 -0.0280513 0.232968 -0.124033 -0.0281617 0.232968 -0.12153 -0.0323624 0.2333 -0.115358 -0.0399163 0.232968 -0.112071 -0.043531 0.2333 -0.104233 -0.0493386 0.232968 -0.10436 -0.0495328 0.232968 -0.100159 -0.0520358 0.2333 -0.100048 -0.0518318 0.2333 -0.0956727 -0.053971 0.2333 -0.0911352 -0.0557416 0.232968 -0.0865239 -0.0573562 0.2333 -0.0816999 -0.0581309 0.2333 -0.0768666 -0.0587334 0.232968 -0.0817381 -0.0583597 0.2333 -0.072 -0.0589346 0.2333 -0.0671335 -0.0587334 0.232968 -0.0671143 -0.0589645 0.2333 -0.0623002 -0.0581309 0.2333 -0.0575331 -0.0571313 0.2333 -0.0528649 -0.0557416 0.232968 -0.0527896 -0.055961 0.2333 -0.0439516 -0.0518318 0.232968 -0.0438412 -0.0520358 0.2333 -0.0397674 -0.0493386 0.2333 -0.0358034 -0.0465083 0.232968 -0.0319295 -0.043531 0.2333 -0.0320866 -0.0433604 0.232968 -0.0284718 -0.0400734 0.2333 -0.0254946 -0.0361995 0.2333 -0.0226643 -0.0322355 0.232968 -0.0253115 -0.036342 0.232968 -0.0224701 -0.0323624 0.2333 -0.0201711 -0.0280513 0.2333 -0.0180319 -0.0236755 0.232968 -0.0178194 -0.0237687 0.232968 -0.0160419 -0.0192133 0.2333 -0.0148716 -0.0144698 0.2333 -0.0162613 -0.019138 0.233696 -0.0140441 -0.0102221 0.232968 -0.0136432 -0.00974089 0.2333 -0.0132695 -0.00486941 0.2333 -0.013872 -0.00970271 0.233696 -0.0139527 -0.00968925 0.232968 -0.0130384 -0.00488856 0.2333 -0.0130683 -2.85742e-06 0.233696 -0.01315 -2.85742e-06 0.230674 -0.0986674 -0.0399134 0.230674 -0.0903688 -0.0443491 0.230674 -0.072 -0.0480029 0.230674 -0.0629479 -0.0455113 0.230674 -0.0626357 -0.0470806 0.230674 -0.0536312 -0.0443491 0.230674 -0.0453327 -0.0399134 0.230674 -0.0380589 -0.033944 0.230674 -0.0320895 -0.0266702 0.230674 -0.024 -2.85742e-06 0.230674 -0.0249223 0.00936148 0.230674 -0.029132 0.0177537 0.230674 -0.0391903 0.0328069 0.230674 -0.0380589 0.0339383 0.230674 -0.0462216 0.0385773 0.230674 -0.0542435 0.0428652 0.230674 -0.0536312 0.0443434 0.230674 -0.0629479 0.0455056 0.230674 -0.072 0.0463971 0.230674 -0.072 0.0479971 0.230674 -0.0810522 0.0455056 0.230674 -0.0897566 0.0428652 0.230674 -0.114868 0.0177537 0.230674 -0.116346 0.0183659 0.230674 -0.119078 0.00936148 0.230674 -0.1184 -2.85742e-06 0.230674 -0.114868 -0.0177594 0.230674 -0.11058 -0.0257813 0.230674 -0.10481 -0.0328126 0.230674 -0.119078 -0.00936719 0.230674 -0.116346 -0.0183717 0.230674 -0.111911 -0.0266702 0.238174 -0.116346 -0.0183717 0.230674 -0.105941 -0.033944 0.238174 -0.0986674 -0.0399134 0.230674 -0.0813644 -0.0470806 0.238174 -0.0813644 -0.0470806 0.238174 -0.0626357 -0.0470806 0.238174 -0.0536312 -0.0443491 0.238174 -0.0453327 -0.0399134 0.238174 -0.0380589 -0.033944 0.238174 -0.0320895 -0.0266702 0.230674 -0.0276538 -0.0183717 0.230674 -0.0249223 -0.00936719 0.238174 -0.0276538 -0.0183717 0.238474 -0.0988341 -0.0401628 0.238474 -0.0904837 -0.0446262 0.238474 -0.081688 -0.0487074 0.238474 -0.0814229 -0.0473748 0.238474 -0.0625772 -0.0473748 0.238474 -0.072 -0.0496616 0.238474 -0.0529965 -0.0458815 0.238474 -0.045166 -0.0401628 0.238474 -0.0444111 -0.0412926 0.238474 -0.0273767 -0.0184865 0.238474 -0.0307103 -0.0275918 0.238474 -0.0232955 -0.0096908 0.238474 -0.0237 -2.85742e-06 0.238474 -0.0246281 0.00942 0.238474 -0.0318401 0.0268312 0.238474 -0.045166 0.0401571 0.238474 -0.0529965 0.0458758 0.238474 -0.0535164 0.0446205 0.238474 -0.0623121 0.0487017 0.238474 -0.072 0.0482971 0.238474 -0.072 0.0496559 0.238474 -0.099589 0.0412869 0.238474 -0.0988341 0.0401571 0.238474 -0.106153 0.0341504 0.238474 -0.107114 0.0351112 0.238474 -0.116623 0.0184808 0.238474 -0.117879 0.0190007 0.238474 -0.120705 0.00968508 0.238474 -0.119372 -0.00942572 0.238474 -0.120705 -0.0096908 0.238474 -0.107114 -0.0351169 0.238474 -0.106153 -0.0341561 0.238474 -0.099589 -0.0412926 0.236974 -0.121859 -2.85742e-06 0.238274 -0.118064 0.0190773 0.236974 -0.118064 0.0190773 0.238274 -0.113456 0.0276972 0.236974 -0.113456 0.0276972 0.236974 -0.107255 0.0352526 0.236974 -0.0997001 0.0414532 0.238274 -0.0997001 0.0414532 0.238274 -0.081727 0.0488979 0.236974 -0.081727 0.0488979 0.238274 -0.072 0.0498559 0.238274 -0.0622731 0.0488979 0.236974 -0.0622731 0.0488979 0.236974 -0.0443 0.0414532 0.236974 -0.0367446 0.0352526 0.236974 -0.0259366 0.0190773 0.238274 -0.0259366 0.0190773 0.236974 -0.0230993 0.0097241 0.238274 -0.0221413 -2.85742e-06 0.236974 -0.030544 0.0276972 0.236974 -0.0417478 0.0400576 0.236974 -0.049624 0.0449343 0.236974 -0.0529199 0.0460606 0.236974 -0.072 0.0498559 0.236974 -0.0857379 0.0482808 0.236974 -0.0910802 0.0460606 0.236974 -0.102252 0.0400576 0.236974 -0.114681 0.026424 0.236974 -0.120901 0.0097241 0.236974 -0.11881 0.0181315 0.236974 -0.121345 0.00922137 0.236974 -0.1222 -2.85742e-06 0.236974 -0.11881 -0.0181372 0.236974 -0.118064 -0.019083 0.236974 -0.114681 -0.0264298 0.236974 -0.102252 -0.0400633 0.236974 -0.0910802 -0.0460663 0.236974 -0.0943761 -0.0449401 0.236974 -0.0857379 -0.0482865 0.236974 -0.0622731 -0.0489036 0.236974 -0.0582622 -0.0482865 0.236974 -0.0529199 -0.0460663 0.236974 -0.0443 -0.0414589 0.236974 -0.030544 -0.0277029 0.236974 -0.0293191 -0.0264298 0.236974 -0.0251899 -0.0181372 0.236974 -0.0259366 -0.019083 0.236974 -0.0221413 -2.85742e-06 0.236974 -0.0251899 0.0181315 0.236974 -0.0293191 0.026424 0.230674 -0.11909 0.0182398 0.236674 -0.11909 0.0182398 0.230674 -0.114936 0.026582 0.236674 -0.10932 0.0340188 0.230674 -0.102433 0.040297 0.236674 -0.08582 0.0485693 0.230674 -0.08582 0.0485693 0.230674 -0.0581801 0.0485693 0.230674 -0.0494903 0.0452029 0.236674 -0.0494903 0.0452029 0.230674 -0.041567 0.040297 0.236674 -0.0346801 0.0340188 0.236674 -0.0290641 0.026582 0.236674 -0.0215 -2.85742e-06 0.230674 -0.0215 -2.85742e-06 0.230674 -0.0249102 0.0182398 0.230674 -0.0290641 0.026582 0.230674 -0.0346801 0.0340188 0.230674 -0.0305047 0.0378252 0.230674 -0.0381621 0.0448058 0.230674 -0.0673405 0.0502817 0.230674 -0.0566339 0.0540037 0.230674 -0.0766596 0.0502817 0.230674 -0.0668192 0.0559076 0.230674 -0.0945098 0.0452029 0.230674 -0.0970282 0.0502606 0.230674 -0.105838 0.0448058 0.230674 -0.113495 0.0378252 0.230674 -0.10932 0.0340188 0.230674 -0.11974 0.0295563 0.230674 -0.12164 0.00927649 0.230674 -0.127194 0.0103147 0.230674 -0.1225 -2.85742e-06 0.230674 -0.11974 -0.029562 0.230674 -0.102433 -0.0403027 0.230674 -0.113495 -0.0378309 0.230674 -0.0766596 -0.0502874 0.230674 -0.0771809 -0.0559133 0.230674 -0.0494903 -0.0452086 0.230674 -0.0469718 -0.0502663 0.230674 -0.0381621 -0.0448115 0.230674 -0.0346801 -0.0340245 0.230674 -0.0290641 -0.0265877 0.230674 -0.0249102 -0.0182456 0.230674 -0.0223599 -0.00928221 0.230674 -0.0223599 0.00927649 0.230674 -0.01585 -2.85742e-06 0.236874 -0.0971174 -0.0504453 0.236874 -0.0917175 -0.0541761 0.236874 -0.0820109 -0.056777 0.236874 -0.0565791 -0.0542017 0.236874 -0.0522826 -0.0541761 0.236874 -0.0468827 -0.0504453 0.236874 -0.043175 -0.0499292 0.236874 -0.0380416 -0.0449711 0.236874 -0.0349433 -0.0441653 0.236874 -0.0240903 -0.0296673 0.236874 -0.0278376 -0.0370596 0.236874 -0.0194552 -0.0203588 0.236874 -0.0166095 -0.0103571 0.236874 -0.0166095 0.0103514 0.236874 -0.01435 -2.85742e-06 0.236874 -0.0152259 0.010008 0.236874 -0.0178268 0.0197146 0.236874 -0.0194552 0.0203531 0.236874 -0.0220737 0.0288221 0.236874 -0.0240903 0.0296616 0.236874 -0.0303569 0.0379599 0.236874 -0.0278376 0.0370538 0.236874 -0.0380416 0.0449654 0.236874 -0.043175 0.0499235 0.236874 -0.0522826 0.0541704 0.236874 -0.0468827 0.0504396 0.236874 -0.0668007 0.0561068 0.236874 -0.0820109 0.0567713 0.236874 -0.0917175 0.0541704 0.236874 -0.100825 0.0499235 0.236874 -0.113643 0.0379599 0.236874 -0.109057 0.0441596 0.236874 -0.116163 0.0370538 0.236874 -0.124545 0.0203531 0.236874 -0.126173 0.0197146 0.236874 -0.12965 -2.85742e-06 0.236874 -0.127391 -0.0103571 0.236874 -0.124545 -0.0203588 0.236874 -0.126173 -0.0197203 0.236874 -0.121926 -0.0288279 0.236874 -0.116163 -0.0370596 0.236874 -0.113643 -0.0379656 0.236874 -0.105959 -0.0449711 0.236874 -0.109057 -0.0441653 0.236874 -0.128774 -0.0100137 0.237674 -0.128774 -0.0100137 0.237674 -0.121926 -0.0288279 0.237674 -0.116163 -0.0370596 0.236874 -0.100825 -0.0499292 0.237674 -0.100825 -0.0499292 0.236874 -0.072 -0.0576529 0.237674 -0.0820109 -0.056777 0.237674 -0.072 -0.0576529 0.236874 -0.0619892 -0.056777 0.237674 -0.0619892 -0.056777 0.237674 -0.043175 -0.0499292 0.237674 -0.0349433 -0.0441653 0.236874 -0.0220737 -0.0288279 0.237674 -0.0278376 -0.0370596 0.237674 -0.0220737 -0.0288279 0.236874 -0.0178268 -0.0197203 0.236874 -0.0152259 -0.0100137 0.237874 -0.0821845 0.0577561 0.237874 -0.0920595 0.0551101 0.237874 -0.100925 0.0500967 0.237874 -0.101325 0.0507895 0.237874 -0.109185 0.0443128 0.237874 -0.116316 0.0371824 0.237874 -0.1097 0.0449256 0.237874 -0.1221 0.0289221 0.237874 -0.122792 0.0293221 0.237874 -0.127113 0.0200566 0.237874 -0.128971 0.0100427 0.237874 -0.129759 0.0101816 0.237874 -0.12985 -2.85742e-06 0.237874 -0.126361 -0.0197887 0.237874 -0.1221 -0.0289279 0.237874 -0.122792 -0.0293279 0.237874 -0.116316 -0.0371881 0.237874 -0.116929 -0.0377024 0.237874 -0.100925 -0.0501024 0.237874 -0.1097 -0.0449314 0.237874 -0.101325 -0.0507952 0.237874 -0.0917859 -0.0543641 0.237874 -0.0820456 -0.056974 0.237874 -0.0821845 -0.0577618 0.237874 -0.0619545 -0.056974 0.237874 -0.072 -0.0586529 0.237874 -0.0522142 -0.0543641 0.237874 -0.043075 -0.0501024 0.237874 -0.0348148 -0.0443185 0.237874 -0.0343005 -0.0449314 0.237874 -0.0270715 -0.0377024 0.237874 -0.0219005 -0.0289279 0.237874 -0.0150289 -0.0100484 0.237874 -0.0150289 0.0100427 0.237874 -0.01335 -2.85742e-06 0.237874 -0.0176388 0.019783 0.237874 -0.0168871 0.0200566 0.237874 -0.0276844 0.0371824 0.237874 -0.0348148 0.0443128 0.237874 -0.0343005 0.0449256 0.237874 -0.042675 0.0507895 0.237874 -0.0522142 0.0543584 0.237874 -0.0619545 0.0569683 0.237874 -0.072 0.0578471 0.237674 -0.129956 0.0102163 0.237674 -0.13085 -2.85742e-06 0.233696 -0.130649 0.00485694 0.233696 -0.127661 0.0191057 0.237674 -0.127301 0.020125 0.233696 -0.129956 0.0102163 0.233696 -0.123757 0.0280066 0.233696 -0.118441 0.0361436 0.233696 -0.122966 0.0294221 0.237674 -0.117082 0.0378252 0.237674 -0.109828 0.0450789 0.233696 -0.109828 0.0450789 0.233696 -0.104188 0.0492644 0.237674 -0.101425 0.0509627 0.233696 -0.0911086 0.0556585 0.237674 -0.0921279 0.0552981 0.233696 -0.0921279 0.0552981 0.233696 -0.101425 0.0509627 0.233696 -0.0864469 0.0570463 0.237674 -0.0822192 0.0579531 0.233696 -0.0822192 0.0579531 0.233696 -0.0671402 0.0586461 0.233696 -0.0528915 0.0556585 0.237674 -0.0518722 0.0552981 0.233696 -0.0439905 0.0517542 0.237674 -0.034172 0.0450789 0.237674 -0.042575 0.0509627 0.233696 -0.0358536 0.0464381 0.233696 -0.0269183 0.0378252 0.233696 -0.020243 0.0280066 0.233696 -0.0181068 0.0236369 0.237674 -0.0210344 0.0294221 0.237674 -0.0166991 0.020125 0.233696 -0.0166991 0.020125 0.237674 -0.01315 -2.85742e-06 0.233696 -0.013351 0.00485694 0.233696 -0.0139527 0.00968353 0.228874 -0.117312 -0.00901603 0.228874 -0.110414 -0.0256702 0.230474 -0.114683 -0.0176828 0.228874 -0.104668 -0.0326712 0.230474 -0.0976674 -0.0384168 0.228874 -0.0976674 -0.0384168 0.230474 -0.08968 -0.0426861 0.228874 -0.0810132 -0.0453151 0.230474 -0.0810132 -0.0453151 0.228874 -0.072 -0.0462029 0.230474 -0.0629869 -0.0453151 0.228874 -0.0543201 -0.0426861 0.230474 -0.0543201 -0.0426861 0.228874 -0.0393317 -0.0326712 0.230474 -0.0335861 -0.0256702 0.228874 -0.0293168 -0.0176828 0.230474 -0.0293168 -0.0176828 0.228874 -0.0258 -2.85742e-06 0.236674 -0.12815 -2.85742e-06 0.236074 -0.11974 -0.029562 0.236674 -0.124358 -0.0202866 0.236674 -0.11974 -0.029562 0.236074 -0.113495 -0.0378309 0.236674 -0.113495 -0.0378309 0.236074 -0.105838 -0.0448115 0.236074 -0.0873662 -0.0540094 0.236074 -0.0771809 -0.0559133 0.236674 -0.0771809 -0.0559133 0.236074 -0.0668192 -0.0559133 0.236674 -0.0668192 -0.0559133 0.236674 -0.0566339 -0.0540094 0.236074 -0.0305047 -0.0378309 0.236674 -0.0381621 -0.0448115 0.236074 -0.0196417 -0.0202866 0.236674 -0.0242603 -0.029562 0.236074 -0.0168061 -0.0103204 0.230674 -0.127194 -0.0103204 0.233274 -0.12815 -2.85742e-06 0.230674 -0.124358 -0.0202866 0.233274 -0.124358 -0.0202866 0.233274 -0.11974 -0.029562 0.230674 -0.105838 -0.0448115 0.233274 -0.105838 -0.0448115 0.230674 -0.0970282 -0.0502663 0.233274 -0.0970282 -0.0502663 0.230674 -0.0873662 -0.0540094 0.230674 -0.0668192 -0.0559133 0.233274 -0.0771809 -0.0559133 0.230674 -0.0566339 -0.0540094 0.233274 -0.0566339 -0.0540094 0.233274 -0.0381621 -0.0448115 0.230674 -0.0305047 -0.0378309 0.230674 -0.0242603 -0.029562 0.233274 -0.0242603 -0.029562 0.230674 -0.0196417 -0.0202866 0.233274 -0.0168061 -0.0103204 0.230674 -0.0168061 -0.0103204 0.233274 -0.01585 -2.85742e-06 0.226574 -0.0216587 -0.0456422 0.226574 -0.0248637 -0.0473925 0.226574 -0.0242613 -0.0461416 0.226574 -0.0244757 -0.0453416 0.226574 -0.02241 -0.0453503 0.226574 -0.0250613 -0.0447559 0.226574 -0.0258613 -0.0445416 0.226574 -0.0266378 -0.0432438 0.226574 -0.0268589 -0.0473925 0.226574 -0.0262174 -0.0477015 0.226574 -0.0263602 -0.0503298 0.224774 -0.00487679 -0.0105703 0.225074 -0.011749 -0.0320634 0.224774 -0.0120139 -0.0319225 0.225074 -0.0178928 -0.0416017 0.225074 -0.0255317 -0.0499904 0.224774 -0.025736 -0.0497707 0.225074 -0.0344548 -0.0569977 0.225074 -0.0444154 -0.06243 0.225074 -0.0776729 -0.0680167 0.224774 -0.0663522 -0.0677177 0.224774 -0.0887876 -0.0658465 0.225074 -0.0888618 -0.0661371 0.225074 -0.0995847 -0.06243 0.224774 -0.0994634 -0.0621556 0.224774 -0.118264 -0.0497707 0.224774 -0.125869 -0.0414189 0.225074 -0.132251 -0.0320634 0.224774 -0.136445 0.0215383 0.225074 -0.109545 0.056992 0.224774 -0.10938 0.0567415 0.224774 -0.0994634 0.0621499 0.224774 -0.0887876 0.0658407 0.224774 -0.0445367 0.0621499 0.224774 -0.0346198 0.0567415 0.224774 -0.0181306 0.0414131 0.224774 -0.0120139 0.0319168 0.225074 -0.011749 0.0320577 0.225074 -0.00727035 0.0216335 0.224774 -0.00755488 0.0215383 0.228738 -0.00514165 0.0137091 0.228738 -0.00458044 0.0106113 0.229745 -0.00504457 0.0105382 0.229745 -0.138398 0.0136147 0.228738 -0.13942 0.0106113 0.229745 -0.138956 0.0105382 0.229768 -0.138913 0.0104002 0.229764 -0.138916 0.0104543 0.23126 -0.135198 0.00728929 0.232756 -0.131305 0.00491127 0.229745 -0.136311 0.021403 0.229777 -0.136255 0.0212978 0.229808 -0.136199 0.0211927 0.229785 -0.136256 0.0212214 0.23097 -0.133183 0.0201487 0.231414 -0.132215 0.0191706 0.232756 -0.128284 0.0193194 0.231809 -0.131582 0.0175391 0.231929 -0.131673 0.0159937 0.231911 -0.131878 0.0154138 0.231496 -0.133476 0.0136362 0.231115 -0.134643 0.0131967 0.229745 -0.138856 0.0111534 0.230654 -0.135942 0.0131629 0.230492 -0.136379 0.0132532 0.229777 -0.138297 0.0136778 0.229785 -0.13826 0.0137446 0.229765 -0.138322 0.0137229 0.231742 -0.1147 0.0453535 0.231929 -0.11568 0.0436872 0.231809 -0.114828 0.0449797 0.232756 -0.115781 0.0403008 0.231811 -0.116971 0.0428298 0.231911 -0.116148 0.0432873 0.231115 -0.11965 0.0427496 0.229808 -0.122455 0.0449971 0.229777 -0.122575 0.0449934 0.229785 -0.122509 0.0450327 0.230492 -0.121126 0.0436666 0.229765 -0.122573 0.0450448 0.229745 -0.122694 0.0449894 0.22975 -0.122639 0.04503 0.229765 -0.117048 0.0505703 0.23097 -0.11491 0.0480405 0.231414 -0.114561 0.0467094 0.232756 -0.112304 0.0437786 0.23171 -0.114657 0.0455153 0.232756 -0.0866084 0.0576842 0.232756 -0.0959041 0.054493 0.231911 -0.0885878 0.0595613 0.229785 -0.0932243 0.0642536 0.229765 -0.0932739 0.0642961 0.229777 -0.0933007 0.0642522 0.229745 -0.0934059 0.0643084 0.22975 -0.0933379 0.0643161 0.229745 -0.0856176 0.0663953 0.229765 -0.0857259 0.0663186 0.229785 -0.0857475 0.066257 0.229808 -0.0857435 0.0661927 0.229777 -0.0856807 0.066294 0.22975 -0.0856805 0.0663678 0.23097 -0.0851399 0.0630591 0.231414 -0.0855029 0.0617317 0.231482 -0.0856135 0.0615186 0.231809 -0.0865991 0.0603673 0.231908 -0.0873844 0.0598896 0.229745 -0.0664028 0.0675458 0.230654 -0.0588343 0.0639387 0.229785 -0.0582525 0.066257 0.229765 -0.0582742 0.0663186 0.229777 -0.0583194 0.066294 0.229745 -0.0583825 0.0663953 0.229777 -0.0506994 0.0642522 0.229765 -0.0507262 0.0642961 0.232756 -0.048096 0.054493 0.231365 -0.0526892 0.0603107 0.231482 -0.0530289 0.060083 0.23171 -0.0539088 0.0596984 0.232756 -0.0573917 0.0576842 0.231891 -0.0568204 0.0599903 0.231767 -0.0575984 0.060533 0.229745 -0.0349278 0.0567404 0.230654 -0.0286274 0.0487893 0.230492 -0.0283305 0.0491228 0.229777 -0.0270038 0.0505716 0.229745 -0.018512 0.0416286 0.229777 -0.0214256 0.0449934 0.23097 -0.0239567 0.0429076 0.23171 -0.0264819 0.0426543 0.231742 -0.0266437 0.042697 0.232756 -0.0282186 0.0403008 0.229745 -0.00560192 0.0136147 0.229765 -0.0056786 0.013723 0.229785 -0.00574023 0.0137446 0.229777 -0.00570317 0.0136778 0.229745 -0.00514432 0.0111534 0.229808 -0.00580448 0.0137406 0.230492 -0.00762121 0.0132532 0.23097 -0.00893804 0.013137 0.232756 -0.0133037 0.00979183 0.231742 -0.0113704 0.0142981 0.231911 -0.0124359 0.0165849 0.231115 -0.0111502 0.0198872 0.229808 -0.00780127 0.0211927 0.229777 -0.00774495 0.0212978 0.231383 -0.00898724 0.0058079 0.232756 -0.0126953 0.00491127 0.231317 -0.00891566 0.00689681 0.23113 -0.00851494 0.00790044 0.229764 -0.00508432 0.0104543 0.23021 -0.00621386 0.0097386 0.229768 -0.00508675 0.0104002 0.232756 -0.0157164 0.0193194 0.230654 -0.0100421 0.020566 0.229745 -0.0078924 0.0220053 0.229745 -0.0111507 0.0298552 0.232756 -0.0196643 0.0283198 0.232756 -0.022182 0.0325449 0.229745 -0.0157175 0.0377652 0.231911 -0.0287099 0.0441446 0.232756 -0.0316964 0.0437786 0.231767 -0.0292599 0.0452219 0.232756 -0.0354495 0.0469573 0.232756 -0.0394523 0.0498152 0.232756 -0.0436774 0.0523328 0.229745 -0.042142 0.0608465 0.231115 -0.0588004 0.0626397 0.232756 -0.072 0.0595051 0.231115 -0.0918901 0.060847 0.232756 -0.100323 0.0523328 0.232756 -0.104548 0.0498152 0.230492 -0.11567 0.0491228 0.229777 -0.116996 0.0505716 0.231496 -0.118421 0.0425471 0.232756 -0.11896 0.0365477 0.232756 -0.121818 0.0325449 0.232756 -0.124336 0.0283198 0.229745 -0.131611 0.0322569 0.229745 -0.132849 0.0298552 0.230492 -0.134382 0.0207065 0.226274 -0.00724299 -0.0215571 0.228738 -0.00724299 -0.0215571 0.228738 -0.00727035 -0.0216392 0.228738 -0.13942 -0.010617 0.226274 -0.136757 -0.0215571 0.225074 -0.13942 -0.010617 0.225074 -0.13673 -0.0216392 0.225074 -0.118468 -0.0499904 0.228738 -0.11003 -0.0566755 0.226274 -0.118468 -0.0499904 0.226274 -0.0935543 -0.0647599 0.228738 -0.0663272 -0.0680167 0.225074 -0.0551383 -0.0661371 0.226274 -0.0504458 -0.0647599 0.226274 -0.0266959 -0.0510479 0.228738 -0.0266959 -0.0510479 0.226274 -0.00514165 -0.0137148 0.225074 -0.00727035 -0.0216392 0.228738 -0.0107289 -0.0300679 0.228738 -0.011749 -0.0320634 0.228738 -0.0339702 -0.0566755 0.228738 -0.0344548 -0.0569977 0.225074 -0.0663272 -0.0680167 0.228738 -0.0765985 -0.0680978 0.225074 -0.109545 -0.0569977 0.228738 -0.102065 -0.061274 0.228738 -0.0935543 -0.0647599 0.228738 -0.126107 -0.0416017 0.225074 -0.126107 -0.0416017 0.228738 -0.128673 -0.0380327 0.228738 -0.136757 -0.0215571 0.228738 -0.13673 -0.0216392 0.228738 -0.133271 -0.0300679 0.228738 -0.132251 -0.0320634 0.226274 -0.00514165 0.0137091 0.225074 -0.00458044 0.0106113 0.226274 -0.00724299 0.0215514 0.225074 -0.0178928 0.041596 0.228738 -0.0344548 0.056992 0.228738 -0.0339702 0.0566698 0.226274 -0.0266959 0.0510422 0.225074 -0.0255317 0.0499847 0.226274 -0.0255317 0.0499847 0.226274 -0.020955 0.0453013 0.225074 -0.0444154 0.0624243 0.225074 -0.0551383 0.0661314 0.225074 -0.0776729 0.068011 0.225074 -0.0888618 0.0661314 0.228738 -0.0935543 0.0647542 0.225074 -0.0995847 0.0624243 0.226274 -0.0935543 0.0647542 0.225074 -0.126107 0.041596 0.226274 -0.123045 0.0453013 0.225074 -0.118468 0.0499847 0.225074 -0.13673 0.0216335 0.228738 -0.13673 0.0216335 0.225074 -0.132251 0.0320577 0.228738 -0.128673 0.038027 0.228738 -0.11003 0.0566698 0.225074 -0.0663272 0.068011 0.225074 -0.0344548 0.056992 0.228738 -0.0444154 0.0624243 0.228738 -0.00727035 0.0216335 0.228738 -0.011749 0.0320577 0.185974 -0.0759402 -0.0467513 0.185974 -0.0763 -0.0421843 0.185974 -0.0825578 -0.0598792 0.185974 -0.0512052 -0.0571362 0.185974 -0.0749531 -0.0477715 0.185974 -0.072 -0.0608029 0.185974 -0.069047 -0.0477715 0.185974 -0.0680599 -0.0467513 0.185974 -0.0677 -0.0453781 0.185974 -0.076432 -0.0421706 0.185974 -0.0515253 -0.0371316 0.185974 -0.0588977 -0.0403277 0.185974 -0.0939617 -0.0386197 0.185974 -0.0980929 -0.0399687 0.185974 -0.10016 -0.0391212 0.185974 -0.10702 -0.033121 0.185974 -0.124654 -0.0304029 0.185974 -0.116784 -0.017825 0.185974 -0.131876 -0.0105607 0.185974 -0.119338 -0.00907612 0.185974 -0.119274 0.0094005 0.185974 -0.131876 0.010555 0.185974 -0.116531 0.0184425 0.185974 -0.124654 0.0303971 0.185974 -0.106083 0.0340797 0.185974 -0.072 0.0481971 0.185974 -0.0625967 0.047271 0.185974 -0.0614422 0.0598735 0.185974 -0.0535547 0.0445281 0.185974 -0.0416 -0.0526572 0.185974 -0.0459072 -0.0399687 0.185974 -0.0438399 -0.0391212 0.185974 -0.0329186 0.0465726 0.185974 -0.0379175 0.0340797 0.185974 -0.0319232 0.0267756 0.185974 -0.0193457 0.0303971 0.185974 -0.0148667 0.020792 0.185974 -0.0247262 0.0094005 0.185974 -0.0121237 0.010555 0.185974 -0.0238 -2.85742e-06 0.185974 -0.0246617 -0.00907612 0.185974 -0.0121237 -0.0105607 0.185974 -0.0193457 -0.0304029 0.185974 -0.0369796 -0.033121 0.190674 -0.113335 -0.01441 0.190674 -0.1155 -0.01441 0.185974 -0.113335 -0.01441 0.190674 -0.113792 -0.0148675 0.190674 -0.114417 -0.015035 0.185974 -0.114417 -0.015035 0.190674 -0.115042 -0.0148675 0.185974 -0.115042 -0.0127025 0.185974 -0.115267 -0.0123128 0.185974 -0.114417 -0.012535 0.185974 -0.113792 -0.0127025 0.185974 -0.114417 -0.012085 0.185974 -0.112945 -0.012935 0.185974 -0.113792 -0.0148675 0.185974 -0.112945 -0.014635 0.185974 -0.113567 -0.0152573 0.185974 -0.115042 -0.0148675 0.185974 -0.1155 -0.01441 0.185974 -0.115889 -0.014635 0.185974 -0.116117 -0.013785 0.185974 -0.1155 -0.01316 0.190674 -0.114417 0.0125293 0.190674 -0.113792 0.0126968 0.190674 -0.1155 0.0131543 0.190674 -0.115667 0.0137793 0.190674 -0.115042 0.0126968 0.190674 -0.113167 0.0137793 0.190674 -0.113335 0.0131543 0.185974 -0.113335 0.0131543 0.185974 -0.1155 0.0131543 0.185974 -0.115667 0.0137793 0.185974 -0.112945 0.0129293 0.185974 -0.113567 0.0123071 0.185974 -0.113792 0.0126968 0.185974 -0.114417 0.0125293 0.185974 -0.115042 0.0126968 0.185974 -0.115889 0.0129293 0.185974 -0.115267 0.0152515 0.185974 -0.114417 0.0150293 0.185974 -0.114417 0.0154793 0.185974 -0.113792 0.0148618 0.185974 -0.113335 0.0144043 0.185974 -0.112945 0.0146293 0.185974 -0.112717 0.0137793 0.185974 -0.113167 0.0137793 0.190674 -0.0971327 0.0354543 0.190674 -0.0975903 0.0349968 0.191425 -0.0982153 0.0360793 0.190674 -0.0994653 0.0360793 0.190674 -0.0992978 0.0354543 0.190674 -0.0982153 0.0348293 0.185974 -0.0975903 0.0349968 0.185974 -0.0982153 0.0348293 0.190674 -0.0988403 0.0349968 0.185974 -0.0988403 0.0349968 0.185974 -0.0992978 0.0354543 0.185974 -0.0982153 0.0377793 0.185974 -0.0973653 0.0375515 0.185974 -0.0975903 0.0371618 0.185974 -0.0969653 0.0360793 0.185974 -0.0971327 0.0354543 0.185974 -0.0973653 0.0346071 0.185974 -0.0982153 0.0343793 0.185974 -0.0996875 0.0369293 0.185974 -0.0990653 0.0375515 0.185974 -0.0982153 0.0373293 0.191425 -0.072 0.0445971 0.190674 -0.072 0.0433471 0.190674 -0.072625 0.0435146 0.190674 -0.07075 0.0445971 0.190674 -0.0709175 0.0439721 0.190674 -0.071375 0.0435146 0.185974 -0.0709175 0.0439721 0.185974 -0.072625 0.0435146 0.190674 -0.0730826 0.0439721 0.190674 -0.07325 0.0445971 0.185974 -0.0730826 0.0439721 0.185974 -0.072 0.0462971 0.185974 -0.07115 0.0460694 0.185974 -0.0705278 0.0454471 0.185974 -0.07075 0.0445971 0.185974 -0.0705278 0.0437471 0.185974 -0.071375 0.0435146 0.185974 -0.072 0.0433471 0.185974 -0.07115 0.0431249 0.185974 -0.07325 0.0445971 0.185974 -0.0737 0.0445971 0.185974 -0.0730826 0.0452221 0.185974 -0.072625 0.0456797 0.190674 -0.0447023 0.0354543 0.185974 -0.0445348 0.0360793 0.190674 -0.0451598 0.0349968 0.190674 -0.0457848 0.0348293 0.190674 -0.0464098 0.0349968 0.185974 -0.0457848 0.0348293 0.190674 -0.0468674 0.0354543 0.185974 -0.0464098 0.0349968 0.185974 -0.0468674 0.0354543 0.190674 -0.0470348 0.0360793 0.185974 -0.0473165 0.0368169 0.185974 -0.046063 0.037298 0.185974 -0.0468448 0.0374084 0.185974 -0.0461631 0.0377367 0.185974 -0.0454065 0.0377367 0.185974 -0.0447249 0.0374084 0.185974 -0.0446586 0.0366217 0.185974 -0.0442532 0.0368169 0.185974 -0.0440848 0.0360793 0.185974 -0.0447023 0.0354543 0.185974 -0.0443126 0.0352293 0.185974 -0.0451598 0.0349968 0.185974 -0.0449348 0.0346071 0.185974 -0.0457848 0.0343793 0.185974 -0.046911 0.0366217 0.185974 -0.0474848 0.0360793 0.190674 -0.0295829 0.0125293 0.190674 -0.0285004 0.0131543 0.190674 -0.0289579 0.0126968 0.191425 -0.0295829 0.0137793 0.190674 -0.0306655 0.0131543 0.185974 -0.0285004 0.0131543 0.185974 -0.0289579 0.0126968 0.190674 -0.0302079 0.0126968 0.185974 -0.0306655 0.0131543 0.190674 -0.0308329 0.0137793 0.185974 -0.0304329 0.0152515 0.185974 -0.0295829 0.0154793 0.185974 -0.0295829 0.0150293 0.185974 -0.0285004 0.0144043 0.185974 -0.0287329 0.0152515 0.185974 -0.0283329 0.0137793 0.185974 -0.0295829 0.0125293 0.185974 -0.0302079 0.0126968 0.185974 -0.0304329 0.0123071 0.185974 -0.0312829 0.0137793 0.185974 -0.0308329 0.0137793 0.185974 -0.0306655 0.0144043 0.185974 -0.0310552 0.0146293 0.191425 -0.0295829 -0.013785 0.190674 -0.0308329 -0.013785 0.190674 -0.0306655 -0.01441 0.190674 -0.0302079 -0.0148675 0.185974 -0.0283329 -0.013785 0.190674 -0.0285004 -0.01441 0.185974 -0.0285004 -0.01441 0.190674 -0.0289579 -0.0148675 0.185974 -0.0289579 -0.0148675 0.190674 -0.0295829 -0.015035 0.185974 -0.0295829 -0.015035 0.185974 -0.0302079 -0.0148675 0.185974 -0.0302079 -0.0127025 0.185974 -0.0310552 -0.012935 0.185974 -0.0304329 -0.0123128 0.185974 -0.0287329 -0.0123128 0.185974 -0.0285004 -0.01316 0.185974 -0.0281107 -0.014635 0.185974 -0.0287329 -0.0152573 0.185974 -0.0304329 -0.0152573 0.185974 -0.0306655 -0.01441 0.185974 -0.0310552 -0.014635 0.185974 -0.0308329 -0.013785 0.185974 -0.0306655 -0.01316 0.190674 -0.0446586 -0.0366274 0.190674 -0.0455067 -0.0373037 0.190674 -0.0450055 -0.0370623 0.190674 -0.046911 -0.0366274 0.191425 -0.0457848 -0.036085 0.190674 -0.046063 -0.0373037 0.185974 -0.0446586 -0.0366274 0.185974 -0.0450055 -0.0370623 0.185974 -0.0455067 -0.0373037 0.185974 -0.046063 -0.0373037 0.190674 -0.0465642 -0.0370623 0.185974 -0.046911 -0.0366274 0.190674 -0.0470348 -0.036085 0.185974 -0.0461631 -0.0377424 0.185974 -0.0465642 -0.0370623 0.185974 -0.0472571 -0.035235 0.185974 -0.0464098 -0.0350025 0.185974 -0.0466348 -0.0346128 0.185974 -0.0457848 -0.034835 0.185974 -0.0449348 -0.0346128 0.185974 -0.0443126 -0.035235 0.185974 -0.0445348 -0.036085 0.185974 -0.0440848 -0.036085 0.185974 -0.0447249 -0.0374141 0.185974 -0.0454065 -0.0377424 0.190674 -0.071375 -0.0456854 0.190674 -0.0730826 -0.0452279 0.191425 -0.072 -0.0446029 0.190674 -0.072 -0.0458529 0.185974 -0.07075 -0.0446029 0.185974 -0.0709175 -0.0452279 0.190674 -0.0709175 -0.0452279 0.185974 -0.072 -0.0458529 0.190674 -0.072625 -0.0456854 0.185974 -0.072625 -0.0456854 0.185974 -0.0734723 -0.0437529 0.185974 -0.07285 -0.0431306 0.185974 -0.072 -0.0433529 0.185974 -0.071375 -0.0435203 0.185974 -0.072 -0.0429029 0.185974 -0.0709175 -0.0439779 0.185974 -0.0703 -0.0446029 0.185974 -0.071375 -0.0456854 0.185974 -0.07115 -0.0460751 0.185974 -0.0730826 -0.0452279 0.185974 -0.07285 -0.0460751 0.185974 -0.0734723 -0.0454529 0.185974 -0.0737 -0.0446029 0.185974 -0.0979371 -0.0373037 0.185974 -0.0993415 -0.0366274 0.185974 -0.0988403 -0.0350025 0.185974 -0.0990653 -0.0346128 0.185974 -0.0982153 -0.034835 0.185974 -0.0982153 -0.034385 0.185974 -0.0975903 -0.0350025 0.185974 -0.0973653 -0.0346128 0.185974 -0.096743 -0.035235 0.185974 -0.0969653 -0.036085 0.185974 -0.0966836 -0.0368226 0.185974 -0.0971553 -0.0374141 0.185974 -0.0970891 -0.0366274 0.185974 -0.0974359 -0.0370623 0.190674 -0.0984934 -0.0373037 0.185974 -0.0984934 -0.0373037 0.190674 -0.0989946 -0.0370623 0.185974 -0.0989946 -0.0370623 0.190674 -0.0979371 -0.0373037 0.190674 -0.0970891 -0.0366274 0.190674 -0.0974359 -0.0370623 0.191425 -0.0982153 -0.036085 0.190674 -0.0993415 -0.0366274 0.237874 -0.0204343 -0.0199795 0.238074 -0.0251531 -0.0290093 0.238074 -0.0312807 -0.0371235 0.238074 -0.0387949 -0.0439736 0.237874 -0.0473507 -0.0495054 0.238074 -0.0669161 -0.0548678 0.237874 -0.0568665 -0.0531918 0.237874 -0.0771025 -0.055067 0.237874 -0.0871336 -0.0531918 0.237874 -0.0966494 -0.0495054 0.238074 -0.105205 -0.0439736 0.238074 -0.118847 -0.0290093 0.237874 -0.119017 -0.0291146 0.238074 -0.126162 -0.0101275 0.237474 -0.0166095 -0.0103571 0.237474 -0.0194552 -0.0203588 0.237274 -0.0164129 -0.0103939 0.237274 -0.0192687 -0.0204311 0.237474 -0.0240903 -0.0296673 0.237474 -0.0380416 -0.0449711 0.237274 -0.0379211 -0.0451307 0.237274 -0.0874757 -0.0543941 0.237274 -0.0972065 -0.0506243 0.237474 -0.113643 -0.0379656 0.237274 -0.12008 -0.0297726 0.237474 -0.127391 -0.0103571 0.237274 -0.12925 -2.85742e-06 0.237474 -0.128577 0.00997323 0.237274 -0.12838 0.0099385 0.237474 -0.125985 0.0196462 0.237274 -0.12158 0.0286221 0.237474 -0.121753 0.0287221 0.237274 -0.115856 0.0367967 0.237274 -0.1088 0.0438532 0.237274 -0.0915807 0.0537945 0.237474 -0.0916491 0.0539825 0.237474 -0.0819761 0.0565743 0.237274 -0.0819414 0.0563774 0.237274 -0.072 0.0572471 0.237474 -0.052351 0.0539825 0.237274 -0.0524194 0.0537945 0.237274 -0.043375 0.0495771 0.237474 -0.0350719 0.0440064 0.237274 -0.0352005 0.0438532 0.237474 -0.0222469 0.0287221 0.237274 -0.0182026 0.0195778 0.237474 -0.0154228 0.00997323 0.238074 -0.121328 0.0191068 0.238074 -0.116977 0.0278454 0.237874 -0.116806 0.0277401 0.238074 -0.111094 0.0356356 0.237874 -0.0768626 0.0524723 0.238074 -0.067119 0.0526715 0.237874 -0.0671375 0.0524723 0.238074 -0.0401207 0.0422123 0.237874 -0.0402412 0.0420526 0.238074 -0.0329065 0.0356356 0.237874 -0.0330543 0.0355009 0.238074 -0.0270236 0.0278454 0.237874 -0.0271936 0.0277401 0.238074 -0.0226723 0.0191068 0.237874 -0.0228588 0.0190346 0.237874 -0.0201974 0.00968074 0.238074 -0.02 -2.85742e-06 0.238074 -0.0235115 -0.0187874 0.237874 -0.0206888 -0.00959458 0.238074 -0.0277888 -0.0273773 0.237874 -0.0276187 -0.0274826 0.238074 -0.0335716 -0.035035 0.238074 -0.040663 -0.0414998 0.238074 -0.0488216 -0.0465513 0.237874 -0.0487325 -0.0467304 0.237874 -0.0577148 -0.0502102 0.238074 -0.0577696 -0.0500178 0.237874 -0.0671836 -0.0519802 0.238074 -0.0672021 -0.051781 0.238074 -0.076798 -0.051781 0.237874 -0.0768164 -0.0519802 0.238074 -0.0862305 -0.0500178 0.237874 -0.0862852 -0.0502102 0.237874 -0.103458 -0.0416594 0.238074 -0.116211 -0.0273773 0.237874 -0.110576 -0.0351698 0.237874 -0.116381 -0.0274826 0.238074 -0.120489 -0.0187874 0.238474 -0.13085 -2.85742e-06 0.238474 -0.129956 0.0102163 0.238474 -0.127301 0.020125 0.238474 -0.122966 0.0294221 0.238474 -0.117082 0.0378252 0.238274 -0.116929 0.0376966 0.238274 -0.1097 0.0449256 0.238474 -0.101425 0.0509627 0.238274 -0.0920595 0.0551101 0.238474 -0.0617808 0.0579531 0.238274 -0.0618156 0.0577561 0.238274 -0.0519406 0.0551101 0.238474 -0.0518722 0.0552981 0.238474 -0.042575 0.0509627 0.238474 -0.034172 0.0450789 0.238274 -0.0212077 0.0293221 0.238474 -0.0210344 0.0294221 0.238274 -0.0168871 0.0200566 0.238274 -0.0142411 0.0101816 0.238474 -0.01315 -2.85742e-06 0.238674 -0.0776379 0.0318295 0.238874 -0.0810587 0.0300545 0.238674 -0.0830337 0.0303837 0.238874 -0.0848087 0.0338045 0.238674 -0.0844795 0.0318295 0.238874 -0.0929988 0.0247459 0.238874 -0.0948738 0.0214983 0.238674 -0.093328 0.0227709 0.238674 -0.10017 0.0227709 0.238674 -0.100699 0.0247459 0.238874 -0.102057 0.00905581 0.238874 -0.10256 0.00718081 0.238674 -0.101857 0.00905581 0.238674 -0.103832 0.00563501 0.238874 -0.107682 0.00580821 0.238674 -0.105807 0.00510581 0.238674 -0.107782 0.00563501 0.238874 -0.109055 0.00718081 0.238674 -0.109228 0.00708081 0.238674 -0.109757 0.00905581 0.238874 -0.10256 -0.0109365 0.238874 -0.105807 -0.0128115 0.238674 -0.109228 -0.0110365 0.238674 -0.093328 -0.0267266 0.238874 -0.0948738 -0.0279992 0.238674 -0.0967488 -0.0287016 0.238674 -0.0987238 -0.0281724 0.238874 -0.0999964 -0.0266266 0.238674 -0.0771087 -0.0338103 0.238674 -0.0790837 -0.0372311 0.238874 -0.0810587 -0.0375603 0.238674 -0.0830337 -0.0372311 0.238674 -0.0844795 -0.0357853 0.238674 -0.0850087 -0.0338103 0.238874 -0.0610664 -0.0370579 0.238674 -0.0629414 -0.0377603 0.238674 -0.0649164 -0.0372311 0.238874 -0.066189 -0.0356853 0.238674 -0.0663622 -0.0357853 0.238674 -0.0438305 -0.0267266 0.238874 -0.0472513 -0.0285016 0.238874 -0.0510013 -0.0247516 0.238674 -0.0512013 -0.0247516 0.238874 -0.0344426 -0.00906152 0.238874 -0.034945 -0.0109365 0.238674 -0.0362176 -0.0124823 0.238674 -0.0401676 -0.0124823 0.238874 -0.0414402 -0.0109365 0.238874 -0.0419426 -0.00906152 0.238674 -0.0421426 -0.00906152 0.238874 -0.0381926 0.00530581 0.238674 -0.0381926 0.00510581 0.238674 -0.0401676 0.00563501 0.238874 -0.0400676 0.00580821 0.238874 -0.0419426 0.00905581 0.238674 -0.0438305 0.0227709 0.238874 -0.0472513 0.0209959 0.238674 -0.0452763 0.0213251 0.238874 -0.0510013 0.0247459 0.238674 -0.0589914 0.0338045 0.238674 -0.0609664 0.0303837 0.238874 -0.0629414 0.0300545 0.238874 -0.066189 0.0319295 0.241474 -0.0843063 -0.0356853 0.241474 -0.0810587 -0.0375603 0.241674 -0.0810587 -0.0377603 0.241474 -0.0791837 -0.0370579 0.241474 -0.0778111 -0.0356853 0.241674 -0.0776379 -0.0357853 0.241674 -0.100699 -0.0247516 0.241674 -0.10017 -0.0267266 0.241474 -0.0967488 -0.0285016 0.241674 -0.0987238 -0.0281724 0.241674 -0.0967488 -0.0287016 0.241674 -0.107782 -0.0124823 0.241674 -0.105807 -0.0130115 0.241674 -0.103832 -0.0124823 0.241474 -0.102057 -0.00906152 0.241474 -0.109055 0.00718081 0.241474 -0.107682 0.00580821 0.241674 -0.107782 0.00563501 0.241474 -0.103932 0.00580821 0.241674 -0.103832 0.00563501 0.241474 -0.10256 0.00718081 0.241474 -0.0999964 0.0228709 0.241674 -0.100699 0.0247459 0.241674 -0.10017 0.0227709 0.241474 -0.0967488 0.0209959 0.241474 -0.0948738 0.0214983 0.241674 -0.0850087 0.0338045 0.241674 -0.0844795 0.0318295 0.241474 -0.0829337 0.030557 0.241474 -0.0810587 0.0300545 0.241674 -0.0830337 0.0303837 0.241474 -0.0791837 0.030557 0.241674 -0.0790837 0.0303837 0.241474 -0.0778111 0.0319295 0.241474 -0.0773087 0.0338045 0.241674 -0.0776379 0.0318295 0.241674 -0.0668914 0.0338045 0.241474 -0.066189 0.0319295 0.241474 -0.0629414 0.0300545 0.241674 -0.0609664 0.0303837 0.241674 -0.0506721 0.0227709 0.241474 -0.0491263 0.0214983 0.241674 -0.0472513 0.0207959 0.241474 -0.0453763 0.0214983 0.241674 -0.0452763 0.0213251 0.241474 -0.0440037 0.0228709 0.241474 -0.0414402 0.00718081 0.241674 -0.0421426 0.00905581 0.241474 -0.0400676 0.00580821 0.241674 -0.0416134 0.00708081 0.241674 -0.0401676 0.00563501 0.241474 -0.0381926 0.00530581 0.241474 -0.0363176 0.00580821 0.241474 -0.0414402 -0.0109365 0.241674 -0.0416134 -0.0110365 0.241674 -0.0381926 -0.0130115 0.241474 -0.0381926 -0.0128115 0.241474 -0.034945 -0.0109365 0.241674 -0.0347718 -0.0110365 0.241674 -0.0512013 -0.0247516 0.241474 -0.0504989 -0.0266266 0.241474 -0.0472513 -0.0285016 0.241674 -0.0472513 -0.0287016 0.241474 -0.0453763 -0.0279992 0.241474 -0.0440037 -0.0266266 0.241674 -0.0452763 -0.0281724 0.241474 -0.0666914 -0.0338103 0.241674 -0.0663622 -0.0357853 0.241474 -0.066189 -0.0356853 0.241474 -0.0648164 -0.0370579 0.241474 -0.0596938 -0.0356853 0.241674 -0.0595206 -0.0357853 0.241674 -0.0312113 0.00866706 0.241674 -0.0303 -2.85742e-06 0.241374 -0.03 -2.85742e-06 0.241674 -0.0312377 0.00879035 0.241374 -0.0438966 0.0312092 0.241674 -0.0440973 0.0309863 0.241674 -0.05115 0.0361104 0.241374 -0.0590213 0.0399415 0.241674 -0.059114 0.0396562 0.241374 -0.0763902 0.0417671 0.241674 -0.0763589 0.0414687 0.241674 -0.0848861 0.0396562 0.241374 -0.093 0.0363702 0.241674 -0.105736 0.0245078 0.238674 -0.110095 0.0169581 0.238674 -0.112789 0.00866706 0.238674 -0.1137 -2.85742e-06 0.238674 -0.101192 0.0297746 0.238974 -0.105979 0.0246841 0.238674 -0.0440973 0.0309863 0.238974 -0.0590213 0.0399415 0.238674 -0.0763589 0.0414687 0.238674 -0.0848861 0.0396562 0.238674 -0.0339052 0.0169581 0.238674 -0.0328076 0.0142394 0.238674 -0.0312113 0.00866706 0.238874 -0.105807 0.00530581 0.241474 -0.105807 0.00530581 0.238874 -0.103932 0.00580821 0.238874 -0.0999964 0.0228709 0.238874 -0.0986238 0.0214983 0.241474 -0.0986238 0.0214983 0.238874 -0.0967488 0.0209959 0.238874 -0.0935012 0.0228709 0.241474 -0.0935012 0.0228709 0.238874 -0.0843063 0.0319295 0.241474 -0.0843063 0.0319295 0.238874 -0.0829337 0.030557 0.238874 -0.0791837 0.030557 0.238874 -0.0778111 0.0319295 0.238874 -0.0773087 0.0338045 0.238874 -0.0648164 0.030557 0.241474 -0.0648164 0.030557 0.238874 -0.0610664 0.030557 0.241474 -0.0610664 0.030557 0.238874 -0.0596938 0.0319295 0.241474 -0.0596938 0.0319295 0.238874 -0.0591914 0.0338045 0.241474 -0.0591914 0.0338045 0.238874 -0.0504989 0.0228709 0.241474 -0.0504989 0.0228709 0.238874 -0.0491263 0.0214983 0.241474 -0.0472513 0.0209959 0.238874 -0.0453763 0.0214983 0.238874 -0.0440037 0.0228709 0.238874 -0.0414402 0.00718081 0.238874 -0.0363176 0.00580821 0.238874 -0.034945 0.00718081 0.241474 -0.034945 0.00718081 0.238874 -0.0400676 -0.0123091 0.241474 -0.0400676 -0.0123091 0.238874 -0.0381926 -0.0128115 0.238874 -0.0363176 -0.0123091 0.241474 -0.0363176 -0.0123091 0.241474 -0.0510013 -0.0247516 0.238874 -0.0504989 -0.0266266 0.241474 -0.0491263 -0.0279992 0.238874 -0.0491263 -0.0279992 0.238874 -0.0453763 -0.0279992 0.238874 -0.0440037 -0.0266266 0.238874 -0.0435013 -0.0247516 0.238874 -0.0648164 -0.0370579 0.238874 -0.0629414 -0.0375603 0.241474 -0.0629414 -0.0375603 0.241474 -0.0610664 -0.0370579 0.238874 -0.0596938 -0.0356853 0.241474 -0.0591914 -0.0338103 0.238874 -0.0843063 -0.0356853 0.238874 -0.0829337 -0.0370579 0.241474 -0.0829337 -0.0370579 0.238874 -0.0791837 -0.0370579 0.238874 -0.0778111 -0.0356853 0.241474 -0.0999964 -0.0266266 0.238874 -0.0986238 -0.0279992 0.238874 -0.0967488 -0.0285016 0.241474 -0.0986238 -0.0279992 0.238874 -0.0935012 -0.0266266 0.241474 -0.0948738 -0.0279992 0.238874 -0.0929988 -0.0247516 0.241474 -0.0935012 -0.0266266 0.241474 -0.109557 -0.00906152 0.238874 -0.109055 -0.0109365 0.238874 -0.107682 -0.0123091 0.241474 -0.109055 -0.0109365 0.241474 -0.107682 -0.0123091 0.241474 -0.105807 -0.0128115 0.238874 -0.103932 -0.0123091 0.241474 -0.103932 -0.0123091 0.238874 -0.102057 -0.00906152 0.241474 -0.10256 -0.0109365 0.241674 -0.101243 0.0128175 0.239024 -0.10097 0.0158162 0.239024 -0.101833 0.015401 0.241674 -0.103379 0.0128175 0.239024 -0.102789 0.015401 0.239024 -0.103651 0.0158162 0.241674 -0.107071 0.0168789 0.239024 -0.104248 0.0165643 0.238674 -0.103651 0.0158162 0.238674 -0.101833 0.015401 0.238674 -0.10097 0.0158162 0.238674 -0.100374 0.0165643 0.239024 -0.100374 0.0165643 0.239024 -0.100161 0.0174971 0.241674 -0.0943 0.030308 0.241674 -0.0919 0.0261511 0.239024 -0.0895 0.028158 0.241674 -0.0895 0.025508 0.241674 -0.0871 0.0261511 0.239024 -0.091362 0.029233 0.238674 -0.090575 0.0284461 0.239024 -0.090575 0.0284461 0.238674 -0.088425 0.0284461 0.239024 -0.088425 0.0284461 0.238674 -0.0876381 0.029233 0.239024 -0.0876381 0.029233 0.239024 -0.073862 0.0339221 0.241674 -0.076157 0.0325971 0.239024 -0.073075 0.0331352 0.239024 -0.072 0.0328471 0.241674 -0.0744 0.0308402 0.241674 -0.072 0.0301971 0.238674 -0.073862 0.0339221 0.238674 -0.072 0.0328471 0.238674 -0.070925 0.0331352 0.239024 -0.070925 0.0331352 0.238674 -0.0701381 0.0339221 0.239024 -0.0701381 0.0339221 0.238674 -0.06985 0.0349971 0.239024 -0.0438392 0.0174971 0.241674 -0.0464892 0.0174971 0.241674 -0.0458461 0.0150971 0.239024 -0.0416892 0.0153471 0.239024 -0.0406142 0.0156352 0.241674 -0.0392892 0.0133402 0.239024 -0.0395392 0.0174971 0.239024 -0.0435511 0.0164221 0.239024 -0.0427642 0.0156352 0.238674 -0.0416892 0.0153471 0.239024 -0.0398272 0.0164221 0.241674 -0.0394 -0.00415978 0.239024 -0.038075 -0.00186481 0.241674 -0.037 -0.00480286 0.241674 -0.0346 -0.00415978 0.238674 -0.038862 -0.00107786 0.239024 -0.038862 -0.00107786 0.238674 -0.038075 -0.00186481 0.238674 -0.037 -0.00215286 0.239024 -0.037 -0.00215286 0.239024 -0.035925 -0.00186481 0.238674 -0.03485 -2.85742e-06 0.239024 -0.0351381 -0.00107786 0.239024 -0.0435511 -0.0185779 0.239024 -0.0416892 -0.0196529 0.241674 -0.0392892 -0.0216598 0.241674 -0.0375322 -0.0199029 0.238674 -0.0435511 -0.0185779 0.239024 -0.0427642 -0.0193648 0.238674 -0.0416892 -0.0196529 0.238674 -0.0406142 -0.0193648 0.239024 -0.0406142 -0.0193648 0.238674 -0.0398272 -0.0185779 0.239024 -0.0398272 -0.0185779 0.241674 -0.0768 -0.0350029 0.239024 -0.073862 -0.0360779 0.239024 -0.073075 -0.0368648 0.241674 -0.072 -0.0398029 0.239024 -0.070925 -0.0368648 0.241674 -0.0696 -0.0391598 0.238674 -0.07415 -0.0350029 0.239024 -0.07415 -0.0350029 0.238674 -0.073862 -0.0360779 0.238674 -0.072 -0.0371529 0.239024 -0.072 -0.0371529 0.239024 -0.0701381 -0.0360779 0.239024 -0.06985 -0.0350029 0.241674 -0.093657 -0.0327137 0.239024 -0.088425 -0.0321757 0.241674 -0.0853431 -0.0327137 0.239024 -0.0876381 -0.0313887 0.239024 -0.091362 -0.0313887 0.238674 -0.090575 -0.0321757 0.239024 -0.090575 -0.0321757 0.239024 -0.0895 -0.0324637 0.238674 -0.0876381 -0.0313887 0.238674 -0.08735 -0.0303137 0.239024 -0.103386 -0.0193648 0.241674 -0.104711 -0.0216598 0.239024 -0.102311 -0.0196529 0.241674 -0.102311 -0.0223029 0.241674 -0.098154 -0.0199029 0.238674 -0.103386 -0.0193648 0.239024 -0.104173 -0.0185779 0.238674 -0.100449 -0.0185779 0.239024 -0.101236 -0.0193648 0.239024 -0.100449 -0.0185779 0.238674 -0.100161 -0.0175029 0.240174 -0.114499 0.0176006 0.239374 -0.106922 0.0233311 0.239374 -0.110369 0.0170801 0.239374 -0.110803 0.0160698 0.240174 -0.117116 0.0089713 0.239374 -0.100104 0.0312092 0.240174 -0.110248 0.0255534 0.239374 -0.105979 0.0246841 0.239374 -0.0763902 0.0417671 0.240174 -0.072 0.0459971 0.240174 -0.0630259 0.0451133 0.240174 -0.0543966 0.0424956 0.239374 -0.0559273 0.0388001 0.239374 -0.051 0.0363702 0.239374 -0.0486661 0.0349189 0.240174 -0.0464438 0.0382447 0.240174 -0.0394731 0.0325241 0.239374 -0.0423016 0.0296956 0.239374 -0.0370783 0.0233311 0.240174 -0.0337524 0.0255534 0.239374 -0.0336311 0.0170801 0.240174 -0.0295016 0.0176006 0.239374 -0.0331971 0.0160698 0.239374 -0.0309178 0.00872943 0.240174 -0.0268839 0.0089713 0.240174 -0.072 -0.0460029 0.240174 -0.110429 -0.035035 0.240174 -0.116211 -0.0273773 0.240174 -0.124 -2.85742e-06 0.240174 -0.123115 0.00955212 0.240174 -0.120489 0.0187817 0.240174 -0.104527 0.0325241 0.240174 -0.116211 0.0273716 0.240174 -0.0975563 0.0382447 0.240174 -0.0896035 0.0424956 0.240174 -0.0809742 0.0451133 0.240174 -0.0862305 0.0500121 0.240174 -0.0672021 0.0517753 0.240174 -0.0488216 0.0465456 0.240174 -0.040663 0.041494 0.240174 -0.0335716 0.0350293 0.240174 -0.0235115 0.0187817 0.240174 -0.0268839 -0.00897701 0.240174 -0.0295016 -0.0176063 0.240174 -0.0235115 -0.0187874 0.240174 -0.040663 -0.0414998 0.240174 -0.0488216 -0.0465513 0.240174 -0.076798 -0.051781 0.238074 -0.124 -2.85742e-06 0.238074 -0.123115 -0.00955783 0.240174 -0.123115 -0.00955783 0.240174 -0.120489 -0.0187874 0.238074 -0.110429 -0.035035 0.238074 -0.103337 -0.0414998 0.240174 -0.103337 -0.0414998 0.240174 -0.0951784 -0.0465513 0.238074 -0.0951784 -0.0465513 0.240174 -0.0862305 -0.0500178 0.240174 -0.0672021 -0.051781 0.240174 -0.0577696 -0.0500178 0.240174 -0.0335716 -0.035035 0.240174 -0.0277888 -0.0273773 0.238074 -0.0208854 -0.00955783 0.240174 -0.0208854 -0.00955783 0.237874 -0.123803 0.00968074 0.237874 -0.120675 0.018854 0.237874 -0.121141 0.0190346 0.237874 -0.110576 0.0351641 0.237874 -0.110946 0.0355009 0.237874 -0.103759 0.0420526 0.237874 -0.0954905 0.0471722 0.237874 -0.0952676 0.0467247 0.237874 -0.0864221 0.0506854 0.237874 -0.0671836 0.0519745 0.237874 -0.057578 0.0506854 0.237874 -0.0487325 0.0467247 0.237874 -0.0485096 0.0471722 0.237874 -0.0405425 0.0416536 0.237874 -0.0276187 0.0274769 0.237874 -0.023325 0.018854 0.237874 -0.0198 -2.85742e-06 0.237874 -0.0193 -2.85742e-06 0.237874 -0.0201974 -0.00968646 0.237874 -0.023325 -0.0188597 0.237874 -0.0334238 -0.0351698 0.237874 -0.0405425 -0.0416594 0.237874 -0.0402412 -0.0420584 0.237874 -0.0864221 -0.0506911 0.237874 -0.0952676 -0.0467304 0.237874 -0.103759 -0.0420584 0.237874 -0.110946 -0.0355066 0.237874 -0.120675 -0.0188597 0.237874 -0.123311 -0.00959458 0.237874 -0.1242 -2.85742e-06 0.237874 -0.123803 -0.00968646 0.237874 -0.123311 0.00958887 0.237874 -0.1247 -2.85742e-06 0.239974 -0.1249 -2.85742e-06 0.238074 -0.123999 0.00971749 0.239974 -0.121328 0.0191068 0.239974 -0.116977 0.0278454 0.239974 -0.111094 0.0356356 0.238074 -0.103879 0.0422123 0.239974 -0.0955796 0.0473513 0.238074 -0.0955796 0.0473513 0.238074 -0.0864768 0.0508777 0.238074 -0.076881 0.0526715 0.239974 -0.0575233 0.0508777 0.238074 -0.0575233 0.0508777 0.239974 -0.0484205 0.0473513 0.238074 -0.0484205 0.0473513 0.239974 -0.0401207 0.0422123 0.239974 -0.0329065 0.0356356 0.239974 -0.0270236 0.0278454 0.239974 -0.0226723 0.0191068 0.238074 -0.0200008 0.00971749 0.239974 -0.0251531 -0.0290093 0.239974 -0.0312807 -0.0371235 0.239974 -0.0387949 -0.0439736 0.239974 -0.0474399 -0.0493264 0.239974 -0.0569212 -0.0529995 0.239974 -0.067119 -0.0526772 0.239974 -0.077084 -0.0548678 0.239974 -0.0864768 -0.0508834 0.239974 -0.0870789 -0.0529995 0.239974 -0.0965602 -0.0493264 0.239974 -0.103879 -0.042218 0.239974 -0.112719 -0.0371235 0.239974 -0.116977 -0.0278511 0.239974 -0.118847 -0.0290093 0.239974 -0.123379 -0.0199073 0.239974 -0.126162 -0.0101275 0.239974 -0.1271 -2.85742e-06 0.239974 -0.123999 0.00971749 0.239974 -0.126162 0.0101217 0.239974 -0.123379 0.0199016 0.239974 -0.118847 0.0290036 0.239974 -0.103879 0.0422123 0.239974 -0.0965602 0.0493206 0.239974 -0.0864768 0.0508777 0.239974 -0.0870789 0.0529937 0.239974 -0.076881 0.0526715 0.239974 -0.067119 0.0526715 0.239974 -0.0669161 0.0548621 0.239974 -0.0569212 0.0529937 0.239974 -0.0474399 0.0493206 0.239974 -0.0312807 0.0371178 0.239974 -0.0251531 0.0290036 0.239974 -0.0206208 0.0199016 0.239974 -0.0200008 0.00971749 0.239974 -0.0178382 0.0101217 0.239974 -0.0226723 -0.0191125 0.239974 -0.0178382 -0.0101275 0.239974 -0.0270236 -0.0278511 0.238074 -0.123379 -0.0199073 0.238074 -0.112719 -0.0371235 0.239974 -0.105205 -0.0439736 0.238074 -0.0965602 -0.0493264 0.238074 -0.0870789 -0.0529995 0.238074 -0.077084 -0.0548678 0.239974 -0.0669161 -0.0548678 0.238074 -0.0569212 -0.0529995 0.238074 -0.0474399 -0.0493264 0.238074 -0.0206208 -0.0199073 0.239974 -0.0206208 -0.0199073 0.238074 -0.0178382 -0.0101275 0.238074 -0.0169 -2.85742e-06 0.237874 -0.024983 -0.0291146 0.237874 -0.0311328 -0.0372582 0.237874 -0.0303569 -0.0379656 0.237874 -0.0386743 -0.0441332 0.237874 -0.0565791 -0.0542017 0.237874 -0.0668976 -0.055067 0.237874 -0.0668007 -0.0561125 0.237874 -0.0971174 -0.0504453 0.237874 -0.105326 -0.0441332 0.237874 -0.105959 -0.0449711 0.237874 -0.112867 -0.0372582 0.237874 -0.11991 -0.0296673 0.237874 -0.123566 -0.0199795 0.237874 -0.126358 -0.0101642 0.237874 -0.1273 -2.85742e-06 0.237874 -0.126358 0.0101585 0.237874 -0.123566 0.0199738 0.237874 -0.11991 0.0296616 0.237874 -0.105326 0.0441275 0.237874 -0.105959 0.0449654 0.237874 -0.0874209 0.054196 0.237874 -0.0771025 0.0550612 0.237874 -0.0668976 0.0550612 0.237874 -0.0668007 0.0561068 0.237874 -0.0568665 0.0531861 0.237874 -0.0473507 0.0494997 0.237874 -0.0565791 0.054196 0.237874 -0.0380416 0.0449654 0.237874 -0.0240903 0.0296616 0.237874 -0.0204343 0.0199738 0.237874 -0.0176416 0.0101585 0.237874 -0.0167 -2.85742e-06 0.237874 -0.0176416 -0.0101642 0.237874 -0.0166095 -0.0103571 0.237874 -0.12835 -2.85742e-06 0.237874 -0.127391 -0.0103571 0.237474 -0.124545 -0.0203588 0.237874 -0.124545 -0.0203588 0.237474 -0.11991 -0.0296673 0.237874 -0.113643 -0.0379656 0.237474 -0.105959 -0.0449711 0.237474 -0.0971174 -0.0504453 0.237474 -0.0874209 -0.0542017 0.237874 -0.0874209 -0.0542017 0.237474 -0.0771994 -0.0561125 0.237874 -0.0771994 -0.0561125 0.237474 -0.0668007 -0.0561125 0.237474 -0.0565791 -0.0542017 0.237474 -0.0468827 -0.0504453 0.237874 -0.0468827 -0.0504453 0.237874 -0.0380416 -0.0449711 0.237474 -0.0303569 -0.0379656 0.237874 -0.0240903 -0.0296673 0.237874 -0.0194552 -0.0203588 0.237274 -0.106079 0.045125 0.237274 -0.100625 0.0495771 0.237274 -0.0972065 0.0506186 0.237274 -0.0874757 0.0543884 0.237274 -0.0772178 0.0563059 0.237274 -0.0667823 0.0563059 0.237274 -0.0620587 0.0563774 0.237274 -0.0302091 0.0380946 0.237274 -0.028144 0.0367967 0.237274 -0.0239203 0.0297669 0.237274 -0.0224201 0.0286221 0.237274 -0.0156198 0.0099385 0.237274 -0.01475 -2.85742e-06 0.237274 -0.0156198 -0.00994422 0.237274 -0.0239203 -0.0297726 0.237274 -0.0302091 -0.0381003 0.237274 -0.028144 -0.0368024 0.237274 -0.0352005 -0.0438589 0.237274 -0.0467935 -0.0506243 0.237274 -0.0565244 -0.0543941 0.237274 -0.0667823 -0.0563116 0.237274 -0.072 -0.0572529 0.237274 -0.0772178 -0.0563116 0.237274 -0.106079 -0.0451307 0.237274 -0.113791 -0.0381003 0.237274 -0.12158 -0.0286279 0.237274 -0.124731 -0.0204311 0.237274 -0.127587 -0.0103939 0.237274 -0.12838 -0.00994422 0.237274 -0.12855 -2.85742e-06 0.237274 -0.124731 0.0204254 0.237274 -0.12008 0.0297669 0.237274 -0.125797 0.0195778 0.238274 -0.128577 0.00997323 0.238274 -0.125985 0.0196462 0.238274 -0.121753 0.0287221 0.238274 -0.116009 0.0369253 0.237474 -0.116009 0.0369253 0.237474 -0.108928 0.0440064 0.238274 -0.100725 0.0497503 0.237474 -0.100725 0.0497503 0.238274 -0.0819761 0.0565743 0.238274 -0.062024 0.0565743 0.237474 -0.072 0.0574471 0.237474 -0.062024 0.0565743 0.238274 -0.043275 0.0497503 0.237474 -0.043275 0.0497503 0.238274 -0.0350719 0.0440064 0.237474 -0.0279908 0.0369253 0.238274 -0.0279908 0.0369253 0.238274 -0.0222469 0.0287221 0.238274 -0.0180147 0.0196462 0.237474 -0.0180147 0.0196462 0.237474 -0.01455 -2.85742e-06 0.238274 -0.042675 0.0507895 0.238274 -0.0343005 0.0449256 0.238274 -0.0270715 0.0376966 0.238274 -0.0154228 0.00997323 0.238274 -0.01455 -2.85742e-06 0.238274 -0.0154228 -0.00997895 0.238274 -0.0168871 -0.0200623 0.238274 -0.0222469 -0.0287279 0.238274 -0.0270715 -0.0377024 0.238274 -0.0343005 -0.0449314 0.238274 -0.042675 -0.0507952 0.238274 -0.052351 -0.0539882 0.238274 -0.0519406 -0.0551158 0.238274 -0.0618156 -0.0577618 0.238274 -0.072 -0.0586529 0.238274 -0.0821845 -0.0577618 0.238274 -0.116009 -0.036931 0.238274 -0.121753 -0.0287279 0.238274 -0.12945 -2.85742e-06 0.238274 -0.13065 -2.85742e-06 0.238274 -0.129759 0.0101816 0.238274 -0.127113 0.0200566 0.238274 -0.122792 0.0293221 0.238274 -0.108928 0.0440064 0.238274 -0.101325 0.0507895 0.238274 -0.0916491 0.0539825 0.238274 -0.0821845 0.0577561 0.238274 -0.072 0.0574471 0.238274 -0.072 0.0586471 0.238274 -0.052351 0.0539825 0.238974 -0.129956 0.0102163 0.238974 -0.127301 0.020125 0.238974 -0.122966 0.0294221 0.238474 -0.109828 0.0450789 0.238474 -0.0921279 0.0552981 0.238474 -0.0822192 0.0579531 0.238474 -0.072 0.0588471 0.238974 -0.0617808 0.0579531 0.238974 -0.042575 0.0509627 0.238974 -0.034172 0.0450789 0.238474 -0.0269183 0.0378252 0.238974 -0.0210344 0.0294221 0.238974 -0.0140441 0.0102163 0.238474 -0.0166991 0.020125 0.238474 -0.0140441 0.0102163 0.241174 -0.0195652 0.0190819 0.238974 -0.0166991 0.020125 0.238974 -0.0269183 0.0378252 0.241174 -0.0441 0.0483214 0.238974 -0.0518722 0.0552981 0.241174 -0.0529153 0.052432 0.241174 -0.0623105 0.0549494 0.238974 -0.072 0.0588471 0.241174 -0.072 0.0557971 0.238974 -0.0822192 0.0579531 0.241174 -0.0816896 0.0549494 0.238974 -0.0921279 0.0552981 0.241174 -0.0910848 0.052432 0.241174 -0.0999 0.0483214 0.238974 -0.101425 0.0509627 0.238974 -0.109828 0.0450789 0.238974 -0.117082 0.0378252 0.241174 -0.107868 0.0427424 0.241174 -0.114745 0.0358647 0.241174 -0.120324 0.0278971 0.238974 -0.13085 -2.85742e-06 0.241174 -0.124435 0.0190819 0.241174 -0.110369 0.0170801 0.241174 -0.113082 0.00872943 0.241174 -0.126952 0.00968671 0.241174 -0.1278 -2.85742e-06 0.241174 -0.114 -2.85742e-06 0.241174 -0.126952 -0.00969243 0.241174 -0.0623105 -0.0549551 0.241174 -0.0529153 -0.0524377 0.241174 -0.0590213 -0.0399472 0.241174 -0.0438966 -0.0312149 0.241174 -0.110369 -0.0170858 0.241174 -0.120324 -0.0279029 0.241174 -0.114745 -0.0358704 0.241174 -0.107868 -0.0427481 0.241174 -0.093 -0.0363759 0.241174 -0.0999 -0.0483271 0.241174 -0.0910848 -0.0524377 0.241174 -0.0849788 -0.0399472 0.241174 -0.0816896 -0.0549551 0.241174 -0.072 -0.0558029 0.241174 -0.0763902 0.0417671 0.241174 -0.100104 0.0312092 0.241174 -0.105979 0.0246841 0.241174 -0.0236758 0.0278971 0.241174 -0.0292548 0.0358647 0.241174 -0.0361325 0.0427424 0.241174 -0.0236758 -0.0279029 0.241174 -0.0336311 -0.0170858 0.241174 -0.0195652 -0.0190876 0.241174 -0.0162 -2.85742e-06 0.241174 -0.0309178 0.00872943 0.241174 -0.0170478 0.00968671 0.241374 -0.113082 0.00872943 0.241374 -0.110369 0.0170801 0.241374 -0.105979 0.0246841 0.241374 -0.100104 0.0312092 0.241174 -0.093 0.0363702 0.241374 -0.0849788 0.0399415 0.241174 -0.0849788 0.0399415 0.241174 -0.0676098 0.0417671 0.241374 -0.0676098 0.0417671 0.241174 -0.0590213 0.0399415 0.241374 -0.051 0.0363702 0.241174 -0.051 0.0363702 0.241174 -0.0438966 0.0312092 0.241374 -0.0380213 0.0246841 0.241174 -0.0380213 0.0246841 0.241174 -0.0336311 0.0170801 0.241374 -0.0336311 0.0170801 0.241374 -0.0309178 0.00872943 0.239374 -0.113193 0.00819094 0.238974 -0.113082 0.00872943 0.239374 -0.113082 0.00872943 0.238974 -0.110369 0.0170801 0.238974 -0.093 0.0363702 0.238974 -0.100104 0.0312092 0.239374 -0.101699 0.0296956 0.239374 -0.095334 0.0349189 0.239374 -0.093 0.0363702 0.239374 -0.0880727 0.0388001 0.238974 -0.0849788 0.0399415 0.239374 -0.0849788 0.0399415 0.239374 -0.0801938 0.0411901 0.239374 -0.072 0.0419971 0.238974 -0.0763902 0.0417671 0.238974 -0.0676098 0.0417671 0.239374 -0.0676098 0.0417671 0.239374 -0.0638063 0.0411901 0.239374 -0.0590213 0.0399415 0.238974 -0.051 0.0363702 0.239374 -0.0438966 0.0312092 0.238974 -0.0438966 0.0312092 0.238974 -0.0380213 0.0246841 0.239374 -0.0380213 0.0246841 0.238974 -0.0336311 0.0170801 0.239374 -0.03 -2.85742e-06 0.238974 -0.03 -2.85742e-06 0.239374 -0.0308071 0.00819094 0.238974 -0.0309178 0.00872943 0.238674 -0.0738524 -0.0294446 0.238674 -0.0861794 -0.0291022 0.238674 -0.101236 -0.0156409 0.238674 -0.0474037 0.0162843 0.238674 -0.081116 0.0280533 0.238674 -0.0861794 0.0290965 0.238674 -0.102789 0.015401 0.238674 -0.101679 0.0202215 0.238674 -0.105736 0.0245078 0.238674 -0.08623 0.0391941 0.238674 -0.0861794 0.0374508 0.238674 -0.05115 0.0361104 0.238674 -0.038264 0.0245078 0.238674 -0.101823 -0.0291491 0.238674 -0.103832 -0.0124823 0.238674 -0.102387 -0.0110365 0.238674 -0.101857 -0.00906152 0.238674 -0.102387 -0.00708652 0.238674 -0.101679 -0.00363219 0.238674 -0.107782 -0.00564072 0.238674 -0.109228 -0.00708652 0.238674 -0.112789 -0.00867277 0.238674 -0.109757 -0.00906152 0.238674 -0.107782 -0.0124823 0.238674 -0.105807 -0.0130115 0.238674 -0.104173 -0.0185779 0.238674 -0.104461 -0.0175029 0.238674 -0.111192 -0.0142452 0.238674 -0.103386 -0.0156409 0.238674 -0.102311 -0.0153529 0.238674 -0.0967488 -0.0208016 0.238674 -0.101679 -0.0202272 0.238674 -0.0964799 -0.0202272 0.238674 -0.0987238 -0.0213308 0.238674 -0.10017 -0.0227766 0.238674 -0.100699 -0.0247516 0.238674 -0.10017 -0.0267266 0.238674 -0.101745 -0.0292286 0.238674 -0.0964799 -0.0291022 0.238674 -0.101192 -0.0297803 0.238674 -0.0999028 -0.030992 0.238674 -0.0810587 -0.0377603 0.238674 -0.0763589 -0.0414744 0.238674 -0.0776379 -0.0357853 0.238674 -0.0589914 -0.0338103 0.238674 -0.0595206 -0.0318353 0.238674 -0.070925 -0.0331409 0.238674 -0.0663622 -0.0318353 0.238674 -0.0756294 -0.0326583 0.238674 -0.073075 -0.0368648 0.238674 -0.0701381 -0.0360779 0.238674 -0.0668914 -0.0338103 0.238674 -0.06985 -0.0350029 0.238674 -0.0701381 -0.0339279 0.238674 -0.05115 -0.0361161 0.238674 -0.0609664 -0.0372311 0.238674 -0.0676412 -0.0414744 0.238674 -0.070925 -0.0368648 0.238674 -0.0422554 -0.0292286 0.238674 -0.0427898 -0.0297628 0.238674 -0.0428077 -0.0297803 0.238674 -0.0347718 -0.0110365 0.238674 -0.0342426 -0.00906152 0.238674 -0.0345463 -0.0141822 0.238674 -0.038264 -0.0245135 0.238674 -0.0312113 -0.00867277 0.238674 -0.0303 -2.85742e-06 0.238674 -0.039242 0.0258003 0.238674 -0.0428077 0.0297746 0.238674 -0.0861794 0.0296758 0.238674 -0.0899268 0.0376471 0.238674 -0.0895 0.032458 0.238674 -0.091362 0.031383 0.238674 -0.090575 0.03217 0.238674 -0.0964799 0.0296758 0.238674 -0.0999028 0.0309863 0.238674 -0.09285 0.0361104 0.238674 -0.0922244 0.0296758 0.238674 -0.0922514 0.0364495 0.238674 -0.0987238 0.0213251 0.238674 -0.104461 0.0174971 0.238674 -0.101679 0.00362648 0.238674 -0.102387 0.00708081 0.238674 -0.103832 0.0124766 0.238674 -0.101679 0.0141765 0.238674 -0.104248 0.0165643 0.238674 -0.111192 0.0142394 0.238674 -0.109228 0.0110308 0.238674 -0.0595206 0.0318295 0.238674 -0.0676412 0.0414687 0.238674 -0.0629414 0.0377545 0.238674 -0.059114 0.0396562 0.238674 -0.0550963 0.0374508 0.238674 -0.0595206 0.0357795 0.238674 -0.070925 0.0368591 0.238674 -0.0475202 0.0296758 0.238674 -0.0819377 0.0376555 0.238674 -0.0756294 0.0374508 0.238674 -0.0629414 0.0298545 0.238674 -0.0649164 0.0303837 0.238674 -0.0649164 0.0372253 0.238674 -0.0663622 0.0357795 0.238674 -0.0756294 0.0296758 0.238674 -0.073075 0.0331352 0.238674 -0.0663622 0.0318295 0.238674 -0.0668914 0.0338045 0.238674 -0.0427898 0.0297571 0.238674 -0.0422554 0.0292229 0.238674 -0.053196 0.0227273 0.238674 -0.0506721 0.0227709 0.238674 -0.048134 0.0173368 0.238674 -0.0492263 0.0213251 0.238674 -0.0472513 0.0207959 0.238674 -0.0433013 0.0247459 0.238674 -0.0429007 0.0290965 0.238674 -0.0472513 0.0286959 0.238674 -0.0506721 0.0267209 0.238674 -0.0362176 0.00563501 0.238674 -0.0345463 0.00362648 0.238674 -0.0347718 0.00708081 0.238674 -0.0342426 0.00905581 0.238674 -0.0421426 0.00905581 0.238674 -0.0429007 0.0141765 0.238674 -0.0345463 0.0141765 0.238674 -0.0362176 0.0124766 0.238674 -0.0381926 0.0130058 0.238674 -0.0416134 -0.0110365 0.238674 -0.0393446 -0.0141822 0.238674 -0.0381926 -0.0130115 0.238674 -0.0346338 -0.00734768 0.238674 -0.0357299 -0.00597329 0.238674 -0.0475202 -0.0326583 0.238674 -0.0440973 -0.030992 0.238674 -0.0452763 -0.0281724 0.238674 -0.0429007 -0.0202272 0.238674 -0.0475202 -0.0202272 0.238674 -0.0506742 -0.0203857 0.238674 -0.053196 -0.022733 0.238674 -0.0506721 -0.0227766 0.238674 -0.0506721 -0.0267266 0.238674 -0.0550963 -0.0326583 0.238674 -0.0776379 -0.0318353 0.238674 -0.0790837 -0.0303895 0.238674 -0.0810587 -0.0298603 0.238674 -0.0861794 -0.0296816 0.238674 -0.0927988 -0.0247516 0.238674 -0.093328 -0.0227766 0.238674 -0.0947738 0.0213251 0.238674 -0.0927988 0.0247459 0.238674 -0.0922244 0.0290965 0.238674 -0.0958698 0.0285968 0.238674 -0.0964799 0.0290965 0.238674 -0.101823 0.0291434 0.238674 -0.0810587 0.0298545 0.238674 -0.0790837 0.0303837 0.238674 -0.0771087 0.0338045 0.238674 -0.0774999 0.0355184 0.238674 -0.100161 0.0174971 0.238674 -0.0964799 0.0202215 0.238674 -0.102311 0.0196471 0.238674 -0.103386 0.0193591 0.238674 -0.104173 0.0185721 0.238674 -0.0935046 0.0201913 0.238674 -0.0967488 0.0207959 0.238674 -0.09319 0.0264597 0.238674 -0.0895 0.028158 0.238674 -0.0427642 0.0156352 0.238674 -0.0406142 0.0156352 0.238674 -0.0398272 0.0164221 0.238674 -0.0398272 0.0185721 0.238674 -0.0393446 0.0202215 0.238674 -0.0406142 0.0193591 0.238674 -0.0429007 0.0202215 0.238674 -0.0427642 0.0193591 0.238674 -0.0475202 0.0202215 0.238674 -0.0435511 0.0164221 0.238674 -0.0393446 0.0141765 0.238674 -0.0395392 0.0174971 0.238674 -0.0417515 -0.00734768 0.238674 -0.0427327 -0.00370019 0.238674 -0.0445716 -0.0108625 0.238674 -0.0429007 -0.0141822 0.238674 -0.048134 -0.0173425 0.238674 -0.0427642 -0.0193648 0.238674 -0.0429007 -0.0291022 0.238674 -0.0393446 -0.0202272 0.238674 -0.0406142 -0.0156409 0.238674 -0.0416892 -0.0153529 0.238674 -0.0395392 -0.0175029 0.238674 -0.0895 -0.0324637 0.238674 -0.0861794 -0.0326583 0.238674 -0.088425 -0.0321757 0.238674 -0.0922244 -0.0291022 0.238674 -0.0922244 -0.0296816 0.238674 -0.09165 -0.0303137 0.238674 -0.091362 -0.0313887 0.238674 -0.081116 -0.028059 0.238674 -0.0923279 -0.0213811 0.238674 -0.105736 -0.0245135 0.238674 -0.102311 -0.0196529 0.238674 -0.101236 -0.0193648 0.238674 -0.0878069 0.0249048 0.238674 -0.0393446 -0.00363219 0.238674 -0.0393446 0.00362648 0.238674 -0.0416134 0.00708081 0.238674 -0.0756294 -0.0296816 0.238674 -0.0978511 -0.0142146 0.238674 -0.101679 -0.0141822 0.238674 -0.100573 0.00733349 0.238674 -0.091362 0.029233 0.238674 -0.101745 0.0292229 0.238674 -0.0475202 0.0290965 0.238674 -0.0550963 0.0296758 0.238674 -0.0664723 0.0289746 0.238674 -0.0550963 0.0290965 0.238674 -0.0594396 0.0266895 0.238674 -0.038075 0.0018591 0.238674 -0.0345463 -0.00363219 0.238674 -0.037 0.00214714 0.238674 -0.03915 -2.85742e-06 0.238674 -0.035925 -0.00186481 0.238674 -0.0351381 -0.00107786 0.238674 -0.0351381 0.00107214 0.238674 -0.035925 0.0018591 0.238674 -0.0964799 -0.0326583 0.238674 -0.0964799 -0.0296816 0.238674 -0.0922244 -0.0326583 0.238674 -0.0947738 -0.0281724 0.238674 -0.0595206 -0.0357853 0.238674 -0.0475202 -0.0296816 0.238674 -0.0550963 -0.0296816 0.238674 -0.0550963 -0.0291022 0.238674 -0.0492263 -0.0281724 0.238674 -0.0475202 -0.0291022 0.238674 -0.0472513 -0.0287016 0.239374 -0.0308071 -0.00819665 0.239374 -0.0331971 -0.0160756 0.239374 -0.0336311 -0.0170858 0.238974 -0.0336311 -0.0170858 0.239374 -0.0486661 -0.0349246 0.239374 -0.0380213 -0.0246898 0.239374 -0.0438966 -0.0312149 0.239374 -0.0590213 -0.0399472 0.239374 -0.0676098 -0.0417728 0.238974 -0.0676098 -0.0417728 0.239374 -0.072 -0.0420029 0.238974 -0.0849788 -0.0399472 0.239374 -0.0849788 -0.0399472 0.239374 -0.0880727 -0.0388058 0.239374 -0.093 -0.0363759 0.238974 -0.093 -0.0363759 0.238974 -0.100104 -0.0312149 0.238974 -0.105979 -0.0246898 0.238974 -0.110369 -0.0170858 0.239374 -0.114 -2.85742e-06 0.238974 -0.113082 -0.00873515 0.241174 -0.03 -2.85742e-06 0.241374 -0.0336311 -0.0170858 0.241174 -0.0309178 -0.00873515 0.241174 -0.0380213 -0.0246898 0.241374 -0.0438966 -0.0312149 0.241374 -0.051 -0.0363759 0.241174 -0.051 -0.0363759 0.241174 -0.0676098 -0.0417728 0.241374 -0.0849788 -0.0399472 0.241174 -0.0763902 -0.0417728 0.241174 -0.100104 -0.0312149 0.241374 -0.100104 -0.0312149 0.241374 -0.105979 -0.0246898 0.241174 -0.105979 -0.0246898 0.241174 -0.113082 -0.00873515 0.238974 -0.129956 -0.0102221 0.241174 -0.124435 -0.0190876 0.238974 -0.122966 -0.0294279 0.238974 -0.101425 -0.0509685 0.238974 -0.0617808 -0.0579588 0.238974 -0.0518722 -0.0553038 0.241174 -0.0441 -0.0483271 0.238974 -0.034172 -0.0450846 0.241174 -0.0361325 -0.0427481 0.238974 -0.0269183 -0.0378309 0.241174 -0.0292548 -0.0358704 0.241174 -0.0170478 -0.00969243 0.238974 -0.01315 -2.85742e-06 0.238974 -0.0140441 -0.0102221 0.238974 -0.0166991 -0.0201307 0.238974 -0.0210344 -0.0294279 0.238474 -0.0210344 -0.0294279 0.238474 -0.0269183 -0.0378309 0.238974 -0.042575 -0.0509685 0.238474 -0.0518722 -0.0553038 0.238974 -0.072 -0.0588529 0.238974 -0.0822192 -0.0579588 0.238974 -0.0921279 -0.0553038 0.238474 -0.0921279 -0.0553038 0.238974 -0.109828 -0.0450846 0.238474 -0.109828 -0.0450846 0.238474 -0.117082 -0.0378309 0.238974 -0.117082 -0.0378309 0.238974 -0.127301 -0.0201307 0.238474 -0.129956 -0.0102221 0.238274 -0.0180147 -0.0196519 0.238274 -0.0279908 -0.036931 0.238274 -0.0350719 -0.0440121 0.237474 -0.0350719 -0.0440121 0.237474 -0.043275 -0.049756 0.238274 -0.043275 -0.049756 0.238274 -0.062024 -0.0565801 0.237474 -0.052351 -0.0539882 0.238274 -0.072 -0.0574529 0.237474 -0.062024 -0.0565801 0.238274 -0.0819761 -0.0565801 0.237474 -0.0819761 -0.0565801 0.238274 -0.0916491 -0.0539882 0.237474 -0.0916491 -0.0539882 0.238274 -0.100725 -0.049756 0.238274 -0.108928 -0.0440121 0.237474 -0.116009 -0.036931 0.237474 -0.121753 -0.0287279 0.238274 -0.125985 -0.0196519 0.238274 -0.128577 -0.00997895 0.237474 -0.12945 -2.85742e-06 0.237474 -0.01565 -2.85742e-06 0.237874 -0.01565 -2.85742e-06 0.237474 -0.0166095 0.0103514 0.237874 -0.0166095 0.0103514 0.237474 -0.0194552 0.0203531 0.237874 -0.0194552 0.0203531 0.237474 -0.0240903 0.0296616 0.237874 -0.0303569 0.0379599 0.237474 -0.0468827 0.0504396 0.237874 -0.0468827 0.0504396 0.237474 -0.0565791 0.054196 0.237474 -0.0668007 0.0561068 0.237474 -0.0874209 0.054196 0.237874 -0.0771994 0.0561068 0.237474 -0.0971174 0.0504396 0.237874 -0.0971174 0.0504396 0.237474 -0.105959 0.0449654 0.237474 -0.113643 0.0379599 0.237874 -0.113643 0.0379599 0.237474 -0.11991 0.0296616 0.237474 -0.124545 0.0203531 0.237874 -0.124545 0.0203531 0.237874 -0.127391 0.0103514 0.239974 -0.0169 -2.85742e-06 0.238074 -0.0312807 0.0371178 0.238074 -0.0474399 0.0493206 0.239974 -0.0387949 0.0439679 0.238074 -0.0569212 0.0529937 0.238074 -0.0669161 0.0548621 0.239974 -0.077084 0.0548621 0.238074 -0.0965602 0.0493206 0.238074 -0.112719 0.0371178 0.239974 -0.105205 0.0439679 0.239974 -0.112719 0.0371178 0.238074 -0.123379 0.0199016 0.238074 -0.1271 -2.85742e-06 0.239974 -0.0191 -2.85742e-06 0.239974 -0.0200008 -0.00972321 0.238074 -0.0226723 -0.0191125 0.238074 -0.0329065 -0.0356414 0.239974 -0.0329065 -0.0356414 0.239974 -0.0401207 -0.042218 0.238074 -0.0401207 -0.042218 0.239974 -0.0484205 -0.047357 0.239974 -0.0575233 -0.0508834 0.238074 -0.0484205 -0.047357 0.238074 -0.0575233 -0.0508834 0.239974 -0.076881 -0.0526772 0.239974 -0.0955796 -0.047357 0.238074 -0.0955796 -0.047357 0.238074 -0.103879 -0.042218 0.239974 -0.111094 -0.0356414 0.238074 -0.111094 -0.0356414 0.238074 -0.116977 -0.0278511 0.239974 -0.121328 -0.0191125 0.238074 -0.121328 -0.0191125 0.238074 -0.123999 -0.00972321 0.239974 -0.123999 -0.00972321 0.240174 -0.02 -2.85742e-06 0.240174 -0.0208854 0.00955212 0.238074 -0.0235115 0.0187817 0.238074 -0.0277888 0.0273716 0.240174 -0.0277888 0.0273716 0.238074 -0.0335716 0.0350293 0.238074 -0.040663 0.041494 0.238074 -0.0488216 0.0465456 0.240174 -0.0577696 0.0500121 0.240174 -0.076798 0.0517753 0.238074 -0.0862305 0.0500121 0.240174 -0.0951784 0.0465456 0.238074 -0.103337 0.041494 0.238074 -0.110429 0.0350293 0.240174 -0.103337 0.041494 0.240174 -0.110429 0.0350293 0.238074 -0.120489 0.0187817 0.240174 -0.0630259 -0.045119 0.240174 -0.026 -2.85742e-06 0.240174 -0.0337524 -0.0255591 0.239374 -0.0370783 -0.0233368 0.239374 -0.0309178 -0.00873515 0.240174 -0.0394731 -0.0325298 0.239374 -0.0423016 -0.0297013 0.240174 -0.0543966 -0.0425013 0.239374 -0.0638063 -0.0411958 0.239374 -0.0559273 -0.0388058 0.240174 -0.0464438 -0.0382505 0.239374 -0.051 -0.0363759 0.239374 -0.0763902 -0.0417728 0.239374 -0.0801938 -0.0411958 0.240174 -0.0809742 -0.045119 0.240174 -0.0896035 -0.0425013 0.240174 -0.0975563 -0.0382505 0.239374 -0.095334 -0.0349246 0.239374 -0.100104 -0.0312149 0.240174 -0.104527 -0.0325298 0.239374 -0.101699 -0.0297013 0.239374 -0.105979 -0.0246898 0.240174 -0.110248 -0.0255591 0.239374 -0.106922 -0.0233368 0.239374 -0.110369 -0.0170858 0.239374 -0.110803 -0.0160756 0.240174 -0.114499 -0.0176063 0.239374 -0.113082 -0.00873515 0.240174 -0.117116 -0.00897701 0.239374 -0.113193 -0.00819665 0.240174 -0.118 -2.85742e-06 0.238674 -0.100449 -0.0164279 0.239024 -0.100449 -0.0164279 0.239024 -0.101236 -0.0156409 0.239024 -0.102311 -0.0153529 0.238674 -0.104173 -0.0164279 0.239024 -0.100161 -0.0175029 0.241674 -0.098154 -0.0151029 0.239024 -0.103386 -0.0156409 0.241674 -0.102311 -0.0127029 0.239024 -0.104173 -0.0164279 0.239024 -0.104461 -0.0175029 0.241674 -0.106468 -0.0151029 0.241674 -0.107111 -0.0175029 0.239024 -0.08735 -0.0303137 0.238674 -0.0876381 -0.0292387 0.238674 -0.088425 -0.0284518 0.239024 -0.0876381 -0.0292387 0.239024 -0.088425 -0.0284518 0.238674 -0.0895 -0.0281637 0.239024 -0.0895 -0.0281637 0.238674 -0.090575 -0.0284518 0.238674 -0.091362 -0.0292387 0.239024 -0.091362 -0.0292387 0.241674 -0.0943 -0.0303137 0.239024 -0.09165 -0.0303137 0.241674 -0.0941783 -0.0292394 0.241674 -0.0871 -0.0261568 0.239024 -0.090575 -0.0284518 0.241674 -0.0919 -0.0261568 0.238674 -0.072 -0.0328529 0.238674 -0.073075 -0.0331409 0.238674 -0.073862 -0.0339279 0.239024 -0.073862 -0.0339279 0.239024 -0.0701381 -0.0339279 0.241674 -0.0678431 -0.0326029 0.239024 -0.070925 -0.0331409 0.239024 -0.072 -0.0328529 0.239024 -0.073075 -0.0331409 0.241674 -0.076157 -0.0326029 0.238674 -0.0398272 -0.0164279 0.239024 -0.0403486 -0.0158219 0.239024 -0.0406142 -0.0156409 0.239024 -0.0416892 -0.0153529 0.238674 -0.0427642 -0.0156409 0.239024 -0.0430297 -0.0158219 0.239024 -0.0438392 -0.0175029 0.238674 -0.0438392 -0.0175029 0.239024 -0.0436262 -0.01657 0.238674 -0.0435511 -0.0164279 0.241674 -0.0460138 -0.0154202 0.239024 -0.0435511 -0.0164279 0.241674 -0.0446819 -0.0137501 0.239024 -0.0427642 -0.0156409 0.239024 -0.0421676 -0.0154068 0.239024 -0.0412107 -0.0154068 0.241674 -0.0386964 -0.0137501 0.239024 -0.0395392 -0.0175029 0.241674 -0.0368892 -0.0175029 0.239024 -0.0397521 -0.01657 0.239024 -0.0398272 -0.0164279 0.239024 -0.03485 -2.85742e-06 0.239024 -0.0351381 0.00107214 0.239024 -0.037 0.00214714 0.239024 -0.038075 0.0018591 0.238674 -0.038862 0.00107214 0.239024 -0.03915 -2.85742e-06 0.241674 -0.0322 -2.85742e-06 0.241674 -0.0328431 0.00239714 0.239024 -0.035925 0.0018591 0.241674 -0.0346 0.00415406 0.241674 -0.037 0.00479714 0.239024 -0.038862 0.00107214 0.241674 -0.041157 0.00239714 0.239024 -0.0398272 0.0185721 0.238674 -0.0416892 0.0196471 0.239024 -0.0406142 0.0193591 0.239024 -0.0416892 0.0196471 0.239024 -0.0427642 0.0193591 0.238674 -0.0435511 0.0185721 0.238674 -0.0438392 0.0174971 0.241674 -0.0368892 0.0174971 0.241674 -0.0375322 0.0198971 0.241674 -0.0416892 0.0222971 0.239024 -0.0435511 0.0185721 0.241674 -0.0440892 0.0216541 0.241674 -0.0458461 0.0198971 0.238674 -0.0701381 0.0360721 0.239024 -0.0701381 0.0360721 0.238674 -0.072 0.0371471 0.238674 -0.073075 0.0368591 0.239024 -0.072 0.0371471 0.238674 -0.073862 0.0360721 0.238674 -0.07415 0.0349971 0.239024 -0.06985 0.0349971 0.241674 -0.0672 0.0349971 0.239024 -0.070925 0.0368591 0.241674 -0.0696 0.0391541 0.239024 -0.073075 0.0368591 0.241674 -0.0744 0.0391541 0.239024 -0.073862 0.0360721 0.239024 -0.07415 0.0349971 0.238674 -0.08735 0.030308 0.239024 -0.08735 0.030308 0.239024 -0.0876381 0.031383 0.238674 -0.0876381 0.031383 0.238674 -0.088425 0.03217 0.239024 -0.0895 0.032458 0.239024 -0.090575 0.03217 0.238674 -0.09165 0.030308 0.239024 -0.088425 0.03217 0.241674 -0.0871 0.034465 0.239024 -0.091362 0.031383 0.241674 -0.0919 0.034465 0.241674 -0.093657 0.032708 0.239024 -0.09165 0.030308 0.238674 -0.100449 0.0185721 0.239024 -0.100449 0.0185721 0.238674 -0.101236 0.0193591 0.239024 -0.101236 0.0193591 0.239024 -0.102311 0.0196471 0.239024 -0.103386 0.0193591 0.241674 -0.0975109 0.0174971 0.241674 -0.098154 0.0198971 0.241674 -0.0999109 0.0216541 0.241674 -0.102311 0.0222971 0.239024 -0.104173 0.0185721 0.241674 -0.106468 0.0198971 0.239024 -0.104461 0.0174971 0.238874 -0.10256 -0.00718652 0.238874 -0.103932 -0.00581393 0.241474 -0.103932 -0.00581393 0.241474 -0.107682 -0.00581393 0.238874 -0.109055 -0.00718652 0.241474 -0.109055 -0.00718652 0.238874 -0.0935012 -0.0228766 0.241474 -0.0929988 -0.0247516 0.241474 -0.0948738 -0.021504 0.241474 -0.0967488 -0.0210016 0.241474 -0.0986238 -0.021504 0.238874 -0.0986238 -0.021504 0.241474 -0.0999964 -0.0228766 0.241474 -0.100499 -0.0247516 0.238874 -0.0773087 -0.0338103 0.241474 -0.0778111 -0.0319353 0.238874 -0.0791837 -0.0305627 0.238874 -0.0810587 -0.0300603 0.238874 -0.0829337 -0.0305627 0.238874 -0.0843063 -0.0319353 0.241474 -0.0829337 -0.0305627 0.238874 -0.0848087 -0.0338103 0.238874 -0.0591914 -0.0338103 0.241474 -0.0629414 -0.0300603 0.238874 -0.0648164 -0.0305627 0.241474 -0.0648164 -0.0305627 0.238874 -0.066189 -0.0319353 0.238874 -0.0440037 -0.0228766 0.241474 -0.0435013 -0.0247516 0.241474 -0.0440037 -0.0228766 0.241474 -0.0453763 -0.021504 0.238874 -0.0453763 -0.021504 0.241474 -0.0472513 -0.0210016 0.241474 -0.0491263 -0.021504 0.238874 -0.0504989 -0.0228766 0.241474 -0.0504989 -0.0228766 0.241474 -0.0344426 -0.00906152 0.238874 -0.0358546 -0.00612966 0.241474 -0.034814 -0.00743446 0.241474 -0.0358546 -0.00612966 0.238874 -0.0405307 -0.00612966 0.241474 -0.0415713 -0.00743446 0.241474 -0.034945 0.0109308 0.238874 -0.0363176 0.0123034 0.238874 -0.0381926 0.0128058 0.241474 -0.0381926 0.0128058 0.241474 -0.0414402 0.0109308 0.241474 -0.0419426 0.00905581 0.238874 -0.0435013 0.0247459 0.241474 -0.0435013 0.0247459 0.238874 -0.0472513 0.0284959 0.241474 -0.0453763 0.0279935 0.241474 -0.0472513 0.0284959 0.238874 -0.0491263 0.0279935 0.238874 -0.0504989 0.0266209 0.238874 -0.0596938 0.0356795 0.238874 -0.0629414 0.0375545 0.238874 -0.0648164 0.0370521 0.238874 -0.066189 0.0356795 0.241474 -0.066189 0.0356795 0.238874 -0.0666914 0.0338045 0.238874 -0.0776801 0.0354316 0.241474 -0.0787206 0.0367364 0.241474 -0.0802243 0.0374605 0.241474 -0.0844373 0.0354316 0.238874 -0.0844373 0.0354316 0.241474 -0.0929988 0.0247459 0.241474 -0.0933701 0.0263729 0.238874 -0.0959143 0.0284019 0.238874 -0.0975832 0.0284019 0.241474 -0.0975832 0.0284019 0.238874 -0.0990869 0.0276777 0.241474 -0.0990869 0.0276777 0.238874 -0.100499 0.0247459 0.241474 -0.10256 0.0109308 0.238874 -0.10256 0.0109308 0.238874 -0.107682 0.0123034 0.241474 -0.109055 0.0109308 0.238874 -0.109557 0.00905581 0.238974 -0.0309178 -0.00873515 0.238674 -0.039242 -0.025806 0.238674 -0.0344469 -0.0181317 0.238674 -0.0339052 -0.0169638 0.238974 -0.0380213 -0.0246898 0.238974 -0.0763902 -0.0417728 0.238674 -0.059114 -0.0396619 0.238974 -0.0590213 -0.0399472 0.238974 -0.051 -0.0363759 0.238974 -0.0438966 -0.0312149 0.238674 -0.09285 -0.0361161 0.238674 -0.08623 -0.0391998 0.238674 -0.0848861 -0.0396619 0.238674 -0.110095 -0.0169638 0.238974 -0.114 -2.85742e-06 0.241374 -0.114 -2.85742e-06 0.241374 -0.113082 -0.00873515 0.241374 -0.110369 -0.0170858 0.241374 -0.093 -0.0363759 0.241674 -0.0999028 -0.030992 0.241674 -0.100853 -0.0301089 0.241374 -0.0590213 -0.0399472 0.241374 -0.0676098 -0.0417728 0.241674 -0.0676412 -0.0414744 0.241674 -0.0763589 -0.0414744 0.241374 -0.0763902 -0.0417728 0.241674 -0.0440973 -0.030992 0.241674 -0.0425995 -0.0295748 0.241674 -0.0424246 -0.0293998 0.241374 -0.0380213 -0.0246898 0.241674 -0.0312635 -0.00891497 0.241374 -0.0309178 -0.00873515 0.241674 -0.0339052 -0.0169638 0.241474 -0.0596938 -0.0319353 0.241474 -0.0610664 -0.0305627 0.241474 -0.066189 -0.0319353 0.241674 -0.0649164 -0.0303895 0.241674 -0.0433013 -0.0247516 0.241674 -0.0438305 -0.0227766 0.241674 -0.0492263 -0.0213308 0.241674 -0.0342426 -0.00906152 0.241674 -0.0346338 -0.00734768 0.241674 -0.0357299 -0.00597329 0.241474 -0.0373582 -0.00540554 0.241474 -0.0390271 -0.00540554 0.241474 -0.0405307 -0.00612966 0.241674 -0.0417515 -0.00734768 0.241474 -0.0419426 -0.00906152 0.241474 -0.0344426 0.00905581 0.241474 -0.0363176 0.0123034 0.241674 -0.0347718 0.0110308 0.241674 -0.0381926 0.0130058 0.241474 -0.0400676 0.0123034 0.241674 -0.0401676 0.0124766 0.241674 -0.0416134 0.0110308 0.241474 -0.0440037 0.0266209 0.241674 -0.0433013 0.0247459 0.241674 -0.0452763 0.0281667 0.241674 -0.0472513 0.0286959 0.241674 -0.0492263 0.0281667 0.241474 -0.0491263 0.0279935 0.241474 -0.0504989 0.0266209 0.241474 -0.0510013 0.0247459 0.241674 -0.0506721 0.0267209 0.241474 -0.0596938 0.0356795 0.241674 -0.0595206 0.0357795 0.241474 -0.0610664 0.0370521 0.241474 -0.0629414 0.0375545 0.241474 -0.0648164 0.0370521 0.241674 -0.0649164 0.0372253 0.241474 -0.0666914 0.0338045 0.241474 -0.0776801 0.0354316 0.241674 -0.0785959 0.0368928 0.241474 -0.0818932 0.0374605 0.241474 -0.0833968 0.0367364 0.241674 -0.0835215 0.0368928 0.241674 -0.0846175 0.0355184 0.241474 -0.0848087 0.0338045 0.241674 -0.09319 0.0264597 0.241474 -0.0944107 0.0276777 0.241674 -0.094286 0.0278341 0.241474 -0.0959143 0.0284019 0.241674 -0.0958698 0.0285968 0.241674 -0.0976277 0.0285968 0.241674 -0.0992116 0.0278341 0.241474 -0.100127 0.0263729 0.241474 -0.100499 0.0247459 0.241474 -0.102057 0.00905581 0.241674 -0.101857 0.00905581 0.241674 -0.102387 0.0110308 0.241474 -0.103932 0.0123034 0.241474 -0.105807 0.0128058 0.241674 -0.103832 0.0124766 0.241474 -0.107682 0.0123034 0.241674 -0.107782 0.0124766 0.241674 -0.109228 0.0110308 0.241474 -0.109557 0.00905581 0.241674 -0.109757 0.00905581 0.241474 -0.10256 -0.00718652 0.241674 -0.103832 -0.00564072 0.241474 -0.105807 -0.00531152 0.241674 -0.105807 -0.00511152 0.241674 -0.109757 -0.00906152 0.241674 -0.0927988 -0.0247516 0.241474 -0.0935012 -0.0228766 0.241674 -0.093328 -0.0227766 0.241674 -0.0947738 -0.0213308 0.241674 -0.0967488 -0.0208016 0.241474 -0.0773087 -0.0338103 0.241674 -0.0776379 -0.0318353 0.241474 -0.0791837 -0.0305627 0.241474 -0.0810587 -0.0300603 0.241674 -0.0790837 -0.0303895 0.241474 -0.0843063 -0.0319353 0.241474 -0.0848087 -0.0338103 0.241674 -0.0844795 -0.0318353 0.238874 -0.0610664 0.0370521 0.238674 -0.0609664 0.0372253 0.238674 -0.0512013 0.0247459 0.238674 -0.0492263 0.0281667 0.238874 -0.0453763 0.0279935 0.238674 -0.0452763 0.0281667 0.238874 -0.0440037 0.0266209 0.238674 -0.0438305 0.0267209 0.238874 -0.0414402 0.0109308 0.238674 -0.0416134 0.0110308 0.238874 -0.0400676 0.0123034 0.238674 -0.0401676 0.0124766 0.238874 -0.034945 0.0109308 0.238674 -0.0347718 0.0110308 0.238874 -0.0344426 0.00905581 0.238874 -0.0415713 -0.00743446 0.238674 -0.0406554 -0.00597329 0.238874 -0.0390271 -0.00540554 0.238674 -0.0390716 -0.00521056 0.238874 -0.0373582 -0.00540554 0.238674 -0.0373137 -0.00521056 0.238874 -0.034814 -0.00743446 0.238874 -0.0491263 -0.021504 0.238674 -0.0492263 -0.0213308 0.238874 -0.0472513 -0.0210016 0.238674 -0.0472513 -0.0208016 0.238674 -0.0452763 -0.0213308 0.238674 -0.0438305 -0.0227766 0.238674 -0.0433013 -0.0247516 0.238874 -0.0666914 -0.0338103 0.238674 -0.0649164 -0.0303895 0.238874 -0.0629414 -0.0300603 0.238874 -0.0610664 -0.0305627 0.238674 -0.0629414 -0.0298603 0.238674 -0.0609664 -0.0303895 0.238874 -0.0596938 -0.0319353 0.238674 -0.0844795 -0.0318353 0.238674 -0.0830337 -0.0303895 0.238874 -0.0778111 -0.0319353 0.238874 -0.100499 -0.0247516 0.238874 -0.0999964 -0.0228766 0.238874 -0.0967488 -0.0210016 0.238874 -0.0948738 -0.021504 0.238674 -0.0947738 -0.0213308 0.238874 -0.109557 -0.00906152 0.238874 -0.107682 -0.00581393 0.238874 -0.105807 -0.00531152 0.238674 -0.105807 -0.00511152 0.238674 -0.103832 -0.00564072 0.238874 -0.109055 0.0109308 0.238874 -0.105807 0.0128058 0.238674 -0.107782 0.0124766 0.238874 -0.103932 0.0123034 0.238674 -0.105807 0.0130058 0.238674 -0.102387 0.0110308 0.238874 -0.100127 0.0263729 0.238674 -0.100308 0.0264597 0.238674 -0.0992116 0.0278341 0.238674 -0.0976277 0.0285968 0.238874 -0.0944107 0.0276777 0.238874 -0.0933701 0.0263729 0.238674 -0.094286 0.0278341 0.238674 -0.0850087 0.0338045 0.238674 -0.0846175 0.0355184 0.238674 -0.0835215 0.0368928 0.238874 -0.0833968 0.0367364 0.238874 -0.0818932 0.0374605 0.238874 -0.0802243 0.0374605 0.238674 -0.0801798 0.0376555 0.238874 -0.0787206 0.0367364 0.238674 -0.0785959 0.0368928 0.238274 -0.01335 -2.85742e-06 0.238474 -0.0140441 -0.0102221 0.238274 -0.0142411 -0.0101873 0.238474 -0.0166991 -0.0201307 0.238274 -0.0212077 -0.0293279 0.238474 -0.034172 -0.0450846 0.238474 -0.042575 -0.0509685 0.238474 -0.0617808 -0.0579588 0.238474 -0.072 -0.0588529 0.238474 -0.0822192 -0.0579588 0.238274 -0.0920595 -0.0551158 0.238474 -0.101425 -0.0509685 0.238274 -0.101325 -0.0507952 0.238274 -0.1097 -0.0449314 0.238474 -0.122966 -0.0294279 0.238274 -0.116929 -0.0377024 0.238274 -0.122792 -0.0293279 0.238474 -0.127301 -0.0201307 0.238274 -0.127113 -0.0200623 0.238274 -0.129759 -0.0101873 0.238074 -0.123115 0.00955212 0.238074 -0.116211 0.0273716 0.237874 -0.116381 0.0274769 0.237874 -0.103458 0.0416536 0.238074 -0.0951784 0.0465456 0.238074 -0.076798 0.0517753 0.237874 -0.0862852 0.0502044 0.237874 -0.0768164 0.0519745 0.238074 -0.0672021 0.0517753 0.238074 -0.0577696 0.0500121 0.237874 -0.0577148 0.0502044 0.237874 -0.0334238 0.0351641 0.237874 -0.0206888 0.00958887 0.238074 -0.0208854 0.00955212 0.238074 -0.0191 -2.85742e-06 0.238074 -0.0200008 -0.00972321 0.238074 -0.0270236 -0.0278511 0.237874 -0.0228588 -0.0190403 0.237874 -0.0271936 -0.0277458 0.237874 -0.0330543 -0.0355066 0.237874 -0.0485096 -0.047178 0.237874 -0.057578 -0.0506911 0.238074 -0.067119 -0.0526772 0.237874 -0.0671375 -0.052478 0.238074 -0.076881 -0.0526772 0.237874 -0.0768626 -0.052478 0.238074 -0.0864768 -0.0508834 0.237874 -0.0954905 -0.047178 0.237874 -0.116806 -0.0277458 0.237874 -0.121141 -0.0190403 0.238074 -0.1249 -2.85742e-06 0.237474 -0.0154228 -0.00997895 0.237474 -0.0180147 -0.0196519 0.237474 -0.0222469 -0.0287279 0.237274 -0.0182026 -0.0195835 0.237274 -0.0224201 -0.0286279 0.237474 -0.0279908 -0.036931 0.237274 -0.043375 -0.0495828 0.237274 -0.0524194 -0.0538003 0.237474 -0.072 -0.0574529 0.237274 -0.0620587 -0.0563831 0.237274 -0.0819414 -0.0563831 0.237274 -0.0915807 -0.0538003 0.237474 -0.100725 -0.049756 0.237274 -0.100625 -0.0495828 0.237474 -0.108928 -0.0440121 0.237274 -0.1088 -0.0438589 0.237274 -0.115856 -0.0368024 0.237274 -0.125797 -0.0195835 0.237474 -0.125985 -0.0196519 0.237474 -0.128577 -0.00997895 0.237474 -0.12835 -2.85742e-06 0.237474 -0.127391 0.0103514 0.237274 -0.127587 0.0103882 0.237274 -0.113791 0.0380946 0.237474 -0.0771994 0.0561068 0.237274 -0.0565244 0.0543884 0.237474 -0.0380416 0.0449654 0.237274 -0.0467935 0.0506186 0.237274 -0.0379211 0.045125 0.237474 -0.0303569 0.0379599 0.237274 -0.0192687 0.0204254 0.237274 -0.0164129 0.0103882 0.237274 -0.01545 -2.85742e-06 0.238074 -0.126162 0.0101217 0.237874 -0.119017 0.0291088 0.238074 -0.118847 0.0290036 0.237874 -0.112867 0.0372525 0.238074 -0.105205 0.0439679 0.237874 -0.0966494 0.0494997 0.238074 -0.0870789 0.0529937 0.237874 -0.0871336 0.0531861 0.238074 -0.077084 0.0548621 0.238074 -0.0387949 0.0439679 0.237874 -0.0386743 0.0441275 0.237874 -0.0311328 0.0372525 0.238074 -0.0251531 0.0290036 0.237874 -0.024983 0.0291088 0.238074 -0.0206208 0.0199016 0.238074 -0.0178382 0.0101217 0.241674 -0.0993182 0.0137444 0.241674 -0.093657 0.027908 0.241674 -0.0959055 0.0169008 0.241674 -0.03125 0.00495148 0.241674 -0.0339052 0.0169581 0.241674 -0.09285 0.0361104 0.241674 -0.101278 0.0292752 0.241674 -0.0355659 -0.0169066 0.241674 -0.0312377 -0.00879606 0.241674 -0.0312113 -0.00867277 0.241674 -0.0355659 -0.00495719 0.241674 -0.03125 -0.00495719 0.241674 -0.0609664 -0.0303895 0.241674 -0.0550963 -0.0300316 0.241674 -0.0595206 -0.0318353 0.241674 -0.0488452 -0.0300316 0.241674 -0.0431467 -0.0301089 0.241674 -0.0663622 -0.0318353 0.241674 -0.0696 -0.0308459 0.241674 -0.0744 -0.0391598 0.241674 -0.0769667 -0.041406 0.241674 -0.076157 -0.0374029 0.241674 -0.0589914 -0.0338103 0.241674 -0.05115 -0.0361161 0.241674 -0.059114 -0.0396619 0.241674 -0.0609664 -0.0372311 0.241674 -0.0629414 -0.0377603 0.241674 -0.0678431 -0.0374029 0.241674 -0.0672 -0.0350029 0.241674 -0.0649164 -0.0372311 0.241674 -0.0668914 -0.0338103 0.241674 -0.0769544 -0.0292809 0.241674 -0.0771087 -0.0338103 0.241674 -0.0769544 -0.0300316 0.241674 -0.0790837 -0.0372311 0.241674 -0.0848861 -0.0396619 0.241674 -0.09285 -0.0361161 0.241674 -0.0830337 -0.0372311 0.241674 -0.0830337 -0.0303895 0.241674 -0.101576 -0.0293998 0.241674 -0.101401 -0.0295748 0.241674 -0.101278 -0.0292809 0.241674 -0.106468 -0.0199029 0.241674 -0.101857 -0.00906152 0.241674 -0.101278 -0.00890719 0.241674 -0.102387 -0.00708652 0.241674 -0.107782 -0.00564072 0.241674 -0.1137 -2.85742e-06 0.241674 -0.110095 -0.0169638 0.241674 -0.109228 -0.0110365 0.241674 -0.112789 -0.00867277 0.241674 -0.109228 -0.00708652 0.241674 -0.101278 0.00495148 0.241674 -0.102387 0.00708081 0.241674 -0.105807 0.00510581 0.241674 -0.101278 -0.00495719 0.241674 -0.112789 0.00866706 0.241674 -0.109228 0.00708081 0.241674 -0.105807 0.0130058 0.241674 -0.105304 0.0137444 0.241674 -0.110095 0.0169581 0.241674 -0.106636 0.0154145 0.241674 -0.0819377 0.0376555 0.241674 -0.0769544 0.0364313 0.241674 -0.076157 0.0373971 0.241674 -0.072 0.0397971 0.241674 -0.0678431 0.0373971 0.241674 -0.0488452 0.0292752 0.241674 -0.0342426 0.00905581 0.241674 -0.0472513 -0.0208016 0.241674 -0.0438305 -0.0267266 0.241674 -0.0488452 -0.0292809 0.241674 -0.0550963 -0.0292809 0.241674 -0.0492263 -0.0281724 0.241674 -0.0550963 -0.0239083 0.241674 -0.0506721 -0.0267266 0.241674 -0.0338806 -0.0169085 0.241674 -0.0362176 -0.0124823 0.241674 -0.0464892 -0.0175029 0.241674 -0.0458461 -0.0199029 0.241674 -0.0452763 -0.0213308 0.241674 -0.0440892 -0.0216598 0.241674 -0.0416892 -0.0223029 0.241674 -0.042722 -0.0239083 0.241674 -0.038264 -0.0245135 0.241674 -0.0373645 -0.0154202 0.241674 -0.0373137 -0.00521056 0.241674 -0.0390716 -0.00521056 0.241674 -0.0406554 -0.00597329 0.241674 -0.0401676 -0.0124823 0.241674 -0.0406211 -0.0128232 0.241674 -0.0427573 -0.0128232 0.241674 -0.042722 -0.00890719 0.241674 -0.0421426 -0.00906152 0.241674 -0.0347718 0.00708081 0.241674 -0.0362176 0.00563501 0.241674 -0.0381926 0.00510581 0.241674 -0.0512013 0.0247459 0.241674 -0.0550963 0.0169008 0.241674 -0.0492263 0.0213251 0.241674 -0.0438305 0.0227709 0.241674 -0.0375322 0.0150971 0.241674 -0.0362176 0.0124766 0.241674 -0.0355659 0.0169008 0.241674 -0.0353792 0.0199422 0.241674 -0.0392892 0.0216541 0.241674 -0.038264 0.0245078 0.241674 -0.042722 0.0292752 0.241674 -0.0438305 0.0267209 0.241674 -0.042722 0.0239026 0.241674 -0.0649164 0.0303837 0.241674 -0.0769544 0.0292752 0.241674 -0.0550963 0.0364313 0.241674 -0.0550963 0.0292752 0.241674 -0.0589914 0.0338045 0.241674 -0.0595206 0.0318295 0.241674 -0.0768 0.0349971 0.241674 -0.0696 0.0308402 0.241674 -0.0663622 0.0318295 0.241674 -0.0678431 0.0325971 0.241674 -0.0663622 0.0357795 0.241674 -0.0676412 0.0414687 0.241674 -0.0629414 0.0377545 0.241674 -0.0609664 0.0372253 0.241674 -0.0853431 0.032708 0.241674 -0.0889037 0.0364313 0.241674 -0.0810587 0.0298545 0.241674 -0.0847 0.030308 0.241674 -0.0771087 0.0338045 0.241674 -0.0801798 0.0376555 0.241674 -0.0774999 0.0355184 0.241674 -0.0959055 0.0292752 0.241674 -0.100308 0.0264597 0.241674 -0.101278 0.0239026 0.241674 -0.104711 0.0216541 0.241674 -0.107111 0.0174971 0.241674 -0.0999028 0.0309863 0.241674 -0.0895 0.035108 0.241674 -0.0927988 0.0247459 0.241674 -0.101278 -0.0239083 0.241674 -0.0959055 -0.0292809 0.241674 -0.0889037 -0.0169066 0.241674 -0.0889037 -0.0239083 0.241674 -0.093328 -0.0267266 0.241674 -0.093657 -0.0279137 0.241674 -0.0947738 -0.0281724 0.241674 -0.0959055 -0.0300316 0.241674 -0.105736 -0.0245135 0.241674 -0.0999109 -0.0216598 0.241674 -0.10017 -0.0227766 0.241674 -0.0987238 -0.0213308 0.241674 -0.0853431 0.027908 0.241674 -0.0488452 0.0169008 0.241674 -0.0488452 0.00495148 0.241674 -0.0440892 0.0133402 0.241674 -0.042722 0.00495148 0.241674 -0.0418 -2.85742e-06 0.241674 -0.041157 -0.00240286 0.241674 -0.0394 0.00415406 0.241674 -0.0355659 0.00495148 0.241674 -0.0328431 -0.00240286 0.241674 -0.0959055 -0.00890719 0.241674 -0.0853431 -0.0279137 0.241674 -0.0847 -0.0303137 0.241674 -0.0850087 -0.0338103 0.241674 -0.0871 -0.0344707 0.241674 -0.0895 -0.0351137 0.241674 -0.0844795 -0.0357853 0.241674 -0.0919 -0.0344707 0.241674 -0.0506721 -0.0227766 0.241674 -0.0488452 -0.0169066 0.241674 -0.0488452 -0.00890719 0.241674 -0.0979863 0.0154145 0.241674 -0.0967488 0.0207959 0.241674 -0.0987238 0.0213251 0.241674 -0.042722 -0.0292809 0.241674 -0.0629414 -0.0298603 0.241674 -0.104711 -0.0133459 0.241674 -0.102387 -0.0110365 0.241674 -0.0999109 -0.0133459 0.241674 -0.0959055 -0.00495719 0.241674 -0.0488452 -0.00495719 0.241674 -0.042722 -0.00495719 0.241674 -0.0416892 0.0126971 0.241674 -0.093328 0.0227709 0.241674 -0.0947738 0.0213251 0.241674 -0.0889037 0.0169008 0.241674 -0.0959055 0.00495148 0.241674 -0.0889037 -0.00890719 0.241674 -0.0959055 -0.0169066 0.241674 -0.0975109 -0.0175029 0.241674 -0.0550963 -0.00890719 0.241674 -0.0895 -0.0255137 0.241674 -0.0889037 -0.00495719 0.241674 -0.0889037 0.00495148 0.241674 -0.0889037 0.0239026 0.241674 -0.0809044 0.0292752 0.241674 -0.0769544 0.0239026 0.241674 -0.0809044 0.0239026 0.241674 -0.0769544 0.0169008 0.241674 -0.0809044 0.0169008 0.241674 -0.0769544 -0.00495719 0.241674 -0.0809044 0.00495148 0.241674 -0.0769544 -0.00890719 0.241674 -0.0809044 -0.00495719 0.241674 -0.0809044 -0.00890719 0.241674 -0.0809044 -0.0169066 0.241674 -0.0769544 -0.0239083 0.241674 -0.0809044 -0.0239083 0.241674 -0.0809044 -0.0292809 0.241674 -0.0810587 -0.0298603 0.241674 -0.0744 -0.0308459 0.241674 -0.072 -0.0302029 0.241674 -0.0769544 -0.0169066 0.241674 -0.0550963 -0.0169066 0.241674 -0.0550963 -0.00495719 0.241674 -0.0769544 0.00495148 0.241674 -0.0550963 0.00495148 0.241674 -0.0550963 0.0239026 0.241674 -0.0629414 0.0298545 0.229694 -0.0626436 -0.0643244 0.230021 -0.0812269 -0.0634338 0.23001 -0.081462 -0.0634301 0.229939 -0.08185 -0.0635675 0.22992 -0.0819119 -0.0636107 0.229465 -0.0820924 -0.0648499 0.229498 -0.0821572 -0.064747 0.229691 -0.0822553 -0.0641933 0.229804 -0.0821556 -0.0638945 0.229446 -0.0619541 -0.0649083 0.229886 -0.0619971 -0.0636904 0.230021 -0.0627732 -0.0634338 0.230021 -0.0689149 -0.0640271 0.229366 -0.0672446 -0.0657296 0.229694 -0.0813565 -0.0643244 0.229366 -0.081486 -0.0652151 0.228239 -0.0623596 -0.0662772 0.228731 -0.0623944 -0.0660375 0.228415 -0.0623689 -0.0662129 0.228731 -0.0816057 -0.0660376 0.228994 -0.0815727 -0.0658112 0.228994 -0.0767989 -0.0663304 0.229366 -0.0767554 -0.0657296 0.228994 -0.072 -0.0665038 0.229366 -0.072 -0.0659014 0.228994 -0.0624273 -0.0658112 0.229366 -0.0625141 -0.0652151 0.228994 -0.0672012 -0.0663304 0.228415 -0.072 -0.0669097 0.228415 -0.0768282 -0.0667353 0.228415 -0.0671719 -0.0667353 0.228239 -0.0816405 -0.0662772 0.227721 -0.0768385 -0.0668781 0.227721 -0.0816518 -0.0663545 0.224574 -0.0831184 -0.0614552 0.224774 -0.0757119 -0.0621421 0.224774 -0.0682882 -0.0621421 0.224574 -0.0682763 -0.0623417 0.224574 -0.0608817 -0.0614552 0.224774 -0.0609173 -0.0612583 0.224574 -0.0600271 -0.0661785 0.224774 -0.059576 -0.0613697 0.224774 -0.0584702 -0.0621367 0.224574 -0.0580599 -0.0639795 0.224574 -0.0581955 -0.0646276 0.224774 -0.0580073 -0.0646952 0.224574 -0.0841591 -0.0614965 0.224574 -0.0850843 -0.0619749 0.224774 -0.0861457 -0.0638168 0.224774 -0.0823252 -0.0610845 0.224774 -0.0827769 -0.0613129 0.224774 -0.072 -0.0615529 0.224574 -0.0596436 -0.0615579 0.22289 -0.0593602 -0.0659531 0.224574 -0.0589035 -0.0656484 0.222881 -0.0591319 -0.0658196 0.224574 -0.0584229 -0.0650948 0.224574 -0.0582687 -0.0628254 0.224574 -0.0580927 -0.0633895 0.222664 -0.0580928 -0.0633892 0.222504 -0.0589993 -0.0619082 0.22252 -0.058841 -0.0620401 0.222576 -0.0584222 -0.0625401 0.222427 -0.0608817 -0.0614552 0.222449 -0.0598514 -0.0614938 0.224574 -0.0589995 -0.0619081 0.224574 -0.0586228 -0.0622659 0.222445 -0.0840473 -0.0614698 0.222516 -0.0851187 -0.0620042 0.222576 -0.0855775 -0.0625395 0.222604 -0.0857182 -0.0627968 0.224574 -0.0857197 -0.0628001 0.222664 -0.0859071 -0.063388 0.2229 -0.07601 -0.0671332 0.224574 -0.083973 -0.0661785 0.224574 -0.07601 -0.0671332 0.2229 -0.0679901 -0.0671332 0.224574 -0.0679901 -0.0671332 0.224574 -0.0757238 -0.0623417 0.221255 -0.0602321 -0.0650454 0.221498 -0.0601523 -0.0654868 0.221231 -0.0599567 -0.0649258 0.220854 -0.0599659 -0.063876 0.220979 -0.0592192 -0.0636801 0.220834 -0.0595359 -0.0632882 0.220726 -0.0600214 -0.0630408 0.220782 -0.0604636 -0.0637662 0.220779 -0.0606752 -0.0625963 0.220692 -0.0606108 -0.0629524 0.221162 -0.0591641 -0.0626218 0.220952 -0.0593315 -0.0629502 0.221036 -0.0598834 -0.0622386 0.220993 -0.0607488 -0.0621895 0.221132 -0.0590893 -0.0641362 0.22094 -0.0597794 -0.0640805 0.221284 -0.0587891 -0.0640257 0.220827 -0.0599419 -0.0626287 0.220684 -0.0605989 -0.0630182 0.221778 -0.0589253 -0.0651693 0.221653 -0.0586088 -0.0645737 0.221498 -0.0585257 -0.0638991 0.22116 -0.0597593 -0.0646905 0.221565 -0.0591284 -0.0650999 0.222358 -0.0592389 -0.0657923 0.222383 -0.060041 -0.0661015 0.2229 -0.0600271 -0.0661785 0.222078 -0.059875 -0.0615284 0.222607 -0.0582687 -0.0628256 0.222253 -0.0583923 -0.0626508 0.222151 -0.0590029 -0.0619503 0.22256 -0.0585175 -0.065198 0.222828 -0.0584604 -0.0651525 0.222737 -0.058076 -0.0641379 0.22247 -0.0581475 -0.0643875 0.222722 -0.0580599 -0.0639795 0.222623 -0.0582021 -0.0629878 0.222183 -0.0582461 -0.0644659 0.221761 -0.0583174 -0.063764 0.221603 -0.0585289 -0.0629966 0.221792 -0.0589976 -0.062105 0.221336 -0.0598525 -0.0619096 0.221619 -0.0608465 -0.0616497 0.222288 -0.0586146 -0.0652182 0.222364 -0.0581023 -0.0635021 0.222056 -0.0581754 -0.063629 0.221921 -0.0584248 -0.0628042 0.221696 -0.0598509 -0.0616698 0.22205 -0.0608744 -0.0614955 0.22147 -0.0597037 -0.0653172 0.22189 -0.0600842 -0.0658631 0.221057 -0.0596923 -0.0643914 0.221392 -0.0593515 -0.0650046 0.221861 -0.0594374 -0.0656196 0.221905 -0.0584011 -0.0645295 0.221327 -0.0587046 -0.0632175 0.221452 -0.0590503 -0.0623324 0.220807 -0.0838359 -0.0637815 0.220855 -0.0840354 -0.0638768 0.22147 -0.0842962 -0.0653173 0.221275 -0.0848616 -0.0645943 0.221392 -0.0846485 -0.0650046 0.221099 -0.0842986 -0.0645108 0.221132 -0.0849107 -0.0641356 0.220952 -0.0846686 -0.0629503 0.22102 -0.0842977 -0.0642886 0.220979 -0.0847806 -0.0636798 0.220982 -0.0842712 -0.0641891 0.220834 -0.0844641 -0.0632883 0.220726 -0.0839789 -0.063041 0.220827 -0.0840584 -0.0626289 0.220779 -0.0833249 -0.0625964 0.222499 -0.0849446 -0.0618667 0.222078 -0.0841254 -0.0615285 0.22205 -0.0831257 -0.0614955 0.222364 -0.0858976 -0.0635009 0.222706 -0.0859457 -0.0638168 0.22247 -0.0858527 -0.0643869 0.222801 -0.0857164 -0.0648406 0.222828 -0.0855396 -0.0651526 0.222878 -0.0849246 -0.0657811 0.222358 -0.0847609 -0.0657925 0.221627 -0.0838752 -0.0656382 0.221778 -0.0850746 -0.0651694 0.22192 -0.0855749 -0.0628036 0.221452 -0.0849498 -0.0623325 0.221696 -0.0841495 -0.0616699 0.221291 -0.0831929 -0.0618667 0.222151 -0.0849973 -0.0619504 0.222253 -0.0856074 -0.0626502 0.221792 -0.0850026 -0.0621051 0.222056 -0.0858246 -0.0636279 0.222183 -0.0857542 -0.0644653 0.22256 -0.0854824 -0.0651982 0.222288 -0.0853854 -0.0652183 0.221861 -0.0845624 -0.0656198 0.221653 -0.0853914 -0.0645732 0.221497 -0.0854743 -0.0638983 0.221905 -0.0855991 -0.064529 0.221761 -0.0856826 -0.063763 0.221603 -0.0854709 -0.062996 0.221327 -0.0852952 -0.063217 0.221162 -0.084836 -0.0626219 0.221336 -0.084148 -0.0619098 0.221036 -0.084117 -0.0622387 0.221627 -0.0680228 -0.0665851 0.221627 -0.0601249 -0.0656382 0.221627 -0.0759773 -0.0665851 0.221255 -0.0759414 -0.0659838 0.222207 -0.0600526 -0.0660376 0.22189 -0.0839159 -0.0658631 0.222207 -0.0839475 -0.0660376 0.222207 -0.0679986 -0.0669903 0.222207 -0.0760015 -0.0669903 0.222383 -0.0839591 -0.0661015 0.221619 -0.0831536 -0.0616497 0.220782 -0.0835365 -0.0637662 0.220782 -0.0761321 -0.0646695 0.220993 -0.0682318 -0.0630867 0.220692 -0.0681855 -0.0638606 0.220782 -0.0758639 -0.0646861 0.220993 -0.0832513 -0.0621895 0.220692 -0.0758145 -0.0638606 0.220692 -0.0833893 -0.0629524 0.222427 -0.0757238 -0.0623417 0.221619 -0.0757356 -0.0625391 0.222427 -0.0831184 -0.0614552 0.221291 -0.0608072 -0.0618667 0.221619 -0.0682645 -0.0625391 0.220993 -0.0757683 -0.0630867 0.222427 -0.0682763 -0.0623417 0.220782 -0.0678671 -0.0646695 0.22102 -0.0597023 -0.0642888 0.22094 -0.0597794 -0.0640805 0.221019 -0.0603478 -0.0644058 0.220796 -0.0602424 -0.0637637 0.221231 -0.0599567 -0.0649258 0.221057 -0.0596923 -0.0643914 0.221255 -0.083768 -0.0650454 0.221099 -0.0842986 -0.0645108 0.221184 -0.0841957 -0.064768 0.221242 -0.083976 -0.0649702 0.220879 -0.0841034 -0.0639325 0.221019 -0.0836522 -0.0644058 0.221255 -0.076215 -0.0659669 0.220782 -0.0681362 -0.0646861 0.221255 -0.0680587 -0.0659838 0.221255 -0.0677842 -0.0659668 0.222809 -0.0856725 -0.0649289 0.224574 -0.0859457 -0.0638168 0.222752 -0.0858967 -0.064299 0.224574 -0.0849846 -0.0657376 0.2229 -0.083973 -0.0661785 0.224574 -0.085692 -0.0648907 0.227842 -0.0604495 -0.0650822 0.227864 -0.0603454 -0.0648885 0.224974 -0.0600798 -0.0637321 0.227721 -0.0623483 -0.0663545 0.227749 -0.0613283 -0.0659812 0.224974 -0.0611902 -0.0658891 0.224974 -0.0603737 -0.0649451 0.224974 -0.0623483 -0.0663545 0.224774 -0.0608652 -0.0615767 0.224974 -0.0603197 -0.0626303 0.224774 -0.0601378 -0.0625471 0.224774 -0.06314 -0.0609118 0.224774 -0.0619302 -0.0609966 0.224774 -0.0612232 -0.0613129 0.224974 -0.060996 -0.061728 0.224774 -0.0808601 -0.0609118 0.224974 -0.0822512 -0.0612703 0.224774 -0.0835077 -0.0619667 0.224974 -0.0838927 -0.0633507 0.224774 -0.0816806 -0.0665525 0.224774 -0.0830358 -0.0659695 0.224974 -0.0834633 -0.0652198 0.224774 -0.0830828 -0.0612583 0.224774 -0.0840906 -0.0633219 0.224774 -0.0839179 -0.064787 0.224774 -0.0851045 -0.0658977 0.224774 -0.0858709 -0.0649802 0.224774 -0.0859009 -0.0627154 0.224774 -0.0852125 -0.0618214 0.224774 -0.0842102 -0.0613032 0.224774 -0.0840086 -0.0663753 0.224774 -0.076022 -0.0673328 0.224774 -0.0679781 -0.0673328 0.224774 -0.0599915 -0.0663753 0.224774 -0.0623195 -0.0665525 0.224774 -0.0587743 -0.0658011 0.224774 -0.061074 -0.0660519 0.224774 -0.0601959 -0.0650367 0.224774 -0.0598798 -0.0637321 0.224774 -0.0578959 -0.0633539 0.224974 -0.072 -0.0617529 0.224974 -0.0808889 -0.0611097 0.228377 -0.0749722 -0.0616813 0.228377 -0.072 -0.0617529 0.228377 -0.0631112 -0.0611097 0.228377 -0.0690279 -0.0616813 0.224974 -0.072 -0.0670529 0.224974 -0.0816518 -0.0663545 0.224774 -0.072 -0.0672529 0.224974 -0.0829119 -0.0658125 0.224974 -0.0837321 -0.064713 0.227951 -0.0838895 -0.0641352 0.224974 -0.0839064 -0.064003 0.224974 -0.0829486 -0.0616813 0.228252 -0.0830817 -0.061798 0.224974 -0.0833507 -0.0620906 0.228169 -0.0835614 -0.0624005 0.224974 -0.08372 -0.0627215 0.228047 -0.0838926 -0.0633498 0.224974 -0.0631112 -0.0611097 0.228354 -0.0621352 -0.0611497 0.224974 -0.0619863 -0.0611886 0.228257 -0.0609593 -0.0617603 0.228377 -0.0808889 -0.0611097 0.229185 -0.0809173 -0.0613054 0.229185 -0.0749817 -0.0618788 0.22981 -0.0750081 -0.0624267 0.229512 -0.080949 -0.0615234 0.229185 -0.0690184 -0.0618788 0.229512 -0.0630511 -0.0615234 0.230112 -0.0750454 -0.0632011 0.230024 -0.0810557 -0.062257 0.22981 -0.068992 -0.0624267 0.230112 -0.0689547 -0.0632011 0.22981 -0.0630038 -0.0618482 0.230024 -0.0629443 -0.062257 0.230021 -0.0750852 -0.0640271 0.230021 -0.0720005 -0.0641014 0.227721 -0.0671616 -0.0668781 0.227721 -0.072 -0.0670529 0.23007 -0.0817952 -0.0627294 0.230112 -0.0811079 -0.0626155 0.229765 -0.0827276 -0.0635118 0.229213 -0.0834433 -0.0638442 0.229578 -0.082873 -0.0640616 0.229024 -0.0833328 -0.0646102 0.228654 -0.083802 -0.0635865 0.228494 -0.0836983 -0.0645152 0.229158 -0.0821002 -0.0654709 0.229256 -0.0825359 -0.0651031 0.22887 -0.0829556 -0.0652823 0.22836 -0.0832639 -0.065342 0.228088 -0.0833614 -0.0653254 0.22964 -0.0822646 -0.0643336 0.229402 -0.0828035 -0.064613 0.228771 -0.0835415 -0.0645732 0.228207 -0.0837993 -0.0644404 0.228623 -0.0829381 -0.0617189 0.228269 -0.0829488 -0.0616815 0.22811 -0.0837708 -0.0628545 0.22981 -0.0809963 -0.0618482 0.229099 -0.0820122 -0.0613656 0.228753 -0.0808948 -0.0611503 0.228718 -0.0819928 -0.0612236 0.228349 -0.0819725 -0.0611769 0.228492 -0.0835875 -0.0625122 0.229141 -0.0834396 -0.0628529 0.228982 -0.0829383 -0.0618736 0.229417 -0.0832568 -0.0630675 0.229612 -0.0827547 -0.0623841 0.229968 -0.0818887 -0.0623205 0.22976 -0.0819605 -0.0619328 0.229822 -0.0825764 -0.0627064 0.229459 -0.0820026 -0.0616052 0.229322 -0.082878 -0.062099 0.228276 -0.0828882 -0.0616333 0.227735 -0.0823915 -0.0661335 0.228415 -0.0816312 -0.0662129 0.228271 -0.0825476 -0.0659616 0.228767 -0.0823555 -0.0657822 0.2294 -0.0818723 -0.065064 0.227748 -0.0826534 -0.0659926 0.22782 -0.0834199 -0.0652819 0.228347 -0.0838792 -0.0634622 0.228824 -0.08355 -0.0626643 0.22895 -0.0836558 -0.0637164 0.22994 -0.0823608 -0.063037 0.22994 -0.0616393 -0.0630371 0.229987 -0.0623608 -0.0634682 0.229377 -0.0622868 -0.0651513 0.229464 -0.0619077 -0.06485 0.229158 -0.0619001 -0.065471 0.229213 -0.0605568 -0.0638431 0.229402 -0.0611965 -0.0646126 0.229024 -0.0606671 -0.0646096 0.229256 -0.0614642 -0.0651032 0.229579 -0.0617551 -0.064508 0.229691 -0.0617448 -0.0641929 0.229578 -0.0611271 -0.0640609 0.229742 -0.061776 -0.064056 0.229765 -0.0612728 -0.0635114 0.229822 -0.0614236 -0.0627065 0.23007 -0.0622047 -0.0627296 0.229968 -0.0621111 -0.0623206 0.230112 -0.0628922 -0.0626155 0.228047 -0.0601077 -0.0633485 0.228135 -0.0603082 -0.0626558 0.228169 -0.0604391 -0.0623997 0.228623 -0.0610619 -0.061719 0.228276 -0.0611118 -0.0616334 0.228753 -0.0631053 -0.0611503 0.228718 -0.0620069 -0.0612237 0.229185 -0.0630828 -0.0613054 0.228 -0.0600798 -0.0637321 0.227981 -0.0600845 -0.0638896 0.228347 -0.060121 -0.063461 0.228207 -0.0602006 -0.0644397 0.227925 -0.0601537 -0.0643536 0.22782 -0.0605803 -0.0652821 0.227754 -0.0612418 -0.065925 0.228088 -0.0606388 -0.0653256 0.229099 -0.0619875 -0.0613657 0.229141 -0.0605608 -0.0628522 0.228824 -0.0604505 -0.0626636 0.228655 -0.0601982 -0.0635852 0.228494 -0.0603016 -0.0645145 0.22887 -0.0610446 -0.0652825 0.22836 -0.0607363 -0.0653422 0.228767 -0.0616448 -0.0657823 0.228982 -0.0610617 -0.0618737 0.228492 -0.060413 -0.0625114 0.228271 -0.0614528 -0.0659618 0.228772 -0.0604584 -0.0645726 0.22895 -0.0603444 -0.0637152 0.229417 -0.0607436 -0.0630669 0.229612 -0.0612453 -0.0623842 0.229322 -0.061122 -0.0620991 0.22976 -0.0620392 -0.0619329 0.229459 -0.0619972 -0.0616053 0.224574 -0.0930974 -0.0587813 0.222427 -0.106394 -0.052128 0.224574 -0.094719 -0.0632991 0.22289 -0.0940288 -0.0634373 0.222881 -0.0937643 -0.0634359 0.222828 -0.0928492 -0.0631939 0.22252 -0.0916226 -0.0603082 0.222576 -0.0915099 -0.0609506 0.222607 -0.0915197 -0.0612746 0.224574 -0.0915255 -0.061328 0.222623 -0.0915432 -0.0614483 0.222449 -0.0922245 -0.0593299 0.224574 -0.115457 -0.0513262 0.224574 -0.109038 -0.0561344 0.2229 -0.102092 -0.0601444 0.224574 -0.102092 -0.0601444 0.2229 -0.094719 -0.0632991 0.224774 -0.102775 -0.0533067 0.224774 -0.0998551 -0.0556729 0.224774 -0.0938394 -0.0577958 0.222828 -0.116301 -0.0496545 0.2229 -0.115457 -0.0513262 0.224574 -0.116083 -0.050504 0.224774 -0.116265 -0.0505881 0.227963 -0.0937085 -0.0614085 0.224974 -0.0939164 -0.0616557 0.227841 -0.0945442 -0.0621427 0.227811 -0.0948498 -0.0622887 0.224974 -0.0943492 -0.0620225 0.224974 -0.0955499 -0.0624636 0.224774 -0.0933184 -0.0611641 0.224974 -0.0934951 -0.0610705 0.224974 -0.0948502 -0.0622888 0.228377 -0.110251 -0.0484786 0.224974 -0.102875 -0.0534799 0.228377 -0.102875 -0.0534799 0.224974 -0.0968172 -0.062291 0.224774 -0.113658 -0.0527962 0.224974 -0.114355 -0.0515397 0.227748 -0.114221 -0.051825 0.224974 -0.114536 -0.0507508 0.22782 -0.114529 -0.0508263 0.224974 -0.113973 -0.0489173 0.228047 -0.113973 -0.0489167 0.227951 -0.114363 -0.0495984 0.224974 -0.114311 -0.0494754 0.224974 -0.111512 -0.0479365 0.228252 -0.112495 -0.0479781 0.224974 -0.112321 -0.0479437 0.224974 -0.112874 -0.0480971 0.224974 -0.113509 -0.0484588 0.228169 -0.113211 -0.0482601 0.224974 -0.0939796 -0.0579385 0.22835 -0.0939658 -0.0579522 0.224974 -0.0933927 -0.058804 0.22981 -0.100607 -0.0555675 0.228753 -0.110277 -0.0485107 0.228377 -0.105413 -0.0519319 0.229185 -0.100356 -0.0550798 0.228377 -0.100265 -0.054904 0.22981 -0.110714 -0.0490644 0.229185 -0.0949287 -0.0575511 0.230112 -0.106237 -0.0532115 0.22981 -0.105817 -0.0525594 0.229185 -0.10552 -0.0520982 0.230112 -0.100962 -0.0562568 0.22981 -0.0951318 -0.0580606 0.230021 -0.106684 -0.0539069 0.227721 -0.0968172 -0.062291 0.224974 -0.105525 -0.0580699 0.224974 -0.113535 -0.0526392 0.228269 -0.112321 -0.0479437 0.229256 -0.113675 -0.0511134 0.229691 -0.112977 -0.0504658 0.2294 -0.11308 -0.0514113 0.22994 -0.11249 -0.0494117 0.229765 -0.113045 -0.0496395 0.23007 -0.111846 -0.0494281 0.23001 -0.111908 -0.0502015 0.230112 -0.111194 -0.0496731 0.229804 -0.112741 -0.0502568 0.229578 -0.113446 -0.0500429 0.229024 -0.114118 -0.0502881 0.228271 -0.114114 -0.051851 0.22836 -0.114424 -0.0509563 0.228088 -0.114501 -0.0508931 0.22964 -0.113055 -0.0505826 0.229402 -0.113661 -0.0505551 0.22887 -0.114128 -0.0510588 0.228771 -0.11428 -0.0501517 0.228494 -0.114387 -0.050023 0.22811 -0.11362 -0.0485486 0.229968 -0.111723 -0.0490272 0.229512 -0.11051 -0.0488067 0.229185 -0.110374 -0.0486338 0.229099 -0.111352 -0.0481385 0.228623 -0.112331 -0.0479815 0.229141 -0.113332 -0.0487128 0.228982 -0.112408 -0.0481154 0.229322 -0.112469 -0.0483407 0.229612 -0.112504 -0.0486493 0.229417 -0.113281 -0.0489901 0.229822 -0.112511 -0.0490175 0.22976 -0.111591 -0.0486555 0.229459 -0.111464 -0.0483508 0.228718 -0.111264 -0.0480252 0.228349 -0.111223 -0.0479949 0.227721 -0.113535 -0.0526392 0.227735 -0.114065 -0.0520779 0.228415 -0.113446 -0.0525269 0.228731 -0.113336 -0.0523878 0.228767 -0.113858 -0.0517917 0.229158 -0.113481 -0.0516497 0.228994 -0.113194 -0.0522082 0.228207 -0.114437 -0.0499077 0.228347 -0.114017 -0.0490207 0.228492 -0.11329 -0.0483438 0.228654 -0.114013 -0.0491669 0.228824 -0.113333 -0.0484943 0.22895 -0.113951 -0.0493525 0.229213 -0.113831 -0.0495694 0.230024 -0.11097 -0.0493887 0.228731 -0.0966987 -0.0619934 0.229886 -0.095181 -0.0601594 0.23007 -0.0948803 -0.0592235 0.229987 -0.0953849 -0.0597851 0.230021 -0.0957248 -0.0595491 0.229446 -0.0957527 -0.0612356 0.229256 -0.095426 -0.0616493 0.229402 -0.0949488 -0.0613583 0.229464 -0.0956834 -0.0612083 0.229578 -0.0946129 -0.0609152 0.229579 -0.0953802 -0.0609885 0.229691 -0.0952138 -0.0607207 0.229417 -0.0937837 -0.0602462 0.230024 -0.0952847 -0.0584444 0.229742 -0.0951723 -0.0605865 0.229765 -0.0944642 -0.0603665 0.229822 -0.0941924 -0.059594 0.22994 -0.0945445 -0.0597725 0.229968 -0.0945948 -0.0589161 0.230112 -0.0954187 -0.0587809 0.228753 -0.0948707 -0.0574055 0.228377 -0.0948555 -0.0573674 0.228363 -0.0942044 -0.0577413 0.228718 -0.0939562 -0.0580182 0.228283 -0.0934194 -0.0587427 0.228623 -0.0933854 -0.0589197 0.228168 -0.0931864 -0.0598292 0.22812 -0.0932175 -0.0602341 0.228492 -0.0932196 -0.0599304 0.228347 -0.0934415 -0.0608987 0.228062 -0.0933307 -0.0606916 0.228207 -0.0939998 -0.0617065 0.227925 -0.0939161 -0.0616554 0.228088 -0.0948223 -0.0622546 0.227749 -0.0957472 -0.0624777 0.229158 -0.0959873 -0.0617499 0.22887 -0.0951522 -0.0620144 0.22836 -0.094915 -0.0622202 0.228494 -0.0941247 -0.0617208 0.228655 -0.0935705 -0.0609677 0.22895 -0.0937621 -0.0610072 0.228824 -0.0933282 -0.0600434 0.228982 -0.0934626 -0.0590538 0.229099 -0.0940104 -0.058151 0.229512 -0.0950103 -0.0577557 0.228767 -0.0959219 -0.0621471 0.228271 -0.0958453 -0.0623986 0.229377 -0.0961623 -0.0612797 0.229024 -0.0944888 -0.0616204 0.228772 -0.0942896 -0.0616927 0.229213 -0.09401 -0.0610118 0.229141 -0.093518 -0.0601516 0.229612 -0.0938769 -0.0594041 0.229322 -0.0936275 -0.0592188 0.229459 -0.0941385 -0.0583536 0.22976 -0.0943387 -0.0586162 0.230021 -0.111706 -0.0503222 0.229939 -0.112313 -0.0501265 0.22992 -0.112388 -0.0501329 0.229465 -0.113164 -0.0511159 0.229498 -0.113169 -0.0509943 0.229366 -0.096391 -0.0612213 0.229694 -0.0960579 -0.0603852 0.229886 -0.095181 -0.0601594 0.230021 -0.10134 -0.0569921 0.229366 -0.100745 -0.0593016 0.230021 -0.10405 -0.0555136 0.229366 -0.108982 -0.0545462 0.229694 -0.112264 -0.0510288 0.228239 -0.113486 -0.0525779 0.229366 -0.112821 -0.0517353 0.228994 -0.10932 -0.0550448 0.229366 -0.104949 -0.0570727 0.228994 -0.105251 -0.0575943 0.228994 -0.096614 -0.0617809 0.228994 -0.101008 -0.0598436 0.228415 -0.109548 -0.0553808 0.228415 -0.0967643 -0.062158 0.228239 -0.0967883 -0.0622184 0.228415 -0.101185 -0.0602089 0.227721 -0.101247 -0.0603377 0.228415 -0.105453 -0.0579459 0.227721 -0.105525 -0.0580699 0.227721 -0.109628 -0.0554992 0.224774 -0.106284 -0.0519611 0.224574 -0.106394 -0.052128 0.224574 -0.0999446 -0.0558518 0.224574 -0.0921976 -0.0593568 0.224774 -0.0920551 -0.0592165 0.224574 -0.0916938 -0.0601146 0.224574 -0.0916366 -0.0602657 0.224574 -0.0918863 -0.0623333 0.224574 -0.0936586 -0.0634272 0.224774 -0.0947866 -0.0634873 0.224774 -0.0936378 -0.0636261 0.224574 -0.0927879 -0.0631627 0.224574 -0.0926476 -0.0630825 0.224574 -0.112355 -0.0476629 0.224574 -0.113317 -0.0471679 0.224774 -0.113268 -0.046974 0.224574 -0.114399 -0.0471457 0.224574 -0.11538 -0.0476007 0.224774 -0.115503 -0.0474429 0.224574 -0.116062 -0.0484405 0.224774 -0.116506 -0.0494945 0.224774 -0.115586 -0.0514788 0.224774 -0.102182 -0.0603233 0.221231 -0.0940317 -0.0622495 0.221255 -0.09433 -0.0622153 0.221498 -0.0944815 -0.0626375 0.220834 -0.0928485 -0.0610416 0.220796 -0.0936981 -0.0611002 0.220726 -0.0931452 -0.0605847 0.220779 -0.0934892 -0.0598728 0.221327 -0.0920932 -0.0613961 0.221162 -0.0921933 -0.0606504 0.221036 -0.0926246 -0.0599589 0.220827 -0.0928703 -0.0602675 0.221132 -0.0928857 -0.0619994 0.22094 -0.0934555 -0.0616061 0.221284 -0.0925704 -0.0620538 0.220979 -0.0927701 -0.0615394 0.220952 -0.0925024 -0.0608511 0.220692 -0.0936114 -0.0602134 0.221778 -0.0932602 -0.062976 0.221392 -0.0935469 -0.0626203 0.222383 -0.0946926 -0.0632255 0.222078 -0.0922623 -0.0593481 0.222253 -0.0915394 -0.0610614 0.222151 -0.091718 -0.0601495 0.222504 -0.0916938 -0.0601148 0.222737 -0.092009 -0.0625075 0.222722 -0.0919158 -0.0623783 0.222664 -0.0916492 -0.0618506 0.222183 -0.0923203 -0.0627065 0.221905 -0.0924864 -0.062684 0.222056 -0.0918406 -0.062017 0.221761 -0.0920311 -0.0620629 0.221696 -0.092312 -0.0594826 0.22247 -0.0921957 -0.0626879 0.222364 -0.0917139 -0.0619436 0.221921 -0.0916442 -0.061178 0.221792 -0.0917907 -0.0602861 0.22205 -0.0931113 -0.0588199 0.22147 -0.0940082 -0.062715 0.22189 -0.0946107 -0.0629975 0.221861 -0.0939289 -0.06311 0.222207 -0.0946706 -0.0631644 0.221565 -0.0934014 -0.0628143 0.222358 -0.0938433 -0.0633588 0.22256 -0.0929214 -0.0632048 0.222288 -0.0930155 -0.0631737 0.221653 -0.0926883 -0.0626184 0.221498 -0.0922791 -0.0620758 0.221603 -0.0918305 -0.0612926 0.221452 -0.09195 -0.0604567 0.221336 -0.0924333 -0.0596895 0.221291 -0.0932387 -0.0591749 0.22205 -0.112381 -0.0476942 0.220782 -0.107688 -0.0540883 0.220782 -0.100996 -0.0579521 0.220684 -0.093634 -0.0602763 0.220692 -0.107232 -0.053398 0.220692 -0.100625 -0.0572125 0.221291 -0.112625 -0.0479821 0.222427 -0.112355 -0.0476629 0.220993 -0.0933495 -0.0594837 0.220993 -0.100279 -0.0565192 0.221619 -0.0931642 -0.0589674 0.221619 -0.100033 -0.0560286 0.220993 -0.106805 -0.0527509 0.221619 -0.106503 -0.0522931 0.222427 -0.0999446 -0.0558518 0.222427 -0.0930974 -0.0587813 0.221627 -0.101847 -0.0596534 0.222207 -0.108959 -0.056015 0.221255 -0.101331 -0.0592372 0.221627 -0.0945335 -0.0627823 0.221255 -0.101577 -0.0591147 0.221627 -0.108736 -0.0556761 0.22189 -0.11525 -0.0510816 0.222207 -0.102028 -0.0600164 0.2229 -0.109038 -0.0561344 0.220692 -0.113338 -0.0488242 0.220726 -0.113893 -0.048606 0.220855 -0.11436 -0.0493017 0.220879 -0.114447 -0.0493159 0.220834 -0.114437 -0.0485776 0.220982 -0.11472 -0.0494542 0.221275 -0.115434 -0.0495099 0.221099 -0.114905 -0.0497191 0.221132 -0.115247 -0.0490881 0.220979 -0.114907 -0.0487584 0.221327 -0.115121 -0.0481004 0.221036 -0.113612 -0.0478422 0.220952 -0.114445 -0.0481827 0.220827 -0.113756 -0.0482094 0.220779 -0.113104 -0.0485481 0.222253 -0.115108 -0.0474533 0.222499 -0.114142 -0.0471062 0.222151 -0.11423 -0.0471524 0.222078 -0.113264 -0.047223 0.222444 -0.113153 -0.0472158 0.22256 -0.116274 -0.0497225 0.222614 -0.115369 -0.0475923 0.222364 -0.115785 -0.048045 0.22247 -0.116189 -0.0488347 0.222727 -0.116085 -0.0484885 0.222878 -0.116082 -0.0505062 0.222358 -0.115946 -0.0505979 0.222383 -0.115406 -0.0512665 0.221627 -0.115102 -0.0509071 0.22147 -0.115306 -0.0504187 0.221861 -0.115688 -0.0505476 0.222183 -0.116143 -0.0489519 0.221905 -0.11604 -0.0490846 0.221761 -0.11573 -0.0483795 0.221603 -0.115163 -0.0478211 0.22192 -0.115157 -0.0476024 0.221619 -0.112483 -0.0478138 0.221696 -0.113355 -0.0473333 0.221792 -0.114312 -0.0472837 0.222056 -0.115785 -0.0481915 0.222288 -0.1162 -0.0497884 0.222207 -0.115364 -0.0512169 0.221242 -0.114855 -0.0502782 0.221392 -0.115455 -0.0499718 0.221778 -0.115906 -0.0499014 0.221653 -0.115882 -0.0492267 0.221497 -0.115617 -0.0486008 0.221162 -0.114426 -0.0478145 0.221452 -0.11438 -0.047507 0.221336 -0.113474 -0.0475419 0.220993 -0.112837 -0.0482324 0.22102 -0.0934929 -0.061825 0.22094 -0.0934555 -0.0616061 0.220854 -0.0935147 -0.0613356 0.220782 -0.0938908 -0.0609917 0.22116 -0.093743 -0.0621444 0.221019 -0.0941104 -0.0616035 0.221057 -0.0935355 -0.0619189 0.221184 -0.114944 -0.0499933 0.221255 -0.114713 -0.0504474 0.220782 -0.113873 -0.0494553 0.220807 -0.11414 -0.0493188 0.221019 -0.114293 -0.0499513 0.22102 -0.114793 -0.0495271 0.220782 -0.107912 -0.0539398 0.221255 -0.108632 -0.0550219 0.221255 -0.108404 -0.0551733 0.220782 -0.100754 -0.0580722 0.222511 -0.1143 -0.0471271 0.222576 -0.115027 -0.0473724 0.224574 -0.116306 -0.0494945 0.222817 -0.116306 -0.0494945 0.222752 -0.116183 -0.0487366 0.222664 -0.115736 -0.0479425 0.224974 -0.0931864 -0.0598292 0.224774 -0.0947815 -0.0571816 0.224774 -0.093322 -0.0584873 0.224774 -0.111483 -0.0477386 0.224774 -0.112948 -0.0479113 0.224774 -0.114541 -0.0516138 0.224974 -0.114515 -0.0501774 0.224774 -0.112226 -0.0475103 0.224774 -0.111988 -0.0477105 0.224774 -0.114713 -0.0501486 0.224774 -0.116242 -0.0483527 0.224774 -0.11413 -0.0487934 0.224774 -0.11444 -0.0469499 0.224774 -0.0929864 -0.0598292 0.224774 -0.0930298 -0.058593 0.224774 -0.0932083 -0.0587266 0.224774 -0.0914473 -0.0602011 0.224774 -0.091327 -0.061352 0.224774 -0.0917179 -0.0624411 0.224774 -0.0925426 -0.0632527 0.224774 -0.094237 -0.0621881 0.224774 -0.0955282 -0.0626625 0.224774 -0.0968913 -0.0624768 0.224774 -0.105625 -0.0582431 0.224774 -0.109148 -0.0563014 0.224974 -0.0948555 -0.0573674 0.224974 -0.110251 -0.0484786 0.224774 -0.110128 -0.0483216 0.224774 -0.0305571 -0.0469361 0.224574 -0.0286971 -0.0475431 0.224574 -0.027696 -0.0495855 0.224774 -0.0276471 -0.0503729 0.224574 -0.0517337 -0.0592896 0.224774 -0.0518705 -0.0591437 0.224774 -0.0492186 -0.0571816 0.224774 -0.041225 -0.0533067 0.224774 -0.0377159 -0.0519611 0.224774 -0.032012 -0.0477105 0.224774 -0.0327298 -0.0477778 0.224574 -0.0316451 -0.0476629 0.224574 -0.0277326 -0.0490673 0.224574 -0.0278353 -0.0503053 0.224574 -0.0282626 -0.0479437 0.224574 -0.0279392 -0.0484382 0.222737 -0.0278739 -0.0485834 0.222504 -0.0297884 -0.0471141 0.224574 -0.0292835 -0.0472356 0.222449 -0.0307336 -0.0471812 0.224574 -0.0305215 -0.0471329 0.224574 -0.0297886 -0.0471141 0.224574 -0.0509027 -0.0587813 0.222446 -0.0517263 -0.0592828 0.224574 -0.0522942 -0.0600863 0.222584 -0.0524919 -0.0610402 0.2229 -0.0492811 -0.0632991 0.224574 -0.0492811 -0.0632991 0.224574 -0.0419076 -0.0601444 0.2229 -0.0285434 -0.0513262 0.224574 -0.0285434 -0.0513262 0.222427 -0.0316451 -0.0476629 0.224574 -0.0440555 -0.0558518 0.222427 -0.0440555 -0.0558518 0.22116 -0.0290554 -0.0499036 0.220854 -0.0296416 -0.0493015 0.220834 -0.0295632 -0.0485775 0.220796 -0.0299372 -0.0493426 0.221284 -0.0285476 -0.0488428 0.221132 -0.0287523 -0.0490886 0.22094 -0.0293779 -0.0493855 0.221327 -0.0288785 -0.0481007 0.220979 -0.0290929 -0.0487585 0.220952 -0.0295551 -0.0481826 0.220827 -0.0302445 -0.0482094 0.220726 -0.0301072 -0.048606 0.220684 -0.0306187 -0.0488751 0.221498 -0.0283828 -0.0486015 0.221392 -0.0285452 -0.0499717 0.221565 -0.0283044 -0.0499427 0.222881 -0.0279476 -0.0505677 0.222358 -0.0280538 -0.0505976 0.22289 -0.0280785 -0.0507975 0.222576 -0.0289726 -0.0473728 0.22252 -0.0295853 -0.0471491 0.222828 -0.0276996 -0.0496542 0.22247 -0.0278111 -0.0488353 0.222364 -0.0282147 -0.0480459 0.222722 -0.0279392 -0.0484382 0.222664 -0.0282629 -0.0479434 0.222623 -0.0285583 -0.0476504 0.222607 -0.028697 -0.0475432 0.222183 -0.0278572 -0.0489525 0.222056 -0.0282145 -0.0481924 0.221921 -0.0288429 -0.0476028 0.221603 -0.0288368 -0.0478214 0.221336 -0.0305266 -0.0475419 0.221696 -0.0306451 -0.0473334 0.222253 -0.0288914 -0.0474537 0.222151 -0.0297705 -0.0471524 0.221792 -0.0296885 -0.0472837 0.222078 -0.0307367 -0.0472231 0.22205 -0.0316186 -0.0476942 0.221619 -0.0315173 -0.0478138 0.22147 -0.0286939 -0.0504186 0.222207 -0.0286359 -0.0512169 0.221057 -0.0291469 -0.0496111 0.221778 -0.0280938 -0.0499013 0.221861 -0.0283121 -0.0505473 0.22256 -0.0277262 -0.0497223 0.222288 -0.0278002 -0.0497882 0.221905 -0.0279597 -0.0490851 0.221761 -0.02827 -0.0483803 0.221653 -0.0281175 -0.0492272 0.221452 -0.0296205 -0.047507 0.221162 -0.0295744 -0.0478145 0.221036 -0.0303888 -0.0478423 0.221291 -0.0313749 -0.0479821 0.222383 -0.0493075 -0.0632255 0.221627 -0.0494666 -0.0627823 0.221242 -0.0498879 -0.0622542 0.220807 -0.0503609 -0.0611547 0.220726 -0.050855 -0.0605849 0.220855 -0.050486 -0.061337 0.220834 -0.0511515 -0.0610417 0.220982 -0.050534 -0.0617253 0.221275 -0.0508427 -0.0623714 0.221132 -0.0511146 -0.0619988 0.22147 -0.0499916 -0.0627149 0.221497 -0.0517214 -0.062075 0.221653 -0.0513121 -0.0626181 0.221392 -0.050453 -0.0626203 0.220979 -0.0512299 -0.061539 0.220952 -0.0514976 -0.0608512 0.221162 -0.0518068 -0.0606505 0.221036 -0.0513757 -0.0599592 0.220827 -0.0511299 -0.0602678 0.220779 -0.0505109 -0.0598729 0.220993 -0.0506506 -0.0594837 0.22102 -0.0505073 -0.0618247 0.222645 -0.0524085 -0.0616673 0.222253 -0.0524607 -0.0610607 0.222496 -0.0522606 -0.0600122 0.222151 -0.0522822 -0.0601496 0.222078 -0.0517381 -0.0593483 0.222437 -0.0515307 -0.0591192 0.222427 -0.0509027 -0.0587813 0.222755 -0.0518648 -0.0626579 0.222809 -0.0513798 -0.0630653 0.22247 -0.0518048 -0.0626874 0.222664 -0.0523513 -0.0618495 0.222878 -0.0503039 -0.0634308 0.222358 -0.0501564 -0.0633588 0.221861 -0.0500709 -0.06311 0.222056 -0.0521599 -0.062016 0.221603 -0.0521696 -0.061292 0.221792 -0.0522095 -0.0602862 0.221336 -0.051567 -0.0596898 0.221291 -0.0507614 -0.0591749 0.221696 -0.0516883 -0.0594828 0.22192 -0.0523559 -0.0611773 0.222364 -0.0522867 -0.0619426 0.222183 -0.0516802 -0.062706 0.22256 -0.0510785 -0.0632049 0.222288 -0.0509844 -0.0631738 0.222207 -0.0493294 -0.0631644 0.22189 -0.0493894 -0.0629975 0.221255 -0.0496701 -0.0622153 0.221778 -0.0507397 -0.062976 0.221905 -0.0515141 -0.0626836 0.221761 -0.0519694 -0.062062 0.221327 -0.0519069 -0.0613955 0.221452 -0.0520501 -0.0604568 0.221255 -0.0292874 -0.0504474 0.221255 -0.035367 -0.0550214 0.221627 -0.0288982 -0.0509071 0.221627 -0.0352645 -0.0556761 0.221498 -0.0289976 -0.0507897 0.221627 -0.0421533 -0.0596534 0.2229 -0.0349621 -0.0561344 0.222383 -0.0285939 -0.0512665 0.22189 -0.0287504 -0.0510816 0.222207 -0.0350409 -0.056015 0.222207 -0.0419717 -0.0600164 0.2229 -0.0419076 -0.0601444 0.220993 -0.0371947 -0.0527509 0.220782 -0.0363123 -0.0540883 0.220692 -0.0306619 -0.0488242 0.220692 -0.0367677 -0.053398 0.220993 -0.0437216 -0.0565192 0.220692 -0.0433746 -0.0572125 0.220692 -0.0503886 -0.0602134 0.222427 -0.0376057 -0.052128 0.22205 -0.0508888 -0.0588199 0.220779 -0.0308957 -0.048548 0.220993 -0.0311629 -0.0482324 0.221619 -0.0374968 -0.0522931 0.221619 -0.0508359 -0.0589674 0.221619 -0.043967 -0.0560286 0.22094 -0.0293779 -0.0493855 0.220782 -0.0301275 -0.0494553 0.22102 -0.0292069 -0.0495273 0.221099 -0.0503969 -0.0620177 0.221184 -0.0501792 -0.0621889 0.220879 -0.050517 -0.0614192 0.220982 -0.050534 -0.0617253 0.221019 -0.0498897 -0.0616035 0.220782 -0.0501093 -0.0609917 0.220782 -0.0432452 -0.0580719 0.221255 -0.0426683 -0.0592369 0.220782 -0.0430046 -0.0579521 0.221255 -0.0424229 -0.0591147 0.221255 -0.0355963 -0.0551733 0.220782 -0.0360875 -0.0539393 0.221019 -0.0297075 -0.0499513 0.221231 -0.0291087 -0.0502061 0.224574 -0.0524919 -0.0610402 0.224574 -0.0518528 -0.0626709 0.224574 -0.0514728 -0.0630031 0.222837 -0.051032 -0.0632484 0.224774 -0.0504399 -0.0636168 0.224574 -0.0504131 -0.0634186 0.224574 -0.0510318 -0.0632485 0.224574 -0.0522219 -0.062146 0.224774 -0.0526919 -0.0610402 0.224774 -0.0523994 -0.0622382 0.22782 -0.0294707 -0.0508265 0.224974 -0.0297225 -0.0517148 0.224974 -0.0304655 -0.0526392 0.224774 -0.0295425 -0.0518021 0.224774 -0.0314643 -0.0477823 0.224974 -0.0294571 -0.0505589 0.224774 -0.0295381 -0.049325 0.224774 -0.0338726 -0.0483216 0.224774 -0.0502628 -0.0579015 0.224974 -0.0507 -0.0590611 0.224974 -0.050782 -0.0602376 0.224974 -0.0503455 -0.0613332 0.224774 -0.0471088 -0.0624768 0.224774 -0.048362 -0.0626723 0.224974 -0.049319 -0.0622141 0.224974 -0.0494769 -0.0621309 0.224774 -0.0508914 -0.0590032 0.224774 -0.0492135 -0.0634873 0.224774 -0.0515879 -0.0631666 0.224774 -0.0505102 -0.0614467 0.224774 -0.0303256 -0.0483343 0.224774 -0.0509796 -0.0602685 0.224774 -0.0524777 -0.0600068 0.224774 -0.049576 -0.0623047 0.224774 -0.0418181 -0.0603233 0.224774 -0.034852 -0.0563014 0.224774 -0.0303417 -0.0527962 0.224774 -0.0284141 -0.0514788 0.224774 -0.0292571 -0.0505589 0.224774 -0.0275358 -0.0490316 0.224774 -0.02811 -0.0478144 0.224774 -0.0292159 -0.0470474 0.224974 -0.0337487 -0.0484786 0.224974 -0.0491445 -0.0573674 0.228377 -0.0437348 -0.054904 0.224974 -0.041125 -0.0534799 0.228377 -0.0337487 -0.0484786 0.224774 -0.038375 -0.0582431 0.227721 -0.0471829 -0.062291 0.227735 -0.047934 -0.0624694 0.227748 -0.0482312 -0.0624783 0.224974 -0.0483481 -0.0624728 0.22782 -0.0492504 -0.0622461 0.227951 -0.0502304 -0.0614879 0.22811 -0.050768 -0.0603193 0.228169 -0.0508137 -0.0598215 0.228127 -0.0507905 -0.0601789 0.228377 -0.0491445 -0.0573674 0.224974 -0.0501155 -0.0580367 0.228349 -0.0500494 -0.0579673 0.228269 -0.0506426 -0.0588925 0.224974 -0.0506425 -0.0588923 0.224974 -0.0315094 -0.0479772 0.228258 -0.031567 -0.0479645 0.224974 -0.0326861 -0.0479729 0.228169 -0.0307895 -0.0482597 0.224974 -0.0304506 -0.0484905 0.228114 -0.0304045 -0.0485282 0.22807 -0.0301498 -0.0487725 0.227845 -0.0294571 -0.0505589 0.227925 -0.0295654 -0.049809 0.224974 -0.0297184 -0.0494116 0.227989 -0.0297693 -0.049311 0.230112 -0.0328061 -0.0496731 0.22981 -0.0381831 -0.0525594 0.228753 -0.0491294 -0.0574055 0.229185 -0.0436442 -0.0550798 0.228377 -0.041125 -0.0534799 0.229185 -0.0384799 -0.0520982 0.228377 -0.0385869 -0.0519319 0.230024 -0.0487154 -0.0584444 0.22981 -0.0433932 -0.0555675 0.229185 -0.0336262 -0.0486338 0.230112 -0.0485814 -0.0587809 0.230112 -0.0377636 -0.0532115 0.22981 -0.0332864 -0.0490644 0.230112 -0.0430383 -0.0562568 0.230021 -0.0373161 -0.0539069 0.230021 -0.0322938 -0.0503222 0.224974 -0.0471829 -0.062291 0.224974 -0.038475 -0.0580699 0.227721 -0.0427527 -0.0603377 0.228252 -0.0506995 -0.0590598 0.22887 -0.0488481 -0.0620143 0.229691 -0.0487861 -0.0607211 0.2294 -0.0480191 -0.0612836 0.22964 -0.048724 -0.0608471 0.229498 -0.0484244 -0.0611515 0.23001 -0.0484807 -0.0596634 0.22992 -0.0487801 -0.0600448 0.229804 -0.0488492 -0.0604124 0.229765 -0.0495358 -0.060367 0.229578 -0.0493869 -0.0609159 0.229024 -0.0495108 -0.0616208 0.229213 -0.0499896 -0.0610127 0.228347 -0.050558 -0.0608999 0.228271 -0.0481552 -0.0623986 0.229256 -0.0485743 -0.0616493 0.228767 -0.0480785 -0.0621472 0.22836 -0.0490853 -0.0622201 0.229402 -0.049051 -0.0613586 0.228771 -0.04971 -0.0616932 0.228494 -0.0498749 -0.0617213 0.22981 -0.0488683 -0.0580606 0.229968 -0.0494051 -0.0589158 0.229512 -0.0489898 -0.0577557 0.229459 -0.0498613 -0.0583533 0.229185 -0.0490714 -0.0575511 0.229099 -0.0499894 -0.0581507 0.228718 -0.0500436 -0.0580179 0.228824 -0.0506718 -0.0600442 0.229141 -0.050482 -0.0601524 0.229322 -0.0503726 -0.0592187 0.22976 -0.0496611 -0.058616 0.229612 -0.0501232 -0.0594039 0.228982 -0.0505375 -0.0590537 0.228623 -0.0506146 -0.0589195 0.228415 -0.0472358 -0.062158 0.229158 -0.048013 -0.0617499 0.228088 -0.049178 -0.0622545 0.228207 -0.0499998 -0.061707 0.228047 -0.0506258 -0.0608092 0.228654 -0.0504291 -0.0609689 0.228492 -0.0507804 -0.0599312 0.22895 -0.0502374 -0.0610082 0.229417 -0.0502163 -0.0602468 0.229822 -0.0498077 -0.0595939 0.22994 -0.0494556 -0.0597724 0.23007 -0.0491196 -0.0592233 0.227749 -0.0297689 -0.0518059 0.227721 -0.0304655 -0.0526392 0.229987 -0.0319195 -0.0501459 0.22994 -0.0315102 -0.0494117 0.229158 -0.0305192 -0.0516499 0.229464 -0.0308363 -0.0511159 0.229256 -0.0303256 -0.0511135 0.229579 -0.030875 -0.0507435 0.229402 -0.0303391 -0.0505547 0.229024 -0.0298821 -0.0502875 0.229765 -0.0309557 -0.0496392 0.229578 -0.0305548 -0.0500423 0.229612 -0.0314955 -0.0486494 0.22976 -0.0324087 -0.0486554 0.230024 -0.0330305 -0.0493887 0.229691 -0.0310237 -0.0504655 0.229822 -0.0314887 -0.0490176 0.23007 -0.0321536 -0.0494281 0.229968 -0.0322771 -0.0490271 0.228492 -0.0307111 -0.0483433 0.228347 -0.0299834 -0.0490197 0.228222 -0.0312205 -0.0480616 0.228375 -0.0335182 -0.0483159 0.228353 -0.0328581 -0.0480175 0.228323 -0.0323439 -0.0479195 0.228276 -0.0317553 -0.0479324 0.228753 -0.0337233 -0.0485107 0.228088 -0.0294996 -0.0508934 0.228207 -0.029563 -0.049907 0.228271 -0.0298864 -0.0518513 0.228994 -0.0308057 -0.0522082 0.22836 -0.0295757 -0.0509565 0.228772 -0.0297198 -0.0501511 0.228494 -0.0296131 -0.0500224 0.22895 -0.0300498 -0.0493516 0.229141 -0.0306687 -0.0487124 0.228655 -0.0299881 -0.0491659 0.228824 -0.0306675 -0.0484939 0.228982 -0.0315917 -0.0481154 0.229322 -0.0315312 -0.0483407 0.229099 -0.0326475 -0.0481384 0.228718 -0.0327353 -0.0480251 0.228623 -0.0316693 -0.0479815 0.228767 -0.0301424 -0.0517919 0.228415 -0.0305542 -0.0525269 0.228731 -0.030664 -0.0523878 0.229377 -0.0310139 -0.0515664 0.22887 -0.0298726 -0.0510589 0.229213 -0.0301698 -0.0495685 0.229417 -0.0307197 -0.0489897 0.229459 -0.0325361 -0.0483507 0.229512 -0.0334897 -0.0488067 0.230021 -0.0482753 -0.0595491 0.230021 -0.0426597 -0.0569921 0.229939 -0.0487481 -0.0599764 0.229465 -0.0483168 -0.0612082 0.229742 -0.0311192 -0.0503625 0.229694 -0.0317363 -0.0510288 0.229446 -0.0308472 -0.0511897 0.229366 -0.0311788 -0.0517353 0.229886 -0.0314934 -0.0501564 0.229366 -0.0350184 -0.0545462 0.230021 -0.0399511 -0.055514 0.229366 -0.043255 -0.0593016 0.229694 -0.0479422 -0.0603852 0.229366 -0.047609 -0.0612213 0.228415 -0.0428151 -0.0602089 0.228994 -0.0473861 -0.0617809 0.228994 -0.0387496 -0.0575943 0.229366 -0.0390508 -0.0570727 0.228994 -0.0346803 -0.0550448 0.228994 -0.0429922 -0.0598436 0.228415 -0.0385466 -0.0579459 0.228731 -0.0473014 -0.0619934 0.228239 -0.030514 -0.0525779 0.227721 -0.0343722 -0.0554992 0.228415 -0.0344525 -0.0553808 0.227721 -0.038475 -0.0580699 0.228239 -0.0472118 -0.0622184 0.224774 -0.0509702 -0.058593 0.224774 -0.0506781 -0.0584873 0.224774 -0.044145 -0.0556729 0.224574 -0.0376057 -0.052128 0.224774 -0.0317744 -0.0475103 0.224574 -0.0349621 -0.0561344 0.224574 -0.0246284 -0.0430335 0.222504 -0.0248887 -0.0422151 0.222642 -0.0242274 -0.0435834 0.224574 -0.0242274 -0.0435834 0.222603 -0.024482 -0.0432743 0.224574 -0.0233342 -0.0441621 0.224574 -0.0227656 -0.0442948 0.222833 -0.0222789 -0.0442977 0.224574 -0.0222787 -0.0442976 0.224574 -0.0216172 -0.0441371 0.224774 -0.021543 -0.0443228 0.224574 -0.023854 -0.0438959 0.224774 -0.0239661 -0.0440616 0.227721 -0.00971192 -0.02482 0.227744 -0.00952372 -0.0238392 0.228753 -0.0234922 -0.0382796 0.228377 -0.0235243 -0.0382542 0.229185 -0.0233691 -0.0383767 0.229185 -0.0199047 -0.033523 0.228377 -0.0146355 -0.0228584 0.229185 -0.0169231 -0.0283587 0.22981 -0.0139423 -0.0231346 0.230112 -0.0187914 -0.0342393 0.230024 -0.0226142 -0.0389724 0.22981 -0.0194435 -0.0338198 0.229512 -0.0231962 -0.0385132 0.22981 -0.0164354 -0.0286097 0.230112 -0.0157461 -0.0289646 0.230024 -0.0135585 -0.0232875 0.230021 -0.0164893 -0.0320525 0.224974 -0.00971192 -0.02482 0.224974 -0.0193637 -0.0415374 0.22811 -0.0234543 -0.0416224 0.228492 -0.0236591 -0.0412925 0.229691 -0.0215371 -0.0409794 0.22964 -0.0214203 -0.0410576 0.229256 -0.0208895 -0.0416774 0.229498 -0.0210086 -0.0411713 0.23007 -0.0225748 -0.039849 0.23001 -0.0218014 -0.0399108 0.229804 -0.0217461 -0.0407436 0.229024 -0.0217148 -0.042121 0.228654 -0.022836 -0.0420155 0.228771 -0.0218512 -0.0422832 0.228494 -0.0219799 -0.04239 0.227748 -0.0201779 -0.0422238 0.229465 -0.020887 -0.0411666 0.22836 -0.0210466 -0.0424272 0.228088 -0.0211098 -0.0425033 0.229578 -0.02196 -0.0414485 0.229402 -0.0214478 -0.0416639 0.22887 -0.0209441 -0.0421304 0.228047 -0.0230862 -0.0419756 0.229968 -0.0229757 -0.0397255 0.22981 -0.0229385 -0.0387165 0.22976 -0.0233474 -0.0395938 0.229459 -0.0236521 -0.0394665 0.229099 -0.0238644 -0.039355 0.228718 -0.0239777 -0.0392672 0.228349 -0.024008 -0.0392263 0.228252 -0.0240248 -0.0404974 0.228623 -0.0240214 -0.0403335 0.229417 -0.0230128 -0.0412838 0.229612 -0.0233536 -0.0405073 0.229822 -0.0229854 -0.040514 0.229322 -0.0236622 -0.0404715 0.228982 -0.0238875 -0.0404111 0.228269 -0.0240592 -0.0403241 0.227721 -0.0193637 -0.0415374 0.227735 -0.019925 -0.0420675 0.228271 -0.0201519 -0.0421167 0.228731 -0.0196151 -0.0413389 0.228767 -0.0202112 -0.0418606 0.229158 -0.0203532 -0.0414838 0.228994 -0.0197947 -0.0411972 0.229366 -0.0202676 -0.0408241 0.22782 -0.0211766 -0.0425323 0.228207 -0.0220952 -0.0424401 0.228347 -0.0229822 -0.0420202 0.228824 -0.0235086 -0.0413361 0.22895 -0.0226504 -0.0419538 0.229213 -0.0224335 -0.0418337 0.229141 -0.0232901 -0.0413349 0.229765 -0.0223634 -0.0410476 0.22994 -0.0225912 -0.0404926 0.230112 -0.0223298 -0.0391968 0.228239 -0.00978454 -0.0247911 0.229213 -0.0109911 -0.0220129 0.228767 -0.00985575 -0.0239247 0.22994 -0.0122304 -0.0225473 0.23007 -0.0127794 -0.0228831 0.230112 -0.013222 -0.0234215 0.229158 -0.010253 -0.0239901 0.229446 -0.0107673 -0.0237555 0.229464 -0.0107946 -0.0236862 0.229402 -0.0106446 -0.0229516 0.229578 -0.0110877 -0.0226157 0.229417 -0.0117567 -0.0217865 0.229968 -0.0130868 -0.0225977 0.229612 -0.0125988 -0.0218797 0.22976 -0.0133867 -0.0223415 0.229691 -0.0112822 -0.0232166 0.229742 -0.0114164 -0.0231751 0.229765 -0.0116364 -0.022467 0.229822 -0.0124089 -0.0221952 0.228105 -0.0116489 -0.0212417 0.228347 -0.0111042 -0.0214443 0.228753 -0.0145974 -0.0228735 0.228718 -0.0139847 -0.021959 0.227727 -0.00957112 -0.0243382 0.227835 -0.00983011 -0.0226023 0.228088 -0.00974833 -0.0228251 0.228415 -0.00984488 -0.0247671 0.228994 -0.010222 -0.0246168 0.22836 -0.00978268 -0.0229179 0.228772 -0.0103102 -0.0222924 0.228494 -0.0102821 -0.0221275 0.228655 -0.0110352 -0.0215733 0.228824 -0.0119595 -0.021331 0.229322 -0.0127841 -0.0216303 0.229512 -0.0142472 -0.0230131 0.229185 -0.0144518 -0.0229315 0.229099 -0.0138519 -0.0220132 0.228623 -0.0130832 -0.0213882 0.228982 -0.0129491 -0.0214654 0.228492 -0.0120725 -0.0212225 0.228207 -0.0102964 -0.0220026 0.228271 -0.0096043 -0.0238481 0.229377 -0.0107232 -0.0241652 0.229256 -0.0103536 -0.0234288 0.22887 -0.00998854 -0.023155 0.229024 -0.0103825 -0.0224917 0.22895 -0.0109957 -0.021765 0.229141 -0.0118513 -0.0215208 0.229459 -0.0136493 -0.0221413 0.229694 -0.0116177 -0.0240607 0.229366 -0.0127013 -0.0287479 0.230021 -0.0216807 -0.0397091 0.229939 -0.0218764 -0.0403155 0.22992 -0.0218699 -0.0403908 0.2294 -0.0205916 -0.041083 0.229694 -0.0209741 -0.0402666 0.229579 -0.0110144 -0.023383 0.229377 -0.0107232 -0.0241652 0.229446 -0.0107673 -0.0237555 0.229987 -0.0122178 -0.0233877 0.229886 -0.0118435 -0.0231838 0.230021 -0.0124538 -0.0237276 0.230021 -0.0150108 -0.0293432 0.230021 -0.018096 -0.0346868 0.229366 -0.0149302 -0.0329521 0.229366 -0.0174567 -0.0369845 0.227721 -0.0116652 -0.0292502 0.228239 -0.019425 -0.0414889 0.228415 -0.019476 -0.0414487 0.228994 -0.0144086 -0.0332533 0.228994 -0.0121593 -0.0290107 0.229366 -0.0107816 -0.0243939 0.228731 -0.0100095 -0.0247015 0.228415 -0.011794 -0.0291878 0.228415 -0.014057 -0.0334563 0.228994 -0.0169581 -0.0373226 0.227721 -0.013933 -0.0335279 0.228415 -0.0166221 -0.0375504 0.227721 -0.0165037 -0.0376307 0.224574 -0.02434 -0.0403578 0.224574 -0.0198749 -0.0343972 0.224774 -0.0200418 -0.034287 0.224574 -0.0161511 -0.0279474 0.224774 -0.01633 -0.0278579 0.224774 -0.0135156 -0.0213248 0.224574 -0.0206767 -0.0434595 0.224574 -0.00870382 -0.0227218 0.224774 -0.0116796 -0.0301848 0.224774 -0.0134099 -0.0210327 0.224574 -0.0118883 -0.0196967 0.224774 -0.0114256 -0.0193526 0.224574 -0.01139 -0.0195494 0.224574 -0.0101519 -0.0196521 0.224574 -0.00962456 -0.0199187 0.224774 -0.0100844 -0.0194639 0.224774 -0.00897847 -0.0202309 0.224774 -0.0244926 -0.0402285 0.224774 -0.0242643 -0.0394855 0.224774 -0.0242924 -0.0399909 0.224774 -0.0236813 -0.0381303 0.224574 -0.0125136 -0.0200794 0.224574 -0.0132216 -0.0211002 0.22289 -0.00856555 -0.0220316 0.224574 -0.00860106 -0.0214837 0.222828 -0.00880901 -0.020852 0.224574 -0.0091311 -0.0203601 0.222737 -0.0094954 -0.0200118 0.224574 -0.00884025 -0.0207907 0.222623 -0.0105546 -0.019546 0.222664 -0.0101523 -0.019652 0.222722 -0.0096246 -0.0199186 0.222504 -0.0118881 -0.0196966 0.22252 -0.0116947 -0.0196254 0.222576 -0.0110523 -0.0195127 0.222607 -0.0107283 -0.0195225 0.224574 -0.0107284 -0.0195225 0.224574 -0.0247618 -0.0410828 0.224574 -0.0249084 -0.0419087 0.222483 -0.0249084 -0.0419087 0.2229 -0.0158685 -0.0370408 0.224574 -0.0158685 -0.0370408 0.224574 -0.0118585 -0.0300953 0.222427 -0.0161511 -0.0279474 0.222427 -0.0198749 -0.0343972 0.22116 -0.00985852 -0.0217459 0.220854 -0.0106673 -0.0215176 0.220834 -0.0109613 -0.0208513 0.220796 -0.0109027 -0.0217009 0.221327 -0.0106068 -0.020096 0.221036 -0.012044 -0.0206274 0.220779 -0.0121301 -0.021492 0.221132 -0.0100035 -0.0208885 0.22094 -0.0103968 -0.0214584 0.22102 -0.0101779 -0.0214957 0.220979 -0.0104635 -0.0207729 0.220952 -0.0111518 -0.0205053 0.220726 -0.0114182 -0.021148 0.220827 -0.0117354 -0.0208732 0.220692 -0.0117895 -0.0216143 0.221653 -0.00938446 -0.0206911 0.22147 -0.00928794 -0.0220111 0.222358 -0.00864412 -0.0218461 0.222383 -0.00877741 -0.0226954 0.222449 -0.012673 -0.0202273 0.222151 -0.0118534 -0.0197208 0.222881 -0.00856704 -0.0217671 0.22247 -0.00931504 -0.0201985 0.222364 -0.0100593 -0.0197167 0.221905 -0.00931888 -0.0204892 0.222056 -0.00998588 -0.0198434 0.221921 -0.0108249 -0.019647 0.221452 -0.0115462 -0.0199529 0.221696 -0.0125203 -0.0203149 0.221336 -0.0123134 -0.0204361 0.221291 -0.012828 -0.0212415 0.222183 -0.00929642 -0.0203231 0.222253 -0.0109415 -0.0195422 0.221792 -0.0117168 -0.0197935 0.222078 -0.0126548 -0.0202651 0.221619 -0.0130355 -0.021167 0.221231 -0.00975342 -0.0220345 0.22189 -0.00900542 -0.0226135 0.222207 -0.00883853 -0.0226735 0.221057 -0.010084 -0.0215383 0.221284 -0.00994912 -0.0205733 0.221392 -0.00938263 -0.0215497 0.221565 -0.00918858 -0.0214042 0.221861 -0.00889292 -0.0219317 0.221778 -0.00902691 -0.021263 0.22256 -0.00879809 -0.0209242 0.222288 -0.0088292 -0.0210184 0.221761 -0.00993995 -0.0200339 0.221498 -0.00992709 -0.0202819 0.221603 -0.0107103 -0.0198333 0.221162 -0.0113525 -0.0201961 0.220993 -0.0125192 -0.0213523 0.2229 -0.0206767 -0.0434595 0.22189 -0.0209213 -0.0432524 0.220782 -0.0225476 -0.0418754 0.220807 -0.0226841 -0.0421424 0.220726 -0.0233969 -0.0418959 0.220834 -0.0234253 -0.0424398 0.221275 -0.022493 -0.043437 0.221184 -0.0220096 -0.0429471 0.221099 -0.0222838 -0.0429077 0.221132 -0.0229148 -0.0432502 0.221327 -0.0239025 -0.0431239 0.220952 -0.0238202 -0.0424479 0.220827 -0.0237935 -0.0417587 0.220779 -0.0234548 -0.0411072 0.22102 -0.0224758 -0.0427958 0.220982 -0.0225487 -0.0427231 0.220979 -0.0232445 -0.0429096 0.222576 -0.0246305 -0.0430296 0.222253 -0.0245496 -0.0431108 0.222151 -0.0248505 -0.0422326 0.222542 -0.0247825 -0.0426757 0.22205 -0.0243087 -0.0403843 0.222441 -0.0247642 -0.0410893 0.222746 -0.0233344 -0.044162 0.22256 -0.0222804 -0.0442766 0.222704 -0.0237264 -0.0439766 0.222664 -0.0240604 -0.0437393 0.222364 -0.0239579 -0.0437875 0.222808 -0.0226277 -0.0443057 0.222358 -0.021405 -0.0439489 0.222878 -0.0214967 -0.044085 0.221627 -0.0210958 -0.0431047 0.221778 -0.0221015 -0.0439091 0.221861 -0.0214553 -0.0436906 0.22192 -0.0244005 -0.0431594 0.221452 -0.0244959 -0.0423825 0.221696 -0.0246696 -0.0413582 0.222078 -0.0247799 -0.0412666 0.221792 -0.0247192 -0.0423145 0.222056 -0.0238114 -0.0437878 0.22247 -0.0231682 -0.0441916 0.222183 -0.023051 -0.0441455 0.222288 -0.0222145 -0.0442026 0.221255 -0.0215555 -0.0427155 0.22147 -0.0215842 -0.0433089 0.221242 -0.0217247 -0.042858 0.221392 -0.0220311 -0.0434576 0.221653 -0.0227762 -0.0438853 0.221905 -0.0229183 -0.044043 0.221761 -0.0236234 -0.0437324 0.221497 -0.0234021 -0.0436196 0.221603 -0.0241818 -0.0431655 0.221162 -0.0241884 -0.0424286 0.221036 -0.0241607 -0.0416144 0.221336 -0.024461 -0.0414767 0.220993 -0.0237705 -0.04084 0.221291 -0.0240208 -0.040628 0.222207 -0.0159879 -0.036962 0.221498 -0.00936537 -0.0224843 0.221627 -0.00922061 -0.0225363 0.221255 -0.0127657 -0.0293338 0.2229 -0.00870382 -0.0227218 0.2229 -0.0118585 -0.0300953 0.221627 -0.0163268 -0.0367384 0.222207 -0.020786 -0.043367 0.221627 -0.0123495 -0.0298496 0.222207 -0.0119865 -0.0300312 0.222383 -0.0207364 -0.043409 0.221619 -0.0241891 -0.0404856 0.220782 -0.0179146 -0.0356906 0.220692 -0.0231787 -0.041341 0.220782 -0.0180631 -0.0359147 0.220684 -0.0117266 -0.0216368 0.220782 -0.0140508 -0.0289983 0.220993 -0.0154837 -0.0282813 0.220993 -0.019252 -0.0348082 0.220692 -0.0147904 -0.0286283 0.220692 -0.0186049 -0.0352352 0.222427 -0.02434 -0.0403578 0.221619 -0.0159743 -0.0280359 0.221619 -0.0197098 -0.0345061 0.22205 -0.013183 -0.0211141 0.222427 -0.0132216 -0.0211002 0.220782 -0.0139307 -0.0287569 0.22094 -0.0103968 -0.0214584 0.221019 -0.0103994 -0.0221132 0.220782 -0.0110112 -0.0218936 0.221057 -0.010084 -0.0215383 0.220807 -0.0226841 -0.0421424 0.220855 -0.0227012 -0.0423628 0.220879 -0.022687 -0.0424495 0.220982 -0.0225487 -0.0427231 0.221019 -0.0220516 -0.0422954 0.221099 -0.0222838 -0.0429077 0.221255 -0.016981 -0.0366351 0.221255 -0.0168295 -0.0364066 0.221255 -0.0128882 -0.02958 0.221255 -0.00978758 -0.0223328 0.221231 -0.00975342 -0.0220345 0.224774 -0.00962049 -0.0225729 0.224774 -0.010449 -0.0215703 0.224974 -0.01057 -0.0217296 0.224774 -0.0116367 -0.0210403 0.224974 -0.0116744 -0.0212367 0.224774 -0.0140769 -0.0217178 0.224974 -0.0139434 -0.0218667 0.224974 -0.0240664 -0.0395143 0.224974 -0.0230856 -0.0419761 0.224774 -0.0232094 -0.0421331 0.224974 -0.0225275 -0.0423142 0.224774 -0.0203891 -0.0425434 0.224974 -0.0212521 -0.0425388 0.224774 -0.0218543 -0.0427161 0.224774 -0.0205241 -0.0435888 0.224774 -0.0240916 -0.0409507 0.224774 -0.022787 -0.0444937 0.224774 -0.0248051 -0.0431272 0.224774 -0.0251084 -0.0419087 0.224774 -0.0249496 -0.041014 0.224774 -0.0129362 -0.0210931 0.224774 -0.0157015 -0.0371509 0.224774 -0.0137598 -0.0336279 0.224774 -0.00952613 -0.0248941 0.224774 -0.00851558 -0.0227894 0.224774 -0.00840425 -0.0214481 0.224774 -0.00932372 -0.0238392 0.224774 -0.0126428 -0.0199268 0.224774 -0.0148213 -0.0227843 0.224774 -0.0186962 -0.0307779 0.224974 -0.0235243 -0.0382542 0.228377 -0.020071 -0.033416 0.224974 -0.018523 -0.0308779 0.228377 -0.0170989 -0.0282681 0.228377 -0.018523 -0.0308779 0.224974 -0.013933 -0.0335279 0.224774 -0.0192067 -0.0416612 0.224974 -0.0204632 -0.0423576 0.224974 -0.0218255 -0.0425182 0.227951 -0.0224045 -0.0423656 0.224974 -0.0240592 -0.0403238 0.224974 -0.0239058 -0.0408766 0.228169 -0.0237428 -0.0412141 0.224974 -0.0235441 -0.041512 0.22835 -0.0140518 -0.0219696 0.224974 -0.0146355 -0.0228584 0.224974 -0.0141173 -0.0220378 0.228276 -0.0131823 -0.0213886 0.224974 -0.0129995 -0.0213211 0.224974 -0.0128827 -0.0212858 0.228253 -0.0129575 -0.0213077 0.228169 -0.0121823 -0.0211892 0.228047 -0.0111949 -0.0213766 0.224974 -0.0104746 -0.0218056 0.227954 -0.0105355 -0.0217563 0.224974 -0.00952372 -0.0238392 0.22782 -0.00975668 -0.0227527 0.224974 -0.00979966 -0.0226618 0.224574 -0.0132216 0.0210945 0.222446 -0.0127201 0.0202708 0.224574 -0.0101519 0.0196464 0.222705 -0.00977407 0.0198203 0.222664 -0.0101534 0.0196459 0.222607 -0.0107284 0.0195167 0.224574 -0.0118883 0.0196909 0.222591 -0.0108877 0.0195064 0.224574 -0.00860106 0.021478 0.222828 -0.00880892 0.0208465 0.224574 -0.00884025 0.020785 0.222808 -0.0089445 0.0206066 0.222722 -0.00962469 0.0199129 0.2229 -0.00870382 0.0227161 0.224574 -0.00870382 0.0227161 0.224574 -0.0118585 0.0300896 0.224574 -0.02434 0.0403521 0.222427 -0.0198749 0.0343915 0.224574 -0.0198749 0.0343915 0.224574 -0.0161511 0.0279417 0.222427 -0.0161511 0.0279417 0.222427 -0.0132216 0.0210945 0.221231 -0.0217968 0.0428885 0.220979 -0.0232444 0.0429043 0.220854 -0.0227014 0.0423555 0.220782 -0.0225476 0.0418697 0.220684 -0.0231278 0.0413785 0.221036 -0.0241606 0.0416084 0.220827 -0.0237935 0.0417527 0.221132 -0.0229143 0.0432449 0.221327 -0.0239022 0.0431186 0.220952 -0.0238203 0.0424421 0.220834 -0.0234254 0.042434 0.220726 -0.0233969 0.04189 0.221284 -0.0231601 0.0434496 0.221498 -0.0234014 0.0436144 0.221392 -0.0220312 0.043452 0.22147 -0.0215843 0.0433033 0.222364 -0.023957 0.0437825 0.22256 -0.0222806 0.0442709 0.222899 -0.020799 0.0435878 0.222383 -0.0207364 0.0434033 0.2229 -0.0206767 0.0434538 0.222483 -0.0249084 0.0419029 0.222441 -0.0247639 0.041083 0.222664 -0.0240595 0.0437343 0.222499 -0.0248967 0.0421393 0.222288 -0.0222147 0.0441969 0.221603 -0.0241815 0.0431604 0.221792 -0.0247192 0.0423087 0.221696 -0.0246695 0.0413521 0.221336 -0.024461 0.0414706 0.22247 -0.0231676 0.0441861 0.222183 -0.0230504 0.0441399 0.222056 -0.0238105 0.0437827 0.222253 -0.0245492 0.0431057 0.221921 -0.0244001 0.0431543 0.222151 -0.0248505 0.0422267 0.222078 -0.0247798 0.0412605 0.22205 -0.0243087 0.0403786 0.221619 -0.0241891 0.0404798 0.221627 -0.0210958 0.043099 0.221861 -0.0214556 0.0436851 0.22189 -0.0209213 0.0432467 0.22102 -0.0224756 0.0427903 0.221057 -0.0223918 0.0428503 0.221565 -0.0220602 0.0436928 0.221778 -0.0221016 0.0439034 0.222358 -0.0214053 0.0439433 0.221905 -0.0229178 0.0440375 0.221761 -0.0236226 0.0437272 0.221653 -0.0227757 0.0438797 0.221452 -0.0244959 0.0423767 0.221162 -0.0241884 0.0424228 0.220993 -0.0237705 0.0408343 0.221861 -0.00889295 0.0219263 0.220807 -0.0108482 0.0216363 0.220855 -0.0106659 0.0215112 0.220879 -0.0105837 0.0214801 0.220982 -0.0102776 0.0214631 0.221275 -0.00963146 0.0211545 0.221184 -0.00981399 0.021818 0.221132 -0.0100041 0.0208826 0.221497 -0.0099279 0.0202758 0.221099 -0.00998524 0.0216003 0.220952 -0.0111517 0.0204996 0.220979 -0.0104639 0.0207673 0.220834 -0.0109612 0.0208456 0.220726 -0.011418 0.0211422 0.220692 -0.0117895 0.0216085 0.220827 -0.0117351 0.0208673 0.222437 -0.0128899 0.0204748 0.222499 -0.0119521 0.0197187 0.222151 -0.0118533 0.019715 0.221619 -0.0130355 0.0211613 0.222078 -0.0126546 0.0202591 0.222752 -0.00936959 0.0201103 0.222823 -0.00884034 0.0207848 0.22247 -0.00931552 0.0201924 0.222878 -0.00857209 0.0216933 0.222358 -0.00864412 0.0218408 0.221627 -0.00922061 0.0225306 0.221778 -0.00902687 0.0212575 0.222288 -0.00882913 0.0210128 0.221761 -0.00994087 0.0200278 0.222183 -0.00929686 0.020317 0.221603 -0.0107109 0.0198276 0.22192 -0.0108256 0.0196413 0.221792 -0.0117167 0.0197877 0.221452 -0.0115461 0.0199471 0.221336 -0.0123131 0.0204302 0.221696 -0.0125201 0.0203089 0.222253 -0.0109422 0.0195365 0.222364 -0.0100603 0.0197105 0.222056 -0.00998689 0.0198373 0.22256 -0.00879801 0.0209187 0.221242 -0.00974872 0.0221093 0.22147 -0.00928799 0.0220055 0.221392 -0.00938264 0.0215441 0.221905 -0.00931927 0.0204831 0.221653 -0.00938482 0.020685 0.221327 -0.0106074 0.0200903 0.221162 -0.0113524 0.0201904 0.221036 -0.0120437 0.0206215 0.221498 -0.0212132 0.0429996 0.221255 -0.0169815 0.0366301 0.221627 -0.0163268 0.0367327 0.221255 -0.0128882 0.0295743 0.222207 -0.0159879 0.0369562 0.222207 -0.020786 0.0433613 0.2229 -0.0158685 0.0370351 0.221255 -0.012766 0.0293289 0.221627 -0.0123495 0.0298439 0.22189 -0.00900545 0.0226078 0.222207 -0.0119865 0.0300255 0.222207 -0.00883853 0.0226677 0.222383 -0.00877742 0.0226897 0.2229 -0.0118585 0.0300896 0.22205 -0.013183 0.0211084 0.220993 -0.0154837 0.0282756 0.220692 -0.0231787 0.0413353 0.220692 -0.0186049 0.0352295 0.220692 -0.0147904 0.0286226 0.221291 -0.012828 0.0212358 0.220993 -0.0125192 0.0213466 0.220779 -0.01213 0.0214863 0.221619 -0.0159743 0.0280302 0.220779 -0.0234549 0.0411015 0.220993 -0.019252 0.0348025 0.221291 -0.0240208 0.0406223 0.221619 -0.0197098 0.0345004 0.221019 -0.0220516 0.0422897 0.22094 -0.0226174 0.0426193 0.220796 -0.0226603 0.04206 0.22116 -0.0220993 0.0429418 0.221057 -0.0223918 0.0428503 0.221255 -0.00978758 0.0223271 0.220807 -0.0108482 0.0216363 0.221019 -0.0103994 0.0221075 0.220982 -0.0102776 0.0214631 0.22102 -0.0101782 0.0214899 0.221099 -0.00998524 0.0216003 0.220782 -0.0110112 0.0218879 0.220782 -0.013931 0.028752 0.220782 -0.0140508 0.0289926 0.220782 -0.0179146 0.0356849 0.221255 -0.0168295 0.0364009 0.220782 -0.0180636 0.0359097 0.221255 -0.0215555 0.0427097 0.221231 -0.0217968 0.0428885 0.222427 -0.02434 0.0403521 0.224774 -0.0251084 0.0419029 0.224574 -0.0247618 0.0410771 0.224974 -0.0116744 0.021231 0.228047 -0.0111937 0.0213714 0.224974 -0.0104746 0.0217999 0.227929 -0.0103729 0.0218894 0.224974 -0.00979966 0.0226561 0.227801 -0.00967339 0.0229553 0.224974 -0.0128827 0.0212801 0.228254 -0.0129602 0.0213029 0.224974 -0.0129995 0.0213154 0.228276 -0.0131824 0.021383 0.224974 -0.0139434 0.021861 0.224974 -0.0146355 0.0228526 0.224774 -0.0140769 0.0217121 0.224774 -0.0135156 0.0213191 0.224774 -0.0116367 0.0210345 0.224774 -0.010449 0.0215646 0.224774 -0.00932372 0.0238335 0.224774 -0.00962049 0.0225672 0.224974 -0.01057 0.0217238 0.224974 -0.0225275 0.0423085 0.224774 -0.0218543 0.0427104 0.224974 -0.0218255 0.0425125 0.224974 -0.0240664 0.0395086 0.224774 -0.0242643 0.0394798 0.224974 -0.0240592 0.0403181 0.224774 -0.0240916 0.040945 0.224974 -0.0230856 0.0419704 0.224974 -0.00952372 0.0238335 0.224774 -0.0232094 0.0421274 0.224774 -0.0244926 0.0402228 0.224774 -0.0249496 0.0410082 0.224774 -0.00897847 0.0202252 0.224774 -0.0100844 0.0194582 0.224774 -0.0129362 0.0210874 0.224774 -0.00851558 0.0227837 0.224774 -0.0192067 0.0416555 0.224774 -0.0203891 0.0425377 0.224774 -0.0239661 0.0440558 0.224974 -0.0235243 0.0382485 0.224974 -0.018523 0.0308721 0.224774 -0.0186962 0.0307721 0.224974 -0.013933 0.0335221 0.224774 -0.0137598 0.0336221 0.224774 -0.00952613 0.0248884 0.227721 -0.00971192 0.0248143 0.227744 -0.00952372 0.0238335 0.224974 -0.0235441 0.0415063 0.228047 -0.0230873 0.0419691 0.228143 -0.0236232 0.0413979 0.224974 -0.0239058 0.0408709 0.228169 -0.0237432 0.0412077 0.228276 -0.0240705 0.0402419 0.224974 -0.0193637 0.0415316 0.227721 -0.0193637 0.0415316 0.224974 -0.0204632 0.0423519 0.22782 -0.0211764 0.0425265 0.224974 -0.0212521 0.0425331 0.227827 -0.0212524 0.0425331 0.227843 -0.0214296 0.04254 0.22981 -0.0194435 0.0338141 0.228377 -0.0146355 0.0228526 0.228377 -0.0170989 0.0282624 0.229185 -0.0169231 0.0283529 0.228377 -0.018523 0.0308721 0.228377 -0.020071 0.0334103 0.229185 -0.0199047 0.0335173 0.228377 -0.0235243 0.0382485 0.22981 -0.0139423 0.0231289 0.228753 -0.0234922 0.0382739 0.229185 -0.0233691 0.038371 0.22981 -0.0164354 0.028604 0.230112 -0.0187914 0.0342336 0.230112 -0.013222 0.0234158 0.230112 -0.0157461 0.0289589 0.227721 -0.013933 0.0335221 0.224974 -0.00971192 0.0248143 0.229498 -0.0108514 0.0235728 0.229256 -0.0103536 0.0234229 0.22964 -0.0111558 0.0232731 0.229804 -0.0115905 0.023148 0.229578 -0.011087 0.0226103 0.230024 -0.0135585 0.0232818 0.229968 -0.0130871 0.0225921 0.22976 -0.0133869 0.0223361 0.22994 -0.0122305 0.0225416 0.23001 -0.0123395 0.0235165 0.23007 -0.0127796 0.0228776 0.229158 -0.010253 0.0239842 0.229822 -0.012409 0.0221895 0.229765 -0.0116359 0.0224613 0.229024 -0.0103821 0.0224863 0.229402 -0.0106443 0.0229462 0.228207 -0.0102959 0.0219974 0.229691 -0.0112818 0.023211 0.22887 -0.00998859 0.0231491 0.228718 -0.013985 0.0219535 0.228349 -0.0140356 0.0219477 0.227945 -0.0104747 0.0217998 0.228083 -0.011474 0.0212775 0.228112 -0.0117025 0.0212257 0.228169 -0.0121814 0.0211835 0.228654 -0.011034 0.0215681 0.22895 -0.0109947 0.0217597 0.229141 -0.0118505 0.0215152 0.228494 -0.0102816 0.0221223 0.228347 -0.011103 0.0214391 0.228492 -0.0120717 0.0212168 0.228824 -0.0119587 0.0213253 0.228982 -0.0129492 0.0214597 0.228623 -0.0130834 0.0213826 0.229099 -0.0138522 0.0220077 0.228753 -0.0145974 0.0228678 0.229185 -0.0144518 0.0229258 0.227727 -0.00957027 0.0243298 0.228271 -0.0096043 0.023842 0.228415 -0.00984488 0.0247614 0.228731 -0.0100095 0.0246958 0.228767 -0.00985574 0.0239187 0.2294 -0.0107193 0.0239781 0.228088 -0.00974842 0.0228192 0.22836 -0.00978277 0.0229119 0.228771 -0.0103097 0.0222872 0.229213 -0.0109902 0.0220076 0.229417 -0.0117561 0.0217809 0.229322 -0.0127842 0.0216246 0.229612 -0.012599 0.021874 0.229459 -0.0136496 0.0221359 0.229512 -0.0142472 0.0230074 0.227749 -0.020197 0.0422283 0.229886 -0.0218465 0.0405037 0.229987 -0.021857 0.0400777 0.23007 -0.0225748 0.0398435 0.230021 -0.0216807 0.0397033 0.229446 -0.0208132 0.0411499 0.229402 -0.0214482 0.0416581 0.229578 -0.0219606 0.0414424 0.229213 -0.0224344 0.0418274 0.229691 -0.0215374 0.0409735 0.229765 -0.0223637 0.0410415 0.229822 -0.0229853 0.0405084 0.229968 -0.0229758 0.0397201 0.22976 -0.0233475 0.0395885 0.230024 -0.0226142 0.0389667 0.229742 -0.0216404 0.040878 0.22994 -0.0225912 0.0404869 0.230112 -0.0223298 0.0391911 0.228363 -0.0239086 0.0389162 0.22835 -0.0240025 0.0391998 0.228623 -0.0240214 0.0403279 0.228718 -0.0239778 0.0392618 0.227984 -0.0226564 0.0422465 0.228207 -0.0220959 0.0424342 0.227925 -0.0221939 0.0424318 0.228239 -0.019425 0.0414832 0.228772 -0.0218518 0.0422774 0.228494 -0.0219805 0.0423841 0.228655 -0.022837 0.0420091 0.228982 -0.0238875 0.0404055 0.229322 -0.0236622 0.040466 0.229099 -0.0238645 0.0393497 0.229459 -0.0236522 0.0394611 0.229512 -0.0231962 0.0385075 0.228492 -0.0236596 0.0412861 0.228824 -0.023509 0.0413297 0.228347 -0.0229832 0.0420138 0.22836 -0.0210464 0.0424215 0.228088 -0.0211095 0.0424976 0.228767 -0.020211 0.0418547 0.228271 -0.0201516 0.0421108 0.229366 -0.0202676 0.0408184 0.229377 -0.0204365 0.0409833 0.229158 -0.020353 0.041478 0.22887 -0.020944 0.0421246 0.229256 -0.0208894 0.0416716 0.229024 -0.0217154 0.0421151 0.22895 -0.0226513 0.0419474 0.229417 -0.0230132 0.0412775 0.229141 -0.0232905 0.0413285 0.229612 -0.0233535 0.0405017 0.22981 -0.0229385 0.0387108 0.229939 -0.0120265 0.0232491 0.230021 -0.0124538 0.0237219 0.22992 -0.0119581 0.0232171 0.229465 -0.0107947 0.0236804 0.229579 -0.0212594 0.0411222 0.229694 -0.0209741 0.0402608 0.229464 -0.020887 0.0411609 0.229886 -0.0218465 0.0405037 0.230021 -0.018096 0.0346811 0.229366 -0.0174567 0.0369788 0.229366 -0.0149302 0.0329464 0.230021 -0.0164889 0.032046 0.230021 -0.0150108 0.0293374 0.229694 -0.0116177 0.024055 0.228415 -0.019476 0.041443 0.228415 -0.0166221 0.0375447 0.228994 -0.010222 0.0246111 0.229366 -0.0107816 0.0243881 0.229366 -0.0127013 0.0287422 0.228994 -0.0197947 0.0411915 0.228731 -0.0196151 0.0413332 0.228994 -0.0169581 0.0373169 0.228994 -0.0144086 0.0332476 0.228415 -0.014057 0.0334506 0.228994 -0.0121593 0.029005 0.228415 -0.011794 0.0291821 0.227721 -0.0165037 0.037625 0.228239 -0.00978454 0.0247854 0.227721 -0.0116652 0.0292445 0.224774 -0.0242924 0.0399852 0.224774 -0.0116796 0.0301791 0.224774 -0.0157015 0.0371452 0.224574 -0.0158685 0.0370351 0.224774 -0.0205241 0.043583 0.224574 -0.0247826 0.0426697 0.224774 -0.0248051 0.0431215 0.224574 -0.0246284 0.0430278 0.224774 -0.021543 0.0443171 0.224774 -0.022787 0.044488 0.224774 -0.00840425 0.0214424 0.224574 -0.0091311 0.0203544 0.224574 -0.00962456 0.019913 0.224574 -0.0107284 0.0195168 0.224574 -0.0125136 0.0200737 0.224774 -0.0134099 0.0210269 0.224774 -0.0126428 0.0199211 0.224574 -0.01139 0.0195436 0.224774 -0.0114256 0.0193468 0.224774 -0.0200418 0.0342813 0.224774 -0.01633 0.0278522 0.224774 -0.0148213 0.0227786 0.224774 -0.0236813 0.0381246 0.222676 -0.0239672 0.0438086 0.224574 -0.023854 0.0438902 0.224574 -0.0233342 0.0441564 0.222746 -0.0233344 0.0441563 0.222785 -0.022908 0.0442694 0.222833 -0.022279 0.044292 0.224574 -0.0227656 0.0442891 0.222866 -0.0217484 0.0441795 0.224574 -0.0222787 0.0442919 0.224574 -0.0216172 0.0441314 0.222881 -0.0214352 0.0440496 0.224574 -0.0206767 0.0434538 0.224574 -0.0242274 0.0435777 0.222642 -0.0242274 0.0435778 0.222564 -0.0246887 0.0429061 0.224574 -0.0249084 0.0419029 0.230021 -0.0322938 0.0503165 0.23001 -0.0320921 0.0501958 0.229694 -0.0317363 0.0510231 0.229465 -0.0308363 0.0511101 0.22964 -0.0309453 0.0505769 0.229691 -0.0310235 0.0504601 0.229742 -0.0488278 0.0605808 0.229694 -0.0479422 0.0603795 0.229377 -0.0478377 0.0612739 0.229366 -0.047609 0.0612156 0.230021 -0.0426597 0.0569863 0.230021 -0.0399504 0.0555079 0.230021 -0.0373161 0.0539012 0.228239 -0.0472118 0.0622126 0.227721 -0.0427527 0.060332 0.228731 -0.0473014 0.0619877 0.228239 -0.030514 0.0525722 0.228994 -0.0308057 0.0522025 0.229366 -0.0311788 0.0517296 0.228994 -0.0387496 0.0575886 0.229366 -0.0350184 0.0545405 0.229366 -0.0390508 0.0570669 0.228994 -0.0429922 0.0598379 0.229366 -0.043255 0.0592959 0.228994 -0.0473861 0.0617752 0.228415 -0.0428151 0.0602032 0.228415 -0.0385466 0.0579402 0.228415 -0.0344525 0.0553751 0.228994 -0.0346803 0.0550391 0.228731 -0.030664 0.052382 0.227721 -0.0343722 0.0554935 0.224574 -0.0376057 0.0521223 0.224774 -0.0377159 0.0519554 0.224774 -0.0284141 0.0514731 0.224574 -0.0492811 0.0632934 0.224774 -0.0492135 0.0634816 0.224774 -0.0523994 0.0622324 0.224574 -0.0524919 0.0610345 0.224574 -0.0523658 0.0618022 0.224574 -0.0522219 0.0621403 0.224574 -0.0518528 0.0626651 0.224574 -0.0504131 0.0634129 0.224574 -0.0285434 0.0513204 0.224774 -0.0277859 0.0482924 0.224574 -0.0276953 0.0494183 0.224574 -0.0286537 0.0475693 0.224774 -0.030747 0.0469721 0.224574 -0.0297886 0.0471084 0.224774 -0.050401 0.058058 0.224774 -0.0338726 0.0483158 0.224774 -0.041225 0.053301 0.224774 -0.044145 0.0556672 0.222795 -0.0515281 0.0629573 0.224574 -0.0514728 0.0629974 0.224574 -0.0510318 0.0632428 0.222837 -0.0510321 0.0632427 0.222757 -0.051853 0.062665 0.222664 -0.0523509 0.0618449 0.224574 -0.0306968 0.0471657 0.222437 -0.031048 0.0472864 0.222446 -0.030799 0.0471946 0.224574 -0.0296292 0.0471343 0.222591 -0.0288299 0.0474488 0.222607 -0.028697 0.0475374 0.222664 -0.0282636 0.0479368 0.222705 -0.0280224 0.0482775 0.224574 -0.0279635 0.0483844 0.224574 -0.0279023 0.0504662 0.222878 -0.0279179 0.0505005 0.224574 -0.027696 0.0495798 0.222823 -0.027696 0.0495796 0.222808 -0.0276971 0.0493732 0.2229 -0.0285434 0.0513204 0.224574 -0.0349621 0.0561287 0.2229 -0.0419076 0.0601387 0.224574 -0.0419076 0.0601387 0.222427 -0.0509027 0.0587756 0.224574 -0.0440555 0.0558461 0.222427 -0.0440555 0.0558461 0.222427 -0.0376057 0.0521223 0.224574 -0.0316451 0.0476572 0.221231 -0.0499684 0.0622438 0.221498 -0.0495186 0.0626318 0.220854 -0.0504853 0.0613299 0.220979 -0.05123 0.0615337 0.220834 -0.0511516 0.0610359 0.220796 -0.050302 0.0610945 0.220692 -0.0503886 0.0602077 0.221162 -0.0518068 0.0606446 0.220952 -0.0514976 0.0608454 0.221036 -0.0513755 0.0599532 0.220827 -0.0511297 0.0602618 0.22094 -0.0505445 0.0616003 0.221284 -0.0514296 0.0620481 0.220726 -0.0508549 0.060579 0.22116 -0.050257 0.0621387 0.222801 -0.0514593 0.0630068 0.22247 -0.0518044 0.0626821 0.2229 -0.0492811 0.0632934 0.222358 -0.0501568 0.0633531 0.222078 -0.0517378 0.0593424 0.222449 -0.0517756 0.0593242 0.222151 -0.0522821 0.0601438 0.222686 -0.0522691 0.0620442 0.222253 -0.0524607 0.0610557 0.222584 -0.0524919 0.0610345 0.22252 -0.052378 0.0603041 0.222499 -0.0522784 0.060045 0.222183 -0.0516798 0.0627008 0.221905 -0.0515137 0.0626783 0.221761 -0.051969 0.0620572 0.221603 -0.0521696 0.0612869 0.221336 -0.0515668 0.0596838 0.221696 -0.051688 0.0594768 0.222056 -0.0521595 0.0620113 0.222364 -0.0522862 0.0619379 0.221921 -0.0523559 0.0611723 0.221792 -0.0522094 0.0602804 0.22205 -0.0508888 0.0588142 0.221619 -0.0508359 0.0589617 0.22147 -0.0499918 0.0627092 0.221861 -0.0500712 0.0631043 0.221627 -0.0494666 0.0627766 0.22189 -0.0493894 0.0629918 0.222207 -0.0493294 0.0631587 0.22102 -0.0505072 0.0618193 0.221057 -0.0504646 0.0619132 0.221132 -0.0511144 0.0619936 0.221392 -0.0504532 0.0626146 0.221565 -0.0505987 0.0628086 0.221778 -0.0507399 0.0629703 0.222875 -0.0503762 0.0634176 0.22256 -0.0510787 0.0631991 0.222288 -0.0509845 0.063168 0.221653 -0.0513118 0.0626127 0.221498 -0.051721 0.0620701 0.221327 -0.0519069 0.0613904 0.221452 -0.05205 0.0604509 0.222383 -0.0285939 0.0512608 0.22189 -0.0287505 0.0510759 0.221184 -0.0290558 0.0499876 0.220807 -0.0298605 0.0493131 0.220855 -0.0296401 0.049296 0.220834 -0.0295631 0.0485719 0.221275 -0.0285659 0.0495042 0.221132 -0.0287527 0.0490824 0.22147 -0.028694 0.050413 0.221627 -0.0288982 0.0509014 0.221099 -0.0290952 0.0497134 0.22102 -0.0292071 0.0495214 0.220979 -0.0290933 0.0487527 0.220952 -0.029555 0.048177 0.221162 -0.0295743 0.0478088 0.220993 -0.0311629 0.0482267 0.220982 -0.0292798 0.0494485 0.220827 -0.0302442 0.0482037 0.220726 -0.030107 0.0486003 0.222078 -0.0307363 0.0472172 0.222499 -0.0298578 0.0471005 0.222253 -0.0288921 0.0474476 0.221619 -0.0315173 0.0478081 0.22205 -0.0316186 0.0476885 0.222427 -0.0316451 0.0476572 0.222752 -0.0278171 0.0487309 0.222364 -0.0282154 0.0480393 0.222722 -0.0279393 0.0484324 0.22247 -0.0278113 0.048829 0.222828 -0.0276996 0.0496487 0.22256 -0.0277263 0.0497168 0.222288 -0.0278003 0.0497827 0.222183 -0.0278574 0.0489462 0.222056 -0.0282151 0.0481858 0.22192 -0.0288435 0.0475967 0.221792 -0.0296884 0.047278 0.221696 -0.0306447 0.0473276 0.222151 -0.0297703 0.0471467 0.221861 -0.0283123 0.0505419 0.222358 -0.028054 0.0505922 0.222207 -0.0286359 0.0512112 0.221242 -0.0291449 0.0502725 0.221392 -0.0285453 0.0499661 0.221778 -0.0280938 0.0498957 0.221653 -0.0281176 0.049221 0.221905 -0.0279599 0.0490789 0.221497 -0.0283833 0.0485951 0.221327 -0.028879 0.0480947 0.221761 -0.0282705 0.0483738 0.221603 -0.0288374 0.0478154 0.221452 -0.0296204 0.0475013 0.221036 -0.0303885 0.0478365 0.221336 -0.0305262 0.0475361 0.221291 -0.0313749 0.0479764 0.221255 -0.0496701 0.0622096 0.221627 -0.0421533 0.0596477 0.221627 -0.0352645 0.0556704 0.221255 -0.0355963 0.0551676 0.222383 -0.0493075 0.0632198 0.222207 -0.0350409 0.0560093 0.222207 -0.0419717 0.0600107 0.2229 -0.0349621 0.0561287 0.220782 -0.0301275 0.0494495 0.220692 -0.0306619 0.0488184 0.220782 -0.0360882 0.0539341 0.220993 -0.0371947 0.0527452 0.220684 -0.0503661 0.0602706 0.220692 -0.0367677 0.0533923 0.220782 -0.0363123 0.0540826 0.220692 -0.0433746 0.0572068 0.220779 -0.0505109 0.0598671 0.220779 -0.0308957 0.0485423 0.221619 -0.0374968 0.0522874 0.220993 -0.0437216 0.0565134 0.220993 -0.0506506 0.0594779 0.221291 -0.0507614 0.0591692 0.221619 -0.043967 0.0560229 0.221019 -0.0498897 0.0615978 0.220782 -0.0501093 0.060986 0.221231 -0.0499684 0.0622438 0.221019 -0.0297075 0.0499456 0.221255 -0.0292874 0.0504417 0.221099 -0.0290952 0.0497134 0.220807 -0.0298605 0.0493131 0.220879 -0.0295534 0.0493101 0.221255 -0.0353677 0.0550162 0.220782 -0.0430046 0.0579464 0.221255 -0.0424229 0.059109 0.220782 -0.043246 0.0580665 0.221255 -0.0426691 0.0592315 0.224574 -0.0517337 0.0592839 0.224574 -0.0509027 0.0587756 0.222444 -0.0516976 0.0592507 0.224574 -0.0522942 0.0600806 0.224774 -0.0526919 0.0610345 0.224774 -0.0518705 0.059138 0.224974 -0.0294571 0.0505532 0.224974 -0.0304506 0.0484847 0.228169 -0.0307888 0.0482544 0.224974 -0.0315094 0.0479715 0.224974 -0.0337487 0.0484729 0.224774 -0.0327298 0.047772 0.224974 -0.0326861 0.0479672 0.224774 -0.032012 0.0477048 0.224974 -0.0297184 0.0494059 0.224774 -0.0303256 0.0483286 0.224774 -0.0499291 0.0620608 0.224974 -0.0485452 0.0624459 0.224974 -0.049319 0.0622083 0.224974 -0.0498053 0.0619038 0.224774 -0.0506781 0.0584816 0.224974 -0.0506425 0.0588865 0.224974 -0.0507861 0.059442 0.224774 -0.050984 0.0594132 0.224974 -0.0506255 0.0608043 0.224774 -0.0508113 0.0608783 0.224974 -0.0503112 0.0613761 0.224774 -0.0295425 0.0517964 0.224774 -0.0509702 0.0585873 0.224774 -0.0524777 0.0600011 0.224774 -0.0317744 0.0475046 0.224774 -0.0314643 0.0477766 0.224774 -0.0292571 0.0505532 0.224774 -0.0277196 0.0505476 0.224774 -0.0274954 0.0494124 0.224774 -0.0295381 0.0493193 0.224774 -0.0285336 0.0474093 0.224774 -0.0295904 0.0469381 0.224774 -0.0303417 0.0527905 0.224774 -0.034852 0.0562957 0.224774 -0.0418181 0.0603176 0.224774 -0.0471088 0.0624711 0.224774 -0.0485739 0.0626438 0.224774 -0.0504399 0.0636111 0.224774 -0.0515879 0.0631609 0.224774 -0.0492186 0.0571759 0.224974 -0.041125 0.0534742 0.228377 -0.0385869 0.0519262 0.228377 -0.041125 0.0534742 0.224974 -0.038475 0.0580641 0.224774 -0.038375 0.0582374 0.224974 -0.0304655 0.0526335 0.224974 -0.0297225 0.0517091 0.227748 -0.0297791 0.0518193 0.22782 -0.0294706 0.0508206 0.228377 -0.0491445 0.0573617 0.224974 -0.0491445 0.0573617 0.228363 -0.0498111 0.0577477 0.224974 -0.050244 0.0581819 0.227984 -0.0503919 0.0612579 0.224974 -0.0507905 0.0601731 0.228169 -0.0508137 0.0598149 0.227749 -0.0482529 0.062472 0.22782 -0.0492502 0.0622405 0.227925 -0.050084 0.0616497 0.229185 -0.0436442 0.0550741 0.228753 -0.0337233 0.048505 0.228377 -0.0337487 0.0484729 0.229185 -0.0384799 0.0520925 0.228377 -0.0437348 0.0548983 0.22981 -0.0332864 0.0490587 0.228753 -0.0491294 0.0573997 0.22981 -0.0433932 0.0555618 0.22981 -0.0381831 0.0525537 0.229512 -0.0334897 0.048801 0.230112 -0.0377636 0.0532058 0.230112 -0.0430383 0.0562511 0.230021 -0.0482753 0.0595434 0.227721 -0.0471829 0.0622853 0.224974 -0.0471829 0.0622853 0.227721 -0.038475 0.0580641 0.227721 -0.0304655 0.0526335 0.228112 -0.0303925 0.0485326 0.228253 -0.0315168 0.0479698 0.228276 -0.0317554 0.0479266 0.229578 -0.0305544 0.0500372 0.229498 -0.0308316 0.0509886 0.229939 -0.0316874 0.0501207 0.22992 -0.0316121 0.0501272 0.22994 -0.0315103 0.049406 0.229804 -0.0312593 0.0502511 0.230112 -0.0328061 0.0496673 0.23001 -0.0320921 0.0501958 0.229158 -0.0305191 0.051644 0.229256 -0.0303255 0.0511077 0.229024 -0.0298819 0.0502823 0.228494 -0.0296129 0.0500173 0.228347 -0.0299827 0.049015 0.227758 -0.0296904 0.0516406 0.227845 -0.0294571 0.0505532 0.228088 -0.0294996 0.0508874 0.228207 -0.0295628 0.049902 0.228654 -0.0299874 0.0491612 0.22836 -0.0295757 0.0509506 0.228771 -0.0297197 0.050146 0.22895 -0.0300491 0.0493468 0.22976 -0.0324091 0.0486498 0.229185 -0.0336262 0.0486281 0.228718 -0.0327357 0.0480195 0.228492 -0.0307104 0.0483381 0.229417 -0.0307191 0.0489844 0.229822 -0.0314889 0.0490118 0.229968 -0.0322774 0.0490215 0.229612 -0.0314956 0.0486436 0.229459 -0.0325364 0.0483451 0.229322 -0.0315314 0.048335 0.229099 -0.0326479 0.0481328 0.228982 -0.0315918 0.0481097 0.228349 -0.0327766 0.0479892 0.228623 -0.0316694 0.0479758 0.228767 -0.0301423 0.051786 0.2294 -0.0309199 0.0514056 0.229402 -0.030339 0.0505494 0.22887 -0.0298725 0.051053 0.228271 -0.0298862 0.0518453 0.228415 -0.0305542 0.0525212 0.227954 -0.0296467 0.0495687 0.228047 -0.0300273 0.048911 0.228824 -0.0306668 0.0484886 0.229141 -0.030668 0.0487071 0.229213 -0.0301692 0.0495637 0.229765 -0.0309553 0.0496338 0.230024 -0.0330305 0.049383 0.23007 -0.0321539 0.0494224 0.229886 -0.0488191 0.0601537 0.22994 -0.0494556 0.0597668 0.229987 -0.0486152 0.0597794 0.23007 -0.0491198 0.0592178 0.229446 -0.0482474 0.0612299 0.229464 -0.0483167 0.0612025 0.229579 -0.0486199 0.0609828 0.229578 -0.0493872 0.0609095 0.229402 -0.0490513 0.0613526 0.229213 -0.04999 0.0610061 0.229024 -0.0495112 0.0616147 0.229417 -0.0502164 0.0602404 0.229765 -0.0495359 0.0603608 0.229612 -0.0501232 0.0593984 0.230024 -0.0487154 0.0584387 0.229691 -0.0487863 0.060715 0.229822 -0.0498077 0.0595883 0.229968 -0.0494053 0.0589104 0.230112 -0.0485814 0.0587752 0.22835 -0.0500343 0.0579464 0.228623 -0.0506147 0.0589139 0.228276 -0.0506143 0.0588149 0.228492 -0.0507804 0.0599247 0.228143 -0.0508049 0.0600397 0.228047 -0.0506263 0.0608023 0.228347 -0.0505586 0.060893 0.228207 -0.0500003 0.0617008 0.227843 -0.0494762 0.0621256 0.227827 -0.0493193 0.0622082 0.228088 -0.0491778 0.0622489 0.228271 -0.0481548 0.0623929 0.228415 -0.0472358 0.0621523 0.228767 -0.0480782 0.0621414 0.22836 -0.049085 0.0622145 0.228772 -0.0497105 0.061687 0.228494 -0.0498754 0.0617151 0.229141 -0.0504821 0.0601459 0.228982 -0.0505375 0.0590481 0.229322 -0.0503726 0.0592131 0.229459 -0.0498616 0.0583479 0.229512 -0.0489898 0.05775 0.229185 -0.0490714 0.0575454 0.228718 -0.0500439 0.0580125 0.229099 -0.0499897 0.0581452 0.228824 -0.0506719 0.0600377 0.228655 -0.0504296 0.060962 0.229158 -0.0480128 0.0617441 0.229256 -0.0485741 0.0616436 0.22887 -0.0488479 0.0620086 0.22895 -0.0502379 0.0610015 0.22976 -0.0496614 0.0586105 0.22981 -0.0488683 0.0580549 0.222878 -0.0590755 0.0657754 0.221627 -0.0601249 0.0656324 0.221242 -0.0600241 0.0649645 0.221184 -0.0598044 0.0647623 0.220782 -0.0604636 0.0637605 0.220807 -0.0601642 0.0637758 0.220855 -0.0599647 0.0638711 0.220879 -0.0598967 0.0639268 0.220834 -0.0595359 0.0632826 0.220982 -0.0597289 0.0641833 0.221132 -0.0590894 0.0641299 0.221255 -0.0602321 0.0650397 0.221497 -0.0585258 0.0638925 0.221275 -0.0591385 0.0645886 0.221099 -0.0597015 0.0645051 0.220979 -0.0592194 0.0636741 0.221036 -0.0598831 0.062233 0.220827 -0.0599417 0.0626232 0.220952 -0.0593315 0.0629446 0.220726 -0.0600212 0.0630353 0.220779 -0.0606752 0.0625907 0.222446 -0.0599176 0.0614719 0.222151 -0.0590028 0.0619447 0.222591 -0.0583394 0.0626766 0.222253 -0.0583927 0.0626445 0.222752 -0.0581033 0.0642933 0.222364 -0.0581025 0.0634952 0.22247 -0.0581474 0.0643811 0.222358 -0.0592392 0.0657868 0.22147 -0.0597039 0.0653116 0.221778 -0.0589254 0.0651637 0.221905 -0.058401 0.0645232 0.221761 -0.0583175 0.0637573 0.222183 -0.0582459 0.0644596 0.221452 -0.0590503 0.0623268 0.221336 -0.0598521 0.0619041 0.221291 -0.0608072 0.061861 0.222078 -0.0598747 0.0615228 0.221696 -0.0598505 0.0616642 0.221792 -0.0589975 0.0620994 0.22192 -0.0584251 0.0627979 0.222056 -0.0581755 0.0636222 0.222288 -0.0586147 0.0652126 0.22256 -0.0585176 0.0651925 0.221861 -0.0594377 0.0656141 0.222207 -0.0600526 0.0660319 0.22189 -0.0600842 0.0658574 0.221392 -0.0593516 0.0649989 0.221653 -0.0586087 0.0645675 0.221327 -0.0587049 0.0632113 0.221603 -0.0585292 0.0629903 0.221162 -0.0591641 0.0626162 0.220993 -0.0607488 0.0621838 0.221255 -0.0762159 0.0659611 0.22189 -0.0839159 0.0658574 0.221627 -0.0838752 0.0656324 0.221255 -0.0759414 0.0659781 0.221627 -0.0680228 0.0665794 0.2229 -0.07601 0.0671275 0.222383 -0.060041 0.0660958 0.222207 -0.0760015 0.0669846 0.221627 -0.0759773 0.0665794 0.222207 -0.0679986 0.0669846 0.2229 -0.0600271 0.0661728 0.221619 -0.0608465 0.061644 0.220692 -0.0758145 0.0638549 0.220782 -0.0678679 0.0646638 0.220692 -0.0606108 0.0629467 0.221619 -0.0757356 0.0625334 0.220993 -0.0682318 0.0630809 0.220993 -0.0757683 0.0630809 0.220692 -0.0681855 0.0638549 0.222427 -0.0682763 0.062336 0.222427 -0.0608817 0.0614494 0.22205 -0.0608744 0.0614898 0.221291 -0.0831929 0.061861 0.22205 -0.0831257 0.0614898 0.221619 -0.0682645 0.0625334 0.222427 -0.0757238 0.062336 0.22116 -0.0842408 0.0646848 0.221057 -0.0843078 0.0643857 0.22102 -0.0842977 0.0642831 0.221019 -0.0603478 0.0644001 0.22102 -0.0597024 0.0642828 0.221255 -0.0677851 0.0659612 0.220782 -0.0681362 0.0646804 0.220782 -0.0758639 0.0646804 0.221255 -0.0680587 0.0659781 0.220782 -0.076133 0.0646637 0.221019 -0.0836522 0.0644001 0.221231 -0.0840434 0.0649201 0.222706 -0.0859457 0.0638111 0.222664 -0.0859073 0.0633834 0.224574 -0.0857197 0.0627944 0.222516 -0.0851171 0.0619971 0.224574 -0.0841591 0.0614908 0.222499 -0.0849445 0.0618609 0.224774 -0.0861457 0.0638111 0.224574 -0.0850843 0.0619692 0.224774 -0.0842102 0.0612975 0.224774 -0.0830828 0.0612526 0.228 -0.0600798 0.0637264 0.228047 -0.0601075 0.0633441 0.224974 -0.0603197 0.0626246 0.228117 -0.0602507 0.0627901 0.224974 -0.060996 0.0617223 0.228258 -0.0609612 0.061753 0.228276 -0.0611119 0.0616276 0.224974 -0.0619863 0.0611828 0.224974 -0.0631112 0.061104 0.224774 -0.0619302 0.0609909 0.224974 -0.0600798 0.0637264 0.224774 -0.0608652 0.061571 0.224774 -0.072 0.0672471 0.227748 -0.0613467 0.0659869 0.227721 -0.0623483 0.0663488 0.22782 -0.0605802 0.0652762 0.227864 -0.0603454 0.0648829 0.227925 -0.0601538 0.0643486 0.224974 -0.0808889 0.061104 0.228363 -0.0816592 0.0611051 0.22835 -0.0819518 0.0611656 0.227984 -0.0839172 0.0638546 0.228047 -0.0838924 0.0633428 0.228143 -0.0836658 0.0625931 0.224974 -0.0833507 0.0620849 0.227749 -0.0826718 0.0659755 0.22782 -0.0834197 0.0652764 0.227827 -0.0834635 0.0652139 0.227925 -0.0838464 0.0643479 0.230021 -0.0812269 0.0634281 0.228377 -0.0631112 0.061104 0.228753 -0.0631053 0.0611446 0.228377 -0.0690279 0.0616756 0.228377 -0.072 0.0617471 0.228377 -0.0749722 0.0616756 0.229512 -0.0630511 0.0615177 0.228377 -0.0808889 0.061104 0.228753 -0.0808948 0.0611446 0.229185 -0.0749817 0.0618731 0.229185 -0.0809173 0.0612997 0.22981 -0.0750081 0.062421 0.22981 -0.0809963 0.0618425 0.230024 -0.0629443 0.0622513 0.22981 -0.068992 0.062421 0.229185 -0.0690184 0.0618731 0.230112 -0.0628922 0.0626098 0.230112 -0.0689547 0.0631954 0.230112 -0.0750454 0.0631954 0.224974 -0.0816518 0.0663488 0.227721 -0.072 0.0670471 0.224974 -0.072 0.0670471 0.224974 -0.0623483 0.0663488 0.22964 -0.0617355 0.0643278 0.22992 -0.0620881 0.063605 0.229578 -0.0611271 0.0640559 0.23007 -0.0622049 0.0627237 0.229968 -0.0621114 0.0623148 0.22976 -0.0620396 0.061927 0.229612 -0.0612454 0.0623784 0.22994 -0.0616393 0.0630313 0.229256 -0.0614641 0.0650974 0.229822 -0.0614237 0.0627007 0.229765 -0.0612725 0.0635061 0.229024 -0.0606673 0.0646044 0.229402 -0.0611966 0.0646072 0.228347 -0.0601208 0.0634565 0.227764 -0.0610922 0.0658101 0.228088 -0.0606387 0.0653196 0.227872 -0.0603097 0.0648062 0.229691 -0.0617448 0.0641876 0.22887 -0.0610445 0.0652766 0.228349 -0.0620276 0.0611711 0.228492 -0.0604126 0.0625065 0.228169 -0.0604387 0.0623947 0.22836 -0.0607362 0.0653363 0.228654 -0.0601981 0.0635807 0.228824 -0.0604501 0.0626586 0.229141 -0.0605604 0.0628472 0.229322 -0.0611221 0.0620933 0.229099 -0.0619879 0.0613599 0.229185 -0.0630828 0.0612997 0.228207 -0.0602008 0.0644346 0.228494 -0.0603018 0.0645095 0.228623 -0.061062 0.0617132 0.228982 -0.0610618 0.0618679 0.228718 -0.0620073 0.0612178 0.227722 -0.0622076 0.0663245 0.228239 -0.0623596 0.0662715 0.228731 -0.0623944 0.0660318 0.228767 -0.0616446 0.0657765 0.229158 -0.0618999 0.0654651 0.2294 -0.0621278 0.0650583 0.228271 -0.0614524 0.0659559 0.228771 -0.0604586 0.0645675 0.22895 -0.0603443 0.0637107 0.229213 -0.0605567 0.0638384 0.229417 -0.0607433 0.0630618 0.229459 -0.0619975 0.0615995 0.22981 -0.0630038 0.0618425 0.228239 -0.0816405 0.0662715 0.229213 -0.0834433 0.0638374 0.22994 -0.0823608 0.0630314 0.229987 -0.0816393 0.0634625 0.229158 -0.0821 0.0654652 0.229377 -0.0817133 0.0651456 0.229446 -0.082046 0.0649026 0.229402 -0.0828036 0.0646069 0.229024 -0.083333 0.0646039 0.229579 -0.082245 0.0645023 0.229578 -0.0828729 0.0640552 0.229691 -0.0822553 0.0641872 0.229417 -0.0832565 0.0630612 0.229765 -0.0827273 0.0635057 0.229822 -0.0825765 0.0627008 0.23007 -0.0817954 0.0627238 0.229968 -0.081889 0.0623149 0.230112 -0.0811079 0.0626098 0.230024 -0.0810557 0.0622513 0.228718 -0.0819932 0.061218 0.228276 -0.0828883 0.0616277 0.228169 -0.083561 0.062394 0.228492 -0.0835871 0.0625057 0.228347 -0.0838791 0.0634553 0.228207 -0.0837995 0.064434 0.228088 -0.0833612 0.0653198 0.227843 -0.083558 0.0650639 0.228271 -0.0825473 0.0659561 0.228415 -0.0816312 0.0662072 0.228994 -0.0815727 0.0658055 0.228767 -0.0823552 0.0657766 0.22887 -0.0829555 0.0652767 0.228655 -0.0838019 0.0635795 0.228824 -0.0835496 0.0626579 0.229512 -0.080949 0.0615177 0.229099 -0.0820126 0.06136 0.228982 -0.0829384 0.061868 0.228623 -0.0829382 0.0617133 0.228494 -0.0836985 0.0645088 0.22836 -0.0832637 0.0653365 0.229256 -0.0825358 0.0650975 0.228772 -0.0835416 0.0645669 0.22895 -0.0836557 0.0637095 0.229141 -0.0834393 0.0628465 0.229612 -0.0827547 0.0623785 0.229322 -0.0828781 0.0620934 0.229459 -0.0820029 0.0615996 0.22976 -0.0819609 0.0619272 0.229366 -0.0767554 0.0657239 0.23001 -0.0625381 0.0634244 0.230021 -0.0627732 0.0634281 0.229939 -0.0621501 0.0635618 0.229465 -0.0619077 0.0648442 0.229498 -0.0618428 0.0647413 0.229804 -0.0618445 0.0638887 0.229694 -0.0813565 0.0643187 0.229366 -0.081486 0.0652094 0.229464 -0.0820924 0.0648443 0.229886 -0.082003 0.0636847 0.229742 -0.0822241 0.0640503 0.230021 -0.0750852 0.0640214 0.229366 -0.072 0.0658957 0.230021 -0.0719996 0.0640957 0.230021 -0.0689149 0.0640214 0.229694 -0.0626436 0.0643187 0.227721 -0.0816518 0.0663488 0.227721 -0.0768385 0.0668723 0.228994 -0.0672012 0.0663247 0.228994 -0.0624273 0.0658055 0.229366 -0.0625141 0.0652094 0.229366 -0.0672446 0.0657239 0.228731 -0.0816057 0.0660318 0.228994 -0.0767989 0.0663247 0.228994 -0.072 0.0664981 0.228415 -0.0671719 0.0667296 0.228415 -0.0623689 0.0662072 0.228415 -0.0768282 0.0667296 0.228415 -0.072 0.066904 0.227721 -0.0671616 0.0668723 0.224574 -0.0608817 0.0614494 0.224574 -0.0757238 0.062336 0.224774 -0.0679781 0.0673271 0.224574 -0.07601 0.0671275 0.224574 -0.083973 0.0661728 0.224774 -0.0851045 0.065892 0.224774 -0.0858709 0.0649745 0.224574 -0.0589035 0.0656427 0.224774 -0.0587743 0.0657953 0.224574 -0.0581955 0.0646219 0.224574 -0.0580599 0.0639738 0.224574 -0.0580927 0.0633838 0.224574 -0.0582687 0.0628197 0.224774 -0.0578959 0.0633482 0.224774 -0.0609173 0.0612526 0.224774 -0.059576 0.061364 0.224574 -0.0586228 0.0622602 0.224774 -0.0827769 0.0613072 0.224774 -0.0823252 0.0610788 0.224774 -0.0612232 0.0613072 0.224774 -0.06314 0.0609061 0.224774 -0.072 0.0615471 0.224774 -0.0682882 0.0621364 0.224774 -0.0757119 0.0621364 0.224574 -0.0849846 0.0657319 0.222874 -0.0849959 0.0657234 0.222828 -0.0855397 0.0651467 0.222801 -0.0857185 0.0648304 0.222752 -0.0858966 0.064294 0.224574 -0.085692 0.064885 0.224574 -0.0859457 0.0638111 0.222437 -0.0601791 0.0614269 0.224574 -0.0596436 0.0615522 0.224574 -0.0589995 0.0619024 0.222705 -0.0580544 0.063798 0.222664 -0.058093 0.0633823 0.222607 -0.0582687 0.0628197 0.222499 -0.0590554 0.061861 0.222828 -0.0584605 0.0651469 0.224574 -0.0584229 0.065089 0.222823 -0.0584228 0.0650889 0.222808 -0.0583206 0.0649096 0.222722 -0.05806 0.0639737 0.224574 -0.0600271 0.0661728 0.224574 -0.0679901 0.0671275 0.2229 -0.0679901 0.0671275 0.222427 -0.0831184 0.0614494 0.224574 -0.0831184 0.0614494 0.224574 -0.0682763 0.062336 0.221255 -0.083768 0.0650397 0.221231 -0.0840434 0.0649201 0.220854 -0.0840342 0.0638702 0.220796 -0.0837576 0.063758 0.220782 -0.0835365 0.0637605 0.220684 -0.0834012 0.0630125 0.220827 -0.0840582 0.062623 0.220692 -0.0833893 0.0629467 0.221036 -0.0841167 0.0622329 0.220993 -0.0832513 0.0621838 0.220779 -0.0833249 0.0625906 0.221132 -0.0849108 0.0641305 0.22094 -0.0842206 0.0640748 0.221327 -0.0852954 0.0632118 0.220979 -0.0847809 0.0636744 0.220952 -0.0846686 0.0629445 0.220834 -0.0844641 0.0632825 0.220726 -0.0839787 0.0630351 0.221778 -0.0850748 0.0651636 0.221498 -0.0854743 0.0638934 0.22147 -0.0842964 0.0653115 0.221565 -0.0848716 0.0650941 0.22256 -0.0854826 0.0651923 0.2229 -0.083973 0.0661728 0.222881 -0.0848682 0.0658138 0.222078 -0.084125 0.0615227 0.222449 -0.0841487 0.0614881 0.222576 -0.0855779 0.0625344 0.222618 -0.0857765 0.062926 0.221905 -0.085599 0.0645238 0.221603 -0.0854712 0.0629909 0.221921 -0.0855753 0.0627985 0.221696 -0.0841492 0.0616641 0.221336 -0.0841476 0.0619039 0.221619 -0.0831536 0.061644 0.22247 -0.0858526 0.0643818 0.222183 -0.085754 0.0644602 0.222364 -0.0858978 0.0634963 0.222056 -0.0858247 0.0636233 0.222253 -0.0856078 0.0626451 0.222151 -0.0849971 0.0619446 0.221792 -0.0850025 0.0620993 0.221498 -0.0838478 0.0654811 0.221861 -0.0845627 0.0656139 0.221057 -0.0843078 0.0643857 0.221284 -0.085211 0.06402 0.221392 -0.0846486 0.0649989 0.222358 -0.0847612 0.0657866 0.222207 -0.0839475 0.0660319 0.222383 -0.0839591 0.0660958 0.222288 -0.0853855 0.0652124 0.221653 -0.0853913 0.0645679 0.221761 -0.0856827 0.0637583 0.221452 -0.0849497 0.0623267 0.221162 -0.0848359 0.062616 0.224974 -0.0829119 0.0658068 0.224774 -0.0830358 0.0659638 0.224974 -0.0834633 0.0652141 0.224974 -0.0837321 0.0647073 0.224974 -0.0822512 0.0612646 0.224974 -0.0829486 0.0616756 0.224774 -0.0835077 0.061961 0.224974 -0.08372 0.0627158 0.224774 -0.0840906 0.0633162 0.224974 -0.0838927 0.063345 0.224974 -0.0839064 0.0639973 0.224974 -0.0611902 0.0658834 0.224774 -0.0623195 0.0665467 0.224774 -0.061074 0.0660461 0.224974 -0.0603737 0.0649394 0.224774 -0.0598798 0.0637264 0.224774 -0.0852125 0.0618157 0.224774 -0.0859009 0.0627097 0.224774 -0.0601959 0.065031 0.224774 -0.0580073 0.0646894 0.224774 -0.0601378 0.0625414 0.224774 -0.0584702 0.062131 0.224774 -0.0599915 0.0663696 0.224774 -0.076022 0.0673271 0.224774 -0.0816806 0.0665467 0.224774 -0.0840086 0.0663696 0.224774 -0.0839179 0.0647813 0.224774 -0.0808601 0.0609061 0.224974 -0.072 0.0617471 0.224774 -0.115586 0.0514731 0.224774 -0.116265 0.0505824 0.224774 -0.0922281 0.0630187 0.224774 -0.0934453 0.0635929 0.224574 -0.0923573 0.0628661 0.224574 -0.0916493 0.0618453 0.224574 -0.0920766 0.0594836 0.2229 -0.115457 0.0513204 0.224574 -0.115457 0.0513204 0.222878 -0.116088 0.050488 0.224574 -0.116083 0.0504983 0.222427 -0.0930974 0.0587756 0.224574 -0.0930974 0.0587756 0.222437 -0.0924777 0.0591073 0.224574 -0.0916938 0.0601089 0.222664 -0.0916488 0.0618438 0.224574 -0.0915197 0.0612687 0.224574 -0.0915465 0.0606072 0.222591 -0.0915093 0.0611094 0.224574 -0.0934809 0.0633961 0.222878 -0.0936962 0.0634251 0.222828 -0.0928494 0.0631883 0.224574 -0.0927879 0.0631569 0.222823 -0.0927877 0.0631568 0.222808 -0.0926095 0.0630527 0.224574 -0.0919159 0.0623726 0.224574 -0.094719 0.0632934 0.224574 -0.102092 0.0601387 0.2229 -0.109038 0.0561287 0.224574 -0.109038 0.0561287 0.224574 -0.112355 0.0476572 0.224574 -0.106394 0.0521223 0.224574 -0.0999446 0.0558461 0.22094 -0.114622 0.0493797 0.220979 -0.114907 0.0487528 0.220796 -0.114063 0.0493369 0.220726 -0.113893 0.0486003 0.220827 -0.113756 0.0482037 0.220952 -0.114445 0.0481769 0.221162 -0.114426 0.0478088 0.221036 -0.113611 0.0478365 0.220993 -0.112837 0.0482267 0.221327 -0.115122 0.048095 0.220834 -0.114437 0.0485718 0.220692 -0.113338 0.0488184 0.221778 -0.115906 0.0498955 0.221284 -0.115453 0.0488371 0.221392 -0.115455 0.049966 0.221565 -0.115696 0.049937 0.22247 -0.116189 0.0488296 0.22256 -0.116274 0.0497166 0.222828 -0.116301 0.0496485 0.222817 -0.116306 0.0494888 0.222735 -0.116119 0.0485603 0.222664 -0.115737 0.0479377 0.222383 -0.115406 0.0512608 0.222151 -0.11423 0.0471467 0.222449 -0.113267 0.0471755 0.222427 -0.112355 0.0476572 0.222514 -0.114345 0.0471294 0.222056 -0.115786 0.0481867 0.221603 -0.115163 0.0478157 0.221336 -0.113474 0.0475362 0.221291 -0.112625 0.0479764 0.222364 -0.115785 0.0480402 0.222183 -0.116143 0.0489468 0.222253 -0.115109 0.047448 0.221921 -0.115157 0.0475971 0.221792 -0.114312 0.0472779 0.221696 -0.113355 0.0473277 0.222078 -0.113263 0.0472174 0.221231 -0.114891 0.0502004 0.22147 -0.115306 0.0504129 0.221627 -0.115102 0.0509014 0.222207 -0.115364 0.0512112 0.221057 -0.114853 0.0496054 0.221132 -0.115248 0.0490829 0.221861 -0.115688 0.0505416 0.222358 -0.115946 0.0505919 0.222288 -0.1162 0.0497825 0.221653 -0.115883 0.0492215 0.221905 -0.11604 0.0490794 0.221761 -0.11573 0.0483746 0.221498 -0.115617 0.0485958 0.221452 -0.11438 0.0475012 0.220834 -0.0928485 0.061036 0.220879 -0.093483 0.0614135 0.221184 -0.0938209 0.0621832 0.221099 -0.0936032 0.0620119 0.22147 -0.0940084 0.0627092 0.221627 -0.0945335 0.0627766 0.221132 -0.0928855 0.0619931 0.221275 -0.0931574 0.0623657 0.221653 -0.0926879 0.0626124 0.22102 -0.0934928 0.061819 0.221327 -0.0920932 0.0613898 0.220952 -0.0925025 0.0608455 0.221162 -0.0921933 0.0606448 0.220979 -0.0927702 0.0615333 0.220982 -0.093466 0.0617196 0.220726 -0.0931451 0.0605792 0.220827 -0.0928702 0.0602621 0.220779 -0.0934892 0.0598672 0.222446 -0.0922737 0.0592771 0.222078 -0.092262 0.0593426 0.222499 -0.0917216 0.0600451 0.222151 -0.0917179 0.0601439 0.222607 -0.0915196 0.0612688 0.222752 -0.0921132 0.0626276 0.222364 -0.0917134 0.0619368 0.222705 -0.0918232 0.0622231 0.222722 -0.0919158 0.0623725 0.22247 -0.0921953 0.0626817 0.222358 -0.0938437 0.0633531 0.221861 -0.0939292 0.0631042 0.222183 -0.0923199 0.0627003 0.221452 -0.09195 0.0604511 0.221696 -0.0923118 0.0594771 0.221792 -0.0917906 0.0602805 0.22192 -0.0916442 0.0611716 0.222253 -0.0915394 0.061055 0.222056 -0.0918402 0.0620103 0.22256 -0.0929216 0.0631992 0.222288 -0.0930157 0.0631681 0.22189 -0.0946107 0.0629917 0.221255 -0.09433 0.0622096 0.221392 -0.093547 0.0626145 0.221778 -0.0932604 0.0629703 0.221905 -0.092486 0.0626779 0.221761 -0.0920307 0.0620563 0.221497 -0.0922787 0.0620693 0.221603 -0.0918305 0.0612862 0.221036 -0.0926244 0.0599535 0.221336 -0.0924331 0.0596841 0.221291 -0.0932387 0.0591692 0.221255 -0.114713 0.0504417 0.22189 -0.11525 0.0510759 0.221498 -0.115003 0.050784 0.221255 -0.108404 0.0551676 0.222207 -0.108959 0.0560093 0.221627 -0.101847 0.0596477 0.222207 -0.0946706 0.0631587 0.221627 -0.108736 0.0556704 0.222207 -0.102028 0.0600107 0.2229 -0.102092 0.0601387 0.222383 -0.0946926 0.0632198 0.2229 -0.094719 0.0632934 0.220782 -0.100996 0.0579464 0.220692 -0.107232 0.0533923 0.220782 -0.0938908 0.060986 0.220782 -0.100755 0.0580662 0.220782 -0.113873 0.0494495 0.220782 -0.107913 0.0539336 0.220684 -0.113381 0.0488694 0.220993 -0.100279 0.0565134 0.220779 -0.113104 0.0485423 0.220692 -0.100625 0.0572068 0.220993 -0.106805 0.0527452 0.220993 -0.0933495 0.0594779 0.220692 -0.0936114 0.0602077 0.222427 -0.0999446 0.0558461 0.22205 -0.0931113 0.0588142 0.221619 -0.112483 0.0478081 0.221619 -0.0931642 0.0589617 0.221619 -0.106503 0.0522874 0.221619 -0.100033 0.0560229 0.222427 -0.106394 0.0521223 0.22205 -0.112381 0.0476885 0.22094 -0.114622 0.0493797 0.220854 -0.114358 0.0492958 0.22116 -0.114945 0.0498979 0.22102 -0.114793 0.0495216 0.221255 -0.101332 0.0592311 0.221242 -0.0941122 0.0622485 0.221019 -0.0941104 0.0615978 0.220807 -0.0936392 0.061149 0.220855 -0.0935141 0.0613313 0.220879 -0.093483 0.0614135 0.220982 -0.093466 0.0617196 0.221099 -0.0936032 0.0620119 0.220782 -0.107688 0.0540826 0.221255 -0.101577 0.059109 0.221255 -0.108633 0.0550157 0.221019 -0.114293 0.0499456 0.224574 -0.116306 0.0494888 0.222519 -0.114405 0.0471413 0.224574 -0.114399 0.0471399 0.222576 -0.115027 0.047367 0.224574 -0.11538 0.047595 0.222622 -0.115429 0.0476344 0.222499 -0.114142 0.0471005 0.224574 -0.116062 0.0484348 0.224774 -0.116242 0.048347 0.224774 -0.115503 0.0474371 0.224774 -0.11444 0.0469442 0.224574 -0.113317 0.0471622 0.224774 -0.113268 0.0469683 0.224974 -0.0933927 0.0587983 0.228353 -0.0940174 0.0578963 0.224974 -0.0948555 0.0573617 0.224774 -0.0929864 0.0598235 0.224774 -0.0938394 0.0577901 0.224974 -0.0939796 0.0579328 0.224774 -0.111483 0.0477329 0.224974 -0.112874 0.0480914 0.224974 -0.113509 0.0484531 0.224974 -0.0931864 0.0598235 0.224774 -0.0933184 0.0611584 0.224974 -0.0934951 0.0610647 0.224774 -0.11413 0.0487877 0.224774 -0.112948 0.0479056 0.224774 -0.112226 0.0475046 0.224774 -0.094237 0.0621824 0.224774 -0.0914611 0.0619128 0.224774 -0.0913497 0.0605716 0.224774 -0.091924 0.0593544 0.224774 -0.0930298 0.0585873 0.224774 -0.0932083 0.0587209 0.224774 -0.114713 0.0501429 0.224774 -0.116506 0.0494888 0.224774 -0.114541 0.0516081 0.224774 -0.113658 0.0527905 0.224774 -0.105625 0.0582374 0.224774 -0.109148 0.0562957 0.224774 -0.0968913 0.0624711 0.224774 -0.0947866 0.0634816 0.224774 -0.0955282 0.0626568 0.224774 -0.110128 0.0483158 0.224774 -0.102775 0.053301 0.224974 -0.102875 0.0534742 0.224774 -0.0947815 0.0571759 0.228377 -0.100265 0.0548983 0.228377 -0.105413 0.0519262 0.224974 -0.113535 0.0526335 0.224974 -0.0968172 0.0622853 0.227721 -0.0968172 0.0622853 0.224974 -0.0955499 0.0624579 0.227759 -0.0955502 0.062458 0.224974 -0.0948502 0.0622831 0.227811 -0.0948496 0.0622829 0.224974 -0.0943492 0.0620168 0.227869 -0.0943063 0.0619871 0.227925 -0.0939166 0.0616502 0.224974 -0.0939164 0.06165 0.22801 -0.0935005 0.0610748 0.228047 -0.0933743 0.0608035 0.224974 -0.110251 0.0484729 0.224974 -0.111512 0.0479308 0.224974 -0.114311 0.0494697 0.224974 -0.113973 0.0489116 0.228047 -0.113972 0.0489099 0.228169 -0.113211 0.0482539 0.224974 -0.112321 0.047938 0.224974 -0.114355 0.051534 0.227721 -0.113535 0.0526335 0.227749 -0.114231 0.0518002 0.224974 -0.114536 0.0507451 0.227827 -0.114536 0.0507448 0.224974 -0.114515 0.0501717 0.227925 -0.114435 0.0498033 0.230021 -0.111706 0.0503165 0.22981 -0.105817 0.0525537 0.228377 -0.0948555 0.0573617 0.229185 -0.0949287 0.0575454 0.229185 -0.100356 0.0550741 0.228377 -0.102875 0.0534742 0.228377 -0.110251 0.0484729 0.22981 -0.100607 0.0555618 0.22981 -0.0951318 0.0580549 0.229185 -0.10552 0.0520925 0.230112 -0.0954187 0.0587752 0.230024 -0.0952846 0.0584387 0.230112 -0.100962 0.0562511 0.229512 -0.0950103 0.05775 0.230112 -0.106237 0.0532058 0.230021 -0.10134 0.0569863 0.230021 -0.104049 0.0555083 0.224974 -0.105525 0.0580641 0.227721 -0.101247 0.060332 0.229822 -0.0941924 0.0595882 0.229765 -0.0944642 0.0603613 0.229498 -0.0955757 0.0611458 0.229939 -0.095252 0.0599707 0.22994 -0.0945445 0.0597667 0.229804 -0.0951509 0.0604066 0.23007 -0.0948805 0.0592175 0.229968 -0.094595 0.0589101 0.23001 -0.0955194 0.0596577 0.229417 -0.0937838 0.0602411 0.229213 -0.0940105 0.061007 0.229024 -0.0944892 0.0616151 0.229578 -0.0946132 0.0609101 0.229402 -0.0949491 0.0613528 0.22836 -0.0949148 0.0622144 0.228239 -0.0967883 0.0622126 0.227748 -0.0957689 0.0624726 0.228349 -0.0939506 0.0579616 0.228718 -0.0939564 0.0580122 0.228168 -0.0931864 0.0598235 0.228347 -0.093442 0.0608942 0.228252 -0.0933008 0.0590532 0.228623 -0.0933855 0.0589138 0.228276 -0.0933859 0.0588148 0.228771 -0.0942901 0.0616874 0.228654 -0.093571 0.0609631 0.22895 -0.0937626 0.0610025 0.229141 -0.0935181 0.0601467 0.228982 -0.0934626 0.0590479 0.229099 -0.0940106 0.0581449 0.229459 -0.0941388 0.0583476 0.228207 -0.0940003 0.0617013 0.228494 -0.0941252 0.0617156 0.228492 -0.0932197 0.0599255 0.228824 -0.0933282 0.0600385 0.228753 -0.0948707 0.0573997 0.228415 -0.0967643 0.0621523 0.228731 -0.0966987 0.0619877 0.229158 -0.0959871 0.0617442 0.2294 -0.095981 0.0612778 0.229366 -0.096391 0.0612156 0.22964 -0.095276 0.0608414 0.229256 -0.0954258 0.0616436 0.228767 -0.0959216 0.0621414 0.228271 -0.0958449 0.0623929 0.228088 -0.0948221 0.0622488 0.22887 -0.095152 0.0620086 0.229612 -0.0938769 0.0593982 0.229322 -0.0936275 0.059213 0.22976 -0.094339 0.0586102 0.229578 -0.113445 0.0500366 0.229886 -0.112507 0.0501507 0.22994 -0.11249 0.049406 0.229987 -0.112081 0.0501402 0.23007 -0.111846 0.0494224 0.230112 -0.111194 0.0496673 0.229446 -0.113153 0.0511839 0.229402 -0.113661 0.050549 0.229579 -0.113125 0.0507378 0.229691 -0.112976 0.0504597 0.229765 -0.113044 0.0496335 0.229822 -0.112511 0.0490119 0.229612 -0.112505 0.0486436 0.22976 -0.111591 0.0486497 0.229968 -0.111723 0.0490214 0.230024 -0.11097 0.049383 0.229742 -0.112881 0.0503567 0.22835 -0.111203 0.0479947 0.228276 -0.112245 0.0479266 0.228143 -0.113401 0.048374 0.228347 -0.114017 0.0490139 0.229185 -0.110374 0.0486281 0.228718 -0.111265 0.0480194 0.228753 -0.110277 0.048505 0.228363 -0.110919 0.0480886 0.227984 -0.114249 0.0493407 0.227843 -0.114543 0.0505676 0.22782 -0.114529 0.0508208 0.228271 -0.114114 0.0518456 0.228767 -0.113858 0.0517862 0.22887 -0.114128 0.0510532 0.228772 -0.11428 0.0501454 0.22895 -0.11395 0.0493459 0.228655 -0.114012 0.0491601 0.228824 -0.113333 0.0484881 0.229322 -0.112469 0.048335 0.229459 -0.111464 0.048345 0.229099 -0.111353 0.0481327 0.229512 -0.11051 0.048801 0.228623 -0.112331 0.0479758 0.228982 -0.112408 0.0481097 0.228492 -0.113289 0.0483376 0.228207 -0.114437 0.0499013 0.228494 -0.114387 0.0500167 0.228088 -0.1145 0.0508877 0.22836 -0.114424 0.0509508 0.228415 -0.113446 0.0525212 0.228731 -0.113336 0.052382 0.229377 -0.112986 0.0515607 0.229158 -0.113481 0.0516442 0.229256 -0.113674 0.0511078 0.229024 -0.114118 0.0502818 0.229213 -0.11383 0.0495628 0.229417 -0.11328 0.048984 0.229141 -0.113331 0.0487066 0.22981 -0.110714 0.0490587 0.230021 -0.0957248 0.0595434 0.22992 -0.09522 0.0600391 0.229465 -0.0956833 0.0612025 0.229694 -0.0960579 0.0603795 0.229691 -0.0952139 0.0607154 0.229366 -0.112821 0.0517296 0.229694 -0.112264 0.0510231 0.229464 -0.113164 0.0511102 0.230021 -0.106684 0.0539012 0.229366 -0.100745 0.0592959 0.228994 -0.096614 0.0617752 0.228994 -0.105251 0.0575886 0.229366 -0.104949 0.0570669 0.229366 -0.108982 0.0545405 0.228994 -0.113194 0.0522025 0.228994 -0.10932 0.0550391 0.228415 -0.109548 0.0553751 0.228994 -0.101008 0.0598379 0.228415 -0.105453 0.0579402 0.228239 -0.113486 0.0525722 0.227721 -0.109628 0.0554935 0.227721 -0.105525 0.0580641 0.228415 -0.101185 0.0602032 0.224774 -0.093322 0.0584816 0.224774 -0.0998551 0.0556672 0.224774 -0.106284 0.0519554 0.224774 -0.111988 0.0477048 0.224774 -0.102182 0.0603176 0.222852 -0.135326 0.0211829 0.222881 -0.135433 0.0217614 0.222886 -0.135437 0.0219053 0.222684 -0.134035 0.0197227 0.224574 -0.135181 0.0208266 0.222624 -0.133449 0.0195408 0.224574 -0.132342 0.0196082 0.222514 -0.132236 0.019643 0.224574 -0.131384 0.0201657 0.222449 -0.131326 0.020223 0.224774 -0.131246 0.0200208 0.224574 -0.132236 0.0196431 0.224774 -0.13536 0.0207367 0.224574 -0.134556 0.0200468 0.224574 -0.134468 0.0199781 0.224774 -0.134587 0.0198175 0.224574 -0.133449 0.0195408 0.224974 -0.119906 0.0398901 0.224974 -0.120053 0.0390213 0.224774 -0.119864 0.0389557 0.230112 -0.130778 0.0234158 0.229185 -0.124095 0.0335173 0.228377 -0.123929 0.0334103 0.229185 -0.127077 0.0283529 0.228377 -0.126901 0.0282624 0.228377 -0.129365 0.0228526 0.229512 -0.129753 0.0230074 0.230112 -0.12167 0.0391911 0.230024 -0.121386 0.0389667 0.22981 -0.124557 0.0338141 0.22981 -0.127565 0.028604 0.22981 -0.130058 0.0231289 0.230112 -0.125209 0.0342336 0.230112 -0.128254 0.0289589 0.227721 -0.132335 0.0292445 0.224974 -0.130067 0.0335221 0.227721 -0.130067 0.0335221 0.224974 -0.124636 0.0415316 0.227721 -0.127496 0.037625 0.227721 -0.124636 0.0415316 0.229498 -0.122991 0.0411656 0.22994 -0.121409 0.0404869 0.22992 -0.12213 0.040385 0.229804 -0.122254 0.0407379 0.23007 -0.121425 0.0398433 0.22981 -0.121062 0.0387108 0.229968 -0.121024 0.0397198 0.22976 -0.120653 0.0395881 0.229612 -0.120646 0.0405016 0.23001 -0.122199 0.0399051 0.230021 -0.122319 0.0397033 0.229158 -0.123647 0.0414781 0.229822 -0.121015 0.0405083 0.229765 -0.121637 0.0410419 0.229213 -0.121567 0.041828 0.229024 -0.122285 0.0421152 0.228088 -0.12289 0.0424976 0.227722 -0.124533 0.041655 0.227748 -0.123822 0.0422181 0.228271 -0.123848 0.042111 0.229691 -0.122463 0.0409737 0.229578 -0.12204 0.0414428 0.229402 -0.122552 0.0416582 0.22964 -0.12258 0.0410518 0.229256 -0.123111 0.0416716 0.22887 -0.123056 0.0421247 0.228377 -0.120476 0.0382485 0.228753 -0.120508 0.0382739 0.228358 -0.120051 0.0390271 0.228718 -0.120022 0.0392614 0.22835 -0.119998 0.0391995 0.228492 -0.120341 0.0412868 0.228494 -0.12202 0.0423843 0.229322 -0.120338 0.0404658 0.229512 -0.120804 0.0385075 0.228207 -0.121905 0.0424344 0.228347 -0.121018 0.0420145 0.228654 -0.121164 0.0420098 0.228824 -0.120491 0.0413304 0.228623 -0.119979 0.0403278 0.228982 -0.120113 0.0404053 0.229099 -0.120136 0.0393493 0.229185 -0.120631 0.038371 0.228767 -0.123789 0.0418549 0.2294 -0.123409 0.0410773 0.227766 -0.123524 0.0423573 0.22836 -0.122953 0.0424215 0.228771 -0.122149 0.0422775 0.22895 -0.12135 0.0419481 0.229141 -0.12071 0.0413291 0.229417 -0.120987 0.0412781 0.229459 -0.120348 0.0394607 0.229742 -0.132584 0.0231694 0.229886 -0.132157 0.0231781 0.229987 -0.131782 0.023382 0.23007 -0.131221 0.0228774 0.229377 -0.133277 0.0241594 0.229464 -0.133205 0.0236805 0.229213 -0.133009 0.0220071 0.229024 -0.133618 0.0224859 0.229402 -0.133355 0.0229459 0.229578 -0.132912 0.02261 0.229612 -0.131401 0.021874 0.22976 -0.130613 0.0223358 0.229968 -0.130913 0.0225919 0.230024 -0.130442 0.0232818 0.229691 -0.132718 0.0232109 0.229765 -0.132364 0.0224613 0.229822 -0.131591 0.0221895 0.22994 -0.13177 0.0225416 0.228276 -0.130818 0.0213829 0.228492 -0.131928 0.0212167 0.228169 -0.131818 0.0211835 0.228143 -0.132043 0.0211923 0.228753 -0.129403 0.0228678 0.228718 -0.130015 0.0219532 0.228347 -0.132896 0.0214386 0.227984 -0.133261 0.0216053 0.228207 -0.133704 0.0219969 0.227843 -0.134128 0.022521 0.228088 -0.134252 0.0228194 0.227749 -0.134475 0.0237443 0.22887 -0.134012 0.0231493 0.228767 -0.134144 0.023919 0.22836 -0.134217 0.0229121 0.228494 -0.133718 0.0221218 0.228772 -0.13369 0.0222867 0.228655 -0.132965 0.0215676 0.229141 -0.132149 0.0215151 0.229459 -0.130351 0.0221356 0.229099 -0.130148 0.0220075 0.229185 -0.129548 0.0229258 0.228623 -0.130917 0.0213825 0.228982 -0.131051 0.0214597 0.228824 -0.132041 0.0213253 0.228271 -0.134396 0.0238424 0.229158 -0.133747 0.0239844 0.229256 -0.133647 0.0234231 0.22895 -0.133004 0.0217592 0.229417 -0.132243 0.0217808 0.229322 -0.131216 0.0216246 0.229939 -0.122124 0.0403098 0.229694 -0.123026 0.0402608 0.229465 -0.123113 0.0411609 0.229446 -0.133233 0.0237498 0.229366 -0.133218 0.0243881 0.229579 -0.132986 0.0233773 0.230021 -0.131546 0.0237219 0.230021 -0.128989 0.0293374 0.229694 -0.132382 0.024055 0.229366 -0.131299 0.0287422 0.229366 -0.12907 0.0329464 0.230021 -0.127511 0.0320468 0.230021 -0.125904 0.0346811 0.228415 -0.134155 0.0247614 0.228415 -0.124524 0.041443 0.228994 -0.124205 0.0411915 0.229366 -0.123732 0.0408184 0.228994 -0.127042 0.0373169 0.229366 -0.126543 0.0369788 0.228994 -0.131841 0.029005 0.228994 -0.133778 0.0246111 0.228731 -0.133991 0.0246958 0.228415 -0.132206 0.0291821 0.228994 -0.129592 0.0332476 0.228731 -0.124385 0.0413332 0.228239 -0.134216 0.0247854 0.228415 -0.129943 0.0334506 0.228415 -0.127378 0.0375447 0.228239 -0.124575 0.0414832 0.224574 -0.11966 0.0403521 0.224774 -0.123958 0.0342813 0.224574 -0.127849 0.0279417 0.224574 -0.130778 0.0210945 0.224774 -0.130485 0.0213191 0.224774 -0.123476 0.043583 0.224774 -0.128299 0.0371452 0.224574 -0.132142 0.0300896 0.224774 -0.135637 0.0219053 0.224574 -0.122303 0.0441618 0.224574 -0.121583 0.0443012 0.224574 -0.120435 0.044058 0.224774 -0.119812 0.0438872 0.224574 -0.11954 0.0433001 0.224774 -0.130061 0.0215961 0.224774 -0.119706 0.0398901 0.224774 -0.120319 0.0381246 0.224774 -0.119708 0.0399852 0.224774 -0.125304 0.0307721 0.224774 -0.12767 0.0278522 0.224574 -0.135437 0.0219053 0.224574 -0.11913 0.0414757 0.222722 -0.120435 0.0440579 0.222705 -0.12028 0.0439748 0.224574 -0.119941 0.0437346 0.224574 -0.119233 0.0427137 0.222607 -0.11954 0.0433001 0.224574 -0.119111 0.0422086 0.222499 -0.119103 0.0421394 0.2229 -0.123323 0.0434538 0.222823 -0.121583 0.0443012 0.224574 -0.121064 0.0442646 0.222808 -0.121376 0.0443001 0.222752 -0.120734 0.0441801 0.224574 -0.123323 0.0434538 0.224574 -0.128132 0.0370351 0.224574 -0.135296 0.0227161 0.222427 -0.130778 0.0210945 0.224574 -0.124125 0.0343915 0.222427 -0.124125 0.0343915 0.222842 -0.135272 0.0210307 0.222585 -0.133049 0.0195053 0.222665 -0.133848 0.0196463 0.222364 -0.133941 0.019711 0.222743 -0.134556 0.0200467 0.22247 -0.134685 0.0201928 0.222777 -0.134827 0.0203058 0.221231 -0.134247 0.0220288 0.220979 -0.133537 0.0207672 0.220834 -0.133039 0.0208456 0.220726 -0.132582 0.0211423 0.221162 -0.132648 0.0201904 0.221036 -0.131956 0.0206217 0.221284 -0.134051 0.0205675 0.221132 -0.133997 0.0208828 0.220952 -0.132848 0.0204995 0.220827 -0.132265 0.0208674 0.220692 -0.132211 0.0216085 0.221498 -0.134073 0.0202762 0.221057 -0.133916 0.0215326 0.221392 -0.134617 0.021544 0.22116 -0.134142 0.0217401 0.22147 -0.134712 0.0220053 0.222506 -0.132127 0.0196845 0.222151 -0.132147 0.0197151 0.222056 -0.134014 0.0198377 0.221921 -0.133175 0.0196413 0.221792 -0.132283 0.0197878 0.221696 -0.13148 0.0203091 0.221619 -0.130965 0.0211613 0.22256 -0.135202 0.0209185 0.222288 -0.135171 0.0210126 0.222183 -0.134704 0.0203174 0.222253 -0.133059 0.0195365 0.222078 -0.131345 0.0202594 0.221498 -0.134635 0.0224786 0.221627 -0.134779 0.0225306 0.221778 -0.134973 0.0212573 0.221565 -0.134812 0.0213985 0.222358 -0.135356 0.0218404 0.221861 -0.135107 0.021926 0.222207 -0.135162 0.0226677 0.221905 -0.134681 0.0204835 0.221653 -0.134616 0.0206854 0.221761 -0.13406 0.0200282 0.221603 -0.13329 0.0198276 0.221327 -0.133393 0.0200903 0.221452 -0.132454 0.0199471 0.221336 -0.131687 0.0204304 0.222878 -0.122503 0.0440793 0.221497 -0.120598 0.0436139 0.22189 -0.123079 0.0432467 0.220782 -0.121452 0.0418697 0.220692 -0.120821 0.0413353 0.220726 -0.120603 0.0418902 0.220855 -0.121299 0.042357 0.220879 -0.121313 0.0424438 0.221392 -0.121969 0.0434519 0.221099 -0.121716 0.042902 0.221275 -0.121507 0.0434313 0.221132 -0.121085 0.0432445 0.22102 -0.121524 0.0427901 0.220979 -0.120756 0.0429039 0.220952 -0.12018 0.0424422 0.220827 -0.120207 0.041753 0.220982 -0.121451 0.0427173 0.220834 -0.120575 0.0424341 0.222446 -0.119198 0.0411982 0.222151 -0.11915 0.0422269 0.222591 -0.119452 0.0431673 0.222253 -0.119451 0.0431051 0.222364 -0.120042 0.0437818 0.222427 -0.11966 0.0403521 0.222078 -0.11922 0.0412609 0.222437 -0.119289 0.0409492 0.222664 -0.11994 0.0437335 0.22247 -0.120832 0.0441859 0.222828 -0.121652 0.0442976 0.222358 -0.122595 0.0439432 0.221627 -0.122904 0.043099 0.221905 -0.121082 0.0440373 0.222183 -0.120949 0.0441398 0.221761 -0.120377 0.0437266 0.221603 -0.119818 0.0431598 0.221452 -0.119504 0.0423768 0.221696 -0.119331 0.0413524 0.221336 -0.119539 0.041471 0.221291 -0.119979 0.0406223 0.221792 -0.119281 0.0423088 0.22192 -0.1196 0.0431537 0.222056 -0.120189 0.0437821 0.22256 -0.12172 0.0442709 0.222288 -0.121786 0.0441969 0.222207 -0.123214 0.0433613 0.221861 -0.122545 0.0436849 0.22147 -0.122416 0.0433032 0.221778 -0.121899 0.0439033 0.221653 -0.121224 0.0438796 0.221327 -0.120098 0.0431181 0.221162 -0.119812 0.0424229 0.221036 -0.119839 0.0416087 0.220993 -0.12023 0.0408343 0.221255 -0.131234 0.0293281 0.221255 -0.131112 0.0295743 0.221627 -0.127673 0.0367327 0.222207 -0.132014 0.0300255 0.22189 -0.134995 0.0226078 0.2229 -0.135296 0.0227161 0.2229 -0.132142 0.0300896 0.222383 -0.135223 0.0226897 0.2229 -0.128132 0.0370351 0.221255 -0.127019 0.0366294 0.222207 -0.128012 0.0369562 0.221627 -0.131651 0.0298439 0.222383 -0.123264 0.0434033 0.22205 -0.119691 0.0403786 0.220692 -0.12921 0.0286226 0.220782 -0.132989 0.0218879 0.220782 -0.130069 0.0287512 0.220684 -0.132273 0.0216311 0.220782 -0.126085 0.0356849 0.220993 -0.124748 0.0348025 0.220692 -0.125395 0.0352295 0.220779 -0.120545 0.0411015 0.222427 -0.127849 0.0279417 0.220779 -0.13187 0.0214863 0.220993 -0.131481 0.0213466 0.220993 -0.128516 0.0282756 0.221291 -0.131172 0.0212358 0.221619 -0.119811 0.0404798 0.221619 -0.12429 0.0345004 0.221619 -0.128026 0.0280302 0.22205 -0.130817 0.0211084 0.22094 -0.133603 0.0214526 0.220854 -0.133333 0.0215118 0.220796 -0.133097 0.0216952 0.22102 -0.133822 0.02149 0.221255 -0.122445 0.0427097 0.221184 -0.12199 0.0429414 0.221242 -0.122275 0.0428523 0.220807 -0.121316 0.0421366 0.221019 -0.121949 0.0422897 0.220782 -0.125937 0.035909 0.221255 -0.127171 0.0364009 0.220782 -0.129949 0.0289926 0.221255 -0.134212 0.0223271 0.221019 -0.133601 0.0221075 0.224774 -0.134064 0.022068 0.224774 -0.134647 0.0234232 0.224974 -0.134449 0.023452 0.224974 -0.131445 0.0212111 0.224974 -0.132176 0.0212067 0.224974 -0.132807 0.0213717 0.224774 -0.120048 0.0412432 0.224774 -0.122309 0.0427294 0.224774 -0.132284 0.0194168 0.224774 -0.131416 0.0210132 0.224774 -0.13059 0.0210269 0.224774 -0.133483 0.0193438 0.224774 -0.132881 0.0211859 0.224774 -0.12237 0.0443501 0.224774 -0.121029 0.0444614 0.224774 -0.120991 0.0422718 0.224774 -0.119045 0.0427813 0.224774 -0.118933 0.04144 0.224774 -0.119507 0.0402228 0.224774 -0.135485 0.0227837 0.224774 -0.134474 0.0248884 0.224774 -0.13232 0.0301791 0.224774 -0.124793 0.0416555 0.224774 -0.123687 0.0425061 0.224774 -0.129179 0.0227786 0.224974 -0.129365 0.0228526 0.224974 -0.120476 0.0382485 0.224974 -0.125477 0.0308721 0.228377 -0.125477 0.0308721 0.224774 -0.13024 0.0336221 0.224974 -0.120678 0.04176 0.228025 -0.121058 0.0420763 0.224974 -0.121101 0.0421047 0.22794 -0.121687 0.0423935 0.224974 -0.121687 0.0423936 0.227875 -0.122253 0.0425227 0.224974 -0.122327 0.0425301 0.224974 -0.122872 0.0425212 0.227816 -0.122871 0.0425213 0.224974 -0.123608 0.0423225 0.228047 -0.120914 0.0419699 0.228086 -0.120678 0.0417601 0.228179 -0.120215 0.0411327 0.224974 -0.120224 0.0411482 0.228276 -0.11993 0.0402418 0.224974 -0.120049 0.0407483 0.228305 -0.119906 0.0398901 0.228363 -0.129751 0.0221861 0.224974 -0.130185 0.0217532 0.22835 -0.129949 0.0219629 0.224974 -0.133379 0.021686 0.228047 -0.132805 0.0213709 0.224974 -0.130889 0.0213546 0.224974 -0.134288 0.0248143 0.227721 -0.134288 0.0248143 0.22782 -0.134243 0.022747 0.224974 -0.134211 0.0226781 0.227827 -0.134211 0.0226779 0.224974 -0.133907 0.0221919 0.227925 -0.133653 0.0219132 0.224574 -0.130778 -0.0211002 0.224574 -0.131229 -0.0203329 0.224574 -0.132236 -0.0196488 0.222518 -0.132287 -0.0196313 0.224574 -0.132342 -0.0196139 0.224574 -0.133449 -0.0195466 0.222576 -0.132947 -0.0195127 0.222664 -0.133847 -0.0196516 0.222738 -0.134511 -0.0200166 0.224574 -0.135181 -0.0208323 0.222833 -0.135218 -0.0209076 0.224574 -0.132142 -0.0300953 0.224574 -0.128132 -0.0370408 0.2229 -0.128132 -0.0370408 0.222427 -0.127849 -0.0279474 0.221231 -0.122203 -0.0428942 0.221255 -0.122445 -0.0427155 0.22116 -0.121901 -0.0429475 0.220854 -0.121299 -0.0423613 0.220827 -0.120207 -0.0417584 0.220692 -0.120821 -0.041341 0.221036 -0.119839 -0.0416141 0.220952 -0.12018 -0.0424478 0.220779 -0.120545 -0.0411072 0.221284 -0.12084 -0.0434553 0.22094 -0.121383 -0.042625 0.22102 -0.121524 -0.042796 0.221327 -0.120098 -0.0431244 0.220979 -0.120756 -0.04291 0.220834 -0.120575 -0.0424397 0.220726 -0.120603 -0.0418957 0.221057 -0.121608 -0.042856 0.221565 -0.12194 -0.0436985 0.222881 -0.122565 -0.0440553 0.222383 -0.123264 -0.043409 0.2229 -0.123323 -0.0434595 0.222607 -0.11954 -0.0433059 0.222253 -0.119451 -0.0431115 0.22252 -0.119146 -0.0424175 0.222449 -0.119178 -0.0412693 0.222828 -0.121651 -0.0443033 0.22247 -0.120833 -0.0441918 0.222722 -0.120435 -0.0440637 0.222056 -0.12019 -0.0437884 0.221603 -0.119819 -0.0431661 0.221336 -0.119539 -0.0414763 0.221696 -0.119331 -0.0413578 0.222183 -0.12095 -0.0441457 0.222364 -0.120043 -0.0437882 0.221921 -0.1196 -0.04316 0.222151 -0.11915 -0.0422324 0.221792 -0.119281 -0.0423144 0.222078 -0.11922 -0.0412662 0.22205 -0.119691 -0.0403843 0.221619 -0.119811 -0.0404856 0.22147 -0.122416 -0.043309 0.221627 -0.122904 -0.0431047 0.221132 -0.121086 -0.0432506 0.221392 -0.121969 -0.0434577 0.221861 -0.122545 -0.0436908 0.222207 -0.123214 -0.043367 0.22256 -0.121719 -0.0442767 0.222358 -0.122595 -0.0439491 0.222288 -0.121785 -0.0442027 0.221905 -0.121082 -0.0440432 0.221778 -0.121898 -0.0439091 0.221761 -0.120377 -0.0437329 0.221653 -0.121224 -0.0438854 0.221498 -0.120599 -0.0436201 0.221452 -0.119504 -0.0423824 0.221162 -0.119812 -0.0424285 0.221291 -0.119979 -0.040628 0.222383 -0.135223 -0.0226954 0.221327 -0.133393 -0.020096 0.221627 -0.134779 -0.0225363 0.220782 -0.132989 -0.0218936 0.220855 -0.133334 -0.0215169 0.220834 -0.133039 -0.0208514 0.221392 -0.134617 -0.0215499 0.221132 -0.133996 -0.0208883 0.221497 -0.134072 -0.0202815 0.221275 -0.134369 -0.0211602 0.221653 -0.134615 -0.0206908 0.221099 -0.134015 -0.021606 0.220979 -0.133536 -0.020773 0.220952 -0.132848 -0.0205053 0.221162 -0.132648 -0.0201961 0.221036 -0.131956 -0.0206272 0.220827 -0.132265 -0.020873 0.220779 -0.13187 -0.021492 0.220982 -0.133722 -0.0214689 0.220726 -0.132582 -0.0211479 0.222253 -0.133058 -0.0195422 0.222626 -0.13347 -0.0195503 0.222078 -0.131346 -0.0202648 0.222499 -0.132048 -0.0197244 0.222427 -0.130778 -0.0211002 0.222447 -0.131305 -0.0202497 0.222881 -0.135433 -0.0217675 0.222358 -0.135356 -0.0218465 0.22256 -0.135202 -0.0209244 0.22247 -0.134685 -0.0201981 0.222364 -0.13394 -0.0197162 0.222886 -0.135437 -0.021911 0.221778 -0.134973 -0.0212632 0.221761 -0.134059 -0.0200335 0.222056 -0.134013 -0.019843 0.221603 -0.133289 -0.0198333 0.22192 -0.133175 -0.019647 0.221452 -0.132454 -0.0199528 0.221336 -0.131687 -0.0204359 0.222151 -0.132147 -0.0197207 0.221696 -0.13148 -0.0203146 0.221792 -0.132283 -0.0197934 0.222183 -0.134703 -0.0203227 0.222288 -0.135171 -0.0210185 0.221861 -0.135107 -0.021932 0.221242 -0.134251 -0.022115 0.22147 -0.134712 -0.0220113 0.221905 -0.134681 -0.0204888 0.221627 -0.127673 -0.0367384 0.221498 -0.122787 -0.0430053 0.221255 -0.127171 -0.0364066 0.221627 -0.131651 -0.0298496 0.22189 -0.134995 -0.0226135 0.222207 -0.135162 -0.0226735 0.22189 -0.123079 -0.0432525 0.222207 -0.128012 -0.036962 0.222207 -0.132014 -0.0300312 0.2229 -0.132142 -0.0300953 0.22205 -0.130817 -0.0211141 0.221619 -0.128026 -0.0280359 0.220782 -0.126085 -0.0356906 0.220692 -0.132211 -0.0216143 0.220782 -0.130069 -0.0287577 0.220684 -0.120872 -0.0413842 0.220692 -0.125395 -0.0352352 0.221291 -0.131172 -0.0212415 0.220993 -0.131481 -0.0213523 0.220692 -0.12921 -0.0286283 0.222427 -0.124125 -0.0343972 0.220993 -0.12023 -0.04084 0.220993 -0.124748 -0.0348082 0.221619 -0.130965 -0.021167 0.220993 -0.128516 -0.0282813 0.221619 -0.12429 -0.0345061 0.220782 -0.125936 -0.0359154 0.221019 -0.121949 -0.0422954 0.220796 -0.12134 -0.0420657 0.220782 -0.121452 -0.0418754 0.221184 -0.134186 -0.0218237 0.221255 -0.134212 -0.0223328 0.220807 -0.133152 -0.021642 0.221019 -0.133601 -0.0221132 0.220879 -0.133416 -0.0214859 0.22102 -0.133822 -0.0214956 0.221255 -0.131234 -0.0293346 0.220782 -0.129949 -0.0289983 0.221255 -0.131112 -0.02958 0.221255 -0.127019 -0.0366359 0.221231 -0.122203 -0.0428942 0.2229 -0.135296 -0.0227218 0.222896 -0.135402 -0.0223221 0.224574 -0.135437 -0.021911 0.224774 -0.135637 -0.021911 0.224774 -0.135485 -0.0227894 0.228086 -0.120678 -0.0417657 0.228225 -0.120049 -0.0407545 0.228276 -0.11993 -0.0402476 0.224974 -0.119906 -0.0398958 0.224974 -0.120224 -0.041154 0.228133 -0.120424 -0.0414696 0.227975 -0.121415 -0.0422874 0.224974 -0.121101 -0.0421104 0.22794 -0.121687 -0.0423992 0.224974 -0.122872 -0.0425269 0.224974 -0.123608 -0.0423282 0.227749 -0.123803 -0.042234 0.224974 -0.124636 -0.0415374 0.224774 -0.123687 -0.0425118 0.224974 -0.122327 -0.0425358 0.224974 -0.121687 -0.0423993 0.224774 -0.120991 -0.0422776 0.224774 -0.120048 -0.0412489 0.224974 -0.120678 -0.0417657 0.224774 -0.119708 -0.0399909 0.224774 -0.119864 -0.0389614 0.224774 -0.119706 -0.0398958 0.224774 -0.130061 -0.0216019 0.224774 -0.131416 -0.0210189 0.224974 -0.131445 -0.0212168 0.224774 -0.134064 -0.0220738 0.224774 -0.134647 -0.023429 0.224974 -0.134211 -0.0226839 0.224974 -0.133907 -0.0221976 0.224774 -0.13059 -0.0210327 0.224774 -0.13536 -0.0207424 0.224774 -0.133483 -0.0193495 0.224774 -0.132881 -0.0211916 0.224774 -0.132284 -0.0194225 0.224774 -0.118941 -0.0424125 0.224774 -0.118975 -0.0412559 0.224774 -0.121415 -0.0445075 0.224774 -0.12255 -0.0442833 0.224774 -0.122309 -0.0427351 0.224774 -0.124793 -0.0416612 0.224774 -0.128299 -0.0371509 0.224774 -0.134474 -0.0248941 0.224774 -0.125304 -0.0307779 0.228377 -0.129365 -0.0228584 0.224974 -0.129365 -0.0228584 0.224974 -0.125477 -0.0308779 0.224974 -0.130067 -0.0335279 0.224974 -0.134288 -0.02482 0.224774 -0.13024 -0.0336279 0.227748 -0.134475 -0.0237717 0.224974 -0.134449 -0.0234577 0.22782 -0.134243 -0.0227525 0.224974 -0.132176 -0.0212124 0.224974 -0.132807 -0.0213774 0.228047 -0.132806 -0.0213771 0.224974 -0.133379 -0.0216917 0.224974 -0.130185 -0.0217589 0.224974 -0.130889 -0.0213604 0.22811 -0.132316 -0.0212349 0.224974 -0.120476 -0.0382542 0.228358 -0.12005 -0.0390334 0.224974 -0.120053 -0.039027 0.22835 -0.119998 -0.0392056 0.230021 -0.122319 -0.0397091 0.230024 -0.121386 -0.0389724 0.229512 -0.129753 -0.0230131 0.229185 -0.129548 -0.0229315 0.228753 -0.129403 -0.0228735 0.228377 -0.126901 -0.0282681 0.228377 -0.125477 -0.0308779 0.229185 -0.124095 -0.033523 0.228377 -0.123929 -0.033416 0.22981 -0.127565 -0.0286097 0.228377 -0.120476 -0.0382542 0.230112 -0.128254 -0.0289646 0.230024 -0.130442 -0.0232875 0.229185 -0.127077 -0.0283587 0.22981 -0.124557 -0.0338198 0.230112 -0.130778 -0.0234215 0.230021 -0.128989 -0.0293432 0.230021 -0.127511 -0.0320518 0.230112 -0.125209 -0.0342393 0.227721 -0.127496 -0.0376307 0.227721 -0.132335 -0.0292502 0.229804 -0.13241 -0.0231537 0.229578 -0.132913 -0.022616 0.229158 -0.133747 -0.0239899 0.229256 -0.133646 -0.0234286 0.229498 -0.133149 -0.0235785 0.229465 -0.133205 -0.0236861 0.23001 -0.131661 -0.0235222 0.23007 -0.13122 -0.0228833 0.22992 -0.132042 -0.0232228 0.22895 -0.133005 -0.0217655 0.227735 -0.134467 -0.0240689 0.22836 -0.134217 -0.0229176 0.228088 -0.134252 -0.0228249 0.22964 -0.132844 -0.0232789 0.229402 -0.133356 -0.0229519 0.229024 -0.133618 -0.0224921 0.228771 -0.13369 -0.0222929 0.22887 -0.134011 -0.0231548 0.228494 -0.133718 -0.022128 0.228207 -0.133704 -0.0220031 0.229968 -0.130913 -0.0225978 0.22981 -0.130058 -0.0231346 0.229459 -0.13035 -0.0221416 0.228169 -0.131819 -0.0211892 0.228252 -0.131057 -0.0213034 0.228623 -0.130917 -0.0213883 0.228982 -0.131051 -0.0214654 0.229322 -0.131216 -0.0216303 0.229141 -0.13215 -0.0215209 0.229417 -0.132244 -0.0217866 0.229612 -0.131401 -0.0218797 0.22976 -0.130613 -0.0223418 0.229099 -0.130148 -0.0220135 0.228718 -0.130015 -0.0219593 0.228349 -0.129965 -0.0219535 0.228269 -0.13089 -0.0213603 0.227721 -0.134288 -0.02482 0.228271 -0.134396 -0.0238477 0.228767 -0.134144 -0.0239244 0.228415 -0.134155 -0.0247671 0.228731 -0.133991 -0.0247015 0.228994 -0.133778 -0.0246168 0.229366 -0.133218 -0.0243939 0.227951 -0.133485 -0.0217725 0.228347 -0.132897 -0.0214449 0.228492 -0.131928 -0.0212225 0.228654 -0.132966 -0.0215738 0.228824 -0.132041 -0.0213311 0.229213 -0.13301 -0.0220133 0.229765 -0.132364 -0.0224671 0.229822 -0.131591 -0.0221952 0.22994 -0.13177 -0.0225473 0.227721 -0.124636 -0.0415374 0.229213 -0.121566 -0.0418331 0.22994 -0.121409 -0.0404927 0.229987 -0.122143 -0.0400834 0.230112 -0.12167 -0.0391968 0.229464 -0.123113 -0.0411666 0.229579 -0.122741 -0.0411279 0.229578 -0.122039 -0.0414481 0.229402 -0.122552 -0.0416638 0.229256 -0.123111 -0.0416773 0.229691 -0.122463 -0.0409792 0.229417 -0.120987 -0.0412832 0.229765 -0.121636 -0.0410472 0.229742 -0.12236 -0.0408837 0.229822 -0.121015 -0.0405142 0.23007 -0.121425 -0.0398493 0.229968 -0.121024 -0.0397258 0.228623 -0.119979 -0.0403336 0.228492 -0.120341 -0.0412918 0.22816 -0.120298 -0.0412834 0.228305 -0.119906 -0.0398958 0.228289 -0.119914 -0.0401007 0.228753 -0.120508 -0.0382796 0.228718 -0.120022 -0.0392676 0.228207 -0.121904 -0.0424399 0.228347 -0.121017 -0.0420195 0.228047 -0.120913 -0.0419748 0.227834 -0.122671 -0.0425433 0.22782 -0.122824 -0.0425323 0.228239 -0.124575 -0.0414889 0.228767 -0.123789 -0.0418605 0.22887 -0.123056 -0.0421303 0.228772 -0.122148 -0.0422831 0.229141 -0.12071 -0.0413342 0.229459 -0.120348 -0.0394668 0.229512 -0.120804 -0.0385132 0.229185 -0.120631 -0.0383767 0.229099 -0.120136 -0.0393554 0.228982 -0.120113 -0.0404112 0.228824 -0.120491 -0.0413354 0.228655 -0.121163 -0.0420148 0.228494 -0.12202 -0.0423898 0.228088 -0.122891 -0.0425033 0.22836 -0.122954 -0.0424272 0.228271 -0.123849 -0.0421165 0.228415 -0.124524 -0.0414487 0.228731 -0.124385 -0.0413389 0.229158 -0.123647 -0.0414837 0.229024 -0.122285 -0.0421208 0.22895 -0.121349 -0.0419531 0.229322 -0.120338 -0.0404717 0.229612 -0.120647 -0.0405074 0.22976 -0.120653 -0.0395942 0.22981 -0.121062 -0.0387165 0.229939 -0.131974 -0.0232548 0.230021 -0.131546 -0.0237276 0.229694 -0.132382 -0.0240607 0.2294 -0.133281 -0.0239838 0.229691 -0.132718 -0.0232168 0.229377 -0.123564 -0.040989 0.229366 -0.123732 -0.0408241 0.229446 -0.123187 -0.0411557 0.229694 -0.123026 -0.0402666 0.229886 -0.122154 -0.0405095 0.230021 -0.125904 -0.0346868 0.229366 -0.126543 -0.0369845 0.229366 -0.12907 -0.0329521 0.228415 -0.132206 -0.0291878 0.228994 -0.131841 -0.0290107 0.229366 -0.131299 -0.0287479 0.228994 -0.127042 -0.0373226 0.228994 -0.124205 -0.0411972 0.228994 -0.129592 -0.0332533 0.228415 -0.127378 -0.0375504 0.228415 -0.129943 -0.0334563 0.227721 -0.130067 -0.0335279 0.228239 -0.134216 -0.0247911 0.224774 -0.130485 -0.0213248 0.224574 -0.127849 -0.0279474 0.224574 -0.124125 -0.0343972 0.224574 -0.11966 -0.0403578 0.224574 -0.135296 -0.0227218 0.224774 -0.13232 -0.0301848 0.224774 -0.123476 -0.0435888 0.224774 -0.119507 -0.0402285 0.224574 -0.119111 -0.0422143 0.224774 -0.119412 -0.0434693 0.224774 -0.120295 -0.044217 0.224574 -0.134556 -0.0200525 0.224574 -0.134468 -0.0199838 0.224774 -0.134587 -0.0198232 0.224774 -0.131246 -0.0200265 0.224574 -0.131384 -0.0201714 0.224774 -0.129179 -0.0227843 0.224774 -0.12767 -0.0278579 0.224774 -0.123958 -0.034287 0.224774 -0.120319 -0.0381303 0.224574 -0.119169 -0.0413061 0.222427 -0.11966 -0.0403578 0.22289 -0.122795 -0.0439244 0.224574 -0.123323 -0.0434595 0.224574 -0.122469 -0.0441006 0.224574 -0.121583 -0.0443069 0.222737 -0.120581 -0.044129 0.224574 -0.121421 -0.0443076 0.224574 -0.120387 -0.0440394 0.222664 -0.119941 -0.04374 0.224574 -0.119572 -0.0433492 0.224574 -0.119137 -0.0423737 0.222576 -0.11937 -0.0430303 0.222623 -0.119648 -0.0434446 0.222504 -0.119111 -0.0422145 -0.15519 0.0382 0.088935 -0.15519 0.0382 0.085235 -0.145831 0.0355206 0.085235 -0.144908 0.0337086 0.085235 -0.146493 0.0362962 0.0894865 -0.145831 0.0355206 0.0894865 -0.145298 0.0346509 0.0894865 -0.148684 0.0377386 0.0890793 -0.148403 0.0376189 0.0893576 -0.148324 0.0375823 0.0894602 -0.148276 0.0375595 0.089495 -0.147269 0.0369586 0.0894865 -0.149127 0.0378965 0.088935 -0.149081 0.0378818 0.085235 -0.150097 0.0381237 0.088935 -0.15109 0.0382 0.085235 -0.158003 0.0375595 0.089495 -0.158011 0.0375555 0.0894915 -0.157198 0.0378818 0.085235 -0.157376 0.0378213 0.0889702 -0.157152 0.0378965 0.088935 -0.158018 0.0375522 0.0894865 -0.159786 0.0362962 0.0894865 -0.15901 0.0369586 0.085235 -0.16169 -0.0317 0.0894865 -0.16169 -0.0251369 0.0885481 -0.16169 0.0251368 0.0885481 -0.16169 -0.0265314 0.0872415 -0.16169 0.0258488 0.0879424 -0.16169 0.0234117 0.0891428 -0.16169 0.0221094 0.0892215 -0.16169 0.0213873 0.0892273 -0.16169 0.0317 0.0894865 -0.16169 -0.0317 0.085235 -0.161371 -0.0337087 0.085235 -0.160448 -0.0355206 0.085235 -0.159786 -0.0362962 0.0894865 -0.157376 -0.0378214 0.0889702 -0.157876 -0.037619 0.0893576 -0.157915 -0.0376009 0.089409 -0.157955 -0.0375824 0.0894602 -0.15797 -0.0375753 0.0894774 -0.158003 -0.0375596 0.089495 -0.15901 -0.0369587 0.085235 -0.157198 -0.0378819 0.085235 -0.156183 -0.0381237 0.088935 -0.15109 -0.0382 0.085235 -0.148403 -0.037619 0.0893576 -0.148268 -0.0375556 0.0894915 -0.146493 -0.0362962 0.0894865 -0.147269 -0.0369587 0.085235 -0.145831 -0.0355206 0.085235 -0.144908 -0.0337087 0.085235 -0.14459 -0.0317 0.085235 -0.14459 -0.027071 0.085235 -0.14459 -0.0267138 0.0865955 -0.14459 0.0258488 0.0879424 -0.14459 -0.0246213 0.0888371 -0.14459 0.0317 0.0894865 -0.14459 0.0267137 0.0865955 -0.14459 -0.0317 0.0894865 -0.14459 0.0242159 0.0889816 -0.14459 0.0246212 0.0888371 -0.14459 0.0251368 0.0885481 -0.14459 -0.0221095 0.0892215 -0.14459 -0.0213874 0.0892273 -0.159894 -0.0323693 0.091235 -0.15774 -0.0319 0.091235 -0.159202 -0.0342453 0.091235 -0.156392 -0.0286474 0.091235 -0.158333 -0.0352633 0.091235 -0.149315 -0.0293444 0.091235 -0.148628 -0.0310026 0.091235 -0.146338 -0.0317 0.091235 -0.146385 -0.0323693 0.091235 -0.146759 -0.0336547 0.091235 -0.150584 0.0280752 0.091235 -0.159941 -0.0317 0.091235 -0.14854 0.0319 0.091235 -0.146338 0.0317 0.091235 -0.14889 0.0301396 0.091235 -0.149315 0.0293443 0.091235 -0.155695 0.0280752 0.091235 -0.1549 0.0276501 0.091235 -0.146385 0.0323692 0.091235 -0.146527 0.0330252 0.091235 -0.146759 0.0336547 0.091235 -0.147077 0.0342452 0.091235 -0.14854 0.0357092 0.091235 -0.155695 -0.0280753 0.091235 -0.152242 -0.0273884 0.091235 -0.151379 0.0276501 0.091235 -0.152242 0.0273883 0.091235 -0.159941 0.0317 0.091235 -0.159894 0.0323692 0.091235 -0.15774 0.0357092 0.091235 -0.158803 0.034785 0.091235 -0.15949 0.0215524 0.085235 -0.15968 0.0230433 0.085235 -0.16024 0.0244361 0.085235 -0.161371 0.0337086 0.085235 -0.160448 0.0355206 0.085235 -0.16169 0.0317 0.085235 -0.16169 0.027071 0.085235 -0.161679 0.0268617 0.085235 -0.161446 0.0260835 0.085235 -0.161501 0.0261962 0.085235 -0.15968 -0.0230434 0.085235 -0.15739 0.00229996 0.085235 -0.15949 0.00804996 0.085235 -0.15729 -0.0142 0.085235 -0.161313 -0.0258651 0.085235 -0.161226 -0.0257493 0.085235 -0.154265 -0.0299515 0.085235 -0.156993 -0.0246925 0.085235 -0.15539 -0.0319 0.085235 -0.151191 -0.030775 0.085235 -0.15089 -0.0319 0.085235 -0.154882 -0.0268032 0.085235 -0.15314 -0.02965 0.085235 -0.151191 -0.033025 0.085235 -0.152015 -0.0338486 0.085235 -0.149081 -0.0378819 0.085235 -0.15519 -0.0382 0.085235 -0.146599 -0.0230434 0.085235 -0.146039 -0.0244362 0.085235 -0.145163 -0.0256242 0.085235 -0.152015 -0.0299515 0.085235 -0.15339 -0.0271 0.085235 -0.156993 -0.0127076 0.085235 -0.144615 -0.0267453 0.085235 -0.144833 -0.0260836 0.085235 -0.14899 -0.0142 0.085235 -0.149186 0.00379242 0.085235 -0.150032 0.00505767 0.085235 -0.154982 0.00590309 0.085235 -0.157215 0.00804996 0.085235 -0.156247 0.00505767 0.085235 -0.157093 0.00379242 0.085235 -0.149186 -0.00419251 0.085235 -0.157093 -0.00419251 0.085235 -0.154982 -0.00630317 0.085235 -0.154882 -0.0105969 0.085235 -0.15279 -0.00660004 0.085235 -0.151397 -0.0105969 0.085235 -0.15279 0.00619996 0.085235 -0.147269 0.0369586 0.085235 -0.152015 0.0338485 0.085235 -0.154265 0.0338485 0.085235 -0.15314 0.03415 0.085235 -0.151191 0.033025 0.085235 -0.14459 0.0317 0.085235 -0.151191 0.030775 0.085235 -0.154265 0.0299514 0.085235 -0.155997 0.0259577 0.085235 -0.156843 0.0246924 0.085235 -0.15539 0.0319 0.085235 -0.155088 0.033025 0.085235 -0.15714 0.0232 0.085235 -0.155997 0.0110422 0.085235 -0.146039 0.0244361 0.085235 -0.15324 0.00989996 0.085235 -0.15304 0.00989996 0.085235 -0.149436 0.0123075 0.085235 -0.14914 0.0232 0.085235 -0.154732 0.0268031 0.085235 -0.15314 0.02965 0.085235 -0.15304 0.0271 0.085235 -0.152015 0.0299514 0.085235 -0.151547 0.0268031 0.085235 -0.14459 0.027071 0.085235 -0.144708 0.0263706 0.085235 -0.144966 0.025865 0.085235 -0.149436 0.0246924 0.085235 -0.145053 0.0257492 0.085235 -0.14889 -0.00270004 0.085235 -0.150032 -0.00545776 0.085235 -0.151297 -0.00630317 0.085235 -0.15279 -0.00660004 0.075433 -0.15349 -0.00660004 0.075433 -0.15349 -0.00660004 0.085235 -0.156247 -0.00545776 0.085235 -0.156247 -0.00545776 0.075433 -0.157093 -0.00419251 0.075433 -0.15739 -0.00270004 0.085235 -0.15739 -0.00270004 0.075433 -0.15739 0.00229996 0.075433 -0.154982 0.00590309 0.075433 -0.15349 0.00619996 0.085235 -0.15279 0.00619996 0.075433 -0.151297 0.00590309 0.085235 -0.150032 0.00505767 0.075433 -0.14889 0.00229996 0.075433 -0.14889 0.00229996 0.085235 -0.15659 -0.00270004 0.073235 -0.15349 0.00539996 0.073235 -0.151603 0.00516398 0.073235 -0.15279 -0.00580004 0.073235 -0.14969 0.00229996 0.073235 -0.154676 0.00516398 0.073235 -0.151603 -0.00556407 0.073235 -0.14969 -0.00270004 0.073235 -0.149286 -0.0246925 0.085235 -0.149286 -0.0246925 0.075433 -0.150132 -0.0259578 0.075433 -0.150132 -0.0259578 0.085235 -0.151397 -0.0268032 0.085235 -0.15289 -0.0271 0.085235 -0.156147 -0.0259578 0.085235 -0.156147 -0.0259578 0.075433 -0.156993 -0.0246925 0.075433 -0.15729 -0.0232 0.085235 -0.156147 -0.0114423 0.085235 -0.156147 -0.0114423 0.075433 -0.15339 -0.0103 0.085235 -0.15289 -0.0103 0.085235 -0.151397 -0.0105969 0.075433 -0.150132 -0.0114423 0.075433 -0.150132 -0.0114423 0.085235 -0.149286 -0.0127076 0.085235 -0.14899 -0.0142 0.075433 -0.14899 -0.0232 0.085235 -0.15649 -0.0142 0.073235 -0.150698 -0.012008 0.073235 -0.15289 -0.0111 0.073235 -0.154576 -0.0260641 0.073235 -0.150698 -0.0253921 0.073235 -0.15339 -0.0263 0.073235 -0.15289 -0.0263 0.073235 -0.15649 -0.0232 0.073235 -0.154576 -0.011336 0.073235 -0.15339 -0.0111 0.073235 -0.150282 0.0110422 0.085235 -0.149436 0.0123075 0.075433 -0.151547 0.0101968 0.075433 -0.151547 0.0101968 0.085235 -0.15304 0.00989996 0.075433 -0.15324 0.00989996 0.075433 -0.154732 0.0101968 0.085235 -0.155997 0.0110422 0.075433 -0.156843 0.0123075 0.085235 -0.156843 0.0123075 0.075433 -0.15714 0.0138 0.085235 -0.15714 0.0232 0.075433 -0.156843 0.0246924 0.075433 -0.154732 0.0268031 0.075433 -0.15324 0.0271 0.085235 -0.15304 0.0271 0.075433 -0.151547 0.0268031 0.075433 -0.150282 0.0259577 0.085235 -0.150282 0.0259577 0.075433 -0.14914 0.0138 0.075433 -0.14914 0.0138 0.085235 -0.151853 0.026064 0.073235 -0.150848 0.025392 0.073235 -0.156104 0.0126136 0.073235 -0.14994 0.0138 0.073235 -0.151853 0.0109359 0.073235 -0.15304 0.0107 0.073235 -0.154426 0.026064 0.073235 -0.15324 0.0263 0.073235 -0.156104 0.0243863 0.073235 -0.144765 -0.0317 0.0899108 -0.145914 0.0317 0.0910593 -0.146618 0.0361719 0.0899108 -0.147666 0.0355814 0.0910593 -0.145965 0.032429 0.0910593 -0.146119 0.0331435 0.0910593 -0.145075 0.0336543 0.0899108 -0.146372 0.0338292 0.0910593 -0.146719 0.0344725 0.0910593 -0.145973 0.0354173 0.0899108 -0.146618 -0.036172 0.0899108 -0.145973 -0.0354174 0.0899108 -0.144843 -0.0326894 0.0899108 -0.145914 -0.0317 0.0910593 -0.145965 -0.0324291 0.0910593 -0.145075 -0.0336543 0.0899108 -0.146719 -0.0344725 0.0910593 -0.157923 0.037403 0.0899108 -0.160306 0.0354173 0.0899108 -0.159126 0.0350604 0.0910593 -0.158613 0.0355814 0.0910593 -0.157967 0.0360672 0.0910593 -0.16016 0.0331435 0.0910593 -0.160825 0.0345711 0.0899108 -0.159907 0.0338292 0.0910593 -0.157967 -0.0360673 0.0910593 -0.158907 -0.0368165 0.0899108 -0.160365 -0.0317 0.0910593 -0.160314 -0.0324291 0.0910593 -0.161436 -0.0326894 0.0899108 -0.15956 -0.0344725 0.0910593 -0.160306 -0.0354174 0.0899108 -0.161514 -0.0317 0.0899108 -0.160121 0.0324016 0.0911894 -0.159752 0.0330252 0.091235 -0.159973 0.0330892 0.0911894 -0.15952 0.0336547 0.091235 -0.15973 0.0337491 0.0911894 -0.159202 0.0342452 0.091235 -0.159396 0.0343682 0.0911894 -0.158978 0.034934 0.0911894 -0.158333 0.0352632 0.091235 -0.158485 0.0354354 0.0911894 -0.160314 0.032429 0.0910593 -0.15956 0.0344725 0.0910593 -0.160365 0.0317 0.0910593 -0.160171 0.0317 0.0911894 -0.158485 -0.0354355 0.0911894 -0.158803 -0.034785 0.091235 -0.15952 -0.0336547 0.091235 -0.15973 -0.0337492 0.0911894 -0.159752 -0.0330252 0.091235 -0.160121 -0.0324017 0.0911894 -0.158613 -0.0355815 0.0910593 -0.158978 -0.0349341 0.0911894 -0.159126 -0.0350605 0.0910593 -0.159396 -0.0343683 0.0911894 -0.159907 -0.0338293 0.0910593 -0.16016 -0.0331436 0.0910593 -0.159973 -0.0330893 0.0911894 -0.160171 -0.0317 0.0911894 -0.147946 0.0352632 0.091235 -0.148416 0.0359029 0.0911894 -0.147476 0.034785 0.091235 -0.147301 0.034934 0.0911894 -0.146883 0.0343682 0.0911894 -0.146306 0.0330892 0.0911894 -0.148412 0.0359102 0.0911857 -0.147794 0.0354354 0.0911894 -0.147153 0.0350604 0.0910593 -0.14655 0.0337491 0.0911894 -0.146158 0.0324016 0.0911894 -0.146108 0.0317 0.0911894 -0.146108 -0.0317 0.0911894 -0.146527 -0.0330252 0.091235 -0.14655 -0.0337492 0.0911894 -0.147077 -0.0342453 0.091235 -0.146883 -0.0343683 0.0911894 -0.147476 -0.034785 0.091235 -0.147301 -0.0349341 0.0911894 -0.147946 -0.0352633 0.091235 -0.148416 -0.035903 0.0911894 -0.146158 -0.0324017 0.0911894 -0.146306 -0.0330893 0.0911894 -0.146119 -0.0331436 0.0910593 -0.146372 -0.0338293 0.0910593 -0.147153 -0.0350605 0.0910593 -0.147794 -0.0354355 0.0911894 -0.147666 -0.0355815 0.0910593 -0.157978 -0.0375179 0.0897226 -0.157923 -0.0374031 0.0899108 -0.157979 -0.0375204 0.0897161 -0.158018 -0.0375523 0.0894865 -0.158017 -0.0375528 0.0894934 -0.158016 -0.037553 0.0894955 -0.158015 -0.0375536 0.0894999 -0.158014 -0.037554 0.0895027 -0.159661 -0.036172 0.0899108 -0.160825 -0.0345712 0.0899108 -0.161204 -0.0336543 0.0899108 -0.161328 -0.0336945 0.0897161 -0.161564 -0.0327097 0.0897161 -0.158983 -0.0369217 0.0897161 -0.159753 -0.0362639 0.0897161 -0.15901 -0.0369587 0.0894865 -0.160411 -0.0354938 0.0897161 -0.160448 -0.0355206 0.0894865 -0.16094 -0.0346302 0.0897161 -0.160981 -0.034651 0.0894865 -0.161371 -0.0337087 0.0894865 -0.161644 -0.0317 0.0897161 -0.16161 -0.0327169 0.0894865 -0.161644 0.0317 0.0897161 -0.161514 0.0317 0.0899108 -0.157979 0.0375203 0.0897161 -0.157999 0.0375607 0.0895189 -0.158014 0.0375539 0.0895027 -0.158015 0.0375535 0.0894999 -0.15901 0.0369586 0.0894865 -0.160448 0.0355206 0.0894865 -0.160411 0.0354937 0.0897161 -0.160981 0.0346509 0.0894865 -0.16094 0.0346302 0.0897161 -0.161371 0.0337086 0.0894865 -0.161564 0.0327096 0.0897161 -0.16161 0.0327168 0.0894865 -0.161436 0.0326893 0.0899108 -0.161204 0.0336543 0.0899108 -0.161328 0.0336945 0.0897161 -0.159753 0.0362639 0.0897161 -0.159661 0.0361719 0.0899108 -0.158907 0.0368164 0.0899108 -0.158983 0.0369216 0.0897161 -0.157978 0.0375179 0.0897226 -0.148269 -0.0375558 0.0895105 -0.1483 -0.0375204 0.0897161 -0.148263 -0.037553 0.0894955 -0.148261 -0.0375523 0.0894865 -0.147269 -0.0369587 0.0894865 -0.147296 -0.0369217 0.0897161 -0.145868 -0.0354938 0.0897161 -0.145831 -0.0355206 0.0894865 -0.145298 -0.034651 0.0894865 -0.145339 -0.0346302 0.0897161 -0.144908 -0.0337087 0.0894865 -0.14467 -0.0327169 0.0894865 -0.144715 -0.0327097 0.0897161 -0.147372 -0.0368165 0.0899108 -0.144635 -0.0317 0.0897161 -0.145455 -0.0345712 0.0899108 -0.144951 -0.0336945 0.0897161 -0.146526 -0.0362639 0.0897161 -0.148301 -0.0375179 0.0897226 -0.144765 0.0317 0.0899108 -0.148301 0.0375178 0.0897226 -0.147372 0.0368164 0.0899108 -0.148268 0.0375554 0.0895094 -0.148261 0.0375522 0.0894865 -0.148262 0.0375528 0.0894934 -0.148263 0.037553 0.0894955 -0.147296 0.0369216 0.0897161 -0.145868 0.0354937 0.0897161 -0.145339 0.0346302 0.0897161 -0.145455 0.0345711 0.0899108 -0.144843 0.0326893 0.0899108 -0.146526 0.0362639 0.0897161 -0.144951 0.0336945 0.0897161 -0.144908 0.0337086 0.0894865 -0.14467 0.0327168 0.0894865 -0.144715 0.0327096 0.0897161 -0.144635 0.0317 0.0897161 -0.155088 0.030775 0.089235 -0.151724 0.0284816 0.089235 -0.152015 0.0299514 0.089235 -0.151191 0.030775 0.089235 -0.154555 0.0284816 0.089235 -0.15314 0.02965 0.089235 -0.156216 0.0298443 0.089235 -0.15539 0.0319 0.089235 -0.15684 0.0369666 0.089235 -0.156768 0.0311781 0.089235 -0.150142 0.0378272 0.089235 -0.150063 0.0298443 0.089235 -0.151191 0.033025 0.089235 -0.154265 0.0338485 0.089235 -0.15109 0.0379 0.089235 -0.156137 0.0378272 0.089235 -0.156972 0.0374877 0.089235 -0.15714 0.0319 0.090635 -0.156835 0.0303692 0.089535 -0.156835 0.0303692 0.090635 -0.156465 0.0296777 0.090635 -0.155362 0.0285741 0.089535 -0.15467 0.0282044 0.089535 -0.15392 0.0279768 0.089535 -0.15314 0.0279 0.089535 -0.152359 0.0279768 0.089535 -0.152359 0.0279768 0.090635 -0.151609 0.0282044 0.090635 -0.150917 0.0285741 0.090635 -0.150311 0.0290715 0.090635 -0.149814 0.0296777 0.089535 -0.149814 0.0296777 0.090635 -0.149444 0.0303692 0.090635 -0.149444 0.0303692 0.089535 -0.149216 0.0311196 0.089535 -0.14914 0.0363695 0.0900661 -0.14944 -0.0319 0.089235 -0.14944 -0.0369667 0.089235 -0.149307 -0.0374878 0.089235 -0.15089 -0.0319 0.089235 -0.151191 -0.030775 0.089235 -0.15684 -0.0319 0.089235 -0.156216 -0.0298444 0.089235 -0.151084 -0.0288236 0.089235 -0.151724 -0.0284817 0.089235 -0.152015 -0.0299515 0.089235 -0.152418 -0.0282711 0.089235 -0.15314 -0.02965 0.089235 -0.152015 -0.0338486 0.089235 -0.15314 -0.03415 0.089235 -0.15519 -0.0379 0.089235 -0.154265 -0.0338486 0.089235 -0.15684 -0.0369667 0.089235 -0.154265 -0.0299515 0.089235 -0.153861 -0.0282711 0.089235 -0.155195 -0.0288236 0.089235 -0.149216 -0.0311197 0.089535 -0.149814 -0.0296778 0.089535 -0.149814 -0.0296778 0.090635 -0.150311 -0.0290716 0.090635 -0.150917 -0.0285742 0.089535 -0.152359 -0.0279769 0.089535 -0.15392 -0.0279769 0.089535 -0.15314 -0.0279 0.090635 -0.15467 -0.0282045 0.089535 -0.155968 -0.0290716 0.089535 -0.155968 -0.0290716 0.090635 -0.156465 -0.0296778 0.089535 -0.157063 -0.0311197 0.089535 -0.157063 -0.0311197 0.090635 -0.14914 -0.0357093 0.090635 -0.15714 -0.0319 0.090635 -0.15714 -0.0357093 0.090635 -0.15714 -0.0363696 0.0900661 -0.14679 0.00804996 0.085235 -0.146391 0.0213873 0.0874955 -0.14679 -0.0215525 0.085235 -0.159888 0.0213873 0.0874955 -0.161215 0.025116 0.0875048 -0.16116 0.0254055 0.0862407 -0.160642 0.0242698 0.0875144 -0.161116 0.0256241 0.085235 -0.161215 -0.0251161 0.0875048 -0.16024 -0.0244362 0.085235 -0.15949 -0.0215525 0.085235 -0.145163 0.0256241 0.085235 -0.146009 0.0234674 0.0875161 -0.146599 0.0230433 0.085235 -0.14679 0.0215524 0.085235 -0.146391 -0.0213874 0.0874955 -0.146082 -0.023264 0.0875156 -0.145637 -0.0242699 0.0875144 -0.161553 0.0260115 0.086405 -0.161664 0.0267449 0.085235 -0.16169 0.0265375 0.087235 -0.16169 0.0267137 0.0865955 -0.161689 0.0265095 0.0872402 -0.161419 0.0254345 0.0874431 -0.16169 -0.027071 0.085235 -0.161612 -0.0265025 0.085235 -0.16116 -0.0254056 0.0862407 -0.161116 -0.0256242 0.085235 -0.161553 -0.0260116 0.086405 -0.161571 -0.0263707 0.085235 -0.16169 -0.0267138 0.0865955 -0.16169 -0.0265376 0.087235 -0.161689 -0.026492 0.0872435 -0.161656 -0.0261362 0.0873097 -0.16156 -0.0257594 0.0873809 -0.144667 0.0265024 0.085235 -0.145119 0.0254055 0.0862407 -0.14459 0.0265375 0.087235 -0.144727 0.0260115 0.086405 -0.144727 -0.0260116 0.086405 -0.1446 -0.0268624 0.085235 -0.144778 -0.0261966 0.085235 -0.14459 -0.0265376 0.087235 -0.145119 -0.0254056 0.0862407 -0.14486 -0.0254345 0.0874431 -0.144761 0.025379 0.0878419 -0.144654 0.0256786 0.0877656 -0.14486 0.0254345 0.0874431 -0.14459 0.0264915 0.0872435 -0.144623 0.0261399 0.087309 -0.144718 0.025763 0.0873802 -0.145064 0.025116 0.0875048 -0.144967 0.0250371 0.0878877 -0.144868 0.0249565 0.0881036 -0.145658 0.0213873 0.0885376 -0.144797 0.0248987 0.0882198 -0.14577 0.0233775 0.08811 -0.14532 0.0232081 0.0885414 -0.144952 0.0233513 0.0886658 -0.14614 0.0213873 0.0880983 -0.145637 0.0242698 0.0875144 -0.145664 0.0213873 0.0885337 -0.146143 0.0213873 0.0880951 -0.14614 -0.0213874 0.0880983 -0.146143 -0.0213874 0.0880951 -0.144868 -0.0249566 0.0881036 -0.144988 -0.0229068 0.0886999 -0.144882 -0.0240885 0.0885449 -0.145383 -0.0230301 0.0885414 -0.145658 -0.0213874 0.0885376 -0.145664 -0.0213874 0.0885337 -0.144845 -0.0244493 0.0884366 -0.14584 -0.023183 0.0881097 -0.14459 -0.0264912 0.0872639 -0.14459 -0.026492 0.0872435 -0.144623 -0.0261362 0.0873097 -0.144605 -0.0261267 0.08749 -0.144967 -0.0250372 0.0878877 -0.144647 -0.0257309 0.0877337 -0.14472 -0.0257594 0.0873809 -0.144761 -0.0253791 0.0878419 -0.145064 -0.0251161 0.0875048 -0.161419 -0.0254345 0.0874431 -0.161632 -0.0257309 0.0877337 -0.16169 -0.0265297 0.0872399 -0.161518 -0.0253791 0.0878419 -0.161411 -0.0249566 0.0881036 -0.161327 -0.0233514 0.0886658 -0.160896 -0.0230301 0.0885414 -0.161247 -0.0221005 0.0887249 -0.161397 -0.0240885 0.0885449 -0.160439 -0.023183 0.0881097 -0.161482 -0.0248988 0.0882198 -0.161434 -0.0244493 0.0884366 -0.161292 -0.0229068 0.0886999 -0.160139 -0.0213874 0.0880983 -0.160197 -0.023264 0.0875156 -0.161312 -0.0250372 0.0878877 -0.160642 -0.0242699 0.0875144 -0.159888 -0.0213874 0.0874955 -0.160136 -0.0213874 0.0880951 -0.160622 0.0213873 0.0885376 -0.160615 -0.0213874 0.0885337 -0.160622 -0.0213874 0.0885376 -0.160959 0.0232081 0.0885414 -0.161305 0.0230858 0.0886886 -0.161327 0.0233513 0.0886658 -0.161434 0.0244492 0.0884366 -0.16027 0.0234674 0.0875161 -0.160136 0.0213873 0.0880951 -0.161411 0.0249565 0.0881036 -0.161482 0.0248987 0.0882198 -0.160615 0.0213873 0.0885337 -0.160139 0.0213873 0.0880983 -0.160509 0.0233775 0.08811 -0.16169 0.0265296 0.0872399 -0.161675 0.0261398 0.0874818 -0.161658 0.0261489 0.0873073 -0.161634 0.0257438 0.0877257 -0.161569 0.0253375 0.0879705 -0.161312 0.0250371 0.0878877 -0.161564 0.0257715 0.0873786 -0.161518 0.0253791 0.0878419 -0.161673 -0.0257609 0.087851 -0.161625 -0.0256786 0.0877656 -0.161674 -0.0261267 0.08749 -0.161689 -0.0264912 0.0872639 -0.16169 -0.0258489 0.0879424 -0.161635 -0.0250032 0.0883637 -0.161569 -0.0253375 0.0879706 -0.161593 -0.0249638 0.0883095 -0.16157 -0.0244933 0.0885391 -0.161465 -0.0213874 0.0888097 -0.16163 -0.0213874 0.0889901 -0.161515 -0.0233641 0.0887663 -0.161399 -0.0241038 0.0885412 -0.161472 -0.022102 0.088809 -0.161644 -0.0233855 0.0889356 -0.161551 -0.0241192 0.0886503 -0.161659 -0.0245531 0.0886783 -0.16169 -0.0221095 0.0892215 -0.161632 -0.0221053 0.0889883 -0.16169 -0.0234118 0.0891428 -0.161654 -0.0241639 0.0888032 -0.16169 -0.024216 0.0889816 -0.16169 -0.0246213 0.0888371 -0.161234 0.0213873 0.0887292 -0.161234 -0.0213874 0.0887292 -0.161465 0.0213873 0.0888097 -0.16169 -0.0213874 0.0892273 -0.16163 0.0213873 0.0889901 -0.161632 0.0221052 0.0889883 -0.16169 0.0242159 0.0889816 -0.16169 0.0246212 0.0888371 -0.161665 0.0250458 0.0884226 -0.161644 0.0233854 0.0889356 -0.161654 0.0241638 0.0888032 -0.161659 0.024553 0.0886783 -0.161635 0.0250031 0.0883637 -0.161593 0.0249637 0.0883095 -0.161247 0.0221004 0.0887249 -0.161472 0.0221019 0.088809 -0.161515 0.023364 0.0887663 -0.161551 0.0241191 0.0886503 -0.161397 0.0240884 0.0885449 -0.16157 0.0244932 0.0885391 -0.161673 0.0257608 0.087851 -0.161689 0.026509 0.0872527 -0.161625 0.0256786 0.0877656 -0.16169 0.0265313 0.0872415 -0.14459 -0.0265297 0.0872399 -0.14459 -0.0265314 0.0872415 -0.144606 -0.0257609 0.087851 -0.144654 -0.0256786 0.0877656 -0.14471 -0.0253375 0.0879706 -0.14459 -0.0258489 0.0879424 -0.145032 -0.0221005 0.0887249 -0.144807 -0.022102 0.088809 -0.145046 -0.0213874 0.0887292 -0.144764 -0.0233641 0.0887663 -0.14459 -0.0234118 0.0891428 -0.144647 -0.0221053 0.0889883 -0.14459 -0.024216 0.0889816 -0.144635 -0.0233855 0.0889356 -0.144728 -0.0241192 0.0886503 -0.14488 -0.0241038 0.0885412 -0.144952 -0.0233514 0.0886658 -0.144644 -0.0250032 0.0883637 -0.14459 -0.0251369 0.0885481 -0.14462 -0.0245531 0.0886783 -0.144625 -0.0241639 0.0888032 -0.144709 -0.0244933 0.0885391 -0.144686 -0.0249638 0.0883095 -0.144797 -0.0248988 0.0882198 -0.144649 -0.0213874 0.0889901 -0.144815 -0.0213874 0.0888097 -0.145046 0.0213873 0.0887292 -0.144614 0.0250458 0.0884226 -0.14459 0.0213873 0.0892273 -0.144815 0.0213873 0.0888097 -0.144807 0.0221019 0.088809 -0.144764 0.023364 0.0887663 -0.145032 0.0221004 0.0887249 -0.144974 0.0230858 0.0886886 -0.144882 0.0240884 0.0885449 -0.144709 0.0244932 0.0885391 -0.144845 0.0244492 0.0884366 -0.144686 0.0249637 0.0883095 -0.144649 0.0213873 0.0889901 -0.144647 0.0221052 0.0889883 -0.144728 0.0241191 0.0886503 -0.144625 0.0241638 0.0888032 -0.14459 0.0221094 0.0892215 -0.144635 0.0233854 0.0889356 -0.14459 0.0234117 0.0891428 -0.14462 0.024553 0.0886783 -0.144606 0.0257608 0.087851 -0.144646 0.0257347 0.0877313 -0.144605 0.0261305 0.0874875 -0.14459 0.0264907 0.0872641 -0.14459 0.0265313 0.0872415 -0.14459 0.0265296 0.0872399 -0.144644 0.0250031 0.0883637 -0.14471 0.0253375 0.0879706 -0.14884 0.0375386 0.0895189 -0.14856 0.0376192 0.0895189 -0.1483 0.0375203 0.0897161 -0.148356 0.037403 0.0899108 -0.14856 0.037422 0.0899318 -0.148635 0.0374171 0.0899264 -0.14856 0.0375622 0.0897435 -0.14905 0.0372315 0.0897205 -0.14905 0.0373051 0.0896216 -0.148841 0.0374893 0.0897089 -0.148893 0.0373451 0.0898465 -0.148871 0.0360318 0.0910174 -0.148595 0.0360945 0.0910917 -0.149069 0.0358913 0.0908508 -0.148874 0.0360305 0.0910159 -0.148336 0.0367418 0.0904903 -0.1486 0.0360942 0.0910913 -0.148619 0.0367617 0.090513 -0.148885 0.0366933 0.0904351 -0.149138 0.0370496 0.0895189 -0.149074 0.0372025 0.0896884 -0.149072 0.0365519 0.090274 -0.148841 0.0373679 0.0898719 -0.148312 0.0360672 0.0910593 -0.14884 0.0357092 0.0911546 -0.148595 0.0359143 0.0911962 -0.148871 0.0358809 0.0911049 -0.149068 0.0358067 0.0909017 -0.14914 0.0357092 0.090635 -0.149068 0.0357092 0.090919 -0.14914 0.0319 0.090635 -0.149059 0.0357092 0.090935 -0.148871 0.0357092 0.0911353 -0.14884 0.0319 0.0911546 -0.148595 0.0357092 0.0912325 -0.149059 0.0319 0.090935 -0.149216 0.0311196 0.090635 -0.149138 0.0311039 0.090935 -0.149747 0.029633 0.090935 -0.150254 0.0290147 0.090935 -0.15314 0.0279 0.090635 -0.15392 0.0279768 0.090635 -0.15467 0.0282044 0.090635 -0.155362 0.0285741 0.090635 -0.155968 0.0290715 0.090635 -0.156025 0.0290147 0.090935 -0.156532 0.029633 0.090935 -0.156909 0.0303385 0.090935 -0.157063 0.0311196 0.090635 -0.157142 0.0311039 0.090935 -0.148922 0.0310611 0.0911546 -0.14937 0.0303385 0.090935 -0.149167 0.0302544 0.0911546 -0.149564 0.029511 0.0911546 -0.150873 0.0285072 0.090935 -0.151578 0.0281302 0.090935 -0.151494 0.0279273 0.0911546 -0.152344 0.027898 0.090935 -0.15314 0.0278196 0.090935 -0.153936 0.027898 0.090935 -0.153978 0.0276826 0.0911546 -0.154701 0.0281302 0.090935 -0.154785 0.0279273 0.0911546 -0.155407 0.0285072 0.090935 -0.155529 0.0283246 0.0911546 -0.15618 0.0288594 0.0911546 -0.157112 0.0302544 0.0911546 -0.148628 0.0310025 0.091235 -0.149887 0.0286473 0.091235 -0.150099 0.0288594 0.0911546 -0.150751 0.0283246 0.0911546 -0.152301 0.0276826 0.0911546 -0.15314 0.0273 0.091235 -0.15314 0.0276 0.0911546 -0.154037 0.0273883 0.091235 -0.156715 0.029511 0.0911546 -0.156392 0.0286473 0.091235 -0.156964 0.0293443 0.091235 -0.157389 0.0301396 0.091235 -0.157357 0.0310611 0.0911546 -0.157651 0.0310025 0.091235 -0.157211 0.0357092 0.090919 -0.15722 0.0319 0.090935 -0.15774 0.0319 0.091235 -0.157684 0.0357092 0.0912325 -0.15744 0.0319 0.0911546 -0.15744 0.0357092 0.0911546 -0.157863 0.0359029 0.0911894 -0.157684 0.0359143 0.0911962 -0.15721 0.0358913 0.0908508 -0.157211 0.0358067 0.0909017 -0.157405 0.0360305 0.0910159 -0.157408 0.0358809 0.0911049 -0.157684 0.0360945 0.0910917 -0.157867 0.0359102 0.0911857 -0.157408 0.0357092 0.0911353 -0.15722 0.0357092 0.090935 -0.15714 0.0357092 0.090635 -0.157943 0.0367418 0.0904903 -0.15766 0.0367617 0.090513 -0.157644 0.0374171 0.0899264 -0.157395 0.0366933 0.0904351 -0.15714 0.0363695 0.0900661 -0.157207 0.0365519 0.090274 -0.157679 0.0360942 0.0910913 -0.157719 0.037422 0.0899318 -0.157439 0.0375386 0.0895189 -0.157719 0.0375622 0.0897435 -0.157438 0.0373679 0.0898719 -0.157438 0.0374893 0.0897089 -0.157229 0.0373051 0.0896216 -0.157386 0.0373451 0.0898465 -0.157229 0.0372315 0.0897205 -0.157205 0.0372025 0.0896884 -0.157438 -0.0374893 0.0897089 -0.157229 -0.037334 0.0895189 -0.157719 -0.0375623 0.0897435 -0.157719 -0.0374221 0.0899318 -0.157386 -0.0373452 0.0898465 -0.157229 -0.0373052 0.0896216 -0.157438 -0.037368 0.0898719 -0.157408 -0.0360319 0.0910174 -0.157395 -0.0366934 0.0904351 -0.157943 -0.0367419 0.0904903 -0.15766 -0.0367618 0.090513 -0.157684 -0.0360946 0.0910917 -0.157644 -0.0374172 0.0899264 -0.15714 -0.0369667 0.089535 -0.157207 -0.036552 0.090274 -0.157205 -0.0372026 0.0896884 -0.157229 -0.0372315 0.0897205 -0.15774 -0.0357093 0.091235 -0.157863 -0.035903 0.0911894 -0.157867 -0.0359103 0.0911857 -0.157408 -0.035881 0.0911049 -0.157684 -0.0359144 0.0911962 -0.157684 -0.0357093 0.0912325 -0.157679 -0.0360942 0.0910913 -0.157211 -0.0357093 0.090919 -0.157211 -0.0358068 0.0909017 -0.157408 -0.0357093 0.0911353 -0.157405 -0.0360306 0.0910159 -0.15721 -0.0358914 0.0908508 -0.157315 -0.0357093 0.0910593 -0.157315 -0.0319 0.0910593 -0.15744 -0.0319 0.0911546 -0.15751 -0.0357093 0.0911894 -0.157142 -0.031104 0.090935 -0.15722 -0.0319 0.090935 -0.156835 -0.0303693 0.090635 -0.156532 -0.0296331 0.090935 -0.156465 -0.0296778 0.090635 -0.156025 -0.0290148 0.090935 -0.155362 -0.0285742 0.090635 -0.154701 -0.0281303 0.090935 -0.15467 -0.0282045 0.090635 -0.15392 -0.0279769 0.090635 -0.152359 -0.0279769 0.090635 -0.151609 -0.0282045 0.090635 -0.150917 -0.0285742 0.090635 -0.150873 -0.0285073 0.090935 -0.149444 -0.0303693 0.090635 -0.149216 -0.0311197 0.090635 -0.157357 -0.0310612 0.0911546 -0.156909 -0.0303385 0.090935 -0.157112 -0.0302545 0.0911546 -0.156715 -0.0295111 0.0911546 -0.15618 -0.0288595 0.0911546 -0.155407 -0.0285073 0.090935 -0.154785 -0.0279274 0.0911546 -0.153978 -0.0276827 0.0911546 -0.153936 -0.0278981 0.090935 -0.15314 -0.0278197 0.090935 -0.15314 -0.0276 0.0911546 -0.152344 -0.0278981 0.090935 -0.151578 -0.0281303 0.090935 -0.151494 -0.0279274 0.0911546 -0.150254 -0.0290148 0.090935 -0.149747 -0.0296331 0.090935 -0.14937 -0.0303385 0.090935 -0.149138 -0.031104 0.090935 -0.14884 -0.0319 0.0911546 -0.157651 -0.0310026 0.091235 -0.157389 -0.0301397 0.091235 -0.156964 -0.0293444 0.091235 -0.155529 -0.0283247 0.0911546 -0.1549 -0.0276502 0.091235 -0.154037 -0.0273884 0.091235 -0.15314 -0.0273 0.091235 -0.152301 -0.0276827 0.0911546 -0.151379 -0.0276502 0.091235 -0.150751 -0.0283247 0.0911546 -0.150584 -0.0280753 0.091235 -0.150099 -0.0288595 0.0911546 -0.149887 -0.0286474 0.091235 -0.149564 -0.0295111 0.0911546 -0.149167 -0.0302545 0.0911546 -0.14889 -0.0301397 0.091235 -0.148922 -0.0310612 0.0911546 -0.14914 -0.0319 0.090635 -0.149068 -0.0357093 0.090919 -0.149059 -0.0319 0.090935 -0.14854 -0.0319 0.091235 -0.148871 -0.0357093 0.0911353 -0.14854 -0.0357093 0.091235 -0.148595 -0.0357093 0.0912325 -0.148595 -0.0359144 0.0911962 -0.148871 -0.035881 0.0911049 -0.149068 -0.0358068 0.0909017 -0.1486 -0.0360942 0.0910913 -0.148595 -0.0360946 0.0910917 -0.148412 -0.0359103 0.0911857 -0.148312 -0.0360673 0.0910593 -0.14884 -0.0357093 0.0911546 -0.149059 -0.0357093 0.090935 -0.148356 -0.0374031 0.0899108 -0.148635 -0.0374172 0.0899264 -0.148893 -0.0373452 0.0898465 -0.148885 -0.0366934 0.0904351 -0.149074 -0.0372026 0.0896884 -0.14914 -0.0363696 0.0900661 -0.149069 -0.0358914 0.0908508 -0.149072 -0.036552 0.090274 -0.148874 -0.0360306 0.0910159 -0.148619 -0.0367618 0.090513 -0.148336 -0.0367419 0.0904903 -0.14856 -0.0375623 0.0897435 -0.14856 -0.0376193 0.0895189 -0.14905 -0.0373052 0.0896216 -0.14856 -0.0374221 0.0899318 -0.148841 -0.0374894 0.0897089 -0.148841 -0.037368 0.0898719 -0.14905 -0.0372315 0.0897205 -0.149138 -0.0370497 0.0895189 -0.149437 -0.0370643 0.089235 -0.149326 -0.0370589 0.0892563 -0.14929 -0.0369667 0.0892752 -0.149227 -0.0369667 0.0893229 -0.149231 -0.0370542 0.0893173 -0.149162 -0.0369667 0.0894202 -0.149165 -0.037051 0.0894091 -0.14914 -0.0369667 0.089535 -0.14918 -0.0369667 0.089385 -0.149325 -0.0369667 0.0892579 -0.148556 -0.0376194 0.0895189 -0.148336 -0.0375851 0.0895062 -0.148303 -0.0375712 0.0895135 -0.148281 -0.0375608 0.0895189 -0.148286 -0.0375636 0.0895151 -0.148685 -0.0376426 0.089385 -0.149217 -0.0376106 0.089235 -0.149072 -0.0376142 0.0892526 -0.14884 -0.0375387 0.0895189 -0.14909 -0.0373556 0.0893758 -0.14905 -0.037334 0.0895189 -0.149051 -0.037332 0.0895189 -0.148863 -0.0375779 0.0893758 -0.148894 -0.0376286 0.0893071 -0.149183 -0.0370519 0.0893758 -0.149183 -0.0374123 0.0892726 -0.149292 -0.0370572 0.0892726 -0.14914 -0.0319 0.089535 -0.149256 -0.0311275 0.089385 -0.149481 -0.0303847 0.089385 -0.149444 -0.0303693 0.089535 -0.150311 -0.0290716 0.089535 -0.15034 -0.0291 0.089385 -0.15094 -0.0286076 0.089385 -0.151609 -0.0282045 0.089535 -0.152367 -0.0280163 0.089385 -0.15314 -0.0279 0.089535 -0.154655 -0.0282417 0.089385 -0.155362 -0.0285742 0.089535 -0.15594 -0.0291 0.089385 -0.156432 -0.0297001 0.089385 -0.156798 -0.0303847 0.089385 -0.156835 -0.0303693 0.089535 -0.157099 -0.0319 0.089385 -0.15714 -0.0319 0.089535 -0.14929 -0.0319 0.0892752 -0.14918 -0.0319 0.089385 -0.149583 -0.0304267 0.0892752 -0.149847 -0.0297001 0.089385 -0.150417 -0.0291777 0.0892752 -0.151001 -0.0286989 0.0892752 -0.151666 -0.0283431 0.0892752 -0.151624 -0.0282417 0.089385 -0.152388 -0.028124 0.0892752 -0.15314 -0.0279402 0.089385 -0.153891 -0.028124 0.0892752 -0.153912 -0.0280163 0.089385 -0.154613 -0.0283431 0.0892752 -0.15534 -0.0286076 0.089385 -0.155279 -0.0286989 0.0892752 -0.156696 -0.0304267 0.0892752 -0.157023 -0.0311275 0.089385 -0.149511 -0.0311782 0.089235 -0.149364 -0.0311489 0.0892752 -0.149721 -0.0304841 0.089235 -0.150063 -0.0298444 0.089235 -0.149938 -0.0297611 0.0892752 -0.150523 -0.0292837 0.089235 -0.15314 -0.0282 0.089235 -0.15314 -0.02805 0.0892752 -0.154555 -0.0284817 0.089235 -0.155756 -0.0292837 0.089235 -0.155862 -0.0291777 0.0892752 -0.156341 -0.0297611 0.0892752 -0.156558 -0.0304841 0.089235 -0.156768 -0.0311782 0.089235 -0.156916 -0.0311489 0.0892752 -0.148273 -0.0375579 0.08951 -0.148274 -0.037558 0.0895151 -0.148285 -0.0375635 0.0895101 -0.148265 -0.037554 0.0895027 -0.148264 -0.0375536 0.0894999 -0.148262 -0.0375528 0.0894934 -0.148558 -0.0376374 0.0894315 -0.148517 -0.0376322 0.0894463 -0.148422 -0.0376169 0.0894567 -0.148443 -0.0376181 0.089472 -0.148365 -0.0375958 0.0894976 -0.1483 -0.0375703 0.0895081 -0.148843 -0.0376873 0.0892692 -0.14899 -0.0376198 0.0892746 -0.149029 -0.0377042 0.0892194 -0.149183 -0.0377201 0.0892122 -0.148322 -0.0375809 0.0894918 -0.148329 -0.0375831 0.089499 -0.148355 -0.0375934 0.0894883 -0.148487 -0.0376353 0.0894253 -0.148458 -0.0376341 0.0894033 -0.149172 -0.0377536 0.0891948 -0.148983 -0.0377738 0.0891556 -0.148274 -0.0375585 0.089505 -0.148284 -0.0375634 0.0895052 -0.148297 -0.0375694 0.0895028 -0.148294 -0.0375683 0.0894974 -0.148344 -0.0375904 0.089479 -0.148402 -0.0376137 0.089441 -0.148382 -0.0376083 0.0894251 -0.148788 -0.0377272 0.0892154 -0.148733 -0.0377448 0.0891503 -0.148939 -0.0378145 0.0890689 -0.149153 -0.0378128 0.0891472 -0.149139 -0.0378583 0.089085 -0.148265 -0.0375542 0.0894969 -0.148275 -0.0375591 0.0895 -0.148276 -0.0375596 0.089495 -0.148284 -0.0375632 0.0895002 -0.148283 -0.037563 0.0894952 -0.148316 -0.0375783 0.0894846 -0.148292 -0.0375671 0.089492 -0.148309 -0.0375753 0.0894774 -0.148334 -0.0375867 0.0894696 -0.148324 -0.0375824 0.0894602 -0.148364 -0.0376009 0.089409 -0.14843 -0.0376286 0.0893806 -0.148684 -0.0377387 0.0890793 -0.148904 -0.0378214 0.0889702 -0.149127 -0.0378966 0.088935 -0.157117 -0.0369667 0.0894202 -0.156954 -0.0369667 0.0892579 -0.15699 -0.0319 0.0892752 -0.150119 -0.0379755 0.0891948 -0.149134 -0.0378748 0.0890498 -0.150097 -0.0381237 0.088935 -0.15109 -0.0379 0.089235 -0.150142 -0.0378273 0.089235 -0.15109 -0.0381122 0.0891472 -0.150103 -0.038084 0.089085 -0.156987 -0.0370572 0.0892726 -0.15699 -0.0369667 0.0892752 -0.157052 -0.0369667 0.0893229 -0.157099 -0.0369667 0.089385 -0.157096 -0.0370519 0.0893758 -0.15109 -0.0380148 0.0892122 -0.15109 -0.03805 0.0891948 -0.15519 -0.03805 0.0891948 -0.15109 -0.0381599 0.089085 -0.15519 -0.0381599 0.089085 -0.15519 -0.0381772 0.0890498 -0.15519 -0.0382 0.088935 -0.15109 -0.0381772 0.0890498 -0.15109 -0.0382 0.088935 -0.157386 -0.0376287 0.0893075 -0.157416 -0.0375779 0.0893758 -0.157207 -0.0376142 0.0892526 -0.157062 -0.0376106 0.089235 -0.158005 -0.037558 0.0895151 -0.157999 -0.0375608 0.0895189 -0.157723 -0.0376194 0.0895189 -0.157189 -0.0373556 0.0893758 -0.157719 -0.0376193 0.0895189 -0.157594 -0.0376426 0.089385 -0.157439 -0.0375387 0.0895189 -0.157228 -0.037332 0.0895189 -0.157114 -0.037051 0.0894091 -0.157141 -0.0370497 0.0895189 -0.157048 -0.0370542 0.0893173 -0.157096 -0.0374123 0.0892726 -0.156953 -0.0370589 0.0892563 -0.156972 -0.0374878 0.089235 -0.156842 -0.0370643 0.089235 -0.157096 -0.0377201 0.0892122 -0.156137 -0.0378273 0.089235 -0.15616 -0.0379755 0.0891948 -0.15519 -0.0380148 0.0892122 -0.156176 -0.038084 0.089085 -0.15519 -0.0381122 0.0891472 -0.157107 -0.0377536 0.0891948 -0.158005 -0.0375585 0.089505 -0.158011 -0.0375556 0.0894915 -0.158011 -0.0375554 0.0895094 -0.158014 -0.0375542 0.0894969 -0.158006 -0.0375579 0.08951 -0.157993 -0.0375636 0.0895151 -0.157979 -0.0375703 0.0895081 -0.157976 -0.0375712 0.0895135 -0.157943 -0.0375851 0.0895062 -0.157914 -0.0375958 0.0894976 -0.157836 -0.0376181 0.089472 -0.157763 -0.0376322 0.0894463 -0.157437 -0.0376873 0.0892692 -0.157792 -0.0376353 0.0894253 -0.157721 -0.0376374 0.0894315 -0.158004 -0.0375591 0.0895 -0.157996 -0.037563 0.0894952 -0.157995 -0.0375632 0.0895002 -0.157985 -0.0375683 0.0894974 -0.157987 -0.0375671 0.089492 -0.157963 -0.0375783 0.0894846 -0.157945 -0.0375867 0.0894696 -0.157849 -0.0376286 0.0893806 -0.157595 -0.0377387 0.0890793 -0.157152 -0.0378966 0.088935 -0.157145 -0.0378748 0.0890498 -0.157982 -0.0375694 0.0895028 -0.157957 -0.0375809 0.0894918 -0.157935 -0.0375904 0.089479 -0.157897 -0.0376083 0.0894251 -0.157546 -0.0377448 0.0891503 -0.157821 -0.0376341 0.0894033 -0.15734 -0.0378145 0.0890689 -0.157297 -0.0377738 0.0891556 -0.15714 -0.0378583 0.089085 -0.157995 -0.0375634 0.0895052 -0.157994 -0.0375635 0.0895101 -0.15795 -0.0375831 0.089499 -0.157924 -0.0375934 0.0894883 -0.157877 -0.0376137 0.089441 -0.157857 -0.0376169 0.0894567 -0.157491 -0.0377272 0.0892154 -0.15725 -0.0377042 0.0892194 -0.157126 -0.0378128 0.0891472 -0.157289 -0.0376198 0.0892746 -0.156954 0.0369666 0.0892579 -0.156842 0.0370642 0.089235 -0.157099 0.0369666 0.089385 -0.157117 0.0369666 0.0894202 -0.15714 0.0369666 0.089535 -0.15714 0.0319 0.089535 -0.157052 0.0369666 0.0893229 -0.15699 0.0319 0.0892752 -0.15699 0.0369666 0.0892752 -0.157723 0.0376193 0.0895189 -0.157719 0.0376192 0.0895189 -0.157836 0.037618 0.089472 -0.157062 0.0376105 0.089235 -0.157096 0.0374122 0.0892726 -0.157207 0.0376142 0.0892526 -0.157416 0.0375778 0.0893758 -0.157594 0.0376425 0.089385 -0.157229 0.0373339 0.0895189 -0.157189 0.0373555 0.0893758 -0.157228 0.037332 0.0895189 -0.157141 0.0370496 0.0895189 -0.157114 0.0370509 0.0894091 -0.157096 0.0370518 0.0893758 -0.157289 0.0376197 0.0892746 -0.157048 0.0370542 0.0893173 -0.156987 0.0370571 0.0892726 -0.156953 0.0370588 0.0892563 -0.157023 0.0311274 0.089385 -0.156798 0.0303846 0.089385 -0.157063 0.0311196 0.089535 -0.156432 0.0297 0.089385 -0.156465 0.0296777 0.089535 -0.155968 0.0290715 0.089535 -0.15534 0.0286075 0.089385 -0.154655 0.0282416 0.089385 -0.153912 0.0280162 0.089385 -0.15314 0.0279402 0.089385 -0.152367 0.0280162 0.089385 -0.151624 0.0282416 0.089385 -0.151609 0.0282044 0.089535 -0.15094 0.0286075 0.089385 -0.150917 0.0285741 0.089535 -0.150311 0.0290715 0.089535 -0.149481 0.0303846 0.089385 -0.14918 0.0319 0.089385 -0.157099 0.0319 0.089385 -0.156916 0.0311489 0.0892752 -0.156341 0.029761 0.0892752 -0.15594 0.0291 0.089385 -0.155862 0.0291776 0.0892752 -0.155279 0.0286988 0.0892752 -0.154613 0.028343 0.0892752 -0.153891 0.0281239 0.0892752 -0.15314 0.02805 0.0892752 -0.152388 0.0281239 0.0892752 -0.151666 0.028343 0.0892752 -0.15034 0.0291 0.089385 -0.150417 0.0291776 0.0892752 -0.149847 0.0297 0.089385 -0.149256 0.0311274 0.089385 -0.15684 0.0319 0.089235 -0.156558 0.030484 0.089235 -0.156696 0.0304266 0.0892752 -0.155756 0.0292837 0.089235 -0.155195 0.0288235 0.089235 -0.153861 0.0282711 0.089235 -0.15314 0.0282 0.089235 -0.152418 0.0282711 0.089235 -0.151084 0.0288235 0.089235 -0.151001 0.0286988 0.0892752 -0.150523 0.0292837 0.089235 -0.149938 0.029761 0.0892752 -0.149721 0.030484 0.089235 -0.149583 0.0304266 0.0892752 -0.149511 0.0311781 0.089235 -0.14944 0.0319 0.089235 -0.149364 0.0311489 0.0892752 -0.15734 0.0378144 0.0890689 -0.158011 0.0375554 0.0895094 -0.158016 0.037553 0.0894955 -0.158014 0.0375541 0.0894969 -0.158017 0.0375528 0.0894934 -0.157721 0.0376373 0.0894315 -0.157437 0.0376873 0.0892692 -0.157763 0.0376321 0.0894463 -0.157914 0.0375957 0.0894976 -0.157943 0.037585 0.0895062 -0.157979 0.0375703 0.0895081 -0.157976 0.0375711 0.0895135 -0.157993 0.0375635 0.0895151 -0.158005 0.0375579 0.0895151 -0.157386 0.0376286 0.0893075 -0.15725 0.0377041 0.0892194 -0.157096 0.03772 0.0892122 -0.158006 0.0375578 0.08951 -0.157994 0.0375635 0.0895101 -0.157982 0.0375693 0.0895028 -0.15795 0.0375831 0.089499 -0.157924 0.0375933 0.0894883 -0.157857 0.0376169 0.0894567 -0.157877 0.0376136 0.089441 -0.157792 0.0376352 0.0894253 -0.157297 0.0377737 0.0891556 -0.157107 0.0377535 0.0891948 -0.158005 0.0375585 0.089505 -0.157995 0.0375633 0.0895052 -0.157985 0.0375682 0.0894974 -0.157957 0.0375808 0.0894918 -0.157935 0.0375903 0.089479 -0.157945 0.0375866 0.0894696 -0.157897 0.0376082 0.0894251 -0.157849 0.0376286 0.0893806 -0.157821 0.037634 0.0894033 -0.157491 0.0377271 0.0892154 -0.157126 0.0378128 0.0891472 -0.158004 0.037559 0.0895 -0.157995 0.0375631 0.0895002 -0.157996 0.0375629 0.0894952 -0.157987 0.037567 0.089492 -0.157963 0.0375782 0.0894846 -0.15797 0.0375752 0.0894774 -0.157955 0.0375823 0.0894602 -0.157915 0.0376008 0.089409 -0.157546 0.0377447 0.0891503 -0.157876 0.0376189 0.0893576 -0.157595 0.0377386 0.0890793 -0.157145 0.0378748 0.0890498 -0.14914 0.0319 0.089535 -0.14918 0.0369666 0.089385 -0.14929 0.0319 0.0892752 -0.14929 0.0369666 0.0892752 -0.15616 0.0379754 0.0891948 -0.15714 0.0378582 0.089085 -0.156183 0.0381237 0.088935 -0.15519 0.0381121 0.0891472 -0.156176 0.0380839 0.089085 -0.149437 0.0370642 0.089235 -0.14944 0.0369666 0.089235 -0.149325 0.0369666 0.0892579 -0.149227 0.0369666 0.0893229 -0.149165 0.0370509 0.0894091 -0.149162 0.0369666 0.0894202 -0.14914 0.0369666 0.089535 -0.15519 0.0379 0.089235 -0.15519 0.03805 0.0891948 -0.15109 0.0381771 0.0890498 -0.15519 0.0381598 0.089085 -0.15109 0.0382 0.088935 -0.148863 0.0375778 0.0893758 -0.149307 0.0374877 0.089235 -0.149072 0.0376142 0.0892526 -0.148274 0.0375579 0.0895151 -0.148281 0.0375607 0.0895189 -0.148556 0.0376193 0.0895189 -0.148336 0.037585 0.0895062 -0.148365 0.0375957 0.0894976 -0.148517 0.0376321 0.0894463 -0.148558 0.0376373 0.0894315 -0.148685 0.0376425 0.089385 -0.14905 0.0373339 0.0895189 -0.149051 0.037332 0.0895189 -0.149183 0.0370518 0.0893758 -0.14909 0.0373555 0.0893758 -0.149231 0.0370542 0.0893173 -0.149292 0.0370571 0.0892726 -0.149183 0.0374122 0.0892726 -0.149326 0.0370588 0.0892563 -0.15109 0.0380148 0.0892122 -0.150125 0.0379406 0.0892122 -0.15109 0.0381121 0.0891472 -0.1501 0.0381011 0.0890498 -0.149217 0.0376105 0.089235 -0.149183 0.03772 0.0892122 -0.15011 0.0380368 0.0891472 -0.149134 0.0378748 0.0890498 -0.148894 0.0376285 0.0893071 -0.148284 0.0375631 0.0895002 -0.148286 0.0375635 0.0895151 -0.148303 0.0375711 0.0895135 -0.148329 0.0375831 0.089499 -0.148422 0.0376169 0.0894567 -0.148487 0.0376352 0.0894253 -0.148443 0.037618 0.089472 -0.148265 0.0375541 0.0894969 -0.148283 0.0375629 0.0894952 -0.148294 0.0375682 0.0894974 -0.148292 0.037567 0.089492 -0.148316 0.0375782 0.0894846 -0.148309 0.0375752 0.0894774 -0.148334 0.0375866 0.0894696 -0.148364 0.0376008 0.089409 -0.148274 0.0375585 0.089505 -0.148284 0.0375633 0.0895052 -0.148297 0.0375693 0.0895028 -0.148322 0.0375808 0.0894918 -0.148382 0.0376082 0.0894251 -0.148402 0.0376136 0.089441 -0.14843 0.0376286 0.0893806 -0.148458 0.037634 0.0894033 -0.148733 0.0377447 0.0891503 -0.148268 0.0375555 0.0894915 -0.148264 0.0375535 0.0894999 -0.148275 0.037559 0.0895 -0.148265 0.0375539 0.0895027 -0.148273 0.0375578 0.08951 -0.148285 0.0375635 0.0895101 -0.1483 0.0375703 0.0895081 -0.148344 0.0375903 0.089479 -0.148355 0.0375933 0.0894883 -0.148843 0.0376873 0.0892692 -0.14899 0.0376197 0.0892746 -0.149029 0.0377041 0.0892194 -0.148788 0.0377271 0.0892154 -0.148904 0.0378213 0.0889702 -0.149153 0.0378128 0.0891472 -0.148983 0.0377737 0.0891556 -0.148939 0.0378144 0.0890689 -0.151191 -0.033025 0.089235 -0.155088 -0.030775 0.089235 -0.155088 -0.030775 0.085235 -0.15539 -0.0319 0.089235 -0.155088 -0.033025 0.085235 -0.155088 -0.033025 0.089235 -0.154265 -0.0338486 0.085235 -0.15314 -0.03415 0.085235 -0.15089 0.0319 0.085235 -0.15089 0.0319 0.089235 -0.152015 0.0338485 0.089235 -0.15314 0.03415 0.089235 -0.155088 0.033025 0.089235 -0.155088 0.030775 0.085235 -0.154265 0.0299514 0.089235 -0.15729 -0.0232 0.075433 -0.15339 -0.0271 0.075433 -0.154882 -0.0268032 0.075433 -0.155582 -0.0253921 0.073235 -0.156254 -0.0243864 0.073235 -0.15729 -0.0142 0.075433 -0.156993 -0.0127076 0.075433 -0.156254 -0.0130137 0.073235 -0.155582 -0.012008 0.073235 -0.154882 -0.0105969 0.075433 -0.15289 -0.0271 0.075433 -0.15339 -0.0103 0.075433 -0.14979 -0.0232 0.073235 -0.14899 -0.0232 0.075433 -0.150026 -0.0243864 0.073235 -0.151397 -0.0268032 0.075433 -0.151703 -0.0260641 0.073235 -0.15289 -0.0103 0.075433 -0.151703 -0.011336 0.073235 -0.150026 -0.0130137 0.073235 -0.149286 -0.0127076 0.075433 -0.14979 -0.0142 0.073235 -0.15659 0.00229996 0.073235 -0.154982 -0.00630317 0.075433 -0.154676 -0.00556407 0.073235 -0.155682 -0.00489207 0.073235 -0.156354 -0.00388636 0.073235 -0.156354 0.00348628 0.073235 -0.157093 0.00379242 0.075433 -0.156247 0.00505767 0.075433 -0.155682 0.00449199 0.073235 -0.15349 0.00619996 0.075433 -0.15349 -0.00580004 0.073235 -0.14889 -0.00270004 0.075433 -0.149186 -0.00419251 0.075433 -0.149926 -0.00388636 0.073235 -0.150032 -0.00545776 0.075433 -0.150598 -0.00489207 0.073235 -0.151297 -0.00630317 0.075433 -0.15279 0.00539996 0.073235 -0.151297 0.00590309 0.075433 -0.150598 0.00449199 0.073235 -0.149186 0.00379242 0.075433 -0.149926 0.00348628 0.073235 -0.15634 0.0138 0.073235 -0.154732 0.0101968 0.075433 -0.15324 0.0107 0.073235 -0.154426 0.0109359 0.073235 -0.155432 0.0116079 0.073235 -0.15714 0.0138 0.075433 -0.15634 0.0232 0.073235 -0.155997 0.0259577 0.075433 -0.155432 0.025392 0.073235 -0.15324 0.0271 0.075433 -0.150176 0.0126136 0.073235 -0.150282 0.0110422 0.075433 -0.150848 0.0116079 0.073235 -0.15304 0.0263 0.073235 -0.149436 0.0246924 0.075433 -0.150176 0.0243863 0.073235 -0.14994 0.0232 0.073235 -0.14914 0.0232 0.075433 0.455051 -0.048602 0.0676085 0.45509 -0.0487248 0.0733538 0.455226 -0.0489581 0.0666864 0.455383 -0.0491101 0.0661908 0.455631 -0.0492431 0.0726357 0.45533 -0.0490666 0.0729331 0.45555 -0.0492105 0.0657834 0.456149 -0.0492654 0.0723839 0.465013 0.0422409 0.0711914 0.46451 0.0446417 0.0632289 0.465064 0.0425216 0.0709363 0.46506 0.0424921 0.0643855 0.465045 0.0434068 0.0702991 0.465062 0.0432969 0.0637242 0.464706 0.0443435 0.0632533 0.46501 0.0422282 0.0646523 0.464376 0.0409968 0.0726667 0.463253 0.0402024 0.0679371 0.468262 -0.015 0.0670775 0.469095 -0.0144433 0.0726336 0.469145 -0.014279 0.0647283 0.469163 -0.0141417 0.0725758 0.469163 -0.0141417 0.064698 0.471135 -0.0145029 0.063204 0.471161 -0.014233 0.0631912 0.471086 -0.0147653 0.0632519 0.469852 -0.0165258 0.0649462 0.470363 -0.0161001 0.0708699 0.470554 -0.0158787 0.0639787 0.470684 -0.0156974 0.0637975 0.46952 -0.0167136 0.0719268 0.469209 -0.0168414 0.0658031 0.469079 -0.016883 0.0659728 0.466795 -0.0339692 0.0659689 0.466974 -0.0338998 0.0728057 0.467194 -0.0337403 0.0725967 0.466913 -0.0339284 0.065682 0.467279 -0.033643 0.0725232 0.46734 -0.033552 0.0724761 0.467422 -0.033363 0.0724269 0.468572 -0.0351893 0.0638225 0.468814 -0.0349261 0.0635704 0.469169 -0.0343699 0.0632496 0.469391 -0.0337368 0.063165 0.46791 -0.035667 0.0645717 0.46656 -0.036 0.0662055 0.466957 -0.0359728 0.0721817 0.445776 -0.0508682 0.072358 0.445787 -0.0508794 0.0723455 0.445785 -0.0508777 0.0653619 0.445984 -0.05103 0.0649538 0.446199 -0.0511175 0.0720799 0.446099 -0.0510849 0.0648031 0.446285 -0.0511354 0.0646631 0.446427 -0.0511467 0.0646316 0.444352 -0.0522726 0.0644511 0.444403 -0.0523234 0.0643823 0.444941 -0.0527371 0.0638067 0.443527 -0.0502467 0.0669241 0.443761 -0.0513883 0.0717708 0.443697 -0.0512247 0.0657912 0.445169 -0.0600342 -0.0366243 0.445169 -0.0598052 -0.0440888 0.441473 -0.0600782 -0.0387561 0.441349 -0.0599777 -0.0402853 0.441641 -0.0599133 -0.0417465 0.441169 -0.0600114 -0.0402868 0.443482 -0.0601697 -0.0366597 0.442666 -0.0598173 -0.0377698 0.443814 -0.0598543 -0.0370012 0.443191 -0.0593678 -0.0431525 0.442694 -0.0593884 -0.0427398 0.443775 -0.059713 -0.0436447 0.445169 -0.0595336 -0.0438051 0.441905 -0.0596318 -0.0416252 0.441795 -0.0599309 -0.0388831 0.441633 -0.0596969 -0.0402731 0.442585 -0.0599851 -0.0376967 0.44377 -0.0600214 -0.0369032 0.445169 -0.0596865 -0.036765 0.443829 -0.0593505 -0.0434985 0.443827 -0.0594441 -0.0435073 0.441929 -0.0595374 -0.0416111 0.44166 -0.0596034 -0.040269 0.445169 -0.0595269 -0.0438024 0.443818 -0.0595399 -0.0435342 0.44269 -0.0594814 -0.0427481 0.442672 -0.0595767 -0.04277 0.441695 -0.0595333 -0.0398356 0.4419 -0.0597621 -0.0389191 0.442138 -0.0595992 -0.0385151 0.443709 -0.0598222 -0.0438106 0.44247 -0.0598587 -0.0429841 0.442593 -0.0597491 -0.0428566 0.441801 -0.0598031 -0.0416756 0.44152 -0.059867 -0.0402805 0.441638 -0.0600422 -0.0388229 0.442466 -0.0600969 -0.0375821 0.443706 -0.0601335 -0.0367526 0.445169 -0.0601121 -0.0365275 0.446804 0.0596662 -0.0371707 0.445169 0.0599301 -0.0367016 0.44826 0.0599005 -0.0428253 0.448696 0.0599132 -0.0417465 0.448278 0.0601212 -0.0377701 0.447872 0.0600969 -0.0375821 0.449077 0.0599741 -0.0411398 0.448864 0.0599445 -0.0418175 0.446855 0.0601697 -0.0366597 0.446632 0.0601334 -0.0367526 0.447644 0.0596353 -0.0377901 0.446524 0.0598542 -0.0370012 0.447644 0.0593883 -0.0427398 0.447648 0.0594813 -0.0427481 0.4482 0.0594245 -0.0420148 0.446562 0.0597129 -0.0436447 0.445169 0.0595335 -0.0438051 0.446519 0.0595398 -0.0435342 0.447666 0.0595766 -0.04277 0.448537 0.0598031 -0.0416756 0.448433 0.0596318 -0.0416252 0.447752 0.0599851 -0.0376967 0.447672 0.0598173 -0.0377698 0.446568 0.0600213 -0.0369032 0.446508 0.0596731 -0.0370314 0.446508 0.0593504 -0.0434985 0.446919 0.0593605 -0.0432959 0.448409 0.0595373 -0.0416111 0.445169 0.0593371 -0.043765 0.445169 0.0595268 -0.0438024 0.44651 0.059444 -0.0435073 0.448677 0.0596033 -0.040269 0.448704 0.0596969 -0.0402731 0.448437 0.059762 -0.0389191 0.448402 0.0595786 -0.0389256 0.4482 0.0595991 -0.0385151 0.446629 0.0598222 -0.0438106 0.445169 0.0596983 -0.0439192 0.447745 0.059749 -0.0428566 0.447867 0.0598586 -0.0429841 0.448988 0.0599776 -0.0402853 0.448817 0.0598669 -0.0402805 0.448699 0.0600421 -0.0388229 0.448542 0.0599308 -0.0388831 0.438935 0.0224218 0.084735 0.438973 0.0224264 0.0849264 0.43896 0.022 0.084735 0.438491 0.02025 0.084735 0.437781 0.0193802 0.084735 0.437807 0.0193517 0.0849264 0.434614 0.0185647 0.0849264 0.436298 0.0186017 0.084735 0.43371 0.0189689 0.084735 0.433139 0.0193802 0.084735 0.432429 0.02025 0.084735 0.433114 0.0193517 0.0849264 0.43196 0.022 0.084735 0.43371 0.025031 0.084735 0.43546 0.025538 0.0849264 0.438372 0.0240098 0.0849264 0.438341 0.0239882 0.084735 0.433816 0.0251328 0.0849264 0.432459 0.0240714 0.0850886 0.432549 0.0240098 0.0849264 0.431948 0.0224264 0.0849264 0.43184 0.0224395 0.0850886 0.432152 0.0207453 0.0849264 0.432051 0.0207069 0.0850886 0.434588 0.0184595 0.0850886 0.436307 0.0185647 0.0849264 0.43887 0.0207069 0.0850886 0.438768 0.0207453 0.0849264 0.438461 0.0240714 0.0850886 0.437155 0.0252287 0.0850886 0.437105 0.0251328 0.0849264 0.43546 0.0256464 0.0850886 0.433766 0.0252287 0.0850886 0.431679 0.022459 0.085197 0.431899 0.0206494 0.085197 0.432935 0.0191491 0.085197 0.433042 0.0192706 0.0850886 0.434549 0.018302 0.085197 0.436333 0.0184595 0.0850886 0.436372 0.018302 0.085197 0.437986 0.0191491 0.085197 0.437878 0.0192706 0.0850886 0.43908 0.0224395 0.0850886 0.439241 0.022459 0.085197 0.43723 0.0253724 0.085197 0.43546 0.0258086 0.085197 0.43369 0.0253724 0.085197 0.432326 0.0241635 0.085197 0.43172 0.0205815 0.085235 0.432808 0.0190059 0.085235 0.434503 0.0181162 0.085235 0.438113 0.0190059 0.085235 0.4392 0.0205815 0.085235 0.439021 0.0206494 0.085197 0.438595 0.0241635 0.085197 0.438491 -0.02025 0.084735 0.438935 -0.0215782 0.084735 0.438973 -0.0215736 0.0849264 0.438768 -0.0232547 0.0849264 0.437807 -0.0246483 0.0849264 0.438491 -0.02375 0.084735 0.433114 -0.0246483 0.0849264 0.434614 -0.0254353 0.0849264 0.43721 -0.0250311 0.084735 0.436307 -0.0254353 0.0849264 0.434623 -0.0253983 0.084735 0.432429 -0.02375 0.084735 0.43196 -0.022 0.084735 0.431986 -0.0215782 0.084735 0.432549 -0.0199902 0.0849264 0.433816 -0.0188672 0.0849264 0.43371 -0.018969 0.084735 0.433834 -0.0189009 0.084735 0.43546 -0.0185 0.084735 0.43546 -0.018462 0.0849264 0.43721 -0.018969 0.084735 0.432459 -0.0199286 0.0850886 0.431948 -0.0215736 0.0849264 0.432051 -0.0232931 0.0850886 0.432152 -0.0232547 0.0849264 0.433042 -0.0247294 0.0850886 0.436333 -0.0255405 0.0850886 0.437878 -0.0247294 0.0850886 0.43908 -0.0215605 0.0850886 0.438372 -0.0199902 0.0849264 0.437155 -0.0187713 0.0850886 0.437105 -0.0188672 0.0849264 0.433766 -0.0187713 0.0850886 0.432326 -0.0198365 0.085197 0.43184 -0.0215605 0.0850886 0.434549 -0.025698 0.085197 0.434588 -0.0255405 0.0850886 0.437986 -0.0248509 0.085197 0.439021 -0.0233506 0.085197 0.43887 -0.0232931 0.0850886 0.438461 -0.0199286 0.0850886 0.43723 -0.0186276 0.085197 0.43546 -0.0181914 0.085197 0.43546 -0.0183536 0.0850886 0.43369 -0.0186276 0.085197 0.431489 -0.0215179 0.085235 0.431679 -0.021541 0.085197 0.431899 -0.0233506 0.085197 0.432935 -0.0248509 0.085197 0.432808 -0.0249941 0.085235 0.436372 -0.025698 0.085197 0.439241 -0.021541 0.085197 0.438752 -0.0197278 0.085235 0.438595 -0.0198365 0.085197 0.437319 -0.0184582 0.085235 0.43546 -0.018 0.085235 0.43599 0.0225735 -0.0854563 0.435509 0.02125 -0.085265 0.435509 0.02475 -0.085265 0.434824 0.0256482 -0.0854563 0.434799 0.0256197 -0.085265 0.434228 0.026031 -0.085265 0.430728 0.026031 -0.085265 0.433324 0.0264352 -0.0854563 0.432478 0.0265 -0.085265 0.431631 0.0264352 -0.0854563 0.43164 0.0263983 -0.085265 0.429447 0.02475 -0.085265 0.42917 0.0242546 -0.0854563 0.428978 0.023 -0.085265 0.428965 0.0225735 -0.0854563 0.429447 0.02125 -0.085265 0.434104 0.0199009 -0.085265 0.430833 0.0198672 -0.0854563 0.429566 0.0209901 -0.0854563 0.429068 0.024293 -0.0856185 0.430131 0.0256482 -0.0854563 0.43335 0.0265404 -0.0856185 0.435786 0.0242546 -0.0854563 0.435887 0.024293 -0.0856185 0.436098 0.0225604 -0.0856185 0.435389 0.0209901 -0.0854563 0.434122 0.0198672 -0.0854563 0.432478 0.0193535 -0.0856185 0.432478 0.0194619 -0.0854563 0.430783 0.0197712 -0.0856185 0.429477 0.0209285 -0.0856185 0.428858 0.0225604 -0.0856185 0.43006 0.0257294 -0.0856185 0.431566 0.0266979 -0.0857269 0.431605 0.0265404 -0.0856185 0.433389 0.0266979 -0.0857269 0.435003 0.0258508 -0.0857269 0.434896 0.0257294 -0.0856185 0.436259 0.0225409 -0.0857269 0.435612 0.0208364 -0.0857269 0.435479 0.0209285 -0.0856185 0.434172 0.0197712 -0.0856185 0.430708 0.0196276 -0.0857269 0.432478 0.0191913 -0.0857269 0.429343 0.0208364 -0.0857269 0.428697 0.0225409 -0.0857269 0.428917 0.0243505 -0.0857269 0.43152 0.0268837 -0.085765 0.429952 0.0258508 -0.0857269 0.436218 0.0244184 -0.085765 0.436039 0.0243505 -0.0857269 0.43577 0.0207277 -0.085765 0.434248 0.0196276 -0.0857269 0.435952 -0.0234219 -0.085265 0.435978 -0.023 -0.085265 0.435786 -0.0217454 -0.0854563 0.434824 -0.0203518 -0.0854563 0.435509 -0.02125 -0.085265 0.433315 -0.0196017 -0.085265 0.43164 -0.0196017 -0.085265 0.429447 -0.02125 -0.085265 0.42917 -0.0217454 -0.0854563 0.429205 -0.0217589 -0.085265 0.428978 -0.023 -0.085265 0.430728 -0.0260311 -0.085265 0.432478 -0.0265381 -0.0854563 0.434122 -0.0261328 -0.0854563 0.434104 -0.0260991 -0.085265 0.435509 -0.02475 -0.085265 0.430833 -0.0261328 -0.0854563 0.429566 -0.0250099 -0.0854563 0.429477 -0.0250715 -0.0856185 0.428965 -0.0234265 -0.0854563 0.429068 -0.021707 -0.0856185 0.430131 -0.0203518 -0.0854563 0.43006 -0.0202706 -0.0856185 0.431631 -0.0195648 -0.0854563 0.431605 -0.0194596 -0.0856185 0.433324 -0.0195648 -0.0854563 0.434896 -0.0202706 -0.0856185 0.43599 -0.0234265 -0.0854563 0.436098 -0.0234396 -0.0856185 0.435479 -0.0250715 -0.0856185 0.435389 -0.0250099 -0.0854563 0.434172 -0.0262288 -0.0856185 0.432478 -0.0266465 -0.0856185 0.430783 -0.0262288 -0.0856185 0.430708 -0.0263724 -0.0857269 0.429343 -0.0251636 -0.0857269 0.428858 -0.0234396 -0.0856185 0.428917 -0.0216495 -0.0857269 0.43335 -0.0194596 -0.0856185 0.435887 -0.021707 -0.0856185 0.436039 -0.0216495 -0.0857269 0.436259 -0.0234591 -0.0857269 0.435612 -0.0251636 -0.0857269 0.432478 -0.0268087 -0.0857269 0.429186 -0.0252723 -0.085765 0.428697 -0.0234591 -0.0857269 0.428738 -0.0215816 -0.085765 0.429825 -0.020006 -0.085765 0.429952 -0.0201492 -0.0857269 0.43152 -0.0191163 -0.085765 0.431566 -0.0193021 -0.0857269 0.433389 -0.0193021 -0.0857269 0.433435 -0.0191163 -0.085765 0.435003 -0.0201492 -0.0857269 0.43577 -0.0252723 -0.085765 0.434248 -0.0263724 -0.0857269 0.430619 -0.0265419 -0.085765 0.432478 -0.02 -0.083265 0.431103 -0.0206185 -0.083198 0.42988 -0.0215 -0.083265 0.429728 -0.023 -0.083198 0.429478 -0.023 -0.083265 0.431103 -0.0253816 -0.083198 0.430978 -0.0255981 -0.083265 0.433853 -0.0253816 -0.083198 0.433978 -0.0255981 -0.083265 0.435076 -0.0245 -0.083265 0.434859 -0.024375 -0.083198 0.435478 -0.023 -0.083265 0.433853 -0.0206185 -0.083198 0.433978 -0.020402 -0.083265 0.430255 -0.0217165 -0.083015 0.430096 -0.021625 -0.083198 0.429911 -0.023 -0.083015 0.430096 -0.024375 -0.083198 0.431194 -0.0252231 -0.083015 0.432478 -0.025567 -0.083015 0.432478 -0.02575 -0.083198 0.433761 -0.0252231 -0.083015 0.435228 -0.023 -0.083198 0.433761 -0.020777 -0.083015 0.434859 -0.021625 -0.083198 0.432478 -0.0204331 -0.083015 0.432478 -0.02025 -0.083198 0.431194 -0.020777 -0.083015 0.430313 -0.02175 -0.082765 0.429978 -0.023 -0.082765 0.430255 -0.0242835 -0.083015 0.432478 -0.0255 -0.082765 0.433728 -0.0251651 -0.082765 0.434701 -0.0242835 -0.083015 0.435045 -0.023 -0.083015 0.434978 -0.023 -0.082765 0.434701 -0.0217165 -0.083015 0.432478 -0.0205 -0.082765 0.431228 -0.020835 -0.082765 0.42988 0.0245 -0.083265 0.429728 0.023 -0.083198 0.430978 0.0204019 -0.083265 0.431103 0.0206184 -0.083198 0.433978 0.0204019 -0.083265 0.434859 0.021625 -0.083198 0.435478 0.023 -0.083265 0.435228 0.023 -0.083198 0.435076 0.0245 -0.083265 0.432478 0.02575 -0.083198 0.433978 0.025598 -0.083265 0.431103 0.0253815 -0.083198 0.430255 0.0242835 -0.083015 0.430096 0.024375 -0.083198 0.430255 0.0217165 -0.083015 0.430096 0.021625 -0.083198 0.431194 0.0207769 -0.083015 0.432478 0.020433 -0.083015 0.432478 0.02025 -0.083198 0.433761 0.0207769 -0.083015 0.433853 0.0206184 -0.083198 0.434701 0.0217165 -0.083015 0.434701 0.0242835 -0.083015 0.434859 0.024375 -0.083198 0.433853 0.0253815 -0.083198 0.431194 0.025223 -0.083015 0.432478 0.0255669 -0.083015 0.429911 0.023 -0.083015 0.432478 0.0205 -0.082765 0.434643 0.02175 -0.082765 0.435045 0.023 -0.083015 0.434978 0.023 -0.082765 0.434643 0.02425 -0.082765 0.433761 0.025223 -0.083015 0.432478 0.0255 -0.082765 0.43546 -0.025 0.083235 0.432862 -0.0205 0.083235 0.433079 -0.020625 0.083168 0.43396 -0.019402 0.083235 0.43546 -0.01925 0.083168 0.437842 -0.020625 0.083168 0.43846 -0.022 0.083235 0.437842 -0.023375 0.083168 0.438058 -0.0235 0.083235 0.436835 -0.0243816 0.083168 0.43696 -0.0245981 0.083235 0.43546 -0.02475 0.083168 0.434085 -0.0243816 0.083168 0.433079 -0.023375 0.083168 0.43271 -0.022 0.083168 0.434085 -0.0196185 0.083168 0.436835 -0.0196185 0.083168 0.438027 -0.022 0.082985 0.43821 -0.022 0.083168 0.437683 -0.0232835 0.082985 0.436744 -0.0242231 0.082985 0.43546 -0.024567 0.082985 0.434177 -0.0242231 0.082985 0.433237 -0.0232835 0.082985 0.432893 -0.022 0.082985 0.433295 -0.02075 0.082735 0.433237 -0.0207165 0.082985 0.434177 -0.019777 0.082985 0.43546 -0.0194331 0.082985 0.43671 -0.019835 0.082735 0.436744 -0.019777 0.082985 0.437625 -0.02075 0.082735 0.437683 -0.0207165 0.082985 0.437625 -0.02325 0.082735 0.43671 -0.0241651 0.082735 0.43271 0.022 0.083168 0.433079 0.023375 0.083168 0.43546 0.02475 0.083168 0.436835 0.0243815 0.083168 0.437842 0.023375 0.083168 0.43696 0.024598 0.083235 0.438058 0.0205 0.083235 0.436835 0.0196184 0.083168 0.43696 0.0194019 0.083235 0.434085 0.0196184 0.083168 0.433079 0.020625 0.083168 0.434177 0.024223 0.082985 0.434085 0.0243815 0.083168 0.436744 0.024223 0.082985 0.437683 0.0232835 0.082985 0.43821 0.022 0.083168 0.438027 0.022 0.082985 0.437842 0.020625 0.083168 0.437683 0.0207165 0.082985 0.43546 0.019433 0.082985 0.43546 0.01925 0.083168 0.434177 0.0197769 0.082985 0.433295 0.02075 0.082735 0.433237 0.0207165 0.082985 0.432893 0.022 0.082985 0.43296 0.022 0.082735 0.433295 0.02325 0.082735 0.433237 0.0232835 0.082985 0.43421 0.024165 0.082735 0.43546 0.0245669 0.082985 0.43546 0.0245 0.082735 0.43671 0.024165 0.082735 0.436744 0.0197769 0.082985 0.43671 0.0198349 0.082735 0.43546 0.0195 0.082735 0.443004 0.0575 -0.039015 0.443885 0.05775 -0.0380419 0.445169 0.0575 -0.037765 0.447392 0.05775 -0.0389815 0.447669 0.0575 -0.040265 0.447736 0.05775 -0.040265 0.446419 0.0575 -0.04243 0.445169 0.0575 -0.042765 0.442946 0.05775 -0.0415485 0.443004 0.0575 -0.041515 0.442602 0.05775 -0.040265 0.442946 0.05775 -0.0389815 0.445169 0.05775 -0.037698 0.446452 0.05775 -0.0380419 0.446544 0.057933 -0.0378834 0.44755 0.057933 -0.03889 0.447919 0.057933 -0.040265 0.44755 0.057933 -0.04164 0.447392 0.05775 -0.0415485 0.445169 0.057933 -0.043015 0.446452 0.05775 -0.042488 0.445169 0.05775 -0.042832 0.443885 0.05775 -0.042488 0.442787 0.057933 -0.04164 0.442419 0.057933 -0.040265 0.442787 0.057933 -0.03889 0.443669 0.058 -0.0376669 0.443794 0.057933 -0.0378834 0.445169 0.058 -0.037265 0.445169 0.057933 -0.037515 0.447767 0.058 -0.038765 0.448169 0.058 -0.040265 0.446669 0.058 -0.042863 0.446544 0.057933 -0.0426465 0.445169 0.058 -0.043265 0.443669 0.058 -0.042863 0.443794 0.057933 -0.0426465 0.442169 0.058 -0.040265 0.446586 0.06145 0.0525185 0.448809 0.06145 0.053802 0.451032 0.06145 0.0525185 0.450974 0.0612 0.052485 0.451376 0.06145 0.051235 0.451309 0.0612 0.051235 0.450059 0.0612 0.04907 0.450092 0.06145 0.049012 0.448809 0.0612 0.048735 0.447559 0.0612 0.04907 0.446644 0.0612 0.049985 0.446242 0.06145 0.051235 0.447434 0.061633 0.0536166 0.447525 0.06145 0.0534581 0.448809 0.061633 0.053985 0.450092 0.06145 0.0534581 0.45119 0.061633 0.05261 0.451559 0.061633 0.051235 0.451032 0.06145 0.0499515 0.450184 0.061633 0.0488535 0.448809 0.061633 0.048485 0.448809 0.06145 0.048668 0.447525 0.06145 0.049012 0.446586 0.06145 0.0499515 0.446427 0.061633 0.04986 0.446059 0.061633 0.051235 0.446427 0.061633 0.05261 0.447309 0.0617 0.0538331 0.450184 0.061633 0.0536166 0.45119 0.061633 0.04986 0.447309 0.0617 0.048637 0.447434 0.061633 0.0488535 0.446211 0.0617 0.052735 0.450974 -0.0612 0.052485 0.450092 -0.06145 0.0534581 0.450059 -0.0612 0.0534001 0.448809 -0.06145 0.053802 0.448809 -0.0612 0.053735 0.446586 -0.06145 0.0525185 0.446309 -0.0612 0.051235 0.446242 -0.06145 0.051235 0.446586 -0.06145 0.0499515 0.446644 -0.0612 0.049985 0.447525 -0.06145 0.049012 0.447559 -0.0612 0.04907 0.448809 -0.0612 0.048735 0.448809 -0.06145 0.048668 0.450092 -0.06145 0.049012 0.451376 -0.06145 0.051235 0.451309 -0.0612 0.051235 0.451032 -0.06145 0.0525185 0.450184 -0.0616331 0.0536166 0.448809 -0.0616331 0.053985 0.447434 -0.0616331 0.0536166 0.447525 -0.06145 0.0534581 0.447434 -0.0616331 0.0488535 0.451032 -0.06145 0.0499515 0.45119 -0.0616331 0.05261 0.448809 -0.0617 0.054235 0.447309 -0.0617 0.0538331 0.446211 -0.0617 0.052735 0.446427 -0.0616331 0.05261 0.446059 -0.0616331 0.051235 0.445809 -0.0617 0.051235 0.446427 -0.0616331 0.04986 0.448809 -0.0617 0.048235 0.448809 -0.0616331 0.048485 0.450309 -0.0617 0.048637 0.450184 -0.0616331 0.0488535 0.45119 -0.0616331 0.04986 0.451559 -0.0616331 0.051235 0.447669 -0.0575 -0.040265 0.446419 -0.0575 -0.0380999 0.446452 -0.05775 -0.0380419 0.445169 -0.05775 -0.037698 0.443919 -0.0575 -0.0380999 0.443004 -0.0575 -0.039015 0.442946 -0.05775 -0.0415485 0.445169 -0.0575 -0.042765 0.447392 -0.05775 -0.0415485 0.446419 -0.0575 -0.04243 0.447334 -0.0575 -0.041515 0.447736 -0.05775 -0.040265 0.44755 -0.0579331 -0.03889 0.447392 -0.05775 -0.0389815 0.446544 -0.0579331 -0.0378834 0.443794 -0.0579331 -0.0378834 0.443885 -0.05775 -0.0380419 0.442787 -0.0579331 -0.03889 0.442946 -0.05775 -0.0389815 0.442602 -0.05775 -0.040265 0.442787 -0.0579331 -0.04164 0.443885 -0.05775 -0.042488 0.443794 -0.0579331 -0.0426465 0.445169 -0.05775 -0.042832 0.446452 -0.05775 -0.042488 0.447919 -0.0579331 -0.040265 0.445169 -0.0579331 -0.037515 0.443669 -0.058 -0.0376669 0.442571 -0.058 -0.038765 0.442419 -0.0579331 -0.040265 0.442571 -0.058 -0.041765 0.445169 -0.058 -0.043265 0.445169 -0.0579331 -0.043015 0.446544 -0.0579331 -0.0426465 0.446669 -0.058 -0.042863 0.44755 -0.0579331 -0.04164 0.447767 -0.058 -0.038765 0.444462 0.0582 0.0523997 0.445627 0.0582 0.054417 0.446592 0.05795 0.0550741 0.447644 0.0582 0.0555817 0.449956 0.05795 0.055517 0.453091 0.05795 0.0523824 0.453155 0.0582 0.0523997 0.453309 0.0582 0.051235 0.453155 0.0582 0.0500703 0.452706 0.0582 0.048985 0.451991 0.0582 0.048053 0.449956 0.05795 0.0469531 0.451059 0.0582 0.0473379 0.448809 0.0582 0.046735 0.446592 0.05795 0.0473959 0.446559 0.0582 0.0473379 0.445627 0.0582 0.048053 0.444912 0.0582 0.048985 0.444376 0.05795 0.051235 0.444527 0.05795 0.0523824 0.445128 0.0577669 0.05336 0.44497 0.05795 0.0534515 0.445674 0.05795 0.0543696 0.447661 0.05795 0.055517 0.448809 0.05795 0.055668 0.451025 0.05795 0.0550741 0.451814 0.0577669 0.0542402 0.451943 0.05795 0.0543696 0.452648 0.05795 0.0534515 0.453242 0.05795 0.051235 0.453091 0.05795 0.0500877 0.452648 0.05795 0.0490185 0.451943 0.05795 0.0481004 0.450934 0.0577669 0.0475544 0.451025 0.05795 0.0473959 0.449909 0.0577669 0.0471298 0.448809 0.0577669 0.046985 0.448809 0.05795 0.046802 0.447709 0.0577669 0.0471298 0.447661 0.05795 0.0469531 0.445804 0.0577669 0.0482298 0.445674 0.05795 0.0481004 0.44497 0.05795 0.0490185 0.444527 0.05795 0.0500877 0.444704 0.0577669 0.050135 0.444559 0.0577669 0.051235 0.444704 0.0577669 0.052335 0.445345 0.0577 0.053235 0.445804 0.0577669 0.0542402 0.446809 0.0577 0.0546991 0.446684 0.0577669 0.0549156 0.447774 0.0577 0.0550987 0.447709 0.0577669 0.0553402 0.448809 0.0577 0.055235 0.448809 0.0577669 0.055485 0.449909 0.0577669 0.0553402 0.450809 0.0577 0.0546991 0.450934 0.0577669 0.0549156 0.452489 0.0577669 0.05336 0.452672 0.0577 0.0522703 0.452914 0.0577669 0.052335 0.452809 0.0577 0.051235 0.453059 0.0577669 0.051235 0.452672 0.0577 0.0501998 0.452914 0.0577669 0.050135 0.452489 0.0577669 0.04911 0.451637 0.0577 0.0484066 0.451814 0.0577669 0.0482298 0.450809 0.0577 0.0477709 0.449844 0.0577 0.0473713 0.448809 0.0577 0.047235 0.447774 0.0577 0.0473713 0.446809 0.0577 0.0477709 0.446684 0.0577669 0.0475544 0.44598 0.0577 0.0484066 0.445128 0.0577669 0.04911 0.449451 -0.05425 -0.0391176 0.449515 -0.0545 -0.0391003 0.448351 -0.0545 -0.037083 0.447419 -0.0545 -0.0363679 0.446333 -0.0545 -0.0359183 0.444021 -0.05425 -0.035983 0.444004 -0.0545 -0.0359183 0.442919 -0.0545 -0.0363679 0.441987 -0.0545 -0.037083 0.441272 -0.0545 -0.038015 0.44133 -0.05425 -0.0380485 0.440669 -0.0545 -0.040265 0.441272 -0.0545 -0.042515 0.442034 -0.05425 -0.0433996 0.441987 -0.0545 -0.043447 0.442919 -0.0545 -0.0441621 0.444021 -0.05425 -0.0445469 0.445169 -0.05425 -0.044698 0.446316 -0.05425 -0.0445469 0.447385 -0.05425 -0.0441041 0.447419 -0.0545 -0.0441621 0.449008 -0.05425 -0.0424815 0.449066 -0.0545 -0.042515 0.449515 -0.0545 -0.0414297 0.449451 -0.05425 -0.0414123 0.449602 -0.05425 -0.040265 0.449274 -0.054067 -0.039165 0.448849 -0.054067 -0.03814 0.449008 -0.05425 -0.0380485 0.448303 -0.05425 -0.0371304 0.447385 -0.05425 -0.0364259 0.446316 -0.05425 -0.035983 0.445169 -0.05425 -0.035832 0.445169 -0.054067 -0.036015 0.442952 -0.05425 -0.0364259 0.442164 -0.054067 -0.0372598 0.441488 -0.054067 -0.03814 0.442034 -0.05425 -0.0371304 0.441064 -0.054067 -0.039165 0.440887 -0.05425 -0.0391176 0.440736 -0.05425 -0.040265 0.440887 -0.05425 -0.0414123 0.44133 -0.05425 -0.0424815 0.442164 -0.054067 -0.0432702 0.442952 -0.05425 -0.0441041 0.444069 -0.054067 -0.0443702 0.445169 -0.054067 -0.044515 0.448174 -0.054067 -0.0432702 0.448303 -0.05425 -0.0433996 0.448849 -0.054067 -0.04239 0.449274 -0.054067 -0.041365 0.449419 -0.054067 -0.040265 0.448174 -0.054067 -0.0372598 0.447294 -0.054067 -0.0365844 0.446269 -0.054067 -0.0361598 0.443169 -0.054 -0.0368009 0.444069 -0.054067 -0.0361598 0.443044 -0.054067 -0.0365844 0.441169 -0.054 -0.040265 0.440919 -0.054067 -0.040265 0.441064 -0.054067 -0.041365 0.441488 -0.054067 -0.04239 0.44234 -0.054 -0.0430934 0.443169 -0.054 -0.0437291 0.443044 -0.054067 -0.0439456 0.444133 -0.054 -0.0441287 0.445169 -0.054 -0.044265 0.446204 -0.054 -0.0441287 0.447169 -0.054 -0.0437291 0.446269 -0.054067 -0.0443702 0.447294 -0.054067 -0.0439456 0.447997 -0.054 -0.0430934 0.448633 -0.054 -0.042265 0.449169 -0.054 -0.040265 0.453155 -0.0582 0.0523997 0.453091 -0.05795 0.0523824 0.452648 -0.05795 0.0534515 0.451943 -0.05795 0.0543696 0.449973 -0.0582 0.0555817 0.449956 -0.05795 0.055517 0.448809 -0.0582 0.055735 0.446592 -0.05795 0.0550741 0.444527 -0.05795 0.0523824 0.444309 -0.0582 0.051235 0.444462 -0.0582 0.0500703 0.446592 -0.05795 0.0473959 0.446559 -0.0582 0.0473379 0.447661 -0.05795 0.0469531 0.449956 -0.05795 0.0469531 0.451059 -0.0582 0.0473379 0.451991 -0.0582 0.048053 0.453155 -0.0582 0.0500703 0.453309 -0.0582 0.051235 0.452489 -0.057767 0.05336 0.451025 -0.05795 0.0550741 0.450934 -0.057767 0.0549156 0.449909 -0.057767 0.0553402 0.448809 -0.05795 0.055668 0.448809 -0.057767 0.055485 0.447661 -0.05795 0.055517 0.446684 -0.057767 0.0549156 0.445674 -0.05795 0.0543696 0.44497 -0.05795 0.0534515 0.444376 -0.05795 0.051235 0.444704 -0.057767 0.050135 0.444527 -0.05795 0.0500877 0.44497 -0.05795 0.0490185 0.445804 -0.057767 0.0482298 0.445674 -0.05795 0.0481004 0.446684 -0.057767 0.0475544 0.447709 -0.057767 0.0471298 0.448809 -0.05795 0.046802 0.448809 -0.057767 0.046985 0.449909 -0.057767 0.0471298 0.450934 -0.057767 0.0475544 0.451025 -0.05795 0.0473959 0.451814 -0.057767 0.0482298 0.451943 -0.05795 0.0481004 0.452648 -0.05795 0.0490185 0.452914 -0.057767 0.050135 0.453091 -0.05795 0.0500877 0.453242 -0.05795 0.051235 0.453059 -0.057767 0.051235 0.452914 -0.057767 0.052335 0.451637 -0.0577 0.0540635 0.451814 -0.057767 0.0542402 0.450809 -0.0577 0.0546991 0.449844 -0.0577 0.0550987 0.448809 -0.0577 0.055235 0.447709 -0.057767 0.0553402 0.447774 -0.0577 0.0550987 0.44598 -0.0577 0.0540635 0.445804 -0.057767 0.0542402 0.445128 -0.057767 0.05336 0.444704 -0.057767 0.052335 0.444809 -0.0577 0.051235 0.444559 -0.057767 0.051235 0.445345 -0.0577 0.049235 0.445128 -0.057767 0.04911 0.446809 -0.0577 0.0477709 0.448809 -0.0577 0.047235 0.451637 -0.0577 0.0484066 0.452273 -0.0577 0.049235 0.452489 -0.057767 0.04911 0.452672 -0.0577 0.0522703 0.440822 0.0545 -0.0391003 0.441272 0.0545 -0.038015 0.441987 0.0545 -0.037083 0.442952 0.05425 -0.0364259 0.444004 0.0545 -0.0359183 0.444021 0.05425 -0.035983 0.445169 0.05425 -0.035832 0.446333 0.0545 -0.0359183 0.447419 0.0545 -0.0363679 0.447385 0.05425 -0.0364259 0.449008 0.05425 -0.0380485 0.449066 0.0545 -0.038015 0.449451 0.05425 -0.0391176 0.449515 0.0545 -0.0391003 0.449669 0.0545 -0.040265 0.449515 0.0545 -0.0414297 0.449008 0.05425 -0.0424815 0.449066 0.0545 -0.042515 0.448303 0.05425 -0.0433996 0.448351 0.0545 -0.043447 0.447385 0.05425 -0.0441041 0.447419 0.0545 -0.0441621 0.446333 0.0545 -0.0446116 0.444021 0.05425 -0.0445469 0.442919 0.0545 -0.0441621 0.441272 0.0545 -0.042515 0.440822 0.0545 -0.0414297 0.440736 0.05425 -0.040265 0.440669 0.0545 -0.040265 0.440887 0.05425 -0.0391176 0.44133 0.05425 -0.0380485 0.441488 0.0540669 -0.03814 0.442034 0.05425 -0.0371304 0.443044 0.0540669 -0.0365844 0.444069 0.0540669 -0.0361598 0.446269 0.0540669 -0.0361598 0.446316 0.05425 -0.035983 0.448303 0.05425 -0.0371304 0.448174 0.0540669 -0.0372598 0.448849 0.0540669 -0.03814 0.449274 0.0540669 -0.039165 0.449602 0.05425 -0.040265 0.449419 0.0540669 -0.040265 0.449451 0.05425 -0.0414123 0.448174 0.0540669 -0.0432702 0.446316 0.05425 -0.0445469 0.445169 0.05425 -0.044698 0.442952 0.05425 -0.0441041 0.442164 0.0540669 -0.0432702 0.442034 0.05425 -0.0433996 0.441488 0.0540669 -0.04239 0.44133 0.05425 -0.0424815 0.440887 0.05425 -0.0414123 0.441064 0.0540669 -0.041365 0.440919 0.0540669 -0.040265 0.441064 0.0540669 -0.039165 0.441705 0.054 -0.038265 0.442164 0.0540669 -0.0372598 0.443169 0.054 -0.0368009 0.444133 0.054 -0.0364013 0.446204 0.054 -0.0364013 0.445169 0.0540669 -0.036015 0.447294 0.0540669 -0.0365844 0.447169 0.054 -0.0368009 0.447997 0.054 -0.0374365 0.448633 0.054 -0.038265 0.449169 0.054 -0.040265 0.449032 0.054 -0.0413002 0.449274 0.0540669 -0.041365 0.448849 0.0540669 -0.04239 0.447169 0.054 -0.0437291 0.447294 0.0540669 -0.0439456 0.446204 0.054 -0.0441287 0.446269 0.0540669 -0.0443702 0.445169 0.0540669 -0.044515 0.444133 0.054 -0.0441287 0.444069 0.0540669 -0.0443702 0.443044 0.0540669 -0.0439456 0.44234 0.054 -0.0430934 0.441705 0.054 -0.042265 0.441305 0.054 -0.0413002 0.441169 0.054 -0.040265 0.441305 0.054 -0.0392297 0.434399 0.0180397 0.0784154 0.434477 0.0183294 0.078335 0.43356 0.0187091 0.078335 0.432773 0.019313 0.078335 0.43191 0.01995 0.0784154 0.43136 0.022 0.0784154 0.4315 0.0230611 0.0784154 0.43191 0.02405 0.0784154 0.432169 0.0239 0.078335 0.432773 0.024687 0.078335 0.432561 0.0248991 0.0784154 0.43356 0.0252909 0.078335 0.436444 0.0256705 0.078335 0.43736 0.0252909 0.078335 0.43751 0.0255507 0.0784154 0.439011 0.02405 0.0784154 0.438751 0.0239 0.078335 0.43956 0.022 0.0784154 0.439131 0.0210164 0.078335 0.439011 0.01995 0.0784154 0.438147 0.019313 0.078335 0.43751 0.0184493 0.0784154 0.436444 0.0183294 0.078335 0.436522 0.0180397 0.0784154 0.43546 0.0179 0.0784154 0.434342 0.0178275 0.078635 0.43341 0.0184493 0.0784154 0.432561 0.0191008 0.0784154 0.4315 0.0209388 0.0784154 0.431288 0.020882 0.078635 0.431719 0.0241598 0.078635 0.433301 0.0257409 0.078635 0.43341 0.0255507 0.0784154 0.434399 0.0259603 0.0784154 0.434342 0.0261724 0.078635 0.43546 0.0263196 0.078635 0.43546 0.0261 0.0784154 0.436578 0.0261724 0.078635 0.436522 0.0259603 0.0784154 0.43762 0.0257409 0.078635 0.438515 0.0250544 0.078635 0.438359 0.0248991 0.0784154 0.439201 0.0241598 0.078635 0.439421 0.0230611 0.0784154 0.439421 0.0209388 0.0784154 0.438359 0.0191008 0.0784154 0.43546 0.0176803 0.078635 0.434322 0.0177499 0.078935 0.433301 0.0182591 0.078635 0.432406 0.0189455 0.078635 0.43165 0.0198 0.078935 0.431719 0.0198402 0.078635 0.43106 0.022 0.078935 0.431141 0.022 0.078635 0.431288 0.023118 0.078635 0.43121 0.0231388 0.078935 0.432349 0.0251112 0.078935 0.432406 0.0250544 0.078635 0.434322 0.02625 0.078935 0.43546 0.0264 0.078935 0.438572 0.0251112 0.078935 0.439633 0.023118 0.078635 0.43971 0.0231388 0.078935 0.43986 0.022 0.078935 0.43978 0.022 0.078635 0.439633 0.020882 0.078635 0.439201 0.0198402 0.078635 0.438515 0.0189455 0.078635 0.43766 0.0181894 0.078935 0.43762 0.0182591 0.078635 0.436578 0.0178275 0.078635 0.43546 0.0176 0.078935 0.434399 -0.0259603 0.0784154 0.43341 -0.0255507 0.0784154 0.432561 -0.0248992 0.0784154 0.432169 -0.0239 0.078335 0.43136 -0.022 0.0784154 0.43166 -0.022 0.078335 0.432773 -0.019313 0.078335 0.43356 -0.0187091 0.078335 0.43546 -0.0182 0.078335 0.436522 -0.0180397 0.0784154 0.43736 -0.0187091 0.078335 0.43751 -0.0184493 0.0784154 0.438147 -0.019313 0.078335 0.43956 -0.022 0.0784154 0.439421 -0.0230612 0.0784154 0.438751 -0.0239 0.078335 0.438359 -0.0248992 0.0784154 0.43736 -0.0252909 0.078335 0.43546 -0.0261 0.0784154 0.43546 -0.0258 0.078335 0.433301 -0.0257409 0.078635 0.432406 -0.0250545 0.078635 0.431719 -0.0241598 0.078635 0.43191 -0.02405 0.0784154 0.431288 -0.023118 0.078635 0.4315 -0.0230612 0.0784154 0.4315 -0.0209389 0.0784154 0.43191 -0.01995 0.0784154 0.432406 -0.0189456 0.078635 0.432561 -0.0191009 0.0784154 0.43341 -0.0184493 0.0784154 0.434342 -0.0178276 0.078635 0.434399 -0.0180397 0.0784154 0.43546 -0.0176804 0.078635 0.436578 -0.0178276 0.078635 0.43546 -0.0179 0.0784154 0.438359 -0.0191009 0.0784154 0.439011 -0.01995 0.0784154 0.439633 -0.020882 0.078635 0.439421 -0.0209389 0.0784154 0.439633 -0.023118 0.078635 0.439011 -0.02405 0.0784154 0.438515 -0.0250545 0.078635 0.43762 -0.0257409 0.078635 0.43751 -0.0255507 0.0784154 0.436522 -0.0259603 0.0784154 0.43546 -0.0263197 0.078635 0.434342 -0.0261725 0.078635 0.434322 -0.0262501 0.078935 0.43326 -0.0258106 0.078935 0.432349 -0.0251113 0.078935 0.43121 -0.0231388 0.078935 0.431141 -0.022 0.078635 0.431288 -0.020882 0.078635 0.431719 -0.0198402 0.078635 0.433301 -0.0182591 0.078635 0.434322 -0.01775 0.078935 0.43546 -0.0176 0.078935 0.43762 -0.0182591 0.078635 0.43766 -0.0181895 0.078935 0.438515 -0.0189456 0.078635 0.439201 -0.0198402 0.078635 0.43986 -0.022 0.078935 0.43978 -0.022 0.078635 0.439201 -0.0241598 0.078635 0.43766 -0.0258106 0.078935 0.436578 -0.0261725 0.078635 0.43546 -0.0264 0.078935 0.430578 0.0262909 -0.078365 0.428927 0.02505 -0.0784454 0.428807 0.0239835 -0.078365 0.428807 0.0220164 -0.078365 0.428927 0.02095 -0.0784454 0.429187 0.0211 -0.078365 0.430428 0.0194493 -0.0784454 0.430578 0.0197091 -0.078365 0.431494 0.0193294 -0.078365 0.433539 0.0190397 -0.0784454 0.434378 0.0197091 -0.078365 0.435769 0.0211 -0.078365 0.436028 0.02095 -0.0784454 0.436438 0.0219388 -0.0784454 0.436278 0.023 -0.078365 0.436148 0.0239835 -0.078365 0.436028 0.02505 -0.0784454 0.435769 0.0249 -0.078365 0.434528 0.0265507 -0.0784454 0.434378 0.0262909 -0.078365 0.432478 0.0271 -0.0784454 0.432478 0.0268 -0.078365 0.43136 0.0271724 -0.078665 0.431417 0.0269603 -0.0784454 0.430428 0.0265507 -0.0784454 0.429579 0.0258991 -0.0784454 0.428305 0.024118 -0.078665 0.428517 0.0240611 -0.0784454 0.428378 0.023 -0.0784454 0.428517 0.0219388 -0.0784454 0.428305 0.021882 -0.078665 0.428737 0.0208402 -0.078665 0.429579 0.0201008 -0.0784454 0.43136 0.0188275 -0.078665 0.431417 0.0190397 -0.0784454 0.432478 0.0189 -0.0784454 0.432478 0.0186803 -0.078665 0.433596 0.0188275 -0.078665 0.434528 0.0194493 -0.0784454 0.435532 0.0199455 -0.078665 0.435377 0.0201008 -0.0784454 0.43665 0.021882 -0.078665 0.436578 0.023 -0.0784454 0.436797 0.023 -0.078665 0.43665 0.024118 -0.078665 0.436438 0.0240611 -0.0784454 0.435377 0.0258991 -0.0784454 0.434637 0.0267409 -0.078665 0.433596 0.0271724 -0.078665 0.433539 0.0269603 -0.0784454 0.432478 0.0273196 -0.078665 0.430318 0.0267409 -0.078665 0.429423 0.0260544 -0.078665 0.428667 0.0252 -0.078965 0.428737 0.0251598 -0.078665 0.428228 0.0241388 -0.078965 0.428158 0.023 -0.078665 0.428228 0.0218612 -0.078965 0.429366 0.0198887 -0.078965 0.429423 0.0199455 -0.078665 0.430318 0.0192591 -0.078665 0.431339 0.0187499 -0.078965 0.432478 0.0186 -0.078965 0.433616 0.0187499 -0.078965 0.434637 0.0192591 -0.078665 0.436728 0.0218612 -0.078965 0.436219 0.0208402 -0.078665 0.436878 0.023 -0.078965 0.436728 0.0241388 -0.078965 0.436288 0.0252 -0.078965 0.436219 0.0251598 -0.078665 0.435532 0.0260544 -0.078665 0.435589 0.0261112 -0.078965 0.433616 0.02725 -0.078965 0.431417 -0.0190397 -0.0784454 0.429579 -0.0201009 -0.0784454 0.429791 -0.020313 -0.078365 0.428927 -0.02095 -0.0784454 0.429187 -0.0211 -0.078365 0.428517 -0.0219389 -0.0784454 0.428378 -0.023 -0.0784454 0.428678 -0.023 -0.078365 0.428927 -0.02505 -0.0784454 0.430578 -0.0262909 -0.078365 0.432478 -0.0271 -0.0784454 0.431494 -0.0266706 -0.078365 0.433539 -0.0269603 -0.0784454 0.432478 -0.0268 -0.078365 0.434378 -0.0262909 -0.078365 0.435165 -0.025687 -0.078365 0.435377 -0.0258992 -0.0784454 0.435769 -0.0249 -0.078365 0.436148 -0.0239836 -0.078365 0.436438 -0.0240612 -0.0784454 0.436278 -0.023 -0.078365 0.436438 -0.0219389 -0.0784454 0.436028 -0.02095 -0.0784454 0.435165 -0.020313 -0.078365 0.435377 -0.0201009 -0.0784454 0.434378 -0.0197091 -0.078365 0.432478 -0.0192 -0.078365 0.432478 -0.0189 -0.0784454 0.43136 -0.0188276 -0.078665 0.430428 -0.0194493 -0.0784454 0.429423 -0.0199456 -0.078665 0.428305 -0.021882 -0.078665 0.428517 -0.0240612 -0.0784454 0.428737 -0.0251598 -0.078665 0.429423 -0.0260545 -0.078665 0.429579 -0.0258992 -0.0784454 0.430428 -0.0265507 -0.0784454 0.43136 -0.0271725 -0.078665 0.431417 -0.0269603 -0.0784454 0.434528 -0.0265507 -0.0784454 0.436219 -0.0251598 -0.078665 0.436028 -0.02505 -0.0784454 0.43665 -0.024118 -0.078665 0.436578 -0.023 -0.0784454 0.43665 -0.021882 -0.078665 0.436219 -0.0208402 -0.078665 0.434528 -0.0194493 -0.0784454 0.433539 -0.0190397 -0.0784454 0.432478 -0.0186804 -0.078665 0.430318 -0.0192591 -0.078665 0.428737 -0.0208402 -0.078665 0.428078 -0.023 -0.078965 0.428158 -0.023 -0.078665 0.428305 -0.024118 -0.078665 0.428667 -0.0252 -0.078965 0.431339 -0.0272501 -0.078965 0.430318 -0.0267409 -0.078665 0.432478 -0.0274 -0.078965 0.432478 -0.0273197 -0.078665 0.433596 -0.0271725 -0.078665 0.434637 -0.0267409 -0.078665 0.435532 -0.0260545 -0.078665 0.435589 -0.0261113 -0.078965 0.436288 -0.0252 -0.078965 0.436878 -0.023 -0.078965 0.436728 -0.0218612 -0.078965 0.436797 -0.023 -0.078665 0.436288 -0.0208 -0.078965 0.435589 -0.0198888 -0.078965 0.435532 -0.0199456 -0.078665 0.434637 -0.0192591 -0.078665 0.433616 -0.01875 -0.078965 0.433596 -0.0188276 -0.078665 0.43546 0.0267923 0.0811979 0.430877 0.0238034 0.0812303 0.430788 0.0230664 0.0811979 0.430573 0.0226053 0.0812303 0.43546 0.0172076 0.0811979 0.433381 0.0176822 0.0811979 0.431714 0.019012 0.0811979 0.430887 0.0201726 0.0812303 0.43546 0.027 0.081235 0.43763 0.0265048 0.081235 0.43754 0.0263177 0.0811979 0.439369 0.0251174 0.081235 0.439207 0.0249879 0.0811979 0.440133 0.0230664 0.0811979 0.440335 0.0208874 0.081235 0.439369 0.0188825 0.081235 0.43546 0.017 0.081235 0.439786 0.0229873 0.0808427 0.4389 0.0247433 0.080635 0.43975 0.0229791 0.080635 0.439271 0.0242 0.080635 0.438929 0.0192335 0.0808427 0.439271 0.0198 0.080635 0.43975 0.0210209 0.080635 0.43986 0.022 0.080635 0.4389 0.0192566 0.080635 0.433535 0.0180023 0.0808427 0.43546 0.0175629 0.0808427 0.43546 0.0176 0.080635 0.437369 0.0180357 0.080635 0.43165 0.0198 0.080635 0.431991 0.0192335 0.0808427 0.43202 0.0192566 0.080635 0.433551 0.0180357 0.080635 0.431134 0.0229873 0.0808427 0.43106 0.022 0.080635 0.431991 0.0247664 0.0808427 0.43326 0.0258105 0.080635 0.437386 0.0259976 0.0808427 0.43546 0.026437 0.0808427 0.433535 0.0259976 0.0808427 0.433475 0.0261226 0.0810593 0.431714 0.0249879 0.0811979 0.431883 0.0248529 0.0810593 0.430788 0.0209336 0.0811979 0.430999 0.0209818 0.0810593 0.431883 0.019147 0.0810593 0.43546 0.0174242 0.0810593 0.43754 0.0176822 0.0811979 0.437446 0.0178774 0.0810593 0.439207 0.019012 0.0811979 0.439038 0.019147 0.0810593 0.440133 0.0209336 0.0811979 0.437446 0.0261226 0.0810593 0.433381 0.0263177 0.0811979 0.43546 0.0265757 0.0810593 0.430999 0.0230182 0.0810593 0.431134 0.0210126 0.0808427 0.433475 0.0178774 0.0810593 0.437386 0.0180023 0.0808427 0.439921 0.0209818 0.0810593 0.439786 0.0210126 0.0808427 0.439921 0.0230182 0.0810593 0.439038 0.0248529 0.0810593 0.438929 0.0247664 0.0808427 0.433381 -0.0176823 0.0811979 0.431486 -0.0190913 0.0812303 0.430887 -0.0201727 0.0812303 0.430788 -0.0230664 0.0811979 0.430877 -0.0238034 0.0812303 0.431714 -0.024988 0.0811979 0.432336 -0.0181933 0.0812303 0.43754 -0.0176823 0.0811979 0.439369 -0.0188826 0.081235 0.440335 -0.0208874 0.081235 0.439369 -0.0251175 0.081235 0.439786 -0.0210127 0.0808427 0.4389 -0.0192567 0.080635 0.437386 -0.0180024 0.0808427 0.43975 -0.021021 0.080635 0.437386 -0.0259977 0.0808427 0.438929 -0.0247665 0.0808427 0.4389 -0.0247434 0.080635 0.433535 -0.0259977 0.0808427 0.43546 -0.0264 0.080635 0.437369 -0.0259643 0.080635 0.431134 -0.0229874 0.0808427 0.43202 -0.0247434 0.080635 0.43165 -0.0198 0.080635 0.431991 -0.0192336 0.0808427 0.43326 -0.0181895 0.080635 0.437369 -0.0180358 0.080635 0.431714 -0.0190121 0.0811979 0.430788 -0.0209336 0.0811979 0.430999 -0.0230182 0.0810593 0.433475 -0.0261226 0.0810593 0.433381 -0.0263178 0.0811979 0.43546 -0.0267924 0.0811979 0.43754 -0.0263178 0.0811979 0.439207 -0.024988 0.0811979 0.440133 -0.0230664 0.0811979 0.439038 -0.024853 0.0810593 0.440133 -0.0209336 0.0811979 0.439921 -0.0230182 0.0810593 0.439207 -0.0190121 0.0811979 0.439038 -0.0191471 0.0810593 0.437446 -0.0178774 0.0810593 0.43546 -0.0174243 0.0810593 0.43546 -0.0172077 0.0811979 0.433475 -0.0178774 0.0810593 0.431883 -0.0191471 0.0810593 0.433535 -0.0180024 0.0808427 0.430999 -0.0209818 0.0810593 0.431134 -0.0210127 0.0808427 0.431991 -0.0247665 0.0808427 0.431883 -0.024853 0.0810593 0.43546 -0.0265758 0.0810593 0.43546 -0.0264371 0.0808427 0.437446 -0.0261226 0.0810593 0.439786 -0.0229874 0.0808427 0.439921 -0.0209818 0.0810593 0.438929 -0.0192336 0.0808427 0.43546 -0.017563 0.0808427 0.428195 0.0205689 -0.0817603 0.427716 0.0217428 -0.0817603 0.427805 0.0240664 -0.0817279 0.428195 0.0254311 -0.0817603 0.428731 0.0259879 -0.0817279 0.428957 0.0264439 -0.0817603 0.428957 0.019556 -0.0817603 0.428731 0.020012 -0.0817279 0.431037 0.0182121 -0.081765 0.434557 0.0186822 -0.0817279 0.436387 0.0198825 -0.081765 0.43715 0.0219336 -0.0817279 0.43715 0.0240664 -0.0817279 0.436224 0.0259879 -0.0817279 0.434647 0.0275048 -0.081765 0.434557 0.0273177 -0.0817279 0.432478 0.028 -0.081765 0.431037 0.0277879 -0.081765 0.436288 0.0208 -0.081165 0.436767 0.0220209 -0.081165 0.436767 0.0239791 -0.081165 0.434403 0.0269976 -0.0813726 0.434678 0.0268105 -0.081165 0.435947 0.0257664 -0.0813726 0.436288 0.0252 -0.081165 0.430569 0.0269642 -0.081165 0.428152 0.0239873 -0.0813726 0.429009 0.0257664 -0.0813726 0.430552 0.0269976 -0.0813726 0.428667 0.0252 -0.081165 0.428188 0.0220209 -0.081165 0.430278 0.0191894 -0.081165 0.429009 0.0202335 -0.0813726 0.434678 0.0191894 -0.081165 0.434387 0.0190357 -0.081165 0.430569 0.0190357 -0.081165 0.430398 0.0186822 -0.0817279 0.428017 0.0219818 -0.0815892 0.427805 0.0219336 -0.0817279 0.4289 0.0258529 -0.0815892 0.430398 0.0273177 -0.0817279 0.432478 0.0277923 -0.0817279 0.432478 0.0275757 -0.0815892 0.434463 0.0271226 -0.0815892 0.436055 0.0258529 -0.0815892 0.436939 0.0240182 -0.0815892 0.436224 0.020012 -0.0817279 0.434463 0.0188774 -0.0815892 0.432478 0.0182076 -0.0817279 0.430492 0.0188774 -0.0815892 0.430552 0.0190023 -0.0813726 0.4289 0.020147 -0.0815892 0.428017 0.0240182 -0.0815892 0.428152 0.0220126 -0.0813726 0.430492 0.0271226 -0.0815892 0.432478 0.027437 -0.0813726 0.436939 0.0219818 -0.0815892 0.436803 0.0239873 -0.0813726 0.436803 0.0220126 -0.0813726 0.436055 0.020147 -0.0815892 0.435947 0.0202335 -0.0813726 0.432478 0.0184242 -0.0815892 0.434403 0.0190023 -0.0813726 0.432478 0.0185629 -0.0813726 0.427805 -0.0240664 -0.0817279 0.427716 -0.0242572 -0.0817603 0.427553 -0.023 -0.0817603 0.427716 -0.0217428 -0.0817603 0.427805 -0.0219336 -0.0817279 0.428957 -0.026444 -0.0817603 0.429953 -0.0272286 -0.0817603 0.431037 -0.0277879 -0.081765 0.432478 -0.0277924 -0.0817279 0.432478 -0.028 -0.081765 0.434647 -0.0275049 -0.081765 0.436224 -0.025988 -0.0817279 0.437352 -0.0241126 -0.081765 0.436224 -0.0200121 -0.0817279 0.437352 -0.0218874 -0.081765 0.434647 -0.0184952 -0.081765 0.432478 -0.0182077 -0.0817279 0.435918 -0.0257434 -0.081165 0.436803 -0.0239874 -0.0813726 0.436767 -0.0239791 -0.081165 0.436878 -0.023 -0.081165 0.435947 -0.0202336 -0.0813726 0.430552 -0.0190024 -0.0813726 0.432478 -0.0186 -0.081165 0.434387 -0.0190358 -0.081165 0.428152 -0.0220127 -0.0813726 0.428667 -0.0208 -0.081165 0.429038 -0.0202567 -0.081165 0.430278 -0.0191895 -0.081165 0.428152 -0.0239874 -0.0813726 0.428667 -0.0252 -0.081165 0.428078 -0.023 -0.081165 0.430278 -0.0268106 -0.081165 0.429009 -0.0257665 -0.0813726 0.432478 -0.0274371 -0.0813726 0.430552 -0.0269977 -0.0813726 0.430398 -0.0273178 -0.0817279 0.428731 -0.025988 -0.0817279 0.4289 -0.025853 -0.0815892 0.428731 -0.0200121 -0.0817279 0.4289 -0.0201471 -0.0815892 0.430398 -0.0186823 -0.0817279 0.430492 -0.0188774 -0.0815892 0.434557 -0.0186823 -0.0817279 0.432478 -0.0184243 -0.0815892 0.434463 -0.0188774 -0.0815892 0.436055 -0.0201471 -0.0815892 0.43715 -0.0219336 -0.0817279 0.436939 -0.0219818 -0.0815892 0.436939 -0.0240182 -0.0815892 0.43715 -0.0240664 -0.0817279 0.436055 -0.025853 -0.0815892 0.434557 -0.0273178 -0.0817279 0.432478 -0.0275758 -0.0815892 0.430492 -0.0271226 -0.0815892 0.428017 -0.0240182 -0.0815892 0.428017 -0.0219818 -0.0815892 0.429009 -0.0202336 -0.0813726 0.432478 -0.018563 -0.0813726 0.434403 -0.0190024 -0.0813726 0.436803 -0.0220127 -0.0813726 0.435947 -0.0257665 -0.0813726 0.434403 -0.0269977 -0.0813726 0.434463 -0.0271226 -0.0815892 0.430851 -0.0260991 -0.085265 0.429597 -0.0249883 -0.085265 0.429447 -0.02475 -0.085265 0.429003 -0.0234219 -0.085265 0.429447 -0.02125 -0.083265 0.430728 -0.019969 -0.083265 0.430157 -0.0203803 -0.085265 0.430728 -0.019969 -0.085265 0.432478 -0.0195 -0.085265 0.434228 -0.019969 -0.085265 0.434228 -0.019969 -0.083265 0.435509 -0.02125 -0.083265 0.434799 -0.0203803 -0.085265 0.43575 -0.0217589 -0.085265 0.435978 -0.023 -0.083265 0.435509 -0.02475 -0.083265 0.435358 -0.0249883 -0.085265 0.434228 -0.0260311 -0.085265 0.432478 -0.0265 -0.085265 0.431228 -0.0251651 -0.082765 0.430313 -0.02425 -0.078365 0.430313 -0.02425 -0.082765 0.431228 -0.020835 -0.078365 0.433728 -0.020835 -0.082765 0.434643 -0.02175 -0.078365 0.434643 -0.02175 -0.082765 0.434643 -0.02425 -0.078365 0.433728 -0.0251651 -0.078365 0.434643 -0.02425 -0.082765 0.430728 0.0199689 -0.085265 0.429597 0.0210117 -0.085265 0.428978 0.023 -0.083265 0.429003 0.0225781 -0.085265 0.429205 0.0242411 -0.085265 0.430728 0.026031 -0.083265 0.430157 0.0256197 -0.085265 0.432478 0.0265 -0.083265 0.433315 0.0263983 -0.085265 0.435509 0.02475 -0.083265 0.43575 0.0242411 -0.085265 0.435978 0.023 -0.085265 0.435978 0.023 -0.083265 0.435952 0.0225781 -0.085265 0.435509 0.02125 -0.083265 0.435358 0.0210117 -0.085265 0.434228 0.0199689 -0.083265 0.434228 0.0199689 -0.085265 0.432478 0.0195 -0.085265 0.430851 0.0199009 -0.085265 0.431228 0.0208349 -0.082765 0.431228 0.0208349 -0.078365 0.430313 0.02175 -0.082765 0.429978 0.023 -0.082765 0.430313 0.02425 -0.082765 0.431228 0.025165 -0.082765 0.433728 0.025165 -0.078365 0.433728 0.025165 -0.082765 0.434978 0.023 -0.078365 0.433728 0.0208349 -0.082765 0.434387 0.0269642 -0.081165 0.432478 0.0274 -0.081165 0.432478 0.0274 -0.078965 0.431339 0.02725 -0.078965 0.430278 0.0268105 -0.078965 0.430278 0.0268105 -0.081165 0.429366 0.0261112 -0.078965 0.429038 0.0257433 -0.081165 0.428078 0.023 -0.078965 0.428188 0.0239791 -0.081165 0.428078 0.023 -0.081165 0.428667 0.0208 -0.081165 0.428667 0.0208 -0.078965 0.429038 0.0202566 -0.081165 0.430278 0.0191894 -0.078965 0.432478 0.0186 -0.081165 0.434678 0.0191894 -0.078965 0.435589 0.0198887 -0.078965 0.435918 0.0202566 -0.081165 0.436288 0.0208 -0.078965 0.436878 0.023 -0.081165 0.435918 0.0257433 -0.081165 0.434678 0.0268105 -0.078965 0.434678 -0.0191895 -0.078965 0.432478 -0.0186 -0.078965 0.430569 -0.0190358 -0.081165 0.431339 -0.01875 -0.078965 0.430278 -0.0191895 -0.078965 0.429366 -0.0198888 -0.078965 0.428667 -0.0208 -0.078965 0.428188 -0.0220209 -0.081165 0.428228 -0.0218612 -0.078965 0.428228 -0.0241388 -0.078965 0.428188 -0.0239791 -0.081165 0.429366 -0.0261113 -0.078965 0.429038 -0.0257434 -0.081165 0.430278 -0.0268106 -0.078965 0.430569 -0.0269643 -0.081165 0.432478 -0.0274 -0.081165 0.434387 -0.0269643 -0.081165 0.433616 -0.0272501 -0.078965 0.434678 -0.0268106 -0.078965 0.434678 -0.0268106 -0.081165 0.436288 -0.0252 -0.081165 0.436728 -0.0241388 -0.078965 0.436767 -0.0220209 -0.081165 0.436288 -0.0208 -0.081165 0.435918 -0.0202567 -0.081165 0.434678 -0.0191895 -0.081165 0.43371 -0.018969 0.083235 0.43258 -0.0200118 0.084735 0.432429 -0.02025 0.084735 0.43196 -0.022 0.083235 0.432188 -0.0232412 0.084735 0.432429 -0.02375 0.083235 0.43371 -0.0250311 0.083235 0.433139 -0.0246198 0.084735 0.43371 -0.0250311 0.084735 0.43546 -0.0255 0.084735 0.43546 -0.0255 0.083235 0.436298 -0.0253983 0.084735 0.437781 -0.0246198 0.084735 0.438733 -0.0232412 0.084735 0.43896 -0.022 0.084735 0.438341 -0.0200118 0.084735 0.43721 -0.018969 0.083235 0.437087 -0.0189009 0.084735 0.43546 -0.0195 0.082735 0.43421 -0.019835 0.082735 0.43296 -0.022 0.082735 0.433295 -0.02325 0.082735 0.43421 -0.0241651 0.082735 0.43546 -0.0245 0.078335 0.43546 -0.0245 0.082735 0.437625 -0.02325 0.078335 0.43796 -0.022 0.082735 0.43671 -0.019835 0.078335 0.43371 0.025031 0.083235 0.43258 0.0239882 0.084735 0.432429 0.02375 0.084735 0.431986 0.0224218 0.084735 0.432188 0.0207588 0.084735 0.432429 0.02025 0.083235 0.434623 0.0186017 0.084735 0.43546 0.0185 0.084735 0.43721 0.0189689 0.084735 0.438733 0.0207588 0.084735 0.43896 0.022 0.083235 0.438491 0.02375 0.083235 0.438491 0.02375 0.084735 0.43721 0.025031 0.084735 0.437087 0.0250991 0.084735 0.43546 0.0255 0.084735 0.433834 0.0250991 0.084735 0.433295 0.02325 0.078335 0.43296 0.022 0.078335 0.43421 0.0198349 0.082735 0.43546 0.0195 0.078335 0.437625 0.02075 0.082735 0.43796 0.022 0.082735 0.437625 0.02325 0.082735 0.437625 0.02325 0.078335 0.43671 0.024165 0.078335 0.436599 0.0177499 0.078935 0.43326 0.0181894 0.078935 0.43326 0.0181894 0.080635 0.432349 0.0188887 0.078935 0.43121 0.0208612 0.078935 0.431171 0.0210209 0.080635 0.43165 0.0242 0.078935 0.431171 0.0229791 0.080635 0.43165 0.0242 0.080635 0.43202 0.0247433 0.080635 0.43326 0.0258105 0.078935 0.433551 0.0259642 0.080635 0.43546 0.0264 0.080635 0.436599 0.02625 0.078935 0.43766 0.0258105 0.078935 0.437369 0.0259642 0.080635 0.43766 0.0258105 0.080635 0.439271 0.0242 0.078935 0.43971 0.0208612 0.078935 0.439271 0.0198 0.078935 0.438572 0.0188887 0.078935 0.43766 0.0181894 0.080635 0.436599 -0.0262501 0.078935 0.433551 -0.0259643 0.080635 0.43326 -0.0258106 0.080635 0.43165 -0.0242 0.078935 0.43165 -0.0242 0.080635 0.431171 -0.0229791 0.080635 0.43106 -0.022 0.080635 0.43106 -0.022 0.078935 0.43121 -0.0208612 0.078935 0.431171 -0.021021 0.080635 0.43165 -0.0198 0.078935 0.432349 -0.0188888 0.078935 0.43202 -0.0192567 0.080635 0.43326 -0.0181895 0.078935 0.433551 -0.0180358 0.080635 0.43546 -0.0176 0.080635 0.436599 -0.01775 0.078935 0.43766 -0.0181895 0.080635 0.438572 -0.0188888 0.078935 0.439271 -0.0198 0.078935 0.439271 -0.0198 0.080635 0.43971 -0.0208612 0.078935 0.43986 -0.022 0.080635 0.43971 -0.0231388 0.078935 0.43975 -0.0229791 0.080635 0.439271 -0.0242 0.078935 0.438572 -0.0251113 0.078935 0.439271 -0.0242 0.080635 0.43766 -0.0258106 0.080635 0.446309 0.0612 0.051235 0.446644 0.0612 0.052485 0.447559 0.0577 0.0534001 0.447559 0.0612 0.0534001 0.448809 0.0612 0.053735 0.448809 0.0577 0.053735 0.450059 0.0612 0.0534001 0.451309 0.0577 0.051235 0.450974 0.0612 0.049985 0.446644 0.0577 0.049985 0.446309 0.0577 0.051235 0.442669 0.0575 -0.040265 0.443919 0.054 -0.0380999 0.443919 0.0575 -0.0380999 0.446419 0.054 -0.0380999 0.446419 0.0575 -0.0380999 0.447334 0.0575 -0.039015 0.447334 0.0575 -0.041515 0.446419 0.054 -0.04243 0.443919 0.054 -0.04243 0.443919 0.0575 -0.04243 0.446644 -0.0612 0.052485 0.447559 -0.0612 0.0534001 0.447559 -0.0577 0.0534001 0.450059 -0.0577 0.0534001 0.450974 -0.0577 0.052485 0.450974 -0.0612 0.049985 0.450059 -0.0612 0.04907 0.448809 -0.0577 0.048735 0.446309 -0.0577 0.051235 0.445169 -0.0575 -0.037765 0.445169 -0.054 -0.037765 0.447334 -0.0575 -0.039015 0.447669 -0.054 -0.040265 0.445169 -0.054 -0.042765 0.443919 -0.0575 -0.04243 0.443004 -0.0575 -0.041515 0.443919 -0.054 -0.04243 0.443004 -0.054 -0.041515 0.442669 -0.0575 -0.040265 0.442669 -0.054 -0.040265 0.447559 -0.056175 -0.0364524 0.445169 -0.0545 -0.035765 0.442206 -0.0561564 -0.0368783 0.441272 -0.0561068 -0.0380151 0.440982 -0.0560805 -0.0386157 0.440822 -0.0545 -0.0391003 0.440822 -0.0545 -0.0414297 0.441234 -0.0559132 -0.0424489 0.444004 -0.0545 -0.0446116 0.445169 -0.0558121 -0.044765 0.445169 -0.0545 -0.044765 0.44634 -0.0558188 -0.04461 0.446333 -0.0545 -0.0446116 0.447419 -0.0558384 -0.044162 0.448351 -0.0545 -0.043447 0.449356 -0.0559365 -0.0419142 0.449669 -0.0545 -0.040265 0.449669 -0.0560085 -0.040265 0.449066 -0.0545 -0.038015 0.449973 -0.0582 0.0468884 0.451183 -0.0597572 0.0474121 0.451059 -0.0597645 0.047338 0.449782 -0.0598052 0.0468415 0.452706 -0.0582 0.048985 0.452706 -0.059597 0.0489851 0.452319 -0.0596538 0.0484189 0.452706 -0.0582 0.053485 0.447644 -0.0582 0.0555817 0.448809 -0.05929 0.055735 0.451059 -0.0582 0.0551321 0.451001 -0.0592838 0.0551647 0.451991 -0.0582 0.054417 0.445627 -0.0582 0.048053 0.446117 -0.0598349 0.0476291 0.444912 -0.0582 0.048985 0.44456 -0.0598591 0.0497536 0.444462 -0.0582 0.0523997 0.444912 -0.0582 0.053485 0.444698 -0.0596828 0.0530661 0.444912 -0.0596375 0.0534852 0.445627 -0.0582 0.054417 0.446559 -0.0582 0.0551321 0.449413 -0.0598062 0.0467758 0.448809 -0.0598044 0.046735 0.448809 -0.0582 0.046735 0.447644 -0.0582 0.0468884 0.448255 -0.0598058 0.0467692 0.44713 -0.0598164 0.0470599 0.446559 -0.0598259 0.0473379 0.442778 0.0561749 -0.0364524 0.442919 0.0561786 -0.0363679 0.442919 0.0545 -0.0363679 0.444772 0.0562042 -0.0357825 0.445169 0.0545 -0.035765 0.447419 0.0561786 -0.0363679 0.448132 0.0561563 -0.0368783 0.449066 0.0561067 -0.0380151 0.448351 0.0545 -0.037083 0.449356 0.0560804 -0.0386157 0.449103 0.0559131 -0.0424489 0.447419 0.0558383 -0.0441621 0.445169 0.0545 -0.044765 0.445169 0.055812 -0.044765 0.445565 0.0558127 -0.0447475 0.444004 0.0545 -0.0446116 0.442919 0.0558383 -0.044162 0.442206 0.0558606 -0.0436517 0.441272 0.0559102 -0.0425149 0.441987 0.0545 -0.043447 0.440669 0.0560084 -0.040265 0.444314 0.0598272 0.0510231 0.444462 0.0582 0.0500703 0.444592 0.0598598 0.0496644 0.447644 0.0582 0.0468884 0.444309 0.0582 0.051235 0.444309 0.0598179 0.051235 0.448299 0.0593007 0.0557061 0.446744 0.0593867 0.0552331 0.446559 0.0582 0.0551321 0.446559 0.059404 0.055132 0.445618 0.0595177 0.0544081 0.444912 0.0596374 0.0534851 0.444912 0.0582 0.053485 0.449973 0.0582 0.0555817 0.451059 0.059284 0.0551321 0.449807 0.0592815 0.0556229 0.448809 0.0582 0.055735 0.448809 0.05929 0.055735 0.452898 0.0595612 0.049356 0.453057 0.0593308 0.0527202 0.452706 0.0582 0.053485 0.452706 0.059307 0.0534849 0.451991 0.0582 0.054417 0.452327 0.0592962 0.0540403 0.451059 0.0582 0.0551321 0.449973 0.0582 0.0468884 0.45205 0.0596851 0.0481134 0.452706 0.0595969 0.0489851 0.45184 -0.0617 0.049485 0.451485 -0.0629453 0.0534901 0.450559 -0.0617 0.0542661 0.45184 -0.0617 0.052985 0.452275 -0.0630134 0.0517195 0.452309 -0.0617 0.051235 0.452309 -0.0630416 0.051235 0.451571 -0.0632131 0.0490859 0.450516 -0.063298 0.0481797 0.448809 -0.0617 0.047735 0.448327 -0.0633259 0.0477683 0.445778 -0.0617 0.049485 0.44548 -0.0633564 0.0501534 0.445342 -0.0633414 0.0507537 0.448809 -0.0617 0.054735 0.445778 -0.0617 0.052985 0.446919 -0.058 -0.0432961 0.446919 -0.058 -0.0372339 0.4482 -0.058 -0.038515 0.4482 -0.0594245 -0.0420149 0.448402 -0.059445 -0.0416044 0.448669 -0.058 -0.040265 0.448642 -0.0594904 -0.0406944 0.446919 -0.0593606 -0.0432959 0.447644 -0.0593884 -0.0427398 0.4482 -0.058 -0.042015 0.448054 -0.059413 -0.0422464 0.443419 -0.058 -0.0432961 0.443419 -0.0593606 -0.0432959 0.445169 -0.058 -0.043765 0.444741 -0.0593385 -0.0437385 0.446508 -0.0593505 -0.0434985 0.446804 -0.0593575 -0.0433592 0.442138 -0.0594245 -0.0420148 0.442138 -0.058 -0.042015 0.441669 -0.0595119 -0.040265 0.442076 -0.0594301 -0.0419038 0.441935 -0.0595787 -0.0389256 0.442284 -0.0596107 -0.0382836 0.442694 -0.0596354 -0.0377901 0.442138 -0.058 -0.038515 0.445169 -0.058 -0.036765 0.443419 -0.058 -0.0372339 0.443829 -0.0596732 -0.0370314 0.443533 -0.0596663 -0.0371707 0.443419 -0.0596631 -0.037234 0.4519 0.0631668 0.0495937 0.445778 0.0631832 0.0529851 0.446004 0.0631431 0.0533289 0.446728 0.0630448 0.0540497 0.447007 0.0630162 0.0542359 0.445309 0.0633214 0.051235 0.445778 0.0617 0.049485 0.445309 0.0617 0.051235 0.445403 0.0633508 0.0504308 0.445341 0.0633413 0.0507577 0.447059 0.0617 0.0482039 0.44668 0.063347 0.0484566 0.446193 0.0633561 0.0489098 0.445783 0.0633611 0.0494754 0.448809 0.0617 0.047735 0.44758 0.0633324 0.0479581 0.45184 0.0631765 0.0494851 0.450515 0.063298 0.0481788 0.450559 0.0617 0.0482039 0.452309 0.0630415 0.051235 0.452189 0.0631056 0.0503274 0.451622 0.0629497 0.0533168 0.45184 0.0629595 0.0529849 0.448809 0.0629292 0.054735 0.448809 0.0617 0.054735 0.449492 0.0629237 0.0546678 0.450559 0.062928 0.0542661 0.443419 0.0593605 -0.0432959 0.443419 0.058 -0.0372339 0.442694 0.0596353 -0.0377901 0.443191 0.0596559 -0.0373774 0.441935 0.0595786 -0.0389256 0.442138 0.058 -0.038515 0.441669 0.058 -0.040265 0.442284 0.0594129 -0.0422464 0.442138 0.0594245 -0.0420149 0.441935 0.0594449 -0.0416044 0.441695 0.0594904 -0.0406944 0.442138 0.058 -0.042015 0.442694 0.0593883 -0.0427398 0.445597 0.0593385 -0.0437385 0.447146 0.0593677 -0.0431525 0.4482 0.058 -0.042015 0.448261 0.05943 -0.0419038 0.4482 0.058 -0.038515 0.448669 0.058 -0.040265 0.448642 0.0595332 -0.0398356 0.448669 0.0595118 -0.040265 0.448054 0.0596106 -0.0382836 0.446919 0.059663 -0.037234 0.445169 0.0596864 -0.036765 0.446919 0.058 -0.0372339 0.462766 -0.0450079 0.0629866 0.463614 -0.0439757 0.0629243 0.463727 0.0437878 0.0629583 0.46375 0.0437327 0.0629845 0.457125 0.0567582 -0.0230165 0.457036 0.0572293 -0.0122978 0.479773 0.0440711 -0.000198317 0.450846 0.0597755 0.0472225 0.453831 0.0431869 -0.0788059 0.457849 0.03142 -0.0815872 0.447915 0.0378495 0.0805206 0.456281 0.036 0.0796103 0.457946 0.0377168 0.0785467 0.462685 0.0400429 0.0747332 0.465758 0.036 0.0734989 0.46575 0.036 0.0735067 0.463856 0.040528 0.0734429 0.463232 0.0401944 0.0741905 0.463977 0.0380337 0.0744884 0.462899 0.0400886 0.0745312 0.464742 0.0415252 0.0719628 0.464666 0.0413924 0.0721273 0.467775 0.0391841 0.0696545 0.471118 0.0345128 0.0667985 0.475845 0.0294242 0.0582272 0.481236 0.0294786 0.0356195 0.481557 0.0294949 0.033249 0.481636 0.0346266 0.0246956 0.481506 0.0341749 0.0272392 0.482792 0.0312418 0.0160433 0.482666 0.0318415 0.0166166 0.48229 0.0299829 -0.0264494 0.482779 0.0298812 -0.0200077 0.481692 0.030561 -0.031859 0.480753 0.0302003 -0.0394724 0.479845 0.0327416 -0.0432929 0.475927 0.0305378 -0.0604141 0.473945 0.0306092 -0.0655968 0.473555 0.0306207 -0.0664795 0.463895 0.0308497 -0.0792746 0.45383 0.0380691 -0.0811194 0.455715 0.0388561 -0.0808272 0.453898 0.0518613 -0.0688225 0.45387 0.0510742 -0.0702363 0.453845 0.0499173 -0.0720424 0.45417 0.0532752 -0.0657054 0.456793 0.057591 -0.00401846 0.449567 0.0597665 0.0458138 0.451059 0.0597644 0.047338 0.451277 0.0595959 0.0423425 0.453576 0.0587877 0.0233911 0.455649 0.0586237 0.020138 0.451203 0.0592848 0.0550452 0.45328 0.0588372 0.0557896 0.453309 0.0594085 0.051235 0.45329 0.0594376 0.0508194 0.454219 0.0593911 0.0442034 0.447066 0.055303 0.0662769 0.450319 0.0585027 0.0587237 0.447472 0.0578184 0.0609828 0.447791 0.0587912 0.0579492 0.448547 0.0545534 0.0674891 0.461709 0.0508144 0.0661964 0.45734 0.0509255 0.0698927 0.469497 0.0418663 0.0650598 0.464861 0.0440298 0.070018 0.46451 0.0446417 0.069917 0.452614 0.04 0.0794787 0.463743 0.036 0.0753914 0.462443 0.036 0.0764135 0.456096 0.0398472 0.0786009 0.455629 0.04 0.0787077 0.452895 0.0398344 0.0794864 0.454656 0.0374112 0.0797917 0.453243 0.036 0.0804102 0.450117 0.036 0.0807938 0.451303 0.0373906 0.0804262 0.449249 0.04 0.0798367 0.469821 0.0314244 0.069747 0.470816 0.0298842 0.0685142 0.47396 0.029642 0.0627452 0.472092 0.0293758 0.0664508 0.47262 0.0320985 0.0649131 0.474195 0.0341121 0.0607751 0.475432 0.0313621 0.0588209 0.473106 0.047228 0.0485459 0.478361 0.0397904 0.0406393 0.478663 0.0356501 0.0449069 0.477072 0.0428531 0.0414613 0.479462 0.0364518 0.0396322 0.481481 0.0317679 0.0314625 0.482244 0.0335196 0.0189919 0.48217 0.0337553 0.0194899 0.481162 0.0373637 0.0228094 0.481742 0.0373066 0.011356 0.48008 0.0409598 0.0233034 0.478827 0.0441661 0.0236762 0.475838 0.0494445 0.0240601 0.476598 0.0495477 0.0117607 0.479468 0.044277 0.0116887 0.480681 0.0410098 0.0115552 0.476998 0.0493284 -0.000388777 0.471586 0.0493052 -0.0491037 0.479503 0.0427937 -0.0235713 0.476765 0.0480382 -0.024386 0.477575 0.0443541 -0.0357389 0.476107 0.0468302 -0.0363044 0.473412 0.0472925 -0.0486736 0.470913 0.0482455 -0.0550473 0.471946 0.044541 -0.0600499 0.473592 0.0420632 -0.0590393 0.474396 0.0437052 -0.0536588 0.469855 0.0398782 -0.0698595 0.468137 0.0421943 -0.0708688 0.471001 0.0424938 -0.0652343 0.476338 0.0364547 -0.0562199 0.472737 0.0461037 -0.0544834 0.47507 0.0449943 -0.0480158 0.476553 0.042399 -0.0471421 0.478876 0.0415023 -0.0350123 0.480941 0.0403082 -0.0116363 0.480951 0.0407755 -0.000113235 0.481949 0.036551 -0.0112682 0.481987 0.0370197 -3.44156e-05 0.476414 0.031382 -0.0587163 0.477407 0.0333199 -0.0544506 0.477163 0.038129 -0.0512946 0.47785 0.0394974 -0.0460612 0.480001 0.0382579 -0.0341243 0.480942 0.0346113 -0.0330737 0.478951 0.0362813 -0.0447778 0.479117 0.0314789 -0.0480498 0.478246 0.0349426 -0.0497799 0.478566 0.0303928 -0.0510399 0.47535 0.0344329 -0.0607485 0.474179 0.0320035 -0.0647703 0.471456 0.0374033 -0.0684831 0.472623 0.0399864 -0.0640338 0.470072 0.0342232 -0.0722069 0.470096 0.0307082 -0.0728032 0.468477 0.03662 -0.0737225 0.468104 0.0307512 -0.0754533 0.466828 0.0325806 -0.0766742 0.466002 0.030798 -0.0776321 0.466701 0.0553532 -0.0245046 0.463849 0.0560735 -0.0241559 0.460283 0.0559777 -0.0352084 0.459729 0.0553452 -0.0471921 0.459061 0.0531735 -0.0644377 0.45673 0.0540859 -0.0628597 0.456564 0.0522817 -0.0677354 0.457892 0.0482515 -0.0737693 0.457237 0.0466423 -0.0756901 0.455895 0.0497956 -0.0721085 0.45455 0.0468357 -0.0757702 0.453831 0.0450101 -0.0774567 0.45383 0.0407758 -0.0801499 0.454017 0.0411582 -0.0799679 0.45533 0.0431054 -0.0788158 0.456394 0.0449275 -0.0773805 0.459025 0.0448503 -0.0768616 0.458722 0.0510668 -0.0693732 0.460714 0.049656 -0.0705917 0.459199 0.0544155 -0.059098 0.459446 0.054981 -0.0532688 0.462509 0.0546799 -0.0481849 0.4633 0.0554288 -0.0359905 0.454092 0.0365379 -0.0814462 0.457047 0.0409859 -0.0798294 0.458748 0.038883 -0.0803198 0.458138 0.0429792 -0.0784934 0.45983 0.0410234 -0.07908 0.460739 0.0430146 -0.077517 0.459739 0.0465983 -0.0749732 0.461256 0.051976 -0.0656139 0.461639 0.0534346 -0.0601748 0.463951 0.0521575 -0.06087 0.462068 0.0542037 -0.0543024 0.466032 0.054628 -0.0365426 0.468489 0.0535855 -0.0368755 0.463347 0.0369512 -0.0787288 0.46233 0.0345868 -0.0798679 0.460515 0.0367523 -0.0803158 0.461146 0.0319634 -0.0806884 0.464128 0.0324079 -0.0790168 0.465118 0.0348002 -0.0778964 0.466783 0.0388895 -0.0748595 0.469239 0.0448128 -0.0660976 0.468204 0.0488242 -0.0611496 0.470144 0.0467968 -0.0607617 0.469592 0.0510453 -0.0492904 0.47268 0.0507695 -0.0369434 0.474478 0.0489571 -0.0367073 0.479787 0.0435997 -0.0119497 0.480642 0.0395251 -0.0229992 0.481621 0.0358077 -0.0223147 0.474105 0.0515577 0.0240699 0.473107 0.0533324 0.0115676 0.473622 0.0530351 -0.000614183 0.477056 0.0488373 -0.0124175 0.475171 0.0500748 -0.0246325 0.470694 0.0523033 -0.0370039 0.468934 0.0501313 -0.055331 0.466802 0.0517595 -0.0553141 0.467365 0.0469319 -0.0665914 0.466337 0.0443379 -0.071475 0.465028 0.0410233 -0.0755878 0.452754 0.0574584 0.0609891 0.449619 0.0567828 0.063355 0.44743 0.0531463 0.0695661 0.456904 0.0574595 -0.00703057 0.456721 0.0576894 -0.00176529 0.454993 0.0590603 0.0319441 0.457059 0.0588391 0.0457404 0.45373 0.0593891 0.0502144 0.456412 0.0586118 0.0518218 0.455779 0.0577864 0.0575477 0.455084 0.056121 0.062895 0.451929 0.0553356 0.065785 0.454116 0.0536699 0.0678098 0.458225 0.0564325 0.0589536 0.461515 0.0561137 0.0540922 0.460598 0.0548275 0.059997 0.462881 0.0530126 0.0606744 0.463899 0.0544754 0.0547525 0.466159 0.0526166 0.0550987 0.472114 0.0458821 0.0543616 0.474157 0.0388019 0.0576986 0.477748 0.0344858 0.049877 0.476688 0.033005 0.0545135 0.475518 0.0359637 0.0562191 0.472775 0.0367853 0.0624804 0.47093 0.044099 0.059906 0.465776 0.0465556 0.0663616 0.467139 0.0488566 0.0609556 0.465064 0.0510158 0.0609902 0.463782 0.0487429 0.066473 0.459563 0.0527539 0.0655134 0.457352 0.0545364 0.064411 0.464027 0.0566471 -0.0126488 0.466151 0.0569013 0.0106959 0.465166 0.0571658 0.0227755 0.459781 0.0579619 0.0469726 0.465667 0.0558164 0.0422462 0.468776 0.0546369 0.0363124 0.467993 0.0542799 0.0426559 0.470149 0.0524952 0.0428332 0.473954 0.0481833 0.0425431 0.469277 0.0517309 0.0490619 0.470923 0.0529653 0.0365353 0.467763 0.0561508 0.0233181 0.470097 0.0548847 0.0237073 0.463166 0.0570961 0.041591 0.466438 0.0560533 0.0358879 0.463895 0.0572134 0.0352487 0.468762 0.055961 0.011075 0.466769 0.0564912 -0.00107598 0.466959 0.0559713 -0.0127358 0.460655 0.0565469 -0.0236619 0.47662 0.037585 0.0513238 0.477555 0.0388707 0.0461181 0.475298 0.0405174 0.0525618 0.476255 0.0418707 0.0471323 0.468287 0.0505563 0.0551392 0.467125 0.0536532 0.0489483 0.464822 0.055344 0.0485688 0.462372 0.0567876 0.0479127 0.459014 0.0575048 0.0531149 0.456224 0.051835 0.069394 0.461139 0.0581092 0.0343828 0.462284 0.0579244 0.0220691 0.458168 0.0587294 0.0332824 0.45911 0.058415 0.0211912 0.463199 0.0575893 0.0102171 0.459893 0.058012 0.00963379 0.46045 0.0575589 -0.00150937 0.463801 0.0571548 -0.00127909 0.460717 0.0570713 -0.012504 0.456878 0.0572354 -0.0121626 0.456591 0.0568079 -0.0219534 0.455577 0.0560838 -0.0385408 0.456986 0.0562593 -0.0341893 0.456731 0.0557221 -0.0458698 0.456641 0.0554342 -0.0518444 0.456627 0.055057 -0.0576297 0.454304 0.0550645 -0.0585728 0.457109 0.0309897 -0.0816752 0.455939 0.0339834 -0.0816654 0.457465 0.0365582 -0.0811944 0.459294 0.0342375 -0.0811382 0.461563 0.0390284 -0.0791408 0.461497 0.0448603 -0.0756799 0.46247 0.0411085 -0.0776464 0.463254 0.0430131 -0.0758743 0.464491 0.0462969 -0.0716458 0.46262 0.0480667 -0.0713555 0.463367 0.0505235 -0.0663652 0.465403 0.048839 -0.0666876 0.464517 0.0531223 -0.054977 0.466138 0.0506148 -0.0611913 0.465068 0.0537362 -0.048853 0.467424 0.052522 -0.0492142 0.469222 0.0543985 -0.0247169 0.473409 0.0517832 -0.0247725 0.469526 0.0550575 -0.0127687 0.473727 0.0525206 -0.0126869 0.469367 0.0555819 -0.000899654 0.4722 0.0533608 0.0239546 0.472889 0.0510311 0.0365689 0.474685 0.0488212 0.036423 0.477769 0.043516 0.0356165 0.479048 0.0403974 0.0349617 0.480145 0.0369568 0.03414 0.447168 0.0561894 0.0646573 0.444366 0.0597769 0.0519503 0.4448 0.0596605 0.0532786 0.449413 0.0598061 0.0467758 0.448809 0.0598044 0.046735 0.447904 0.0598078 0.0468269 0.446497 0.059827 0.0473743 0.44535 0.0598522 0.0483568 0.444912 0.0598601 0.048985 0.443905 0.0597769 0.0519499 0.447323 0.0571513 0.0626293 0.443191 0.0582356 0.0598056 0.44768 0.0585081 0.0589449 0.448072 0.0593073 0.0556743 0.44691 0.0531464 0.069568 0.442886 0.0563727 0.0642959 0.442682 0.0539168 0.0684795 0.442569 0.0509071 0.0723149 0.442531 0.047414 0.0756508 0.446832 0.0390692 0.0802041 0.446829 0.0363005 0.0808433 0.444947 0.0404061 0.0797544 0.442233 0.0374633 0.0806205 0.443911 0.041458 0.0793304 0.442527 0.0403723 0.079767 0.442527 0.041458 0.0793304 0.442529 0.0467297 0.076193 0.441341 0.0345988 0.0810647 0.443706 0.0341038 0.0811084 0.443601 0.0337522 0.0811346 0.482857 -4.19898e-08 0.035119 0.468557 0.00199996 0.0738413 0.468708 0.00200393 0.0736726 0.446827 0.021 0.081235 0.453971 0.017 0.0809203 0.453924 0.021 0.0808904 0.457112 0.017 0.0803192 0.455509 0.021 0.0806132 0.458892 0.021 0.079649 0.459022 0.017 0.0797377 0.459992 0.017 0.0793675 0.46383 0.017 0.0773042 0.465329 0.021 0.075896 0.468262 0.017 0.0733927 0.467957 0.021021 0.0733658 0.470073 0.0290976 0.0697205 0.470258 0.0293546 0.0694237 0.473218 0.0151891 0.0664178 0.471161 0.0142328 0.0698935 0.471052 0.0151141 0.0699775 0.470876 0.0153593 0.0702132 0.469165 0.021453 0.0719046 0.471218 0.0037493 0.0704098 0.469776 0.00226865 0.0724 0.466404 0.00199996 0.0759538 0.465897 -4.74907e-08 0.0763902 0.462852 0.00199996 0.0784395 0.460146 0.00199996 0.0796681 0.455867 0.00199996 0.0807593 0.452094 0.00199996 0.0811426 0.48165 0.0276979 0.0340436 0.481333 0.015534 0.0417814 0.480015 0.0294724 0.042886 0.478479 0.0294568 0.0497278 0.479363 0.0154431 0.0503552 0.476648 0.0294346 0.0559481 0.476727 0.0153282 0.0586454 0.470495 0.0241702 0.0697597 0.474181 0.0294023 0.0622982 0.47481 0.0294105 0.0608495 0.471456 0.00494775 0.0700223 0.481625 -4.24078e-08 0.0420899 0.482636 0.0125198 0.0349934 0.446827 -0.021 0.081235 0.450917 -0.017 0.0811782 0.459495 -0.017 0.0795641 0.457736 -0.021 0.0800417 0.464585 -0.021 0.0764911 0.463624 -0.017 0.0774418 0.463254 -0.021 0.0774392 0.462352 -0.021 0.078002 0.470073 -0.0290948 0.0697206 0.471051 -0.0151141 0.0699808 0.468262 -0.017 0.0733926 0.469372 -0.0167795 0.0721058 0.474297 -0.0294041 0.0620368 0.476725 -0.0153284 0.0586506 0.477836 -0.0294369 0.0521066 0.479361 -0.0154433 0.0503617 0.480271 -0.0294943 0.0415233 0.481562 -0.0293568 0.0333289 0.446827 -0.00200004 0.081235 0.451252 -4.16901e-08 0.0811808 0.450823 -0.00200004 0.081195 0.459224 -3.85537e-08 0.079986 0.459236 -0.00200004 0.0799768 0.455391 -4.3625e-08 0.0808338 0.462728 -3.4833e-08 0.0785156 0.462644 -0.00200004 0.0785522 0.469965 -0.00236488 0.0721584 0.468726 -4.18327e-08 0.0736651 0.466128 -0.00200004 0.0761882 0.46592 -0.00200004 0.07636 0.471161 -0.014233 0.0698935 0.471078 -0.0148005 0.0699682 0.470852 -0.0154077 0.0702439 0.469794 -0.0219942 0.0710298 0.471456 -0.00494772 0.0700223 0.473394 -3.95002e-08 0.0668945 0.471218 -4.53351e-08 0.0704588 0.471403 -0.00434581 0.0701215 0.473216 -0.0151893 0.0664216 0.476929 -3.29554e-08 0.0590785 0.481332 -0.0155343 0.0417892 0.479604 -5.20428e-08 0.0507281 0.468782 -0.0546376 0.0362785 0.473625 -0.0530325 -0.000666495 0.473407 -0.0517777 -0.0248381 0.471578 -0.0492923 -0.0491819 0.457949 -0.0377207 0.078544 0.473964 -0.0296432 0.0627351 0.479107 -0.0314564 -0.0481103 0.453828 -0.0432217 -0.0787836 0.451333 -0.0529532 0.069561 0.46018 -0.0490591 0.069969 0.446831 -0.04 0.0799014 0.446832 -0.0389837 0.0802299 0.455486 -0.04 0.0787555 0.450024 -0.04 0.0797884 0.463254 -0.0402033 0.0741658 0.463981 -0.0380382 0.0744826 0.464385 -0.041007 0.0726518 0.464933 -0.0438423 0.0700863 0.469503 -0.0418711 0.0650461 0.464991 -0.0436515 0.0701707 0.465081 -0.0431163 0.0704796 0.465069 -0.0425624 0.0709014 0.465781 -0.0465613 0.0663479 0.461713 -0.0508204 0.0661827 0.45466 -0.0521443 0.069725 0.454119 -0.0536755 0.0678005 0.448549 -0.0545571 0.0674833 0.447017 -0.0548023 0.0671126 0.44691 -0.0531466 0.0695677 0.452271 -0.0528032 0.0695871 0.4477 -0.0585647 0.0587568 0.447978 -0.0591602 0.0564097 0.450321 -0.0585064 0.0587111 0.453054 -0.0595258 0.049742 0.453309 -0.0594086 0.051235 0.452975 -0.0593231 0.0529348 0.452706 -0.0593071 0.053485 0.452178 -0.0592937 0.0542178 0.451799 -0.0592893 0.0545983 0.453282 -0.0588402 0.0557727 0.451278 -0.059595 0.0423168 0.454996 -0.0590593 0.0319118 0.456704 -0.0576874 -0.00181326 0.4559 -0.0581215 0.00813049 0.457125 -0.0567557 -0.0230758 0.45664 -0.0554303 -0.0519257 0.454216 -0.0548175 -0.0602003 0.456731 -0.0540652 -0.0629341 0.456629 -0.0550488 -0.057707 0.454168 -0.0532481 -0.0657753 0.453867 -0.051028 -0.0703136 0.453901 -0.0519476 -0.0686568 0.453977 -0.0531905 -0.0659235 0.45403 -0.0364534 -0.0814607 0.457796 -0.031316 -0.0815959 0.459906 -0.0309464 -0.0811505 0.471818 -0.0306682 -0.0699653 0.474161 -0.0319604 -0.0648249 0.473831 -0.0306126 -0.0658582 0.481687 -0.0305483 -0.0319178 0.480607 -0.030209 -0.0404278 0.479838 -0.0327229 -0.0433552 0.481885 -0.0344639 0.0218043 0.483096 -0.0295731 0.0148852 0.48146 -0.0330808 0.0297343 0.480149 -0.0369552 0.0341091 0.481542 -0.0343963 0.026356 0.480836 -0.0294692 0.0382547 0.47082 -0.029886 0.068507 0.470054 -0.0293524 0.0697219 0.470256 -0.0293547 0.069427 0.472393 -0.0293801 0.0659065 0.469781 -0.0316899 0.0697503 0.469152 -0.0344033 0.0699013 0.467736 -0.0357515 0.071315 0.467142 -0.0359412 0.0719739 0.468121 -0.0355447 0.070897 0.46778 -0.0391886 0.0696448 0.4688 -0.0349436 0.0702052 0.468865 -0.0348618 0.0701445 0.454659 -0.0374139 0.0797903 0.454562 -0.036 0.0801175 0.452785 -0.036 0.0804931 0.461822 -0.036 0.0768523 0.460377 -0.036 0.0777607 0.458338 -0.04 0.0775857 0.4561 -0.039851 0.0785983 0.452897 -0.039837 0.079485 0.451305 -0.0373919 0.0804257 0.44926 -0.036 0.0808379 0.449512 -0.04 0.079822 0.447916 -0.0378495 0.0805206 0.446952 -0.04 0.0799014 0.465089 -0.0347249 -0.0779366 0.468455 -0.0365614 -0.0737754 0.466799 -0.0325059 -0.0767134 0.469745 -0.0307157 -0.0733155 0.469837 -0.0398322 -0.0699238 0.470049 -0.0341658 -0.0722577 0.471935 -0.0445142 -0.0601256 0.472728 -0.0460839 -0.0545604 0.468119 -0.042148 -0.0709355 0.471438 -0.0373579 -0.0685445 0.474387 -0.0436837 -0.0537331 0.478237 -0.0349194 -0.0498442 0.479144 -0.0303535 -0.0484319 0.477395 -0.0332918 -0.054512 0.477506 -0.0304592 -0.0552354 0.476399 -0.0313481 -0.0587735 0.475335 -0.0343979 -0.0608098 0.473554 -0.0306211 -0.0664815 0.471509 -0.0316454 -0.0703886 0.472675 -0.0507615 -0.0370161 0.474473 -0.0489479 -0.0367791 0.473405 -0.0472776 -0.04875 0.475063 -0.0449777 -0.04809 0.477571 -0.0443427 -0.0358077 0.476103 -0.0468199 -0.0363749 0.470986 -0.0424582 -0.065306 0.472609 -0.0399505 -0.0641024 0.47358 -0.0420352 -0.059112 0.477154 -0.0381058 -0.0513625 0.476326 -0.0364261 -0.0562854 0.478943 -0.0362623 -0.0448434 0.479997 -0.0382452 -0.0341887 0.480938 -0.0345985 -0.0331355 0.481619 -0.0357987 -0.0223732 0.481949 -0.0365441 -0.0113221 0.480941 -0.0403019 -0.0116918 0.481988 -0.0370141 -8.33082e-05 0.480953 -0.0407708 -0.000163342 0.479501 -0.0427856 -0.0236335 0.476764 -0.0480313 -0.0244506 0.479787 -0.0435941 -0.0120064 0.479775 -0.044067 -0.000249375 0.477 -0.0493253 -0.000440966 0.47469 -0.0488222 0.0363898 0.467144 -0.0488617 0.0609375 0.475169 -0.0500686 -0.0246978 0.477056 -0.0488327 -0.0124758 0.479471 -0.0442742 0.0116435 0.476546 -0.0423811 -0.0472138 0.477843 -0.0394787 -0.0461299 0.478872 -0.0414901 -0.035079 0.48064 -0.0395165 -0.0230597 0.481745 -0.0373019 0.0113125 0.477773 -0.0435163 0.0355842 0.478366 -0.0397911 0.0406115 0.479466 -0.0364514 0.039605 0.481497 -0.0312053 0.032014 0.473959 -0.0481854 0.0425136 0.472894 -0.0510322 0.0365353 0.475843 -0.0494439 0.0240201 0.479053 -0.0403969 0.0349301 0.480084 -0.0409575 0.023265 0.478667 -0.0356509 0.0448835 0.47756 -0.0388725 0.0460942 0.477752 -0.0344876 0.0498575 0.476625 -0.0375876 0.0513036 0.47626 -0.0418732 0.0471077 0.475303 -0.0405207 0.052541 0.473111 -0.0472311 0.0485203 0.475524 -0.0359666 0.0562025 0.476693 -0.033007 0.0544974 0.475437 -0.0313638 0.0588079 0.474162 -0.0388055 0.0576815 0.472119 -0.0458861 0.0543399 0.468292 -0.0505604 0.0551169 0.470935 -0.0441037 0.0598883 0.465992 -0.041438 0.070576 0.471123 -0.0345158 0.0667886 0.47278 -0.0367887 0.062467 0.472625 -0.0321006 0.064903 0.4742 -0.0341147 0.0607619 0.476125 -0.0294282 0.0574591 0.465171 -0.057165 0.022736 0.470928 -0.0529662 0.0365015 0.472205 -0.0533603 0.0239143 0.465672 -0.0558175 0.0422158 0.470102 -0.0548842 0.0236671 0.453732 -0.0593898 0.050193 0.455782 -0.0577901 0.0575304 0.453303 -0.0593939 0.0514639 0.456879 -0.0574098 -0.00816965 0.457038 -0.0572272 -0.0123493 0.456723 -0.0576875 -0.00181095 0.45624 -0.0581535 0.00890306 0.459896 -0.0580104 0.00959115 0.459114 -0.0584138 0.0211532 0.455652 -0.0586223 0.0201009 0.454222 -0.0593907 0.0441774 0.456415 -0.0586134 0.0518 0.456227 -0.0518409 0.0693846 0.455086 -0.0561262 0.0628817 0.451931 -0.0553406 0.0657758 0.449621 -0.056787 0.0633459 0.44958 -0.0592824 0.0556684 0.452756 -0.057463 0.0609761 0.457355 -0.0545421 0.0643975 0.458229 -0.0564368 0.058936 0.460602 -0.0548323 0.0599791 0.463787 -0.0487488 0.0664593 0.465069 -0.051021 0.060972 0.466164 -0.0526205 0.0550763 0.469282 -0.0517339 0.0490355 0.477077 -0.0428545 0.0414328 0.479499 -0.0295059 0.0453889 0.462479 -0.0470108 0.0699573 0.46713 -0.0536558 0.0489217 0.467999 -0.0542815 0.0426255 0.470154 -0.052497 0.042803 0.47411 -0.0515573 0.0240297 0.478831 -0.0441645 0.0236372 0.476601 -0.0495459 0.0117145 0.480684 -0.0410062 0.0115107 0.481165 -0.0373603 0.0227719 0.456776 -0.0570202 -0.0170938 0.460719 -0.0570688 -0.0125578 0.460452 -0.0575569 -0.00155698 0.463804 -0.0571527 -0.0013283 0.463202 -0.0575878 0.0101733 0.458172 -0.0587287 0.0332496 0.461143 -0.0581089 0.0343495 0.457062 -0.0588393 0.0457141 0.459785 -0.0579628 0.0469462 0.459017 -0.0575072 0.0530928 0.461519 -0.0561168 0.0540699 0.459719 -0.0465448 -0.0750365 0.458714 -0.0510285 -0.069445 0.461634 -0.0534194 -0.0602551 0.462063 -0.0541958 -0.0543847 0.459726 -0.0553408 -0.0472716 0.462504 -0.0546742 -0.0482653 0.460281 -0.0559741 -0.0352789 0.455882 -0.0338889 -0.0816742 0.455666 -0.038781 -0.0808545 0.453968 -0.0410897 -0.0800016 0.457007 -0.040917 -0.0798684 0.460478 -0.0366721 -0.0803488 0.457419 -0.0364752 -0.0812171 0.459251 -0.034147 -0.0811593 0.456363 -0.0448694 -0.0774317 0.455291 -0.0430426 -0.078859 0.458709 -0.0388084 -0.080355 0.461532 -0.0389566 -0.0791843 0.461476 -0.0448039 -0.0757416 0.462607 -0.0480226 -0.0714271 0.460704 -0.0496142 -0.0706637 0.46125 -0.0519478 -0.0656906 0.466028 -0.054623 -0.0366156 0.463296 -0.0554246 -0.0360625 0.463848 -0.0560701 -0.0242192 0.467417 -0.0525131 -0.0492946 0.469585 -0.0510344 -0.04937 0.468925 -0.0501159 -0.0554117 0.466129 -0.050594 -0.061272 0.465392 -0.0488066 -0.0667647 0.467352 -0.0468981 -0.0666674 0.464476 -0.0462515 -0.0717162 0.463232 -0.042955 -0.0759339 0.462444 -0.0410437 -0.0776989 0.460713 -0.0429523 -0.0775718 0.463358 -0.050493 -0.0664425 0.463943 -0.0521393 -0.0609508 0.466795 -0.0517466 -0.0553959 0.46451 -0.0531118 -0.0550592 0.465062 -0.053729 -0.0489337 0.468484 -0.0535796 -0.0369489 0.46922 -0.0543941 -0.0247822 0.466699 -0.0553493 -0.0245692 0.46696 -0.0559683 -0.0127927 0.4639 -0.0572134 0.035215 0.466155 -0.0568998 0.0106511 0.462289 -0.0579235 0.0220303 0.466771 -0.056489 -0.00112645 0.464028 -0.0566443 -0.0127044 0.460655 -0.056544 -0.0237234 0.456729 -0.0557185 -0.0459474 0.459443 -0.0549754 -0.0533509 0.459197 -0.0544036 -0.059177 0.459059 -0.0531486 -0.0645133 0.456558 -0.0522484 -0.0678065 0.455879 -0.0497521 -0.0721725 0.457874 -0.0482023 -0.0738334 0.454522 -0.0467841 -0.0758234 0.457213 -0.0465886 -0.0757484 0.459 -0.0447917 -0.0769184 0.458106 -0.0429157 -0.0785421 0.459798 -0.0409554 -0.0791259 0.465006 -0.0409643 -0.0756451 0.458456 -0.0502674 0.069937 0.459567 -0.0527599 0.0654998 0.462886 -0.0530176 0.0606563 0.463904 -0.054479 0.0547301 0.462376 -0.0567891 0.0478862 0.464827 -0.0553461 0.0485422 0.463171 -0.0570967 0.0415606 0.467768 -0.0561501 0.0232782 0.466443 -0.0560537 0.0358541 0.468766 -0.0559595 0.0110295 0.473111 -0.0533309 0.0115213 0.46937 -0.0555796 -0.000951033 0.469526 -0.0550543 -0.0128266 0.473727 -0.0525168 -0.0127457 0.47144 -0.053208 -0.0248687 0.470689 -0.0522964 -0.0370772 0.470904 -0.0482277 -0.0551265 0.468194 -0.0488011 -0.0612294 0.470134 -0.0467717 -0.0608397 0.466321 -0.0442918 -0.0715437 0.469225 -0.044778 -0.0661718 0.46676 -0.0388303 -0.0749146 0.463317 -0.0368769 -0.0787705 0.464093 -0.032323 -0.0790486 0.462295 -0.034503 -0.0799001 0.461104 -0.0318691 -0.0807099 0.463301 -0.0308659 -0.0796504 0.46112 -0.0309213 -0.0807325 0.446378 -0.0638469 0.0480473 0.445353 -0.0638612 0.0492196 0.444927 -0.0638518 0.0502779 0.444875 -0.0637828 0.0519899 0.445105 -0.0637254 0.0527864 0.443334 -0.0637282 0.0527446 0.44313 -0.0634849 0.0549228 0.44273 -0.0624489 0.0597256 0.447658 -0.0622692 0.0603248 0.447321 -0.0608094 0.0642478 0.442324 -0.0599459 0.0660941 0.447191 -0.0599458 0.066094 0.447101 -0.0591629 0.0675797 0.442206 -0.0585345 0.0686734 0.44694 -0.0570226 0.0710221 0.442088 -0.0560448 0.0723724 0.44208 -0.0557608 0.0727432 0.44686 -0.0547668 0.0739736 0.442032 -0.0525287 0.0764118 0.446831 -0.052273 0.0766634 0.442028 -0.0510883 0.077772 0.442027 -0.0488085 0.0796358 0.442027 -0.0457592 0.0816402 0.446827 -0.0457592 0.0816402 0.446827 -0.0433138 0.0828839 0.446827 -0.0404488 0.0839654 0.44172 -0.037758 0.0846444 0.459894 -0.0563881 -0.0670537 0.45967 -0.0551971 -0.0698758 0.451622 -0.0610861 0.0631731 0.461887 -0.0619987 0.0366641 0.448048 -0.0631986 0.056622 0.448208 -0.0634341 0.0552655 0.464554 -0.0601043 -0.0226432 0.454733 -0.044131 -0.082905 0.466132 -0.0295074 0.0796969 0.446827 -0.0349768 0.0850469 0.446827 -0.0372847 0.0847329 0.447153 -0.0524905 0.0764478 0.446828 -0.0510878 0.0777715 0.446827 -0.0493345 0.0792351 0.448103 -0.0509987 0.0778367 0.446827 -0.0489304 0.0795445 0.454742 -0.0294621 0.0847222 0.475395 -0.0296064 0.0687215 0.474958 -0.0295997 0.0694687 0.475384 -0.0317766 0.0683603 0.478557 -0.03117 0.0619135 0.48186 -0.0297526 0.0525244 0.482614 -0.0297786 0.0496339 0.484867 -0.0383859 0.0250808 0.484949 -0.037238 0.027374 0.484936 -0.0353831 0.0314727 0.484947 -0.0351016 0.0318635 0.486439 -0.0339491 0.0148573 0.48607 -0.0354469 0.0165975 0.485531 -0.0383839 0.013389 0.485417 -0.0373502 0.0209269 0.48681 -0.0321542 0.0134729 0.487363 -0.03021 0.00181398 0.487361 -0.030236 -0.00106299 0.485573 -0.0368744 -0.0209277 0.48676 -0.0304056 -0.0198728 0.485849 -0.0376273 -0.00964851 0.487238 -0.0303073 -0.0089706 0.485758 -0.0313291 -0.0308346 0.48248 -0.0306938 -0.0518195 0.483211 -0.0323756 -0.0475927 0.483524 -0.0306493 -0.0468848 0.475367 -0.0329947 -0.0714527 0.474639 -0.0308856 -0.0730817 0.472379 -0.0309164 -0.076492 0.47448 -0.030888 -0.0733474 0.47199 -0.0316213 -0.0769403 0.460879 -0.0309934 -0.0850327 0.45704 -0.0357475 -0.0854479 0.45611 -0.0464047 -0.0813443 0.453829 -0.0508806 -0.0773037 0.455026 -0.0506 -0.0775896 0.453854 -0.0538704 -0.0733218 0.455785 -0.0522958 -0.0754901 0.456733 -0.0552707 -0.0706974 0.454055 -0.0565055 -0.06837 0.457075 -0.0583153 -0.0623734 0.454334 -0.0591109 -0.0584145 0.456926 -0.0591681 -0.0564167 0.454515 -0.0593678 -0.0549762 0.457067 -0.0608272 -0.0215614 0.45686 -0.0597958 -0.0443947 0.455866 -0.0621303 0.0082449 0.463711 -0.0616002 0.0120528 0.449635 -0.0637453 0.045235 0.45216 -0.0636946 0.0489754 0.452305 -0.0634514 0.0533391 0.452306 -0.062765 0.0575519 0.447754 -0.0625545 0.0593536 0.448037 -0.0603522 0.0652496 0.446897 -0.0560447 0.0723723 0.467002 -0.0340933 -0.0816877 0.468168 -0.036699 -0.0801694 0.469171 -0.0390534 -0.0783771 0.473414 -0.0420879 -0.0705514 0.472511 -0.0475746 -0.0662034 0.470043 -0.0411728 -0.0763326 0.473764 -0.0358339 -0.0734463 0.47198 -0.0385596 -0.0750861 0.470152 -0.0341956 -0.0787517 0.471026 -0.0309317 -0.0781845 0.469046 -0.0316522 -0.0802162 0.467118 -0.0309651 -0.0818895 0.478899 -0.0411938 -0.0575075 0.476349 -0.0420322 -0.0641696 0.475201 -0.039259 -0.0691274 0.477959 -0.03899 -0.0626619 0.478166 -0.0331764 -0.0653077 0.476793 -0.0362882 -0.0673665 0.478987 -0.0308013 -0.0637345 0.482348 -0.0306989 -0.0523804 0.47934 -0.035775 -0.0608753 0.480302 -0.0379291 -0.0559931 0.48109 -0.0396951 -0.0507647 0.483915 -0.0337061 -0.0425899 0.484954 -0.0356501 -0.0319811 0.481221 -0.0463889 -0.0345467 0.48269 -0.0431729 -0.0338422 0.483258 -0.0444559 -0.0221117 0.478177 -0.0529089 -0.0231483 0.476051 -0.0562336 0.00129724 0.478256 -0.0541551 0.00143943 0.477991 -0.045988 -0.0530582 0.478594 -0.0473468 -0.0471623 0.476661 -0.0500165 -0.0477673 0.483933 -0.0395962 -0.032985 0.482947 -0.0375658 -0.0440287 0.477259 -0.0442467 -0.0587637 0.474527 -0.0448974 -0.0653626 0.476084 -0.048749 -0.0538273 0.477577 -0.0517716 -0.0354671 0.479518 -0.0492526 -0.0350912 0.480102 -0.0504634 -0.0229059 0.481792 -0.0476503 -0.0225591 0.48192 -0.0489032 0.00164389 0.483491 -0.0452401 -0.010254 0.483418 -0.045704 0.00171194 0.471602 -0.0478373 0.0642561 0.473917 -0.0516439 0.0520995 0.474786 -0.0527908 0.0457514 0.47288 -0.050016 0.0583042 0.467872 -0.0476231 0.07036 0.469994 -0.0450632 0.069801 0.464008 -0.035118 0.0804933 0.467978 -0.0416487 0.0747349 0.465474 -0.0375073 0.0788273 0.469974 -0.0392267 0.0736643 0.467502 -0.0354043 0.0776819 0.464509 -0.0307768 0.0807629 0.462371 -0.0324897 0.0818818 0.461923 -0.0371506 0.081303 0.471998 -0.0424289 0.0688658 0.469497 -0.0333328 0.0761786 0.471445 -0.0312554 0.074312 0.467553 -0.0295179 0.0785416 0.471885 -0.0367823 0.0722335 0.473698 -0.0343029 0.0704598 0.475613 -0.0369459 0.0659776 0.477187 -0.0392775 0.0610184 0.473629 -0.0450974 0.0634921 0.474932 -0.0472605 0.0577239 0.475989 -0.0489308 0.0516921 0.476872 -0.0501421 0.0454894 0.477632 -0.0509631 0.0391887 0.483039 -0.045911 0.0138203 0.481488 -0.0491038 0.0139226 0.480206 -0.051716 0.001554 0.480334 -0.0512401 -0.0107023 0.478411 -0.0536686 -0.0108672 0.483692 -0.0422474 0.0256348 0.485834 -0.0381031 0.00179299 0.481738 -0.0411219 -0.0452778 0.480287 -0.0443813 -0.046327 0.479661 -0.0429685 -0.0520298 0.475392 -0.0470826 -0.0597321 0.477115 -0.029636 0.0654491 0.479972 -0.033029 0.0574728 0.481148 -0.0347397 0.0527138 0.478461 -0.0412884 0.0557066 0.482143 -0.0361534 0.0476404 0.479507 -0.0429164 0.050111 0.459343 -0.0624574 0.0231055 0.460837 -0.0616009 0.049603 0.448841 -0.0622503 0.0603533 0.455091 -0.0631217 0.0339311 0.454579 -0.0633868 0.0463899 0.45129 -0.063673 0.0443387 0.456632 -0.060937 0.0607411 0.457287 -0.0622005 0.0545296 0.458573 -0.0627276 0.0354144 0.457767 -0.0626852 0.0481493 0.452146 -0.0631248 0.031025 0.450238 -0.0617097 0.0618167 0.449315 -0.0595496 0.0668062 0.449251 -0.05284 0.0760454 0.453474 -0.0539896 0.0742575 0.446827 -0.0429625 0.0830377 0.45025 -0.0422222 0.0832198 0.448496 -0.0456439 0.081675 0.451927 -0.0448154 0.0818622 0.450005 -0.0479296 0.0801637 0.454697 -0.0495042 0.0782487 0.451325 -0.0500768 0.0784183 0.452477 -0.0520977 0.0764452 0.455814 -0.0516084 0.0760557 0.46303 -0.0591475 0.0572448 0.460215 -0.0608311 0.0560698 0.463775 -0.0601715 0.0507401 0.465021 -0.0609388 0.0376755 0.454258 -0.0632012 0.0526347 0.453768 -0.0622517 0.0587142 0.45568 -0.0587442 0.0665846 0.45941 -0.0592935 0.0623604 0.450896 -0.0634223 0.0547397 0.450824 -0.0631727 0.0562918 0.451843 -0.0577585 0.0695788 0.45299 -0.0603813 0.0644213 0.45433 -0.0557404 0.0718723 0.458301 -0.0568451 0.0682845 0.456774 -0.0535424 0.0736463 0.461494 -0.0488571 0.075535 0.465636 -0.0501007 0.070515 0.46466 -0.0552482 0.0643382 0.465716 -0.057193 0.0580495 0.466565 -0.0584326 0.0515547 0.467296 -0.0591577 0.0449909 0.469989 -0.0573144 0.0455146 0.467963 -0.059554 0.038446 0.466139 -0.061017 0.0249342 0.467079 -0.0608118 0.0126312 0.463291 -0.0524811 0.0702384 0.460843 -0.0547408 0.0695025 0.46209 -0.0573813 0.0635604 0.464421 -0.0606964 0.0441877 0.462862 -0.0618967 0.0241084 0.455586 -0.0626985 0.0219266 0.456087 -0.0622292 0.0105607 0.458126 -0.0491607 0.0772647 0.453407 -0.0472392 0.080195 0.452082 -0.0389389 0.0841028 0.44836 -0.039436 0.0842348 0.450043 -0.0358993 0.0848607 0.456918 -0.046894 0.0794317 0.459127 -0.044365 0.0799875 0.45767 -0.0417872 0.0818072 0.455521 -0.0444331 0.0813281 0.453912 -0.0417814 0.0829047 0.455994 -0.0389902 0.0832915 0.451931 -0.0327914 0.085008 0.447796 -0.0326839 0.0851857 0.454002 -0.030217 0.0848387 0.458119 -0.0365245 0.0831745 0.454076 -0.0359861 0.0843785 0.459812 -0.0393612 0.08176 0.460393 -0.0467209 0.0778833 0.459167 -0.0512281 0.0748668 0.450247 -0.0545858 0.0740711 0.449125 -0.0557709 0.072686 0.447996 -0.0569098 0.0711761 0.463628 -0.0294921 0.081394 0.460533 -0.029619 0.0829759 0.458308 -0.0294702 0.0838212 0.458342 -0.0313695 0.0837334 0.456184 -0.0334661 0.0842141 0.460246 -0.034377 0.082686 0.463408 -0.0396815 0.0796128 0.461294 -0.0419606 0.0800167 0.4659 -0.0440589 0.0754239 0.46374 -0.0464627 0.0757034 0.469425 -0.0504527 0.0646677 0.467108 -0.0529297 0.0647021 0.470653 -0.0526023 0.0585657 0.468261 -0.0550021 0.0584864 0.471648 -0.0541445 0.0522239 0.469194 -0.0564148 0.0520469 0.472489 -0.0551863 0.0457645 0.470702 -0.0578541 0.0389762 0.46917 -0.0598173 0.0255842 0.464325 -0.0611833 0.00040032 0.454126 -0.0583 -0.0630478 0.454098 -0.0581105 -0.0637822 0.454144 -0.057511 -0.065756 0.453912 -0.0557521 -0.0699959 0.458807 -0.0521882 -0.0750749 0.460427 -0.0483803 -0.0787726 0.458119 -0.0504181 -0.077398 0.457071 -0.0575277 -0.065262 0.460015 -0.0573364 -0.0641219 0.458564 -0.0578771 -0.0633024 0.460085 -0.0584977 -0.0580522 0.458526 -0.0588886 -0.0572822 0.460312 -0.0594006 -0.0457396 0.460959 -0.0606148 -0.0221681 0.460152 -0.0590294 -0.0518826 0.463081 -0.0574057 -0.0593006 0.463569 -0.058669 -0.0467957 0.464214 -0.0500983 -0.0747409 0.463545 -0.0482579 -0.0772476 0.461208 -0.0503161 -0.0764468 0.461669 -0.0439331 -0.0815837 0.459441 -0.0462574 -0.0808565 0.45822 -0.0439387 -0.0826477 0.458855 -0.0387102 -0.0846213 0.462707 -0.0462033 -0.0795427 0.460394 -0.0414387 -0.083305 0.462621 -0.0389631 -0.0833016 0.461093 -0.0361205 -0.084555 0.46474 -0.0517197 -0.072058 0.462585 -0.0549041 -0.0683804 0.46338 -0.0336367 -0.0839645 0.463891 -0.0415594 -0.0816557 0.466069 -0.0391495 -0.0811562 0.467101 -0.0415279 -0.079279 0.464939 -0.0439136 -0.0796903 0.465805 -0.0460351 -0.0774642 0.467102 -0.049605 -0.0723848 0.467966 -0.0522895 -0.0666904 0.465908 -0.0559409 -0.060155 0.466263 -0.0569412 -0.0538684 0.46856 -0.054145 -0.0606139 0.470277 -0.0573335 -0.0354967 0.479498 -0.0480949 0.0388344 0.479717 -0.0519267 0.0139429 0.476796 -0.0542771 0.0265186 0.477711 -0.0543887 0.013876 0.473563 -0.0567544 -0.0233031 0.470848 -0.0581818 -0.0232066 0.469468 -0.0561859 -0.0480329 0.471596 -0.0534515 -0.0544938 0.469031 -0.055359 -0.0543497 0.471031 -0.0520519 -0.060684 0.470319 -0.0500463 -0.0666562 0.466519 -0.0479313 -0.0750172 0.462261 -0.0535943 -0.0712202 0.46181 -0.052059 -0.0739186 0.453827 -0.0490476 -0.0792164 0.453827 -0.0484568 -0.0797648 0.454045 -0.0487732 -0.0794742 0.457228 -0.048492 -0.0794976 0.456347 -0.0538594 -0.0731858 0.459316 -0.0537884 -0.0725586 0.456966 -0.056504 -0.0680472 0.46281 -0.0559728 -0.065428 0.465461 -0.054276 -0.0662843 0.4633 -0.0581719 -0.0530452 0.466624 -0.0575972 -0.0475603 0.464154 -0.0594467 -0.0345252 0.467342 -0.0585453 -0.0351141 0.46462 -0.060681 -0.0110731 0.467848 -0.0592952 -0.0229881 0.467723 -0.0604302 0.000677972 0.471039 -0.0588483 -0.0111186 0.470801 -0.05936 0.000918934 0.472943 -0.058268 0.013459 0.470154 -0.059703 0.0130988 0.471956 -0.0582958 0.0260616 0.474496 -0.0564499 0.026371 0.47323 -0.0558496 0.0392708 0.475542 -0.05355 0.0393381 0.47886 -0.0517741 0.0265114 0.480388 -0.0441242 0.0442825 0.481139 -0.0449486 0.0382871 0.483007 -0.0371645 0.0422611 0.483748 -0.0378178 0.0366535 0.482555 -0.0415241 0.0375573 0.482302 -0.0457632 0.0260622 0.480693 -0.0489374 0.0263568 0.475458 -0.0564994 0.0137165 0.476234 -0.0557362 -0.010992 0.473572 -0.0579646 0.00112461 0.473782 -0.057458 -0.0110762 0.476001 -0.0550012 -0.0232822 0.47296 -0.0558051 -0.0356783 0.475392 -0.0539534 -0.0356657 0.474493 -0.0523852 -0.0481246 0.472094 -0.054445 -0.0482178 0.47395 -0.0512417 -0.0543133 0.473312 -0.0496901 -0.0603819 0.471454 -0.0447663 -0.0715963 0.469344 -0.0472789 -0.0722203 0.467977 -0.0436682 -0.0771414 0.464844 -0.0365207 -0.0827333 0.465624 -0.0312266 -0.0829068 0.462859 -0.0309872 -0.084343 0.459283 -0.0330408 -0.0853493 0.454986 -0.0386384 -0.085081 0.45674 -0.0414052 -0.0840821 0.436327 -0.00600004 -0.082765 0.436327 -0.0493907 -0.0781758 0.436327 -0.0501259 -0.0734682 0.436327 -0.052492 -0.069765 0.436327 -0.0411243 -0.0810907 0.436327 -0.0438753 -0.0795499 0.436327 -0.0425231 -0.0831965 0.436327 -0.0470648 -0.0802988 0.436327 -0.0472555 -0.0767764 0.441527 0.0407205 0.0807044 0.441527 0.0447816 0.0816093 0.436827 0.0504824 -0.0777487 0.436827 0.0529574 -0.0746748 0.453853 0.0538296 -0.0733859 0.454032 0.0575558 -0.0656232 0.436846 0.057391 -0.0661054 0.454018 0.0574103 -0.0660502 0.436827 0.0557569 -0.0699868 0.436974 0.0585219 -0.0620887 0.437092 0.0589066 -0.0599819 0.454338 0.0591205 -0.0583266 0.454519 0.0593699 -0.0549326 0.453828 0.0504824 -0.0777487 0.436827 0.0494207 -0.0788544 0.436827 0.0459752 -0.0817472 0.436827 0.0427388 -0.0836476 0.453827 0.0459752 -0.0817472 0.436633 0.0377346 -0.0852966 0.449827 0.0374422 -0.085351 0.436827 0.0408711 -0.0844321 0.44361 0.0358188 -0.0855822 0.435054 0.033063 -0.0857493 0.439287 0.031 -0.085765 0.433435 0.0268837 -0.085765 0.433696 0.031 -0.085765 0.429825 0.025994 -0.085765 0.428689 0.0267061 -0.085765 0.434337 -0.0265419 -0.085765 0.427178 -0.023 -0.085765 0.428507 -0.0234822 -0.085765 0.427868 -0.0256163 -0.085765 0.427353 -0.024353 -0.085765 0.429186 0.0207277 -0.085765 0.428507 0.0225178 -0.085765 0.427178 0.023 -0.085765 0.428738 0.0244184 -0.085765 0.431783 -0.0169927 -0.085765 0.429761 -0.0184495 -0.085765 0.432478 -0.027 -0.085765 0.431688 -0.0289264 -0.085765 0.428689 -0.0267062 -0.085765 0.434337 0.0194581 -0.085765 0.436448 0.0225178 -0.085765 0.43513 0.025994 -0.085765 0.438475 0.0285638 -0.085765 0.442432 -0.0156117 -0.085765 0.441585 -0.0167139 -0.085765 0.436218 -0.0215816 -0.085765 0.436448 -0.0234822 -0.085765 0.439958 -0.0277473 -0.085765 0.440085 -0.0293942 -0.085765 0.453827 -0.0131456 -0.085765 0.451874 -0.0125354 -0.085765 0.449827 -0.0123358 -0.085765 0.447278 -0.0101477 -0.085765 0.447893 -0.0125135 -0.085765 0.442941 -0.0150801 -0.085765 0.440985 -0.00639185 -0.085765 0.436613 -0.00848297 -0.085765 0.436827 -0.00600004 -0.085765 0.436827 0.00599996 -0.085765 0.438208 0.00125273 -0.085765 0.432478 0.019 -0.085765 0.430619 0.0194581 -0.085765 0.434937 -0.0131576 -0.085765 0.443538 -0.00861212 -0.085765 0.43513 -0.020006 -0.085765 0.464383 -4.19898e-08 -0.0844072 0.464476 -0.0156545 -0.0841151 0.461031 -0.0156075 -0.0852123 0.458958 -0.00594067 -0.0855944 0.460515 -0.00312541 -0.0854043 0.454308 -0.0133707 -0.0857648 0.456672 -0.00822296 -0.0857347 0.458018 -0.0169922 -0.0856273 0.458963 -0.0185224 -0.0855419 0.459127 -0.0309971 -0.0854382 0.457447 -0.0155559 -0.0856921 0.487596 -0.0270715 0.0118554 0.484007 -0.0306257 -0.0442636 0.485263 -0.015973 -0.0439274 0.48381 -0.0159493 -0.0509604 0.481455 -0.0307308 -0.0559198 0.481987 -0.0159173 -0.0579102 0.474941 -0.0157997 -0.0744144 0.476741 -0.0158278 -0.0712897 0.459671 -0.0224062 -0.0854075 0.471731 -0.030924 -0.0773335 0.472165 -0.030919 -0.0767758 0.472861 -0.0157688 -0.0773676 0.478389 -0.0308154 -0.0652974 0.476309 -0.0308578 -0.0699955 0.475929 -0.0308646 -0.0707459 0.482652 -4.19898e-08 -0.0569878 0.461125 -0.000999688 -0.0853043 0.467646 -0.0156969 -0.0823627 0.470444 -0.0157348 -0.0800605 0.46859 -4.19898e-08 -0.0821315 0.476952 -4.19898e-08 -0.0717655 0.479688 -0.0158769 -0.0647227 0.481285 -4.19898e-08 -0.0614121 0.487942 -4.19898e-08 -0.0281876 0.488964 -4.19898e-08 -0.0155373 0.488467 -0.015987 -0.0154142 0.489263 -4.19898e-08 -0.00858715 0.489388 -4.19898e-08 -0.0010761 0.486186 -0.0304741 -0.0274662 0.485995 -0.0304924 -0.0294872 0.486763 -0.0235011 -0.0296079 0.485876 -0.030503 -0.0306627 0.486416 -0.0159885 -0.0368411 0.487853 -0.0234516 -0.015355 0.488319 -0.0203269 0.0114419 0.48887 -0.0159463 -0.00106955 0.487007 -0.0303643 -0.0152911 0.486124 -4.19898e-08 -0.041407 0.487315 -0.015996 -0.0297197 0.485473 -0.0305354 -0.0342625 0.485184 -0.0305561 -0.0365574 0.484474 -0.0306004 -0.0414626 0.484123 -0.0306196 -0.0435943 0.46017 0.030995 -0.085219 0.461299 0.0244856 -0.085015 0.461294 0.0257047 -0.0849945 0.461894 0.0309905 -0.0847116 0.488871 0.0159434 -0.00037951 0.488656 0.0158864 0.0112496 0.482358 0.0306984 -0.0523383 0.482954 0.0159343 -0.0544322 0.461304 0.0232665 -0.085035 0.462772 0.0309875 -0.084379 0.462997 0.0156344 -0.0846769 0.465109 0.0309771 -0.0832265 0.466143 0.0156767 -0.0832952 0.465909 0.0309726 -0.0827351 0.46873 0.030953 -0.0805546 0.469176 0.0309492 -0.0801395 0.475525 0.0158085 -0.0734634 0.474745 0.0308839 -0.0728999 0.47861 0.0158585 -0.0673624 0.478318 0.0308169 -0.0654769 0.479001 0.0308009 -0.0636966 0.481026 0.0159002 -0.0609764 0.485613 -4.19898e-08 -0.0442608 0.466208 -4.19898e-08 -0.0835985 0.470577 -4.19898e-08 -0.0804867 0.468987 0.0157148 -0.0813589 0.472326 -4.19898e-08 -0.0786703 0.471481 0.0157491 -0.078993 0.473646 0.0157802 -0.0763289 0.475796 -4.19898e-08 -0.0738202 0.485465 -4.19898e-08 -0.0450366 0.483245 -4.19898e-08 -0.0548316 0.47909 -4.19898e-08 -0.0672455 0.48904 -4.19898e-08 -0.0141091 0.487539 0.0159966 -0.0275837 0.488795 0.0135601 0.0111703 0.485473 0.0305354 -0.0342637 0.485267 0.0235209 -0.0409418 0.486186 0.0304741 -0.0274662 0.487069 0.0303515 -0.0138854 0.487747 -4.19898e-08 -0.0299531 0.484507 0.0159609 -0.0477928 0.485758 0.0159801 -0.0410926 0.486976 0.0234953 -0.0274794 0.488538 0.0159843 -0.0139973 0.487596 0.0270714 0.0118554 0.487363 0.0302297 -0.000378577 0.487493 0.0278538 0.0119383 0.463396 0.0337086 -0.0839497 0.459301 0.0538289 -0.0724988 0.448009 0.0603659 0.0652207 0.453739 0.0622598 0.0587034 0.480381 0.0441301 0.0443008 0.476862 0.0501506 0.0455079 0.446827 0.0493344 0.0792351 0.448479 0.0456724 0.0816594 0.463628 0.029492 0.0813939 0.464498 0.0307806 0.0807696 0.475378 0.0317788 0.0683695 0.486618 0.0331222 0.0141461 0.487238 0.0303072 -0.0089706 0.48588 0.0305026 -0.0306265 0.483533 0.0306488 -0.0468401 0.456754 0.0414776 -0.0840516 0.453827 0.0408711 -0.0844321 0.456331 0.0539007 -0.0731228 0.455548 0.0627 0.0219357 0.45472 0.0624893 0.0164698 0.456047 0.0622301 0.010576 0.464294 0.0611892 0.000425892 0.454258 0.058907 -0.0599828 0.454078 0.0579628 -0.0643128 0.453833 0.0518372 -0.0761615 0.455774 0.0523422 -0.0754297 0.453827 0.04955 -0.0787257 0.465641 0.0312963 -0.0828936 0.465488 0.030975 -0.0830002 0.469058 0.0317136 -0.0801992 0.472001 0.0316746 -0.0769204 0.47084 0.0309335 -0.0783995 0.478174 0.0332093 -0.065278 0.479345 0.0358033 -0.0608418 0.480096 0.0307722 -0.0605216 0.483993 0.0306263 -0.0443441 0.48448 0.0306 -0.0414259 0.48576 0.0313366 -0.0308004 0.486762 0.0304053 -0.01984 0.485072 0.0376409 0.024812 0.484937 0.0353471 0.0315243 0.483744 0.0378212 0.036672 0.48214 0.0361551 0.0476548 0.485227 0.0299033 0.0358045 0.483003 0.0371671 0.0422776 0.479968 0.03303 0.0574837 0.48186 0.0297524 0.0525244 0.481145 0.0347407 0.0527264 0.476979 0.029634 0.065729 0.453988 0.0302294 0.0848407 0.451916 0.0328091 0.0850084 0.447783 0.0327098 0.0851849 0.450029 0.0359228 0.0848583 0.446827 0.0360519 0.0849239 0.446827 0.0417028 0.0835397 0.447934 0.0629851 0.0576418 0.450652 0.0638026 0.0476624 0.454548 0.0633916 0.0463867 0.452458 0.0636547 0.0494795 0.476427 0.0308555 -0.0697554 0.472927 0.0309095 -0.0757368 0.470162 0.0342518 -0.0787302 0.476351 0.0420646 -0.0641321 0.473306 0.0497179 -0.0603371 0.474526 0.044931 -0.0653226 0.473416 0.0421278 -0.0705153 0.477258 0.0442741 -0.0587239 0.475389 0.0471105 -0.05969 0.481788 0.0476634 -0.0225238 0.479513 0.0492684 -0.0350523 0.480285 0.044401 -0.0462878 0.477988 0.0460114 -0.0530175 0.479661 0.0429911 -0.0519909 0.475382 0.0539685 -0.0356246 0.477569 0.0517873 -0.0354271 0.478168 0.0529224 -0.0231117 0.478402 0.0536809 -0.0108343 0.476079 0.0487724 -0.0537845 0.473942 0.0512645 -0.0542682 0.476656 0.0500365 -0.0477248 0.47859 0.047367 -0.0471216 0.480096 0.0504769 -0.0228699 0.480198 0.0517275 0.00158352 0.483216 0.0323919 -0.0475579 0.483919 0.0337201 -0.0425544 0.484955 0.0356606 -0.031946 0.485573 0.0368827 -0.0208945 0.483256 0.044468 -0.0220771 0.483933 0.039609 -0.032949 0.482689 0.0431874 -0.0338053 0.482949 0.0375823 -0.0439921 0.482476 0.0306939 -0.0518335 0.480306 0.0379536 -0.0559573 0.481438 0.0307313 -0.0559823 0.482296 0.0457713 0.0260855 0.483034 0.0459201 0.0138466 0.474773 0.0528002 0.0457694 0.473904 0.0516529 0.0521159 0.472868 0.0500247 0.058319 0.471589 0.0478455 0.0642692 0.470638 0.052612 0.0585793 0.469982 0.0450709 0.0698123 0.46941 0.0504621 0.0646796 0.474921 0.047268 0.0577392 0.471988 0.0424353 0.0688779 0.469488 0.0333364 0.0761874 0.475606 0.0369497 0.0659893 0.482551 0.0415293 0.0375767 0.484864 0.0383907 0.0251029 0.485279 0.0375729 0.022221 0.464425 0.0294971 0.0808973 0.46612 0.0295084 0.0797058 0.467492 0.035409 0.0776903 0.469963 0.0392324 0.0736746 0.471876 0.0367869 0.072244 0.473618 0.0451044 0.0635058 0.475978 0.0489387 0.051709 0.4795 0.0429215 0.0501275 0.47949 0.048103 0.0388547 0.481133 0.0449554 0.038307 0.483687 0.0422541 0.0256576 0.485529 0.0383896 0.0134142 0.470299 0.0295423 0.0758471 0.471438 0.0312581 0.0743206 0.473691 0.0343062 0.0704699 0.478553 0.031171 0.0619228 0.47718 0.0392816 0.0610317 0.478455 0.0412929 0.0557215 0.455056 0.0631244 0.0339343 0.463681 0.0616061 0.0120727 0.452677 0.0629995 0.0281552 0.451256 0.0636741 0.0443307 0.459309 0.0624615 0.0231177 0.462833 0.0619029 0.0241232 0.47078 0.0593693 0.000946775 0.464397 0.0607057 0.0441983 0.467275 0.0591677 0.0450041 0.464997 0.0609475 0.0376883 0.472925 0.0582781 0.0134836 0.4777 0.0543997 0.0139021 0.478245 0.0541667 0.00146886 0.479707 0.0519375 0.0139693 0.481914 0.0489141 0.00167329 0.480326 0.0512523 -0.0106696 0.483487 0.0452508 -0.0102221 0.452276 0.0627719 0.0575383 0.451593 0.0610962 0.0631552 0.44881 0.0622584 0.0603288 0.449014 0.0634207 0.0553074 0.452963 0.0603921 0.0644065 0.450209 0.0617188 0.0617955 0.452316 0.0634519 0.0533203 0.450792 0.0631779 0.0562751 0.447133 0.0525177 0.0764207 0.448084 0.0510255 0.0778134 0.449986 0.0479547 0.0801475 0.446832 0.0521381 0.0767954 0.446837 0.0529757 0.0759581 0.485832 0.0381094 0.00182098 0.483414 0.0457138 0.00174104 0.481481 0.049114 0.013949 0.47885 0.0517841 0.0265347 0.475444 0.0565101 0.0137419 0.474481 0.0564603 0.026393 0.471937 0.0583057 0.0260823 0.467941 0.0595636 0.0384612 0.466545 0.0584431 0.051566 0.46019 0.0608413 0.0560721 0.463007 0.0591582 0.0572508 0.462068 0.0573925 0.0635639 0.463272 0.0524921 0.0702433 0.463724 0.0464725 0.0757094 0.46562 0.0501107 0.0705229 0.463394 0.0396893 0.0796192 0.457259 0.0622093 0.0545275 0.460822 0.0547526 0.0695036 0.461476 0.0488686 0.075538 0.447332 0.0608771 0.0640931 0.449288 0.0595638 0.0667809 0.447971 0.0569302 0.0711473 0.449101 0.0557912 0.0726608 0.44923 0.0528633 0.0760226 0.451305 0.0500988 0.0784024 0.452067 0.0389601 0.0840993 0.462359 0.0324951 0.0818877 0.46191 0.0371583 0.0813087 0.460375 0.0467328 0.0778854 0.458278 0.0568572 0.0682809 0.459386 0.0593045 0.0623598 0.454306 0.0557553 0.0718599 0.458106 0.0491747 0.0772625 0.456899 0.0469093 0.0794287 0.459797 0.0393715 0.0817639 0.454677 0.0495218 0.0782399 0.452455 0.0521169 0.0764302 0.453387 0.0472591 0.0801855 0.455503 0.04445 0.0813246 0.455977 0.0390049 0.0832923 0.456169 0.0334776 0.0842168 0.455792 0.0516241 0.076048 0.457653 0.0418007 0.0818083 0.458104 0.0365353 0.0831778 0.458329 0.0313773 0.0837375 0.456752 0.0535566 0.0736399 0.459147 0.051241 0.0748656 0.45911 0.0443775 0.079989 0.461279 0.0419705 0.0800212 0.460232 0.0343846 0.0826909 0.460521 0.0296242 0.0829809 0.486994 0.0311352 0.0129161 0.487363 0.0302097 0.0018405 0.480686 0.0489467 0.0263802 0.477622 0.0509721 0.0392088 0.476784 0.0542875 0.0265415 0.475529 0.0535597 0.0393577 0.470684 0.0578642 0.0389933 0.473215 0.0558597 0.0392894 0.472474 0.0551963 0.0457815 0.469971 0.0573246 0.04553 0.471633 0.0541543 0.0522391 0.469176 0.0564252 0.0520604 0.468244 0.0550125 0.0584982 0.467091 0.0529399 0.0647119 0.467857 0.047632 0.0703699 0.458796 0.0522337 -0.0750173 0.458112 0.0504687 -0.0773432 0.455021 0.0506516 -0.0775323 0.454046 0.0488305 -0.0794206 0.45403 0.0565359 -0.0682995 0.454114 0.0575352 -0.0656843 0.459991 0.0573603 -0.0640591 0.458496 0.0588994 -0.0572188 0.458537 0.0578983 -0.0632375 0.456894 0.0591758 -0.0563514 0.457045 0.0583334 -0.0623062 0.459872 0.0564177 -0.0669914 0.456942 0.0565343 -0.0679808 0.453917 0.055896 -0.0697023 0.453918 0.055903 -0.0696879 0.463059 0.0574243 -0.0592426 0.462791 0.0560009 -0.0653696 0.457044 0.057552 -0.0651949 0.454128 0.0583115 -0.0630035 0.454161 0.0584982 -0.0621978 0.459442 0.0463167 -0.0808121 0.457227 0.0485479 -0.0794465 0.460424 0.0484341 -0.0787238 0.461799 0.0521026 -0.073864 0.456129 0.0604404 -0.0304579 0.457028 0.0608292 -0.0215218 0.460284 0.0594081 -0.0456842 0.464526 0.0601115 -0.0226042 0.456827 0.0597999 -0.0443368 0.460058 0.0585114 -0.0579905 0.463546 0.0586795 -0.0467426 0.463277 0.0581848 -0.0529892 0.460404 0.041506 -0.0832739 0.458228 0.0440042 -0.0826092 0.456114 0.0464667 -0.0812981 0.454744 0.0442 -0.0828651 0.453827 0.0484567 -0.0797648 0.459305 0.03312 -0.0853407 0.4612 0.0503648 -0.0763946 0.464729 0.0517604 -0.0720064 0.467105 0.0415833 -0.0792468 0.457061 0.0358277 -0.0854361 0.45887 0.038784 -0.0845989 0.464856 0.0365869 -0.0827119 0.466077 0.0392101 -0.081129 0.476799 0.0363238 -0.0673351 0.477962 0.0390206 -0.0626266 0.485848 0.0376344 -0.00961783 0.481218 0.0464044 -0.0345089 0.481739 0.0411403 -0.0452399 0.481092 0.0397163 -0.0507274 0.478901 0.0412201 -0.0574698 0.475376 0.0330365 -0.071427 0.475205 0.039297 -0.0690939 0.473771 0.0358787 -0.0734188 0.471986 0.038607 -0.0750564 0.467014 0.0341574 -0.0816689 0.468177 0.0367577 -0.0801455 0.461109 0.0361938 -0.0845376 0.461271 0.0309923 -0.0849165 0.459042 0.0329863 -0.085398 0.467978 0.0437189 -0.0771049 0.456879 0.0614059 -0.00834422 0.460926 0.0606196 -0.0221287 0.467826 0.0593044 -0.0229495 0.464128 0.0594552 -0.034479 0.467321 0.0585559 -0.0350693 0.466605 0.0576105 -0.0475096 0.466244 0.0569577 -0.0538153 0.46589 0.0559632 -0.0601005 0.462568 0.0549375 -0.0683227 0.465446 0.054307 -0.0662302 0.462247 0.0536329 -0.0711637 0.459651 0.0552323 -0.0698144 0.456713 0.0553067 -0.0706324 0.453869 0.0545097 -0.0722851 0.466514 0.0479777 -0.0749727 0.471021 0.0520788 -0.0606362 0.467955 0.0523224 -0.0666403 0.471585 0.0534729 -0.0544462 0.468546 0.0541701 -0.0605628 0.469016 0.0553784 -0.0542994 0.472947 0.0558191 -0.035636 0.47026 0.057346 -0.0354531 0.47102 0.0588582 -0.0110858 0.467053 0.0608195 0.0126529 0.458542 0.0627328 0.0354212 0.457738 0.0626926 0.0481503 0.456605 0.0609471 0.0607357 0.454228 0.0632076 0.0526278 0.455655 0.0587561 0.0665756 0.453451 0.0540065 0.0742436 0.451817 0.0577732 0.0695601 0.450224 0.0546059 0.0740494 0.453895 0.0418004 0.082901 0.451909 0.0448379 0.0818526 0.454061 0.0360022 0.084379 0.456595 0.061773 6.20069e-05 0.467698 0.060438 0.000704802 0.46459 0.0606874 -0.0110411 0.47083 0.0581926 -0.0231685 0.469453 0.0562017 -0.0479845 0.467095 0.0496468 -0.0723378 0.464206 0.0501439 -0.0746914 0.465804 0.0460862 -0.077423 0.463541 0.0483084 -0.0772011 0.462707 0.046259 -0.0795 0.464941 0.0439698 -0.0796533 0.461673 0.0439943 -0.0815459 0.455006 0.0387181 -0.085061 0.462632 0.0390304 -0.0832763 0.463897 0.041621 -0.0816238 0.470046 0.0412222 -0.0762998 0.471453 0.0448076 -0.0715572 0.469341 0.0473208 -0.0721775 0.472507 0.0476087 -0.0661604 0.470312 0.0500802 -0.0666098 0.472082 0.0544628 -0.0481714 0.474484 0.0524044 -0.0480803 0.47599 0.0550142 -0.023245 0.473548 0.0567665 -0.0232655 0.476221 0.0557481 -0.010959 0.473766 0.0574691 -0.0110432 0.476037 0.0562449 0.00132637 0.473555 0.0579751 0.00115321 0.470132 0.0597121 0.0131221 0.469149 0.0598265 0.0256034 0.466113 0.0610249 0.0249514 0.461859 0.0620059 0.0366741 0.460811 0.06161 0.049608 0.463752 0.0601816 0.0507485 0.465696 0.0572039 0.0580587 0.464641 0.0552591 0.0643452 0.467965 0.0416557 0.0747444 0.465886 0.0440673 0.0754321 0.465462 0.0375134 0.078835 0.463996 0.0351237 0.0805001 0.461659 0.0294825 0.0824628 0.458382 0.0294702 0.0837964 0.448346 0.0394647 0.0842275 0.450234 0.0422477 0.0832108 0.446827 0.0433727 0.0828575 0.458575 -0.0309697 -0.0814726 0.483403 -0.0295999 0.00299215 0.484731 -0.0129043 0.0131655 0.483646 -0.0257416 0.0137954 0.484245 -0.0230701 0.00118069 0.483373 -0.0277861 0.0141595 0.481784 -0.0300617 -0.0315502 0.482192 -0.03 -0.0275273 0.482951 -0.0232418 -0.0276122 0.482688 -0.0299043 -0.0213837 0.483272 -0.0297286 -0.00922504 0.478565 -0.0303954 -0.0510447 0.475727 -0.0305447 -0.0609952 0.476229 -0.0157938 -0.062562 0.475327 -0.0305611 -0.0621164 0.472007 -0.0306636 -0.0696193 0.460308 -0.0156544 -0.0812746 0.457556 -0.0249983 -0.0816484 0.457551 -0.0265309 -0.0816437 0.457305 -0.0286038 -0.0816621 0.456629 -0.0304458 -0.081712 0.453827 -0.0165982 -0.081765 0.457273 -0.0156448 -0.081695 0.455651 -0.00526911 -0.081757 0.457428 -0.00340193 -0.081702 0.467905 -0.0156534 -0.076947 0.465482 -0.030811 -0.0780852 0.467628 -0.0307618 -0.0759987 0.462797 -4.97487e-08 -0.0807292 0.463071 -0.015643 -0.0803628 0.469983 -0.0156791 -0.0745521 0.465598 -0.0156397 -0.0789134 0.466495 -3.95477e-08 -0.0787058 0.480159 -0.015856 -0.0489786 0.47945 -3.81641e-08 -0.0535379 0.478413 -0.0158324 -0.0558731 0.476402 -5.30671e-08 -0.0632031 0.473477 -0.0157403 -0.0688935 0.484946 -0.00802842 -0.0133319 0.485256 -0.00800543 0.00118513 0.484872 -0.015763 0.00118279 0.481553 -0.0158665 -0.0419577 0.483949 -4.17805e-08 -0.0279024 0.483508 -0.0158559 -0.0276984 0.484183 -4.23788e-08 -0.0256174 0.483955 -0.0231595 -0.013248 0.48457 -0.0158163 -0.0132877 0.48107 -0.0233049 -0.0418219 0.459133 0.023245 -0.0814314 0.45883 0.0271653 -0.0814516 0.459311 0.0309572 -0.0813111 0.459693 0.0156552 -0.0814014 0.467265 0.0156478 -0.0775606 0.474386 0.0157579 -0.0670131 0.471232 0.015699 -0.0727852 0.473536 0.0306213 -0.0665228 0.472133 0.0306599 -0.0693829 0.477713 0.0304478 -0.054467 0.483054 0.0232359 -0.0265307 0.481917 0.0300464 -0.030311 0.483294 0.0297197 -0.00838705 0.484244 0.0230678 0.00153068 0.483395 0.0295959 0.00393618 0.4843 0.0193379 0.0134159 0.483646 0.0257415 0.0137954 0.480505 0.0158594 -0.047386 0.47689 0.015806 -0.0607197 0.464958 0.0156388 -0.0793449 0.468089 -4.54414e-08 -0.0773325 0.461634 0.0309084 -0.0805174 0.459827 -4.63762e-08 -0.0814676 0.462441 0.0156456 -0.0806258 0.463253 -4.59763e-08 -0.080555 0.465143 -5.19287e-08 -0.0796181 0.469218 -4.68949e-08 -0.076147 0.469358 0.01567 -0.0753403 0.470176 -4.16443e-08 -0.0749898 0.472632 -3.3148e-08 -0.0713098 0.473696 -3.60242e-08 -0.0693593 0.478694 -4.67871e-08 -0.0562773 0.481308 0.0232995 -0.0403947 0.483986 0.0231549 -0.0125289 0.484871 0.0157615 0.00153372 0.485071 -4.19685e-08 -0.0133847 0.484979 0.00802736 -0.0126081 0.482145 -4.03702e-08 -0.040948 0.478894 0.0158396 -0.0541385 0.479335 0.0303349 -0.0475135 0.481798 0.015867 -0.0405253 0.482088 0.00803153 -0.040665 0.483617 0.0158536 -0.0266132 0.483957 0.00803891 -0.0267034 0.484602 0.0158137 -0.0125664 0.485254 0.00800467 0.00153714 0.485323 -4.23719e-08 -0.00627314 0.445193 0.0332641 -0.0817428 0.443912 0.0324508 -0.0817591 0.435634 0.0330536 -0.0817484 0.434327 0.031 -0.081765 0.44772 0.0341438 -0.0817058 0.436871 0.0361856 -0.0815038 0.453825 0.0361975 -0.0815016 0.453824 0.0350993 -0.0816346 0.437327 0.0404951 -0.0802763 0.437327 0.0450102 -0.0774568 0.453828 0.0457781 -0.076794 0.453824 0.0477911 -0.0747592 0.437327 0.0465727 -0.0760451 0.453834 0.0492054 -0.0730287 0.437328 0.0524684 -0.0675967 0.453929 0.0524679 -0.0675964 0.453994 0.0533521 -0.0655058 0.454121 0.0543941 -0.0621796 0.454179 0.0546715 -0.0609576 0.43775 0.0551647 -0.0576962 0.438161 0.0554266 -0.0535905 0.454433 0.0552947 -0.0561427 0.454585 0.0554266 -0.0535905 0.436387 -0.0261175 -0.081765 0.434327 -0.031 -0.081765 0.440409 0.000523405 -0.081765 0.442405 0.031 -0.081765 0.432806 0.0292671 -0.081765 0.443282 -0.031 -0.081765 0.437352 0.0218874 -0.081765 0.437352 0.0241126 -0.081765 0.440229 0.0248349 -0.081765 0.436387 0.0261174 -0.081765 0.440368 0.0264943 -0.081765 0.44795 -0.0070289 -0.081765 0.436387 -0.0198826 -0.081765 0.444677 -0.017421 -0.081765 0.432478 0.018 -0.081765 0.444474 -0.00561913 -0.081765 0.443048 -0.00445392 -0.081765 0.442123 -0.0218746 -0.081765 0.444243 -0.017826 -0.081765 0.437327 -0.00600004 -0.081765 0.433669 0.0158165 -0.081765 0.434647 0.0184951 -0.081765 0.436905 0.0095336 -0.081765 0.440903 -0.00120438 -0.081765 0.441819 -0.00296047 -0.081765 0.432478 -0.018 -0.081765 0.433911 -0.0155288 -0.081765 0.453827 -0.00636757 -0.081765 0.48551 -0.0261716 0.0365999 0.484072 -0.0298396 0.0428773 0.485227 -0.0299034 0.0358045 0.482808 -0.0155056 0.0529058 0.480955 -0.0297248 0.0556016 0.479116 -0.0296774 0.0608522 0.480003 -0.0153931 0.0612721 0.476216 -0.0152708 0.0692519 0.470188 -0.0295411 0.0759688 0.472652 -0.0295682 0.0729578 0.464721 -0.0294984 0.0807026 0.467799 -0.0150735 0.0794661 0.461655 -0.0294825 0.0824649 0.451274 -0.014798 0.0851697 0.45108 -0.0294582 0.0851549 0.454627 -0.0294619 0.0847429 0.455695 -0.0148666 0.0847313 0.460013 -0.0149357 0.0836889 0.455696 -4.19898e-08 0.0848299 0.460039 -4.19898e-08 0.0839186 0.464162 -4.19898e-08 0.0822801 0.464096 -0.0150049 0.0819284 0.471044 -0.0151408 0.0764309 0.473833 -0.0152066 0.0729832 0.476389 -4.19898e-08 0.069731 0.484898 -0.0156071 0.0443382 0.451274 0.0294582 0.0851426 0.454773 0.0294618 0.0847171 0.460013 0.0149356 0.0836889 0.484898 0.0156071 0.0443382 0.483836 0.0298286 0.0441012 0.446827 0.0147287 0.085235 0.451274 0.0147979 0.0851697 0.446827 -4.19898e-08 0.085235 0.451269 -4.19898e-08 0.0851828 0.455695 0.0148665 0.0847313 0.467906 -4.19898e-08 0.079901 0.471183 -4.19898e-08 0.0769067 0.473992 -4.19898e-08 0.0734699 0.476216 0.0152707 0.0692519 0.480003 0.015393 0.0612721 0.4802 -4.19898e-08 0.0617132 0.483039 -4.19898e-08 0.0532972 0.485177 -4.19898e-08 0.0446747 0.482392 0.0297707 0.0505224 0.482808 0.0155055 0.0529058 0.480813 0.0297206 0.0560513 0.478954 0.0296742 0.0612606 0.475395 0.0296067 0.0687215 0.474963 0.0296001 0.0694609 0.473833 0.0152065 0.0729832 0.472718 0.0295694 0.0728673 0.471044 0.0151407 0.0764309 0.467485 0.0295172 0.0786003 0.467799 0.0150734 0.0794661 0.464096 0.0150049 0.0819284 0.43172 -0.0234185 0.085235 0.431167 -0.0251078 0.085235 0.432076 -0.026079 0.085235 0.434503 -0.0258838 0.085235 0.430201 -0.0226514 0.085235 0.430528 -0.0239408 0.085235 0.43649 -0.0288937 0.085235 0.436418 -0.0258838 0.085235 0.438113 -0.0249941 0.085235 0.437129 -0.0294575 0.085235 0.446827 -0.0294575 0.0852349 0.4392 -0.0234185 0.085235 0.439431 -0.0215179 0.085235 0.437727 -0.00600004 0.085235 0.437727 0.00599996 0.085235 0.430204 -0.0213211 0.085235 0.43756 -0.00825944 0.085235 0.435132 -0.014555 0.085235 0.432168 0.0242722 0.085235 0.433601 0.0255418 0.085235 0.435267 0.0279729 0.085235 0.43546 0.026 0.085235 0.437319 0.0255418 0.085235 0.438752 0.0242722 0.085235 0.446827 0.0294574 0.0852349 0.439431 0.0224821 0.085235 0.446827 -0.0147288 0.085235 0.433738 -0.0163411 0.085235 0.432098 -0.0179034 0.085235 0.433601 -0.0184582 0.085235 0.432168 -0.0197278 0.085235 0.430539 -0.0200335 0.085235 0.431489 0.0224821 0.085235 0.430176 0.0215863 0.085235 0.432098 0.0179033 0.085235 0.436418 0.0181162 0.085235 0.433738 0.016341 0.085235 0.435132 0.0145549 0.085235 0.436249 0.0125836 0.085235 0.437064 0.0104698 0.085235 0.435049 -0.0330535 -0.0857495 0.433696 -0.031 -0.085765 0.440472 -0.031 -0.085765 0.436317 -0.0362512 -0.0855317 0.436827 -0.0473792 -0.0806867 0.436827 -0.0464861 -0.081379 0.453827 -0.0464861 -0.081379 0.436827 -0.0427388 -0.0836476 0.453827 -0.0413468 -0.0842526 0.436827 -0.0401532 -0.0846779 0.45383 -0.0514793 -0.0766016 0.45388 -0.0548794 -0.0716457 0.436827 -0.055757 -0.0699868 0.453915 -0.0558092 -0.06988 0.454009 -0.0573074 -0.0663411 0.45403 -0.0575388 -0.0656739 0.436977 -0.0585354 -0.0620258 0.454156 -0.0584727 -0.0623097 0.454281 -0.0589735 -0.0595231 0.445169 -0.0598367 -0.0442868 0.454585 -0.0594229 -0.053765 0.456146 -0.0604521 -0.0301938 0.454658 -0.0625064 0.0168582 0.447389 -0.0622674 0.0113842 0.45658 -0.0617841 0.000314464 0.456874 -0.061427 -0.00786337 0.456786 -0.0610317 -0.0169185 0.443504 -0.0598526 -0.0439238 0.437646 -0.0594229 -0.053765 0.442077 -0.0599006 -0.0428253 0.441473 -0.0599446 -0.0418175 0.441261 -0.0599741 -0.0411398 0.439213 -0.059883 -0.0432272 0.441261 -0.0600486 -0.0394338 0.44206 -0.0601213 -0.0377701 0.446834 -0.0601702 -0.0366498 0.445169 -0.060186 -0.0362868 0.446839 -0.0615674 -0.00464903 0.446009 -0.0613079 -0.0105906 0.449077 -0.0600486 -0.0394338 0.455236 -0.0598653 -0.0436321 0.449077 -0.0599741 -0.0411398 0.446436 0.0614294 -0.00780677 0.445169 0.0601859 -0.0362868 0.4559 0.0621176 0.00795595 0.444242 0.0609073 -0.0197654 0.439953 0.0600526 -0.0393419 0.437646 0.0594228 -0.053765 0.454585 0.0594228 -0.053765 0.447457 0.0621232 0.00808366 0.439567 0.0599662 -0.0413197 0.446834 0.0598525 -0.0439238 0.455239 0.059867 -0.0435914 0.445344 0.0632923 0.0348602 0.456776 0.0610163 -0.0172684 0.447349 0.0618525 0.00188458 0.441473 0.0600781 -0.0387561 0.449169 0.0600113 -0.0402868 0.449077 0.0600485 -0.0394338 0.448864 0.0600781 -0.0387561 0.442027 0.0488084 0.0796358 0.446827 0.0474559 0.0805902 0.442027 0.0450168 0.0820505 0.442027 0.0417028 0.0835397 0.442027 0.0408773 0.0838281 0.446864 0.0549418 0.0737643 0.446963 0.0574138 0.0704481 0.447147 0.0595873 0.0667931 0.442421 0.0607793 0.0643178 0.447437 0.0614185 0.0627706 0.447814 0.0627133 0.0587632 0.442894 0.0629851 0.0576418 0.443131 0.0634859 0.0549156 0.445604 0.0636403 0.0536815 0.445225 0.063702 0.0530559 0.444936 0.0637645 0.0522691 0.444812 0.0638273 0.0511022 0.443601 0.0638553 0.0500766 0.44518 0.0638606 0.0495539 0.446376 0.0638469 0.0480489 0.449635 0.0637452 0.045235 0.449317 0.0638253 0.0472515 0.436327 0.0501382 -0.0734515 0.436327 0.0525498 -0.0743852 0.436327 0.0470647 -0.0802988 0.436327 0.04 -0.0815559 0.436327 0.0411774 -0.0837819 0.441527 -0.0485095 0.079235 0.44157 -0.0516859 0.0729252 0.441684 -0.0547798 0.0689507 0.441706 -0.0581049 0.0683972 0.442231 -0.0619687 0.0595482 0.442632 -0.06299 0.0548061 0.443624 -0.0607482 0.0452533 0.44363 -0.0632458 0.0452005 0.445075 -0.0602077 0.0328718 0.446343 -0.0596671 0.020522 0.446837 -0.0613409 0.00164986 0.446359 -0.0610745 -0.00442082 0.446342 -0.0610678 -0.00457146 0.446396 -0.0585846 -0.00408263 0.444428 -0.0580433 -0.0163898 0.441741 -0.0575064 -0.0286621 0.441652 -0.0599964 -0.0290573 0.439114 -0.056969 -0.0410041 0.437284 -0.0564684 -0.0525371 0.43675 -0.0561552 -0.0577586 0.436745 -0.0586659 -0.0578183 0.441527 0.0439157 0.079235 0.441527 0.0485095 0.079235 0.437168 0.0564257 -0.0535204 0.437149 0.0589233 -0.0536869 0.436479 0.0554897 -0.0618534 0.436474 0.0580331 -0.0619591 0.436327 0.0553088 -0.069765 0.439076 0.0594667 -0.0412044 0.439096 0.0569647 -0.0411017 0.437284 0.0564683 -0.0525371 0.441693 0.0600042 -0.0288763 0.444388 0.060541 -0.0165922 0.444441 0.058046 -0.0163264 0.445506 0.0582998 -0.0105471 0.446378 0.0610822 -0.00424248 0.44685 0.061353 0.00192893 0.44636 0.05857 -0.0044106 0.446958 0.0591171 0.008002 0.441887 0.0572671 0.0646864 0.441922 0.0603215 0.0640873 0.443078 0.0608489 0.0502691 0.445081 0.0602056 0.0328241 0.44449 0.0629248 0.0378478 0.445081 0.0627052 0.0328198 0.446349 0.0621646 0.0204536 0.449669 0.0560084 -0.040265 0.443293 0.0566185 -0.0262916 0.441234 0.0561038 -0.0380811 0.447559 0.055842 -0.0440776 0.443998 0.0558187 -0.04461 0.439759 0.0558911 -0.0429536 0.440982 0.0559364 -0.0419142 0.456245 0.0579764 0.00480767 0.44634 0.0561981 -0.03592 0.445169 0.0562049 -0.035765 0.449635 0.0597491 0.0454095 0.451623 0.0592525 0.0340346 0.447349 0.0586634 0.0205425 0.455262 0.0583366 0.0130582 0.43785 -0.0294575 0.081235 0.443527 -0.0294575 0.081235 0.439866 -0.0318918 0.0812165 0.441344 -0.0346066 0.081064 0.443527 -0.0331 0.0811734 0.441619 -0.0353012 0.0809874 0.444559 -0.0353182 0.0809853 0.442238 -0.0374909 0.0806145 0.44543 -0.0358232 0.0809174 0.446427 -0.04 0.0799014 0.446427 -0.036 0.0808911 0.442527 -0.0403724 0.079767 0.443527 -0.0429 0.0786444 0.442527 -0.0456268 0.0769974 0.443527 -0.0456268 0.0769973 0.44256 -0.050486 0.0727728 0.443537 -0.0504859 0.0727727 0.442684 -0.0539522 0.0684276 0.444285 -0.0522022 0.0707956 0.442739 -0.0548031 0.0671129 0.445158 -0.0528546 0.069959 0.446427 -0.0531466 0.0695677 0.448072 -0.0593074 0.0556743 0.44575 -0.0530667 0.0696756 0.442888 -0.0563933 0.0642547 0.447072 -0.0553966 0.0661149 0.447329 -0.0571891 0.062544 0.443112 -0.0578692 0.0608492 0.447483 -0.0578693 0.0608486 0.446559 -0.0594041 0.055132 0.446853 -0.0593773 0.055288 0.445794 -0.059493 0.0545757 0.444309 -0.0598179 0.051235 0.444077 -0.0598502 0.0503074 0.444912 -0.0598602 0.048985 0.44428 -0.0598537 0.0484362 0.445285 -0.0598537 0.0484369 0.449635 -0.0597492 0.0454095 0.447463 -0.0576164 -0.00343859 0.443998 -0.0561982 -0.03592 0.442919 -0.0558384 -0.0441621 0.447854 -0.0578564 0.00205873 0.45472 -0.0584932 0.0166444 0.449103 -0.0561039 -0.0380811 0.456543 -0.0567643 -0.022956 0.447419 -0.0561787 -0.0363679 0.456595 -0.0577769 0.00023657 0.445409 -0.0570442 -0.0165432 0.445169 -0.056205 -0.035765 0.445565 -0.0562042 -0.0357825 0.442919 -0.0561787 -0.0363679 0.440669 -0.0560085 -0.040265 0.442778 -0.0558421 -0.0440776 0.438161 -0.0554267 -0.0535905 0.444772 -0.0558128 -0.0447475 0.448132 -0.0558607 -0.0436517 0.449066 -0.0559103 -0.0425149 0.456129 -0.0564443 -0.0302833 0.444618 -0.0597492 0.0454095 0.452677 -0.0590034 0.0283298 0.44727 -0.0587038 0.0214667 0.453828 -0.0457782 -0.076794 0.437327 -0.0458213 -0.0767553 0.453827 -0.0477566 -0.0747985 0.437327 -0.0493232 -0.0728714 0.453844 -0.0499518 -0.0719924 0.437327 -0.0499396 -0.0720102 0.437327 -0.0516139 -0.0692865 0.454176 -0.0546592 -0.0610215 0.454146 -0.0545208 -0.0616543 0.454001 -0.0534649 -0.0652045 0.437563 -0.0548176 -0.0601995 0.454331 -0.0551305 -0.058018 0.454433 -0.0552899 -0.0562138 0.437747 -0.0551604 -0.0577381 0.447918 -0.0341453 -0.0817057 0.453827 -0.0353209 -0.0816125 0.453827 -0.0366912 -0.0814218 0.453828 -0.0412072 -0.0799446 0.453828 -0.0406405 -0.0802118 0.437327 -0.0396497 -0.0806193 0.453827 -0.0380392 -0.0811286 0.435629 -0.0330451 -0.0817486 0.436579 -0.0352225 -0.0816226 0.443915 0.02245 0.081235 0.43763 0.0174951 0.081235 0.443527 0.0239 0.081235 0.440335 0.0231126 0.081235 0.43785 0.0294574 0.081235 0.43763 -0.0265049 0.081235 0.43546 -0.027 0.081235 0.43626 -0.028071 0.081235 0.43546 -0.017 0.081235 0.443915 -0.01555 0.081235 0.443527 -0.0141 0.081235 0.43763 -0.0174952 0.081235 0.443527 -0.00490004 0.081235 0.440335 -0.0231126 0.081235 0.443527 -0.0239 0.081235 0.446827 0.017 0.081235 0.444977 0.0166114 0.081235 0.443915 0.01555 0.081235 0.443527 0.0141 0.081235 0.433333 0.0174753 0.081235 0.436952 0.0122377 0.081235 0.443527 0.00489996 0.081235 0.444977 -0.00238857 0.081235 0.436952 -0.0122378 0.081235 0.437905 -0.00918336 0.081235 0.444376 0.00284935 0.081235 0.443748 0.00379018 0.081235 0.485852 0.0130518 0.0360622 0.48338 -0.0125396 0.0346354 0.48261 -0.0250476 0.0341906 0.485026 -0.026069 0.0355857 0.485048 -0.0193778 0.0138721 0.485809 -4.19972e-08 0.0134328 0.488297 0.0135068 0.0119962 0.485479 0.0129294 0.0136228 0.484392 0.0258007 0.0142507 0.485905 -0.0341156 0.0162989 0.483462 -0.0317756 0.0170345 0.485626 -0.0351489 0.0177703 0.483062 -0.0333512 0.0193097 0.482848 -0.0339657 0.0208727 0.482352 -0.0339662 0.0270548 0.484655 -0.036068 0.0279853 0.48463 -0.035244 0.0298774 0.484639 -0.0345902 0.0309382 0.484699 -0.0327867 0.032961 0.484823 -0.0295372 0.0348945 0.484904 -0.0278299 0.0353722 0.48252 -0.0261965 0.0340656 0.484784 0.0306062 0.0344324 0.484637 0.0357265 0.0288816 0.482294 0.032928 0.0294755 0.482295 0.0321685 0.0305761 0.484638 0.0346042 0.0309178 0.484671 0.0335178 0.0322586 0.482346 0.0339252 0.027195 0.48232 0.0336458 0.0280067 0.485373 0.0359182 0.0193597 0.485912 0.0340867 0.0162647 0.486482 0.0313375 0.013972 0.483893 0.0294558 0.0152631 0.458786 0.0246846 -0.0821593 0.460178 0.02325 -0.0845695 0.458864 0.00250876 -0.0822932 0.440662 0.00241502 -0.082515 0.439074 0.00125273 -0.085265 0.448057 0.0338749 -0.0825549 0.449827 0.0365588 -0.0850738 0.441802 0.0294344 -0.082575 0.443335 0.0314597 -0.0825953 0.444138 0.032166 -0.0825969 0.444002 0.0350949 -0.0852704 0.446108 0.0333124 -0.0825783 0.446814 0.0362083 -0.0851318 0.441158 0.0279738 -0.0825571 0.440782 0.0264261 -0.082537 0.440662 0.0248349 -0.082515 0.439289 0.0283907 -0.0853198 0.440813 0.00063687 -0.0825394 0.439804 -0.00291998 -0.0853575 0.441336 -0.00120565 -0.0825632 0.443277 -0.00415306 -0.0825957 0.44373 -0.0078616 -0.0854451 0.446251 -0.00615948 -0.0826136 0.448015 -0.00668065 -0.0826177 0.445924 -0.00900787 -0.0854625 0.448049 -0.00668701 -0.0826178 0.460157 0.0256875 -0.0845323 0.459891 0.0284042 -0.084641 0.458312 0.0278779 -0.0822722 0.459228 0.0306279 -0.0848559 0.458793 0.0315662 -0.0849631 0.456862 0.0307477 -0.0824984 0.455425 0.0322102 -0.0825752 0.456625 0.0343075 -0.085195 0.455427 0.0351706 -0.0852127 0.453677 0.0332557 -0.0825797 0.451731 0.0364227 -0.0850977 0.449827 0.0340308 -0.0825458 0.454165 -0.0088309 -0.0854593 0.453586 -0.00906137 -0.0854633 0.451739 -0.0095479 -0.0854706 0.449827 -0.00970715 -0.0854721 0.449827 -0.0068536 -0.0826185 0.455435 -0.00497625 -0.0825953 0.456484 -0.00399969 -0.0825611 0.456776 -0.00366167 -0.0825463 0.458261 -0.00546193 -0.0852426 0.459617 -0.00281312 -0.0850119 0.460246 0.00010076 -0.0848267 0.45717 -0.0265326 -0.082391 0.458607 -0.0275842 -0.0848791 0.449827 -0.0130429 -0.0854721 0.448347 -0.0160375 -0.0826177 0.4463 -0.0137255 -0.0854607 0.446953 -0.016444 -0.0826138 0.446575 -0.0166105 -0.082612 0.444522 -0.0180768 -0.0825957 0.444509 -0.0180906 -0.0825956 0.441467 -0.018634 -0.0853601 0.442412 -0.0234151 -0.082515 0.440824 -0.0222528 -0.085265 0.442412 -0.026585 -0.082515 0.451719 -0.036399 -0.0851014 0.453269 -0.0359965 -0.085162 0.451896 -0.0337694 -0.0825599 0.452767 -0.0334842 -0.0825714 0.456018 -0.0307792 -0.0825447 0.456571 -0.0337305 -0.0852245 0.455092 -0.031943 -0.0825801 0.456216 -0.0341205 -0.0852351 0.453642 -0.0330611 -0.0825831 0.457103 -0.0276521 -0.082415 0.458069 -0.0310811 -0.0850659 0.456685 -0.0294146 -0.0824811 0.456895 -0.0287408 -0.0824519 0.458511 -0.0291693 -0.0849354 0.442697 -0.02878 -0.0825512 0.449827 -0.0340309 -0.0825458 0.447051 -0.0362037 -0.085132 0.446385 -0.0359969 -0.0851621 0.446285 -0.0332101 -0.0825799 0.444517 -0.0350791 -0.0852689 0.444788 -0.0321727 -0.0825929 0.444523 -0.0319204 -0.0825925 0.443604 -0.0307852 -0.0825814 0.443072 -0.0298166 -0.0825675 0.458368 -0.019779 -0.08507 0.456972 -0.0215244 -0.0824592 0.458067 -0.01875 -0.0851499 0.456693 -0.020573 -0.082498 0.456502 -0.0201045 -0.0825179 0.455568 -0.0185804 -0.0825755 0.45354 -0.0138056 -0.0854593 0.453644 -0.0169115 -0.0826088 0.451735 -0.0132312 -0.0854697 0.452701 -0.0164441 -0.0826138 0.437066 -0.00818608 0.084735 0.436925 -0.00898315 0.082235 0.435797 -0.0123699 0.084735 0.436032 -0.0118455 0.082235 0.434716 -0.0142772 0.084735 0.432218 -0.0171436 0.0822288 0.43178 -0.017517 0.0822225 0.437227 0.00599996 0.082235 0.437227 0.00599996 0.084735 0.437066 0.008186 0.084735 0.436585 0.0103247 0.084735 0.435797 0.0123699 0.084735 0.434716 0.0142771 0.084735 0.43264 0.0167536 0.082235 0.433368 0.0160053 0.084735 0.432218 0.0171435 0.0822288 0.429678 0.0215473 0.084735 0.429708 0.021257 0.0822225 0.429963 0.0238495 0.084735 0.430762 0.0254009 0.0822225 0.431128 0.0258558 0.084735 0.43078 -0.0185746 0.084735 0.43078 -0.0185746 0.0822225 0.430074 -0.019848 0.0822225 0.429704 -0.0227129 0.0822225 0.430063 -0.0241238 0.0822225 0.430762 -0.025401 0.0822225 0.430762 -0.025401 0.084735 0.431757 -0.0264638 0.084735 0.431757 -0.0264638 0.0822225 0.441257 -0.0378956 0.081591 0.44105 -0.0369799 0.0817847 0.441049 -0.0369779 0.0842997 0.440318 -0.0348424 0.0845754 0.439033 -0.0324684 0.0822162 0.439212 -0.0327441 0.0847017 0.43882 -0.0321566 0.0847178 0.436788 -0.0298232 0.084735 0.43617 -0.0292777 0.084735 0.434005 -0.0277758 0.082235 0.4335 -0.0275008 0.0822288 0.432985 -0.0272454 0.0822225 0.441527 0.0407205 0.0833533 0.441251 0.0378686 0.0815973 0.44105 0.0369795 0.0817847 0.439212 0.032744 0.0847018 0.440416 0.0350744 0.0820601 0.439024 0.0324548 0.0822165 0.436788 0.0298231 0.084735 0.437144 0.0301658 0.082235 0.434005 0.0277758 0.082235 0.432985 0.0272453 0.084735 0.4335 0.0275007 0.0822288 0.435506 -0.0107238 -0.082765 0.435506 -0.0107238 -0.085265 0.434502 -0.0129108 -0.082765 0.433139 -0.0148936 -0.082765 0.429504 -0.0180202 -0.0827524 0.430456 -0.017398 -0.082765 0.431456 -0.0166137 -0.085265 0.433139 -0.0148936 -0.085265 0.434502 -0.0129108 -0.085265 0.429504 -0.0180202 -0.085265 0.427434 -0.020137 -0.085265 0.42687 -0.0215195 -0.085265 0.426678 -0.023 -0.085265 0.426678 -0.023 -0.0827524 0.427434 -0.0258631 -0.0827524 0.42687 -0.0244806 -0.085265 0.428331 -0.0270558 -0.0827524 0.429504 -0.0279798 -0.0827524 0.428331 -0.0270558 -0.085265 0.428331 0.0189442 -0.085265 0.42687 0.0215194 -0.085265 0.427434 0.0201369 -0.0827524 0.42687 0.0244805 -0.0827524 0.427434 0.025863 -0.0827524 0.428331 0.0270557 -0.085265 0.435933 0.00929803 -0.082765 0.435863 0.00957373 -0.085265 0.435506 0.0107238 -0.085265 0.434502 0.0129107 -0.085265 0.433139 0.0148935 -0.085265 0.432912 0.015162 -0.082765 0.430456 0.0173979 -0.082765 0.436327 0.04 -0.084202 0.436157 0.0378255 -0.0822462 0.435629 0.0356337 -0.0826177 0.435566 0.0354475 -0.0851322 0.430456 0.028602 -0.082765 0.432107 0.0299826 -0.082765 0.433304 0.0313103 -0.085265 0.436327 -0.04 -0.084202 0.436155 -0.0378156 -0.0822486 0.435629 -0.0356339 -0.0826177 0.434743 -0.0335311 -0.0827483 0.430456 -0.0286021 -0.082765 0.429504 -0.0279798 -0.085265 0.429986 -0.0282813 -0.0827587 0.446669 0.058 -0.0376669 0.447767 0.058 -0.041765 0.446919 0.058 -0.0432961 0.445169 0.058 -0.043765 0.443419 0.058 -0.0432961 0.442571 0.058 -0.041765 0.442571 0.058 -0.038765 0.445169 0.058 -0.036765 0.450309 0.0617 0.0538331 0.450559 0.0617 0.0542661 0.451407 0.0617 0.052735 0.45184 0.0617 0.052985 0.451809 0.0617 0.051235 0.451407 0.0617 0.049735 0.452309 0.0617 0.051235 0.45184 0.0617 0.049485 0.450309 0.0617 0.048637 0.448809 0.0617 0.048235 0.446211 0.0617 0.049735 0.445809 0.0617 0.051235 0.445778 0.0617 0.052985 0.448809 0.0617 0.054235 0.447059 0.0617 0.0542661 0.442169 -0.058 -0.040265 0.441669 -0.058 -0.040265 0.443669 -0.058 -0.042863 0.447767 -0.058 -0.041765 0.448169 -0.058 -0.040265 0.446669 -0.058 -0.0376669 0.445169 -0.058 -0.037265 0.447059 -0.0617 0.0542661 0.445309 -0.0617 0.051235 0.446211 -0.0617 0.049735 0.447309 -0.0617 0.048637 0.447059 -0.0617 0.0482039 0.450559 -0.0617 0.0482039 0.451407 -0.0617 0.049735 0.451809 -0.0617 0.051235 0.451407 -0.0617 0.052735 0.450309 -0.0617 0.0538331 0.450059 0.0577 0.04907 0.448809 0.0577 0.048735 0.447559 0.0577 0.04907 0.444809 0.0577 0.051235 0.444945 0.0577 0.0501998 0.445345 0.0577 0.049235 0.450974 0.0577 0.049985 0.452273 0.0577 0.049235 0.452273 0.0577 0.053235 0.450974 0.0577 0.052485 0.44598 0.0577 0.0540635 0.446644 0.0577 0.052485 0.444945 0.0577 0.0522703 0.451637 0.0577 0.0540635 0.450059 0.0577 0.0534001 0.449844 0.0577 0.0550987 0.447334 0.054 -0.041515 0.442669 0.054 -0.040265 0.447669 0.054 -0.040265 0.449032 0.054 -0.0392297 0.447334 0.054 -0.039015 0.443004 0.054 -0.041515 0.445169 0.054 -0.037765 0.445169 0.054 -0.036265 0.448633 0.054 -0.042265 0.445169 0.054 -0.042765 0.447997 0.054 -0.0430934 0.443169 0.054 -0.0437291 0.445169 0.054 -0.044265 0.443004 0.054 -0.039015 0.44234 0.054 -0.0374365 0.444945 -0.0577 0.0501998 0.444945 -0.0577 0.0522703 0.447559 -0.0577 0.04907 0.44598 -0.0577 0.0484066 0.446644 -0.0577 0.049985 0.447774 -0.0577 0.0473713 0.450974 -0.0577 0.049985 0.450809 -0.0577 0.0477709 0.450059 -0.0577 0.04907 0.449844 -0.0577 0.0473713 0.451309 -0.0577 0.051235 0.452672 -0.0577 0.0501998 0.452809 -0.0577 0.051235 0.446644 -0.0577 0.052485 0.445345 -0.0577 0.053235 0.452273 -0.0577 0.053235 0.446809 -0.0577 0.0546991 0.448809 -0.0577 0.053735 0.441305 -0.054 -0.0392297 0.441305 -0.054 -0.0413002 0.441705 -0.054 -0.042265 0.446419 -0.054 -0.04243 0.449032 -0.054 -0.0413002 0.447334 -0.054 -0.041515 0.447334 -0.054 -0.039015 0.449032 -0.054 -0.0392297 0.446419 -0.054 -0.0380999 0.441705 -0.054 -0.038265 0.443004 -0.054 -0.039015 0.447169 -0.054 -0.0368009 0.447997 -0.054 -0.0374365 0.448633 -0.054 -0.038265 0.44234 -0.054 -0.0374365 0.443919 -0.054 -0.0380999 0.444133 -0.054 -0.0364013 0.445169 -0.054 -0.036265 0.446204 -0.054 -0.0364013 0.43421 -0.019835 0.078335 0.434477 -0.0183295 0.078335 0.43546 -0.0195 0.078335 0.436444 -0.0183295 0.078335 0.43356 -0.0252909 0.078335 0.43421 -0.0241651 0.078335 0.432773 -0.024687 0.078335 0.438147 -0.024687 0.078335 0.43796 -0.022 0.078335 0.438751 -0.0201 0.078335 0.437625 -0.02075 0.078335 0.439131 -0.0210165 0.078335 0.43926 -0.022 0.078335 0.439131 -0.0229836 0.078335 0.43179 -0.0210165 0.078335 0.432169 -0.0201 0.078335 0.433295 -0.02075 0.078335 0.433295 -0.02325 0.078335 0.43179 -0.0229836 0.078335 0.43296 -0.022 0.078335 0.43671 -0.0241651 0.078335 0.436444 -0.0256706 0.078335 0.434477 -0.0256706 0.078335 0.43421 0.024165 0.078335 0.434477 0.0256705 0.078335 0.43546 0.0258 0.078335 0.43546 0.0245 0.078335 0.438147 0.024687 0.078335 0.43421 0.0198349 0.078335 0.43671 0.0198349 0.078335 0.43796 0.022 0.078335 0.437625 0.02075 0.078335 0.438751 0.0201 0.078335 0.439131 0.0229835 0.078335 0.43926 0.022 0.078335 0.433295 0.02075 0.078335 0.432169 0.0201 0.078335 0.43179 0.0210164 0.078335 0.43166 0.022 0.078335 0.43179 0.0229835 0.078335 0.43736 0.0187091 0.078335 0.43546 0.0182 0.078335 0.432862 0.0235 0.083235 0.432429 0.02375 0.083235 0.43246 0.022 0.083235 0.43196 0.022 0.083235 0.432862 0.0205 0.083235 0.43396 0.0194019 0.083235 0.43371 0.0189689 0.083235 0.43546 0.019 0.083235 0.43546 0.0185 0.083235 0.43721 0.0189689 0.083235 0.43846 0.022 0.083235 0.438491 0.02025 0.083235 0.438058 0.0235 0.083235 0.43546 0.025 0.083235 0.43721 0.025031 0.083235 0.43546 0.0255 0.083235 0.43396 0.024598 0.083235 0.432429 -0.02025 0.083235 0.43246 -0.022 0.083235 0.432862 -0.0235 0.083235 0.43396 -0.0245981 0.083235 0.43721 -0.0250311 0.083235 0.438491 -0.02375 0.083235 0.438058 -0.0205 0.083235 0.43896 -0.022 0.083235 0.438491 -0.02025 0.083235 0.43696 -0.019402 0.083235 0.43546 -0.019 0.083235 0.43546 -0.0185 0.083235 0.431228 -0.0251651 -0.078365 0.432478 -0.0255 -0.078365 0.436148 -0.0220165 -0.078365 0.435769 -0.0211 -0.078365 0.434978 -0.023 -0.078365 0.433461 -0.0266706 -0.078365 0.429978 -0.023 -0.078365 0.428807 -0.0239836 -0.078365 0.429187 -0.0249 -0.078365 0.429791 -0.025687 -0.078365 0.430313 -0.02175 -0.078365 0.428807 -0.0220165 -0.078365 0.431494 -0.0193295 -0.078365 0.433728 -0.020835 -0.078365 0.433461 -0.0193295 -0.078365 0.432478 -0.0205 -0.078365 0.430578 -0.0197091 -0.078365 0.429791 0.020313 -0.078365 0.432478 0.0205 -0.078365 0.434643 0.02425 -0.078365 0.432478 0.0192 -0.078365 0.433728 0.0208349 -0.078365 0.430313 0.02175 -0.078365 0.430313 0.02425 -0.078365 0.429978 0.023 -0.078365 0.428678 0.023 -0.078365 0.435165 0.025687 -0.078365 0.433461 0.0266705 -0.078365 0.432478 0.0255 -0.078365 0.433461 0.0193294 -0.078365 0.435165 0.020313 -0.078365 0.434643 0.02175 -0.078365 0.436148 0.0220164 -0.078365 0.431494 0.0266705 -0.078365 0.431228 0.025165 -0.078365 0.429791 0.025687 -0.078365 0.429187 0.0249 -0.078365 0.432478 0.02 -0.083265 0.432478 0.0195 -0.083265 0.430728 0.0199689 -0.083265 0.429447 0.02125 -0.083265 0.42988 0.0215 -0.083265 0.429478 0.023 -0.083265 0.429447 0.02475 -0.083265 0.430978 0.025598 -0.083265 0.432478 0.026 -0.083265 0.434228 0.026031 -0.083265 0.435076 0.0215 -0.083265 0.434228 -0.0260311 -0.083265 0.432478 -0.026 -0.083265 0.432478 -0.0265 -0.083265 0.430728 -0.0260311 -0.083265 0.42988 -0.0245 -0.083265 0.429447 -0.02475 -0.083265 0.428978 -0.023 -0.083265 0.430978 -0.020402 -0.083265 0.432478 -0.0195 -0.083265 0.435076 -0.0215 -0.083265 0.436577 -0.00600004 -0.085698 0.4315 -0.0166645 -0.085515 0.433191 -0.0149361 -0.085515 0.436186 -0.00840882 -0.085515 0.43612 -0.00839735 -0.085265 0.436394 -0.00600004 -0.085515 0.429632 -0.0182349 -0.085698 0.431619 -0.0168032 -0.085698 0.434561 -0.0129439 -0.085515 0.435569 -0.0107464 -0.085515 0.433332 -0.0150524 -0.085698 0.433525 -0.0152112 -0.085765 0.43472 -0.0130342 -0.085698 0.435976 -0.0108925 -0.085765 0.435741 -0.0108082 -0.085698 0.436366 -0.00844016 -0.085698 0.436327 -0.00600004 -0.085265 0.436473 -0.00600004 -0.0856185 0.436635 0.00599996 -0.0857269 0.429539 -0.0180778 -0.085515 0.428689 -0.0192939 -0.085765 0.427868 -0.0203838 -0.085765 0.427353 -0.0216471 -0.085765 0.427651 -0.0202604 -0.085698 0.427112 -0.0244168 -0.085698 0.427651 -0.0257397 -0.085698 0.429761 -0.0275505 -0.085765 0.42851 -0.026881 -0.085698 0.42851 -0.0191191 -0.085698 0.427492 -0.0201701 -0.085515 0.426935 -0.0215366 -0.085515 0.427112 -0.0215833 -0.085698 0.426928 -0.023 -0.085698 0.426745 -0.023 -0.085515 0.426935 -0.0244635 -0.085515 0.427492 -0.02583 -0.085515 0.428379 -0.0189911 -0.085515 0.428331 -0.0189443 -0.085265 0.427434 -0.0258631 -0.085265 0.428379 -0.027009 -0.085515 0.436473 0.00599996 -0.0856185 0.432439 0.0158922 -0.0856185 0.436365 0.00599996 -0.0854563 0.4359 0.00958344 -0.0854563 0.436327 0.00599996 -0.085265 0.434535 0.0129295 -0.0854563 0.432335 0.0157898 -0.085265 0.429504 0.0180202 -0.085265 0.436005 0.00961111 -0.0856185 0.43463 0.012983 -0.0856185 0.432362 0.0158164 -0.0854563 0.432555 0.0160056 -0.0857269 0.436161 0.00965252 -0.0857269 0.436346 0.00970136 -0.085765 0.434771 0.0130631 -0.0857269 0.434937 0.0131575 -0.085765 0.432692 0.0161394 -0.085765 0.431365 -0.0293082 -0.085265 0.431526 -0.0291173 -0.085698 0.433418 -0.0312195 -0.0856185 0.431408 -0.0292571 -0.085515 0.429539 -0.0279223 -0.085515 0.429632 -0.0277652 -0.085698 0.429524 0.0279471 -0.0854563 0.429579 0.027854 -0.0856185 0.428379 0.0270089 -0.085515 0.427492 0.0258299 -0.085515 0.427651 0.0257396 -0.085698 0.426928 0.023 -0.085698 0.426745 0.023 -0.085515 0.427492 0.02017 -0.085515 0.427651 0.0202603 -0.085698 0.429761 0.0184495 -0.085765 0.428689 0.0192938 -0.085765 0.427868 0.0203837 -0.085765 0.427112 0.0215832 -0.085698 0.427353 0.021647 -0.085765 0.427353 0.0243529 -0.085765 0.427112 0.0244167 -0.085698 0.42851 0.0268809 -0.085698 0.427868 0.0256162 -0.085765 0.429662 0.0182852 -0.0857269 0.429632 0.0182348 -0.085698 0.429579 0.0181459 -0.0856185 0.42851 0.019119 -0.085698 0.429539 0.0180777 -0.085515 0.429524 0.0180528 -0.0854563 0.427434 0.025863 -0.085265 0.426935 0.0244634 -0.085515 0.42687 0.0244805 -0.085265 0.426935 0.0215365 -0.085515 0.426678 0.023 -0.085265 0.427434 0.0201369 -0.085265 0.428379 0.018991 -0.085515 0.436632 -0.0377233 -0.0852988 0.436473 -0.0401083 -0.0845385 0.436362 -0.0400564 -0.0843772 0.436138 -0.0377105 -0.0848078 0.435867 -0.035384 -0.0855913 0.436453 -0.0377455 -0.08526 0.436288 -0.0377516 -0.0851497 0.436177 -0.0377383 -0.0849855 0.435566 -0.0354469 -0.0851323 0.436039 -0.0353286 -0.0856303 0.435709 -0.0354285 -0.0854795 0.434642 -0.0332689 -0.0854326 0.435603 -0.0354502 -0.0853128 0.4335 -0.0311552 -0.085698 0.434888 -0.0331405 -0.0857129 0.43474 -0.033219 -0.0856012 0.433356 -0.0312688 -0.085515 0.433304 -0.0313104 -0.085265 0.43461 -0.0332824 -0.0852496 0.429504 0.0279798 -0.085265 0.43158 0.0294436 -0.0854563 0.429539 0.0279222 -0.085515 0.431759 0.0292401 -0.0857269 0.429632 0.0277651 -0.085698 0.429761 0.0275505 -0.085765 0.431555 0.0294722 -0.085265 0.431652 0.0293621 -0.0856185 0.433333 0.0312867 -0.0854563 0.433418 0.0312194 -0.0856185 0.431885 0.0290962 -0.085765 0.436327 -0.0490692 -0.0784989 0.43635 -0.04716 -0.0804163 0.436327 -0.0448271 -0.0819142 0.43635 -0.0526732 -0.0744728 0.436327 -0.0516105 -0.0756425 0.436327 -0.0525499 -0.0743852 0.436327 -0.0552901 -0.0698028 0.436827 -0.0508808 -0.0773038 0.436827 -0.0413468 -0.0842526 0.436671 -0.0451457 -0.0822746 0.436671 -0.0473641 -0.080668 0.436671 -0.0494034 -0.0788368 0.436671 -0.0529373 -0.0746605 0.436827 -0.0529575 -0.0746748 0.436827 -0.0548794 -0.0716458 0.436532 -0.0528788 -0.0746189 0.436671 -0.0557348 -0.0699758 0.436473 -0.0556257 -0.0699218 0.436643 -0.0401424 -0.0846445 0.436671 -0.0427282 -0.0836253 0.436532 -0.0426972 -0.0835605 0.436421 -0.042649 -0.0834598 0.436532 -0.0451069 -0.0822142 0.436421 -0.0450466 -0.0821202 0.436532 -0.0473189 -0.0806123 0.436532 -0.0493529 -0.0787858 0.43635 -0.0425884 -0.083333 0.43635 -0.0449707 -0.0820019 0.436421 -0.0472486 -0.0805255 0.43635 -0.0491755 -0.0786065 0.436421 -0.0492744 -0.0787064 0.436421 -0.0527878 -0.0745542 0.436421 -0.0555704 -0.0698944 0.434893 0.0331499 -0.0857127 0.433546 0.0311187 -0.0857269 0.434745 0.0332282 -0.085601 0.434647 0.033278 -0.0854323 0.434615 0.0332914 -0.0852494 0.435603 0.0354508 -0.0853127 0.436039 0.0353292 -0.0856303 0.436455 0.0377566 -0.0852579 0.43629 0.0377625 -0.0851476 0.435867 0.0353846 -0.0855912 0.435709 0.0354291 -0.0854794 0.436179 0.0377491 -0.0849834 0.436827 0.0401531 -0.0846779 0.436473 0.0401082 -0.0845385 0.436362 0.0400563 -0.0843772 0.43614 0.0377212 -0.0848057 0.437123 -0.0589734 -0.0595223 0.437059 -0.0591297 -0.0578893 0.436847 -0.0574028 -0.0660718 0.436327 -0.0553089 -0.069765 0.43635 -0.0554444 -0.0698321 0.436532 -0.0556705 -0.069944 0.436511 -0.0582275 -0.0619372 0.436347 -0.0569307 -0.0658992 0.436622 -0.058394 -0.0619782 0.436381 -0.057105 -0.0659606 0.436492 -0.0572654 -0.0660183 0.436792 -0.0585026 -0.0620097 0.436662 -0.0573704 -0.0660576 0.436477 -0.0580464 -0.0618969 0.43689 -0.0590191 -0.0578646 0.436779 -0.0588498 -0.0578391 0.437243 -0.0591635 -0.0579077 0.436327 0.042523 -0.0831965 0.436327 0.0460544 -0.0810762 0.436327 0.0507439 -0.0766985 0.436361 0.0491962 -0.0786274 0.436361 0.0526971 -0.0744899 0.436327 0.0515911 -0.0756671 0.436361 0.042601 -0.0833596 0.436471 0.0450789 -0.0821707 0.436361 0.0449865 -0.0820267 0.436361 0.0471785 -0.0804392 0.436471 0.0426748 -0.0835139 0.436471 0.0472862 -0.0805721 0.436471 0.0493165 -0.078749 0.436471 0.0528366 -0.074589 0.436827 0.0545097 -0.0722851 0.436642 0.0493957 -0.0788291 0.436642 0.0473572 -0.0806596 0.436642 0.0451398 -0.0822655 0.436642 0.0427234 -0.0836155 0.436643 0.0401423 -0.0846445 0.436642 0.055725 -0.069971 0.436471 0.0556241 -0.069921 0.436642 0.0529284 -0.0746542 0.436361 0.0554707 -0.0698451 0.447336 -0.0618404 0.00160417 0.446244 -0.0629427 0.0268524 0.444127 -0.0637453 0.045235 0.447278 -0.0620806 0.00788017 0.446856 -0.0626597 0.020369 0.437462 -0.0593885 -0.0537427 0.43937 -0.0599294 -0.0413817 0.441963 -0.0604635 -0.0291477 0.442733 -0.0606105 -0.0265647 0.444824 -0.0610291 -0.0169775 0.437293 -0.0592775 -0.0537188 0.441795 -0.0603531 -0.0291051 0.444646 -0.0609966 -0.0169399 0.444478 -0.0608861 -0.0169009 0.44562 -0.0611539 -0.0107729 0.445789 -0.0612644 -0.0108059 0.446488 -0.0614237 -0.00460343 0.437183 -0.0591078 -0.0536988 0.439202 -0.0598189 -0.0413449 0.437149 -0.0589234 -0.0536869 0.437284 -0.0589734 -0.0525371 0.439091 -0.0596483 -0.0413165 0.439058 -0.0594625 -0.041302 0.441685 -0.0601824 -0.0290729 0.444368 -0.0607154 -0.0168711 0.444334 -0.0605296 -0.0168561 0.445509 -0.0609834 -0.010747 0.446377 -0.0612533 -0.00458345 0.445475 -0.0607977 -0.0107332 0.447107 -0.0619698 0.00788383 0.446506 -0.0625145 0.0203465 0.446676 -0.0626254 0.0203557 0.445404 -0.0631683 0.0327896 0.445235 -0.0630574 0.0327748 0.443948 -0.0637109 0.0452162 0.445123 -0.0628878 0.0327692 0.443778 -0.0635999 0.0452019 0.447234 -0.061762 -0.000191845 0.446659 -0.0615343 -0.00462738 0.447156 -0.0618069 0.00161427 0.446985 -0.0616962 0.00162729 0.446872 -0.0615261 0.00164009 0.446994 -0.0617998 0.00789048 0.446959 -0.0616149 0.00789831 0.446393 -0.0623448 0.0203447 0.446357 -0.0621601 0.0203498 0.445087 -0.0627033 0.0327731 0.443666 -0.0634303 0.0451966 0.436886 0.0590152 -0.0579047 0.437183 0.0591077 -0.0536988 0.436742 0.0586619 -0.0578582 0.436776 0.0588459 -0.057879 0.436619 0.0583805 -0.062041 0.437056 0.0591257 -0.0579294 0.43724 0.0591595 -0.0579478 0.436508 0.058214 -0.0619997 0.436789 0.058489 -0.0620726 0.436346 0.0569191 -0.0659325 0.436381 0.0570933 -0.065994 0.436492 0.0572536 -0.0660518 0.436662 0.0573586 -0.0660912 0.443601 -0.0638554 0.0500777 0.443418 -0.0638205 0.050058 0.442945 -0.063452 0.0549011 0.442421 -0.0607753 0.0643272 0.442234 -0.0607463 0.0643035 0.441894 -0.0557346 0.0727188 0.442544 -0.0624182 0.0597025 0.442776 -0.0633422 0.0548698 0.442373 -0.0623119 0.0596586 0.44202 -0.0585069 0.0686494 0.441678 -0.0524257 0.0763067 0.441848 -0.0525042 0.0763863 0.441843 -0.0487875 0.0796077 0.441673 -0.0487209 0.0795184 0.443249 -0.0637092 0.0500386 0.442665 -0.0631735 0.0548354 0.442063 -0.0606451 0.0642489 0.442263 -0.0621476 0.0596025 0.441953 -0.0604883 0.0641735 0.441849 -0.0584118 0.0685858 0.441738 -0.0582649 0.0684938 0.441724 -0.055647 0.0726471 0.443104 -0.0633554 0.0500179 0.443139 -0.0635396 0.0500244 0.441922 -0.0603175 0.0640966 0.44158 -0.0553657 0.0724259 0.441613 -0.0555122 0.0725402 0.441532 -0.0521756 0.0760551 0.441567 -0.0523058 0.0761859 0.441562 -0.0486196 0.0793826 0.439389 0.0599336 -0.0412843 0.442003 0.0604713 -0.0289668 0.4447 0.061008 -0.0166756 0.44584 0.0612779 -0.0104946 0.447427 0.0619501 0.00411983 0.44716 0.0624767 0.0161812 0.447277 0.0620894 0.00808361 0.445399 0.0631703 0.0328363 0.446847 0.0626641 0.0204731 0.444127 0.0637453 0.045235 0.443948 0.0637108 0.0452162 0.443778 0.0635998 0.0452019 0.445229 0.0630593 0.0328215 0.446667 0.0626299 0.0204597 0.447169 0.0618191 0.0018942 0.446695 0.0615486 -0.00429734 0.445671 0.0611674 -0.010462 0.437462 0.0593885 -0.0537427 0.43922 0.0598231 -0.0412474 0.446497 0.0625189 0.0204504 0.446993 0.0618086 0.00809346 0.447106 0.0619786 0.008087 0.446998 0.0617083 0.00190675 0.446525 0.061438 -0.00427396 0.446413 0.0612677 -0.00425435 0.44556 0.0609969 -0.0104363 0.444421 0.0607269 -0.0166071 0.444531 0.0608975 -0.0166368 0.441726 0.0601902 -0.028892 0.441836 0.0603609 -0.0289242 0.43911 0.0596525 -0.0412189 0.437293 0.0592774 -0.0537188 0.44363 0.0632457 0.0452005 0.445117 0.0628897 0.032816 0.446385 0.0623492 0.0204486 0.446957 0.0616237 0.00810124 0.446885 0.0615382 0.00191925 0.445526 0.0608112 -0.0104226 0.441725 -0.0449698 0.0819622 0.441527 -0.0447897 0.0816244 0.442027 -0.0450169 0.0820505 0.441527 -0.0407256 0.0833686 0.441527 -0.0447817 0.0816093 0.441564 -0.0407796 0.0835321 0.441564 -0.0448707 0.0817763 0.441657 -0.0449406 0.0819074 0.441657 -0.0408262 0.0836731 0.441725 -0.0408457 0.0837321 0.441883 -0.0450074 0.0820328 0.441843 0.0487874 0.0796077 0.441562 0.0486195 0.0793826 0.441673 0.0487208 0.0795184 0.441567 0.0523144 0.0761772 0.442032 0.0525373 0.076403 0.442081 0.0557908 0.0727043 0.442021 0.0585239 0.0686207 0.442132 0.0572022 0.0707618 0.442207 0.0585514 0.0686447 0.442731 0.0624533 0.0597101 0.442545 0.0624226 0.0596869 0.442946 0.063453 0.0548939 0.44348 0.0638203 0.0512629 0.441848 0.0525129 0.0763776 0.441895 0.0557646 0.07268 0.442235 0.0607504 0.0642941 0.44185 0.0584288 0.0685572 0.442064 0.0606491 0.0642395 0.442374 0.0623163 0.0596431 0.442776 0.0633432 0.0548626 0.443418 0.0638205 0.0500569 0.441678 0.0524344 0.076298 0.441725 0.0556768 0.0726084 0.441614 0.0555419 0.0725016 0.443249 0.0637092 0.0500375 0.441532 0.0521841 0.0760465 0.441581 0.0553953 0.0723875 0.441739 0.0582817 0.0684653 0.441707 0.0581217 0.0683688 0.441954 0.0604923 0.0641642 0.442232 0.061973 0.0595329 0.442264 0.0621519 0.0595871 0.442633 0.0629909 0.054799 0.442666 0.0631744 0.0548283 0.443139 0.0635396 0.0500233 0.443104 0.0633554 0.0500168 0.443666 0.0634302 0.0451966 0.436959 -0.0296403 0.085168 0.439079 -0.031984 0.0851809 0.440355 -0.0348424 0.0847553 0.43885 -0.0321392 0.0849006 0.438941 -0.0320785 0.0850692 0.440612 -0.0347567 0.0850337 0.440458 -0.0348127 0.0849217 0.44138 -0.0377974 0.0844942 0.44123 -0.037761 0.0841538 0.441527 -0.0407206 0.0833533 0.44127 -0.0377877 0.0843306 0.441543 -0.037786 0.0846047 0.441843 -0.0408663 0.0837947 0.439229 -0.0318797 0.0852177 0.440778 -0.0346889 0.0850735 0.441883 -0.0408708 0.0838081 0.442027 -0.0408773 0.0838281 0.442027 0.0474559 0.0805902 0.441855 0.0450028 0.0820244 0.441703 0.0408399 0.083715 0.441703 0.0449612 0.0819463 0.441599 0.0408016 0.083599 0.441562 0.0407782 0.083528 0.441599 0.0449038 0.0818385 0.441536 0.0448264 0.0816934 0.436812 -0.0297975 0.0849191 0.436834 -0.0297742 0.084985 0.436213 -0.0292262 0.084985 0.436888 -0.0297161 0.0850886 0.43633 -0.0290857 0.085168 0.43881 0.032143 0.0847181 0.43884 0.0321256 0.0849009 0.441714 0.0377304 0.0846498 0.440315 0.0348338 0.0845762 0.441225 0.0377347 0.0841591 0.441536 0.0407501 0.0834428 0.441264 0.0377612 0.084336 0.441855 0.0408677 0.083799 0.440774 0.03468 0.0850743 0.440608 0.0347479 0.0850344 0.441274 0.0360289 0.0849268 0.441538 0.0377587 0.08461 0.441375 0.0377706 0.0844996 0.441049 0.0369776 0.0842997 0.440455 0.034804 0.0849224 0.438932 0.0320648 0.0850695 0.440351 0.0348338 0.0847561 0.439219 0.0318656 0.085218 0.436999 0.0295973 0.085197 0.43907 0.0319701 0.0851812 0.432985 -0.0272454 0.084735 0.433014 -0.0271848 0.084985 0.433092 -0.0270193 0.085168 0.433199 -0.0267932 0.085235 0.431917 -0.0262714 0.085168 0.429956 -0.0212891 0.085168 0.431183 -0.0188699 0.085235 0.430982 -0.0187222 0.085168 0.4318 -0.0264123 0.084985 0.430965 -0.0252544 0.085168 0.430296 -0.0240323 0.085168 0.429952 -0.0226822 0.085168 0.429771 -0.0227047 0.084985 0.430307 -0.0199408 0.085168 0.430137 -0.0198729 0.084985 0.430834 -0.0186141 0.084985 0.431939 -0.0177102 0.085168 0.431823 -0.0175687 0.084985 0.430816 -0.0253617 0.084985 0.430126 -0.0240993 0.084985 0.430063 -0.0241238 0.084735 0.429775 -0.0212656 0.084985 0.429704 -0.0227129 0.084735 0.429708 -0.0212571 0.084735 0.430074 -0.019848 0.084735 0.43178 -0.017517 0.084735 0.436814 0.0297953 0.0849264 0.436888 0.029716 0.0850886 0.435069 0.0282655 0.0850886 0.437129 0.0294574 0.085235 0.434987 0.0283867 0.084735 0.435008 0.0283552 0.0849264 0.43516 0.0281312 0.085197 0.433199 0.0267931 0.085235 0.437132 -0.00819591 0.084985 0.436585 -0.0103248 0.084735 0.435857 -0.0123986 0.084985 0.434772 -0.0143144 0.084985 0.433368 -0.0160053 0.084735 0.437477 -0.00600004 0.085168 0.436649 -0.0103443 0.084985 0.433417 -0.0160503 0.084985 0.437313 -0.00822276 0.085168 0.437064 -0.0104699 0.085235 0.436825 -0.0103974 0.085168 0.436023 -0.0124768 0.085168 0.436249 -0.0125837 0.085235 0.434924 -0.0144161 0.085168 0.433553 -0.0161732 0.085168 0.430762 0.0254009 0.084735 0.430761 0.0195488 0.085235 0.431823 0.0175686 0.084985 0.430592 0.0194603 0.085197 0.430448 0.0193853 0.0850886 0.429986 0.0215714 0.085197 0.429824 0.0215588 0.0850886 0.429716 0.0215503 0.0849264 0.430318 0.0193175 0.084735 0.430352 0.0193351 0.0849264 0.430074 0.0198479 0.084735 0.430256 0.0237511 0.085197 0.429999 0.0238374 0.0849264 0.429704 0.0227128 0.084735 0.431156 0.0258305 0.0849264 0.430102 0.0238028 0.0850886 0.431237 0.0257585 0.0850886 0.431358 0.0256506 0.085197 0.430437 0.0236901 0.085235 0.431501 0.0255234 0.085235 0.433117 0.0269662 0.085197 0.433048 0.0271129 0.0850886 0.433001 0.0272109 0.0849264 0.437227 -0.00600004 0.084735 0.437294 -0.00600004 0.084985 0.437477 0.00599996 0.085168 0.431805 0.0175463 0.0849264 0.43178 0.0175169 0.084735 0.433417 0.0160502 0.084985 0.431976 0.0177554 0.085197 0.431939 0.0177101 0.085168 0.434772 0.0143143 0.084985 0.435857 0.0123985 0.084985 0.437132 0.00819582 0.084985 0.437294 0.00599996 0.084985 0.431873 0.0176301 0.0850886 0.433553 0.0161731 0.085168 0.434924 0.014416 0.085168 0.436023 0.0124767 0.085168 0.436649 0.0103442 0.084985 0.436825 0.0103973 0.085168 0.437313 0.00822267 0.085168 0.43756 0.00825935 0.085235 0.430815 0.0179005 -0.0818411 0.429953 0.0187714 -0.0817603 0.4305 0.0174599 -0.0823823 0.429504 0.0180202 -0.0827524 0.429986 0.0177187 -0.0827587 0.429724 0.0183889 -0.0819311 0.429631 0.0182322 -0.0820944 0.430626 0.0176364 -0.0820579 0.435506 0.0107238 -0.082765 0.437327 0.00599996 -0.081765 0.436403 0.00599996 -0.0823823 0.435662 0.0128683 -0.081765 0.436533 0.00944345 -0.0818411 0.435322 0.0126931 -0.0818411 0.436217 0.00936703 -0.0820579 0.435033 0.0125446 -0.0820579 0.436007 0.00931596 -0.0823823 0.433379 0.015566 -0.0818411 0.434841 0.0124453 -0.0823823 0.434773 0.0124105 -0.082765 0.433134 0.0153537 -0.0820579 0.43297 0.0152119 -0.0823823 0.428413 0.0269761 -0.082289 0.429563 0.027882 -0.082289 0.429953 0.0272285 -0.0817603 0.428639 0.0267554 -0.0819311 0.427285 0.0243709 -0.0819311 0.426792 0.023 -0.082289 0.427285 0.021629 -0.0819311 0.42698 0.0215485 -0.082289 0.427533 0.0201931 -0.082289 0.427807 0.0203489 -0.0819311 0.429534 0.0180701 -0.0824165 0.428331 0.0189442 -0.0827524 0.42687 0.0215194 -0.0827524 0.426678 0.023 -0.0827524 0.42698 0.0244515 -0.082289 0.427533 0.0258068 -0.082289 0.428331 0.0270557 -0.0827524 0.429504 0.0279798 -0.0827524 0.429563 0.0181179 -0.082289 0.428413 0.0190238 -0.082289 0.427807 0.025651 -0.0819311 0.427716 0.0242572 -0.0817603 0.427553 0.023 -0.0817603 0.427107 0.023 -0.0819311 0.428639 0.0192445 -0.0819311 0.429782 0.0184848 -0.0818639 0.436327 0.00599996 -0.082765 0.43662 -0.00600004 -0.0820579 0.43662 0.00599996 -0.0820579 0.436827 -0.00600004 -0.0818989 0.436944 0.00599996 -0.0818411 0.429782 0.0275151 -0.0818639 0.429724 0.027611 -0.0819311 0.430626 0.0283635 -0.0820579 0.429631 0.0277677 -0.0820944 0.429534 0.0279299 -0.0824165 0.429986 0.0282812 -0.0827587 0.430495 -0.017453 -0.0824035 0.433243 -0.0149787 -0.082265 0.430624 -0.0176336 -0.0820614 0.431037 -0.0182121 -0.081765 0.433525 -0.0152112 -0.0818989 0.434937 -0.0131576 -0.0818989 0.435372 -0.0134044 -0.081765 0.436447 -0.0110613 -0.081765 0.437105 -0.00856858 -0.081765 0.435976 -0.0108925 -0.0818989 0.436252 -0.00842029 -0.082265 0.436613 -0.00848297 -0.0818989 0.436461 -0.00600004 -0.082265 0.434619 -0.0129769 -0.082265 0.435632 -0.010769 -0.082265 0.43612 -0.00839735 -0.082765 0.430815 0.0280994 -0.0818411 0.432538 0.0295409 -0.0818411 0.4305 0.02854 -0.0823823 0.43216 0.0299282 -0.0823823 0.433527 0.0316 -0.082765 0.432984 0.0309217 -0.082765 0.433588 0.0315543 -0.0823823 0.432312 0.0297731 -0.0820579 0.429986 -0.0177188 -0.0827587 0.430534 -0.0175071 -0.082265 0.429563 -0.018118 -0.082289 0.429631 -0.0182323 -0.0820944 0.429724 -0.018389 -0.0819311 0.430746 -0.0178051 -0.0818989 0.430822 -0.0179107 -0.0818361 0.436774 0.0375243 -0.0813289 0.434747 0.0335392 -0.0827481 0.435003 0.0333887 -0.0820373 0.433761 0.0314242 -0.0820579 0.434021 0.0312296 -0.0818411 0.435687 0.0355774 -0.082245 0.434806 0.0334993 -0.0823779 0.435896 0.0354744 -0.0819029 0.436223 0.0353453 -0.0816834 0.435305 0.0332261 -0.0818154 0.436216 0.0377347 -0.08188 0.436579 0.0352224 -0.0816226 0.436397 0.039871 -0.0812111 0.436434 0.0376257 -0.081544 0.436959 0.0396743 -0.080685 0.437327 0.0396497 -0.0806193 0.437145 0.037453 -0.0812701 0.428413 -0.0190239 -0.082289 0.429953 -0.0187715 -0.0817603 0.428413 -0.0269762 -0.082289 0.427533 -0.0258069 -0.082289 0.42698 -0.0244515 -0.082289 0.42687 -0.0244806 -0.0827524 0.42698 -0.0215485 -0.082289 0.42687 -0.0215195 -0.0827524 0.427533 -0.0201932 -0.082289 0.427434 -0.020137 -0.0827524 0.428331 -0.0189443 -0.0827524 0.428639 -0.0192446 -0.0819311 0.427285 -0.0216291 -0.0819311 0.427107 -0.023 -0.0819311 0.426792 -0.023 -0.082289 0.429631 -0.0277678 -0.0820944 0.428639 -0.0267555 -0.0819311 0.429782 -0.0184849 -0.0818639 0.428957 -0.0195561 -0.0817603 0.428195 -0.0205689 -0.0817603 0.427807 -0.020349 -0.0819311 0.427285 -0.024371 -0.0819311 0.427807 -0.0256511 -0.0819311 0.428195 -0.0254311 -0.0817603 0.429782 -0.0275152 -0.0818639 0.43662 0.051871 -0.0694267 0.436515 0.0519794 -0.0694857 0.436736 0.0434489 -0.078864 0.436327 0.0438989 -0.0795339 0.436327 0.0444322 -0.0791638 0.436327 0.0472746 -0.0767575 0.436327 0.0482417 -0.0757539 0.436327 0.0517263 -0.0710933 0.436374 0.0498953 -0.0732712 0.436374 0.0522262 -0.0696202 0.437327 0.0433412 -0.0787038 0.437016 0.0433688 -0.0787449 0.437016 0.0466075 -0.0760804 0.437327 0.0492054 -0.0730288 0.437327 0.0516138 -0.0692865 0.437016 0.0516572 -0.0693102 0.437016 0.0493751 -0.0728849 0.43662 0.0397523 -0.0808936 0.436736 0.0467082 -0.0761826 0.436515 0.046865 -0.0763417 0.436736 0.0494903 -0.0729704 0.436515 0.0496696 -0.0731036 0.436515 0.0435734 -0.0790494 0.436374 0.0437302 -0.0792828 0.436374 0.0470623 -0.0765419 0.430822 -0.0280894 -0.0818361 0.430746 -0.028195 -0.0818989 0.429724 -0.0276111 -0.0819311 0.430624 -0.0283665 -0.0820614 0.430534 -0.028493 -0.082265 0.429563 -0.0278821 -0.082289 0.436736 0.0517832 -0.0693789 0.43698 0.0533964 -0.0655862 0.436327 0.0524919 -0.069765 0.436419 0.0539208 -0.0657775 0.436642 0.0536048 -0.0656604 0.436347 0.0542636 -0.0659073 0.436776 0.0548045 -0.0617099 0.437113 0.0545868 -0.0616763 0.437478 0.0545153 -0.0616779 0.437347 0.0533293 -0.0655664 0.436826 0.055795 -0.0576841 0.436553 0.0551332 -0.0617747 0.436754 0.0561595 -0.0577153 0.43746 0.055721 -0.0535232 0.437048 0.055459 -0.0576682 0.437797 0.0554982 -0.0535519 0.437385 0.0552369 -0.0576733 0.433746 -0.0302733 -0.081765 0.433761 -0.0314243 -0.0820579 0.433583 -0.0315579 -0.0823969 0.433086 -0.0308349 -0.082265 0.433365 -0.0305975 -0.0818989 0.432984 -0.0309218 -0.082765 0.445801 0.0575924 -0.0105648 0.437239 0.0560589 -0.0535126 0.445356 0.0570326 -0.0168076 0.445714 0.0592726 0.0329382 0.446988 0.0587299 0.0205098 0.447886 0.0582711 0.0115575 0.447597 0.0581855 0.00804759 0.447842 0.0578441 0.00177766 0.44774 0.0577642 -5.13671e-05 0.447354 0.057571 -0.00447688 0.439168 0.0565964 -0.0410994 0.442325 0.0565697 -0.0289433 0.445003 0.0571026 -0.0167393 0.441993 0.0567919 -0.028878 0.444447 0.0576635 -0.0166515 0.439724 0.0560355 -0.0411811 0.43939 0.0562576 -0.0411269 0.441772 0.0571305 -0.0288431 0.444375 0.0580317 -0.016653 0.4417 0.0574985 -0.0288429 0.446656 0.0578618 -0.00441244 0.446995 0.0576399 -0.00444027 0.447481 0.0579122 0.00179148 0.44714 0.0581339 0.00179769 0.447254 0.0584071 0.00803528 0.446646 0.0589512 0.0204719 0.445373 0.0594938 0.0328891 0.446432 0.0582011 -0.00440245 0.446533 0.0573115 -0.0104197 0.444669 0.0573248 -0.0166815 0.446137 0.0573703 -0.0106107 0.445578 0.0579313 -0.0105429 0.446915 0.0584736 0.00179334 0.446843 0.0588431 0.00178054 0.447029 0.0587471 0.0080187 0.446422 0.0592917 0.0204385 0.446352 0.0596624 0.0204166 0.446727 0.0589499 0.0271049 0.44515 0.0598346 0.0328483 0.44449 0.060425 0.0378478 0.443624 0.0607481 0.0452533 0.437143 -0.0374429 -0.0812723 0.436993 -0.0366804 -0.0814237 0.436772 -0.0375145 -0.0813312 0.436223 -0.0353454 -0.0816834 0.435896 -0.0354746 -0.0819029 0.433927 -0.0313 -0.0818989 0.435301 -0.0332179 -0.0818156 0.434999 -0.0333806 -0.0820375 0.436433 -0.037616 -0.0815463 0.433634 -0.0315197 -0.082265 0.436327 -0.04 -0.0815559 0.436215 -0.0377249 -0.0818823 0.435687 -0.0355776 -0.0822449 0.434802 -0.0334913 -0.0823781 0.433527 -0.0316 -0.082765 0.444618 0.0597491 0.0454095 0.444072 0.0598492 0.0503486 0.443917 0.0600364 0.0453176 0.443694 0.0603772 0.0452774 0.444258 0.0598152 0.0453658 0.443707 0.0599201 0.0503123 0.443589 0.0593997 0.0551577 0.442527 0.0434328 0.0783593 0.442159 0.0434667 0.0784208 0.442163 0.047459 0.0757044 0.442318 0.0539798 0.0685086 0.442523 0.0564419 0.0643099 0.44334 0.0587913 0.0579493 0.44289 0.0596936 0.0551442 0.443225 0.0594731 0.0551372 0.442828 0.0583086 0.0598028 0.442189 0.0566425 0.0643912 0.441983 0.0541651 0.068622 0.442203 0.050962 0.0723574 0.443148 0.0604814 0.0502677 0.44337 0.0601429 0.0502826 0.442667 0.0600257 0.0551805 0.442494 0.0585213 0.0598485 0.441866 0.0511278 0.0725007 0.441825 0.0475999 0.0758757 0.442593 0.0603855 0.0552349 0.44227 0.0588397 0.0599376 0.442193 0.0591845 0.0600465 0.441965 0.0569424 0.0645284 0.441759 0.0544427 0.0688024 0.441682 0.0547435 0.0690042 0.441643 0.051378 0.0727224 0.441602 0.0478141 0.076137 0.441569 0.0516492 0.072966 0.441531 0.0480465 0.0764213 0.436327 -0.0441678 -0.0793503 0.436374 -0.0470433 -0.0765607 0.436327 -0.0486855 -0.0752574 0.437016 -0.0516573 -0.0693102 0.436374 -0.0498831 -0.0732877 0.436515 -0.0496575 -0.07312 0.436374 -0.0437069 -0.0792985 0.437327 -0.0433187 -0.078719 0.437016 -0.0433462 -0.0787601 0.436959 -0.0396743 -0.080685 0.437327 -0.0412072 -0.0799446 0.437016 -0.0493631 -0.0729011 0.437016 -0.046589 -0.0760986 0.436397 -0.0398711 -0.0812111 0.43662 -0.0397523 -0.0808936 0.436515 -0.0435504 -0.079065 0.436736 -0.0434261 -0.0788794 0.436515 -0.0468462 -0.0763602 0.436736 -0.0466896 -0.0762009 0.436736 -0.0494783 -0.0729867 0.441939 0.0404388 0.079946 0.442218 0.0403893 0.0798129 0.44182 0.0435742 0.0786158 0.441718 0.0405158 0.0801534 0.441597 0.0437379 0.0789127 0.436736 -0.0517833 -0.0693789 0.437168 -0.0564258 -0.0535204 0.437381 -0.0552327 -0.0577155 0.437341 -0.0531905 -0.0659236 0.436979 -0.0533843 -0.0656183 0.437346 -0.0533172 -0.0655983 0.437474 -0.054498 -0.0617529 0.437045 -0.0554547 -0.0577107 0.437109 -0.0545694 -0.0617517 0.436772 -0.054787 -0.0617861 0.436641 -0.0535926 -0.0656929 0.436822 -0.0557907 -0.057727 0.436549 -0.0551155 -0.0618519 0.43662 -0.0518711 -0.0694267 0.436515 -0.0519795 -0.0694857 0.436476 -0.0554717 -0.0619316 0.436346 -0.0542511 -0.0659405 0.436418 -0.0539084 -0.0658104 0.436374 -0.0522263 -0.0696202 0.44182 0.0404743 0.0800416 0.441576 0.0406129 0.0804147 0.441524 0.037661 0.080892 0.441597 0.0405923 0.0803594 0.439548 0.0320847 0.0812834 0.440674 0.0348988 0.081343 0.439264 0.0322788 0.0815052 0.439079 0.0324096 0.081846 0.437351 0.0299583 0.0815279 0.43758 0.0297285 0.0813112 0.439856 0.0318776 0.0812168 0.44194 0.0362787 0.0808469 0.441863 0.0375478 0.0806773 0.440993 0.0347469 0.0811239 0.441308 0.0377769 0.0812294 0.440471 0.0350156 0.081686 0.440096 -0.05597 -0.0411483 0.440486 -0.0560568 -0.0391588 0.442366 -0.0565777 -0.0287627 0.445692 -0.057107 -0.0151068 0.446188 -0.057384 -0.0102997 0.44739 -0.0575855 -0.0041456 0.447962 -0.0580746 0.00705665 0.447595 -0.0581945 0.00825229 0.447956 -0.0581271 0.0082586 0.446404 -0.0590799 0.0300815 0.44734 -0.0586681 0.0206485 0.445708 -0.0592748 0.0329858 0.443694 -0.0603772 0.0452774 0.443917 -0.0600365 0.0453176 0.446979 -0.0587346 0.0206156 0.447253 -0.0584161 0.00823944 0.447494 -0.0579245 0.00207155 0.447031 -0.0576544 -0.00411018 0.446692 -0.0578763 -0.00408348 0.445851 -0.057606 -0.0102546 0.445056 -0.0571142 -0.0164754 0.445144 -0.0598367 0.032896 0.445368 -0.059496 0.0329367 0.446637 -0.0589559 0.0205775 0.447152 -0.0581462 0.00207686 0.446927 -0.0584859 0.00207191 0.445628 -0.057945 -0.0102332 0.444722 -0.0573364 -0.0164179 0.442034 -0.0567999 -0.0286973 0.444501 -0.0576751 -0.0163882 0.44449 -0.0604251 0.0378478 0.446413 -0.0592964 0.020544 0.447027 -0.0587561 0.0082225 0.446956 -0.0591262 0.00820569 0.446856 -0.0588555 0.00205892 0.446468 -0.0582156 -0.00407424 0.445556 -0.0583135 -0.0102375 0.441813 -0.0571384 -0.0286623 0.437239 -0.056059 -0.0535126 0.43746 -0.0557211 -0.0535232 0.439186 -0.0566007 -0.0410018 0.437797 -0.0554983 -0.0535519 0.439408 -0.056262 -0.0410294 0.439743 -0.0560398 -0.0410838 0.43626 0.0280709 0.081235 0.435832 0.0286334 0.0815279 0.437198 0.0301119 0.0818523 0.434501 0.026907 0.081235 0.436028 0.0283753 0.0813112 0.4357 0.0288059 0.0818523 0.43415 0.0275213 0.0815279 0.435654 0.0288664 0.082235 0.441527 -0.0439157 0.079235 0.441602 -0.047847 0.0761101 0.442531 -0.0474462 0.0756245 0.442163 -0.0474913 0.075678 0.442159 -0.0434668 0.0784208 0.442569 -0.0509427 0.0722755 0.44232 -0.0540153 0.0684565 0.444258 -0.0598153 0.0453658 0.443595 -0.0594115 0.0550879 0.443192 -0.0582401 0.0597924 0.442204 -0.0509977 0.0723178 0.442526 -0.0564626 0.0642686 0.442191 -0.0566633 0.0643495 0.442829 -0.058313 0.0597895 0.443232 -0.059485 0.0550671 0.443711 -0.0599211 0.0502709 0.441825 -0.0476325 0.0758491 0.441867 -0.0511638 0.0724609 0.441985 -0.0542007 0.0685695 0.441761 -0.0544787 0.0687494 0.441967 -0.0569634 0.0644863 0.442495 -0.0585258 0.0598351 0.442896 -0.0597056 0.0550736 0.443374 -0.0601439 0.050241 0.441531 -0.0480798 0.076394 0.441643 -0.0514143 0.0726821 0.44189 -0.0572884 0.0646438 0.442271 -0.0588443 0.0599241 0.442194 -0.0591892 0.0600329 0.442674 -0.0600377 0.055109 0.442599 -0.0603978 0.0551626 0.443153 -0.0604825 0.0502257 0.443082 -0.06085 0.0502267 0.434311 0.0272395 0.0813112 0.434043 0.0277096 0.0818523 0.433091 0.0270219 0.0815644 0.433216 0.0267559 0.081334 0.433359 0.026454 0.0812303 0.441527 -0.0407206 0.0807044 0.441597 -0.043738 0.0789127 0.441603 -0.0405873 0.0803457 0.44182 -0.0435743 0.0786158 0.442527 -0.0434329 0.0783593 0.442144 -0.0403989 0.0798384 0.431817 0.0175618 0.0818865 0.431486 0.0190913 0.0812303 0.43183 0.0263761 0.0817591 0.431757 0.0264637 0.0822225 0.430169 0.0240821 0.0817591 0.429817 0.0226988 0.0817591 0.430063 0.0241238 0.0822225 0.429704 0.0227128 0.0822225 0.430074 0.0198479 0.0822225 0.43078 0.0185745 0.0822225 0.431937 0.0177078 0.0815644 0.430872 0.0186417 0.0817591 0.431127 0.0188281 0.0814012 0.43018 0.0198902 0.0817591 0.430134 0.021312 0.0814012 0.429821 0.0212716 0.0817591 0.430854 0.0253341 0.0817591 0.432985 0.0272453 0.0822225 0.433034 0.0271424 0.0817591 0.433169 0.0268569 0.0814012 0.430473 0.0200073 0.0814012 0.430576 0.0213691 0.0812303 0.430131 0.02266 0.0814012 0.430463 0.0239665 0.0814012 0.431471 0.0248878 0.0812303 0.43111 0.025149 0.0814012 0.432031 0.0261332 0.0814012 0.432316 0.0257903 0.0812303 0.440419 -0.035082 0.0820593 0.439088 -0.0324231 0.0818456 0.437198 -0.0301119 0.0818523 0.437351 -0.0299584 0.0815279 0.439273 -0.0322925 0.0815048 0.439557 -0.0320986 0.081283 0.43758 -0.0297286 0.0813112 0.440474 -0.0350231 0.0816853 0.441314 -0.0378035 0.0812232 0.440677 -0.0349064 0.0813422 0.44153 -0.0376876 0.080886 0.441869 -0.0375748 0.0806713 0.440996 -0.0347546 0.0811231 0.44182 -0.0404744 0.0800416 0.43178 0.0175169 0.0822225 0.431853 0.0176049 0.0817591 0.432336 0.0181932 0.0812303 0.432124 0.0179352 0.081334 0.432053 0.0178488 0.0814012 0.434501 -0.0269071 0.081235 0.434311 -0.0272395 0.0813112 0.43415 -0.0275214 0.0815279 0.436028 -0.0283754 0.0813112 0.434043 -0.0277097 0.0818523 0.4357 -0.028806 0.0818523 0.435654 -0.0288665 0.082235 0.435832 -0.0286335 0.0815279 0.437144 -0.0301659 0.082235 0.438227 0.00599996 0.081235 0.437727 0.00599996 0.081369 0.437212 0.00904171 0.0815279 0.433068 0.0171991 0.0813112 0.435407 0.0150395 0.081235 0.432843 0.016965 0.0815279 0.432693 0.0168085 0.0818523 0.434584 0.014471 0.082235 0.435092 0.014822 0.0813112 0.4366 0.0120876 0.0813112 0.434825 0.0146375 0.0815279 0.436302 0.0119603 0.0815279 0.434647 0.0145143 0.0818523 0.436032 0.0118454 0.082235 0.437 0.00899831 0.0818523 0.436585 0.0103247 0.082235 0.436102 0.0118752 0.0818523 0.43753 0.00910666 0.0813112 0.437905 0.00918328 0.081235 0.436925 0.00898307 0.082235 0.433359 -0.0264541 0.0812303 0.433034 -0.0271424 0.0817591 0.433091 -0.027022 0.0815644 0.433169 -0.026857 0.0814012 0.438227 -0.00600004 0.081235 0.437844 0.00599996 0.0813112 0.437727 -0.00600004 0.081369 0.43752 0.00599996 0.0815279 0.437361 0.00599996 0.081735 0.437303 0.00599996 0.0818523 0.437361 -0.00600004 0.081735 0.437303 -0.00600004 0.0818523 0.437227 -0.00600004 0.082235 0.433216 -0.026756 0.081334 0.430854 -0.0253342 0.0817591 0.43111 -0.0251491 0.0814012 0.430463 -0.0239666 0.0814012 0.430134 -0.0213121 0.0814012 0.429821 -0.0212716 0.0817591 0.43018 -0.0198903 0.0817591 0.430473 -0.0200074 0.0814012 0.431817 -0.0175619 0.0818865 0.429708 -0.0212571 0.0822225 0.429817 -0.0226989 0.0817591 0.430169 -0.0240821 0.0817591 0.43183 -0.0263762 0.0817591 0.431853 -0.0176049 0.0817591 0.430872 -0.0186418 0.0817591 0.432124 -0.0179352 0.081334 0.432316 -0.0257904 0.0812303 0.432031 -0.0261333 0.0814012 0.431471 -0.0248879 0.0812303 0.430131 -0.0226601 0.0814012 0.430573 -0.0226054 0.0812303 0.430576 -0.0213691 0.0812303 0.431127 -0.0188282 0.0814012 0.437844 -0.00600004 0.0813112 0.43753 -0.00910675 0.0813112 0.43752 -0.00600004 0.0815279 0.437212 -0.00904179 0.0815279 0.436302 -0.0119604 0.0815279 0.436102 -0.0118753 0.0818523 0.437 -0.00899839 0.0818523 0.436585 -0.0103248 0.082235 0.4366 -0.0120876 0.0813112 0.434647 -0.0145144 0.0818523 0.435407 -0.0150396 0.081235 0.435092 -0.014822 0.0813112 0.433333 -0.0174754 0.081235 0.434825 -0.0146376 0.0815279 0.434584 -0.0144711 0.082235 0.432693 -0.0168086 0.0818523 0.43264 -0.0167537 0.082235 0.433068 -0.0171992 0.0813112 0.432843 -0.0169651 0.0815279 0.432053 -0.0178489 0.0814012 0.431937 -0.0177079 0.0815644 0.438851 0.00125273 -0.085531 0.439084 -0.000897983 -0.0854992 0.449827 -0.0104143 -0.085765 0.447607 -0.00982255 -0.0856883 0.445343 -0.00954973 -0.085765 0.441856 -0.00672741 -0.0856756 0.440476 -0.00500188 -0.0856675 0.440117 -0.0052389 -0.085765 0.438884 -0.000935413 -0.085645 0.438922 -0.00286978 -0.085765 0.438417 -0.0010226 -0.085765 0.449827 -0.0100316 -0.0856889 0.447668 -0.00950315 -0.08547 0.445491 -0.00918882 -0.0856857 0.443545 -0.00813827 -0.0856815 0.442595 -0.00696809 -0.0854313 0.440799 -0.0048625 -0.0853951 0.439476 -0.00305256 -0.0856573 0.439317 -0.00127606 -0.0853227 0.451793 -0.00986839 -0.0856884 0.453696 -0.00936965 -0.0856865 0.451856 -0.0102468 -0.085765 0.439074 0.0259972 -0.085265 0.43855 0.00125273 -0.0857047 0.438208 0.0259972 -0.085765 0.460268 -0.003033 -0.0854084 0.459793 -0.00286805 -0.0852011 0.458579 -0.00567171 -0.0855208 0.459189 -0.00385618 -0.0850993 0.453827 -0.00973534 -0.085765 0.456421 -0.00789534 -0.0856546 0.457249 -0.00776569 -0.0857125 0.458769 -0.00580431 -0.0855859 0.460435 8.51061e-05 -0.0850482 0.460018 -0.0029438 -0.0853395 0.460692 6.09876e-05 -0.0852111 0.45621 -0.00762545 -0.0854122 0.459758 -0.00471875 -0.0855077 0.458405 -0.00555454 -0.0854023 0.457068 -0.00687676 -0.0853612 0.460298 0.00145858 -0.0847779 0.460986 3.11836e-05 -0.0852886 0.461276 -4.19898e-08 -0.0852761 0.461358 0.0014605 -0.0852591 0.460294 0.00399996 -0.0847704 0.460483 0.00400138 -0.0850063 0.460487 0.00145918 -0.0850134 0.460751 0.00145976 -0.0851884 0.461056 0.00146022 -0.0852721 0.461356 0.00400447 -0.0852511 0.43855 0.0259972 -0.0857047 0.438937 0.0284656 -0.0856467 0.439135 0.0284234 -0.0855029 0.438851 0.0259972 -0.085531 0.460378 0.0232553 -0.0848154 0.460748 0.00400274 -0.0851814 0.461054 0.00400381 -0.0852647 0.460988 0.0232643 -0.0850678 0.439691 0.0308124 -0.0856601 0.441077 0.0337401 -0.085729 0.440011 0.0306641 -0.0853675 0.446621 0.0370527 -0.0854172 0.446729 0.0365979 -0.0853789 0.441649 0.033202 -0.0853798 0.441394 0.0334462 -0.0856431 0.443828 0.0354279 -0.0855216 0.449827 0.0369665 -0.0853208 0.460662 0.0232604 -0.0849934 0.460976 0.0257025 -0.0850311 0.453689 0.0363798 -0.0854101 0.453581 0.0360006 -0.0851619 0.451849 0.0372907 -0.0853776 0.453827 0.0368224 -0.0854528 0.451782 0.0368233 -0.0853443 0.461005 0.0284175 -0.0850311 0.460408 0.0282969 -0.0850072 0.459417 0.030691 -0.0850497 0.460133 0.0282474 -0.0848511 0.460359 0.0256931 -0.0847802 0.460155 0.0259507 -0.0845355 0.460646 0.0256984 -0.0849587 0.460716 0.0283573 -0.085067 0.458299 0.0324031 -0.085051 0.455621 0.0355073 -0.0854685 0.459922 0.0308867 -0.0852416 0.458877 0.0327707 -0.0854049 0.459658 0.0307802 -0.0851851 0.458659 0.0326258 -0.0853474 0.457139 0.0340796 -0.0853337 0.458458 0.0324986 -0.0852224 0.457294 0.0342393 -0.0854491 0.45763 0.0345932 -0.0855007 0.455861 0.0359099 -0.0855199 0.440804 -0.0204287 -0.0854991 0.441097 -0.0186065 -0.0856573 0.440958 -0.0204575 -0.0853136 0.440536 -0.0188132 -0.085765 0.440136 -0.0203046 -0.085765 0.439958 -0.0222528 -0.085765 0.443102 -0.0155009 -0.0856756 0.444315 -0.0139712 -0.085765 0.446069 -0.0130442 -0.085765 0.447964 -0.0128909 -0.0856883 0.449827 -0.0127185 -0.0856889 0.440668 -0.0222528 -0.0854688 0.440603 -0.0203914 -0.0856449 0.448024 -0.0132105 -0.08547 0.446173 -0.0134229 -0.0856858 0.444537 -0.0143037 -0.0856816 0.444722 -0.0145807 -0.0854453 0.443343 -0.0157401 -0.0854236 0.441944 -0.0169513 -0.0856676 0.442233 -0.0171425 -0.0853944 0.440824 -0.0277473 -0.085265 0.440668 -0.0277473 -0.0854688 0.440458 -0.0222528 -0.085631 0.453335 -0.0137179 -0.0854609 0.451799 -0.0129122 -0.0856882 0.459303 -0.0195606 -0.0854889 0.458817 -0.0224002 -0.085155 0.458546 -0.0197425 -0.0852684 0.457416 -0.0173239 -0.0852672 0.456001 -0.0149974 -0.0856602 0.456278 -0.0146867 -0.0857431 0.457068 -0.0154561 -0.085713 0.457955 -0.0170254 -0.0856252 0.459042 -0.0196268 -0.0854902 0.453671 -0.0135041 -0.0856854 0.459075 -0.0224028 -0.0853289 0.458779 -0.01969 -0.0854152 0.457751 -0.017142 -0.0855564 0.457566 -0.0172442 -0.0854327 0.456326 -0.0158108 -0.0853796 0.455769 -0.0152519 -0.0854119 0.440558 -0.0293206 -0.0856429 0.440916 -0.029265 -0.0853063 0.440458 -0.0277473 -0.085631 0.458619 -0.025 -0.084901 0.458632 -0.0223975 -0.0849227 0.459068 -0.0250058 -0.0853095 0.459669 -0.0250094 -0.0853838 0.459374 -0.0224049 -0.085415 0.449827 -0.0365589 -0.0850738 0.446958 -0.0365911 -0.0853798 0.446838 -0.0370432 -0.0854188 0.444087 -0.0357818 -0.0855861 0.442219 -0.0334205 -0.0856408 0.442496 -0.0331974 -0.0853689 0.443397 -0.0342021 -0.0853333 0.444327 -0.0354023 -0.0855232 0.441874 -0.0336901 -0.0857309 0.441429 -0.0312689 -0.085357 0.440907 -0.0308554 -0.0856537 0.441096 -0.0307925 -0.0855182 0.441245 -0.0307429 -0.0853446 0.458806 -0.025003 -0.0851349 0.45937 -0.025008 -0.0853943 0.453662 -0.0362679 -0.0854249 0.449827 -0.0374423 -0.085351 0.451781 -0.0367976 -0.0853483 0.45186 -0.0372626 -0.0853824 0.449827 -0.0369665 -0.0853208 0.458367 -0.0307665 -0.0852354 0.458185 -0.0307184 -0.0850379 0.458796 -0.027587 -0.0851148 0.45906 -0.0275897 -0.0852899 0.458954 -0.0292393 -0.0853122 0.459245 -0.029282 -0.0853866 0.459366 -0.0275918 -0.0853733 0.459668 -0.0275931 -0.0853599 0.459598 -0.028826 -0.0853631 0.456759 -0.0341177 -0.0855072 0.453827 -0.0366998 -0.085471 0.455636 -0.0357309 -0.0855517 0.456937 -0.0342791 -0.0855673 0.457111 -0.0344445 -0.0855674 0.458086 -0.0326995 -0.085528 0.458304 -0.0328315 -0.0855245 0.453533 -0.0358981 -0.0851751 0.458793 -0.0308914 -0.0854366 0.457862 -0.0325748 -0.0854639 0.45766 -0.0324646 -0.0853352 0.457498 -0.0323792 -0.0851577 0.458542 -0.0308163 -0.0853505 0.455333 -0.0353764 -0.0854949 0.453975 -0.0357101 -0.0851964 0.455119 -0.0350527 -0.0852348 0.486827 0.0291262 0.0130536 0.487458 0.0270182 0.0123351 0.486913 0.0298494 0.0131158 0.488652 0.0135372 0.0116476 0.489156 -4.19898e-08 0.010964 0.488319 0.0203268 0.0114419 0.488178 0.0202904 0.0119204 0.4873 0.0269832 0.0125357 0.488657 -4.19898e-08 0.0117881 0.487823 0.0202419 0.0122697 0.487104 0.026947 0.0126848 0.485567 0.0370158 0.0197261 0.485397 0.0368678 0.021038 0.485629 0.0363177 0.0192394 0.485908 0.0360164 0.0174941 0.486233 0.0348189 0.0157807 0.486483 0.0330989 0.0147347 0.486781 0.0315646 0.0136717 0.487162 0.0301136 0.012491 0.487052 0.0299381 0.0129301 0.486735 0.0297705 0.013257 0.485063 0.0371367 0.0247792 0.486199 0.0328164 0.0149986 0.486183 0.0344166 0.0160438 0.485631 0.0351319 0.0177414 0.485893 0.0355012 0.0175692 0.485144 0.036447 0.0211026 0.485208 0.0371351 0.0228909 0.484956 0.0367029 0.0228998 0.484809 0.0367021 0.024735 0.489013 -4.19897e-08 0.0114401 0.488652 -0.0135373 0.0116476 0.487823 -0.020242 0.0122697 0.487104 -0.0269471 0.0126848 0.488297 -0.0135069 0.0119962 0.4873 -0.0269833 0.0125357 0.488795 -0.0135601 0.0111703 0.488656 -0.0158865 0.0112496 0.488178 -0.0202905 0.0119204 0.487457 -0.0270183 0.0123352 0.484962 0.0368994 0.0247575 0.485113 0.0319771 0.0347673 0.485011 0.0338153 0.0333195 0.484916 0.0364845 0.028127 0.484958 0.0373063 0.0270925 0.484925 0.0369701 0.0282871 0.485073 0.032822 0.0338425 0.485089 0.0312456 0.0345819 0.485151 0.031383 0.0348145 0.485165 0.0297059 0.0352929 0.484655 0.0360681 0.0279847 0.484695 0.0363981 0.02681 0.485021 0.0296126 0.0350667 0.484893 0.0324976 0.0334517 0.484715 0.0323709 0.0333064 0.484913 0.0365389 0.0294048 0.484955 0.031119 0.0343748 0.485017 0.0326532 0.0336366 0.484915 0.0349697 0.0311597 0.484812 0.0362564 0.0280498 0.484803 0.034769 0.0310259 0.486735 -0.0297701 0.0132569 0.487162 -0.0301137 0.012491 0.487034 -0.0275398 0.01274 0.487051 -0.0299369 0.0129324 0.487272 -0.0293986 0.0122622 0.484904 0.0278297 0.0353722 0.484823 0.0295368 0.0348947 0.485352 0.0280106 0.0360699 0.48551 0.0261716 0.0365999 0.485346 0.0280682 0.0363468 0.485235 0.0298068 0.0355491 0.485274 0.0279464 0.0357925 0.485117 0.0278836 0.0355508 0.485254 0.0261007 0.0357661 0.485026 0.0260689 0.0355857 0.486472 -0.0331411 0.0147736 0.486175 -0.0344443 0.0160809 0.485722 -0.0365975 0.0186425 0.485624 -0.0363254 0.0192667 0.485394 -0.0368683 0.0210534 0.485207 -0.0371325 0.0228953 0.485072 -0.037641 0.024812 0.485174 -0.0376631 0.0233959 0.484962 -0.0368994 0.0247575 0.484809 -0.0367022 0.024735 0.484955 -0.0367033 0.0229039 0.485142 -0.0364502 0.021117 0.485369 -0.0359282 0.0193852 0.485887 -0.0355163 0.0176004 0.48619 -0.0328589 0.0150343 0.486769 -0.0316211 0.013707 0.486472 -0.0313934 0.0140039 0.486338 0.0130918 0.0370866 0.486342 0.0130856 0.0367913 0.486253 0.013076 0.0364952 0.486487 -4.20523e-08 0.0366312 0.486085 -4.19898e-08 0.0361968 0.485512 0.0261556 0.0363086 0.485425 0.0261311 0.0360171 0.486078 0.013064 0.0362406 0.485062 -0.0371338 0.0247789 0.484925 -0.0369701 0.0282878 0.484912 -0.036364 0.0297845 0.48503 -0.0334547 0.0336526 0.48496 -0.0351722 0.031328 0.485007 -0.0340764 0.0326863 0.484916 -0.0349552 0.0311808 0.485075 -0.0327815 0.0338746 0.484894 -0.0324588 0.0334822 0.484716 -0.0323328 0.0333364 0.484957 -0.0310695 0.0344017 0.485091 -0.0311951 0.0346095 0.484728 -0.0365387 0.0261076 0.485138 -0.0315195 0.0350428 0.485154 -0.0313313 0.0348429 0.485019 -0.0326136 0.0336678 0.484804 -0.0347547 0.0310466 0.484916 -0.0364843 0.0281277 0.484812 -0.0362563 0.0280505 0.485852 -0.0130519 0.0360622 0.486311 -4.22236e-08 0.0363758 0.486081 -0.0130643 0.0362446 0.486342 -0.0130857 0.0367931 0.486338 -0.0130919 0.0370866 0.486576 -4.20783e-08 0.0369283 0.486572 -4.19898e-08 0.0372243 0.486254 -0.0130762 0.0364985 0.485346 -0.0280684 0.0363467 0.485117 -0.0278838 0.0355508 0.485254 -0.0261008 0.0357661 0.485274 -0.0279466 0.0357925 0.485425 -0.0261311 0.0360171 0.485512 -0.0261557 0.0363086 0.485021 -0.0296129 0.0350666 0.485165 -0.0297062 0.0352928 0.485235 -0.029807 0.0355491 0.485352 -0.0280108 0.0360699 0.483443 -0.0306679 0.0161658 0.4835 -0.029507 0.0153982 0.482646 -0.0319358 0.0167162 0.483241 -0.0316717 0.0170861 0.483608 -0.0310703 0.0163598 0.483643 -0.0295251 0.0154084 0.483667 -0.0307589 0.0161048 0.48387 -0.0296005 0.0153407 0.482471 -0.0326817 0.017621 0.482824 -0.0317041 0.0169698 0.482952 -0.0316608 0.0170369 0.482427 -0.0332773 0.0192484 0.482558 -0.0332221 0.0192957 0.482705 -0.0332062 0.0193258 0.48304 -0.0325313 0.0181524 0.482847 -0.0332291 0.0193358 0.483348 -0.0322775 0.0176158 0.481988 -0.0342448 0.0218556 0.481723 -0.0344314 0.0246883 0.481883 -0.0342898 0.0246896 0.482225 -0.0340897 0.0219093 0.482633 -0.0341469 0.0219417 0.482628 -0.034351 0.0229045 0.482231 -0.0335625 0.0190772 0.482016 -0.0341847 0.0206508 0.482991 -0.0301889 0.0152502 0.482728 -0.0317724 0.0168861 0.483235 -0.0295356 0.0152665 0.483098 -0.0316503 0.0170767 0.482325 -0.0333622 0.019191 0.482092 -0.0341514 0.0218838 0.482372 -0.0340701 0.0219284 0.482513 -0.0340924 0.0219391 0.482969 -0.0332814 0.0193281 0.482725 -0.0342202 0.0219379 0.482133 -0.0337875 0.027221 0.481503 -0.0341539 0.0273103 0.481472 -0.0337284 0.0284771 0.482478 -0.0343716 0.024735 0.482299 -0.0342569 0.0247153 0.48231 -0.031245 0.0315846 0.482298 -0.0318693 0.030935 0.4822 -0.0327956 0.0295608 0.482297 -0.0331285 0.0291223 0.482122 -0.0293229 0.032876 0.482005 -0.0292959 0.0328874 0.481689 -0.0312156 0.0315735 0.48159 -0.03128 0.0316438 0.481558 -0.0294711 0.0332659 0.481611 -0.0339425 0.02725 0.481636 -0.0346267 0.0246956 0.481958 -0.0311549 0.0315017 0.482081 -0.0327532 0.029535 0.481817 -0.0311717 0.0315236 0.481799 -0.0327584 0.0295382 0.481462 -0.0326606 0.0303744 0.482308 -0.0334511 0.0284702 0.482252 -0.0338367 0.02724 0.482088 -0.0342278 0.0246992 0.481982 -0.0342478 0.0246934 0.482326 -0.0305451 0.0321867 0.482215 -0.0311985 0.0315391 0.482095 -0.0311657 0.0315086 0.482097 -0.0333409 0.0284175 0.481942 -0.0327384 0.029526 0.481994 -0.0337694 0.0272108 0.481849 -0.0337909 0.0272123 0.481668 -0.0328128 0.0295713 0.481716 -0.0338519 0.0272262 0.481565 -0.0328933 0.0296202 0.483078 -0.0296854 0.0149478 0.483432 -0.0277274 0.0143919 0.483103 -0.0295355 0.0148644 0.483145 -0.0295787 0.0151618 0.483358 -0.0295102 0.0153496 0.483769 -0.0295586 0.0153857 0.48404 -0.0277438 0.014639 0.484144 -0.0277724 0.0145917 0.483775 -0.0257323 0.0141501 0.483516 -0.0277067 0.0145053 0.483633 -0.0276976 0.0145956 0.483772 -0.0277021 0.0146492 0.483913 -0.0277188 0.0146618 0.484286 -0.0257846 0.0142962 0.482304 -0.0261664 0.0339948 0.481681 -0.0272389 0.0341825 0.481578 -0.0293381 0.0332596 0.481654 -0.0293019 0.03311 0.481851 -0.0272902 0.0338465 0.481687 -0.0292936 0.0330682 0.481869 -0.0292812 0.0329326 0.482173 -0.0283704 0.0333495 0.482355 -0.029428 0.0329325 0.482259 -0.0293742 0.0328944 0.48239 -0.0284158 0.0334288 0.482446 -0.0273083 0.0338166 0.482229 -0.0272845 0.0337374 0.481867 -0.0249972 0.0345535 0.481951 -0.0249935 0.0343414 0.481761 -0.027311 0.0339393 0.481968 -0.0272779 0.033777 0.482034 -0.0249963 0.0342477 0.482099 -0.0272762 0.0337399 0.482399 -0.0250241 0.0341257 0.485479 -0.0129296 0.0136228 0.485244 -0.0129153 0.0136893 0.485105 -0.0129085 0.0136735 0.485185 -4.19839e-08 0.0133321 0.485059 -4.19898e-08 0.0129745 0.484813 -0.0193554 0.0139384 0.48497 -0.0129032 0.0136163 0.484427 -0.0193313 0.0137718 0.484857 -0.0129002 0.0135223 0.484349 -0.0193304 0.0136551 0.4843 -0.0193375 0.0134159 0.484779 -0.0128996 0.0134052 0.483696 -0.025731 0.0140338 0.48454 -0.0193362 0.0138655 0.483887 -0.0257395 0.0142434 0.484674 -0.0193447 0.0139226 0.484021 -0.0257518 0.0143004 0.484159 -0.0257676 0.0143163 0.484392 -0.0258007 0.0142507 0.482636 -0.0125199 0.0349934 0.483601 -4.19898e-08 0.0347626 0.483389 -4.20472e-08 0.0346971 0.483138 -4.20094e-08 0.0347433 0.483169 -0.0125304 0.03457 0.482268 -0.0250122 0.0341334 0.482147 -0.0250029 0.0341736 0.482917 -0.0125222 0.0346166 0.482721 -0.0125185 0.0347825 0.48251 -0.0155927 0.0349211 0.484731 0.012904 0.0131655 0.484859 0.0128998 0.0135242 0.485107 -4.19838e-08 0.0132147 0.484973 0.012903 0.0136181 0.485298 -4.19844e-08 0.0134263 0.485109 0.0129084 0.0136746 0.485433 -4.19852e-08 0.0134837 0.485573 -4.19862e-08 0.0134996 0.48435 0.0193305 0.0136566 0.48478 0.0128993 0.0134067 0.484543 0.0193364 0.0138673 0.484818 0.0193559 0.0139382 0.485249 0.0129152 0.0136892 0.485047 0.019378 0.0138722 0.483697 0.0257309 0.0140353 0.484429 0.0193314 0.0137737 0.48389 0.0257396 0.0142452 0.484679 0.019345 0.0139236 0.484025 0.0257522 0.0143014 0.484164 0.0257682 0.0143161 0.483169 0.0125303 0.03457 0.48338 0.0125395 0.0346354 0.48261 0.0250475 0.0341906 0.482941 -4.19925e-08 0.0349085 0.482721 0.0125184 0.0347825 0.481951 0.0249934 0.0343414 0.48251 0.0155924 0.0349211 0.482917 0.0125221 0.0346166 0.482268 0.0250121 0.0341334 0.483103 0.0295337 0.0148655 0.48317 0.0294312 0.015082 0.483529 0.0276142 0.0144789 0.483381 0.029366 0.0152715 0.483523 0.0293635 0.0153206 0.483666 0.0293815 0.015331 0.483926 0.0276275 0.014636 0.483387 0.0276903 0.0141323 0.483445 0.0276339 0.0143652 0.483776 0.0257323 0.014152 0.483646 0.0276059 0.0145694 0.483785 0.0276108 0.0146232 0.484052 0.027652 0.0146132 0.484156 0.02768 0.0145659 0.481554 0.0295605 0.0332149 0.482004 0.029366 0.0328475 0.482355 0.0294279 0.0329325 0.481968 0.0272779 0.033777 0.481905 0.0293725 0.0328652 0.481851 0.0272901 0.0338465 0.481558 0.0294764 0.0332568 0.481604 0.0294875 0.0330849 0.482099 0.0272761 0.0337399 0.482173 0.0283703 0.0333495 0.482399 0.025024 0.0341257 0.48252 0.0261964 0.0340656 0.482304 0.0261663 0.0339948 0.48239 0.0284157 0.0334288 0.482446 0.0273082 0.0338166 0.482229 0.0272844 0.0337374 0.482147 0.0250028 0.0341736 0.482034 0.0249962 0.0342477 0.481761 0.027311 0.0339393 0.481821 0.0254994 0.0345133 0.481867 0.0249971 0.0345535 0.482476 0.0326622 0.0175931 0.482478 0.0343715 0.024735 0.482299 0.0342568 0.0247153 0.481694 0.0346533 0.0238901 0.481909 0.0344194 0.0215762 0.482338 0.0333203 0.0191076 0.482097 0.0341426 0.021837 0.482377 0.0340614 0.0218821 0.482678 0.0337311 0.0205449 0.482868 0.0339156 0.0207105 0.482981 0.0332402 0.0192464 0.483155 0.0330344 0.0187227 0.482748 0.0316804 0.0167889 0.482844 0.0316131 0.0168738 0.483259 0.0293901 0.0151877 0.483117 0.0315603 0.016982 0.483792 0.0294144 0.0153082 0.483384 0.0316265 0.0169741 0.483779 0.0301443 0.0156659 0.481723 0.0344313 0.0246883 0.481992 0.0342359 0.0218083 0.48223 0.0340809 0.0218629 0.482088 0.0342278 0.0246992 0.482381 0.0342526 0.0232938 0.482518 0.0340837 0.0218929 0.48266 0.0343142 0.0225651 0.482439 0.0332359 0.019166 0.482571 0.033181 0.019214 0.482717 0.0331652 0.0192444 0.482972 0.0315705 0.0169417 0.482859 0.0331881 0.0192544 0.48326 0.0315816 0.0169914 0.483477 0.0317062 0.0169613 0.481469 0.033652 0.0286498 0.482328 0.0304633 0.03225 0.482139 0.0293731 0.032851 0.482112 0.0303946 0.0321706 0.481586 0.0314342 0.0314917 0.481565 0.0329666 0.0294968 0.481955 0.0313062 0.0313533 0.482081 0.0321365 0.0304303 0.482082 0.0328254 0.0294147 0.482201 0.0328682 0.0294401 0.481613 0.0339631 0.0271804 0.481883 0.0342897 0.0246896 0.481982 0.0342477 0.0246934 0.482136 0.0338079 0.027153 0.482255 0.0338572 0.0271717 0.481536 0.0300443 0.0329161 0.481758 0.029404 0.0329297 0.481686 0.0313683 0.031423 0.481813 0.0313233 0.0313744 0.482092 0.0313173 0.0313605 0.482304 0.0315101 0.0313233 0.48146 0.0331558 0.0296081 0.481669 0.0328854 0.0294493 0.481718 0.0338723 0.0271573 0.4818 0.0328305 0.0294171 0.481851 0.0338112 0.0271439 0.481943 0.0328104 0.0294056 0.481997 0.0337897 0.0271427 0.440726 0.00241502 -0.0823172 0.440726 0.0248349 -0.0823172 0.44066 0.00241502 -0.082012 0.440704 0.00241502 -0.0821105 0.440229 0.00241502 -0.081765 0.440598 0.0264564 -0.0818227 0.440774 0.0281069 -0.081765 0.441461 0.0296273 -0.081765 0.442593 0.0308449 -0.0818283 0.44167 0.029509 -0.0818267 0.442685 0.030769 -0.0819209 0.442751 0.0307148 -0.0824873 0.442784 0.0306869 -0.0823561 0.442788 0.0306839 -0.0822047 0.442754 0.0307119 -0.0820519 0.441212 0.0279549 -0.0824527 0.441857 0.0294034 -0.0824717 0.441243 0.027944 -0.0823231 0.441891 0.0293843 -0.0823411 0.441892 0.029384 -0.0821924 0.4408 0.0264232 -0.0820231 0.441239 0.0279454 -0.0821777 0.440833 0.0264177 -0.0824316 0.441773 0.029451 -0.0819165 0.440998 0.0280291 -0.0818248 0.440432 0.0248349 -0.0818082 0.4406 0.0248349 -0.0819304 0.441851 0.0294068 -0.0820436 0.441108 0.027991 -0.0819113 0.440711 0.0264378 -0.0819057 0.441193 0.0279615 -0.0820338 0.44085 0.0264148 -0.0821618 0.440704 0.0248349 -0.0821105 0.44086 0.0264133 -0.0823034 0.449827 0.0339109 -0.0823528 0.447807 0.0337513 -0.0824609 0.4459 0.0331415 -0.0824836 0.447794 0.033825 -0.0825575 0.445821 0.0332916 -0.0818099 0.447793 0.0337924 -0.0818877 0.44781 0.0337139 -0.0820258 0.447818 0.0336822 -0.0821821 0.445923 0.0330799 -0.0822028 0.447816 0.0336984 -0.0823332 0.444064 0.0322533 -0.0818286 0.444215 0.0320617 -0.0822152 0.444181 0.0321093 -0.0824973 0.442699 0.0307576 -0.0825893 0.448625 0.0342844 -0.0816976 0.449827 0.034135 -0.0817589 0.447769 0.0339032 -0.0817863 0.449827 0.0339689 -0.0819141 0.449827 0.0339166 -0.0820157 0.449827 0.0338887 -0.0821267 0.445919 0.0330934 -0.0823547 0.44587 0.0331867 -0.0819094 0.445906 0.0331115 -0.0820464 0.444137 0.0321603 -0.0819251 0.44419 0.0320922 -0.0820599 0.44421 0.0320702 -0.0823672 0.452092 0.0341113 -0.0817076 0.451814 0.0339168 -0.0817856 0.453727 0.0333427 -0.0818048 0.451775 0.0337274 -0.0820251 0.453627 0.0331251 -0.0822054 0.453631 0.0331385 -0.0823514 0.451741 0.0338482 -0.0825562 0.449827 0.0343526 -0.0816933 0.451792 0.033806 -0.0818871 0.451767 0.0336957 -0.0821815 0.451769 0.033712 -0.0823326 0.451778 0.033765 -0.0824602 0.448035 -0.00657665 -0.0820694 0.449827 -0.00695299 -0.0818344 0.447996 -0.00678387 -0.0818316 0.449827 -0.00720715 -0.081765 0.44623 -0.00626949 -0.0818311 0.444611 -0.00541367 -0.0818302 0.446133 -0.00649849 -0.081765 0.440432 0.00241502 -0.0818082 0.446309 -0.00607434 -0.0820668 0.448018 -0.00666411 -0.08193 0.444678 -0.00531318 -0.0819262 0.444727 -0.00523891 -0.0820622 0.443333 -0.00409722 -0.0820557 0.446275 -0.00615691 -0.0819286 0.44084 0.000604493 -0.0820246 0.4406 0.00241502 -0.0819304 0.440751 0.000587872 -0.0819065 0.440638 0.000566634 -0.081823 0.441363 -0.00111501 -0.0824583 0.442195 -0.00271006 -0.0824785 0.440898 0.000615565 -0.0823062 0.44089 0.000613976 -0.082164 0.441393 -0.00110306 -0.082182 0.441348 -0.00112112 -0.0820366 0.442119 -0.00276085 -0.0819184 0.441157 -0.00119848 -0.0818253 0.44202 -0.00282649 -0.0818274 0.441396 -0.00110197 -0.0823283 0.442231 -0.00268604 -0.0821977 0.442194 -0.00271116 -0.0820472 0.44327 -0.00416042 -0.0819228 0.443185 -0.00424504 -0.081829 0.442905 -0.00430895 -0.081765 0.449827 -0.00677737 -0.0825205 0.448029 -0.00660559 -0.0825189 0.446299 -0.00609816 -0.0825144 0.444681 -0.00531799 -0.0826063 0.443326 -0.00410411 -0.0824942 0.442144 -0.00274987 -0.0825813 0.442141 -0.00274598 -0.0825813 0.446324 -0.00603777 -0.0822267 0.448039 -0.00655239 -0.0823871 0.443364 -0.00406692 -0.0822103 0.443359 -0.00407163 -0.0823628 0.444717 -0.00525471 -0.0825061 0.444745 -0.00521325 -0.0823744 0.446319 -0.00604941 -0.0823826 0.441265 -0.00115475 -0.0819128 0.448042 -0.00653868 -0.0822305 0.44475 -0.00520486 -0.0822199 0.442229 -0.00268734 -0.0823476 0.440871 0.000610394 -0.0824346 0.455634 0.0324921 -0.0817371 0.456937 0.0308513 -0.0817449 0.455351 0.032116 -0.0823459 0.456757 0.0306887 -0.0821368 0.455344 0.0321088 -0.0821945 0.456785 0.0306977 -0.0823404 0.455382 0.0321536 -0.0824756 0.453641 0.0331648 -0.0824342 0.453825 0.0335647 -0.0817326 0.455487 0.0323006 -0.0818087 0.453657 0.033187 -0.0819777 0.455417 0.0322082 -0.0819056 0.455366 0.0321402 -0.08204 0.451788 -0.00657355 -0.0825193 0.449827 -0.00672296 -0.0823897 0.449827 -0.0067081 -0.0822342 0.451782 -0.00654298 -0.082073 0.449827 -0.00674521 -0.0820736 0.4518 -0.00662849 -0.0819335 0.449827 -0.00683248 -0.0819339 0.451824 -0.00674643 -0.0818343 0.45185 -0.00687457 -0.0817804 0.451875 -0.00699516 -0.081765 0.449827 -0.00708394 -0.0817804 0.45368 -0.0060397 -0.0826126 0.451804 -0.00664788 -0.0826175 0.453649 -0.0059719 -0.0825138 0.451777 -0.00652063 -0.0823886 0.451774 -0.00650642 -0.0822332 0.453623 -0.0059126 -0.0822286 0.453638 -0.00594758 -0.0820698 0.453674 -0.00602737 -0.0819319 0.453777 -0.00625564 -0.0817803 0.459117 0.0249552 -0.0814171 0.456812 0.0307449 -0.0819043 0.457682 0.0294333 -0.0817636 0.456783 0.0307184 -0.0819776 0.457642 0.0293762 -0.082289 0.458924 0.0246791 -0.0815063 0.458777 0.0263399 -0.0815228 0.458395 0.0279602 -0.0815805 0.458622 0.0263112 -0.0817257 0.458243 0.0279005 -0.0817922 0.458213 0.0278841 -0.0819253 0.458665 0.0263079 -0.0821929 0.458588 0.0263003 -0.0819799 0.458588 0.0263031 -0.0818527 0.458721 0.0246822 -0.0819464 0.45816 0.0291887 -0.081554 0.457769 0.029485 -0.0816685 0.458306 0.027927 -0.0816733 0.457621 0.0293928 -0.0818882 0.458218 0.027879 -0.0820576 0.457594 0.0293694 -0.0820284 0.457604 0.0293646 -0.0821669 0.4577 0.0293989 -0.0823869 0.45539 -0.00492063 -0.0824957 0.456802 -0.00350488 -0.0820148 0.455352 -0.00487601 -0.0822134 0.456774 -0.00347684 -0.0821647 0.456782 -0.00347792 -0.0823125 0.456818 -0.0035027 -0.0824406 0.458602 0.000102395 -0.0823623 0.458439 -0.000515764 -0.0823889 0.45855 0.000112244 -0.082262 0.457888 -0.00178809 -0.0823523 0.458947 -4.19898e-08 -0.0815825 0.458558 9.99595e-05 -0.0818704 0.45852 0.000112607 -0.0820051 0.456951 -0.00363321 -0.0817892 0.454829 -0.00583956 -0.0817637 0.453628 -0.0059243 -0.0823831 0.455359 -0.00488297 -0.0823656 0.455375 -0.00490817 -0.0820579 0.455427 -0.00497749 -0.0819229 0.455498 -0.00507138 -0.0818262 0.453723 -0.00613682 -0.0818337 0.458254 -0.00199235 -0.0816475 0.458045 -0.00188832 -0.0817254 0.456865 -0.00356009 -0.0818842 0.45795 -0.00183873 -0.0818181 0.45788 -0.00180023 -0.0819429 0.457847 -0.0017786 -0.0820855 0.457852 -0.00177547 -0.0822272 0.458266 -0.00104048 -0.0824137 0.459122 0.0246794 -0.0814188 0.459128 0.0239622 -0.0814252 0.45884 0.0232451 -0.0816059 0.458765 0.0246801 -0.0817 0.458727 0.0246811 -0.0818246 0.458729 0.0232477 -0.081959 0.459235 0.00250794 -0.081547 0.458517 0.000116364 -0.0821219 0.458519 0.000116376 -0.0821402 0.458727 0.00130483 -0.082101 0.458802 0.00129926 -0.0823213 0.459162 0.00124537 -0.0815576 0.458715 5.74612e-05 -0.0816735 0.458632 7.94062e-05 -0.0817523 0.458806 0.00250818 -0.0819463 0.458794 0.02325 -0.0821726 0.458837 0.0136251 -0.0822464 0.459233 0.00399872 -0.0815442 0.459196 0.0136216 -0.0815019 0.459019 0.00399861 -0.0816236 0.458934 0.0232448 -0.0815179 0.458922 0.00399868 -0.0817077 0.458774 0.0232457 -0.0817116 0.458847 0.00399884 -0.0818178 0.458796 0.00399936 -0.0820717 0.458862 0.00399996 -0.0822903 0.458805 0.00399907 -0.0819436 0.458798 0.00250837 -0.0820745 0.458849 0.00250802 -0.0818203 0.458924 0.00250792 -0.0817102 0.459021 0.00250787 -0.0816261 0.442924 -0.0205352 -0.0825621 0.446796 -0.016121 -0.081765 0.44689 -0.0163513 -0.0818311 0.447598 -0.0158477 -0.081765 0.448328 -0.0159342 -0.0818315 0.449827 -0.0156607 -0.081779 0.442229 -0.0234151 -0.081832 0.44232 -0.0234151 -0.0818998 0.442466 -0.0219378 -0.0819063 0.446969 -0.0165464 -0.0820668 0.445688 -0.0172243 -0.0820621 0.446935 -0.0164639 -0.0819286 0.449827 -0.0159144 -0.0819302 0.44835 -0.016054 -0.0819299 0.445638 -0.0171501 -0.0819262 0.445571 -0.0170497 -0.0818302 0.44459 -0.0181719 -0.0823627 0.444057 -0.0185963 -0.0825894 0.446959 -0.0165226 -0.0825144 0.445677 -0.0172086 -0.0825059 0.446979 -0.0165714 -0.0823826 0.448361 -0.0161126 -0.0825189 0.442772 -0.0204741 -0.0818253 0.443466 -0.0191595 -0.0818273 0.443565 -0.0192248 -0.0819183 0.442881 -0.0205176 -0.0819127 0.442964 -0.020551 -0.0820365 0.44364 -0.0192743 -0.0820471 0.443009 -0.020569 -0.0821817 0.442605 -0.0219635 -0.0821637 0.442613 -0.021965 -0.0823058 0.44269 -0.0200615 -0.081765 0.442353 -0.021917 -0.0818229 0.442554 -0.0219541 -0.0820243 0.444558 -0.0181394 -0.0824941 0.443676 -0.0192981 -0.0823474 0.445705 -0.01725 -0.0823743 0.448371 -0.0161658 -0.0823871 0.446984 -0.016583 -0.0822267 0.448373 -0.0161795 -0.0822305 0.449827 -0.0160276 -0.082388 0.449827 -0.0160418 -0.0822312 0.443642 -0.0192756 -0.0824783 0.443012 -0.0205701 -0.0823281 0.444595 -0.0181765 -0.0822102 0.444565 -0.0181463 -0.0820556 0.445711 -0.0172583 -0.0822197 0.448366 -0.0161415 -0.0820694 0.442634 -0.0214664 -0.0825472 0.442586 -0.02196 -0.0824342 0.442979 -0.0205572 -0.082458 0.443678 -0.0192994 -0.0821975 0.444501 -0.0180831 -0.0819228 0.444416 -0.0179986 -0.081829 0.442479 -0.026585 -0.082265 0.442458 -0.0234151 -0.082409 0.442479 -0.0234151 -0.082265 0.442464 -0.0234151 -0.0821451 0.442412 -0.0234151 -0.082015 0.441979 -0.0234151 -0.081765 0.441979 -0.026585 -0.081765 0.451805 -0.0161485 -0.0826168 0.451773 -0.0162742 -0.082386 0.453575 -0.0170282 -0.0822221 0.451779 -0.0162498 -0.0820688 0.451801 -0.0161636 -0.0819297 0.453596 -0.0169933 -0.0820638 0.451864 -0.0159182 -0.081779 0.449827 -0.0158965 -0.0826185 0.451786 -0.0162221 -0.0825178 0.449827 -0.0159731 -0.0825198 0.449827 -0.0160033 -0.0820699 0.45177 -0.0162874 -0.0822296 0.449827 -0.0157924 -0.0818317 0.451832 -0.0160456 -0.0818315 0.449827 -0.0155429 -0.081765 0.451893 -0.0158043 -0.081765 0.456191 -0.0187949 -0.0817418 0.457413 -0.0218109 -0.0816712 0.4567 -0.0205924 -0.0824971 0.457129 -0.0224857 -0.0824266 0.45711 -0.0234625 -0.0821778 0.456612 -0.0206201 -0.0822703 0.45513 -0.0180828 -0.0825894 0.453606 -0.016975 -0.0825088 0.455119 -0.0181705 -0.0824879 0.453581 -0.0170188 -0.0823771 0.455078 -0.0182058 -0.0822074 0.455107 -0.0181764 -0.0820542 0.453641 -0.0169163 -0.081927 0.453702 -0.0168118 -0.0818305 0.455252 -0.0180329 -0.0818266 0.453768 -0.0166991 -0.0817788 0.45543 -0.01786 -0.0817581 0.45701 -0.0215027 -0.081842 0.45621 -0.0197441 -0.0821612 0.456214 -0.0197457 -0.0823061 0.456889 -0.0215392 -0.0822341 0.457053 -0.0224915 -0.0822034 0.456892 -0.0215358 -0.0820969 0.456933 -0.0215232 -0.0819606 0.457112 -0.0214768 -0.0817538 0.456624 -0.0195084 -0.081725 0.456414 -0.0196239 -0.0817969 0.456317 -0.0196791 -0.0818891 0.456245 -0.0197214 -0.0820156 0.455168 -0.0181151 -0.0819216 0.455085 -0.0182016 -0.0823581 0.45625 -0.0197296 -0.0824334 0.442478 -0.026585 -0.0822826 0.442556 -0.0276809 -0.0823004 0.442464 -0.026585 -0.0821451 0.442925 -0.0294666 -0.0825621 0.443127 -0.029791 -0.0824637 0.442781 -0.0287558 -0.0823172 0.442776 -0.0287575 -0.0821729 0.442304 -0.0288937 -0.081765 0.442229 -0.026585 -0.081832 0.44232 -0.026585 -0.0818998 0.442412 -0.026585 -0.082015 0.442728 -0.0287713 -0.0820306 0.44253 -0.0276845 -0.0824284 0.442751 -0.0287645 -0.0824465 0.44253 -0.0288283 -0.0818241 0.443487 -0.0308633 -0.0818299 0.442642 -0.0287962 -0.0819096 0.44316 -0.0297756 -0.0823335 0.443692 -0.0307265 -0.0823495 0.457559 -0.02423 -0.0816508 0.457561 -0.0234617 -0.0816531 0.457176 -0.0234634 -0.0824008 0.457173 -0.025 -0.0823959 0.45712 -0.0234622 -0.0820468 0.457166 -0.0234618 -0.0819188 0.457245 -0.0234616 -0.081808 0.457342 -0.0249982 -0.0817213 0.457346 -0.0234616 -0.0817252 0.443658 -0.0307493 -0.0824793 0.444834 -0.0321202 -0.0824928 0.444869 -0.0320772 -0.0822115 0.443694 -0.0307248 -0.0822006 0.443658 -0.0307493 -0.0820507 0.444841 -0.0321064 -0.0820574 0.443584 -0.0307982 -0.0819218 0.444538 -0.0324426 -0.0817592 0.446317 -0.0331442 -0.0824818 0.444864 -0.0320844 -0.0823629 0.446283 -0.0331891 -0.0819088 0.444783 -0.0321703 -0.0819237 0.446229 -0.0332914 -0.0818097 0.444704 -0.0322575 -0.081828 0.446116 -0.0335116 -0.0817347 0.446323 -0.0331157 -0.0820453 0.448018 -0.0337174 -0.0820254 0.446342 -0.0330848 -0.0822012 0.446338 -0.0330976 -0.0823529 0.446963 -0.0335144 -0.0825704 0.448015 -0.0337546 -0.0824605 0.448 -0.0338279 -0.0825571 0.448025 -0.0337019 -0.0823328 0.449827 -0.0338849 -0.0821718 0.448027 -0.0336858 -0.0821817 0.449827 -0.0339959 -0.0818776 0.447998 -0.0337955 -0.0818875 0.449827 -0.0341081 -0.0817756 0.447973 -0.0339058 -0.0817861 0.457107 -0.0249992 -0.0821733 0.457117 -0.0249988 -0.0820427 0.457163 -0.0249985 -0.0819149 0.457241 -0.0249983 -0.0818042 0.457237 -0.0265308 -0.0818003 0.457338 -0.0265307 -0.0817173 0.451851 -0.0338665 -0.081788 0.451805 -0.0337155 -0.0824623 0.453184 -0.0333016 -0.0825772 0.453585 -0.032952 -0.0823556 0.452724 -0.0333656 -0.0823456 0.451793 -0.0336632 -0.0823345 0.453581 -0.03294 -0.0822039 0.451801 -0.0336788 -0.0820271 0.451823 -0.0337567 -0.0818892 0.452084 -0.0340609 -0.0817103 0.449827 -0.0343526 -0.0816933 0.450065 -0.0343492 -0.0816934 0.449827 -0.0339167 -0.0820157 0.451792 -0.0336473 -0.0821834 0.449827 -0.0339017 -0.0823225 0.449827 -0.0339558 -0.0824497 0.456114 -0.030863 -0.0818015 0.456315 -0.0309949 -0.0817285 0.455973 -0.0307673 -0.0819743 0.456808 -0.0287358 -0.0822334 0.456527 -0.0298115 -0.0824996 0.456437 -0.0297779 -0.0822784 0.455918 -0.0307256 -0.0822004 0.457027 -0.0276442 -0.0821976 0.457019 -0.0288056 -0.0817468 0.456919 -0.0287759 -0.0818374 0.456845 -0.0287526 -0.0819581 0.456807 -0.0287389 -0.0820957 0.457159 -0.026531 -0.0819109 0.457114 -0.0265313 -0.0820385 0.457104 -0.0265317 -0.0821688 0.455953 -0.0307415 -0.0824207 0.454893 -0.0319765 -0.0823531 0.455927 -0.0307274 -0.0823214 0.454887 -0.0319705 -0.082203 0.454914 -0.0319992 -0.0820502 0.45592 -0.0307272 -0.082175 0.454972 -0.0320611 -0.0819172 0.455051 -0.0321451 -0.0818211 0.453608 -0.032997 -0.0824847 0.454925 -0.0320101 -0.0824822 0.453601 -0.0329708 -0.0820482 0.453644 -0.0330429 -0.0819121 0.453702 -0.033143 -0.0818135 0.453826 -0.0333582 -0.0817397 0.455221 -0.032324 -0.0817496 0.450882 0.0630307 0.054067 0.449614 0.0630216 0.0546511 0.45071 0.0629298 0.0541734 0.452195 0.0629932 0.0521201 0.452285 0.0631116 0.0517199 0.452276 0.0630136 0.0517141 0.44926 0.0635555 0.0477078 0.449279 0.0637358 0.0475508 0.450692 0.0637684 0.047898 0.45177 0.0637342 0.0484955 0.452738 0.063601 0.0502139 0.452853 0.0635618 0.0508146 0.452545 0.0635846 0.0502646 0.452771 0.0634904 0.0521954 0.451418 0.0634286 0.0543715 0.451095 0.0634163 0.0543643 0.450207 0.0634176 0.0550664 0.449698 0.0634071 0.0550061 0.448283 0.0630884 0.0547182 0.452641 0.0634963 0.0517873 0.452132 0.0634424 0.0532297 0.451962 0.0633389 0.0531252 0.450978 0.0633127 0.0542026 0.449653 0.0633034 0.0548122 0.450522 0.063391 0.0481729 0.45157 0.0632132 0.0490843 0.450539 0.0634862 0.0481502 0.451581 0.0633076 0.0490836 0.450831 0.0632798 0.0483781 0.450932 0.0632288 0.054139 0.45237 0.0633087 0.051741 0.452231 0.0633011 0.0503295 0.451608 0.0634045 0.0490705 0.451711 0.0635793 0.0490044 0.450602 0.0636587 0.048051 0.45186 0.0636873 0.0488969 0.448282 0.0631364 0.0547359 0.449622 0.0631228 0.0546821 0.4509 0.063132 0.0540934 0.451849 0.0631582 0.0530527 0.451822 0.0630567 0.0530343 0.452316 0.0632124 0.0517289 0.4522 0.0632021 0.0503311 0.452284 0.0633959 0.0503217 0.452358 0.0634787 0.0503076 0.452446 0.0633923 0.0517554 0.451895 0.063255 0.0530834 0.449635 0.0632195 0.0547363 0.448266 0.0633188 0.0548687 0.448244 0.0634104 0.0550246 0.449307 0.0638211 0.0473331 0.448809 0.0633245 0.0477347 0.449254 0.0633256 0.0477634 0.447898 0.0633289 0.0478556 0.447059 0.0633402 0.048204 0.446661 0.0635305 0.0484275 0.445754 0.063543 0.0494579 0.445307 0.0635226 0.0507584 0.445714 0.0631956 0.0528698 0.445414 0.0633539 0.0521174 0.44542 0.0632657 0.0521098 0.446002 0.0632334 0.0533401 0.446488 0.0638151 0.0481953 0.449294 0.0637957 0.047436 0.448172 0.0638259 0.0472698 0.447816 0.0637987 0.0475368 0.445196 0.063694 0.0507482 0.445508 0.063827 0.0493147 0.445281 0.0636214 0.0521701 0.445026 0.0638063 0.0507282 0.445113 0.0637328 0.052221 0.446999 0.0632091 0.0542763 0.445984 0.0633306 0.0533638 0.448283 0.0629397 0.0546954 0.447009 0.0631089 0.0542467 0.446977 0.0633051 0.0543256 0.448271 0.063279 0.0548278 0.446944 0.0633889 0.0543933 0.449272 0.0636847 0.0476124 0.449257 0.0635105 0.0477281 0.44789 0.0635136 0.047821 0.447861 0.0636876 0.0477083 0.446593 0.0637036 0.0483351 0.445657 0.0637148 0.0494012 0.445389 0.0634488 0.0521303 0.445949 0.063424 0.0534004 0.445896 0.0635065 0.0534485 0.44685 0.0634955 0.0545636 0.445755 0.0636157 0.053566 0.44646 0.0635377 0.0545383 0.448208 0.063434 0.0552655 0.451843 -0.0634366 0.0539636 0.452133 -0.0634433 0.053236 0.44959 -0.0634173 0.0552378 0.449697 -0.0634082 0.0550103 0.448238 -0.0634231 0.0550647 0.45258 -0.0634679 0.0527931 0.452876 -0.063526 0.0514437 0.452743 -0.0635998 0.0502327 0.45255 -0.0635854 0.0502684 0.449317 -0.0638254 0.0472515 0.450104 -0.0638188 0.0474325 0.449272 -0.0636865 0.0476106 0.450604 -0.0636605 0.0480503 0.452284 -0.063112 0.0517254 0.452128 -0.0629833 0.0523454 0.451813 -0.0629581 0.0530313 0.45088 -0.0630314 0.0540684 0.450591 -0.0629284 0.0542473 0.448283 -0.0629398 0.0546954 0.44826 -0.0633537 0.0549138 0.449651 -0.0633053 0.0548147 0.451095 -0.0634174 0.0543688 0.451961 -0.0633407 0.0531304 0.452644 -0.0634971 0.0517939 0.45219 -0.0631054 0.0503316 0.452201 -0.0632024 0.0503354 0.451911 -0.0631651 0.0496148 0.451582 -0.0633082 0.0490851 0.45184 -0.0631766 0.0494851 0.450523 -0.0633916 0.0481737 0.450816 -0.0632808 0.0483681 0.449254 -0.0633256 0.0477634 0.451609 -0.0634056 0.0490719 0.450541 -0.0634874 0.0481506 0.449613 -0.0630223 0.0546516 0.451714 -0.063581 0.049005 0.452315 -0.0632134 0.0517345 0.45237 -0.0633101 0.0517467 0.451847 -0.0631594 0.053057 0.450899 -0.0631333 0.0540951 0.45182 -0.0630573 0.0530384 0.452233 -0.0633021 0.0503337 0.451179 -0.0637772 0.0479816 0.450695 -0.0637697 0.0478959 0.451865 -0.0636884 0.0488965 0.452361 -0.0634803 0.0503116 0.452287 -0.0633973 0.0503259 0.452447 -0.0633939 0.0517614 0.451894 -0.0632567 0.0530881 0.450977 -0.0633145 0.0542057 0.450931 -0.0632305 0.0541414 0.449633 -0.0632213 0.0547379 0.44962 -0.0631241 0.054683 0.448284 -0.0630385 0.0547054 0.448809 -0.0629293 0.054735 0.44943 -0.062924 0.0546794 0.447862 -0.0636877 0.0477081 0.448231 -0.063434 0.0551168 0.447131 -0.0634828 0.0549378 0.449287 -0.0637732 0.0474883 0.447418 -0.0638321 0.0474699 0.445846 -0.0638558 0.0485408 0.445115 -0.0637323 0.0522168 0.445602 -0.0636405 0.0536796 0.447057 -0.0630116 0.0542653 0.445419 -0.0632659 0.0521065 0.445527 -0.0632367 0.0524525 0.445412 -0.0633576 0.0521145 0.445778 -0.0631828 0.0529852 0.446154 -0.0631196 0.0535158 0.445307 -0.063525 0.0507543 0.445785 -0.063361 0.0494723 0.445755 -0.0635453 0.0494543 0.446117 -0.0633573 0.0489979 0.446662 -0.0635328 0.0484253 0.446682 -0.0633471 0.0484552 0.447899 -0.063329 0.0478554 0.447094 -0.0633397 0.0481841 0.449258 -0.063514 0.0477268 0.449254 -0.0634006 0.0477578 0.448809 -0.0633246 0.047735 0.446851 -0.0634949 0.054561 0.446943 -0.063389 0.0543929 0.44528 -0.0636218 0.0521666 0.445755 -0.0636152 0.0535628 0.445196 -0.0636942 0.050744 0.445029 -0.0638056 0.050724 0.445512 -0.0638262 0.0493124 0.446595 -0.0637036 0.0483336 0.446491 -0.0638143 0.0481956 0.447818 -0.063798 0.0475388 0.445309 -0.0633215 0.051235 0.445387 -0.0634513 0.0521273 0.446001 -0.0632371 0.0533391 0.445895 -0.0635067 0.0534468 0.446976 -0.0633063 0.054326 0.44828 -0.0631771 0.0547554 0.448266 -0.0633207 0.0548707 0.446998 -0.0632116 0.0542769 0.447008 -0.0631126 0.0542471 0.445983 -0.0633332 0.053363 0.445659 -0.0637149 0.049398 0.447891 -0.063516 0.0478199 0.449264 -0.0636163 0.0476709 0.443504 0.0601701 -0.0366498 0.442077 0.0601221 -0.0377483 0.44247 0.0598586 -0.0429841 0.44206 0.0599014 -0.0428034 0.441473 0.0599445 -0.0418175 0.441641 0.0599132 -0.0417465 0.441261 0.0599741 -0.0411398 0.441169 0.0600113 -0.0402868 0.441349 0.0599776 -0.0402853 0.441638 0.0600421 -0.0388229 0.441261 0.0600485 -0.0394338 0.443482 0.0598529 -0.0439138 0.445169 0.0598051 -0.0440888 0.445169 0.0598367 -0.0442868 0.443827 0.059444 -0.0435073 0.44269 0.0594813 -0.0427481 0.441905 0.0596318 -0.0416252 0.443533 0.0593574 -0.0433592 0.443829 0.0593504 -0.0434985 0.443814 0.0598542 -0.0370012 0.442666 0.0598173 -0.0377698 0.442585 0.0599851 -0.0376967 0.441795 0.0599308 -0.0388831 0.441633 0.0596969 -0.0402731 0.442672 0.0595766 -0.04277 0.443775 0.0597129 -0.0436447 0.443818 0.0595398 -0.0435342 0.443829 0.0596731 -0.0370314 0.443419 0.059663 -0.0372341 0.442138 0.0595991 -0.0385151 0.442076 0.0595936 -0.0386262 0.444741 0.0596851 -0.0367914 0.445169 0.0598672 -0.0367312 0.44377 0.0600213 -0.0369031 0.445169 0.0600341 -0.0366243 0.4419 0.059762 -0.0389191 0.441669 0.0595118 -0.040265 0.44166 0.0596033 -0.040269 0.441929 0.0595373 -0.0416111 0.443706 0.0601334 -0.0367526 0.445169 0.060112 -0.0365275 0.442466 0.0600969 -0.0375821 0.44152 0.0598669 -0.0402805 0.441801 0.0598031 -0.0416756 0.443709 0.0598222 -0.0438106 0.442593 0.059749 -0.0428566 0.447872 -0.0600969 -0.0375821 0.44826 -0.0601222 -0.0377483 0.448699 -0.0600422 -0.0388229 0.448864 -0.0600782 -0.0387561 0.448278 -0.0599015 -0.0428034 0.448864 -0.0599446 -0.0418175 0.448696 -0.0599133 -0.0417465 0.448988 -0.0599777 -0.0402853 0.449169 -0.0600114 -0.0402868 0.446855 -0.059853 -0.0439138 0.44651 -0.0594441 -0.0435073 0.448409 -0.0595374 -0.0416111 0.447648 -0.0594814 -0.0427481 0.448817 -0.059867 -0.0402805 0.448704 -0.0596969 -0.0402731 0.448537 -0.0598031 -0.0416756 0.448433 -0.0596318 -0.0416252 0.447745 -0.0597491 -0.0428566 0.447666 -0.0595767 -0.04277 0.446519 -0.0595399 -0.0435342 0.445169 -0.0593372 -0.043765 0.446508 -0.0596732 -0.0370314 0.446919 -0.0596631 -0.0372341 0.447146 -0.0596559 -0.0373774 0.447672 -0.0598173 -0.0377698 0.448437 -0.0597621 -0.0389191 0.447644 -0.0596354 -0.0377901 0.4482 -0.0595992 -0.0385151 0.445169 -0.0598673 -0.0367312 0.445597 -0.0596852 -0.0367914 0.445169 -0.0599302 -0.0367016 0.446524 -0.0598543 -0.0370012 0.448261 -0.0595936 -0.0386262 0.448402 -0.0595787 -0.0389256 0.448669 -0.0595119 -0.040265 0.448677 -0.0596034 -0.040269 0.446632 -0.0601335 -0.0367526 0.446568 -0.0600214 -0.0369031 0.447752 -0.0599851 -0.0376967 0.448542 -0.0599309 -0.0388831 0.447867 -0.0598587 -0.0429841 0.446562 -0.059713 -0.0436447 0.446629 -0.0598222 -0.0438106 0.445169 -0.0596984 -0.0439192 0.446427 -0.0403393 0.0748945 0.445248 -0.0416703 0.0741861 0.447046 -0.0512312 0.0643241 0.444674 -0.0512202 0.0643429 0.444127 -0.0492122 0.067315 0.444127 -0.0448808 0.0719051 0.444127 -0.0425721 0.0736292 0.462425 -0.0412855 0.0672328 0.460604 -0.0461566 0.0645465 0.449049 -0.0411155 0.0744344 0.449149 -0.0403395 0.0748252 0.452358 -0.0508281 0.0643707 0.453149 -0.0503397 0.0648693 0.454208 -0.0495234 0.0656233 0.453454 -0.0497137 0.0656934 0.447428 -0.0512313 0.0643231 0.449597 -0.051949 0.0629615 0.450669 -0.0511029 0.0643184 0.451555 -0.0517663 0.0629635 0.452339 -0.051125 0.0638768 0.453488 -0.0462931 0.0698116 0.45426 -0.0479488 0.0676899 0.455833 -0.0494213 0.0647647 0.455372 -0.0506358 0.0630922 0.456402 -0.0492494 0.0645844 0.456846 -0.0499003 0.0631211 0.458098 -0.0491462 0.0631187 0.463267 -0.0443806 0.0629855 0.462449 -0.0441542 0.0644808 0.463145 -0.0431777 0.0645312 0.462965 -0.0434921 0.0644619 0.463749 -0.043734 0.0629845 0.462859 -0.040629 0.0671897 0.463183 -0.040843 0.0666009 0.463619 -0.0413007 0.0656192 0.46325 -0.0427583 0.0648038 0.46387 -0.0434884 0.0630703 0.46178 -0.0403524 0.0686815 0.458093 -0.0411293 0.0714937 0.458507 -0.040349 0.0716616 0.457829 -0.0403487 0.0721272 0.457741 -0.0404615 0.0721217 0.455062 -0.0403475 0.0735887 0.455022 -0.0403474 0.0736051 0.455698 -0.0411264 0.0728906 0.454647 -0.0415789 0.0730851 0.449404 -0.0405274 0.0747174 0.449436 -0.0411157 0.0744106 0.452028 -0.0411175 0.0740951 0.451041 -0.0403401 0.0746522 0.454211 -0.0403461 0.0739132 0.453507 -0.0423082 0.0730323 0.465009 -0.0435815 0.0635482 0.464705 -0.0443453 0.0632533 0.464669 -0.0444065 0.0699313 0.464612 -0.0444961 0.0632336 0.465047 -0.0424065 0.0644694 0.465055 -0.0433447 0.0636926 0.464371 -0.04099 0.0662797 0.464915 -0.041911 0.0715245 0.465013 -0.0422397 0.0646402 0.465024 -0.0422897 0.0711453 0.464179 -0.0407917 0.0729831 0.462186 -0.04 0.0690463 0.462939 -0.0400989 0.0683003 0.463247 -0.0402002 0.0679441 0.450862 -0.0530085 0.06321 0.448151 -0.0531436 0.0695598 0.447429 -0.0531466 0.0695658 0.458721 -0.0500975 0.0633858 0.457161 -0.0510225 0.0698839 0.456793 -0.0512149 0.0633844 0.456793 -0.051215 0.0698643 0.455824 -0.0516762 0.0633645 0.454018 -0.0523612 0.0696816 0.459562 -0.0495209 0.0699623 0.46451 -0.0446418 0.0699172 0.463638 -0.0457375 0.0632541 0.461337 -0.0480982 0.0633278 0.446427 -0.0531467 0.0632122 0.447143 -0.0531466 0.0632123 0.462186 -0.04 0.0751554 0.460989 -0.04 0.0760329 0.456467 -0.04 0.0735419 0.453016 -0.04 0.0794042 0.453206 -0.04 0.0747866 0.451882 -0.04 0.0750712 0.44982 -0.04 0.0798026 0.443527 -0.0502467 0.0730254 0.443527 -0.0449945 0.0725927 0.443527 -0.0469035 0.0708644 0.445143 -0.0402999 0.0797938 0.445299 -0.0402284 0.0753463 0.444294 -0.0409354 0.0750571 0.444453 -0.0407752 0.0796128 0.443939 -0.0414092 0.0793515 0.443527 -0.0429 0.0741316 0.445585 -0.0425812 0.0744677 0.445784 -0.0422703 0.074775 0.446346 -0.0420038 0.0750225 0.446064 -0.0420762 0.0790514 0.446113 -0.0420567 0.0749745 0.445527 -0.0449945 0.0725927 0.445527 -0.0467509 0.0761766 0.445527 -0.0469035 0.0708644 0.44743 -0.0511466 0.0720439 0.446699 -0.0511467 0.0646316 0.447011 -0.0511466 0.0646316 0.449905 -0.0510828 0.0720221 0.453027 -0.049871 0.066474 0.453027 -0.0473711 0.0751459 0.453027 -0.0429 0.0733496 0.452127 -0.042 0.0746152 0.449488 -0.042 0.0749367 0.452127 -0.042 0.0787316 0.448527 -0.042 0.0790527 0.446829 -0.042 0.0790868 0.446427 -0.042 0.079087 0.455027 -0.0483931 0.0736859 0.455027 -0.0457927 0.0758055 0.458523 -0.0478033 0.064891 0.458748 -0.0476363 0.0724946 0.459948 -0.0466567 0.0648564 0.459035 -0.0474153 0.072504 0.462909 -0.0434427 0.0647516 0.463064 -0.0431154 0.0649441 0.462187 -0.042 0.0684757 0.462625 -0.0421132 0.0674505 0.462796 -0.0422364 0.0669156 0.462875 -0.042318 0.0733218 0.462949 -0.0424181 0.0731917 0.463078 -0.0427571 0.0728527 0.462878 -0.0423221 0.0666134 0.463068 -0.0427044 0.0656057 0.463086 -0.0429861 0.0651079 0.462942 -0.0433962 0.0647548 0.463018 -0.043254 0.064819 0.462909 -0.0434427 0.0725438 0.459257 -0.042 0.0761728 0.455927 -0.042 0.0777516 0.456056 -0.0492838 0.0724079 0.455927 -0.0492931 0.0724569 0.456133 -0.0465592 0.0748114 0.456359 -0.0491827 0.072368 0.462632 -0.0421173 0.0736613 0.462931 -0.042932 0.0728737 0.463079 -0.0430381 0.0726631 0.463022 -0.0432434 0.0725761 0.457519 -0.0449857 0.0753252 0.459709 -0.042 0.0759002 0.460573 -0.042 0.0753348 0.461086 -0.0455748 0.0725422 0.462186 -0.042 0.0741114 0.455323 -0.0424751 0.0777296 0.455622 -0.0420533 0.0778357 0.456585 -0.042 0.0774956 0.446846 -0.0511467 0.0720468 0.446427 -0.0511467 0.0720469 0.44683 -0.0494177 0.073861 0.446001 -0.0510396 0.0721675 0.446825 -0.0468784 0.0760779 0.445527 -0.0502467 0.0730254 0.445583 -0.050559 0.0726944 0.445772 -0.0422828 0.0789532 0.445977 -0.0424502 0.0788717 0.445588 -0.0425728 0.0788109 0.445527 -0.0429 0.0786444 0.446827 -0.0449781 0.0774324 0.448465 -0.0446452 0.077614 0.448471 -0.0491105 0.074132 0.449639 -0.0509925 0.0721424 0.453027 -0.049871 0.072849 0.453027 -0.0446889 0.0770896 0.452933 -0.0502715 0.0724534 0.452373 -0.0507368 0.0720724 0.452864 -0.0423838 0.0784188 0.452891 -0.0470066 0.0754686 0.451512 -0.0446654 0.0773608 0.449862 -0.0421738 0.0788986 0.450013 -0.0468974 0.0759522 0.452413 -0.0420469 0.0786629 0.451294 -0.0490222 0.0739985 0.44706 -0.0471224 0.0758853 0.457818 -0.0297156 0.0748632 0.467513 -0.0333182 0.0643396 0.468003 -0.0305235 0.0643203 0.46786 -0.029685 0.0647242 0.467662 -0.0346041 0.0635173 0.467284 -0.0338353 0.0645295 0.467467 -0.0334786 0.0643576 0.466071 -0.0352537 0.0658908 0.463696 -0.0352568 0.0691377 0.459214 -0.0352687 0.073248 0.456618 -0.0341786 0.0749264 0.457659 -0.0330206 0.074625 0.458235 -0.0341955 0.0741087 0.458871 -0.0344675 0.0736705 0.458215 -0.029211 0.074687 0.457248 -0.0297975 0.075123 0.456895 -0.0303683 0.0752452 0.455653 -0.0352821 0.0751105 0.456863 -0.0352773 0.0745882 0.456634 -0.0338451 0.0749777 0.456869 -0.0332279 0.0749703 0.454009 -0.0352895 0.0756636 0.451151 -0.0353011 0.0762404 0.446823 -0.0345324 0.0765472 0.45004 -0.0345269 0.0764533 0.451207 -0.0345217 0.0763507 0.458393 -0.0290836 0.0745997 0.456972 -0.0292509 0.0752612 0.456419 -0.0292709 0.0754799 0.456134 -0.0279087 0.0756187 0.455452 -0.0280874 0.0758374 0.455449 -0.0288885 0.0758213 0.456908 -0.0265801 0.0753739 0.455718 -0.0215856 0.0759256 0.455473 -0.022386 0.0759716 0.452821 -0.0215953 0.0764936 0.446827 -0.0224 0.076735 0.451061 -0.0215986 0.0766567 0.451215 -0.0280985 0.0766283 0.457693 -0.0238754 0.0751637 0.457681 -0.0265768 0.0750492 0.457213 -0.0292426 0.075159 0.459124 -0.028877 0.0742027 0.461274 -0.0288718 0.0727344 0.468155 -0.0273071 0.0645281 0.46139 -0.0280683 0.0726942 0.463223 -0.0288685 0.0709936 0.465246 -0.0280621 0.0687775 0.466538 -0.0288652 0.0669284 0.466955 -0.0289265 0.0662928 0.466876 -0.0280606 0.066513 0.467731 -0.0277812 0.0651846 0.468309 -0.0269222 0.064316 0.468062 -0.0227043 0.0654252 0.468454 -0.0220016 0.0648718 0.467114 -0.0215559 0.0670732 0.467113 -0.0223532 0.0669656 0.465456 -0.0223541 0.0692094 0.463378 -0.0215587 0.0715485 0.463576 -0.0223564 0.0712795 0.463057 -0.0215593 0.071847 0.463006 -0.0223575 0.0718182 0.459148 -0.0223699 0.074551 0.444556 -0.0343739 0.0765645 0.445399 -0.0350748 0.0764786 0.44683 -0.03531 0.0764444 0.446427 -0.0345324 0.076547 0.446427 -0.0353101 0.0764443 0.444927 -0.0330664 0.0766689 0.444127 -0.0330664 0.0766689 0.444127 -0.0294575 0.076735 0.445013 -0.0298991 0.0767349 0.44526 -0.0294575 0.076735 0.445128 -0.02735 0.076735 0.445277 -0.0219082 0.076735 0.444435 -0.02275 0.076735 0.445128 -0.02315 0.076735 0.444927 -0.0266 0.076735 0.446427 -0.0289 0.076735 0.44578 -0.0290466 0.076735 0.470504 -0.024052 0.0697645 0.470495 -0.0241702 0.0631597 0.470298 -0.0228174 0.0636195 0.470299 -0.0228199 0.0702305 0.470476 -0.0234749 0.0698868 0.470022 -0.022293 0.064099 0.469924 -0.022155 0.0708349 0.469727 -0.0219204 0.064571 0.469693 -0.0218839 0.0646247 0.468656 -0.0211957 0.0661038 0.468985 -0.0213478 0.0721379 0.46869 -0.0212093 0.072509 0.443527 -0.0239 0.077335 0.443527 -0.0294575 0.077335 0.443527 -0.0312794 0.077327 0.444977 -0.0213886 0.077335 0.444977 -0.0213886 0.081235 0.443915 -0.02245 0.081235 0.443582 -0.0336652 0.0772395 0.443798 -0.0343248 0.0810899 0.444367 -0.0351409 0.0771294 0.446427 -0.036 0.0770375 0.44593 -0.0359569 0.0770427 0.445417 -0.0358185 0.0770588 0.460605 -0.021 0.0789289 0.459839 -0.021 0.0749053 0.461409 -0.021 0.0739295 0.46399 -0.021 0.0717912 0.46703 -0.021 0.0743407 0.465871 -0.021 0.0697411 0.46761 -0.021 0.0737433 0.446427 -0.021 0.077335 0.446427 -0.021 0.081235 0.446827 -0.021 0.077335 0.450367 -0.021 0.0811948 0.453685 -0.021 0.0809238 0.45516 -0.021 0.0766854 0.456843 -0.021 0.0802984 0.470495 -0.0241702 0.0697599 0.470284 -0.0266325 0.0631386 0.470073 -0.0290948 0.0631526 0.469813 -0.0314823 0.0631608 0.469391 -0.0337368 0.0697771 0.470066 -0.0292022 0.0631529 0.47007 -0.0291366 0.0631527 0.455542 -0.036 0.0757817 0.457192 -0.036 0.0750818 0.464295 -0.036 0.0749123 0.46656 -0.036 0.0726289 0.464913 -0.036 0.0685517 0.457548 -0.036 0.0791407 0.449683 -0.036 0.0769592 0.446828 -0.036 0.0808912 0.456527 -0.02525 0.0802791 0.445527 -0.0239 0.081235 0.445647 -0.02345 0.081235 0.445977 -0.0231206 0.081235 0.445527 -0.0266 0.077335 0.446427 -0.023 0.077335 0.446827 -0.023 0.077335 0.451283 -0.023 0.0811481 0.455627 -0.023 0.0765514 0.452282 -0.023 0.081071 0.455627 -0.023 0.0805522 0.446427 -0.0275 0.081235 0.451297 -0.0275 0.0811363 0.451264 -0.0275 0.0772263 0.452415 -0.0275 0.0810352 0.456527 -0.0304 0.0757978 0.456527 -0.0317527 0.0756946 0.445527 -0.0317505 0.0773187 0.445527 -0.0331 0.0811734 0.446081 -0.0339311 0.077156 0.446129 -0.0339495 0.0811206 0.446013 -0.0338993 0.0771617 0.445787 -0.0337333 0.0771894 0.445688 -0.0336147 0.0772073 0.445787 -0.0337334 0.0811361 0.44558 -0.0334055 0.0772351 0.445665 -0.0335788 0.0811463 0.445534 -0.0332149 0.0772566 0.445549 -0.0332994 0.0811629 0.445527 -0.0331 0.077268 0.455627 -0.034 0.0759061 0.453273 -0.034 0.0806853 0.451277 -0.034 0.0769415 0.450112 -0.034 0.081035 0.446821 -0.034 0.0811168 0.446803 -0.034 0.0771432 0.446827 -0.0294636 0.0812349 0.446827 -0.0295 0.077335 0.451273 -0.0295 0.0772235 0.468373 -0.025505 0.0723725 0.468273 -0.0266769 0.0645762 0.468416 -0.0235044 0.0650095 0.467609 -0.023 0.0672995 0.46791 -0.0230519 0.0665221 0.468298 -0.0233217 0.0727273 0.468442 -0.0235626 0.0725295 0.468311 -0.0233379 0.0653566 0.468503 -0.023989 0.0646196 0.459427 -0.023 0.0750815 0.461841 -0.023 0.0735575 0.46191 -0.023 0.0781361 0.465229 -0.023 0.0758058 0.458527 -0.0266 0.0795747 0.458527 -0.0266 0.0755962 0.458527 -0.0239 0.0757155 0.461197 -0.0275 0.0782727 0.459427 -0.0275 0.0747579 0.462599 -0.0275 0.0774166 0.467376 -0.0275 0.0668419 0.464998 -0.0275 0.0756002 0.461762 -0.0275 0.0731637 0.467717 -0.0319097 0.0723951 0.463576 -0.0295 0.0766102 0.463554 -0.0295 0.0715101 0.467034 -0.0295 0.0672649 0.458527 -0.0331 0.0792116 0.465267 -0.034 0.0745516 0.462745 -0.034 0.0766595 0.46212 -0.034 0.0770985 0.446427 -0.0295 0.081235 0.446427 -0.034 0.0811167 0.445866 -0.0338037 0.0811312 0.44558 -0.0334054 0.0811568 0.446818 -0.031791 0.0812187 0.446229 -0.029522 0.081235 0.44595 -0.0296369 0.081235 0.445527 -0.0304 0.0812339 0.446113 -0.0295563 0.081235 0.456407 -0.0299506 0.08021 0.456512 -0.0302401 0.0801688 0.455934 -0.0295541 0.0803537 0.456081 -0.029955 0.0803036 0.455627 -0.034 0.0801379 0.455879 -0.0339641 0.0800684 0.456346 -0.0336407 0.0799634 0.456266 -0.0337337 0.0799777 0.45614 -0.0338391 0.0800041 0.452382 -0.0295 0.0810304 0.453426 -0.0295 0.0808889 0.451802 -0.0315723 0.0810529 0.453464 -0.0295 0.0808829 0.456077 -0.0335416 0.0800596 0.456481 -0.0333849 0.0799502 0.448441 -0.0295 0.0812309 0.463786 -0.0275 0.0765773 0.464458 -0.023 0.0764282 0.468497 -0.0237635 0.0724399 0.468503 -0.023989 0.0724052 0.46761 -0.023 0.0735332 0.468008 -0.0230936 0.0730845 0.458794 -0.0232601 0.0795999 0.458527 -0.02525 0.0796245 0.458625 -0.0270085 0.0795214 0.458979 -0.0270491 0.0793752 0.458534 -0.0267145 0.0795677 0.462717 -0.0252205 0.077492 0.46655 -0.0252242 0.0743814 0.467376 -0.0275 0.0732879 0.468136 -0.0270824 0.0724693 0.461646 -0.0339238 0.0774255 0.459096 -0.0339371 0.0788379 0.458982 -0.033557 0.0789476 0.458527 -0.0304 0.0794448 0.45857 -0.0301233 0.0794402 0.458695 -0.029876 0.079399 0.458794 -0.02976 0.0793619 0.459427 -0.034 0.0786683 0.463467 -0.0321957 0.0764254 0.466561 -0.034 0.0732365 0.467925 -0.0302762 0.0724015 0.467732 -0.0298317 0.072677 0.467439 -0.0332985 0.0724225 0.460973 -0.0295 0.0783063 0.464632 -0.0295 0.0757714 0.465298 -0.0305143 0.0751034 0.467034 -0.0295 0.0734837 0.446827 -0.0252435 0.081235 0.446427 -0.023 0.081235 0.449796 -0.025261 0.081209 0.446827 -0.0275 0.081235 0.456527 -0.0266 0.0802468 0.454617 -0.0252493 0.0807237 0.45626 -0.0272397 0.0803074 0.456131 -0.0273455 0.0803403 0.455627 -0.0275 0.0804677 0.456079 -0.0234508 0.0804374 0.456201 -0.0232071 0.0804127 0.446827 -0.023 0.081235 0.451213 -0.0033997 0.076678 0.446827 -0.00340004 0.076735 0.456959 -0.00778154 0.0758875 0.456976 -0.00489406 0.0759205 0.457997 -0.00405713 0.0756318 0.455711 -0.00340972 0.0762136 0.456539 -0.00865706 0.0759822 0.45652 -0.0151543 0.0758601 0.456697 -0.0149355 0.075815 0.456943 -0.0142752 0.0757591 0.457728 -0.0140834 0.0755094 0.456963 -0.0113878 0.0758199 0.456343 -0.0101597 0.0760058 0.455513 -0.00909301 0.0762014 0.451213 -0.00989916 0.0766713 0.446827 -0.00910004 0.076735 0.457881 -0.0147575 0.0754342 0.455496 -0.0155896 0.0761069 0.446827 -0.0156 0.076735 0.458099 -0.0163805 0.0752983 0.458983 -0.0163777 0.0749211 0.458942 -0.0155597 0.0749728 0.459171 -0.0155778 0.0748664 0.461744 -0.0155716 0.0733501 0.461619 -0.0163709 0.0733918 0.463608 -0.0155694 0.0718173 0.466045 -0.0155691 0.0691536 0.468631 -0.0152823 0.0653654 0.469055 -0.0147958 0.0646751 0.468791 -0.0102029 0.0655193 0.469297 -0.00829086 0.0647554 0.469154 -0.0106296 0.0648546 0.469438 -0.00790215 0.064521 0.46932 -0.0110731 0.0645212 0.46935 -0.0114342 0.0644385 0.469201 -0.0144078 0.0644495 0.469472 -0.00762307 0.0644753 0.469529 -0.00491436 0.0644942 0.470312 -0.00470881 0.0629887 0.468052 -0.00339233 0.0670496 0.468052 -0.00259409 0.0670664 0.464217 -0.00339137 0.071835 0.45909 -0.00259512 0.0752485 0.456546 -0.0038301 0.0760356 0.459197 -0.00339365 0.0751966 0.468477 -0.0100094 0.0660603 0.467994 -0.0090801 0.0668942 0.466208 -0.009079 0.0694089 0.446827 -0.00260004 0.076735 0.446427 -0.00260004 0.076735 0.445677 -0.003601 0.076735 0.444127 -0.00490004 0.076735 0.445128 -0.00415004 0.076735 0.444927 -0.00490004 0.076735 0.446427 -0.00910004 0.076735 0.445677 -0.00889908 0.076735 0.445677 -0.010101 0.076735 0.445128 -0.01065 0.076735 0.446827 -0.0164 0.076735 0.446427 -0.0156 0.076735 0.446427 -0.0164 0.076735 0.444927 -0.0141 0.076735 0.444927 -0.0114 0.076735 0.444927 -0.00760004 0.076735 0.470825 -0.00309383 0.0709892 0.470994 -0.00332901 0.0639993 0.471211 -0.00373198 0.0704221 0.471455 -0.00480878 0.0632395 0.470275 -0.00256444 0.0650841 0.469561 -0.00217934 0.0660889 0.468557 -0.00200004 0.0673903 0.468557 -0.00200004 0.0738413 0.469641 -0.00221062 0.0725685 0.443527 -0.00490004 0.077335 0.446427 -0.00200004 0.081235 0.444977 -0.00238857 0.077335 0.443915 -0.00345004 0.077335 0.443915 -0.00345004 0.081235 0.444977 -0.0166115 0.081235 0.446427 -0.017 0.081235 0.446827 -0.00200004 0.077335 0.466713 -0.00200004 0.0699799 0.454458 -0.00200004 0.0809508 0.457176 -0.00200004 0.0805155 0.460002 -0.00200004 0.0797201 0.463659 -0.00200004 0.0779702 0.471282 -0.0113185 0.0699421 0.471456 -0.00494772 0.0632346 0.461966 -0.017 0.0738806 0.462269 -0.017 0.0782692 0.456233 -0.017 0.0765305 0.456506 -0.017 0.080467 0.446827 -0.017 0.081235 0.454924 -0.017 0.080779 0.453119 -0.017 0.0771006 0.462464 -0.017 0.0735141 0.466042 -0.017 0.0755901 0.468263 -0.017 0.067002 0.456527 -0.00490004 0.0765012 0.456527 -0.00760004 0.0806056 0.445527 -0.00490004 0.081235 0.445647 -0.00445004 0.081235 0.445977 -0.00412062 0.081235 0.445527 -0.00490004 0.077335 0.445527 -0.00760004 0.081235 0.446427 -0.00400004 0.081235 0.446427 -0.00400004 0.077335 0.446827 -0.00400004 0.077335 0.446827 -0.00400004 0.081235 0.451252 -0.00400004 0.0811795 0.455627 -0.00400004 0.0807895 0.451256 -0.00850004 0.0811754 0.456527 -0.0114 0.0763969 0.456527 -0.0141 0.0763348 0.445527 -0.0114 0.081235 0.445527 -0.0141 0.077335 0.445647 -0.01455 0.081235 0.454829 -0.015 0.0808168 0.451245 -0.015 0.0772603 0.446827 -0.015 0.081235 0.451227 -0.015 0.0811673 0.446427 -0.0105 0.077335 0.446827 -0.0105 0.077335 0.451241 -0.0105 0.0772706 0.463148 -0.00850004 0.0781322 0.465585 -0.00850004 0.0764555 0.462163 -0.00850004 0.0741147 0.466678 -0.00850004 0.0697812 0.466219 -0.00850004 0.0759309 0.462701 -0.00850004 0.0783868 0.469399 -0.0076234 0.0647617 0.469399 -0.0076234 0.0726986 0.468557 -0.00400004 0.0673734 0.468701 -0.00401168 0.0669918 0.468885 -0.00406197 0.0734336 0.469196 -0.00426677 0.0730657 0.468977 -0.00410431 0.0662317 0.469361 -0.0044959 0.0728627 0.469324 -0.00443066 0.0652073 0.469456 -0.00491471 0.0727343 0.469374 -0.00452358 0.065053 0.469441 -0.00473647 0.064836 0.462194 -0.00400004 0.0742573 0.468557 -0.00400004 0.0738039 0.466291 -0.00400004 0.0760171 0.465688 -0.00400004 0.0765154 0.462761 -0.00400004 0.0784639 0.458527 -0.00643357 0.0801435 0.466576 -0.0105 0.0698624 0.459427 -0.0105 0.0756133 0.459954 -0.0105 0.0795919 0.463468 -0.0105 0.0730835 0.466085 -0.0105 0.0759516 0.458527 -0.0127501 0.08002 0.458527 -0.0114 0.0761494 0.466515 -0.015 0.0695252 0.462093 -0.015 0.0738371 0.465069 -0.015 0.0765227 0.462139 -0.015 0.0784356 0.459427 -0.015 0.0754088 0.446827 -0.00850004 0.081235 0.445977 -0.00837946 0.081235 0.451786 -0.00400004 0.0811566 0.456508 -0.0047157 0.0806348 0.456079 -0.00445005 0.0807136 0.455928 -0.00405195 0.0807412 0.456195 -0.0042019 0.080695 0.456527 -0.00625005 0.0806189 0.451866 -0.00850004 0.0811467 0.455627 -0.00850004 0.0807578 0.458917 -0.0106581 0.0799475 0.458527 -0.0141 0.0799861 0.458638 -0.0145326 0.0799396 0.462557 -0.015 0.0782038 0.459427 -0.015 0.079655 0.45898 -0.01455 0.0798262 0.458837 -0.01478 0.0798675 0.465557 -0.015 0.076134 0.468931 -0.0147037 0.0728093 0.466596 -0.0127726 0.0753734 0.467931 -0.015 0.0739079 0.469092 -0.0128279 0.072757 0.468263 -0.015 0.0735481 0.468694 -0.0148903 0.0730712 0.469141 -0.0143013 0.0725901 0.469222 -0.0127881 0.0726038 0.46907 -0.0144986 0.0726594 0.468377 -0.0105 0.0737262 0.469203 -0.0110433 0.0727444 0.46262 -0.0105 0.0783618 0.46276 -0.012721 0.078192 0.46299 -0.0105 0.0781517 0.465445 -0.0105 0.0764762 0.469432 -0.00469071 0.072771 0.469012 -0.00445699 0.0732762 0.469444 -0.00559196 0.0727264 0.458711 -0.00435477 0.0801162 0.458922 -0.00415512 0.0800561 0.460118 -0.00400004 0.0796598 0.459117 -0.00844511 0.079931 0.458842 -0.00828403 0.0800204 0.458642 -0.00804066 0.0800848 0.46658 -0.00627058 0.0757024 0.462773 -0.00624004 0.0784115 0.463271 -0.00400004 0.0781759 0.45898 -0.00805005 0.0799822 0.460045 -0.00850004 0.0796075 0.458527 -0.00760004 0.0801258 0.468954 -0.00806215 0.0732057 0.469287 -0.0080348 0.0728139 0.469119 -0.00825286 0.0730039 0.468499 -0.00850004 0.0737 0.446427 -0.015 0.081235 0.445977 -0.0148795 0.081235 0.445527 -0.0141 0.081235 0.446827 -0.0105 0.081235 0.446427 -0.0105 0.081235 0.445977 -0.0106206 0.081235 0.455627 -0.0105 0.0807377 0.456527 -0.0114 0.0805571 0.455929 -0.0105522 0.0806843 0.456079 -0.0109501 0.0806517 0.456397 -0.0109351 0.0805901 0.456478 -0.0143924 0.08052 0.456527 -0.0127501 0.0805364 0.456263 -0.0147366 0.0805602 0.451258 -0.0105 0.0811728 0.455627 -0.015 0.0806817 0.451914 -0.0105 0.0811401 0.455844 -0.0149733 0.0806408 0.45612 -0.0148529 0.0805879 0.451213 0.0155987 0.0766612 0.446827 0.0156 0.076735 0.456976 0.00489398 0.0759205 0.456345 0.00882323 0.0760265 0.45618 0.0100584 0.0760462 0.456955 0.0140858 0.0757601 0.457736 0.0142453 0.0755018 0.456792 0.0147728 0.0757915 0.456333 0.0153152 0.0759075 0.455688 0.015576 0.0760636 0.454893 0.016391 0.07622 0.456705 0.010533 0.0759077 0.456806 0.00828239 0.07592 0.457745 0.00758957 0.0756609 0.457754 0.00776068 0.0756548 0.456716 0.00403764 0.0759937 0.457909 0.00420956 0.0756582 0.455511 0.00989243 0.0761918 0.453153 0.00259904 0.0765581 0.451213 0.00339962 0.076678 0.455521 0.00339704 0.0762486 0.456245 0.00259716 0.0761103 0.459197 0.00339357 0.0751966 0.464244 0.00339129 0.071809 0.46634 0.00259352 0.0694845 0.468052 0.002594 0.0670663 0.468052 0.00339225 0.067049 0.469723 0.00334011 0.064179 0.468955 0.00370565 0.0655572 0.469373 0.00422004 0.0648029 0.469504 0.00461816 0.0645497 0.469331 0.011134 0.0644962 0.469472 0.00762298 0.0644753 0.469237 0.0141412 0.0644089 0.467759 0.0163688 0.0666772 0.467759 0.01557 0.0667517 0.464029 0.0155691 0.0714139 0.463608 0.0155693 0.0718173 0.456519 0.0151549 0.0758602 0.458465 0.0153889 0.0751857 0.456067 0.0163874 0.075954 0.459171 0.0155777 0.0748664 0.461744 0.0155716 0.07335 0.461566 0.0163709 0.0734296 0.46942 0.00797859 0.0645503 0.468791 0.0102028 0.0655195 0.468544 0.00897281 0.0660165 0.467994 0.00908002 0.0668942 0.466211 0.00907892 0.0694045 0.464077 0.00987708 0.0717283 0.458492 0.00890077 0.0753732 0.458961 0.00990234 0.07516 0.461826 0.00908006 0.0736183 0.445041 0.0108259 0.076735 0.445677 0.008899 0.076735 0.445128 0.00834996 0.076735 0.446427 0.0164 0.076735 0.445677 0.015399 0.076735 0.445128 0.01485 0.076735 0.444927 0.0141 0.076735 0.444127 0.0141 0.076735 0.445366 0.0103393 0.076735 0.445853 0.0100141 0.076735 0.446427 0.00989996 0.076735 0.446827 0.00339996 0.076735 0.446827 0.00259996 0.076735 0.446427 0.00339996 0.076735 0.445547 0.00277504 0.076735 0.4448 0.00327361 0.076735 0.445128 0.00414996 0.076735 0.444302 0.00401979 0.076735 0.444927 0.00489996 0.076735 0.444127 0.00489996 0.076735 0.469543 0.00217283 0.0661128 0.468557 0.00199996 0.0673903 0.469014 0.00203629 0.0668127 0.469946 0.00235464 0.072182 0.470761 0.00301572 0.0710804 0.470275 0.00256435 0.0650841 0.471456 0.00494775 0.0632346 0.470653 0.00289592 0.0645251 0.471036 0.00339556 0.0639337 0.471408 0.00437466 0.0701116 0.471381 0.00424453 0.0633717 0.471447 0.00467076 0.0632549 0.471135 0.0145032 0.0632041 0.471084 0.0147745 0.0699604 0.470213 0.0162462 0.0644516 0.470465 0.0159874 0.070739 0.469677 0.0166317 0.0717332 0.469342 0.0167917 0.0721421 0.443527 0.00489996 0.077335 0.443527 0.0141 0.077335 0.443915 0.01555 0.077335 0.445317 0.00222071 0.077335 0.445317 0.00222071 0.081235 0.446427 0.00199996 0.081235 0.446427 0.017 0.081235 0.450533 0.017 0.0811931 0.459176 0.017 0.0754923 0.461911 0.017 0.0739197 0.462673 0.017 0.0780369 0.466327 0.017 0.0753365 0.466437 0.017 0.0695558 0.471393 0.00786424 0.0699911 0.459408 0.00199996 0.0757666 0.464057 0.00199996 0.0777196 0.462714 0.00199996 0.0739034 0.46468 0.00199996 0.0722364 0.446827 0.00199996 0.081235 0.446827 0.00199996 0.077335 0.453745 0.00199996 0.0771042 0.457199 0.00199996 0.0805105 0.456371 0.00199996 0.0766969 0.456527 0.0141 0.0763348 0.456527 0.0114 0.0805571 0.445527 0.0141 0.077335 0.445977 0.0148794 0.081235 0.446427 0.015 0.081235 0.446827 0.015 0.081235 0.451265 0.015 0.0811655 0.452037 0.015 0.0811208 0.455627 0.015 0.0806817 0.446427 0.0105 0.081235 0.45124 0.0105 0.0772706 0.446827 0.0105 0.081235 0.451258 0.0105 0.0811728 0.456527 0.00759996 0.0764666 0.456527 0.00489996 0.0765012 0.445527 0.00489996 0.077335 0.445527 0.00489996 0.081235 0.445977 0.00412054 0.081235 0.445647 0.00444996 0.077335 0.455627 0.00399996 0.0807895 0.455627 0.00399996 0.0768392 0.446827 0.00399996 0.077335 0.451238 0.00399996 0.0772775 0.455074 0.00399996 0.0808688 0.446827 0.00849996 0.081235 0.455627 0.00849996 0.0807578 0.46262 0.0105 0.0783619 0.46299 0.0105 0.0781518 0.465445 0.0105 0.0764763 0.466085 0.0105 0.0759516 0.466571 0.0105 0.0698679 0.469163 0.0141408 0.0646981 0.469222 0.0127876 0.0647123 0.46856 0.0149495 0.0732196 0.468395 0.0149902 0.0667349 0.468531 0.0149591 0.0663758 0.468803 0.0148201 0.0656452 0.469043 0.0145502 0.0726885 0.469125 0.0143604 0.0726045 0.4691 0.0144316 0.0648408 0.463484 0.015 0.0727354 0.468262 0.015 0.0735488 0.465254 0.015 0.076378 0.468557 0.00399996 0.0738041 0.46934 0.00445702 0.0651593 0.469402 0.00459162 0.0649643 0.469442 0.00473747 0.0727575 0.469448 0.00477782 0.0648131 0.469416 0.00694633 0.0727086 0.466681 0.00849996 0.0697767 0.468499 0.00849996 0.0737 0.468499 0.00849996 0.067218 0.466219 0.00849996 0.0759309 0.462167 0.00849996 0.0741118 0.462701 0.00849996 0.0783868 0.468557 0.00399996 0.0673728 0.467673 0.00399996 0.074735 0.466776 0.00399996 0.0698846 0.465312 0.00399996 0.0768076 0.465094 0.00399996 0.0718082 0.464647 0.00399996 0.0772936 0.445527 0.0141 0.081235 0.445647 0.01455 0.081235 0.44579 0.0107636 0.081235 0.445527 0.0114 0.081235 0.456508 0.0142821 0.0805153 0.456197 0.0147965 0.080573 0.456078 0.0145501 0.0806011 0.455837 0.0105248 0.080701 0.451914 0.0105 0.0811401 0.456527 0.0141 0.0805143 0.455929 0.0149477 0.0806247 0.456477 0.0111059 0.0805715 0.456336 0.0108453 0.0806037 0.45626 0.0107604 0.0806196 0.456527 0.01275 0.0805364 0.456115 0.010644 0.0806488 0.458527 0.00759996 0.0801258 0.458711 0.00814569 0.0800624 0.459194 0.00846935 0.0799057 0.459427 0.00849996 0.0798278 0.458527 0.00606644 0.0801485 0.458527 0.00489996 0.0801628 0.458542 0.00473627 0.0801604 0.458646 0.00445259 0.0801339 0.459427 0.00399996 0.0798995 0.45898 0.00445003 0.0800356 0.46658 0.00627051 0.0757023 0.462147 0.00399996 0.0787853 0.469456 0.00491516 0.0727343 0.469403 0.00459578 0.072808 0.468992 0.00411242 0.0733084 0.469243 0.00431815 0.0730083 0.469378 0.00453321 0.0728402 0.460045 0.00849996 0.0796075 0.462773 0.00623997 0.0784114 0.463148 0.00849996 0.0781322 0.465585 0.00849996 0.0764555 0.469163 0.0141408 0.0725758 0.46887 0.0147643 0.0728757 0.466597 0.0127734 0.0753728 0.465948 0.015 0.0758067 0.458574 0.0143884 0.0799636 0.458527 0.0141 0.0799861 0.458794 0.0147398 0.079883 0.459824 0.015 0.079505 0.459427 0.015 0.079655 0.459427 0.0105 0.0797821 0.458645 0.0109546 0.0800258 0.458979 0.01095 0.0799209 0.458542 0.0112375 0.0800508 0.459954 0.0105 0.0795919 0.458527 0.01275 0.08002 0.458844 0.0107141 0.0799695 0.46251 0.015 0.0782305 0.462761 0.0127218 0.0781916 0.469027 0.0107774 0.0729707 0.468377 0.0105 0.0737262 0.469091 0.0128287 0.0727577 0.469222 0.0127876 0.0726038 0.469276 0.0114342 0.072631 0.446427 0.00399996 0.081235 0.445977 0.00837938 0.081235 0.445647 0.00444996 0.081235 0.451227 0.00399996 0.0811805 0.446827 0.00399996 0.081235 0.451256 0.00849996 0.0811754 0.451866 0.00849996 0.0811467 0.456396 0.00806676 0.0806259 0.456527 0.00759996 0.0806056 0.456079 0.00805012 0.0806848 0.456477 0.00460547 0.0806413 0.456527 0.00624997 0.0806189 0.469121 0.0227902 0.0635473 0.46858 0.0239936 0.0643261 0.468867 0.0291189 0.0629718 0.466955 0.0289264 0.0662925 0.459124 0.0288769 0.0742027 0.463444 0.0280643 0.0708339 0.463223 0.0288684 0.0709936 0.466538 0.0288651 0.0669285 0.457213 0.0292435 0.0751586 0.457681 0.0265767 0.0750492 0.457687 0.025226 0.0751057 0.457649 0.0215773 0.0752806 0.457844 0.0232132 0.0751289 0.455473 0.0223859 0.0759716 0.456908 0.0236892 0.0754812 0.456466 0.0276574 0.0755068 0.455968 0.0289865 0.0756489 0.456972 0.0292517 0.075261 0.456913 0.0252294 0.0754214 0.446827 0.0289 0.076735 0.455755 0.0215853 0.0759154 0.45454 0.0215899 0.0762079 0.451061 0.0215985 0.0766567 0.451213 0.0223983 0.0766449 0.446827 0.0216 0.076735 0.458522 0.0215736 0.074903 0.458878 0.0223971 0.0746884 0.461079 0.0215641 0.0734292 0.459148 0.0223699 0.074551 0.461483 0.0223614 0.0730775 0.463057 0.0215592 0.071847 0.463575 0.0223564 0.0712799 0.465404 0.022354 0.0692723 0.465455 0.022354 0.0692101 0.468049 0.0217608 0.0655889 0.453414 0.0352919 0.0758227 0.457247 0.0297974 0.0751231 0.456419 0.029271 0.0754798 0.457669 0.0303653 0.0748989 0.458215 0.0292108 0.074687 0.456884 0.0330239 0.0749928 0.456734 0.0336706 0.0749622 0.457659 0.0330205 0.074625 0.457817 0.0336932 0.0744335 0.456618 0.0341784 0.0749265 0.458324 0.0342574 0.0740451 0.456192 0.0352797 0.0748907 0.456312 0.0341918 0.0750562 0.458694 0.0352705 0.0735861 0.461145 0.034479 0.0719885 0.463106 0.035258 0.0698171 0.462968 0.0344738 0.0702346 0.466071 0.0344678 0.0662355 0.467994 0.0300953 0.0644221 0.468005 0.0305023 0.0643205 0.467388 0.0336633 0.0644217 0.467126 0.0349935 0.0642809 0.466854 0.0342437 0.0650851 0.446827 0.0224 0.076735 0.446427 0.0224 0.076735 0.445128 0.02315 0.076735 0.444435 0.02275 0.076735 0.444127 0.0239 0.076735 0.445128 0.02735 0.076735 0.445677 0.027899 0.076735 0.446427 0.0281 0.076735 0.446427 0.0289 0.076735 0.44526 0.0294574 0.076735 0.44683 0.03531 0.0764444 0.446823 0.0345323 0.0765472 0.446427 0.03531 0.0764443 0.446427 0.0345323 0.076547 0.445067 0.0348774 0.0765051 0.445719 0.0343597 0.076566 0.445366 0.0341039 0.0765916 0.444127 0.0330663 0.0766689 0.444939 0.0332499 0.076658 0.469935 0.0221689 0.0708188 0.469005 0.0213584 0.0721129 0.467609 0.021 0.067409 0.467812 0.0210071 0.0735258 0.468318 0.021088 0.0729552 0.468515 0.0211453 0.0662895 0.469735 0.0219281 0.0711166 0.468934 0.0213204 0.0657279 0.470158 0.0225181 0.0638698 0.470345 0.0229405 0.0701497 0.470385 0.0230641 0.0634546 0.470491 0.0235874 0.0698498 0.46887 0.0348547 0.0701399 0.46907 0.0345543 0.0699654 0.468863 0.0348643 0.0635226 0.469321 0.0339912 0.0697971 0.46939 0.0337368 0.0697776 0.46791 0.0356669 0.064572 0.468618 0.0351443 0.0703821 0.467728 0.0357549 0.0647871 0.467953 0.0356442 0.0710785 0.467596 0.035809 0.0714692 0.46656 0.036 0.0662058 0.46656 0.036 0.0726291 0.443527 0.0294574 0.077335 0.443527 0.0294574 0.081235 0.443527 0.0312792 0.0773271 0.443527 0.0331 0.0811734 0.444816 0.0355112 0.0770926 0.444628 0.0353744 0.0809782 0.445423 0.0358207 0.0809177 0.445259 0.0357544 0.0770661 0.445473 0.0358388 0.0809151 0.443572 0.0336076 0.0772427 0.443978 0.0346538 0.0810593 0.443915 0.02245 0.077335 0.444977 0.0213885 0.077335 0.444977 0.0213885 0.081235 0.460795 0.036 0.0728129 0.462914 0.036 0.0708789 0.446427 0.036 0.0808911 0.446828 0.036 0.0808912 0.456931 0.036 0.0793798 0.45872 0.036 0.0742568 0.459799 0.036 0.0780833 0.466167 0.036 0.0730637 0.46939 0.0337368 0.0631654 0.470054 0.0293523 0.069722 0.470073 0.0290976 0.0631527 0.470284 0.0266339 0.0631386 0.457195 0.021 0.0760919 0.458566 0.021 0.0797669 0.446427 0.021 0.081235 0.449918 0.021 0.0812085 0.451165 0.021 0.0811594 0.461413 0.021 0.078526 0.46285 0.021 0.0776988 0.467609 0.021 0.0737435 0.465553 0.021 0.0701202 0.456527 0.0304 0.0757978 0.445544 0.0332763 0.0772501 0.445582 0.0334116 0.0772344 0.445595 0.0334442 0.0811545 0.445631 0.0335207 0.0772203 0.44579 0.0337359 0.0811359 0.446315 0.033993 0.0771445 0.445921 0.0338442 0.0771712 0.445527 0.0331 0.0811734 0.450265 0.034 0.0810268 0.451283 0.034 0.0769408 0.446821 0.034 0.0811168 0.446823 0.034 0.0771433 0.446625 0.034 0.0771432 0.446427 0.0295 0.081235 0.45343 0.0295 0.0808883 0.446828 0.0294787 0.0812349 0.446827 0.0295 0.077335 0.452381 0.0295 0.0810305 0.445527 0.0266 0.081235 0.445977 0.0231205 0.081235 0.445647 0.02345 0.081235 0.445647 0.02345 0.077335 0.445527 0.0239 0.077335 0.455627 0.023 0.0805522 0.455627 0.023 0.0765514 0.446427 0.023 0.081235 0.446827 0.0275 0.077335 0.455627 0.0275 0.0764111 0.455627 0.0275 0.0804677 0.467034 0.0295 0.0734838 0.463647 0.0295 0.0714163 0.463576 0.0295 0.0766103 0.467439 0.0332973 0.0724229 0.467439 0.0332973 0.0646331 0.466918 0.033926 0.0656704 0.467242 0.0336884 0.0725544 0.467361 0.033513 0.0724613 0.46417 0.034 0.0755381 0.46656 0.034 0.0732375 0.463371 0.034 0.0706633 0.46656 0.034 0.0665563 0.461527 0.034 0.0724349 0.458527 0.0331 0.0792116 0.459427 0.023 0.0750815 0.463984 0.023 0.0717175 0.465245 0.023 0.0757926 0.461841 0.023 0.0735577 0.462654 0.023 0.0776889 0.462154 0.023 0.0779936 0.468503 0.0239889 0.0724052 0.468499 0.0237722 0.0724373 0.468311 0.0233377 0.0653568 0.46828 0.0233009 0.0654544 0.467609 0.023 0.0673008 0.46804 0.0231101 0.0730468 0.468403 0.0251609 0.0723795 0.459427 0.0275 0.0747579 0.462601 0.0275 0.0774154 0.464998 0.0275 0.0756002 0.467376 0.0275 0.0732879 0.465726 0.0275 0.0691363 0.458527 0.0239 0.0757155 0.445549 0.0302024 0.0812344 0.446129 0.0295507 0.081235 0.445865 0.0296972 0.081235 0.445977 0.029953 0.0812348 0.445787 0.0297666 0.081235 0.446817 0.0318108 0.0812178 0.445527 0.0304 0.0812339 0.446081 0.033931 0.0811219 0.446427 0.034 0.0811167 0.448439 0.0295 0.0812309 0.449622 0.034 0.0810573 0.451805 0.0315728 0.0810526 0.455627 0.034 0.0801379 0.455929 0.0339475 0.0800552 0.456201 0.0337933 0.0799909 0.456507 0.0332871 0.0799526 0.455627 0.0295 0.0804357 0.455845 0.0295268 0.0803782 0.456123 0.0296494 0.0802994 0.456081 0.0299549 0.0803036 0.456527 0.0304 0.0801585 0.452398 0.034 0.0808243 0.45863 0.0299812 0.0794218 0.460712 0.034 0.0779816 0.459427 0.034 0.0786683 0.459192 0.0339689 0.0787872 0.458703 0.0336355 0.0790631 0.458794 0.0337401 0.0790073 0.458911 0.0338374 0.0789396 0.461646 0.0339204 0.0774262 0.460973 0.0295 0.0783063 0.467716 0.0319117 0.0723953 0.465297 0.0305122 0.0751044 0.467926 0.0302857 0.0723989 0.467875 0.0300816 0.0724828 0.464631 0.0295 0.0757715 0.463466 0.0321929 0.0764262 0.467739 0.0298409 0.0726675 0.466672 0.0339931 0.0731177 0.467023 0.0338721 0.0727571 0.463305 0.034 0.0762397 0.459111 0.0295573 0.0792326 0.458827 0.0297291 0.0793492 0.458907 0.0273343 0.0793949 0.459174 0.0274637 0.0792765 0.459427 0.023 0.0793589 0.458835 0.0232218 0.0795857 0.458637 0.023468 0.079651 0.458527 0.0252499 0.0796245 0.458527 0.0239 0.0796756 0.458978 0.0234494 0.079521 0.459115 0.0230557 0.0794832 0.467609 0.0229999 0.0735339 0.468308 0.023334 0.072714 0.468441 0.0235588 0.0725318 0.468062 0.0234944 0.0729765 0.461197 0.0275 0.0782727 0.463786 0.0275 0.0765773 0.462718 0.0252198 0.0774909 0.466552 0.0252235 0.0743798 0.467828 0.0270866 0.0728257 0.468036 0.0272121 0.0725723 0.446427 0.0275 0.081235 0.446827 0.0275 0.081235 0.445527 0.0239 0.081235 0.446827 0.0252436 0.081235 0.446827 0.023 0.081235 0.445647 0.02705 0.081235 0.449796 0.0252611 0.0812091 0.451227 0.023 0.0811515 0.456527 0.0266 0.0802468 0.456527 0.0252499 0.0802791 0.456527 0.0239 0.0803122 0.456478 0.0236081 0.0803322 0.454616 0.0252494 0.0807239 0.45459 0.023 0.0807597 0.456077 0.0270493 0.0803607 0.455932 0.0274466 0.0803912 0.456404 0.0270544 0.0802714 0.452415 0.0275 0.0810352 0.451297 0.0275 0.0811363 0.44714 0.0519974 0.0629633 0.446043 0.051182 0.0644067 0.445584 0.0509769 0.0647439 0.444363 0.0507553 0.0650976 0.444127 0.0497587 0.066575 0.444927 0.0497587 0.066575 0.444127 0.0464806 0.0704387 0.444927 0.0446129 0.072128 0.444927 0.0435886 0.0729243 0.444927 0.042572 0.0736292 0.444182 0.0420851 0.0739377 0.445442 0.0405539 0.0747892 0.445668 0.0413149 0.0743883 0.446427 0.0403393 0.0748945 0.452504 0.0515993 0.0629694 0.449404 0.0405273 0.0747174 0.449565 0.0403395 0.0747984 0.453194 0.0417085 0.0734914 0.449069 0.0519712 0.0629618 0.447046 0.0512309 0.0643244 0.447128 0.0518851 0.0631729 0.449796 0.051388 0.0639499 0.450783 0.0518607 0.0629616 0.452339 0.0511252 0.0638765 0.453489 0.049395 0.0661359 0.452467 0.0507985 0.0643834 0.452359 0.0508277 0.064371 0.449908 0.0511677 0.064312 0.452028 0.0411174 0.0740951 0.450991 0.0403399 0.0746587 0.449452 0.0411156 0.0744096 0.44919 0.0403394 0.0748229 0.446832 0.0403391 0.0748943 0.454756 0.0414745 0.0731029 0.4544 0.0419362 0.0729645 0.45872 0.0403491 0.0715059 0.456957 0.0403483 0.0726597 0.460365 0.0404247 0.070083 0.459355 0.041131 0.0705249 0.460377 0.0403505 0.0701187 0.46266 0.0418552 0.0678437 0.462691 0.0417629 0.0674982 0.463136 0.0408072 0.066691 0.463611 0.0412903 0.0656388 0.463998 0.0421655 0.0642622 0.463008 0.0417946 0.0660473 0.463223 0.0422979 0.0652903 0.463222 0.0429354 0.0646671 0.463262 0.0443873 0.0629855 0.462463 0.0441373 0.06448 0.460569 0.0472587 0.0630617 0.459975 0.0467334 0.0645658 0.455367 0.0506377 0.0630921 0.455573 0.0494193 0.0649559 0.454208 0.0495235 0.0656229 0.455156 0.0493137 0.0653914 0.453615 0.0479647 0.0679398 0.45426 0.0479487 0.0676899 0.454258 0.0454394 0.0703467 0.453487 0.0462823 0.0698222 0.453481 0.0425791 0.0728641 0.454252 0.0425817 0.0726055 0.453507 0.0423083 0.0730321 0.453045 0.040343 0.0742681 0.461016 0.041134 0.0689622 0.462842 0.0406199 0.0672181 0.462621 0.0419703 0.0682751 0.455046 0.0403474 0.0735952 0.455224 0.0412056 0.0730617 0.455698 0.0411263 0.0728906 0.457741 0.0404616 0.0721215 0.464075 0.0452048 0.0632406 0.463623 0.0457549 0.0632541 0.459462 0.049592 0.0699606 0.46048 0.0488221 0.0699704 0.462783 0.0466949 0.0699522 0.458726 0.0500941 0.0633857 0.458456 0.0502676 0.0699371 0.452725 0.0527087 0.0696069 0.454285 0.0522742 0.0696994 0.456929 0.0511452 0.0698717 0.457037 0.0510886 0.0698774 0.450856 0.053009 0.0695542 0.450168 0.0530694 0.06955 0.443527 0.0429 0.0741316 0.443527 0.0467296 0.0761928 0.443527 0.0469033 0.0708645 0.446427 0.0531465 0.0632125 0.446239 0.0531404 0.0632197 0.446427 0.0531465 0.0695675 0.445763 0.0530695 0.0696718 0.444818 0.0526591 0.0639173 0.444922 0.0527252 0.0701289 0.444353 0.0522738 0.0707061 0.443902 0.0516725 0.0714383 0.443527 0.0502465 0.0730256 0.447143 0.0531463 0.0632126 0.447286 0.0531463 0.0632127 0.44743 0.0531463 0.0632124 0.462186 0.04 0.0751554 0.459636 0.04 0.0768876 0.456894 0.04 0.078237 0.457227 0.04 0.0731328 0.454496 0.04 0.0743895 0.45199 0.04 0.0750521 0.449828 0.04 0.0798021 0.446629 0.04 0.0754348 0.446831 0.04 0.0799014 0.446832 0.04 0.0754344 0.448265 0.04 0.0798785 0.443527 0.0429 0.0786444 0.446427 0.04 0.0754349 0.446427 0.04 0.0799014 0.445654 0.0401048 0.0798644 0.445419 0.0401805 0.0753651 0.445238 0.040255 0.0753358 0.44437 0.0408559 0.0795808 0.445631 0.0506676 0.0725772 0.445574 0.0505342 0.0662361 0.446255 0.0511298 0.0720659 0.445831 0.0509213 0.0722992 0.445718 0.0508017 0.0655606 0.445633 0.0506713 0.0658943 0.446382 0.0511453 0.0646351 0.44622 0.0511223 0.0646992 0.445527 0.0467507 0.0761767 0.445527 0.0429 0.0741316 0.445527 0.0449944 0.0725928 0.445527 0.0502465 0.0669243 0.445905 0.0421668 0.0790086 0.445782 0.0422722 0.074773 0.445712 0.0423533 0.0746948 0.445573 0.0426159 0.0787893 0.445585 0.0425823 0.0744665 0.453027 0.0466942 0.0702357 0.453027 0.0429 0.0733496 0.449873 0.0510849 0.0720221 0.449901 0.0510831 0.0646196 0.452326 0.0507484 0.0646779 0.446427 0.0511465 0.0720471 0.44743 0.0511463 0.0720441 0.452127 0.042 0.0746152 0.450441 0.042 0.0789344 0.449487 0.042 0.0749367 0.446628 0.042 0.0750258 0.446829 0.042 0.0790868 0.44683 0.042 0.0750253 0.462938 0.0434667 0.0646064 0.462917 0.0434255 0.0648442 0.462827 0.0432488 0.0658659 0.45995 0.0466547 0.0648562 0.462677 0.0429545 0.0675667 0.456359 0.0491826 0.0648822 0.458718 0.0476586 0.0648846 0.455027 0.0429 0.0776064 0.455027 0.045748 0.0758375 0.455027 0.0429 0.0730831 0.455027 0.0458295 0.07077 0.457257 0.042 0.0726668 0.461692 0.042 0.0745108 0.455418 0.0421579 0.0778554 0.455474 0.0424463 0.0776928 0.45529 0.0422639 0.0778462 0.455228 0.0423331 0.0778325 0.460195 0.042 0.0755895 0.459166 0.042 0.0762262 0.458641 0.042 0.0765205 0.461944 0.0446405 0.0725457 0.462187 0.042 0.0741109 0.458811 0.0475886 0.0724966 0.460575 0.042 0.0753332 0.457525 0.0449945 0.0753158 0.456139 0.0465679 0.074802 0.45512 0.0487921 0.0732786 0.455873 0.0491469 0.0726276 0.455306 0.0490449 0.0729635 0.458636 0.0477201 0.0724905 0.456359 0.0491826 0.072368 0.446825 0.0496578 0.0736249 0.446046 0.051062 0.0721423 0.446427 0.042 0.079087 0.44615 0.0420436 0.0790667 0.44579 0.0422644 0.078962 0.445707 0.0423591 0.0789162 0.445527 0.0429 0.0786444 0.445527 0.0502465 0.0730256 0.446846 0.0511464 0.072047 0.448473 0.0491113 0.074131 0.446825 0.0468784 0.0760779 0.449863 0.0421731 0.0788988 0.446828 0.0448401 0.0775199 0.453027 0.0429 0.0781242 0.452936 0.0425069 0.0783436 0.451514 0.0446657 0.0773602 0.453027 0.0491444 0.07357 0.449641 0.0509941 0.0721405 0.452326 0.0507484 0.0720689 0.452549 0.0506653 0.0721142 0.453027 0.0484959 0.0741755 0.452894 0.0470078 0.0754671 0.453027 0.0457747 0.0763621 0.451296 0.0490236 0.0739969 0.450015 0.046898 0.0759515 0.448466 0.0446449 0.077614 0.44706 0.0471225 0.0758852 0.452127 0.042 0.0787316 0.45626 0.0337392 0.0755637 0.456384 0.033587 0.0755177 0.4564 0.0335612 0.0799558 0.456471 0.0334117 0.0755005 0.456514 0.0332497 0.0755097 0.456527 0.0331 0.0799667 0.458574 0.0333866 0.0791545 0.458607 0.033471 0.0749872 0.458815 0.0337604 0.0747097 0.458877 0.0338123 0.0746348 0.458698 0.0336283 0.0748589 0.459427 0.034 0.0740099 0.446113 0.0295562 0.077335 0.445664 0.0299229 0.0812349 0.44558 0.0300946 0.0812346 0.445647 0.02705 0.077335 0.445977 0.0273794 0.081235 0.467927 0.0305117 0.0723698 0.467901 0.0301581 0.0648053 0.467723 0.0298216 0.0653966 0.467465 0.0296099 0.0730018 0.46825 0.0268165 0.0723646 0.467803 0.0273922 0.0728216 0.467897 0.0273341 0.065494 0.468177 0.0270112 0.0724292 0.468123 0.0271016 0.0649053 0.468273 0.0266768 0.072353 0.469271 0.0113026 0.0647583 0.469256 0.0112085 0.0726698 0.46923 0.0111121 0.0649095 0.469189 0.0110116 0.0727636 0.469 0.010751 0.06563 0.468716 0.0105663 0.0733432 0.469379 0.00779095 0.0727152 0.46931 0.00798972 0.0727882 0.469299 0.00801177 0.0650266 0.468932 0.00838892 0.0732152 0.468775 0.00845661 0.0664868 0.46912 0.00825203 0.0655345 0.469172 0.0081975 0.0729433 0.469268 0.00806853 0.0651166 0.469399 0.00762331 0.0647617 0.469399 0.00762331 0.0726986 0.469375 0.00780801 0.0648182 0.446082 0.0105685 0.081235 0.446082 0.0105685 0.077335 0.445595 0.0110555 0.081235 0.446427 0.00849996 0.081235 0.445527 0.00759996 0.077335 0.445647 0.00804996 0.081235 0.445527 0.00759996 0.081235 0.446427 -0.00850004 0.081235 0.445977 -0.00837946 0.077335 0.445647 -0.00805004 0.081235 0.445977 -0.0106206 0.077335 0.445647 -0.01095 0.077335 0.445647 -0.01095 0.081235 0.469366 -0.00784371 0.0727286 0.469335 -0.00793249 0.0649253 0.469268 -0.00806796 0.0651155 0.46881 -0.00844457 0.0733528 0.468499 -0.00850004 0.067218 0.469264 -0.0112507 0.0726573 0.468525 -0.0105122 0.0669699 0.468812 -0.0106121 0.0732308 0.469069 -0.0108247 0.0729179 0.469018 -0.0107684 0.0655761 0.4692 -0.0110361 0.0650082 0.469276 -0.0114343 0.072631 0.469265 -0.0112537 0.064785 0.469277 -0.0114035 0.0647286 0.468273 -0.0266769 0.072353 0.468192 -0.0269802 0.064736 0.468226 -0.0268957 0.0723835 0.468128 -0.0270941 0.0648927 0.467963 -0.0272822 0.0653196 0.467953 -0.0272906 0.0726599 0.467897 -0.0273337 0.0654921 0.467691 -0.0274433 0.066033 0.467655 -0.0274556 0.0729825 0.467867 -0.0300594 0.0724955 0.467464 -0.0296095 0.0730026 0.46768 -0.0297737 0.065527 0.467917 -0.0302261 0.0647379 0.467927 -0.0305118 0.0723698 0.445977 -0.0273795 0.081235 0.445977 -0.0273795 0.077335 0.445647 -0.02705 0.081235 0.445647 -0.02705 0.077335 0.445527 -0.0266 0.081235 0.445527 -0.0304 0.0773339 0.445579 -0.0300998 0.0773349 0.445578 -0.0301021 0.0812346 0.445724 -0.0298378 0.0812349 0.445727 -0.0298345 0.077335 0.446039 -0.029588 0.077335 0.446427 -0.0295 0.077335 0.455027 0.0483931 0.0736859 0.455051 0.0486017 0.067609 0.455086 0.0487138 0.0673432 0.455226 0.0489576 0.0666872 0.455385 0.0491117 0.0728669 0.455368 0.0490989 0.0662308 0.455549 0.0492105 0.0657838 0.455671 0.0492559 0.0726059 0.455649 0.0492495 0.0655827 0.455929 0.049293 0.0724557 0.456153 0.0492641 0.0723829 0.456092 0.0492777 0.0649903 0.455797 0.0492836 0.0653325 0.455766 0.0492786 0.0653803 0.452474 0.0507009 0.0647246 0.452681 0.0505799 0.0649257 0.452885 0.0503559 0.0653794 0.45273 0.0505388 0.0722128 0.453027 0.0498707 0.0728492 0.452914 0.0503067 0.0724202 0.452955 0.0502241 0.0656667 0.452974 0.0425975 0.0736986 0.452966 0.0425743 0.0737268 0.452891 0.0424246 0.0739141 0.452727 0.0422296 0.0785199 0.452501 0.0420815 0.0744096 0.452428 0.0420518 0.0786581 0.455035 0.0427821 0.0732078 0.455927 0.042 0.0777516 0.455583 0.0420681 0.0735675 0.455665 0.0420388 0.0778274 0.455573 0.0420724 0.0735708 0.45534 0.0422177 0.0735926 0.455276 0.0422788 0.0735754 0.455099 0.0425464 0.0777669 0.455033 0.0427965 0.077659 0.455086 0.0425799 0.0733915 0.455627 0.0295 0.0763943 0.455949 0.0295598 0.0762159 0.456096 0.0296323 0.0761265 0.456266 0.0297663 0.0802561 0.45634 0.0298509 0.0802324 0.456353 0.0298689 0.0759554 0.456478 0.0301084 0.0801837 0.456459 0.0300575 0.0758742 0.459427 0.0295 0.0790921 0.458864 0.0296978 0.0752207 0.458537 0.0302639 0.0794473 0.458527 0.0304 0.0794448 0.45651 0.0267709 0.0802475 0.45647 0.0269152 0.075951 0.456203 0.0272916 0.080322 0.456258 0.0272417 0.0760677 0.455799 0.0274834 0.0763217 0.458527 0.0266 0.0795747 0.458527 0.0266 0.0755962 0.458573 0.0268843 0.0795464 0.458598 0.0269514 0.0755172 0.458703 0.027135 0.0794855 0.458791 0.027237 0.0794461 0.459427 0.0275 0.0791637 0.456527 0.0239 0.0760326 0.455764 0.0230105 0.0764891 0.455844 0.0230265 0.0805025 0.456122 0.0231484 0.0804335 0.456174 0.0231855 0.0762763 0.456266 0.0232664 0.0803951 0.456265 0.0232649 0.0762229 0.456339 0.0233499 0.0803745 0.459101 0.0230611 0.0753497 0.458948 0.0231381 0.0754642 0.458795 0.0232594 0.0755705 0.458809 0.0232455 0.0755608 0.458923 0.0231537 0.0754814 0.458539 0.0237508 0.0796766 0.458602 0.0235395 0.0756891 0.458641 0.0234621 0.0756675 0.45647 0.0144144 0.07635 0.456398 0.0145642 0.0805344 0.458709 0.0146434 0.0799134 0.458607 0.0144715 0.0760089 0.458919 0.0148433 0.0798382 0.458805 0.0147507 0.0758696 0.45919 0.0149683 0.079741 0.459313 0.0149926 0.0754976 0.459119 0.0105542 0.0798846 0.459259 0.0105156 0.0757316 0.459427 0.0105 0.0756133 0.458796 0.0107581 0.0760205 0.458948 0.0106381 0.0759322 0.458684 0.0108916 0.076081 0.45854 0.0112469 0.0761485 0.458527 0.0114 0.0800516 0.458527 0.00759996 0.0762325 0.458575 0.00788942 0.0801071 0.458791 0.00823676 0.0800368 0.458923 0.00834563 0.0799943 0.458803 0.00824861 0.076056 0.459094 0.00843629 0.0758677 0.456438 0.0110105 0.0764513 0.455627 0.0105 0.0807377 0.455754 0.0105091 0.0767373 0.456259 0.0107596 0.0765375 0.455627 0.00849996 0.0767904 0.455928 0.00844803 0.0807074 0.456195 0.00829779 0.0806612 0.456508 0.00778486 0.0806074 0.456457 0.00794851 0.0764887 0.459094 0.00406361 0.0759677 0.459259 0.00401578 0.0758636 0.45912 0.00405401 0.0799968 0.459427 0.00399996 0.0757506 0.458802 0.00425185 0.0761374 0.45868 0.00439791 0.0762025 0.458845 0.00421288 0.0800783 0.458538 0.00475922 0.0762708 0.458527 0.00489996 0.0762737 0.456527 0.00489996 0.0806299 0.456436 0.00450683 0.0765458 0.456335 0.00434436 0.0806692 0.456262 0.00426271 0.0766191 0.456263 0.00426345 0.0806826 0.456162 0.00417675 0.0766581 0.456114 0.00414317 0.0807094 0.455934 0.00405399 0.0767408 0.455934 0.00405396 0.0807402 0.455836 0.00402451 0.0807564 0.455756 0.00400931 0.0767996 0.456063 -0.00411282 0.0766951 0.456396 -0.00443289 0.0806575 0.456527 -0.00490004 0.0806299 0.45647 -0.00458556 0.0765305 0.456387 -0.0044175 0.0765676 0.458527 -0.00490004 0.0801628 0.458574 -0.00461124 0.0801525 0.458687 -0.00438825 0.076199 0.458794 -0.00426027 0.080093 0.458802 -0.0042525 0.0761377 0.459191 -0.00403158 0.0799749 0.458861 -0.00420052 0.0761051 0.459427 -0.00400004 0.0798995 0.459094 -0.00406395 0.0759681 0.459225 -0.00402298 0.0758853 0.456527 -0.00760004 0.0764666 0.456438 -0.0079889 0.0764956 0.456478 -0.00789366 0.080612 0.456336 -0.00815434 0.0806364 0.45584 -0.00847453 0.0807224 0.456116 -0.00835525 0.080675 0.45626 -0.00823956 0.0806498 0.45626 -0.0107602 0.0765372 0.456196 -0.0107029 0.0806327 0.456391 -0.0109247 0.0764753 0.456521 -0.0113025 0.0764029 0.456508 -0.011219 0.0805635 0.45647 -0.0110853 0.0764343 0.456456 -0.0110512 0.0764416 0.459427 -0.00850004 0.0798278 0.459427 -0.00850004 0.0756365 0.45853 -0.00767315 0.0762287 0.45854 -0.00775349 0.0801194 0.458527 -0.0114 0.0800516 0.458545 -0.0112186 0.0761466 0.458574 -0.0111128 0.0800438 0.458709 -0.0108574 0.0800084 0.458687 -0.0108871 0.0760793 0.458794 -0.0107602 0.0799842 0.458852 -0.0107079 0.0759889 0.459184 -0.0105334 0.0798637 0.459095 -0.0105634 0.0758406 0.459207 -0.0105274 0.0757672 0.459427 -0.0105 0.0797821 0.456527 -0.0141 0.0805143 0.456442 -0.0144814 0.0763611 0.456338 -0.0146522 0.0805458 0.455627 -0.015 0.0766925 0.455933 -0.0149462 0.0765736 0.455968 -0.0149327 0.0765594 0.45926 -0.0149845 0.0755379 0.459115 -0.0149441 0.0797683 0.458943 -0.0148593 0.0757714 0.45863 -0.0145179 0.0759928 0.458538 -0.0142432 0.0799788 0.458527 -0.0141 0.0760754 0.458527 -0.0239 0.0796756 0.458546 -0.0237161 0.0757157 0.458572 -0.023618 0.0796695 0.458598 -0.02355 0.0756915 0.458702 -0.0233667 0.0796306 0.458691 -0.0233817 0.075637 0.458903 -0.0231684 0.0795619 0.458798 -0.0232557 0.0755679 0.458839 -0.0232186 0.0755405 0.459101 -0.0230613 0.0753499 0.459162 -0.0230398 0.079465 0.459427 -0.023 0.0793589 0.456403 -0.0234441 0.0803559 0.456261 -0.0232619 0.0762248 0.455932 -0.0230533 0.0804813 0.456521 -0.0237992 0.0760424 0.456511 -0.0237313 0.0803206 0.456455 -0.0235485 0.0760973 0.456527 -0.0239 0.0803122 0.459427 -0.0275 0.0791637 0.459103 -0.0274397 0.0750631 0.458823 -0.0272673 0.079432 0.459107 -0.0274412 0.0793063 0.458951 -0.0273639 0.0752013 0.458794 -0.0272401 0.0753413 0.458604 -0.0269655 0.0755115 0.458527 -0.0304 0.0754396 0.45855 -0.0301964 0.0754408 0.458586 -0.0300792 0.0754222 0.458764 -0.0297907 0.0752984 0.458888 -0.0296788 0.0793248 0.459142 -0.0295462 0.0792189 0.459134 -0.0295489 0.0749923 0.459427 -0.0295 0.0790921 0.459279 -0.0295122 0.0748613 0.459427 -0.0295 0.0747203 0.459103 -0.03394 0.0743693 0.458817 -0.0337621 0.0747075 0.458808 -0.0337539 0.0789988 0.458759 -0.0337033 0.0747803 0.458609 -0.0334763 0.0791269 0.458529 -0.0331645 0.0792026 0.458527 -0.0331 0.0751558 0.456527 -0.0331 0.0799667 0.456254 -0.0337457 0.0755665 0.455944 -0.0339422 0.0757216 0.456479 -0.0268886 0.0802537 0.456343 -0.0271451 0.0802864 0.456255 -0.0272443 0.0760692 0.455627 -0.0275 0.0764111 0.455859 -0.0274696 0.0804097 0.455627 -0.0295 0.0804357 0.455949 -0.0295599 0.076216 0.456527 -0.0304 0.0801585 0.456229 -0.0297315 0.076041 0.456205 -0.0297103 0.080275 0.456353 -0.0298685 0.075955 0.455076 -0.0426079 0.0777432 0.455124 -0.0424929 0.0734576 0.455041 -0.0427416 0.0732478 0.455027 -0.0429 0.0776064 0.455027 -0.0429 0.0730831 0.455927 -0.042 0.073373 0.455739 -0.04202 0.0734992 0.455676 -0.0420358 0.0778251 0.455527 -0.0420936 0.0735833 0.455313 -0.0422415 0.0735871 0.455442 -0.0421415 0.0778549 0.455229 -0.0423321 0.0778327 0.452499 -0.0420808 0.074411 0.452764 -0.0422645 0.0784962 0.452469 -0.0420677 0.0744347 0.452661 -0.0421754 0.0785583 0.452656 -0.042172 0.0742633 0.452769 -0.0422697 0.0741215 0.452787 -0.0422881 0.0740959 0.452851 -0.0423652 0.0739918 0.452973 -0.0425944 0.0737024 0.452997 -0.0426719 0.0782481 0.453027 -0.0429 0.0781242 0.452767 -0.0505036 0.0722427 0.452671 -0.0505875 0.0721729 0.452572 -0.050653 0.0721228 0.452645 -0.0506067 0.0648768 0.452325 -0.0507488 0.0720687 0.445351 0.0499015 0.0666773 0.445985 0.0510305 0.0649521 0.446427 0.0511518 0.0645518 0.44592 0.0510053 0.0648685 0.445189 0.0502346 0.065945 0.445384 0.0506513 0.0652957 0.445064 0.050373 0.0656857 0.445246 0.0506669 0.0652364 0.445517 0.0506698 0.0653746 0.44534 0.0500983 0.0663516 0.445363 0.0502931 0.0660244 0.445548 0.0505636 0.0657932 0.445539 0.0503926 0.0665794 0.445476 0.0502338 0.0664617 0.445497 0.0503997 0.0661273 0.445632 0.0507221 0.065466 0.445847 0.0509986 0.0647854 0.446427 0.051231 0.0643247 0.446735 0.0511464 0.0646318 0.446427 0.0511465 0.0646318 0.447046 0.0512048 0.0643728 0.446427 0.051168 0.0644726 0.445112 0.0446323 0.0721516 0.445279 0.0446864 0.0722175 0.445112 0.042588 0.0736538 0.445497 0.0467727 0.0707329 0.445112 0.0465013 0.0704595 0.445112 0.0497825 0.0665921 0.444927 0.048216 0.0685563 0.445279 0.0465614 0.07052 0.445412 0.0466549 0.0706142 0.445412 0.0447706 0.0723201 0.445497 0.0448767 0.0724494 0.445527 0.0469033 0.0708645 0.445497 0.0500957 0.0668164 0.445412 0.0499597 0.066719 0.445279 0.0498518 0.0666417 0.447236 0.0511463 0.0646312 0.447042 0.0511464 0.0646311 0.447429 0.051231 0.0643234 0.447429 0.0511676 0.0644723 0.445623 0.0418654 0.0742364 0.445371 0.0419406 0.0740911 0.445525 0.0417573 0.074205 0.445934 0.0414877 0.0743682 0.446427 0.0415817 0.074454 0.446084 0.0419953 0.0746873 0.445865 0.0418613 0.0743916 0.445517 0.0428403 0.0740402 0.446427 0.042 0.0750258 0.445922 0.0421364 0.0747429 0.446104 0.0420598 0.0749716 0.445528 0.0428562 0.074179 0.445761 0.0420854 0.0743987 0.445788 0.0421764 0.0745141 0.445535 0.0423721 0.0741538 0.445497 0.0427986 0.0739763 0.445579 0.0424511 0.0742558 0.445412 0.0427072 0.0738363 0.445279 0.0426346 0.0737251 0.445463 0.0422909 0.0740659 0.445148 0.042595 0.0736644 0.445787 0.0422457 0.0746363 0.445594 0.0425223 0.0743627 0.445149 0.0418079 0.0741051 0.446284 0.0411212 0.0744945 0.446427 0.0413089 0.0744328 0.446427 0.0411147 0.074498 0.446073 0.0419011 0.0745599 0.446042 0.0417762 0.0744569 0.445994 0.041633 0.0743913 0.446247 0.041854 0.0746023 0.446252 0.041948 0.0747334 0.446427 0.041965 0.074824 0.446247 0.042002 0.0748734 0.446077 0.0420539 0.0748231 0.445928 0.042072 0.0746134 0.44591 0.0419785 0.0744915 0.445705 0.0419784 0.0743026 0.44557 0.042123 0.0741932 0.445255 0.0421474 0.0739598 0.445023 0.0420571 0.0739549 0.449692 0.0511809 0.0643117 0.449903 0.0511046 0.0644601 0.44743 0.0511463 0.0646307 0.446831 0.0411146 0.0744976 0.446831 0.0413866 0.074425 0.446831 0.0417073 0.0745096 0.446427 0.0417072 0.0745105 0.44683 0.0418401 0.0746171 0.446427 0.0418166 0.0745941 0.44683 0.0419341 0.0747517 0.453259 0.0501877 0.0650614 0.45299 0.0501246 0.0658894 0.452784 0.0505435 0.0647529 0.452338 0.0507678 0.0645187 0.452842 0.0506183 0.0645441 0.453156 0.0495674 0.0662585 0.453058 0.0497146 0.0663633 0.453027 0.0498707 0.0664743 0.453309 0.0494558 0.0661791 0.453149 0.0498962 0.0657186 0.453037 0.0502273 0.065203 0.45305 0.0499967 0.0658133 0.452949 0.0502825 0.0652901 0.452725 0.050557 0.0648345 0.453144 0.0501952 0.065125 0.449835 0.0411158 0.0743812 0.44946 0.0418404 0.0745302 0.449453 0.0417079 0.074423 0.452031 0.0417088 0.0741098 0.452019 0.0415518 0.0740449 0.449447 0.0413877 0.0743382 0.449448 0.0415505 0.0743573 0.446831 0.0415497 0.0744439 0.449469 0.0419343 0.0746644 0.44683 0.0418171 0.0745936 0.453309 0.0463352 0.0698753 0.453058 0.0427953 0.0731912 0.453058 0.0465592 0.0701002 0.453156 0.0464318 0.0699723 0.452959 0.0424463 0.0735482 0.453011 0.0427336 0.0735375 0.452925 0.0421202 0.0735479 0.452863 0.0422941 0.0737228 0.452783 0.0419701 0.073702 0.452749 0.0420729 0.0737882 0.452418 0.0418866 0.0740542 0.45274 0.0421633 0.0738879 0.452102 0.0419845 0.0744823 0.45243 0.0419826 0.0741696 0.452755 0.0422362 0.0739923 0.452623 0.0412462 0.0738999 0.452726 0.0416038 0.0737402 0.452459 0.0416264 0.0738932 0.452917 0.041759 0.0735964 0.453025 0.0426145 0.0733698 0.453154 0.0426965 0.0730417 0.453115 0.0424887 0.073213 0.453304 0.0426211 0.0729275 0.453467 0.0423795 0.0729986 0.452285 0.0419981 0.0744045 0.452387 0.0420383 0.0744922 0.45246 0.0420472 0.0742918 0.452749 0.0422496 0.0741497 0.452801 0.0423033 0.0740749 0.452076 0.0419344 0.0743473 0.452235 0.0418453 0.0741497 0.452255 0.0419404 0.0742732 0.452015 0.0413893 0.0740258 0.452508 0.0414872 0.073863 0.452051 0.0418409 0.0742154 0.45223 0.041717 0.0740494 0.452428 0.0417642 0.0739585 0.452614 0.0418494 0.0738413 0.453191 0.0421538 0.0732715 0.453037 0.0422952 0.073383 0.454513 0.0425707 0.072589 0.454518 0.0454276 0.0703339 0.454786 0.045504 0.0704168 0.45452 0.047936 0.0676794 0.454658 0.0479663 0.0677045 0.454892 0.0426901 0.0727681 0.45497 0.0456572 0.070583 0.45497 0.0427583 0.0728706 0.455927 0.042 0.073373 0.455231 0.0415016 0.0729805 0.455679 0.0415629 0.0728513 0.455312 0.0420139 0.0731712 0.455229 0.0418943 0.0730651 0.455193 0.0421102 0.073156 0.4551 0.0419991 0.0730511 0.455373 0.0420988 0.0733089 0.455708 0.0420093 0.0733598 0.455444 0.0419357 0.0731508 0.455091 0.0425226 0.0732689 0.455014 0.0428303 0.0729787 0.454543 0.0423498 0.0727286 0.454758 0.0421998 0.0728643 0.454689 0.0423911 0.0727546 0.454653 0.0425919 0.0726208 0.454784 0.0426326 0.0726819 0.454986 0.0421277 0.0730041 0.455533 0.0417482 0.0729945 0.455653 0.0419647 0.0732229 0.455162 0.0424255 0.0735022 0.455172 0.0423795 0.0733721 0.455148 0.042314 0.0732342 0.455253 0.0421963 0.0732915 0.455278 0.0422518 0.0734369 0.455406 0.0421452 0.073457 0.455552 0.0420633 0.0734305 0.454861 0.0417572 0.0729855 0.454612 0.042135 0.0728449 0.454891 0.0422798 0.0729245 0.454823 0.0424505 0.0728154 0.455506 0.042021 0.0732857 0.455592 0.0418766 0.0730951 0.455372 0.0418103 0.0730464 0.455298 0.0416588 0.0729881 0.454984 0.0418761 0.0729928 0.455086 0.0422277 0.0731054 0.455064 0.0424501 0.0731409 0.454997 0.0423666 0.0730209 0.456363 0.0491863 0.0648049 0.455073 0.048718 0.0670899 0.455019 0.0485148 0.0675402 0.455027 0.0483931 0.068057 0.455009 0.0486531 0.0670277 0.455014 0.0482968 0.0679775 0.45497 0.0481973 0.0678953 0.45488 0.048358 0.0674018 0.454962 0.0484314 0.0674695 0.45483 0.0485635 0.0669133 0.455106 0.0488573 0.066577 0.455694 0.0492777 0.0652834 0.455612 0.0492983 0.0652003 0.455735 0.049276 0.0653259 0.454787 0.0480233 0.0677515 0.454894 0.048103 0.0678173 0.454392 0.0485633 0.0668555 0.454952 0.049038 0.0659556 0.455106 0.049013 0.0660349 0.456268 0.0492257 0.0648941 0.456006 0.0492975 0.0649483 0.45525 0.0490351 0.0661308 0.455499 0.0491919 0.0657382 0.455313 0.0490625 0.0661811 0.455119 0.0487901 0.0671508 0.456402 0.0492492 0.0645844 0.456371 0.0491988 0.0647282 0.456052 0.0493851 0.0646538 0.455966 0.0493238 0.0648696 0.455533 0.0493413 0.0651237 0.454614 0.0485464 0.066834 0.454941 0.0488042 0.0664728 0.454724 0.0485454 0.066868 0.454777 0.0483012 0.0673424 0.455708 0.0417163 0.0729124 0.457211 0.0411282 0.0720711 0.455669 0.0414029 0.072831 0.457079 0.0411281 0.0721508 0.459326 0.042 0.0712412 0.462443 0.0424932 0.0702337 0.455869 0.0419847 0.0732515 0.459582 0.0411314 0.0703318 0.459118 0.0411306 0.0707204 0.460041 0.0411322 0.0699207 0.455811 0.041936 0.0731294 0.455754 0.0418449 0.0730094 0.458654 0.04113 0.0710852 0.458297 0.0411295 0.071349 0.457939 0.0411291 0.0716002 0.46061 0.046151 0.0645461 0.458621 0.047827 0.0645953 0.45996 0.0466718 0.0647059 0.462628 0.0428576 0.0681271 0.462875 0.0433431 0.0653205 0.462777 0.0431509 0.0664319 0.462861 0.0421787 0.0662376 0.462727 0.0430523 0.0670019 0.462691 0.0420933 0.0668141 0.462776 0.0431485 0.0664458 0.462668 0.0418313 0.0677542 0.462477 0.041981 0.0673358 0.462677 0.0429534 0.0675735 0.462644 0.041901 0.0680153 0.462774 0.0415216 0.0665942 0.462735 0.0416356 0.0670212 0.46272 0.0416777 0.0671791 0.462862 0.0420954 0.0661921 0.463253 0.0425014 0.0650527 0.454206 0.0288922 0.0761594 0.451236 0.0291211 0.0766669 0.451247 0.0293258 0.0768016 0.455461 0.0291138 0.0758588 0.446827 0.0294196 0.077035 0.451273 0.0295 0.0772235 0.446827 0.0293263 0.0769129 0.451265 0.0294593 0.0770064 0.446827 0.0292 0.0768154 0.451233 0.0288985 0.0766248 0.446427 0.0294196 0.077035 0.455695 0.0293265 0.0759102 0.455912 0.0291839 0.0757034 0.455902 0.0295014 0.0760175 0.455791 0.0295152 0.0763063 0.455733 0.0294633 0.0761005 0.455562 0.0294585 0.0761849 0.455449 0.0288884 0.0758213 0.455501 0.0293223 0.0759872 0.455887 0.0293693 0.0758329 0.456062 0.0295707 0.0759351 0.445905 0.0289938 0.076735 0.446427 0.0292 0.0768154 0.446427 0.0295 0.077335 0.445361 0.0293443 0.076735 0.446009 0.029275 0.0768154 0.446086 0.0294809 0.077035 0.445574 0.0295554 0.0768154 0.445664 0.0297839 0.077035 0.44573 0.02971 0.077035 0.445787 0.0297666 0.077335 0.445694 0.029808 0.0771142 0.445727 0.0298344 0.077335 0.45635 0.0298141 0.0757753 0.456457 0.0299866 0.0757076 0.456229 0.0297315 0.0760408 0.45663 0.0298421 0.075409 0.456284 0.0294689 0.0755867 0.45652 0.0299212 0.0755413 0.456238 0.0295623 0.0756815 0.456214 0.0296402 0.0757957 0.456626 0.030381 0.0754677 0.45677 0.0297631 0.0753264 0.44559 0.029724 0.0769108 0.445221 0.0299734 0.076777 0.445013 0.0298998 0.0767349 0.445493 0.0296459 0.0768154 0.445527 0.0304 0.0773339 0.445578 0.0301002 0.0773349 0.445539 0.030086 0.077114 0.445351 0.0303985 0.0769097 0.445413 0.0300413 0.0769106 0.456527 0.0317526 0.0756946 0.45655 0.0303904 0.0756312 0.45655 0.0330772 0.0753736 0.456747 0.0303733 0.075334 0.456623 0.0330548 0.0752138 0.456895 0.0303682 0.0752452 0.444927 0.0330663 0.0766689 0.445527 0.0317504 0.0773187 0.445527 0.0331 0.077268 0.444927 0.032636 0.0766902 0.444927 0.0303978 0.0767339 0.445148 0.030398 0.0767761 0.445279 0.0330727 0.0767827 0.445485 0.0303992 0.0771131 0.456248 0.0337855 0.0753994 0.45674 0.0330364 0.075082 0.456347 0.0339647 0.0751088 0.455711 0.0344707 0.075248 0.456438 0.0340819 0.0750221 0.456474 0.0334652 0.0753378 0.456527 0.0331 0.0755362 0.45628 0.0338609 0.0752394 0.455741 0.0340264 0.0756239 0.456092 0.0338704 0.0756432 0.455796 0.0339839 0.0758053 0.455627 0.034 0.0759061 0.455559 0.034033 0.0757215 0.455922 0.0339821 0.0755367 0.455908 0.0340839 0.0753701 0.456537 0.0334966 0.0751806 0.445484 0.0330875 0.0770462 0.445527 0.0330991 0.0772527 0.44579 0.0337362 0.0771889 0.445552 0.0334466 0.0770134 0.445656 0.0338313 0.0767799 0.445428 0.033483 0.0768131 0.446427 0.034 0.0771432 0.446007 0.0340682 0.0767537 0.44606 0.0339625 0.0769476 0.446427 0.034031 0.0769527 0.445087 0.0330676 0.0766908 0.445185 0.03389 0.0766109 0.445501 0.0332706 0.0770312 0.445242 0.0335498 0.0766788 0.445373 0.0330775 0.0768674 0.445148 0.0330687 0.076711 0.446427 0.0343465 0.0765994 0.446427 0.034331 0.0766069 0.445517 0.0339582 0.0766445 0.445753 0.0337537 0.0769767 0.446082 0.0339313 0.0771559 0.451211 0.0341471 0.0765529 0.451188 0.0345217 0.076353 0.455424 0.0345009 0.0753502 0.455447 0.0343081 0.0754137 0.451195 0.0343224 0.0764155 0.446823 0.0341506 0.0767459 0.451234 0.0340346 0.0767443 0.455494 0.0341403 0.0755438 0.455494 0.034142 0.0755419 0.446823 0.0343298 0.0766077 0.446427 0.0341524 0.0767436 0.446823 0.0340354 0.0769404 0.445327 0.0272352 0.0767807 0.445351 0.0266 0.0769108 0.445527 0.0266 0.077335 0.445446 0.0266 0.077035 0.445495 0.0271378 0.0769108 0.445889 0.0275316 0.0769108 0.445608 0.0270728 0.0771054 0.446427 0.0278703 0.0767807 0.445792 0.0277001 0.0767807 0.445954 0.0274189 0.0771054 0.446427 0.0275456 0.0771054 0.445977 0.0273794 0.077335 0.446427 0.0275 0.077335 0.444927 0.0239 0.076735 0.444927 0.0266 0.076735 0.445227 0.0239 0.0768154 0.445156 0.0266 0.0767807 0.445227 0.0266 0.0768154 0.445446 0.0239 0.077035 0.445481 0.0239 0.0771054 0.445481 0.0266 0.0771054 0.446827 0.0275456 0.0771054 0.446427 0.0276757 0.0769108 0.446827 0.0278703 0.0767807 0.446827 0.0281 0.076735 0.446427 0.0228242 0.0769108 0.446427 0.0227 0.0768154 0.445677 0.0226009 0.076735 0.445327 0.0232648 0.0767807 0.445156 0.0239 0.0767807 0.445792 0.0227998 0.0767807 0.445954 0.023081 0.0771054 0.445608 0.0234271 0.0771054 0.445351 0.0239 0.0769108 0.445495 0.0233621 0.0769108 0.445889 0.0229683 0.0769108 0.446427 0.0229543 0.0771054 0.445977 0.0231205 0.077335 0.455564 0.0275395 0.0762061 0.451264 0.0275 0.0772263 0.451246 0.0275404 0.0770105 0.45123 0.027673 0.0768061 0.451219 0.0278766 0.0766713 0.446827 0.0276757 0.0769108 0.451215 0.0280984 0.0766283 0.454234 0.0280914 0.0761643 0.455505 0.0276692 0.0760117 0.455563 0.0275411 0.0762024 0.446427 0.023 0.077335 0.446827 0.023 0.077335 0.446827 0.0229196 0.077035 0.446427 0.0229196 0.077035 0.446827 0.0227 0.0768154 0.456753 0.0272508 0.0754111 0.456471 0.0269827 0.0757841 0.456244 0.027297 0.0758874 0.456092 0.0273704 0.0761614 0.456386 0.0270837 0.0759958 0.455465 0.0278687 0.0758817 0.455941 0.0277871 0.0757255 0.455452 0.0280873 0.0758374 0.455661 0.028071 0.0757725 0.456527 0.0266 0.0759322 0.456516 0.0267364 0.075931 0.456279 0.0273931 0.0757152 0.455744 0.027533 0.0761204 0.455923 0.0274892 0.0760381 0.456756 0.0265831 0.0754607 0.456538 0.0270333 0.0756178 0.456631 0.0265879 0.0755943 0.456091 0.0274103 0.0759592 0.455913 0.0276128 0.0758566 0.456358 0.0275206 0.0755826 0.456305 0.0277977 0.0755612 0.451216 0.0226196 0.0766865 0.455542 0.0228994 0.07623 0.451225 0.0228236 0.0768197 0.45557 0.0229567 0.0763352 0.451254 0.023 0.0772436 0.451239 0.0229577 0.0770229 0.446827 0.0228242 0.0769108 0.456553 0.0238934 0.075857 0.456552 0.0265938 0.0757593 0.456635 0.0238871 0.0756897 0.456908 0.02658 0.0753739 0.45654 0.0234478 0.0757462 0.456764 0.0238821 0.0755554 0.456246 0.0232004 0.0760373 0.456671 0.0230365 0.0755888 0.456147 0.0225543 0.0757748 0.455925 0.0228781 0.0759979 0.45594 0.0230563 0.0764028 0.455945 0.0230479 0.0762883 0.456446 0.0235265 0.0761044 0.455929 0.0230099 0.076186 0.455922 0.0229527 0.0760873 0.455517 0.0228192 0.0761365 0.455483 0.0226106 0.0760083 0.45596 0.0226927 0.0758671 0.456919 0.0238789 0.07547 0.456373 0.0229564 0.0757262 0.456285 0.0230947 0.0758591 0.45647 0.0235094 0.075917 0.456246 0.0232355 0.0761329 0.455599 0.0229897 0.0764446 0.468003 0.0305235 0.0643204 0.467458 0.0333026 0.0644803 0.467717 0.0319105 0.0646243 0.467927 0.0305117 0.0646148 0.467335 0.0335593 0.0647619 0.467414 0.0333884 0.0646486 0.467226 0.0337638 0.0647231 0.467513 0.0333159 0.0643401 0.46667 0.0340267 0.0658736 0.466796 0.0339687 0.0659689 0.466399 0.0340318 0.0664505 0.467099 0.0338217 0.0652485 0.466368 0.0344375 0.0657868 0.466132 0.0342867 0.0662758 0.466864 0.0341297 0.0651438 0.466564 0.0341297 0.0657825 0.466959 0.0339298 0.0653023 0.467111 0.0340404 0.0647392 0.4669 0.0340206 0.0652186 0.467242 0.0337039 0.0648015 0.467271 0.0336534 0.064881 0.467916 0.0300993 0.0646135 0.467612 0.0296802 0.0654457 0.467329 0.0292441 0.0656999 0.46733 0.0292681 0.0657092 0.467381 0.029481 0.0658216 0.467344 0.0291094 0.0656593 0.467821 0.0296134 0.0648014 0.467933 0.0303645 0.0646472 0.467946 0.0305153 0.0644626 0.467782 0.0296941 0.064878 0.467771 0.0297858 0.0649526 0.467781 0.029872 0.0650335 0.467812 0.0299481 0.065116 0.463122 0.0341332 0.0703774 0.466247 0.0341313 0.0663509 0.463021 0.0342907 0.0702839 0.4614 0.0340327 0.0722865 0.459374 0.0340079 0.0739281 0.463255 0.0340323 0.070502 0.459106 0.0344857 0.073516 0.459144 0.0342988 0.0735747 0.461191 0.0342942 0.0720428 0.461281 0.0341349 0.072147 0.459267 0.0340765 0.0737641 0.45932 0.0340332 0.0738448 0.46696 0.0291243 0.0663255 0.467142 0.0294582 0.0665036 0.467426 0.0295534 0.0658763 0.467367 0.0295641 0.0664082 0.467526 0.0296468 0.0659719 0.466565 0.0290966 0.0669466 0.467034 0.0295 0.067265 0.467023 0.0293134 0.0664012 0.466849 0.0292989 0.0667116 0.466994 0.029445 0.0668208 0.467164 0.0295094 0.0669385 0.467289 0.0295369 0.0666166 0.458246 0.0330248 0.0746532 0.458514 0.033412 0.0747411 0.458575 0.0334355 0.0748665 0.458378 0.0332241 0.0747034 0.458512 0.0330801 0.0750234 0.458526 0.0332621 0.0749608 0.458596 0.0334469 0.0750033 0.458657 0.0335932 0.0747455 0.458605 0.0337323 0.0743906 0.4589 0.0339675 0.0740928 0.458765 0.0337302 0.0746038 0.458373 0.0330406 0.0747593 0.458252 0.0332238 0.0746016 0.458299 0.03342 0.0745248 0.458094 0.0330147 0.0745859 0.458163 0.0334545 0.0744581 0.458291 0.0339151 0.0741951 0.458023 0.0335049 0.0744277 0.458694 0.0337192 0.0744946 0.458589 0.0335745 0.0746283 0.458503 0.0337714 0.0743013 0.459102 0.0339393 0.0743712 0.459043 0.0339273 0.0742786 0.458975 0.0339358 0.0741839 0.459219 0.0341371 0.0736898 0.458823 0.0340224 0.0740117 0.458749 0.0340979 0.073946 0.458682 0.0341886 0.0738995 0.458471 0.033238 0.0748281 0.45842 0.0334057 0.0746228 0.458497 0.0335775 0.0745171 0.458384 0.0336051 0.0744234 0.458395 0.0338343 0.0742346 0.463636 0.0295 0.0714276 0.461295 0.0291015 0.0727613 0.461378 0.0293163 0.0728659 0.45921 0.0293182 0.0743489 0.459315 0.0294576 0.0745291 0.459427 0.0295 0.0747203 0.463246 0.0290991 0.071017 0.461274 0.0288717 0.0727345 0.46334 0.0293152 0.0711108 0.461507 0.0294572 0.0730305 0.463489 0.0294569 0.0712589 0.461645 0.0295 0.0732054 0.466674 0.029314 0.067021 0.466849 0.0294567 0.0671393 0.458527 0.0331 0.0751558 0.458527 0.031753 0.0753262 0.458527 0.0304 0.0754396 0.458463 0.0330602 0.0748902 0.458464 0.0303829 0.0751735 0.458376 0.0303745 0.0750423 0.457935 0.0330112 0.0745625 0.459134 0.0295488 0.0749923 0.45882 0.0297153 0.0751024 0.458757 0.0297094 0.0749797 0.458673 0.0296752 0.0748637 0.458797 0.029572 0.0747753 0.45858 0.0296154 0.0747704 0.458542 0.029294 0.0745754 0.458219 0.0292168 0.0746848 0.458991 0.0296125 0.0751159 0.458876 0.0296134 0.0748861 0.45871 0.0295009 0.0746812 0.458865 0.0294112 0.0745802 0.458733 0.0291957 0.0744713 0.459012 0.0295364 0.0747761 0.458847 0.0289053 0.0743605 0.459032 0.029349 0.0744682 0.459142 0.0291053 0.0742336 0.459159 0.0294835 0.0746553 0.459279 0.0295121 0.0748613 0.458797 0.0297573 0.0752738 0.45855 0.0301953 0.0754412 0.458596 0.030017 0.0752726 0.458483 0.030195 0.0751701 0.458542 0.0300161 0.0751373 0.458336 0.029959 0.0749062 0.458693 0.0298535 0.0752028 0.458437 0.0297743 0.0748497 0.458316 0.0297007 0.0747817 0.458195 0.0296138 0.0747516 0.458387 0.029437 0.0746669 0.45853 0.0303193 0.0754451 0.458395 0.0301817 0.0750401 0.458251 0.0303676 0.0749354 0.458271 0.0301588 0.0749347 0.458101 0.0303632 0.0748665 0.458125 0.0301285 0.0748671 0.457944 0.0303616 0.074841 0.457973 0.0300944 0.0748424 0.457806 0.0297424 0.074868 0.458619 0.0300035 0.0754026 0.458454 0.0299971 0.07501 0.458633 0.0298521 0.0750731 0.458547 0.029826 0.0749507 0.458199 0.0299049 0.0748384 0.458059 0.0298414 0.0748117 0.459102 0.0274394 0.0750636 0.45825 0.0265785 0.0750909 0.458799 0.0272451 0.0753366 0.458668 0.0274494 0.0747777 0.458515 0.0271111 0.0750626 0.458602 0.0270945 0.0751819 0.458694 0.0271229 0.0754298 0.458524 0.0269361 0.075254 0.459048 0.0274308 0.0749598 0.458851 0.0272919 0.0752904 0.458706 0.0272354 0.0750892 0.458391 0.027869 0.0746507 0.458698 0.0277528 0.0745498 0.458184 0.0270137 0.0749589 0.458374 0.026583 0.0751961 0.458268 0.0267777 0.0750714 0.458319 0.0269709 0.0750278 0.45877 0.0272359 0.0752092 0.458622 0.0272605 0.0749754 0.458492 0.0276359 0.0746684 0.458836 0.0275559 0.0746621 0.459329 0.0274946 0.0748516 0.459373 0.0275095 0.0746656 0.458984 0.0274457 0.074853 0.459266 0.0275928 0.0744803 0.458911 0.0274875 0.074751 0.459126 0.0280744 0.0742391 0.458045 0.0270678 0.0749285 0.457694 0.02678 0.0750348 0.457926 0.0274151 0.0749007 0.45831 0.0274792 0.0747733 0.458415 0.027388 0.0748102 0.458522 0.0273126 0.0748792 0.458405 0.0271513 0.0749631 0.458389 0.0267664 0.0751756 0.458436 0.0269444 0.07513 0.458478 0.0267653 0.0753029 0.458462 0.0265885 0.0753256 0.458547 0.0267873 0.0755681 0.457948 0.0265745 0.0749971 0.457957 0.0238732 0.0751169 0.457963 0.0238732 0.0751172 0.458102 0.0265756 0.0750228 0.45811 0.0238744 0.0751447 0.458255 0.0238775 0.0752136 0.458512 0.0238941 0.0755848 0.46005 0.0280716 0.0736665 0.461775 0.0275 0.0731533 0.459151 0.0278594 0.0742822 0.45922 0.0276648 0.0744004 0.461519 0.0276626 0.0728317 0.459321 0.0275386 0.0745746 0.461644 0.0275381 0.0729885 0.461402 0.0280681 0.0726842 0.461434 0.0278549 0.0727245 0.463481 0.0278522 0.0708705 0.465298 0.0278506 0.068798 0.463579 0.0276613 0.0709663 0.465405 0.0276605 0.0688831 0.463722 0.0275378 0.0711057 0.465562 0.0275376 0.0690066 0.463555 0.0275 0.0715709 0.467376 0.0275 0.0668419 0.467035 0.02766 0.0666177 0.466921 0.0278495 0.0665423 0.466876 0.0280605 0.0665129 0.465256 0.028062 0.0687651 0.458774 0.0232601 0.0754392 0.458992 0.0230475 0.0751249 0.459323 0.022957 0.0748842 0.458769 0.023096 0.0751134 0.459152 0.0229861 0.0750082 0.459263 0.023015 0.0752209 0.458637 0.0232194 0.0751942 0.458716 0.0232529 0.0753133 0.458433 0.0230759 0.0750246 0.458327 0.0229792 0.0749897 0.458714 0.0227069 0.0748118 0.458778 0.0228216 0.0748531 0.458532 0.0237995 0.0757191 0.458581 0.0235912 0.0756999 0.458683 0.023026 0.0750166 0.458539 0.0231589 0.0750944 0.458845 0.0231372 0.0752275 0.457693 0.0238753 0.0751637 0.457989 0.0236241 0.0751174 0.458276 0.0226747 0.0749631 0.458176 0.0231686 0.0750525 0.458061 0.023387 0.0750956 0.458279 0.0236806 0.075216 0.459032 0.0228502 0.0748152 0.459225 0.0228134 0.0746966 0.458849 0.022922 0.0749228 0.458422 0.0233156 0.0751544 0.458334 0.0234921 0.0751954 0.458448 0.0235272 0.0752995 0.458376 0.0238822 0.0753186 0.458532 0.023546 0.0754259 0.458582 0.0235491 0.07556 0.458463 0.023888 0.0754472 0.467814 0.0274143 0.0654054 0.467727 0.0276487 0.0652444 0.468269 0.026715 0.0645782 0.468237 0.0268614 0.0646332 0.468143 0.0270706 0.0648552 0.467642 0.0274598 0.06616 0.468087 0.0272247 0.0647336 0.468275 0.0270385 0.0643582 0.468099 0.0271547 0.0648125 0.46835 0.0266814 0.0642823 0.467321 0.0279899 0.0658275 0.46773 0.027782 0.0651865 0.468052 0.027465 0.0646841 0.467755 0.0275221 0.0653195 0.467397 0.0276546 0.0659639 0.467507 0.0275305 0.0660595 0.467353 0.0275473 0.0663913 0.467202 0.0275375 0.0667271 0.46751 0.0274899 0.0664993 0.461581 0.0228126 0.0732085 0.463836 0.022956 0.0715462 0.460134 0.023 0.0746893 0.461707 0.0229564 0.0733777 0.467136 0.0225877 0.0669824 0.465477 0.0225884 0.0692281 0.465919 0.023 0.0695878 0.467421 0.0229557 0.0671744 0.467325 0.0228928 0.0671096 0.461502 0.0225939 0.0731024 0.463596 0.0225902 0.0713009 0.463688 0.0228108 0.071395 0.459164 0.0226001 0.0745808 0.465579 0.0228099 0.0693112 0.465744 0.0229558 0.0694451 0.459226 0.0228157 0.0746985 0.468388 0.0253328 0.0645935 0.468292 0.0266774 0.0644243 0.468278 0.0266767 0.0644999 0.468273 0.0266768 0.0645761 0.468571 0.023993 0.0643423 0.468577 0.023678 0.0643846 0.468389 0.0233564 0.0648484 0.467909 0.0230517 0.0665233 0.468143 0.0231673 0.0656896 0.468187 0.0232111 0.065735 0.467705 0.0229001 0.0663646 0.467766 0.0229666 0.0664168 0.467113 0.0223531 0.0669666 0.467245 0.0228096 0.0670559 0.467601 0.0226323 0.0662415 0.468061 0.022703 0.0654278 0.468469 0.0232609 0.0646451 0.468039 0.0228479 0.0654808 0.468523 0.0239899 0.0644679 0.468501 0.0236446 0.0645767 0.468506 0.0238495 0.0646505 0.468503 0.0239889 0.0646196 0.467793 0.0230191 0.0668305 0.467515 0.0229891 0.0672372 0.467836 0.0230173 0.0664705 0.468259 0.0232493 0.0652713 0.468474 0.0236563 0.064799 0.468393 0.0234346 0.0649278 0.468105 0.0231152 0.0656438 0.468053 0.0229902 0.0655558 0.467656 0.0228198 0.0663165 0.446427 0.0156 0.076735 0.445227 0.0141 0.0768154 0.445388 0.0147 0.0768154 0.445578 0.0145902 0.077035 0.445647 0.01455 0.077335 0.445827 0.0151392 0.0768154 0.446427 0.0151757 0.0769108 0.445937 0.014949 0.077035 0.446427 0.0150803 0.077035 0.445977 0.0148794 0.077335 0.445527 0.0114 0.077335 0.445446 0.0114 0.077035 0.445446 0.0141 0.077035 0.445227 0.0114 0.0768154 0.444927 0.0114 0.076735 0.446427 0.015 0.077335 0.446427 0.0153 0.0768154 0.446827 0.0153703 0.0767807 0.446427 0.0104196 0.077035 0.445968 0.0102913 0.0768154 0.445318 0.0109407 0.0768154 0.446052 0.0104942 0.077035 0.445578 0.0105514 0.0768154 0.446427 0.0105 0.077335 0.445734 0.0107067 0.077035 0.44579 0.0107636 0.077335 0.445595 0.0110555 0.077335 0.445521 0.0110248 0.077035 0.446827 0.015 0.077335 0.446827 0.0150456 0.0771054 0.451222 0.0151732 0.0768392 0.446827 0.0151757 0.0769108 0.455627 0.015 0.0766925 0.451246 0.015 0.0772603 0.451233 0.0150404 0.077044 0.455536 0.01517 0.076284 0.451215 0.0153769 0.0767041 0.455496 0.0155896 0.0761069 0.446827 0.0105 0.077335 0.446827 0.0104196 0.077035 0.446827 0.0103242 0.0769108 0.446427 0.0102 0.0768154 0.446827 0.0102 0.0768154 0.446827 0.00989996 0.076735 0.456257 0.0147887 0.0762463 0.456259 0.0147409 0.0764381 0.455944 0.0151077 0.0761696 0.456391 0.0145761 0.0763823 0.455506 0.0153703 0.0761514 0.45652 0.0142086 0.0763337 0.456556 0.0140954 0.0761509 0.4558 0.014983 0.0766263 0.456072 0.0148823 0.0765169 0.455939 0.0149843 0.0763578 0.456477 0.0144767 0.0761699 0.456556 0.0145273 0.0759944 0.456787 0.0140878 0.0758404 0.45558 0.0150397 0.0764828 0.455761 0.0150306 0.0764186 0.456305 0.0148843 0.0760657 0.456399 0.0150146 0.0759308 0.455984 0.0152846 0.0760363 0.451215 0.0101202 0.0767131 0.455544 0.0103216 0.0763616 0.451221 0.0103239 0.0768465 0.455563 0.0104007 0.0764561 0.45123 0.0104578 0.0770498 0.455606 0.0104898 0.0766726 0.455627 0.0105 0.0767805 0.451213 0.00989908 0.0766713 0.456527 0.0114 0.0763969 0.456556 0.011396 0.0762112 0.456648 0.0113923 0.0760354 0.456646 0.0140911 0.0759765 0.456963 0.0113877 0.0758199 0.456476 0.011018 0.0762522 0.456792 0.0113894 0.0758991 0.455943 0.0105151 0.0764508 0.456257 0.0107093 0.07634 0.456164 0.0106776 0.0765794 0.455932 0.0105534 0.0766726 0.456408 0.0104696 0.0760207 0.455997 0.0102017 0.0761254 0.456308 0.0106073 0.0761554 0.455943 0.0104596 0.0763496 0.455953 0.0105509 0.0765556 0.455584 0.0104572 0.0765623 0.455952 0.0103862 0.0762583 0.455519 0.0101153 0.076231 0.456253 0.0107414 0.0764394 0.456557 0.0109599 0.0760737 0.456951 0.0111936 0.0758274 0.468632 0.015282 0.0653648 0.469167 0.0141402 0.0646231 0.468263 0.0154809 0.0659608 0.467802 0.0153563 0.0667794 0.469182 0.0141401 0.0645488 0.469176 0.0145016 0.0644846 0.46899 0.0147054 0.0648728 0.468974 0.0149274 0.0648058 0.468626 0.0151475 0.0654218 0.468394 0.0150314 0.0662758 0.467917 0.0151633 0.0668538 0.468262 0.015 0.0670775 0.468085 0.0150382 0.0669629 0.469001 0.0146348 0.0649505 0.469029 0.0145729 0.0650294 0.468712 0.014909 0.0655809 0.468234 0.0150485 0.0666268 0.469151 0.0142497 0.0647167 0.468653 0.0150191 0.0654959 0.468283 0.0151584 0.0661808 0.459381 0.0150096 0.075312 0.462093 0.015 0.073837 0.466085 0.0153556 0.0691851 0.466045 0.0155691 0.0691533 0.466848 0.015 0.0690951 0.46635 0.0150381 0.0693943 0.466192 0.0151629 0.06927 0.45925 0.0151659 0.0750341 0.45929 0.0150935 0.0751178 0.459336 0.0150388 0.0752167 0.466515 0.015 0.069525 0.46197 0.0150383 0.0736654 0.464302 0.0150381 0.0716906 0.464161 0.0151629 0.0715479 0.464065 0.0153556 0.0714504 0.461853 0.0151638 0.0735022 0.461773 0.0153574 0.0733911 0.46935 0.0114341 0.0644385 0.459096 0.014937 0.0756604 0.458864 0.0150608 0.0752466 0.458274 0.0140856 0.0755862 0.45829 0.014286 0.07557 0.458689 0.0146156 0.0759508 0.458531 0.0146191 0.0755863 0.458451 0.0144525 0.0756387 0.458531 0.0144407 0.0757605 0.458483 0.0142696 0.0757976 0.458862 0.0148009 0.0758292 0.459051 0.0149313 0.0755535 0.458771 0.0147352 0.0757528 0.458996 0.0149486 0.0754436 0.458716 0.0147395 0.0756323 0.458735 0.0152558 0.0751285 0.458529 0.015138 0.0752238 0.457958 0.0148956 0.0754017 0.458138 0.0140835 0.0755141 0.458217 0.0145209 0.0754643 0.458085 0.0145713 0.0754275 0.457993 0.0140825 0.0754793 0.458609 0.0145991 0.0757048 0.458932 0.0149919 0.0753385 0.45864 0.0147677 0.0755178 0.458549 0.0148202 0.0754199 0.458695 0.0149553 0.0753395 0.459427 0.015 0.0754088 0.459192 0.0153618 0.0749106 0.458347 0.0149814 0.0753067 0.458448 0.0148938 0.0753479 0.45843 0.01466 0.0754859 0.458343 0.0144798 0.0755364 0.458402 0.0142736 0.0756736 0.458546 0.0142833 0.0760552 0.458527 0.0141 0.0760754 0.468727 0.010571 0.0664187 0.469276 0.0114342 0.0647265 0.469165 0.0109651 0.0651221 0.469243 0.0111303 0.0647727 0.468465 0.0104039 0.0664318 0.468414 0.0103272 0.0663852 0.469281 0.0114336 0.0646519 0.469295 0.0114334 0.0645779 0.469129 0.0108186 0.0649654 0.469206 0.0107299 0.0647537 0.468689 0.0105558 0.0665255 0.467874 0.00987843 0.0670298 0.467904 0.0101051 0.0670493 0.468354 0.0101472 0.0663114 0.468015 0.0103165 0.0671212 0.468891 0.0106528 0.0657781 0.468526 0.0104672 0.066482 0.468595 0.0105155 0.0665337 0.468852 0.010603 0.0657335 0.469138 0.0108961 0.0650431 0.468796 0.0104827 0.0656479 0.468775 0.0103444 0.0655743 0.457728 0.0140834 0.0755094 0.458 0.0113849 0.075554 0.458277 0.0113876 0.0756624 0.458389 0.0113903 0.0757665 0.458387 0.0140887 0.0756904 0.458468 0.0113934 0.0758909 0.458468 0.0140923 0.0758155 0.458527 0.0114 0.0761494 0.466103 0.00987735 0.0694933 0.466131 0.0101043 0.0695154 0.466234 0.0103162 0.0695979 0.468096 0.0103979 0.0671741 0.468188 0.0104561 0.0672337 0.468284 0.0104896 0.0672958 0.468377 0.0105 0.0673563 0.464337 0.010456 0.0719976 0.466395 0.010456 0.069727 0.464493 0.0105 0.0721599 0.461988 0.0104561 0.0739275 0.464193 0.0103161 0.0718487 0.464101 0.0101041 0.0717537 0.462115 0.0105 0.0741129 0.459337 0.0104565 0.0754079 0.459254 0.0103184 0.0752194 0.461871 0.0103167 0.0737574 0.459201 0.0101088 0.0750981 0.459186 0.00988352 0.0750639 0.461796 0.0101054 0.0736486 0.461776 0.00987883 0.0736191 0.458774 0.0107616 0.0758963 0.458804 0.0107507 0.0760162 0.458584 0.0110848 0.0761305 0.4586 0.0110441 0.0761229 0.458723 0.0107521 0.0757724 0.458651 0.0107183 0.0756547 0.458458 0.011029 0.0757444 0.458536 0.0110474 0.0758674 0.457736 0.0113856 0.0755807 0.458025 0.0111359 0.0755517 0.459059 0.010353 0.0753195 0.458513 0.0113967 0.0760224 0.458582 0.0110516 0.0759974 0.459002 0.0105463 0.0756143 0.458853 0.0106357 0.0757002 0.458096 0.0108988 0.0755319 0.458209 0.0106801 0.075495 0.457895 0.0107059 0.0755438 0.458339 0.0101692 0.0753987 0.45836 0.0104902 0.0754422 0.458748 0.0102161 0.0752931 0.458809 0.0103268 0.075338 0.458297 0.0111875 0.0756602 0.458442 0.0108177 0.0756056 0.458352 0.0109961 0.0756412 0.458461 0.0105815 0.0754823 0.458561 0.0106601 0.0755548 0.458707 0.0105268 0.0754889 0.458875 0.0104236 0.0754101 0.459096 0.0105631 0.0758402 0.459165 0.0104857 0.0755159 0.468526 0.00866041 0.0662927 0.46923 0.00840389 0.0648679 0.469036 0.00832208 0.0657688 0.469228 0.0082051 0.0649612 0.469417 0.00762265 0.0646139 0.469403 0.00762286 0.0646875 0.469256 0.00808619 0.0651479 0.468461 0.0088287 0.0662187 0.469397 0.00766061 0.0647636 0.469239 0.00813242 0.0650383 0.468639 0.0084891 0.0668511 0.468477 0.00854933 0.0667435 0.468638 0.00853099 0.0663871 0.468895 0.00851862 0.0655973 0.468953 0.0084065 0.0656817 0.46832 0.00853898 0.067103 0.468317 0.00854049 0.0671009 0.46815 0.00866668 0.0669939 0.468869 0.00864898 0.0655239 0.468876 0.00878481 0.0654677 0.466514 0.0085389 0.0696447 0.463462 0.00849996 0.0731262 0.464441 0.00853887 0.0719555 0.466781 0.00849996 0.0696498 0.459342 0.00853933 0.0754404 0.459207 0.00886669 0.0751294 0.463795 0.00907864 0.0720349 0.464171 0.00907856 0.0716782 0.464205 0.00886238 0.071713 0.466249 0.00886264 0.0694347 0.461854 0.00886346 0.073658 0.466356 0.0086663 0.0695194 0.468035 0.00886342 0.0669202 0.459298 0.00859479 0.0753395 0.461931 0.0086667 0.0737702 0.462046 0.00853899 0.0739366 0.4643 0.00866618 0.0718108 0.469461 0.00491493 0.0647054 0.469475 0.00491486 0.0646316 0.458543 0.00864303 0.0754148 0.45861 0.00797753 0.0761756 0.459384 0.0085097 0.0755377 0.459053 0.00843183 0.0757593 0.459188 0.00908458 0.0750863 0.458007 0.00758915 0.075638 0.458099 0.00807651 0.0755952 0.459427 0.00849996 0.0756365 0.45924 0.0084802 0.0757689 0.458648 0.00827201 0.0757028 0.45872 0.00824215 0.0758179 0.458352 0.00798578 0.075707 0.458533 0.00794371 0.0759304 0.458613 0.00810203 0.075882 0.458688 0.00811319 0.0761275 0.458771 0.00823556 0.0759387 0.458866 0.00830401 0.076016 0.458338 0.00879965 0.0754329 0.458749 0.00876103 0.0753287 0.458875 0.00856476 0.0754483 0.457983 0.00841482 0.0755665 0.458361 0.00848629 0.075489 0.458229 0.00802687 0.0756339 0.458461 0.00839927 0.0755314 0.458559 0.00832556 0.0756043 0.458706 0.00846005 0.0755323 0.459261 0.00866825 0.0752542 0.45894 0.00849483 0.0755415 0.459001 0.00845038 0.075648 0.45844 0.00816572 0.0756629 0.458149 0.00758983 0.0756751 0.458298 0.00779189 0.0757356 0.458469 0.00759529 0.0759757 0.458485 0.00777265 0.0759618 0.458546 0.00778193 0.0762169 0.468619 0.00400212 0.0672091 0.468838 0.0040452 0.0666198 0.468373 0.00395881 0.067255 0.468199 0.00382364 0.0671436 0.468086 0.00361656 0.0670709 0.469529 0.00491516 0.0644942 0.469456 0.00491517 0.0647797 0.468583 0.00382818 0.066422 0.468634 0.00390376 0.0664682 0.468464 0.00398964 0.0673131 0.468765 0.00401334 0.0665693 0.468696 0.00396607 0.0665181 0.469062 0.0041473 0.0658136 0.469023 0.00409836 0.0657694 0.469313 0.00438961 0.0650807 0.469174 0.00424536 0.0656601 0.46852 0.00365017 0.0663486 0.468943 0.00384298 0.065611 0.468965 0.00397972 0.0656842 0.469303 0.00431372 0.0650033 0.469421 0.00462503 0.0648147 0.458011 0.00489267 0.0756797 0.458281 0.00759115 0.0757482 0.458283 0.00489403 0.0757908 0.462088 0.00395877 0.0740658 0.461552 0.00399996 0.0746698 0.46221 0.00399996 0.0742467 0.464509 0.00395873 0.0720829 0.466336 0.00361612 0.0695378 0.466442 0.00382343 0.0696213 0.466604 0.00395876 0.0697492 0.466305 0.00339164 0.0695129 0.464272 0.00361586 0.0718379 0.461874 0.00339174 0.07375 0.461896 0.00361619 0.0737833 0.459212 0.00361752 0.0752342 0.468277 0.00389933 0.0671933 0.464365 0.0038233 0.0719345 0.461972 0.00382346 0.0738948 0.459264 0.00382411 0.0753587 0.458219 0.00418737 0.0756163 0.458951 0.00413575 0.0760532 0.459005 0.0040465 0.075743 0.459343 0.00395891 0.0755492 0.458714 0.00402938 0.0756155 0.458654 0.00421973 0.0757791 0.458566 0.00416301 0.0756795 0.458447 0.00432112 0.0757296 0.458582 0.00455285 0.0761184 0.4586 0.00454497 0.0762426 0.458773 0.0042623 0.0760185 0.45879 0.00426416 0.0761442 0.458392 0.0048953 0.0758945 0.457749 0.00489292 0.0757006 0.458369 0.00399734 0.0755645 0.459169 0.00398604 0.0756486 0.458982 0.00341033 0.0752835 0.458581 0.00459287 0.0762517 0.458513 0.00489841 0.0761479 0.458469 0.00489682 0.0760178 0.458536 0.00454926 0.07599 0.458724 0.00425276 0.0758958 0.458855 0.00413608 0.0758258 0.458882 0.00392618 0.0755394 0.458302 0.00469282 0.0757859 0.458035 0.00464349 0.0756746 0.458105 0.00440625 0.0756534 0.458356 0.00367387 0.0755147 0.458757 0.00372299 0.0754203 0.458817 0.00383144 0.0754666 0.458357 0.0045004 0.0757654 0.458461 0.00453188 0.0758682 0.458469 0.00408649 0.0756063 0.459067 0.00385596 0.0754524 0.445227 0.00759996 0.0768154 0.445388 0.00819996 0.0768154 0.445827 0.00863919 0.0768154 0.445578 0.00809015 0.077035 0.445647 0.00804996 0.077335 0.445937 0.008449 0.077035 0.446427 0.00858034 0.077035 0.445977 0.00837938 0.077335 0.446427 0.00849996 0.077335 0.445481 0.00489996 0.0771054 0.445446 0.00759996 0.077035 0.445351 0.00759996 0.0769108 0.444927 0.00759996 0.076735 0.446827 0.00849996 0.077335 0.446427 0.00867569 0.0769108 0.446827 0.00867569 0.0769108 0.446427 0.00879996 0.0768154 0.446427 0.00909996 0.076735 0.446427 0.00369996 0.0768154 0.445889 0.00396834 0.0769108 0.446427 0.00391957 0.077035 0.446427 0.00382422 0.0769108 0.445954 0.00408098 0.0771054 0.446427 0.00399996 0.077335 0.445677 0.00360092 0.076735 0.445792 0.00379977 0.0767807 0.445327 0.00426476 0.0767807 0.445608 0.00442712 0.0771054 0.445977 0.00412054 0.077335 0.445495 0.00436209 0.0769108 0.445156 0.00489996 0.0767807 0.445351 0.00489996 0.0769108 0.455513 0.00909292 0.0762014 0.446827 0.00854563 0.0771054 0.451215 0.00887718 0.0767152 0.446827 0.00887035 0.0767807 0.446827 0.00909996 0.076735 0.455586 0.00853998 0.0765788 0.451241 0.00849996 0.0772717 0.45123 0.00854046 0.0770553 0.451221 0.0086733 0.0768503 0.451314 0.00909907 0.0766678 0.451213 0.00909914 0.0766724 0.446427 0.00395429 0.0771054 0.446827 0.00369996 0.0768154 0.456562 0.00802754 0.0761204 0.456259 0.00824053 0.076565 0.456971 0.00759113 0.0758872 0.455801 0.00848293 0.0767324 0.456386 0.0080828 0.0765157 0.45626 0.00828656 0.0763691 0.455701 0.0090799 0.0761641 0.455999 0.00878591 0.076144 0.455521 0.00887269 0.0762452 0.456557 0.00759708 0.0762778 0.45652 0.00770848 0.0764668 0.45647 0.00791428 0.0764837 0.456479 0.00797576 0.0762992 0.456066 0.00838562 0.0766381 0.456313 0.00838291 0.0761854 0.456652 0.00759436 0.0760995 0.455547 0.00867114 0.0763784 0.455767 0.00853001 0.0765222 0.455945 0.0084829 0.0764686 0.455955 0.00860698 0.0762778 0.456413 0.00851535 0.0760501 0.456538 0.00865766 0.0759823 0.455528 0.00361869 0.0762892 0.451215 0.00362057 0.07672 0.455552 0.00382319 0.0764205 0.45122 0.0038241 0.0768534 0.446827 0.00391957 0.077035 0.451229 0.0039578 0.0770567 0.446827 0.00382422 0.0769108 0.456654 0.00489616 0.0761322 0.456974 0.00624257 0.0759054 0.456801 0.00759228 0.0759629 0.456964 0.00470027 0.0759256 0.455588 0.0039576 0.0766212 0.455948 0.00401683 0.0765202 0.456316 0.00411249 0.0762352 0.45619 0.00356345 0.0761168 0.456419 0.00397595 0.0761 0.455955 0.00405181 0.0766253 0.455608 0.00398989 0.0767314 0.456255 0.00424322 0.0765214 0.456478 0.00452149 0.0763449 0.456558 0.004898 0.0763113 0.456007 0.00370656 0.0761936 0.455959 0.00388973 0.076327 0.456804 0.00489475 0.0759955 0.456563 0.0044656 0.0761644 0.456261 0.0042124 0.0764211 0.445446 -0.00490004 0.077035 0.445388 -0.00430004 0.0768154 0.445578 -0.00440985 0.077035 0.445647 -0.00445004 0.077335 0.446427 -0.00370004 0.0768154 0.446427 -0.00382431 0.0769108 0.445827 -0.00386081 0.0768154 0.446427 -0.00391966 0.077035 0.445937 -0.004051 0.077035 0.445977 -0.00412062 0.077335 0.445527 -0.00760004 0.077335 0.445446 -0.00760004 0.077035 0.445227 -0.00490004 0.0768154 0.445227 -0.00760004 0.0768154 0.446827 -0.00382431 0.0769108 0.446427 -0.00340004 0.076735 0.446427 -0.00858043 0.077035 0.445937 -0.00844908 0.077035 0.446427 -0.00850004 0.077335 0.445128 -0.00835004 0.076735 0.445827 -0.00863927 0.0768154 0.445388 -0.00820004 0.0768154 0.445578 -0.00809023 0.077035 0.445647 -0.00805004 0.077335 0.451239 -0.00400004 0.0772774 0.455588 -0.00395925 0.0766251 0.446827 -0.00395437 0.0771054 0.446827 -0.00362965 0.0767807 0.451215 -0.00362198 0.0767205 0.451221 -0.00382629 0.0768556 0.455528 -0.00362011 0.0762897 0.451229 -0.00395945 0.0770607 0.455588 -0.00395768 0.0766212 0.446427 -0.00880004 0.0768154 0.446827 -0.00880004 0.0768154 0.456418 -0.00397547 0.0761002 0.456812 -0.00420236 0.0759686 0.456259 -0.0042597 0.0766203 0.455947 -0.00401663 0.0765204 0.455801 -0.00401716 0.0767849 0.455627 -0.00400004 0.0768392 0.45577 -0.00396946 0.0765718 0.456557 -0.0048981 0.0763125 0.455521 -0.00339712 0.0762486 0.455552 -0.00382539 0.0764226 0.456006 -0.00370624 0.0761938 0.456478 -0.00452083 0.076345 0.456521 -0.00479718 0.0765055 0.456457 -0.00455181 0.0765367 0.456562 -0.00446484 0.0761645 0.456652 -0.00489626 0.0761342 0.456112 -0.00409793 0.0764696 0.456261 -0.00421207 0.0764213 0.455959 -0.00388949 0.0763272 0.456315 -0.0041121 0.0762353 0.456352 -0.00366334 0.076081 0.451213 -0.00909922 0.0766724 0.455521 -0.00887409 0.0762447 0.45123 -0.0085421 0.0770513 0.45124 -0.00850004 0.0772718 0.455627 -0.00850004 0.0767904 0.446827 -0.00850004 0.077335 0.446827 -0.00858043 0.077035 0.446827 -0.00867578 0.0769108 0.451221 -0.00867549 0.0768482 0.451215 -0.00887859 0.0767147 0.456557 -0.00759718 0.0762789 0.456971 -0.00759121 0.0758872 0.456801 -0.00489486 0.0759975 0.456651 -0.00759448 0.0761014 0.456479 -0.00797509 0.0762991 0.456314 -0.0083825 0.0761853 0.455946 -0.0084827 0.0764683 0.456172 -0.00831602 0.0765983 0.456413 -0.00851485 0.0760499 0.456798 -0.0075924 0.0759648 0.456712 -0.00844441 0.075942 0.455776 -0.00848745 0.0767409 0.455932 -0.0084468 0.0766868 0.455969 -0.00843233 0.0766734 0.456259 -0.00824034 0.0765649 0.456261 -0.00828621 0.076369 0.455956 -0.00860674 0.0762776 0.455547 -0.0086733 0.0763763 0.456 -0.0087856 0.0761438 0.456184 -0.00892316 0.0760623 0.456562 -0.00802677 0.0761203 0.455954 -0.00844837 0.0765718 0.455585 -0.0085416 0.076575 0.455606 -0.00850993 0.0766839 0.445227 -0.0114 0.0768154 0.445388 -0.0108 0.0768154 0.445578 -0.0109098 0.077035 0.445527 -0.0114 0.077335 0.445937 -0.010551 0.077035 0.446427 -0.00990004 0.076735 0.446427 -0.0103243 0.0769108 0.445827 -0.0103608 0.0768154 0.445446 -0.0141 0.077035 0.445446 -0.0114 0.077035 0.445227 -0.0141 0.0768154 0.446427 -0.0104197 0.077035 0.446427 -0.0102 0.0768154 0.445677 -0.0153991 0.076735 0.445937 -0.0149491 0.077035 0.446427 -0.0150804 0.077035 0.445827 -0.0151393 0.0768154 0.445578 -0.0145902 0.077035 0.445977 -0.0148795 0.077335 0.445647 -0.01455 0.077335 0.445128 -0.01485 0.076735 0.445388 -0.0147 0.0768154 0.45509 -0.00989343 0.0762703 0.45123 -0.0104594 0.0770538 0.451221 -0.0103261 0.0768486 0.446827 -0.0104544 0.0771054 0.446827 -0.0103243 0.0769108 0.455627 -0.0105 0.0767805 0.455545 -0.0103238 0.0763637 0.451215 -0.0101216 0.0767136 0.446827 -0.0101297 0.0767807 0.446827 -0.00990004 0.076735 0.446427 -0.015 0.077335 0.446827 -0.0150804 0.077035 0.446827 -0.0151758 0.0769108 0.446827 -0.0153 0.0768154 0.446427 -0.0153 0.0768154 0.45575 -0.0103336 0.0763111 0.456108 -0.0105954 0.0763944 0.455943 -0.0105149 0.076451 0.455951 -0.010386 0.0762585 0.456792 -0.0113895 0.0758991 0.455511 -0.00989251 0.0761918 0.455703 -0.00990516 0.0761529 0.456534 -0.0103234 0.0759557 0.456802 -0.0106994 0.0758785 0.456257 -0.010709 0.0763401 0.456066 -0.0106146 0.07662 0.456476 -0.0110174 0.0762524 0.456408 -0.0104691 0.0760208 0.456557 -0.0109592 0.0760738 0.456308 -0.0106069 0.0761555 0.455996 -0.0102014 0.0761257 0.455519 -0.0101168 0.0762315 0.455765 -0.0104684 0.0765078 0.455585 -0.0104589 0.0765662 0.455801 -0.0105171 0.0767208 0.451213 -0.0155988 0.0766612 0.451215 -0.0153783 0.0767036 0.455506 -0.0153717 0.0761509 0.446827 -0.015 0.077335 0.451233 -0.0150421 0.07704 0.451222 -0.0151753 0.0768371 0.456556 -0.0140955 0.0761509 0.456556 -0.0113961 0.0762112 0.456648 -0.0113924 0.0760354 0.456646 -0.0140912 0.0759765 0.455951 -0.0149495 0.0764594 0.456181 -0.0148089 0.0764709 0.456477 -0.014476 0.0761698 0.456556 -0.0145266 0.0759943 0.455945 -0.0151074 0.0761693 0.456787 -0.0140879 0.0758404 0.456955 -0.0140859 0.0757601 0.456262 -0.0147375 0.0764367 0.456257 -0.0147883 0.0762461 0.455535 -0.0151721 0.076282 0.455985 -0.0152843 0.076036 0.45617 -0.0154173 0.075948 0.456399 -0.0150141 0.0759306 0.456305 -0.0148839 0.0760656 0.455579 -0.0150413 0.076479 0.45594 -0.0149841 0.0763575 0.455603 -0.0150099 0.0765869 0.455793 -0.0149845 0.0766293 0.458487 -0.00472032 0.0760125 0.45861 -0.0045224 0.0762377 0.458536 -0.00455009 0.0759901 0.459054 -0.00406727 0.0758573 0.459343 -0.00395899 0.0755492 0.459212 -0.0036176 0.0752342 0.45776 -0.00471291 0.0756995 0.458152 -0.00489321 0.0757174 0.458653 -0.00422044 0.0757794 0.458302 -0.00469423 0.075786 0.458616 -0.00439265 0.075951 0.458508 -0.00357574 0.0754618 0.45855 -0.00384153 0.075499 0.458756 -0.00372347 0.0754207 0.458105 -0.00440737 0.0756535 0.458368 -0.00399823 0.0755648 0.458566 -0.00416377 0.0756798 0.458468 -0.00408731 0.0756066 0.458712 -0.00403039 0.075616 0.458881 -0.00392662 0.0755398 0.458945 -0.00399983 0.0756345 0.458773 -0.00426296 0.0760188 0.459004 -0.00404689 0.0757434 0.458723 -0.00425344 0.0758961 0.458235 -0.00445808 0.0756922 0.458446 -0.00432247 0.0757299 0.458357 -0.00450132 0.0757656 0.458469 -0.0048969 0.0760178 0.458545 -0.00471903 0.0762678 0.457749 -0.00489301 0.0757006 0.458011 -0.00489275 0.0756797 0.458391 -0.00759313 0.075852 0.458283 -0.00489411 0.0757908 0.458513 -0.00759775 0.0761063 0.458527 -0.00490004 0.0762737 0.458527 -0.00760004 0.0762325 0.461268 -0.00339213 0.0741403 0.461858 -0.00339183 0.0737602 0.459427 -0.00400004 0.0757506 0.459385 -0.00398991 0.0756492 0.46627 -0.00339171 0.0695566 0.466569 -0.00395883 0.0697936 0.468199 -0.00382371 0.0671441 0.468373 -0.00395888 0.0672555 0.466742 -0.00400004 0.069927 0.466302 -0.00361618 0.0695816 0.466407 -0.00382349 0.0696652 0.464338 -0.00382337 0.0719607 0.464634 -0.00400004 0.0722665 0.461881 -0.00361627 0.0737936 0.464245 -0.00361594 0.0718639 0.462072 -0.00395884 0.0740763 0.464482 -0.00395881 0.0721093 0.463434 -0.00400004 0.0733341 0.4593 -0.00390099 0.0754457 0.461956 -0.00382354 0.0739052 0.459264 -0.00382418 0.0753587 0.458099 -0.0080776 0.0755951 0.458352 -0.00798668 0.0757068 0.458942 -0.00835803 0.0759679 0.459001 -0.00845079 0.0756476 0.45856 -0.00832634 0.075604 0.458794 -0.0082398 0.0760617 0.458772 -0.00823622 0.0759384 0.45864 -0.00803751 0.0761567 0.4586 -0.00795644 0.0761815 0.458456 -0.00795825 0.0758091 0.45872 -0.00824284 0.0758175 0.458441 -0.00816705 0.0756626 0.457745 -0.00758965 0.0756609 0.458007 -0.00758923 0.075638 0.458281 -0.00759124 0.0757482 0.458362 -0.0084872 0.0754887 0.458462 -0.00840011 0.0755311 0.458811 -0.0086564 0.0753755 0.45897 -0.00906813 0.0751792 0.459259 -0.00848428 0.0757556 0.45875 -0.00876153 0.0753283 0.458581 -0.00794479 0.076058 0.458469 -0.00759537 0.0759757 0.458534 -0.00794452 0.0759302 0.458804 -0.00824927 0.0760556 0.458939 -0.00835658 0.0759694 0.458648 -0.00827273 0.0757025 0.458851 -0.00836037 0.0757387 0.45803 -0.00783964 0.0756248 0.457901 -0.00826991 0.0755968 0.458346 -0.00880533 0.0754302 0.458298 -0.00779335 0.0757355 0.458212 -0.00829693 0.0755492 0.458707 -0.00846103 0.0755318 0.458876 -0.00856522 0.0754479 0.459062 -0.00863613 0.0753539 0.459166 -0.0085119 0.0755459 0.459095 -0.00843665 0.0758672 0.469492 -0.00455693 0.0645745 0.468966 -0.00398117 0.0656858 0.468701 -0.00396757 0.0665104 0.468864 -0.00401688 0.066138 0.468588 -0.00383107 0.066415 0.469456 -0.00491471 0.0647797 0.468841 -0.00404629 0.0666114 0.469107 -0.00418808 0.0658581 0.469191 -0.00426173 0.065611 0.469023 -0.0040989 0.0657705 0.469456 -0.0048842 0.0647817 0.46931 -0.00438507 0.065089 0.469475 -0.00491422 0.0646324 0.468634 -0.00351384 0.0661079 0.468943 -0.00384537 0.0656128 0.468526 -0.00365489 0.0663415 0.468086 -0.00361663 0.0670714 0.468394 -0.00380937 0.0667799 0.468536 -0.00394794 0.0668822 0.468955 -0.00370545 0.0655578 0.469319 -0.00412048 0.0649036 0.469299 -0.00430897 0.065012 0.469337 -0.00445256 0.0651673 0.466245 -0.008864 0.0694387 0.468148 -0.00866879 0.0669927 0.468317 -0.00854057 0.0671009 0.468409 -0.0085097 0.0671601 0.464426 -0.00854045 0.0719651 0.466508 -0.00854048 0.0696468 0.466351 -0.0086684 0.0695225 0.464576 -0.00850004 0.0721203 0.464286 -0.00866828 0.0718216 0.461822 -0.00908015 0.073621 0.464192 -0.00886375 0.0717248 0.464159 -0.00907865 0.0716904 0.45934 -0.00854093 0.0754368 0.45926 -0.00867038 0.0752523 0.46204 -0.00854057 0.0739362 0.461926 -0.0086688 0.0737712 0.459206 -0.00886807 0.0751289 0.459188 -0.00908467 0.0750863 0.461849 -0.00886483 0.0736603 0.469461 -0.00491439 0.0647058 0.469403 -0.00762294 0.0646875 0.468705 -0.00848662 0.0664367 0.46924 -0.00813177 0.0650372 0.468895 -0.00851843 0.0655965 0.469228 -0.00820434 0.0649601 0.468461 -0.0088287 0.0662181 0.468035 -0.00886479 0.0669199 0.469417 -0.00762273 0.0646139 0.469386 -0.00775351 0.0647893 0.469037 -0.00832194 0.065768 0.468953 -0.00840635 0.0656808 0.469108 -0.00826311 0.0655686 0.468876 -0.00878451 0.0654668 0.468869 -0.00864874 0.065523 0.468526 -0.00866043 0.0662921 0.468638 -0.00853102 0.0663866 0.46881 -0.00844459 0.0663917 0.457982 -0.0105523 0.0755174 0.458359 -0.0104911 0.0754425 0.458441 -0.010819 0.0756059 0.458607 -0.0110285 0.0761196 0.45856 -0.0106609 0.075555 0.459382 -0.0104897 0.0755118 0.459054 -0.0105671 0.0757292 0.459001 -0.0105466 0.0756146 0.45894 -0.0104987 0.0755053 0.459186 -0.00988361 0.0750639 0.458747 -0.0102166 0.0752934 0.458 -0.011385 0.075554 0.458143 -0.0113859 0.0755899 0.45865 -0.010719 0.075655 0.458615 -0.0108915 0.0758286 0.458535 -0.0110483 0.0758676 0.458803 -0.0107513 0.0760166 0.458773 -0.0107623 0.0758966 0.458493 -0.0100688 0.0753432 0.459255 -0.0103206 0.0752213 0.457747 -0.0112053 0.0755815 0.458095 -0.0109 0.075532 0.458227 -0.0109522 0.0755687 0.45846 -0.0105824 0.0754825 0.458541 -0.0103346 0.0753747 0.458706 -0.0105278 0.0754894 0.458874 -0.010424 0.0754105 0.458722 -0.0107528 0.0757727 0.458352 -0.0109971 0.0756413 0.458277 -0.0113877 0.0756624 0.458297 -0.0111889 0.0756602 0.458486 -0.0112177 0.0758884 0.457993 -0.0140826 0.0754793 0.457736 -0.0113857 0.0755807 0.458274 -0.0140857 0.0755862 0.458387 -0.0140887 0.0756904 0.458468 -0.0140924 0.0758155 0.458468 -0.0113935 0.0758909 0.458513 -0.0140963 0.0759478 0.461995 -0.0104578 0.0739281 0.466788 -0.0105 0.0695938 0.461801 -0.0101068 0.0736463 0.462121 -0.0105 0.0741102 0.459338 -0.0104582 0.0754117 0.459293 -0.010399 0.0753081 0.466193 -0.00987747 0.0693809 0.467904 -0.0101065 0.0670495 0.466136 -0.0101057 0.0695103 0.466108 -0.00987743 0.0694879 0.464117 -0.0101055 0.0717392 0.464092 -0.00987716 0.0717134 0.461781 -0.00987884 0.0736164 0.459201 -0.0101103 0.0750985 0.461877 -0.0103189 0.0737564 0.46624 -0.0103184 0.0695938 0.46421 -0.0103183 0.0718352 0.464355 -0.0104577 0.0719853 0.466403 -0.0104577 0.0697242 0.468191 -0.0104578 0.0672359 0.458601 -0.0144586 0.0760131 0.458085 -0.0145724 0.0754273 0.458343 -0.0144807 0.0755362 0.458791 -0.0147373 0.0758793 0.459336 -0.0150389 0.0752167 0.459097 -0.0149374 0.0756599 0.458865 -0.0150612 0.0752462 0.458696 -0.0149561 0.0753391 0.45858 -0.0144443 0.0758888 0.458531 -0.0144415 0.0757603 0.458716 -0.0147402 0.0756319 0.458451 -0.0144533 0.0756385 0.458641 -0.0147684 0.0755174 0.458431 -0.0146612 0.0754856 0.45925 -0.015166 0.0750341 0.459052 -0.0151329 0.0751429 0.458529 -0.0141583 0.0760714 0.458806 -0.0147514 0.0758691 0.458771 -0.0147359 0.0757524 0.458925 -0.0148472 0.0757847 0.458846 -0.0148579 0.0755441 0.458736 -0.0152563 0.0751281 0.458348 -0.0149823 0.0753063 0.458321 -0.015294 0.0752477 0.458016 -0.0143338 0.0754624 0.45829 -0.0142875 0.0755699 0.458198 -0.0147919 0.0753747 0.45855 -0.0148211 0.0754195 0.458449 -0.0148947 0.0753475 0.458798 -0.0151517 0.0751747 0.458996 -0.014949 0.0754432 0.459161 -0.0150107 0.0753318 0.468667 -0.0105482 0.0665847 0.468526 -0.0104673 0.0664821 0.469152 -0.0109428 0.0651629 0.469243 -0.0111294 0.0647735 0.469129 -0.0108181 0.0649661 0.467874 -0.00987851 0.0670298 0.469138 -0.0108957 0.0650439 0.468936 -0.0106946 0.065822 0.468805 -0.0106083 0.0662004 0.468691 -0.0105185 0.0661054 0.468852 -0.0106032 0.0657334 0.468796 -0.0104828 0.0656477 0.468775 -0.0103446 0.0655741 0.468354 -0.0101472 0.0663114 0.468414 -0.0103273 0.0663853 0.468017 -0.0103188 0.0671223 0.468216 -0.0103043 0.0667544 0.468358 -0.0104467 0.0668583 0.468377 -0.0105 0.0673563 0.459192 -0.0153618 0.0749106 0.466349 -0.0150382 0.0693946 0.464409 -0.015 0.0718802 0.460681 -0.015 0.0747505 0.464029 -0.0155692 0.0714141 0.466085 -0.0153557 0.0691854 0.464065 -0.0153557 0.0714505 0.464161 -0.015163 0.071548 0.461773 -0.0153575 0.0733911 0.466192 -0.015163 0.0692703 0.464301 -0.0150382 0.0716908 0.461852 -0.0151639 0.0735023 0.46197 -0.0150384 0.0736655 0.469295 -0.0114335 0.0645779 0.469281 -0.0114337 0.0646519 0.469167 -0.0141414 0.0646226 0.469276 -0.0114343 0.0647265 0.467835 -0.0152829 0.066801 0.467759 -0.0155701 0.0667521 0.468631 -0.0151472 0.0654133 0.468991 -0.0147044 0.0648694 0.469237 -0.0141429 0.0644088 0.469002 -0.0146335 0.0649475 0.469091 -0.0144532 0.0648637 0.468715 -0.0149076 0.0655729 0.468797 -0.0148245 0.0656609 0.468018 -0.0150755 0.0669195 0.468399 -0.015031 0.0662631 0.468173 -0.0150096 0.0670199 0.468304 -0.0149991 0.0669698 0.468466 -0.0149872 0.0663136 0.468536 -0.0149577 0.0663634 0.469182 -0.0141414 0.0645479 0.467913 -0.0151672 0.066852 0.467917 -0.0151633 0.0668542 0.468288 -0.015159 0.0661678 0.468657 -0.0150182 0.0654876 0.468857 -0.0147766 0.0654979 0.46903 -0.0145714 0.0650269 0.445677 -0.022601 0.076735 0.445388 -0.0233 0.0768154 0.445156 -0.0239 0.0767807 0.444927 -0.0239 0.076735 0.445527 -0.0239 0.077335 0.445578 -0.0234098 0.077035 0.445351 -0.0239 0.0769108 0.445937 -0.023051 0.077035 0.445647 -0.02345 0.077335 0.445977 -0.0231206 0.077335 0.445827 -0.0228608 0.0768154 0.446427 -0.0228243 0.0769108 0.446427 -0.0229197 0.077035 0.445481 -0.0239 0.0771054 0.445446 -0.0239 0.077035 0.445481 -0.0266 0.0771054 0.445446 -0.0266 0.077035 0.445351 -0.0266 0.0769108 0.445227 -0.0239 0.0768154 0.446827 -0.0229544 0.0771054 0.446427 -0.0227 0.0768154 0.446427 -0.0224 0.076735 0.445156 -0.0266 0.0767807 0.446427 -0.0281 0.076735 0.445827 -0.0276393 0.0768154 0.445937 -0.0274491 0.077035 0.446427 -0.0275 0.077335 0.445677 -0.0278991 0.076735 0.445388 -0.0272 0.0768154 0.445227 -0.0266 0.0768154 0.445578 -0.0270902 0.077035 0.451225 -0.0228258 0.0768218 0.446827 -0.0228243 0.0769108 0.446827 -0.0226297 0.0767807 0.451254 -0.023 0.0772435 0.451239 -0.0229593 0.0770269 0.451216 -0.022621 0.076687 0.451213 -0.0223984 0.0766449 0.446427 -0.0275804 0.077035 0.446427 -0.0278 0.0768154 0.456469 -0.0235088 0.0759172 0.456095 -0.0230882 0.0761105 0.456767 -0.0232045 0.0755497 0.455656 -0.0223972 0.0759219 0.456315 -0.0226602 0.0757193 0.45649 -0.0228113 0.0756577 0.456527 -0.0239 0.0760326 0.456396 -0.0234325 0.0761391 0.456246 -0.0232001 0.0760375 0.456081 -0.0231233 0.0763283 0.455928 -0.0230097 0.0761864 0.456635 -0.0238872 0.0756897 0.456553 -0.0238935 0.075857 0.456764 -0.0238821 0.0755554 0.456372 -0.0229561 0.0757264 0.45654 -0.0234471 0.0757463 0.455959 -0.0226924 0.0758674 0.456285 -0.0230944 0.0758592 0.455924 -0.0228779 0.0759982 0.455483 -0.022612 0.0760088 0.455722 -0.0228283 0.0760689 0.455518 -0.0228215 0.0761386 0.455571 -0.0229584 0.0763391 0.455751 -0.0229656 0.0762623 0.455801 -0.023017 0.0764717 0.454234 -0.0280915 0.0761643 0.45123 -0.0276752 0.076804 0.451246 -0.027542 0.0770065 0.446827 -0.0275 0.077335 0.446827 -0.0275804 0.077035 0.446827 -0.0276758 0.0769108 0.446827 -0.0278 0.0768154 0.446827 -0.0281 0.076735 0.451219 -0.0278781 0.0766707 0.456631 -0.0265879 0.0755943 0.456913 -0.0252295 0.0754214 0.456919 -0.0238789 0.07547 0.456453 -0.0269578 0.0759597 0.456471 -0.0269821 0.075784 0.456527 -0.0266 0.0759322 0.456552 -0.0265939 0.0757593 0.456245 -0.0272648 0.0759788 0.455563 -0.0275412 0.0762024 0.456244 -0.0272967 0.0758872 0.455924 -0.027489 0.0760378 0.455914 -0.0276127 0.0758563 0.45628 -0.0273928 0.0757151 0.456359 -0.0275202 0.0755824 0.456466 -0.0276569 0.0755066 0.45666 -0.0274161 0.0754415 0.456896 -0.0267673 0.0753721 0.455504 -0.0276713 0.0760097 0.455941 -0.0277869 0.0757253 0.455465 -0.0278701 0.0758811 0.456756 -0.0265832 0.0754607 0.456538 -0.0270326 0.0756177 0.455941 -0.0274529 0.0761357 0.455913 -0.0274535 0.0762606 0.455595 -0.0275098 0.0763079 0.446427 -0.0294544 0.0771054 0.446427 -0.0293243 0.0769108 0.446827 -0.0294544 0.0771054 0.445439 -0.0296018 0.0767807 0.445963 -0.0294294 0.0769108 0.446427 -0.0291297 0.0767807 0.445879 -0.0292537 0.0767807 0.446019 -0.0295467 0.0771054 0.455562 -0.0294586 0.0761849 0.451265 -0.0294594 0.0770064 0.455461 -0.0291138 0.0758588 0.454206 -0.0288923 0.0761594 0.451233 -0.0288986 0.0766249 0.446827 -0.0293243 0.0769108 0.451247 -0.0293259 0.0768016 0.446827 -0.0291297 0.0767807 0.446827 -0.0289 0.076735 0.451236 -0.0291212 0.0766669 0.450923 -0.0288989 0.0766487 0.445539 -0.0300855 0.077114 0.445413 -0.0300408 0.0769106 0.445351 -0.0303985 0.0769097 0.445691 -0.0298058 0.0771054 0.44559 -0.0297241 0.0769108 0.445221 -0.0299728 0.076777 0.456062 -0.0295707 0.0759351 0.456238 -0.0295622 0.0756816 0.456284 -0.0294688 0.0755868 0.455912 -0.029184 0.0757034 0.455902 -0.0295014 0.0760176 0.456096 -0.0296323 0.0761266 0.455934 -0.0295542 0.0762249 0.455968 -0.0289866 0.075649 0.455887 -0.0293693 0.0758329 0.455695 -0.0293266 0.0759103 0.455501 -0.0293224 0.0759872 0.455733 -0.0294634 0.0761005 0.455791 -0.0295152 0.0763063 0.455627 -0.0295 0.0763943 0.444927 -0.0303979 0.0767339 0.445527 -0.0330992 0.0772527 0.444927 -0.0326361 0.0766902 0.445087 -0.0330676 0.0766908 0.445148 -0.0303981 0.0767761 0.445351 -0.0330763 0.0768444 0.445485 -0.0303993 0.0771131 0.456214 -0.0296402 0.0757958 0.456457 -0.0299864 0.0757077 0.456747 -0.0303734 0.075334 0.45663 -0.0298417 0.0754091 0.45677 -0.0297627 0.0753265 0.456349 -0.0298138 0.0757755 0.45652 -0.0299209 0.0755414 0.456447 -0.03003 0.0758826 0.445557 -0.0342614 0.0765761 0.445091 -0.0337357 0.0766237 0.446059 -0.0339623 0.0769476 0.446427 -0.034 0.0771432 0.445427 -0.0334822 0.0768132 0.445373 -0.0330776 0.0768674 0.445484 -0.0330876 0.0770462 0.445595 -0.0334443 0.0772303 0.445583 -0.0334411 0.0771231 0.44579 -0.0337359 0.077189 0.445552 -0.0334459 0.0770135 0.446238 -0.0345207 0.0765484 0.445516 -0.0339577 0.0766445 0.446427 -0.034331 0.0766069 0.446006 -0.0340679 0.0767537 0.445242 -0.0335489 0.0766789 0.445279 -0.0330728 0.0767827 0.445656 -0.0338309 0.07678 0.445752 -0.0337534 0.0769768 0.45655 -0.0330773 0.0753736 0.45655 -0.0303905 0.0756312 0.456626 -0.0303811 0.0754677 0.456884 -0.033024 0.0749928 0.446823 -0.0340354 0.0769404 0.446427 -0.0343429 0.0766011 0.446823 -0.0343298 0.0766077 0.446823 -0.0341506 0.0767459 0.446605 -0.034 0.0771432 0.446427 -0.0341507 0.0767456 0.446427 -0.0340307 0.0769539 0.456527 -0.0331 0.0755362 0.456623 -0.0330549 0.0752138 0.456439 -0.0340813 0.075022 0.455494 -0.0341421 0.0755419 0.455909 -0.0340839 0.07537 0.455923 -0.0339821 0.0755365 0.455559 -0.0340331 0.0757216 0.455939 -0.0339519 0.075625 0.45628 -0.0338604 0.0752392 0.456347 -0.0339641 0.0751086 0.456127 -0.0343151 0.0751111 0.455447 -0.0343081 0.0754137 0.455424 -0.034501 0.0753502 0.456453 -0.0334567 0.0755019 0.456249 -0.0337851 0.0753992 0.456475 -0.0334644 0.0753378 0.456538 -0.0334958 0.0751806 0.45674 -0.0330365 0.075082 0.453137 -0.034512 0.0760212 0.451253 -0.0340346 0.0767421 0.455495 -0.0341404 0.0755439 0.451215 -0.0343224 0.0764133 0.446824 -0.034 0.0771433 0.451231 -0.0341471 0.0765507 0.458813 -0.0272581 0.0753246 0.45825 -0.0265786 0.0750909 0.459219 -0.0276668 0.0743986 0.458836 -0.0275563 0.0746617 0.458668 -0.0274499 0.0747775 0.458757 -0.0273883 0.0748701 0.459263 -0.0274851 0.074914 0.458635 -0.0270285 0.0754831 0.458623 -0.0272615 0.0749747 0.458707 -0.0272363 0.0750885 0.458125 -0.0268001 0.0750026 0.457948 -0.0265746 0.0749971 0.457975 -0.0268283 0.0749744 0.459022 -0.0276297 0.0745343 0.458763 -0.0276472 0.0745932 0.458311 -0.0274805 0.0747726 0.458185 -0.027015 0.0749586 0.458698 -0.0277532 0.0745494 0.45886 -0.0280499 0.0743916 0.458255 -0.0277755 0.0747241 0.458159 -0.0272895 0.0748603 0.457825 -0.0272337 0.0749557 0.458046 -0.0270692 0.0749281 0.458582 -0.0269103 0.0755326 0.45858 -0.0269451 0.075385 0.458531 -0.0266846 0.0755873 0.458512 -0.0265945 0.0754644 0.458525 -0.0269371 0.0752536 0.458436 -0.0269455 0.0751297 0.458268 -0.026779 0.0750714 0.458836 -0.0273544 0.074978 0.458771 -0.0272368 0.0752085 0.458885 -0.0273191 0.0752599 0.459147 -0.0275088 0.0747158 0.458984 -0.0274461 0.0748526 0.458416 -0.0273892 0.0748096 0.458523 -0.0273137 0.0748785 0.458405 -0.0271527 0.0749627 0.458283 -0.027214 0.0748937 0.45832 -0.0269721 0.0750275 0.459126 -0.0280745 0.0742391 0.46692 -0.0278509 0.066542 0.465287 -0.0278519 0.0688101 0.467288 -0.0275094 0.0667841 0.465715 -0.0275 0.069149 0.465548 -0.0275391 0.0690168 0.463552 -0.0276634 0.070991 0.465393 -0.0276626 0.0688942 0.463455 -0.0278536 0.0708962 0.463418 -0.0280644 0.0708599 0.463846 -0.0275 0.0712788 0.461629 -0.0275396 0.0729957 0.463694 -0.0275393 0.0711295 0.461506 -0.0276647 0.0728402 0.459319 -0.0275401 0.0745713 0.459151 -0.0278608 0.0742817 0.460051 -0.0280717 0.0736666 0.461422 -0.0278563 0.0727341 0.457687 -0.0252261 0.0751057 0.458102 -0.0265757 0.0750228 0.45811 -0.0238745 0.0751447 0.458374 -0.0265831 0.0751961 0.458255 -0.0238776 0.0752136 0.458462 -0.0265886 0.0753256 0.468099 -0.0271548 0.0648126 0.468252 -0.0268079 0.0646044 0.467815 -0.0274139 0.0654034 0.467397 -0.0276546 0.0659628 0.467033 -0.027662 0.0666166 0.468087 -0.0272248 0.0647337 0.467728 -0.0276481 0.0652425 0.467756 -0.0275216 0.0653175 0.467508 -0.0275304 0.0660583 0.467198 -0.027539 0.066725 0.467573 -0.0274881 0.0661089 0.458279 -0.0236821 0.075216 0.457957 -0.0238733 0.0751169 0.459032 -0.0228504 0.0748153 0.458528 -0.0233657 0.075257 0.458531 -0.0235469 0.075426 0.45861 -0.0233916 0.0753804 0.459052 -0.0230671 0.0752392 0.458991 -0.0230477 0.0751251 0.458922 -0.0229993 0.0750164 0.459323 -0.0229572 0.0748843 0.458509 -0.0228239 0.0749088 0.458434 -0.022567 0.074895 0.458935 -0.0226316 0.0747014 0.458376 -0.0238823 0.0753186 0.4582 -0.0234446 0.0751258 0.459258 -0.0230161 0.0752248 0.458714 -0.0227071 0.074812 0.458849 -0.0229223 0.074923 0.458683 -0.0230263 0.0750167 0.458636 -0.0232202 0.0751946 0.458716 -0.0232537 0.0753137 0.458773 -0.0232608 0.0754397 0.45806 -0.0233882 0.0750958 0.457704 -0.0236988 0.0751669 0.457929 -0.0230597 0.0750993 0.458326 -0.0229802 0.0749901 0.458432 -0.0230769 0.0750249 0.458538 -0.0231597 0.0750948 0.458421 -0.023317 0.0751548 0.458333 -0.023493 0.0751955 0.458447 -0.0235281 0.0752996 0.458397 -0.0237023 0.075321 0.458482 -0.0237144 0.0754491 0.458463 -0.023888 0.0754472 0.468278 -0.0266768 0.0644999 0.468388 -0.0253328 0.0645935 0.46835 -0.0266815 0.0642824 0.46858 -0.0239937 0.0643261 0.468292 -0.0266775 0.0644243 0.468523 -0.0239897 0.0644679 0.459375 -0.0229895 0.0749823 0.46592 -0.023 0.069587 0.463526 -0.023 0.0721531 0.46558 -0.0228101 0.0693105 0.467137 -0.0225878 0.0669814 0.467246 -0.0228098 0.0670549 0.465745 -0.0229559 0.0694444 0.463596 -0.0225903 0.0713005 0.465478 -0.0225885 0.0692274 0.463688 -0.0228109 0.0713946 0.463837 -0.0229561 0.0715458 0.467422 -0.0229558 0.0671735 0.461707 -0.0229565 0.0733776 0.461502 -0.022594 0.0731022 0.461483 -0.0223615 0.0730773 0.459164 -0.0226003 0.0745808 0.459226 -0.0228158 0.0746986 0.461581 -0.0228127 0.0732083 0.45927 -0.0228963 0.074783 0.467601 -0.0226326 0.0662403 0.467785 -0.0225174 0.0659051 0.468054 -0.0231179 0.066124 0.46794 -0.0230232 0.0660258 0.468262 -0.023281 0.0655109 0.468154 -0.0231843 0.065834 0.468105 -0.0231155 0.0656431 0.468259 -0.023249 0.0652708 0.468447 -0.023575 0.0649005 0.468504 -0.0239889 0.0645951 0.468389 -0.0233558 0.0648494 0.4685 -0.023644 0.0645772 0.468502 -0.0237988 0.0646772 0.468505 -0.0239632 0.0646204 0.467758 -0.0230126 0.0669217 0.467767 -0.0229668 0.0664156 0.467589 -0.0229441 0.0668052 0.46857 -0.0236216 0.0644071 0.468425 -0.0231658 0.0647373 0.468053 -0.0229905 0.0655551 0.468039 -0.0228482 0.0654801 0.467447 -0.0227946 0.066697 0.468393 -0.023434 0.0649288 0.467657 -0.02282 0.0663154 0.45882 -0.0297154 0.0751024 0.458542 -0.0292942 0.0745755 0.458865 -0.0294113 0.0745802 0.45857 -0.0296085 0.0747626 0.45871 -0.029501 0.0746812 0.458732 -0.0291958 0.0744713 0.458864 -0.029698 0.0752208 0.458991 -0.0296126 0.0751159 0.458861 -0.0296997 0.0752138 0.459012 -0.0295365 0.0747762 0.458797 -0.0295721 0.0747753 0.458875 -0.0296135 0.0748862 0.459159 -0.0294836 0.0746553 0.459032 -0.0293491 0.0744682 0.45921 -0.0293183 0.0743489 0.458595 -0.0300179 0.0752729 0.458745 -0.0297063 0.0749619 0.458438 -0.0297749 0.0748496 0.458673 -0.0296754 0.0748637 0.458373 -0.0294214 0.074664 0.458633 -0.0298527 0.075073 0.458547 -0.0298266 0.0749506 0.458453 -0.029998 0.0750102 0.458316 -0.0297014 0.0747816 0.458195 -0.0296146 0.0747515 0.458059 -0.0298426 0.074812 0.458484 -0.030196 0.0751699 0.458395 -0.0301827 0.0750399 0.458376 -0.0303746 0.0750423 0.458271 -0.0301599 0.0749345 0.458251 -0.0303677 0.0749354 0.458125 -0.0301297 0.0748669 0.457973 -0.0300958 0.0748422 0.458101 -0.0303633 0.0748665 0.458199 -0.0299061 0.0748386 0.458335 -0.02996 0.0749064 0.458541 -0.030017 0.0751376 0.458693 -0.0298541 0.0752027 0.461645 -0.0295 0.0732053 0.461378 -0.0293164 0.0728659 0.459315 -0.0294577 0.0745291 0.459142 -0.0291054 0.0742336 0.461295 -0.0291016 0.0727613 0.461507 -0.0294573 0.0730305 0.463648 -0.0295 0.0714163 0.463489 -0.029457 0.0712589 0.463341 -0.0293152 0.0711107 0.463246 -0.0290992 0.071017 0.457669 -0.0303654 0.0748989 0.458094 -0.0330148 0.0745859 0.457944 -0.0303617 0.074841 0.458246 -0.0330249 0.0746532 0.458464 -0.030383 0.0751735 0.458527 -0.031753 0.0753262 0.467021 -0.0293131 0.0664059 0.466848 -0.029299 0.0667139 0.46714 -0.0294579 0.0665084 0.466957 -0.0291238 0.0663301 0.466565 -0.0290967 0.0669465 0.467369 -0.0295649 0.0664031 0.467289 -0.029537 0.0666169 0.46733 -0.0292681 0.0657094 0.466674 -0.029314 0.0670209 0.466993 -0.029445 0.0668231 0.466849 -0.0294567 0.0671392 0.467163 -0.0295094 0.0669409 0.459427 -0.034 0.0740099 0.458976 -0.0339368 0.0741822 0.458825 -0.0338419 0.0743437 0.458652 -0.0339132 0.0741615 0.458252 -0.0332253 0.0746012 0.458373 -0.0330407 0.0747593 0.458607 -0.0337344 0.0743888 0.458421 -0.0334076 0.0746219 0.458766 -0.033732 0.0746017 0.458105 -0.0332394 0.0745348 0.457935 -0.0330113 0.0745625 0.457954 -0.0332657 0.0745088 0.458397 -0.0338367 0.0742328 0.458751 -0.034099 0.0739444 0.458163 -0.0334567 0.0744572 0.458024 -0.0335073 0.0744267 0.457791 -0.0336394 0.0744566 0.458139 -0.0337267 0.0743204 0.458293 -0.0339176 0.0741932 0.458684 -0.0341897 0.0738979 0.459262 -0.033985 0.0741905 0.459321 -0.034032 0.0738478 0.459142 -0.0340012 0.0740151 0.458471 -0.0332394 0.0748277 0.458514 -0.0334138 0.0747401 0.458576 -0.0334373 0.0748653 0.458561 -0.0333473 0.0750615 0.458608 -0.0334728 0.074986 0.458463 -0.0330603 0.0748902 0.458378 -0.0332256 0.074703 0.458512 -0.0330802 0.0750234 0.458526 -0.0332635 0.0749603 0.458837 -0.0337801 0.0746827 0.458953 -0.0338651 0.0745441 0.458696 -0.0337212 0.0744926 0.458385 -0.033607 0.0744224 0.458825 -0.0340235 0.0740101 0.459015 -0.0340989 0.073852 0.458504 -0.0337736 0.0742995 0.4583 -0.033422 0.0745239 0.468003 -0.0301406 0.0643973 0.467916 -0.0301013 0.064612 0.467934 -0.0304051 0.0646315 0.467946 -0.0305153 0.0644625 0.467927 -0.0305118 0.0646146 0.467526 -0.0296467 0.0659726 0.467426 -0.0295533 0.065877 0.467615 -0.0296828 0.0654387 0.467814 -0.0299508 0.065111 0.467783 -0.029875 0.0650286 0.467773 -0.0297891 0.0649477 0.467384 -0.029487 0.0658265 0.467785 -0.0296979 0.0648732 0.467388 -0.029139 0.065585 0.467329 -0.0292395 0.0656982 0.467343 -0.0291092 0.06566 0.462968 -0.0344739 0.0702349 0.463022 -0.0342897 0.0702847 0.46607 -0.0344679 0.0662363 0.466248 -0.0341298 0.0663527 0.463123 -0.0341317 0.070379 0.463258 -0.0340312 0.0705047 0.4664 -0.0340311 0.0664525 0.463376 -0.034 0.0706576 0.461192 -0.0342932 0.0720434 0.461282 -0.0341333 0.0721486 0.461402 -0.0340315 0.0722893 0.461527 -0.034 0.072435 0.45922 -0.0341355 0.0736915 0.459144 -0.0342978 0.0735753 0.459106 -0.0344858 0.073516 0.461145 -0.0344791 0.0719887 0.46656 -0.034 0.066557 0.466561 -0.034 0.0665549 0.466342 -0.0340597 0.066414 0.466864 -0.0341291 0.0651451 0.466854 -0.0342434 0.0650838 0.466167 -0.0342267 0.0662996 0.467226 -0.0337639 0.0647249 0.467037 -0.0338639 0.065389 0.467439 -0.0332985 0.0646325 0.467458 -0.0333043 0.0644809 0.467394 -0.0334425 0.0646714 0.467283 -0.0336379 0.0648575 0.467242 -0.0337037 0.0648036 0.46696 -0.0339286 0.0653047 0.4669 -0.0340195 0.0652204 0.466673 -0.0340253 0.0658758 0.466565 -0.0341281 0.0657842 0.445412 -0.0447708 0.07232 0.445112 -0.0497828 0.0665918 0.444927 -0.0492122 0.067315 0.445112 -0.0465015 0.0704594 0.445279 -0.0498521 0.0666414 0.445279 -0.0465615 0.0705199 0.445527 -0.0502467 0.0669241 0.444927 -0.0464808 0.0704386 0.444927 -0.0448808 0.0719051 0.445112 -0.0446325 0.0721515 0.444927 -0.0425721 0.0736292 0.445279 -0.0446865 0.0722174 0.445412 -0.0466551 0.0706141 0.445351 -0.0426681 0.0737763 0.445497 -0.0467729 0.0707328 0.445497 -0.0448769 0.0724494 0.445485 -0.0427793 0.0739467 0.44539 -0.0424736 0.0739265 0.445112 -0.0425881 0.0736538 0.445279 -0.0426347 0.0737251 0.445255 -0.0421459 0.0739608 0.445995 -0.0416325 0.0743916 0.445717 -0.0416029 0.0742991 0.445799 -0.0417312 0.0743261 0.445625 -0.0418645 0.0742371 0.445464 -0.0422898 0.0740669 0.445367 -0.0422128 0.0740008 0.445659 -0.04243 0.0746196 0.445788 -0.0422449 0.0746371 0.445686 -0.0423895 0.0746595 0.445671 -0.0423037 0.0743943 0.445762 -0.0420847 0.0743994 0.445541 -0.0427395 0.0743036 0.445527 -0.0429 0.0741316 0.445517 -0.0426103 0.0741063 0.445497 -0.0427987 0.0739763 0.446078 -0.0420536 0.0748235 0.446057 -0.0420794 0.0749537 0.446028 -0.0420933 0.074941 0.445764 -0.0422911 0.074755 0.446427 -0.0419634 0.0748194 0.446253 -0.0419481 0.0747334 0.446085 -0.0419949 0.0746877 0.446249 -0.0420022 0.0748733 0.445936 -0.0414872 0.0743686 0.446044 -0.0417759 0.0744572 0.446427 -0.0415833 0.0744545 0.445789 -0.0421757 0.0745149 0.44558 -0.0424501 0.0742568 0.445636 -0.0422174 0.0742856 0.445148 -0.0425951 0.0736644 0.444963 -0.0422518 0.0738342 0.445526 -0.0417562 0.0742057 0.445792 -0.0412516 0.0744233 0.446427 -0.0411148 0.074498 0.446248 -0.0418542 0.0746022 0.446074 -0.0419008 0.0745603 0.445866 -0.0418609 0.074392 0.445706 -0.0419776 0.0743033 0.44557 -0.0421226 0.0741936 0.445536 -0.0423711 0.0741548 0.445412 -0.0427073 0.0738363 0.445516 -0.050669 0.0653762 0.445846 -0.0509983 0.0647861 0.445245 -0.0506659 0.065238 0.445773 -0.0508656 0.065394 0.445597 -0.050595 0.066086 0.445517 -0.0501579 0.0668605 0.445497 -0.050096 0.0668161 0.445412 -0.04996 0.0667187 0.446427 -0.0512313 0.0643245 0.445919 -0.0510051 0.0648692 0.44618 -0.0512111 0.0643583 0.445767 -0.0510813 0.0645736 0.444927 -0.0497589 0.0665747 0.445383 -0.0506504 0.0652973 0.445363 -0.0502927 0.0660254 0.445631 -0.0507214 0.0654677 0.445679 -0.0507585 0.0655152 0.445543 -0.0504647 0.0661831 0.445497 -0.0503993 0.0661283 0.445436 -0.050341 0.0660749 0.445189 -0.0502341 0.0659459 0.446427 -0.042 0.0750258 0.446427 -0.0419846 0.0748904 0.446831 -0.0417107 0.0745116 0.446427 -0.0418155 0.074593 0.446427 -0.0417073 0.0745105 0.446831 -0.0415837 0.0744537 0.446427 -0.0413138 0.0744321 0.446831 -0.0411147 0.0744976 0.446427 -0.0511521 0.0645516 0.447048 -0.0511682 0.0644722 0.446427 -0.0511683 0.0644721 0.446831 -0.0413922 0.0744249 0.449433 -0.0415552 0.0743595 0.446831 -0.0415544 0.0744451 0.446831 -0.042 0.0750249 0.446831 -0.0419349 0.074753 0.449453 -0.041935 0.0746667 0.446831 -0.041842 0.074619 0.449431 -0.0413933 0.0743392 0.452015 -0.0413949 0.0740257 0.449437 -0.0417112 0.074426 0.449444 -0.0418423 0.0745332 0.452076 -0.0419352 0.0743486 0.447049 -0.0511466 0.0646312 0.447429 -0.0511682 0.064471 0.447239 -0.0511466 0.0646309 0.44743 -0.0511466 0.0646303 0.453191 -0.0421518 0.0732731 0.453304 -0.0426211 0.0729275 0.452102 -0.0419846 0.0744823 0.452428 -0.0419821 0.0741708 0.452233 -0.0418451 0.0741505 0.452416 -0.0418861 0.0740553 0.452613 -0.0418487 0.0738423 0.452458 -0.0420466 0.0742931 0.452592 -0.0420571 0.0740406 0.452616 -0.0421271 0.0741538 0.453036 -0.0422935 0.0733846 0.452739 -0.042162 0.0738898 0.452754 -0.0422348 0.0739944 0.453481 -0.0425792 0.0728641 0.453245 -0.0417829 0.073433 0.452915 -0.041757 0.0735982 0.452839 -0.0418609 0.0736385 0.452952 -0.0425133 0.0736402 0.452965 -0.0425729 0.0737286 0.452284 -0.0419979 0.0744053 0.452646 -0.0412573 0.0738883 0.452506 -0.0414863 0.0738641 0.453098 -0.0427441 0.0731136 0.452986 -0.0423702 0.0734628 0.452959 -0.0424448 0.0735499 0.452253 -0.0419402 0.074274 0.452051 -0.0418427 0.0742172 0.452031 -0.0417121 0.0741117 0.452228 -0.0417168 0.0740501 0.452019 -0.0415565 0.0740461 0.452426 -0.0417636 0.0739595 0.452457 -0.0416257 0.0738942 0.45259 -0.0419625 0.0739332 0.452781 -0.0419685 0.0737038 0.452747 -0.0420715 0.0737901 0.452325 -0.0507488 0.0646775 0.449916 -0.0510821 0.0646198 0.449917 -0.0511036 0.0644603 0.453154 -0.0426966 0.0730417 0.453156 -0.0464426 0.0699616 0.453058 -0.04657 0.0700894 0.453058 -0.0427954 0.0731912 0.453034 -0.0428481 0.073271 0.453027 -0.0467051 0.0702249 0.453156 -0.0495677 0.0662583 0.453309 -0.0494561 0.0661789 0.453309 -0.0463459 0.0698646 0.45315 -0.0498941 0.0657221 0.45295 -0.0502806 0.0652937 0.453058 -0.0497149 0.066363 0.452338 -0.0507682 0.0645184 0.452458 -0.0507079 0.0647156 0.452785 -0.0505431 0.0647535 0.452886 -0.0503544 0.0653831 0.452952 -0.0502305 0.0656528 0.452994 -0.0501132 0.0659156 0.452723 -0.0506906 0.0644709 0.453489 -0.0493952 0.0661356 0.452725 -0.0505567 0.0648351 0.453039 -0.050225 0.0652066 0.45305 -0.0499949 0.0658169 0.453145 -0.0501926 0.0651285 0.462086 -0.041985 0.0683883 0.459158 -0.0419365 0.0710311 0.459076 -0.0418461 0.0709274 0.461804 -0.0417207 0.068143 0.461752 -0.0415695 0.0680981 0.46178 -0.0411356 0.0681224 0.461734 -0.0414113 0.0680821 0.458992 -0.0411305 0.070822 0.458952 -0.0414068 0.070772 0.457143 -0.0411282 0.0721125 0.455679 -0.041563 0.0728513 0.455708 -0.0417164 0.0729124 0.458967 -0.0415659 0.0707903 0.459009 -0.0417184 0.0708435 0.455754 -0.041845 0.0730094 0.455811 -0.0419361 0.0731294 0.459305 -0.042 0.0712577 0.455277 -0.0422533 0.0734364 0.455505 -0.0420218 0.0732861 0.45497 -0.0427584 0.0728706 0.454996 -0.0423677 0.0730202 0.455085 -0.0422292 0.0731046 0.454985 -0.0421294 0.0730034 0.455311 -0.0420149 0.0731712 0.455091 -0.0425237 0.0732681 0.455063 -0.0424512 0.0731402 0.455443 -0.0419365 0.0731512 0.455038 -0.0426755 0.0731345 0.455003 -0.042601 0.0730169 0.455147 -0.0423155 0.0732333 0.455252 -0.0421977 0.073291 0.455192 -0.0421116 0.0731556 0.455371 -0.0420998 0.0733089 0.45486 -0.0417593 0.072985 0.455371 -0.0418111 0.0730467 0.455531 -0.0417488 0.0729949 0.455669 -0.041403 0.072831 0.454983 -0.0418778 0.0729925 0.455229 -0.0415026 0.0729809 0.454757 -0.0422011 0.0728636 0.454653 -0.0425919 0.0726208 0.454611 -0.0421364 0.0728442 0.454359 -0.042027 0.0729234 0.455092 -0.0412585 0.0730882 0.455405 -0.0421463 0.0734571 0.455579 -0.04207 0.0735689 0.45555 -0.0420641 0.073431 0.455171 -0.0423812 0.0733712 0.455869 -0.0419848 0.0732515 0.455652 -0.0419652 0.0732235 0.455591 -0.0418772 0.0730956 0.455296 -0.0416597 0.0729885 0.45493 -0.0425237 0.072906 0.454822 -0.0424515 0.0728148 0.454891 -0.042281 0.0729239 0.455099 -0.0420006 0.0730508 0.455227 -0.0418954 0.0730651 0.455707 -0.0420098 0.0733604 0.463115 -0.0430261 0.0647905 0.462408 -0.0415351 0.0671354 0.462392 -0.0416555 0.0671653 0.463018 -0.0425326 0.0658164 0.462898 -0.0423308 0.0663356 0.462695 -0.042096 0.066805 0.462652 -0.0419075 0.0667015 0.462863 -0.0420956 0.0661917 0.46243 -0.041887 0.0672629 0.462242 -0.0419259 0.0678254 0.4624 -0.0417755 0.0672086 0.462482 -0.041983 0.0673243 0.46233 -0.0419931 0.0679004 0.462423 -0.0420313 0.067973 0.462912 -0.0434467 0.0646765 0.462933 -0.0423948 0.066385 0.46274 -0.0421735 0.0668608 0.462549 -0.0420589 0.0673881 0.462543 -0.0420732 0.0676733 0.463122 -0.0426469 0.0652027 0.463103 -0.0426917 0.0652425 0.463082 -0.0430688 0.0648668 0.463091 -0.0427371 0.0652835 0.463177 -0.0425623 0.065129 0.463129 -0.0420132 0.0656863 0.462167 -0.0418294 0.0677541 0.461984 -0.0419369 0.0683 0.461885 -0.0418473 0.0682133 0.462114 -0.0417081 0.0676934 0.462908 -0.0419293 0.0661166 0.462861 -0.0421789 0.0662372 0.462873 -0.0422581 0.0662858 0.463086 -0.0427825 0.0653248 0.463081 -0.0427781 0.0654575 0.454258 -0.0454395 0.0703466 0.45452 -0.0479361 0.0676794 0.454787 -0.0480234 0.0677515 0.454252 -0.0425818 0.0726055 0.454518 -0.0454277 0.0703339 0.454513 -0.0425708 0.072589 0.454786 -0.0455041 0.0704168 0.454784 -0.0426327 0.0726819 0.454894 -0.0481031 0.0678173 0.45497 -0.0481974 0.0678953 0.45497 -0.0456573 0.070583 0.454892 -0.0426901 0.0727681 0.455014 -0.0428304 0.0729787 0.455027 -0.0458296 0.07077 0.459973 -0.0467348 0.064566 0.459958 -0.0466732 0.0647061 0.460782 -0.0458801 0.0648273 0.462923 -0.0434565 0.064602 0.458621 -0.047827 0.0645954 0.456384 -0.0492201 0.0646541 0.456359 -0.0491827 0.0648822 0.456223 -0.0492429 0.0649102 0.456371 -0.0491989 0.0647281 0.456013 -0.049289 0.0650608 0.455927 -0.0492931 0.0651557 0.455966 -0.0493239 0.0648695 0.455694 -0.0492777 0.065284 0.455181 -0.0490187 0.0660806 0.45488 -0.0483584 0.0674012 0.455019 -0.0485152 0.0675396 0.455074 -0.0487191 0.0670875 0.455009 -0.0486543 0.0670254 0.45512 -0.0487911 0.0671484 0.455172 -0.0489035 0.0666317 0.454689 -0.048997 0.0661182 0.454615 -0.048548 0.0668318 0.454533 -0.0482538 0.0672647 0.456232 -0.0493284 0.0645999 0.455931 -0.0493632 0.0647945 0.455612 -0.0492982 0.0652009 0.455258 -0.0493519 0.0652697 0.454953 -0.0490385 0.0659548 0.45483 -0.0485649 0.0669111 0.454777 -0.0483016 0.0673419 0.455042 -0.0485608 0.0677014 0.45508 -0.0486971 0.0673843 0.455314 -0.0490629 0.0661802 0.455369 -0.0490992 0.0662299 0.455298 -0.0490374 0.06644 0.45525 -0.0490355 0.0661299 0.455621 -0.0492398 0.0656366 0.455532 -0.0493412 0.0651243 0.455106 -0.0490135 0.066034 0.455445 -0.0491808 0.0656918 0.454927 -0.0486016 0.0669654 0.454962 -0.0484317 0.0674689 0.455014 -0.0482969 0.0679775 0.455027 -0.0483931 0.0680569 0.447143 0.0520451 0.0628829 0.449967 0.051987 0.0628642 0.450014 0.0519247 0.0629611 0.44613 0.0519973 0.0629636 0.446329 0.0520401 0.0628905 0.447143 0.0520202 0.0629227 0.469354 0.0235286 0.0629741 0.468369 0.033508 0.0627647 0.470049 0.0143962 0.0628618 0.469967 0.0146005 0.0629812 0.470335 0.00492828 0.0629379 0.470312 0.00470874 0.0629887 0.468574 -0.0325392 0.0627596 0.46811 -0.0339823 0.0629754 0.469442 -0.0237839 0.062803 0.469354 -0.0235287 0.0629741 0.46928 -0.026545 0.062699 0.468867 -0.0291185 0.0629718 0.469039 -0.0291304 0.0627337 0.44714 -0.0519975 0.0629633 0.446204 -0.0520188 0.0629252 0.446427 -0.0520458 0.0628819 0.447143 -0.0520206 0.0629222 0.449955 -0.0519877 0.0628645 0.445556 0.052564 0.0628313 0.445717 0.0519061 0.0631341 0.445151 0.0516367 0.0636234 0.445031 0.0516963 0.0635558 0.445014 0.0515403 0.0637938 0.445479 0.0519309 0.0631308 0.444305 0.0511972 0.0645163 0.443941 0.0497825 0.0665921 0.445975 0.0526577 0.0626803 0.445547 0.052768 0.062921 0.445224 0.0527897 0.0632471 0.445574 0.0529218 0.0630592 0.446018 0.0530966 0.0630918 0.446 0.0530578 0.0629967 0.445988 0.0530151 0.0629257 0.444021 0.051587 0.0646277 0.44408 0.051439 0.064564 0.444275 0.0521909 0.0645609 0.444336 0.052234 0.064291 0.444741 0.0525855 0.0638114 0.445267 0.0529046 0.0635656 0.445283 0.0528911 0.0633842 0.444685 0.0524688 0.0636986 0.446006 0.0523981 0.0626721 0.446042 0.0522322 0.0627299 0.445373 0.0520551 0.0630533 0.444786 0.0519482 0.0634908 0.444903 0.0517998 0.0635063 0.445212 0.0524342 0.0630386 0.444006 0.0517303 0.0647082 0.444294 0.0519578 0.0641044 0.444295 0.0521105 0.0641942 0.444668 0.0523107 0.063595 0.444701 0.0521277 0.0635208 0.445195 0.0526325 0.0631224 0.445985 0.0525438 0.0626629 0.443556 0.0500957 0.0668164 0.443641 0.0499597 0.066719 0.443774 0.0498518 0.0666417 0.443681 0.0511789 0.0658466 0.444081 0.0519522 0.0648764 0.443648 0.0510359 0.0658271 0.44403 0.0518544 0.0647942 0.443656 0.0509231 0.0657544 0.443696 0.0508053 0.0656853 0.44377 0.0506928 0.0656267 0.444179 0.0513041 0.0645259 0.445239 0.0523302 0.0630192 0.445277 0.0522295 0.063016 0.446001 0.0524313 0.0626669 0.446427 0.0531258 0.0630564 0.446427 0.0527187 0.0626377 0.446427 0.0521423 0.062769 0.446062 0.0521631 0.062773 0.446427 0.052494 0.0626148 0.446053 0.0531222 0.0632449 0.445972 0.0528925 0.0627958 0.443556 0.0427986 0.0739763 0.443527 0.0449944 0.0725928 0.443569 0.0427792 0.0739467 0.443556 0.0448767 0.0724494 0.443641 0.0447706 0.0723201 0.443556 0.0467727 0.0707329 0.443641 0.0466549 0.0706142 0.443774 0.0446864 0.0722175 0.443774 0.0465614 0.07052 0.444127 0.048216 0.0685563 0.444127 0.0435886 0.0729243 0.443941 0.0446323 0.0721516 0.443941 0.042588 0.0736538 0.443774 0.0426346 0.0737251 0.443703 0.0426681 0.0737763 0.443941 0.0465013 0.0704595 0.443537 0.0501577 0.0668608 0.443527 0.0502465 0.0669243 0.446427 0.0520453 0.0628825 0.447143 0.052142 0.0627693 0.446427 0.0522946 0.0626679 0.447143 0.0522943 0.0626681 0.446427 0.0527135 0.0626362 0.446427 0.0529108 0.0627358 0.446427 0.0530513 0.0628882 0.447143 0.0530511 0.0628883 0.447143 0.0530549 0.0628942 0.447143 0.0531275 0.0630635 0.443641 0.0427072 0.0738363 0.443778 0.0418005 0.074462 0.444614 0.0411968 0.0744534 0.443909 0.0417533 0.0742992 0.444127 0.042572 0.0736292 0.446427 0.0400918 0.0751158 0.445278 0.0402629 0.0751722 0.446427 0.0400369 0.0752276 0.445971 0.0400356 0.0754213 0.443572 0.0423851 0.0743918 0.443629 0.0422843 0.0742133 0.443713 0.0418785 0.0746355 0.443928 0.0414283 0.0748419 0.445409 0.0404121 0.0748862 0.445337 0.0403166 0.0750154 0.444765 0.0405236 0.0752283 0.444371 0.0408541 0.0750915 0.444021 0.0413336 0.0746906 0.444355 0.040909 0.0748887 0.44446 0.0409204 0.0747301 0.444086 0.0417489 0.0741792 0.444593 0.0409747 0.0746043 0.447428 0.0521476 0.062764 0.447143 0.0524937 0.062615 0.447427 0.0525004 0.0626141 0.447143 0.0527133 0.0626363 0.447143 0.0529106 0.0627359 0.447143 0.0529157 0.0627398 0.447429 0.0531259 0.0630573 0.447143 0.0531257 0.0630566 0.446832 0.0400219 0.0752737 0.446832 0.0400917 0.0751155 0.446427 0.0401687 0.0750177 0.447429 0.0520453 0.0628823 0.449985 0.0522449 0.0626532 0.447428 0.052301 0.0626648 0.449998 0.0524427 0.0626063 0.450013 0.0526577 0.0626323 0.447427 0.0527186 0.0626376 0.447428 0.0529138 0.0627381 0.450025 0.0528495 0.0627334 0.450034 0.0529857 0.0628846 0.447428 0.0530524 0.0628901 0.450039 0.0530783 0.0632051 0.45244 0.0516135 0.0629668 0.452465 0.0517028 0.0628369 0.449975 0.0520911 0.0627487 0.452501 0.0518472 0.0627211 0.452596 0.0522704 0.0626641 0.452637 0.0524752 0.0627613 0.452674 0.0526983 0.0630882 0.450038 0.0530582 0.0630508 0.446832 0.0401684 0.0750175 0.45106 0.04 0.0751949 0.45104 0.040022 0.0750353 0.458837 0.04 0.0720958 0.457146 0.0400225 0.0729912 0.461779 0.0403524 0.0686817 0.458773 0.0402103 0.0715771 0.45508 0.0402092 0.0736774 0.451002 0.0402044 0.0747475 0.446832 0.0402038 0.0749838 0.461047 0.04 0.0702344 0.458948 0.0400226 0.0718123 0.457067 0.0400945 0.072852 0.455192 0.0400225 0.0739479 0.45314 0.0400222 0.0746365 0.453101 0.0400929 0.0744825 0.451019 0.040092 0.0748782 0.453068 0.0402064 0.0743546 0.455131 0.0400942 0.0737999 0.457001 0.0402098 0.0727369 0.458852 0.0400947 0.0716835 0.461944 0.0400957 0.0688294 0.462064 0.0400228 0.0689369 0.45582 0.0516783 0.0633644 0.45547 0.0508537 0.0628425 0.452547 0.0520454 0.0626528 0.455554 0.0510395 0.0627716 0.455787 0.0515839 0.0630335 0.452663 0.0526212 0.0629165 0.455815 0.0516572 0.063206 0.453063 0.0526292 0.0632606 0.452673 0.0527203 0.0632462 0.456846 0.0499002 0.0631211 0.45815 0.0492189 0.0629861 0.45823 0.049343 0.0628662 0.455407 0.0507195 0.0629606 0.458341 0.0495145 0.0627935 0.458468 0.0497096 0.0628017 0.458585 0.0498869 0.0628981 0.455647 0.0512516 0.0627811 0.45573 0.0514455 0.0628779 0.458669 0.0500121 0.0630541 0.458713 0.0500771 0.063227 0.45734 0.0509254 0.0633897 0.458103 0.049143 0.0631187 0.460626 0.0473278 0.0629289 0.460722 0.0474398 0.0628088 0.461154 0.0479255 0.0628401 0.461256 0.0480358 0.0629962 0.461312 0.048092 0.0631691 0.462752 0.0450245 0.0629866 0.462819 0.0450847 0.0628541 0.460856 0.0475937 0.0627358 0.463084 0.045315 0.0626619 0.463262 0.0454654 0.0626702 0.461011 0.047768 0.0627438 0.463605 0.0457437 0.0630955 0.461329 0.0481056 0.0633279 0.464718 0.0416052 0.0649956 0.463814 0.0404987 0.0671917 0.463554 0.0403421 0.0675535 0.462186 0.04 0.0690463 0.464867 0.0417881 0.065154 0.46454 0.0412025 0.0659471 0.464469 0.0411267 0.0658801 0.464922 0.041931 0.0649829 0.46471 0.0443295 0.0631855 0.464791 0.0441843 0.0632905 0.463812 0.0411116 0.0656211 0.46298 0.0404476 0.0672451 0.462589 0.0401417 0.0681105 0.463071 0.040378 0.0672773 0.461845 0.0402124 0.0687408 0.464367 0.0410622 0.0658071 0.463918 0.0406239 0.066626 0.463475 0.0403098 0.0674961 0.464098 0.040718 0.0667537 0.464944 0.0437508 0.0632926 0.465059 0.0432949 0.063645 0.465029 0.0423882 0.0642964 0.464137 0.043882 0.062678 0.46417 0.0438993 0.0626715 0.464366 0.0440141 0.0626819 0.464371 0.044017 0.0626833 0.464615 0.0434246 0.0629177 0.46479 0.0435347 0.0630069 0.464405 0.0433438 0.0628997 0.4645 0.0428682 0.0632337 0.465 0.0431287 0.0634558 0.464952 0.0422786 0.0641972 0.46495 0.0430698 0.0633942 0.46424 0.0410234 0.0657378 0.4638 0.0406091 0.0665624 0.463277 0.0402986 0.0673749 0.464708 0.0429198 0.0632579 0.464301 0.0428641 0.0632652 0.464462 0.0421137 0.0640041 0.464281 0.0421468 0.0640101 0.464704 0.0443075 0.0631051 0.4649 0.0436502 0.0631433 0.465053 0.043243 0.0635838 0.464812 0.0416944 0.0650786 0.46402 0.0406635 0.0666923 0.464371 0.0409904 0.066279 0.464028 0.0423474 0.064036 0.463967 0.0432073 0.0632289 0.464137 0.0428973 0.0633351 0.463984 0.0438092 0.0627397 0.464824 0.0421848 0.064105 0.464653 0.0421258 0.0640365 0.463948 0.0410493 0.0656401 0.464131 0.0422124 0.0640464 0.462909 0.0400911 0.0683328 0.46338 0.0402934 0.0674344 0.462755 0.040083 0.0682199 0.463172 0.0403272 0.0673213 0.463674 0.0406232 0.0665072 0.464095 0.0410183 0.06568 0.464587 0.0415396 0.0649176 0.464427 0.0415104 0.0648558 0.464894 0.0422285 0.0641492 0.464883 0.0430134 0.0633384 0.464681 0.0442696 0.0630005 0.462929 0.0451819 0.0627345 0.463692 0.0440364 0.0627986 0.463614 0.043976 0.0629235 0.463944 0.0442282 0.0626375 0.463773 0.044099 0.0627184 0.463425 0.045601 0.0627666 0.464433 0.04459 0.0629088 0.463542 0.0456957 0.0629226 0.464355 0.0445337 0.0627921 0.464318 0.0445067 0.0627531 0.464478 0.0446216 0.06302 0.464613 0.0444951 0.0632333 0.463917 0.0437817 0.0627858 0.463975 0.0442519 0.0626321 0.464152 0.0443837 0.0626502 0.464156 0.0443869 0.0626517 0.464543 0.0441389 0.0627808 0.46456 0.0441522 0.0627969 0.464656 0.0442397 0.0629353 0.464924 0.036 0.0685377 0.462816 0.0359482 0.070629 0.455626 0.036 0.0757506 0.455542 0.0359502 0.0755266 0.453942 0.036 0.0762945 0.449806 0.036 0.076952 0.452701 0.0359512 0.0763469 0.449792 0.0359521 0.0767176 0.448742 0.036 0.0770017 0.446829 0.0359524 0.0768036 0.446829 0.0355552 0.0764581 0.450612 0.035303 0.0762977 0.457184 0.0352761 0.0744321 0.460429 0.03552 0.072353 0.460941 0.0352635 0.0719357 0.464456 0.0355126 0.0681787 0.466066 0.0355238 0.0658881 0.465169 0.0352546 0.0672261 0.466071 0.0352536 0.0658909 0.466249 0.0358718 0.0660052 0.466162 0.0357688 0.0659497 0.46473 0.0359479 0.0683887 0.466457 0.0359872 0.0661391 0.466339 0.0359391 0.0660632 0.464551 0.0357727 0.0682512 0.462567 0.0355155 0.0703905 0.462654 0.0357742 0.0704733 0.45803 0.0355262 0.0739809 0.458091 0.0357795 0.0740869 0.45542 0.0355345 0.0752031 0.452632 0.0355439 0.0760083 0.452657 0.0357883 0.0761309 0.449772 0.0355521 0.0763726 0.460504 0.0357764 0.0724474 0.460644 0.0359487 0.072623 0.458201 0.0359493 0.0742811 0.455464 0.0357836 0.0753187 0.449779 0.0357924 0.0764989 0.446829 0.036 0.0770375 0.446829 0.0357939 0.0765851 0.446427 0.0357888 0.0765805 0.468539 0.0349174 0.0631174 0.468701 0.034927 0.0632393 0.469026 0.0344395 0.0629477 0.469075 0.0344318 0.0630153 0.468888 0.0348306 0.0634977 0.468145 0.0355102 0.0640893 0.468012 0.0355271 0.0639881 0.468356 0.0352767 0.0635995 0.468818 0.0348916 0.0633733 0.466876 0.0358479 0.0651541 0.466762 0.0357466 0.0650952 0.467309 0.0359018 0.0652892 0.467002 0.0359096 0.0652267 0.467522 0.0356646 0.0643103 0.467672 0.034751 0.0634685 0.468176 0.0340668 0.0628591 0.467865 0.0343756 0.0632527 0.467742 0.0349011 0.0634135 0.468293 0.0341709 0.0627575 0.468168 0.0347354 0.0630142 0.468349 0.034851 0.0630357 0.468019 0.03518 0.06342 0.467644 0.0346205 0.0635408 0.468571 0.0351906 0.0638245 0.468484 0.0352476 0.0637145 0.468194 0.0352573 0.0634941 0.467175 0.0352828 0.064211 0.467258 0.0354373 0.064212 0.466099 0.0356442 0.0659092 0.467125 0.0359315 0.065304 0.467802 0.0357043 0.0644856 0.46767 0.0357077 0.0643947 0.467378 0.0355713 0.0642459 0.467861 0.0350531 0.0633929 0.443904 0.0341097 0.0767753 0.445863 0.0358944 0.076806 0.445888 0.0357379 0.0765904 0.445322 0.0357286 0.0768272 0.444363 0.0340606 0.0765956 0.444636 0.034822 0.0765595 0.446105 0.0352881 0.0764476 0.446427 0.035536 0.0764532 0.443538 0.0330936 0.0771551 0.443782 0.0341784 0.076981 0.443613 0.0330826 0.0769581 0.444828 0.0354621 0.0768592 0.444395 0.0351037 0.0768984 0.44392 0.0330684 0.0767055 0.444095 0.034019 0.0766435 0.443706 0.0341038 0.0772125 0.443755 0.0341997 0.0770944 0.444155 0.0349031 0.0771511 0.444377 0.0351356 0.077015 0.444487 0.0349868 0.0766885 0.444899 0.035327 0.0766469 0.445454 0.0353623 0.0764867 0.445371 0.0355802 0.0766129 0.446427 0.035955 0.0768096 0.445861 0.0359442 0.0770442 0.446427 0.036 0.0770375 0.469014 0.0336534 0.062605 0.468894 0.0340028 0.062623 0.469199 0.0340735 0.062872 0.469185 0.0336915 0.0627089 0.469372 0.0337329 0.0630155 0.468517 0.0338701 0.0626229 0.46867 0.0343745 0.0627146 0.468799 0.0341819 0.0626523 0.468598 0.034105 0.0626259 0.468434 0.0342644 0.0627049 0.469296 0.0340643 0.0631835 0.469124 0.0344137 0.0631047 0.469169 0.0343683 0.0632496 0.46827 0.0337632 0.0628119 0.468111 0.033981 0.0629754 0.468373 0.0338076 0.0627048 0.468235 0.0341245 0.0627976 0.468698 0.0339389 0.062589 0.46907 0.0340499 0.0627249 0.46887 0.0344296 0.0628054 0.468898 0.034434 0.062825 0.469272 0.0340755 0.063033 0.444127 0.0294574 0.076735 0.443827 0.0294574 0.0768154 0.443527 0.0331 0.077268 0.444127 0.032636 0.0766902 0.443738 0.0330743 0.0768115 0.443703 0.0330762 0.0768444 0.470066 0.0292014 0.0631529 0.470047 0.0292009 0.0630046 0.469306 0.0337185 0.0628555 0.469862 0.029189 0.0627018 0.468819 0.0336097 0.0625656 0.468633 0.0335678 0.0625916 0.468481 0.0335333 0.0626659 0.443827 0.0239 0.0768154 0.443607 0.0294574 0.077035 0.4697 0.0290747 0.0625971 0.470069 0.0291495 0.0631528 0.469982 0.029197 0.0628469 0.469833 0.0290842 0.0626725 0.469693 0.0291774 0.0625973 0.469507 0.0290601 0.0625537 0.469499 0.0291636 0.0625538 0.469047 0.0290224 0.062733 0.469039 0.0291295 0.0627337 0.469289 0.0290428 0.0625822 0.469155 0.0291384 0.0626406 0.469312 0.02915 0.0625734 0.446427 0.021 0.077335 0.446427 0.0210803 0.077035 0.445017 0.0214581 0.077035 0.446427 0.0211757 0.0769108 0.445277 0.0219081 0.076735 0.446427 0.0216 0.076735 0.445127 0.0216483 0.0768154 0.443985 0.0224902 0.077035 0.443527 0.0239 0.077335 0.443607 0.0239 0.077035 0.444175 0.0226 0.0768154 0.469695 0.0240941 0.0625954 0.469552 0.0265691 0.0625544 0.469601 0.0265732 0.0625453 0.469817 0.0265918 0.0625538 0.470116 0.0241337 0.0626015 0.470352 0.0241561 0.0627706 0.470137 0.0266199 0.062745 0.469919 0.02909 0.0627518 0.470013 0.0290957 0.0628907 0.470247 0.02663 0.0629322 0.470478 0.0241684 0.0630192 0.469461 0.0240723 0.0627507 0.469357 0.0265527 0.0626382 0.469573 0.0290652 0.0625611 0.469965 0.0266046 0.0626082 0.446427 0.0213 0.0768154 0.446827 0.0211757 0.0769108 0.469713 0.0237652 0.062616 0.470072 0.0235515 0.062652 0.469852 0.0233351 0.0627018 0.46956 0.0234092 0.0627745 0.469664 0.0235891 0.0626658 0.469557 0.0237806 0.0626952 0.469447 0.0238075 0.0627944 0.470487 0.023806 0.0630289 0.47045 0.0234344 0.063106 0.470495 0.0241702 0.0631597 0.470507 0.0238272 0.0631785 0.470288 0.02415 0.0627057 0.470418 0.0237845 0.0628689 0.470003 0.024123 0.0625692 0.469851 0.0241087 0.0625615 0.470297 0.0233519 0.0628768 0.470289 0.0237664 0.0627225 0.47011 0.023756 0.0626204 0.469905 0.0237559 0.0625848 0.46986 0.0235622 0.0626242 0.467438 0.0210369 0.0672926 0.465557 0.0211583 0.069484 0.467273 0.0211581 0.0671812 0.465408 0.0215564 0.0693617 0.46571 0.021037 0.0696103 0.463645 0.0210371 0.0718339 0.463508 0.0211591 0.0716894 0.46545 0.0213464 0.0693964 0.463376 0.0215587 0.0715504 0.458775 0.021 0.0754463 0.461302 0.0210375 0.0737493 0.463788 0.021 0.0719847 0.461641 0.021 0.0737659 0.461188 0.0211609 0.0735851 0.463413 0.021348 0.0715896 0.461109 0.0213519 0.0734724 0.458543 0.0213586 0.0749484 0.458686 0.0210383 0.0752551 0.455857 0.0210392 0.0762881 0.458601 0.0211642 0.0750725 0.452806 0.021 0.0771001 0.452885 0.0210399 0.0768732 0.455804 0.0211682 0.0760921 0.455767 0.021367 0.0759606 0.452842 0.0213741 0.0765353 0.452836 0.0215952 0.0764916 0.446827 0.021 0.077335 0.446827 0.0210456 0.0771054 0.452859 0.0211716 0.07667 0.446827 0.0213703 0.0767807 0.470213 0.0233337 0.0628107 0.470383 0.0233847 0.0629757 0.468071 0.0210371 0.0668534 0.469725 0.0219174 0.0645751 0.469228 0.0215104 0.0650972 0.469327 0.021564 0.0651724 0.468455 0.0213564 0.0654625 0.468574 0.0217491 0.064836 0.46906 0.0224565 0.0637563 0.469443 0.0234644 0.06286 0.467114 0.0215558 0.0670734 0.468817 0.021543 0.064886 0.468648 0.0211925 0.0661146 0.467875 0.0210511 0.0667292 0.470479 0.0234951 0.0632491 0.470243 0.022732 0.0635045 0.470298 0.0228173 0.0636195 0.469602 0.0218142 0.0645412 0.469105 0.0214829 0.0650188 0.468714 0.0212733 0.065587 0.468833 0.0212837 0.0656587 0.468415 0.0211252 0.0662247 0.468303 0.0211303 0.066158 0.470138 0.0226588 0.0633812 0.469945 0.0222105 0.0640032 0.469783 0.0233465 0.0627054 0.470007 0.0233219 0.0627206 0.470153 0.0233262 0.0627754 0.46967 0.0221219 0.0638078 0.470065 0.0226327 0.063322 0.469827 0.0221477 0.0639015 0.468963 0.0214919 0.0649453 0.469165 0.0223316 0.0637169 0.469584 0.0226809 0.0631664 0.469785 0.0226232 0.0631911 0.469313 0.0222211 0.0637082 0.468683 0.0216327 0.0648486 0.468454 0.0220015 0.0648719 0.470022 0.0222928 0.0640991 0.469479 0.0217684 0.0644534 0.468187 0.0211654 0.0660944 0.469885 0.0226134 0.063224 0.46998 0.0226169 0.0632686 0.46949 0.0221463 0.0637391 0.468584 0.0212966 0.0655191 0.468076 0.0212313 0.0660397 0.467679 0.021165 0.0666155 0.467978 0.0213238 0.0659987 0.467901 0.0214346 0.0659742 0.467159 0.021346 0.067104 0.446427 0.0167 0.0768154 0.446827 0.017 0.077335 0.446827 0.0164 0.076735 0.446827 0.0167 0.0768154 0.467832 0.0167112 0.066724 0.465994 0.0165989 0.0692035 0.468262 0.017 0.0670025 0.461783 0.0169574 0.0737381 0.46424 0.017 0.0719868 0.460808 0.017 0.0746353 0.459085 0.0169579 0.0752916 0.456162 0.0169586 0.0763229 0.456288 0.017 0.0765161 0.453111 0.017 0.0771015 0.45072 0.017 0.0772833 0.467979 0.016896 0.0668192 0.466098 0.0168153 0.0692863 0.468168 0.0169894 0.0669415 0.466263 0.0169571 0.0694172 0.467787 0.0165996 0.0666953 0.465968 0.0163679 0.0691829 0.463907 0.0163681 0.0714751 0.458942 0.0166061 0.0749798 0.458927 0.0163777 0.074947 0.458099 0.0163805 0.0752981 0.453042 0.0163958 0.0765055 0.46393 0.016599 0.0714988 0.464023 0.0168154 0.0715941 0.461585 0.0166011 0.0734574 0.461662 0.0168164 0.0735665 0.456076 0.0166132 0.0759918 0.453047 0.0166193 0.0765468 0.453062 0.0168252 0.076681 0.46417 0.0169571 0.0717447 0.458998 0.0168188 0.0751016 0.45611 0.0168222 0.0761221 0.453086 0.0169593 0.0768858 0.446827 0.0168266 0.0769132 0.446827 0.0169196 0.077035 0.443607 0.0141 0.077035 0.443985 0.0155098 0.077035 0.445017 0.0165418 0.077035 0.444175 0.0154 0.0768154 0.444435 0.01525 0.076735 0.444977 0.0166114 0.077335 0.446427 0.017 0.077335 0.446427 0.0169196 0.077035 0.445127 0.0163516 0.0768154 0.445277 0.0160918 0.076735 0.46974 0.0165956 0.065098 0.469852 0.0165257 0.0649462 0.470472 0.0159534 0.0638775 0.470524 0.015555 0.0631872 0.470475 0.0152248 0.0628852 0.470686 0.0155328 0.0633061 0.470722 0.0156384 0.0637448 0.470796 0.0154742 0.0634367 0.471086 0.0147652 0.0632519 0.47024 0.016222 0.0644151 0.470118 0.0163096 0.0643636 0.469095 0.016265 0.0646031 0.47097 0.014849 0.062948 0.470838 0.0148663 0.0628161 0.470838 0.0152232 0.0631033 0.470679 0.0152466 0.0629712 0.470382 0.0148045 0.0626913 0.469599 0.0156085 0.0636335 0.47012 0.0147046 0.0627955 0.470188 0.0147362 0.0627525 0.469692 0.0157451 0.0635861 0.470127 0.015445 0.0630852 0.470378 0.0148034 0.0626918 0.470554 0.0158786 0.0639787 0.470349 0.0160047 0.0637697 0.470326 0.0155255 0.0631071 0.468974 0.0168999 0.0659052 0.469195 0.0163976 0.0646111 0.468621 0.0167645 0.0657136 0.468735 0.0168437 0.0657693 0.467899 0.0168156 0.0667676 0.468076 0.0169572 0.0668816 0.468856 0.0168887 0.0658354 0.469218 0.0168384 0.0657922 0.469749 0.0165741 0.0648673 0.469989 0.0163456 0.0642709 0.469621 0.0165935 0.0647847 0.469475 0.0165721 0.0647076 0.469327 0.0165049 0.0646468 0.470187 0.0160142 0.0636706 0.470004 0.0159696 0.0635997 0.469831 0.0158736 0.0635712 0.469001 0.0159942 0.0646524 0.469652 0.0153383 0.0635192 0.443827 0.0141 0.0768154 0.443572 0.00489996 0.0771054 0.443607 0.00489996 0.077035 0.443703 0.00489996 0.0769108 0.470083 0.0141818 0.0628294 0.470715 0.0145174 0.0626383 0.470752 0.0142113 0.0626224 0.470906 0.0145308 0.0627411 0.470938 0.0142203 0.0627245 0.47107 0.0142271 0.0628742 0.471141 0.0142311 0.0630383 0.471053 0.0148119 0.0631035 0.47005 0.0146644 0.0628596 0.470502 0.014491 0.0626096 0.470305 0.0144577 0.0626539 0.470346 0.0147939 0.062697 0.470602 0.0148515 0.0627043 0.471042 0.0145302 0.0628927 0.471011 0.0148356 0.063011 0.471161 0.0142328 0.0631912 0.443748 0.00379018 0.077335 0.444408 0.00288164 0.0771054 0.444376 0.00284935 0.077335 0.446427 0.00204563 0.0771054 0.446427 0.00199996 0.077335 0.445334 0.0022629 0.0771054 0.44379 0.00380765 0.0771054 0.44391 0.00385743 0.0769108 0.443827 0.00489996 0.0768154 0.445459 0.0025629 0.0767807 0.445384 0.00238307 0.0769108 0.4445 0.00297361 0.0769108 0.444638 0.00311125 0.0767807 0.44409 0.00393192 0.0767807 0.443897 0.00489996 0.0767807 0.470191 0.0141862 0.0627194 0.470581 0.00493161 0.0627014 0.470346 0.0141928 0.0626312 0.470542 0.0142016 0.0625915 0.470783 0.00493474 0.062639 0.446827 0.00237035 0.0767807 0.446427 0.00259996 0.076735 0.446427 0.00237035 0.0767807 0.446827 0.00217569 0.0769108 0.446427 0.00217569 0.0769108 0.471455 0.00480877 0.0632395 0.470401 0.00467628 0.0628586 0.470431 0.0049295 0.0628117 0.47101 0.00493851 0.0626546 0.471197 0.00459804 0.062781 0.471214 0.00494219 0.062753 0.471359 0.00494508 0.0629072 0.471347 0.00461642 0.062936 0.471435 0.00494689 0.0630775 0.458553 0.00199996 0.0760911 0.466642 0.00203999 0.0697222 0.468375 0.00204003 0.0672739 0.466481 0.0021713 0.0695959 0.466421 0.00199996 0.0703407 0.46453 0.00203997 0.0720818 0.464387 0.00217119 0.0719352 0.464293 0.00237287 0.0718379 0.4621 0.00203999 0.0740727 0.461985 0.00217131 0.0739035 0.459196 0.00237414 0.0752528 0.458447 0.0025955 0.0754925 0.459179 0.00259497 0.075212 0.461909 0.00237311 0.0737913 0.461884 0.00259354 0.0737544 0.464262 0.00259321 0.0718059 0.466375 0.00237309 0.069512 0.468089 0.00237344 0.0670903 0.459326 0.0020401 0.0755671 0.456326 0.00204027 0.0764855 0.456283 0.00217257 0.0762852 0.459248 0.00217181 0.0753781 0.456254 0.00237572 0.0761528 0.453157 0.00237708 0.0766009 0.446827 0.00204563 0.0771054 0.453169 0.00217322 0.0767356 0.453187 0.00204042 0.07694 0.471055 0.00373955 0.063212 0.471128 0.00376223 0.0632773 0.471231 0.00382802 0.0634136 0.470919 0.00324719 0.0638972 0.470752 0.00461211 0.0626724 0.470548 0.00464183 0.0627418 0.470378 0.00389696 0.0630935 0.470254 0.00400347 0.0631742 0.470895 0.00412074 0.0628393 0.470673 0.00416399 0.0628255 0.470117 0.00339419 0.0636075 0.469611 0.0026512 0.0647565 0.468702 0.00210076 0.0666277 0.47128 0.00390512 0.0635401 0.470561 0.00282527 0.0644382 0.470598 0.00284037 0.0646073 0.470174 0.0025098 0.0650071 0.469876 0.00231716 0.065654 0.470968 0.00372703 0.0631535 0.470277 0.0027747 0.0642614 0.469771 0.00227985 0.0655839 0.469352 0.00212252 0.0661656 0.47087 0.0037266 0.0631056 0.471104 0.00411686 0.0629282 0.470799 0.00318529 0.0637884 0.471187 0.00379257 0.0633456 0.470434 0.00277961 0.0643464 0.470047 0.0024827 0.0649265 0.469456 0.00214286 0.0662308 0.46845 0.00263012 0.0664294 0.469394 0.00304117 0.0647949 0.469503 0.00277685 0.0647481 0.470014 0.00352413 0.0636574 0.470206 0.00417664 0.0632179 0.468203 0.00217147 0.0671635 0.468605 0.00217654 0.066575 0.468136 0.00226841 0.0671203 0.468999 0.00224034 0.06598 0.469748 0.00255261 0.0647918 0.470267 0.00327574 0.0635903 0.47045 0.00319271 0.0636176 0.470555 0.00380115 0.0630523 0.470765 0.00373923 0.0630716 0.471004 0.00411369 0.0628753 0.470985 0.00459579 0.0626834 0.471426 0.00464345 0.0631063 0.471392 0.00462829 0.0630149 0.471276 0.00460502 0.0628489 0.470637 0.00316235 0.0636885 0.469899 0.002495 0.0648512 0.469114 0.00216811 0.0660343 0.469647 0.00227051 0.065511 0.469235 0.00212912 0.0660982 0.468809 0.0020524 0.0666881 0.446827 -0.00230004 0.0768154 0.446827 -0.00217363 0.0769129 0.446427 -0.00200004 0.077335 0.464432 -0.00204005 0.0721764 0.465076 -0.00200004 0.071841 0.461984 -0.00204008 0.0741509 0.462103 -0.00200004 0.0743303 0.461047 -0.00200004 0.0749747 0.459315 -0.00200004 0.0758045 0.456228 -0.00204036 0.0765063 0.456595 -0.00200004 0.0766477 0.453143 -0.00200004 0.0771612 0.453125 -0.0020405 0.0769454 0.45076 -0.00200004 0.0772957 0.446827 -0.00208043 0.077035 0.466243 -0.00259358 0.0696063 0.468203 -0.00217155 0.0671636 0.468465 -0.00200995 0.0673317 0.468375 -0.00204011 0.0672739 0.464166 -0.0025933 0.0718987 0.461771 -0.00259367 0.0738307 0.464196 -0.00237295 0.0719309 0.459106 -0.00237427 0.0752893 0.456149 -0.00259731 0.0761307 0.453096 -0.00237718 0.0766062 0.453092 -0.00259915 0.0765634 0.466278 -0.00237316 0.069634 0.461795 -0.00237322 0.0738677 0.456158 -0.00237585 0.0761732 0.453107 -0.00217332 0.076741 0.466384 -0.00217138 0.0697184 0.466544 -0.00204007 0.0698457 0.46429 -0.00217128 0.0720289 0.46187 -0.00217141 0.0739807 0.459157 -0.00217191 0.075415 0.459234 -0.00204019 0.0756046 0.456186 -0.00217268 0.0763057 0.444175 -0.00360004 0.0768154 0.443827 -0.00490004 0.0768154 0.443985 -0.00349023 0.077035 0.444435 -0.00375004 0.076735 0.445017 -0.00245818 0.077035 0.446427 -0.00208043 0.077035 0.445127 -0.00264838 0.0768154 0.446427 -0.00230004 0.0768154 0.445277 -0.00290818 0.076735 0.470014 -0.00352419 0.0636574 0.470035 -0.00377942 0.0635676 0.469456 -0.00214293 0.0662308 0.471128 -0.00376229 0.0632773 0.470895 -0.0041208 0.0628393 0.470968 -0.00372709 0.0631535 0.470277 -0.00277477 0.0642615 0.469899 -0.00249507 0.0648513 0.470434 -0.00277967 0.0643464 0.469235 -0.0021292 0.0660983 0.470174 -0.00250986 0.0650072 0.470047 -0.00248277 0.0649266 0.469151 -0.0020616 0.066635 0.469352 -0.0021226 0.0661656 0.469114 -0.00216818 0.0660343 0.468282 -0.00209668 0.067214 0.468999 -0.00224042 0.06598 0.468136 -0.0022685 0.0671204 0.470548 -0.00464189 0.0627418 0.470378 -0.00389703 0.0630935 0.470117 -0.00339426 0.0636075 0.470555 -0.00380121 0.0630523 0.470658 -0.00376467 0.0630537 0.470752 -0.00461217 0.0626724 0.470267 -0.00327581 0.0635904 0.469394 -0.00304124 0.0647949 0.470254 -0.00400354 0.0631742 0.470266 -0.00439962 0.0630906 0.470653 -0.00289599 0.0645251 0.470717 -0.00296507 0.0644281 0.470561 -0.00282533 0.0644382 0.471231 -0.00382808 0.0634136 0.470919 -0.00324726 0.0638972 0.470799 -0.00318536 0.0637884 0.470637 -0.00316241 0.0636886 0.47045 -0.00319278 0.0636177 0.469748 -0.00255268 0.0647918 0.468089 -0.00237352 0.0670904 0.469503 -0.00277692 0.0647482 0.469611 -0.00265127 0.0647565 0.470765 -0.00373929 0.0630716 0.470985 -0.00459585 0.0626834 0.471104 -0.00411692 0.0629282 0.47126 -0.00414935 0.0630677 0.471347 -0.00461647 0.062936 0.471426 -0.00464351 0.0631063 0.471351 -0.0042036 0.0632219 0.471286 -0.00392194 0.0635302 0.443607 -0.00490004 0.077035 0.443527 -0.0141 0.077335 0.470335 -0.0049284 0.0629379 0.470401 -0.00467635 0.0628586 0.470431 -0.00492952 0.0628117 0.470581 -0.00493158 0.0627014 0.470783 -0.00493465 0.0626391 0.470863 -0.0046022 0.0626664 0.471197 -0.0045981 0.062781 0.471435 -0.00494683 0.0630775 0.471447 -0.00467082 0.0632549 0.445017 -0.0165419 0.077035 0.445127 -0.0163517 0.0768154 0.444977 -0.0166115 0.077335 0.443915 -0.01555 0.077335 0.443985 -0.0155098 0.077035 0.445277 -0.0160919 0.076735 0.444175 -0.0154 0.0768154 0.443607 -0.0141 0.077035 0.443827 -0.0141 0.0768154 0.444435 -0.01525 0.076735 0.444127 -0.0141 0.076735 0.470303 -0.0141911 0.0626497 0.470752 -0.0142117 0.0626224 0.47101 -0.00493839 0.0626546 0.471214 -0.00494207 0.062753 0.470938 -0.0142207 0.0627245 0.471359 -0.00494498 0.0629072 0.470996 -0.0142237 0.0627787 0.471137 -0.0142312 0.0630255 0.446427 -0.0169197 0.077035 0.446427 -0.0167 0.0768154 0.446827 -0.0169197 0.077035 0.446427 -0.017 0.077335 0.471074 -0.0142277 0.0628801 0.470906 -0.0145322 0.0627412 0.47049 -0.0141995 0.0625955 0.470304 -0.0144588 0.0626541 0.471053 -0.014812 0.0631035 0.471042 -0.0145315 0.0628928 0.470042 -0.0144185 0.0628696 0.470715 -0.0145187 0.0626384 0.470501 -0.0144923 0.0626098 0.470346 -0.014794 0.062697 0.470188 -0.0147363 0.0627525 0.470191 -0.0141863 0.0627194 0.47005 -0.0146645 0.0628596 0.470083 -0.0141818 0.0628294 0.471011 -0.0148357 0.063011 0.470711 -0.0148638 0.0627414 0.470602 -0.0148516 0.0627043 0.470378 -0.0148035 0.0626918 0.458323 -0.017 0.0758545 0.464404 -0.017 0.0718269 0.466333 -0.016957 0.0693278 0.466038 -0.016368 0.0690949 0.466063 -0.0165989 0.0691154 0.4641 -0.0168152 0.0715182 0.464007 -0.016599 0.0714235 0.461716 -0.0168162 0.073528 0.464247 -0.0169571 0.071668 0.466281 -0.017 0.0697495 0.461837 -0.0169573 0.0736991 0.459142 -0.0169578 0.0752648 0.459054 -0.0168186 0.0750752 0.463983 -0.0163681 0.0713999 0.461639 -0.016601 0.0734195 0.466168 -0.0168152 0.0691977 0.467832 -0.0167113 0.066724 0.458998 -0.016606 0.0749538 0.456082 -0.0163874 0.0759499 0.456178 -0.0169586 0.0763184 0.45308 -0.016825 0.0766787 0.456126 -0.0168221 0.0761177 0.456092 -0.0166131 0.0759876 0.453065 -0.0166192 0.0765446 0.454893 -0.0163911 0.07622 0.45306 -0.0163958 0.0765034 0.446827 -0.0167 0.0768154 0.446827 -0.0168265 0.076913 0.446827 -0.017 0.077335 0.453104 -0.0169592 0.0768833 0.469243 -0.0167714 0.0653075 0.470127 -0.0154451 0.0630852 0.47012 -0.0147047 0.0627955 0.469963 -0.0153323 0.0631202 0.469599 -0.0156086 0.0636335 0.469752 -0.0151696 0.0633438 0.469967 -0.0146006 0.0629812 0.469473 -0.0167354 0.0654552 0.468974 -0.0169 0.0659053 0.468675 -0.0169708 0.0664888 0.468075 -0.0169571 0.0668815 0.470237 -0.0162243 0.0644184 0.470611 -0.0155497 0.0632435 0.470686 -0.0155329 0.0633061 0.470838 -0.0148665 0.0628161 0.470428 -0.0155473 0.0631407 0.470326 -0.0155256 0.0631071 0.470004 -0.0159697 0.0635997 0.470524 -0.0155551 0.0631872 0.47097 -0.0148491 0.062948 0.467759 -0.0163689 0.0666772 0.467787 -0.0165995 0.0666953 0.469195 -0.0163976 0.0646111 0.469327 -0.016505 0.0646468 0.470118 -0.0163097 0.0643637 0.469749 -0.0165742 0.0648673 0.469621 -0.0165936 0.0647847 0.469367 -0.016768 0.0653828 0.468856 -0.0168888 0.0658355 0.468466 -0.0169495 0.0663593 0.467979 -0.0168961 0.0668192 0.468735 -0.0168438 0.0657693 0.468621 -0.0167646 0.0657136 0.467899 -0.0168155 0.0667675 0.470856 -0.0153988 0.0635582 0.470796 -0.0154743 0.0634368 0.470349 -0.0160048 0.0637697 0.470472 -0.0159535 0.0638775 0.469989 -0.0163457 0.0642709 0.469474 -0.0165722 0.0647076 0.470187 -0.0160143 0.0636707 0.469831 -0.0158737 0.0635712 0.469692 -0.0157452 0.0635861 0.469095 -0.0162651 0.0646031 0.468914 -0.0160493 0.0648012 0.46955 -0.0154822 0.0636983 0.46761 -0.021 0.0674087 0.455819 -0.0210395 0.0762979 0.458678 -0.0210386 0.0752585 0.455876 -0.021 0.0765042 0.461289 -0.0210378 0.0737573 0.452897 -0.021 0.0770887 0.452869 -0.0210402 0.0768746 0.449578 -0.021 0.0773155 0.467273 -0.0211585 0.0671809 0.467437 -0.0210372 0.0672921 0.467349 -0.0210893 0.0672321 0.465409 -0.0215565 0.0693606 0.465451 -0.0213467 0.0693953 0.463415 -0.0213483 0.0715876 0.461067 -0.0215642 0.0734376 0.458514 -0.0215737 0.0749069 0.457649 -0.0215774 0.0752807 0.452826 -0.0213744 0.0765372 0.461097 -0.0213522 0.0734807 0.46351 -0.0211595 0.0716872 0.458593 -0.0211646 0.0750761 0.458535 -0.0213589 0.0749522 0.455766 -0.0211686 0.076102 0.45573 -0.0213674 0.0759707 0.446827 -0.0213 0.0768154 0.465557 -0.0211587 0.0694827 0.46571 -0.0210373 0.0696089 0.463647 -0.0210374 0.0718315 0.461175 -0.0211613 0.0735933 0.452843 -0.021172 0.0766717 0.446427 -0.0216 0.076735 0.446827 -0.0216 0.076735 0.446427 -0.0213 0.0768154 0.446827 -0.0211737 0.0769129 0.446427 -0.0210804 0.077035 0.446827 -0.0210804 0.077035 0.468304 -0.0211304 0.0661579 0.469105 -0.021483 0.0650187 0.469141 -0.0214378 0.0654393 0.469327 -0.0215641 0.0651723 0.470392 -0.023087 0.0634411 0.470243 -0.0227321 0.0635045 0.469827 -0.0221478 0.0639015 0.470168 -0.0225384 0.0638511 0.469228 -0.0215105 0.0650971 0.467523 -0.0210092 0.06735 0.468415 -0.0211253 0.0662246 0.467978 -0.0213239 0.0659986 0.46906 -0.0224566 0.0637563 0.470001 -0.0233222 0.0627193 0.470383 -0.0233848 0.0629757 0.470267 -0.0229844 0.0631482 0.470112 -0.0229387 0.0630226 0.46991 -0.0229355 0.0629393 0.469852 -0.0233352 0.0627018 0.469584 -0.022681 0.0631664 0.46956 -0.0234093 0.0627745 0.469945 -0.0222107 0.0640032 0.46967 -0.022122 0.0638077 0.470138 -0.022659 0.0633812 0.46998 -0.0226171 0.0632686 0.469785 -0.0226233 0.0631911 0.468574 -0.0217492 0.0648359 0.467901 -0.0214347 0.0659741 0.467159 -0.0213463 0.0671038 0.468187 -0.0211655 0.0660943 0.468076 -0.0212314 0.0660396 0.468963 -0.0214921 0.0649452 0.469602 -0.0218143 0.0645411 0.469479 -0.0217686 0.0644533 0.468817 -0.0215432 0.0648859 0.46949 -0.0221465 0.063739 0.468683 -0.0216328 0.0648485 0.469313 -0.0222212 0.0637081 0.469165 -0.0223317 0.0637169 0.469113 -0.0227737 0.0635662 0.443607 -0.0239 0.077035 0.443985 -0.0224902 0.077035 0.444175 -0.0226 0.0768154 0.443915 -0.02245 0.077335 0.445127 -0.0216484 0.0768154 0.445017 -0.0214582 0.077035 0.469536 -0.0240791 0.0626822 0.46957 -0.0240822 0.0626581 0.469706 -0.0237658 0.0626182 0.469716 -0.0240958 0.0625881 0.469899 -0.0237562 0.0625848 0.46978 -0.0241018 0.0625715 0.470003 -0.0241228 0.0625692 0.470105 -0.023756 0.0626187 0.470416 -0.0237843 0.062867 0.469783 -0.0233466 0.0627054 0.469854 -0.0235629 0.0626245 0.470067 -0.0235517 0.0626504 0.470153 -0.0233263 0.0627754 0.47021 -0.0233333 0.0628085 0.470479 -0.0234952 0.0632491 0.470449 -0.0234341 0.0631051 0.469438 -0.0234673 0.0628647 0.469658 -0.0235904 0.0626684 0.469551 -0.0237814 0.0626992 0.47026 -0.0235607 0.0627481 0.470287 -0.0237662 0.0627202 0.470487 -0.0238059 0.063028 0.470507 -0.0238273 0.0631785 0.470443 -0.0241646 0.0629153 0.444127 -0.0239 0.076735 0.443827 -0.0239 0.0768154 0.443897 -0.0294575 0.0767807 0.443703 -0.0294575 0.0769108 0.443703 -0.0239 0.0769108 0.443572 -0.0294575 0.0771054 0.469047 -0.0290196 0.0627329 0.469267 -0.0290376 0.0625899 0.469965 -0.0266033 0.0626082 0.469694 -0.0290707 0.0625945 0.470247 -0.0266287 0.0629323 0.46992 -0.0290865 0.0627517 0.470071 -0.029095 0.0631088 0.470137 -0.0266186 0.062745 0.470268 -0.0241478 0.0626891 0.470112 -0.024133 0.0625997 0.469817 -0.0265905 0.0625538 0.470007 -0.0241231 0.0625698 0.469601 -0.0265719 0.0625453 0.469914 -0.0241144 0.06256 0.469553 -0.0265678 0.0625543 0.469358 -0.0265514 0.0626381 0.46946 -0.0240724 0.0627508 0.443527 -0.0331 0.077268 0.443569 -0.0330877 0.0770475 0.44392 -0.0330685 0.0767055 0.444127 -0.0326361 0.0766902 0.469312 -0.029151 0.0625734 0.469499 -0.0291646 0.0625538 0.469541 -0.029059 0.0625564 0.469807 -0.0290788 0.0626536 0.469861 -0.0291899 0.0627019 0.46999 -0.0290911 0.0628479 0.470066 -0.0291903 0.0631529 0.444485 -0.0349856 0.0766886 0.443781 -0.0341762 0.0769811 0.443613 -0.0330826 0.0769581 0.443538 -0.0330937 0.0771551 0.443621 -0.0336416 0.0770175 0.443774 -0.034271 0.077201 0.444375 -0.0351343 0.0770151 0.444393 -0.0351024 0.0768986 0.445369 -0.0355794 0.0766131 0.445452 -0.0353615 0.0764868 0.444635 -0.0348209 0.0765596 0.444145 -0.0333478 0.0766518 0.443703 -0.0330763 0.0768444 0.443738 -0.0330744 0.0768115 0.446427 -0.0359569 0.0768142 0.445311 -0.0357645 0.076947 0.44532 -0.0357277 0.0768273 0.446427 -0.0358841 0.076683 0.445339 -0.0356654 0.0767128 0.444629 -0.0353752 0.0771066 0.44404 -0.0346675 0.0769406 0.44443 -0.0350523 0.0767869 0.444094 -0.0340171 0.0766437 0.443903 -0.0341076 0.0767754 0.469155 -0.0291393 0.0626407 0.468601 -0.0335603 0.0626028 0.469693 -0.0291783 0.0625973 0.469139 -0.0336814 0.0626722 0.469982 -0.0291978 0.0628469 0.470047 -0.0292016 0.0630047 0.446628 -0.036 0.0770375 0.446427 -0.0359884 0.0769198 0.446829 -0.0359523 0.0768031 0.446427 -0.0357912 0.0765826 0.446427 -0.0355375 0.0764535 0.44683 -0.0357937 0.0765849 0.468276 -0.0337546 0.0628076 0.468798 -0.0341832 0.0626523 0.468598 -0.0341064 0.0626257 0.468894 -0.0340044 0.0626229 0.468517 -0.0338715 0.0626226 0.468292 -0.0341725 0.0627577 0.468434 -0.034266 0.0627051 0.469123 -0.0344154 0.0631048 0.469199 -0.0340751 0.0628719 0.468373 -0.0338089 0.0627044 0.46837 -0.0335079 0.0627639 0.469075 -0.0344335 0.0630154 0.468698 -0.0339404 0.0625888 0.468878 -0.0336229 0.0625697 0.469015 -0.0336535 0.0626048 0.46907 -0.0340514 0.0627248 0.469324 -0.0337225 0.062887 0.469271 -0.034077 0.0630328 0.469297 -0.0340638 0.0631831 0.455459 -0.0359501 0.075557 0.452269 -0.036 0.0766708 0.461518 -0.036 0.07221 0.460602 -0.0359485 0.0726556 0.460753 -0.036 0.0728463 0.466457 -0.0359873 0.0661391 0.465088 -0.036 0.0683225 0.464446 -0.0355125 0.0681924 0.462543 -0.0355155 0.0704154 0.461505 -0.0352622 0.0714379 0.460388 -0.03552 0.0723855 0.457971 -0.0355263 0.0740147 0.455339 -0.0355347 0.0752333 0.44683 -0.0355551 0.0764581 0.44683 -0.036 0.0770377 0.449669 -0.035952 0.0767243 0.449657 -0.0357923 0.0765059 0.452598 -0.0359511 0.0763673 0.452555 -0.0357882 0.0761513 0.455382 -0.0357836 0.0753489 0.45803 -0.0357794 0.0741207 0.45814 -0.0359492 0.0743152 0.462792 -0.0359481 0.0706539 0.46454 -0.0357725 0.0682649 0.464719 -0.0359477 0.0684023 0.466162 -0.0357689 0.0659497 0.466249 -0.0358719 0.0660052 0.447244 -0.0353104 0.0764426 0.44965 -0.0355524 0.0763797 0.452531 -0.0355441 0.0760288 0.460463 -0.0357763 0.0724799 0.46263 -0.035774 0.0704982 0.466066 -0.0355239 0.065888 0.468235 -0.0341259 0.0627978 0.467672 -0.0347517 0.0634689 0.468175 -0.0340682 0.0628592 0.467236 -0.0359205 0.0653783 0.467802 -0.0357047 0.0644859 0.467669 -0.035708 0.064395 0.467125 -0.0359316 0.0653042 0.467522 -0.035665 0.0643106 0.466761 -0.0357467 0.0650954 0.468817 -0.0348928 0.0633736 0.468897 -0.0344358 0.0628252 0.46887 -0.0344314 0.0628056 0.468349 -0.0348521 0.0630362 0.468669 -0.0343762 0.0627149 0.468167 -0.0347364 0.0630146 0.467742 -0.0349018 0.0634139 0.46786 -0.0350538 0.0633934 0.468538 -0.0349185 0.0631178 0.4687 -0.0349281 0.0632397 0.468355 -0.0352775 0.0635999 0.466839 -0.0351201 0.0647111 0.467257 -0.0354376 0.0642123 0.466099 -0.0356442 0.0659092 0.466876 -0.035848 0.0651543 0.467002 -0.0359098 0.0652269 0.466339 -0.0359391 0.0660632 0.467175 -0.0352831 0.0642113 0.467378 -0.0355716 0.0642462 0.468019 -0.0351807 0.0634205 0.468194 -0.0352581 0.0634945 0.468483 -0.0352484 0.0637148 0.458146 -0.0492221 0.0629861 0.460577 -0.0472517 0.0630616 0.46073 -0.0474328 0.0628088 0.463276 -0.0454483 0.0626702 0.461162 -0.0479183 0.0628401 0.461265 -0.0480285 0.0629961 0.46132 -0.0480847 0.0631691 0.463619 -0.0457263 0.0630954 0.460634 -0.0473208 0.0629289 0.460864 -0.0475866 0.0627358 0.461019 -0.0477608 0.0627438 0.45858 -0.0498901 0.0628981 0.458664 -0.0500154 0.0630541 0.458708 -0.0500804 0.063227 0.455819 -0.0516551 0.0632061 0.455792 -0.0515818 0.0630337 0.458464 -0.0497128 0.0628017 0.458336 -0.0495176 0.0627935 0.455558 -0.0510374 0.0627718 0.458225 -0.0493462 0.0628662 0.455474 -0.0508517 0.0628426 0.455412 -0.0507176 0.0629608 0.452468 -0.0517021 0.062837 0.452641 -0.0524745 0.0627613 0.455652 -0.0512495 0.0627813 0.455735 -0.0514434 0.062878 0.452678 -0.0526977 0.0630883 0.452676 -0.0527196 0.0632462 0.447428 -0.0520459 0.0628814 0.449961 -0.0520918 0.0627489 0.447427 -0.052304 0.0626633 0.449984 -0.0524434 0.0626064 0.447427 -0.0527243 0.062639 0.449999 -0.0526585 0.0626324 0.450019 -0.0529866 0.0628847 0.447429 -0.0531466 0.063212 0.450024 -0.0530591 0.0630509 0.452667 -0.0526205 0.0629165 0.450011 -0.0528503 0.0627334 0.452599 -0.0522697 0.0626641 0.45255 -0.0520447 0.0626528 0.452504 -0.0518466 0.0627211 0.449971 -0.0522456 0.0626534 0.452443 -0.0516129 0.0629668 0.464082 -0.045196 0.0632408 0.464493 -0.0446322 0.0630796 0.463557 -0.0456783 0.0629226 0.46344 -0.0455838 0.0627666 0.464267 -0.0444693 0.0627108 0.464155 -0.0443869 0.0626519 0.463098 -0.0452981 0.0626619 0.462943 -0.0451652 0.0627344 0.463788 -0.0441108 0.0627074 0.463691 -0.0440363 0.0627993 0.462832 -0.0450681 0.0628541 0.447286 -0.0531466 0.0632124 0.447429 -0.053128 0.0630639 0.447428 -0.0530565 0.0628958 0.447143 -0.0530565 0.062896 0.447428 -0.0529193 0.0627418 0.447143 -0.0527241 0.0626392 0.447427 -0.052505 0.0626135 0.447428 -0.0521491 0.0627626 0.447143 -0.0523036 0.0626637 0.447143 -0.0521488 0.0627632 0.447143 -0.0520457 0.0628821 0.463658 -0.0439132 0.0629265 0.464365 -0.0440163 0.0626818 0.464027 -0.0442913 0.0626293 0.463975 -0.0442518 0.0626325 0.463983 -0.0438111 0.0627396 0.463916 -0.0437834 0.0627857 0.464318 -0.0445068 0.0627534 0.464443 -0.0445975 0.0629302 0.46468 -0.0442717 0.0630004 0.46451 -0.0446418 0.0632292 0.447143 -0.0531281 0.0630642 0.446427 -0.0529143 0.062738 0.447143 -0.0529192 0.062742 0.446427 -0.0527243 0.0626391 0.446427 -0.0527192 0.0626375 0.447143 -0.0525047 0.0626138 0.446427 -0.0523017 0.0626645 0.446427 -0.0521482 0.0627637 0.464654 -0.0442418 0.0629352 0.464559 -0.0441545 0.0627967 0.464784 -0.0435365 0.0630009 0.464896 -0.0436515 0.0631357 0.464941 -0.0437521 0.0632844 0.46495 -0.0422848 0.0641834 0.46465 -0.0421342 0.0640246 0.464872 -0.0418004 0.0651391 0.465028 -0.0423938 0.0642824 0.464702 -0.0443074 0.0630981 0.46505 -0.0432457 0.0635739 0.464996 -0.0431318 0.0634464 0.465003 -0.0426797 0.0638046 0.464878 -0.0430174 0.0633301 0.464879 -0.0425744 0.0637027 0.463493 -0.0403196 0.0674645 0.463929 -0.0406349 0.0665985 0.464031 -0.0406741 0.0666646 0.464373 -0.0410725 0.0657842 0.462862 -0.0400865 0.0682432 0.463576 -0.0403538 0.0675246 0.462781 -0.0400897 0.0681851 0.462002 -0.0400536 0.0688808 0.462063 -0.0400235 0.0689353 0.462594 -0.0405055 0.067616 0.463954 -0.0410608 0.0656191 0.463819 -0.041123 0.0656008 0.464136 -0.043884 0.0626778 0.464298 -0.0428704 0.0632609 0.464165 -0.0438994 0.062672 0.4644 -0.0433476 0.0628976 0.464609 -0.0434274 0.0629138 0.464702 -0.042925 0.0632513 0.464496 -0.0428743 0.0632285 0.464429 -0.0415207 0.0648389 0.46266 -0.0400387 0.068596 0.462125 -0.0400058 0.068991 0.463398 -0.0403033 0.067403 0.463295 -0.0403086 0.0673439 0.46472 -0.041614 0.0649773 0.464588 -0.0415492 0.0648999 0.464538 -0.0441377 0.0627767 0.464821 -0.0421921 0.0640921 0.464815 -0.0417024 0.06506 0.464476 -0.0411365 0.065857 0.464193 -0.040805 0.066595 0.464113 -0.0407313 0.0667289 0.461976 -0.0400705 0.0688579 0.463189 -0.0403371 0.0672908 0.461944 -0.0400958 0.0688292 0.461846 -0.0402109 0.0687414 0.463088 -0.0403879 0.0672473 0.462997 -0.0404573 0.0672157 0.461824 -0.0402492 0.0687214 0.464136 -0.0429034 0.0633309 0.464132 -0.042221 0.0640368 0.464035 -0.0428291 0.063529 0.463993 -0.0421432 0.0642914 0.464281 -0.0421559 0.0640002 0.464461 -0.0421227 0.0639934 0.464101 -0.0410297 0.0656582 0.464245 -0.0410343 0.0657154 0.446427 -0.0530528 0.0628899 0.445998 -0.0530578 0.0629968 0.446427 -0.0531263 0.0630572 0.446238 -0.0531405 0.0632195 0.44606 -0.0521631 0.062773 0.446005 -0.0523981 0.0626723 0.445968 -0.0527668 0.0627188 0.445973 -0.0526577 0.0626804 0.446427 -0.052501 0.062614 0.445998 -0.0524352 0.0626665 0.455081 -0.0402077 0.0736786 0.459004 -0.04 0.0719738 0.446832 -0.04 0.0754347 0.455191 -0.0400231 0.073946 0.449596 -0.0403396 0.0747962 0.451931 -0.0403409 0.074513 0.458734 -0.0402088 0.071608 0.457698 -0.0403487 0.0722117 0.458906 -0.0400232 0.071841 0.455131 -0.0400943 0.0737998 0.453125 -0.040093 0.0744761 0.453092 -0.0402049 0.0743496 0.446832 -0.0402343 0.0749588 0.451053 -0.040203 0.0747423 0.446832 -0.0403392 0.0748943 0.460703 -0.040351 0.0698071 0.458812 -0.0400947 0.0717136 0.457123 -0.0400231 0.0730021 0.45806 -0.04 0.072627 0.45107 -0.0400921 0.0748717 0.446832 -0.0400704 0.0751524 0.45109 -0.0400225 0.0750269 0.453165 -0.0400228 0.0746283 0.443703 -0.0499018 0.0666771 0.445355 -0.0529414 0.0635121 0.444741 -0.052586 0.0638107 0.444005 -0.0517297 0.064709 0.443656 -0.0509227 0.0657549 0.443667 -0.0511363 0.065898 0.443562 -0.050701 0.0664106 0.44358 -0.0505018 0.0662756 0.443556 -0.050096 0.0668161 0.443569 -0.0500672 0.0667955 0.44408 -0.0514385 0.0645648 0.444294 -0.0519582 0.0641039 0.445552 -0.0525631 0.0628329 0.445972 -0.0526631 0.0626818 0.444685 -0.0524694 0.063698 0.444029 -0.0518538 0.064795 0.444336 -0.0522344 0.0642905 0.44402 -0.0515865 0.0646285 0.445222 -0.0527892 0.0632478 0.445987 -0.0530192 0.0629317 0.445203 -0.0527172 0.0631821 0.44597 -0.0528925 0.0627959 0.445193 -0.052632 0.0631231 0.44556 -0.0518501 0.0632377 0.446129 -0.0519974 0.0629636 0.445478 -0.0519307 0.0631314 0.445031 -0.0516968 0.0635551 0.446051 -0.0531223 0.0632449 0.445826 -0.0530837 0.0633024 0.446017 -0.0530966 0.0630919 0.445282 -0.0528907 0.0633848 0.444668 -0.0523112 0.0635943 0.444081 -0.0519516 0.0648772 0.443838 -0.0515538 0.0653858 0.443803 -0.0514524 0.0653103 0.443796 -0.0513322 0.065232 0.443648 -0.0510356 0.0658276 0.446041 -0.0522322 0.06273 0.445372 -0.0520548 0.063054 0.444903 -0.0518002 0.0635056 0.445601 -0.0523463 0.062815 0.44377 -0.0506925 0.0656271 0.444702 -0.0521282 0.0635201 0.444786 -0.0519487 0.0634901 0.445276 -0.0522291 0.0630168 0.445211 -0.0524338 0.0630393 0.445196 -0.0525362 0.0630744 0.444295 -0.0521109 0.0641937 0.443696 -0.050805 0.0656858 0.443706 -0.0503036 0.0661531 0.444179 -0.0513037 0.0645267 0.444304 -0.0511968 0.0645171 0.443941 -0.0497828 0.0665918 0.444318 -0.0506612 0.0652454 0.444127 -0.0497589 0.0665747 0.446427 -0.0400919 0.0751158 0.446427 -0.0401677 0.0750188 0.446832 -0.0401675 0.0750186 0.443641 -0.0466551 0.0706141 0.443641 -0.04996 0.0667187 0.444127 -0.0464808 0.0704386 0.443941 -0.0465015 0.0704594 0.443774 -0.0465615 0.0705199 0.443774 -0.0498521 0.0666414 0.443941 -0.0446325 0.0721515 0.443774 -0.0446865 0.0722174 0.443641 -0.0447708 0.07232 0.443556 -0.0467729 0.0707328 0.443774 -0.0426347 0.0737251 0.443556 -0.0448769 0.0724494 0.443537 -0.0428404 0.0740402 0.446427 -0.0400375 0.0752263 0.44534 -0.0403153 0.075016 0.446427 -0.04 0.0754349 0.443838 -0.0417675 0.0743795 0.444358 -0.0409056 0.0748903 0.445138 -0.0407224 0.0747042 0.444596 -0.0409717 0.0746059 0.44439 -0.041533 0.0742653 0.44391 -0.041749 0.0743016 0.443739 -0.041832 0.0745518 0.443656 -0.0420431 0.0745577 0.443641 -0.0427073 0.0738363 0.443941 -0.0425881 0.0736538 0.444087 -0.041745 0.0741815 0.446093 -0.0403629 0.0748831 0.445412 -0.0404108 0.0748868 0.444463 -0.0409172 0.0747317 0.445281 -0.0402615 0.0751728 0.44378 -0.0417959 0.0744644 0.444321 -0.0409159 0.0749743 0.443556 -0.0427987 0.0739763 + + + + + + + + + + 0.770477 0.372956 0.51698 -0.791433 0.570714 0.218906 -0.561915 0.782323 0.268741 -0.313819 0.73144 0.605404 -0.300253 0.750908 0.588205 -0.108261 0.727784 0.677207 -0.107148 0.735156 0.669376 0.106416 0.735278 0.66936 0.109522 0.728111 0.676653 0.297566 0.750948 0.589518 0.315733 0.73238 0.603268 0.444104 0.772967 0.453094 0.476761 0.749776 0.45884 -0.067771 0.939476 0.335846 -0.240467 0.689311 0.683393 -0.0218143 0.940388 0.339404 8.65278e-05 0.81311 0.582111 0.021896 0.940345 0.339516 0.35171 0.448274 0.821797 0.0703077 0.938238 0.338772 0.354373 0.810943 0.465608 0.126312 0.937099 0.325409 0.278014 0.914485 0.293983 -0.493627 -0.759354 0.423927 -0.572375 -0.478896 0.665617 -0.696833 0.0654971 0.714237 -0.799519 0.0976313 0.592653 -0.690939 -0.706859 0.151504 -0.87168 -0.391737 0.294476 -0.938185 0.0729341 0.338364 -0.977422 0.117295 0.175748 -0.2 0.213259 0.956306 -0.55166 0.255199 0.794068 -0.569242 0.20213 0.796936 -0.811027 0.277675 0.51491 -0.968413 0.214633 0.126921 -0.863754 0.46302 0.198849 -0.777458 0.378564 0.502244 0.691872 -0.705693 0.152678 0.99649 0.0704863 -0.0451516 0.800162 -0.584711 -0.133617 0.813206 -0.567412 -0.129382 0.96552 0.100591 0.24011 0.912847 0.0536014 0.404768 0.848359 -0.21779 0.48255 0.506438 0.492975 0.707458 0.570987 -0.586048 0.57491 0.470572 0.0302466 0.881843 0.900538 0.395699 0.180147 0.864381 0.463792 0.194275 0.791474 0.569305 0.222395 0.200623 0.213338 0.956158 0.554156 0.255483 0.792237 0.567199 0.201615 0.798522 0.813083 0.278451 0.511235 0.838589 0.200639 0.506471 0.941612 0.30016 0.152546 0.968163 0.212656 0.13205 0.423919 0.0806996 0.902098 0.212571 0.0548299 0.975606 0.208817 0.159057 0.964933 -0.0948008 0.158382 0.982816 -0.245996 -0.599269 0.761816 -0.306767 0.0665249 0.949457 -0.450788 0.083823 0.888687 -0.339006 0.888683 0.308736 -0.186773 0.947458 0.25969 -0.16063 0.944877 0.285317 -0.531629 0.803238 0.268662 -0.900666 0.397395 0.17572 -0.752313 0.6158 0.234128 -0.673294 0.538996 0.506121 -0.475501 0.748437 0.462322 -0.446981 0.773428 0.449462 -0.117193 0.939701 0.321292 -0.399128 0.763719 0.507376 0.190322 0.93923 0.285699 0.561634 0.783747 0.265157 0.530745 0.802344 0.273045 0.75277 0.616572 0.230599 0.673019 0.539141 0.506333 0.692361 0.513417 0.50699 0.485382 0.448796 0.750324 0.463467 0.487007 0.740286 0.169622 0.451543 0.875978 0.165556 0.465883 0.869221 -0.166686 0.465696 0.869105 -0.167542 0.451279 0.876514 -0.46736 0.487216 0.737696 -0.481911 0.447602 0.753269 -0.687452 0.512482 0.51456 -0.840664 0.201845 0.502537 -0.941158 0.298894 0.157747 -0.806109 -0.576609 -0.133082 -0.996455 0.0705033 -0.0458928 -0.784667 0.0667291 -0.616316 -0.441413 0.0951822 -0.892241 0.187374 0.123649 -0.974475 0.60014 0.119874 -0.790862 0.95456 0.0491878 -0.293931 0.95292 0.136764 -0.270627 0.94249 0.240427 -0.232179 0.925924 0.315139 -0.208214 0.887734 0.433008 -0.156309 0.860786 0.491027 -0.133943 0.787387 0.612502 -0.0697452 0.75596 0.652636 -0.0508897 0.563331 0.823405 0.0682848 0.536133 0.840578 0.0773928 0.182573 0.95593 0.229926 0.375437 0.918362 0.125134 0.127042 0.971238 0.20139 0.471592 0.875756 -0.103209 0.491429 0.86295 -0.117539 0.658612 0.685654 -0.310014 0.680405 0.652594 -0.333422 0.741744 0.51597 -0.428475 0.759565 0.466583 -0.453168 0.786897 0.328933 -0.522108 0.796037 0.264385 -0.54445 0.790325 0.0643815 -0.609296 0.761558 -0.0652424 -0.644804 0.883763 0.0985502 -0.457439 0.441348 0.0949987 -0.892293 0.420062 -0.366132 -0.830359 0.536748 0.291847 -0.791661 0.532505 0.336818 -0.776526 0.517303 0.501172 -0.693704 0.50863 0.535415 -0.67426 0.466897 0.691807 -0.550826 0.456309 0.713969 -0.531066 0.3399 0.899676 -0.273954 0.329756 0.907425 -0.260463 0.0875975 0.982204 0.166137 0.248192 0.968452 0.0223748 0.184162 0.0972147 -0.978077 0.189628 0.317501 -0.929104 0.188216 0.333708 -0.923696 0.183471 0.529233 -0.828403 0.181577 0.541415 -0.820914 0.166121 0.720156 -0.673632 0.16412 0.727973 -0.665672 0.121398 0.923627 -0.363559 0.11938 0.926131 -0.357812 0.0344721 0.991074 0.128779 0.115782 0.99062 -0.0725736 -0.188496 0.123865 -0.974231 -0.187082 0.112078 -0.97593 -0.191966 0.333717 -0.92292 -0.190514 0.317504 -0.928922 -0.185067 0.541515 -0.820068 -0.184431 0.52923 -0.828191 -0.167124 0.727909 -0.664994 -0.167124 0.720166 -0.673373 -0.121909 0.926047 -0.357177 -0.121769 0.923666 -0.363338 -0.0389612 0.99343 0.107602 0.0047593 0.996073 0.0884134 -0.124685 0.982928 -0.135301 -0.0875459 0.982099 0.166784 -0.338255 0.900142 -0.274461 -0.33313 0.906992 -0.257662 -0.466012 0.692192 -0.551093 -0.460034 0.713525 -0.528441 -0.515988 0.501851 -0.694192 -0.513188 0.534799 -0.671289 -0.535171 0.292395 -0.792526 -0.53755 0.336271 -0.77328 -0.420675 -0.368373 -0.829056 -0.601543 0.119892 -0.789793 -0.884435 0.0986039 -0.456127 -0.769731 -0.0634483 -0.635207 -0.791108 0.327629 -0.516534 -0.793759 0.265643 -0.547157 -0.745378 0.515005 -0.423299 -0.757569 0.467653 -0.455401 -0.661418 0.684925 -0.30562 -0.678744 0.653535 -0.33496 -0.474234 0.874858 -0.0986142 -0.488952 0.864091 -0.119474 -0.126781 0.971174 0.201858 -0.241508 0.969895 0.0312563 -0.955023 0.134715 -0.264165 -0.952944 0.0510822 -0.298813 -0.927814 0.313707 -0.201862 -0.9409 0.242251 -0.236689 -0.86236 0.489764 -0.128323 -0.886188 0.434791 -0.160087 -0.757097 0.651664 -0.0462399 -0.785938 0.614024 -0.0726407 -0.537122 0.839447 0.0826333 -0.561351 0.825043 0.0647232 -0.182592 0.955895 0.230056 -0.379914 0.916851 0.12268 0.770477 0.372956 0.51698 -0.791433 0.570715 0.218902 -0.561914 0.782325 0.268739 -0.313811 0.731451 0.605394 -0.300253 0.750908 0.588205 -0.108261 0.727784 0.677207 -0.107148 0.735156 0.669376 0.106415 0.735278 0.66936 0.109525 0.728103 0.676662 0.297586 0.750927 0.589535 0.315722 0.73239 0.603262 0.444084 0.77298 0.45309 0.476761 0.749776 0.45884 -0.0677725 0.939475 0.335848 -0.240485 0.689276 0.683422 -0.0218145 0.940388 0.339404 8.65278e-05 0.81311 0.582111 0.0218959 0.940346 0.339515 0.351652 0.448451 0.821725 0.070306 0.938238 0.338771 0.354373 0.810943 0.465608 0.126312 0.937099 0.325409 0.278014 0.914485 0.293983 -0.493618 -0.759365 0.423917 -0.572364 -0.478955 0.665584 -0.696825 0.0655759 0.714237 -0.799493 0.0977162 0.592674 -0.690939 -0.706859 0.151504 -0.87168 -0.391737 0.294476 -0.938176 0.0730361 0.338366 -0.977404 0.117391 0.175786 -0.199995 0.213303 0.956297 -0.551621 0.255317 0.794057 -0.569245 0.202131 0.796934 -0.811027 0.277675 0.51491 -0.968435 0.21455 0.12689 -0.863755 0.463021 0.198844 -0.777456 0.378563 0.502248 0.691907 -0.705652 0.152709 0.996502 0.0702942 -0.0451984 0.800123 -0.584761 -0.133636 0.813192 -0.567429 -0.129394 0.96552 0.100591 0.24011 0.912843 0.053599 0.404777 0.848365 -0.217858 0.482509 0.506438 0.492975 0.707458 0.570971 -0.58609 0.574883 0.47058 0.0301911 0.881841 0.900538 0.395697 0.180151 0.86438 0.463792 0.194279 0.791475 0.569304 0.222399 0.20062 0.21336 0.956153 0.554138 0.255543 0.79223 0.567196 0.201613 0.798524 0.813083 0.278451 0.511235 0.838589 0.200639 0.506471 0.941612 0.300159 0.152552 0.96812 0.212825 0.132096 0.423969 0.0806059 0.902083 0.212575 0.0547803 0.975608 0.208821 0.159033 0.964936 -0.0947991 0.158393 0.982815 -0.245999 -0.599267 0.761816 -0.306771 0.0664893 0.949458 -0.450796 0.083771 0.888687 -0.33898 0.888694 0.308733 -0.186772 0.94746 0.259683 -0.160624 0.944878 0.285316 -0.53163 0.803238 0.268659 -0.900666 0.397397 0.175716 -0.752313 0.615801 0.234124 -0.673293 0.538994 0.506124 -0.4755 0.748436 0.462324 -0.446963 0.773442 0.449456 -0.117189 0.939702 0.321291 -0.399137 0.763708 0.507384 0.190322 0.93923 0.285699 0.561634 0.783747 0.265157 0.530745 0.802344 0.273045 0.752722 0.616626 0.230612 0.672979 0.539192 0.506331 0.692361 0.513417 0.50699 0.485384 0.448797 0.750322 0.463456 0.487029 0.740278 0.16962 0.451551 0.875974 0.165554 0.465891 0.869217 -0.166687 0.465688 0.869109 -0.167544 0.451271 0.876518 -0.467373 0.487194 0.737703 -0.481923 0.447581 0.753274 -0.687473 0.512452 0.514562 -0.840664 0.201845 0.502537 -0.941158 0.298894 0.157747 -0.806109 -0.576609 -0.133082 -0.996449 0.0706018 -0.0458776 -0.78466 0.066732 -0.616325 -0.441417 0.0952207 -0.892236 0.187375 0.12365 -0.974475 0.60015 0.119925 -0.790846 0.954561 0.049277 -0.293914 0.95293 0.136584 -0.270684 0.94248 0.240502 -0.232144 0.925885 0.315295 -0.208149 0.887734 0.433008 -0.156309 0.860786 0.491027 -0.133943 0.787421 0.612454 -0.0697723 0.755959 0.652637 -0.0508944 0.563311 0.823418 0.0682915 0.536133 0.840578 0.0773928 0.182573 0.95593 0.229926 0.375459 0.918355 0.125121 0.127045 0.971238 0.201387 0.47158 0.875764 -0.103196 0.491417 0.862958 -0.117526 0.658636 0.685617 -0.310046 0.680402 0.652595 -0.333425 0.741741 0.515971 -0.428479 0.759562 0.466584 -0.453171 0.786885 0.328997 -0.522085 0.796044 0.264322 -0.544471 0.790336 0.0644494 -0.609274 0.761538 -0.0653147 -0.644821 0.883828 0.0985959 -0.457304 0.441342 0.0949995 -0.892296 0.420054 -0.366147 -0.830356 0.536745 0.291848 -0.791663 0.532506 0.336777 -0.776543 0.517298 0.501206 -0.693683 0.508632 0.535415 -0.674258 0.4669 0.691807 -0.550825 0.456311 0.713969 -0.531064 0.339907 0.899671 -0.273964 0.329749 0.90743 -0.260453 0.0875962 0.982204 0.166138 0.2482 0.968451 0.022368 0.184159 0.0971828 -0.97808 0.189627 0.31753 -0.929094 0.188217 0.333708 -0.923695 0.183472 0.529233 -0.828403 0.181576 0.541427 -0.820906 0.166121 0.720156 -0.673632 0.16412 0.727973 -0.665672 0.121399 0.923626 -0.363563 0.119381 0.92613 -0.357816 0.0344721 0.991074 0.128779 0.11578 0.99062 -0.072568 -0.188496 0.123881 -0.974229 -0.187084 0.11211 -0.975926 -0.191966 0.333703 -0.922926 -0.190513 0.317475 -0.928932 -0.185065 0.541515 -0.820068 -0.18443 0.52923 -0.828192 -0.167123 0.727909 -0.664995 -0.167123 0.720166 -0.673373 -0.121908 0.926047 -0.357177 -0.121769 0.923667 -0.363333 -0.0389615 0.993431 0.1076 0.00475941 0.996072 0.0884135 -0.124685 0.982927 -0.135305 -0.0875459 0.982099 0.166784 -0.338255 0.900142 -0.274461 -0.33313 0.906992 -0.257662 -0.466012 0.692192 -0.551093 -0.460041 0.713501 -0.528467 -0.515985 0.501852 -0.694193 -0.513182 0.534832 -0.671266 -0.535172 0.292354 -0.792541 -0.537555 0.336312 -0.773259 -0.420681 -0.368371 -0.829054 -0.601548 0.119891 -0.789788 -0.884493 0.0985716 -0.456022 -0.769701 -0.0635835 -0.63523 -0.7911 0.327692 -0.516506 -0.793755 0.265705 -0.547132 -0.74536 0.515056 -0.423268 -0.757555 0.467704 -0.455372 -0.661442 0.684888 -0.305652 -0.678766 0.653497 -0.33499 -0.474221 0.874867 -0.0986012 -0.488949 0.864091 -0.119476 -0.12679 0.971175 0.201851 -0.241522 0.969892 0.0312436 -0.955019 0.134804 -0.264134 -0.952942 0.0510841 -0.298819 -0.927832 0.31363 -0.201901 -0.94089 0.242325 -0.236654 -0.862361 0.489763 -0.128318 -0.886166 0.434851 -0.160047 -0.7571 0.651662 -0.0462303 -0.785974 0.613974 -0.072663 -0.537123 0.839446 0.0826367 -0.561336 0.825052 0.0647388 -0.182592 0.955894 0.230058 -0.380003 0.91682 0.122632 0.770476 0.372954 0.516984 -0.791475 0.570663 0.218884 -0.561893 0.78234 0.268739 -0.313804 0.731462 0.605384 -0.300253 0.750908 0.588205 -0.108261 0.727784 0.677207 -0.107148 0.735156 0.669376 0.106415 0.735278 0.66936 0.109523 0.728107 0.676658 0.297575 0.750937 0.589527 0.315732 0.73238 0.603269 0.444104 0.772967 0.453094 0.476761 0.749776 0.45884 -0.0677725 0.939475 0.335848 -0.240485 0.689276 0.683422 -0.0218145 0.940388 0.339404 8.65278e-05 0.81311 0.582111 0.0218959 0.940346 0.339516 0.351681 0.448362 0.821761 0.0703068 0.938238 0.338771 0.354366 0.810948 0.465606 0.12631 0.9371 0.325408 0.278005 0.914488 0.293983 -0.493618 -0.759365 0.423917 -0.572364 -0.478955 0.665584 -0.696825 0.0655759 0.714237 -0.799493 0.0977162 0.592674 -0.690926 -0.706876 0.151487 -0.871656 -0.391817 0.294439 -0.938192 0.0729408 0.338341 -0.977421 0.117293 0.175756 -0.199998 0.213281 0.956301 -0.551639 0.255258 0.794064 -0.569242 0.20213 0.796936 -0.811029 0.277676 0.514906 -0.968413 0.214633 0.126921 -0.863712 0.463091 0.198868 -0.777418 0.378628 0.502257 0.691885 -0.705677 0.152694 0.996497 0.0703878 -0.0451669 0.800162 -0.584711 -0.133617 0.813234 -0.567374 -0.129373 0.965523 0.100596 0.240094 0.912843 0.053599 0.404777 0.848359 -0.21779 0.48255 0.506438 0.492975 0.707458 0.570987 -0.586048 0.57491 0.470572 0.0302466 0.881843 0.900504 0.395769 0.180167 0.86438 0.463792 0.194279 0.791517 0.56925 0.222385 0.20062 0.21336 0.956153 0.554141 0.255543 0.792229 0.567199 0.201615 0.798522 0.813081 0.27845 0.511239 0.838587 0.200637 0.506475 0.941612 0.30016 0.152546 0.968142 0.212742 0.132071 0.423962 0.0806548 0.902082 0.212573 0.0548051 0.975607 0.208819 0.159045 0.964935 -0.0948005 0.158388 0.982815 -0.245998 -0.599261 0.761821 -0.306767 0.0665249 0.949457 -0.450777 0.0838217 0.888692 -0.339006 0.888683 0.308736 -0.186772 0.94746 0.259683 -0.160624 0.944878 0.285316 -0.53163 0.803238 0.268659 -0.900666 0.397397 0.175716 -0.752313 0.615801 0.234124 -0.673292 0.538993 0.506128 -0.475499 0.748435 0.462326 -0.446945 0.773456 0.449451 -0.117193 0.939701 0.321292 -0.399158 0.763692 0.507393 0.190327 0.939229 0.2857 0.561623 0.783753 0.26516 0.530745 0.802344 0.273045 0.75277 0.616572 0.230599 0.673019 0.539141 0.506333 0.69234 0.513447 0.50699 0.485372 0.448819 0.750317 0.463469 0.487007 0.740284 0.169621 0.451542 0.875978 0.165555 0.465883 0.869221 -0.166686 0.465696 0.869105 -0.167542 0.451279 0.876514 -0.467364 0.487216 0.737693 -0.481931 0.447558 0.753283 -0.687495 0.512423 0.514561 -0.840666 0.201847 0.502533 -0.941158 0.298894 0.157747 -0.806068 -0.576661 -0.133101 -0.996454 0.0705082 -0.0459091 -0.784655 0.0666623 -0.616338 -0.441411 0.0952213 -0.892238 0.187375 0.12365 -0.974475 0.60014 0.119874 -0.790862 0.954558 0.0491896 -0.293936 0.952924 0.136675 -0.270659 0.942478 0.240504 -0.232149 0.925904 0.315217 -0.208181 0.887734 0.433008 -0.156309 0.860753 0.491091 -0.133917 0.787419 0.612456 -0.0697768 0.755998 0.652591 -0.0509222 0.563311 0.823418 0.0682915 0.536124 0.840584 0.0773961 0.182577 0.955929 0.229924 0.375459 0.918355 0.125121 0.127045 0.971238 0.201387 0.47158 0.875764 -0.103196 0.491417 0.862958 -0.117526 0.658636 0.685617 -0.310046 0.680402 0.652595 -0.333425 0.741741 0.515971 -0.428479 0.75958 0.466532 -0.453197 0.786889 0.328996 -0.522081 0.79604 0.264384 -0.544446 0.790328 0.0643803 -0.609292 0.761543 -0.0653093 -0.644815 0.883793 0.0985333 -0.457384 0.441342 0.0949995 -0.892296 0.420054 -0.366147 -0.830356 0.536745 0.291848 -0.791663 0.532502 0.336819 -0.776528 0.517294 0.501206 -0.693685 0.508639 0.535381 -0.67428 0.4669 0.691807 -0.550825 0.456311 0.713969 -0.531064 0.339902 0.899676 -0.273953 0.32975 0.90743 -0.260452 0.0875975 0.982204 0.166137 0.2482 0.968451 0.022368 0.184161 0.0971987 -0.978078 0.189628 0.317516 -0.929099 0.188217 0.333708 -0.923695 0.183472 0.529233 -0.828403 0.181576 0.541427 -0.820906 0.166121 0.720156 -0.673632 0.16412 0.727973 -0.665672 0.121399 0.923626 -0.363563 0.119379 0.926131 -0.357812 0.0344717 0.991074 0.12878 0.115782 0.99062 -0.0725736 -0.188497 0.123881 -0.974229 -0.187083 0.112094 -0.975928 -0.191966 0.333717 -0.92292 -0.190513 0.317489 -0.928927 -0.185065 0.541515 -0.820068 -0.18443 0.52923 -0.828192 -0.167123 0.727909 -0.664995 -0.167123 0.720166 -0.673373 -0.121908 0.926047 -0.357177 -0.121769 0.923667 -0.363333 -0.0389615 0.993431 0.1076 0.00475929 0.996073 0.0884136 -0.124688 0.982926 -0.135312 -0.0875473 0.982099 0.166783 -0.338256 0.900141 -0.27446 -0.333132 0.906992 -0.257661 -0.466015 0.692191 -0.551092 -0.460044 0.713501 -0.528466 -0.515988 0.501851 -0.694192 -0.513188 0.534799 -0.671289 -0.535171 0.292395 -0.792526 -0.537553 0.336354 -0.773242 -0.420671 -0.368398 -0.829047 -0.601543 0.119838 -0.7898 -0.884464 0.0985878 -0.456075 -0.769712 -0.063521 -0.635224 -0.791097 0.327693 -0.51651 -0.793751 0.265767 -0.547108 -0.745378 0.515005 -0.423299 -0.757569 0.467653 -0.455401 -0.661442 0.684888 -0.305652 -0.678766 0.653497 -0.33499 -0.474221 0.874867 -0.0986012 -0.488949 0.864091 -0.119476 -0.126786 0.971175 0.201853 -0.241515 0.969894 0.0312499 -0.955023 0.134715 -0.264165 -0.952944 0.0510822 -0.298813 -0.927814 0.313707 -0.201862 -0.94089 0.242325 -0.236654 -0.862361 0.489763 -0.128318 -0.88619 0.434789 -0.160081 -0.757137 0.651616 -0.0462632 -0.785974 0.613974 -0.072663 -0.537104 0.839458 0.0826467 -0.561334 0.825053 0.0647358 -0.182592 0.955894 0.230057 -0.379969 0.916832 0.122649 0.770477 0.372955 0.516982 -0.791475 0.570662 0.218886 -0.561893 0.782339 0.26874 -0.313807 0.731457 0.605389 -0.300253 0.750908 0.588205 -0.108261 0.727785 0.677207 -0.107148 0.735156 0.669376 0.106415 0.735278 0.66936 0.109523 0.728105 0.67666 0.297581 0.750932 0.589531 0.315727 0.732385 0.603265 0.444094 0.772974 0.453092 0.47677 0.749769 0.458842 -0.0677718 0.939475 0.335847 -0.24048 0.689285 0.683415 -0.0218146 0.940388 0.339404 8.6528e-05 0.81311 0.582111 0.0218959 0.940346 0.339516 0.351667 0.448402 0.821746 0.0703056 0.938239 0.33877 0.354356 0.810956 0.465599 0.12631 0.9371 0.325408 0.278003 0.914488 0.293983 -0.493618 -0.759365 0.423917 -0.572364 -0.478955 0.665584 -0.696825 0.0655759 0.714237 -0.79949 0.0977152 0.592678 -0.690915 -0.706888 0.15148 -0.871678 -0.391752 0.294462 -0.938184 0.0729884 0.338353 -0.977412 0.117341 0.175775 -0.199997 0.213292 0.956299 -0.55163 0.255288 0.794061 -0.569253 0.202101 0.796936 -0.811044 0.277635 0.514904 -0.968424 0.214591 0.126906 -0.863733 0.463056 0.198856 -0.777437 0.378595 0.502252 0.691893 -0.705669 0.152697 0.996499 0.070341 -0.0451826 0.800152 -0.584723 -0.133625 0.813195 -0.567425 -0.129391 0.965525 0.100568 0.240099 0.912847 0.0535757 0.404771 0.848362 -0.217784 0.482548 0.506434 0.492982 0.707455 0.570979 -0.586069 0.574897 0.470576 0.0302188 0.881842 0.900521 0.395734 0.180158 0.86438 0.463792 0.194278 0.791496 0.569277 0.222391 0.20062 0.21336 0.956153 0.554139 0.255543 0.792229 0.567197 0.201614 0.798523 0.813082 0.27845 0.511237 0.838582 0.200659 0.506475 0.941604 0.300182 0.152554 0.968136 0.212762 0.132079 0.423987 0.080608 0.902074 0.212574 0.0547802 0.975608 0.20882 0.159039 0.964936 -0.0947998 0.158391 0.982815 -0.245998 -0.599264 0.761819 -0.306769 0.0665071 0.949458 -0.450787 0.0837963 0.88869 -0.338993 0.888689 0.308734 -0.186777 0.94746 0.259682 -0.160627 0.944878 0.285316 -0.531629 0.803238 0.268661 -0.900649 0.397431 0.175728 -0.752313 0.615801 0.234126 -0.673292 0.538994 0.506126 -0.4755 0.748435 0.462325 -0.446954 0.773449 0.449453 -0.117191 0.939701 0.321291 -0.399133 0.763714 0.50738 0.190324 0.93923 0.285699 0.561623 0.783753 0.26516 0.530756 0.802338 0.273042 0.752734 0.616613 0.230607 0.672989 0.539179 0.506331 0.69235 0.513432 0.50699 0.485378 0.448808 0.75032 0.463463 0.487018 0.740281 0.16962 0.451546 0.875977 0.165555 0.465883 0.869221 -0.166686 0.465696 0.869105 -0.167543 0.451275 0.876516 -0.467368 0.487205 0.737698 -0.481923 0.447581 0.753274 -0.687473 0.512452 0.514562 -0.840664 0.201845 0.502537 -0.941158 0.298894 0.157747 -0.806068 -0.576661 -0.133101 -0.996451 0.0705575 -0.0459015 -0.784655 0.0666623 -0.616338 -0.441414 0.0952209 -0.892237 0.187375 0.12365 -0.974475 0.600143 0.119873 -0.79086 0.95456 0.0492333 -0.293925 0.952927 0.136629 -0.270671 0.942479 0.240503 -0.232146 0.9259 0.315236 -0.208172 0.887728 0.433023 -0.1563 0.86077 0.491058 -0.133927 0.787447 0.612419 -0.0697926 0.755978 0.652614 -0.0509095 0.563297 0.823427 0.0682981 0.536124 0.840584 0.0773977 0.182575 0.955929 0.229925 0.375469 0.918351 0.125116 0.127044 0.971238 0.201388 0.47157 0.875771 -0.103188 0.491411 0.862963 -0.11752 0.658654 0.685589 -0.310069 0.680412 0.652577 -0.333441 0.741736 0.515984 -0.428472 0.759571 0.466558 -0.453184 0.786887 0.328996 -0.522083 0.796038 0.264384 -0.544448 0.790327 0.0643809 -0.609294 0.761535 -0.0653301 -0.644822 0.883818 0.0985604 -0.457331 0.441342 0.0949995 -0.892296 0.420053 -0.366153 -0.830354 0.536747 0.291827 -0.791669 0.532502 0.336819 -0.776528 0.517292 0.501223 -0.693675 0.508636 0.535398 -0.674269 0.4669 0.691807 -0.550825 0.456317 0.713956 -0.531075 0.339905 0.899673 -0.273958 0.329747 0.907433 -0.260447 0.0875968 0.982204 0.166138 0.248201 0.96845 0.0223666 0.18416 0.0971907 -0.978079 0.189627 0.31753 -0.929094 0.188218 0.333701 -0.923698 0.183474 0.529227 -0.828406 0.181576 0.541433 -0.820903 0.166121 0.720156 -0.673632 0.16412 0.727973 -0.665672 0.121399 0.923626 -0.363563 0.11938 0.926131 -0.357814 0.0344719 0.991074 0.128779 0.115781 0.99062 -0.0725708 -0.188496 0.123881 -0.974229 -0.187083 0.112102 -0.975927 -0.191966 0.33371 -0.922923 -0.190512 0.317475 -0.928932 -0.185065 0.541515 -0.820068 -0.18443 0.529236 -0.828188 -0.167123 0.727909 -0.664995 -0.167123 0.720166 -0.673373 -0.121908 0.926046 -0.357179 -0.121769 0.923667 -0.363333 -0.0389618 0.993431 0.107599 0.00475941 0.996072 0.0884136 -0.124685 0.982927 -0.135305 -0.0875459 0.982099 0.166784 -0.338257 0.900139 -0.274466 -0.333131 0.906992 -0.257661 -0.466014 0.692191 -0.551092 -0.460043 0.713501 -0.528466 -0.515987 0.501851 -0.694193 -0.513187 0.534799 -0.671289 -0.53517 0.292374 -0.792534 -0.537553 0.336354 -0.773242 -0.420676 -0.368384 -0.82905 -0.601541 0.119838 -0.789802 -0.884462 0.098548 -0.456087 -0.769706 -0.0635523 -0.635227 -0.791099 0.327693 -0.516508 -0.793753 0.265766 -0.547106 -0.74537 0.51503 -0.423281 -0.757569 0.467653 -0.455401 -0.661442 0.684888 -0.305652 -0.678766 0.653497 -0.33499 -0.474221 0.874867 -0.0986012 -0.488949 0.864091 -0.119476 -0.126788 0.971175 0.201852 -0.241519 0.969893 0.0312467 -0.955022 0.134758 -0.264147 -0.952941 0.0510402 -0.298829 -0.927823 0.313669 -0.201882 -0.94089 0.242325 -0.236654 -0.862346 0.489794 -0.128302 -0.886177 0.434821 -0.160067 -0.757137 0.651616 -0.0462632 -0.785974 0.613974 -0.072663 -0.537104 0.839458 0.0826467 -0.561334 0.825053 0.0647358 -0.182596 0.955894 0.230055 -0.379986 0.916826 0.122641 -0.194594 0.957972 0.210769 -0.194605 0.95797 0.210768 -0.554575 0.812696 0.178806 -0.554569 0.8127 0.178807 -0.194606 0.978327 0.0707478 -0.194612 0.978326 0.0707471 -0.554569 0.829971 0.0600189 -0.554568 0.829971 0.060019 -0.555569 0.83147 0 -0.555569 0.83147 0 -0.195101 0.980783 0 -0.195101 0.980783 0 -0.19485 0.924941 0.32637 -0.194844 0.924942 0.326371 -0.527901 0.77705 0.342802 -0.162782 0.9027 0.398291 -0.195044 0.898962 0.392204 -0.555379 0.758549 0.340819 -0.555095 0.784389 0.276776 -0.555087 0.784393 0.276778 -0.194612 0.978325 -0.0707477 -0.194606 0.978327 -0.0707472 -0.554568 0.829971 -0.060019 -0.554569 0.829971 -0.060019 -0.194605 0.957969 -0.210769 -0.194594 0.957972 -0.210768 -0.554569 0.8127 -0.178806 -0.554575 0.812696 -0.178806 -0.163153 0.878552 0.448919 -0.172589 0.877896 0.446667 -0.191732 0.847788 0.494464 -0.151121 0.853609 0.498511 -0.176802 0.820037 0.544317 -0.125886 0.830839 0.542087 -0.156641 0.793002 0.588737 -0.101521 0.809349 0.578487 -0.130378 0.768418 0.626526 -0.0802047 0.789252 0.608809 -0.0973805 0.748688 0.655731 -0.0582917 0.772936 0.6318 -0.0597379 0.735236 0.675174 -0.0354308 0.760107 0.648831 -0.0193961 0.731977 0.681053 -0.0127919 0.746138 0.665669 -0.527909 0.749168 0.400074 -0.532083 0.747312 0.39801 -0.516076 0.697329 0.49739 -0.491764 0.709859 0.504251 -0.461195 0.664042 0.588513 -0.439197 0.676534 0.591108 -0.395121 0.633531 0.66522 -0.37653 0.645681 0.66432 -0.319939 0.606664 0.727734 -0.305551 0.618092 0.724294 -0.236376 0.584531 0.776176 -0.226869 0.594414 0.771494 -0.145269 0.568827 0.809526 -0.140709 0.575839 0.805364 -0.0488842 0.561625 0.825946 -0.0480146 0.564211 0.824234 -0.194844 0.924942 -0.32637 -0.194849 0.924941 -0.32637 -0.555087 0.784393 -0.276777 -0.555095 0.784388 -0.276776 -0.195026 0.897334 -0.395924 -0.241159 0.885051 -0.398155 -0.555511 0.762904 -0.330733 -0.594118 0.735943 -0.324673 0 0.746198 0.665724 0 0.746198 0.665724 0 0.56486 0.825187 0 0.56486 0.825187 -0.0143517 0.746121 -0.665655 -0.0183527 0.737309 -0.675307 -0.0436859 0.762016 -0.646083 -0.0562237 0.725964 -0.685431 -0.0631179 0.781954 -0.620132 -0.102979 0.726173 -0.679756 -0.0844264 0.785492 -0.613086 -0.131971 0.767296 -0.627568 -0.100159 0.805353 -0.584274 -0.156241 0.873221 -0.461599 -0.256818 0.809516 -0.527948 -0.104039 0.86991 -0.482112 -0.248718 0.767267 -0.591135 -0.0877192 0.850675 -0.518322 -0.161477 0.79048 -0.590819 -0.593939 0.705913 -0.385905 -0.241358 0.874051 -0.42164 -0.250668 0.867841 -0.428973 -0.530222 0.74074 -0.412516 -0.515049 0.694399 -0.502528 -0.493546 0.71251 -0.498741 -0.459548 0.661556 -0.592587 -0.441531 0.678771 -0.586788 -0.39314 0.631574 -0.668248 -0.379146 0.647373 -0.661178 -0.317958 0.605211 -0.72981 -0.308095 0.619237 -0.722235 -0.234618 0.583623 -0.777392 -0.229018 0.59502 -0.770391 -0.144022 0.568395 -0.810052 -0.142155 0.576003 -0.804992 -0.0484195 0.561521 -0.826044 -0.048509 0.564195 -0.824215 0.04425 0.758874 0.649732 0.0534633 0.73139 0.679861 0.064691 0.779278 0.62333 0.098331 0.731634 0.674569 0.0849002 0.785152 0.613455 0.131256 0.76662 0.628542 0.100211 0.805325 0.584302 0.156352 0.873201 0.461599 0.254854 0.810303 0.527691 0.105608 0.869373 0.482739 0.244383 0.769575 0.589942 0.0898355 0.84969 0.519574 0.161249 0.789783 0.591812 0.514849 0.756766 0.402784 0.0155446 0.739268 0.673232 0.0159006 0.746104 0.66564 0.0459982 0.564262 0.824313 0.147937 0.891308 0.428585 0.192961 0.872091 0.449693 0.532492 0.749224 0.393847 0.514686 0.694044 0.50339 0.493095 0.712224 0.499594 0.45872 0.66102 0.593825 0.440636 0.678313 0.58799 0.391723 0.630918 0.669698 0.377716 0.646771 0.662585 0.315873 0.604504 0.731299 0.306054 0.618549 0.723691 0.231804 0.582954 0.778737 0.226293 0.594317 0.771738 0.140415 0.567913 0.811024 0.138648 0.575391 0.806041 0.0468069 0.561872 0.825899 0 0.746198 -0.665724 0 0.746198 -0.665724 0 0.56486 -0.825187 0 0.56486 -0.825187 0.555089 0.784392 0.276777 0.555081 0.784397 0.276778 0.194851 0.924941 0.32637 0.194845 0.924942 0.32637 0.195027 0.897334 0.395923 0.147555 0.907744 0.392719 0.555322 0.757271 0.34374 0.514835 0.784351 0.346032 0.242059 0.870443 -0.428646 0.172594 0.877896 -0.446665 0.191734 0.847788 -0.494462 0.151132 0.853609 -0.498508 0.176808 0.820033 -0.544321 0.125899 0.830834 -0.542092 0.156645 0.793004 -0.588734 0.101506 0.809356 -0.57848 0.130371 0.768424 -0.626521 0.079996 0.789335 -0.608729 0.0975886 0.748477 -0.655941 0.0580193 0.772961 -0.631795 0.0598775 0.735002 -0.675416 0.0351376 0.76023 -0.648703 0.0194636 0.731621 -0.681433 0.0126742 0.746138 -0.66567 0.594347 0.705618 -0.385817 0.53022 0.74072 -0.412554 0.516092 0.69732 -0.497387 0.491784 0.709847 -0.504247 0.461213 0.664033 -0.588509 0.439182 0.676543 -0.591108 0.395108 0.633541 -0.665219 0.376548 0.645669 -0.664321 0.319956 0.606652 -0.727738 0.305557 0.618088 -0.724295 0.236378 0.584531 -0.776176 0.226874 0.59441 -0.771495 0.145272 0.568822 -0.809529 0.140721 0.575821 -0.805375 0.0488897 0.561607 -0.825958 0.0480146 0.564209 -0.824235 0.554569 0.8127 0.178807 0.554563 0.812704 0.178807 0.194595 0.957972 0.210768 0.194607 0.957969 0.210769 0.554563 0.829975 0.0600193 0.554562 0.829975 0.0600193 0.194607 0.978327 0.0707472 0.194614 0.978325 0.0707477 0.194846 0.924942 -0.326371 0.194851 0.924941 -0.32637 0.594564 0.735643 -0.324536 0.241733 0.887769 -0.391703 0.194976 0.89375 -0.403973 0.555506 0.762926 -0.330693 0.555089 0.784392 -0.276777 0.555081 0.784397 -0.276779 0.195103 0.980783 0 0.195103 0.980783 0 0.555564 0.831474 0 0.555564 0.831474 0 0.554562 0.829975 -0.0600193 0.554563 0.829975 -0.0600192 0.194614 0.978325 -0.0707471 0.194607 0.978327 -0.0707478 0.554563 0.812704 -0.178808 0.554569 0.8127 -0.178806 0.194606 0.957969 -0.210768 0.194595 0.957971 -0.210769 0.999913 0.0120959 -0.00517145 0.999996 0.0026925 -0.00115544 0.998815 0.0448263 -0.0189767 0.985232 0.158449 -0.0648984 0.980778 0.181078 -0.0726983 0.980755 0.184888 -0.0627336 0.980756 0.184887 -0.0627329 0.831285 0.526371 -0.1786 0.831284 0.526373 -0.178601 0.714951 0.643058 -0.274446 0.831305 0.511575 -0.217309 0.837746 0.502152 -0.214536 0.946063 0.297934 -0.127281 0.980685 0.195083 -0.0141076 0.980686 0.195079 -0.014107 0.830796 0.555128 -0.0401435 0.830802 0.555119 -0.0401418 0.980686 0.19102 -0.0420274 0.980685 0.191024 -0.0420288 0.830802 0.543567 -0.119594 0.830804 0.543564 -0.119593 0.71152 0.619377 -0.33183 0.706043 0.624661 -0.333619 0.940818 0.275349 -0.197596 0.977594 0.140813 -0.156465 0.987852 0.0638761 -0.141666 0.0756014 0.350741 -0.933416 0.0965407 0.118959 -0.988195 0.270041 0.301376 -0.914467 0.220505 0.124589 -0.967396 0.0988302 0.107849 -0.989243 0.289347 0.100884 -0.951893 0.454235 0.146017 -0.878834 0.474014 0.102015 -0.874588 0.605829 0.158106 -0.779727 0.631894 0.106994 -0.767634 0.077061 0.344841 -0.935493 0.221888 0.364321 -0.904453 0.229232 0.348019 -0.90903 0.357727 0.383222 -0.85157 0.372686 0.359585 -0.855455 0.480122 0.405366 -0.777922 0.50171 0.377656 -0.778244 0.588164 0.430168 -0.68485 0.614585 0.399961 -0.679938 0.680695 0.457115 -0.572451 0.709466 0.425817 -0.56155 0.754586 0.485982 -0.440933 0.783653 0.45398 -0.424017 0.805187 0.513632 -0.296404 0.833899 0.479644 -0.273046 0.72835 0.165291 -0.66497 0.716724 0.213265 -0.663947 0.79674 0.14135 -0.587559 0.840679 0.181016 -0.510385 0.867447 0.124438 -0.481716 0.918551 0.192625 -0.345196 0.9408 0.135513 -0.310696 0.965275 0.204538 -0.162506 0.98867 0.0925637 -0.118165 0.980783 0.195103 0 0.980783 0.195103 0 0.831466 0.555575 0 0.831466 0.555575 0 0 0.351747 -0.936095 0 0.351747 -0.936095 0 0.119517 -0.992832 0 0.119517 -0.992832 0.980685 0.191024 0.0420284 0.980686 0.19102 0.0420278 0.830804 0.543564 0.119594 0.830802 0.543567 0.119594 0.980686 0.195079 0.0141073 0.980685 0.195083 0.0141072 0.830802 0.555118 0.0401428 0.830796 0.555128 0.0401425 -0.706531 0.624193 -0.333462 -0.712781 0.618149 -0.331414 -0.98785 0.0638907 -0.141671 -0.977685 0.140284 -0.156375 -0.941018 0.274811 -0.197391 -0.0980496 0.118941 -0.988048 -0.0764735 0.350717 -0.933354 -0.0973672 0.107637 -0.989411 -0.220504 0.124586 -0.967397 -0.255973 0.248599 -0.934171 -0.317693 0.108698 -0.941943 -0.460438 0.147704 -0.875317 -0.468456 0.0997243 -0.877841 -0.612783 0.161171 -0.773642 -0.704274 0.223233 -0.673918 -0.735289 0.169745 -0.656153 -0.625708 0.103445 -0.773168 -0.79673 0.141356 -0.587571 -0.846058 0.186313 -0.499473 -0.862573 0.119046 -0.491727 -0.921965 0.198483 -0.332544 -0.937656 0.129711 -0.322452 -0.965367 0.205113 -0.16123 -0.982073 0.114779 -0.149527 -0.0762221 0.344707 -0.935611 -0.224412 0.364593 -0.903721 -0.226963 0.347342 -0.909858 -0.36148 0.384154 -0.849563 -0.369457 0.358155 -0.857453 -0.484461 0.407136 -0.774298 -0.498056 0.3754 -0.781674 -0.592468 0.432737 -0.6795 -0.61103 0.396946 -0.684891 -0.684357 0.460356 -0.565445 -0.706497 0.422183 -0.567999 -0.757073 0.489689 -0.432488 -0.781756 0.449897 -0.431799 -0.806158 0.517751 -0.286431 -0.83402 0.47369 -0.282893 0.999996 0.00269574 0.00115683 0.99992 0.0116627 0.00498648 0.831289 0.511229 0.218184 0.832414 0.509596 0.217715 0.942914 0.306258 0.130839 0.980777 0.180931 0.0730823 0.982152 0.174248 0.0708179 0.998438 0.0514495 0.0217793 0.980756 0.184887 0.062733 0.980755 0.184888 0.0627334 0.831284 0.526373 0.1786 0.831285 0.526371 0.1786 -0.998811 0.0448848 -0.019 -0.999915 0.0119638 -0.00511434 -0.999997 0.00235594 -0.00101101 -0.831286 0.511233 -0.218186 -0.716701 0.648525 -0.256426 -0.838924 0.500485 -0.213825 -0.980758 0.179532 -0.0766931 -0.94667 0.301338 -0.114066 -0.985335 0.157901 -0.0646723 -0.980758 0.184875 -0.0627291 -0.980758 0.184877 -0.0627295 -0.831281 0.526377 -0.178602 -0.831282 0.526376 -0.178602 0.937687 0.283357 0.201125 0.82858 0.487054 0.276103 0.98171 0.116963 0.150217 0.987621 0.0659423 0.142327 0.974813 0.154993 0.160362 0.975759 0.154268 0.155229 0.92138 0.18274 0.343024 0.926427 0.160634 0.340484 0.849069 0.155205 0.504969 0.847423 0.161944 0.505616 0.746693 0.133211 0.651693 0.736109 0.17495 0.653862 0.621965 0.100325 0.776592 0.594049 0.215653 0.774984 0.481112 0.0299112 0.876149 0.429582 0.289351 0.855416 0.365814 0.0411893 0.929776 0.244898 0.268132 0.931735 0.233996 0.126891 0.963921 0.0931755 0.118997 0.988513 0.0494695 0.316031 0.947458 0.153825 0.116573 0.981198 0.0729508 0.35081 0.933601 0.0743246 0.345297 0.935546 0.219085 0.363953 0.905285 0.221447 0.347167 0.911283 0.356535 0.383358 0.852009 0.364327 0.357553 0.859896 0.480645 0.406404 0.777056 0.49419 0.374609 0.784503 0.590102 0.432276 0.681848 0.608836 0.396161 0.687295 0.683207 0.460079 0.567058 0.705479 0.421693 0.569627 0.756567 0.489533 0.433547 0.781358 0.449587 0.432841 0.805189 0.514273 0.295287 0.706032 0.624499 0.333944 -0.980688 0.191012 -0.0420257 -0.980688 0.191008 -0.0420252 -0.830801 0.543568 -0.119595 -0.830799 0.543572 -0.119595 -0.980688 0.195067 -0.0141064 -0.980688 0.195071 -0.0141063 -0.830799 0.555123 -0.0401431 -0.830793 0.555132 -0.0401428 0 0.351747 0.936095 0 0.351747 0.936095 0 0.119517 0.992832 0 0.119517 0.992832 -0.831463 0.55558 0 -0.831463 0.55558 0 -0.980785 0.19509 0 -0.980785 0.19509 0 -0.563796 0.141922 0.813629 -0.706519 0.624034 0.333784 -0.0737942 0.350788 0.933543 -0.0807299 0.119127 0.989592 -0.0877781 0.191097 0.977638 -0.251461 0.0531549 0.966407 -0.251633 0.240918 0.937358 -0.347434 0.118706 0.930161 -0.462067 0.0995803 0.881236 -0.396767 0.387214 0.832251 -0.411109 0.135748 0.901422 -0.937902 0.282799 0.20091 -0.974949 0.154299 0.160209 -0.987625 0.0659005 0.142319 -0.555919 0.356273 0.751015 -0.663228 -0.043519 0.747151 -0.705212 0.246305 0.664838 -0.715358 0.210103 0.666423 -0.805532 0.132379 0.577576 -0.824475 0.217569 0.522403 -0.888057 0.0867816 0.451468 -0.905041 0.228377 0.358811 -0.949278 0.121483 0.290022 -0.95974 0.226637 0.165933 -0.989771 0.0890221 0.111483 -0.0735115 0.345181 0.935653 -0.216614 0.363711 0.905976 -0.223668 0.347819 0.910491 -0.352815 0.382459 0.853959 -0.367525 0.35896 0.857947 -0.476304 0.404673 0.780624 -0.497836 0.376837 0.781123 -0.585787 0.429729 0.687158 -0.612401 0.399151 0.682381 -0.67954 0.456837 0.574043 -0.70845 0.425333 0.563197 -0.75406 0.48584 0.441988 -0.78326 0.45367 0.425074 -0.805186 0.514277 0.295287 -0.82858 0.487056 0.276102 -0.980688 0.195071 0.0141067 -0.980689 0.195067 0.0141061 -0.830793 0.555132 0.0401438 -0.830799 0.555123 0.0401422 -0.980688 0.191008 0.0420248 -0.980688 0.191012 0.0420261 -0.830799 0.543571 0.119595 -0.830801 0.543568 0.119594 -0.999997 0.00235877 0.00101223 -0.99992 0.0116006 0.00495923 -0.998451 0.051242 0.0216921 -0.980778 0.180782 0.0734345 -0.980758 0.184877 0.0627297 -0.980758 0.184875 0.0627288 -0.831283 0.526375 0.178601 -0.831281 0.526377 0.178602 -0.83242 0.509669 0.217518 -0.831282 0.511155 0.218382 -0.943135 0.305681 0.130593 -0.982331 0.173682 0.0697109 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.957794 -0.258322 0.126096 0.707892 -0.700145 0.0931957 -0.0235914 -0.970603 -0.239527 0.270937 -0.961936 0.0356695 -0.239475 -0.970391 -0.0315275 -0.0956929 -0.988558 -0.116603 -0.14704 -0.970391 -0.191626 -0.186052 -0.970603 -0.152689 -0.131779 -0.986108 -0.101118 -0.299524 -0.94056 -0.160099 -0.138869 -0.988639 -0.0575214 -0.325003 -0.94056 -0.0985887 -0.150112 -0.988558 -0.0147847 0.270938 -0.961936 0.0356696 0.252473 -0.961936 0.104578 0.252468 -0.961937 0.104576 0.216799 -0.961937 0.166356 0.216802 -0.961936 0.166358 0.166358 -0.961937 0.216801 0.166356 -0.961937 0.216799 0.707887 -0.70015 0.0931954 0.659646 -0.70015 0.273235 0.659655 -0.70014 0.273238 0.566459 -0.700141 0.434658 0.566454 -0.700146 0.434656 0.434657 -0.700144 0.566456 0.434653 -0.70015 0.566451 0.427093 -0.259878 0.866057 0.588099 -0.25832 0.766427 0.5881 -0.258319 0.766427 0.766427 -0.258319 0.5881 0.766427 -0.25832 0.5881 0.866058 -0.259878 0.427091 0.874133 0.323715 0.362078 0.914394 -0.25988 0.310396 0.957794 -0.258321 0.126096 0.310392 -0.259901 0.914389 0.362077 0.323725 0.874129 0.27324 -0.700138 0.659657 0.273234 -0.700151 0.659645 0.104576 -0.961938 0.252468 0.104576 -0.961937 0.252469 -0.0575218 -0.988639 -0.13887 -0.160105 -0.940556 -0.299534 -0.0985896 -0.940559 -0.325006 -0.021681 -0.986108 -0.164684 0.0356688 -0.961938 0.270931 0.0356687 -0.961938 0.270931 0.0931966 -0.700138 0.707899 0.0931951 -0.700145 0.707892 0.126094 -0.258343 0.957789 0.126096 -0.258322 0.957794 -0.239594 -0.970873 0 -0.239594 -0.970873 0 0.27111 -0.962548 0 0.27111 -0.962548 0 0.710987 -0.703206 0 0.710987 -0.703206 0 0.965501 -0.260401 0 0.965501 -0.260401 0 0.126095 -0.258322 -0.957794 0.0931957 -0.700145 -0.707892 -0.239527 -0.970603 0.0235914 0.0356687 -0.961938 -0.270931 -0.0315275 -0.970391 0.239475 -0.1166 -0.988558 0.0956907 -0.191626 -0.970391 0.14704 -0.152688 -0.970603 0.186052 -0.10112 -0.986108 0.131782 -0.160105 -0.940556 0.299534 -0.0575218 -0.988639 0.13887 -0.0985896 -0.940559 0.325006 -0.0147848 -0.988558 0.150112 0.0356687 -0.961938 -0.270931 0.104576 -0.961938 -0.252468 0.104576 -0.961937 -0.252469 0.166356 -0.961937 -0.216799 0.166358 -0.961937 -0.216801 0.216802 -0.961936 -0.166358 0.2168 -0.961937 -0.166356 0.093196 -0.700138 -0.707899 0.273239 -0.700138 -0.659657 0.273235 -0.700151 -0.659645 0.434653 -0.70015 -0.56645 0.434657 -0.700143 -0.566456 0.566455 -0.700146 -0.434655 0.566458 -0.700141 -0.434659 0.866058 -0.259878 -0.427091 0.766427 -0.25832 -0.5881 0.766427 -0.258319 -0.5881 0.5881 -0.258319 -0.766427 0.588099 -0.25832 -0.766427 0.427093 -0.259878 -0.866057 0.362077 0.323725 -0.874129 0.310396 -0.25988 -0.914394 0.126095 -0.258321 -0.957795 -0.299524 -0.94056 0.160099 -0.138869 -0.988639 0.0575214 0.252468 -0.961937 -0.104576 0.252473 -0.961936 -0.104578 0.659655 -0.70014 -0.273239 0.659646 -0.70015 -0.273234 0.874133 0.323715 -0.362078 0.914394 -0.25988 -0.310396 -0.325003 -0.94056 0.0985887 -0.164683 -0.986108 0.021681 0.270938 -0.961936 -0.0356696 0.270937 -0.961936 -0.0356695 0.707887 -0.70015 -0.093195 0.707892 -0.700145 -0.0931961 0.957794 -0.258321 -0.126096 0.957794 -0.258322 -0.126096 0.991432 -0.00519126 -0.130525 0.980429 -0.0269478 -0.195019 0.946917 -0.00522445 -0.321436 0.896861 -0.00522443 -0.442281 0.831168 -0.0269477 -0.555369 0.793343 -0.00519121 -0.608753 0.608753 -0.00519121 -0.793343 0.555369 -0.0269476 -0.831168 0.442283 -0.00522463 -0.89686 0.321436 -0.0052246 -0.946917 0.195019 -0.026948 -0.980429 0.130523 -0.00519126 -0.991432 0.130525 -0.00519126 0.991432 0.195019 -0.0269475 0.980429 0.321434 -0.00522459 0.946918 0.442283 -0.00522463 0.89686 0.555369 -0.0269476 0.831168 0.608753 -0.00519121 0.793343 0.793343 -0.00519121 0.608753 0.831168 -0.0269477 0.555369 0.896861 -0.00522443 0.442281 0.946917 -0.00522445 0.321436 0.980429 -0.0269478 0.195019 0.991432 -0.00519126 0.130525 -0.862892 -0.498191 -0.0849876 -0.881663 -0.457862 -0.114163 -0.814542 -0.52485 -0.247089 -0.821126 -0.499142 -0.276784 -0.793548 -0.499928 -0.34692 -0.754342 -0.518067 -0.403204 -0.756925 -0.490359 -0.431988 -0.665854 -0.507965 -0.546452 -0.665662 -0.501779 -0.55237 -0.551455 -0.494348 -0.67195 -0.554533 -0.51594 -0.652916 -0.441956 -0.485636 -0.75421 -0.40209 -0.521952 -0.752257 -0.351469 -0.49988 -0.791574 -0.251696 -0.49819 -0.829732 -0.273035 -0.541768 -0.794946 -0.0885197 -0.429425 -0.898754 -0.116383 -0.4966 -0.860141 -0.917339 -0.379973 -0.118782 -0.983374 -0.129465 -0.127333 -0.46735 -0.381447 -0.797548 -0.5984 -0.381447 -0.704567 -0.598401 -0.381446 -0.704567 -0.71137 -0.381446 -0.590299 -0.711369 -0.381446 -0.590299 -0.802843 -0.381446 -0.458194 -0.802843 -0.381446 -0.458194 -0.846543 -0.382621 -0.370089 -0.880213 -0.354174 -0.315888 -0.875772 -0.381939 -0.295205 -0.917338 -0.379976 -0.118782 -0.983375 -0.129463 -0.127333 -0.933232 -0.130041 -0.334915 -0.933232 -0.130041 -0.334915 -0.861136 -0.130042 -0.491462 -0.861135 -0.130042 -0.491462 -0.76302 -0.130042 -0.633159 -0.76302 -0.130042 -0.633159 -0.641849 -0.130041 -0.755724 -0.64185 -0.13004 -0.755724 -0.501284 -0.13004 -0.855455 -0.501283 -0.130042 -0.855456 -0.306111 -0.334628 -0.891246 -0.374936 -0.382579 -0.844427 -0.467351 -0.381445 -0.797548 -0.132958 -0.129367 -0.982643 -0.132958 -0.129368 -0.982642 -0.345572 -0.130042 -0.929338 -0.345573 -0.13004 -0.929338 -0.32218 -0.381447 -0.866428 -0.124041 -0.379728 -0.916745 -0.124042 -0.379727 -0.916745 -0.0849878 -0.498189 0.862893 -0.119745 -0.449944 0.884992 -0.246687 -0.52709 0.813217 -0.281452 -0.499281 0.819453 -0.351469 -0.49988 0.791574 -0.40209 -0.521952 0.752257 -0.441956 -0.485636 0.75421 -0.544338 -0.513574 0.663278 -0.562267 -0.495562 0.662023 -0.668646 -0.501789 0.548744 -0.662704 -0.508346 0.549916 -0.756924 -0.490359 0.431988 -0.754342 -0.518067 0.403205 -0.793549 -0.499927 0.346918 -0.829733 -0.498189 0.251696 -0.800471 -0.535203 0.269822 -0.892027 -0.443361 0.0878572 -0.860631 -0.496886 0.11144 -0.124042 -0.37973 0.916743 -0.132958 -0.129365 0.982643 -0.802843 -0.381446 0.458194 -0.711369 -0.381446 0.590299 -0.711369 -0.381446 0.590299 -0.598401 -0.381446 0.704568 -0.598401 -0.381447 0.704567 -0.467351 -0.381447 0.797547 -0.46735 -0.381445 0.797548 -0.374936 -0.382579 0.844427 -0.326614 -0.349029 0.878352 -0.300195 -0.382059 0.874022 -0.124042 -0.379728 0.916744 -0.132959 -0.129367 0.982642 -0.345572 -0.13004 0.929338 -0.345573 -0.130042 0.929338 -0.501284 -0.130042 0.855455 -0.501283 -0.13004 0.855456 -0.641848 -0.13004 0.755725 -0.641849 -0.130044 0.755724 -0.76302 -0.130044 0.633158 -0.76302 -0.130044 0.633159 -0.861136 -0.130043 0.491461 -0.861135 -0.13004 0.491463 -0.889247 -0.34553 0.299747 -0.846544 -0.382621 0.370086 -0.802843 -0.381446 0.458195 -0.983375 -0.129463 0.127333 -0.983375 -0.129465 0.127332 -0.933232 -0.13004 0.334915 -0.933232 -0.130041 0.334915 -0.870058 -0.381448 0.312243 -0.917338 -0.379975 0.118782 -0.917339 -0.379974 0.118783 -0.866025 -0.5 0 -0.866025 -0.5 0 -0.991445 -0.130527 0 -0.991445 -0.130527 0 -0.92388 -0.382683 0 -0.92388 -0.382683 0 -0.593693 -0.802565 -0.0584731 -0.787386 -0.611563 -0.0775509 -0.787388 -0.61156 -0.0775503 -0.75713 -0.61156 -0.229673 -0.757129 -0.61156 -0.229673 -0.697774 -0.61156 -0.372968 -0.697772 -0.611563 -0.372968 -0.611602 -0.611564 -0.501929 -0.611605 -0.61156 -0.50193 -0.501931 -0.61156 -0.611604 -0.50193 -0.611561 -0.611604 -0.372968 -0.611561 -0.697773 -0.372968 -0.611562 -0.697773 -0.229672 -0.611562 -0.757128 -0.229673 -0.611561 -0.757129 -0.0775511 -0.611561 -0.787388 -0.0775502 -0.611563 -0.787386 -0.593691 -0.802566 -0.0584734 -0.570876 -0.802566 -0.173173 -0.570875 -0.802567 -0.173173 -0.526121 -0.802566 -0.281218 -0.526125 -0.802564 -0.281219 -0.461153 -0.802564 -0.378457 -0.461151 -0.802565 -0.378456 -0.378456 -0.802565 -0.461151 -0.378454 -0.802567 -0.461149 -0.281218 -0.802567 -0.526121 -0.281218 -0.802566 -0.526121 -0.173173 -0.802567 -0.570875 -0.173174 -0.802566 -0.570876 -0.0584731 -0.802566 -0.593691 -0.0584737 -0.802565 -0.593693 -0.0584732 -0.802565 0.593693 -0.0775509 -0.611563 0.787386 -0.0775504 -0.611561 0.787388 -0.229672 -0.611561 0.757129 -0.229672 -0.611562 0.757128 -0.372968 -0.611562 0.697773 -0.372968 -0.611561 0.697774 -0.50193 -0.611561 0.611604 -0.501931 -0.61156 0.611604 -0.611604 -0.61156 0.501931 -0.611604 -0.611561 0.50193 -0.697773 -0.611561 0.372968 -0.697773 -0.611562 0.372968 -0.757128 -0.611562 0.229672 -0.75713 -0.61156 0.229673 -0.787388 -0.61156 0.0775511 -0.787386 -0.611563 0.0775501 -0.0584735 -0.802566 0.593691 -0.173173 -0.802566 0.570876 -0.173173 -0.802567 0.570875 -0.281218 -0.802567 0.526121 -0.281218 -0.802567 0.526121 -0.378455 -0.802567 0.461149 -0.378456 -0.802565 0.461151 -0.461151 -0.802565 0.378456 -0.461151 -0.802565 0.378456 -0.526123 -0.802565 0.281219 -0.526122 -0.802567 0.281217 -0.570875 -0.802567 0.173173 -0.570876 -0.802566 0.173174 -0.593691 -0.802566 0.058473 -0.593693 -0.802565 0.0584736 -0.789764 -0.61341 0 -0.789764 -0.61341 0 -0.59471 -0.80394 0 -0.59471 -0.80394 0 -0.205528 0.978645 -0.00336256 -0.207562 0.978103 -0.0152163 -0.184076 0.98288 -0.00790173 -0.590303 0.806742 -0.0266257 -0.58371 0.811566 -0.0253621 -0.583942 0.811795 0.000364781 -0.205841 0.978585 -0.000161701 -0.20818 0.978091 -4.38768e-05 -0.20951 0.977807 -9.177e-06 -0.205538 0.978649 9.45088e-05 -0.584699 0.81125 -0.000500327 -0.5845 0.811394 -0.000446086 -0.570829 0.821069 -1.05349e-05 -0.575517 0.81779 0.000138307 -0.58513 0.810939 0.000688799 -0.205688 0.978117 -0.031305 -0.202889 0.844962 -0.494849 -0.350584 0.837639 -0.41887 -0.354487 0.830754 -0.429169 -0.469355 0.822567 -0.321075 -0.474492 0.816837 -0.328077 -0.541489 0.811139 -0.221004 -0.54629 0.806809 -0.225003 -0.582658 0.804039 -0.118452 -0.579577 0.806484 -0.116935 -0.0910187 0.831197 -0.548477 -0.0775314 0.856112 -0.510942 -0.201735 0.851873 -0.483337 -0.0407792 0.862606 -0.50423 0.0135444 0.862019 -0.506694 0.0124649 0.867128 -0.497929 -0.203904 0.978514 -0.0305486 -0.196637 0.979098 -0.0519774 -0.188372 0.981021 -0.0459695 -0.171654 0.982465 -0.0727867 -0.163113 0.984611 -0.0627327 -0.128267 0.987118 -0.0956329 -0.122522 0.98898 -0.0831103 -0.0728485 0.991404 -0.108677 -0.0711711 0.992646 -0.0979188 -0.0267159 0.993844 -0.10752 -0.0270721 0.994494 -0.101234 0.0048056 0.99467 -0.102995 0.00451333 0.99494 -0.100373 -0.20779 0.978052 0.0154059 -0.205832 0.978582 0.00321055 -0.183781 0.982935 0.0079007 -0.584453 0.810999 0.0263633 -0.591018 0.806248 0.025735 0.000452637 0.867489 -0.497456 3.79408e-05 0.995081 -0.0990647 7.75822e-06 0.995233 -0.0975302 -9.95448e-06 0.995145 -0.0984233 -8.4536e-05 0.994949 -0.100381 -0.000510657 0.867187 -0.497983 -0.000118576 0.865442 -0.501009 -2.70204e-05 0.863084 -0.50506 3.5431e-05 0.864682 -0.50232 0.000127473 0.866056 -0.499947 -0.0131325 0.994675 0.102224 -0.113259 0.989752 0.0869692 -0.108774 0.991866 0.06611 -0.179536 0.978169 0.104652 -0.151405 0.986922 0.0553398 -0.173188 0.984233 0.0359421 -0.179613 0.982732 0.0444761 -0.193738 0.978988 0.0636236 0.012202 0.867036 0.498097 0.009296 0.993369 0.114597 0.00611811 0.994296 0.106483 0.00175221 0.994944 0.100412 -0.0123746 0.994677 0.102297 -0.00401333 0.994892 0.100863 0.00395414 0.996827 0.0795065 0.00943328 0.993325 0.114962 0.0114116 0.861835 0.507061 -0.0417529 0.862421 0.504466 -0.084304 0.838949 0.53764 -0.102167 0.990304 0.0941242 -0.0973408 0.990524 0.0968845 -0.0668756 0.993962 0.0869923 -0.0710756 0.988952 0.130089 -0.0254241 0.995686 0.0892383 -0.0240462 0.994704 0.0999261 -0.0130592 0.994675 0.102232 -0.495986 0.816394 0.295803 -0.537872 0.754787 0.375488 -0.444786 0.826082 0.346055 -0.360097 0.830371 0.425223 -0.352093 0.83751 0.417861 -0.210209 0.844629 0.492355 -0.204168 0.851679 0.482658 -0.0879694 0.855921 0.509568 -0.58004 0.806016 0.117865 -0.582914 0.803939 0.11787 -0.541038 0.811411 0.221111 -0.547392 0.806722 0.222622 -0.187173 0.981187 0.0473141 -0.214021 0.976258 0.0333986 -0.205762 0.978056 0.0326977 -0.0122291 0.867432 -0.497406 -0.0044635 0.995072 -0.0990572 -0.0112787 0.861226 -0.508097 0.0785516 0.860829 -0.502795 0.0818184 0.855183 -0.511828 0.205307 0.850975 -0.483415 0.21126 0.844029 -0.492935 0.353504 0.836925 -0.417841 0.361458 0.829826 -0.425132 0.445854 0.825555 -0.345938 0.537741 0.755644 -0.373948 0.496523 0.815865 -0.296361 0.541953 0.81086 -0.22089 0.548229 0.806224 -0.222368 0.583656 0.803438 -0.117614 0.581273 0.805164 -0.117612 -0.00413841 0.99461 -0.103603 0.0273749 0.994438 -0.101704 0.0294119 0.993726 -0.107904 0.0713549 0.992576 -0.0984964 0.0768581 0.991195 -0.107823 0.122026 0.98897 -0.0839471 0.131973 0.98684 -0.093438 0.162589 0.984615 -0.0640254 0.17409 0.982228 -0.0701527 0.187933 0.981032 -0.0475109 0.197667 0.978989 -0.0500841 0.204011 0.97847 -0.0312415 0.20728 0.977779 -0.0313642 -0.000497113 0.867092 0.498149 0.000446976 0.866682 0.498861 7.47811e-05 0.865024 0.50173 -1.08562e-05 0.86282 0.505512 -1.16983e-05 0.862842 0.505474 -0.000207828 0.865805 0.500381 -4.64741e-05 0.994946 0.100415 -7.39142e-06 0.995143 0.0984436 8.34773e-06 0.995064 0.0992382 6.39314e-05 0.994917 0.100699 0.20915 0.977763 -0.0153459 0.205831 0.978582 -0.0033449 0.184973 0.982713 -0.0077683 0.584447 0.811 -0.0264794 0.592185 0.80539 -0.0257447 0.581852 0.804751 0.117575 0.207445 0.977723 0.0319914 0.583679 0.803295 0.118473 0.547276 0.806078 0.225228 0.542562 0.810342 0.221297 0.475387 0.816068 0.328696 0.47021 0.821861 0.321633 0.355048 0.830077 0.430015 0.351111 0.837046 0.419614 0.203407 0.844297 0.495769 0.202288 0.851065 0.484529 0.0762298 0.855302 0.512491 0.0771391 0.86092 0.502859 -0.0137145 0.861317 0.507883 -0.0125939 0.866621 0.498808 0.204268 0.978435 0.0306423 0.19701 0.979018 0.052061 0.188842 0.980924 0.0461229 0.172045 0.982375 0.0730755 0.163457 0.984539 0.0629623 0.1285 0.987055 0.0959682 0.122746 0.988926 0.0834173 0.0730773 0.991345 0.10906 0.0714221 0.992578 0.0984316 0.0269752 0.993782 0.108025 0.0273305 0.994442 0.101682 -0.00487308 0.994618 0.103496 -0.00455961 0.994907 0.100691 0.585273 0.810836 -0.000488404 0.205841 0.978586 0.000154282 0.2079 0.97815 5.04901e-05 0.210119 0.977676 -7.45999e-06 0.206087 0.978534 -0.000112678 0.584697 0.811252 0.000409775 0.584847 0.811144 0.000450641 0.570444 0.821336 -8.7409e-06 0.576886 0.816825 -0.000213482 0.586228 0.810146 -0.000749091 0.206078 0.97853 0.00333497 0.209388 0.977712 0.0153797 0.185162 0.982677 0.00777778 0.592662 0.805003 0.0268685 0.585043 0.810605 0.0254034 -0.992799 0.11099 0.045078 -0.975754 0.21292 0.0506779 -0.947324 0.317466 0.042341 -0.858144 0.511977 0.0383044 -0.804924 0.591882 0.0421062 -0.73122 0.681406 0.0316726 -0.977486 0.211002 9.73345e-05 -0.976387 0.21603 -3.42995e-05 -0.977015 0.213172 -0.00010979 -0.807365 0.590052 0.00105064 -0.8083 0.588771 0.000698233 -0.814636 0.579973 0.000188929 -0.818554 0.57443 1.07733e-05 -0.807548 0.589801 -0.000481302 -0.805647 0.592395 -0.00119375 -0.609968 0.0110942 0.792348 -0.0663638 0.0641891 0.995729 -0.0620943 0.0022109 0.998068 -0.00554866 0.211083 0.977452 -0.619757 0.207507 0.756864 -0.792855 0.2343 0.56257 -0.764084 0.31186 0.56473 -0.899926 0.332143 0.282513 -0.907081 0.312361 0.282195 -0.736226 -0.414585 0.534875 -0.842388 0.108607 0.527814 -0.876069 0.113485 0.468641 -0.896634 0.110381 0.428793 -0.91001 -0.33224 0.247988 -0.95337 -0.161517 0.254946 -0.983336 0.11055 0.144326 -0.129175 0.315164 0.940205 -0.269336 0.330599 0.904523 -0.283781 0.286762 0.915006 -0.569449 0.335817 0.750303 -0.120305 0.104809 0.987189 -0.219346 0.118086 0.968475 -0.363331 -0.602488 0.710632 -0.401787 0.0944617 0.910848 -0.530626 0.115466 0.839704 -0.0396281 0.859474 0.50964 -0.650206 0.694957 0.307029 -0.59198 0.686789 0.42176 -0.313732 0.876415 0.365334 -0.714768 0.680515 0.161264 -0.310017 0.939861 0.143357 -0.820744 0.505306 0.266543 -0.066576 0.677892 0.732141 -0.00364317 0.669327 0.742959 0.0262342 0.734098 0.678536 -0.390851 0.696064 0.602271 -0.276331 0.680936 0.678209 -0.0827918 0.815438 0.572892 -0.808091 0.525831 0.265502 -0.694887 0.512252 0.504707 -0.610731 0.616281 0.497198 -0.447316 0.589438 0.67266 -0.488322 0.528658 0.694307 -0.227588 0.48176 0.846233 -0.211503 0.519672 0.827772 -0.0219386 0.497724 0.867058 0.0014224 0.589655 0.807654 -0.942434 0.317621 -0.104569 -0.990588 0.110828 -0.0803244 -0.977395 0.210987 -0.0135619 -0.995521 0.0835945 -0.0441495 -0.80683 0.589674 -0.0361894 -0.857659 0.511767 -0.0501664 -0.731814 0.68077 -0.0316318 3.74094e-05 0.2114 0.9774 -7.29045e-06 0.209153 0.977883 -8.59647e-06 0.209219 0.977869 -7.97612e-05 0.21108 0.977469 -0.000499148 0.589657 0.807654 -0.000206974 0.591756 0.806117 -1.03473e-05 0.596507 0.802608 -8.69461e-06 0.596575 0.802557 7.3447e-05 0.593201 0.805054 0.000455184 0.590463 0.807064 0.00273766 0.589712 -0.807609 -0.712538 0.679019 -0.176701 -0.00967437 0.211239 -0.977387 -0.0611745 0.00155679 -0.998126 -0.0925016 0.310269 -0.946138 -0.268591 0.330588 -0.904749 -0.27781 0.286233 -0.917002 -0.565896 0.335668 -0.753053 -0.761766 0.311489 -0.568056 -0.852811 -0.0166595 -0.521955 -0.825446 0.105355 -0.554562 -0.900603 0.118047 -0.418304 -0.676336 0.508073 -0.533321 -0.618317 0.61664 -0.487278 -0.563411 0.680015 -0.469198 -0.739398 0.227337 -0.633726 -0.597624 0.204068 -0.775372 -0.599415 0.126943 -0.790308 -0.473217 0.106812 -0.874447 -0.369791 -0.352857 -0.859504 -0.280932 0.126126 -0.951404 -0.0985647 0.102059 -0.989883 -0.965246 0.109021 -0.237515 -0.879463 -0.413223 -0.236202 -0.906524 0.311938 -0.284447 -0.899792 0.332694 -0.282292 -0.82046 0.504623 -0.268704 -0.808085 0.526204 -0.264779 -0.313271 0.938693 -0.143932 -0.641598 0.694702 -0.32518 0.00110324 0.583549 -0.812077 -0.092265 0.596809 -0.797061 -0.106077 0.747945 -0.65523 -0.234914 0.580637 -0.779536 -0.437033 0.614428 -0.656872 -0.355156 0.699096 -0.620587 -0.510716 0.603641 -0.612199 0.873977 0.113627 0.472497 0.711282 0.680569 0.175795 0.00962174 0.211402 0.977352 0.558989 0.120802 0.820328 0.646121 0.213073 0.73289 0.606295 -0.0100152 0.795176 0.565513 0.336415 0.753007 0.277633 0.28723 0.916743 0.268584 0.330825 0.904664 0.761602 0.312052 0.567967 0.825524 0.105485 0.554421 0.852819 -0.0158462 0.521966 0.739393 0.227821 0.633559 0.675886 0.508892 0.533111 0.617513 0.617834 0.486784 0.562611 0.681016 0.468707 0.473328 0.107137 0.874347 0.370225 -0.348754 0.86099 0.369789 -0.358308 0.857247 0.0934651 0.280686 0.955238 0.0922731 0.3112 0.945854 0.0609388 0.0027873 0.998138 -0.0033003 0.593012 0.805187 -0.00513871 0.590451 0.807057 0.952024 0.108143 0.28628 0.95242 0.10421 0.286419 0.906266 0.312747 0.284378 0.899547 0.333417 0.282221 0.81972 0.505937 0.26849 0.807529 0.52714 0.264615 0.3125 0.939008 0.143553 0.641042 0.695764 0.324004 -0.00080367 0.585248 0.810854 0.0920532 0.598144 0.796084 0.105031 0.750262 0.652745 0.235246 0.582405 0.778116 0.435896 0.615788 0.656353 0.356431 0.697846 0.621263 0.510628 0.605043 0.610887 6.49172e-05 0.211562 -0.977365 1.03703e-05 0.210136 -0.977672 -7.84709e-06 0.209221 -0.977868 -4.80536e-05 0.211238 -0.977435 0.000459395 0.590496 -0.80704 0.000126354 0.592887 -0.805286 3.34571e-05 0.595131 -0.803629 -1.01384e-05 0.596921 -0.8023 -0.000116948 0.592527 -0.80555 -0.00050766 0.589717 -0.80761 0.976001 0.213252 0.0441037 0.992102 0.111177 0.0580806 0.947156 0.317972 0.0422972 0.80463 0.592694 0.0358451 0.856852 0.513114 0.0501917 0.730397 0.682293 0.0315624 0.317112 0.874669 -0.366599 0.720884 0.224416 -0.655716 0.826556 0.111867 -0.551625 0.764038 0.312156 -0.564627 0.899843 0.332438 -0.282432 0.907024 0.312597 -0.282118 0.971211 0.109679 -0.211472 0.852639 -0.472348 -0.223371 0.914377 0.120061 -0.386651 0.826928 0.105624 -0.552299 0.204895 0.1162 -0.971862 0.367236 -0.562203 -0.74099 0.269233 0.33064 -0.904539 0.323554 0.600001 -0.73165 0.714582 0.680903 -0.160449 0.309814 0.939965 -0.143111 0.649995 0.695472 -0.30631 0.591989 0.687393 -0.420761 0.0111493 0.211562 -0.977301 0.13536 0.69723 -0.703952 0.283501 0.28738 -0.914899 0.569339 0.336332 -0.750156 0.399598 -0.250795 -0.881716 0.479324 0.107415 -0.87104 0.603168 0.12715 -0.787414 0.601027 0.0438511 -0.798025 0.672541 0.21678 -0.707598 0.111155 0.773769 -0.623639 0.0927751 0.597932 -0.79616 0.022043 0.588513 -0.808187 0.102521 0.102743 -0.989411 0.0972419 0.311481 -0.945264 0.0624723 -0.0025841 -0.998043 -0.00817569 0.637581 -0.77034 -0.0141489 0.590425 -0.806969 0.427547 0.614516 -0.663004 0.41547 0.652782 -0.633452 0.52536 0.606804 -0.596478 0.610342 0.61695 -0.496845 0.694791 0.512682 -0.504403 0.807883 0.526227 -0.265348 0.820615 0.50559 -0.2664 0.976956 0.213439 -0.000216562 0.976355 0.216172 -7.76098e-05 0.975906 0.218192 -2.45568e-05 0.977286 0.211925 0.000139032 0.805156 0.593063 -0.00119631 0.806327 0.59147 -0.000757406 0.812266 0.583287 -0.000285972 0.81875 0.57415 6.11267e-06 0.808053 0.589109 0.000488073 0.806416 0.591348 0.00110306 0.992795 0.111028 -0.0450687 0.97603 0.211672 -0.0505951 0.947264 0.317661 -0.0422267 0.857993 0.512228 -0.0383519 0.805691 0.590833 -0.0421689 0.730913 0.68174 -0.0315826 -0.00499985 -0.999987 -0.000356205 -0.00524601 -0.999986 -5.84763e-06 -0.00524599 -0.999986 1.24817e-06 -0.0044343 -0.99999 0.000356214 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.991713 -0.00381829 -0.128413 -0.996564 0 -0.0828254 -0.972368 0.178052 -0.15099 -0.965484 0.0023871 -0.260451 -0.899388 -0.00763837 -0.437085 -0.94118 0.00962837 -0.337767 -0.838379 -0.00555994 -0.54506 -0.86851 -8.85016e-06 -0.495671 -0.780003 1.05382e-05 -0.625776 -0.769554 -0.00131867 -0.638581 -0.662782 0.00154896 -0.748811 -0.647346 -0.000444889 -0.762196 -0.500117 0.00052789 -0.865958 -0.505576 0.00128255 -0.862781 -0.338826 -0.00113674 -0.940848 -0.348532 -2.04256e-05 -0.937297 -0.23827 5.84815e-06 -0.971199 -0.134084 -0.00377772 -0.990963 -0.105734 0 -0.994394 -0.134085 0 0.99097 -0.975735 0.167062 0.141532 -0.99699 0 0.077536 -0.991713 -0.00397917 0.128413 -0.868511 -1.03232e-05 0.49567 -0.843551 -0.00464612 0.53703 -0.941198 0.0074843 0.337774 -0.908022 -0.00556819 0.418887 -0.969667 0.00208007 0.24442 -0.647345 -9.28566e-05 0.762197 -0.607319 -0.00533494 0.79444 -0.769524 0.00889042 0.638556 -0.699246 -0.00819767 0.714834 -0.791106 6.38362e-06 0.611679 -0.0874676 -0.00792839 0.996136 -0.258813 0.0023773 0.965925 -0.348531 -0.00232528 0.937294 -0.372589 -0.00084247 0.927996 -0.505576 0.00184623 0.86278 -0.445862 -0.00660966 0.895077 -0.533987 5.90273e-05 0.845493 -0.707109 0.707104 0 -0.707109 0.707104 0 -0.706187 0.706182 -0.0510673 -0.706181 0.706187 -0.0510659 -0.706182 0.691492 -0.152139 -0.706184 0.69149 -0.15214 -0.706184 0.69149 0.152139 -0.706182 0.691492 0.15214 -0.706182 0.706187 0.0510676 -0.706187 0.706182 0.0510656 -0.708356 0.649203 -0.277069 -0.706849 0.650592 -0.27766 -0.706846 0.669858 -0.227286 -0.68363 0.68824 -0.242849 -0.727696 0.627546 -0.276848 -0.675644 0.698135 0.236881 -0.706656 0.667238 0.235439 -0.721372 0.636964 0.271846 -0.708272 0.646179 0.284258 -0.706988 0.647058 0.285455 -0.0634984 0.460166 -0.885559 -0.0630303 0.458875 -0.886262 -0.187344 0.47075 -0.862147 -0.186722 0.465885 -0.86492 -0.302696 0.489882 -0.817552 -0.303343 0.480134 -0.823076 -0.406321 0.514948 -0.754806 -0.409506 0.50073 -0.76261 -0.498225 0.543582 -0.675493 -0.505081 0.524729 -0.685239 -0.576433 0.576222 -0.579391 -0.588072 0.552541 -0.590652 -0.639644 0.610845 -0.466609 -0.657363 0.581983 -0.478716 -0.682476 0.646495 -0.340986 -0.705948 0.613933 -0.353162 -0.706665 0.623894 0.333738 -0.680056 0.63763 0.361873 -0.6605 0.590244 0.464061 -0.63437 0.603461 0.483125 -0.592114 0.558773 0.580667 -0.570298 0.570089 0.591404 -0.508049 0.529367 0.679453 -0.492951 0.538013 0.68377 -0.409843 0.504827 0.759722 -0.402575 0.509672 0.760373 -0.30117 0.484233 0.821471 -0.30065 0.484664 0.821407 -0.182831 0.470292 0.863364 -0.186652 0.466067 0.864837 -0.0609225 0.463236 0.884139 -0.0628583 0.460185 0.885595 -0.00523598 0 -0.999986 -0.00523598 0 -0.999986 -0.00523586 0.999986 0 -0.00523586 0.999986 0 -0.00523598 0 0.999986 -0.00523598 0 0.999986 -0.0052361 -0.999986 -4.59682e-07 -0.00523637 -0.999986 2.91531e-06 -0.00523492 -0.999986 1.00901e-05 -0.00523658 -0.999986 -7.00473e-06 -0.00523607 -0.999986 5.57134e-06 -0.00523547 -0.999986 -2.72714e-06 -0.00523692 -0.999986 3.28816e-06 -0.00523586 -0.999986 0 -0.00523586 -0.999986 0 -0.00523725 -0.999986 -4.2941e-06 -9.10231e-08 0.00523582 -0.999986 0 0.00523597 -0.999986 1.16743e-08 0.00523593 -0.999986 -3.56714e-07 0.00523421 -0.999986 1.59944e-07 0.00523624 -0.999986 -1.19866e-07 0.00523557 -0.999986 7.83628e-08 0.00523585 -0.999986 -3.63576e-08 0.00523598 -0.999986 -2.61372e-08 0.00523599 -0.999986 0.999986 0.00523758 3.71341e-07 0.999986 0.00523586 0 0.999986 0.00523717 -2.83214e-07 0.999986 0.00523687 -1.55539e-07 7.09169e-08 0.00523491 0.999986 7.75168e-08 0.00523594 0.999986 0 0.00523583 0.999986 1.98685e-07 0.00523524 0.999986 1.72012e-08 0.00523617 0.999986 -1.56319e-07 0.00523638 0.999986 -2.15149e-07 0.00523624 0.999986 5.57913e-08 0.00523605 0.999986 1.26415e-06 0.00523629 0.999986 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.999986 0.00523621 -1.47444e-08 -0.999986 0.00523602 0 -0.999986 0.00523629 2.14274e-08 -0.00737054 -0.961308 0.275378 -0.00577243 -0.9941 0.108318 -0.00559994 -0.831456 0.555562 -0.0263456 -0.865892 0.499537 -0.0119854 -0.824451 0.565807 -0.00638801 -0.796289 0.604883 -0.00572434 -0.993867 0.110432 -0.006542 -0.958966 0.283445 -0.00651259 -0.959369 0.282081 -0.00698714 -0.897784 0.440381 -0.00592189 -0.914558 0.404412 -0.0097449 -0.746895 0.66487 -0.00626365 -0.79425 0.607559 -0.00616664 -0.98077 0.195071 -0.0544183 -0.989607 0.133102 -0.0317368 -0.980527 0.193805 -0.00624546 -0.794585 0.60712 -0.00841584 -0.484718 0.87463 -0.00661308 -0.555552 0.831455 -0.00661099 -0.167884 0.985785 -0.00615681 -0.195086 0.980767 -0.00578214 0.11043 0.993867 -0.00715572 0.195081 0.980761 -0.00668284 0.283415 0.958974 -0.00683471 0.440399 0.897776 -0.00825341 0.555552 0.831441 -0.00673116 0.664886 0.746915 -0.00841592 0.874628 0.484721 -0.00661304 0.831451 0.555559 -0.00661103 0.985786 0.167875 -0.00615671 0.980767 0.195085 -0.00578205 0.993867 -0.110433 -0.00715563 0.980761 -0.195083 -0.00668285 0.958978 -0.283403 -0.00683474 0.897773 -0.440406 -0.00825336 0.831441 -0.555551 -0.0067311 0.746915 -0.664886 -0.00841588 0.484717 -0.874631 -0.00661289 0.555559 -0.831451 -0.00661094 0.167884 -0.985785 -0.00615679 0.195083 -0.980767 -0.00578214 -0.11043 -0.993867 -0.00715577 -0.195084 -0.98076 -0.00673095 -0.664886 -0.746915 -0.00825333 -0.555545 -0.831446 -0.00683471 -0.440399 -0.897776 -0.00668285 -0.283428 -0.95897 -0.00804052 -0.825939 -0.563702 -0.00626849 -0.794861 -0.606759 -0.00638801 -0.796289 -0.604883 -0.00569492 -0.995944 -0.0897977 -0.0311375 -0.980317 -0.19496 -0.00703333 -0.959845 -0.280441 -0.00623923 -0.831453 -0.55556 -0.0241201 -0.861963 -0.506397 -0.0106584 -0.817937 -0.575209 -0.00604085 -0.985787 -0.167893 -0.00173111 -0.996773 -0.0802588 -0.0091702 -0.940897 -0.33857 -0.00630942 -0.969179 -0.246278 -0.00722098 -0.870718 -0.491731 -0.00320866 -0.914455 -0.404675 -0.00551358 -0.879077 -0.476647 -0.00990511 0.00523466 0.999937 -0.106227 0.0642383 0.992265 -0.910244 0.0219492 0.413489 -0.0396364 -0.0579846 0.99753 -0.182248 0.0186769 0.983075 -0.25713 -0.00275328 0.966373 -0.373913 0.0313952 0.926932 -0.444584 -0.0358315 0.89502 -0.513978 -0.00696484 0.857775 -0.675534 0.0363127 0.736434 -0.586786 -0.0762216 0.806147 -0.785505 0.0672159 0.615195 -0.765805 0.0404643 0.641799 -0.82819 0.00814297 0.560389 -0.868889 -0.00156295 0.495005 -0.991549 -0.0211361 0.127998 -0.964173 0.0100661 0.265085 -0.964581 0.00938221 0.263621 -0.946853 -0.00209854 0.321661 -0.91428 0.0157422 0.404776 -0.993469 -0.00156219 0.114092 -0.999915 0.000711884 0.0130529 -0.999927 2.70356e-05 0.0121013 -0.0121012 0.00523519 -0.999913 -0.0294298 0.0170291 -0.999422 -0.127995 -0.024227 -0.991479 -0.161425 0.0078107 -0.986854 -0.265099 0.00451464 -0.964211 -0.366376 0.023053 -0.930181 -0.383822 0.0048342 -0.923394 -0.513293 0.00449293 -0.858202 -0.569045 0.0184782 -0.822099 -0.560253 0.0235155 -0.827987 -0.718317 -0.035608 -0.694804 -0.7063 -0.0193351 -0.707649 -0.880602 0.0281507 -0.47302 -0.882821 0.0339643 -0.468481 -0.940767 0.000709802 -0.339054 -0.963869 0.00373361 -0.266351 -0.966377 -0.00163012 -0.257124 -0.996889 0.00840197 -0.0783737 -0.992355 0.0628052 -0.106245 -0.999951 5.1829e-05 -0.00990494 -0.999951 5.18658e-05 -0.00990499 -0.014205 0.00530968 0.999885 -0.191806 0.0218869 0.981189 -0.135467 0.00385125 0.990774 -0.075979 0.00824208 0.997075 -0.0730085 0.00687895 0.997308 -0.0160988 0.00413314 0.999862 -0.407288 0.0196839 0.913088 -0.413921 0.0290653 0.909849 -0.23948 -0.00350933 0.970895 -0.806176 -0.0458884 0.589893 -0.851325 0.0255375 0.524017 -0.777602 -0.000205631 0.628757 -0.673955 0.0460813 0.737334 -0.653595 0.018253 0.756624 -0.548187 0.00622842 0.836332 -0.999829 0.00532812 0.0177124 -0.998188 -0.039268 0.0456013 -0.985928 0.0746236 0.149591 -0.986101 0.0822502 0.144362 -0.954125 -0.0781841 0.28902 -0.963601 -0.0409884 0.264185 -0.900081 0.0584449 0.431786 -0.901997 0.0643084 0.426925 -0.884173 0.038987 0.465529 -0.0177116 0.00532788 -0.999829 -0.022524 0.00196218 -0.999744 -0.149993 0.0150675 -0.988572 -0.10396 0.0645457 -0.992485 -0.289758 -0.0321686 -0.956559 -0.428645 -0.133635 -0.893535 -0.282491 0.118229 -0.951956 -0.488932 0.0181482 -0.872133 -0.590515 -0.00241987 -0.807023 -0.635646 -0.0262097 -0.771535 -0.73676 0.060653 -0.673429 -0.774612 0.0221984 -0.632047 -0.852171 -0.00117135 -0.523263 -0.911613 0.0601093 -0.40663 -0.905977 0.0748927 -0.416649 -0.97873 -0.074041 -0.191326 -0.971602 0.0225808 -0.235542 -0.996707 -7.48438e-05 -0.0810814 -0.997136 0.0743067 -0.0140573 -0.99913 0.00544833 -0.0413555 0.0222865 0.00535133 0.999737 0.496893 0.019651 0.867589 0.0816456 0.0306484 0.99619 0.13681 0.00580405 0.99058 0.303819 0.00667622 0.952706 0.33614 -0.00636272 0.941791 0.489114 0.0171173 0.872052 0.577088 0.00468187 0.816669 0.681427 0.0121935 0.731784 0.765201 0.048405 0.641969 0.772632 0.0430142 0.633396 0.851742 0.00769291 0.523904 0.884251 0.0070762 0.466958 0.9395 0.00664436 0.342485 0.959157 -0.0361043 0.280561 0.989527 0.0195465 0.143022 0.998917 -0.0093876 0.0455801 0.9997 0.00536058 0.0239154 0.606619 -0.000328377 -0.794992 0.533748 0.0129679 -0.845544 0.496643 0.00713495 -0.867925 0.369529 0.00683519 -0.929194 0.343365 0.0178434 -0.939033 0.223371 0.0024033 -0.974731 0.143726 0.014701 -0.989508 0.116184 0.00590946 -0.99321 0.0241328 0.00526771 -0.999695 0.0239168 0.00535954 -0.9997 0.996728 0.00564271 -0.0806344 0.99758 0.0526649 -0.0454 0.977894 -0.00741834 -0.20897 0.950749 0.019736 -0.309334 0.924842 -0.00217022 -0.380345 0.856432 0.0211659 -0.515825 0.836942 0.00719463 -0.547244 0.694873 0.00747245 -0.719094 0.753781 0.0434283 -0.65569 0.707069 0.022462 -0.706788 -0.710792 -0.703402 0 -0.710792 -0.703402 0 -0.707442 -0.700087 0.0969793 -0.67029 -0.666176 0.326988 -0.71722 -0.66818 0.197815 -0.683524 -0.725421 0.0809917 -0.668341 -0.667137 0.32901 -0.740559 -0.497474 0.451765 -0.733287 -0.507825 0.452111 -0.674987 -0.38654 0.628473 -0.720242 -0.336427 0.606686 -0.690914 -0.131391 0.710897 -0.705719 -0.119312 0.698373 -0.707446 -0.0969783 -0.700083 -0.670276 -0.327007 -0.66618 -0.717219 -0.197803 -0.668185 -0.683527 -0.0809893 -0.725418 -0.668351 -0.329005 -0.667131 -0.740566 -0.451758 -0.49747 -0.733296 -0.452103 -0.507818 -0.664057 -0.650957 -0.367809 -0.711957 -0.598148 -0.367881 -0.710771 -0.66181 -0.238352 -0.690913 -0.710897 -0.131395 -0.705714 -0.698377 -0.119319 -0.710796 0 0.703398 -0.710796 0 0.703398 -0.710796 0 -0.703398 -0.710796 0 -0.703398 -0.707446 0.0969764 0.700083 -0.670276 0.327007 0.66618 -0.717222 0.197794 0.668184 -0.683529 0.0809891 0.725416 -0.668344 0.329012 0.667134 -0.740556 0.451766 0.497478 -0.733286 0.452111 0.507826 -0.674985 0.628474 0.386543 -0.720241 0.606686 0.33643 -0.69091 0.710901 0.131386 -0.705715 0.698378 0.119306 -0.707441 0.700087 -0.0969795 -0.670261 0.66619 -0.327018 -0.717213 0.668195 -0.197788 -0.683524 0.725421 -0.0809918 -0.668341 0.667138 -0.32901 -0.740559 0.497475 -0.451765 -0.733287 0.507825 -0.45211 -0.674987 0.38654 -0.628474 -0.720242 0.336426 -0.606686 -0.690914 0.131391 -0.710897 -0.705719 0.119312 -0.698373 -0.710792 0.703402 0 -0.710792 0.703402 0 -0.365662 0.701517 -0.611691 -0.0118763 0.191973 -0.981328 -0.245508 0.728828 -0.639168 -0.278942 0.686711 -0.671282 -0.155677 0.718575 -0.677801 -0.205697 0.630678 -0.748287 -0.0786417 0.789011 -0.609325 -0.415401 0.671014 -0.614151 -0.4522 0.639116 -0.62213 -0.456936 0.762451 -0.458124 -0.687664 0.579777 -0.437009 -0.623279 0.706595 -0.335033 -0.663417 0.708949 -0.23931 -0.661326 0.710268 -0.241178 -0.685196 0.705132 -0.182473 -0.786521 0.602466 -0.135721 -0.679615 0.72994 -0.0728748 -0.715778 0.698292 -0.00712598 -0.69802 0.715902 -0.0159003 -0.705802 0.708408 -0.000920381 -0.705803 0.708409 0 -0.705803 0.708409 0 -0.189739 0.674732 0.713257 -0.00957645 0.255515 0.966758 -0.0571703 0.843449 0.534159 -0.120795 0.670491 0.732018 -0.208313 0.746556 0.63187 -0.494574 0.681478 0.539429 -0.469338 0.760979 0.44792 -0.360983 0.584177 0.72693 -0.325588 0.776169 0.539957 -0.255973 0.721953 0.642855 -0.551405 0.713603 0.432114 -0.594409 0.696191 0.402487 -0.617808 0.680593 0.393836 -0.612797 0.708821 0.349359 -0.644968 0.708769 0.285766 -0.699429 0.666092 0.259077 -0.68401 0.691407 0.232564 -0.679452 0.709499 0.186965 -0.712712 0.698361 0.0658387 -0.841929 0.52851 0.108777 -0.705777 0.708382 0.00858509 -0.190918 0.962775 0.191351 -0.96488 0.257644 0.0512504 -0.981363 0.191566 0.0151551 -0.788593 0.599296 0.137714 -0.835605 0.538793 0.107079 -0.605742 0.780363 0.155275 -0.549159 0.817682 0.172687 -0.432908 0.884126 0.175819 -0.189527 0.962985 0.191674 -0.191378 0.81613 0.545258 -0.190921 0.816154 0.545382 -0.548597 0.695208 0.464464 -0.548286 0.695334 0.464644 -0.835727 0.456615 0.305063 -0.835613 0.456733 0.305198 -0.982451 0.155093 0.103615 -0.982441 0.155129 0.103653 -0.193117 0 0.981176 -0.193117 0 0.981176 -0.439696 0 0.898147 -0.439696 0 0.898147 -0.613144 0 0.789971 -0.613144 0 0.789971 -0.79619 0 0.605047 -0.79619 0 0.605047 -0.966151 0 0.257976 -0.966151 0 0.257976 -0.193108 0.981178 0 -0.193108 0.981178 0 -0.439759 0.898116 0 -0.439759 0.898116 0 -0.613179 0.789944 0 -0.613179 0.789944 0 -0.796179 0.605061 0 -0.796179 0.605061 0 -0.96615 0.257983 0 -0.96615 0.257983 0 -0.190907 -0.191353 0.962777 -0.964882 -0.0512469 0.257637 -0.981361 -0.0151599 0.191575 -0.788603 -0.137718 0.599282 -0.835617 -0.107079 0.538775 -0.605707 -0.155287 0.780388 -0.549151 -0.172689 0.817686 -0.432846 -0.175822 0.884156 -0.189537 -0.191671 0.962984 -0.191425 -0.545246 0.816127 -0.190907 -0.545387 0.816154 -0.548563 -0.464479 0.695225 -0.548277 -0.464644 0.69534 -0.835728 -0.305061 0.456615 -0.835623 -0.305186 0.456723 -0.982451 -0.103614 0.155095 -0.98244 -0.103658 0.155137 -0.190922 0.191349 -0.962774 -0.964882 0.0512469 -0.257637 -0.981361 0.0151599 -0.191575 -0.788603 0.137718 -0.599282 -0.835617 0.107079 -0.538775 -0.605707 0.155287 -0.780388 -0.549151 0.172689 -0.817686 -0.432846 0.175822 -0.884156 -0.189537 0.191671 -0.962984 -0.191383 0.545257 -0.816129 -0.19095 0.545375 -0.816152 -0.548586 0.464465 -0.695216 -0.548277 0.464643 -0.695341 -0.835728 0.30506 -0.456615 -0.835623 0.305185 -0.456724 -0.982451 0.103613 -0.155094 -0.98244 0.103658 -0.155137 -0.8685 -0.495689 0 -0.832288 -0.554341 0.00162802 -0.830595 -0.556875 0.00173173 -0.591173 -0.806542 -0.00238604 -0.553349 -0.832949 0.000816522 -0.207858 -0.978159 -0.000852764 -0.196028 -0.980598 0.000346975 -0.196028 -0.980598 -0.000346835 -0.201019 -0.979587 0.000158972 -0.553349 -0.832949 -0.000158343 -0.588898 -0.808201 0.00305273 -0.830595 -0.556875 -0.00169855 -0.8685 -0.495689 0 -0.980682 -0.195609 0 -0.980682 -0.195609 0 -0.193117 0 -0.981176 -0.193117 0 -0.981176 -0.439696 0 -0.898147 -0.439696 0 -0.898147 -0.613144 0 -0.789971 -0.613144 0 -0.789971 -0.79619 0 -0.605047 -0.79619 0 -0.605047 -0.966151 0 -0.257976 -0.966151 0 -0.257976 -0.190919 -0.962777 -0.191337 -0.19242 -0.962548 -0.190988 -0.548332 -0.820096 -0.163632 -0.545803 -0.82159 -0.164584 -0.835527 -0.539122 -0.10603 -0.825256 -0.553295 -0.11321 -0.982328 -0.184114 -0.0336569 -0.979941 -0.195461 -0.0388772 -0.191441 -0.81612 -0.545251 -0.190923 -0.816147 -0.545392 -0.548551 -0.695228 -0.464489 -0.548282 -0.695336 -0.464645 -0.835728 -0.456613 -0.305062 -0.835632 -0.456713 -0.305176 -0.982451 -0.155095 -0.103613 -0.982439 -0.155139 -0.10366 -0.455034 0.762559 0.459834 0.455026 0.763304 -0.458606 -0.686256 0.727359 -0.00100501 -0.659867 0.696672 0.281468 -0.441582 0.707465 0.551813 0.686105 0.727502 0.000923682 0.660514 0.696268 -0.280947 0.443047 0.706897 -0.551367 -0.686885 0.726766 0.000879008 -0.69295 0.720336 -0.0306071 -0.75653 0.65352 0.0239555 -0.690802 0.717559 -0.0888943 -0.716518 0.681287 -0.149837 -0.436364 0.709125 -0.553831 -0.0401725 0.745824 -0.664931 0.0165614 0.724197 -0.689395 0.0241463 0.744396 -0.667302 -0.000448684 0.744639 -0.667468 -0.000448073 0.744636 -0.667471 -0.000112936 0.744636 -0.667471 -0.000119542 0.744768 -0.667324 3.20026e-05 0.744767 -0.667324 4.13995e-05 0.744674 -0.667429 0.000118954 0.744673 -0.667429 0.000121618 0.744647 -0.667459 0.000420175 0.744646 -0.667459 -0.0108784 0.724563 -0.689123 -0.0151341 0.7166 -0.69732 -0.0271484 0.744396 -0.667186 0.0004363 0.744714 -0.667383 0.041086 0.74551 -0.665227 0.148677 0.709559 -0.688782 0.0977562 0.753184 -0.650506 0.73863 0.66896 -0.0831701 0.72085 0.687797 -0.085501 0.642975 0.76538 -0.0278581 0.705653 0.708557 -0.000688011 0.705654 0.708557 -0.000188658 0.705518 0.708692 -0.000280787 0.705519 0.708691 0.000406628 0.705659 0.708551 0.000454233 0.705659 0.708551 0.000275798 0.708807 0.705354 0.00827057 0.726232 0.686696 -0.0321917 0.659086 0.739747 -0.135573 0.685622 0.727957 -0.0010039 0.693007 0.720282 0.0305851 0.705669 0.708542 -0.000343339 0.705668 0.708542 -0.000677488 0.757839 0.651955 -0.0252103 0.691307 0.717035 0.0891933 0.717166 0.680556 0.150055 0.436705 0.708513 0.554346 0.38803 0.651095 0.65231 0.0902504 0.775535 0.62482 0.181812 0.69065 0.699962 0.0402147 0.746008 0.664722 -0.0167235 0.724098 0.689495 -0.0314732 0.762834 0.645828 -0.00752964 0.74469 0.667368 0.000412895 0.744723 0.667373 0.000434527 0.744632 0.667475 6.90645e-05 0.744633 0.667474 7.15312e-05 0.744682 0.667419 4.76657e-07 0.744682 0.667419 -5.46649e-06 0.744623 0.667486 -0.000210011 0.744623 0.667485 -0.000209218 0.744631 0.667476 -0.000438277 0.744631 0.667476 -0.000439926 0.744638 0.667468 0.0271519 0.744333 0.667257 0.0151205 0.716634 0.697285 0.0105045 0.725247 0.688409 -0.0529632 0.749733 0.659618 -0.0424086 0.742797 0.668172 -0.110586 0.735987 0.667903 -0.125552 0.749041 0.650518 -0.259034 0.719564 0.644305 -0.738045 0.669521 0.0838541 -0.721428 0.68712 0.0860697 -0.642109 0.766106 0.0278903 -0.705639 0.708572 0.000238485 -0.705639 0.708571 0.000631028 -0.705617 0.708593 0.000646283 -0.705616 0.708594 0.000110883 -0.705524 0.708686 0.000173919 -0.705523 0.708687 -0.000400035 -0.705651 0.70856 -0.000443628 -0.705651 0.708559 -0.000353477 -0.708714 0.705449 -0.0081741 -0.726103 0.68683 0.0322252 -0.659178 0.73958 0.13604 0.566511 0.71591 0.408092 0.565713 0.738406 0.367051 0.827671 0.416255 0.376421 0.242586 0.751069 0.614042 0.416703 0.72033 0.554511 0.416002 0.732504 0.538869 0.469955 0.778125 0.416731 0.642055 0.766154 0.0278181 0.842558 0.501132 0.197391 0.620539 0.778183 0.0967589 0.642932 0.709227 0.289199 0.658925 0.697208 0.282347 0.540353 0.717855 -0.438978 0.542932 0.720902 -0.430726 0.583783 0.72675 -0.361984 0.571049 0.710724 -0.410822 0.626844 0.720917 -0.295543 0.62977 0.716402 -0.300265 0.647171 0.747564 -0.149392 0.260098 0.719178 -0.644307 0.254925 0.715561 -0.650374 0.364974 0.749395 -0.55245 0.402362 0.65453 -0.640075 0.423983 0.739736 -0.522523 -0.566076 0.716353 -0.407918 -0.565424 0.738137 -0.368035 -0.829503 0.411297 -0.377835 -0.0520241 0.741981 -0.6684 -0.107727 0.735972 -0.668387 -0.139183 0.760934 -0.633725 -0.253481 0.718114 -0.64812 -0.324437 0.739971 -0.589223 -0.417092 0.720465 -0.554043 -0.416242 0.731379 -0.540211 -0.470303 0.7778 -0.416945 -0.643225 0.765169 -0.027876 -0.846777 0.49344 -0.19871 -0.619392 0.779122 -0.0965585 -0.64394 0.708658 -0.28835 -0.658117 0.698012 -0.282245 -0.539521 0.71807 0.439651 -0.541838 0.720861 0.43217 -0.583447 0.727246 0.361529 -0.570444 0.710808 0.411516 -0.626925 0.720765 0.295741 -0.630221 0.715674 0.301053 -0.647006 0.74756 0.150124 -0.33096 0.765452 0.551859 -0.473509 0.18481 0.861182 -0.382828 0.706743 0.594943 0 -0.260401 0.965501 0 -0.260401 0.965501 0 -0.703206 0.710987 0 -0.703206 0.710987 0 -0.96255 0.271103 0 -0.96255 0.271103 0 -0.970873 -0.239594 0 -0.970873 -0.239594 -0.126095 -0.258322 0.957794 -0.0931958 -0.700145 0.707892 -0.0356687 -0.961938 0.270931 0.227324 -0.970757 -0.077166 0.0315276 -0.970391 -0.239475 0.0315277 -0.97039 -0.239476 0.0771706 -0.970754 -0.227337 0.0575211 -0.988639 -0.138868 0.106184 -0.970754 -0.215319 0.14704 -0.970391 -0.191626 0.147038 -0.970392 -0.191623 0.191623 -0.970392 -0.147037 0.191629 -0.97039 -0.147042 -0.0356688 -0.961938 0.270931 -0.104576 -0.961938 0.252468 -0.104576 -0.961937 0.252469 -0.166356 -0.961937 0.216799 -0.166357 -0.961937 0.216801 -0.216802 -0.961936 0.166358 -0.2168 -0.961937 0.166356 -0.0931963 -0.700136 0.707901 -0.27324 -0.700134 0.659661 -0.273235 -0.700151 0.659644 -0.434653 -0.700151 0.566451 -0.434648 -0.700159 0.566444 -0.56644 -0.700165 0.434643 -0.566465 -0.700131 0.434666 -0.866052 -0.259899 0.42709 -0.766423 -0.258338 0.588097 -0.766429 -0.258301 0.588104 -0.588103 -0.258305 0.766429 -0.588102 -0.258306 0.766429 -0.427094 -0.259868 0.86606 -0.362077 0.323729 0.874128 -0.310392 -0.259901 0.914389 -0.126096 -0.258343 0.957788 -0.914399 -0.259858 0.310401 -0.874133 0.323715 0.362078 -0.659636 -0.700161 0.27323 -0.659665 -0.700129 0.273245 -0.252484 -0.961932 0.104583 -0.252469 -0.961937 0.104576 0.138863 -0.98864 -0.057519 0.215321 -0.970753 -0.106186 0.23946 -0.970394 -0.0315247 0.239486 -0.970388 -0.0315296 -0.27095 -0.961932 0.035672 -0.270931 -0.961938 0.0356683 -0.707875 -0.700163 0.0931925 -0.707892 -0.700145 0.0931961 -0.9578 -0.258298 0.126097 -0.957783 -0.258367 0.126091 0 -0.260401 -0.965501 0 -0.260401 -0.965501 0 -0.703206 -0.710987 0 -0.703206 -0.710987 0 -0.96255 -0.271103 0 -0.96255 -0.271103 0 -0.970873 0.239594 0 -0.970873 0.239594 -0.965488 -0.260446 0 -0.965488 -0.260446 0 -0.710987 -0.703206 0 -0.710987 -0.703206 0 -0.271103 -0.96255 0 -0.271103 -0.96255 0 0.239605 -0.97087 0 0.239605 -0.97087 0 -0.957782 -0.258367 -0.126095 -0.707892 -0.700145 -0.0931947 -0.270931 -0.961938 -0.0356694 0.0771706 -0.970754 0.227337 0.239486 -0.970388 0.0315281 0.23946 -0.970394 0.0315261 0.227324 -0.970757 0.077166 0.138863 -0.98864 0.057519 0.215321 -0.970753 0.106186 0.191629 -0.97039 0.147041 0.191623 -0.970392 0.147037 0.147038 -0.970392 0.191623 0.14704 -0.970391 0.191626 -0.27095 -0.961932 -0.0356709 -0.252484 -0.961933 -0.104582 -0.252468 -0.961937 -0.104577 -0.2168 -0.961937 -0.166356 -0.216803 -0.961936 -0.166358 -0.166357 -0.961937 -0.216801 -0.166356 -0.961937 -0.2168 -0.707875 -0.700163 -0.0931938 -0.659635 -0.700161 -0.273232 -0.659666 -0.700129 -0.273242 -0.566467 -0.700131 -0.434664 -0.566438 -0.700166 -0.434645 -0.434648 -0.700159 -0.566444 -0.434653 -0.70015 -0.56645 -0.427094 -0.259868 -0.86606 -0.588102 -0.258306 -0.766429 -0.588103 -0.258305 -0.766429 -0.766431 -0.258301 -0.588103 -0.766421 -0.258338 -0.588098 -0.866052 -0.259899 -0.42709 -0.874133 0.323715 -0.362078 -0.914399 -0.259858 -0.310401 -0.957801 -0.258298 -0.126093 -0.310396 -0.25988 -0.914394 -0.362077 0.323729 -0.874128 -0.273242 -0.700133 -0.659661 -0.273234 -0.700151 -0.659645 -0.104576 -0.961938 -0.252468 -0.104576 -0.961937 -0.252469 0.0575211 -0.988639 0.138868 0.106184 -0.970754 0.215319 0.0315277 -0.97039 0.239476 0.0315275 -0.970391 0.239475 -0.0356688 -0.961938 -0.270931 -0.0356687 -0.961938 -0.270931 -0.0931969 -0.700136 -0.707901 -0.0931951 -0.700145 -0.707892 -0.126095 -0.258321 -0.957795 -0.126095 -0.258322 -0.957794 -0.130523 -0.00519126 -0.991432 -0.195019 -0.026948 -0.980429 -0.321436 -0.0052246 -0.946917 -0.442283 -0.00522463 -0.89686 -0.555369 -0.0269477 -0.831167 -0.608754 -0.00519122 -0.793342 -0.793343 -0.00519121 -0.608753 -0.831167 -0.0269475 -0.555369 -0.89686 -0.00522443 -0.442283 -0.946916 -0.00522445 -0.321439 -0.980429 -0.0269481 -0.19502 -0.991432 -0.00518992 -0.130521 -0.991432 -0.00518992 0.130521 -0.980429 -0.0269481 0.19502 -0.946916 -0.00522445 0.321439 -0.89686 -0.00522443 0.442283 -0.831167 -0.0269475 0.555369 -0.793343 -0.00519121 0.608753 -0.608754 -0.00519121 0.793342 -0.555369 -0.0269477 0.831167 -0.442283 -0.00522463 0.89686 -0.321434 -0.00522459 0.946918 -0.195019 -0.0269475 0.980429 -0.130525 -0.00519126 0.991432 0.0849879 -0.498189 -0.862893 0.119745 -0.449944 -0.884992 0.246686 -0.52709 -0.813217 0.281453 -0.499281 -0.819453 0.351467 -0.49988 -0.791575 0.402089 -0.521952 -0.752257 0.441956 -0.485636 -0.75421 0.544339 -0.513574 -0.663277 0.562264 -0.495566 -0.662022 0.668644 -0.501794 -0.548742 0.662703 -0.508349 -0.549914 0.756925 -0.490362 -0.431985 0.754343 -0.518064 -0.403207 0.793546 -0.499926 -0.346926 0.829733 -0.498188 -0.251697 0.800472 -0.535201 -0.269823 0.892029 -0.443358 -0.0878559 0.860632 -0.496884 -0.111439 0.124042 -0.379727 -0.916745 0.132958 -0.129368 -0.982642 0.802844 -0.381443 -0.458194 0.711371 -0.381444 -0.590298 0.711371 -0.381441 -0.5903 0.5984 -0.381442 -0.70457 0.5984 -0.381443 -0.704569 0.467351 -0.381444 -0.797548 0.467351 -0.381444 -0.797549 0.374934 -0.382578 -0.844428 0.326614 -0.349029 -0.878352 0.300195 -0.382058 -0.874022 0.124042 -0.379727 -0.916745 0.132958 -0.129367 -0.982643 0.345573 -0.130041 -0.929338 0.345573 -0.130042 -0.929338 0.501284 -0.130042 -0.855455 0.501284 -0.130042 -0.855455 0.641847 -0.130042 -0.755726 0.641848 -0.130044 -0.755725 0.76302 -0.130044 -0.633157 0.76302 -0.130042 -0.633159 0.861136 -0.130042 -0.491462 0.861135 -0.130042 -0.491462 0.889248 -0.345529 -0.299747 0.84654 -0.382624 -0.370094 0.802844 -0.381448 -0.458191 0.983374 -0.129463 -0.127336 0.983374 -0.129468 -0.127335 0.933233 -0.130041 -0.334912 0.933233 -0.130041 -0.334912 0.870062 -0.381442 -0.312242 0.91734 -0.37997 -0.118784 0.917338 -0.379977 -0.118781 0 -0.499998 -0.866026 0 -0.499998 -0.866026 0 -0.130527 -0.991445 0 -0.130527 -0.991445 0 -0.382683 -0.92388 0 -0.382683 -0.92388 0 -0.499998 0.866026 0 -0.499998 0.866026 0 -0.382686 0.923879 0 -0.382686 0.923879 0 -0.130524 0.991445 0 -0.130524 0.991445 0.862893 -0.498189 0.0849864 0.881664 -0.457859 0.114162 0.814544 -0.524849 0.247088 0.821127 -0.49914 0.276785 0.793548 -0.499925 0.346924 0.754342 -0.518065 0.403208 0.756924 -0.490362 0.431985 0.665852 -0.507968 0.546451 0.66566 -0.501777 0.552373 0.551457 -0.494347 0.67195 0.554534 -0.51594 0.652915 0.441956 -0.485636 0.75421 0.402089 -0.521952 0.752257 0.351467 -0.49988 0.791575 0.251696 -0.49819 0.829732 0.273035 -0.541768 0.794946 0.0885198 -0.429425 0.898754 0.116383 -0.4966 0.860141 0.917338 -0.379976 0.118784 0.983374 -0.129468 0.127336 0.467351 -0.381444 0.797548 0.598403 -0.381443 0.704567 0.598399 -0.38145 0.704567 0.711366 -0.381451 0.5903 0.71137 -0.381444 0.590299 0.802845 -0.381443 0.458193 0.802842 -0.381448 0.458194 0.846541 -0.382624 0.370092 0.880215 -0.354174 0.315885 0.875775 -0.381933 0.295205 0.917341 -0.379969 0.118782 0.983374 -0.129463 0.127335 0.933233 -0.130041 0.334912 0.933233 -0.13004 0.334912 0.861136 -0.13004 0.491461 0.861135 -0.130044 0.491463 0.763021 -0.130044 0.633157 0.763019 -0.130047 0.633158 0.641846 -0.130046 0.755726 0.641848 -0.130042 0.755725 0.501284 -0.130042 0.855455 0.501284 -0.130042 0.855455 0.306111 -0.334629 0.891246 0.374934 -0.382578 0.844428 0.467351 -0.381444 0.797548 0.132958 -0.129367 0.982643 0.132959 -0.129365 0.982643 0.345573 -0.130042 0.929338 0.345573 -0.130041 0.929338 0.32218 -0.381446 0.866429 0.124042 -0.379727 0.916745 0.124041 -0.37973 0.916744 0.866026 -0.499998 0 0.866026 -0.499998 0 0.923879 -0.382686 0 0.923879 -0.382686 0 0.991444 -0.130531 0 0.991444 -0.130531 0 0.077551 -0.611563 -0.787386 0.0584732 -0.802565 -0.593693 0.0775504 -0.61156 -0.787388 0.229673 -0.61156 -0.75713 0.229673 -0.61156 -0.757129 0.372968 -0.61156 -0.697774 0.372968 -0.611563 -0.697772 0.50193 -0.611563 -0.611602 0.501931 -0.611557 -0.611607 0.611606 -0.611557 -0.501932 0.611605 -0.61156 -0.50193 0.697774 -0.61156 -0.37297 0.697771 -0.611564 -0.372968 0.757126 -0.611565 -0.229671 0.757121 -0.611572 -0.229668 0.787378 -0.611573 -0.0775489 0.787383 -0.611567 -0.0775511 0.0702444 -0.842842 -0.533557 0.185802 -0.768319 -0.612506 0.191428 -0.803331 -0.563928 0.281219 -0.802565 -0.526122 0.294128 -0.746831 -0.596433 0.331069 -0.853027 -0.403409 0.364047 -0.801486 -0.474436 0.461153 -0.802563 -0.378458 0.426953 -0.842842 -0.327611 0.564486 -0.768321 -0.301725 0.534119 -0.803328 -0.263403 0.570882 -0.802562 -0.173173 0.629731 -0.746822 -0.213765 0.519361 -0.853022 -0.0511531 0.592896 -0.801487 -0.0780542 0.787383 -0.611567 0.0775493 0.593693 -0.802565 0.0584741 0.787378 -0.611573 0.0775506 0.757121 -0.611572 0.229669 0.757126 -0.611566 0.229669 0.697769 -0.611566 0.372969 0.697776 -0.611557 0.372969 0.611606 -0.611557 0.501932 0.611606 -0.611557 0.501932 0.501933 -0.611557 0.611605 0.501928 -0.611564 0.611603 0.372967 -0.611563 0.697772 0.372969 -0.61156 0.697774 0.229672 -0.61156 0.757129 0.229673 -0.61156 0.75713 0.0775513 -0.61156 0.787388 0.0775502 -0.611563 0.787386 0.533566 -0.842836 0.0702434 0.612517 -0.76831 0.185803 0.563933 -0.803327 0.191429 0.526126 -0.802562 0.281221 0.59642 -0.746842 0.294127 0.403404 -0.85303 0.331065 0.474437 -0.801486 0.364046 0.378457 -0.802564 0.461153 0.327614 -0.84284 0.426955 0.301727 -0.768317 0.564491 0.263397 -0.803331 0.534117 0.173173 -0.802566 0.570876 0.213761 -0.746834 0.629719 0.0511512 -0.853029 0.51935 0.0780565 -0.801487 0.592896 0.59471 -0.80394 0 0.59471 -0.80394 0 0.789761 -0.613415 0 0.789761 -0.613415 0 0 -0.80394 -0.59471 0 -0.80394 -0.59471 0 -0.61341 -0.789764 0 -0.61341 -0.789764 0 -0.80394 0.59471 0 -0.80394 0.59471 0 -0.61341 0.789764 0 -0.61341 0.789764 0.208862 0.977825 -0.0153112 0.591394 0.805972 -0.0257293 0.58369 0.811546 -0.0264582 0.18474 0.982757 -0.00776204 0.205526 0.978646 -0.00336356 0.205841 0.978586 -0.000161584 0.208176 0.978091 -4.39189e-05 0.209508 0.977807 -9.15651e-06 0.205536 0.97865 9.45479e-05 0.58394 0.811796 0.00036287 0.585138 0.810933 0.000689584 0.575499 0.817803 0.00013754 0.570836 0.821064 -1.04789e-05 0.584509 0.811387 -0.000446087 0.584704 0.811246 -0.000499264 0.207006 0.977841 -0.0312429 0.580479 0.805723 -0.117704 0.582876 0.803989 -0.117719 0.546789 0.806841 -0.223673 0.540779 0.81128 -0.22222 0.475595 0.816853 -0.326436 0.467986 0.822798 -0.32248 0.356375 0.830787 -0.42754 0.348433 0.837921 -0.420099 0.205224 0.845027 -0.493774 0.199243 0.852095 -0.483979 0.203721 0.978535 -0.0311059 0.197246 0.979068 -0.0502086 0.187393 0.981134 -0.0475481 0.172945 0.982389 -0.0707258 0.161353 0.984793 -0.064406 0.130124 0.987042 -0.0938916 0.120265 0.989158 -0.0842812 0.0746321 0.991371 -0.107767 0.0692087 0.992743 -0.0983473 0.0278412 0.993839 -0.10728 0.025914 0.994518 -0.1013 -0.00456857 0.994673 -0.102982 -0.00486155 0.995092 -0.0988385 0.0855089 0.856255 -0.509426 0.0810745 0.837802 -0.539922 0.0407791 0.862606 -0.50423 -0.0124765 0.862055 -0.506661 -0.0133694 0.867911 -0.49654 0.205832 0.978582 0.00320984 0.584474 0.811014 0.0254226 0.591932 0.805541 0.0268544 0.184439 0.982813 0.0077604 0.209084 0.977775 0.0155024 -3.82311e-05 0.994922 -0.100652 2.3063e-05 0.99523 -0.0975591 9.87488e-06 0.995295 -0.0968892 8.39295e-05 0.995103 -0.0988477 -0.00045247 0.866717 -0.4988 -0.000127449 0.86527 -0.501307 -3.54844e-05 0.863883 -0.503693 -4.99507e-06 0.863096 -0.50504 0.000118548 0.86625 -0.499611 0.000511051 0.867979 -0.4966 0.207141 0.977785 0.0320836 0.216187 0.97569 0.0359474 0.184631 0.981726 0.0461059 0.209161 0.975569 0.0672045 0.151301 0.986942 0.0552562 0.182215 0.977043 0.110386 0.108269 0.991968 0.0654063 0.118685 0.984405 0.129848 0.0617843 0.995419 0.0729625 0.0561802 0.986172 0.155911 -0.00492299 0.994934 0.100405 -0.00429602 0.995129 0.0984883 -0.0112613 0.867045 0.498103 0.0929653 0.833795 0.544191 0.0417531 0.862421 0.504466 -0.01234 0.861803 0.507094 -6.99963e-05 0.990656 0.136387 0.0249592 0.996001 0.0857893 0.080901 0.855788 0.510962 0.206652 0.851455 0.481995 0.207885 0.844566 0.49345 0.354251 0.837225 0.416607 0.35821 0.830338 0.426878 0.4448 0.826078 0.346047 0.537884 0.754773 0.375498 0.496 0.816392 0.295785 0.541777 0.81127 0.219816 0.54686 0.806693 0.224033 0.582791 0.80397 0.11827 0.581124 0.805296 0.117446 0.00408182 0.994914 -0.100646 0.0112686 0.866669 -0.498757 0.0123925 0.861187 -0.508137 -0.0806289 0.860737 -0.502624 -0.0797899 0.855138 -0.512223 -0.207755 0.850752 -0.482762 -0.208973 0.843964 -0.49402 -0.35564 0.836642 -0.416594 -0.35959 0.829792 -0.426778 0.0044033 0.994607 -0.103618 -0.0285705 0.994412 -0.10163 -0.028252 0.993732 -0.108161 -0.0733157 0.992477 -0.098053 -0.0750824 0.991229 -0.108753 -0.12428 0.988791 -0.0827458 -0.130121 0.986917 -0.0952021 -0.164327 0.984434 -0.0623405 -0.172817 0.982303 -0.0722217 -0.188893 0.980923 -0.0459308 -0.197072 0.979017 -0.0518474 -0.204202 0.978448 -0.0306782 -0.206025 0.978041 -0.0314564 -0.445859 0.825552 -0.345941 -0.537734 0.75565 -0.373945 -0.496516 0.815869 -0.296362 -0.542678 0.810726 -0.219599 -0.547698 0.806199 -0.223762 -0.583422 0.803497 -0.118365 -0.580326 0.805961 -0.116827 4.6474e-05 0.994946 0.100415 7.39141e-06 0.995143 0.0984436 -8.34758e-06 0.995064 0.0992382 -6.39314e-05 0.994917 0.100699 0.000497113 0.867092 0.498149 0.000207827 0.865805 0.500381 1.16983e-05 0.862842 0.505474 1.08562e-05 0.86282 0.505512 -7.47811e-05 0.865024 0.50173 -0.000446976 0.866682 0.498861 -0.205831 0.978582 -0.0033449 -0.584473 0.811017 -0.0253773 -0.591048 0.806196 -0.0266395 -0.184339 0.982831 -0.00790234 -0.207917 0.978027 -0.0152562 -0.206307 0.977993 0.0310988 -0.580737 0.80549 0.118026 -0.204148 0.978449 0.0310074 -0.197611 0.978989 0.0503088 -0.187876 0.981034 0.0476883 -0.173349 0.982298 0.0709997 -0.161683 0.984723 0.0646491 -0.130365 0.986979 0.0942203 -0.120483 0.989104 0.084596 -0.074843 0.991313 0.108156 -0.0694805 0.992673 0.0988562 -0.0281123 0.993777 0.107783 -0.0261594 0.994466 0.10175 0.00461923 0.994621 0.103482 0.00481656 0.994906 0.10069 -0.583803 0.803269 0.118042 -0.547766 0.806111 0.223915 -0.541877 0.810471 0.222498 -0.476512 0.816075 0.327043 -0.468819 0.822098 0.323053 -0.356956 0.830113 0.428364 -0.348938 0.837328 0.420861 -0.205695 0.844361 0.494716 -0.199846 0.851287 0.485152 -0.0782819 0.855348 0.512105 -0.0750375 0.86101 0.503022 0.0127641 0.86135 0.507852 0.0135574 0.866611 0.498801 -0.205841 0.978586 0.000154437 -0.207906 0.978149 5.03217e-05 -0.210119 0.977676 -7.45979e-06 -0.206084 0.978534 -0.000112757 -0.585273 0.810836 -0.00048832 -0.586229 0.810145 -0.000749097 -0.576895 0.816818 -0.000213997 -0.570437 0.821341 -8.74088e-06 -0.584848 0.811143 0.000450905 -0.584704 0.811247 0.000411726 -0.208155 0.977976 0.0152892 -0.591724 0.80573 0.0257216 -0.585026 0.810586 0.0263643 -0.184531 0.982795 0.00791213 -0.206074 0.978531 0.00333631 0.976459 0.211135 0.0441472 0.992149 0.110944 0.0577185 0.947315 0.317506 0.0422276 0.806255 0.59046 0.0362045 0.857332 0.512305 0.0502515 0.73124 0.681385 0.0316733 0.806254 0.591569 0.00104777 0.977417 0.211322 -0.000109196 0.976385 0.21604 1.42504e-05 0.977083 0.212859 9.83093e-05 0.806791 0.590836 -0.00119501 0.808674 0.588257 -0.000481513 0.818564 0.574415 -3.46811e-05 0.813607 0.581416 0.000188438 0.807192 0.590289 0.00069817 0.390858 0.696053 0.602279 0.313726 0.876418 0.365331 0.71479 0.680495 0.161251 0.310022 0.939859 0.143359 0.650207 0.694966 0.307008 0.591973 0.686796 0.421757 0.214034 0.51983 0.827022 0.787149 0.233564 0.570828 0.775071 0.314112 0.548268 0.809962 0.102804 0.577402 0.914258 0.119908 0.386981 0.900278 0.332185 0.281342 0.906721 0.312328 0.283387 0.852302 -0.473071 0.223128 0.971159 0.109559 0.21177 0.00364318 0.669327 0.742959 0.0665757 0.677893 0.73214 0.039628 0.859475 0.50964 0.0827924 0.815438 0.572893 0.276338 0.680928 0.678214 0.225271 0.481175 0.847186 0.474109 0.52727 0.70513 0.454069 0.591096 0.666654 0.620322 0.616787 0.484536 0.678492 0.508309 0.53035 0.808552 0.525787 0.26418 0.820378 0.505178 0.267908 0.00455166 0.211083 0.977458 0.0935529 -0.110479 0.989466 0.586691 0.124392 0.8002 0.383524 0.0914376 0.918993 0.367531 -0.558606 0.743559 0.203892 0.116072 0.972088 0.0874563 0.100204 0.991116 0.671741 0.216329 0.708496 0.608417 0.0544572 0.791747 0.569451 0.335804 0.750307 0.281283 0.286215 0.915948 0.271982 0.330831 0.903646 0.033025 0.300981 0.953058 0.0106139 0.495819 0.868361 0.00456056 0.589654 0.807643 -0.0262342 0.734098 0.678537 0.731814 0.68077 -0.0316321 0.805534 0.591055 -0.0420646 0.992817 0.110834 -0.0450667 0.975826 0.212602 -0.0506431 0.947447 0.3171 -0.0423177 0.858473 0.511428 -0.0382847 0.000499146 0.589657 0.807654 -0.000455178 0.590463 0.807064 -7.3447e-05 0.593201 0.805054 8.69461e-06 0.596575 0.802557 1.03473e-05 0.596507 0.802608 0.000206974 0.591756 0.806117 -3.74093e-05 0.2114 0.9774 7.2904e-06 0.209153 0.977883 8.59649e-06 0.209219 0.977869 7.9761e-05 0.21108 0.977469 0.965248 0.109007 -0.237515 0.411493 0.611952 -0.675418 -0.00191973 0.589714 -0.80761 0.739394 0.227345 -0.633728 0.590542 0.202809 -0.781107 0.613809 0.129221 -0.778807 0.641604 0.694693 -0.325184 0.563418 0.680008 -0.4692 0.692752 0.512078 -0.50781 0.60871 0.616121 -0.499867 0.761777 0.311464 -0.568055 0.840348 0.0200808 -0.541675 0.84179 0.108043 -0.528882 0.313736 0.130114 -0.940553 0.341474 -0.430003 -0.835759 0.473213 0.106836 -0.874446 0.00967437 0.211239 -0.977387 0.0611743 0.0015583 -0.998126 -0.00189813 0.583413 -0.812173 0.189458 0.568989 -0.800223 0.110621 0.803131 -0.585443 0.0922655 0.596807 -0.797062 0.712538 0.679019 -0.1767 0.313268 0.938694 -0.143931 0.820847 0.504745 -0.267287 0.807605 0.526247 -0.266153 0.906889 0.311999 -0.28321 0.899428 0.332646 -0.283506 0.879458 -0.413235 -0.236199 0.900604 0.118041 -0.418306 0.510713 0.603638 -0.612204 0.395765 0.677081 -0.620429 0.5659 0.335652 -0.753057 0.280297 0.286761 -0.91608 0.265959 0.330362 -0.905608 0.0925012 0.31027 -0.946137 0.0985642 0.10206 -0.989883 -0.952023 0.108143 0.286281 -0.411178 0.613409 0.674286 -0.599244 0.127102 0.790412 -0.585563 -0.0843804 0.806223 -0.64612 0.213064 0.732893 -0.739395 0.22781 0.633559 -0.64103 0.695777 0.323998 -0.5626 0.681028 0.468704 -0.692387 0.512937 0.507441 -0.607839 0.617322 0.499445 -0.761609 0.312032 0.567968 -0.840372 0.0207593 0.541613 -0.841776 0.108183 0.528877 -0.369789 -0.358312 0.857245 -0.370224 -0.348766 0.860986 -0.473332 0.107137 0.874345 -0.00962173 0.211402 0.977352 -0.0609388 0.00278706 0.998138 -0.18898 0.570584 0.7992 -0.109263 0.806474 0.581087 -0.0920536 0.598146 0.796083 0.00223181 0.585009 0.811024 0.00225903 0.594459 0.804123 0.00513877 0.590451 0.807057 -0.711282 0.680569 0.175795 -0.3125 0.939008 0.143553 -0.820109 0.506045 0.267096 -0.807054 0.527185 0.265971 -0.906617 0.312849 0.283144 -0.899181 0.333375 0.283433 -0.952419 0.104224 0.286419 -0.874028 0.113635 0.472401 -0.510626 0.605043 0.610889 -0.395363 0.677166 0.620592 -0.565512 0.336423 0.753005 -0.280081 0.28776 0.915832 -0.265987 0.330614 0.905508 -0.0922732 0.311201 0.945854 -0.0934653 0.280685 0.955238 -0.000459396 0.590496 -0.80704 0.00050766 0.589717 -0.80761 0.000116948 0.592527 -0.80555 1.01384e-05 0.596921 -0.8023 -3.34572e-05 0.595131 -0.803629 -0.000126356 0.592887 -0.805286 4.80536e-05 0.211238 -0.977435 7.84709e-06 0.209221 -0.977868 -1.03703e-05 0.210136 -0.977672 -6.49172e-05 0.211562 -0.977365 -0.730397 0.682293 0.0315638 -0.805206 0.591495 0.0421592 -0.992779 0.111171 0.0450667 -0.975974 0.21193 0.0506058 -0.947151 0.317997 0.0422185 -0.857674 0.512764 0.0383315 -0.914381 0.120035 -0.386651 -0.714582 0.680903 -0.160449 -0.591976 0.687405 -0.42076 -0.317106 0.874671 -0.366598 -0.0927757 0.597931 -0.79616 -0.108592 0.748016 -0.654736 -0.619971 0.617448 -0.484142 -0.67833 0.50874 -0.530144 -0.764039 0.312156 -0.564626 -0.827875 0.105751 -0.550854 -0.825885 0.112713 -0.552458 -0.72089 0.224417 -0.65571 -0.649982 0.695485 -0.306307 -0.309805 0.939968 -0.143108 -0.808338 0.5262 -0.264013 -0.820258 0.505444 -0.267775 -0.900205 0.332454 -0.281257 -0.906668 0.312547 -0.283314 -0.852628 -0.472371 -0.223364 -0.971214 0.10965 -0.211469 0.00173488 0.590493 -0.807041 0.0194206 0.655081 -0.755309 -0.0220431 0.588513 -0.808187 -0.161218 0.685926 -0.709588 -0.323558 0.600002 -0.731647 -0.439425 0.615596 -0.654177 -0.399857 0.658313 -0.63776 -0.525372 0.606796 -0.596475 -0.367235 -0.562213 -0.740982 -0.204896 0.116194 -0.971863 -0.102521 0.10274 -0.989411 -0.587646 0.124708 -0.79945 -0.47933 0.107409 -0.871037 -0.399598 -0.250812 -0.881711 -0.672535 0.216779 -0.707604 -0.608126 0.058657 -0.79167 -0.569339 0.336324 -0.75016 -0.281031 0.286844 -0.915829 -0.27185 0.330864 -0.903674 -0.0972417 0.311484 -0.945263 -0.0624721 -0.00258321 -0.998043 -0.0111494 0.211562 -0.977301 -0.805932 0.592007 -0.00120271 -0.977231 0.212178 -0.000215989 -0.976623 0.214959 -7.55669e-05 -0.975909 0.218177 8.4484e-06 -0.977008 0.213204 0.000139123 -0.805636 0.59241 0.0010993 -0.807274 0.590176 0.000488561 -0.818758 0.574139 -2.51542e-05 -0.812976 0.582297 -0.000287432 -0.807113 0.590396 -0.000756495 -0.976053 0.213012 -0.0441057 -0.992123 0.111006 -0.058055 -0.947251 0.317688 -0.0423031 -0.805111 0.592038 -0.035873 -0.857199 0.512534 -0.0501804 -0.730913 0.68174 -0.031584 -0.827715 0.416162 0.376427 -0.740538 0.666873 0.0829633 -0.658915 0.697221 0.282337 0.135049 0.732683 0.667036 0.686882 0.726769 0.00087792 -0.686106 0.727501 0.00092147 -0.692951 0.720335 -0.0305837 -0.757598 0.652245 0.0249297 -0.690899 0.717432 -0.089167 -0.716436 0.68147 -0.149391 -0.625379 0.720789 -0.29894 -0.571048 0.710723 -0.410826 -0.583781 0.726748 -0.36199 -0.542925 0.720901 -0.430737 -0.540351 0.717859 -0.438975 -0.443046 0.7069 -0.551365 -0.101472 0.726591 -0.679536 -0.0410862 0.74551 -0.665227 0.0108784 0.724563 -0.689123 0.0151342 0.7166 -0.69732 0.0271483 0.744396 -0.667186 -0.000420196 0.744714 -0.667383 -0.000436316 0.744646 -0.667459 -0.000118957 0.744647 -0.667459 -0.00012162 0.744673 -0.667429 -3.20058e-05 0.744674 -0.667429 -4.13959e-05 0.744767 -0.667324 0.00011293 0.744768 -0.667324 0.00011954 0.744636 -0.667471 0.000448681 0.744636 -0.667471 0.000448075 0.744639 -0.667468 -0.0162137 0.744523 -0.667399 -0.0207557 0.722473 -0.691087 0.0514369 0.749745 -0.659725 0.0413449 0.742866 -0.668163 0.107726 0.735972 -0.668387 0.139182 0.760935 -0.633725 0.253481 0.718113 -0.648121 0.436365 0.709124 -0.553831 0.566075 0.716354 -0.407917 0.705522 0.708688 -0.000443424 0.705523 0.708687 0.000109986 0.705617 0.708594 0.00017362 0.705617 0.708593 0.000631984 0.705639 0.708571 0.000646693 0.705638 0.708572 0.000236236 0.708625 0.705542 0.00782579 0.686253 0.727363 -0.00100453 0.69296 0.720326 0.0306244 0.70565 0.708561 -0.00035231 0.70565 0.708561 -0.00039998 0.756983 0.652979 -0.0244229 0.690591 0.717638 0.0898873 0.715937 0.681922 0.149721 0.625273 0.720632 0.299538 0.570445 0.710807 0.411517 0.225332 0.808015 0.544368 0.441574 0.707482 0.551799 0.539536 0.718067 0.439637 0.0535875 0.74192 0.668343 0.0413211 0.74554 0.665179 -0.0105045 0.725247 0.688409 -0.0151205 0.716634 0.697285 -0.0271518 0.744333 0.667257 0.000438281 0.744638 0.667468 0.000439929 0.744631 0.667476 0.00021001 0.744631 0.667476 0.000209218 0.744623 0.667485 -4.72266e-07 0.744623 0.667486 5.46931e-06 0.744682 0.667419 -6.90604e-05 0.744682 0.667419 -7.15295e-05 0.744633 0.667474 -0.000412866 0.744632 0.667475 -0.000434506 0.744723 0.667373 0.00752971 0.74469 0.667368 0.016249 0.751414 0.659631 0.0237041 0.721194 0.692328 -0.0402152 0.746008 0.664722 -0.0971407 0.725989 0.680811 -0.436701 0.708523 0.554336 -0.218639 0.811828 0.541417 -0.70566 0.708551 0.000278215 -0.70566 0.70855 0.000406881 -0.705519 0.708691 0.000454815 -0.705518 0.708692 -0.000189328 -0.705655 0.708556 -0.000282057 -0.705654 0.708557 -0.000677523 -0.705667 0.708543 -0.00068677 -0.705668 0.708543 -0.000343175 -0.708865 0.705293 -0.00851097 -0.726473 0.68644 0.0322021 -0.659291 0.739472 0.136071 -0.56652 0.715896 0.408104 -0.565728 0.738402 0.367035 -0.642951 0.709218 0.289177 -0.630939 0.758847 0.161457 -0.720103 0.688561 0.0856475 -0.64207 0.766142 0.0278199 -0.685636 0.727944 -0.00100829 -0.140554 0.76047 0.633979 -0.388035 0.651092 0.65231 -0.417084 0.627309 0.657666 -0.416013 0.73249 0.53888 -0.469905 0.778169 0.416705 0.45502 0.762572 0.459827 0.541854 0.72086 0.432151 0.583454 0.727254 0.361501 0.108123 0.751829 0.650433 0.369443 0.683634 0.629409 0.473639 0.18426 0.861228 0.382874 0.706682 0.594986 0.642116 0.7661 0.0278904 0.826573 0.533777 0.178488 0.649246 0.754679 0.0945513 0.631389 0.717631 0.293859 0.659858 0.696682 0.281464 0.643221 0.765173 -0.0278761 0.721375 0.687292 -0.085132 0.630677 0.758931 -0.162082 0.725798 0.687154 -0.032196 0.658756 0.739989 -0.13586 0.739945 0.667567 -0.0826773 0.658116 0.698012 -0.282246 0.64394 0.708658 -0.288351 0.565423 0.738137 -0.368037 0.829493 0.411316 -0.377836 0.470311 0.777793 -0.416948 0.36365 0.749472 -0.553218 0.418445 0.599926 -0.681904 0.416243 0.731373 -0.540218 -0.455031 0.763297 -0.458612 -0.423991 0.739735 -0.522516 -0.419572 0.720472 -0.552159 -0.337951 0.742464 -0.578391 -0.260598 0.717653 -0.645804 -0.250752 0.721726 -0.645163 -0.126459 0.748716 -0.650717 -0.642975 0.765381 -0.0278593 -0.824653 0.537095 -0.177415 -0.649639 0.754441 -0.0937448 -0.630832 0.718114 -0.293876 -0.660522 0.696261 -0.280948 0.982443 -0.18298 -0.0363947 0.980049 -0.195454 -0.0360879 0.835884 -0.537802 -0.109851 0.825633 -0.553577 -0.109005 0.548387 -0.819938 -0.164237 0.545877 -0.82167 -0.163941 0.190912 -0.962837 -0.191043 0.192407 -0.962493 -0.191279 0.982456 -0.155065 -0.10361 0.982444 -0.155128 -0.103634 0.835722 -0.4566 -0.3051 0.83563 -0.456737 -0.305146 0.548571 -0.695178 -0.46454 0.548287 -0.695373 -0.464583 0.191439 -0.816064 -0.545335 0.190932 -0.816202 -0.545307 0.966154 0 -0.257965 0.966154 0 -0.257965 0.796198 0 -0.605037 0.796198 0 -0.605037 0.613147 0 -0.789969 0.613147 0 -0.789969 0.439702 0 -0.898144 0.439702 0 -0.898144 0.193114 0 -0.981176 0.193114 0 -0.981176 0.980687 -0.195581 0 0.196026 -0.980599 0.000347082 0.207858 -0.978159 -0.000852883 0.553363 -0.83294 0.00081628 0.59118 -0.806536 -0.00238567 0.830581 -0.556895 0.00173183 0.832249 -0.5544 0.00162972 0.868501 -0.495688 0 0.980687 -0.195581 0 0.868501 -0.495688 0 0.830581 -0.556895 -0.00169914 0.588892 -0.808206 0.00305218 0.553363 -0.83294 -0.000157073 0.201024 -0.979586 0.000159435 0.196026 -0.980599 -0.000347084 0.982444 0.0363957 -0.182974 0.965581 0.0344549 -0.257811 0.836577 0.117713 -0.535054 0.189544 0.191402 -0.963036 0.190937 0.191618 -0.962718 0.432852 0.175824 -0.884152 0.54915 0.172692 -0.817687 0.605708 0.155289 -0.780386 0.790498 0.119435 -0.600706 0.982456 0.103609 -0.155064 0.982444 0.103633 -0.155125 0.835722 0.305101 -0.456599 0.835621 0.305151 -0.45675 0.548607 0.464524 -0.695161 0.548283 0.464573 -0.695383 0.19138 0.545328 -0.816083 0.190958 0.545304 -0.816197 0.982444 -0.0363957 0.182974 0.965581 -0.0344549 0.257811 0.836577 -0.117713 0.535054 0.189544 -0.191405 0.963036 0.190922 -0.191619 0.962721 0.432852 -0.175824 0.884152 0.54915 -0.172692 0.817687 0.605708 -0.155289 0.780386 0.790498 -0.119435 0.600706 0.982456 -0.10361 0.155066 0.982444 -0.103633 0.155125 0.835722 -0.305101 0.456599 0.835621 -0.305152 0.456749 0.548583 -0.464533 0.695173 0.548283 -0.464579 0.695379 0.191423 -0.54533 0.816071 0.190916 -0.545302 0.816209 0.966152 0.257972 0 0.966152 0.257972 0 0.796187 0.605051 0 0.796187 0.605051 0 0.613182 0.789942 0 0.613182 0.789942 0 0.439765 0.898113 0 0.439765 0.898113 0 0.193104 0.981178 0 0.193104 0.981178 0 0.193114 0 0.981176 0.193114 0 0.981176 0.439702 0 0.898144 0.439702 0 0.898144 0.613147 0 0.789969 0.613147 0 0.789969 0.796198 0 0.605037 0.796198 0 0.605037 0.966154 0 0.257965 0.966154 0 0.257965 0.982446 0.182964 0.0363951 0.965579 0.257819 0.0344537 0.836565 0.535073 0.117711 0.189534 0.963037 0.191404 0.190934 0.962718 0.191622 0.432914 0.884122 0.175821 0.549158 0.817682 0.17269 0.605744 0.780361 0.155277 0.790488 0.60072 0.119433 0.982456 0.155065 0.10361 0.982446 0.155116 0.10363 0.835721 0.456597 0.305107 0.835611 0.45676 0.305162 0.548618 0.695152 0.464523 0.548292 0.695376 0.464572 0.191375 0.816081 0.545332 0.190929 0.816202 0.545307 0.00939996 0.254116 0.967128 0.056492 0.845257 0.531366 0.12011 0.669469 0.733065 0.177105 0.721378 0.669513 0.396622 0.640348 0.657758 0.291315 0.752977 0.590052 0.255647 0.722786 0.642047 0.223678 0.699738 0.67848 0.593008 0.696991 0.403168 0.551044 0.713424 0.43287 0.519289 0.696225 0.495591 0.501181 0.708883 0.496289 0.437126 0.709378 0.552905 0.659577 0.650466 0.376633 0.595904 0.707528 0.379872 0.657086 0.707717 0.259565 0.686145 0.681622 0.254159 0.679386 0.709309 0.187924 0.705201 0.703019 0.0919625 0.800164 0.595209 0.0739167 0.705777 0.708379 0.00877581 0.705805 0.708407 0 0.705805 0.708407 0 0.447803 0.603943 -0.659337 0.447023 0.649566 -0.615007 0.457985 0.762509 -0.456979 0.77496 0.476355 -0.415358 0.600614 0.702548 -0.381692 0.662544 0.708983 -0.241618 0.662231 0.710475 -0.238064 0.686353 0.704188 -0.181766 0.786761 0.602143 -0.135762 0.679127 0.730448 -0.0723366 0.711127 0.702877 -0.0161982 0.702743 0.711411 -0.00687177 0.705804 0.708406 -0.000923607 0.0121361 0.194866 -0.980755 0.0793993 0.78857 -0.609797 0.15291 0.704198 -0.693342 0.187055 0.711801 -0.677015 0.25881 0.692107 -0.673799 0.264598 0.725314 -0.635537 0.366199 0.701364 -0.611544 0.710783 0.703411 0 0.710783 0.703411 0 0.704856 0.128922 -0.697537 0.688736 0.122079 -0.71466 0.72124 0.362889 -0.590021 0.661542 0.363648 -0.655837 0.731992 0.504376 -0.458031 0.738787 0.503361 -0.448132 0.667683 0.668274 -0.328039 0.669636 0.666092 -0.328495 0.717208 0.668196 -0.197805 0.689603 0.717338 -0.0993693 0.7086 0.70125 -0.0783205 0.704852 0.697542 0.128916 0.688732 0.714665 0.122074 0.721238 0.590021 0.362893 0.66154 0.655837 0.363652 0.731991 0.458031 0.504378 0.738785 0.448133 0.503362 0.667681 0.328035 0.668278 0.669647 0.328493 0.666082 0.717217 0.197811 0.668185 0.689608 0.099366 0.717333 0.708604 0.0783179 0.701246 0.710787 0 -0.703407 0.710787 0 -0.703407 0.710787 0 0.703407 0.710787 0 0.703407 0.704851 -0.697541 -0.128927 0.688735 -0.71466 -0.122086 0.721238 -0.590025 -0.362886 0.661558 -0.655823 -0.363645 0.732002 -0.458023 -0.504369 0.738795 -0.448126 -0.503354 0.66769 -0.328031 -0.66827 0.66965 -0.328488 -0.666082 0.717214 -0.19782 -0.668185 0.689606 -0.0993682 -0.717335 0.708604 -0.0783179 -0.701246 0.704856 -0.128922 0.697537 0.688736 -0.122079 0.71466 0.72124 -0.36289 0.59002 0.661542 -0.363649 0.655836 0.731992 -0.504375 0.458033 0.738787 -0.50336 0.448132 0.667673 -0.668291 0.328025 0.669656 -0.666076 0.328487 0.717215 -0.66818 0.197832 0.689603 -0.717338 0.099369 0.7086 -0.70125 0.0783204 0.710783 -0.703411 0 0.710783 -0.703411 0 -0.494755 0.0197394 -0.868808 -0.533565 0.00719871 -0.845729 -0.369528 0.00683547 -0.929194 -0.343365 0.0178434 -0.939033 -0.22337 0.00240323 -0.974731 -0.143726 0.0147009 -0.989508 -0.116184 0.00590925 -0.99321 -0.0239149 0.00526609 -0.9997 -0.0241273 0.00536067 -0.999695 -0.606621 -0.000328121 -0.794991 -0.707063 0.0224606 -0.706794 -0.694817 0.0172049 -0.718981 -0.757279 0.00740488 -0.653049 -0.856583 0.00711482 -0.51596 -0.835579 0.0270895 -0.548702 -0.950826 -0.0137881 -0.309419 -0.998947 0.00546698 -0.0455519 -0.99595 0.0399303 -0.0805582 -0.977895 -0.00741731 -0.208967 -0.922797 0.0402116 -0.383183 -0.681424 0.0121932 0.731787 -0.0222865 0.00535133 0.999737 -0.0816455 0.0306484 0.99619 -0.495942 -0.000749304 0.868355 -0.571754 0.0447025 0.819207 -0.489118 0.0171191 0.87205 -0.302164 -0.0113606 0.953188 -0.333992 0.00681708 0.942551 -0.13681 0.00580396 0.99058 -0.771714 0.0514335 0.633887 -0.765284 0.0459497 0.642051 -0.851744 0.00769214 0.523902 -0.937698 -0.0615454 0.341957 -0.95914 0.00640173 0.282861 -0.884303 0.00707437 0.46686 -0.989527 0.0195465 0.143022 -0.999589 -0.0157875 0.0239181 -0.998947 0.0054681 0.0455527 0.0223239 0.00535154 -0.999736 0.0177118 0.00146754 -0.999842 0.111366 0.0110955 -0.993718 0.149883 0.0411382 -0.987848 0.289763 -0.0321716 -0.956558 0.310604 -0.0470218 -0.949376 0.432041 0.0472876 -0.900613 0.488933 0.0181481 -0.872133 0.590501 -0.00241709 -0.807033 0.635645 -0.0262135 -0.771536 0.69251 0.0206786 -0.721112 0.776427 -0.000289724 -0.630207 0.848833 0.0473251 -0.526539 0.800214 -0.0438733 -0.598108 0.907822 0.0555671 -0.415657 0.911164 0.067777 -0.406431 0.978731 -0.0740408 -0.191323 0.971602 0.0225882 -0.235542 0.999127 -0.00584575 -0.0413588 0.998947 0.00546368 -0.0455496 0.0143729 0.00531054 0.999883 0.0413456 0.0229619 0.998881 0.101485 -0.00695925 0.994813 0.191807 0.021887 0.981189 0.22176 0.00597472 0.975083 0.407355 0.00763387 0.913238 0.998947 0.00546737 0.0455526 0.396465 0.0206578 0.917818 0.605595 0.000267575 0.795773 0.673511 0.05856 0.736854 0.705012 0.0330809 0.708423 0.80694 -0.0151319 0.59044 0.821873 -0.0306008 0.568848 0.899977 0.0603625 0.431739 0.924577 0.00204308 0.380989 0.957029 0.00752278 0.289896 0.97782 -0.0138136 0.208992 0.985928 0.0746275 0.14959 0.997426 -0.0694901 0.0176729 0.718614 -0.0176974 -0.695184 0.881078 0.0293886 -0.472057 0.88282 0.0339643 -0.468482 0.941134 0.000454383 -0.338034 0.70781 -0.0300026 -0.705765 0.561818 0.022773 -0.826947 0.569052 0.0186729 -0.82209 0.513934 0.00449082 -0.857818 0.364782 0.00487436 -0.93108 0.384328 0.027003 -0.922802 0.159907 -0.0149696 -0.987019 0.0123732 0.00523517 -0.99991 0.0294294 0.0169809 -0.999423 0.129109 -0.0239341 -0.991342 0.264774 0.109097 -0.958119 0.999953 5.09261e-05 -0.00972553 0.966722 0.00478363 -0.255785 0.963965 -0.00244084 -0.266018 0.994367 0.0073643 -0.10574 0.995702 0.0457208 -0.080548 0.999953 5.08903e-05 -0.00972548 0.182255 0.0187683 0.983072 0.10572 -0.0223253 0.994145 0.040779 0.0240715 0.998878 0.00971887 0.00523467 0.999939 0.367648 -0.0359727 0.929269 0.25333 0.138245 0.957451 0.505539 -0.09973 0.85702 0.44274 -0.0229997 0.896355 0.590979 0.0128098 0.806585 0.620373 0.00219793 0.784304 0.705898 0.00700017 0.708279 0.710773 0.00368295 0.703412 0.786579 0.00323304 0.617481 0.81379 0.0160483 0.580937 0.82713 0.00853161 0.561947 0.868522 -0.00174937 0.495647 0.910243 0.0219527 0.413492 0.930116 -0.0106883 0.367112 0.964585 0.00922339 0.263613 0.963813 0.0105309 0.26637 0.993378 -0.0257626 0.111969 0.991625 -0.00109316 0.129144 0.999923 0.000533272 0.0123722 0.999915 2.91451e-05 0.0130453 0.00638801 -0.796289 -0.604883 0.00626849 -0.794861 -0.606759 0.00616648 -0.98077 -0.195071 0.0447209 -0.988324 -0.145658 0.00703332 -0.959845 -0.280442 0.00623922 -0.831453 -0.55556 0.0241201 -0.861963 -0.506397 0.0106584 -0.817937 -0.575209 0.00804052 -0.825939 -0.563702 0.00673095 -0.664885 -0.746915 0.00825333 -0.555545 -0.831446 0.00578214 -0.11043 -0.993867 0.00715577 -0.195084 -0.98076 0.00668285 -0.283428 -0.95897 0.00683471 -0.440399 -0.897776 0.0056099 -0.997232 -0.0741446 0.00425033 -0.985796 -0.167893 0.00649387 -0.969298 -0.245804 0.0068926 -0.874639 -0.484726 0.00320866 -0.914455 -0.404675 0.00551357 -0.879078 -0.476647 0.00578205 0.993867 -0.110433 0.00715563 0.980761 -0.195083 0.00668285 0.958978 -0.283403 0.00683474 0.897773 -0.440406 0.00825336 0.831441 -0.555552 0.0067311 0.746915 -0.664886 0.00808381 0.555553 -0.831442 0.00670667 0.484722 -0.874642 0.00664755 0.195082 -0.980764 0.00604067 0.167884 -0.985788 0.00578214 0.11043 0.993867 0.00715572 0.195081 0.980761 0.00668284 0.283415 0.958974 0.00683471 0.440399 0.897776 0.00825341 0.555552 0.831441 0.00673116 0.664886 0.746915 0.00808387 0.831442 0.555552 0.00670681 0.87464 0.484727 0.00664766 0.980764 0.195084 0.00604053 0.98579 0.167875 0.00558439 -0.997746 0.0668722 0.0313013 -0.980312 0.194958 0.00638801 -0.796289 0.604883 0.0119854 -0.824451 0.565807 0.0263456 -0.865892 0.499537 0.00559993 -0.831456 0.555562 0.00737054 -0.961308 0.275378 0.031737 -0.980527 0.193804 0.00578228 -0.993867 0.110432 0.00571388 -0.994089 0.108419 0.00654201 -0.958966 0.283446 0.00651259 -0.959369 0.282081 0.00698714 -0.897784 0.440381 0.00592188 -0.914558 0.404412 0.0097449 -0.746895 0.66487 0.00626366 -0.79425 0.607559 0.00624546 -0.794585 0.60712 0.00808382 -0.555546 0.831447 0.00670682 -0.484724 0.874641 0.00664761 -0.195085 0.980764 0.00604067 -0.167884 0.985788 0.999986 0.00523062 1.16891e-07 0.999986 0.00522913 0 0.999986 0.00523431 -4.06318e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.98455e-07 0.00523583 0.999986 -1.53359e-08 0.00523594 0.999986 -7.75986e-08 0.0052361 0.999986 -8.03957e-08 0.0052361 0.999986 0 0.00523504 0.999986 -2.03352e-07 0.00523524 0.999986 2.15105e-07 0.00523516 0.999986 -8.40962e-07 0.00523878 0.999986 7.68406e-07 0.00523491 0.999986 -0.999986 0.00523503 -9.08576e-07 -0.999986 0.00522955 1.3553e-06 -0.999986 0.00523586 0 -0.999986 0.00523392 -4.16263e-07 2.61914e-08 0.00523582 -0.999986 8.99766e-08 0.00523595 -0.999986 3.63576e-08 0.00523598 -0.999986 -7.83629e-08 0.00523585 -0.999986 1.19998e-07 0.00523557 -0.999986 0 0.00523597 -0.999986 -1.16518e-08 0.00523593 -0.999986 4.13643e-08 0.00523569 -0.999986 -4.74416e-09 0.00523587 -0.999986 0.00523607 -0.999986 5.56269e-06 0.00523658 -0.999986 -7.00473e-06 0.00523547 -0.999986 -2.72728e-06 0.00523637 -0.999986 2.92001e-06 0.0052361 -0.999986 -4.76249e-07 0.00523492 -0.999986 1.01075e-05 0.00523725 -0.999986 -4.28695e-06 0.00523586 -0.999986 0 0.00523586 -0.999986 0 0.00523692 -0.999986 3.27868e-06 0.00523598 0 0.999986 0.00523598 0 0.999986 0.00523586 0.999986 0 0.00523586 0.999986 0 0.00523598 0 -0.999986 0.00523598 0 -0.999986 0 0.461097 0.88735 0 0.461097 0.88735 0 0.461097 -0.88735 0 0.461097 -0.88735 0.0612652 0.460231 0.885683 0.0604864 0.458203 0.886787 0.182582 0.47103 0.863015 0.181886 0.46589 0.865947 0.298771 0.48861 0.819754 0.299271 0.480259 0.824493 0.403617 0.513398 0.757308 0.406438 0.500582 0.764347 0.496686 0.542448 0.677534 0.503422 0.523938 0.687063 0.575324 0.575964 0.580748 0.587222 0.55182 0.59217 0.638994 0.610818 0.467534 0.657026 0.581508 0.479755 0.682255 0.646528 0.341364 0.705932 0.613742 0.353527 0.706677 0.624054 -0.333413 0.679767 0.637882 -0.361972 0.661125 0.590293 -0.463107 0.633735 0.604039 -0.483236 0.593577 0.55867 -0.57927 0.569203 0.571152 -0.591433 0.510897 0.529034 -0.677575 0.490883 0.54024 -0.683502 0.414759 0.503405 -0.757997 0.399979 0.512994 -0.759509 0.307294 0.481586 -0.820759 0.298028 0.489053 -0.81976 0.188858 0.466389 -0.864184 0.184949 0.470591 -0.86275 0.063642 0.458952 -0.886179 0.0628611 0.460185 -0.885595 0.707865 0.649656 0.277262 0.706849 0.650592 0.277661 0.706848 0.669856 0.227285 0.683633 0.688238 0.242849 0.7277 0.627541 0.276849 0.675647 0.698133 -0.23688 0.706658 0.667235 -0.235438 0.721374 0.636961 -0.271845 0.707779 0.64652 -0.284711 0.706991 0.647055 -0.285454 0.706189 0.706179 0.0510671 0.706184 0.706185 0.0510658 0.706184 0.69149 0.152139 0.706186 0.691487 0.152139 0.706186 0.691488 -0.152138 0.706184 0.69149 -0.15214 0.706184 0.706185 -0.0510674 0.706189 0.706179 -0.0510654 0.707112 0.707102 0 0.707112 0.707102 0 0.962731 0.206311 0.174888 0.995367 0 0.0961461 0.063975 0 0.997952 0.134083 -0.00566428 0.990954 0.991715 -0.00315759 0.128416 0.959462 0.00199001 0.281832 0.941224 -0.00171088 0.33778 0.890837 0.00192167 0.454319 0.86851 -0.00149762 0.49567 0.790809 0.00165976 0.612061 0.769555 -0.00116754 0.63858 0.665737 0.00122683 0.746185 0.647343 -0.000969404 0.762198 0.521395 0.00100867 0.853315 0.505577 -0.000764464 0.862781 0.373763 0.000656687 0.927524 0.348532 -0.00161713 0.937296 0.253076 0.000772501 0.967446 0.165743 -0.00283254 0.986165 0.134085 0 -0.99097 0.99172 0 -0.128417 0.996739 -0.00602812 -0.0804676 0.972296 0.178349 -0.151105 0.106012 -0.00478074 -0.994353 0.238272 5.84788e-06 -0.971199 0.348532 -2.04243e-05 -0.937297 0.338826 -0.0011368 -0.940848 0.505576 0.00128246 -0.862781 0.500118 0.000527967 -0.865957 0.647344 -0.000444768 -0.762198 0.66278 0.00154901 -0.748813 0.769555 -0.0013187 -0.63858 0.780003 1.03658e-05 -0.625776 0.86851 -9.10678e-06 -0.495671 0.838385 -0.00555905 -0.54505 0.941181 0.00962872 -0.337765 0.899387 -0.0076389 -0.437087 0.965485 0.00238682 -0.260448 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0.943016 -0.332748 -0.00936824 0.84026 -0.542104 0.00163954 0.852778 -0.522271 -0.00190666 0.841956 -0.539543 -0.0103059 0.840448 -0.541795 0.00838458 0.839108 -0.5439 0.00119298 0.841275 -0.540606 -0.00116727 0.850944 -0.525255 0.0125114 0.867651 -0.497016 -3.80989e-05 0.859548 -0.511055 -0.00291547 0.837382 -0.546611 0 0.835429 -0.549599 4.46923e-05 0.834428 -0.551117 0.0030818 0.836579 -0.547837 0.00912079 0.839236 -0.543691 -0.0137778 0.870768 -0.491501 7.25259e-05 0.862389 -0.506246 -6.44571e-05 0.882594 -0.470135 6.91989e-05 0.878893 -0.477019 -7.2167e-05 0.897128 -0.44177 8.72172e-05 0.893119 -0.44982 0 0.902038 -0.431657 0 0.914902 -0.403675 0 0.914902 -0.403675 0 0.943016 -0.332748 0.00940759 0.840271 0.542086 -0.00163834 0.85278 0.522268 0.00190045 0.841976 0.539512 0.0102842 0.840445 0.5418 -0.00838021 0.839107 0.543901 -0.00119053 0.841274 0.540608 0.00116981 0.850944 0.525255 -0.0125089 0.867651 0.497016 3.80678e-05 0.85955 0.511052 0.00294504 0.837401 0.546582 0 0.835428 0.5496 -4.46863e-05 0.834427 0.551118 -0.00308267 0.836579 0.547837 -0.00912254 0.839236 0.543691 0.013778 0.87077 0.491498 -7.25182e-05 0.86239 0.506245 6.43658e-05 0.882592 0.470139 -6.91838e-05 0.878894 0.477017 7.2115e-05 0.897128 0.441771 0 0.914903 0.403675 0 0.914903 0.403675 0 0.90204 0.431652 -8.7207e-05 0.89312 0.449818 0 0.943016 0.332748 0.00536237 0.956442 0.291873 0.00415867 0.953221 0.302246 0.00306282 0.949929 0.31245 0 0.957069 0.289861 -5.79603e-07 0.953143 0.302519 7.99896e-07 0.954568 0.297993 7.65319e-07 0.954568 0.297992 -8.2421e-07 0.957065 0.289873 0.00257597 0.950449 0.310869 -0.000771908 0.93688 0.349651 -1.76548e-05 0.952806 0.303581 0 0.957069 0.289861 -5.79603e-07 0.953143 0.302519 7.99896e-07 0.954568 0.297993 7.65319e-07 0.954568 0.297992 -8.2421e-07 0.957065 0.289873 0.00222267 0.950825 0.309721 -0.000810462 0.936005 0.351987 -1.76536e-05 0.952805 0.303584 0 0.957069 0.289861 -5.79603e-07 0.953143 0.302519 7.99896e-07 0.954568 0.297993 7.65319e-07 0.954568 0.297992 -8.2421e-07 0.957065 0.289873 -0.000743728 0.942217 0.335003 0 0.939625 0.342206 0.00195459 0.951109 0.30885 -0.000853063 0.935031 0.354566 -1.76548e-05 0.952806 0.303581 0 0.957069 0.289861 -0.000590079 0.943016 0.332748 -0.00415683 0.953217 0.302259 -0.00311579 0.95009 0.311962 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.0038344 0.995584 -0.0937933 -0.00791104 0.997191 -0.0744869 0 0.997395 -0.0721268 -0.0275809 0.999403 -0.0208185 -0.0153373 0.998623 -0.0501689 0.0158325 0.925341 -0.378806 0.0121514 0.951155 -0.308475 0.00966405 0.965391 -0.26063 0.0033278 0.990414 -0.138092 0.00190111 0.993951 -0.109807 0.00149576 0.994907 -0.100781 0.00144094 0.995035 -0.0995121 0.0012173 0.99554 -0.0943327 0.000605337 0.996944 -0.0781215 0.000109345 0.998428 -0.0560575 0 0.999856 -0.0169583 2.25323e-05 0.999841 -0.0178579 -6.26046e-06 0.999219 -0.0395267 2.85865e-05 0.999006 -0.0445851 -0.00189042 0.994218 -0.107367 -0.000960732 0.993214 -0.116295 0.000502453 0.991091 -0.133183 -5.35021e-06 0.991942 -0.12669 2.76721e-07 0.99193 -0.126784 3.92529e-06 0.991921 -0.126859 -0.000109952 0.992327 -0.123645 -0.000268435 0.992879 -0.119127 -0.000462884 0.993536 -0.113515 -0.000309951 0.993021 -0.117935 0.000757133 0.988568 -0.150777 0.0133489 0.848319 -0.529316 -0.00109431 0.99865 -0.0519251 -0.000811756 0.996873 -0.0790156 -0.000429455 0.995305 -0.096785 -0.000256308 0.99421 -0.107457 -1.24018e-07 0.993941 -0.109913 -0.000502451 0.991091 -0.133183 6.41223e-06 0.991933 -0.126763 2.00629e-05 0.991984 -0.126367 -2.7672e-07 0.99193 -0.126784 5.34995e-06 0.991942 -0.12669 0.000960727 0.993214 -0.116295 0.00189042 0.994218 -0.107367 0.0038344 0.995584 -0.0937933 0 0.999891 -0.0147407 0.00615409 0.997377 -0.0721254 0.0153373 0.998623 -0.0501689 0.00791104 0.997191 -0.0744868 0 0.991908 -0.126959 0 0.976641 -0.214877 0 0.976641 -0.214877 0.00807547 0.997237 0.07385 0 0.997395 0.0721268 0.027707 0.999404 0.0205819 0.0155281 0.998646 0.0496433 0.00393688 0.99564 0.0931966 0.0019443 0.994267 0.106907 0.000987683 0.99325 0.115987 -0.000435311 0.991207 0.132318 3.86284e-06 0.991941 0.126702 -1.83422e-06 0.991926 0.126819 -0.000213383 0.993857 0.110669 0 0.991855 0.127369 0.000221312 0.992713 0.1205 -6.50163e-06 0.991911 0.126932 0 0.99767 0.0682258 0 0.996076 0.0885059 0 0.999891 0.0147364 0 0.99767 0.0682258 0 0.999074 0.0430316 0 0.999074 0.0430316 0 0.999891 0.0147364 0 0.996076 0.088506 0 0.994773 0.10211 4.89894e-05 0.993997 0.109407 -2.35446e-07 0.993898 0.110306 9.50634e-07 0.993919 0.110112 -0.000323346 0.99468 0.103008 0.000295023 0.990638 0.136517 -2.23653e-06 0.991864 0.1273 1.04265e-07 0.993894 0.110342 -7.52712e-07 0.993922 0.110089 -0.000987682 0.99325 0.115987 -0.0019443 0.994267 0.106907 -0.00393688 0.99564 0.0931966 0 0.999895 0.0145011 -0.00608153 0.997377 0.0721255 -0.015528 0.998646 0.0496433 -0.00807548 0.997237 0.07385 0 0.976641 0.214877 -0.00692219 0.961363 0.275198 4.26817e-05 0.965935 0.258785 -5.40211e-05 0.96118 0.275923 7.73932e-05 0.961666 0.274223 0 0.958911 0.283709 -0.0050585 0.966494 0.256641 -0.00375461 0.970329 0.241761 -1.65831e-05 0.980838 0.194824 4.26817e-05 0.965935 0.258785 -5.40211e-05 0.96118 0.275923 7.73932e-05 0.961666 0.274223 0 0.958911 0.283709 0.000725152 0.969017 0.246992 -0.000304389 0.965679 0.259739 0.00231557 0.986294 0.164983 -0.00307799 0.970012 0.243039 -1.65697e-05 0.980827 0.194879 -5.40211e-05 0.96118 0.275923 7.73932e-05 0.961666 0.274223 0 0.958911 0.283709 0.000725151 0.969017 0.246992 -0.000304389 0.965679 0.259739 0.00267691 0.988418 0.15173 -0.002608 0.96979 0.243926 -1.65567e-05 0.980817 0.194929 -1.6721e-05 0.980922 0.194401 0 0.98088 0.194614 -0.00226252 0.969627 0.244578 0.00317096 0.991039 0.133536 -0.000304389 0.965679 0.259739 0.000725151 0.969017 0.246992 4.26817e-05 0.965935 0.258785 0.00370167 0.970493 0.241099 0.00493654 0.966845 0.255317 0.000951452 0.976641 0.214877 1.57698e-05 0.961663 0.274233 0 0.958911 0.283709 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.00524603 -0.999986 1.21989e-05 0.00525307 -0.999986 -1.86233e-06 0.00443427 -0.99999 0.000356217 0.005246 -0.999986 -5.85367e-06 0.00499984 -0.999987 -0.000356211 -0.999986 -0.0052347 0 -0.999986 -0.0052347 0 0 -0.00523605 -0.999986 0 -0.00523605 -0.999986 0.999986 -0.00523605 0 0.999986 -0.00523605 0 0 -0.00523605 0.999986 0 -0.00523605 0.999986 0.982444 -0.103646 -0.155119 0.982455 -0.1036 -0.155075 0.835617 -0.30519 -0.456731 0.83572 -0.305067 -0.456624 0.548276 -0.464644 -0.695341 0.548571 -0.464474 -0.695222 0.190912 -0.191352 -0.962776 0.190912 -0.545386 -0.816154 0.191419 -0.545248 -0.816127 0.964885 -0.0512448 -0.257626 0.981365 -0.0151531 -0.191555 0.788612 -0.137714 -0.599272 0.835611 -0.107084 -0.538783 0.605708 -0.155289 -0.780386 0.54915 -0.172692 -0.817687 0.432852 -0.175824 -0.884152 0.189533 -0.191672 -0.962984 0.982445 0.155111 -0.103641 0.982456 0.155073 -0.1036 0.835607 0.456741 -0.305202 0.835717 0.456627 -0.305073 0.548281 0.695336 -0.464646 0.548606 0.695205 -0.464457 0.190924 0.962774 -0.191351 0.190928 0.816154 -0.54538 0.191371 0.816131 -0.545259 0.964883 0.257633 -0.0512482 0.981367 0.191546 -0.0151483 0.788601 0.599286 -0.13771 0.8356 0.538801 -0.107083 0.605744 0.780361 -0.155277 0.549157 0.817683 -0.17269 0.432914 0.884122 -0.175821 0.189524 0.962985 -0.191676 0.982443 -0.155122 0.103648 0.982456 -0.155075 0.103599 0.835627 -0.456721 0.30518 0.835717 -0.456627 0.305073 0.548284 -0.695334 0.464645 0.548568 -0.69522 0.464481 0.190925 -0.816147 0.545391 0.191435 -0.816121 0.545252 0.979946 -0.195434 0.0388717 0.982333 -0.184093 0.0336542 0.825242 -0.553315 0.113216 0.835521 -0.539131 0.106031 0.545817 -0.821582 0.164581 0.548332 -0.820095 0.163635 0.192418 -0.962548 0.190989 0.190923 -0.962777 0.191336 0.982444 0.103646 0.155119 0.982455 0.1036 0.155075 0.835617 0.30519 0.456731 0.835718 0.30507 0.456627 0.548276 0.464646 0.69534 0.548604 0.464456 0.695208 0.190927 0.191349 0.962773 0.190955 0.545374 0.816152 0.191377 0.545259 0.81613 0.964885 0.0512448 0.257626 0.981365 0.0151531 0.191555 0.788612 0.137714 0.599272 0.835611 0.107084 0.538783 0.605708 0.155289 0.780386 0.54915 0.172692 0.817687 0.432852 0.175824 0.884152 0.189533 0.191672 0.962984 -0.98244 -0.0363998 -0.182995 -0.982451 -0.103624 -0.155086 -0.98244 -0.103645 -0.155142 -0.835734 -0.305091 -0.456582 -0.190911 -0.545302 -0.81621 -0.191429 -0.545331 -0.81607 -0.548284 -0.464581 -0.695377 -0.965578 -0.0344592 -0.257822 -0.836582 -0.117711 -0.535046 -0.835627 -0.305145 -0.456743 -0.548565 -0.464539 -0.695184 -0.189547 -0.191405 -0.963035 -0.190917 -0.191618 -0.962722 -0.432846 -0.175822 -0.884156 -0.549151 -0.172689 -0.817686 -0.605707 -0.155287 -0.780388 -0.790491 -0.119434 -0.600716 -0.982442 0.182985 -0.0363992 -0.982452 0.155084 -0.103623 -0.982442 0.155134 -0.103642 -0.835731 0.456584 -0.305098 -0.190927 0.816203 -0.545306 -0.191381 0.81608 -0.545332 -0.548289 0.695376 -0.464575 -0.965576 0.25783 -0.034458 -0.836571 0.535064 -0.11771 -0.835617 0.456754 -0.305155 -0.548601 0.695162 -0.464529 -0.189537 0.963037 -0.191405 -0.19093 0.962719 -0.191621 -0.432908 0.884126 -0.175819 -0.549158 0.817683 -0.172687 -0.605742 0.780363 -0.155275 -0.79048 0.60073 -0.119432 -0.190924 -0.816204 0.545307 -0.191445 -0.816062 0.545336 -0.548292 -0.695369 0.464584 -0.548561 -0.695183 0.464543 -0.835636 -0.45673 0.30514 -0.83573 -0.456589 0.305093 -0.982439 -0.155145 0.103647 -0.982452 -0.155085 0.103623 -0.192409 -0.962492 0.191279 -0.190907 -0.962838 0.191042 -0.545863 -0.82168 0.16394 -0.548389 -0.819936 0.164237 -0.825647 -0.553557 0.109002 -0.835889 -0.537794 0.109847 -0.980043 -0.195481 0.0360919 -0.982439 -0.183001 0.0363989 -0.98244 0.0363998 0.182995 -0.982451 0.103624 0.155086 -0.98244 0.103645 0.155142 -0.835732 0.305093 0.456585 -0.190953 0.545304 0.816199 -0.191386 0.545328 0.816081 -0.548284 0.464575 0.695381 -0.965578 0.0344592 0.257822 -0.836582 0.117711 0.535046 -0.835627 0.305146 0.456743 -0.548599 0.464527 0.695165 -0.189547 0.191402 0.963035 -0.190932 0.191617 0.962719 -0.432846 0.175822 0.884156 -0.549151 0.172689 0.817686 -0.605707 0.155287 0.780388 -0.790491 0.119434 0.600716 0.23931 0.00695173 0.970918 0.354605 0 0.935016 0.568064 0 0.822984 0.663107 0.00695173 0.748493 0.748511 0 0.663122 0.885456 0 0.464724 0.934994 0.00695173 0.354597 0.970942 0 0.239316 1 0 0 0.992685 0.00695171 -0.120534 0.970942 0 -0.239316 0.885456 0 -0.464724 0.822964 0.00695168 -0.568051 0.748511 0 -0.663122 0.568064 0 -0.822984 0.464712 0.0069517 -0.885435 0.354605 0 -0.935016 0.120537 0 -0.992709 0.120537 0 -0.992709 -0.120537 0 -0.992709 -0.120537 0 -0.992709 -0.354605 0 -0.935016 -0.464712 0.00695173 -0.885435 -0.568065 0 -0.822983 -0.74851 0 -0.663123 -0.822964 0.00695172 -0.568052 -0.885456 0 -0.464724 -0.970942 0 -0.239316 -0.992685 0.00695171 -0.120534 -1 0 0 -0.970942 0 0.239316 -0.934994 0.00695173 0.354597 -0.885456 0 0.464724 -0.74851 0 0.663123 -0.663107 0.00695166 0.748493 -0.568065 0 0.822983 -0.354605 0 0.935016 -0.23931 0.00695174 0.970918 -0.120536 0 0.992709 0.120536 0 0.992709 -0.578881 1.63182e-06 0.815412 -0.100607 0 0.994926 -0.430151 5.07803e-07 -0.902757 -0.707107 1.41003e-05 -0.707107 -0.586346 0.00386389 -0.810052 -0.775057 -1.31675e-06 -0.631891 -0.965926 3.64449e-06 -0.258818 -0.875466 0.00582062 -0.483245 -0.951255 0.00155661 -0.308402 0.258818 0.00136202 -0.965925 0.180839 0 -0.983513 -0.258818 0 -0.965926 -0.182035 0.00192188 -0.98329 0.707106 0.00151425 -0.707106 0.584302 -7.22641e-08 -0.811536 0.430101 -7.26857e-06 -0.902781 0.997636 -2.73932e-06 -0.0687135 0.951042 0.00156089 -0.309059 0.965926 0.000370211 -0.258819 0.873957 -3.01181e-07 -0.486004 0.774536 -2.34319e-06 -0.632529 0.997418 -3.78404e-06 0.0718207 0.965925 0.0012544 0.258819 0.977466 0.00210921 0.211081 0.707106 0.000982781 0.707106 0.839487 -2.44604e-06 0.54338 0.920309 4.62326e-06 0.391192 0.216224 0 0.976344 0.434028 0.00453911 0.900888 0.258818 0.000641926 0.965926 0.474467 -4.15755e-06 0.880273 0.670215 3.03488e-06 0.742167 -0.258818 -1.48201e-05 0.965926 -0.461796 0.00513532 0.886971 -0.312989 0.00198916 0.949755 -0.707989 0.00143731 0.706222 -0.707106 0.00141779 0.707106 -0.817643 -5.4607e-06 0.575726 -0.997581 2.41534e-06 -0.0695082 -0.990214 -2.60552e-06 0.139555 -0.965925 0.00156781 0.258818 -0.947818 0.000869004 0.31881 -0.902404 4.077e-06 0.430891 -0.578881 1.6648e-06 0.815412 -0.100607 0 0.994926 -0.430148 5.32673e-07 -0.902758 -0.707106 1.41416e-05 -0.707108 -0.586349 0.00386381 -0.810049 -0.775057 -1.3618e-06 -0.631891 -0.965926 3.58834e-06 -0.258818 -0.875466 0.00582056 -0.483245 -0.951254 0.00155663 -0.308405 0.258817 0.00136201 -0.965925 0.180839 0 -0.983513 -0.258818 0 -0.965926 -0.182035 0.00192187 -0.98329 0.707107 0.00151426 -0.707105 0.584299 -1.0658e-07 -0.811538 0.430101 -7.29372e-06 -0.902781 0.997636 -2.71055e-06 -0.0687135 0.951043 0.00156089 -0.309056 0.965926 0.000370269 -0.258818 0.873932 -3.27164e-07 -0.486048 0.774539 -2.36565e-06 -0.632526 0.997417 -3.75531e-06 0.071825 0.965925 0.00125439 0.258818 0.977469 0.00210941 0.211068 0.707108 0.000982794 0.707105 0.839484 -2.39819e-06 0.543385 0.920309 4.67594e-06 0.391192 0.216224 0 0.976344 0.43401 0.00453869 0.900897 0.258817 0.000641913 0.965926 0.474467 -4.18458e-06 0.880273 0.670214 2.99668e-06 0.742168 -0.258818 -1.48053e-05 0.965926 -0.461791 0.00513517 0.886974 -0.312989 0.00198915 0.949755 -0.707989 0.00143735 0.706222 -0.707105 0.00141781 0.707107 -0.817646 -5.50709e-06 0.575722 -0.997582 2.35759e-06 -0.0694992 -0.990215 -2.66251e-06 0.13955 -0.965925 0.00156781 0.258818 -0.947818 0.000869004 0.31881 -0.902401 4.02493e-06 0.430897 -0.578881 1.59885e-06 0.815412 -0.100606 0 0.994926 -0.430154 4.82697e-07 -0.902756 -0.707108 1.4059e-05 -0.707106 -0.586349 0.00386381 -0.810049 -0.775053 -1.27177e-06 -0.631896 -0.965926 3.70063e-06 -0.258818 -0.875497 0.00581917 -0.483189 -0.951254 0.00155663 -0.308405 0.258817 0.00136201 -0.965925 0.180839 0 -0.983513 -0.258817 0 -0.965926 -0.182034 0.00192188 -0.98329 0.707107 0.00151418 -0.707105 0.584305 -1.06287e-07 -0.811534 0.430101 -7.29372e-06 -0.902781 0.997636 -2.71055e-06 -0.0687135 0.951041 0.00156094 -0.309062 0.965926 0.000370156 -0.258818 0.873965 -3.26386e-07 -0.485989 0.774535 -2.36572e-06 -0.632531 0.997417 -3.75531e-06 0.071825 0.965925 0.00125439 0.258818 0.977465 0.00210911 0.211085 0.707108 0.000982794 0.707105 0.839495 -2.49348e-06 0.543368 0.920309 4.57058e-06 0.391192 0.216224 0 0.976344 0.43401 0.00453869 0.900897 0.258817 0.000641913 0.965926 0.474467 -4.18458e-06 0.880273 0.670214 2.99668e-06 0.742168 -0.258817 -1.48349e-05 0.965926 -0.461802 0.00513547 0.886968 -0.312989 0.00198918 0.949755 -0.707989 0.00143727 0.706222 -0.707107 0.00141778 0.707105 -0.817646 -5.50709e-06 0.575722 -0.997582 2.35759e-06 -0.0694992 -0.990215 -2.66251e-06 0.13955 -0.965925 0.00156781 0.258818 -0.947818 0.000869004 0.31881 -0.902401 4.02493e-06 0.430897 -0.578881 1.59885e-06 0.815412 -0.100607 0 0.994926 -0.430154 4.82697e-07 -0.902756 -0.707106 1.40589e-05 -0.707108 -0.586343 0.00386391 -0.810054 -0.775061 -1.45183e-06 -0.631886 -0.965927 3.47611e-06 -0.258813 -0.875435 0.00582207 -0.483301 -0.951254 0.00155674 -0.308405 0.258816 0.00136202 -0.965926 0.180838 0 -0.983513 -0.258818 0 -0.965926 -0.182035 0.00192187 -0.98329 0.70711 0.00151421 -0.707102 0.584299 -1.74917e-07 -0.811538 0.430107 -7.34376e-06 -0.902778 0.997635 -2.71041e-06 -0.0687314 0.951045 0.00156074 -0.309049 0.965925 0.000370374 -0.258822 0.8739 -3.27943e-07 -0.486106 0.774539 -2.36565e-06 -0.632526 0.997417 -3.75531e-06 0.071825 0.965924 0.00125442 0.258822 0.977465 0.00210922 0.211085 0.70711 0.000982859 0.707103 0.839484 -2.30209e-06 0.543385 0.920313 4.78169e-06 0.391184 0.216224 0 0.976344 0.433973 0.00453791 0.900914 0.258816 0.000641916 0.965926 0.474467 -4.18458e-06 0.880273 0.670214 2.99668e-06 0.742168 -0.258818 -1.48348e-05 0.965926 -0.461802 0.00513542 0.886968 -0.312989 0.00198915 0.949755 -0.707981 0.00143717 0.70623 -0.707105 0.00141781 0.707107 -0.817652 -5.59988e-06 0.575712 -0.997583 2.35716e-06 -0.0694813 -0.990216 -2.6623e-06 0.139542 -0.965926 0.00156787 0.258813 -0.94781 0.000868705 0.318835 -0.902401 3.92162e-06 0.430897 0.307656 0.49726 0.811222 0.307656 0.49726 0.811222 0.492854 0.497259 0.714023 0.492854 0.497258 0.714023 0.649411 0.497258 0.575326 0.649407 0.497263 0.575326 0.768221 0.497264 0.403195 0.768225 0.497258 0.403194 0.842393 0.497257 0.20763 0.842389 0.497262 0.207631 0.8676 0.497262 0 0.8676 0.497262 0 0.84239 0.497262 -0.207629 0.842392 0.497257 -0.207631 0.768224 0.497257 -0.403196 0.768222 0.497263 -0.403193 0.649409 0.497263 -0.575324 0.64941 0.497258 -0.575328 0.492854 0.497258 -0.714023 0.492854 0.497259 -0.714023 0.307656 0.497259 -0.811222 0.307656 0.497259 -0.811222 0.104578 0.49726 -0.861276 0.104578 0.49726 -0.861276 -0.104577 0.49726 -0.861276 -0.104578 0.49726 -0.861276 -0.307656 0.497259 -0.811222 -0.307656 0.497259 -0.811222 -0.492855 0.497259 -0.714022 -0.492853 0.497261 -0.714022 -0.649408 0.497261 -0.575326 -0.64941 0.497259 -0.575326 -0.768224 0.497259 -0.403195 -0.768222 0.497262 -0.403195 -0.84239 0.497262 -0.207631 -0.842389 0.497262 -0.207631 -0.8676 0.497262 0 -0.8676 0.497262 0 -0.842389 0.497262 0.207631 -0.84239 0.497262 0.207631 -0.768222 0.497262 0.403194 -0.768223 0.497259 0.403195 -0.649409 0.49726 0.575327 -0.649409 0.497261 0.575325 -0.492854 0.497261 0.714021 -0.492854 0.497259 0.714022 -0.307656 0.49726 0.811222 -0.307656 0.49726 0.811222 -0.104578 0.49726 0.861276 -0.104578 0.49726 0.861276 0.104578 0.49726 0.861276 0.104578 0.49726 0.861276 0.0855433 0.704518 0.704512 0.251658 0.704518 0.663568 0.251658 0.704518 0.663568 0.403148 0.704517 0.584062 0.403145 0.704523 0.584056 0.531204 0.704524 0.470605 0.531211 0.704513 0.470613 0.628401 0.704512 0.32981 0.628394 0.70452 0.329806 0.689062 0.70452 0.169838 0.689068 0.704514 0.16984 0.70969 0.704514 0 0.70969 0.704514 0 0.689068 0.704514 -0.16984 0.689061 0.704521 -0.169839 0.628394 0.70452 -0.329807 0.6284 0.704513 -0.329809 0.531211 0.704514 -0.470611 0.531203 0.704523 -0.470606 0.403145 0.704522 -0.584058 0.403148 0.704517 -0.584061 0.251658 0.704517 -0.663569 0.251658 0.704518 -0.663568 0.0855433 0.704518 -0.704512 0.0855433 0.704518 -0.704512 -0.0855432 0.704518 -0.704512 -0.0855432 0.704518 -0.704512 -0.251658 0.704518 -0.663568 -0.251658 0.704518 -0.663568 -0.403149 0.704517 -0.584061 -0.403149 0.704515 -0.584063 -0.53121 0.704514 -0.470612 -0.531204 0.704523 -0.470605 -0.628391 0.704524 -0.329805 -0.628394 0.70452 -0.329807 -0.689062 0.704521 -0.169838 -0.689068 0.704514 -0.16984 -0.70969 0.704514 0 -0.70969 0.704514 0 -0.689068 0.704514 0.16984 -0.689062 0.70452 0.169839 -0.628394 0.70452 0.329807 -0.628391 0.704523 0.329806 -0.531204 0.704522 0.470607 -0.53121 0.704515 0.47061 -0.403149 0.704516 0.584062 -0.403149 0.704517 0.584061 -0.251658 0.704517 0.663569 -0.251658 0.704518 0.663568 -0.0855432 0.704518 0.704512 -0.0855432 0.704518 0.704512 0.0855433 0.704518 0.704512 0.0314189 0.965431 0.258757 0.0924305 0.965431 0.243719 0.0924302 0.965432 0.243718 0.148069 0.965432 0.214515 0.148072 0.96543 0.21452 0.195108 0.96543 0.172851 0.195104 0.965432 0.172847 0.2308 0.965432 0.121133 0.230799 0.965432 0.121133 0.253082 0.965432 0.0623789 0.253082 0.965432 0.0623789 0.260656 0.965432 0 0.260656 0.965432 0 0.253082 0.965432 -0.0623789 0.253082 0.965432 -0.0623789 0.2308 0.965432 -0.121133 0.2308 0.965432 -0.121133 0.195104 0.965432 -0.172847 0.195108 0.96543 -0.17285 0.148072 0.965431 -0.214519 0.148069 0.965432 -0.214515 0.0924298 0.965432 -0.243718 0.0924306 0.965431 -0.243719 0.0314189 0.965431 -0.258757 0.0314189 0.965431 -0.258758 -0.0314188 0.965431 -0.258757 -0.0314188 0.965431 -0.258757 -0.0924305 0.965431 -0.243719 -0.0924299 0.965432 -0.243718 -0.148069 0.965432 -0.214515 -0.14807 0.965431 -0.214517 -0.195104 0.965432 -0.172848 -0.195104 0.965432 -0.172847 -0.2308 0.965432 -0.121133 -0.2308 0.965432 -0.121133 -0.253082 0.965432 -0.0623789 -0.253082 0.965432 -0.0623789 -0.260656 0.965432 0 -0.260656 0.965432 0 -0.253082 0.965432 0.0623789 -0.253082 0.965432 0.0623789 -0.230799 0.965432 0.121133 -0.2308 0.965432 0.121133 -0.195104 0.965432 0.172847 -0.195104 0.965432 0.172848 -0.14807 0.965431 0.214517 -0.148069 0.965432 0.214515 -0.0924301 0.965432 0.243718 -0.0924306 0.965431 0.243719 -0.0314188 0.965431 0.258757 -0.0314188 0.965431 0.258758 0.0314189 0.965431 0.258757 0.116486 0.257053 -0.959351 0.342689 0.257053 -0.903597 0.342689 0.257054 -0.903597 0.548976 0.257054 -0.795329 0.548976 0.257054 -0.795329 0.723359 0.257054 -0.640839 0.72336 0.25705 -0.64084 0.855703 0.257049 -0.449108 0.855702 0.257054 -0.449108 0.938315 0.257054 -0.231274 0.938318 0.257045 -0.231273 0.9664 0.257044 0 0.9664 0.257044 0 0.938318 0.257044 0.231275 0.938316 0.257054 0.231272 0.855702 0.257054 0.449108 0.855703 0.257049 0.449109 0.72336 0.257049 0.64084 0.723359 0.257054 0.640839 0.548976 0.257054 0.795329 0.548976 0.257054 0.795329 0.342689 0.257054 0.903597 0.342689 0.257052 0.903597 0.116486 0.257052 0.959352 0.116486 0.257055 0.959351 -0.116486 0.257055 0.959351 -0.116486 0.257052 0.959351 -0.34269 0.257052 0.903597 -0.342689 0.257054 0.903597 -0.548977 0.257054 0.795329 -0.548977 0.257054 0.795329 -0.723358 0.257054 0.640841 -0.723359 0.257049 0.640841 -0.855703 0.257049 0.449108 -0.855705 0.257044 0.449108 -0.938318 0.257043 0.231275 -0.938318 0.257044 0.231275 -0.9664 0.257044 0 -0.9664 0.257044 0 -0.938318 0.257044 -0.231275 -0.938318 0.257043 -0.231275 -0.855704 0.257044 -0.449109 -0.855703 0.257049 -0.449107 -0.723359 0.25705 -0.640841 -0.723359 0.257054 -0.64084 -0.548977 0.257054 -0.795329 -0.548977 0.257054 -0.795329 -0.342689 0.257054 -0.903597 -0.342689 0.257053 -0.903597 -0.116486 0.257053 -0.959351 -0.116486 0.257052 -0.959352 0.116487 0.257052 -0.959352 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -0.258818 0 0.965926 -0.258818 0 0.965926 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.965926 0 0.258819 -0.965926 0 0.258819 0 0 1 0 0 1 0 0 1 0.980786 0 0.195088 0.980786 0 0.195088 0.831468 0 0.555572 0.831468 0 0.555572 0.55557 0 0.831469 0.55557 0 0.831469 0.19509 0 0.980785 0.19509 0 0.980785 1 0 0 1 0 0 1 0 0 0.19509 0 -0.980785 0.19509 0 -0.980785 0.55557 0 -0.831469 0.55557 0 -0.831469 0.831468 0 -0.555572 0.831468 0 -0.555572 0.980786 0 -0.195088 0.980786 0 -0.195088 0 0 -1 0 0 -1 0 0 -1 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.365571 -0.930784 0 -0.365571 -0.930784 0 -0.656461 -0.75436 0 -0.656461 -0.75436 0 -0.87137 -0.490627 0 -0.87137 -0.490627 0 -0.985426 -0.170102 0 -0.985426 -0.170102 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -0.0687042 -0.997637 0 -0.0957452 -0.985494 0.140122 -0.034245 -0.999414 0 -0.0545185 -0.998513 0 -0.100634 -0.994924 0 -0.0924193 -0.992395 -0.081305 -0.12921 -0.991617 0 -0.0177472 -0.995072 -0.0975556 -0.0273763 -0.999625 0 0.0204794 -0.99979 0 0.0458831 -0.995781 -0.0794668 0.0571621 -0.998365 0 0.0953623 -0.995443 0 0.118753 -0.989266 -0.0851503 0.131835 -0.991272 0 0.169709 -0.985494 0 0.190932 -0.977523 -0.089408 0.205766 -0.978601 0 0.174302 -0.984692 0 0.121005 -0.992036 0.0349636 0.0669168 -0.997759 0 -0.0949378 -0.995483 0 -0.0949378 -0.995483 0 -0.201912 -0.979404 0 -0.201912 -0.979404 -5.31355e-08 -0.201912 -0.979404 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.985426 0.170102 0 -0.985426 0.170102 0 -0.87137 0.490627 0 -0.87137 0.490627 0 -0.656461 0.75436 0 -0.656461 0.75436 0 -0.365571 0.930784 0 -0.365571 0.930784 0 -0.201912 0.979404 0 -0.201912 0.979404 -4.81989e-08 -0.201912 0.979404 0 -0.0949378 0.995483 0 -0.0949378 0.995483 0 0.121079 0.992643 0 0.170023 0.98318 0.0667023 0.0667667 0.997769 0 0.205766 0.978601 0 0.190932 0.977523 -0.089408 0.169709 0.985494 0 0.131835 0.991272 0 0.118753 0.989266 -0.0851501 0.0953624 0.995443 0 0.0571621 0.998365 0 0.0458831 0.995781 -0.0794665 0.0204795 0.99979 0 -0.0178323 0.999841 0 -0.0273046 0.997005 -0.0723508 -0.0545185 0.998513 0 -0.0927263 0.995692 0 -0.100429 0.992897 -0.0637975 -0.12921 0.991617 0 -0.102828 0.994699 0 -0.0684959 0.994613 0.0778088 -0.034245 0.999414 0 0 1 0 0 1 0 0.100391 0.994948 0 0.194932 0.979989 0.0402773 0.29118 0.956668 0.000581704 0.381189 0.924497 0 0.555569 0.831471 0 0.555569 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980785 0.195091 0 0.980785 0.195091 0 0.373362 -0.905516 0.201599 0.19509 -0.980785 0 0.119426 -0.990316 0.0707904 0.291912 -0.956445 0 0.555569 -0.831471 0 0.555569 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980785 -0.195091 0 0.980785 -0.195091 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.70711 -0.707104 0 0.70711 -0.707104 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.70711 0.707104 0 0.70711 0.707104 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.70711 0.707104 0 -0.70711 0.707104 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.70711 -0.707104 0 -0.70711 -0.707104 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.508593 -0.508588 0.694745 0.508589 -0.50859 0.694747 0.694746 -0.186157 0.694747 0.694746 -0.186158 0.694747 0.694746 0.186157 0.694747 0.694746 0.186158 0.694747 0.508592 0.508587 0.694747 0.50859 0.508591 0.694746 0.186156 0.694747 0.694746 0.186157 0.694747 0.694747 -0.186156 0.694747 0.694747 -0.186157 0.694747 0.694746 -0.508593 0.508588 0.694745 -0.508589 0.50859 0.694747 -0.694746 0.186157 0.694747 -0.694746 0.186158 0.694747 -0.694746 -0.186157 0.694747 -0.694746 -0.186158 0.694747 -0.508592 -0.508587 0.694747 -0.50859 -0.508591 0.694746 -0.186156 -0.694747 0.694746 -0.186157 -0.694747 0.694746 0.186156 -0.694747 0.694747 0.186157 -0.694747 0.694746 0.258818 -0.965926 0 0.258818 -0.965926 0 0.70711 -0.707104 0 0.70711 -0.707104 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.70711 0.707104 0 0.70711 0.707104 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.70711 0.707104 0 -0.70711 0.707104 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.70711 -0.707104 0 -0.70711 -0.707104 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.508593 -0.508588 0.694745 0.508589 -0.50859 0.694747 0.694746 -0.186157 0.694747 0.694746 -0.186158 0.694747 0.694746 0.186157 0.694747 0.694746 0.186158 0.694747 0.508592 0.508587 0.694747 0.50859 0.508591 0.694746 0.186156 0.694747 0.694746 0.186157 0.694747 0.694747 -0.186156 0.694747 0.694747 -0.186157 0.694747 0.694746 -0.508593 0.508588 0.694745 -0.508589 0.50859 0.694747 -0.694746 0.186157 0.694747 -0.694746 0.186158 0.694747 -0.694746 -0.186157 0.694747 -0.694746 -0.186158 0.694747 -0.508592 -0.508587 0.694747 -0.50859 -0.508591 0.694746 -0.186156 -0.694747 0.694746 -0.186157 -0.694747 0.694746 0.186156 -0.694747 0.694747 0.186157 -0.694747 0.694746 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258823 0.965925 0 -0.258823 0.965925 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258823 -0.965925 0 -0.258823 -0.965925 0 0.508588 -0.50859 0.694748 0.508591 -0.508588 0.694747 0.694746 -0.186157 0.694747 0.694746 -0.186158 0.694747 0.694746 0.186157 0.694747 0.694746 0.186158 0.694747 0.508589 0.508591 0.694747 0.50859 0.508588 0.694748 0.186156 0.694746 0.694747 0.186155 0.694747 0.694747 -0.186159 0.694746 0.694746 -0.186157 0.694746 0.694747 -0.508588 0.50859 0.694748 -0.508591 0.508588 0.694747 -0.694746 0.186157 0.694747 -0.694746 0.186158 0.694747 -0.694746 -0.186157 0.694747 -0.694746 -0.186158 0.694747 -0.508589 -0.508591 0.694747 -0.50859 -0.508588 0.694748 -0.186159 -0.694745 0.694748 -0.186157 -0.694747 0.694746 0.186156 -0.694747 0.694747 0.186155 -0.694747 0.694747 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258823 0.965925 0 -0.258823 0.965925 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258823 -0.965925 0 -0.258823 -0.965925 0 0.508588 -0.50859 0.694748 0.508591 -0.508588 0.694747 0.694746 -0.186157 0.694747 0.694746 -0.186158 0.694747 0.694746 0.186157 0.694747 0.694746 0.186158 0.694747 0.508589 0.508591 0.694747 0.50859 0.508588 0.694748 0.186156 0.694746 0.694747 0.186155 0.694747 0.694747 -0.186159 0.694746 0.694746 -0.186157 0.694746 0.694747 -0.508588 0.50859 0.694748 -0.508591 0.508588 0.694747 -0.694746 0.186157 0.694747 -0.694746 0.186158 0.694747 -0.694746 -0.186157 0.694747 -0.694746 -0.186158 0.694747 -0.508589 -0.508591 0.694747 -0.50859 -0.508588 0.694748 -0.186159 -0.694745 0.694748 -0.186157 -0.694747 0.694746 0.186156 -0.694747 0.694747 0.186155 -0.694747 0.694747 0.135598 0.694227 0.706868 0.135598 0.694226 0.706869 0.0843053 0.702303 0.706868 0.0843053 0.702303 0.706868 0.0325581 0.706596 0.706868 0.0325581 0.706596 0.706868 -0.0193645 0.707081 0.706868 -0.0193645 0.70708 0.706868 -0.0711828 0.703755 0.706868 -0.0711829 0.703755 0.706867 0.085867 0.703962 0.705028 0.085867 0.703962 0.705028 -0.0673279 0.705975 0.705029 -0.0673275 0.705976 0.705028 -0.0486387 0.706271 0.706269 -0.0486387 0.706271 0.706269 -0.142774 0.692544 0.707106 -0.142774 0.692544 0.707106 0 0.707107 0.707106 0 0.707107 0.707106 -0.260388 0.662978 0.701897 -0.260388 0.662977 0.701897 -0.467583 0.537315 0.701897 -0.467582 0.537314 0.701898 -0.620657 0.349462 0.701898 -0.620656 0.34946 0.7019 -0.701894 0.12116 0.701901 -0.701897 0.121162 0.701897 0.70022 0.139283 0.700209 0.700217 0.139284 0.700211 0.593617 0.396639 0.700212 0.593611 0.396638 0.700218 0.396638 0.593613 0.700216 0.396638 0.593613 0.700216 0.139281 0.700215 0.700214 0.139282 0.700215 0.700214 -0.707107 0 0.707107 -0.707107 0 0.707107 0.707112 0 0.707102 0.707112 0 0.707102 0.707112 0 0.707102 -0.701898 -0.12116 0.701898 -0.701894 -0.121161 0.701901 -0.620655 -0.349461 0.7019 -0.620658 -0.349462 0.701898 -0.467582 -0.537314 0.701898 -0.467583 -0.537314 0.701897 -0.260388 -0.662977 0.701897 -0.260389 -0.662978 0.701896 0.139281 -0.700215 0.700214 0.139282 -0.700215 0.700214 0.396638 -0.593613 0.700216 0.396638 -0.593612 0.700216 0.593612 -0.396636 0.700217 0.593616 -0.396641 0.700212 0.700218 -0.139283 0.700211 0.700219 -0.139284 0.700209 -0.142774 -0.692544 0.707106 -0.142774 -0.692544 0.707106 0 -0.707107 0.707106 0 -0.707107 0.707106 -0.0673279 -0.705976 0.705028 -0.0673275 -0.705975 0.705029 0.085867 -0.703961 0.705028 0.085867 -0.703962 0.705028 -0.0486387 -0.706271 0.706269 -0.0486386 -0.706271 0.706269 -0.0711829 -0.703755 0.706867 -0.0711829 -0.703755 0.706868 -0.0193645 -0.707081 0.706868 -0.0193645 -0.70708 0.706868 0.0325581 -0.706596 0.706868 0.0325582 -0.706596 0.706868 0.0843053 -0.702303 0.706868 0.0843052 -0.702303 0.706868 0.135598 -0.694226 0.706869 0.135598 -0.694227 0.706868 0.164477 0.701691 -0.693237 0.164271 0.70237 -0.692597 0.162949 0.708814 -0.686317 0.161046 0.714017 -0.681355 -0.113385 0.722333 -0.682187 -0.103818 0.709029 -0.697495 -0.118903 0.735373 -0.667149 -0.117916 0.732117 -0.670896 -0.115381 0.721486 -0.682748 0.145517 0.692062 -0.707018 0.120008 0.696885 -0.70707 0.1071 0.725462 -0.679879 0.0932347 0.701036 -0.707005 0.0674342 0.703913 -0.707078 0.0511533 0.730158 -0.681361 0.0404263 0.706066 -0.706991 0.0144817 0.70698 -0.707085 -0.00488112 0.730165 -0.683253 -0.0126117 0.707125 -0.706976 -0.0385513 0.706071 -0.707091 -0.0605842 0.725502 -0.685549 -0.065581 0.704206 -0.70696 -0.0913665 0.70119 -0.707096 -0.115386 -0.721514 -0.682717 -0.117932 -0.732168 -0.670837 -0.118903 -0.735373 -0.667149 -0.113385 -0.722333 -0.682187 -0.103818 -0.709029 -0.697495 -0.0913665 -0.70119 -0.707096 -0.0588649 -0.704913 -0.706847 -0.0681678 -0.731982 -0.677905 -0.0385513 -0.706071 -0.707091 -0.00472861 -0.707351 -0.706847 -0.0131943 -0.73979 -0.672709 0.0144816 -0.70698 -0.707085 0.0494354 -0.705637 -0.706847 0.0425681 -0.743472 -0.66741 0.0674341 -0.703913 -0.707078 0.103309 -0.699782 -0.706847 0.0988098 -0.742955 -0.662008 0.120008 -0.696885 -0.70707 0.155632 -0.690014 -0.706865 0.154044 -0.732619 -0.662978 0.162949 -0.708814 -0.686316 0.164272 -0.702363 -0.692604 0.164474 -0.7017 -0.693228 0.258817 0.965926 0 0.258817 0.965926 0 0.70711 0.707104 0 0.70711 0.707104 0 0.965923 0.258831 0 0.965923 0.258831 0 0.965923 -0.258831 0 0.965923 -0.258831 0 0.70711 -0.707104 0 0.70711 -0.707104 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.7071 -0.707113 0 -0.7071 -0.707113 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.7071 0.707113 0 -0.7071 0.707113 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707105 0.707109 0 0.707105 0.707109 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258823 0.965925 0 -0.258823 0.965925 0 -0.707105 0.707109 0 -0.707105 0.707109 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.258823 -0.965925 0 -0.258823 -0.965925 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258823 0.965925 0 -0.258823 0.965925 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258823 -0.965925 0 -0.258823 -0.965925 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.70711 -0.707104 0 0.70711 -0.707104 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.70711 0.707104 0 0.70711 0.707104 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.70711 0.707104 0 -0.70711 0.707104 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.70711 -0.707104 0 -0.70711 -0.707104 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258815 -0.965927 0 0.258815 -0.965927 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258823 0.965925 0 -0.258823 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258815 -0.965927 0 0.258815 -0.965927 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707111 0.707102 0 0.707111 0.707102 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707111 0.707102 0 -0.707111 0.707102 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.258815 -0.965927 0 -0.258815 -0.965927 0 -0.707108 0.707106 0 -0.707108 0.707106 0 0.707106 0.707108 0 0.707106 0.707108 0 0.707106 -0.707108 0 0.707106 -0.707108 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 0.555571 -0.831469 0 0.555571 -0.831469 0 0.195088 -0.980786 0 0.195088 -0.980786 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555571 0.831469 0 0.555571 0.831469 0 -0.555571 0.831469 0 -0.555571 0.831469 0 -0.195088 0.980786 0 -0.195088 0.980786 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0 -1 0 0 -1 0 -0.980784 -0.195095 0 -0.965728 -0.258766 0.0202336 -0.896879 -0.442276 0 -0.793349 -0.608767 0 -0.706847 -0.70685 0.0270136 -0.19509 -0.980785 0 -0.258766 -0.965728 0.0202353 -0.442293 -0.89687 0 -0.608763 -0.793352 0 -1 0 0 -1 0 0 -1 0 0 -0.258819 0.965926 0 -0.195018 0.980432 -0.0268419 -0.608637 0.793191 0.0202337 -0.555574 0.831467 0 -0.793349 0.608767 0 -0.831393 0.55552 0.0135413 -0.965728 0.258766 -0.0202336 -0.980784 0.195095 0 0 1 0 0 1 0 0.980786 0.195087 0 0.980786 0.195087 0 0.831469 0.555571 0 0.831469 0.555571 0 0.55557 0.83147 0 0.55557 0.83147 0 0.195088 0.980786 0 0.195088 0.980786 0 1 0 0 1 0 0 1 0 0 -0.195099 0.980784 0 -0.195099 0.980784 0 -0.555561 0.831476 0 -0.555561 0.831476 0 0.55557 0.83147 0 0.55557 0.83147 0 0.195095 0.980784 0 0.195095 0.980784 0 0.555577 -0.831465 0 0.555577 -0.831465 0 0.195086 -0.980786 0 0.195086 -0.980786 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.989476 0.144696 0 -0.989476 0.144696 -2.11622e-07 -0.989476 0.144696 0 -0.989476 0.144696 0 -0.994291 -0.106705 0 -0.994291 -0.106705 0 -0.818995 -0.5738 0 -0.818995 -0.5738 0 -0.439845 -0.898074 0 -0.439845 -0.898074 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.201912 0.979404 0 -0.201912 0.979404 -8.51382e-07 -0.201912 0.979404 0 -0.201912 0.979404 0 -0.439845 0.898074 0 -0.439845 0.898074 0 -0.818995 0.5738 0 -0.818995 0.5738 0 -0.994291 0.106705 0 -0.994291 0.106705 0 -0.989476 -0.144696 0 -0.989476 -0.144696 0 -0.989476 -0.144696 0 -0.989476 -0.144696 -6.34867e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.989476 0.144697 0 0.989476 0.144696 0 0.989476 0.144696 0 0.989476 0.144697 -6.98354e-06 0.201912 -0.979404 0 0.201912 -0.979404 0 0.201912 -0.979404 -3.24736e-07 0.201912 -0.979404 -2.83794e-07 0.201912 -0.979404 0 0.439843 -0.898075 0 0.439843 -0.898075 0 0.818995 -0.5738 0 0.818995 -0.5738 0 0.994291 -0.106705 0 0.994291 -0.106705 0 0.989476 -0.144697 0 0.989476 -0.144697 -7.40678e-06 0.989476 -0.144696 0 0.989476 -0.144696 0 0.994291 0.106705 0 0.994291 0.106705 0 0.818995 0.5738 0 0.818995 0.5738 0 0.439843 0.898075 0 0.439843 0.898075 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.417983 0.908455 0 0.417983 0.908455 0 0.775214 0.631699 0 0.775214 0.631699 0 0.97414 0.225946 0 0.97414 0.225946 0 1 0 0 1 0 0 1 0 0 0.97414 -0.225946 0 0.97414 -0.225946 0 0.775214 -0.631699 0 0.775214 -0.631699 0 0.417983 -0.908455 0 0.417983 -0.908455 0 -0.201912 -0.979404 0 -0.201912 -0.979404 0 -0.201912 -0.979404 0 -0.201912 -0.979404 -8.51382e-07 -0.417984 -0.908455 0 -0.417984 -0.908455 0 -0.775214 -0.631699 0 -0.775214 -0.631699 0 -0.974139 -0.225948 0 -0.974139 -0.225948 0 -1 0 0 -1 0 0 -1 0 0 -0.974139 0.225948 0 -0.974139 0.225948 0 -0.775214 0.631699 0 -0.775214 0.631699 0 -0.417984 0.908455 0 -0.417984 0.908455 0 0.201912 0.979404 0 0.201912 0.979404 0 0.201912 0.979404 -2.83794e-07 0.201912 0.979404 0 0.201912 0.979404 -4.89912e-07 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.965924 0.258825 0 0.965924 0.258825 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965924 0.258825 0 -0.965924 0.258825 0 -0.965924 -0.258825 0 -0.965924 -0.258825 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.965927 0.258813 0 0.965927 0.258813 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.965924 0.258825 0 0.965924 0.258825 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.965924 0.258825 0 0.965924 0.258825 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.965927 0.258813 0 0.965927 0.258813 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965924 0.258825 0 -0.965924 0.258825 0 -0.965924 -0.258825 0 -0.965924 -0.258825 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.965924 0.258825 0 0.965924 0.258825 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.965927 0.258813 0 0.965927 0.258813 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.508589 -0.508591 0.694746 0.50859 -0.50859 0.694746 0.694749 -0.186153 0.694745 0.694747 -0.186156 0.694747 0.694747 0.186152 0.694747 0.694748 0.186156 0.694746 0.50859 0.50859 0.694746 0.508591 0.50859 0.694746 0.186156 0.694748 0.694746 0.186156 0.694747 0.694746 -0.186158 0.694747 0.694746 -0.186157 0.694747 0.694746 -0.50859 0.50859 0.694746 -0.508591 0.50859 0.694746 -0.694749 0.186153 0.694745 -0.694747 0.186156 0.694747 -0.694747 -0.186152 0.694747 -0.694748 -0.186156 0.694746 -0.50859 -0.508591 0.694746 -0.50859 -0.50859 0.694746 -0.186158 -0.694746 0.694746 -0.186157 -0.694747 0.694746 0.186156 -0.694747 0.694746 0.186156 -0.694747 0.694746 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.965926 0.258818 0 0.965926 0.258818 0 0.707107 0.707106 0 0.707107 0.707106 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.965926 0.258818 0 -0.965926 0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.965927 0.258813 0 0.965927 0.258813 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.50859 -0.50859 0.694746 0.508591 -0.50859 0.694746 0.694749 -0.186153 0.694745 0.694747 -0.186156 0.694747 0.694747 0.186152 0.694747 0.694748 0.186156 0.694746 0.50859 0.50859 0.694746 0.50859 0.50859 0.694746 0.186156 0.694748 0.694746 0.186156 0.694748 0.694746 -0.186158 0.694747 0.694745 -0.186157 0.694747 0.694746 -0.50859 0.50859 0.694746 -0.50859 0.50859 0.694746 -0.694749 0.186153 0.694745 -0.694747 0.186156 0.694747 -0.694747 -0.186152 0.694747 -0.694748 -0.186156 0.694746 -0.50859 -0.50859 0.694746 -0.508591 -0.50859 0.694746 -0.186158 -0.694747 0.694746 -0.186157 -0.694748 0.694746 0.186156 -0.694748 0.694746 0.186156 -0.694748 0.694746 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.965926 0.258818 0 0.965926 0.258818 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258818 0 -0.965926 0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.965924 0.258825 0 0.965924 0.258825 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.508589 -0.508591 0.694746 0.50859 -0.50859 0.694746 0.694745 -0.186161 0.694747 0.694749 -0.186156 0.694745 0.694748 0.186162 0.694744 0.694748 0.186156 0.694746 0.50859 0.50859 0.694746 0.508591 0.50859 0.694746 0.186158 0.694747 0.694746 0.186157 0.694747 0.694746 -0.186156 0.694748 0.694746 -0.186157 0.694748 0.694745 -0.508591 0.508591 0.694745 -0.508592 0.508591 0.694744 -0.694751 0.186153 0.694743 -0.694746 0.18616 0.694746 -0.694747 -0.186152 0.694747 -0.694748 -0.18616 0.694744 -0.508591 -0.508592 0.694744 -0.508591 -0.508591 0.694745 -0.186156 -0.694748 0.694746 -0.186157 -0.694747 0.694746 0.186158 -0.694747 0.694746 0.186157 -0.694747 0.694746 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.965926 0.258818 0 0.965926 0.258818 0 0.707107 0.707106 0 0.707107 0.707106 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.965925 0.258823 0 -0.965925 0.258823 0 -0.965925 -0.258823 0 -0.965925 -0.258823 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.965924 0.258825 0 0.965924 0.258825 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.50859 -0.50859 0.694746 0.508591 -0.50859 0.694746 0.694745 -0.186161 0.694747 0.694749 -0.186156 0.694745 0.694748 0.186162 0.694744 0.694748 0.186156 0.694746 0.50859 0.50859 0.694746 0.50859 0.50859 0.694746 0.186158 0.694747 0.694746 0.186157 0.694748 0.694745 -0.186156 0.694748 0.694746 -0.186158 0.694748 0.694745 -0.508591 0.508591 0.694744 -0.508591 0.508591 0.694744 -0.694751 0.186153 0.694743 -0.694746 0.18616 0.694746 -0.694747 -0.186152 0.694747 -0.694748 -0.18616 0.694744 -0.508591 -0.508591 0.694744 -0.508592 -0.508591 0.694745 -0.186156 -0.694748 0.694745 -0.186157 -0.694748 0.694746 0.186158 -0.694747 0.694745 0.186157 -0.694747 0.694746 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.965926 0.258818 0 0.965926 0.258818 0 0.707107 0.707107 0 0.707107 0.707107 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965925 0.258823 0 -0.965925 0.258823 0 -0.965925 -0.258823 0 -0.965925 -0.258823 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.508589 -0.508592 0.694745 0.508596 -0.508593 0.69474 0.694752 -0.186159 0.69474 0.694746 -0.186162 0.694746 0.694747 0.186157 0.694747 0.694751 0.186163 0.694741 0.508593 0.508596 0.69474 0.508592 0.50859 0.694745 0.186157 0.694749 0.694745 0.186157 0.69475 0.694743 -0.186161 0.69475 0.694743 -0.186159 0.694748 0.694745 -0.508589 0.508592 0.694745 -0.508584 0.508592 0.69475 -0.694739 0.186155 0.694754 -0.694747 0.186151 0.694747 -0.694746 -0.186158 0.694746 -0.694741 -0.18615 0.694754 -0.508586 -0.508589 0.69475 -0.508587 -0.508594 0.694746 -0.18616 -0.694747 0.694745 -0.186159 -0.69475 0.694743 0.186158 -0.69475 0.694743 0.186156 -0.694749 0.694744 0.508593 -0.508589 0.694745 0.508592 -0.508589 0.694745 0.694746 -0.186157 0.694747 0.694747 -0.186157 0.694747 0.694747 0.186157 0.694747 0.694746 0.186156 0.694747 0.508592 0.508589 0.694745 0.508592 0.50859 0.694745 0.186157 0.694749 0.694745 0.186157 0.69475 0.694743 -0.186158 0.69475 0.694743 -0.186158 0.69475 0.694743 -0.508596 0.508593 0.69474 -0.50859 0.508592 0.694745 -0.694746 0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694746 -0.186158 0.694746 -0.694746 -0.186157 0.694747 -0.508592 -0.508589 0.694745 -0.508593 -0.508596 0.69474 -0.186158 -0.69475 0.694743 -0.186158 -0.69475 0.694743 0.186158 -0.69475 0.694743 0.186156 -0.694749 0.694744 0.50859 -0.508592 0.694745 0.508594 -0.508592 0.694742 0.694752 -0.186159 0.694741 0.694746 -0.186161 0.694746 0.694747 0.186157 0.694747 0.69475 0.186163 0.694741 0.508592 0.508594 0.694741 0.508592 0.50859 0.694745 0.186157 0.694749 0.694744 0.186157 0.694749 0.694744 -0.18616 0.694749 0.694744 -0.186159 0.694748 0.694745 -0.50859 0.508592 0.694745 -0.508583 0.508591 0.694751 -0.694739 0.186155 0.694755 -0.694747 0.186151 0.694747 -0.694747 -0.186157 0.694747 -0.694741 -0.18615 0.694754 -0.508585 -0.508587 0.694752 -0.508586 -0.508595 0.694746 -0.18616 -0.694748 0.694745 -0.186159 -0.694749 0.694744 0.186157 -0.694749 0.694744 0.186157 -0.694749 0.694744 0.508593 -0.508589 0.694745 0.508591 -0.508589 0.694747 0.694745 -0.186157 0.694748 0.694747 -0.186156 0.694747 0.694747 0.186157 0.694747 0.694746 0.186156 0.694748 0.508592 0.508587 0.694747 0.508592 0.50859 0.694745 0.186157 0.694749 0.694744 0.186157 0.694749 0.694744 -0.186157 0.694749 0.694744 -0.186158 0.69475 0.694743 -0.508597 0.508592 0.694739 -0.508588 0.508592 0.694746 -0.694745 0.186157 0.694748 -0.694747 0.186156 0.694747 -0.694747 -0.186157 0.694747 -0.694746 -0.186156 0.694748 -0.508592 -0.508587 0.694747 -0.508593 -0.508596 0.69474 -0.186157 -0.694751 0.694742 -0.186158 -0.694749 0.694744 0.186157 -0.694749 0.694744 0.186157 -0.694749 0.694744 0.508591 -0.508591 0.694745 0.508594 -0.508591 0.694743 0.694752 -0.186159 0.694741 0.694746 -0.186161 0.694746 0.694746 0.186158 0.694746 0.69475 0.186162 0.694742 0.508593 0.508593 0.694743 0.508592 0.50859 0.694745 0.186157 0.694749 0.694745 0.186157 0.69475 0.694743 -0.186161 0.69475 0.694743 -0.186159 0.694748 0.694745 -0.508591 0.508591 0.694745 -0.508582 0.50859 0.694752 -0.694738 0.186155 0.694755 -0.694747 0.186151 0.694747 -0.694746 -0.186158 0.694746 -0.694741 -0.18615 0.694755 -0.508586 -0.508586 0.694753 -0.508587 -0.508594 0.694746 -0.186157 -0.694748 0.694745 -0.186158 -0.694746 0.694746 0.186154 -0.694747 0.694747 0.186156 -0.694749 0.694744 0.508594 -0.508588 0.694745 0.50859 -0.508588 0.694748 0.694745 -0.186157 0.694748 0.694747 -0.186156 0.694747 0.694746 0.186158 0.694746 0.694745 0.186156 0.694748 0.508592 0.508586 0.694748 0.508592 0.50859 0.694745 0.186157 0.694749 0.694745 0.186157 0.69475 0.694743 -0.186158 0.69475 0.694743 -0.186158 0.69475 0.694743 -0.508598 0.508592 0.694739 -0.508588 0.508591 0.694747 -0.694745 0.186157 0.694748 -0.694747 0.186156 0.694747 -0.694746 -0.186158 0.694746 -0.694745 -0.186156 0.694748 -0.508592 -0.508586 0.694748 -0.508593 -0.508596 0.69474 -0.186155 -0.694752 0.694742 -0.186157 -0.694747 0.694747 0.186154 -0.694747 0.694747 0.186156 -0.694749 0.694744 -0.927621 -0.373524 0 -0.927621 -0.373524 0 -0.653939 -0.756548 0 -0.653939 -0.756548 0 -0.235371 -0.971906 0 -0.235371 -0.971906 0 -0.235371 0.971906 0 -0.235371 0.971906 0 -0.653948 0.75654 0 -0.653948 0.75654 0 -0.927619 0.373529 0 -0.927619 0.373529 0 0.927619 0.373529 0 0.927619 0.373529 0 0.653963 0.756526 0 0.653963 0.756526 0 0.235371 0.971906 0 0.235371 0.971906 0 0.235371 -0.971906 0 0.235371 -0.971906 0 0.653954 -0.756534 0 0.653954 -0.756534 0 0.927621 -0.373524 0 0.927621 -0.373524 0 0.965928 -0.25881 0 0.130531 -0.991444 0 0.258788 -0.965786 -0.0169003 0.382693 -0.923875 0 0.513354 -0.858177 0 0.718046 -0.695982 -0.00425336 0.7071 -0.707114 0 0.965928 -0.25881 0 0.97414 0.225945 0 0.97414 0.225945 0 0.805516 0.592574 0 0.775179 0.631674 -0.0092425 0.652057 0.75817 -8.74854e-05 0.520059 0.85413 0.000195426 0.417953 0.908379 -0.0127743 0.311977 0.95009 0 0.97414 -0.225945 0 0.311977 -0.95009 0 0.417953 -0.908379 -0.0127743 0.518572 -0.855034 0 0.650783 -0.759264 0 0.805461 -0.592533 -0.0117663 0.775212 -0.631701 0 0.97414 -0.225945 0 0.965929 0.258808 0 0.965929 0.258808 0 0.718049 0.695992 0 0.707094 0.707108 -0.00400375 0.514088 0.857737 -1.23702e-05 0.383274 0.923635 8.14129e-05 0.258788 0.965786 -0.0169003 0.130531 0.991444 0 -0.0980172 0.995185 0 -0.195086 0.98074 -0.00946191 -0.620987 0.783645 -0.0166261 -0.456227 0.889863 0 -0.290296 0.956937 0 -0.55557 0.83147 0 -0.831468 0.555572 0 -0.831468 0.555572 0 -0.980784 0.195095 0 -0.980784 0.195095 0 -0.97414 -0.225945 0 -0.97414 -0.225945 0 -0.805506 -0.592587 0 -0.775179 -0.631674 -0.00923946 -0.652058 -0.758169 -8.49929e-05 -0.520074 -0.854121 0.000197387 -0.417946 -0.908382 -0.0127751 -0.311968 -0.950093 0 -0.980784 -0.195097 0 -0.980784 -0.195097 0 -0.831468 -0.555572 0 -0.831468 -0.555572 0 -0.621083 -0.783745 0 -0.55555 -0.831425 -0.00980527 -0.458247 -0.888825 -0.000193545 -0.292619 -0.956229 0.000236162 -0.195077 -0.980742 -0.00946101 -0.0980172 -0.995185 0 -0.97414 0.225945 0 -0.311968 0.950093 0 -0.417946 0.908382 -0.0127751 -0.518572 0.855034 0 -0.65082 0.759232 0 -0.805451 0.592546 -0.0117623 -0.775212 0.631701 0 -0.97414 0.225945 0 0.40871 0.898684 -0.159135 0.564011 0.825767 0 0.742507 0.669839 0 0.770274 0.636625 -0.0372312 0.926494 0.373073 0.0492558 0.948982 0.315329 0 0.92762 -0.373526 0 0.950443 -0.303003 0.0696169 0.741604 -0.669025 -0.049285 0.782609 -0.622513 0 0.564011 -0.825767 0 0.40871 -0.898684 -0.159135 -0.92762 0.373526 0 -0.950444 0.302999 0.0696205 -0.741638 0.668989 -0.0492658 -0.782626 0.622492 0 -0.563983 0.825786 0 -0.408712 0.898687 -0.159112 -0.408712 -0.898687 -0.159112 -0.563983 -0.825786 0 -0.742539 -0.669803 0 -0.770302 -0.636592 -0.0372245 -0.926494 -0.373073 0.0492527 -0.948981 -0.315332 0 0.69964 0.102313 0.707132 0.699669 0.102317 0.707103 0.699678 0.102317 0.707094 0.699651 0.102314 0.707121 0.665206 0.267862 0.696959 0.665212 0.267855 0.696956 0.468965 0.542515 0.696957 0.468934 0.542527 0.696969 0.168786 0.696958 0.696966 0.168803 0.69696 0.69696 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 -0.139288 0.700214 0.700214 -0.139282 0.700219 0.70021 -0.396637 0.593623 0.700208 -0.396642 0.593609 0.700216 -0.500002 0.500001 0.707105 -0.499999 0.499999 0.707109 -0.13928 0.700215 0.700215 -0.139284 0.700219 0.70021 -0.396644 0.593619 0.700207 -0.396637 0.593616 0.700214 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0.396637 0.593608 0.70022 0.396637 0.593616 0.700214 0.13928 0.700218 0.700211 0.139282 0.700215 0.700215 0.500003 0.500005 0.707101 0.499997 0.499995 0.707113 0.396642 0.593617 0.70021 0.396635 0.593617 0.700214 0.139285 0.700216 0.700212 0.139281 0.700215 0.700215 0 0.707107 0.707107 0 0.707107 0.707107 -0.168787 0.696962 0.696962 -0.168792 0.696958 0.696964 -0.468953 0.542522 0.69696 -0.468959 0.542511 0.696964 -0.665198 0.267859 0.696967 -0.665199 0.26785 0.69697 -0.699658 0.102317 0.707114 -0.699639 0.102312 0.707134 -0.69968 0.102318 0.707092 -0.699664 0.102316 0.707108 -0.699658 0.102315 0.707114 -0.699636 -0.102311 0.707137 -0.699659 -0.102315 0.707113 -0.699659 -0.102315 0.707114 -0.699681 -0.102318 0.707091 -0.665199 -0.267855 0.696967 -0.665196 -0.267858 0.696969 -0.468942 -0.542524 0.696966 -0.46898 -0.542509 0.696952 -0.168788 -0.696965 0.696958 -0.16877 -0.696964 0.696964 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0.139278 -0.700215 0.700215 0.139281 -0.700212 0.700217 0.396643 -0.593608 0.700217 0.396638 -0.593621 0.700209 0.499998 -0.499999 0.707109 0.500005 -0.500003 0.707101 0.13928 -0.700215 0.700215 0.139282 -0.700217 0.700212 0.396641 -0.593614 0.700213 0.396638 -0.593613 0.700216 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 -0.396643 -0.593617 0.70021 -0.396643 -0.59362 0.700207 -0.139281 -0.70022 0.700209 -0.139283 -0.700214 0.700214 -0.499999 -0.499998 0.707109 -0.500003 -0.500005 0.707101 -0.396637 -0.593613 0.700216 -0.396645 -0.593613 0.700211 -0.139281 -0.700214 0.700215 -0.139281 -0.700215 0.700215 0 -0.707107 0.707107 0 -0.707107 0.707107 0.168787 -0.696962 0.696962 0.168782 -0.696965 0.69696 0.468956 -0.542517 0.696962 0.468953 -0.542522 0.69696 0.665208 -0.267858 0.696958 0.665208 -0.267863 0.696957 0.699669 -0.102318 0.707103 0.699637 -0.102312 0.707135 0.699653 -0.102314 0.70712 0.699675 -0.102317 0.707097 0.699678 -0.102318 0.707094 0 0.707107 -0.707107 0 0.707098 -0.707116 1.98259e-06 0.707023 -0.70719 0 0.707107 -0.707107 0.168785 0.696953 -0.696971 0.168776 0.696962 -0.696963 0.468962 0.54251 -0.696963 0.468958 0.542521 -0.696957 0.665212 0.267864 -0.696952 0.665213 0.267869 -0.69695 0.699659 0.102315 -0.707113 0.699676 0.102317 -0.707096 0.714263 -0.0766532 -0.695667 0.714267 -0.0766526 -0.695663 0.588339 -0.412199 -0.695664 0.588333 -0.412197 -0.695671 0.315967 -0.645144 -0.695668 0.31597 -0.645148 -0.695663 0.142773 -0.69254 -0.70711 0.142773 -0.69254 -0.70711 0.142772 -0.692538 -0.707112 0.142773 -0.692543 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0.665215 -0.267861 -0.69695 0.665213 -0.267862 -0.696952 0.468959 -0.54252 -0.696957 0.468943 -0.542522 -0.696966 0.168786 -0.696959 -0.696965 0.168792 -0.696961 -0.696961 0.699659 -0.102315 -0.707113 0.699676 -0.102318 -0.707096 0.315969 0.645148 -0.695663 0.315968 0.645144 -0.695668 0.588334 0.412196 -0.695671 0.588339 0.412201 -0.695664 0.714266 0.0766536 -0.695664 0.714263 0.0766522 -0.695668 0.142773 0.692539 -0.707111 0.142773 0.69254 -0.70711 0.142771 0.692529 -0.707121 0.142774 0.692546 -0.707104 -0.142777 -0.692559 -0.70709 -0.142773 -0.69254 -0.70711 -0.142771 -0.692529 -0.70712 -0.142773 -0.69254 -0.70711 -0.315971 -0.645148 -0.695663 -0.31597 -0.645143 -0.695668 -0.588334 -0.412196 -0.695671 -0.588339 -0.412201 -0.695664 -0.714266 -0.0766536 -0.695664 -0.71428 -0.0766587 -0.695649 -0.699659 0.102315 -0.707113 -0.699676 0.102318 -0.707096 -0.665198 0.267859 -0.696967 -0.665195 0.267861 -0.696969 -0.468947 0.542516 -0.696968 -0.468953 0.542516 -0.696965 -0.168786 0.696959 -0.696965 -0.168774 0.696954 -0.696972 0 0.707107 -0.707107 -2.89643e-08 0.707098 -0.707116 3.04344e-07 0.707083 -0.70713 0 0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 -0.168787 -0.696962 -0.696962 -0.168791 -0.696957 -0.696965 -0.468942 -0.542523 -0.696966 -0.468942 -0.542522 -0.696967 -0.665198 -0.267854 -0.696968 -0.665199 -0.267857 -0.696967 -0.699676 -0.102317 -0.707096 -0.699659 -0.102315 -0.707113 -0.71428 0.0766551 -0.695649 -0.714266 0.0766571 -0.695664 -0.588339 0.412199 -0.695664 -0.588333 0.412197 -0.695671 -0.315969 0.645143 -0.695668 -0.315972 0.645147 -0.695663 -0.142777 0.692561 -0.707088 -0.142773 0.69254 -0.70711 -0.142772 0.692538 -0.707112 -0.142771 0.692531 -0.707119 -0.699676 0.102317 0.707096 -0.699659 0.102315 0.707113 -0.71428 -0.0766551 0.695649 -0.714266 -0.0766571 0.695664 -0.588339 -0.412199 0.695664 -0.588333 -0.412197 0.695671 -0.315969 -0.645143 0.695668 -0.315972 -0.645147 0.695663 -0.134175 0.700713 0.700713 -0.163742 0.676141 0.718346 -0.292905 0.644048 0.706688 -0.400334 0.586171 0.704369 -0.447558 0.517751 0.729127 -0.526745 0.475147 0.704823 -0.665199 0.267857 0.696967 -0.665199 0.267857 0.696967 -0.142773 -0.69254 0.70711 -0.142773 -0.69254 0.70711 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 -0.697792 -0.16185 0.697775 -0.697782 -0.161847 0.697786 -0.55529 -0.45249 0.697786 -0.55529 -0.452489 0.697787 -0.299404 -0.650731 0.697787 -0.299404 -0.650731 0.697787 0.665199 0.267857 0.696967 0.665199 0.267857 0.696967 0.526723 0.475174 0.704821 0.447546 0.517769 0.729121 0.134175 0.700713 0.700713 0.163749 0.676136 0.71835 0.292902 0.644042 0.706696 0.400349 0.58615 0.704378 -0.707116 0 0.707098 -0.707116 0 0.707098 0.699659 0.102315 0.707113 0.699659 0.102315 0.707113 -0.299404 0.650731 0.697787 -0.299404 0.650731 0.697787 -0.555289 0.452489 0.697787 -0.55529 0.45249 0.697786 -0.697782 0.161848 0.697786 -0.697793 0.161849 0.697775 0.315969 -0.645148 0.695663 0.315968 -0.645144 0.695668 0.588334 -0.412196 0.695671 0.588339 -0.412201 0.695664 0.714266 -0.0766536 0.695664 0.714263 -0.0766522 0.695668 -0.142773 0.69254 0.70711 -0.142773 0.69254 0.707109 0.142773 -0.69254 0.70711 0.142773 -0.69254 0.70711 -0.315971 0.645148 0.695663 -0.31597 0.645143 0.695668 -0.588334 0.412196 0.695671 -0.588339 0.412201 0.695664 -0.714266 0.0766536 0.695664 -0.71428 0.0766587 0.695649 0.299403 -0.650731 0.697787 0.299403 -0.650731 0.697787 0.555289 -0.452489 0.697787 0.55529 -0.45249 0.697786 0.697782 -0.161846 0.697786 0.697776 -0.161845 0.697793 -0.699676 -0.102318 0.707096 -0.699664 -0.102315 0.707108 -0.699659 -0.102315 0.707114 0.707098 0 0.707116 0.707098 0 0.707116 -0.665197 -0.267856 0.696969 -0.665198 -0.267856 0.696969 -0.526743 -0.475145 0.704826 -0.447561 -0.517746 0.729129 -0.134174 -0.700709 0.700717 -0.163735 -0.676143 0.718347 -0.292905 -0.644048 0.706688 -0.400334 -0.586171 0.704369 0.697776 0.161845 0.697793 0.697782 0.161847 0.697786 0.55529 0.45249 0.697786 0.55529 0.452489 0.697787 0.299403 0.650731 0.697787 0.299403 0.650731 0.697787 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.707102 0.707111 0.142773 0.69254 0.70711 0.142773 0.69254 0.70711 0.134174 -0.700709 0.700717 0.163741 -0.676137 0.71835 0.292902 -0.644042 0.706696 0.400349 -0.58615 0.704378 0.44755 -0.517763 0.729123 0.526721 -0.475172 0.704824 0.665197 -0.267856 0.696969 0.665197 -0.267856 0.696969 0.714263 0.0766532 0.695667 0.714267 0.0766526 0.695663 0.588339 0.412199 0.695664 0.588333 0.412197 0.695671 0.315967 0.645144 0.695668 0.31597 0.645148 0.695663 0.699659 -0.102315 0.707113 0.699659 -0.102315 0.707114 0.707112 0 0.707102 0.707112 0 0.707102 0.707112 0 0.707102 0.707112 0 0.707102 0.70022 0.13928 0.700209 0.700219 0.139279 0.700211 0.593615 0.396642 0.700212 0.593617 0.396645 0.700208 0.396642 0.593617 0.70021 0.396641 0.593611 0.700215 0.13928 0.700215 0.700214 0.13928 0.700215 0.700215 0.186156 -0.694747 0.694747 0.186158 -0.69475 0.694743 0.508594 -0.508592 0.694742 0.50859 -0.50859 0.694746 0.694747 -0.186157 0.694746 0.694752 -0.186156 0.694741 0 0.707107 0.707107 0 0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 -0.694752 0.186156 0.694742 -0.694747 0.186157 0.694746 -0.50859 0.50859 0.694746 -0.186157 0.694747 0.694747 -0.186156 0.694745 0.694748 -0.432302 0.563387 0.704067 -0.759405 0.582721 0.28938 -0.139282 -0.700214 0.700214 -0.139282 -0.700217 0.700212 -0.313086 -0.634866 0.706344 -0.428823 -0.641782 0.635789 -0.432304 -0.563386 0.704066 -0.593609 -0.396638 0.700219 -0.700219 -0.139286 0.700209 -0.700208 -0.139277 0.700221 -0.634862 -0.313068 0.706355 -0.640429 -0.491426 0.590213 -0.707112 0 0.707102 -0.707112 0 0.707102 -0.707112 0 0.707102 -0.707112 0 0.707102 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 -0.19509 0.980785 0 -0.19509 0.980785 0 -0.555569 0.83147 0 -0.555569 0.83147 0 -0.831469 0.555571 0 -0.831469 0.555571 0 -0.980785 0.195092 0 -0.980785 0.195092 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.980785 -0.195092 0 -0.980785 -0.195092 0 -0.831469 -0.555571 0 -0.831469 -0.555571 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 0 -1 0 0 -1 0 0 -1 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258817 0 0.965926 -0.258817 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.980785 0.195092 0 0.980785 0.195092 0 0.831473 0.555565 0 0.831473 0.555565 0 0.555568 0.831471 0 0.555568 0.831471 0 0.19509 0.980785 0 0.19509 0.980785 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258817 0.965926 0 0.258817 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965927 0.258814 0 0.965927 0.258814 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965927 -0.258814 0 0.965927 -0.258814 0 1 0 0 1 0 0 -0.19509 0.980785 0 -0.19509 0.980785 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980782 0.195106 0 -0.980782 0.195106 0 0 1 0 0 1 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965924 -0.258828 0 -0.965924 -0.258828 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.417985 0.908454 0 0.417985 0.908454 0 0.77521 0.631703 0 0.77521 0.631703 0 0.974142 0.225936 0 0.974142 0.225936 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965927 -0.258815 0 0.965927 -0.258815 0 1 0 0 1 0 0 -0.0184531 0.99983 0 -0.0184531 0.99983 0 -0.445724 0.89517 0 -0.445724 0.89517 0 -0.786732 0.617295 0 -0.786732 0.617295 0 -0.975511 0.21995 0 -0.975511 0.21995 0 0.201912 0.979404 0 0.201912 0.979404 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.323329 -0.946287 0 0.323329 -0.946287 0 -0.0928486 -0.99568 0 -0.0928486 -0.99568 0 -0.492719 -0.870189 0 -0.492719 -0.870189 0 -0.806053 -0.591843 0 -0.806053 -0.591843 0 -0.977798 -0.209549 0 -0.977798 -0.209549 0 0.977798 -0.209549 0 0.977798 -0.209549 0 0.806053 -0.591843 0 0.806053 -0.591843 0 0.492719 -0.870189 0 0.492719 -0.870189 0 0.0928486 -0.99568 0 0.0928486 -0.99568 0 -0.323329 -0.946287 0 -0.323329 -0.946287 0 -0.352504 -0.935811 0 -0.352504 -0.935811 0 0 -1 0 0 -1 0 0.352504 -0.935811 0 0.352504 -0.935811 0 0.974139 0.225951 0 0.974139 0.225951 0 0.775219 0.631693 0 0.775219 0.631693 0 0.417983 0.908455 0 0.417983 0.908455 0 1 0 0 1 0 0 0.201912 0.979404 0 0.201912 0.979404 0 -0.971924 0.235295 0 -0.971924 0.235295 0 -0.756693 0.65377 0 -0.756693 0.65377 0 -0.373884 0.927475 0 -0.373884 0.927475 0 0.0917161 0.995785 0 0.0917161 0.995785 0 0.263199 0.964741 0 0.263199 0.964741 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.965923 -0.258828 0 0.965923 -0.258828 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.801095 0.598538 0 0.801095 0.598538 0 0.977209 0.212279 0 0.977209 0.212279 0 1 0 0 1 0 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.55557 -0.83147 0 -0.55557 -0.83147 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 0 -1 0 0 -1 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -1 0 0 -1 0 0 0.234284 0.972168 0 0.234284 0.972168 0 0.651407 0.758728 0 0.651407 0.758728 0 0.925517 0.378706 0 0.925517 0.378706 0 0 1 0 0 1 0 0.946742 0.321992 0 0.946742 0.321992 0 0.777787 0.628528 0 0.777787 0.628528 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.965927 -0.258815 0 0.965927 -0.258815 0 0.70711 -0.707103 0 0.70711 -0.707103 0 0.258814 -0.965927 0 0.258814 -0.965927 0 0.965927 0.258815 0 0.965927 0.258815 0 0.707109 0.707105 0 0.707109 0.707105 0 0.25882 0.965926 0 0.25882 0.965926 0 1 0 0 1 0 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 0 -1 0 0 -1 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258814 -0.965927 0 0.258814 -0.965927 0 0.70711 -0.707103 0 0.70711 -0.707103 0 0.965927 -0.258815 0 0.965927 -0.258815 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965927 0.258815 0 0.965927 0.258815 0 -0.195092 0.980785 0 -0.195092 0.980785 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980782 0.195106 0 -0.980782 0.195106 0 0 1 0 0 1 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.70711 -0.707103 0 -0.70711 -0.707103 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.965927 0.258814 0 0.965927 0.258814 0 0.707102 0.707112 0 0.707102 0.707112 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.980786 0.195088 0 -0.980786 0.195088 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.19509 0.980785 0 -0.19509 0.980785 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -0.707102 -0.707112 0 -0.707102 -0.707112 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -1 0 0 -1 0 0 0.965927 -0.258814 0 0.965927 -0.258814 0 0.707102 -0.707112 0 0.707102 -0.707112 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.975511 0.21995 0 0.975511 0.21995 0 0.78674 0.617285 0 0.78674 0.617285 0 0.445718 0.895174 0 0.445718 0.895174 0 0.0184531 0.99983 0 0.0184531 0.99983 0 -0.974139 0.225951 0 -0.974139 0.225951 0 -0.775218 0.631693 0 -0.775218 0.631693 0 -0.417985 0.908454 0 -0.417985 0.908454 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.55557 -0.83147 0 -0.55557 -0.83147 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -1 0 0 -1 0 0 0.965927 -0.258815 0 0.965927 -0.258815 0 0.707102 -0.707112 0 0.707102 -0.707112 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0 -1 0 0 -1 0 1 0 0 1 0 0 -0.201912 0.979404 0 -0.201912 0.979404 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.417983 0.908455 0 -0.417983 0.908455 0 -0.775211 0.631702 0 -0.775211 0.631702 0 -0.974139 0.225951 0 -0.974139 0.225951 0 0.977798 -0.209549 0 0.977798 -0.209549 0 0.806053 -0.591843 0 0.806053 -0.591843 0 0.492719 -0.870189 0 0.492719 -0.870189 0 0.0928486 -0.99568 0 0.0928486 -0.99568 0 -0.323334 -0.946285 0 -0.323334 -0.946285 0 0.323334 -0.946285 0 0.323334 -0.946285 0 -0.092847 -0.99568 0 -0.092847 -0.99568 0 -0.492726 -0.870184 0 -0.492726 -0.870184 0 -0.806045 -0.591854 0 -0.806045 -0.591854 0 -0.977798 -0.209549 0 -0.977798 -0.209549 0 -0.352504 -0.935811 0 -0.352504 -0.935811 0 0 -1 0 0 -1 0 0.352504 -0.935811 0 0.352504 -0.935811 0 -0.0917147 0.995785 0 -0.0917147 0.995785 0 0.37389 0.927473 0 0.37389 0.927473 0 0.756685 0.653779 0 0.756685 0.653779 0 0.971928 0.23528 0 0.971928 0.23528 0 1 0 0 1 0 0 -0.263201 0.964741 0 -0.263201 0.964741 0 -0.201912 0.979404 0 -0.201912 0.979404 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965924 -0.258828 0 -0.965924 -0.258828 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965927 -0.258814 0 0.965927 -0.258814 0 -0.323334 0.946285 0 -0.323334 0.946285 0 0.0928464 0.99568 0 0.0928464 0.99568 0 0.492719 0.870189 0 0.492719 0.870189 0 0.806053 0.591843 0 0.806053 0.591843 0 0.977798 0.209548 0 0.977798 0.209548 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -0.977798 0.209548 0 -0.977798 0.209548 0 -0.806045 0.591854 0 -0.806045 0.591854 0 -0.492726 0.870184 0 -0.492726 0.870184 0 -0.0928448 0.995681 0 -0.0928448 0.995681 0 0.323334 0.946285 0 0.323334 0.946285 0 -1 0 0 -1 0 0 0.352504 0.935811 0 0.352504 0.935811 0 0 1 0 0 1 0 -0.352504 0.935811 0 -0.352504 0.935811 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -0.19509 0.980785 0 -0.19509 0.980785 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980786 0.195088 0 -0.980786 0.195088 0 -1 0 0 -1 0 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965924 -0.258828 0 0.965924 -0.258828 0 0 -1 0 0 -1 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965924 0.258828 0 0.965924 0.258828 0 1 0 0 1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831462 0.555582 0 0.831462 0.555582 0 0.555578 0.831464 0 0.555578 0.831464 0 0.19509 0.980785 0 0.19509 0.980785 0 -0.925517 0.378706 0 -0.925517 0.378706 0 -0.651407 0.758728 0 -0.651407 0.758728 0 -0.23428 0.972169 0 -0.23428 0.972169 0 0 1 0 0 1 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -0.977213 0.212262 0 -0.977213 0.212262 0 -0.801095 0.598538 0 -0.801095 0.598538 0 -1 0 0 -1 0 0 -0.777787 0.628528 0 -0.777787 0.628528 0 -0.946742 0.321992 0 -0.946742 0.321992 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.70711 -0.707103 0 -0.70711 -0.707103 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.70711 -0.707103 0 0.70711 -0.707103 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.258824 0.965925 0 0.258824 0.965925 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965923 0.258828 0 0.965923 0.258828 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -0.195092 0.980785 0 -0.195092 0.980785 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980786 0.195088 0 -0.980786 0.195088 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -0.555577 -0.831465 0 -0.555577 -0.831465 0 -0.831462 -0.555581 0 -0.831462 -0.555581 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 0.258814 -0.965927 0 0.258814 -0.965927 0 0.70711 -0.707103 0 0.70711 -0.707103 0 0.965927 -0.258815 0 0.965927 -0.258815 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965927 0.258815 0 0.965927 0.258815 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -0.258824 0.965925 0 -0.258824 0.965925 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.965927 -0.258815 0 0.965927 -0.258815 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195092 0.980785 0 0.195092 0.980785 0 1 0 0 1 0 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.975511 -0.21995 0 -0.975511 -0.21995 0 -0.786732 -0.617295 0 -0.786732 -0.617295 0 -0.445724 -0.89517 0 -0.445724 -0.89517 0 -0.0184531 -0.99983 0 -0.0184531 -0.99983 0 0.974142 -0.225936 0 0.974142 -0.225936 0 0.77521 -0.631703 0 0.77521 -0.631703 0 0.417985 -0.908454 0 0.417985 -0.908454 0 0.965927 0.258815 0 0.965927 0.258815 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258818 0.965926 0 0.258818 0.965926 0 1 0 0 1 0 0 -0.980782 0.195106 0 -0.980782 0.195106 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.19509 0.980785 0 -0.19509 0.980785 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0.201912 -0.979404 0 0.201912 -0.979404 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.417983 -0.908455 0 0.417983 -0.908455 0 0.775219 -0.631693 0 0.775219 -0.631693 0 0.974139 -0.225951 0 0.974139 -0.225951 0 -0.977798 0.209548 0 -0.977798 0.209548 0 -0.806052 0.591844 0 -0.806052 0.591844 0 -0.492719 0.870189 0 -0.492719 0.870189 0 -0.0928486 0.99568 0 -0.0928486 0.99568 0 0.323329 0.946287 0 0.323329 0.946287 0 -0.323329 0.946287 0 -0.323329 0.946287 0 0.0928486 0.99568 0 0.0928486 0.99568 0 0.492719 0.870189 0 0.492719 0.870189 0 0.806052 0.591844 0 0.806052 0.591844 0 0.977798 0.209548 0 0.977798 0.209548 0 0.352504 0.935811 0 0.352504 0.935811 0 0 1 0 0 1 0 -0.352504 0.935811 0 -0.352504 0.935811 0 0.0917161 -0.995785 0 0.0917161 -0.995785 0 -0.373884 -0.927475 0 -0.373884 -0.927475 0 -0.756693 -0.65377 0 -0.756693 -0.65377 0 -0.971924 -0.235295 0 -0.971924 -0.235295 0 -1 0 0 -1 0 0 0.263199 -0.964741 0 0.263199 -0.964741 0 0.201912 -0.979404 0 0.201912 -0.979404 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.195092 0.980785 0 0.195092 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980786 0.195088 0 0.980786 0.195088 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965927 0.258815 0 -0.965927 0.258815 0 0.323333 -0.946285 0 0.323333 -0.946285 0 -0.0928507 -0.99568 0 -0.0928507 -0.99568 0 -0.492719 -0.870189 0 -0.492719 -0.870189 0 -0.806053 -0.591843 0 -0.806053 -0.591843 0 -0.977798 -0.209549 0 -0.977798 -0.209549 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0.977798 -0.209549 0 0.977798 -0.209549 0 0.806053 -0.591843 0 0.806053 -0.591843 0 0.492719 -0.870189 0 0.492719 -0.870189 0 0.0928507 -0.99568 0 0.0928507 -0.99568 0 -0.323333 -0.946285 0 -0.323333 -0.946285 0 1 0 0 1 0 0 -0.352502 -0.935811 0 -0.352502 -0.935811 0 0 -1 0 0 -1 0 0.352502 -0.935811 0 0.352502 -0.935811 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.195092 0.980785 0 0.195092 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980782 0.195106 0 0.980782 0.195106 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965923 -0.258828 0 0.965923 -0.258828 0 1 0 0 1 0 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965927 0.258815 0 -0.965927 0.258815 0 0 1 0 0 1 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555572 -0.831469 0 -0.555572 -0.831469 0 -0.831469 -0.55557 0 -0.831469 -0.55557 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258818 0.965926 0 0.258818 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965923 0.258828 0 0.965923 0.258828 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.831471 -0.555569 0 -0.831471 -0.555569 0 -0.55557 -0.83147 0 -0.55557 -0.83147 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 0.925517 -0.378706 0 0.925517 -0.378706 0 0.651407 -0.758728 0 0.651407 -0.758728 0 0.234284 -0.972168 0 0.234284 -0.972168 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0.977209 -0.212279 0 0.977209 -0.212279 0 0.801095 -0.598538 0 0.801095 -0.598538 0 1 0 0 1 0 0 0.777787 -0.628528 0 0.777787 -0.628528 0 0.946742 -0.321992 0 0.946742 -0.321992 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258814 0.965927 0 0.258814 0.965927 0 0.70711 0.707103 0 0.70711 0.707103 0 0.965923 0.258828 0 0.965923 0.258828 0 -0.258814 0.965927 0 -0.258814 0.965927 0 -0.70711 0.707103 0 -0.70711 0.707103 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -0.555572 -0.831469 0 -0.555572 -0.831469 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965924 -0.258828 0 0.965924 -0.258828 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258814 0.965927 0 0.258814 0.965927 0 0.70711 0.707103 0 0.70711 0.707103 0 0.965927 0.258815 0 0.965927 0.258815 0 -0.258814 0.965927 0 -0.258814 0.965927 0 -0.70711 0.707103 0 -0.70711 0.707103 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -0.555572 -0.831469 0 -0.555572 -0.831469 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965927 -0.258814 0 0.965927 -0.258814 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.965927 -0.258814 0 0.965927 -0.258814 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.965924 -0.258828 0 -0.965924 -0.258828 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0 -1 0 0 -1 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195088 0.980786 0 0.195088 0.980786 0 1 0 0 1 0 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.70711 0.707103 0 -0.70711 0.707103 0 -0.258814 0.965927 0 -0.258814 0.965927 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707102 -0.707112 0 -0.707102 -0.707112 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -0.258824 0.965925 0 -0.258824 0.965925 0 -0.707102 0.707112 0 -0.707102 0.707112 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -1 0 0 -1 0 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707102 -0.707112 0 0.707102 -0.707112 0 0.965927 -0.258815 0 0.965927 -0.258815 0 0 -1 0 0 -1 0 0.195092 0.980785 0 0.195092 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980786 0.195088 0 0.980786 0.195088 0 1 0 0 1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.417985 -0.908454 0 -0.417985 -0.908454 0 -0.775218 -0.631693 0 -0.775218 -0.631693 0 -0.974139 -0.225951 0 -0.974139 -0.225951 0 -0.19509 0.980785 0 -0.19509 0.980785 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980786 0.195088 0 -0.980786 0.195088 0 -1 0 0 -1 0 0 0.0184531 -0.99983 0 0.0184531 -0.99983 0 0.445718 -0.895174 0 0.445718 -0.895174 0 0.78674 -0.617285 0 0.78674 -0.617285 0 0.975511 -0.21995 0 0.975511 -0.21995 0 -0.201912 -0.979404 0 -0.201912 -0.979404 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707102 0.707112 0 0.707102 0.707112 0 0.965927 0.258815 0 0.965927 0.258815 0 1 0 0 1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.323334 0.946285 0 -0.323334 0.946285 0 0.0928486 0.99568 0 0.0928486 0.99568 0 0.492719 0.870189 0 0.492719 0.870189 0 0.806052 0.591844 0 0.806052 0.591844 0 0.977798 0.209548 0 0.977798 0.209548 0 -0.977798 0.209548 0 -0.977798 0.209548 0 -0.806044 0.591855 0 -0.806044 0.591855 0 -0.492726 0.870184 0 -0.492726 0.870184 0 -0.092847 0.99568 0 -0.092847 0.99568 0 0.323334 0.946285 0 0.323334 0.946285 0 0.352504 0.935811 0 0.352504 0.935811 0 0 1 0 0 1 0 -0.352504 0.935811 0 -0.352504 0.935811 0 -0.974139 -0.225951 0 -0.974139 -0.225951 0 -0.775211 -0.631702 0 -0.775211 -0.631702 0 -0.417983 -0.908455 0 -0.417983 -0.908455 0 -1 0 0 -1 0 0 -0.201912 -0.979404 0 -0.201912 -0.979404 0 0.971928 -0.23528 0 0.971928 -0.23528 0 0.756685 -0.653779 0 0.756685 -0.653779 0 0.37389 -0.927473 0 0.37389 -0.927473 0 -0.0917147 -0.995785 0 -0.0917147 -0.995785 0 -0.263201 -0.964741 0 -0.263201 -0.964741 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980786 0.195088 0 -0.980786 0.195088 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.19509 0.980785 0 -0.19509 0.980785 0 -0.801095 -0.598538 0 -0.801095 -0.598538 0 -0.977213 -0.212262 0 -0.977213 -0.212262 0 -1 0 0 -1 0 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831462 0.555581 0 0.831462 0.555581 0 0.555579 0.831464 0 0.555579 0.831464 0 0.19509 0.980785 0 0.19509 0.980785 0 0 1 0 0 1 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965923 -0.258828 0 0.965923 -0.258828 0 1 0 0 1 0 0 -0.234281 -0.972169 0 -0.234281 -0.972169 0 -0.651407 -0.758728 0 -0.651407 -0.758728 0 -0.925517 -0.378706 0 -0.925517 -0.378706 0 0 -1 0 0 -1 0 -0.946742 -0.321992 0 -0.946742 -0.321992 0 -0.777787 -0.628528 0 -0.777787 -0.628528 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.70711 0.707103 0 -0.70711 0.707103 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.965924 -0.258828 0 -0.965924 -0.258828 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -1 0 0 -1 0 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195088 0.980786 0 0.195088 0.980786 0 0 1 0 0 1 0 0.965927 -0.258814 0 0.965927 -0.258814 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258817 -0.965926 0 0.258817 -0.965926 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707103 0.70711 0 -0.707103 0.70711 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -0.555572 -0.831469 0 -0.555572 -0.831469 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707102 -0.707112 0 0.707102 -0.707112 0 0.965927 -0.258814 0 0.965927 -0.258814 0 0 -1 0 0 -1 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707103 0.70711 0 0.707103 0.70711 0 0.965927 0.258815 0 0.965927 0.258815 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258824 -0.965925 0 -0.258824 -0.965925 0 -0.831462 0.555581 0 -0.831462 0.555581 0 -0.980786 0.195088 0 -0.980786 0.195088 0 -1 0 0 -1 0 0 -0.195088 0.980786 0 -0.195088 0.980786 0 -0.555577 0.831465 0 -0.555577 0.831465 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195088 0.980786 0 0.195088 0.980786 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258824 -0.965925 0 0.258824 -0.965925 0 1 0 0 1 0 0 0 1 0 0 1 0 -0.707107 0.707107 0 -0.707107 0.707107 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.831471 0.555568 0 0.831471 0.555568 0 0.980786 0.195088 0 0.980786 0.195088 0 0.195088 -0.980786 0 0.195088 -0.980786 0 0.555575 -0.831467 0 0.555575 -0.831467 0 0.831468 -0.555573 0 0.831468 -0.555573 0 0.980786 -0.195088 0 0.980786 -0.195088 0 1 0 0 1 0 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195088 0.980786 0 0.195088 0.980786 0 0.707107 0.707107 0 0.707107 0.707107 0 -0.195088 0.980786 0 -0.195088 0.980786 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980786 0.195088 0 -0.980786 0.195088 0 0 1 0 0 1 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.70711 0.707103 0 -0.70711 0.707103 0 -0.258814 0.965927 0 -0.258814 0.965927 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -1 0 0 -1 0 0 0.965923 0.258828 0 0.965923 0.258828 0 0.70711 0.707103 0 0.70711 0.707103 0 0.258817 0.965926 0 0.258817 0.965926 0 0 1 0 0 1 0 0.965924 -0.258828 0 0.965924 -0.258828 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.25882 -0.965926 0 0.25882 -0.965926 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.965923 0.258828 0 0.965923 0.258828 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258824 0.965925 0 0.258824 0.965925 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -1 0 0 -1 0 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258824 0.965925 0 -0.258824 0.965925 0 0.323338 -0.946284 0 0.323338 -0.946284 0 -0.0928491 -0.99568 0 -0.0928491 -0.99568 0 -0.492726 -0.870184 0 -0.492726 -0.870184 0 -0.806045 -0.591854 0 -0.806045 -0.591854 0 -0.977798 -0.209549 0 -0.977798 -0.209549 0 -1 0 0 -1 0 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195092 0.980785 0 0.195092 0.980785 0 0 1 0 0 1 0 0.977798 -0.209549 0 0.977798 -0.209549 0 0.806053 -0.591843 0 0.806053 -0.591843 0 0.492719 -0.870189 0 0.492719 -0.870189 0 0.0928507 -0.99568 0 0.0928507 -0.99568 0 -0.323338 -0.946284 0 -0.323338 -0.946284 0 1 0 0 1 0 0 -0.352502 -0.935811 0 -0.352502 -0.935811 0 0 -1 0 0 -1 0 0.352502 -0.935811 0 0.352502 -0.935811 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.965923 -0.258828 0 0.965923 -0.258828 0 0.70711 -0.707103 0 0.70711 -0.707103 0 0.258814 -0.965927 0 0.258814 -0.965927 0 0.965923 0.258828 0 0.965923 0.258828 0 0.707109 0.707105 0 0.707109 0.707105 0 0.25882 0.965926 0 0.25882 0.965926 0 1 0 0 1 0 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 0 -1 0 0 -1 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.965924 -0.258828 0 0.965924 -0.258828 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.965924 0.258828 0 0.965924 0.258828 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258817 0.965926 0 0.258817 0.965926 0 1 0 0 1 0 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.965927 -0.258814 0 0.965927 -0.258814 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.323329 0.946287 0 -0.323329 0.946287 0 0.0928464 0.99568 0 0.0928464 0.99568 0 0.492719 0.870189 0 0.492719 0.870189 0 0.806053 0.591843 0 0.806053 0.591843 0 0.977798 0.209548 0 0.977798 0.209548 0 1 0 0 1 0 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0 -1 0 0 -1 0 -0.977798 0.209548 0 -0.977798 0.209548 0 -0.806053 0.591843 0 -0.806053 0.591843 0 -0.492719 0.870189 0 -0.492719 0.870189 0 -0.0928464 0.99568 0 -0.0928464 0.99568 0 0.323329 0.946287 0 0.323329 0.946287 0 -1 0 0 -1 0 0 0.352504 0.935811 0 0.352504 0.935811 0 0 1 0 0 1 0 -0.352504 0.935811 0 -0.352504 0.935811 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980786 0.195088 0 -0.980786 0.195088 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195092 0.980785 0 -0.195092 0.980785 0 0.965927 0.258815 0 0.965927 0.258815 0 0.707102 0.707112 0 0.707102 0.707112 0 0.258824 0.965925 0 0.258824 0.965925 0 0 1 0 0 1 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -1 0 0 -1 0 0 0.965927 -0.258815 0 0.965927 -0.258815 0 0.707103 -0.70711 0 0.707103 -0.70711 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.195088 -0.980786 0 0.195088 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -0.70711 -0.707103 0 -0.70711 -0.707103 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.195088 0.980786 0 -0.195088 0.980786 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980786 0.195088 0 -0.980786 0.195088 0 0.980786 -0.195088 0 0.980786 -0.195088 0 0.831471 -0.555568 0 0.831471 -0.555568 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195088 0.980786 0 0.195088 0.980786 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.195088 0.980786 0 -0.195088 0.980786 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980786 0.195088 0 -0.980786 0.195088 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.70711 -0.707103 0 -0.70711 -0.707103 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -1 0 0 -1 0 0 0.195088 -0.980786 0 0.195088 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831471 -0.555568 0 0.831471 -0.555568 0 0.980786 -0.195088 0 0.980786 -0.195088 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980786 0.195088 0 0.980786 0.195088 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.195088 0.980786 0 -0.195088 0.980786 0 -0.555569 0.831471 0 -0.555569 0.831471 0 -0.83147 0.55557 0 -0.83147 0.55557 0 -0.980785 0.19509 0 -0.980785 0.19509 0 -0.258815 -0.965927 0 -0.258815 -0.965927 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -1 0 0 -1 0 0 0.258814 -0.965927 0 0.258814 -0.965927 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -1 0 0 -1 0 0 0.980785 0.195092 0 0.980785 0.195092 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195097 0.980784 0 0.195097 0.980784 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.258821 -0.965925 0 0.258821 -0.965925 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.70711 0.707103 0 -0.70711 0.707103 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -1 0 0 -1 0 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831469 0.555572 0 0.831469 0.555572 0 0.55557 0.831469 0 0.55557 0.831469 0 0.195097 0.980784 0 0.195097 0.980784 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.258822 -0.965925 0 0.258822 -0.965925 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -0.707103 -0.70711 0 -0.707103 -0.70711 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -1 0 0 -1 0 0 0.980784 0.195097 0 0.980784 0.195097 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195097 0.980784 0 0.195097 0.980784 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.25882 -0.965926 0 0.25882 -0.965926 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.980786 0.195088 0 -0.980786 0.195088 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195097 0.980784 0 -0.195097 0.980784 0 -1 0 0 -1 0 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195097 0.980784 0 0.195097 0.980784 0 0.965927 -0.258815 0 0.965927 -0.258815 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.25882 -0.965926 0 0.25882 -0.965926 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.70711 0.707103 0 -0.70711 0.707103 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.831468 -0.555573 0 -0.831468 -0.555573 0 -0.555575 -0.831467 0 -0.555575 -0.831467 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -1 0 0 -1 0 0 0.258822 0.965925 0 0.258822 0.965925 0 0.70711 0.707103 0 0.70711 0.707103 0 0.965925 0.258822 0 0.965925 0.258822 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965925 -0.258822 0 0.965925 -0.258822 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.980785 -0.195092 0 -0.980785 -0.195092 0 -0.831468 -0.555573 0 -0.831468 -0.555573 0 -0.555575 -0.831467 0 -0.555575 -0.831467 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -1 0 0 -1 0 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965927 0.258815 0 0.965927 0.258815 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707103 -0.70711 0 0.707103 -0.70711 0 0.965927 -0.258815 0 0.965927 -0.258815 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.707103 0.70711 0 -0.707103 0.70711 0 -0.258824 0.965925 0 -0.258824 0.965925 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -0.7071 -0.707114 0 -0.7071 -0.707114 0 -0.258824 -0.965925 0 -0.258824 -0.965925 0 -1 0 0 -1 0 0 0.195097 0.980784 0 0.195097 0.980784 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980782 0.195106 0 0.980782 0.195106 0 0.195088 -0.980786 0 0.195088 -0.980786 0 0.555575 -0.831467 0 0.555575 -0.831467 0 0.831468 -0.555573 0 0.831468 -0.555573 0 0.980782 -0.195106 0 0.980782 -0.195106 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980786 0.195088 0 -0.980786 0.195088 0 -0.831469 0.555572 0 -0.831469 0.555572 0 -0.55557 0.831469 0 -0.55557 0.831469 0 -0.195097 0.980784 0 -0.195097 0.980784 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.831466 -0.555576 0 -0.831466 -0.555576 0 -0.555577 -0.831465 0 -0.555577 -0.831465 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -1 0 0 -1 0 0 0.195097 0.980784 0 0.195097 0.980784 0 0.555569 0.831471 0 0.555569 0.831471 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 0.195088 -0.980786 0 0.195088 -0.980786 0 0.555575 -0.831466 0 0.555575 -0.831466 0 0.831467 -0.555574 0 0.831467 -0.555574 0 0.980785 -0.19509 0 0.980785 -0.19509 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258815 0.965927 0 -0.258815 0.965927 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.258815 -0.965927 0 -0.258815 -0.965927 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -1 0 0 -1 0 0 0.195088 -0.980786 0 0.195088 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831471 -0.555568 0 0.831471 -0.555568 0 0.980784 -0.195097 0 0.980784 -0.195097 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980784 0.195097 0 0.980784 0.195097 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258814 0.965927 0 -0.258814 0.965927 0 -0.70711 0.707103 0 -0.70711 0.707103 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.70711 -0.707103 0 -0.70711 -0.707103 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -1 0 0 -1 0 0 0.258815 -0.965927 0 0.258815 -0.965927 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195088 0.980786 0 0.195088 0.980786 0 0.55557 0.831469 0 0.55557 0.831469 0 0.831469 0.555572 0 0.831469 0.555572 0 0.980786 0.195088 0 0.980786 0.195088 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.195088 0.980786 0 -0.195088 0.980786 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980785 0.195092 0 -0.980785 0.195092 0 -1 0 0 -1 0 0 0.980786 -0.195088 0 0.980786 -0.195088 0 0.831471 -0.555568 0 0.831471 -0.555568 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.195088 -0.980786 0 0.195088 -0.980786 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195088 0.980786 0 0.195088 0.980786 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.195088 0.980786 0 -0.195088 0.980786 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980786 0.195088 0 -0.980786 0.195088 0 -1 0 0 -1 0 0 0.980786 -0.195088 0 0.980786 -0.195088 0 0.831467 -0.555575 0 0.831467 -0.555575 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.19509 -0.980785 0 0.19509 -0.980785 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831467 0.555575 0 0.831467 0.555575 0 0.555568 0.831471 0 0.555568 0.831471 0 0.19509 0.980785 0 0.19509 0.980785 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -0.55557 -0.831469 0 -0.55557 -0.831469 0 -0.831469 -0.555572 0 -0.831469 -0.555572 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.258815 0.965927 0 -0.258815 0.965927 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -1 0 0 -1 0 0 0.980785 -0.19509 0 0.980785 -0.19509 0 0.83147 -0.55557 0 0.83147 -0.55557 0 0.555569 -0.831471 0 0.555569 -0.831471 0 0.195088 -0.980786 0 0.195088 -0.980786 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707108 0.707105 0 0.707108 0.707105 0 0.258815 0.965927 0 0.258815 0.965927 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.195088 0.980786 0 -0.195088 0.980786 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980786 0.195088 0 -0.980786 0.195088 0 -1 0 0 -1 0 0 0.980782 -0.195106 0 0.980782 -0.195106 0 0.831471 -0.555568 0 0.831471 -0.555568 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.195088 -0.980786 0 0.195088 -0.980786 0 0.980782 0.195106 0 0.980782 0.195106 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195088 0.980786 0 0.195088 0.980786 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.55557 -0.83147 0 -0.55557 -0.83147 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.19509 0 -0.980785 -0.19509 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.19509 0.980785 0 0.19509 0.980785 0 0.55557 0.83147 0 0.55557 0.83147 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.258816 0.965927 0 -0.258816 0.965927 0 -0.70711 0.707103 0 -0.70711 0.707103 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.195087 -0.980786 0 -0.195087 -0.980786 0 -0.555572 -0.831468 0 -0.555572 -0.831468 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.980785 -0.195092 0 -0.980785 -0.195092 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -0.555572 -0.831468 0 -0.555572 -0.831468 0 -0.83147 -0.555569 0 -0.83147 -0.555569 0 -0.980785 -0.195092 0 -0.980785 -0.195092 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.195092 -0.980785 0 -0.195092 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.831469 -0.555572 0 -0.831469 -0.555572 0 -0.980785 -0.19509 0 -0.980785 -0.19509 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555572 0.831468 0 0.555572 0.831468 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980785 0.195093 0 0.980785 0.195093 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.195092 -0.980785 0 -0.195092 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.831469 -0.555572 0 -0.831469 -0.555572 0 -0.980785 -0.19509 0 -0.980785 -0.19509 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.990434 0.137984 0 0.990434 0.137984 0 1 0 0 1 0 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.195092 -0.980785 0 -0.195092 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.195092 -0.980785 0 -0.195092 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.195092 -0.980785 0 -0.195092 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.831469 -0.555571 0 -0.831469 -0.555571 0 -0.980785 -0.19509 0 -0.980785 -0.19509 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.831469 -0.555571 0 -0.831469 -0.555571 0 -0.980785 -0.19509 0 -0.980785 -0.19509 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.19509 0 -0.980785 -0.19509 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.19509 0 -0.980785 -0.19509 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.19509 0 -0.980785 -0.19509 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.55557 -0.83147 0 -0.55557 -0.83147 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.19509 0 -0.980785 -0.19509 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -0.55557 -0.83147 0 -0.55557 -0.83147 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.19509 0 -0.980785 -0.19509 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.195092 -0.980785 0 -0.195092 -0.980785 0 -0.555569 -0.83147 0 -0.555569 -0.83147 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 0.990434 -0.137984 0 0.990434 -0.137984 0 -0.258817 0.965927 0 -0.258817 0.965927 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.258817 0.965927 0 -0.258817 0.965927 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 -0.258817 0.965927 0 -0.258817 0.965927 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258816 0.965927 0 0.258816 0.965927 0 0.70711 0.707103 0 0.70711 0.707103 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258816 0.965927 0 -0.258816 0.965927 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.195087 -0.980786 0 -0.195087 -0.980786 0 -0.555572 -0.831468 0 -0.555572 -0.831468 0 -0.831468 -0.555573 0 -0.831468 -0.555573 0 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258816 0.965927 0 -0.258816 0.965927 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.195087 -0.980786 0 -0.195087 -0.980786 0 -0.555572 -0.831468 0 -0.555572 -0.831468 0 -0.831468 -0.555573 0 -0.831468 -0.555573 0 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258816 0.965927 0 -0.258816 0.965927 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.195087 -0.980786 0 -0.195087 -0.980786 0 -0.555572 -0.831468 0 -0.555572 -0.831468 0 -0.831468 -0.555573 0 -0.831468 -0.555573 0 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.195087 -0.980786 0 -0.195087 -0.980786 0 -0.555572 -0.831468 0 -0.555572 -0.831468 0 -0.831468 -0.555573 0 -0.831468 -0.555573 0 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.19509 0.980785 0 0.19509 0.980785 0 0.555571 0.831469 0 0.555571 0.831469 0 0.831469 0.555571 0 0.831469 0.555571 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.19509 0.980785 0 0.19509 0.980785 0 0.555571 0.831469 0 0.555571 0.831469 0 0.831469 0.555571 0 0.831469 0.555571 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.19509 0.980785 0 0.19509 0.980785 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.19509 0.980785 0 0.19509 0.980785 0 0.55557 0.83147 0 0.55557 0.83147 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.19509 0.980785 0 0.19509 0.980785 0 0.55557 0.83147 0 0.55557 0.83147 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195091 0.980785 0 0.195091 0.980785 0 0.55557 0.83147 0 0.55557 0.83147 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.19509 0.980785 0 0.19509 0.980785 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.19509 0.980785 0 0.19509 0.980785 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.195091 0 0.980785 0.195091 0 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.19509 0.980785 0 0.19509 0.980785 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.195091 0 0.980785 0.195091 0 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.19509 0.980785 0 0.19509 0.980785 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.195091 0 0.980785 0.195091 0 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195092 0.980785 0 0.195092 0.980785 0 0.555571 0.831469 0 0.555571 0.831469 0 0.831469 0.555572 0 0.831469 0.555572 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195092 0.980785 0 0.195092 0.980785 0 0.555571 0.831469 0 0.555571 0.831469 0 0.831469 0.555572 0 0.831469 0.555572 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195092 0.980785 0 0.195092 0.980785 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.195091 0 0.980785 0.195091 0 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195092 0.980785 0 0.195092 0.980785 0 0.555571 0.831469 0 0.555571 0.831469 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980785 0.195091 0 0.980785 0.195091 0 1 0 0 1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.373498 0.373493 -0.849118 0.136709 0.510204 -0.849119 0.373498 -0.373493 -0.849118 0.510204 -0.136714 -0.849118 0.510204 0.136713 -0.849118 -0.373491 -0.373498 -0.849119 -0.136709 -0.510204 -0.849119 0.136709 -0.510204 -0.849119 -0.373491 0.373498 -0.849119 -0.510205 0.136702 -0.84912 -0.510205 -0.136702 -0.84912 -0.136709 0.510204 -0.849119 0.258819 0.965926 0 0.258819 0.965926 0 0.707112 0.707102 0 0.707112 0.707102 0 0.965924 0.258828 0 0.965924 0.258828 0 0.965924 -0.258828 0 0.965924 -0.258828 0 0.707112 -0.707102 0 0.707112 -0.707102 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.7071 -0.707113 0 -0.7071 -0.707113 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.7071 0.707113 0 -0.7071 0.707113 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.373491 0.373498 -0.849119 0.136709 0.510204 -0.849119 0.373491 -0.373498 -0.849119 0.510205 -0.136702 -0.84912 0.510205 0.136702 -0.84912 -0.373498 -0.373493 -0.849118 -0.136709 -0.510204 -0.849119 0.136709 -0.510204 -0.849119 -0.373498 0.373493 -0.849118 -0.510204 0.136713 -0.849118 -0.510204 -0.136714 -0.849118 -0.136709 0.510204 -0.849119 0.258819 0.965926 0 0.258819 0.965926 0 0.7071 0.707113 0 0.7071 0.707113 0 0.965929 0.258806 0 0.965929 0.258806 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.7071 -0.707113 0 0.7071 -0.707113 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707112 -0.707102 0 -0.707112 -0.707102 0 -0.965924 -0.258828 0 -0.965924 -0.258828 0 -0.965924 0.258828 0 -0.965924 0.258828 0 -0.707112 0.707102 0 -0.707112 0.707102 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.373491 0.373498 -0.849119 0.136709 0.510203 -0.849119 0.373491 -0.373498 -0.849119 0.510205 -0.136702 -0.84912 0.510205 0.136702 -0.84912 -0.373498 -0.373493 -0.849118 -0.13671 -0.510203 -0.849119 0.13671 -0.510203 -0.849119 -0.373499 0.373493 -0.849118 -0.510204 0.136714 -0.849118 -0.510204 -0.136714 -0.849118 -0.136709 0.510203 -0.849119 0.25882 0.965926 0 0.25882 0.965926 0 0.707101 0.707113 0 0.707101 0.707113 0 0.965929 0.258806 0 0.965929 0.258806 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.7071 -0.707114 0 0.7071 -0.707114 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.707113 0.707101 0 -0.707113 0.707101 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.373499 0.373493 -0.849118 0.136709 0.510203 -0.849119 0.373498 -0.373493 -0.849118 0.510204 -0.136714 -0.849118 0.510204 0.136714 -0.849118 -0.373491 -0.373498 -0.849119 -0.13671 -0.510203 -0.849119 0.13671 -0.510203 -0.849119 -0.373491 0.373498 -0.849119 -0.510205 0.136702 -0.84912 -0.510205 -0.136702 -0.84912 -0.136709 0.510203 -0.849119 0.25882 0.965926 0 0.25882 0.965926 0 0.707113 0.707101 0 0.707113 0.707101 0 0.965923 0.258828 0 0.965923 0.258828 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.7071 -0.707114 0 -0.7071 -0.707114 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.707101 0.707113 0 -0.707101 0.707113 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.373491 0.373498 -0.849119 0.136708 0.510204 -0.849119 0.373491 -0.373498 -0.849119 0.510205 -0.136702 -0.84912 0.510205 0.136702 -0.84912 -0.373499 -0.373493 -0.849118 -0.136709 -0.510203 -0.849119 0.136709 -0.510203 -0.849119 -0.373499 0.373493 -0.849118 -0.510204 0.136714 -0.849118 -0.510204 -0.136714 -0.849118 -0.136708 0.510204 -0.849119 0.258817 0.965926 0 0.258817 0.965926 0 0.707101 0.707113 0 0.707101 0.707113 0 0.965929 0.258806 0 0.965929 0.258806 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.707101 -0.707113 0 0.707101 -0.707113 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.707113 0.707101 0 -0.707113 0.707101 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.373499 0.373493 -0.849118 0.136708 0.510204 -0.849119 0.373499 -0.373493 -0.849118 0.510204 -0.136714 -0.849118 0.510204 0.136714 -0.849118 -0.373491 -0.373498 -0.849119 -0.136709 -0.510203 -0.849119 0.136709 -0.510203 -0.849119 -0.373491 0.373498 -0.849119 -0.510205 0.136702 -0.84912 -0.510205 -0.136702 -0.84912 -0.136708 0.510204 -0.849119 0.258817 0.965926 0 0.258817 0.965926 0 0.707113 0.707101 0 0.707113 0.707101 0 0.965923 0.258828 0 0.965923 0.258828 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707101 -0.707113 0 -0.707101 -0.707113 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.707101 0.707113 0 -0.707101 0.707113 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -1 0 0 -1 0 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258816 0.965927 0 -0.258816 0.965927 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195089 -0.980786 0 -0.195089 -0.980786 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258816 0.965927 0 -0.258816 0.965927 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258816 0.965927 0 -0.258816 0.965927 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195089 -0.980786 0 -0.195089 -0.980786 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258821 0.965925 0 0.258821 0.965925 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555567 -0.831472 0 -0.555567 -0.831472 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195089 0.980786 0 0.195089 0.980786 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831472 0 0.555568 0.831472 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258816 0.965927 0 0.258816 0.965927 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 0.195085 -0.980786 0 0.195085 -0.980786 0 0.555576 -0.831466 0 0.555576 -0.831466 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980783 -0.1951 0 0.980783 -0.1951 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258816 0.965927 0 0.258816 0.965927 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258816 0.965927 0 0.258816 0.965927 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 0.195085 -0.980786 0 0.195085 -0.980786 0 0.555576 -0.831466 0 0.555576 -0.831466 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980783 -0.1951 0 0.980783 -0.1951 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -0.990434 -0.137987 0 -0.990434 -0.137987 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.83147 0.555569 0 0.83147 0.555569 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980786 -0.195084 0 -0.980786 -0.195084 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.83147 0.555569 0 0.83147 0.555569 0 0.980785 0.195092 0 0.980785 0.195092 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.19509 0.980785 0 0.19509 0.980785 0 0.555576 0.831466 0 0.555576 0.831466 0 0.83147 0.555569 0 0.83147 0.555569 0 0.980783 0.1951 0 0.980783 0.1951 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -0.990434 0.137987 0 -0.990434 0.137987 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980787 -0.195084 0 -0.980787 -0.195084 0 -0.83147 -0.555569 0 -0.83147 -0.555569 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980785 0.195093 0 0.980785 0.195093 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.19509 0.980785 0 0.19509 0.980785 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980783 0.195101 0 0.980783 0.195101 0 0.19509 -0.980785 0 0.19509 -0.980785 0 0.555576 -0.831466 0 0.555576 -0.831466 0 0.83147 -0.555569 0 0.83147 -0.555569 0 0.980783 -0.1951 0 0.980783 -0.1951 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980785 0.195093 0 0.980785 0.195093 0 1 0 0 1 0 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.195091 -0.980785 0 0.195091 -0.980785 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980783 -0.195101 0 0.980783 -0.195101 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980783 0.1951 0 0.980783 0.1951 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707105 0.707108 0 0.707105 0.707108 0 0.258819 0.965926 0 0.258819 0.965926 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.195091 -0.980785 0 0.195091 -0.980785 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831471 -0.555568 0 0.831471 -0.555568 0 0.980783 -0.1951 0 0.980783 -0.1951 0 0.980783 0.195101 0 0.980783 0.195101 0 0.831472 0.555567 0 0.831472 0.555567 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195091 0.980785 0 0.195091 0.980785 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.195091 0.980785 0 0.195091 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980783 0.195101 0 0.980783 0.195101 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.980787 0.195084 0 0.980787 0.195084 0 0.831472 0.555567 0 0.831472 0.555567 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195091 0.980785 0 0.195091 0.980785 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258821 -0.965925 0 0.258821 -0.965925 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.980787 0.195084 0 0.980787 0.195084 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195091 0.980785 0 0.195091 0.980785 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258821 -0.965925 0 0.258821 -0.965925 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.980787 0.195084 0 0.980787 0.195084 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195091 0.980785 0 0.195091 0.980785 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258821 -0.965925 0 0.258821 -0.965925 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 0.980787 0.195084 0 0.980787 0.195084 0 0.831472 0.555567 0 0.831472 0.555567 0 0.555568 0.831472 0 0.555568 0.831472 0 0.195091 0.980785 0 0.195091 0.980785 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258821 -0.965925 0 0.258821 -0.965925 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.980787 0.195084 0 0.980787 0.195084 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195091 0.980785 0 0.195091 0.980785 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.258822 -0.965925 0 0.258822 -0.965925 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.980787 0.195084 0 0.980787 0.195084 0 0.831471 0.555568 0 0.831471 0.555568 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195091 0.980785 0 0.195091 0.980785 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.258822 -0.965925 0 0.258822 -0.965925 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195089 0.980786 0 0.195089 0.980786 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980783 0.1951 0 0.980783 0.1951 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 0.195093 -0.980785 0 0.195093 -0.980785 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980783 -0.195101 0 0.980783 -0.195101 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.83147 0.555569 0 0.83147 0.555569 0 0.980783 0.1951 0 0.980783 0.1951 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.195091 0.980785 0 -0.195091 0.980785 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.831462 0.555581 0 -0.831462 0.555581 0 -0.980786 0.195088 0 -0.980786 0.195088 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.831462 -0.555581 0 -0.831462 -0.555581 0 -1 0 0 -1 0 0 0.195088 -0.980786 0 0.195088 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831471 -0.555568 0 0.831471 -0.555568 0 0.980786 -0.195088 0 0.980786 -0.195088 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831471 0.555568 0 0.831471 0.555568 0 0.980786 0.195088 0 0.980786 0.195088 0 1 0 0 1 0 0 0 1 0 0 1 0 -0.555577 -0.831465 0 -0.555577 -0.831465 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 0 -1 0 0 -1 0 0.693738 -0.44681 0.564879 0.578721 -0.503946 0.641186 0.0154304 -0.518387 0.855007 0.00435491 -0.838177 0.545381 0.0315328 -0.805161 0.592218 0.0389728 -0.809507 0.585815 -0.000201097 -0.796076 0.605197 -0.00221673 -0.795602 0.605815 0.00239894 -0.796626 0.604468 0.0422317 -0.691446 0.721192 0.0251214 -0.728605 0.684473 0.0208475 -0.741468 0.670664 0.01609 -0.765783 0.642898 0.0253273 -0.795198 0.60582 0.00631038 -0.356371 0.934323 0.000830541 -0.359527 0.933134 0.00885547 -0.353672 0.935328 0.0182095 -0.342689 0.939272 0.0165657 -0.346197 0.938015 0.012687 -0.358437 0.933468 0.00701724 -0.390153 0.920723 0.0814207 -0.371934 0.924681 0.0508761 -0.353497 0.934051 0.0267608 -0.349889 0.936409 0.0715797 -0.361424 0.92965 0.185653 -0.330862 0.925237 0.160889 -0.3814 0.910301 0.32131 -0.293929 0.900203 0.281384 -0.432349 0.856678 0.432196 -0.243957 0.868155 0.666507 -0.32255 0.672108 0.611878 -0.331823 0.717982 0.590121 -0.378372 0.713157 0.654121 -0.485963 0.579625 0.6857 -0.478305 0.548671 0.675786 -0.491751 0.549085 0.595903 -0.553233 0.582093 0.597902 -0.552429 0.580806 0.648795 -0.523335 0.552436 0.198352 -0.767463 0.609637 0.319487 -0.746595 0.583544 0.338585 -0.731629 0.591675 0.455869 -0.701796 0.547418 0.480572 -0.671246 0.56434 0.0213004 -0.799941 0.599701 0.0682246 -0.793484 0.604755 0.091124 -0.785031 0.612717 0.112867 -0.785293 0.60875 0.188848 -0.772914 0.605756 0.0118482 -0.445065 0.89542 0.0212409 -0.470048 0.882385 0.0795368 -0.463084 0.882738 0.0904039 -0.472927 0.876451 0.199355 -0.455185 0.867793 0.576371 -0.6436 0.503562 0.602389 -0.547134 0.581182 0.482918 -0.602462 0.635476 0.468139 -0.600479 0.648283 0.339086 -0.641692 0.687934 0.329825 -0.639669 0.69429 0.195488 -0.666951 0.719 0.204801 -0.669763 0.713775 0.085531 -0.683613 0.724815 0.11157 -0.693207 0.712051 0.0356936 -0.697962 0.715245 0.537572 -0.324754 0.778171 0.446818 -0.396207 0.802106 0.460448 -0.370159 0.806827 0.338609 -0.407213 0.848246 0.328991 -0.423144 0.844224 0.196622 -0.452918 0.869601 0.0515178 -0.612277 0.788963 0.0287816 -0.592367 0.805154 0.0986187 -0.586263 0.804096 0.105122 -0.588816 0.801402 0.206987 -0.574254 0.792078 0.199046 -0.571628 0.796004 0.341065 -0.54079 0.768909 0.323996 -0.536292 0.77937 0.475369 -0.489363 0.731128 0.462103 -0.486628 0.741387 0.596428 -0.430281 0.677593 0.590137 -0.429226 0.683742 0.650042 -0.398437 0.647065 0.688495 -0.419277 0.591761 0.0209993 0.787219 0.616316 0.0358049 0.699067 0.714159 0.648748 0.404675 0.644488 0.680879 0.411426 0.605914 0.693332 0.434047 0.575234 0.691471 0.459748 0.557225 0.325933 0.409785 0.851965 0.444759 0.374596 0.813553 0.462914 0.383676 0.799064 0.536286 0.322186 0.780124 0.590367 0.377963 0.71317 0.58609 0.386692 0.712016 0.298153 0.308456 0.903305 0.190241 0.366352 0.910821 0.161858 0.333721 0.928672 0.0797673 0.359661 0.929667 0.0716136 0.365746 0.927955 0.0509158 0.353197 0.934162 0.000823958 0.359078 0.933307 0.0134887 0.449939 0.892958 0.00661201 0.399645 0.916646 0.0119111 0.357487 0.933842 0.0181048 0.342106 0.939487 0.0104467 0.352071 0.935915 0.00100213 0.358975 0.933346 0.00777293 0.355485 0.93465 0.0268048 0.34945 0.936572 0.000335857 0.796185 0.605053 -0.000126904 0.796076 0.605196 0.00235654 0.796825 0.604206 0.0233345 0.803159 0.595307 0.04114 0.810653 0.58408 0.0354709 0.806863 0.589673 0.00336201 0.796781 0.604259 0.0921089 0.80959 0.579724 0.0307812 0.778182 0.627285 0.117075 0.788318 0.604026 0.198603 0.765922 0.611491 0.209701 0.767085 0.606306 0.274957 0.755271 0.594949 0.339159 0.731637 0.591336 0.358423 0.733706 0.577243 0.479749 0.682549 0.551333 0.473915 0.680924 0.558344 0.586415 0.628672 0.510773 0.600137 0.554143 0.576854 0.747315 0.638245 -0.184834 0.0305449 0.620038 0.783977 0.0453732 0.591357 0.805133 0.104839 0.585719 0.803705 0.0993504 0.589287 0.801792 0.199255 0.575361 0.793257 0.206552 0.570138 0.79516 0.324451 0.54484 0.773227 0.339163 0.532636 0.775414 0.462679 0.494187 0.736008 0.475113 0.481763 0.736323 0.590583 0.432893 0.68104 0.596309 0.425852 0.680489 0.625708 0.41105 0.662969 0.680036 0.248929 0.689627 0.0141635 0.526879 0.849822 0.0210292 0.469941 0.882447 0.0899373 0.461489 0.882576 0.0801834 0.474855 0.876404 0.196711 0.456189 0.867869 0.199516 0.452086 0.869374 0.339292 0.420033 0.841697 0.332382 0.369928 0.867569 0.430684 0.246837 0.868092 0.0165096 0.754222 0.656412 0.0349043 0.697961 0.715284 0.0859129 0.695215 0.713649 0.110915 0.681283 0.723569 0.19584 0.670886 0.715234 0.204625 0.665313 0.717974 0.33946 0.636888 0.6922 0.329822 0.644121 0.690163 0.48288 0.594725 0.642751 0.468172 0.608147 0.641072 0.600235 0.548175 0.582429 0.596062 0.552847 0.582298 0.649431 0.522542 0.55244 0.681638 0.484578 0.548229 0.662008 0.485373 0.571103 0.350041 0.191933 0.916861 -0.000166665 -0.00103781 0.999999 0.00195974 -0.000147619 0.999998 -9.31429e-05 0.000874305 1 0.0140534 -0.00472235 0.99989 0.040706 0.0117806 0.999102 -0.001519 -0.000166571 0.999999 -0.00137617 -0.000610414 0.999999 -0.001016 -0.000932138 0.999999 -0.000608809 -0.00106473 0.999999 0.00107089 0.070852 0.997486 0.0793373 0.0716844 0.994267 -0.00597019 0.135917 0.990702 0.0185666 0.146929 0.988973 0.00501673 0.148384 0.988917 0.00540016 0.148656 0.988874 -0.000164032 0.152618 0.988285 0.00817383 0.148006 0.988953 0.104347 0.161281 0.981377 0.0998677 0.159924 0.982065 0.0679233 0.147558 0.986718 0.0584722 0.157393 0.985804 0.0213941 0.156037 0.98752 0.221931 0.189215 0.956527 0.289672 0.0500402 0.955817 0.170375 0.179715 0.968852 0.431614 0.158067 0.888101 0.417804 0.181838 0.890155 0.500686 0.211628 0.839361 0.682225 0.181719 0.7082 0.635635 0.185574 0.749353 0.812991 0.1782 0.554338 0.730736 0.165205 0.662368 0.71654 0.179614 0.674025 0.771891 0.191632 0.606186 0.795503 0.182017 0.577966 0.793411 0.180803 0.581214 0.809302 0.18143 0.558671 0.801864 0.16327 0.574767 0.838277 0.0743768 0.540148 0.83019 0.0574247 0.554515 0.836906 0.0725614 0.542516 0.84597 0.138945 0.51481 0.82266 0.113513 0.557087 0.839452 0.0892146 0.536061 0.823024 0.0696725 0.563717 0.794083 0.0801985 0.602495 0.789621 0.0733691 0.609192 0.75562 0.0660286 0.651673 0.705367 0.0853443 0.703686 0.695052 0.0694009 0.715602 0.59293 0.0492868 0.803744 0.554729 0.0781144 0.828356 0.49224 0.0406211 0.869511 0.365257 0.0624067 0.928813 0.37805 0.0542854 0.924192 0.429713 0.0420474 0.901986 0.0557097 0.00796094 0.998415 0.107544 0.00689527 0.994176 0.165323 0.0414209 0.985369 0.214549 0.0102064 0.97666 0.313923 0.0319805 0.94891 0.563155 0.149034 0.812801 0.61301 0.206192 0.762695 0.582634 0.136138 0.801252 0.42021 0.140635 0.896463 0.406525 0.113623 0.906547 0.225642 0.11364 0.96756 0.207307 0.0788283 0.975095 0.0708785 0.0777887 0.994447 0.0625106 0.0670948 0.995786 0.0089239 0.0665452 0.997744 0.00407087 0.0601294 0.998182 0.00773115 0.0601612 0.998159 -0.0120613 0.0171912 0.99978 0.00411319 -2.68127e-06 0.999992 -0.00132959 0.0017762 0.999998 0.00655686 0.00158691 0.999977 0.00179541 0.00368938 0.999992 0.0649319 0.00223725 0.997887 0.0406717 0.0126713 0.999092 0.209098 0.00945435 0.977849 0.165467 0.0363594 0.985545 0.408228 0.0326988 0.912294 0.365301 0.0600767 0.928949 0.58487 0.0548679 0.809269 0.554763 0.076182 0.828514 0.722229 0.0684127 0.688262 0.705396 0.0840089 0.703817 0.802142 0.076354 0.592232 0.794035 0.0823217 0.602272 0.842158 0.0771021 0.53369 0.839478 0.0889264 0.536068 0.816506 -0.190687 0.544937 0.822587 -0.185028 0.537695 0.833054 -0.167685 0.527164 0.80569 -0.194676 0.559433 0.795151 -0.191965 0.575225 0.788005 -0.198565 0.582769 0.766328 -0.203761 0.609281 0.716718 -0.189826 0.67103 0.717784 -0.188581 0.670241 0.62279 -0.200626 0.756229 0.583321 -0.164917 0.795323 0.543694 -0.18381 0.818909 0.408603 -0.164654 0.897737 0.391984 -0.141672 0.908998 0.482007 -0.184076 0.856613 0.048252 -0.110661 0.992686 0.132591 -0.145147 0.980486 0.212107 -0.11396 0.970579 0.226629 -0.126091 0.965785 0.288984 -0.160057 0.943859 -0.000198053 -0.115639 0.993291 0.0390845 -0.11348 0.992771 0.0355487 -0.112708 0.992992 0.0135847 -0.113965 0.993392 -0.00425786 2.68127e-06 0.999991 0.00249558 -0.0171924 0.999849 -0.00643695 -0.0123492 0.999903 -0.000414614 -0.0688705 0.997626 0.0192844 -0.100587 0.994741 1.34944e-05 -7.71603e-06 1 -0.00261065 0.000916217 0.999996 -0.00115191 0.00125554 0.999999 -0.000580713 0.00130927 0.999999 -7.43953e-05 0.000284893 1 0.0944782 -0.0017373 0.995525 0.185751 -0.0269002 0.982229 0.198142 -0.0233326 0.979896 0.388227 -0.0466086 0.920384 0.303898 -0.0243639 0.952393 0.254571 -0.0225258 0.966792 0.572964 -0.0609875 0.817308 0.578509 -0.0643708 0.813132 0.519667 -0.0494436 0.852937 0.4551 -0.0389799 0.889587 0.372792 -0.0513285 0.926494 0.846932 -0.0777944 0.525979 0.82998 -0.072126 0.55311 0.828076 -0.0749383 0.555585 0.798442 -0.0772912 0.59709 0.803563 -0.0747941 0.590502 0.761436 -0.0679509 0.644669 0.692619 -0.0819162 0.716637 0.847356 -0.0584383 0.5278 0.843098 -0.0747771 0.532535 0.848786 -0.0835092 0.5221 0.847619 -0.0853483 0.523697 0.844971 -0.0908538 0.527039 0.052522 -0.0163365 0.998486 0.0528744 -0.00726976 0.998575 0.0136843 0.0029014 0.999902 0.00311939 -0.117282 0.993094 0.00756002 -0.0169512 0.999828 0.00176529 -0.0122192 0.999924 0.00234624 0.000856425 0.999997 -0.000147265 0.00128421 0.999999 0.723022 -0.0941828 0.684375 0.572103 -0.102077 0.813805 0.5871 -0.0829065 0.805258 0.387355 -0.0874158 0.917777 0.412716 -0.0579692 0.909013 0.184784 -0.0598024 0.980958 0.214978 -0.0260936 0.97627 0.0668372 -0.0277024 0.997379 0.0628716 -0.123128 0.990397 0.0154354 -0.121892 0.992423 0.846325 -0.106288 0.521955 0.837189 -0.0920083 0.539119 0.802465 -0.0961052 0.58891 0.802945 -0.0966747 0.58816 0.716782 -0.104429 0.689433 0.717717 -0.0628353 0.693494 0.63197 -0.0589187 0.77275 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.713723 -0.683416 0.153436 -0.815019 -0.469738 0.33925 -0.647403 -0.690517 0.322578 -0.830269 -0.553997 0.061164 -0.866935 -0.498003 0.0204047 -0.866273 -0.497885 0.0410023 -0.865817 -0.498708 0.040627 -0.860507 -0.506944 0.0503548 -0.847728 -0.526967 0.0605304 -0.732362 -0.680908 0.00299659 -0.759689 -0.650286 -0.000239523 -0.740918 -0.671483 0.0122922 -0.693342 -0.72025 -0.022749 -0.692513 -0.72098 -0.0247587 -0.705419 -0.708728 -0.00945338 -0.671831 -0.740247 0.0260169 -0.642207 -0.722745 0.255364 -0.652717 -0.737211 0.174586 -0.721637 -0.632381 0.281665 -0.62391 -0.7262 0.288739 -0.628251 -0.723904 0.285067 -0.719313 -0.594674 0.359099 -0.702323 -0.618004 0.353288 -0.676788 -0.644623 0.355556 -0.880743 -0.397528 0.257416 -0.879696 -0.393403 0.26715 -0.880635 -0.388453 0.271267 -0.877296 -0.390704 0.278753 -0.875761 -0.384032 0.29251 -0.892199 -0.397191 0.214989 -0.850205 -0.463 0.250564 -0.886127 -0.445609 0.127327 -0.794574 -0.605715 0.0419766 -0.793599 -0.606932 0.0428311 -0.793855 -0.606846 0.0391477 -0.881549 -0.46968 0.0476633 -0.87927 -0.471618 0.0667844 -0.764389 -0.585193 0.270662 -0.764503 -0.585122 0.270496 -0.73172 -0.568504 0.376017 -0.772612 -0.540937 0.332353 -0.661931 -0.652887 0.36822 -0.669067 -0.64974 0.360815 -0.698038 -0.66606 0.262883 -0.687301 -0.671397 0.277206 -0.713981 -0.683056 0.153839 -0.63896 -0.755438 0.145062 -0.665598 -0.741456 0.0849857 -0.867899 -0.405683 0.286657 -0.811418 -0.481925 0.330679 -0.829203 -0.489568 0.269713 -0.82371 -0.495652 0.275372 -0.837403 -0.501134 0.218222 -0.777957 -0.591068 0.213123 -0.828554 -0.546363 0.122417 -0.791651 -0.589222 0.161576 -0.804597 -0.591202 0.0557121 -0.727183 -0.68472 0.0486179 -0.739216 -0.672457 0.0369016 -0.672756 -0.739208 0.0311693 -0.697227 -0.71685 0.000869091 -0.669309 0.740853 0.0562426 -0.688633 0.720993 -0.0771554 -0.67725 0.683161 0.273174 -0.603157 0.709586 0.364265 -0.653728 0.703435 0.27896 -0.588401 0.714345 0.378808 -0.581793 0.726472 0.365726 -0.591369 0.712642 0.377391 -0.58756 0.71392 0.380908 -0.590466 0.711688 0.380592 -0.619316 0.697549 0.360379 -0.675331 0.726705 0.125809 -0.646553 0.711696 0.274698 -0.644933 0.711469 0.27906 -0.645023 0.709485 0.283859 -0.63724 0.697617 0.3275 -0.709522 0.701094 0.071033 -0.690109 0.716608 0.101107 -0.631639 0.764715 0.127449 -0.730496 0.682145 -0.0324709 -0.729564 0.683352 -0.0276836 -0.724669 0.689072 -0.00589823 -0.723775 0.689932 -0.0119888 -0.721947 0.691043 0.0353916 -0.729291 0.668965 -0.143596 -0.733779 0.671783 -0.101371 -0.735301 0.67488 -0.062199 -0.697439 0.618016 -0.362815 -0.722336 0.621022 -0.304242 -0.739284 0.646804 -0.187361 -0.696153 0.554089 -0.456461 -0.69543 0.554792 -0.456708 -0.688486 0.647271 -0.327152 -0.692458 0.622977 -0.363871 -0.718385 0.594803 -0.360739 -0.68495 0.714796 -0.1411 -0.683145 0.694798 -0.224875 -0.685339 0.662958 -0.301326 -0.624375 0.768303 0.140951 -0.578166 0.747799 0.326375 -0.600241 0.758096 0.254952 -0.606386 0.757233 0.242683 -0.60736 0.762765 0.222043 -0.610233 0.768479 0.192499 -0.600519 0.712077 0.363763 -0.632046 0.734896 0.245856 -0.612445 0.741093 0.275123 -0.646236 0.759089 0.078502 -0.623139 0.772828 0.120143 -0.635255 0.772232 -0.0104349 -0.655792 0.752441 -0.0613992 -0.655909 0.752977 -0.0529936 -0.659725 0.714105 -0.234131 -0.70809 0.667648 -0.229902 -0.677772 0.621859 -0.392322 -0.696241 0.55391 -0.456544 -0.707395 0.554528 -0.438281 -0.734852 0.603178 -0.310111 -0.662488 0.678361 -0.317706 -0.681601 0.716548 -0.14825 -0.64935 0.757962 -0.0619598 -0.666379 0.745522 -0.0116814 -0.65009 0.744608 0.151468 -0.542051 0.828813 0.138743 -0.677766 0.701683 0.219716 -0.938105 0.345455 0.0248841 -0.981392 0.161716 0.103526 -0.971531 0.199048 0.128479 -0.949797 0.269945 0.158163 -0.971543 0.235849 -0.0219128 -0.970448 0.240892 0.0142345 -0.961744 0.267046 0.0611052 -0.992891 0.0828153 -0.0854988 -0.963883 0.214727 0.15755 -0.967855 0.205349 0.145221 -0.958389 0.284723 0.0205933 -0.986565 0.161118 -0.0270173 -0.973069 0.229521 0.0213795 -0.95932 0.281849 0.0163014 -0.957261 0.289022 0.0108648 -0.989653 0.134298 -0.0505141 -0.989131 0.14038 -0.0437385 -0.991843 0.115244 -0.054459 -0.993532 0.0708764 -0.0887139 -0.993481 0.0702034 -0.089817 -0.993652 0.0761424 -0.0828096 -0.993336 0.0925645 -0.0686653 -0.955315 0.252009 0.154483 -0.959464 0.236737 0.152922 -0.979662 0.125009 0.156953 -0.924937 0.314043 0.214168 -0.921836 0.334327 0.196071 -0.961744 0.246739 0.119028 -0.975248 0.212991 0.0593911 -0.931769 0.319457 0.172494 -0.937849 0.309164 0.157659 -0.990277 0.138938 -0.00695236 -0.994303 0.0992948 -0.0387455 -0.995036 0.0939765 -0.0327534 -0.993317 0.11451 -0.0144806 -0.97526 0.221012 -0.00469234 -0.957207 0.284524 0.0529259 -0.948157 0.314606 0.0449703 0.258819 -0.965926 0 0.258819 -0.965926 0 0.7071 -0.707113 0 0.7071 -0.707113 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258806 0 0.965929 0.258806 0 0.7071 0.707113 0 0.7071 0.707113 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707112 0.707102 0 -0.707112 0.707102 0 -0.965924 0.258828 0 -0.965924 0.258828 0 -0.965924 -0.258828 0 -0.965924 -0.258828 0 -0.707112 -0.707102 0 -0.707112 -0.707102 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.373491 -0.373498 0.849119 0.136709 -0.510204 0.849119 0.373491 0.373498 0.849119 0.510205 0.136702 0.84912 0.510205 -0.136702 0.84912 -0.373498 0.373493 0.849118 -0.136709 0.510204 0.849119 0.136709 0.510204 0.849119 -0.373498 -0.373493 0.849118 -0.510204 -0.136713 0.849118 -0.510204 0.136714 0.849118 -0.136709 -0.510204 0.849119 0.258819 -0.965926 0 0.258819 -0.965926 0 0.7071 -0.707113 0 0.7071 -0.707113 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258806 0 0.965929 0.258806 0 0.7071 0.707113 0 0.7071 0.707113 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707112 0.707102 0 -0.707112 0.707102 0 -0.965924 0.258828 0 -0.965924 0.258828 0 -0.965924 -0.258828 0 -0.965924 -0.258828 0 -0.707112 -0.707102 0 -0.707112 -0.707102 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.373491 -0.373498 0.849119 0.136709 -0.510204 0.849119 0.373491 0.373498 0.849119 0.510205 0.136702 0.84912 0.510205 -0.136702 0.84912 -0.373498 0.373493 0.849118 -0.136709 0.510204 0.849119 0.136709 0.510204 0.849119 -0.373498 -0.373493 0.849118 -0.510204 -0.136713 0.849118 -0.510204 0.136714 0.849118 -0.136709 -0.510204 0.849119 -0.0831147 0.798436 -0.596315 -0.413038 0.564984 -0.714277 -0.40822 0.497911 -0.765141 0.278984 0.716575 0.639288 0.380708 0.683591 -0.622708 0.377459 0.678647 -0.63005 0.484252 0.724285 -0.490827 0.480529 0.734595 -0.479022 0.625911 0.681989 -0.378321 0.841742 0.539204 0.0270029 0.773544 0.630946 0.0594693 0.625931 0.756044 -0.191332 0.62007 0.762189 -0.185958 0.6403 0.673345 -0.369624 0.696199 0.706075 0.129483 0.650025 0.712855 0.26326 0.681412 0.612148 0.401189 0.680731 0.612865 0.401249 0.3584 0.82039 0.445544 0.512443 0.681056 0.523034 0.349189 0.720715 0.598864 0.0874711 0.827393 0.55477 0.176315 0.711049 0.680678 -0.0156476 0.722277 0.691426 -0.205945 0.673181 0.710221 -0.202329 0.660702 0.722866 -0.0613598 0.721963 0.689205 -0.0157169 0.722291 0.691411 -0.325703 0.724923 0.606963 -0.391692 0.710001 0.585214 -0.530634 0.624378 0.573218 -0.497179 0.758125 0.42197 -0.624165 0.704962 0.336817 -0.629298 0.711531 0.312583 -0.676052 0.717689 0.166962 -0.630607 0.766987 0.118603 -0.773545 0.623361 -0.114233 -0.8336 0.546667 -0.0791652 -0.707504 0.683467 -0.179751 -0.630809 0.714096 -0.303559 -0.670708 0.591871 -0.447035 -0.662082 0.600554 -0.44831 -0.422219 0.759407 -0.495007 -0.167425 0.681752 -0.712168 0.0433468 0.690862 -0.721686 0.186422 0.592956 -0.783358 0.171201 0.531255 -0.829734 0.27002 0.703368 -0.657543 0.0831132 -0.798435 -0.596317 0.413039 -0.564981 -0.714279 0.408223 -0.497932 -0.765126 -0.278987 -0.716572 0.639289 -0.380708 -0.683591 -0.622708 -0.377459 -0.678647 -0.63005 -0.484251 -0.724285 -0.490828 -0.480527 -0.734597 -0.479021 -0.625896 -0.681998 -0.37833 -0.841742 -0.539204 0.0270029 -0.773544 -0.630946 0.0594693 -0.625931 -0.756044 -0.191331 -0.620073 -0.762187 -0.185959 -0.640302 -0.673344 -0.369622 -0.696199 -0.706075 0.129483 -0.650026 -0.712855 0.263257 -0.681414 -0.612145 0.40119 -0.680733 -0.612862 0.401251 -0.358402 -0.820388 0.445546 -0.512442 -0.681057 0.523035 -0.349203 -0.720712 0.598858 -0.087473 -0.827392 0.554771 -0.176318 -0.711049 0.680677 0.0156579 -0.722277 0.691426 0.205946 -0.673179 0.710223 0.20233 -0.660699 0.722869 0.0613526 -0.721964 0.689206 0.0157283 -0.722291 0.69141 0.325709 -0.724922 0.606961 0.391692 -0.710001 0.585214 0.530633 -0.624379 0.573218 0.497178 -0.758126 0.421971 0.624165 -0.704962 0.336817 0.629298 -0.711531 0.312583 0.676052 -0.717689 0.166961 0.630608 -0.766986 0.118601 0.729616 -0.683206 -0.0298284 0.701599 -0.708216 -0.0786657 0.694395 -0.694453 -0.188549 0.707508 -0.683464 -0.179748 0.630811 -0.714093 -0.30356 0.670709 -0.591868 -0.447036 0.662084 -0.600551 -0.448311 0.422219 -0.759406 -0.495009 0.167422 -0.681752 -0.712169 -0.043349 -0.690862 -0.721686 -0.186423 -0.592961 -0.783354 -0.171199 -0.531248 -0.829739 -0.270022 -0.703367 -0.657543 0.508587 0.694757 -0.508579 0.508592 0.694743 -0.508592 0.186157 0.694745 -0.694748 0.186157 0.694747 -0.694747 -0.186156 0.694747 -0.694747 -0.186157 0.694745 -0.694748 -0.508587 0.694744 -0.508596 -0.508601 0.69473 -0.508601 -0.69477 0.694723 -0.186157 -0.694755 0.694738 -0.186159 -0.694756 0.694739 0.186153 -0.694768 0.694724 0.186163 -0.508597 0.694729 0.508606 -0.508591 0.694746 0.508589 -0.186156 0.69475 0.694744 -0.186156 0.694751 0.694742 0.186155 0.694751 0.694743 0.186156 0.69475 0.694744 0.508594 0.694746 0.508586 0.508584 0.694757 0.508582 0.69473 0.694761 0.186163 0.694755 0.694738 0.186159 0.694754 0.694736 -0.186168 0.694734 0.69476 -0.186153 0.508578 0.694759 -0.508584 0.508574 0.694769 -0.508574 0.186154 0.694755 -0.694739 0.186153 0.694747 -0.694747 -0.186161 0.694746 -0.694746 -0.186155 0.694755 -0.694739 -0.508571 0.69477 -0.508577 -0.508581 0.69476 -0.508581 -0.694735 0.69476 -0.186148 -0.694722 0.694773 -0.18615 -0.694722 0.694774 0.186144 -0.694734 0.69476 0.186154 -0.50858 0.694756 0.508588 -0.508573 0.694772 0.508571 -0.186157 0.69476 0.694733 -0.186156 0.694751 0.694742 0.186155 0.694751 0.694743 0.18615 0.694759 0.694736 0.508567 0.694773 0.508576 0.508584 0.694757 0.508582 0.694736 0.694759 0.186148 0.694722 0.694773 0.18615 0.694722 0.694774 -0.186144 0.694733 0.694761 -0.186153 -0.508601 -0.694725 -0.508609 -0.508595 -0.694739 -0.508595 -0.186158 -0.694741 -0.694752 -0.186158 -0.694742 -0.694751 0.186157 -0.694742 -0.694751 0.186158 -0.694741 -0.694752 0.5086 -0.694738 -0.508592 0.508586 -0.694752 -0.508586 0.694735 -0.694757 -0.186163 0.694759 -0.694733 -0.18616 0.694758 -0.694732 0.18617 0.694738 -0.694755 0.186155 0.50859 -0.694753 0.508582 0.508594 -0.694742 0.508592 0.186157 -0.694745 0.694748 0.186157 -0.694747 0.694747 -0.186156 -0.694747 0.694747 -0.186157 -0.694745 0.694748 -0.508588 -0.694743 0.508596 -0.508605 -0.694726 0.508603 -0.694774 -0.694719 0.186158 -0.694759 -0.694733 0.18616 -0.69476 -0.694734 -0.186154 -0.694772 -0.69472 -0.186163 -0.508581 -0.694755 -0.508587 -0.508577 -0.694765 -0.508577 -0.186159 -0.694751 -0.694742 -0.186158 -0.694742 -0.694751 0.186157 -0.694742 -0.694751 0.186152 -0.69475 -0.694744 0.508574 -0.694766 -0.50858 0.508584 -0.694755 -0.508584 0.694739 -0.694756 -0.186149 0.694726 -0.694769 -0.186151 0.694727 -0.69477 0.186145 0.694738 -0.694755 0.186155 0.508583 -0.694751 0.508591 0.508576 -0.694768 0.508574 0.186154 -0.694755 0.694739 0.186153 -0.694747 0.694747 -0.186161 -0.694746 0.694746 -0.186155 -0.694755 0.694739 -0.50857 -0.694769 0.508579 -0.508587 -0.694752 0.508585 -0.694741 -0.694755 0.186149 -0.694726 -0.694769 0.186151 -0.694727 -0.69477 -0.186145 -0.694737 -0.694757 -0.186154 0.508591 -0.508591 0.694745 0.50858 -0.508585 0.694758 0.694735 -0.186149 0.69476 0.694722 -0.186149 0.694773 0.694722 0.186146 0.694774 0.694734 0.186152 0.69476 0.508582 0.508582 0.694758 0.508588 0.508593 0.694745 0.186158 0.694745 0.694748 0.186158 0.694744 0.694749 -0.186155 0.694745 0.694749 -0.186156 0.694746 0.694747 -0.508591 0.508591 0.694745 -0.50858 0.508585 0.694758 -0.694735 0.186149 0.69476 -0.694722 0.186149 0.694773 -0.694722 -0.186146 0.694774 -0.694734 -0.186152 0.69476 -0.508582 -0.508582 0.694758 -0.508588 -0.508593 0.694745 -0.186155 -0.694746 0.694747 -0.186155 -0.694743 0.694751 0.186156 -0.694742 0.694751 0.186158 -0.694745 0.694748 0.508591 -0.508591 0.694745 0.50858 -0.508585 0.694758 0.694735 -0.186149 0.69476 0.694722 -0.186149 0.694773 0.694722 0.186146 0.694774 0.694734 0.186152 0.69476 0.508582 0.508582 0.694758 0.508588 0.508593 0.694745 0.186158 0.694745 0.694748 0.186158 0.694744 0.694749 -0.186155 0.694745 0.694749 -0.186156 0.694746 0.694747 -0.508591 0.508591 0.694745 -0.50858 0.508585 0.694758 -0.694735 0.186149 0.69476 -0.694722 0.186149 0.694773 -0.694722 -0.186146 0.694774 -0.694734 -0.186152 0.69476 -0.508582 -0.508582 0.694758 -0.508588 -0.508593 0.694745 -0.186155 -0.694746 0.694747 -0.186155 -0.694745 0.694749 0.186157 -0.694744 0.694749 0.186158 -0.694745 0.694748 -0.000214045 -0.258818 0.965926 0.108445 -0.183889 0.976947 -8.93377e-05 0.422761 0.906241 0.0736126 0.258116 0.963305 0.0443362 0.224775 0.973402 3.76063e-05 0.0454727 0.998966 0.0113483 0.965864 0.258802 0.000444992 0.877391 0.479777 -0.00869708 0.707081 0.70708 0.0478845 0.748588 0.661304 9.28878e-05 0.534534 0.845147 0.0142761 0.965827 -0.258793 0 0.971949 -0.235192 0 0.969346 0.245699 0.023302 0.706915 -0.706914 -3.39385e-05 0.738824 -0.673899 2.87846e-05 0.878151 -0.478383 0.031978 0.258688 -0.965432 -2.56393e-05 0.324936 -0.945736 -6.52617e-05 0.5387 -0.842498 0.0398425 -0.258615 -0.965159 0.000138556 -0.172777 -0.984961 -1.16825e-05 0.0689675 -0.997619 -0.0123857 -0.707053 -0.707052 0.150863 -0.815001 -0.559476 0.0261289 -0.697425 -0.716181 9.70477e-05 -0.540234 -0.841515 4.449e-05 -0.421365 -0.906891 0 -0.992935 0.118661 0 -0.99992 -0.0126267 0.0127075 -0.965848 -0.258799 0.0790242 -0.977856 -0.193786 0.00438391 -0.915773 -0.401673 0.000144576 -0.437087 0.899419 0.000248908 -0.564821 0.825214 0.0790331 -0.704895 0.704894 0.0892551 -0.697256 0.711244 0.0150654 -0.797952 0.602533 -8.89307e-05 -0.850123 0.526585 0.000420955 -0.965926 0.25882 0.151397 -0.91886 0.364382 0.0689502 -0.967514 0.243233 0.539011 2.3569e-05 -0.842299 0.415322 -3.48345e-05 -0.909675 0.257148 0.113511 -0.959682 0.25005 0.104538 -0.962573 0.70467 0.0639572 -0.706647 0.705583 0.0656222 -0.705583 0.83724 1.93759e-05 -0.546836 0.891446 9.99477e-06 0.453127 0.964857 0.0535579 0.257258 0.964602 0.0522957 0.258471 0.998689 0 0.0511953 0.965924 0 -0.258825 0.978861 0.139148 -0.1499 0.911117 -2.18218e-05 -0.412148 0.80759 1.30082e-05 0.589745 0.704826 0.0802536 0.704826 0.623592 -0.00371218 0.781741 0.34111 0.0040962 0.940015 0.258041 0.0775658 0.963015 0.0909575 0 0.995855 -0.258101 0.0743746 0.963251 -0.244195 0.0612227 0.967792 -0.0685147 0 0.99765 -0.842431 -6.5511e-06 0.538805 -0.720647 0.0503969 0.691468 -0.705317 0.0711147 0.705317 -0.551641 -0.00371384 0.834073 -0.41776 0.00431606 0.908547 -0.963486 0.0710593 0.258159 -0.968001 0.13809 0.209538 -0.91679 -4.85576e-06 0.399369 -0.910224 0.220286 -0.350667 -0.965415 0.0325595 -0.258676 -0.976889 0.0694867 -0.202135 -0.997108 0 -0.0759975 -0.998716 0 0.0506659 -0.758431 0.0540392 -0.649509 -0.837367 -6.87421e-06 -0.546641 -0.874771 -6.09324e-06 -0.484537 -0.610635 0.229573 -0.757906 -0.706513 0.0409856 -0.706513 -0.519385 0 -0.85454 0.0817361 6.19104e-06 -0.996654 -0.0720471 -5.4602e-06 -0.997401 -0.257418 0.103838 -0.960705 -0.301649 0.0394442 -0.952603 -0.476256 0 -0.879307 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.965927 0.258813 0 0.965927 0.258813 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.965927 0.258813 0 0.965927 0.258813 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.886531 -1.11315e-05 0.462668 0.533071 -3.55166e-06 0.84607 -0.0929721 0.00176499 -0.995667 0.0840496 -0.00151179 -0.99646 0.193341 -0.0690547 -0.978698 0.256871 -0.122503 -0.95865 -0.257394 -0.120915 -0.958712 -0.256938 -0.120296 -0.958912 -0.415815 0 -0.909449 -0.833535 1.36518e-05 -0.552467 -0.704018 -0.0933629 -0.704018 -0.696236 -0.0745205 -0.713935 -0.541699 0 -0.840572 -0.939924 -0.129189 0.315997 -0.964923 -0.0455999 0.258544 -0.990906 -0.0268973 0.131839 -0.998896 0 0.0469729 -0.965927 0 -0.258813 -0.969067 -0.200823 -0.143457 -0.912493 -4.74396e-06 -0.409092 -0.704058 -0.0927544 0.704058 -0.795516 1.61982e-05 0.605933 -0.882367 2.28601e-06 0.470562 -0.0690582 -2.08301e-06 0.997613 -0.293488 -0.0789885 0.952694 -0.258654 -0.0355683 0.965315 -0.473689 1.18557e-05 0.880692 -0.611585 -1.80901e-05 0.791178 0.258821 1.70191e-06 0.965925 0.366023 -0.148969 0.918605 0.114713 -2.07421e-06 0.993399 0.707107 -1.70144e-05 0.707107 0.780005 -0.15376 0.60659 0.63199 -0.0232804 0.774627 0.966506 -0.0459406 0.2525 0.965187 -0.0390579 0.258628 0.999371 0 0.0354767 0.965924 7.50499e-05 -0.258825 0.908788 -0.183827 -0.374584 0.988815 0 -0.149148 0.36361 4.34824e-05 -0.931551 0.519237 -1.04394e-05 -0.85463 0.70666 -0.0355571 -0.70666 0.689698 -0.0703487 -0.720672 0.838325 -1.97341e-05 -0.54517 0.000205545 0.563201 0.82632 0.000174922 0.437228 0.899351 0.0781492 0.258027 0.962972 -3.86506e-05 0.852142 0.52331 0.0331383 0.706718 0.706718 0.111447 0.74711 0.655291 0.0353958 0.630245 0.775589 0 0.99055 0.137154 0.078905 0.962915 0.258011 0.0109072 0.92843 0.371346 -2.40947e-05 0.874561 0.484916 0 0.992491 -0.122318 0.0626135 0.964031 -0.258311 0.044972 0.955383 -0.291926 0.0257815 0.669243 -0.742596 0.0870849 0.76 -0.644062 0.0332312 0.706716 -0.706716 -9.92171e-05 0.840093 -0.542443 -8.32743e-05 0.911111 -0.412162 0.0399507 0.258613 -0.965154 -4.60845e-05 0.421233 -0.906953 0.000145165 0.553163 -0.833073 0.0311616 -0.258695 -0.965456 -0.000101024 -0.065669 -0.997841 3.88611e-05 0.172034 -0.985091 -3.28509e-05 -0.874623 -0.484804 -7.80491e-05 -0.738624 -0.674118 0.0231486 -0.706917 -0.706917 2.27477e-05 -0.539025 -0.84229 6.56102e-05 -0.322158 -0.946686 0.00138531 -0.889577 -0.456783 0.0180579 -0.965768 -0.258777 0 -0.973651 -0.228043 0 -0.986617 0.163056 0.0503986 -0.964698 0.25849 0.00215426 -0.913716 0.406349 0.0152266 -0.707025 0.707025 0.123235 -0.627452 0.768841 -0.00317986 -0.787985 0.615686 -7.17806e-05 0.189917 0.9818 9.89005e-05 -0.0418562 0.999124 0.0491657 -0.258505 0.964758 -0.000168569 -0.298743 0.954334 -4.70596e-05 -0.51173 0.859146 0.207662 0.0428507 -0.977262 0.258018 0.0785309 -0.962943 0.397449 -1.35787e-05 -0.917624 0.534322 -9.86475e-06 -0.845281 0.706482 0.0420452 -0.706482 0.73494 -1.80244e-05 -0.678132 0.875632 -1.28718e-05 -0.482978 0.965665 0.0233321 -0.258743 0.970806 0 -0.239866 0.909111 4.46115e-07 0.416554 0.96236 0.08587 0.257857 0.972539 0.0554683 0.226036 0.998012 0 0.0630294 0.707106 -3.46845e-06 0.707108 0.677906 0.059455 0.732741 0.844902 -5.43916e-06 0.534921 -0.267309 0.0782663 0.960427 -0.258248 0.066512 0.963786 -0.452361 -1.51863e-05 0.891835 -0.0844444 0.00820464 0.996394 -0.0216458 0 0.999766 0.258818 0 0.965926 0.239603 0.0308248 0.970382 0.482542 -1.20135e-05 0.875873 -0.965927 0 0.258813 -0.970733 0.0285005 0.238466 -0.875637 -1.4629e-05 0.482971 -0.707106 -2.1418e-05 0.707108 -0.735032 0.0615882 0.67523 -0.534314 -1.23206e-05 0.845286 -0.962364 0.0858203 -0.257858 -0.977682 0.0466894 -0.204837 -0.998012 0 -0.0630294 -0.706426 0.0438809 -0.706426 -0.844902 -4.78573e-06 -0.534921 -0.919898 1.4197e-06 -0.392157 0.0628638 0 -0.998022 -0.239374 0 -0.970928 -0.258754 0.0227448 -0.965676 -0.482542 -1.1339e-05 -0.875873 -0.677669 -5.23858e-06 -0.735367 -0.207661 -0.0428475 -0.977262 -0.258021 -0.0785293 -0.962942 -0.397449 1.35787e-05 -0.917624 -0.534322 9.86475e-06 -0.845281 -0.706482 -0.0420452 -0.706482 -0.73494 1.80244e-05 -0.678132 -0.875632 1.28718e-05 -0.482978 -0.965665 -0.0233321 -0.258743 -0.970806 0 -0.239866 -0.909111 -4.46116e-07 0.416554 -0.96236 -0.08587 0.257857 -0.972539 -0.0554683 0.226036 -0.998012 0 0.0630294 -0.707106 3.46845e-06 0.707108 -0.677906 -0.0594551 0.732741 -0.844902 5.43918e-06 0.534921 0.267308 -0.0782718 0.960427 0.258244 -0.0665132 0.963787 0.452361 1.51863e-05 0.891835 0.0844443 -0.00820632 0.996394 0.0216424 0 0.999766 -0.258821 0 0.965925 -0.239606 -0.0308245 0.970381 -0.482542 1.20135e-05 0.875873 0.965927 0 0.258813 0.970733 -0.0285006 0.238465 0.875637 1.4629e-05 0.482971 0.707106 2.1418e-05 0.707108 0.735032 -0.0615882 0.67523 0.534314 1.23206e-05 0.845286 0.962364 -0.0858205 -0.257858 0.977682 -0.0466894 -0.204837 0.998012 0 -0.0630294 0.706426 -0.043881 -0.706426 0.844902 4.78574e-06 -0.534921 0.919898 -1.4197e-06 -0.392157 -0.0628671 0 -0.998022 0.23937 0 -0.970928 0.258751 -0.0227451 -0.965676 0.482542 1.1339e-05 -0.875873 0.677669 5.23858e-06 -0.735367 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258821 0.965925 0 0.258821 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0.25882 -0.965925 0 0.25882 -0.965925 0 0.707103 -0.707111 0 0.707103 -0.707111 0 0.965929 -0.258808 0 0.965929 -0.258808 0 0.965929 0.258808 0 0.965929 0.258808 0 0.707103 0.707111 0 0.707103 0.707111 0 0.25882 0.965925 0 0.25882 0.965925 0 -0.25882 0.965925 0 -0.25882 0.965925 0 -0.707103 0.707111 0 -0.707103 0.707111 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707103 -0.707111 0 -0.707103 -0.707111 0 -0.25882 -0.965925 0 -0.25882 -0.965925 0 0.25882 -0.965925 0 0.25882 -0.965925 0 0.707103 -0.707111 0 0.707103 -0.707111 0 0.965929 -0.258808 0 0.965929 -0.258808 0 0.965929 0.258808 0 0.965929 0.258808 0 0.707103 0.707111 0 0.707103 0.707111 0 0.25882 0.965925 0 0.25882 0.965925 0 -0.25882 0.965925 0 -0.25882 0.965925 0 -0.707103 0.707111 0 -0.707103 0.707111 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707103 -0.707111 0 -0.707103 -0.707111 0 -0.25882 -0.965925 0 -0.25882 -0.965925 0 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258821 0.965925 0 0.258821 0.965925 0 0.707108 0.707106 0 0.707108 0.707106 0 0.965926 0.25882 0 0.965926 0.25882 0.965922 0 -0.258832 0.965922 0 -0.258832 0.707112 0 -0.707101 0.707112 0 -0.707101 0.258818 0 -0.965926 0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.965926 -0.707101 0 -0.707112 -0.707101 0 -0.707112 -0.965928 0 -0.258811 -0.965928 0 -0.258811 -0.965928 0 0.258811 -0.965928 0 0.258811 -0.707101 0 0.707112 -0.707101 0 0.707112 -0.258818 0 0.965926 -0.258818 0 0.965926 0.258818 0 0.965926 0.258818 0 0.965926 0.707112 0 0.707101 0.707112 0 0.707101 0.965922 0 0.258832 0.965922 0 0.258832 0.508588 -0.508582 0.694753 0.508605 -0.508584 0.69474 0.694748 -0.18618 0.694739 0.694763 -0.186174 0.694726 0.694762 0.186184 0.694724 0.694751 0.18617 0.694739 0.508597 0.508591 0.69474 0.508595 0.508577 0.694752 0.186161 0.694742 0.69475 0.186159 0.694746 0.694746 -0.186153 0.694747 0.694747 -0.186152 0.694746 0.694749 -0.508588 0.508582 0.694753 -0.508603 0.508584 0.694741 -0.694747 0.18618 0.69474 -0.694763 0.186174 0.694726 -0.694762 -0.186184 0.694724 -0.694752 -0.18617 0.694738 -0.508599 -0.508592 0.694738 -0.508596 -0.508576 0.694752 -0.186153 -0.694746 0.694749 -0.186152 -0.694747 0.694747 0.186162 -0.694746 0.694746 0.186158 -0.694743 0.694749 0.508588 -0.508582 0.694753 0.508603 -0.508584 0.694741 0.694747 -0.18618 0.69474 0.694763 -0.186174 0.694726 0.694762 0.186184 0.694724 0.694751 0.18617 0.694738 0.508597 0.508591 0.69474 0.508595 0.508577 0.694752 0.186161 0.694742 0.69475 0.186159 0.694746 0.694746 -0.186153 0.694747 0.694747 -0.186152 0.694746 0.694749 -0.508588 0.508582 0.694753 -0.508603 0.508584 0.694741 -0.694747 0.18618 0.69474 -0.694763 0.186173 0.694726 -0.694762 -0.186184 0.694724 -0.694751 -0.18617 0.694739 -0.508597 -0.508591 0.69474 -0.508595 -0.508577 0.694752 -0.186153 -0.694746 0.694749 -0.186152 -0.694747 0.694747 0.186162 -0.694746 0.694746 0.186158 -0.694743 0.694749 -0.965928 0 -0.258811 -0.965928 0 -0.258811 -0.707101 0 -0.707112 -0.707101 0 -0.707112 -0.258818 0 -0.965926 -0.258818 0 -0.965926 0.258818 0 -0.965926 0.258818 0 -0.965926 0.707112 0 -0.707101 0.707112 0 -0.707101 0.965922 0 -0.258832 0.965922 0 -0.258832 0.965922 0 0.258832 0.965922 0 0.258832 0.707112 0 0.707101 0.707112 0 0.707101 0.258818 0 0.965926 0.258818 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.965926 -0.707101 0 0.707112 -0.707101 0 0.707112 -0.965928 0 0.258811 -0.965928 0 0.258811 0.965928 0 -0.258811 0.965928 0 -0.258811 0.707103 0 -0.707111 0.707103 0 -0.707111 0.258818 0 -0.965926 0.258818 0 -0.965926 -0.258824 0 -0.965925 -0.258824 0 -0.965925 -0.707103 0 -0.707111 -0.707103 0 -0.707111 -0.965928 0 -0.258811 -0.965928 0 -0.258811 -0.965928 0 0.258811 -0.965928 0 0.258811 -0.707101 0 0.707112 -0.707101 0 0.707112 -0.258824 0 0.965925 -0.258824 0 0.965925 0.258818 0 0.965926 0.258818 0 0.965926 0.707101 0 0.707112 0.707101 0 0.707112 0.965928 0 0.258811 0.965928 0 0.258811 0.258826 -0.965924 0 0.258826 -0.965924 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.965918 -0.258849 0 0.965918 -0.258849 0 0.965918 0.258849 0 0.965918 0.258849 0 0.707111 0.707102 0 0.707111 0.707102 0 0.258826 0.965924 0 0.258826 0.965924 0 -0.258814 0.965927 0 -0.258814 0.965927 0 -0.707111 0.707102 0 -0.707111 0.707102 0 -0.965918 0.258849 0 -0.965918 0.258849 0 -0.965918 -0.258849 0 -0.965918 -0.258849 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 0.258826 -0.965924 0 0.258826 -0.965924 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.965918 -0.258849 0 0.965918 -0.258849 0 0.965918 0.258849 0 0.965918 0.258849 0 0.707111 0.707102 0 0.707111 0.707102 0 0.258826 0.965924 0 0.258826 0.965924 0 -0.258814 0.965927 0 -0.258814 0.965927 0 -0.707111 0.707102 0 -0.707111 0.707102 0 -0.965918 0.258849 0 -0.965918 0.258849 0 -0.965918 -0.258849 0 -0.965918 -0.258849 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.965928 0 -0.258811 -0.965928 0 -0.258811 -0.707103 0 -0.707111 -0.707103 0 -0.707111 -0.258824 0 -0.965925 -0.258824 0 -0.965925 0.258818 0 -0.965926 0.258818 0 -0.965926 0.707103 0 -0.707111 0.707103 0 -0.707111 0.965928 0 -0.258811 0.965928 0 -0.258811 0.965928 0 0.258811 0.965928 0 0.258811 0.707101 0 0.707112 0.707101 0 0.707112 0.258818 0 0.965926 0.258818 0 0.965926 -0.258824 0 0.965925 -0.258824 0 0.965925 -0.707101 0 0.707112 -0.707101 0 0.707112 -0.965928 0 0.258811 -0.965928 0 0.258811 -2.61314e-06 -0.974372 -0.224943 9.83447e-06 0.551633 -0.834087 -0.00622223 0.155149 0.987871 0.00502037 0.0768025 0.997034 0.0330695 0.0243553 0.999156 0.0262571 -0.218658 0.975448 0.230072 -0.117303 0.966078 0.12567 -0.0600429 0.990254 0.0757782 -0.0223829 0.996873 -1.40879e-05 0.581305 0.813686 5.90347e-05 0.510655 0.859786 0.319664 0.335999 0.885957 0.442456 0.344354 0.828042 0.112342 0.297219 0.948177 -5.33316e-06 0.893088 0.449882 5.18679e-05 0.831032 0.556225 0.591422 0.603571 0.534717 0.502042 0.634414 0.587769 0.0660132 0.666223 0.742826 0 0.99621 0.0869867 0.605268 0.780453 0.156666 0.745434 0.64721 0.159523 0.475355 0.841392 0.257093 0.0636119 0.914983 0.398447 -2.70354e-05 0.910657 -0.413164 0.282861 0.899204 -0.333798 0.680824 0.711163 -0.175286 0.626079 0.758979 -0.17882 0 0.998304 -0.0582204 -6.23554e-05 0.640404 -0.768038 0.358265 0.661956 -0.658377 0.575509 0.612129 -0.542299 0.270769 0.762932 -0.587043 1.35616e-05 0.869716 -0.493552 -0.0163538 0.22513 -0.974191 0.32247 0.335662 -0.885067 0.314241 0.339482 -0.886569 0.0478746 0.488943 -0.871001 0.125669 -0.0600431 -0.990254 0.0757821 -0.0223871 -0.996873 0.0330653 0.0243598 -0.999156 0.00501849 0.0768028 -0.997034 0.17829 -0.502041 -0.846267 0.466273 -0.502533 -0.728045 5.28848e-05 -0.675156 -0.737675 0.045431 -0.430255 -0.901563 -5.50571e-05 -0.387348 -0.921933 0.000378678 -0.120537 -0.992709 0.455767 -0.184945 -0.870673 0.223869 -0.113898 -0.967941 8.7177e-06 -0.953818 -0.300385 0.474006 -0.803389 -0.360396 0.697519 -0.634488 -0.333005 0.0972698 -0.834118 -0.542942 -4.47837e-06 -0.757927 -0.652339 -4.77774e-06 -0.984007 0.178129 0.507227 -0.860197 0.0527509 0.765941 -0.642911 0 0.301485 -0.949711 -0.084589 0.0386343 -0.980624 -0.192053 -5.41414e-05 -0.803883 0.594788 0.639965 -0.680733 0.356438 0.634252 -0.68457 0.35929 0.222144 -0.914439 0.338308 3.06085e-06 -0.959048 0.283244 -0.010658 -0.396937 0.917784 0.13165 -0.477964 0.868458 0.425459 -0.514086 0.744782 0.207222 -0.599591 0.773014 1.40556e-05 -0.728313 0.685244 0 0.032585 0.999469 0 -0.0325852 0.999469 -0.00091666 -0.392751 0.919644 0.267747 -0.24937 0.930659 0.102264 -0.183795 0.977631 0.0243115 -0.0934894 0.995323 -0.000125439 0.554043 0.832488 0.000253065 0.449048 0.893508 0.229522 0.25191 0.940139 0.147295 0.235521 0.960643 0.0243116 0.0934893 0.995323 0.2971 0.654029 0.695685 0.485895 0.618024 0.618024 -0.000295037 0.828898 0.5594 0.691602 0.697668 0.186939 0.441383 0.855599 0.270429 -0.000439074 0.892132 0.451776 0.0128497 0.904677 -0.425903 0.471818 0.834851 -0.283568 0.716291 0.674025 -0.180604 0 0.990711 -0.135981 0 0.995856 0.0909423 -0.0165851 0.81424 -0.580291 0.526495 0.601167 -0.601167 0.475744 0.614022 -0.629797 0 -0.0325807 -0.999469 0 0.0325806 -0.999469 0.0243133 0.0934891 -0.995323 0.102265 0.183794 -0.977631 0.267748 0.249369 -0.930659 -0.00091666 0.392751 -0.919644 0.00112333 0.606194 -0.795316 0.000251514 -0.449047 -0.893508 0.22952 -0.251909 -0.94014 0.147297 -0.235521 -0.960642 0.0243131 -0.0934891 -0.995323 -0.000439076 -0.892132 -0.451776 -0.000295034 -0.828899 -0.559399 0.485897 -0.618023 -0.618022 0.297096 -0.654029 -0.695686 -0.000126461 -0.554044 -0.832487 0.441385 -0.855598 -0.270428 0.691597 -0.697673 -0.186941 0 -0.995856 -0.0909454 0 -0.990711 0.135982 0.716289 -0.674027 0.180605 0.471821 -0.83485 0.283567 0.00112332 -0.606194 0.795316 0.475747 -0.614021 0.629796 0.526496 -0.601167 0.601167 -0.0165834 -0.81424 0.580291 0.0128533 -0.904678 0.425903 0 0.0325852 0.999469 0 -0.032585 0.999469 -0.000916664 -0.392751 0.919644 0.267746 -0.24937 0.930659 0.102264 -0.183795 0.977631 0.0243116 -0.0934894 0.995323 -0.000123497 0.554044 0.832487 0.000254638 0.449047 0.893508 0.229522 0.25191 0.940139 0.147295 0.235521 0.960643 0.0243115 0.0934894 0.995323 0.2971 0.654029 0.695685 0.485893 0.618024 0.618025 -0.000300965 0.828898 0.559399 0.691598 0.697671 0.18694 0.441378 0.855601 0.27043 -0.000445458 0.892132 0.451775 0.01285 0.904678 -0.425902 0.471813 0.834854 -0.283569 0.716288 0.674028 -0.180605 0 0.990711 -0.135982 0 0.995856 0.0909439 -0.0165851 0.81424 -0.580291 0.526496 0.601167 -0.601167 0.475738 0.614023 -0.629801 0 -0.0325806 -0.999469 0 0.0325807 -0.999469 0.0243131 0.0934891 -0.995323 0.102265 0.183794 -0.977631 0.267748 0.249369 -0.930659 -0.00091666 0.392751 -0.919644 0.00112333 0.606194 -0.795316 0.000249941 -0.449048 -0.893507 0.22952 -0.251909 -0.94014 0.147298 -0.235521 -0.960642 0.0243133 -0.0934891 -0.995323 -0.000439076 -0.892132 -0.451776 -0.000295032 -0.828898 -0.5594 0.485894 -0.618024 -0.618024 0.297097 -0.65403 -0.695686 -0.000128394 -0.554043 -0.832488 0.441385 -0.855598 -0.270428 0.691597 -0.697673 -0.186941 0 -0.995856 -0.0909454 0 -0.990711 0.135982 0.716289 -0.674027 0.180605 0.471821 -0.83485 0.283567 0.00112332 -0.606194 0.795316 0.475753 -0.61402 0.629792 0.526493 -0.601168 0.601168 -0.0165892 -0.81424 0.580291 0.0128465 -0.904677 0.425904 3.62065e-06 0.519724 -0.854334 0 0.997953 -0.0639521 -0.0359465 0.998993 0.0268357 -0.0286697 0.999568 0.0064143 0 0.107664 -0.994187 6.6885e-05 0.107422 -0.994214 -3.768e-05 0.272561 -0.962139 -1.59347e-05 0.355311 -0.934748 -0.046472 0.45852 -0.887468 -0.0188764 0.383273 -0.923442 5.05975e-07 0.886884 -0.461993 -0.00297178 0.849706 -0.527248 -0.0166167 0.816319 -0.577363 -0.00242457 0.777967 -0.6283 0.00527068 0.612496 -0.790456 -0.0430118 0.689902 -0.722624 -0.00957978 0.599381 -0.800407 -0.00740758 0.99805 -0.0619821 0.00314938 0.983434 -0.181239 -0.0135891 0.949269 -0.31417 -0.0172308 0.95224 -0.304863 -1.38013e-06 0.913751 -0.406275 0.508584 0.694733 -0.508614 0.508581 0.694754 -0.508588 0.186162 0.69475 -0.694742 0.186161 0.694746 -0.694746 -0.186155 0.694747 -0.694747 -0.186162 0.694739 -0.694752 -0.508607 0.694725 -0.508603 -0.508594 0.694735 -0.508601 -0.694761 0.694734 -0.18615 -0.694727 0.694764 -0.186164 -0.69473 0.694767 0.186142 -0.694751 0.694739 0.18617 -0.508596 0.69474 0.508592 -0.508599 0.694726 0.508609 -0.186157 0.694739 0.694755 -0.186161 0.694746 0.694746 0.186164 0.694746 0.694746 0.18616 0.69475 0.694743 0.508569 0.694757 0.508598 0.50859 0.694739 0.5086 0.694759 0.694736 0.18615 0.694767 0.694729 0.186147 0.694766 0.694729 -0.186151 0.694762 0.694734 -0.186146 0.3735 -0.373496 0.849116 0.136712 -0.510203 0.849119 0.3735 0.373496 0.849116 0.510203 0.136726 0.849117 0.510203 -0.136725 0.849117 -0.373496 0.373491 0.84912 -0.136706 0.510204 0.849119 0.136712 0.510204 0.849118 -0.373495 -0.373491 0.849121 -0.510194 -0.136723 0.849122 -0.510194 0.136723 0.849122 -0.136706 -0.510204 0.849119 0.3735 -0.373496 0.849116 0.136712 -0.510204 0.849118 0.3735 0.373496 0.849116 0.510203 0.136725 0.849117 0.510203 -0.136726 0.849117 -0.373495 0.373491 0.849121 -0.136706 0.510204 0.849119 0.136712 0.510203 0.849119 -0.373496 -0.373491 0.84912 -0.510194 -0.136723 0.849122 -0.510194 0.136723 0.849122 -0.136706 -0.510204 0.849119 -0.508599 -0.694736 -0.508595 -0.508601 -0.694726 -0.508607 -0.186157 -0.694739 -0.694755 -0.186161 -0.694746 -0.694746 0.186164 -0.694746 -0.694746 0.18616 -0.69475 -0.694743 0.508569 -0.694757 -0.508598 0.508594 -0.694735 -0.508601 0.694761 -0.694734 -0.18615 0.694767 -0.694729 -0.186147 0.694766 -0.694728 0.186152 0.694761 -0.694735 0.186146 0.508582 -0.694737 0.508611 0.508579 -0.694755 0.508589 0.186162 -0.69475 0.694742 0.186161 -0.694746 0.694746 -0.186155 -0.694747 0.694747 -0.186162 -0.694739 0.694752 -0.508607 -0.694725 0.508603 -0.50859 -0.694739 0.5086 -0.694759 -0.694736 0.18615 -0.694727 -0.694764 0.186164 -0.69473 -0.694768 -0.186141 -0.694752 -0.694737 -0.186171 0.508598 0.69474 -0.50859 0.508596 0.694752 -0.508576 0.186154 0.694749 -0.694745 0.186152 0.694743 -0.694752 -0.186165 0.694741 -0.69475 -0.186157 0.694749 -0.694744 -0.50859 0.694753 -0.508581 -0.508604 0.694741 -0.508583 -0.694747 0.69474 -0.18618 -0.694763 0.694726 -0.186174 -0.694762 0.694724 0.186184 -0.694751 0.694739 0.18617 -0.508598 0.69474 0.50859 -0.508597 0.694749 0.50858 -0.18616 0.694745 0.694748 -0.186161 0.694746 0.694746 0.186151 0.694747 0.694747 0.186154 0.694744 0.69475 0.508592 0.694749 0.508584 0.508602 0.694741 0.508585 0.694747 0.69474 0.18618 0.694763 0.694726 0.186174 0.694762 0.694724 -0.186184 0.694751 0.694739 -0.18617 0.96593 0 -0.258805 0.96593 0 -0.258805 0.707087 0 -0.707127 0.707087 0 -0.707127 0.258828 0 -0.965923 0.258828 0 -0.965923 -0.258817 0 -0.965927 -0.258817 0 -0.965927 -0.70711 0 -0.707104 -0.70711 0 -0.707104 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.965929 0 0.258806 -0.965929 0 0.258806 -0.70711 0 0.707104 -0.70711 0 0.707104 -0.258817 0 0.965927 -0.258817 0 0.965927 0.258828 0 0.965923 0.258828 0 0.965923 0.707087 0 0.707127 0.707087 0 0.707127 0.965929 0 0.258806 0.965929 0 0.258806 -0.96593 0 -0.258805 -0.96593 0 -0.258805 -0.70711 0 -0.707104 -0.70711 0 -0.707104 -0.258817 0 -0.965927 -0.258817 0 -0.965927 0.258828 0 -0.965923 0.258828 0 -0.965923 0.707087 0 -0.707127 0.707087 0 -0.707127 0.96593 0 -0.258805 0.96593 0 -0.258805 0.965929 0 0.258806 0.965929 0 0.258806 0.707087 0 0.707127 0.707087 0 0.707127 0.258828 0 0.965923 0.258828 0 0.965923 -0.258817 0 0.965927 -0.258817 0 0.965927 -0.70711 0 0.707104 -0.70711 0 0.707104 -0.965929 0 0.258806 -0.965929 0 0.258806 -0.508595 -0.694745 -0.508587 -0.508593 -0.694757 -0.508573 -0.186161 -0.694755 -0.694737 -0.186157 -0.694747 -0.694747 0.186155 -0.694747 -0.694747 0.186149 -0.694753 -0.694742 0.508586 -0.694758 -0.508578 0.5086 -0.694746 -0.50858 0.694743 -0.694745 -0.186179 0.694759 -0.69473 -0.186172 0.694757 -0.694729 0.186183 0.694747 -0.694743 0.186169 0.508595 -0.694745 0.508587 0.508594 -0.694753 0.508577 0.186151 -0.694748 0.694746 0.186152 -0.694752 0.694743 -0.186158 -0.694751 0.694742 -0.18616 -0.69475 0.694743 -0.508589 -0.694754 0.50858 -0.508599 -0.694746 0.508582 -0.694743 -0.694745 0.186179 -0.694759 -0.69473 0.186172 -0.694757 -0.694729 -0.186183 -0.694747 -0.694743 -0.186169 0.965918 0 -0.258849 0.965918 0 -0.258849 0.707113 0 -0.707101 0.707113 0 -0.707101 0.258817 0 -0.965927 0.258817 0 -0.965927 -0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.707113 0 -0.707101 -0.707113 0 -0.707101 -0.965918 0 -0.258849 -0.965918 0 -0.258849 -0.965918 0 0.258849 -0.965918 0 0.258849 -0.707113 0 0.707101 -0.707113 0 0.707101 -0.258823 0 0.965925 -0.258823 0 0.965925 0.258811 0 0.965928 0.258811 0 0.965928 0.707113 0 0.707101 0.707113 0 0.707101 0.965918 0 0.258849 0.965918 0 0.258849 0.373483 0.84912 -0.373505 0.510203 0.849121 -0.1367 -0.373493 0.849122 -0.37349 -0.136707 0.849121 -0.510201 0.136713 0.84912 -0.510201 -0.373494 0.849121 0.373491 -0.510203 0.849121 0.136701 -0.510203 0.849121 -0.1367 0.373484 0.849119 0.373505 0.136713 0.849119 0.510202 -0.136707 0.84912 0.510202 0.510203 0.849121 0.136701 -0.373495 -0.849121 -0.373492 -0.510205 -0.84912 -0.136701 0.373485 -0.849119 -0.373506 0.136714 -0.849119 -0.510203 -0.136707 -0.84912 -0.510203 0.373485 -0.849118 0.373507 0.510205 -0.84912 0.136702 0.510205 -0.84912 -0.136701 -0.373495 -0.84912 0.373492 -0.136707 -0.849119 0.510204 0.136714 -0.849118 0.510204 -0.510205 -0.84912 0.136702 -0.965918 0 -0.258849 -0.965918 0 -0.258849 -0.707113 0 -0.707101 -0.707113 0 -0.707101 -0.258828 0 -0.965923 -0.258828 0 -0.965923 0.258817 0 -0.965927 0.258817 0 -0.965927 0.707113 0 -0.707101 0.707113 0 -0.707101 0.965918 0 -0.258849 0.965918 0 -0.258849 0.965918 0 0.258849 0.965918 0 0.258849 0.707113 0 0.707101 0.707113 0 0.707101 0.258811 0 0.965928 0.258811 0 0.965928 -0.258823 0 0.965925 -0.258823 0 0.965925 -0.707113 0 0.707101 -0.707113 0 0.707101 -0.965918 0 0.258849 -0.965918 0 0.258849 0.373495 0.849122 -0.373489 0.510192 0.849124 -0.136723 -0.3735 0.849117 -0.373494 -0.136713 0.84912 -0.510201 0.136707 0.849121 -0.510201 -0.3735 0.849117 0.373494 -0.510201 0.849118 0.136725 -0.510201 0.849118 -0.136725 0.373495 0.849122 0.373489 0.136704 0.84912 0.510203 -0.13671 0.84912 0.510202 0.510192 0.849124 0.136723 -0.373501 -0.849116 -0.373495 -0.510203 -0.849117 -0.136726 0.373496 -0.84912 -0.37349 0.136707 -0.84912 -0.510203 -0.136714 -0.849119 -0.510203 0.373496 -0.84912 0.37349 0.510194 -0.849122 0.136723 0.510194 -0.849122 -0.136723 -0.373501 -0.849116 0.373495 -0.136711 -0.849118 0.510204 0.136704 -0.849119 0.510204 -0.510203 -0.849117 0.136726 -0.928777 0.370578 0.00674054 -0.940517 0.32872 0.085854 -0.940496 0.32876 0.0859326 -0.958009 0.265135 0.109188 -0.97531 0.161293 0.150846 -0.967214 0.197263 0.159955 -0.963027 0.185239 0.195613 -0.93886 0.27968 0.200803 -0.933832 0.258322 0.247444 -0.947082 0.250235 0.201042 -0.970573 0.207041 0.12297 -0.912331 0.339598 0.228746 -0.948369 0.26885 0.168274 -0.951887 0.256547 0.167615 -0.969119 0.199029 0.145589 -0.967926 0.206819 0.142633 -0.979908 0.149259 0.132296 -0.979487 0.157388 0.125832 -0.644385 0.694052 0.321031 -0.603322 0.723854 0.334721 -0.646501 0.758225 0.0844417 -0.680672 0.732118 0.0262459 -0.652823 0.755782 0.0511384 -0.645072 0.762194 0.054256 -0.643551 0.751509 0.145176 -0.606618 0.771613 0.191387 -0.63629 0.751987 0.17219 -0.631013 0.740749 0.230465 -0.626272 0.739245 0.247589 -0.62766 0.734498 0.257985 -0.610938 0.724256 0.3197 -0.59884 0.742441 0.300285 -0.604152 0.728024 0.32401 -0.651945 0.645805 0.397371 -0.635691 0.699007 0.327545 -0.607533 0.690895 0.391878 -0.652285 0.689397 0.315048 -0.968218 -0.204917 0.1434 -0.969112 -0.199022 0.145643 -0.936632 -0.340324 0.0830699 -0.938986 -0.336587 0.0708136 -0.928774 -0.370577 0.00717304 -0.957972 -0.265149 0.109482 -0.951812 -0.256817 0.16763 -0.926737 -0.334364 0.171345 -0.931587 -0.286965 0.223154 -0.9247 -0.309157 0.222152 -0.924772 -0.291975 0.244023 -0.929178 -0.284203 0.23634 -0.919645 -0.297544 0.256361 -0.979085 -0.154775 0.132054 -0.971317 -0.176156 0.159725 -0.965976 -0.196186 0.168529 -0.963009 -0.184788 0.19613 -0.960032 -0.20953 0.185568 -0.653471 -0.756528 0.0253187 -0.662133 -0.746067 0.0704534 -0.639565 -0.768725 0.0044114 -0.645908 -0.763217 0.0173983 -0.652345 -0.753328 0.0833276 -0.632899 -0.755473 0.16941 -0.642692 -0.743605 0.184389 -0.604135 -0.728568 0.322814 -0.603366 -0.723904 0.334533 -0.623834 -0.738405 0.256105 -0.630586 -0.73559 0.247527 -0.617908 -0.730399 0.291045 -0.602326 -0.733261 0.315486 -0.650043 -0.689276 0.319911 -0.622563 -0.70777 0.333881 -0.638241 -0.690972 0.33942 -0.647675 -0.687669 0.328066 -0.661477 -0.698204 0.273789 -0.662242 -0.654203 0.365314 -0.621384 -0.661871 0.419296 -0.665746 -0.689479 0.285308 -0.738408 -0.630646 0.238828 -0.695993 -0.65547 0.293176 -0.671182 -0.653633 0.349684 -0.677798 -0.647416 0.348487 -0.64742 -0.664587 0.373057 -0.732139 -0.673285 0.10325 -0.715873 -0.688953 0.113449 -0.720448 -0.670381 0.177606 -0.723901 -0.6673 0.175153 -0.715828 -0.672477 0.188057 -0.79291 -0.606429 0.0594723 -0.763217 -0.636239 0.112694 -0.777319 -0.624902 0.0726113 -0.840878 -0.538699 0.0522282 -0.844642 -0.533635 0.0425861 -0.959297 -0.257176 0.116658 -0.965785 -0.242793 0.0911658 -0.948913 -0.227614 0.218532 -0.994524 -0.00807846 0.104197 -0.992866 -0.00653956 0.119053 -0.992741 -0.00604733 0.120117 -0.956733 -0.0161943 0.290517 -0.960798 -0.0120854 0.276985 -0.939957 -0.00393992 0.34127 -0.999098 -0.0348564 0.0242668 -0.993182 -0.113747 0.0255043 -0.984369 -0.122034 0.126986 -0.991494 -0.10371 0.0786429 -0.971673 -0.0847361 0.220617 -0.967071 -0.0926517 0.237043 -0.888226 -0.455369 -0.0607807 -0.913027 -0.327898 0.242622 -0.971335 -0.206599 0.117584 -0.919947 -0.382428 0.086291 -0.910683 -0.399465 0.105281 -0.866677 -0.370054 0.334562 -0.839104 -0.537606 0.0829694 -0.81876 -0.549897 0.165064 -0.761663 -0.6369 0.119281 -0.764776 -0.638139 0.088863 -0.767625 -0.625726 0.138633 -0.679512 -0.63457 0.368217 -0.883995 0.0833861 0.46 -0.629701 -0.723993 0.281623 -0.691083 -0.666732 0.279058 -0.783663 -0.594579 0.179853 -0.647669 -0.734337 0.20316 -0.711919 -0.6819 0.167878 -0.700056 -0.256753 -0.666333 -0.871635 -0.48325 0.0819831 -0.684877 -0.696482 -0.214141 -0.77928 -0.626482 -0.0155961 -0.991565 -0.0345936 -0.124912 -0.990155 -0.00804434 -0.139745 -0.978778 0.0266247 -0.203186 -0.803439 -0.590986 -0.0722562 -0.823908 -0.559874 -0.087842 -0.758072 -0.635751 -0.14542 -0.642578 -0.487289 -0.591305 -0.674543 -0.471817 -0.567786 -0.68713 -0.453695 -0.567462 -0.697209 -0.50647 -0.507335 -0.716366 -0.508104 -0.478174 -0.710314 -0.481585 -0.513353 -0.682307 -0.544013 -0.488371 -0.704966 -0.621576 -0.341564 -0.728459 -0.630711 -0.267491 -0.641826 -0.656114 -0.396956 -0.675449 -0.640057 -0.366191 -0.668964 -0.743119 -0.0161582 -0.696463 -0.717565 0.00627422 -0.695472 -0.718031 -0.0273932 -0.675726 -0.732253 -0.0848551 -0.679164 -0.73243 -0.0477833 -0.669144 -0.743133 0.000715045 -0.653657 -0.756745 -0.0083745 -0.645969 -0.76329 -0.0105637 -0.706758 -0.6994 -0.10645 -0.693301 -0.688341 -0.213355 -0.748641 -0.660126 -0.0614098 -0.756623 -0.653688 -0.0146417 -0.761002 -0.64849 -0.0183512 -0.79505 -0.606327 0.0162274 -0.910126 -0.405305 0.0860183 -0.90404 -0.415019 0.102327 -0.904299 -0.415914 0.0962231 -0.913222 -0.402663 0.0623563 -0.951876 -0.279394 0.12598 -0.950065 -0.303607 0.0721139 -0.939888 -0.334922 0.0666103 -0.916196 -0.39062 0.0894495 -0.93201 -0.356763 0.0638502 -0.914029 -0.401036 0.0610007 -0.91454 -0.400012 0.0600533 -0.922389 -0.38567 0.0213844 -0.917748 -0.396405 0.0245507 -0.928773 -0.370576 -0.00735335 -0.995717 -0.0551003 -0.074235 -0.987071 -0.0375983 -0.155814 -0.985676 -0.0355125 -0.164871 -0.983855 -0.0609342 -0.168278 -0.987757 -0.0457024 -0.149155 -0.989767 -0.0442853 -0.135645 -0.988809 -0.049662 -0.140681 -0.992314 -0.0555689 -0.110566 -0.990669 -0.0697414 -0.117096 -0.995278 -0.0515811 -0.0822298 -0.991083 -0.118221 -0.0614715 -0.991257 -0.116979 -0.0610382 -0.997779 -0.0246123 -0.0618993 -0.998289 -0.0404827 -0.0421948 -0.997936 -0.0384139 -0.0514599 -0.995629 -0.0828509 -0.0431029 -0.993557 -0.111558 -0.0199966 -0.99297 -0.116408 -0.021442 -0.985477 -0.169706 -0.0058413 -0.988093 -0.153469 0.0108844 -0.977475 -0.210911 0.0077428 -0.97848 -0.204647 0.0264122 -0.959021 -0.278316 0.0530988 -0.954306 -0.297654 0.0264916 -0.913468 -0.378885 0.148402 -0.887502 -0.405107 -0.219608 -0.805479 -0.459543 0.374197 -0.85641 -0.507391 0.0954788 -0.850989 -0.518688 0.0823453 -0.710603 -0.372422 -0.596947 -0.614407 -0.245368 -0.749866 -0.928729 -0.326096 0.17642 -0.369133 -0.100597 -0.923916 -0.765368 -0.0182007 -0.643335 -0.765156 -0.0180617 -0.643591 -0.854596 0.00172747 -0.51929 -0.848472 0.0103413 -0.529139 -0.934581 -0.0283693 -0.354618 -0.959084 -0.257119 -0.11852 -0.959665 -0.245586 -0.136861 -0.913946 -0.235438 -0.330563 -0.912686 -0.23185 -0.336527 -0.840247 -0.215505 -0.497536 -0.835304 -0.207531 -0.509116 -0.767338 -0.192355 -0.611712 -0.758642 -0.181457 -0.625729 -0.669902 -0.162248 -0.724504 -0.697475 -0.0226465 -0.716251 -0.676346 -0.024361 -0.736181 -0.684305 0.00228055 -0.729192 -0.637981 -0.0630694 -0.767465 -0.76351 -0.0736189 -0.641587 -0.767747 -0.0778012 -0.636013 -0.846012 -0.0844514 -0.526432 -0.848936 -0.08801 -0.521116 -0.931042 -0.094817 -0.352378 -0.93227 -0.0971372 -0.348477 -0.986938 -0.101265 -0.125293 -0.988161 -0.113172 -0.103582 -0.626655 -0.0937159 -0.773641 -0.787532 -0.183631 -0.588279 -0.689782 -0.145759 -0.709193 -0.670877 -0.285082 -0.684582 -0.745378 -0.313763 -0.588187 -0.757483 -0.334659 -0.560556 -0.807966 -0.354796 -0.470438 -0.81371 -0.368946 -0.44917 -0.868637 -0.39127 -0.303937 -0.869437 -0.396659 -0.294519 -0.905966 -0.411371 -0.0999934 -0.91072 -0.378593 -0.165094 -0.830252 -0.554141 0.0600848 -0.802907 -0.591573 0.073366 -0.568412 -0.421613 0.706505 -0.625384 -0.548395 -0.55512 -0.610928 -0.535845 -0.582784 -0.629531 -0.550058 -0.548751 -0.75206 -0.598335 -0.276408 -0.766173 -0.605182 -0.21618 -0.47647 -0.336162 -0.812386 -0.56842 -0.390956 -0.723915 -0.771606 -0.406169 -0.489542 -0.709744 -0.376045 -0.595696 -0.665299 -0.411939 -0.622642 -0.736172 -0.451871 -0.503849 -0.721016 -0.454136 -0.523352 -0.759136 -0.492544 -0.425573 -0.767127 -0.491992 -0.411654 -0.791358 -0.542367 -0.282117 -0.803279 -0.537358 -0.256884 -0.809091 -0.546574 -0.215936 -0.829581 -0.558247 -0.0124583 -0.841621 -0.531726 -0.0945584 -0.863084 -0.410822 0.29379 -0.997666 -0.0438854 -0.0523207 -0.922219 -0.360756 0.139163 -0.980652 -0.194822 0.0191347 -0.817893 -0.524054 0.237525 -0.743974 -0.520224 0.419369 -0.806869 -0.478167 0.34687 -0.795153 -0.516037 0.318494 -0.787739 -0.521767 0.327454 -0.81961 -0.513958 0.253153 -0.17153 -0.746325 0.643099 -0.954426 -0.247238 -0.167165 -0.954463 -0.23078 -0.189055 -0.954336 -0.229559 -0.191167 -0.98196 -0.188933 0.00772893 -0.975639 -0.219227 -0.00826696 -0.983866 -0.178478 -0.0123583 -0.970088 -0.235033 -0.0607304 -0.978778 -0.195954 -0.0599659 -0.969215 -0.224686 -0.100694 -0.966348 -0.234545 -0.105644 -0.184076 -0.809877 0.556971 -0.189001 -0.748524 0.635602 -0.486353 -0.67167 0.558857 -0.186056 -0.935487 0.300413 -0.192697 -0.909954 0.367222 -0.184716 -0.912188 0.365776 -0.190643 -0.87677 0.441508 -0.226266 -0.858293 0.460584 -0.187773 -0.851605 0.489398 -0.191733 -0.80733 0.558083 -0.841799 -0.49913 0.205533 -0.836913 -0.527143 0.147296 -0.837793 -0.525746 0.147288 -0.828679 -0.556429 0.0606419 -0.832196 -0.551105 0.0611017 -0.819439 -0.572224 -0.0328518 -0.826092 -0.562684 -0.030974 -0.81254 -0.57125 -0.115983 -0.819995 -0.561138 -0.11284 -0.548914 -0.658805 0.514461 -0.54497 -0.702284 0.458044 -0.556103 -0.693724 0.457709 -0.55113 -0.745043 0.375722 -0.556129 -0.741226 0.375905 -0.548906 -0.787084 0.281427 -0.553137 -0.783976 0.281818 -0.54161 -0.822934 0.171578 -0.549809 -0.817241 0.172707 -0.533541 -0.844101 0.0531718 -0.545885 -0.836017 0.0555359 -0.528197 -0.847337 -0.0550258 -0.540915 -0.839476 -0.0518827 -0.219878 -0.946663 0.235548 -0.192845 -0.948964 0.249555 -0.178809 -0.973041 0.145664 -0.217705 -0.968512 0.120785 -0.18577 -0.979098 0.0827974 -0.174008 -0.984673 0.0118377 -0.19059 -0.981558 0.0148116 -0.18472 -0.980858 -0.0616057 -0.176729 -0.982234 -0.0631094 -0.535722 -0.835481 -0.122365 -0.528237 -0.839915 -0.124533 -0.815823 -0.553945 -0.166065 -0.810231 -0.561232 -0.16895 -0.960581 -0.209289 -0.182983 -0.966927 -0.202708 -0.154794 -0.961934 -0.22159 -0.159939 -0.968947 -0.212532 -0.126383 -0.86506 -0.391339 0.313886 -0.175945 -0.702081 0.690019 -0.825223 -0.412194 0.38614 -0.820175 -0.422845 0.385377 -0.698019 -0.565395 0.43943 -0.745161 -0.508383 0.431604 -0.593898 -0.58045 0.557103 -0.489058 -0.646803 0.585208 -0.388398 -0.645726 0.657408 -0.164294 -0.714041 0.680553 -0.128017 -0.686433 0.715836 -0.753916 -0.369511 0.543206 -0.878023 -0.356603 0.319233 -0.860481 -0.339971 0.379463 -0.821416 -0.442495 0.359826 -0.82122 -0.434886 0.36942 -0.786167 -0.417091 0.456044 -0.760618 -0.474002 0.443602 -0.756778 -0.476193 0.447803 -0.695668 -0.527091 0.488079 -0.689396 -0.528482 0.495419 -0.928186 -0.248906 0.276617 -0.926639 -0.2692 0.262433 -0.949391 -0.203168 0.23954 -0.879145 -0.328075 0.345647 -0.826565 -0.386322 0.409324 -0.750804 -0.429261 0.502024 -0.706903 -0.463633 0.534166 -0.597248 -0.524959 0.606394 -0.342188 -0.33762 0.876881 -0.359492 -0.368825 0.857166 -0.364986 -0.359673 0.858732 -0.38972 -0.39074 0.833931 -0.391205 -0.387391 0.834797 -0.420878 -0.413049 0.807622 -0.419206 -0.418633 0.805613 -0.447337 -0.435951 0.78092 -0.444662 -0.450769 0.774005 -0.496031 -0.472688 0.728367 -0.483694 -0.483064 0.729855 -0.479665 -0.55582 0.678959 -0.391711 -0.593174 0.703354 -0.107409 -0.192911 0.97532 -0.128819 -0.226166 0.965533 -0.111424 -0.25513 0.960465 -0.137212 -0.282123 0.949515 -0.131063 -0.310304 0.941559 -0.148914 -0.345921 0.926371 -0.0937875 -0.376148 0.921801 -0.150539 -0.410334 0.899424 -0.152029 -0.46576 0.871754 -0.165727 -0.473789 0.864904 -0.151228 -0.516228 0.842994 -0.17728 -0.534879 0.826121 -0.122882 -0.601582 0.789303 -0.18833 -0.615682 0.765158 -0.129597 -0.66645 0.7342 -0.551835 -0.455214 0.698754 -0.563064 -0.482424 0.670989 -0.590437 -0.436733 0.678711 -0.609718 -0.466207 0.641011 -0.631443 -0.417226 0.653607 -0.658389 -0.442947 0.608541 -0.671322 -0.399993 0.623965 -0.699851 -0.417509 0.579565 -0.699674 -0.418399 0.579135 -0.88156 -0.288256 0.373846 -0.93256 -0.255359 0.255194 -0.99903 0.014514 0.0415654 -0.93996 0.00316478 0.34127 -0.956817 0.00973089 0.290528 -0.995805 0.0913629 -0.00496083 -0.992739 0.00641151 0.12012 -0.992868 0.00598473 0.119065 -0.986309 0.106322 0.126058 -0.988678 0.0994244 0.112384 -0.91012 0.398926 0.11198 -0.934526 0.348568 0.0718478 -0.963828 0.240216 0.115465 -0.969704 0.224897 0.0953707 -0.982608 0.157406 0.098518 -0.76545 0.63835 0.0812146 -0.756517 0.640588 0.131636 -0.786002 0.61455 0.0672978 -0.814079 0.579326 0.040702 -0.80762 0.587862 0.0465596 -0.722726 0.667891 0.177734 -0.716214 0.682715 0.144702 -0.721901 0.683248 0.10969 -0.678162 0.656481 0.330347 -0.700569 0.653058 0.287609 -0.700023 0.653349 0.288276 -0.697502 0.68003 0.225942 -0.718555 0.67119 0.182159 -0.659553 0.654007 0.370492 -0.655498 0.652925 0.379488 -0.61984 0.691626 0.370745 -0.655161 0.645774 0.392097 -0.67577 0.653111 0.341732 -0.807373 0.44315 0.389573 -0.629707 0.723985 0.28163 -0.766936 0.581046 0.272389 -0.684816 0.710607 0.161444 -0.705343 0.686442 0.176888 -0.773321 0.629604 0.0746608 -0.759627 0.635947 0.136158 -0.829807 0.531774 0.169224 -0.838048 0.536949 0.0967573 -0.879488 0.472266 0.0588732 -0.961866 0.0151341 0.273102 -0.971577 0.0896425 0.219094 -0.968618 0.0827771 0.234365 -0.953115 0.200753 0.226431 -0.96055 0.236787 0.145862 -0.913376 0.325119 0.245036 -0.912277 0.401148 0.0826481 -0.865621 0.444423 0.230627 -0.829921 0.555364 0.0529432 -0.761035 0.319737 -0.564442 -0.990606 0.120618 -0.0644351 -0.980089 0.157045 -0.121498 -0.93326 0.348102 -0.0886057 -0.653679 0.756772 0.00062857 -0.843194 0.462283 0.274442 -0.997787 0.0476045 -0.0464114 -0.997538 0.030954 -0.0629215 -0.997482 0.0231386 -0.067035 -0.995637 0.0829123 -0.0428025 -0.995452 0.0864458 -0.040027 -0.992856 0.114179 -0.0346458 -0.951525 0.266761 0.1531 -0.9501 0.303359 0.0726897 -0.940006 0.334648 0.0663277 -0.915321 0.392447 0.0904097 -0.932279 0.356186 0.0631369 -0.913295 0.402514 0.0622504 -0.9146 0.39991 0.0598232 -0.921803 0.386875 0.024619 -0.918941 0.393819 0.0213195 -0.928773 0.370576 -0.0073522 -0.887493 0.405105 -0.219651 -0.909889 0.405086 0.0894826 -0.904868 0.41342 0.10148 -0.905935 0.414084 0.0884092 -0.91418 0.400728 0.0607631 -0.830553 0.551388 0.0784426 -0.832772 0.548597 0.0743773 -0.865945 0.494809 0.0728248 -0.857382 0.506361 0.0921629 -0.876355 0.474796 0.081058 -0.722562 0.691069 0.0180933 -0.757652 0.65241 -0.0180025 -0.768315 0.639974 -0.0111845 -0.625275 0.749371 -0.217884 -0.755961 0.653473 -0.0386811 -0.703971 0.686485 -0.182105 -0.697936 0.71616 -0.000518641 -0.693509 0.716717 -0.0732278 -0.645987 0.763275 -0.0105563 -0.669103 0.74316 -0.00390927 -0.668005 0.742452 -0.0503443 -0.681153 0.731878 -0.0196035 -0.681324 0.731848 -0.0140177 -0.71151 0.617211 -0.335864 -0.704422 0.667947 -0.240078 -0.688243 0.693055 -0.214469 -0.689588 0.549438 -0.471791 -0.696375 0.626146 -0.350719 -0.678079 0.638489 -0.364061 -0.69866 0.435291 -0.567799 -0.675799 0.470709 -0.567211 -0.68503 0.465608 -0.560306 -0.684917 0.538624 -0.490686 -0.673796 0.561007 -0.480905 -0.738034 0.452902 -0.500186 -0.71978 0.457457 -0.52216 -0.762974 0.492297 -0.418945 -0.806036 0.48697 -0.336401 -0.804628 0.584256 -0.105921 -0.711297 0.679241 -0.180801 -0.80828 0.588341 0.0232207 -0.979026 0.0142234 -0.203238 -0.406257 0.109674 -0.907153 -0.938614 0.330663 0.098315 -0.58853 0.234327 -0.773772 -0.742648 0.392131 -0.542869 -0.780107 0.408213 -0.474125 -0.563147 0.387558 -0.729838 -0.456968 0.324149 -0.828316 -0.768526 0.606794 -0.202903 -0.564809 0.482696 -0.669324 -0.734318 0.635303 -0.239097 -0.723099 0.636121 -0.269217 -0.578218 0.508891 -0.637725 -0.577984 0.449759 0.68092 -0.79413 0.607557 0.015256 -0.795077 0.606379 0.0125225 -0.989542 0.143077 -0.0182975 -0.984113 0.177148 0.011809 -0.984042 0.177549 0.0117286 -0.966966 0.251733 0.0400924 -0.964502 0.262881 -0.0250981 -0.933752 0.344335 0.0976774 -0.914896 0.400071 -0.0539219 -0.997689 0.0455052 -0.0504516 -0.995696 0.0512345 -0.0772266 -0.994071 0.0461334 -0.0984629 -0.985081 0.0193084 -0.171007 -0.983428 0.055829 -0.172491 -0.994305 0.043442 -0.097313 -0.991996 0.0553134 -0.113511 -0.989243 0.0524656 -0.13655 -0.990025 0.0481597 -0.132402 -0.987643 0.0445335 -0.15026 -0.987972 0.0418975 -0.148849 -0.986194 0.0360737 -0.161618 -0.664986 0.0259062 -0.746406 -0.684305 -0.00227915 -0.729192 -0.765154 0.0181443 -0.643591 -0.765371 0.0180191 -0.643337 -0.848574 -0.000239436 -0.529077 -0.85457 -0.00803456 -0.519274 -0.934581 0.0283693 -0.354618 -0.989608 -0.0506528 -0.134573 -0.967435 0.224331 -0.117243 -0.958294 0.245312 -0.146608 -0.912015 0.234989 -0.336169 -0.914598 0.232267 -0.331002 -0.834185 0.214106 -0.508226 -0.841325 0.208858 -0.498549 -0.757491 0.190132 -0.624545 -0.863836 0.463853 -0.196542 -0.90991 0.412615 -0.0425615 -0.866975 0.395624 -0.303043 -0.871093 0.39224 -0.295541 -0.804762 0.365237 -0.467932 -0.988667 0.0907279 -0.119608 -0.98547 0.101187 -0.136419 -0.930854 0.0970174 -0.352277 -0.932445 0.0949271 -0.348619 -0.845789 0.0877398 -0.526253 -0.849136 0.0847115 -0.521337 -0.763309 0.0774179 -0.641378 -0.767921 0.0739823 -0.636258 -0.689507 0.0674341 -0.721133 -0.809042 0.586545 -0.0376311 -0.818841 0.565618 -0.097861 -0.823566 0.55528 -0.115777 -0.805887 0.544595 -0.232296 -0.805952 0.532647 -0.258318 -0.756239 0.515187 -0.403343 -0.816921 0.358326 -0.451933 -0.741863 0.328365 -0.584651 -0.768445 0.183558 -0.613024 -0.689099 0.166428 -0.705297 -0.67931 0.122868 -0.723493 -0.725093 0.491462 -0.482395 -0.649538 0.551125 -0.523795 -0.695045 0.428785 -0.57711 -0.679034 0.360939 -0.639246 -0.693602 0.293881 -0.657686 -0.677174 0.249016 -0.692406 -0.687544 0.16982 -0.706006 -0.564366 0.141847 -0.813247 -0.689057 0.127395 -0.713422 -0.616912 0.0915875 -0.781685 -0.696659 0.0236611 -0.717012 -0.965235 0.216618 -0.14628 -0.0263872 0.75251 0.658052 -0.533223 0.661651 0.527154 -0.786303 0.487325 0.379792 -0.78645 0.487117 0.379754 -0.814915 0.486204 0.315465 -0.790135 0.521311 0.322369 -0.804476 0.518245 0.290242 -0.940558 0.319424 0.115408 -0.986201 0.164761 -0.0161831 -0.984944 0.172798 0.00519632 -0.978131 0.207991 0.000574592 -0.979819 0.198993 -0.0188907 -0.977323 0.207421 -0.0426284 -0.97201 0.229656 -0.0495495 -0.974491 0.212719 -0.0715398 -0.970902 0.212931 -0.109587 -0.958684 0.258973 -0.117723 -0.970906 0.2186 -0.0977496 -0.955754 0.243042 -0.165728 -0.96693 0.202702 -0.154787 -0.963043 0.206857 -0.172505 -0.954799 0.234335 -0.182881 -0.954336 0.229556 -0.191172 -0.22359 0.739282 0.635193 -0.188862 0.75067 0.633108 -0.184071 0.809863 0.556992 -0.229282 0.793984 0.563045 -0.18999 0.829199 0.525674 -0.186354 0.863604 0.468466 -0.192295 0.863795 0.465704 -0.18711 0.899537 0.394743 -0.228194 0.90494 0.359182 -0.190195 0.920591 0.341083 -0.181154 0.949679 0.255527 -0.192846 0.94896 0.24957 -0.176998 0.97516 0.133168 -0.192343 0.973334 0.124997 -0.174962 0.984422 0.01737 -0.189637 0.981811 0.00926302 -0.177241 0.982318 -0.0603137 -0.184202 0.980777 -0.0643952 -0.549358 0.649827 0.525292 -0.545338 0.699299 0.462155 -0.555974 0.69652 0.4536 -0.551305 0.743913 0.377699 -0.556029 0.7423 0.373928 -0.54908 0.78634 0.283162 -0.553013 0.784684 0.280087 -0.542062 0.821933 0.174913 -0.549469 0.818174 0.169338 -0.534399 0.843224 0.0582299 -0.545223 0.836774 0.0504192 -0.529206 0.847035 -0.0497267 -0.540084 0.839663 -0.0572279 -0.528867 0.839993 -0.12129 -0.535127 0.835381 -0.12561 -0.822508 0.518008 0.234839 -0.822345 0.518541 0.23423 -0.841845 0.498764 0.206233 -0.836984 0.526878 0.147844 -0.837758 0.525955 0.146741 -0.828989 0.555729 0.0627882 -0.831985 0.551662 0.058897 -0.82015 0.571424 -0.0287939 -0.825576 0.563197 -0.0351102 -0.813428 0.570897 -0.11141 -0.819293 0.561215 -0.117458 -0.810921 0.56128 -0.165444 -0.81519 0.553815 -0.169573 0.184182 -0.980798 -0.0641209 0.574868 -0.816625 0.0514852 0.761713 -0.486123 0.428343 0.211628 -0.957719 0.194905 0.00468546 -0.999028 -0.0438409 0.018846 -0.998815 -0.044862 0.967126 -0.164156 -0.194219 0.980509 -0.127382 0.149585 0.285661 -0.402828 0.869556 0.641034 -0.596172 0.483379 -0.000405964 -0.874665 0.484727 0.128126 -0.858618 0.496346 0.0762836 -0.868625 0.489562 0.298899 -0.839641 0.4535 0.281167 -0.844072 0.456605 0.715333 -0.513984 0.473413 0.760672 -0.48419 0.432364 0.760585 -0.482942 0.433909 0.711288 -0.306091 0.632754 0.722086 -0.31737 0.61471 0.748503 -0.314685 0.583709 0.745231 -0.355513 0.564129 0.767116 -0.400934 0.500785 0.775829 -0.376295 0.506449 0.763962 -0.431858 0.479438 0.62645 -0.284445 0.725707 0.598248 -0.233885 0.766418 0.531138 -0.355885 0.76892 0.0528074 -0.24866 0.96715 0.0849994 -0.251874 0.96402 0.130323 -0.228977 0.964669 0.167381 -0.273747 0.947125 0.220747 -0.253061 0.941929 0.255372 -0.258876 0.931541 0.284015 -0.239898 0.928323 0.332355 -0.269146 0.903936 0.383874 -0.242994 0.890839 0.425192 -0.298986 0.854295 0.471997 -0.270174 0.839181 0.504451 -0.278819 0.817184 0.534757 -0.25466 0.805719 0.602824 -0.316904 0.73224 0.0151317 -0.215103 0.976474 0.00137362 -0.235434 0.971889 0.0468868 -0.244367 0.968549 0.0672126 -0.240245 0.968383 0.0275938 -0.266546 0.963427 0.0167301 -0.262081 0.964901 0.00650435 -0.276964 0.960858 0.865325 -0.345782 0.362833 0.817098 -0.298427 0.493246 0.783952 -0.293598 0.54701 0.747028 -0.320506 0.58243 0.726099 -0.344526 0.595048 0.725685 0.121398 0.677233 0.694849 -0.278351 0.663103 0.668991 -0.29399 0.682657 0.646175 -0.361975 0.671887 0.861981 -0.17401 0.47614 0.943721 -0.121412 0.307652 0.93529 -0.0930236 0.341437 0.918615 -0.0876366 0.385314 0.970825 -0.142283 0.193011 0.962596 -0.139694 0.232154 0.962998 -0.139344 0.230692 0.957479 -0.120871 0.261963 0.954077 -0.125085 0.272195 0.943594 -0.0977676 0.31634 0.974638 -0.184806 0.126201 0.973311 -0.165148 0.159345 0.974509 -0.167505 0.149245 0.974695 -0.165117 0.150688 0.969313 -0.145441 0.198188 0.972083 -0.208619 0.107393 0.969444 -0.223607 0.100891 0.972217 -0.216614 0.0887225 0.980411 -0.193265 -0.0379813 0.981267 -0.192322 -0.01132 0.980656 -0.194984 0.0171768 0.979102 -0.200479 0.0341787 0.976939 -0.208552 0.0457743 0.972158 -0.226441 0.060277 0.971972 -0.227439 0.0595109 0.972931 -0.218055 0.0765366 0.98284 -0.149793 -0.107647 0.982818 -0.112085 -0.146646 0.981893 -0.122196 -0.144758 0.978779 -0.137482 -0.151954 0.97354 -0.164973 -0.158128 0.964539 -0.201981 -0.16991 0.968585 -0.190047 -0.160388 0.971459 -0.205903 -0.117776 0.983433 -0.144454 -0.109507 0.983802 -0.165241 -0.0694966 0.963553 -0.160057 -0.214352 0.971206 -0.0792234 -0.224684 0.966376 -0.103316 -0.235464 0.969824 -0.0936564 -0.225098 0.968845 -0.136752 -0.206489 0.966099 -0.128685 -0.223813 0.967145 -0.156645 -0.20023 0.956265 -0.19675 -0.216443 0.951109 -0.247523 -0.184728 0.873237 -0.400277 -0.277914 0.837509 -0.518673 -0.171923 0.239145 -0.968177 -0.0737765 0.23151 -0.969696 -0.0780604 0.196372 -0.977534 -0.076583 0.113976 -0.991151 -0.0680318 0.159549 -0.986137 -0.0455781 0.129746 -0.990152 -0.0525808 0.132699 -0.990033 -0.0471668 0.00685436 -0.999022 -0.0436904 0.0974287 -0.994362 -0.0418635 0.000208063 -0.999048 -0.0436183 0.0100881 -0.999035 -0.0427431 0.0342665 -0.998716 -0.0373167 0.0342354 -0.998719 -0.0372508 0.0349263 -0.998684 -0.0375496 0.0126178 -0.999058 -0.0415249 0.0269697 -0.998966 -0.0366047 0.0269042 -0.998896 -0.0385005 0.24811 -0.968087 0.0353284 0.157728 -0.987286 0.0197132 0.140276 -0.990112 -0.000103501 0.0213114 -0.999002 -0.0392623 0.0257975 -0.998698 -0.0440068 0.0543934 -0.998163 -0.0266794 0.0864238 -0.995842 -0.0288084 0.261323 -0.960433 0.0963262 0.227978 -0.958959 0.168594 0.1857 -0.966722 0.175966 0.149459 -0.968263 0.200324 0.103102 -0.956387 0.273303 0.141837 -0.954195 0.263429 0.0155768 -0.967041 0.254142 0.0461763 -0.968791 0.243542 0.0396052 -0.894685 0.444938 -0.0131698 -0.874141 0.485495 0.00115321 -0.874646 0.484762 0.00669342 -0.91526 0.402809 0.0311248 -0.934951 0.35341 0.0468167 -0.940638 0.336169 0.0107926 -0.956864 0.290334 0.044462 -0.973116 0.225982 0.80951 -0.571006 -0.136551 0.872105 -0.472212 -0.128254 0.890933 -0.439864 -0.112949 0.745908 -0.661511 -0.0776234 0.706946 -0.701129 -0.092979 0.706176 -0.696434 -0.127652 0.968503 -0.189014 -0.162098 0.95365 -0.24592 -0.173421 0.951948 -0.234864 -0.196554 0.939989 -0.313015 -0.1358 0.922119 -0.310134 -0.23133 0.925431 -0.3329 -0.180982 0.948028 -0.269436 -0.169254 0.950375 -0.286209 -0.121946 0.968405 -0.222057 -0.113502 0.969708 -0.231605 -0.0776207 0.98438 -0.160961 -0.0713271 0.982351 -0.184089 -0.0331261 0.808076 -0.556261 -0.193874 0.891782 -0.418527 -0.171932 0.870506 -0.453297 -0.19168 0.916567 -0.358795 -0.176553 0.918219 -0.37486 -0.127885 0.946557 -0.299896 -0.118708 0.947477 -0.309581 -0.0802969 0.967413 -0.242046 -0.0743308 0.967894 -0.247315 -0.0448952 0.985043 -0.167581 -0.0400766 0.979267 -0.20257 -0.00112055 0.9425 -0.333744 -0.0175773 0.885611 -0.463849 -0.0231674 0.887412 -0.460515 -0.0206189 0.74092 -0.670921 -0.0300479 0.742887 -0.668812 -0.0284546 0.76365 -0.623939 -0.16595 0.727415 -0.660501 -0.186025 0.72914 -0.670851 -0.135325 0.794823 -0.592494 -0.131174 0.79521 -0.598826 -0.0951273 0.891024 -0.445827 -0.0855274 0.88843 -0.450227 -0.0893732 0.945369 -0.316443 -0.0783727 0.945652 -0.321838 -0.0465162 0.966193 -0.254302 -0.0424328 0.966285 -0.256778 -0.0189539 0.985478 -0.169128 -0.0151613 0.976084 -0.215409 0.0293233 0.764797 -0.607546 0.214412 0.73074 -0.679701 0.0634566 0.731093 -0.679291 0.0637646 0.729451 -0.678238 0.0888526 0.775261 -0.621951 0.110213 0.772145 -0.616439 0.154254 0.865808 -0.47579 0.154919 0.86453 -0.479285 0.151244 0.866548 -0.48679 0.110138 0.867532 -0.48474 0.11142 0.86941 -0.489919 0.0640728 0.874077 -0.480676 0.0702895 0.757935 -0.594115 0.269372 0.847016 -0.203477 0.491081 0.827156 -0.294642 0.478538 0.831383 -0.306339 0.463636 0.83191 -0.299431 0.467191 0.849977 -0.346526 0.396812 0.849369 -0.351401 0.393815 0.860192 -0.382084 0.337761 0.866227 -0.440659 0.235523 0.861926 -0.426642 0.273972 0.768372 -0.568333 0.294282 0.761241 -0.55501 0.335375 0.867954 -0.0788357 0.490348 0.47345 -0.0545054 0.879133 0.870559 -0.130871 0.474342 0.867348 -0.168477 0.46832 0.881166 -0.210209 0.423507 0.882855 -0.196473 0.426574 0.898598 -0.24398 0.364684 0.899208 -0.240014 0.365812 0.909662 -0.273783 0.312342 0.909298 -0.27575 0.311671 0.916411 -0.300322 0.26457 0.885234 -0.131668 0.446122 0.883819 -0.0923092 0.458631 0.909992 -0.119714 0.396967 0.909673 -0.128172 0.395052 0.924321 -0.173666 0.339811 0.924736 -0.168348 0.341354 0.934717 -0.201024 0.293076 0.934682 -0.20135 0.292963 0.941666 -0.225523 0.249808 0.941385 -0.227641 0.248944 0.94638 -0.245978 0.209425 0.133446 -0.990369 -0.0368864 0.0543485 -0.997689 -0.0407852 0.0506658 -0.998407 -0.0248442 0.0767208 -0.996454 -0.0345358 0.10321 -0.994635 -0.00702266 0.126978 -0.990975 -0.0429478 0.126336 -0.991689 -0.0243541 0.0124803 -0.999068 -0.0413171 0.0322128 -0.998657 -0.0405797 0.0702148 -0.99725 -0.0237066 0.179225 -0.983668 -0.0166098 0.171672 -0.985153 -0.00169286 0.210551 -0.976919 0.0360135 0.211195 -0.976823 0.0348411 0.247797 -0.965095 0.084783 0.330891 -0.943599 -0.0115067 0.463666 -0.886006 -0.00281811 0.458763 -0.887754 0.0377965 0.586147 -0.808721 0.049 0.581299 -0.808695 0.0900223 0.697556 -0.709713 0.0986057 0.690814 -0.703927 0.165115 0.758054 -0.630779 0.165746 0.785627 -0.588212 0.191826 0.863752 -0.46869 0.185102 0.0770419 -0.9687 0.235978 0.167602 -0.95272 0.253445 0.0810856 -0.93703 0.339707 0.116424 -0.90891 0.40041 0.0581701 -0.89222 0.447839 0.0759074 -0.868806 0.4893 0.0221671 -0.854822 0.518448 0.314931 -0.935021 0.162954 0.298482 -0.940656 0.161477 0.21193 -0.936582 0.279104 0.252184 -0.911191 0.325781 0.179161 -0.89648 0.405246 0.214429 -0.866568 0.450644 0.177246 -0.856851 0.484138 0.196932 -0.795968 0.572409 0.354114 -0.861156 0.36471 0.317413 -0.889925 0.327539 0.369146 -0.896291 0.245754 0.324954 -0.924008 0.201529 0.352782 -0.923961 0.147788 0.303376 -0.947608 0.100008 0.311471 -0.946699 0.082142 0.267449 -0.962674 0.0415981 0.279062 -0.960177 0.0135953 0.105732 -0.994393 -0.00194617 0.11817 -0.992485 -0.0317571 0.0203714 -0.999094 -0.0373714 0.00681573 -0.999065 -0.0426854 0.358411 -0.819878 0.446477 0.376415 -0.779842 0.500159 0.447428 -0.80279 0.394126 0.415226 -0.833417 0.364697 0.457662 -0.842527 0.284068 0.418588 -0.873746 0.247694 0.442246 -0.875997 0.192477 0.397518 -0.905009 0.151454 0.407033 -0.904726 0.125676 0.36386 -0.927332 0.0875291 0.377158 -0.924939 0.0473213 0.195618 -0.980267 0.028453 0.579099 -0.646888 0.496166 0.579114 -0.647848 0.494894 0.608874 -0.668585 0.426926 0.587937 -0.69726 0.410072 0.61465 -0.714373 0.334479 0.588717 -0.745525 0.312418 0.604487 -0.754182 0.256524 0.574169 -0.785639 0.230435 0.58269 -0.789184 0.194063 0.551158 -0.817439 0.167388 0.562087 -0.819541 0.111404 0.394775 -0.913845 0.0950808 0.407653 -0.912216 0.0410017 0.256783 -0.966139 0.0252649 0.263541 -0.964645 -0.00226998 0.121552 -0.992123 -0.030272 0.239257 -0.97068 -0.0231631 0.234357 -0.972143 0.00376392 0.368615 -0.929438 0.0163805 0.362002 -0.930881 0.0491503 0.509714 -0.85794 0.0642731 0.498609 -0.857776 0.124938 0.645884 -0.751168 0.136306 0.637101 -0.745399 0.19617 0.660847 -0.718629 0.216457 0.653512 -0.712281 0.256083 0.67612 -0.68332 0.275563 0.663485 -0.671016 0.330944 0.682693 -0.642966 0.347167 0.661691 -0.621443 0.419493 0.083983 -0.995069 -0.0527656 0.136319 -0.989173 -0.0543453 0.137379 -0.989393 -0.0472004 0.125463 -0.990774 -0.0512491 0.0705702 -0.99429 -0.0800488 0.0724233 -0.990214 -0.119293 0.0423023 -0.997671 -0.0535011 0.0432338 -0.9977 -0.0522013 0.035916 -0.998212 -0.0477752 0.123245 -0.991159 -0.0491331 0.0814199 -0.994903 -0.0594895 0.242267 -0.967993 -0.0655443 0.179266 -0.98057 -0.0796687 0.363103 -0.92751 -0.0887727 0.286295 -0.952314 -0.105514 0.291547 -0.952848 -0.0841506 0.242764 -0.967812 -0.0663745 0.234347 -0.969731 -0.0685843 0.236376 -0.970274 -0.0519062 0.223433 -0.973118 -0.0558581 0.316995 -0.940623 -0.12142 0.364268 -0.928755 -0.0687316 0.380037 -0.924705 -0.0221988 0.415161 -0.361109 -0.83501 0.457709 -0.88174 -0.114179 0.402379 -0.906638 -0.126883 0.408742 -0.908246 -0.0895557 0.365793 -0.925363 -0.0994915 0.369507 -0.926372 -0.0727998 0.345204 -0.935201 -0.0789492 0.347266 -0.936058 -0.0565863 0.334772 -0.940376 -0.0601663 0.219388 -0.975407 -0.021205 0.3481 -0.937368 -0.0129629 0.342876 -0.939138 0.0213283 0.478115 -0.877638 0.0340156 0.472187 -0.878595 0.0714877 0.607821 -0.789622 0.0839688 0.598956 -0.78683 0.148832 0.721535 -0.674935 0.154435 0.698899 -0.645824 0.30733 0.780718 -0.577756 0.23807 0.863201 -0.451529 0.225843 0.866112 -0.461429 0.192181 0.670295 -0.72542 -0.156431 0.629315 -0.757366 -0.174241 0.632603 -0.765324 -0.118715 0.599752 -0.789747 -0.128829 0.601802 -0.793611 -0.0895353 0.584995 -0.805502 -0.0945903 0.586092 -0.807689 -0.0642989 0.745948 -0.663325 -0.0596731 0.743002 -0.666408 -0.0620302 0.888546 -0.455883 -0.0515441 0.887596 -0.457575 -0.0529102 0.944297 -0.325973 -0.0452219 0.944277 -0.328585 -0.0193139 0.964594 -0.263223 -0.0165149 0.964262 -0.264456 0.0162013 0.981731 -0.189382 0.0184017 0.979908 -0.193648 -0.0477639 0.0374259 -0.998567 -0.0382526 0.141063 -0.989463 -0.0326226 0.138031 -0.990264 -0.0180448 0.165566 -0.986138 -0.0109115 0.203636 -0.979027 0.0062151 0.306017 -0.951887 0.0162437 0.292415 -0.954288 0.0618635 0.471959 -0.877892 0.0809956 0.459213 -0.878678 0.130569 0.497638 -0.851833 0.163516 0.488198 -0.850579 0.195392 0.526193 -0.818993 0.228847 0.506658 -0.813772 0.284734 0.539423 -0.781468 0.313578 0.505499 -0.76864 0.391999 0.532349 -0.737989 0.414702 0.484345 -0.715808 0.50302 0.480613 -0.73932 0.471611 0.0153085 -0.998865 -0.0451095 0.0499374 -0.997712 -0.0455802 0.0504096 -0.99781 -0.0428382 0.0308101 -0.998417 -0.047062 0.0376297 -0.99832 -0.0440592 0.125998 -0.99114 -0.0420176 0.122013 -0.991572 -0.0435645 0.224108 -0.973688 -0.0413252 0.220118 -0.974537 -0.0427175 0.335451 -0.941206 -0.0400522 0.331868 -0.942425 -0.0412149 0.453397 -0.890498 -0.0379969 0.452248 -0.89189 -0.00190281 0.530828 -0.847474 0.00311272 0.577743 -0.815951 0.0208986 0.735906 -0.676326 0.0320317 0.732663 -0.679962 0.0292741 0.880663 -0.472255 0.0375092 0.875262 -0.482708 0.0301411 0.935547 -0.351635 0.0332225 0.934774 -0.349155 0.0654812 0.931288 -0.358995 0.0618477 0.929682 -0.352238 0.107792 0.927563 -0.358383 0.105779 0.925527 -0.348611 0.147884 0.925263 -0.349534 0.147357 0.922928 -0.339862 0.180824 0.923203 -0.33883 0.181359 0.919789 -0.325452 0.219248 0.561809 -0.81566 -0.13809 0.518935 -0.841398 -0.150852 0.52373 -0.845309 -0.105641 0.483427 -0.867679 -0.115896 0.4865 -0.869785 -0.0824175 0.46468 -0.881079 -0.0881612 0.466416 -0.882509 -0.0602879 0.517656 -0.854398 -0.0451392 0.517518 -0.853912 -0.0548506 0.576537 -0.816293 -0.0356451 0.57581 -0.817548 -0.00759538 0.740247 -0.672332 0.00197308 0.737194 -0.675681 -0.000558713 0.885179 -0.465175 0.0083388 0.881402 -0.472356 0.00307514 0.942276 -0.334751 0.007572 0.950616 -0.309851 0.0179577 0.960283 -0.278394 0.0187804 0.959552 -0.274524 0.062422 0.95767 -0.281635 0.0595771 0.956038 -0.274249 0.103819 0.954629 -0.279836 0.101857 0.952463 -0.269395 0.142267 0.956516 -0.246631 0.155722 0.949699 -0.260881 0.173242 0.94619 -0.2472 0.208845 0.920513 -0.322457 0.220627 0.915569 -0.30424 0.263003 0.86486 -0.413758 0.284292 0.858204 -0.393387 0.329747 0.769329 -0.52994 0.356786 0.756589 -0.506962 0.412992 0.67677 -0.596534 0.431427 0.645267 -0.563579 0.515762 0.700237 -0.569051 0.431102 -1.53231e-06 -1.7022e-06 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 4.08776e-06 8.06817e-06 1 2.17472e-06 -2.6813e-06 1 -9.47066e-07 -9.47074e-07 1 -1.53231e-06 -1.37351e-07 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 3.43288e-05 1.15359e-05 1 -6.6382e-07 -8.09844e-07 1 0 0 1 0 0 1 0 0 1 0 0 1 5.64405e-06 1.00245e-06 1 -5.69936e-05 3.31137e-05 1 -9.31311e-05 3.31137e-05 1 -0.00016761 4.96649e-05 1 -0.000111757 -9.93335e-05 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1.21784e-06 5.72438e-07 1 -9.47066e-07 9.47074e-07 1 2.17472e-06 2.6813e-06 1 2.78469e-06 -7.46152e-07 1 -1.19164e-06 -5.28011e-06 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -7.43999e-05 -4.96914e-05 1 -0.000186247 -2.48322e-05 1 2.84797e-06 -2.48354e-05 1 -3.38635e-05 -6.01458e-06 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -4.20271e-06 7.11774e-06 1 -0.000111748 9.93334e-05 1 0.000111769 -1.85055e-09 1 -4.55969e-05 7.54941e-10 1 -3.38635e-05 -6.01458e-06 1 0 0 1 0 0 1 2.2954e-06 -8.09844e-07 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.000393592 -0.999156 -0.0410757 -8.00227e-05 -0.999086 -0.0427376 -2.21156e-05 -0.999093 -0.0425857 -3.07037e-08 -0.999074 -0.043024 -0.00229211 -0.999282 -0.0378144 -0.0136049 -0.999372 -0.0327144 -0.0237569 -0.999193 -0.0323979 -0.00120887 -0.999958 -0.0090878 0.00193794 -0.999973 0.00702677 -0.0603354 -0.998172 0.00338787 0.0571741 -0.997711 0.0361099 -0.984596 -0.152969 -0.084682 -0.523895 -0.851139 0.033115 -0.107105 -0.989508 0.0969656 -0.0172265 -0.991709 0.127345 0.00123595 -0.987952 0.154753 -0.00561965 -0.970137 0.242491 -0.0262001 -0.972827 0.230047 0.0897999 -0.934613 0.344144 -0.0194803 -0.963306 0.267697 -0.0796662 -0.974278 0.210799 -0.0234054 -0.895279 0.444891 -0.542078 -0.785102 0.299609 -0.000133976 -0.874658 0.48474 -0.0126423 -0.957547 0.288 0.000170477 -0.936384 0.350977 0.00017037 -0.913852 0.406047 0.0418784 -0.885952 0.461883 -0.00256512 -0.870248 0.492608 0.000742492 -0.840869 0.541239 -0.00171639 -0.835348 0.549719 0.00410388 -0.824975 0.565154 -0.0159831 -0.805576 0.592277 -0.197609 -0.774824 0.600499 -0.274935 -0.760298 0.588522 0.0228029 -0.74139 0.670687 -0.0509424 -0.731698 0.679723 0.00201121 -0.728834 0.684688 0.00198488 -0.692062 0.721835 -0.471638 -0.60133 0.64495 0.437371 -0.551341 0.710443 0.0045121 -0.598253 0.801294 0.0045114 -0.523163 0.852221 0.13232 -0.51389 0.84759 -0.186449 -0.41054 0.892577 0.000326258 -0.348526 0.937299 0.00312549 -0.343313 0.939216 -0.00858159 -0.382995 0.92371 -0.186692 -0.410528 0.892532 -0.000209573 -0.235436 0.97189 -0.0313329 -0.245669 0.968847 -0.0288602 -0.246537 0.968703 -0.00727923 -0.244969 0.969504 -0.00650643 -0.245334 0.969417 -0.0366088 -0.245176 0.968787 0.000831224 -0.27697 0.960878 -0.000293615 -0.327035 0.945012 -0.0208019 -0.245498 0.969174 0.0366629 -0.27307 0.961295 -0.0159978 -0.158375 0.987249 -1.53227e-06 -0.0075257 0.999972 -0.0353079 -0.188291 0.981478 0.0028193 -0.108759 0.994064 -0.00544091 -0.0586589 0.998263 -0.0157856 -0.0711503 0.997341 0.00831226 -0.0171918 0.999818 0.869149 -0.0600525 0.49089 0.984726 -0.0124696 0.173663 0.982914 -0.0732301 0.168873 0.984615 -0.0447165 0.168922 0.981838 -0.116384 0.149828 0.981518 -0.119164 0.149744 0.982395 -0.10702 0.153126 0.981527 -0.0778333 0.174774 0.976678 -0.0791982 0.199567 0.972266 -0.0689483 0.223483 0.969707 -0.0711051 0.233692 0.961976 -0.0735712 0.263039 0.949008 -0.0618549 0.309123 0.9509 -0.0655541 0.302477 0.937159 -0.0690228 0.342006 0.83573 -0.0565915 0.546216 0.855877 -0.0621659 0.51343 0.866842 -0.0617034 0.494751 0.870036 -0.0621963 0.489049 0.874377 -0.0644183 0.480952 0.904031 -0.0744273 0.420938 0.920062 -0.068041 0.38582 0.909857 -0.0580652 0.410838 0.891119 -0.0678138 0.448674 0.883211 -0.0679876 0.464022 0.867251 -0.0767047 0.491927 0.853858 -0.0764518 0.514861 0.823977 -0.0577139 0.563676 0.801182 -0.0661455 0.594754 0.789337 -0.053715 0.611605 0.761306 -0.0690249 0.644709 0.535571 -0.0418291 0.843454 0.578227 -0.071298 0.812755 0.763368 -0.0715597 0.641988 0.739446 -0.0532352 0.671108 0.692488 -0.0841515 0.716504 0.693451 -0.0864645 0.715297 0.632555 -0.0408799 0.773436 0.630912 -0.0389739 0.774875 0.576613 -0.0728552 0.813762 0.198148 -0.0226152 0.979911 0.254594 -0.0196873 0.966848 0.269399 -0.0150276 0.962911 0.303718 -0.039008 0.951963 0.376309 -0.00871748 0.926453 0.373404 -0.004302 0.927659 0.473425 -0.0778476 0.877388 0.454926 -0.0469224 0.889292 0.519701 -0.0482239 0.852986 0.206999 -0.0344193 0.977735 0.12485 0.01081 0.992117 0.0943985 -0.0285603 0.995125 0.023602 0.0215545 0.999489 0.0136837 -4.58134e-05 0.999906 0.852752 0.0157167 0.52208 0.866159 -0.00320547 0.499758 0.876243 -0.00861302 0.481792 0.880426 -0.0321734 0.47309 0.872252 -0.0450726 0.486975 0.87026 -0.049367 0.490113 0.83123 0.0857851 0.549269 0.849727 -0.101186 0.517422 0.782593 0.0647677 0.619156 0.790027 0.0250814 0.612559 0.720926 -0.0218049 0.692669 0.692305 0.0809496 0.71705 0.625225 -0.0656505 0.777678 0.555366 0.0971907 0.825907 0.49742 -0.0651327 0.865061 0.386527 0.0822423 0.918604 0.354125 -0.0269846 0.934809 0.23679 0.0213142 0.971327 0.215856 0.0792472 0.973204 0.170799 0.00609704 0.985287 0.0837347 -0.0158722 0.996362 0.106395 0.0968759 0.989593 0.0122591 -0.0717435 0.997348 0.0230279 0.000100848 0.999735 0.890391 -0.0128998 0.455013 0.923534 -0.0226861 0.382846 0.911237 -0.0234341 0.411214 0.911372 -0.0236167 0.410905 0.952335 -0.0211485 0.304321 0.952888 -0.0221903 0.302508 0.973629 -0.0206985 0.227196 0.974439 -0.0228028 0.223492 0.982465 -0.0221938 0.185123 0.984153 -0.0326339 0.174292 0.647287 0.00118557 0.762246 0.869173 0.0598698 0.490871 0.893307 0.0710698 0.443793 0.869712 0.062424 0.489596 0.844094 0.0627462 0.532511 0.909315 0.066929 0.41069 0.867273 0.0766926 0.49189 0.88321 0.0679988 0.464023 0.891679 0.0678181 0.44756 0.921169 0.0512805 0.38577 0.966563 0.0721664 0.246066 0.960178 0.0722978 0.269873 0.951067 0.0632039 0.30245 0.948127 0.0663058 0.3109 0.936908 0.0690832 0.342682 0.982465 0.107018 0.152675 0.981952 0.115686 0.149623 0.894476 0.430841 0.119536 0.981594 0.0731815 0.176401 0.969009 0.0713617 0.236495 0.972255 0.0692524 0.22344 0.976196 0.0795815 0.201763 0.980359 0.0782355 0.18104 0.982179 0.0929331 0.163363 0.983432 0.0190871 0.180268 0.984617 0.0447254 0.168903 0.984023 0.0563142 0.168899 0.0107712 -0.000100048 0.999942 0.0122904 -0.00709841 0.999899 0.0348493 6.67995e-05 0.999393 0.07866 -8.88761e-05 0.996902 0.0837259 -0.0214964 0.996257 0.13556 0.00048289 0.990769 0.280829 0.00117351 0.959757 0.216161 -0.0589115 0.974579 0.225966 -0.0956856 0.969424 0.166878 0.000277425 0.985977 0.352048 0.000384386 0.935982 0.386021 -0.0967617 0.917401 0.441249 0.00205219 0.897382 0.558004 0.00374346 0.82983 0.581294 -0.150283 0.799695 0.508511 0.000806885 0.861055 0.689187 -0.0533675 0.722615 0.692797 -0.0716911 0.71756 0.73755 0.01142 0.675196 0.769712 -0.0102681 0.638309 0.788778 -0.0615511 0.611589 0.800989 -0.0142435 0.59851 0.86702 0.0608505 0.494543 0.870839 0.0791638 0.485153 0.869873 0.0509281 0.49064 0.871632 0.0463781 0.487962 0.87223 0.0450792 0.487014 0.877121 0.037405 0.47881 0.880487 0.0102563 0.473959 0.869151 0.00525257 0.494518 0.854065 -0.0103422 0.520063 0.866862 -0.0323574 0.497497 0.829417 0.0103605 0.558534 0.851578 0.0583689 0.520968 0.825101 0.0633763 0.561419 0.816807 0.0571048 0.574078 0.791064 0.0665539 0.608103 0.780337 0.0534964 0.623067 0.75567 0.0655313 0.651666 0.7443 0.0568492 0.665421 0.694839 0.0736195 0.715387 0.458298 0.0574374 0.886941 0.556654 0.0469064 0.829419 0.591509 0.0840907 0.801901 0.608801 0.0655844 0.790608 0.682859 0.0428759 0.729291 0.49271 -0.0128968 0.870098 0.429888 0.0325627 0.902295 0.364292 0.0457022 0.930163 0.37846 0.0328772 0.925034 0.299439 0.0309538 0.953613 0.314088 0.0159881 0.949259 0.197583 0.0388871 0.979515 0.214573 0.00469825 0.976697 0.105134 0.012342 0.994381 0.107537 0.00945327 0.994156 0.0563835 0.000492294 0.998409 0.0557184 0.000865634 0.998446 0.0140517 0.00231143 0.999899 0.0130109 5.00972e-05 0.999915 0.920074 0.0235078 0.391039 0.92346 0.0226697 0.383024 0.911402 0.0234095 0.410852 0.911233 0.0236407 0.411212 0.952929 0.021091 0.302458 0.952312 0.0222386 0.304314 0.9745 0.0206094 0.223439 0.973583 0.0228734 0.227185 0.984564 0.0219995 0.173634 -0.0331086 0.858723 0.51137 -0.0157723 0.874182 0.485343 -0.00118458 0.872383 0.488822 -0.000181162 0.872268 0.489029 -0.0858991 0.846593 0.525263 0.118855 0.854489 0.50569 -0.0442267 0.799837 0.598585 -0.29682 0.756458 0.582811 0.0926178 0.745575 0.659954 -0.00676982 0.394435 0.918899 -0.203529 0.416718 0.885958 -0.353468 0.65436 0.668487 -0.582822 0.565435 0.58361 0.353384 0.580303 0.733736 0.000585271 0.606116 0.795376 0.000580116 0.526932 0.849907 0.174888 0.523504 0.833881 -0.167083 0.418404 0.89276 -0.000172403 0.245543 0.969386 0.000825301 0.245338 0.969437 -0.00728934 0.245332 0.969412 -0.00819245 0.245818 0.969281 -0.0310414 0.245203 0.968975 0.0035491 0.350588 0.936523 0.00593533 0.355134 0.934797 -0.0172119 0.282897 0.958996 -0.0368389 0.247166 0.968273 0.0253237 0.249981 0.96792 -0.0113485 0.167179 0.985861 -0.00260711 0.173412 0.984846 0.00144817 0.114126 0.993465 0.00129479 0.113966 0.993484 -0.00137859 0.0712617 0.997457 -0.011799 0.061905 0.998012 0.00830908 0.0171918 0.999818 -1.53227e-06 0.00744577 0.999972 -0.00146596 0.870579 0.492027 0.000343833 0.899454 0.437016 -0.0107177 0.924197 0.381766 -0.00122857 0.928063 0.372421 0.000726355 0.958947 0.283584 -1.71924e-06 0.958535 0.284975 -4.37073e-06 0.973759 0.227582 -0.00524996 0.977401 0.21133 -0.0146842 0.980588 0.195527 0.00233031 0.977945 0.208849 -0.00103623 0.989645 0.143534 -0.0343453 0.992604 0.116436 -0.0858382 0.990743 0.105168 0.0415443 0.997517 0.0568721 -0.653819 0.755809 -0.0356887 0.0821878 0.995883 0.0382521 -0.179861 0.982872 -0.0401488 -0.083792 0.995931 -0.0331603 -0.0316344 0.999011 -0.0312362 -0.00706741 0.999371 -0.0347606 -0.00263604 0.999268 -0.0381738 -0.00102736 0.999212 -0.039676 -0.000325802 0.999141 -0.0414327 -3.03863e-08 0.999094 -0.0425651 -0.000310094 0.999066 -0.0432139 -2.57853e-05 0.999083 -0.0428247 0.474024 0.87842 0.0606552 0.123269 0.991156 -0.0491351 0.224144 0.973679 -0.0413247 0.899046 0.437491 0.0178421 0.856524 0.515668 0.021305 0.775851 0.630698 0.016627 0.528436 0.360175 0.768784 0.0276343 0.266592 0.963413 0.342476 0.277429 0.897632 0.74093 -0.0159685 0.671392 0.864913 0.145926 0.480242 0.868161 0.0761299 0.490409 0.0268893 0.998874 -0.0390779 0.0100622 0.999254 -0.037285 0.0127245 0.999065 -0.0413282 0.0346447 0.998695 -0.0375275 0.00408565 0.999029 -0.0438647 0.00112434 0.999047 -0.043629 0.00280981 0.999046 -0.0435742 1.19489e-05 0.999048 -0.0436189 0.0769334 0.996246 -0.0396996 0.00944567 0.999041 -0.0427614 0.00679087 0.999066 -0.0426692 0.0359273 0.998212 -0.0477768 0.0187797 0.998817 -0.0448497 0.0144716 0.998878 -0.0450983 0.00506907 0.999023 -0.0438923 0.00508572 0.999027 -0.0438053 0.0432445 0.9977 -0.052204 0.0328784 0.997234 -0.0666538 0.0400832 0.997315 -0.0612944 0.316741 0.939405 -0.131121 0.372241 0.92657 -0.0538984 0.404707 0.330945 -0.85246 0.525956 0.838515 -0.142344 0.630443 0.759654 -0.159584 0.636254 0.754097 -0.162844 0.728105 0.66328 -0.172983 0.733192 0.656871 -0.175928 0.808717 0.559808 -0.180533 0.81241 0.553674 -0.182855 0.891756 0.341463 -0.296942 0.949225 0.227879 -0.216894 0.950354 0.226701 -0.213153 0.962756 0.174682 -0.206366 0.966173 0.161236 -0.201277 0.970916 0.0838867 -0.224244 0.965862 0.161272 -0.202736 0.966136 0.139792 -0.216885 0.96646 0.141316 -0.214442 0.970486 0.103183 -0.217968 0.968002 0.0941902 -0.232593 0.971296 0.0827007 -0.223035 0.971284 0.0754004 -0.225658 0.977326 0.138097 -0.160506 0.970844 0.182668 -0.155225 0.968422 0.189229 -0.162331 0.978184 0.140477 -0.153044 0.983036 0.115909 -0.142146 0.978132 0.161874 -0.13059 0.980868 0.173691 -0.0879209 0.982907 0.182063 -0.027317 0.982935 0.181351 -0.0308271 0.982819 0.179589 -0.0426073 0.979142 0.202376 0.0180286 0.981879 0.189487 0.00284999 0.973656 0.219894 0.0603453 0.965802 0.249664 0.0699642 0.974768 0.216649 0.0537659 0.977953 0.204754 0.0410214 0.979613 0.198673 0.029773 0.980824 0.194429 0.0134536 0.981232 0.192366 -0.013379 0.980185 0.193395 -0.042839 0.979521 0.193971 -0.0539733 0.981657 0.188721 0.027077 0.973294 0.165093 0.15951 0.974656 0.184566 0.126418 0.971004 0.216799 0.100749 0.965275 0.233265 0.117609 0.972219 0.216588 0.0887627 0.982537 -0.127665 0.135358 0.962789 0.140375 0.230939 0.962229 0.136751 0.235402 0.918606 0.0895019 0.384906 0.935115 0.0923793 0.342092 0.940778 0.110651 0.320457 0.945037 0.10393 0.310007 0.954376 0.123681 0.271791 0.955369 0.122278 0.268919 0.960603 0.131019 0.245103 0.829715 0.332567 0.448299 0.841339 0.225799 0.491083 0.286614 0.403861 0.868763 0.334275 0.265498 0.904307 0.428497 0.265178 0.863754 0.419619 0.277999 0.864081 0.501873 0.274515 0.820223 0.000970728 0.245543 0.969385 0.00489286 0.245228 0.969453 0.28158 0.233563 0.930678 0.254919 0.25599 0.932462 0.167358 0.25485 0.952388 0.16593 0.25691 0.952084 0.102171 0.252561 0.962172 0.0828454 0.251458 0.964316 0.097517 0.260331 0.960582 0.0530085 0.237484 0.969944 0.0573073 0.242394 0.968484 0.0664676 0.24055 0.968358 0.0210904 0.217834 0.975758 -0.0178752 0.24745 0.968736 0.00810237 0.245909 0.969259 0.742781 0.322503 0.586744 0.725945 0.344729 0.595118 0.755996 0.309777 0.576635 0.490362 0.288571 0.822358 0.552019 0.244995 0.797027 0.57096 0.286621 0.76932 0.621314 0.277769 0.732676 0.618941 0.273667 0.736219 0.661631 0.300454 0.687002 0.660325 0.298404 0.689149 0.70046 0.295267 0.649749 0.709107 0.310042 0.633278 0.75443 0.317919 0.57425 0.757772 0.478786 0.443335 0.760631 0.509633 0.402138 0.761887 0.45307 0.462877 0.76971 0.397314 0.499688 0.777742 0.398439 0.486173 0.75252 0.37686 0.540084 0.000134027 0.872259 0.489043 0.47075 0.779201 0.413812 -0.0200906 0.878444 0.477422 0.0365726 0.895054 0.444456 0.00436253 0.943536 0.331242 0.0982352 0.95088 0.293558 -0.000872433 0.928052 0.372448 0.111608 0.967257 0.227944 0.0206558 0.968224 0.24923 0.0384894 0.97199 0.231848 0.276353 0.947572 0.160428 0.163014 0.970161 0.179481 0.106892 0.957974 0.266195 0.146996 0.989072 0.0113861 0.119792 0.992175 -0.0351996 0.714673 0.665247 0.216079 0.720545 0.673346 0.165592 0.692288 0.705123 0.153424 0.766234 0.494648 0.410133 0.75179 0.498902 0.43117 0.773821 0.538901 0.332848 0.756334 0.546503 0.359573 0.772192 0.576215 0.267761 0.75364 0.58665 0.296426 0.759699 0.597184 0.257351 0.780766 0.57769 0.238073 0.78766 0.593473 0.165473 0.720942 0.665223 0.194217 0.7722 0.61637 0.15426 0.794292 0.292386 0.532551 0.831574 0.306745 0.463025 0.830115 0.302613 0.468331 0.833373 0.302658 0.46248 0.850767 0.348829 0.393084 0.848542 0.349209 0.397529 0.86167 0.386953 0.328317 0.85654 0.388857 0.339307 0.866231 0.418686 0.272663 0.860334 0.422084 0.285782 0.867176 0.444263 0.225026 0.862092 0.448189 0.236484 0.866648 0.463457 0.184738 0.863147 0.46677 0.192618 0.866046 0.476569 0.151152 0.85012 0.197565 0.488122 0.866175 0.165183 0.471652 0.87956 0.204654 0.429524 0.8847 0.201189 0.42051 0.898231 0.242492 0.366577 0.899682 0.241203 0.363859 0.909848 0.27434 0.31131 0.909136 0.275126 0.312695 0.916697 0.30135 0.262402 0.91529 0.303207 0.265159 0.920701 0.323107 0.218887 0.919627 0.324748 0.220965 0.923276 0.338965 0.180734 0.751287 0.122031 0.648595 0.872326 0.090885 0.480404 0.878357 0.108835 0.46545 0.889496 0.0964634 0.446644 0.911325 0.122607 0.393006 0.908654 0.125329 0.398297 0.923777 0.171522 0.34237 0.925382 0.170071 0.338739 0.934766 0.201065 0.292893 0.934675 0.201171 0.29311 0.94185 0.226098 0.248593 0.941225 0.227006 0.250129 0.946476 0.24624 0.208686 0.962273 0.233484 0.139702 0.898168 0.434847 0.064821 0.86892 0.487836 0.0836369 0.867656 0.484817 0.110118 0.931119 0.299307 -0.208406 0.925979 0.341333 -0.161413 0.925728 0.336411 -0.172786 0.904343 0.386467 -0.181128 0.870785 0.454602 -0.187272 0.884099 0.43261 -0.176686 0.852309 0.490156 -0.182525 0.925598 0.348667 0.147307 0.927594 0.358302 0.105776 0.929712 0.352161 0.107788 0.931317 0.35892 0.061844 0.934803 0.349078 0.0654786 0.935594 0.352679 0.0167889 0.94195 0.335121 0.0206166 0.974668 0.165476 0.150464 0.974511 0.167495 0.149246 0.951265 0.265348 0.15712 0.954651 0.279764 0.101852 0.956062 0.274168 0.103817 0.957694 0.281555 0.0595762 0.959573 0.274452 0.0624184 0.960287 0.27857 0.0157687 0.964201 0.264482 0.0191333 0.987811 0.139358 -0.0693514 0.969727 0.231529 -0.0776215 0.967431 0.241976 -0.0743289 0.947504 0.309499 -0.0802941 0.945397 0.316359 -0.07837 0.891094 0.445012 -0.0889705 0.888537 0.450699 -0.085861 0.795262 0.598757 -0.0951245 0.745971 0.66144 -0.0776208 0.916059 0.355784 -0.185077 0.948052 0.269358 -0.169245 0.953674 0.24583 -0.173416 0.967505 0.193315 -0.162981 0.968083 0.172119 -0.182184 0.346266 0.938136 -0.00027572 0.520459 0.853783 0.0133256 0.513806 0.857745 0.0166163 0.684649 0.728323 0.0283215 0.729959 0.683315 0.0155394 0.784151 0.620283 0.0188759 0.785322 0.618467 -0.0276971 0.857508 0.513955 -0.0230135 0.887672 0.458883 -0.0382634 0.331916 0.942408 -0.0412153 0.514981 0.856445 -0.0360113 0.517794 0.85468 -0.0375594 0.236413 0.970265 -0.0519078 0.223469 0.973109 -0.0558602 0.347314 0.93604 -0.0565885 0.23873 0.97088 -0.0200057 0.30662 0.951703 -0.0156885 0.331307 0.943274 -0.0216982 0.515791 0.856637 -0.0115179 0.514277 0.857557 -0.0107316 0.689656 0.724137 -0.0011924 0.690341 0.722817 -0.0310643 0.743119 0.667507 -0.0469964 0.0217496 0.999068 -0.037293 0.0531525 0.997954 -0.0355291 0.0543651 0.997688 -0.040784 0.0778079 0.995985 -0.0442768 0.0777101 0.996114 -0.0414516 0.0814305 0.995693 -0.0443186 0.08151 0.995742 -0.0430583 0.0910024 0.994548 -0.0509167 0.0917815 0.994713 -0.0460779 0.707013 0.701062 -0.0929788 0.601658 0.793141 -0.0945213 0.526122 0.847385 -0.0716522 0.486555 0.869753 -0.0824225 0.345252 0.935183 -0.0789545 0.369558 0.926351 -0.0728039 0.234385 0.969721 -0.0685882 0.25822 0.964075 -0.0623026 0.121624 0.990876 -0.0580786 0.0917166 0.995257 -0.032439 0.0814369 0.994901 -0.0594937 0.363142 0.927495 -0.0887807 0.286334 0.952301 -0.105524 0.438093 0.891754 -0.11336 0.404144 0.907156 -0.117196 0.520314 0.842528 -0.139354 0.990368 0.0932486 -0.102352 0.971477 0.205822 -0.117771 0.968423 0.221982 -0.113494 0.9504 0.286132 -0.121938 0.946584 0.299814 -0.118702 0.918252 0.37478 -0.127879 0.890976 0.439778 -0.112942 0.872148 0.472132 -0.128253 0.79468 0.591114 -0.138089 0.809545 0.572492 -0.12996 0.705912 0.695045 -0.136385 0.729294 0.67231 -0.127006 0.599817 0.789697 -0.128836 0.632665 0.765272 -0.118721 0.483483 0.867647 -0.115904 0.523782 0.845276 -0.105649 0.365844 0.925342 -0.0994996 0.408795 0.908221 -0.0895622 0.254471 0.963579 -0.0822201 0.294268 0.952931 -0.0730027 0.183011 0.98076 -0.0679403 0.179296 0.980564 -0.079676 0.242299 0.967985 -0.0655502 0.240058 0.968124 -0.0714666 0.0816953 0.987759 -0.132886 0.200119 0.979429 -0.0259181 0.143766 0.988212 -0.052609 0.145462 0.988613 -0.0385386 0.111097 0.99148 -0.0680108 0.00294975 0.865617 0.500699 0.033276 0.848264 0.528527 0.101815 0.885144 0.454042 0.0317036 0.882926 0.468441 0.177481 0.920726 0.34751 0.0266966 0.920112 0.390743 0.145643 0.950068 0.275969 0.252006 0.963002 0.0955011 0.266624 0.960211 0.0831056 0.214914 0.956939 0.195143 0.297899 0.940691 0.162348 0.178065 0.929836 0.322021 0.290461 0.914638 0.281195 0.139746 0.884409 0.4453 0.258234 0.87523 0.409008 0.18026 0.857702 0.481512 0.130833 0.852784 0.505611 0.0342564 0.998718 -0.0372621 0.0342618 0.998718 -0.0372735 0.041905 0.998796 -0.0254913 0.0793573 0.996087 -0.0389071 0.0620918 0.998019 -0.0101848 0.120199 0.992213 -0.032649 0.119193 0.992383 -0.0311259 0.0273822 0.99932 -0.0246962 0.037902 0.998612 -0.0365847 0.388547 0.786936 0.479336 0.393275 0.786234 0.476624 0.465916 0.806763 0.363396 0.398223 0.828102 0.394544 0.474588 0.844242 0.249042 0.402804 0.870658 0.28232 0.456927 0.875739 0.155881 0.383424 0.90421 0.188125 0.418639 0.903378 0.0929981 0.352546 0.928034 0.120271 0.377191 0.924925 0.0473328 0.292447 0.954278 0.0618768 0.30203 0.952827 0.0299845 0.362048 0.930862 0.0491603 0.407699 0.912195 0.0410104 0.394822 0.913823 0.0950959 0.471999 0.877869 0.0810098 0.451142 0.878035 0.159767 0.505708 0.852128 0.134675 0.478415 0.848394 0.226597 0.536131 0.8206 0.197938 0.495735 0.809856 0.313656 0.550771 0.784657 0.284544 0.493775 0.763246 0.416704 0.544683 0.742722 0.389467 0.490323 0.718793 0.492869 0.499573 0.718239 0.484314 0.598971 0.64331 0.47685 0.569502 0.640797 0.514826 0.616859 0.673818 0.406761 0.580111 0.691817 0.429955 0.622029 0.718616 0.31092 0.581385 0.740999 0.336025 0.610927 0.757192 0.231146 0.567638 0.782402 0.256192 0.587938 0.790896 0.169746 0.54575 0.815609 0.192194 0.562131 0.819509 0.111418 0.498664 0.857742 0.124952 0.507974 0.858113 0.0748588 0.582433 0.808762 0.0816984 0.969871 0.138754 0.200243 0.970024 0.146682 0.193745 0.946126 0.246849 0.20955 0.94972 0.260809 0.173236 0.922905 0.339598 0.181435 0.925263 0.349291 0.14793 0.864308 0.47847 0.15504 0.86655 0.486493 0.111425 0.775315 0.621883 0.110216 0.729509 0.678176 0.0888544 0.697611 0.709658 0.0986112 0.606917 0.789422 0.0920082 0.599006 0.786789 0.148844 0.645927 0.751129 0.136317 0.633652 0.742789 0.216218 0.664088 0.721262 0.196896 0.649289 0.70844 0.276653 0.68016 0.687146 0.255367 0.658697 0.666241 0.34963 0.687364 0.647728 0.328601 0.656644 0.616228 0.434836 0.681778 0.601798 0.415955 0.645348 0.563573 0.515666 0.683964 0.567948 0.457852 0.202968 0.978642 0.0326047 0.212332 0.976646 0.0328195 0.228645 0.973506 0.00280291 0.155212 0.987409 0.0305392 0.179248 0.983664 -0.0166045 0.105749 0.994391 -0.00193931 0.113294 0.99336 -0.0199899 0.138056 0.99026 -0.0180399 0.140374 0.989669 -0.0291705 0.219539 0.975299 -0.0243913 0.220155 0.974529 -0.0427168 0.335503 0.941187 -0.0400508 0.334825 0.940358 -0.0601673 0.517492 0.853583 -0.0599794 0.526408 0.84773 -0.0651852 0.743085 0.66652 -0.0597943 0.74602 0.663043 -0.0618803 0.88765 0.457614 -0.0516385 0.888604 0.455625 -0.052798 0.944321 0.325904 -0.0452153 0.94568 0.321754 -0.0465145 0.966212 0.254232 -0.0424319 0.967912 0.247246 -0.0448946 0.983207 0.177892 -0.0407147 0.983878 0.167739 -0.0620365 0.224215 0.804327 0.55026 0.321078 0.849058 0.419535 0.304124 0.837725 0.45357 0.275375 0.842235 0.463474 0.381047 0.864507 0.327765 0.29332 0.884351 0.363162 0.393597 0.896305 0.20425 0.302905 0.921748 0.242135 0.373464 0.921589 0.105827 0.284023 0.948299 0.141637 0.326869 0.943881 0.0473799 0.252876 0.964513 0.0759456 0.279088 0.960169 0.0136043 0.195643 0.980262 0.0284631 0.206011 0.97855 -0.000352541 0.239354 0.970929 0.00274909 0.234395 0.972134 0.00377096 0.368661 0.92942 0.0163886 0.342925 0.939121 0.0213362 0.478165 0.877611 0.0340234 0.519174 0.854279 0.0257962 0.585858 0.808721 0.0523426 0.682528 0.72841 0.0597923 0.730081 0.678557 0.0808801 0.773807 0.629985 0.0658914 0.845391 0.529655 0.0691413 0.846833 0.531551 0.0180653 0.907666 0.419136 0.0216187 0.908438 0.417482 -0.0211858 0.942525 0.333674 -0.0175773 0.944301 0.328515 -0.0193142 0.964613 0.263152 -0.016515 0.966303 0.256708 -0.0189544 0.982517 0.185493 -0.0158778 0.981974 0.188505 -0.0138901 0.763245 -0.324848 -0.558508 0.7635 -0.40702 -0.5014 0.765481 -0.405765 -0.499394 0.769176 -0.49325 -0.406292 0.637171 -0.622563 -0.454344 0.773607 -0.537883 -0.334983 0.770598 -0.595461 -0.227167 0.77566 -0.590155 -0.223761 0.770166 -0.633986 -0.0700474 0.775391 -0.627854 -0.0675858 0.763363 -0.638531 0.0977495 0.722609 -0.404695 0.560408 0.727589 -0.398936 0.558091 0.712996 -0.326216 0.62066 0.718396 -0.320563 0.617371 0.769752 -0.630607 0.0990731 0.758304 -0.60982 0.230425 0.560791 -0.768849 0.30722 0.754681 -0.572885 0.319779 0.741471 -0.53088 0.41035 0.745908 -0.525143 0.409691 0.732084 -0.472815 0.490408 0.683706 -0.528382 0.503348 0.732694 -0.446047 0.514006 0.710049 -0.26856 0.650927 0.71426 -0.259872 0.649845 0.709709 -0.252401 0.657729 0.971048 0.0821942 -0.2243 0.957895 0.0713735 -0.278105 0.925559 0.0694292 -0.372182 0.8627 0.0652905 -0.501483 0.970788 0.0821927 -0.225421 0.963868 0.0704293 -0.256903 0.965327 0.0701323 -0.251448 0.969243 0.0688283 -0.236285 0.972399 0.0659433 -0.22381 0.975488 0.0622893 -0.211052 0.976111 0.0610852 -0.208508 0.978227 0.0658112 -0.196828 0.980372 0.0699733 -0.184323 0.982739 0.0721358 -0.170352 0.998353 0.0495406 0.0289194 0.999784 0.00850115 0.018987 0.999884 0.00156993 0.0151825 0.99253 0.12063 0.0182536 0.996145 0.0843057 0.0242229 0.990982 0.132751 0.0182391 0.999999 -0.000857171 0.00100852 0.9908 0.132927 0.0254005 0.989492 0.142038 0.0270504 0.991813 0.119935 -0.0438592 0.991917 0.12576 0.0168761 0.991798 0.126666 0.0170933 0.991834 0.126684 -0.0147482 0.993359 0.11147 -0.0285167 0.99108 0.0940553 -0.0944104 0.990633 0.102724 -0.0899704 0.990762 0.119965 -0.0632397 0.98218 0.0952211 -0.162037 0.988452 0.0716254 -0.133539 0.986511 0.0915914 -0.135673 0.982889 0.116537 -0.142651 0.983848 0.0886585 -0.155511 0.980801 0.000516775 -0.19501 0.980787 -0.0017699 -0.195072 0.98829 0.0267362 -0.150225 0.986615 0.013839 -0.162478 0.993448 0.0130673 -0.11354 0.994277 0.0301675 -0.102483 0.996879 0.0155466 -0.0774046 0.993922 0.0471989 -0.0994546 0.993903 0.0407634 -0.102443 0.986351 0.0413461 -0.159382 0.985989 0.0380885 -0.162406 0.977493 0.0386554 -0.207394 0.974936 0.024301 -0.221154 0.993718 0.107201 -0.0321241 0.993765 0.10686 -0.031827 0.995804 0.08573 -0.0320234 0.996003 0.0857104 0.0251202 0.999204 0.0355495 0.0180787 0.985269 0.073457 -0.154434 0.984187 0.0736006 -0.161115 0.984684 0.0712625 -0.159117 0.992979 0.0708676 -0.0947138 0.991738 0.0813762 -0.0991683 0.996114 0.081238 -0.034007 0.998314 0.0468882 -0.0342038 0.998142 0.0495752 -0.0354176 0.999254 0.0151997 -0.0355056 0.998464 0.0335805 -0.0440588 0.274872 0.000446656 -0.961481 0.251353 -0.00548564 -0.96788 0.222828 -0.0221717 -0.974606 0.242075 0.0192012 -0.970068 0.185115 -0.0312434 -0.98222 0.203541 0.0175456 -0.978909 0.193188 0.00540759 -0.981147 0.185787 0 -0.98259 0.185783 -1.97004e-06 -0.982591 0.185768 -4.47497e-06 -0.982594 0.185798 -3.34124e-07 -0.982588 0.177425 2.64657e-06 -0.984134 0.177414 4.48592e-06 -0.984136 0.177436 0 -0.984132 0.177436 0 -0.984132 0.181178 -0.0036209 -0.983444 0.189531 -0.0142863 -0.981771 0.192897 -0.0239857 -0.980926 0.266851 -0.00184371 -0.963736 0.227483 0.00939143 -0.973737 0.247585 -0.00975238 -0.968817 0.190399 0.0178439 -0.981545 0.174781 0.0363224 -0.983937 0.365305 0.0144983 -0.930775 0.336526 -0.0109731 -0.94161 0.348648 0.00149397 -0.937252 0.311895 -0.00285854 -0.950112 0.319827 0.0066406 -0.947453 0.297489 -0.000404099 -0.954725 0.352328 0.00605058 -0.935857 0.359215 0.0172547 -0.933095 0.354542 -0.00849304 -0.935002 0.370291 -0.000313118 -0.928916 0.377483 0.000298915 -0.926016 0.377373 0.000218924 -0.926061 0.376829 0.000279587 -0.926283 0.00227992 0 -0.999997 0.000506212 0 -1 0.00451983 -0.000173629 -0.99999 0.0207866 -0.00374663 -0.999777 0.0125266 0.00476191 -0.99991 0.00609634 0.00730958 -0.999955 -0.00533172 0.0122551 -0.999911 -0.0807886 0.0463463 -0.995653 -0.143797 0.0750048 -0.986761 -0.00375883 0.00326872 -0.999988 0.00139512 0.000516738 -0.999999 0.320834 0.000137669 -0.947135 0.279361 0.000137811 -0.960186 0.235754 0.0588263 -0.970031 0.190584 8.17439e-06 -0.981671 0.140149 4.95067e-06 -0.990131 0.132664 -0.000377794 -0.991161 0.110465 0.00408397 -0.993872 0.0701995 -0.0174905 -0.99738 0.0573244 -0.00513048 -0.998342 0.0226961 0.00161848 -0.999741 0.0177859 0.00296207 -0.999837 0.0496031 2.55382e-05 -0.998769 0.042985 0.00104717 -0.999075 0.0388292 0.00338515 -0.99924 0.110677 0.010064 -0.993806 0.0507354 -0.00302239 -0.998708 0.0380305 0.00289826 -0.999272 0.0354083 0.00227777 -0.99937 0.0339882 0.0020481 -0.99942 0.0807142 0.000272296 -0.996737 0.181638 -0.000437901 -0.983365 0.177443 4.99135e-07 -0.984131 0.118566 -0.00943139 -0.992901 0.0655175 0.000805802 -0.997851 0.0448912 -0.0053994 -0.998977 0.0442699 -0.00478316 -0.999008 0.0435633 -0.000882357 -0.99905 0.0499326 -2.57084e-05 -0.998753 0.0590516 -0.00145489 -0.998254 0.157788 -0.023195 -0.987201 0.0385288 -0.00251798 -0.999254 0.0419994 -0.0037182 -0.999111 0.288945 0.000955797 -0.957345 0.313211 -0.00245238 -0.94968 0.31 1.86193e-05 -0.950737 0.341642 0.000315285 -0.93983 0.353285 -0.00880669 -0.935474 0.363591 -0.00129393 -0.931558 0.37665 0.000484424 -0.926356 0.193794 -0.112724 -0.974545 0.27985 -0.000140496 -0.960044 0.359269 -0.000133242 -0.933234 0.349503 -0.0265161 -0.93656 0.377216 9.65215e-05 -0.926125 0.00478088 -0.000470613 -0.999988 0.00227992 0 -0.999997 0.00227992 0 -0.999997 0.0182957 -0.00121863 -0.999832 0.0206959 -0.000657533 -0.999786 0.0396782 0.00105143 -0.999212 0.0076338 -0.00109254 -0.99997 0.012175 -0.00236414 -0.999923 -0.00269139 0.00310914 -0.999992 0.00185887 0.00169904 -0.999997 0.236163 -1.11105e-05 -0.971713 0.140149 -4.95067e-06 -0.990131 0.133015 0.000359851 -0.991114 0.131637 9.57613e-05 -0.991298 0.0707902 -0.000898057 -0.997491 0.0927494 0.0354379 -0.995059 0.0580285 0.00849528 -0.998279 0 0.998256 -0.059034 -0.00052567 0.998111 -0.061439 0.000398205 0.993373 -0.114935 -0.00364531 0.989723 -0.142949 -0.00567739 0.988734 -0.149575 -0.00629342 0.988477 -0.151238 -0.00375314 0.988905 -0.148504 5.72135e-08 0.999048 -0.0436195 2.43669e-07 0.999048 -0.0436196 -6.65054e-07 0.999048 -0.043619 -4.86167e-07 0.999048 -0.0436197 3.74893e-07 0.999048 -0.0436193 1.14045e-06 0.999048 -0.0436189 -7.71798e-08 0.999048 -0.0436194 -9.75149e-07 0.999048 -0.0436189 1.56663e-07 0.999048 -0.0436196 2.68804e-07 0.999048 -0.0436195 8.52115e-08 0.999048 -0.0436194 9.3595e-08 0.999048 -0.0436194 -8.17936e-07 0.999048 -0.0436195 1.89255e-06 0.999048 -0.0436197 -4.73467e-07 0.999048 -0.0436189 9.58985e-09 0.999048 -0.0436194 1.90945e-08 0.999048 -0.0436193 1.62905e-07 0.999048 -0.0436195 1.65331e-07 0.999048 -0.0436195 -2.10497e-06 0.999048 -0.0436181 -1.67357e-08 0.999048 -0.0436195 0 0.999048 -0.0436195 1.40895e-05 0.999049 -0.0436037 -5.30456e-07 0.999048 -0.0436197 5.26655e-07 0.999048 -0.0436197 -1.05294e-06 0.999048 -0.0436186 -5.16204e-07 0.999048 -0.0436192 -3.1139e-08 0.999048 -0.0436194 1.25662e-06 0.999048 -0.0436196 -2.3353e-06 0.999048 -0.0436189 4.05177e-06 0.999048 -0.0436205 2.78891e-05 0.999048 -0.0436273 5.32845e-05 0.999048 -0.04363 7.40342e-07 0.999048 -0.0436187 -9.08883e-08 0.999048 -0.0436193 5.15637e-07 0.999048 -0.0436194 -2.18888e-07 0.999048 -0.0436191 -2.44253e-07 0.999048 -0.043619 -2.58295e-07 0.999048 -0.043619 -2.44088e-07 0.999048 -0.0436195 -1.4228e-07 0.999048 -0.0436196 -1.26729e-07 0.999048 -0.0436192 4.13423e-07 0.999048 -0.0436194 1.76668e-08 0.999048 -0.04362 3.62909e-07 0.999048 -0.043619 0.997546 0 -0.0700188 0.997577 0.000816799 -0.0695625 0.995242 -0.000794646 -0.097434 0.995072 0.00151458 -0.0991426 0.991991 -0.0015503 -0.126298 0.984201 0.059865 -0.166626 0.984807 0.0551846 -0.164648 0.983519 0.0049702 -0.180739 0.976624 -0.00450973 -0.21491 0.976825 0.00155093 -0.214035 0.978382 0.00341857 -0.206778 0.978141 -0.00426882 -0.2079 0.988085 0.00654846 -0.153771 0.997354 -3.45296e-06 0.0727027 0.997306 -0.000290699 0.0733602 0.99654 0.00115004 0.0831097 0.996485 -0.000741502 0.083771 0.995202 0.00070874 0.0978441 0.995257 -0.000266658 0.0972773 0.994111 0.000203342 0.108369 0.994116 0.000103935 0.108321 0.993321 -6.70112e-05 0.115384 0.993214 0.00209211 0.116282 0.993959 0.0274004 0.106272 0.994767 0.000695528 0.102163 0.998817 -0.00122078 0.048607 0.998759 0.00496955 0.04956 0.99999 -0.000442507 0.00449276 0.999984 -3.16561e-08 0.00567018 0.999749 1.25022e-07 -0.0223937 0.999778 0.00468607 -0.0205327 0.996775 -0.00624556 -0.0800028 0.997132 0.0084348 -0.0752122 0.990818 -0.00617954 -0.135059 0.999555 0.00119521 0.029801 0.999927 -0.0011084 0.0120546 0.99993 0.000575054 0.0117917 0.999999 -0.000270361 0.00141511 0.999999 0 0.00137422 0.997955 -1.69302e-06 0.0639214 0.997861 0.00122714 0.0653621 0.998916 -0.00181983 0.0465177 0.998715 0.00175903 0.0506411 0.999542 -0.00139335 0.0302341 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.995215 -0.0977102 0 0.994031 -0.107814 0.0166607 0.97476 -0.22324 -0.00247479 0.948372 -0.316804 0.0150427 0.94389 -0.328867 0.0302965 0.878423 -0.477231 -0.0249685 0.872656 -0.488136 -0.0139681 0.81109 -0.58486 0.0085065 0.765117 -0.643212 -0.0295495 0.69593 -0.717036 0.0392604 0.635121 -0.772233 -0.016683 0.520697 -0.853412 0.0237126 0.499784 -0.86615 0 0.753677 0.0325942 -0.656436 0.759369 0.001173 -0.65066 0.777919 0.00482185 -0.628346 0.816075 0.00838228 -0.577886 0.75451 0.0325721 -0.65548 0.755106 0.0248553 -0.655131 0.756061 0.0250952 -0.654019 0.756408 0.019216 -0.653818 0.746218 0.0168202 -0.665489 0.757982 0.0158741 -0.652083 0.758045 0.0141584 -0.652048 0.758794 0.0103584 -0.651248 0.76034 -0.21453 -0.613074 0.762787 -0.296699 -0.574566 0.753471 0.0348169 -0.656559 0.753842 -0.01745 -0.656823 0.607863 -0.0903256 -0.788888 0.756328 -0.105603 -0.645613 0.765193 -0.21098 -0.608249 0.957136 0.248767 -0.148345 0.991761 0.128103 0 0.874706 0.484655 0 0.804667 0.58892 -0.0753908 0.726461 0.687207 0 0.999997 0.00263185 0 0.969142 -0.246503 0 0.927897 -0.365136 -0.0753875 0.536874 -0.843662 0 0.636695 -0.767422 -0.0753904 0.730052 -0.683392 0 0.877233 -0.480064 0 0.989179 0.146711 0 0.989355 0.0729644 0.125907 0.975707 0.219078 0 0.933005 0.359864 0 0.902187 0.426648 0.0634925 0.870119 0.492841 0 0.741007 0.671497 0 0.782119 0.610278 0.125899 0.689608 0.724183 0 1 0 0 1 0 0 0.863197 -0.48892 0.125888 0.904011 -0.42751 0 0.788392 -0.615173 0 0.739512 -0.670142 0.0634983 0.689608 -0.724183 0 0.997292 -0.0735497 0 0.987183 -0.146415 0.0635026 0.975707 -0.219078 0 0.933005 -0.359864 0 0.536874 0.843662 0 0.636695 0.767422 -0.0753904 0.730052 0.683392 0 0.930545 0.366178 0 0.867526 0.474753 -0.148351 0.969142 0.246502 0 0.991761 -0.128103 0 0.988932 -0.00260273 -0.148344 0.967844 -0.25155 0 0.806964 -0.590601 0 0.865026 -0.479292 -0.148356 0.726461 -0.687207 0 0.993761 0.111534 0 0.537949 0.842978 0 0.520608 0.853267 -0.0300449 0.668987 0.743147 0.0137358 0.696045 0.716918 0.0393727 0.765437 0.642817 -0.029868 0.811184 0.584732 0.00830691 0.879184 0.476214 -0.0160064 0.872036 0.488544 -0.0296257 0.948889 0.313587 0.0356869 0.94388 0.329796 0.018053 0.974926 0.222514 -0.00265605 0.99569 0.0905858 0.0198952 0.763031 0.254266 -0.594249 0.773618 0.315344 -0.549612 0.76465 0.33422 -0.551006 0.763634 0.332817 -0.553259 0.762388 0.307334 -0.569482 0.773215 0.289182 -0.564369 0.774867 0.298336 -0.557294 0.775675 0.304687 -0.552716 0.75876 0.0511277 -0.649361 0.751665 0.0545301 -0.657287 0.763105 0.22358 -0.606368 0.762029 0.223931 -0.60759 0.791669 0.208327 -0.574334 0.850517 0.172109 -0.496991 0.913851 0.121181 -0.387546 0.721477 -0.00555188 -0.692416 0.759362 -0.00424172 -0.650654 0.758604 -0.0115745 -0.651449 0.757757 -0.0158493 -0.652345 0.747216 -0.0166626 -0.664373 0.799849 -0.0304155 -0.599431 0.804007 -0.0306439 -0.59383 0.753691 -0.0328865 -0.656405 -4.51423e-06 -0.999048 -0.0436188 3.7827e-07 -0.999048 -0.0436194 -9.54574e-07 -0.999048 -0.0436204 0 -0.999048 -0.0436195 2.1672e-08 -0.999048 -0.0436195 2.73401e-06 -0.999048 -0.0436218 -3.82039e-07 -0.999048 -0.0436194 0 -0.999048 -0.0436194 4.2827e-08 -0.999048 -0.0436194 4.84001e-08 -0.999048 -0.0436175 4.62087e-07 -0.999048 -0.04362 -1.09687e-06 -0.999048 -0.0436191 -1.58816e-07 -0.999048 -0.0436194 1.32607e-07 -0.999048 -0.043619 -4.80531e-07 -0.999048 -0.043621 -8.59793e-06 -0.999048 -0.043618 -0.000410216 -0.999052 -0.0435364 -2.29568e-05 -0.999048 -0.0436145 -1.92015e-06 -0.999048 -0.0436185 -5.30352e-06 -0.999048 -0.0436268 -1.03444e-05 -0.999048 -0.0436221 -9.37662e-06 -0.999048 -0.0436228 -9.71182e-06 -0.999048 -0.0436226 1.60982e-06 -0.999048 -0.043619 -1.20254e-07 -0.999048 -0.0436197 -1.29652e-05 -0.999048 -0.0436272 -2.29836e-06 -0.999048 -0.0436193 -2.2743e-06 -0.999048 -0.0436192 -2.82017e-06 -0.999048 -0.0436196 -1.7373e-06 -0.999048 -0.0436172 -5.96698e-06 -0.999048 -0.043626 -1.46516e-05 -0.999049 -0.0436128 6.12114e-07 -0.999048 -0.0436203 -1.0327e-06 -0.999048 -0.0436192 2.24133e-06 -0.999048 -0.0436194 -4.65e-06 -0.999048 -0.0436194 -4.69251e-06 -0.999048 -0.0436197 -4.74052e-06 -0.999048 -0.0436255 3.55432e-07 -0.999048 -0.0436197 4.79428e-07 -0.999048 -0.0436194 -1.12954e-05 -0.99905 -0.0435727 4.73443e-05 -0.999046 -0.0436721 -2.02472e-05 -0.999048 -0.0436218 8.86729e-05 -0.999051 -0.0435516 -3.11611e-08 -0.999047 -0.0436504 0.00034393 -0.99373 -0.111802 -0.000525712 -0.998111 -0.0614382 -0.00377997 -0.997076 -0.0763192 0 -0.998698 -0.0510175 -0.00408987 -0.988907 -0.148481 -0.00622004 -0.98848 -0.151225 -0.00326397 -0.989855 -0.142044 0.986351 -0.0413444 -0.15938 0.980801 -0.000516775 -0.19501 0.989546 -0.141206 0.0293244 0.99378 -0.109022 0.0226844 0.997284 -0.0716272 0.0171427 0.994115 -0.106357 0.0206052 0.991589 -0.128305 0.0169836 0.970788 -0.0875791 -0.223383 0.979015 -0.0914614 -0.182112 0.972048 -0.0832938 -0.219509 0.978389 -0.0813273 -0.190107 0.978274 -0.062784 -0.197583 0.977953 -0.0434377 -0.204259 0.976504 -0.057183 -0.207774 0.973468 -0.0775041 -0.215296 0.969135 -0.0897254 -0.229623 0.969808 -0.0895782 -0.226823 0.992993 -0.0897674 0.0768583 0.972651 -0.0816547 -0.217445 0.971344 -0.0773244 -0.224746 0.98424 -0.0981558 -0.147093 0.988751 0.0986116 -0.112457 0.983755 -0.092503 -0.153852 0.983155 -0.0931441 -0.15726 0.980431 -0.0942172 -0.172852 0.991188 -0.132453 -0.00180448 0.993259 -0.110668 -0.0344935 0.992608 -0.117146 -0.031724 0.990021 -0.121944 -0.0706323 0.99143 -0.0902352 -0.0944645 0.983615 -0.12783 -0.127128 0.983725 -0.0970642 -0.151206 0.977036 -0.0614457 -0.204021 0.97579 -0.0660049 -0.208511 0.985846 -0.0656078 -0.154283 0.984685 -0.0712577 -0.159115 0.992979 -0.0708627 -0.0947144 0.998314 -0.0468868 -0.0342034 0.998143 -0.0495701 -0.0354154 0.998574 -0.0495528 0.0198637 0.998905 -0.0408896 0.0227325 0.992867 -0.0365862 -0.113473 0.996879 -0.0155472 -0.0774046 0.999254 -0.0151984 -0.0355034 0.998464 -0.0335855 -0.0440588 0.99974 0.00247902 0.0226668 0.999767 -0.0153333 0.0151807 0.995957 -0.085701 0.0269125 0.995804 -0.0857259 -0.0320213 0.996115 -0.0812296 -0.0340067 0.991738 -0.0813678 -0.0991672 0.993922 -0.0471976 -0.0994534 0.993904 -0.0407617 -0.102441 0.994647 -0.0128888 -0.102523 0.982735 -0.0141775 -0.184474 0.988129 -0.0322626 -0.1502 0.978348 -0.0145127 -0.206459 0.980635 -0.0245776 -0.194295 0.710672 0.26048 0.653525 0.713185 0.261287 0.650458 0.711417 0.27617 0.646232 0.768835 0.637299 0.0523727 0.771907 0.633643 0.0515369 0.754711 0.623139 0.205205 0.555189 0.808621 0.19467 0.826874 0.45496 0.330592 0.752475 0.560523 0.345826 0.737703 0.503596 0.449651 0.689812 0.537672 0.484839 0.731493 0.471672 0.492386 0.737861 0.406183 0.539051 0.756038 0.384585 0.529623 0.688795 0.349108 0.635362 0.718164 0.318905 0.618498 0.775445 0.627656 -0.068797 0.770121 0.634145 -0.0690861 0.776126 0.598912 -0.197314 0.662981 0.698396 -0.269628 0.773459 0.570594 -0.276012 0.771625 0.514136 -0.374513 0.767934 0.518201 -0.376491 0.765498 0.405843 -0.499303 0.763539 0.407696 -0.500792 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.999999 0 0.00135575 0.99893 0.00200159 0.0462037 0.998909 0.00600074 0.0463208 0.997895 -0.00227846 0.064815 0.99776 -7.45179e-06 0.0668895 0.997355 -1.34574e-06 0.0726908 0.997172 0.001055 0.0751404 0.996506 -0.00313338 0.0834584 0.996324 0.000702804 0.0856626 0.995262 -0.000838707 0.0972299 0.995369 -0.00335818 0.0960727 0.994103 0.00406273 0.108363 0.999964 0.00802193 0.00267559 0.999943 -0.00520392 0.0092994 0.999709 0.0071715 0.0230439 0.999537 -0.0131478 0.027445 0.999558 -0.00142737 0.0296885 0.994782 0.000955504 0.10202 0.994288 -0.000142504 0.106727 0.993321 6.69089e-05 0.11538 0.993215 -0.0020909 0.116277 0.993116 9.86271e-05 0.117134 0.994757 -0.000576356 0.102262 0.996752 -0.000104537 0.0805351 0.998802 0.0134401 0.0470466 0.998802 0.00182197 0.048899 0.999986 -0.000131596 0.00529051 0.999811 0.00673011 -0.0182379 0.999778 0.00108291 -0.0210547 0.99695 -0.00138876 -0.0780318 0.997028 0.000866618 -0.0770413 0.990412 -0.000744385 -0.138142 0.990437 -0.000342281 -0.137965 0.983257 0.000222555 -0.182222 0.983168 -0.000865537 -0.182704 0.976751 0.000845133 -0.214377 0.976677 -0.000558908 -0.214715 0.978173 -0.00127392 -0.207789 0.978359 0.00240054 -0.206899 0.986334 -0.00257806 -0.16474 0.997585 0 -0.0694515 0.997537 -0.00078367 -0.0701325 0.995242 0.000794934 -0.097434 0.995072 -0.00151456 -0.0991427 0.991991 0.0015503 -0.126298 0.991849 -0.000142931 -0.127419 0.986236 -0.000142638 -0.165343 0 -0.0561314 -0.998423 0 -0.716733 -0.697348 0.542682 -0.305049 -0.782586 0.322559 -0.412865 -0.851762 -0.061587 -0.386716 -0.92014 0.0814436 -0.184197 -0.979509 0.320269 -0.20831 -0.92414 0.00413703 -0.126625 -0.991942 0 -0.651173 -0.758929 0.718323 -0.487694 -0.496152 3.84117e-05 -0.779857 -0.625958 6.92697e-06 -0.848436 -0.529298 0.699574 -0.650607 -0.295476 0.180559 -0.911617 -0.36926 -0.15497 -0.975427 -0.156611 0 -0.985241 -0.171174 1.73466e-06 -0.769623 0.638499 0 -0.998714 0.0507036 0.274133 -0.955964 0.104802 -7.08725e-06 -0.812848 0.582476 0.0895208 -0.865884 0.492169 0.186562 -0.872293 0.451995 0.000125028 -0.93527 0.353935 -0.0001082 -0.973588 0.228311 0.0348593 -0.701856 0.711465 0.0882614 -0.667448 0.739408 0 -0.595137 0.803624 0.69632 -0.18138 0.694434 0.692462 -0.184129 0.697562 0.697885 -0.108838 0.707892 0.697962 -0.107789 0.707977 0.692565 -0.0732606 0.717626 0.6977 -0.0733577 0.712624 0.690378 -0.0168924 0.723252 0.693194 -0.0176919 0.720534 0.688517 0.0201356 0.72494 0.690508 0.0188695 0.723079 0 -0.509043 0.860741 0.0265274 -0.418359 0.907894 -0.00685986 -0.389328 0.921074 0 -0.0916802 0.995789 0.010048 -0.14652 0.989157 0.0310235 -0.188631 0.981558 0.00706712 -0.230822 0.97297 0.00082705 -0.285336 0.958427 0.701312 0.0105631 0.712777 0.646819 0.0052827 0.762625 0.688707 0.00235673 0.725036 0.68911 0.0309707 0.723994 0.736357 0.0321063 0.675832 0.789154 0.0375909 0.613044 0.688868 0.0185529 0.724649 0.689081 0.014783 0.724534 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.998256 0.0590348 0 0.980666 0.195067 -0.0155866 0.975508 0.219782 -0.00892532 0.942854 0.333203 -0.00127933 0.903119 0.429383 0.00271003 0.831339 0.555485 -0.017656 0.804669 0.593694 -0.00597092 0.667479 0.74462 0.00363779 0.555461 0.831303 -0.019958 0.501766 0.864997 -0.00339308 0.305305 0.952251 0.00264819 0.195029 0.980481 -0.0249208 0.102805 0.994702 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.297826 0.954526 -0.0133924 -0.194426 0.977448 -0.0824224 -0.146606 0.988892 -0.0244738 -0.0230328 0.999735 0 -0.553756 0.828752 -0.0807699 -0.532901 0.844979 -0.0450286 -0.395831 0.918301 0.00644284 -0.860088 0.502776 -0.0863989 -0.7351 0.677959 -1.20392e-06 -0.663874 0.747844 -1.32802e-06 -0.830732 0.55508 0.0420841 -0.9802 0.194975 -0.034546 -0.984427 0.175792 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.990314 -0.138849 0 0.998192 -0.0600993 -0.00404328 0.998059 -0.0621432 -4.35829e-06 0.990313 -0.13885 -5.04585e-05 0.990311 -0.138867 0.0053815 0.990652 -0.136306 -0.000198195 0.990876 -0.134778 0 -0.990313 -0.13885 -2.87328e-05 -0.99087 -0.134824 -0.000139826 -0.990874 -0.134794 -0.000257861 -0.990876 -0.134773 0.00553502 -0.990487 -0.137499 -0.00435414 -0.998208 -0.0596764 0 -0.998032 -0.0627081 -0.980785 -0.195091 0 -0.65252 -0.757729 0.00806321 -0.74158 -0.670854 -0.0038924 -0.829832 -0.554478 -0.0627196 -0.862915 -0.504428 0.0305058 -0.983704 -0.175663 -0.0383322 -0.487839 -0.859524 -0.152421 -0.555392 -0.831201 -0.0253952 -0.310116 -0.950612 0.0128461 -0.19433 -0.976965 -0.08818 -0.103749 -0.994603 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0783887 -0.996923 0 0.195031 -0.980489 -0.0245927 0.25331 -0.967367 -0.00587211 0.439489 -0.898238 0.00423734 0.555448 -0.831284 -0.0210732 0.616454 -0.787387 -0.00237486 0.757819 -0.652463 0.00181465 0.831317 -0.55547 -0.0191047 0.871404 -0.490561 -0.00197768 0.952803 -0.303584 0.00166823 0.980616 -0.195058 -0.0185613 0.994713 -0.102693 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.999048 -0.0436192 -4.02264e-07 0.999048 -0.0436191 -5.5827e-07 0.999048 -0.0436194 -4.84743e-08 0.999048 -0.0436196 1.29404e-07 0.999048 -0.0436194 -4.04185e-07 0.999048 -0.0436192 -5.0819e-07 0.999048 -0.0436193 -9.46512e-08 0.999048 -0.0436195 -6.39504e-08 0.999048 -0.0436195 2.39118e-07 0.999048 -0.0436197 -9.48949e-08 0.999048 -0.0436189 2.41647e-07 0.999048 -0.0436191 1.77084e-07 0.999048 -0.0436192 1.78143e-07 0.999048 -0.0436192 3.43231e-08 0.999048 -0.0436197 -8.89898e-07 0.999048 -0.0436195 0 0.999048 -0.0436199 0.0289831 0.279293 0.959768 -0.0407036 0.171437 0.984354 -0.00549629 0.251795 0.967765 0.00114131 0.341446 0.939901 3.23247e-06 0.329147 0.944279 -8.20122e-06 0.38465 0.923063 0 0.0095518 0.999954 -0.000898741 0.00733252 0.999973 0.00212222 0.060803 0.998148 -0.00203367 0.0492194 0.998786 0.00114388 0.114814 0.993386 2.50925e-05 0.107288 0.994228 -1.54194e-05 0.149733 0.988726 0.00480993 0.199486 0.979889 0.0225447 0.469121 0.882846 -0.0155427 0.409298 0.912268 0.00760803 0.533067 0.846039 4.4244e-07 0.511525 0.859268 2.00475e-07 0.560756 0.827981 0.00142922 0.574585 0.818444 -0.00668125 0.629917 0.776634 0.00728625 0.654894 0.755686 0.000667852 0.690985 0.722869 -0.00026468 0.707333 0.706881 -8.41677e-05 0.709641 0.704563 0.000719116 0.751891 0.659287 0.00192418 0.753475 0.657474 -0.0012882 0.809815 0.586684 -1.36983e-06 0.81198 0.583685 -2.55205e-06 0.839901 0.54274 0.00149386 0.846021 0.533148 -0.00460053 0.874328 0.485313 0.00780974 0.888632 0.458555 -0.00137675 0.910571 0.413352 0.00252627 0.932159 0.36204 0.00962759 0.93952 0.342358 -0.00798866 0.960773 0.277221 0.0006893 0.96914 0.246509 -0.00131772 0.987361 0.158484 0 0.999742 -0.0227147 0.00407594 0.999585 -0.0285295 -0.00247493 0.999611 0.027777 -0.00677706 0.999003 0.0441322 0.0058932 0.995864 0.0906615 -0.0115166 0.98415 0.176967 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.0220443 -0.0101377 -0.999706 0.00855149 -0.00712243 -0.999938 0 -0.00198824 -0.999998 0.000399249 -0.0271062 -0.999632 -6.3821e-07 -0.0205923 -0.999788 -1.70029e-05 -0.0154931 -0.99988 0.055745 -0.0357763 -0.997804 0.0500831 -0.0353419 -0.99812 0 -0.0495257 -0.998773 0 -0.999742 -0.0227246 0.00858016 -0.996998 0.0769564 -0.00441659 -0.999 0.0444947 0.00407074 -0.999585 -0.0285334 0.00817024 -0.887914 0.459938 -0.00662985 -0.922022 0.387082 0.00443195 -0.934247 0.356598 -8.64538e-07 -0.946737 0.322008 1.26756e-06 -0.955931 0.293591 -0.00432008 -0.964469 0.264159 0.0103905 -0.977355 0.211351 -0.00323717 -0.985316 0.17071 0.00175966 -0.993808 0.111094 2.14284e-06 -0.667337 0.744756 0.00221363 -0.682405 0.730971 1.15621e-05 -0.896988 0.442054 1.14957e-05 -0.868283 0.496069 -0.00197648 -0.862375 0.506266 0.00556741 -0.826821 0.562437 -0.00202961 -0.817761 0.575554 0.000318629 -0.7836 0.621266 -0.00325237 -0.752026 0.659125 0.00248394 -0.742583 0.669749 -0.000360745 -0.706098 0.708114 0.00115186 -0.687057 0.726603 -1.48126e-06 -0.602403 0.798192 -0.017045 -0.628235 0.777837 0.00714221 -0.545287 0.838219 3.51476e-06 -0.0965413 0.995329 0.000622831 -0.131845 0.99127 0.0164673 -0.203636 0.978908 -0.0139201 -0.144444 0.989415 0.0086555 -0.269629 0.962926 0.00335234 -0.251111 0.967953 -0.00398343 -0.360456 0.932768 0.0122541 -0.40418 0.914597 1.08394e-05 -0.457908 0.889 -1.1425e-05 -0.515396 0.856952 0 -0.00642917 0.999979 -0.00656864 -0.0330754 0.999431 -0.00124213 -0.0488236 0.998807 -5.18732e-06 -0.0883752 0.996087 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.358157 0.358271 -0.862186 0.0476304 0.512087 -0.857612 0.0168431 0.527872 -0.849157 0 0.544318 -0.838879 -0.11467 0.433806 -0.89368 0.0932479 0.185434 -0.978222 0 0.173238 -0.98488 0 0.0499117 -0.998754 0.0482885 0.0353448 -0.998208 0.0541271 0.0357723 -0.997893 2.19291e-05 0.0266581 -0.999645 -3.65987e-05 0.01014 -0.999949 0 0.0101438 -0.999949 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.688708 -0.00135074 0.725037 0.710129 -0.00474299 0.704056 0.69964 -0.00515742 0.714477 0.679627 -0.0100107 0.73349 0.689744 -0.011452 0.723963 0.687626 -0.0196422 0.725799 0.689782 -0.0199797 0.723741 0.688869 -0.0296206 0.724281 0.689206 -0.0297105 0.723956 0.615106 0.222164 0.756497 0.705998 0.230502 0.669653 0.690227 -0.0208925 0.723291 0.652372 0.0254866 0.757471 0.570418 0.0716579 0.818223 0.689573 0.0734368 0.720483 0.707815 0.155654 0.689036 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.0309697 0.186731 0.981923 0.00984075 0.144433 0.989466 0 0.0908476 0.995865 0 0.509823 0.86028 0.0148113 0.45986 0.887868 0.0387607 0.419261 0.907038 -0.00751105 0.360818 0.932606 0.00675373 0.229809 0.973212 -3.27188e-05 0.842195 0.539173 1.16464e-05 0.798534 0.60195 0.0550003 0.685519 0.725975 0.129847 0.701279 0.700961 0 0.592702 0.805422 0.15952 0.900185 0.405242 0.0940616 0.901949 0.421474 -0.0645145 0.985133 0.159219 0.301623 0.949609 0.085247 0 0.999937 -0.0112624 0 0.621008 -0.783804 0 0.98522 -0.171296 0.6666 0.722931 -0.1817 -0.347257 0.617091 -0.706124 0.622283 0.634291 -0.458736 0.645921 0.619592 -0.445973 -1.23901e-05 0.893997 -0.448073 0.000118355 0.939085 -0.343684 -3.81759e-07 -0.999048 -0.0436196 -2.16548e-07 -0.999048 -0.0436194 0 -0.999048 -0.0436192 -7.83457e-08 -0.999048 -0.0436193 -1.14385e-07 -0.999048 -0.0436195 2.15696e-07 -0.999048 -0.0436193 1.91584e-07 -0.999048 -0.0436194 -2.76881e-07 -0.999048 -0.0436196 -3.34876e-07 -0.999048 -0.0436197 1.33461e-07 -0.999048 -0.0436195 -4.14289e-08 -0.999048 -0.0436191 -8.93651e-08 -0.999048 -0.0436192 3.88068e-07 -0.999048 -0.0436199 1.0109e-06 -0.999048 -0.0436192 0 -0.999048 -0.0436195 1.75319e-06 -0.999048 -0.0436196 1.93008e-06 -0.999048 -0.0436196 -1.67611e-07 -0.999048 -0.0436195 -2.98874e-08 -0.999048 -0.0436188 -5.29725e-07 -0.999048 -0.0436194 1 1.14059e-05 -2.86145e-06 1 -1.18719e-07 1.17074e-05 1 1.25999e-06 -1.14526e-05 1 0 0 1 3.10752e-05 -1.47878e-05 1 -2.31917e-06 -1.17659e-05 1 1.188e-05 2.14729e-06 1 -9.77496e-07 -2.03712e-05 1 -3.71414e-05 1.71503e-05 1 0 0 1 -2.01317e-05 7.24042e-05 1 0 0 1 0 0 1 0 0 1 3.07189e-05 1.66634e-05 1 -2.11664e-05 4.36046e-05 1 -3.64031e-05 3.47932e-05 1 -2.30721e-05 2.91204e-05 1 -2.38678e-05 2.91506e-05 1 -5.71616e-05 4.11442e-05 1 -0.000140517 -7.19669e-06 1 0 0 1 1.01593e-06 3.40769e-05 1 -6.31872e-05 -5.67236e-06 1 -4.14885e-05 -4.08484e-05 1 -2.74996e-05 -1.28503e-05 1 -2.36032e-05 -1.5512e-05 1 -2.26489e-05 -2.39856e-05 1 -1.26929e-05 -2.74602e-05 1 5.944e-05 4.51729e-05 1 -2.16706e-05 -2.97682e-05 1 -9.26617e-05 -0.000155363 1 -1.52955e-07 -1.05796e-05 1 -8.79033e-06 -2.78987e-05 1 1.00734e-05 3.19708e-05 1 8.5514e-06 2.88327e-05 1 0.000190023 0.000136934 1 -5.10987e-05 -3.68227e-05 1 -6.55538e-05 -5.68246e-05 1 1.18935e-05 2.47444e-05 1 1.7983e-05 4.71315e-05 1 -4.26701e-06 -1.11834e-05 1 2.27648e-05 -5.85413e-05 1 0 0 1 0 0 1 0 0 1 -3.1058e-05 -1.48785e-05 1 1.26571e-05 -2.74676e-05 1 2.79992e-05 -2.2134e-05 1 1.70749e-05 -1.89158e-05 1 1.20232e-05 -2.12874e-05 1 4.80829e-05 -2.4915e-05 1 8.95237e-05 1.68814e-05 1 0 0 1 1.00314e-06 -3.36934e-05 1 7.22902e-05 1.16067e-05 1 0.000103676 8.21327e-05 1 3.88943e-05 1.7664e-05 1 3.36239e-05 3.06067e-05 1 3.49764e-05 3.5583e-05 1 -2.09379e-05 6.81597e-05 1 0 0 1 0 0 1 0 0 1 3.64071e-05 -1.32842e-05 1 9.42133e-07 2.66076e-05 1 -1.1406e-05 -2.86117e-06 1 -4.7634e-07 1.29893e-05 1 -1.89338e-06 1.62764e-05 1 -4.45682e-05 5.10771e-05 1 1.54511e-05 -7.27517e-06 1 -1.71735e-05 -5.13747e-05 1 0 0 1 0 0 1 2.25549e-05 -2.33108e-05 1 -1.29915e-05 -1.92512e-05 1 0 2.70249e-05 1 0 -3.38839e-05 1 1.48872e-06 -2.73103e-05 1 -6.00396e-07 1.10142e-05 1 2.00251e-05 3.65035e-05 1 0 0 1 0 0 1 -1.36655e-05 6.9669e-05 1 1.00681e-05 2.42845e-05 1 5.68482e-06 9.53156e-06 0 -0.0646422 0.997909 0.0125145 -0.0519125 0.998573 0.02142 -0.047914 0.998622 0.00215774 -0.0386196 0.999252 1.09151e-06 -0.0305125 0.999534 -1.47657e-05 -0.0144528 0.999896 0 -0.0144567 0.999896 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -0.188969 -0.975092 -0.116129 -0.195906 -0.973469 -0.11823 -0.542086 -0.838751 -0.0513847 -0.55542 -0.829726 -0.0553546 -0.824574 -0.56552 0.0162733 -0.826308 -0.563003 0.0155795 -0.972889 -0.216855 0.0803754 -0.973099 -0.215982 0.0801876 -0.178408 -0.98327 -0.0367392 -0.181832 -0.98271 -0.0349109 -0.531877 -0.846437 0.0255387 -0.532078 -0.846306 0.0256756 -0.815624 -0.57236 0.0846239 -0.81632 -0.571263 0.0853266 -0.96658 -0.221645 0.128829 -0.966988 -0.219181 0.129976 -0.933107 -0.214573 0.288565 -0.773478 -0.364521 0.518513 -0.804945 -0.207575 0.555857 -0.837035 -0.123078 0.533128 -0.803098 -0.15031 0.576577 -0.803086 -0.0749401 0.591131 -0.804031 -0.0736544 0.590008 -0.784141 -0.0190421 0.620291 -0.922297 -0.211792 0.323283 -0.914657 -0.184388 0.359726 -0.906781 -0.199663 0.371327 -0.975137 -0.0619729 0.212759 -0.949898 -0.0914927 0.298869 -0.951153 -0.133 0.278604 -0.946747 -0.15798 0.280556 -0.979867 -0.0250993 0.198068 -0.98143 -0.0167334 0.191089 -0.982233 0.0256164 0.185911 -0.982485 0.00351483 0.18631 -0.982177 -0.00766039 0.187803 -0.976602 -0.033682 0.212402 -0.976043 -0.0342286 0.214868 -0.982325 -0.0609488 0.176985 -0.971819 -0.0989677 0.213945 -0.97643 -0.0914101 0.195522 -0.992177 -0.0651178 0.10651 -0.992442 -0.0711201 0.100005 -0.985982 -0.148893 0.0753091 -0.982066 -0.166522 0.0884085 -0.987786 -0.0634283 0.142323 -0.988327 -0.104368 0.110983 -0.977993 -0.147171 0.147889 -0.960188 -0.244017 0.135996 -0.967335 -0.246408 0.0595561 -0.953304 -0.288236 0.0901699 -0.804909 -0.541664 0.242327 -0.825429 -0.500577 0.260941 -0.719758 -0.545655 0.429196 -0.763176 -0.455229 0.458617 -0.683332 -0.512071 0.520423 -0.688175 -0.380927 0.617503 -0.690667 -0.376228 0.617602 -0.696819 -0.367488 0.615951 -0.66613 -0.397953 0.630796 -0.651396 -0.298187 0.697688 -0.713922 -0.232806 0.660392 -0.563843 -0.267805 0.781256 -0.627271 -0.206742 0.750859 -0.617243 -0.150781 0.772189 -0.619334 -0.12382 0.775302 -0.62105 -0.118486 0.774764 -0.616452 -0.106175 0.780201 -0.616494 -0.106522 0.780121 -0.620813 -0.0280961 0.783455 -0.672582 -0.46322 0.577114 -0.718641 -0.417121 0.556386 -0.698974 -0.392743 0.597652 -0.707335 -0.395438 0.585923 -0.726753 -0.33444 0.599983 -0.736229 -0.340576 0.584786 -0.792381 -0.298456 0.53203 -0.746905 -0.251353 0.615593 -0.648185 -0.0557354 0.759441 -0.656683 -0.0535679 0.752262 -0.680803 -0.0674875 0.729351 -0.682577 -0.0564579 0.72863 -0.740563 -0.0326544 0.671193 -0.73183 -0.0921311 0.67523 -0.747804 -0.0678154 0.660447 -0.74834 -0.068003 0.659821 -0.802153 -0.150119 0.57794 -0.902237 -0.417154 0.109324 -0.889623 -0.410786 0.199564 -0.898494 -0.328162 0.291578 -0.905718 -0.331376 0.26432 -0.906675 -0.276488 0.318582 -0.879982 -0.266879 0.392946 -0.885562 -0.243175 0.395785 -0.870855 -0.238852 0.429606 -0.863716 -0.177311 0.471759 -0.712683 -0.389688 0.583289 -0.698075 -0.415619 0.583054 -0.758027 -0.404604 0.511558 -0.741847 -0.448641 0.498382 -0.84343 -0.400878 0.357664 -0.971468 -0.0889651 0.219854 -0.956063 -0.137942 0.258681 -0.96741 -0.140059 0.210954 -0.939216 -0.181378 0.291504 -0.964085 -0.188598 0.187004 -0.93206 -0.232601 0.277778 -0.960284 -0.243075 0.136998 -0.918285 -0.332018 0.215678 -0.937869 -0.340137 0.0686247 -0.907645 -0.403495 0.115634 -0.61782 -0.124096 0.776466 -0.617888 -0.118345 0.777308 -0.624922 -0.021054 0.780403 -0.682724 -0.0135743 0.730551 -0.682587 -0.0134521 0.730681 -0.740941 -0.0158324 0.671383 -0.734979 -0.00876974 0.678033 -0.788443 -0.0151006 0.614923 -0.743195 -0.121998 0.657858 -0.784732 -0.172094 0.595466 -0.782252 -0.201373 0.589518 -0.823231 -0.265268 0.50192 -0.815694 -0.295597 0.497258 -0.860978 -0.313967 0.400177 -0.846537 -0.360492 0.391689 -0.855842 -0.364968 0.366515 -0.848302 -0.461174 0.260198 -0.865453 -0.470981 0.170787 -0.857319 -0.487745 0.164646 -0.771275 0.363397 0.522568 -0.953544 0.240329 0.18165 -0.706023 0.39503 0.587778 -0.981871 0.0551054 0.181361 -0.98241 0.00794708 0.186568 -0.982106 0.00676427 0.188209 -0.983262 0.00600131 0.182097 -0.983681 -0.00505742 0.179851 -0.97056 0.0931775 0.222106 -0.974734 0.0665943 0.213212 -0.9754 0.0544345 0.213614 -0.978016 0.0452531 0.203561 -0.982044 0.0208008 0.187503 -0.978293 0.0181943 0.206427 -0.981192 0.014808 0.192463 -0.962726 0.117062 0.243836 -0.950674 0.13697 0.278313 -0.950639 0.138377 0.277736 -0.93205 0.2143 0.292162 -0.900809 0.145685 0.409047 -0.930671 0.256658 0.260727 -0.868304 0.182616 0.461194 -0.856264 0.221699 0.466542 -0.829585 0.175023 0.530242 -0.826236 0.155003 0.541579 -0.799073 0.127868 0.58748 -0.805553 0.0738167 0.587907 -0.780723 0.045912 0.623188 -0.788527 0.00392804 0.614988 -0.623692 0.0500186 0.780068 -0.617294 0.127884 0.776269 -0.617489 0.119252 0.777487 -0.650673 0.0501447 0.757701 -0.680802 0.0674862 0.729352 -0.616175 0.105625 0.780494 -0.617098 0.109534 0.779225 -0.621776 0.12141 0.773728 -0.623005 0.117711 0.773311 -0.617633 0.142439 0.77346 -0.62191 0.209608 0.754515 -0.67095 0.167725 0.722284 -0.630117 0.207289 0.74832 -0.643101 0.308728 0.700792 -0.58605 0.355651 0.72805 -0.736115 0.333567 0.588954 -0.696025 0.372976 0.613546 -0.697075 0.392123 0.600271 -0.779361 0.586001 0.22181 -0.845084 0.459361 0.273533 -0.822052 0.552519 0.137672 -0.889785 0.410875 0.198655 -0.866863 0.49292 0.0746931 -0.930953 0.337144 0.140215 -0.914673 0.401768 0.0442305 -0.984516 0.148545 0.0930778 -0.983746 0.165103 0.070601 -0.985119 0.100059 0.139748 -0.976431 0.0914075 0.19552 -0.982389 0.0803865 0.168673 -0.689565 0.383945 0.614074 -0.690057 0.382331 0.614528 -0.693141 0.412632 0.591008 -0.684021 0.407098 0.605299 -0.760101 0.141643 0.63418 -0.780011 0.114172 0.615262 -0.748226 0.0678618 0.659964 -0.747628 0.0680833 0.660619 -0.738199 0.0825794 0.669509 -0.734551 0.0352545 0.677637 -0.682577 0.0564462 0.728631 -0.709914 0.413818 0.569892 -0.710582 0.413711 0.569137 -0.767661 0.3752 0.51954 -0.730022 0.336559 0.594808 -0.736227 0.340582 0.584785 -0.992197 0.0647058 0.106578 -0.992477 0.0711921 0.0996013 -0.993669 0.0738715 0.0846449 -0.977993 0.147171 0.147887 -0.960396 0.243133 0.13611 -0.878199 0.319367 0.356051 -0.920327 0.281561 0.271516 -0.941561 0.182029 0.283424 -0.792379 0.298459 0.532032 -0.795135 0.287375 0.534019 -0.833948 0.395872 0.384468 -0.846534 0.360499 0.39169 -0.957172 0.285796 0.046277 -0.963915 0.245208 0.103635 -0.959958 0.243945 0.137741 -0.918285 0.332027 0.215665 -0.916863 0.336481 0.214808 -0.873064 0.402686 0.274962 -0.882244 0.377926 0.280745 -0.824825 0.447951 0.34497 -0.806434 0.488697 0.332925 -0.762808 0.461607 0.452817 -0.730004 0.527435 0.434633 -0.794953 0.0159094 0.606462 -0.741027 0.00946121 0.671409 -0.734918 0.0155803 0.677977 -0.682724 0.013459 0.730552 -0.682586 0.0135929 0.730679 -0.616875 0.0220536 0.786752 -0.62104 0.00781417 0.78374 -0.974476 0.0595151 0.21646 -0.960218 0.187402 0.207029 -0.94577 0.136093 0.294955 -0.917589 0.280531 0.281662 -0.893464 0.204498 0.399877 -0.866508 0.316247 0.386202 -0.831422 0.227357 0.506997 -0.809527 0.318075 0.493451 -0.795724 0.205056 0.56989 -0.778242 0.237086 0.581489 -0.78473 0.172095 0.595468 -0.972926 0.216819 0.0800336 -0.973001 0.216386 0.0802845 -0.824679 0.565396 0.0152364 -0.825875 0.563609 0.0165864 -0.542807 0.837857 -0.05794 -0.554911 0.830489 -0.0486042 -0.189341 0.974661 -0.119109 -0.195548 0.973899 -0.115243 -0.966438 0.22173 0.129743 -0.967427 0.217962 0.128753 -0.815469 0.572438 0.0855872 -0.818538 0.568223 0.0843699 -0.531721 0.846503 0.0265596 -0.537256 0.843043 0.0251892 -0.178057 0.983424 -0.0342506 -0.185462 0.982004 -0.0356705 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.967319 0.253049 0.0161417 -0.960735 0.236762 0.144677 -0.974988 0.190465 0.114549 -0.965489 0.233537 0.115291 -0.96979 0.231954 0.075531 -0.974885 0.214866 0.0585731 -0.969669 0.238841 0.05194 -0.975796 0.218374 0.0116091 -0.971679 0.164928 0.169229 -0.97237 0.15931 0.170637 -0.96046 0.244783 0.132654 -0.962347 0.219358 0.160533 -0.950084 0.262409 0.168766 -0.957146 0.237961 0.165066 -0.964698 0.194253 0.177831 -0.965345 0.193091 0.175568 -0.179694 0.982963 -0.0386546 -0.528657 0.848532 -0.0227247 -0.813069 0.582163 -0.00251263 -0.187611 0.981424 -0.0401182 -0.18713 0.981882 -0.029842 -0.187213 0.981866 -0.0298543 -0.186187 0.982336 -0.0187077 -0.186276 0.982319 -0.0187056 -0.184754 0.98274 -0.00934483 -0.184475 0.982792 -0.0093657 -0.184385 0.982814 -0.00889329 -0.181231 0.983398 -0.00913907 -0.549575 0.835002 -0.0271923 -0.54825 0.836313 0.00168213 -0.5485 0.836149 0.00163463 -0.545424 0.837458 0.0343013 -0.545679 0.837292 0.0343045 -0.54128 0.838576 0.061693 -0.540532 0.839062 0.0616453 -0.540344 0.83911 0.0626341 -0.531431 0.844827 0.0620451 -0.836348 0.548118 -0.00937386 -0.834408 0.550089 0.0341356 -0.834696 0.549657 0.0340483 -0.829859 0.551649 0.083766 -0.830215 0.551115 0.0837568 -0.823641 0.553069 0.125424 -0.822763 0.554378 0.125401 -0.822546 0.554434 0.126571 -0.811826 0.57008 0.126283 -0.966362 0.251699 -0.0528371 -0.970338 0.210136 -0.119528 -0.939581 0.286689 -0.187077 -0.953704 0.229411 -0.194472 -0.795426 0.580434 -0.17434 -0.812969 0.553321 -0.181429 -0.516473 0.84582 -0.133585 -0.5326 0.834857 -0.139108 -0.175527 0.981574 -0.0755148 -0.181724 0.980291 -0.0775013 -0.176089 0.981703 -0.0724756 -0.176306 0.981659 -0.072539 -0.518216 0.846202 -0.124074 -0.518814 0.845809 -0.124257 -0.798095 0.581026 -0.15954 -0.798812 0.579971 -0.159791 -0.962454 0.210823 -0.170984 -0.951409 0.265819 -0.155439 -0.177674 0.982062 -0.0631418 -0.17815 0.981968 -0.0632538 -0.522814 0.846961 -0.0965514 -0.524133 0.846108 -0.0968814 -0.804903 0.581742 -0.117077 -0.806484 0.579455 -0.117541 -0.970182 0.210791 -0.119638 -0.963699 0.250069 -0.0935393 -0.967671 0.251821 -0.0141046 -0.972625 0.227223 -0.048694 -0.812843 0.579571 -0.0581626 -0.811132 0.582001 -0.0577915 -0.52859 0.84687 -0.0583352 -0.527183 0.847764 -0.0580905 -0.179691 0.982443 -0.0501642 -0.179192 0.982538 -0.0500847 -0.817774 0.423637 0.389585 -0.804748 0.45466 0.381661 -0.786893 0.481933 0.385409 -0.625643 0.558689 0.54446 -0.536323 0.635903 0.554965 -0.42882 0.645454 0.632062 -0.298413 0.686164 0.663422 -0.120848 0.747667 0.652985 -0.211541 0.683666 0.698464 -0.230869 0.656486 0.718141 -0.0306108 0.708216 0.705332 -0.0962403 0.336535 0.93674 -0.718176 0.473684 0.509752 -0.705155 0.55512 0.441132 -0.691475 0.525548 0.495642 -0.860316 0.338325 0.381304 -0.827054 0.434013 0.35723 -0.811768 0.406845 0.418939 -0.769313 0.456711 0.446736 -0.74981 0.499856 0.433507 -0.87494 0.335937 0.34875 -0.949866 0.202115 0.238546 -0.538918 0.472687 0.697233 -0.574759 0.464165 0.673946 -0.576625 0.461058 0.674484 -0.622122 0.441215 0.646756 -0.619819 0.446428 0.645389 -0.668808 0.413838 0.617603 -0.664539 0.428262 0.612356 -0.706535 0.389715 0.590703 -0.701297 0.418831 0.576856 -0.755677 0.369493 0.540766 -0.750312 0.453484 0.481024 -0.918904 0.291551 0.265734 -0.928882 0.260388 0.263396 -0.929961 0.230486 0.286441 -0.896103 0.292365 0.33395 -0.867867 0.344072 0.35836 -0.130891 0.628517 0.766703 -0.161265 0.621659 0.766508 -0.157517 0.266319 0.950927 -0.102811 0.270427 0.957235 -0.133479 0.219285 0.966487 -0.121817 0.222694 0.967248 -0.113904 0.184327 0.976242 -0.154049 0.328415 0.931887 -0.143695 0.368526 0.918445 -0.138291 0.412395 0.900448 -0.157501 0.40525 0.900537 -0.144989 0.47783 0.866405 -0.146739 0.477073 0.866527 -0.165575 0.532018 0.830386 -0.303789 0.611834 0.730323 -0.432883 0.581283 0.689001 -0.480958 0.560214 0.674418 -0.627886 0.519486 0.579563 -0.81964 0.370548 0.436904 -0.329555 0.354297 0.875139 -0.370341 0.351534 0.859809 -0.352835 0.380737 0.85472 -0.399725 0.370285 0.838516 -0.382058 0.410471 0.827977 -0.428263 0.392384 0.814018 -0.414377 0.439719 0.79683 -0.451634 0.418654 0.78788 -0.438754 0.489801 0.753386 -0.546799 0.432016 0.717198 -0.485019 0.48634 0.726794 -0.177507 0.539582 0.823008 -0.164759 0.55796 0.813348 -0.00336263 0.0608028 0.998144 0.00188478 0.0062048 0.999979 0 0.0095518 0.999954 -0.980785 -0.19509 0 -0.980785 -0.19509 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -1 0 0 -1 0 0 -0.19509 0.980785 0 -0.19509 0.980785 0 -0.555571 0.831469 0 -0.555571 0.831469 0 -0.83147 0.55557 0 -0.83147 0.55557 0 -0.980785 0.19509 0 -0.980785 0.19509 0 -0.0491262 -0.0964248 0.994127 0.0271919 -0.0330639 0.999083 0 -0.00811726 0.999967 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.00281662 0.999996 0.00511693 0.0101719 0.999935 0.0253422 0.0211272 0.999456 -7.96069e-06 0.014456 0.999896 7.15188e-06 0.0414938 0.999139 0.0206184 0.0479189 0.998638 0 0.0620432 0.998074 -0.964001 -0.250228 -0.0899299 -0.965573 -0.229434 -0.12259 -0.959121 -0.228702 -0.166684 -0.175378 -0.981537 -0.0763433 -0.181871 -0.980326 -0.0767024 -0.515959 -0.845698 -0.136313 -0.533105 -0.83497 -0.136474 -0.794586 -0.580231 -0.178787 -0.813793 -0.553511 -0.177106 -0.953703 -0.229414 -0.194471 -0.176313 -0.98166 -0.0725114 -0.176089 -0.9817 -0.072504 -0.518827 -0.845815 -0.124159 -0.518194 -0.846202 -0.12417 -0.798838 -0.579983 -0.159619 -0.798064 -0.581022 -0.159712 -0.962491 -0.210655 -0.170982 -0.94125 -0.280611 -0.1879 -0.178155 -0.981971 -0.063193 -0.177668 -0.982059 -0.0632029 -0.52415 -0.846122 -0.0966667 -0.522783 -0.846956 -0.0967655 -0.806521 -0.579481 -0.11716 -0.804854 -0.581733 -0.117458 -0.960628 -0.250431 -0.120327 -0.955902 -0.248998 -0.155727 -0.179692 -0.982446 -0.0501011 -0.179188 -0.982536 -0.0501488 -0.528589 -0.846886 -0.0581094 -0.527166 -0.847759 -0.0583193 -0.812844 -0.579611 -0.0577554 -0.811108 -0.581994 -0.0582027 -0.966957 -0.250087 -0.0494946 -0.966498 -0.251801 -0.0497674 -0.961031 -0.220751 0.166398 -0.18008 -0.983458 -0.0195596 -0.185302 -0.982235 -0.0296171 -0.183612 -0.982537 -0.0301337 -0.184006 -0.98217 -0.0385171 -0.179696 -0.982924 -0.03962 -0.179225 -0.983748 -0.0108461 -0.181746 -0.983261 -0.0128881 -0.182718 -0.982984 -0.0188734 -0.176413 -0.984256 -0.0108948 -0.178588 -0.983876 -0.00966338 -0.177836 -0.984011 -0.00987367 -0.960506 -0.235833 0.147683 -0.960198 -0.245931 0.132431 -0.971909 -0.163464 0.169332 -0.963713 -0.203407 0.172869 -0.963137 -0.209742 0.168448 -0.962706 -0.235205 0.133703 -0.982795 -0.138939 0.121698 -0.968876 -0.225509 0.102102 -0.968725 -0.241508 0.0569688 -0.973134 -0.22187 0.0615156 -0.967384 -0.252951 0.013554 -0.970935 -0.238733 0.0170845 -0.813201 -0.581854 -0.0122255 -0.528686 -0.848353 -0.0280808 -0.834041 -0.551702 -0.000560992 -0.832384 -0.553172 0.0337314 -0.832664 -0.55274 0.0339007 -0.827859 -0.554718 0.0832945 -0.828188 -0.554205 0.0834371 -0.821607 -0.556156 0.125113 -0.820793 -0.557445 0.124715 -0.820136 -0.557613 0.128237 -0.81021 -0.572967 0.123569 -0.544285 -0.838596 -0.0226096 -0.543165 -0.839625 0.00111275 -0.543396 -0.839475 0.00120498 -0.540361 -0.840768 0.0334617 -0.540609 -0.840605 0.0335388 -0.536238 -0.841878 0.0607411 -0.535539 -0.842342 0.0604864 -0.535103 -0.842451 0.0627798 -0.52669 -0.847954 0.0597557 0.500013 -2.30775e-05 0.866018 0.499992 4.64938e-06 0.86603 0.499997 0 0.866027 0.499992 -4.64938e-06 0.86603 0.500013 2.30818e-05 0.866018 0.667828 0.730996 0.140181 0.662788 0.734041 0.14797 0.705589 0.705588 0.0655017 0.663906 0.622772 0.413985 0.628302 0.63168 0.454111 0.68 0.645663 0.347447 0.695603 0.652536 0.300556 0.702021 0.679993 0.211603 0.610862 0.353181 0.708598 0.581662 0.434129 0.687897 0.571409 0.454309 0.683443 0.647521 0.478984 0.592699 0.665807 0.538848 0.516085 0.514637 0.0482418 0.85605 0.461392 0.167092 0.87132 0.538557 0.191947 0.820434 0.592559 0.288573 0.752064 0.530875 0.107806 -0.840565 0.468367 0.166403 -0.867723 0.58159 0.254221 -0.772738 0.607057 0.33889 -0.718773 0.673674 0.572268 -0.467624 0.659863 0.517525 -0.544746 0.605864 0.440416 -0.662543 0.551632 0.503761 -0.664776 0.594699 0.399959 -0.697399 0.619413 0.672059 -0.405788 0.644507 0.636748 -0.423276 0.694194 0.648151 -0.313042 0.706398 0.706396 -0.0447966 0.671735 0.727535 -0.139518 0.693821 0.70073 -0.166101 0.699586 0.667044 -0.256187 0.500014 -2.28183e-05 -0.866017 0.499996 1.10141e-06 -0.866028 0.499999 -1.27881e-06 -0.866026 0.499997 0 -0.866027 0.500014 2.28183e-05 -0.866017 0.701574 -0.677014 -0.222363 0.682496 -0.71097 -0.169473 0.667828 -0.730996 -0.140181 0.662787 -0.734042 -0.147972 0.705589 -0.705588 -0.0655015 0.663906 -0.622772 -0.413985 0.644998 -0.627793 -0.435722 0.695602 -0.652536 -0.300556 0.592557 -0.288569 -0.752066 0.613787 -0.364753 -0.700158 0.571409 -0.454309 -0.683443 0.651535 -0.480168 -0.587317 0.665937 -0.541941 -0.512667 0.514639 -0.0482414 -0.856049 0.461393 -0.167092 -0.871319 0.487651 -0.175568 -0.855203 0.571759 -0.249772 -0.781477 0.530873 -0.107807 0.840566 0.468365 -0.166403 0.867723 0.58159 -0.254221 0.772739 0.607057 -0.338891 0.718773 0.57435 -0.478192 0.66442 0.605864 -0.440416 0.662543 0.661394 -0.519876 0.540635 0.66935 -0.730259 0.136721 0.671735 -0.727535 0.139518 0.706398 -0.706396 0.0447965 0.697441 -0.685101 0.210267 0.699586 -0.667044 0.256187 0.679438 -0.611044 0.406189 0.588846 -0.717133 0.372801 0.671552 -0.576801 0.465102 0.521053 0.07091 -0.850574 0.393287 0.301092 -0.868717 0.569614 0.153388 -0.807473 0.610976 0.429632 -0.664925 0.604205 0.440703 -0.663866 0.658254 0.512053 -0.551818 0.674693 0.577258 -0.459959 0.648668 0.634071 -0.420932 0.692281 0.642536 -0.328474 0.700814 0.700812 -0.133124 0.675394 0.729856 -0.105613 0.700955 0.673501 -0.234646 0.500006 -1.22233e-05 -0.866022 0.499994 3.90878e-06 -0.866029 0.500005 -4.70668e-06 -0.866023 0.499997 0 -0.866027 0.500006 1.22149e-05 -0.866022 0.705405 -0.705404 -0.0693506 0.6756 -0.724316 -0.137586 0.709225 -0.670351 -0.218242 0.681803 -0.640399 -0.353603 0.648331 -0.634311 -0.421091 0.665141 -0.597989 -0.447211 0.664552 -0.486267 -0.567376 0.58489 -0.448603 -0.675765 0.608015 -0.381166 -0.696441 0.542676 -0.156752 -0.825186 0.485161 -0.141392 -0.862918 0.595326 -0.281076 -0.752717 0.521053 -0.07091 0.850574 0.393287 -0.301092 0.868717 0.569614 -0.153388 0.807473 0.610976 -0.429632 0.664925 0.604205 -0.440702 0.663866 0.658254 -0.512054 0.551818 0.674693 -0.577258 0.459959 0.648668 -0.634071 0.420932 0.692281 -0.642536 0.328474 0.700814 -0.700813 0.133123 0.675394 -0.729855 0.105614 0.700955 -0.673501 0.234646 0.500006 1.22233e-05 0.866022 0.499997 -2.78699e-07 0.866027 0.499998 3.35595e-07 0.866027 0.499997 0 0.866027 0.500006 -1.22149e-05 0.866022 0.705405 0.705404 0.0693483 0.6756 0.724317 0.137587 0.709225 0.670351 0.218243 0.681802 0.640399 0.353603 0.64833 0.634311 0.42109 0.665141 0.597988 0.447211 0.664552 0.486267 0.567376 0.58489 0.448603 0.675766 0.608015 0.381166 0.696441 0.542676 0.156752 0.825186 0.48516 0.141391 0.862919 0.595326 0.281077 0.752717 0.705405 -0.705404 -0.0693505 0.675601 -0.724316 -0.137587 0.709225 -0.670351 -0.218242 0.681803 -0.640399 -0.353603 0.648331 -0.634311 -0.421091 0.665141 -0.597987 -0.447212 0.664552 -0.486267 -0.567376 0.58489 -0.448603 -0.675765 0.608016 -0.381165 -0.696441 0.542676 -0.156752 -0.825186 0.485161 -0.141392 -0.862918 0.595327 -0.281077 -0.752716 0.521053 -0.0709102 0.850574 0.393287 -0.301092 0.868717 0.569614 -0.153388 0.807473 0.610976 -0.429632 0.664925 0.604205 -0.440702 0.663866 0.658255 -0.512055 0.551816 0.674694 -0.577258 0.459959 0.648668 -0.634071 0.420932 0.692281 -0.642536 0.328475 0.700814 -0.700812 0.133124 0.675394 -0.729855 0.105614 0.700955 -0.673501 0.234646 0.500006 1.22233e-05 0.866022 0.499997 -2.78701e-07 0.866027 0.499998 3.35593e-07 0.866027 0.499997 0 0.866027 0.500006 -1.22149e-05 0.866022 0.705405 0.705404 0.0693494 0.6756 0.724317 0.137587 0.709225 0.67035 0.218243 0.681802 0.640399 0.353603 0.648331 0.634311 0.42109 0.665141 0.597987 0.447211 0.664552 0.486267 0.567375 0.58489 0.448602 0.675766 0.608015 0.381166 0.696441 0.542676 0.156752 0.825186 0.48516 0.141391 0.862919 0.595326 0.281077 0.752717 0.521053 0.07091 -0.850574 0.393287 0.301092 -0.868717 0.569614 0.153388 -0.807473 0.610976 0.429632 -0.664925 0.604205 0.440702 -0.663866 0.658254 0.512052 -0.551819 0.674693 0.577258 -0.459959 0.648668 0.634071 -0.420932 0.692281 0.642536 -0.328473 0.700814 0.700812 -0.133124 0.675394 0.729855 -0.105614 0.700955 0.673501 -0.234646 0.500006 1.22233e-05 -0.866022 0.499994 -3.93898e-06 -0.866029 0.499999 0 -0.866026 0.499994 3.93896e-06 -0.866029 0.500007 -1.22401e-05 -0.866022 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.956153 -0.110052 0.271404 -0.993311 -0.0370577 0.109365 -0.999002 -0.0156556 0.0418381 -0.999981 -0.00236039 0.00567656 -0.999829 -0.00688255 0.0171933 -0.999517 -0.0112419 0.0289839 -0.977378 -0.0656142 0.201066 -0.949027 -0.0346942 0.31328 -0.966807 -0.0364756 0.252893 -0.979943 -0.0449946 0.19413 -0.984427 -0.0422424 0.170645 -0.984512 -0.0486004 0.168448 -0.983304 -0.0537043 0.173863 -0.985747 -0.0307958 0.165391 -0.984513 -0.0348461 0.171812 -0.984192 -0.0517216 0.169387 -0.996653 -0.00926131 0.0812195 -0.865962 -0.0785245 0.493906 -0.799285 -0.0616898 0.597778 -0.911518 -0.0946358 0.400224 -0.871875 -0.155931 0.46424 -0.81339 -0.219253 0.538818 -0.862458 -0.191139 0.468649 -0.862441 -0.140415 0.486291 -0.862237 -0.140702 0.486571 -0.862289 -0.0925864 0.497882 -0.862671 -0.0921033 0.497309 -0.862866 -0.0762781 0.499644 -0.919595 -0.0434632 0.390457 -0.0830264 0.994262 0.0674529 -0.0830378 0.994266 0.067384 -0.0944549 0.98634 0.134948 -0.248008 0.947062 0.203875 -0.409036 0.851396 0.328351 -0.421085 0.842974 0.334788 -0.565806 0.680773 0.4652 -0.552277 0.705852 0.44358 -0.691573 0.458679 0.55798 -0.684633 0.472404 0.555079 -0.760023 0.235377 0.605774 -0.760144 0.234545 0.605945 -0.77406 -0.110444 0.623405 -0.784943 -0.0466027 0.617813 0.0112873 0.983302 0.181631 -0.658246 -0.251109 0.709688 -0.466093 -0.20708 0.86016 -0.300712 -0.0997908 0.94848 -0.259314 -0.049603 0.964518 -0.316652 0.0262156 0.948179 -0.483743 0.352295 0.801175 -0.395314 0.477985 0.784383 -0.550157 0.540004 0.636964 -0.616415 0.326845 0.716383 -0.529472 0.679547 0.507815 -0.692821 -0.226967 0.684459 -0.681412 0.174141 0.710881 -0.737031 0.186381 0.649652 -0.720663 0.235076 0.652214 -0.692645 -0.250064 0.676543 -0.71001 -0.181175 0.680486 -0.725572 -0.174996 0.665524 -0.744986 -0.0773246 0.662583 -0.752419 -0.110397 0.649368 -0.618343 -0.31913 0.718197 -0.334216 0.150789 0.930356 -0.279204 0.0938199 0.955638 -0.487889 -0.138835 0.861794 -0.450555 -0.188187 0.872689 -0.607586 -0.305533 0.733137 -0.167731 0.924584 0.342069 -0.0355465 0.879834 0.473949 0.130525 0.920731 0.367719 -0.106853 0.709457 0.696601 -0.0483647 0.670135 0.740662 -0.123002 0.00937437 0.992362 -0.056429 0.0914885 0.994206 -0.131177 0.190774 0.97283 -0.0793121 0.275243 0.958098 -0.121508 0.372866 0.919895 -0.0797478 0.455838 0.886483 -0.134069 0.502218 0.854285 -0.087883 0.607955 0.789093 -0.360781 0.683526 0.634531 -0.265948 0.630212 0.729455 -0.11802 0.763234 0.635252 -0.308181 0.837671 0.450924 -0.147832 0.935493 0.320934 -0.608364 -0.25568 0.751346 -0.66324 -0.299062 0.686057 -0.501582 0.0314345 0.864539 -0.609737 0.106842 0.78537 -0.558659 0.194688 0.806224 -0.673148 0.240145 0.69943 -0.591004 0.39272 0.704617 -0.672903 0.410739 0.61522 -0.638964 0.471284 0.607961 -0.614736 -0.307917 0.726145 -0.624782 -0.294547 0.723111 -0.473157 -0.108998 0.874209 -0.532865 -0.0464192 0.844926 -0.214744 0.410103 0.886398 -0.383006 0.282302 0.879552 -0.254955 0.415833 0.872973 -0.379818 0.50154 0.777301 -0.259765 0.637664 0.725195 -0.443848 0.710123 0.546557 -0.313734 0.832622 0.456412 -0.181068 -0.0595219 0.981668 -0.477518 -0.160336 0.863869 -0.618243 -0.284216 0.732801 -0.496062 -0.222533 0.839287 -0.517348 -0.168358 0.839051 -0.165906 -0.0561101 0.984544 -0.0957858 -0.0438125 0.994437 -0.174934 -0.0750415 0.981716 -0.284835 -0.131304 0.949541 -0.464245 -0.210787 0.860259 -0.479683 -0.15256 0.864077 -0.561181 -0.181624 0.80752 -0.171051 -0.34235 0.923871 -0.300132 -0.848649 0.435564 -0.0942689 -0.944171 0.315679 -0.129152 -0.642304 0.75549 -0.162977 -0.467171 0.869017 -0.0743142 -0.582654 0.809316 -0.227534 -0.441971 0.867693 -0.280149 -0.500575 0.81911 -0.24119 -0.558428 0.793716 -0.31465 -0.609825 0.727399 -0.242143 -0.718929 0.651543 -0.369878 -0.755534 0.540702 -0.634957 -0.239152 0.7346 -0.620844 -0.207008 0.756109 -0.616269 -0.218384 0.756651 -0.580846 -0.208071 0.786972 -0.601653 -0.168923 0.780691 -0.574341 -0.19089 0.796049 -0.0662645 -0.981864 0.177631 -0.15848 -0.957538 0.240842 -0.0561429 -0.942517 0.329407 -0.167483 -0.89795 0.406983 -0.0177759 -0.886994 0.461438 -0.0125383 -0.889139 0.457465 -0.122454 -0.685021 0.718158 0.0832231 -0.737562 0.670131 -0.488428 -0.199836 0.849413 -0.476677 -0.151459 0.865933 -0.0921415 -0.128775 0.987384 -0.158041 -0.0855214 0.983722 -0.203538 -0.195161 0.959419 -0.111433 -0.335416 0.935456 -0.437344 -0.212065 0.873933 -0.49307 -0.222951 0.840937 -0.443959 -0.350644 0.82459 -0.411461 -0.377821 0.829428 -0.473993 -0.421902 0.772871 -0.427113 -0.482662 0.7646 -0.523528 -0.510829 0.681889 -0.478068 -0.581078 0.658634 -0.714706 -0.232399 0.659687 -0.133942 -0.981984 0.133291 -0.69335 -0.313182 0.648986 -0.595457 -0.578541 0.557424 -0.591828 -0.584509 0.555057 -0.0950799 -0.992708 0.0741025 -0.200169 -0.960482 0.19341 -0.382302 -0.848786 0.365251 -0.34637 -0.883882 0.314292 -0.451502 -0.780775 0.431897 -0.119989 -0.984094 0.131006 -0.110631 -0.986809 0.118189 -0.360037 -0.850146 0.38422 -0.36148 -0.848687 0.386087 -0.555811 -0.582526 0.593075 -0.55749 -0.57848 0.595454 -0.664012 -0.239038 0.708483 -0.664739 -0.232416 0.710004 -9.58687e-07 0.999048 0.0436197 0 0.999048 0.0436198 -1.04269e-06 0.999048 0.0436191 4.03021e-07 0.999048 0.0436195 1.63734e-06 0.999048 0.0436197 -6.36806e-06 0.999048 0.0436187 0 0.999048 0.0436194 0 0.999048 0.0436194 4.49045e-07 0.999048 0.0436194 6.45461e-08 0.999048 0.0436194 1.90966e-07 0.999048 0.0436177 0 0.999048 0.0436232 -0.0016711 0.183158 0.983082 -0.0143083 0.129431 0.991485 0 0.0615395 0.998105 0 0.990359 0.138521 -0.0176906 0.984842 0.172547 0.00501477 0.956568 0.291465 -0.0131507 0.911373 0.411372 -0.0336742 0.890501 0.453733 -0.00565935 0.854287 0.519771 -0.00271214 0.625423 0.780281 -0.0348159 0.705182 0.708171 -0.0243165 0.691308 0.722151 1.11423e-06 0.774577 0.63248 4.85525e-08 0.812098 0.583521 0.00132779 0.302408 0.953178 -0.0223826 0.412558 0.910656 -0.023378 0.41458 0.909712 -1.08579e-06 0.516914 0.856037 2.44348e-07 0.568854 0.822439 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.169167 -0.97598 0.137277 -0.0740791 -0.989891 0.120948 -0.0830264 -0.994262 0.0674529 -0.780432 0.110433 0.61541 -0.779225 0.0222409 0.626349 -0.747073 -0.298336 0.594035 -0.754991 -0.235387 0.612031 -0.674534 -0.507097 0.536523 -0.685953 -0.472402 0.553448 -0.570982 -0.680774 0.458831 -0.453278 -0.799521 0.394087 -0.418218 -0.842987 0.33833 -0.249454 -0.947064 0.202096 -0.993872 0.0752224 0.0809929 -0.974037 0.0369653 0.223349 -0.946254 0.0346566 0.321563 -0.984559 0.0198327 0.173927 -0.984539 0.0320555 0.172208 -0.984919 0.0327522 0.169885 -0.984093 0.0492498 0.170691 -0.984524 0.0499541 0.167979 -0.999526 0.0103667 0.0289876 -0.999828 0.00702007 0.0171916 -0.99998 0.0026728 0.00566515 -0.886442 0.163739 0.432909 -0.925431 0.142785 0.350985 -0.984523 0.0652785 0.162646 -0.965157 0.0501566 0.256818 -0.995692 0.0342647 0.0861582 -0.993886 0.0172418 0.109059 -0.999045 0.012631 0.041835 -0.81388 0.218989 0.538185 -0.780321 0.0641624 0.622079 -0.821181 0.0670887 0.56671 -0.862762 0.16679 0.477309 -0.862447 0.140602 0.486227 -0.862242 0.14051 0.486617 -0.862282 0.0922244 0.497961 -0.862665 0.0924715 0.497251 -0.862844 0.0607817 0.501803 -0.883061 0.0829252 0.461873 -0.171044 0.964525 0.201088 -0.0597528 0.996079 0.0652395 -0.131276 0.982888 0.129218 -0.382762 0.848779 0.364783 -0.356346 0.875026 0.327639 -0.5813 0.578714 0.571997 -0.549834 0.657452 0.515208 -0.669452 0.399172 0.626495 -0.71475 0.232398 0.659639 -0.71492 0.231179 0.659883 -0.663632 0.239043 0.708838 -0.665116 0.23242 0.709649 -0.555512 0.582531 0.59335 -0.557783 0.578487 0.595173 -0.359869 0.850149 0.38437 -0.36164 0.84869 0.385929 -0.110631 0.986809 0.118189 -0.133942 0.981984 0.133291 -0.479963 0.151544 0.8641 -0.620822 0.219596 0.752567 -0.477769 0.58106 0.658867 -0.286626 0.847604 0.446557 -0.230992 0.550236 0.802424 -0.188194 0.468237 0.863329 -0.16338 0.383424 0.909007 -0.133669 0.328257 0.935083 -0.174577 0.29592 0.939124 -0.156079 0.133855 0.978633 -0.143787 0.137286 0.98004 -0.580741 0.207863 0.787104 -0.473741 0.421537 0.773225 -0.411443 0.377479 0.829593 -0.290037 0.51131 0.808975 -0.239076 0.45483 0.857888 0.0229922 0.990278 0.137193 -0.164587 0.918789 0.3588 -0.0957156 0.959391 0.265343 -0.223999 0.885507 0.407065 -0.347586 0.749938 0.562829 -0.0910001 0.724696 0.683033 -0.077281 0.714833 0.695012 -0.0461847 0.705013 0.707689 -0.0397491 0.712548 0.700497 -0.145959 0.498418 0.854562 -0.613843 0.239012 0.752376 -0.523437 0.510407 0.682275 -0.426966 0.482055 0.765064 -0.242061 0.718077 0.652512 -0.31445 0.609175 0.72803 -0.0814854 0.844021 0.530083 -0.0817046 0.843838 0.530341 0.0566162 0.916579 0.395826 -0.51122 0.140939 0.847815 -0.453935 0.17316 0.874047 -0.491757 0.186253 0.850579 -0.476557 0.212668 0.853033 -0.492526 0.223438 0.841127 -0.482117 0.245557 0.84099 -0.516911 0.284427 0.807406 -0.550474 0.216339 0.806335 -0.606133 0.159851 0.779134 -0.618243 0.284216 0.732801 -0.496062 0.222533 0.839287 -0.173261 0.0792495 0.981682 -0.0535838 0.0100565 0.998513 -0.145662 0.0600955 0.987507 -0.284835 0.131304 0.949541 -0.464245 0.210787 0.860259 -0.166289 0.0546635 0.984561 -0.180564 0.0608013 0.981682 -0.478717 0.156046 0.863991 -0.515905 0.172195 0.839161 -0.638939 -0.471283 0.607988 -0.738379 0.169715 0.652681 -0.683702 0.233555 0.691378 -0.649461 0.257042 0.715633 -0.307865 0.0853046 0.947598 -0.113046 -0.968357 0.222497 -0.529441 -0.679545 0.507849 -0.209969 -0.945278 0.249726 -0.419562 -0.77866 0.466536 -0.344423 -0.762024 0.548354 -0.511612 -0.526149 0.679279 -0.446035 -0.50003 0.74231 -0.046189 -0.992579 0.112492 -0.268437 -0.89813 0.348287 -0.191856 -0.881316 0.431825 -0.385431 -0.691324 0.611158 -0.302091 -0.657531 0.690213 -0.437923 -0.519282 0.733873 -0.223045 -0.348553 0.910363 -0.238253 -0.328498 0.913961 0.0858564 -0.640377 0.763247 -0.766713 0.110442 0.632419 -0.737072 0.161801 0.65616 -0.697164 -0.234518 0.677468 -0.710299 -0.136026 0.690631 -0.501581 -0.658075 0.561563 -0.108084 -0.0965334 0.989444 0.173292 -0.374068 0.911067 -0.198975 -0.0461188 0.978919 -0.0646983 -0.183859 0.980821 -0.393106 0.124398 0.911039 -0.279284 -0.0943258 0.955564 -0.0572327 -0.724719 0.686664 -0.109902 -0.738263 0.6655 -0.188146 -0.779492 0.597489 -0.0842032 -0.826817 0.556132 -0.199959 -0.873023 0.4448 0.160909 -0.972077 0.170804 -0.0304046 -0.949471 0.312379 -0.468933 0.201346 0.859978 -0.447324 0.192106 0.873497 -0.4933 0.131278 0.859896 -0.467861 0.114041 0.876413 -0.532827 0.0462395 0.84496 -0.381236 -0.200942 0.902376 -0.270667 -0.314102 0.909989 -0.100493 -0.515536 0.850955 -0.0485021 -0.669963 0.740809 -0.098969 -0.704165 0.703105 -0.226073 -0.604729 0.763671 -0.334088 -0.462106 0.821489 -0.402433 -0.406445 0.820274 -0.571272 -0.0790773 0.816942 -0.501675 -0.0314011 0.864486 -0.652476 0.269255 0.708363 -0.62646 0.296705 0.720773 -0.62437 0.295193 0.723204 -0.613266 0.309919 0.726536 -0.606672 0.307321 0.733146 -0.376324 -0.841266 0.38814 -0.556629 -0.61233 0.561441 -0.484898 -0.596499 0.63958 -0.61416 -0.333042 0.715466 -0.548663 -0.306935 0.777663 -0.656431 -0.114267 0.745682 -0.54022 -0.266056 0.798359 -0.687703 0.189636 0.700787 -0.712103 0.280132 0.643766 6.344e-07 -0.568638 0.822588 0 -0.0338998 0.999425 0 -0.990359 0.138521 -0.0176906 -0.984842 0.172547 -9.90052e-06 -0.414693 0.909961 -0.0999183 -0.543411 0.833499 -0.063016 -0.497231 0.865327 -0.0165156 -0.394885 0.918582 -0.00576348 -0.332671 0.943025 0.0224011 -0.129412 0.991338 -0.0275908 -0.21037 0.977232 -0.00564375 -0.0835243 0.99649 -0.0128657 -0.691456 0.722304 -0.0363543 -0.716353 0.696791 -0.00227655 -0.61761 0.786481 -8.02359e-08 -0.964096 0.265553 6.22414e-07 -0.938631 0.344923 -0.0289843 -0.890632 0.4538 -7.66426e-06 -0.867753 0.496996 1.17311e-06 -0.79078 0.612101 -9.61036e-07 -0.999048 0.0436196 6.01428e-07 -0.999048 0.0436194 0 -0.999048 0.0436232 1.90966e-07 -0.999048 0.0436177 7.67929e-08 -0.999048 0.0436193 -1.55252e-07 -0.999048 0.0436194 1.08793e-06 -0.999048 0.0436193 -1.87798e-07 -0.999048 0.0436194 -6.56015e-06 -0.999048 0.0436185 1.67435e-06 -0.999048 0.0436196 3.75642e-07 -0.999048 0.0436194 4.7097e-09 -0.999048 0.0436191 0 -0.999048 0.0436191 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.650318 0.590134 0.47836 -0.645992 0.592211 0.481643 -0.618803 0.618184 0.484698 -0.599476 0.637447 0.484035 -0.598501 0.631794 0.492578 -0.473447 0.507436 0.71997 -0.469834 0.496899 0.729621 -0.301144 0.328193 0.895322 -0.294083 0.312255 0.903334 -0.105505 0.123461 0.986725 -0.0967826 0.106242 0.989619 -0.657716 0.570946 0.491356 -0.655102 0.590181 0.471728 -0.518749 0.498876 0.694278 -0.505812 0.47416 0.720643 -0.33374 0.34881 0.875756 -0.313061 0.316005 0.895619 -0.123342 0.171781 0.977383 -0.0962604 0.132907 0.986443 -0.506857 0.648812 0.567573 -0.555599 0.637242 0.534072 -0.592181 0.6376 0.492735 -0.572722 0.643182 0.508239 -0.574439 0.653644 0.492717 -0.0887241 0.101298 0.990892 -0.293279 0.301793 0.907143 -0.268909 0.293099 0.917486 -0.473797 0.477224 0.740117 -0.442929 0.466485 0.76564 -0.596724 0.598739 0.534258 -0.595584 0.598517 0.535777 -0.0868209 0.100767 0.991115 -0.090165 0.106501 0.990216 -0.273265 0.31985 0.907206 -0.275838 0.325186 0.904526 -0.436826 0.510862 0.740407 -0.440158 0.518723 0.732931 -0.534298 0.625577 0.568488 -0.532894 0.647505 0.544758 -0.090226 0.107847 0.990065 -0.0919798 0.110535 0.989607 -0.273039 0.327493 0.904543 -0.274462 0.329773 0.903283 -0.435628 0.522483 0.732966 -0.437503 0.525709 0.729535 -0.55287 0.663127 0.504577 -0.563123 0.684313 0.463259 -0.596316 0.715518 0.363924 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 -7.17422e-05 0.999999 -0.00162119 0 1 0 0 1 0 0 1 0 -0.532895 -0.647509 0.544752 -0.576093 -0.713719 0.398398 -0.565348 -0.678615 0.468896 -0.574442 -0.653641 0.492717 -0.533877 -0.633236 0.560345 -0.609342 -0.574989 0.545977 -0.0887178 -0.101296 0.990893 -0.270854 -0.279876 0.921036 -0.285859 -0.308535 0.907244 -0.447147 -0.453609 0.770908 -0.464759 -0.48566 0.74036 -0.582757 -0.587185 0.56179 -0.59546 -0.636605 0.490062 -0.573952 -0.642843 0.507279 -0.53303 -0.624143 0.571249 -0.434813 -0.512631 0.74037 -0.442184 -0.51703 0.732907 -0.27211 -0.320879 0.90719 -0.277012 -0.324216 0.904516 -0.0847495 -0.100189 0.991352 -0.090076 -0.104545 0.990433 -0.092263 -0.110282 0.989609 -0.0902541 -0.108467 0.989995 -0.274738 -0.329529 0.903288 -0.272753 -0.327728 0.904544 -0.437981 -0.525295 0.729546 -0.435138 -0.522888 0.732969 -0.554891 -0.665531 0.499164 -0.502858 -0.648947 0.570966 -0.657715 -0.570945 0.491358 -0.618776 -0.618212 0.484697 -0.65545 -0.587835 0.474168 -0.109619 -0.119244 0.986795 -0.0923314 -0.110221 0.989609 -0.305561 -0.323697 0.895462 -0.289454 -0.316424 0.903378 -0.476939 -0.503947 0.720115 -0.466239 -0.500189 0.72968 -0.60188 -0.6351 0.484136 -0.596074 -0.634055 0.492616 -0.131891 -0.160344 0.97821 -0.0862868 -0.143052 0.985947 -0.342161 -0.337657 0.876877 -0.303337 -0.325964 0.895396 -0.526651 -0.488771 0.695515 -0.497012 -0.483421 0.720613 -0.655818 -0.590624 0.470176 -0.64639 -0.59182 0.48159 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.0454212 0.998968 -0.00434678 -0.175796 0.984417 0.00168007 -0.539137 0.842216 -0.027585 -0.663988 0.747234 -0.0115628 -0.573421 0.81918 0.000815553 -0.419928 0.907557 -0.00115756 -0.208134 0.9781 0 -0.984426 0.175797 -0.0180264 -0.994092 0.107036 -0.000392441 -0.967615 0.25243 0.000904152 -0.842218 0.539137 -0.0195584 -0.885856 0.463549 -0.000816724 -0.785271 0.619152 0 0.110749 0.993848 -0.00879131 0.175791 0.984388 0.00404299 0.332199 0.943201 -0.00807367 0.499466 0.866296 -0.0181836 0.539048 0.842079 0.00033756 0.64761 0.761972 -4.12685e-05 0.715792 0.698313 -0.00437711 0.84221 0.539132 -0.0706973 0.744175 0.664233 -0.00653362 0.897132 0.441714 0 0.999926 0.0121942 0.0622761 0.990508 0.122541 0.125105 0.991508 0.0355048 0.0131243 0.97977 0.199698 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.0839589 -0.883188 0.461444 -0.00378987 -0.842212 0.539133 0.00137018 -0.961148 0.276031 -0.0442841 -0.978893 0.199519 0.0373894 -0.997653 0.0573653 0.0136681 -0.999243 0.0364295 0 -0.999926 0.0121942 -0.0408826 -0.85872 0.510812 -0.0189843 -0.816471 0.577074 -0.00185708 -0.77333 0.634 -4.34071e-05 -0.715754 0.698352 0.000828709 -0.558912 0.829227 -0.00539641 -0.53913 0.842206 0.00476291 -0.200227 0.979738 0 -0.175797 0.984426 -0.000182264 0.742183 0.670197 0 0.985337 0.170622 -0.000966574 0.984426 0.175796 0.000753398 0.886177 0.463347 -0.00981168 0.842177 0.539112 -0.00372432 0.794244 0.607588 -0.00213591 0.77382 0.633402 0.000508664 0.602987 0.797751 -0.00790849 0.539121 0.842191 -0.00344364 0.469375 0.882992 0.00260656 0.355607 0.934632 -0.00489708 0.175796 0.984415 0 0.121724 0.992564 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 -0.0538296 -0.99855 -0.00702502 -0.107419 -0.994189 0 -0.999249 -0.0387587 -0.00723494 -0.997927 -0.0639494 -0.000198137 -0.989628 -0.143653 0.000906131 -0.959775 -0.28077 -0.0120141 -0.949288 -0.314177 -1.63653e-06 -0.906858 -0.421436 1.2054e-06 -0.87928 -0.476305 -0.0106513 -0.816386 -0.577409 -0.0200017 -0.830646 -0.556441 -0.0154521 -0.612431 -0.790373 4.69219e-06 -0.676475 -0.736465 -4.10514e-06 -0.760729 -0.64907 0.000232782 -0.162549 -0.986701 -0.000497876 -0.325827 -0.945429 -0.0103589 -0.355291 -0.934698 -8.45551e-06 -0.460181 -0.887825 2.11793e-05 -0.560395 -0.828225 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0 -1 0 0 -1 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -1 0 0 -1 0 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 1 0 0 1 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965926 0.258819 0 0.965926 0.258819 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0.19509 0.980785 0 0.19509 0.980785 0 0.55557 0.83147 0 0.55557 0.83147 0 0.831469 0.55557 0 0.831469 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 1 0 0 1 0 0 0.980785 -0.19509 0 0.980785 -0.19509 0 0.83147 -0.55557 0 0.83147 -0.55557 0 0.55557 -0.83147 0 0.55557 -0.83147 0 0.19509 -0.980785 0 0.19509 -0.980785 0 0 -1 0 0 -1 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.55557 -0.83147 0 -0.55557 -0.83147 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -1 0 0 -1 0 0 -0.980785 0.195091 0 -0.980785 0.195091 0 -0.83147 0.55557 0 -0.83147 0.55557 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.19509 0.980785 0 -0.19509 0.980785 -0.707116 0 -0.707098 -0.707116 0 -0.707098 -0.694756 -0.186154 -0.694738 -0.694755 -0.186154 -0.694738 -0.694755 -0.508584 -0.508583 -0.694762 -0.508579 -0.50858 -0.694761 -0.694733 -0.186153 -0.69476 -0.694734 -0.186153 -0.69476 0.694734 -0.186153 -0.694757 0.694737 -0.186155 -0.694759 0.508582 -0.508581 -0.694755 0.508584 -0.508584 -0.694755 0.186154 -0.694739 -0.694756 0.186154 -0.694738 -0.70712 -0.707094 0 -0.70712 -0.707094 0 -0.70712 0.707094 0 -0.70712 0.707094 0 -0.69476 -0.694734 0.186153 -0.694761 -0.694734 0.186153 -0.69476 -0.508581 0.50858 -0.694757 -0.508582 0.508583 -0.694758 -0.186154 0.694736 -0.694759 -0.186154 0.694735 -0.694759 0.186153 0.694735 -0.694758 0.186154 0.694736 -0.694757 0.508583 0.508582 -0.694757 0.508583 0.508582 -0.694756 0.694738 0.186154 -0.69476 0.694734 0.186154 -0.707119 0 0.707095 -0.707119 0 0.707095 -0.580511 0.121656 0.805113 -0.513478 0.111526 0.850824 -0.514198 0.108212 0.850818 -0.493117 0.107023 0.863355 -0.498526 0.0795854 0.863214 -0.463385 0.0761282 0.882881 -0.468773 0.027505 0.882891 -0.456647 0.0274483 0.889224 -0.457097 0.00227292 0.889414 -0.456739 0.00231572 0.889598 -0.480193 -0.0855568 0.872981 -0.456711 -0.0113243 0.889543 -0.482363 -0.0727559 0.872945 -0.393475 -0.0498359 0.917984 -0.484114 -0.0461397 0.873788 -0.460286 -0.0335238 0.887137 -0.461685 -0.0111838 0.886973 -0.509671 -0.101946 0.854308 -0.568985 -0.119471 0.813623 -0.529293 -0.116096 0.840459 -0.541564 -0.123089 0.8316 -0.543688 -0.113361 0.831597 -0.581361 -0.117109 0.805174 -0.678759 -0.666115 0.309155 -0.654947 -0.681434 0.326637 -0.690725 -0.626411 0.36126 -0.702689 -0.413733 0.578838 -0.632493 -0.541537 0.553796 -0.637373 -0.535615 0.553961 -0.711585 -0.538758 0.450984 -0.743627 -0.497997 0.446113 -0.648001 -0.642887 0.4084 -0.637174 -0.383885 0.668312 -0.645846 -0.381598 0.661261 -0.661771 -0.45822 0.593374 -0.62585 -0.145258 0.766297 -0.635185 -0.196152 0.747037 -0.62927 -0.201668 0.750566 -0.64589 -0.285999 0.707835 -0.63837 -0.293595 0.711538 -0.646636 -0.331451 0.687024 -0.647701 -0.337894 0.68287 -0.605142 -0.110927 0.788351 -0.754757 0.0405032 0.654753 -0.611097 -0.0520059 0.789846 -0.589277 0.0708598 0.804818 -0.558287 0.0766028 0.826104 -0.594448 0.0470005 0.80276 -0.675525 0.661924 0.324842 -0.68256 0.653496 0.327192 -0.668016 0.624041 0.405373 -0.675493 0.615063 0.406703 -0.661513 0.576808 0.479262 -0.669376 0.567423 0.479548 -0.66097 0.537204 0.523956 -0.637751 0.534866 0.554249 -0.662751 0.503318 0.554465 -0.651984 0.459469 0.603162 -0.659256 0.45069 0.601881 -0.646102 0.391574 0.655151 -0.590492 -0.0629924 0.804581 -0.590599 -0.0630592 0.804498 -0.607866 0.0264273 0.7936 -0.605904 0.027908 0.795049 -0.623908 0.118983 0.772387 -0.619696 0.122623 0.775204 -0.637164 0.211345 0.741185 -0.630996 0.217201 0.74476 -0.646287 0.293751 0.704289 -0.62524 0.316482 0.713382 -0.646461 0.338846 0.683572 -0.65471 0.382256 0.652101 -0.712698 -0.665186 0.222686 -0.692319 -0.684589 0.228106 -0.693132 0.685771 0.222006 -0.711403 0.664628 0.228419 -0.736683 -0.674711 0.0454211 -0.736711 -0.67468 0.0454254 -0.735363 -0.67332 0.0766952 -0.756468 -0.649004 0.0809338 -0.735561 -0.670869 0.0942603 -0.725212 -0.679211 0.112875 -0.67416 -0.729292 0.116797 -0.727017 -0.673314 0.134514 -0.728557 -0.669078 0.146764 -0.727474 -0.670384 0.146175 -0.727036 0.670272 0.148845 -0.736031 0.662227 0.140408 -0.728724 0.670704 0.138264 -0.73198 0.671738 0.113904 -0.731995 0.671721 0.113903 -0.734903 0.673055 0.0831581 -0.734928 0.673028 0.0831546 -0.736351 0.674332 0.055356 -0.70834 0.704186 0.0487568 -0.73676 0.675158 0.0366993 -0.736775 -0.675594 0.0271302 -0.736769 -0.6756 0.0271376 -0.73631 -0.67664 -0.00234269 -0.784133 -0.620474 -0.012156 -0.724421 -0.681339 -0.104836 -0.724459 -0.681297 -0.104848 -0.728548 -0.680256 -0.0804374 -0.728564 -0.680238 -0.0804432 -0.732136 -0.679045 -0.0536124 -0.732157 -0.679022 -0.0536192 -0.73411 -0.678212 -0.0333272 -0.724321 0.681356 -0.105417 -0.724366 0.681307 -0.105425 -0.727182 0.68064 -0.0890875 -0.727176 0.680646 -0.0890883 -0.728497 0.68028 -0.0806925 -0.778901 0.62336 -0.0688129 -0.732009 0.679014 -0.0556956 -0.736412 0.676531 -0.00207046 -0.75954 0.650457 -0.00207142 -0.734333 0.6781 -0.0305756 -0.723898 -0.681464 -0.107606 -0.723996 -0.681317 -0.107875 -0.723953 -0.681433 -0.107433 -0.723862 0.681464 -0.107843 -0.723973 0.681378 -0.10764 -0.723953 0.681433 -0.107433 -0.703847 -0.691204 -0.163815 -0.711109 -0.682767 -0.167789 -0.702683 0.690515 -0.171542 -0.721959 0.681844 -0.117748 -0.724882 0.679651 -0.112342 -0.718693 0.682592 -0.132473 -0.683754 0.708206 -0.175855 -0.693374 -0.684531 -0.225054 -0.696527 -0.679568 -0.230296 -0.679228 -0.663515 -0.313683 -0.701558 -0.63847 -0.316501 -0.685627 -0.597927 -0.41521 -0.659048 -0.629522 -0.411531 -0.695727 -0.571955 -0.434547 -0.687817 -0.546459 -0.477798 -0.702259 -0.528369 -0.477136 -0.691673 -0.482559 -0.537332 -0.604128 -0.519122 -0.604601 -0.71829 -0.396429 -0.571755 -0.700308 -0.298176 -0.648583 -0.682127 0.273067 -0.678334 -0.670092 0.256086 -0.696704 -0.713941 0.145506 -0.684921 -0.698466 0.124181 -0.704787 -0.74586 -0.0402929 -0.664883 -0.705014 -0.0783623 -0.704851 -0.73215 -0.198778 -0.651493 -0.629044 -0.358642 -0.689696 -0.709748 -0.205355 -0.67386 -0.670948 -0.196723 -0.714933 -0.736204 -0.00285582 -0.676754 -0.710301 -0.00133984 -0.703897 -0.741377 0.127946 -0.658779 -0.715416 0.131242 -0.686262 -0.73073 0.205481 -0.651008 -0.700729 0.266095 -0.661945 -0.715885 0.267002 -0.64515 -0.727067 0.338437 -0.597356 -0.704525 0.345909 -0.61967 -0.716814 0.419118 -0.557241 -0.696223 0.428132 -0.576175 -0.707809 0.487763 -0.510974 -0.68969 0.497623 -0.526022 -0.701793 0.547119 -0.456232 -0.687227 0.680266 -0.254867 -0.699485 0.669623 -0.249653 -0.684611 0.649098 -0.331632 -0.698069 0.638275 -0.324505 -0.685687 0.610945 -0.3957 -0.68204 0.61336 -0.39826 -0.693602 0.580278 -0.426843 -0.685726 0.557402 -0.468063 -0.337374 0.0116783 -0.941298 -0.319916 0.0120839 -0.947369 -0.354375 0.0535791 -0.933567 -0.34616 0.0534151 -0.936654 -0.338235 0.0920656 -0.936548 -0.361 0.0951463 -0.9277 -0.335641 0.137102 -0.931959 -0.367761 0.145105 -0.91853 -0.347341 0.189135 -0.918467 -0.387683 0.20324 -0.899108 -0.339466 0.245296 -0.908071 -0.424079 0.293128 -0.856874 -0.402114 0.321471 -0.857298 -0.421265 0.366499 -0.829587 -0.437471 0.376743 -0.816507 -0.461585 0.417733 -0.782585 -0.504331 0.44103 -0.74239 -0.519919 0.4227 -0.7423 -0.537409 0.432598 -0.723914 -0.612878 0.412118 -0.674195 -0.604016 0.409116 -0.683951 -0.638671 0.352437 -0.684023 -0.64368 0.353282 -0.678872 -0.417272 -0.297924 -0.85856 -0.636664 -0.366589 -0.678433 -0.50196 -0.439221 -0.745065 -0.550514 -0.441774 -0.708358 -0.511073 -0.395084 -0.763356 -0.620875 -0.418199 -0.663041 -0.593601 -0.326298 -0.735641 -0.394492 -0.327168 -0.858684 -0.418077 -0.334648 -0.844525 -0.405253 -0.348542 -0.845156 -0.474835 -0.422593 -0.771976 -0.485627 -0.429484 -0.761387 -0.485411 -0.42935 -0.7616 -0.427141 -0.303248 -0.851816 -0.330247 -0.179824 -0.926607 -0.282774 -0.14774 -0.94774 -0.388864 -0.15837 -0.907581 -0.339667 -0.123687 -0.932378 -0.371281 -0.101156 -0.922994 -0.30084 -0.0735886 -0.950831 -0.371502 -0.0564999 -0.926711 -0.330893 -0.0433221 -0.942674 -0.35354 -0.0181591 -0.935243 -0.425756 -0.0155101 -0.904705 -0.337396 -0.00183566 -0.941361 0.977854 0.186065 -0.0958182 0.977371 0.188552 -0.095887 0.828521 0.542437 -0.138981 0.831396 0.537993 -0.139088 0.541317 0.825268 -0.160963 0.558744 0.813221 -0.162718 0.18153 0.970678 -0.157582 0.194724 0.967801 -0.159513 0.976755 0.18484 -0.108549 0.976287 0.187114 -0.108863 0.830552 0.544692 -0.116163 0.828948 0.547071 -0.116444 0.546251 0.830958 -0.105447 0.543169 0.832951 -0.105639 0.188321 0.978935 -0.0788753 0.183904 0.979771 -0.0789133 0.541719 0.840132 0.0267926 0.180945 0.980932 -0.0709392 0.17962 0.980648 -0.0778889 0.194714 0.977249 -0.0840875 0.162619 0.983554 -0.0785893 0.162159 0.98364 -0.0784685 0.173614 0.98158 -0.0797398 0.195903 0.977465 -0.0786429 0.251548 0.964039 -0.085741 0.164125 0.984269 -0.0654062 0.22519 0.972347 -0.0618988 0.183636 0.981361 -0.056648 0.18401 0.981742 -0.048199 0.16575 0.985106 -0.045749 0.183917 0.981987 -0.0433095 0.183843 0.982311 -0.0355805 0.148553 0.988258 -0.0357587 0.229264 0.973152 -0.0203393 0.183436 0.982737 -0.0240682 0.183137 0.982853 -0.0214791 0.182951 0.982888 -0.0214768 0.183124 0.982856 -0.0214483 0.824437 0.545218 -0.151794 0.978535 0.189158 -0.0817876 0.972282 0.186596 -0.140892 0.971868 0.188617 -0.141051 0.9648 0.186714 -0.185197 0.964506 0.188133 -0.185294 0.957931 0.186705 -0.217968 0.957752 0.187587 -0.217995 0.958999 0.187828 -0.212231 0.959246 0.186605 -0.212192 0.96907 0.188862 -0.158854 0.969881 0.1848 -0.15868 0.991871 0.124634 -0.025655 0.981621 0.189285 -0.0243269 0.979012 0.186768 -0.0815685 0.982111 0.188286 -0.0027167 0.980941 0.190028 0.0405439 0.981472 0.187215 0.0407817 0.977545 0.189522 0.0921283 0.977766 0.188324 0.0922408 0.976235 0.188945 0.106136 0.976214 0.189062 0.106125 0.829876 0.55314 0.0730858 0.831199 0.552591 0.0612449 0.830742 0.553284 0.0611951 0.834167 0.551236 0.0174665 0.833123 0.552814 0.017408 0.833919 0.550591 -0.0377916 0.833082 0.551862 -0.037733 0.830881 0.549696 -0.0864325 0.829965 0.551097 -0.0863146 0.824616 0.548937 -0.13666 0.823771 0.550246 -0.136499 0.817724 0.548656 -0.174083 0.817173 0.549516 -0.173953 0.811585 0.548303 -0.201725 0.811202 0.5489 -0.201643 0.812272 0.549091 -0.196755 0.812809 0.548257 -0.196866 0.821218 0.550082 -0.151693 0.541371 0.832129 -0.120326 0.829856 0.553172 0.0730807 0.541725 0.840129 0.0267936 0.542606 0.839771 0.0190641 0.542217 0.840023 0.0190285 0.544532 0.838686 -0.00950768 0.543697 0.839228 -0.00954013 0.54411 0.837777 -0.0455485 0.543456 0.838203 -0.045505 0.542043 0.836791 -0.0772664 0.54122 0.837333 -0.0771634 0.537712 0.835925 -0.109978 0.536976 0.836416 -0.10984 0.533007 0.83538 -0.134329 0.53254 0.835695 -0.134219 0.528899 0.834905 -0.152311 0.52855 0.835141 -0.152231 0.529259 0.835266 -0.149051 0.52971 0.834962 -0.149152 0.535261 0.83615 -0.119786 0.184781 0.980184 -0.0713871 0.976625 0.188907 0.102552 0.829175 0.553403 0.0788263 -0.0150501 0.995913 0.0890545 0.183974 0.980975 0.0619792 0.190219 0.981741 0.000745536 0.976944 0.187139 0.10276 0.97591 0.186912 0.112534 0.976402 0.184317 0.112545 0.975159 0.182025 0.12622 0.976109 0.177364 0.125509 0.975632 0.175172 0.132123 0.977702 0.163067 0.132314 0.976742 0.16704 0.134434 0.976328 0.163426 0.141689 0.978183 0.155396 0.137879 0.977895 0.150365 0.145297 0.980013 0.141718 0.13961 0.979809 0.133026 0.149257 0.981726 0.125781 0.142807 0.540016 0.840647 0.041179 0.832343 0.548491 0.0797659 0.826682 0.54712 0.131362 0.829806 0.54251 0.130789 0.823386 0.530724 0.200917 0.827351 0.525145 0.199282 0.82264 0.503974 0.2632 0.826939 0.498315 0.260489 0.823857 0.471092 0.315169 0.828377 0.465613 0.311442 0.826421 0.4315 0.361712 0.831166 0.426321 0.35695 0.83008 0.380883 0.407302 0.834153 0.377063 0.402508 0.180777 0.983523 -0.00107816 0.548448 0.835074 0.0430823 0.538944 0.832322 0.129536 0.546584 0.827395 0.129089 0.535859 0.807651 0.246081 0.543803 0.802733 0.244741 0.535819 0.766941 0.353127 0.542593 0.763027 0.351258 0.537325 0.716423 0.444995 0.543206 0.713331 0.442817 0.539899 0.655269 0.528329 0.545046 0.652885 0.525991 0.543285 0.577586 0.609291 0.54715 0.576099 0.607237 0.186802 0.595208 0.781558 0.186671 0.67848 0.710506 0.184457 0.678907 0.710676 0.186501 0.771185 0.60868 0.182524 0.772021 0.608825 0.186586 0.843988 0.502862 0.180797 0.845278 0.50281 0.187376 0.903064 0.386479 0.179086 0.904951 0.385996 0.186469 0.937938 0.292408 -0.0672735 0.969684 0.23492 0.181037 0.958402 0.220659 0.189194 0.973255 0.130306 0.981597 0.106996 0.158176 0.98215 0.105201 0.15593 0.833637 0.310547 0.456738 0.834724 0.309486 0.455471 0.546418 0.471312 0.69231 0.547335 0.470899 0.691866 -0.100629 0.560386 0.822096 0.187061 0.522311 0.831985 0.186961 0.416887 0.889523 0.982197 0.0784881 0.17067 0.876014 0.193012 0.44198 0.835146 0.229821 0.499713 0.940523 0.14195 0.308652 0.987658 0.062338 0.143686 0.156426 0.350768 0.923305 0.0917334 0.411876 0.906611 0.452888 0.374666 0.809023 0.547801 0.344328 0.762464 0.648349 0.318129 0.691692 0.759452 0.271839 0.591047 0.155947 0.269167 0.950384 0.153451 -0.122846 0.98049 0.428798 -0.35666 0.830015 0.752432 -0.630802 0.189566 0.867771 -0.460945 0.185749 0.866638 -0.457562 0.198936 0.752146 -0.629754 0.194129 0.639821 -0.534681 0.552038 0.748329 -0.373849 0.547943 0.737963 -0.370258 0.564198 0.822973 -0.164307 0.543801 0.806032 -0.159459 0.569988 0.139835 -0.107941 0.984274 0.181516 -0.0465103 0.982287 0.156067 -0.0276197 0.98736 0.184852 0.0409329 0.981914 0.0832098 0.130763 0.987916 0.177769 0.121872 0.976497 0.204019 0.256039 0.944892 0.451309 0.206797 0.868075 0.569937 0.186316 0.800286 0.527416 -0.0316519 0.849017 0.554244 -0.0380736 0.831483 0.480981 -0.215676 0.849789 0.501509 -0.223793 0.835707 0.419379 -0.345621 0.839445 0.639245 -0.533889 0.553469 0.645251 0.157036 0.747657 0.7551 0.114454 0.645542 0.851862 0.0748263 0.518393 0.870659 0.0601327 0.488197 0.934904 0.0121911 0.354692 0.939534 -0.289396 0.1831 0.956608 -0.288358 0.0418316 0.964535 -0.179353 0.193661 0.985319 -0.0474215 0.164003 0.982709 -0.0398693 0.180814 0.490244 -0.849617 0.194453 0.623087 -0.757601 0.194431 0.490248 -0.849618 0.194436 0.415991 -0.720928 0.55427 0.623075 -0.757598 0.194481 0.528703 -0.642851 0.554271 0.528713 -0.642858 0.554253 0.353731 -0.430099 0.830596 0.353732 -0.4301 0.830595 0.430442 -0.787155 0.441709 0.397012 -0.688038 0.607442 0.27832 -0.482339 0.830595 0.29587 -0.532971 0.792719 0.221652 -0.38413 0.896278 0.0978286 -0.16954 0.980656 0.0978252 -0.169536 0.980657 0.124332 -0.151174 0.980657 0.12433 -0.151173 0.980657 0.238963 -0.375523 0.895477 0.427179 -0.6713 0.605702 0.526716 -0.8277 0.193607 0.482228 -0.757808 0.439526 0.533101 -0.805947 0.257395 0.70555 -0.660458 0.256893 0.705552 -0.660458 0.256888 0.847797 -0.463951 0.256884 0.847792 -0.463953 0.256896 0.936621 -0.238214 0.256896 0.936605 -0.238227 0.256941 0.966423 0.00252334 0.256942 0.966438 0.00254352 0.256886 0.935361 0.243124 0.256886 0.935353 0.243105 0.256931 0.845351 0.468368 0.25693 0.845354 0.468392 0.256876 0.702079 0.664151 0.256881 0.70208 0.664144 0.256899 0.328452 -0.516151 0.791017 0.400244 -0.584755 0.705597 0.51827 -0.485144 0.704295 0.518266 -0.485143 0.704298 0.622753 -0.340795 0.704299 0.62275 -0.340795 0.704302 0.687994 -0.174993 0.704303 0.688022 -0.174987 0.704277 0.709924 0.0018697 0.704276 0.709893 0.00185352 0.704307 0.687067 0.178579 0.704307 0.687078 0.178589 0.704294 0.620967 0.344049 0.704294 0.620967 0.344048 0.704295 0.51572 0.487854 0.704295 0.515723 0.487862 0.704287 0.105546 -0.165862 0.980485 0.154699 -0.207929 0.965833 0.190362 -0.178194 0.965406 0.19036 -0.178193 0.965407 0.22874 -0.125174 0.965407 0.228735 -0.125173 0.965408 0.252698 -0.0642752 0.965408 0.2527 -0.064275 0.965407 0.260745 0.000687275 0.965407 0.260744 0.000686706 0.965408 0.252361 0.0655884 0.965408 0.252369 0.0655945 0.965405 0.228082 0.126375 0.965405 0.228074 0.126365 0.965409 0.189418 0.179183 0.965409 0.189419 0.179184 0.965409 0.258778 0.0190864 0.965748 0.258771 0.019084 0.96575 0.25317 0.0568425 0.96575 0.253174 0.0568444 0.965749 0.242094 0.0933761 0.965749 0.242092 0.0933745 0.96575 0.225773 0.127882 0.96575 0.225779 0.127887 0.965748 0.204574 0.159626 0.965748 0.204572 0.159623 0.965749 0.178937 0.187911 0.965749 0.178935 0.187908 0.96575 0.70614 0.0520809 0.706154 0.706143 0.052082 0.706151 0.690862 0.155112 0.706152 0.690867 0.155115 0.706146 0.660629 0.254808 0.706146 0.660624 0.254804 0.706152 0.616097 0.348962 0.706152 0.616106 0.348972 0.706138 0.558238 0.435588 0.706139 0.558232 0.435579 0.706151 0.488285 0.512767 0.70615 0.488289 0.512777 0.70614 0.963491 0.0710569 0.258141 0.963495 0.071062 0.258121 0.942643 0.211654 0.258122 0.942633 0.21164 0.258169 0.901376 0.347665 0.258168 0.901376 0.347665 0.258168 0.840622 0.476134 0.258168 0.840623 0.476135 0.258165 0.761666 0.59432 0.258165 0.761667 0.594322 0.258158 0.666232 0.699635 0.258159 0.666232 0.699636 0.258156 0.258825 0 0.965924 0.258825 0 0.965924 0.7071 0 0.707114 0.7071 0 0.707114 0.965932 0 0.258795 0.965932 0 0.258795 0.178935 -0.187908 0.96575 0.178938 -0.18791 0.965749 0.204571 -0.159623 0.965749 0.204575 -0.159625 0.965748 0.22578 -0.127885 0.965748 0.225773 -0.127883 0.96575 0.242091 -0.0933751 0.96575 0.242094 -0.0933755 0.965749 0.253175 -0.0568434 0.965749 0.25317 -0.0568434 0.96575 0.25877 -0.0190858 0.96575 0.258778 -0.0190845 0.965748 0.488292 -0.512774 0.70614 0.488282 -0.512769 0.70615 0.558229 -0.435582 0.706151 0.55824 -0.435585 0.70614 0.616109 -0.348969 0.706138 0.616095 -0.348966 0.706151 0.660624 -0.254806 0.706152 0.660629 -0.254806 0.706146 0.690867 -0.155113 0.706146 0.690862 -0.155114 0.706152 0.706143 -0.0520811 0.706151 0.70614 -0.0520818 0.706154 0.666232 -0.699635 0.258156 0.666231 -0.699635 0.258159 0.761668 -0.594321 0.258158 0.761665 -0.594321 0.258165 0.840623 -0.476134 0.258164 0.840622 -0.476135 0.258168 0.901376 -0.347665 0.258168 0.901376 -0.347665 0.258168 0.942631 -0.211651 0.258169 0.942645 -0.211643 0.258123 0.963496 -0.0710572 0.258121 0.96349 -0.0710616 0.258141 0.702075 -0.664148 0.2569 0.702083 -0.664147 0.256882 0.845364 -0.468375 0.256876 0.845342 -0.468385 0.256929 0.935349 -0.243121 0.256932 0.935365 -0.243108 0.256887 0.966439 -0.00252338 0.256886 0.966424 -0.00254349 0.256942 0.936609 0.238211 0.256941 0.936617 0.238229 0.256897 0.847794 0.463949 0.256898 0.847795 0.463955 0.256884 0.705551 0.660459 0.256888 0.705551 0.660457 0.256892 0.518847 0.815354 0.256896 0.518852 0.815342 0.256925 0.515725 -0.48786 0.704287 0.515717 -0.487857 0.704295 0.620967 -0.344048 0.704295 0.620968 -0.344048 0.704294 0.68708 -0.178583 0.704293 0.687066 -0.178586 0.704306 0.709892 -0.00186961 0.704308 0.709923 -0.00185362 0.704277 0.688019 0.175 0.704276 0.687998 0.174981 0.704302 0.622751 0.340794 0.704302 0.622752 0.340796 0.704299 0.518267 0.485142 0.704299 0.518268 0.485146 0.704295 0.381125 0.598926 0.704295 0.381125 0.598928 0.704293 0.189419 -0.179184 0.965409 0.189418 -0.179184 0.965409 0.228071 -0.126369 0.965409 0.228084 -0.126371 0.965406 0.25237 -0.0655909 0.965405 0.25236 -0.0655922 0.965408 0.260744 -0.000687271 0.965408 0.260745 -0.000686709 0.965407 0.2527 0.0642755 0.965407 0.252699 0.0642746 0.965408 0.228736 0.125171 0.965408 0.228739 0.125175 0.965407 0.19036 0.178192 0.965407 0.190361 0.178194 0.965406 0.139987 0.219986 0.965407 0.139987 0.219986 0.965407 0.173278 0.192481 0.965881 0.173281 0.192493 0.965878 0.646285 0.717929 0.258639 0.68192 0.707012 0.187402 0.60246 0.669254 0.434904 0.473245 0.525713 0.70687 0.573139 0.548834 0.608517 0.407494 0.452654 0.793129 0.140291 0.219839 0.965396 0.14029 0.219838 0.965396 0.381925 0.598486 0.704235 0.38192 0.598472 0.70425 0.519899 0.814687 0.256886 0.519899 0.814694 0.256864 0.202667 -0.250721 0.946607 0.142912 -0.267936 0.952778 0.187353 -0.336035 0.923027 0.829992 -0.0793793 0.552097 0.976672 0.0352489 0.211826 0.739566 0.367156 0.564127 0.822064 0.16716 0.544305 0.528683 0.0259662 0.848422 0.569102 -0.182593 0.801737 0.54565 -0.185603 0.817201 0.947393 0.319882 -0.0110113 0.964673 0.178405 0.19385 0.985527 0.0445051 0.163574 0.154633 0.0308288 0.987491 0.18379 0.0428141 0.982033 0.499848 0.226186 0.836057 0.138404 0.109861 0.984264 0.209725 0.156795 0.965107 0.41536 0.350984 0.839218 0.471088 0.389231 0.791565 0.610825 0.508812 0.606633 0.172621 -0.0977847 0.980123 0.205189 -0.0911093 0.974472 0.553032 0.0410502 0.832148 0.482684 0.211849 0.849786 0.747382 0.375488 0.548115 0.636624 0.53869 0.551836 0.691911 0.577563 0.433221 0.851517 -0.0728762 0.519238 0.807536 0.153808 0.569411 0.948248 0.261608 0.179964 0.866216 0.458331 0.199005 0.868981 0.458669 0.185729 0.752491 0.630708 0.189644 0.753208 0.630804 0.186451 0.890787 -0.199583 0.408247 0.835235 -0.225925 0.501338 0.987661 -0.0685105 0.140826 0.982191 -0.0785015 0.170699 0.156013 -0.412751 0.897383 0.186801 -0.413144 0.891301 0.452971 -0.370422 0.810928 0.547715 -0.354845 0.757689 0.648429 -0.3181 0.69163 0.759499 -0.271816 0.590996 0.187427 -0.981824 0.0298927 0.186409 -0.893319 0.408941 0.975636 -0.17513 0.132152 0.185398 -0.817312 0.545553 0.647804 -0.428114 0.630134 0.890167 -0.257068 0.376189 0.156251 -0.516729 0.84177 -0.148467 -0.551322 0.820976 0.186753 -0.587526 0.787361 0.186846 -0.666531 0.721682 0.185745 -0.717808 0.671007 0.0267586 -0.690422 0.722912 0.547178 -0.574961 0.608289 0.546583 -0.473155 0.690921 0.452701 -0.495124 0.741562 0.182531 -0.770862 0.610291 0.186502 -0.770408 0.609663 0.54506 -0.65178 0.527344 0.54333 -0.576991 0.609815 0.834186 -0.376071 0.403366 0.833665 -0.310056 0.45702 0.759399 -0.357037 0.543909 0.830185 -0.380682 0.407277 0.831241 -0.425319 0.357969 0.53999 -0.654743 0.528887 0.543238 -0.712408 0.444261 0.0295145 -0.86163 0.506678 0.181667 -0.851718 0.491501 0.977855 -0.162076 0.132408 0.182562 -0.920359 0.345846 -0.0326767 -0.924181 0.380555 0.542598 -0.76247 0.352459 0.537389 -0.716081 0.445467 0.828395 -0.46486 0.312517 0.826499 -0.431371 0.361689 0.177867 -0.950876 0.253375 0.18902 -0.948843 0.252919 0.543737 -0.802243 0.246488 0.53585 -0.766917 0.353133 0.826933 -0.497856 0.261382 0.823916 -0.471005 0.315145 0.976391 -0.184392 0.112516 0.975874 -0.186883 0.11289 0.826654 -0.547082 0.131696 0.976131 -0.177414 0.125269 0.975105 -0.181981 0.126699 0.82349 -0.53055 0.200951 0.829761 -0.542279 0.132026 0.538971 -0.832215 0.130109 0.178757 -0.977796 0.109368 0.190954 -0.975482 0.109416 0.546535 -0.827103 0.131148 0.536039 -0.807451 0.246345 0.827306 -0.524784 0.200417 0.822681 -0.50402 0.262981 0.976776 -0.16718 0.134012 0.976301 -0.16301 0.142351 0.978211 -0.155668 0.137373 0.977877 -0.149789 0.14601 0.98004 -0.142078 0.139053 0.979814 -0.132322 0.149849 0.981736 -0.12617 0.14239 0.981576 -0.105143 0.15954 0.987596 -0.08777 0.130195 0.976957 -0.187131 0.102653 0.976837 -0.187746 0.102674 0.832352 -0.54851 0.079543 0.831157 -0.550318 0.0795514 0.548536 -0.835035 0.042721 0.54495 -0.837384 0.0426291 0.0962338 -0.995309 -0.00999313 0.18521 -0.982661 -0.00865089 0.536364 -0.835461 -0.119663 0.194128 -0.980764 -0.0204094 0.162063 -0.986426 -0.0264608 0.183414 -0.982707 -0.025408 0.183949 -0.982418 -0.0318873 0.145454 -0.988707 -0.0360732 0.240274 -0.969734 -0.0434158 0.183682 -0.981895 -0.0462905 0.183376 -0.981619 -0.0528894 0.166019 -0.984532 -0.0559893 0.182717 -0.981414 -0.0586615 0.181663 -0.980995 -0.0681762 0.178384 -0.98164 -0.0675461 0.182556 -0.980204 -0.07664 0.179935 -0.980737 -0.0760225 0.178793 -0.980492 -0.0816641 0.169642 -0.982243 -0.0801271 0.174992 -0.98115 -0.0819863 0.205949 -0.974751 -0.0862931 0.172815 -0.98186 -0.078017 0.197567 -0.977544 -0.0733081 0.181373 -0.980888 -0.0704489 0.831885 -0.550071 0.0734117 0.967208 -0.188407 -0.170328 0.959314 -0.186597 -0.211892 0.95908 -0.187835 -0.211858 0.957665 -0.187562 -0.2184 0.957834 -0.186666 -0.218426 0.964218 -0.188041 -0.186879 0.964462 -0.186719 -0.186948 0.971494 -0.188586 -0.14365 0.971871 -0.186564 -0.143739 0.978294 -0.189119 -0.0847063 0.978744 -0.18674 -0.0847836 0.981563 -0.189307 -0.0264034 0.981967 -0.187196 -0.0264479 0.980983 -0.189992 0.0396904 0.981524 -0.187164 0.0397535 0.977563 -0.189511 0.0919542 0.977791 -0.188312 0.0919929 0.976232 -0.188946 0.106163 0.97643 -0.187899 0.1062 0.546752 -0.836845 0.0274428 0.829869 -0.553141 0.0731612 0.831217 -0.552582 0.0610922 0.830767 -0.553269 0.0609889 0.83421 -0.551193 0.0167314 0.833124 -0.552839 0.016541 0.833845 -0.550586 -0.0394582 0.833027 -0.551814 -0.0395937 0.830668 -0.549622 -0.0889209 0.829691 -0.551078 -0.0890236 0.82424 -0.548949 -0.138863 0.823382 -0.550227 -0.138901 0.81742 -0.54868 -0.175427 0.816855 -0.549521 -0.175426 0.811464 -0.548358 -0.202062 0.811123 -0.548875 -0.20203 0.812333 -0.549092 -0.196502 0.812867 -0.548285 -0.196548 0.821266 -0.550112 -0.151323 0.890214 -0.427744 -0.1567 0.973262 -0.187175 -0.133142 0.822446 -0.548298 -0.151499 0.535352 -0.836134 -0.119495 0.529797 -0.834942 -0.148956 0.529308 -0.835264 -0.148886 0.528506 -0.835123 -0.152485 0.528832 -0.834908 -0.152534 0.532346 -0.835665 -0.135174 0.532823 -0.835355 -0.135211 0.536738 -0.836363 -0.111398 0.537467 -0.835891 -0.111421 0.541049 -0.83728 -0.0789186 0.54188 -0.836745 -0.0788956 0.543398 -0.838175 -0.0467074 0.544099 -0.837723 -0.0466462 0.543737 -0.839195 -0.0100927 0.544564 -0.83866 -0.00999637 0.542235 -0.840014 0.0188963 0.542619 -0.839765 0.0189617 0.541713 -0.840133 0.0269042 0.186638 -0.982202 -0.0211226 0.0963702 -0.983233 -0.154807 0.18098 -0.969821 -0.163383 0.29236 -0.942529 -0.161753 0.475587 -0.864241 -0.164028 0.540659 -0.824482 -0.167084 0.638546 -0.753353 -0.157224 0.775114 -0.614615 -0.146448 0.82799 -0.541876 -0.14423 0.881361 -0.454397 -0.129327 0.954111 -0.279305 -0.10799 0.977454 -0.185601 -0.100681 0.991983 -0.0948714 -0.0834874 0.188288 -0.978907 -0.0793014 0.180514 -0.980487 -0.0778412 0.54619 -0.830902 -0.106201 0.538191 -0.836294 -0.104703 0.830508 -0.544641 -0.116714 0.826965 -0.550154 -0.116012 0.976725 -0.184808 -0.108878 0.976088 -0.188249 -0.108692 0.689638 5.74775e-05 -0.724155 0.689603 0 -0.724188 0.689638 -3.64531e-06 -0.724155 0.689625 3.09808e-08 -0.724167 0.689624 0 -0.724167 0.0776483 -0.628844 -0.773644 0.0956037 -0.621328 -0.777697 0.197663 -0.600379 -0.774903 0.20064 -0.59837 -0.775691 0.311188 -0.551724 -0.773798 0.302869 -0.56013 -0.771054 0.41492 -0.484169 -0.770339 0.400467 -0.505805 -0.76406 0.506029 -0.399255 -0.764545 0.491081 -0.434787 -0.754851 0.581492 -0.299101 -0.756575 0.571067 -0.346926 -0.743992 0.638493 -0.186389 -0.746717 0.63669 -0.243633 -0.73162 0.674784 -0.0638194 -0.735251 0.68409 -0.126434 -0.718356 0.048471 -0.629554 -0.775443 0.183856 -0.661692 -0.726884 0.214244 -0.659617 -0.72042 0.235606 -0.674524 -0.699648 0.235279 -0.676298 -0.698043 0.0446239 -0.644868 -0.76299 0.086288 -0.633575 -0.768854 0.118257 -0.652641 -0.748382 0.125235 -0.636468 -0.761068 0.184519 -0.653435 -0.73415 0.623094 -0.0601368 -0.779831 0.295794 -0.677857 -0.673064 0.280476 -0.70472 -0.651693 0.34482 -0.653015 -0.674292 0.361001 -0.63487 -0.683095 0.354812 -0.6467 -0.675195 0.370921 -0.644202 -0.668896 0.387232 -0.637067 -0.666481 0.383829 -0.644175 -0.661599 0.418102 -0.601315 -0.68089 0.460155 -0.593534 -0.660284 0.417142 -0.605112 -0.678109 0.438447 -0.589355 -0.678547 0.440573 -0.588629 -0.677799 0.461697 -0.543927 -0.700699 0.577321 -0.261967 -0.773352 0.594091 -0.333339 -0.73208 0.554409 -0.321468 -0.767652 0.569007 -0.399367 -0.718844 0.535416 -0.386369 -0.751032 0.539384 -0.46584 -0.701469 0.511385 -0.446291 -0.734377 0.501485 -0.519224 -0.69204 0.503859 -0.52145 -0.688633 0.480089 -0.523765 -0.703694 0.583244 -0.0742832 -0.808893 0.607093 -0.0849418 -0.790078 0.637792 -0.133872 -0.758485 0.62233 -0.125895 -0.772565 0.613705 -0.16118 -0.772908 0.604389 -0.153255 -0.78181 0.639897 -0.21981 -0.736353 0.579217 -0.184545 -0.79401 0.614981 -0.267063 -0.741941 0.618357 -0.0154588 -0.785746 0.623426 -0.0561409 -0.779864 0.548836 -0.0412229 -0.834913 0.618051 -0.0388769 -0.785176 0.619135 -0.0155188 -0.785131 0.61844 -0.000318412 -0.785832 0.618418 -0.000368439 -0.785849 0.618418 0.000318394 -0.785849 0.61844 0.000368449 -0.785832 0.624149 0.0468434 -0.7799 0.617604 0.0466914 -0.785102 0.619126 0.0154332 -0.78514 0.618358 0.0153739 -0.785747 0.624012 0.0486059 -0.779902 0.618904 0.110699 -0.777627 0.597153 0.0791831 -0.798209 0.561726 0.0812277 -0.823326 0.62259 0.0605338 -0.780203 0.629425 0.147927 -0.762851 0.571016 0.146686 -0.807728 0.611366 0.189777 -0.768255 0.537092 0.318499 -0.781083 0.579459 0.303613 -0.756338 0.608343 0.250942 -0.752959 0.490196 0.216338 -0.844338 0.600583 0.220468 -0.768566 0.639225 0.363975 -0.677432 0.544165 0.359344 -0.758126 0.563047 0.426381 -0.707939 0.457389 0.559398 -0.691281 0.487824 0.530428 -0.693307 0.487814 0.530293 -0.693416 0.513613 0.461504 -0.723336 0.527335 0.508234 -0.680894 0.527137 0.413688 -0.742286 0.353189 0.647375 -0.675399 0.381075 0.643018 -0.664312 0.413466 0.579498 -0.702302 0.417058 0.594563 -0.687428 0.454597 0.581593 -0.674604 0.340494 0.601885 -0.722356 0.338826 0.587868 -0.73458 0.282362 0.677764 -0.678902 0.231705 0.67612 -0.69941 0.231142 0.678892 -0.696907 0.187273 0.63855 -0.746447 0.186744 0.64679 -0.739452 0.115616 0.685832 -0.718518 0.116759 0.59157 -0.797754 0.150875 0.645582 -0.748639 0.0858451 0.638592 -0.764743 0.0468779 0.616346 -0.786079 0.0433497 0.62962 -0.775693 0.683648 0.131367 -0.717891 0.639114 0.184577 -0.746636 0.562865 0.363153 -0.742497 0.518161 0.385605 -0.763425 0.371239 0.531788 -0.761172 0.350165 0.53291 -0.770319 0.138463 0.620325 -0.772026 0.1503 0.624714 -0.766252 0.689625 0 -0.724167 0.689624 -1.28927e-07 -0.724167 0.689606 -5.15342e-06 -0.724184 0.689664 6.36045e-06 -0.72413 0.689603 0 -0.724188 0.00405681 -0.639453 -0.76882 0.0043148 -0.639657 -0.768649 0.00323766 -0.638185 -0.769877 0.00339375 -0.638538 -0.769582 0.00148516 -0.638219 -0.769854 0.0017575 -0.637859 -0.770151 0.000386782 -0.639091 -0.769131 0 -0.639091 -0.769131 0 -0.639091 -0.769131 -0.730627 -0.142555 -0.66773 -0.70069 -0.155008 -0.696424 -0.601677 -0.388409 -0.697942 -0.570334 -0.387665 -0.724179 -0.395047 -0.563772 -0.725327 -0.37047 -0.552208 -0.746872 -0.141144 -0.649013 -0.74757 -0.128014 -0.633833 -0.762803 -0.73849 -0.0485811 -0.672513 -0.727729 -0.0509403 -0.68397 -0.719476 -0.122132 -0.683694 -0.709314 -0.123231 -0.694037 -0.689279 -0.208449 -0.693862 -0.68662 -0.208382 -0.696512 -0.655701 -0.291261 -0.696579 -0.664511 -0.292591 -0.687616 -0.633699 -0.353617 -0.688027 -0.711865 -0.443736 -0.544377 -0.645082 -0.423452 -0.636049 -0.615853 -0.464677 -0.636239 -0.94748 -0.0421241 -0.317029 -0.945703 -0.0427295 -0.322211 -0.930427 -0.173624 -0.322738 -0.924696 -0.176466 -0.337338 -0.896254 -0.287876 -0.337427 -0.884232 -0.29146 -0.364944 -0.845992 -0.388454 -0.365241 -0.826869 -0.390636 -0.404587 -0.791056 -0.458553 -0.40492 -0.76594 -0.457638 -0.451556 -0.742257 -0.494902 -0.451803 -0.675251 -0.487155 -0.553819 -0.676449 -0.48897 -0.550749 -0.672704 -0.494034 -0.550818 -0.738356 0.0512848 -0.672459 -0.728124 0.0475975 -0.683791 -0.719398 0.123625 -0.683509 -0.710216 0.11928 -0.693805 -0.689941 0.206829 -0.693688 -0.687479 0.20528 -0.696587 -0.657701 0.286373 -0.696721 -0.66424 0.291721 -0.688247 -0.633126 0.353652 -0.688536 -0.646815 0.367796 -0.668099 -0.621928 0.408073 -0.668343 -0.639272 0.429742 -0.637694 -0.622065 0.454124 -0.637814 -0.665417 0.501339 -0.553063 -0.682762 0.477849 -0.552718 -0.721689 0.522635 -0.453891 -0.769406 0.449539 -0.453794 -0.782112 0.47177 -0.407105 -0.828055 0.385886 -0.406715 -0.838576 0.402551 -0.367074 -0.883958 0.290024 -0.366749 -0.891815 0.300495 -0.338185 -0.924399 0.176485 -0.338142 -0.928891 0.18144 -0.322863 -0.94347 0.0742935 -0.323025 -0.945138 0.0758143 -0.317753 -0.948041 0.0117507 -0.31793 -0.948254 0.0119212 -0.317288 -0.137908 0.632982 -0.761785 -0.131427 0.652057 -0.746691 -0.382895 0.545656 -0.74542 -0.383858 0.573033 -0.724077 -0.581314 0.374409 -0.722421 -0.593169 0.403818 -0.696478 -0.706399 0.136815 -0.694465 -0.728245 0.161411 -0.666038 0 0.639088 -0.769134 0 0.639088 -0.769134 0.00147759 0.640792 -0.767713 0.00262551 0.638201 -0.769865 0.000110216 0.639088 -0.769134 0.000719643 0.638792 -0.769379 0.00185667 0.637769 -0.770225 0.00286557 0.639132 -0.769092 0.00533828 0.639136 -0.769076 0.558906 -0.671528 -0.486491 0.212422 -0.432233 0.876385 0.949517 -0.0423502 -0.310845 0.967293 -0.0192477 -0.25293 0.958999 -0.0879747 -0.269409 0.97633 -0.0278276 -0.214489 0.971244 -0.11985 -0.205721 0.98429 -0.0326627 -0.173512 0.983499 -0.124883 -0.130894 0.990829 -0.0326975 -0.131103 0.992763 -0.102508 -0.062559 0.995575 -0.0248883 -0.0906145 0.99807 -0.0583421 -0.0212539 0.999468 -0.0117694 -0.0304245 0.998285 -0.0079168 -0.0580028 0.951212 -0.183518 0.248024 0.853398 -0.269037 0.446465 -0.156564 -0.551072 0.819639 0.217752 -0.498486 0.839104 0.205074 -0.692028 0.692129 0.0091528 -0.73579 0.677148 0.215065 -0.792482 0.570718 0.225993 -0.895264 0.383965 0.0114851 -0.921169 0.388993 0.205198 -0.84551 0.492957 0.171608 -0.884529 -0.433774 0.218819 -0.950039 -0.222585 0.168492 -0.964447 -0.203597 0.199539 -0.978269 -0.0563285 0.156963 -0.982315 0.102075 0.0717192 -0.991994 0.103941 0.200639 -0.955648 0.215593 0.257414 -0.633989 -0.729243 0.140908 -0.51004 -0.84853 -0.136467 -0.466834 -0.873752 0.0961215 -0.403472 -0.909929 0.492254 -0.32771 -0.806407 0.407143 -0.367706 -0.836078 0.271226 -0.414243 -0.868815 0.925834 -0.0342029 -0.376379 0.743088 -0.187956 -0.642257 0.780838 -0.168839 -0.601486 0.662099 -0.250185 -0.706423 0.566696 -0.302088 -0.76655 0.831071 -0.380912 -0.405249 0.820282 -0.395166 -0.413498 0.855487 -0.44695 -0.26149 0.844463 -0.464904 -0.265982 0.877849 -0.469219 -0.0959912 0.867247 -0.488645 -0.0954379 0.894934 -0.439966 0.0743194 0.885711 -0.457335 0.0797491 0.90509 -0.358782 0.228226 0.898343 -0.370546 0.235959 0.908848 -0.238314 0.342348 0.634692 -0.726394 -0.263663 0.680393 -0.732223 -0.030251 0.657739 -0.752981 -0.0199698 0.695651 -0.685814 0.213842 0.67695 -0.700312 0.226499 0.703763 -0.56243 0.43404 0.690408 -0.570108 0.445324 0.151424 -0.681506 -0.715975 0.50629 -0.529854 -0.680386 0.537236 -0.515521 -0.667544 0.797944 -0.291671 -0.52746 0.807839 -0.282278 -0.517411 0.957814 -0.0049528 -0.287347 0.943634 0.00335439 -0.330973 0.195318 -0.802033 -0.564441 -0.0306422 -0.893786 -0.447446 0.525546 -0.691494 -0.495618 0.579247 -0.77043 -0.266291 0.460566 -0.858332 -0.226152 0.506769 -0.861914 0.0170123 0.474108 -0.879969 0.0295961 0.516973 -0.803857 0.294197 0.490596 -0.815429 0.307231 0.520936 -0.658914 0.54264 0.503118 -0.664377 0.552699 0.519785 -0.447003 0.728019 0.705632 -0.400097 0.584813 0.517134 -0.425763 0.742495 0.700608 -0.380768 0.60346 0.547716 0.328808 -0.769345 0.767181 0.574134 0.286013 0.814113 0.321932 0.483302 0.353816 -0.0555455 -0.933664 0.986376 0.162008 -0.0285625 0.993619 0.110409 -0.0230607 0.977635 0.202266 -0.0576087 0.952342 0.262487 -0.155386 0.96083 0.214596 -0.175367 0.957673 0.257843 -0.127981 0.967944 0.235399 -0.087582 0.9716 0.195835 -0.132822 0.974863 0.21315 -0.0648848 0.934566 0.220315 -0.279371 0.955677 0.16605 -0.243124 0.935665 0.236766 -0.261675 0.940842 0.255913 -0.222093 0.955401 0.199757 -0.2175 0.944062 0.263824 -0.197846 0.791667 0.188562 -0.581127 0.884986 0.1661 -0.434984 0.706872 0.00875555 -0.707287 0.0593996 -0.164274 -0.984625 -0.773865 -0.163892 -0.611778 0.667438 -0.112791 0.736074 -0.149553 -0.0315556 0.98825 0.320384 0.0136911 0.947189 0.29244 0.254962 0.921669 0.693157 -0.0634062 0.717993 0.853759 -0.0260053 0.520019 0.844575 -0.0297135 0.534613 0.998476 0.0515345 0.0197233 0.952852 -0.0606377 0.297314 0.999552 0.0256605 -0.0154232 0.831077 0.314349 0.458798 0.922475 0.266813 0.279016 0.950517 0.0755889 0.301337 0.995819 0.0854757 -0.0322291 0.96404 0.00734815 0.265655 0.913607 0.0434995 -0.404266 0.953671 0.09235 -0.286329 0.771432 0.0187911 -0.636034 0.761972 0.207201 -0.613569 0.87631 0.204478 -0.436199 0.986034 0.154138 -0.0630729 0.929054 0.260868 0.26231 0.88299 0.44893 0.13708 0.847155 0.493779 0.196243 0.789667 0.613245 -0.0188649 0.809046 0.586708 -0.0348916 0.761672 0.592809 -0.261598 0.779144 0.569189 -0.2626 0.749431 0.468694 -0.467631 0.315421 0.91366 -0.256388 0.0451298 0.874333 -0.483224 -0.583125 0.654397 -0.481382 0.211793 0.710985 -0.670555 0.0448365 0.537744 -0.841915 -0.744683 0.228208 -0.627191 0.0863597 0.327416 -0.940926 0.080233 0.0767577 -0.993816 -0.158648 0.387119 0.908278 0.118154 0.553683 0.824303 -0.0798851 0.724572 0.684553 0.141309 0.749853 0.646338 0.0889641 0.885086 0.456847 -0.0373429 0.960221 0.276735 0.367161 0.920214 0.13564 -0.274482 0.945534 -0.175002 0.316697 -0.213783 0.924121 0.304061 0.00995893 0.952601 0.523596 0.0322971 0.851354 0.496365 0.266264 0.826272 -0.392628 0.239691 0.887914 0.0770496 0.0540783 0.99556 0.161383 0.244719 0.956069 0.318835 0.260408 0.911335 0.279704 0.478753 0.832203 0.505295 0.475387 0.720197 0.430856 0.728547 0.532524 0.493677 0.711106 0.500611 0.39886 0.904514 0.150879 0.462911 0.876726 0.130637 0.381637 0.886984 -0.260024 0.432386 0.862848 -0.261793 0.38141 0.68886 -0.61644 0.485071 0.648274 -0.586896 0.47651 0.343345 -0.809353 0.391205 0.348278 -0.851857 0.420831 -0.0464169 -0.905951 0.574503 -0.0147152 -0.81837 0.518755 -0.0299275 -0.854399 0.619434 -0.0101649 -0.784983 0.119704 0.235191 0.96455 0.0792009 0.46167 0.883509 0.313476 0.483955 0.817019 0.237602 0.752123 0.6147 0.318421 0.744792 0.586424 0.215764 0.954051 0.207924 0.296922 0.936532 0.186402 0.207854 0.947634 -0.242462 0.271398 0.930016 -0.247817 0.21513 0.737333 -0.640359 0.245118 0.731142 -0.636669 0.234811 0.371638 -0.898192 0.225327 0.371789 -0.900556 0.259384 -0.0684955 -0.963342 0.216058 -0.0772199 -0.973322 0.94668 0.164433 -0.277054 0.933724 0.176673 -0.311362 0.759286 0.318652 -0.567402 0.759514 0.458189 -0.461737 0.541509 0.617062 -0.570966 0.585049 0.76549 -0.267848 0.548008 0.792105 -0.268806 0.618154 0.783105 0.0680659 0.57277 0.815265 0.0853096 0.65543 0.646502 0.390444 0.61223 0.669074 0.421324 0.690439 0.351795 0.632087 0.659551 0.358866 0.660461 0.707348 -0.0593793 0.704367 -0.355679 -0.150868 0.922351 0.519654 -0.209352 0.82833 0.213988 -0.247262 0.945024 0.95015 -0.0654965 0.304835 0.960888 -0.252392 -0.113989 0.975553 -0.0861353 -0.20218 0.926994 -0.220277 -0.303579 0.948752 -0.264778 -0.172518 0.94408 -0.265441 -0.195588 0.971614 -0.206664 -0.11514 0.972239 -0.201666 -0.118668 0.975195 -0.221312 0.00394019 0.999998 0.00165183 0.00137011 0.997885 -0.0407747 -0.0506202 0.851911 0.0250063 0.523089 0.888779 0.0216372 0.457825 0.703089 0.0681061 0.707833 0.691631 0.0714499 0.718708 0.702282 0.105368 0.704058 -0.152798 0.0487668 0.987054 0.0911683 -0.051928 0.994481 0.126033 -0.31799 0.93968 0.936167 -0.20958 0.282253 -0.534576 -0.323533 0.78074 0.118827 -0.801931 0.58548 0.0653467 -0.918496 0.389994 -0.752111 -0.5549 0.35555 0.27335 -0.95779 0.0889814 -0.248905 -0.955563 -0.157941 0.10475 -0.963513 -0.246314 0.100948 -0.729597 -0.676386 -0.576787 -0.652045 -0.492092 0.0321333 -0.872089 -0.488291 0.0772347 -0.882 -0.464877 0.0725647 -0.53693 -0.8405 -0.727494 -0.223177 -0.648802 -0.0376597 -0.32029 -0.946571 0.112493 -0.0765645 -0.990698 -0.732962 0.170377 -0.658589 0.0555773 0.16409 -0.984879 0.721766 0.085256 -0.686866 0.880543 -0.0523539 -0.471065 0.769876 -0.0757001 -0.633688 0.751771 -0.260642 -0.605728 0.913661 -0.19761 -0.355209 0.760001 -0.199729 -0.618471 0.913283 -0.290435 -0.28559 0.939281 -0.222105 -0.261573 0.75876 -0.497728 -0.420179 0.568829 -0.81728 0.092126 0.786157 -0.617736 -0.0189908 0.807705 -0.588896 -0.0285234 0.949965 -0.273216 -0.151393 0.968301 -0.180336 -0.172833 0.393404 -0.905531 0.158892 0.614028 -0.786299 0.0685773 0.543724 -0.794981 -0.269013 0.758257 -0.595215 -0.266018 0.776949 -0.572582 -0.261727 0.95203 -0.216637 -0.216119 0.954296 -0.209071 -0.21356 0.207013 0.244945 0.947179 0.308365 0.248834 0.918146 0.296424 0.00738661 0.955028 0.312462 0.00778626 0.949899 0.284567 -0.242003 0.927608 0.168288 -0.631891 0.756566 0.000235875 -0.436854 0.899532 0.271417 -0.470951 0.839368 0.311776 -0.241073 0.919064 0.490888 -0.251363 0.834174 0.517517 -0.0137355 0.855562 -0.312719 0.157993 0.936614 0.510916 0.219987 0.831006 0.935603 -0.19681 0.29311 0.984046 -0.177701 0.00866218 0.812765 -0.312034 0.491984 0.829296 -0.308186 0.466144 0.656426 -0.346049 0.67034 0.687028 -0.344195 0.639939 -0.40595 -0.224198 0.885968 0.499956 -0.465754 0.730149 0.307152 -0.468931 0.828107 0.999039 -0.0337442 -0.0279893 0.997486 -0.0452301 0.0545531 0.995601 -0.0818457 -0.0456128 0.989801 -0.139242 0.0301053 0.99021 -0.138039 -0.0207187 0.9819 -0.183568 -0.0466468 0.921349 -0.308609 0.236382 0.882141 -0.448782 0.142902 0.769682 -0.562102 0.302706 0.844952 -0.497846 0.195466 0.609288 -0.664749 0.432293 0.651639 -0.646771 0.396299 0.425998 -0.722332 0.544759 0.488102 -0.710749 0.50655 0.231283 -0.743865 0.627035 0.522304 0.0357761 -0.852009 0.571668 0.0219508 -0.820192 0.543182 -0.319296 -0.776533 0.426742 -0.864089 -0.266911 0.377614 -0.691826 -0.615455 0.480078 -0.641955 -0.597845 0.471646 -0.328728 -0.818222 0.383708 -0.345136 -0.856533 0.416512 0.0544243 -0.9075 0.358035 0.0623916 -0.931621 0.290225 -0.938644 0.186323 0.201312 -0.949231 -0.241733 0.264719 -0.930455 -0.253333 0.208498 -0.733816 -0.646562 0.238197 -0.726063 -0.645054 0.228998 -0.358165 -0.90514 0.217934 -0.3592 -0.907458 0.253702 0.0793026 -0.964026 0.213736 0.083403 -0.973325 -0.669679 -0.407566 0.620822 0.311358 -0.743445 0.5919 0.20913 -0.953591 0.21663 0.457359 -0.879597 0.130886 0.376061 -0.889429 -0.259795 0.580836 -0.767115 -0.27233 0.536912 -0.614814 -0.577693 0.872506 -0.324065 -0.36567 0.759795 -0.411441 -0.503416 0.932671 -0.208391 -0.294446 0.934857 -0.173326 -0.309839 0.911755 -0.190829 -0.363714 0.944601 -0.130972 -0.300956 0.902641 -0.122268 -0.412663 0.947657 -0.0945156 -0.30498 0.919466 -0.0357463 -0.391541 0.897303 -0.0288329 -0.440472 0.569041 0.304012 -0.764048 0.999855 0.0164106 -0.00448609 0.999059 0.0280229 -0.0330982 0.998917 0.0258172 -0.0387147 0.996229 0.0446053 -0.0744247 0.99622 0.0419461 -0.076062 0.990926 0.0695221 -0.115036 0.991328 0.0560373 -0.118862 0.983066 0.0719723 -0.168525 0.983824 0.0612301 -0.168348 0.973689 0.0610542 -0.219549 0.974439 0.0552742 -0.217745 0.976257 -0.0818362 -0.200563 0.947329 -0.0164508 -0.319838 0.910453 0.0545261 -0.410003 0.408692 0.356526 -0.840155 -0.262464 0.449319 -0.853947 0.0996294 0.450104 -0.887401 0.894392 0.250777 0.370371 0.908731 0.241323 0.340547 0.898501 0.371909 0.233194 0.904835 0.363828 0.221139 0.886239 0.456409 0.0791883 0.894351 0.442274 0.0673013 0.86808 0.487567 -0.0933594 0.877197 0.46928 -0.101496 0.84563 0.465055 -0.261979 0.738624 0.202998 -0.642827 0.779319 0.166815 -0.604015 0.808062 0.283203 -0.516558 0.159114 0.863514 -0.478568 -0.0755955 0.916151 -0.393641 0.192363 0.797326 -0.572073 0.170313 0.738265 -0.652655 -0.0428566 0.726126 -0.686225 0.191823 0.627956 -0.754238 0.164815 0.51647 -0.840294 0.268334 0.418874 -0.867491 0.492773 0.335575 -0.802848 0.536915 0.515969 -0.667456 0.508624 0.538387 -0.671894 0.55808 0.670128 -0.489362 0.222838 0.739995 0.634626 0.200048 0.739415 0.642843 0.211843 0.625453 0.750953 0.193001 0.560856 0.805103 0.205536 0.432849 0.877723 -0.00129709 0.50661 0.862174 0.505448 0.456485 0.732219 0.955082 0.0157703 -0.295921 0.955368 0.0150251 -0.295038 0.799343 0.296208 -0.522792 0.830932 0.380346 -0.406065 0.528112 0.695909 -0.48663 0.581316 0.773696 -0.251924 0.454143 0.854945 -0.250645 0.506834 0.861849 0.0183261 0.473393 0.880536 0.023561 0.51697 0.804839 0.291508 0.490054 0.818842 0.298906 0.521 0.663567 0.536878 0.50269 0.671941 0.543873 0.519845 0.451203 0.725381 0.20554 0.847429 0.489507 0.156505 0.873934 0.460158 0.0295818 0.909277 0.415138 0.219273 0.917671 0.33136 0.179842 0.979152 0.0944383 0.15388 0.982489 0.105049 0.239534 0.946522 -0.216147 -0.0193199 0.992846 -0.117832 0.197727 0.925737 -0.322358 0.964378 0.0394012 -0.261578 0.964124 0.0405499 -0.262338 0.821602 0.397469 -0.408643 0.85496 0.446135 -0.264587 0.635145 0.726259 -0.262943 0.680659 0.732013 -0.0293305 0.657105 0.75338 -0.0251395 0.69561 0.686613 0.211399 0.676218 0.703321 0.219246 0.703568 0.566478 0.429063 0.689999 0.576694 0.437407 0.705145 0.382981 0.596738 0.697456 0.387485 0.602836 0.717694 0.681717 -0.142048 0.691804 0.707427 -0.144756 0.700867 0.704656 -0.110658 0.702906 0.702525 -0.111273 0.700016 0.699388 -0.144342 0.703625 0.69565 -0.144854 0.702452 0.691013 -0.170477 0.69978 0.704209 -0.119994 0.776554 0.612998 -0.145595 0.694743 0.70416 -0.1466 0.689138 0.702863 -0.176273 0.688574 0.703451 -0.176132 0.687268 0.70322 -0.182053 0.687601 0.702872 -0.182139 0.694938 0.704271 -0.145132 0.69644 0.702723 -0.145436 0.703299 0.705516 -0.0872848 0.70426 0.704533 -0.0874747 0.706301 0.706381 -0.0465251 0.696491 0.716153 -0.0450067 0.707204 0.706473 -0.0275582 0.70668 0.707524 0.00355456 0.707745 0.706459 0.00356768 0.704387 0.708372 0.0452583 0.681373 0.730674 0.0429664 0.704113 0.708265 0.0508498 0.69668 0.668331 0.260712 0.702976 0.708638 0.0604811 0.705015 0.706622 0.0603317 0.701981 0.706324 0.0912641 0.730237 0.671997 0.123182 0.702291 0.699836 0.130447 0.694945 0.688532 0.207302 0.783206 0.596415 0.175722 0.699104 0.677824 0.227614 0.618903 0.717927 0.318653 0.699275 0.655519 0.285149 0.695093 0.623997 0.357034 0.700132 0.620022 0.354101 0.698725 0.593585 0.399299 0.740294 0.544143 0.394809 0.706186 0.463104 0.535571 0.704805 0.463792 0.536792 0.705806 0.500758 0.501077 0.718594 0.51661 0.46555 0.701198 0.532523 0.474068 0.702495 0.56878 0.427774 0.707062 0.232756 0.667748 0.707752 0.23331 0.666824 0.705733 0.264237 0.657359 0.659365 0.307757 0.685947 0.706833 0.30785 0.636879 0.706716 0.361903 0.60793 0.75727 0.350844 0.550863 0.706962 0.406376 0.578846 0.701266 0.0980293 0.706128 0.673256 -0.199863 0.711886 0.768365 -0.191051 0.610831 0.690686 -0.0790055 0.718826 0.726245 0.0964202 0.68064 0.49753 -0.506163 0.70446 0.492739 -0.503469 0.709738 0.6134 -0.354165 0.705909 0.447318 -0.296849 0.843675 0.623217 -0.303257 0.720857 0.369349 -0.605356 0.705071 0.369348 -0.605353 0.705074 0.458668 -0.552843 0.695693 0.458654 -0.552833 0.69571 0.668427 -0.263033 0.695715 0.668442 -0.263033 0.6957 0.712414 0.0920208 0.6957 0.712406 0.0920171 0.695709 0.579663 0.424244 0.695707 0.579663 0.424244 0.695707 0.703255 0.104304 0.703245 0.70325 0.104304 0.70325 0.6427 0.303935 0.70325 0.642688 0.303933 0.703262 0.526807 0.47739 0.703259 0.526811 0.477392 0.703254 0.707112 0 0.707102 0.707112 0 0.707102 0.526811 -0.477393 0.703254 0.526808 -0.477389 0.703259 0.64269 -0.303931 0.703261 0.642699 -0.303938 0.70325 0.70325 -0.104303 0.70325 0.703255 -0.104305 0.703245 0.579663 -0.424244 0.695707 0.579662 -0.424244 0.695707 0.712405 -0.0920197 0.695709 0.712414 -0.0920181 0.695701 0.668441 0.263038 0.6957 0.668429 0.263028 0.695715 0.458657 0.55283 0.69571 0.458664 0.552845 0.695694 0.369347 0.605353 0.705074 0.36935 0.605355 0.705071 0.701964 -0.105724 0.704322 0.725245 -0.0899045 0.682596 0.678071 0.122608 0.724698 0.72478 0.167458 0.66832 0.654776 0.240473 0.716548 0.623276 0.303082 0.72088 0.536841 0.301436 0.787996 0.581603 0.397661 0.70965 0.4939 0.502221 0.709815 0.496428 0.507121 0.704548 0.717734 -0.350628 0.601596 0.664768 -0.294778 0.686432 0.705435 -0.286494 0.648292 0.642253 -0.425537 0.637518 0.672656 -0.403499 0.620261 0.707073 -0.414595 0.572851 0.70685 -0.444311 0.55041 0.791291 -0.411386 0.45235 0.769652 -0.434555 0.467759 0.66866 -0.548428 0.502116 0.717544 -0.528183 0.454041 0.702102 -0.55113 0.450898 0.702404 -0.578278 0.414998 0.637531 -0.620415 0.456771 0.727623 -0.581776 0.363457 0.776494 -0.542586 0.320402 0.731728 -0.595592 0.331427 0.665983 -0.683799 0.298137 0.685183 -0.664664 0.297903 0.705676 -0.663242 0.249261 0.718277 -0.648585 0.251824 0.656151 -0.724658 0.210564 0.69616 -0.690359 0.196888 0.702825 -0.700877 0.121688 0.619374 -0.773367 0.135199 0.755574 -0.651622 0.0670533 0.701863 -0.708924 0.0693934 0.707243 -0.706456 -0.0269771 0.704113 -0.708265 0.050847 0.707908 -0.704374 0.0521832 0.706681 -0.70752 0.00415668 0.681577 -0.731747 -0.000145259 0.706071 -0.707655 0.0262204 0.70473 -0.708258 0.0415438 0.705187 -0.707797 0.0416484 0.704003 -0.708283 0.0521122 0.691895 -0.720536 -0.0459242 0.706451 -0.706439 -0.0432559 0.704508 -0.704579 -0.0850693 0.703496 -0.705575 -0.0851952 0.698833 -0.703752 -0.127929 0.697973 -0.704595 -0.127982 0.692831 -0.703275 -0.159341 0.69225 -0.703845 -0.159349 0.68769 -0.702866 -0.181828 0.687334 -0.703223 -0.181794 0.688517 -0.703431 -0.176433 0.689077 -0.702871 -0.176482 0.694698 -0.704167 -0.14678 0.777429 -0.611815 -0.145898 0.69978 -0.704209 -0.119994 0.715165 -0.683434 -0.146481 0.716336 -0.682171 -0.146646 0.691223 -0.707996 -0.144749 0.691814 -0.707418 -0.144755 0.700806 -0.704632 -0.111195 0.702946 -0.70257 -0.110735 0.700123 -0.699503 -0.143259 -0.897234 -0.387039 0.212537 -0.88295 -0.416608 0.21642 -0.849031 -0.436449 0.297757 -0.87007 -0.391901 0.298984 -0.860731 -0.410091 0.301609 -0.900905 -0.325799 0.28675 -0.835054 -0.432579 0.33994 -0.814332 -0.42991 0.389925 -0.808456 -0.437837 0.393316 -0.784748 -0.434822 0.441702 -0.784011 -0.441141 0.436716 -0.0636497 -0.705673 0.705673 -0.115433 -0.640191 0.759494 -0.21778 -0.638353 0.738293 -0.279132 -0.569738 0.772971 -0.414425 -0.566998 0.711874 -0.477097 -0.499315 0.723231 -0.647434 -0.495139 0.579367 -0.696743 -0.437671 0.568325 0 -0.707107 0.707107 0 -0.707107 0.707107 -0.70022 -0.139282 0.700209 -0.700218 -0.139282 0.700211 -0.593615 -0.396641 0.700212 -0.593618 -0.396643 0.700209 -0.396642 -0.593616 0.70021 -0.396643 -0.593617 0.700209 -0.139282 -0.700217 0.700212 -0.139282 -0.700215 0.700215 -0.707112 0 0.707102 -0.707112 0 0.707102 -0.139281 0.700215 0.700215 -0.139282 0.700217 0.700212 -0.396643 0.593617 0.700209 -0.396642 0.593616 0.70021 -0.593618 0.396643 0.700209 -0.593615 0.396642 0.700212 -0.700218 0.139282 0.700211 -0.70022 0.139282 0.700209 0 0.707107 0.707107 0 0.707107 0.707107 -0.671139 0.434974 0.600309 -0.676657 0.491459 0.548273 -0.436753 0.496831 0.749937 -0.458989 0.563155 0.687158 -0.232855 0.56788 0.789488 -0.268147 0.634824 0.724635 -0.0691143 0.63875 0.766304 -0.114055 0.702493 0.702493 -0.878362 0.400745 0.260547 -0.828304 0.452827 0.329939 -0.854582 0.410288 0.31836 -0.789584 0.456894 0.40964 -0.799072 0.440519 0.409178 -0.873937 0.407987 0.264161 -0.86447 0.426311 0.266367 -0.880812 0.418207 0.221976 -0.883896 0.414093 0.217383 -0.892647 0.397622 0.212314 -0.956578 0.183555 0.226418 0.0229848 -0.773572 -0.633292 0.0794567 -0.69899 -0.710704 -0.0926463 -0.810804 -0.577939 -0.0495121 -0.775847 -0.628975 -0.192723 -0.775849 -0.600763 -0.172413 -0.742208 -0.647612 -0.285761 -0.802738 -0.523405 -0.268056 -0.766016 -0.584265 -0.338828 -0.782048 -0.523064 -0.382892 -0.771485 -0.508138 -0.418052 -0.803773 -0.423298 -0.659355 -0.749501 -0.0591513 -0.595434 -0.803375 -0.00682278 -0.611347 -0.751263 -0.248713 -0.597346 -0.770168 -0.22365 -0.520807 -0.786728 -0.331391 -0.519591 -0.783864 -0.339973 -0.462938 -0.780437 -0.420246 -0.189749 -0.717708 0.669993 -0.626878 -0.773297 0.0950543 -0.635116 -0.757126 0.15293 -0.655533 -0.727698 0.201821 -0.565885 -0.780494 0.265713 -0.576253 -0.716077 0.393912 -0.578627 -0.714658 0.393007 -0.460228 -0.761439 0.45651 -0.472244 -0.755924 0.453392 -0.432926 -0.711861 0.553018 -0.358763 -0.749031 0.556994 -0.330797 -0.723141 0.606334 -0.290552 -0.725383 0.624018 -0.256759 -0.715261 0.649982 -0.141057 -0.764872 0.628549 0.50987 -0.612845 0.6037 -0.0500833 -0.720975 0.691149 0.0111477 -0.678279 0.73472 0.0813747 -0.737126 0.670838 0.226022 -0.694541 0.683028 0.256911 -0.743886 0.616952 0.3952 -0.696148 0.599329 0.640221 -0.746811 0.179974 0.668006 -0.705918 0.235475 0.628928 -0.707642 0.322014 0.628635 -0.70653 0.325014 0.559658 -0.713655 0.421284 0.562631 -0.703287 0.43455 0.404585 -0.719877 0.563992 0.720823 -0.651604 -0.236277 0.625183 -0.742901 -0.239259 0.737683 -0.67253 -0.0593872 0.67839 -0.730518 -0.0782942 0.716249 -0.69538 0.0585972 0.7064 -0.706632 0.040876 0.69999 -0.703018 0.125615 0.621066 -0.725169 -0.297333 0.523554 -0.738809 -0.424326 0.515513 -0.766748 -0.382548 0.412202 -0.744256 -0.525521 0.387937 -0.72772 -0.565622 0.277477 -0.796686 -0.536933 0.162499 -0.725499 -0.668764 0.206857 -0.769306 -0.604465 0.198286 0.77004 -0.6064 0.256478 0.730647 -0.632751 0.32407 0.774309 -0.543529 0.452746 0.728111 -0.51466 0.445114 0.704782 -0.552409 0.508571 0.771795 -0.381691 0.609276 0.697651 -0.376916 0.619307 0.726644 -0.297401 0.674679 0.712568 -0.192497 0.694445 0.68158 -0.230642 0.673163 0.73935 -0.0145918 0.741191 0.667748 -0.0689136 0.701756 0.709177 0.0678699 0.709245 0.686763 0.159148 0.658031 0.729354 0.187184 0.656999 0.705202 0.266537 0.630111 0.709842 0.314777 0.625687 0.690283 0.363352 0.561553 0.727224 0.39472 0.527547 0.681739 0.50688 0.424671 0.750775 0.505956 0.232659 0.759437 0.607557 0.338096 0.691472 0.638402 0.408897 0.733676 0.5427 -0.0496065 0.720727 0.691442 -0.0295733 0.70731 0.706285 0.0649382 0.73253 0.67763 0.104878 0.71104 0.695286 0.199318 0.731312 0.652269 0.072937 0.775131 -0.627576 -0.0430887 0.689804 -0.722713 0.00226726 0.749482 -0.662021 -0.182928 0.7926 -0.581656 -0.250966 0.738432 -0.625887 -0.302979 0.773391 -0.55684 -0.465213 0.732856 -0.496487 -0.395936 0.777343 -0.488847 -0.326684 0.779265 -0.534812 -0.571963 0.780009 -0.253858 -0.68813 0.682984 -0.24497 -0.577262 0.758796 -0.301656 -0.527709 0.782535 -0.330398 -0.47623 0.783046 -0.400054 -0.556645 0.762703 0.329288 -0.734638 0.644409 0.212236 -0.609207 0.750807 0.255255 -0.630492 0.769993 0.0979382 -0.681583 0.731717 -0.00586939 -0.690108 0.723706 -0.000748269 -0.622045 0.778179 -0.0865824 -0.531509 0.730067 0.429535 -0.532101 0.724618 0.437947 -0.426454 0.753899 0.499772 -0.427017 0.675622 0.600992 -0.337361 0.726321 0.59887 -0.202079 0.71719 0.666935 -0.182517 0.62478 0.759169 -0.259244 0.721732 0.641791 -0.217602 0.192273 0.956912 -0.0407634 0.00743286 0.999141 -0.102048 0.0747641 0.991966 -0.136348 0.0916986 0.986408 -0.143601 0.0794854 0.986439 -0.164632 0.0847744 0.982705 -0.126355 0.0527274 0.990583 -0.137813 0.00152454 0.990457 -0.166294 0.0174907 0.985921 -0.154082 0.0148429 0.987947 -0.151123 0.0349839 0.987896 -0.130262 0.0280299 0.991083 -0.16937 0.060605 0.983687 -0.437023 0.00196904 0.899448 -0.878994 0.00428282 0.476813 -0.730831 0.596677 0.331455 -0.783136 0.526219 0.331349 -0.779965 0.521855 0.34543 -0.834408 0.429549 0.345327 -0.829297 0.424269 0.36368 -0.877153 0.313668 0.363612 -0.869137 0.307731 0.387172 -0.901725 0.192171 0.38725 -0.890358 0.18631 0.415393 -0.905439 0.0863861 0.415593 -0.891989 0.0816242 0.444627 -0.895708 0.0018656 0.444639 -0.695069 0.00316671 0.718936 -0.711747 0.00158935 0.702434 -0.708794 0.0649666 0.702418 -0.724491 0.0691982 0.685802 -0.712535 0.149219 0.685585 -0.726565 0.154909 0.669407 -0.700337 0.248092 0.669312 -0.710975 0.254313 0.655621 -0.672113 0.343984 0.655698 -0.679381 0.349786 0.645051 -0.634947 0.424955 0.645179 -0.63981 0.429944 0.637017 -0.60029 0.483282 0.637253 -0.717064 0.592499 0.367102 -0.146549 -0.000797926 0.989203 -0.150001 0.00070187 0.988686 -0.449083 0.00109708 0.893489 -0.447221 0.0411492 0.893477 -0.458749 0.0438684 0.887483 -0.451245 0.094662 0.887365 -0.461779 0.0985064 0.881508 -0.445116 0.157841 0.881452 -0.453256 0.16217 0.876504 -0.428405 0.219417 0.876542 -0.434038 0.223505 0.872729 -0.405562 0.271569 0.872794 -0.409442 0.275169 0.86985 -0.386693 0.305779 0.870039 -0.5273 0.441451 0.726 -0.13119 -0.103331 0.985957 -0.100721 -0.0367162 0.994237 -0.175689 -0.0381006 0.983708 -0.138231 -0.0196889 0.990204 -0.169032 -0.0167489 0.985468 -0.128939 -0.00188853 0.991651 -0.146548 -0.000877966 0.989203 -0.138608 -0.0934129 0.985932 -0.11047 -0.0685502 0.991513 -0.163213 -0.0844391 0.982971 -0.147511 -0.0686804 0.986673 -0.155961 -0.0492966 0.986532 -0.443232 -0.361539 0.820265 -0.686874 -0.572446 0.447783 -0.565118 -0.444245 0.695189 -0.758671 -0.618852 0.203569 -0.734498 -0.593812 0.328482 -0.784582 -0.52598 0.328293 -0.77937 -0.524861 0.342204 -0.835789 -0.429459 0.342084 -0.828498 -0.42864 0.360361 -0.878528 -0.313674 0.360275 -0.868548 -0.313638 0.38374 -0.903241 -0.191963 0.383805 -0.89055 -0.193342 0.411752 -0.907166 -0.08567 0.411958 -0.89313 -0.0885614 0.440993 -0.89748 -0.00239177 0.441048 -0.878991 -0.00502095 0.476812 -0.189785 -0.16092 0.968549 -0.172871 -0.157138 0.972329 -0.388961 -0.307481 0.868427 -0.412023 -0.27647 0.868217 -0.407251 -0.2743 0.871152 -0.43673 -0.224699 0.871078 -0.430082 -0.222547 0.87493 -0.456027 -0.163154 0.874883 -0.447043 -0.161459 0.87982 -0.464762 -0.099126 0.87987 -0.453575 -0.0984911 0.885759 -0.461822 -0.0439658 0.885882 -0.449954 -0.0446281 0.891936 -0.452097 -0.0013983 0.891968 -0.437015 -0.00247137 0.899451 -0.600268 -0.48885 0.633013 -0.643081 -0.431258 0.632822 -0.636592 -0.428757 0.641029 -0.682699 -0.35097 0.640892 -0.673791 -0.348631 0.651507 -0.714483 -0.255295 0.651413 -0.702373 -0.253668 0.665075 -0.730348 -0.155428 0.665157 -0.715286 -0.155322 0.681353 -0.728485 -0.0689995 0.681579 -0.712299 -0.0706558 0.69831 -0.715735 -0.00202183 0.698369 -0.695058 -0.00396711 0.718942 0.707102 0 -0.707111 0.707102 0 -0.707111 0.139281 0.700217 -0.700212 0.139282 0.700215 -0.700214 0.396639 0.59361 -0.700218 0.39664 0.593615 -0.700213 0.593613 0.396642 -0.700213 0.593605 0.396631 -0.700227 0.700201 0.139279 -0.700228 0.70021 0.139284 -0.700219 0.70021 -0.139281 -0.700219 0.700201 -0.139282 -0.700228 0.593604 -0.396635 -0.700225 0.593615 -0.396638 -0.700214 0.396641 -0.593613 -0.700215 0.396636 -0.593609 -0.70022 0.139281 -0.700213 -0.700217 0.139282 -0.700215 -0.700214 0 0.707109 -0.707105 0 0.707109 -0.707105 0 -0.707107 -0.707107 0 -0.707107 -0.707107 -0.70021 0.139281 -0.700219 -0.700219 0.13928 -0.70021 -0.593615 0.396643 -0.700211 -0.593628 0.396647 -0.700198 -0.396647 0.593622 -0.700203 -0.396643 0.593619 -0.700208 -0.139282 0.700218 -0.700211 -0.139281 0.700217 -0.700212 -0.139281 -0.700215 -0.700215 -0.139281 -0.700216 -0.700213 -0.396643 -0.593616 -0.70021 -0.396645 -0.593622 -0.700204 -0.593625 -0.396649 -0.700199 -0.593618 -0.39664 -0.70021 -0.700219 -0.139283 -0.70021 -0.700211 -0.139278 -0.700219 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.876634 0.389418 0.282605 -0.652512 0.736942 0.176479 -0.734538 0.562077 0.380163 -0.668834 0.649162 0.362283 -0.692548 0.630868 0.349833 -0.719296 0.594668 0.359143 -0.639575 0.702565 0.312002 -0.635508 0.699573 0.326691 -0.727792 0.685795 0.00190362 -0.704168 0.709946 -0.0111024 -0.671818 0.740263 0.0259117 -0.672748 0.739217 0.031112 -0.697226 0.716851 0.000862158 -0.693157 0.720388 -0.0239832 -0.690475 0.72301 -0.0223687 -0.767783 0.640152 0.0267513 -0.794577 0.605713 0.0419552 -0.866145 0.498244 0.0393157 -0.862392 0.504003 0.0475478 -0.851249 0.521462 0.0587551 -0.865716 0.49884 0.0411747 -0.865394 0.498972 0.0460505 -0.884122 0.466797 0.02071 -0.870068 0.476564 0.125969 -0.891734 0.445089 0.0818883 -0.864334 0.452375 0.219737 -0.865172 0.45145 0.218335 -0.875481 0.384631 0.292561 -0.822744 0.487283 0.292655 -0.82368 0.435996 0.362573 -0.71367 0.683483 0.153382 -0.727112 0.684797 0.0485923 -0.739205 0.672473 0.0368267 -0.741059 0.671372 0.00956983 -0.755657 0.654966 0.0012261 -0.641625 0.722037 0.258802 -0.63589 0.723145 0.269641 -0.693986 0.664121 0.278077 -0.679224 0.655926 0.329267 -0.653005 0.657712 0.3755 -0.665348 0.741465 0.0868456 -0.638304 0.756024 0.144899 -0.713892 0.683174 0.153728 -0.691162 0.673551 0.261961 -0.764324 0.585295 0.270628 -0.733115 0.569499 0.371771 -0.806445 0.497496 0.319599 -0.832462 0.550565 0.0623229 -0.79352 0.607031 0.0428836 -0.793776 0.606946 0.0392004 -0.804469 0.591381 0.0556608 -0.797777 0.59099 0.119512 -0.807208 0.567324 0.162969 -0.777858 0.591239 0.213011 -0.76431 0.585363 0.270519 -0.849842 0.448597 0.27664 -0.808767 0.481163 0.338199 -0.886437 0.383149 0.259666 -0.878894 0.390829 0.273492 -0.739454 -0.672371 -0.0335332 -0.72283 -0.591915 -0.356584 -0.693199 -0.612225 -0.380337 -0.688147 -0.649614 -0.323195 -0.6674 -0.727338 -0.159864 -0.682604 -0.693083 -0.231706 -0.683409 -0.697032 -0.217022 -0.684843 -0.667731 -0.291764 -0.739709 -0.597392 -0.309765 -0.704661 -0.553559 -0.443875 -0.694841 -0.555278 -0.457015 -0.735383 -0.672753 -0.0813366 -0.729724 -0.669215 -0.140193 -0.728729 -0.669459 -0.144148 -0.737256 -0.621688 -0.264494 -0.696067 -0.617634 -0.366085 -0.677762 -0.718979 0.153972 -0.449643 -0.880953 0.147458 -0.582099 -0.802068 0.133594 -0.666805 -0.736212 0.115598 -0.704308 -0.704831 0.0846376 -0.71706 -0.695242 0.0496317 -0.723449 -0.69 0.0228313 -0.72328 -0.690523 -0.00662012 -0.726852 -0.686631 -0.0149736 -0.732156 -0.679851 -0.0418422 -0.641011 -0.71187 0.286959 -0.646915 -0.709683 0.279019 -0.635907 -0.697759 0.32978 -0.619481 -0.697512 0.360167 -0.590992 -0.712709 0.377856 -0.581588 -0.726744 0.365511 -0.579962 -0.739168 0.342453 -0.587733 -0.715458 0.377743 -0.59064 -0.711472 0.380725 -0.58752 -0.713875 0.381056 -0.585907 -0.752143 0.301652 -0.604291 -0.758986 0.242432 -0.605741 -0.754107 0.253775 -0.718818 -0.695181 0.00497754 -0.659311 -0.748589 0.0701604 -0.60859 -0.773984 0.174835 -0.655545 -0.751289 -0.0763265 -0.655869 -0.754799 -0.0106761 -0.637158 -0.768163 -0.062886 -0.626197 -0.773582 0.0972017 -0.640994 -0.757828 0.121754 -0.619613 -0.745912 0.244327 -0.624932 -0.730088 0.276463 -0.598948 -0.71056 0.369278 -0.596129 -0.714851 0.36554 -0.696344 -0.553731 -0.456605 -0.667827 -0.609066 -0.427839 -0.694889 -0.646427 -0.315056 -0.674562 -0.700694 -0.232366 -0.681452 -0.716609 -0.148644 -0.649218 -0.758081 -0.061886 -0.666127 -0.745739 -0.0121464 -0.654112 -0.746305 0.12315 -0.671107 -0.725343 0.153275 -0.646973 -0.711923 0.273115 -0.676669 -0.681225 0.279376 -0.932343 -0.318309 0.171512 -0.947406 -0.288917 0.137655 -0.976371 -0.204971 0.0684548 -0.98485 -0.171467 0.0258782 -0.993661 -0.0750876 -0.0836693 -0.993486 -0.0701483 -0.0898057 -0.982916 -0.118972 -0.140434 -0.992851 -0.104124 -0.0583524 -0.989549 -0.136863 -0.045403 -0.988984 -0.14119 -0.0444471 -0.959246 -0.282097 0.0163723 -0.966869 -0.254561 0.0190495 -0.98045 -0.196714 0.004553 -0.957817 -0.284639 0.039598 -0.958356 -0.284855 0.0202635 -0.957225 -0.28914 0.0108955 -0.954302 -0.298805 0.00472142 -0.97398 -0.226363 -0.0111141 -0.961596 -0.267366 0.0620352 -0.95273 -0.292467 0.0822753 -0.994537 -0.10356 0.0130644 -0.968197 -0.204539 0.144078 -0.930017 -0.322006 0.177144 -0.91965 -0.32677 0.217864 -0.979659 -0.125121 0.156887 -0.959458 -0.236786 0.152882 -0.953758 -0.257528 0.155002 -0.94987 -0.269781 0.158002 -0.971309 -0.199825 0.128952 -0.98174 -0.160258 0.10249 -0.938129 -0.345391 0.0248848 -0.954628 -0.291794 0.0595038 -0.97528 -0.220922 -0.00480759 -0.993291 -0.114732 -0.014494 -0.995024 -0.0940547 -0.0328705 -0.994312 -0.0992249 -0.0387008 -0.995669 -0.0675487 -0.0638739 0 0 1 0 0 1 -0.00109431 0.00169954 0.999998 -0.000192287 0.00121292 0.999999 0.000996049 2.53319e-05 1 -0.00016761 -1.7324e-06 1 0 0 1 -0.0014028 -0.000903259 0.999999 -0.000971215 -0.000103763 1 -0.00161404 0.000568287 0.999999 -0.00104531 -8.09855e-07 1 -0.000165643 -0.000157995 1 0.00848485 0.0093577 0.99992 -0.000111754 -0.000953598 1 -0.000484818 -0.00132646 0.999999 -4.62951e-05 -8.09645e-05 1 0.197782 0.0115754 0.980178 0.0130109 -1.75509e-06 0.999915 0.0107712 0.000507183 0.999942 0.0563828 0.00113569 0.998409 0.0348492 0.00249782 0.999389 0.105164 -0.000774444 0.994455 0.078659 0.00361119 0.996895 0.135556 0.00673819 0.990747 0.683027 0.0368133 0.729465 0.166858 0.0151225 0.985865 0.226975 0.0132166 0.973811 0.29957 0.0182359 0.9539 0.280775 0.019004 0.959585 0.364675 0.0197331 0.930926 0.351972 0.020586 0.935784 0.45892 0.0285635 0.888018 0.441038 0.0308947 0.896957 0.557088 0.0270072 0.830014 0.508208 0.0343883 0.860547 0.609891 0.0287615 0.791963 0.587658 0.0320134 0.808476 0.64692 0.033571 0.761819 0.68973 0.0355691 0.723193 0.737181 0.033619 0.674858 0.745068 0.0343692 0.666102 0.767771 0.0338994 0.639827 0.779753 0.0348478 0.625116 0.795027 0.0329576 0.605678 0.828821 0.0349574 0.558421 0.821378 0.0426477 0.568788 0.85118 0.022967 0.524372 0.841352 0.0372506 0.539203 0.858693 0.0209669 0.512062 0.830466 0.0364574 0.555875 0.536772 -0.362368 0.761948 0.814676 0.0422969 0.578372 0.84251 0.0567244 0.535686 0.849985 0.0369401 0.525511 0.847319 0.033552 0.530023 0.850873 0.0442 0.523509 0.850986 0.0445158 0.523298 0 0 1 0 0 1 -0.000903539 0.00140326 0.999999 -0.000160538 0.00100235 1 0.000818972 2.33807e-05 1 -0.000111748 1.7325e-06 1 0 0 1 -0.00168678 -0.00108611 0.999998 -0.00116872 -0.00012641 0.999999 -0.00133281 0.000469266 0.999999 -0.000862993 -8.09843e-07 1 -0.00014598 -0.000128917 1 0.0101755 0.011225 0.999885 -0.000186247 -0.00120317 0.999999 -0.00057994 -0.00159662 0.999999 -4.62953e-05 -8.09646e-05 1 0.0230279 1.77213e-06 0.999735 0.0235986 -0.000198602 0.999722 0.106878 -0.00430622 0.994263 0.124821 -0.0081099 0.992146 0.170794 -0.00897335 0.985266 0.207175 -0.0122173 0.978228 0.236821 -0.0124762 0.971473 0.269386 -0.0169755 0.962883 0.354186 -0.0197466 0.934967 0.37617 -0.0246896 0.926222 0.474789 -0.026826 0.879691 0.498323 -0.0251738 0.866626 0.535807 -0.0305137 0.843789 0.577904 -0.0317844 0.815486 0.626275 -0.0311839 0.778978 0.631067 -0.0322617 0.775057 0.695659 -0.034667 0.717536 0.720729 -0.0319504 0.69248 0.740059 -0.0344773 0.671658 0.764315 -0.0339872 0.643946 0.777458 -0.0331219 0.628063 0.78821 -0.034554 0.614436 0.809938 -0.0328932 0.585592 0.815101 -0.0219266 0.578904 0.84703 -0.00350631 0.531533 0.852815 -0.0272146 0.521504 0.850461 -0.0302708 0.525166 0.854054 -0.0196696 0.519812 0.845444 -0.0402948 0.532542 0.831166 -0.0313686 0.555138 0.811326 0.00716469 0.58455 0.849847 -0.0444757 0.525149 0.836906 -0.0235786 0.546839 0.854366 -0.0409812 0.518054 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0.19509 -0.980785 0 0.19509 -0.980785 0 0.555569 -0.83147 0 0.555569 -0.83147 0 0.831469 -0.555571 0 0.831469 -0.555571 0 0.980785 -0.195092 0 0.980785 -0.195092 0 1 0 0 1 0 0 0.980785 0.195092 0 0.980785 0.195092 0 0.831469 0.555571 0 0.831469 0.555571 0 0.555571 0.831469 0 0.555571 0.831469 0 0.19509 0.980785 0 0.19509 0.980785 0 0 1 0 0 1 0 -0.195089 0.980786 0 -0.195089 0.980786 0 -0.555572 0.831468 0 -0.555572 0.831468 0 -0.831469 0.555571 0 -0.831469 0.555571 0 -0.980785 0.195092 0 -0.980785 0.195092 0 -1 0 0 -1 0 0 -0.980785 -0.195092 0 -0.980785 -0.195092 0 -0.831469 -0.555571 0 -0.831469 -0.555571 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.195089 -0.980786 0 -0.195089 -0.980786 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.965924 0.258828 0 0.965924 0.258828 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965924 0.258828 0 -0.965924 0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.508595 -0.508592 0.694741 0.50859 -0.508592 0.694746 0.694745 -0.186164 0.694746 0.694746 -0.186163 0.694746 0.694746 0.186163 0.694746 0.694745 0.186163 0.694746 0.508592 0.508589 0.694746 0.508592 0.508594 0.694742 0.186156 0.69475 0.694744 0.186157 0.694747 0.694747 -0.186158 0.694746 0.694746 -0.186157 0.694746 0.694747 -0.508589 0.508586 0.69475 -0.508584 0.508586 0.694754 -0.694734 0.18616 0.694758 -0.694747 0.186155 0.694747 -0.694746 -0.186164 0.694746 -0.694737 -0.186153 0.694757 -0.508586 -0.508583 0.694755 -0.508586 -0.508588 0.69475 -0.186158 -0.694746 0.694747 -0.186157 -0.694747 0.694747 0.186155 -0.694747 0.694747 0.186158 -0.694749 0.694744 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.965927 -0.258815 0 0.965927 -0.258815 0 0.965927 0.258814 0 0.965927 0.258814 0 0.707105 0.707109 0 0.707105 0.707109 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707105 0.707109 0 -0.707105 0.707109 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.508589 -0.508592 0.694746 0.50859 -0.508592 0.694746 0.694749 -0.186154 0.694745 0.694747 -0.186155 0.694747 0.694747 0.186153 0.694747 0.694749 0.186155 0.694745 0.508589 0.508592 0.694745 0.508589 0.508591 0.694746 0.186157 0.694748 0.694745 0.186157 0.694747 0.694747 -0.186156 0.694747 0.694747 -0.186158 0.694748 0.694745 -0.508589 0.508592 0.694746 -0.50859 0.508592 0.694746 -0.694749 0.186154 0.694745 -0.694747 0.186155 0.694747 -0.694747 -0.186154 0.694747 -0.694748 -0.186156 0.694745 -0.508589 -0.508592 0.694745 -0.508589 -0.508591 0.694746 -0.186157 -0.694748 0.694745 -0.186157 -0.694747 0.694747 0.186156 -0.694747 0.694747 0.186158 -0.694748 0.694745 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.965923 0.258828 0 0.965923 0.258828 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.508595 -0.508592 0.694742 0.50859 -0.508591 0.694746 0.694745 -0.186163 0.694746 0.694746 -0.186163 0.694746 0.694746 0.186164 0.694746 0.694745 0.186163 0.694746 0.508592 0.508589 0.694746 0.508592 0.508593 0.694742 0.186156 0.694749 0.694745 0.186157 0.694747 0.694747 -0.186158 0.694746 0.694746 -0.186157 0.694745 0.694748 -0.508588 0.508586 0.694751 -0.508584 0.508585 0.694754 -0.694734 0.18616 0.694758 -0.694747 0.186155 0.694747 -0.694746 -0.186164 0.694746 -0.694737 -0.186153 0.694757 -0.508586 -0.508583 0.694755 -0.508586 -0.508587 0.694751 -0.186158 -0.694745 0.694748 -0.186157 -0.694747 0.694746 0.186156 -0.694747 0.694747 0.186157 -0.694748 0.694745 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965927 -0.258815 0 0.965927 -0.258815 0 0.965927 0.258815 0 0.965927 0.258815 0 0.707105 0.707108 0 0.707105 0.707108 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.508589 -0.508591 0.694747 0.50859 -0.508591 0.694746 0.694749 -0.186154 0.694745 0.694747 -0.186155 0.694747 0.694747 0.186154 0.694747 0.694748 0.186156 0.694745 0.50859 0.508592 0.694745 0.508589 0.50859 0.694747 0.186157 0.694747 0.694746 0.186157 0.694747 0.694747 -0.186157 0.694747 0.694747 -0.186157 0.694747 0.694746 -0.508589 0.508591 0.694747 -0.50859 0.508591 0.694746 -0.694749 0.186154 0.694745 -0.694747 0.186155 0.694747 -0.694747 -0.186154 0.694747 -0.694748 -0.186156 0.694745 -0.508589 -0.508592 0.694746 -0.508589 -0.50859 0.694747 -0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694746 0.186157 -0.694747 0.694746 0.186157 -0.694747 0.694747 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.965923 0.258828 0 0.965923 0.258828 0 0.70711 0.707103 0 0.70711 0.707103 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.70711 0.707103 0 -0.70711 0.707103 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258824 -0.965925 0 -0.258824 -0.965925 0 0.508593 -0.508591 0.694743 0.50859 -0.50859 0.694746 0.694745 -0.186164 0.694746 0.694746 -0.186163 0.694746 0.694746 0.186164 0.694746 0.694745 0.186163 0.694746 0.508593 0.508588 0.694746 0.508593 0.508593 0.694741 0.186156 0.69475 0.694744 0.186157 0.694747 0.694747 -0.186158 0.694746 0.694746 -0.186157 0.694746 0.694747 -0.50859 0.508585 0.69475 -0.508584 0.508584 0.694754 -0.694734 0.186161 0.694758 -0.694747 0.186155 0.694747 -0.694746 -0.186164 0.694746 -0.694737 -0.186153 0.694757 -0.508586 -0.508583 0.694755 -0.508586 -0.508586 0.694752 -0.186159 -0.694742 0.69475 -0.186157 -0.694747 0.694747 0.186158 -0.694746 0.694746 0.186157 -0.694746 0.694747 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.965927 -0.258815 0 0.965927 -0.258815 0 0.965927 0.258815 0 0.965927 0.258815 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.508588 -0.50859 0.694748 0.50859 -0.50859 0.694746 0.694749 -0.186154 0.694745 0.694747 -0.186155 0.694747 0.694747 0.186154 0.694747 0.694748 0.186156 0.694745 0.50859 0.50859 0.694746 0.50859 0.50859 0.694746 0.186157 0.694748 0.694745 0.186157 0.694747 0.694747 -0.186156 0.694747 0.694747 -0.186158 0.694748 0.694745 -0.50859 0.50859 0.694746 -0.50859 0.50859 0.694746 -0.694749 0.186154 0.694745 -0.694747 0.186155 0.694747 -0.694747 -0.186154 0.694747 -0.694748 -0.186156 0.694745 -0.508589 -0.508592 0.694745 -0.508589 -0.508589 0.694748 -0.186158 -0.694744 0.694749 -0.186157 -0.694747 0.694747 0.186159 -0.694746 0.694746 0.186157 -0.694745 0.694748 -0.707102 0 0.707112 -0.707102 0 0.707112 -0.707102 0 0.707112 -0.707102 0 0.707112 -0.700209 -0.139281 0.70022 -0.700219 -0.139279 0.700211 -0.593615 -0.396642 0.700212 -0.593607 -0.396641 0.700219 -0.396638 -0.59361 0.700218 -0.396641 -0.593611 0.700215 -0.13928 -0.700215 0.700214 -0.139282 -0.700217 0.700212 -0.13928 0.700215 0.700215 -0.13928 0.700215 0.700214 -0.396641 0.593612 0.700215 -0.396641 0.593611 0.700216 -0.59361 0.396639 0.700217 -0.593613 0.396645 0.700211 -0.700217 0.139283 0.700211 -0.70021 0.139277 0.70022 0 -0.707109 0.707104 0 -0.707109 0.707104 0 -0.707109 0.707104 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0.139282 -0.700217 0.700212 0.139282 -0.700215 0.700213 0.39664 -0.593615 0.700212 0.39664 -0.593612 0.700215 0.593613 -0.39664 0.700214 0.593615 -0.396643 0.700211 0.700217 -0.139283 0.700211 0.700215 -0.139281 0.700215 0.700214 0.139282 0.700214 0.700218 0.139281 0.700211 0.593615 0.396642 0.700212 0.593613 0.396642 0.700213 0.396641 0.593614 0.700213 0.396641 0.593615 0.700212 0.139282 0.700216 0.700213 0.139281 0.700215 0.700215 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.139281 0.70021 -0.700219 0.13928 0.700212 -0.700218 0.39664 0.593613 -0.700214 0.396639 0.593608 -0.700219 0.593609 0.396638 -0.700219 0.593611 0.396641 -0.700216 0.700214 0.139282 -0.700215 0.700206 0.139278 -0.700224 0.700206 -0.139281 -0.700223 0.700215 -0.13928 -0.700215 0.593612 -0.396639 -0.700216 0.593609 -0.396638 -0.700219 0.396637 -0.59361 -0.700219 0.396643 -0.593616 -0.70021 0.139282 -0.700216 -0.700213 0.139281 -0.700215 -0.700215 0 0.707102 -0.707111 0 0.707102 -0.707111 0 0.707102 -0.707111 0 0.707102 -0.707111 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 -0.700206 0.139281 -0.700223 -0.700215 0.13928 -0.700215 -0.593612 0.39664 -0.700216 -0.593608 0.396639 -0.700219 -0.396639 0.593609 -0.700219 -0.396634 0.593605 -0.700225 -0.139279 0.700209 -0.700221 -0.13928 0.70021 -0.700219 -0.13928 -0.700215 -0.700215 -0.139281 -0.700213 -0.700217 -0.396637 -0.593608 -0.700221 -0.396637 -0.59361 -0.700219 -0.593609 -0.396638 -0.700219 -0.593612 -0.39664 -0.700216 -0.700214 -0.139282 -0.700215 -0.700206 -0.139278 -0.700224 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.980786 -0.195088 0 0.980786 -0.195088 0 0.831468 -0.555573 0 0.831468 -0.555573 0 0.55557 -0.83147 0 0.55557 -0.83147 0 0.195092 -0.980785 0 0.195092 -0.980785 0 0 -1 0 0 -1 0 -0.195092 -0.980785 0 -0.195092 -0.980785 0 -0.55557 -0.83147 0 -0.55557 -0.83147 0 -0.831469 -0.555571 0 -0.831469 -0.555571 0 -0.980785 -0.195092 0 -0.980785 -0.195092 0 -1 0 0 -1 0 0 -1 0 0 -0.195089 0.980785 0 -0.195089 0.980785 0 -0.555572 0.831468 0 -0.555572 0.831468 0 -0.831469 0.555572 0 -0.831469 0.555572 0 -0.980785 0.195093 0 -0.980785 0.195093 0 0 1 0 0 1 0 0.980786 0.195088 0 0.980786 0.195088 0 0.831469 0.555572 0 0.831469 0.555572 0 0.55557 0.83147 0 0.55557 0.83147 0 0.195091 0.980785 0 0.195091 0.980785 0 1 0 0 1 0 0 1 0 0 -0.980785 0.195092 0 -0.980785 0.195092 0 -0.83147 0.55557 0 -0.83147 0.55557 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.19509 0.980785 0 -0.19509 0.980785 0 0 1 0 0 1 0 0.195091 0.980785 0 0.195091 0.980785 0 0.55557 0.83147 0 0.55557 0.83147 0 0.831468 0.555572 0 0.831468 0.555572 0 0.980786 0.195088 0 0.980786 0.195088 0 1 0 0 1 0 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0 -1 0 0 -1 0 -0.980785 -0.195093 0 -0.980785 -0.195093 0 -0.831469 -0.555572 0 -0.831469 -0.555572 0 -0.555572 -0.831468 0 -0.555572 -0.831468 0 -0.195089 -0.980785 0 -0.195089 -0.980785 0 -1 0 0 -1 0 0 0.0949378 -0.995483 0 0.0949378 -0.995483 0 -0.12108 -0.992643 0 -0.12108 -0.992643 0 -0.210411 -0.977613 0 -0.190857 -0.977137 -0.0936836 -0.174387 -0.984677 0 -0.141213 -0.989979 0 -0.118705 -0.988868 -0.0897191 -0.104781 -0.994495 0 -0.0713168 -0.997454 0 -0.0458797 -0.995708 -0.0803764 -0.0346581 -0.999399 0 0.100634 -0.994924 0 0.105607 -0.993006 -0.0527916 0.0691851 -0.997604 0 0.0273763 -0.999625 0 0.0355088 -0.995786 -0.0845532 -0.00106845 -0.999999 0 0.0990044 -0.995087 0 0.0685105 -0.994824 0.0750388 0.0304038 -0.999538 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0.0304038 0.999538 0 0.0845763 0.990676 0.106804 0.0686634 0.997045 0.0344605 0.129398 0.991593 0 0.105755 0.994392 0 0.10053 0.993897 -0.0454074 0.0691851 0.997604 0 0.0356364 0.999365 0 0.0273174 0.997471 -0.0656191 -0.00106832 0.999999 0 -0.0346581 0.999399 0 -0.0458797 0.995708 -0.0803761 -0.0713167 0.997454 0 -0.104781 0.994495 0 -0.118705 0.988868 -0.089719 -0.141213 0.989979 0 -0.174387 0.984677 0 -0.190857 0.977137 -0.0936836 -0.210411 0.977613 0 -0.12108 0.992643 0 -0.12108 0.992643 0 0.0949378 0.995483 0 0.0949378 0.995483 0 0.201912 0.979404 0 0.201912 0.979404 -4.49868e-07 0.201912 0.979404 0 0.201912 0.979404 2.31355e-07 0.365571 0.930784 0 0.365571 0.930784 0 0.656461 0.75436 0 0.656461 0.75436 0 0.871371 0.490624 0 0.871371 0.490624 0 0.985426 0.170106 0 0.985426 0.170106 0 1 0 0 1 0 0 0.985426 -0.170106 0 0.985426 -0.170106 0 0.871371 -0.490624 0 0.871371 -0.490624 0 0.656461 -0.75436 0 0.656461 -0.75436 0 0.365571 -0.930784 0 0.365571 -0.930784 0 0.201912 -0.979404 0 0.201912 -0.979404 -1.4198e-07 0.201912 -0.979404 2.31355e-07 0.201912 -0.979404 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707114 0.707099 0 -0.707114 0.707099 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707114 -0.707099 0 -0.707114 -0.707099 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.508589 -0.508591 0.694746 0.508588 -0.508592 0.694746 0.694746 -0.186157 0.694747 0.694746 -0.186158 0.694747 0.694746 0.186157 0.694747 0.694746 0.186158 0.694747 0.508589 0.508591 0.694747 0.508588 0.508592 0.694746 0.186156 0.694747 0.694746 0.186157 0.694747 0.694747 -0.186156 0.694747 0.694747 -0.186157 0.694747 0.694746 -0.508597 0.508586 0.694745 -0.508591 0.508588 0.694747 -0.694746 0.186157 0.694747 -0.694746 0.186158 0.694747 -0.694746 -0.186157 0.694747 -0.694746 -0.186158 0.694747 -0.508594 -0.508584 0.694748 -0.508592 -0.50859 0.694745 -0.186156 -0.694747 0.694746 -0.186157 -0.694747 0.694746 0.186156 -0.694747 0.694747 0.186157 -0.694747 0.694746 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707114 0.707099 0 -0.707114 0.707099 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707114 -0.707099 0 -0.707114 -0.707099 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.508589 -0.508591 0.694746 0.508588 -0.508592 0.694746 0.694746 -0.186157 0.694747 0.694746 -0.186158 0.694747 0.694746 0.186157 0.694747 0.694746 0.186158 0.694747 0.508589 0.508591 0.694747 0.508588 0.508592 0.694746 0.186156 0.694747 0.694746 0.186157 0.694747 0.694747 -0.186156 0.694747 0.694747 -0.186157 0.694747 0.694746 -0.508597 0.508586 0.694745 -0.508591 0.508588 0.694747 -0.694746 0.186157 0.694747 -0.694746 0.186158 0.694747 -0.694746 -0.186157 0.694747 -0.694746 -0.186158 0.694747 -0.508594 -0.508584 0.694748 -0.508592 -0.50859 0.694745 -0.186156 -0.694747 0.694746 -0.186157 -0.694747 0.694746 0.186156 -0.694747 0.694747 0.186157 -0.694747 0.694746 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.25882 0.965925 0 -0.25882 0.965925 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.25882 -0.965925 0 -0.25882 -0.965925 0 0.508589 -0.50859 0.694747 0.508589 -0.50859 0.694747 0.694746 -0.186157 0.694747 0.694748 -0.186155 0.694746 0.694747 0.186158 0.694746 0.694747 0.186155 0.694747 0.508589 0.508591 0.694747 0.508589 0.50859 0.694747 0.186156 0.694747 0.694747 0.186156 0.694747 0.694747 -0.186158 0.694746 0.694746 -0.186157 0.694746 0.694747 -0.508589 0.50859 0.694747 -0.508589 0.50859 0.694747 -0.694746 0.186157 0.694747 -0.694748 0.186155 0.694746 -0.694747 -0.186158 0.694746 -0.694747 -0.186155 0.694747 -0.508589 -0.508591 0.694747 -0.508589 -0.50859 0.694747 -0.186158 -0.694746 0.694747 -0.186157 -0.694747 0.694746 0.186156 -0.694747 0.694747 0.186156 -0.694747 0.694747 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.25882 0.965925 0 -0.25882 0.965925 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.25882 -0.965925 0 -0.25882 -0.965925 0 0.508589 -0.50859 0.694747 0.508589 -0.50859 0.694747 0.694746 -0.186157 0.694747 0.694748 -0.186155 0.694746 0.694747 0.186158 0.694746 0.694747 0.186155 0.694747 0.508589 0.508591 0.694747 0.508589 0.50859 0.694747 0.186156 0.694747 0.694747 0.186156 0.694747 0.694747 -0.186158 0.694746 0.694746 -0.186157 0.694746 0.694747 -0.508589 0.50859 0.694747 -0.508589 0.50859 0.694747 -0.694746 0.186157 0.694747 -0.694748 0.186155 0.694746 -0.694747 -0.186158 0.694746 -0.694747 -0.186155 0.694747 -0.508589 -0.508591 0.694747 -0.508589 -0.50859 0.694747 -0.186158 -0.694746 0.694747 -0.186157 -0.694747 0.694746 0.186156 -0.694747 0.694747 0.186156 -0.694747 0.694747 -0.0422458 -0.999107 0 -0.195039 -0.980527 0.0229654 -0.236349 -0.971668 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.831469 -0.555571 0 -0.831469 -0.555571 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -0.0422458 0.999107 0 -0.195039 0.980527 0.0229654 -0.236349 0.971668 0 -0.555571 0.831469 0 -0.555571 0.831469 0 -0.831469 0.555571 0 -0.831469 0.555571 0 -0.980785 0.195091 0 -0.980785 0.195091 0 -0.163286 -0.708259 -0.686809 -0.162521 -0.706539 -0.68876 0.115581 -0.706201 -0.698513 0.126905 -0.724701 -0.677277 0.130026 -0.740653 -0.659186 0.103895 -0.698195 -0.708329 0.0767454 -0.707935 -0.702096 0.0747985 -0.703317 -0.706931 -0.164379 -0.709337 -0.685434 -0.148795 -0.691331 -0.707052 -0.113237 -0.698184 -0.706907 -0.129834 -0.733112 -0.6676 -0.0998577 -0.700058 -0.707069 -0.0661032 -0.704211 -0.706907 -0.0771584 -0.732322 -0.676573 -0.0504302 -0.705329 -0.707084 -0.0186713 -0.70706 -0.706907 -0.0252417 -0.72787 -0.68525 -0.000755481 -0.707118 -0.707095 0.0288448 -0.706718 -0.706907 0.0256696 -0.719862 -0.693642 0.0489217 -0.705417 -0.707102 0.130026 0.740653 -0.659186 0.126905 0.724701 -0.677277 0.115581 0.706201 -0.698513 -0.169521 0.697853 -0.695891 -0.167354 0.694467 -0.699792 0.105379 0.699222 -0.707095 0.0983554 0.700234 -0.707106 0.0767454 0.707935 -0.702096 0.0747985 0.703317 -0.706931 0.0489217 0.705417 -0.707102 0.0292913 0.717657 -0.69578 0.0252039 0.706801 -0.706964 -0.000755388 0.707118 -0.707095 -0.0190857 0.722753 -0.690843 -0.0245109 0.706795 -0.706993 -0.0504301 0.705329 -0.707084 -0.0678788 0.723127 -0.687372 -0.0741008 0.703301 -0.707019 -0.0998577 0.700058 -0.707069 -0.116572 0.718746 -0.68543 -0.123321 0.696336 -0.707042 -0.14471 0.692166 -0.707082 -0.14771 0.686292 -0.712169 -0.164255 0.692015 -0.702947 0.0711828 0.703754 0.706868 0.0711828 0.703755 0.706868 0.0193645 0.70708 0.706868 0.0193645 0.707081 0.706868 -0.0325582 0.706596 0.706868 -0.0325581 0.706596 0.706868 -0.0843053 0.702303 0.706868 -0.0843055 0.702304 0.706867 -0.135598 0.694228 0.706867 -0.122029 0.642252 0.756718 -0.157401 0.689372 0.7071 0.0486387 0.70627 0.70627 0.0486387 0.706271 0.706269 0.0673279 0.705976 0.705028 0.0673278 0.705976 0.705028 -0.0858672 0.703961 0.705029 -0.0858667 0.703962 0.705028 0 0.707107 0.707106 0 0.707107 0.707106 0 0.707107 0.707106 0.142774 0.692544 0.707106 0.142774 0.692544 0.707106 0.142774 0.692544 0.707106 0.142774 0.692544 0.707106 -0.139281 0.700215 0.700214 -0.139282 0.700215 0.700214 -0.39664 0.593612 0.700215 -0.396641 0.593617 0.70021 -0.593617 0.396644 0.700209 -0.593616 0.396641 0.700212 -0.700218 0.139283 0.700211 -0.70021 0.139277 0.70022 0.701897 0.121163 0.701897 0.701899 0.121162 0.701896 0.62066 0.349462 0.701896 0.620658 0.349462 0.701898 0.467582 0.537314 0.701898 0.467583 0.537314 0.701897 0.260388 0.662977 0.701897 0.260388 0.662977 0.701897 -0.707102 0 0.707112 -0.707102 0 0.707112 -0.707102 0 0.707112 0.707107 0 0.707107 0.707107 0 0.707107 -0.700209 -0.139281 0.70022 -0.700219 -0.139279 0.700211 -0.593615 -0.396642 0.700211 -0.593618 -0.396643 0.700209 -0.396643 -0.593616 0.70021 -0.396638 -0.593613 0.700216 -0.139281 -0.700215 0.700214 -0.139282 -0.700215 0.700214 0.260388 -0.662978 0.701896 0.260388 -0.662977 0.701897 0.467583 -0.537315 0.701897 0.467582 -0.537314 0.701898 0.620658 -0.349461 0.701898 0.62066 -0.349463 0.701896 0.701899 -0.121163 0.701896 0.701897 -0.121162 0.701897 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.707107 0.707106 0.142774 -0.692544 0.707106 0.142774 -0.692544 0.707105 0.142774 -0.692544 0.707106 0.0486387 -0.706271 0.706269 0.0486387 -0.70627 0.70627 -0.0858674 -0.703962 0.705028 -0.0858665 -0.703961 0.705029 0.0673279 -0.705976 0.705028 0.0673278 -0.705976 0.705028 -0.135598 -0.694228 0.706867 -0.135598 -0.694228 0.706867 -0.0843054 -0.702304 0.706867 -0.0843054 -0.702303 0.706868 -0.0325581 -0.706596 0.706868 -0.0325581 -0.706596 0.706868 0.0193645 -0.70708 0.706868 0.0193646 -0.707081 0.706868 0.0711828 -0.703755 0.706868 0.0711827 -0.703754 0.706868 0.258817 -0.965926 0 0.258817 -0.965926 0 0.7071 -0.707113 0 0.7071 -0.707113 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.965927 0.258813 0 0.965927 0.258813 0 0.7071 0.707113 0 0.7071 0.707113 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707119 0.707094 0 -0.707119 0.707094 0 -0.965918 0.258849 0 -0.965918 0.258849 0 -0.965918 -0.258849 0 -0.965918 -0.258849 0 -0.707119 -0.707094 0 -0.707119 -0.707094 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258827 -0.965924 0 0.258827 -0.965924 0 0.7071 -0.707113 0 0.7071 -0.707113 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.965927 0.258813 0 0.965927 0.258813 0 0.7071 0.707113 0 0.7071 0.707113 0 0.258827 0.965924 0 0.258827 0.965924 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.7071 0.707113 0 -0.7071 0.707113 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.7071 -0.707113 0 -0.7071 -0.707113 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.99863 0 -0.052336 -0.99863 0 -0.052336 -0.995559 0.0783525 -0.0521751 -0.996064 0.0712392 -0.0527432 -0.983091 0.175544 -0.0521219 -0.984309 0.16852 -0.0523175 -0.966278 0.252144 -0.0522457 -0.969734 0.23832 -0.053094 -0.936947 0.34566 -0.0514787 -0.941752 0.332223 -0.0522613 -0.906901 0.418085 -0.0522959 -0.9156 0.398564 -0.0531377 -0.861637 0.505015 -0.0504088 -0.87645 0.478579 -0.0528932 -0.819286 0.571018 -0.0520534 -0.799501 0.598494 -0.0510239 -0.759303 0.648509 -0.0538085 -0.598497 0.799499 -0.0510237 -0.64851 0.759302 -0.0538081 -0.680482 0.730896 -0.0523029 -0.73089 0.680488 -0.052303 -0.0712413 0.996092 -0.0522029 -0.0783504 0.995531 -0.0527193 -0.168539 0.984313 -0.052182 -0.175561 0.983077 -0.0523258 -0.238321 0.969778 -0.0522839 -0.252137 0.966243 -0.052926 -0.33224 0.941776 -0.0517206 -0.345645 0.936907 -0.0522957 -0.398568 0.915645 -0.0523276 -0.418073 0.906883 -0.052704 -0.478621 0.876529 -0.051171 -0.504955 0.861534 -0.0527216 -0.571016 0.819287 -0.0520533 0 0.99863 -0.0523359 0 0.99863 -0.0523359 0.0783527 0.995559 -0.052175 0.0712393 0.996064 -0.052743 0.175557 0.983088 -0.0521217 0.168534 0.984306 -0.0523172 0.252148 0.966277 -0.0522454 0.238313 0.969736 -0.0530943 0.34566 0.936947 -0.051479 0.332231 0.941749 -0.0522612 0.418082 0.906903 -0.0522957 0.398551 0.915605 -0.053138 0.505015 0.861637 -0.0504086 0.478574 0.876452 -0.0528934 0.571016 0.819287 -0.0520536 0.5985 0.799496 -0.0510239 0.648505 0.759306 -0.0538079 0.799501 0.598494 -0.0510239 0.759307 0.648504 -0.0538082 0.73089 0.680488 -0.0523025 0.680482 0.730896 -0.0523025 0.996092 0.0712412 -0.0522024 0.995531 0.0783503 -0.0527188 0.984316 0.168521 -0.0521817 0.983075 0.175574 -0.0523262 0.969776 0.23833 -0.0522842 0.966244 0.252135 -0.0529257 0.941779 0.332232 -0.0517205 0.936907 0.345645 -0.0522959 0.915639 0.398582 -0.0523278 0.906882 0.418076 -0.052704 0.876529 0.478622 -0.0511711 0.861534 0.504955 -0.0527217 0.819286 0.571018 -0.0520534 0.99863 0 -0.0523354 0.99863 0 -0.0523354 0.99556 -0.0783525 -0.0521745 0.996064 -0.0712392 -0.0527426 0.983085 -0.175576 -0.052121 0.984309 -0.16852 -0.0523175 0.966278 -0.252144 -0.0522457 0.969734 -0.23832 -0.053094 0.936947 -0.34566 -0.0514787 0.941752 -0.332223 -0.0522613 0.906901 -0.418085 -0.0522959 0.9156 -0.398564 -0.0531377 0.861637 -0.505015 -0.0504088 0.87645 -0.478579 -0.0528932 0.819286 -0.571018 -0.0520534 0.799501 -0.598494 -0.0510239 0.759307 -0.648504 -0.0538082 0.598502 -0.799495 -0.0510238 0.648505 -0.759306 -0.0538077 0.68048 -0.730898 -0.0523025 0.73089 -0.680488 -0.0523025 0.0712413 -0.996092 -0.0522031 0.0783505 -0.995531 -0.0527194 0.16853 -0.984314 -0.0521823 0.17554 -0.983081 -0.0523258 0.238327 -0.969777 -0.0522839 0.252142 -0.966242 -0.0529259 0.332242 -0.941775 -0.0517206 0.345645 -0.936907 -0.0522956 0.398555 -0.915651 -0.0523275 0.418073 -0.906883 -0.0527042 0.478619 -0.87653 -0.0511712 0.504955 -0.861534 -0.0527219 0.571016 -0.819287 -0.0520537 0 -0.99863 -0.052336 0 -0.99863 -0.052336 -0.0783527 -0.995559 -0.0521751 -0.0712393 -0.996064 -0.0527432 -0.175547 -0.98309 -0.0521219 -0.168532 -0.984307 -0.0523172 -0.252148 -0.966277 -0.0522454 -0.238314 -0.969736 -0.0530943 -0.34566 -0.936947 -0.051479 -0.332233 -0.941748 -0.052261 -0.418082 -0.906903 -0.0522956 -0.398537 -0.915611 -0.0531384 -0.505015 -0.861637 -0.0504088 -0.478579 -0.87645 -0.0528931 -0.571016 -0.819287 -0.0520533 -0.598498 -0.799498 -0.0510236 -0.648509 -0.759302 -0.053808 -0.799501 -0.598494 -0.0510239 -0.759303 -0.648509 -0.0538085 -0.73089 -0.680488 -0.052303 -0.68048 -0.730898 -0.0523029 -0.996092 -0.0712412 -0.0522031 -0.995531 -0.0783503 -0.0527194 -0.984316 -0.168521 -0.0521823 -0.98308 -0.175543 -0.0523261 -0.969776 -0.23833 -0.0522842 -0.966244 -0.252135 -0.0529257 -0.941779 -0.332232 -0.0517205 -0.936907 -0.345645 -0.0522959 -0.915639 -0.398582 -0.0523278 -0.906882 -0.418076 -0.052704 -0.876529 -0.478622 -0.0511711 -0.861534 -0.504955 -0.0527217 -0.819286 -0.571018 -0.0520534 -0.99863 0 -0.052336 -0.99863 0 -0.052336 0.201517 0 0.979485 0.201517 0 0.979485 0.571749 0 0.820429 0.571749 0 0.820429 0.849199 0 0.528073 0.849199 0 0.528073 0.988702 0 0.149895 0.988702 0 0.149895 0.201496 0.0144099 0.979383 0.571271 0.0408592 0.819744 0.847637 0.0606279 0.527102 0.898978 0.317133 0.302103 0.926415 0.345535 0.149534 0.960152 0.235965 0.14976 0.934164 0.203212 0.29333 0.974524 0.166845 0.149888 0.986232 0.070541 0.149568 0.986239 0.0705365 0.149522 0.906536 0.394619 0.149897 0.867809 0.47386 0.149549 0.8678 0.473861 0.149593 0.791536 0.592531 0.149594 0.791533 0.592531 0.149611 0.723623 0.673723 0.149889 0.674008 0.674012 0.302359 0.203213 0.934163 0.293331 0.673718 0.72363 0.149876 0.592537 0.79153 0.149597 0.592534 0.791529 0.149615 0.473852 0.867803 0.14961 0.473857 0.867805 0.149579 0.394604 0.906537 0.149932 0.336896 0.90325 0.265784 0.328934 0.932405 0.149742 0.235957 0.960147 0.149808 0.166857 0.974515 0.14993 0.0705357 0.986226 0.149606 0.0705372 0.986228 0.149594 0.847647 0.0606265 0.527085 0.830392 0.180638 0.527085 0.830372 0.180638 0.527117 0.796213 0.296972 0.527118 0.796212 0.296972 0.527118 0.745843 0.407266 0.527117 0.745863 0.407272 0.527084 0.680311 0.509272 0.527086 0.680294 0.509264 0.527115 0.600894 0.600897 0.527114 0.600909 0.600907 0.527086 0.509274 0.680308 0.527088 0.509261 0.680296 0.527116 0.407263 0.745847 0.527114 0.407276 0.745863 0.527081 0.296981 0.796232 0.527084 0.296973 0.79622 0.527105 0.180636 0.83038 0.527104 0.180639 0.830385 0.527095 0.060625 0.84764 0.527098 0.0606243 0.847637 0.527102 0.571309 0.0408568 0.819718 0.559677 0.121751 0.819718 0.559663 0.12175 0.819728 0.536641 0.200157 0.819728 0.536637 0.200156 0.819731 0.502691 0.27449 0.81973 0.502699 0.274494 0.819724 0.458517 0.343243 0.819724 0.45853 0.34325 0.819713 0.405012 0.405011 0.819714 0.405007 0.405007 0.819718 0.343246 0.458524 0.819718 0.343255 0.458534 0.819709 0.274504 0.502712 0.819712 0.274494 0.502697 0.819725 0.200158 0.536647 0.819724 0.200156 0.536644 0.819726 0.121748 0.559668 0.819725 0.121748 0.559669 0.819724 0.0408602 0.5713 0.819724 0.0408615 0.571306 0.819719 0.201484 0.0144104 0.979386 0.197383 0.042939 0.979386 0.197386 0.0429394 0.979385 0.189267 0.0705929 0.979385 0.189274 0.0705948 0.979383 0.1773 0.0968127 0.979384 0.177292 0.0968097 0.979385 0.161711 0.121055 0.979385 0.161715 0.121057 0.979384 0.14284 0.14284 0.979384 0.142838 0.142838 0.979385 0.121056 0.161712 0.979385 0.121057 0.161713 0.979384 0.0968108 0.177296 0.979384 0.0968118 0.177297 0.979384 0.0705934 0.18927 0.979384 0.0705953 0.189273 0.979383 0.04294 0.197392 0.979384 0.0429392 0.19739 0.979384 0.0144113 0.201492 0.979384 0.0144108 0.201489 0.979385 0.0144111 -0.201489 0.979385 0.0408595 -0.571306 0.819719 0.0606248 -0.847637 0.527102 0.317146 -0.898984 0.30207 0.345531 -0.926407 0.149595 0.235959 -0.960144 0.149826 0.203213 -0.934156 0.293353 0.166852 -0.974516 0.14993 0.0705371 -0.986226 0.149606 0.0705359 -0.986228 0.149594 0.394589 -0.90654 0.149948 0.473854 -0.867804 0.149595 0.473855 -0.867801 0.14961 0.592537 -0.791527 0.149615 0.592537 -0.791533 0.149582 0.673717 -0.723634 0.149863 0.674008 -0.674012 0.302359 0.934164 -0.203212 0.29333 0.723623 -0.673723 0.149889 0.791534 -0.592529 0.149611 0.791535 -0.592532 0.149594 0.867803 -0.473857 0.149593 0.867806 -0.473864 0.149549 0.906536 -0.394619 0.149897 0.90325 -0.336895 0.265784 0.932415 -0.328929 0.149697 0.960152 -0.235965 0.14976 0.974524 -0.166845 0.149888 0.986232 -0.070536 0.149568 0.986239 -0.0705415 0.149522 0.0606233 -0.847648 0.527084 0.180641 -0.830393 0.527082 0.180641 -0.830388 0.527091 0.296977 -0.796227 0.527093 0.296978 -0.796233 0.527084 0.407272 -0.745865 0.527081 0.407266 -0.745845 0.527115 0.509264 -0.680294 0.527116 0.509274 -0.680316 0.527077 0.60091 -0.600914 0.527077 0.600897 -0.600894 0.527115 0.680297 -0.509261 0.527115 0.680308 -0.509275 0.527086 0.745861 -0.407276 0.527085 0.745845 -0.407263 0.527117 0.796212 -0.296972 0.527118 0.796213 -0.296972 0.527118 0.830373 -0.180634 0.527117 0.830391 -0.180642 0.527085 0.847647 -0.0606286 0.527085 0.847637 -0.0606257 0.527102 0.0408605 -0.571291 0.81973 0.121747 -0.559661 0.81973 0.121749 -0.559677 0.819719 0.200159 -0.536651 0.819721 0.200159 -0.536647 0.819724 0.274496 -0.502696 0.819725 0.274502 -0.502713 0.819712 0.343252 -0.458535 0.819709 0.343243 -0.458518 0.819723 0.405004 -0.405002 0.819723 0.405012 -0.405012 0.819714 0.458528 -0.343251 0.819713 0.458518 -0.343241 0.819724 0.502699 -0.274494 0.819724 0.502692 -0.27449 0.81973 0.536637 -0.200155 0.819731 0.536641 -0.200157 0.819728 0.559663 -0.121748 0.819728 0.559679 -0.121754 0.819717 0.571309 -0.0408619 0.819717 0.571272 -0.0408541 0.819744 0.014411 -0.201492 0.979384 0.042939 -0.19739 0.979384 0.0429389 -0.197389 0.979384 0.070594 -0.18927 0.979384 0.0705938 -0.18927 0.979384 0.0968116 -0.177297 0.979384 0.0968122 -0.177299 0.979384 0.121059 -0.161716 0.979384 0.121057 -0.161712 0.979385 0.142838 -0.142838 0.979385 0.14284 -0.14284 0.979384 0.161715 -0.121058 0.979384 0.161712 -0.121055 0.979385 0.177293 -0.096809 0.979385 0.177299 -0.0968135 0.979384 0.189274 -0.0705955 0.979383 0.189267 -0.0705921 0.979385 0.197386 -0.0429399 0.979385 0.197382 -0.0429385 0.979386 0.201484 -0.014409 0.979386 0.201496 -0.0144113 0.979383 0 0.20151 0.979486 0 0.20151 0.979486 0 0.571784 0.820405 0 0.571784 0.820405 0 0.849199 0.528073 0 0.849199 0.528073 0 0.988691 0.149967 0 0.988691 0.149967 0 -0.20151 0.979486 0 -0.20151 0.979486 0 -0.571784 0.820405 0 -0.571784 0.820405 0 -0.849199 0.528073 0 -0.849199 0.528073 0 -0.988691 0.149967 0 -0.988691 0.149967 -0.0144111 0.201489 0.979385 -0.0408607 0.571306 0.819719 -0.0606248 0.847637 0.527102 -0.317142 0.898979 0.30209 -0.345534 0.926408 0.149578 -0.235954 0.960148 0.149808 -0.203214 0.934168 0.293318 -0.166861 0.974514 0.14993 -0.0705371 0.986226 0.149606 -0.0705359 0.986228 0.149594 -0.394604 0.906537 0.149932 -0.473857 0.867805 0.149579 -0.473857 0.867806 0.149575 -0.592536 0.791536 0.149572 -0.592536 0.791532 0.149597 -0.673718 0.72363 0.149876 -0.674008 0.674012 0.302359 -0.934164 0.203212 0.29333 -0.723623 0.673723 0.149889 -0.791534 0.592529 0.149611 -0.791535 0.592532 0.149594 -0.867803 0.473857 0.149593 -0.867801 0.473854 0.149612 -0.906526 0.394615 0.149963 -0.903235 0.336897 0.265831 -0.932415 0.328929 0.149697 -0.960152 0.235965 0.14976 -0.974524 0.166845 0.149888 -0.986232 0.070536 0.149568 -0.986229 0.0705328 0.149594 -0.0606245 0.84764 0.527097 -0.180638 0.830386 0.527095 -0.180637 0.83038 0.527104 -0.296976 0.796219 0.527105 -0.296976 0.796221 0.527103 -0.407265 0.745851 0.527107 -0.407263 0.745846 0.527114 -0.509264 0.680294 0.527116 -0.509271 0.68031 0.527088 -0.600906 0.600909 0.527086 -0.600896 0.600894 0.527115 -0.680297 0.509261 0.527115 -0.680308 0.509275 0.527086 -0.745864 0.407271 0.527084 -0.74587 0.407276 0.527071 -0.796239 0.296988 0.527068 -0.796213 0.296972 0.527118 -0.830373 0.180634 0.527117 -0.830391 0.180642 0.527085 -0.847648 0.0606218 0.527085 -0.847637 0.0606189 0.527102 -0.0408611 0.5713 0.819724 -0.121748 0.559669 0.819724 -0.121748 0.559668 0.819725 -0.200158 0.536643 0.819726 -0.200162 0.536659 0.819715 -0.274502 0.502712 0.819713 -0.274496 0.502697 0.819724 -0.343241 0.458518 0.819724 -0.343245 0.458525 0.819718 -0.405008 0.405007 0.819718 -0.405012 0.405012 0.819714 -0.458528 0.343251 0.819713 -0.458518 0.343241 0.819724 -0.502699 0.274494 0.819724 -0.502692 0.27449 0.81973 -0.536637 0.200155 0.819731 -0.536641 0.200157 0.819728 -0.559663 0.121748 0.819728 -0.559645 0.121741 0.819742 -0.571274 0.0408547 0.819742 -0.571306 0.0408614 0.819719 -0.014411 0.201492 0.979384 -0.0429394 0.19739 0.979384 -0.0429397 0.197393 0.979384 -0.0705948 0.189274 0.979383 -0.0705926 0.189265 0.979385 -0.096809 0.177291 0.979386 -0.0968109 0.177295 0.979384 -0.121056 0.161714 0.979384 -0.121056 0.161713 0.979385 -0.142838 0.142838 0.979385 -0.14284 0.14284 0.979384 -0.161715 0.121058 0.979384 -0.161712 0.121055 0.979385 -0.177293 0.096809 0.979385 -0.177299 0.0968135 0.979384 -0.189274 0.0705955 0.979383 -0.189267 0.0705921 0.979385 -0.197387 0.0429383 0.979385 -0.197397 0.0429417 0.979383 -0.201499 0.0144118 0.979383 -0.201496 0.0144113 0.979383 -0.201496 -0.0144115 0.979383 -0.571306 -0.040857 0.819719 -0.847637 -0.0606211 0.527102 -0.898959 -0.317127 0.302164 -0.926413 -0.345542 0.149534 -0.960152 -0.235965 0.14976 -0.934164 -0.203212 0.29333 -0.974524 -0.166845 0.149888 -0.986233 -0.0705331 0.149567 -0.986228 -0.0705357 0.149594 -0.906526 -0.394615 0.149963 -0.8678 -0.473855 0.149612 -0.867804 -0.473855 0.149593 -0.791536 -0.592531 0.149594 -0.791533 -0.592531 0.149611 -0.723623 -0.673723 0.149889 -0.674008 -0.674012 0.302359 -0.203214 -0.934161 0.293339 -0.673717 -0.723634 0.149863 -0.592536 -0.791534 0.149582 -0.592538 -0.791535 0.149572 -0.473859 -0.867805 0.149575 -0.473856 -0.867803 0.149595 -0.394589 -0.90654 0.149948 -0.336896 -0.903253 0.265772 -0.328936 -0.932402 0.149759 -0.235956 -0.960144 0.149826 -0.166856 -0.974515 0.14993 -0.0705357 -0.986226 0.149606 -0.0705372 -0.986228 0.149594 -0.847648 -0.0606196 0.527085 -0.830392 -0.180638 0.527085 -0.830372 -0.180638 0.527117 -0.796211 -0.296978 0.527117 -0.796242 -0.296982 0.527068 -0.745871 -0.407275 0.527071 -0.745863 -0.407272 0.527084 -0.680311 -0.509272 0.527086 -0.680294 -0.509264 0.527115 -0.600894 -0.600897 0.527114 -0.600914 -0.60091 0.527077 -0.509278 -0.680313 0.527077 -0.50926 -0.680297 0.527116 -0.407263 -0.745847 0.527114 -0.407266 -0.745851 0.527107 -0.296975 -0.796222 0.527103 -0.296978 -0.796227 0.527093 -0.18064 -0.830388 0.527091 -0.180642 -0.830393 0.527082 -0.0606256 -0.847648 0.527084 -0.0606225 -0.847637 0.527102 -0.571274 -0.040859 0.819741 -0.559646 -0.121744 0.819741 -0.559664 -0.121746 0.819728 -0.536641 -0.200157 0.819728 -0.536637 -0.200156 0.819731 -0.502691 -0.27449 0.81973 -0.502699 -0.274494 0.819724 -0.458517 -0.343243 0.819724 -0.45853 -0.34325 0.819713 -0.405013 -0.405011 0.819714 -0.405003 -0.405003 0.819723 -0.343241 -0.458519 0.819723 -0.34324 -0.458519 0.819724 -0.274494 -0.502699 0.819724 -0.274504 -0.502711 0.819713 -0.200164 -0.536658 0.819715 -0.20016 -0.536651 0.819721 -0.121751 -0.559676 0.819719 -0.121745 -0.559661 0.81973 -0.0408584 -0.571291 0.81973 -0.0408615 -0.571306 0.819719 -0.201499 -0.0144114 0.979383 -0.197396 -0.0429404 0.979383 -0.197386 -0.0429394 0.979385 -0.189267 -0.0705929 0.979385 -0.189274 -0.0705948 0.979383 -0.1773 -0.0968127 0.979384 -0.177292 -0.0968097 0.979385 -0.161711 -0.121055 0.979385 -0.161715 -0.121057 0.979384 -0.14284 -0.14284 0.979384 -0.142838 -0.142838 0.979385 -0.121056 -0.161713 0.979385 -0.121059 -0.161716 0.979384 -0.096813 -0.177298 0.979384 -0.0968081 -0.177291 0.979386 -0.070592 -0.189265 0.979385 -0.0705946 -0.18927 0.979384 -0.0429388 -0.197389 0.979384 -0.0429392 -0.19739 0.979384 -0.0144113 -0.201492 0.979384 -0.0144108 -0.201489 0.979385 -0.201517 0 0.979485 -0.201517 0 0.979485 -0.571784 0 0.820404 -0.571784 0 0.820404 -0.849199 0 0.528073 -0.849199 0 0.528073 -0.988691 0 0.149967 -0.988691 0 0.149967 -0.201517 0 0.979485 -0.201517 0 0.979485 -0.571784 0 0.820404 -0.571784 0 0.820404 -0.849199 0 0.528073 -0.849199 0 0.528073 -0.988691 0 0.149967 -0.988691 0 0.149967 0 0.98404 -0.177946 0 0.98404 -0.177946 0 0.932797 -0.360401 0 0.932797 -0.360401 0 0.879855 -0.475243 0 0.879855 -0.475243 0 0.774394 -0.632703 0 0.774394 -0.632703 0 0.591309 -0.806445 0 0.591309 -0.806445 0 0.42854 -0.903523 0 0.42854 -0.903523 0 0.311086 -0.950382 0 0.311086 -0.950382 0 0.126202 -0.992005 0 0.126202 -0.992005 -0.893672 0.411987 -0.177811 -0.807309 0.56267 -0.177914 -0.497615 0.849011 -0.177649 -0.172997 0.96872 -0.177912 -0.126194 0.00993233 -0.991956 -0.00993165 0.126195 -0.991956 -0.00993209 0.126196 -0.991956 -0.0244763 0.310993 -0.950097 -0.0511282 0.367067 -0.928788 -0.116951 0.0484419 -0.991956 -0.116949 0.0484424 -0.991956 -0.343261 0.142185 -0.928415 -0.343261 0.142186 -0.928415 -0.547389 0.226739 -0.805577 -0.547397 0.226737 -0.805572 -0.716334 0.296712 -0.631529 -0.716326 0.296714 -0.631536 -0.839465 0.347721 -0.417598 -0.123087 0.0295507 -0.991956 -0.123087 0.0295506 -0.991956 -0.361278 0.0867352 -0.928415 -0.361279 0.0867346 -0.928415 -0.576127 0.138315 -0.805572 -0.576123 0.138316 -0.805575 -0.753923 0.181003 -0.631536 -0.753925 0.181001 -0.631534 -0.0891467 0.904033 -0.418063 -0.0690808 0.877753 -0.474107 -0.0608334 0.772961 -0.631531 -0.060833 0.77296 -0.631531 -0.0464863 0.590668 -0.805575 -0.0464879 0.590669 -0.805573 -0.0337085 0.428296 -0.90301 -0.0484426 0.11695 -0.991956 -0.0484429 0.11695 -0.991956 -0.142185 0.343262 -0.928415 -0.142181 0.343259 -0.928417 -0.226736 0.547395 -0.805574 -0.226738 0.547396 -0.805573 -0.296713 0.71633 -0.631533 -0.296712 0.716329 -0.631533 -0.347717 0.839467 -0.417598 -0.347721 0.839468 -0.417593 -0.126195 0.00993169 -0.991956 -0.310991 0.0244752 -0.950098 -0.367069 0.0511291 -0.928787 -0.428302 0.0337088 -0.903007 -0.590668 0.0464875 -0.805575 -0.590666 0.0464889 -0.805576 -0.772958 0.0608363 -0.631534 -0.772964 0.0608315 -0.631527 -0.87775 0.0690781 -0.474113 -0.839468 0.347719 -0.417594 -0.883528 0.212116 -0.417595 -0.883528 0.212116 -0.417594 -0.904033 0.0891463 -0.418063 -0.930299 0.073212 -0.359421 -0.0772149 0.981103 -0.177414 -0.0772143 0.981102 -0.177415 -0.0732156 0.930294 -0.359434 -0.248475 0.95221 -0.177643 -0.228575 0.952088 -0.203178 -0.212115 0.883527 -0.417597 -0.212116 0.883527 -0.417596 -0.181001 0.753927 -0.631533 -0.181004 0.753928 -0.631529 -0.138317 0.576124 -0.805574 -0.138315 0.576123 -0.805575 -0.0867355 0.361278 -0.928415 -0.0867342 0.361277 -0.928416 -0.0295506 0.123088 -0.991956 -0.029551 0.123089 -0.991956 -0.376614 0.909223 -0.177415 -0.405949 0.880583 -0.244497 -0.340603 0.923241 -0.177808 -0.562668 0.80731 -0.177917 -0.511602 0.834853 -0.203187 -0.474764 0.774739 -0.417588 -0.47476 0.774738 -0.417592 -0.405119 0.661095 -0.631532 -0.405116 0.661094 -0.631534 -0.309576 0.505184 -0.805575 -0.309581 0.505186 -0.805572 -0.194131 0.316791 -0.928416 -0.194128 0.31679 -0.928417 -0.066141 0.107933 -0.991956 -0.0661405 0.107933 -0.991956 -0.0822114 0.0962571 -0.991956 -0.082211 0.096257 -0.991956 -0.241297 0.282523 -0.928416 -0.241297 0.282523 -0.928416 -0.384793 0.450536 -0.805576 -0.384796 0.450536 -0.805574 -0.503551 0.58958 -0.631532 -0.503552 0.58958 -0.631531 -0.590115 0.690931 -0.417587 -0.59011 0.690932 -0.417592 -0.639144 0.748343 -0.17742 -0.639148 0.748341 -0.177414 -0.0962568 0.0822113 -0.991956 -0.096256 0.0822113 -0.991956 -0.282521 0.241299 -0.928416 -0.282527 0.241299 -0.928415 -0.450539 0.384794 -0.805573 -0.450533 0.384794 -0.805577 -0.58958 0.503551 -0.631531 -0.589585 0.503551 -0.631527 -0.690932 0.59011 -0.417592 -0.69093 0.59011 -0.417595 -0.748343 0.639146 -0.177414 -0.748342 0.639147 -0.177416 -0.849012 0.497615 -0.177645 -0.834852 0.511603 -0.203185 -0.774734 0.474762 -0.417598 -0.774736 0.474761 -0.417595 -0.661096 0.405122 -0.631529 -0.661098 0.405122 -0.631527 -0.505181 0.309576 -0.805577 -0.505182 0.309576 -0.805577 -0.316794 0.194131 -0.928415 -0.316797 0.194131 -0.928414 -0.107933 0.0661405 -0.991956 -0.107932 0.0661406 -0.991956 -0.909715 0.335613 -0.244503 -0.909224 0.376613 -0.177412 -0.95221 0.248473 -0.177644 -0.952089 0.228576 -0.203176 -0.968726 0.172979 -0.177901 -0.981105 0.0772103 -0.177403 -0.981103 0.0772148 -0.177411 0.411983 0.893673 -0.177814 0.562669 0.807311 -0.177909 0.849012 0.497615 -0.177645 0.968718 0.17301 -0.177915 0.0099317 0.126196 -0.991956 0.126195 0.0099324 -0.991956 0.126195 0.00993162 -0.991956 0.310991 0.0244752 -0.950098 0.367069 0.0511291 -0.928787 0.0484422 0.11695 -0.991956 0.0484423 0.11695 -0.991956 0.142183 0.34326 -0.928416 0.142183 0.343262 -0.928415 0.226737 0.547397 -0.805573 0.226739 0.547391 -0.805576 0.296715 0.716328 -0.631534 0.296713 0.716332 -0.631529 0.347718 0.839469 -0.417593 0.0295509 0.123088 -0.991956 0.0295507 0.123089 -0.991956 0.0867345 0.361278 -0.928415 0.0867352 0.361277 -0.928416 0.138315 0.576122 -0.805575 0.138315 0.576123 -0.805575 0.181002 0.753928 -0.631531 0.181003 0.753927 -0.631532 0.904033 0.0891463 -0.418063 0.87775 0.0690781 -0.474113 0.772958 0.0608311 -0.631534 0.772964 0.0608368 -0.631527 0.590668 0.046489 -0.805575 0.590666 0.0464874 -0.805576 0.428302 0.0337088 -0.903007 0.11695 0.0484433 -0.991956 0.11695 0.048443 -0.991956 0.343261 0.142185 -0.928415 0.343258 0.142181 -0.928417 0.547391 0.226735 -0.805577 0.547395 0.226741 -0.805573 0.716332 0.296718 -0.631528 0.716331 0.296717 -0.631529 0.839467 0.347722 -0.417594 0.839466 0.347718 -0.417598 0.00993206 0.126195 -0.991956 0.0244763 0.310993 -0.950097 0.0511282 0.367067 -0.928788 0.0337085 0.428296 -0.90301 0.0464877 0.590668 -0.805575 0.0464865 0.590669 -0.805574 0.060833 0.77296 -0.631532 0.0608329 0.77296 -0.631531 0.0690802 0.877753 -0.474107 0.34772 0.839466 -0.417598 0.212117 0.883527 -0.417597 0.212115 0.883529 -0.417593 0.0891464 0.904034 -0.418062 0.0732156 0.930294 -0.359434 0.981102 0.0772147 -0.177417 0.981101 0.07721 -0.177425 0.930299 0.073212 -0.359421 0.95221 0.248473 -0.177644 0.952089 0.228576 -0.203176 0.883528 0.212116 -0.417595 0.883528 0.212116 -0.417594 0.75393 0.181003 -0.631528 0.753926 0.180997 -0.631534 0.576122 0.138311 -0.805577 0.576124 0.138314 -0.805575 0.361278 0.0867343 -0.928415 0.361279 0.0867354 -0.928415 0.123089 0.029551 -0.991956 0.123087 0.0295492 -0.991956 0.909224 0.376613 -0.177413 0.88058 0.405951 -0.244503 0.923241 0.340603 -0.17781 0.807311 0.562672 -0.177903 0.834857 0.511598 -0.203176 0.774738 0.474757 -0.417595 0.774738 0.474755 -0.417598 0.661095 0.405115 -0.631534 0.661096 0.405121 -0.631529 0.505187 0.309579 -0.805572 0.505187 0.309579 -0.805573 0.316792 0.19413 -0.928416 0.316791 0.194127 -0.928417 0.107932 0.0661402 -0.991956 0.107933 0.066141 -0.991956 0.0962563 0.0822109 -0.991956 0.0962564 0.0822116 -0.991956 0.282522 0.241299 -0.928416 0.282522 0.241298 -0.928416 0.450537 0.384798 -0.805573 0.450537 0.384797 -0.805573 0.589578 0.50355 -0.631534 0.589579 0.503553 -0.631531 0.690927 0.590113 -0.417595 0.690928 0.590109 -0.417601 0.748344 0.639147 -0.177405 0.748346 0.639142 -0.177413 0.0822112 0.0962568 -0.991956 0.0822112 0.0962572 -0.991956 0.241297 0.282523 -0.928416 0.241297 0.282523 -0.928416 0.384795 0.450538 -0.805574 0.384795 0.450534 -0.805576 0.503551 0.58958 -0.631531 0.503551 0.589579 -0.631532 0.590111 0.690927 -0.4176 0.59011 0.690931 -0.417595 0.639145 0.748344 -0.177414 0.639144 0.748345 -0.177411 0.497615 0.849011 -0.177649 0.511599 0.834856 -0.203181 0.474759 0.774739 -0.417592 0.47476 0.774738 -0.417594 0.405118 0.661093 -0.631534 0.405118 0.661096 -0.631532 0.309578 0.505188 -0.805573 0.309578 0.505183 -0.805576 0.194131 0.316792 -0.928416 0.194131 0.316791 -0.928416 0.0661414 0.107932 -0.991956 0.0661414 0.107932 -0.991956 0.335613 0.909715 -0.244503 0.376615 0.909224 -0.177409 0.248477 0.952209 -0.177643 0.228575 0.952088 -0.203181 0.172992 0.968722 -0.177912 0.0772143 0.981103 -0.177414 0.0772149 0.981102 -0.177415 -0.126202 0 -0.992005 -0.188642 -0.0159552 -0.981916 -0.311084 0 -0.950383 -0.428545 0 -0.90352 -0.539068 -0.0159551 -0.842111 -0.591305 0 -0.806448 -0.774398 0 -0.632699 -0.812745 -0.0159547 -0.582401 -0.879852 0 -0.475248 -0.932802 0 -0.360388 -0.970699 -0.0159547 -0.239768 -0.984041 0 -0.177942 0.126202 0 -0.992005 0.126202 0 -0.992005 0.311084 0 -0.950383 0.311084 0 -0.950383 0.428545 0 -0.90352 0.428545 0 -0.90352 0.591305 0 -0.806448 0.591305 0 -0.806448 0.774398 0 -0.632699 0.774398 0 -0.632699 0.879852 0 -0.475248 0.879852 0 -0.475248 0.932802 0 -0.360388 0.932802 0 -0.360388 0.984038 0 -0.177957 0.984038 0 -0.177957 -0.126202 0 -0.992005 -0.188642 0.0159552 -0.981916 -0.311084 0 -0.950382 -0.428545 0 -0.90352 -0.539068 0.0159551 -0.842111 -0.591305 0 -0.806448 -0.774398 0 -0.632699 -0.812745 0.0159547 -0.582401 -0.984041 0 -0.177942 -0.970699 0.0159547 -0.239768 -0.932802 0 -0.360388 -0.879852 0 -0.475248 0.95221 -0.248473 -0.177644 0.893672 -0.411987 -0.177811 0.807311 -0.562672 -0.177903 0.497615 -0.849011 -0.177649 0.340603 -0.923241 -0.177808 0.172976 -0.968725 -0.177908 0.126194 -0.00993233 -0.991956 0.00993165 -0.126195 -0.991956 0.00993209 -0.126196 -0.991956 0.0244763 -0.310993 -0.950097 0.0511282 -0.367067 -0.928788 0.126195 -0.00993169 -0.991956 0.310991 -0.0244752 -0.950098 0.367069 -0.0511291 -0.928787 0.428302 -0.0337088 -0.903007 0.590668 -0.0464875 -0.805575 0.590666 -0.0464889 -0.805576 0.772958 -0.0608363 -0.631534 0.0891464 -0.904034 -0.418062 0.0690823 -0.877756 -0.474102 0.0608346 -0.772962 -0.631529 0.060833 -0.77296 -0.631531 0.0464862 -0.590666 -0.805576 0.0464877 -0.590668 -0.805575 0.0337085 -0.428296 -0.90301 0.0772149 -0.981103 -0.17741 0.0772144 -0.981103 -0.177411 0.0732156 -0.930294 -0.359434 0.24848 -0.952208 -0.177643 0.228575 -0.952087 -0.203185 0.212115 -0.883527 -0.417597 0.212118 -0.883528 -0.417593 0.181003 -0.753928 -0.631531 0.181004 -0.753928 -0.631529 0.138317 -0.576124 -0.805574 0.138313 -0.576121 -0.805577 0.0867343 -0.361277 -0.928416 0.0867342 -0.361277 -0.928416 0.0295506 -0.123088 -0.991956 0.029551 -0.123089 -0.991956 0.411983 -0.893673 -0.177814 0.374013 -0.902943 -0.211681 0.347721 -0.839469 -0.41759 0.347715 -0.839468 -0.417598 0.29671 -0.716328 -0.631535 0.296716 -0.716331 -0.631529 0.22674 -0.547395 -0.805573 0.226737 -0.547393 -0.805575 0.142183 -0.343261 -0.928416 0.142183 -0.343261 -0.928416 0.0484424 -0.11695 -0.991956 0.0484421 -0.11695 -0.991956 0.56267 -0.807312 -0.177906 0.511598 -0.834857 -0.203179 0.474757 -0.774738 -0.417597 0.474762 -0.774738 -0.41759 0.405121 -0.661094 -0.631532 0.405116 -0.661093 -0.631536 0.309576 -0.505184 -0.805575 0.309581 -0.505186 -0.805572 0.194131 -0.316791 -0.928416 0.194132 -0.316792 -0.928416 0.0661416 -0.107932 -0.991956 0.0661413 -0.107932 -0.991956 0.0822114 -0.0962571 -0.991956 0.082211 -0.096257 -0.991956 0.241297 -0.282523 -0.928416 0.241297 -0.282523 -0.928416 0.384793 -0.450536 -0.805576 0.384796 -0.450536 -0.805574 0.503551 -0.58958 -0.631532 0.503552 -0.58958 -0.631531 0.590112 -0.690928 -0.417597 0.590109 -0.690928 -0.4176 0.639147 -0.748343 -0.177408 0.639144 -0.748345 -0.177414 0.0962568 -0.0822113 -0.991956 0.096256 -0.0822113 -0.991956 0.282521 -0.241299 -0.928416 0.282522 -0.241299 -0.928416 0.450536 -0.384797 -0.805573 0.450537 -0.384797 -0.805573 0.58958 -0.503551 -0.631531 0.589577 -0.503551 -0.631534 0.690925 -0.590112 -0.417601 0.69093 -0.59011 -0.417595 0.748343 -0.639146 -0.177414 0.748347 -0.639143 -0.177405 0.849012 -0.497615 -0.177645 0.834857 -0.511598 -0.203176 0.774737 -0.474757 -0.417598 0.77474 -0.474756 -0.417595 0.661098 -0.405117 -0.631529 0.661093 -0.405119 -0.631534 0.505187 -0.309579 -0.805573 0.505188 -0.309579 -0.805572 0.31679 -0.194129 -0.928417 0.316793 -0.194129 -0.928416 0.107933 -0.0661405 -0.991956 0.107932 -0.0661406 -0.991956 0.923241 -0.340603 -0.17781 0.902943 -0.374011 -0.211682 0.839468 -0.347719 -0.417594 0.839465 -0.347721 -0.417598 0.716332 -0.296717 -0.631528 0.716331 -0.296718 -0.631529 0.54739 -0.226739 -0.805577 0.547397 -0.226737 -0.805572 0.343262 -0.142182 -0.928416 0.343257 -0.142184 -0.928417 0.11695 -0.0484431 -0.991956 0.11695 -0.0484432 -0.991956 0.968718 -0.17301 -0.177915 0.952089 -0.228576 -0.203176 0.883528 -0.212116 -0.417594 0.883528 -0.212116 -0.417595 0.753926 -0.181001 -0.631534 0.753932 -0.180998 -0.631528 0.576124 -0.138311 -0.805575 0.576121 -0.138313 -0.805577 0.361279 -0.0867346 -0.928415 0.361278 -0.0867352 -0.928415 0.123087 -0.0295506 -0.991956 0.123089 -0.0295497 -0.991956 0.772964 -0.0608315 -0.631527 0.87775 -0.0690781 -0.474113 0.904034 -0.0891463 -0.418063 0.930299 -0.073212 -0.359421 0.981102 -0.0772101 -0.177417 0.9811 -0.0772146 -0.177425 -0.411983 -0.893673 -0.177814 -0.562669 -0.807311 -0.177915 -0.849012 -0.497615 -0.177645 -0.968726 -0.172979 -0.177901 -0.0099317 -0.126196 -0.991956 -0.126195 -0.0099324 -0.991956 -0.126195 -0.00993162 -0.991956 -0.310991 -0.0244752 -0.950098 -0.367069 -0.0511291 -0.928787 -0.0484427 -0.11695 -0.991956 -0.0484428 -0.11695 -0.991956 -0.142184 -0.343258 -0.928417 -0.142183 -0.343261 -0.928416 -0.226738 -0.547396 -0.805573 -0.226738 -0.547396 -0.805573 -0.296712 -0.716327 -0.631535 -0.296711 -0.71633 -0.631533 -0.347717 -0.839471 -0.41759 -0.0295509 -0.123088 -0.991956 -0.0295507 -0.123089 -0.991956 -0.0867342 -0.361277 -0.928416 -0.0867343 -0.361277 -0.928416 -0.138315 -0.576126 -0.805573 -0.138317 -0.576121 -0.805576 -0.181005 -0.753926 -0.631533 -0.181002 -0.753931 -0.631527 -0.904033 -0.0891463 -0.418063 -0.87775 -0.0690781 -0.474113 -0.772958 -0.0608311 -0.631534 -0.772964 -0.0608368 -0.631527 -0.590668 -0.046489 -0.805575 -0.590666 -0.0464874 -0.805576 -0.428302 -0.0337088 -0.903007 -0.116949 -0.0484413 -0.991956 -0.11695 -0.048443 -0.991956 -0.343261 -0.142185 -0.928415 -0.343261 -0.142186 -0.928415 -0.547395 -0.226742 -0.805572 -0.547391 -0.226734 -0.805577 -0.716328 -0.296709 -0.631536 -0.716331 -0.296717 -0.631529 -0.839467 -0.347722 -0.417594 -0.839466 -0.347718 -0.417598 -0.00993206 -0.126195 -0.991956 -0.0244763 -0.310993 -0.950097 -0.0511282 -0.367067 -0.928788 -0.0337085 -0.428296 -0.90301 -0.0464876 -0.590666 -0.805576 -0.0464863 -0.590668 -0.805575 -0.0608332 -0.772962 -0.631529 -0.060835 -0.77296 -0.631531 -0.0690829 -0.877756 -0.474102 -0.34772 -0.839466 -0.417598 -0.212115 -0.883527 -0.417597 -0.212115 -0.883527 -0.417596 -0.0891467 -0.904033 -0.418063 -0.0732156 -0.930294 -0.359434 -0.981104 -0.0772149 -0.177403 -0.981103 -0.0772102 -0.177411 -0.930299 -0.073212 -0.359421 -0.95221 -0.248473 -0.177644 -0.952089 -0.228576 -0.203176 -0.883528 -0.212116 -0.417595 -0.883528 -0.212116 -0.417594 -0.753923 -0.181001 -0.631536 -0.753925 -0.181003 -0.631534 -0.576127 -0.138317 -0.805572 -0.576124 -0.138314 -0.805575 -0.361278 -0.0867343 -0.928415 -0.361279 -0.0867354 -0.928415 -0.123087 -0.0295506 -0.991956 -0.123087 -0.0295507 -0.991956 -0.909224 -0.376613 -0.177413 -0.88058 -0.405951 -0.244503 -0.923241 -0.340603 -0.17781 -0.807309 -0.56267 -0.177914 -0.834852 -0.511603 -0.203185 -0.774735 -0.474763 -0.417595 -0.774735 -0.474761 -0.417598 -0.661097 -0.405123 -0.631527 -0.661096 -0.405121 -0.631529 -0.505182 -0.309576 -0.805577 -0.505182 -0.309575 -0.805577 -0.316796 -0.194132 -0.928414 -0.316794 -0.19413 -0.928415 -0.107932 -0.0661402 -0.991956 -0.107933 -0.066141 -0.991956 -0.0962563 -0.0822109 -0.991956 -0.0962564 -0.0822116 -0.991956 -0.282525 -0.241301 -0.928414 -0.282524 -0.241296 -0.928416 -0.450535 -0.384791 -0.805577 -0.450537 -0.384797 -0.805573 -0.589583 -0.503554 -0.631527 -0.589582 -0.503549 -0.631531 -0.690931 -0.590109 -0.417595 -0.690931 -0.590111 -0.417592 -0.748342 -0.639146 -0.177416 -0.748342 -0.639147 -0.177414 -0.0822112 -0.0962568 -0.991956 -0.0822112 -0.0962572 -0.991956 -0.241297 -0.282523 -0.928416 -0.241297 -0.282523 -0.928416 -0.384795 -0.450538 -0.805574 -0.384795 -0.450534 -0.805576 -0.503551 -0.58958 -0.631531 -0.503551 -0.589579 -0.631532 -0.590113 -0.690929 -0.417592 -0.590112 -0.690932 -0.417589 -0.639146 -0.748343 -0.177414 -0.639147 -0.748341 -0.177417 -0.497615 -0.849011 -0.177649 -0.5116 -0.834854 -0.203185 -0.474762 -0.774739 -0.41759 -0.474762 -0.774738 -0.41759 -0.405119 -0.661091 -0.631536 -0.405118 -0.661096 -0.631532 -0.309578 -0.505188 -0.805573 -0.309578 -0.505183 -0.805576 -0.19413 -0.316789 -0.928417 -0.19413 -0.316793 -0.928416 -0.0661408 -0.107932 -0.991956 -0.0661407 -0.107933 -0.991956 -0.335613 -0.909715 -0.244503 -0.376615 -0.909224 -0.177409 -0.248477 -0.952209 -0.177643 -0.228575 -0.952088 -0.203181 -0.172982 -0.968724 -0.177908 -0.0772144 -0.981103 -0.17741 -0.0772149 -0.981103 -0.177411 0 -0.984041 -0.177942 0 -0.984041 -0.177942 0 -0.932797 -0.360401 0 -0.932797 -0.360401 0 -0.879858 -0.475237 0 -0.879858 -0.475237 0 -0.774394 -0.632703 0 -0.774394 -0.632703 0 -0.591307 -0.806447 0 -0.591307 -0.806447 0 -0.42854 -0.903523 0 -0.42854 -0.903523 0 -0.311086 -0.950382 0 -0.311086 -0.950382 0 -0.126202 -0.992005 0 -0.126202 -0.992005 -0.130525 0.991441 -0.00297075 -0.382682 0.923875 -0.00318871 -0.333141 0.942877 0.000227994 -0.169 0.985616 -0.0002476 -0.699577 0.714557 0 -0.628215 0.77804 -0.00080237 -0.60876 0.79335 -0.00267306 -0.530328 0.847793 0 -0.456505 0.889721 0 -0.757645 0.652667 0 -0.793348 0.608759 -0.00332744 -0.836346 0.548202 0 -0.879829 0.47529 0 -0.923878 0.382681 -0.0022967 -0.927887 0.372858 -0.0014358 -0.991439 0.130525 -0.00338713 -0.98113 0.193352 0 -0.961201 0.27585 0 -0.972036 -0.234831 0 -0.991899 -0.127012 -0.0021481 -0.991443 -0.130525 -0.00184094 -0.999775 -0.0212285 0 -0.997973 0.0636401 0 -0.948622 -0.316411 0 -0.923875 -0.38268 -0.00336728 -0.899209 -0.437519 0 -0.858859 -0.512213 0 -0.793352 -0.608762 -0.00130616 -0.803991 -0.594635 -0.00293816 -0.608759 -0.793349 -0.00326797 -0.6686 -0.743622 0 -0.729267 -0.684229 0 -0.296209 -0.955123 0 -0.411898 -0.911222 -0.00380767 -0.382683 -0.923879 -0.000692304 -0.493822 -0.869563 0 -0.565827 -0.824524 0 -0.214134 -0.976804 0 -0.130525 -0.99144 -0.00308971 -0.0848059 -0.996397 0 0.084805 -0.996398 0 0.130525 -0.99144 -0.0030898 0.214138 -0.976803 0 0.382681 -0.92388 -0.000692319 0.411898 -0.911222 -0.00380796 0.296203 -0.955125 0 0.608759 -0.793349 -0.00326797 0.565827 -0.824524 0 0.493822 -0.869563 0 0.858886 -0.512166 0 0.803994 -0.594637 -0.00110956 0.793354 -0.608756 -0.00249475 0.729267 -0.684229 0 0.6686 -0.743622 0 0.899204 -0.43753 0 0.923872 -0.382686 -0.00336758 0.948622 -0.316411 0 0.991443 -0.130525 -0.00184094 0.991898 -0.127023 -0.0021472 0.972044 -0.234797 0 0.991439 0.130525 -0.00338713 0.997973 0.0636401 0 0.999775 -0.0212285 0 0.879816 0.475314 0 0.927889 0.372848 -0.00253412 0.923877 0.382687 -0.00158309 0.961187 0.275896 0 0.98113 0.193352 0 0.836353 0.548191 0 0.793352 0.608754 -0.00332776 0.757645 0.652667 0 0.60876 0.79335 -0.00267306 0.62822 0.778035 -0.000801873 0.699535 0.714598 0 0.382679 0.923876 -0.00318881 0.456505 0.889721 0 0.530328 0.847793 0 -0.0424407 0.999099 0 0.0424398 0.999099 0 0.130525 0.991441 -0.00297084 0.169 0.985616 -0.000247719 0.333141 0.942877 0.00022776 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.212485 -0.969264 -0.124008 0.290519 -0.936799 -0.194954 0.404042 -0.893841 -0.194421 0.404042 -0.893841 -0.194421 0.484333 -0.852854 -0.195093 0.550526 -0.814519 -0.182977 0.555019 -0.808774 -0.19452 0.678732 -0.708186 -0.194412 0.662296 -0.736612 -0.13699 0.715267 -0.671093 -0.195006 0.788652 -0.58329 -0.194425 0.788655 -0.583288 -0.194419 0.842385 -0.502327 -0.195076 0.879373 -0.443366 -0.173578 0.88201 -0.429163 -0.194621 0.937922 -0.287236 -0.194415 0.937903 -0.312836 -0.149907 0.953376 -0.230288 -0.195045 0.972971 -0.124599 -0.194427 0.972977 -0.124588 -0.194407 0.980574 -0.0208208 -0.19504 0.985205 0.0418463 -0.166195 0.978872 0.0624221 -0.194712 0.958902 0.206662 -0.194415 0.968052 0.190775 -0.16273 0.942723 0.270597 -0.195065 0.910187 0.365735 -0.194418 0.910186 0.365744 -0.194402 0.862926 0.466189 -0.195003 0.84043 0.517473 -0.160931 0.820333 0.53769 -0.194788 0.736353 0.648065 -0.194413 0.745888 0.642539 -0.175483 0.686094 0.700868 -0.195089 0.616232 0.763189 -0.194423 0.61623 0.763193 -0.194416 0.52015 0.831522 -0.194975 0.481587 0.862084 -0.15775 0.165776 0.96681 -0.194413 0.326784 0.924887 -0.194412 0.326785 0.924887 -0.194414 0.447755 0.872666 -0.194859 0.0421459 0.99218 -0.117483 0 0.980919 -0.194417 0.165777 0.96681 -0.194416 -0.326784 0.924886 -0.194418 -0.165775 0.96681 -0.194417 -0.165776 0.96681 -0.194416 -0.0416266 0.979935 -0.194924 -0.452601 0.882112 -0.130505 -0.478388 0.856356 -0.194422 -0.326783 0.924886 -0.19442 -0.520149 0.83152 -0.194985 -0.616227 0.763192 -0.194427 -0.616236 0.763189 -0.194411 -0.686137 0.700829 -0.195076 -0.738681 0.650124 -0.178016 -0.743163 0.640192 -0.194586 -0.83528 0.514301 -0.194428 -0.827695 0.542531 -0.143458 -0.862936 0.466164 -0.195019 -0.910183 0.365743 -0.194419 -0.91019 0.365736 -0.194401 -0.94274 0.270552 -0.195047 -0.96339 0.207629 -0.169615 -0.96236 0.189653 -0.194668 -0.980035 0.0416368 -0.194416 -0.985701 0.0628575 -0.156343 -0.980571 -0.0208207 -0.195059 -0.972973 -0.124589 -0.194425 -0.972975 -0.124598 -0.194408 -0.953371 -0.230322 -0.195027 -0.943331 -0.288892 -0.163303 -0.930458 -0.310353 -0.194752 -0.87589 -0.44161 -0.194415 -0.886256 -0.431217 -0.169124 -0.842358 -0.502372 -0.195076 -0.788653 -0.583291 -0.194419 -0.788654 -0.583287 -0.194425 -0.715267 -0.671093 -0.195006 -0.683128 -0.712762 -0.159081 -0.655787 -0.729372 -0.194836 -0.549289 -0.8127 -0.194423 -0.556396 -0.810781 -0.181818 -0.484333 -0.852854 -0.195093 -0.404042 -0.89384 -0.194421 -0.404042 -0.893841 -0.194421 -0.290525 -0.936797 -0.194954 -0.248852 -0.955738 -0.156961 0.247167 -0.949269 -0.194413 0.0831879 -0.977386 -0.194414 0.0831869 -0.977385 -0.194416 -0.0831887 -0.977385 -0.194416 -0.0831878 -0.977386 -0.194414 -0.210028 -0.958074 -0.194891 -0.0705928 -0.829396 -0.554183 -0.209742 -0.805537 -0.554183 -0.209743 -0.805536 -0.554184 -0.342867 -0.7585 -0.554185 -0.342866 -0.758504 -0.55418 -0.466119 -0.689651 -0.554179 -0.46612 -0.689647 -0.554184 -0.57597 -0.600949 -0.554184 -0.57597 -0.600956 -0.554176 -0.669244 -0.494977 -0.554175 -0.669243 -0.494971 -0.554182 -0.743267 -0.374748 -0.554182 -0.743266 -0.374743 -0.554187 -0.795906 -0.243743 -0.554187 -0.795906 -0.243744 -0.554187 -0.825651 -0.105725 -0.554187 -0.825657 -0.105733 -0.554176 -0.831649 0.0353288 -0.554176 -0.831645 0.0353325 -0.554182 -0.813713 0.175366 -0.554183 -0.813707 0.17537 -0.55419 -0.772366 0.310362 -0.55419 -0.772376 0.310359 -0.554178 -0.708811 0.436431 -0.554179 -0.70881 0.436431 -0.554181 -0.624857 0.549943 -0.55418 -0.624854 0.549943 -0.554184 -0.522927 0.647633 -0.554183 -0.52293 0.647633 -0.55418 -0.405956 0.726694 -0.554181 -0.405954 0.726693 -0.554182 -0.277304 0.784846 -0.554183 -0.277304 0.784846 -0.554183 -0.140676 0.820421 -0.554183 -0.140674 0.82042 -0.554185 0 0.832394 -0.554184 0 0.832394 -0.554184 0.140676 0.82042 -0.554185 0.140676 0.82042 -0.554186 0.277303 0.784844 -0.554187 0.277303 0.784844 -0.554187 0.405953 0.726689 -0.554189 0.405952 0.726691 -0.554187 0.522929 0.647627 -0.554188 0.522928 0.647639 -0.554175 0.624856 0.549951 -0.554174 0.624855 0.549936 -0.554191 0.708804 0.436426 -0.554192 0.708805 0.436427 -0.554191 0.772365 0.310362 -0.554191 0.772366 0.310363 -0.55419 0.813708 0.175365 -0.55419 0.813712 0.175371 -0.554182 0.831645 0.0353287 -0.554182 0.831641 0.0353237 -0.554189 0.825649 -0.105725 -0.554189 0.825651 -0.105724 -0.554187 0.795906 -0.243743 -0.554187 0.795906 -0.243744 -0.554187 0.743264 -0.374746 -0.554187 0.743269 -0.374745 -0.554182 0.669241 -0.494974 -0.554182 0.669247 -0.494973 -0.554175 0.575969 -0.600956 -0.554176 0.575962 -0.600956 -0.554184 0.466121 -0.689646 -0.554184 0.466126 -0.689647 -0.554179 0.342865 -0.758504 -0.55418 0.342866 -0.758504 -0.554179 0.209745 -0.805538 -0.554181 0.209743 -0.805537 -0.554183 0.0705921 -0.829396 -0.554183 0.0705921 -0.829396 -0.554183 -0.0705928 -0.829396 -0.554183 -0.047234 -0.554954 -0.830539 -0.14034 -0.538989 -0.830539 -0.14034 -0.53899 -0.830539 -0.229414 -0.507518 -0.830539 -0.229414 -0.507516 -0.83054 -0.311883 -0.461446 -0.83054 -0.311883 -0.46145 -0.830538 -0.385385 -0.402103 -0.830537 -0.385384 -0.402097 -0.83054 -0.447793 -0.331186 -0.83054 -0.447795 -0.331192 -0.830537 -0.497327 -0.250748 -0.830537 -0.497327 -0.250747 -0.830537 -0.532549 -0.163093 -0.830537 -0.532547 -0.163091 -0.830539 -0.55245 -0.0707414 -0.830539 -0.55245 -0.0707416 -0.830539 -0.556459 0.0236363 -0.830539 -0.556455 0.0236385 -0.830541 -0.544457 0.117338 -0.830541 -0.544457 0.117338 -0.830541 -0.516794 0.207667 -0.830541 -0.516797 0.207666 -0.830539 -0.474267 0.29202 -0.830539 -0.474272 0.29202 -0.830536 -0.418098 0.367971 -0.830537 -0.418096 0.36797 -0.830538 -0.349894 0.433336 -0.830539 -0.349894 0.433336 -0.830538 -0.271627 0.486235 -0.830538 -0.271628 0.486236 -0.830538 -0.185546 0.525146 -0.830539 -0.185546 0.525146 -0.830539 -0.094127 0.548949 -0.830539 -0.0941272 0.54895 -0.830539 0 0.55696 -0.830539 0 0.55696 -0.830539 0.094127 0.54895 -0.830539 0.0941271 0.548949 -0.830539 0.185546 0.525146 -0.830539 0.185546 0.525146 -0.830539 0.271627 0.486236 -0.830538 0.271627 0.486235 -0.830538 0.349894 0.433336 -0.830538 0.349893 0.433329 -0.830542 0.418092 0.367965 -0.830543 0.418095 0.367975 -0.830537 0.474271 0.292022 -0.830536 0.474269 0.292018 -0.830539 0.516799 0.207664 -0.830539 0.516802 0.207668 -0.830535 0.544464 0.117345 -0.830535 0.544457 0.117338 -0.830541 0.556456 0.0236362 -0.830541 0.556459 0.0236386 -0.830539 0.55245 -0.0707415 -0.830539 0.55245 -0.0707416 -0.830539 0.532547 -0.163092 -0.830539 0.53255 -0.163092 -0.830537 0.497326 -0.250747 -0.830537 0.497327 -0.250747 -0.830537 0.447797 -0.331189 -0.830537 0.447791 -0.331189 -0.83054 0.385382 -0.402099 -0.83054 0.38538 -0.402099 -0.830541 0.311882 -0.461445 -0.830541 0.311884 -0.461445 -0.83054 0.229412 -0.507518 -0.83054 0.229413 -0.507518 -0.830539 0.140342 -0.538989 -0.830539 0.140341 -0.538989 -0.830539 0.0472344 -0.554954 -0.830539 0.0472335 -0.554952 -0.83054 -0.0472347 -0.554952 -0.83054 -0.0166024 -0.195059 -0.980651 -0.049328 -0.189447 -0.980651 -0.0493278 -0.189448 -0.980651 -0.0806358 -0.178386 -0.980651 -0.0806358 -0.178385 -0.980651 -0.109623 -0.162192 -0.980651 -0.109623 -0.162192 -0.980651 -0.135456 -0.141332 -0.980651 -0.135457 -0.141333 -0.980651 -0.157394 -0.116407 -0.980651 -0.157394 -0.116408 -0.980651 -0.174803 -0.088134 -0.980651 -0.174803 -0.0881343 -0.980651 -0.187184 -0.0573249 -0.980651 -0.187184 -0.0573249 -0.980651 -0.194179 -0.0248655 -0.980651 -0.194178 -0.0248645 -0.980651 -0.195587 0.00830828 -0.980651 -0.195588 0.00830785 -0.980651 -0.19137 0.041244 -0.980651 -0.191373 0.0412435 -0.980651 -0.181649 0.072993 -0.980651 -0.181649 0.072993 -0.980651 -0.1667 0.102641 -0.980651 -0.166698 0.102641 -0.980651 -0.146955 0.129336 -0.980651 -0.146955 0.129336 -0.980651 -0.122983 0.152312 -0.980651 -0.122983 0.152312 -0.980651 -0.0954733 0.170905 -0.980651 -0.095473 0.170905 -0.980651 -0.0652166 0.184582 -0.980651 -0.0652174 0.184583 -0.980651 -0.0330846 0.192949 -0.980651 -0.0330845 0.192949 -0.980651 0 0.195765 -0.980651 0 0.195765 -0.980651 0.0330846 0.192949 -0.980651 0.0330845 0.192949 -0.980651 0.0652169 0.184583 -0.980651 0.0652171 0.184582 -0.980651 0.0954731 0.170905 -0.980651 0.0954732 0.170905 -0.980651 0.122983 0.152312 -0.980651 0.122983 0.152312 -0.980651 0.146955 0.129337 -0.980651 0.146955 0.129336 -0.980651 0.166699 0.10264 -0.980651 0.1667 0.102642 -0.980651 0.181649 0.0729927 -0.980651 0.181647 0.0729905 -0.980651 0.191369 0.0412437 -0.980651 0.19137 0.0412447 -0.980651 0.195588 0.00830832 -0.980651 0.195587 0.00830781 -0.980651 0.194178 -0.0248653 -0.980651 0.194179 -0.0248648 -0.980651 0.187184 -0.0573249 -0.980651 0.187184 -0.0573249 -0.980651 0.174804 -0.0881342 -0.980651 0.174803 -0.0881342 -0.980651 0.157394 -0.116408 -0.980651 0.157393 -0.116408 -0.980651 0.135456 -0.141333 -0.980651 0.135458 -0.141334 -0.980651 0.109624 -0.162194 -0.980651 0.109624 -0.162194 -0.980651 0.0806362 -0.178387 -0.980651 0.0806354 -0.178386 -0.980651 0.0493286 -0.189448 -0.980651 0.049328 -0.189447 -0.980651 0.0166016 -0.195059 -0.980651 0.0166024 -0.19506 -0.980651 -0.0166019 -0.19506 -0.980651 0.258818 0.965926 0 0.258818 0.965926 0 0.422615 0.906309 0 0.422615 0.906309 0 0.573581 0.819149 0 0.573581 0.819149 0 0.707109 0.707105 0 0.707109 0.707105 0 0.819152 0.573577 0 0.819152 0.573577 0 0.906305 0.422624 0 0.906305 0.422624 0 0.965926 0.258817 0 0.965926 0.258817 0 0.996194 0.0871615 0 0.996194 0.0871615 0 0.996194 -0.0871612 0 0.996194 -0.0871612 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.906305 -0.422624 0 0.906305 -0.422624 0 0.819152 -0.573577 0 0.819152 -0.573577 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.573581 -0.819149 0 0.573581 -0.819149 0 0.422615 -0.906309 0 0.422615 -0.906309 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.0871566 -0.996195 0 0.0871566 -0.996195 0 -0.087158 -0.996195 0 -0.087158 -0.996195 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.422615 -0.906309 0 -0.422615 -0.906309 0 -0.573581 -0.819149 0 -0.573581 -0.819149 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.819152 -0.573577 0 -0.819152 -0.573577 0 -0.906305 -0.422624 0 -0.906305 -0.422624 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.996194 -0.0871612 0 -0.996194 -0.0871612 0 -0.996194 0.0871615 0 -0.996194 0.0871615 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.906305 0.422624 0 -0.906305 0.422624 0 -0.819152 0.573577 0 -0.819152 0.573577 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.573581 0.819149 0 -0.573581 0.819149 0 -0.422615 0.906309 0 -0.422615 0.906309 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.087158 0.996195 0 -0.087158 0.996195 0 0.0871566 0.996195 0 0.0871566 0.996195 0 -0.222426 0.974516 -0.0290704 -0.623227 0.781501 -0.0290702 -0.532035 0.846722 0 -0.330274 0.943885 0 -0.900587 0.433703 -0.0290699 -0.846725 0.53203 0 -0.707104 0.70711 0 -0.999577 0 -0.0290688 -0.993713 0.111955 0 -0.94388 0.330288 0 -0.900587 -0.433703 -0.0290699 -0.94388 -0.330288 0 -0.993713 -0.111955 0 -0.623227 -0.781501 -0.0290702 -0.707104 -0.70711 0 -0.846725 -0.53203 0 -0.222426 -0.974516 -0.0290704 -0.330274 -0.943885 0 -0.532035 -0.846722 0 0.222428 -0.974516 -0.0290711 0.111966 -0.993712 0 -0.111966 -0.993712 0 0.623227 -0.781501 -0.0290702 0.532035 -0.846722 0 0.330281 -0.943883 0 0.900587 -0.433703 -0.0290699 0.846725 -0.53203 0 0.707104 -0.70711 0 0.999577 0 -0.0290688 0.993713 -0.111955 0 0.94388 -0.330288 0 0.900587 0.433703 -0.0290699 0.94388 0.330288 0 0.993713 0.111955 0 0.623227 0.781501 -0.0290702 0.707104 0.70711 0 0.846725 0.53203 0 -0.111966 0.993712 0 0.111966 0.993712 0 0.222428 0.974516 -0.0290711 0.330281 0.943883 0 0.532035 0.846722 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.222426 0.974516 -0.0290704 -0.623227 0.781501 -0.0290702 -0.532035 0.846722 0 -0.330274 0.943885 0 -0.900587 0.433703 -0.0290699 -0.846725 0.53203 0 -0.707104 0.70711 0 -0.999577 0 -0.0290688 -0.993713 0.111955 0 -0.94388 0.330288 0 -0.900587 -0.433703 -0.0290699 -0.94388 -0.330288 0 -0.993713 -0.111955 0 -0.623227 -0.781501 -0.0290702 -0.707104 -0.70711 0 -0.846725 -0.53203 0 -0.222426 -0.974516 -0.0290704 -0.330274 -0.943885 0 -0.532035 -0.846722 0 0.222428 -0.974516 -0.0290711 0.111966 -0.993712 0 -0.111966 -0.993712 0 0.623227 -0.781501 -0.0290702 0.532035 -0.846722 0 0.330281 -0.943883 0 0.900587 -0.433703 -0.0290699 0.846725 -0.53203 0 0.707104 -0.70711 0 0.999577 0 -0.0290688 0.993713 -0.111955 0 0.94388 -0.330288 0 0.900587 0.433703 -0.0290699 0.94388 0.330288 0 0.993713 0.111955 0 0.623227 0.781501 -0.0290702 0.707104 0.70711 0 0.846725 0.53203 0 -0.111966 0.993712 0 0.111966 0.993712 0 0.222428 0.974516 -0.0290711 0.330281 0.943883 0 0.532035 0.846722 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.0291488 -0.258712 0.965515 0.0859894 -0.24574 0.965514 0.0859888 -0.245741 0.965514 0.138513 -0.220448 0.965514 0.138514 -0.220445 0.965514 0.184098 -0.184092 0.965514 0.184098 -0.184091 0.965515 0.220441 -0.138517 0.965515 0.220441 -0.138514 0.965515 0.245736 -0.0859868 0.965515 0.245739 -0.0859942 0.965514 0.258714 -0.029149 0.965514 0.258708 -0.0291415 0.965516 0.258708 0.0291484 0.965516 0.258715 0.0291423 0.965514 0.24574 0.085989 0.965514 0.245733 0.0859929 0.965516 0.22044 0.138515 0.965515 0.220444 0.138514 0.965515 0.184097 0.184092 0.965515 0.184096 0.184092 0.965515 0.138511 0.220445 0.965515 0.138517 0.220446 0.965514 0.0859881 0.245741 0.965514 0.085989 0.245741 0.965514 0.0291512 0.258714 0.965514 0.0291487 0.258712 0.965515 -0.0291502 0.258712 0.965515 -0.0291489 0.258713 0.965514 -0.0859875 0.245739 0.965515 -0.085986 0.245742 0.965514 -0.138517 0.220446 0.965514 -0.138517 0.220445 0.965514 -0.184096 0.184098 0.965514 -0.184097 0.184092 0.965515 -0.220442 0.138517 0.965515 -0.220441 0.138513 0.965515 -0.245736 0.0859874 0.965515 -0.245734 0.0859842 0.965516 -0.258706 0.0291482 0.965516 -0.258708 0.0291506 0.965516 -0.258708 -0.0291484 0.965516 -0.258706 -0.0291503 0.965516 -0.245734 -0.0859861 0.965516 -0.245737 -0.0859844 0.965515 -0.220439 -0.138516 0.965515 -0.220443 -0.138515 0.965515 -0.184094 -0.184096 0.965515 -0.184102 -0.184095 0.965513 -0.138517 -0.220447 0.965513 -0.138515 -0.220446 0.965514 -0.0859896 -0.24574 0.965514 -0.0859847 -0.245738 0.965515 -0.0291484 -0.258711 0.965515 -0.0291487 -0.258712 0.965515 0.0291492 -0.258712 0.965515 0.0794187 -0.704875 0.704871 0.234277 -0.66953 0.704872 0.234281 -0.669525 0.704876 0.377385 -0.600608 0.704876 0.377383 -0.600615 0.704872 0.501575 -0.501575 0.704872 0.501577 -0.501562 0.70488 0.600603 -0.377385 0.70488 0.600605 -0.377399 0.704872 0.669532 -0.23427 0.704872 0.669536 -0.234281 0.704865 0.704882 -0.0794209 0.704864 0.70488 -0.0794182 0.704866 0.70488 0.0794208 0.704866 0.704883 0.0794184 0.704864 0.669538 0.234272 0.704865 0.669526 0.234279 0.704874 0.600609 0.377388 0.704874 0.600598 0.377392 0.704881 0.50157 0.50157 0.70488 0.501583 0.501568 0.704872 0.377387 0.600611 0.704872 0.37738 0.600611 0.704877 0.234276 0.669526 0.704875 0.234276 0.669526 0.704875 0.0794207 0.704871 0.704875 0.0794234 0.704873 0.704873 -0.079419 0.704873 0.704873 -0.0794209 0.704871 0.704875 -0.234276 0.669526 0.704875 -0.234276 0.669526 0.704875 -0.377385 0.600608 0.704876 -0.377387 0.600602 0.70488 -0.501568 0.501568 0.704882 -0.501568 0.501572 0.70488 -0.600603 0.377385 0.70488 -0.600604 0.377396 0.704874 -0.669531 0.234269 0.704874 -0.669535 0.234282 0.704865 -0.704882 0.0794209 0.704864 -0.70488 0.0794182 0.704866 -0.70488 -0.0794208 0.704866 -0.704883 -0.0794184 0.704864 -0.669538 -0.234272 0.704865 -0.669528 -0.234278 0.704873 -0.60061 -0.377389 0.704872 -0.600597 -0.377394 0.704881 -0.50157 -0.50157 0.70488 -0.501565 -0.50157 0.704883 -0.377383 -0.600605 0.70488 -0.377389 -0.600606 0.704876 -0.234276 -0.669526 0.704875 -0.234282 -0.669528 0.704872 -0.0794192 -0.704875 0.704871 -0.0794163 -0.704873 0.704873 0.0794209 -0.704873 0.704873 0.108196 -0.960254 0.257305 0.31916 -0.912102 0.257307 0.319157 -0.912104 0.257303 0.514122 -0.818214 0.257303 0.514118 -0.818218 0.257296 0.683298 -0.683304 0.257292 0.6833 -0.6833 0.257297 0.818219 -0.514118 0.257295 0.818218 -0.514121 0.257291 0.912104 -0.319168 0.25729 0.912105 -0.319146 0.257315 0.960252 -0.108185 0.257316 0.960254 -0.108194 0.257306 0.960255 0.108186 0.257306 0.960251 0.108194 0.257317 0.912098 0.319166 0.257315 0.912111 0.319148 0.25729 0.818219 0.514119 0.257291 0.818217 0.514121 0.257295 0.683298 0.683303 0.257296 0.683301 0.683301 0.257292 0.514123 0.818215 0.257296 0.514117 0.818217 0.257303 0.319161 0.912103 0.257303 0.319157 0.912103 0.257307 0.108197 0.960254 0.257305 0.108196 0.960254 0.257306 -0.108197 0.960254 0.257306 -0.108193 0.960255 0.257302 -0.319154 0.912107 0.257298 -0.319157 0.912104 0.257303 -0.514122 0.818214 0.257303 -0.514118 0.818218 0.257296 -0.683298 0.683304 0.257292 -0.6833 0.6833 0.257297 -0.818219 0.514118 0.257295 -0.818218 0.514121 0.257291 -0.912104 0.319168 0.25729 -0.912105 0.319146 0.257315 -0.960252 0.108185 0.257316 -0.960254 0.108194 0.257306 -0.960255 -0.108186 0.257306 -0.960251 -0.108194 0.257317 -0.912098 -0.319166 0.257315 -0.912111 -0.319148 0.25729 -0.818219 -0.514119 0.257291 -0.818217 -0.514121 0.257295 -0.683298 -0.683303 0.257296 -0.683301 -0.683301 0.257292 -0.514123 -0.818215 0.257296 -0.514117 -0.818217 0.257303 -0.319154 -0.912105 0.257303 -0.319158 -0.912105 0.257298 -0.108197 -0.960255 0.257302 -0.108193 -0.960254 0.257306 0.108197 -0.960254 0.257306 0.029149 -0.258714 0.965514 0.0859883 -0.245742 0.965514 0.0859888 -0.245741 0.965514 0.138513 -0.220448 0.965514 0.138515 -0.220442 0.965515 0.184097 -0.184091 0.965515 0.184097 -0.184092 0.965515 0.220442 -0.138517 0.965515 0.220441 -0.138514 0.965515 0.245736 -0.0859876 0.965515 0.245739 -0.0859942 0.965514 0.258714 -0.029149 0.965514 0.258708 -0.0291415 0.965516 0.258708 0.0291484 0.965516 0.258715 0.0291423 0.965514 0.24574 0.0859884 0.965514 0.245733 0.0859922 0.965516 0.220439 0.138516 0.965515 0.220443 0.138515 0.965515 0.184097 0.184092 0.965515 0.184096 0.184092 0.965515 0.138511 0.220445 0.965515 0.138517 0.220446 0.965514 0.0859896 0.24574 0.965514 0.0859884 0.24574 0.965514 0.0291492 0.258712 0.965515 0.0291487 0.258712 0.965515 -0.0291484 0.258712 0.965515 -0.0291487 0.258711 0.965515 -0.0859886 0.245737 0.965515 -0.085986 0.245742 0.965514 -0.138517 0.220446 0.965514 -0.138517 0.220445 0.965514 -0.184096 0.184098 0.965514 -0.184097 0.184092 0.965515 -0.220441 0.138517 0.965515 -0.220441 0.138514 0.965515 -0.245736 0.0859868 0.965515 -0.245735 0.0859835 0.965516 -0.258706 0.0291482 0.965516 -0.258708 0.0291506 0.965516 -0.258708 -0.0291484 0.965516 -0.258706 -0.0291503 0.965516 -0.245734 -0.0859867 0.965516 -0.245738 -0.0859846 0.965515 -0.220441 -0.138516 0.965515 -0.220443 -0.138515 0.965515 -0.184094 -0.184096 0.965515 -0.1841 -0.184095 0.965513 -0.138517 -0.220446 0.965514 -0.138517 -0.220446 0.965514 -0.0859881 -0.245741 0.965514 -0.0859853 -0.24574 0.965515 -0.0291503 -0.258713 0.965514 -0.0291487 -0.258712 0.965515 0.029151 -0.258712 0.965515 0.0794231 -0.704871 0.704875 0.234276 -0.669526 0.704875 0.234276 -0.669526 0.704875 0.377385 -0.600608 0.704876 0.377383 -0.600615 0.704872 0.501575 -0.501575 0.704872 0.501577 -0.501562 0.70488 0.600603 -0.377385 0.70488 0.600604 -0.377396 0.704874 0.669531 -0.234269 0.704874 0.669535 -0.234282 0.704865 0.704882 -0.0794209 0.704864 0.70488 -0.0794182 0.704866 0.70488 0.0794208 0.704866 0.704883 0.0794184 0.704864 0.669538 0.234272 0.704865 0.669528 0.234278 0.704873 0.60061 0.377389 0.704872 0.600597 0.377394 0.704881 0.50157 0.50157 0.70488 0.501583 0.501568 0.704872 0.377387 0.600611 0.704872 0.37738 0.600611 0.704877 0.234276 0.669526 0.704875 0.234282 0.669528 0.704872 0.0794211 0.704875 0.704871 0.0794185 0.704873 0.704873 -0.079419 0.704873 0.704873 -0.0794165 0.704876 0.704871 -0.234277 0.66953 0.704872 -0.234281 0.669525 0.704876 -0.377385 0.600608 0.704876 -0.377387 0.600602 0.70488 -0.501568 0.501568 0.704882 -0.501568 0.501572 0.70488 -0.600603 0.377385 0.70488 -0.600605 0.377399 0.704872 -0.669532 0.23427 0.704872 -0.669536 0.234281 0.704865 -0.704882 0.0794209 0.704864 -0.70488 0.0794182 0.704866 -0.70488 -0.0794208 0.704866 -0.704883 -0.0794184 0.704864 -0.669538 -0.234272 0.704865 -0.669526 -0.234279 0.704874 -0.600609 -0.377388 0.704874 -0.600598 -0.377392 0.704881 -0.50157 -0.50157 0.70488 -0.501565 -0.50157 0.704883 -0.377383 -0.600605 0.70488 -0.377389 -0.600606 0.704876 -0.234276 -0.669526 0.704875 -0.234276 -0.669526 0.704875 -0.0794188 -0.704872 0.704875 -0.0794211 -0.704873 0.704873 0.0794209 -0.704873 0.704873 0.108196 -0.960254 0.257305 0.31916 -0.912102 0.257307 0.319157 -0.912104 0.257303 0.514122 -0.818214 0.257303 0.514118 -0.818218 0.257296 0.683298 -0.683304 0.257292 0.6833 -0.6833 0.257297 0.818219 -0.514118 0.257295 0.818218 -0.514121 0.257291 0.912104 -0.319168 0.25729 0.912105 -0.319146 0.257315 0.960252 -0.108185 0.257316 0.960254 -0.108194 0.257306 0.960255 0.108186 0.257306 0.960251 0.108194 0.257317 0.912098 0.319166 0.257315 0.912111 0.319148 0.25729 0.818219 0.514119 0.257291 0.818217 0.514121 0.257295 0.683298 0.683303 0.257296 0.683301 0.683301 0.257292 0.514123 0.818215 0.257296 0.514117 0.818217 0.257303 0.319161 0.912103 0.257303 0.319157 0.912103 0.257307 0.108197 0.960254 0.257305 0.108196 0.960254 0.257306 -0.108197 0.960254 0.257306 -0.108193 0.960255 0.257302 -0.319154 0.912107 0.257298 -0.319157 0.912104 0.257303 -0.514122 0.818214 0.257303 -0.514118 0.818218 0.257296 -0.683298 0.683304 0.257292 -0.6833 0.6833 0.257297 -0.818219 0.514118 0.257295 -0.818218 0.514121 0.257291 -0.912104 0.319168 0.25729 -0.912105 0.319146 0.257315 -0.960252 0.108185 0.257316 -0.960254 0.108194 0.257306 -0.960255 -0.108186 0.257306 -0.960251 -0.108194 0.257317 -0.912098 -0.319166 0.257315 -0.912111 -0.319148 0.25729 -0.818219 -0.514119 0.257291 -0.818217 -0.514121 0.257295 -0.683298 -0.683303 0.257296 -0.683301 -0.683301 0.257292 -0.514123 -0.818215 0.257296 -0.514117 -0.818217 0.257303 -0.319154 -0.912105 0.257303 -0.319158 -0.912105 0.257298 -0.108197 -0.960255 0.257302 -0.108193 -0.960254 0.257306 0.108197 -0.960254 0.257306 -0.0226384 0.258754 -0.965678 -0.0672264 0.250893 -0.965678 -0.0672267 0.250893 -0.965678 -0.109774 0.235408 -0.965677 -0.109772 0.235406 -0.965678 -0.148982 0.212767 -0.965678 -0.148978 0.212764 -0.96568 -0.183658 0.183662 -0.96568 -0.183667 0.183667 -0.965677 -0.212771 0.148983 -0.965677 -0.212777 0.148985 -0.965676 -0.235414 0.109777 -0.965676 -0.235414 0.109777 -0.965676 -0.2509 0.0672281 -0.965676 -0.250898 0.0672282 -0.965676 -0.258761 0.0226364 -0.965676 -0.258759 0.0226367 -0.965677 -0.258759 -0.0226361 -0.965677 -0.258761 -0.0226368 -0.965676 -0.250898 -0.0672275 -0.965676 -0.2509 -0.0672288 -0.965676 -0.235414 -0.109777 -0.965676 -0.235414 -0.109777 -0.965676 -0.212776 -0.148986 -0.965676 -0.212772 -0.148981 -0.965677 -0.183665 -0.183669 -0.965677 -0.18366 -0.18366 -0.96568 -0.148979 -0.212763 -0.96568 -0.14898 -0.212768 -0.965678 -0.109773 -0.235405 -0.965678 -0.109773 -0.235408 -0.965677 -0.0672266 -0.250893 -0.965678 -0.0672266 -0.250893 -0.965678 -0.0226388 -0.258754 -0.965678 -0.0226378 -0.258759 -0.965677 0.0226393 -0.258759 -0.965677 0.0226369 -0.258753 -0.965678 0.0672255 -0.250889 -0.965679 0.0672258 -0.25089 -0.965679 0.109769 -0.235403 -0.965679 0.109772 -0.235406 -0.965678 0.148982 -0.212767 -0.965678 0.148978 -0.212764 -0.96568 0.18366 -0.18366 -0.96568 0.183669 -0.183665 -0.965677 0.212769 -0.148985 -0.965677 0.212775 -0.148987 -0.965676 0.235416 -0.109774 -0.965675 0.235402 -0.109772 -0.965679 0.250887 -0.0672245 -0.965679 0.250884 -0.0672245 -0.96568 0.258746 -0.0226392 -0.96568 0.258759 -0.0226366 -0.965677 0.258759 0.0226404 -0.965677 0.258746 0.0226356 -0.96568 0.250884 0.0672239 -0.96568 0.250886 0.0672252 -0.965679 0.235403 0.109768 -0.965679 0.235414 0.109777 -0.965676 0.212774 0.148989 -0.965676 0.21277 0.148984 -0.965677 0.183667 0.183667 -0.965677 0.183662 0.183658 -0.96568 0.148979 0.212763 -0.96568 0.14898 0.212768 -0.965678 0.109771 0.235406 -0.965678 0.10977 0.235403 -0.965679 0.0672256 0.25089 -0.965679 0.0672256 0.250889 -0.965679 0.0226387 0.258752 -0.965678 0.0226382 0.258755 -0.965678 -0.022639 0.258755 -0.965678 -0.061749 0.705768 -0.705747 -0.183365 0.684322 -0.705748 -0.183363 0.684319 -0.705751 -0.299409 0.64208 -0.705753 -0.299411 0.642082 -0.70575 -0.406353 0.580338 -0.705751 -0.406364 0.580346 -0.705738 -0.500969 0.500966 -0.705736 -0.500943 0.500955 -0.705762 -0.580323 0.406352 -0.705765 -0.580343 0.406357 -0.705745 -0.642093 0.299403 -0.705743 -0.642058 0.299402 -0.705776 -0.684294 0.183357 -0.705777 -0.6843 0.183357 -0.705772 -0.705741 0.0617448 -0.705774 -0.705758 0.0617396 -0.705758 -0.705758 -0.0617459 -0.705758 -0.705742 -0.061738 -0.705774 -0.684299 -0.183359 -0.705772 -0.684295 -0.183355 -0.705777 -0.642063 -0.299389 -0.705777 -0.642087 -0.299415 -0.705744 -0.580339 -0.406363 -0.705745 -0.580327 -0.406346 -0.705764 -0.500951 -0.500947 -0.705762 -0.500961 -0.500973 -0.705737 -0.40636 -0.580349 -0.705738 -0.406357 -0.580336 -0.705751 -0.29941 -0.642083 -0.70575 -0.29941 -0.64208 -0.705753 -0.183364 -0.684319 -0.705751 -0.183364 -0.684323 -0.705748 -0.0617474 -0.705769 -0.705746 -0.0617486 -0.705765 -0.70575 0.0617461 -0.705765 -0.70575 0.0617492 -0.705771 -0.705744 0.183367 -0.68433 -0.705741 0.183365 -0.684327 -0.705744 0.299414 -0.642091 -0.705741 0.299407 -0.642084 -0.70575 0.406353 -0.580338 -0.705751 0.406364 -0.580346 -0.705738 0.500969 -0.500966 -0.705736 0.500963 -0.500963 -0.705742 0.580348 -0.406358 -0.705741 0.580319 -0.406351 -0.705769 0.642065 -0.299402 -0.70577 0.642086 -0.299403 -0.705751 0.684321 -0.183364 -0.70575 0.684326 -0.183364 -0.705744 0.70577 -0.061747 -0.705745 0.705757 -0.0617509 -0.705757 0.705758 0.0617462 -0.705758 0.705769 0.0617522 -0.705745 0.684326 0.183366 -0.705744 0.684322 0.183362 -0.705749 0.642083 0.29941 -0.70575 0.642068 0.299395 -0.70577 0.580325 0.406341 -0.705769 0.580341 0.406367 -0.705741 0.500965 0.500962 -0.705742 0.500967 0.500967 -0.705737 0.40636 0.580349 -0.705738 0.406357 0.580336 -0.705751 0.29941 0.642083 -0.70575 0.299411 0.642092 -0.705741 0.183366 0.684326 -0.705744 0.183365 0.68433 -0.705741 0.0617466 0.705771 -0.705744 0.0617486 0.705765 -0.70575 -0.0617471 0.705765 -0.70575 -0.0842081 0.962492 -0.25791 -0.250062 0.933247 -0.257914 -0.250065 0.933248 -0.257905 -0.408318 0.875648 -0.25791 -0.408325 0.87565 -0.257891 -0.55418 0.791442 -0.257884 -0.554167 0.791441 -0.257917 -0.683185 0.683181 -0.257919 -0.683185 0.683181 -0.257919 -0.791437 0.55417 -0.25792 -0.791429 0.554172 -0.25794 -0.875636 0.408322 -0.257944 -0.875657 0.408312 -0.257886 -0.933254 0.250063 -0.257885 -0.93325 0.250065 -0.257897 -0.962496 0.0842131 -0.257896 -0.962501 0.0842085 -0.257879 -0.9625 -0.0842131 -0.257879 -0.962496 -0.0842077 -0.257896 -0.933251 -0.250062 -0.257897 -0.933253 -0.250066 -0.257885 -0.87565 -0.408329 -0.257886 -0.875643 -0.408306 -0.257944 -0.791433 -0.554167 -0.257941 -0.791433 -0.554175 -0.25792 -0.683185 -0.683181 -0.257919 -0.683185 -0.683181 -0.257919 -0.554175 -0.791435 -0.257917 -0.554172 -0.791448 -0.257884 -0.40832 -0.875653 -0.25789 -0.408323 -0.875646 -0.25791 -0.250062 -0.933249 -0.257905 -0.250064 -0.933246 -0.257914 -0.0842094 -0.962492 -0.25791 -0.0842082 -0.962493 -0.257906 0.0842081 -0.962493 -0.257906 0.0842067 -0.962492 -0.25791 0.250062 -0.933247 -0.257914 0.250065 -0.933248 -0.257905 0.408318 -0.875648 -0.25791 0.408325 -0.87565 -0.257891 0.55418 -0.791442 -0.257884 0.554167 -0.791441 -0.257917 0.683185 -0.683181 -0.257919 0.683185 -0.683181 -0.257919 0.791437 -0.55417 -0.25792 0.791446 -0.554168 -0.257897 0.875648 -0.408327 -0.257896 0.875651 -0.408326 -0.257886 0.933254 -0.250063 -0.257885 0.93325 -0.250065 -0.257897 0.962496 -0.0842128 -0.257896 0.962501 -0.0842081 -0.257879 0.9625 0.0842135 -0.257879 0.962496 0.0842081 -0.257896 0.933251 0.250062 -0.257897 0.933253 0.250066 -0.257885 0.87565 0.408329 -0.257886 0.875649 0.408325 -0.257895 0.791442 0.554174 -0.257896 0.791441 0.554164 -0.25792 0.683185 0.683181 -0.257919 0.683185 0.683181 -0.257919 0.554175 0.791435 -0.257917 0.554172 0.791448 -0.257884 0.40832 0.875653 -0.25789 0.408323 0.875646 -0.25791 0.250062 0.933249 -0.257905 0.250064 0.933246 -0.257914 0.084208 0.962492 -0.25791 0.0842068 0.962493 -0.257906 -0.0842095 0.962493 -0.257906 -0.0226374 -0.258754 0.965678 -0.0672264 -0.250893 0.965678 -0.0672267 -0.250893 0.965678 -0.109774 -0.235408 0.965677 -0.109772 -0.235406 0.965678 -0.148982 -0.212767 0.965678 -0.148978 -0.212764 0.96568 -0.183658 -0.183662 0.96568 -0.183667 -0.183667 0.965677 -0.212771 -0.148983 0.965677 -0.212777 -0.148985 0.965676 -0.235414 -0.109777 0.965676 -0.235414 -0.109777 0.965676 -0.2509 -0.0672281 0.965676 -0.250898 -0.0672282 0.965676 -0.258761 -0.0226363 0.965676 -0.258759 -0.0226366 0.965677 -0.258759 0.0226362 0.965677 -0.258761 0.0226369 0.965676 -0.250898 0.0672275 0.965676 -0.2509 0.0672288 0.965676 -0.235414 0.109777 0.965676 -0.235414 0.109777 0.965676 -0.212776 0.148986 0.965676 -0.212772 0.148981 0.965677 -0.183665 0.183669 0.965677 -0.18366 0.18366 0.96568 -0.148979 0.212763 0.96568 -0.14898 0.212768 0.965678 -0.109773 0.235405 0.965678 -0.109773 0.235408 0.965677 -0.0672266 0.250893 0.965678 -0.0672266 0.250893 0.965678 -0.0226388 0.258754 0.965678 -0.0226385 0.258755 0.965678 0.022639 0.258755 0.965678 0.0226379 0.258753 0.965678 0.0672255 0.250889 0.965679 0.0672258 0.25089 0.965679 0.109769 0.235403 0.965679 0.109772 0.235406 0.965678 0.148982 0.212767 0.965678 0.148978 0.212764 0.96568 0.18366 0.18366 0.96568 0.183669 0.183665 0.965677 0.212769 0.148985 0.965677 0.212775 0.148987 0.965676 0.235416 0.109774 0.965675 0.235402 0.109772 0.965679 0.250887 0.0672245 0.965679 0.250884 0.0672245 0.96568 0.258746 0.0226393 0.96568 0.258759 0.0226367 0.965677 0.258759 -0.0226404 0.965677 0.258746 -0.0226355 0.96568 0.250884 -0.0672239 0.96568 0.250886 -0.0672252 0.965679 0.235403 -0.109768 0.965679 0.235414 -0.109777 0.965676 0.212774 -0.148989 0.965676 0.21277 -0.148984 0.965677 0.183667 -0.183667 0.965677 0.183662 -0.183658 0.96568 0.148979 -0.212763 0.96568 0.14898 -0.212768 0.965678 0.109771 -0.235406 0.965678 0.10977 -0.235403 0.965679 0.0672256 -0.25089 0.965679 0.0672256 -0.250889 0.965679 0.0226387 -0.258752 0.965678 0.0226375 -0.258759 0.965677 -0.0226393 -0.258759 0.965677 -0.0617477 -0.705754 0.705761 -0.183361 -0.684308 0.705762 -0.183359 -0.684306 0.705766 -0.299403 -0.642067 0.705768 -0.299405 -0.642069 0.705765 -0.406345 -0.580327 0.705766 -0.406356 -0.580334 0.705753 -0.500958 -0.500955 0.705751 -0.500933 -0.500945 0.705776 -0.580311 -0.406344 0.705779 -0.580331 -0.406348 0.70576 -0.64208 -0.299397 0.705758 -0.642045 -0.299396 0.705791 -0.68428 -0.183354 0.705792 -0.684286 -0.183353 0.705787 -0.705727 -0.0617433 0.705788 -0.705744 -0.0617381 0.705772 -0.705743 0.061745 0.705772 -0.705728 0.061737 0.705788 -0.684285 0.183355 0.705787 -0.684281 0.183352 0.705792 -0.64205 0.299383 0.705791 -0.642074 0.299409 0.705758 -0.580327 0.406355 0.705759 -0.580316 0.406337 0.705779 -0.50094 0.500937 0.705777 -0.500951 0.500962 0.705751 -0.406352 0.580337 0.705753 -0.406349 0.580324 0.705765 -0.299404 0.64207 0.705765 -0.299404 0.642067 0.705768 -0.18336 0.684305 0.705766 -0.18336 0.684309 0.705762 -0.0617462 0.705754 0.705761 -0.0617474 0.70575 0.705765 0.0617448 0.70575 0.705765 0.0617479 0.705757 0.705758 0.183363 0.684316 0.705755 0.183361 0.684313 0.705758 0.299408 0.642078 0.705755 0.299401 0.642071 0.705765 0.406345 0.580327 0.705766 0.406356 0.580334 0.705753 0.500958 0.500955 0.705751 0.500953 0.500953 0.705756 0.580336 0.406349 0.705755 0.580307 0.406343 0.705783 0.642052 0.299396 0.705785 0.642073 0.299397 0.705765 0.684307 0.183361 0.705764 0.684313 0.18336 0.705759 0.705756 0.061746 0.70576 0.705743 0.0617499 0.705772 0.705743 -0.0617447 0.705772 0.705755 -0.0617507 0.70576 0.684312 -0.183362 0.705759 0.684308 -0.183359 0.705764 0.64207 -0.299404 0.705765 0.642055 -0.299389 0.705784 0.580313 -0.406333 0.705783 0.580329 -0.406359 0.705755 0.500955 -0.500952 0.705756 0.500957 -0.500957 0.705751 0.406352 -0.580337 0.705753 0.406349 -0.580324 0.705765 0.299404 -0.64207 0.705765 0.299404 -0.642079 0.705756 0.183362 -0.684312 0.705758 0.183362 -0.684316 0.705755 0.0617454 -0.705757 0.705758 0.0617474 -0.70575 0.705765 -0.0617458 -0.70575 0.705765 -0.0842083 -0.962494 0.257903 -0.250062 -0.933249 0.257906 -0.250065 -0.93325 0.257898 -0.408319 -0.87565 0.257902 -0.408326 -0.875652 0.257883 -0.554181 -0.791444 0.257877 -0.554168 -0.791442 0.257909 -0.683186 -0.683182 0.257912 -0.683186 -0.683182 0.257912 -0.791439 -0.554171 0.257913 -0.791431 -0.554173 0.257933 -0.875638 -0.408323 0.257937 -0.875659 -0.408313 0.257879 -0.933256 -0.250063 0.257878 -0.933252 -0.250066 0.25789 -0.962498 -0.0842129 0.257889 -0.962502 -0.0842083 0.257872 -0.962502 0.0842137 0.257872 -0.962498 0.0842082 0.257888 -0.933253 0.250062 0.25789 -0.933255 0.250067 0.257878 -0.875652 0.408329 0.257879 -0.875645 0.408307 0.257937 -0.791434 0.554168 0.257933 -0.791435 0.554177 0.257913 -0.683186 0.683182 0.257912 -0.683186 0.683182 0.257912 -0.554176 0.791437 0.25791 -0.554173 0.791449 0.257877 -0.408321 0.875654 0.257883 -0.408324 0.875647 0.257902 -0.250063 0.933251 0.257898 -0.250065 0.933248 0.257906 -0.0842096 0.962494 0.257903 -0.0842084 0.962495 0.257899 0.0842082 0.962495 0.257899 0.0842068 0.962494 0.257903 0.250062 0.933249 0.257906 0.250065 0.93325 0.257898 0.408319 0.87565 0.257902 0.408326 0.875652 0.257883 0.554181 0.791444 0.257877 0.554168 0.791442 0.257909 0.683186 0.683182 0.257912 0.683186 0.683182 0.257912 0.791439 0.554171 0.257913 0.791448 0.554169 0.257889 0.875649 0.408328 0.257888 0.875653 0.408327 0.257879 0.933256 0.250063 0.257878 0.933252 0.250066 0.25789 0.962498 0.0842133 0.257889 0.962502 0.0842086 0.257872 0.962502 -0.0842133 0.257872 0.962498 -0.0842079 0.257889 0.933253 -0.250062 0.25789 0.933255 -0.250067 0.257878 0.875652 -0.408329 0.257879 0.875651 -0.408326 0.257888 0.791444 -0.554175 0.257889 0.791443 -0.554166 0.257913 0.683186 -0.683182 0.257912 0.683186 -0.683182 0.257912 0.554176 -0.791437 0.25791 0.554173 -0.791449 0.257877 0.408321 -0.875654 0.257883 0.408324 -0.875647 0.257902 0.250063 -0.933251 0.257898 0.250065 -0.933248 0.257906 0.0842081 -0.962494 0.257903 0.0842069 -0.962495 0.257899 -0.0842097 -0.962495 0.257899 -0.985426 -0.170102 0 -0.985426 -0.170102 0 -0.87137 -0.490627 0 -0.87137 -0.490627 0 -0.656461 -0.75436 0 -0.656461 -0.75436 0 -0.365571 -0.930784 0 -0.365571 -0.930784 0 -0.201912 -0.979404 0 -0.201912 -0.979404 4.81989e-08 -0.201912 -0.979404 0 -0.0949378 -0.995483 0 -0.0949378 -0.995483 0 0.121079 -0.992643 0 0.170023 -0.98318 -0.066702 0.0667667 -0.997769 0 0.205766 -0.978601 0 0.190932 -0.977523 0.089408 0.169709 -0.985494 0 0.131835 -0.991272 0 0.118753 -0.989266 0.0851503 0.0953623 -0.995443 0 0.0571621 -0.998365 0 0.0458831 -0.995781 0.0794668 0.0204794 -0.99979 0 -0.0178323 -0.999841 0 -0.0273046 -0.997005 0.0723509 -0.0545185 -0.998513 0 -0.0927263 -0.995692 0 -0.100429 -0.992897 0.0637975 -0.12921 -0.991617 0 -0.102828 -0.994699 0 -0.0684959 -0.994613 -0.0778086 -0.034245 -0.999414 0 0 -1 0 0 -1 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.201912 0.979404 0 -0.201912 0.979404 5.31355e-08 -0.201912 0.979404 0 0.174302 0.984692 0 0.121005 0.992036 -0.0349636 0.0669168 0.997759 0 -0.0949378 0.995483 0 -0.0949378 0.995483 0 -0.0545185 0.998513 0 -0.100634 0.994924 0 -0.0924193 0.992395 0.081305 -0.12921 0.991617 0 -0.0177473 0.995072 0.0975555 -0.0273764 0.999625 0 0.0204795 0.99979 0 0.0458831 0.995781 0.0794665 0.0571621 0.998365 0 0.0953624 0.995443 0 0.118753 0.989266 0.0851501 0.131835 0.991272 0 0.169709 0.985494 0 0.190932 0.977523 0.089408 0.205766 0.978601 0 -0.0687042 0.997637 0 -0.0957451 0.985494 -0.140122 -0.034245 0.999414 0 0 1 0 0 1 0 -0.365571 0.930784 0 -0.365571 0.930784 0 -0.656461 0.75436 0 -0.656461 0.75436 0 -0.87137 0.490627 0 -0.87137 0.490627 0 -0.985426 0.170102 0 -0.985426 0.170102 0 0.373362 0.905516 -0.201599 0.19509 0.980785 0 0.119426 0.990316 -0.0707905 0.291912 0.956445 0 0.555569 0.831471 0 0.555569 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980785 0.195091 0 0.980785 0.195091 0 0.100391 -0.994948 0 0.194932 -0.979989 -0.0402773 0.29118 -0.956668 -0.000581704 0.381189 -0.924497 0 0.555569 -0.831471 0 0.555569 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980785 -0.195091 0 0.980785 -0.195091 0 0.258818 0.965926 0 0.258818 0.965926 0 0.70711 0.707104 0 0.70711 0.707104 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.70711 -0.707104 0 0.70711 -0.707104 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.70711 -0.707104 0 -0.70711 -0.707104 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.70711 0.707104 0 -0.70711 0.707104 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.508593 0.508588 -0.694745 0.508589 0.50859 -0.694747 0.694746 0.186157 -0.694747 0.694746 0.186158 -0.694747 0.694746 -0.186157 -0.694747 0.694746 -0.186158 -0.694747 0.508592 -0.508587 -0.694747 0.50859 -0.508591 -0.694746 0.186156 -0.694747 -0.694746 0.186157 -0.694747 -0.694746 -0.186156 -0.694747 -0.694747 -0.186157 -0.694747 -0.694746 -0.508593 -0.508588 -0.694745 -0.508589 -0.50859 -0.694747 -0.694746 -0.186157 -0.694747 -0.694746 -0.186158 -0.694747 -0.694746 0.186157 -0.694747 -0.694746 0.186158 -0.694747 -0.508592 0.508587 -0.694747 -0.50859 0.508591 -0.694746 -0.186156 0.694747 -0.694746 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186157 0.694747 -0.694746 0.258818 0.965926 0 0.258818 0.965926 0 0.70711 0.707104 0 0.70711 0.707104 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.70711 -0.707104 0 0.70711 -0.707104 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.70711 -0.707104 0 -0.70711 -0.707104 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.70711 0.707104 0 -0.70711 0.707104 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.508593 0.508588 -0.694745 0.508589 0.50859 -0.694747 0.694746 0.186157 -0.694747 0.694746 0.186158 -0.694747 0.694746 -0.186157 -0.694747 0.694746 -0.186158 -0.694747 0.508592 -0.508587 -0.694747 0.50859 -0.508591 -0.694746 0.186156 -0.694747 -0.694746 0.186157 -0.694747 -0.694746 -0.186156 -0.694747 -0.694747 -0.186157 -0.694747 -0.694746 -0.508593 -0.508588 -0.694745 -0.508589 -0.50859 -0.694747 -0.694746 -0.186157 -0.694747 -0.694746 -0.186158 -0.694747 -0.694746 0.186157 -0.694747 -0.694746 0.186158 -0.694747 -0.508592 0.508587 -0.694747 -0.50859 0.508591 -0.694746 -0.186156 0.694747 -0.694746 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186157 0.694747 -0.694746 0.258818 0.965926 0 0.258818 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258823 -0.965925 0 -0.258823 -0.965925 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258823 0.965925 0 -0.258823 0.965925 0 0.508588 0.50859 -0.694748 0.508591 0.508588 -0.694747 0.694746 0.186157 -0.694747 0.694746 0.186158 -0.694747 0.694746 -0.186157 -0.694747 0.694746 -0.186158 -0.694747 0.508589 -0.508591 -0.694747 0.50859 -0.508588 -0.694748 0.186156 -0.694746 -0.694747 0.186155 -0.694747 -0.694747 -0.18616 -0.694746 -0.694746 -0.186157 -0.694746 -0.694747 -0.508588 -0.50859 -0.694748 -0.508591 -0.508588 -0.694747 -0.694746 -0.186157 -0.694747 -0.694746 -0.186158 -0.694747 -0.694746 0.186157 -0.694747 -0.694746 0.186158 -0.694747 -0.508589 0.508591 -0.694747 -0.50859 0.508588 -0.694748 -0.186159 0.694745 -0.694748 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186155 0.694747 -0.694747 0.258818 0.965926 0 0.258818 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258823 -0.965925 0 -0.258823 -0.965925 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258823 0.965925 0 -0.258823 0.965925 0 0.508588 0.50859 -0.694748 0.508591 0.508588 -0.694747 0.694746 0.186157 -0.694747 0.694746 0.186158 -0.694747 0.694746 -0.186157 -0.694747 0.694746 -0.186158 -0.694747 0.508589 -0.508591 -0.694747 0.50859 -0.508588 -0.694748 0.186156 -0.694746 -0.694747 0.186155 -0.694747 -0.694747 -0.18616 -0.694746 -0.694746 -0.186157 -0.694746 -0.694747 -0.508588 -0.50859 -0.694748 -0.508591 -0.508588 -0.694747 -0.694746 -0.186157 -0.694747 -0.694746 -0.186158 -0.694747 -0.694746 0.186157 -0.694747 -0.694746 0.186158 -0.694747 -0.508589 0.508591 -0.694747 -0.50859 0.508588 -0.694748 -0.186159 0.694745 -0.694748 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186155 0.694747 -0.694747 0.164477 -0.701691 0.693237 0.164272 -0.702364 0.692603 0.162951 -0.70881 0.68632 0.161046 -0.714017 0.681355 -0.113384 -0.722331 0.682189 -0.103818 -0.70903 0.697494 -0.118904 -0.735375 0.667147 -0.117915 -0.732113 0.670899 -0.115381 -0.721486 0.682748 0.145517 -0.692062 0.707018 0.120008 -0.696885 0.70707 0.1071 -0.725462 0.679879 0.0932347 -0.701036 0.707005 0.0674341 -0.703913 0.707078 0.0511533 -0.730158 0.681361 0.0404263 -0.706066 0.706991 0.0144816 -0.70698 0.707085 -0.00488112 -0.730165 0.683254 -0.0126117 -0.707125 0.706976 -0.0385513 -0.706071 0.707091 -0.0605842 -0.725502 0.685549 -0.065581 -0.704206 0.70696 -0.0913665 -0.70119 0.707096 -0.115386 0.721514 0.682717 -0.117931 0.732165 0.67084 -0.118904 0.735375 0.667147 -0.113384 0.722331 0.682189 -0.103818 0.70903 0.697494 -0.0913665 0.70119 0.707096 -0.0588649 0.704913 0.706847 -0.0681678 0.731982 0.677905 -0.0385513 0.706071 0.707091 -0.00472861 0.707351 0.706847 -0.0131943 0.73979 0.672709 0.0144817 0.70698 0.707085 0.0494354 0.705637 0.706847 0.042568 0.743472 0.66741 0.0674342 0.703913 0.707078 0.103309 0.699782 0.706847 0.0988098 0.742955 0.662008 0.120008 0.696885 0.70707 0.155632 0.690014 0.706865 0.154044 0.732619 0.662978 0.162951 0.70881 0.68632 0.164272 0.702365 0.692602 0.164477 0.701692 0.693236 -0.0711829 0.703755 -0.706867 -0.0711828 0.703755 -0.706868 -0.0193645 0.70708 -0.706868 -0.0193645 0.707081 -0.706868 0.0325582 0.706596 -0.706868 0.0325581 0.706596 -0.706868 0.0843053 0.702303 -0.706868 0.0843053 0.702303 -0.706868 0.135598 0.694226 -0.706869 0.135598 0.694227 -0.706868 -0.0673279 0.705976 -0.705028 -0.0673275 0.705975 -0.705029 0.085867 0.703961 -0.705028 0.085867 0.703962 -0.705028 -0.0486387 0.706271 -0.706269 -0.0486386 0.706271 -0.706269 -0.142774 0.692544 -0.707106 -0.142774 0.692544 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.707106 -0.701898 0.12116 -0.701898 -0.701894 0.121161 -0.701901 -0.620655 0.349461 -0.7019 -0.620658 0.349462 -0.701898 -0.467582 0.537314 -0.701898 -0.467583 0.537314 -0.701897 -0.260388 0.662977 -0.701897 -0.260388 0.662977 -0.701897 0.139281 0.700215 -0.700214 0.139282 0.700215 -0.700214 0.396638 0.593613 -0.700216 0.396638 0.593612 -0.700216 0.593612 0.396636 -0.700217 0.593616 0.396641 -0.700212 0.700218 0.139283 -0.700211 0.70022 0.139284 -0.700209 -0.707107 0 -0.707107 -0.707107 0 -0.707107 0.707112 0 -0.707102 0.707112 0 -0.707102 -0.260388 -0.662978 -0.701896 -0.260388 -0.662977 -0.701897 -0.467583 -0.537315 -0.701897 -0.467582 -0.537314 -0.701898 -0.620657 -0.349462 -0.701898 -0.620656 -0.34946 -0.7019 -0.701894 -0.12116 -0.701901 -0.701897 -0.121162 -0.701897 0.70022 -0.139283 -0.700209 0.700217 -0.139284 -0.700211 0.593617 -0.396639 -0.700212 0.593611 -0.396638 -0.700218 0.396638 -0.593613 -0.700216 0.396638 -0.593613 -0.700216 0.139281 -0.700215 -0.700214 0.139282 -0.700215 -0.700214 -0.142774 -0.692544 -0.707106 -0.142774 -0.692544 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0.085867 -0.703962 -0.705028 0.085867 -0.703962 -0.705028 -0.0673279 -0.705975 -0.705029 -0.0673275 -0.705976 -0.705028 -0.0486387 -0.706271 -0.706269 -0.0486387 -0.706271 -0.706269 0.135598 -0.694227 -0.706868 0.135598 -0.694226 -0.706869 0.0843053 -0.702303 -0.706868 0.0843053 -0.702303 -0.706868 0.0325581 -0.706596 -0.706868 0.0325581 -0.706596 -0.706868 -0.0193645 -0.70708 -0.706868 -0.0193646 -0.707081 -0.706868 -0.0711828 -0.703755 -0.706868 -0.0711829 -0.703755 -0.706867 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 0.974928 -0.222521 0 0.974928 -0.222521 0 0.781832 -0.623489 0 0.781832 -0.623489 0 0.433887 -0.900967 0 0.433887 -0.900967 0 0 -1 0 0 -1 0 -0.433886 -0.900968 0 -0.433886 -0.900968 0 -0.781832 -0.623489 0 -0.781832 -0.623489 0 -0.974928 -0.222521 0 -0.974928 -0.222521 0 -1 0 0 -1 0 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0 1 0 0 1 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 1 0 0 1 0 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0 -1 0 0 -1 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707108 0.707106 0 0.707108 0.707106 0 0.965926 0.258818 0 0.965926 0.258818 0 -0.965926 0.258818 0 -0.965926 0.258818 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707108 0.707106 0 0.707108 0.707106 0 0.965926 0.258818 0 0.965926 0.258818 -0.707105 0 0.707109 -0.707105 0 0.707109 -0.694745 0.186157 0.694749 -0.694744 0.186157 0.694749 -0.694744 0.508591 0.508592 -0.694745 0.508591 0.508592 -0.694745 0.694749 0.186157 -0.694745 0.694749 0.186157 -0.694745 -0.694749 0.186157 -0.694745 -0.694749 0.186157 -0.694745 -0.508591 0.508591 -0.694744 -0.508591 0.508592 -0.694744 -0.186157 0.694749 -0.694745 -0.186157 0.694749 -0.707105 0.707109 0 -0.707105 0.707109 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.694745 0.694749 -0.186157 -0.694745 0.694749 -0.186157 -0.694745 0.508591 -0.508591 -0.694745 0.508591 -0.508591 -0.694745 0.186158 -0.694748 -0.694745 0.186157 -0.694749 -0.694744 -0.186158 -0.694748 -0.694745 -0.186157 -0.694748 -0.694745 -0.508591 -0.508591 -0.694745 -0.508591 -0.508591 -0.694745 -0.694749 -0.186157 -0.694745 -0.694749 -0.186157 -0.707105 0 -0.707109 -0.707105 0 -0.707109 -0.850912 -0.284649 0.441502 -0.942318 0.314918 -0.113413 -0.923155 0.367798 -0.111847 -0.915222 0.378704 -0.137665 -0.833595 0.471463 0.287824 -0.961455 0.258289 -0.0942923 -0.950003 0.307346 -0.0550779 -0.990056 0.13888 0.0224028 -0.978739 0.203074 -0.028827 -0.999569 0.0292823 -0.00223621 -0.998221 0.0386434 -0.0454051 -0.999794 -0.016744 -0.011467 -0.997778 -0.0497997 -0.0442612 -0.997406 -0.0313265 -0.0648042 -0.994707 -0.0762321 -0.0688945 -0.990617 -0.0901849 -0.102683 -0.989189 -0.105409 -0.101955 -0.933011 0.347096 -0.0949496 -0.78535 0.604953 0.131365 -0.772969 0.618551 0.141117 -0.849294 -0.00779416 0.527862 -0.811185 0.254867 0.526329 -0.876534 0.270311 0.398272 -0.818938 0.484916 0.306916 -0.835335 -0.0163521 0.549498 -0.946231 0.0410463 0.320877 -0.912822 0.255874 0.318253 -0.978898 0.204295 -0.00474966 -0.962714 0.268622 -0.0320061 -0.867202 -0.497844 -0.0105568 -0.868915 -0.494816 -0.0120162 -0.891391 -0.40872 0.195883 -0.891755 -0.408198 0.195316 -0.899327 -0.227149 0.37365 -0.950805 -0.166694 0.26112 -0.939104 0.033917 0.341954 -0.994438 0.101795 0.0270476 -0.991727 0.105353 -0.0733313 0.335019 -0.213624 0.917675 0.316463 -0.215784 0.923736 -0.110182 -0.0380574 0.993183 -0.0984578 -0.300513 0.948682 -0.107724 -0.470581 0.875756 0.359453 -0.515906 0.777583 -0.00381923 -0.623634 0.781707 -0.270804 -0.772588 0.574259 0.274607 -0.784669 0.555774 -0.622307 -0.779836 0.0677529 -0.0994974 -0.96872 0.227338 -0.0961189 -0.995221 -0.0172156 -0.505739 -0.856063 0.106694 0.075224 0.942917 0.32442 -0.242169 0.92489 0.293141 -0.0810541 0.146521 0.985881 0.333783 0.110492 0.936152 0.011343 0.288159 0.957515 -0.150404 0.568988 0.808474 -0.388734 0.608048 0.692217 -0.312895 0.605409 0.731831 -0.888115 0.446944 -0.107203 -0.702457 0.711302 -0.0245674 -0.73678 0.675318 -0.0331791 -0.536713 0.842141 0.0523237 -0.449003 0.890402 0.0747089 -0.391005 0.91506 0.0988935 0.142574 0.958009 0.248778 -0.178063 0.979074 0.0985292 -0.473258 -0.873853 0.11139 -0.509887 -0.734112 0.448437 -0.496726 -0.740714 0.452335 -0.510676 -0.471151 0.719184 -0.517527 -0.468166 0.71623 -0.497381 -0.110959 0.860407 -0.525878 -0.100976 0.844545 -0.468638 0.271103 0.840763 -0.514394 0.281195 0.810141 -0.430828 0.596604 0.67709 -0.485812 0.598131 0.637359 -0.240079 0.593266 0.768373 -0.327673 0.263314 0.907357 -0.268721 0.24777 0.930806 -0.328214 -0.138626 0.934376 -0.29393 -0.148325 0.944248 -0.31482 -0.520608 0.793635 -0.309487 -0.522059 0.794778 -0.294589 -0.805946 0.513487 -0.314167 -0.80057 0.510282 -0.275064 -0.949474 0.151127 -0.319101 -0.936312 0.146611 -0.44301 0.828429 0.342707 -0.0324486 0.830412 0.556205 -0.28926 0.840269 0.45856 -0.215184 0.840657 0.496983 -0.526637 0.78211 0.333101 -0.401075 0.807869 0.431842 -0.563884 0.762201 0.317938 -0.644909 0.566108 0.513434 -0.608964 0.571605 0.549938 -0.684444 0.286492 0.670417 -0.652879 0.28129 0.703295 -0.704908 -0.0564544 0.707048 -0.68366 -0.0659567 0.726814 -0.702061 -0.388238 0.596977 -0.694504 -0.393264 0.602501 -0.682301 -0.6336 0.364713 -0.688733 -0.628374 0.361654 -0.65676 -0.751249 0.0655092 -0.670817 -0.73894 0.0630155 -0.537112 -0.841834 0.0531737 -0.504876 0.859519 0.0795385 -0.996808 0.0622487 -0.0499825 -0.988703 0.105674 -0.106296 -0.989657 0.0960926 -0.106517 -0.994033 0.0826039 -0.0712379 -0.997501 0.030811 -0.0635866 -0.866063 0.499318 -0.0248534 -0.863685 0.503428 -0.0246715 -0.887006 0.422408 0.186524 -0.886891 0.422612 0.186611 -0.896754 0.25463 0.361934 -0.902636 0.245573 0.353473 -0.890461 0.011343 0.454919 -0.900768 0.000834136 0.4343 -0.863095 -0.252042 0.437655 -0.87559 -0.255507 0.409949 -0.819712 -0.472097 0.324341 -0.83238 -0.466456 0.299268 -0.773001 -0.614194 0.158853 0.307251 -0.0968556 0.946687 0.312561 -0.703365 0.638423 -0.108505 -0.333252 0.936574 -0.0748591 -0.461869 0.883783 0.371769 -0.391455 0.841755 -0.0528844 -0.61114 0.789754 -0.135098 -0.801576 0.582429 -0.0928081 -0.899385 0.427193 -0.0313048 -0.974223 0.223404 -0.188747 -0.963776 0.18844 -0.095996 0.994685 -0.0372457 -0.0915803 0.995553 -0.0220842 0.0431075 0.983318 0.176715 -0.317822 0.940866 0.117304 -0.489443 0.862562 0.12819 0.378154 0.725038 0.575604 -0.499648 0.75337 0.427535 0.0240329 0.649046 0.760369 0.333478 0.539352 0.773235 -0.106947 0.511017 0.852891 -0.0963238 0.292823 0.951302 0.357227 0.238299 0.903107 -0.335143 0.0107899 0.942106 0.207374 -0.108258 0.972253 -0.669874 0.74138 0.0403072 -0.272668 0.953182 0.130749 -0.312086 0.815904 0.486727 -0.291346 0.819468 0.493548 -0.308029 0.544021 0.780487 -0.311523 0.543655 0.779354 -0.292836 0.171341 0.940686 -0.326025 0.168659 0.930195 -0.267365 -0.2282 0.936184 -0.327285 -0.232279 0.915932 -0.237966 -0.578925 0.779883 -0.313982 -0.580267 0.751469 -0.212655 -0.831674 0.512928 -0.290781 -0.824966 0.484642 -0.199291 -0.96245 0.184319 -0.392346 -0.912054 0.119254 -0.924653 -0.350786 -0.148212 -0.919316 -0.37458 -0.120616 -0.930655 -0.356662 -0.0816943 -0.932902 -0.348652 -0.0901929 -0.956565 -0.289535 -0.0339441 -0.951002 -0.308887 0.01359 -0.980642 -0.193128 -0.0322827 -0.981325 -0.191889 0.0134408 -0.99151 -0.129415 0.0126026 -0.993348 -0.10906 -0.0369589 -0.996871 -0.0754327 0.0236368 -0.999961 -0.00589938 -0.00654601 -0.997158 -0.0523096 -0.0542226 -0.999627 0.0249975 -0.0110214 -0.469116 0.878351 0.0918135 -0.506145 0.749194 0.427229 -0.492062 0.754665 0.433999 -0.507684 0.492651 0.70679 -0.512993 0.491342 0.703862 -0.494853 0.133676 0.858633 -0.522807 0.130278 0.842437 -0.46632 -0.25195 0.847978 -0.513595 -0.252203 0.820131 -0.428447 -0.583299 0.690069 -0.486522 -0.575918 0.656974 -0.391853 -0.811355 0.433768 -0.528961 -0.766831 0.363553 -0.450525 -0.88668 0.104042 -0.705283 -0.708909 -0.00498215 -0.651546 0.757093 0.0479437 -0.684101 0.643 0.344321 -0.676701 0.648056 0.349426 -0.690404 0.41363 0.593509 -0.697042 0.410705 0.587753 -0.68039 0.0872355 0.727639 -0.701619 0.0834894 0.707644 -0.650234 -0.263765 0.712477 -0.683259 -0.261131 0.681885 -0.606475 -0.560235 0.564202 -0.645297 -0.548008 0.532239 -0.562921 -0.754733 0.336895 -0.784155 -0.603874 0.142958 -0.733229 -0.679576 -0.0234875 -0.889254 -0.445663 -0.103013 -0.352285 -0.919183 0.176062 -0.988075 0.121533 0.0945396 -0.986016 0.155634 0.0595914 -0.991825 0.124779 0.0267186 -0.960342 0.278763 0.00593951 -0.98065 0.194236 -0.0244485 -0.997083 0.0549946 0.0529271 -0.987475 0.109903 0.113202 -0.989039 0.0487341 0.139381 -0.994253 0.0303345 0.102666 -0.989238 0.012001 0.145825 -0.988553 -0.0371004 0.14624 -0.992856 -0.0268826 0.116248 -0.977811 -0.136758 0.158692 -0.988272 -0.101259 0.114298 -0.985059 -0.163375 0.0544789 -0.986093 -0.157936 0.0517464 -0.965704 -0.259634 0.00228551 -0.989432 -0.138189 -0.0439196 -0.983992 -0.178152 0.00467718 0.00874644 -0.617834 0.78626 -0.244882 -0.771458 0.587269 0.332701 -0.767465 0.548003 -0.570248 -0.804611 0.165585 -0.0995867 -0.974968 0.198794 -0.182436 -0.541367 0.820755 0.331053 -0.433751 0.838012 0.0475703 -0.183637 0.981842 0.104382 -0.169424 0.98 -0.190318 -0.306975 0.932494 0.0941551 0.203236 0.974592 -0.188477 0.127051 0.973825 -0.189437 -0.0431866 0.980943 -0.135898 0.833204 0.536006 -0.0403747 0.56172 0.826342 -0.182139 0.56569 0.804251 -0.190078 0.347442 0.918235 -0.0820592 0.276216 0.957586 -0.0877384 0.996017 -0.0158637 -0.0869865 0.996163 -0.0096767 -0.0263267 0.98268 0.183432 0.431965 0.887253 0.16183 -0.580252 0.71601 0.38812 -0.793393 -0.604195 0.0739986 -0.830371 -0.554611 0.0537544 -0.844409 -0.464138 0.267487 -0.839426 -0.469637 0.273506 -0.847944 -0.310052 0.429953 -0.844371 -0.312122 0.435451 -0.848527 -0.105851 0.518457 -0.847138 -0.105806 0.520732 -0.847195 0.116365 0.518382 -0.848304 0.115664 0.516723 -0.844286 0.321459 0.428771 -0.847775 0.317531 0.424796 -0.839485 0.475411 0.263153 -0.844579 0.468091 0.259956 -0.832186 0.552268 0.0496662 -0.832078 0.552429 0.0496713 -0.27759 -0.639246 0.717153 -0.263694 -0.803801 0.533262 -0.2793 -0.799856 0.531245 -0.257879 -0.94901 0.181327 -0.188063 -0.964843 0.183603 -0.277767 0.54828 0.788819 -0.264157 0.814142 0.517102 -0.279075 0.811763 0.512989 -0.258762 0.951973 0.163674 -0.287585 0.94475 0.157298 -0.610396 -0.784643 0.108408 -0.535651 -0.832621 0.140785 -0.554408 -0.702397 0.446397 -0.54335 -0.706783 0.453021 -0.55593 -0.46832 0.686744 -0.548692 -0.469448 0.691777 -0.554843 -0.159195 0.816582 -0.552254 -0.158934 0.818386 -0.552339 0.176132 0.8148 -0.554645 0.175352 0.813401 -0.548703 0.484778 0.681113 -0.555578 0.481176 0.678087 -0.543315 0.717195 0.436394 -0.554175 0.710314 0.433986 -0.535568 0.836038 0.119197 -0.557995 0.821215 0.119365 -0.156895 -0.681664 0.714646 -0.0847712 -0.996398 -0.0022589 -0.0735682 -0.997233 0.0106724 -0.179638 -0.823865 0.537565 -0.0669413 -0.90284 0.424734 0.0149655 -0.62166 0.783144 0.209438 -0.586759 0.782208 -0.161701 -0.475317 0.864827 -0.156868 -0.324042 0.932947 0.216698 -0.216769 0.951868 0.00473635 -0.176868 0.984223 -0.21453 0.496896 0.840876 -0.183526 0.506769 0.842321 -0.158729 0.292071 0.943133 0.1015 0.180145 0.978389 -0.166786 0.105992 0.98028 -0.158932 -0.0759551 0.984363 0.314378 0.844026 0.434496 -0.0904958 0.689584 0.71853 0.00186609 0.530875 0.847448 -0.954702 0.0242354 0.296575 -0.940885 0.0732691 0.330706 -0.94963 0.113896 0.291943 -0.958996 0.0741329 0.273552 -0.952981 0.136001 0.270797 -0.94346 -0.0856822 0.320223 -0.932715 -0.222869 0.283501 -0.945591 -0.173701 0.275111 -0.921659 -0.21305 0.324275 -0.935106 -0.148081 0.321946 -0.926434 -0.157986 0.341702 -0.925568 -0.120019 0.359052 -0.776066 0.422298 0.468387 -0.791905 0.399731 0.461629 -0.758247 0.252366 0.601144 -0.771106 0.239263 0.590041 -0.746866 0.0478909 0.663248 -0.753308 0.0446336 0.656151 -0.742704 -0.160078 0.650204 -0.741047 -0.16014 0.652077 -0.746998 -0.34395 0.56894 -0.737928 -0.348848 0.577727 -0.760502 -0.484452 0.432368 -0.746913 -0.497387 0.44128 -0.78321 -0.567321 0.254419 0.355329 -0.791285 0.497603 -0.237271 -0.878866 0.41388 -0.27137 -0.938582 0.213124 -0.111532 -0.976959 0.181964 0.1552 -0.978015 0.139284 0.0969822 0.954936 0.280521 -0.544153 0.615732 0.569888 -0.217501 0.772372 0.59677 -0.273237 0.75662 0.594027 -0.39447 0.705679 0.588566 -0.0670579 0.983388 0.168675 0.430495 0.896575 0.104054 -0.23559 0.935341 0.263885 -0.286374 0.920092 0.267248 -0.419032 0.862471 0.283826 -0.458211 0.842255 0.283988 -0.591972 0.750952 0.292644 -0.940026 -0.237147 0.245177 -0.953423 -0.196122 0.229173 -0.9477 -0.239643 0.210798 -0.927448 -0.0833231 0.364551 -0.929398 -0.0505498 0.3656 -0.944958 -0.0276726 0.326021 -0.931399 -0.0110829 0.363832 -0.937586 0.0359668 0.345889 -0.402002 -0.891379 0.209374 -0.564235 -0.78856 0.244565 -0.773684 -0.579238 0.256703 -0.221184 -0.954567 0.1997 -0.514584 -0.821537 0.24552 -0.459474 -0.715286 0.526545 -0.491673 -0.700515 0.517238 -0.456917 -0.490954 0.741748 -0.474422 -0.486794 0.733454 -0.46547 -0.205133 0.860963 -0.46503 -0.205109 0.861207 -0.481164 0.104112 0.870427 -0.463757 0.110331 0.879066 -0.499994 0.396847 0.769753 -0.469919 0.415026 0.779057 -0.521034 0.642915 0.561413 -0.563771 0.611559 0.55512 -0.618876 0.729745 0.29063 -0.81519 0.505772 0.282242 -0.804969 0.522745 0.280646 -0.961094 0.154578 0.228921 -0.959959 0.161053 0.229219 -0.958359 -0.14715 0.244736 -0.388608 0.881385 0.268597 -0.761429 -0.271506 0.588652 -0.933648 0.221251 0.28169 -0.781705 0.55695 0.280614 -0.769235 0.575158 0.278337 -0.940541 0.237855 0.242501 -0.940108 0.239527 0.242534 -0.744923 0.134842 0.653381 -0.744231 0.135104 0.654116 -0.748145 0.320631 0.580926 -0.740176 0.327416 0.587315 -0.760356 0.466022 0.452419 -0.748042 0.481167 0.457069 -0.930738 0.206324 0.301922 -0.943949 0.167444 0.284469 -0.944711 0.0195063 0.327325 -0.7573 -0.0705725 0.649243 -0.74971 -0.0716047 0.657882 -0.775667 -0.262426 0.573998 -0.938226 -0.0663953 0.339595 -0.910504 -0.102367 0.40063 0.183347 -0.234503 0.954669 0.188397 -0.630278 0.753165 -0.35638 -0.688357 0.631789 -0.0863168 -0.996242 0.00720433 -0.0826627 -0.99647 0.0146172 -0.157116 -0.301457 0.940446 -0.17678 -0.446286 0.877256 0.153671 -0.592811 0.790545 -0.23994 -0.605384 0.758907 -0.280846 -0.77799 0.562012 0.430775 -0.807565 0.40283 -0.0755138 -0.896982 0.435569 -0.23115 -0.949197 0.213531 -0.465526 -0.849191 0.249319 -0.40765 -0.739325 0.53593 -0.0373621 0.971112 0.235683 -0.361674 0.892134 0.270717 -0.163957 0.480149 0.861728 0.145152 0.54871 0.823315 -0.126051 0.629107 0.76703 -0.162365 0.663813 0.730061 -0.178656 0.783305 0.595412 -0.0248567 0.825524 0.563819 -0.265368 0.906319 0.328886 -0.276223 0.927416 0.25219 -0.212235 0.945627 0.246465 -0.161501 0.302034 0.939517 0.0631468 0.214599 0.974659 0.208587 0.167972 0.963471 -0.254472 0.0675382 0.964719 -0.0570188 -0.156161 0.986085 -0.59153 -0.765379 0.25355 -0.804973 -0.533626 0.259349 -0.820491 -0.511968 0.254329 -0.960983 -0.165268 0.221805 -0.972662 -0.108316 0.205417 -0.931492 0.0178055 0.363325 -0.929346 0.0598975 0.364319 -0.943145 0.0793071 0.322783 -0.925715 0.0977659 0.365368 -0.926619 0.153947 0.343043 -0.949909 0.109125 0.292856 -0.926139 0.171846 0.335761 -0.416603 -0.877336 0.238168 -0.625296 -0.735873 0.259799 -0.570245 -0.631572 0.525298 -0.779644 -0.434863 0.45061 -0.796919 -0.416334 0.437706 -0.948195 -0.129134 0.290259 -0.951427 -0.120212 0.283437 -0.557267 0.782313 0.278281 -0.517012 0.811831 0.271348 -0.464447 0.692597 0.551904 -0.493507 0.673318 0.55054 -0.462418 0.459169 0.758507 -0.477488 0.451757 0.753605 -0.471603 0.166858 0.865881 -0.469041 0.167453 0.867156 -0.487906 -0.144134 0.860914 -0.468237 -0.145215 0.871589 -0.507253 -0.432498 0.745413 -0.47473 -0.442752 0.760659 -0.527288 -0.656119 0.539885 -0.226362 -0.799432 0.556479 -0.293909 -0.927733 0.230063 -0.121854 -0.972604 0.197971 0.0521556 -0.983438 0.173576 -0.291704 -0.939379 0.180212 -0.987947 0.123576 0.0932213 -0.98573 0.158071 0.0578708 -0.991617 0.126853 0.0245811 -0.959417 0.281965 0.00378263 -0.965354 0.260915 -0.0038783 -0.997075 0.0566182 0.0513428 -0.98731 0.112189 0.1124 -0.989032 0.0505294 0.138791 -0.994243 0.0321869 0.102197 -0.989218 0.0137337 0.145807 -0.988626 -0.0351781 0.146221 -0.992651 -0.0256391 0.118268 -0.978825 -0.132388 0.156126 -0.988287 -0.0997299 0.115511 -0.985376 -0.160858 0.0562066 -0.986373 -0.155564 0.053552 -0.980909 -0.193469 -0.0196926 -0.989866 -0.135839 -0.0413891 -0.984438 -0.175595 0.00689462 0.0089576 -0.617974 0.786148 -0.245384 -0.770974 0.587695 0.332382 -0.768288 0.547043 -0.569846 -0.804509 0.167456 -0.0992482 -0.974967 0.198968 -0.182841 -0.541057 0.820869 0.331068 -0.434641 0.837545 0.0479762 -0.183852 0.981782 0.104414 -0.16984 0.979925 -0.190207 -0.306583 0.932646 0.0940327 0.202919 0.97467 -0.188269 0.127453 0.973813 -0.189529 -0.0430028 0.980933 -0.134515 0.833493 0.535906 -0.0415925 0.561848 0.826194 -0.181717 0.566056 0.804089 -0.190155 0.34854 0.917802 -0.0841191 0.277099 0.957152 -0.0864099 0.996139 -0.015537 -0.0857531 0.996266 -0.0100273 -0.0254744 0.982699 0.183448 0.433215 0.886373 0.163302 -0.580795 0.716655 0.386113 -0.832511 -0.550495 0.0622966 -0.832652 -0.550292 0.0622015 -0.844914 -0.462258 0.269144 -0.840061 -0.467627 0.274998 -0.847968 -0.308404 0.431089 -0.844669 -0.310323 0.436158 -0.848355 -0.104301 0.519052 -0.847337 -0.104271 0.520718 -0.846979 0.118042 0.518356 -0.848526 0.117068 0.516041 -0.84403 0.323288 0.427901 -0.847803 0.319051 0.423599 -0.838889 0.477355 0.261529 -0.844045 0.469975 0.258286 -0.830949 0.5543 0.0476939 -0.79317 0.606993 0.0494126 -0.277591 -0.638843 0.717512 -0.264349 -0.803255 0.533761 -0.279031 -0.799513 0.531903 -0.25877 -0.94866 0.181885 -0.188542 -0.964685 0.183945 -0.278212 0.548706 0.788366 -0.263597 0.814615 0.516642 -0.279403 0.812124 0.512239 -0.25914 0.950008 0.174159 -0.347152 0.925959 0.148616 -0.558507 -0.818766 0.133011 -0.536742 -0.831704 0.142042 -0.554489 -0.701472 0.447748 -0.544004 -0.705651 0.454 -0.555703 -0.467287 0.687631 -0.549089 -0.468332 0.692218 -0.554559 -0.158163 0.816976 -0.55255 -0.157965 0.818374 -0.552031 0.177238 0.814769 -0.554916 0.176269 0.813018 -0.548272 0.486012 0.680581 -0.555779 0.482098 0.677268 -0.542605 0.718397 0.4353 -0.554063 0.711167 0.432731 -0.533553 0.838264 0.112403 -0.609603 0.785404 0.107349 -0.964236 0.0589785 -0.258402 -0.698074 0.159329 -0.698074 -0.252757 0.215296 -0.943272 -0.252766 0.215293 -0.94327 -0.258667 0.451376 -0.85402 -0.0994774 0.620398 -0.777953 -0.254625 0.630788 -0.732989 -0.258166 0.798229 -0.544225 -0.00283191 0.900966 -0.433881 -0.256135 0.899821 -0.353154 -0.252767 0.967527 0 0.309197 0.945018 -0.106479 -0.257318 0.960251 0.108195 -0.252771 0.871711 0.419794 0.128685 0.923135 0.362302 -0.258158 0.798231 0.544226 -0.252762 0.603245 0.756444 -0.0656479 0.65088 0.756337 -0.258668 0.451363 0.854027 -0.252766 0.215295 0.943269 -0.25277 0.215295 0.943268 -0.698067 0.159332 -0.69808 -0.698067 0.446439 -0.559816 -0.698066 0.44644 -0.559817 -0.698066 0.645124 -0.310675 -0.698068 0.645122 -0.310674 -0.698067 0.716032 0 -0.698067 0.716032 0 -0.698068 0.645122 0.310675 -0.698066 0.645123 0.310676 -0.698066 0.44644 0.559818 -0.698067 0.44644 0.559816 -0.698067 0.159333 0.69808 -0.698066 0.159333 0.698081 -0.964236 0.0589773 -0.258399 -0.964236 0.165252 -0.207219 -0.964237 0.165251 -0.207219 -0.964237 0.238796 -0.114998 -0.964236 0.238796 -0.114998 -0.964236 0.265044 0 -0.964236 0.265044 0 -0.964236 0.238796 0.114998 -0.964237 0.238795 0.114998 -0.964237 0.165252 0.207218 -0.964236 0.165252 0.207219 -0.964236 0.0589778 0.258398 -0.964236 0.0589778 0.258398 -0.196975 -0.65136 0.732756 -0.0655506 -0.975387 0.210531 -0.0247984 -0.877594 0.478763 -0.111377 -0.130567 -0.985164 -0.0759077 -0.569232 -0.818666 -0.0168499 -0.963643 -0.26666 -0.693666 -0.0509294 0.718494 -0.782551 -0.110933 0.612624 -0.802551 -0.114606 0.585471 -0.793993 -0.14032 0.591512 -0.649485 -0.385201 0.655583 -0.611779 -0.427028 0.665863 -0.703969 -0.48635 0.517582 -0.788253 -0.500565 0.357898 -0.873635 -0.442493 0.20239 -0.861479 -0.480093 0.165422 -0.939629 -0.341872 0.0148656 -0.932491 -0.36047 -0.0228424 -0.983127 -0.133902 -0.124629 -0.97789 -0.136874 -0.158102 -0.540323 -0.826751 0.156632 -0.603168 -0.767314 0.217758 -0.372747 -0.926992 0.0417917 -0.463184 -0.877875 0.121638 -0.194045 -0.978435 -0.0707905 -0.309779 -0.950503 0.0241273 0.28842 -0.888683 -0.35645 -0.0867364 -0.994765 -0.0540256 -0.69102 -0.571569 -0.442493 -0.734626 -0.558669 -0.384985 -0.496359 -0.618425 -0.609244 -0.56235 -0.616446 -0.551141 -0.28104 -0.623997 -0.729139 -0.366602 -0.636714 -0.678379 0.170688 -0.519836 -0.83704 -0.105169 -0.732069 -0.673063 -0.613912 -0.774661 -0.151701 -0.670841 -0.737098 -0.0816039 -0.431284 -0.85129 -0.298829 -0.515502 -0.828559 -0.218511 -0.23283 -0.875981 -0.422431 -0.341644 -0.87645 -0.339286 -0.0681746 -0.862535 -0.501385 -0.281585 -0.890366 -0.357712 0.138278 -0.178528 0.97417 -0.161237 -0.00988894 0.986866 -0.0420442 -0.0366801 0.998442 -0.126143 -0.385129 0.914201 -0.763549 -0.091473 0.639238 -0.759907 -0.0419495 0.648677 -0.556433 -0.0924904 0.825729 -0.386096 -0.1429 0.911323 -0.32044 -0.151386 0.935094 0.548153 -0.26136 0.794493 -0.101036 -0.301784 0.948008 -0.249951 -0.635431 0.730584 0.495531 -0.85181 0.169907 -0.253132 -0.728736 0.636293 -0.138502 -0.79875 0.585504 -0.434635 -0.599437 0.672137 -0.293268 -0.727282 0.620527 -0.426955 -0.618767 0.659422 -0.77072 -0.084298 0.631573 -0.605148 -0.252887 0.75488 -0.573025 -0.275268 0.771926 -0.396697 -0.403019 0.824747 -0.323364 -0.439019 0.838271 0.00642296 -0.591334 0.806402 0.194872 -0.627007 0.754246 -0.975999 -0.0648979 0.207881 -0.963667 -0.0414359 0.263873 -0.953737 -0.186095 0.236126 -0.947277 -0.132333 0.291812 -0.907837 -0.201775 0.367586 -0.908634 -0.175782 0.378794 -0.881069 -0.195213 0.430825 -0.869585 -0.140048 0.473507 -0.861524 -0.181242 0.474266 -0.825301 -0.180332 0.535125 -0.850661 -0.0877326 0.518342 -0.818377 -0.155803 0.553159 -0.752318 -0.213662 -0.62319 -0.769831 -0.214328 -0.601185 -0.569157 -0.229552 -0.789536 -0.581786 -0.230615 -0.779963 -0.348948 -0.232815 -0.907762 -0.367557 -0.235545 -0.899678 0.309474 -0.159021 -0.937517 -0.124257 -0.349962 -0.928486 -0.0767798 -0.914607 0.396987 0.0819144 -0.988614 0.126225 -0.279984 -0.890727 0.358069 -0.16301 -0.947401 0.275424 -0.416286 -0.805944 0.420904 -0.323845 -0.874837 0.360256 -0.543335 -0.693868 0.472583 -0.477348 -0.764535 0.433156 -0.666487 -0.539513 0.514511 -0.764005 -0.542321 0.34955 -0.693741 -0.676148 0.248087 -0.793628 -0.605202 0.0623369 -0.762126 -0.647381 0.00789091 -0.864812 -0.464521 -0.190577 -0.841957 -0.482983 -0.24049 -0.908977 -0.180401 -0.375787 -0.900005 -0.181206 -0.39643 -0.386491 0.135712 0.912254 -0.158459 0.185122 0.969856 -0.678808 0.682509 0.270926 -0.796242 0.602341 0.0564326 -0.758769 0.651236 0.0126871 -0.866313 0.459879 -0.19497 -0.840058 0.487359 -0.238293 -0.909106 0.177772 -0.376727 -0.899664 0.183216 -0.396279 -0.859256 0.482968 0.168588 -0.940769 0.338847 0.0116782 -0.93133 0.363549 -0.02138 -0.983399 0.130848 -0.125718 -0.977466 0.139948 -0.158034 -0.903591 0.157241 0.398495 -0.925159 0.173905 0.337398 -0.944273 0.138473 0.298619 -0.946577 0.144122 0.28848 -0.972901 0.0615019 0.222892 -0.976148 0.0625038 0.207912 -0.604113 0.248703 0.757096 -0.906713 0.177226 0.382703 -0.875486 0.440613 0.198456 -0.787926 0.500453 0.358774 -0.770592 0.541414 0.336243 -0.671036 0.539447 0.508634 -0.699315 0.483105 0.526848 -0.615353 0.428795 0.66142 -0.0417698 0.119862 0.991911 0.783258 0.199298 0.588887 -0.0363821 0.303677 0.95208 -0.242731 0.431244 0.868971 -0.112217 0.0464652 -0.992597 0.147978 0.536758 -0.830658 0.211505 0.502659 -0.838212 -0.0987705 0.469215 -0.877543 -0.125415 0.349388 -0.928547 0.146764 0.151727 -0.977466 0.306003 0.159367 -0.938597 -0.348813 0.234381 -0.907411 -0.11122 0.737157 -0.666506 -0.0678119 0.810327 -0.582041 0.292015 0.716287 -0.633766 -0.191143 0.925699 -0.326413 0.09217 0.970305 -0.223636 -0.0798507 0.988047 -0.13186 -0.07753 0.987759 0.135353 0.356941 0.931322 -0.0723336 0.0288937 0.97307 0.22869 -0.240255 0.73627 0.632601 -0.327286 0.444687 0.833749 -0.439461 0.606457 0.662634 -0.281544 0.717299 0.63735 -0.420495 0.807498 0.413679 -0.318847 0.872973 0.369126 -0.468122 0.876389 0.113157 -0.367047 0.928765 0.0517012 -0.519938 0.823414 -0.227273 -0.426381 0.85657 -0.290666 -0.564807 0.608918 -0.556967 -0.493723 0.62475 -0.604917 -0.581896 0.22872 -0.780439 -0.568988 0.230773 -0.789301 -0.367801 0.232804 -0.900291 -0.278601 0.630836 -0.724173 -0.36956 0.628637 -0.684281 -0.227843 0.881703 -0.413144 -0.346908 0.870736 -0.34853 -0.188025 0.980361 -0.0594811 -0.315667 0.948754 0.0148363 -0.157564 0.94527 0.285724 -0.285138 0.89234 0.349895 -0.134615 0.794454 0.592218 -0.256607 0.733315 0.629605 -0.694238 0.0308129 0.719086 -0.798512 0.0413035 0.60056 -0.777161 0.102674 0.620869 -0.795943 0.130235 0.591196 -0.780187 0.172717 0.601229 -0.834323 0.138965 0.533474 -0.828416 0.180272 0.530311 -0.866817 0.181282 0.464505 -0.866002 0.121096 0.485157 -0.879986 0.195839 0.432749 0.0632806 0.880733 0.469366 -0.0879533 0.675961 0.73167 -0.195437 0.649193 0.735087 0.162778 0.63638 0.754005 -0.394508 0.394919 0.8297 -0.323052 0.159192 0.932896 -0.556446 0.092481 0.825721 -0.764761 0.0405013 0.64304 -0.758169 0.047344 0.650337 -0.769464 0.0858472 0.632895 -0.574995 0.27794 0.7695 -0.646486 0.380536 0.661248 -0.427137 0.618077 0.659951 -0.546605 0.695207 0.466808 -0.473085 0.763089 0.440325 -0.60698 0.766286 0.210669 -0.53532 0.828441 0.164678 -0.674297 0.733044 -0.0892749 -0.60948 0.779387 -0.145224 -0.736459 0.552448 -0.390422 -0.688484 0.577066 -0.439299 -0.769896 0.210937 -0.602301 -0.751881 0.216245 -0.622827 -0.890357 -0.112102 -0.441246 -0.199901 -0.979435 0.0273321 -0.187636 -0.912297 0.364016 -0.929534 -0.117257 -0.349596 -0.907769 -0.130523 -0.398646 -0.896739 -0.178297 -0.405056 -0.885158 -0.312102 -0.34509 -0.858508 -0.426718 -0.284387 -0.823559 -0.529232 -0.204119 -0.944392 -0.155067 -0.289961 -0.884998 -0.413679 -0.213653 -0.475482 -0.878017 0.0548047 -0.772844 -0.618178 -0.143417 -0.821651 -0.522597 -0.227557 -0.830857 -0.516725 -0.206571 -0.621177 -0.776974 -0.102228 -0.55655 -0.827964 -0.0687669 -0.437574 -0.898789 -0.0265989 0.112914 -0.978348 0.173453 -0.396246 -0.911729 0.108349 -0.151253 -0.966407 0.207796 -0.623098 -0.78206 -0.0114769 -0.649689 -0.75921 -0.0387834 -0.445593 -0.886164 0.127125 0.50794 -0.614078 0.604074 -0.144278 -0.917808 0.369882 -0.201628 -0.933371 0.296926 -0.811542 -0.579448 -0.0750937 -0.863103 -0.49348 0.107382 -0.927888 -0.0973671 -0.359922 -0.923215 -0.0587399 -0.379769 -0.947308 -0.313309 -0.0666681 -0.940785 -0.336928 -0.0374536 -0.563174 -0.633481 0.530601 -0.876052 -0.43529 0.207498 -0.134588 -0.437969 0.888858 -0.0918282 -0.595672 0.797962 -0.319086 -0.600049 0.73357 -0.732133 -0.53625 0.420021 -0.536788 -0.595706 0.597489 -0.270547 -0.606586 0.747568 -0.186761 -0.703572 0.685644 -0.207502 -0.710675 0.672223 -0.224725 -0.79591 0.562162 -0.233276 -0.797824 0.555931 -0.186021 -0.863765 0.468302 -0.227079 -0.872188 0.433272 -0.560179 -0.588773 0.582706 -0.519333 -0.694097 0.498521 -0.546768 -0.685187 0.481211 -0.499802 -0.773702 0.389336 -0.530837 -0.762606 0.369654 -0.479296 -0.8338 0.273956 -0.516434 -0.81902 0.250005 -0.117227 -0.139526 0.983255 -0.126486 -0.139177 0.982156 -0.343493 -0.140187 0.928633 -0.35598 -0.139193 0.924069 -0.569293 -0.132539 0.811381 -0.582931 -0.13062 0.801954 -0.771773 -0.114263 0.625548 -0.780721 -0.112111 0.61474 -0.918474 -0.0865501 0.385895 -0.923005 -0.084465 0.375402 -0.991542 -0.0523713 0.118755 -0.992571 -0.0507304 0.110585 -0.966534 -3.4276e-05 -0.25654 -0.827227 -0.560612 0.0375424 -0.533536 -0.78734 0.308926 -0.892555 -0.416203 -0.173552 -0.902547 -0.379903 -0.202687 -0.908979 -0.131763 -0.395468 -0.908283 -0.288301 -0.303158 -0.904859 -0.0970817 -0.414493 -0.942217 -0.0385132 -0.332781 -0.961674 -0.0362417 -0.271789 -0.965286 0.00122177 -0.261193 -0.748241 -0.52633 0.403871 -0.710516 -0.623559 0.326099 -0.729749 -0.610483 0.307858 -0.686246 -0.69241 0.22279 -0.707911 -0.676393 0.203357 -0.660227 -0.742236 0.11483 -0.684234 -0.723111 0.0945225 -0.943348 -0.0924613 -0.318663 -0.954348 -0.051901 -0.294153 -0.978644 -0.200646 0.0446972 -0.975327 -0.210732 0.0657939 -0.910595 -0.293991 0.290494 -0.899445 -0.304012 0.313967 -0.77332 -0.366334 0.51747 -0.752598 -0.375034 0.541245 -0.582556 -0.410304 0.701626 -0.552432 -0.416071 0.72229 -0.363239 -0.424636 0.829302 -0.325269 -0.426375 0.844041 0.184306 -0.356357 0.915992 -0.110255 -0.303564 0.94641 -0.187913 -0.981726 -0.0300666 -0.970946 -0.155858 -0.181582 -0.970553 -0.182358 -0.157394 -0.188037 -0.981547 -0.0347609 -0.190358 -0.981151 -0.0332516 -0.551836 -0.828562 -0.0946689 -0.548958 -0.830343 -0.0957838 -0.836117 -0.529539 -0.143168 -0.8328 -0.534159 -0.145323 -0.972458 -0.163353 -0.166254 -0.234063 0.000835401 0.972221 -0.966449 0.0112137 -0.256614 -0.965069 0.0113448 -0.261751 -0.992808 0.0115647 0.119156 -0.993318 0.0116398 0.114824 -0.921403 0.010736 0.38846 -0.922723 0.0108075 0.385311 -0.775226 0.00903557 0.631619 -0.776683 0.00909037 0.629826 -0.571283 0.00665884 0.820726 -0.572564 0.00669826 0.819833 -0.34275 0.00399657 0.939418 -0.243644 0.00139741 0.969864 -0.113801 0.00225219 0.993501 -0.167871 -0.973604 -0.154642 -0.175213 -0.972378 -0.154211 -0.539361 -0.828345 -0.151443 -0.539474 -0.828274 -0.151426 -0.836057 -0.534284 -0.124695 -0.844923 -0.520858 -0.121708 -0.983486 -0.163032 -0.0785813 -0.984669 -0.156445 -0.0771434 -0.234063 -0.000835402 0.972221 -0.233488 -0.00462088 0.972349 -0.274046 -0.00318928 0.961711 -0.571282 -0.00668319 0.820726 -0.572564 -0.00667398 0.819833 -0.775226 -0.00907309 0.631619 -0.776683 -0.00905298 0.629827 -0.921402 -0.0107915 0.38846 -0.922724 -0.0107522 0.385312 -0.992807 -0.0116329 0.119156 -0.993318 -0.0115719 0.114824 -0.966447 -0.0113595 -0.256615 -0.96507 -0.0111994 -0.261752 -0.608315 -0.0858587 -0.789038 -0.175839 -0.106489 -0.978642 -0.175849 -0.10649 -0.97864 -0.176444 -0.276846 -0.944576 0.217142 -0.341165 -0.91458 -0.176408 -0.406183 -0.896602 -0.175168 -0.586046 -0.791117 -0.175172 -0.586046 -0.791116 -0.175171 -0.782171 -0.597933 -0.175164 -0.782171 -0.597934 -0.176305 -0.893523 -0.412956 0.00853532 -0.919449 -0.393117 -0.176777 -0.932871 -0.313851 -0.984889 -0.159244 -0.0680856 -0.984889 -0.159244 -0.0680858 -0.98477 -0.138123 -0.105589 -0.984771 -0.138123 -0.105589 -0.984771 -0.103489 -0.139703 -0.984771 -0.103489 -0.139702 -0.984771 -0.0607641 -0.162893 -0.98477 -0.060765 -0.162896 -0.984889 -0.018735 -0.172173 -0.984888 -0.018735 -0.172174 -0.905944 -0.0458013 -0.420912 -0.793674 -0.0540064 -0.605942 -0.424239 -0.0798476 -0.902023 -0.539748 -0.0910655 -0.836887 -0.538225 -0.294564 -0.789649 -0.538215 -0.294565 -0.789656 -0.538216 -0.50168 -0.677231 -0.53822 -0.501678 -0.677228 -0.538221 -0.669569 -0.511855 -0.538227 -0.669566 -0.511852 -0.53975 -0.774043 -0.330947 -0.539748 -0.774045 -0.330948 -0.844029 -0.0580144 -0.533151 -0.843059 -0.187971 -0.503903 -0.84306 -0.187971 -0.503901 -0.84306 -0.320136 -0.43216 -0.843059 -0.320137 -0.432161 -0.843059 -0.427274 -0.326632 -0.84306 -0.427273 -0.326631 -0.844029 -0.493116 -0.210834 -0.844026 -0.49312 -0.210837 -0.964844 0.00440888 -0.262785 -0.571742 0.0583332 0.818357 -0.903794 0.102372 -0.415542 -0.564495 0.349752 0.747676 -0.17302 0.350229 0.920545 -0.23517 0.0674883 0.969608 -0.240007 0.0662275 0.96851 -0.234528 0.21599 0.947811 -0.961226 0.0399955 -0.272845 -0.943474 0.0350502 -0.329589 -0.975504 0.209892 0.0658612 -0.978283 0.202642 0.0435804 -0.899703 0.303083 0.314127 -0.910235 0.29656 0.289007 -0.752908 0.373975 0.541547 -0.772904 0.369473 0.515858 -0.0966671 0.405814 0.908829 -0.569652 0.478492 0.668238 -0.349911 0.491175 0.79769 -0.349097 0.491021 0.798141 -0.130075 0.45769 0.879546 -0.0877147 0.610093 0.787459 -0.269207 0.834741 0.480349 -0.342627 0.834887 0.43078 -0.211153 0.835543 0.50723 -0.161975 0.82929 0.534829 -0.0660303 0.812904 0.578642 -0.893578 0.414591 -0.172142 -0.901143 0.381732 -0.205478 -0.807914 0.589281 0.00480683 -0.833187 0.551197 -0.0445232 -0.664334 0.72421 0.18488 -0.709216 0.693252 0.128117 -0.477 0.807375 0.347297 -0.552208 0.785785 0.278581 -0.459087 0.814079 0.35569 -0.91727 0.0266465 -0.397373 -0.928248 0.096575 -0.359206 -0.91028 0.129397 -0.393251 -0.96617 -0.0252897 -0.256662 -0.956894 -0.00480363 -0.290399 -0.991554 0.0521183 0.118757 -0.992554 0.0515907 0.110337 -0.918503 0.0861565 0.385912 -0.923001 0.0857107 0.37513 -0.771811 0.113759 0.625593 -0.78072 0.113643 0.61446 -0.0842171 0.136581 0.987043 -0.579993 0.20682 0.78793 -0.243228 0.214057 0.946055 -0.230756 0.333471 0.914084 -0.952092 0.0606735 -0.299731 -0.938927 0.106403 -0.327252 -0.941319 0.335511 -0.0367484 -0.946407 0.315525 -0.0689783 -0.860314 0.476896 0.180084 -0.877711 0.45781 0.141542 -0.713654 0.584304 0.386378 -0.745859 0.569798 0.345 -0.51805 0.646569 0.559975 -0.565239 0.640129 0.520326 -0.298209 0.662444 0.687197 -0.357988 0.666497 0.653931 0.256404 0.533213 0.806189 -0.0717676 0.701869 0.708681 -0.176855 0 -0.984237 -0.176855 0 -0.984237 -0.425598 0 -0.904912 -0.425598 0 -0.904912 -0.610569 0 -0.791963 -0.610569 0 -0.791963 -0.794834 0 -0.606827 -0.794834 0 -0.606827 -0.906896 0 -0.421355 -0.906896 0 -0.421355 -0.985062 0 -0.172203 -0.985062 0 -0.172203 -0.628804 0.777388 -0.0165695 -0.951977 0.155432 -0.263783 -0.894994 0.111556 -0.431904 -0.890705 0.213398 -0.40138 -0.903547 0.132583 -0.40746 -0.822264 0.522129 -0.226412 -0.777066 0.611688 -0.148344 -0.858537 0.426792 -0.284188 -0.468463 0.874037 0.128849 -0.644639 0.762838 -0.0501929 0.363784 0.741511 0.563757 0.0191608 0.902622 0.430008 -0.0750513 0.920538 0.383377 -0.300867 0.914251 0.271337 -0.267789 0.916131 0.298316 -0.383335 0.897061 0.219857 -0.159685 0.980803 0.111923 -0.19108 0.965003 0.179605 -0.19361 0.98106 -0.00609718 0.124536 0.976081 0.178203 -0.555197 0.828199 -0.0764306 -0.923231 0.120949 -0.364714 -0.915909 0.303389 -0.262805 -0.830329 0.516964 -0.208091 -0.823866 0.529264 -0.202791 -0.621028 0.77713 -0.101953 -0.443389 0.896229 -0.01343 -0.475607 0.877869 0.0560626 -0.168592 0.954637 0.245449 -0.111967 0.959046 0.260179 -0.176779 0.932872 -0.313847 0.0692888 0.906885 -0.415642 -0.1759 0.906371 -0.384124 -0.175142 0.785457 -0.593618 -0.175144 0.785457 -0.593618 -0.175144 0.589071 -0.788872 -0.175147 0.589071 -0.788872 -0.176389 0.407522 -0.895998 0.221254 0.342799 -0.912982 -0.176459 0.277459 -0.944393 -0.175834 0.107127 -0.978574 -0.175837 0.107126 -0.978573 -0.608288 0.0863742 -0.789003 -0.984887 0.0188483 -0.172172 -0.905933 0.046078 -0.420907 -0.984887 0.0188479 -0.172171 -0.984767 0.0611199 -0.162782 -0.984767 0.0611214 -0.162785 -0.984767 0.104037 -0.139324 -0.984767 0.104036 -0.139323 -0.984767 0.13872 -0.104839 -0.984767 0.13872 -0.104839 -0.984899 0.159408 -0.0675577 -0.984899 0.159408 -0.0675578 -0.844111 0.493665 -0.209217 -0.539878 0.775015 -0.328456 -0.539876 0.775017 -0.328456 -0.538177 0.672402 -0.508175 -0.538182 0.672399 -0.508173 -0.538184 0.50428 -0.675322 -0.53818 0.504282 -0.675324 -0.538179 0.296264 -0.789044 -0.538177 0.296265 -0.789046 -0.539351 0.0845669 -0.837824 -0.423525 0.0985803 -0.900505 -0.844113 0.493662 -0.209217 -0.843032 0.429101 -0.324298 -0.84303 0.429104 -0.3243 -0.843029 0.321816 -0.43097 -0.84303 0.321816 -0.430969 -0.84303 0.189065 -0.503541 -0.843029 0.189066 -0.503543 -0.843638 0.051384 -0.534448 -0.793086 0.0662848 -0.605493 -0.973826 0.163527 -0.157868 -0.549202 0.830361 -0.0942218 -0.551544 0.828578 -0.0962148 -0.833235 0.534188 -0.1427 -0.835647 0.52957 -0.145772 -0.970837 0.172925 -0.16605 -0.970946 0.155853 -0.181585 -0.187539 0.98171 -0.0327721 -0.193768 0.980556 -0.0310323 -0.188037 0.981547 -0.0347609 -0.985012 0.1618 -0.0597698 -0.175227 0.972272 -0.154864 -0.168003 0.973678 -0.154034 -0.539474 0.828272 -0.151438 -0.539364 0.828345 -0.15143 -0.844968 0.520444 -0.123157 -0.836289 0.534285 -0.123132 -0.958571 0.269475 -0.0923281 -0.979335 0.163488 -0.11906 -0.589566 0.0677546 -0.804873 -0.58951 0.0667602 -0.804997 -0.649269 -0.438916 -0.62113 -0.599058 -0.0567738 -0.79869 -0.646297 -0.0555241 -0.761064 -0.59733 -0.316241 -0.737014 -0.489645 -0.41642 -0.766056 -0.596105 -0.243791 -0.765 -0.546166 -0.602296 -0.582187 -0.554515 -0.592549 -0.584294 -0.654769 -0.561222 -0.506267 -0.694167 -0.613377 -0.376696 -0.606235 -0.729014 -0.317832 -0.696616 -0.676103 -0.240021 -0.626743 0.73677 -0.253697 -0.652346 0.701046 -0.288061 -0.576789 0.71174 -0.400926 -0.529839 0.736589 -0.420364 -0.617634 0.612123 -0.493795 -0.54946 0.567867 -0.612879 -0.616061 0.502302 -0.606762 -0.546713 0.380393 -0.745926 -0.588699 0.350698 -0.728316 -0.571416 0.170514 -0.802751 -0.57471 0.169205 -0.800674 -0.881005 -0.471613 -0.0375535 -0.694706 -0.719154 -0.0141992 -0.7071 -0.707113 -0.0010767 -0.712094 -0.677071 -0.185734 -0.72548 -0.663912 -0.181385 -0.613579 -0.777469 -0.138065 -0.799652 -0.577514 -0.16442 -0.633575 -0.766515 -0.105059 -0.703591 -0.702013 -0.110175 -0.706546 -0.702042 -0.0890511 -0.795657 -0.599365 -0.0877061 -0.734135 -0.674872 -0.0747861 -0.672253 -0.739017 -0.0439331 -0.660047 0.729449 -0.179563 -0.647713 0.738065 -0.189018 -0.635169 0.749378 -0.187064 -0.664818 0.724343 -0.182601 -0.704516 -0.69815 0.127453 -0.717247 -0.682977 0.1382 -0.718246 -0.681917 0.138248 -0.708108 -0.691495 0.142892 -0.714566 -0.689075 0.120712 -0.785116 -0.607325 0.121443 -0.650222 -0.754515 0.0889892 -0.741334 -0.666124 0.0818679 -0.70279 -0.707782 0.0716236 -0.713089 -0.699261 0.0503793 -0.67313 -0.738178 0.0446021 -0.740312 -0.672023 0.017991 -0.707025 -0.707039 0.0145495 -0.66459 0.729388 -0.162216 -0.656087 0.736111 -0.166402 -0.660618 0.736073 -0.147581 -0.652009 0.742836 -0.151918 -0.611239 -0.496766 0.616126 -0.676449 -0.568756 0.467904 -0.63097 -0.683791 0.366477 -0.749481 -0.587635 0.304898 -0.69787 -0.690778 0.189219 -0.710318 -0.439698 0.549649 -0.58558 -0.313678 0.747463 -0.459655 -0.416721 0.784258 -0.701348 -0.134542 0.700007 -0.545349 -0.0855207 0.833835 -0.621975 -0.000752828 0.783037 -0.653945 0.742844 -0.143311 -0.672726 0.734809 0.0865754 -0.912253 0.399126 0.0921578 -0.638702 0.767836 0.0498849 -0.610727 0.791629 0.0183296 -0.666818 0.745029 0.0169017 -0.538517 0.842605 -0.00412485 -0.558921 0.829203 -0.00543199 -0.575426 0.81759 -0.0207917 -0.587732 0.808766 -0.0216453 -0.57266 0.819121 -0.0331811 -0.671712 0.728155 -0.136358 -0.694003 0.706637 -0.137931 -0.624149 0.773711 -0.108674 -0.583495 0.806766 -0.0930671 -0.643107 0.759565 -0.0973424 -0.616392 0.783992 -0.0736103 -0.670488 0.738321 -0.0729921 -0.530503 0.846536 -0.0440803 -0.524098 0.850519 -0.0440369 -0.601867 0.797558 -0.0407242 -0.619835 0.0392806 0.783748 -0.620023 0.0384338 0.783641 -0.670268 0.734915 0.103151 -0.677982 0.726734 0.110445 -0.676759 0.726748 0.117619 -0.684313 0.718356 0.125219 -0.612666 0.120621 0.781083 -0.602695 0.116306 0.789451 -0.629547 0.303042 0.715427 -0.544019 0.306891 0.780936 -0.642989 0.420181 0.640323 -0.592493 0.486066 0.642411 -0.630513 0.508332 0.58656 -0.6065 0.624435 0.492179 -0.603644 0.626017 0.493677 -0.6787 0.682864 0.270303 -0.635788 0.717823 0.283733 -0.673193 0.724383 0.148594 -0.64705 0.749891 0.137804 -0.68172 0.718365 0.138598 -0.568654 0.0670856 -0.819836 -0.568986 0.0662731 -0.819672 -0.578816 -0.0547797 -0.813616 -0.312031 -0.0644029 -0.947886 -0.627365 -0.417104 -0.657599 -0.593095 -0.345111 -0.727418 -0.48602 -0.368542 -0.79244 -0.54858 -0.2892 -0.784489 -0.623601 -0.137782 -0.769505 -0.574376 -0.541238 -0.614128 -0.538431 -0.587384 -0.604212 -0.670382 -0.540447 -0.508434 -0.631415 -0.692572 -0.348796 -0.660309 -0.669004 -0.341213 -0.60555 0.733871 -0.307802 -0.518046 0.788995 -0.330327 -0.610204 0.667599 -0.42657 -0.577886 0.628034 -0.521173 -0.464097 0.671164 -0.578059 -0.638468 0.460611 -0.616601 -0.433509 0.465183 -0.771799 -0.613031 0.32015 -0.722286 -0.467303 0.194725 -0.862386 -0.554775 0.162747 -0.815927 -0.703033 -0.682453 -0.200006 -0.704976 -0.68012 -0.201111 -0.704544 -0.677108 -0.212466 -0.706521 -0.674663 -0.213679 -0.639416 0.736761 -0.219843 -0.638209 0.737843 -0.219721 -0.649313 0.730301 -0.212255 -0.648231 0.731275 -0.212211 -0.717094 -0.672013 -0.184862 -0.708625 -0.68428 -0.172077 -0.710954 -0.674471 -0.199082 -0.706516 -0.682439 -0.187382 -0.658088 0.728661 -0.189667 -0.672238 0.716762 -0.185333 -0.652139 0.731261 -0.199931 -0.771959 -0.632314 0.0652539 -0.777186 -0.625704 0.0669045 -0.744877 -0.662983 0.0749124 -0.7515 -0.654009 0.086716 -0.793014 -0.600284 0.103868 -0.748006 -0.655497 0.103974 -0.723133 -0.680988 0.115478 -0.799441 -0.598624 -0.0504344 -0.820927 -0.5691 -0.0469506 -0.78401 -0.619943 -0.0316142 -0.84491 -0.534146 -0.0285384 -0.79401 -0.607801 -0.0111778 -0.847338 -0.531002 -0.007482 -0.766317 -0.642241 0.0168557 -0.855401 -0.51692 0.0329131 -0.810535 -0.584427 0.0384504 -0.754073 -0.654883 0.0500176 -0.798768 -0.598616 -0.0602458 -0.848523 -0.523131 -0.0796376 -0.784697 -0.614788 -0.0792829 -0.745263 -0.657528 -0.110636 -0.931737 -0.324716 -0.162558 -0.725696 -0.671985 -0.147654 -0.706852 0.70723 -0.0136487 -0.686106 0.72104 0.0967461 -0.834569 0.541185 0.103022 -0.69578 0.715538 0.0624209 -0.696933 0.715567 0.0474227 -0.685563 0.726757 0.0427653 -0.752537 0.658187 0.02187 -0.780066 0.625354 0.020724 -0.679125 0.734022 -0.0014361 -0.707395 0.706798 -0.00527989 -0.705118 0.709026 -0.00950959 -0.703099 0.710991 -0.0120248 -0.720886 0.692912 -0.0140399 -0.710125 0.703955 -0.0130301 -0.707869 0.706221 -0.0131909 -0.708085 0.706004 -0.0131554 -0.707009 0.707054 -0.014589 -0.713884 0.700057 -0.0170354 -0.717555 0.69628 -0.0175469 -0.707002 0.706927 -0.0200716 -0.703045 0.710733 -0.0242082 -0.724023 0.689149 -0.0293962 -0.718406 0.694975 -0.03006 -0.696374 0.716803 -0.0354552 -0.713128 0.699666 -0.043777 -0.7592 0.64845 -0.0559314 -0.766832 0.639293 -0.0572103 -0.714048 0.697296 -0.0625548 -0.684217 0.725824 -0.0708971 -0.702687 0.707108 -0.0789198 -0.689211 0.719716 -0.0836496 -0.699275 0.707976 -0.0989111 -0.792737 0.596027 -0.127749 -0.778307 0.614872 -0.127162 -0.675124 0.726632 -0.127331 -0.675992 0.72035 -0.155342 -0.693951 0.7027 -0.156986 -0.663814 0.728796 -0.16795 -0.705151 -0.694393 0.143459 -0.712421 -0.688024 0.138133 -0.714044 -0.687895 0.130159 -0.72168 -0.680972 0.124323 -0.677066 0.721717 0.143896 -0.691981 0.704309 0.158465 -0.679584 0.721259 0.133982 -0.706752 -0.689249 0.15949 -0.704563 -0.691473 0.159551 -0.705908 -0.692369 0.149396 -0.703909 -0.694386 0.149467 -0.671462 0.721874 0.167442 -0.674748 0.718143 0.170254 -0.667865 0.724184 0.171795 -0.666588 -0.682419 0.299942 -0.547431 -0.801366 0.241106 -0.628127 -0.38819 0.674363 -0.653867 -0.467855 0.594617 -0.55057 -0.614703 0.564812 -0.569558 -0.607524 0.55364 -0.70935 -0.559229 0.429052 -0.477105 -0.391865 0.786646 -0.535414 -0.381714 0.75341 -0.65115 -0.187958 0.735307 -0.50347 -0.111907 0.856735 -0.609864 -0.0429695 0.79134 -0.598214 0.126729 0.791252 -0.572887 0.117331 0.811193 -0.635317 0.303071 0.710296 -0.493083 0.313698 0.811457 -0.635629 0.411533 0.653159 -0.585872 0.482982 0.650755 -0.618308 0.502152 0.604597 -0.6012 0.616584 0.508313 -0.581568 0.627511 0.517696 -0.682622 0.67042 0.290799 -0.625943 0.717161 0.306391 -0.606424 0.0408731 0.794091 -0.60626 0.0399838 0.79426 -0.54978 0.0581243 -0.833285 -0.550123 0.0572865 -0.833117 -0.555821 -0.00927509 -0.83125 -0.415924 -0.104707 -0.903351 -0.55342 -0.13164 -0.822434 -0.628995 -0.326971 -0.705305 -0.46465 -0.372872 -0.803161 -0.531934 -0.28591 -0.797058 -0.574527 -0.203932 -0.792673 -0.567305 -0.52444 -0.634924 -0.518979 -0.588714 -0.619739 -0.645878 -0.541352 -0.538312 -0.630198 -0.679551 -0.375581 -0.641038 -0.670543 -0.37342 -0.598012 0.728712 -0.333707 -0.515078 0.781668 -0.351697 -0.602671 0.657289 -0.452503 -0.565105 0.617846 -0.546738 -0.455687 0.662919 -0.594044 -0.57228 0.522648 -0.631929 -0.546845 0.450933 -0.705422 -0.410445 0.461114 -0.786708 -0.604807 0.293415 -0.740349 -0.425396 0.188316 -0.885198 -0.538437 0.145794 -0.829958 -0.693397 -0.682643 -0.230648 -0.692321 -0.683971 -0.229946 -0.695868 -0.675482 -0.243909 -0.694935 -0.676699 -0.243197 -0.636211 0.731636 -0.244834 -0.636962 0.730946 -0.244942 -0.645835 0.726958 -0.233302 -0.646482 0.726359 -0.233373 -0.702515 -0.685224 -0.192199 -0.707528 -0.675874 -0.206396 -0.698974 -0.682605 -0.213275 -0.657695 0.724567 -0.206009 -0.678127 0.706815 -0.201384 -0.652094 0.72634 -0.217266 -0.709924 -0.685099 -0.163238 -0.839358 -0.532329 0.110022 -0.740049 -0.663379 0.110704 -0.709834 -0.693098 0.125504 -0.749237 -0.661126 0.0394548 -0.712456 -0.699838 0.0513149 -0.714052 -0.697635 0.0586036 -0.701867 -0.709207 0.0663918 -0.781256 -0.617113 0.0938626 -0.856826 -0.514698 0.0305933 -0.856459 -0.515307 0.0306173 -0.745754 -0.666041 0.0154876 -0.719609 -0.694299 -0.0105507 -0.731203 -0.68207 -0.0110899 -0.70541 -0.708789 0.0037553 -0.718918 -0.693946 -0.0399488 -0.703301 -0.710167 -0.0321082 -0.711433 -0.702106 -0.0301875 -0.707357 -0.706365 -0.0263519 -0.719372 -0.694336 -0.020033 -0.700836 -0.713092 -0.0181235 -0.7079 -0.70618 -0.0136798 -0.743178 -0.663745 -0.0844317 -0.821704 -0.564389 -0.0791738 -0.915875 -0.393775 -0.0781925 -0.873005 -0.482574 -0.0705996 -0.763041 -0.644302 -0.0514129 -0.649825 -0.746868 -0.141123 -0.756783 -0.640656 -0.129768 -0.778464 -0.614122 -0.1298 -0.707659 -0.698773 -0.104576 -0.713582 -0.694739 -0.0902138 -0.806279 0.582116 0.105141 -0.850598 0.512769 0.11641 -0.685573 0.718829 0.115211 -0.71845 0.691132 0.0785254 -0.694323 0.716766 0.0645131 -0.698299 0.713612 0.0560021 -0.656001 0.753809 0.0378835 -0.806716 0.590143 0.0306769 -0.703402 0.710635 0.0149583 -0.703539 0.710649 0.00319616 -0.711059 0.703013 -0.0129994 -0.733486 0.679604 -0.0116467 -0.68857 0.725135 -0.00719394 -0.700014 0.714116 -0.0042665 -0.714085 0.700057 0.00148962 -0.704619 0.708788 -0.0336565 -0.716305 0.697114 -0.0306331 -0.706191 0.707843 -0.0159018 -0.709992 0.70395 -0.0191511 -0.716061 0.697746 -0.020202 -0.706134 0.707705 -0.0229852 -0.704217 0.709439 -0.0278502 -0.701484 0.711539 -0.0403906 -0.743394 0.666903 -0.051051 -0.793081 0.606062 -0.0609285 -0.690867 0.718779 -0.0778508 -0.683422 0.725802 -0.0783974 -0.706704 0.704243 -0.0679127 -0.755817 0.651873 -0.0616665 -0.695284 0.712929 -0.0911666 -0.742996 0.659698 -0.112943 -0.810491 0.570825 -0.131391 -0.741487 0.658261 -0.129962 -0.664326 0.735303 -0.134165 -0.704854 0.688674 -0.170025 -0.697833 0.695965 -0.169301 -0.664851 0.724747 -0.180874 -0.704821 -0.692932 0.151901 -0.724564 -0.674002 0.143974 -0.703178 -0.692201 0.162474 -0.679578 0.718903 0.146124 -0.68773 0.708075 0.160179 -0.673574 0.719379 0.169682 -0.699101 -0.692238 0.179066 -0.711596 -0.67945 0.178827 -0.700779 -0.68986 0.181667 -0.66961 0.719425 0.184524 -0.66876 0.720412 0.183758 -0.667146 0.720266 0.190088 -0.666224 0.721343 0.189236 -0.54929 -0.605981 0.575384 -0.759154 -0.533271 0.373239 -0.657374 -0.683095 0.318183 -0.611804 -0.23713 0.754629 -0.566837 -0.313852 0.761704 -0.504447 -0.391034 0.769822 -0.608429 -0.371373 0.701353 -0.647789 -0.482014 0.589942 -0.586626 -0.117202 0.801332 -0.504644 -0.111005 0.856161 -0.594645 0.00839261 0.803945 -0.586915 0.110256 0.802106 -0.460987 0.17464 0.870053 -0.588167 0.227601 0.776052 -0.541526 0.642014 0.542741 -0.609349 0.491551 0.62215 -0.569413 0.399398 0.718506 -0.382822 0.524553 0.760455 -0.594923 0.315553 0.739252 -0.602941 0.581324 0.546374 -0.647268 0.691426 0.320895 -0.618975 0.713956 0.327318 -0.593173 0.0364901 0.804247 -0.593059 0.0359109 0.804358 -0.534965 0.0429034 -0.843784 -0.535197 0.0423152 -0.843667 -0.539264 -0.0240802 -0.841793 -0.389694 -0.118769 -0.913254 -0.53619 -0.144306 -0.83167 -0.600136 -0.335688 -0.726052 -0.445809 -0.382721 -0.809184 -0.517518 -0.289265 -0.805296 -0.556798 -0.215138 -0.802304 -0.561767 -0.511017 -0.6506 -0.49909 -0.595866 -0.629169 -0.616893 -0.550538 -0.562451 -0.634688 -0.661899 -0.398825 -0.618428 -0.675768 -0.401104 -0.602757 0.637854 -0.479403 -0.46216 0.832503 -0.305527 -0.578755 0.718035 -0.386612 -0.548175 0.609173 -0.573073 -0.454492 0.650653 -0.608348 -0.565359 0.504292 -0.652732 -0.53445 0.432252 -0.726306 -0.397802 0.452458 -0.798145 -0.541926 0.322571 -0.776057 -0.521603 0.162321 -0.837605 -0.271397 0.133845 -0.953116 -0.530498 0.234611 -0.814573 -0.681327 -0.688143 -0.249507 -0.678855 -0.691158 -0.247905 -0.683016 -0.679971 -0.266698 -0.680974 -0.68261 -0.265176 -0.636851 0.723774 -0.265655 -0.637088 0.72355 -0.265696 -0.646264 0.720199 -0.252302 -0.646473 0.720002 -0.25233 -0.69422 -0.689606 -0.206159 -0.700501 -0.678366 -0.221627 -0.688291 -0.68811 -0.229697 -0.657674 0.720113 -0.221138 -0.685634 0.695009 -0.216492 -0.653723 0.719964 -0.233021 -0.71068 -0.700334 0.0668336 -0.682937 -0.726427 0.0768145 -0.833836 -0.538821 0.119958 -0.738385 -0.663711 0.119476 -0.705841 -0.695408 0.134896 -0.710401 -0.703734 0.00938494 -0.714416 -0.699536 0.0160998 -0.829614 -0.556981 0.0388929 -0.794285 -0.606242 0.0397795 -0.715415 -0.696386 0.0568141 -0.813354 -0.581715 -0.007978 -0.778737 -0.62733 -0.0050922 -0.739811 -0.672815 -4.85021e-05 -0.713978 -0.700151 0.00490274 -0.703465 -0.709437 -0.0428501 -0.714286 -0.698927 -0.0360146 -0.724024 -0.688924 -0.0342375 -0.714038 -0.69939 -0.0316702 -0.703656 -0.710076 -0.0256997 -0.72278 -0.690746 -0.021418 -0.714033 -0.699825 -0.0200638 -0.697399 -0.716582 -0.012048 -0.710614 -0.698674 -0.0829607 -0.7574 -0.648354 -0.0773415 -0.831926 -0.549975 -0.0736668 -0.814168 -0.57632 -0.070604 -0.739912 -0.670543 -0.0538787 -0.696282 -0.706832 -0.124821 -0.713277 -0.693954 -0.0983017 -0.718285 -0.688487 -0.100259 -0.709508 -0.69869 -0.0918202 -0.714736 -0.687214 -0.129959 -0.695313 -0.697793 -0.172121 -0.703349 -0.689466 -0.173021 -0.791692 0.601038 0.109443 -0.84634 0.517976 0.124137 -0.687598 0.715834 0.12162 -0.704728 0.709366 -0.0125687 -0.736904 0.675923 -0.0100737 -0.678622 0.734482 -0.0028113 -0.699081 0.715043 0.000156267 -0.712951 0.701144 0.00990624 -0.70346 0.710683 0.00857789 -0.703174 0.710676 0.0220616 -0.811266 0.583299 0.0401246 -0.662981 0.7473 0.0447205 -0.698647 0.71259 0.0640957 -0.694385 0.716134 0.0705834 -0.712037 0.697172 0.0833949 -0.707762 0.706225 -0.0178532 -0.722182 0.691338 -0.0224934 -0.737014 0.67543 -0.02461 -0.716822 0.696722 -0.0273029 -0.710816 0.701812 -0.0469173 -0.737123 0.674267 -0.0448843 -0.71557 0.697415 -0.0396405 -0.698936 0.714454 -0.0323242 -0.698775 0.713271 -0.0543806 -0.712023 0.69914 -0.0650038 -0.756599 0.649496 -0.0755845 -0.695891 0.711315 -0.0988301 -0.705445 0.702017 -0.0975733 -0.683592 0.724989 -0.0842216 -0.726717 0.682588 -0.0771767 -0.683365 0.721478 -0.111727 -0.765436 0.627333 -0.143392 -0.773266 0.617062 -0.145925 -0.673663 0.724701 -0.14487 -0.683252 0.707962 -0.178765 -0.70149 0.689329 -0.180936 -0.666255 0.720339 -0.192912 -0.699713 -0.695187 0.164673 -0.725102 -0.670537 0.156864 -0.696852 -0.695014 0.177067 -0.678141 0.715219 0.169076 -0.702876 0.685462 0.190021 -0.680764 0.715915 0.155002 -0.692902 -0.693133 0.19863 -0.691914 -0.694053 0.198861 -0.693593 -0.694206 0.192372 -0.692668 -0.695069 0.19259 -0.669572 0.715496 0.199345 -0.669014 0.716179 0.198768 -0.66734 0.715977 0.205021 -0.666697 0.716773 0.204334 -0.615007 -0.587409 0.526039 -0.71136 -0.597615 0.369897 -0.646446 -0.686474 0.332958 -0.308384 -0.645786 0.698469 -0.788904 -0.353253 0.502835 -0.441165 -0.400093 0.803305 -0.507604 -0.386988 0.769791 -0.599288 -0.242847 0.76281 -0.579062 -0.143764 0.802508 -0.454179 -0.126352 0.881905 -0.583634 -0.0208338 0.81175 -0.57709 0.099926 0.810544 -0.446736 0.167396 0.878866 -0.578067 0.216893 0.786636 -0.546045 0.62591 0.556841 -0.603553 0.479331 0.637155 -0.558591 0.391464 0.731254 -0.380742 0.515287 0.767799 -0.587243 0.303318 0.750429 -0.59463 0.576021 0.560905 -0.650449 0.680957 0.336471 -0.615618 0.709186 0.343612 -0.582095 0.0271026 0.812669 -0.582009 0.0267119 0.812744 -0.525395 0.0241346 -0.850516 -0.525475 0.0239143 -0.850473 -0.527345 -0.0430855 -0.848558 -0.369304 -0.134658 -0.919501 -0.506717 -0.298244 -0.808881 -0.543592 -0.23167 -0.806745 -0.524359 -0.161446 -0.836052 -0.308508 -0.52898 -0.790572 -0.574869 -0.304739 -0.759381 -0.557924 -0.503701 -0.65955 -0.481303 -0.607071 -0.632307 -0.587599 -0.56581 -0.578435 -0.644673 -0.641096 -0.416406 -0.596155 -0.683634 -0.421004 -0.579989 0.709355 -0.400536 -0.472666 0.820421 -0.321708 -0.562884 0.486004 -0.668552 -0.458456 0.63708 -0.619635 -0.544338 0.596421 -0.589897 -0.603301 0.624552 -0.495946 -0.527298 0.413431 -0.742315 -0.39586 0.440223 -0.805915 -0.537118 0.299213 -0.788655 -0.520997 0.209954 -0.827334 -0.361489 0.168652 -0.916996 -0.520795 0.0956767 -0.848304 -0.668777 -0.694802 -0.264552 -0.664759 -0.699673 -0.261825 -0.669421 -0.686967 -0.282758 -0.666073 -0.691272 -0.280161 -0.640636 0.715055 -0.27979 -0.635147 0.720321 -0.278796 -0.651997 0.70898 -0.268789 -0.647319 0.713455 -0.268254 -0.681277 -0.694585 -0.231113 -0.700189 -0.667879 -0.252335 -0.685656 -0.694261 -0.218807 -0.655524 0.713394 -0.247704 -0.671544 0.700845 -0.24051 -0.662332 0.715729 -0.221469 -0.857813 -0.498165 0.126448 -0.735667 -0.665634 0.125403 -0.70153 -0.698521 0.141151 -0.826798 -0.560823 0.0434043 -0.686859 -0.725322 0.0461877 -0.711761 -0.699147 0.0677489 -0.70781 -0.701837 0.0801848 -0.807935 -0.578459 0.112372 -0.767619 -0.640896 -0.00365046 -0.793746 -0.608219 -0.00611756 -0.726362 -0.687312 0.00116842 -0.703886 -0.710262 0.0084994 -0.713284 -0.700771 0.0121089 -0.710594 -0.703463 0.0140097 -0.710408 -0.703449 0.0219251 -0.754787 -0.654805 -0.0390753 -0.725719 -0.687138 -0.0342673 -0.692234 -0.721346 -0.0217158 -0.706849 -0.707066 -0.0205658 -0.70704 -0.707067 -0.0122895 -0.767283 -0.641265 -0.00752296 -0.707707 -0.698936 -0.103146 -0.732096 -0.674206 -0.0973739 -0.806026 -0.584581 -0.0926671 -0.824913 -0.557557 -0.0929986 -0.748449 -0.659069 -0.0738437 -0.702937 -0.708777 -0.0592848 -0.711461 -0.700718 -0.0530759 -0.707147 -0.705256 -0.0505605 -0.71413 -0.698691 -0.0430096 -0.706185 -0.698934 -0.113111 -0.704216 -0.70108 -0.112101 -0.708016 -0.695045 -0.125005 -0.76621 -0.623456 -0.155647 -0.781998 -0.602173 -0.160832 -0.70779 -0.686901 -0.164926 -0.678476 -0.710723 -0.185856 -0.694939 -0.694198 -0.187481 -0.689966 0.712912 0.125313 -0.845785 0.51765 0.129179 -0.740128 0.664918 0.100474 -0.695995 0.713775 0.0782116 -0.696948 0.713776 0.0691858 -0.780676 0.623398 0.0438076 -0.802109 0.595355 0.0466192 -0.700189 0.711708 0.0566369 -0.696195 0.714545 0.0688245 -0.70315 0.710582 0.0255703 -0.70337 0.710588 0.0182902 -0.716483 0.697454 0.014524 -0.693233 0.72065 0.00955501 -0.706127 0.70806 0.00596487 -0.70471 0.709491 -0.0022863 -0.75433 0.656458 -0.00704995 -0.706991 0.70712 -0.0120444 -0.706652 0.707094 -0.0257048 -0.719288 0.69425 -0.0253457 -0.699805 0.713284 -0.038713 -0.729352 0.682497 -0.0473669 -0.7729 0.616989 -0.148159 -0.690062 0.72199 -0.0504502 -0.72086 0.689429 -0.0710561 -0.759364 0.645885 -0.078734 -0.669951 0.737281 -0.0870764 -0.704325 0.70265 -0.101039 -0.688783 0.717088 -0.106599 -0.701453 0.701888 -0.123763 -0.730921 0.666496 -0.146756 -0.662934 0.733099 -0.151936 -0.721546 0.66425 -0.195304 -0.704717 0.682698 -0.193128 -0.667451 0.715773 -0.205372 -0.689691 -0.699125 0.188548 -0.708226 -0.683205 0.177898 -0.697447 -0.698453 0.160411 -0.680412 0.71089 0.177976 -0.709813 0.674919 0.201618 -0.682385 0.713009 0.161145 -0.684228 -0.698054 0.211074 -0.683673 -0.698552 0.211224 -0.685338 -0.698754 0.20507 -0.684851 -0.699194 0.2052 -0.670687 0.711239 0.210518 -0.670563 0.711411 0.210334 -0.669065 0.711419 0.215025 -0.668903 0.711644 0.214782 -0.635907 -0.691508 0.342694 -0.521273 -0.807535 0.275974 -0.589622 -0.395383 0.704285 -0.619466 -0.472025 0.627259 -0.515415 -0.621041 0.59047 -0.526246 -0.616787 0.585354 -0.679945 -0.560258 0.47306 -0.409215 -0.411579 0.814337 -0.495859 -0.39493 0.773404 -0.61881 -0.198983 0.759921 -0.451089 -0.134003 0.882362 -0.574763 -0.0628855 0.8159 -0.570969 0.0873884 0.816307 -0.437398 0.158693 0.885155 -0.571625 0.20473 0.794563 -0.546745 0.617359 0.56563 -0.601298 0.468012 0.647615 -0.55242 0.382417 0.740668 -0.37951 0.507499 0.773574 -0.583225 0.290656 0.75853 -0.59487 0.566311 0.570458 -0.650145 0.676203 0.346498 -0.616114 0.704076 0.3531 -0.574454 0.015431 0.818391 -0.574363 0.0150633 0.818462 -0.521043 0.00715153 -0.853501 -0.521007 0.00703287 -0.853524 -0.520773 -0.0607418 -0.851531 -0.357267 -0.148131 -0.922181 -0.500083 -0.30956 -0.808758 -0.535888 -0.248395 -0.806922 -0.518319 -0.177859 -0.836488 -0.32296 -0.516959 -0.792749 -0.551786 -0.330441 -0.765729 -0.555481 -0.503197 -0.661992 -0.468001 -0.61887 -0.630852 -0.564588 -0.581726 -0.585521 -0.654931 -0.624123 -0.426071 -0.578999 -0.691913 -0.431296 -0.583287 0.702679 -0.407454 -0.481107 0.811974 -0.330506 -0.563761 0.4724 -0.677504 -0.463658 0.626674 -0.62634 -0.544953 0.586648 -0.599057 -0.605905 0.61515 -0.50445 -0.525142 0.399188 -0.751581 -0.399367 0.428913 -0.810271 -0.536474 0.281051 -0.795742 -0.516691 0.190285 -0.834758 -0.351001 0.15901 -0.922775 -0.518945 0.0738224 -0.851614 -0.657186 -0.701545 -0.275575 -0.65298 -0.706687 -0.272416 -0.656648 -0.695765 -0.291073 -0.653222 -0.70022 -0.288085 -0.643497 0.708417 -0.289926 -0.644057 0.707909 -0.289924 -0.647235 0.70874 -0.280667 -0.647831 0.708196 -0.280667 -0.67049 -0.701302 -0.242114 -0.692807 -0.670028 -0.26661 -0.676962 -0.698842 -0.23096 -0.656468 0.71183 -0.249697 -0.690461 0.680258 -0.245991 -0.655616 0.708123 -0.262164 -0.853434 -0.504487 0.130932 -0.732994 -0.667859 0.129171 -0.697809 -0.701433 0.1451 -0.849892 -0.524419 0.0516658 -0.836107 -0.546098 0.0519694 -0.749324 -0.661245 0.0356299 -0.710145 -0.703571 0.0261244 -0.764002 -0.642625 0.0577489 -0.703879 -0.707309 0.0653291 -0.710118 -0.70021 0.0737438 -0.708337 -0.701355 0.0797452 -0.751017 -0.652293 0.102403 -0.712193 -0.701871 -0.0126296 -0.798922 -0.601434 0.00072529 -0.826038 -0.563614 -0.00122213 -0.781625 -0.623732 -0.00450862 -0.73307 -0.680098 -0.00869363 -0.74915 -0.662372 0.00614094 -0.711974 -0.702107 0.0117362 -0.708437 -0.705512 0.0192181 -0.712109 -0.701831 0.0182569 -0.710307 -0.703577 0.0210576 -0.704948 -0.70669 -0.0603155 -0.721809 -0.690331 -0.0493388 -0.807479 -0.588105 -0.0459405 -0.707632 -0.705859 -0.0319373 -0.707067 -0.7068 -0.0221118 -0.713139 -0.700734 -0.0201201 -0.7069 -0.707078 -0.0182469 -0.706974 -0.707079 -0.0150677 -0.749397 -0.656795 -0.0838162 -0.808827 -0.580313 -0.0950532 -0.706497 -0.700222 -0.10272 -0.703497 -0.700201 -0.121696 -0.689042 -0.715254 -0.116758 -0.732486 -0.660708 -0.164104 -0.662166 -0.735757 -0.142123 -0.711827 -0.67298 -0.200998 -0.687251 -0.698794 -0.198426 -0.687483 0.711126 0.147198 -0.72865 0.673799 0.122734 -0.812427 0.568736 0.128461 -0.711606 0.696565 0.0917271 -0.696443 0.712953 0.0816349 -0.697175 0.712953 0.0751357 -0.692775 0.717483 0.0726692 -0.711805 0.699638 0.0619728 -0.788369 0.61252 0.057391 -0.825934 0.560967 0.0561196 -0.760585 0.647619 0.045823 -0.715416 0.697825 0.0349225 -0.703316 0.710261 0.0295927 -0.7035 0.710261 0.0248462 -0.715325 0.698461 0.0214932 -0.701848 0.712305 0.00561087 -0.717497 0.696495 0.0096537 -0.700226 0.713792 0.0136285 -0.710659 0.703244 0.0203123 -0.711358 0.70283 -0.000178325 -0.736851 0.676028 -0.00600654 -0.738424 0.674309 -0.0061755 -0.71262 0.701458 -0.0114056 -0.702139 0.711839 -0.0169175 -0.724952 0.688398 -0.0235345 -0.747023 0.664224 -0.0276333 -0.701867 0.709713 -0.0607423 -0.727444 0.683961 -0.0549764 -0.721051 0.692241 -0.029799 -0.698278 0.714834 -0.0376881 -0.704623 0.70845 -0.0400707 -0.703374 0.709392 -0.0450371 -0.723369 0.688333 -0.0541761 -0.698044 0.7127 -0.069233 -0.749521 0.656558 -0.0845627 -0.793813 0.60064 -0.0953561 -0.739814 0.666124 -0.0946269 -0.682094 0.724019 -0.102685 -0.696477 0.708791 -0.111966 -0.687796 0.716468 -0.116666 -0.708851 0.692174 -0.13574 -0.796415 0.581455 -0.166232 -0.756054 0.633757 -0.163507 -0.666548 0.727313 -0.163492 -0.701892 0.681817 -0.206091 -0.706676 0.676641 -0.2068 -0.666989 0.71208 -0.219246 -0.682951 -0.703448 0.196824 -0.706362 -0.683056 0.185707 -0.693178 -0.701343 0.166197 -0.682495 0.711013 0.169294 -0.700341 0.688034 0.190083 -0.67679 0.707704 0.202758 -0.676745 -0.703182 0.218064 -0.676558 -0.703337 0.218145 -0.677985 -0.70333 0.213692 -0.677743 -0.703531 0.213797 -0.671535 0.707809 0.219196 -0.67213 0.70685 0.220463 -0.671857 0.707788 0.218279 -0.627867 -0.69672 0.346935 -0.511327 -0.813159 0.27806 -0.582945 -0.403749 0.705097 -0.612217 -0.479694 0.628557 -0.506539 -0.627353 0.591479 -0.517368 -0.62315 0.586528 -0.673073 -0.565658 0.476449 -0.399063 -0.419756 0.815202 -0.487686 -0.403287 0.774288 -0.613122 -0.21046 0.761438 -0.445387 -0.142585 0.883912 -0.569618 -0.0749073 0.818489 -0.568734 0.0762954 0.818976 -0.433537 0.151047 0.888386 -0.569087 0.194557 0.798929 -0.544421 0.616814 0.568459 -0.601997 0.460459 0.652363 -0.550766 0.374924 0.745714 -0.378475 0.503079 0.776961 -0.582551 0.280866 0.762725 -0.600659 0.556016 0.574504 -0.64746 0.676829 0.350283 -0.618745 0.700393 0.355813 -0.570763 0.00451929 0.821103 -0.570796 0.00440283 0.82108 -0.520259 0 -0.854008 -0.520259 0 -0.854008 -0.520244 -0.00774016 -0.853983 -0.520243 -0.00774354 -0.853983 -0.520451 -0.0224158 -0.853598 -0.520193 -0.0234664 -0.853726 -0.585118 0.700342 -0.408849 -0.484249 0.809262 -0.332562 -0.564732 0.46815 -0.679642 -0.465915 0.623256 -0.628072 -0.546141 0.583345 -0.601198 -0.60742 0.612165 -0.506256 -0.525297 0.3947 -0.75384 -0.401352 0.424996 -0.811354 -0.537005 0.275221 -0.797421 -0.515997 0.183655 -0.836671 -0.349264 0.155262 -0.924072 -0.519134 0.0657792 -0.852158 -0.521103 -0.0983368 -0.84781 -0.372741 -0.184446 -0.90942 -0.518266 -0.211845 -0.828566 -0.569967 -0.390191 -0.72311 -0.423037 -0.4343 -0.79525 -0.511219 -0.325738 -0.79533 -0.533067 -0.269004 -0.80217 -0.540395 -0.535453 -0.649049 -0.47047 -0.629731 -0.61814 -0.579045 -0.582979 -0.56995 -0.610584 -0.676341 -0.412008 -0.581838 -0.700003 -0.414078 -0.645512 0.706097 -0.291103 -0.645849 0.705792 -0.291095 -0.648991 0.706529 -0.282183 -0.64934 0.706212 -0.282176 -0.648819 -0.706411 -0.282875 -0.648593 -0.70672 -0.28262 -0.645471 -0.706033 -0.29135 -0.645264 -0.706324 -0.291103 -0.655452 0.706177 -0.267761 -0.658758 0.703653 -0.266288 -0.667022 0.704303 -0.242979 -0.670271 0.701751 -0.241417 -0.669502 -0.701185 -0.245166 -0.667722 -0.704162 -0.241462 -0.657612 -0.703282 -0.270077 -0.655934 -0.706354 -0.266111 -0.698791 0.703126 0.131548 -0.849079 0.510819 0.134642 -0.706612 0.701122 0.0955393 -0.708813 0.7012 0.076826 -0.690675 0.720112 0.0663825 -0.817057 0.57382 0.0561168 -0.709221 0.703756 0.0416313 -0.710049 0.703809 0.0219781 -0.704704 0.709188 0.0210829 -0.713102 0.700995 0.00959677 -0.634168 0.773195 -0.000547159 -0.858936 0.511693 -0.0199714 -0.771313 0.636007 -0.0239073 -0.665257 0.745628 -0.0383641 -0.661534 0.748924 -0.038539 -0.735217 0.675502 -0.0561502 -0.682376 0.728296 -0.0628288 -0.791338 0.603834 -0.0957554 -0.659164 0.746642 -0.0896009 -0.752101 0.643835 -0.140787 -0.856662 0.486031 -0.172927 -0.550614 0.821845 -0.146271 -0.683309 0.70155 -0.202277 -0.702959 -0.70245 0.111408 -0.680742 -0.72432 0.109321 -0.708483 -0.701002 0.0815371 -0.717939 -0.694135 0.0523433 -0.706942 -0.70709 -0.016005 -0.707256 -0.706935 0.00555862 -0.710764 -0.703407 0.00570352 -0.710032 -0.70359 0.0285538 -0.710293 -0.703261 0.0301286 -0.670565 -0.740103 0.0508963 -0.707985 -0.70602 -0.0171109 -0.692116 -0.72127 -0.0272889 -0.588414 -0.807993 -0.0302805 -0.785115 -0.616444 -0.0599266 -0.734595 -0.675502 -0.0637746 -0.637615 -0.766252 -0.0794006 -0.725366 -0.681595 -0.0962911 -0.694262 -0.708312 -0.127649 -0.573559 -0.81011 -0.121457 -0.664503 -0.73173 -0.151682 -0.714244 -0.66712 -0.211674 -0.682387 -0.701083 -0.206955 -0.689912 0.703177 0.171938 -0.704817 0.682965 0.191812 -0.677726 0.706463 0.203954 -0.686433 -0.702696 0.187155 -0.727752 -0.66138 0.181531 -0.67743 -0.706644 0.204312 -0.672887 0.706544 0.21913 -0.672946 0.706226 0.219975 -0.672364 0.706565 0.220664 -0.672386 -0.706724 0.220089 -0.673149 -0.706175 0.219518 -0.67223 -0.706676 0.220715 -0.568701 0.0719713 0.81939 -0.432905 0.14822 0.88917 -0.29939 0.56863 0.766176 -0.5829 0.277842 0.763565 -0.568807 0.19102 0.799981 -0.634693 0.321447 0.702735 -0.554122 0.592985 0.584224 -0.608302 0.562135 0.560332 -0.645731 0.678323 0.350585 -0.620209 0.69924 0.355533 -0.657278 -0.398087 0.639931 -0.625599 -0.700676 0.343044 -0.529057 -0.799752 0.283719 -0.517182 -0.631238 0.57798 -0.497833 -0.639067 0.586307 -0.668709 -0.571164 0.476025 -0.336845 -0.448497 0.827881 -0.519549 -0.410487 0.74938 -0.581592 -0.279149 0.764086 -0.56871 -0.150979 0.808563 -0.278791 -0.138219 0.950353 -0.568948 -0.21186 0.794615 -0.570177 0 0.821522 -0.570177 0 0.821522 -0.570183 -0.0237691 0.821174 -0.570341 -0.0243921 0.821045 -0.570177 -0.00803098 0.821483 -0.570159 -0.00795782 0.821496 -0.521194 -0.00795668 -0.853401 -0.521233 -0.00784005 -0.853379 -0.518949 -0.0762854 -0.851394 -0.353945 -0.158721 -0.9217 -0.517178 -0.192254 -0.834005 -0.534079 -0.269389 -0.801367 -0.331852 -0.512715 -0.791832 -0.539092 -0.350111 -0.76603 -0.554472 -0.508007 -0.659158 -0.459365 -0.629848 -0.626319 -0.549577 -0.595975 -0.585473 -0.636507 -0.61215 -0.469182 -0.54846 -0.735713 -0.39739 -0.623637 -0.708054 -0.331265 -0.59219 0.693857 -0.409724 -0.494104 0.802061 -0.335498 -0.569296 0.458268 -0.682563 -0.473566 0.614666 -0.63081 -0.552041 0.574831 -0.604004 -0.613328 0.604778 -0.508009 -0.528696 0.384689 -0.756634 -0.408827 0.415576 -0.812501 -0.539875 0.264297 -0.799176 -0.517153 0.17249 -0.838332 -0.352288 0.148832 -0.923982 -0.521162 0.0547248 -0.851701 -0.647441 -0.708411 -0.281024 -0.645145 -0.711341 -0.278896 -0.645327 -0.706141 -0.291407 -0.64348 -0.708643 -0.28941 -0.654654 0.699677 -0.286146 -0.647239 0.707051 -0.284887 -0.664463 0.695098 -0.274459 -0.658296 0.701183 -0.273839 -0.661743 -0.712156 -0.234373 -0.674061 -0.691006 -0.261059 -0.668703 -0.698976 -0.253514 -0.653219 -0.708397 -0.267354 -0.665704 0.701145 -0.255409 -0.684873 0.685731 -0.246416 -0.677501 0.698563 -0.230222 -0.832762 -0.53745 0.132875 -0.723339 -0.67812 0.130133 -0.687527 -0.711379 0.145761 -0.701618 -0.711909 0.030299 -0.702429 -0.711121 0.029992 -0.705087 -0.708736 0.023334 -0.705292 -0.707886 0.0382203 -0.779651 -0.623797 0.0549667 -0.794772 -0.604192 0.0573525 -0.732161 -0.678321 0.061808 -0.687465 -0.722929 0.0690366 -0.698553 -0.711459 0.0764883 -0.693725 -0.715512 0.082394 -0.726762 -0.679186 0.102587 -0.715342 -0.698722 -0.00862227 -0.772132 -0.635461 -0.00128553 -0.852101 -0.52335 0.00538812 -0.876981 -0.480468 0.00737266 -0.806862 -0.59062 0.0118882 -0.746954 -0.664643 0.0176226 -0.705719 -0.708353 -0.0140071 -0.708464 -0.705552 -0.0165862 -0.701571 -0.712328 -0.0196497 -0.727403 -0.685646 -0.0278349 -0.720441 -0.692933 -0.0284225 -0.703699 -0.707533 -0.0648462 -0.737011 -0.673298 -0.0590237 -0.78356 -0.618638 -0.0576252 -0.729048 -0.682805 -0.0476065 -0.698603 -0.71459 -0.0362576 -0.701606 -0.704431 -0.107358 -0.756294 -0.646156 -0.102484 -0.799176 -0.592078 -0.103736 -0.742046 -0.664444 -0.0887787 -0.694423 -0.715837 -0.073172 -0.681325 -0.72245 -0.117738 -0.704372 -0.698301 -0.127421 -0.684433 -0.716768 -0.133397 -0.697248 -0.700116 -0.153891 -0.717909 -0.677063 -0.161838 -0.633383 -0.753536 -0.176094 -0.699306 -0.684748 -0.205161 -0.666781 -0.712197 -0.219493 -0.698198 0.701252 0.144101 -0.758794 0.640007 0.120925 -0.812035 0.570211 0.124327 -0.71686 0.691973 0.0853479 -0.709504 0.700459 0.0772053 -0.710168 0.700454 0.070888 -0.702634 0.708375 0.06716 -0.723937 0.687425 0.0579836 -0.77836 0.6258 0.0503028 -0.824863 0.56325 0.048481 -0.769756 0.637138 0.0391397 -0.714075 0.69952 0.0277258 -0.70906 0.704867 0.0199163 -0.720221 0.693581 0.0150549 -0.710421 0.703652 0.0132255 -0.708219 0.705964 0.00635466 -0.711293 0.702859 0.00715893 -0.705327 0.70888 0.00180656 -0.734569 0.678519 -0.00462942 -0.755985 0.654553 -0.0068775 -0.722164 0.691646 -0.0102012 -0.706992 0.707074 -0.0144452 -0.706699 0.707043 -0.0258222 -0.72711 0.686057 -0.025237 -0.702307 0.710853 -0.0381149 -0.730737 0.681032 -0.047115 -0.734732 0.67666 -0.0479713 -0.702453 0.709731 -0.0533063 -0.730691 0.675547 -0.0986246 -0.68384 0.722981 -0.0982964 -0.721205 0.687505 -0.0848577 -0.769891 0.633131 -0.0800759 -0.757782 0.647881 -0.0775629 -0.714754 0.696522 -0.063126 -0.702822 0.703069 -0.10833 -0.71379 0.688996 -0.125651 -0.78449 0.601623 -0.150414 -0.744806 0.650332 -0.149442 -0.678708 0.717727 -0.15564 -0.739177 0.642998 -0.200429 -0.721171 0.6638 -0.198197 -0.683576 0.698632 -0.211274 -0.67845 -0.707794 0.196808 -0.699663 -0.68889 0.189478 -0.683632 -0.711334 0.163252 -0.687964 0.702947 0.180474 -0.720372 0.661991 0.206961 -0.693415 0.701166 0.165959 -0.671151 -0.707938 0.219954 -0.671997 -0.707391 0.219128 -0.671796 -0.707952 0.217932 -0.67815 0.703306 0.213242 -0.678279 0.703121 0.213446 -0.676926 0.703128 0.217675 -0.677078 0.702906 0.217919 -0.622771 -0.701529 0.346429 -0.503204 -0.81891 0.275994 -0.58037 -0.41229 0.702273 -0.608449 -0.487836 0.625944 -0.500886 -0.63366 0.589566 -0.513351 -0.62892 0.583892 -0.669164 -0.571654 0.474797 -0.397914 -0.425996 0.812522 -0.483539 -0.410889 0.772891 -0.610745 -0.222109 0.760038 -0.446829 -0.149515 0.882037 -0.568301 -0.0864199 0.81827 -0.570094 0.0665611 0.818879 -0.435633 0.143678 0.888583 -0.297899 0.569353 0.76622 -0.585149 0.272265 0.763854 -0.570229 0.185388 0.800294 -0.639482 0.313645 0.701918 -0.555903 0.590111 0.585441 -0.616163 0.555495 0.558362 -0.64546 0.679129 0.349521 -0.625262 0.695713 0.353597 -0.570932 -0.00496064 0.820983 -0.5709 -0.00484407 0.821005 -0.525932 -0.0252124 -0.850153 -0.525862 -0.024946 -0.850204 -0.521333 -0.094055 -0.848154 -0.359564 -0.169355 -0.917623 -0.339112 -0.513439 -0.788279 -0.534957 -0.284741 -0.795452 -0.520972 -0.208218 -0.827788 -0.534677 -0.367022 -0.761193 -0.558753 -0.557569 -0.613931 -0.485613 -0.601574 -0.634262 -0.636082 -0.611502 -0.470601 -0.534437 -0.751294 -0.387213 -0.616694 -0.714752 -0.329876 -0.605327 0.684661 -0.405979 -0.509528 0.792645 -0.334808 -0.57978 0.444413 -0.6829 -0.486815 0.603039 -0.631946 -0.565116 0.562656 -0.603376 -0.624845 0.595208 -0.505269 -0.538094 0.370099 -0.757285 -0.42261 0.400683 -0.812929 -0.548313 0.247323 -0.798864 -0.522917 0.154129 -0.838333 -0.363881 0.135462 -0.921543 -0.527843 0.034888 -0.848625 -0.639891 -0.715531 -0.280276 -0.647205 -0.713799 -0.267612 -0.646566 -0.714566 -0.26711 -0.642024 -0.714784 -0.277289 -0.651068 -0.701633 -0.289521 -0.667758 0.69066 -0.277646 -0.658614 0.700029 -0.27602 -0.677481 0.686654 -0.263679 -0.669811 0.694474 -0.262792 -0.659834 -0.713558 -0.235487 -0.679004 -0.688123 -0.255812 -0.662265 -0.716034 -0.220684 -0.67724 0.694439 -0.243108 -0.693299 0.681507 -0.234275 -0.686171 0.693972 -0.218112 -0.742277 -0.662443 0.100962 -0.845677 -0.517889 0.128927 -0.721149 -0.68112 0.126571 -0.686436 -0.713222 0.141846 -0.746024 -0.664994 0.0350856 -0.82667 -0.560502 0.0495393 -0.823892 -0.564573 0.0496034 -0.712594 -0.699212 0.057548 -0.690641 -0.719777 0.0702576 -0.696957 -0.713809 0.0687608 -0.695969 -0.713808 0.0781367 -0.737727 -0.675046 -0.00845804 -0.78694 -0.617014 -0.00449281 -0.81746 -0.57598 -0.00238021 -0.778833 -0.627231 0.000560149 -0.734681 -0.678388 0.00581072 -0.702912 -0.711186 0.0113372 -0.704789 -0.709199 0.0175729 -0.704159 -0.70982 0.017754 -0.701595 -0.712139 0.024949 -0.780843 -0.623198 -0.0436829 -0.686635 -0.726547 -0.0257167 -0.713562 -0.700296 -0.0203722 -0.706828 -0.707162 -0.0177822 -0.706962 -0.707125 -0.0133954 -0.828219 -0.552195 -0.0955731 -0.700309 -0.71028 -0.0712011 -0.70155 -0.711199 -0.0449881 -0.672185 -0.715925 -0.188729 -0.710938 -0.6724 -0.206025 -0.663624 -0.729757 -0.164493 -0.737116 -0.657289 -0.156943 -0.686686 -0.713379 -0.139827 -0.689224 -0.715296 -0.115419 -0.676258 -0.72836 -0.110302 -0.715628 -0.691724 -0.0969259 -0.702411 0.698345 0.1376 -0.793803 0.596847 0.116836 -0.79564 0.594373 0.116949 -0.710508 0.699612 0.0756409 -0.711501 0.699616 0.0656098 -0.691452 0.720265 0.0557891 -0.805142 0.591714 0.0402644 -0.75121 0.659201 0.0337237 -0.710531 0.703456 0.0171874 -0.710601 0.703458 0.0139177 -0.721809 0.692002 -0.0111577 -0.73796 0.674771 -0.00996624 -0.659615 0.751603 0.000374176 -0.661124 0.750276 0.000502381 -0.715558 0.698494 0.00911765 -0.706996 0.707068 -0.0145613 -0.706831 0.707059 -0.0213664 -0.734443 0.678217 -0.0248003 -0.685674 0.727081 -0.0347187 -0.742377 0.668426 -0.045646 -0.705404 0.706995 -0.0506355 -0.717743 0.692859 -0.0692259 -0.748714 0.658602 -0.0752993 -0.684003 0.723804 -0.0908211 -0.708506 0.698774 -0.098663 -0.705799 0.698783 -0.116406 -0.782007 0.605392 -0.148208 -0.748145 0.647249 -0.14611 -0.69791 0.698896 -0.156416 -0.704206 0.685509 -0.184855 -0.726798 0.660794 -0.187394 -0.691477 0.694026 -0.200466 -0.676181 -0.711409 0.191512 -0.696713 -0.693931 0.181799 -0.682302 -0.713155 0.160852 -0.694041 0.698647 0.17378 -0.719322 0.666471 0.195937 -0.697713 0.698293 0.159947 -0.668692 -0.711933 0.214481 -0.668978 -0.711696 0.214377 -0.670396 -0.711688 0.209927 -0.670615 -0.711506 0.209845 -0.68538 0.698938 0.204304 -0.685761 0.698442 0.204721 -0.684239 0.698259 0.21036 -0.684621 0.697753 0.210794 -0.620771 -0.705548 0.341827 -0.497537 -0.824137 0.270655 -0.581731 -0.421645 0.69556 -0.607819 -0.496647 0.619595 -0.498609 -0.639646 0.585015 -0.514075 -0.633923 0.577813 -0.6681 -0.577968 0.46861 -0.405482 -0.431253 0.805981 -0.483163 -0.418571 0.768994 -0.611091 -0.236149 0.755514 -0.455398 -0.15691 0.876351 -0.570391 -0.100115 0.815249 -0.575282 0.0554804 0.816072 -0.443433 0.134801 0.886113 -0.291087 0.575387 0.764329 -0.591767 0.26349 0.76183 -0.575478 0.175255 0.798818 -0.653282 0.298988 0.695579 -0.557876 0.588812 0.584871 -0.633649 0.545073 0.548985 -0.64248 0.685086 0.343332 -0.635339 0.690921 0.344923 -0.57474 -0.0159012 0.818181 -0.57479 -0.0157395 0.81815 -0.53587 -0.0438009 -0.843164 -0.535781 -0.0433946 -0.843241 -0.528781 -0.113487 -0.841137 -0.373807 -0.181025 -0.90967 -0.529766 -0.226552 -0.817326 -0.540194 -0.30382 -0.784783 -0.340279 -0.523447 -0.781162 -0.541221 -0.38254 -0.748828 -0.557441 -0.532335 -0.637086 -0.454723 -0.651052 -0.607748 -0.540141 -0.622079 -0.566803 -0.635574 -0.620293 -0.459655 -0.524994 -0.765659 -0.371683 -0.612478 -0.723361 -0.318778 -0.622363 0.675895 -0.394754 -0.526913 0.784507 -0.326973 -0.595436 0.432649 -0.676957 -0.503388 0.593107 -0.62835 -0.584058 0.551555 -0.595536 -0.640268 0.587667 -0.494676 -0.553876 0.357184 -0.752091 -0.440767 0.385845 -0.810462 -0.562453 0.232171 -0.793563 -0.535091 0.137221 -0.833575 -0.384888 0.119639 -0.915176 -0.539767 0.0161534 -0.84166 -0.646106 -0.72042 -0.252076 -0.642937 -0.723997 -0.249921 -0.639848 -0.720715 -0.266768 -0.636743 -0.724289 -0.264507 -0.682675 0.68215 -0.261965 -0.67269 0.692541 -0.260527 -0.69056 0.679204 -0.248615 -0.682248 0.687809 -0.247904 -0.661434 -0.72054 -0.208153 -0.669165 -0.708517 -0.224103 -0.653579 -0.720388 -0.23211 -0.691136 0.689157 -0.217702 -0.714674 0.666763 -0.211349 -0.688916 0.687772 -0.228835 -0.846787 -0.517321 0.123818 -0.717948 -0.68532 0.122013 -0.684351 -0.716186 0.1369 -0.703209 -0.710739 0.0186504 -0.740498 -0.671496 0.0274837 -0.820825 -0.569657 0.0416833 -0.835068 -0.54842 0.0435529 -0.75174 -0.657563 0.0499802 -0.689152 -0.722256 0.0584382 -0.696243 -0.714733 0.0663524 -0.6957 -0.714567 0.0734548 -0.744666 -0.660359 0.0969498 -0.707902 -0.706165 -0.0143076 -0.722192 -0.691603 -0.011094 -0.761191 -0.648474 -0.00834108 -0.793049 -0.609123 -0.00645105 -0.772523 -0.634968 -0.0048278 -0.735017 -0.678049 -0.000316377 -0.704615 -0.709574 0.00482371 -0.703784 -0.710324 0.011322 -0.705742 -0.708386 0.0108213 -0.703316 -0.710746 0.0136899 -0.703387 -0.710506 -0.0206951 -0.699944 -0.71391 -0.0202711 -0.71594 -0.697166 -0.0372759 -0.702045 -0.711241 -0.0356087 -0.701966 -0.710414 -0.0505569 -0.701268 -0.711124 -0.0502606 -0.700146 -0.711081 -0.0644987 -0.839498 -0.535334 -0.0930681 -0.692712 -0.715521 -0.090444 -0.689808 -0.715599 -0.109925 -0.687873 -0.717642 -0.10872 -0.691697 -0.710693 -0.128336 -0.791946 -0.588633 -0.162273 -0.69118 -0.70554 -0.156474 -0.657414 -0.731782 -0.179729 -0.66946 -0.720505 -0.180819 -0.706064 0.695257 0.134505 -0.755379 0.645961 0.110168 -0.825155 0.55336 0.113631 -0.711826 0.698744 0.0711433 -0.713023 0.698755 0.0577991 -0.719017 0.694693 -0.0204022 -0.696003 0.716238 0.0508265 -0.782328 0.622154 0.0297942 -0.773709 0.632827 0.0300626 -0.710631 0.70348 0.0109728 -0.710722 0.70347 0.00199653 -0.711931 0.702246 0.00214499 -0.708536 0.705664 -0.00391533 -0.696501 0.717489 -0.00981973 -0.719573 0.694325 -0.011253 -0.704448 0.70958 -0.0157877 -0.712613 0.701298 -0.0190688 -0.706325 0.707067 -0.0340912 -0.722582 0.690561 -0.0316427 -0.710679 0.702952 -0.0281772 -0.705013 0.708822 -0.0229963 -0.710986 0.701986 -0.0414084 -0.740832 0.669686 -0.0518444 -0.797458 0.600146 -0.0623415 -0.736462 0.673357 -0.0649196 -0.696744 0.713148 -0.0772516 -0.710656 0.698679 -0.0825614 -0.708944 0.698671 -0.0962141 -0.803342 0.58081 -0.131534 -0.67499 0.72758 -0.12254 -0.730524 0.659598 -0.17682 -0.73213 0.657774 -0.176971 -0.699093 0.689346 -0.189921 -0.674322 -0.715744 0.181662 -0.691696 -0.701439 0.171872 -0.680641 -0.716126 0.154568 -0.70269 0.69521 0.151361 -0.710892 0.683297 0.166545 -0.697274 0.694799 0.176249 -0.666512 -0.717041 0.203995 -0.667366 -0.716303 0.203798 -0.668822 -0.716475 0.198344 -0.669585 -0.715812 0.198167 -0.69325 0.694854 0.191265 -0.694005 0.693899 0.191992 -0.692575 0.693771 0.197542 -0.693279 0.692867 0.198242 -0.620361 -0.710659 0.331837 -0.490986 -0.831376 0.260283 -0.5866 -0.43413 0.68369 -0.609601 -0.50867 0.607982 -0.498173 -0.647533 0.576649 -0.51898 -0.640173 0.566426 -0.668954 -0.586926 0.45609 -0.422348 -0.437063 0.794102 -0.485989 -0.427917 0.762038 -0.614075 -0.254015 0.747253 -0.472088 -0.165052 0.865962 -0.576081 -0.116316 0.809075 -0.584079 0.0954704 0.806062 -0.327476 0.0851343 0.941016 -0.527761 0.648513 0.548542 -0.624698 0.448172 0.639449 -0.582196 0.343996 0.736691 -0.37839 0.505491 0.775435 -0.649673 0.185807 0.737157 -0.653738 0.509676 0.559337 -0.639701 0.693379 0.331675 -0.648208 0.686482 0.329496 -0.582544 -0.0278159 0.812323 -0.582743 -0.0271951 0.812202 -0.551041 -0.0589326 -0.832395 -0.550872 -0.0580019 -0.832572 -0.541902 -0.129495 -0.830406 -0.396516 -0.190874 -0.897966 -0.597881 -0.26084 -0.757958 -0.431844 -0.452777 -0.780066 -0.563331 -0.426355 -0.707729 -0.558414 -0.554607 -0.616916 -0.459398 -0.661111 -0.593199 -0.550292 -0.632569 -0.54501 -0.636454 -0.637259 -0.434542 -0.52478 -0.77466 -0.352856 -0.614347 -0.731118 -0.296722 -0.640424 0.669872 -0.375669 -0.542982 0.779935 -0.311243 -0.638611 0.480715 -0.600907 -0.277179 0.669193 -0.689458 -0.688456 0.493916 -0.531108 -0.559729 0.061603 -0.826383 -0.23013 0.0756637 -0.970214 -0.553239 0.127138 -0.823263 -0.59578 0.287596 -0.749889 -0.235283 0.40329 -0.884307 -0.574545 0.350297 -0.739723 -0.646358 -0.726659 -0.232785 -0.64417 -0.729059 -0.23134 -0.638573 -0.729568 -0.244857 -0.636335 -0.732037 -0.24331 -0.696474 0.676393 -0.239616 -0.687684 0.685555 -0.238966 -0.701215 0.675112 -0.229174 -0.69415 0.682395 -0.229114 -0.660457 -0.724975 -0.195469 -0.666077 -0.716372 -0.20773 -0.652095 -0.726642 -0.216249 -0.699835 0.684832 -0.203065 -0.719291 0.666508 -0.195928 -0.69955 0.682355 -0.212183 -0.699659 -0.714397 0.0106388 -0.750189 -0.660531 0.0302565 -0.813474 -0.580411 0.0372021 -0.699249 -0.712979 0.0520747 -0.692582 -0.717999 0.0693374 -0.576547 -0.813307 0.078266 -0.687347 -0.718805 0.104277 -0.720198 -0.693761 -0.00332274 -0.803313 -0.595497 -0.00844157 -0.706852 -0.707246 -0.0127727 -0.659886 -0.750392 -0.0382473 -0.706637 -0.707237 -0.0219141 -0.691896 -0.721709 -0.0204005 -0.71305 -0.700336 -0.0329942 -0.794182 -0.60419 -0.0650282 -0.816992 -0.57249 -0.0691356 -0.695219 -0.715217 -0.0716612 -0.69277 -0.715238 -0.0922195 -0.612115 -0.785087 -0.0946223 -0.727721 -0.673747 -0.128404 -0.660336 -0.73785 -0.139762 -0.716552 -0.675785 -0.172823 -0.667679 -0.724951 -0.169268 -0.710864 0.698429 -0.0828831 -0.712348 0.692841 0.111944 -0.865145 0.489793 0.107826 -0.71189 0.698422 0.073613 -0.713611 0.698553 0.0527556 -0.716217 0.696121 0.0494817 -0.685134 0.72768 0.0327642 -0.821988 0.569055 0.0226273 -0.746473 0.664994 -0.0236931 -0.766992 0.641264 -0.0224512 -0.684062 0.729299 -0.01351 -0.714605 0.699413 -0.0126647 -0.704648 0.709527 -0.00657188 -0.716468 0.697606 -0.00434529 -0.710311 0.703886 -0.00137617 -0.710283 0.703862 0.00874624 -0.701937 0.711603 -0.0300906 -0.729688 0.682179 -0.0467635 -0.865828 0.495621 -0.0685744 -0.784441 0.616229 -0.070108 -0.726022 0.68337 -0.0767943 -0.713171 0.694854 -0.0925535 -0.754664 0.64685 -0.109852 -0.844214 0.517732 -0.138765 -0.80827 0.572705 -0.136783 -0.725287 0.673728 -0.141599 -0.693611 0.703403 -0.155328 -0.691432 0.705527 -0.155414 -0.713471 0.678383 -0.175372 -0.706436 0.684974 -0.178209 -0.677146 -0.718909 0.156979 -0.701 -0.6972 0.150038 -0.67357 -0.719566 0.168904 -0.707358 0.69291 0.139717 -0.713592 0.683681 0.152858 -0.70349 0.69209 0.161595 -0.666077 -0.721596 0.188787 -0.66732 -0.720512 0.188537 -0.668648 -0.72063 0.18331 -0.669809 -0.719612 0.183071 -0.700275 0.692135 0.174828 -0.705315 0.685795 0.179488 -0.701155 0.689763 0.180581 -0.622798 -0.715186 0.317225 -0.4859 -0.838615 0.246225 -0.595096 -0.446348 0.668307 -0.614547 -0.520684 0.592638 -0.50141 -0.654836 0.565489 -0.527925 -0.645946 0.551407 -0.672464 -0.596215 0.438543 -0.445964 -0.441933 0.778339 -0.493027 -0.436183 0.752774 -0.620194 -0.27072 0.736254 -0.494287 -0.171695 0.852174 -0.585413 -0.130423 0.800176 -0.596935 0.0875854 0.797495 -0.352535 0.0782652 0.93252 -0.518297 0.668825 0.532956 -0.637819 0.448151 0.626376 -0.595712 0.339093 0.728109 -0.386117 0.506548 0.770924 -0.662915 0.181028 0.726479 -0.677084 0.496354 0.543314 -0.638759 0.701598 0.315827 -0.660905 0.683785 0.309261 -0.593786 -0.0367554 0.803783 -0.59397 -0.0361951 0.803673 -0.570099 -0.0674725 -0.818801 -0.569929 -0.066383 -0.819008 -0.559825 -0.139542 -0.816776 -0.42429 -0.197461 -0.883735 -0.61595 -0.275301 -0.738116 -0.445295 -0.460884 -0.767658 -0.588932 -0.437666 -0.679417 -0.558978 -0.578685 -0.593858 -0.470622 -0.667656 -0.576845 -0.56995 -0.638788 -0.516824 -0.637764 -0.659099 -0.398554 -0.535129 -0.776622 -0.332409 -0.622259 -0.73619 -0.266117 -0.705371 0.498272 -0.504159 -0.554911 0.780103 -0.288986 -0.656671 0.667897 -0.350282 -0.308233 0.661278 -0.683889 -0.655091 0.48378 -0.580355 -0.597405 0.351443 -0.720829 -0.48484 0.370272 -0.792357 -0.654866 0.144626 -0.741778 -0.445776 0.0956875 -0.890016 -0.576772 0.00121424 -0.816904 -0.647848 -0.731484 -0.21266 -0.641123 -0.738556 -0.208556 -0.645331 -0.730764 -0.222557 -0.639641 -0.736942 -0.218578 -0.708387 0.674598 -0.207618 -0.68342 0.700836 -0.204369 -0.71952 0.665621 -0.198093 -0.703142 0.683078 -0.197472 -0.660148 -0.728971 -0.181124 -0.663944 -0.723162 -0.190302 -0.652232 -0.731478 -0.19883 -0.705854 0.683084 -0.187527 -0.71057 0.678819 -0.18519 -0.716942 0.67465 -0.175617 -0.721171 0.670963 -0.172398 -0.69554 -0.716935 0.0472112 -0.69751 -0.713149 0.069987 -0.857375 -0.503962 0.10455 -0.711097 -0.695126 0.105555 -0.681764 -0.72181 0.119111 -0.748841 -0.662045 0.0305474 -0.848249 -0.528951 0.0261686 -0.704008 -0.710157 0.00706927 -0.704019 -0.710177 -0.00250042 -0.694116 -0.719836 -0.0062748 -0.697809 -0.715597 -0.0313605 -0.704417 -0.708937 -0.0347227 -0.700879 -0.71226 -0.0381423 -0.718143 -0.695394 -0.026441 -0.748253 -0.663025 -0.0227155 -0.754375 -0.656062 -0.0223863 -0.69278 -0.72101 -0.0141398 -0.725949 -0.687639 -0.0122921 -0.754212 -0.65647 -0.014515 -0.735709 -0.677183 -0.0124802 -0.822749 -0.563221 -0.0765884 -0.86745 -0.491572 -0.0767243 -0.787296 -0.613481 -0.0616964 -0.715771 -0.696751 -0.0470032 -0.701731 -0.704713 -0.104653 -0.679429 -0.728529 -0.0873048 -0.73478 -0.673502 -0.0805762 -0.776097 -0.616293 -0.133626 -0.790656 -0.596592 -0.137625 -0.699017 -0.701584 -0.1384 -0.636524 -0.756226 -0.151523 -0.666971 -0.728925 -0.154331 -0.821961 0.564997 0.0718255 -0.946221 0.308154 0.0985241 -0.726957 0.679787 0.0970762 -0.772179 0.633613 0.0476897 -0.79351 0.608032 0.0252625 -0.84104 0.540516 0.0222392 -0.805284 0.592873 0.00441703 -0.824598 0.565677 -0.00688614 -0.778285 0.627766 -0.0135019 -0.90356 0.427232 -0.0324313 -0.810227 0.579648 -0.0868412 -0.830503 0.550385 -0.0856777 -0.761602 0.644863 -0.0641437 -0.818931 0.57098 -0.0577401 -0.803864 0.59283 -0.0485292 -0.846597 0.531046 -0.0355593 -0.765548 0.632412 -0.118285 -0.793625 0.597114 -0.11668 -0.776726 0.620164 -0.109971 -0.759128 0.644108 -0.09407 -0.742841 0.657704 -0.124952 -0.751789 0.643755 -0.142801 -0.789471 0.593558 -0.156283 -0.738116 0.65604 -0.15747 -0.723268 0.670978 -0.163318 -0.674861 -0.721883 0.153125 -0.685334 -0.713705 0.144715 -0.679277 -0.721775 0.132753 -0.706609 0.694837 0.13381 -0.706291 0.695244 0.133374 -0.723109 0.679888 0.121927 -0.671225 -0.721914 0.168219 -0.679112 -0.714503 0.168205 -0.668099 -0.724232 0.170681 -0.704091 0.69485 0.146422 -0.705921 0.692816 0.147247 -0.704819 0.691717 0.157346 -0.706983 0.68927 0.158373 -0.652875 -0.723139 0.225441 -0.562952 -0.564964 0.603242 -0.622107 -0.58751 0.517507 -0.648103 -0.652975 0.391901 -0.541791 -0.722731 0.429096 -0.680186 -0.682834 0.266618 -0.359599 -0.360004 0.860863 -0.584564 -0.395252 0.708563 -0.645482 -0.478513 0.595297 -0.624319 -0.339134 0.703715 -0.579686 -0.147511 0.801377 -0.597524 -0.139103 0.789693 -0.610743 0.0851743 0.787235 -0.377839 0.0743214 0.922884 -0.511137 0.687127 0.516328 -0.650196 0.453006 0.609943 -0.610042 0.339107 0.716139 -0.395226 0.509835 0.76411 -0.676826 0.182306 0.713212 -0.69611 0.490945 0.523835 -0.639324 0.70903 0.29756 -0.671114 0.683615 0.28684 -0.60704 -0.0409133 0.793617 -0.607245 -0.0402829 0.793493 -0.812317 0.0657848 0.579494 -0.52165 0.282586 0.805001 -0.683068 0.346001 0.643197 -0.643196 0.414585 0.643753 -0.674671 0.535881 0.507592 -0.435121 0.655005 0.617769 -0.775572 0.524192 0.351725 -0.635441 0.721531 0.274969 -0.700778 0.691116 0.17683 -0.710191 0.691436 0.13246 -0.624257 0.773448 0.109918 -0.783173 0.611749 0.111372 -0.637218 0.766765 0.077621 -0.72107 0.688907 0.0739291 -0.70597 0.70524 0.0651351 -0.70775 0.705111 0.0436845 -0.537449 0.842954 0.0240375 -0.707049 0.707062 0.0120706 -0.712022 0.677072 -0.186008 -0.724356 0.665234 -0.181032 -0.724152 0.665461 -0.181011 -0.683781 0.71418 -0.149635 -0.671913 0.726075 -0.146108 -0.707548 0.69278 -0.139395 -0.702326 0.700042 -0.12915 -0.779836 0.61254 -0.129041 -0.653366 0.750732 -0.0975402 -0.740432 0.666213 -0.0889984 -0.702352 0.707428 -0.0790423 -0.707015 0.703821 -0.069037 -0.696441 0.714829 -0.0631644 -0.767199 0.639437 -0.0502622 -0.944595 0.325223 -0.0443857 -0.706989 0.707002 -0.0177421 -0.677949 0.672762 -0.296272 -0.78732 0.482896 -0.383326 -0.76976 0.0521591 -0.636199 -0.380128 0.027865 -0.924514 -0.572022 0.626068 -0.529934 -0.705988 0.360487 -0.609615 -0.654115 0.443225 -0.612932 -0.622613 0.354794 -0.697477 -0.636798 0.322455 -0.700365 -0.602115 0.273387 -0.750145 -0.683432 0.128124 -0.718683 0.707079 -0.706462 -0.0308447 0.707082 -0.706458 -0.0308447 0.707083 -0.706458 -0.0308447 0.707087 -0.706453 -0.0308443 0.707083 -0.706457 -0.0308453 0.702928 -0.697595 -0.13876 0.702932 -0.69759 -0.13876 0.702932 -0.623578 -0.342106 0.702935 -0.623575 -0.342105 0.388582 -0.63711 -0.665654 0.387814 -0.637393 -0.665831 0.595084 -0.587111 -0.548796 0.706726 -0.541293 -0.455566 0.706605 -0.43543 -0.557773 0.702932 -0.314581 -0.637907 0.702934 -0.31458 -0.637905 0.702935 -0.108198 -0.702977 0.702934 -0.108199 -0.702977 0.704045 -0.0926941 0.70408 0.704041 -0.0926941 0.704084 0.704041 -0.271767 0.656102 0.704042 -0.271766 0.656101 0.704042 -0.432317 0.563406 0.70404 -0.432318 0.563408 0.70404 -0.563408 0.432318 0.704039 -0.563409 0.432319 0.704038 -0.656105 0.271768 0.704039 -0.656103 0.271767 0.70404 -0.704085 0.0926942 0.704036 -0.704089 0.0926953 0.707085 0 -0.707129 0.707085 0 -0.707129 0.707085 0 -0.707129 0.707085 0 -0.707129 0.707085 0 -0.707129 0.707085 0 -0.707129 0.707085 0 -0.707129 0.707089 0 0.707124 0.707089 0 0.707124 0.707089 0 0.707124 0.707089 0 0.707124 0.707089 0 0.707124 0.707089 0 0.707124 0.707089 0 0.707124 0.702934 0.108198 -0.702977 0.702935 0.108198 -0.702977 0.702934 0.31458 -0.637905 0.702934 0.31458 -0.637905 0.702934 0.491842 -0.513785 0.702932 0.491843 -0.513787 0.702931 0.623579 -0.342107 0.702936 0.623575 -0.342105 0.702936 0.697586 -0.138758 0.702932 0.69759 -0.13876 0.703866 0.707399 0.0644823 0.703867 0.707399 0.0644823 0.703867 0.664804 0.250214 0.703869 0.664802 0.250214 0.703867 0.574366 0.41794 0.703865 0.574368 0.417942 0.703865 0.442597 0.555591 0.703863 0.442599 0.555592 0.703864 0.278976 0.65326 0.703867 0.278975 0.653257 0.703867 0.0952775 0.703913 0.703873 0.0952759 0.703908 0.707083 0.706457 -0.0308444 0.707082 0.706458 -0.0308447 0.707084 0.706457 -0.0308446 0.707081 0.70646 -0.0308447 0.707083 0.706457 -0.0308447 -0.7443 0.472991 -0.471485 -0.701464 0.709645 0.0659693 -0.700073 0.71114 0.0646441 -0.702965 0.710783 0.025064 -0.744532 0.667457 0.0132103 -0.661739 0.74726 -0.0608577 -0.730802 0.678828 -0.0715617 -0.724177 0.663211 -0.188997 -0.749966 0.646358 -0.140614 -0.728311 0.66967 -0.145274 -0.710334 0.695711 -0.106831 -0.722377 0.660499 -0.204728 -0.731706 0.636226 -0.244587 -0.735594 0.632385 -0.242881 -0.728527 0.617221 -0.297131 -0.738209 0.60168 -0.305006 -0.739515 0.601276 -0.302629 -0.69627 0.595294 -0.40104 -0.782771 0.542891 -0.304203 -0.741702 0.548653 -0.38582 -0.723124 0.51943 -0.455285 -0.75561 0.505912 -0.416061 -0.743736 0.479995 -0.465254 -0.800597 0.409241 -0.437682 -0.667709 0.438174 -0.601804 -0.750488 0.45893 -0.475554 -0.758846 0.390606 -0.521132 -0.741827 0.357244 -0.567511 -0.69701 0.382186 -0.606722 -0.790643 0.314925 -0.525076 -0.783298 0.311113 -0.538194 -0.751651 0.286092 -0.594282 -0.770046 0.267976 -0.57898 -0.773018 0.210252 -0.598529 -0.782969 0.213778 -0.584174 -0.786732 0.148234 -0.599232 -0.789524 0.146305 -0.596026 -0.885236 0.00773454 -0.465079 -0.894353 0.0059978 -0.447322 -0.870432 0.0370861 -0.49089 -0.905131 0.0473781 -0.422486 -0.874321 0.0698478 -0.480295 -0.889146 0.0996408 -0.446643 -0.820107 0.105311 -0.562436 -0.860192 0.130683 -0.492941 -0.848703 0.155411 -0.505521 -0.810848 0.15361 -0.564738 -0.826092 0.165504 -0.538684 -0.8013 0.164177 -0.575295 -0.809557 0.156288 -0.565855 -0.811071 0.155356 -0.56394 -0.788318 0.143338 -0.598339 -0.798816 0.138468 -0.585423 -0.792113 0.131229 -0.5961 -0.707066 0.706743 -0.0239032 -0.6303 0.776264 -0.0116505 -0.600634 0.799446 -0.0111803 -0.747044 0.664276 0.0257493 -0.680804 0.731737 0.0326547 -0.753339 0.65475 0.0615076 -0.699526 0.712239 0.0581245 -0.701376 0.70901 0.0733207 -0.71817 0.691129 0.0810727 -0.699086 0.71043 0.08104 -0.792001 -0.131905 -0.5961 -0.809758 -0.148012 -0.567789 -0.864505 -0.169076 -0.473333 -0.84772 -0.162015 -0.505096 -0.802319 -0.140898 -0.580028 -0.842761 -0.167382 -0.511602 -0.829404 -0.167709 -0.532881 -0.829955 -0.167347 -0.532137 -0.832043 -0.166527 -0.529125 -0.861496 -0.138043 -0.488639 -0.864368 -0.118587 -0.488677 -0.862026 -0.115201 -0.493599 -0.893219 -0.0924932 -0.440006 -0.838097 -0.0734426 -0.540554 -0.88158 -0.0559843 -0.468702 -0.882767 -0.0327251 -0.46867 -0.88593 -0.0318254 -0.462725 -0.883288 -0.00694264 -0.46878 -0.878075 -0.00800223 -0.478457 -0.885262 -0.000418944 -0.465092 -0.701407 0.693717 -0.163662 -0.722507 0.671291 -0.165383 -0.691737 0.705209 -0.155501 -0.684063 0.71096 -0.163078 -0.68402 0.710996 -0.163098 -0.686653 0.708164 -0.164351 -0.687209 0.707656 -0.164218 -0.692944 0.705509 -0.148616 -0.701434 0.697159 -0.14819 -0.67714 0.724052 -0.131264 -0.71837 0.683108 -0.13156 -0.674198 0.731457 -0.102112 -0.731132 0.67764 -0.0790524 -0.692853 0.715627 -0.0885034 -0.732479 0.671703 -0.110858 -0.707077 0.706261 -0.035197 -0.731288 0.680707 -0.043092 -0.758204 0.650306 -0.0472136 -0.708336 0.703611 -0.0564906 -0.702545 0.70788 -0.0730469 -0.789047 -0.148969 -0.595998 -0.760966 -0.28937 -0.580686 -0.736292 -0.603738 -0.305571 -0.70169 -0.709562 0.0644508 -0.687957 -0.722438 0.0692684 -0.709495 -0.70355 0.0404272 -0.62738 -0.776503 -0.0586387 -0.761392 -0.648024 0.01863 -0.699116 -0.661734 -0.270824 -0.752198 -0.611855 -0.244605 -0.72146 -0.659366 -0.211498 -0.725551 -0.662643 -0.185686 -0.684897 -0.705941 -0.180452 -0.755162 -0.647743 -0.100792 -0.743304 -0.661413 -0.100157 -0.692235 -0.716309 -0.0878229 -0.743266 -0.488327 -0.457267 -0.744482 -0.486988 -0.456716 -0.736851 -0.522428 -0.429093 -0.751686 -0.508827 -0.4196 -0.726833 -0.558912 -0.399164 -0.764416 -0.520747 -0.380118 -0.647907 -0.64798 -0.400423 -0.797596 -0.522527 -0.301341 -0.744969 -0.592002 -0.307499 -0.760893 -0.354221 -0.543663 -0.79298 -0.335288 -0.50869 -0.758206 -0.375807 -0.532816 -0.747145 -0.401049 -0.530032 -0.717651 -0.432716 -0.54565 -0.775354 -0.428521 -0.463893 -0.750212 -0.459269 -0.475662 -0.744173 -0.472816 -0.471859 -0.790377 -0.148168 -0.594433 -0.78068 -0.18822 -0.595914 -0.807707 -0.215655 -0.548729 -0.736319 -0.253668 -0.627286 -0.79787 -0.299975 -0.522895 -0.609928 0.314249 0.727486 -0.618681 0.31268 0.720739 -0.621486 0.34003 0.705786 -0.626603 0.339814 0.701352 -0.633044 0.370517 0.679685 -0.643629 0.366478 0.67189 -0.632834 0.38728 0.670474 -0.669711 0.403596 0.623376 -0.656447 0.410929 0.632625 -0.653012 0.430902 0.622816 -0.655889 0.424684 0.624062 -0.646907 0.461264 0.607246 -0.676188 0.44745 0.585285 -0.666504 0.492816 0.559379 -0.658536 0.499894 0.562526 -0.709716 0.515294 0.480391 -0.734554 0.495338 0.463758 -0.698916 0.532876 0.477033 -0.642373 0.614732 0.45767 -0.785095 0.502082 0.362684 -0.712462 0.582029 0.39197 -0.694552 0.608525 0.38379 -0.69739 0.619078 0.361095 -0.657123 0.665706 0.353589 -0.73574 0.619758 0.273104 -0.689311 0.675988 0.260556 -0.729977 0.660092 0.177234 -0.71957 0.668754 0.187046 -0.69469 0.704178 0.146762 -0.707499 0.696365 0.120503 -0.656896 0.748023 0.0946017 -0.731802 0.680643 0.0344932 -0.68345 0.729979 0.00517676 -0.730222 0.678015 -0.0840913 -0.640388 0.767057 -0.0390758 -0.70506 0.694163 -0.145008 -0.689287 0.711933 -0.134295 -0.707045 -0.706873 -0.0204496 -0.678763 -0.734137 -0.0179835 -0.743432 -0.668727 0.010685 -0.770819 -0.636831 0.0168894 -0.678086 -0.734565 0.0247534 -0.739523 -0.671345 0.0490051 -0.771507 -0.633452 0.0592978 -0.688495 -0.723092 0.0557992 -0.707208 -0.703234 0.0729244 -0.681703 -0.72789 0.0738666 -0.699036 -0.710448 0.0813179 -0.6165 0.300322 0.727828 -0.623819 0.293299 0.724448 -0.62191 0.295945 0.725014 -0.619329 0.298382 0.726223 -0.621713 0.289248 0.72788 -0.683928 -0.710929 -0.163778 -0.725202 -0.66853 -0.164771 -0.703011 -0.692787 -0.160689 -0.690997 -0.708148 -0.145085 -0.719442 -0.680261 -0.140171 -0.714474 -0.685714 -0.139008 -0.696871 -0.705462 -0.129207 -0.698812 -0.706044 -0.114731 -0.698086 -0.706783 -0.114605 -0.703231 -0.704869 -0.092879 -0.702771 -0.705339 -0.09279 -0.703985 -0.706056 -0.0767471 -0.771867 -0.632668 -0.0628735 -0.755994 -0.651707 -0.0612372 -0.709877 -0.702661 -0.0484048 -0.702828 -0.710416 -0.0366464 -0.716523 -0.696451 -0.039378 -0.707082 -0.706357 -0.0331022 -0.684888 0.128749 0.717183 -0.693409 0.0791816 0.71618 -0.699667 0.0831404 0.709616 -0.703744 0.0199472 0.710174 -0.706108 0.0221678 0.707757 -0.706399 0.00200131 0.707811 -0.707118 0.0028171 0.70709 -0.625755 0.280513 0.727834 -0.601464 0.206418 0.771772 -0.52329 0.201903 0.82789 -0.672796 0.179891 0.717624 -0.631113 -0.74397 0.219556 -0.625057 -0.376469 0.683794 -0.632153 -0.33624 0.698087 -0.614509 -0.336223 0.713676 -0.620658 -0.31105 0.719744 -0.613962 -0.31274 0.724737 -0.65282 -0.409999 0.636967 -0.613783 -0.397646 0.682018 -0.678896 -0.365934 0.636547 -0.667536 -0.506502 0.545757 -0.667484 -0.443504 0.598138 -0.640128 -0.455528 0.618653 -0.651844 -0.425106 0.628 -0.736188 -0.557148 0.384206 -0.676949 -0.575783 0.458491 -0.692284 -0.540879 0.477695 -0.634703 -0.540737 0.552046 -0.765671 -0.440475 0.468754 -0.709498 -0.658909 0.249904 -0.664039 -0.670299 0.331287 -0.728243 -0.613492 0.305434 -0.690877 -0.617685 0.375705 -0.705335 -0.58862 0.395004 -0.725456 -0.685121 0.065749 -0.688984 -0.711221 0.139521 -0.755587 -0.631823 0.172884 -0.687484 -0.711655 -0.144617 -0.664865 -0.736757 -0.123058 -0.728431 -0.679757 -0.0855526 -0.647059 -0.761825 -0.0306112 -0.704765 -0.709437 -0.00243192 -0.691461 -0.722036 0.023367 -0.711352 -0.699587 0.0675036 -0.70712 -3.46043e-08 0.707094 -0.707124 0 0.707089 -0.707124 0 0.707089 -0.619444 -0.294066 0.727883 -0.619227 -0.294314 0.727969 -0.617702 -0.304133 0.725222 -0.6186 -0.302902 0.724972 -0.707043 -0.0147767 0.707016 -0.706262 -0.0493339 0.70623 -0.613492 -0.0319926 0.789053 -0.705582 -0.0930883 0.702488 -0.65953 -0.179165 0.730014 -0.712949 -0.235424 0.660514 -0.643758 -0.251359 0.722768 -0.624715 -0.282116 0.728108 -0.625088 -0.281946 0.727854 -0.694766 0.694729 -0.18615 -0.694764 0.694731 -0.186153 -0.694764 0.508578 -0.508578 -0.694766 0.508577 -0.508576 -0.694766 0.186151 -0.694729 -0.694766 0.186151 -0.694729 -0.694766 -0.18615 -0.694729 -0.694765 -0.186151 -0.69473 -0.694764 -0.508579 -0.508577 -0.694766 -0.508577 -0.508576 -0.694766 -0.694728 -0.186152 -0.694764 -0.694731 -0.186151 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 -0.849119 0.136708 -0.510204 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136708 -0.849119 -0.510203 -0.136709 -0.849119 -0.373496 -0.373494 -0.849119 -0.136707 -0.510204 -0.694764 0.694731 -0.186153 -0.694766 0.694729 -0.186151 -0.694766 0.508577 -0.508575 -0.694764 0.508578 -0.508578 -0.694765 0.18615 -0.69473 -0.694766 0.186151 -0.694729 -0.694766 -0.18615 -0.694729 -0.694766 -0.186151 -0.694729 -0.694766 -0.508578 -0.508576 -0.694766 -0.508577 -0.508575 -0.694766 -0.694728 -0.186152 -0.694766 -0.694728 -0.186152 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.258816 -0.965927 0 0.258816 -0.965927 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 -0.849119 0.136707 -0.510204 -0.849119 0.373496 -0.373494 -0.849119 0.510203 -0.136709 -0.849119 -0.510204 -0.136709 -0.849119 -0.373496 -0.373495 -0.849119 -0.136708 -0.510204 -0.986508 0.0439693 -0.1577 -0.902506 0.428869 0.0394272 -0.903052 0.427724 0.0393496 -0.911049 0.411153 0.0307132 -0.955218 0.293138 0.0403566 -0.964852 0.262762 0.00407719 -0.930554 0.36394 0.0402149 -0.999992 0.00395643 0.000409744 -0.999737 0.0228277 -0.00215035 -0.999501 0.0314625 0.00269801 -0.992876 0.118127 0.0155756 -0.999759 0.0219445 -0.000258719 -0.999806 0.0186389 -0.00644233 -0.999763 0.0210613 -0.00543934 -0.99974 0.0178272 -0.0141968 -0.999713 0.0192451 -0.0142456 -0.999717 0.0166007 -0.0170689 -0.999681 0.0163747 -0.0192075 -0.99969 0.0157307 -0.0193016 -0.999647 0.0144562 -0.0223091 -0.999638 0.0147805 -0.0225016 -0.999638 0.0128589 -0.023628 -0.999603 0.0127554 -0.025137 -0.999622 0.0117933 -0.024842 -0.9996 0.0108076 -0.0261317 -0.999686 0.00794414 -0.0237479 -0.999604 0.0096903 -0.0264061 -0.99953 -0.00258639 -0.0305465 -0.99854 0.0126599 -0.0525167 -0.918015 0.0983325 -0.384161 -0.964089 0.0590908 -0.258923 -0.875259 0.110223 -0.470928 -0.853181 0.100748 -0.511793 -0.865821 0.195451 -0.4606 -0.860529 0.183039 -0.47538 -0.860404 0.162876 -0.482883 -0.866196 0.163799 -0.472096 -0.853599 0.139187 -0.501991 -0.874922 0.227788 -0.427346 -0.866686 0.228793 -0.443294 -0.862279 0.201182 -0.46476 -0.895244 0.26042 -0.361552 -0.872319 0.259168 -0.414598 -0.872391 0.242688 -0.424308 -0.887362 0.265676 -0.376835 -0.887 0.322316 -0.330671 -0.903339 0.282539 -0.322724 -0.892921 0.354426 -0.277623 -0.905719 0.31924 -0.278853 -0.913201 0.406131 0.0334963 -0.918459 0.394411 -0.0295527 -0.910395 0.413206 -0.0210095 -0.925292 0.358607 -0.123435 -0.91498 0.386508 -0.115859 -0.955009 0.296147 -0.0159504 -0.957047 0.28978 -0.00935939 -0.956681 0.279297 -0.0821889 -0.954577 0.284444 -0.0887331 -0.954845 0.248038 -0.163551 -0.981362 0.190012 -0.0287017 -0.990999 0.133712 0.00654954 -0.990903 0.134415 -0.00655362 -0.991286 0.131682 -0.00346142 -0.991213 0.1268 -0.0376693 -0.990791 0.129013 -0.0410928 -0.990812 0.112276 -0.0754072 -0.989196 0.118276 -0.0866111 -0.989325 0.101346 -0.104715 -0.988007 0.103195 -0.114858 -0.987988 0.0890035 -0.126325 -0.98634 0.0917646 -0.136792 -0.986367 0.077338 -0.145254 -0.985507 0.0778582 -0.150715 -0.985513 0.0661801 -0.156157 -0.985107 0.0661547 -0.15871 -0.985107 0.0549246 -0.162933 -0.985012 0.0548706 -0.163523 -0.985028 0.0472491 -0.165792 -0.982171 0.0488107 -0.181545 -0.913075 0.347885 -0.212769 -0.907847 0.363205 -0.209515 -0.958787 0.240396 -0.151449 -0.947478 0.244468 -0.206205 -0.947527 0.22413 -0.227943 -0.940953 0.228894 -0.249431 -0.940969 0.196542 -0.275588 -0.932712 0.20289 -0.298134 -0.932901 0.170285 -0.31733 -0.928589 0.17137 -0.329172 -0.928641 0.145279 -0.341351 -0.926596 0.145145 -0.34692 -0.926607 0.120258 -0.356283 -0.926096 0.120103 -0.35766 -0.926017 0.089673 -0.366675 -0.884982 0.105875 -0.453428 -0.865015 -0.119435 -0.487324 -0.891935 -0.260243 -0.369765 -0.948056 -0.316478 0.0321245 -0.992965 -0.0433759 -0.110177 -0.986379 -0.0464563 -0.157793 -0.999587 -0.00911084 -0.0272514 -0.999646 -0.0101315 -0.024582 -0.999638 -0.010168 -0.0249084 -0.999605 -0.0127242 -0.0250607 -0.999638 -0.0126938 -0.0237264 -0.999638 -0.0146548 -0.0225757 -0.99962 -0.0148218 -0.0232322 -0.999717 -0.0153406 -0.0181737 -0.999718 -0.0153308 -0.0181457 -0.999711 -0.0188535 -0.014922 -0.999761 -0.0178568 -0.0126054 -0.999756 -0.020914 -0.00716558 -0.999729 -0.0216025 -0.00864579 -0.999809 -0.0195638 -0.0001497 -0.99976 -0.0217975 -0.00218705 -0.99972 -0.023285 0.00433114 -0.999756 -0.0218881 0.00309868 -0.999766 -0.0215933 0.00158182 -0.9029 -0.428825 0.029691 -0.903977 -0.426567 0.0294467 -0.910038 -0.41364 0.0270622 -0.939196 -0.343381 0.000982654 -0.941063 -0.337672 -0.0194634 -0.93803 -0.343669 -0.0446282 -0.943 -0.319301 -0.0938026 -0.936144 -0.324765 -0.134764 -0.93792 -0.302864 -0.169057 -0.930776 -0.299213 -0.210066 -0.924554 -0.271796 -0.267072 -0.925066 -0.267993 -0.269132 -0.881465 -0.265513 -0.39054 -0.862827 -0.238474 -0.445712 -0.884327 -0.229514 -0.406557 -0.860596 -0.221183 -0.458751 -0.867833 -0.193879 -0.457468 -0.860432 -0.192347 -0.471869 -0.853012 -0.166594 -0.494588 -0.865364 -0.15281 -0.477278 -0.860514 -0.175724 -0.478161 -0.955287 -0.0870921 -0.282562 -0.849555 -0.0953289 -0.518815 -0.873415 -0.110496 -0.474276 -0.877395 -0.10841 -0.46736 -0.909713 -0.09647 -0.403875 -0.990689 -0.135398 0.0142236 -0.990984 -0.13341 0.0123555 -0.990936 -0.134279 -0.00379607 -0.991325 -0.131271 -0.00651434 -0.991156 -0.126305 -0.0407123 -0.990723 -0.130198 -0.038947 -0.990851 -0.11354 -0.0729528 -0.991194 -0.10976 -0.0740766 -0.883635 -0.300702 -0.358843 -0.935208 -0.298488 -0.190504 -0.940759 -0.18955 -0.281145 -0.932511 -0.210322 -0.293578 -0.932851 -0.166019 -0.319728 -0.928494 -0.175793 -0.327102 -0.9286 -0.143025 -0.342412 -0.926546 -0.147232 -0.346172 -0.926584 -0.119541 -0.356584 -0.92609 -0.120473 -0.357553 -0.925605 -0.073563 -0.371272 -0.982171 -0.0487932 -0.181549 -0.931546 -0.288723 -0.221046 -0.989319 -0.110122 -0.095509 -0.98925 -0.0971482 -0.109303 -0.987942 -0.1077 -0.111223 -0.987936 -0.0858615 -0.128878 -0.986295 -0.0951483 -0.134793 -0.98635 -0.0754736 -0.14635 -0.985483 -0.0798372 -0.14983 -0.9855 -0.0652088 -0.156647 -0.985097 -0.0670591 -0.158388 -0.985103 -0.0546153 -0.163061 -0.985007 -0.0550224 -0.163504 -0.984988 -0.0405907 -0.167784 -0.999664 -0.00603193 -0.025206 -0.999597 -0.00715219 -0.0274794 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.998636 -0.0522194 -0.00874915 -0.965889 -0.258809 -0.010584 -0.968653 -0.248194 -1.97574e-05 -0.611344 -0.791365 -0.0213146 -0.766801 -0.641531 -0.00648948 -0.707092 -0.707092 -9.21783e-07 -0.846022 -0.533148 1.50665e-06 -0.897321 -0.44138 3.72114e-06 -0.479816 -0.877369 -0.00396947 -0.258817 -0.965918 0 -0.236184 -0.971708 0 0.195092 -0.980785 -0.00465686 0.161331 -0.986889 0.00547319 0.555561 -0.831458 -0.0103959 0.469391 -0.882929 0.00499573 0.738383 -0.674363 -0.00673061 0.831452 -0.555556 2.61088e-05 0.887455 -0.460895 -2.60448e-05 0.953507 -0.301369 -0.00695295 0.980761 -0.195088 0 0.993936 -0.109965 0 -0.988239 -0.152917 -0.0118356 -0.965858 -0.258801 -5.17131e-06 -0.526333 -0.850278 -0.00269037 -0.635411 -0.77217 -0.017156 -0.750131 -0.661066 -0.00881489 -0.707079 -0.707079 2.82184e-06 -0.831027 -0.556232 -3.46854e-06 -0.915005 -0.403442 2.48471e-05 -0.377663 -0.925943 -0.0108925 -0.258803 -0.965869 0 -0.124868 -0.992173 0 0.195092 -0.980785 -0.00489904 0.155906 -0.98776 0.00589125 0.55556 -0.831455 -0.01038 0.460196 -0.887756 0.00482518 0.734547 -0.67854 -0.00616138 0.831454 -0.55556 0.000331939 0.889389 -0.457151 -0.000331233 0.95554 -0.294861 -0.00639524 0.980765 -0.195087 0 0.994112 -0.10836 0 -0.987182 -0.1596 -0.0106029 -0.965871 -0.258806 -8.86227e-06 -0.912291 -0.409542 6.4444e-06 -0.827642 -0.561257 -0.00853045 -0.707083 -0.70708 -0.00311929 -0.673858 -0.738854 0 -0.1247 -0.992195 -0.0144614 -0.318247 -0.947897 -0.00707383 -0.258811 -0.965902 1.16093e-05 -0.448132 -0.893967 -5.21577e-06 -0.524009 -0.851713 0 0.195092 -0.980785 -0.00555181 0.146666 -0.989171 0.00340745 0.446806 -0.894625 -0.00534056 0.555562 -0.831458 0.000440633 0.658166 -0.752873 -0.00060545 0.783794 -0.621021 -0.00573376 0.831456 -0.555561 0.000388558 0.888796 -0.458304 -0.000380677 0.956205 -0.292698 -0.0059574 0.980768 -0.195087 0 0.994221 -0.107349 0 -0.98537 -0.170431 -0.00938202 -0.965883 -0.258809 -1.46554e-05 -0.907794 -0.419417 1.29969e-05 -0.822941 -0.568127 -0.00846022 -0.707083 -0.70708 -0.00236613 -0.664703 -0.747104 0 -0.124207 -0.992256 -0.0135823 -0.319619 -0.947449 -0.00647171 -0.258812 -0.965906 1.0628e-05 -0.449571 -0.893245 -4.17367e-06 -0.520515 -0.853853 0 0.135307 -0.990804 -0.00444162 0.19509 -0.980775 0.000271367 0.333808 -0.942641 -0.000499834 0.490417 -0.871488 -0.00517756 0.555562 -0.831459 0.000543648 0.653702 -0.756752 -0.00065728 0.782783 -0.622295 -0.00544235 0.831458 -0.555562 3.41502e-05 0.884206 -0.467098 -3.26134e-05 0.954456 -0.298351 -0.00565436 0.980769 -0.195088 0 0.994256 -0.107026 0 -0.983039 -0.183395 -0.00818235 -0.965893 -0.258811 -1.79486e-05 -0.90225 -0.431214 2.08055e-05 -0.817802 -0.575499 -0.00849575 -0.707082 -0.70708 -0.00171474 -0.654491 -0.756068 0 -0.123373 -0.99236 -0.0130034 -0.320388 -0.947197 -0.00608477 -0.258813 -0.965908 8.46564e-06 -0.450625 -0.892713 -2.78894e-06 -0.516441 -0.856323 0 0.124928 -0.992166 -0.0046211 0.19509 -0.980774 0.000352437 0.325111 -0.945676 -0.000520796 0.485736 -0.874105 -0.00506337 0.555562 -0.83146 0.000615291 0.649512 -0.760352 -0.000668491 0.781367 -0.624072 -0.00527477 0.831458 -0.555562 3.25962e-05 0.882674 -0.469987 -2.97468e-05 0.954353 -0.298682 -0.00548286 0.980771 -0.195088 0 0.994223 -0.107335 0 -0.980918 -0.194422 -0.00720001 -0.9659 -0.258813 -1.82222e-05 -0.897391 -0.441237 2.64368e-05 -0.813686 -0.581305 -0.0085558 -0.707082 -0.70708 -0.0012606 -0.646099 -0.763252 0 -0.122294 -0.992494 -0.0126798 -0.320317 -0.947226 -0.0059045 -0.258814 -0.965909 6.64606e-06 -0.451104 -0.892472 -1.35763e-06 -0.512903 -0.858446 0 0.118183 -0.992992 -0.00470812 0.19509 -0.980774 0.000400216 0.31918 -0.947694 -0.0005211 0.482902 -0.875674 -0.00501125 0.555562 -0.83146 0.000639354 0.6468 -0.762659 -0.000652895 0.780122 -0.625627 -0.00521171 0.831459 -0.555562 2.94706e-05 0.881645 -0.471914 -2.63848e-05 0.954158 -0.299303 -0.00542011 0.980771 -0.195088 0 0.994159 -0.107927 0 -0.986024 -0.166605 -0.00880264 -0.965888 -0.25881 -2.69913e-05 -0.909518 -0.415665 2.0039e-05 -0.829301 -0.558801 -0.00715977 -0.70709 -0.707088 -0.00406726 -0.685426 -0.728131 0 -0.0133959 -0.99991 -0.000181783 -0.0401069 -0.999195 -0.00200612 -0.1738 -0.984779 -0.0166457 -0.361834 -0.932094 -0.00418412 -0.258816 -0.965918 9.78876e-06 -0.468724 -0.883345 -1.06616e-05 -0.535659 -0.844435 0 0.116393 -0.993203 -0.00473257 0.19509 -0.980774 0.000410396 0.317514 -0.948254 -0.000517501 0.482141 -0.876093 -0.00500643 0.555562 -0.83146 0.000639492 0.64603 -0.763312 -0.000642824 0.77967 -0.62619 -0.00520676 0.831459 -0.555562 2.83545e-05 0.881341 -0.47248 -2.48744e-05 0.954057 -0.299624 -0.00541464 0.980771 -0.195088 0 0.994125 -0.108234 0 -0.9996 -0.0282689 -0.00381665 -0.965919 -0.258818 -0.00733928 -0.972328 -0.233503 -0.00866326 -0.707081 -0.707079 2.96064e-05 -0.810836 -0.585273 -1.67612e-05 -0.893799 -0.448468 0 -0.12111 -0.992639 -0.0125584 -0.319521 -0.947496 -0.00589095 -0.258814 -0.965909 0.000338429 -0.461319 -0.887234 -0.00096239 -0.640055 -0.768329 0 0.113247 -0.993567 -0.00480883 0.19509 -0.980774 0.000426457 0.31445 -0.949274 -0.000508964 0.480749 -0.876858 -0.00504022 0.555562 -0.83146 0.000630894 0.644537 -0.764573 -0.000615788 0.778519 -0.627621 -0.00524266 0.831459 -0.555562 2.41633e-05 0.880636 -0.473793 -2.09233e-05 0.95368 -0.300824 -0.00544509 0.980771 -0.195088 0 0.993997 -0.109408 0 -0.999258 -0.0385228 -0.00356011 -0.980779 -0.195089 0.0012585 -0.969282 -0.245949 -0.00144481 -0.831469 -0.555569 -0.00242876 -0.83681 -0.547488 0.00163193 -0.63575 -0.771894 -0.00477968 -0.555563 -0.831461 -0.000351659 -0.458357 -0.888768 0.000359145 -0.320003 -0.947417 -0.00475432 -0.19509 -0.980774 0 -0.120029 -0.99277 0 0.110933 -0.993828 -0.00495139 0.19509 -0.980773 0.000418198 0.311608 -0.950211 -0.000484437 0.479887 -0.87733 -0.00516926 0.555562 -0.831459 0.00057752 0.643258 -0.765649 -0.000552794 0.776744 -0.629816 -0.0053799 0.831458 -0.555562 1.70695e-05 0.879867 -0.47522 0 0.980785 -0.195091 -0.00950769 0.993194 -0.116081 -1.39326e-05 0.952984 -0.30302 0 -0.998928 -0.0462991 -0.00599084 -0.965908 -0.258815 -0.0057883 -0.965503 -0.260329 -0.00923853 -0.707078 -0.707075 3.03373e-05 -0.807646 -0.589667 -1.34196e-05 -0.888935 -0.458033 0 -0.118382 -0.992968 -0.0129631 -0.316112 -0.948633 -0.00637512 -0.258813 -0.965907 0.000226457 -0.455616 -0.890176 -0.00060169 -0.632546 -0.774522 0 0.112171 -0.993689 -0.00516622 0.195089 -0.980772 0.00037139 0.311542 -0.950232 -0.000445006 0.480463 -0.877015 -0.00542766 0.555562 -0.831458 0.000483066 0.643183 -0.765712 -0.000468013 0.774987 -0.631977 -0.00565378 0.831456 -0.555562 8.7738e-06 0.879412 -0.476061 0 0.980785 -0.195091 -0.00968397 0.992899 -0.118568 -6.9401e-06 0.952107 -0.305766 0 -0.998869 -0.047556 -0.00645254 -0.965905 -0.258815 -0.00629201 -0.965599 -0.259959 -1.38012e-05 -0.889646 -0.456651 2.92762e-05 -0.80888 -0.587974 -0.00973704 -0.707075 -0.707072 -0.000636594 -0.634108 -0.773244 0.000590919 -0.376358 -0.926474 -0.00976104 -0.258806 -0.96588 0 -0.116734 -0.993163 0 0.117148 -0.993115 -0.005442 0.195089 -0.98077 0.000298133 0.31474 -0.949178 -0.000395053 0.482428 -0.875935 -0.00581438 0.55556 -0.831456 0.000373504 0.644403 -0.764686 -0.000377186 0.773668 -0.633591 -0.00607885 0.831454 -0.55556 0.00532264 0.915097 -0.403198 -0.00615837 0.980767 -0.195087 0 0.993125 -0.117058 0 -0.999101 -0.042401 -0.00634711 -0.965907 -0.258814 -0.00787483 -0.96849 -0.248927 -1.51091e-05 -0.892572 -0.450906 2.73922e-05 -0.811958 -0.583716 -0.0103537 -0.70707 -0.707068 -0.000891625 -0.639529 -0.768767 0.000806587 -0.376892 -0.926257 -0.0106044 -0.258803 -0.965872 0 -0.115595 -0.993297 0 0.195092 -0.980785 -0.00906142 0.122855 -0.992383 0.00508785 0.418433 -0.908233 -0.0063083 0.555558 -0.831454 0.00027282 0.646519 -0.762898 -0.000293299 0.772989 -0.634419 -0.00664941 0.831452 -0.555557 0.00559369 0.914412 -0.404746 -0.00664399 0.980763 -0.195088 0 0.992848 -0.11939 0 0.0928001 -0.995685 -0.00448587 0.309836 -0.95078 0.00201786 0.349622 -0.936889 -0.00082567 0.620178 -0.784461 -0.010683 0.729285 -0.684127 -0.00143541 0.780598 -0.625032 0.00232367 0.968624 -0.248521 0 0.965656 -0.259826 0 -0.977607 -0.210439 -0.00592063 -0.984923 -0.172892 0.00379542 -0.868629 -0.495449 -0.00715743 -0.804417 -0.594022 -1.46396e-05 -0.717306 -0.696758 1.74319e-05 -0.58816 -0.808745 -0.00753713 -0.488759 -0.872386 0.0036595 -0.362371 -0.932027 -0.00222877 -0.180274 -0.983614 0 -0.135134 -0.990827 0.203868 -0.0274965 -0.978612 -0.0293981 0.0308287 -0.999092 0.0428529 0.243585 -0.968932 0.518807 0.319876 -0.792792 -0.330216 0.369991 -0.868368 0 -0.173293 0.98487 -0.323732 0.320456 0.890228 0.00577323 0.185083 0.982706 -0.019675 0.0161852 0.999675 0.0819282 0.0392785 0.995864 -0.0723974 -0.196231 0.977881 7.99748e-07 -0.1733 0.984869 -8.38089e-07 -0.354849 0.934924 -0.010233 -0.478394 0.878086 0.00359726 -0.56845 0.82271 -0.00494512 -0.800191 0.599724 -0.00444013 -0.801856 0.597501 0.0033924 -0.952549 0.304366 -0.0105776 -0.977052 0.21274 0 -0.997419 0.0717939 0 0.999582 0.0289218 -0.00743264 0.968224 0.249974 0.00452549 0.955554 0.294782 -0.00253292 0.796658 0.604425 -0.0168211 0.726123 0.687359 0.00102741 0.629388 0.77709 -0.00190938 0.306974 0.951716 0 0.299558 0.954078 0 0.980785 0.195092 -0.00765086 0.987126 0.159761 0.0051892 0.884105 0.46726 -0.00840362 0.831441 0.555549 -0.000172323 0.752409 0.658697 0.00027598 0.633625 0.77364 -0.00922597 0.555545 0.831435 0.0064514 0.403922 0.914771 -0.0083636 0.195085 0.980751 0 0.123632 0.992328 0 -0.155253 0.987875 -0.0150918 -0.25879 0.965816 -0.0134915 -0.731416 0.681798 -8.49362e-06 -0.553215 0.833038 1.48629e-05 -0.405782 0.91397 -0.055416 -0.845645 0.530861 3.61246e-05 -0.707107 0.707107 -2.0335e-05 -0.93023 0.366977 -0.0167001 -0.965791 0.258782 0 -0.993498 0.113847 0 0.980785 0.19509 -0.00650772 0.98662 0.162906 0.00451496 0.88114 0.472834 -0.00760317 0.831445 0.555554 -0.000206336 0.75105 0.660245 0.000351174 0.633352 0.773864 -0.00855446 0.555549 0.83144 0.00590962 0.40263 0.915344 -0.00777012 0.195086 0.980755 0 0.12359 0.992333 0 -0.151082 0.988521 -0.0142221 -0.258793 0.965828 1.98818e-05 -0.401971 0.915652 -0.0271646 -0.776428 0.62962 -0.00693484 -0.657844 0.753122 -1.07847e-05 -0.550643 0.834741 -0.0515065 -0.844759 0.532663 3.99317e-05 -0.707108 0.707106 -2.28502e-05 -0.930445 0.36643 -0.0156797 -0.965807 0.258788 0 -0.993562 0.113291 0 0.980785 0.19509 -0.00515857 0.985764 0.168055 0.00369456 0.876363 0.481637 -0.00683926 0.83145 0.555557 -0.000232218 0.748851 0.662738 0.000435263 0.632512 0.77455 -0.00802264 0.555552 0.831443 0.00546116 0.400213 0.916406 -0.00733608 0.195086 0.980759 0 0.123231 0.992378 0 -0.14573 0.989324 -0.0136167 -0.258795 0.965836 2.60239e-05 -0.397071 0.917788 -0.025771 -0.775659 0.630625 -0.00620772 -0.655677 0.755016 -1.23875e-05 -0.547574 0.836757 -0.048574 -0.843575 0.534809 4.16788e-05 -0.707108 0.707106 -2.4163e-05 -0.930505 0.366279 -0.014977 -0.965817 0.258791 0 -0.993578 0.11315 0 0.980785 0.19509 -0.00382785 0.984705 0.174186 0.0042901 0.831462 0.555565 -0.00916951 0.868704 0.495247 0.00456512 0.666767 0.745252 -0.0076536 0.555553 0.831446 -0.000336518 0.466807 0.884359 0.000279785 0.318491 0.947926 -0.00707323 0.195087 0.98076 0 0.122625 0.992453 0 -0.140608 0.990065 -0.0132506 -0.258797 0.965841 3.12326e-05 -0.392369 0.919808 -0.02488 -0.774687 0.631855 -0.00567736 -0.653568 0.756846 -1.36659e-05 -0.54487 0.838521 -0.0467398 -0.842404 0.536815 4.12252e-05 -0.707107 0.707106 -2.34661e-05 -0.930421 0.366494 -0.0145931 -0.965823 0.258791 0 -0.993552 0.113375 0 0.980785 0.19509 -0.00280113 0.983764 0.179445 0.00305456 0.831466 0.555567 -0.00807317 0.86411 0.503238 0.00420995 0.662098 0.749405 -0.00744848 0.555554 0.831447 -0.000341852 0.465106 0.885255 0.00029472 0.318105 0.948056 -0.00696318 0.195087 0.980761 0 0.121919 0.99254 0 -0.137246 0.990537 -0.0130933 -0.258797 0.965843 3.44861e-05 -0.389273 0.921123 -0.0244624 -0.773861 0.632883 -0.0053985 -0.65215 0.758071 -1.41828e-05 -0.543255 0.839568 -0.0459368 -0.841594 0.538154 3.86592e-05 -0.707107 0.707107 -2.2105e-05 -0.930271 0.366873 -0.0144681 -0.965825 0.258792 0 -0.993507 0.113772 0 0.980785 0.19509 -0.0023879 0.983358 0.18166 0.00257319 0.831467 0.555568 -0.00768962 0.862241 0.50644 0.00409238 0.66019 0.751087 -0.00738693 0.555554 0.831447 -0.000337734 0.464232 0.885713 0.000296757 0.317581 0.948231 -0.0069553 0.195087 0.980761 0 0.12135 0.99261 -0.00278531 -0.162642 0.986681 -0.000273168 -0.0401076 0.999195 0 -0.0133957 0.99991 -0.00888463 -0.718575 0.695392 -1.42066e-05 -0.542872 0.839816 7.31832e-05 -0.25882 0.965926 -0.042846 -0.45759 0.888131 -0.0227111 -0.34766 0.937345 -0.0458162 -0.84137 0.538515 3.77345e-05 -0.707107 0.707107 -2.13975e-05 -0.930202 0.367048 -0.0144658 -0.965825 0.258792 0 -0.993486 0.113953 0 0.980785 0.19509 -0.00213268 0.983092 0.183099 0.00164946 0.862499 0.506056 -0.0054816 0.831457 0.555562 -1.17019e-05 0.738367 0.674399 2.94062e-05 0.623922 0.781487 -0.00738158 0.555554 0.831448 -0.000334362 0.463665 0.886011 0.000296588 0.317393 0.948294 -0.00697446 0.195087 0.980761 0 0.12118 0.992631 0 -0.134932 0.990855 -0.0131301 -0.258797 0.965842 3.6741e-05 -0.387132 0.922024 -0.024394 -0.77291 0.634047 -0.0052697 -0.650996 0.759063 -1.41492e-05 -0.542189 0.840257 -0.0458967 -0.840851 0.539317 3.46151e-05 -0.707107 0.707106 -1.97206e-05 -0.929953 0.367679 -0.0145757 -0.965823 0.258792 0 -0.99341 0.114614 0 0.980785 0.19509 -0.00163331 0.982551 0.185984 0.00127824 0.859927 0.510415 -0.00537684 0.831458 0.555562 -1.07557e-05 0.737144 0.675736 2.87259e-05 0.622928 0.782279 -0.0074407 0.555554 0.831447 -0.00031733 0.462339 0.886703 0.000287879 0.316571 0.948569 -0.00709659 0.195087 0.98076 0 0.120581 0.992704 0 -0.13378 0.991011 -0.013381 -0.258796 0.965839 3.74433e-05 -0.386058 0.922474 -0.0246956 -0.771844 0.635332 -0.00531048 -0.650196 0.759748 -1.41463e-05 -0.541846 0.840478 -0.0466863 -0.840212 0.540245 2.81244e-05 -0.707107 0.707106 -1.59397e-05 -0.929478 0.368879 -0.0149346 -0.965818 0.25879 0 -0.993265 0.115864 0 0.980785 0.195091 -0.00138288 0.982251 0.187569 0.00108625 0.858689 0.512495 -0.00547414 0.831457 0.555561 -9.86821e-06 0.736715 0.676204 2.70491e-05 0.622211 0.782849 -0.00765185 0.555553 0.831446 -0.000284136 0.461023 0.887388 0.000263858 0.315139 0.949046 -0.00737459 0.195087 0.980758 0 0.11968 0.992812 0 -0.0837306 0.996488 -0.0134448 -0.278958 0.960209 -0.0412873 -0.438848 0.897612 0.000110443 -0.258819 0.965926 -2.31786e-05 -0.547152 0.837033 -0.00948914 -0.707076 0.707074 5.95071e-05 -0.745044 0.667015 -1.32352e-05 -0.888068 0.459711 -0.00878742 -0.965888 0.25881 0 -0.976721 0.214514 0 0.980785 0.19509 -0.00161283 0.982418 0.186687 0.00125727 0.859805 0.510621 -0.00586699 0.831455 0.555561 -9.43118e-06 0.737532 0.675312 2.43611e-05 0.622172 0.78288 -0.00805472 0.555552 0.831443 -0.000241698 0.4603 0.887764 0.000227143 0.313492 0.949591 -0.00781928 0.195086 0.980755 0 0.118791 0.992919 -3.2539e-06 -0.517693 0.855566 0 -0.0505572 0.998721 4.23303e-05 -0.258819 0.965926 -0.0435225 -0.437529 0.89815 -0.00857093 -0.246879 0.969009 -0.00242114 -0.627485 0.778625 -0.0155049 -0.707023 0.707021 0.00101665 -0.801138 0.598479 -0.00201902 -0.965924 0.258819 0 -0.9681 0.250565 0 0.980785 0.19509 -0.00236193 0.983018 0.183492 0.00180729 0.863024 0.505159 -0.006551 0.831452 0.555559 -8.87987e-06 0.739429 0.673234 2.13874e-05 0.622886 0.782312 -0.00865079 0.555549 0.831439 0.00593542 0.387857 0.9217 -0.00841442 0.195085 0.98075 0 0.118206 0.992989 0 -0.139731 0.990189 -0.0158127 -0.258787 0.965805 -0.00674147 -0.651148 0.75892 -1.16651e-05 -0.545436 0.838152 2.70933e-05 -0.391467 0.920192 0 -0.965926 0.258818 -0.0369617 -0.990872 0.129638 -4.11604e-06 -0.92785 0.372954 9.07639e-06 -0.707106 0.707108 -0.0555609 -0.839879 0.539923 -0.0287274 -0.769733 0.637719 0 0.980785 0.195092 -0.00354605 0.983872 0.178837 0.00264519 0.867438 0.497538 -0.00744457 0.831447 0.555554 -8.34026e-06 0.741934 0.670473 1.83336e-05 0.624188 0.781274 -0.00939354 0.555545 0.831434 0.00655271 0.389324 0.921077 -0.00910451 0.195084 0.980744 0 0.118144 0.992997 0 -0.06766 0.997708 -0.0130548 -0.258798 0.965843 6.25427e-05 -0.323886 0.946096 -1.94302e-05 -0.552026 0.833827 -0.0126369 -0.70705 0.707051 2.9228e-05 -0.748916 0.662665 0 -0.965926 0.258818 -0.0137675 -0.976633 0.21447 -6.90165e-06 -0.889459 0.457015 -0.962815 0.069813 -0.260987 -0.966278 0.0792708 -0.244994 -0.967478 0.0796018 -0.240102 -0.966383 0.0820804 -0.243652 -0.969572 0.0942213 -0.225947 -0.962782 0.0628193 -0.262876 -0.96191 0.064176 -0.265725 -0.953626 0.0666353 -0.293525 -0.954288 0.0673014 -0.291212 -0.954598 0.0680816 -0.290014 -0.946842 0.0532422 -0.317264 -0.957052 0.0503816 -0.285506 -0.951308 0.0424717 -0.305302 -0.955934 0.0798046 -0.282527 -0.947769 0.0541434 -0.314328 -0.940289 0.0359912 -0.338468 -0.941208 0.0373016 -0.335763 -0.952768 0.00388432 -0.303673 -0.944149 0.0469656 -0.326155 -0.952922 0.035992 -0.301071 -0.933752 0.0186529 -0.357433 -0.934638 0.0199595 -0.355039 -0.946918 -0.0147074 -0.321138 -0.938093 0.0317758 -0.344924 -0.947617 0.0217589 -0.318667 -0.926428 0.00618545 -0.376421 -0.927442 0.00643772 -0.373911 -0.939943 -0.0225965 -0.340583 -0.931639 0.0198691 -0.362842 -0.941087 0.0115095 -0.337968 -0.92444 -0.00514061 -0.381293 -0.941653 -0.0111987 -0.336398 -0.931394 -0.0202661 -0.363449 -0.932162 -0.0191113 -0.361536 -0.940367 0.0232811 -0.339364 -0.92695 -0.00621444 -0.375134 -0.935043 -0.020967 -0.353913 -0.947957 -0.022578 -0.317598 -0.938469 -0.0326807 -0.343813 -0.947299 0.0137541 -0.320057 -0.934129 -0.0196767 -0.356392 -0.941603 -0.038326 -0.334537 -0.953185 -0.0373648 -0.300072 -0.940667 -0.0371165 -0.337296 -0.946402 -0.0543687 -0.318383 -0.947612 -0.0199965 -0.318799 -0.952471 -0.036344 -0.302454 -0.957334 -0.0511814 -0.284416 -0.948192 -0.0551104 -0.312882 -0.956215 -0.0801294 -0.281481 -0.953104 -0.0536676 -0.297847 -0.947911 -0.0386755 -0.316179 -0.954008 -0.0681641 -0.291927 -0.962253 -0.0637207 -0.264592 -0.96303 -0.0645799 -0.261538 -0.954419 -0.0672168 -0.290803 -0.955024 -0.0687314 -0.288452 -0.969386 -0.0924535 -0.227472 -0.966238 -0.0728755 -0.247129 -0.969095 -0.0820362 -0.232647 -0.969036 -0.0820102 -0.232902 -0.97032 -0.0830333 -0.227122 -0.984627 0.0691781 0.16039 -0.982324 0.052496 0.179675 -0.984035 0.0542773 0.169496 -0.981858 0.0444397 0.184336 -0.980814 0.0437323 0.189979 -0.973306 0.0418193 0.225671 -0.973171 0.0422189 0.226176 -0.9799 0.0398344 0.19547 -0.9804 0.0408955 0.192726 -0.974064 0.0408137 0.222563 -0.969188 0.0351292 0.243805 -0.977189 0.033313 0.209742 -0.971251 0.0441179 0.233933 -0.977331 0.00357745 0.211686 -0.968561 0.0345351 0.246366 -0.964969 0.0245428 0.261213 -0.974689 0.0240677 0.222265 -0.967659 0.0371887 0.249504 -0.974528 -0.0159147 0.223699 -0.964455 0.0237263 0.26318 -0.961569 0.0131983 0.274245 -0.972852 0.0149459 0.230946 -0.964874 0.0298852 0.261009 -0.972091 -0.0360317 0.231819 -0.961178 0.012408 0.275651 -0.957368 0.00398927 0.288845 -0.970078 0.00803823 0.242662 -0.962402 0.0252767 0.270452 -0.969597 -0.0472198 0.240108 -0.958008 0.00425823 0.28671 -0.95983 -0.00539571 0.280529 -0.958126 -0.00433753 0.286315 -0.95903 -0.000988877 0.283303 -0.970717 -0.0114866 0.239949 -0.972135 -0.0091941 0.234241 -0.961348 -0.0130554 0.275026 -0.961748 -0.0138586 0.273584 -0.972214 0.0348556 0.231483 -0.96501 -0.03028 0.26046 -0.972942 -0.0154349 0.230533 -0.964659 -0.0244065 0.262368 -0.965189 -0.0252019 0.260335 -0.974693 0.014817 0.223055 -0.967847 -0.0376352 0.248709 -0.974812 -0.0246484 0.221663 -0.968841 -0.0350423 0.245193 -0.969443 -0.0356838 0.242708 -0.977504 -0.00461923 0.210868 -0.971477 -0.0445029 0.232922 -0.977373 -0.0337856 0.208807 -0.974341 -0.042786 0.220971 -0.97358 -0.0421693 0.224418 -0.973938 -0.0411119 0.223059 -0.980042 -0.0415967 0.194388 -0.980653 -0.0405099 0.191518 -0.983049 -0.0515193 0.175956 -0.983087 -0.0507577 0.175967 -0.984756 -0.0567321 0.164429 -0.979425 -0.100719 0.17488 -0.986081 -0.0589449 0.155468 -0.984855 0.0765634 0.155562 -0.98698 0.095309 0.129561 -0.988785 0.0627634 0.135519 -0.986166 0.12287 0.111263 -0.985967 0.136429 0.096212 -0.988573 0.126361 0.0821997 -0.989204 0.122411 0.0805621 -0.977558 0.201522 0.0613901 -0.974021 0.222298 0.0432064 -0.977078 0.212067 0.0186046 -0.952911 0.301623 0.0313804 -0.952514 0.304144 -0.0146299 -0.920367 0.39102 -0.00526871 -0.940903 0.336913 -0.0345261 -0.934973 0.352833 -0.0365327 -0.946239 0.318471 -0.0566385 -0.970733 0.107917 -0.214547 -0.970327 0.141848 -0.195816 -0.946106 0.318693 -0.0575978 -0.954613 0.289579 -0.0697022 -0.969769 0.229185 -0.0838013 -0.959145 0.26673 -0.0943165 -0.973371 0.195822 -0.119177 -0.968671 0.204284 -0.141229 -0.981133 0.109112 -0.1596 -0.968299 0.152045 -0.198192 -0.98381 0.0396461 0.174773 -0.990186 0.0129779 0.139152 -0.988384 -0.0326453 0.148432 -0.992561 0.0231296 0.119534 -0.995364 0.0371477 0.0887137 -0.995355 0.019042 0.0943717 -0.997059 0.0256941 0.0722082 -0.997989 0.0137113 0.061888 -0.999826 -0.000296073 -0.0186601 -0.999799 -0.0042781 -0.019569 -0.999644 0.0220663 -0.0150178 -0.998936 0.0427621 -0.0172604 -0.999952 -0.00948293 -0.00242265 -0.998192 0.028497 0.0529127 -0.999332 0.00691308 0.0358826 -0.999509 -0.0125273 0.0287371 -0.99971 0.0116893 0.0210366 -0.999911 0.0121323 0.00562734 -0.998545 0.0185507 -0.0506279 -0.999116 0.00607322 -0.0415873 -0.999278 0.00621183 -0.0374937 -0.999416 0.0014553 -0.0341466 -0.999556 0.00998049 -0.0280773 -0.999535 0.0161297 -0.0258937 -0.999706 0.0056805 -0.0235863 -0.999791 0.000332633 -0.020438 -0.999813 2.24284e-05 -0.0193466 -0.999816 -0.000155871 -0.0192071 -0.999828 -0.000155644 -0.0185696 -0.998941 -0.000955852 -0.0459955 -0.998361 0.0119619 -0.0559596 -0.998073 0.0111442 -0.0610486 -0.997519 0.0194428 -0.0676536 -0.997266 0.0102693 -0.0731756 -0.996541 0.0192575 -0.0808349 -0.996071 0.0175373 -0.0868024 -0.994108 0.0353098 -0.102479 -0.967829 0.0609963 -0.244104 -0.973811 0.0804602 -0.212648 -0.995309 0.0102127 -0.0962071 -0.99316 0.0281611 -0.113316 -0.992459 0.025412 -0.119913 -0.991539 0.0314899 -0.125936 -0.98991 0.0252797 -0.139427 -0.988264 0.0427446 -0.146651 -0.986412 0.035188 -0.160481 -0.98465 0.0429053 -0.169187 -0.982292 0.0340002 -0.184247 -0.969033 0.114793 -0.218626 -0.991268 0.0270312 0.129065 -0.986623 0.0317535 0.159899 -0.986092 0.0167257 0.165357 -0.981585 0.0334027 0.188083 -0.992326 0.059871 0.108187 -0.992572 0.047614 0.111952 -0.995475 0.0231346 0.09217 -0.99656 0.0234331 0.0794884 -0.998283 -0.0121356 0.0573094 -0.998466 0.0232751 0.0502418 -0.999731 0.0100002 0.0209296 -0.999735 0.00312755 0.0228147 -0.999858 0.0100548 0.0135349 -0.999937 0.0104142 0.00425604 -0.999973 0.00155842 0.00716432 -0.999972 0.00751964 0.000182073 -0.999973 0.0036346 -0.0063522 -0.999878 -0.0114234 -0.0106683 -0.999618 0.0207085 -0.0182871 -0.999801 0.0100926 -0.0172152 -0.999748 0.00117049 -0.0224132 -0.99964 -0.000161308 -0.0268245 -0.999595 0.00342141 -0.0282421 -0.999475 0.00190511 -0.0323426 -0.999305 0.00647826 -0.0367172 -0.999227 0.00172454 -0.0392821 -0.998984 0.00687513 -0.0445495 -0.99886 0.00552648 -0.0474081 -0.998683 0.00853422 -0.0505936 -0.998352 0.00521649 -0.0571516 -0.998028 0.0144035 -0.061097 -0.997616 0.0103041 -0.0682392 -0.997232 0.0142929 -0.0729684 -0.996668 0.00939052 -0.0810232 -0.995998 0.0219314 -0.0866379 -0.995327 0.0161318 -0.0952036 -0.994578 0.0210625 -0.101838 -0.993662 0.0141717 -0.111513 -0.992912 0.0244353 -0.116309 -0.991294 0.0233725 -0.129578 -0.991424 0.0222842 -0.128771 -0.988062 0.0358347 -0.149829 -0.990328 -0.00334741 -0.138708 -0.982984 0.0648615 -0.171859 -0.980951 0.0813332 -0.176411 -0.979811 0.0324183 -0.19728 -0.970728 0.0502234 -0.234874 -0.968861 0.0647535 -0.23899 -0.963923 0.0494102 -0.261553 -0.979991 0.0248861 0.19748 -0.984698 0.00846821 0.174061 -0.985458 0.025402 0.16801 -0.990344 0.0222893 0.136831 -0.990242 0.020669 0.13782 -0.992922 0.0248529 0.116142 -0.993135 0.0316063 0.112627 -0.994691 0.0202858 0.100891 -0.997424 0.0254853 0.0670508 -0.997453 0.0235352 0.0673387 -0.99946 0.0108285 0.0310398 -0.99946 0.0105851 0.0311069 -0.999747 0.0101992 0.0200363 -0.999892 0.00558022 0.0136296 -0.999886 0.00871009 0.0123609 -0.999989 0.00436002 0.0018127 -0.999862 -0.016001 -0.00437965 -0.999412 0.0135368 -0.0315059 -0.999876 -0.015098 -0.0045839 -0.999953 9.82939e-05 -0.00968016 -0.99984 0.000934606 -0.0178373 -0.999848 -0.00180608 -0.0173616 -0.999685 0.000843344 -0.0251004 -0.999457 0.0112107 -0.0309994 -0.997664 0.0192274 -0.065548 -0.998468 0.00586219 -0.0550212 -0.998853 0.00699079 -0.0473784 -0.998938 0.00311283 -0.04596 -0.999275 0.00390329 -0.0378748 -0.998176 -0.00219906 -0.0603311 -0.997368 0.0115291 -0.0715901 -0.996953 0.0102509 -0.077327 -0.995542 0.02616 -0.0906154 -0.996432 0.000946452 -0.0843884 -0.994999 0.017049 -0.0984223 -0.994336 0.0150207 -0.105214 -0.991976 0.0337467 -0.121841 -0.993431 0.00385732 -0.11437 -0.990971 0.0229333 -0.132102 -0.989906 0.019845 -0.140331 -0.989197 0.0243047 -0.144561 -0.986745 0.0198094 -0.161066 -0.987267 0.0131905 -0.158527 -0.984305 0.0288845 -0.174097 -0.982656 0.0244705 -0.183814 -0.976493 0.0500591 -0.209657 -0.979896 0.00904952 -0.199301 -0.973247 0.0351442 -0.227058 -0.968136 0.0231591 -0.249351 -0.964173 0.0502098 -0.260479 -0.959975 0.0370257 -0.277629 -0.980192 0.0233176 -0.196671 -0.993624 0.0164703 0.111533 -0.978872 0.0168982 0.203775 -0.98388 0.00048391 0.17883 -0.984723 0.0168561 0.173311 -0.990641 0.0197214 0.135061 -0.990738 0.0182815 0.134552 -0.99476 0.0280964 0.098305 -0.99421 0.0712676 0.0804151 -0.983769 0.168567 0.061519 -0.995597 0.0754495 0.0556262 -0.926815 0.375506 -0.00300436 -0.993634 0.111852 0.0134329 -0.999237 0.0293696 0.0257585 -0.999349 0.00029043 0.0360855 -0.998707 -0.048021 0.016688 -0.995975 -0.0887784 0.0123222 -0.998092 -0.0611834 0.00833263 -0.999763 -0.0217393 0.0011387 -0.999975 -0.00447157 -0.00544459 -0.999925 0.00315944 -0.011836 -0.999834 -0.00588014 -0.017273 -0.999829 -0.00392136 -0.0180459 -0.999768 -8.33323e-05 -0.0215165 -0.997163 0.0198922 -0.0725993 -0.998485 0.00159605 -0.0549955 -0.998793 0.0190149 -0.0452802 -0.999162 -0.021136 -0.0350642 -0.999464 -0.00936836 -0.0313783 -0.999665 0.000306903 -0.0258696 -0.997656 -0.00249349 -0.068377 -0.996241 0.0137001 -0.0855308 -0.995195 0.00187192 -0.0978931 -0.992723 0.0462054 -0.111207 -0.985154 0.0183641 -0.170688 -0.984398 0.0285143 -0.173631 -0.989486 0.0127194 -0.144068 -0.987486 0.0393175 -0.152729 -0.991703 0.000287934 -0.12855 -0.972578 0.0666865 -0.22281 -0.974772 0.0458 -0.218453 -0.964402 0.0108094 -0.264221 -0.960007 0.0392841 -0.277206 -0.955479 0.0249003 -0.294007 -0.998837 -0.00778869 0.0475766 -0.995624 -0.0711514 0.0605912 -0.993075 0.0190544 0.115927 -0.992084 0.0575001 0.111634 -0.955218 -0.28437 0.0818055 -0.918606 -0.385841 0.0853791 -0.975134 -0.208942 0.0738745 -0.999154 0.0178391 0.0370425 -0.999539 0.00486384 0.0299593 -0.999653 -0.00454142 0.0259363 -0.984132 0.0789684 0.158898 -0.985247 0.0413178 0.166074 -0.977509 0.0116211 0.210575 -0.993795 0.0387701 0.104255 -0.993059 0.0175541 0.116297 -0.991671 0.0150185 0.127915 -0.998785 0.008767 0.0484924 -0.997383 0.0406889 0.0597574 -0.977015 0.199443 0.0752573 -0.966952 0.24508 0.0702794 -0.988963 0.120535 0.0861591 -0.989524 0.14437 -0.000236567 -0.995876 0.0862145 0.0282563 -0.998703 0.0369024 0.035091 -0.999045 0.0125018 0.0418548 -0.941499 0.336911 0.00843029 -0.933627 0.358171 0.00737199 -0.98319 0.181605 0.018907 -0.9993 0.028636 -0.0240778 -0.99986 -0.00440427 -0.0161469 -0.999828 0.0166681 -0.0081898 -0.994475 0.0604715 -0.0858063 -0.996548 -0.0369621 -0.0743335 -0.979697 0.190473 -0.0625637 -0.871258 0.488575 -0.0469447 -0.794894 0.605399 -0.0404569 -0.92971 0.366291 -0.0383474 -0.984425 0.172897 -0.0318557 -0.898009 0.424754 -0.114735 -0.604479 0.793512 -0.0703185 -0.677613 0.731432 -0.0764682 -0.937713 0.334756 -0.0929113 -0.665329 0.73577 -0.126406 -0.956441 0.242655 -0.162291 -0.98197 -0.118141 -0.147573 -0.961 -0.144362 -0.235877 -0.964059 0.16472 -0.208465 -0.704115 0.697167 -0.134832 -0.949757 0.0166237 -0.312545 -0.95868 0.0462549 -0.2807 -0.954282 0.172962 -0.243782 -0.952343 -0.0988416 -0.28857 -0.969207 0.163311 -0.184301 -0.976859 -0.0541106 -0.206928 -0.990231 0.064665 -0.123539 -0.992354 -0.0540229 -0.110973 -0.996227 0.00388247 -0.0866962 -0.99818 0.0401806 -0.0449655 -0.994994 -0.0856666 -0.0514531 -0.978634 0.135243 0.154873 -0.990723 -0.115017 0.0723771 -0.992781 0.0905956 0.0786078 -0.999173 0.00330789 0.0405239 -0.998094 -0.0599236 0.0147431 -0.998454 0.0550092 0.00801683 -0.999705 -0.00844715 -0.0227839 -0.958839 -0.125981 -0.254472 -0.903303 0.393912 0.16993 -0.988902 -0.0650355 0.133576 -0.994451 0.0435181 0.0957821 -0.974202 0.209978 0.082698 -0.997069 -0.0491071 0.0586652 -0.999329 0.0207642 0.0301566 -0.988065 0.153241 0.0156127 -0.999337 -0.0364053 -0.000730464 -0.999217 0.0245082 -0.0310668 -0.99227 0.116449 -0.0429034 -0.99826 -0.00829543 -0.0583864 -0.995727 -0.00852931 -0.0919511 -0.989219 0.0957552 -0.110803 -0.988416 -0.0703362 -0.134486 -0.989772 -0.049387 -0.133838 -0.988504 -0.00585319 -0.151083 -0.98096 0.0627749 -0.183785 -0.981357 0.0492936 -0.185765 -0.907293 -0.384593 -0.170022 -0.97909 -0.112799 -0.169293 -0.945126 -0.269784 -0.184265 -0.97643 0.0118432 -0.215508 -0.961766 -0.0805967 -0.261745 -0.962194 -0.0501991 -0.267699 -0.949567 -0.01553 -0.313179 -0.945315 -0.314346 -0.0869803 -0.749132 -0.658034 -0.0761123 -0.809094 -0.581467 -0.0852219 -0.940416 -0.320916 -0.112386 -0.999771 -0.00775517 -0.0199642 -0.995753 -0.087766 -0.027807 -0.933875 -0.355706 -0.0367663 -0.745211 -0.665707 -0.0386572 -0.725071 -0.687607 -0.0383216 -0.986738 -0.149064 -0.0642497 -0.994203 0.0725882 -0.0793122 -0.999037 -0.00908965 0.0429342 -0.998709 -0.0387515 0.0328422 -0.991185 -0.130441 0.0231743 -0.970634 -0.240143 0.0141688 -0.92399 -0.382373 0.00581839 -0.932449 -0.361235 0.00692102 -0.991979 -0.126395 -0.00164694 -0.999871 0.0105325 -0.0121562 -0.993995 -0.044704 0.0998779 -0.986765 -0.139105 0.0833319 -0.975786 -0.205822 0.0740211 -0.988799 -0.132065 0.0695355 -0.998457 -0.014033 0.0537192 -0.977942 -0.0121242 0.208525 -0.983465 -0.0382371 0.177016 -0.981536 -0.10976 0.156655 -0.989865 -0.0245735 0.139867 -0.992929 -0.0142085 0.117858 -0.947671 -0.319247 0.000640838 -0.992306 -0.0371625 0.118105 -0.979169 -0.0174016 0.202302 -0.979043 -0.0178476 0.202871 -0.987444 -0.0151101 0.157248 -0.9806 -0.0938049 0.172119 -0.992471 0.0197164 0.120886 -0.99908 -0.0177906 0.039034 -0.998444 0.0229343 0.0508274 -0.992683 0.102229 0.0642692 -0.963547 0.256106 0.0773783 -0.92568 0.368879 0.0839301 -0.984717 0.146432 0.0942831 -0.99409 -0.00948151 0.108141 -0.999996 0.000483848 0.00282445 -0.99964 0.0247778 0.0102491 -0.998511 0.052139 0.0160597 -0.999393 0.0292914 0.018858 -0.999586 -0.00470232 0.0284034 -0.999978 -0.00310032 -0.00594733 -0.999977 -0.00398894 -0.00558452 -0.999886 0.00501335 -0.0142653 -0.999917 -0.00566228 -0.0115359 -0.999777 0.0042707 -0.020677 -0.999816 0.000200022 -0.0192013 -0.999686 -0.000204309 -0.0250487 -0.999285 -0.0147096 -0.034821 -0.999304 -0.00148739 -0.0372619 -0.990817 -0.0185694 -0.133932 -0.990822 -0.0187319 -0.133871 -0.993018 -0.0156152 -0.116927 -0.994844 0.0104271 -0.100881 -0.994654 0.0158736 -0.102041 -0.996058 -0.00869771 -0.0882776 -0.997032 -0.0129838 -0.0758808 -0.997812 0.0177048 -0.0637025 -0.997699 0.0209294 -0.0644921 -0.998503 -0.00560384 -0.0544087 -0.955078 -0.0253195 -0.295272 -0.960393 -0.0146575 -0.278263 -0.963479 -0.0397232 -0.26482 -0.970569 -0.013324 -0.240455 -0.974006 -0.0371346 -0.223457 -0.979918 -0.000313113 -0.199401 -0.98042 -0.00684099 -0.1968 -0.985992 -0.0444747 -0.160752 -0.984763 0.0102541 -0.173597 -0.988102 -0.0193278 -0.152581 -0.999183 -0.0317906 0.0249644 -0.995418 -0.0943099 0.0157987 -0.978417 -0.206501 0.00753425 -0.990377 -0.0315406 0.134755 -0.993637 -0.0163956 0.111428 -0.994787 -0.0278448 0.0981018 -0.994335 -0.0696479 0.0802928 -0.982316 -0.177696 0.0589928 -0.985131 -0.160507 0.0612763 -0.997942 -0.0440657 0.0465926 -0.999376 0.00174015 0.0352801 -0.994145 -0.0212943 0.105938 -0.980975 -0.0255467 0.192444 -0.980116 -0.03013 0.196124 -0.985776 -0.015249 0.167371 -0.987168 -0.0661026 0.145362 -0.991437 -0.0204629 0.128973 -0.99423 -0.0231097 0.104748 -0.99847 -0.0225561 0.0504824 -0.996514 -0.0210864 0.0807125 -0.995819 -0.0351357 0.0843193 -0.997672 -0.016463 0.0661807 -0.999628 -0.0193679 0.0192059 -0.999654 -0.00208623 0.0262343 -0.997103 -0.0666269 0.0366855 -0.997805 -0.0530356 0.0396575 -0.998986 9.10239e-05 0.0450311 -0.999616 -0.0129209 0.024505 -0.999787 -0.00545998 0.0199085 -0.999812 0.0158157 0.0112032 -0.999138 -0.0415098 0.000824887 -0.98728 -0.0245311 -0.157085 -0.99103 -0.0212721 -0.131933 -0.99994 -0.00887044 -0.0064113 -0.999938 -0.000969877 -0.0110882 -0.999881 0.000216926 -0.0153977 -0.999881 0.000248965 -0.0154058 -0.999787 0.000244941 -0.0206461 -0.999796 -0.000675839 -0.0201876 -0.999537 0.00228695 -0.0303548 -0.999564 -0.00392896 -0.0292745 -0.998707 -0.00199306 -0.0508028 -0.998655 0.00345086 -0.0517307 -0.997305 -0.0146796 -0.0718804 -0.99732 -0.015358 -0.0715382 -0.995353 -0.0012348 -0.0962825 -0.995419 -0.0280826 -0.0913909 -0.991589 -0.00871319 -0.129132 -0.975176 -0.0214014 -0.220395 -0.975438 -0.0241847 -0.218943 -0.982452 -0.0409916 -0.181956 -0.981407 -0.00178592 -0.191929 -0.986095 -0.0322633 -0.163019 -0.964002 -0.0556941 -0.259997 -0.96598 -0.0390073 -0.255658 -0.96825 0.00454987 -0.249944 -0.959661 -0.037356 -0.278668 -0.999314 -0.0338292 0.0150657 -0.995536 -0.0941539 0.00655588 -0.980759 -0.195224 -0.000617788 -0.994792 -0.0212507 0.0996867 -0.989252 0.0589703 0.133805 -0.989491 -0.00283838 0.14457 -0.98168 -0.0338409 0.187509 -0.99698 -0.0259725 0.0731813 -0.996851 -0.0285031 0.0739923 -0.999253 -0.0053291 0.0382775 -0.999066 -0.0163453 0.0400012 -0.999808 -0.0116791 0.0157622 -0.99984 -0.00991404 0.0149032 -0.99994 -0.0104609 0.00329893 -0.999763 0.0212028 -0.00485864 -0.999649 -0.022493 -0.0139648 -0.999821 0.00557048 -0.0180984 -0.999745 -0.00213604 -0.0224853 -0.999191 -0.00530149 -0.0398544 -0.999498 0.00735965 -0.0308218 -0.999297 0.0181785 -0.0327865 -0.999634 0.0028966 -0.0268943 -0.998136 0.0204935 -0.0574918 -0.997993 0.0244863 -0.0583932 -0.998813 -0.00489254 -0.0484541 -0.963602 -0.0502105 -0.262583 -0.968875 -0.0360877 -0.244908 -0.970353 -0.0558917 -0.235142 -0.978031 -0.0296508 -0.20634 -0.980495 -0.0820317 -0.178609 -0.987935 0.0291332 -0.152108 -0.990668 -0.0191875 -0.134942 -0.994337 -0.0296672 -0.102044 -0.993816 0.0102988 -0.110562 -0.996129 -0.0334121 -0.0813109 -0.996024 -0.012965 -0.088134 -0.997427 -0.0148489 -0.0701378 -0.99744 -0.024512 0.0671805 -0.994399 -0.0230755 0.103145 -0.994129 -0.0433249 0.0991443 -0.988817 -0.0281026 0.146464 -0.986437 -0.0518732 0.155729 -0.984325 -0.0405415 0.171644 -0.999957 -0.000865359 -0.00923422 -0.999958 -0.00161862 -0.00906181 -0.999961 -0.00872901 -0.00165715 -0.999923 -0.00764644 0.00974632 -0.999711 -0.0204796 0.0126159 -0.999166 -0.00634555 0.0403365 -0.997932 -0.0426095 0.0481269 -0.997143 -0.0146042 0.0741133 -0.999839 -0.00539465 -0.017126 -0.999755 -0.0107349 -0.0193686 -0.99973 -0.0123404 -0.0196762 -0.99755 -0.0273272 -0.0644044 -0.999781 -0.00492848 -0.0203131 -0.999546 -0.00154964 -0.0300909 -0.999475 -0.00593529 -0.0318593 -0.999321 -0.0045276 -0.0365572 -0.998996 -0.0119092 -0.0431858 -0.998969 -0.00807067 -0.0446682 -0.998481 -0.0103151 -0.0541227 -0.993817 -0.0234946 -0.108518 -0.99407 -0.0258843 -0.10562 -0.995575 -0.0174036 -0.0923428 -0.995712 -0.0239996 -0.0893373 -0.996846 -0.0156471 -0.0777974 -0.997572 -0.0243591 -0.0652499 -0.967432 -0.0618363 -0.245464 -0.973476 -0.0439456 -0.22453 -0.973904 -0.0552476 -0.220132 -0.980082 -0.0460849 -0.193173 -0.980256 -0.047394 -0.191969 -0.984891 -0.0385376 -0.168835 -0.985016 -0.042956 -0.167027 -0.988601 -0.0334598 -0.146794 -0.988861 -0.0356437 -0.14451 -0.991568 -0.0265979 -0.126828 -0.99139 -0.0209589 -0.129252 -0.992814 -0.0281441 -0.116312 -0.98171 -0.145793 0.122433 -0.970356 -0.104211 -0.21806 -0.970919 -0.102062 -0.216565 -0.972034 -0.112651 -0.206058 -0.974236 -0.109645 -0.197086 -0.973019 -0.140604 -0.182931 -0.977891 -0.13215 -0.162068 -0.979619 -0.12431 -0.15778 -0.975934 -0.159935 -0.148235 -0.971782 -0.1935 -0.1349 -0.96925 -0.216383 -0.117187 -0.975319 -0.195782 -0.102089 -0.97068 -0.214412 -0.108661 -0.948719 -0.306548 -0.0772102 -0.956488 -0.284075 -0.0665701 -0.942196 -0.330525 -0.0549512 -0.932496 -0.359159 -0.0381581 -0.942879 -0.331772 -0.030097 -0.925116 -0.379303 -0.0170262 -0.942211 -0.334957 -0.0065443 -0.946509 -0.322664 0.00281397 -0.966371 -0.256158 0.022578 -0.961729 -0.272613 0.0275729 -0.982566 -0.170497 0.0741228 -0.98398 -0.123067 0.128989 -0.986555 -0.105099 0.125154 -0.983117 -0.162955 0.0832315 -0.992922 -0.103499 0.0582495 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -5.43863e-07 1 1.30537e-06 0 1 -1.51883e-06 0 1 0 0 1 0 0 1 0 1.99689e-06 1 -3.44117e-07 -1.16888e-06 1 2.01429e-07 1.94719e-06 1 -6.95891e-07 0 1 0 0 1 0 0 1 0 0 1 0 -2.84035e-06 1 3.06158e-07 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -9.20031e-06 -1 -7.92263e-06 7.61788e-06 -1 8.43525e-06 0 -1 0 0 -1 0 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.01287e-06 1 2.16048e-06 0 1 -2.59211e-06 0 1 0 0 1 0 0 1 0 3.04914e-06 1 1.22664e-06 -1.16623e-06 1 -2.05935e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1.47476e-06 -5.38102e-07 -1 1.26085e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -2.34045e-07 1 6.34663e-07 0 1 -7.45939e-07 -5.47489e-07 1 9.98227e-08 7.83171e-07 1 -3.02087e-07 0 1 0 0 1 0 0 1 0 0 1 0 7.98407e-06 1 1.22322e-06 -2.43422e-06 1 -2.60871e-07 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 -2.251e-08 1 6.47947e-08 0 1 0 0 1 0 -5.79137e-08 1 2.50985e-07 0 1 -2.80537e-07 0 1 0 0 1 0 6.50395e-08 1 -2.78215e-08 0 1 0 0 1 0 -2.4109e-06 1 -4.65611e-07 3.4093e-06 1 4.59471e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -7.73309e-07 -2.33497e-07 -1 6.61444e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 -2.23339e-08 1 6.66564e-08 0 1 0 0 1 0 1.03777e-07 1 -2.00014e-08 3.24548e-08 1 6.55138e-09 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 3.67715e-07 -1 -4.0285e-07 4.47696e-08 -1 2.3835e-08 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1.05637e-06 -1 4.46709e-07 4.91813e-07 -1 -2.07974e-07 -1.2174e-06 -1 1.59942e-07 2.77357e-07 -1 -3.64393e-08 -1.91676e-06 -1 1.9148e-07 0 -1 0 0 -1 0 -1.2918e-06 -1 -2.51195e-07 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -2.33727e-07 1 6.49225e-07 0 1 -7.60822e-07 -5.47114e-07 1 9.96906e-08 7.76299e-07 1 -2.99686e-07 0 1 0 0 1 0 0 1 0 2.71695e-06 1 5.08754e-07 -4.48349e-06 1 -5.95636e-07 -1.22081e-06 1 -1.30959e-07 0 1 0 -1.07681e-06 1 1.10445e-07 8.5048e-07 1 -1.54967e-07 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 2.09381e-07 -1 -2.22111e-07 1.11974e-07 -1 2.34821e-08 -3.62064e-07 -1 -1.95365e-07 0 -1 0 -6.38479e-07 -1 2.63878e-07 8.06128e-07 -1 -3.33166e-07 -2.03767e-06 -1 2.64685e-07 2.97387e-07 -1 -3.86292e-08 -1.47922e-06 -1 1.46462e-07 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -5.97202e-07 1 1.13789e-07 7.65391e-07 1 -2.98e-07 0 1 0 0 1 0 0 1 0 1.54865e-06 1 2.82606e-07 -3.11887e-06 1 -4.29663e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 2.35154e-07 -1 -9.05804e-08 0 -1 0 0 -1 0 0 -1 0 -6.72199e-07 -1 7.81027e-08 0 -1 0 0 -1 0 -7.98257e-07 -1 -8.54956e-08 3.16726e-06 -1 5.91559e-07 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -5.40596e-07 1 1.27977e-06 0 1 -1.49349e-06 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 -2.60605e-06 -1.01654e-06 -1 2.17461e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -7.22414e-06 1 8.86221e-06 0 1 0 0 1 0 0 1 0 6.20976e-06 1 -9.43952e-06 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 2.44287e-07 -1 -2.69537e-07 -7.73457e-07 -1 1.35733e-07 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 6.65637e-06 -1 -1.16812e-06 -1.6047e-06 -1 1.72472e-07 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 -3.99313e-06 1 1.42402e-07 0 1 0 -1.45921e-05 1 -6.57067e-07 -9.51782e-07 1 -9.29375e-08 3.10469e-06 1 -4.41964e-07 0 1 0 7.54328e-07 1 4.2763e-07 -5.16178e-06 1 -5.53389e-07 3.25016e-06 1 3.48446e-07 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.694765 0.69473 -0.186152 -0.694765 0.69473 -0.186152 -0.694765 0.508578 -0.508577 -0.694765 0.508578 -0.508577 -0.694766 0.186154 -0.694728 -0.694761 0.186152 -0.694733 -0.694761 -0.186155 -0.694733 -0.694766 -0.186151 -0.694729 -0.694765 -0.508578 -0.508577 -0.694765 -0.508578 -0.508577 -0.694765 -0.69473 -0.186152 -0.694765 -0.69473 -0.186152 -0.698092 0.698056 -0.159327 -0.698092 0.698056 -0.159326 -0.698094 0.559796 -0.446422 -0.698093 0.559797 -0.446424 -0.698094 0.310666 -0.645098 -0.698092 0.310665 -0.645101 -0.698092 0 -0.716008 -0.698092 0 -0.716008 -0.698092 -0.310666 -0.6451 -0.698094 -0.310664 -0.645099 -0.698093 -0.559797 -0.446423 -0.698094 -0.559795 -0.446423 -0.698093 -0.698056 -0.159327 -0.698092 -0.698057 -0.159326 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965925 -0.258821 0 0.965925 -0.258821 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.998156 -0.0606972 -0.00367729 -0.985864 -0.167506 -0.0140567 -0.786441 -0.617506 1.80174e-05 -0.896537 -0.44297 -1.45042e-05 -0.973929 -0.226854 -0.0290118 -0.698726 -0.714801 0.00135493 -0.834572 -0.550896 -0.000841946 -0.542323 -0.840169 -0.00801381 -0.473853 -0.880567 0.000498638 -0.320151 -0.947367 -2.11194e-05 0 -1 -0.0216359 0.148041 -0.988744 -0.00085825 -0.0838608 -0.996477 -0.0228347 0.60207 -0.798117 -0.00527311 0.443184 -0.896415 9.47096e-07 0.298674 -0.954355 0.00890276 0.962694 -0.270447 -0.0142083 0.778631 -0.627321 6.46329e-06 0.834573 -0.550897 -5.97121e-06 0.473869 -0.880596 0 0.985871 -0.167507 -0.016956 0.999804 -0.0102479 -0.0155096 0.99958 -0.0244743 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965926 -0.25882 0 0.965926 -0.25882 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258816 -0.965927 0 0.258816 -0.965927 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258817 0 0.965926 -0.258817 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.999998 -0.00176367 -0.000194117 -0.985871 -0.167503 -0.00272324 -0.989565 -0.144058 0.000509336 -0.942437 -0.334384 -0.00414503 -0.834565 -0.550894 -0.00279105 -0.829002 -0.559239 0.00345409 -0.473866 -0.88059 -0.00387246 -0.512909 -0.858434 0.00184246 -0.144828 -0.989455 -0.00891833 0 -0.99996 -0.0015476 0.104278 -0.994547 0.000969137 0.295314 -0.9554 -0.0073854 0.473856 -0.880572 -0.00359391 0.507586 -0.861594 -6.61184e-06 0.646579 -0.762847 2.75137e-05 0.834572 -0.550899 -0.00770127 0.802428 -0.596699 -0.000718255 0.91478 -0.403952 0.00241438 0.985869 -0.167503 0 0.981816 -0.189833 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965927 -0.258816 0 0.965927 -0.258816 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.989574 -0.144025 -0.0123594 -0.985796 -0.167495 0.00195063 -0.944409 -0.328766 -0.017914 -0.83444 -0.550808 -0.0180618 -0.83454 -0.550651 0.0136142 -0.562459 -0.826713 -0.0428613 -0.473434 -0.879786 -0.00753748 -0.347582 -0.937619 -1.62767e-06 0.169333 -0.985559 -0.0317279 0.0410746 -0.998652 -0.0486747 0 -0.998815 4.05913e-06 -0.128866 -0.991662 2.09239e-06 -0.273053 -0.961999 -2.37299e-05 0.309057 -0.951044 -0.0392247 0.473504 -0.879918 -0.045416 0.46398 -0.884681 -0.0130489 0.834502 -0.55085 -8.62417e-06 0.687136 -0.726529 6.1402e-06 0.617028 -0.786941 0 0.999996 -0.00288727 -6.60987e-05 0.99996 -0.00888889 -0.00355865 0.985865 -0.167506 0.0472845 0.967569 -0.248141 -0.0663316 0.792785 -0.605882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.965927 -0.258816 0 0.965927 -0.258816 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1.90877e-05 -0.110305 -0.993898 0 -0.999968 -0.00796948 -0.000133459 -0.999715 -0.0238742 -0.00255221 -0.985868 -0.167507 0.00693166 -0.974183 -0.225653 -0.00942098 -0.834536 -0.550873 -0.00255426 -0.817494 -0.575932 -5.42462e-05 -0.473869 -0.880596 -0.0534189 -0.308796 -0.949627 0.00230885 -0.535632 -0.844448 -0.0411635 0.135637 -0.989903 7.9781e-06 0 -1 -5.30773e-06 0.328527 -0.944495 -0.0171776 0.473799 -0.880466 1.74095e-05 0.549388 -0.835568 -1.28967e-05 0.702984 -0.711206 -0.00966394 0.834534 -0.550871 -0.00275541 0.849526 -0.527539 0.00239139 0.985868 -0.167507 0 0.983873 -0.178868 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.258818 0 0.965926 -0.258818 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.000164634 -0.985871 -0.167506 -0.0101921 -0.962607 -0.270712 0 -0.993695 -0.112119 -0.000160232 -0.473869 -0.880596 -0.0241108 -0.334102 -0.942228 0.000104415 -0.550055 -0.835128 -0.000146853 -0.834573 -0.550897 -0.0289721 -0.713122 -0.700442 0.000198096 -0.857067 -0.515205 -0.00858178 0 -0.999963 -0.0133372 0.0441899 -0.998934 1.87386e-05 -0.123341 -0.992364 0.000185457 0.586229 -0.810146 -0.0114802 0.450771 -0.892566 -0.00885884 0.47385 -0.880561 -5.22281e-05 0.329096 -0.944297 5.49217e-05 0.167814 -0.985819 -7.57881e-05 0.708462 -0.705749 -0.00541123 0.834561 -0.550889 -0.0135291 0.796245 -0.604823 0.00016987 0.900016 -0.435857 -0.000243868 0.985871 -0.167506 0 0.9863 -0.164959 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.965926 -0.25882 0 0.965926 -0.25882 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.00183519 -0.977763 -0.209703 -3.70488e-05 -0.999925 -0.0122337 0 -0.999992 -0.00408096 0.00828145 -0.985837 -0.167501 -0.00861019 -0.834542 -0.550877 -0.00390496 -0.823821 -0.566837 0.00336461 -0.542324 -0.840163 -0.0144819 -0.473819 -0.880503 -2.445e-06 -0.306402 -0.951902 -9.00854e-07 -0.112916 -0.993605 -0.0186529 0 -0.999826 2.72661e-05 0.133474 -0.991052 -2.4004e-05 0.325628 -0.945498 -0.0165473 0.473804 -0.880475 3.08487e-05 0.546719 -0.837316 -1.05865e-05 0.699691 -0.714446 -0.00839239 0.834544 -0.550878 -0.00417948 0.843895 -0.536492 0.00368473 0.985864 -0.167506 0 0.982695 -0.185231 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965925 -0.258821 0 0.965925 -0.258821 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.989595 -0.143882 -0.0125422 -0.985793 -0.167494 0.00198997 -0.94442 -0.328735 -0.0181596 -0.834436 -0.550806 -0.0210589 -0.836383 -0.547741 -0.00229573 -0.712175 -0.701999 0.0137077 -0.562443 -0.826722 -0.0430585 -0.47343 -0.879779 -0.00779692 -0.348358 -0.937329 -3.10406e-06 0.169632 -0.985507 -0.031493 0.0416663 -0.998635 -0.048683 0 -0.998814 6.07799e-06 -0.12884 -0.991665 2.16824e-06 -0.273954 -0.961743 -2.23275e-05 0.309096 -0.951031 -0.0390571 0.473508 -0.879923 -0.0449379 0.464418 -0.884475 -0.013003 0.834503 -0.55085 -8.84492e-06 0.687204 -0.726465 7.41301e-06 0.617149 -0.786846 0 0.999996 -0.00292874 -6.06743e-05 0.999963 -0.00856606 -0.00348062 0.985865 -0.167506 0.0468574 0.967625 -0.248005 -0.0656189 0.792991 -0.60569 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.999048 -0.0436191 -3.58081e-07 0.999048 -0.0436194 5.87184e-08 0.999048 -0.0436193 2.17792e-07 0.999048 -0.0436194 -2.10183e-07 0.999048 -0.0436193 -4.75163e-06 0.999048 -0.0436201 5.34976e-06 0.999048 -0.0436188 2.57667e-07 0.999048 -0.0436194 1.99761e-06 0.999048 -0.0436195 -1.17131e-06 0.999048 -0.0436192 7.42727e-07 0.999048 -0.0436196 -1.07582e-07 0.999048 -0.0436192 0 0.999048 -0.0436196 0.00122592 0.0563383 0.998411 0.000164572 0.0180237 0.999838 3.90009e-05 0.00889987 0.99996 0 0.00295615 0.999996 0.00698144 0.367892 0.929842 -1.57535e-05 0.302431 0.953171 5.54636e-05 0.134131 0.990964 0.0334311 0.229806 0.972662 0.0110112 0.148013 0.988924 0.00898929 0.608172 0.793755 0.000424935 0.553593 0.832787 -0.00129488 0.392738 0.919649 0.0265534 0.458681 0.888204 0.0136259 0.400199 0.916327 0.00226314 0.760704 0.649095 2.20997e-07 0.736911 0.67599 -5.77041e-07 0.623084 0.782155 0.032103 0.684452 0.728351 0.0171641 0.639329 0.768741 0.0112125 0.811845 0.583766 0.0093814 0.808554 0.588348 -0.000300622 0.867806 0.496903 0.0145764 0.935807 0.352212 0.0116385 0.931363 0.363907 0.000535117 0.904841 0.425749 0 0.995871 0.0907776 0.0491439 0.99875 -0.0091456 0.0146178 0.996774 0.0789197 0.00101756 0.984167 0.177239 -0.00158221 0.961169 0.275955 0.00228973 -0.978815 0.204735 0.0134536 -0.992799 0.119035 0.00905191 -0.991404 0.13052 -0.00187669 -0.999997 0.00161506 0 -0.999762 -0.0218118 -0.00194109 -0.962335 0.271858 0.0103357 -0.92383 0.382663 0.0206817 -0.935497 0.352729 0.00116973 -0.739838 0.672784 0.00638589 -0.771205 0.636554 0.0127265 -0.793289 0.608712 0.00033577 -0.827333 0.561712 -0.000319403 -0.897231 0.441562 -0.00104125 -0.691664 0.722219 0.00923205 -0.608736 0.793319 0.00773706 -0.604536 0.79654 0.0114048 -0.382659 0.923819 -0.000861428 -0.449587 0.893236 0.00039399 -0.528712 0.848801 0.000247815 -0.0210245 0.999779 0 -0.00905726 0.999959 0.000972126 -0.0471667 0.998887 0.00793287 -0.130286 0.991445 0.00799103 -0.130522 0.991413 -0.000182835 -0.229221 0.973374 0.000381378 -0.326244 0.945286 -1.97583e-06 -0.999048 -0.0436198 5.80283e-07 -0.999048 -0.0436191 -4.5606e-07 -0.999048 -0.0436199 0 -0.999048 -0.0436191 0 -0.999048 -0.0436195 -4.47927e-07 -0.999048 -0.0436194 -1.4753e-06 -0.999048 -0.0436192 -8.01211e-07 -0.999048 -0.0436193 -6.85594e-07 -0.999048 -0.0436193 1.02481e-06 -0.999048 -0.0436194 -1.65368e-05 -0.999048 -0.0436213 3.81725e-06 -0.999048 -0.043619 0 -0.0279141 -0.99961 0.00558079 -0.0862034 -0.996262 0.0289285 -0.470891 -0.881717 0.0120303 -0.442257 -0.896808 0.000781942 -0.547557 -0.836768 0.0101859 -0.398172 -0.917254 -1.63001e-06 -0.343857 -0.939022 4.05079e-06 -0.152123 -0.988362 0.0655745 -0.265678 -0.961829 0.0256035 -0.182257 -0.982918 0.00595124 -0.640215 -0.768173 -1.56939e-08 -0.592838 -0.805322 2.58694e-07 -0.56677 -0.823876 -2.09595e-07 -0.797874 -0.602824 -2.25905e-07 -0.78887 -0.61456 0.00482237 -0.691505 -0.722356 0.0450933 -0.733722 -0.677951 0.0190404 -0.677776 -0.735022 2.49836e-07 -0.942551 -0.334062 -1.84765e-07 -0.917101 -0.398656 0.0273925 -0.876398 -0.480808 0.03211 -0.881288 -0.471487 0.00261862 -0.841592 -0.540108 0 -0.997387 -0.0722488 0.0205713 -0.980578 -0.195049 0.0348657 -0.983885 -0.175368 0.00238309 -0.959239 -0.282586 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -3.42527e-06 -2.18721e-06 -1 0 0 -1 0 0 -1 1.41405e-06 6.83639e-07 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.0115722 0.972754 -0.23155 0.0311352 0.98031 -0.194995 0.00984994 0.991187 -0.132103 0 0.997448 -0.0713978 0.000840124 0.811686 -0.584093 0.00890385 0.853752 -0.520604 0.0359233 0.885175 -0.463869 0.0448443 0.893885 -0.446048 0.024266 0.876469 -0.480847 -5.81066e-07 0.923065 -0.384644 1.49182e-07 0.947637 -0.31935 2.17299e-07 0.579395 -0.815047 0.00223186 0.639752 -0.768578 0.0286344 0.69881 -0.714734 0.0244434 0.691306 -0.722148 -6.07095e-07 0.754509 -0.65629 -1.23144e-07 0.798232 -0.60235 -9.41669e-07 0.358055 -0.933701 0.0170195 0.424864 -0.905097 0.0226785 0.442175 -0.896642 0.00242895 0.5018 -0.864981 2.36315e-07 0.567263 -0.823537 0 0.0286688 -0.999589 0.00946142 0.124791 -0.992138 0.0191198 0.152095 -0.988181 0.00174724 0.239534 -0.970887 1.17816e-07 0.292461 -0.956277 -0.985522 -0.0294314 0.166971 -0.988224 -0.00795345 0.152808 -0.992055 -0.00801801 0.12555 -0.998561 -0.00509904 0.0533804 -0.980926 -0.0276525 0.192404 -0.933156 -0.0281686 0.358365 -0.935113 -0.0337674 0.352738 -0.92821 -0.00792574 0.371972 -0.934719 -0.0150688 0.355068 -0.927577 0 0.373633 -0.927578 -0.000114818 0.373629 -0.927586 -0.00116786 0.373609 -0.950827 -0.00152282 0.30972 -0.950277 -0.00314501 0.31139 -0.951212 -0.00193506 0.308531 -0.950854 -0.00148751 0.309637 -0.950129 -0.00195721 0.311851 -0.947622 -0.00195234 0.319388 -0.947556 -0.00216352 0.319584 -0.943509 -0.00213135 0.33134 -0.943348 -0.002377 0.331797 -0.930175 -0.00232254 0.36711 -0.924067 0.0293936 0.381099 -0.927427 0.00576575 0.37396 -0.953823 -0.0108302 0.300174 -0.954322 -0.0117065 0.29855 -0.954158 -0.0123304 0.299049 -0.952226 -0.0120493 0.305158 -0.951847 -0.0127662 0.306307 -0.94915 -0.0127323 0.314567 -0.948689 -0.0141557 0.315894 -0.945632 -0.0140835 0.324934 -0.944779 -0.0153663 0.327349 -0.93062 -0.0151189 0.365674 -0.928234 0.0135991 0.371749 -0.92861 -0.00349173 0.37104 -0.957565 -0.0553015 0.282861 -0.932031 -0.0344975 0.360734 -0.955275 -0.0510679 0.291275 -0.938723 -0.0502432 0.34099 -0.94656 -0.0613496 0.31664 -0.952517 -0.0691119 0.296537 -0.956839 -0.0582058 0.284729 -0.956513 -0.0590674 0.285645 -0.935479 -0.04391 0.350643 -0.936843 -0.0478612 0.346461 -0.938445 -0.0549704 0.341026 -0.957934 -0.0231724 0.286052 -0.9586 -0.02404 0.283739 -0.958284 -0.025691 0.28466 -0.956065 -0.025467 0.292048 -0.955342 -0.0273346 0.294237 -0.953069 -0.0272738 0.301523 -0.952118 -0.0301619 0.304238 -0.950238 -0.030078 0.310071 -0.948486 -0.0327091 0.315125 -0.935416 -0.0322497 0.352076 -0.935902 -0.0105464 0.352102 -0.934749 -0.0226697 0.354584 -0.96322 -0.0345557 0.266482 -0.964009 -0.0352476 0.263521 -0.963557 -0.0378356 0.264814 -0.961628 -0.0377157 0.271751 -0.960647 -0.0406375 0.274782 -0.959064 -0.0405752 0.280269 -0.957716 -0.0447238 0.284219 -0.956847 -0.0446687 0.287139 -0.954473 -0.0483374 0.294356 -0.951203 -0.0481715 0.304782 -0.969159 -0.0419939 0.242832 -0.967586 -0.0559587 0.246264 -0.970004 -0.0422597 0.239388 -0.971345 -0.058745 0.230299 -0.96797 -0.0533438 0.245333 -0.968715 -0.0741171 0.236851 -0.974951 -0.0588685 0.214487 -0.968136 -0.0583185 0.243541 -0.968093 -0.0622821 0.242726 -0.968003 -0.0645028 0.242508 -0.969612 -0.0584722 0.237556 -0.969159 -0.0419952 0.242833 -0.967017 -0.0488911 0.249977 -0.966589 -0.0488711 0.251631 -0.96463 -0.0522719 0.258372 -0.965007 -0.0532367 0.256761 -0.961636 -0.0559584 0.268559 -0.963338 -0.0580061 0.261945 -0.956771 -0.0594133 0.284709 -0.956268 -0.0730824 0.283215 -0.95613 -0.0671936 0.285131 -0.968272 -0.060167 0.242547 -0.967561 -0.0631406 0.244622 -0.959733 -0.0854879 0.267591 -0.954766 -0.0547327 0.292279 -0.955747 -0.0633483 0.287289 -0.972221 -0.0543737 0.227662 -0.972606 -0.054214 0.22605 -0.971867 -0.05234 0.229641 -0.973718 -0.0495168 0.22231 -0.974588 -0.0493782 0.218493 -0.976647 -0.0363659 0.211749 -0.978033 -0.0418915 0.204197 -0.980368 -0.0305498 0.194794 -0.984302 -0.0357457 0.172835 -0.983979 -0.0385408 0.174071 -0.978042 -0.0426506 0.203997 -0.978695 -0.0429895 0.200767 -0.976569 -0.0532743 0.208504 -0.975547 -0.0569843 0.212277 -0.989995 -0.0104495 0.140713 -0.994218 -0.0304588 0.102972 -0.992613 0.00149858 0.121314 -0.99574 -0.00460752 0.0920922 -0.998981 -0.00518952 0.0448304 -0.998915 -0.0077988 0.0459086 -0.999784 9.65679e-10 0.0207978 -0.986297 -0.0203651 0.163718 -0.985262 -0.0189412 0.17 -0.985724 -0.0205835 0.167105 -0.985904 -0.0195125 0.166168 -0.986277 -0.0175825 0.164158 -0.984783 -0.0178414 0.17287 -0.983829 -0.0151739 0.178468 -0.984345 -0.0173476 0.175399 -0.982988 -0.0159089 0.182979 -0.983665 -0.017577 0.179146 -0.982348 -0.0165227 0.186332 -0.982744 -0.0177906 0.184112 -0.981782 -0.0210889 0.188837 -0.98121 -0.0219296 0.191691 -0.980618 -0.0193892 0.19497 -0.980714 -0.0271835 0.193549 -0.980408 -0.0354018 0.193769 -0.979773 -0.0276723 0.198192 -0.979822 -0.0388402 0.196065 -0.978117 -0.037989 0.204559 -0.978501 -0.0417951 0.201961 -0.978065 -0.0542377 0.201116 -0.977691 -0.0496091 0.204106 -0.9753 -0.0684273 0.210016 -0.957211 -0.14078 0.252839 -0.973806 -0.0549693 0.220635 -0.974312 -0.0607463 0.216854 -0.973745 -0.0866167 0.210521 -0.973608 -0.0666138 0.218291 -0.971896 -0.105275 0.210562 -0.969908 -0.0791457 0.23025 -0.969255 -0.130082 0.208863 -0.953304 -0.113851 0.27973 -0.95576 -0.162306 0.245314 -0.956085 -0.154827 0.248857 -0.922877 -0.128581 0.362995 -0.929371 -0.187799 0.317808 -0.931722 -0.173696 0.318943 -0.884644 -0.115936 0.451623 -0.9025 -0.17541 0.39335 -0.900843 -0.185608 0.392468 -0.85642 -0.0551505 0.513325 -0.863184 -0.0906604 0.496684 -0.865359 -0.0842285 0.494024 -0.875261 -0.12195 0.468024 -0.878366 -0.143036 0.456086 -0.871946 -0.0124386 0.489444 -0.866806 -0.0108232 0.498528 -0.848176 0.00367737 0.529702 -0.854375 0.0320535 0.518668 -0.84395 0.00262568 0.536415 -0.826521 0.00122511 0.562904 -0.82871 -0.00765164 0.559626 -0.835767 -0.00535848 0.549058 -0.837983 -0.00372947 0.545683 -0.826266 0.000178904 0.563281 -0.826262 0.000176485 0.563286 -0.824434 -0.000397163 0.565958 -0.906311 -0.0056811 0.422574 -0.928561 -0.00436423 0.371153 -0.932315 -0.0101707 0.361505 -0.898535 0.0028252 0.438892 -0.894344 0.00898867 0.447289 -0.890907 0.0164584 0.453887 -0.966661 -0.0838582 0.241937 -0.97056 -0.0838366 0.225799 -0.971486 -0.0845813 0.221499 -0.975521 -0.0627861 0.210754 -0.976574 -0.0590675 0.206916 -0.977796 -0.0566527 0.201755 -0.979086 -0.0546515 0.19597 -0.981317 -0.0535349 0.184799 -0.978277 -0.0533985 0.200306 -0.98067 -0.0416481 0.191185 -0.984606 -0.0225398 0.173329 -0.996509 -0.00152496 0.0834679 -0.994583 -0.00710077 0.103703 -0.994446 -0.00693274 0.105022 -0.990012 -0.00614453 0.140849 -0.993237 -0.0170344 0.114848 -0.985154 -0.0168426 0.170845 -0.98533 -0.0420647 0.165396 -0.934189 -0.0253766 0.355874 -0.933446 -0.0287795 0.35756 -0.898145 -0.0279402 0.438812 -0.898457 -0.0018213 0.439057 -0.877196 -0.0125066 0.47997 -0.85315 -0.0310678 0.52074 -0.850891 -0.0416672 0.523687 -0.905828 -0.0437142 0.421383 -0.903353 -0.0874453 0.419888 -0.915594 -0.0667228 0.396529 -0.935402 -0.121876 0.331919 -0.938842 -0.0837986 0.333996 -0.952498 -0.132236 0.274338 -0.957868 -0.0733981 0.277671 -0.967724 -0.115271 0.224103 -0.970815 -0.0799955 0.226096 -0.972403 -0.086408 0.216719 -0.958309 0.023323 0.284782 -0.963677 0.0346553 0.264811 -0.978139 0.0154676 0.207378 -0.994457 0.00431536 0.10506 -0.994457 0.00310862 0.105096 -0.826262 -0.000614388 0.563286 -0.824412 0.0072995 0.565943 -0.844435 9.25316e-05 0.535658 -0.836727 0.00669099 0.54758 -0.837534 0.00646605 0.546348 -0.840068 0.0042601 0.542464 -0.859446 0.00533554 0.511199 -0.8623 0.0980484 0.496816 -0.855704 0.0453825 0.515471 -0.878218 0.115465 0.464113 -0.902317 0.16797 0.397003 -0.901084 0.184035 0.392657 -0.936484 0.130609 0.325483 -0.930128 0.183067 0.318353 -0.957025 0.142072 0.252821 -0.956047 0.155259 0.248736 -0.956655 0.11448 0.267779 -0.937721 0.158628 0.309057 -0.93178 0.172991 0.319154 -0.975603 0.0614057 0.210779 -0.976063 0.0602389 0.208977 -0.972883 0.0777635 0.217833 -0.972756 0.0704749 0.22086 -0.971494 0.0980291 0.215846 -0.971878 0.0829556 0.220392 -0.963906 0.106668 0.243942 -0.959964 0.125869 0.250253 -0.976796 0.0565766 0.206562 -0.977709 0.0506819 0.203755 -0.976661 0.0372379 0.211533 -0.980157 0.0435354 0.193383 -0.979256 0.0207526 0.201561 -0.979967 0.0242118 0.197685 -0.981083 0.0249259 0.191974 -0.981976 0.0230337 0.187597 -0.981455 0.0216208 0.19047 -0.98287 0.0187537 0.183343 -0.982314 0.016529 0.186511 -0.983977 0.0174304 0.17744 -0.983166 0.0141103 0.182169 -0.987183 0.0287375 0.156985 -0.983621 0.0156265 0.179572 -0.984435 0.017063 0.174918 -0.984745 0.0173963 0.173131 -0.985318 0.0190347 0.169668 -0.985529 0.0195068 0.168379 -0.986168 0.0224891 0.164218 -0.98843 0.0444311 0.145021 -0.985901 0.00800316 0.167141 -0.991975 0.00810415 0.126177 -0.999218 0 0.0395377 -0.998996 0.00310912 0.0446966 -0.99821 -0.056149 0.0205792 -0.997785 0.00571306 0.0662742 -0.989817 0.0155855 0.141493 -0.99049 0.0206114 0.136034 -0.994821 8.41794e-05 0.101641 -0.978602 0.0426214 0.201299 -0.981688 0.017586 0.189683 -0.983652 0.0228667 0.178624 -0.985625 0.0251031 0.167075 -0.979205 0.0421568 0.198444 -0.984228 0.0343914 0.17353 -0.984568 0.0170722 0.174168 -0.989797 0.0171951 0.14144 -0.991745 0.00650781 0.12806 -0.995529 0.00740227 0.0941636 -0.955859 0.0663714 0.28623 -0.955647 0.0633428 0.287621 -0.957099 0.0857554 0.276782 -0.966661 0.0655429 0.247527 -0.967258 0.063833 0.245638 -0.96762 0.0656186 0.243732 -0.96783 0.0622467 0.243782 -0.967861 0.0602762 0.244157 -0.967604 0.0744661 0.241243 -0.97422 0.0608717 0.217234 -0.974864 0.0592068 0.214791 -0.978475 0.0467761 0.200996 -0.974302 0.0408653 0.221509 -0.977393 0.0430578 0.207001 -0.967165 0.0695256 0.244456 -0.968626 0.058488 0.241544 -0.97074 0.0590608 0.232755 -0.968603 0.0530181 0.242895 -0.97241 0.054911 0.226724 -0.977862 0.0249592 0.207759 -0.97783 0.0231478 0.208115 -0.974064 0.0497435 0.220737 -0.97148 0.0496225 0.231873 -0.937663 0.0546632 0.343221 -0.9391 0.0720302 0.33601 -0.936186 0.0469868 0.348349 -0.934894 0.0427941 0.352338 -0.931942 0.0337896 0.36103 -0.958978 0.0525532 0.278568 -0.956866 0.0578384 0.284715 -0.956458 0.0588569 0.285875 -0.957387 0.0557855 0.28337 -0.964207 0.0484709 0.260682 -0.965286 0.0537531 0.255603 -0.96072 0.0517498 0.272652 -0.963128 0.0577245 0.262777 -0.957255 0.0564038 0.283692 -0.955502 0.0782113 0.284429 -0.955906 0.0716802 0.28479 -0.9688 0.0417445 0.244303 -0.966636 0.048584 0.251506 -0.968793 0.0416597 0.244347 -0.967178 0.0559659 0.247861 -0.969635 0.0420571 0.240915 -0.962879 0.0340093 0.267781 -0.963219 0.0372705 0.266121 -0.960419 0.0370899 0.276079 -0.961161 0.0400101 0.273073 -0.957287 0.0398599 0.286378 -0.958277 0.0440188 0.282432 -0.953546 0.0437783 0.298049 -0.955583 0.0476239 0.290849 -0.950809 0.0474029 0.306128 -0.95485 0.0502518 0.292807 -0.938027 0.0494487 0.343016 -0.950969 0.0694083 0.301397 -0.957656 0.0224313 0.287039 -0.958006 0.0248906 0.285667 -0.955132 0.0245947 0.295156 -0.955726 0.0264142 0.293069 -0.951762 0.0263118 0.305707 -0.934401 0.0337077 0.354624 -0.927561 -0.00730889 0.373599 -0.927418 0.0122013 0.373827 -0.929244 0.0040211 0.369446 -0.934368 0.0150304 0.355992 -0.934838 0.0218089 0.354403 -0.934166 0.0246473 0.355987 -0.95254 0.0291872 0.30301 -0.937452 0.028691 0.346931 -0.937028 -0.0237672 0.348446 -0.936214 0.0108146 0.351265 -0.95412 0.0109965 0.299223 -0.954302 0.0103224 0.298667 -0.928098 0.00720946 0.372265 -0.928655 0.00269955 0.370934 -0.928574 0.00666717 0.371088 -0.942089 0.0143564 0.335055 -0.945186 0.0143975 0.326214 -0.944422 0.0131776 0.328471 -0.948893 0.0132345 0.31532 -0.948509 0.0119422 0.316524 -0.952048 0.0119839 0.305715 -0.951686 0.0112305 0.306869 -0.953618 0.0115155 0.300798 -0.951076 0.00157305 0.308953 -0.951167 0.00146934 0.308675 -0.927845 -0.00454125 0.372939 -0.94037 0.0020348 0.340149 -0.943429 0.00182718 0.33157 -0.943492 0.00192049 0.331391 -0.947599 0.00156474 0.319458 -0.947609 0.00159644 0.319428 -0.9502 0.00160058 0.311638 -0.950092 0.00151962 0.311965 -0.950716 0.00163858 0.310057 -0.867053 0.0111965 0.49809 -0.872187 0.0125263 0.489013 -0.898036 0.0122709 0.43975 -0.906309 -0.00608405 0.422573 -0.904579 0.00608047 0.426262 -0.894424 -0.00800198 0.447148 -0.886979 -0.0237322 0.4612 -0.97832 0.0556461 0.199483 -0.97987 0.0546579 0.192006 -0.974269 0.0963116 0.203774 -0.972498 0.0866366 0.216197 -0.971465 0.0848334 0.221493 -0.97071 0.0839784 0.2251 -0.969008 0.0838819 0.232353 -0.985554 0.0257236 0.167395 -0.985453 0.0321295 0.166886 -0.985538 0.0217801 0.16805 -0.981851 0.0363929 0.186128 -0.978293 0.051225 0.200798 -0.987008 0.0555519 0.150763 -0.981951 0.0534947 0.181411 -0.850579 -0.0125533 0.525697 -0.848659 -0.00760231 0.528886 -0.853271 0.0418602 0.519784 -0.897297 0.043513 0.439278 -0.905944 0.0282955 0.422451 -0.932911 0.0289345 0.358943 -0.933673 0.026637 0.357135 -0.976954 0.0585575 0.205262 -0.971264 0.072339 0.226745 -0.971114 0.074696 0.226625 -0.954382 0.114252 0.275865 -0.956905 0.0857398 0.277457 -0.93425 0.130331 0.331949 -0.939625 0.0686794 0.335242 -0.884223 0.116182 0.452384 -0.902998 0.0876338 0.420612 -0.879022 0.0856062 0.469034 -0.84714 0.130924 0.514988 0 0 -1 0 0 -1 0 0.108822 -0.994061 -0.0111164 0.175786 -0.984366 0 0.989094 -0.147284 -0.00642724 0.984406 -0.175792 -0.0157438 0.539071 -0.842113 0 0.414014 -0.910271 0 0.281882 -0.959449 0 0.947799 -0.318869 0 0.90907 -0.416644 -0.0160322 0.842109 -0.539069 0.000303713 0.797788 -0.602938 -0.000309948 0.598319 -0.801258 0 1 0 0 1 0 0 1 0 0 0.0689137 0.997623 -0.0182443 0.175768 0.984263 8.813e-05 0.984427 0.175796 -0.0381371 0.953743 0.298194 -0.0288522 0.964839 0.261253 -0.00913842 0.984785 0.173536 0 0.99898 0.0451647 -0.010319 0.205219 0.978662 0.000400709 0.312496 0.949919 -0.00208734 0.539137 0.842215 -0.0549815 0.446931 0.892877 -0.00817582 0.593156 0.805046 6.42703e-05 0.684643 0.728878 -0.000397555 0.842217 0.539138 -0.0299547 0.804564 0.59311 -4.02424e-05 0.907219 0.420659 0 -0.136027 0.990705 -0.013316 -0.175781 0.984339 -0.00159284 -0.29255 0.956249 0.0037563 -0.41738 0.908724 -0.026233 -0.538953 0.841928 -0.0127594 -0.579363 0.814969 -0.00153751 -0.913066 0.407808 -0.00684371 -0.887166 0.4614 -0.0199177 -0.843218 0.537202 -0.0205274 -0.84204 0.539024 -0.000209357 -0.757978 0.65228 0.000140923 -0.672125 0.740438 0.00266486 -0.959016 0.28334 -0.0125353 -0.984349 0.175782 0 -0.995844 0.0910735 0 -1 0 0 -1 0 0 -1 0 0 -0.108175 -0.994132 -0.0111564 -0.175786 -0.984365 0 -0.989094 -0.147285 -0.00642724 -0.984406 -0.175792 -0.0163206 -0.842105 -0.539067 0 -0.907742 -0.419528 0 -0.947798 -0.318873 0 -0.281259 -0.959632 0 -0.412655 -0.910888 -0.0155849 -0.539073 -0.842115 -0.000819279 -0.595249 -0.803541 0.000776606 -0.794454 -0.607324 0 -0.993712 -0.111965 -0.00706457 -0.965902 -0.258813 0 -0.930874 -0.365341 0 -0.826238 -0.563321 -0.00588166 -0.707094 -0.707095 0 -0.652287 -0.757972 0 -0.46728 -0.88411 -0.00352264 -0.258819 -0.965919 0 -0.222521 -0.974928 0 0.222521 -0.974928 -0.00352263 0.258819 -0.965919 0 0.467279 -0.88411 0 0.652288 -0.757972 -0.00588165 0.707094 -0.707095 0 0.826238 -0.563321 0 0.930874 -0.365341 -0.00706455 0.965902 -0.258813 0 0.993712 -0.111965 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.918138 -0.367687 -0.147749 -0.887121 -0.0103604 -0.461421 -0.917339 -0.00197286 -0.398103 -0.924109 -0.0173542 -0.381735 -0.470223 0.863419 -0.182748 -0.939705 -0.0558468 -0.337396 -0.948129 -0.0705233 -0.309965 -0.963039 -0.030526 -0.267628 -0.99784 -0.00515607 -0.0654913 -0.999571 0.0150227 -0.0251322 -0.97828 -0.0501038 -0.201143 -0.982587 -0.185582 -0.00908416 -0.961414 -0.265091 -0.0735516 -0.96793 -0.243068 0.0634802 -0.966424 -0.252166 0.0493768 -0.964591 -0.26122 0.0364376 -0.954188 -0.298928 0.0128999 -0.928066 -0.370612 0.036603 -0.981425 -0.183857 -0.0547903 -0.982726 -0.171409 -0.0697696 -0.984517 -0.164749 -0.0598701 -0.988072 -0.140518 -0.062998 -0.987276 -0.142043 -0.0714776 -0.98853 -0.125904 -0.0834077 -0.988385 -0.105279 -0.109596 -0.987127 -0.113507 -0.112681 -0.988045 -0.105325 -0.11258 -0.987528 -0.0929739 -0.127059 -0.987098 -0.0923625 -0.130796 -0.985949 -0.0768981 -0.148292 -0.967061 -0.144194 -0.209766 -0.967802 -0.140037 -0.209164 -0.984054 -0.0739189 -0.16178 -0.986176 -0.10071 -0.131586 -0.981948 -0.0853851 -0.168782 -0.980274 -0.0775393 -0.181798 -0.980626 -0.0776572 -0.179838 -0.971758 -0.0585131 -0.228612 -0.980664 -0.0533779 -0.188279 -0.983081 -0.0119001 -0.182783 -0.984432 -0.0193698 -0.174697 -0.986365 -0.0173734 -0.163656 -0.988297 -0.0174397 -0.151541 -0.995483 -0.00251067 -0.094903 -0.995076 -0.00592436 -0.0989341 -0.996375 -0.0270249 -0.0806599 -0.995571 -0.0167113 -0.0925174 -0.995121 -0.0130357 -0.0977978 -0.994776 -0.010782 -0.101507 -0.994255 -0.00804026 -0.106732 -0.989868 -0.0201837 -0.140552 -0.987756 -0.0149901 -0.155284 -0.992853 -0.00555283 -0.119218 -0.994194 -0.00777684 -0.107318 -0.995159 -0.0039869 -0.0981951 -0.995841 0.000100282 -0.0911047 -0.996186 0.00794525 -0.0868929 -0.996152 0.00450549 -0.0875277 -0.997155 -0.0016147 -0.0753565 -0.997478 -0.00104172 -0.0709735 -0.997543 0.0293006 -0.0636329 -0.998098 0.00115317 -0.0616367 -0.99904 -0.0056583 -0.0434488 -0.998919 0.0113083 -0.0450807 -0.999067 0.0049267 -0.0429132 -0.999379 -0.0239337 -0.0258753 -0.999353 0.00568471 -0.0355172 -0.999278 -0.0353356 -0.0139475 -0.998237 -0.0590894 -0.00567832 -0.999521 -0.00327636 -0.0307588 -0.999752 -5.00478e-10 -0.0222727 -0.999744 0.000631921 -0.0226026 -0.999689 0.00473094 -0.0244724 -0.999193 -0.00704466 -0.0395386 -0.998724 -0.0120749 -0.049032 -0.999317 -0.00408836 -0.0367325 -0.99812 -0.00236029 -0.0612401 -0.997811 -0.00222656 -0.0660961 -0.987788 -0.0132403 -0.155239 -0.988781 -0.0190993 -0.148145 -0.995106 -0.00166261 -0.0988045 -0.993579 0.0152598 -0.112104 -0.995893 0.000358569 -0.0905407 -0.964336 -0.0768872 -0.253268 -0.967129 -0.0752443 -0.242897 -0.978201 -0.0515301 -0.201165 -0.976168 -0.040049 -0.21329 -0.982882 -0.0321487 -0.181412 -0.959508 -0.098572 -0.263873 -0.957369 -0.101473 -0.27046 -0.927672 -0.108241 -0.357363 -0.927578 -0.124637 -0.352228 -0.942731 -0.114279 -0.313365 -0.942842 -0.114173 -0.313072 -0.950187 -0.107146 -0.292686 -0.948666 -0.103655 -0.298812 -0.95015 -0.104128 -0.293891 -0.950523 -0.103104 -0.293045 -0.948804 -0.103535 -0.298416 -0.948353 -0.10351 -0.299852 -0.9497 -0.105633 -0.294807 -0.950549 -0.101244 -0.29361 -0.949836 -0.108852 -0.293193 -0.955243 -0.103852 -0.276993 -0.956132 -0.102929 -0.274259 -0.939732 -0.0581297 -0.336936 -0.94968 -0.0900548 -0.299996 -0.959546 -0.0888398 -0.267167 -0.959174 -0.0157077 -0.282381 -0.962593 -0.050723 -0.266163 -0.906156 -0.123115 -0.404628 -0.908228 -0.101973 -0.405861 -0.907939 -0.0979318 -0.4075 -0.925826 -0.116706 -0.35948 -0.927406 -0.111196 -0.357146 -0.927652 -0.109901 -0.356909 -0.947852 -0.0697199 -0.310992 -0.947962 -0.0716595 -0.310214 -0.941893 -0.0835308 -0.325363 -0.942284 -0.0858034 -0.323633 -0.935897 -0.0852487 -0.341803 -0.937673 -0.0927082 -0.334924 -0.929863 -0.0917631 -0.356279 -0.933764 -0.0988133 -0.343979 -0.92456 -0.0978581 -0.368255 -0.903263 -0.0844835 -0.420687 -0.904585 -0.0873008 -0.417258 -0.907274 -0.0956882 -0.409508 -0.899074 -0.0877217 -0.428917 -0.897216 -0.0750977 -0.435159 -0.896406 -0.0729815 -0.437184 -0.90391 -0.0848512 -0.419222 -0.915168 -0.0737482 -0.396269 -0.939156 -0.0547433 -0.3391 -0.939352 -0.0583359 -0.337956 -0.931206 -0.0663359 -0.358407 -0.931741 -0.0708007 -0.356154 -0.923174 -0.0701767 -0.377921 -0.924946 -0.0763907 -0.372343 -0.916646 -0.0755339 -0.392499 -0.9137 -0.0709689 -0.400145 -0.910901 -0.0780192 -0.405181 -0.910675 -0.0783572 -0.405625 -0.931223 -0.036871 -0.36258 -0.898882 -0.147492 -0.412623 -0.900842 -0.0332871 -0.432868 -0.921933 -0.053737 -0.383604 -0.92358 -0.0692274 -0.377103 -0.931366 -0.0357004 -0.362329 -0.894521 -0.0371872 -0.445476 -0.894563 -0.0440947 -0.444761 -0.896949 -0.0399198 -0.440328 -0.899445 -0.036901 -0.435474 -0.89573 -0.0423591 -0.442577 -0.896027 -0.0402218 -0.442174 -0.899488 -0.0174292 -0.436597 -0.900593 0.0512128 -0.431636 -0.913646 -0.0688114 -0.400644 -0.918493 0.10027 -0.382514 -0.92402 -0.0162243 -0.382001 -0.924134 -0.0171582 -0.381682 -0.915924 -0.0231663 -0.400683 -0.881432 -0.000132214 -0.472312 -0.858375 0.208941 -0.468547 -0.885125 -0.000428036 -0.465353 -0.890743 -0.0110679 -0.454372 -0.89074 -0.0110714 -0.454379 -0.891195 -0.0114942 -0.453475 -0.917707 -0.0319197 -0.395973 -0.913641 -0.022449 -0.405901 -0.907373 -0.0223007 -0.419734 -0.908121 -0.0243073 -0.418001 -0.901039 -0.0240669 -0.43307 -0.902432 -0.0258955 -0.430054 -0.898011 -0.0257709 -0.439217 -0.886737 -0.0201173 -0.461837 -0.888341 -0.0142979 -0.458962 -0.888973 -0.0134271 -0.457764 -0.917047 -0.00127365 -0.398777 -0.917251 -0.00254629 -0.398301 -0.911566 -0.003917 -0.411135 -0.911409 -0.00355271 -0.411487 -0.905384 -0.00353011 -0.42458 -0.905522 -0.00387829 -0.424281 -0.898872 -0.00384838 -0.438194 -0.899137 -0.00417759 -0.437647 -0.894492 -0.00415985 -0.447065 -0.881803 0.00177028 -0.471614 -0.881211 0.00390302 -0.472707 -0.881427 0 -0.47232 -0.871596 -0.0522702 -0.48743 -0.870901 -0.0513744 -0.488766 -0.86649 -0.0494199 -0.496743 -0.85542 -0.0473087 -0.51577 -0.869993 -0.0377006 -0.49162 -0.87685 -0.0295679 -0.479854 -0.80904 -0.106321 -0.578058 -0.856615 -0.122836 -0.50112 -0.847175 -0.162137 -0.50597 -0.861382 -0.147811 -0.485977 -0.867996 -0.171133 -0.466151 -0.869495 -0.182521 -0.458982 -0.982875 -0.0633604 -0.173039 -0.878662 -0.235387 -0.415386 -0.873853 -0.269846 -0.404429 -0.876899 -0.270981 -0.39701 -0.911788 -0.296572 -0.284058 -0.908954 -0.354616 -0.219203 -0.912174 -0.339634 -0.229322 -0.908581 -0.2953 -0.29543 -0.958013 -0.208767 -0.196537 -0.958649 -0.207109 -0.195185 -0.961609 -0.197388 -0.190647 -0.958901 -0.220733 -0.178285 -0.954143 -0.260104 -0.148181 -0.98191 -0.105789 -0.157039 -0.981804 -0.10566 -0.157785 -0.984235 -0.103738 -0.143249 -0.985353 -0.0795687 -0.150822 -0.979895 -0.136251 -0.145743 -0.981784 -0.111159 -0.154088 -0.956965 -0.260695 -0.127497 -0.962766 -0.254697 -0.0906178 -0.930565 -0.361717 -0.0566502 -0.925118 -0.377139 0.0438583 -0.908891 -0.415957 0.0299382 -0.965359 -0.240558 -0.10106 -0.96475 -0.245544 -0.0946844 -0.962242 -0.265219 -0.0612338 -0.977593 -0.205762 -0.0444292 -0.979399 -0.196746 -0.0454907 -0.961811 -0.176007 -0.209621 -0.94722 -0.201837 -0.249071 -0.925577 -0.243297 -0.290025 -0.95061 -0.252395 -0.18066 -0.924078 -0.305093 -0.230213 -0.942789 -0.31257 -0.115972 -0.869468 -0.48927 -0.0681181 -0.873317 -0.159639 -0.460252 -0.901857 -0.219592 -0.372067 -0.853849 -0.206854 -0.477653 -0.869833 -0.213642 -0.444688 -0.915985 -0.142443 -0.375076 -0.937128 -0.194085 -0.290038 -0.893224 -0.183776 -0.410339 -0.919064 -0.249815 -0.304818 -0.892624 -0.241072 -0.380929 -0.911314 -0.271646 -0.309378 -0.876031 -0.311211 -0.368399 -0.89711 -0.322668 -0.301794 -0.979972 -0.0533958 -0.191844 -0.97382 -0.0292344 -0.225432 -0.978286 -0.032982 -0.20462 -0.976463 -0.0661325 -0.205297 -0.971219 -0.0500091 -0.23288 -0.969184 -0.0794722 -0.233166 -0.962465 -0.077272 -0.260174 -0.965542 -0.154185 -0.209655 -0.963982 -0.173031 -0.201987 -0.958601 -0.171474 -0.227333 -0.942707 -0.125263 -0.309213 -0.965445 -0.129235 -0.226305 -0.952074 -0.0935334 -0.291216 -0.961371 -0.0942468 -0.258617 -0.954673 -0.147805 -0.258367 -0.939247 -0.107982 -0.325814 -0.930607 -0.169348 -0.324487 -0.909157 -0.122636 -0.397987 -0.904751 -0.154728 -0.396845 -0.881319 -0.11216 -0.459017 -0.88153 -0.110204 -0.459087 -0.86373 -0.0819777 -0.497242 -0.869705 -0.031254 -0.492582 -0.870927 -0.0494762 -0.488915 -0.871854 0.259668 -0.415262 -0.929868 0.366326 0.0339369 -0.981859 0.18175 -0.054042 -0.988633 0.10075 -0.111596 -0.987296 0.0990239 -0.124265 -0.997918 0.00198866 -0.0644688 -0.920289 0.0376786 -0.38942 -0.89317 -0.00841345 -0.44964 -0.890813 0.011449 -0.454226 -0.889762 0.0137297 -0.456218 -0.89136 0.0120889 -0.453135 -0.891743 0.0117058 -0.45239 -0.889762 0.0102643 -0.456309 -0.890712 0.0112092 -0.454429 -0.916654 0.00057187 -0.399682 -0.885122 -0.00272134 -0.465351 -0.877531 -0.0222364 -0.479004 -0.875737 -0.0297326 -0.481871 -0.886025 0.0039088 -0.463621 -0.899132 0.00328291 -0.437666 -0.899107 0.00331484 -0.437717 -0.905453 0.00296191 -0.424437 -0.905484 0.00288593 -0.424371 -0.911432 0.00290415 -0.41144 -0.911756 0.00212655 -0.410727 -0.917125 0.00342017 -0.398586 -0.917474 0.0015322 -0.397792 -0.896465 0.0402513 -0.441283 -0.898838 0.0714992 -0.43241 -0.904817 -0.0568065 -0.421993 -0.900356 0.0217601 -0.434609 -0.895232 0.0429729 -0.443523 -0.896973 0.0406679 -0.440211 -0.897487 0.0399998 -0.439224 -0.921997 0.0145507 -0.386923 -0.894214 0.0374405 -0.446072 -0.893534 0.0365505 -0.447505 -0.892689 0.034054 -0.449385 -0.902612 0.0225887 -0.429862 -0.90725 0.0227486 -0.419976 -0.908038 0.0208872 -0.418368 -0.913891 0.0210168 -0.405415 -0.916471 0.0131979 -0.399883 -0.92287 0.0263036 -0.384213 -0.924514 0.0165061 -0.380791 -0.929117 0.034195 -0.368201 -0.925778 -0.0136579 -0.377822 -0.922023 0.0926474 -0.375887 -0.931174 0.0357872 -0.362813 -0.895381 0.0714437 -0.439533 -0.914999 0.0687163 -0.39756 -0.910827 0.077992 -0.405353 -0.911184 0.0775115 -0.404642 -0.896193 0.0740127 -0.437448 -0.897589 0.0889734 -0.431762 -0.897613 0.0874031 -0.432031 -0.914765 0.0447698 -0.401499 -0.921635 0.0580041 -0.383699 -0.937332 0.053822 -0.344256 -0.939431 0.0547738 -0.338334 -0.937561 0.0671197 -0.341283 -0.932044 0.0587046 -0.357557 -0.928891 0.0695137 -0.36377 -0.925056 0.0692386 -0.373466 -0.922501 0.0749917 -0.37864 -0.92118 0.07485 -0.38187 -0.909124 0.0883011 -0.407057 -0.907459 0.100674 -0.407901 -0.907434 0.096607 -0.408938 -0.923885 0.11473 -0.365067 -0.925667 0.116732 -0.35988 -0.927625 0.109044 -0.35724 -0.923737 0.0971402 -0.370506 -0.904159 0.084808 -0.418692 -0.905157 0.0872795 -0.41602 -0.906977 0.0945872 -0.410423 -0.946232 0.0692785 -0.315984 -0.946243 0.0701858 -0.31575 -0.929877 0.0977906 -0.354634 -0.934859 0.091839 -0.342935 -0.934957 0.0918516 -0.342663 -0.937946 0.0848979 -0.336228 -0.939875 0.0850644 -0.330756 -0.94347 0.0742413 -0.323035 -0.947464 0.0844824 -0.308504 -0.949619 0.0967291 -0.298106 -0.948641 0.0974083 -0.300985 -0.94937 0.106862 -0.295426 -0.949196 0.107445 -0.295776 -0.992757 0.00100976 -0.120138 -0.944643 0.105619 -0.310635 -0.951291 0.102131 -0.290886 -0.942099 0.114568 -0.315156 -0.929927 0.124896 -0.345887 -0.928014 0.102984 -0.358029 -0.927716 0.107886 -0.357357 -0.963322 0.0629038 -0.260873 -0.950611 0.0918649 -0.29648 -0.952029 0.0896815 -0.292572 -0.953157 0.089782 -0.288846 -0.958124 0.0677611 -0.278221 -0.958816 0.0746095 -0.274053 -0.962364 0.068008 -0.263119 -0.951078 0.108905 -0.28912 -0.951654 0.0912694 -0.2933 -0.949958 0.104822 -0.294264 -0.978917 0.0370644 -0.200868 -0.972854 0.0711293 -0.220219 -0.964438 0.0768493 -0.25289 -0.969512 0.0757236 -0.233052 -0.961467 0.0950067 -0.257982 -0.958841 0.0996076 -0.2659 -0.997818 0.00932643 -0.0653665 -0.994809 -0.00622001 -0.10157 -0.995118 -0.00325466 -0.0986386 -0.992028 0.0126748 -0.125378 -0.999716 -0.00260675 -0.0236742 -0.999534 -0.0226274 -0.0204691 -0.999301 0.00468282 -0.0370998 -0.998763 0.0117225 -0.0483176 -0.999063 0.00856198 -0.0424216 -0.999241 0.00659735 -0.0384033 -0.999724 0 -0.0234853 -0.999813 0.00864897 -0.0172856 -0.999777 0.00250492 -0.0209452 -0.998568 -0.000419231 -0.0535016 -0.999326 0.00462357 -0.0364224 -0.999232 -0.00480177 -0.0388824 -0.9996 0.0208975 -0.0190827 -0.998984 0.0443454 -0.00799721 -0.993928 0.00654552 -0.109838 -0.998413 -0.00888784 -0.0556134 -0.997805 -0.0308519 -0.0585996 -0.997909 -0.0274771 -0.058503 -0.997438 0.00688241 -0.0712055 -0.9966 -0.0101345 -0.0817608 -0.996455 -0.00277325 -0.0840807 -0.993315 0.0290998 -0.111711 -0.994637 -0.0129072 -0.102623 -0.994509 -0.00687829 -0.104422 -0.994298 -0.00149139 -0.106624 -0.994072 0.00214862 -0.108703 -0.993788 0.00599271 -0.11113 -0.987812 0.0121202 -0.155179 -0.987784 0.013724 -0.155221 -0.986044 0.027608 -0.164181 -0.994872 0.0111926 -0.100521 -0.995625 0.0171365 -0.0918519 -0.995026 0.0105319 -0.0990581 -0.996913 0.00436199 -0.0783901 -0.997287 0.00310976 -0.0735515 -0.982157 0.0167069 -0.187317 -0.983848 0.0180237 -0.178098 -0.980873 0.0352581 -0.191429 -0.980853 0.0532883 -0.187319 -0.980213 0.0533045 -0.190636 -0.98109 0.0780645 -0.177114 -0.984918 0.0753523 -0.15575 -0.986239 0.0761237 -0.146755 -0.988085 0.136593 -0.0709294 -0.963763 0.265192 0.0288825 -0.974128 0.225989 -0.00209936 -0.98584 0.159967 -0.0502976 -0.98078 0.190868 -0.0404899 -0.982308 0.187041 -0.00932168 -0.980217 0.196556 -0.023237 -0.900464 0.291933 -0.322397 -0.891555 0.30109 -0.338341 -0.892661 0.288916 -0.345954 -0.911776 0.307903 -0.271773 -0.910159 0.35124 -0.219637 -0.912643 0.348781 -0.213155 -0.914415 0.383309 -0.130073 -0.876914 0.235909 -0.41877 -0.87532 0.221044 -0.430063 -0.860034 0.208495 -0.465695 -0.980109 0.0711619 -0.185263 -0.875521 0.150131 -0.459264 -0.848999 0.141193 -0.509182 -0.866932 0.16337 -0.470893 -0.86887 0.17765 -0.462066 -0.86373 0.0820192 -0.497236 -0.903138 0.084841 -0.420885 -0.895004 0.0707961 -0.440403 -0.885094 0.0103382 -0.465298 -0.875989 0.0344899 -0.481096 -0.858297 0.0479005 -0.510912 -0.865307 0.049222 -0.498819 -0.870603 0.0510637 -0.48933 -0.871549 0.0522666 -0.487514 -0.8709 0.0493008 -0.488981 -0.869658 0.0314881 -0.49265 -0.987784 0.0950505 -0.123488 -0.985033 0.0826952 -0.151232 -0.980663 0.129684 -0.146569 -0.981893 0.109591 -0.154517 -0.97657 0.0782911 -0.200455 -0.987199 0.115044 -0.11047 -0.982852 0.0896302 -0.161145 -0.98813 0.093894 -0.121583 -0.989697 0.0971498 -0.105173 -0.981974 0.105477 -0.156849 -0.981903 0.105426 -0.15733 -0.955805 0.249459 -0.155583 -0.957955 0.208959 -0.196616 -0.961229 0.210604 -0.178004 -0.951788 0.191985 -0.239252 -0.962655 0.175036 -0.206537 -0.964134 0.172862 -0.201407 -0.965138 0.158375 -0.208389 -0.966865 0.145486 -0.209777 -0.959804 0.207958 -0.188496 -0.963234 0.193679 -0.186195 -0.957794 0.209301 -0.197037 -0.979145 0.198016 -0.0454385 -0.963685 0.264843 -0.0342067 -0.964007 0.264427 0.0277391 -0.950927 0.308936 0.0172064 -0.965344 0.240318 -0.101776 -0.964923 0.244532 -0.0955411 -0.96443 0.247636 -0.0924712 -0.958198 0.260028 -0.119338 -0.955278 0.260871 -0.139248 -0.986772 0.104574 -0.123879 -0.987978 0.10582 -0.112704 -0.987993 0.107984 -0.110498 -0.988435 0.106728 -0.107728 -0.98857 0.124839 -0.0845303 -0.987801 0.135717 -0.0763552 -0.987425 0.139146 -0.0750368 -0.909323 0.414219 0.0394242 -0.921049 0.385589 0.0546761 -0.931741 0.36223 -0.0254694 -0.928307 0.367824 -0.0543372 -0.93626 0.309516 -0.166184 -0.935776 0.309322 -0.169244 -0.938266 0.247508 -0.241654 -0.925707 0.243091 -0.28978 -0.914315 0.287927 -0.284826 -0.90124 0.252051 -0.352473 -0.971617 0.0614552 -0.228438 -0.965082 0.128996 -0.227984 -0.93684 0.16546 -0.308146 -0.931901 0.192746 -0.307262 -0.882061 0.237557 -0.406861 -0.878538 0.252068 -0.405749 -0.841565 0.271407 -0.467018 -0.868668 0.187364 -0.458596 -0.864376 0.209639 -0.457062 -0.912294 0.166286 -0.374258 -0.908545 0.187243 -0.373478 -0.945494 0.146494 -0.290827 -0.948376 0.126057 -0.291019 -0.969479 0.0947096 -0.226142 -0.972963 0.0491498 -0.225669 -0.980867 0.0352557 -0.191458 -0.971244 0.0499303 -0.23279 -0.99035 0.0500424 -0.129242 -0.979265 0.0276279 -0.200691 -0.985577 0.0178639 -0.168281 -0.989122 0.0164551 -0.146176 -0.978377 0.0309423 -0.204502 -0.976484 0.0660362 -0.205227 -0.961416 0.0941149 -0.258498 -0.959775 0.109582 -0.258505 -0.934517 0.144979 -0.325053 -0.937173 0.125661 -0.325448 -0.903206 0.164748 -0.39633 -0.910075 0.115169 -0.398121 -0.876531 0.150293 -0.45728 -0.88154 0.110217 -0.459064 -0.830532 0.107632 -0.546473 0 0.993712 0.111965 -0.00706452 0.965902 0.258812 0 0.930874 0.36534 0 0.826238 0.563321 -0.00588165 0.707094 0.707095 0 0.652288 0.757972 0 0.467266 0.884117 -0.00352241 0.258817 0.96592 0 0.222521 0.974928 0 -0.222521 0.974928 -0.00352241 -0.258817 0.96592 0 -0.467266 0.884117 0 -0.652287 0.757972 -0.00588166 -0.707094 0.707095 0 -0.826238 0.563321 0 -0.930874 0.36534 -0.00706454 -0.965902 0.258812 0 -0.993712 0.111965 -8.9909e-06 0.128282 0.991738 0 -0.999997 0.00248 -5.38576e-05 -0.999969 0.00793149 -0.00321075 -0.985866 0.167506 0 0.989519 0.144406 -0.0133342 0.985783 0.167492 0.0244261 0.834325 0.550732 -9.9854e-06 0.276799 0.960928 -0.0114621 0.351536 0.936104 -0.0563366 0.473116 0.879197 0.016757 0.560624 0.827901 -0.0267119 0.86004 0.509527 -0.087501 -0.0434994 0.995214 -0.0553758 0 0.998466 1.48394e-05 -0.171601 0.985167 0.0517965 -0.965798 0.254068 -0.0783845 -0.787698 0.611054 -4.15356e-05 -0.834573 0.550897 1.22066e-06 -0.618243 0.785987 -0.0541479 -0.473174 0.879304 -0.0505086 -0.468864 0.881825 7.52284e-06 -0.309419 0.950926 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707106 0.707108 0 0.707106 0.707108 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.965925 0.25882 0 -0.965925 0.25882 0 -0.982627 0.185592 0.00361215 -0.985864 0.167506 0 0.999992 0.00387529 -0.000654107 0.985871 0.167507 -0.0263189 0.999489 0.0181181 -0.00360713 0.834568 0.550893 -0.0122724 0.812293 0.58312 0.00863353 0.974202 0.225514 -8.05808e-06 0.306927 0.951733 -0.0126506 0.494355 0.869168 -0.008036 0.473853 0.880567 1.0552e-05 0.644206 0.764852 -4.43711e-06 0.686824 0.726823 -0.0131261 0 0.999914 -0.00445866 0.055774 0.998433 -3.41805e-06 0.216092 0.976373 -0.0395054 -0.608665 0.792443 -0.0135946 -0.476654 0.878986 -2.58006e-05 -0.325071 0.94569 2.72788e-05 -0.162071 0.986779 -0.00156612 -0.906644 0.421893 -0.0207903 -0.785032 0.619106 -7.01418e-05 -0.834573 0.550897 6.1634e-05 -0.473869 0.880596 0 0.965925 0.258821 0 0.965925 0.258821 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965925 0.258821 0 -0.965925 0.258821 0.000160706 0 1 -0.017616 -0.160166 0.986933 -0.00887118 -0.0377165 0.999249 -0.00682959 -0.473858 0.880575 -0.00420392 -0.426131 0.904652 -5.27176e-05 -0.328435 0.944527 -0.0256675 -0.930315 0.365863 -0.0127163 -0.881544 0.471931 -0.000204241 -0.761386 0.648298 0.000227425 -0.569135 0.822244 0.000135652 -0.834573 0.550897 -0.000102919 -0.985871 0.167506 0 -0.986075 0.166304 0 0.996602 0.082362 -0.0037278 0.985864 0.167505 -0.00479434 0.834563 0.550891 0.000135398 0.862755 0.505622 -6.93819e-05 0.968713 0.248185 5.404e-05 0.124078 0.992272 -3.23934e-05 0.312462 0.94993 -0.00559893 0.473861 0.880582 0.00015944 0.535956 0.844246 -4.46454e-05 0.713195 0.700966 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707107 0.707106 0 0.707107 0.707106 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.965926 0.25882 0 -0.965926 0.25882 -2.81234e-06 -0.329851 0.944033 0 -0.984079 0.177734 0.00185458 -0.985869 0.167507 0 0.99988 0.0154965 -0.00260036 0.985868 0.167507 -0.00474356 0.987914 0.15493 -0.00770039 0.834549 0.550881 -2.89832e-06 0.854011 0.520255 -1.63194e-05 0.952973 0.303055 -0.010859 0.473841 0.880544 0.00110041 0.530767 0.847517 -0.000213403 0.705058 0.70915 4.64517e-06 -0.176994 0.984212 -0.00717071 -0.06899 0.997592 -0.0143295 0 0.999897 0.00191574 0.12319 0.992381 -0.000841634 0.315538 0.948913 -0.000828885 -0.910442 0.413637 -0.0163249 -0.810715 0.585213 -0.00801102 -0.834547 0.550879 -2.03989e-05 -0.704162 0.710039 8.68304e-05 -0.473869 0.880596 -0.040381 -0.617089 0.785856 -0.0148168 -0.488839 0.872248 0 0.965926 0.258817 0 0.965926 0.258817 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965925 0.258821 0 -0.965925 0.258821 -9.33492e-06 0.128283 0.991738 0 -0.999996 0.00268751 -5.09681e-05 -0.999969 0.00781428 -0.00323007 -0.985866 0.167506 0 0.989524 0.144367 -0.013449 0.985782 0.167492 0.0246437 0.83432 0.550729 -9.89278e-06 0.276078 0.961135 -0.0112227 0.350814 0.936378 -0.0564447 0.473113 0.879192 0.0167908 0.560629 0.827897 -0.0267647 0.859989 0.509611 -0.0874926 -0.0434754 0.995216 -0.055436 0 0.998462 1.54563e-05 -0.171408 0.9852 0.051516 -0.965714 0.254447 -0.0780034 -0.787777 0.611002 -4.46341e-05 -0.834573 0.550897 2.78593e-06 -0.618117 0.786086 -0.0540635 -0.473176 0.879308 -0.0504029 -0.468824 0.881853 6.9167e-06 -0.309418 0.950926 0 0.965927 0.258816 0 0.965927 0.258816 0 0.707106 0.707108 0 0.707106 0.707108 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.965925 0.25882 0 -0.965925 0.25882 3.70262e-05 0.129533 0.991575 0 0.999994 0.00357204 0 -0.985871 0.167503 -1.45874e-05 0.999943 0.0107184 -0.000564106 0.989398 0.14523 -0.00237305 0.985869 0.167503 -6.60734e-06 0.952729 0.303822 -5.56858e-05 0.834573 0.550898 -0.00342836 0.847421 0.530911 -8.15356e-05 0.473869 0.880596 -0.0296588 0.298328 0.954002 0.00277548 0.53438 0.84524 -2.9633e-05 0 1 -0.0291541 -0.181016 0.983048 -0.0139059 -0.0538698 0.998451 0.0082864 -0.970035 0.242822 -0.012131 -0.790915 0.611806 -1.70698e-05 -0.834573 0.550898 1.27599e-05 -0.623585 0.781756 -0.00785061 -0.473854 0.880568 -0.00812871 -0.475915 0.879454 1.67914e-05 -0.309691 0.950837 0 0.974929 0.222518 0 0.974929 0.222518 0 0.781829 0.623493 0 0.781829 0.623493 0 0.433886 0.900968 0 0.433886 0.900968 0 0 1 0 0 1 0 -0.433888 0.900967 0 -0.433888 0.900967 0 -0.781829 0.623493 0 -0.781829 0.623493 0 -0.974929 0.222518 0 -0.974929 0.222518 0 0.965926 0.258818 0 0.965926 0.258818 0 0.707105 0.707108 0 0.707105 0.707108 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.965926 0.258818 0 -0.965926 0.258818 0 -0.999949 0.010073 -0.00011771 -0.999534 0.0305094 -0.00244186 -0.972868 0.231347 0.00566787 -0.985855 0.167504 0 0.974699 0.223523 0.00837439 0.985836 0.167501 -0.00705863 0.834553 0.550882 -1.50825e-05 0.801874 0.597493 -0.00886089 0.47385 0.880561 -0.00364992 0.515474 0.856898 -1.06399e-06 0.649716 0.760177 -0.00906592 0 0.999959 -0.00222037 0.0671854 0.997738 0.0011475 0.302087 0.95328 -0.00744203 -0.473855 0.880571 -3.77414e-05 -0.307681 0.95149 4.46871e-05 -0.15793 0.98745 -0.00243945 -0.889926 0.456099 -0.0130953 -0.783092 0.621768 -3.92532e-05 -0.834574 0.550896 1.54676e-05 -0.598021 0.80148 -0.0110224 -0.446002 0.894964 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707105 0.707109 0 0.707105 0.707109 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707105 0.707109 0 -0.707105 0.707109 0 -0.965926 0.25882 0 -0.965926 0.25882 -0.694765 -0.69473 0.186153 -0.694766 -0.694729 0.186152 -0.694766 -0.508577 0.508576 -0.694763 -0.508577 0.50858 -0.694761 -0.186152 0.694734 -0.694766 -0.186154 0.694728 -0.694766 0.18615 0.694729 -0.694761 0.186155 0.694732 -0.694762 0.50858 0.508579 -0.694765 0.508576 0.508579 -0.694765 0.69473 0.186152 -0.694765 0.69473 0.186152 -0.694765 -0.69473 0.186152 -0.694765 -0.69473 0.186152 -0.694765 -0.508578 0.508577 -0.694762 -0.508578 0.508581 -0.694761 -0.186152 0.694734 -0.694766 -0.186154 0.694728 -0.694766 0.18615 0.694729 -0.694761 0.186155 0.694732 -0.694762 0.50858 0.508579 -0.694765 0.508576 0.508579 -0.694765 0.69473 0.186152 -0.694765 0.69473 0.186152 -0.849119 -0.136708 0.510204 -0.849119 -0.373496 0.373495 -0.849119 -0.510204 0.136709 -0.849119 0.510203 0.136709 -0.849119 0.373496 0.373494 -0.849119 0.136707 0.510204 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258816 0.965927 0 0.258816 0.965927 0 0.707108 0.707105 0 0.707108 0.707105 0 0.965926 0.25882 0 0.965926 0.25882 -0.694766 -0.694728 0.186152 -0.694766 -0.694728 0.186152 -0.694766 -0.508577 0.508575 -0.694766 -0.508577 0.508576 -0.694766 -0.186151 0.694729 -0.694766 -0.186151 0.694729 -0.694766 0.18615 0.694729 -0.694765 0.186151 0.69473 -0.694764 0.508579 0.508577 -0.694766 0.508577 0.508576 -0.694766 0.694728 0.186152 -0.694764 0.694731 0.186151 -0.849119 -0.136707 0.510204 -0.849119 -0.373496 0.373494 -0.849119 -0.510203 0.136709 -0.849119 0.510204 0.136708 -0.849119 0.373495 0.373495 -0.849119 0.136708 0.510204 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.258816 0.965927 0 -0.258816 0.965927 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258817 0 0.965926 0.258817 -0.694764 -0.694731 0.186153 -0.694766 -0.694729 0.186151 -0.694766 -0.508577 0.508575 -0.694764 -0.508578 0.508578 -0.694765 -0.18615 0.69473 -0.694766 -0.186151 0.694729 -0.694766 0.18615 0.694729 -0.694766 0.186151 0.694729 -0.694766 0.508577 0.508577 -0.694764 0.508578 0.508577 -0.694763 0.694731 0.186151 -0.694766 0.694728 0.186152 0.706996 -0.707049 -0.0154256 0.706999 -0.707046 -0.015428 -0.964237 -0.0589777 0.258398 -0.698066 -0.159333 0.698081 -0.25277 -0.215295 0.943269 -0.252766 -0.215296 0.943269 -0.258668 -0.451364 0.854027 -0.0994662 -0.620398 0.777954 -0.254614 -0.63079 0.732991 -0.258157 -0.798231 0.544226 -0.00282792 -0.900965 0.433883 -0.25614 -0.89982 0.353152 -0.257318 -0.960251 0.108194 0.0295941 -0.999562 0 -0.257317 -0.960251 -0.108194 -0.252765 -0.871713 -0.419794 0.128677 -0.923135 -0.362304 -0.258165 -0.798229 -0.544225 -0.252772 -0.603243 -0.756442 -0.0656596 -0.65088 -0.756336 -0.258667 -0.451376 -0.85402 -0.252766 -0.215295 -0.943269 -0.252757 -0.215294 -0.943272 -0.698067 -0.159332 0.69808 -0.698067 -0.446439 0.559816 -0.698066 -0.44644 0.559817 -0.698066 -0.645123 0.310675 -0.698068 -0.645122 0.310675 -0.698067 -0.716032 0 -0.698067 -0.716032 0 -0.698068 -0.645122 -0.310674 -0.698066 -0.645124 -0.310675 -0.698066 -0.44644 -0.559817 -0.698067 -0.44644 -0.559816 -0.698067 -0.159331 -0.69808 -0.698074 -0.159331 -0.698074 -0.964236 -0.0589779 0.258398 -0.964236 -0.165252 0.207219 -0.964237 -0.165252 0.207219 -0.964237 -0.238795 0.114998 -0.964236 -0.238796 0.114998 -0.964236 -0.265044 0 -0.964236 -0.265044 0 -0.964236 -0.238796 -0.114998 -0.964237 -0.238796 -0.114998 -0.964237 -0.165252 -0.207219 -0.964236 -0.165252 -0.207219 -0.964236 -0.0589778 -0.258398 -0.964236 -0.058978 -0.258402 -0.969348 -0.113016 -0.218157 -0.971931 -0.145364 -0.184985 -0.98078 -0.116883 -0.156233 -0.952057 -0.274792 -0.134451 -0.974874 -0.194383 -0.108791 -0.983022 -0.0479859 -0.177101 -0.967292 -0.0998751 -0.233175 -0.965275 -0.0427283 -0.257717 -0.974728 -0.0251833 -0.221971 -0.964782 -0.0082521 -0.262921 -0.964034 0.0363091 -0.263285 -0.972531 0.025593 -0.231361 -0.946075 0.139543 -0.292352 -0.96606 0.0969228 -0.239447 -0.970645 0.15472 -0.184148 -0.97095 0.153497 -0.183561 -0.955978 0.259391 -0.137191 -0.986723 0.132762 -0.0935531 -0.975101 0.172608 -0.139227 -0.775517 0.603437 -0.185574 -0.82774 0.535879 -0.166375 -0.812411 0.448117 -0.373067 -0.816311 0.444082 -0.36936 -0.804181 0.29317 -0.517053 -0.806526 0.291861 -0.514134 -0.800312 0.0997108 -0.591235 -0.801131 0.0997051 -0.590126 -0.802068 -0.105919 -0.587765 -0.801036 -0.106492 -0.589068 -0.808825 -0.296881 -0.507605 -0.806126 -0.299731 -0.510218 -0.819059 -0.447149 -0.359443 -0.81502 -0.452875 -0.361451 -0.83041 -0.533188 -0.161649 -0.817666 -0.552883 -0.160445 0.148117 0.169799 -0.974284 0.0751204 0.185027 -0.979858 -0.176822 0.299388 -0.937604 -0.181313 0.451695 -0.873554 0.13848 0.548456 -0.824633 -0.125688 0.606301 -0.78524 -0.180238 0.667176 -0.722766 -0.188987 0.804065 -0.563705 0.128154 0.796967 -0.590271 -0.272973 0.881731 -0.384755 -0.320524 0.920439 -0.223734 -0.280642 0.934392 -0.219434 -0.0711778 0.975305 -0.209078 -0.568468 0.782554 -0.253878 -0.0876266 -0.996153 0.000951428 -0.08634 -0.996256 -0.00438124 -0.190349 -0.948934 0.251578 -0.0319627 -0.988707 -0.146413 0.325963 -0.933927 -0.146726 -0.255295 -0.800609 -0.54208 -0.281753 -0.939139 -0.196551 -0.266356 -0.943412 -0.197555 -0.18351 -0.543224 -0.819287 -0.14491 -0.554017 -0.819797 -0.181653 -0.691169 -0.699491 -0.190516 -0.818918 -0.541366 -0.074849 -0.831862 -0.549912 -0.0935207 -0.93762 -0.334846 -0.177652 -0.336483 -0.924781 -0.0531595 -0.27191 -0.960853 0.131553 -0.208596 -0.969114 -0.177961 -0.123685 -0.976234 -0.178131 0.0409632 -0.983154 -0.589162 0.783273 -0.198425 -0.544899 0.811783 -0.209985 -0.521482 0.683118 -0.51128 -0.534035 0.677593 -0.505643 -0.515479 0.447536 -0.730748 -0.523964 0.445735 -0.725797 -0.514408 0.150727 -0.844195 -0.516953 0.150882 -0.842612 -0.518429 -0.164972 -0.839056 -0.51458 -0.166263 -0.841168 -0.526544 -0.456918 -0.716922 -0.517232 -0.462121 -0.720358 -0.536855 -0.684914 -0.492625 -0.52396 -0.69377 -0.494115 -0.546988 -0.814537 -0.193218 -0.536509 -0.821858 -0.191592 -0.0238382 0.983537 -0.179127 -0.0826371 0.996274 0.0246907 -0.0830108 0.99602 0.0324423 -0.0967192 0.710487 -0.697032 -0.0554007 0.849058 -0.525387 -0.125766 0.849277 -0.51275 -0.0465911 0.984094 -0.171431 0.252663 0.492421 -0.832876 -0.0706435 0.579993 -0.811553 -0.104023 0.335418 -0.936309 0.384796 0.163605 -0.908386 -0.0915112 0.139422 -0.985996 -0.100788 -0.111105 -0.988685 0.347428 -0.164725 -0.923125 -0.0988702 -0.308176 -0.946178 -0.086056 -0.545284 -0.833823 -0.114619 -0.547973 -0.828606 -0.0708566 -0.825683 -0.559666 -0.12073 -0.828681 -0.546545 -0.0587888 -0.977519 -0.202485 -0.121335 -0.975571 -0.183136 -0.975333 -0.164071 0.147669 -0.974407 -0.172299 0.144378 -0.98671 -0.146419 0.0704662 -0.99086 -0.0939004 0.0968423 -0.983156 -0.153146 0.0997566 -0.999667 0.00218262 0.0257036 -0.999704 -0.0176409 -0.0167503 -0.996074 -0.0878441 0.0109691 -0.996658 -0.0304663 0.0757923 -0.994367 -0.102344 0.0275843 -0.985953 0.165018 0.0257933 -0.993538 0.113461 0.00296702 -0.996771 0.0739028 0.0313919 -0.997227 0.0724839 -0.0168797 -0.999487 0.0265998 -0.0178309 -0.961486 0.234034 0.144126 -0.971409 0.216047 0.0984297 -0.972888 0.207347 0.102446 -0.979441 0.191588 0.0631574 -0.987132 0.155883 0.0356411 -0.812398 0.578078 0.0763853 -0.955386 0.240609 0.171304 -0.963094 0.191032 0.189624 -0.617852 0.786278 -0.00503297 -0.459035 0.88646 -0.0589533 -0.288626 0.951225 -0.108928 -0.797023 0.599496 0.0732008 -0.844197 0.519979 -0.130204 -0.830256 0.539299 -0.140824 -0.872426 0.377653 -0.310242 -0.861609 0.390275 -0.324524 -0.890436 0.164763 -0.424237 -0.884314 0.169124 -0.435185 -0.894055 -0.0817068 -0.440442 -0.89333 -0.0816635 -0.441919 -0.883119 -0.310444 -0.351745 -0.887544 -0.307512 -0.343078 -0.861178 -0.475331 -0.180091 -0.87015 -0.463925 -0.166167 -0.833848 -0.550852 0.0355021 -0.846359 -0.530525 0.0471119 -0.582864 0.81244 -0.0144906 -0.647586 0.702935 -0.294133 -0.615257 0.72412 -0.311624 -0.67249 0.503701 -0.542256 -0.647191 0.515835 -0.5613 -0.686162 0.208881 -0.696814 -0.672254 0.212291 -0.70923 -0.685387 -0.130566 -0.716378 -0.684776 -0.130583 -0.716959 -0.670673 -0.445738 -0.592888 -0.683024 -0.441796 -0.58163 -0.646468 -0.675166 -0.355289 -0.669051 -0.661868 -0.338085 -0.618302 -0.783999 -0.0552097 -0.64798 -0.7606 -0.0401286 -0.408669 0.909928 -0.0708637 -0.481955 0.78604 -0.387118 -0.434898 0.804027 -0.405467 -0.499079 0.556901 -0.663914 -0.4626 0.566719 -0.681785 -0.506035 0.224446 -0.832798 -0.486151 0.227368 -0.843777 -0.500709 -0.154347 -0.851744 -0.500571 -0.154345 -0.851825 -0.484778 -0.505769 -0.713574 -0.503295 -0.503156 -0.702516 -0.46231 -0.764505 -0.449223 -0.495554 -0.754114 -0.430973 -0.438358 -0.891732 -0.112498 -0.48052 -0.871866 -0.0946066 -0.224137 0.966839 -0.122417 -0.302643 0.834227 -0.460948 -0.242285 0.844608 -0.477425 -0.310288 0.583014 -0.750877 -0.263708 0.588226 -0.764492 -0.309373 0.228612 -0.923052 -0.284268 0.230514 -0.930621 -0.299483 -0.169441 -0.938936 -0.299814 -0.169456 -0.938827 -0.283144 -0.53823 -0.793812 -0.307337 -0.538008 -0.784915 -0.264016 -0.813718 -0.51784 -0.306562 -0.809232 -0.501162 -0.245744 -0.955589 -0.162666 -0.299664 -0.943249 -0.143119 -0.0960358 -0.116116 -0.988582 -0.104647 0.330698 -0.937917 -0.0933896 0.994958 0.0365607 -0.987966 0.14812 0.0445389 -0.997956 -0.00306282 -0.063827 -0.968323 -0.221365 0.115538 -0.98086 -0.155858 0.116714 -0.987341 0.0882207 0.131811 0.0555538 0.980137 -0.190382 -0.975408 0.167833 0.142869 -0.985918 0.145239 0.082893 -0.869592 0.472576 -0.143114 -0.859252 0.488791 -0.150894 -0.671393 0.675805 -0.304169 -0.647011 0.693717 -0.316439 -0.500165 0.771267 -0.393678 -0.464945 0.786841 -0.405842 -0.313975 0.829232 -0.462378 -0.268604 0.839329 -0.47263 -0.969937 0.162651 0.181017 -0.97873 0.121901 0.165008 -0.845656 0.529163 0.0696636 -0.831273 0.551745 0.0675502 -0.649688 0.760181 -0.00543709 -0.618538 0.785656 -0.0124562 -0.484692 0.872931 -0.0553614 -0.440403 0.895524 -0.0638911 -0.306254 0.946557 -0.10118 -0.250163 0.961873 -0.110539 -0.0615906 0.985915 -0.155495 -0.125765 0.851483 -0.509078 -0.072731 0.853633 -0.515773 -0.9966 0.0685748 0.0456743 -0.995271 0.0954995 0.0177646 -0.887873 0.326805 -0.323851 -0.882601 0.333817 -0.33103 -0.686325 0.469959 -0.555065 -0.67236 0.477869 -0.565309 -0.509155 0.535441 -0.673843 -0.488423 0.542586 -0.683406 -0.315447 0.573212 -0.756255 -0.288381 0.578135 -0.76328 -0.0883877 0.584174 -0.806801 0.282718 0.504298 -0.815938 -0.102579 0.709021 -0.697687 -0.999064 0.0428495 -0.00593053 -0.999424 0.00460536 0.0336131 -0.895275 0.109774 -0.431778 -0.895404 0.109666 -0.431538 -0.689716 0.169165 -0.704042 -0.68866 0.169516 -0.704991 -0.507881 0.197525 -0.838475 -0.505797 0.198003 -0.839622 -0.30887 0.215073 -0.926468 -0.305668 0.215572 -0.927414 0.370579 0.201275 -0.90673 -0.103495 0.134607 -0.985479 -0.10554 -0.313103 -0.943837 0.316243 -0.135194 -0.938996 -0.316242 -0.18488 -0.930489 -0.294493 -0.182223 -0.93812 -0.512173 -0.182637 -0.839239 -0.495161 -0.181091 -0.849719 -0.691327 -0.171197 -0.701967 -0.67911 -0.170581 -0.713941 -0.893505 -0.138159 -0.427271 -0.888421 -0.13741 -0.437981 -0.99729 -0.0725893 -0.0120139 -0.996919 -0.0717994 0.0315905 -0.126895 -0.549491 -0.825807 -0.0767543 -0.541479 -0.837204 -0.317626 -0.54843 -0.773523 -0.274762 -0.546233 -0.791287 -0.506124 -0.523861 -0.685133 -0.472772 -0.526506 -0.706596 -0.678837 -0.473765 -0.561006 -0.655985 -0.479566 -0.582838 -0.876835 -0.356694 -0.32238 -0.867703 -0.362055 -0.3406 -0.989716 -0.123457 0.0722569 -0.991056 -0.132965 0.0113336 -0.128692 -0.827174 -0.547012 -0.0620283 -0.820479 -0.568302 -0.310109 -0.812664 -0.493365 -0.253561 -0.816546 -0.518613 -0.489413 -0.765607 -0.417517 -0.445604 -0.777461 -0.443838 -0.654822 -0.684221 -0.321013 -0.624768 -0.700326 -0.345267 -0.84927 -0.506802 -0.147957 -0.837549 -0.520488 -0.166142 -0.973058 -0.214148 0.0854384 -0.985196 -0.166683 0.0400696 -0.124321 -0.973724 -0.190805 -0.0514167 -0.974897 -0.216637 -0.296319 -0.943924 -0.145613 -0.234641 -0.957012 -0.170504 -0.466602 -0.879558 -0.0930594 -0.418801 -0.90074 -0.11521 -0.625098 -0.779754 -0.0351588 -0.592246 -0.804014 -0.0529828 -0.817536 -0.573097 0.0565152 -0.804277 -0.592599 0.0443328 -0.957577 -0.23796 0.162547 -0.956941 -0.241532 0.161014 -0.074108 -0.829946 -0.552899 -0.968393 -0.118419 -0.219528 -0.970825 -0.150225 -0.186901 -0.979839 -0.121877 -0.158309 -0.950511 -0.278936 -0.136835 -0.956376 -0.261033 -0.131172 -0.9823 -0.0546652 -0.179159 -0.966419 -0.105592 -0.234273 -0.964765 -0.0493101 -0.25845 -0.974416 -0.0317435 -0.222499 -0.964717 -0.0149306 -0.262865 -0.96427 0.0298542 -0.263233 -0.97316 0.0184439 -0.229388 -0.94527 0.137105 -0.296087 -0.966901 0.0907535 -0.238465 -0.971759 0.149862 -0.182278 -0.971943 0.149108 -0.181916 -0.974579 0.193198 -0.113451 -0.987518 0.128554 -0.0910032 -0.976142 0.168506 -0.136941 -0.816525 0.549658 -0.17653 -0.82977 0.531548 -0.170111 -0.81431 0.445187 -0.372436 -0.818429 0.440894 -0.368493 -0.805632 0.288869 -0.517216 -0.808265 0.287383 -0.513925 -0.800849 0.0942708 -0.5914 -0.801801 0.0942582 -0.59011 -0.80134 -0.111353 -0.587755 -0.800431 -0.111849 -0.588897 -0.807048 -0.301352 -0.5078 -0.804555 -0.303954 -0.510199 -0.816875 -0.450408 -0.360346 -0.813172 -0.455611 -0.362174 -0.828606 -0.535486 -0.163298 -0.778362 -0.607543 -0.158253 0.148283 0.170642 -0.974112 0.0732346 0.185721 -0.97987 -0.176773 0.298151 -0.938007 -0.18221 0.450458 -0.874006 0.136311 0.549124 -0.82455 -0.126268 0.605683 -0.785624 -0.180744 0.666571 -0.723197 -0.19005 0.803652 -0.563936 0.125665 0.797171 -0.590531 -0.273834 0.88164 -0.38435 -0.26221 0.940323 -0.216882 -0.28138 0.934268 -0.219016 -0.0729677 0.975112 -0.209361 -0.568789 0.782584 -0.253064 -0.0932364 -0.937608 -0.33496 -0.0874333 -0.99617 0.000610806 -0.0861955 -0.996269 -0.00439842 -0.189897 -0.950783 0.244848 -0.0304724 -0.98874 -0.146511 0.326504 -0.933881 -0.145816 -0.326396 -0.92397 -0.199363 -0.182115 -0.544259 -0.818912 -0.144404 -0.554606 -0.819487 -0.21369 -0.812959 -0.541696 -0.254353 -0.801073 -0.541836 -0.280827 -0.93758 -0.205133 -0.17751 -0.336822 -0.924684 -0.0505151 -0.271493 -0.961114 0.13248 -0.207503 -0.969222 -0.17715 -0.125136 -0.976196 -0.178467 0.0392016 -0.983165 -0.535609 0.817462 -0.211848 -0.546454 0.810957 -0.209133 -0.523105 0.681772 -0.511417 -0.536125 0.67601 -0.50555 -0.516616 0.445024 -0.731479 -0.525871 0.443019 -0.726082 -0.514467 0.147192 -0.844783 -0.517984 0.147383 -0.842598 -0.517284 -0.168635 -0.839035 -0.514398 -0.16958 -0.840617 -0.524585 -0.459718 -0.716568 -0.51602 -0.464446 -0.719731 -0.534786 -0.686502 -0.492665 -0.52231 -0.695019 -0.494106 -0.545316 -0.817255 -0.186345 -0.588244 -0.786049 -0.189991 -0.346745 -0.150911 -0.925739 -0.459457 0.0630167 -0.885962 -0.719221 -0.605862 -0.340077 -0.946369 -0.276768 -0.166687 -0.917832 -0.340962 -0.203296 -0.914804 -0.36028 -0.182569 -0.9149 -0.360083 -0.182478 -0.905447 -0.385677 -0.177254 -0.823101 0.375347 -0.426168 -0.84316 0.351979 -0.406439 -0.80849 0.191052 -0.556636 -0.831782 0.175155 -0.526744 -0.793124 -0.0413864 -0.607652 -0.814068 -0.0445447 -0.579059 -0.772436 -0.277266 -0.571373 -0.0798166 0.282854 -0.955836 -0.104423 0.423928 -0.899656 0.450187 0.543495 -0.708481 0.280864 0.202028 -0.938243 0.384375 0.229743 -0.894133 -0.289534 0.103162 -0.951592 -0.0365911 0.599814 -0.799302 -0.168763 0.749874 -0.639694 0.338794 0.800812 -0.493882 -0.577393 0.752884 -0.315885 -0.0675775 0.970562 -0.231176 -0.414597 0.079867 -0.906494 -0.470625 0.398339 -0.787298 -0.425594 0.421756 -0.80062 -0.477744 0.668144 -0.570389 -0.435979 0.693182 -0.573952 -0.486376 0.832352 -0.265759 -0.458101 0.849393 -0.262058 -0.235362 0.121086 -0.964335 -0.295032 0.461611 -0.836583 -0.242705 0.481921 -0.84193 -0.298656 0.747207 -0.593705 -0.249238 0.766878 -0.591421 -0.303505 0.916804 -0.259527 -0.267154 0.929913 -0.252767 -0.156377 -0.987694 -0.0027429 -0.122078 -0.963877 -0.236722 0.23597 -0.964468 -0.118824 -0.0852439 -0.993523 -0.0751416 -0.146289 -0.989049 -0.0195467 -0.151648 -0.78505 -0.600583 -0.16466 -0.702406 -0.692469 0.171535 -0.50815 -0.844014 -0.491872 -0.849983 -0.188654 -0.725039 -0.662652 -0.187645 -0.673817 -0.716589 -0.180198 -0.90556 -0.386835 -0.174128 -0.877504 -0.448572 -0.169619 -0.0520281 -0.573917 -0.817259 -0.215398 -0.59231 -0.776384 -0.463761 -0.570524 -0.677811 -0.940329 -0.250193 -0.23062 -0.928949 -0.308984 -0.203919 -0.746448 -0.470429 -0.470651 -0.728325 -0.597027 -0.336304 -0.451778 -0.768297 -0.453449 -0.46139 -0.8678 -0.184506 -0.336479 -0.92346 -0.184402 -0.979524 0.103702 -0.172567 -0.855356 0.46358 -0.231213 -0.83621 0.492754 -0.240722 -0.960825 -0.136851 -0.241013 -0.967774 -0.136708 -0.21148 -0.953043 -0.00063199 -0.302834 -0.965694 -0.022716 -0.258689 -0.978059 0.0340811 -0.205522 -0.973253 0.0539964 -0.223301 -0.980456 0.0722838 -0.18298 -0.987524 0.0446622 -0.151005 -0.950274 -0.199501 -0.239121 -0.961434 -0.21689 -0.169126 -0.783796 -0.273435 -0.557582 -0.747746 -0.469504 -0.469512 -0.48309 -0.564264 -0.6695 -0.453172 -0.767613 -0.453216 0.240502 -0.820307 -0.518898 -0.186968 -0.881275 -0.434047 -0.0980407 -0.337871 -0.936072 0.485922 -0.0954531 -0.868774 -0.276098 -0.268648 -0.922821 -0.225196 -0.25744 -0.939687 -0.517079 -0.287379 -0.806252 -0.40332 -0.258505 -0.877786 -0.564231 -0.282903 -0.775635 -0.618268 0.0191626 -0.785734 -0.583744 0.0341575 -0.811219 -0.633803 0.317241 -0.705444 -0.59792 0.342041 -0.724914 -0.644002 0.558563 -0.522751 -0.611278 0.586783 -0.531061 -0.65533 0.708081 -0.262991 -0.628746 0.732583 -0.260768 -0.49176 0.845892 -0.206493 -0.671096 0.713322 -0.201992 -0.980664 -0.105181 -0.16503 -0.983037 -0.0813409 -0.164383 -0.838938 -0.497235 -0.221223 -0.85594 -0.466106 -0.223856 -0.825559 -0.38752 -0.41022 -0.843459 -0.357496 -0.400967 -0.811028 -0.210025 -0.546007 -0.832169 -0.182492 -0.523633 -0.795776 0.0197436 -0.605269 -0.815117 0.0347271 -0.578254 -0.774793 0.259257 -0.576612 -0.978238 0.0583272 -0.199118 -0.971041 -0.00194962 -0.238904 -0.977915 -0.0351622 -0.206026 -0.979989 -0.0179047 -0.198243 -0.978598 -0.0689899 -0.19387 -0.929309 0.333391 -0.158854 -0.11495 0.65555 -0.746352 0.206295 0.487738 -0.848265 -0.453448 0.757139 -0.470239 -0.304042 0.804394 -0.5104 0.150089 0.785885 -0.599882 -0.0753826 0.977345 -0.197772 -0.156369 0.987315 -0.0275293 -0.158243 0.987165 -0.0215394 -0.0763711 -0.984838 -0.155762 0.345296 -0.929874 -0.126904 -0.100757 -0.931643 -0.349126 -0.0629593 -0.821319 -0.566984 -0.0970611 -0.817225 -0.568087 -0.0792134 -0.499095 -0.862919 -0.646028 -0.319081 -0.693422 0.443257 -0.217685 -0.869561 -0.118966 -0.169186 -0.978378 -0.0692227 0.118194 -0.990575 0.48165 0.0730805 -0.873311 -0.0984051 0.313599 -0.944443 -0.0598134 0.515651 -0.854709 -0.906043 0.387753 -0.169508 -0.905192 0.376735 -0.196717 -0.728935 0.591403 -0.344815 -0.748895 0.458538 -0.478434 -0.465775 0.550664 -0.692692 -0.520122 0.255044 -0.815123 -0.399436 0.254882 -0.880617 -0.460911 -0.0911473 -0.882753 -0.414417 -0.100156 -0.904559 -0.471419 -0.422818 -0.773944 -0.425361 -0.439047 -0.791395 -0.478605 -0.685069 -0.549198 -0.435765 -0.705384 -0.559055 -0.487133 -0.839394 -0.24108 -0.458528 -0.854965 -0.242462 -0.879916 0.448006 -0.158237 -0.897285 0.404291 -0.177282 -0.724337 0.662187 -0.191946 -0.720291 0.597992 -0.351549 -0.453364 0.757166 -0.470278 -0.485443 0.549874 -0.679694 -0.215848 0.571714 -0.791551 -0.27783 0.239725 -0.930238 -0.225077 0.236208 -0.945276 -0.290688 -0.133344 -0.947481 -0.2351 -0.142366 -0.961489 -0.295853 -0.487436 -0.821509 -0.242226 -0.500094 -0.831404 -0.299356 -0.764916 -0.570342 -0.248852 -0.779442 -0.574928 -0.304206 -0.923966 -0.231832 -0.267936 -0.935161 -0.231698 -0.930431 0.302613 -0.206696 -0.940132 0.253904 -0.227341 -0.961795 0.212448 -0.172675 -0.932478 0.195305 -0.303875 -0.971198 0.134452 -0.196713 -0.960307 0.104606 -0.258588 -0.970459 0.0492834 -0.236178 -0.155602 0.902892 -0.400717 -0.157985 0.968146 -0.194253 -0.460322 0.862689 -0.209456 -0.341727 0.920727 -0.188373 -0.911379 0.359318 -0.200695 -0.934042 0.2985 -0.196122 -0.749406 0.45835 -0.477814 -0.786011 0.261218 -0.560314 -0.565862 0.262156 -0.781713 -0.620075 -0.0440989 -0.783302 -0.583889 -0.0525253 -0.810132 -0.634798 -0.339215 -0.694236 -0.597713 -0.357751 -0.717463 -0.644766 -0.57406 -0.504709 -0.611425 -0.597869 -0.518375 -0.656423 -0.714915 -0.240845 -0.629215 -0.737844 -0.244286 -0.987688 0.0509304 0.147913 -0.987688 0.0509304 0.147913 -0.891007 0.147805 0.429256 -0.891007 0.147805 0.429256 -0.707108 0.230211 0.668581 -0.707108 0.230211 0.668581 -0.453989 0.290084 0.842464 -0.453989 0.290084 0.842464 -0.156435 0.32156 0.933878 -0.156435 0.32156 0.933878 0 0.325568 0.945519 0 0.325568 0.945519 0 0.325568 0.945519 0 0.325568 0.945519 0 0.325568 0.945519 0 0.325568 0.945519 0 0.325568 0.945519 0 0.325568 0.945519 0.156435 0.32156 0.933878 0.156435 0.32156 0.933878 0.45399 0.290083 0.842463 0.45399 0.290083 0.842463 0.707107 0.230211 0.668582 0.707107 0.230211 0.668583 0.891007 0.147805 0.429256 0.891007 0.147805 0.429256 0.987688 0.0509304 0.147913 0.987688 0.0509304 0.147913 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.987688 -0.0509304 -0.147913 0.987688 -0.0509304 -0.147913 0.891007 -0.147805 -0.429256 0.891007 -0.147805 -0.429256 0.707107 -0.230211 -0.668582 0.707107 -0.230211 -0.668583 0.45399 -0.290083 -0.842464 0.45399 -0.290083 -0.842464 0.156435 -0.32156 -0.933878 0.156435 -0.32156 -0.933878 0 -0.325568 -0.945519 0 -0.325568 -0.945519 0 -0.325568 -0.945519 0 -0.325568 -0.945519 0 -0.325568 -0.945519 0 -0.325568 -0.945519 0 -0.325568 -0.945519 0 -0.325568 -0.945519 -0.156435 -0.32156 -0.933878 -0.156435 -0.32156 -0.933878 -0.453988 -0.290084 -0.842464 -0.453988 -0.290084 -0.842464 -0.707108 -0.230211 -0.668581 -0.707108 -0.230211 -0.668581 -0.891007 -0.147805 -0.429256 -0.891007 -0.147805 -0.429256 -0.987688 -0.0509304 -0.147913 -0.987688 -0.0509304 -0.147913 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 5.84977e-06 0.945518 -0.32557 -6.4836e-07 0.945517 -0.325572 1.3695e-06 0.945522 -0.325559 2.57174e-06 0.945518 -0.32557 2.63028e-06 0.945519 -0.325568 -2.01078e-07 0.945521 -0.32556 0 0.945521 -0.325561 3.59164e-06 0.94552 -0.325565 -1.10187e-06 0.945518 -0.325569 -4.43264e-08 0.945519 -0.325568 9.79439e-07 0.945518 -0.325568 0 0.945519 -0.325568 5.7512e-06 0.945519 -0.325567 1.31971e-06 0.945519 -0.325567 6.38536e-07 0.945517 -0.325572 -1.48502e-06 0.945519 -0.325568 0 0.945516 -0.325576 1.35727e-06 0.945519 -0.325567 -5.42494e-07 0.945517 -0.325572 -3.48357e-06 0.945518 -0.325571 0 0.945518 -0.32557 -1.83559e-06 0.94552 -0.325564 -2.80577e-07 0.945518 -0.325569 2.20004e-07 0.945521 -0.32556 -3.14357e-06 0.945519 -0.325567 0 0.945519 -0.325566 -2.76335e-07 0.945519 -0.325568 -6.32959e-07 0.945518 -0.325569 -1.56073e-06 0.945519 -0.325568 -2.27563e-07 0.945519 -0.325568 1.14605e-06 0.945519 -0.325568 3.5387e-06 0.945518 -0.325569 1.07341e-06 0.945519 -0.325567 -1.14605e-06 0.945519 -0.325568 2.73075e-07 0.945519 -0.325568 8.1214e-08 0.945519 -0.325567 -1.05107e-07 0.945518 -0.325569 0 0.945518 -0.32557 3.38091e-07 0.945519 -0.325567 -1.88971e-06 0.945519 -0.325568 2.41836e-06 0.945519 -0.325566 7.08466e-07 0.945518 -0.325569 -3.63384e-07 0.94552 -0.325565 -1.09047e-06 0.945523 -0.325556 0 0.945505 -0.325606 1.93171e-06 0.945522 -0.32556 7.76821e-07 0.94552 -0.325565 1.19196e-05 0.945518 -0.32557 -3.62033e-06 0.945519 -0.325567 7.95327e-07 0.945518 -0.325568 7.27035e-06 0.945519 -0.325568 -3.15622e-06 0.945519 -0.325567 0 0.945519 -0.325566 3.21187e-06 0.945519 -0.325566 -5.69566e-06 0.945518 -0.325571 -5.64769e-07 0.945518 -0.325568 1.64742e-06 0.945519 -0.325567 -1.90754e-06 0.945519 -0.325567 5.73458e-07 0.945518 -0.325568 -6.24417e-07 0.945519 -0.325567 0 0.945517 -0.325572 -1.53306e-05 0.945511 -0.325589 -1.39838e-05 0.945515 -0.325579 1.43782e-05 0.945522 -0.325559 -3.85505e-06 0.945518 -0.32557 -2.051e-06 0.945518 -0.325571 0 0.945524 -0.325553 -9.34825e-06 0.945527 -0.325543 -1.27599e-06 0.945518 -0.32557 -4.88532e-07 0.945519 -0.325568 -1.23849e-06 0.945518 -0.325569 -2.86325e-07 0.945519 -0.325568 1.28965e-07 0.945522 -0.325559 0 0.945521 -0.325561 -2.20004e-07 0.945521 -0.32556 2.04897e-06 0.945518 -0.325569 1.10187e-06 0.945518 -0.325568 -3.61641e-06 0.94552 -0.325565 -9.52011e-07 0.945518 -0.325569 2.63173e-07 0.945517 -0.325573 -8.70513e-07 0.94552 -0.325564 0 0.945517 -0.325572 1.33759e-06 0.945518 -0.325569 5.64295e-06 0.945519 -0.325566 -2.10845e-06 0.945519 -0.325568 -1.23055e-07 0.945519 -0.325568 1.39447e-06 0.945519 -0.325568 -7.80027e-06 0.945518 -0.325569 1.92772e-06 0.945519 -0.325568 1.93251e-06 0.945518 -0.325568 0 0.945519 -0.325567 1.78763e-06 0.945519 -0.325566 3.14357e-06 0.945519 -0.325567 -4.3401e-07 0.945519 -0.325568 4.81487e-07 0.945518 -0.325569 0 0.945519 -0.325568 1.51744e-06 0.945518 -0.325569 0 0.945522 -0.325559 7.64087e-06 0.945517 -0.325572 0 0.945522 -0.325559 -1.66657e-06 0.945515 -0.325578 1.88802e-06 0.945519 -0.325566 -1.47655e-06 0.945518 -0.325568 -3.09418e-06 0.945519 -0.325568 3.62454e-06 0.945518 -0.325571 -4.46797e-07 0.945518 -0.325569 1.4469e-06 0.945518 -0.32557 9.30999e-09 0.945518 -0.325568 -3.38384e-06 0.945519 -0.325567 2.52668e-06 0.945516 -0.325576 -1.29504e-06 0.945519 -0.325567 -3.40386e-06 0.94552 -0.325564 0 0.945518 -0.325571 3.6069e-06 0.94552 -0.325565 1.45835e-06 0.945519 -0.325567 0 0.945522 -0.325559 1.49464e-07 0.945519 -0.325568 0 0.945518 -0.325571 -2.54082e-07 0.945518 -0.325571 3.42105e-06 0.94552 -0.325564 1.28169e-06 0.945519 -0.325567 -1.48647e-06 0.945518 -0.325569 0 0.945522 -0.325559 -2.52669e-06 0.945516 -0.325576 5.01643e-07 0.945517 -0.325571 1.61041e-06 0.945519 -0.325566 1.79726e-06 0.945519 -0.325566 1.15773e-07 0.945516 -0.325574 3.97079e-07 0.945518 -0.325569 3.85119e-07 0.945518 -0.325569 0 0.945519 -0.325568 -7.69203e-07 0.945519 -0.325566 -2.59914e-06 0.945521 -0.325561 1.8195e-06 0.945518 -0.32557 -1.88803e-06 0.945519 -0.325566 1.66657e-06 0.945515 -0.325577 0 0.945519 -0.325567 0 0.945516 -0.325576 1.48502e-06 0.945519 -0.325568 0 0.945519 -0.325567 -4.15379e-06 0.945517 -0.325573 -1.47516e-07 0.945518 -0.325568 4.55549e-07 0.94552 -0.325565 -9.66936e-07 0.945518 -0.325569 -1.08203e-06 0.945518 -0.325571 2.24707e-06 0.945519 -0.325568 3.67867e-06 0.945518 -0.325569 -1.07269e-06 0.94552 -0.325564 -1.1414e-07 0.945519 -0.325567 -1.09132e-07 0.945519 -0.325567 -1.1266e-06 0.945518 -0.325569 -1.90863e-07 0.94552 -0.325565 -1.49388e-06 0.945522 -0.325558 4.17495e-07 0.94551 -0.325592 1.47077e-06 0.945522 -0.325558 5.34408e-07 0.94552 -0.325565 7.21865e-06 0.945518 -0.32557 -2.97256e-06 0.945519 -0.325567 5.41423e-06 0.945518 -0.325571 0 0.945518 -0.32557 0 0.945518 -0.325568 -4.16942e-07 0.945518 -0.325569 -9.76688e-06 0.945527 -0.325544 -1.01544e-07 0.945519 -0.325568 1.12468e-06 0.945519 -0.325568 1.18573e-06 0.945519 -0.325568 3.05078e-06 0.945519 -0.325567 0 0.945519 -0.325567 0 0.945519 -0.325567 -5.41423e-06 0.945518 -0.325571 -5.34408e-07 0.94552 -0.325565 1.1266e-06 0.945518 -0.325569 1.72473e-06 0.945522 -0.325559 -0.00144777 0.948456 -0.316906 0 0.945532 -0.32553 0 0.945505 -0.325606 -1.47147e-06 0.945522 -0.325558 6.61425e-07 0.94552 -0.325565 -1.49915e-06 0.945518 -0.325568 -7.66424e-07 0.945519 -0.325568 9.81522e-06 0.945518 -0.32557 -3.34036e-06 0.945519 -0.325567 2.45606e-06 0.945521 -0.325563 0 0.945519 -0.325568 5.41159e-07 0.945518 -0.325569 0 0.945518 -0.325569 0 0.945518 -0.325569 0 0.945518 -0.325569 0 0.945518 -0.325569 0 0.945518 -0.325569 0 0.945518 -0.325569 -1.15004e-06 0.945519 -0.325568 0 0.945519 -0.325568 0 0.945519 -0.325568 -1.02758e-06 0.945519 -0.325568 4.349e-06 0.945517 -0.325571 -2.8696e-06 0.945519 -0.325567 2.26689e-06 0.945516 -0.325576 0 0.945522 -0.325559 0 0.945522 -0.325559 -1.20331e-06 0.945515 -0.325578 1.25874e-06 0.945519 -0.325566 1.03193e-06 0.945518 -0.325569 -9.95331e-07 0.945519 -0.325566 0 0.945519 -0.325568 -8.41061e-06 0.945513 -0.325583 3.7655e-06 0.94552 -0.325565 1.59583e-06 0.945519 -0.325567 -2.19214e-06 0.945518 -0.325568 -9.16517e-08 0.945518 -0.325568 0 0.945518 -0.325568 0 0.945518 -0.325568 -2.69623e-06 0.945518 -0.325569 3.48276e-06 0.945518 -0.32557 -1.15531e-06 0.945518 -0.325568 0 0.945518 -0.325568 0 0.945518 -0.325568 0 0.945518 -0.325568 0 0.945518 -0.325568 -6.88138e-08 0.945518 -0.325568 3.75177e-06 0.945518 -0.325571 -4.99722e-07 0.945519 -0.325568 0 0.945519 -0.325568 0 0.945519 -0.325568 0 0.945519 -0.325568 0 0.945519 -0.325568 -5.78644e-07 0.945519 -0.325568 2.2326e-06 0.945518 -0.325571 0 0.945532 -0.32553 0 0.945532 -0.32553 0 0.945532 -0.32553 0 0.945532 -0.32553 0 0.945532 -0.32553 0 0.945532 -0.32553 0 0.945532 -0.32553 0 0.945532 -0.32553 0 0.945532 -0.32553 0 0.945532 -0.32553 -2.35535e-07 0.945536 -0.325517 -1.78364e-06 0.945518 -0.325569 0 0.945518 -0.325569 0 0.945518 -0.325569 0 0.945518 -0.325569 0 0.945518 -0.325569 0 0.945518 -0.325569 0 0.945518 -0.325569 -4.14448e-06 -0.945523 0.325556 6.51507e-06 -0.945517 0.325572 0 -0.945519 0.325568 -6.94014e-07 -0.945519 0.325567 6.20379e-06 -0.945517 0.325574 0 -0.945518 0.325569 0 -0.945519 0.325568 -1.86298e-06 -0.945519 0.325568 0 -0.945519 0.325568 -6.47633e-07 -0.945518 0.32557 1.51116e-06 -0.945519 0.325566 -7.33483e-08 -0.945519 0.325568 7.12404e-07 -0.945519 0.325568 1.1087e-06 -0.945518 0.32557 1.78802e-06 -0.945518 0.325569 6.95491e-07 -0.94552 0.325565 4.72904e-07 -0.945518 0.325568 -2.12702e-07 -0.945519 0.325568 -2.94346e-06 -0.945519 0.325567 -7.47314e-06 -0.945517 0.325572 -2.76911e-07 -0.945519 0.325567 -3.68662e-06 -0.945523 0.325554 -9.74662e-06 -0.945522 0.325559 6.29301e-06 -0.945517 0.325574 1.76293e-06 -0.945519 0.325568 3.7087e-06 -0.945523 0.325554 -1.83933e-06 -0.945519 0.325568 -6.00071e-07 -0.94552 0.325566 -2.9041e-06 -0.945516 0.325575 -4.32899e-07 -0.945521 0.325562 1.02714e-07 -0.94552 0.325565 -1.22717e-07 -0.945519 0.325568 9.66828e-06 -0.94552 0.325564 0 -0.945518 0.325569 2.6937e-07 -0.945518 0.325569 -3.49535e-07 -0.945518 0.325569 8.32807e-08 -0.945518 0.32557 -1.84945e-07 -0.945518 0.325569 7.48073e-07 -0.945519 0.325568 1.93301e-06 -0.945519 0.325568 -5.40199e-08 -0.945518 0.32557 4.8309e-07 -0.945521 0.325562 -1.6982e-07 -0.945519 0.325566 6.19628e-06 -0.945516 0.325575 -3.61662e-07 -0.945519 0.325567 2.98501e-08 -0.945519 0.325568 -5.31307e-06 -0.945515 0.325578 0 -0.945519 0.325568 5.5627e-06 -0.945516 0.325577 -1.05693e-05 -0.945522 0.325559 9.56414e-06 -0.945522 0.325558 -8.68687e-06 -0.945516 0.325574 5.61778e-07 -0.945519 0.325568 -9.02604e-06 -0.94552 0.325564 3.40721e-07 -0.945518 0.325569 2.11081e-06 -0.945518 0.325569 0 -0.945519 0.325568 -1.61726e-06 -0.945518 0.325571 1.3885e-06 -0.945519 0.325566 -2.815e-06 -0.945518 0.325569 7.82131e-08 -0.945519 0.325568 2.98059e-06 -0.945518 0.325569 -1.28932e-06 -0.945519 0.325566 1.13515e-05 -0.945517 0.325573 2.59189e-06 -0.945519 0.325567 -4.47994e-06 -0.945522 0.325557 0 -0.945519 0.325568 2.90254e-06 -0.945524 0.325551 -1.20538e-06 -0.945519 0.325568 -7.7853e-06 -0.945518 0.32557 -4.74899e-07 -0.945518 0.325569 -7.2386e-06 -0.94552 0.325564 4.1282e-06 -0.945518 0.325571 3.77507e-07 -0.945518 0.325569 -2.06638e-06 -0.945519 0.325568 -4.06586e-07 -0.945518 0.32557 0 -0.945519 0.325567 -3.39926e-07 -0.945519 0.325567 5.35043e-07 -0.94552 0.325565 1.85058e-06 -0.945518 0.325569 8.05912e-06 -0.945518 0.325569 -2.45195e-06 -0.945519 0.325568 3.54035e-06 -0.945519 0.325567 4.11188e-06 -0.945518 0.325569 1.22815e-07 -0.945519 0.325568 4.16872e-07 -0.94552 0.325565 4.37293e-06 -0.945519 0.325567 0 -0.945518 0.325569 -7.22873e-07 -0.945519 0.325566 -1.38987e-06 -0.945521 0.32556 -4.31555e-06 -0.945518 0.325569 2.30783e-07 -0.945519 0.325568 -5.35043e-07 -0.94552 0.325565 -2.28991e-07 -0.945519 0.325568 1.03749e-07 -0.945518 0.325569 1.02766e-07 -0.945518 0.325569 -1.88163e-06 -0.945518 0.325569 -9.11595e-08 -0.945519 0.325568 5.806e-07 -0.945518 0.32557 1.90078e-07 -0.945519 0.325568 8.93998e-07 -0.945517 0.325574 -7.31799e-07 -0.945518 0.32557 1.72705e-06 -0.945519 0.325566 -1.84e-08 -0.945519 0.325568 4.81344e-07 -0.945519 0.325568 -1.43921e-06 -0.945519 0.325566 -8.59614e-07 -0.945517 0.325574 0 -0.945521 0.325562 1.81337e-06 -0.945518 0.325569 0 -0.945518 0.325569 5.55723e-06 -0.945519 0.325566 3.39925e-07 -0.945519 0.325567 -8.5035e-07 -0.945518 0.325569 2.34337e-06 -0.945519 0.325566 -2.27614e-07 -0.945519 0.325568 7.44296e-07 -0.945519 0.325568 -2.81204e-06 -0.945519 0.325566 6.94016e-07 -0.945519 0.325567 1.8859e-06 -0.945518 0.325569 0 -0.945521 0.325561 -1.81337e-06 -0.945518 0.325569 0 -0.945521 0.325562 1.62373e-06 -0.945518 0.32557 -1.68676e-06 -0.945518 0.32557 -5.42592e-07 -0.945519 0.325568 0 -0.945519 0.325567 -5.80599e-07 -0.945518 0.32557 1.43921e-06 -0.945519 0.325566 -1.104e-07 -0.945519 0.325568 3.30924e-07 -0.945519 0.325568 -1.72705e-06 -0.945519 0.325566 0 -0.945518 0.325569 3.29308e-06 -0.945519 0.325568 2.65759e-07 -0.945519 0.325568 0 -0.945521 0.325561 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945519 0.325567 -4.57132e-06 -0.945515 0.325579 0 -0.945519 0.325567 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945519 0.325568 0 -0.945519 0.325568 -4.18083e-07 -0.945518 0.325569 1.97951e-06 -0.945518 0.325568 0 -0.945518 0.325568 0 -0.945518 0.325568 -1.30255e-06 -0.945519 0.325568 0 -0.945519 0.325568 3.04163e-07 -0.945519 0.325568 -3.79484e-06 -0.945516 0.325575 -1.43247e-05 -0.94552 0.325565 1.2882e-05 -0.945521 0.325561 4.23248e-07 -0.945518 0.325569 6.7323e-06 -0.945517 0.325572 0 -0.945519 0.325567 -5.57671e-06 -0.945516 0.325576 -2.65163e-07 -0.945518 0.325569 1.70374e-06 -0.945518 0.325571 6.16883e-07 -0.945521 0.325561 1.84924e-07 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945519 0.325568 8.14625e-07 -0.945519 0.325568 -7.43094e-06 -0.945522 0.32556 5.42427e-06 -0.945516 0.325575 -6.94862e-06 -0.945523 0.325555 0 -0.945518 0.325571 1.2216e-05 -0.945524 0.325553 -6.02747e-06 -0.945516 0.325575 -1.48179e-05 -0.945517 0.325573 1.30699e-06 -0.945519 0.325568 0 -0.945519 0.325568 0 -0.945519 0.325568 0 -0.945519 0.325567 -6.2038e-06 -0.945517 0.325574 -3.40723e-07 -0.945518 0.325569 1.44188e-06 -0.945519 0.325568 -1.75077e-05 -0.945522 0.325557 1.13656e-05 -0.945522 0.325559 -1.1633e-05 -0.945517 0.325574 8.65441e-07 -0.945519 0.325568 -1.16114e-05 -0.94552 0.325565 3.87181e-07 -0.945518 0.325569 8.68687e-06 -0.945517 0.325574 -9.5642e-06 -0.945522 0.325558 0 -0.945518 0.325571 1.36928e-05 -0.945526 0.325548 -5.72294e-06 -0.945516 0.325577 0 -0.945519 0.325568 3.66975e-06 -0.945523 0.325554 -1.76293e-06 -0.945519 0.325568 -4.51313e-07 -0.945518 0.325569 1.61285e-05 -0.945519 0.325566 0 -0.945519 0.325568 8.68237e-06 -0.945517 0.325574 2.18934e-06 -0.945519 0.325567 -6.27513e-06 -0.945517 0.325574 2.23162e-08 -0.945518 0.325568 0 -0.945519 0.325568 0 -0.945519 0.325568 -5.19191e-08 -0.945518 0.325568 1.8366e-05 -0.945519 0.325566 -1.33058e-05 -0.94552 0.325565 4.18087e-07 -0.945518 0.325569 0 -0.945518 0.325569 9.36163e-06 -0.94552 0.325565 -7.65605e-06 -0.945518 0.325571 -8.73847e-07 -0.945516 0.325575 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 -1.83401e-06 -0.945518 0.32557 -3.9008e-07 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0 -0.945518 0.325569 0.258669 0.346165 0.901809 0.482439 0.285169 0.82821 0.678054 0.239292 0.694969 0.705756 0.288227 0.647174 0.845233 0.17398 0.505284 0.948535 0.103097 0.299421 0.962492 0.163623 0.216416 0.998177 0.019651 0.05707 0.983623 -0.0586807 -0.170419 0.960984 0.0116954 -0.276358 0.903439 -0.139574 -0.40536 0.707109 -0.230207 -0.668582 0.762071 -0.0331641 -0.646644 0.584532 -0.264152 -0.767168 0.258821 -0.314469 -0.913302 0.364765 -0.0933416 -0.926409 0.120532 -0.323198 -0.938624 -0.120532 -0.323198 -0.938624 -0.257021 -0.200974 -0.945278 -0.373359 -0.30202 -0.877147 -0.584512 -0.264156 -0.767182 -0.702638 -0.122699 -0.700889 -0.774603 -0.205901 -0.597992 -0.90346 -0.13956 -0.405319 -0.960986 0.0116684 -0.27635 -0.983619 -0.0586881 -0.170441 -0.998173 0.0196739 0.0571364 -0.962495 0.163596 0.216426 -0.948541 0.103091 0.299403 -0.845185 0.174004 0.505356 -0.705748 0.288213 0.647188 -0.678054 0.239292 0.694969 -0.482439 0.285169 0.82821 -0.258669 0.346165 0.901809 -0.23932 0.31611 0.918042 0.23932 0.31611 0.918042 -0.478218 0.830764 0.284847 -0.485347 0.83155 0.270117 -0.597902 0.791391 0.127336 -0.677158 0.735609 0.0183211 -0.677527 0.735365 -0.0139811 -0.706457 0.681894 -0.189575 -0.721316 0.6211 -0.306494 -0.701245 0.6212 -0.34981 -0.639868 0.56864 -0.516931 -0.599403 0.513198 -0.614284 -0.551295 0.51767 -0.654287 -0.414342 0.479611 -0.773495 -0.338947 0.436603 -0.833363 -0.265327 0.450616 -0.852377 0 0.425072 -0.905159 -0.0910369 0.375566 -0.922314 0.0855396 0.436763 -0.895501 0.333417 0.451829 -0.827456 0.279483 0.400887 -0.872456 0.414355 0.479616 -0.773484 0.590455 0.525964 -0.612147 0.574733 0.481148 -0.661951 0.639857 0.568625 -0.51696 0.712227 0.630494 -0.308562 0.723514 0.59739 -0.34591 0.706465 0.681873 -0.18962 0.670834 0.74148 0.013756 0.691798 0.722078 -0.00435124 0.597936 0.791372 0.127286 0.47576 0.833491 0.280973 0.490433 0.825995 0.277861 0.341183 0.870183 0.355493 0.171693 0.885448 0.431861 0.171707 0.885443 0.431865 -0.171694 0.885445 0.431866 -0.171705 0.885448 0.431856 -0.341183 0.870183 0.355493 0.258669 0.346165 0.901809 0.482439 0.285169 0.82821 0.678059 0.239291 0.694965 0.705753 0.288211 0.647184 0.845185 0.174004 0.505356 0.948538 0.103094 0.299412 0.962493 0.16361 0.216421 0.998175 0.0196624 0.0571032 0.983619 -0.0586881 -0.170441 0.960986 0.0116684 -0.27635 0.90346 -0.13956 -0.405319 0.707105 -0.230208 -0.668586 0.762069 -0.0331533 -0.646646 0.584522 -0.264154 -0.767175 0.258821 -0.314469 -0.913302 0.36477 -0.0933313 -0.926408 0.12053 -0.323198 -0.938625 -0.12053 -0.323198 -0.938625 -0.257019 -0.200972 -0.945279 -0.373359 -0.30202 -0.877147 -0.584532 -0.264152 -0.767168 -0.702647 -0.122709 -0.700878 -0.774603 -0.205901 -0.597992 -0.90345 -0.139567 -0.40534 -0.960985 0.0116819 -0.276354 -0.983621 -0.0586844 -0.17043 -0.998177 0.019651 0.05707 -0.962492 0.163623 0.216416 -0.948535 0.103097 0.299421 -0.845185 0.174004 0.505356 -0.705757 0.288208 0.647181 -0.678064 0.239289 0.694961 -0.482439 0.285169 0.82821 -0.258667 0.346166 0.90181 -0.239318 0.31611 0.918042 0.23932 0.31611 0.918042 -0.478219 0.830763 0.284848 -0.485352 0.83155 0.270108 -0.5979 0.791392 0.127334 -0.677158 0.735609 0.0183174 -0.677527 0.735366 -0.0139652 -0.706465 0.681873 -0.18962 -0.721316 0.6211 -0.306494 -0.701248 0.6212 -0.349802 -0.639863 0.568633 -0.516946 -0.599403 0.513198 -0.614284 -0.551295 0.51767 -0.654287 -0.414355 0.479616 -0.773484 -0.338948 0.436601 -0.833363 -0.265328 0.450614 -0.852378 -0.0855381 0.436762 -0.895501 0 0.408941 -0.912561 0.0855381 0.436762 -0.895501 0.333415 0.451827 -0.827458 0.279486 0.40089 -0.872453 0.414348 0.479614 -0.77349 0.590455 0.525964 -0.612147 0.574733 0.481148 -0.661951 0.639868 0.56864 -0.516931 0.712223 0.630497 -0.308562 0.723514 0.59738 -0.345925 0.706461 0.681883 -0.189598 0.670832 0.741482 0.013758 0.691803 0.722073 -0.00435587 0.5979 0.791392 0.127334 0.475759 0.833492 0.280972 0.490437 0.825994 0.277859 0.341183 0.870183 0.355493 0.171693 0.885448 0.431861 0.171707 0.885443 0.431865 -0.171694 0.885445 0.431866 -0.171704 0.885447 0.431857 -0.341184 0.870182 0.355494 0.258669 0.346169 0.901808 0.482483 0.285161 0.828186 0.678059 0.239291 0.694965 0.705753 0.288211 0.647184 0.845185 0.174004 0.505356 0.948538 0.103094 0.299412 0.962493 0.16361 0.216421 0.998175 0.0196624 0.0571032 0.983619 -0.0586881 -0.170441 0.960986 0.0116684 -0.27635 0.90346 -0.13956 -0.405319 0.707105 -0.230208 -0.668586 0.762069 -0.0331533 -0.646646 0.584522 -0.264154 -0.767175 0.258821 -0.314469 -0.913302 0.36477 -0.0933313 -0.926408 0.12053 -0.323198 -0.938625 -0.12053 -0.323198 -0.938625 -0.257019 -0.200972 -0.945279 -0.373359 -0.30202 -0.877147 -0.584532 -0.264152 -0.767168 -0.702647 -0.122709 -0.700878 -0.774603 -0.205901 -0.597992 -0.90345 -0.139567 -0.40534 -0.960985 0.0116819 -0.276354 -0.983621 -0.0586844 -0.17043 -0.998177 0.019651 0.05707 -0.962492 0.163623 0.216416 -0.948535 0.103097 0.299421 -0.845185 0.174004 0.505356 -0.705757 0.288208 0.647181 -0.678064 0.239289 0.694961 -0.482439 0.285169 0.82821 -0.258667 0.346166 0.90181 -0.239318 0.31611 0.918042 0.239318 0.31611 0.918042 -0.478219 0.830763 0.284848 -0.485352 0.83155 0.270108 -0.5979 0.791392 0.127334 -0.677158 0.735609 0.0183174 -0.677527 0.735366 -0.0139652 -0.706465 0.681873 -0.18962 -0.721316 0.6211 -0.306494 -0.701248 0.6212 -0.349802 -0.639863 0.568633 -0.516946 -0.599403 0.513198 -0.614284 -0.551295 0.51767 -0.654287 -0.414355 0.479616 -0.773484 -0.338948 0.436601 -0.833363 -0.265328 0.450614 -0.852378 -0.0855381 0.436762 -0.895501 0 0.408941 -0.912561 0.0855381 0.436762 -0.895501 0.333415 0.451827 -0.827458 0.279486 0.40089 -0.872453 0.414348 0.479614 -0.77349 0.590455 0.525964 -0.612147 0.574733 0.481148 -0.661951 0.639868 0.56864 -0.516931 0.712223 0.630497 -0.308562 0.723514 0.59738 -0.345925 0.706461 0.681883 -0.189598 0.670832 0.741482 0.013758 0.691803 0.722073 -0.00435587 0.5979 0.791392 0.127334 0.475759 0.833492 0.280972 0.490437 0.825994 0.277859 0.341216 0.870177 0.355478 0.171693 0.885447 0.431862 0.171705 0.885443 0.431865 -0.171694 0.885445 0.431866 -0.171704 0.885447 0.431857 -0.341184 0.870182 0.355494 0.258676 0.346176 0.901803 0.482448 0.285177 0.828201 0.678057 0.239299 0.694964 0.705756 0.288228 0.647173 0.845225 0.173989 0.505295 0.948535 0.103099 0.299419 0.962492 0.16362 0.216421 0.998177 0.0196516 0.0570718 0.983623 -0.0586801 -0.170418 0.960984 0.0116957 -0.276358 0.903436 -0.13958 -0.405365 0.707106 -0.230214 -0.668583 0.76207 -0.0331666 -0.646644 0.584526 -0.264153 -0.767172 0.258822 -0.314468 -0.913302 0.364763 -0.0933498 -0.926409 0.120538 -0.323197 -0.938624 -0.120538 -0.323197 -0.938624 -0.257022 -0.200978 -0.945276 -0.373356 -0.30202 -0.877148 -0.584506 -0.264158 -0.767186 -0.702636 -0.1227 -0.70089 -0.774605 -0.205906 -0.597988 -0.903457 -0.139566 -0.405324 -0.960986 0.0116687 -0.27635 -0.983619 -0.0586875 -0.170439 -0.998172 0.0196745 0.0571382 -0.962494 0.163594 0.216431 -0.948542 0.103093 0.299401 -0.845177 0.174013 0.505366 -0.705748 0.288215 0.647187 -0.678057 0.239299 0.694964 -0.482448 0.285177 0.828201 -0.258676 0.346176 0.901803 -0.239314 0.316102 0.918046 0.239314 0.316102 0.918046 -0.478218 0.830764 0.284847 -0.485354 0.831551 0.2701 -0.597853 0.791418 0.127397 -0.677158 0.735609 0.0183211 -0.677527 0.735365 -0.0139985 -0.70645 0.681913 -0.189533 -0.721316 0.6211 -0.306494 -0.701238 0.621199 -0.349823 -0.639877 0.568653 -0.516905 -0.599403 0.513197 -0.614284 -0.551282 0.517671 -0.654297 -0.414359 0.47962 -0.77348 -0.338947 0.436602 -0.833363 -0.265324 0.450616 -0.852378 -0.0855455 0.436764 -0.8955 0 0.40894 -0.912561 0.0855455 0.436764 -0.8955 0.333418 0.451829 -0.827456 0.27948 0.400884 -0.872458 0.414373 0.479625 -0.773469 0.590453 0.525967 -0.612147 0.574727 0.481139 -0.661963 0.639867 0.568638 -0.516934 0.712224 0.630497 -0.308562 0.723514 0.597382 -0.345921 0.706458 0.681893 -0.189578 0.670831 0.741483 0.0137535 0.691805 0.722071 -0.0043632 0.597888 0.791399 0.127348 0.475757 0.833494 0.280969 0.490447 0.82599 0.277853 0.341188 0.870182 0.355492 0.171693 0.885447 0.431861 0.17169 0.885449 0.43186 -0.171693 0.885448 0.43186 -0.17169 0.885447 0.431863 -0.341188 0.870182 0.355492 0.258676 0.346176 0.901803 0.482448 0.285177 0.828201 0.678062 0.239298 0.694959 0.705753 0.288212 0.647184 0.845177 0.174013 0.505366 0.948538 0.103096 0.29941 0.962493 0.163607 0.216426 0.998175 0.019663 0.057105 0.983619 -0.0586875 -0.170439 0.960986 0.0116687 -0.27635 0.903457 -0.139566 -0.405324 0.707102 -0.230215 -0.668587 0.762069 -0.0331558 -0.646647 0.584516 -0.264155 -0.767179 0.258822 -0.314468 -0.913302 0.364767 -0.0933395 -0.926409 0.120536 -0.323197 -0.938624 -0.120536 -0.323197 -0.938624 -0.25702 -0.200977 -0.945277 -0.373356 -0.30202 -0.877148 -0.584526 -0.264153 -0.767172 -0.702645 -0.122709 -0.700879 -0.774605 -0.205906 -0.597988 -0.903446 -0.139573 -0.405345 -0.960985 0.0116822 -0.276354 -0.983621 -0.0586838 -0.170428 -0.998177 0.0196516 0.0570718 -0.962492 0.16362 0.216421 -0.948535 0.103099 0.299419 -0.845177 0.174013 0.505366 -0.705757 0.288209 0.647181 -0.678067 0.239296 0.694955 -0.482448 0.285177 0.828201 -0.258674 0.346177 0.901803 -0.239312 0.316102 0.918046 0.239314 0.316102 0.918046 -0.478219 0.830763 0.284849 -0.48536 0.83155 0.270092 -0.597851 0.791419 0.127396 -0.677158 0.735609 0.0183174 -0.677527 0.735365 -0.0139825 -0.706458 0.681893 -0.189578 -0.721316 0.6211 -0.306494 -0.701242 0.6212 -0.349815 -0.639872 0.568646 -0.516919 -0.599403 0.513197 -0.614284 -0.551282 0.517671 -0.654297 -0.414373 0.479625 -0.773469 -0.338948 0.4366 -0.833363 -0.265324 0.450614 -0.852379 -0.085544 0.436763 -0.8955 0 0.40894 -0.912561 0.085544 0.436763 -0.8955 0.333416 0.451827 -0.827458 0.279484 0.400888 -0.872455 0.414366 0.479623 -0.773475 0.590453 0.525967 -0.612147 0.574727 0.481139 -0.661963 0.639877 0.568653 -0.516905 0.712221 0.630501 -0.308563 0.723515 0.597373 -0.345937 0.706454 0.681903 -0.189555 0.670829 0.741485 0.0137555 0.691811 0.722066 -0.00436782 0.597851 0.791419 0.127396 0.475756 0.833495 0.280968 0.490451 0.825988 0.277851 0.341188 0.870182 0.355492 0.171693 0.885447 0.431861 0.17169 0.885449 0.43186 -0.171693 0.885448 0.43186 -0.171689 0.885447 0.431864 -0.341188 0.870181 0.355492 0.258676 0.34618 0.901802 0.482493 0.285169 0.828178 0.678062 0.239298 0.694959 0.705753 0.288212 0.647184 0.845177 0.174013 0.505366 0.948538 0.103096 0.29941 0.962493 0.163607 0.216426 0.998175 0.019663 0.057105 0.983619 -0.0586875 -0.170439 0.960986 0.0116687 -0.27635 0.903457 -0.139566 -0.405324 0.707102 -0.230215 -0.668587 0.762069 -0.0331558 -0.646647 0.584516 -0.264155 -0.767179 0.258822 -0.314468 -0.913302 0.364767 -0.0933395 -0.926409 0.120536 -0.323197 -0.938624 -0.120536 -0.323197 -0.938624 -0.25702 -0.200977 -0.945277 -0.373356 -0.30202 -0.877148 -0.584526 -0.264153 -0.767172 -0.702645 -0.122709 -0.700879 -0.774605 -0.205906 -0.597988 -0.903446 -0.139573 -0.405345 -0.960985 0.0116822 -0.276354 -0.983621 -0.0586838 -0.170428 -0.998177 0.0196516 0.0570718 -0.962492 0.16362 0.216421 -0.948535 0.103099 0.299419 -0.845177 0.174013 0.505366 -0.705757 0.288209 0.647181 -0.678067 0.239296 0.694955 -0.482448 0.285177 0.828201 -0.258674 0.346177 0.901803 -0.239312 0.316102 0.918046 0.239312 0.316102 0.918046 -0.478219 0.830763 0.284849 -0.48536 0.83155 0.270092 -0.597851 0.791419 0.127396 -0.677158 0.735609 0.0183174 -0.677527 0.735365 -0.0139825 -0.706458 0.681893 -0.189578 -0.721316 0.6211 -0.306494 -0.701242 0.6212 -0.349815 -0.639872 0.568646 -0.516919 -0.599403 0.513197 -0.614284 -0.551282 0.517671 -0.654297 -0.414373 0.479625 -0.773469 -0.338948 0.4366 -0.833363 -0.265324 0.450614 -0.852379 -0.085544 0.436763 -0.8955 0 0.40894 -0.912561 0.085544 0.436763 -0.8955 0.333416 0.451827 -0.827458 0.279484 0.400888 -0.872455 0.414366 0.479623 -0.773475 0.590453 0.525967 -0.612147 0.574727 0.481139 -0.661963 0.639877 0.568653 -0.516905 0.712221 0.630501 -0.308563 0.723515 0.597373 -0.345937 0.706454 0.681903 -0.189555 0.670829 0.741485 0.0137555 0.691811 0.722066 -0.00436782 0.597851 0.791419 0.127396 0.475756 0.833495 0.280968 0.490451 0.825988 0.277851 0.34122 0.870176 0.355476 0.171694 0.885447 0.431862 0.171688 0.885449 0.431861 -0.171693 0.885448 0.43186 -0.171689 0.885447 0.431864 -0.341188 0.870181 0.355492 0.564442 0.268742 0.780501 0.295409 -0.311041 -0.90332 0.156089 -0.257965 -0.953462 0.428362 -0.294188 -0.854377 0.450753 -0.175327 -0.875261 0.564435 -0.268752 -0.780503 0.676175 -0.239862 -0.696602 0.698213 -0.0778155 -0.711649 0.783103 -0.202464 -0.588012 0.863637 -0.16412 -0.47665 0.875847 0.028379 -0.481753 0.931862 -0.118122 -0.343046 0.974012 -0.0737406 -0.214156 0.968463 0.135709 -0.208955 0.997452 -0.0232252 -0.0674502 0.987689 0.0509286 0.147911 0.914654 0.394276 0.0891929 0.997452 0.0232252 0.0674503 0.707108 0.230207 0.668583 0.660417 0.437205 0.610492 0.783102 0.202471 0.588011 0.891006 0.147807 0.429257 0.82881 0.423301 0.365911 0.931863 0.118117 0.343045 0.423836 0.42815 0.798155 0.453988 0.290086 0.842463 0.295404 0.311042 0.903322 0.15609 0.383734 0.910156 0.142315 0.322248 0.935897 -0.142314 0.322248 0.935897 -0.156089 0.383734 0.910156 -0.295404 0.311042 0.903322 -0.428361 0.294189 0.854377 -0.450753 0.400713 0.797653 -0.56445 0.268741 0.780497 -0.676175 0.239855 0.696604 -0.698213 0.376807 0.6087 -0.783097 0.202473 0.588017 -0.863636 0.164126 0.476651 -0.875846 0.318972 0.362148 -0.931865 0.118115 0.343039 -0.974012 0.0737387 0.214157 -0.968464 0.235581 0.0811122 -0.997452 0.0232273 0.0674562 -0.987688 -0.050931 -0.147913 -0.914663 0.255759 -0.313016 -0.997452 -0.0232273 -0.0674561 -0.707106 -0.230214 -0.668582 -0.660419 -0.0313444 -0.750243 -0.783098 -0.202467 -0.588018 -0.891007 -0.147802 -0.429256 -0.82881 0.108293 -0.548951 -0.931865 -0.118119 -0.34304 0.142315 -0.322257 -0.935893 -0.142315 -0.322257 -0.935894 -0.156088 -0.257965 -0.953462 -0.295409 -0.311041 -0.90332 -0.45399 -0.290086 -0.842462 -0.423836 -0.154004 -0.89255 -0.564443 -0.26875 -0.780499 0.615664 0.256553 0.745076 0.325568 -0.307825 -0.894007 0.17322 -0.25339 -0.951729 0.469473 -0.287454 -0.834845 0.496119 -0.162198 -0.85297 0.615654 -0.256548 -0.745086 0.731353 -0.222033 -0.644844 0.755878 -0.0529618 -0.652567 0.838673 -0.177313 -0.514964 0.913545 -0.132418 -0.384579 0.923493 0.0653808 -0.378003 0.970297 -0.0787611 -0.228736 1 0 0 0.927961 0.370343 -0.0416551 0.996195 -0.0283754 -0.0824073 0.766044 0.209273 0.607767 0.71204 0.432026 0.553491 0.838672 0.177318 0.514963 0.939693 0.111352 0.323385 0.871956 0.408434 0.269954 0.970297 0.0787617 0.228738 0.463834 0.430079 0.774526 0.5 0.281953 0.818842 0.325575 0.307833 0.894002 0.17322 0.386269 0.905975 0.156435 0.321563 0.933877 -0.156435 0.321563 0.933877 -0.17322 0.386269 0.905975 -0.325575 0.307833 0.894002 -0.469471 0.287462 0.834843 -0.496119 0.397335 0.772004 -0.615664 0.256553 0.745076 -0.731355 0.222039 0.64484 -0.755879 0.360017 0.546841 -0.838667 0.17732 0.514971 -0.913545 0.132422 0.384577 -0.923493 0.284241 0.257619 -0.970297 0.0787617 0.228738 -0.996195 0.0283754 0.0824073 -0.981332 0.181845 -0.0626143 -0.996195 -0.0283754 -0.0824073 -0.766045 -0.209267 -0.607769 -0.712045 -0.000337799 -0.702134 -0.838668 -0.177315 -0.514971 -0.939693 -0.111349 -0.323386 -0.871953 0.155656 -0.464186 -0.970297 -0.0787611 -0.228736 0.156434 -0.321563 -0.933877 -0.156434 -0.321563 -0.933877 -0.17322 -0.25339 -0.951729 -0.325568 -0.307825 -0.894007 -0.499999 -0.281945 -0.818845 -0.463837 -0.13795 -0.875115 -0.615654 -0.256548 -0.745086 0.615664 0.256553 0.745076 0.325558 -0.307826 -0.894011 0.17322 -0.253393 -0.951728 0.469473 -0.287454 -0.834845 0.496119 -0.162198 -0.85297 0.615654 -0.256548 -0.745086 0.731355 -0.222032 -0.644842 0.755879 -0.0529725 -0.652564 0.838668 -0.177315 -0.514971 0.913547 -0.132417 -0.384575 0.923495 0.0653679 -0.377999 0.970295 -0.0787637 -0.228744 1 0 0 0.927961 0.370343 -0.0416551 0.996195 -0.0283754 -0.0824073 0.766044 0.209273 0.607767 0.712045 0.432012 0.553496 0.838667 0.17732 0.514971 0.939693 0.111352 0.323385 0.871963 0.408415 0.269958 0.970295 0.0787642 0.228745 0.463834 0.430079 0.774526 0.5 0.281953 0.818842 0.325565 0.307834 0.894005 0.17322 0.386266 0.905976 0.156436 0.321563 0.933876 -0.156435 0.321563 0.933877 -0.173219 0.386267 0.905976 -0.325565 0.307834 0.894005 -0.469471 0.287462 0.834843 -0.49612 0.39734 0.772001 -0.615672 0.256551 0.745071 -0.731352 0.222039 0.644843 -0.755877 0.360027 0.546836 -0.838672 0.177318 0.514963 -0.913545 0.132422 0.384577 -0.923493 0.284235 0.257625 -0.970295 0.0787642 0.228745 -0.996195 0.0283754 0.0824073 -0.981332 0.181845 -0.0626143 -0.996195 -0.0283754 -0.0824073 -0.766045 -0.209267 -0.607769 -0.71204 -0.00032442 -0.702138 -0.838673 -0.177313 -0.514964 -0.939692 -0.111349 -0.323389 -0.871957 0.155644 -0.464184 -0.970295 -0.0787636 -0.228744 0.156434 -0.321563 -0.933877 -0.156434 -0.321563 -0.933877 -0.173219 -0.253393 -0.951729 -0.325558 -0.307826 -0.894011 -0.500001 -0.281945 -0.818845 -0.463836 -0.137943 -0.875116 -0.615662 -0.256546 -0.74508 -0.326394 0.865755 0.379389 -0.333586 0.86956 0.364124 -0.435477 0.84984 0.29687 -0.512369 0.818434 0.260082 -0.519078 0.823666 0.228325 -0.593435 0.793592 0.134335 -0.649002 0.755491 0.0896064 -0.647744 0.760638 0.0431024 -0.686936 0.723531 -0.0679871 -0.721309 0.683103 -0.114385 -0.705757 0.68741 -0.171391 -0.702713 0.628194 -0.334016 -0.747662 0.60355 -0.277 -0.686938 0.612007 -0.391873 -0.633926 0.55927 -0.534187 -0.676422 0.537457 -0.503579 -0.593433 0.542656 -0.594442 -0.503087 0.500641 -0.704459 -0.534302 0.483429 -0.693411 -0.435481 0.486916 -0.757146 -0.323001 0.458041 -0.828172 -0.338443 0.448041 -0.827476 -0.230247 0.450846 -0.862394 -0.1113 0.435647 -0.89321 -0.1113 0.435647 -0.89321 0.1113 0.435647 -0.89321 0.1113 0.435647 -0.89321 0.230247 0.450846 -0.862394 0.32639 0.448651 -0.831975 0.333582 0.461049 -0.822288 0.43548 0.486917 -0.757145 0.512368 0.484818 -0.708824 0.519075 0.508486 -0.687025 0.593438 0.542656 -0.594437 0.649004 0.54017 -0.535733 0.647746 0.57285 -0.502263 0.686939 0.612005 -0.391873 0.721311 0.608713 -0.330424 0.705759 0.647204 -0.288154 0.702715 0.700663 -0.123546 0.747663 0.646141 -0.153303 0.686937 0.72353 -0.0679862 0.633925 0.769589 0.0766249 0.676426 0.733554 0.0659342 0.59344 0.793589 0.134332 0.50309 0.828216 0.246898 0.534303 0.807852 0.248789 0.435476 0.849841 0.296868 0.323003 0.870814 0.370611 0.338445 0.862505 0.376219 0.230214 0.886219 0.402016 0.111298 0.89321 0.435647 0.111304 0.893207 0.435652 -0.111298 0.893208 0.435652 -0.111303 0.89321 0.435646 -0.230214 0.886219 0.402016 -0.298211 0.870851 0.390753 -0.304149 0.874688 0.377378 -0.399219 0.858514 0.321836 -0.473768 0.830756 0.292214 -0.479686 0.836555 0.264721 -0.553985 0.811512 0.185874 -0.612015 0.776776 0.148514 -0.612209 0.783251 0.108254 -0.659471 0.751622 0.0127311 -0.700364 0.713233 -0.0280892 -0.689993 0.719594 -0.0780719 -0.706203 0.684174 -0.18216 -0.730747 0.645456 -0.222249 -0.706202 0.651285 -0.277679 -0.681924 0.599966 -0.418353 -0.72713 0.574052 -0.376491 -0.659465 0.584447 -0.472787 -0.597891 0.540058 -0.592338 -0.636785 0.517714 -0.571382 -0.553987 0.525045 -0.646086 -0.465416 0.490286 -0.73689 -0.492455 0.473243 -0.730431 -0.399211 0.478373 -0.78217 -0.295243 0.454676 -0.840298 -0.308172 0.445091 -0.840788 -0.208873 0.448599 -0.868983 -0.101145 0.436124 -0.894184 -0.101146 0.436122 -0.894185 0.101145 0.436122 -0.894185 0.101146 0.436124 -0.894184 0.208873 0.448599 -0.868983 0.298211 0.445666 -0.844069 0.30415 0.456927 -0.835889 0.399205 0.478374 -0.782173 0.473771 0.474737 -0.741732 0.479689 0.496235 -0.723636 0.553991 0.525045 -0.646082 0.612013 0.520674 -0.595264 0.612206 0.550566 -0.567521 0.659461 0.584448 -0.472792 0.700368 0.579327 -0.416972 0.689995 0.615115 -0.381498 0.706205 0.651285 -0.277674 0.730747 0.645456 -0.222249 0.706206 0.684171 -0.182164 0.681926 0.730342 -0.0397079 0.727124 0.684157 -0.0567384 0.659467 0.751625 0.0127346 0.597891 0.790251 0.134277 0.636784 0.759742 0.13152 0.553989 0.811509 0.185871 0.465418 0.840025 0.278827 0.492451 0.822622 0.284228 0.399213 0.858516 0.321838 0.332385 0.871074 0.361593 0.296803 0.885605 0.357229 0.240664 0.883137 0.402679 0.208871 0.888502 0.40858 0.101142 0.894187 0.436119 0.101144 0.894185 0.436122 -0.101142 0.894186 0.436122 -0.101144 0.894187 0.436119 -0.208871 0.888502 0.40858 -0.326394 0.865755 0.379389 -0.333586 0.869559 0.364125 -0.435483 0.849838 0.296867 -0.512368 0.818435 0.260083 -0.519077 0.823666 0.228327 -0.593439 0.79359 0.13433 -0.649002 0.755491 0.089604 -0.647744 0.760638 0.0431024 -0.686934 0.723533 -0.067982 -0.72131 0.683101 -0.114384 -0.705759 0.687409 -0.17139 -0.702715 0.628192 -0.334016 -0.747664 0.603548 -0.276999 -0.686936 0.612005 -0.391879 -0.633926 0.559271 -0.534185 -0.676421 0.537459 -0.503579 -0.593436 0.542658 -0.594437 -0.503086 0.50064 -0.70446 -0.5343 0.483429 -0.693412 -0.435487 0.486916 -0.757142 -0.323002 0.45804 -0.828172 -0.338443 0.448041 -0.827476 -0.23024 0.450846 -0.862396 -0.1113 0.435647 -0.89321 -0.1113 0.435647 -0.89321 0.1113 0.435647 -0.89321 0.1113 0.435647 -0.89321 0.23024 0.450846 -0.862396 0.32639 0.448651 -0.831975 0.333583 0.461048 -0.822288 0.435481 0.486916 -0.757146 0.512367 0.484816 -0.708825 0.519076 0.508488 -0.687023 0.593433 0.542656 -0.594442 0.649004 0.54017 -0.535733 0.647746 0.572853 -0.50226 0.686936 0.612005 -0.391879 0.721309 0.608713 -0.330426 0.705757 0.647205 -0.288154 0.702713 0.700665 -0.123545 0.747663 0.646141 -0.153303 0.686934 0.723533 -0.067982 0.633924 0.769591 0.0766237 0.676428 0.733551 0.0659319 0.593435 0.793592 0.134335 0.503088 0.828217 0.246898 0.534306 0.80785 0.248789 0.435477 0.84984 0.29687 0.323004 0.870813 0.370611 0.338445 0.862505 0.376219 0.230207 0.88622 0.402017 0.111298 0.89321 0.435647 0.111304 0.893207 0.435652 -0.111298 0.893208 0.435652 -0.111303 0.89321 0.435645 -0.230207 0.88622 0.402017 0 0.898795 0.438369 0 0.898795 0.438369 0 0.898795 0.438369 0 0.898795 0.438369 0 0.898795 0.438369 0 0.898795 0.438369 0 0.898795 0.43837 -0.702715 0.700663 -0.123546 -0.702709 0.700668 -0.123547 -0.633922 0.769592 0.0766209 -0.633925 0.769589 0.0766223 -0.503087 0.828219 0.246894 -0.503095 0.828212 0.2469 -0.323003 0.870811 0.370617 -0.323 0.870814 0.370613 -0.111301 0.893208 0.435651 -0.111299 0.893211 0.435646 0.1113 0.893211 0.435646 0.111299 0.893208 0.435651 0.323002 0.870814 0.370612 0.323003 0.870811 0.370618 0.503091 0.828214 0.246903 0.503088 0.828219 0.246893 0.633925 0.76959 0.0766233 0.633923 0.769592 0.0766198 0.70271 0.700668 -0.123548 0.702709 0.700668 -0.123549 -0.707108 0.668582 -0.230211 -0.70711 0.66858 -0.230211 -0.707107 0.668582 -0.230211 -0.707109 0.66858 -0.230211 -0.707108 0.668581 -0.230211 0.707103 0.668587 -0.230212 0.707104 0.668585 -0.230213 0.707102 0.668587 -0.230213 0.707104 0.668585 -0.230212 0.707103 0.668586 -0.230213 -0.0522955 0.437766 -0.897567 -0.194391 0.230437 -0.953473 -0.111298 0.435646 -0.893211 -0.323001 0.458042 -0.828172 -0.323001 0.458047 -0.828169 -0.503085 0.500645 -0.704457 -0.503086 0.500643 -0.704458 -0.633926 0.559273 -0.534183 -0.633928 0.55927 -0.534184 -0.702714 0.628192 -0.334018 -0.702715 0.628191 -0.334018 0.702709 0.628196 -0.334019 0.702714 0.628193 -0.334017 0.633928 0.55927 -0.534184 0.633925 0.559273 -0.534184 0.503086 0.500642 -0.704459 0.503084 0.500645 -0.704458 0.323 0.458047 -0.828169 0.323004 0.458042 -0.828171 0.111298 0.435646 -0.893211 0.111299 0.435643 -0.893212 0 0.438366 -0.898796 0 0.438366 -0.898796 0 0.438366 -0.898796 0 0.438366 -0.898796 0 0.438366 -0.898796 0 0.438366 -0.898796 0 0.438366 -0.898796 0 0.398953 0.916971 0 0.18902 0.981973 0.0173265 0.158354 0.98723 0 0.0644561 0.997921 0 -0.0921492 0.995745 0 -0.0921492 0.995745 0 -0.336886 0.941546 0 -0.336886 0.941546 0 -0.560455 0.828185 0 -0.560455 0.828185 0 -0.748808 0.662787 0 -0.748808 0.662787 0 -0.838019 0.54564 0.0132908 -0.890033 0.455702 0 -0.899797 0.436309 0 -0.975486 0.220064 0 -0.975486 0.220064 0 -0.999566 -0.029444 0 -0.999566 -0.029444 0 -0.960841 -0.277101 0 -0.960841 -0.277101 0 -0.861742 -0.507347 0 -0.861742 -0.507347 0 -0.748497 -0.663139 0.0231408 -0.708307 -0.705525 0 -0.659482 -0.75172 0 -0.510734 -0.859739 0 -0.510734 -0.859739 0 -0.28088 -0.959743 0 -0.28088 -0.959743 0 -0.0333778 -0.999443 0 -0.0333778 -0.999443 0 0.216222 -0.976344 0 0.216222 -0.976344 0 0.452237 -0.891898 0 0.452237 -0.891898 0 0.638309 -0.76978 0.0162263 0.659747 -0.751312 0 0.729754 -0.683709 0 0.825973 -0.56371 0 0.825973 -0.56371 0 0.940212 -0.340589 0 0.940212 -0.340589 0 0.995375 -0.096067 0 0.995375 -0.096067 0 0.987994 0.154491 0 0.987994 0.154491 0 0.918535 0.395341 0 0.918535 0.395341 0 0.79136 0.611351 0 0.79136 0.611351 0 0.688245 0.725479 0.0162263 0.61438 0.788844 0 0.591892 0.806018 0 0.398953 0.916971 0.851305 -0.507858 -0.131762 0.851305 0.0154488 -0.524444 0.851304 -0.21363 -0.479211 0.851304 -0.400395 -0.339064 0.851305 0.514733 -0.101638 0.851305 0.419659 -0.314908 0.851304 0.241467 -0.465805 0 -0.967953 -0.251132 0 -0.967953 -0.251132 0 -0.763134 -0.64624 0 -0.763134 -0.64624 0 -0.407169 -0.913353 0 -0.407169 -0.913353 0 0.0294447 -0.999566 0 0.0294447 -0.999566 0 0.460224 -0.887803 0 0.460224 -0.887803 0 0.79985 -0.6002 0 0.79985 -0.6002 0 0.981057 -0.193718 0 0.981057 -0.193718 0 -0.967953 -0.251132 0.00442615 -0.957875 -0.287151 -0.00369713 -0.763126 -0.646239 0 -0.738437 -0.674323 0 -0.538757 -0.842461 -0.00592468 -0.407162 -0.913337 0 -0.337771 -0.941228 0 -0.0826622 -0.996578 -0.00666822 0.0294441 -0.999544 0 0.141179 -0.989984 0 0.39259 -0.919713 -0.00592371 0.460208 -0.887791 0 0.587382 -0.80931 0 0.799853 -0.600196 -0.00442581 0.776843 -0.629679 0.00514708 0.981045 -0.193714 0 0.973129 -0.230261 0.849119 -0.505956 -0.151675 0.856529 -0.278052 -0.434793 0.855727 -0.0427717 -0.515657 0.854595 0.20387 -0.477603 0.849119 0.514009 -0.121624 0.853125 0.405288 -0.32851 0.856529 0.303147 -0.417684 0.855727 0.07305 -0.512246 0.854596 -0.175403 -0.488774 0.853125 -0.385247 -0.351798 0 -0.967953 -0.251132 0.00442485 -0.957878 -0.28714 -0.00369805 -0.763136 -0.646228 0 -0.73844 -0.674319 0 -0.538724 -0.842482 -0.00592352 -0.407157 -0.913339 0 -0.33778 -0.941225 0 -0.082649 -0.996579 -0.00666742 0.0294441 -0.999544 0 0.141166 -0.989986 0 0.39259 -0.919713 -0.00592466 0.460219 -0.887786 0 0.587414 -0.809287 0 0.799853 -0.600196 -0.00442641 0.77684 -0.629683 0.00514665 0.981042 -0.193728 0 0.973126 -0.230271 0.849119 -0.505959 -0.15167 0.856528 -0.278036 -0.434805 0.855727 -0.0427649 -0.515658 0.854595 0.20387 -0.477602 0.849119 0.514006 -0.12163 0.853125 0.405286 -0.328513 0.856529 0.303164 -0.417672 0.855727 0.0730433 -0.512247 0.854595 -0.175408 -0.488774 0.853125 -0.385249 -0.351796 0 -0.957888 -0.287143 0 -0.957888 -0.287143 0 -0.685977 -0.727624 0 -0.685977 -0.727624 0 -0.230267 -0.973127 0 -0.230267 -0.973127 0 0.287147 -0.957887 0 0.287147 -0.957887 0 0.727621 -0.685979 0 0.727621 -0.685979 0 0.973127 -0.230271 0 0.973127 -0.230271 0.849119 -0.121628 -0.514008 0.849119 -0.362334 -0.384333 0.849119 -0.505958 -0.15167 0.849119 0.514006 -0.121629 0.849119 0.38433 -0.362335 0.849119 0.151671 -0.505957 0 -0.967953 -0.251133 0 -0.967953 -0.251133 0 -0.763134 -0.646241 0 -0.763134 -0.646241 0 -0.407169 -0.913353 0 -0.407169 -0.913353 0 0.0294447 -0.999566 0 0.0294447 -0.999566 0 0.460226 -0.887802 0 0.460226 -0.887802 0 0.799846 -0.600205 0 0.799846 -0.600205 0 0.981057 -0.193717 0 0.981057 -0.193717 0.851304 -0.507859 -0.131763 0.851305 0.0154488 -0.524444 0.851304 -0.21363 -0.479211 0.851304 -0.400395 -0.339065 0.851306 0.514732 -0.101638 0.851305 0.419656 -0.31491 0.851305 0.241467 -0.465804 0 -0.967956 -0.251121 0.00442634 -0.957878 -0.287142 -0.00369704 -0.763129 -0.646236 0 -0.73844 -0.674319 0 -0.538757 -0.842461 -0.00592468 -0.407162 -0.913337 0 -0.337771 -0.941228 0 -0.08266 -0.996578 -0.00666824 0.0294437 -0.999544 0 0.141179 -0.989984 0 0.39259 -0.919713 -0.00592466 0.460219 -0.887786 0 0.587414 -0.809287 0 0.799851 -0.600199 -0.00442591 0.77684 -0.629683 0.00514683 0.981042 -0.193727 0 0.973126 -0.230271 0.849119 -0.505958 -0.15167 0.856529 -0.278052 -0.434793 0.855727 -0.0427706 -0.515657 0.854595 0.20387 -0.477602 0.849119 0.514006 -0.12163 0.853125 0.405286 -0.328513 0.856529 0.303164 -0.417672 0.855727 0.07305 -0.512245 0.854596 -0.175403 -0.488774 0.853125 -0.385249 -0.351796 0 -0.967953 -0.251132 0 -0.967953 -0.251132 0 -0.763134 -0.64624 0 -0.763134 -0.64624 0 -0.407163 -0.913355 0 -0.407163 -0.913355 0 0.029438 -0.999567 0 0.029438 -0.999567 0 0.460221 -0.887804 0 0.460221 -0.887804 0 0.799853 -0.600196 0 0.799853 -0.600196 0 0.981057 -0.193718 0 0.981057 -0.193718 0.851305 -0.507856 -0.131762 0.851305 0.0154453 -0.524444 0.851305 -0.213627 -0.479211 0.851305 -0.400394 -0.339063 0.851304 0.514734 -0.101638 0.851305 0.41966 -0.314906 0.851305 0.241465 -0.465805 0 -0.967952 -0.251134 -0.00442547 -0.957876 -0.287147 0 -0.869977 -0.493093 0 -0.738436 -0.674323 -0.00738949 -0.685963 -0.727599 0 -0.538757 -0.842461 0 -0.337771 -0.941228 -0.0088757 -0.230257 -0.973089 0 -0.0826611 -0.996578 0 0.141181 -0.989984 -0.00887565 0.287138 -0.957848 0 0.39259 -0.919713 0 0.587404 -0.809294 -0.00738976 0.727599 -0.685963 0 0.776847 -0.629689 0 0.897483 -0.44105 -0.00442593 0.973118 -0.230264 0 0.981058 -0.193716 0.851305 -0.507857 -0.131763 0.853125 -0.385247 -0.351799 0.854595 -0.175403 -0.488775 0.855727 0.073051 -0.512245 0.856529 0.303159 -0.417676 0.851305 0.514733 -0.101637 0.857008 0.462476 -0.227275 0.853125 0.405286 -0.328513 0.854595 0.20387 -0.477602 0.855727 -0.0427711 -0.515657 0.856529 -0.278052 -0.434794 0.857007 -0.448303 -0.254093 0 -0.967954 -0.25113 0.00442555 -0.957877 -0.287143 -0.00369762 -0.76313 -0.646235 0 -0.738437 -0.674322 0 -0.538745 -0.842469 -0.00592421 -0.407161 -0.913337 0 -0.337776 -0.941227 0 -0.0826578 -0.996578 -0.00666803 0.029444 -0.999544 0 0.141177 -0.989984 0 0.392592 -0.919713 -0.00592425 0.460216 -0.887787 0 0.587403 -0.809295 0 0.799851 -0.600199 -0.00442598 0.77684 -0.629683 0.00514728 0.981044 -0.193718 0 0.973128 -0.230266 0.849119 -0.505958 -0.151671 0.856529 -0.278046 -0.434798 0.855727 -0.0427694 -0.515657 0.854595 0.203871 -0.477602 0.849119 0.514008 -0.121627 0.853125 0.405286 -0.328512 0.856529 0.303158 -0.417676 0.855727 0.0730488 -0.512245 0.854595 -0.175405 -0.488774 0.853125 -0.385247 -0.351798 0 -0.967954 -0.25113 0.00442555 -0.957877 -0.287143 -0.00369765 -0.763129 -0.646236 0 -0.738436 -0.674323 0 -0.53875 -0.842466 -0.00592438 -0.40716 -0.913337 0 -0.337773 -0.941227 0 -0.0826578 -0.996578 -0.00666803 0.029444 -0.999544 0 0.141177 -0.989984 0 0.392589 -0.919714 -0.00592449 0.460215 -0.887788 0 0.587406 -0.809293 0 0.79985 -0.6002 -0.00442548 0.776842 -0.62968 0.00514777 0.981044 -0.193714 0 0.973128 -0.230266 0.849119 -0.505957 -0.151671 0.856529 -0.278048 -0.434796 0.855727 -0.0427694 -0.515657 0.854595 0.203869 -0.477602 0.849119 0.514008 -0.121627 0.853125 0.405287 -0.328511 0.856529 0.30316 -0.417675 0.855727 0.0730488 -0.512245 0.854596 -0.175404 -0.488774 0.853125 -0.385247 -0.351798 -0.93985 -0.336283 -0.0599631 -0.939662 -0.336293 -0.0627888 -0.939713 -0.336193 -0.0625621 -0.939654 -0.336358 -0.0625553 -0.939762 -0.336214 -0.0617051 -0.939691 -0.335928 -0.0642947 -0.940682 -0.333163 -0.0641901 -0.940489 -0.333695 -0.0642464 -0.939711 -0.336113 -0.0630136 -0.940044 -0.336156 -0.0575861 -0.940594 -0.3353 -0.0534534 -0.940961 -0.334535 -0.0517446 -0.939576 -0.341368 -0.0257962 -0.938802 -0.343594 -0.0243619 -0.939811 -0.339065 -0.0423167 -0.940119 -0.33767 -0.0464305 -0.940379 -0.31885 -0.118416 -0.940242 -0.319221 -0.118499 -0.93971 -0.321203 -0.117359 -0.939693 -0.321334 -0.117136 -0.939729 -0.321275 -0.117015 -0.939755 -0.321127 -0.117208 -0.939727 -0.320985 -0.117819 -0.939824 -0.321413 -0.115866 -0.939964 -0.321501 -0.114479 -0.940224 -0.321577 -0.112102 -0.940768 -0.320892 -0.109472 -0.941066 -0.320475 -0.108124 -0.942088 -0.318778 -0.10417 -0.941623 -0.319706 -0.105524 -0.944166 -0.318592 -0.0839617 -0.939063 -0.334206 -0.0804166 -0.939771 -0.327884 -0.096555 -0.940194 -0.32572 -0.0997064 -0.941649 -0.326845 -0.080433 -0.940556 -0.330682 -0.0774918 -0.939668 -0.334139 -0.0733178 -0.940373 -0.332869 -0.0699816 -0.939674 -0.334293 -0.0725274 -0.939733 -0.332652 -0.0790179 -0.939751 -0.332609 -0.0789899 -0.939552 -0.334555 -0.0728997 -0.941744 -0.328713 -0.0711709 -0.94163 -0.329023 -0.0712505 -0.939677 -0.332852 -0.0788468 -0.939817 -0.332522 -0.0785725 -0.939883 -0.227109 -0.255033 -0.939796 -0.226405 -0.255977 -0.940267 -0.228734 -0.252147 -0.941316 -0.229872 -0.24715 -0.942082 -0.230067 -0.244032 -0.94139 -0.232882 -0.24403 -0.940149 -0.238735 -0.243159 -0.937959 -0.257884 -0.231796 -0.943048 -0.242452 -0.227767 -0.940655 -0.255573 -0.22327 -0.939635 -0.256466 -0.226521 -0.939733 -0.248566 -0.234769 -0.93974 -0.248557 -0.234752 -0.939425 -0.256695 -0.227131 -0.943052 -0.249411 -0.220105 -0.942939 -0.249648 -0.220324 -0.939665 -0.24884 -0.23475 -0.93984 -0.248655 -0.234248 -0.939706 -0.219512 -0.262236 -0.946015 -0.190696 -0.26209 -0.939781 -0.219296 -0.262148 -0.940298 -0.200193 -0.275251 -0.942699 -0.199511 -0.267421 -0.927048 -0.208791 -0.311429 -0.941547 -0.213069 -0.260942 -0.93998 -0.212773 -0.266767 -0.939695 -0.223383 -0.258987 -0.939686 -0.225195 -0.257443 -0.944499 -0.0985438 -0.313385 -0.932708 -0.121144 -0.339676 -0.941868 -0.0857714 -0.324851 -0.941584 -0.0865495 -0.325468 -0.940165 -0.0801642 -0.331154 -0.940932 -0.113745 -0.318919 -0.939577 -0.113361 -0.323024 -0.939726 -0.0978759 -0.327622 -0.939753 -0.0978797 -0.327543 -0.939276 -0.113342 -0.323906 -0.944292 -0.109104 -0.310498 -0.944193 -0.109194 -0.310768 -0.939675 -0.098138 -0.32769 -0.939864 -0.0982363 -0.327115 -0.939707 -0.0589871 -0.336854 -0.945381 -0.0367661 -0.323887 -0.939774 -0.0588825 -0.336686 -0.94022 -0.0404055 -0.338161 -0.939493 -0.0387724 -0.340367 -0.939105 -0.0391974 -0.341388 -0.945475 -0.0367321 -0.323618 -0.939726 -0.0593155 -0.336743 -0.939691 -0.0592399 -0.336856 -0.941267 -0.0601376 -0.332264 -0.932885 -0.0340084 -0.358565 -0.943339 -0.0451031 -0.328751 -0.942118 -0.0436615 -0.332426 -0.942238 -0.0619441 -0.329167 -0.942759 -0.0628421 -0.327501 -0.940603 -0.0598586 -0.334191 -0.939643 -0.0729797 -0.334284 -0.939752 -0.0769104 -0.333094 -0.931685 0.0555279 -0.358998 -0.941189 0.0562984 -0.333156 -0.939498 0.0587336 -0.337481 -0.939719 0.0790741 -0.33268 -0.939743 0.0790358 -0.332621 -0.939105 0.0592242 -0.338488 -0.945477 0.0557157 -0.320886 -0.945378 0.0557686 -0.32117 -0.939661 0.0788783 -0.332889 -0.939865 0.0784798 -0.332409 -0.944294 0.12719 -0.303533 -0.944185 0.127306 -0.303823 -0.939698 0.117335 -0.321248 -0.939682 0.117119 -0.321375 -0.939723 0.116978 -0.321305 -0.939774 0.117347 -0.321022 -0.940123 0.129903 -0.315111 -0.941521 0.124987 -0.312918 -0.942443 0.122345 -0.311178 -0.942784 0.121394 -0.310519 -0.936863 0.136654 -0.32189 -0.940305 0.111714 -0.321477 -0.94077 0.109461 -0.320889 -0.941064 0.108132 -0.320479 -0.942088 0.10417 -0.318778 -0.941623 0.105523 -0.319705 -0.940194 0.0997047 -0.325721 -0.939771 0.0965543 -0.327884 -0.939691 0.0943559 -0.328752 -0.939623 0.0800584 -0.332716 -0.943785 0.0834205 -0.319862 -0.941649 0.0804332 -0.326846 -0.946018 0.205785 -0.250403 -0.939672 0.234724 -0.248842 -0.939862 0.234174 -0.248639 -0.941427 0.211338 -0.262776 -0.939397 0.216137 -0.266116 -0.964079 0.153102 -0.217053 -0.939001 0.218699 -0.26542 -0.946111 0.205612 -0.250196 -0.939726 0.234793 -0.248571 -0.939752 0.234726 -0.248537 -0.94305 0.261939 -0.205046 -0.942939 0.262183 -0.205246 -0.939697 0.262226 -0.219562 -0.939684 0.262129 -0.219734 -0.939729 0.261958 -0.219745 -0.939784 0.262151 -0.219278 -0.940005 0.267459 -0.211791 -0.940915 0.263366 -0.212878 -0.941549 0.260935 -0.213069 -0.942469 0.257449 -0.213242 -0.938636 0.269643 -0.215068 -0.939795 0.255987 -0.226396 -0.939883 0.255031 -0.22711 -0.939929 0.241902 -0.240869 -0.939663 0.240429 -0.243365 -0.939761 0.22851 -0.254228 -0.942016 0.228008 -0.246207 -0.924376 0.230715 -0.303807 -0.940267 0.252147 -0.228734 -0.941316 0.247149 -0.229872 -0.942082 0.244032 -0.230067 -0.94139 0.24403 -0.232883 -0.940295 0.24326 -0.238056 -0.939902 0.327761 -0.0956879 -0.940421 0.327395 -0.0917649 -0.939699 0.336871 -0.059023 -0.941626 0.332658 -0.0517635 -0.939779 0.336676 -0.0588571 -0.939685 0.336873 -0.0592325 -0.939728 0.336738 -0.0593229 -0.941745 0.332332 -0.0516997 -0.939553 0.338265 -0.0530819 -0.939673 0.337985 -0.0527298 -0.93987 0.337197 -0.0542488 -0.940325 0.335489 -0.0568825 -0.94069 0.334241 -0.0581936 -0.940838 0.333737 -0.0586894 -0.941413 0.331802 -0.0604076 -0.939643 0.334284 -0.07298 -0.940603 0.334191 -0.0598586 -0.942759 0.327501 -0.062842 -0.942239 0.329163 -0.0619461 -0.939751 0.333095 -0.0769102 -0.940165 0.331154 -0.0801637 -0.941584 0.325468 -0.0865498 -0.942158 0.324219 -0.0849734 -0.94118 0.326071 -0.088642 -0.939688 0.32715 -0.0997918 -0.939728 0.327614 -0.0978766 -0.939749 0.327553 -0.0978796 -0.939659 0.327307 -0.099553 -0.940387 0.325244 -0.0994392 -0.940247 0.325629 -0.0995016 -0.93967 0.327701 -0.0981408 -0.939852 0.32715 -0.0982352 -0.939598 0.342255 -0.00406916 -0.938904 0.344133 -0.00568893 -0.940223 0.339038 -0.032156 -0.942586 0.33301 -0.0252095 -0.940989 0.336961 -0.0315899 -0.940252 0.338577 -0.0359433 -0.940496 0.33688 -0.0444889 -0.939648 0.33943 -0.0429928 -0.939939 0.338601 -0.0431738 -0.939973 0.339061 -0.0385684 -0.93985 0.33923 -0.0400706 -0.939688 0.339289 -0.0432342 -0.940105 0.337977 -0.0444286 -0.940694 0.33633 -0.0444633 -0.939701 0.339321 -0.0427031 -0.939714 0.339284 -0.0427068 -0.939753 0.327486 -0.0980721 -0.939691 0.327133 -0.0998214 -0.939599 0.322389 -0.114978 -0.938046 0.32381 -0.123358 -0.940362 0.309878 -0.140341 -0.939671 0.308521 -0.147763 -0.939599 0.299067 -0.166474 -0.939163 0.299076 -0.168898 -0.939988 0.283409 -0.190006 -0.939625 0.28306 -0.192309 -0.939634 0.269356 -0.211034 -0.939425 0.269619 -0.211628 -0.94363 0.214232 -0.252325 -0.939371 0.216807 -0.265661 -0.939599 0.183789 -0.288749 -0.938156 0.180043 -0.295717 -0.940362 0.158338 -0.30108 -0.939668 0.153161 -0.305887 -0.939574 0.132178 -0.3158 -0.939276 0.132211 -0.316672 -0.942918 0.0641054 -0.326797 -0.939477 0.059538 -0.337398 -0.939599 0.0242079 -0.341421 -0.941835 0.0350544 -0.334242 -0.934773 -0.00422312 -0.355221 -0.940342 0.0100177 -0.340084 -0.939689 -0.015591 -0.341673 -0.942123 -0.104549 -0.31855 -0.939562 -0.112614 -0.323329 -0.939599 -0.141208 -0.311793 -0.940951 -0.133492 -0.311113 -0.937335 -0.169465 -0.304441 -0.939486 -0.160624 -0.302599 -0.939391 -0.200111 -0.278389 -0.964079 -0.14006 -0.225688 -0.939001 -0.202697 -0.277833 -0.94611 -0.190529 -0.261866 -0.939728 -0.219745 -0.261962 -0.939689 -0.219735 -0.26211 -0.941325 -0.248694 -0.228165 -0.939625 -0.255954 -0.227139 -0.939599 -0.272586 -0.207006 -0.940026 -0.270375 -0.207964 -0.939068 -0.289976 -0.18457 -0.939569 -0.287682 -0.185608 -0.939599 -0.30294 -0.159316 -0.941047 -0.295959 -0.163825 -0.937104 -0.321296 -0.136402 -0.939476 -0.312434 -0.140605 -0.939691 -0.320693 -0.118897 -0.93966 -0.320877 -0.118648 0 0.998019 -0.0629095 0 0.998019 -0.0629095 0 0.969466 -0.245225 0 0.969466 -0.245225 0 0.907899 -0.419188 0 0.907899 -0.419188 0 0.815415 -0.578877 0 0.815415 -0.578877 0 0.695163 -0.718852 0 0.695163 -0.718852 0 0.551238 -0.834348 0 0.551238 -0.834348 0 0.38854 -0.921432 0 0.38854 -0.921432 0 0.212612 -0.977137 0 0.212612 -0.977137 0 0.0294439 -0.999566 0 0.0294439 -0.999566 0 -0.154728 -0.987957 0 -0.154728 -0.987957 0 -0.333629 -0.942704 0 -0.333629 -0.942704 0 -0.50117 -0.865349 0 -0.50117 -0.865349 0 -0.651644 -0.758525 0 -0.651644 -0.758525 0 -0.779927 -0.62587 0 -0.779927 -0.62587 0 -0.881651 -0.471902 0 -0.881651 -0.471902 0 -0.953351 -0.301864 0 -0.953351 -0.301864 0 -0.992586 -0.121547 0 -0.992586 -0.121547 0 0.998019 -0.0629095 0 0.998019 -0.0629095 0 0.969466 -0.245225 0 0.969466 -0.245225 0 0.907899 -0.419188 0 0.907899 -0.419188 0 0.815415 -0.578877 0 0.815415 -0.578877 0 0.695163 -0.718852 0 0.695163 -0.718852 0 0.551238 -0.834348 0 0.551238 -0.834348 0 0.38854 -0.921432 0 0.38854 -0.921432 0 0.212612 -0.977137 0 0.212612 -0.977137 0 0.0294439 -0.999566 0 0.0294439 -0.999566 0 -0.154728 -0.987957 0 -0.154728 -0.987957 0 -0.333629 -0.942704 0 -0.333629 -0.942704 0 -0.50117 -0.865349 0 -0.50117 -0.865349 0 -0.651644 -0.758525 0 -0.651644 -0.758525 0 -0.779927 -0.62587 0 -0.779927 -0.62587 0 -0.881651 -0.471902 0 -0.881651 -0.471902 0 -0.953351 -0.301864 0 -0.953351 -0.301864 0 -0.992586 -0.121547 0 -0.992586 -0.121547 0 0.997639 -0.0686725 0 0.997639 -0.0686725 0 0.965073 -0.261983 0 0.965073 -0.261983 0 0.895418 -0.445226 0 0.895418 -0.445226 0 0.791354 -0.611358 0 0.791354 -0.611358 0 0.656879 -0.753996 0 0.656879 -0.753996 0 0.497159 -0.867659 0 0.497159 -0.867659 0 0.318335 -0.947978 0 0.318335 -0.947978 0 0.127277 -0.991867 0 0.127277 -0.991867 0 -0.0686725 -0.997639 0 -0.0686725 -0.997639 0 -0.261983 -0.965073 0 -0.261983 -0.965073 0 -0.445225 -0.895419 0 -0.445225 -0.895419 0 -0.611358 -0.791354 0 -0.611358 -0.791354 0 -0.753996 -0.656879 0 -0.753996 -0.656879 0 -0.867659 -0.49716 0 -0.867659 -0.49716 0 -0.947978 -0.318335 0 -0.947978 -0.318335 0 -0.991867 -0.127277 0 -0.991867 -0.127277 0 -0.997496 -0.0707261 -0.100449 -0.98325 -0.152085 -0.0112177 -0.993134 -0.116442 0 -0.980191 -0.198052 0 -0.93257 -0.360989 -0.0211924 -0.957671 -0.287084 -0.0844683 -0.946217 -0.312313 0 -0.971165 -0.238407 0 -0.858086 -0.513507 -0.0299144 -0.893072 -0.448919 -0.0696547 -0.88292 -0.464328 0 -0.916856 -0.399219 0 -0.731317 -0.682038 0 -0.758879 -0.651232 -0.0373867 -0.801348 -0.597029 -0.0560289 -0.795135 -0.603838 0 -0.836131 -0.548529 -0.0436099 -0.685328 -0.726928 -0.0436105 -0.685328 -0.726928 0 -0.637808 -0.770195 0 -0.498362 -0.866969 -0.0485865 -0.54856 -0.834698 -0.0324137 -0.55657 -0.830168 0 -0.605434 -0.795896 0 -0.344559 -0.938765 -0.0523161 -0.395208 -0.917101 -0.0224491 -0.41245 -0.910704 0 -0.462108 -0.886824 0 -0.140035 -0.990147 0 -0.180828 -0.983515 -0.0548018 -0.22992 -0.971665 -0.0137229 -0.256968 -0.966322 0 -0.305471 -0.952201 -0.0062392 -0.0944196 -0.995513 -0.0560446 -0.0576956 -0.99676 0 -0.0118883 -0.999929 0 0.198072 -0.980188 -0.0112204 0.116443 -0.993134 -0.100447 0.152083 -0.98325 0 0.0707261 -0.997496 0 0.399219 -0.916856 0 0.360989 -0.93257 -0.0211926 0.287083 -0.957671 -0.0844684 0.312312 -0.946217 0 0.238406 -0.971166 -0.0696543 0.464328 -0.88292 -0.0299148 0.448919 -0.893072 0 0.513507 -0.858085 0 0.651233 -0.758878 -0.0373877 0.597029 -0.801348 -0.0560289 0.603838 -0.795136 0 0.548529 -0.836131 0 0.770196 -0.637808 -0.0436109 0.726928 -0.685328 -0.0436111 0.726928 -0.685328 0 0.682037 -0.731318 0 0.866969 -0.498362 -0.0485866 0.834698 -0.54856 -0.0324151 0.830169 -0.556569 0 0.795895 -0.605435 0 0.952202 -0.305469 0 0.938765 -0.344559 -0.0523163 0.917101 -0.395208 -0.022449 0.910703 -0.41245 0 0.886824 -0.462108 -0.0137225 0.966322 -0.256969 -0.0548016 0.971665 -0.22992 0 0.983515 -0.180828 0 0.999929 -0.0118885 -0.0560441 0.99676 -0.0576954 -0.00623852 0.995513 -0.0944194 0 0.990147 -0.14003 0 0.998329 -0.0577863 0 0.998329 -0.0577863 0 0.973128 -0.230266 0 0.973128 -0.230266 0 0.918358 -0.39575 0 0.918358 -0.39575 0 0.835685 -0.549209 0 0.835685 -0.549209 0 0.72762 -0.68598 0 0.72762 -0.68598 0 0.597447 -0.801909 0 0.597447 -0.801909 0 0.449121 -0.893471 0 0.449121 -0.893471 0 0.287147 -0.957887 0 0.287147 -0.957887 0 0.11645 -0.993197 0 0.11645 -0.993197 0 -0.057786 -0.998329 0 -0.057786 -0.998329 0 -0.230266 -0.973128 0 -0.230266 -0.973128 0 -0.39575 -0.918358 0 -0.39575 -0.918358 0 -0.549209 -0.835685 0 -0.549209 -0.835685 0 -0.68598 -0.72762 0 -0.68598 -0.72762 0 -0.801909 -0.597447 0 -0.801909 -0.597447 0 -0.893471 -0.44912 0 -0.893471 -0.44912 0 -0.957886 -0.287148 0 -0.957886 -0.287148 0 -0.993197 -0.11645 0 -0.993197 -0.11645 0 -0.992586 -0.121546 0 -0.992586 -0.121546 0 -0.953351 -0.301864 0 -0.953351 -0.301864 0 -0.881651 -0.471902 0 -0.881651 -0.471902 0 -0.779927 -0.62587 0 -0.779927 -0.62587 0 -0.651644 -0.758525 0 -0.651644 -0.758525 0 -0.50117 -0.865349 0 -0.50117 -0.865349 0 -0.333629 -0.942704 0 -0.333629 -0.942704 0 -0.154728 -0.987957 0 -0.154728 -0.987957 0 0.0294438 -0.999566 0 0.0294438 -0.999566 0 0.212612 -0.977137 0 0.212612 -0.977137 0 0.388541 -0.921432 0 0.388541 -0.921432 0 0.551238 -0.834348 0 0.551238 -0.834348 0 0.695163 -0.718852 0 0.695163 -0.718852 0 0.815415 -0.578877 0 0.815415 -0.578877 0 0.907899 -0.419188 0 0.907899 -0.419188 0 0.969466 -0.245225 0 0.969466 -0.245225 0 0.998019 -0.0629101 0 0.998019 -0.0629101 0 -0.991867 -0.127276 0 -0.991867 -0.127276 0 -0.947978 -0.318335 0 -0.947978 -0.318335 0 -0.867659 -0.497159 0 -0.867659 -0.497159 0 -0.753996 -0.656879 0 -0.753996 -0.656879 0 -0.611358 -0.791354 0 -0.611358 -0.791354 0 -0.445225 -0.895419 0 -0.445225 -0.895419 0 -0.261983 -0.965073 0 -0.261983 -0.965073 0 -0.0686726 -0.997639 0 -0.0686726 -0.997639 0 0.127277 -0.991867 0 0.127277 -0.991867 0 0.318335 -0.947978 0 0.318335 -0.947978 0 0.497159 -0.867659 0 0.497159 -0.867659 0 0.656878 -0.753996 0 0.656878 -0.753996 0 0.791354 -0.611358 0 0.791354 -0.611358 0 0.895419 -0.445225 0 0.895419 -0.445225 0 0.965073 -0.261983 0 0.965073 -0.261983 0 0.997639 -0.0686726 0 0.997639 -0.0686726 0 0.997639 -0.0686722 0 0.997639 -0.0686722 0 0.965073 -0.261983 0 0.965073 -0.261983 0 0.895419 -0.445225 0 0.895419 -0.445225 0 0.791354 -0.611358 0 0.791354 -0.611358 0 0.656879 -0.753996 0 0.656879 -0.753996 0 0.497159 -0.867659 0 0.497159 -0.867659 0 0.318335 -0.947978 0 0.318335 -0.947978 0 0.127277 -0.991867 0 0.127277 -0.991867 0 -0.0686726 -0.997639 0 -0.0686726 -0.997639 0 -0.261983 -0.965073 0 -0.261983 -0.965073 0 -0.445225 -0.895419 0 -0.445225 -0.895419 0 -0.611358 -0.791354 0 -0.611358 -0.791354 0 -0.753996 -0.656879 0 -0.753996 -0.656879 0 -0.867659 -0.49716 0 -0.867659 -0.49716 0 -0.947978 -0.318335 0 -0.947978 -0.318335 0 -0.991867 -0.127277 0 -0.991867 -0.127277 -0.202046 -0.979307 0.0116446 -0.20206 -0.979304 0.0116434 -0.20206 -0.974998 0.0924723 -0.202019 -0.975006 0.0924766 -0.202183 -0.969699 0.137136 -0.148172 -0.972658 0.178833 -0.202053 -0.964033 0.17267 -0.202053 -0.946481 0.251692 -0.202039 -0.946483 0.251694 -0.202197 -0.932533 0.299164 -0.0930101 -0.934695 0.343065 -0.202052 -0.922464 0.328992 -0.202052 -0.892145 0.404045 -0.202055 -0.892145 0.404045 -0.202202 -0.868504 0.452564 -0.0930903 -0.869959 0.484257 -0.202153 -0.849069 0.488073 -0.202061 -0.813472 0.545375 -0.202046 -0.813474 0.545378 -0.202179 -0.77946 0.59293 -0.0806765 -0.779235 0.621518 -0.202153 -0.754294 0.624639 -0.202039 -0.712614 0.671834 -0.202048 -0.712613 0.671832 -0.202162 -0.667955 0.716217 -0.0806846 -0.666308 0.741299 -0.20219 -0.637782 0.743205 -0.202056 -0.592314 0.77996 -0.202044 -0.592315 0.779962 -0.202137 -0.537206 0.818871 -0.0930769 -0.534626 0.839947 -0.202196 -0.502901 0.840362 -0.202048 -0.455858 0.866816 -0.202043 -0.455859 0.866817 -0.202109 -0.39098 0.897935 -0.117732 -0.388063 0.914082 -0.202209 -0.35353 0.913306 -0.202052 -0.306968 0.930025 -0.202049 -0.306967 0.930025 -0.202083 -0.233488 0.951129 -0.154296 -0.231143 0.960607 -0.202217 -0.193975 0.959939 -0.202053 -0.149704 0.967865 -0.20204 -0.149704 0.967868 -0.20204 -0.0692668 0.976925 -0.202046 -0.0692673 0.976923 -0.202046 0.0116431 0.979307 -0.202051 0.0116427 0.979306 -0.202051 0.092474 0.974999 -0.202045 0.0924746 0.975001 -0.202209 0.137135 0.969693 -0.148199 0.178832 0.972654 -0.202044 0.172673 0.964034 -0.202044 0.251692 0.946483 -0.202048 0.251692 0.946482 -0.202205 0.299161 0.932532 -0.0930121 0.343065 0.934695 -0.202044 0.328993 0.922465 -0.202044 0.404046 0.892147 -0.202045 0.404045 0.892146 -0.202192 0.452566 0.868506 -0.0930838 0.484258 0.86996 -0.202143 0.488074 0.849071 -0.202051 0.545376 0.813474 -0.202046 0.545377 0.813475 -0.202179 0.592932 0.779459 -0.0806831 0.621518 0.779234 -0.202159 0.624638 0.754294 -0.202045 0.671833 0.712614 -0.202051 0.671832 0.712613 -0.202166 0.716216 0.667955 -0.0806831 0.741299 0.666308 -0.202184 0.743206 0.637783 -0.202051 0.779961 0.592314 -0.202043 0.779963 0.592315 -0.202135 0.818872 0.537206 -0.0930813 0.839947 0.534626 -0.202197 0.840361 0.502902 -0.202049 0.866816 0.455858 -0.202051 0.866815 0.455858 -0.202116 0.897933 0.39098 -0.117734 0.914082 0.388062 -0.202205 0.913306 0.353532 -0.850915 -0.525267 0.00624465 -0.850912 -0.525272 0.0062452 -0.850912 -0.522962 0.0496007 -0.850914 -0.522957 0.0495999 -0.850914 -0.517076 0.092615 -0.850911 -0.517082 0.0926167 -0.850911 -0.507667 0.135001 -0.850907 -0.507672 0.135002 -0.850907 -0.49479 0.176465 -0.850906 -0.494792 0.176466 -0.850906 -0.47853 0.216722 -0.850912 -0.478521 0.216717 -0.850912 -0.45899 0.255494 -0.850909 -0.458995 0.255497 -0.850909 -0.436328 0.292527 -0.850905 -0.436333 0.292531 -0.850905 -0.410686 0.327564 -0.850906 -0.410685 0.327563 -0.850906 -0.382232 0.360358 -0.850906 -0.382232 0.360358 -0.850906 -0.351168 0.390692 -0.850911 -0.351164 0.390686 -0.85091 -0.317702 0.418351 -0.850906 -0.317706 0.418357 -0.850906 -0.282073 0.443164 -0.850907 -0.282072 0.443162 -0.850907 -0.244513 0.464942 -0.850907 -0.244513 0.464942 -0.850907 -0.205283 0.483545 -0.85091 -0.205282 0.483541 -0.85091 -0.16465 0.498841 -0.850907 -0.164651 0.498846 -0.850907 -0.122894 0.510739 -0.850909 -0.122894 0.510737 -0.850909 -0.080298 0.519141 -0.850907 -0.0802981 0.519143 -0.850907 -0.037153 0.524 -0.85091 -0.0371531 0.523997 -0.85091 0.00624474 0.525275 -0.850907 0.0062453 0.52528 -0.850906 0.0496012 0.522971 -0.850907 0.049601 0.52297 -0.850907 0.0926182 0.517087 -0.850908 0.0926178 0.517085 -0.850908 0.135002 0.507671 -0.850907 0.135003 0.507673 -0.850907 0.176465 0.494791 -0.850909 0.176464 0.494788 -0.850909 0.21672 0.478526 -0.85091 0.216719 0.478523 -0.85091 0.255495 0.458992 -0.850906 0.255499 0.458998 -0.850906 0.29253 0.436332 -0.850907 0.292529 0.436331 -0.850907 0.327562 0.410683 -0.850907 0.327561 0.410683 -0.850907 0.360357 0.382231 -0.850907 0.360357 0.382231 -0.850907 0.39069 0.351167 -0.850908 0.390689 0.351166 -0.850908 0.418354 0.317704 -0.850908 0.418354 0.317704 -0.850908 0.443161 0.282072 -0.850907 0.443162 0.282072 -0.850907 0.464942 0.244513 -0.850907 0.464941 0.244513 -0.850908 0.483545 0.205283 -0.850907 0.483545 0.205283 -0.850907 0.498845 0.164651 -0.850907 0.498845 0.164651 -0.850907 0.510738 0.122894 -0.850908 0.510738 0.122894 -0.573241 -0.819329 0.00974136 -0.573248 -0.819324 0.00974056 -0.573248 -0.815721 0.0773689 -0.57326 -0.815713 0.0773669 -0.573261 -0.806538 0.144461 -0.573257 -0.80654 0.144462 -0.573257 -0.791855 0.210574 -0.573272 -0.791845 0.21057 -0.573272 -0.771752 0.275241 -0.573255 -0.771763 0.275247 -0.573255 -0.746398 0.338037 -0.57325 -0.746401 0.338039 -0.573251 -0.715936 0.398521 -0.573256 -0.715933 0.398519 -0.573256 -0.680578 0.45628 -0.573268 -0.680571 0.456274 -0.573268 -0.640568 0.510917 -0.573266 -0.640569 0.510919 -0.573266 -0.59619 0.562071 -0.573265 -0.59619 0.562072 -0.573264 -0.547739 0.609385 -0.573257 -0.547742 0.609389 -0.573258 -0.495548 0.65254 -0.573265 -0.495545 0.652535 -0.573264 -0.439967 0.691229 -0.573259 -0.439968 0.691232 -0.57326 -0.381384 0.725203 -0.57326 -0.381384 0.725203 -0.57326 -0.320195 0.75422 -0.573258 -0.320196 0.754222 -0.573258 -0.256818 0.778087 -0.573265 -0.256817 0.778082 -0.573265 -0.191687 0.796632 -0.573256 -0.191687 0.796639 -0.573256 -0.125247 0.809747 -0.573266 -0.125246 0.80974 -0.573266 -0.0579506 0.817317 -0.57326 -0.0579503 0.817322 -0.573259 0.00974059 0.819316 -0.573261 0.00974045 0.819315 -0.573261 0.0773668 0.815712 -0.573266 0.0773659 0.815709 -0.573266 0.144462 0.806534 -0.573263 0.144463 0.806536 -0.573264 0.210572 0.791851 -0.57326 0.210573 0.791853 -0.57326 0.275245 0.77176 -0.573258 0.275245 0.771761 -0.573258 0.338036 0.746396 -0.573256 0.338037 0.746397 -0.573256 0.39852 0.715933 -0.573263 0.398517 0.715929 -0.573263 0.456277 0.680574 -0.573263 0.456277 0.680574 -0.573263 0.51092 0.640571 -0.573262 0.51092 0.640571 -0.573262 0.562073 0.596192 -0.57326 0.562074 0.596193 -0.57326 0.609387 0.547741 -0.573259 0.609388 0.547741 -0.573259 0.652539 0.495547 -0.573261 0.652538 0.495546 -0.573261 0.691231 0.439968 -0.57326 0.691231 0.439968 -0.57326 0.725203 0.381384 -0.57326 0.725203 0.381384 -0.57326 0.75422 0.320195 -0.573262 0.754219 0.320194 -0.573262 0.778085 0.256818 -0.573261 0.778085 0.256818 -0.573261 0.796636 0.191687 -0.573261 0.796636 0.191687 -0.202047 0.930026 0.306968 -0.202048 0.930025 0.306968 -0.202083 0.951129 0.233488 -0.154294 0.960607 0.231142 -0.202212 0.959939 0.193977 -0.850908 0.519142 0.080298 -0.850908 0.519142 0.080298 -0.573261 0.809744 0.125247 -0.573261 0.809744 0.125247 -0.202047 0.967867 0.149704 -0.202048 0.967866 0.149704 -0.850908 0.524 0.0371533 -0.850908 0.524 0.0371533 -0.57326 0.817322 0.0579508 -0.573261 0.817321 0.0579508 -0.202049 0.976923 0.0692672 -0.202047 0.976923 0.0692671 0.0292524 -0.272378 -0.961746 0.022233 0.9 -0.435323 -0.0628793 0.915157 -0.398164 0.0265234 0.934418 -0.35519 0 0.944876 -0.327428 0 0.962157 -0.272494 -0.0146314 0.963468 -0.267423 0.0128702 0.982164 -0.187584 0 0.983214 -0.182455 0 0.994858 -0.101277 0.0535599 0.991306 -0.120183 -0.0769823 0.996932 -0.0141441 0 0.999443 -0.0333785 0.0163848 0.245059 -0.96937 -0.0613277 0.276579 -0.959032 0.0292501 0.328515 -0.944046 0 0.353265 -0.935523 0 0.409721 -0.912211 -0.00487599 0.411308 -0.911484 0.00468195 0.48766 -0.873021 0 0.489189 -0.872178 0 0.561899 -0.827206 0.0632635 0.5419 -0.838059 -0.0958678 0.628946 -0.771515 0.0148163 0.611284 -0.791273 -0.010533 0.696967 -0.717026 -0.0473436 0.704923 -0.707702 0.0280805 0.756551 -0.653332 0 0.767022 -0.641621 0 0.810934 -0.585138 0.0243726 0.805558 -0.592016 -0.0292446 0.858478 -0.512015 0 0.854343 -0.51971 0 0.885291 -0.465037 -0.116173 -0.18633 -0.975595 0.0311794 -0.219956 -0.975011 0 -0.15148 -0.98846 0 -0.101277 -0.994858 -0.034115 -0.0890638 -0.995441 0.0245738 -0.0141804 -0.999597 0 -0.00196774 -0.999998 0 0.073016 -0.997331 0.0341156 0.0607906 -0.997567 -0.0436424 0.15951 -0.986231 0 0.14759 -0.989049 0 0.2094 -0.97783 0 -0.827206 -0.561899 -0.0243749 -0.822026 -0.568927 0.0195051 -0.774938 -0.631737 0 -0.769541 -0.638597 0 -0.717066 -0.697006 0.0438453 -0.727225 -0.684997 -0.059564 -0.652429 -0.755506 -0.0132598 -0.662728 -0.748742 0.00897256 -0.585115 -0.810901 -0.0582232 -0.562754 -0.824572 0.0304199 -0.511997 -0.858448 0 -0.492618 -0.870246 0 -0.435431 -0.900222 0.00487807 -0.436997 -0.89945 -0.00506987 -0.355311 -0.934735 0 -0.356946 -0.934125 0 -0.297588 -0.954694 0 -0.997331 -0.0730162 -0.053562 -0.994316 -0.0920167 0.0300307 -0.986727 -0.15959 0 -0.983925 -0.178583 0 -0.9695 -0.245092 0.0146285 -0.970666 -0.239986 -0.0163812 -0.944323 -0.328612 0 -0.946157 -0.323707 0 -0.912211 -0.40972 0.0826074 -0.920807 -0.38117 -0.137845 -0.864697 -0.48301 0.0490673 -0.890824 -0.451692 0 -0.856382 -0.516343 0.793129 0.608992 -0.00863916 0.896669 -0.441519 -0.0323244 0.60836 -0.791543 -0.0579502 0.194919 -0.978201 -0.0716157 0.441933 -0.894653 -0.0654992 0.258615 -0.96329 -0.0720496 0.258599 -0.953593 -0.154231 0.2586 -0.953593 -0.154231 0.258599 -0.936522 -0.236755 0.258598 -0.936522 -0.236755 0.258598 -0.912324 -0.317477 0.25859 -0.912326 -0.317478 0.25859 -0.881184 -0.395784 0.258597 -0.881183 -0.395783 0.258597 -0.843335 -0.471078 0.258595 -0.843335 -0.471078 0.258596 -0.799069 -0.542787 0.258601 -0.799067 -0.542786 0.258601 -0.74872 -0.610364 0.258589 -0.748722 -0.610366 0.258589 -0.692676 -0.673299 0.258591 -0.692676 -0.673298 0.25859 -0.631359 -0.731107 0.258593 -0.631358 -0.731106 0.258592 -0.565236 -0.783351 0.2586 -0.565235 -0.783349 0.258599 -0.49481 -0.829632 0.258608 -0.494809 -0.82963 0.258609 -0.420619 -0.869598 0.258585 -0.420621 -0.869604 0.258586 -0.34323 -0.902954 0.258605 -0.343229 -0.90295 0.258605 -0.263225 -0.929428 0.258598 -0.263225 -0.92943 0.258597 -0.181219 -0.948835 0.2586 -0.181219 -0.948834 0.258602 -0.0978324 -0.961017 0.258598 -0.0978324 -0.961018 0.258597 -0.0137025 -0.965888 0.258588 -0.0137022 -0.96589 0.258589 0.0705331 -0.963409 0.258604 0.0705323 -0.963405 0.258603 0.15423 -0.953592 0.25859 0.154231 -0.953595 0.258591 0.236755 -0.936524 0.258582 0.236756 -0.936527 0.258582 0.317479 -0.912328 0.258618 0.317475 -0.912319 0.25862 0.395781 -0.881177 0.258568 0.395788 -0.881189 0.258566 0.471082 -0.843342 0.258569 0.471081 -0.843341 0.258567 0.542792 -0.799074 0.258601 0.542786 -0.799068 0.258601 0.610363 -0.74872 0.258603 0.610363 -0.74872 0.258604 0.673295 -0.692674 0.258591 0.673298 -0.692676 0.25859 0.731107 -0.631358 0.25861 0.731103 -0.631355 0.25861 0.783347 -0.565233 0.258587 0.783352 -0.565237 0.258587 0.829635 -0.494811 0.258627 0.829626 -0.494807 0.258629 0.869593 -0.420617 0.25859 0.869603 -0.420621 0.25859 0.902954 -0.343229 0.258622 0.902945 -0.343227 0.258623 0.929423 -0.263224 0.258617 0.929425 -0.263224 0.258617 0.94883 -0.181218 0.258604 0.948833 -0.181218 0.258604 0.961016 -0.0978338 0.25853 0.961037 -0.0978335 0.258529 0.965906 -0.013702 0.258588 0.96589 -0.0137037 0.608353 0.793587 -0.0112575 0.706828 0.707282 -0.0120695 0.706785 0.703791 -0.0716476 0.70679 0.703786 -0.0716473 0.70679 0.694864 -0.132713 0.706771 0.694882 -0.132715 0.706771 0.680671 -0.192774 0.706758 0.680684 -0.192777 0.706759 0.661291 -0.251369 0.706777 0.661274 -0.251363 0.706777 0.636849 -0.308041 0.706772 0.636854 -0.308043 0.706772 0.607584 -0.362375 0.706787 0.60757 -0.362368 0.706787 0.573676 -0.413943 0.706772 0.573688 -0.413951 0.706772 0.535427 -0.462376 0.706776 0.535423 -0.462373 0.706776 0.493088 -0.507279 0.706781 0.493084 -0.507276 0.706781 0.446996 -0.54832 0.706767 0.447005 -0.548331 0.706767 0.397514 -0.585203 0.706776 0.397509 -0.585196 0.706775 0.344993 -0.617615 0.706781 0.34499 -0.617611 0.706779 0.28985 -0.64533 0.706761 0.289858 -0.645346 0.706762 0.232509 -0.668152 0.706774 0.232504 -0.668141 0.706774 0.173387 -0.685862 0.706769 0.173389 -0.685868 0.706769 0.112952 -0.698369 0.706775 0.11295 -0.698363 0.706776 0.0516546 -0.705549 0.706779 0.0516542 -0.705546 0.706779 -0.0100349 -0.707363 0.706773 -0.0100347 -0.707369 0.706774 -0.0716477 -0.703802 0.706779 -0.0716474 -0.703797 0.706779 -0.132715 -0.694874 0.70677 -0.132716 -0.694883 0.70677 -0.192774 -0.680672 0.706769 -0.192775 -0.680672 0.70677 -0.251365 -0.66128 0.706779 -0.251362 -0.661272 0.70678 -0.308039 -0.636847 0.706772 -0.308042 -0.636855 0.706772 -0.362376 -0.607584 0.706771 -0.362376 -0.607584 0.70677 -0.413952 -0.57369 0.706782 -0.413946 -0.57368 0.706781 -0.46237 -0.53542 0.706767 -0.462379 -0.535431 0.706768 -0.507285 -0.493094 0.706777 -0.507279 -0.493087 0.706776 -0.548324 -0.446999 0.706772 -0.548328 -0.447002 0.706772 -0.585199 -0.397511 0.706777 -0.585195 -0.397508 0.706777 -0.617613 -0.344992 0.706774 -0.617616 -0.344994 0.706775 -0.645334 -0.289852 0.706775 -0.645333 -0.289852 0.706775 -0.66814 -0.232504 0.706771 -0.668143 -0.232506 0.706771 -0.685865 -0.173388 0.706771 -0.685865 -0.173388 0.706771 -0.698367 -0.112951 0.706774 -0.698365 -0.112951 0.706816 -0.705357 -0.0536816 0.793116 -0.607445 -0.0444721 0.980738 -0.194807 -0.0142622 0.965862 -0.25825 -0.0204383 0.965846 -0.255792 -0.0413708 0.965846 -0.255791 -0.0413707 0.965846 -0.251212 -0.063507 0.965847 -0.251211 -0.0635067 0.965847 -0.24472 -0.0851596 0.965846 -0.244721 -0.0851598 0.965847 -0.236367 -0.106164 0.965846 -0.23637 -0.106165 0.965846 -0.226217 -0.126362 0.965846 -0.226217 -0.126363 0.965846 -0.214343 -0.145598 0.965846 -0.214343 -0.145598 0.965846 -0.200838 -0.163725 0.965846 -0.200837 -0.163724 0.965846 -0.185803 -0.180605 0.965846 -0.185803 -0.180605 0.965846 -0.169355 -0.196111 0.965845 -0.169358 -0.196115 0.965845 -0.151621 -0.21013 0.965846 -0.151619 -0.210126 0.965846 -0.132728 -0.222541 0.965847 -0.132727 -0.22254 0.965846 -0.112827 -0.233261 0.965847 -0.112827 -0.233261 0.965847 -0.0920675 -0.242207 0.965846 -0.0920681 -0.242208 0.965846 -0.0706078 -0.249311 0.965846 -0.0706078 -0.249311 0.965846 -0.0486101 -0.254516 0.965846 -0.0486102 -0.254517 0.965846 -0.0262427 -0.257785 0.965846 -0.0262426 -0.257783 0.965846 -0.0036756 -0.259089 0.965845 -0.00367551 -0.259094 0.965845 0.0189201 -0.258428 0.965846 0.0189198 -0.258425 0.965846 0.0413709 -0.255792 0.965847 0.0413702 -0.255789 0.965847 0.0635064 -0.25121 0.965847 0.0635064 -0.25121 0.965847 0.0851592 -0.244719 0.965848 0.0851579 -0.244716 0.965848 0.106162 -0.236362 0.965847 0.106164 -0.236367 0.965847 0.126361 -0.226215 0.965846 0.126362 -0.226216 0.965846 0.145598 -0.214343 0.965846 0.145598 -0.214343 0.965846 0.163725 -0.200838 0.965845 0.163728 -0.200841 0.965845 0.180609 -0.185807 0.965846 0.180605 -0.185803 0.965846 0.196111 -0.169355 0.965846 0.196112 -0.169355 0.965846 0.210126 -0.151619 0.965845 0.21013 -0.151621 0.965845 0.222545 -0.13273 0.965846 0.222542 -0.132729 0.965846 0.233264 -0.112828 0.965847 0.233261 -0.112827 0.965847 0.242207 -0.0920675 0.965846 0.242207 -0.0920677 0.965846 0.24931 -0.0706073 0.965848 0.249305 -0.0706061 0.965848 0.25451 -0.0486094 0.965843 0.254528 -0.0486121 0.965843 0.257796 -0.0262435 0.96585 0.257771 -0.0262418 0.96585 0.259077 -0.00367562 0.965847 0.259088 -0.00367542 -0.830974 0.510122 -0.221942 -0.830972 -0.122424 -0.542676 -0.96578 0.259217 -0.00865678 -0.9807 0.193049 -0.0309657 -0.980699 -0.19469 -0.0180171 -0.9807 -0.194689 -0.0180171 -0.9807 -0.0430268 -0.190727 -0.980699 -0.0430273 -0.190729 -0.980699 -0.0665928 -0.183833 -0.980698 0.179293 -0.0780065 -0.9807 0.179284 -0.0780022 -0.9807 0.168094 -0.0998575 -0.896489 -0.44118 -0.040828 -0.830994 -0.553849 -0.0519661 -0.792815 -0.60687 -0.0561614 -0.5548 -0.0799264 -0.828135 -0.830972 -0.0534435 -0.553741 -0.83097 -0.0534439 -0.553744 -0.9807 -0.0187831 -0.194616 -0.9807 -0.018783 -0.194615 -0.554763 0.798514 -0.233695 -0.830974 0.533916 -0.156257 -0.83096 0.533935 -0.156263 -0.980698 0.187657 -0.0549202 -0.980701 0.187641 -0.0549153 -0.554782 -0.783362 -0.280288 -0.19509 -0.839927 -0.506422 -0.19473 -0.874825 -0.443579 -0.554789 -0.742051 -0.376257 -0.554789 -0.783357 -0.280286 -0.830975 -0.52379 -0.187413 -0.980699 -0.184093 -0.0658688 -0.980699 -0.174386 -0.0884224 -0.830969 -0.49618 -0.251587 -0.830969 -0.460735 -0.311791 -0.554776 -0.68905 -0.466298 -0.554776 -0.625174 -0.548982 -0.9807 -0.161926 -0.10958 -0.9807 -0.146915 -0.12901 -0.830981 -0.418011 -0.367067 -0.83098 -0.368709 -0.416564 -0.554782 -0.551435 -0.623005 -0.554784 -0.469003 -0.687205 -0.194735 -0.552918 -0.81016 -0.195068 -0.483154 -0.853528 -0.980699 -0.129592 -0.146411 -0.980699 -0.11022 -0.161499 -0.830973 -0.313599 -0.459499 -0.830972 -0.253536 -0.495181 -0.554788 -0.379174 -0.740565 -0.554791 -0.283366 -0.782247 -0.9807 -0.110217 -0.161494 -0.9807 -0.0891065 -0.174034 -0.830976 -0.253533 -0.495176 -0.830976 -0.189472 -0.523048 -0.554787 -0.283367 -0.78225 -0.554784 -0.183092 -0.811598 -0.194741 -0.21585 -0.95681 -0.195107 -0.148569 -0.969464 -0.55479 0.128535 -0.822002 -0.195069 0.346479 -0.917551 -0.19473 0.271796 -0.942447 -0.554781 0.230547 -0.799416 -0.554783 0.128535 -0.822006 -0.830977 0.0859442 -0.549628 -0.980698 0.0302071 -0.19318 -0.980698 0.054181 -0.187872 -0.830972 0.154155 -0.534529 -0.83097 0.219935 -0.510996 -0.554784 0.328922 -0.764216 -0.554781 0.422111 -0.716967 -0.980699 0.0772993 -0.179597 -0.980699 0.0991994 -0.168493 -0.830981 0.282237 -0.479388 -0.830983 0.340094 -0.440232 -0.554797 0.508635 -0.6584 -0.5548 0.587143 -0.589458 -0.194729 0.692205 -0.694934 -0.195025 0.752294 -0.629301 -0.980699 0.119533 -0.154729 -0.980699 0.137984 -0.138528 -0.830966 0.392605 -0.394154 -0.830964 0.438912 -0.341841 -0.554807 0.656387 -0.511218 -0.554808 0.715284 -0.42492 -0.9807 0.13798 -0.138524 -0.9807 0.154253 -0.120138 -0.830961 0.438915 -0.341843 -0.830961 0.4783 -0.284138 -0.554775 0.715303 -0.424932 -0.554773 0.762922 -0.33193 -0.194748 0.899415 -0.391314 -0.195098 0.926719 -0.321136 -0.607968 -0.790583 -0.0731628 -0.554802 -0.828377 -0.0773703 -0.44157 -0.89341 -0.0826786 -0.194733 -0.976683 -0.090385 -0.194727 -0.976684 -0.090385 -0.980699 -0.190896 -0.0422761 -0.830975 -0.54315 -0.120287 -0.830974 -0.543152 -0.120287 -0.554782 -0.812314 -0.179896 -0.554781 -0.812315 -0.179896 -0.751911 -0.64367 -0.142548 -0.195047 -0.965028 -0.175153 -0.194727 -0.874825 -0.443579 -0.195079 -0.906213 -0.375129 -0.662125 -0.705588 -0.25246 -0.194878 -0.928017 -0.317501 -0.194964 -0.952141 -0.235406 -0.9807 -0.190896 -0.042276 -0.980699 -0.184092 -0.0658683 -0.830975 -0.523792 -0.187413 -0.830975 -0.496172 -0.251584 -0.55479 -0.742051 -0.376256 -0.55479 -0.689042 -0.466293 -0.599475 -0.662874 -0.448584 -0.194727 -0.650099 -0.734474 -0.195024 -0.713948 -0.672491 -0.762146 -0.486467 -0.42718 -0.194993 -0.75477 -0.626339 -0.194849 -0.80651 -0.558189 -0.9807 -0.174385 -0.0884216 -0.9807 -0.161927 -0.109581 -0.830973 -0.46073 -0.311788 -0.830973 -0.41802 -0.367074 -0.554773 -0.625175 -0.548983 -0.554772 -0.55144 -0.62301 -0.194731 -0.650099 -0.734474 -0.19473 -0.552919 -0.810161 -0.980699 -0.14692 -0.129014 -0.980699 -0.129591 -0.146411 -0.830978 -0.368712 -0.416566 -0.830977 -0.313595 -0.459494 -0.554779 -0.469005 -0.687207 -0.554778 -0.379178 -0.740571 -0.733559 -0.309735 -0.604943 -0.194754 -0.215849 -0.956807 -0.195096 -0.29187 -0.936349 -0.704864 -0.241594 -0.666933 -0.19491 -0.3501 -0.91621 -0.19494 -0.428618 -0.882205 -0.980699 -0.0891075 -0.174036 -0.980699 -0.0665924 -0.183832 -0.830972 -0.189475 -0.523054 -0.830972 -0.122424 -0.542677 -0.554789 -0.183091 -0.811595 -0.554791 -0.0799271 -0.828141 -0.508113 -0.082742 -0.857307 -0.194788 -0.0874087 -0.976943 -0.9807 0.00575688 -0.195434 -0.830976 0.01638 -0.556067 -0.83097 0.0163801 -0.556076 -0.554792 0.0244969 -0.831629 -0.554802 0.0244969 -0.831622 -0.765434 0.0189476 -0.643235 -0.194989 -0.00192997 -0.980803 -0.194736 0.271796 -0.942446 -0.195099 0.205376 -0.95904 -0.508106 0.133062 -0.850954 -0.194815 0.144762 -0.970099 -0.195012 0.0596582 -0.978985 -0.980699 0.00575697 -0.195441 -0.980699 0.0302068 -0.193178 -0.830976 0.0859443 -0.549629 -0.830977 0.154153 -0.534522 -0.55478 0.230547 -0.799417 -0.554783 0.328922 -0.764216 -0.704873 0.280429 -0.651547 -0.194719 0.599649 -0.776212 -0.195046 0.532559 -0.823613 -0.733547 0.344813 -0.585674 -0.194923 0.479805 -0.855448 -0.194895 0.403425 -0.894016 -0.980699 0.0541798 -0.187867 -0.980699 0.0772986 -0.179595 -0.83098 0.219929 -0.510983 -0.830981 0.282237 -0.479388 -0.554772 0.422114 -0.716972 -0.554767 0.508647 -0.658416 -0.19471 0.59965 -0.776214 -0.194709 0.692207 -0.694937 -0.9807 0.0991969 -0.168489 -0.9807 0.119532 -0.154727 -0.830974 0.340101 -0.440242 -0.830973 0.392598 -0.394146 -0.554782 0.587151 -0.589466 -0.554783 0.6564 -0.511229 -0.762151 0.510763 -0.397802 -0.194717 0.89942 -0.391317 -0.195076 0.868283 -0.456103 -0.599478 0.688127 -0.408787 -0.194802 0.837976 -0.509754 -0.194946 0.790337 -0.58083 -0.980701 0.154249 -0.120135 -0.980701 0.168089 -0.0998547 -0.830984 0.47827 -0.284119 -0.830984 0.510108 -0.221936 -0.554799 0.762906 -0.331922 -0.5548 0.798491 -0.233687 -0.662139 0.719213 -0.210486 -0.194884 0.945096 -0.262324 -0.194994 0.973675 -0.118046 -0.980701 0.193044 -0.0309647 -0.830963 0.549306 -0.0881101 -0.83096 0.549311 -0.088111 -0.554781 0.821496 -0.13177 -0.554763 0.821508 -0.131772 -0.751914 0.65094 -0.104413 -0.19497 0.964346 -0.178954 -0.980682 0.19554 -0.00512276 -0.792795 0.609112 -0.0214014 -0.830963 0.556018 -0.0185691 -0.607961 0.793525 -0.026501 -0.554801 0.831496 -0.0284764 -0.258358 0.965546 -0.0311893 -0.194679 0.98032 -0.0327399 0.705614 -0.703343 -0.0861275 0.705615 -0.703342 -0.0861273 0.705615 -0.67554 -0.2139 0.705614 -0.675541 -0.2139 0.705614 -0.624735 -0.334388 0.705613 -0.624735 -0.334388 0.705614 -0.552654 -0.44349 0.705613 -0.552655 -0.44349 0.705612 -0.461754 -0.537489 0.705612 -0.461754 -0.537489 0.705612 -0.355128 -0.613185 0.705611 -0.355129 -0.613185 0.705611 -0.23641 -0.668 0.705617 -0.236408 -0.667994 0.705616 -0.109639 -0.700061 0.705608 -0.10964 -0.700069 0.70561 0.020864 -0.708294 0.705614 0.0208637 -0.708289 0.705615 0.150656 -0.692395 0.70561 0.150657 -0.6924 0.70561 0.27532 -0.652927 0.70561 0.27532 -0.652927 0.705609 0.390608 -0.591221 0.70561 0.390607 -0.59122 0.705609 0.492594 -0.50938 0.705619 0.492586 -0.509372 0.70562 0.577795 -0.410187 0.705612 0.577802 -0.410191 0.705613 0.643335 -0.297036 0.705609 0.643339 -0.297037 0.705608 0.686966 -0.173767 0.705611 0.686963 -0.173766 0.705611 0.707196 -0.0445776 0.705615 0.707191 -0.0445775 -0.705615 0.707191 -0.0445773 -0.705611 0.707196 -0.0445778 -0.705611 0.686963 -0.173766 -0.705608 0.686966 -0.173767 -0.705609 0.643339 -0.297037 -0.705613 0.643335 -0.297036 -0.705612 0.577801 -0.410191 -0.70562 0.577795 -0.410186 -0.705619 0.492586 -0.509372 -0.705609 0.492593 -0.50938 -0.70561 0.390607 -0.59122 -0.705609 0.390608 -0.591221 -0.70561 0.27532 -0.652927 -0.70561 0.27532 -0.652927 -0.70561 0.150657 -0.6924 -0.705615 0.150656 -0.692395 -0.705614 0.0208639 -0.708289 -0.70561 0.0208638 -0.708294 -0.705608 -0.10964 -0.700069 -0.705616 -0.109639 -0.700061 -0.705617 -0.236408 -0.667994 -0.705611 -0.23641 -0.668 -0.705611 -0.355129 -0.613185 -0.705612 -0.355128 -0.613185 -0.705612 -0.461754 -0.537489 -0.705612 -0.461754 -0.537489 -0.705613 -0.552655 -0.44349 -0.705614 -0.552654 -0.44349 -0.705613 -0.624735 -0.334389 -0.705614 -0.624735 -0.334388 -0.705614 -0.675541 -0.2139 -0.705615 -0.67554 -0.2139 -0.705615 -0.703342 -0.0861274 -0.705614 -0.703343 -0.0861275 0 0.987172 0.159661 0 0.987172 0.159661 0 0.981056 -0.193722 0 0.981056 -0.193722 0 0.799851 -0.600199 0 0.799851 -0.600199 0 0.460224 -0.887803 0 0.460224 -0.887803 0 0.0294438 -0.999566 0 0.0294438 -0.999566 0 -0.407167 -0.913354 0 -0.407167 -0.913354 0 -0.763138 -0.646236 0 -0.763138 -0.646236 0 -0.967953 -0.251131 0 -0.967953 -0.251131 0 0.98717 0.159672 0 0.98717 0.159672 0 0.992664 0.120908 -0.0230722 0.963666 0.266112 -0.0179382 0.731981 0.681088 -0.00299072 0.774099 0.633057 0.00272135 0.931602 0.363469 -0.00102392 0.178043 0.984022 -0.015165 0.328092 0.944524 -0.0168072 0.334795 0.942141 0.002904 0.511995 0.858984 -0.00305534 0.63327 0.773925 0.00245953 -0.0472592 0.99888 -0.0182305 -0.138065 0.990255 0.00010246 -0.294546 0.955637 -0.000131605 -0.465121 0.885247 -0.0217734 -0.579675 0.814557 0.000127567 -0.662045 0.749464 -5.05257e-05 -0.791183 0.61158 -0.01743 -0.890373 0.454897 0 -0.913656 0.406488 0 0.985424 0.170116 -0.0190913 0.964899 0.261926 -0.00602331 0.935151 0.354198 -0.00266485 0.646234 0.763134 -0.019539 0.756196 0.654053 -0.0137659 0.740883 0.671493 3.08992e-05 0.849625 0.527387 -2.53635e-05 0.898483 0.439007 0.00491754 0.458211 0.88883 -0.0185595 0.355254 0.934586 0.000114345 0.214204 0.976789 -0.000122573 0.0310841 0.999517 -0.0205989 -0.107757 0.993964 0.000124507 -0.202858 0.979208 -4.39123e-05 -0.383403 0.923581 -0.016016 -0.547307 0.836779 0 -0.588005 0.808857 0 0.998289 0.058468 -0.00524546 0.982222 0.187649 -0.0176946 0.966617 0.255613 -0.00601153 0.941236 0.337696 0.00773926 0.841016 0.540956 -0.0184401 0.753868 0.656767 0.000129053 0.664184 0.747569 -0.000104417 0.515518 0.856878 -0.0186159 0.385642 0.922461 0.0106294 0.263074 0.964717 -0.0138943 -0.0621269 0.997972 0 -0.104799 0.994493 0 0.992375 0.123253 -0.0162608 0.97001 0.24252 0.000138985 0.942781 0.333412 -7.27611e-05 0.865465 0.50097 -0.0152285 0.77747 0.628736 0.00884419 0.710696 0.703443 -0.0107835 0.436585 0.899599 0 0.406481 0.913659 0 0.998293 0.0584056 -0.00751468 0.974588 0.223877 0.00292928 0.964802 0.262961 -0.00327934 0.814746 0.579808 0 0.808852 0.588013 0 0.981057 -0.193719 0 0.981057 -0.193719 0 0.799854 -0.600194 0 0.799854 -0.600194 0 0.46022 -0.887805 0 0.46022 -0.887805 0 0.0294436 -0.999566 0 0.0294436 -0.999566 0 -0.407169 -0.913353 0 -0.407169 -0.913353 0 -0.763135 -0.646239 0 -0.763135 -0.646239 0 -0.967953 -0.251131 0 -0.967953 -0.251131 0 0.973127 -0.230267 0 0.973127 -0.230267 0 0.727619 -0.685982 0 0.727619 -0.685982 0 0.28715 -0.957886 0 0.28715 -0.957886 0 -0.230267 -0.973127 0 -0.230267 -0.973127 0 -0.685979 -0.727621 0 -0.685979 -0.727621 0 -0.957886 -0.287149 0 -0.957886 -0.287149 0 0.973129 -0.230259 0 0.973129 -0.230259 0 0.727616 -0.685985 0 0.727616 -0.685985 0 0.287148 -0.957886 0 0.287148 -0.957886 0 -0.230267 -0.973128 0 -0.230267 -0.973128 0 -0.685979 -0.727621 0 -0.685979 -0.727621 0 -0.957886 -0.287149 0 -0.957886 -0.287149 0 0.973129 -0.230259 0 0.973129 -0.230259 0 0.727616 -0.685985 0 0.727616 -0.685985 0 0.287149 -0.957886 0 0.287149 -0.957886 0 -0.230269 -0.973127 0 -0.230269 -0.973127 0 -0.685978 -0.727622 0 -0.685978 -0.727622 0 -0.957886 -0.287149 0 -0.957886 -0.287149 0 0.973127 -0.230268 0 0.973127 -0.230268 0 0.727621 -0.685979 0 0.727621 -0.685979 0 0.287143 -0.957888 0 0.287143 -0.957888 0 -0.230265 -0.973128 0 -0.230265 -0.973128 0 -0.685979 -0.727621 0 -0.685979 -0.727621 0 -0.957886 -0.287149 0 -0.957886 -0.287149 0 0.973129 -0.230259 0 0.973129 -0.230259 0 0.727619 -0.685982 0 0.727619 -0.685982 0 0.287147 -0.957886 0 0.287147 -0.957886 0 -0.230267 -0.973127 0 -0.230267 -0.973127 0 -0.685984 -0.727617 0 -0.685984 -0.727617 0 -0.957886 -0.287149 0 -0.957886 -0.287149 0 0.981056 -0.193722 0 0.981056 -0.193722 0 0.799851 -0.600199 0 0.799851 -0.600199 0 0.46022 -0.887805 0 0.46022 -0.887805 0 0.0294436 -0.999566 0 0.0294436 -0.999566 0 -0.407161 -0.913357 0 -0.407161 -0.913357 0 -0.76314 -0.646233 0 -0.76314 -0.646233 0 -0.967953 -0.251131 0 -0.967953 -0.251131 0 0.981057 -0.193721 0 0.981057 -0.193721 0 0.799851 -0.600198 0 0.799851 -0.600198 0 0.460224 -0.887803 0 0.460224 -0.887803 0 0.0294438 -0.999566 0 0.0294438 -0.999566 0 -0.407169 -0.913353 0 -0.407169 -0.913353 0 -0.763133 -0.646242 0 -0.763133 -0.646242 0 -0.967954 -0.251129 0 -0.967954 -0.251129 0 0.973128 -0.230265 0 0.973128 -0.230265 0 0.727619 -0.685982 0 0.727619 -0.685982 0 0.287149 -0.957886 0 0.287149 -0.957886 0 -0.230268 -0.973127 0 -0.230268 -0.973127 0 -0.685979 -0.727621 0 -0.685979 -0.727621 0 -0.957886 -0.287148 0 -0.957886 -0.287148 0 0.981057 -0.193719 0 0.981057 -0.193719 0 0.79985 -0.6002 0 0.79985 -0.6002 0 0.460224 -0.887803 0 0.460224 -0.887803 0 0.0294438 -0.999566 0 0.0294438 -0.999566 0 -0.407167 -0.913354 0 -0.407167 -0.913354 0 -0.763135 -0.646239 0 -0.763135 -0.646239 0 -0.967953 -0.25113 0 -0.967953 -0.25113 0 0.973128 -0.230265 0 0.973128 -0.230265 0 0.72762 -0.68598 0 0.72762 -0.68598 0 0.287148 -0.957886 0 0.287148 -0.957886 0 -0.230268 -0.973127 0 -0.230268 -0.973127 0 -0.685979 -0.727621 0 -0.685979 -0.727621 0 -0.957886 -0.287147 0 -0.957886 -0.287147 1.54415e-07 0.719192 0.694811 -1.81755e-06 0.547819 0.836597 0.0026077 0.497182 0.867642 -0.00577453 0.343109 0.939278 0 0.28598 0.958236 0 0.995319 0.0966426 0.0102393 0.964992 0.262078 0.00864848 0.967678 0.252039 3.03966e-07 0.911558 0.411172 -5.71228e-07 0.858379 0.513016 -0.0028996 0.829337 0.558742 0.00842825 0.680771 0.732448 0 0.998672 0.0515218 -0.00295939 0.980416 0.196913 0.00532001 0.966436 0.256853 -0.00526165 0.848706 0.528839 -0.0128004 0.813376 0.581597 0 0.720095 0.693875 0 0.981984 0.188963 0 0.981984 0.188963 -0.000263156 0.879214 0.476427 0.00198861 0.762154 0.647393 0.00249301 0.764103 0.645089 -0.00297541 0.450243 0.892901 0 0.436609 0.899651 3.22145e-08 0.884815 0.465942 -2.44957e-06 0.970138 0.242552 0 0.970135 0.242565 0 0.725001 0.688748 0.0109788 0.859424 0.511146 -0.00531104 0.815422 0.578843 0.00402017 0.974871 0.222732 0 0.980404 0.196999 -0.70539 0.707146 -0.0486765 -0.705392 0.707144 -0.0486765 -0.705392 0.68406 -0.185698 -0.705393 0.684059 -0.185698 -0.705394 0.634687 -0.315583 -0.705395 0.634686 -0.315582 -0.705394 0.560924 -0.43334 -0.705391 0.560926 -0.433341 -0.705392 0.465607 -0.534446 -0.705387 0.46561 -0.534449 -0.705387 0.352398 -0.615016 -0.70539 0.352396 -0.615014 -0.705391 0.225642 -0.671944 -0.705397 0.22564 -0.671938 -0.705397 0.0902152 -0.703048 -0.705393 0.090216 -0.703052 -0.705394 -0.0486762 -0.707142 -0.705392 -0.0486763 -0.707144 -0.705394 -0.185698 -0.684059 -0.705394 -0.185698 -0.684059 -0.705394 -0.315583 -0.634687 -0.705393 -0.315583 -0.634688 -0.705393 -0.43334 -0.560925 -0.705387 -0.433344 -0.56093 -0.705387 -0.534449 -0.46561 -0.705395 -0.534444 -0.465605 -0.705395 -0.615009 -0.352394 -0.705393 -0.615011 -0.352395 -0.705393 -0.671943 -0.225641 -0.70539 -0.671945 -0.225642 -0.70539 -0.703055 -0.0902159 -0.705393 -0.703052 -0.0902154 -0.705615 0.707191 -0.0445773 -0.705611 0.707196 -0.0445778 -0.705611 0.686963 -0.173766 -0.705608 0.686966 -0.173767 -0.705609 0.643339 -0.297037 -0.705613 0.643335 -0.297036 -0.705612 0.577801 -0.410191 -0.70562 0.577795 -0.410186 -0.705619 0.492586 -0.509372 -0.705609 0.492593 -0.50938 -0.70561 0.390607 -0.59122 -0.705609 0.390608 -0.591221 -0.70561 0.27532 -0.652927 -0.70561 0.27532 -0.652927 -0.70561 0.150657 -0.6924 -0.705615 0.150656 -0.692395 -0.705614 0.0208639 -0.708289 -0.70561 0.0208638 -0.708294 -0.705608 -0.10964 -0.700069 -0.705616 -0.109639 -0.700061 -0.705617 -0.236408 -0.667994 -0.705611 -0.23641 -0.668 -0.705611 -0.355129 -0.613185 -0.705612 -0.355128 -0.613185 -0.705612 -0.461754 -0.537489 -0.705612 -0.461754 -0.537489 -0.705613 -0.552655 -0.44349 -0.705614 -0.552654 -0.44349 -0.705613 -0.624735 -0.334389 -0.705614 -0.624735 -0.334388 -0.705614 -0.675541 -0.2139 -0.705615 -0.67554 -0.2139 -0.705615 -0.703342 -0.0861274 -0.705614 -0.703343 -0.0861275 -0.705779 0.707248 -0.0409377 -0.705784 0.707243 -0.0409372 -0.705784 0.68939 -0.163127 -0.705778 0.689396 -0.163128 -0.705778 0.650595 -0.280362 -0.705774 0.650599 -0.280364 -0.705775 0.59203 -0.389079 -0.705771 0.592033 -0.389082 -0.705771 0.515475 -0.485976 -0.705782 0.515467 -0.485968 -0.705782 0.423249 -0.568096 -0.705783 0.423248 -0.568094 -0.705782 0.31817 -0.632961 -0.705768 0.318176 -0.632973 -0.70577 0.203427 -0.678606 -0.705779 0.203425 -0.678598 -0.705778 0.0824969 -0.703613 -0.705779 0.0824969 -0.703613 -0.705779 -0.0409374 -0.707248 -0.705778 -0.0409376 -0.70725 -0.705778 -0.163128 -0.689396 -0.705778 -0.163128 -0.689396 -0.705778 -0.280362 -0.650595 -0.705774 -0.280364 -0.650599 -0.705775 -0.38908 -0.59203 -0.705776 -0.389079 -0.592028 -0.705776 -0.485973 -0.515472 -0.705782 -0.485968 -0.515467 -0.705782 -0.568096 -0.423249 -0.705777 -0.568099 -0.423251 -0.705778 -0.632965 -0.318172 -0.705779 -0.632964 -0.318171 -0.705779 -0.678598 -0.203425 -0.705777 -0.678599 -0.203425 -0.705778 -0.703614 -0.0824969 -0.705779 -0.703612 -0.0824967 -0.705778 0.70725 -0.0409377 -0.705778 0.70725 -0.0409377 -0.705778 0.689396 -0.163128 -0.705779 0.689395 -0.163128 -0.705779 0.650594 -0.280362 -0.705781 0.650593 -0.280361 -0.70578 0.592025 -0.389077 -0.705777 0.592028 -0.389078 -0.705776 0.515472 -0.485973 -0.705773 0.515474 -0.485974 -0.705772 0.423254 -0.568103 -0.705779 0.42325 -0.568098 -0.705779 0.318171 -0.632964 -0.70578 0.318171 -0.632963 -0.70578 0.203424 -0.678597 -0.705777 0.203425 -0.678599 -0.705777 0.0824971 -0.703614 -0.70578 0.0824966 -0.703611 -0.705779 -0.0409378 -0.707249 -0.705778 -0.0409378 -0.707249 -0.705778 -0.163128 -0.689396 -0.705779 -0.163128 -0.689395 -0.705781 -0.280361 -0.650593 -0.705783 -0.28036 -0.650591 -0.705784 -0.389074 -0.592022 -0.70578 -0.389076 -0.592025 -0.70578 -0.485969 -0.515468 -0.705782 -0.485968 -0.515467 -0.705783 -0.568095 -0.423248 -0.705779 -0.568098 -0.42325 -0.705779 -0.632964 -0.318171 -0.705774 -0.632968 -0.318173 -0.705774 -0.678603 -0.203426 -0.70579 -0.678587 -0.203421 -0.705791 -0.703601 -0.0824952 -0.705779 -0.703612 -0.082497 0.705393 -0.703051 -0.0902158 0.705394 -0.703051 -0.0902158 0.705394 -0.671942 -0.225641 0.705392 -0.671944 -0.225641 0.705392 -0.615012 -0.352396 0.705393 -0.615011 -0.352395 0.705393 -0.534445 -0.465607 0.705392 -0.534446 -0.465607 0.705392 -0.433341 -0.560926 0.705389 -0.433343 -0.560928 0.70539 -0.315584 -0.63469 0.705394 -0.315583 -0.634687 0.705394 -0.185698 -0.684059 0.705392 -0.185698 -0.68406 0.705392 -0.0486763 -0.707144 0.705394 -0.0486762 -0.707142 0.705393 0.0902158 -0.703052 0.705389 0.0902164 -0.703056 0.705387 0.225643 -0.671948 0.705391 0.225642 -0.671945 0.70539 0.352396 -0.615014 0.705393 0.352395 -0.615011 0.705392 0.465607 -0.534445 0.705392 0.465607 -0.534446 0.705392 0.560926 -0.433341 0.705391 0.560926 -0.433342 0.705391 0.634689 -0.315584 0.705392 0.634688 -0.315584 0.705393 0.68406 -0.185698 0.705398 0.684054 -0.185696 0.705398 0.707138 -0.0486758 0.705393 0.707143 -0.048676 -0.70542 0.707117 -0.0486744 -0.705425 0.707112 -0.0486738 -0.705424 0.684029 -0.185689 -0.705419 0.684034 -0.185691 -0.705419 0.634664 -0.315572 -0.705418 0.634665 -0.315572 -0.705418 0.560906 -0.433325 -0.705418 0.560905 -0.433325 -0.705418 0.46559 -0.534426 -0.705419 0.46559 -0.534425 -0.70542 0.352382 -0.614988 -0.705417 0.352383 -0.614991 -0.705417 0.225633 -0.67192 -0.705413 0.225635 -0.671924 -0.705415 0.0902129 -0.70303 -0.705419 0.0902126 -0.703026 -0.70542 -0.0486743 -0.707116 -0.705418 -0.0486746 -0.707118 -0.705418 -0.185691 -0.684035 -0.70542 -0.185691 -0.684033 -0.70542 -0.315571 -0.634663 -0.705416 -0.315573 -0.634667 -0.705416 -0.433327 -0.560907 -0.705418 -0.433325 -0.560905 -0.705418 -0.534426 -0.46559 -0.705419 -0.534425 -0.465589 -0.70542 -0.614988 -0.352382 -0.705418 -0.614989 -0.352382 -0.705418 -0.671919 -0.225633 -0.70542 -0.671917 -0.225632 -0.70542 -0.703025 -0.0902125 -0.70542 -0.703025 -0.0902125 -0.705393 0.707143 -0.048676 -0.705394 0.707142 -0.0486759 -0.705394 0.684058 -0.185698 -0.705393 0.684059 -0.185698 -0.705393 0.634688 -0.315583 -0.705388 0.634692 -0.315585 -0.705388 0.560929 -0.433343 -0.705388 0.560929 -0.433344 -0.705389 0.465609 -0.534448 -0.705389 0.465609 -0.534448 -0.705389 0.352396 -0.615014 -0.70539 0.352396 -0.615014 -0.705391 0.225642 -0.671945 -0.705395 0.22564 -0.67194 -0.705395 0.0902156 -0.70305 -0.705394 0.0902156 -0.703051 -0.705393 -0.0486763 -0.707143 -0.705394 -0.0486762 -0.707142 -0.705393 -0.185698 -0.684059 -0.705394 -0.185698 -0.684059 -0.705394 -0.315582 -0.634687 -0.705391 -0.315584 -0.634689 -0.705391 -0.433342 -0.560927 -0.705391 -0.433342 -0.560926 -0.705392 -0.534446 -0.465607 -0.705392 -0.534446 -0.465607 -0.705392 -0.615012 -0.352395 -0.705392 -0.615012 -0.352395 -0.705392 -0.671943 -0.225641 -0.705392 -0.671943 -0.225641 -0.705392 -0.703052 -0.0902159 -0.705391 -0.703054 -0.090216 -0.705607 0.7072 -0.0445783 -0.705606 0.707201 -0.0445783 -0.705606 0.686968 -0.173767 -0.705605 0.686969 -0.173767 -0.705605 0.643342 -0.297039 -0.705605 0.643343 -0.297039 -0.705605 0.577807 -0.410195 -0.705603 0.577809 -0.410196 -0.705603 0.492598 -0.509384 -0.705606 0.492595 -0.509382 -0.705606 0.39061 -0.591223 -0.705607 0.390609 -0.591222 -0.705606 0.275321 -0.65293 -0.705607 0.275321 -0.65293 -0.705606 0.150658 -0.692403 -0.705609 0.150657 -0.692401 -0.705608 0.020864 -0.708296 -0.705605 0.0208642 -0.708298 -0.705605 -0.109641 -0.700072 -0.705602 -0.109641 -0.700075 -0.705602 -0.236413 -0.668008 -0.7056 -0.236413 -0.66801 -0.705599 -0.355135 -0.613196 -0.705608 -0.355131 -0.613189 -0.705608 -0.461757 -0.537493 -0.705601 -0.461761 -0.537498 -0.7056 -0.552665 -0.443498 -0.70561 -0.552657 -0.443491 -0.705611 -0.624738 -0.33439 -0.705608 -0.62474 -0.334391 -0.705608 -0.675547 -0.213902 -0.705608 -0.675547 -0.213902 -0.705608 -0.703349 -0.0861282 -0.705607 -0.70335 -0.0861284 0 -0.999864 0.0165222 -7.89463e-10 -0.999864 0.0165222 0 -0.580833 0.814023 -0.00906362 -0.676404 0.736475 0.00422442 -0.745068 0.666975 -0.00531403 -0.901228 0.433312 -0.00130118 -0.911642 0.410983 0.00126352 -0.99346 0.114177 0 -0.992475 0.12245 0 0.997157 0.0753543 0 0.997157 0.0753543 0 0.994225 0.107318 0 0.994225 0.107318 0 0.619954 0.784638 -0.00116189 0.629623 0.7769 0.000501069 0.801909 0.597446 -0.00379715 0.860534 0.509379 0.0085165 0.957852 0.287137 0 0.980489 0.196575 0.701668 0.44172 0.559058 0.729581 0.469138 0.497616 0.705751 0.56812 0.423266 0.69474 0.68897 0.206534 0.694741 0.68897 0.206534 0.694741 0.493398 0.523348 0.703419 0.700125 0.122582 0.558633 0.794486 0.238164 0.704633 0.643451 0.299104 0.694741 0.493398 0.523348 0.706726 0.705475 0.0533122 0.706727 0.705475 0.0533122 0.706727 0.705475 0.0533115 0.706727 0.705475 0.0533122 0.706021 0.704101 0.0760017 0.706021 0.704101 0.0760017 -0.422261 -0.90635 0.0149848 -0.422249 -0.906356 0.0149824 0.504734 0.86082 0.0650515 0.504734 0.860821 0.0650514 -0.70604 -0.707335 0.0344326 -0.706033 -0.707342 0.0344039 -0.706746 -0.707371 0.0116889 -0.706739 -0.707378 0.0117058 -0.706746 -0.707371 0.0116951 -0.706738 -0.707378 0.0116944 -0.701817 -0.705087 0.101516 -0.732083 -0.676761 0.0777765 -0.681464 -0.672713 0.288208 -0.64116 -0.691617 0.332534 -0.775474 -0.459405 0.433114 -0.700675 -0.482619 0.525484 -0.694755 -0.523335 0.493393 -0.658237 -0.515124 0.548972 -0.723174 -0.64735 0.240743 -0.700499 -0.652765 0.288444 -0.704153 -0.706898 0.0668091 -0.704458 -0.706679 0.0659123 0 0.994225 0.107318 0 0.994225 0.107318 -0.00111281 0.889306 0.457311 0.000519419 0.728568 0.684974 -0.00596467 0.64015 0.768227 0 0.569552 0.821955 0 0.992358 0.123392 -0.00190544 0.988479 0.151346 0.00124295 0.953056 0.302791 -0.00849861 0.858261 0.513143 0 0.997157 0.0753543 0 0.997157 0.0753543 0 -0.999996 -0.00278965 0.00159149 -0.998726 0.050438 0.00710661 -0.989769 0.142504 -0.00285499 -0.976394 0.215977 0.00285115 -0.898332 0.439308 -0.0041938 -0.919185 0.393803 0.00395675 -0.80425 0.594278 0.02046 -0.727468 0.685836 0 -0.645111 0.764089 0 -0.999981 -0.00615351 0.000589492 -0.999863 0.0165222 0 -0.999208 0.0397839 0 0.981057 -0.193718 0 0.981057 -0.193718 0 0.79985 -0.6002 0 0.79985 -0.6002 0 0.460226 -0.887802 0 0.460225 -0.887802 0 0.0294446 -0.999566 0 0.0294446 -0.999566 0 -0.407168 -0.913353 0 -0.407168 -0.913353 0 -0.763136 -0.646238 0 -0.763136 -0.646238 0 -0.967954 -0.251129 0 -0.967954 -0.251129 0 0.981057 -0.19372 0 0.981057 -0.19372 0 0.799851 -0.600199 0 0.799851 -0.600199 0 0.460223 -0.887803 0 0.460223 -0.887803 0 0.0294446 -0.999566 0 0.0294446 -0.999566 0 -0.407168 -0.913353 0 -0.407168 -0.913353 0 -0.763134 -0.64624 0 -0.763134 -0.64624 0 -0.967953 -0.251131 0 -0.967953 -0.251131 0 0.981057 -0.19372 0 0.981057 -0.19372 0 0.799851 -0.600198 0 0.799851 -0.600198 0 0.460223 -0.887804 0 0.460223 -0.887804 0 0.0294446 -0.999566 0 0.0294446 -0.999566 0 -0.407168 -0.913353 0 -0.407168 -0.913353 0 -0.763135 -0.646239 0 -0.763135 -0.646239 0 -0.967953 -0.25113 0 -0.967953 -0.25113 0 0.981057 -0.19372 0 0.981057 -0.19372 0 0.799851 -0.600198 0 0.799851 -0.600198 0 0.460219 -0.887806 0 0.460219 -0.887806 0 0.0294446 -0.999566 0 0.0294446 -0.999566 0 -0.407169 -0.913353 0 -0.407169 -0.913353 0 -0.763131 -0.646243 0 -0.763131 -0.646243 0 -0.967954 -0.251129 0 -0.967954 -0.251129 0 0.981057 -0.193718 0 0.981057 -0.193718 0 0.799852 -0.600197 0 0.799852 -0.600197 0 0.460224 -0.887803 0 0.460224 -0.887803 0 0.029438 -0.999567 0 0.029438 -0.999567 0 -0.407163 -0.913355 0 -0.407163 -0.913355 0 -0.763134 -0.64624 0 -0.763134 -0.64624 0 -0.967953 -0.251132 0 -0.967953 -0.251132 0 0.409862 -0.912148 0 0.973126 -0.230271 0 0.973126 -0.230271 0 0.727622 -0.685979 0.0184928 0.634295 -0.77287 0 0.811372 -0.58453 0.0190712 0.158909 -0.987109 0 0.287143 -0.957888 0 -0.102173 -0.994767 0.00947059 -0.230249 -0.973086 0 -0.35617 -0.934421 0 -0.685985 -0.727616 0 -0.685985 -0.727616 0 -0.957888 -0.287143 0 -0.957888 -0.287143 0 0.994957 -0.100304 0.0184578 0.935834 -0.351957 0 0.973126 -0.230271 0 0.810923 -0.585153 0.00959946 0.727588 -0.685947 0 0.631836 -0.775102 0 0.408861 -0.912597 0.00946981 0.287135 -0.957843 0 0.158735 -0.987321 0 -0.230267 -0.973127 0 -0.230267 -0.973127 0 -0.685979 -0.727622 0 -0.685979 -0.727622 0 -0.957887 -0.287145 0 -0.957887 -0.287145 0 0.981057 -0.193717 0 0.981057 -0.193717 0 0.799852 -0.600198 0 0.799852 -0.600198 0 0.460227 -0.887801 0 0.460227 -0.887801 0 0.0294426 -0.999566 0 0.0294426 -0.999566 0 -0.407168 -0.913354 0 -0.407168 -0.913354 0 -0.763134 -0.64624 0 -0.763134 -0.64624 0 -0.967956 -0.25112 0 -0.967956 -0.25112 0 0.981057 -0.193717 0 0.981057 -0.193717 0 0.799852 -0.600198 0 0.799852 -0.600198 0 0.460227 -0.887801 0 0.460227 -0.887801 0 0.0294443 -0.999566 0 0.0294443 -0.999566 0 -0.407169 -0.913353 0 -0.407169 -0.913353 0 -0.763134 -0.64624 0 -0.763134 -0.64624 0 -0.967956 -0.251121 0 -0.967956 -0.251121 0 0.981057 -0.193718 0 0.981057 -0.193718 0 0.799853 -0.600196 0 0.799853 -0.600196 0 0.460216 -0.887807 0 0.460216 -0.887807 0 0.0294447 -0.999566 0 0.0294447 -0.999566 0 -0.407163 -0.913355 0 -0.407163 -0.913355 0 -0.763134 -0.64624 0 -0.763134 -0.64624 0 -0.967953 -0.251132 0 -0.967953 -0.251132 0 0.981055 -0.193731 0 0.981055 -0.193731 0 0.799851 -0.600199 0 0.79985 -0.600199 0 0.460227 -0.887801 0 0.460227 -0.887801 0 0.0294514 -0.999566 0 0.0294514 -0.999566 0 -0.40717 -0.913353 0 -0.40717 -0.913353 0 -0.763141 -0.646232 0 -0.763141 -0.646232 0 -0.967952 -0.251136 0 -0.967952 -0.251136 0 0.981057 -0.193718 0 0.981057 -0.193718 0 0.799852 -0.600197 0 0.799852 -0.600197 0 0.460219 -0.887806 0 0.460219 -0.887806 0 0.0294447 -0.999566 0 0.0294447 -0.999566 0 -0.407169 -0.913353 0 -0.407169 -0.913353 0 -0.763131 -0.646243 0 -0.763131 -0.646243 0 -0.967953 -0.251132 0 -0.967953 -0.251132 0.705156 -0.70268 -0.0948469 0.705157 -0.702679 -0.0948467 0.705157 -0.667604 -0.238869 0.705155 -0.667606 -0.23887 0.705155 -0.603354 -0.372453 0.705155 -0.603354 -0.372453 0.705155 -0.512731 -0.489759 0.705157 -0.51273 -0.489756 0.705157 -0.399699 -0.585657 0.705157 -0.399699 -0.585657 0.705157 -0.2692 -0.655961 0.705156 -0.2692 -0.655962 0.705155 -0.126935 -0.697599 0.705156 -0.126935 -0.697597 0.705157 0.0208772 -0.708744 0.705157 0.0208772 -0.708744 0.705156 0.167777 -0.688916 0.705156 0.167777 -0.688917 0.705156 0.307345 -0.638979 0.705157 0.307345 -0.638978 0.705156 0.433479 -0.561115 0.705154 0.433481 -0.561117 0.705154 0.540672 -0.458729 0.705156 0.54067 -0.458728 0.705156 0.62423 -0.336293 0.705155 0.62423 -0.336293 0.705155 0.680509 -0.199159 0.705157 0.680507 -0.199158 0.705157 0.707043 -0.0533212 0.705157 0.707043 -0.0533212 0.705758 -0.703633 -0.0824993 0.705757 -0.703635 -0.0824989 0.705757 -0.678619 -0.203431 0.705757 -0.678619 -0.203431 0.705757 -0.632984 -0.318181 0.705756 -0.632984 -0.318181 0.705756 -0.568116 -0.423264 0.705757 -0.568115 -0.423264 0.705757 -0.485985 -0.515485 0.705756 -0.485986 -0.515486 0.705756 -0.38909 -0.592045 0.705756 -0.38909 -0.592045 0.705756 -0.280371 -0.650615 0.705757 -0.28037 -0.650615 0.705757 -0.163133 -0.689416 0.705757 -0.163133 -0.689416 0.705757 -0.0409392 -0.707271 0.705757 -0.0409389 -0.70727 0.705757 0.0824994 -0.703634 0.705757 0.0824993 -0.703634 0.705757 0.203431 -0.678618 0.705757 0.203431 -0.678619 0.705757 0.318181 -0.632984 0.705757 0.318181 -0.632984 0.705757 0.423264 -0.568116 0.705757 0.423264 -0.568115 0.705757 0.515485 -0.485986 0.705757 0.515485 -0.485985 0.705757 0.592044 -0.389089 0.705757 0.592045 -0.389089 0.705757 0.650615 -0.280371 0.705757 0.650615 -0.280371 0.705757 0.689416 -0.163133 0.705757 0.689416 -0.163133 0.705757 0.70727 -0.0409388 0.705757 0.70727 -0.0409389 0.202051 -0.975012 0.0923391 0.839737 -0.54207 0.0316677 0.839522 -0.543284 0.00671974 0.203238 -0.979055 0.0121122 0.202039 -0.979301 0.01221 0.576261 -0.817205 0.0100145 0.202038 -0.975015 0.0923383 0.202193 -0.969782 0.136535 0.146804 -0.974076 0.17212 0.202105 -0.963522 0.175441 0.202067 -0.947611 0.247393 0.202052 -0.947614 0.247392 0.202196 -0.933373 0.296532 0.098384 -0.939554 0.327963 0.202148 -0.920701 0.333836 0.202069 -0.895719 0.396051 0.202085 -0.895715 0.396051 0.202207 -0.870767 0.448192 0.0782856 -0.87642 0.475141 0.202165 -0.852039 0.482866 0.202053 -0.820679 0.534473 0.202072 -0.820675 0.534472 0.202166 -0.783724 0.587287 0.0871654 -0.788369 0.608996 0.202202 -0.759459 0.618334 0.202066 -0.72442 0.659079 0.202068 -0.724419 0.659079 0.202067 -0.669095 0.715179 0.105545 -0.68505 0.72081 0.202207 -0.645569 0.736447 0.202057 -0.609441 0.766652 0.202059 -0.609441 0.766651 0.20206 -0.54584 0.813161 0.189361 -0.548113 0.814687 0.202216 -0.513536 0.8339 0.20206 -0.478708 0.854407 0.20206 -0.478707 0.854407 0.202061 -0.408477 0.890123 0.202069 -0.408475 0.890121 0.202223 -0.367122 0.907925 0.142094 -0.339192 0.929924 0.202113 -0.330311 0.921979 0.202071 -0.260553 0.944076 0.202065 -0.260554 0.944077 0.202206 -0.210389 0.956478 0.0957903 -0.186829 0.977711 0.202148 -0.171746 0.964178 0.202066 -0.105897 0.97363 0.202066 -0.105897 0.97363 0.202186 -0.0477491 0.978182 0.0779537 -0.0277785 0.99657 0.202178 -0.00836381 0.979313 0.202064 0.0514976 0.978017 0.202063 0.0514975 0.978018 0.202154 0.116232 0.972432 0.0890568 0.132159 0.98722 0.202195 0.155253 0.966961 0.202057 0.20756 0.957127 0.20206 0.20756 0.957126 0.20206 0.283828 0.937344 0.112153 0.281007 0.95313 0.202221 0.314513 0.927463 0.202069 0.358258 0.911493 0.202067 0.358258 0.911493 0.202067 0.43037 0.879745 0.202062 0.43037 0.879746 0.202062 0.499696 0.842303 0.202063 0.499696 0.842303 0.202064 0.565788 0.799409 0.202055 0.565789 0.79941 0.202209 0.602319 0.77222 0.1375 0.635357 0.759879 0.20211 0.632908 0.747381 0.202065 0.686582 0.698409 0.202063 0.686582 0.698409 0.202204 0.722792 0.660822 0.093376 0.752796 0.651598 0.202146 0.748797 0.631221 0.20206 0.78963 0.579358 0.202062 0.78963 0.579358 0.202181 0.822977 0.530878 0.0777754 0.848626 0.523244 0.202181 0.843666 0.497344 0.202064 0.872267 0.445331 0.202063 0.872268 0.445331 0.202152 0.900064 0.38603 0.09113 0.920463 0.380056 0.202202 0.914854 0.349508 0.202063 0.93236 0.299794 0.202064 0.932359 0.299794 0.202064 0.953441 0.223875 0.118747 0.96507 0.233535 0.202216 0.960363 0.191864 0.202064 0.968352 0.146508 0.202063 0.968352 0.146508 0.202063 0.976996 0.0681918 0.202065 0.976995 0.0681916 0.840828 -0.541263 0.00652977 0.573247 -0.819318 0.0103267 0.573268 -0.815718 0.0772529 0.57327 -0.815716 0.0772529 0.57327 -0.806867 0.142574 0.573268 -0.806868 0.142574 0.573268 -0.792796 0.206974 0.573277 -0.79279 0.206974 0.573277 -0.773587 0.270033 0.573248 -0.773606 0.270037 0.573248 -0.749395 0.331351 0.57326 -0.749387 0.331349 0.57326 -0.720327 0.390516 0.57327 -0.72032 0.390514 0.57327 -0.686597 0.447153 0.573256 -0.686606 0.447157 0.573256 -0.648439 0.500904 0.573257 -0.648439 0.500903 0.573256 -0.606074 0.551408 0.573259 -0.606073 0.551407 0.57326 -0.559786 0.598341 0.573267 -0.559783 0.598338 0.573267 -0.509874 0.6414 0.573268 -0.509873 0.641399 0.573268 -0.456663 0.680311 0.573266 -0.456665 0.680312 0.573266 -0.400499 0.714819 0.573263 -0.4005 0.714821 0.573263 -0.341743 0.744702 0.573258 -0.341745 0.744705 0.573258 -0.280775 0.769767 0.573261 -0.280774 0.769765 0.573261 -0.217987 0.789844 0.573261 -0.217987 0.789844 0.573261 -0.15379 0.804811 0.57326 -0.15379 0.804812 0.57326 -0.0885965 0.81457 0.573261 -0.0885964 0.814569 0.573261 -0.0228301 0.819054 0.573258 -0.0228305 0.819057 0.573258 0.0430844 0.818241 0.57326 0.0430845 0.81824 0.57326 0.108719 0.812129 0.573265 0.108719 0.812125 0.573264 0.173651 0.800758 0.573263 0.173651 0.800759 0.573263 0.237459 0.784209 0.573262 0.237459 0.784209 0.573262 0.299729 0.762583 0.573261 0.29973 0.762584 0.573261 0.360061 0.736022 0.573261 0.360061 0.736022 0.57326 0.418061 0.704697 0.573262 0.418061 0.704696 0.573262 0.473355 0.668809 0.573266 0.473354 0.668807 0.573266 0.525584 0.628592 0.57326 0.525586 0.628595 0.57326 0.574416 0.584311 0.57326 0.574416 0.584311 0.57326 0.619527 0.536245 0.573263 0.619526 0.536244 0.573263 0.660628 0.484707 0.573262 0.660628 0.484708 0.573262 0.697454 0.430034 0.57326 0.697455 0.430035 0.57326 0.729766 0.372578 0.57326 0.729766 0.372578 0.57326 0.757355 0.312709 0.57326 0.757354 0.312709 0.57326 0.780041 0.250817 0.573261 0.780041 0.250817 0.573261 0.797678 0.187301 0.573261 0.797678 0.187301 0.573261 0.810153 0.122573 0.573261 0.810153 0.122573 0.573261 0.817384 0.0570513 0.57326 0.817385 0.0570513 0.850935 0.523997 0.0365736 0.850935 0.523997 0.0365736 0.850935 0.519361 0.0785771 0.850934 0.519361 0.0785772 0.850934 0.511364 0.120072 0.850935 0.511364 0.120072 0.850935 0.500057 0.16079 0.850935 0.500057 0.16079 0.850935 0.485513 0.200467 0.850935 0.485513 0.200467 0.850935 0.467827 0.238846 0.850935 0.467828 0.238847 0.850934 0.447114 0.27568 0.850935 0.447113 0.27568 0.850935 0.423506 0.310729 0.850934 0.423507 0.31073 0.850934 0.397158 0.343769 0.850935 0.397157 0.343768 0.850935 0.368238 0.374581 0.850933 0.368239 0.374583 0.850933 0.336937 0.402972 0.850934 0.336936 0.40297 0.850935 0.303452 0.428751 0.850935 0.303452 0.428751 0.850935 0.268005 0.451757 0.850935 0.268004 0.451756 0.850935 0.230822 0.471837 0.850934 0.230823 0.471839 0.850934 0.192147 0.488866 0.850934 0.192147 0.488867 0.850934 0.152227 0.50273 0.850933 0.152227 0.502732 0.850933 0.111322 0.513342 0.850935 0.111322 0.513339 0.850935 0.069696 0.520627 0.850936 0.0696959 0.520625 0.850936 0.0276197 0.524542 0.850937 0.0276197 0.524542 0.850937 -0.0146355 0.525064 0.850937 -0.0146354 0.525064 0.850937 -0.0567957 0.522188 0.850934 -0.0567967 0.522193 0.850934 -0.0985894 0.515938 0.850935 -0.098589 0.515936 0.850935 -0.139744 0.506341 0.850933 -0.139745 0.506345 0.850932 -0.179996 0.493473 0.850935 -0.179994 0.493469 0.850935 -0.219079 0.477403 0.850934 -0.219081 0.477405 0.850934 -0.256748 0.458249 0.850934 -0.256748 0.458249 0.850933 -0.292754 0.436128 0.850931 -0.292756 0.43613 0.850931 -0.326867 0.411186 0.850934 -0.326864 0.411182 0.850934 -0.35886 0.383576 0.850936 -0.358857 0.383574 0.850937 -0.388529 0.353485 0.850933 -0.388534 0.353489 0.850933 -0.415693 0.321113 0.850936 -0.415688 0.32111 0.850936 -0.440156 0.286656 0.850933 -0.44016 0.286658 0.850933 -0.461779 0.250347 0.850932 -0.46178 0.250348 0.850931 -0.480411 0.212418 0.850936 -0.480404 0.212415 0.850936 -0.495925 0.173111 0.850931 -0.495932 0.173112 0.850931 -0.508243 0.132686 0.850927 -0.50825 0.132687 0.850927 -0.517271 0.0914022 0.850933 -0.517261 0.0914013 0.850933 -0.522935 0.0495247 0.878475 -0.475229 0.049384 0.832075 -0.554195 0.0227909 0 -0.995965 -0.0897425 0.00671586 -0.993174 -0.116447 0 -0.984353 -0.176205 0 -0.971918 -0.235319 0.00746223 -0.95786 -0.28714 0.00671297 -0.8994 -0.437075 0.00223799 -0.893469 -0.449119 0 -0.926715 -0.375764 0 -0.947711 -0.31913 0 -0.777202 -0.629251 0.00783566 -0.801884 -0.597428 0 -0.829087 -0.55912 0 -0.861333 -0.50804 0 -0.737791 -0.67503 0.00410337 -0.685974 -0.727614 0.00410334 -0.685974 -0.727614 0 -0.630431 -0.776245 0 -0.582413 -0.812893 0.00783583 -0.549192 -0.835659 0.00186558 -0.383385 -0.923587 0.00559602 -0.395744 -0.918344 0 -0.456459 -0.889744 0 -0.509348 -0.86056 0 -0.320567 -0.947226 0 -0.262793 -0.964852 0.0074625 -0.23026 -0.973101 0 -0.1777 -0.984085 0 -0.117959 -0.993018 0.00671589 -0.0577853 -0.998306 0 -0.0309624 -0.999521 0 0.0897425 -0.995965 0.00671586 0.116447 -0.993174 0 0.31913 -0.947711 0.00746245 0.28714 -0.95786 0 0.235318 -0.971919 0 0.176205 -0.984353 0 0.375766 -0.926715 0.00186558 0.437084 -0.899419 0.00559617 0.449113 -0.893457 0 0.508042 -0.861333 0 0.55912 -0.829087 0.00783578 0.597428 -0.801884 0.00410328 0.727614 -0.685974 0.0041033 0.727614 -0.685975 0 0.67503 -0.73779 0 0.629252 -0.777202 0 0.776244 -0.630432 0 0.812893 -0.582413 0.0078358 0.83566 -0.549192 0.00186549 0.923587 -0.383384 0.00559605 0.918344 -0.395744 0 0.889744 -0.45646 0 0.86056 -0.509348 0 0.947225 -0.32057 0 0.964852 -0.262792 0.00746243 0.973101 -0.23026 0 0.999521 -0.0309622 0.00671582 0.998307 -0.0577848 0 0.993019 -0.117958 0 0.984085 -0.1777 0.947051 -0.319363 0.033187 0.939631 -0.333903 0.0748428 0.93947 -0.334031 0.0762826 0.938494 -0.335543 0.081481 0.937007 -0.340053 0.0798865 0.938856 -0.3342 0.0828196 0.944805 -0.311136 0.102656 0.933765 -0.341736 0.1063 0.937605 -0.331251 0.105683 0.941144 -0.326057 0.0890804 0.943472 -0.320249 0.0854478 0.946731 -0.311582 0.0813438 0.942921 -0.323556 0.078816 0.940745 -0.330294 0.0768424 0.940036 -0.332585 0.075634 0.939779 -0.333541 0.0746087 0.942648 -0.331879 0.0356541 0.941686 -0.332235 0.0533674 0.939458 -0.338062 0.0559665 0.941473 -0.332698 0.0542377 0.941855 -0.331705 0.0536654 0.9397 -0.334011 0.0734856 0.939394 -0.337966 0.0575962 0.942825 -0.329182 0.0521575 0.939678 -0.334088 0.0734126 0.939884 -0.337122 0.0544607 0.933321 -0.353567 0.0624761 0.940455 -0.337735 0.0384659 0.941316 -0.335477 0.0371431 0.939606 0.341427 0.0238307 0.862582 0.504479 0.038123 0.964232 0.262077 0.0396512 0.953212 0.298758 0.0461546 0.943332 0.327571 0.0531245 0.940994 0.333749 0.0560508 0.940283 0.335443 0.0578421 0.940015 0.336023 0.0588243 0.940158 0.334977 0.0623967 0.940094 0.335153 0.062412 0.939597 0.333105 0.0787364 0.939687 0.336511 0.0612369 0.94017 0.334939 0.0624136 0.939758 0.328892 0.0931969 0.938786 0.33538 0.0787498 0.94066 0.330064 0.0788511 0.938536 0.336243 0.0780396 0.940186 0.327239 0.0946857 0.942437 0.320136 0.0965675 0.947247 0.30512 0.0981091 0.943205 0.315536 0.103927 0.939472 0.326551 0.103715 0.940498 0.320933 0.111651 0.939127 0.325428 0.110167 0.940127 0.321918 0.11194 0.938987 0.328456 0.102079 0.937374 0.333805 0.0995218 0.930024 0.355678 0.0924603 0.932281 0.350414 0.0897954 0.936604 0.340212 0.0838356 0.941032 0.320707 0.107733 0.939668 0.323616 0.110893 0.939603 0.316359 0.130624 0.936316 0.32137 0.141539 0.940945 0.301535 0.153947 0.939677 0.300951 0.162592 0.939603 0.291338 0.179632 0.936377 0.294478 0.191001 0.940953 0.27295 0.200265 0.939676 0.271094 0.208609 0.944851 0.230376 0.232775 0.946999 0.225201 0.22908 0.939691 0.230221 0.252943 0.941038 0.231192 0.246975 0.939912 0.231363 0.251072 0.939705 0.230524 0.252614 0.939638 0.231331 0.252124 0.939336 0.233495 0.251253 0.93877 0.235959 0.251066 0.939214 0.236161 0.249208 0.943 0.246668 0.223397 0.929105 0.269758 0.252972 0.935384 0.260172 0.239515 0.939482 0.254137 0.229757 0.938527 0.256618 0.230897 0.926825 0.283911 0.245745 0.940343 0.242221 0.238923 0.941594 0.23864 0.237596 0.947267 0.0680831 0.313128 0.946921 0.0681293 0.314165 0.939619 0.0521191 0.338229 0.952735 0.03403 0.301892 0.936786 0.0766792 0.341398 0.931666 0.0695856 0.356591 0.934979 0.0658451 0.348538 0.937776 0.0619615 0.341667 0.939718 0.0846421 0.331311 0.939871 0.0832211 0.331236 0.940659 0.080583 0.329647 0.938947 0.0807736 0.334446 0.939513 0.0828959 0.332332 0.939661 0.0843826 0.331538 0.939694 0.230041 0.253095 0.939692 0.229818 0.253305 0.939603 0.219546 0.262574 0.936497 0.218951 0.273921 0.940966 0.195554 0.276301 0.939674 0.191409 0.283505 0.939603 0.174631 0.294363 0.936558 0.172271 0.305258 0.940971 0.148743 0.304056 0.939673 0.143631 0.310458 0.939603 0.125202 0.318544 0.936618 0.121206 0.328719 0.940974 0.0980928 0.323953 0.939673 0.0921592 0.329427 0.939692 0.0853975 0.331188 0.939691 0.0853423 0.331206 0.942153 0.0677686 0.328261 0.940618 0.0669515 0.332799 0.925879 0.0501314 0.374479 0.939491 0.0523124 0.338556 0.939603 0.017997 0.341792 0.936738 0.0112634 0.349851 0.940978 -0.00943067 0.338336 0.939671 -0.0165126 0.341681 0.939603 -0.0370085 0.340259 0.936798 -0.0447836 0.346994 0.940978 -0.0635274 0.332452 0.93967 -0.0709167 0.334651 0.939373 -0.117247 0.32223 0.94452 -0.118579 0.306303 0.938699 -0.109049 0.327036 0.937589 -0.108223 0.330477 0.936144 -0.10759 0.334751 0.932864 -0.10684 0.34402 0.927835 -0.10626 0.357535 0.93172 -0.100456 0.349008 0.935608 -0.0940745 0.340276 0.937276 -0.0909639 0.33651 0.938549 -0.0882168 0.333683 0.939666 -0.0849471 0.331378 0.939627 -0.0848847 0.331506 0.940699 -0.0858657 0.328197 0.942353 -0.0863481 0.323288 0.947847 -0.0855504 0.30703 0.946195 -0.0860904 0.311936 0.940341 -0.0998429 0.325254 0.935167 -0.121376 0.332762 0.943938 -0.110134 0.311211 0.941272 -0.114294 0.317716 0.939605 -0.11738 0.321504 0.939603 -0.142752 0.311075 0.936917 -0.151862 0.314841 0.940976 -0.165443 0.295286 0.939668 -0.172906 0.295173 0.939603 -0.190757 0.284178 0.936976 -0.200144 0.286387 0.940972 -0.21063 0.264964 0.939667 -0.217868 0.263742 0.941542 -0.244183 0.232106 0.947569 -0.236366 0.215046 0.944476 -0.244175 0.219874 0.941443 -0.252193 0.223794 0.939413 -0.257749 0.225983 0.938613 -0.258107 0.228881 0.939755 -0.257043 0.225366 0.939683 -0.251553 0.231771 0.939584 -0.250826 0.232958 0.939339 -0.250241 0.234568 0.938803 -0.249806 0.237161 0.933956 -0.248918 0.25645 0.930186 -0.257194 0.261927 0.934256 -0.24801 0.256235 0.937147 -0.241033 0.252307 0.939594 -0.234358 0.249478 0.939514 -0.234438 0.249706 0.938799 -0.235335 0.251544 0.93975 -0.244666 0.238764 0.940076 -0.245187 0.236938 0.940291 -0.255626 0.224742 0.939672 -0.257758 0.224896 0.939603 -0.270862 0.209235 0.937095 -0.28004 0.2084 0.940963 -0.283658 0.184735 0.939665 -0.289971 0.181512 0.939603 -0.300892 0.163125 0.937154 -0.30961 0.160883 0.940956 -0.309613 0.136898 0.939664 -0.315258 0.132828 0.939603 -0.323144 0.112798 0.93463 -0.33959 0.105577 0.940054 -0.328559 0.0913648 0 0.997168 -0.0752009 0 0.997168 -0.0752009 0 0.959743 -0.28088 0 0.959743 -0.28088 0 0.880372 -0.474285 0 0.880372 -0.474285 0 0.762525 -0.646959 0 0.762525 -0.646959 0 0.611351 -0.79136 0 0.611351 -0.79136 0 0.433459 -0.901173 0 0.433459 -0.901173 0 0.236622 -0.971602 0 0.236622 -0.971602 0 0.0294438 -0.999566 0 0.0294438 -0.999566 0 -0.179021 -0.983845 0 -0.179021 -0.983845 0 -0.379662 -0.925125 0 -0.379662 -0.925125 0 -0.56371 -0.825973 0 -0.56371 -0.825973 0 -0.723121 -0.690722 0 -0.723121 -0.690722 0 -0.850928 -0.525282 0 -0.850928 -0.525282 0 -0.941546 -0.336886 0 -0.941546 -0.336886 0 -0.991013 -0.133766 0 -0.991013 -0.133766 -0.849121 0.15167 -0.505955 -0.849121 0.384326 -0.362335 -0.849122 0.514003 -0.121626 -0.849121 -0.505953 -0.151674 -0.84912 -0.362332 -0.384331 -0.849121 -0.121625 -0.514005 -0.849121 0.151672 -0.505953 -0.849121 0.384325 -0.362336 -0.849122 0.514003 -0.121626 -0.849121 -0.505955 -0.151668 -0.849121 -0.362333 -0.384329 -0.849121 -0.121626 -0.514005 -0.851307 0.514728 -0.101641 -0.851307 0.0154472 -0.524441 -0.851307 0.241465 -0.465801 -0.851307 0.419657 -0.314904 -0.851308 -0.507854 -0.131757 -0.851308 -0.40039 -0.339063 -0.851307 -0.213626 -0.479208 -0.849121 0.151669 -0.505955 -0.849121 0.384329 -0.362333 -0.849121 0.514005 -0.121627 -0.849121 -0.505953 -0.151674 -0.849121 -0.362334 -0.384328 -0.849121 -0.121625 -0.514005 -0.705513 0.707189 -0.0462011 -0.705512 0.707191 -0.0462012 -0.705512 0.685851 -0.178498 -0.705511 0.685852 -0.178498 -0.70551 0.63999 -0.304413 -0.705512 0.639989 -0.304413 -0.705513 0.571244 -0.419443 -0.705516 0.571241 -0.419441 -0.705516 0.482073 -0.519474 -0.70551 0.482077 -0.519479 -0.705393 -0.707143 0.0486761 -0.705398 -0.707138 0.048676 -0.705398 -0.684054 0.185696 -0.705394 -0.684059 0.185697 -0.705394 -0.634687 0.315583 -0.705393 -0.634687 0.315583 -0.705393 -0.560925 0.433341 -0.705382 -0.560934 0.433347 -0.705383 -0.465613 0.534452 -0.705393 -0.465606 0.534445 -0.705393 -0.352395 0.615011 -0.705397 -0.352393 0.615008 -0.705395 -0.22564 0.671941 -0.705391 -0.225642 0.671944 -0.705391 -0.0902161 0.703054 -0.705394 -0.0902155 0.70305 -0.705393 0.0486764 0.707143 -0.705392 0.0486765 0.707144 -0.705392 0.185698 0.68406 -0.705394 0.185698 0.684059 -0.705394 0.315583 0.634687 -0.705393 0.315583 0.634687 -0.705393 0.43334 0.560925 -0.705387 0.433344 0.56093 -0.705387 0.534449 0.46561 -0.705395 0.534444 0.465605 -0.705395 0.61501 0.352394 -0.705394 0.615011 0.352395 -0.705393 0.671943 0.225641 -0.705394 0.671942 0.225641 -0.705394 0.703051 0.0902157 -0.705393 0.703052 0.0902158 0.706952 0.535379 0.462156 0.756782 0.521688 0.393856 0.746961 0.528023 0.404031 0.707014 0.588548 0.392101 0.707067 0.603605 0.368398 0.669696 0.660439 0.339599 0.706167 0.634799 0.313622 0.706929 0.6635 0.244989 0.647194 0.729006 0.222912 0.706538 0.683044 0.18508 0.705706 0.703532 0.0837942 0.572956 0.80919 0.130124 0.706814 0.70565 0.0497193 0.705521 -0.703236 -0.0877464 0.705522 -0.703235 -0.0877465 0.705522 -0.674145 -0.218556 0.705521 -0.674146 -0.218556 0.705521 -0.620953 -0.341551 0.705522 -0.620952 -0.341551 0.705522 -0.545557 -0.452334 0.705522 -0.545557 -0.452335 0.705522 -0.450656 -0.546945 0.705523 -0.450655 -0.546944 0.705403 0.615003 0.35239 0.705403 0.671933 0.225638 0.705403 0.671933 0.225638 0.705403 0.703042 0.0902146 0.705403 0.703042 0.0902146 0.705402 0.315579 0.634679 0.705402 0.433335 0.560918 0.705402 0.433335 0.560917 0.707079 0.491901 0.508008 0.664013 0.563779 0.491162 0.705836 0.540271 0.458151 0.705403 0.615003 0.35239 0.705403 -0.225638 0.671933 0.705403 -0.0902146 0.703042 0.705403 -0.0902146 0.703042 0.705403 0.0486757 0.707134 0.705402 0.0486758 0.707134 0.706789 0.147147 0.691951 0.610541 0.207486 0.764323 0.706565 0.214329 0.67441 0.705402 0.315579 0.634679 0.705402 -0.560917 0.433335 0.705402 -0.4656 0.534438 0.705403 -0.4656 0.534438 0.707034 -0.397921 0.584603 0.644295 -0.380216 0.663566 0.706053 -0.339174 0.621651 0.705403 -0.225638 0.671933 0.64188 -0.692258 0.329801 0.707061 -0.605519 0.365255 0.705403 -0.560917 0.433335 0.705404 -0.634678 0.315578 0.705404 -0.684049 0.185695 0.705404 -0.684049 0.185695 0.705404 -0.707133 0.0486754 0.705401 -0.707135 0.0486761 0.891961 0.449664 0.0469946 0.706852 0.705805 0.0468896 0.159329 0.718322 -0.677221 0.159339 0.718326 -0.677214 0.446436 0.580125 -0.681286 0.446433 0.580125 -0.681287 0.645117 0.331086 -0.688626 0.645116 0.331087 -0.688627 0.716024 0.0205541 -0.697773 0.716024 0.020554 -0.697773 0.645117 -0.289982 -0.706919 0.645115 -0.289975 -0.706923 0.446431 -0.539011 -0.714259 0.44643 -0.539014 -0.714258 0.159338 -0.677211 -0.718329 0.159332 -0.677218 -0.718324 0.222532 0.974503 0.0287059 0.22252 0.974505 0.0287052 0.623489 0.781493 0.0230198 0.623489 0.781493 0.0230198 0.900969 0.433695 0.012775 0.900972 0.433689 0.0127752 1 0 0 1 0 0 0.900972 -0.433689 -0.0127752 0.900969 -0.433695 -0.012775 0.623489 -0.781493 -0.0230198 0.623489 -0.781493 -0.0230198 0.22252 -0.974506 -0.0287052 0.222532 -0.974503 -0.0287059 0.116756 0.536358 -0.835876 0.524675 0.025066 -0.850934 0.472715 0.252614 -0.844232 0.327127 0.435093 -0.838857 0.11675 -0.48623 -0.865997 0.327128 -0.384963 -0.863013 0.472717 -0.20248 -0.857637 0.186157 0.714901 -0.673989 0.186157 0.714901 -0.67399 0.508595 0.528825 -0.679467 0.508591 0.528825 -0.67947 0.694745 0.206539 -0.688964 0.694746 0.206538 -0.688963 0.694745 -0.165626 -0.699926 0.694746 -0.165626 -0.699926 0.508593 -0.487912 -0.709419 0.508593 -0.487915 -0.709417 0.186157 -0.67399 -0.714901 0.186159 -0.673987 -0.714903 0.258814 0.965508 0.0284406 0.25882 0.965507 0.0284409 0.707113 0.706794 0.02082 0.70711 0.706797 0.0208198 0.965923 0.258716 0.00762088 0.965923 0.258716 0.00762088 0.965924 -0.258714 -0.00762084 0.965924 -0.258714 -0.00762084 0.70711 -0.706797 -0.0208198 0.70711 -0.706797 -0.0208198 0.25882 -0.965507 -0.0284405 0.25882 -0.965507 -0.0284405 0.510202 0.161656 -0.844725 0.373498 0.398331 -0.837754 0.136706 0.534984 -0.833729 0.136709 -0.48498 -0.863774 0.373497 -0.34833 -0.859748 0.510203 -0.111652 -0.852776 0.15934 0.718326 -0.677213 0.159331 0.718323 -0.677219 0.446432 0.580122 -0.681291 0.44643 0.580122 -0.681292 0.645113 0.331088 -0.688629 0.645116 0.331086 -0.688627 0.716024 0.0205541 -0.697773 0.716024 0.020554 -0.697773 0.645117 -0.289982 -0.706919 0.645115 -0.289975 -0.706924 0.446431 -0.539011 -0.71426 0.44643 -0.539014 -0.714258 0.159338 -0.677211 -0.718329 0.159332 -0.677218 -0.718324 0.22252 0.974506 0.0287052 0.222532 0.974503 0.0287059 0.623489 0.781493 0.0230204 0.623489 0.781493 0.0230204 0.900969 0.433695 0.0127753 0.900969 0.433695 0.0127753 1 0 0 1 0 0 0.900969 -0.433695 -0.012775 0.900969 -0.433695 -0.012775 0.623489 -0.781493 -0.0230198 0.623489 -0.781493 -0.0230198 0.22252 -0.974506 -0.0287052 0.222532 -0.974503 -0.0287059 0.11675 0.53636 -0.835875 0.524675 0.0250654 -0.850934 0.472715 0.252613 -0.844232 0.327127 0.435094 -0.838857 0.11675 -0.48623 -0.865997 0.327127 -0.384963 -0.863013 0.472715 -0.202482 -0.857637 -0.830791 0.473614 0.292364 -0.965715 0.258197 0.0270144 -0.980668 0.189408 0.0491409 -0.98067 -0.195467 0.00887076 -0.980668 -0.195478 0.00887141 -0.980668 0.166507 0.102786 -0.980668 0.166509 0.102787 -0.980668 0.14933 0.126456 -0.549574 0.76837 0.327988 -0.830791 0.511898 0.21851 -0.830795 0.511892 0.218508 -0.980668 0.179966 0.076821 -0.980668 0.179967 0.0768213 -0.441173 -0.896573 0.0390371 -0.607645 -0.793393 0.0360057 -0.830766 -0.55605 0.0252346 -0.792689 -0.609036 0.0268153 -0.896278 -0.443037 0.0201064 -0.549573 -0.786319 0.282261 -0.195041 -0.81829 0.540704 -0.194536 -0.863553 0.465224 -0.554391 -0.732695 0.394727 -0.554388 -0.783344 0.281116 -0.830798 -0.523862 0.187996 -0.980667 -0.184185 0.0660978 -0.980667 -0.172277 0.0928111 -0.830772 -0.490026 0.263993 -0.830773 -0.445206 0.334078 -0.549575 -0.66823 0.501434 -0.549577 -0.586031 0.595426 -0.980666 -0.15652 0.117451 -0.980667 -0.137266 0.139467 -0.830791 -0.390423 0.396682 -0.830791 -0.32694 0.450441 -0.554412 -0.488862 0.673529 -0.554421 -0.383082 0.738827 -0.188906 -0.451872 0.871852 -0.189334 -0.358302 0.914206 -0.980669 -0.114939 0.158357 -0.980669 -0.0900531 0.173719 -0.830793 -0.256152 0.494135 -0.830793 -0.179644 0.526793 -0.549615 -0.269642 0.790706 -0.54961 -0.14871 0.822079 -0.980667 -0.0900573 0.173727 -0.980667 -0.0631589 0.185209 -0.830789 -0.179646 0.526799 -0.830789 -0.0991241 0.547689 -0.55444 -0.148213 0.81892 -0.554445 -0.0245035 0.83186 -0.194553 -0.0288809 0.980467 -0.19506 0.0591161 0.979008 -0.980669 -0.034848 0.192545 -0.980669 -0.00576146 0.195589 -0.830801 -0.0163878 0.556328 -0.830797 0.0667126 0.552563 -0.549575 0.100139 0.829421 -0.549579 0.222639 0.80523 -0.980668 0.0234543 0.194266 -0.980668 0.0521463 0.1886 -0.830781 0.148329 0.53647 -0.830782 0.226629 0.508371 -0.554407 0.338864 0.760135 -0.554408 0.448307 0.70118 -0.188876 0.529114 0.827263 -0.189305 0.612578 0.767406 -0.980669 0.0796716 0.178718 -0.980669 0.105419 0.164848 -0.83079 0.29986 0.468906 -0.83079 0.366397 0.418976 -0.549616 0.54995 0.628869 -0.549616 0.637583 0.539824 -0.980668 0.105421 0.164852 -0.980668 0.128814 0.147299 -0.830786 0.366401 0.418981 -0.830786 0.424755 0.359692 -0.554433 0.635102 0.537819 -0.554429 0.708169 0.437156 -0.19456 0.834667 0.515245 -0.195067 0.877403 0.438306 -0.549624 -0.834557 0.0378011 -0.188837 -0.980995 0.0445946 -0.194626 -0.979869 0.0444687 -0.98067 -0.191962 0.0379045 -0.830799 -0.54603 0.107818 -0.830766 -0.546077 0.107828 -0.549575 -0.819619 0.161842 -0.549625 -0.819586 0.161835 0.791393 -0.599728 0.118419 -0.189265 -0.97089 0.146806 -0.194636 -0.863536 0.465213 -0.19514 -0.901667 0.385898 0.61081 -0.745352 0.267136 -0.189147 -0.929095 0.317813 -0.189292 -0.957199 0.21895 -0.980668 -0.191972 0.0379067 -0.980668 -0.184178 0.0660952 -0.830818 -0.523834 0.187986 -0.830817 -0.489967 0.26396 -0.55448 -0.732643 0.394697 -0.55448 -0.665679 0.499423 0.610853 -0.633081 0.475466 -0.18892 -0.576826 0.794721 -0.189353 -0.656681 0.730011 0.791372 -0.42883 0.435701 -0.189172 -0.709424 0.67892 -0.189028 -0.776526 0.601062 -0.980671 -0.172259 0.0928014 -0.98067 -0.156505 0.11744 -0.8308 -0.445173 0.334053 -0.830799 -0.390415 0.396673 -0.549604 -0.586019 0.595414 -0.549604 -0.490672 0.676148 -0.194596 -0.576232 0.793782 -0.194585 -0.451426 0.870834 -0.980667 -0.137263 0.139464 -0.980668 -0.114944 0.158363 -0.830801 -0.326931 0.450428 -0.8308 -0.256148 0.494126 -0.549588 -0.384488 0.741702 -0.549588 -0.269647 0.790723 0.791384 -0.197314 0.578601 -0.1946 -0.0288812 0.980457 -0.195107 -0.11664 0.973822 0.610807 -0.14133 0.779064 -0.189116 -0.189314 0.963533 -0.189262 -0.288985 0.938439 -0.980668 -0.0631581 0.185207 -0.980668 -0.0348486 0.192549 -0.830779 -0.0991265 0.547704 -0.83078 -0.0163882 0.55636 -0.554438 -0.0245035 0.831864 -0.554443 0.0996769 0.826231 0.610862 0.0952243 0.78599 -0.18892 0.399836 0.896906 -0.189351 0.303868 0.933708 0.791379 0.162911 0.58922 -0.189173 0.233249 0.953839 -0.189029 0.132272 0.973022 -0.980668 -0.00576152 0.195593 -0.980668 0.0234543 0.194266 -0.830801 0.0667119 0.552558 -0.8308 0.148321 0.536444 -0.549618 0.222631 0.805205 -0.549614 0.340222 0.763003 -0.194597 0.399319 0.895922 -0.194602 0.528449 0.826361 -0.980669 0.0521453 0.188597 -0.980669 0.0796716 0.178718 -0.830797 0.226619 0.50835 -0.830797 0.299854 0.468897 -0.549596 0.450087 0.703823 -0.549593 0.549961 0.628881 0.791388 0.402423 0.460175 -0.194563 0.834667 0.515244 -0.195067 0.785039 0.587931 0.610809 0.604023 0.511926 -0.189076 0.739793 0.645722 -0.18922 0.668224 0.719494 -0.980669 0.12881 0.147295 -0.980669 0.149324 0.126451 -0.830794 0.424745 0.359684 -0.830795 0.473608 0.292361 -0.55443 0.708168 0.437156 -0.554434 0.765381 0.326795 0.610845 0.728311 0.310533 -0.189061 0.908792 0.371957 -0.189741 0.960475 0.203682 -0.980668 0.189407 0.0491405 -0.830793 0.538745 0.139774 -0.830796 0.538741 0.139773 -0.549997 0.808402 0.209735 -0.549574 0.808674 0.209799 0.790864 0.592373 0.153719 -0.189204 0.942668 0.274918 -0.980683 0.194424 0.0214457 -0.792689 0.606402 0.0626179 -0.830793 0.55356 0.0579174 -0.607668 0.78988 0.082643 -0.549969 0.830713 0.0863135 -0.25812 0.960777 0.101398 -0.189317 0.976585 0.102177 -0.705184 0.707017 -0.0533191 -0.705184 0.707017 -0.0533191 -0.705184 0.680481 -0.199151 -0.705181 0.680484 -0.199152 -0.705181 0.624208 -0.33628 -0.705183 0.624206 -0.33628 -0.705182 0.54065 -0.458711 -0.705184 0.540648 -0.45871 -0.705184 0.433462 -0.561093 -0.705184 0.433463 -0.561093 -0.705184 0.307333 -0.638954 -0.705182 0.307333 -0.638956 -0.705183 0.167771 -0.68889 -0.705186 0.16777 -0.688887 -0.705185 0.0208763 -0.708716 -0.705182 0.0208765 -0.708719 -0.70518 -0.126931 -0.697574 -0.705182 -0.126931 -0.697572 -0.705179 -0.269191 -0.65594 -0.705176 -0.269192 -0.655943 -0.705176 -0.399689 -0.585642 -0.705181 -0.399686 -0.585637 -0.705182 -0.512712 -0.48974 -0.705183 -0.512711 -0.489739 -0.705183 -0.60333 -0.372438 -0.705185 -0.603328 -0.372437 -0.705186 -0.667577 -0.238859 -0.70518 -0.667583 -0.238862 -0.70518 -0.702657 -0.0948439 -0.705183 -0.702653 -0.0948432 0 -0.998976 0.0452323 0 -0.998976 0.0452323 0.698116 0.702422 -0.138698 0.698126 0.702412 -0.138699 0.70691 0.634798 -0.311946 0.601324 0.639085 -0.479563 0.70091 0.554087 -0.449123 0.706164 0.415911 -0.573018 0.526075 0.391391 -0.755022 0.70317 0.279141 -0.653936 0.704919 0.100134 -0.702184 0.497719 0.0255377 -0.866962 0.704919 -0.0586279 -0.70686 0.69812 -0.291525 -0.653944 0.389972 -0.311032 -0.866707 0.706162 -0.38146 -0.596509 0.698121 -0.546389 -0.462695 0.698122 -0.693034 -0.179804 0.698124 -0.693033 -0.179803 0.706908 -0.615339 -0.348767 0.573335 -0.605017 -0.552486 0 -0.967953 -0.25113 0.0147897 -0.957782 -0.287115 0 -0.869977 -0.493093 0 -0.738437 -0.674322 0.0246917 -0.685771 -0.727399 0 -0.538747 -0.842468 0 -0.337775 -0.941227 0.0296536 -0.230165 -0.9727 0 -0.0826574 -0.996578 0 0.141175 -0.989985 0.0296535 0.287021 -0.957465 0 0.392591 -0.919713 0 0.587405 -0.809293 0.0246913 0.727399 -0.68577 0 0.981057 -0.19372 0.01479 0.973021 -0.230242 0 0.89749 -0.441035 0 0.776849 -0.629686 -0.694735 0.699937 -0.165624 -0.694743 0.69993 -0.16562 -0.694743 0.523347 -0.493396 -0.694739 0.523349 -0.493399 -0.694738 0.206534 -0.688972 -0.694737 0.206535 -0.688973 -0.69474 -0.165622 -0.699933 -0.69474 -0.165622 -0.699933 -0.69474 -0.493398 -0.523349 -0.694739 -0.493399 -0.523349 -0.694741 -0.68897 -0.206533 -0.694741 -0.688969 -0.206533 0.698123 0.702416 -0.138699 0.698119 0.702419 -0.138698 0.706904 0.634803 -0.311948 0.601317 0.639089 -0.479565 0.70091 0.554087 -0.449124 0.706164 0.415909 -0.57302 0.52608 0.39139 -0.755019 0.703169 0.279142 -0.653936 0.704917 0.100132 -0.702187 0.497723 0.0255387 -0.86696 0.704919 -0.0586263 -0.706861 0.69812 -0.291525 -0.653944 0.389965 -0.311032 -0.86671 0.706162 -0.381462 -0.596508 0.698121 -0.54639 -0.462694 0.698116 -0.69304 -0.179805 0.698117 -0.693039 -0.179805 0.706903 -0.615339 -0.348778 0.573336 -0.605018 -0.552485 0 -0.967953 -0.25113 0.0147906 -0.957781 -0.287117 0 -0.86997 -0.493105 0 -0.738438 -0.674321 0.0246913 -0.685772 -0.727397 0 -0.53875 -0.842466 0 -0.337774 -0.941227 0.0296537 -0.230164 -0.9727 0 -0.0826552 -0.996578 0 0.141172 -0.989985 0.029654 0.287021 -0.957465 0 0.392593 -0.919712 0 0.587402 -0.809296 0.0246917 0.727398 -0.685772 0 0.981057 -0.193718 0.0147902 0.973021 -0.23024 0 0.89749 -0.441035 0 0.776849 -0.629687 -0.694742 0.699931 -0.16562 -0.694743 0.69993 -0.16562 -0.694743 0.523346 -0.493398 -0.694744 0.523346 -0.493396 -0.694745 0.206533 -0.688966 -0.694742 0.206533 -0.688968 -0.694741 -0.165621 -0.699932 -0.694737 -0.165623 -0.699936 -0.694738 -0.493401 -0.52335 -0.694742 -0.493398 -0.523347 -0.694742 -0.688968 -0.206534 -0.694736 -0.688974 -0.206535 0.69478 -0.688933 -0.206524 0.694793 -0.688922 -0.206517 0.69479 -0.493365 -0.523314 0.694796 -0.493362 -0.523309 0.694791 -0.165608 -0.699885 0.694797 -0.165608 -0.69988 0.694794 0.206517 -0.688921 0.694793 0.206517 -0.688922 0.69479 0.523314 -0.493365 0.694796 0.523309 -0.493362 0.694792 0.699884 -0.165611 0.69478 0.699895 -0.165611 0 -0.967953 -0.251131 -0.0147903 -0.957781 -0.287117 0 -0.869974 -0.493098 0 -0.738437 -0.674322 -0.024692 -0.68577 -0.727399 0 -0.538746 -0.842468 0 -0.337776 -0.941226 -0.0296546 -0.230163 -0.9727 0 -0.0826497 -0.996579 0 0.141167 -0.989986 -0.0296546 0.287018 -0.957466 0 0.392593 -0.919713 0 0.587402 -0.809296 -0.024692 0.727399 -0.68577 0 0.776851 -0.629685 0 0.897494 -0.441026 -0.0147891 0.973021 -0.230243 0 0.981056 -0.193723 -0.698054 -0.693098 -0.17982 -0.698057 -0.693095 -0.17982 -0.706844 -0.615393 -0.348803 -0.60125 -0.609792 -0.516383 -0.700853 -0.526732 -0.480998 -0.706109 -0.381488 -0.596555 -0.526022 -0.346285 -0.77678 -0.703117 -0.240184 -0.669281 -0.704866 -0.0586267 -0.706913 -0.497679 0.0255394 -0.866985 -0.704862 0.100136 -0.70224 -0.698063 0.329537 -0.635699 -0.389917 0.361519 -0.846917 -0.706105 0.415944 -0.573068 -0.698062 0.572723 -0.429766 -0.698053 0.702481 -0.138715 -0.698073 0.702464 -0.138706 -0.706859 0.634847 -0.311962 -0.573284 0.636518 -0.515937 0.694798 -0.688917 -0.206519 0.694797 -0.688917 -0.206519 0.6948 -0.493358 -0.523307 0.694796 -0.49336 -0.52331 0.694792 -0.165611 -0.699884 0.694796 -0.165611 -0.699879 0.694794 0.206521 -0.68892 0.694794 0.206521 -0.68892 0.694791 0.523312 -0.493366 0.694787 0.523316 -0.493368 0.694789 0.699887 -0.165611 0.694796 0.699879 -0.165611 0 -0.957886 -0.287149 0 -0.957886 -0.287149 0 -0.685979 -0.727621 0 -0.685979 -0.727621 0 -0.230267 -0.973127 0 -0.230267 -0.973127 0 0.28715 -0.957886 0 0.28715 -0.957886 0 0.727619 -0.685982 0 0.727619 -0.685982 0 0.973127 -0.230267 0 0.973127 -0.230267 -0.694743 0.69993 -0.165622 -0.694735 0.699937 -0.165625 -0.694733 0.523353 -0.493404 -0.694737 0.523351 -0.493401 -0.69474 0.206536 -0.68897 -0.69474 0.206536 -0.68897 -0.694743 -0.165622 -0.69993 -0.694738 -0.165624 -0.699934 -0.694743 -0.493396 -0.523348 -0.694747 -0.493393 -0.523345 -0.694744 -0.688966 -0.206534 -0.694744 -0.688966 -0.206534 0.698121 -0.693035 -0.179805 0.698124 -0.693033 -0.179803 0.698123 -0.546389 -0.462691 0.698107 -0.546399 -0.462704 0.698115 -0.291527 -0.653947 0.69812 -0.291527 -0.653943 0.69812 0.0210811 -0.71567 0.698116 0.0210822 -0.715674 0.69811 0.329516 -0.635659 0.698122 0.329508 -0.63565 0.698126 0.572675 -0.429726 0.698127 0.572674 -0.429726 0.698126 0.702412 -0.138697 0.698121 0.702418 -0.138697 0 -0.967953 -0.251131 0.0147903 -0.957781 -0.287117 -0.0123571 -0.763079 -0.646187 0 -0.738441 -0.674319 0 -0.538753 -0.842464 -0.0197974 -0.407089 -0.913174 0 -0.337774 -0.941227 0 -0.0826497 -0.996579 -0.0222793 0.0294363 -0.999318 0 0.141167 -0.989986 0 0.39259 -0.919714 -0.0197975 0.460134 -0.887629 0 0.587409 -0.80929 0 0.799852 -0.600197 -0.0147922 0.776763 -0.62962 0.0171991 0.980912 -0.193689 0 0.973129 -0.23026 -0.69474 -0.68897 -0.206535 -0.69474 -0.68897 -0.206535 -0.694737 -0.493401 -0.523351 -0.309 -0.702303 -0.641319 -0.706096 -0.3815 -0.596562 -0.703108 -0.240185 -0.669291 -0.396498 -0.211393 -0.893366 -0.704869 -0.0586265 -0.70691 -0.704868 0.100135 -0.702235 -0.396502 0.263608 -0.879373 -0.69474 0.699933 -0.165617 -0.694738 0.699936 -0.165618 -0.700857 0.554127 -0.449158 -0.462292 0.645201 -0.608278 -0.706107 0.415947 -0.573062 -0.703117 0.27916 -0.653985 0.694796 -0.688919 -0.206519 0.694795 -0.688919 -0.206519 0.694795 -0.493362 -0.523311 0.694799 -0.49336 -0.523308 0.694795 -0.16561 -0.699881 0.694796 -0.16561 -0.69988 0.694794 0.206517 -0.688921 0.69479 0.206519 -0.688924 0.694788 0.523315 -0.493367 0.694791 0.523312 -0.493365 0.69479 0.699885 -0.165611 0.694795 0.69988 -0.165611 0 -0.957886 -0.287149 0 -0.957886 -0.287149 0 -0.685979 -0.727621 0 -0.685979 -0.727621 0 -0.230267 -0.973128 0 -0.230267 -0.973128 0 0.287145 -0.957887 0 0.287145 -0.957887 0 0.72762 -0.68598 0 0.72762 -0.68598 0 0.973127 -0.230268 0 0.973127 -0.230268 -0.694742 0.699931 -0.165622 -0.694737 0.699935 -0.165624 -0.694738 0.52335 -0.4934 -0.694735 0.523352 -0.493403 -0.694736 0.206533 -0.688974 -0.69474 0.206533 -0.68897 -0.694743 -0.165621 -0.69993 -0.694742 -0.165622 -0.699931 -0.694745 -0.493395 -0.523346 -0.694742 -0.493397 -0.523348 -0.694742 -0.688968 -0.206534 -0.694742 -0.688968 -0.206534 0.694796 -0.688919 -0.206519 0.694795 -0.688919 -0.206519 0.694795 -0.493361 -0.523311 0.694799 -0.493359 -0.523308 0.694795 -0.165611 -0.69988 0.694787 -0.165611 -0.699889 0.694799 0.206517 -0.688916 0.694793 0.206519 -0.688921 0.69479 0.523313 -0.493366 0.694789 0.523314 -0.493367 0.694789 0.699886 -0.165612 0.694795 0.699881 -0.165611 0 -0.967953 -0.25113 -0.0147906 -0.957781 -0.287117 0 -0.86997 -0.493105 0 -0.738434 -0.674325 -0.0246908 -0.68577 -0.7274 0 -0.53875 -0.842466 0 -0.337774 -0.941227 -0.029653 -0.230167 -0.972699 0 -0.0826591 -0.996578 0 0.141174 -0.989985 -0.0296535 0.28702 -0.957466 0 0.39259 -0.919714 0 0.587409 -0.80929 -0.0246902 0.727398 -0.685772 0 0.776846 -0.629691 0 0.897485 -0.441045 -0.0147909 0.973021 -0.230242 0 0.981057 -0.193718 -0.698069 -0.693084 -0.179816 -0.69807 -0.693083 -0.179816 -0.706856 -0.61538 -0.348802 -0.601267 -0.60978 -0.516379 -0.700863 -0.526722 -0.480994 -0.706116 -0.381487 -0.596547 -0.526029 -0.346284 -0.776776 -0.703127 -0.240179 -0.669274 -0.704869 -0.0586332 -0.70691 -0.497664 0.0255384 -0.866994 -0.704868 0.10014 -0.702234 -0.698072 0.329533 -0.635691 -0.389917 0.361516 -0.846918 -0.706115 0.415943 -0.573056 -0.698074 0.572714 -0.429756 -0.698069 0.702467 -0.138708 -0.698047 0.702487 -0.138718 -0.706835 0.634862 -0.311986 -0.573255 0.63653 -0.515954 0.694794 -0.68892 -0.20652 0.694793 -0.688921 -0.20652 0.694791 -0.493366 -0.523313 0.694787 -0.493368 -0.523315 0.694799 -0.165609 -0.699877 0.694797 -0.165609 -0.69988 0.694794 0.206519 -0.688921 0.694793 0.206519 -0.688921 0.694791 0.523312 -0.493366 0.694796 0.523308 -0.493364 0.694791 0.699886 -0.165605 0.694794 0.699883 -0.165605 0 -0.957886 -0.287149 0 -0.957886 -0.287149 0 -0.685981 -0.727619 0 -0.685981 -0.727619 0 -0.230267 -0.973127 0 -0.230267 -0.973127 0 0.287147 -0.957886 0 0.287147 -0.957886 0 0.727619 -0.685982 0 0.727619 -0.685982 0 0.973129 -0.23026 0 0.973129 -0.23026 -0.69474 0.699933 -0.165617 -0.694738 0.699936 -0.165618 -0.694742 0.523346 -0.493398 -0.694737 0.523349 -0.493403 -0.69474 0.206534 -0.688971 -0.69474 0.206534 -0.68897 -0.694743 -0.165622 -0.69993 -0.694745 -0.16562 -0.699928 -0.694733 -0.493404 -0.523353 -0.694737 -0.493401 -0.523351 -0.69474 -0.68897 -0.206535 -0.69474 -0.68897 -0.206535 0.698124 -0.693032 -0.179803 0.698124 -0.693033 -0.179803 0.698122 -0.546385 -0.462697 0.698128 -0.546381 -0.462692 0.698126 -0.291523 -0.653937 0.69812 -0.291524 -0.653944 0.69812 0.0210813 -0.71567 0.698117 0.0210822 -0.715673 0.698123 0.329507 -0.635649 0.69811 0.329516 -0.635659 0.698104 0.572692 -0.429739 0.698126 0.572671 -0.429731 0.698126 0.702412 -0.138697 0.698123 0.702415 -0.138697 0 -0.967954 -0.251129 0.0147909 -0.957781 -0.287117 -0.0123565 -0.763072 -0.646195 0 -0.738434 -0.674325 0 -0.538753 -0.842464 -0.0197974 -0.407089 -0.913174 0 -0.337774 -0.941227 0 -0.08266 -0.996578 -0.0222814 0.0294366 -0.999318 0 0.14118 -0.989984 0 0.39259 -0.919714 -0.0197963 0.46013 -0.887631 0 0.587394 -0.809301 0 0.799852 -0.600197 -0.0147899 0.776766 -0.629615 0.0172028 0.980912 -0.193689 0 0.973127 -0.230267 -0.694744 -0.688966 -0.206534 -0.694744 -0.688966 -0.206534 -0.694747 -0.493393 -0.523345 -0.309068 -0.70228 -0.64131 -0.70611 -0.381492 -0.59655 -0.703117 -0.240182 -0.669282 -0.396519 -0.211393 -0.893356 -0.704869 -0.0586338 -0.70691 -0.704868 0.100144 -0.702234 -0.396527 0.26361 -0.879361 -0.694743 0.69993 -0.165622 -0.694735 0.699937 -0.165625 -0.700849 0.554136 -0.44916 -0.462255 0.645215 -0.608291 -0.706108 0.415936 -0.573069 -0.703117 0.27916 -0.653985 0.694794 -0.688921 -0.206517 0.694793 -0.688922 -0.206517 0.69479 -0.493363 -0.523316 0.694806 -0.493355 -0.523302 0.694805 -0.165608 -0.699871 0.694793 -0.165608 -0.699883 0.694798 0.206519 -0.688917 0.694797 0.206519 -0.688917 0.694801 0.523305 -0.49336 0.694787 0.523317 -0.493366 0.694789 0.699887 -0.165612 0.694793 0.699882 -0.165612 0 -0.957887 -0.287144 0 -0.957887 -0.287144 0 -0.685977 -0.727623 0 -0.685977 -0.727623 0 -0.230268 -0.973127 0 -0.230268 -0.973127 0 0.287149 -0.957886 0 0.287149 -0.957886 0 0.727619 -0.685982 0 0.727619 -0.685982 0 0.973127 -0.230268 0 0.973127 -0.230268 -0.69474 0.699933 -0.165623 -0.694735 0.699937 -0.165625 -0.694733 0.523353 -0.493404 -0.694747 0.523345 -0.493393 -0.694744 0.206534 -0.688966 -0.694744 0.206534 -0.688966 -0.69474 -0.165623 -0.699933 -0.694751 -0.165618 -0.699922 -0.694753 -0.493388 -0.523342 -0.694737 -0.493401 -0.523351 -0.694739 -0.688971 -0.206532 -0.694741 -0.68897 -0.206532 3.40462e-05 -0.0746144 -0.997213 -0.320215 -0.359671 -0.876413 0 -0.367356 -0.93008 0 -0.451818 -0.89211 -0.000479744 -0.453526 -0.891243 -0.00615886 -0.461079 -0.887338 -5.50723e-05 -0.0770401 -0.997028 0 -0.076692 -0.997055 -0.0433034 -0.178853 -0.982922 -0.166633 -0.172276 -0.970852 0 -0.275232 -0.961378 -0.0414728 0.232172 -0.97179 -0.159792 0.233582 -0.959117 0 0.331349 -0.943508 -0.012943 0.0294416 -0.999483 -0.0129373 0.0294412 -0.999483 3.60167e-05 0.13314 -0.991097 -4.64048e-05 0.13537 -0.990795 0 0.135553 -0.99077 -0.00885747 0.51598 -0.856555 -0.000474082 0.505207 -0.862998 0 0.503573 -0.863953 0 0.421465 -0.906845 -0.320217 0.410634 -0.853722 0 0.513949 -0.857821 0 0.611351 -0.79136 0 0.611351 -0.79136 0 0.762524 -0.646959 0 0.762524 -0.646959 0 0.880372 -0.474284 0 0.880372 -0.474284 0 0.959743 -0.28088 0 0.959743 -0.28088 0 0.997168 -0.0752006 0 0.997168 -0.0752006 0 -0.464688 -0.885475 0 -0.56371 -0.825973 0 -0.56371 -0.825973 0 -0.723121 -0.690722 0 -0.723121 -0.690722 0 -0.850928 -0.525282 0 -0.850928 -0.525282 0 -0.941546 -0.336885 0 -0.941546 -0.336885 0 -0.991013 -0.133766 0 -0.991013 -0.133766 0 -0.999934 0.0114466 0.179821 -0.978731 0.0987405 0 -0.998221 0.0596159 0 -0.978915 0.204266 0.0915341 -0.967767 0.234625 0 -0.956857 0.290561 0 -0.914693 0.40415 0.0716594 -0.918701 0.3884 -0.0844496 -0.82561 0.557885 0 -0.837459 0.5465 0 -0.992305 -0.123815 0 -0.992305 -0.123815 0 -0.951258 -0.308396 0 -0.951258 -0.308396 0 -0.8762 -0.481948 0 -0.8762 -0.481948 0 -0.769812 -0.63827 0 -0.769812 -0.63827 0 -0.635901 -0.771771 0 -0.635901 -0.771771 0 0.991867 0.127277 0 0.991867 0.127277 0 0.947978 0.318335 0 0.947978 0.318335 0 0.867659 0.497159 0 0.867659 0.497159 0 0.753996 0.656879 0 0.753996 0.656879 0 0.611358 0.791354 0 0.611358 0.791354 0 0.445225 0.895419 0 0.445225 0.895419 0 0.261983 0.965073 0 0.261983 0.965073 0 0.0686728 0.997639 0 0.0686728 0.997639 0 -0.127277 0.991867 0 -0.127277 0.991867 0 -0.318335 0.947978 0 -0.318335 0.947978 0 -0.49716 0.867659 0 -0.49716 0.867659 0 -0.656879 0.753996 0 -0.656879 0.753996 0 -0.791354 0.611358 0 -0.791354 0.611358 0 -0.895419 0.445225 0 -0.895419 0.445225 0 -0.965073 0.261983 0 -0.965073 0.261983 0 -0.997639 0.0686724 0 -0.997639 0.0686724 0 -0.994571 -0.104058 -0.29351 -0.947365 -0.127874 0 -0.978245 -0.207453 0 -0.960007 -0.279975 -0.345754 -0.883476 -0.316108 0 -0.925483 -0.378788 -0.181117 -0.836855 -0.516595 -0.18112 -0.836854 -0.516595 0 -0.89459 -0.446888 -0.345761 -0.678521 -0.648119 0 -0.753383 -0.657582 0 -0.800415 -0.599446 -0.293499 -0.538884 -0.789597 0 -0.623858 -0.781538 0 -0.680518 -0.732731 -0.293502 -0.362941 -0.884382 0 -0.407167 -0.913354 0 -0.538749 -0.842467 0 -0.0602739 -0.998182 0 -0.134701 -0.990886 -0.345755 -0.16798 -0.923166 0 -0.237539 -0.971378 0 -0.309465 -0.950911 -0.181111 0.0289566 -0.983036 -0.181113 0.0289568 -0.983036 0 0.118925 -0.992903 0 0.192793 -0.981239 -0.345757 0.222028 -0.911677 0 0.294305 -0.955712 0 0.364901 -0.931046 -0.293502 0.414368 -0.861484 0 0.460224 -0.887803 0 0.587403 -0.809294 -0.293499 0.584426 -0.756508 0 0.668779 -0.743461 0 0.722469 -0.691403 -0.345754 0.715496 -0.607058 0 0.790782 -0.612098 0 0.919342 -0.393459 -0.181112 0.865813 -0.46644 -0.18111 0.865813 -0.466441 0 0.834314 -0.551289 0 0.946175 -0.323656 -0.345758 0.900549 -0.263557 0 0.974823 -0.222981 0 0.98876 -0.149509 -0.293502 0.953252 -0.0718887 0 0.998972 -0.0453362 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.994571 0.104059 -0.293502 0.947367 0.127874 0 0.894589 0.446891 0 0.925483 0.378789 -0.345755 0.883476 0.316108 0 0.960007 0.279975 0 0.978246 0.20745 -0.181114 0.836855 0.516595 -0.181117 0.836855 0.516595 0 0.800415 0.599446 0 0.753382 0.657583 -0.345759 0.678521 0.64812 0 0.680518 0.732731 0 0.623858 0.781537 -0.2935 0.538884 0.789596 0 0.538748 0.842467 0 0.407168 0.913353 -0.293499 0.362942 0.884382 0 0.309467 0.95091 0 0.237539 0.971378 -0.345755 0.16798 0.923166 0 0.134701 0.990886 -0.181112 -0.0289572 0.983036 -0.181112 -0.0289572 0.983036 0 0.0602739 0.998182 -0.345755 -0.222028 0.911678 0 -0.192793 0.981239 0 -0.118925 0.992903 -0.293499 -0.414369 0.861485 0 -0.364902 0.931046 0 -0.294304 0.955712 -0.293501 -0.584426 0.756507 0 -0.587403 0.809294 0 -0.460223 0.887803 0 -0.834313 0.551291 0 -0.790783 0.612097 -0.345758 -0.715495 0.607057 0 -0.722468 0.691404 0 -0.66878 0.743461 -0.181116 -0.865812 0.46644 -0.181108 -0.865813 0.466441 0 -0.919341 0.393462 0 -0.946175 0.323656 -0.345753 -0.900551 0.263557 0 -0.974823 0.222982 0 -0.988761 0.149508 -0.293501 -0.953252 0.0718881 0 -0.998972 0.0453356 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.680226 -0.733002 0 0.680226 -0.733002 0 0.806048 -0.591851 0 0.806048 -0.591851 0 0.903049 -0.429538 0 0.903049 -0.429538 0 0.967762 -0.251867 0 0.967762 -0.251867 0 0.997873 -0.0651917 0 0.997873 -0.0651917 0 0.859695 -0.510808 0 0.794177 0.607686 0.0716552 0.801772 0.593319 0 0.853579 0.520964 0 0.896551 0.442941 0.117 0.904068 0.411063 0 0.938095 0.346379 0 0.965195 0.261533 0.13656 0.967526 0.212709 0 0.987316 0.158768 0 0.999982 0.00607 0.210809 0.976935 -0.0340352 0 0.997527 0.0702846 0 0.915277 -0.402824 0.128348 0.897632 -0.421643 0 0.944749 -0.327795 0 0.97921 -0.202847 0.170026 0.957898 -0.23135 0 0.991325 -0.131433 0.0859639 0.798356 -0.596018 0 0.811001 -0.585045 0 0.739627 -0.673017 0.0397677 0.670447 -0.740891 0 0.66489 -0.746941 0 -0.619771 -0.784783 -0.0397685 -0.625674 -0.779071 0.0364256 -0.758921 -0.650163 0 -0.76472 -0.644363 0 -0.870592 -0.492005 0.0793437 -0.875754 -0.476193 0 -0.828136 -0.560527 0 -0.992018 -0.1261 0.157188 -0.983235 -0.0924203 0 -0.98187 -0.189555 0 -0.949105 -0.314959 0.118542 -0.949802 -0.289523 0 -0.923816 -0.382837 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.0294437 -0.999566 0 0.0294437 -0.999566 0 0.991013 0.133766 0 0.991013 0.133766 0 0.941545 0.336886 0 0.941545 0.336886 0 0.850928 0.525282 0 0.850928 0.525282 0 0.723121 0.690721 0 0.723121 0.690721 0 0.56371 0.825973 0 0.56371 0.825973 0 0.379662 0.925125 0 0.379662 0.925125 0 0.179021 0.983845 0 0.179021 0.983845 0 -0.0294441 0.999566 0 -0.0294441 0.999566 0 -0.236622 0.971602 0 -0.236622 0.971602 0 -0.433459 0.901173 0 -0.433459 0.901173 0 -0.611351 0.79136 0 -0.611351 0.79136 0 -0.762525 0.646959 0 -0.762525 0.646959 0 -0.880372 0.474284 0 -0.880372 0.474284 0 -0.959743 0.28088 0 -0.959743 0.28088 0 -0.997168 0.0752004 0 -0.997168 0.0752004 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.23417 0.972196 0 0.23417 0.972196 0 0.0591213 0.998251 0 0.0591213 0.998251 0 -0.117778 0.99304 0 -0.117778 0.99304 0 -0.290989 0.956726 0 -0.290989 0.956726 0 -0.999566 -0.0294437 0 -0.999566 -0.0294437 -5.09048e-08 0.0294438 -0.999566 -1.10947e-07 0.0294442 -0.999566 -1.39897e-07 0.0294442 -0.999566 5.94872e-08 0.0294438 -0.999566 1.77332e-07 0.029444 -0.999566 -7.50314e-08 0.0294438 -0.999566 5.39782e-07 0.029443 -0.999566 2.29477e-08 0.0294438 -0.999566 8.32433e-08 0.029444 -0.999566 6.82121e-08 0.0294433 -0.999566 8.67751e-08 0.0294432 -0.999566 0 0.0294447 -0.999566 -6.52646e-08 0.0294436 -0.999566 9.30764e-08 0.0294435 -0.999566 6.72664e-08 0.0294436 -0.999566 0 0.0294444 -0.999566 -2.78397e-08 0.0294442 -0.999566 -2.05769e-07 0.0294435 -0.999566 1.49961e-08 0.0294439 -0.999566 -5.97344e-08 0.0294438 -0.999566 -8.53105e-08 0.0294435 -0.999566 5.24653e-08 0.0294439 -0.999566 -1.41228e-08 0.0294438 -0.999566 1.78505e-07 0.0294437 -0.999566 1.73888e-07 0.0294437 -0.999566 -2.17445e-07 0.0294439 -0.999566 2.18736e-08 0.0294436 -0.999566 6.33498e-08 0.0294436 -0.999566 0 0.0294437 -0.999566 6.06507e-09 0.0294437 -0.999566 5.30263e-07 0.0294443 -0.999566 1.57419e-07 0.029444 -0.999566 1.14779e-06 0.0294446 -0.999566 -7.59718e-08 0.0294438 -0.999566 2.75533e-07 0.0294437 -0.999566 -3.82468e-07 0.0294441 -0.999566 -1.51229e-07 0.0294441 -0.999566 8.01685e-09 0.0294439 -0.999566 -3.96095e-08 0.0294439 -0.999566 0 0.0294439 -0.999566 -1.39523e-08 0.0294439 -0.999566 4.29277e-09 0.0294438 -0.999566 3.51844e-07 0.0294438 -0.999566 3.01214e-07 0.0294438 -0.999566 -3.14887e-07 0.0294439 -0.999566 6.40482e-08 0.0294438 -0.999566 -5.20552e-07 0.0294435 -0.999566 -2.03021e-08 0.0294438 -0.999566 2.65764e-07 0.0294439 -0.999566 -1.32531e-07 0.0294438 -0.999566 -1.93509e-07 0.0294438 -0.999566 0 0.0294438 -0.999566 -4.5085e-08 0.0294436 -0.999566 0 0.0294444 -0.999566 -1.55844e-07 0.0294441 -0.999566 -2.89578e-07 0.0294428 -0.999566 8.82219e-08 0.029444 -0.999566 1.51343e-07 0.0294436 -0.999566 -1.88311e-08 0.0294441 -0.999566 4.81999e-08 0.0294436 -0.999566 1.75387e-08 0.0294441 -0.999566 -1.36513e-07 0.0294436 -0.999566 1.88006e-08 0.0294439 -0.999566 -2.47963e-07 0.029444 -0.999566 -3.57874e-07 0.0294441 -0.999566 -1.16637e-07 0.029444 -0.999566 2.9414e-08 0.0294438 -0.999566 0 0.0294438 -0.999566 0 0.0294438 -0.999566 0 0.0294437 -0.999566 -1.84763e-07 0.0294437 -0.999566 2.32e-07 0.0294438 -0.999566 -4.39805e-08 0.0294438 -0.999566 5.01111e-07 0.0294438 -0.999566 1.5454e-07 0.0294438 -0.999566 1.65957e-08 0.0294439 -0.999566 -2.31851e-08 0.0294439 -0.999566 1.7613e-07 0.029444 -0.999566 3.40557e-08 0.0294437 -0.999566 -2.21229e-08 0.0294436 -0.999566 0 0.0294434 -0.999566 0 0.0294434 -0.999566 1.55394e-08 0.0294436 -0.999566 8.82649e-08 0.0294438 -0.999566 -4.15505e-08 0.0294438 -0.999566 1.88899e-07 0.0294439 -0.999566 -2.75604e-07 0.0294438 -0.999566 2.41886e-08 0.0294438 -0.999566 -1.90584e-07 0.0294439 -0.999566 0 0.999566 0.0294438 0 0.999566 0.0294438 0 0.230266 0.973128 0 0.230266 0.973128 0 0.984054 0.17787 0 0.984054 0.17787 9.84879e-06 0.984049 0.177897 0 0.984054 0.17787 7.35313e-08 0.984054 0.17787 -1.46399e-05 0.98406 0.177836 -2.34193e-08 0.984054 0.17787 -1.44572e-07 0.984054 0.17787 0 -0.992818 0.119638 6.10464e-07 -0.992817 0.119639 0 -0.992818 0.119637 0 -0.992818 0.119637 5.10946e-07 -0.992818 0.119639 6.4829e-07 -0.992818 0.119639 0 -0.287148 0.957886 0 -0.287148 0.957886 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.999566 -0.0294446 0 -0.999566 -0.0294446 0 -0.029444 0.999566 0 -0.029444 0.999566 0 -0.999566 -0.0294436 3.82939e-07 -0.999566 -0.0294435 0 -0.999567 -0.029428 7.62238e-06 -0.999566 -0.0294507 2.53376e-06 -0.999566 -0.0294438 -5.02085e-07 -0.999566 -0.0294439 0 -0.999566 -0.0294431 0 -0.0294432 0.999566 0 -0.0294432 0.999566 0 0.999566 0.0294462 2.65664e-06 0.999566 0.0294442 0 0.999566 0.0294436 0 0.999566 0.0294437 4.69916e-07 0.999566 0.0294444 4.15624e-06 0.999566 0.0294439 -2.05807e-06 0.999566 0.0294523 0 -0.0294435 0.999566 0 -0.0294435 0.999566 0 0.999566 0.0294425 0 0.999566 0.0294425 0 0.727621 -0.68598 0 0.727621 -0.68598 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.68598 -0.72762 0 -0.68598 -0.72762 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.351901 -0.936037 0 -0.351901 -0.936037 0 0.109955 -0.993937 0 0.109955 -0.993937 0 0.547988 -0.836486 0 0.547988 -0.836486 0 -0.497801 -0.867291 0 -0.497801 -0.867291 0 -0.0512594 -0.998685 0 -0.0512594 -0.998685 0 0.406387 -0.913701 0 0.406387 -0.913701 0 0.313413 -0.949617 0 0.313413 -0.949617 0 0.738854 -0.673865 0 0.738854 -0.673865 0 0.974381 -0.224904 0 0.974381 -0.224904 0 -0.959453 -0.281868 0 -0.959453 -0.281868 0 -0.697908 -0.716187 0 -0.697908 -0.716187 0 -0.256974 -0.966418 0 -0.256974 -0.966418 0.160365 0.98314 0.0878539 0.0135722 0.9578 0.287116 0 0.998865 0.0476378 0 0.230267 0.973128 0.0422795 0.165981 0.985222 -0.0318838 0.584839 0.810522 0 0.530844 0.84747 0 0.775083 0.631859 -0.0213389 0.814567 0.579677 0.0339342 0.960943 0.274658 0 0.965773 0.259389 0 -0.999937 -0.0112209 0.00997052 -0.986057 0.166111 0.0851588 -0.995978 0.0278643 0 -0.97937 0.202077 0 -0.97937 0.202077 0 -0.847463 0.530855 0 -0.847463 0.530855 0 -0.579814 0.814749 0 -0.579814 0.814749 0 -0.223886 0.974615 0 -0.223886 0.974615 0 -0.45031 0.892873 0 -0.45031 0.892873 0 -0.321543 0.946895 0 -0.321543 0.946895 0 0.265248 0.96418 0 0.265248 0.96418 0 0.396973 0.91783 0 0.396973 0.91783 0 0.931568 0.363566 0 0.931568 0.363566 0 0.725777 0.68793 0 0.725777 0.68793 0 0.412887 0.910782 0 0.412887 0.910782 0 -0.465781 0.8849 0 -0.465781 0.8849 0 -0.765012 0.644016 0 -0.765012 0.644016 0 -0.951354 0.3081 0 -0.951354 0.3081 0 0.9695 0.245092 0 0.9695 0.245092 0 0.775086 0.631856 0 0.775086 0.631856 0 0.435431 0.900222 0 0.435431 0.900222 0 -0.487664 0.873031 0 -0.487664 0.873031 0 -0.810934 0.585137 0 -0.810934 0.585137 0 -0.982246 0.187599 0 -0.982246 0.187599 0 -0.532626 0.846351 0 -0.532626 0.846351 0 -0.794003 0.607913 0 -0.794003 0.607913 0 -0.955997 0.293377 0 -0.955997 0.293377 0 0.937069 0.349144 0 0.937069 0.349144 0 0.756844 0.653595 0 0.756844 0.653595 0 0.481883 0.876235 0 0.481883 0.876235 0 0.287146 -0.957887 0 0.287146 -0.957887 0 0.727619 -0.685982 0 0.727619 -0.685982 0 0.973128 -0.230266 0 0.973128 -0.230266 0 -0.957886 -0.287149 0 -0.957886 -0.287149 0 -0.685982 -0.727618 0 -0.685982 -0.727618 0 -0.230263 -0.973128 0 -0.230263 -0.973128 0 0.986104 -0.166128 0 0.847467 -0.530848 0.120402 0.794724 -0.59491 0 0.8715 -0.490396 0.00667395 0.884253 -0.46696 0.0159664 0.890582 -0.454542 0 0.915969 -0.401249 0 0.986104 -0.166128 0.0551985 -0.889403 -0.453779 0.00666241 -0.855224 -0.518215 0 -0.841139 -0.54082 0 -0.763885 -0.645353 0.0701526 -0.812743 -0.578384 0 -0.87511 -0.483924 0 -0.974616 -0.223882 0 -0.974616 -0.223882 0.167276 0.963733 0.207936 0.0317184 0.957404 0.287004 0 0.99887 0.0475346 0 0.230266 0.973128 0.084336 0.165535 0.982591 -0.0636682 0.583953 0.809287 0 0.530849 0.847466 0 0.775084 0.631859 -0.042646 0.814009 0.579284 0.0379472 0.931219 0.362478 0 0.938983 0.343964 0 -0.936709 0.35011 0.104085 -0.967842 0.229017 0.016954 -0.992912 0.11764 0 -0.999936 -0.0113556 0 -0.936709 0.35011 0 -0.727621 0.68598 0 -0.727621 0.68598 0 -0.287147 0.957887 0 -0.287147 0.957887 0 0.629753 0.776795 -0.00526074 0.630694 0.776014 0.00519896 0.885473 0.464663 0 0.886048 0.463593 0 -0.911301 0.411742 0.00523923 -0.911789 0.410627 -0.00528418 -0.674379 0.738367 0 -0.675289 0.737553 0 -0.0417606 0.999128 -0.00591437 -0.0404657 0.999163 0.00587292 0.379849 0.92503 -0.0117495 0.383418 0.9235 0.0116769 0.731816 0.681402 -0.0175092 0.736146 0.676596 0.0174229 0.949617 0.312929 0 0.95097 0.309284 0 -0.966536 0.25653 0.0177188 -0.967373 0.252737 -0.018049 -0.770581 0.637086 0.0120278 -0.774759 0.632142 -0.0119548 -0.433617 0.901018 0.00598378 -0.437136 0.899376 -0.00594626 -0.0171217 0.999836 0 -0.0184164 0.99983 0 0.999566 0.0294442 0 0.999566 0.0294442 -0.258818 -0.965507 -0.0284406 -0.195069 -0.980682 -0.0145276 -0.608732 -0.79264 -0.0341737 -0.555571 -0.831109 -0.0244813 -0.79335 -0.608501 -0.0179242 -0.831448 -0.555102 -0.0235942 -0.965869 -0.25901 0.00319469 -0.980785 -0.195007 -0.00574425 0 -0.999566 -0.0294439 0 -0.999566 -0.0294439 0.980787 -0.194998 -0.00574398 0.980787 -0.194998 -0.00574398 0.831469 -0.55533 -0.0163581 0.831469 -0.555331 -0.0163579 0.555567 -0.831111 -0.0244814 0.555569 -0.83111 -0.0244817 0.195089 -0.98036 -0.0288781 0.195089 -0.98036 -0.0288781 1 0 0 1 0 0 0.258819 0.965507 0.028441 0.258816 0.965508 0.0284402 0.707107 0.7068 0.0208197 0.707109 0.706798 0.0208202 0.965926 0.258706 0.00762072 0.965926 0.258706 0.00762072 -0.965926 0.258706 0.00762072 -0.965926 0.258706 0.00762072 -0.707107 0.7068 0.0208202 -0.707109 0.706798 0.0208196 -0.258819 0.965507 0.0284402 -0.258816 0.965508 0.028441 -1 0 0 -1 0 0 0 -0.999566 -0.0294442 0 -0.999566 -0.0294442 -0.195087 -0.980361 -0.0288785 -0.195091 -0.98036 -0.0288777 -0.555573 -0.831107 -0.0244813 -0.555573 -0.831107 -0.0244813 -0.831469 -0.555331 -0.0163579 -0.831469 -0.555331 -0.0163579 -0.980785 -0.195007 -0.00574416 -0.980785 -0.195008 -0.00574434 0.980787 -0.194999 -0.00574407 0.965869 -0.258373 -0.0184365 0.896865 -0.442112 -0.0130233 0.793356 -0.608494 -0.0179244 0.707035 -0.706299 -0.0352582 0.195091 -0.98036 -0.0288785 0.258801 -0.965133 -0.0392539 0.442286 -0.896485 -0.0264071 0.60876 -0.79301 -0.0233591 1 0 0 1 0 0 0.258819 0.965507 0.028441 0.258816 0.965508 0.0284402 0.707107 0.7068 0.0208197 0.707109 0.706798 0.0208202 0.965926 0.258705 0.00762069 0.965926 0.258706 0.00762052 0 0.999566 0.0294442 0 0.999566 0.0294442 -0.965926 0.258705 0.00762049 -0.965926 0.258706 0.00762072 -0.707107 0.7068 0.0208202 -0.707109 0.706798 0.0208196 -0.258819 0.965507 0.0284402 -0.258816 0.965508 0.028441 -1 0 0 -1 0 0 0.707102 0.706805 0.0208201 0.707102 0.706805 0.0208201 0.698571 0.693717 0.175374 0.69857 0.693717 0.175373 0.69857 0.554606 0.452119 0.69857 0.554606 0.452119 0.69857 0.311569 0.644147 0.69857 0.311569 0.644147 0.694741 0.206533 -0.68897 0.69474 0.206532 -0.688971 0.69474 0.523348 -0.4934 0.694742 0.523349 -0.493396 0.694742 0.699931 -0.165621 0.694742 0.699931 -0.165621 0.707101 0.162824 0.688111 0.707101 0.162824 0.688111 0.707101 0.0208201 -0.706806 0.707101 0.0208201 -0.706806 0.707101 0.0208201 -0.706806 0.700424 0.664886 0.259487 0.700426 0.664884 0.259485 0.700426 0.518005 0.490993 0.700425 0.518006 0.490993 0.700426 0.294688 0.650048 0.700426 0.294688 0.650049 0.694742 -0.688969 -0.206534 0.694742 -0.688968 -0.206534 0.694742 -0.493399 -0.523346 0.694741 -0.4934 -0.523346 0.694741 -0.165619 -0.699933 0.694741 -0.165619 -0.699933 0.707102 0.695836 0.125774 0.707099 0.695838 0.125775 0.707097 -0.70681 -0.0208203 0.707102 -0.706805 -0.02082 0.70146 0.667857 0.248838 0.701458 0.66786 0.248837 0.701458 0.539411 0.465824 0.701457 0.539413 0.465824 0.701457 0.343444 0.624503 0.701459 0.343442 0.624502 0.698568 -0.348945 0.624692 0.69857 -0.348945 0.624689 0.698571 -0.580257 0.41869 0.698569 -0.580257 0.418691 0.698569 -0.702839 0.134235 0.698565 -0.702842 0.134238 0.70571 0.16591 0.688801 0.705712 0.165909 0.6888 0.705712 0.0418873 0.70726 0.705709 0.041888 0.707263 0.705708 -0.0834461 0.703572 0.70571 -0.0834461 0.70357 0.70571 -0.206166 0.677841 0.70571 -0.206166 0.677841 0.707101 -0.203046 0.677333 0.7071 -0.203046 0.677335 0.701459 -0.379608 0.603202 0.701458 -0.379608 0.603204 0.701459 -0.565894 0.433266 0.701458 -0.565894 0.433267 0.701458 -0.68135 0.209093 0.70146 -0.681348 0.209091 0.700425 -0.33244 0.631576 0.700425 -0.33244 0.631576 0.700425 -0.546009 0.459651 0.700424 -0.546011 0.459651 0.700424 -0.679007 0.2199 0.700426 -0.679005 0.2199 0.707102 -0.702033 0.0845977 0.707102 -0.702033 0.0845977 -0.694743 -0.69993 0.165618 -0.694735 -0.699938 0.165622 -0.694733 -0.523353 0.493404 -0.694737 -0.523351 0.493401 -0.69474 -0.206535 0.68897 -0.69474 -0.206535 0.68897 -0.694743 0.165622 0.69993 -0.694748 0.165619 0.699925 -0.694743 0.493398 0.523346 -0.694747 0.493394 0.523344 -0.694744 0.688966 0.206534 -0.694744 0.688966 0.206534 0 0.957886 0.287149 0 0.957886 0.287149 0 0.685982 0.727619 0 0.685982 0.727619 0 0.230267 0.973127 0 0.230267 0.973127 0 -0.287149 0.957886 0 -0.287149 0.957886 0 -0.727619 0.685982 0 -0.727619 0.685982 0 -0.973128 0.230263 0 -0.973128 0.230263 0.694798 0.688917 0.206519 0.694797 0.688917 0.206519 0.694801 0.49336 0.523305 0.694797 0.493362 0.523309 0.694802 0.165608 0.699874 0.694797 0.165608 0.69988 0.694794 -0.20652 0.68892 0.694793 -0.20652 0.688921 0.694791 -0.523312 0.493366 0.694787 -0.523316 0.493368 0.694788 -0.699888 0.165608 0.694797 -0.69988 0.165608 -0.69474 -0.699933 0.165623 -0.694738 -0.699934 0.165624 -0.694743 -0.523348 0.493396 -0.694737 -0.523351 0.493401 -0.694739 -0.206531 0.688972 -0.694748 -0.206531 0.688963 -0.694737 0.165621 0.699936 -0.694738 0.165621 0.699935 -0.694743 0.493396 0.523348 -0.694737 0.493401 0.523351 -0.69474 0.68897 0.206535 -0.69474 0.68897 0.206535 0 0.957886 0.287149 0 0.957886 0.287149 0 0.685979 0.727621 0 0.685979 0.727621 0 0.230265 0.973128 0 0.230265 0.973128 0 -0.287143 0.957888 0 -0.287143 0.957888 0 -0.727621 0.685979 0 -0.727621 0.685979 0 -0.973127 0.230268 0 -0.973127 0.230268 0.694794 0.68892 0.20652 0.694793 0.688921 0.20652 0.69479 0.493365 0.523314 0.694796 0.493362 0.523309 0.694792 0.165609 0.699885 0.69479 0.165609 0.699886 0.694802 -0.206514 0.688914 0.694793 -0.206518 0.688921 0.69479 -0.523314 0.493365 0.694796 -0.523309 0.493362 0.694792 -0.699884 0.165611 0.694793 -0.699883 0.165611 -0.694745 0.688967 0.206528 -0.694743 0.688969 0.206528 -0.694747 0.493394 0.523344 -0.309059 0.702285 0.64131 -0.706122 0.381478 0.596545 -0.70313 0.240178 0.669271 -0.396532 0.211388 0.893352 -0.704869 0.0586338 0.70691 -0.704868 -0.100142 0.702234 -0.396518 -0.263609 0.879366 -0.694743 -0.69993 0.165622 -0.694735 -0.699937 0.165625 -0.700849 -0.554136 0.44916 -0.462281 -0.645209 0.608278 -0.706123 -0.415927 0.573057 -0.703128 -0.27916 0.653973 0 0.967954 0.251129 0.0147875 0.957784 0.287109 -0.0123589 0.763079 0.646187 0 0.738437 0.674322 0 0.538742 0.842471 -0.0197962 0.407085 0.913176 0 0.337774 0.941227 0 0.08266 0.996578 -0.0222814 -0.0294363 0.999318 0 -0.141177 0.989984 0 -0.392595 0.919711 -0.0197956 -0.460134 0.887629 0 -0.587394 0.809301 0 -0.799851 0.600199 -0.0147886 -0.776766 0.629615 0.0172033 -0.980912 0.193688 0 -0.973127 0.230267 0.698124 0.693032 0.179803 0.698124 0.693033 0.179803 0.698123 0.546389 0.462691 0.698119 0.546392 0.462694 0.698113 0.291525 0.65395 0.69812 0.291524 0.653944 0.69812 -0.0210811 0.71567 0.698116 -0.0210822 0.715674 0.69811 -0.329516 0.635659 0.69811 -0.329516 0.635659 0.698104 -0.57269 0.42974 0.698118 -0.572677 0.429735 0.698123 -0.702415 0.138697 0.698123 -0.702415 0.138697 -0.694741 -0.699931 0.165622 -0.694737 -0.699935 0.165624 -0.694738 -0.52335 0.4934 -0.694737 -0.523351 0.493401 -0.69474 -0.206534 0.68897 -0.69474 -0.206534 0.68897 -0.694743 0.16562 0.69993 -0.694738 0.165622 0.699934 -0.694743 0.493396 0.523348 -0.694742 0.493397 0.523348 -0.694742 0.688968 0.206534 -0.694742 0.688968 0.206534 0 0.957886 0.287149 0 0.957886 0.287149 0 0.685979 0.727621 0 0.685979 0.727621 0 0.230265 0.973128 0 0.230265 0.973128 0 -0.287148 0.957886 0 -0.287148 0.957886 0 -0.72762 0.68598 0 -0.72762 0.68598 0 -0.973127 0.230268 0 -0.973127 0.230268 0.694796 0.688919 0.206519 0.694795 0.688919 0.206519 0.694795 0.493362 0.523311 0.694796 0.493361 0.52331 0.694792 0.165609 0.699884 0.694797 0.165609 0.69988 0.694794 -0.206519 0.68892 0.694793 -0.206519 0.688921 0.69479 -0.523313 0.493366 0.694791 -0.523313 0.493365 0.69479 -0.699885 0.165611 0.694795 -0.699881 0.165611 -0.694741 -0.699931 0.165622 -0.694736 -0.699936 0.165625 -0.694735 -0.523352 0.493402 -0.694737 -0.523351 0.493401 -0.69474 -0.206535 0.68897 -0.694737 -0.206535 0.688973 -0.69474 0.165621 0.699933 -0.694741 0.165621 0.699932 -0.694745 0.493394 0.523346 -0.694742 0.493397 0.523348 -0.694742 0.688968 0.206534 -0.694741 0.688969 0.206534 0 0.957886 0.287149 0 0.957886 0.287149 0 0.685979 0.727622 0 0.685979 0.727622 0 0.230266 0.973128 0 0.230266 0.973128 0 -0.287149 0.957886 0 -0.287149 0.957886 0 -0.72762 0.685981 0 -0.72762 0.685981 0 -0.973127 0.230268 0 -0.973127 0.230268 0.694795 0.688919 0.20652 0.694795 0.688919 0.206519 0.694795 0.493361 0.523311 0.694799 0.493359 0.523308 0.694795 0.165609 0.699881 0.694793 0.165609 0.699883 0.69479 -0.206521 0.688923 0.694793 -0.206519 0.688921 0.69479 -0.523313 0.493366 0.694789 -0.523314 0.493367 0.694789 -0.699886 0.165612 0.694795 -0.699881 0.165611 -0.694743 -0.69993 0.165622 -0.694735 -0.699937 0.165625 -0.694733 -0.523353 0.493404 -0.694756 -0.52334 0.493385 -0.694748 -0.206533 0.688962 -0.69474 -0.206534 0.68897 -0.694743 0.165622 0.69993 -0.694738 0.165624 0.699934 -0.694743 0.493396 0.523348 -0.694728 0.493408 0.523356 -0.694716 0.688994 0.206535 -0.694744 0.688966 0.206534 0 0.957889 0.28714 0 0.957889 0.28714 0 0.685979 0.727621 0 0.685979 0.727621 0 0.230267 0.973127 0 0.230267 0.973127 0 -0.28715 0.957886 0 -0.28715 0.957886 0 -0.727619 0.685982 0 -0.727619 0.685982 0 -0.973127 0.230267 0 -0.973127 0.230267 0.694799 0.688918 0.206513 0.694771 0.688941 0.206526 0.694781 0.493371 0.52332 0.694796 0.493363 0.523308 0.694792 0.165611 0.699884 0.694796 0.165611 0.699879 0.694794 -0.206521 0.68892 0.694801 -0.206517 0.688914 0.694811 -0.523298 0.493353 0.694787 -0.523318 0.493365 0.694789 -0.699887 0.165611 0.694796 -0.699879 0.165611 -0.69474 -0.699933 0.165623 -0.694738 -0.699934 0.165624 -0.694742 -0.523346 0.493398 -0.694737 -0.523349 0.493403 -0.69474 -0.206534 0.688971 -0.694748 -0.206533 0.688962 -0.694736 0.165624 0.699936 -0.694751 0.165618 0.699922 -0.694753 0.493388 0.523342 -0.694737 0.493401 0.523351 -0.69474 0.68897 0.206535 -0.69474 0.68897 0.206535 0 0.957886 0.287149 0 0.957886 0.287149 0 0.685977 0.727623 0 0.685977 0.727623 0 0.230269 0.973127 0 0.230269 0.973127 0 -0.287147 0.957886 0 -0.287147 0.957886 0 -0.727619 0.685982 0 -0.727619 0.685982 0 -0.973127 0.230268 0 -0.973127 0.230268 0.694794 0.68892 0.20652 0.694793 0.688921 0.20652 0.69479 0.493363 0.523316 0.694806 0.493355 0.523302 0.694806 0.165609 0.699871 0.69479 0.165609 0.699886 0.694802 -0.206517 0.688913 0.694794 -0.206521 0.68892 0.694791 -0.523312 0.493366 0.694796 -0.523308 0.493364 0.694792 -0.699884 0.165611 0.694793 -0.699883 0.165611 -0.694729 -0.699943 0.165624 -0.694735 -0.699938 0.165622 -0.694733 -0.523353 0.493404 -0.694737 -0.523351 0.493401 -0.69474 -0.206535 0.68897 -0.69474 -0.206535 0.68897 -0.694743 0.165622 0.69993 -0.694738 0.165624 0.699934 -0.694743 0.493396 0.523348 -0.694747 0.493393 0.523345 -0.694744 0.688966 0.206534 -0.694731 0.688979 0.206534 0 0.957886 0.287149 0 0.957886 0.287149 0 0.685979 0.727621 0 0.685979 0.727621 0 0.230268 0.973127 0 0.230268 0.973127 0 -0.287149 0.957886 0 -0.287149 0.957886 0 -0.727619 0.685982 0 -0.727619 0.685982 0 -0.973127 0.230267 0 -0.973127 0.230267 0.694784 0.688929 0.206522 0.694797 0.688918 0.206516 0.6948 0.493358 0.523307 0.694796 0.49336 0.52331 0.694792 0.165611 0.699884 0.694796 0.165611 0.699879 0.694794 -0.20652 0.68892 0.694793 -0.20652 0.688921 0.694791 -0.523312 0.493366 0.694787 -0.523316 0.493368 0.694789 -0.699887 0.165611 0.694783 -0.699892 0.165611 -0.694735 -0.699938 0.165624 -0.694743 -0.69993 0.16562 -0.694743 -0.523347 0.493397 -0.694742 -0.523348 0.493397 -0.694742 -0.206534 0.688969 -0.69474 -0.206534 0.68897 -0.694743 0.165621 0.69993 -0.69474 0.165622 0.699933 -0.69474 0.493398 0.523349 -0.694742 0.493397 0.523348 -0.694742 0.688969 0.206533 -0.694741 0.688969 0.206533 0 0.957887 0.287147 0 0.957887 0.287147 0 0.68598 0.727621 0 0.68598 0.727621 0 0.230267 0.973128 0 0.230267 0.973128 0 -0.287148 0.957886 0 -0.287148 0.957886 0 -0.727621 0.68598 0 -0.727621 0.68598 0 -0.973127 0.230268 0 -0.973127 0.230268 0.694795 0.68892 0.206518 0.694795 0.688919 0.206518 0.694795 0.493362 0.52331 0.694794 0.493363 0.523311 0.694794 0.16561 0.699882 0.694796 0.16561 0.69988 0.694794 -0.206519 0.68892 0.694795 -0.206518 0.688919 0.694795 -0.52331 0.493362 0.694796 -0.523309 0.493361 0.694797 -0.699879 0.16561 0.694788 -0.699888 0.16561 -0.694742 -0.699931 0.16562 -0.694743 -0.69993 0.16562 -0.694743 -0.523347 0.493397 -0.69474 -0.523349 0.4934 -0.694738 -0.206534 0.688972 -0.694739 -0.206534 0.688971 -0.694738 0.165622 0.699935 -0.694738 0.165622 0.699934 -0.694735 0.493402 0.523351 -0.694739 0.493399 0.523349 -0.694741 0.688969 0.206535 -0.694735 0.688975 0.206535 0 0.957886 0.287149 0 0.957886 0.287149 0 0.685981 0.72762 0 0.685981 0.72762 0 0.230267 0.973128 0 0.230267 0.973128 0 -0.287148 0.957886 0 -0.287148 0.957886 0 -0.72762 0.68598 0 -0.72762 0.68598 0 -0.973128 0.230265 0 -0.973128 0.230265 0.694788 0.688926 0.206521 0.694794 0.68892 0.206518 0.694793 0.493364 0.523311 0.694789 0.493366 0.523314 0.694792 0.16561 0.699884 0.694792 0.16561 0.699884 0.694792 -0.206519 0.688922 0.694792 -0.20652 0.688922 0.694793 -0.523311 0.493364 0.694796 -0.523309 0.493362 0.694797 -0.69988 0.165608 0.694796 -0.69988 0.165608 0.939691 0.0100705 -0.341877 0.939691 0.0100705 -0.341877 0.923695 -0.173748 -0.341467 0.923696 -0.173757 -0.34146 0.783071 -0.513107 -0.351456 0.783072 -0.513103 -0.351459 0.523229 -0.772833 -0.35911 0.523229 -0.772834 -0.359109 0.183733 -0.913396 -0.363249 0.183734 -0.913396 -0.36325 0.244166 0.920622 -0.304693 0.244168 0.920622 -0.304691 0.667084 0.676556 -0.311883 0.667083 0.676557 -0.311884 0.91125 0.253828 -0.324336 0.911248 0.253831 -0.32434 0 -0.929215 -0.369541 0 -0.929215 -0.369541 0 0.949356 -0.314203 0 0.949356 -0.314203 -0.911249 -0.234299 -0.338718 -0.91125 -0.234297 -0.338715 -0.66708 -0.657028 -0.351167 -0.244168 -0.90109 -0.358356 -0.244169 -0.90109 -0.358354 -0.572626 -0.735931 -0.361255 -0.782094 -0.594925 -0.185456 -0.911249 0.253828 -0.324341 -0.911249 0.253831 -0.324337 -0.667084 0.676556 -0.311884 -0.667082 0.676561 -0.311877 -0.244167 0.920623 -0.304689 -0.244169 0.920621 -0.304693 -0.939691 0.0100705 -0.341877 -0.939691 0.0100705 -0.341877 0.939691 0.0100705 -0.341877 0.939691 0.0100705 -0.341877 0.183734 -0.913396 -0.363248 0.183735 -0.913396 -0.363249 0.415717 -0.83258 -0.366047 0.529895 -0.783858 -0.323693 0.572618 -0.735935 -0.361259 0.783072 -0.513103 -0.351459 0.923695 -0.173748 -0.341466 0.923696 -0.173757 -0.34146 0.84299 -0.405502 -0.353464 0.762191 -0.576419 -0.294629 0.244166 0.920622 -0.304694 0.244168 0.920622 -0.304692 0.667084 0.676556 -0.311883 0.667083 0.676557 -0.311884 0.91125 0.253828 -0.324336 0.911249 0.25383 -0.324339 0 -0.929215 -0.369539 0 -0.929215 -0.369539 0 0.949356 -0.314203 0 0.949356 -0.314203 -0.183735 -0.913396 -0.363248 -0.183734 -0.913396 -0.363249 -0.523234 -0.772831 -0.359109 -0.523232 -0.772831 -0.35911 -0.78307 -0.513106 -0.351459 -0.783067 -0.513108 -0.351462 -0.923693 -0.173757 -0.341467 -0.923693 -0.173756 -0.341466 -0.911249 0.253828 -0.32434 -0.91125 0.253831 -0.324336 -0.667084 0.676556 -0.311884 -0.667082 0.676561 -0.311878 -0.244167 0.920623 -0.304689 -0.244169 0.920621 -0.304693 -0.939691 0.0100705 -0.341877 -0.939691 0.0100705 -0.341877 0 0.183997 0.982927 0 0.183997 0.982927 0 0.576186 0.817318 0 0.576186 0.817318 0 -0.623294 0.781988 0 -0.623294 0.781988 0 -0.241537 0.970392 0 -0.241537 0.970392 0 0.40153 -0.915846 -0.0153895 0.386477 -0.922171 0.0142508 -0.0211502 -0.999675 -0.0284871 -0.0700571 -0.997136 0.0262023 -0.439755 -0.897736 -0.0392761 -0.51129 -0.85851 0.035838 -0.776469 -0.629135 0 -0.806864 -0.590737 0 -0.921656 -0.388008 0.0431575 -0.96884 -0.243898 0 -0.983611 -0.180306 0 0.994583 0.103944 0.0511107 0.997275 -0.0531929 0 0.991823 -0.127625 0 0.941026 -0.338335 0.0447596 0.868187 -0.494215 0 0.837966 -0.545722 0 0.700698 -0.713457 0.0364692 0.555226 -0.8309 -0.0243262 0.49186 -0.870335 0.0262387 0.124493 -0.991873 -0.0131228 0.0799586 -0.996712 0.0140809 -0.332845 -0.942876 0 -0.346928 -0.937892 -0.705184 -0.707017 0.053319 -0.705184 -0.707017 0.053319 -0.705184 -0.680481 0.199151 -0.705174 -0.680491 0.199153 -0.705175 -0.624213 0.336283 -0.70518 -0.624208 0.336281 -0.70518 -0.540652 0.458712 -0.705187 -0.540646 0.458708 -0.705186 -0.433462 0.561092 -0.705188 -0.43346 0.56109 -0.705187 -0.307332 0.638952 -0.705182 -0.307334 0.638956 -0.705183 -0.167771 0.688891 -0.705179 -0.167772 0.688894 -0.705179 -0.0208768 0.708722 -0.705189 -0.020876 0.708712 -0.705187 0.12693 0.697567 -0.705178 0.126931 0.697577 -0.705178 0.269192 0.655942 -0.705185 0.269189 0.655935 -0.705185 0.399684 0.585634 -0.705183 0.399685 0.585636 -0.705182 0.512712 0.48974 -0.705178 0.512715 0.489743 -0.705177 0.603334 0.372441 -0.705179 0.603333 0.37244 -0.70518 0.667583 0.238862 -0.705182 0.66758 0.238861 -0.705183 0.702654 0.0948433 -0.705184 0.702653 0.0948431 -0.258733 -0.864128 -0.431671 -0.258086 -0.822101 -0.507486 -0.258811 -0.0582202 -0.964172 -0.258163 0.0284457 -0.965683 -0.698583 -0.658081 -0.280911 -0.698585 -0.085765 -0.710369 -0.698593 0.572308 -0.429454 -0.965714 -0.0691833 -0.25022 -0.965715 0.182103 -0.185022 -0.965714 0.25934 -0.0117696 -0.965715 0.207645 -0.155815 -0.965715 0.207645 -0.155815 -0.965715 0.228549 -0.123126 -0.965715 0.152493 -0.210097 -0.965715 0.152492 -0.210095 -0.965715 0.119476 -0.230477 -0.965715 0.119476 -0.230477 -0.965715 0.0837903 -0.245709 -0.965714 0.0837924 -0.245716 -0.965714 0.0462346 -0.25546 -0.965714 -0.0311172 -0.257736 -0.965714 -0.0311172 -0.257736 -0.965715 0.00764368 -0.259493 -0.965714 -0.105705 -0.237115 -0.965712 -0.105707 -0.23712 -0.965712 -0.139868 -0.218718 -0.965713 -0.139865 -0.218713 -0.965714 -0.170899 -0.195424 -0.965716 -0.170895 -0.195419 -0.965716 -0.198111 -0.167765 -0.965712 -0.238771 -0.101922 -0.965715 -0.238762 -0.101919 -0.965715 -0.220905 -0.136366 -0.980668 -0.194617 -0.0203621 -0.965698 -0.258345 -0.0261983 -0.965714 -0.251291 -0.065196 -0.607745 0.793412 -0.033818 -0.792659 0.609038 -0.0276399 -0.965715 0.259339 -0.0117696 -0.69858 0.673418 -0.241856 -0.965715 0.254688 -0.0502904 -0.965715 0.244348 -0.087688 -0.706166 0.666433 -0.23916 -0.706167 0.623343 -0.335814 -0.25815 0.850532 -0.458208 -0.258798 0.80589 -0.532508 -0.698633 0.420132 -0.579139 -0.706158 0.415913 -0.573024 -0.706165 0.326025 -0.628521 -0.698586 0.329302 -0.635246 -0.698586 0.230945 -0.677232 -0.69863 0.230932 -0.677191 -0.698624 0.127249 -0.704082 -0.706162 0.126099 -0.696732 -0.706164 0.0208476 -0.707741 -0.698648 -0.291476 -0.653401 -0.706166 -0.288294 -0.646697 -0.706173 -0.381299 -0.5966 -0.698604 -0.385479 -0.602792 -0.698605 -0.471015 -0.538606 -0.698622 -0.471004 -0.538594 -0.698612 -0.546138 -0.46225 -0.70615 -0.540347 -0.457578 -0.706147 -0.602513 -0.371933 -0.698628 0.714758 -0.03226 -0.247976 0.967762 -0.0440965 -0.258137 0.965115 -0.0437997 -0.965714 0.254689 -0.0502908 -0.698588 0.701971 -0.138611 -0.698635 0.701925 -0.138601 0.665824 0.731975 -0.144541 -0.24852 0.95774 -0.144818 -0.258152 0.850531 -0.458208 -0.258802 0.88802 -0.380054 0.431024 0.849498 -0.304256 -0.248089 0.916595 -0.313538 -0.24827 0.944302 -0.215999 -0.965715 0.244347 -0.0876877 -0.965715 0.228549 -0.123127 -0.706165 0.623345 -0.335815 -0.706173 0.566437 -0.424816 0.431041 0.721392 -0.542031 -0.248093 0.766059 -0.592961 -0.965715 0.182103 -0.185022 -0.698638 0.501879 -0.509924 -0.698593 0.501908 -0.509956 0.66583 0.523367 -0.531749 -0.248277 0.699848 -0.669755 0.66586 0.240811 -0.706145 -0.248409 0.353464 -0.901863 -0.247866 0.445703 -0.860181 -0.258152 0.444624 -0.85771 -0.258147 0.567631 -0.781764 -0.247978 0.569056 -0.784016 -0.248526 0.647797 -0.720135 -0.258151 0.0284455 -0.965686 -0.258797 0.114874 -0.959077 0.430981 0.161255 -0.887836 -0.248204 0.18676 -0.950534 -0.248388 0.285081 -0.92576 -0.965715 0.0462337 -0.255454 -0.965715 0.00764367 -0.259492 -0.706155 0.0208477 -0.70775 -0.706165 -0.0846841 -0.702965 0.431029 -0.108717 -0.895765 -0.248102 -0.130489 -0.959905 -0.965714 -0.0691831 -0.250219 -0.698654 -0.190664 -0.689587 -0.698581 -0.190684 -0.689655 0.665828 -0.198826 -0.719125 -0.24829 -0.2301 -0.94096 0.665873 -0.491125 -0.561612 -0.248394 -0.604306 -0.757043 -0.24785 -0.522089 -0.816084 -0.258143 -0.520489 -0.813913 -0.258137 -0.393213 -0.882468 -0.247951 -0.394453 -0.884832 -0.248497 -0.299758 -0.921083 -0.258168 -0.822081 -0.507476 -0.258814 -0.773143 -0.579021 0.430946 -0.688274 -0.583579 -0.248193 -0.72981 -0.637007 -0.248374 -0.659194 -0.70977 -0.965714 -0.198116 -0.167769 -0.965714 -0.220909 -0.136368 -0.706168 -0.602495 -0.371923 -0.706175 -0.651119 -0.278141 0.431043 -0.830107 -0.353728 -0.248144 -0.896537 -0.366941 -0.248495 -0.947561 -0.200945 -0.965712 -0.251295 -0.0651971 -0.698639 -0.692545 -0.179677 -0.698584 -0.692598 -0.179689 0.665808 -0.722211 -0.187379 -0.248326 -0.929937 -0.271205 -0.896278 -0.441085 -0.0461492 -0.792659 -0.606355 -0.0634408 -0.698595 -0.711756 -0.0732689 -0.607649 -0.789904 -0.0825478 -0.24795 -0.963495 -0.100985 -0.441221 -0.892861 -0.0901286 -0.194625 -0.975553 -0.102068 -0.510203 -0.11164 -0.852777 -0.373489 -0.348335 -0.859749 -0.136706 -0.484981 -0.863773 -0.136706 0.534983 -0.833729 -0.373489 0.398337 -0.837755 -0.510203 0.161643 -0.844727 -0.258814 -0.965508 -0.028441 -0.258825 -0.965505 -0.0284401 -0.707099 -0.706808 -0.0208198 -0.707099 -0.706808 -0.0208198 -0.96593 -0.258693 -0.0076201 -0.965929 -0.258696 -0.0076204 -0.96593 0.258693 0.00762031 -0.96593 0.258693 0.00762031 -0.707099 0.706808 0.0208204 -0.707099 0.706808 0.0208204 -0.258814 0.965508 0.028441 -0.258825 0.965505 0.0284401 -0.186162 -0.67399 -0.7149 -0.186156 -0.673987 -0.714904 -0.50858 -0.487915 -0.709427 -0.508592 -0.487914 -0.709418 -0.694751 -0.165613 -0.699924 -0.694748 -0.165615 -0.699927 -0.694747 0.206522 -0.688967 -0.694749 0.206526 -0.688963 -0.508584 0.528831 -0.679471 -0.508585 0.528819 -0.679479 -0.186159 0.714893 -0.673997 -0.186151 0.714905 -0.673987 -0.11675 -0.486229 -0.865997 -0.340299 -0.370149 -0.864399 -0.483398 -0.164467 -0.859812 -0.514174 0.0830983 -0.853651 -0.426413 0.315831 -0.847598 -0.116746 0.536361 -0.835875 -0.240796 0.480617 -0.843223 -0.340301 0.420386 -0.841113 -0.483398 0.214793 -0.848641 -0.514174 -0.032706 -0.857062 -0.426412 -0.265393 -0.86472 -0.240793 -0.430152 -0.870051 -0.22252 -0.974505 -0.0287056 -0.258819 -0.965572 -0.0261429 -0.467284 -0.883724 -0.0260315 -0.652283 -0.757647 -0.0223177 -0.707094 -0.706916 -0.016984 -0.826225 -0.563095 -0.0165869 -0.930879 -0.365169 -0.0107566 -0.965919 -0.258826 -0.00301243 -0.993714 -0.111904 -0.00329632 -0.993713 0.111906 0.00329636 -0.965919 0.258556 0.0122278 -0.930879 0.365169 0.0107566 -0.826225 0.563095 0.0165869 -0.707094 0.70669 0.024656 -0.652287 0.757643 0.0223179 -0.467284 0.883724 0.0260318 -0.258819 0.965437 0.0307384 -0.222514 0.974507 0.0287056 -0.186157 -0.673987 -0.714903 -0.186156 -0.673987 -0.714904 -0.50858 -0.487915 -0.709426 -0.508592 -0.487914 -0.709419 -0.694752 -0.165611 -0.699923 -0.694747 -0.165614 -0.699928 -0.694748 0.206523 -0.688966 -0.69475 0.206527 -0.688963 -0.508586 0.528832 -0.679468 -0.508587 0.528821 -0.679476 -0.186156 0.714898 -0.673993 -0.186154 0.714902 -0.67399 -0.510203 -0.111642 -0.852777 -0.373493 -0.348332 -0.859749 -0.136706 -0.484981 -0.863773 -0.136711 0.534981 -0.83373 -0.373489 0.398337 -0.837755 -0.510203 0.161643 -0.844727 -0.258814 -0.965508 -0.028441 -0.258825 -0.965505 -0.0284401 -0.707105 -0.706802 -0.0208197 -0.707099 -0.706808 -0.0208204 -0.965929 -0.258696 -0.0076204 -0.96593 -0.258693 -0.0076201 -0.96593 0.258693 0.0076201 -0.965929 0.258696 0.0076204 -0.707099 0.706808 0.0208204 -0.707105 0.706802 0.0208197 -0.258825 0.965505 0.0284401 -0.258814 0.965508 0.028441 -0.186161 -0.67399 -0.7149 -0.186156 -0.673987 -0.714904 -0.50858 -0.487915 -0.709426 -0.508592 -0.487914 -0.709419 -0.694752 -0.165611 -0.699923 -0.694746 -0.165615 -0.699928 -0.694748 0.206524 -0.688965 -0.69475 0.206526 -0.688963 -0.508588 0.528826 -0.679471 -0.508588 0.528822 -0.679474 -0.186153 0.714902 -0.67399 -0.186156 0.714898 -0.673993 0.707111 -0.0208199 0.706796 0.707113 -0.0208193 0.706794 0.69475 0.688962 0.206527 0.694752 0.688959 0.206531 0.704067 0.550412 0.448704 0.718855 0.476866 0.505812 0.704067 0.415525 0.575872 0.694751 0.165619 0.699922 0.694752 0.165617 0.699922 0.70022 -0.159838 0.695804 0.700219 -0.159835 0.695806 0.700219 -0.413946 0.581672 0.700217 -0.413941 0.581677 0.700218 -0.605028 0.378993 0.70022 -0.60503 0.378987 0.70022 -0.704008 0.118597 0.700218 -0.704009 0.118604 0.707113 0.706795 0.0208196 0.70711 0.706797 0.0208201 0.707113 -0.706795 -0.0208196 0.70711 -0.706797 -0.0208201 0.695275 0.225264 -0.682531 0.695276 0.225265 -0.682529 0.695276 0.531046 -0.484336 0.695276 0.531046 -0.484336 0.695277 0.700329 -0.161648 0.695277 0.700328 -0.161647 0.695276 -0.6896 -0.20259 0.695275 -0.689602 -0.202588 0.695275 -0.501617 -0.514755 0.695276 -0.501616 -0.514755 0.695276 -0.184698 -0.694607 0.695275 -0.1847 -0.694607 0.706917 0.0208254 -0.70699 0.706918 0.0208256 -0.706989 0.698642 0.702905 -0.133508 0.639687 0.76235 -0.098097 0.706482 0.665993 -0.239451 0.701816 0.596932 -0.38875 0.698659 -0.248211 -0.671019 0.698658 -0.24821 -0.671021 0.698658 0.0572118 -0.713165 0.698659 0.0572101 -0.713164 0.698658 0.352008 -0.62287 0.698659 0.352007 -0.62287 0.706756 0.495714 -0.504741 0.687539 0.569151 -0.450952 0.736835 0.586264 -0.336702 0.70515 -0.44399 -0.552844 0.70515 -0.44399 -0.552844 0.706621 -0.524289 -0.475193 0.755394 -0.501099 -0.422232 0.707038 -0.563972 -0.426653 0.706993 -0.585615 -0.396505 0.707065 -0.585616 -0.396376 0.70515 -0.631047 -0.323331 0.617251 -0.691193 -0.375837 0.707005 -0.65333 -0.270745 0.70515 -0.684647 -0.18445 0.581325 -0.778315 -0.237249 0.706922 -0.694468 -0.134071 0.706381 -0.704721 -0.0662848 0.706495 -0.704612 -0.0662308 0.706743 -0.707424 0.00805458 0.706816 -0.707351 0.00809732 0.706701 -0.703939 0.0710178 0.612039 -0.781038 0.124048 0.706954 -0.56152 0.430013 0.762731 -0.541598 0.353431 0.706538 -0.692755 0.144554 0.706929 -0.67677 0.205509 0.627535 -0.726505 0.279984 0.706167 -0.652159 0.275713 0.706853 -0.616934 0.346051 0.776009 -0.525301 0.349097 0.698868 -0.172759 0.694073 0.698869 -0.172759 0.694073 0.698869 -0.44581 0.559317 0.698868 -0.445812 0.559317 0.707111 -0.0208199 0.706796 0.707111 -0.0208199 0.706796 0.694751 -0.20653 0.68896 0.694751 -0.206531 0.68896 0.694751 -0.523342 0.493391 0.694751 -0.523342 0.493391 0.694751 -0.699922 0.16562 0.694751 -0.699922 0.16562 0.707111 -0.706796 -0.0208203 0.707111 -0.706796 -0.0208203 0.700219 -0.695806 -0.159835 0.700219 -0.695806 -0.159836 0.70022 -0.581672 -0.413944 0.700218 -0.581675 -0.413943 0.707111 -0.485059 -0.514502 0.707111 -0.485059 -0.514502 0.6972 -0.356862 -0.621741 0.697201 -0.35686 -0.621741 0.697201 -0.0367466 -0.715934 0.697199 -0.0367479 -0.715935 0.697199 0.29133 -0.655011 0.6972 0.29133 -0.65501 0.705522 0.482068 -0.51947 0.705523 0.482068 -0.519469 0.705523 0.571236 -0.419437 0.705523 0.571236 -0.419437 0.705523 0.639979 -0.304408 0.705522 0.63998 -0.304408 0.705522 0.685841 -0.178495 0.705522 0.685841 -0.178495 0.705522 0.70718 -0.0462005 0.705522 0.70718 -0.0462005 0.697201 -0.252269 -0.671023 0.6972 -0.252269 -0.671023 0.697201 0.0788244 -0.712529 0.6972 0.078824 -0.71253 0.6972 0.39284 -0.599658 0.6972 0.39284 -0.599657 0.70711 0.514503 -0.485059 0.707111 0.514502 -0.485059 0.700218 0.605032 -0.378988 0.700219 0.605032 -0.378986 0.700218 0.704009 -0.118604 0.700218 0.704009 -0.118604 0.707113 0.706794 0.0208188 0.70711 0.706797 0.0208203 0.694752 0.688959 0.206532 0.694752 0.688959 0.206531 0.704068 0.550413 0.448704 0.740619 0.460929 0.488905 0.704067 0.415528 0.575871 0.694751 0.165619 0.699923 0.694751 0.165619 0.699922 0.707111 -0.0208196 0.706796 0.707111 -0.0208196 0.706796 0.698869 0.412117 0.584587 0.698867 0.412116 0.58459 0.698868 0.131604 0.703039 0.698868 0.131605 0.703039 0.705442 0.707151 -0.0478336 0.593252 0.804529 -0.0280288 0.706924 0.701154 -0.0929613 0.705446 0.684665 -0.183249 0.625463 0.758447 -0.183179 0.707004 0.668136 -0.23182 0.705443 0.636503 -0.311791 0.65475 0.68413 -0.321355 0.707065 0.607931 -0.361217 0.787167 0.477532 -0.390296 0.708923 0.585968 -0.392516 0.707112 0.601161 -0.372288 0.705444 0.471251 -0.529406 0.705444 0.471252 -0.529406 0.7071 0.523001 -0.475899 0.681331 0.586549 -0.437891 0.307966 -0.950424 0.0430339 0.697319 0.277045 -0.661054 0.697319 0.277045 -0.661054 0.697319 -0.0502355 -0.714998 0.697318 -0.0502346 -0.714999 0.697318 -0.366756 -0.615823 0.697319 -0.366756 -0.615822 0.704547 -0.551833 -0.446199 0.720053 -0.559898 -0.409924 0.693538 -0.655798 -0.298217 0.706354 -0.652402 -0.274655 0.703006 -0.699528 -0.128231 0.699625 -0.482501 0.526989 0.69963 -0.482496 0.526987 0.699809 -0.651327 0.293327 0.874977 -0.412838 0.252944 0.706234 -0.227645 0.670381 0.706238 -0.227644 0.670377 0.706238 -0.318808 0.632131 0.706236 -0.318809 0.632133 0.813673 0.521883 0.256077 0.950204 0.295582 0.0987147 0.991529 0.123517 0.0401716 0.856116 0.488501 0.168617 0.704229 0.654146 0.275961 0.698656 0.526762 0.48415 0.698661 0.52676 0.484146 0.698664 0.274335 0.660764 0.698661 0.274336 0.660767 0.698663 -0.0289517 0.714865 0.698659 -0.0289529 0.714868 0.70499 -0.256608 -0.661167 0.701664 -0.124488 -0.701548 0.705426 -0.124018 -0.697849 0.70709 -0.194623 -0.679813 0.775048 -0.230324 -0.588432 0.704171 -0.260834 -0.660385 0.704183 0.299248 -0.643877 0.705219 0.29879 -0.642954 0.773337 0.263783 -0.576514 0.701638 0.165753 -0.692986 0.705422 0.164703 -0.689386 0.707095 0.234303 -0.667172 0.759286 -0.617149 0.206426 0.856109 -0.497591 0.139576 0.950199 -0.300894 0.0811502 0.991527 -0.125684 0.0328364 0.698662 -0.0131761 0.715331 0.69866 -0.0131766 0.715333 0.698659 -0.312757 0.643475 0.698657 -0.312757 0.643476 0.698657 -0.554347 0.452303 0.698663 -0.554341 0.452301 0.706234 -0.652843 0.273917 0.706244 0.281045 0.649795 0.706234 0.281048 0.649804 0.706234 0.18779 0.682619 0.706238 0.187789 0.682615 0.79326 0.5395 0.282274 0.706101 0.58097 0.40484 0.699633 0.450639 0.554472 0.699636 0.450637 0.554469 -0.707043 -0.706864 -0.0208217 -0.707102 -0.706805 -0.0208207 -0.707134 -0.706772 -0.0208238 -0.707146 -0.706761 -0.0208193 -0.695261 -0.184702 -0.69462 -0.695264 -0.184702 -0.694618 -0.695264 -0.501625 -0.514763 -0.695267 -0.501623 -0.514761 -0.695267 -0.689609 -0.202593 -0.695265 -0.689611 -0.202594 -0.706906 0.0208258 -0.707001 -0.706903 0.0208262 -0.707004 -0.695267 0.700338 -0.16165 -0.695262 0.700343 -0.161649 -0.69526 0.531058 -0.484346 -0.695265 0.531053 -0.484344 -0.695267 0.225266 -0.682539 -0.695261 0.225269 -0.682544 -0.707163 0.706744 0.0208187 -0.707102 0.706805 0.0208207 -0.707147 0.70676 0.0208137 -0.707056 0.706851 0.0208213 -0.707077 -0.491022 -0.508861 -0.703099 -0.54752 -0.453734 -0.692045 -0.553385 -0.463507 -0.702383 -0.543733 -0.459362 -0.7071 -0.485066 -0.51451 -0.7071 -0.485066 -0.51451 -0.697188 0.291334 -0.655022 -0.697191 0.291333 -0.655019 -0.697192 -0.0367471 -0.715942 -0.697191 -0.036747 -0.715943 -0.697192 -0.356866 -0.621748 -0.69719 -0.356867 -0.62175 -0.705513 -0.450661 -0.546951 -0.705512 -0.450662 -0.546952 -0.705512 -0.545565 -0.452341 -0.705514 -0.545563 -0.45234 -0.705514 -0.620959 -0.341555 -0.705511 -0.620962 -0.341557 -0.70551 -0.674156 -0.21856 -0.705519 -0.674148 -0.218557 -0.705519 -0.703238 -0.0877467 -0.705513 -0.703244 -0.0877477 -0.697194 0.392843 -0.599662 -0.697187 0.392848 -0.599668 -0.697187 0.0788259 -0.712543 -0.697189 0.0788254 -0.712541 -0.697188 -0.252273 -0.671034 -0.69719 -0.252273 -0.671033 -0.7071 0.51451 -0.485066 -0.707105 0.514507 -0.485062 -0.707077 0.520094 -0.479108 -0.691161 0.582642 -0.427581 -0.702539 0.569677 -0.426506 -0.702377 0.569834 -0.426563 -0.851307 -0.514728 0.101641 -0.851307 -0.0154472 0.524441 -0.851307 -0.241465 0.465801 -0.851307 -0.419657 0.314904 -0.851307 0.507855 0.131757 -0.851307 0.400391 0.339064 -0.851307 0.213629 0.479207 -0.849121 -0.151672 0.505953 -0.849121 -0.384326 0.362335 -0.849122 -0.514003 0.121626 -0.849121 0.505953 0.151674 -0.84912 0.362332 0.384331 -0.849121 0.121627 0.514004 -0.849121 -0.151671 0.505954 -0.849121 -0.384329 0.362333 -0.849121 -0.514005 0.121627 -0.849121 0.505953 0.151674 -0.849121 0.362334 0.384328 -0.849121 0.121627 0.514004 -0.851307 -0.514728 0.101641 -0.851307 -0.0154472 0.524441 -0.851307 -0.241465 0.465801 -0.851307 -0.419657 0.314904 -0.851308 0.507854 0.131757 -0.851308 0.40039 0.339063 -0.851307 0.213626 0.479208 -2.97471e-07 0.0294443 -0.999566 -7.11744e-08 0.0294439 -0.999566 0 0.0294438 -0.999566 9.37688e-08 0.0294438 -0.999566 -7.10095e-08 0.0294439 -0.999566 0 0.0294438 -0.999566 -4.82775e-08 0.0294439 -0.999566 -3.47451e-08 0.0294438 -0.999566 0 0.0294437 -0.999566 2.95854e-07 0.0294443 -0.999566 -7.10097e-08 0.0294437 -0.999566 0 0.0294438 -0.999566 5.12233e-08 0.0294438 -0.999566 8.15239e-09 0.0294438 -0.999566 -9.34074e-08 0.0294437 -0.999566 0 0.0294438 -0.999566 3.56897e-07 0.0294435 -0.999566 0 0.0294439 -0.999566 1.24348e-07 0.0294437 -0.999566 0 0.0294438 -0.999566 -1.1238e-08 0.0294438 -0.999566 -7.95161e-08 0.0294439 -0.999566 -8.38673e-09 0.0294438 -0.999566 0 0.0294437 -0.999566 2.97473e-07 0.0294437 -0.999566 -2.17764e-07 0.029444 -0.999566 2.389e-08 0.0294438 -0.999566 0 0.0294438 -0.999566 1.42386e-07 0.0294438 -0.999566 -1.43928e-07 0.0294439 -0.999566 -2.07572e-08 0.0294438 -0.999566 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.997168 0.0752006 0 -0.997168 0.0752006 0 -0.959743 0.28088 0 -0.959743 0.28088 0 -0.880372 0.474284 0 -0.880372 0.474284 0 -0.762525 0.646959 0 -0.762525 0.646959 0 -0.611351 0.79136 0 -0.611351 0.79136 0 -0.433458 0.901174 0 -0.433458 0.901174 0 -0.236622 0.971602 0 -0.236622 0.971602 0 -0.0294439 0.999566 0 -0.0294439 0.999566 0 0.179021 0.983845 0 0.179021 0.983845 0 0.379662 0.925125 0 0.379662 0.925125 0 0.56371 0.825973 0 0.56371 0.825973 0 0.723121 0.690722 0 0.723121 0.690722 0 0.850928 0.525282 0 0.850928 0.525282 0 0.941546 0.336886 0 0.941546 0.336886 0 0.991013 0.133765 0 0.991013 0.133765 0.938947 0.100322 -0.32911 0.934187 -0.076228 -0.348547 0.939695 -0.329029 -0.0933476 0.939751 -0.328902 -0.0932235 0.940168 -0.327278 -0.0947232 0.942367 -0.320327 -0.0966122 0.951832 -0.289924 -0.0998001 0.946587 -0.304266 -0.10675 0.942452 -0.31477 -0.112715 0.940338 -0.319757 -0.116277 0.935724 -0.329749 -0.125244 0.937605 -0.324456 -0.124998 0.942312 -0.311155 -0.123411 0.939412 -0.326644 -0.103963 0.938857 -0.328743 -0.102348 0.938154 -0.331048 -0.10136 0.938988 -0.329562 -0.0984394 0.939564 -0.328843 -0.0952973 0.943798 -0.321993 -0.0746097 0.939538 -0.333641 -0.0771457 0.941905 -0.327761 -0.0734031 0.938576 -0.33603 -0.0784861 0.940248 -0.33712 -0.0477837 0.934411 -0.34832 -0.0744942 0.94725 -0.313783 -0.0652451 0.944876 -0.320422 -0.0673713 0.938495 -0.337276 -0.0739722 0.943046 -0.32486 -0.0716219 0.941 -0.33034 -0.0734425 0.941705 -0.328428 -0.0729872 0.941423 -0.32916 -0.0733262 0.939849 0.339223 -0.0401547 0.93969 0.339377 -0.0425006 0.940066 0.338326 -0.0425706 0.940187 0.337991 -0.0425611 0.939549 0.341058 -0.0304598 0.940214 0.338472 -0.0378762 0.940417 0.337946 -0.0375216 0.940015 0.338903 -0.0389432 0.939579 0.342286 -0.00565838 0.985127 0.171745 -0.00532014 0.948572 0.315716 -0.0231238 0.940593 0.338458 -0.0270504 0.939281 -0.262751 -0.220712 0.940163 -0.261911 -0.217939 0.939456 -0.279252 -0.198597 0.939673 -0.279445 -0.197295 0.939508 -0.294117 -0.175554 0.93623 -0.298766 -0.184966 0.941652 -0.30195 -0.148719 0.939609 -0.304536 -0.15618 0.939667 -0.313264 -0.137445 0.939516 -0.219476 -0.262944 0.937148 -0.225762 -0.266056 0.93425 -0.232511 -0.270398 0.933489 -0.234186 -0.271579 0.937509 -0.234867 -0.256738 0.938803 -0.235413 -0.251454 0.939338 -0.235998 -0.248895 0.939583 -0.236677 -0.247323 0.940251 -0.242359 -0.239145 0.937569 -0.244957 -0.246903 0.938613 -0.244187 -0.243678 0.939753 -0.243919 -0.239517 0.939318 -0.245532 -0.239572 0.940331 -0.242158 -0.239033 0.949925 -0.21107 -0.230419 0.957628 -0.197568 -0.209561 0.944764 -0.230475 -0.233027 0.941559 -0.238627 -0.237747 0.942682 -0.221936 -0.249187 0.940746 -0.224099 -0.254514 0.930197 -0.229164 -0.286736 0.939594 -0.219244 -0.262858 0.939608 -0.197142 -0.279771 0.941844 -0.198399 -0.271233 0.935831 -0.1792 -0.303494 0.939501 -0.179356 -0.291839 0.939672 -0.155823 -0.304524 0.939547 -0.155382 -0.305135 0.939886 -0.130922 -0.315395 0.939313 -0.130595 -0.317231 0.927833 -0.0850316 -0.363173 0.933931 -0.0866433 -0.346794 0.937525 -0.0884559 -0.336486 0.946744 -0.098367 -0.306594 0.937483 -0.0972654 -0.334163 0.939734 -0.0982324 -0.327492 0.939343 -0.0990067 -0.328379 0.94131 -0.0956779 -0.323699 0.94404 -0.0918446 -0.316784 0.951589 -0.0826196 -0.296062 0.951129 -0.083147 -0.29739 0.940793 -0.0762287 -0.3303 0.935847 -0.0669649 -0.345986 0.942353 -0.067169 -0.32781 0.939718 -0.0650873 -0.3357 0.938798 -0.0677718 -0.337736 0.937528 -0.0705928 -0.340674 0.932627 0.0898388 -0.34948 0.92675 0.0964973 -0.363075 0.934978 0.0862479 -0.344059 0.956713 0.0495655 -0.28678 0.936657 0.07615 -0.341871 0.939638 0.0719112 -0.33453 0.939348 0.0311943 -0.341545 0.939592 0.0307185 -0.340915 0.939641 0.0036287 -0.342144 0.939672 0.00346223 -0.34206 0.939492 -0.0237744 -0.341744 0.935414 -0.0177745 -0.353108 0.942036 -0.0501136 -0.331747 0.939607 -0.0446282 -0.339333 0.939666 -0.0652681 -0.335809 0.940698 -0.0663981 -0.332685 0.93962 0.0719075 -0.33458 0.942608 0.0718917 -0.326069 0.936933 0.0730957 -0.34178 0.93988 0.0939643 -0.328323 0.940791 0.0955378 -0.325245 0.942378 0.096273 -0.320399 0.940658 0.0998476 -0.324334 0.93987 0.102574 -0.325764 0.939691 0.104691 -0.325608 0.939661 0.103748 -0.325997 0.939513 0.102316 -0.326874 0.939717 0.103997 -0.325755 0.939692 0.10474 -0.325589 0.939606 0.118103 -0.321236 0.94223 0.109075 -0.316709 0.934979 0.148762 -0.321999 0.939484 0.137236 -0.313904 0.939671 0.161956 -0.301311 0.939736 0.161576 -0.301314 0.939282 0.186093 -0.288305 0.939704 0.244994 -0.238608 0.939638 0.245771 -0.238071 0.939691 0.244708 -0.238955 0.939385 0.185796 -0.288161 0.939704 0.207716 -0.271682 0.942105 0.214479 -0.257754 0.936601 0.23451 -0.260353 0.939669 0.239356 -0.244399 0.939692 0.244337 -0.239329 0.939694 0.244544 -0.239112 0.939912 0.245742 -0.237017 0.941038 0.24533 -0.232941 0.946917 0.238395 -0.215677 0.938622 0.268627 -0.216398 0.935384 0.27382 -0.223786 0.94028 0.265321 -0.213258 0.939631 0.251336 -0.232216 0.93898 0.249912 -0.236347 0.938246 0.25257 -0.236437 0.939336 0.247879 -0.237073 0.944763 0.243795 -0.219058 0.941559 0.252207 -0.223289 0.917994 0.314534 -0.241567 0.941583 0.261931 -0.211693 0.939486 0.267332 -0.214244 0.939671 0.283385 -0.191602 0.939833 0.282546 -0.192048 0.938953 0.29954 -0.169241 0.939423 0.298047 -0.169268 0.93969 0.309966 -0.14458 0.941987 0.310001 -0.128683 0.936524 0.328625 -0.122184 0.93967 0.32549 -0.105249 0.936498 0.341734 -0.0786759 0.930024 0.360504 -0.071364 0.932281 0.355092 -0.0690135 0.9382 0.336459 -0.0810972 0.938934 0.334048 -0.0825485 0.941863 0.323291 -0.0915311 0.93742 0.336614 -0.0890778 0.938616 0.332998 -0.0900694 0.939669 0.329546 -0.0917737 0.939632 0.32962 -0.0918887 0.940736 0.327193 -0.0892205 0.942122 0.323817 -0.0868876 0.944103 0.31876 -0.0840383 0.947181 0.310544 -0.0800653 0.94237 0.32545 -0.0775916 0.940168 0.332286 -0.0752939 0.936025 0.346749 -0.0601841 0.942921 0.327605 -0.0597923 0.94066 0.334133 -0.0592861 0.939601 0.337202 -0.0586983 0.93873 0.339328 -0.0603596 0.936604 0.344557 -0.0636646 0 0.968433 0.249273 -0.0572596 0.962505 0.265153 0 0.944363 0.328905 0 0.915033 0.40338 -0.064691 0.904868 0.420748 0 0.878338 0.478039 0 0.837292 0.546756 -0.0711025 0.822304 0.564589 0 0.78895 0.614458 0 0.737279 0.675588 -0.0764975 0.717124 0.692735 0 0.678574 0.734532 0 0.617654 0.78645 -0.0808797 0.59225 0.801685 0 0.550148 0.835067 0 0.4816 0.876391 -0.08425 0.451132 0.888471 0 0.407088 0.913389 0 0.332733 0.943021 -0.0866098 0.297653 0.950737 0 0.2532 0.967414 0 0.175017 0.984565 -0.0879631 0.136024 0.986793 0 0.0925768 0.995706 0 -0.029444 0.999566 -0.172492 -0.0694538 0.982559 0 0.0126456 0.99992 0 -0.354431 0.935082 -0.146685 -0.382584 0.912202 0 -0.308779 0.951134 0 -0.194627 0.980877 -0.159633 -0.22875 0.960308 0 -0.150062 0.988677 0 -0.64051 0.767949 -0.120571 -0.657316 0.743908 0 -0.597568 0.801818 0 -0.504441 0.863446 -0.133663 -0.526757 0.839441 0 -0.459282 0.88829 0 -0.856278 0.516516 -0.0942029 -0.863682 0.495156 0 -0.823196 0.567758 0 -0.75888 0.65123 -0.107414 -0.770668 0.628118 0 -0.719959 0.694017 0 -0.978048 0.20838 -0.0676235 -0.978994 0.19235 0 -0.96182 0.273684 0 -0.930013 0.367526 -0.0809309 -0.933777 0.348585 0 -0.90454 0.426389 0 -0.96819 -0.250216 -0.0547559 -0.96264 -0.265191 0 -0.944043 -0.329823 0 -0.91464 -0.40427 -0.062506 -0.904994 -0.420807 0 -0.877871 -0.478896 0 -0.83676 -0.547571 -0.0692313 -0.822412 -0.564664 0 -0.788351 -0.615226 0 -0.736621 -0.676305 -0.0749403 -0.717209 -0.692817 0 -0.677858 -0.735192 0 -0.616888 -0.787051 -0.0796337 -0.59231 -0.801765 0 -0.549335 -0.835602 0 -0.480746 -0.87686 -0.083315 -0.451168 -0.888542 0 -0.4062 -0.913784 0 -0.331816 -0.943344 -0.0859885 -0.297669 -0.950789 0 -0.252258 -0.96766 0 -0.174058 -0.984735 -0.0876518 -0.136027 -0.98682 0 -0.0916072 -0.995795 0 -0.0116724 -0.999932 -0.0883111 0.0293283 -0.995661 0 0.0714803 -0.997442 0 0.354431 -0.935082 -0.15069 0.383238 -0.911274 0 0.309706 -0.950832 0 0.194627 -0.980877 -0.163607 0.229531 -0.959452 0 0.151026 -0.98853 0 0.640511 -0.767949 -0.124622 0.657708 -0.742893 0 0.598348 -0.801236 0 0.504441 -0.863446 -0.137692 0.52728 -0.838461 0 0.460147 -0.887843 0 0.856278 -0.516515 -0.0982858 0.863821 -0.494119 0 0.82375 -0.566953 0 0.75888 -0.651231 -0.111484 0.770931 -0.627086 0 0.720633 -0.693316 0 0.978048 -0.20838 -0.0717385 0.978898 -0.191343 0 0.962086 -0.272748 0 0.930013 -0.367526 -0.0850352 0.933795 -0.347556 0 0.904954 -0.42551 0.422643 -0.899811 0.108228 0.42754 -0.896752 0.114218 0.422552 -0.899402 0.111915 0.4447 -0.878876 0.172679 0.421781 0.892113 0.16197 0.427441 0.888531 0.166752 0.424201 0.890298 0.165599 0.423091 0.891419 0.162376 0.422435 0.892316 0.159124 0.227025 -0.678304 0.69883 0.422539 -0.577225 0.698765 0.422478 -0.54162 0.726747 0.503856 -0.494807 0.708022 0.354689 -0.496969 0.791971 0.422542 -0.458107 0.782047 0.422444 -0.416288 0.805137 0.504658 -0.375066 0.77759 0.362301 -0.360491 0.859526 0.422542 -0.327208 0.845218 0.422405 -0.27988 0.862114 0.503951 -0.246065 0.82794 0.369597 -0.215314 0.903902 0.422551 -0.187892 0.88665 0.422372 -0.136019 0.896159 0.501736 -0.110723 0.857906 0.376585 -0.0653198 0.924076 0.42255 -0.0437501 0.905283 0.422325 0.0114626 0.906372 0.497983 0.0279045 0.866738 0.383264 0.0855075 0.919672 0.422553 0.101522 0.900634 0.422278 0.158647 0.892475 0.492664 0.166672 0.854109 0.389649 0.233188 0.890953 0.422554 0.244178 0.872826 0.422227 0.30162 0.854839 0.485729 0.302402 0.820135 0.395742 0.373854 0.838821 0.42256 0.380556 0.822569 0.422176 0.436577 0.794461 0.477112 0.431936 0.765373 0.401544 0.503847 0.764788 0.422561 0.507148 0.751161 0.422118 0.559929 0.712949 0.466743 0.55219 0.690823 0.407066 0.619809 0.67092 0.422565 0.620697 0.660435 0.422058 0.668394 0.612468 0.454525 0.660216 0.597931 0.412312 0.718767 0.559798 0.422567 0.718284 0.552725 0.421994 0.759088 0.495688 0.440356 0.753252 0.488567 0.417287 0.798212 0.43443 0.422569 0.797399 0.430803 0.421926 0.829597 0.365716 0.424116 0.828787 0.365017 0.421997 0.856157 0.298185 0.422571 0.856007 0.297801 0.421855 0.878043 0.226007 0.405676 0.884616 0.22996 0.423539 0.89056 0.165886 0.594071 -0.532638 0.602806 0.422507 -0.652541 0.629029 0.422536 -0.681499 0.597514 0.22293 -0.782048 0.581983 0.575946 -0.633678 0.516467 0.422539 -0.746099 0.514585 0.422538 -0.768246 0.480895 0.218833 -0.865843 0.449919 0.556932 -0.720542 0.413092 0.422556 -0.819818 0.386452 0.42253 -0.83524 0.351912 0.320927 -0.887294 0.331232 0.485215 -0.830365 0.27397 0.422581 -0.871722 0.248046 0.422532 -0.880752 0.213876 0.25607 -0.952078 0.16726 0.406301 -0.900752 0.153506 0.397689 -0.889575 -0.224722 0.466203 -0.85693 -0.219833 0.531482 -0.820124 -0.211951 0.427312 -0.888603 -0.166701 0.420179 0.900331 -0.113373 0.423902 0.898752 -0.112034 0.423036 0.899475 -0.109475 0.422462 0.900131 -0.10625 0.406051 -0.890263 -0.206285 0.264933 -0.937552 -0.225402 0.422524 -0.86664 -0.265346 0.422573 -0.855613 -0.298928 0.485211 -0.812801 -0.322374 0.320928 -0.866259 -0.382886 0.422531 -0.813078 -0.400466 0.422557 -0.795647 -0.434041 0.492255 -0.747431 -0.44613 0.329877 -0.789921 -0.51692 0.422531 -0.738611 -0.525283 0.422531 -0.71452 -0.557609 0.49768 -0.664141 -0.557881 0.33848 -0.693141 -0.636386 0.422536 -0.645146 -0.636592 0.422508 -0.614383 -0.666349 0.501537 -0.564973 -0.655184 0.346751 -0.578615 -0.73822 0.42254 -0.535093 -0.73153 0.422478 -0.497903 -0.757367 0.503855 -0.452274 -0.73592 0.354685 -0.449491 -0.819852 0.422542 -0.411278 -0.807656 0.422445 -0.368175 -0.828244 0.504659 -0.328645 -0.798318 0.362301 -0.309273 -0.879255 0.422547 -0.276887 -0.863011 0.422548 -0.135376 -0.896173 0.421999 -0.206676 -0.882724 0.555081 -0.209827 -0.804896 0.369595 -0.161733 -0.915009 0.422548 0.0096119 -0.90629 0.421989 -0.0629181 -0.904415 0.542889 -0.0769321 -0.836273 0.376586 -0.0108131 -0.926319 0.421977 0.0824599 -0.902849 0.530157 0.0606081 -0.84573 0.341363 0.160079 -0.9262 0.422354 0.136895 -0.896034 0.42197 0.225718 -0.878062 0.516865 0.199178 -0.832574 0.35914 0.303906 -0.882417 0.422397 0.280721 -0.861845 0.421963 0.363172 -0.830694 0.502981 0.335058 -0.79671 0.37466 0.438157 -0.817097 0.422433 0.417075 -0.804736 0.421953 0.49129 -0.761965 0.488499 0.46451 -0.738647 0.388052 0.559779 -0.732164 0.422469 0.542329 -0.726222 0.421946 0.606772 -0.673638 0.47339 0.583896 -0.659521 0.3994 0.666084 -0.62993 0.422499 0.653156 -0.628396 0.421937 0.706653 -0.567989 0.457638 0.689764 -0.561064 0.408794 0.754779 -0.513026 0.422525 0.746607 -0.513859 0.421927 0.788362 -0.447731 0.44122 0.778963 -0.445579 0.416301 0.823999 -0.384343 0.422549 0.820196 -0.385657 0.421918 0.849797 -0.315958 0.424121 0.848725 -0.315893 0.421983 0.872316 -0.246973 0.422569 0.871968 -0.2472 0.421909 0.88938 -0.176058 0.406322 0.896759 -0.175287 0.423779 0.898782 -0.112258 0.424892 0.89804 -0.113976 0.424659 0.898203 -0.113564 -0.705887 -0.692775 0.1476 -0.705894 -0.692768 0.147599 -0.705894 -0.658745 0.260325 -0.705894 -0.658745 0.260325 -0.705894 -0.606517 0.365857 -0.705889 -0.606521 0.365859 -0.70589 -0.537531 0.46128 -0.705889 -0.537532 0.461281 -0.70589 -0.453688 0.543955 -0.70589 -0.453687 0.543955 -0.705889 -0.357307 0.611598 -0.705891 -0.357306 0.611597 -0.705891 -0.25105 0.662338 -0.705888 -0.251052 0.662341 -0.705889 -0.137858 0.694778 -0.705892 -0.137858 0.694775 -0.705891 -0.0208558 0.708013 -0.705891 -0.0208559 0.708014 -0.705891 0.0967232 0.701686 -0.705891 0.0967232 0.701685 -0.705892 0.211629 0.675966 -0.705889 0.211629 0.675968 -0.70589 0.320687 0.631569 -0.705888 0.320688 0.63157 -0.705888 0.420883 0.569719 -0.705893 0.420881 0.569715 -0.705893 0.509445 0.492119 -0.705894 0.509444 0.492118 -0.705894 0.58393 0.400923 -0.705894 0.58393 0.400923 -0.705894 0.64228 0.298649 -0.705892 0.642281 0.29865 -0.705892 0.682881 0.188122 -0.705892 0.682881 0.188122 -0.705892 0.69277 -0.1476 -0.705892 0.692771 -0.1476 -0.705892 0.658747 -0.260326 -0.705892 0.658746 -0.260326 -0.705892 0.606519 -0.365858 -0.705893 0.606518 -0.365857 -0.705892 0.537529 -0.461279 -0.705891 0.53753 -0.46128 -0.705891 0.453687 -0.543954 -0.705893 0.453686 -0.543953 -0.705893 0.357305 -0.611595 -0.705893 0.357305 -0.611595 -0.705893 0.25105 -0.662336 -0.705898 0.251048 -0.662331 -0.705898 0.137857 -0.694769 -0.705892 0.137858 -0.694775 -0.705891 0.0208553 -0.708013 -0.705891 0.0208554 -0.708014 -0.705891 -0.0967228 -0.701686 -0.705899 -0.0967221 -0.701678 -0.705897 -0.211627 -0.675961 -0.705891 -0.211629 -0.675967 -0.705892 -0.320686 -0.631567 -0.705894 -0.320685 -0.631565 -0.705894 -0.42088 -0.569713 -0.705894 -0.42088 -0.569714 -0.705894 -0.509444 -0.492118 -0.70589 -0.509447 -0.492121 -0.70589 -0.583934 -0.400926 -0.705893 -0.583931 -0.400924 -0.705893 -0.64228 -0.29865 -0.705891 -0.642282 -0.298651 -0.705891 -0.682882 -0.188122 -0.705893 -0.68288 -0.188122 0 0.980622 0.195911 0.00132324 0.988747 0.149593 0.00783465 0.993166 0.116446 0 0.997573 0.0696279 0 0.93415 0.35688 0.00414377 0.957878 0.287145 0.0101966 0.951947 0.306092 0 0.971947 0.235199 0 0.861457 0.507831 0.00564318 0.893457 0.449113 0.00737779 0.890615 0.454698 0 0.919038 0.394168 0 0.840332 0.542072 0.00493957 0.806251 0.591553 0.00676055 0.80189 0.597433 0.0104313 0.701005 0.71308 0.0040115 0.685975 0.727614 0 0.738037 0.67476 0 0.764581 0.644527 0.0136594 0.57765 0.81617 0.00210068 0.549207 0.835683 0 0.615024 0.788508 0 0.646245 0.76313 0.00144183 0.365803 0.930691 0.00781864 0.395738 0.91833 -8.66464e-05 0.439434 0.898275 8.90708e-05 0.510221 0.860043 0 0.321148 0.947029 0 0.282791 0.959182 0.0074066 0.23026 0.973101 0.00317672 0.211931 0.97728 0 0.158528 0.987355 0 -0.00854017 0.999964 0.00574362 0.057785 0.998313 0.0071749 0.0525808 0.998591 0 0.118683 0.992932 0 -0.175367 0.984503 0.00683124 -0.116447 0.993173 0.00476628 -0.108126 0.994126 0 -0.0487561 0.998811 0 -0.214826 0.976652 0.0027388 -0.266041 0.963958 0.00753662 -0.287139 0.957859 0 -0.337271 0.941408 0 -0.374867 0.927078 0.00193646 -0.449119 0.89347 0.0139258 -0.417039 0.908782 0.000180239 -0.48879 0.872402 0 -0.524369 0.851491 0 -0.558212 0.829698 0.00780038 -0.597429 0.801884 0.00156299 -0.622275 0.782797 0 -0.659186 0.75198 0 -0.775477 0.631376 0.00440154 -0.727613 0.685974 0.00973417 -0.739643 0.67293 0 -0.688898 0.724858 0 -0.870003 0.493047 0.00584152 -0.835671 0.5492 0.00697422 -0.837941 0.545717 0 -0.800248 0.59967 0 -0.940109 0.340873 0.00689982 -0.918337 0.39574 0.00459476 -0.914575 0.40439 0 -0.889135 0.457646 0 -0.983824 0.179138 0.00757532 -0.9731 0.230261 0.00259757 -0.967567 0.252601 0 -0.953059 0.302786 0 -0.999924 0.0123704 0.00786861 -0.998298 0.0577842 0.000981071 -0.995545 0.0942826 0 -0.990234 0.139414 0.201868 0.978945 -0.0302597 0.203403 -0.313865 -0.927424 0.575882 0.658115 -0.485021 0.575888 -0.485018 -0.658111 0.575896 -0.799444 -0.170975 0.852356 -0.238221 -0.465555 0.852353 0.247596 -0.460641 0.851972 0.334902 -0.402473 0.851971 0.455859 -0.257562 0.850693 0.525408 -0.0164029 0.904325 0.421937 -0.0645456 0.85235 0.519727 -0.0581593 0.851971 0.523338 -0.0162115 0.851971 0.483581 -0.200736 0.852349 0.497606 -0.160903 0.904555 0.41061 -0.114802 0.85221 0.506633 -0.130622 0.852207 0.515497 -0.0894733 0.852213 0.38798 -0.351005 0.852206 0.414949 -0.318688 0.904088 0.344013 -0.253533 0.852352 0.433236 -0.29292 0.852212 0.180539 -0.49106 0.852201 0.219436 -0.474975 0.852347 0.150496 -0.500854 0.851972 0.109502 -0.512009 0.85197 0.109503 -0.512012 0.85197 0.0469883 -0.521477 0.851973 0.0469876 -0.521473 0.852356 0.00529303 -0.522936 0.903598 -0.0132637 -0.428177 0.852202 -0.0263038 -0.522551 0.852218 -0.0682206 -0.518719 0.905209 -0.0642616 -0.420081 0.852345 -0.0993773 -0.513451 0.851971 -0.140983 -0.504251 0.851974 -0.140982 -0.504247 0.851974 -0.200734 -0.483577 0.851968 -0.359175 -0.380978 0.852341 -0.326511 -0.408539 0.905413 -0.251863 -0.341748 0.852217 -0.301364 -0.427675 0.852196 -0.266028 -0.450545 0.85222 -0.465533 -0.238746 0.852195 -0.444869 -0.275418 0.851975 -0.495073 -0.170418 0.852347 -0.478909 -0.210121 0.868557 -0.492326 -0.0567788 0.851969 -0.512014 -0.109503 0.851965 -0.512019 -0.109504 0.852381 -0.517746 -0.0733859 0.880406 -0.471798 -0.0478694 0.575893 -0.814227 -0.0733665 0.575883 -0.628423 -0.522918 0.852357 -0.427213 -0.301623 0.851972 -0.402473 -0.334902 0.575891 -0.62842 -0.522914 0.57589 -0.560807 -0.594849 0.203052 -0.67169 -0.712462 0.203391 -0.617254 -0.76002 0.575884 0.170978 -0.799453 0.575883 0.170978 -0.799453 0.575883 0.073367 -0.814234 0.57588 0.0733673 -0.814235 0.57588 -0.0253127 -0.817142 0.575877 -0.0253125 -0.817144 0.575877 -0.123624 -0.808135 0.575882 -0.123624 -0.808132 0.575882 -0.220132 -0.787339 0.575882 -0.220132 -0.787338 0.575883 0.522918 -0.628423 0.85197 0.283949 -0.439909 0.85197 0.334904 -0.402475 0.575886 0.522916 -0.628422 0.575886 0.594851 -0.560809 0.203059 0.712461 -0.671689 0.203396 0.760018 -0.617254 0.572873 0.819255 -0.0252465 0.575886 0.817136 -0.0253788 0.575885 0.80813 -0.123623 0.575885 0.80813 -0.123623 0.575885 0.787337 -0.220131 0.575885 0.787337 -0.220131 0.203053 -0.975217 -0.087873 0.203059 -0.975216 -0.0878725 0.203344 -0.963788 -0.172524 0.84078 -0.539838 -0.0407952 0.893227 -0.447792 -0.040349 0.575883 -0.814234 -0.0733678 0.575883 -0.799453 -0.170978 -0.0764914 -0.975021 -0.208527 0.203314 -0.951618 -0.230404 0.203395 -0.907344 -0.367909 0.851969 -0.495081 -0.170422 0.575889 -0.773011 -0.266093 0.575896 -0.773007 -0.266091 0.0933504 -0.941418 -0.324064 0.203142 -0.927951 -0.312476 0.905611 -0.381453 -0.185372 0.575886 -0.735303 -0.357329 0.575889 -0.735301 -0.357328 0.203063 -0.880682 -0.427978 0.203044 -0.880685 -0.42798 0.903076 -0.360841 -0.232913 0.575883 -0.686872 -0.443357 0.575886 -0.68687 -0.443355 -0.0482351 -0.8392 -0.54168 0.203379 -0.843331 -0.497422 0.203048 -0.67169 -0.712463 0.203386 -0.72237 -0.660921 0.00852489 -0.768655 -0.639606 0.203209 -0.760986 -0.616122 0.203267 -0.811778 -0.547448 0.85197 -0.402476 -0.334904 0.85197 -0.359173 -0.380975 0.575893 -0.560806 -0.594848 0.575892 -0.485017 -0.658109 0.00853045 -0.593252 -0.804971 0.203195 -0.570263 -0.795934 0.203373 -0.44692 -0.87115 0.90334 -0.210995 -0.37344 0.575886 -0.402156 -0.711777 0.575888 -0.402155 -0.711775 -0.0482432 -0.491343 -0.869629 0.203253 -0.498716 -0.842597 0.851972 -0.200735 -0.483579 0.575882 -0.31343 -0.755064 0.575886 -0.313429 -0.755062 0.203052 -0.375398 -0.904348 0.203057 -0.375398 -0.904347 0.0792373 -0.261967 -0.961819 0.203057 -0.263654 -0.943003 0.203303 -0.173989 -0.963533 -0.076481 -0.150773 -0.985606 0.203346 -0.115495 -0.972271 0.203061 -0.0303174 -0.978697 0.203053 -0.0303169 -0.978698 0.203052 0.087873 -0.975217 0.203059 0.0878725 -0.975216 0.203345 0.172524 -0.963787 -0.0764862 0.208526 -0.975021 0.203305 0.230403 -0.95162 0.20341 0.36791 -0.90734 0.904997 0.138467 -0.402254 0.575884 0.266094 -0.773015 0.575883 0.266094 -0.773015 0.0933605 0.324063 -0.941418 0.203134 0.312477 -0.927952 0.903846 0.187011 -0.384825 0.575884 0.357331 -0.735305 0.575884 0.357331 -0.735305 0.203056 0.427979 -0.880683 0.203058 0.427979 -0.880682 0.851972 0.283947 -0.439906 0.575883 0.443357 -0.686873 0.575883 0.443357 -0.686872 -0.0482351 0.54168 -0.8392 0.203372 0.497424 -0.843332 0.203054 0.712462 -0.67169 0.203392 0.66092 -0.722368 0.0085279 0.639606 -0.768655 0.203202 0.616124 -0.760987 0.20326 0.547448 -0.81178 0.852349 0.365924 -0.373633 0.904779 0.309879 -0.292146 0.575882 0.594853 -0.560811 0.575882 0.658114 -0.485021 0.00852955 0.804972 -0.593252 0.203196 0.795934 -0.570263 0.203373 0.87115 -0.44692 0.851972 0.455858 -0.257561 0.575884 0.711777 -0.402157 0.575882 0.711779 -0.402157 -0.048242 0.869629 -0.491343 0.203253 0.842597 -0.498716 0.851971 0.483581 -0.200736 0.575884 0.755062 -0.313429 0.575885 0.755062 -0.313429 0.203058 0.904347 -0.375398 0.203057 0.904347 -0.375398 0.203059 0.978697 -0.0303172 0.203344 0.972272 -0.115494 -0.0764892 0.985605 -0.150772 0.203304 0.963533 -0.173989 0.203058 0.943003 -0.263654 0.0792367 0.961819 -0.261966 0.203409 0.927422 -0.313868 0.705757 0.703634 0.0824993 0.705757 0.703634 0.0824993 0.705757 0.678619 0.203431 0.705757 0.678618 0.203431 0.705757 0.632983 0.318181 0.705757 0.632983 0.318181 0.705757 0.568115 0.423264 0.705756 0.568116 0.423264 0.705756 0.485986 0.515486 0.705757 0.485985 0.515485 0.705757 0.389089 0.592044 0.705757 0.389089 0.592045 0.705757 0.280371 0.650615 0.705757 0.280371 0.650615 0.705757 0.163133 0.689416 0.705757 0.163133 0.689416 0.705757 0.0409387 0.70727 0.705757 0.0409389 0.70727 0.705757 -0.0824992 0.703634 0.705756 -0.0824991 0.703635 0.705756 -0.203431 0.678619 0.705757 -0.203431 0.678618 0.705757 -0.318181 0.632984 0.705758 -0.318181 0.632983 0.705758 -0.423263 0.568115 0.705756 -0.423264 0.568116 0.705756 -0.515486 0.485986 0.705757 -0.515485 0.485985 0.705757 -0.592044 0.389089 0.705758 -0.592044 0.389088 0.705758 -0.650614 0.28037 0.705756 -0.650615 0.280371 0.705756 -0.689417 0.163134 0.705758 -0.689415 0.163133 0.705758 -0.707269 0.0409386 0.705758 -0.707269 0.0409386 0.705154 -0.433481 0.561117 0.705154 -0.433481 0.561117 0.705155 -0.540671 0.458729 0.705156 -0.54067 0.458728 0.705156 -0.62423 0.336292 0.705155 -0.624231 0.336293 0.705155 -0.680509 0.199159 0.705156 -0.680508 0.199159 0.705156 -0.707044 0.0533212 0.705156 -0.707045 0.0533212 0.705155 -0.167778 0.688917 0.705158 -0.167776 0.688914 0.705158 -0.307344 0.638977 0.759496 -0.276199 0.588965 0.707082 -0.365518 0.605336 0.714702 -0.0205939 0.699126 0.714703 -0.0205937 0.699125 0.707099 -0.0935084 0.700904 0.755262 0.248839 0.606349 0.705507 0.262616 0.65825 0.705158 0.126935 0.697596 0.705157 0.126935 0.697596 0.707101 0.0520635 0.705193 0.705157 0.702679 0.0948465 0.705156 0.70268 0.0948469 0.705156 0.667605 0.23887 0.705152 0.667608 0.238871 0.705152 0.603356 0.372455 0.705155 0.603354 0.372453 0.705155 0.512731 0.489759 0.705157 0.51273 0.489757 0.705156 0.3997 0.585658 0.705156 0.3997 0.585658 0.707083 0.329248 0.625803 0 -0.981056 0.193724 0 -0.981056 0.193724 0 -0.799855 0.600193 0 -0.799855 0.600193 0 -0.460224 0.887803 0 -0.460224 0.887803 0 -0.029438 0.999567 0 -0.029438 0.999567 0 0.407161 0.913356 0 0.407161 0.913356 0 0.763138 0.646236 0 0.763138 0.646236 0 0.967953 0.251132 0 0.967953 0.251132 0 -0.981058 0.193715 0 -0.981058 0.193715 0 -0.799851 0.600199 0 -0.79985 0.600199 0 -0.460221 0.887804 0 -0.460221 0.887804 0 -0.029438 0.999567 0 -0.029438 0.999567 0 0.407163 0.913355 0 0.407163 0.913355 0 0.763134 0.64624 0 0.763134 0.64624 0 0.967953 0.251132 0 0.967953 0.251132 0 0.585036 0.811008 0 -0.973126 0.230271 0 -0.973126 0.230271 0 -0.727622 0.685979 0 -0.727622 0.685979 0 -0.287148 0.957886 0 -0.287148 0.957886 0 0.230267 0.973127 0.0184925 0.352179 0.93575 0 0.100543 0.994933 0.0190759 0.775422 0.631155 0 0.685979 0.727621 0 0.912565 0.408932 0.00946954 0.957845 0.28713 0 0.987307 0.158823 0 -0.981057 0.193717 0 -0.981057 0.193717 0 -0.799853 0.600196 0 -0.799853 0.600196 0 -0.460224 0.887803 0 -0.460224 0.887803 0 -0.0294443 0.999566 0 -0.0294443 0.999566 0 0.407169 0.913353 0 0.407169 0.913353 0 0.763133 0.646242 0 0.763133 0.646242 0 0.967956 0.25112 0 0.967956 0.25112 0 -0.994869 0.101176 0.00796631 -0.973096 0.230264 0 -0.934776 0.355239 0 -0.810386 0.585897 0.00806028 -0.727597 0.685957 0 -0.63111 0.775693 0 -0.287147 0.957887 0 -0.287147 0.957887 0 0.23027 0.973127 0 0.23027 0.973127 0 0.685972 0.727628 0 0.685972 0.727628 0 0.957891 0.287133 0.0184327 0.986408 0.163275 0 0.911729 0.410792 0 -0.981058 0.193716 0 -0.981058 0.193716 0 -0.79985 0.600199 0 -0.79985 0.600199 0 -0.460221 0.887804 0 -0.460221 0.887804 0 -0.0294447 0.999566 0 -0.0294447 0.999566 0 0.407169 0.913353 0 0.407169 0.913353 0 0.763134 0.64624 0 0.763134 0.64624 0 0.967952 0.251134 0 0.967952 0.251134 0 -0.981057 0.193718 0 -0.981057 0.193718 0 -0.799853 0.600196 0 -0.799853 0.600196 0 -0.460227 0.887801 0 -0.460227 0.887801 0 -0.0294443 0.999566 0 -0.0294443 0.999566 0 0.407169 0.913353 0 0.407169 0.913353 0 0.763134 0.64624 0 0.763134 0.64624 0 0.967953 0.251132 0 0.967953 0.251132 0 -0.981058 0.193716 0 -0.981058 0.193716 0 -0.799847 0.600204 0 -0.799847 0.600204 0 -0.460224 0.887803 0 -0.460224 0.887803 0 -0.0294447 0.999566 0 -0.0294447 0.999566 0 0.407167 0.913354 0 0.407167 0.913354 0 0.763138 0.646236 0 0.763138 0.646236 0 0.967952 0.251134 0 0.967952 0.251134 0 -0.981057 0.19372 0 -0.981057 0.19372 0 -0.799849 0.600201 0 -0.799849 0.600201 0 -0.460225 0.887802 0 -0.460225 0.887802 0 -0.0294446 0.999566 0 -0.0294446 0.999566 0 0.407168 0.913353 0 0.407168 0.913353 0 0.763136 0.646238 0 0.763136 0.646238 0 0.967952 0.251134 0 0.967952 0.251134 0 -0.981057 0.193719 0 -0.981057 0.193719 0 -0.79985 0.6002 0 -0.79985 0.6002 0 -0.460225 0.887802 0 -0.460225 0.887802 0 -0.0294446 0.999566 0 -0.0294446 0.999566 0 0.407168 0.913353 0 0.407168 0.913353 0 0.763135 0.646239 0 0.763135 0.646239 0 0.967953 0.251132 0 0.967953 0.251132 0 -0.994868 0.101179 0.0190803 -0.934295 0.355989 0 -0.973128 0.230266 0 -0.810401 0.585876 0.00946987 -0.727587 0.68595 0 -0.631154 0.775658 0 -0.287149 0.957886 0 -0.287149 0.957886 0 0.230269 0.973127 0 0.230269 0.973127 0 0.68598 0.727621 0 0.68598 0.727621 0 0.911713 0.410829 0.00805939 0.957855 0.287138 0 0.986977 0.160861 0 -0.981057 0.193718 0 -0.981057 0.193718 0 -0.799851 0.600198 0 -0.799851 0.600198 0 -0.460224 0.887803 0 -0.460224 0.887803 0 -0.0294446 0.999566 0 -0.0294446 0.999566 0 0.407169 0.913353 0 0.407169 0.913353 0 0.763134 0.64624 0 0.763134 0.64624 0 0.967954 0.251129 0 0.967954 0.251129 0 -0.999863 0.0165309 0 -0.999863 0.0165309 0 -0.997157 -0.0753565 0 -0.997157 -0.0753565 0 -0.610699 -0.791862 0.0194624 -0.68585 -0.727482 0 -0.99846 -0.0554709 0.0015477 -0.994105 -0.108408 0.0122281 -0.95853 -0.284728 0.0128239 -0.957807 -0.287125 -3.22178e-05 -0.877721 -0.479173 5.84605e-05 -0.794546 -0.607205 0 -0.99716 -0.0753165 0 -0.99716 -0.0753165 0 -0.474283 -0.880372 4.69136e-07 -0.474284 -0.880372 0 -0.474286 -0.880371 0 -0.52528 0.850929 -2.00285e-06 -0.525282 0.850928 0 0.996651 0.081773 0.00635211 0.997638 -0.0684006 -0.00301664 0.991971 -0.126428 0.00344323 0.901235 -0.433317 -0.00235962 0.887327 -0.461135 0.00245448 0.676429 -0.736504 0 0.667488 -0.744621 0 0.999863 -0.0165288 0 0.999863 -0.0165288 0 0.564415 0.825491 0.0104743 0.631871 0.775003 -0.00699418 0.757826 0.652419 0.00949449 0.874132 0.485595 -0.0044663 0.920859 0.38987 0.00584327 0.991885 0.127005 0 0.995733 0.0922863 0 0.525282 -0.850928 -2.34406e-07 0.525282 -0.850928 0 0.525283 -0.850928 0 0.474284 0.880372 -6.0104e-09 0.474284 0.880372 0 0.474284 0.880372 0 0.996205 -0.0870362 -0.00114078 0.998817 -0.0486083 0 0.999959 -0.00906921 0.0153511 0.892311 -0.451161 -0.0124609 0.603736 -0.797087 0 0.684272 -0.729227 0 0.995675 -0.0929007 -0.00243818 0.997807 -0.0661504 0.00161485 0.964416 -0.264384 0 0.971468 -0.23717 0 0.841436 -0.540357 -0.221333 0.712517 -0.665832 0 -0.983587 -0.180432 -0.00201981 -0.988477 -0.151357 0.00169954 -0.999806 0.0196177 0 -0.998817 0.0486217 0 -0.928842 -0.370476 -0.00235597 -0.915628 -0.402019 0.00230657 -0.812691 -0.58269 -0.0105887 -0.685944 -0.727577 0 -0.607221 -0.794533 -0.0110231 -0.727571 0.685944 -2.59049e-06 -0.638074 0.769975 0 -0.994229 -0.107274 0.00174401 -0.996982 -0.0776207 -0.00207774 -0.995561 0.0940907 0 -0.992269 0.124102 0 -0.937284 0.348567 -0.0030197 -0.947658 0.319274 0.00274132 -0.835073 0.550133 -0.706039 0.704083 0.0759998 -0.706039 0.704083 0.0759998 -0.694759 0.699915 -0.165617 -0.757486 0.650028 -0.0606503 -0.699924 0.488719 -0.520827 -0.723233 0.502498 -0.473741 -0.694079 0.642449 -0.324829 -0.725825 0.663403 -0.181865 -0.707118 0.371425 -0.601687 -0.707118 0.371425 -0.601687 -0.694758 0.523336 -0.493387 -0.528401 0.574286 -0.62529 -0.753345 0.592678 -0.284962 -0.558652 0.807114 -0.190983 -0.742805 0.66794 -0.0457957 -0.706744 0.705458 0.0533109 -0.706744 0.705458 0.0533108 -0.706744 0.705458 0.0533109 -0.706744 0.707373 -0.0116936 -0.706744 0.707372 -0.0116937 -0.706745 0.707372 -0.0116946 -0.770129 0.611025 0.183168 -0.700679 0.45085 0.552977 -0.590046 0.55384 0.587459 -0.753345 0.574877 0.319354 -0.281187 0.951882 0.121883 -0.707119 0.335364 0.622506 -0.707118 0.335364 0.622507 -0.694759 0.493386 0.523336 -0.725418 0.440629 0.528787 -0.685036 0.647868 0.333156 -0.733469 0.651098 0.195181 -0.704455 0.701573 0.107418 -0.706039 0.707336 -0.0344249 -0.706039 0.707336 -0.0344231 -0.706039 -0.704086 -0.0759684 -0.706042 -0.704085 -0.0759586 -0.707115 -0.371426 0.60169 -0.707115 -0.371426 0.60169 -0.706736 -0.705468 -0.0532847 -0.706746 -0.705456 -0.0533082 -0.706736 -0.705466 -0.053313 -0.706746 -0.705456 -0.0533113 -0.694764 -0.493383 -0.523332 -0.703438 -0.700107 -0.122577 -0.790825 -0.586267 -0.175747 -0.641158 -0.670844 -0.372672 -0.793646 -0.384442 -0.47152 -0.707113 -0.335367 -0.622511 -0.707122 -0.335361 -0.622504 -0.699917 -0.457221 -0.548695 -0.67265 -0.5076 -0.538409 -0.719706 -0.617433 -0.317489 -0.703662 -0.650588 -0.28565 -0.704447 -0.701583 -0.107403 -0.704455 -0.701571 -0.107426 0.54627 -0.72948 0.41164 0.55274 -0.643373 0.52967 0.590586 -0.57305 0.568174 0.539987 -0.738898 0.403045 0.54377 -0.73237 0.409816 0.579548 -0.582198 0.570236 0.576706 -0.583383 0.571904 0.577472 -0.582895 0.57163 0.529117 -0.6861 0.499302 0.567895 -0.656297 0.496758 0.524181 -0.770087 0.363595 0.544124 -0.75024 0.375591 0.510375 -0.820282 0.258177 0.540785 -0.793818 0.278218 0.478724 -0.870241 0.116207 0.512778 -0.848015 0.133898 0.483219 -0.87118 -0.0868541 0.505507 -0.862821 0.00193793 0.491961 -0.869337 -0.0471935 0.490327 -0.87096 -0.0317332 0.48687 -0.87003 -0.0774952 0.4833 -0.873965 0.051057 0.455037 -0.890405 0.0110132 0.482931 -0.875539 0.0144754 0.482931 -0.873169 -0.0659866 0.482918 -0.873176 -0.0659854 0.483255 -0.874537 0.0406228 0.505453 -0.861269 -0.0522697 0.48584 -0.873906 0.0157266 0.467469 -0.883755 -0.0212207 0.478501 -0.878008 0.011793 0.512309 -0.842616 -0.165946 0.520815 -0.839659 -0.154029 0.513363 -0.80577 -0.295283 0.505992 -0.802844 -0.315299 0.53959 -0.755392 -0.371787 0.532834 -0.738902 -0.412446 0.555589 -0.657791 -0.508558 0.535401 -0.643338 -0.547231 0.577728 -0.547574 -0.605304 0.578431 -0.548152 -0.604108 0.578518 -0.547927 -0.604229 0.579208 -0.548481 -0.603064 0.576983 -0.554205 -0.599956 0.574609 -0.607272 -0.548675 0.544777 -0.712289 -0.442563 0.542126 -0.717479 -0.437405 0.545318 -0.712479 -0.44159 0.551688 0.686876 -0.473119 0.562805 0.620825 -0.545735 0.584659 0.583997 -0.563136 0.554655 0.691317 -0.463075 0.55235 0.69385 -0.462041 0.579086 0.582285 -0.570617 0.577999 0.582788 -0.571205 0.578318 0.581986 -0.5717 0.577206 0.582505 -0.572294 0.555248 0.633615 -0.538732 0.594977 0.672166 -0.440675 0.493116 0.757656 -0.427543 0.593437 0.78502 -0.177696 0.432589 0.843006 -0.3197 0.541904 0.839016 -0.0489109 0.466265 0.884635 -0.0042209 0.504968 0.859498 0.0791882 0.504735 0.863156 -0.0142689 0.504734 0.863157 -0.014269 0.504493 0.863408 -0.00362761 0.544099 0.838005 0.0412883 0.449608 0.875971 0.174723 0.548564 0.804991 0.225979 0.482834 0.783197 0.391758 0.562973 0.723264 0.399938 0.522108 0.638539 0.565395 0.545005 0.622984 0.561125 0.577359 0.547411 0.605804 0.578165 0.547724 0.604751 0.578149 0.547765 0.604729 0.578952 0.54807 0.603684 0.574217 0.56016 0.597073 0.575266 0.585885 0.570796 0.559616 0.65582 0.506685 0.551435 0.672696 0.493355 0.552188 0.671783 0.493757 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.42237 0.902848 -0.0804338 -0.424938 0.905222 0.00022517 -0.42522 0.905014 -0.0117011 -0.422908 0.876703 0.229219 -0.428219 0.887601 0.169682 -0.464425 0.777211 0.42456 -0.464755 0.770389 0.436467 -0.509013 0.635913 0.580104 -0.520136 0.557862 0.646721 -0.522618 0.551478 0.650187 -0.521075 0.552637 0.650441 -0.521658 0.551124 0.651256 -0.520078 0.552324 0.651503 -0.422483 0.90583 -0.0312921 -0.405 0.912177 0.0625166 -0.438946 0.892005 0.107949 -0.423126 0.857681 0.292144 -0.465248 0.820613 0.331872 -0.451223 0.74138 0.496744 -0.501722 0.683679 0.529961 -0.497 0.607864 0.619268 -0.422252 0.903901 0.068307 -0.422252 0.903901 0.0683071 -0.422252 0.906355 -0.014983 -0.422252 0.906355 -0.0149831 -0.474064 0.689244 -0.547911 -0.475608 0.68778 -0.548412 -0.474164 0.767741 -0.430979 -0.431549 0.836465 -0.337775 -0.419314 0.83175 -0.363825 -0.452527 0.870762 -0.192336 -0.398855 0.912427 -0.0916072 -0.438714 0.898601 0.00680998 -0.422342 0.90343 0.0737608 -0.520525 0.588591 -0.618558 -0.521211 0.589626 -0.616993 -0.521508 0.58888 -0.617454 -0.522185 0.589877 -0.615928 -0.484464 0.673174 -0.558687 -0.529396 0.580571 -0.618609 -0.456701 0.80342 -0.382022 -0.366151 0.910381 -0.192717 -0.45072 0.821186 -0.350007 -0.427253 0.902602 -0.052574 -0.425693 0.903309 0.0530925 -0.421618 0.901327 0.0992351 -0.419809 -0.907612 -0.00040488 -0.416589 -0.908469 -0.0337207 -0.441303 -0.869076 -0.223512 -0.443501 -0.83747 -0.319297 -0.471475 -0.774966 -0.420879 -0.492277 -0.671237 -0.55417 -0.506361 -0.636376 -0.581914 -0.54407 -0.490995 -0.680376 -0.522615 -0.551477 -0.650189 -0.521072 -0.552637 -0.650444 -0.521654 -0.551126 -0.651258 -0.520076 -0.552325 -0.651505 -0.422402 -0.906069 0.0248232 -0.402506 -0.913263 -0.0627694 -0.438663 -0.891349 -0.114329 -0.423131 -0.857671 -0.292164 -0.465244 -0.820611 -0.331881 -0.451224 -0.741376 -0.496748 -0.501718 -0.683683 -0.529959 -0.497 -0.607859 -0.619272 -0.422244 -0.903905 -0.0683093 -0.422261 -0.903897 -0.0683051 -0.384559 -0.877682 0.285987 -0.487754 -0.758372 0.432397 -0.466247 -0.68936 0.554434 -0.487103 -0.663881 0.567444 -0.422396 -0.903042 -0.0780852 -0.421499 -0.903819 -0.0738265 -0.426432 -0.902607 0.0587905 -0.408432 -0.90834 0.090008 -0.469079 -0.822678 0.321195 -0.520527 -0.588588 0.618559 -0.521211 -0.589621 0.616997 -0.521506 -0.588883 0.617453 -0.522181 -0.589877 0.615932 -0.484394 -0.673302 0.558593 -0.529372 -0.580629 0.618575 -0.456745 -0.80338 0.382052 -0.471101 -0.777998 0.415671 -0.435806 -0.88317 0.173449 -0.429061 -0.891241 0.146956 -0.424669 -0.903797 -0.0529804 -0.421139 -0.903072 -0.0842773 0.699903 -0.488725 0.520849 0.699907 -0.488727 0.520841 0.699909 -0.653295 0.288675 0.699907 -0.653295 0.288679 0.704437 -0.706699 0.0659142 0.683161 -0.730186 0.0109247 0.706021 -0.704105 -0.0759608 0.707098 -0.371436 0.601705 0.707098 -0.371436 0.601705 0.700657 -0.482632 0.525495 0.700662 -0.482628 0.525494 0.700662 -0.64303 0.30917 0.700666 -0.643025 0.30917 0.703424 -0.706122 0.0811534 0.703421 -0.706126 0.0811513 0.706729 -0.705475 -0.0532852 0.706719 -0.705484 -0.0533103 0.706721 -0.707396 0.0116955 0.706728 -0.707389 0.0116946 0.706728 -0.705474 -0.0533136 0.706719 -0.705483 -0.0533133 0.706721 -0.707396 0.0116894 0.706728 -0.707389 0.0117059 0.70342 -0.700123 -0.12259 0.703433 -0.700112 -0.122578 0.700674 -0.623707 -0.346477 0.70066 -0.623715 -0.34649 0.70066 -0.450862 -0.55299 0.700666 -0.450861 -0.552984 0.707105 -0.335371 -0.622519 0.707096 -0.335373 -0.622528 0.706016 -0.70736 0.0344047 0.664375 -0.738792 -0.113099 0.699899 -0.712294 -0.0527032 0.699902 -0.635186 -0.326614 0.699904 -0.635182 -0.326616 0.699905 -0.45722 -0.54871 0.699899 -0.457232 -0.548708 0.69474 0.523348 -0.493399 0.694741 0.523348 -0.493398 0.694741 0.699932 -0.165621 0.694741 0.699932 -0.165621 0.707101 0.371434 -0.601702 0.707101 0.371434 -0.601702 0.694741 0.699932 -0.165621 0.694741 0.523349 -0.493398 0.694741 0.523348 -0.493398 0.704633 0.659941 -0.26071 0.372177 0.922091 -0.105981 0.706727 0.70739 -0.0116939 0.706726 0.70739 -0.011694 0.706727 0.70739 -0.0116948 0.706727 0.70739 -0.0116948 0.707101 0.335372 0.622522 0.707101 0.335372 0.622522 0.706021 0.707353 -0.034424 0.706021 0.707354 -0.0344257 0 0.998818 -0.0486083 0.00166674 0.996148 -0.087667 0 0.999953 -0.00970941 0 0.973128 -0.230266 0.023456 0.997581 -0.0654329 -0.00840511 0.913185 -0.407458 0.00846954 0.727594 -0.685956 0 0.660757 -0.7506 0 -0.995914 -0.0903072 0.00545194 -0.999873 0.0149596 -0.00363052 -0.985024 0.172381 0.00471217 -0.914671 0.404171 -0.00235558 -0.872286 0.48899 0.00289117 -0.684258 0.729234 0 -0.660808 0.750555 0 -0.556909 -0.830574 0.0136398 -0.7545 -0.656158 -0.0091659 -0.640126 -0.768215 0.00474981 -0.889308 -0.457284 -0.00237689 -0.929255 -0.369431 0.00294248 -0.99727 -0.0737887 0 -0.999132 -0.041652 0 0.474284 0.880372 -3.30918e-08 0.474284 0.880372 0 0.474284 0.880372 0 0.525282 -0.850928 -2.75765e-08 0.525282 -0.850928 0 0.525282 -0.850928 0 0.999666 -0.0258529 -0.000335396 0.999863 -0.01653 0.00145691 0.983849 0.178996 0.00251375 0.985013 0.172462 -0.00161192 0.906814 0.421527 0.00860157 0.860111 0.510034 -0.015459 0.685898 0.727533 0 0.624147 0.781307 0 0.999863 -0.0165288 0 0.999863 -0.0165288 0 0.621236 -0.783624 -0.0182421 0.727499 -0.685866 0 0.997157 0.0753534 0.00474478 0.999538 -0.0300113 -0.00403634 0.993452 -0.114182 0.00424091 0.946054 -0.32398 -0.000943662 0.930055 -0.367419 0.000627805 0.848058 -0.529904 -0.0106921 0.760074 -0.649748 0 -0.525285 0.850926 9.48633e-07 -0.525282 0.850928 0 -0.52528 0.85093 0 -0.474286 -0.880371 -6.50806e-07 -0.474284 -0.880372 0 -0.474283 -0.880373 0 -0.99716 -0.0753165 0 -0.99716 -0.0753165 7.58295e-09 -0.985014 -0.172473 0.00226101 -0.982115 -0.188269 -0.00273955 -0.87417 -0.485612 0.00181923 -0.86111 -0.508416 -0.0018832 -0.631905 -0.775043 0 -0.624151 -0.781304 0 -0.999863 0.0165309 0 -0.999863 0.0165309 0 -0.997157 -0.0753565 0 -0.997157 -0.0753565 -0.705607 -0.7072 0.0445782 -0.705611 -0.707196 0.0445782 -0.70561 -0.686964 0.173766 -0.705612 -0.686963 0.173766 -0.705611 -0.643337 0.297036 -0.70561 -0.643338 0.297037 -0.70561 -0.577804 0.410193 -0.705606 -0.577807 0.410195 -0.705606 -0.492596 0.509382 -0.705606 -0.492595 0.509381 -0.705606 -0.390609 0.591223 -0.705605 -0.39061 0.591224 -0.705605 -0.275322 0.652932 -0.705603 -0.275322 0.652933 -0.705604 -0.150658 0.692405 -0.705603 -0.150659 0.692407 -0.705603 -0.0208641 0.7083 -0.705605 -0.0208639 0.708298 -0.705605 0.109641 0.700072 -0.705606 0.10964 0.70007 -0.705606 0.236411 0.668004 -0.705606 0.236411 0.668005 -0.705605 0.355132 0.61319 -0.705607 0.355131 0.613189 -0.705608 0.461757 0.537493 -0.705604 0.461759 0.537496 -0.705603 0.552662 0.443496 -0.705605 0.552661 0.443495 -0.705605 0.624743 0.334392 -0.705606 0.624742 0.334392 -0.705606 0.675549 0.213902 -0.705603 0.675551 0.213903 -0.705603 0.703353 0.0861288 -0.705607 0.70335 0.0861282 -0.705391 -0.707145 0.0486764 -0.705392 -0.707144 0.0486763 -0.705392 -0.68406 0.185698 -0.705391 -0.684061 0.185698 -0.705391 -0.634689 0.315584 -0.705392 -0.634689 0.315583 -0.705392 -0.560926 0.433341 -0.705392 -0.560926 0.433341 -0.705392 -0.465607 0.534446 -0.705389 -0.465609 0.534448 -0.705389 -0.352397 0.615014 -0.705388 -0.352397 0.615015 -0.705388 -0.225642 0.671947 -0.70539 -0.225642 0.671946 -0.70539 -0.0902162 0.703055 -0.705388 -0.0902163 0.703056 -0.705389 0.0486765 0.707147 -0.705389 0.0486765 0.707147 -0.705389 0.185699 0.684063 -0.705394 0.185697 0.684059 -0.705394 0.315583 0.634687 -0.705393 0.315583 0.634687 -0.705393 0.43334 0.560925 -0.705392 0.433341 0.560926 -0.705392 0.534446 0.465607 -0.705391 0.534447 0.465608 -0.70539 0.615013 0.352396 -0.705396 0.615008 0.352394 -0.705397 0.671939 0.22564 -0.705399 0.671937 0.225639 -0.705399 0.703046 0.090215 -0.705393 0.703052 0.0902154 -0.70542 -0.707116 0.0486745 -0.705421 -0.707115 0.0486743 -0.705422 -0.684032 0.18569 -0.705419 -0.684034 0.185691 -0.705419 -0.634665 0.315572 -0.705418 -0.634665 0.315572 -0.705418 -0.560906 0.433325 -0.705417 -0.560906 0.433326 -0.705419 -0.46559 0.534426 -0.705418 -0.46559 0.534426 -0.705417 -0.352383 0.61499 -0.70542 -0.352382 0.614988 -0.705419 -0.225633 0.671918 -0.705415 -0.225634 0.671922 -0.705416 -0.0902128 0.703029 -0.705421 -0.0902124 0.703024 -0.705419 0.0486744 0.707117 -0.705418 0.0486746 0.707119 -0.705417 0.185691 0.684037 -0.705414 0.185692 0.68404 -0.705414 0.315574 0.634668 -0.705419 0.315571 0.634664 -0.70542 0.433324 0.560904 -0.705418 0.433325 0.560905 -0.705418 0.534426 0.46559 -0.705419 0.534426 0.465589 -0.70542 0.614988 0.352381 -0.705418 0.61499 0.352382 -0.705418 0.671919 0.225633 -0.705417 0.67192 0.225633 -0.705417 0.703028 0.0902127 -0.70542 0.703025 0.0902125 0.705393 0.703051 0.0902157 0.70539 0.703054 0.0902162 0.705391 0.671945 0.225642 0.705392 0.671944 0.225641 0.705392 0.615012 0.352395 0.705393 0.615011 0.352394 0.705393 0.534445 0.465607 0.705392 0.534446 0.465607 0.705392 0.433341 0.560926 0.705393 0.43334 0.560925 0.705393 0.315583 0.634687 0.705388 0.315585 0.634692 0.705387 0.185699 0.684065 0.70539 0.185698 0.684062 0.705391 0.0486763 0.707145 0.705393 0.0486763 0.707143 0.705394 -0.0902155 0.70305 0.70539 -0.0902163 0.703055 0.705389 -0.225642 0.671947 0.705393 -0.225641 0.671943 0.705393 -0.352395 0.615011 0.705391 -0.352396 0.615013 0.705392 -0.465607 0.534446 0.705392 -0.465607 0.534446 0.705391 -0.560927 0.433342 0.705391 -0.560926 0.433342 0.705391 -0.634689 0.315584 0.705392 -0.634688 0.315583 0.705393 -0.68406 0.185698 0.705395 -0.684057 0.185697 0.705395 -0.707141 0.0486762 0.705393 -0.707143 0.0486763 -0.705779 -0.707248 0.0409375 -0.705784 -0.707243 0.0409374 -0.705784 -0.68939 0.163127 -0.705778 -0.689396 0.163129 -0.705778 -0.650595 0.280362 -0.705774 -0.650599 0.280364 -0.705775 -0.59203 0.389079 -0.705786 -0.592021 0.389074 -0.705785 -0.515465 0.485966 -0.705782 -0.515467 0.485968 -0.705782 -0.423249 0.568096 -0.705775 -0.423253 0.568101 -0.705776 -0.318172 0.632966 -0.70578 -0.31817 0.632963 -0.70578 -0.203424 0.678597 -0.705779 -0.203424 0.678598 -0.705778 -0.0824967 0.703613 -0.705779 -0.0824967 0.703613 -0.70578 0.0409375 0.707248 -0.705778 0.0409375 0.70725 -0.705778 0.163128 0.689396 -0.705777 0.163128 0.689396 -0.705778 0.280362 0.650595 -0.705774 0.280364 0.650599 -0.705775 0.389079 0.59203 -0.70578 0.389077 0.592025 -0.70578 0.485969 0.515468 -0.705782 0.485968 0.515467 -0.705782 0.568096 0.423249 -0.705777 0.5681 0.423252 -0.705776 0.632966 0.318172 -0.705777 0.632965 0.318172 -0.705777 0.678599 0.203425 -0.705778 0.678599 0.203425 -0.705778 0.703614 0.0824969 -0.705778 0.703614 0.0824969 -0.705779 -0.707248 0.0409376 -0.705778 -0.70725 0.0409377 -0.705778 -0.689396 0.163128 -0.705778 -0.689395 0.163128 -0.705778 -0.650595 0.280362 -0.705779 -0.650594 0.280362 -0.705779 -0.592026 0.389077 -0.70578 -0.592025 0.389077 -0.70578 -0.515468 0.485969 -0.705778 -0.515471 0.485971 -0.705776 -0.423252 0.5681 -0.705779 -0.42325 0.568098 -0.705779 -0.318171 0.632964 -0.705777 -0.318172 0.632965 -0.705778 -0.203425 0.678598 -0.705777 -0.203425 0.678599 -0.705777 -0.0824969 0.703614 -0.70578 -0.0824967 0.703611 -0.705779 0.0409377 0.707249 -0.705778 0.0409378 0.70725 -0.705778 0.163128 0.689396 -0.705776 0.163129 0.689398 -0.705775 0.280364 0.650598 -0.705783 0.28036 0.650591 -0.705784 0.389074 0.592022 -0.70578 0.389077 0.592025 -0.70578 0.48597 0.515468 -0.705782 0.485969 0.515467 -0.705783 0.568095 0.423248 -0.705777 0.568099 0.423251 -0.705778 0.632965 0.318172 -0.705773 0.632969 0.318174 -0.705773 0.678604 0.203426 -0.70579 0.678587 0.203421 -0.705791 0.703601 0.0824959 -0.705779 0.703612 0.0824968 -0.705614 -0.707193 0.0445779 -0.705616 -0.707191 0.0445778 -0.705616 -0.686959 0.173765 -0.705614 -0.68696 0.173765 -0.705615 -0.643333 0.297035 -0.705614 -0.643334 0.297035 -0.705614 -0.5778 0.41019 -0.705615 -0.5778 0.41019 -0.705615 -0.492589 0.509376 -0.705613 -0.49259 0.509377 -0.705613 -0.390605 0.591217 -0.705612 -0.390606 0.591218 -0.705612 -0.275319 0.652925 -0.705616 -0.275318 0.652921 -0.705616 -0.150656 0.692393 -0.705615 -0.150656 0.692395 -0.705614 -0.0208639 0.708289 -0.705616 -0.0208639 0.708287 -0.705616 0.109639 0.700061 -0.705609 0.10964 0.700067 -0.70561 0.23641 0.668 -0.70562 0.236407 0.667992 -0.705621 0.355124 0.613177 -0.705618 0.355126 0.61318 -0.705617 0.461751 0.537486 -0.705613 0.461754 0.537488 -0.705612 0.552656 0.443491 -0.705614 0.552654 0.443489 -0.705615 0.624734 0.334388 -0.70562 0.62473 0.334386 -0.70562 0.675535 0.213898 -0.705617 0.675539 0.213899 -0.705617 0.70334 0.086127 -0.705615 0.703341 0.0861271 -0.705393 -0.707143 0.0486763 -0.705385 -0.707151 0.0486765 -0.705385 -0.684067 0.1857 -0.705393 -0.68406 0.185698 -0.705392 -0.634688 0.315583 -0.705392 -0.634689 0.315583 -0.705391 -0.560926 0.433342 -0.705391 -0.560926 0.433342 -0.705392 -0.465607 0.534446 -0.705393 -0.465606 0.534445 -0.705393 -0.352395 0.615011 -0.70539 -0.352396 0.615013 -0.705391 -0.225642 0.671945 -0.705387 -0.225643 0.671948 -0.705389 -0.0902163 0.703056 -0.705393 -0.0902156 0.703052 -0.705394 0.0486763 0.707142 -0.705392 0.0486763 0.707144 -0.705392 0.185698 0.68406 -0.705387 0.185699 0.684065 -0.705388 0.315585 0.634692 -0.705393 0.315583 0.634688 -0.705393 0.43334 0.560925 -0.705392 0.433341 0.560926 -0.705392 0.534446 0.465607 -0.705392 0.534446 0.465607 -0.705392 0.615012 0.352395 -0.705393 0.615011 0.352395 -0.705393 0.671943 0.225641 -0.705391 0.671945 0.225642 -0.70539 0.703054 0.0902161 -0.70539 0.703055 0.0902162 -0.42183 -0.575665 0.700478 -0.42223 -0.351451 0.835586 -0.415756 -0.351475 0.838816 -0.42544 -0.406277 0.808666 -0.422539 -0.405791 0.810428 -0.421926 -0.472944 0.773501 -0.40979 -0.474364 0.779135 -0.423779 -0.523485 0.739171 -0.42261 -0.5224 0.740607 -0.421827 -0.575666 0.700479 -0.45188 0.130206 0.882525 -0.494355 0.347025 0.796986 -0.401262 0.163897 0.901181 -0.551323 0.560778 0.617714 -0.460507 0.438917 0.771548 -0.610544 0.69281 0.383731 -0.529883 0.639109 0.557462 -0.435652 -0.0154955 0.899982 -0.425243 -0.159365 0.890939 -0.419427 -0.193861 0.886848 -0.41734 -0.728263 0.543563 -0.418484 -0.722104 0.55085 -0.444969 -0.848772 0.285635 -0.451346 -0.852547 0.263535 -0.483914 -0.871297 0.0816616 -0.512343 -0.856725 -0.0593901 -0.502317 -0.864223 -0.0282214 -0.552299 -0.789469 -0.267779 -0.563966 -0.770741 -0.296481 -0.609442 -0.641578 -0.465788 -0.587416 0.686604 0.428388 -0.587079 0.686775 0.428577 -0.587416 -0.690667 -0.421809 -0.587067 -0.69092 -0.421879 -0.509152 -0.788213 0.345666 -0.52967 -0.827825 0.184811 -0.549759 -0.818055 0.168974 -0.571961 -0.820053 0.0193412 -0.443087 -0.769836 0.459376 -0.492402 -0.761818 0.420919 -0.448901 -0.647484 0.615835 -0.445294 -0.646784 0.61918 -0.441953 -0.553658 0.705791 -0.467804 0.179876 0.865335 -0.438098 -0.54219 0.717008 -0.433943 -0.468325 0.769652 -0.450793 -0.429413 0.782554 -0.432122 -0.389709 0.813263 -0.411976 -0.297611 0.861222 -0.421841 -0.314979 0.850199 -0.421616 -0.190859 0.886461 -0.42646 -0.199761 0.882172 -0.42175 -0.0501753 0.905323 -0.422552 -0.0517359 0.904861 -0.439975 0.0512158 0.896548 -0.43814 0.0727835 0.895955 -0.448958 0.123748 0.884942 -0.450502 0.231451 0.862252 -0.481542 0.328983 0.812334 -0.493578 0.35062 0.795893 -0.492649 0.359713 0.792404 -0.490043 0.45962 0.74068 -0.48417 0.487371 0.726669 -0.550305 0.539313 0.637421 -0.530413 0.652087 0.541706 -0.554094 0.659361 0.508156 -0.554094 0.316944 0.769757 -0.530413 0.293869 0.795175 -0.550305 0.148347 0.82168 -0.484171 0.058741 0.873 -0.505523 -0.0717153 0.859828 -0.497117 -0.0861672 0.863394 -0.440717 -0.205729 0.873753 -0.442834 -0.21106 0.871408 -0.456042 -0.335555 0.824274 -0.45239 -0.317978 0.833206 -0.438139 -0.384948 0.812311 -0.439975 -0.40393 0.802037 -0.422553 -0.497236 0.757763 -0.421749 -0.496113 0.758946 -0.42646 -0.614087 0.6641 -0.421615 -0.608521 0.672267 -0.42184 -0.697875 0.578811 -0.411979 -0.688349 0.597033 -0.427726 -0.731489 0.531013 -0.41257 -0.800976 0.433848 -0.415593 -0.801268 0.43041 -0.466924 -0.857476 0.216142 -0.384957 -0.881004 0.275027 -0.46076 -0.873029 0.159754 -0.492678 -0.870016 -0.0184362 -0.493912 -0.869369 -0.0157482 -0.529671 -0.809324 -0.253859 -0.54976 -0.792942 -0.26269 -0.571964 -0.719851 -0.393284 -0.587417 -0.809038 -0.0199654 -0.587067 -0.809294 -0.0198993 -0.587417 0.380423 0.714296 -0.587079 0.380476 0.714546 -0.41734 -0.35889 0.83488 -0.418481 -0.349948 0.838099 -0.444963 -0.592229 0.671769 -0.45136 -0.606594 0.654461 -0.483917 -0.71374 0.50636 -0.512343 -0.771639 0.376932 -0.502327 -0.762557 0.407646 -0.552303 -0.81759 0.162813 -0.563943 -0.815728 0.128673 -0.609434 -0.788525 -0.082573 -0.451877 -0.328525 0.829385 -0.494356 -0.0979603 0.863722 -0.401251 -0.308679 0.862389 -0.551321 0.176787 0.815348 -0.460522 -0.00563315 0.88763 -0.610549 0.408134 0.678717 -0.529885 0.274758 0.802328 -0.435653 -0.463399 0.771666 -0.42525 -0.583437 0.691927 -0.419425 -0.611316 0.6711 -0.421998 -0.155101 0.893231 -0.423622 -0.155213 0.892442 -0.422393 -0.0945498 0.901468 -0.422608 -0.0947835 0.901343 -0.42183 -0.0266957 0.906282 -0.422003 0.102499 0.900782 -0.423618 0.102171 0.900061 -0.422399 0.0415643 0.905456 -0.422608 0.0413133 0.905371 -0.421828 -0.0266959 0.906283 -0.422611 -0.86675 0.264848 -0.424537 -0.866966 0.261034 -0.394026 -0.858885 0.3272 -0.421851 -0.848569 0.319333 -0.422556 -0.817422 0.391494 -0.429552 -0.815816 0.387208 -0.403887 -0.796563 0.449847 -0.422166 -0.790907 0.442993 -0.422403 -0.749745 0.50937 -0.432832 -0.747168 0.504378 -0.411781 -0.717561 0.561732 -0.422401 -0.715382 0.556602 -0.612011 0.78963 -0.0438994 -0.562652 0.807787 0.175794 -0.583171 0.80463 0.111726 -0.548325 0.798665 0.24794 -0.522344 0.766405 0.373872 -0.507016 0.733952 0.451939 -0.491556 0.710317 0.503807 -0.45829 0.593993 0.661168 -0.456402 0.564618 0.68768 -0.442014 0.482674 0.756075 -0.417833 0.309333 0.854242 -0.417438 0.307734 0.855012 -0.417336 -0.902476 0.10662 -0.418481 -0.900785 0.116019 -0.444969 -0.877878 -0.177012 -0.451337 -0.870107 -0.198011 -0.483917 -0.795384 -0.36495 -0.512346 -0.712231 -0.479822 -0.502353 -0.734241 -0.456653 -0.552297 -0.549819 -0.626631 -0.563954 -0.519279 -0.64211 -0.609442 -0.322728 -0.724174 -0.587415 0.808812 0.0276932 -0.587081 0.809051 0.0277704 -0.587417 -0.38723 -0.71063 -0.587066 -0.387415 -0.710818 -0.529669 -0.624513 0.573963 -0.549759 -0.623971 0.555361 -0.571961 -0.700517 0.426774 -0.357332 -0.18906 0.914642 -0.455988 -0.279461 0.844971 -0.492399 -0.449293 0.745439 -0.458599 -0.441013 0.771488 -0.511641 -0.520973 0.683236 -0.450502 0.63157 0.631005 -0.467805 0.588444 0.659464 -0.466927 -0.241557 0.850664 -0.438099 -0.111037 0.892043 -0.43121 0.0162742 0.902105 -0.442039 0.00547424 0.896979 -0.411976 0.172876 0.894645 -0.421841 0.152323 0.893783 -0.421617 0.27794 0.863127 -0.426459 0.268089 0.863864 -0.421749 0.409212 0.809119 -0.422553 0.407624 0.809501 -0.439976 0.492623 0.750829 -0.43814 0.511009 0.739528 -0.448957 0.549632 0.704515 -0.538125 0.830088 0.146202 -0.481541 0.691075 0.539012 -0.497114 0.704637 0.506324 -0.505523 0.708776 0.492019 -0.484172 0.785409 0.385629 -0.521412 0.787073 0.329615 -0.545556 0.820431 0.171059 -0.554089 -0.110406 0.825104 -0.530414 -0.143089 0.835576 -0.550307 -0.282368 0.785768 -0.484174 -0.385628 0.785409 -0.490043 -0.41162 0.768393 -0.49265 -0.50638 0.707726 -0.49358 -0.51395 0.701594 -0.440713 -0.615049 0.653825 -0.467802 -0.659469 0.58844 -0.448967 -0.704491 0.549655 -0.438141 -0.739538 0.510995 -0.439975 -0.750829 0.492624 -0.422552 -0.809501 0.407625 -0.421746 -0.809118 0.409216 -0.426457 -0.863862 0.268099 -0.421619 -0.863126 0.277941 -0.421843 -0.893784 0.152313 -0.411979 -0.894646 0.172864 -0.445437 -0.895099 -0.0195794 -0.403709 -0.91481 0.01194 -0.441956 -0.888063 -0.126566 -0.445298 -0.859613 -0.250547 -0.448898 -0.857072 -0.252821 -0.492399 -0.745439 -0.449293 -0.44309 -0.782747 -0.43701 -0.509148 -0.693471 -0.509771 -0.529669 -0.573963 -0.624514 -0.549762 -0.555358 -0.623971 -0.571963 -0.426772 -0.700517 -0.587416 -0.71063 0.38723 -0.587066 -0.710818 0.387415 -0.587416 -0.0276926 0.808811 -0.587081 -0.0277703 0.809052 -0.417342 0.106626 0.902473 -0.418484 0.115999 0.900786 -0.444969 -0.177011 0.877878 -0.451338 -0.198011 0.870107 -0.48482 -0.370998 0.79203 -0.514408 -0.484683 0.707437 -0.502329 -0.456574 0.734306 -0.552302 -0.626645 0.549799 -0.563962 -0.642127 0.519249 -0.609441 -0.724173 0.322732 -0.451881 -0.699197 0.55401 -0.49436 -0.516688 0.699029 -0.4012 -0.698599 0.592452 -0.551321 -0.254569 0.794506 -0.460549 -0.448639 0.765909 -0.610546 0.0140916 0.791855 -0.529902 -0.163186 0.832211 -0.435652 -0.787166 0.43655 -0.425261 -0.851194 0.307605 -0.419425 -0.864956 0.275561 -0.422253 0.300497 0.855222 -0.415965 0.302619 0.857552 -0.425268 0.356881 0.831735 -0.422551 0.358507 0.83242 -0.421969 0.425069 0.800786 -0.410199 0.429118 0.804732 -0.423425 0.477701 0.769748 -0.422617 0.479354 0.769165 -0.421831 0.533435 0.733148 -0.421828 0.533435 0.733149 -0.529892 0.802319 -0.274769 -0.610555 0.678705 -0.408145 -0.541548 0.821398 -0.178973 -0.505726 0.862363 0.0239059 -0.511787 0.85911 0.00210477 -0.426692 0.84928 0.310896 -0.472736 0.860342 0.190612 -0.390398 0.705881 0.591034 -0.411991 0.737715 0.534827 -0.417335 -0.834854 -0.358957 -0.418486 -0.8381 -0.349939 -0.444969 -0.671745 -0.592251 -0.451333 -0.654527 -0.606542 -0.484815 -0.500421 -0.71731 -0.514405 -0.370316 -0.773469 -0.502324 -0.407645 -0.762559 -0.552299 -0.162826 -0.81759 -0.563958 -0.128631 -0.815724 -0.609437 0.0825784 -0.788522 -0.587416 0.714297 -0.380423 -0.58708 0.714545 -0.380476 -0.587417 0.019964 -0.809038 -0.587068 0.0198982 -0.809293 -0.512128 -0.112527 0.851506 -0.529671 -0.253861 0.809323 -0.549761 -0.262692 0.792941 -0.571964 -0.393284 0.719851 -0.461628 0.00202827 0.887071 -0.492401 -0.0163808 0.870214 -0.457351 0.17466 0.871966 -0.429782 0.210402 0.878076 -0.449928 0.300459 0.841005 -0.438098 0.349854 0.828053 -0.431209 0.465146 0.773109 -0.442039 0.45323 0.77407 -0.411975 0.597039 0.688346 -0.421839 0.578811 0.697875 -0.421615 0.672268 0.60852 -0.42646 0.664102 0.614086 -0.42358 0.740024 0.522442 -0.413514 0.761894 0.498521 -0.429786 0.775737 0.462079 -0.46588 0.838313 0.283174 -0.439974 0.802039 0.403926 -0.438139 0.812309 0.384952 -0.44896 0.828257 0.335299 -0.538126 0.791978 -0.288428 -0.454884 0.854695 0.250155 -0.475417 0.868725 0.138907 -0.483341 0.866669 0.123559 -0.485118 0.87058 0.0821616 -0.49778 0.867083 -0.0195566 -0.487436 0.871283 -0.0572013 -0.529035 0.837561 -0.136433 -0.542102 0.794201 -0.274536 -0.554087 -0.508172 0.659355 -0.531244 -0.540568 0.652354 -0.550308 -0.637436 0.539292 -0.48468 -0.724977 0.489381 -0.490879 -0.740495 0.459025 -0.492528 -0.791335 0.362222 -0.493628 -0.795882 0.350576 -0.440768 -0.858737 0.261332 -0.468257 -0.865139 0.179638 -0.449631 -0.884263 0.126142 -0.438026 -0.895901 0.074124 -0.439979 -0.896545 0.0512448 -0.422785 -0.904821 -0.0505186 -0.422686 -0.904878 -0.0503216 -0.425832 -0.882733 -0.198618 -0.421619 -0.886456 -0.190877 -0.421872 -0.850596 -0.313863 -0.412775 -0.860891 -0.297461 -0.444048 -0.767055 -0.463085 -0.405209 -0.797752 -0.446539 -0.442028 -0.705761 -0.553637 -0.444212 -0.621062 -0.645722 -0.449876 -0.615766 -0.646872 -0.491038 -0.423003 -0.761545 -0.444563 -0.45961 -0.768845 -0.509437 -0.345769 -0.787983 -0.528413 -0.187039 -0.828128 -0.550515 -0.169373 -0.817463 -0.571485 -0.0205085 -0.820356 -0.587416 -0.421809 0.690666 -0.587066 -0.421879 0.69092 -0.587417 -0.428386 0.686605 -0.58708 -0.428575 0.686776 -0.417341 0.543574 0.728254 -0.418483 0.550844 0.72211 -0.444967 0.285642 0.848772 -0.451345 0.263535 0.852547 -0.484818 0.0747276 0.871417 -0.514409 -0.066038 0.854998 -0.502331 -0.028264 0.864213 -0.552301 -0.267785 0.789465 -0.56395 -0.296442 0.770768 -0.609439 -0.465785 0.641583 -0.451872 -0.882534 0.130174 -0.494354 -0.796986 0.347027 -0.401264 -0.901179 0.163901 -0.551321 -0.617719 0.560775 -0.460548 -0.771493 0.438969 -0.610548 -0.383724 0.692811 -0.529864 -0.557498 0.639093 -0.435639 -0.899987 -0.0155473 -0.425225 -0.890933 -0.159442 -0.419426 -0.886853 -0.193838 -0.42244 0.679584 0.599759 -0.412724 0.684721 0.600679 -0.431997 0.71487 0.549855 -0.422439 0.720091 0.550468 -0.422227 0.761713 0.491445 -0.405225 0.769943 0.49293 -0.428347 0.790578 0.437613 -0.422572 0.794492 0.436137 -0.421936 0.826762 0.372069 -0.395842 0.838946 0.373467 -0.422874 0.849542 0.315367 -0.422619 0.850926 0.311959 -0.422435 -0.679586 -0.59976 -0.412721 -0.684723 -0.60068 -0.431993 -0.714871 -0.549856 -0.422432 -0.720093 -0.55047 -0.422221 -0.761715 -0.491446 -0.40522 -0.769945 -0.492931 -0.428341 -0.79058 -0.437616 -0.422568 -0.794493 -0.43614 -0.421931 -0.826764 -0.372069 -0.395844 -0.838945 -0.373468 -0.422878 -0.849542 -0.315361 -0.422619 -0.850948 -0.311899 -0.529897 0.557435 -0.639121 -0.610553 0.383704 -0.692817 -0.460493 0.771548 -0.43893 -0.551356 0.617631 -0.560838 -0.501556 0.767669 -0.398906 -0.441572 0.884543 -0.150326 -0.482406 0.832686 -0.271878 -0.442471 0.891853 -0.0938991 -0.421607 0.892679 0.159288 -0.418375 0.891152 0.175532 -0.417334 -0.54354 -0.728283 -0.418482 -0.550851 -0.722105 -0.444967 -0.285648 -0.84877 -0.451346 -0.263536 -0.852546 -0.484821 -0.0747045 -0.871417 -0.514407 0.0660376 -0.855 -0.50233 0.0282676 -0.864214 -0.5523 0.267787 -0.789465 -0.563959 0.29647 -0.77075 -0.609438 0.465776 -0.64159 -0.587416 0.428388 -0.686605 -0.58708 0.428576 -0.686775 -0.587416 0.421809 -0.690667 -0.587069 0.421879 -0.690919 -0.493911 0.42105 0.760769 -0.529671 0.184811 0.827825 -0.54976 0.168972 0.818054 -0.571963 0.0193354 0.820052 -0.432875 0.899905 0.0528212 -0.405881 0.913883 0.00882308 -0.424437 0.899794 0.101112 -0.42646 0.882172 0.199762 -0.421615 0.886462 0.190858 -0.421839 0.850202 0.314973 -0.411977 0.861221 0.297611 -0.44204 0.779543 0.44375 -0.431209 0.789384 0.436958 -0.438097 0.717012 0.542185 -0.451811 0.674369 0.584032 -0.42884 0.62137 0.65574 -0.459352 0.580034 0.672723 -0.492676 0.419044 0.762675 -0.438544 0.895766 -0.0726795 -0.455253 0.881993 -0.121787 -0.473398 0.866245 -0.159731 -0.4404 0.859678 -0.258847 -0.478304 0.816848 -0.322467 -0.484102 0.795376 -0.364723 -0.498583 0.758331 -0.41994 -0.484293 0.726643 -0.487289 -0.511229 0.691681 -0.510121 -0.563068 0.541128 -0.624607 -0.521208 0.57452 -0.631086 -0.55408 -0.769778 0.316919 -0.531247 -0.794322 0.294667 -0.55031 -0.821679 0.148334 -0.484674 -0.872542 0.0613313 -0.505522 -0.859828 -0.0717205 -0.498276 -0.862948 -0.0839204 -0.473809 -0.8699 -0.137038 -0.46342 -0.859182 -0.216907 -0.448263 -0.858844 -0.247884 -0.454672 -0.831834 -0.318316 -0.449645 -0.828884 -0.332821 -0.438019 -0.812925 -0.383786 -0.439973 -0.802033 -0.403938 -0.422787 -0.758338 -0.49616 -0.422687 -0.758487 -0.496018 -0.425833 -0.665162 -0.613372 -0.421613 -0.672268 -0.608522 -0.421868 -0.579705 -0.697115 -0.412766 -0.596829 -0.688055 -0.427712 -0.53099 -0.731514 -0.411755 -0.43602 -0.800215 -0.416674 -0.430362 -0.800732 -0.465488 -0.218198 -0.857736 -0.386823 -0.275337 -0.880089 -0.461278 -0.159911 -0.872726 -0.491619 0.0190398 -0.870602 -0.494406 0.0130321 -0.869133 -0.528416 0.252085 -0.810697 -0.550512 0.262048 -0.792633 -0.571484 0.392417 -0.720705 -0.587416 -0.0199639 0.809039 -0.587068 -0.0198982 0.809293 -0.587416 -0.714297 0.380423 -0.58708 -0.714545 0.380476 -0.41734 0.834879 0.358892 -0.418483 0.838103 0.349935 -0.444967 0.671758 0.592237 -0.451347 0.654496 0.606565 -0.48482 0.500414 0.717311 -0.514408 0.370309 0.77347 -0.50233 0.40763 0.762563 -0.552301 0.162824 0.817589 -0.563957 0.128636 0.815724 -0.609438 -0.0825813 0.788521 -0.451874 -0.829385 -0.328528 -0.494357 -0.863723 -0.0979507 -0.401269 -0.862396 -0.308635 -0.551321 -0.815349 0.17678 -0.460501 -0.887641 -0.00567547 -0.610549 -0.678713 0.408141 -0.529917 -0.802288 0.274812 -0.43565 -0.771665 -0.463403 -0.425237 -0.691868 -0.583517 -0.41943 -0.671109 -0.611302 -0.422248 -0.300499 -0.855223 -0.415969 -0.302618 -0.85755 -0.425272 -0.356879 -0.831734 -0.422547 -0.35851 -0.832421 -0.421964 -0.42507 -0.800788 -0.410201 -0.429118 -0.804732 -0.423426 -0.477699 -0.769749 -0.422617 -0.479354 -0.769165 -0.421831 -0.533435 -0.733148 -0.421833 -0.533435 -0.733147 -0.451877 0.699204 -0.554005 -0.494358 0.516695 -0.699026 -0.401249 0.698521 -0.59251 -0.551323 0.254569 -0.794505 -0.46051 0.448717 -0.765888 -0.610546 -0.0140913 -0.791855 -0.529898 0.163191 -0.832212 -0.435651 0.787156 -0.436569 -0.425247 0.851241 -0.307497 -0.419426 0.864961 -0.275545 -0.417336 -0.106626 -0.902475 -0.418479 -0.115998 -0.900788 -0.444964 0.177013 -0.87788 -0.451361 0.198108 -0.870073 -0.484819 0.37099 -0.792034 -0.514409 0.484682 -0.707437 -0.50233 0.456574 -0.734306 -0.552304 0.626644 -0.549798 -0.563952 0.642112 -0.519279 -0.609439 0.72417 -0.32274 -0.587416 0.0276923 -0.808811 -0.58708 0.0277701 -0.809052 -0.587419 0.710629 -0.387229 -0.587068 0.710817 -0.387415 -0.494406 0.746175 0.445854 -0.528415 0.576043 0.623661 -0.550513 0.555415 0.623257 -0.571484 0.427942 0.700194 -0.42415 0.811654 -0.401639 -0.424605 0.864313 -0.269581 -0.408244 0.861078 -0.30312 -0.422494 0.875426 -0.234796 -0.421869 0.893571 -0.153483 -0.437218 0.891355 -0.119691 -0.412543 0.910933 -0.00289419 -0.434928 0.899723 0.0365473 -0.438065 0.892201 0.109891 -0.454042 0.872418 0.18092 -0.429406 0.866471 0.254636 -0.462676 0.832864 0.303757 -0.49162 0.744444 0.451788 -0.420486 0.809673 -0.409415 -0.44509 0.736815 -0.508919 -0.457069 0.718701 -0.523981 -0.452991 0.701863 -0.549716 -0.446581 0.621565 -0.643601 -0.451679 0.62988 -0.631852 -0.481229 0.537947 -0.692122 -0.477906 0.544681 -0.689151 -0.484584 0.50424 -0.714787 -0.497666 0.454865 -0.73853 -0.484788 0.383175 -0.78623 -0.500691 0.361303 -0.786618 -0.576045 0.160235 -0.801559 -0.515471 0.193705 -0.834726 -0.554083 -0.825106 -0.110418 -0.531243 -0.835239 -0.141971 -0.550306 -0.785764 -0.282379 -0.484672 -0.786311 -0.383154 -0.505521 -0.708772 -0.492026 -0.498282 -0.705378 -0.504139 -0.440768 -0.655689 -0.613021 -0.444007 -0.648375 -0.618439 -0.455705 -0.54832 -0.701198 -0.452724 -0.562382 -0.69193 -0.438017 -0.51213 -0.738826 -0.439972 -0.492622 -0.750832 -0.422784 -0.408661 -0.808857 -0.422687 -0.408855 -0.80881 -0.425833 -0.269363 -0.863776 -0.421614 -0.277938 -0.863129 -0.421868 -0.153484 -0.893571 -0.41277 -0.172837 -0.894286 -0.427715 -0.0940929 -0.899003 -0.411758 0.0225032 -0.911016 -0.416672 0.0276556 -0.908636 -0.465487 0.239904 -0.85192 -0.386825 0.201598 -0.899847 -0.46128 0.297879 -0.835757 -0.491619 0.451788 -0.744445 -0.494406 0.44585 -0.746177 -0.528416 0.623661 -0.576042 -0.550515 0.623257 -0.555413 -0.571485 0.700192 -0.427944 -0.587417 0.38723 0.71063 -0.587068 0.387414 0.710818 -0.587415 -0.808812 -0.0276932 -0.587081 -0.809051 -0.0277704 -0.41734 0.902473 -0.106627 -0.41928 0.899524 -0.122726 -0.443258 0.872788 0.204363 -0.442184 0.874007 0.201457 -0.492291 0.77497 0.396323 -0.506912 0.733046 0.453524 -0.518066 0.669965 0.531748 -0.567018 0.519248 0.63943 -0.584006 0.395536 0.708864 -0.451877 -0.554003 -0.699205 -0.494358 -0.699022 -0.516699 -0.401251 -0.592508 -0.698521 -0.551325 -0.794506 -0.254562 -0.460541 -0.765902 -0.448661 -0.610548 -0.791854 0.0140931 -0.529897 -0.832212 -0.163196 -0.435649 -0.436559 -0.787163 -0.425238 -0.307437 -0.851267 -0.419427 -0.275541 -0.864961 -0.422615 0.866748 -0.264849 -0.42452 0.866961 -0.261077 -0.394029 0.858884 -0.327199 -0.421844 0.848571 -0.319335 -0.42255 0.817424 -0.391497 -0.429554 0.815815 -0.387206 -0.403888 0.796563 -0.449847 -0.422166 0.790906 -0.442993 -0.422403 0.749745 -0.50937 -0.432838 0.747166 -0.504375 -0.411787 0.717559 -0.561731 -0.422403 0.715381 -0.556603 -0.421998 0.155102 -0.893231 -0.423622 0.155214 -0.892442 -0.422393 0.0945433 -0.901469 -0.422608 0.0947773 -0.901343 -0.42183 0.0266957 -0.906282 -0.422003 -0.102499 -0.900781 -0.423618 -0.102171 -0.900061 -0.422399 -0.0415643 -0.905456 -0.422608 -0.0413133 -0.905371 -0.421828 0.0266959 -0.906283 -0.451877 0.32853 -0.829382 -0.494359 0.0979601 -0.863721 -0.401249 0.308687 -0.862387 -0.551325 -0.176796 -0.815343 -0.460499 0.00567461 -0.887642 -0.610544 -0.408126 -0.678726 -0.529916 -0.274806 -0.802291 -0.435651 0.463416 -0.771656 -0.425249 0.583433 -0.691932 -0.419425 0.611307 -0.671108 -0.41734 0.35889 -0.83488 -0.418478 0.349966 -0.838093 -0.440673 0.519432 -0.732118 -0.456241 0.603919 -0.653549 -0.458872 0.649927 -0.605831 -0.504371 0.763837 -0.402694 -0.502714 0.762281 -0.407684 -0.545141 0.811346 -0.211042 -0.583164 0.809813 -0.0642082 -0.562613 0.816741 -0.128066 -0.612022 0.785659 0.0903793 -0.587417 -0.380423 -0.714297 -0.587082 -0.380476 -0.714544 -0.587417 0.809038 0.019964 -0.587067 0.809294 0.0198979 -0.571484 0.720705 0.392416 -0.550514 0.792631 0.26205 -0.528414 0.810698 0.252085 -0.496819 0.867495 0.0249463 -0.490225 0.871354 0.0205191 -0.470348 0.874974 -0.114865 -0.475513 0.874165 -0.0986065 -0.44099 0.871503 -0.214503 -0.459641 0.852353 -0.249447 -0.438049 0.827623 -0.350932 -0.436254 0.807189 -0.397652 -0.412568 0.787433 -0.45797 -0.442406 0.730399 -0.520379 -0.417816 0.698647 -0.580794 -0.426906 0.63023 -0.648507 -0.417904 0.615637 -0.668092 -0.429079 0.544128 -0.720983 -0.414101 0.497388 -0.762316 -0.433693 0.458844 -0.775482 -0.439437 0.383753 -0.812175 -0.450936 0.35435 -0.819203 -0.44926 0.332844 -0.829084 -0.45155 0.228157 -0.862581 -0.4416 0.203205 -0.873898 -0.478874 0.124265 -0.869044 -0.484546 0.0792771 -0.871166 -0.496236 0.0276339 -0.867748 -0.485282 -0.0610409 -0.872225 -0.50114 -0.0787178 -0.861779 -0.571951 -0.265096 -0.77627 -0.51742 -0.252881 -0.817513 -0.536073 -0.558113 -0.633353 -0.536667 -0.647918 -0.540547 -0.540887 -0.648145 -0.53605 -0.514443 -0.519664 -0.682127 -0.492084 -0.492793 -0.717641 -0.485558 -0.488791 -0.724787 -0.495723 -0.409239 -0.766018 -0.484544 -0.366933 -0.794089 -0.479198 -0.327359 -0.814374 -0.436132 0.488453 -0.75578 -0.42456 0.390851 -0.816691 -0.428565 0.348239 -0.833703 -0.416461 0.314907 -0.852874 -0.429333 0.232301 -0.87276 -0.416974 0.199169 -0.886828 -0.432673 0.0926238 -0.89678 -0.416038 0.0497994 -0.907983 -0.438224 -0.0214604 -0.89861 -0.438016 -0.074102 -0.895908 -0.449087 -0.10904 -0.886809 -0.448257 -0.126613 -0.884892 -0.453406 -0.228253 -0.861582 -0.452044 -0.232106 -0.861269 -0.480959 -0.330566 -0.812038 -0.40148 0.466439 -0.788193 -0.446015 0.549994 -0.7061 -0.43603 0.650193 -0.622195 -0.447915 0.65367 -0.60999 -0.496722 0.757591 -0.423466 -0.530399 0.840108 -0.113557 -0.6196 0.783498 -0.0471805 -0.465303 0.853231 -0.235563 -0.530676 0.826499 -0.187839 -0.500756 0.775903 -0.383689 -0.398408 0.772211 -0.494935 -0.587416 0.690666 0.421809 -0.587068 0.690919 0.421879 -0.587416 -0.686604 -0.428388 -0.587081 -0.686774 -0.428576 -0.417341 0.728245 -0.543586 -0.418478 0.722129 -0.550823 -0.445577 0.859643 -0.249949 -0.441263 0.858149 -0.262425 -0.494411 0.868607 -0.0328511 -0.507352 0.861345 0.0260365 -0.521605 0.841251 0.142218 -0.587402 0.71263 0.383558 -0.547249 0.777887 0.308886 -0.629031 0.588579 0.507833 -0.451877 -0.130173 -0.882532 -0.49436 -0.347027 -0.796982 -0.401267 -0.163895 -0.901179 -0.551326 -0.560783 -0.617707 -0.460507 -0.438917 -0.771548 -0.610544 -0.69281 -0.383731 -0.529899 -0.639121 -0.557433 -0.435652 0.0154955 -0.899982 -0.425244 0.159356 -0.890939 -0.419427 0.193861 -0.886848 -0.42183 0.575665 -0.700478 -0.42223 0.35145 -0.835586 -0.415757 0.351474 -0.838816 -0.425441 0.406278 -0.808665 -0.422539 0.405792 -0.810428 -0.421926 0.472943 -0.773501 -0.409793 0.474364 -0.779133 -0.423783 0.523487 -0.739168 -0.422612 0.5224 -0.740606 -0.421829 0.575665 -0.700478 -0.671501 0.514164 -0.533594 -0.698096 0.497412 -0.515018 -0.704195 0.493886 -0.510085 -0.678254 0.534675 -0.504077 -0.751437 0.483144 -0.449349 -0.650511 0.558059 -0.515176 -0.47849 0.645816 -0.594953 -0.539201 0.819546 -0.193925 -0.687819 0.706376 -0.167146 -0.678329 0.715034 -0.169103 -0.673026 0.719704 -0.170474 -0.635406 0.751451 -0.17771 -0.385679 0.897533 -0.213742 -0.539194 0.806714 0.24183 -0.678256 0.703879 0.211003 -0.386812 0.882944 0.266056 -0.635412 0.739683 0.221633 -0.673241 0.708235 0.212487 -0.687751 0.695534 0.207922 -0.479306 0.609367 0.631615 -0.650515 0.526764 0.547128 -0.683878 0.50547 0.526128 -0.745945 0.456868 0.4846 -0.7042 0.463001 0.538267 -0.698116 0.466223 0.543388 -0.671284 0.48199 0.563084 -0.553658 0.210886 0.805599 -0.667212 0.18788 0.720783 -0.690897 0.181599 0.699774 -0.781955 0.143533 0.606585 -0.698245 0.14143 0.701748 -0.686367 0.142857 0.713087 -0.629448 0.151721 0.762087 -0.6168 -0.198862 0.761585 -0.682908 -0.185306 0.706611 -0.697661 -0.182505 0.692792 -0.781954 -0.178989 0.597086 -0.690893 -0.222475 0.687875 -0.667225 -0.229977 0.708464 -0.553112 -0.258052 0.792134 -0.669945 -0.515139 0.534608 -0.697635 -0.497697 0.515367 -0.704117 -0.493899 0.510179 -0.678259 -0.534672 0.504074 -0.751439 -0.483142 0.449347 -0.6505 -0.558065 0.515182 -0.478446 -0.645835 0.594969 -0.678259 -0.715077 0.169205 -0.678233 -0.7151 0.169209 -0.635156 -0.751629 0.177853 -0.371883 -0.904045 0.210726 -0.633708 -0.7526 0.178904 -0.396876 -0.893207 0.211356 -0.678249 -0.703885 -0.211006 -0.678266 -0.70387 -0.211001 -0.635207 -0.739816 -0.221776 -0.372188 -0.888173 -0.26949 -0.633704 -0.741226 -0.221366 -0.396416 -0.879408 -0.263623 -0.479235 -0.609395 -0.631643 -0.650505 -0.52677 -0.547135 -0.683878 -0.50547 -0.526128 -0.745944 -0.456869 -0.484602 -0.704121 -0.463012 -0.538362 -0.697675 -0.466479 -0.543734 -0.669688 -0.482929 -0.564178 -0.553693 -0.210881 -0.805576 -0.667214 -0.187881 -0.720782 -0.690898 -0.1816 -0.699773 -0.781959 -0.143532 -0.606579 -0.697656 -0.141407 -0.702339 -0.682942 -0.143385 -0.716262 -0.616446 -0.153741 -0.772242 -0.0532486 0.998554 0.00736149 0.00989819 0.964449 -0.264084 0 0.999908 -0.0135433 0 0.759841 -0.650109 -0.00533968 0.797827 -0.602862 0.00215671 0.879576 -0.475754 -0.00810337 0.978313 -0.206975 -0.00487631 0.0664584 -0.997777 0.00850005 -0.144078 -0.98953 -0.00422876 -0.246165 -0.969219 0.00530378 -0.524519 -0.851382 0 -0.553831 -0.832629 -0.00647167 0.0892213 -0.995991 0.0164942 0.354028 -0.935089 1.34103e-06 0.266948 -0.963711 -4.70929e-07 0.506557 -0.862206 0.00190065 0.53661 -0.843828 -0.00302832 0.670591 -0.741821 0 0.696696 -0.717367 0 0.991404 -0.130833 0 0.991404 -0.130833 -0.00487146 0.556379 -0.830914 0.00849979 0.369994 -0.928995 -0.00422839 0.271433 -0.962448 0.00530463 -0.0285585 -0.999578 0 -0.0633256 -0.997993 -0.00647201 0.575261 -0.817944 0.0164937 0.774139 -0.632801 1.66104e-06 0.713039 -0.701125 -3.75319e-07 0.869792 -0.493418 0.00190107 0.886633 -0.46247 -0.00302793 0.951659 -0.307142 0 0.962038 -0.272915 0 0.944238 0.329263 -0.00547181 0.921023 0.38947 0.0187224 0.405203 0.914035 0.00145905 0.314681 0.949196 -0.000531691 0.553544 0.83282 -0.00413805 0.506523 0.862216 0.0134131 0.740282 0.672162 -0.00671168 0.673308 0.739332 0.00189851 0.857769 0.514032 -0.00600208 0.159826 0.987127 0.0114556 -0.149937 0.988629 0 -0.0873472 0.996178 0 0.993031 -0.11785 0.00911671 0.981327 -0.192133 -1.03842e-06 0.943982 -0.329998 -1.50473e-08 0.909627 -0.415425 -0.00151421 0.875075 -0.483985 0.0083844 0.798124 -0.602435 -0.00534184 0.716258 -0.697816 0.00749771 0.487649 -0.873007 0 0.444124 -0.895966 0 0.653103 0.75727 -0.0054726 0.602887 0.797808 0.0187233 -0.106101 0.994179 0.0014601 -0.202075 0.979369 -0.000530733 0.0629863 0.998014 -0.0041433 0.00747104 0.999964 0.0134126 0.305023 0.952251 -0.0067121 0.213437 0.976934 0.00189774 0.485824 0.874055 -0.00600119 -0.35515 0.93479 0.0114572 -0.624173 0.781202 0 -0.573736 0.81904 0 0.99968 -0.0252941 0.00705673 0.98608 -0.166124 -0.00350905 0.96919 -0.24629 0.00417572 0.847459 -0.530844 0 0.832605 -0.553868 0 0.186977 0.982364 -0.00547241 0.123221 0.992364 0.0187256 -0.588968 0.80794 0.00146073 -0.664685 0.747122 -0.000529777 -0.444466 0.895796 -0.00414697 -0.49358 0.86969 0.0134135 -0.211965 0.977185 -0.00671257 -0.303629 0.952767 0.00189775 -0.0162764 0.999866 -0.00600092 -0.774969 0.631971 0.0114569 -0.931152 0.364452 0 -0.906392 0.422437 0 0.994858 -0.101275 0 0.994858 -0.101275 0 -0.329261 0.944239 -0.00547314 -0.389483 0.921017 0.0194985 -0.910682 0.412648 1.77237e-08 -0.949201 0.31467 -2.91128e-06 -0.828285 0.560307 -0.00413442 -0.862179 0.506588 0.0134141 -0.672151 0.740293 -0.00671557 -0.739336 0.673303 0.00189556 -0.51402 0.857776 -0.00600213 -0.987129 0.159813 0.0114541 -0.988631 -0.149926 0 -0.996178 -0.0873437 -0.00485664 0.441634 0.897182 0.00849883 0.619539 0.78492 -0.00422944 0.69779 0.71629 0.00530284 0.87994 0.475054 0 0.895946 0.444163 -0.00647545 0.420727 0.907164 0.0164878 0.160982 0.98682 2.34676e-06 0.250666 0.968074 -7.09707e-08 -0.0075808 0.999971 0.0019021 -0.042817 0.999081 -0.00302724 -0.209847 0.977729 0 -0.244671 0.969606 0 -0.757278 0.653092 -0.00547063 -0.797803 0.602894 0.0194974 -0.994997 -0.0979801 2.06992e-06 -0.97937 -0.202075 -7.28409e-07 -0.997468 0.0711106 -0.00416008 -0.999965 0.00721251 0.0134108 -0.952253 0.305016 -0.0067105 -0.976932 0.213445 0.00189933 -0.874045 0.485842 -0.00600038 -0.934793 -0.355143 0.0114584 -0.781198 -0.624178 0 -0.81904 -0.573736 -0.00487566 -0.0664498 0.997778 0.00849988 0.144079 0.98953 -0.00422713 0.246152 0.969222 0.00530611 0.524519 0.851382 0 0.553844 0.832621 -0.00647159 -0.0892213 0.995991 0.0164939 -0.354022 0.935092 2.01152e-06 -0.266945 0.963712 -7.06164e-07 -0.506538 0.862217 0.00190181 -0.536614 0.843826 -0.00302758 -0.670601 0.741812 0 -0.6967 0.717362 0 -0.982365 0.186975 -0.00547045 -0.992361 0.123243 0.0194897 -0.812681 -0.582382 1.13923e-06 -0.747121 -0.664688 -2.03677e-06 -0.899376 -0.437177 -0.0041437 -0.869722 -0.493525 0.0134133 -0.977185 -0.211967 -0.00671284 -0.952766 -0.30363 0.00189884 -0.999866 -0.0162394 -0.0060025 -0.631993 -0.774951 0.0114571 -0.364449 -0.931153 0 -0.422434 -0.906394 -0.00484857 -0.556074 0.831118 0.00849925 -0.369998 0.928994 -0.0042292 -0.271433 0.962448 0.00530471 0.0285586 0.999578 0 0.063327 0.997993 -0.00647431 -0.575254 0.817949 0.0164908 -0.774134 0.632808 4.64796e-06 -0.713055 0.701108 3.27189e-06 -0.869804 0.493397 0.00190214 -0.886621 0.462492 -0.00302703 -0.951653 0.30716 0 -0.96203 0.272943 0 -0.944229 -0.32929 -0.00546989 -0.921021 -0.389475 0.0187226 -0.40521 -0.914032 0.00145863 -0.314684 -0.949196 -0.000532814 -0.55355 -0.832816 -0.00415163 -0.506363 -0.862311 0.0134081 -0.740268 -0.672178 -0.00671076 -0.673313 -0.739327 0.00189966 -0.857773 -0.514025 -0.00600211 -0.159828 -0.987127 0.0114552 0.149931 -0.98863 0 0.0873451 -0.996178 -0.00489044 -0.897436 0.441117 0.0085006 -0.784924 0.619534 -0.00422732 -0.716295 0.697785 0.00530556 -0.475062 0.879937 0 -0.444154 0.89595 -0.00646873 -0.907163 0.420729 0.0164979 -0.986826 0.160944 1.95437e-06 -0.968069 0.250686 -5.95937e-08 -0.999971 -0.00763867 0.00189714 -0.999083 -0.0427817 -0.00303196 -0.977735 -0.209822 0 -0.969599 -0.244699 0 -0.653111 -0.757262 -0.00547277 -0.602894 -0.797803 0.0187219 0.1061 -0.994179 0.00145827 0.202077 -0.979369 -0.00053219 -0.0629607 -0.998016 -0.00414334 -0.00747008 -0.999964 0.0134138 -0.305029 -0.952249 -0.00671226 -0.213437 -0.976934 0.00189771 -0.485834 -0.874049 -0.00600236 0.355152 -0.934789 0.0114556 0.624161 -0.781211 0 0.573732 -0.819043 -0.00487697 -0.997777 -0.0664669 0.00849972 -0.989531 0.144069 -0.00422738 -0.969224 0.246144 0.00530635 -0.851378 0.524525 0 -0.832616 0.553851 -0.00647097 -0.995992 -0.0892103 0.0164952 -0.93509 -0.354025 1.34103e-06 -0.963713 -0.266939 -4.70806e-07 -0.862215 -0.506542 0.00190211 -0.843823 -0.536619 -0.00302695 -0.741824 -0.670587 0 -0.71738 -0.696682 0 -0.186973 -0.982365 -0.00547234 -0.12322 -0.992364 0.0187266 0.588968 -0.80794 0.00145832 0.6647 -0.747109 -0.000532914 0.444457 -0.8958 -0.00412171 0.49319 -0.869912 0.013413 0.211968 -0.977185 -0.00671257 0.303629 -0.952767 0.00189775 0.0162764 -0.999866 -0.0059996 0.774969 -0.631971 0.011458 0.931148 -0.364461 0 0.906385 -0.422452 -0.00486856 -0.830929 -0.556357 0.00850025 -0.928994 -0.369996 -0.00422925 -0.96245 -0.271426 0.00530364 -0.999578 0.0285678 0 -0.997993 0.0633284 -0.00647143 -0.81794 -0.575267 0.0164941 -0.632799 -0.774141 2.15628e-06 -0.701122 -0.713042 3.6516e-07 -0.493407 -0.869799 0.00190164 -0.462461 -0.886638 -0.00302733 -0.307138 -0.95166 0 -0.272917 -0.962038 0 -0.973127 0.230268 0 -0.973127 0.230268 0 -0.72762 0.68598 0 -0.72762 0.68598 0 -0.287149 0.957886 0 -0.287149 0.957886 0 0.230268 0.973127 0 0.230268 0.973127 0 0.685978 0.727622 0 0.685978 0.727622 0 0.957887 0.287147 0 0.957887 0.287147 0 -0.973128 0.230266 0 -0.973128 0.230266 0 -0.727619 0.685981 0 -0.727619 0.685981 0 -0.287149 0.957886 0 -0.287149 0.957886 0 0.230265 0.973128 0 0.230265 0.973128 0 0.685981 0.72762 0 0.685981 0.72762 0 0.957886 0.287148 0 0.957886 0.287148 0 -0.973128 0.230267 0 -0.973128 0.230267 0 -0.727621 0.68598 0 -0.727621 0.68598 0 -0.287147 0.957887 0 -0.287147 0.957887 0 0.230265 0.973128 0 0.230265 0.973128 0 0.685981 0.72762 0 0.685981 0.72762 0 0.957886 0.287148 0 0.957886 0.287148 0 -0.973128 0.230266 0 -0.973128 0.230266 0 -0.727621 0.685979 0 -0.727621 0.685979 0 -0.287144 0.957887 0 -0.287144 0.957887 0 0.230263 0.973128 0 0.230263 0.973128 0 0.685982 0.727619 0 0.685982 0.727619 0 0.957886 0.287149 0 0.957886 0.287149 0 -0.973128 0.230264 0 -0.973128 0.230264 0 -0.727621 0.685979 0 -0.727621 0.685979 0 -0.287144 0.957887 0 -0.287144 0.957887 0 0.230263 0.973128 0 0.230263 0.973128 0 0.685982 0.727619 0 0.685982 0.727619 0 0.957886 0.287149 0 0.957886 0.287149 0 -0.973127 0.230268 0 -0.973127 0.230268 0 -0.727619 0.685982 0 -0.727619 0.685982 0 -0.28715 0.957886 0 -0.28715 0.957886 0 0.230267 0.973127 0 0.230267 0.973127 0 0.685977 0.727623 0 0.685977 0.727623 0 0.957889 0.28714 0 0.957889 0.28714 0 -0.973127 0.230268 0 -0.973127 0.230268 0 -0.727621 0.685979 0 -0.727621 0.685979 0 -0.28715 0.957886 0 -0.28715 0.957886 0 0.230267 0.973127 0 0.230267 0.973127 0 0.685979 0.727621 0 0.685979 0.727621 0 0.957886 0.287149 0 0.957886 0.287149 0 -0.973129 0.230259 0 -0.973129 0.230259 0 -0.727616 0.685985 0 -0.727616 0.685985 0 -0.287149 0.957886 0 -0.287149 0.957886 0 0.230268 0.973127 0 0.230268 0.973127 0 0.685979 0.727622 0 0.685979 0.727622 0 0.957886 0.287149 0 0.957886 0.287149 0 -0.973129 0.230259 0 -0.973129 0.230259 0 -0.727615 0.685986 0 -0.727615 0.685986 0 -0.28715 0.957886 0 -0.28715 0.957886 0 0.230269 0.973127 0 0.230269 0.973127 0 0.685978 0.727622 0 0.685978 0.727622 0 0.957886 0.287149 0 0.957886 0.287149 0 -0.973127 0.230268 0 -0.973127 0.230268 0 -0.727621 0.685979 0 -0.727621 0.685979 0 -0.287143 0.957888 0 -0.287143 0.957888 0 0.230265 0.973128 0 0.230265 0.973128 0 0.685979 0.727621 0 0.685979 0.727621 0 0.957886 0.287149 0 0.957886 0.287149 0 -0.973127 0.230267 0 -0.973127 0.230267 0 -0.727621 0.685979 0 -0.727621 0.685979 0 -0.28715 0.957886 0 -0.28715 0.957886 0 0.230267 0.973127 0 0.230267 0.973127 0 0.685979 0.727621 0 0.685979 0.727621 0 0.957889 0.287139 0 0.957889 0.287139 0 0.973128 -0.230267 0 0.973128 -0.230267 0 -0.973128 0.230267 0 -0.973128 0.230267 0 -0.983491 0.180959 -0.0171495 -0.999821 0.00795094 -0.000512194 -0.999162 -0.0409213 0.00046621 -0.931274 -0.364318 -0.0160225 -0.904274 -0.426653 -5.66618e-05 -0.82609 -0.563538 7.2159e-05 -0.731649 -0.681682 -0.0170249 -0.629597 -0.776735 -0.0173294 -0.630783 -0.775766 3.34475e-05 -0.0653964 -0.997859 -0.00905186 -0.178231 -0.983947 -0.0172984 -0.230231 -0.972982 -0.00160036 -0.328777 -0.944406 0.00130783 -0.511779 -0.859116 -6.49686e-05 0.105075 -0.994464 -0.0179055 0.214725 -0.97651 0.000136211 0.32416 -0.946002 -8.90046e-05 0.492465 -0.870333 -0.0170374 0.617165 -0.786649 0.00980271 0.703713 -0.710417 -0.012381 0.897422 -0.440999 0 0.913661 -0.406478 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.68598 0.72762 0 0.68598 0.72762 0 -0.685981 -0.727619 0 -0.685981 -0.727619 0 -0.550831 -0.834617 -0.0195919 -0.495844 -0.86819 -3.94781e-05 -0.339775 -0.940507 4.72481e-05 -0.202326 -0.979318 -0.0198232 -0.0448268 -0.998798 -0.0220615 -0.0537041 -0.998313 -1.94376e-05 0.560875 -0.8279 -0.014138 0.436732 -0.899481 -0.0188553 0.416085 -0.90913 0.000117859 0.278464 -0.960447 -0.000124745 0.0955656 -0.995423 2.50176e-05 0.687325 -0.72635 -0.0183081 0.785231 -0.618932 0.000101721 0.839054 -0.544048 -4.45295e-05 0.933338 -0.359 -0.0149166 0.979855 -0.199154 0 0.990531 -0.137292 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.230266 0.973128 0 0.230266 0.973128 0 -0.230266 -0.973128 0 -0.230266 -0.973128 0 -0.0536081 -0.998562 -0.0157763 -0.00327658 -0.99987 -2.70721e-05 0.174239 -0.984703 4.85848e-05 0.309694 -0.950836 -0.0198642 0.439261 -0.89814 -0.0160538 0.454666 -0.890518 2.68224e-05 0.932873 -0.360207 -4.31263e-05 0.864573 -0.502508 -0.0180886 0.791225 -0.611258 0.000197477 0.727365 -0.686251 -0.000117477 0.5686 -0.822614 -0.00812924 0.963541 -0.267437 -0.0176135 0.979989 -0.198272 0 0.994767 -0.102171 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.287148 0.957886 0 -0.287148 0.957886 0 0.287147 -0.957886 0 0.287147 -0.957886 0 0.436618 -0.899647 -0.0164584 0.4876 -0.872912 -3.78017e-05 0.6207 -0.784048 6.49485e-05 0.734958 -0.678112 -0.0187811 0.810791 -0.585034 -0.00925757 0.83912 -0.543868 0.00946204 0.942758 -0.333343 -0.0167174 0.982108 -0.187574 0 0.997749 -0.0670577 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.727619 0.685981 0 -0.727619 0.685981 0 0.727621 -0.68598 0 0.727621 -0.68598 0 0.803741 -0.59498 -0.0172658 0.847965 -0.529771 -0.000895704 0.902243 -0.431228 0.00114006 0.964397 -0.264455 -0.0153584 0.986183 -0.164946 0 0.99786 -0.0653898 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.973127 0.230267 0 -0.973127 0.230267 0 0.973128 -0.230267 0 0.973128 -0.230267 0 0.994858 -0.101276 0 0.994858 -0.101276 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.957886 -0.287147 0 -0.957886 -0.287147 0 0.957886 0.287148 0 0.957886 0.287148 0 0.942216 0.335007 -0.0207828 0.850744 0.525169 -0.0136019 0.841571 0.539976 -2.54303e-05 0.714186 0.699956 7.77134e-05 0.593502 0.804833 -0.0260749 0.474125 0.880072 0.00215453 0.35529 0.934754 -0.000901067 0.161931 0.986802 -0.0168386 -0.0294399 0.999425 -0.0278914 0.00934504 0.999567 -0.016573 -0.538116 0.842708 6.794e-05 -0.337852 0.941199 -0.00012559 -0.187398 0.982284 -0.0769745 -0.687535 0.72206 0.0002183 -0.525284 0.850927 -0.000123908 -0.82117 0.570684 -0.0258751 -0.880076 0.474128 0.000128207 -0.940956 0.33853 -8.53495e-05 -0.987833 0.155521 -0.0244915 -0.999267 -0.0294353 0 -0.994494 -0.104797 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.685981 -0.72762 0 -0.685981 -0.72762 0 0.685979 0.727622 0 0.685979 0.727622 0 0.64848 0.761231 -0.0171489 0.506797 0.861895 -0.000514239 0.464152 0.885755 0.000468596 0.150146 0.988664 -0.0160232 0.0826469 0.99645 -5.5764e-05 -0.074988 0.997184 7.31708e-05 -0.224519 0.97447 -0.0170239 -0.357874 0.933615 -0.0173298 -0.356435 0.934159 3.32144e-05 -0.831461 0.555582 -0.00905235 -0.763002 0.646333 -0.0172977 -0.727512 0.685877 -0.00159968 -0.65349 0.756933 0.00130656 -0.488115 0.872779 -6.50608e-05 -0.913769 0.406234 -0.0179048 -0.953047 0.302294 0.000135946 -0.98134 0.19228 -8.93888e-05 -0.999962 0.00869248 -0.0170368 -0.989841 -0.141154 0.00980189 -0.967099 -0.25421 -0.0123775 -0.830629 -0.556689 0 -0.808859 -0.588003 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.230267 -0.973128 0 -0.230267 -0.973128 0 0.230265 0.973128 0 0.230265 0.973128 0 0.180973 0.983488 -0.0207814 -0.0294372 0.999351 -0.0136006 -0.0468466 0.99881 -2.48867e-05 -0.249071 0.968485 7.81695e-05 -0.40025 0.916406 -0.0260758 -0.525103 0.850639 0.00215509 -0.631882 0.775062 -0.000899906 -0.773634 0.633632 -0.0168366 -0.880248 0.474215 -0.0278919 -0.860974 0.507883 -0.0165719 -0.998865 -0.0446662 6.84842e-05 -0.98403 0.178002 -0.000125004 -0.944382 0.328851 -0.0769675 -0.969095 -0.234372 0.000216841 -0.999566 -0.0294489 -0.00012514 -0.904812 -0.425811 -0.0258772 -0.850643 -0.525107 0.000126395 -0.763651 -0.64563 -8.6627e-05 -0.628614 -0.777717 -0.024494 -0.474144 -0.880107 0 -0.406486 -0.913657 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.287149 -0.957886 0 0.287149 -0.957886 0 -0.287146 0.957887 0 -0.287146 0.957887 0 -0.335023 0.94221 -0.0207848 -0.525169 0.850744 -0.0135955 -0.539994 0.841559 -2.61695e-05 -0.699922 0.714219 7.66739e-05 -0.804839 0.593493 -0.026076 -0.880073 0.474121 0.00215571 -0.934761 0.35527 -0.000901014 -0.986798 0.161954 -0.01684 -0.999425 -0.0294352 -0.0278895 -0.999567 0.00933848 -0.0165747 -0.842701 -0.538127 6.9275e-05 -0.941196 -0.337861 -0.000124044 -0.982281 -0.187416 -0.0769798 -0.722049 -0.687546 0.000220065 -0.850928 -0.525283 -0.000122518 -0.57068 -0.821172 -0.0258758 -0.474122 -0.880079 0.000128181 -0.338511 -0.940962 -8.5347e-05 -0.155523 -0.987832 -0.0244943 0.0294353 -0.999267 0 0.104807 -0.994493 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.727621 -0.68598 0 0.727621 -0.68598 0 -0.727621 0.68598 0 -0.727621 0.68598 0 -0.761256 0.648451 -0.0171481 -0.861895 0.506797 -0.000511574 -0.885759 0.464145 0.000466521 -0.988666 0.15013 -0.0160221 -0.99645 0.0826467 -5.66871e-05 -0.997184 -0.0749881 7.22838e-05 -0.974466 -0.224536 -0.0170245 -0.933613 -0.357877 -0.0173276 -0.934153 -0.356451 3.27224e-05 -0.555565 -0.831473 -0.00905299 -0.64633 -0.763004 -0.0172989 -0.685877 -0.727512 -0.00160074 -0.756934 -0.65349 0.00130751 -0.872775 -0.488121 -6.54154e-05 -0.406229 -0.913771 -0.0179052 -0.302296 -0.953046 0.00013576 -0.192273 -0.981341 -8.94086e-05 -0.00868287 -0.999962 -0.0170377 0.141154 -0.989841 0.00980353 0.254227 -0.967095 -0.01238 0.556689 -0.830629 0 0.588011 -0.808853 -0.629059 0.196394 -0.75214 -0.686233 0.18461 -0.703565 -0.698221 0.182489 -0.692232 -0.781961 0.178987 -0.597077 -0.690892 0.222477 -0.687875 -0.667228 0.229978 -0.708461 -0.553155 0.258044 -0.792106 0 0.34145 -0.9399 -0.00493495 0.389508 -0.92101 0.0025605 0.545869 -0.837867 -2.08801e-06 0.587763 -0.809033 9.96904e-07 0.757953 -0.652309 0.00348851 0.743366 -0.668876 -0.00158703 0.885813 -0.464039 -0.00330258 0.896692 -0.442644 0.00764289 0.980308 -0.197328 0.0110186 0.976027 -0.217371 0 0.999278 -0.037983 -0.00486154 -0.441532 -0.897232 0.0084999 -0.619532 -0.784925 -0.00423043 -0.697796 -0.716284 0.00530274 -0.879941 -0.475054 0 -0.895946 -0.444163 -0.00647203 -0.420731 -0.907162 0.0164946 -0.160944 -0.986826 1.95438e-06 -0.250668 -0.968073 -5.91422e-08 0.0075808 -0.999971 0.00190216 0.042817 -0.999081 -0.00302692 0.209847 -0.977729 0 0.244667 -0.969607 0 -0.973128 0.230263 0 -0.973128 0.230263 0 -0.727617 0.685984 0 -0.727617 0.685984 0 -0.287149 0.957886 0 -0.287149 0.957886 0 0.230267 0.973127 0 0.230267 0.973127 0 0.685982 0.727619 0 0.685982 0.727619 0 0.957886 0.28715 0 0.957886 0.28715 0 0.957887 0.287147 0 0.957887 0.287147 0 -0.957887 -0.287147 0 -0.957887 -0.287147 0.000517317 0.247962 -0.96877 -3.19178e-05 -0.75059 -0.660768 0 -0.92595 -0.377645 -0.0259637 -0.861893 -0.506425 -0.0174213 -0.845591 -0.533548 -0.00595434 -0.794516 -0.607214 4.71727e-05 -0.663648 -0.748045 -0.0196155 -0.530746 -0.847304 -0.0243237 -0.545761 -0.837588 -0.000608856 0.0452652 -0.998975 -0.0255255 -0.11452 -0.993093 -0.0170879 -0.0795401 -0.996685 7.73526e-05 -0.246834 -0.969058 -0.000110052 -0.409173 -0.912457 -0.0206993 0.770762 -0.636787 -0.00409199 0.699717 -0.714409 0.0100156 0.389704 -0.920886 -0.0608827 0.556101 -0.828882 -0.0221608 0.413156 -0.910391 0 0.97792 -0.20898 -0.0650616 0.996067 -0.0601492 -0.0155061 0.975507 -0.219421 0.00126143 0.917812 -0.397013 -0.00292725 0.827013 -0.562176 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.705614 -0.707193 0.0445779 -0.705616 -0.707191 0.0445778 -0.705616 -0.686959 0.173765 -0.705614 -0.68696 0.173765 -0.705615 -0.643333 0.297035 -0.705614 -0.643334 0.297035 -0.705614 -0.5778 0.41019 -0.705615 -0.5778 0.41019 -0.705615 -0.492589 0.509376 -0.705613 -0.49259 0.509377 -0.705613 -0.390605 0.591217 -0.705612 -0.390606 0.591218 -0.705612 -0.275319 0.652925 -0.705616 -0.275318 0.652921 -0.705616 -0.150656 0.692393 -0.705615 -0.150656 0.692395 -0.705614 -0.0208639 0.708289 -0.705616 -0.0208639 0.708287 -0.705616 0.109639 0.700061 -0.705609 0.10964 0.700067 -0.70561 0.23641 0.668 -0.70562 0.236407 0.667992 -0.705621 0.355124 0.613177 -0.705618 0.355126 0.61318 -0.705617 0.461751 0.537486 -0.705613 0.461754 0.537488 -0.705612 0.552656 0.443491 -0.705614 0.552654 0.443489 -0.705615 0.624734 0.334388 -0.70562 0.62473 0.334386 -0.70562 0.675535 0.213898 -0.705617 0.675539 0.213899 -0.705617 0.70334 0.086127 -0.705615 0.703341 0.0861271 0.705615 0.703341 0.0861271 0.705617 0.70334 0.086127 0.705616 0.675539 0.213899 0.70562 0.675535 0.213898 0.70562 0.62473 0.334386 0.705615 0.624734 0.334388 0.705614 0.552654 0.443489 0.705612 0.552656 0.443491 0.705613 0.461753 0.537489 0.705617 0.461751 0.537486 0.705618 0.355126 0.61318 0.70562 0.355124 0.613177 0.70562 0.236407 0.667992 0.70561 0.23641 0.668 0.705609 0.10964 0.700068 0.705616 0.109639 0.700061 0.705616 -0.0208638 0.708287 0.705614 -0.0208639 0.708289 0.705615 -0.150656 0.692395 0.705616 -0.150656 0.692393 0.705616 -0.275318 0.652922 0.705612 -0.275319 0.652925 0.705612 -0.390606 0.591218 0.705613 -0.390605 0.591217 0.705613 -0.49259 0.509377 0.705615 -0.492589 0.509376 0.705615 -0.5778 0.41019 0.705614 -0.5778 0.41019 0.705614 -0.643334 0.297035 0.705615 -0.643333 0.297035 0.705615 -0.68696 0.173765 0.705616 -0.686959 0.173765 0.705616 -0.707191 0.0445778 0.705614 -0.707193 0.0445779 -0.793129 0.607428 0.0444713 -0.896669 -0.442656 0.0062796 -0.60836 -0.793581 0.0112579 -0.194919 -0.980721 0.0139126 -0.441933 -0.896958 0.0127244 -0.258613 -0.965861 0.0152235 -0.258596 -0.961019 0.0978328 -0.258598 -0.961018 0.0978327 -0.258598 -0.948835 0.181219 -0.258599 -0.948834 0.181219 -0.258599 -0.929429 0.263225 -0.258594 -0.929431 0.263226 -0.258594 -0.902952 0.343229 -0.258605 -0.90295 0.343228 -0.258605 -0.869599 0.420619 -0.258593 -0.869602 0.420621 -0.258595 -0.829633 0.494811 -0.258597 -0.829633 0.494811 -0.258596 -0.78335 0.565235 -0.258588 -0.783352 0.565237 -0.258586 -0.731108 0.631359 -0.258599 -0.731106 0.631357 -0.258598 -0.673297 0.692675 -0.258589 -0.673299 0.692677 -0.258589 -0.610366 0.748722 -0.258587 -0.610366 0.748723 -0.258589 -0.542787 0.799071 -0.258599 -0.542786 0.799068 -0.258599 -0.471077 0.843334 -0.258596 -0.471078 0.843335 -0.258598 -0.395784 0.881182 -0.25859 -0.395784 0.881184 -0.25859 -0.317478 0.912326 -0.258603 -0.317477 0.912323 -0.258603 -0.236755 0.936521 -0.258591 -0.236755 0.936524 -0.25859 -0.154231 0.953595 -0.258581 -0.154231 0.953598 -0.258582 -0.0705325 0.963411 -0.258608 -0.0705328 0.963404 -0.258611 0.0137017 0.965884 -0.258597 0.0137022 0.965888 -0.258598 0.0978326 0.961018 -0.258582 0.0978335 0.961022 -0.258582 0.181219 0.948839 -0.258593 0.181218 0.948836 -0.258592 0.263226 0.929431 -0.258605 0.263225 0.929428 -0.258605 0.343229 0.90295 -0.258594 0.34323 0.902952 -0.258595 0.42062 0.869602 -0.258579 0.420623 0.869606 -0.258577 0.494814 0.829637 -0.258599 0.49481 0.829632 -0.2586 0.565234 0.78335 -0.258597 0.565235 0.78335 -0.258595 0.631358 0.731106 -0.258576 0.631361 0.73111 -0.258574 0.692679 0.673301 -0.258573 0.69268 0.673302 -0.258572 0.748727 0.610368 -0.258601 0.74872 0.610364 -0.258601 0.799067 0.542786 -0.258586 0.799071 0.542788 -0.258585 0.843337 0.471079 -0.258602 0.843333 0.471078 -0.258602 0.881181 0.395783 -0.25861 0.881179 0.395783 -0.258611 0.912321 0.317475 -0.258628 0.912317 0.317474 -0.258628 0.936514 0.236754 -0.258567 0.936531 0.236756 -0.258566 0.953602 0.154232 -0.258605 0.953591 0.154231 -0.258605 0.963405 0.0705335 -0.258589 0.963409 0.0705333 -0.608353 0.791548 0.0579514 -0.70682 0.705354 0.0536822 -0.706776 0.698362 0.11295 -0.70676 0.698379 0.112952 -0.70676 0.685876 0.173392 -0.706739 0.685896 0.173396 -0.70674 0.668173 0.232515 -0.706775 0.66814 0.232505 -0.706775 0.645333 0.289852 -0.706772 0.645336 0.289853 -0.706772 0.617618 0.344995 -0.706772 0.617618 0.344995 -0.706772 0.585199 0.397511 -0.706757 0.585212 0.397519 -0.706758 0.548339 0.44701 -0.706791 0.548313 0.446991 -0.70679 0.507269 0.493078 -0.706776 0.507279 0.493087 -0.706776 0.462373 0.535424 -0.706772 0.462376 0.535427 -0.706772 0.413951 0.573689 -0.70677 0.413952 0.57369 -0.706771 0.362377 0.607584 -0.706784 0.362369 0.607573 -0.706782 0.308037 0.636845 -0.706769 0.308044 0.636857 -0.706771 0.251365 0.66128 -0.706781 0.251361 0.66127 -0.706781 0.192772 0.680661 -0.706785 0.19277 0.680658 -0.706784 0.132713 0.694869 -0.706775 0.132716 0.694879 -0.706776 0.0716475 0.7038 -0.706771 0.0716482 0.703804 -0.706773 0.0100345 0.707369 -0.706767 0.0100348 0.707375 -0.706767 -0.0516547 0.705558 -0.706778 -0.0516544 0.705547 -0.706779 -0.11295 0.698359 -0.706783 -0.11295 0.698355 -0.706783 -0.173385 0.685854 -0.706774 -0.173387 0.685862 -0.706774 -0.232504 0.668141 -0.706777 -0.232504 0.668138 -0.706777 -0.289851 0.645331 -0.706774 -0.289852 0.645334 -0.706775 -0.344993 0.617616 -0.706769 -0.344996 0.617621 -0.706769 -0.397512 0.585202 -0.706774 -0.39751 0.585198 -0.706775 -0.447 0.548325 -0.706781 -0.446996 0.54832 -0.706781 -0.493084 0.507275 -0.70678 -0.493085 0.507276 -0.70678 -0.535421 0.462371 -0.706772 -0.535427 0.462376 -0.706772 -0.573688 0.413951 -0.706772 -0.573688 0.413951 -0.706772 -0.607583 0.362376 -0.706777 -0.607579 0.362373 -0.706777 -0.63685 0.30804 -0.706769 -0.636857 0.308044 -0.706769 -0.661281 0.251366 -0.706774 -0.661277 0.251364 -0.706774 -0.680669 0.192773 -0.706772 -0.68067 0.192774 -0.706771 -0.694882 0.132716 -0.706772 -0.694881 0.132716 -0.706772 -0.703804 0.071648 -0.706773 -0.703803 0.0716479 -0.706816 -0.707294 0.0120697 -0.793116 -0.60901 0.00863952 -0.980738 -0.195309 0.00277066 -0.965862 -0.259005 0.00520166 -0.965846 -0.257783 0.0262426 -0.965846 -0.257783 0.0262426 -0.965846 -0.254515 0.04861 -0.965847 -0.254513 0.0486097 -0.965847 -0.249308 0.070607 -0.965846 -0.24931 0.0706075 -0.965846 -0.242207 0.0920676 -0.965847 -0.242207 0.0920674 -0.965847 -0.233261 0.112827 -0.965846 -0.233264 0.112828 -0.965846 -0.222542 0.132729 -0.965847 -0.222538 0.132727 -0.965847 -0.210124 0.151617 -0.965847 -0.210125 0.151618 -0.965847 -0.196111 0.169354 -0.965846 -0.196113 0.169356 -0.965846 -0.180606 0.185804 -0.965847 -0.180603 0.185801 -0.965847 -0.163723 0.200835 -0.965846 -0.163725 0.200838 -0.965846 -0.145597 0.214343 -0.965847 -0.145596 0.21434 -0.965847 -0.126361 0.226214 -0.965847 -0.126361 0.226215 -0.965847 -0.106164 0.236367 -0.965847 -0.106165 0.236367 -0.965846 -0.0851599 0.244721 -0.965846 -0.085161 0.244724 -0.965846 -0.0635078 0.251215 -0.965845 -0.0635078 0.251216 -0.965846 -0.0413713 0.255795 -0.965846 -0.0413712 0.255794 -0.965846 -0.0189197 0.258426 -0.965847 -0.0189196 0.258422 -0.965847 0.00367539 0.259088 -0.965846 0.00367543 0.259089 -0.965847 0.0262425 0.257782 -0.965846 0.0262427 0.257784 -0.965846 0.0486102 0.254515 -0.965846 0.0486103 0.254516 -0.965846 0.0706078 0.249311 -0.965847 0.0706073 0.249309 -0.965847 0.0920672 0.242206 -0.965847 0.0920665 0.242205 -0.965847 0.112826 0.233259 -0.965846 0.112827 0.233261 -0.965846 0.132728 0.222541 -0.965846 0.132728 0.222541 -0.965846 0.151618 0.210126 -0.965846 0.151618 0.210126 -0.965846 0.169356 0.196112 -0.965847 0.169352 0.196108 -0.965848 0.185799 0.180602 -0.965845 0.185808 0.180609 -0.965845 0.200842 0.163728 -0.965848 0.200831 0.16372 -0.965848 0.214336 0.145593 -0.965845 0.214346 0.145599 -0.965845 0.22622 0.126364 -0.965847 0.226215 0.126361 -0.965847 0.236367 0.106164 -0.965848 0.236364 0.106163 -0.965848 0.244717 0.0851585 -0.965847 0.244719 0.0851593 -0.965847 0.25121 0.0635062 -0.965849 0.251204 0.0635048 -0.965849 0.255782 0.0413691 -0.965847 0.255787 0.0413698 -0.965847 0.25842 0.0189196 -0.965847 0.258422 0.0189198 0.830977 0.49617 0.251582 0.830975 -0.154154 0.534525 0.96578 0.258258 0.0239001 0.9807 0.190895 0.0422758 0.980699 -0.195413 0.00652602 0.980699 -0.195412 0.00652602 0.9807 -0.0541786 0.187863 0.9807 -0.0541781 0.187861 0.9807 -0.0772963 0.17959 0.980698 0.17439 0.0884242 0.980698 0.17439 0.088424 0.980699 0.161931 0.109583 0.896489 -0.442818 0.0147884 0.830996 -0.555945 0.0192752 0.792815 -0.609123 0.0203424 0.554768 -0.128537 0.822016 0.830975 -0.0859447 0.549631 0.830977 -0.0859441 0.549628 0.9807 -0.0302059 0.193172 0.9807 -0.0302059 0.193172 0.554754 0.783379 0.280295 0.830977 0.523787 0.187412 0.830984 0.523778 0.187409 0.980698 0.184098 0.0658705 0.980701 0.184086 0.0658661 0.554779 -0.798504 0.233692 0.19509 -0.86828 0.456103 0.19473 -0.899418 0.391316 0.554783 -0.762916 0.331927 0.554782 -0.798502 0.233691 0.830976 -0.533912 0.156256 0.9807 -0.187649 0.0549178 0.9807 -0.179287 0.0780036 0.830975 -0.51012 0.221942 0.830975 -0.478281 0.284126 0.554778 -0.715301 0.42493 0.554776 -0.656404 0.511231 0.980699 -0.168099 0.0998605 0.980699 -0.154258 0.120141 0.830972 -0.438903 0.341833 0.830972 -0.392599 0.394147 0.554769 -0.587157 0.589473 0.554769 -0.508647 0.658414 0.194742 -0.599646 0.776209 0.195072 -0.532556 0.823609 0.9807 -0.137981 0.138525 0.9807 -0.119531 0.154726 0.830976 -0.340099 0.440239 0.830976 -0.282241 0.479394 0.554761 -0.422117 0.716978 0.554762 -0.328928 0.764229 0.9807 -0.119532 0.154727 0.9807 -0.0991966 0.168488 0.830981 -0.282237 0.479388 0.83098 -0.219929 0.510982 0.554775 -0.328924 0.764221 0.554774 -0.230548 0.799421 0.194734 -0.271796 0.942447 0.195099 -0.205376 0.95904 0.554779 0.0799279 0.82815 0.195049 0.29187 0.936359 0.194711 0.215851 0.956816 0.554768 0.183093 0.811609 0.55477 0.0799283 0.828156 0.83098 0.0534424 0.55373 0.9807 0.0187831 0.194616 0.980699 0.0430271 0.190728 0.830971 0.122424 0.542677 0.830971 0.189475 0.523054 0.55477 0.283371 0.78226 0.554769 0.37918 0.740576 0.980699 0.066593 0.183833 0.980699 0.0891087 0.174038 0.830981 0.25353 0.49517 0.830981 0.313592 0.459489 0.554766 0.46901 0.687215 0.554766 0.551443 0.623013 0.194748 0.650097 0.734471 0.195047 0.713945 0.672487 0.9807 0.110217 0.161495 0.9807 0.129589 0.146408 0.830969 0.36872 0.416576 0.83097 0.418023 0.367078 0.554784 0.62517 0.548979 0.55478 0.689047 0.466297 0.9807 0.129588 0.146407 0.9807 0.146917 0.129011 0.83098 0.418012 0.367068 0.830981 0.46072 0.311781 0.554794 0.68904 0.466291 0.554795 0.742048 0.376255 0.194713 0.874828 0.443581 0.195065 0.906215 0.375132 0.607968 -0.793519 0.0265005 0.554801 -0.831496 0.0284762 0.44157 -0.896727 0.0299473 0.194733 -0.98031 0.0327386 0.194727 -0.980311 0.0327386 0.980699 -0.193054 0.0309663 0.830976 -0.549286 0.0881068 0.830975 -0.549288 0.0881071 0.554778 -0.821497 0.13177 0.55478 -0.821496 0.13177 0.75191 -0.650945 0.104413 0.195047 -0.973664 0.118046 0.194725 -0.899419 0.391316 0.195079 -0.926723 0.321137 0.662128 -0.719222 0.210489 0.194877 -0.945097 0.262325 0.194962 -0.964347 0.178953 0.980699 -0.193054 0.0309663 0.980699 -0.18765 0.0549181 0.830974 -0.533916 0.156257 0.830974 -0.510122 0.221942 0.554784 -0.762915 0.331927 0.554784 -0.715298 0.424928 0.599476 -0.688129 0.408788 0.194727 -0.692205 0.694934 0.195025 -0.752295 0.6293 0.762144 -0.51077 0.397806 0.194989 -0.790329 0.580826 0.194844 -0.837969 0.509749 0.980699 -0.17929 0.078005 0.980699 -0.1681 0.099861 0.830978 -0.478277 0.284124 0.830979 -0.438895 0.341827 0.554784 -0.6564 0.511228 0.554783 -0.587151 0.589466 0.194752 -0.692201 0.694931 0.194754 -0.599645 0.776207 0.9807 -0.154253 0.120138 0.9807 -0.13798 0.138524 0.830973 -0.392597 0.394146 0.830973 -0.340103 0.440244 0.554763 -0.508649 0.658418 0.554764 -0.422116 0.716976 0.733555 -0.344808 0.585666 0.194739 -0.271796 0.942446 0.19508 -0.34648 0.917549 0.704864 -0.280433 0.651556 0.194923 -0.403422 0.894011 0.19495 -0.479803 0.855444 0.980699 -0.0991979 0.16849 0.980699 -0.0772984 0.179595 0.830974 -0.219933 0.510991 0.830975 -0.154154 0.534525 0.554782 -0.230547 0.799416 0.554783 -0.128535 0.822006 0.508108 -0.133061 0.850953 0.194806 -0.144761 0.9701 0.9807 -0.00575679 0.195435 0.83098 -0.0163795 0.556061 0.830976 -0.0163798 0.556067 0.55478 -0.0244971 0.831636 0.55477 -0.0244976 0.831643 0.765443 -0.0189474 0.643225 0.195008 -0.0596593 0.978985 0.194748 0.21585 0.956808 0.195112 0.148568 0.969463 0.508113 0.082742 0.857307 0.194824 0.0874087 0.976936 0.19502 0.00192996 0.980797 0.980699 -0.00575706 0.19544 0.980699 0.0187835 0.194621 0.830972 0.0534433 0.553741 0.830973 0.122424 0.542676 0.554784 0.183091 0.811599 0.554786 0.283368 0.78225 0.704868 0.241593 0.666929 0.194711 0.552921 0.810165 0.195042 0.483157 0.853533 0.733553 0.309738 0.604949 0.19494 0.428618 0.882205 0.19491 0.350101 0.916209 0.9807 0.0430261 0.190724 0.9807 0.0665909 0.183827 0.83098 0.189471 0.523042 0.830981 0.253531 0.49517 0.554778 0.379178 0.740571 0.554779 0.469005 0.687208 0.194737 0.552918 0.81016 0.194734 0.650098 0.734473 0.980698 0.0891103 0.174041 0.980698 0.110221 0.161501 0.830977 0.313595 0.459494 0.830978 0.368712 0.416566 0.554788 0.551433 0.623002 0.554787 0.625168 0.548977 0.762148 0.486466 0.427179 0.194715 0.874827 0.44358 0.195077 0.839928 0.506425 0.599456 0.662886 0.448593 0.194857 0.806509 0.558188 0.194997 0.754769 0.626338 0.980699 0.146918 0.129013 0.980699 0.161929 0.109582 0.830976 0.460726 0.311786 0.830976 0.496171 0.251583 0.554809 0.74204 0.37625 0.55481 0.783344 0.280281 0.662131 0.705583 0.252458 0.194818 0.928029 0.317503 0.195033 0.96503 0.175155 0.980701 0.19089 0.0422745 0.830971 0.543155 0.120287 0.830985 0.543136 0.120283 0.554798 0.812304 0.179893 0.554754 0.812333 0.1799 0.751893 0.643689 0.142552 0.194903 0.952153 0.235409 0.980682 0.194903 0.0166243 0.792795 0.606797 0.0572186 0.830971 0.553948 0.0512645 0.607961 0.790589 0.0731641 0.554819 0.828366 0.0773699 0.258358 0.962036 0.0879695 0.194718 0.976686 0.0903858 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.999899 0.0141847 0.0535616 -0.998008 0.0333296 -0.030031 -0.99441 0.101232 0 -0.992731 0.120358 0 -0.982246 0.1876 -0.0146278 -0.983109 0.182435 0.016382 -0.962028 0.272458 0 -0.963571 0.267453 0 -0.934747 0.355315 -0.0826058 -0.941647 0.326309 0.137846 -0.891628 0.431275 -0.0490671 -0.915867 0.398473 0 -0.88529 0.465039 0 -0.858846 0.512234 0.0243752 -0.854089 0.519555 -0.0195048 -0.810779 0.585027 0 -0.805796 0.592193 0 -0.75685 0.653589 -0.043845 -0.766285 0.641003 0.0595652 -0.695768 0.715793 0.0132589 -0.705652 0.708435 -0.00897354 -0.631831 0.775054 0.0582221 -0.610314 0.790017 -0.0304208 -0.561639 0.826823 0 -0.542987 0.839741 0 -0.487665 0.873031 -0.00487691 -0.489183 0.872168 0.005071 -0.409715 0.9122 0 -0.411312 0.911495 0 -0.328657 0.944449 -0.0729459 -0.352326 0.93303 0.116174 -0.243432 0.962935 -0.0311795 -0.276966 0.960374 0 -0.2094 0.97783 0 -0.159661 0.987172 0.0341152 -0.147503 0.988473 -0.0245731 -0.0729946 0.99703 0 -0.0608271 0.998148 0 0.0141847 0.999899 -0.0341156 0.00196659 0.999416 0.0436423 0.101182 0.99391 0 0.0891163 0.996021 0 0.15148 0.98846 -0.0163849 0.187574 0.982114 0.0613289 0.219649 0.973649 -0.0292495 0.272378 0.961746 0 0.297586 0.954695 0 0.355316 0.934746 0.00487684 0.356942 0.934114 -0.00468128 0.435427 0.900212 0 0.437002 0.899461 0 0.512234 0.858846 -0.0632617 0.491631 0.868503 0.0958688 0.582443 0.807199 -0.0148167 0.563648 0.825882 0.0105326 0.653553 0.756807 0.0473417 0.662043 0.747969 -0.028083 0.716783 0.696731 0 0.727926 0.685656 0 0.775085 0.631857 -0.0243771 0.769313 0.638407 0.0292407 0.826852 0.561659 0 0.822271 0.569096 0 0.856381 0.516345 -0.0222356 0.872814 0.487545 0.0628796 0.890133 0.451341 -0.026522 0.91189 0.409576 0 0.923964 0.382479 0 0.94445 0.328656 0.0146291 0.946057 0.323671 -0.0128727 0.96942 0.245071 0 0.97077 0.240012 0 0.987172 0.159663 -0.0535624 0.982512 0.178328 0.076985 0.994371 0.0728 0 0.995745 0.0921496 -0.202049 0.979306 -0.0116433 -0.202049 0.979306 -0.0116432 -0.202049 0.975 -0.0924739 -0.202048 0.975 -0.092474 -0.202211 0.969693 -0.137137 -0.148204 0.972654 -0.178831 -0.202049 0.964033 -0.172673 -0.202049 0.946481 -0.251692 -0.202048 0.946482 -0.251693 -0.202205 0.932532 -0.299159 -0.0930078 0.934696 -0.343065 -0.202046 0.922465 -0.328993 -0.202046 0.892146 -0.404046 -0.202049 0.892146 -0.404045 -0.202196 0.868506 -0.452563 -0.0930771 0.86996 -0.484258 -0.202139 0.849072 -0.488074 -0.202047 0.813475 -0.545377 -0.202046 0.813475 -0.545377 -0.202179 0.779458 -0.592932 -0.0806879 0.779234 -0.621518 -0.202166 0.754292 -0.624638 -0.202051 0.712613 -0.671832 -0.202048 0.712613 -0.671833 -0.202162 0.667954 -0.716217 -0.0806881 0.666308 -0.741298 -0.202184 0.637784 -0.743205 -0.202051 0.592314 -0.779961 -0.202043 0.592315 -0.779963 -0.202135 0.537207 -0.818872 -0.0930788 0.534626 -0.839947 -0.202199 0.502901 -0.840361 -0.202051 0.455858 -0.866815 -0.202047 0.455859 -0.866816 -0.202112 0.39098 -0.897934 -0.117734 0.388062 -0.914082 -0.202204 0.353532 -0.913306 -0.202046 0.306968 -0.930026 -0.202049 0.306968 -0.930025 -0.202084 0.233488 -0.951129 -0.154295 0.231142 -0.960607 -0.202208 0.19398 -0.959939 -0.202044 0.149704 -0.967867 -0.202049 0.149704 -0.967866 -0.202049 0.0692675 -0.976923 -0.202046 0.0692673 -0.976923 -0.202046 -0.0116431 -0.979307 -0.202043 -0.0116434 -0.979308 -0.202043 -0.0924741 -0.975001 -0.202045 -0.0924739 -0.975001 -0.202209 -0.137142 -0.969693 -0.148208 -0.178831 -0.972653 -0.202053 -0.172673 -0.964033 -0.202053 -0.251692 -0.946481 -0.202043 -0.251693 -0.946482 -0.2022 -0.299161 -0.932533 -0.0930049 -0.343065 -0.934696 -0.202055 -0.328991 -0.922463 -0.202056 -0.404045 -0.892144 -0.202049 -0.404046 -0.892145 -0.202196 -0.452563 -0.868506 -0.0930741 -0.484259 -0.86996 -0.202131 -0.488075 -0.849073 -0.202039 -0.545379 -0.813476 -0.202046 -0.545377 -0.813475 -0.202179 -0.592931 -0.779459 -0.0806779 -0.621518 -0.779235 -0.20216 -0.624639 -0.754293 -0.202045 -0.671833 -0.712614 -0.202054 -0.671831 -0.712613 -0.202169 -0.716216 -0.667955 -0.0806773 -0.7413 -0.666308 -0.202178 -0.743207 -0.637783 -0.202045 -0.779962 -0.592315 -0.202055 -0.77996 -0.592314 -0.202147 -0.81887 -0.537205 -0.0930794 -0.839948 -0.534625 -0.202197 -0.840362 -0.5029 -0.202049 -0.866815 -0.455859 -0.202047 -0.866816 -0.455859 -0.202112 -0.897934 -0.39098 -0.117726 -0.914084 -0.388062 -0.202194 -0.913308 -0.353533 -0.850908 0.525278 -0.00624509 -0.850907 0.525279 -0.00624518 -0.850907 0.522969 -0.0496011 -0.850908 0.522968 -0.0496008 -0.850908 0.517086 -0.0926178 -0.850908 0.517086 -0.0926178 -0.850908 0.507671 -0.135002 -0.850908 0.507671 -0.135002 -0.850908 0.494789 -0.176464 -0.850908 0.49479 -0.176464 -0.850908 0.478527 -0.216721 -0.850907 0.478528 -0.216721 -0.850907 0.458997 -0.255498 -0.850908 0.458996 -0.255497 -0.850908 0.436329 -0.292528 -0.850909 0.436327 -0.292527 -0.85091 0.41068 -0.327559 -0.850908 0.410682 -0.327561 -0.850908 0.38223 -0.360356 -0.850908 0.38223 -0.360356 -0.850908 0.351166 -0.390689 -0.850909 0.351165 -0.390688 -0.850909 0.317703 -0.418353 -0.850908 0.317704 -0.418354 -0.850908 0.282072 -0.443161 -0.850909 0.28207 -0.443159 -0.850909 0.244511 -0.464938 -0.850907 0.244513 -0.464942 -0.850907 0.205283 -0.483545 -0.850907 0.205283 -0.483546 -0.850907 0.164651 -0.498846 -0.850907 0.164651 -0.498846 -0.850907 0.122895 -0.510739 -0.850906 0.122895 -0.51074 -0.850906 0.0802982 -0.519145 -0.850907 0.0802981 -0.519143 -0.850907 0.0371534 -0.524 -0.850907 0.0371534 -0.524001 -0.850907 -0.00624519 -0.525279 -0.850909 -0.00624484 -0.525276 -0.850909 -0.0496007 -0.522966 -0.850907 -0.0496014 -0.522969 -0.850908 -0.0926177 -0.517087 -0.850906 -0.0926185 -0.51709 -0.850906 -0.135003 -0.507675 -0.850909 -0.135001 -0.507669 -0.850909 -0.176463 -0.494787 -0.850909 -0.176464 -0.494788 -0.850909 -0.21672 -0.478526 -0.850907 -0.216722 -0.478528 -0.850907 -0.255498 -0.458997 -0.850907 -0.255498 -0.458997 -0.850907 -0.292529 -0.436331 -0.850907 -0.292529 -0.43633 -0.850907 -0.327562 -0.410683 -0.850909 -0.327559 -0.41068 -0.85091 -0.360353 -0.382228 -0.850904 -0.36036 -0.382234 -0.850904 -0.390694 -0.35117 -0.850905 -0.390692 -0.351169 -0.850905 -0.418358 -0.317706 -0.850909 -0.418352 -0.317703 -0.850909 -0.443159 -0.282071 -0.850907 -0.443162 -0.282072 -0.850907 -0.464942 -0.244513 -0.850905 -0.464944 -0.244514 -0.850905 -0.483548 -0.205284 -0.850904 -0.483549 -0.205284 -0.850904 -0.49885 -0.164652 -0.85091 -0.498841 -0.16465 -0.85091 -0.510734 -0.122894 -0.850903 -0.510745 -0.122895 -0.57326 0.819316 -0.00974105 -0.573261 0.819315 -0.00974093 -0.573261 0.815712 -0.0773664 -0.57326 0.815713 -0.0773664 -0.57326 0.806538 -0.144463 -0.57326 0.806538 -0.144463 -0.57326 0.791854 -0.210573 -0.57326 0.791853 -0.210573 -0.57326 0.77176 -0.275244 -0.57326 0.77176 -0.275244 -0.57326 0.746394 -0.338036 -0.573261 0.746394 -0.338035 -0.573261 0.71593 -0.398518 -0.57326 0.71593 -0.398518 -0.57326 0.680576 -0.456278 -0.573257 0.680577 -0.456279 -0.573257 0.640574 -0.510923 -0.573259 0.640573 -0.510921 -0.573259 0.596193 -0.562075 -0.57326 0.596193 -0.562074 -0.57326 0.547741 -0.609387 -0.573257 0.547742 -0.609389 -0.573257 0.495548 -0.65254 -0.573261 0.495547 -0.652537 -0.573261 0.439968 -0.691231 -0.573258 0.439969 -0.691233 -0.573257 0.381385 -0.725204 -0.57326 0.381384 -0.725203 -0.57326 0.320195 -0.75422 -0.573263 0.320194 -0.754218 -0.573264 0.256818 -0.778083 -0.573258 0.256818 -0.778087 -0.573258 0.191687 -0.796638 -0.573263 0.191687 -0.796634 -0.573264 0.125246 -0.809742 -0.57326 0.125246 -0.809744 -0.57326 0.0579509 -0.817322 -0.57326 0.0579509 -0.817322 -0.573259 -0.00974121 -0.819316 -0.573261 -0.00974108 -0.819315 -0.573261 -0.0773661 -0.815712 -0.57326 -0.0773664 -0.815713 -0.57326 -0.144463 -0.806538 -0.573262 -0.144462 -0.806536 -0.573262 -0.210573 -0.791852 -0.573264 -0.210573 -0.791851 -0.573264 -0.275243 -0.771757 -0.573256 -0.275246 -0.771762 -0.573255 -0.338038 -0.746397 -0.573261 -0.338035 -0.746394 -0.573261 -0.398518 -0.715929 -0.573266 -0.398516 -0.715927 -0.573266 -0.456276 -0.680572 -0.573263 -0.456277 -0.680574 -0.573263 -0.51092 -0.640571 -0.573261 -0.510921 -0.640572 -0.573261 -0.562073 -0.596192 -0.573265 -0.562071 -0.596191 -0.573264 -0.609386 -0.547738 -0.57327 -0.609382 -0.547736 -0.57327 -0.652532 -0.495543 -0.573253 -0.652543 -0.49555 -0.573253 -0.691236 -0.43997 -0.573268 -0.691226 -0.439966 -0.573268 -0.725197 -0.381382 -0.57326 -0.725203 -0.381384 -0.57326 -0.754221 -0.320194 -0.573264 -0.754218 -0.320193 -0.573265 -0.778083 -0.256817 -0.573258 -0.778088 -0.256818 -0.573258 -0.796637 -0.191688 -0.573258 -0.796637 -0.191688 -0.202037 -0.930027 -0.306969 -0.202031 -0.930029 -0.306969 -0.202065 -0.951132 -0.233489 -0.154283 -0.960609 -0.231144 -0.202224 -0.95994 -0.19396 -0.850905 -0.519146 -0.0802995 -0.850903 -0.519149 -0.0802996 -0.573265 -0.809741 -0.125247 -0.573258 -0.809746 -0.125247 -0.202049 -0.967866 -0.149704 -0.202061 -0.967864 -0.149705 -0.850915 -0.523988 -0.0371525 -0.850905 -0.524004 -0.0371521 -0.573241 -0.817335 -0.0579493 -0.573266 -0.817318 -0.0579506 -0.202046 -0.976923 -0.0692672 -0.202049 -0.976923 -0.0692674 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.997639 0.0686726 0 -0.997639 0.0686726 0 -0.965073 0.261983 0 -0.965073 0.261983 0 -0.895419 0.445225 0 -0.895419 0.445225 0 -0.791354 0.611358 0 -0.791354 0.611358 0 -0.656879 0.753996 0 -0.656879 0.753996 0 -0.49716 0.867659 0 -0.49716 0.867659 0 -0.318335 0.947978 0 -0.318335 0.947978 0 -0.127277 0.991867 0 -0.127277 0.991867 0 0.0686726 0.997639 0 0.0686726 0.997639 0 0.261983 0.965073 0 0.261983 0.965073 0 0.445225 0.895419 0 0.445225 0.895419 0 0.611358 0.791354 0 0.611358 0.791354 0 0.753996 0.656879 0 0.753996 0.656879 0 0.867659 0.497159 0 0.867659 0.497159 0 0.947978 0.318335 0 0.947978 0.318335 0 0.991867 0.127277 0 0.991867 0.127277 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.991867 0.127277 0 0.991867 0.127277 0 0.947978 0.318335 0 0.947978 0.318335 0 0.867659 0.49716 0 0.867659 0.49716 0 0.753996 0.656879 0 0.753996 0.656879 0 0.611358 0.791354 0 0.611358 0.791354 0 0.445225 0.895419 0 0.445225 0.895419 0 0.261983 0.965073 0 0.261983 0.965073 0 0.0686727 0.997639 0 0.0686727 0.997639 0 -0.127277 0.991867 0 -0.127277 0.991867 0 -0.318335 0.947978 0 -0.318335 0.947978 0 -0.497159 0.867659 0 -0.497159 0.867659 0 -0.656879 0.753996 0 -0.656879 0.753996 0 -0.791354 0.611358 0 -0.791354 0.611358 0 -0.895419 0.445225 0 -0.895419 0.445225 0 -0.965073 0.261983 0 -0.965073 0.261983 0 -0.997639 0.0686726 0 -0.997639 0.0686726 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.992586 0.121547 0 0.992586 0.121547 0 0.953351 0.301864 0 0.953351 0.301864 0 0.881651 0.471902 0 0.881651 0.471902 0 0.779927 0.62587 0 0.779927 0.62587 0 0.651644 0.758525 0 0.651644 0.758525 0 0.50117 0.865349 0 0.50117 0.865349 0 0.333629 0.942704 0 0.333629 0.942704 0 0.154727 0.987957 0 0.154727 0.987957 0 -0.0294438 0.999566 0 -0.0294438 0.999566 0 -0.212612 0.977137 0 -0.212612 0.977137 0 -0.38854 0.921432 0 -0.38854 0.921432 0 -0.551238 0.834348 0 -0.551238 0.834348 0 -0.695163 0.718852 0 -0.695163 0.718852 0 -0.815415 0.578877 0 -0.815415 0.578877 0 -0.907899 0.419188 0 -0.907899 0.419188 0 -0.969466 0.245224 0 -0.969466 0.245224 0 -0.998019 0.0629099 0 -0.998019 0.0629099 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.998329 0.0577862 0 -0.998329 0.0577862 0 -0.973128 0.230266 0 -0.973128 0.230266 0 -0.918358 0.39575 0 -0.918358 0.39575 0 -0.835685 0.549209 0 -0.835685 0.549209 0 -0.72762 0.68598 0 -0.72762 0.68598 0 -0.597447 0.801909 0 -0.597447 0.801909 0 -0.44912 0.893471 0 -0.44912 0.893471 0 -0.287147 0.957886 0 -0.287147 0.957886 0 -0.11645 0.993197 0 -0.11645 0.993197 0 0.0577864 0.998329 0 0.0577864 0.998329 0 0.230266 0.973128 0 0.230266 0.973128 0 0.39575 0.918358 0 0.39575 0.918358 0 0.549209 0.835685 0 0.549209 0.835685 0 0.68598 0.72762 0 0.68598 0.72762 0 0.801909 0.597447 0 0.801909 0.597447 0 0.893471 0.449121 0 0.893471 0.449121 0 0.957887 0.287146 0 0.957887 0.287146 0 0.993196 0.116451 0 0.993196 0.116451 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.980188 0.198069 -0.01122 0.993134 0.116442 -0.100448 0.98325 0.152084 0 0.997496 0.0707257 0 0.93257 0.360989 -0.0211925 0.957671 0.287083 -0.0844681 0.946217 0.312312 0 0.971165 0.238407 0 0.836131 0.548529 0 0.858085 0.513508 -0.0299152 0.893071 0.448919 -0.0696533 0.88292 0.464328 0 0.916856 0.399219 -0.0560291 0.795136 0.603838 -0.0373873 0.801348 0.597029 0 0.758878 0.651232 0 0.637807 0.770196 -0.0436111 0.685328 0.726928 -0.04361 0.685328 0.726928 0 0.731317 0.682038 0 0.462111 0.886822 0 0.498362 0.866969 -0.0485863 0.54856 0.834698 -0.0324147 0.556569 0.830169 0 0.605435 0.795895 -0.0224503 0.41245 0.910704 -0.0523167 0.395208 0.917101 0 0.344558 0.938765 0 0.140028 0.990148 0 0.180828 0.983515 -0.0548017 0.22992 0.971665 -0.0137229 0.256968 0.966322 0 0.305471 0.952201 -0.00623826 0.0944196 0.995513 -0.0560442 0.0576953 0.99676 0 0.0118883 0.999929 0 -0.238407 0.971165 0 -0.198066 0.980189 -0.0112196 -0.116442 0.993134 -0.100449 -0.152084 0.98325 0 -0.0707254 0.997496 -0.0844672 -0.312312 0.946217 -0.0211919 -0.287083 0.957671 0 -0.360987 0.932571 0 -0.513507 0.858085 -0.0299148 -0.448919 0.893072 -0.0696536 -0.464328 0.88292 0 -0.399219 0.916856 0 -0.682037 0.731317 0 -0.651232 0.758879 -0.0373868 -0.597029 0.801348 -0.056029 -0.603838 0.795135 0 -0.54853 0.836131 -0.0436101 -0.726927 0.685328 -0.0436113 -0.726928 0.685328 0 -0.770196 0.637807 0 -0.886823 0.46211 0 -0.866969 0.498362 -0.0485858 -0.834698 0.54856 -0.032414 -0.830169 0.556569 0 -0.795896 0.605433 -0.02245 -0.910704 0.41245 -0.0523165 -0.917101 0.395208 0 -0.938765 0.344558 0 -0.990148 0.140028 0 -0.983514 0.180829 -0.0548015 -0.971665 0.229921 -0.0137237 -0.966322 0.256968 0 -0.952201 0.305473 -0.00623846 -0.995513 0.0944181 -0.0560423 -0.99676 0.0576953 0 -0.999929 0.0118898 0 -0.997639 0.0686727 0 -0.997639 0.0686727 0 -0.965073 0.261983 0 -0.965073 0.261983 0 -0.895419 0.445225 0 -0.895419 0.445225 0 -0.791354 0.611358 0 -0.791354 0.611358 0 -0.656879 0.753996 0 -0.656879 0.753996 0 -0.497159 0.867659 0 -0.497159 0.867659 0 -0.318335 0.947978 0 -0.318335 0.947978 0 -0.127277 0.991867 0 -0.127277 0.991867 0 0.0686725 0.997639 0 0.0686725 0.997639 0 0.261983 0.965073 0 0.261983 0.965073 0 0.445226 0.895418 0 0.445226 0.895418 0 0.611358 0.791354 0 0.611358 0.791354 0 0.753996 0.656879 0 0.753996 0.656879 0 0.867659 0.497159 0 0.867659 0.497159 0 0.947978 0.318335 0 0.947978 0.318335 0 0.991867 0.127277 0 0.991867 0.127277 0 -0.998019 0.0629102 0 -0.998019 0.0629102 0 -0.969466 0.245224 0 -0.969466 0.245224 0 -0.907899 0.419188 0 -0.907899 0.419188 0 -0.815415 0.578877 0 -0.815415 0.578877 0 -0.695163 0.718852 0 -0.695163 0.718852 0 -0.551238 0.834348 0 -0.551238 0.834348 0 -0.388541 0.921432 0 -0.388541 0.921432 0 -0.212612 0.977137 0 -0.212612 0.977137 0 -0.0294439 0.999566 0 -0.0294439 0.999566 0 0.154727 0.987957 0 0.154727 0.987957 0 0.33363 0.942704 0 0.33363 0.942704 0 0.50117 0.865349 0 0.50117 0.865349 0 0.651644 0.758525 0 0.651644 0.758525 0 0.779927 0.62587 0 0.779927 0.62587 0 0.881651 0.471902 0 0.881651 0.471902 0 0.953351 0.301864 0 0.953351 0.301864 0 0.992586 0.121546 0 0.992586 0.121546 0 -0.998019 0.0629102 0 -0.998019 0.0629102 0 -0.969466 0.245224 0 -0.969466 0.245224 0 -0.907899 0.419188 0 -0.907899 0.419188 0 -0.815415 0.578877 0 -0.815415 0.578877 0 -0.695163 0.718852 0 -0.695163 0.718852 0 -0.551238 0.834348 0 -0.551238 0.834348 0 -0.388541 0.921432 0 -0.388541 0.921432 0 -0.212612 0.977137 0 -0.212612 0.977137 0 -0.0294439 0.999566 0 -0.0294439 0.999566 0 0.154727 0.987957 0 0.154727 0.987957 0 0.33363 0.942704 0 0.33363 0.942704 0 0.50117 0.865349 0 0.50117 0.865349 0 0.651644 0.758525 0 0.651644 0.758525 0 0.779927 0.62587 0 0.779927 0.62587 0 0.881651 0.471902 0 0.881651 0.471902 0 0.953351 0.301864 0 0.953351 0.301864 0 0.992586 0.121546 0 0.992586 0.121546 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.705876 -0.682897 -0.188126 0.705874 -0.682899 -0.188127 0.705873 -0.642298 -0.298658 0.705875 -0.642296 -0.298657 0.705875 -0.583946 -0.400934 0.705872 -0.583948 -0.400935 0.705872 -0.50946 -0.492133 0.705877 -0.509456 -0.49213 0.705876 -0.420891 -0.569728 0.705877 -0.42089 -0.569727 0.705877 -0.320693 -0.631581 0.705874 -0.320694 -0.631583 0.705873 -0.211634 -0.675984 0.70588 -0.211632 -0.675978 0.705881 -0.0967241 -0.701695 0.705873 -0.0967256 -0.701703 0.705873 0.0208559 -0.708031 0.705874 0.0208559 -0.708031 0.705874 0.137861 -0.694792 0.705881 0.13786 -0.694786 0.70588 0.251055 -0.662348 0.705875 0.251056 -0.662352 0.705875 0.357314 -0.61161 0.705875 0.357314 -0.61161 0.705875 0.453697 -0.543966 0.705874 0.453698 -0.543967 0.705874 0.537543 -0.461291 0.705875 0.537543 -0.461291 0.705875 0.606533 -0.365867 0.705874 0.606534 -0.365867 0.705874 0.658763 -0.260332 0.705874 0.658763 -0.260332 0.705874 0.692788 -0.147604 0.705874 0.692788 -0.147604 0.705874 0.682898 0.188127 0.705874 0.682899 0.188127 0.705874 0.642297 0.298657 0.705876 0.642295 0.298656 0.705876 0.583944 0.400933 0.705876 0.583944 0.400933 0.705877 0.509457 0.49213 0.705875 0.509458 0.492131 0.705875 0.420891 0.569729 0.70587 0.420894 0.569733 0.705871 0.320696 0.631586 0.705872 0.320695 0.631585 0.705872 0.211634 0.675985 0.705874 0.211634 0.675983 0.705874 0.0967255 0.701703 0.705873 0.0967256 0.701703 0.705873 -0.0208563 0.708031 0.705874 -0.0208563 0.70803 0.705874 -0.137861 0.694792 0.705871 -0.137862 0.694795 0.705871 -0.251058 0.662357 0.705874 -0.251057 0.662354 0.705873 -0.357315 0.611612 0.705872 -0.357315 0.611614 0.705872 -0.453699 0.543969 0.705872 -0.453699 0.543969 0.705872 -0.537545 0.461292 0.705872 -0.537545 0.461292 0.705872 -0.606535 0.365868 0.705876 -0.606532 0.365866 0.705876 -0.658761 0.260331 0.705876 -0.658761 0.260332 0.705876 -0.692786 0.147603 0.70587 -0.692792 0.147604 -0.422559 -0.885804 -0.191822 -0.413976 -0.890542 -0.188571 -0.422623 -0.889961 -0.171344 -0.422526 -0.896205 0.135235 -0.411769 -0.900452 0.140115 -0.422614 -0.89851 0.118644 -0.422527 0.896204 -0.135238 -0.411777 0.900448 -0.140115 -0.422615 0.898508 -0.118658 -0.42256 0.885802 0.191827 -0.413966 0.890546 0.188572 -0.422615 0.889966 0.17134 -0.93985 0.336283 0.0599691 -0.939677 0.336255 0.0627664 -0.939714 0.336183 0.0626028 -0.939701 0.33622 0.0626013 -0.939762 0.336214 0.0617047 -0.939691 0.335929 0.064289 -0.940694 0.333129 0.0641832 -0.940495 0.333679 0.0642413 -0.939737 0.336037 0.063039 -0.940046 0.336155 0.0575682 -0.940591 0.335305 0.0534644 -0.940962 0.334535 0.0517441 -0.939576 0.341367 0.0257968 -0.938802 0.343594 0.024362 -0.93981 0.339072 0.0422899 -0.94012 0.337665 0.0464381 -0.940386 0.31883 0.118412 -0.940248 0.319206 0.118496 -0.939699 0.321252 0.117318 -0.939685 0.321357 0.11714 -0.939728 0.321285 0.116993 -0.939779 0.321001 0.117363 -0.939728 0.320994 0.117787 -0.939825 0.321415 0.115853 -0.939975 0.321506 0.114375 -0.940231 0.321574 0.112048 -0.940765 0.320896 0.109483 -0.941077 0.320458 0.108082 -0.942097 0.318762 0.104132 -0.941616 0.319724 0.105529 -0.940188 0.325751 0.099662 -0.939767 0.327901 0.0965296 -0.93909 0.334134 0.0803995 -0.944609 0.317196 0.0842667 -0.942943 0.322637 0.0822369 -0.941633 0.326901 0.0804004 -0.940548 0.330709 0.0774651 -0.939668 0.334141 0.0733061 -0.940358 0.332898 0.0700459 -0.939669 0.334305 0.0725465 -0.939728 0.332662 0.0790433 -0.93975 0.332608 0.0790084 -0.939553 0.334554 0.0729009 -0.941745 0.328711 0.0711716 -0.941625 0.329035 0.0712549 -0.939671 0.332867 0.0788561 -0.939854 0.332435 0.0784967 -0.939888 0.227133 0.254992 -0.939793 0.226375 0.256014 -0.941378 0.232933 0.24403 -0.942082 0.230067 0.244032 -0.941333 0.229876 0.247082 -0.94027 0.228748 0.252122 -0.943023 0.242535 0.22778 -0.937987 0.257828 0.231746 -0.939927 0.240884 0.241894 -0.94029 0.238089 0.243245 -0.940636 0.255585 0.223337 -0.939629 0.256473 0.226537 -0.939726 0.248572 0.234792 -0.939748 0.248542 0.234734 -0.939425 0.256695 0.227131 -0.943049 0.249418 0.220112 -0.942938 0.24965 0.220325 -0.939669 0.248845 0.234732 -0.939853 0.248649 0.234202 -0.939695 0.219567 0.26223 -0.946017 0.190691 0.262084 -0.939783 0.219272 0.262161 -0.940313 0.200194 0.275199 -0.942724 0.199499 0.267342 -0.926974 0.208893 0.31158 -0.941577 0.213076 0.26083 -0.939972 0.212788 0.266785 -0.939696 0.223353 0.259008 -0.939687 0.225244 0.257396 -0.940169 0.0801931 0.331137 -0.941592 0.0865438 0.325445 -0.944467 0.0986179 0.313459 -0.932765 0.121095 0.339538 -0.941174 0.0886649 0.326082 -0.942146 0.0850179 0.324242 -0.940908 0.113732 0.318995 -0.939568 0.11336 0.32305 -0.939724 0.0978756 0.327627 -0.939753 0.0978797 0.327543 -0.939276 0.113342 0.323905 -0.944291 0.109105 0.310502 -0.944186 0.1092 0.310786 -0.93967 0.0981522 0.327698 -0.93984 0.0982402 0.327184 -0.939693 0.05904 0.336885 -0.945381 0.0367661 0.323887 -0.939791 0.0587819 0.336656 -0.940233 0.0404339 0.338123 -0.939493 0.0387723 0.340367 -0.939104 0.0391979 0.341389 -0.945483 0.0367291 0.323594 -0.939731 0.05933 0.336729 -0.939681 0.0592247 0.336886 -0.942138 0.0436899 0.332368 -0.94338 0.0451501 0.328626 -0.932837 0.0340197 0.358688 -0.94084 0.0586952 0.33373 -0.941423 0.0604364 0.331769 -0.942236 0.0619408 0.329173 -0.942779 0.0628706 0.327437 -0.940603 0.0598586 0.334191 -0.93964 0.0730092 0.334284 -0.939757 0.0769514 0.333071 -0.941633 -0.0804003 0.326901 -0.931736 -0.0555078 0.358869 -0.941161 -0.0563465 0.33323 -0.939487 -0.058747 0.337509 -0.939732 -0.0790203 0.332656 -0.939751 -0.07899 0.332609 -0.939105 -0.0592244 0.338489 -0.945477 -0.0557161 0.320888 -0.945387 -0.0557638 0.321144 -0.939678 -0.0788485 0.332849 -0.939868 -0.0784755 0.3324 -0.944295 -0.127188 0.303529 -0.944183 -0.127307 0.303827 -0.939699 -0.117341 0.321244 -0.939682 -0.117119 0.321375 -0.939724 -0.116975 0.321304 -0.939777 -0.117358 0.321009 -0.940132 -0.129863 0.315099 -0.941534 -0.124942 0.312894 -0.942479 -0.122244 0.31111 -0.942792 -0.121372 0.310503 -0.936863 -0.136655 0.32189 -0.940309 -0.111677 0.321476 -0.940765 -0.109485 0.320896 -0.941077 -0.108079 0.320457 -0.942097 -0.104132 0.318762 -0.941616 -0.105529 0.319724 -0.940188 -0.0996615 0.325751 -0.939768 -0.0965317 0.3279 -0.939691 -0.0943237 0.32876 -0.939622 -0.0800585 0.332717 -0.944196 -0.0837603 0.318556 -0.942943 -0.0822366 0.322638 -0.946013 -0.205795 0.250414 -0.939658 -0.234765 0.248853 -0.939848 -0.234217 0.248651 -0.941393 -0.211425 0.262829 -0.939384 -0.216167 0.26614 -0.964079 -0.153102 0.217053 -0.939001 -0.218699 0.26542 -0.946114 -0.205606 0.25019 -0.939728 -0.234792 0.248565 -0.939737 -0.234767 0.248552 -0.943049 -0.261941 0.205048 -0.942941 -0.262179 0.205243 -0.939698 -0.262222 0.21956 -0.939685 -0.262122 0.219737 -0.939727 -0.261961 0.219748 -0.93979 -0.262181 0.219216 -0.940012 -0.267426 0.211804 -0.940924 -0.263328 0.212885 -0.941575 -0.260836 0.213075 -0.942492 -0.257366 0.213239 -0.93861 -0.269699 0.215112 -0.939793 -0.256017 0.226374 -0.939888 -0.254991 0.227133 -0.941378 -0.24403 0.232933 -0.942082 -0.244032 0.230067 -0.941333 -0.247083 0.229876 -0.94027 -0.252123 0.228748 -0.93969 -0.336885 0.0590797 -0.941633 -0.332638 0.0517603 -0.939766 -0.336676 0.0590617 -0.941282 -0.332216 0.0601769 -0.940709 -0.334174 0.0582618 -0.939684 -0.336886 0.0591719 -0.939741 -0.336707 0.0592917 -0.94175 -0.332317 0.0516978 -0.939552 -0.338266 0.0530834 -0.939673 -0.337985 0.0527302 -0.939874 -0.337181 0.0542803 -0.94033 -0.335473 0.0569043 -0.94224 -0.32916 0.0619481 -0.942777 -0.327444 0.0628675 -0.940603 -0.334191 0.0598584 -0.944493 -0.319034 0.0784307 -0.940988 -0.327074 0.0869769 -0.939757 -0.333069 0.0769549 -0.93964 -0.334284 0.0730093 -0.941845 -0.324898 0.0858496 -0.940413 -0.327406 0.0918116 -0.9399 -0.32776 0.0957201 -0.939687 -0.327156 0.099782 -0.939724 -0.327635 0.097846 -0.93976 -0.327531 0.0978511 -0.939659 -0.327307 0.099551 -0.940395 -0.325223 0.099436 -0.940244 -0.325638 0.0995032 -0.93967 -0.3277 0.0981491 -0.939837 -0.327195 0.0982355 -0.939598 -0.342256 0.00406923 -0.938904 -0.344134 0.00568866 -0.940223 -0.339038 0.0321561 -0.942583 -0.333018 0.0252183 -0.940992 -0.336953 0.0315732 -0.940251 -0.338579 0.0359538 -0.940495 -0.336882 0.0444838 -0.939676 -0.339348 0.0430377 -0.940011 -0.338391 0.0432463 -0.939974 -0.33906 0.0385643 -0.939849 -0.33923 0.0400716 -0.939688 -0.339289 0.0432338 -0.940105 -0.337977 0.0444284 -0.940668 -0.336404 0.0444615 -0.939675 -0.339393 0.0427028 -0.939748 -0.339187 0.0427235 -0.939752 -0.327483 0.0980886 -0.939691 -0.327134 0.0998204 -0.939599 -0.322388 0.114979 -0.938046 -0.32381 0.123358 -0.940362 -0.309878 0.140341 -0.939671 -0.308521 0.147762 -0.939599 -0.299067 0.166474 -0.939163 -0.299075 0.168898 -0.939988 -0.283409 0.190006 -0.939625 -0.28306 0.192309 -0.939634 -0.269356 0.211033 -0.939425 -0.269619 0.211628 -0.94014 -0.243137 0.238792 -0.939662 -0.240396 0.243403 -0.939771 -0.228492 0.254208 -0.941313 -0.228163 0.248742 -0.930359 -0.221744 0.291994 -0.939372 -0.216796 0.265669 -0.939599 -0.183789 0.288749 -0.938156 -0.180043 0.295717 -0.940362 -0.158338 0.30108 -0.939668 -0.153161 0.305887 -0.939574 -0.132178 0.3158 -0.939276 -0.132211 0.316672 -0.942895 -0.0640801 0.32687 -0.939477 -0.0595246 0.3374 -0.939599 -0.0242079 0.341421 -0.941836 -0.0350566 0.33424 -0.934773 0.00422339 0.355221 -0.940342 -0.0100177 0.340084 -0.93969 0.015591 0.341673 -0.942105 0.1046 0.318586 -0.939562 0.112627 0.323324 -0.939599 0.141208 0.311793 -0.940951 0.133492 0.311113 -0.937335 0.169466 0.304441 -0.939486 0.160624 0.302599 -0.939391 0.200111 0.278389 -0.964078 0.140062 0.225689 -0.939001 0.202697 0.277833 -0.946112 0.190525 0.261861 -0.939725 0.219763 0.261957 -0.93968 0.219752 0.262125 -0.941312 0.248742 0.228162 -0.939626 0.255962 0.227128 -0.939599 0.272586 0.207006 -0.940026 0.270375 0.207964 -0.939068 0.289976 0.18457 -0.939568 0.287682 0.185608 -0.939599 0.30294 0.159316 -0.941047 0.29596 0.163824 -0.937104 0.321296 0.136402 -0.939476 0.312434 0.140605 -0.939691 0.320693 0.118898 -0.939659 0.320879 0.118646 0 -0.938917 -0.344143 0 0.789248 -0.614075 0 0.988805 -0.149211 0 0.988805 -0.149211 0.211514 0.951111 -0.225056 0.00594406 0.978031 -0.208377 0.188717 0.745244 -0.639529 0 0.634919 -0.772579 0 0.57795 -0.816072 0.010914 0.63262 -0.774386 0.0934761 0.637706 -0.764587 0 0.693874 -0.720096 0 0.735476 -0.677551 0.189516 0.348008 -0.918136 0 0.309748 -0.950819 0 0.252643 -0.96756 0.158227 0.192175 -0.968521 0 0.171348 -0.985211 0 -0.113059 -0.993588 0 -0.113059 -0.993588 0.158228 -0.134832 -0.978153 0 -0.332774 -0.943006 0 -0.332775 -0.943006 0.189517 -0.293361 -0.937029 0 -0.253243 -0.967403 0 -0.195252 -0.980753 0.0934769 -0.591595 -0.800798 0 -0.588342 -0.808612 0 -0.751734 -0.659467 0 -0.751734 -0.659467 0.188717 -0.706308 -0.682287 0 -0.694319 -0.719667 0 -0.650285 -0.75969 0 -0.978308 -0.207156 0 -0.978308 -0.207156 0.155782 -0.952316 -0.262347 0.00432643 -0.957877 -0.287146 0 -0.938917 -0.344143 0 -0.906767 -0.421632 0.0507845 -0.912389 -0.406162 0 -0.876603 -0.481215 0 -0.82439 -0.566022 0.0992311 -0.838032 -0.536522 0 -0.794459 -0.607318 0.0109147 -0.585941 -0.81028 0 -0.528909 -0.848679 0 -0.452742 -0.891642 0.0619678 -0.469622 -0.88069 0 -0.395558 -0.918441 0 -0.0458559 -0.998948 0.0221248 0.0294363 -0.999322 0.0221244 0.0294362 -0.999322 0 0.104575 -0.994517 0 0.171348 -0.985211 0 0.52165 -0.85316 0.0470995 0.503881 -0.862488 0 0.448932 -0.893566 0 0.387705 -0.921784 0 0.387705 -0.921784 0 0.789248 -0.614075 0 0.828829 -0.559502 0.0610584 0.854681 -0.515551 0 0.957525 -0.288349 0 0.957525 -0.288349 0 0.935922 -0.352207 0.0407987 0.929239 -0.36722 0 0.903409 -0.42878 0 0.872466 -0.488675 0 -0.104581 0.994516 0 0.938893 0.344209 0 -0.789248 0.614074 0 -0.988806 0.149208 0 -0.988806 0.149208 0.211524 -0.951108 0.225057 0.0059407 -0.978031 0.208376 0.188718 -0.745244 0.639528 0 -0.634919 0.772579 0 -0.577948 0.816074 0.0109145 -0.63262 0.774386 0.0934743 -0.637706 0.764587 0 -0.693873 0.720097 0 -0.735476 0.67755 0.189521 -0.348007 0.918136 0 -0.171347 0.985211 0 -0.171347 0.985211 0.158234 -0.192175 0.96852 0 -0.252645 0.967559 0 -0.309746 0.950819 0.158232 0.134833 0.978153 0 0.332775 0.943006 0 0.332775 0.943006 0.18952 0.293361 0.937028 0 0.253242 0.967403 0 0.195254 0.980753 0.0934733 0.591595 0.800798 0 0.588342 0.808612 0 0.751734 0.659467 0 0.751734 0.659467 0.188718 0.706308 0.682287 0 0.694319 0.719668 0 0.650283 0.759692 0 0.978308 0.207156 0 0.978308 0.207156 0.155782 0.952316 0.262347 0.00433166 0.957877 0.287145 0 0.938893 0.344209 0 0.906767 0.421631 0.0507836 0.912389 0.406161 0 0.876604 0.481213 0 0.82439 0.566022 0.0992316 0.838032 0.536522 0 0.794459 0.607318 0.0109147 0.585941 0.81028 0 0.528909 0.848679 0 0.452742 0.891642 0.0619702 0.469622 0.88069 0 0.395556 0.918442 0.0221264 -0.0294363 0.999322 0.0221249 -0.0294368 0.999322 0 0.0458559 0.998948 0 0.113059 0.993588 0 0.113059 0.993588 0 -0.52165 0.85316 0.0471004 -0.503881 0.862488 0 -0.448931 0.893566 0 -0.387705 0.921783 0 -0.387705 0.921783 0 -0.789248 0.614074 0 -0.828828 0.559503 0.06106 -0.85468 0.515552 0 -0.957539 0.288304 0 -0.957539 0.288304 0 -0.935923 0.352206 0.0407999 -0.929239 0.36722 0 -0.903408 0.428782 0 -0.872466 0.488675 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.851304 0.507858 0.131761 0.853125 0.385247 0.351798 0.854595 0.175404 0.488774 0.855727 -0.0730471 0.512246 0.856529 -0.30316 0.417675 0.851305 -0.514733 0.101638 0.857008 -0.462478 0.22727 0.853125 -0.405286 0.328512 0.854595 -0.203871 0.477602 0.855727 0.0427694 0.515657 0.856529 0.278046 0.434798 0.857007 0.448304 0.254091 0 0.967954 0.25113 -0.0044255 0.957878 0.287143 0 0.869979 0.493089 0 0.738437 0.674322 -0.00738993 0.685961 0.727601 0 0.538745 0.842469 0 0.337773 0.941227 -0.00887589 0.230257 0.973089 0 0.0826578 0.996578 0 -0.141174 0.989985 -0.00887601 -0.287136 0.957849 0 -0.392592 0.919713 0 -0.587406 0.809293 -0.00738965 -0.7276 0.685962 0 -0.776847 0.629689 0 -0.897487 0.441042 -0.00442583 -0.973118 0.230264 0 -0.981057 0.193717 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.851305 0.507858 0.131761 0.853125 0.385247 0.351798 0.854595 0.175404 0.488774 0.855727 -0.0730471 0.512246 0.856529 -0.303158 0.417676 0.851305 -0.514733 0.101638 0.857007 -0.462479 0.227271 0.853125 -0.405288 0.328511 0.854595 -0.20387 0.477602 0.855727 0.0427694 0.515657 0.856529 0.278048 0.434796 0.857008 0.448299 0.254098 0 0.967953 0.25113 -0.00442582 0.957877 0.287146 0 0.869971 0.493104 0 0.738437 0.674322 -0.00738974 0.685962 0.7276 0 0.53875 0.842466 0 0.337773 0.941227 -0.00887589 0.230257 0.973089 0 0.0826578 0.996578 0 -0.141174 0.989985 -0.00887596 -0.287136 0.957849 0 -0.392591 0.919713 0 -0.587403 0.809295 -0.00738987 -0.727601 0.685961 0 -0.77685 0.629685 0 -0.897487 0.441042 -0.00442583 -0.973118 0.230264 0 -0.981057 0.193717 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.849119 0.121627 0.514008 0.849119 0.362335 0.384331 0.849119 0.505957 0.151672 0.849119 -0.514008 0.121626 0.849119 -0.384329 0.362336 0.849119 -0.151672 0.505957 0 0.957886 0.287148 0 0.957886 0.287148 0 0.685979 0.727622 0 0.685979 0.727622 0 0.230266 0.973128 0 0.230266 0.973128 0 -0.287148 0.957886 0 -0.287148 0.957886 0 -0.727619 0.685982 0 -0.727619 0.685982 0 -0.973128 0.230265 0 -0.973128 0.230265 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.849118 0.121628 0.514009 0.849118 0.362334 0.384333 0.849118 0.505959 0.15167 0.849119 -0.514006 0.12163 0.849119 -0.384331 0.362335 0.849119 -0.15167 0.505958 0 0.957888 0.287143 0 0.957888 0.287143 0 0.685976 0.727624 0 0.685976 0.727624 0 0.230267 0.973127 0 0.230267 0.973127 0 -0.287143 0.957888 0 -0.287143 0.957888 0 -0.727622 0.685979 0 -0.727622 0.685979 0 -0.973126 0.230271 0 -0.973126 0.230271 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.851305 0.507856 0.131762 0.853125 0.385247 0.351798 0.854596 0.175403 0.488774 0.855727 -0.07305 0.512245 0.856529 -0.303157 0.417677 0.851304 -0.514734 0.101638 0.857007 -0.462485 0.227258 0.853125 -0.405288 0.32851 0.854595 -0.20387 0.477602 0.855727 0.0427706 0.515657 0.856529 0.278052 0.434793 0.857008 0.448293 0.254108 0 0.967953 0.251132 -0.00442615 0.957875 0.287151 0 0.869959 0.493123 0 0.738437 0.674323 -0.00738948 0.685963 0.727599 0 0.538757 0.842461 0 0.337771 0.941228 -0.0088758 0.230256 0.97309 0 0.08266 0.996578 0 -0.141179 0.989984 -0.00887578 -0.287137 0.957848 0 -0.39259 0.919713 0 -0.587401 0.809296 -0.00738989 -0.727602 0.68596 0 -0.776851 0.629685 0 -0.897498 0.441018 -0.00442526 -0.973119 0.230258 0 -0.981058 0.193716 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.849119 0.121626 0.514008 0.849119 0.362337 0.384329 0.849119 0.505956 0.151675 0.849119 -0.514009 0.121624 0.849119 -0.384328 0.362339 0.849119 -0.151673 0.505957 0 0.957884 0.287154 0 0.957884 0.287154 0 0.685982 0.727618 0 0.685982 0.727618 0 0.230265 0.973128 0 0.230265 0.973128 0 -0.28715 0.957886 0 -0.28715 0.957886 0 -0.727615 0.685985 0 -0.727615 0.685985 0 -0.973129 0.230261 0 -0.973129 0.230261 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.849119 0.505956 0.151675 0.856529 0.278048 0.434796 0.855727 0.0427706 0.515657 0.854595 -0.203872 0.477602 0.849119 -0.514009 0.121624 0.853125 -0.405286 0.328512 0.856529 -0.303151 0.417682 0.855727 -0.0730485 0.512245 0.854596 0.175403 0.488774 0.853125 0.385249 0.351796 0 0.967953 0.251133 0.00442614 0.957875 0.287151 -0.00369704 0.763129 0.646236 0 0.73844 0.674319 0 0.53875 0.842466 -0.00592444 0.407159 0.913338 0 0.337771 0.941228 0 0.08266 0.996578 -0.00666806 -0.0294407 0.999544 0 -0.141176 0.989984 0 -0.392595 0.919712 -0.00592383 -0.460213 0.887789 0 -0.587388 0.809305 0 -0.799852 0.600198 -0.00442617 -0.77684 0.629683 0.00514699 -0.981044 0.193714 0 -0.973129 0.230261 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.851305 0.507856 0.131762 0.853126 0.385248 0.351796 0.854596 0.175407 0.488772 0.855727 -0.0730451 0.512245 0.856529 -0.303157 0.417677 0.851304 -0.514734 0.101638 0.857008 -0.462489 0.22725 0.853126 -0.405286 0.328512 0.854596 -0.203871 0.477602 0.855727 0.0427637 0.515657 0.856529 0.278044 0.434798 0.857008 0.448293 0.254108 0 0.967953 0.251132 -0.00442615 0.957875 0.287151 0 0.869959 0.493123 0 0.73844 0.674319 -0.00739006 0.685963 0.727599 0 0.538742 0.842471 0 0.33778 0.941225 -0.00887658 0.230256 0.97309 0 0.0826468 0.996579 0 -0.14117 0.989985 -0.00887608 -0.287137 0.957848 0 -0.392592 0.919713 0 -0.587401 0.809296 -0.00738974 -0.727599 0.685963 0 -0.776847 0.629689 0 -0.897506 0.441002 -0.00442508 -0.973119 0.230258 0 -0.981057 0.193718 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.851304 0.507858 0.131763 0.853125 0.385245 0.351801 0.854595 0.175403 0.488775 0.855727 -0.07305 0.512245 0.856529 -0.303164 0.417672 0.851306 -0.514732 0.101637 0.857008 -0.462468 0.227291 0.853125 -0.405286 0.328513 0.854595 -0.20387 0.477602 0.855727 0.0427717 0.515657 0.856528 0.278052 0.434794 0.857007 0.448312 0.254078 0 0.967952 0.251134 -0.00442482 0.957878 0.287142 0 0.869994 0.493063 0 0.738432 0.674328 -0.00738934 0.68596 0.727602 0 0.538757 0.842461 0 0.337771 0.941228 -0.00887559 0.230258 0.973089 0 0.0826622 0.996578 0 -0.141179 0.989984 -0.00887578 -0.287137 0.957848 0 -0.39259 0.919713 0 -0.587414 0.809287 -0.00738935 -0.727602 0.68596 0 -0.776847 0.629689 0 -0.897467 0.441082 -0.00442659 -0.973117 0.230269 0 -0.981058 0.193716 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.957886 0.287148 0 0.957886 0.287148 0 0.685982 0.727619 0 0.685982 0.727619 0 0.230265 0.973128 0 0.230265 0.973128 0 -0.287145 0.957887 0 -0.287145 0.957887 0 -0.727619 0.685982 0 -0.727619 0.685982 0 -0.973128 0.230266 0 -0.973128 0.230266 0.849119 0.121626 0.514008 0.849119 0.362336 0.384329 0.849119 0.505957 0.151672 0.849119 -0.514007 0.121627 0.849119 -0.384329 0.362336 0.849119 -0.15167 0.505957 0.705563 0.703393 0.086134 0.70559 0.703366 0.0861296 0.70559 0.675564 0.213907 0.705581 0.675572 0.21391 0.705582 0.624763 0.334403 0.705588 0.624758 0.3344 0.705588 0.552674 0.443506 0.705581 0.552679 0.44351 0.705582 0.461774 0.537512 0.705586 0.461771 0.537509 0.705586 0.355142 0.613207 0.705587 0.355141 0.613206 0.705589 0.236417 0.668021 0.70559 0.236417 0.668019 0.70559 0.109643 0.700087 0.70559 0.109643 0.700087 0.705589 -0.0208644 0.708314 0.705587 -0.0208646 0.708316 0.705585 -0.150663 0.692423 0.705591 -0.150661 0.692418 0.705592 -0.275327 0.652943 0.705592 -0.275327 0.652943 0.705592 -0.390617 0.591235 0.705587 -0.39062 0.591239 0.705587 -0.492609 0.509396 0.705588 -0.492608 0.509395 0.705588 -0.577821 0.410205 0.705588 -0.577821 0.410205 0.705588 -0.643358 0.297046 0.70559 -0.643356 0.297045 0.705591 -0.686983 0.173771 0.705588 -0.686986 0.173772 0.705588 -0.707219 0.0445796 0.705587 -0.707219 0.0445796 0.705589 0.703367 0.0861303 0.70559 0.703366 0.0861301 0.70559 0.675564 0.213907 0.705581 0.675572 0.21391 0.705582 0.624763 0.334404 0.705588 0.624757 0.3344 0.705588 0.552674 0.443506 0.705591 0.552671 0.443503 0.70559 0.461768 0.537506 0.705586 0.461771 0.537509 0.705586 0.355142 0.613208 0.705582 0.355143 0.613211 0.705583 0.236419 0.668026 0.70559 0.236417 0.668019 0.70559 0.109643 0.700087 0.705588 0.109643 0.700089 0.70559 -0.0208646 0.708313 0.705594 -0.0208643 0.708309 0.705592 -0.150661 0.692417 0.70559 -0.150661 0.692419 0.705589 -0.275328 0.652946 0.705592 -0.275327 0.652943 0.705592 -0.390617 0.591235 0.705591 -0.390618 0.591236 0.705592 -0.492605 0.509392 0.705588 -0.492608 0.509395 0.705588 -0.577821 0.410205 0.705586 -0.577823 0.410206 0.705586 -0.643359 0.297047 0.705587 -0.643358 0.297046 0.705587 -0.686986 0.173772 0.705587 -0.686986 0.173772 0.705587 -0.707219 0.0445795 0.705587 -0.707219 0.0445795 0.705751 0.70364 0.0824999 0.705753 0.703638 0.0824998 0.705753 0.678623 0.203432 0.705753 0.678623 0.203432 0.705752 0.632987 0.318183 0.70575 0.632989 0.318184 0.70575 0.568121 0.423268 0.705752 0.56812 0.423267 0.705751 0.48599 0.51549 0.705749 0.485991 0.515491 0.70575 0.389093 0.59205 0.705754 0.389091 0.592047 0.705754 0.280372 0.650617 0.705752 0.280373 0.65062 0.705751 0.163134 0.689422 0.70575 0.163135 0.689423 0.705751 0.040939 0.707276 0.705747 0.0409394 0.707281 0.705746 -0.0825006 0.703645 0.70575 -0.0825002 0.703641 0.705749 -0.203433 0.678626 0.705753 -0.203432 0.678622 0.705754 -0.318182 0.632986 0.705756 -0.318181 0.632984 0.705757 -0.423264 0.568115 0.705742 -0.423272 0.568127 0.705741 -0.515497 0.485996 0.705745 -0.515495 0.485994 0.705744 -0.592055 0.389096 0.705749 -0.592051 0.389093 0.705748 -0.650623 0.280374 0.70575 -0.650621 0.280373 0.70575 -0.689423 0.163134 0.705732 -0.68944 0.163139 0.705731 -0.707296 0.0409406 0.705753 -0.707274 0.0409386 0.705586 0.703371 0.0861309 0.705587 0.703369 0.0861308 0.705587 0.675567 0.213908 0.705588 0.675566 0.213908 0.705588 0.624758 0.334401 0.705589 0.624756 0.3344 0.70559 0.552673 0.443505 0.705587 0.552675 0.443506 0.705586 0.461771 0.537509 0.705585 0.461771 0.537509 0.705586 0.355142 0.613208 0.705585 0.355142 0.613208 0.705585 0.236419 0.668024 0.70559 0.236416 0.668019 0.70559 0.109643 0.700087 0.705583 0.109644 0.700093 0.705583 -0.0208646 0.70832 0.705588 -0.0208646 0.708315 0.705588 -0.150662 0.692421 0.70559 -0.150661 0.692419 0.705589 -0.275328 0.652946 0.705584 -0.27533 0.652951 0.705582 -0.390622 0.591243 0.705591 -0.390618 0.591235 0.705592 -0.492606 0.509392 0.705579 -0.492614 0.509402 0.705579 -0.577829 0.41021 0.705588 -0.577822 0.410205 0.705588 -0.643358 0.297046 0.705581 -0.643364 0.297049 0.705581 -0.686992 0.173773 0.705584 -0.68699 0.173772 0.705584 -0.707223 0.0445798 0.705589 -0.707218 0.0445793 0.705589 0.703367 0.08613 0.705577 0.703379 0.086132 0.705578 0.675575 0.213911 0.705594 0.67556 0.213906 0.705593 0.624753 0.334398 0.70559 0.624756 0.3344 0.70559 0.552673 0.443504 0.705591 0.552671 0.443503 0.70559 0.461768 0.537506 0.705586 0.461771 0.53751 0.705586 0.355142 0.613207 0.705588 0.35514 0.613205 0.705587 0.236418 0.668022 0.70559 0.236417 0.668019 0.70559 0.109643 0.700087 0.705581 0.109644 0.700095 0.705583 -0.0208647 0.70832 0.705588 -0.0208644 0.708315 0.705588 -0.150662 0.692421 0.70559 -0.150662 0.692419 0.705589 -0.275328 0.652946 0.705589 -0.275328 0.652947 0.70559 -0.390618 0.591237 0.705587 -0.39062 0.591239 0.705587 -0.492609 0.509395 0.705588 -0.492608 0.509394 0.705588 -0.577821 0.410205 0.705588 -0.577821 0.410205 0.705588 -0.643358 0.297046 0.705587 -0.643359 0.297046 0.705587 -0.686986 0.173772 0.705587 -0.686986 0.173772 0.705587 -0.707219 0.0445795 0.705589 -0.707218 0.0445795 0.705751 0.70364 0.0825 0.705751 0.70364 0.0825 0.705751 0.678624 0.203432 0.705751 0.678625 0.203433 0.705751 0.632989 0.318184 0.70575 0.632989 0.318184 0.70575 0.568121 0.423267 0.705755 0.568117 0.423265 0.705756 0.485986 0.515486 0.705754 0.485987 0.515488 0.705754 0.389091 0.592047 0.705748 0.389094 0.592052 0.705748 0.280374 0.650623 0.705752 0.280373 0.65062 0.705751 0.163134 0.689422 0.705752 0.163134 0.689421 0.705751 0.0409391 0.707276 0.705753 0.0409389 0.707274 0.705752 -0.0824997 0.703639 0.705752 -0.0824998 0.703639 0.705753 -0.203432 0.678623 0.705754 -0.203432 0.678622 0.705754 -0.318182 0.632986 0.70575 -0.318184 0.63299 0.705749 -0.423268 0.568122 0.705755 -0.423265 0.568117 0.705756 -0.515486 0.485987 0.705759 -0.515484 0.485984 0.705759 -0.592043 0.389088 0.705748 -0.592052 0.389094 0.705748 -0.650623 0.280374 0.705752 -0.65062 0.280373 0.705751 -0.689422 0.163135 0.705758 -0.689416 0.163133 0.705758 -0.707269 0.0409387 0.705753 -0.707274 0.0409392 0.694736 -0.699936 0.165622 0.509838 -0.843975 0.166651 0.322026 -0.271852 0.90686 0.706856 -0.634843 0.311976 0.700858 -0.554128 0.449155 0.4065 -0.664791 0.626746 0.706107 -0.415944 0.573065 0.703117 -0.279161 0.653984 0.704869 -0.100141 0.702234 0.704868 0.0586315 0.706911 0.32202 0.218001 0.921292 0.703116 0.240183 0.669283 0.706106 0.381492 0.596555 0.406501 0.626745 0.664791 0.698068 0.693086 0.179816 0.547279 0.801704 0.240327 0.706855 0.615382 0.348801 0.700857 0.526729 0.480995 0.694742 -0.699931 0.16562 0.322022 -0.271851 0.906862 0.694743 -0.69993 0.16562 0.700858 -0.554127 0.449156 0.406506 -0.664788 0.626745 0.706111 -0.415941 0.573062 0.70312 -0.279161 0.653981 0.704865 -0.100142 0.702237 0.704865 0.0586334 0.706914 0.322022 0.218001 0.921291 0.694741 0.688969 0.206534 0.694741 0.688969 0.206535 0.700855 0.526731 0.480996 0.406498 0.626747 0.664791 0.70611 0.381488 0.596554 0.703118 0.240182 0.669281 0.698069 -0.702467 0.13871 0.698066 -0.70247 0.138709 0.706852 -0.634852 0.311968 0.581207 -0.650883 0.488416 0.700852 -0.554132 0.44916 0.706107 -0.415942 0.573066 0.486771 -0.40202 0.775522 0.70312 -0.27916 0.653981 0.704868 -0.100141 0.702234 0.450651 -0.0262845 0.892313 0.704867 0.058632 0.706912 0.703118 0.240182 0.669281 0.486768 0.355673 0.797843 0.70611 0.38149 0.596552 0.698068 0.546428 0.462728 0.698069 0.693084 0.179817 0.69807 0.693083 0.179816 0.706856 0.615385 0.348792 0.54728 0.618034 0.564374 0.694742 -0.699931 0.165621 0.509851 -0.843967 0.166649 0.322025 -0.271852 0.906861 0.706856 -0.634848 0.311967 0.700858 -0.554127 0.449156 0.406501 -0.66479 0.626746 0.70611 -0.415941 0.573064 0.703118 -0.279161 0.653983 0.704867 -0.100141 0.702235 0.704867 0.0586317 0.706913 0.32202 0.218 0.921292 0.70312 0.240182 0.66928 0.706111 0.381487 0.596552 0.4065 0.626747 0.664791 0.698069 0.693084 0.179817 0.547281 0.801702 0.240329 0.706848 0.615392 0.348796 0.700851 0.526733 0.481 0.694741 0.688969 0.206533 0.694741 0.68897 0.206533 0.694739 0.493399 0.523349 0.69474 0.493399 0.523349 0.69474 0.165622 0.699933 0.694738 0.165622 0.699935 0.694739 -0.206534 0.688971 0.694742 -0.206533 0.688969 0.694742 -0.523347 0.493398 0.694738 -0.523351 0.4934 0.694736 -0.699936 0.165622 0.694742 -0.699931 0.165622 0.698069 -0.702467 0.138708 0.698073 -0.702463 0.138708 0.706859 -0.634846 0.311964 0.581213 -0.650879 0.488414 0.450652 -0.0262842 0.892313 0.700854 -0.55413 0.449159 0.70611 -0.415941 0.573063 0.486771 -0.402019 0.775522 0.703116 -0.279162 0.653985 0.704864 -0.100139 0.702239 0.704866 0.0586317 0.706913 0.703117 0.240182 0.669282 0.486771 0.355673 0.797842 0.706107 0.381488 0.596557 0.698065 0.54643 0.46273 0.698069 0.693084 0.179816 0.69807 0.693083 0.179815 0.706856 0.615381 0.3488 0.547293 0.61803 0.564366 0.698068 -0.702467 0.13871 0.698059 -0.702476 0.138709 0.706847 -0.634849 0.311984 0.581215 -0.650879 0.488412 0.450646 -0.0262862 0.892316 0.70085 -0.554135 0.449159 0.706105 -0.415942 0.57307 0.486771 -0.402019 0.775522 0.703114 -0.279164 0.653987 0.704863 -0.100141 0.702239 0.704866 0.058632 0.706913 0.703117 0.240184 0.669281 0.486782 0.35567 0.797836 0.706116 0.381485 0.596548 0.698075 0.546424 0.462723 0.698069 0.693084 0.179816 0.69807 0.693083 0.179815 0.706856 0.615383 0.348796 0.547282 0.618033 0.564373 0.694742 -0.69993 0.165623 0.322024 -0.271851 0.906862 0.694736 -0.699936 0.165623 0.700851 -0.554132 0.449162 0.406512 -0.664788 0.626742 0.706107 -0.415947 0.573062 0.703117 -0.27916 0.653985 0.704864 -0.100142 0.702238 0.704865 0.0586336 0.706914 0.322028 0.218001 0.921289 0.694741 0.688969 0.206533 0.694742 0.688969 0.206533 0.700857 0.526729 0.480995 0.406501 0.626745 0.664791 0.706106 0.381492 0.596555 0.703116 0.240181 0.669284 0.698069 -0.702467 0.13871 0.698072 -0.702463 0.13871 0.706857 -0.634846 0.311966 0.581215 -0.650879 0.488412 0.450653 -0.0262842 0.892312 0.700852 -0.554133 0.449159 0.706107 -0.415942 0.573066 0.486771 -0.40202 0.775522 0.703124 -0.279158 0.653979 0.70487 -0.100141 0.702233 0.704866 0.058632 0.706913 0.703117 0.240182 0.669282 0.486771 0.355673 0.797842 0.706106 0.381488 0.596558 0.698062 0.546433 0.462732 0.698069 0.693084 0.179819 0.698071 0.693082 0.179818 0.706857 0.615388 0.348785 0.547274 0.618037 0.564376 0.694742 0.688969 0.206533 0.694741 0.688969 0.206533 0.694741 0.493398 0.523348 0.694736 0.493401 0.523352 0.694739 0.165621 0.699934 0.694742 0.165621 0.699931 0.694739 -0.206535 0.688971 0.694743 -0.206533 0.688968 0.694746 -0.523343 0.493395 0.694737 -0.523351 0.4934 0.694736 -0.699937 0.165621 0.694742 -0.699931 0.165621 0.694741 0.688969 0.206533 0.694742 0.688969 0.206533 0.694742 0.493398 0.523347 0.694736 0.493401 0.523352 0.694738 0.165622 0.699934 0.69474 0.165622 0.699933 0.694737 -0.206536 0.688973 0.694744 -0.206532 0.688967 0.694747 -0.523343 0.493395 0.694736 -0.523353 0.493401 0.694736 -0.699937 0.165621 0.694742 -0.699931 0.165621 0.694743 -0.69993 0.16562 0.32202 -0.271852 0.906862 0.694736 -0.699937 0.165621 0.700853 -0.55413 0.44916 0.406509 -0.664788 0.626743 0.706113 -0.41594 0.573061 0.703119 -0.279161 0.653982 0.704868 -0.10014 0.702235 0.704869 0.0586312 0.70691 0.32202 0.218001 0.921292 0.69474 0.68897 0.206534 0.694742 0.688969 0.206533 0.700857 0.526729 0.480995 0.406501 0.626745 0.664791 0.706106 0.381492 0.596555 0.703116 0.240183 0.669283 -0.694741 -0.699932 0.165621 -0.694743 -0.69993 0.16562 -0.694743 -0.523347 0.493397 -0.694742 -0.523347 0.493398 -0.694742 -0.206533 0.688969 -0.69474 -0.206533 0.68897 -0.694743 0.165621 0.69993 -0.694743 0.165621 0.69993 -0.694743 0.493397 0.523347 -0.694742 0.493398 0.523347 -0.694742 0.688969 0.206533 -0.694742 0.688968 0.206533 -0.698068 0.693085 0.179817 -0.698064 0.693089 0.179817 -0.70685 0.615387 0.348801 -0.581208 0.621005 0.52588 -0.700858 0.526728 0.480995 -0.706112 0.381489 0.59655 -0.486773 0.355673 0.79784 -0.703121 0.240181 0.669279 -0.70487 0.058633 0.706909 -0.450649 -0.0262852 0.892314 -0.704867 -0.100141 0.702235 -0.70312 -0.27916 0.653982 -0.486768 -0.40202 0.775524 -0.706111 -0.415943 0.57306 -0.698069 -0.572717 0.429761 -0.698069 -0.702467 0.138709 -0.698066 -0.702469 0.13871 -0.706853 -0.634851 0.311966 -0.547275 -0.650185 0.52702 -0.694742 0.688969 0.206534 -0.509839 0.832701 0.21604 -0.32202 0.218 0.921292 -0.706848 0.615392 0.348796 -0.700851 0.526733 0.481 -0.4065 0.626747 0.664791 -0.706111 0.381487 0.596552 -0.70312 0.240182 0.66928 -0.704867 0.0586317 0.706913 -0.704867 -0.100141 0.702235 -0.322025 -0.271852 0.906861 -0.703118 -0.279161 0.653983 -0.70611 -0.415941 0.573064 -0.406501 -0.66479 0.626746 -0.698069 -0.702467 0.138709 -0.54729 -0.814453 0.192719 -0.706856 -0.634848 0.311967 -0.700858 -0.554127 0.449156 -0.694742 -0.699931 0.165621 -0.694736 -0.699936 0.165623 -0.694737 -0.523351 0.493401 -0.694741 -0.523348 0.493398 -0.694741 -0.206534 0.688969 -0.694739 -0.206534 0.688972 -0.694741 0.165621 0.699932 -0.694739 0.165622 0.699933 -0.694736 0.493401 0.523351 -0.694741 0.493397 0.523349 -0.694741 0.688969 0.206533 -0.694742 0.688969 0.206533 -0.698069 -0.702467 0.138707 -0.698066 -0.70247 0.138709 -0.698067 -0.572718 0.429762 -0.698069 -0.572717 0.429761 -0.698069 -0.329535 0.635694 -0.698066 -0.329535 0.635697 -0.698067 -0.0210825 0.715722 -0.69807 -0.0210832 0.715719 -0.69807 0.291544 0.653989 -0.69807 0.291544 0.653988 -0.698069 0.546428 0.462727 -0.69807 0.546427 0.462727 -0.69807 0.693083 0.179817 -0.698068 0.693085 0.179817 -0.69474 0.68897 0.206533 -0.509837 0.832702 0.216039 -0.32202 0.218001 0.921292 -0.706855 0.615382 0.348801 -0.700857 0.526729 0.480995 -0.406501 0.626745 0.664791 -0.706106 0.381492 0.596555 -0.703116 0.240183 0.669283 -0.704868 0.0586315 0.706911 -0.704869 -0.100141 0.702234 -0.322026 -0.271852 0.90686 -0.703117 -0.279161 0.653984 -0.706107 -0.415944 0.573065 -0.4065 -0.664791 0.626746 -0.698063 -0.702472 0.13871 -0.547278 -0.81446 0.192721 -0.706856 -0.634843 0.311976 -0.700858 -0.554128 0.449155 -0.69807 -0.702466 0.138707 -0.698059 -0.702476 0.138712 -0.69806 -0.572724 0.429767 -0.698064 -0.572722 0.429764 -0.698066 -0.329536 0.635697 -0.698066 -0.329536 0.635697 -0.698067 -0.0210825 0.715722 -0.698067 -0.0210825 0.715722 -0.698066 0.291546 0.653991 -0.69807 0.291544 0.653989 -0.698073 0.546425 0.462726 -0.69807 0.546427 0.462727 -0.69807 0.693083 0.179815 -0.698068 0.693086 0.179816 -0.698069 0.693085 0.179815 -0.69807 0.693083 0.179815 -0.706856 0.615381 0.3488 -0.581219 0.620999 0.525876 -0.70086 0.526726 0.480993 -0.706113 0.381488 0.596549 -0.486773 0.355673 0.79784 -0.703121 0.240181 0.669279 -0.70487 0.0586327 0.706909 -0.450649 -0.0262852 0.892314 -0.704866 -0.100142 0.702236 -0.703117 -0.279162 0.653984 -0.486775 -0.402017 0.775521 -0.706115 -0.415938 0.573059 -0.698075 -0.572713 0.429758 -0.698069 -0.702467 0.138707 -0.698073 -0.702464 0.138706 -0.706859 -0.634846 0.311964 -0.547283 -0.650181 0.527016 -0.698069 0.693084 0.179815 -0.698071 0.693083 0.179815 -0.706856 0.615381 0.348799 -0.581218 0.620999 0.525876 -0.700861 0.526726 0.480993 -0.706114 0.381488 0.596549 -0.486773 0.355672 0.797841 -0.703118 0.240182 0.669281 -0.704867 0.0586318 0.706912 -0.450651 -0.0262845 0.892313 -0.704867 -0.100141 0.702235 -0.703118 -0.279162 0.653984 -0.48677 -0.402019 0.775522 -0.706107 -0.415942 0.573066 -0.698064 -0.572722 0.429764 -0.698069 -0.702467 0.138707 -0.698059 -0.702476 0.138711 -0.706846 -0.634857 0.311971 -0.547267 -0.650189 0.527023 -0.694742 -0.699931 0.165622 -0.69475 -0.699924 0.165619 -0.694748 -0.523344 0.493393 -0.694736 -0.523351 0.493403 -0.694738 -0.206534 0.688972 -0.694744 -0.206534 0.688966 -0.69474 0.165622 0.699933 -0.694741 0.165621 0.699931 -0.694745 0.493394 0.523346 -0.694732 0.493405 0.523353 -0.694728 0.688981 0.206537 -0.694741 0.688968 0.206536 -0.698069 -0.702466 0.13871 -0.698073 -0.702463 0.138709 -0.698073 -0.572714 0.429759 -0.698075 -0.572713 0.429758 -0.698072 -0.329533 0.635691 -0.698072 -0.329533 0.635691 -0.698067 -0.0210826 0.715722 -0.698067 -0.0210824 0.715722 -0.698072 0.291542 0.653987 -0.698064 0.291547 0.653993 -0.698062 0.546432 0.462732 -0.698059 0.546435 0.462734 -0.698057 0.693096 0.179819 -0.698068 0.693084 0.179818 -0.694741 -0.699931 0.165622 -0.69475 -0.699924 0.165619 -0.694748 -0.523344 0.493393 -0.694737 -0.52335 0.493402 -0.69474 -0.206535 0.68897 -0.694738 -0.206535 0.688973 -0.694733 0.165625 0.699939 -0.694745 0.16562 0.699928 -0.694748 0.493393 0.523344 -0.694737 0.493402 0.52335 -0.69474 0.688971 0.206533 -0.694742 0.688968 0.206533 -0.707093 -0.695503 0.127653 -0.705149 -0.707052 0.0533213 -0.705157 -0.707043 0.0533212 -0.688903 -0.695365 0.204649 -0.705152 -0.680511 0.19916 -0.706815 -0.643192 0.294476 -0.266122 -0.848625 0.457181 -0.706356 -0.609282 0.360328 -0.705154 -0.540671 0.458729 -0.705155 -0.54067 0.458728 -0.705156 -0.43348 0.561116 -0.705159 -0.433478 0.561113 -0.705158 -0.307344 0.638977 -0.705156 -0.307345 0.638979 -0.705155 -0.167778 0.688917 -0.705156 -0.167777 0.688916 -0.705156 -0.0208772 0.708744 -0.705158 -0.020877 0.708743 -0.705158 0.126935 0.697596 -0.705157 0.126935 0.697597 -0.705156 0.2692 0.655962 -0.705156 0.2692 0.655962 -0.705155 0.3997 0.585658 -0.705156 0.3997 0.585658 -0.705156 0.512731 0.489758 -0.705156 0.512731 0.489758 -0.705156 0.603352 0.372452 -0.705157 0.603352 0.372452 -0.705156 0.667605 0.23887 -0.705157 0.667604 0.238869 -0.705157 0.702679 0.0948467 -0.705157 0.702679 0.0948467 0.705157 0.702679 0.0948467 0.705157 0.603352 0.372452 0.706882 0.647812 0.284002 0.30069 0.897973 0.321295 0.706245 0.674556 0.214924 0.705157 0.702679 0.0948467 0.705156 0.3997 0.585658 0.707021 0.468864 0.529423 0.633296 0.53057 0.563411 0.587937 0.560829 0.582925 0.329724 0.682682 0.652095 0.706162 0.527351 0.472479 0.705156 0.603352 0.372452 0.26806 0.365767 0.891268 0.67224 0.319545 0.66782 0.707088 0.33023 0.625279 0.705155 0.3997 0.585658 0.707021 -0.499215 0.500905 0.705156 -0.43348 0.561116 0.705158 -0.433478 0.561113 0.705158 -0.307344 0.638977 0.705156 -0.307345 0.638979 0.705155 -0.167778 0.688917 0.705156 -0.167777 0.688916 0.705156 -0.0208771 0.708744 0.705158 -0.0208771 0.708743 0.705158 0.126935 0.697596 0.705157 0.126935 0.697597 0.70705 0.210165 0.675212 0.567028 0.295451 0.768887 0.511611 -0.661328 0.548543 0.342812 -0.716319 0.607756 0.6321 -0.563685 0.531703 0.657483 -0.543202 0.522156 0.707033 -0.576254 0.409922 0.705155 -0.624231 0.336293 0.705153 -0.624233 0.336294 0.706878 -0.66341 0.245378 0.30069 -0.915328 0.267882 0.706237 -0.686045 0.174848 0.705149 -0.707052 0.0533219 0.705157 -0.707043 0.0533206 0 -0.981057 0.193719 0.0239936 -0.972848 0.2302 0 -0.897492 0.441031 0 -0.776849 0.629687 0.0400448 -0.727036 0.68543 0 -0.587402 0.809295 0 -0.392591 0.919713 0.048081 -0.286816 0.956778 0 -0.141175 0.989985 0 0.0826572 0.996578 0.0480811 0.23 0.972002 0 0.337773 0.941227 0 0.53875 0.842466 0.040044 0.68543 0.727036 0 0.738437 0.674323 0 0.869977 0.493092 0.0239933 0.957611 0.287064 0 0.967953 0.251131 0 -0.981057 0.193717 -0.0239949 -0.972848 0.230199 0.0200479 -0.799689 0.600079 0 -0.776849 0.629687 0 -0.587403 0.809294 0.032112 -0.459987 0.887345 0 -0.392592 0.919713 0 -0.141175 0.989985 0.0361385 -0.0294242 0.998914 0 0.0826589 0.996578 0 0.337774 0.941227 0.0321119 0.406957 0.912883 0 0.538747 0.842468 0 0.763135 0.646239 0.0239938 0.738225 0.674127 -0.0279055 0.967576 0.251033 0 0.957886 0.287149 0 -0.981057 0.193719 0 -0.981057 0.193719 0 -0.897485 0.441045 0 -0.897485 0.441045 0 -0.77685 0.629686 0 -0.77685 0.629686 0 -0.587404 0.809294 0 -0.587404 0.809294 0 -0.392591 0.919713 0 -0.392591 0.919713 0 -0.141175 0.989985 0 -0.141175 0.989985 0 0.0826567 0.996578 0 0.0826567 0.996578 0 0.337774 0.941227 0 0.337774 0.941227 0 0.53875 0.842466 0 0.53875 0.842466 0 0.738437 0.674322 0 0.738437 0.674322 0 0.869971 0.493103 0 0.869971 0.493103 0 0.967954 0.251129 0 0.967954 0.251129 0 -0.981058 0.193717 -0.0239938 -0.972848 0.230198 0.0200486 -0.799689 0.600079 0 -0.776848 0.629688 0 -0.587403 0.809294 0.032112 -0.459987 0.887345 0 -0.392592 0.919713 0 -0.141174 0.989985 0.0361378 -0.0294242 0.998914 0 0.0826563 0.996578 0 0.337774 0.941227 0.0321123 0.406958 0.912882 0 0.53875 0.842466 0 0.763134 0.646241 0.0239934 0.738225 0.674128 -0.0279059 0.967577 0.251031 0 0.957887 0.287147 0 -0.981057 0.193717 -0.0239937 -0.972848 0.230198 0 -0.897493 0.441029 0 -0.776848 0.629689 -0.0400442 -0.727035 0.685431 0 -0.587403 0.809294 0 -0.392592 0.919713 -0.0480809 -0.286816 0.956778 0 -0.141176 0.989985 0 0.0826585 0.996578 -0.0480811 0.23 0.972002 0 0.337774 0.941227 0 0.53875 0.842466 -0.040044 0.68543 0.727036 0 0.967954 0.251129 -0.0239947 0.957611 0.287064 0 0.869971 0.493103 0 0.738437 0.674322 0 -0.981057 0.193717 -0.0239938 -0.972848 0.230198 0 -0.897492 0.441031 0 -0.776848 0.629688 -0.0400445 -0.727035 0.685431 0 -0.587402 0.809295 0 -0.392592 0.919713 -0.0480812 -0.286816 0.956778 0 -0.141175 0.989985 0 0.0826569 0.996578 -0.0480814 0.23 0.972002 0 0.337774 0.941227 0 0.53875 0.842466 -0.040044 0.68543 0.727036 0 0.967954 0.251129 -0.0239946 0.957611 0.287064 0 0.869972 0.493102 0 0.738437 0.674323 0 -0.981057 0.193721 0.0239934 -0.972847 0.230201 0 -0.897492 0.441031 0 -0.776851 0.629685 0.0400451 -0.727037 0.685429 0 -0.587402 0.809295 0 -0.392589 0.919714 0.0480808 -0.286815 0.956779 0 -0.141175 0.989985 0 0.082657 0.996578 0.0480811 0.23 0.972002 0 0.337774 0.941227 0 0.538743 0.84247 0.0400454 0.685429 0.727038 0 0.738437 0.674322 0 0.869983 0.493082 0.0239919 0.957611 0.287064 0 0.967953 0.251133 0 -0.981057 0.193721 -0.0239933 -0.972847 0.230201 0.0200491 -0.799689 0.600079 0 -0.776848 0.629689 0 -0.587409 0.80929 0.0321133 -0.459987 0.887345 0 -0.392589 0.919714 0 -0.141176 0.989985 0.0361385 -0.0294244 0.998914 0 0.0826593 0.996578 0 0.337772 0.941228 0.0321127 0.406956 0.912883 0 0.53875 0.842466 0 0.763134 0.646241 0.0239934 0.738225 0.674128 -0.0279059 0.967577 0.251031 0 0.957887 0.287147 0 -0.981057 0.193717 0.023996 -0.972847 0.230201 0 -0.897483 0.44105 0 -0.776851 0.629684 0.0400458 -0.727037 0.685429 0 -0.587399 0.809298 0 -0.392593 0.919712 0.0480817 -0.286816 0.956778 0 -0.141175 0.989985 0 0.082657 0.996578 0.0480817 0.230002 0.972002 0 0.337777 0.941226 0 0.538747 0.842467 0.0400443 0.685429 0.727037 0 0.738437 0.674323 0 0.869974 0.493097 0.0239943 0.957611 0.287064 0 0.967954 0.251129 0 -0.981057 0.193719 0.0239934 -0.972848 0.2302 0 -0.897493 0.441029 0 -0.776849 0.629687 0.0400445 -0.727036 0.68543 0 -0.587403 0.809294 0 -0.392592 0.919713 0.0480818 -0.286815 0.956779 0 -0.141172 0.989985 0 0.0826567 0.996578 0.0480813 0.23 0.972002 0 0.337774 0.941227 0 0.538744 0.842469 0.0400455 0.68543 0.727036 0 0.738439 0.67432 0 0.869971 0.493103 0.0239947 0.957611 0.287064 0 0.967954 0.251129 0 -0.981057 0.193719 -0.0239935 -0.972848 0.230199 0 -0.897493 0.441029 0 -0.776848 0.629689 -0.0400435 -0.727036 0.68543 0 -0.587406 0.809292 0 -0.392591 0.919713 -0.048081 -0.286815 0.956779 0 -0.141175 0.989985 0 0.0826589 0.996578 -0.0480809 0.230001 0.972002 0 0.337774 0.941227 0 0.53875 0.842466 -0.0400439 0.68543 0.727037 0 0.967954 0.251129 -0.0239945 0.957611 0.287064 0 0.869973 0.4931 0 0.738437 0.674323 0 -0.981057 0.193719 0 -0.981057 0.193719 0 -0.897492 0.441031 0 -0.897492 0.441031 0 -0.776849 0.629687 0 -0.776849 0.629687 0 -0.587402 0.809295 0 -0.587402 0.809295 0 -0.392591 0.919713 0 -0.392591 0.919713 0 -0.141175 0.989985 0 -0.141175 0.989985 0 0.0826567 0.996578 0 0.0826567 0.996578 0 0.337775 0.941227 0 0.337775 0.941227 0 0.538747 0.842468 0 0.538747 0.842468 0 0.738437 0.674323 0 0.738437 0.674323 0 0.869977 0.493092 0 0.869977 0.493092 0 0.967953 0.251131 0 0.967953 0.251131 -0.694746 0.688965 0.206532 -0.694745 0.688966 0.206531 -0.694745 0.493395 0.523345 -0.694746 0.493395 0.523345 -0.694745 0.16562 0.699928 -0.694746 0.165619 0.699928 -0.694746 -0.206532 0.688965 -0.694746 -0.206533 0.688965 -0.694746 -0.523345 0.493395 -0.694746 -0.523345 0.493396 -0.700225 -0.682465 0.209588 -0.711388 -0.683913 0.161832 -0.706344 -0.707406 0.0255906 0 -0.973127 0.230268 0 -0.973127 0.230268 0 -0.72762 0.685981 0 -0.72762 0.685981 0 -0.287148 0.957886 0 -0.287148 0.957886 0 0.230265 0.973128 0 0.230265 0.973128 0 0.68598 0.72762 0 0.68598 0.72762 0 0.957887 0.287145 0 0.957887 0.287145 -0.694746 -0.699927 0.165619 -0.694746 -0.699928 0.16562 -0.694745 -0.523345 0.493396 -0.694746 -0.523345 0.493395 -0.694746 -0.206532 0.688965 -0.694746 -0.206532 0.688965 -0.694746 0.16562 0.699927 -0.694746 0.165621 0.699927 -0.694746 0.493395 0.523345 -0.694746 0.493395 0.523345 -0.694746 0.688965 0.206533 -0.694745 0.688965 0.206532 0 -0.973128 0.230264 0 -0.973128 0.230264 0 -0.72762 0.685981 0 -0.72762 0.685981 0 -0.287147 0.957886 0 -0.287147 0.957886 0 0.230266 0.973128 0 0.230266 0.973128 0 0.68598 0.72762 0 0.68598 0.72762 0 0.957886 0.287149 0 0.957886 0.287149 -0.694745 -0.699928 0.165622 -0.694745 -0.699928 0.165619 -0.694745 -0.523344 0.493396 -0.694746 -0.523344 0.493395 -0.694746 -0.206533 0.688965 -0.694746 -0.206533 0.688965 -0.694745 0.165621 0.699928 -0.694746 0.16562 0.699928 -0.694745 0.493396 0.523344 -0.694746 0.493395 0.523345 -0.694746 0.688965 0.206531 -0.694746 0.688965 0.206531 0 -0.973127 0.230268 0 -0.973127 0.230268 0 -0.727619 0.685982 0 -0.727619 0.685982 0 -0.287149 0.957886 0 -0.287149 0.957886 0 0.230268 0.973127 0 0.230268 0.973127 0 0.685982 0.727619 0 0.685982 0.727619 0 0.957887 0.287146 0 0.957887 0.287146 -0.694745 -0.699928 0.165622 -0.694745 -0.699928 0.165619 -0.694745 -0.523344 0.493397 -0.694746 -0.523344 0.493395 -0.694746 -0.206533 0.688965 -0.694746 -0.206533 0.688965 -0.694745 0.16562 0.699928 -0.694745 0.16562 0.699928 -0.694745 0.493396 0.523344 -0.694746 0.493395 0.523345 -0.694746 0.688965 0.206531 -0.694746 0.688965 0.206531 0 -0.973127 0.230268 0 -0.973127 0.230268 0 -0.727618 0.685982 0 -0.727618 0.685982 0 -0.287148 0.957886 0 -0.287148 0.957886 0 0.230266 0.973128 0 0.230266 0.973128 0 0.685982 0.727619 0 0.685982 0.727619 0 0.957887 0.287146 0 0.957887 0.287146 -0.694745 -0.699928 0.165622 -0.694745 -0.699928 0.165619 -0.694745 -0.523344 0.493397 -0.694746 -0.523344 0.493395 -0.694746 -0.206533 0.688965 -0.694746 -0.206533 0.688965 -0.694745 0.16562 0.699928 -0.694745 0.16562 0.699928 -0.694745 0.493396 0.523344 -0.694746 0.493395 0.523345 -0.694746 0.688965 0.206531 -0.694746 0.688965 0.206531 0 -0.973127 0.230268 0 -0.973127 0.230268 0 -0.727619 0.685982 0 -0.727619 0.685982 0 -0.287148 0.957886 0 -0.287148 0.957886 0 0.230266 0.973128 0 0.230266 0.973128 0 0.685982 0.727619 0 0.685982 0.727619 0 0.957887 0.287146 0 0.957887 0.287146 -0.698073 0.69308 0.179816 -0.698072 0.693081 0.179814 -0.706858 0.615379 0.348798 -0.693897 0.549514 0.46534 -0.70086 0.526728 0.480991 -0.706115 0.381485 0.596549 -0.691347 0.294188 0.659918 -0.703123 0.240182 0.669276 -0.698072 -0.0210825 0.715717 -0.67038 0.0613304 0.739479 -0.704872 -0.100139 0.70223 -0.698073 -0.329533 0.635691 -0.680458 -0.287687 0.673953 -0.706114 -0.415933 0.573064 -0.698072 -0.572715 0.42976 -0.698071 -0.702464 0.138712 -0.698073 -0.702463 0.138707 -0.706859 -0.63485 0.311955 -0.689671 -0.562535 0.455971 0 -0.981056 0.193724 -0.101682 -0.968084 0.229074 0 -0.897499 0.441017 0 -0.727618 0.685983 -0.2312 -0.755802 0.612626 0 -0.587395 0.8093 0 -0.287147 0.957886 -0.335407 -0.369852 0.866436 0 -0.141173 0.989985 0 0.0826536 0.996578 -0.200846 0.225574 0.953298 0 0.337777 0.941226 0 0.538747 0.842468 -0.168257 0.676202 0.717245 0 0.967954 0.251128 -0.101694 0.952921 0.285657 0 0.869972 0.493102 0 0.738439 0.67432 -0.698072 0.693081 0.179816 -0.698073 0.69308 0.179819 -0.706858 0.615377 0.348802 -0.693897 0.549514 0.46534 -0.700861 0.526727 0.480992 -0.706115 0.381488 0.596547 -0.691347 0.294188 0.659918 -0.703124 0.24018 0.669276 -0.698073 -0.0210825 0.715716 -0.670378 0.0613363 0.73948 -0.704872 -0.100141 0.70223 -0.698073 -0.329533 0.635691 -0.680457 -0.287686 0.673954 -0.706116 -0.415943 0.573055 -0.698073 -0.572714 0.429759 -0.698073 -0.702463 0.138706 -0.698073 -0.702463 0.138707 -0.706859 -0.634849 0.311958 -0.68967 -0.562532 0.455975 0 -0.981058 0.193717 -0.101685 -0.968085 0.229068 0 -0.897497 0.441021 0 -0.727619 0.685982 -0.231175 -0.755802 0.612635 0 -0.58741 0.80929 0 -0.287149 0.957886 -0.335398 -0.369851 0.86644 0 -0.141175 0.989985 0 0.0826613 0.996578 -0.200838 0.225576 0.953299 0 0.337774 0.941227 0 0.538751 0.842465 -0.168254 0.676202 0.717246 0 0.967952 0.251134 -0.101693 0.952919 0.285663 0 0.869969 0.493107 0 0.738438 0.674321 -0.694745 -0.699928 0.165621 -0.694745 -0.699928 0.16562 -0.694745 -0.523344 0.493396 -0.694746 -0.523345 0.493395 -0.694746 -0.206533 0.688965 -0.694746 -0.206533 0.688965 -0.694746 0.165619 0.699927 -0.694746 0.16562 0.699928 -0.694745 0.493396 0.523344 -0.694746 0.493395 0.523344 -0.694745 0.688966 0.206531 -0.694746 0.688965 0.206532 0 -0.973127 0.230268 0 -0.973127 0.230268 0 -0.727619 0.685982 0 -0.727619 0.685982 0 -0.287149 0.957886 0 -0.287149 0.957886 0 0.230264 0.973128 0 0.230264 0.973128 0 0.685982 0.727619 0 0.685982 0.727619 0 0.957887 0.287146 0 0.957887 0.287146 -0.694746 -0.699927 0.165619 -0.694746 -0.699928 0.16562 -0.694746 -0.523345 0.493395 -0.694745 -0.523345 0.493396 -0.694745 -0.206532 0.688966 -0.694746 -0.206532 0.688965 -0.694746 0.165621 0.699928 -0.694746 0.16562 0.699928 -0.694746 0.493395 0.523345 -0.694746 0.493395 0.523345 -0.694746 0.688965 0.206533 -0.694745 0.688965 0.206532 0 -0.973128 0.230265 0 -0.973128 0.230265 0 -0.72762 0.68598 0 -0.72762 0.68598 0 -0.287146 0.957887 0 -0.287146 0.957887 0 0.230267 0.973128 0 0.230267 0.973128 0 0.68598 0.72762 0 0.68598 0.72762 0 0.957886 0.287148 0 0.957886 0.287148 0.980541 0.023713 0.194876 0.980398 0.195426 0.0250771 0.980398 0.195426 0.0250771 0.980398 0.170953 0.0979544 0.979269 0.174423 0.102998 0.980578 0.177847 0.0826945 0.980398 0.186778 0.0627209 0.979846 0.188942 0.0648267 0.98058 0.19085 0.0451578 0.980398 0.120455 0.155919 0.978034 0.123074 0.168235 0.980568 0.130793 0.146219 0.980398 0.148558 0.129423 0.978665 0.152237 0.137978 0.980573 0.157552 0.116847 0.980398 0.051618 0.190146 0.976678 0.0480721 0.209261 0.980552 0.0624784 0.186051 0.980398 0.0877219 0.176423 0.977372 0.0879308 0.192387 0.980561 0.0986647 0.169606 0.97595 0.00499427 0.217939 0.980398 0.0135304 0.196563 0.980529 -0.0160471 0.195718 0.978323 -0.0263571 0.205401 0.980541 -0.0351426 0.193143 0.980515 -0.0551756 0.188536 0.978403 -0.0658024 0.195955 0.980552 -0.0733213 0.182051 0.9805 -0.0920707 0.173618 0.978561 -0.102394 0.178702 0.980561 -0.108477 0.163505 0.980483 -0.125221 0.15157 0.978794 -0.134558 0.154452 0.980568 -0.139173 0.138266 0.980464 -0.153267 0.123286 0.9791 -0.160944 0.124337 0.980573 -0.164156 0.107371 0.980444 -0.175057 0.0899196 0.979473 -0.180493 0.0897457 0.980578 -0.182405 0.0720835 0.980422 -0.189691 0.0528296 0.979908 -0.192483 0.0522525 0.98058 -0.193177 0.0338474 0.980398 -0.196563 0.0135303 0.980398 -0.196563 0.0135304 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.998019 0.0629101 0 -0.998019 0.0629101 0 -0.969466 0.245225 0 -0.969466 0.245225 0 -0.907899 0.419188 0 -0.907899 0.419188 0 -0.815415 0.578877 0 -0.815415 0.578877 0 -0.695163 0.718852 0 -0.695163 0.718852 0 -0.551237 0.834348 0 -0.551237 0.834348 0 -0.38854 0.921432 0 -0.38854 0.921432 0 -0.212613 0.977137 0 -0.212613 0.977137 0 -0.0294439 0.999566 0 -0.0294439 0.999566 0 0.154728 0.987957 0 0.154728 0.987957 0 0.333629 0.942704 0 0.333629 0.942704 0 0.50117 0.865349 0 0.50117 0.865349 0 0.651644 0.758525 0 0.651644 0.758525 0 0.779927 0.62587 0 0.779927 0.62587 0 0.881651 0.471902 0 0.881651 0.471902 0 0.953351 0.301865 0 0.953351 0.301865 0 0.992586 0.121546 0 0.992586 0.121546 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.992586 0.121547 0 0.992586 0.121547 0 0.953351 0.301864 0 0.953351 0.301864 0 0.881651 0.471902 0 0.881651 0.471902 0 0.779927 0.62587 0 0.779927 0.62587 0 0.651644 0.758525 0 0.651644 0.758525 0 0.50117 0.865349 0 0.50117 0.865349 0 0.33363 0.942704 0 0.33363 0.942704 0 0.154727 0.987957 0 0.154727 0.987957 0 -0.0294436 0.999566 0 -0.0294436 0.999566 0 -0.212612 0.977137 0 -0.212612 0.977137 0 -0.388541 0.921432 0 -0.388541 0.921432 0 -0.551237 0.834348 0 -0.551237 0.834348 0 -0.695163 0.718852 0 -0.695163 0.718852 0 -0.815415 0.578877 0 -0.815415 0.578877 0 -0.907899 0.419188 0 -0.907899 0.419188 0 -0.969466 0.245224 0 -0.969466 0.245224 0 -0.998019 0.0629102 0 -0.998019 0.0629102 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.998019 0.0629102 0 -0.998019 0.0629102 0 -0.969466 0.245225 0 -0.969466 0.245225 0 -0.907899 0.419188 0 -0.907899 0.419188 0 -0.815415 0.578877 0 -0.815415 0.578877 0 -0.695163 0.718852 0 -0.695163 0.718852 0 -0.551238 0.834348 0 -0.551238 0.834348 0 -0.388541 0.921432 0 -0.388541 0.921432 0 -0.212613 0.977137 0 -0.212613 0.977137 0 -0.0294437 0.999566 0 -0.0294437 0.999566 0 0.154727 0.987957 0 0.154727 0.987957 0 0.333629 0.942704 0 0.333629 0.942704 0 0.50117 0.865349 0 0.50117 0.865349 0 0.651644 0.758525 0 0.651644 0.758525 0 0.779927 0.62587 0 0.779927 0.62587 0 0.881651 0.471902 0 0.881651 0.471902 0 0.953351 0.301864 0 0.953351 0.301864 0 0.992586 0.121547 0 0.992586 0.121547 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.998019 0.0629101 0 -0.998019 0.0629101 0 -0.969466 0.245224 0 -0.969466 0.245224 0 -0.907899 0.419188 0 -0.907899 0.419188 0 -0.815415 0.578877 0 -0.815415 0.578877 0 -0.695163 0.718852 0 -0.695163 0.718852 0 -0.551238 0.834348 0 -0.551238 0.834348 0 -0.388541 0.921432 0 -0.388541 0.921432 0 -0.212612 0.977137 0 -0.212612 0.977137 0 -0.029444 0.999566 0 -0.029444 0.999566 0 0.154728 0.987957 0 0.154728 0.987957 0 0.333629 0.942704 0 0.333629 0.942704 0 0.50117 0.865349 0 0.50117 0.865349 0 0.651645 0.758525 0 0.651645 0.758525 0 0.779927 0.62587 0 0.779927 0.62587 0 0.881651 0.471902 0 0.881651 0.471902 0 0.953351 0.301864 0 0.953351 0.301864 0 0.992586 0.121546 0 0.992586 0.121546 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.993197 0.11645 0 0.993197 0.11645 0 0.957886 0.287147 0 0.957886 0.287147 0 0.893471 0.44912 0 0.893471 0.44912 0 0.801909 0.597447 0 0.801909 0.597447 0 0.68598 0.72762 0 0.68598 0.72762 0 0.549209 0.835685 0 0.549209 0.835685 0 0.39575 0.918358 0 0.39575 0.918358 0 0.230266 0.973128 0 0.230266 0.973128 0 0.0577859 0.998329 0 0.0577859 0.998329 0 -0.11645 0.993197 0 -0.11645 0.993197 0 -0.287147 0.957887 0 -0.287147 0.957887 0 -0.44912 0.893471 0 -0.44912 0.893471 0 -0.597447 0.801908 0 -0.597447 0.801908 0 -0.72762 0.68598 0 -0.72762 0.68598 0 -0.835685 0.549209 0 -0.835685 0.549209 0 -0.918358 0.39575 0 -0.918358 0.39575 0 -0.973128 0.230266 0 -0.973128 0.230266 0 -0.998329 0.0577866 0 -0.998329 0.0577866 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.993197 0.11645 0 0.993197 0.11645 0 0.957886 0.287147 0 0.957886 0.287147 0 0.893471 0.44912 0 0.893471 0.44912 0 0.801909 0.597447 0 0.801909 0.597447 0 0.68598 0.72762 0 0.68598 0.72762 0 0.549209 0.835685 0 0.549209 0.835685 0 0.39575 0.918358 0 0.39575 0.918358 0 0.230266 0.973128 0 0.230266 0.973128 0 0.0577861 0.998329 0 0.0577861 0.998329 0 -0.11645 0.993197 0 -0.11645 0.993197 0 -0.287147 0.957886 0 -0.287147 0.957886 0 -0.44912 0.893471 0 -0.44912 0.893471 0 -0.597447 0.801909 0 -0.597447 0.801909 0 -0.72762 0.68598 0 -0.72762 0.68598 0 -0.835685 0.549209 0 -0.835685 0.549209 0 -0.918358 0.39575 0 -0.918358 0.39575 0 -0.973128 0.230267 0 -0.973128 0.230267 0 -0.998329 0.0577861 0 -0.998329 0.0577861 -0.80997 -0.585492 0.0338899 -0.809969 -0.585493 0.0338897 -0.809969 -0.570713 0.135045 -0.809969 -0.570713 0.135045 -0.809969 -0.538593 0.232097 -0.809968 -0.538593 0.232097 -0.809968 -0.490108 0.322096 -0.809969 -0.490107 0.322096 -0.809969 -0.42673 0.402309 -0.809968 -0.42673 0.402309 -0.809968 -0.350387 0.470298 -0.809969 -0.350386 0.470298 -0.809969 -0.263397 0.523997 -0.809969 -0.263397 0.523997 -0.809969 -0.168404 0.561775 -0.809969 -0.168404 0.561775 -0.809969 -0.0682945 0.582483 -0.809969 -0.0682948 0.582483 -0.809969 0.03389 0.585493 -0.809969 0.03389 0.585493 -0.809968 0.135045 0.570714 -0.809969 0.135045 0.570713 -0.809969 0.232097 0.538593 -0.809968 0.232097 0.538593 -0.809968 0.322096 0.490107 -0.809969 0.322096 0.490107 -0.809969 0.402309 0.42673 -0.809969 0.402309 0.42673 -0.809969 0.470298 0.350386 -0.809969 0.470298 0.350387 -0.809969 0.523997 0.263397 -0.809968 0.523997 0.263397 -0.809969 0.561775 0.168404 -0.809969 0.561775 0.168404 -0.809969 0.582483 0.0682947 -0.809969 0.582483 0.0682947 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.991013 0.133766 0 0.991013 0.133766 0 0.941545 0.336886 0 0.941545 0.336886 0 0.850928 0.525282 0 0.850928 0.525282 0 0.723121 0.690722 0 0.723121 0.690722 0 0.56371 0.825973 0 0.56371 0.825973 0 0.379662 0.925125 0 0.379662 0.925125 0 0.179021 0.983845 0 0.179021 0.983845 0 -0.0294438 0.999566 0 -0.0294438 0.999566 0 -0.236622 0.971602 0 -0.236622 0.971602 0 -0.433458 0.901174 0 -0.433458 0.901174 0 -0.611351 0.79136 0 -0.611351 0.79136 0 -0.762525 0.646959 0 -0.762525 0.646959 0 -0.880372 0.474284 0 -0.880372 0.474284 0 -0.959743 0.28088 0 -0.959743 0.28088 0 -0.997168 0.0752008 0 -0.997168 0.0752008 0 0.991013 0.133766 0.142203 0.981787 0.125983 0 0.97313 0.230256 0 0.941545 0.336886 0.276155 0.909092 0.311912 0 0.90677 0.421627 0 0.861077 0.508474 0.330669 0.803061 0.495733 0.443078 0.505356 0.740471 0 0.803211 0.595695 0 0.740954 0.671556 0.396032 0.663996 0.634246 0 0.666698 0.745328 0 0.590433 0.807087 0.4927 0.155784 0.856141 0 0.502835 0.864382 0 0.41569 0.909506 0.474615 0.334176 0.814289 0 0.318343 0.947976 0 0.223892 0.974614 0 0.120791 0.992678 0 0.0229099 0.999738 0.498596 -0.0255229 0.866459 0 -0.0817167 0.996656 0 -0.179012 0.983847 0.492705 -0.205908 0.845484 0 -0.280873 0.959745 0 -0.37359 0.927594 0.474616 -0.381527 0.793207 0 -0.468505 0.883461 0 -0.552843 0.833286 0.443077 -0.548066 0.709441 0 -0.636916 0.770933 0 -0.709415 0.704791 0.396024 -0.700181 0.594064 0 -0.779198 0.626777 0 -0.836881 0.547385 0.330677 -0.830846 0.447603 0 -0.889514 0.456907 0 -0.930013 0.367525 0.243935 -0.930751 0.272395 0 -0.997639 0.0686724 0.13352 -0.98824 0.0745275 0 -0.984995 0.172585 0 -0.963337 0.268293 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.991013 -0.133766 0.142212 -0.981786 -0.125983 0 -0.973128 -0.230263 0 -0.941546 -0.336885 0.276157 -0.909092 -0.311912 0.396031 -0.663997 -0.634246 0 -0.90677 -0.421627 0 -0.861077 -0.508474 0.330672 -0.80306 -0.495733 0 -0.80321 -0.595696 0 -0.740954 -0.671556 0.47461 -0.334177 -0.814292 0 -0.666699 -0.745327 0 -0.590433 -0.807087 0.443078 -0.505356 -0.740471 0 -0.502835 -0.864382 0 -0.415689 -0.909507 0.498596 0.0255229 -0.866459 0 -0.318343 -0.947976 0 -0.223893 -0.974614 0.492706 -0.155783 -0.856138 0 -0.12079 -0.992678 0 -0.0229099 -0.999738 0 0.0817166 -0.996656 0 0.179012 -0.983847 0.492703 0.205908 -0.845486 0 0.280872 -0.959745 0 0.373591 -0.927593 0.474608 0.381529 -0.793211 0 0.468504 -0.883462 0 0.552843 -0.833286 0.443079 0.548065 -0.70944 0 0.636916 -0.770933 0 0.709413 -0.704793 0.396034 0.700177 -0.594061 0 0.779199 -0.626777 0 0.836882 -0.547384 0.330669 0.830848 -0.447604 0 0.889514 -0.456908 0 0.930016 -0.367519 0.243918 0.930755 -0.272397 0 0.997639 -0.0686726 0.133511 0.988241 -0.0745274 0 0.984996 -0.172579 0 0.963337 -0.268294 0 -0.991013 -0.133766 0 -0.991013 -0.133766 0 -0.941546 -0.336885 0 -0.941546 -0.336885 0 -0.850928 -0.525282 0 -0.850928 -0.525282 0 -0.723121 -0.690721 0 -0.723121 -0.690721 0 -0.56371 -0.825973 0 -0.56371 -0.825973 0 -0.379662 -0.925125 0 -0.379662 -0.925125 0 -0.179021 -0.983845 0 -0.179021 -0.983845 0 0.0294438 -0.999566 0 0.0294438 -0.999566 0 0.236622 -0.971602 0 0.236622 -0.971602 0 0.433458 -0.901174 0 0.433458 -0.901174 0 0.611351 -0.791359 0 0.611351 -0.791359 0 0.762524 -0.646959 0 0.762524 -0.646959 0 0.880372 -0.474284 0 0.880372 -0.474284 0 0.959743 -0.28088 0 0.959743 -0.28088 0 0.997168 -0.0752006 0 0.997168 -0.0752006 -0.809969 0.585493 -0.0338901 -0.809969 0.585493 -0.03389 -0.809969 0.570713 -0.135045 -0.809969 0.570714 -0.135045 -0.809968 0.538593 -0.232097 -0.809969 0.538592 -0.232097 -0.809969 0.490107 -0.322096 -0.809968 0.490107 -0.322096 -0.809968 0.42673 -0.402309 -0.809968 0.42673 -0.402309 -0.809969 0.350387 -0.470298 -0.809969 0.350386 -0.470298 -0.809969 0.263397 -0.523997 -0.809968 0.263397 -0.523997 -0.809968 0.168404 -0.561775 -0.809968 0.168404 -0.561775 -0.809968 0.0682948 -0.582483 -0.809969 0.0682947 -0.582483 -0.809969 -0.0338902 -0.585493 -0.809968 -0.0338902 -0.585494 -0.809968 -0.135045 -0.570714 -0.809969 -0.135045 -0.570713 -0.809969 -0.232097 -0.538593 -0.809969 -0.232097 -0.538593 -0.809969 -0.322096 -0.490107 -0.809969 -0.322096 -0.490107 -0.809969 -0.402309 -0.42673 -0.809969 -0.402309 -0.426729 -0.809969 -0.470298 -0.350386 -0.809968 -0.470298 -0.350387 -0.809968 -0.523997 -0.263397 -0.809969 -0.523997 -0.263397 -0.809969 -0.561775 -0.168405 -0.809969 -0.561774 -0.168404 -0.809969 -0.582482 -0.0682945 -0.80997 -0.582482 -0.0682942 0 -0.993197 -0.11645 0 -0.993197 -0.11645 0 -0.957886 -0.287148 0 -0.957886 -0.287148 0 -0.893471 -0.44912 0 -0.893471 -0.44912 0 -0.801909 -0.597447 0 -0.801909 -0.597447 0 -0.68598 -0.72762 0 -0.68598 -0.72762 0 -0.549209 -0.835685 0 -0.549209 -0.835685 0 -0.39575 -0.918358 0 -0.39575 -0.918358 0 -0.230266 -0.973128 0 -0.230266 -0.973128 0 -0.0577864 -0.998329 0 -0.0577864 -0.998329 0 0.11645 -0.993197 0 0.11645 -0.993197 0 0.287147 -0.957886 0 0.287147 -0.957886 0 0.44912 -0.893471 0 0.44912 -0.893471 0 0.597447 -0.801908 0 0.597447 -0.801908 0 0.72762 -0.68598 0 0.72762 -0.68598 0 0.835685 -0.549209 0 0.835685 -0.549209 0 0.918358 -0.39575 0 0.918358 -0.39575 0 0.973128 -0.230266 0 0.973128 -0.230266 0 0.998329 -0.0577862 0 0.998329 -0.0577862 0 -0.993197 -0.11645 0 -0.993197 -0.11645 0 -0.957886 -0.287148 0 -0.957886 -0.287148 0 -0.893472 -0.44912 0 -0.893472 -0.44912 0 -0.801909 -0.597447 0 -0.801909 -0.597447 0 -0.68598 -0.72762 0 -0.68598 -0.72762 0 -0.549209 -0.835685 0 -0.549209 -0.835685 0 -0.395749 -0.918359 0 -0.395749 -0.918359 0 -0.230266 -0.973128 0 -0.230266 -0.973128 0 -0.0577863 -0.998329 0 -0.0577863 -0.998329 0 0.11645 -0.993197 0 0.11645 -0.993197 0 0.287148 -0.957886 0 0.287148 -0.957886 0 0.44912 -0.893471 0 0.44912 -0.893471 0 0.597447 -0.801909 0 0.597447 -0.801909 0 0.72762 -0.68598 0 0.72762 -0.68598 0 0.835685 -0.549209 0 0.835685 -0.549209 0 0.918358 -0.39575 0 0.918358 -0.39575 0 0.973128 -0.230266 0 0.973128 -0.230266 0 0.998329 -0.0577862 0 0.998329 -0.0577862 0 0.998019 -0.0629097 0 0.998019 -0.0629097 0 0.969466 -0.245225 0 0.969466 -0.245225 0 0.907899 -0.419188 0 0.907899 -0.419188 0 0.815415 -0.578877 0 0.815415 -0.578877 0 0.695163 -0.718853 0 0.695163 -0.718853 0 0.551238 -0.834348 0 0.551238 -0.834348 0 0.38854 -0.921432 0 0.38854 -0.921432 0 0.212613 -0.977137 0 0.212613 -0.977137 0 0.0294437 -0.999566 0 0.0294437 -0.999566 0 -0.154727 -0.987957 0 -0.154727 -0.987957 0 -0.33363 -0.942704 0 -0.33363 -0.942704 0 -0.50117 -0.865349 0 -0.50117 -0.865349 0 -0.651644 -0.758525 0 -0.651644 -0.758525 0 -0.779927 -0.62587 0 -0.779927 -0.62587 0 -0.881651 -0.471902 0 -0.881651 -0.471902 0 -0.953351 -0.301864 0 -0.953351 -0.301864 0 -0.992586 -0.121547 0 -0.992586 -0.121547 0 0.998019 -0.062911 0 0.998019 -0.062911 0 0.969466 -0.245224 0 0.969466 -0.245224 0 0.907899 -0.419188 0 0.907899 -0.419188 0 0.815415 -0.578877 0 0.815415 -0.578877 0 0.695163 -0.718852 0 0.695163 -0.718852 0 0.551238 -0.834348 0 0.551238 -0.834348 0 0.388541 -0.921432 0 0.388541 -0.921432 0 0.212612 -0.977137 0 0.212612 -0.977137 0 0.0294441 -0.999566 0 0.0294441 -0.999566 0 -0.154727 -0.987957 0 -0.154727 -0.987957 0 -0.333629 -0.942704 0 -0.333629 -0.942704 0 -0.501171 -0.865349 0 -0.501171 -0.865349 0 -0.651644 -0.758525 0 -0.651644 -0.758525 0 -0.779927 -0.62587 0 -0.779927 -0.62587 0 -0.881651 -0.471902 0 -0.881651 -0.471902 0 -0.953351 -0.301864 0 -0.953351 -0.301864 0 -0.992586 -0.121547 0 -0.992586 -0.121547 0 -0.992586 -0.121546 0 -0.992586 -0.121546 0 -0.953351 -0.301864 0 -0.953351 -0.301864 0 -0.881651 -0.471902 0 -0.881651 -0.471902 0 -0.779927 -0.62587 0 -0.779927 -0.62587 0 -0.651644 -0.758525 0 -0.651644 -0.758525 0 -0.50117 -0.865349 0 -0.50117 -0.865349 0 -0.33363 -0.942704 0 -0.33363 -0.942704 0 -0.154727 -0.987957 0 -0.154727 -0.987957 0 0.0294436 -0.999566 0 0.0294436 -0.999566 0 0.212613 -0.977137 0 0.212613 -0.977137 0 0.388541 -0.921432 0 0.388541 -0.921432 0 0.551237 -0.834349 0 0.551237 -0.834349 0 0.695163 -0.718852 0 0.695163 -0.718852 0 0.815415 -0.578877 0 0.815415 -0.578877 0 0.907899 -0.419188 0 0.907899 -0.419188 0 0.969466 -0.245225 0 0.969466 -0.245225 0 0.998019 -0.06291 0 0.998019 -0.06291 0 0.998019 -0.0629097 0 0.998019 -0.0629097 0 0.969466 -0.245225 0 0.969466 -0.245225 0 0.9079 -0.419188 0 0.9079 -0.419188 0 0.815415 -0.578877 0 0.815415 -0.578877 0 0.695163 -0.718852 0 0.695163 -0.718852 0 0.551237 -0.834348 0 0.551237 -0.834348 0 0.388541 -0.921432 0 0.388541 -0.921432 0 0.212612 -0.977137 0 0.212612 -0.977137 0 0.0294439 -0.999566 0 0.0294439 -0.999566 0 -0.154727 -0.987957 0 -0.154727 -0.987957 0 -0.33363 -0.942704 0 -0.33363 -0.942704 0 -0.50117 -0.865349 0 -0.50117 -0.865349 0 -0.651644 -0.758525 0 -0.651644 -0.758525 0 -0.779927 -0.62587 0 -0.779927 -0.62587 0 -0.881651 -0.471902 0 -0.881651 -0.471902 0 -0.953351 -0.301864 0 -0.953351 -0.301864 0 -0.992586 -0.121547 0 -0.992586 -0.121547 0.980541 -0.0237128 -0.194877 0.980398 -0.195426 -0.025077 0.980398 -0.195426 -0.025077 0.980398 -0.170953 -0.0979543 0.979269 -0.174423 -0.102998 0.980577 -0.177847 -0.0826946 0.980398 -0.186778 -0.062721 0.979846 -0.188942 -0.0648265 0.98058 -0.19085 -0.0451591 0.980398 -0.120455 -0.155919 0.978033 -0.123074 -0.168235 0.980568 -0.130793 -0.146219 0.980398 -0.148559 -0.129424 0.978666 -0.152237 -0.137978 0.980573 -0.157551 -0.116847 0.980398 -0.0516179 -0.190146 0.976678 -0.0480722 -0.20926 0.980552 -0.0624784 -0.186051 0.980398 -0.0877218 -0.176422 0.977372 -0.0879306 -0.192388 0.980561 -0.0986647 -0.169606 0.97595 -0.00499427 -0.217939 0.980398 -0.0135305 -0.196563 0.980529 0.0160471 -0.195718 0.978323 0.0263571 -0.205401 0.980541 0.0351426 -0.193143 0.980515 0.0551754 -0.188536 0.978403 0.0658025 -0.195955 0.980552 0.0733215 -0.182051 0.9805 0.0920705 -0.173618 0.978561 0.102395 -0.178702 0.980561 0.108477 -0.163505 0.980483 0.125221 -0.15157 0.978794 0.134558 -0.154452 0.980568 0.139173 -0.138267 0.980464 0.153268 -0.123286 0.9791 0.160944 -0.124337 0.980574 0.164156 -0.10737 0.980444 0.175057 -0.0899196 0.979473 0.180493 -0.0897457 0.980578 0.182406 -0.0720823 0.980422 0.189691 -0.0528297 0.979908 0.192484 -0.0522525 0.98058 0.193177 -0.0338461 0.980398 0.196563 -0.0135304 0.980398 0.196563 -0.0135304 0 0.981057 -0.19372 -0.101693 0.968082 -0.229074 0 0.897488 -0.44104 0 0.72762 -0.68598 -0.231189 0.755804 -0.612628 0 0.587404 -0.809294 0 0.287148 -0.957886 -0.335399 0.369851 -0.86644 0 0.141176 -0.989985 0 -0.0826574 -0.996578 -0.200842 -0.225575 -0.953299 0 -0.337776 -0.941227 0 -0.538747 -0.842468 -0.168255 -0.6762 -0.717247 0 -0.967954 -0.251127 -0.101694 -0.952921 -0.285657 0 -0.869972 -0.493102 0 -0.738437 -0.674323 -0.698073 -0.69308 -0.179816 -0.698072 -0.693082 -0.179814 -0.706858 -0.615379 -0.348798 -0.693897 -0.549514 -0.465341 -0.700861 -0.526726 -0.480993 -0.706115 -0.381485 -0.596549 -0.691347 -0.294188 -0.659918 -0.703123 -0.240181 -0.669276 -0.704872 -0.0586318 -0.706907 -0.69049 0.0212979 -0.723028 -0.704872 0.100141 -0.70223 -0.698073 0.329532 -0.635691 -0.680457 0.287686 -0.673954 -0.706115 0.415939 -0.573058 -0.698073 0.572714 -0.429759 -0.698072 0.702464 -0.138709 -0.698073 0.702463 -0.138707 -0.706859 0.634842 -0.311972 -0.689671 0.562534 -0.45597 0 0.973128 -0.230265 0 0.973128 -0.230265 0 0.72762 -0.68598 0 0.72762 -0.68598 0 0.287146 -0.957887 0 0.287146 -0.957887 0 -0.230267 -0.973128 0 -0.230267 -0.973128 0 -0.68598 -0.72762 0 -0.68598 -0.72762 0 -0.957886 -0.287148 0 -0.957886 -0.287148 -0.704845 -0.70219 -0.100612 -0.71628 -0.668426 -0.200376 -0.694746 0.699927 -0.165619 -0.694746 0.699928 -0.16562 -0.694746 0.523345 -0.493395 -0.694745 0.523345 -0.493396 -0.694745 0.206532 -0.688966 -0.694746 0.206532 -0.688965 -0.694746 -0.165621 -0.699928 -0.694746 -0.16562 -0.699928 -0.694746 -0.493395 -0.523345 -0.694746 -0.493395 -0.523345 -0.703159 -0.65376 -0.279581 0 0.973127 -0.230268 0 0.973127 -0.230268 0 0.727619 -0.685982 0 0.727619 -0.685982 0 0.287146 -0.957887 0 0.287146 -0.957887 0 -0.230264 -0.973128 0 -0.230264 -0.973128 0 -0.685982 -0.727619 0 -0.685982 -0.727619 0 -0.957887 -0.287145 0 -0.957887 -0.287145 -0.694745 0.699928 -0.165621 -0.694745 0.699928 -0.165619 -0.694745 0.523344 -0.493396 -0.694746 0.523344 -0.493395 -0.694745 0.206531 -0.688966 -0.694746 0.206532 -0.688965 -0.694746 -0.165619 -0.699928 -0.694745 -0.165619 -0.699928 -0.694745 -0.493396 -0.523344 -0.694746 -0.493395 -0.523344 -0.694746 -0.688966 -0.206531 -0.694746 -0.688965 -0.206531 0 0.973129 -0.230261 0 0.973129 -0.230261 0 0.727618 -0.685983 0 0.727618 -0.685983 0 0.287149 -0.957886 0 0.287149 -0.957886 0 -0.230266 -0.973128 0 -0.230266 -0.973128 0 -0.685982 -0.727619 0 -0.685982 -0.727619 0 -0.957885 -0.287152 0 -0.957885 -0.287152 -0.694746 0.699928 -0.165616 -0.694745 0.699928 -0.165619 -0.694745 0.523344 -0.493397 -0.694746 0.523345 -0.493395 -0.694746 0.206533 -0.688965 -0.694746 0.206532 -0.688965 -0.694745 -0.16562 -0.699928 -0.694745 -0.16562 -0.699928 -0.694745 -0.493396 -0.523344 -0.694746 -0.493395 -0.523345 -0.694746 -0.688963 -0.206535 -0.694745 -0.688966 -0.206531 0 0.973129 -0.230261 0 0.973129 -0.230261 0 0.727619 -0.685982 0 0.727619 -0.685982 0 0.287148 -0.957886 0 0.287148 -0.957886 0 -0.230266 -0.973128 0 -0.230266 -0.973128 0 -0.685982 -0.727619 0 -0.685982 -0.727619 0 -0.957885 -0.287152 0 -0.957885 -0.287152 -0.694746 0.699928 -0.165617 -0.694745 0.699928 -0.165619 -0.694745 0.523344 -0.493397 -0.694746 0.523344 -0.493395 -0.694746 0.206533 -0.688965 -0.694745 0.206532 -0.688965 -0.694746 -0.16562 -0.699927 -0.694746 -0.165621 -0.699927 -0.694745 -0.493396 -0.523344 -0.694746 -0.493395 -0.523345 -0.694746 -0.688963 -0.206535 -0.694745 -0.688966 -0.206531 0 0.973129 -0.230261 0 0.973129 -0.230261 0 0.727618 -0.685983 0 0.727618 -0.685983 0 0.287149 -0.957886 0 0.287149 -0.957886 0 -0.230266 -0.973128 0 -0.230266 -0.973128 0 -0.685982 -0.727619 0 -0.685982 -0.727619 0 -0.957885 -0.287152 0 -0.957885 -0.287152 -0.694746 0.699928 -0.165616 -0.694745 0.699928 -0.165619 -0.694745 0.523344 -0.493397 -0.694746 0.523344 -0.493396 -0.694746 0.206533 -0.688965 -0.694745 0.206532 -0.688965 -0.694746 -0.16562 -0.699927 -0.694746 -0.16562 -0.699928 -0.694745 -0.493396 -0.523344 -0.694746 -0.493395 -0.523345 -0.694746 -0.688963 -0.206535 -0.694745 -0.688966 -0.206531 0 0.981058 -0.193717 -0.101683 0.968085 -0.229068 0 0.897501 -0.441012 0 0.727619 -0.685982 -0.231196 0.755802 -0.612627 0 0.587399 -0.809298 0 0.287146 -0.957887 -0.335404 0.36985 -0.866438 0 0.141173 -0.989985 0 -0.0826536 -0.996578 -0.200844 -0.225572 -0.953299 0 -0.337774 -0.941227 0 -0.538751 -0.842465 -0.168254 -0.676202 -0.717246 0 -0.967952 -0.251134 -0.10169 -0.95292 -0.285662 0 -0.869974 -0.493097 0 -0.738438 -0.674321 -0.698072 -0.693081 -0.179816 -0.698073 -0.69308 -0.179819 -0.706858 -0.615381 -0.348794 -0.693897 -0.549514 -0.46534 -0.700861 -0.526727 -0.480992 -0.706115 -0.381488 -0.596547 -0.691347 -0.294188 -0.659918 -0.703124 -0.24018 -0.669276 -0.704872 -0.058629 -0.706907 -0.690491 0.0212979 -0.723028 -0.704872 0.100139 -0.70223 -0.698073 0.329533 -0.635691 -0.680457 0.287686 -0.673955 -0.706115 0.415935 -0.573062 -0.698072 0.572715 -0.429759 -0.698073 0.702463 -0.138706 -0.698073 0.702463 -0.138707 -0.706859 0.634851 -0.311952 -0.689671 0.562535 -0.455971 0 0.981057 -0.19372 -0.101692 0.968083 -0.229074 0 0.89749 -0.441035 0 0.72762 -0.68598 -0.231189 0.755804 -0.612628 0 0.587404 -0.809294 0 0.287146 -0.957887 -0.335398 0.369849 -0.866441 0 0.141174 -0.989985 0 -0.0826536 -0.996578 -0.200844 -0.225572 -0.953299 0 -0.337774 -0.941227 0 -0.538751 -0.842465 -0.168253 -0.676201 -0.717247 0 -0.967954 -0.251128 -0.101694 -0.952921 -0.285657 0 -0.869972 -0.493102 0 -0.738437 -0.674323 -0.698073 -0.69308 -0.179816 -0.698072 -0.693081 -0.179814 -0.706858 -0.615379 -0.348798 -0.693897 -0.549514 -0.465341 -0.700861 -0.526726 -0.480993 -0.706115 -0.381488 -0.596547 -0.691347 -0.294188 -0.659918 -0.703124 -0.24018 -0.669276 -0.704872 -0.058629 -0.706907 -0.690491 0.0212979 -0.723028 -0.704872 0.10014 -0.70223 -0.698073 0.329532 -0.635691 -0.680457 0.287684 -0.673956 -0.706115 0.415939 -0.573058 -0.698073 0.572714 -0.429759 -0.698072 0.702464 -0.138709 -0.698073 0.702463 -0.138707 -0.706859 0.634844 -0.311968 -0.689671 0.562534 -0.45597 0 0.981058 -0.193716 -0.101694 0.968083 -0.229071 0 0.897488 -0.44104 0 0.72762 -0.68598 -0.231193 0.755804 -0.612626 0 0.5874 -0.809296 0 0.287147 -0.957886 -0.335401 0.369851 -0.866439 0 0.141174 -0.989985 0 -0.0826574 -0.996578 -0.200841 -0.225574 -0.953299 0 -0.337774 -0.941227 0 -0.538747 -0.842468 -0.168255 -0.6762 -0.717247 0 -0.967953 -0.251131 -0.101693 -0.95292 -0.28566 0 -0.869972 -0.493102 0 -0.738437 -0.674323 -0.698072 -0.693081 -0.179816 -0.698073 -0.693081 -0.179816 -0.706858 -0.615379 -0.348798 -0.693897 -0.549514 -0.46534 -0.700861 -0.526725 -0.480993 -0.706115 -0.381485 -0.596549 -0.691347 -0.294187 -0.659919 -0.703124 -0.24018 -0.669276 -0.704872 -0.0586318 -0.706907 -0.69049 0.0212979 -0.723028 -0.704872 0.10014 -0.70223 -0.698073 0.329532 -0.635691 -0.680457 0.287686 -0.673954 -0.706115 0.415936 -0.573061 -0.698072 0.572715 -0.429759 -0.698073 0.702463 -0.138706 -0.698072 0.702464 -0.138708 -0.706858 0.634843 -0.311972 -0.689671 0.562535 -0.45597 0 0.981057 -0.193719 -0.0239936 0.972848 -0.2302 0 0.897492 -0.441031 0 0.776848 -0.629688 -0.0400436 0.727036 -0.68543 0 0.587406 -0.809293 0 0.392591 -0.919713 -0.0480812 0.286815 -0.956779 0 0.141174 -0.989985 0 -0.0826576 -0.996578 -0.0480809 -0.23 -0.972002 0 -0.337773 -0.941228 0 -0.53875 -0.842466 -0.040044 -0.68543 -0.727036 0 -0.967953 -0.251131 -0.0239932 -0.957611 -0.287064 0 -0.869977 -0.493092 0 -0.738437 -0.674323 0 0.973128 -0.230266 0 0.973128 -0.230266 0 0.72762 -0.68598 0 0.72762 -0.68598 0 0.287147 -0.957887 0 0.287147 -0.957887 0 -0.230266 -0.973128 0 -0.230266 -0.973128 0 -0.685981 -0.72762 0 -0.685981 -0.72762 0 -0.957886 -0.287149 0 -0.957886 -0.287149 0 0.981057 -0.193717 -0.0239936 0.972848 -0.230198 0.0200491 0.799689 -0.600079 0 0.776848 -0.629689 0 0.587406 -0.809292 0.0321125 0.459988 -0.887344 0 0.392592 -0.919713 0 0.141174 -0.989985 0.0361378 0.0294243 -0.998914 0 -0.0826567 -0.996578 0 -0.337773 -0.941228 0.0321125 -0.406957 -0.912883 0 -0.53875 -0.842466 0 -0.763135 -0.646239 0.0239955 -0.738224 -0.674129 -0.027904 -0.967576 -0.251033 0 -0.957887 -0.287146 0 0.981057 -0.193717 -0.0239936 0.972848 -0.230198 0.0200491 0.799689 -0.600079 0 0.776848 -0.629689 0 0.587403 -0.809294 0.032112 0.459987 -0.887345 0 0.392592 -0.919713 0 0.141176 -0.989985 0.0361382 0.0294253 -0.998914 0 -0.0826563 -0.996578 0 -0.337776 -0.941227 0.0321116 -0.406958 -0.912882 0 -0.538747 -0.842467 0 -0.763134 -0.64624 0.0239933 -0.738225 -0.674128 -0.0279059 -0.967577 -0.251031 0 -0.957887 -0.287147 0 0.973127 -0.230268 0 0.973127 -0.230268 0 0.727621 -0.68598 0 0.727621 -0.68598 0 0.287147 -0.957886 0 0.287147 -0.957886 0 -0.230267 -0.973127 0 -0.230267 -0.973127 0 -0.68598 -0.72762 0 -0.68598 -0.72762 0 -0.957886 -0.28715 0 -0.957886 -0.28715 0 0.981057 -0.193721 -0.0239933 0.972847 -0.230201 0.0200488 0.799689 -0.600079 0 0.776848 -0.629688 0 0.587409 -0.80929 0.0321132 0.459987 -0.887345 0 0.392589 -0.919714 0 0.141175 -0.989985 0.0361379 0.0294249 -0.998914 0 -0.082657 -0.996578 0 -0.337772 -0.941228 0.0321126 -0.406957 -0.912883 0 -0.53875 -0.842466 0 -0.763136 -0.646238 0.0239958 -0.738224 -0.674129 -0.0279026 -0.967576 -0.251035 0 -0.957887 -0.287147 0 0.973128 -0.230264 0 0.973128 -0.230264 0 0.727619 -0.685981 0 0.727619 -0.685981 0 0.287148 -0.957886 0 0.287148 -0.957886 0 -0.230266 -0.973128 0 -0.230266 -0.973128 0 -0.68598 -0.72762 0 -0.68598 -0.72762 0 -0.957887 -0.287147 0 -0.957887 -0.287147 0 0.981057 -0.193717 0.0239961 0.972847 -0.230201 0 0.897483 -0.44105 0 0.77685 -0.629686 0.0400448 0.727037 -0.685429 0 0.587403 -0.809294 0 0.392592 -0.919713 0.0480814 0.286815 -0.956779 0 0.141175 -0.989985 0 -0.0826593 -0.996578 0.0480807 -0.230001 -0.972002 0 -0.337774 -0.941227 0 -0.53875 -0.842466 0.040044 -0.68543 -0.727036 0 -0.738437 -0.674322 0 -0.869971 -0.493103 0.0239947 -0.957611 -0.287064 0 -0.967954 -0.251129 0 0.973128 -0.230264 0 0.973128 -0.230264 0 0.72762 -0.685981 0 0.72762 -0.685981 0 0.287148 -0.957886 0 0.287148 -0.957886 0 -0.230266 -0.973128 0 -0.230266 -0.973128 0 -0.685981 -0.72762 0 -0.685981 -0.72762 0 -0.957887 -0.287147 0 -0.957887 -0.287147 0 0.981058 -0.193717 -0.0239937 0.972848 -0.230197 0 0.897493 -0.441029 0 0.776848 -0.629689 -0.0400442 0.727035 -0.685431 0 0.587403 -0.809294 0 0.39259 -0.919713 -0.0480809 0.286815 -0.956779 0 0.141175 -0.989985 0 -0.0826567 -0.996578 -0.0480813 -0.23 -0.972002 0 -0.337774 -0.941227 0 -0.538752 -0.842465 -0.0400435 -0.68543 -0.727036 0 -0.967953 -0.251131 -0.0239945 -0.95761 -0.287066 0 -0.869971 -0.493103 0 -0.738437 -0.674323 0 0.973127 -0.230268 0 0.973127 -0.230268 0 0.727621 -0.685979 0 0.727621 -0.685979 0 0.287146 -0.957887 0 0.287146 -0.957887 0 -0.230266 -0.973128 0 -0.230266 -0.973128 0 -0.685981 -0.72762 0 -0.685981 -0.72762 0 -0.957887 -0.287147 0 -0.957887 -0.287147 0 0.981057 -0.193719 -0.0239936 0.972848 -0.2302 0.0200484 0.79969 -0.600078 0 0.776849 -0.629687 0 0.587402 -0.809295 0.032112 0.459985 -0.887346 0 0.392591 -0.919713 0 0.141175 -0.989985 0.036138 0.0294248 -0.998914 0 -0.0826567 -0.996578 0 -0.337774 -0.941227 0.0321124 -0.406958 -0.912882 0 -0.53875 -0.842466 0 -0.763135 -0.646239 0.0239947 -0.738224 -0.674129 -0.0279042 -0.967576 -0.251033 0 -0.957887 -0.287147 0.705149 -0.667612 -0.238872 0.705148 -0.702687 -0.0948474 0.705157 -0.702679 -0.0948468 0.707032 -0.551128 -0.44313 0.705686 -0.597087 -0.381438 0.521926 -0.725834 -0.448061 0.707058 -0.632462 -0.316324 0.705155 -0.667605 -0.23887 0.511604 -0.627896 -0.586522 0.342805 -0.679305 -0.648868 0.632118 -0.531397 -0.563953 0.705156 0.167777 -0.688916 0.705156 0.0208774 -0.708744 0.705153 0.0208772 -0.708747 0.705153 -0.126936 -0.6976 0.705152 -0.126936 -0.697602 0.705151 -0.269202 -0.655967 0.705156 -0.2692 -0.655962 0.705155 -0.3997 -0.585658 0.705157 -0.399699 -0.585657 0.707022 -0.468863 -0.529421 0.657358 -0.511626 -0.55328 0.705158 0.433478 -0.561113 0.705741 0.317927 -0.633129 0.501519 0.375005 -0.779647 0.707047 0.249547 -0.661672 0.705154 0.167778 -0.688918 0.633297 0.562813 -0.531203 0.707021 0.499214 -0.500906 0.705156 0.43348 -0.561116 0.587909 0.594187 -0.548912 0.329729 0.719881 -0.610779 0.706161 0.554248 -0.44062 0.705155 0.624231 -0.336293 0.705155 0.624231 -0.336293 0.706881 0.663408 -0.245377 0.300696 0.915326 -0.267881 0.706246 0.686037 -0.174845 0.705157 0.707043 -0.0533211 0.705157 0.707043 -0.0533211 -0.705157 0.707043 -0.0533211 -0.705157 0.707043 -0.0533211 -0.705157 0.680506 -0.199158 -0.705154 0.68051 -0.199159 -0.705155 0.624231 -0.336293 -0.705155 0.624231 -0.336293 -0.706049 0.552471 -0.443025 -0.373128 0.707455 -0.600236 -0.628627 0.565906 -0.533459 -0.705158 0.307344 -0.638977 -0.705159 0.433478 -0.561113 -0.705155 0.43348 -0.561116 -0.707058 0.496345 -0.503698 -0.66576 0.536706 -0.518373 -0.705155 -0.3997 -0.585658 -0.705156 -0.2692 -0.655962 -0.705151 -0.269202 -0.655967 -0.705152 -0.126936 -0.697602 -0.705153 -0.126936 -0.6976 -0.705153 0.0208775 -0.708747 -0.705156 0.0208772 -0.708744 -0.707092 0.0997242 -0.700055 -0.622905 0.185109 -0.760082 -0.705418 0.172762 -0.687415 -0.705154 0.307346 -0.638981 -0.665772 -0.505252 -0.54906 -0.707059 -0.465835 -0.532038 -0.705157 -0.399699 -0.585657 -0.628608 -0.533538 -0.565852 -0.373131 -0.670896 -0.640837 -0.706048 -0.525436 -0.474777 -0.705153 -0.603355 -0.372454 -0.705155 -0.603353 -0.372453 -0.706659 -0.686708 -0.170487 -0.673288 -0.69616 -0.249086 -0.697825 -0.673856 -0.242814 -0.7071 -0.637445 -0.306061 -0.707093 -0.686778 -0.168392 -0.705148 -0.702687 -0.094848 -0.705157 -0.702679 -0.0948462 -0.698069 0.702467 -0.138708 -0.698073 0.702464 -0.138706 -0.698073 0.572714 -0.429759 -0.698077 0.572711 -0.429756 -0.698075 0.329532 -0.635689 -0.698066 0.329534 -0.635698 -0.698067 0.0210833 -0.715722 -0.698067 0.0210833 -0.715722 -0.698066 -0.291546 -0.653991 -0.698067 -0.291546 -0.653991 -0.69807 -0.546426 -0.462727 -0.698059 -0.546436 -0.462732 -0.698057 -0.693096 -0.179819 -0.698069 -0.693084 -0.179818 -0.694742 0.699931 -0.165622 -0.694749 0.699924 -0.165619 -0.694746 0.523345 -0.493395 -0.694737 0.52335 -0.493402 -0.69474 0.206534 -0.688971 -0.694741 0.206534 -0.688969 -0.694736 -0.165623 -0.699936 -0.694741 -0.165621 -0.699931 -0.694745 -0.493395 -0.523345 -0.694739 -0.4934 -0.523349 -0.694741 -0.688969 -0.206536 -0.694741 -0.688969 -0.206536 -0.698069 0.702467 -0.13871 -0.698073 0.702463 -0.138709 -0.698072 0.572715 -0.42976 -0.698075 0.572713 -0.429757 -0.698073 0.329533 -0.635691 -0.698073 0.329533 -0.635691 -0.698068 0.0210829 -0.715721 -0.698067 0.0210826 -0.715722 -0.698072 -0.291543 -0.653987 -0.698065 -0.291547 -0.653992 -0.698062 -0.546434 -0.46273 -0.69807 -0.546427 -0.462727 -0.698071 -0.693082 -0.179818 -0.698069 -0.693084 -0.179818 -0.694742 0.699931 -0.16562 -0.694736 0.699936 -0.165622 -0.694738 0.52335 -0.493401 -0.694746 0.523345 -0.493395 -0.694742 0.206534 -0.688968 -0.694739 0.206534 -0.688972 -0.694741 -0.165621 -0.699932 -0.694738 -0.165622 -0.699934 -0.694736 -0.493402 -0.523352 -0.69474 -0.493398 -0.523349 -0.694741 -0.688969 -0.206533 -0.694742 -0.688969 -0.206533 -0.694742 0.699931 -0.165622 -0.694749 0.699924 -0.165619 -0.694746 0.523345 -0.493395 -0.694747 0.523345 -0.493394 -0.694744 0.206533 -0.688967 -0.694741 0.206533 -0.68897 -0.694736 -0.165623 -0.699936 -0.694741 -0.165621 -0.699931 -0.694745 -0.493396 -0.523345 -0.694742 -0.493398 -0.523347 -0.694742 -0.688969 -0.206533 -0.694741 -0.688969 -0.206533 -0.694743 0.69993 -0.165619 -0.694736 0.699936 -0.165622 -0.694738 0.52335 -0.493401 -0.694742 0.523348 -0.493397 -0.694737 0.206535 -0.688973 -0.69474 0.206535 -0.68897 -0.694743 -0.16562 -0.69993 -0.694735 -0.165624 -0.699937 -0.694733 -0.493404 -0.523353 -0.694742 -0.493397 -0.523349 -0.694742 -0.688969 -0.206533 -0.69474 -0.68897 -0.206533 -0.698061 -0.693092 -0.179819 -0.698064 -0.693089 -0.179819 -0.70685 -0.615386 -0.348803 -0.581211 -0.621003 -0.52588 -0.450652 0.0262842 -0.892313 -0.700858 -0.526728 -0.480995 -0.706112 -0.38149 -0.596549 -0.486768 -0.355674 -0.797843 -0.703117 -0.240182 -0.669282 -0.704866 -0.0586317 -0.706913 -0.704869 0.100141 -0.702233 -0.70312 0.27916 -0.653982 -0.486764 0.402022 -0.775525 -0.706105 0.415945 -0.573067 -0.698062 0.572723 -0.429766 -0.69807 0.702466 -0.138707 -0.69806 0.702476 -0.138711 -0.706847 0.634857 -0.311969 -0.547266 0.650189 -0.527023 -0.694742 0.699931 -0.165622 -0.694743 0.699929 -0.165622 -0.694743 0.523347 -0.493396 -0.694739 0.52335 -0.493399 -0.694738 0.206534 -0.688972 -0.694742 0.206533 -0.688968 -0.694741 -0.165621 -0.699932 -0.69474 -0.165622 -0.699933 -0.69474 -0.493399 -0.523348 -0.694742 -0.493398 -0.523347 -0.694742 -0.688969 -0.206533 -0.694741 -0.688969 -0.206533 -0.698069 0.702467 -0.138709 -0.698066 0.70247 -0.13871 -0.698066 0.57272 -0.429763 -0.698064 0.572722 -0.429764 -0.698065 0.329535 -0.635697 -0.69807 0.329534 -0.635693 -0.698069 0.0210829 -0.71572 -0.698067 0.0210825 -0.715722 -0.698066 -0.291546 -0.653991 -0.698068 -0.291544 -0.65399 -0.698068 -0.546428 -0.462727 -0.69807 -0.546427 -0.462727 -0.69807 -0.693083 -0.179817 -0.698069 -0.693084 -0.179817 -0.698069 -0.693084 -0.179817 -0.69807 -0.693083 -0.179817 -0.706856 -0.615385 -0.348792 -0.58121 -0.621004 -0.52588 -0.450652 0.0262844 -0.892313 -0.700856 -0.526729 -0.480996 -0.70611 -0.38149 -0.596552 -0.486769 -0.355674 -0.797842 -0.703121 -0.240181 -0.669279 -0.704868 -0.0586322 -0.706911 -0.704868 0.10014 -0.702234 -0.70312 0.27916 -0.653981 -0.486769 0.40202 -0.775523 -0.706111 0.415942 -0.573061 -0.698069 0.572717 -0.429761 -0.698069 0.702467 -0.138709 -0.698066 0.70247 -0.13871 -0.706852 0.634852 -0.311968 -0.547275 0.650185 -0.527019 -0.694742 0.699931 -0.165621 -0.694743 0.69993 -0.16562 -0.694743 0.523347 -0.493397 -0.69474 0.523349 -0.493399 -0.694738 0.206534 -0.688972 -0.694742 0.206534 -0.688968 -0.694741 -0.165621 -0.699932 -0.69474 -0.165622 -0.699933 -0.69474 -0.493399 -0.523348 -0.694742 -0.493398 -0.523347 -0.694742 -0.688968 -0.206534 -0.694741 -0.688969 -0.206534 -0.698069 0.702467 -0.138708 -0.698073 0.702464 -0.138706 -0.698073 0.572714 -0.429759 -0.698077 0.572711 -0.429756 -0.698075 0.329532 -0.635688 -0.698069 0.329534 -0.635694 -0.698067 0.0210825 -0.715722 -0.698067 0.0210825 -0.715722 -0.698069 -0.291544 -0.653989 -0.698067 -0.291545 -0.653991 -0.698067 -0.54643 -0.462728 -0.69807 -0.546427 -0.462727 -0.69807 -0.693083 -0.179817 -0.698069 -0.693084 -0.179817 0.69474 -0.68897 -0.206534 0.694742 -0.688969 -0.206533 0.694742 -0.493398 -0.523347 0.694733 -0.493402 -0.523354 0.694735 -0.165622 -0.699938 0.694743 -0.165622 -0.69993 0.69474 0.206534 -0.68897 0.694737 0.206535 -0.688973 0.694742 0.523347 -0.493398 0.694738 0.523351 -0.4934 0.694736 0.699937 -0.165621 0.694743 0.69993 -0.165621 0.698069 0.702467 -0.138709 0.698059 0.702476 -0.138709 0.706847 0.634849 -0.311984 0.581214 0.650879 -0.488413 0.450646 0.0262843 -0.892316 0.700852 0.554132 -0.449159 0.706107 0.415943 -0.573065 0.486768 0.40202 -0.775524 0.703117 0.279162 -0.653984 0.704866 0.100141 -0.702236 0.704866 -0.0586335 -0.706913 0.703117 -0.240182 -0.669282 0.486771 -0.355673 -0.797842 0.706113 -0.381488 -0.596549 0.698072 -0.546425 -0.462725 0.698069 -0.693085 -0.179816 0.69807 -0.693083 -0.179815 0.706856 -0.615381 -0.3488 0.54729 -0.61803 -0.564369 0.694742 -0.688969 -0.206533 0.694741 -0.688969 -0.206533 0.694741 -0.493399 -0.523348 0.694736 -0.493401 -0.523352 0.694738 -0.165622 -0.699934 0.694741 -0.165622 -0.699932 0.694739 0.206535 -0.688972 0.694742 0.206533 -0.688969 0.694746 0.523344 -0.493396 0.694738 0.523351 -0.4934 0.694736 0.699937 -0.165621 0.694742 0.699931 -0.165621 0.694741 0.699931 -0.165623 0.322024 0.271851 -0.906861 0.694737 0.699936 -0.165623 0.700853 0.55413 -0.449161 0.406511 0.664788 -0.626743 0.706107 0.415948 -0.573063 0.703116 0.27916 -0.653985 0.704867 0.100141 -0.702235 0.704868 -0.0586318 -0.706911 0.322027 -0.218 -0.92129 0.694742 -0.688969 -0.206533 0.694741 -0.688969 -0.206533 0.700856 -0.526729 -0.480996 0.406502 -0.626745 -0.664791 0.706107 -0.381491 -0.596555 0.703117 -0.240181 -0.669283 0.694741 -0.688969 -0.206536 0.694741 -0.688969 -0.206536 0.694739 -0.493399 -0.523349 0.694745 -0.493396 -0.523345 0.694742 -0.165622 -0.699931 0.694736 -0.165622 -0.699936 0.694741 0.206534 -0.688969 0.69474 0.206534 -0.68897 0.694737 0.523352 -0.493401 0.694745 0.523344 -0.493396 0.694749 0.699924 -0.16562 0.694742 0.699931 -0.165621 0.694741 0.699932 -0.165621 0.322024 0.271851 -0.906862 0.694736 0.699937 -0.165621 0.700853 0.55413 -0.449161 0.406514 0.664787 -0.626742 0.706115 0.415938 -0.573059 0.703122 0.27916 -0.653979 0.704864 0.100142 -0.702238 0.704866 -0.0586315 -0.706914 0.322016 -0.218001 -0.921293 0.694742 -0.688968 -0.206533 0.694742 -0.688969 -0.206533 0.700857 -0.526729 -0.480995 0.406499 -0.626746 -0.664791 0.706109 -0.381489 -0.596554 0.703119 -0.240183 -0.66928 0.694741 0.699932 -0.165621 0.32202 0.271852 -0.906862 0.694736 0.699937 -0.165621 0.700853 0.55413 -0.449161 0.406514 0.664787 -0.626742 0.706111 0.415943 -0.57306 0.70312 0.279161 -0.653981 0.704868 0.10014 -0.702235 0.704869 -0.0586315 -0.70691 0.322026 -0.218 -0.92129 0.694742 -0.688968 -0.206533 0.69474 -0.688971 -0.206534 0.700852 -0.526731 -0.480999 0.406506 -0.626745 -0.664788 0.70611 -0.38149 -0.596552 0.703118 -0.240181 -0.669282 0.694741 -0.688969 -0.206535 0.694742 -0.688968 -0.206534 0.694742 -0.493398 -0.523347 0.69474 -0.493399 -0.523349 0.69474 -0.165621 -0.699933 0.694741 -0.165621 -0.699931 0.694742 0.206533 -0.688968 0.694739 0.206535 -0.688972 0.694739 0.523349 -0.493399 0.694743 0.523346 -0.493397 0.694743 0.69993 -0.165621 0.694742 0.699931 -0.165621 0.694742 -0.688969 -0.206533 0.694741 -0.688969 -0.206533 0.694741 -0.493398 -0.523348 0.69474 -0.493399 -0.523349 0.69474 -0.165622 -0.699933 0.694741 -0.165621 -0.699932 0.694741 0.206533 -0.688969 0.69474 0.206534 -0.68897 0.694741 0.523348 -0.493399 0.694738 0.523351 -0.4934 0.694737 0.699936 -0.165622 0.694742 0.699931 -0.165622 0.694742 0.699931 -0.165622 0.322022 0.271851 -0.906862 0.694737 0.699936 -0.165622 0.700853 0.554131 -0.449159 0.406498 0.664792 -0.626747 0.70611 0.415941 -0.573064 0.703118 0.279161 -0.653983 0.704866 0.100141 -0.702236 0.704867 -0.0586316 -0.706912 0.322022 -0.218001 -0.921291 0.694742 -0.688969 -0.206533 0.694742 -0.688969 -0.206533 0.700857 -0.526728 -0.480996 0.406503 -0.626745 -0.66479 0.706108 -0.381491 -0.596554 0.703117 -0.240182 -0.669282 0.694741 -0.688969 -0.206533 0.694742 -0.688969 -0.206533 0.694742 -0.493398 -0.523347 0.69474 -0.493399 -0.523349 0.69474 -0.165621 -0.699933 0.694741 -0.165621 -0.699931 0.694742 0.206533 -0.688968 0.694738 0.206534 -0.688972 0.694739 0.52335 -0.493398 0.694743 0.523347 -0.493397 0.694743 0.699929 -0.165622 0.694742 0.699931 -0.165622 0.694734 -0.688976 -0.206537 0.694742 -0.688969 -0.206533 0.694742 -0.493398 -0.523347 0.694738 -0.4934 -0.523351 0.694736 -0.165622 -0.699936 0.694741 -0.165622 -0.699931 0.694742 0.206533 -0.688968 0.694744 0.206532 -0.688967 0.694747 0.523343 -0.493395 0.694738 0.523351 -0.4934 0.694736 0.699937 -0.165621 0.694743 0.69993 -0.16562 0.705753 -0.703638 -0.0824996 0.705765 -0.703627 -0.0824987 0.705764 -0.678611 -0.203429 0.705747 -0.678628 -0.203433 0.705748 -0.632991 -0.318185 0.705753 -0.632987 -0.318183 0.705753 -0.568119 -0.423266 0.705757 -0.568116 -0.423264 0.705755 -0.485987 -0.515487 0.705754 -0.485988 -0.515488 0.705754 -0.389091 -0.592047 0.705758 -0.389089 -0.592044 0.705757 -0.280371 -0.650615 0.705754 -0.280372 -0.650617 0.705753 -0.163134 -0.68942 0.705752 -0.163134 -0.689421 0.705751 -0.0409394 -0.707276 0.705752 -0.0409393 -0.707275 0.705754 0.0824998 -0.703637 0.705751 0.0825 -0.70364 0.705751 0.203433 -0.678625 0.705753 0.203432 -0.678622 0.705754 0.318182 -0.632986 0.705753 0.318183 -0.632987 0.705753 0.423266 -0.568119 0.705746 0.42327 -0.568124 0.705746 0.515493 -0.485993 0.70575 0.515491 -0.48599 0.70575 0.59205 -0.389093 0.705754 0.592047 -0.389091 0.705754 0.650617 -0.280372 0.705754 0.650618 -0.280372 0.705753 0.68942 -0.163134 0.705751 0.689422 -0.163134 0.705751 0.707276 -0.0409392 0.705751 0.707276 -0.0409392 0.705589 -0.703367 -0.0861304 0.705587 -0.703369 -0.0861308 0.705587 -0.675567 -0.213908 0.705588 -0.675566 -0.213908 0.705587 -0.624758 -0.334401 0.705587 -0.624758 -0.334401 0.705587 -0.552675 -0.443506 0.705591 -0.552671 -0.443503 0.70559 -0.461768 -0.537506 0.705586 -0.461771 -0.53751 0.705586 -0.355142 -0.613208 0.705591 -0.355139 -0.613203 0.705591 -0.236416 -0.668018 0.705584 -0.236418 -0.668025 0.705583 -0.109644 -0.700093 0.70559 -0.109643 -0.700087 0.705589 0.0208646 -0.708314 0.705588 0.0208647 -0.708315 0.705588 0.150662 -0.692421 0.70559 0.150661 -0.692419 0.705589 0.275328 -0.652946 0.705589 0.275329 -0.652946 0.70559 0.390618 -0.591237 0.705591 0.390618 -0.591236 0.705592 0.492605 -0.509392 0.705584 0.492611 -0.509398 0.705583 0.577825 -0.410208 0.705588 0.577821 -0.410205 0.705588 0.643358 -0.297046 0.705593 0.643353 -0.297044 0.705594 0.68698 -0.17377 0.705584 0.686989 -0.173772 0.705584 0.707223 -0.0445795 0.705589 0.707218 -0.0445794 0.705589 -0.703367 -0.0861304 0.70559 -0.703366 -0.0861303 0.70559 -0.675564 -0.213907 0.705594 -0.67556 -0.213906 0.705593 -0.624753 -0.334398 0.705589 -0.624756 -0.3344 0.70559 -0.552673 -0.443504 0.705591 -0.552671 -0.443503 0.70559 -0.461768 -0.537506 0.705585 -0.461771 -0.537509 0.705586 -0.355142 -0.613208 0.705582 -0.355143 -0.61321 0.705583 -0.236419 -0.668026 0.705584 -0.236419 -0.668025 0.705583 -0.109644 -0.700093 0.70559 -0.109643 -0.700086 0.705589 0.0208644 -0.708314 0.705594 0.0208644 -0.708309 0.705592 0.150661 -0.692417 0.705583 0.150663 -0.692426 0.705583 0.27533 -0.652951 0.705586 0.275329 -0.652949 0.705586 0.39062 -0.59124 0.705587 0.390619 -0.591238 0.705587 0.492609 -0.509396 0.705589 0.492607 -0.509394 0.705588 0.577821 -0.410205 0.705588 0.577821 -0.410205 0.705588 0.643358 -0.297046 0.705589 0.643357 -0.297046 0.705588 0.686985 -0.173772 0.705587 0.686986 -0.173772 0.705587 0.707219 -0.0445795 0.705586 0.707221 -0.0445797 0.705753 -0.703638 -0.0824997 0.705765 -0.703627 -0.0824988 0.705764 -0.678612 -0.203429 0.705746 -0.678629 -0.203433 0.705747 -0.632993 -0.318185 0.705753 -0.632987 -0.318183 0.705753 -0.568119 -0.423266 0.705761 -0.568112 -0.423262 0.70576 -0.485983 -0.515483 0.705745 -0.485994 -0.515494 0.705746 -0.389095 -0.592053 0.705758 -0.389088 -0.592044 0.705757 -0.28037 -0.650615 0.705749 -0.280374 -0.650622 0.70575 -0.163135 -0.689423 0.705751 -0.163134 -0.689422 0.705751 -0.0409393 -0.707276 0.705753 -0.0409391 -0.707274 0.705752 0.0824998 -0.703639 0.705751 0.0824999 -0.70364 0.705751 0.203433 -0.678625 0.705745 0.203434 -0.67863 0.705745 0.318186 -0.632994 0.70575 0.318184 -0.63299 0.705749 0.423268 -0.568122 0.705752 0.423267 -0.56812 0.705751 0.51549 -0.48599 0.705752 0.515489 -0.485989 0.705751 0.59205 -0.389093 0.705751 0.592049 -0.389092 0.705751 0.65062 -0.280373 0.70575 0.650621 -0.280374 0.70575 0.689423 -0.163135 0.705751 0.689422 -0.163134 0.705751 0.707276 -0.0409392 0.705751 0.707276 -0.0409392 0.705587 -0.703369 -0.0861307 0.705587 -0.703369 -0.0861307 0.705587 -0.675567 -0.213908 0.705588 -0.675566 -0.213908 0.705588 -0.624758 -0.334401 0.705588 -0.624757 -0.3344 0.705588 -0.552674 -0.443506 0.705589 -0.552673 -0.443505 0.705588 -0.46177 -0.537507 0.705586 -0.461771 -0.537509 0.705586 -0.355142 -0.613208 0.705591 -0.355139 -0.613203 0.705591 -0.236416 -0.668018 0.705588 -0.236417 -0.668021 0.705589 -0.109643 -0.700088 0.70559 -0.109643 -0.700087 0.705589 0.0208644 -0.708314 0.705588 0.0208645 -0.708315 0.705588 0.150662 -0.692421 0.70559 0.150662 -0.692419 0.705589 0.275328 -0.652946 0.705589 0.275328 -0.652947 0.70559 0.390618 -0.591236 0.705591 0.390618 -0.591236 0.705592 0.492605 -0.509392 0.705584 0.492611 -0.509398 0.705583 0.577826 -0.410208 0.705588 0.577821 -0.410205 0.705588 0.643358 -0.297046 0.705593 0.643353 -0.297044 0.705594 0.68698 -0.17377 0.705584 0.686989 -0.173772 0.705584 0.707223 -0.0445795 0.705589 0.707218 -0.0445794 0.705587 -0.703369 -0.0861307 0.705587 -0.703369 -0.0861308 0.705587 -0.675567 -0.213908 0.705588 -0.675566 -0.213908 0.705588 -0.624758 -0.334401 0.705585 -0.62476 -0.334402 0.705585 -0.552676 -0.443507 0.70559 -0.552672 -0.443504 0.705591 -0.461768 -0.537505 0.70559 -0.461768 -0.537506 0.705589 -0.35514 -0.613205 0.705585 -0.355142 -0.613208 0.705585 -0.236418 -0.668024 0.705588 -0.236417 -0.668021 0.705589 -0.109643 -0.700088 0.705583 -0.109644 -0.700093 0.705583 0.0208649 -0.70832 0.705587 0.0208646 -0.708316 0.705585 0.150662 -0.692423 0.705583 0.150663 -0.692425 0.705583 0.27533 -0.652951 0.705589 0.275328 -0.652947 0.70559 0.390618 -0.591236 0.705589 0.390619 -0.591237 0.705587 0.492608 -0.509396 0.705584 0.492611 -0.509398 0.705583 0.577825 -0.410208 0.705588 0.577821 -0.410205 0.705588 0.643358 -0.297046 0.705581 0.643364 -0.297049 0.705581 0.686992 -0.173773 0.705584 0.686989 -0.173772 0.705584 0.707222 -0.0445804 0.705563 0.707244 -0.0445809 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.939621 0.026969 0.341152 0.939566 -0.0429391 0.339664 0.938414 -0.0598822 0.340284 0.939693 -0.0607292 0.336585 0.93939 -0.0619145 0.337213 0.939414 -0.0618329 0.337161 0.939897 -0.0613715 0.335897 0.939963 -0.0615351 0.335683 0.939947 -0.0615071 0.335732 0.939759 -0.0615064 0.33626 0.939562 -0.0615996 0.336792 0.939619 0.0416485 0.339678 0.939836 0.0415801 0.339086 0.940958 0.0389249 0.336277 0.939692 0.040789 0.339581 0.939967 0.0416723 0.338711 0.939975 0.0416927 0.338688 0.939692 0.0403092 0.339637 0.939471 0.0417295 0.340077 0.939451 0.0417827 0.340128 0.939565 0.022871 0.341605 0.94337 0.0238955 0.330881 0.936007 -0.00189221 0.351977 0.939622 0.00228097 0.342206 0.939661 -0.0183029 0.341618 0.937285 -0.0228357 0.347815 0.94337 -0.0433306 0.328901 0.939621 -0.0470035 0.338973 0.939692 -0.0602032 0.336681 0.149349 0.0779239 0.985709 0.488776 0.0687531 0.869696 0.346106 -0.128861 0.929304 0.655061 -0.103779 0.748415 0.85096 -0.0721405 0.520252 0.850961 -0.0721403 0.520252 0.850961 -0.0344102 0.524101 0.850962 -0.0344097 0.524099 0.850962 0.0035009 0.525215 0.850962 0.00350083 0.525216 0.850962 0.0413915 0.523594 0.850962 0.0413916 0.523594 0.655067 0.0595442 0.753221 0.573443 0.0570845 0.817254 0.573332 0.0054612 0.819305 0.573323 0.00545969 0.819311 0.573323 -0.053678 0.817569 0.573329 -0.0536768 0.817565 0.57344 -0.105092 0.812479 0.488788 -0.119824 0.864134 0.34611 0.0739375 0.935276 0.20213 0.0714041 0.976752 0.202091 0.00652612 0.979345 0.202099 0.00652725 0.979343 0.202098 -0.0641616 0.977261 0.202097 -0.0641618 0.977262 0.202135 -0.128773 0.970855 0.149347 -0.13581 0.979414 -0.707099 0.144596 -0.692173 -0.67118 0.10805 -0.733377 -0.706471 0.104906 -0.699924 -0.70647 0.0208388 -0.707436 -0.706467 0.0208391 -0.707439 -0.706519 -0.0617621 -0.704994 -0.672819 -0.0664033 -0.736821 -0.707106 -0.103606 -0.699476 -0.706477 -0.104906 0.699918 -0.706469 -0.104907 0.699926 -0.70647 -0.0208387 0.707436 -0.706467 -0.0208386 0.707439 -0.706467 0.0635262 0.704889 -0.706471 0.0635256 0.704885 -0.694748 0.0805724 -0.714726 -0.487523 0.80028 -0.349103 -0.694736 0.08057 -0.714738 -0.702915 0.357973 -0.614627 -0.494615 0.516136 -0.699256 -0.705018 0.503375 -0.499562 -0.703704 0.6113 -0.362095 -0.704396 0.683528 -0.191355 -0.704396 0.709565 -0.0185347 -0.487526 0.867612 0.0978101 -0.69474 0.287588 0.659265 -0.694742 0.287586 0.659263 -0.70292 0.523173 0.481864 -0.49461 0.699261 0.516135 -0.705007 0.628232 0.329075 -0.70369 0.690867 0.165901 -0.698525 -0.00736109 -0.715548 -0.698529 -0.00735949 -0.715544 -0.698527 -0.309793 -0.64505 -0.698526 -0.309793 -0.64505 -0.698527 -0.553882 -0.453072 -0.698528 -0.553882 -0.453072 -0.698526 -0.693661 -0.175771 -0.698525 -0.693662 -0.175771 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.112017 -0.993706 0 0.292137 0.956377 0.0478516 0.39938 0.915536 0.0190462 0.479684 0.877235 -0.0231293 0.682462 0.730555 0.00914329 0.972317 0.233487 -0.0343166 0.922568 0.384305 -0.00482453 0.88582 0.464003 0.00546038 0.735539 0.677461 0.00782277 0.962947 -0.269578 1.53235e-05 0.972209 -0.234113 -2.6105e-05 0.999659 -0.0261124 1.26975e-05 0.999656 -0.0262377 8.82307e-06 0.991488 0.130198 0.0166638 0.661359 -0.749884 -0.0109394 0.785816 -0.618364 0.0114753 0.860332 -0.509605 -2.37155e-05 0.894368 -0.447331 -1.69106e-05 0.935959 -0.352109 0.0264203 0.0664763 -0.997438 -0.0156583 0.464588 -0.885389 -1.9749e-05 0.503284 -0.864121 5.45803e-06 0.70979 -0.704413 0 0.0136401 -0.999907 0.0104374 -0.0102862 -0.999893 -0.00978196 -0.377902 -0.925794 0.0153983 -0.432872 -0.901324 -0.000796009 -0.596389 -0.802695 0.00343889 -0.739579 -0.673061 0.0232009 -0.773821 -0.63298 0.0001531 -0.862901 -0.505373 -0.000283313 -0.943129 -0.332427 0.0289669 -0.968956 -0.24553 0 -0.992896 -0.118984 0 -0.148227 0.988953 0 -0.148227 0.988953 0 -0.0294438 0.999566 0 -0.0294438 0.999566 0 0.0897584 0.995964 0 0.0897584 0.995964 0 -0.0897576 -0.995964 0 -0.0897576 -0.995964 0 0.029444 -0.999566 0 0.029444 -0.999566 0 0.148227 -0.988953 0 0.148227 -0.988953 -0.879243 0.107446 0.464097 -0.887084 0.172677 0.428093 -0.954988 0.207535 0.211959 -0.960101 0.203684 0.19162 -0.978436 0.145277 0.146826 -0.978976 0.143887 0.144579 -0.991396 0.0587277 0.116981 -0.990797 0.0630717 0.119761 -0.965171 0.0816322 -0.248558 -0.793207 0.574447 -0.202073 -0.859467 0.36079 -0.362142 -0.839109 0.388918 -0.380314 -0.884193 0.0832219 -0.459649 -0.876481 0.0923288 -0.4725 -0.859294 0.484593 0.163658 -0.938545 0.234274 0.253475 -0.933195 0.230306 0.275875 -0.821646 0.569064 0.0326028 -0.847485 0.529734 -0.0339317 -0.891282 0.452877 -0.0227736 -0.947044 0.282608 -0.152448 -0.938318 0.303957 -0.164834 -0.970911 0.0958327 -0.219427 -0.989048 0.0797225 -0.12421 -0.80733 0.421445 0.413041 -0.693234 0.671034 0.262945 -0.770715 0.635641 0.0442643 -0.902136 0.224656 0.368348 -0.88785 0.166849 0.428816 -0.749526 0.321894 0.578442 -0.71014 0.330372 0.621736 -0.276027 0.849582 0.449465 -0.145867 0.469795 0.870641 -0.197802 0.32009 0.926508 -0.147931 0.286901 0.94647 -0.11168 0.466457 -0.877465 -0.094864 0.068787 -0.993111 -0.105759 0.0649134 -0.992271 -0.0780633 0.894897 -0.439392 -0.143541 0.784735 -0.602981 -0.177918 0.772649 -0.609392 -0.097301 0.664784 -0.740672 -0.110864 0.466725 -0.877426 -0.0290598 0.682116 0.730666 -0.134929 0.911376 0.388829 0.129852 0.895187 0.426354 -0.156052 0.977311 0.143216 -0.216084 0.970786 0.104322 -0.0506036 0.998492 -0.0212609 -0.14339 0.950851 -0.274447 -0.27377 0.941001 -0.198914 -0.142503 0.931164 -0.335599 -0.354222 0.805801 0.474565 -0.457115 0.873165 0.169197 -0.363193 0.910925 0.195721 -0.490852 0.8579 -0.151894 -0.397286 0.906891 -0.140404 -0.522589 0.717808 -0.460057 -0.442831 0.765557 -0.466716 -0.546602 0.449537 -0.7065 -0.493393 0.481754 -0.724207 -0.553363 0.0843614 -0.828657 -0.54624 0.0876841 -0.833027 -0.176408 0.86034 0.478221 -0.302664 0.946399 0.112802 -0.186322 0.97255 0.139393 -0.325665 0.914593 -0.239714 -0.208488 0.952141 -0.223517 -0.343274 0.749032 -0.566669 -0.241846 0.788824 -0.565037 -0.351502 0.455912 -0.817674 -0.282656 0.485473 -0.827298 -0.345031 0.0680152 -0.936124 -0.333666 0.0727197 -0.939882 -0.879553 0.106246 0.463788 -0.763472 0.16839 0.623502 -0.693962 0.234695 0.680688 -0.651411 0.220085 0.726103 -0.484418 0.264546 0.833879 -0.91828 0.236642 0.317431 -0.901027 0.249153 0.355067 -0.758739 0.51365 0.400599 -0.805287 0.46065 0.373249 -0.700531 0.595841 0.392721 -0.633825 0.43169 0.641802 -0.461119 0.521826 0.717682 -0.425664 0.307776 0.850931 -0.341514 0.302761 0.889778 -0.172208 0.632717 0.754993 -0.179224 0.633114 0.753025 -0.424085 0.566273 0.706744 -0.486856 0.705773 0.514641 -0.502676 0.700386 0.506731 -0.601397 0.767796 0.220931 -0.531857 0.810029 0.246943 -0.642826 0.764001 -0.0554745 -0.575092 0.816785 -0.0461644 -0.685233 0.650458 -0.32766 -0.629215 0.700093 -0.337577 -0.721675 0.417847 -0.551896 -0.685618 0.449747 -0.572411 -0.739937 0.084403 -0.66736 -0.725684 0.094579 -0.681497 -0.146145 -0.405233 0.902457 -0.826271 -0.561647 0.0427616 -0.651405 -0.26239 0.711915 -0.992269 -0.0811323 0.0939181 -0.992328 -0.0431223 0.115872 -0.976263 -0.169616 0.13469 -0.978909 -0.151699 0.136841 -0.963218 -0.205509 0.173141 -0.85102 -0.0937894 0.51669 -0.880896 -0.186715 0.434925 -0.902137 -0.230364 0.364802 -0.895764 -0.23344 0.378303 -0.919309 -0.2495 0.304335 -0.74053 -0.612278 0.277006 -0.783613 -0.575776 0.233309 -0.707957 -0.537362 0.4583 -0.918518 -0.250487 0.305909 -0.938742 -0.247722 0.239578 -0.785901 -0.614214 0.0714225 -0.847486 -0.52682 -0.0650244 -0.793258 -0.561476 -0.235557 -0.856962 -0.355257 -0.373374 -0.844209 -0.348451 -0.407299 -0.884164 -0.0646976 -0.462675 -0.877675 -0.0560903 -0.475962 -0.945949 -0.232926 0.22567 -0.960045 -0.215728 0.178258 -0.891349 -0.450621 -0.0493663 -0.944832 -0.285169 -0.161156 -0.94185 -0.280274 -0.185376 -0.970926 -0.0828186 -0.224596 -0.965172 -0.066897 -0.252918 -0.0803353 -0.863903 -0.49721 -0.171667 -0.929849 -0.32544 -0.146973 -0.740143 -0.656192 -0.158079 -0.736404 -0.657815 -0.0929081 -0.599295 -0.795119 -0.146465 -0.414652 -0.898116 -0.0593281 -0.379811 -0.92316 -0.106173 0.0115181 -0.994281 -0.150215 -0.00768051 -0.988624 -0.334013 -0.0125836 -0.942484 -0.138284 -0.938471 -0.316464 -0.0626517 -0.991658 -0.112646 -0.205189 -0.97767 0.0453734 -0.119314 -0.989435 0.0823609 -0.0122648 -0.921023 0.389315 -0.365902 -0.881659 0.297981 -0.18019 -0.887347 0.424437 -0.0941643 -0.867261 0.488868 -0.0329078 -0.733515 0.678876 -0.190431 -0.676631 0.711271 -0.0911561 -0.382883 0.919288 -0.341495 -0.35455 0.870445 -0.693999 -0.274325 0.665665 -0.714756 -0.409848 0.5667 -0.412198 -0.58392 0.699379 -0.486908 -0.73487 0.472108 -0.354186 -0.832396 0.426227 -0.44765 -0.880821 0.154154 -0.378521 -0.919346 0.107351 -0.480137 -0.861386 -0.16578 -0.413115 -0.88194 -0.226977 -0.514076 -0.713921 -0.475439 -0.455185 -0.712345 -0.534201 -0.542693 -0.430639 -0.721134 -0.499643 -0.415492 -0.760081 -0.553289 -0.0388344 -0.832083 -0.546672 -0.0349425 -0.836617 -0.344673 -0.0182493 -0.938545 -0.288258 -0.411481 -0.864633 -0.346232 -0.432695 -0.832405 -0.253712 -0.728515 -0.636314 -0.332836 -0.741522 -0.582551 -0.224028 -0.922061 -0.315618 -0.313032 -0.914955 -0.254692 -0.201529 -0.978451 0.0449496 -0.291642 -0.9517 0.0959749 -0.187832 -0.897658 0.39866 -0.269291 -0.862583 0.42829 -0.179202 -0.676257 0.714537 -0.463843 -0.590601 0.660333 -0.425692 -0.357281 0.831347 -0.484457 -0.313097 0.816867 -0.875376 -0.127633 0.46629 -0.889597 -0.18907 0.415775 -0.689724 -0.406976 0.598875 -0.745697 -0.522773 0.41309 -0.502659 -0.729048 0.464568 -0.593275 -0.777558 0.208394 -0.546277 -0.820593 0.167953 -0.63376 -0.770594 -0.0673273 -0.589993 -0.797911 -0.123472 -0.678236 -0.650772 -0.341308 -0.640941 -0.656431 -0.39786 -0.718698 -0.404943 -0.565238 -0.691733 -0.394775 -0.604697 -0.73991 -0.0546655 -0.67048 -0.727058 -0.0446586 -0.685122 -0.57289 -0.0241337 0.819277 -0.850728 -0.0789869 0.519637 -0.879519 0.0436983 0.473852 -0.654682 0.0678487 0.752853 -0.764986 0.0578086 0.641447 -0.845146 0.0445716 0.532674 -0.851117 0.016952 0.524702 -0.850699 -0.0154776 0.525425 -0.850696 -0.0154772 0.52543 -0.851114 -0.0478049 0.5228 -0.345828 0.0842198 0.934511 -0.488391 0.0783252 0.869103 -0.149198 0.0887538 0.984816 -0.201918 0.0844292 0.975756 -0.201879 -0.0288376 0.978986 -0.844347 -0.0794189 0.529877 -0.654671 -0.112046 0.747564 -0.573011 -0.117004 0.811153 -0.488427 -0.129343 0.862966 -0.345799 -0.139082 0.927943 -0.573002 0.069055 0.81664 -0.572881 -0.0241329 0.819283 -0.201873 -0.0288371 0.978987 -0.201914 -0.141719 0.969096 -0.149209 -0.146568 0.977883 -0.340896 0.139348 -0.929716 -0.994035 -0.00321125 0.109015 -0.994036 -0.0163875 0.10781 -0.99425 -0.0158721 0.105896 -0.991754 0.0117685 0.127615 -0.996675 0.00263198 0.0814361 -0.658678 0.0221546 -0.752099 -0.931791 0.0106881 -0.362837 -0.994046 0.00785872 0.108682 -0.993745 -0.0100236 -0.111222 -0.971837 -0.021152 -0.234703 -0.994056 -0.00991333 0.108419 -0.994035 -0.00321123 0.109015 -0.931791 0.010688 -0.362838 -0.931639 -0.0391102 -0.361274 -0.558459 0.136758 -0.818181 -0.739299 0.0998119 -0.665939 -0.931791 0.0538051 -0.358984 -0.888072 0.0795849 -0.452763 -0.971842 0.0349274 -0.233031 -0.237289 0.0286031 -0.971018 -0.237289 0.143993 -0.960708 -0.108132 0.16177 -0.980886 -0.887834 -0.0413031 -0.458306 -0.739299 -0.0604406 -0.670659 -0.658466 -0.0741806 -0.748946 -0.558112 -0.0744785 -0.826416 -0.340885 -0.0843824 -0.93631 -0.658675 0.11153 -0.744116 -0.658675 0.0221543 -0.752101 -0.237288 0.0286029 -0.971018 -0.237191 -0.0938211 -0.966922 -0.10803 -0.0892323 -0.990135 -0.939508 0.0314539 0.34108 -0.939611 0.0526718 0.338167 -0.939481 0.0528657 0.338497 -0.939573 0.0525564 0.338289 -0.93969 0.0515068 0.338126 -0.939847 0.0526007 0.337521 -0.939868 0.0526382 0.337458 -0.939722 0.0526266 0.337866 -0.939514 -0.0514716 0.33862 -0.940509 -0.0704822 0.332377 -0.939696 -0.0719836 0.334349 -0.939886 -0.0724341 0.333719 -0.93969 -0.0715114 0.334469 -0.939536 -0.0725203 0.334682 -0.93949 -0.0726812 0.334777 -0.939515 -0.0726123 0.334723 -0.939751 -0.0723649 0.334114 -0.939507 -0.0514743 0.338639 -0.939511 -0.0514738 0.338629 -0.939694 -0.0311426 0.340597 -0.939694 -0.0311441 0.340596 -0.939498 -0.0100862 0.342406 -0.939497 -0.0100861 0.342407 -0.939693 0.0110481 0.34184 -0.939694 0.0110441 0.341839 -0.939511 0.031454 0.341071 -0.939514 0.0314527 0.341065 -0.939696 0.0517299 0.338076 0.042035 -0.736139 0.675524 0.00148229 -0.874596 0.484851 -0.000288982 -0.908225 0.418482 0.00686619 -0.97954 0.201132 0.0567908 -0.957498 0.282795 0 -0.997431 0.0716338 -0.0105536 -0.785974 0.618169 0.00928245 -0.426288 0.90454 0 -0.412458 0.910977 -0.697441 -0.701997 0.144143 -0.697441 -0.701997 0.144144 -0.697442 -0.563293 0.44303 -0.697441 -0.563294 0.443032 -0.69744 -0.30551 0.64826 -0.697442 -0.305509 0.648258 0.000647583 0.866573 0.49905 0 0.998258 0.0590063 -0.00490218 0.964509 0.264005 -0.0463839 0.931845 0.359879 -0.00611593 0.984419 0.175732 0 0.345462 0.938433 -0.0139882 0.31637 0.948533 -0.000713711 0.520408 0.853918 0.00557358 0.736687 0.676211 -0.03396 0.676938 0.735257 -0.00401587 0.820523 0.571599 0.696944 0.691682 0.189327 0.696945 0.691682 0.189327 0.696947 0.528304 0.484934 0.69695 0.528302 0.484931 0.696951 0.247737 0.672968 0.696941 0.247738 0.672978 0.698869 0.584706 -0.411948 0.698877 0.584698 -0.411946 0.698877 0.703042 -0.131539 0.698867 0.703052 -0.131538 0.698861 0.0709837 -0.711727 0.698869 0.0709798 -0.711719 0.698868 0.36048 -0.617768 0.819611 0.249261 -0.515855 0.706021 0.436731 -0.557494 0.458499 -0.805669 -0.375067 0.694738 -0.0631422 -0.716486 0.694743 -0.063143 -0.716481 0.705702 -0.300893 -0.641443 0.754941 -0.316152 -0.574554 0.624891 -0.503196 -0.596913 0.705019 -0.491057 -0.511674 0.703702 -0.602304 -0.376875 0.704395 -0.678665 -0.207944 0.704394 -0.708905 -0.0358136 0.458494 -0.885267 0.0780162 0.694731 -0.303565 0.652071 0.694748 -0.303554 0.652058 0.702921 -0.534752 0.468981 0.466755 -0.724125 0.507724 0.705016 -0.636051 0.313674 0.703699 -0.694693 0.149029 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706175 -0.0302786 -0.70739 0.706179 -0.0302782 -0.707386 0.706178 0.0718642 -0.704378 0.706175 0.0718643 -0.704381 0 0.125417 -0.992104 0.0420199 0.101408 -0.993957 0 0.0534977 -0.998568 0 -0.0427641 -0.999085 0.0629305 -0.0666701 -0.995789 0 0.00537307 -0.999986 0.706174 0.0302787 0.707391 0.706165 0.0302787 0.7074 0.706166 -0.0718654 0.70439 0.706168 -0.0718651 0.704388 0 -0.087789 -0.996139 0 -0.314398 0.949291 -0.0323189 -0.421826 0.906101 -0.0129584 -0.500046 0.865902 0.0156213 -0.700322 0.713656 -0.00369028 -0.751824 0.659354 0.00326071 -0.896863 0.442296 0.0251176 -0.934875 0.354088 -3.31921e-05 -0.956125 -0.292958 4.15925e-05 -0.999678 -0.0253653 0.00666503 -0.998704 -0.0504542 -0.00509185 -0.977742 0.20975 -0.00405121 -0.692416 -0.721487 0.00867153 -0.764344 -0.64475 -0.00792462 -0.847696 -0.530422 0.0030689 -0.895622 -0.444806 -0.00558267 -0.963449 -0.267834 -0.0225155 -0.0319995 -0.999234 0.0120835 -0.420501 -0.907212 -0.00323417 -0.482089 -0.876117 3.06576e-06 -0.598784 -0.800911 -9.21772e-07 -0.636641 -0.77116 0 0.0703115 -0.997525 -0.00839107 0.0992386 -0.995028 0.00844827 0.454272 -0.890823 -0.0083813 0.503973 -0.863679 0.000412913 0.662044 -0.749465 -0.00245887 0.793791 -0.608186 -0.0133793 0.817411 -0.575899 0.000409534 0.903331 -0.428944 -0.00121537 0.968264 -0.249927 -0.0176829 0.98279 -0.18388 0 0.999067 -0.0431791 0.994042 0.00728104 0.108752 0.97185 -0.0157384 -0.235072 0.658911 0.0221481 -0.751895 0.108089 0.124682 -0.986292 0.55829 0.104051 -0.823095 0.341057 0.117897 -0.93262 0.237325 0.130104 -0.962679 0.23762 0.0519654 -0.969967 0.153986 0.0290925 -0.987645 0.237618 0.00521918 -0.971345 0.237423 -0.0648924 -0.969237 0.887897 0.057697 -0.456409 0.739449 0.0844322 -0.667897 0.108173 -0.0846488 -0.990522 0.341051 -0.0627965 -0.937945 0.658911 -0.0502496 -0.750541 0.558602 -0.0728768 -0.826228 0.739456 -0.0449713 -0.671701 0.971845 0.029551 -0.233762 0.931702 0.0536545 -0.359238 0.931867 0.0106823 -0.362643 0.658687 0.102636 -0.745384 0.658909 0.0221485 -0.751897 0.931867 0.0106823 -0.362643 0.931867 -0.0242357 -0.36199 0.888088 -0.0452036 -0.457445 0.994042 -0.01367 0.108135 0.994042 -0.0136697 0.108134 0.994053 -0.00582622 0.108745 0.994978 -0.0029472 0.100051 0.994053 -0.000585438 0.1089 0.994042 0.00728106 0.108751 0 0.0788078 0.99689 -0.0635014 0.0426779 0.997069 0 0.00666477 0.999978 0 -0.0655136 0.997852 -0.0635019 -0.101293 0.992828 0 -0.13735 0.990523 0.738161 -0.489037 0.464715 0.93308 -0.238134 0.269543 0.88579 -0.174772 0.429919 0.902775 -0.213928 0.373138 0.900886 -0.238359 0.362752 0.893717 -0.199067 0.402048 0.982611 -0.136859 0.125476 0.968946 -0.18248 0.166865 0.959186 -0.211394 0.187814 0.978164 -0.146763 0.14716 0.993506 -0.0459376 0.104097 0.993503 -0.0516786 0.101397 0.955084 -0.213316 0.205697 0.937216 -0.243436 0.249731 0.812779 -0.572173 0.109581 0.759737 -0.598181 0.254911 0.532649 -0.816129 0.224095 0.600308 -0.773204 0.204419 0.364128 -0.915657 0.170242 0.456005 -0.877168 0.150454 0.187419 -0.975843 0.112274 0.145516 -0.489029 0.860044 0.172307 -0.652424 0.738007 0.884954 -0.180522 0.429265 0.712673 -0.369695 0.596173 0.697723 -0.401873 0.593027 0.4611 -0.540969 0.703378 0.423348 -0.582449 0.693923 0.17969 -0.652557 0.736126 0.275273 -0.859515 0.43065 0.918219 -0.245473 0.310831 0.916084 -0.2475 0.31549 0.771366 -0.56143 0.299653 0.722823 -0.531679 0.441412 0.503313 -0.713757 0.487061 0.487236 -0.720033 0.494119 0.353633 -0.817115 0.455265 0.177311 -0.872925 0.454492 0.301511 -0.948951 0.0926458 0.17552 -0.763961 -0.620932 0.0983751 -0.640718 -0.761448 0.100528 -0.603052 -0.791342 0.275281 -0.934901 -0.224009 0.876441 -0.0806911 -0.474701 0.884046 -0.0729534 -0.461672 0.725681 -0.0775761 -0.683644 0.73982 -0.0688211 -0.669276 0.5462 -0.0671824 -0.834956 0.553287 -0.0643126 -0.830504 0.333635 -0.0500118 -0.941375 0.344986 -0.0458836 -0.937486 0.105762 -0.0403256 -0.993573 0.121174 -0.0354561 -0.991998 0.0684108 -0.896959 -0.436788 0.148724 -0.758722 -0.63421 0.342315 -0.737126 -0.582637 0.24233 -0.773282 -0.585927 0.521629 -0.708387 -0.47549 0.443206 -0.752666 -0.486891 0.68426 -0.644223 -0.341709 0.629491 -0.690636 -0.356039 0.792145 -0.571105 -0.21528 0.839075 -0.379098 -0.390176 0.858962 -0.353637 -0.370304 0.68563 -0.434993 -0.583689 0.721184 -0.406077 -0.561244 0.493425 -0.46308 -0.736267 0.546146 -0.434025 -0.716482 0.282722 -0.464054 -0.839477 0.351088 -0.437746 -0.827717 0.0859278 -0.443084 -0.892352 0.151875 -0.424685 -0.892511 0.147944 -0.308446 0.939667 0.205591 -0.342256 0.916839 0.34146 -0.324213 0.882208 0.424994 -0.325904 0.844492 0.484353 -0.285394 0.827014 0.687669 -0.224401 0.690476 0.647368 -0.281935 0.708116 0.870202 -0.0606006 0.488954 0.85001 -0.140859 0.507585 0.0290032 -0.69945 0.714092 0.135837 -0.922283 0.36186 -0.181661 -0.902708 0.390022 0.289903 -0.956992 0.0110896 0.013127 -0.998458 0.0539398 0.143538 -0.943611 -0.298321 0.324419 -0.909781 -0.258942 0.209391 -0.945413 -0.2497 0.489615 -0.855187 -0.170094 0.398063 -0.902343 -0.165294 0.641639 -0.763645 -0.0717368 0.57571 -0.814766 -0.0686669 0.805188 -0.590642 0.0530402 0.849347 -0.525066 -0.0540003 0.891415 -0.451833 -0.0350107 0.946585 -0.280566 -0.158934 0.938296 -0.299647 -0.172661 0.97139 -0.0753968 -0.225202 0.963017 -0.0925619 -0.253042 0.484342 0.236174 0.842398 0.146446 0.309184 0.939659 0.546584 0.113017 -0.829743 0.824719 0.556848 0.0987874 0.942263 0.248666 0.224287 0.971801 0.158986 0.174143 0.978817 0.143654 0.145883 0.98931 0.0683385 0.128823 0.993672 0.0400887 0.104921 0.851107 0.0558321 0.522016 0.873461 0.141564 0.46586 0.889412 0.164927 0.426316 0.901408 0.194911 0.386619 0.8953 0.198107 0.398988 0.918228 0.220674 0.328877 0.651396 0.194581 0.733363 0.692776 0.206281 0.691021 0.714412 0.353959 0.603597 0.741742 0.584479 0.328942 0.782192 0.551579 0.289719 0.708898 0.49414 0.503278 0.911963 0.228574 0.3407 0.938587 0.219751 0.266017 0.786964 0.60423 0.124879 0.849349 0.52733 -0.0229987 0.79219 0.582711 -0.181336 0.856725 0.388518 -0.339229 0.843571 0.386552 -0.372781 0.884012 0.107562 -0.454921 0.877481 0.101152 -0.468823 0.921866 0.256013 0.290896 0.959989 0.17806 0.216138 0.891439 0.453063 -0.00836965 0.944652 0.29916 -0.134669 0.941309 0.2981 -0.158348 0.970892 0.101857 -0.216781 0.965073 0.0908331 -0.245731 0.13928 0.962989 -0.230767 0.170817 0.956218 -0.237633 0.0818721 0.904364 -0.418834 0.148658 0.794689 -0.588532 0.148777 0.794657 -0.588546 0.0946755 0.665599 -0.74028 0.146666 0.496114 -0.85578 0.0322496 0.455518 -0.889642 0.106339 0.0723623 -0.991693 0.174509 0.100066 -0.979558 0.333937 0.101091 -0.937159 0.183933 0.842637 0.506095 0.234215 0.84473 0.481223 0.068068 0.997077 -0.0347044 0.154398 0.985002 0.0770197 0.226176 0.964031 0.1396 0.114473 0.975369 0.188549 0.0516797 0.927719 0.369685 0.0913832 0.812062 0.576372 0.0352324 0.67325 0.738575 0.511443 0.424623 0.747075 0.553204 0.116147 -0.824909 0.499063 0.485875 -0.717539 0.542559 0.495702 -0.678166 0.454257 0.760186 -0.464508 0.513924 0.754819 -0.407592 0.412116 0.899877 -0.142765 0.480034 0.873027 -0.0859759 0.377673 0.90552 0.193384 0.447573 0.863027 0.234227 0.353591 0.788962 0.502507 0.487274 0.689736 0.535563 0.412923 0.518272 0.748925 0.463496 0.524889 0.713907 0.425019 0.275572 0.862217 0.344666 0.105943 -0.932728 0.287817 0.491456 -0.821968 0.346289 0.508022 -0.788668 0.253029 0.785555 -0.564695 0.332867 0.792185 -0.51151 0.223311 0.947856 -0.227379 0.31305 0.93453 -0.169275 0.200948 0.970026 0.136637 0.291671 0.938816 0.183172 0.187472 0.856405 0.481067 0.269272 0.819496 0.505885 0.179546 0.607661 0.773635 0.178802 0.608174 0.773405 0.111641 0.295155 0.948905 0.341473 0.271654 0.899778 0.870901 0.0793331 0.485013 0.892968 0.143292 0.426703 0.690169 0.351339 0.632636 0.744776 0.480877 0.462673 0.503278 0.683909 0.528186 0.593135 0.755435 0.278404 0.545197 0.801821 0.244627 0.633554 0.773691 0.00334854 0.588795 0.806887 -0.0474804 0.677982 0.679613 -0.28012 0.63989 0.692089 -0.333996 0.718477 0.455713 -0.525468 0.691084 0.450926 -0.564862 0.739773 0.116706 -0.662658 0.726918 0.109026 -0.678014 0 0.420249 -0.907409 0 0.420249 -0.907409 0 0.525283 -0.850928 0 0.525283 -0.850928 0 0.622845 -0.782346 0 0.622845 -0.782346 0 0.563367 -0.826207 0 -0.225188 0.974315 0.0323304 -0.149024 0.988305 0.00477503 -0.0236766 0.999708 -0.0109501 0.226458 0.973959 0.00691356 0.262367 0.964943 -0.00189146 0.470535 0.882379 -0.02333 0.607742 0.793791 0.0208215 0.679982 0.732933 0.00130043 0.793597 0.608443 -0.00323674 0.878692 0.477378 0.0314914 0.930392 0.365211 0.00698268 0.959185 0.282694 -0.000755495 0.948254 -0.317512 0.00320148 0.989598 -0.143823 0.0274194 0.996833 -0.0746453 0.00213265 0.998222 0.0595701 -0.000710812 0.986611 0.163091 0.00389269 0.556879 -0.830584 -0.00331251 0.844751 -0.535149 -2.06711e-05 0.848738 -0.528813 1.06956e-07 0.945132 -0.32669 0 -0.622845 0.782346 0 -0.622845 0.782346 0 -0.525283 0.850928 0 -0.525283 0.850928 0 -0.420249 0.907409 0 -0.420249 0.907409 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.999992 0.00388821 0.0196624 -0.975675 0.218337 -0.000198293 -0.982454 0.186504 0.000205466 -0.812885 0.582424 0 -0.812689 0.582698 -0.698658 -0.702902 0.133436 -0.698656 -0.702904 0.133437 -0.698657 -0.581584 0.416699 -0.698655 -0.581585 0.416701 0 0.994308 0.106541 -0.0215574 0.962691 0.269743 -0.0224918 0.963572 0.2665 0.0284617 0.793683 0.607666 -0.0230699 0.871439 0.489962 -0.00843379 0.404977 0.914288 0.0119191 0.623777 0.781512 2.36678e-05 0.589652 0.807657 -8.61667e-06 0.745677 0.666308 -1.10832e-05 0.443164 0.896441 2.46945e-05 0.213724 0.976894 0.00961764 0.176725 0.984213 -0.0145583 -0.164088 0.986338 0 -0.200647 0.979664 0.696411 -0.11777 0.707913 0.696414 -0.117769 0.707911 0.703789 0.151831 0.693995 0.504591 0.273739 0.818813 0.696417 0.691024 0.193622 0.696415 0.691025 0.193623 0.703792 0.564066 0.431865 0.504587 0.625392 0.595212 0.70506 0.442381 0.554247 0.70506 0.314269 0.635709 0 0.604667 -0.796479 0.0420204 0.584801 -0.810088 0 0.545614 -0.838037 0 0.462508 -0.886615 0.0629302 0.440157 -0.895713 0 0.504646 -0.863326 0.706174 -0.327473 0.627758 0.706178 -0.327471 0.627754 0.706178 -0.414425 0.574077 0.70618 -0.414424 0.574075 0 0.422043 -0.906576 0 -0.746924 0.664909 -0.0323167 -0.81836 0.573797 -0.0129601 -0.865993 0.499888 0.0156221 -0.963325 0.267882 -0.00369107 -0.980777 0.195099 0.00326021 -0.997854 -0.0653906 0.0251179 -0.986669 -0.160789 -3.45566e-05 -0.681552 -0.73177 3.989e-05 -0.853067 -0.521802 0.00666631 -0.839673 -0.543052 -0.00509129 -0.951624 -0.307222 -0.0225152 0.471905 -0.881362 0.0133487 0.0747582 -0.997112 1.52514e-05 0.0205565 -0.999789 -2.07137e-07 -0.165754 -0.986167 -0.0040512 -0.238907 -0.971034 0.00867133 -0.339565 -0.940543 -0.007925 -0.468916 -0.883207 0.00306789 -0.553224 -0.833027 -0.00558407 -0.700456 -0.713674 0 0.523132 -0.852252 -0.0125342 0.570528 -0.821182 0.000325431 0.683792 -0.729676 -0.00111404 0.843852 -0.536575 -0.00397652 0.838758 -0.54449 0.00430327 0.985718 -0.168352 0 0.98349 -0.180961 0.994042 -0.0480701 0.0978221 0.97185 0.103907 -0.211449 0.658909 0.39513 -0.640088 0.108093 0.601124 -0.791812 0.558294 0.501658 -0.660793 0.341051 0.568414 -0.748726 0.237325 0.594012 -0.768652 0.237621 0.529986 -0.814034 0.153991 0.519017 -0.840778 0.237624 0.490191 -0.838598 0.23743 0.428419 -0.871828 0.887898 0.278171 -0.366412 0.73945 0.407068 -0.536198 0.108171 0.421952 -0.900142 0.341051 0.414588 -0.843683 0.658908 0.331753 -0.675114 0.558601 0.350001 -0.751974 0.739458 0.296903 -0.604194 0.971844 0.142474 -0.187669 0.931702 0.226085 -0.284282 0.931867 0.190573 -0.308718 0.658687 0.461578 -0.594203 0.658909 0.395129 -0.640087 0.931867 0.190573 -0.308717 0.931867 0.160006 -0.325611 0.888087 0.189576 -0.418763 0.994042 -0.0659055 0.086812 0.994042 -0.0659055 0.0868121 0.994053 -0.0594183 0.091263 0.994978 -0.0525782 0.0851737 0.994053 -0.054957 0.0940173 0.994042 -0.0480702 0.0978222 0 -0.585318 0.810804 -0.12616 -0.609302 0.782837 0 -0.555663 0.831408 0 -0.462508 0.886615 -0.126162 -0.490268 0.862392 0 -0.430195 0.902736 0.068407 -0.558391 -0.826753 0.0983748 -0.174141 -0.979795 0.738158 -0.65588 0.157934 0.933081 -0.341 0.114358 0.885792 -0.366308 0.28494 0.902775 -0.371837 0.216182 0.900887 -0.387797 0.194978 0.89372 -0.37342 0.248641 0.982611 -0.181262 0.0402369 0.968948 -0.24146 0.0532688 0.959187 -0.276978 0.0569543 0.978164 -0.200681 0.0540632 0.993506 -0.0918321 0.0671821 0.993503 -0.0954559 0.0619712 0.955084 -0.287585 0.0714819 0.937215 -0.335689 0.0945579 0.81278 -0.550307 -0.191184 0.759738 -0.645494 -0.0783284 0.532649 -0.818837 -0.213991 0.600306 -0.771825 -0.209569 0.364127 -0.878105 -0.310392 0.456008 -0.834875 -0.308285 0.187421 -0.901242 -0.390688 0.145514 -0.853523 0.500324 0.172308 -0.93402 0.312916 0.884955 -0.370968 0.281494 0.712671 -0.618255 0.331454 0.697719 -0.644551 0.312638 0.461103 -0.820181 0.338655 0.423351 -0.851377 0.309727 0.179688 -0.933195 0.311221 0.275271 -0.959687 -0.0568001 0.918217 -0.368008 0.146452 0.916084 -0.372087 0.149469 0.771366 -0.636038 -0.0212099 0.722822 -0.681154 0.116438 0.503306 -0.861665 0.06493 0.487237 -0.870626 0.0679033 0.353642 -0.935272 -0.0142819 0.177311 -0.983221 -0.0428574 0.301514 -0.868138 -0.39424 0.275286 -0.697645 -0.661445 0.876442 0.167468 -0.451447 0.884048 0.167655 -0.436293 0.725681 0.274639 -0.630841 0.739819 0.275038 -0.614021 0.546204 0.359295 -0.756682 0.553288 0.359554 -0.751394 0.33363 0.427376 -0.840262 0.344985 0.429007 -0.834828 0.105767 0.461864 -0.880622 0.121178 0.465293 -0.876823 0.145476 -0.349776 -0.925469 0.171339 -0.341485 -0.924138 0.342326 -0.347047 -0.873139 0.242333 -0.376718 -0.894069 0.52163 -0.375735 -0.76598 0.443194 -0.408387 -0.797997 0.684256 -0.387062 -0.618042 0.629495 -0.420087 -0.653653 0.792145 -0.386951 -0.47199 0.839078 -0.13322 -0.527447 0.858963 -0.121107 -0.49751 0.685629 -0.0848699 -0.722987 0.721187 -0.0710499 -0.689087 0.493428 -0.0329031 -0.869164 0.546137 -0.0176378 -0.83751 0.282717 0.0178536 -0.959037 0.351091 0.0347585 -0.935696 0.0859322 0.0624531 -0.994342 0.106813 0.0675445 -0.991982 0.147942 -0.736958 0.65955 0.205582 -0.754822 0.62288 0.341456 -0.721881 0.601911 0.424996 -0.704486 0.568399 0.484354 -0.660665 0.573519 0.687667 -0.539575 0.48577 0.647365 -0.598223 0.47228 0.870205 -0.296954 0.393144 0.850012 -0.375778 0.36915 0.0290171 -0.962788 0.268697 0.135841 -0.97965 -0.147762 -0.181675 -0.976777 -0.113583 0.289891 -0.834329 -0.468891 0.0131293 -0.89166 -0.452515 0.143537 -0.668031 -0.730159 0.324425 -0.658422 -0.679138 0.209402 -0.6939 -0.688951 0.489614 -0.655566 -0.574901 0.398062 -0.698805 -0.594322 0.641639 -0.625467 -0.443949 0.575708 -0.671275 -0.466852 0.805188 -0.538031 -0.249387 0.849347 -0.427719 -0.309299 0.891417 -0.373791 -0.256235 0.946585 -0.163509 -0.277923 0.938295 -0.173173 -0.299354 0.97139 0.0473066 -0.232732 0.963016 0.0463614 -0.265424 0.146443 -0.202072 0.96836 0.824719 0.432851 0.363976 0.651396 -0.198174 0.7324 0.942263 0.103208 0.318574 0.971801 0.0506141 0.230305 0.978816 0.0514662 0.198167 0.98931 -0.00522989 0.145734 0.993672 -0.0177441 0.110908 0.851106 -0.212659 0.479995 0.873457 -0.110336 0.474234 0.889406 -0.070339 0.451674 0.901405 -0.0245117 0.432283 0.8953 -0.0279264 0.444587 0.918228 0.0266718 0.395154 0.741742 0.341704 0.577111 0.782191 0.332823 0.526694 0.708893 0.176296 0.682927 0.911966 0.0276017 0.409337 0.938587 0.0573006 0.340252 0.78696 0.460841 0.410267 0.849347 0.468184 0.243748 0.792188 0.595313 0.134315 0.856724 0.506082 -0.099526 0.84357 0.521155 -0.129565 0.884011 0.320614 -0.340193 0.877479 0.322014 -0.355439 0.92187 0.0762619 0.379921 0.959989 0.0461346 0.276212 0.89144 0.396549 0.219282 0.944652 0.326414 0.0329525 0.941309 0.337336 0.0119142 0.970892 0.196601 -0.136807 0.965073 0.201531 -0.167393 0.333937 0.556129 -0.761056 0.105765 0.580314 -0.807496 0.307678 0.502395 -0.808043 0.0132315 0.528382 0.848904 0.284299 0.540748 0.791685 0.115726 0.682749 -0.72143 0.0794239 0.839244 -0.537923 0.183108 0.853901 -0.48716 0.01044 0.983631 -0.179889 0.144763 0.982998 -0.112958 0.075104 0.990513 0.115084 0.208451 0.938353 0.275755 0.181329 0.940879 0.286124 -0.0831661 0.809741 0.580864 0.373387 0.783781 0.496256 0.105701 0.733217 0.67173 0.0688671 0.397665 0.914943 0.100105 0.169812 0.980379 0.178761 0.139745 0.973918 0.111637 -0.218845 0.969352 0.341454 -0.214635 0.915064 0.692777 -0.16687 0.70158 0.714412 0.00473888 0.699709 0.412917 0.0743748 0.907727 0.487267 0.329546 0.808684 0.353592 0.431999 0.829668 0.447579 0.630286 0.63436 0.377672 0.687513 0.620234 0.480034 0.799051 0.362056 0.412115 0.850699 0.3263 0.513925 0.857487 0.0244221 0.454271 0.890588 -0.0221756 0.542569 0.76837 -0.33945 0.499057 0.77955 -0.378476 0.553195 0.513043 -0.656325 0.546582 0.512749 -0.66207 0.344665 0.558115 -0.754794 0.287816 0.836598 -0.466118 0.346275 0.834295 -0.429004 0.253014 0.962661 -0.0962658 0.332863 0.941809 -0.0468844 0.223304 0.93456 0.277008 0.313049 0.893965 0.320668 0.200946 0.771748 0.603346 0.291656 0.72146 0.628039 0.187456 0.501134 0.844823 0.269268 0.456755 0.847862 0.179692 0.139889 0.973726 0.4635 0.0976189 0.880703 0.425024 -0.192455 0.884486 0.484358 -0.21667 0.847615 0.870901 -0.173803 0.459699 0.892968 -0.0892563 0.441181 0.690171 -0.0120485 0.723546 0.744779 0.185114 0.641122 0.50329 0.328185 0.79937 0.593142 0.515018 0.618821 0.545205 0.572079 0.612762 0.633557 0.66836 0.389744 0.588801 0.72252 0.362324 0.677985 0.728619 0.0972183 0.639887 0.766367 0.0567923 0.718476 0.657393 -0.227216 0.691092 0.672939 -0.263714 0.739779 0.432396 -0.515519 0.726922 0.433424 -0.532662 0.939621 -0.14722 0.308931 0.939565 -0.207019 0.27269 0.938422 -0.221999 0.264728 0.939692 -0.22089 0.261126 0.939392 -0.222218 0.261077 0.939415 -0.222129 0.261073 0.939897 -0.221096 0.260214 0.939965 -0.221132 0.259936 0.939946 -0.221133 0.260002 0.939758 -0.221396 0.26046 0.939564 -0.221738 0.260868 0.93962 -0.13377 0.314991 0.939838 -0.133532 0.314442 0.940955 -0.134431 0.310695 0.939692 -0.134469 0.314479 0.939965 -0.133278 0.31417 0.939976 -0.133238 0.314156 0.939692 -0.134911 0.314289 0.939472 -0.133902 0.315378 0.939449 -0.13388 0.315455 0.939565 -0.150996 0.307274 0.94337 -0.144746 0.298499 0.936007 -0.177627 0.303874 0.939622 -0.169128 0.2975 0.93966 -0.18666 0.286699 0.937285 -0.193684 0.289799 0.94337 -0.201976 0.263171 0.939621 -0.210193 0.270058 0.939692 -0.220478 0.261472 0.149347 -0.425371 0.892612 0.48879 -0.375303 0.787548 0.346099 -0.57625 0.740372 0.655058 -0.464084 0.596259 0.850962 -0.3226 0.414479 0.850962 -0.3226 0.41448 0.850962 -0.291849 0.436679 0.850962 -0.291849 0.436678 0.850962 -0.259576 0.4566 0.850962 -0.259576 0.4566 0.850962 -0.22595 0.474141 0.850961 -0.225951 0.474142 0.655067 -0.325043 0.682081 0.57344 -0.35919 0.736307 0.573329 -0.404925 0.712271 0.57333 -0.404925 0.71227 0.57333 -0.455268 0.681193 0.573329 -0.455268 0.681193 0.57344 -0.497252 0.651081 0.48879 -0.535838 0.688449 0.346096 -0.403609 0.846946 0.202129 -0.426538 0.881595 0.202091 -0.48402 0.851401 0.202092 -0.48402 0.851401 0.202092 -0.544197 0.814253 0.20209 -0.544198 0.814253 0.202128 -0.596949 0.776399 0.149345 -0.607322 0.780293 -0.707105 0.471309 -0.527135 -0.671184 0.46026 -0.581096 -0.706468 0.440815 -0.553701 -0.706468 0.371766 -0.60224 -0.706471 0.371764 -0.602237 -0.706523 0.299008 -0.64142 -0.672819 0.310903 -0.671307 -0.707101 0.260021 -0.657569 -0.698069 0.403388 -0.591589 -0.698068 0.403389 -0.59159 -0.69807 0.620121 -0.357979 -0.618519 0.666913 -0.415525 -0.706902 0.668502 -0.231071 -0.698069 0.714032 -0.0534679 -0.698067 0.714033 -0.0534685 -0.698068 0.66652 0.261634 -0.698065 0.666524 0.261634 -0.698067 0.486996 0.524917 -0.698076 -0.106761 0.70802 -0.69806 -0.106757 0.708036 -0.700593 0.187219 0.688562 -0.634898 0.227683 0.738285 -0.706901 0.332815 0.624119 -0.698069 0.486994 0.524916 -0.697832 0.346345 -0.626958 -0.697825 0.346346 -0.626965 -0.697824 0.0358126 -0.715373 -0.697831 0.0358146 -0.715367 -0.69783 -0.281993 -0.658418 -0.697822 -0.281998 -0.658424 -0.697821 -0.54251 -0.467684 -0.697827 -0.542505 -0.467682 -0.697826 -0.692782 -0.181913 -0.697828 -0.69278 -0.181913 -0.706469 -0.440815 0.553701 -0.706472 -0.440813 0.553698 -0.706472 -0.371764 0.602237 -0.706468 -0.371766 0.60224 -0.706468 -0.297429 0.642214 -0.706478 -0.297425 0.642205 -0.879243 -0.139003 0.455642 -0.887085 -0.0644997 0.457077 -0.954989 0.073753 0.287326 -0.960101 0.0805862 0.267791 -0.978436 0.0524009 0.199795 -0.978976 0.0523213 0.19715 -0.991397 -0.00763269 0.130669 -0.990797 -0.00525812 0.135252 -0.965171 0.194972 -0.174443 -0.793208 0.598521 0.112227 -0.859467 0.493524 -0.133232 -0.839104 0.526977 -0.134906 -0.884191 0.301901 -0.356459 -0.876485 0.316201 -0.363029 -0.859292 0.337848 0.384026 -0.938545 0.0761524 0.33665 -0.933192 0.0615087 0.354075 -0.821647 0.476522 0.312767 -0.847484 0.475729 0.235483 -0.891281 0.40359 0.206718 -0.947044 0.32097 0.00928209 -0.938319 0.345647 0.00923008 -0.970911 0.192705 -0.142113 -0.989048 0.131148 -0.0677101 -0.807334 0.158457 0.568422 -0.693243 0.449651 0.563231 -0.77072 0.528343 0.356151 -0.902136 0.0103799 0.431327 -0.887851 -0.0699097 0.454789 -0.74952 -0.0104473 0.661899 -0.710135 -0.0247511 0.703631 -0.276014 0.511029 0.814043 -0.145864 -0.0284625 0.988895 -0.197801 -0.18605 0.962424 -0.147935 -0.224769 0.963117 -0.111693 0.842693 -0.526681 -0.094879 0.556125 -0.825665 -0.105774 0.552351 -0.826874 -0.0780639 0.9947 0.0669131 -0.143539 0.981092 -0.129829 -0.177906 0.973832 -0.141421 -0.0972949 0.946061 -0.309035 -0.110862 0.84291 -0.52651 -0.0290688 0.225397 0.973833 -0.134934 0.59486 0.792423 0.129855 0.562077 0.816828 -0.156003 0.774746 0.612725 -0.216101 0.788558 0.57574 -0.0506092 0.875352 0.48083 -0.143392 0.960686 0.237742 -0.273785 0.914383 0.298237 -0.142497 0.974215 0.174926 -0.354226 0.460563 0.813883 -0.457116 0.671584 0.583112 -0.363188 0.691023 0.624965 -0.490849 0.818911 0.297409 -0.397297 0.855588 0.33185 -0.522601 0.851661 -0.0395196 -0.442823 0.896353 -0.0214083 -0.546593 0.742567 -0.38708 -0.493389 0.779317 -0.386306 -0.553359 0.487385 -0.675462 -0.546229 0.492452 -0.677587 -0.176408 0.505968 0.84432 -0.302665 0.763202 0.570891 -0.186325 0.772555 0.606994 -0.325672 0.911916 0.249693 -0.208472 0.93634 0.282501 -0.34326 0.932021 -0.116232 -0.24186 0.965656 -0.0949282 -0.351515 0.803662 -0.480171 -0.282648 0.834084 -0.473723 -0.345026 0.526965 -0.776701 -0.333671 0.532913 -0.777603 -0.879553 -0.139888 0.454773 -0.763474 -0.165928 0.62416 -0.693955 -0.137096 0.706846 -0.651403 -0.172457 0.738873 -0.484435 -0.187839 0.854424 -0.918285 0.0462254 0.393212 -0.901027 0.0382392 0.432074 -0.758733 0.244541 0.603758 -0.805283 0.212317 0.553572 -0.700534 0.319652 0.638024 -0.633832 0.0529456 0.771657 -0.461123 0.0930664 0.882442 -0.425669 -0.15892 0.890814 -0.341497 -0.182693 0.921956 -0.172204 0.170457 0.970201 -0.179208 0.171782 0.968698 -0.424083 0.137036 0.895195 -0.486856 0.353901 0.798577 -0.502664 0.35319 0.789041 -0.601388 0.554469 0.575236 -0.531853 0.578036 0.618875 -0.642826 0.689382 0.333956 -0.575096 0.730438 0.368409 -0.685232 0.727143 0.0414689 -0.629211 0.77509 0.0576997 -0.721676 0.637813 -0.269031 -0.685626 0.675691 -0.270847 -0.739941 0.406772 -0.535746 -0.725681 0.422661 -0.542905 -0.340893 0.585538 -0.735485 -0.994035 -0.0572884 0.092804 -0.994036 -0.0680974 0.0851729 -0.994251 -0.0666935 0.0837726 -0.991754 -0.0536159 0.116403 -0.996676 -0.0384357 0.0718331 -0.658679 0.395235 -0.640259 -0.931791 0.190676 -0.308884 -0.994046 -0.0475349 0.0980502 -0.993744 0.0469324 -0.101337 -0.971837 0.099034 -0.213836 -0.994056 -0.0627939 0.0889369 -0.994035 -0.0572885 0.0928042 -0.93179 0.190676 -0.308884 -0.931639 0.146767 -0.332428 -0.558463 0.527525 -0.640185 -0.739296 0.419412 -0.526817 -0.931791 0.22609 -0.283989 -0.888071 0.295305 -0.352313 -0.971843 0.146762 -0.184345 -0.237289 0.51028 -0.826625 -0.237289 0.605055 -0.760001 -0.108125 0.630541 -0.768588 -0.887838 0.19338 -0.41755 -0.739296 0.282987 -0.611031 -0.658467 0.31023 -0.685696 -0.558103 0.348711 -0.752942 -0.340889 0.395078 -0.853058 -0.658679 0.468644 -0.588656 -0.658679 0.395235 -0.640259 -0.237287 0.51028 -0.826625 -0.237191 0.40221 -0.884289 -0.108043 0.417789 -0.902097 -0.572885 -0.43054 0.697451 -0.850726 -0.328225 0.410528 -0.879519 -0.199083 0.432218 -0.654674 -0.317671 0.68592 -0.764986 -0.27066 0.584414 -0.845144 -0.227738 0.483597 -0.851115 -0.247669 0.462885 -0.850698 -0.276118 0.447295 -0.850697 -0.276118 0.447296 -0.851115 -0.302799 0.428855 -0.345809 -0.394322 0.851426 -0.488407 -0.366716 0.791819 -0.149204 -0.415545 0.897252 -0.201917 -0.41476 0.887245 -0.201877 -0.514467 0.833408 -0.844348 -0.333717 0.419177 -0.654677 -0.470814 0.591382 -0.573006 -0.506907 0.643979 -0.488418 -0.543501 0.682682 -0.345801 -0.58442 0.734081 -0.573004 -0.348515 0.741757 -0.572883 -0.430541 0.697452 -0.201874 -0.514468 0.833409 -0.201914 -0.60728 0.768402 -0.149218 -0.615872 0.773587 -0.146153 -0.80217 0.578932 -0.826271 -0.507782 -0.24379 -0.65141 -0.583194 0.485335 -0.992269 -0.11722 0.0407714 -0.992328 -0.0952814 0.0787856 -0.976262 -0.21424 0.0318338 -0.978909 -0.199794 0.0426585 -0.963219 -0.26454 0.0471896 -0.851018 -0.339569 0.400576 -0.880895 -0.379164 0.2833 -0.902136 -0.381904 0.200749 -0.895766 -0.391312 0.210896 -0.919311 -0.368238 0.13881 -0.740533 -0.668747 -0.0662475 -0.783612 -0.615292 -0.0858376 -0.707955 -0.694521 0.128222 -0.918518 -0.369884 0.139682 -0.938742 -0.334323 0.0836201 -0.785901 -0.567637 -0.245252 -0.847487 -0.423726 -0.319723 -0.793259 -0.368471 -0.484737 -0.856962 -0.120975 -0.500981 -0.84421 -0.0981192 -0.526956 -0.884164 0.175306 -0.433038 -0.877674 0.189406 -0.440242 -0.945947 -0.314559 0.0789739 -0.960044 -0.275956 0.0465109 -0.891348 -0.365568 -0.268066 -0.944831 -0.166383 -0.282153 -0.94185 -0.150036 -0.300678 -0.970926 0.0405761 -0.235916 -0.965173 0.0685223 -0.25248 -0.130879 -0.307197 -0.942603 -0.0963532 -0.108525 -0.989413 -0.146465 0.0899589 -0.985117 -0.0515375 0.136397 -0.989313 -0.106236 0.509943 -0.853623 -0.157407 0.486934 -0.859138 -0.33401 0.460347 -0.822507 -0.0122593 -0.992287 -0.123355 -0.240099 -0.956867 -0.163581 -0.151004 -0.300523 -0.941745 -0.0724033 -0.519703 -0.851274 -0.201893 -0.641723 -0.739885 -0.130414 -0.672146 -0.728843 -0.0119135 -0.877037 -0.480276 -0.320807 -0.800246 -0.506645 -0.105199 -0.91714 -0.384432 -0.0889248 -0.995985 0.0103241 -0.0329032 -0.974681 0.221165 -0.190435 -0.941614 0.277664 -0.0911601 -0.79123 0.604685 -0.341493 -0.742273 0.576553 -0.693994 -0.570408 0.439325 -0.714751 -0.638292 0.285858 -0.412191 -0.85538 0.313726 -0.486903 -0.872473 0.0414249 -0.35418 -0.933992 -0.0470718 -0.447644 -0.839892 -0.306913 -0.378518 -0.849854 -0.366704 -0.480137 -0.663092 -0.574263 -0.413113 -0.650292 -0.63754 -0.514073 -0.380556 -0.768704 -0.455181 -0.349809 -0.818806 -0.542688 -0.012377 -0.839843 -0.499639 0.0202123 -0.865998 -0.553286 0.382414 -0.740023 -0.546676 0.388046 -0.742002 -0.344677 0.453467 -0.821928 -0.28826 0.0759629 -0.954534 -0.346237 0.0414754 -0.93723 -0.253714 -0.312758 -0.915321 -0.332834 -0.350901 -0.875265 -0.224029 -0.640719 -0.734364 -0.313029 -0.665026 -0.678051 -0.201526 -0.869838 -0.450299 -0.291644 -0.872184 -0.392732 -0.187833 -0.976724 -0.103578 -0.269299 -0.961162 -0.0603766 -0.179207 -0.942923 0.280679 -0.463844 -0.841641 0.276565 -0.425693 -0.725087 0.541326 -0.484449 -0.679591 0.550877 -0.875379 -0.343679 0.339995 -0.889599 -0.371626 0.265533 -0.689729 -0.651887 0.315147 -0.745699 -0.659278 0.0963594 -0.502663 -0.863655 0.0378033 -0.59328 -0.777579 -0.208301 -0.54628 -0.794629 -0.264845 -0.63376 -0.633691 -0.443603 -0.58999 -0.629276 -0.505889 -0.678233 -0.392928 -0.620973 -0.640944 -0.369556 -0.67277 -0.718702 -0.0680739 -0.691978 -0.691735 -0.0395372 -0.721068 -0.739912 0.287897 -0.607985 -0.727056 0.303889 -0.615663 -0.939508 -0.1433 0.311112 -0.939607 -0.123473 0.319206 -0.939482 -0.123471 0.319575 -0.939572 -0.123629 0.319251 -0.93969 -0.124468 0.318576 -0.939849 -0.123205 0.318598 -0.939867 -0.123148 0.318566 -0.939728 -0.123352 0.318899 -0.939515 -0.213885 0.267517 -0.940506 -0.227239 0.252608 -0.939696 -0.229515 0.253562 -0.939886 -0.22959 0.252789 -0.93969 -0.22916 0.253906 -0.939535 -0.23015 0.253583 -0.939494 -0.230317 0.253585 -0.939513 -0.230251 0.253575 -0.93975 -0.229729 0.253169 -0.939508 -0.213897 0.267532 -0.939511 -0.213892 0.267524 -0.939694 -0.197267 0.279396 -0.939694 -0.197269 0.279393 -0.939498 -0.179938 0.291489 -0.939498 -0.179938 0.29149 -0.939694 -0.161357 0.301563 -0.939693 -0.161354 0.301565 -0.939511 -0.143296 0.311104 -0.939515 -0.143292 0.311094 -0.939697 -0.124242 0.318644 0 0.514583 -0.857441 0.0153588 0.483488 -0.875216 -0.0139711 0.138633 -0.990245 0.0215397 0.0499872 -0.998518 0.00266667 -0.101761 -0.994805 -0.00681614 -0.292184 -0.956338 0.029277 -0.393531 -0.918845 0.000646875 -0.515148 -0.857101 0 -0.967211 -0.253974 0.0389784 -0.980615 -0.192027 0.001844 -0.918336 -0.395798 -0.00669146 -0.757392 -0.652927 0.0594577 -0.822028 -0.566334 -0.000757916 -0.668447 -0.74376 0.700047 0.703904 -0.120221 0.700048 0.703903 -0.120221 0.700044 0.407446 -0.586452 0.700041 0.407448 -0.586454 0.700042 0.602597 -0.38317 0.776297 0.515637 -0.362604 0.706719 0.647649 -0.284777 0.4585 -0.510195 -0.727653 0.694737 0.30356 -0.652067 0.694738 0.30356 -0.652067 0.705698 0.0601412 -0.705956 0.754938 0.0134809 -0.655658 0.624887 -0.137325 -0.768543 0.705016 -0.169432 -0.688655 0.703698 -0.333175 -0.627537 0.704401 -0.483767 -0.519412 0.704401 -0.596015 -0.385468 0.458493 -0.805672 -0.375069 0.694743 -0.588919 0.412923 0.694739 -0.588923 0.412925 0.702914 -0.697606 0.13877 0.466759 -0.88097 0.0776386 0.705015 -0.707675 -0.0463747 0.703697 -0.676138 -0.218284 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706174 0.327473 -0.627758 0.706176 0.327473 -0.627756 0.706175 0.414427 -0.57408 0.706175 0.414427 -0.574079 -0.69807 -0.310635 -0.645139 -0.698065 -0.310639 -0.645143 -0.698069 4.14946e-05 -0.71603 -0.618517 -0.0263993 -0.785328 -0.706896 0.13413 -0.694483 -0.698061 0.310713 -0.645111 -0.698066 0.310713 -0.645105 -0.698068 0.559842 -0.446407 -0.698068 0.559841 -0.446406 -0.698069 0.698087 -0.159293 -0.698073 0.559787 0.446468 -0.698063 0.559796 0.446471 -0.700594 0.689922 0.182142 -0.634912 0.753204 0.171963 -0.706906 0.706905 0.0238473 -0.698074 0.698083 -0.15929 -0.699624 -0.354733 -0.620235 -0.699628 -0.354729 -0.620232 -0.699624 -0.572021 -0.428158 -0.699633 -0.572012 -0.428155 -0.699633 -0.695061 -0.165539 -0.699629 -0.695065 -0.165539 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.433832 -0.900994 0 0.73119 0.682174 0.0323308 0.781387 0.623209 0.00477353 0.85394 0.520349 -0.0109507 0.956702 0.290865 0.00691634 0.96685 0.255252 -0.00188771 0.99943 0.0337156 -0.023329 0.991315 -0.129426 0.0208222 0.97473 -0.222416 0.00130027 0.923723 -0.38306 -0.00323655 0.852767 -0.522282 0.0314905 0.781479 -0.623136 0.00698259 0.724416 -0.689328 -0.000756838 0.199149 -0.979969 0.00319996 0.370241 -0.92893 0.0274198 0.433773 -0.900605 0.00213086 0.550712 -0.834693 -0.000711902 0.634537 -0.772892 0.00389266 -0.440868 -0.897564 -0.00331188 -0.0410754 -0.999151 -2.10096e-05 -0.0335967 -0.999435 -6.06363e-07 0.189633 -0.981855 0 -0.447582 -0.894243 0.0184741 -0.496384 -0.867906 0.00026109 -0.618221 -0.786005 -0.000963971 -0.800576 -0.599231 0.00813377 -0.788603 -0.614849 -0.00869777 -0.972754 -0.231676 0 -0.968677 -0.248325 0 0.366108 0.930572 0 0.366108 0.930572 0 0.474284 0.880372 0 0.474284 0.880372 0 0.575714 0.817651 0 0.575714 0.817651 0 -0.575714 -0.817651 0 -0.575714 -0.817651 0 -0.474284 -0.880372 0 -0.474284 -0.880372 0 -0.366109 -0.930572 0 -0.366109 -0.930572 -0.87924 0.325102 0.348202 -0.887085 0.363594 0.284394 -0.954989 0.28571 0.0797911 -0.960101 0.272209 0.0641057 -0.978436 0.199228 0.0545167 -0.978976 0.196898 0.0532634 -0.991397 0.109347 0.0719443 -0.990797 0.114504 0.0721797 -0.965172 -0.0535835 -0.256071 -0.793203 0.396452 -0.462228 -0.859465 0.13138 -0.494023 -0.839107 0.146653 -0.523825 -0.884191 -0.157751 -0.439683 -0.876484 -0.156291 -0.455356 -0.859294 0.501497 -0.100578 -0.938547 0.329621 0.102373 -0.933195 0.337388 0.123763 -0.821649 0.509122 -0.256297 -0.847484 0.441802 -0.294248 -0.891282 0.38082 -0.246157 -0.947045 0.16852 -0.273325 -0.938318 0.180816 -0.294727 -0.970911 -0.0267213 -0.237945 -0.989047 0.00693388 -0.147436 -0.807335 0.571493 0.146989 -0.693238 0.712601 -0.107801 -0.770717 0.572611 -0.279487 -0.902136 0.378729 0.206678 -0.887851 0.358904 0.287938 -0.749525 0.567992 0.339996 -0.710136 0.596983 0.373253 -0.276028 0.960492 -0.0355467 -0.14587 0.842182 0.519087 -0.197808 0.74046 0.642333 -0.147943 0.7217 0.676211 -0.111694 -0.0347702 -0.993134 -0.0948779 -0.436984 -0.894451 -0.105771 -0.439918 -0.891788 -0.0780741 0.55531 -0.827971 -0.143553 0.378107 -0.914564 -0.177907 0.364444 -0.914073 -0.0972938 0.205394 -0.973831 -0.110864 -0.0345141 -0.993236 -0.0290519 0.956062 0.29172 -0.134924 0.98369 -0.118954 0.129847 0.988433 -0.0783636 -0.15601 0.918005 -0.364593 -0.216103 0.892883 -0.395044 -0.050615 0.854086 -0.517663 -0.143394 0.686234 -0.713107 -0.273798 0.715473 -0.642754 -0.142492 0.638588 -0.756241 -0.354213 0.93513 0.00807699 -0.457104 0.840788 -0.290055 -0.363203 0.88674 -0.285965 -0.490858 0.667015 -0.56049 -0.397284 0.715192 -0.575036 -0.522593 0.391605 -0.757326 -0.442823 0.429632 -0.786972 -0.546593 0.0360627 -0.836621 -0.49339 0.0551079 -0.868061 -0.553359 -0.34127 -0.759821 -0.546236 -0.340578 -0.765266 -0.176415 0.984185 -0.0160239 -0.302674 0.876004 -0.375508 -0.186318 0.911952 -0.365554 -0.325665 0.6722 -0.664898 -0.208473 0.712821 -0.669646 -0.343261 0.365352 -0.865268 -0.241869 0.400617 -0.883745 -0.351515 -0.0140071 -0.936078 -0.282654 0.00678643 -0.959198 -0.345033 -0.409159 -0.844714 -0.333666 -0.406963 -0.850322 -0.879551 0.323902 0.348536 -0.763486 0.457561 0.455771 -0.693957 0.543599 0.472148 -0.651405 0.553655 0.518784 -0.484424 0.646041 0.589885 -0.91828 0.363652 0.156583 -0.901027 0.393306 0.182923 -0.758731 0.645143 0.0901013 -0.805284 0.585564 0.0929158 -0.700528 0.712377 0.042184 -0.633822 0.694758 0.339973 -0.461114 0.810758 0.360618 -0.425661 0.692012 0.583037 -0.34149 0.707095 0.619194 -0.172209 0.925443 0.33749 -0.17922 0.924803 0.335589 -0.424087 0.843775 0.328928 -0.48686 0.868536 0.0928071 -0.502661 0.859926 0.0886557 -0.60139 0.7754 -0.192574 -0.531849 0.824981 -0.191164 -0.642818 0.633913 -0.430045 -0.575099 0.68427 -0.44837 -0.685236 0.39948 -0.608989 -0.62921 0.437513 -0.642399 -0.721674 0.0859193 -0.68688 -0.685624 0.103285 -0.720591 -0.73994 -0.260583 -0.62015 -0.72568 -0.258838 -0.637489 -0.146141 0.100286 0.984168 -0.826272 -0.46502 0.317854 -0.651418 0.128714 0.747722 -0.992269 -0.0233025 0.121902 -0.992328 0.0205897 0.121909 -0.976263 -0.0795488 0.201453 -0.978909 -0.0629538 0.194356 -0.963218 -0.0914059 0.252699 -0.851017 0.177128 0.494364 -0.880896 0.0557595 0.470015 -0.902136 -0.017096 0.431114 -0.895768 -0.0130131 0.444332 -0.919312 -0.0639051 0.388306 -0.740536 -0.391746 0.546024 -0.783608 -0.381986 0.489945 -0.707948 -0.236217 0.665591 -0.918518 -0.0639726 0.390169 -0.938742 -0.0947438 0.331342 -0.785898 -0.496217 0.368964 -0.847485 -0.488754 0.207095 -0.793258 -0.604031 0.076738 -0.856961 -0.494351 -0.145721 -0.844208 -0.50542 -0.178506 -0.884163 -0.287369 -0.368341 -0.877674 -0.286559 -0.384152 -0.945947 -0.0888853 0.311902 -0.960044 -0.0976978 0.262241 -0.89135 -0.414932 0.182555 -0.944832 -0.327542 0.00301927 -0.94185 -0.335413 -0.0204023 -0.970926 -0.18402 -0.153097 -0.965173 -0.184393 -0.185582 -0.261285 -0.957171 0.124717 -0.0792265 -0.981593 0.173777 -0.103093 -0.972476 -0.208956 -0.0250711 -0.968891 -0.246215 -0.16551 -0.806554 -0.567518 -0.0785806 -0.789145 -0.609159 -0.114909 -0.61722 -0.778354 -0.334014 -0.48214 -0.809923 -0.105776 -0.502793 -0.857911 -0.273946 -0.434074 -0.858215 -0.300416 -0.615278 0.728824 -0.0388401 -0.600424 0.798738 -0.115213 -0.842293 0.526563 -0.0235603 -0.869947 0.492582 -0.107881 -0.953847 0.280245 -0.0615422 -0.48697 0.871248 -0.111848 -0.26413 0.95798 -0.190427 -0.230344 0.954295 -0.0911502 0.128057 0.987569 -0.341511 0.128173 0.931097 -0.693992 0.0952681 0.713652 -0.71475 -0.0715892 0.695706 -0.412193 -0.155998 0.897642 -0.486905 -0.400356 0.776298 -0.354173 -0.507763 0.785327 -0.447643 -0.685743 0.57391 -0.378516 -0.742505 0.552641 -0.480131 -0.828877 0.287118 -0.413117 -0.87727 0.244401 -0.514077 -0.855993 -0.0547791 -0.455181 -0.884011 -0.10646 -0.542688 -0.733513 -0.409204 -0.499643 -0.739868 -0.450502 -0.553288 -0.449676 -0.701188 -0.546669 -0.448572 -0.707062 -0.344677 -0.485078 -0.803677 -0.288256 -0.78867 -0.543054 -0.346234 -0.790928 -0.504535 -0.253714 -0.949068 -0.186811 -0.332848 -0.933448 -0.133741 -0.224043 -0.956334 0.187698 -0.313045 -0.919716 0.236907 -0.201539 -0.824885 0.528154 -0.291643 -0.77621 0.558965 -0.187831 -0.578065 0.794078 -0.269301 -0.532868 0.802203 -0.179216 -0.22839 0.956932 -0.463848 -0.181312 0.867162 -0.425696 0.106261 0.898605 -0.484445 0.137277 0.863984 -0.875379 0.122608 0.467632 -0.8896 0.0441421 0.454602 -0.689732 -0.0530238 0.722121 -0.745699 -0.246191 0.61913 -0.502682 -0.399082 0.766841 -0.59329 -0.569173 0.569253 -0.546282 -0.626677 0.555745 -0.633765 -0.701015 0.326988 -0.589994 -0.752749 0.29202 -0.678233 -0.734242 0.0298015 -0.640943 -0.767415 -0.016339 -0.718701 -0.633308 -0.287035 -0.691732 -0.644233 -0.326297 -0.739909 -0.382584 -0.553321 -0.727058 -0.381238 -0.571003 -0.572883 0.388741 0.721586 -0.850726 0.191416 0.489516 -0.879516 0.274773 0.388523 -0.654677 0.435187 0.61807 -0.764997 0.370779 0.526594 -0.845142 0.304941 0.439028 -0.851114 0.277031 0.445935 -0.850697 0.249311 0.462773 -0.850698 0.24931 0.462772 -0.851115 0.219998 0.476659 -0.3458 0.540197 0.767209 -0.488397 0.502381 0.7135 -0.149213 0.569269 0.808498 -0.201915 0.560997 0.802816 -0.201875 0.46452 0.862246 -0.844349 0.196159 0.498595 -0.654685 0.276742 0.703421 -0.573004 0.30425 0.760985 -0.488413 0.319471 0.812029 -0.345817 0.343521 0.873158 -0.573004 0.468122 0.672702 -0.572883 0.388741 0.721585 -0.201878 0.464519 0.862246 -0.201919 0.361816 0.91012 -0.149204 0.36201 0.920156 -0.340896 -0.344179 -0.874832 -0.994035 0.0517264 0.096015 -0.994036 0.0397131 0.10156 -0.994251 0.0392024 0.0996446 -0.991754 0.0739999 0.104634 -0.996676 0.0429936 0.0692054 -0.658678 -0.356863 -0.662413 -0.93179 -0.172164 -0.319572 -0.994046 0.0611463 0.0901914 -0.993745 -0.0642939 -0.0913127 -0.971837 -0.135668 -0.192681 -0.994056 0.0456227 0.0988499 -0.994035 0.0517263 0.0960149 -0.93179 -0.172164 -0.319572 -0.931639 -0.214508 -0.293318 -0.558458 -0.290655 -0.776946 -0.739297 -0.24653 -0.626629 -0.93179 -0.132896 -0.337795 -0.888071 -0.157459 -0.431898 -0.971842 -0.0862666 -0.219272 -0.237291 -0.460738 -0.855227 -0.237291 -0.355652 -0.903994 -0.108131 -0.350346 -0.930358 -0.887837 -0.26492 -0.376249 -0.739294 -0.387676 -0.550592 -0.658467 -0.438715 -0.611516 -0.558112 -0.477708 -0.678459 -0.340883 -0.541233 -0.768678 -0.658679 -0.275469 -0.700185 -0.658679 -0.356863 -0.662413 -0.237287 -0.460739 -0.855228 -0.23719 -0.564712 -0.790469 -0.108042 -0.572344 -0.812865 -0.939508 0.19778 0.279657 -0.93961 0.214698 0.266529 -0.939482 0.215027 0.266716 -0.939572 0.214663 0.266691 -0.93969 0.213662 0.267079 -0.939849 0.214312 0.265996 -0.939867 0.214313 0.265932 -0.939722 0.214505 0.266288 -0.939514 0.124734 0.318989 -0.940508 0.105147 0.323091 -0.939696 0.104833 0.325548 -0.939887 0.104123 0.325225 -0.93969 0.105305 0.325412 -0.939536 0.104534 0.326104 -0.939492 0.104446 0.326261 -0.939513 0.104474 0.32619 -0.93975 0.104384 0.325537 -0.939508 0.124741 0.319005 -0.939511 0.124737 0.318998 -0.939693 0.143325 0.310539 -0.939693 0.143327 0.310539 -0.939497 0.162469 0.301577 -0.939498 0.162469 0.301576 -0.939694 0.180484 0.29052 -0.939694 0.180482 0.29052 -0.939511 0.197775 0.279649 -0.939515 0.197769 0.279641 -0.939697 0.213833 0.266917 0 -0.994656 0.10324 0.0350267 -0.977437 0.208303 0.0183693 -0.962734 0.269827 -0.022483 -0.87002 0.492504 0.0010649 -0.834548 0.550935 -0.00105133 -0.66517 0.746691 -0.0080751 -0.680068 0.733104 0.00656488 -0.49218 0.870469 6.10314e-06 -0.511723 0.85915 -3.22836e-05 -0.29339 0.955993 -0.00856137 -0.271239 0.962474 0.0138175 0.0756576 0.997038 0 0.0982886 0.995158 -0.696805 0.05427 0.715205 -0.696801 0.0542718 0.715209 -0.696798 -0.281376 0.659773 -0.324174 -0.277546 0.904367 -0.696798 -0.701514 0.149501 -0.696792 -0.701519 0.149504 -0.7039 -0.592779 0.391329 -0.535506 -0.651969 0.536814 -0.705125 -0.48224 0.519849 -0.705126 -0.362854 0.609208 0 0.9968 0.0799386 -0.0226704 0.947968 0.317558 0.00884496 0.967592 0.252365 -0.00748658 0.760613 0.649163 0 0.748091 0.663596 0.697964 0.692951 0.180734 0.697964 0.692951 0.180734 0.697965 0.544715 0.464899 0.697955 0.54472 0.464908 0.698108 0.331152 -0.634809 0.698113 0.331149 -0.634806 0.698115 0.573344 -0.42885 0.69811 0.573349 -0.428851 0.698111 0.702498 -0.138339 0.698111 0.702498 -0.138339 0.698111 -0.288494 -0.655295 0.698109 -0.288494 -0.655298 0.698106 0.0236626 -0.715603 0.842206 -0.0344845 -0.538052 0.705432 0.112842 -0.699737 0.698063 -0.388865 -0.601242 0.698066 -0.388864 -0.601239 0.704265 -0.56689 -0.427373 0.7716 -0.531537 -0.349431 0.684045 -0.665572 -0.29849 0.706898 -0.662677 -0.247296 0.698065 -0.712522 -0.0708389 0.698066 -0.71252 -0.0708384 0.698068 -0.672694 0.245324 0.698066 -0.672696 0.245324 0.698066 -0.499636 0.512902 0.69807 0.089484 0.710416 0.69807 0.089484 0.710417 0.700604 -0.20393 0.683789 0.627463 -0.247521 0.738258 0.706894 -0.347899 0.615847 0.698059 -0.499642 0.512905 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706179 -0.379914 -0.597475 0.706171 -0.379919 -0.597482 0.706171 -0.289956 -0.645948 0.706173 -0.289955 -0.645946 0 -0.387437 -0.921896 0.0420207 -0.409156 -0.911496 0 -0.452954 -0.891534 0 -0.536577 -0.843851 0.0629302 -0.555632 -0.829043 0 -0.495339 -0.868699 0.706172 0.379918 0.597481 0.706183 0.379913 0.597471 0.706183 0.289951 0.645937 0.706179 0.289952 0.64594 0 -0.543081 -0.83968 0 0.202371 0.979309 -0.0219204 0.124942 0.991922 -0.00326123 0.000314986 0.999995 0.00738482 -0.250246 0.968154 -0.00467538 -0.285793 0.95828 0.00127474 -0.491854 0.870676 0.0165186 -0.633399 0.773649 -0.0121514 -0.697733 0.716255 0.00722492 -0.877987 0.47863 -0.0216186 -0.939256 0.342536 -0.00297729 -0.968217 0.250095 4.3776e-06 -0.936919 -0.349546 3.11689e-05 -0.984189 -0.177119 -0.0189469 -0.994916 -0.0989139 -0.0014698 -0.999378 0.0352247 0.000304479 -0.991606 0.129296 -0.00626426 -0.527807 -0.849341 0.00534402 -0.825879 -0.563822 1.82963e-05 -0.835608 -0.549326 -2.65639e-07 -0.936889 -0.349626 0.00101487 0.298269 -0.954481 0 -0.552361 -0.833605 -0.0140738 -0.402891 -0.91514 -0.000858713 0.197129 -0.980377 -0.0120158 0.0503044 -0.998662 -0.0163229 0.0330442 -0.999321 0.00344529 -0.158067 -0.987422 -0.00894427 -0.385081 -0.922839 -0.0133957 0.442792 -0.896524 -0.0187232 0.462427 -0.886459 0.00146417 0.596127 -0.802889 -0.00147684 0.713039 -0.701123 -0.0193635 0.800626 -0.598852 -0.00546891 0.832976 -0.553283 0 0.981157 -0.193214 -0.0315539 0.992628 -0.11702 0.00301905 0.936312 -0.351157 0.994042 0.0606815 0.0905413 0.97185 -0.131167 -0.19571 0.658911 -0.356767 -0.662234 0.108091 -0.385167 -0.916495 0.558293 -0.321435 -0.764845 0.341056 -0.364208 -0.866622 0.237326 -0.368666 -0.898756 0.237622 -0.439981 -0.865998 0.153992 -0.468627 -0.869871 0.237622 -0.481152 -0.843818 0.237427 -0.540816 -0.806937 0.887897 -0.178238 -0.424111 0.739453 -0.260826 -0.620628 0.108168 -0.56857 -0.815492 0.34105 -0.523357 -0.780886 0.658911 -0.418788 -0.624862 0.558609 -0.476224 -0.679093 0.739452 -0.374799 -0.559228 0.971845 -0.091289 -0.217219 0.931702 -0.133153 -0.337937 0.931867 -0.172071 -0.3194 0.658688 -0.283806 -0.696839 0.65891 -0.356767 -0.662235 0.931867 -0.172071 -0.3194 0.931867 -0.201984 -0.301375 0.888089 -0.267869 -0.373556 0.994042 0.0422288 0.100482 0.994042 0.0422287 0.100482 0.994053 0.0493269 0.0970892 0.994978 0.0474735 0.0881209 0.994053 0.0539431 0.094603 0.994042 0.0606816 0.0905414 0 0.566694 0.823928 -0.0635019 0.535494 0.842148 0 0.50576 0.862674 0 0.44219 0.896921 -0.0635027 0.408691 0.910461 0 0.376312 0.926493 0.0983853 -0.935593 -0.339095 0.738159 -0.191161 0.646976 0.933081 -0.0714618 0.352495 0.885792 0.0636078 0.459702 0.902775 0.00130264 0.430112 0.900886 -0.0250439 0.433333 0.893717 0.0286265 0.447717 0.982611 -0.0557846 0.177096 0.968947 -0.0745983 0.235748 0.959186 -0.0891649 0.268349 0.978164 -0.0535197 0.200825 0.993506 0.0122652 0.11312 0.993503 0.00594048 0.113653 0.955084 -0.0818879 0.284797 0.937215 -0.0859553 0.337993 0.812781 -0.440725 0.380984 0.759739 -0.390581 0.519849 0.532646 -0.594743 0.602137 0.600305 -0.567406 0.563634 0.364123 -0.707864 0.605263 0.456001 -0.684425 0.568882 0.187429 -0.788965 0.585154 0.14552 0.00652308 0.989334 0.172314 -0.196015 0.965343 0.884955 0.0582936 0.462014 0.712668 -0.0220864 0.701154 0.69772 -0.0515216 0.714516 0.461102 -0.116805 0.879626 0.423351 -0.157455 0.892178 0.179688 -0.19707 0.963782 0.275272 -0.529032 0.802715 0.91822 -0.0571743 0.391923 0.916084 -0.0566001 0.396972 0.771368 -0.336384 0.54022 0.722823 -0.239736 0.648116 0.503307 -0.374598 0.77869 0.487236 -0.376504 0.787938 0.353628 -0.480011 0.802831 0.177325 -0.528724 0.830064 0.301521 -0.775489 0.554708 0.2753 -0.921645 0.273461 0.144762 -0.978748 0.145243 0.0773407 -0.996015 0.0444149 0.87644 -0.30723 -0.370758 0.884046 -0.294014 -0.363344 0.725686 -0.409001 -0.553262 0.739823 -0.394236 -0.545197 0.546204 -0.475658 -0.689501 0.55328 -0.470954 -0.687084 0.333635 -0.514002 -0.790246 0.344989 -0.508481 -0.788942 0.105765 -0.531712 -0.840295 0.121187 -0.526704 -0.841366 0.145495 -0.976366 -0.159816 0.171355 -0.971067 -0.16633 0.342311 -0.929689 -0.136019 0.242335 -0.962644 -0.120791 0.521637 -0.851221 -0.0575966 0.443192 -0.89528 -0.0453264 0.684251 -0.728776 0.0261829 0.629491 -0.776127 0.0369773 0.792146 -0.602231 0.0991133 0.839075 -0.523397 -0.148353 0.858963 -0.491409 -0.143874 0.685633 -0.668556 -0.287993 0.721183 -0.632296 -0.283013 0.493415 -0.769177 -0.40609 0.546138 -0.734122 -0.403482 0.282724 -0.821621 -0.494982 0.351088 -0.792958 -0.497951 0.0859443 -0.829898 -0.551256 0.106822 -0.825309 -0.554485 0.147941 0.202713 0.967998 0.20559 0.162017 0.965134 0.341466 0.160328 0.926119 0.424997 0.140006 0.894302 0.484349 0.166347 0.858915 0.687664 0.1509 0.710175 0.647358 0.10989 0.754223 0.870205 0.191994 0.453742 0.850013 0.131804 0.510006 0.0290233 -0.248694 0.968147 0.135847 -0.61779 0.77452 -0.181678 -0.586753 0.789122 0.289896 -0.823236 0.488101 0.0131217 -0.83772 0.545942 0.14353 -0.966354 0.213448 0.324431 -0.91736 0.230639 0.209385 -0.943602 0.256463 0.489608 -0.825664 0.28029 0.39807 -0.864097 0.308021 0.641638 -0.697206 0.319695 0.575702 -0.739947 0.347917 0.805191 -0.484988 0.341255 0.849349 -0.481716 0.215769 0.891417 -0.4088 0.195598 0.946586 -0.322441 0.00264392 0.938297 -0.345831 0.00029731 0.97139 -0.177896 -0.157333 0.963017 -0.206681 -0.172861 0.146452 0.737589 0.659177 0.824721 0.531634 -0.192872 0.651388 0.535194 0.537831 0.942264 0.327492 0.0699064 0.971801 0.22476 0.07132 0.978816 0.19735 0.0545108 0.98931 0.123593 0.0773954 0.993672 0.0871783 0.0708205 0.851108 0.309356 0.424163 0.873459 0.35553 0.332668 0.889408 0.355991 0.286747 0.901406 0.36211 0.237368 0.895298 0.371063 0.246482 0.918227 0.355551 0.174478 0.741744 0.670643 -0.00736795 0.78219 0.622542 -0.0248846 0.708896 0.679579 0.188784 0.911964 0.3683 0.180765 0.938587 0.323318 0.1205 0.78696 0.585723 -0.193967 0.849346 0.445186 -0.283585 0.792187 0.413979 -0.4484 0.856723 0.16685 -0.488043 0.84357 0.148373 -0.516115 0.884012 -0.134309 -0.447754 0.877482 -0.14681 -0.456588 0.921868 0.367159 0.123914 0.959989 0.262276 0.09815 0.891441 0.388176 -0.233776 0.944653 0.191746 -0.266204 0.941309 0.178987 -0.286184 0.970892 -0.020179 -0.238666 0.965072 -0.044202 -0.258227 0.0703902 0.601203 -0.79599 0.218124 0.707482 -0.672229 0.128116 0.453174 -0.882167 0.235913 0.39761 -0.886708 0.122754 0.307696 -0.943533 0.153996 -0.375957 -0.913751 0.0814445 -0.153094 -0.98485 0.241036 0.0103342 -0.970461 0.132203 0.0613084 -0.989325 0.0950298 0.204942 -0.97415 0.108059 -0.548522 -0.829124 0.222491 -0.397689 -0.890135 0.333936 -0.38103 -0.86215 0.307529 0.948522 -0.07571 0.0132501 0.999363 -0.0331413 0.118476 0.934432 -0.335857 0.217933 0.905959 -0.362964 0.0215235 0.834633 -0.550387 0.197909 0.715863 -0.669606 0.0926701 0.991791 0.0881086 0.0301626 0.946603 0.320987 0.178763 0.91331 0.365936 0.111636 0.73006 0.674203 0.341459 0.685148 0.643411 0.692777 0.524153 0.495302 0.714412 0.608334 0.345752 0.412914 0.823302 0.389455 0.487266 0.865115 0.118945 0.353587 0.934516 0.0407074 0.447571 0.864518 -0.228668 0.377675 0.880895 -0.285282 0.480035 0.713076 -0.510969 0.412106 0.707934 -0.573584 0.513918 0.449891 -0.730401 0.454268 0.426089 -0.782361 0.542568 0.0902128 -0.835154 0.499057 0.062006 -0.864348 0.553194 -0.311876 -0.77247 0.546588 -0.316992 -0.775085 0.344666 -0.374612 -0.860738 0.287818 0.0146279 -0.957574 0.346284 0.0456207 -0.93702 0.253027 0.397964 -0.881818 0.332872 0.430301 -0.839069 0.223318 0.707179 -0.670841 0.313043 0.724687 -0.613867 0.200936 0.908388 -0.366682 0.291654 0.904629 -0.31078 0.187454 0.982205 -0.0115866 0.269265 0.962648 0.0283651 0.179683 0.913217 0.365718 0.463498 0.811521 0.355814 0.425022 0.669758 0.608918 0.484356 0.62572 0.611452 0.8709 0.311207 0.380373 0.892969 0.337446 0.297887 0.690176 0.620582 0.372204 0.744782 0.647782 0.160244 0.503297 0.856365 0.115464 0.593148 0.79342 -0.136603 0.545205 0.816707 -0.189055 0.633559 0.671705 -0.383947 0.58881 0.675039 -0.444552 0.677992 0.448503 -0.582385 0.639888 0.432364 -0.635299 0.718476 0.131924 -0.682927 0.69109 0.108087 -0.714641 0.739778 -0.230255 -0.632227 0.726916 -0.244592 -0.641691 0.939621 0.193932 0.281961 0.939566 0.132647 0.315628 0.938422 0.118263 0.324621 0.939692 0.115697 0.321859 0.939391 0.114988 0.322988 0.939415 0.115031 0.322905 0.939897 0.114801 0.321582 0.939962 0.114554 0.321479 0.939947 0.114601 0.321507 0.939758 0.114866 0.321963 0.939563 0.115049 0.322466 0.939619 0.205906 0.273346 0.939838 0.205548 0.272865 0.94096 0.201841 0.27176 0.939692 0.205113 0.273693 0.939965 0.205441 0.272505 0.939975 0.205448 0.272468 0.939692 0.204726 0.273982 0.939471 0.206178 0.273652 0.939451 0.206247 0.273669 0.939565 0.19061 0.284404 0.94337 0.186134 0.274603 0.936007 0.174349 0.305766 0.939622 0.173078 0.295219 0.939661 0.154958 0.305002 0.937285 0.154131 0.312634 0.94337 0.126925 0.306501 0.939621 0.12878 0.317061 0.939692 0.116202 0.321676 0.149354 0.560338 0.814687 0.488788 0.494386 0.718796 0.34611 0.353054 0.86923 0.655052 0.284336 0.700043 0.850963 0.197649 0.486617 0.850962 0.19765 0.486619 0.850962 0.23225 0.471088 0.850962 0.23225 0.471088 0.850962 0.265639 0.453101 0.850963 0.265638 0.453099 0.850963 0.297643 0.432748 0.850963 0.297643 0.432748 0.65506 0.428182 0.622541 0.57344 0.458066 0.679222 0.573329 0.414382 0.706811 0.573327 0.414382 0.706812 0.573327 0.362298 0.734872 0.573328 0.362298 0.734871 0.573439 0.315227 0.756174 0.488785 0.328297 0.808276 0.346098 0.531672 0.773007 0.202127 0.550215 0.81019 0.202089 0.495324 0.844875 0.202092 0.495324 0.844874 0.202092 0.433066 0.878415 0.202093 0.433066 0.878415 0.202131 0.373907 0.905172 0.149342 0.372092 0.916103 -0.707098 -0.220866 -0.671737 -0.671183 -0.273114 -0.689146 -0.706463 -0.259114 -0.658613 -0.706462 -0.335675 -0.623084 -0.70647 -0.335671 -0.623077 -0.706522 -0.405983 -0.579659 -0.672813 -0.425921 -0.604909 -0.707103 -0.439468 -0.553962 -0.70648 0.259107 0.658597 -0.706474 0.259109 0.658603 -0.706474 0.33567 0.623073 -0.706476 0.335669 0.623072 -0.706475 0.407454 0.578682 -0.706474 0.407455 0.578684 0 -0.999404 0.0345316 0.0265334 -0.976749 0.212737 0.0347834 -0.980553 0.193145 -2.44723e-05 -0.70363 0.710566 -2.60529e-05 -0.790267 0.612762 0.0119367 -0.824923 0.56512 -0.000130663 -0.869747 0.493498 0.000177804 -0.930081 0.367353 0.0156617 -0.604257 0.796636 -0.0106424 -0.664049 0.747613 0.00969939 -0.45493 0.890475 6.76378e-06 -0.481784 0.87629 -2.75286e-05 -0.228133 0.97363 -0.0116988 -0.255897 0.966633 0.00783143 -0.00724392 0.999943 1.42793e-05 -0.0352058 0.99938 -2.53166e-05 0.207168 0.978305 -0.0108604 0.23418 0.972133 0.0165405 0.560317 0.828113 0 0.582701 0.812686 -0.696406 0.402164 0.594377 -0.6964 0.402169 0.59438 -0.696398 0.0766845 0.713547 -0.33281 0.195358 0.922536 -0.705268 -0.0249588 0.708501 -0.704459 -0.181634 0.686109 -0.524004 -0.316506 0.790724 -0.696403 -0.701211 0.152725 -0.696403 -0.701211 0.152725 -0.703503 -0.586308 0.401655 -0.530087 -0.64731 0.547721 -0.705264 -0.4708 0.530046 -0.704455 -0.341945 0.621945 0 0.976109 0.21728 -0.0342186 0.95075 0.308064 0 0.992301 0.123849 0.700681 0.696429 0.155024 0.700684 0.696427 0.155022 0.994042 0.0978231 0.0480708 0.97185 -0.211448 -0.103907 0.658911 -0.640086 -0.395128 0.108088 -0.791812 -0.601124 0.55829 -0.660795 -0.501659 0.341054 -0.748725 -0.568413 0.237326 -0.768652 -0.594012 0.237622 -0.814033 -0.529987 0.153989 -0.840779 -0.519017 0.237623 -0.838599 -0.490191 0.237429 -0.871828 -0.428419 0.887898 -0.366413 -0.278171 0.739454 -0.536195 -0.407065 0.108165 -0.900143 -0.421952 0.34105 -0.843683 -0.414588 0.658911 -0.675112 -0.331752 0.558596 -0.751977 -0.350001 0.739463 -0.604189 -0.2969 0.971845 -0.187668 -0.142473 0.931703 -0.284281 -0.226084 0.931867 -0.308716 -0.190571 0.658687 -0.594203 -0.461578 0.658909 -0.640087 -0.39513 0.931865 -0.30872 -0.190575 0.931865 -0.325614 -0.160008 0.888089 -0.418759 -0.189575 0.994042 0.0868126 0.0659059 0.994042 0.0868127 0.065906 0.994053 0.0912636 0.0594188 0.994978 0.0851736 0.052578 0.994053 0.0940168 0.0549566 0.994042 0.0978216 0.0480698 0 0.902737 0.430193 -0.126167 0.862391 0.490269 0 0.886615 0.462507 0 0.831408 0.555662 -0.0635028 0.809168 0.584136 0 0.789142 0.614211 0.0983842 -0.979794 0.17414 0.73816 0.157935 0.655879 0.933081 0.11436 0.341001 0.885791 0.284935 0.366313 0.902775 0.216182 0.371837 0.900887 0.194983 0.387793 0.893722 0.248634 0.37342 0.982611 0.0402372 0.181262 0.968946 0.0532706 0.241465 0.959186 0.0569559 0.276979 0.978164 0.0540633 0.200679 0.993506 0.067182 0.0918326 0.993503 0.0619724 0.0954555 0.955084 0.0714802 0.287584 0.937215 0.0945563 0.335689 0.812781 -0.191179 0.550307 0.75974 -0.0783257 0.645492 0.532641 -0.213993 0.818841 0.600307 -0.209571 0.771824 0.364131 -0.310393 0.878103 0.456011 -0.308285 0.834874 0.187422 -0.390689 0.901241 0.145513 0.500314 0.853529 0.172305 0.312917 0.93402 0.884955 0.281493 0.370966 0.712669 0.331454 0.618256 0.697719 0.312641 0.644549 0.461104 0.338658 0.820179 0.42335 0.309728 0.851377 0.179682 0.311223 0.933196 0.275265 -0.0568009 0.959689 0.918218 0.146449 0.368005 0.916084 0.149469 0.372087 0.771367 -0.0212117 0.636037 0.722822 0.116436 0.681154 0.503313 0.0649291 0.861662 0.487237 0.0679036 0.870626 0.353638 -0.0142844 0.935273 0.177311 -0.0428592 0.983221 0.30151 -0.394242 0.868139 0.275292 -0.661443 0.697644 0.144757 -0.775002 0.615157 0.0773267 -0.840376 0.536459 0.876442 -0.451447 -0.16747 0.884045 -0.436298 -0.167656 0.725685 -0.630838 -0.274636 0.739824 -0.614018 -0.275034 0.546199 -0.756686 -0.359295 0.553282 -0.751398 -0.359554 0.333634 -0.840263 -0.427372 0.344997 -0.834824 -0.429005 0.10576 -0.880623 -0.461864 0.121162 -0.876826 -0.465291 0.145473 -0.925466 0.349785 0.171351 -0.924134 0.341489 0.342305 -0.873146 0.347051 0.242336 -0.894069 0.376713 0.521639 -0.765976 0.37573 0.4432 -0.797995 0.408384 0.684257 -0.618043 0.38706 0.629484 -0.653661 0.420092 0.792145 -0.471988 0.386953 0.839073 -0.527456 0.133219 0.858964 -0.49751 0.121103 0.685635 -0.722982 0.0848649 0.721179 -0.689096 0.0710508 0.493421 -0.869168 0.0329051 0.546143 -0.837506 0.0176358 0.282735 -0.959032 -0.0178548 0.35109 -0.935696 -0.0347553 0.0859124 -0.994343 -0.0624515 0.106824 -0.991981 -0.0675503 0.14794 0.659554 0.736955 0.205586 0.622879 0.754822 0.341456 0.601911 0.721881 0.425 0.568398 0.704485 0.484354 0.573517 0.660667 0.687665 0.48577 0.539578 0.647358 0.472277 0.598232 0.870204 0.393143 0.296958 0.850013 0.369151 0.375773 0.0290106 0.268696 0.962788 0.135834 -0.147761 0.979651 -0.181674 -0.113583 0.976777 0.289901 -0.468892 0.834325 0.0131241 -0.452515 0.89166 0.143534 -0.730162 0.668028 0.324422 -0.679142 0.65842 0.20938 -0.688955 0.693903 0.489619 -0.574897 0.655567 0.39807 -0.594317 0.698804 0.641634 -0.443952 0.62547 0.575709 -0.466852 0.671274 0.805189 -0.249388 0.53803 0.849347 -0.309299 0.427721 0.891417 -0.256234 0.373792 0.946586 -0.277921 0.16351 0.938297 -0.29935 0.173172 0.97139 -0.23273 -0.0473068 0.963017 -0.265424 -0.0463615 0.148789 0.940066 0.306819 0.824721 0.363973 -0.43285 0.651402 0.732395 0.198173 0.942263 0.318572 -0.103207 0.971801 0.230307 -0.0506151 0.978817 0.198165 -0.0514671 0.989311 0.14573 0.00523191 0.993672 0.11091 0.017744 0.851109 0.479992 0.212654 0.873462 0.474226 0.110333 0.889402 0.451679 0.0703582 0.901408 0.432277 0.0245058 0.895298 0.444591 0.0279231 0.918226 0.395156 -0.0266758 0.741744 0.57711 -0.341702 0.782194 0.526691 -0.33282 0.708904 0.682915 -0.176302 0.911965 0.409339 -0.0276059 0.938586 0.340255 -0.0573037 0.786958 0.410269 -0.460843 0.849346 0.243749 -0.468185 0.792188 0.134316 -0.595313 0.856725 -0.0995223 -0.50608 0.843571 -0.129563 -0.521154 0.884015 -0.340186 -0.32061 0.877481 -0.355437 -0.322011 0.921865 0.379933 -0.0762694 0.959988 0.276213 -0.046138 0.891438 0.219284 -0.396551 0.944652 0.0329524 -0.326416 0.941308 0.0119155 -0.337337 0.970892 -0.13681 -0.196602 0.965073 -0.167392 -0.20153 0.0662002 0.134718 -0.98867 0.226437 0.277266 -0.933729 0.146321 -0.105024 -0.983646 0.165355 -0.109914 -0.98009 0.0926767 -0.301205 -0.949045 0.146675 -0.493066 -0.857539 0.0760749 -0.524733 -0.847861 0.105979 -0.813168 -0.572299 0.133575 -0.804248 -0.579089 0.333935 -0.761056 -0.55613 0.306088 0.94332 0.12829 0.276858 0.773922 -0.569556 -0.207825 0.816109 -0.539236 0.21619 0.603137 -0.767781 0.0427149 0.528288 -0.84799 0.123731 0.32498 -0.937592 0.088049 0.910865 -0.403202 0.025666 0.983515 -0.178996 0.152044 0.979033 -0.135564 0.145453 0.964826 0.218985 0.341503 0.915047 0.214626 0.692787 0.701572 0.166865 0.714423 0.699698 -0.00474613 0.412937 0.907717 -0.0743841 0.487281 0.808675 -0.329547 0.353595 0.829661 -0.43201 0.447575 0.634361 -0.630287 0.377678 0.620238 -0.687506 0.480037 0.362057 -0.799049 0.412112 0.326299 -0.850701 0.513922 0.0244212 -0.857489 0.454267 -0.0221766 -0.89059 0.542562 -0.339457 -0.768372 0.499064 -0.37847 -0.779548 0.553209 -0.656313 -0.513042 0.546579 -0.662073 -0.512749 0.344654 -0.754799 -0.558114 0.287811 -0.466116 -0.836601 0.346274 -0.429001 -0.834298 0.253015 -0.0962681 -0.962661 0.332868 -0.0468839 -0.941807 0.223309 0.27701 -0.934558 0.31305 0.320666 -0.893965 0.200945 0.603348 -0.771746 0.291665 0.628043 -0.721452 0.187469 0.844821 -0.501132 0.269245 0.847859 -0.456773 0.179653 0.973734 -0.139882 0.463484 0.880713 -0.0976117 0.425007 0.884493 0.192463 0.484328 0.847632 0.216672 0.870893 0.459708 0.17382 0.892964 0.441188 0.0892627 0.690156 0.72356 0.0120582 0.74477 0.641132 -0.185115 0.503266 0.799384 -0.328191 0.593129 0.618824 -0.515029 0.545196 0.612766 -0.572084 0.633555 0.389741 -0.668364 0.588805 0.362325 -0.722515 0.677989 0.0972213 -0.728614 0.63989 0.056793 -0.766365 0.718478 -0.227213 -0.657392 0.691088 -0.263719 -0.672941 0.739772 -0.515527 -0.432399 0.726925 -0.532656 -0.433426 0.939621 0.308931 0.14722 0.939566 0.272689 0.207019 0.938419 0.264737 0.221999 0.939692 0.261126 0.220888 0.939391 0.261077 0.222224 0.939415 0.261073 0.222128 0.939897 0.260209 0.221097 0.939967 0.259928 0.221133 0.939945 0.260005 0.221134 0.939759 0.260457 0.221395 0.939563 0.260869 0.221739 0.939617 0.314997 0.133775 0.939838 0.314441 0.133534 0.940966 0.310663 0.134433 0.939692 0.314479 0.134471 0.939963 0.314172 0.133289 0.939976 0.314154 0.13324 0.939693 0.314284 0.134919 0.93947 0.315382 0.133903 0.93945 0.315452 0.133883 0.939565 0.307274 0.150995 0.94337 0.298498 0.144746 0.936007 0.303874 0.177626 0.939622 0.297499 0.169128 0.939661 0.286698 0.18666 0.937285 0.289798 0.193684 0.94337 0.263171 0.201975 0.939621 0.270058 0.210193 0.939692 0.261474 0.220477 0.149328 0.892615 0.42537 0.488763 0.787562 0.375308 0.346099 0.740372 0.57625 0.655051 0.596264 0.464087 0.850964 0.414477 0.322598 0.850963 0.414477 0.322598 0.850964 0.436676 0.291847 0.850961 0.436679 0.29185 0.850961 0.456602 0.259578 0.850963 0.456599 0.259576 0.850963 0.47414 0.225949 0.850964 0.474139 0.225948 0.655072 0.682077 0.325041 0.573437 0.736309 0.359192 0.573326 0.712272 0.404926 0.573328 0.712271 0.404926 0.573328 0.681195 0.455268 0.573325 0.681196 0.45527 0.573436 0.651084 0.497254 0.48879 0.68845 0.535837 0.346139 0.846932 0.403601 0.202133 0.881594 0.426538 0.202095 0.8514 0.48402 0.202092 0.8514 0.484021 0.202092 0.814253 0.544197 0.202097 0.814253 0.544196 0.202134 0.776398 0.596948 0.149343 0.780292 0.607323 -0.707105 -0.527135 -0.471309 -0.671184 -0.581096 -0.46026 -0.706477 -0.553694 -0.44081 -0.706477 -0.602233 -0.37176 -0.706458 -0.602248 -0.371771 -0.706509 -0.641432 -0.299013 -0.672804 -0.67132 -0.310909 -0.707083 -0.657584 -0.260034 -0.706476 0.553695 0.44081 -0.706483 0.553689 0.440806 -0.706485 0.602225 0.371757 -0.706471 0.602238 0.371764 -0.706471 0.642211 0.297428 -0.706478 0.642204 0.297426 -0.698053 -0.591605 -0.403393 -0.698078 -0.59158 -0.403386 -0.698073 -0.357974 -0.62012 -0.618505 -0.415532 -0.666922 -0.706898 -0.231068 -0.668508 -0.698068 -0.0534683 -0.714032 -0.698068 -0.0534683 -0.714032 -0.698066 0.261633 -0.666522 -0.698076 0.261633 -0.666511 -0.698081 0.52491 -0.486983 -0.698076 0.708021 0.106756 -0.698086 0.70801 0.106758 -0.700619 0.688538 -0.187212 -0.634901 0.73828 -0.227691 -0.706877 0.624164 -0.332783 -0.698048 0.524926 -0.487013 -0.701603 -0.605088 -0.376327 -0.701593 -0.605099 -0.376328 -0.701593 -0.697643 -0.145125 -0.701598 -0.697638 -0.145126 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.826204 -0.563371 0 0.974316 0.225187 0.0323333 0.988306 0.149017 0.00477942 0.999708 0.0236764 -0.0109463 0.973958 -0.226466 0.0069133 0.964944 -0.262367 -0.00188918 0.882413 -0.470472 -0.0233354 0.793795 -0.607738 0.020824 0.732926 -0.67999 0.00129934 0.608413 -0.793619 -0.00323657 0.477383 -0.878689 0.0314913 0.365216 -0.93039 0.00698241 0.282699 -0.959183 -0.000755079 -0.317531 -0.948247 0.00320236 -0.143824 -0.989598 0.0274206 -0.074645 -0.996833 0.00213117 0.0595817 -0.998221 -0.000711987 0.163078 -0.986613 0.00389208 -0.830581 -0.556884 -0.00331332 -0.535146 -0.844753 -2.3523e-05 -0.528814 -0.848738 -1.65613e-06 -0.326683 -0.945134 0 -0.849914 -0.526921 -0.000563236 -0.849165 -0.528128 0.000568098 -0.979041 -0.203661 0 -0.979337 -0.202235 0 0.782345 0.622845 0 0.782345 0.622845 0 0.850928 0.525282 0 0.850928 0.525282 0 0.907409 0.420249 0 0.907409 0.420249 0 -0.907409 -0.420249 0 -0.907409 -0.420249 0 -0.850929 -0.525281 0 -0.850929 -0.525281 0 -0.782345 -0.622845 0 -0.782345 -0.622845 -0.879238 0.455655 0.138994 -0.887083 0.45708 0.0645155 -0.954991 0.28732 -0.0737497 -0.960103 0.267784 -0.0805835 -0.978435 0.199797 -0.0524019 -0.978975 0.197154 -0.0523224 -0.991396 0.130673 0.00763029 -0.990797 0.135252 0.00525856 -0.965171 -0.17444 -0.194974 -0.793206 0.112225 -0.598523 -0.859466 -0.133232 -0.493525 -0.839106 -0.134906 -0.526973 -0.884193 -0.356456 -0.301899 -0.876482 -0.363031 -0.316209 -0.859293 0.38403 -0.337841 -0.938544 0.336655 -0.0761492 -0.933193 0.354071 -0.0615122 -0.821646 0.312768 -0.476522 -0.847485 0.235482 -0.475729 -0.891286 0.206714 -0.403583 -0.947045 0.00928223 -0.320968 -0.938318 0.0092302 -0.34565 -0.970911 -0.142112 -0.192707 -0.989048 -0.0677069 -0.131146 -0.80733 0.568426 -0.158461 -0.693231 0.563233 -0.449666 -0.770711 0.356159 -0.528352 -0.902133 0.431333 -0.010395 -0.887846 0.4548 0.0699071 -0.749542 0.661874 0.0104554 -0.71014 0.703625 0.0247667 -0.276014 0.814042 -0.51103 -0.145863 0.988895 0.0284625 -0.197803 0.962422 0.186058 -0.14795 0.963115 0.224768 -0.111698 -0.526682 -0.842692 -0.0948876 -0.825661 -0.55613 -0.105795 -0.826871 -0.552351 -0.0780642 0.0669246 -0.9947 -0.143548 -0.129829 -0.98109 -0.177911 -0.141419 -0.973832 -0.0972898 -0.309054 -0.946055 -0.110851 -0.526508 -0.842913 -0.0290443 0.973832 -0.225405 -0.134911 0.792428 -0.594859 0.129851 0.816828 -0.562078 -0.15604 0.612695 -0.774762 -0.216084 0.575743 -0.788561 -0.0506013 0.480835 -0.87535 -0.143388 0.237744 -0.960686 -0.273786 0.298241 -0.914382 -0.14248 0.174911 -0.974221 -0.354206 0.813888 -0.46057 -0.457102 0.583113 -0.671593 -0.363178 0.624963 -0.691031 -0.490843 0.297408 -0.818914 -0.397289 0.33185 -0.855592 -0.522594 -0.039521 -0.851665 -0.442825 -0.0214119 -0.896352 -0.546599 -0.387076 -0.742564 -0.493391 -0.386302 -0.779317 -0.553361 -0.675459 -0.487387 -0.546248 -0.677579 -0.492443 -0.176405 0.84432 -0.505969 -0.30266 0.570893 -0.763203 -0.186336 0.606992 -0.772554 -0.325672 0.249695 -0.911916 -0.20848 0.282501 -0.936338 -0.343263 -0.116231 -0.93202 -0.241864 -0.0949272 -0.965656 -0.351514 -0.480173 -0.803661 -0.28264 -0.473724 -0.834087 -0.345013 -0.776705 -0.526968 -0.333653 -0.777607 -0.532919 -0.879551 0.454777 0.139888 -0.76349 0.624141 0.165925 -0.693963 0.706839 0.137089 -0.651404 0.738872 0.172456 -0.484419 0.854432 0.187839 -0.918285 0.393212 -0.0462277 -0.901025 0.432079 -0.0382405 -0.758736 0.603758 -0.244534 -0.805297 0.553557 -0.2123 -0.700524 0.63803 -0.319661 -0.633817 0.771669 -0.0529495 -0.461123 0.882442 -0.0930665 -0.425668 0.890813 0.158928 -0.341496 0.921955 0.182701 -0.172204 0.970201 -0.170457 -0.179208 0.968698 -0.171782 -0.424083 0.895195 -0.137035 -0.486855 0.798581 -0.353893 -0.502683 0.789032 -0.353182 -0.601404 0.575228 -0.554461 -0.531872 0.618867 -0.578028 -0.642834 0.333956 -0.689375 -0.57509 0.368416 -0.730439 -0.685235 0.0414665 -0.727141 -0.629209 0.0576984 -0.775092 -0.721671 -0.269032 -0.637819 -0.685624 -0.270848 -0.675693 -0.739942 -0.535747 -0.406769 -0.725678 -0.542908 -0.422662 -0.146143 0.578936 0.80217 -0.106519 -0.846062 -0.522335 -0.82627 -0.24379 0.507783 -0.651418 0.485329 0.58319 -0.992269 0.0407695 0.117222 -0.992328 0.0787858 0.0952819 -0.976263 0.0318364 0.214237 -0.978909 0.0426587 0.199795 -0.963219 0.0471899 0.26454 -0.851016 0.40058 0.339569 -0.880892 0.283307 0.379165 -0.902137 0.200746 0.381904 -0.895768 0.210892 0.391311 -0.91931 0.138814 0.368239 -0.740529 -0.0662457 0.668752 -0.783614 -0.0858383 0.61529 -0.707959 0.128218 0.694518 -0.918517 0.139686 0.369885 -0.938742 0.0836189 0.334322 -0.785901 -0.245252 0.567637 -0.847487 -0.319723 0.423726 -0.793258 -0.484738 0.36847 -0.856961 -0.500981 0.120978 -0.844209 -0.526958 0.0981214 -0.884165 -0.433035 -0.175309 -0.877678 -0.440236 -0.189402 -0.945948 0.0789726 0.314557 -0.960044 0.0465112 0.275956 -0.891348 -0.268066 0.365568 -0.944831 -0.282153 0.166385 -0.94185 -0.300679 0.150038 -0.970926 -0.235915 -0.0405786 -0.965173 -0.252479 -0.0685244 -0.244566 -0.751482 0.612749 -0.169577 -0.747213 0.642585 -0.0807701 -0.863147 0.498452 -0.126153 -0.91848 0.374806 -0.22559 -0.922941 0.311912 -0.0935001 -0.974831 0.202392 -0.334012 -0.822507 -0.460345 -0.185734 -0.855243 -0.4838 0.00744828 -0.994682 -0.102724 -0.309741 -0.93419 -0.177057 -0.104014 -0.99371 0.0415025 -0.333469 -0.187049 0.924019 0.0467059 -0.129119 0.990529 -0.150595 -0.436163 0.887177 -0.201227 -0.450362 0.869874 -0.0642574 -0.596816 0.799801 -0.110751 -0.691508 0.713829 -0.076841 -0.00102072 0.997043 -0.075394 0.237006 0.968578 -0.190435 0.277665 0.941614 -0.0911609 0.604683 0.791232 -0.341518 0.576546 0.742267 -0.693992 0.43933 0.570407 -0.71475 0.285858 0.638293 -0.412192 0.313727 0.855379 -0.486904 0.0414232 0.872473 -0.35419 -0.0470679 0.933988 -0.447658 -0.306904 0.839888 -0.378516 -0.36671 0.849853 -0.480135 -0.574266 0.66309 -0.41312 -0.637535 0.650293 -0.51408 -0.768697 0.380561 -0.455181 -0.818806 0.349811 -0.542689 -0.839843 0.0123703 -0.499647 -0.865993 -0.0202147 -0.553288 -0.740024 -0.382409 -0.546673 -0.742004 -0.388046 -0.344679 -0.821928 -0.453465 -0.288261 -0.954534 -0.0759627 -0.346229 -0.937233 -0.0414803 -0.253708 -0.915322 0.312759 -0.332831 -0.875266 0.350903 -0.224023 -0.734367 0.640718 -0.313031 -0.678048 0.665028 -0.201532 -0.4503 0.869836 -0.291641 -0.392738 0.872183 -0.187832 -0.103578 0.976725 -0.269304 -0.0603735 0.961161 -0.179217 0.280678 0.942922 -0.463849 0.276563 0.841639 -0.425697 0.541327 0.725085 -0.484444 0.550876 0.679595 -0.875381 0.339988 0.343679 -0.8896 0.265534 0.371624 -0.689725 0.31515 0.651889 -0.745697 0.0963595 0.65928 -0.502659 0.0378026 0.863658 -0.593275 -0.208306 0.777582 -0.546282 -0.264841 0.794629 -0.633762 -0.4436 0.633691 -0.589987 -0.505893 0.629276 -0.678229 -0.620978 0.392928 -0.640947 -0.672765 0.369561 -0.718705 -0.691974 0.068078 -0.691728 -0.721076 0.0395299 -0.739905 -0.607991 -0.287901 -0.727054 -0.615667 -0.303887 -0.572885 0.697451 0.43054 -0.850725 0.41053 0.328227 -0.879514 0.432226 0.199087 -0.654675 0.685919 0.31767 -0.765001 0.584397 0.270652 -0.845146 0.483596 0.227737 -0.851113 0.462896 0.247657 -0.850696 0.447298 0.276119 -0.850697 0.447295 0.276118 -0.851115 0.428853 0.302802 -0.345806 0.851428 0.394322 -0.488393 0.791827 0.366719 -0.149218 0.89725 0.415545 -0.20191 0.887246 0.41476 -0.20187 0.833409 0.514468 -0.844349 0.419176 0.333717 -0.654686 0.591375 0.470809 -0.573006 0.643979 0.506907 -0.488412 0.682685 0.543503 -0.345826 0.734073 0.584415 -0.573006 0.741756 0.348515 -0.572885 0.697451 0.43054 -0.201868 0.83341 0.514468 -0.201909 0.768403 0.60728 -0.149204 0.773588 0.615873 -0.340894 -0.735484 -0.585537 -0.994035 0.0928046 0.0572887 -0.994036 0.085173 0.0680975 -0.99425 0.0837729 0.0666937 -0.991754 0.116402 0.0536158 -0.996675 0.0718435 0.0384393 -0.658681 -0.640258 -0.395234 -0.931791 -0.308884 -0.190675 -0.994045 0.0980508 0.0475352 -0.993745 -0.101332 -0.0469298 -0.971837 -0.213834 -0.0990329 -0.994056 0.0889352 0.0627957 -0.994035 0.0928038 0.0572884 -0.931792 -0.308881 -0.190674 -0.93164 -0.332426 -0.146766 -0.558462 -0.640185 -0.527526 -0.739293 -0.526818 -0.419414 -0.931791 -0.283989 -0.226091 -0.888074 -0.352309 -0.295301 -0.971842 -0.184345 -0.146762 -0.237283 -0.826627 -0.51028 -0.237283 -0.760002 -0.605057 -0.108121 -0.768588 -0.630541 -0.887835 -0.417556 -0.193383 -0.739293 -0.611035 -0.282989 -0.658469 -0.685694 -0.31023 -0.558122 -0.75293 -0.348705 -0.34087 -0.853064 -0.395081 -0.65868 -0.588655 -0.468643 -0.65868 -0.640258 -0.395234 -0.237287 -0.826625 -0.51028 -0.237191 -0.884289 -0.402211 -0.108068 -0.902094 -0.417788 -0.939506 0.311114 0.143302 -0.93961 0.319199 0.123475 -0.939485 0.319567 0.123472 -0.939571 0.319253 0.123626 -0.939689 0.318583 0.124458 -0.939847 0.318598 0.123216 -0.939869 0.31856 0.123148 -0.939727 0.318899 0.123357 -0.939514 0.267518 0.213886 -0.940498 0.252619 0.22726 -0.939696 0.253563 0.229515 -0.939887 0.252784 0.229591 -0.93969 0.253902 0.229163 -0.939536 0.25358 0.23015 -0.939495 0.253582 0.230317 -0.939514 0.253572 0.230248 -0.939749 0.25317 0.229732 -0.939508 0.267531 0.213896 -0.939511 0.267524 0.213892 -0.939694 0.279391 0.197273 -0.939693 0.279393 0.197272 -0.939498 0.29149 0.179938 -0.939498 0.291489 0.179938 -0.939694 0.301565 0.16135 -0.939693 0.301569 0.161345 -0.939511 0.311103 0.143295 -0.939516 0.311091 0.143291 -0.939698 0.318643 0.124235 0.697588 0.702108 -0.142878 0.697571 0.702126 -0.142876 0.697574 0.56553 -0.439963 0.638187 0.618368 -0.458627 0.707015 0.45691 -0.53978 0.697593 0.311151 -0.645406 0.697584 0.311157 -0.645413 0.697587 -0.00801094 -0.716455 0.697587 -0.00801082 -0.716456 0.70701 -0.184812 -0.682628 0.685364 -0.250438 -0.683782 0.825857 -0.309626 -0.471266 0.701048 -0.591457 -0.398386 0.600133 -0.642166 -0.47693 0.706708 -0.481158 -0.518701 0.699404 -0.339271 -0.62907 0.698063 -0.637388 -0.326259 0.698061 -0.63739 -0.326261 0.704259 -0.704633 -0.0866699 0.771594 -0.635047 -0.0368476 0.684034 -0.725658 0.0742901 0.706903 -0.697532 0.117208 0.698071 -0.652478 0.294908 0.698061 -0.652487 0.294909 0.698065 -0.459911 0.548806 0.698065 -0.45991 0.548806 0.698066 -0.176245 0.694004 0.698069 0.432705 0.570496 0.698068 0.432706 0.570497 0.700601 0.165287 0.694146 0.627461 0.154771 0.763111 0.706899 0.00661841 0.707284 0.698065 -0.176246 0.694004 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.70618 -0.627752 -0.327471 0.706179 -0.627753 -0.327471 0.706179 -0.574077 -0.414425 0.706174 -0.574081 -0.414428 0 -0.796479 -0.604667 0.0420197 -0.810088 -0.584801 0 -0.838036 -0.545615 0 -0.886615 -0.462508 0.0629299 -0.895713 -0.440157 0 -0.863327 -0.504646 0.70618 0.627753 0.32747 0.706178 0.627754 0.327471 0.706179 0.574077 0.414425 0.706177 0.574078 0.414426 0 -0.890161 -0.455646 0 0.664913 0.746921 -0.0219197 0.604166 0.796557 -0.00325965 0.500268 0.865865 0.00738634 0.267357 0.963569 -0.00467365 0.231636 0.972791 0.00127751 0.00935709 0.999955 0.0165191 -0.161713 0.9867 -0.0121505 -0.246123 0.969162 0.00722545 -0.521044 0.853499 -0.0216183 -0.642151 0.766273 -0.00297586 -0.713456 0.700693 2.26203e-06 -0.986167 0.165753 2.90433e-05 -0.94089 0.338713 -0.0189449 -0.911083 0.411788 -0.00146866 -0.847883 0.530182 0.000305833 -0.79411 0.607774 -0.00626211 -0.881767 -0.471644 0.00534624 -0.997143 -0.0753516 1.82619e-05 -0.998321 -0.0579259 -1.09677e-07 -0.986175 0.16571 0 -0.819313 -0.573347 0.00561297 -0.829386 -0.558647 -0.000790931 -0.680076 -0.733141 0.00753351 -0.530379 -0.847727 -0.0100097 -0.474662 -0.880111 0.000486546 -0.31074 -0.950495 -0.00020682 -0.261328 -0.96525 0.00316947 -0.121603 -0.992574 -0.0212949 -0.0111779 -0.999711 0.000797212 0.127266 -0.991868 -0.000777113 0.312846 -0.949804 -0.0220045 0.434167 -0.900564 0.0020006 0.52454 -0.851383 -0.000198905 0.646085 -0.763265 0.00579884 0.803185 -0.595701 -0.00514757 0.786221 -0.617924 0 0.979917 -0.199404 -0.00804481 0.983394 -0.181306 0.000452667 0.911163 -0.412045 0 -0.895123 0.445819 0.0376704 -0.837532 0.545088 0.0154242 -0.787434 0.616206 -0.0283307 -0.546712 0.836841 -9.11536e-06 0.424657 0.905354 0.0268103 0.499121 0.866117 -7.05443e-05 0.390735 0.920503 0.000101187 0.190573 0.981673 1.08283e-05 0.190286 0.981729 5.01976e-06 -0.0699999 0.997547 0.0341679 0.0316723 0.998914 -0.0536325 -0.311178 0.948837 -0.00712374 -0.22393 0.974579 0.00709798 -0.607647 0.794176 0 0.998577 -0.0533276 0.032916 0.994686 -0.0975476 -0.025121 0.934974 0.353826 0.00777265 0.954482 0.298169 -3.60906e-07 0.877222 0.480085 1.25922e-05 0.811801 0.583935 0.0188771 0.847144 0.531028 -0.0358091 0.644087 0.764114 0.0352488 0.737378 0.67456 -2.16092e-05 0.588408 0.808564 0 0.930572 -0.366109 0 0.930572 -0.366109 0 0.880372 -0.474284 0 0.880372 -0.474284 0 0.817651 -0.575714 0 0.817651 -0.575714 0 -0.817651 0.575714 0 -0.817651 0.575714 0 -0.880372 0.474284 0 -0.880372 0.474284 0 -0.930572 0.366109 0 -0.930572 0.366109 -0.879239 0.348198 -0.325111 -0.887084 0.284401 -0.36359 -0.954989 0.0797929 -0.285709 -0.960101 0.0641054 -0.272206 -0.978436 0.0545168 -0.199228 -0.978976 0.0532638 -0.196899 -0.991396 0.0719441 -0.109349 -0.990797 0.0721794 -0.114504 -0.965172 -0.256072 0.0535838 -0.793206 -0.462225 -0.396449 -0.859466 -0.494022 -0.131382 -0.839106 -0.523825 -0.146657 -0.884191 -0.439684 0.157749 -0.876486 -0.455353 0.156289 -0.859293 -0.100575 -0.501498 -0.938546 0.102376 -0.329622 -0.933195 0.123763 -0.337388 -0.821648 -0.256296 -0.509123 -0.847485 -0.29425 -0.441798 -0.89128 -0.246161 -0.38082 -0.947043 -0.27333 -0.168523 -0.938317 -0.29473 -0.180817 -0.970911 -0.237946 0.0267232 -0.989049 -0.147428 -0.00693602 -0.807336 0.146986 -0.571493 -0.69324 -0.107795 -0.712599 -0.770718 -0.279485 -0.572609 -0.902136 0.206672 -0.378732 -0.88785 0.287941 -0.358905 -0.749529 0.339998 -0.567986 -0.710137 0.373257 -0.596979 -0.0480076 -0.223258 -0.973576 -0.18325 -0.431883 -0.883118 -0.089506 -0.417327 -0.904338 -0.276016 -0.0355482 -0.960495 -0.162561 0.411463 -0.896812 -0.244201 0.0127618 -0.969641 -0.0759047 -0.0580551 -0.995424 -0.0762241 0.239873 -0.967807 -0.12919 0.608426 -0.783025 -0.195892 0.64254 -0.74079 -0.149375 0.750087 -0.644249 -0.105762 -0.891789 0.439917 -0.0427663 -0.933505 -0.356006 -0.117365 -0.989352 -0.0860722 -0.222624 -0.974571 0.0255112 -0.0405076 -0.988994 0.142301 -0.20109 -0.863139 0.463199 -0.0855184 -0.594826 -0.799293 -0.110712 -0.647871 -0.753661 -0.210345 -0.698516 -0.683981 -0.0061709 -0.806818 -0.590768 -0.241482 -0.922704 -0.300507 -0.354223 0.0080784 -0.935126 -0.457112 -0.290052 -0.840784 -0.363201 -0.285961 -0.886742 -0.490857 -0.560489 -0.667017 -0.397291 -0.575033 -0.71519 -0.522596 -0.757324 -0.391605 -0.442823 -0.786971 -0.429634 -0.546594 -0.836621 -0.0360593 -0.493391 -0.86806 -0.0551043 -0.553359 -0.75982 0.341274 -0.546234 -0.765266 0.340581 -0.176403 -0.0160254 -0.984187 -0.302658 -0.375507 -0.876009 -0.186318 -0.365554 -0.911952 -0.325664 -0.664895 -0.672204 -0.208479 -0.669642 -0.712823 -0.343266 -0.865268 -0.365349 -0.241866 -0.883746 -0.400617 -0.351516 -0.936077 0.0140107 -0.282654 -0.959198 -0.00678276 -0.345029 -0.844716 0.409158 -0.333676 -0.850317 0.406965 -0.879552 0.348534 -0.323903 -0.76348 0.455772 -0.457569 -0.693959 0.472147 -0.543597 -0.65141 0.518782 -0.553652 -0.484425 0.589885 -0.646041 -0.918282 0.156579 -0.363649 -0.901027 0.182922 -0.393307 -0.758731 0.0901011 -0.645142 -0.805288 0.0929158 -0.585558 -0.700528 0.0421817 -0.712377 -0.633823 0.339978 -0.694754 -0.461116 0.360624 -0.810754 -0.425662 0.583036 -0.692012 -0.341501 0.61919 -0.707093 -0.233092 0.320287 -0.918196 -0.179203 0.335591 -0.924805 -0.424086 0.32893 -0.843775 -0.486861 0.0928025 -0.868536 -0.502662 0.0886511 -0.859926 -0.601391 -0.19257 -0.775401 -0.531846 -0.19116 -0.824983 -0.642818 -0.430046 -0.633913 -0.575097 -0.448371 -0.684271 -0.685237 -0.608987 -0.399481 -0.62922 -0.642393 -0.437509 -0.721682 -0.686872 -0.0859173 -0.685622 -0.720593 -0.103288 -0.739941 -0.620147 0.260585 -0.725673 -0.637496 0.258839 -0.146169 0.984163 -0.100286 -0.826272 0.317857 0.465018 -0.651393 0.747743 -0.128716 -0.992269 0.121902 0.0233056 -0.992328 0.12191 -0.02059 -0.976264 0.201449 0.0795426 -0.978909 0.194356 0.0629556 -0.963212 0.252716 0.0914166 -0.85102 0.494363 -0.177115 -0.880899 0.470008 -0.0557613 -0.902139 0.431106 0.0170985 -0.895768 0.444332 0.0130133 -0.919312 0.388306 0.0639048 -0.740535 0.546026 0.391744 -0.78361 0.489943 0.381983 -0.707955 0.665582 0.236223 -0.918518 0.39017 0.0639723 -0.938741 0.331346 0.0947414 -0.785897 0.368967 0.496214 -0.847487 0.207092 0.488752 -0.79326 0.0767377 0.604028 -0.856962 -0.145722 0.494349 -0.844209 -0.178507 0.505418 -0.884164 -0.368337 0.28737 -0.877671 -0.384157 0.286559 -0.945947 0.311903 0.0888821 -0.960045 0.262238 0.0976958 -0.891348 0.182555 0.414937 -0.944831 0.00301559 0.327544 -0.94185 -0.0204025 0.335413 -0.970926 -0.153098 0.18402 -0.965174 -0.185579 0.184392 -0.115172 -0.779542 0.61567 -0.077111 -0.602079 0.794705 -0.146458 -0.570467 0.808157 -0.0440677 -0.22066 0.974355 -0.0575924 -0.21461 0.975 -0.0997376 0.0442338 0.99403 -0.181849 0.184022 0.965954 -0.334017 -0.809923 0.482138 -0.105766 -0.857913 0.502791 -0.27889 -0.857786 0.431767 -0.0122504 0.797668 0.602972 -0.315861 0.719815 0.618141 -0.112719 0.847095 0.51935 -0.136052 0.201581 0.969977 -0.0636913 0.39568 0.916177 -0.202714 0.528141 0.824605 -0.248208 0.50635 0.825834 -0.108765 0.593104 0.797745 -0.0841857 0.876973 0.473108 -0.0328882 0.954678 0.295818 -0.19044 0.954292 0.230347 -0.091162 0.987567 -0.128066 -0.341476 0.931109 -0.128181 -0.693996 0.713651 -0.0952491 -0.71475 0.695708 0.0715815 -0.412188 0.897646 0.155989 -0.486901 0.7763 0.400357 -0.35417 0.785328 0.507763 -0.447638 0.573914 0.685743 -0.378505 0.552642 0.74251 -0.480131 0.287121 0.828876 -0.413115 0.244402 0.877271 -0.514077 -0.0547788 0.855993 -0.455185 -0.106457 0.88401 -0.542694 -0.4092 0.733511 -0.499644 -0.450503 0.739867 -0.553291 -0.70119 0.449668 -0.546679 -0.707058 0.448566 -0.344675 -0.803681 0.485074 -0.288259 -0.543054 0.788669 -0.346235 -0.504535 0.790927 -0.253711 -0.186808 0.94907 -0.332841 -0.13374 0.933451 -0.224028 0.187699 0.956337 -0.313026 0.236907 0.919723 -0.201524 0.528148 0.824893 -0.291647 0.558965 0.776208 -0.187834 0.794079 0.578063 -0.269304 0.802203 0.532866 -0.179218 0.956932 0.228391 -0.463858 0.867157 0.181311 -0.425707 0.8986 -0.106258 -0.484461 0.863975 -0.137277 -0.875375 0.467638 -0.12261 -0.889595 0.45461 -0.0441542 -0.689718 0.722136 0.0530061 -0.745695 0.619134 0.246194 -0.50268 0.766842 0.399083 -0.593288 0.569254 0.569175 -0.546284 0.555747 0.626673 -0.633763 0.326991 0.701014 -0.589992 0.292024 0.752749 -0.678233 0.029801 0.734242 -0.640943 -0.016339 0.767415 -0.718698 -0.28704 0.633309 -0.691734 -0.326295 0.644233 -0.73991 -0.553322 0.382581 -0.727055 -0.571009 0.381235 -0.572885 0.721584 -0.38874 -0.850729 0.489512 -0.191414 -0.879515 0.388526 -0.274775 -0.654682 0.618066 -0.435186 -0.764993 0.526599 -0.370783 -0.845144 0.439025 -0.304939 -0.851115 0.445931 -0.277036 -0.850698 0.462772 -0.24931 -0.8507 0.462769 -0.249308 -0.851118 0.476654 -0.22 -0.345815 0.767204 -0.540195 -0.488395 0.7135 -0.502382 -0.149213 0.808497 -0.569269 -0.201915 0.802815 -0.560997 -0.201875 0.862246 -0.464519 -0.844351 0.498592 -0.196158 -0.654662 0.70344 -0.27675 -0.573006 0.760984 -0.304248 -0.488429 0.812021 -0.319467 -0.345785 0.873169 -0.343524 -0.573004 0.672702 -0.468123 -0.572883 0.721585 -0.388741 -0.20187 0.862247 -0.46452 -0.20191 0.910122 -0.361815 -0.149232 0.920152 -0.362009 -0.3409 -0.874831 0.344178 -0.994035 0.0960149 -0.0517263 -0.994036 0.10156 -0.0397131 -0.994251 0.0996444 -0.0392024 -0.991754 0.104634 -0.074 -0.996675 0.0692071 -0.0429951 -0.658681 -0.662412 0.356862 -0.931791 -0.31957 0.172162 -0.994046 0.0901913 -0.0611462 -0.993745 -0.0913088 0.0642912 -0.971837 -0.192682 0.135669 -0.994056 0.0988498 -0.0456225 -0.994035 0.0960147 -0.0517262 -0.93179 -0.319572 0.172164 -0.931639 -0.293318 0.214508 -0.558466 -0.77694 0.290655 -0.739294 -0.62663 0.246532 -0.931791 -0.337792 0.132896 -0.888067 -0.431905 0.157461 -0.971843 -0.219268 0.0862652 -0.237293 -0.855227 0.460738 -0.237293 -0.903993 0.355652 -0.108119 -0.930359 0.350346 -0.887838 -0.376246 0.264918 -0.739291 -0.550595 0.387679 -0.658469 -0.611514 0.438714 -0.558108 -0.678461 0.477709 -0.340893 -0.768676 0.54123 -0.658672 -0.700191 0.275471 -0.658672 -0.662418 0.356866 -0.237287 -0.855228 0.460739 -0.23719 -0.790469 0.564712 -0.108034 -0.812866 0.572344 -0.939507 0.279659 -0.197781 -0.93961 0.266528 -0.214698 -0.939482 0.266715 -0.215027 -0.939572 0.26669 -0.214666 -0.93969 0.267078 -0.213666 -0.939848 0.266001 -0.21431 -0.939868 0.26593 -0.214311 -0.939726 0.266281 -0.214501 -0.939514 0.31899 -0.124735 -0.94051 0.323088 -0.105147 -0.939696 0.325549 -0.104833 -0.939886 0.325226 -0.104124 -0.939689 0.325417 -0.105298 -0.939538 0.326097 -0.104542 -0.939485 0.326285 -0.104436 -0.939514 0.326189 -0.104474 -0.93975 0.325537 -0.104384 -0.939507 0.319008 -0.124742 -0.939511 0.318999 -0.124737 -0.939693 0.31054 -0.143324 -0.939693 0.310538 -0.143329 -0.939497 0.301577 -0.162469 -0.939498 0.301576 -0.162468 -0.939694 0.290519 -0.180486 -0.939694 0.290519 -0.180485 -0.939511 0.279649 -0.197776 -0.939516 0.27964 -0.197768 -0.939698 0.266912 -0.213837 0 -0.989515 0.144428 0.000492126 -0.989332 0.145676 -0.000541632 -0.87878 0.477228 0 -0.879431 0.476026 -0.7016 -0.70497 0.103804 -0.701596 -0.704974 0.103807 -0.701597 -0.626195 0.34006 -0.701597 -0.626196 0.34006 0.000338617 0.191933 0.981408 -0.00613622 0.288259 0.957533 -0.0220229 0.380399 0.92456 0.00551356 0.486951 0.873412 -8.52395e-06 0.600068 0.799949 -6.99747e-06 0.637931 0.770094 -0.00814597 0.766719 0.641931 0.0204025 0.820003 0.571995 -0.019235 0.966299 0.256702 0 0.980319 0.197423 -0.000849554 0.0585214 0.998286 -0.0212862 -0.070005 0.99732 0.00326992 -0.180095 0.983644 -0.000184378 -0.317693 0.948194 0.000479421 -0.366261 0.930512 -0.0100181 -0.525645 0.850645 0.00632878 -0.575783 0.817578 -0.00763764 -0.836488 0.547933 0 -0.849273 0.527954 0.697577 -0.599373 0.392603 0.697605 -0.599346 0.392595 0.704535 -0.423909 0.56915 0.786901 -0.324381 0.524942 0.685364 -0.290246 0.667857 0.707008 -0.224674 0.670567 0.697589 -0.0501698 0.71474 0.697588 -0.0501698 0.71474 0.697588 0.272623 0.662606 0.697587 0.692481 0.183961 0.697577 0.69249 0.183966 0.699408 0.54801 0.458818 0.64682 0.57333 0.502908 0.707001 0.424376 0.565734 0.697582 0.272624 0.662612 0.694734 0.446878 -0.563599 0.458498 -0.326995 -0.82635 0.694742 0.446872 -0.563595 0.702914 0.179594 -0.688228 0.466754 0.129361 -0.874875 0.705018 -0.0046418 -0.709174 0.703699 -0.178108 -0.687812 0.694733 -0.668808 0.264654 0.694736 -0.668805 0.264654 0.702912 -0.710754 -0.0272657 0.782476 -0.622469 0.0162421 0.561454 -0.790514 -0.244655 0.701774 -0.6927 -0.166373 0.703699 -0.606839 -0.369532 0.458489 -0.696364 -0.552146 0.704399 -0.490036 -0.513505 0.704398 -0.349717 -0.617674 0.70067 0.704357 -0.113765 0.700681 0.704345 -0.113768 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.70617 -0.597482 0.37992 0.706185 -0.59747 0.379911 0.706186 -0.645934 0.289949 0.706167 -0.645951 0.289958 0 -0.921896 0.387437 0.0420193 -0.911497 0.409156 0 -0.891535 0.452952 0 -0.843851 0.536578 0.0629301 -0.829043 0.555632 0 -0.868699 0.49534 0.70617 0.597482 -0.379919 0.706174 0.597479 -0.379917 0.706174 0.645945 -0.289954 0.706167 0.645952 -0.289957 0 0.967666 -0.252234 -0.0173643 0.987057 -0.159426 0 0.997948 -0.0640294 0 -0.881026 0.473068 -0.0262991 -0.929524 0.367822 -0.0108355 -0.957957 0.286706 0.0197313 -0.999071 -0.038326 -0.00459575 -0.492689 -0.870193 6.63683e-05 -0.516481 -0.856299 -8.74461e-05 -0.690382 -0.723445 0.00524369 -0.708376 -0.705816 -0.00480604 -0.854093 -0.520097 -0.012997 -0.830598 -0.556721 0.0208384 -0.955088 -0.295589 0.00416492 -0.937065 -0.34913 -0.00493722 -0.999337 0.036065 0 0.621295 -0.783577 -0.0272105 0.662843 -0.748264 0.0218243 0.252435 -0.967368 -0.00552027 0.318767 -0.947817 4.40925e-06 0.11587 -0.993264 -7.14499e-06 -0.00654523 -0.999979 -0.0147138 0.0666288 -0.997669 0.0291932 -0.250573 -0.967657 -0.0251801 -0.113791 -0.993186 0.00322785 -0.344198 -0.938892 0.994042 0.0905411 -0.0606814 0.97185 -0.195711 0.131167 0.65891 -0.662234 0.356768 0.108089 -0.916495 0.385167 0.558299 -0.764842 0.321434 0.341069 -0.866617 0.364206 0.237334 -0.898754 0.368665 0.237629 -0.865998 0.439978 0.153988 -0.869871 0.468628 0.237619 -0.843818 0.481153 0.237424 -0.806937 0.540817 0.887894 -0.424116 0.17824 0.739448 -0.620633 0.260829 0.108173 -0.815492 0.568569 0.34105 -0.780886 0.523356 0.65891 -0.624863 0.418789 0.5586 -0.679097 0.476228 0.739459 -0.559222 0.374795 0.971844 -0.217222 0.0912897 0.931702 -0.337938 0.133153 0.931866 -0.319401 0.172071 0.658687 -0.69684 0.283807 0.658909 -0.662235 0.356768 0.931867 -0.319398 0.17207 0.931867 -0.301374 0.201983 0.888089 -0.373556 0.267869 0.994043 0.100481 -0.0422284 0.994042 0.100483 -0.042229 0.994053 0.0970901 -0.0493273 0.994978 0.0881214 -0.0474738 0.994053 0.0946031 -0.053943 0.994042 0.0905414 -0.0606816 0 0.823928 -0.566695 -0.126164 0.855781 -0.501718 0 0.843851 -0.536577 0 0.896922 -0.44219 -0.063503 0.910461 -0.408691 0 0.926493 -0.376312 0.891418 0.195596 0.4088 0.89372 0.447711 -0.0286282 0.900888 0.43333 0.0250353 0.982611 0.177095 0.055786 0.968941 0.235768 0.074607 0.959187 0.268347 0.0891639 0.955086 0.284788 0.0818901 0.937216 0.33799 0.0859585 0.963016 -0.172861 0.206687 0.971391 -0.15733 0.177895 0.876438 -0.370761 0.307234 0.884044 -0.363346 0.294016 0.858962 -0.143874 0.491411 0.839074 -0.148353 0.523398 0.946585 0.0026423 0.322443 0.938297 0.000295752 0.345831 0.978163 0.200829 0.0535209 0.993506 0.113119 -0.0122671 0.993503 0.113652 -0.0059397 0.712667 0.701155 0.0220772 0.884956 0.462011 -0.0583003 0.885795 0.459696 -0.063622 0.792145 0.0991159 0.602231 0.849346 0.215768 0.481721 0.805188 0.341253 0.484993 0.812779 0.380985 0.440727 0.759736 0.51985 0.390584 0.771367 0.540227 0.336374 0.722829 0.648108 0.239737 0.103167 0.643692 0.758299 0.199234 0.55717 0.806143 -0.0424616 0.815803 0.576769 -0.0162641 0.814286 0.580236 0.275291 0.802705 0.529036 0.149125 0.986448 -0.068424 0.151999 0.970793 0.185626 0.933079 0.352501 0.0714558 0.918223 0.391915 0.057173 0.91608 0.396981 0.0565969 0.902775 0.430112 -0.00128883 0.738162 0.646969 0.191176 0.697717 0.714518 0.0515156 0.461102 0.879627 0.116797 0.105762 -0.840298 0.531708 0.121171 -0.841368 0.526704 0.0859258 -0.551252 0.829902 0.15189 -0.560592 0.814043 0.0926996 -0.356652 0.929627 0.164548 -0.167412 0.972058 0.14651 -0.163005 0.975687 0.0375628 0.490021 0.870901 0.112556 0.300428 0.94714 0.225703 0.222142 0.948531 0.211643 0.212894 0.953878 0.0696104 0.0667394 0.995339 0.353661 0.802826 0.479994 0.456023 0.568879 0.684412 0.364141 0.605265 0.707853 0.489621 0.280287 0.825657 0.398076 0.308021 0.864094 0.521635 -0.057594 0.851222 0.443198 -0.0453249 0.895277 0.546138 -0.403483 0.734122 0.493424 -0.406089 0.769171 0.553281 -0.687084 0.470951 0.54621 -0.6895 0.475652 0.177283 0.830071 0.528728 0.301496 0.55471 0.775498 0.187401 0.585154 0.788971 0.324414 0.230642 0.917366 0.209391 0.25646 0.943601 0.342316 -0.13602 0.929687 0.242326 -0.12079 0.962646 0.351084 -0.497947 0.792962 0.282737 -0.494978 0.821618 0.34501 -0.788938 0.508473 0.333647 -0.790244 0.513999 0.148807 0.956458 -0.251087 0.230486 0.959504 -0.161952 0.341433 0.926131 -0.160329 0.424998 0.894303 -0.139999 0.484365 0.858906 -0.166347 0.687663 0.710175 -0.150901 0.647372 0.754209 -0.109904 0.870207 0.453735 -0.192002 0.850006 0.510021 -0.131788 0.172919 0.965218 0.196096 0.179712 0.963778 0.197067 0.423341 0.892183 0.157457 0.487231 0.787936 0.376515 0.503296 0.778691 0.37461 0.600297 0.563639 0.56741 0.532646 0.602137 0.594743 0.641638 0.319694 0.697206 0.575706 0.347914 0.739945 0.684256 0.0261846 0.728772 0.629492 0.0369799 0.776126 0.72119 -0.283011 0.632289 0.68563 -0.287993 0.668559 0.739821 -0.5452 0.394234 0.725679 -0.553268 0.409004 0.146446 0.659179 -0.737588 0.82472 -0.192874 -0.531635 0.651396 0.537822 -0.535192 0.942263 0.0699063 -0.327495 0.971801 0.07132 -0.224759 0.978816 0.0545115 -0.19735 0.98931 0.0773955 -0.123594 0.993672 0.0708204 -0.0871777 0.851108 0.424165 -0.309353 0.873456 0.332675 -0.355532 0.889412 0.286733 -0.355993 0.901406 0.237368 -0.36211 0.8953 0.246479 -0.371061 0.918228 0.174478 -0.355549 0.741744 -0.00736795 -0.670643 0.782191 -0.0248847 -0.622542 0.708895 0.188784 -0.67958 0.911965 0.180765 -0.368299 0.938587 0.120501 -0.323318 0.78696 -0.193969 -0.585722 0.849346 -0.283586 -0.445185 0.792188 -0.448396 -0.413979 0.856724 -0.488042 -0.166851 0.843569 -0.516119 -0.14837 0.88401 -0.447757 0.13431 0.87748 -0.456591 0.14681 0.921868 0.123915 -0.367157 0.959989 0.0981512 -0.262275 0.89144 -0.233779 -0.388177 0.944652 -0.266206 -0.191746 0.941309 -0.286184 -0.178988 0.970892 -0.238666 0.0201789 0.965072 -0.258228 0.0442022 0.115177 -0.953168 0.279653 0.0767977 -0.99659 0.030169 0.146669 -0.989184 -0.00176271 0.0529748 -0.933965 -0.353415 0.148672 -0.907046 -0.393908 0.0857604 -0.821116 -0.564282 0.146316 -0.689278 -0.709569 0.333936 -0.862149 0.381033 0.105767 -0.906313 0.409158 0.296924 -0.843836 0.446965 0.143131 -0.689065 -0.710424 0.0595993 -0.509286 -0.858531 0.223302 -0.361766 -0.905131 0.11619 -0.32931 -0.937046 0.0132374 -0.0331427 -0.999363 0.298947 -0.0745137 -0.951356 0.108596 0.077701 -0.991045 0.0837651 0.122869 -0.988882 0.0301416 0.320984 -0.946605 0.178767 0.365941 -0.913307 0.111647 0.674199 -0.730063 0.341459 0.643408 -0.685151 0.692774 0.495305 -0.524154 0.714411 0.345753 -0.608336 0.412914 0.389455 -0.823302 0.487266 0.118945 -0.865115 0.353596 0.0407125 -0.934512 0.447579 -0.228662 -0.864515 0.37767 -0.285286 -0.880896 0.480034 -0.510974 -0.713073 0.412117 -0.573579 -0.707931 0.513926 -0.730392 -0.449897 0.454267 -0.78236 -0.426091 0.542568 -0.835154 -0.0902101 0.499062 -0.864345 -0.0620064 0.553204 -0.772466 0.311869 0.54658 -0.775089 0.316998 0.344664 -0.860738 0.374617 0.287816 -0.957574 -0.0146345 0.346267 -0.937026 -0.0456187 0.253009 -0.881826 -0.397957 0.332875 -0.839067 -0.430304 0.223317 -0.670841 -0.707179 0.313043 -0.613867 -0.724687 0.200937 -0.366684 -0.908387 0.291655 -0.310782 -0.904628 0.187454 -0.0115866 -0.982205 0.269276 0.0283706 -0.962645 0.179699 0.36572 -0.913213 0.463496 0.355815 -0.811522 0.425019 0.608915 -0.669762 0.48435 0.61145 -0.625727 0.870901 0.380372 -0.311205 0.89297 0.297886 -0.337444 0.690172 0.372206 -0.620584 0.744779 0.160246 -0.647785 0.503288 0.115466 -0.85637 0.59314 -0.136608 -0.793425 0.545205 -0.189051 -0.816707 0.633562 -0.383945 -0.671704 0.588807 -0.444558 -0.675037 0.677988 -0.582387 -0.448506 0.63989 -0.635293 -0.43237 0.71848 -0.682922 -0.131922 0.691095 -0.714636 -0.108085 0.73978 -0.632225 0.230253 0.726923 -0.641686 0.244585 0.939621 0.281963 -0.193933 0.939565 0.315631 -0.132648 0.938422 0.324619 -0.118261 0.939691 0.321861 -0.115698 0.939384 0.323015 -0.114975 0.939417 0.322898 -0.115035 0.939895 0.321583 -0.114809 0.939964 0.321475 -0.114549 0.939946 0.321508 -0.114606 0.939763 0.321952 -0.114863 0.939561 0.322472 -0.115053 0.939619 0.273345 -0.205908 0.939838 0.272864 -0.20555 0.940957 0.271767 -0.201846 0.939691 0.273696 -0.205112 0.939968 0.272493 -0.205444 0.939975 0.272465 -0.205449 0.939693 0.273981 -0.204725 0.939471 0.273651 -0.206179 0.93945 0.273668 -0.206249 0.939565 0.284403 -0.190609 0.94337 0.274604 -0.186135 0.936007 0.305767 -0.174349 0.939622 0.295219 -0.173078 0.93966 0.305002 -0.154958 0.937285 0.312633 -0.154131 0.94337 0.3065 -0.126924 0.939622 0.317058 -0.12878 0.939693 0.321676 -0.116192 0.14935 0.814687 -0.560339 0.488782 0.718799 -0.494388 0.346081 0.869239 -0.35306 0.655063 0.700034 -0.284332 0.850958 0.486626 -0.197652 0.850961 0.486621 -0.197651 0.850961 0.47109 -0.232251 0.850965 0.471084 -0.232249 0.850964 0.453096 -0.265638 0.850962 0.4531 -0.265639 0.850962 0.43275 -0.297643 0.850963 0.432748 -0.297642 0.655068 0.622536 -0.428177 0.573448 0.679217 -0.458062 0.573338 0.706805 -0.41438 0.573327 0.706812 -0.414382 0.573327 0.734872 -0.362297 0.573328 0.734872 -0.362297 0.573439 0.756174 -0.315228 0.4888 0.808268 -0.328295 0.346098 0.773007 -0.531673 0.20213 0.81019 -0.550215 0.202091 0.844875 -0.495324 0.202095 0.844874 -0.495324 0.202095 0.878415 -0.433065 0.202101 0.878413 -0.433065 0.20214 0.905171 -0.373906 0.149343 0.916103 -0.372091 -0.707107 -0.671729 0.220861 -0.67119 -0.68914 0.273112 -0.706479 -0.658598 0.259108 -0.706478 -0.62307 0.335667 -0.70647 -0.623077 0.335671 -0.706522 -0.57966 0.405983 -0.672818 -0.604905 0.425918 -0.707099 -0.553972 0.439461 -0.706453 0.658622 -0.259117 -0.706479 0.658598 -0.259107 -0.706478 0.62307 -0.335667 -0.706458 0.623087 -0.335678 -0.706459 0.578695 -0.407464 -0.70647 0.578687 -0.407457 -0.696401 -0.691009 -0.193734 -0.430449 -0.886021 -0.172278 -0.705929 -0.642037 -0.299088 -0.696398 -0.519614 -0.495007 -0.33281 -0.745229 -0.577815 -0.705266 -0.438785 -0.556837 -0.704458 -0.304746 -0.64099 -0.523998 -0.269415 -0.807986 -0.6964 0.436455 -0.569678 -0.696399 0.436456 -0.56968 -0.703502 0.187908 -0.685402 -0.530088 0.140076 -0.836293 -0.705276 0.0167801 -0.708734 -0.704466 -0.140926 -0.695606 -0.694722 0.718255 -0.0383693 -0.487538 0.476261 0.731766 -0.694762 0.718217 -0.0383553 -0.702934 0.665215 0.25174 -0.494634 0.774767 0.393793 -0.705006 0.57573 0.414127 -0.70369 0.457922 0.543257 -0.704405 0.301421 0.642619 -0.704401 0.135269 0.696794 -0.487517 0.046568 0.871871 -0.694748 -0.602825 0.392335 -0.694741 -0.60283 0.39234 -0.702915 -0.389018 0.595462 -0.494623 -0.393791 0.774775 -0.70501 -0.221005 0.673882 -0.703696 -0.049735 0.708759 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.00865726 -0.604429 -0.796612 0.00529883 -0.61892 -0.785436 -0.00896936 -0.454608 -0.890646 1.60513e-05 -0.429374 -0.903127 -7.62185e-06 -0.227666 -0.973739 0.00734497 -0.198555 -0.980062 -0.00815697 -0.00559977 -0.999951 2.31492e-05 0.0236695 -0.99972 -1.94532e-05 0.236128 -0.971722 0.00925684 0.264389 -0.964372 -0.00335919 0.41044 -0.911882 0.0236761 0.608 -0.793584 0.0218078 0.61063 -0.791616 0 0.758249 -0.651965 1.5136e-05 -0.660161 -0.751124 6.52406e-06 -0.79028 -0.612746 -0.0095665 -0.806605 -0.591014 0.0035768 -0.906464 -0.422268 -0.0142009 -0.956505 -0.291371 0.0128876 -0.981535 -0.19085 0 -0.996899 -0.0786901 0.939621 0.14722 -0.308931 0.939565 0.207019 -0.27269 0.938422 0.221998 -0.264728 0.939692 0.22089 -0.261127 0.939391 0.222223 -0.261078 0.939414 0.222132 -0.261074 0.939897 0.221096 -0.260212 0.939965 0.221132 -0.259935 0.939947 0.221132 -0.26 0.939757 0.221398 -0.260461 0.939564 0.221738 -0.260867 0.93962 0.133771 -0.314991 0.939836 0.133535 -0.314446 0.94095 0.134433 -0.31071 0.939692 0.134471 -0.314479 0.939969 0.133264 -0.314165 0.939976 0.133237 -0.314155 0.939692 0.134915 -0.314287 0.939471 0.1339 -0.315382 0.939451 0.13388 -0.31545 0.939565 0.150995 -0.307274 0.94337 0.144746 -0.298499 0.936007 0.177627 -0.303874 0.939622 0.169128 -0.2975 0.93966 0.186661 -0.286699 0.937285 0.193684 -0.289798 0.94337 0.201975 -0.263171 0.939621 0.210193 -0.270058 0.939692 0.220477 -0.261473 0.14935 0.425371 -0.892611 0.48878 0.375305 -0.787553 0.346113 0.576247 -0.740368 0.65506 0.464083 -0.596258 0.850963 0.322599 -0.414478 0.850963 0.322599 -0.414478 0.850963 0.291848 -0.436677 0.850963 0.291848 -0.436677 0.850963 0.259575 -0.456599 0.850961 0.259577 -0.456602 0.850961 0.225951 -0.474143 0.850963 0.22595 -0.474141 0.655066 0.325044 -0.682081 0.573442 0.359191 -0.736306 0.573331 0.404924 -0.71227 0.573329 0.404924 -0.712271 0.57333 0.455268 -0.681193 0.573327 0.455269 -0.681194 0.573439 0.497252 -0.651082 0.488784 0.53584 -0.688452 0.346096 0.403609 -0.846946 0.202127 0.426538 -0.881595 0.202088 0.48402 -0.851402 0.202085 0.484021 -0.851402 0.202085 0.544198 -0.814254 0.20209 0.544197 -0.814254 0.202127 0.596949 -0.7764 0.149337 0.607323 -0.780293 -0.7071 -0.471312 0.527139 -0.671179 -0.460263 0.581099 -0.706468 -0.440815 0.553701 -0.706468 -0.371766 0.60224 -0.706468 -0.371766 0.60224 -0.70652 -0.299009 0.641423 -0.672809 -0.310907 0.671315 -0.707099 -0.260015 0.657574 -0.706476 0.440811 -0.553695 -0.706476 0.440811 -0.553695 -0.706475 0.371762 -0.602234 -0.706468 0.371766 -0.60224 -0.706468 0.297429 -0.642214 -0.70647 0.297429 -0.642213 -0.696796 -0.691498 -0.190542 -0.457746 -0.872701 -0.169888 -0.706051 -0.643202 -0.296283 -0.696788 -0.525936 -0.487727 -0.324166 -0.757437 -0.56675 -0.696797 0.0962738 -0.710778 -0.696799 0.0962743 -0.710776 -0.703909 -0.168058 -0.690122 -0.535518 -0.284996 -0.794983 -0.70513 -0.326366 -0.629505 -0.705132 -0.450801 -0.547327 -0.698072 0.585097 -0.412743 -0.698068 0.585099 -0.412747 -0.698065 0.706243 -0.118006 -0.618512 0.770234 -0.15551 -0.706899 0.70709 0.0178122 -0.698066 0.687503 0.200105 -0.698061 0.687509 0.200105 -0.698063 0.5326 0.478587 -0.698072 0.532591 0.478584 -0.69807 0.272199 0.662274 -0.698067 -0.348074 0.625737 -0.698069 -0.348073 0.625736 -0.700601 -0.065908 0.710503 -0.634906 -0.0454312 0.771253 -0.706901 0.0930249 0.701169 -0.698068 0.2722 0.662275 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.141324 -0.989963 0.00466185 0.134221 -0.99094 -0.00281844 -0.236604 -0.971602 0.00399087 -0.646823 -0.76263 -0.000100444 -0.560477 -0.82817 0.00079068 -0.460268 -0.88778 3.49312e-05 -0.457845 -0.889032 -1.29983e-05 -0.229743 -0.973251 -1.74907e-05 -0.635759 -0.771888 1.16152e-05 -0.800673 -0.599101 -0.00757377 -0.813341 -0.581738 0.00303655 -0.908267 -0.418381 0.00129207 -0.91347 -0.406904 -0.00405403 -0.981566 -0.191081 0 -0.979732 -0.200313 0 -0.552279 0.833659 0.0254425 -0.485957 0.873612 0.00385953 -0.373518 0.927615 -0.0105392 -0.0923609 0.99567 0.00709964 -0.129158 0.991599 -0.00161433 0.131519 0.991312 -0.0200922 0.294364 0.955482 0.0193189 0.38008 0.924752 0.00123245 0.529841 0.848096 -0.00305223 0.655882 0.754858 0.0538738 0.794286 0.60515 0.0129819 0.743751 0.668331 -0.000757912 0.86696 0.498378 0 0.817142 -0.576437 0.00483859 0.812736 -0.582612 -0.00427975 0.980212 -0.197904 0.00777096 0.975688 -0.219027 -6.76859e-06 0.999742 -0.0227219 -1.46788e-06 0.999683 0.0251829 -0.000888353 0.999394 0.0348023 0.00553182 0.960142 0.279457 0.0432314 0.975416 0.216092 0.00223858 0.913761 0.406245 0 0.622845 -0.782345 0 0.622845 -0.782345 0 0.525282 -0.850928 0 0.525282 -0.850928 0 0.420249 -0.907409 0 0.420249 -0.907409 0 -0.420249 0.907409 0 -0.420249 0.907409 0 -0.525282 0.850928 0 -0.525282 0.850928 0 -0.622845 0.782346 0 -0.622845 0.782346 -0.879241 0.138997 -0.455647 -0.887085 0.0645054 -0.457077 -0.954989 -0.0737514 -0.287326 -0.960102 -0.0805852 -0.267789 -0.978435 -0.0524011 -0.199796 -0.978976 -0.0523215 -0.197151 -0.991396 0.00763117 -0.130671 -0.990797 0.00525729 -0.135253 -0.965171 -0.194974 0.174444 -0.793209 -0.598518 -0.11223 -0.85947 -0.493519 0.133231 -0.839104 -0.526977 0.134905 -0.884191 -0.301901 0.356459 -0.876485 -0.316201 0.363029 -0.859289 -0.337855 -0.384026 -0.938546 -0.0761506 -0.33665 -0.933194 -0.0615099 -0.354071 -0.821644 -0.476524 -0.312771 -0.847484 -0.475731 -0.235482 -0.891284 -0.403587 -0.206715 -0.947044 -0.320969 -0.00928209 -0.938318 -0.345651 -0.00923007 -0.970911 -0.192706 0.142114 -0.989048 -0.131146 0.067707 -0.807338 -0.158449 -0.568418 -0.693245 -0.449653 -0.563226 -0.77072 -0.528343 -0.356152 -0.902135 -0.0103824 -0.431329 -0.88785 0.0699096 -0.454791 -0.749526 0.0104494 -0.661893 -0.710138 0.0247543 -0.703627 -0.105496 -0.803355 -0.586081 -0.139 -0.805451 -0.576131 -0.276014 -0.51103 -0.814042 -0.109034 -0.222461 -0.968826 -0.0571397 -0.453354 -0.889497 -0.220855 -0.5236 -0.822841 -0.206098 -0.534588 -0.819597 -0.0677862 -0.640598 -0.764878 -0.146988 0.186247 -0.971446 -0.0741755 0.142584 -0.986999 -0.106181 -0.536808 0.836996 -0.151427 -0.550124 0.821239 -0.105036 -0.705679 0.700703 -0.111701 -0.842694 0.526679 -0.0784085 -0.907438 -0.412805 -0.152077 -0.965265 -0.212455 -0.0787939 -0.969615 -0.231602 -0.10182 -0.988102 0.115268 -0.178472 -0.97374 0.141347 -0.089763 -0.942022 0.323323 -0.149951 -0.831991 0.534141 -0.354223 -0.460566 -0.813883 -0.457117 -0.671582 -0.583114 -0.363202 -0.691019 -0.624961 -0.490859 -0.818905 -0.297409 -0.397298 -0.855586 -0.331854 -0.5226 -0.851661 0.0395195 -0.442832 -0.896349 0.0214102 -0.546602 -0.74256 0.38708 -0.493382 -0.779321 0.386306 -0.553356 -0.487388 0.675463 -0.546229 -0.492453 0.677587 -0.176409 -0.505969 -0.844319 -0.302665 -0.763203 -0.57089 -0.186316 -0.772555 -0.606996 -0.325662 -0.911919 -0.249696 -0.208472 -0.93634 -0.282501 -0.343261 -0.93202 0.116235 -0.24185 -0.965659 0.0949295 -0.351503 -0.803666 0.480173 -0.282654 -0.83408 0.473727 -0.345033 -0.526965 0.776698 -0.333675 -0.532915 0.7776 -0.879553 0.139888 -0.454773 -0.763483 0.165926 -0.624149 -0.69396 0.137092 -0.706842 -0.651402 0.172458 -0.738873 -0.484429 0.18784 -0.854427 -0.918286 -0.0462257 -0.39321 -0.901026 -0.0382388 -0.432076 -0.758726 -0.244546 -0.603765 -0.805288 -0.212313 -0.553565 -0.700526 -0.319662 -0.638028 -0.633825 -0.0529516 -0.771662 -0.461119 -0.0930722 -0.882444 -0.425663 0.158922 -0.890817 -0.341494 0.182694 -0.921957 -0.206907 -0.176948 -0.962226 -0.179207 -0.171778 -0.968699 -0.424087 -0.137031 -0.895194 -0.48686 -0.353897 -0.798576 -0.502658 -0.353188 -0.789046 -0.601384 -0.554475 -0.575235 -0.531856 -0.578039 -0.618869 -0.642826 -0.689381 -0.333959 -0.575098 -0.730435 -0.368411 -0.685238 -0.727138 -0.0414673 -0.629204 -0.775095 -0.0577014 -0.721671 -0.637819 0.269032 -0.685629 -0.675688 0.270848 -0.739941 -0.406772 0.535746 -0.725681 -0.422661 0.542905 -0.146147 0.802169 -0.578935 -0.826274 0.507778 0.243791 -0.651414 0.583193 -0.485331 -0.992269 0.11722 -0.040772 -0.992328 0.0952823 -0.078785 -0.976262 0.214243 -0.0318319 -0.978909 0.199793 -0.0426597 -0.963222 0.26453 -0.0471905 -0.851017 0.339571 -0.400575 -0.880973 0.379098 -0.283147 -0.902083 0.382043 -0.200725 -0.895842 0.39125 -0.210689 -0.919311 0.368239 -0.138809 -0.740535 0.668745 0.0662457 -0.783613 0.615291 0.0858355 -0.707956 0.69452 -0.128222 -0.918519 0.369881 -0.13968 -0.938741 0.334324 -0.0836215 -0.785898 0.56764 0.245253 -0.847486 0.423727 0.319724 -0.793259 0.368473 0.484734 -0.856963 0.120978 0.500978 -0.84421 0.0981198 0.526956 -0.884163 -0.175309 0.433038 -0.877676 -0.189405 0.44024 -0.945947 0.31456 -0.0789755 -0.960044 0.275956 -0.0465112 -0.891348 0.365568 0.268066 -0.944831 0.166384 0.282153 -0.94185 0.150037 0.300679 -0.970926 -0.0405777 0.235915 -0.965173 -0.0685233 0.252479 -0.115166 -0.367275 0.922955 -0.0771069 -0.124071 0.989273 -0.146477 -0.0899574 0.985115 -0.0440741 0.296083 0.954145 -0.0575955 0.301644 0.951679 -0.0997434 0.535312 0.838744 -0.181858 0.642341 0.74453 -0.33401 -0.460346 0.822508 -0.105769 -0.491577 0.864387 -0.278866 -0.526975 0.802827 -0.0122451 0.992288 0.123352 -0.315859 0.93245 0.175415 -0.112681 0.993286 0.0261932 -0.136048 0.659564 0.739234 -0.0636826 0.800763 0.595587 -0.202697 0.86969 0.450059 -0.248148 0.851452 0.462008 -0.108768 0.912507 0.394335 -0.0842248 0.996035 -0.0286428 -0.0328943 0.974682 -0.221161 -0.190435 0.941614 -0.277664 -0.0911601 0.79123 -0.604685 -0.341493 0.742273 -0.576553 -0.693996 0.570408 -0.439323 -0.714753 0.63829 -0.285859 -0.41219 0.85538 -0.313728 -0.486902 0.872473 -0.0414272 -0.35418 0.933992 0.0470698 -0.447649 0.839888 0.306917 -0.378535 0.849849 0.366699 -0.48015 0.66309 0.574253 -0.413117 0.65029 0.637541 -0.514074 0.38056 0.768702 -0.45518 0.349812 0.818806 -0.542688 0.0123736 0.839843 -0.49964 -0.0202155 0.865997 -0.553286 -0.382411 0.740025 -0.546675 -0.388043 0.742003 -0.344679 -0.453464 0.821929 -0.288261 -0.0759624 0.954534 -0.346229 -0.0414799 0.937232 -0.253706 0.312755 0.915324 -0.332838 0.350905 0.875262 -0.22403 0.640718 0.734365 -0.313026 0.665025 0.678054 -0.201522 0.869837 0.450302 -0.291644 0.872184 0.392732 -0.187832 0.976725 0.103574 -0.269292 0.961164 0.0603755 -0.179204 0.942923 -0.28068 -0.463846 0.84164 -0.276566 -0.425696 0.725087 -0.541324 -0.484449 0.679593 -0.550875 -0.87538 0.343681 -0.33999 -0.889598 0.371625 -0.265536 -0.689728 0.651886 -0.315152 -0.7457 0.659277 -0.0963596 -0.502668 0.863653 -0.0378043 -0.593281 0.777579 0.2083 -0.546272 0.794632 0.264854 -0.633754 0.633691 0.443612 -0.589994 0.629277 0.505884 -0.678235 0.392932 0.620969 -0.640945 0.36956 0.672767 -0.718702 0.0680743 0.691978 -0.691731 0.0395334 0.721072 -0.73991 -0.287898 0.607986 -0.727057 -0.303886 0.615663 -0.572883 0.430541 -0.697452 -0.850726 0.328226 -0.410529 -0.879517 0.199084 -0.432221 -0.654672 0.317672 -0.685922 -0.764996 0.270656 -0.584403 -0.845143 0.227739 -0.483599 -0.851115 0.247675 -0.462882 -0.850698 0.276117 -0.447295 -0.850699 0.276116 -0.447293 -0.851117 0.302789 -0.428859 -0.345802 0.394323 -0.851428 -0.488403 0.366717 -0.791821 -0.149214 0.415545 -0.89725 -0.201917 0.41476 -0.887245 -0.201877 0.514467 -0.833408 -0.844348 0.333718 -0.419177 -0.654681 0.470812 -0.591379 -0.573004 0.506908 -0.643981 -0.488418 0.543501 -0.682682 -0.345801 0.58442 -0.734081 -0.573004 0.348516 -0.741757 -0.572883 0.430541 -0.697452 -0.201874 0.514467 -0.833409 -0.201914 0.60728 -0.768402 -0.14921 0.615873 -0.773587 -0.340893 -0.585538 0.735484 -0.994035 0.0572884 -0.092804 -0.994036 0.0680976 -0.0851732 -0.994251 0.0666935 -0.0837727 -0.991754 0.0536159 -0.116403 -0.996676 0.0384357 -0.0718331 -0.658679 -0.395235 0.640259 -0.931791 -0.190676 0.308884 -0.994046 0.047535 -0.0980502 -0.993745 -0.0469299 0.101332 -0.971837 -0.0990343 0.213836 -0.994056 0.0627947 -0.0889359 -0.994035 0.0572883 -0.0928038 -0.931791 -0.190675 0.308883 -0.931639 -0.146767 0.332428 -0.558463 -0.527525 0.640185 -0.739298 -0.41941 0.526815 -0.931791 -0.22609 0.283989 -0.888072 -0.295304 0.352312 -0.971843 -0.146761 0.184344 -0.237291 -0.510279 0.826624 -0.237292 -0.605055 0.760001 -0.108122 -0.630542 0.768588 -0.887838 -0.193381 0.41755 -0.739296 -0.282988 0.611031 -0.658467 -0.31023 0.685696 -0.558104 -0.348711 0.752942 -0.340892 -0.395078 0.853057 -0.658675 -0.468646 0.588658 -0.658675 -0.395236 0.640262 -0.237287 -0.51028 0.826625 -0.237191 -0.40221 0.884289 -0.108043 -0.417789 0.902097 -0.939508 0.1433 -0.311111 -0.93961 0.123471 -0.3192 -0.939482 0.123468 -0.319576 -0.939573 0.123629 -0.319248 -0.93969 0.124462 -0.318577 -0.939848 0.123208 -0.3186 -0.939867 0.123147 -0.318567 -0.939726 0.123354 -0.318902 -0.939515 0.213885 -0.267517 -0.940464 0.227337 -0.252678 -0.939696 0.229496 -0.253579 -0.939901 0.229575 -0.252749 -0.93969 0.229162 -0.253905 -0.939535 0.230154 -0.253582 -0.939497 0.230308 -0.253583 -0.939513 0.230252 -0.253575 -0.939751 0.229728 -0.253167 -0.939508 0.213897 -0.267532 -0.939511 0.213891 -0.267523 -0.939694 0.19727 -0.279392 -0.939693 0.197264 -0.279398 -0.939498 0.179938 -0.29149 -0.939498 0.179938 -0.29149 -0.939693 0.161357 -0.301563 -0.939693 0.161358 -0.301563 -0.939511 0.143295 -0.311104 -0.939514 0.143293 -0.311095 -0.939697 0.124238 -0.318646 0 -0.992194 0.124706 0.0179213 -0.984583 0.173996 -0.000942638 -0.943641 0.330969 0.00366025 -0.834451 0.551069 0.00541218 -0.836579 0.54782 -0.000281949 -0.706649 0.707564 0.00443696 -0.5467 0.837317 0 -0.538132 0.84286 -0.69963 -0.703603 0.124341 -0.699617 -0.703615 0.124348 -0.699619 -0.596233 0.393751 -0.699633 -0.596224 0.393738 -0.699633 -0.390622 0.598271 -0.699625 -0.390624 0.598279 0 0.975988 0.217826 -0.0113426 0.968021 0.250613 0.00654442 0.85091 0.52527 -0.0215143 0.763955 0.644911 -0.00273662 0.698569 0.715538 0.00186522 0.550601 0.834766 -0.0187057 0.409444 0.912144 0.000307933 0.336659 0.941626 -8.76788e-05 0.149136 0.988817 -0.0133101 -0.0258377 0.999578 0.00481129 -0.0899636 0.995933 -0.00560073 -0.456099 0.889911 0 -0.471516 0.881858 0.698114 -0.326565 0.637175 0.69811 -0.326568 0.637178 0.704246 -0.0870325 0.704602 0.798049 -0.015571 0.602392 0.698111 0.693137 0.179448 0.698103 0.693144 0.179453 0.698105 0.547115 0.46186 0.698112 0.547111 0.461854 0.69811 0.293209 0.6532 0.698115 0.293208 0.653196 0.705434 0.0714572 0.705165 0.698069 0.131145 -0.703918 0.698062 0.131148 -0.703924 0.698063 -0.187261 -0.691116 0.609318 -0.181499 -0.771874 0.706896 -0.31104 -0.635257 0.698062 -0.468582 -0.541425 0.698068 -0.468579 -0.541419 0.698069 -0.657087 -0.284494 0.698061 -0.657093 -0.284499 0.698062 -0.715459 0.0287782 0.698064 -0.715457 0.0287788 0.706898 -0.676087 0.207852 0.698066 -0.42358 0.577308 0.69807 -0.423576 0.577305 0.700606 -0.618284 0.356197 0.796086 -0.503852 0.335233 0.68404 -0.681992 0.258798 0.697968 0.571132 -0.43203 0.697969 0.57113 -0.432029 0.69797 0.702382 -0.139632 0.697963 0.702389 -0.139631 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706177 -0.327472 0.627755 0.706169 -0.327475 0.627762 0.706169 -0.41443 0.574084 0.706182 -0.414423 0.574074 0 -0.604666 0.796479 0.0420198 -0.5848 0.810088 0 -0.545614 0.838037 0 -0.462508 0.886615 0.0629311 -0.440157 0.895713 0 -0.504647 0.863326 0.706177 0.327472 -0.627755 0.706175 0.327473 -0.627756 0.706175 0.414427 -0.57408 0.706182 0.414422 -0.574074 0 0.783208 -0.62176 -0.00897472 0.797494 -0.60326 0.000616644 0.908354 -0.418202 -0.00470314 0.973132 -0.230199 -0.0163923 0.980675 -0.194956 0 0.999778 -0.0210679 0 -0.526454 0.850203 -0.0178436 -0.59147 0.80613 -0.00272678 -0.686549 0.727078 0.00733731 -0.866469 0.499178 -0.00493575 -0.847421 0.530898 0.00112494 -0.955848 0.29386 0.0112965 -0.986157 0.165432 -0.0189616 -0.999012 0.0401846 -0.00488878 -0.997688 -0.0677864 0.00688782 -0.966319 -0.257256 -0.03889 -0.877082 -0.478763 -0.00581117 -0.917663 -0.397318 0.000322586 -0.808852 -0.588012 0 0.183159 -0.983083 -0.00756791 0.200455 -0.979674 0.00704874 -0.228892 -0.973426 -0.00552138 -0.197846 -0.980218 3.01404e-06 -0.396275 -0.918132 -1.54291e-06 -0.439746 -0.898122 1.30607e-05 -0.439956 -0.898019 3.62336e-06 -0.654411 -0.756139 -0.0308332 -0.595524 -0.802746 -0.00153125 -0.750315 -0.661079 0.994042 0.0480702 -0.0978223 0.97185 -0.103907 0.21145 0.658911 -0.395129 0.640086 0.108082 -0.601124 0.791813 0.558286 -0.50166 0.660798 0.341058 -0.568412 0.748724 0.237328 -0.594012 0.768652 0.237623 -0.529986 0.814033 0.153993 -0.519017 0.840778 0.237623 -0.490192 0.838598 0.237428 -0.42842 0.871828 0.887896 -0.278173 0.366415 0.739454 -0.407065 0.536195 0.108167 -0.421952 0.900143 0.341051 -0.414588 0.843683 0.658911 -0.331752 0.675113 0.558601 -0.35 0.751974 0.739458 -0.296903 0.604194 0.971845 -0.142473 0.187668 0.931703 -0.226085 0.284281 0.931867 -0.190573 0.308717 0.658687 -0.461578 0.594203 0.65891 -0.395129 0.640086 0.931866 -0.190573 0.308718 0.931867 -0.160007 0.325611 0.888088 -0.189575 0.418761 0.994042 0.0659055 -0.0868121 0.994042 0.065906 -0.0868126 0.994053 0.0594188 -0.0912635 0.994978 0.0525781 -0.0851736 0.994053 0.0549569 -0.0940173 0.994042 0.0480701 -0.0978222 0 0.430196 -0.902736 -0.126161 0.490269 -0.862392 0 0.462508 -0.886615 0 0.555662 -0.831408 -0.063502 0.584136 -0.809168 0 0.61421 -0.789142 0.0694066 0.55596 0.828306 0.0923953 0.157045 0.98326 0.81278 0.550306 0.191185 0.893719 0.373421 -0.248645 0.900887 0.3878 -0.194972 0.982611 0.181262 -0.040237 0.968946 0.241465 -0.0532703 0.959186 0.276979 -0.0569556 0.955083 0.287587 -0.0714835 0.937216 0.335686 -0.0945574 0.978164 0.200681 -0.0540641 0.993506 0.0918318 -0.0671826 0.993503 0.0954563 -0.0619707 0.712669 0.618255 -0.331456 0.884954 0.370968 -0.281494 0.885791 0.366312 -0.284939 0.759736 0.645496 0.0783252 0.771364 0.636041 0.0212099 0.722821 0.681156 -0.116432 0.187412 0.901242 0.390691 0.301511 0.868137 0.394244 0.0388932 0.971669 -0.233126 0.491514 0.780004 -0.387308 0.146926 0.764214 -0.628004 0.123005 0.775382 -0.619397 0.0926653 0.99526 -0.0295212 0.219676 0.973418 0.0648018 0.275276 0.959686 0.0567993 0.177309 0.983222 0.0428556 0.353647 0.93527 0.0142792 0.456016 0.834872 0.308283 0.364116 0.87811 0.310391 0.172309 0.93402 -0.312916 0.179699 0.933194 -0.311219 0.423345 0.851381 -0.309724 0.487232 0.870629 -0.0679006 0.503314 0.861661 -0.0649251 0.600307 0.771825 0.209564 0.532649 0.818838 0.213986 0.26823 0.696436 0.665604 0.87644 -0.16747 0.451451 0.884046 -0.167656 0.436295 0.725686 -0.274638 0.630836 0.739822 -0.275036 0.614019 0.546197 -0.359297 0.756687 0.553285 -0.359557 0.751395 0.333638 -0.427375 0.84026 0.34499 -0.429006 0.834827 0.105756 -0.461865 0.880623 0.121171 -0.465295 0.876823 0.146148 0.347752 0.926126 0.166945 0.341201 0.925047 0.342321 0.347045 0.873141 0.242319 0.376718 0.894072 0.521629 0.375736 0.76598 0.443207 0.408382 0.797992 0.684257 0.387059 0.618043 0.62949 0.420087 0.653659 0.792147 0.38695 0.471989 0.839075 0.13322 0.527452 0.858963 0.121105 0.497509 0.685634 0.0848681 0.722982 0.721183 0.0710521 0.689092 0.493421 0.0329053 0.869168 0.546143 0.0176358 0.837506 0.282727 -0.0178558 0.959034 0.351082 -0.0347563 0.935699 0.0859223 -0.0624508 0.994343 0.15188 -0.0784668 0.985279 0.484348 0.660671 -0.573516 0.687665 0.53958 -0.485767 0.647368 0.598222 -0.472278 0.870204 0.296956 -0.393144 0.850012 0.375774 -0.369152 0.933082 0.340998 -0.114359 0.918216 0.368009 -0.146457 0.916084 0.372085 -0.149473 0.902776 0.371835 -0.216182 0.73816 0.655878 -0.157935 0.69772 0.644548 -0.312643 0.461109 0.820175 -0.338662 0.425004 0.704483 -0.568398 0.341467 0.721877 -0.601908 -0.0661784 0.97225 0.224387 0.305608 0.82882 0.46868 0.0131364 0.891659 0.452517 0.143546 0.668034 0.730154 0.324413 0.658426 0.67914 0.209402 0.6939 0.688951 0.489608 0.655568 0.574904 0.39806 0.698804 0.594324 0.641643 0.625464 0.443947 0.575708 0.671275 0.466851 0.805189 0.538031 0.249387 0.849348 0.427718 0.309298 0.891414 0.373795 0.25624 0.946584 0.16351 0.277925 0.938297 0.173172 0.299351 0.97139 -0.0473056 0.23273 0.963017 -0.0463603 0.265422 0.146445 0.202071 -0.96836 0.824721 -0.432849 -0.363975 0.651396 0.198173 -0.732401 0.942263 -0.103208 -0.318573 0.971801 -0.0506149 -0.230306 0.978816 -0.0514669 -0.198166 0.98931 0.00523045 -0.145733 0.993672 0.017744 -0.110908 0.851107 0.212659 -0.479992 0.873455 0.110341 -0.474238 0.889413 0.0703202 -0.451664 0.901406 0.0245109 -0.43228 0.8953 0.0279263 -0.444587 0.918227 -0.0266701 -0.395155 0.741741 -0.341701 -0.577114 0.782193 -0.332819 -0.526692 0.708899 -0.176299 -0.682921 0.911964 -0.0276001 -0.409341 0.938588 -0.0573014 -0.34025 0.786963 -0.460838 -0.410265 0.849349 -0.468181 -0.243747 0.79219 -0.595311 -0.134313 0.856723 -0.506083 0.0995268 0.843573 -0.521152 0.129558 0.884014 -0.320612 0.340188 0.877479 -0.322013 0.35544 0.921869 -0.0762641 -0.379922 0.959989 -0.0461361 -0.276212 0.891437 -0.396553 -0.219284 0.944652 -0.326416 -0.0329492 0.941309 -0.337336 -0.0119143 0.970892 -0.196603 0.136807 0.965072 -0.201533 0.167394 0.11518 -0.685638 0.718773 0.0768014 -0.84799 0.524419 0.146656 -0.85754 0.493069 0.0529591 -0.985546 0.160916 0.148675 -0.98248 0.11238 0.0857671 -0.993248 -0.0781238 0.146321 -0.951716 -0.269863 0.333937 -0.556126 0.761058 0.105763 -0.580311 0.807498 0.296926 -0.507298 0.809001 0.0132514 -0.528386 -0.848901 0.298936 -0.540209 -0.786646 0.108601 -0.428239 -0.897116 0.143132 -0.951961 -0.270711 0.0596012 -0.870327 -0.488854 0.223319 -0.765858 -0.602985 0.243316 -0.766993 -0.593733 0.107844 -0.737416 -0.666774 0.0837599 -0.388023 -0.917836 0.030144 -0.195319 -0.980276 0.178761 -0.139741 -0.973918 0.111637 0.218845 -0.969352 0.341454 0.214635 -0.915064 0.692776 0.166869 -0.701581 0.714412 -0.00473889 -0.699709 0.412917 -0.0743751 -0.907727 0.48727 -0.329547 -0.808682 0.35359 -0.432004 -0.829667 0.447572 -0.63029 -0.634361 0.377676 -0.687508 -0.620237 0.480038 -0.799049 -0.362056 0.412116 -0.850699 -0.326299 0.513925 -0.857487 -0.0244221 0.454265 -0.890591 0.0221803 0.542564 -0.768371 0.339456 0.49906 -0.779549 0.378475 0.5532 -0.513043 0.656321 0.546582 -0.512749 0.66207 0.344674 -0.558113 0.754791 0.28783 -0.836597 0.466112 0.346283 -0.834293 0.429002 0.253022 -0.96266 0.0962607 0.332855 -0.941812 0.0468896 0.223297 -0.934561 -0.277009 0.313037 -0.89397 -0.320666 0.200931 -0.771751 -0.603346 0.291654 -0.721457 -0.628043 0.187458 -0.501139 -0.844819 0.269275 -0.456758 -0.847858 0.179693 -0.139885 -0.973726 0.463495 -0.0976164 -0.880706 0.425018 0.192457 -0.884489 0.484349 0.21667 -0.847621 0.870905 0.173799 -0.459694 0.89297 0.089256 -0.441178 0.690171 0.0120484 -0.723546 0.744777 -0.185115 -0.641124 0.503282 -0.328188 -0.799375 0.593137 -0.515022 -0.618822 0.545199 -0.572082 -0.612764 0.633554 -0.668363 -0.389744 0.588798 -0.722522 -0.362324 0.677985 -0.728619 -0.0972151 0.639892 -0.766363 -0.0567936 0.71848 -0.657391 0.227208 0.691085 -0.672943 0.263721 0.739774 -0.432398 0.515525 0.726921 -0.433425 0.532661 -0.146158 0.405232 -0.902455 -0.826271 0.561648 -0.0427641 -0.651419 0.262393 -0.711902 -0.992269 0.0811323 -0.0939181 -0.992328 0.0431234 -0.115871 -0.976262 0.169619 -0.134689 -0.978909 0.151699 -0.136841 -0.96322 0.205503 -0.173136 -0.851017 0.093786 -0.516696 -0.880975 0.186735 -0.434757 -0.902084 0.230498 -0.36485 -0.895847 0.233487 -0.378076 -0.919312 0.249498 -0.304331 -0.740533 0.612275 -0.277002 -0.783613 0.575776 -0.233309 -0.707959 0.537363 -0.458297 -0.918516 0.25049 -0.305915 -0.938741 0.247724 -0.239579 -0.785899 0.614216 -0.0714262 -0.847487 0.526818 0.0650273 -0.79326 0.561472 0.23556 -0.856962 0.355259 0.373373 -0.844209 0.348453 0.407299 -0.884164 0.064698 0.462675 -0.877675 0.0560901 0.475963 -0.945948 0.232929 -0.225671 -0.960045 0.21573 -0.178256 -0.89135 0.450619 0.0493687 -0.944831 0.28517 0.161158 -0.94185 0.280275 0.185376 -0.970926 0.0828177 0.224596 -0.965173 0.0668974 0.252916 -0.115165 0.143409 0.98294 -0.0771055 0.387191 0.91877 -0.146469 0.414653 0.898114 -0.0440749 0.733487 0.678273 -0.0576011 0.737071 0.673356 -0.0997497 0.882969 0.45871 -0.181859 0.928548 0.323613 -0.334006 0.0125799 0.942487 -0.105777 0.00647198 0.994369 -0.278874 -0.0549629 0.958753 -0.0122648 0.921023 -0.389315 -0.315851 0.895235 -0.314314 -0.112669 0.873306 -0.473964 -0.136051 0.940815 0.310416 -0.0636846 0.991274 0.115415 -0.202704 0.978202 -0.0450854 -0.248132 0.968387 -0.025628 -0.108786 0.987421 -0.114741 -0.0842308 0.848285 -0.522799 -0.0328908 0.73352 -0.678872 -0.190445 0.676625 -0.711273 -0.0911722 0.382884 -0.919286 -0.341502 0.354551 -0.870443 -0.693993 0.274322 -0.665673 -0.714752 0.409848 -0.566704 -0.412196 0.583917 -0.699382 -0.486908 0.73487 -0.472108 -0.354186 0.832396 -0.426227 -0.447649 0.880821 -0.154158 -0.378511 0.919351 -0.10735 -0.480131 0.861388 0.165786 -0.413117 0.881939 0.226976 -0.514079 0.713923 0.475433 -0.455176 0.712347 0.534207 -0.542684 0.43064 0.72114 -0.499637 0.415495 0.760083 -0.553284 0.0388308 0.832087 -0.546679 0.0349461 0.836613 -0.344681 0.0182533 0.938542 -0.288266 0.411482 0.86463 -0.346239 0.432696 0.832402 -0.253718 0.728515 0.636312 -0.332836 0.74152 0.582553 -0.224029 0.92206 0.315621 -0.313042 0.914953 0.25469 -0.20154 0.978448 -0.0449506 -0.291653 0.951697 -0.095976 -0.187842 0.897656 -0.39866 -0.269302 0.86258 -0.42829 -0.179209 0.676251 -0.714541 -0.463839 0.590598 -0.660338 -0.425689 0.357281 -0.831348 -0.484439 0.31311 -0.816873 -0.875377 0.127634 -0.466289 -0.889597 0.189069 -0.415776 -0.689721 0.406976 -0.598878 -0.745695 0.522776 -0.413091 -0.502659 0.729048 -0.464568 -0.593275 0.777558 -0.208394 -0.546283 0.820588 -0.167958 -0.633765 0.770591 0.0673202 -0.589987 0.797915 0.123479 -0.678229 0.650774 0.341319 -0.640947 0.65643 0.397852 -0.718704 0.404943 0.565231 -0.691735 0.394774 0.604695 -0.739911 0.0546653 0.67048 -0.727055 0.0446557 0.685125 -0.572883 0.0241331 -0.819282 -0.850725 0.0789877 -0.519642 -0.879516 -0.0436989 -0.473859 -0.654682 -0.067848 -0.752854 -0.765002 -0.0578063 -0.641428 -0.845143 -0.0445722 -0.532679 -0.851114 -0.0169522 -0.524707 -0.850697 0.0154772 -0.525429 -0.850696 0.0154772 -0.52543 -0.851114 0.0478036 -0.5228 -0.345793 -0.084221 -0.934523 -0.488391 -0.0783252 -0.869103 -0.149212 -0.0887536 -0.984814 -0.201918 -0.0844302 -0.975756 -0.201879 0.0288376 -0.978986 -0.844347 0.0794195 -0.529878 -0.654684 0.112045 -0.747552 -0.573004 0.117004 -0.811158 -0.48841 0.129345 -0.862975 -0.345802 0.139082 -0.927943 -0.573009 -0.0690542 -0.816635 -0.572888 0.0241335 -0.819279 -0.201883 0.028838 -0.978985 -0.201924 0.141719 -0.969094 -0.149222 0.146567 -0.977881 -0.340889 -0.139349 0.929719 -0.994035 0.00321122 -0.109014 -0.994036 0.0163875 -0.10781 -0.994251 0.0158719 -0.105896 -0.991754 -0.0117687 -0.127616 -0.996675 -0.00263207 -0.0814366 -0.658678 -0.0221542 0.752099 -0.93179 -0.010688 0.36284 -0.994046 -0.00785853 -0.108681 -0.993745 0.0100235 0.111222 -0.971837 0.0211518 0.234703 -0.994056 0.00991325 -0.108418 -0.994035 0.0032112 -0.109015 -0.93179 -0.010688 0.36284 -0.931639 0.0391101 0.361275 -0.558466 -0.136757 0.818177 -0.739295 -0.0998131 0.665944 -0.93179 -0.0538058 0.358987 -0.888072 -0.0795845 0.452762 -0.971842 -0.0349268 0.233029 -0.237289 -0.0286031 0.971018 -0.237289 -0.143993 0.960708 -0.108131 -0.16177 0.980886 -0.887836 0.0413028 0.458303 -0.739299 0.0604406 0.670659 -0.658466 0.0741806 0.748946 -0.558106 0.0744785 0.82642 -0.340885 0.084382 0.93631 -0.658678 -0.11153 0.744113 -0.658678 -0.0221543 0.752099 -0.237288 -0.0286029 0.971018 -0.237191 0.0938206 0.966922 -0.10804 0.0892322 0.990134 -0.939508 -0.0314542 -0.34108 -0.939611 -0.0526681 -0.338168 -0.939483 -0.0528584 -0.338492 -0.939571 -0.0525632 -0.338294 -0.93969 -0.0514954 -0.338128 -0.939848 -0.0525981 -0.337519 -0.939868 -0.0526344 -0.337458 -0.939722 -0.0526227 -0.337866 -0.939514 0.0514716 -0.33862 -0.940472 0.0705239 -0.332473 -0.939696 0.0719596 -0.334354 -0.939902 0.072447 -0.333669 -0.93969 0.0715114 -0.334469 -0.939536 0.0725215 -0.334682 -0.939491 0.072679 -0.334776 -0.939515 0.072613 -0.334723 -0.939748 0.072368 -0.334121 -0.939507 0.0514743 -0.338639 -0.939511 0.0514737 -0.338628 -0.939694 0.0311426 -0.340597 -0.939694 0.0311433 -0.340596 -0.939498 0.0100862 -0.342406 -0.939497 0.0100861 -0.342407 -0.939693 -0.0110484 -0.34184 -0.939694 -0.0110441 -0.341839 -0.939511 -0.0314543 -0.341071 -0.939515 -0.0314524 -0.341061 -0.939697 -0.0517285 -0.338073 0 -0.998193 0.0600901 0.0289425 -0.98173 0.188067 0.00936145 -0.96889 0.247315 -0.00448714 -0.904972 0.425447 0.0231653 -0.809736 0.586337 0.00325425 -0.777697 0.628631 -0.000780788 -0.642436 0.766339 0.0154079 -0.485173 0.874282 -0.000839607 -0.45091 0.892569 0.00100278 -0.0691247 0.997608 0 -0.0670639 0.997749 -0.698525 -0.702806 0.134635 -0.698522 -0.702808 0.134636 -0.698521 -0.579594 0.419689 -0.698525 -0.579592 0.419686 -0.698524 -0.347225 0.625699 -0.698523 -0.347225 0.6257 -0.698522 -0.0494648 0.713877 -0.698526 -0.0494659 0.713873 0 0.994819 0.101661 -0.0176539 0.970264 0.241406 -0.00801374 0.960078 0.279617 0.00276866 0.890241 0.455481 -0.0133488 0.782093 0.623019 -0.00232082 0.756382 0.654126 0.000404711 0.616613 0.787266 -0.00838814 0.452265 0.891844 0.00230274 0.4199 0.907567 -0.00254961 0.0404979 0.999176 0 0.0325856 0.999469 0.698862 0.0289663 0.714669 0.698863 0.0289664 0.714669 0.703793 0.270889 0.656731 0.787844 0.278548 0.549284 0.698865 0.694093 0.172693 0.698865 0.694093 0.172693 0.698863 0.559446 0.445657 0.698866 0.559445 0.445655 0.70602 0.40316 0.582235 0 -0.125418 0.992104 0.0420212 -0.101408 0.993957 0 -0.0534963 0.998568 0 0.0427637 0.999085 0.0629301 0.0666695 0.995789 0 -0.00537307 0.999986 0.706187 -0.0302781 -0.707377 0.706178 -0.0302781 -0.707386 0.706179 0.0718641 -0.704377 0.706181 0.0718639 -0.704375 0.00152341 0.594362 -0.804196 -0.0135941 0.400059 -0.916388 -0.01042 0.39248 -0.919701 0 0.198842 -0.980032 -0.00712895 0.741969 -0.670396 -0.0225393 0.775027 -0.631526 0.00163157 0.873305 -0.487171 0 0.996038 -0.0889241 -0.0252481 0.978077 -0.206706 -0.00605636 0.955786 -0.294002 -0.000611653 0.918634 -0.395108 0 -0.0308216 0.999525 -0.0178431 -0.109161 0.993864 -0.00272511 -0.231035 0.972942 0.00733945 -0.500799 0.865533 -0.00493652 -0.468435 0.883484 0.00112446 -0.680863 0.73241 0.0112952 -0.771318 0.636349 -0.0189637 -0.845077 0.534308 -0.00489034 -0.897918 0.440136 0.00688662 -0.965486 0.260363 -0.0388908 -0.998957 0.0239159 -0.00580982 -0.993378 0.114746 0.000322626 -0.994496 -0.104775 0 -0.332919 -0.942955 -0.00756832 -0.316234 -0.948651 0.00704801 -0.684938 -0.728567 -0.00552175 -0.661448 -0.749971 3.31006e-06 -0.802256 -0.59698 -1.0928e-06 -0.829898 -0.557916 1.16553e-05 -0.830012 -0.557746 2.0971e-06 -0.944806 -0.327629 -0.0308317 -0.917115 -0.397429 -0.00153218 -0.980329 -0.197365 0.994042 -0.00728114 -0.108752 0.97185 0.0157385 0.235072 0.658911 -0.0221481 0.751895 0.10809 -0.124683 0.986291 0.558296 -0.104051 0.823091 0.341056 -0.117898 0.93262 0.237323 -0.130104 0.962679 0.237619 -0.0519641 0.969967 0.153991 -0.0290924 0.987644 0.237622 -0.00521918 0.971344 0.237427 0.0648918 0.969236 0.887897 -0.057697 0.456409 0.73945 -0.0844321 0.667896 0.108165 0.0846501 0.990523 0.341051 0.0627971 0.937945 0.658911 0.0502501 0.750541 0.558602 0.0728773 0.826228 0.739456 0.0449717 0.671701 0.971845 -0.029551 0.233762 0.931702 -0.0536545 0.359238 0.931867 -0.0106823 0.362643 0.658687 -0.102636 0.745384 0.658909 -0.0221485 0.751897 0.931867 -0.0106823 0.362643 0.931867 0.0242359 0.36199 0.888088 0.0452039 0.457445 0.994042 0.0136698 -0.108135 0.994042 0.0136699 -0.108135 0.994053 0.00582627 -0.108746 0.994978 0.00294722 -0.100052 0.994053 0.000585702 -0.1089 0.994042 -0.00728119 -0.108751 0 -0.0788078 -0.99689 -0.0635013 -0.0426779 -0.997069 0 -0.00666479 -0.999978 0 0.0655136 -0.997852 -0.0635018 0.101293 -0.992828 0 0.13735 -0.990523 0.127341 0.385793 -0.913755 0.0569293 0.952206 -0.300104 0.891416 0.451831 0.035008 0.893723 0.199084 -0.402025 0.900887 0.238349 -0.362756 0.982611 0.13686 -0.125478 0.968946 0.18248 -0.166866 0.959187 0.211392 -0.187814 0.955084 0.213314 -0.205696 0.937215 0.243437 -0.249734 0.963017 0.092561 0.253042 0.97139 0.0753965 0.225203 0.876441 0.0806908 0.4747 0.884046 0.0729534 0.461672 0.858962 0.353637 0.370304 0.839075 0.379098 0.390176 0.946585 0.280565 0.158933 0.938298 0.299644 0.172658 0.978164 0.146762 -0.147159 0.993506 0.0459384 -0.104097 0.993503 0.051681 -0.101397 0.712675 0.369694 -0.596172 0.884953 0.180523 -0.429266 0.885792 0.174756 -0.429922 0.792143 0.571107 0.215282 0.849346 0.525067 0.0539981 0.805188 0.590643 -0.0530399 0.81278 0.572172 -0.109583 0.759739 0.598178 -0.254911 0.771366 0.561434 -0.299645 0.72282 0.531681 -0.441415 0.133812 0.988481 -0.0707016 0.275273 0.859515 -0.43065 0.447067 0.511943 -0.733516 0.0443681 0.738658 -0.672618 0.119366 0.896371 -0.426933 0.332109 0.807966 -0.486717 0.192862 0.893359 -0.405849 0.933082 0.238137 -0.269536 0.918216 0.245479 -0.310836 0.916085 0.247502 -0.315485 0.902775 0.213926 -0.373139 0.738159 0.489038 -0.464719 0.697721 0.401879 -0.593025 0.4611 0.540974 -0.703373 0.105762 0.0403258 0.993573 0.121175 0.035456 0.991998 0.0859317 0.443089 0.89235 0.151883 0.424688 0.892509 0.0947263 0.620708 0.778298 0.147692 0.758749 0.634418 0.148864 0.758421 0.634537 0.223945 0.96801 -0.113163 0.0681351 0.993325 0.0930757 0.143527 0.943612 0.298322 0.246954 0.93865 0.240729 0.0723721 0.89164 0.446923 0.353642 0.81711 -0.455268 0.456009 0.877166 -0.150451 0.364118 0.915661 -0.170242 0.489607 0.855191 0.170096 0.398057 0.902346 0.165296 0.521627 0.708388 0.475491 0.443208 0.752665 0.48689 0.546144 0.434025 0.716484 0.493415 0.463083 0.736272 0.553281 0.064315 0.830508 0.546207 0.0671794 0.834952 0.177299 0.872926 -0.454495 0.3015 0.948954 -0.0926479 0.187431 0.97584 -0.112272 0.324428 0.909779 0.258939 0.2094 0.945412 0.249697 0.342324 0.737119 0.58264 0.242315 0.773284 0.585931 0.351079 0.437751 0.827718 0.28273 0.464052 0.839476 0.344994 0.0458839 0.937483 0.333635 0.050015 0.941374 0.14938 0.196149 -0.969129 0.188397 0.344023 -0.919867 0.341466 0.324212 -0.882206 0.424994 0.325903 -0.844492 0.48435 0.285394 -0.827016 0.68767 0.2244 -0.690475 0.647368 0.281937 -0.708115 0.870205 0.0605967 -0.488949 0.850012 0.140858 -0.507581 0.172307 0.652427 -0.738003 0.179692 0.652561 -0.736122 0.42335 0.582453 -0.693919 0.487236 0.720033 -0.494119 0.50331 0.713758 -0.487062 0.600311 0.773201 -0.204421 0.532656 0.816124 -0.224096 0.641645 0.76364 0.0717342 0.575715 0.814762 0.0686641 0.684263 0.644221 0.341708 0.629491 0.690636 0.356039 0.721184 0.406079 0.561243 0.685634 0.434991 0.583686 0.739823 0.0688185 0.669272 0.725681 0.0775761 0.683644 0.146433 -0.309179 -0.939663 0.82472 -0.556847 -0.0987864 0.651397 -0.194575 -0.733364 0.942262 -0.248669 -0.22429 0.971801 -0.158987 -0.174145 0.978817 -0.143654 -0.145883 0.98931 -0.0683362 -0.128823 0.993672 -0.040088 -0.104922 0.851107 -0.0558255 -0.522016 0.873457 -0.14156 -0.465868 0.889412 -0.164928 -0.426316 0.901407 -0.194912 -0.386619 0.8953 -0.198108 -0.398988 0.918228 -0.220675 -0.328877 0.741742 -0.58448 -0.328942 0.782192 -0.551579 -0.289719 0.708898 -0.49414 -0.503278 0.911963 -0.228576 -0.3407 0.938587 -0.219752 -0.266015 0.786962 -0.604232 -0.12488 0.849348 -0.527333 0.0229993 0.792189 -0.582713 0.181335 0.856724 -0.388518 0.339232 0.84357 -0.386552 0.372784 0.88401 -0.107562 0.454924 0.877481 -0.101154 0.468823 0.921876 -0.255995 -0.29088 0.959988 -0.178061 -0.21614 0.891439 -0.453063 0.00836967 0.944652 -0.299159 0.134668 0.941309 -0.298099 0.158349 0.970892 -0.101858 0.216779 0.965073 -0.0908335 0.245731 0.115183 -0.234399 0.965293 0.0768042 -0.472168 0.878156 0.146661 -0.496114 0.855781 0.0529645 -0.773048 0.632132 0.148683 -0.794661 0.588564 0.0857736 -0.899241 0.428963 0.146326 -0.959141 0.24215 0.333937 -0.101095 0.937158 0.105756 -0.0988196 0.98947 0.296933 -0.0348329 0.954263 0.0132384 -0.882046 -0.470978 0.298959 -0.861154 -0.411143 0.108592 -0.819414 -0.562822 0.143117 -0.959781 0.241534 0.0595883 -0.998153 0.0118004 0.223304 -0.964748 -0.13927 0.243361 -0.961094 -0.130665 0.107827 -0.972008 -0.208745 0.0837665 -0.79496 -0.600851 0.0301454 -0.659289 -0.751285 0.178762 -0.607978 -0.773568 0.111641 -0.295155 -0.948905 0.341468 -0.271654 -0.89978 0.692775 -0.206275 -0.691024 0.714412 -0.353962 -0.603595 0.412922 -0.518276 -0.748923 0.487269 -0.689735 -0.535569 0.353588 -0.788959 -0.502513 0.447572 -0.863027 -0.23423 0.377664 -0.905524 -0.193383 0.480027 -0.87303 0.0859819 0.412117 -0.899877 0.142764 0.513927 -0.754816 0.407592 0.454268 -0.760184 0.464501 0.542566 -0.495702 0.678161 0.499061 -0.485872 0.717542 0.553203 -0.116147 0.82491 0.546584 -0.113018 0.829743 0.344659 -0.105943 0.932731 0.287814 -0.491456 0.821969 0.346279 -0.50802 0.788674 0.253016 -0.785557 0.564698 0.332859 -0.792188 0.51151 0.223302 -0.947857 0.227383 0.31305 -0.93453 0.169275 0.200946 -0.970026 -0.13664 0.29166 -0.93882 -0.183171 0.187462 -0.856407 -0.481067 0.269283 -0.819489 -0.505891 0.179707 -0.608007 -0.773326 0.463496 -0.524893 -0.713904 0.42502 -0.275573 -0.862217 0.484358 -0.236164 -0.842392 0.870904 -0.0793304 -0.485008 0.89297 -0.143289 -0.4267 0.690165 -0.351342 -0.632638 0.744774 -0.480878 -0.462676 0.503284 -0.683904 -0.528187 0.593141 -0.75543 -0.278406 0.545207 -0.801813 -0.244631 0.633561 -0.773686 -0.00334782 0.588802 -0.806881 0.047481 0.677986 -0.679611 0.280114 0.639888 -0.69209 0.333999 0.718477 -0.455711 0.525469 0.69109 -0.450925 0.564855 0.739777 -0.116709 0.662653 0.726918 -0.109026 0.678014 0.939621 -0.0269695 -0.341152 0.939565 0.042939 -0.339667 0.938416 0.0598883 -0.340276 0.939692 0.0607331 -0.336588 0.93939 0.0619145 -0.337213 0.939415 0.0618324 -0.337161 0.939896 0.0613642 -0.335902 0.939969 0.0615454 -0.335665 0.939946 0.0615044 -0.335737 0.939758 0.0615036 -0.336262 0.939564 0.0615955 -0.336786 0.939625 -0.0416439 -0.339662 0.939836 -0.0415773 -0.339086 0.940953 -0.0389279 -0.33629 0.939692 -0.0407846 -0.339582 0.939968 -0.0416701 -0.33871 0.939975 -0.0416901 -0.338686 0.939692 -0.040303 -0.339638 0.939471 -0.0417283 -0.340079 0.939449 -0.0417844 -0.340133 0.939565 -0.0228713 -0.341605 0.94337 -0.0238959 -0.330881 0.936007 0.00189306 -0.351977 0.939622 -0.00228044 -0.342206 0.939661 0.0183029 -0.341618 0.937285 0.0228357 -0.347815 0.94337 0.0433306 -0.328901 0.939621 0.0470034 -0.338973 0.939692 0.0602037 -0.33668 0.149335 -0.0779241 -0.985711 0.488791 -0.0687524 -0.869687 0.346108 0.128861 -0.929303 0.655061 0.103779 -0.748415 0.850963 0.0721398 -0.520248 0.850963 0.0721397 -0.520247 0.850963 0.0344091 -0.524097 0.850962 0.0344097 -0.524099 0.850962 -0.00350009 -0.525215 0.850962 -0.00350001 -0.525216 0.850962 -0.0413923 -0.523594 0.850962 -0.0413923 -0.523594 0.655067 -0.0595453 -0.753221 0.573443 -0.0570858 -0.817254 0.573332 -0.00545993 -0.819305 0.57333 -0.00545966 -0.819306 0.573331 0.0536764 -0.817564 0.573329 0.0536768 -0.817565 0.57344 0.105092 -0.812479 0.488787 0.119824 -0.864135 0.346109 -0.0739375 -0.935276 0.202119 -0.0714039 -0.976755 0.202081 -0.00652613 -0.979347 0.202089 -0.00652727 -0.979346 0.202088 0.0641617 -0.977263 0.202087 0.0641619 -0.977264 0.202125 0.128773 -0.970857 0.149333 0.13581 -0.979416 -0.707097 -0.144597 0.692174 -0.671179 -0.10805 0.733379 -0.706471 -0.104906 0.699924 -0.70647 -0.0208388 0.707436 -0.706467 -0.0208391 0.707439 -0.706519 0.0617622 0.704994 -0.672819 0.0664033 0.736821 -0.7071 0.103598 0.699484 -0.706475 0.104906 -0.699919 -0.706471 0.104906 -0.699924 -0.70647 0.0208386 -0.707436 -0.706467 0.0208386 -0.707439 -0.706467 -0.0635262 -0.704889 -0.706471 -0.0635256 -0.704885 -0.697438 -0.26682 -0.665122 -0.697429 -0.266826 -0.665129 -0.69743 -0.536248 -0.475425 -0.697435 -0.536244 -0.475423 -0.697436 -0.692299 -0.185215 -0.697442 -0.692294 -0.185215 -0.694741 0.325896 -0.641192 -0.487518 0.87187 -0.0465708 -0.694746 0.325895 -0.641186 -0.70292 0.550631 -0.450231 -0.49462 0.728424 -0.474078 -0.705005 0.646511 -0.291532 -0.70369 0.699434 -0.12495 -0.704402 0.707237 0.0602751 -0.704401 0.671076 0.23125 -0.487515 0.778347 0.395607 -0.694741 0.0383628 0.718237 -0.694742 0.0383623 0.718235 -0.702919 0.321174 0.634628 -0.49463 0.474077 0.728418 -0.705019 0.473094 0.528328 -0.703702 0.588927 0.397452 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.374858 -0.927082 -0.00179856 -0.372318 -0.928104 0.00133444 -0.706975 -0.707237 0.0291309 -0.74795 -0.663115 -0.00212646 -0.855509 -0.517784 0.00441439 -0.939417 -0.342747 0.034693 -0.965444 -0.258291 0 -0.991466 -0.130365 0 -0.0614611 0.99811 0.0376688 0.0532986 0.997868 0.0154251 0.139927 0.990042 -0.0283297 0.451369 0.891888 -1.38936e-05 0.996388 0.0849183 0.02682 0.99964 0.000766459 -6.85633e-05 0.992547 0.12186 0.000103217 0.94544 0.325795 1.23416e-05 0.945345 0.326073 6.16125e-06 0.828897 0.559402 0.0341694 0.880918 0.472033 -0.0536288 0.666131 0.743904 -0.00712104 0.732046 0.681218 0.00710002 0.383949 0.923327 0 0.4531 -0.89146 0.0329122 0.412864 -0.910198 -0.0251244 0.773909 -0.632798 0.00777378 0.735457 -0.677527 -5.00478e-06 0.854456 -0.519524 8.06739e-06 0.911604 -0.41107 0.0188849 0.883438 -0.468168 -0.0358073 0.983784 -0.175748 0.0352491 0.952873 -0.301314 -2.76243e-05 0.994444 -0.105263 0 0.148227 -0.988953 0 0.148227 -0.988953 0 0.0294438 -0.999566 0 0.0294438 -0.999566 0 -0.0897584 -0.995964 0 -0.0897584 -0.995964 0 0.0897576 0.995964 0 0.0897576 0.995964 0 -0.029444 0.999566 0 -0.029444 0.999566 0 -0.148226 0.988953 0 -0.148226 0.988953 -0.87924 -0.107449 -0.464103 -0.887085 -0.172676 -0.428093 -0.95499 -0.207533 -0.211954 -0.960101 -0.203684 -0.191622 -0.978435 -0.145279 -0.14683 -0.978976 -0.143886 -0.144576 -0.991397 -0.0587238 -0.116978 -0.990797 -0.0630736 -0.119762 -0.965171 -0.0816309 0.248558 -0.793204 -0.574451 0.202074 -0.859464 -0.360792 0.362147 -0.839108 -0.388918 0.380318 -0.884193 -0.0832223 0.459649 -0.876483 -0.0923263 0.472496 -0.859291 -0.484599 -0.163652 -0.938545 -0.234274 -0.253473 -0.933195 -0.230306 -0.275875 -0.821646 -0.569065 -0.0326031 -0.847484 -0.529736 0.0339289 -0.891281 -0.452879 0.0227713 -0.947045 -0.282607 0.152446 -0.938318 -0.303957 0.164833 -0.970911 -0.0958308 0.219429 -0.989048 -0.0797214 0.12421 -0.807335 -0.421435 -0.41304 -0.693243 -0.671024 -0.262946 -0.77072 -0.635635 -0.0442636 -0.902136 -0.224653 -0.36835 -0.887851 -0.166849 -0.428816 -0.749526 -0.321894 -0.578442 -0.710139 -0.330372 -0.621737 -0.276006 -0.849589 -0.449466 -0.0376704 -0.704871 -0.708335 -0.0993069 -0.84747 -0.521471 -0.220891 -0.864862 -0.450801 -0.0485195 -0.936748 -0.346626 -0.133707 -0.986395 -0.0956467 -0.146989 -0.324424 -0.934421 -0.0701276 -0.372459 -0.925395 -0.105769 -0.0649136 0.99227 -0.0948739 -0.0687871 0.99311 -0.111688 -0.466451 0.877467 -0.149938 -0.453451 0.878579 -0.0929437 -0.644892 0.758601 -0.157213 -0.773975 0.61339 -0.147184 -0.777248 0.611738 -0.245698 -0.957773 -0.149345 -0.0627196 -0.996578 0.0538306 -0.143391 -0.95085 0.274451 -0.24674 -0.944872 0.215258 -0.0700946 -0.905382 0.418773 -0.354234 -0.805798 -0.474561 -0.457118 -0.873163 -0.169201 -0.363195 -0.910923 -0.195725 -0.490849 -0.857902 0.151894 -0.397288 -0.90689 0.140404 -0.522594 -0.717803 0.460059 -0.442828 -0.765557 0.466719 -0.546597 -0.44954 0.706503 -0.493388 -0.481757 0.724209 -0.553357 -0.0843608 0.828661 -0.546233 -0.0876841 0.833031 -0.176398 -0.860344 -0.478218 -0.30266 -0.946399 -0.112806 -0.18632 -0.97255 -0.139397 -0.325666 -0.914591 0.239718 -0.208476 -0.952144 0.223519 -0.343259 -0.74904 0.566667 -0.241868 -0.788818 0.565036 -0.351519 -0.455904 0.817671 -0.282651 -0.485475 0.827298 -0.34503 -0.0680152 0.936124 -0.333666 -0.0727194 0.939882 -0.879552 -0.106238 -0.463791 -0.76349 -0.168372 -0.623485 -0.693961 -0.234695 -0.680688 -0.651411 -0.220086 -0.726103 -0.484418 -0.264548 -0.833879 -0.91828 -0.236642 -0.317431 -0.901027 -0.249153 -0.355067 -0.75873 -0.513662 -0.4006 -0.805287 -0.460652 -0.373245 -0.700526 -0.595849 -0.392718 -0.63382 -0.431692 -0.641805 -0.461119 -0.521826 -0.717682 -0.425665 -0.307777 -0.85093 -0.341481 -0.302759 -0.889791 -0.209215 -0.634437 -0.744123 -0.179196 -0.633117 -0.753029 -0.424088 -0.56627 -0.706745 -0.486861 -0.705774 -0.514635 -0.502658 -0.700395 -0.506737 -0.601386 -0.767804 -0.220934 -0.531853 -0.810032 -0.246942 -0.642827 -0.764 0.0554747 -0.5751 -0.816779 0.0461655 -0.685237 -0.650454 0.327658 -0.629212 -0.700096 0.337576 -0.721675 -0.417849 0.551894 -0.685621 -0.449747 0.572409 -0.739938 -0.084403 0.667359 -0.725684 -0.0945794 0.681497 0.698076 -0.23838 -0.675177 0.698069 -0.23838 -0.675185 0.69807 -0.507726 -0.504889 0.609321 -0.543117 -0.577712 0.706901 -0.586997 -0.394621 0.698068 -0.676511 -0.234595 0.698074 -0.676505 -0.234591 0.698073 -0.711297 0.0821651 0.698065 -0.711305 0.0821634 0.698066 -0.605213 0.38265 0.698069 -0.60521 0.38265 0.706902 -0.481583 0.518042 0.698072 -0.0781746 0.711748 0.698068 -0.0781761 0.711751 0.700599 -0.357357 0.617621 0.796091 -0.268727 0.542241 0.684044 -0.461223 0.565117 0.696946 0.286919 -0.657225 0.696944 0.28692 -0.657226 0.696949 0.555929 -0.452996 0.696946 0.555932 -0.452997 0.696948 0.701624 -0.14828 0.696947 0.701625 -0.14828 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706181 0.0302781 0.707384 0.706172 0.0302788 0.707393 0.706171 -0.0718648 0.704384 0.706174 -0.0718647 0.704382 -0.698657 -0.556048 -0.45021 -0.698658 -0.556047 -0.45021 -0.698658 -0.69383 -0.17458 -0.698656 -0.693831 -0.174579 -0.698076 -0.0648966 -0.713077 -0.698065 -0.0649015 -0.713087 -0.698064 0.250928 -0.670628 -0.618523 0.250444 -0.744787 -0.706892 0.368951 -0.603473 -0.69806 0.517053 -0.495347 -0.698067 0.51705 -0.49534 -0.698067 0.680766 -0.221947 -0.698067 0.680766 -0.221947 -0.698067 0.709648 0.0954054 -0.698061 0.367872 0.614313 -0.698064 0.367869 0.614311 -0.700599 0.582361 0.412332 -0.634903 0.64521 0.424973 -0.706897 0.653745 0.270026 -0.698064 0.709651 0.0954047 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.778665 -0.62744 -0.00144216 -0.777192 -0.629262 0.00122295 -0.96178 -0.273819 0.0167217 -0.969637 -0.243978 0 -0.998032 -0.062702 0 0.445833 0.895116 0.0254423 0.513594 0.857656 0.00385939 0.616581 0.787282 -0.0105378 0.816094 0.577823 0.00709884 0.794173 0.607651 -0.00161436 0.92426 0.381761 -0.0200921 0.974654 0.222814 0.0193194 0.990899 0.133215 0.00123012 0.999392 -0.0348349 -0.00305379 0.981668 -0.190574 0.053873 0.92122 -0.385293 0.0129835 0.950667 -0.309942 -0.000755149 0.865096 -0.501606 0 -0.0906402 -0.995884 0.00483596 -0.0981865 -0.995156 -0.00428181 0.318723 -0.947838 0.00777296 0.298161 -0.954484 -4.59334e-06 0.480179 -0.87717 5.25261e-07 0.521617 -0.85318 -0.000890206 0.529839 -0.848098 0.00553024 0.722093 -0.691774 0.0432329 0.67485 -0.736688 0.00224204 0.808694 -0.588225 0 -0.366109 -0.930572 0 -0.366109 -0.930572 0 -0.474284 -0.880372 0 -0.474284 -0.880372 0 -0.575714 -0.817651 0 -0.575714 -0.817651 0 0.575714 0.817651 0 0.575714 0.817651 0 0.474284 0.880372 0 0.474284 0.880372 0 0.366108 0.930572 0 0.366108 0.930572 -0.87924 -0.325108 -0.348199 -0.887085 -0.363587 -0.284402 -0.954989 -0.285708 -0.0797921 -0.960101 -0.272205 -0.0641052 -0.978436 -0.199228 -0.0545167 -0.978976 -0.196898 -0.0532637 -0.991397 -0.109348 -0.0719444 -0.990797 -0.114504 -0.0721797 -0.965171 0.053586 0.256073 -0.793206 -0.396451 0.462224 -0.859466 -0.131381 0.494021 -0.839105 -0.146657 0.523827 -0.884192 0.157753 0.439681 -0.876484 0.156292 0.455355 -0.859292 -0.501501 0.100573 -0.938545 -0.329624 -0.102377 -0.933194 -0.33739 -0.123765 -0.821647 -0.509126 0.256296 -0.847485 -0.441799 0.29425 -0.891282 -0.380818 0.246159 -0.947044 -0.168523 0.273328 -0.938319 -0.180817 0.294725 -0.970911 0.0267212 0.237945 -0.989048 -0.00693673 0.147428 -0.807336 -0.571492 -0.146986 -0.693243 -0.712597 0.107794 -0.77072 -0.572608 0.279483 -0.902135 -0.378731 -0.206675 -0.88785 -0.358905 -0.287939 -0.749527 -0.56799 -0.339996 -0.710138 -0.596981 -0.373253 -0.0119392 -0.903951 0.427468 -0.276016 -0.960495 0.0355482 -0.0335986 -0.960694 -0.275568 -0.0889133 -0.993654 -0.0688904 -0.188286 -0.981048 0.0457612 0.0533218 -0.983568 0.172483 -0.267917 -0.848536 0.456297 -0.146982 -0.748177 -0.647014 -0.0953358 -0.773845 -0.626159 -0.093756 -0.176196 0.97988 -0.149945 0.0465883 0.987596 -0.111694 0.0347741 0.993134 -0.0948779 0.436983 0.894452 -0.10577 0.439917 0.891788 -0.110867 -0.231372 0.966528 -0.174406 -0.364308 0.914802 -0.144203 -0.376131 0.915276 -0.143394 -0.686236 0.713105 -0.266608 -0.714261 0.64711 -0.0669701 -0.582154 0.810316 -0.354223 -0.935126 -0.0080784 -0.457113 -0.840784 0.290053 -0.363193 -0.886745 0.285962 -0.490849 -0.667019 0.560493 -0.397293 -0.715187 0.575036 -0.522596 -0.391606 0.757323 -0.442824 -0.429634 0.78697 -0.546593 -0.0360626 0.836621 -0.49339 -0.0551078 0.868061 -0.553359 0.341274 0.75982 -0.546233 0.340581 0.765267 -0.176403 -0.984187 0.0160254 -0.302658 -0.876009 0.375507 -0.186323 -0.91195 0.365554 -0.325668 -0.672201 0.664895 -0.208475 -0.712823 0.669643 -0.343264 -0.36535 0.865268 -0.241864 -0.400618 0.883746 -0.351516 0.0140107 0.936077 -0.282645 -0.0067855 0.959201 -0.345025 0.409159 0.844717 -0.333671 0.406966 0.850319 -0.879552 -0.3239 -0.348535 -0.763486 -0.457561 -0.455771 -0.693959 -0.543597 -0.472147 -0.651406 -0.553653 -0.518786 -0.484427 -0.646037 -0.589886 -0.918284 -0.363646 -0.156573 -0.901026 -0.393308 -0.18292 -0.758732 -0.645142 -0.0901 -0.805288 -0.585559 -0.0929148 -0.700528 -0.712377 -0.0421806 -0.633825 -0.694755 -0.339974 -0.461116 -0.810756 -0.36062 -0.425662 -0.692011 -0.583038 -0.341501 -0.707092 -0.619191 -0.193427 -0.923354 -0.331668 -0.179204 -0.924806 -0.335588 -0.424087 -0.843775 -0.328927 -0.486861 -0.868536 -0.0928025 -0.502662 -0.859926 -0.0886511 -0.60139 -0.775402 0.192568 -0.531852 -0.82498 0.191158 -0.642825 -0.633907 0.430044 -0.575096 -0.684271 0.448372 -0.685235 -0.399482 0.608989 -0.629213 -0.437511 0.642397 -0.721678 -0.0859197 0.686876 -0.685623 -0.103288 0.720592 -0.73994 0.260585 0.620149 -0.725682 0.25884 0.637486 -0.146155 -0.100286 -0.984165 -0.826271 0.465021 -0.317855 -0.651418 -0.128714 -0.747722 -0.992269 0.0233037 -0.121902 -0.992328 -0.02059 -0.12191 -0.976263 0.0795453 -0.201451 -0.978909 0.0629538 -0.194356 -0.963217 0.0914075 -0.252702 -0.851017 -0.177122 -0.494366 -0.880972 -0.055663 -0.469883 -0.902082 0.0171905 -0.431222 -0.895845 0.0131669 -0.444171 -0.919311 0.0639049 -0.38831 -0.740531 0.391746 -0.546031 -0.783611 0.381983 -0.489941 -0.707954 0.236217 -0.665584 -0.918518 0.0639723 -0.390169 -0.938742 0.0947435 -0.331341 -0.785901 0.496214 -0.36896 -0.847486 0.488752 -0.207094 -0.793261 0.604027 -0.0767394 -0.856963 0.494348 0.145719 -0.84421 0.505417 0.178502 -0.884165 0.287367 0.368337 -0.877675 0.286556 0.384151 -0.945947 0.0888853 -0.311902 -0.960044 0.0976977 -0.262241 -0.891348 0.414936 -0.182557 -0.944831 0.327545 -0.00301751 -0.941849 0.335416 0.0204041 -0.970926 0.18402 0.153099 -0.965173 0.184393 0.185582 -0.115171 0.615667 0.779545 -0.0771136 0.794702 0.602082 -0.146474 0.808156 0.570465 -0.0440766 0.974355 0.220656 -0.0575899 0.975 0.214611 -0.0997403 0.994029 -0.0442486 -0.181838 0.965957 -0.184018 -0.33401 0.482142 0.809924 -0.105776 0.502794 0.85791 -0.278873 0.431783 0.857784 -0.0122547 0.602973 -0.797668 -0.315855 0.618141 -0.719818 -0.112678 0.519329 -0.847113 -0.136046 0.969979 -0.201575 -0.0636799 0.916177 -0.395683 -0.202702 0.824605 -0.528146 -0.248187 0.825835 -0.50636 -0.108775 0.797752 -0.593094 -0.0842128 0.473199 -0.876921 -0.032886 0.295811 -0.95468 -0.190439 0.230339 -0.954294 -0.0911641 -0.128057 -0.987568 -0.341476 -0.128173 -0.93111 -0.694 -0.0952619 -0.713645 -0.714757 0.0715868 -0.6957 -0.412192 0.155998 -0.897643 -0.486904 0.400361 -0.776296 -0.354182 0.50776 -0.785325 -0.447648 0.685738 -0.573911 -0.378517 0.742504 -0.552642 -0.480135 0.828874 -0.287121 -0.413115 0.877271 -0.244401 -0.514077 0.855993 0.054779 -0.455182 0.884011 0.106461 -0.542688 0.733514 0.409203 -0.499638 0.73987 0.450505 -0.553285 0.449673 0.701192 -0.546678 0.448571 0.707055 -0.344674 0.48508 0.803677 -0.288259 0.788669 0.543054 -0.346234 0.790927 0.504536 -0.253713 0.949069 0.186809 -0.33284 0.933451 0.133744 -0.224033 0.956336 -0.187697 -0.313036 0.91972 -0.236906 -0.201531 0.824888 -0.528153 -0.291643 0.77621 -0.558966 -0.187831 0.578065 -0.794078 -0.269301 0.532868 -0.802203 -0.179214 0.228382 -0.956935 -0.463837 0.181307 -0.86717 -0.425687 -0.106256 -0.89861 -0.484446 -0.137277 -0.863983 -0.875378 -0.122603 -0.467634 -0.889598 -0.0441482 -0.454606 -0.689728 0.0530136 -0.722125 -0.7457 0.24619 -0.61913 -0.50267 0.399088 -0.766845 -0.593281 0.569182 -0.569253 -0.54628 0.626677 -0.555747 -0.633761 0.701017 -0.326989 -0.589992 0.752749 -0.292024 -0.678233 0.734242 -0.0298015 -0.640943 0.767415 0.016339 -0.718701 0.633309 0.287034 -0.691732 0.644234 0.326296 -0.739909 0.382582 0.553322 -0.727056 0.381236 0.571007 -0.572886 -0.38874 -0.721584 -0.850726 -0.191415 -0.489516 -0.879516 -0.274774 -0.388525 -0.654677 -0.435188 -0.61807 -0.764997 -0.370779 -0.526594 -0.845144 -0.304939 -0.439025 -0.851115 -0.277036 -0.445931 -0.850698 -0.24931 -0.462772 -0.850698 -0.24931 -0.462772 -0.851115 -0.220004 -0.476656 -0.345814 -0.540195 -0.767204 -0.4884 -0.50238 -0.713498 -0.149207 -0.56927 -0.808498 -0.201915 -0.560997 -0.802816 -0.201875 -0.464519 -0.862246 -0.844347 -0.19616 -0.498597 -0.654685 -0.276742 -0.703421 -0.573007 -0.304249 -0.760983 -0.488416 -0.319471 -0.812028 -0.345784 -0.343525 -0.873169 -0.573004 -0.468123 -0.672702 -0.572883 -0.388741 -0.721585 -0.201874 -0.464519 -0.862246 -0.201914 -0.361816 -0.910121 -0.149217 -0.36201 -0.920154 -0.340893 0.344179 0.874833 -0.994035 -0.0517262 -0.0960149 -0.994036 -0.0397132 -0.10156 -0.994251 -0.0392025 -0.0996445 -0.991754 -0.0740001 -0.104635 -0.996675 -0.0429951 -0.0692071 -0.658678 0.356863 0.662413 -0.93179 0.172164 0.319573 -0.994046 -0.0611462 -0.0901913 -0.993745 0.0642901 0.0913071 -0.971837 0.135671 0.192685 -0.994056 -0.0456233 -0.0988497 -0.994035 -0.0517263 -0.0960149 -0.93179 0.172164 0.319572 -0.931639 0.214508 0.293318 -0.558466 0.290653 0.77694 -0.739295 0.246531 0.62663 -0.93179 0.132896 0.337795 -0.888072 0.157459 0.431897 -0.971843 0.0862667 0.219272 -0.237285 0.460739 0.855228 -0.237286 0.355652 0.903995 -0.10813 0.350346 0.930358 -0.887837 0.26492 0.376249 -0.739297 0.387674 0.55059 -0.658467 0.438715 0.611516 -0.558106 0.47771 0.678462 -0.34089 0.541231 0.768676 -0.658679 0.275469 0.700185 -0.658679 0.356863 0.662413 -0.237287 0.460738 0.855228 -0.23719 0.564712 0.790469 -0.108042 0.572344 0.812865 -0.939508 -0.19778 -0.279657 -0.93961 -0.2147 -0.266529 -0.939482 -0.215026 -0.266714 -0.939573 -0.214663 -0.26669 -0.93969 -0.213663 -0.267077 -0.939848 -0.214312 -0.266001 -0.939867 -0.214313 -0.265932 -0.939727 -0.214499 -0.266278 -0.939514 -0.124734 -0.318989 -0.940466 -0.105158 -0.32321 -0.939696 -0.104858 -0.325539 -0.939902 -0.104095 -0.32519 -0.93969 -0.105301 -0.325414 -0.939538 -0.104538 -0.3261 -0.939493 -0.104449 -0.326258 -0.939513 -0.104476 -0.32619 -0.93975 -0.104385 -0.325537 -0.939508 -0.124741 -0.319006 -0.939511 -0.124737 -0.318998 -0.939694 -0.143326 -0.310538 -0.939693 -0.14333 -0.310536 -0.939498 -0.162469 -0.301576 -0.939498 -0.162468 -0.301576 -0.939694 -0.180486 -0.290519 -0.939694 -0.180485 -0.290519 -0.939511 -0.197776 -0.279649 -0.939515 -0.197769 -0.279641 -0.939697 -0.213837 -0.266914 0 -0.985751 0.168209 0.0148611 -0.980375 0.19658 -0.0092399 -0.86801 0.49646 0.032048 -0.794119 0.606917 -5.13144e-05 -0.224385 0.9745 0.00046029 -0.368452 0.929647 0.0292584 -0.446937 0.894087 -0.00285212 -0.578494 0.815682 0.00336318 -0.722327 0.691544 0.00141587 -0.169988 0.985445 0.0215473 -0.0088717 0.999729 -0.00415815 0.0555911 0.998445 0.00518609 0.431176 0.902253 0 0.440795 0.897608 -0.697823 -0.702291 0.14082 -0.697827 -0.702288 0.140818 -0.697828 -0.569092 0.434937 -0.69783 -0.569091 0.434936 -0.69783 -0.320262 0.640676 -0.69783 -0.320262 0.640676 -0.697831 -0.00635594 0.716234 -0.697833 -0.0063565 0.716233 -0.697832 0.308839 0.646258 -0.697824 0.308845 0.646264 0 0.98441 0.175889 -0.012157 0.974036 0.226066 -0.000277445 0.931634 0.363397 0.00108247 0.810803 0.585319 -0.00248192 0.81723 0.576307 0.000124601 0.67774 0.735302 -0.00291341 0.521241 0.853404 0 0.512767 0.858528 0.700047 0.695607 0.161445 0.700052 0.372217 0.609411 0.700048 0.372218 0.609415 0.702984 0.556674 0.442637 0.763181 0.523929 0.378224 0.706716 0.629767 0.322408 0.700045 0.695609 0.161446 0.694741 -0.563595 -0.446874 0.458494 -0.826352 0.326995 0.69474 -0.563595 -0.446874 0.702915 -0.688227 -0.179592 0.466758 -0.874873 -0.12936 0.705014 -0.709178 0.00463955 0.703696 -0.687815 0.178109 0.694742 0.264652 0.6688 0.694736 0.264652 0.668806 0.702913 -0.0272624 0.710754 0.782472 0.0162422 0.622474 0.561443 -0.244658 0.790522 0.701774 -0.166371 0.692701 0.703699 -0.369535 0.606837 0.458501 -0.552141 0.696359 0.704399 -0.513502 0.490039 0.704398 -0.617674 0.349717 0.696418 0.701222 -0.152611 0.696414 0.701225 -0.152611 0.703789 0.588511 -0.397914 0.504583 0.659345 -0.557369 0.696417 -0.0758955 -0.713613 0.696413 -0.0758949 -0.713616 0.703788 0.192417 -0.683856 0.504586 0.321461 -0.801284 0.705062 0.351144 -0.616104 0.705062 0.474235 -0.527246 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706179 0.379914 0.597475 0.706179 0.379914 0.597474 0.70618 0.289952 0.64594 0.706182 0.289951 0.645938 0 0.387438 0.921896 0.0420195 0.409156 0.911496 0 0.452953 0.891534 0 0.536577 0.843851 0.0629302 0.555632 0.829043 0 0.495339 0.868699 0.706178 -0.379915 -0.597476 0.70618 -0.379914 -0.597474 0.70618 -0.289952 -0.64594 0.706179 -0.289952 -0.64594 0 -0.146851 -0.989159 -0.015902 -0.105744 -0.994266 -2.56903e-05 0.0958867 -0.995392 -5.78224e-06 0.270853 -0.962621 2.41308e-05 0.270964 -0.96259 -2.9566e-05 0.495166 -0.868799 0.00193298 0.503675 -0.863891 -0.00175611 0.668741 -0.743493 -8.64898e-06 0.676008 -0.736894 1.38681e-05 0.827197 -0.561912 -0.000492231 0.828411 -0.56012 0.000221742 0.918678 -0.395008 -0.017633 0.976975 -0.212624 0 0.987233 -0.159284 0 0.47307 0.881025 -0.0262993 0.367823 0.929524 -0.0108355 0.286706 0.957957 0.0197309 -0.0383214 0.999071 -0.0045958 -0.870194 0.492689 6.75088e-05 -0.856296 0.516486 -8.61748e-05 -0.723441 0.690386 0.00524334 -0.705817 0.708375 -0.00480616 -0.520101 0.854091 -0.0129963 -0.556721 0.830598 0.0208392 -0.29559 0.955088 0.00416598 -0.34913 0.937065 -0.00493609 0.036065 0.999337 0 -0.783576 -0.621296 -0.0272096 -0.748264 -0.662843 0.0218247 -0.967368 -0.252434 -0.00552138 -0.947816 -0.31877 4.25568e-06 -0.993267 -0.115846 -7.13615e-06 -0.999979 0.00654203 -0.0147149 -0.997669 -0.0666377 0.0291929 -0.967657 0.250573 -0.0251793 -0.993185 0.113793 0.00322801 -0.938892 0.344198 0.994042 -0.0606814 -0.090541 0.97185 0.131167 0.195711 0.658911 0.356767 0.662234 0.108087 0.385168 0.916495 0.558299 0.321434 0.764842 0.34105 0.364209 0.866624 0.237326 0.368666 0.898756 0.237622 0.43998 0.865999 0.153988 0.468627 0.869871 0.237619 0.481152 0.843819 0.237424 0.540816 0.806937 0.887897 0.178238 0.424111 0.739448 0.260828 0.620633 0.108168 0.56857 0.815493 0.34105 0.523356 0.780886 0.658911 0.418788 0.624863 0.5586 0.476228 0.679097 0.739456 0.374797 0.559225 0.971845 0.0912881 0.217217 0.931702 0.133153 0.337936 0.931867 0.17207 0.319399 0.658689 0.283806 0.696838 0.658911 0.356767 0.662234 0.931867 0.17207 0.319399 0.931867 0.201984 0.301374 0.888089 0.26787 0.373556 0.994042 -0.042229 -0.100483 0.994042 -0.0422289 -0.100482 0.994053 -0.0493271 -0.0970899 0.994978 -0.0474736 -0.088121 0.994053 -0.053943 -0.0946029 0.994042 -0.0606815 -0.0905412 0 -0.566695 -0.823928 -0.126161 -0.501719 -0.855781 0 -0.536577 -0.843851 0 -0.442189 -0.896922 -0.0635009 -0.408691 -0.910461 0 -0.376313 -0.926493 0.891416 0.408803 -0.195596 0.893721 -0.0286141 -0.447711 0.900887 0.0250416 -0.433331 0.982611 0.0557851 -0.177096 0.968947 0.074599 -0.235747 0.959187 0.0891652 -0.268347 0.955084 0.0818879 -0.284797 0.937215 0.0859554 -0.337994 0.963018 0.20668 0.172859 0.97139 0.177898 0.157334 0.87644 0.307233 0.370757 0.884047 0.294014 0.363341 0.858962 0.49141 0.143874 0.839076 0.523395 0.148353 0.946585 0.322443 -0.0026423 0.938296 0.345833 -0.000295567 0.978164 0.0535202 -0.200826 0.993506 -0.0122652 -0.11312 0.993503 -0.00594241 -0.113653 0.712671 0.0220805 -0.701151 0.884954 -0.0582958 -0.462015 0.885792 -0.0636135 -0.459702 0.792145 0.602231 -0.0991159 0.849347 0.48172 -0.215767 0.805188 0.484992 -0.341255 0.81278 0.440723 -0.380989 0.759739 0.390582 -0.519849 0.771367 0.336386 -0.54022 0.722823 0.239739 -0.648114 0.182175 0.800928 -0.570374 0.133805 0.820703 -0.555467 0.0550205 0.670551 -0.73982 0.275266 0.529036 -0.802714 0.329675 0.448568 -0.830723 0.0482189 0.573302 -0.817924 0.095719 0.263135 -0.959999 0.146933 -0.161759 -0.97583 0.123005 -0.148718 -0.9812 0.158575 0.0863635 -0.983563 0.106261 0.512007 0.852384 0.166734 0.528891 0.83215 0.10777 0.677596 0.727495 0.0859306 0.829898 0.551257 0.073667 0.912568 -0.402236 0.156269 0.971894 -0.176073 0.0282446 0.979608 -0.198925 0.141808 0.97703 0.159066 0.170935 0.97113 0.166397 0.0918654 0.930796 0.353806 0.151874 0.814045 0.560594 0.353637 0.480009 -0.802827 0.456006 0.68442 -0.568883 0.364129 0.707859 -0.605265 0.489616 0.825661 -0.280286 0.398061 0.8641 -0.308023 0.521629 0.851226 0.0575956 0.4432 0.895276 0.0453278 0.54614 0.734122 0.40348 0.493427 0.76917 0.406087 0.553286 0.47095 0.687081 0.546209 0.475655 0.689498 0.177316 0.528728 -0.830064 0.301515 0.775491 -0.554709 0.187413 0.788967 -0.585156 0.324419 0.917364 -0.230641 0.209396 0.9436 -0.256459 0.34232 0.929686 0.136017 0.242335 0.962644 0.120788 0.351093 0.792957 0.49795 0.282723 0.821622 0.49498 0.344989 0.508478 0.788944 0.333629 0.514002 0.790249 0.484349 -0.166348 -0.858915 0.687667 -0.1509 -0.710171 0.647364 -0.109892 -0.754217 0.870205 -0.191995 -0.453742 0.850011 -0.131801 -0.510009 0.933081 0.0714627 -0.352495 0.918216 0.0571713 -0.391933 0.916084 0.0565981 -0.396973 0.902775 -0.00130027 -0.430111 0.738159 0.191166 -0.646975 0.697719 0.0515217 -0.714516 0.461103 0.116805 -0.879625 0.424996 -0.140006 -0.894302 0.341466 -0.160328 -0.926119 0.222905 0.203049 -0.953459 0.179686 0.19707 -0.963782 0.423352 0.157455 -0.892178 0.487239 0.376506 -0.787935 0.503308 0.374601 -0.778688 0.600305 0.567405 -0.563636 0.532651 0.594739 -0.602136 0.64164 0.697203 -0.319696 0.575711 0.73994 -0.347916 0.684261 0.728767 -0.0261834 0.62949 0.776128 -0.0369802 0.721185 0.632294 0.283014 0.685628 0.66856 0.287995 0.73982 0.394237 0.5452 0.72568 0.409005 0.553266 0.146444 -0.737588 -0.65918 0.824719 -0.531638 0.192873 0.651396 -0.53519 -0.537824 0.942262 -0.327498 -0.0699043 0.971801 -0.224757 -0.0713186 0.978816 -0.197351 -0.0545115 0.98931 -0.123594 -0.0773958 0.993672 -0.0871774 -0.0708207 0.851107 -0.309355 -0.424165 0.873457 -0.35553 -0.332672 0.88941 -0.355991 -0.286742 0.901406 -0.36211 -0.237368 0.895301 -0.371059 -0.246478 0.918228 -0.355548 -0.174479 0.74174 -0.670647 0.00736793 0.782191 -0.622542 0.024886 0.708895 -0.67958 -0.188784 0.911964 -0.368299 -0.180767 0.938587 -0.323316 -0.120501 0.786962 -0.58572 0.193968 0.849348 -0.445184 0.283585 0.792188 -0.413977 0.448399 0.856722 -0.166851 0.488045 0.843568 -0.148372 0.516119 0.88401 0.13431 0.447757 0.87748 0.14681 0.456591 0.92187 -0.367152 -0.123915 0.959989 -0.262274 -0.0981513 0.89144 -0.388178 0.233779 0.944652 -0.191745 0.266206 0.941309 -0.178988 0.286182 0.970892 0.020177 0.238665 0.965072 0.0442022 0.258228 0.115177 0.279653 0.953168 0.0767977 0.030169 0.99659 0.146659 -0.00175841 0.989186 0.0529651 -0.353415 0.933966 0.148671 -0.393911 0.907045 0.0857604 -0.564282 0.821116 0.146315 -0.709568 0.689279 0.333936 0.381033 0.862149 0.105763 0.409158 0.906313 0.296925 0.446966 0.843834 0.143122 -0.710426 0.689066 0.0595916 -0.858528 0.509293 0.223303 -0.905131 0.361764 0.116194 -0.937046 0.329309 0.0132378 -0.999363 0.0331428 0.298955 -0.951353 0.0745149 0.108592 -0.991044 -0.0777095 0.0837794 -0.988883 -0.122846 0.0301517 -0.946603 -0.320987 0.178762 -0.913309 -0.365939 0.111639 -0.730061 -0.674201 0.341459 -0.68515 -0.64341 0.692776 -0.524151 -0.495305 0.714413 -0.608335 -0.34575 0.412918 -0.823302 -0.389452 0.487267 -0.865115 -0.118945 0.353596 -0.934512 -0.0407125 0.447579 -0.864515 0.228662 0.37767 -0.880896 0.285286 0.480033 -0.713075 0.510971 0.412116 -0.707934 0.573577 0.513926 -0.449895 0.730393 0.454268 -0.426089 0.782361 0.542568 -0.0902099 0.835154 0.499062 -0.0620063 0.864345 0.553204 0.311868 0.772466 0.54658 0.316998 0.775089 0.344664 0.374617 0.860738 0.287817 -0.0146313 0.957574 0.346275 -0.0456195 0.937023 0.253015 -0.39796 0.881823 0.332866 -0.430301 0.839072 0.223308 -0.707178 0.670845 0.313045 -0.724689 0.613863 0.200941 -0.908387 0.366681 0.291655 -0.904628 0.310782 0.187454 -0.982205 0.0115866 0.269276 -0.962645 -0.0283706 0.179695 -0.913214 -0.365718 0.463496 -0.811522 -0.355814 0.425018 -0.669761 -0.608917 0.48435 -0.625724 -0.611452 0.870903 -0.311207 -0.380366 0.89297 -0.337444 -0.297887 0.69017 -0.620586 -0.372207 0.744778 -0.647786 -0.160247 0.503288 -0.85637 -0.115466 0.59314 -0.793424 0.13661 0.545207 -0.816706 0.18905 0.633561 -0.671706 0.383943 0.588805 -0.67504 0.444556 0.677989 -0.448503 0.582389 0.639892 -0.432367 0.635293 0.71848 -0.131924 0.682922 0.691091 -0.108084 0.71464 0.739777 0.230255 0.632229 0.726919 0.244587 0.64169 0.939621 -0.193932 -0.281962 0.939566 -0.132647 -0.315628 0.938417 -0.118274 -0.324629 0.939692 -0.115699 -0.321858 0.939391 -0.11499 -0.322989 0.939414 -0.115032 -0.322907 0.939896 -0.114804 -0.321582 0.939965 -0.114543 -0.321473 0.939947 -0.114602 -0.321507 0.939757 -0.114868 -0.321967 0.939563 -0.11505 -0.322466 0.93962 -0.205906 -0.273343 0.939837 -0.20555 -0.272865 0.940955 -0.201855 -0.27177 0.939692 -0.205112 -0.273694 0.939967 -0.205443 -0.272497 0.939975 -0.205449 -0.272465 0.939692 -0.204725 -0.273981 0.939471 -0.206176 -0.273652 0.939449 -0.206252 -0.27367 0.939565 -0.190609 -0.284403 0.94337 -0.186135 -0.274603 0.936007 -0.174349 -0.305766 0.939622 -0.173078 -0.295219 0.93966 -0.154958 -0.305002 0.937285 -0.154131 -0.312634 0.94337 -0.126925 -0.306501 0.939621 -0.12878 -0.317061 0.939693 -0.1162 -0.321676 0.149347 -0.560339 -0.814688 0.488782 -0.494388 -0.7188 0.34611 -0.353054 -0.86923 0.655057 -0.284334 -0.700039 0.850962 -0.19765 -0.486619 0.850963 -0.197649 -0.486617 0.850963 -0.232249 -0.471086 0.850962 -0.23225 -0.471087 0.850962 -0.265639 -0.4531 0.850962 -0.265639 -0.4531 0.850962 -0.297644 -0.43275 0.850962 -0.297643 -0.432749 0.655066 -0.428178 -0.622536 0.57344 -0.458066 -0.679222 0.573329 -0.414382 -0.706811 0.57333 -0.414382 -0.70681 0.57333 -0.362297 -0.73487 0.573329 -0.362297 -0.73487 0.57344 -0.315227 -0.756173 0.488785 -0.328296 -0.808276 0.346103 -0.531671 -0.773006 0.20213 -0.550214 -0.81019 0.202091 -0.495325 -0.844874 0.202092 -0.495325 -0.844874 0.202092 -0.433066 -0.878415 0.202087 -0.433066 -0.878416 0.202125 -0.373907 -0.905174 0.149344 -0.372093 -0.916102 -0.707094 0.220865 0.671742 -0.671175 0.273117 0.689152 -0.706471 0.25911 0.658605 -0.706471 0.335671 0.623076 -0.70647 0.335671 0.623077 -0.706522 0.405983 0.57966 -0.672812 0.425921 0.604909 -0.707097 0.439465 0.553971 -0.70648 -0.259107 -0.658597 -0.706471 -0.259111 -0.658605 -0.706471 -0.335671 -0.623076 -0.70647 -0.335671 -0.623077 -0.70647 -0.407458 -0.578687 -0.70647 -0.407458 -0.578687 0.0340209 -0.978771 0.202113 0.0129853 -0.988101 0.153255 0 -1 0.000556224 2.60571e-06 -0.283879 0.95886 0.0270241 -0.401454 0.91548 0.0339808 -0.421017 0.906416 -0.00635911 -0.553695 0.832695 1.68242e-06 -0.637486 0.770462 -5.54971e-06 -0.712197 0.701979 0.0273495 -0.797904 0.602163 -0.0167716 -0.867447 0.497247 0.0102813 -0.952174 0.305383 -1.77482e-06 -0.117248 0.993103 0.0300932 0.0313102 0.999057 -0.00808332 0.137725 0.990438 1.45919e-06 0.283769 0.958893 -5.6295e-07 0.328652 0.944451 0.0102313 0.497549 0.867375 -0.00702988 0.532061 0.846677 0.00814257 0.821257 0.570501 0 0.830754 0.55664 -0.697344 0.588644 0.408913 -0.697343 0.588645 0.408913 -0.697343 0.342045 0.629856 -0.64234 0.381351 0.664808 -0.707006 0.200684 0.678136 -0.697345 0.0224504 0.716384 -0.697343 0.0224513 0.716386 -0.697343 -0.301933 0.650038 -0.697344 -0.701928 0.144945 -0.697344 -0.701927 0.144945 -0.699222 -0.570639 0.43065 -0.650496 -0.595415 0.471525 -0.707004 -0.450836 0.544878 -0.697343 -0.301933 0.650038 0 0.987023 0.160579 -0.00725972 0.980738 0.195195 -4.3103e-05 0.946846 0.321686 0.000319586 0.862561 0.505953 0 0.863177 0.504901 0.702127 0.698355 0.138992 0.702129 0.698353 0.138991 0.702129 0.614186 0.360264 0.702132 0.614185 0.360262 0.994042 -0.0978222 -0.0480702 0.97185 0.211449 0.103907 0.658911 0.640086 0.395128 0.108082 0.791813 0.601124 0.558295 0.660792 0.501657 0.341056 0.748724 0.568413 0.237325 0.768652 0.594013 0.237621 0.814034 0.529986 0.15399 0.840779 0.519017 0.23762 0.838599 0.490192 0.237425 0.871829 0.42842 0.887897 0.366414 0.278172 0.739449 0.5362 0.407069 0.108169 0.900142 0.421952 0.341049 0.843683 0.414589 0.658911 0.675113 0.331753 0.558604 0.751972 0.35 0.739455 0.604197 0.296905 0.971845 0.187667 0.142472 0.931702 0.284282 0.226086 0.931867 0.308718 0.190573 0.658688 0.594203 0.461577 0.65891 0.640086 0.395129 0.931867 0.308718 0.190573 0.931867 0.325611 0.160006 0.888089 0.41876 0.189575 0.994042 -0.0868122 -0.0659056 0.994042 -0.0868122 -0.0659057 0.994053 -0.0912632 -0.0594184 0.994978 -0.0851738 -0.0525782 0.994053 -0.0940173 -0.054957 0.994042 -0.0978222 -0.0480702 0 -0.902736 -0.430196 -0.12616 -0.862392 -0.490268 0 -0.886615 -0.462508 0 -0.831408 -0.555663 -0.0635015 -0.809168 -0.584137 0 -0.789143 -0.61421 0.891416 0.256237 -0.373792 0.893719 -0.248641 -0.373422 0.900886 -0.194976 -0.387799 0.982611 -0.0402361 -0.181261 0.968946 -0.0532692 -0.241465 0.959187 -0.0569542 -0.276978 0.955083 -0.0714834 -0.287586 0.937215 -0.0945584 -0.335688 0.963017 0.265422 0.0463603 0.97139 0.23273 0.0473056 0.87644 0.451449 0.167469 0.884047 0.436295 0.167656 0.858963 0.497509 -0.121106 0.839075 0.527452 -0.133221 0.946585 0.277924 -0.16351 0.938296 0.299352 -0.173172 0.978164 -0.0540632 -0.200681 0.993506 -0.0671821 -0.0918321 0.993503 -0.0619716 -0.0954556 0.712674 -0.331452 -0.618252 0.884954 -0.281493 -0.37097 0.885792 -0.284941 -0.366309 0.792146 0.471989 -0.386951 0.849347 0.3093 -0.427719 0.805188 0.249389 -0.538032 0.812779 0.191183 -0.550308 0.759738 0.0783275 -0.645495 0.771366 0.0212081 -0.636038 0.722823 -0.116436 -0.681154 0.116233 0.46109 -0.879708 0.185746 0.422504 -0.887124 0.0296638 0.247742 -0.968372 0.275264 0.0567974 -0.95969 0.127919 -0.595587 -0.79304 0.161203 -0.398591 -0.90285 0.286351 -0.00152725 -0.958124 0.0901225 0.0822356 -0.99253 0.0666561 -0.219586 -0.973313 0.933082 -0.114357 -0.340999 0.918215 -0.146456 -0.368011 0.916084 -0.149471 -0.372087 0.902775 -0.216183 -0.371837 0.73816 -0.157935 -0.655878 0.697722 -0.312637 -0.644548 0.461099 -0.338654 -0.820184 0.106656 0.859381 0.500088 0.207979 0.867762 0.45137 0.0433269 0.942779 -0.330591 0.121176 0.99152 -0.0469583 0.24583 0.968202 0.0464027 0.0874157 0.984126 0.154447 0.112142 0.942495 0.314844 0.0815446 0.606002 -0.791272 0.113666 0.672235 -0.73156 0.227268 0.70995 -0.666573 0.0281123 0.819542 -0.572329 0.212712 0.932415 -0.292158 0.353638 0.0142845 -0.935273 0.456004 0.308285 -0.834878 0.364127 0.310392 -0.878105 0.489614 0.5749 -0.655567 0.398069 0.59432 -0.698803 0.521635 0.765977 -0.375734 0.443203 0.797993 -0.408385 0.546143 0.837506 -0.0176358 0.493425 0.869166 -0.0329042 0.553285 0.751396 0.359554 0.546206 0.756681 0.359295 0.177323 0.0428574 -0.983219 0.301525 0.394241 -0.868134 0.187413 0.390688 -0.901243 0.324417 0.67914 -0.658424 0.209395 0.688952 -0.693901 0.342317 0.873142 -0.347048 0.242327 0.89407 -0.376717 0.351087 0.935698 0.0347589 0.282722 0.959036 0.0178564 0.34499 0.834827 0.429005 0.333634 0.840262 0.427374 0.149377 -0.738936 -0.657008 0.192853 -0.624186 -0.757099 0.341467 -0.601908 -0.721877 0.424993 -0.568402 -0.704486 0.484345 -0.573521 -0.660669 0.68767 -0.485769 -0.539573 0.647367 -0.472278 -0.598222 0.870204 -0.393144 -0.296955 0.850012 -0.369151 -0.375776 0.238105 -0.297076 -0.92469 0.179684 -0.311222 -0.933196 0.42335 -0.309728 -0.851377 0.487237 -0.0679032 -0.870626 0.503312 -0.0649289 -0.861662 0.600309 0.209567 -0.771823 0.532649 0.213989 -0.818837 0.641641 0.443949 -0.625465 0.575708 0.466852 -0.671275 0.684257 0.618042 -0.387061 0.629491 0.653656 -0.420089 0.721185 0.689089 -0.0710509 0.685632 0.722984 -0.0848688 0.73982 0.61402 0.275037 0.72568 0.630842 0.274639 0.146445 -0.96836 -0.202072 0.82472 -0.363975 0.432851 0.651395 -0.732401 -0.198175 0.942263 -0.318573 0.103209 0.971801 -0.230306 0.0506148 0.978816 -0.198166 0.0514669 0.98931 -0.145733 -0.00522981 0.993672 -0.110908 -0.0177437 0.851107 -0.479993 -0.212658 0.873456 -0.474236 -0.110338 0.88941 -0.451668 -0.0703283 0.901406 -0.432281 -0.0245113 0.895301 -0.444586 -0.0279262 0.918228 -0.395154 0.0266704 0.741741 -0.577113 0.341703 0.782191 -0.526694 0.332822 0.708896 -0.682925 0.176297 0.911964 -0.409341 0.0276005 0.938587 -0.340251 0.0573018 0.786962 -0.410265 0.460841 0.849348 -0.243747 0.468183 0.79219 -0.134317 0.59531 0.856724 0.0995232 0.506082 0.84357 0.129564 0.521156 0.884011 0.340193 0.320613 0.877481 0.355436 0.322014 0.921871 -0.379918 0.0762622 0.959989 -0.276212 0.0461354 0.891439 -0.219283 0.39655 0.944652 -0.0329526 0.326416 0.941308 -0.0119154 0.337337 0.970892 0.136808 0.196601 0.965073 0.167393 0.20153 0.115182 0.718773 0.685638 0.0768035 0.524422 0.847987 0.146661 0.493071 0.857538 0.0529643 0.160915 0.985546 0.14867 0.112384 0.98248 0.085762 -0.0781235 0.993248 0.146317 -0.269864 0.951717 0.333935 0.761058 0.556128 0.105764 0.807497 0.580313 0.296925 0.809 0.507301 0.14312 -0.270714 0.951962 0.0595906 -0.488858 0.870326 0.223305 -0.602986 0.765861 0.116199 -0.646851 0.753712 0.0132443 -0.848902 0.528384 0.298955 -0.78664 0.540208 0.1086 -0.897122 0.428227 0.0837765 -0.917827 0.38804 0.0301532 -0.980276 0.195318 0.178763 -0.973918 0.139742 0.111639 -0.969352 -0.218845 0.341458 -0.915062 -0.214635 0.692777 -0.70158 -0.166869 0.714413 -0.699708 0.00473949 0.412917 -0.907727 0.0743761 0.487267 -0.808684 0.329547 0.353593 -0.829668 0.432 0.447575 -0.634361 0.630287 0.37767 -0.620236 0.687512 0.480032 -0.362056 0.799052 0.412114 -0.326301 0.8507 0.513925 -0.0244221 0.857487 0.454268 0.0221779 0.890589 0.542567 0.339453 0.76837 0.499059 0.378475 0.779549 0.5532 0.656322 0.513041 0.546585 0.662068 0.512748 0.344664 0.754795 0.558114 0.287817 0.466117 0.836598 0.346279 0.429003 0.834294 0.253019 0.0962649 0.96266 0.332863 0.0468861 0.941809 0.223305 -0.277011 0.934559 0.313046 -0.320668 0.893965 0.200941 -0.603347 0.771748 0.291656 -0.628041 0.721458 0.187455 -0.844821 0.501137 0.269276 -0.84786 0.456753 0.179697 -0.973725 0.139887 0.463496 -0.880705 0.0976181 0.42502 -0.884488 -0.192457 0.484352 -0.847618 -0.216671 0.870902 -0.459698 -0.173803 0.892969 -0.44118 -0.0892564 0.690171 -0.723546 -0.0120484 0.744778 -0.641123 0.185114 0.503286 -0.799372 0.328188 0.59314 -0.618821 0.515019 0.545205 -0.612763 0.572077 0.633559 -0.389742 0.668359 0.588805 -0.362324 0.722516 0.677989 -0.0972213 0.728614 0.63989 -0.056793 0.766365 0.718478 0.227213 0.657391 0.69109 0.263716 0.67294 0.739777 0.51552 0.432399 0.726918 0.532665 0.433426 0.939621 -0.308931 -0.14722 0.939565 -0.27269 -0.207019 0.938421 -0.264732 -0.221998 0.939692 -0.261127 -0.220889 0.939391 -0.261078 -0.222223 0.939414 -0.261074 -0.222131 0.939897 -0.260213 -0.221096 0.939965 -0.259936 -0.221132 0.939947 -0.260001 -0.221132 0.939757 -0.260462 -0.221397 0.939564 -0.260868 -0.221737 0.93962 -0.314991 -0.13377 0.939837 -0.314444 -0.133533 0.940954 -0.310698 -0.134432 0.939692 -0.314479 -0.13447 0.939968 -0.314167 -0.133267 0.939975 -0.314156 -0.133237 0.939692 -0.314288 -0.134912 0.939471 -0.31538 -0.133901 0.93945 -0.315453 -0.13388 0.939565 -0.307274 -0.150995 0.94337 -0.298499 -0.144746 0.936007 -0.303874 -0.177627 0.939622 -0.2975 -0.169128 0.93966 -0.286699 -0.18666 0.937285 -0.289799 -0.193684 0.94337 -0.263171 -0.201976 0.939621 -0.270058 -0.210193 0.939692 -0.261473 -0.220478 0.149349 -0.892611 -0.425371 0.488785 -0.787551 -0.375304 0.346113 -0.740368 -0.576248 0.65506 -0.596258 -0.464083 0.850963 -0.414478 -0.322599 0.850962 -0.414479 -0.3226 0.850962 -0.436678 -0.291849 0.850962 -0.436678 -0.291849 0.850962 -0.4566 -0.259576 0.850962 -0.4566 -0.259576 0.850962 -0.474141 -0.22595 0.850962 -0.474141 -0.22595 0.655065 -0.682082 -0.325044 0.57344 -0.736307 -0.359191 0.573329 -0.712271 -0.404925 0.57333 -0.712271 -0.404925 0.57333 -0.681193 -0.455268 0.573329 -0.681194 -0.455268 0.57344 -0.651082 -0.497252 0.488782 -0.688453 -0.535841 0.3461 -0.846945 -0.403608 0.202128 -0.881595 -0.426539 0.20209 -0.851401 -0.48402 0.202091 -0.851401 -0.48402 0.202091 -0.814253 -0.544197 0.202091 -0.814253 -0.544197 0.202128 -0.776399 -0.596949 0.149344 -0.780293 -0.607322 -0.707095 0.527144 0.471313 -0.671176 0.581102 0.460265 -0.706472 0.553698 0.440813 -0.706472 0.602237 0.371764 -0.706471 0.602237 0.371764 -0.706523 0.64142 0.299008 -0.672813 0.671313 0.310906 -0.7071 0.657572 0.260017 -0.706471 -0.553699 -0.440814 -0.706472 -0.553698 -0.440813 -0.706472 -0.602237 -0.371764 -0.706471 -0.602237 -0.371764 -0.706471 -0.642211 -0.297428 -0.706471 -0.642211 -0.297428 -0.701807 -0.697918 -0.142749 -0.701806 -0.697919 -0.142749 -0.694741 -0.392342 -0.602829 -0.487516 0.395605 -0.778347 -0.694742 -0.392341 -0.602828 -0.702917 -0.114597 -0.70198 -0.494615 -0.0463525 -0.867875 -0.705014 0.0707894 -0.705652 -0.703696 0.241503 -0.668198 -0.704394 0.405821 -0.582356 -0.704394 0.535815 -0.465544 -0.487519 0.731778 -0.476264 -0.694737 0.641196 0.325897 -0.694741 0.641191 0.325896 -0.702915 0.710194 0.0391701 -0.494619 0.867873 -0.0463548 -0.705015 0.694096 -0.145549 -0.703697 0.63867 -0.311306 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.979717 -0.200387 0 -0.979717 -0.200387 0 0.833659 0.552279 0.0376678 0.890828 0.452776 0.0154249 0.927364 0.373843 -0.0283309 0.998082 0.0550483 -1.1933e-05 0.571732 -0.82044 0.026812 0.500508 -0.865317 -7.18703e-05 0.601813 -0.798637 0.000100095 0.754872 -0.655872 1.18485e-05 0.75506 -0.655656 5.67828e-06 0.898902 -0.43815 0.0341675 0.849251 -0.526883 -0.0536302 0.977305 -0.204937 -0.007123 0.955975 -0.293363 0.00709814 0.991599 0.129153 0 -0.54548 -0.838124 0.0329101 -0.581823 -0.812649 -0.0251273 -0.161064 -0.986624 0.00777146 -0.219028 -0.975688 -6.72024e-06 -0.0227219 -0.999742 6.59756e-06 0.0998168 -0.995006 0.0188852 0.036279 -0.999163 -0.0358052 0.339687 -0.939857 0.0352476 0.215494 -0.975869 -2.51268e-05 0.406043 -0.913854 0 -0.782345 -0.622845 0 -0.782345 -0.622845 0 -0.850928 -0.525282 0 -0.850928 -0.525282 0 -0.907409 -0.420249 0 -0.907409 -0.420249 0 0.907409 0.420249 0 0.907409 0.420249 0 0.850928 0.525282 0 0.850928 0.525282 0 0.782345 0.622845 0 0.782345 0.622845 -0.879241 -0.455649 -0.138996 -0.105441 -0.949075 0.296883 -0.089541 -0.125347 0.988064 -0.0979813 0.129412 0.986738 -0.150378 0.145136 0.977917 -0.275066 -0.298882 0.913788 -0.143299 -0.237736 0.960701 -0.0795298 -0.40985 0.908679 -0.132375 -0.575999 0.806661 -0.188259 -0.558262 0.808023 0.0290729 -0.829225 0.558159 -0.204981 -0.856204 0.474233 -0.0559233 -0.714597 0.697298 -0.214587 -0.966826 0.138566 -0.147365 -0.968523 -0.200614 -0.169268 -0.967818 -0.186218 -0.887085 -0.457077 -0.0645061 -0.954989 -0.287327 0.0737522 -0.960101 -0.26779 0.0805861 -0.978436 -0.199795 0.0524011 -0.978976 -0.197151 0.0523215 -0.991397 -0.13067 -0.00763198 -0.990797 -0.135253 -0.00525779 -0.965171 0.174442 0.194973 -0.793206 -0.112225 0.598523 -0.859466 0.133232 0.493525 -0.839106 0.134906 0.526975 -0.884191 0.356458 0.3019 -0.876485 0.36303 0.316203 -0.859292 -0.384026 0.337848 -0.938545 -0.33665 0.0761515 -0.933193 -0.354071 0.0615106 -0.821647 -0.312767 0.476521 -0.847485 -0.235484 0.475728 -0.891282 -0.206719 0.403589 -0.947044 -0.00928134 0.320969 -0.938319 -0.00922926 0.345649 -0.970911 0.142113 0.192705 -0.989048 0.0677108 0.131148 -0.807335 -0.568421 0.158453 -0.693241 -0.56323 0.449653 -0.770718 -0.356153 0.528345 -0.902135 -0.431328 0.0103817 -0.88785 -0.454791 -0.0699093 -0.749527 -0.661891 -0.0104499 -0.710138 -0.703627 -0.0247556 -0.0995203 0.319947 0.942194 -0.100578 0.524708 0.84532 -0.110654 0.526811 0.842749 -0.0958612 0.825778 0.555788 -0.105771 0.826874 0.552352 -0.354223 -0.813883 0.460567 -0.457112 -0.583113 0.671586 -0.363193 -0.624962 0.691024 -0.49085 -0.297408 0.818911 -0.397291 -0.331852 0.85559 -0.522593 0.0395211 0.851666 -0.442821 0.021411 0.896355 -0.546592 0.38708 0.742567 -0.493392 0.386306 0.779315 -0.553361 0.67546 0.487386 -0.546232 0.677585 0.492453 -0.190683 -0.959191 0.208791 -0.276013 -0.814041 0.511032 -0.176407 -0.844319 0.505971 -0.302663 -0.570891 0.763203 -0.186324 -0.606994 0.772555 -0.325668 -0.249694 0.911917 -0.208477 -0.2825 0.936339 -0.343264 0.116229 0.93202 -0.241869 0.0949263 0.965654 -0.351519 0.480171 0.803661 -0.282649 0.473723 0.834084 -0.345028 0.7767 0.526966 -0.333669 0.777603 0.532916 -0.879553 -0.454773 -0.139889 -0.763482 -0.62415 -0.165927 -0.693959 -0.706843 -0.137094 -0.651408 -0.738869 -0.172454 -0.484427 -0.854429 -0.187836 -0.918284 -0.393215 0.0462248 -0.901027 -0.432075 0.0382389 -0.758731 -0.60376 0.244542 -0.805287 -0.553567 0.212313 -0.700529 -0.638027 0.319658 -0.633824 -0.771663 0.0529519 -0.461116 -0.882445 0.0930727 -0.425663 -0.890818 -0.158919 -0.341495 -0.921957 -0.18269 -0.149325 -0.988777 -0.00481209 -0.172458 -0.969786 0.172552 -0.424088 -0.895194 0.137028 -0.486861 -0.798575 0.353897 -0.502664 -0.789042 0.353187 -0.601391 -0.575232 0.55447 -0.531853 -0.618874 0.578038 -0.642825 -0.333958 0.689382 -0.575093 -0.368412 0.730439 -0.685232 -0.0414674 0.727143 -0.629212 -0.0576979 0.77509 -0.721676 0.269032 0.637814 -0.685622 0.270849 0.675695 -0.739939 0.535747 0.406774 -0.725682 0.542904 0.42266 -0.146149 -0.578934 -0.802169 -0.826272 0.243791 -0.50778 -0.651412 -0.485333 -0.583193 -0.992269 -0.0407707 -0.117221 -0.992328 -0.0787855 -0.0952819 -0.976263 -0.0318355 -0.214237 -0.978909 -0.0426577 -0.199795 -0.963217 -0.0471892 -0.264551 -0.851018 -0.400575 -0.33957 -0.880974 -0.283144 -0.379097 -0.902083 -0.200724 -0.382042 -0.895843 -0.210688 -0.391248 -0.919311 -0.13881 -0.368238 -0.740533 0.0662475 -0.668747 -0.783611 0.0858371 -0.615293 -0.707954 -0.128221 -0.694522 -0.918518 -0.139682 -0.369884 -0.938742 -0.0836193 -0.334323 -0.785902 0.245254 -0.567634 -0.847487 0.319723 -0.423726 -0.79326 0.484733 -0.368472 -0.856963 0.500979 -0.120978 -0.844208 0.526958 -0.0981189 -0.884163 0.433039 0.175308 -0.877675 0.440241 0.189404 -0.945948 -0.0789729 -0.314557 -0.960044 -0.0465112 -0.275956 -0.891348 0.268066 -0.365568 -0.944831 0.282153 -0.166385 -0.94185 0.300679 -0.150038 -0.970926 0.235915 0.0405774 -0.965173 0.252479 0.0685225 -0.115171 0.922954 0.367276 -0.0771112 0.989273 0.124066 -0.14647 0.985116 0.0899583 -0.0440752 0.954145 -0.296084 -0.0575919 0.95168 -0.301642 -0.099739 0.83874 -0.53532 -0.181849 0.744531 -0.642343 -0.33401 0.822508 0.460346 -0.105773 0.864387 0.491577 -0.278871 0.802826 0.526974 -0.0122591 0.123354 -0.992287 -0.315859 0.175415 -0.93245 -0.112681 0.026193 -0.993286 -0.136049 0.739235 -0.659562 -0.0636861 0.595594 -0.800757 -0.20271 0.450057 -0.869688 -0.248186 0.462012 -0.851439 -0.108776 0.394325 -0.912511 -0.084225 -0.0286429 -0.996035 -0.0328957 -0.221162 -0.974682 -0.190435 -0.277664 -0.941614 -0.0911601 -0.604685 -0.79123 -0.341493 -0.576553 -0.742273 -0.693996 -0.439323 -0.570408 -0.714753 -0.285856 -0.638291 -0.412191 -0.313724 -0.85538 -0.486902 -0.0414271 -0.872473 -0.354179 0.0470699 -0.933992 -0.447646 0.306913 -0.839891 -0.378522 0.366703 -0.849853 -0.48014 0.574262 -0.66309 -0.413119 0.637538 -0.650291 -0.514078 0.7687 -0.380558 -0.455181 0.818806 -0.349809 -0.542688 0.839843 -0.0123753 -0.49964 0.865997 0.020214 -0.553286 0.740025 0.382411 -0.546675 0.742003 0.388043 -0.344679 0.821929 0.453464 -0.288261 0.954534 0.0759627 -0.346233 0.937231 0.0414777 -0.253711 0.915323 -0.312754 -0.332839 0.875264 -0.350901 -0.224032 0.734362 -0.640719 -0.313029 0.678051 -0.665026 -0.201525 0.450301 -0.869837 -0.291646 0.392731 -0.872184 -0.187834 0.103578 -0.976724 -0.269305 0.0603737 -0.961161 -0.179216 -0.280677 -0.942922 -0.463845 -0.276563 -0.841642 -0.425694 -0.541325 -0.725087 -0.484449 -0.550876 -0.679592 -0.875379 -0.339992 -0.34368 -0.889599 -0.265535 -0.371625 -0.689726 -0.315151 -0.651888 -0.745698 -0.0963587 -0.65928 -0.502668 -0.0378042 -0.863653 -0.593281 0.208299 -0.777579 -0.546277 0.264847 -0.794631 -0.633759 0.443607 -0.63369 -0.58999 0.50589 -0.629275 -0.678232 0.620972 -0.392931 -0.640943 0.672769 -0.369559 -0.718702 0.691978 -0.0680739 -0.691733 0.72107 -0.0395354 -0.739911 0.607987 0.287897 -0.727056 0.615665 0.303887 -0.572885 -0.697451 -0.43054 -0.850726 -0.410528 -0.328225 -0.879517 -0.432222 -0.199084 -0.65468 -0.685916 -0.317669 -0.764994 -0.584405 -0.270656 -0.845143 -0.483599 -0.227738 -0.851115 -0.462883 -0.247674 -0.850698 -0.447295 -0.276118 -0.850697 -0.447296 -0.276118 -0.851115 -0.428855 -0.302798 -0.345806 -0.851427 -0.394322 -0.4884 -0.791823 -0.366718 -0.149208 -0.897251 -0.415545 -0.201916 -0.887245 -0.41476 -0.201876 -0.833408 -0.514467 -0.844348 -0.419177 -0.333717 -0.654679 -0.59138 -0.470813 -0.573006 -0.643979 -0.506907 -0.488418 -0.682682 -0.543501 -0.345803 -0.73408 -0.58442 -0.573005 -0.741756 -0.348516 -0.572884 -0.697452 -0.430541 -0.201875 -0.833409 -0.514467 -0.201915 -0.768402 -0.60728 -0.149213 -0.773587 -0.615872 -0.340893 0.735485 0.585538 -0.994035 -0.0928039 -0.0572884 -0.994036 -0.085173 -0.0680974 -0.994251 -0.0837728 -0.0666936 -0.991754 -0.116403 -0.0536159 -0.996676 -0.0718361 -0.0384367 -0.658679 0.640259 0.395235 -0.931791 0.308883 0.190675 -0.994046 -0.0980501 -0.0475349 -0.993745 0.101334 0.0469311 -0.971837 0.213835 0.0990338 -0.994056 -0.0889361 -0.0627948 -0.994035 -0.092804 -0.0572884 -0.931791 0.308884 0.190676 -0.931639 0.332429 0.146767 -0.558463 0.640185 0.527525 -0.739296 0.526817 0.419412 -0.931791 0.283988 0.22609 -0.888072 0.352312 0.295304 -0.971843 0.184345 0.146762 -0.237287 0.826625 0.51028 -0.237287 0.760001 0.605056 -0.108128 0.768588 0.63054 -0.887837 0.417552 0.193381 -0.739297 0.61103 0.282987 -0.658467 0.685695 0.31023 -0.558106 0.75294 0.34871 -0.340888 0.853059 0.395078 -0.658678 0.588656 0.468644 -0.658678 0.64026 0.395236 -0.237287 0.826625 0.51028 -0.23719 0.88429 0.40221 -0.108041 0.902097 0.417789 -0.939508 -0.311111 -0.1433 -0.939609 -0.319203 -0.123472 -0.939483 -0.319574 -0.123469 -0.939572 -0.31925 -0.123628 -0.93969 -0.318577 -0.124464 -0.939848 -0.3186 -0.123209 -0.939867 -0.318566 -0.123147 -0.939727 -0.318901 -0.123353 -0.939515 -0.267517 -0.213885 -0.940468 -0.252672 -0.227327 -0.939697 -0.253578 -0.229497 -0.939901 -0.252749 -0.229575 -0.93969 -0.253904 -0.229163 -0.939536 -0.253583 -0.230148 -0.939492 -0.253585 -0.230326 -0.939514 -0.253573 -0.230249 -0.93975 -0.253169 -0.229729 -0.939508 -0.267532 -0.213897 -0.939511 -0.267524 -0.213892 -0.939694 -0.279393 -0.19727 -0.939694 -0.279394 -0.197269 -0.939498 -0.29149 -0.179938 -0.939498 -0.29149 -0.179938 -0.939693 -0.301564 -0.161355 -0.939694 -0.301563 -0.161356 -0.939511 -0.311103 -0.143295 -0.939515 -0.311094 -0.143292 -0.939697 -0.318645 -0.124237 0.69474 -0.711525 -0.105207 0.458492 -0.552145 0.696362 0.694741 -0.711524 -0.105206 0.702916 -0.685818 0.188582 0.466757 -0.822343 0.325409 0.705014 -0.611846 0.358608 0.703697 -0.506611 0.498152 0.69474 0.563595 0.446874 0.694741 0.563595 0.446873 0.702916 0.331766 0.629159 0.782471 0.325303 0.530959 0.561443 0.183381 0.806941 0.701771 0.20227 0.683084 0.703697 -0.016607 0.710306 0.458492 -0.12999 0.87914 0.704396 -0.199688 0.68114 0.704396 -0.360065 0.611702 0.380727 0.916217 -0.124871 0.734319 0.660211 -0.157789 0.707049 0.707106 0.00902779 0.705897 0.657045 -0.264577 0.703398 0.582786 -0.406929 0.500116 0.655232 -0.566176 0.705217 0.464234 -0.535869 0.704384 0.332273 -0.627246 0.492749 0.309364 -0.813322 0.696088 -0.420624 -0.581839 0.696089 -0.420624 -0.581838 0.703396 -0.165022 -0.691377 0.500107 -0.113319 -0.858517 0.705214 0.00925654 -0.708935 0.704381 0.168586 -0.689512 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706177 0.627755 0.327472 0.706179 0.627753 0.327471 0.706178 0.574077 0.414425 0.706179 0.574076 0.414424 0 0.796479 0.604666 0.0420202 0.810088 0.584801 0 0.838037 0.545614 0 0.886615 0.462508 0.0629308 0.895713 0.440156 0 0.863326 0.504646 0.706177 -0.627755 -0.327472 0.706175 -0.627756 -0.327473 0.706175 -0.57408 -0.414427 0.706176 -0.574079 -0.414427 -0.00948946 0.616912 -0.786975 -0.00154315 0.65478 -0.755818 0.00207518 0.47649 -0.879177 -2.03469e-05 0.468109 -0.883671 8.95268e-06 0.251039 -0.967977 -0.00278422 0.237503 -0.971383 0.00262194 0.026849 -0.999636 -2.24014e-05 0.0130559 -0.999915 2.59381e-05 -0.215211 -0.976568 -0.00416167 -0.232162 -0.972668 0.00144298 -0.395729 -0.918366 -0.0172867 -0.585776 -0.810289 -0.0118228 -0.597305 -0.801927 0 -0.746958 -0.664871 -1.03034e-05 0.686955 -0.7267 6.01808e-08 0.819906 -0.572498 0.00078421 0.821734 -0.56987 -0.000435534 0.927618 -0.373531 0.0126654 0.960298 -0.278689 -0.0104822 0.990786 -0.135034 0 0.999312 -0.0370973 0 0.850202 0.526457 -0.026299 0.783305 0.621081 -0.0108363 0.727276 0.68626 0.0197303 0.466349 0.884381 -0.0045961 -0.507267 0.861777 6.78626e-05 -0.483328 0.875439 -8.57203e-05 -0.281327 0.959612 0.00524413 -0.257068 0.966379 -0.0048054 -0.0233734 0.999715 -0.0129957 -0.0668345 0.997679 0.02084 0.221556 0.974925 0.00416585 0.166176 0.986087 -0.00493649 0.530902 0.847419 0 -0.989245 -0.14627 -0.0272096 -0.979437 -0.199906 0.0218248 -0.963982 0.26507 -0.00552145 -0.980218 0.197845 3.78836e-06 -0.918124 0.396294 -7.66592e-06 -0.862735 0.505656 -0.0147147 -0.897323 0.441129 0.0291921 -0.712731 0.70083 -0.0251797 -0.803228 0.595139 0.0032277 -0.641005 0.76753 0 0.865245 -0.501348 -0.0110684 0.876748 -0.480823 0.00122558 0.742026 -0.67037 -0.00871403 0.60078 -0.799367 0.0162798 0.547699 -0.836517 -0.00109728 0.390248 -0.920709 0.000331205 0.339714 -0.940529 -0.0035857 0.205407 -0.97867 0.0321396 0.0900574 -0.995418 -0.00116102 -0.0424856 -0.999096 0.000938258 -0.230932 -0.972969 0.0315927 -0.366962 -0.929699 -0.00427725 -0.455879 -0.890031 0.000330131 -0.591017 -0.806659 -0.00703232 -0.761343 -0.648312 -0.0104211 -0.765126 -0.643796 0.00955686 -0.962179 -0.27225 0.0171097 -0.965595 -0.259487 0 -0.998238 -0.0593388 0 -0.930572 0.366109 0 -0.930572 0.366109 0 -0.880372 0.474284 0 -0.880372 0.474284 0 -0.817651 0.575715 0 -0.817651 0.575715 0 0.817651 -0.575714 0 0.817651 -0.575714 0 0.880372 -0.474284 0 0.880372 -0.474284 0 0.930572 -0.366109 0 0.930572 -0.366109 -0.879241 -0.3482 0.325103 -0.887085 -0.284403 0.363586 -0.954989 -0.0797927 0.28571 -0.960101 -0.0641056 0.272207 -0.978436 -0.0545169 0.199228 -0.978976 -0.0532634 0.196898 -0.991397 -0.0719443 0.109347 -0.990797 -0.0721797 0.114503 -0.965171 0.256073 -0.0535857 -0.793207 0.462222 0.396451 -0.859466 0.494021 0.13138 -0.839105 0.523826 0.146656 -0.884191 0.439682 -0.157752 -0.876485 0.455354 -0.156292 -0.859292 0.100572 0.501501 -0.938545 -0.102376 0.329624 -0.933193 -0.123768 0.337391 -0.821646 0.256296 0.509126 -0.847485 0.294251 0.441799 -0.891282 0.24616 0.380818 -0.947044 0.273327 0.168523 -0.938319 0.294724 0.180817 -0.970911 0.237944 -0.0267201 -0.989048 0.147429 0.00693716 -0.807335 -0.146985 0.571495 -0.693241 0.107796 0.712599 -0.770718 0.279484 0.57261 -0.902135 -0.206673 0.378732 -0.88785 -0.28794 0.358906 -0.749523 -0.339998 0.567994 -0.710138 -0.373251 0.596982 -0.276003 0.0355456 0.960499 -0.145864 -0.519087 0.842183 -0.197804 -0.642335 0.740459 -0.147938 -0.676213 0.721699 -0.111694 0.993134 -0.0347741 -0.0948779 0.894451 -0.436984 -0.105766 0.891789 -0.439917 -0.0780633 0.827972 0.55531 -0.143542 0.914564 0.378111 -0.177907 0.914073 0.364444 -0.0972913 0.973833 0.205389 -0.110859 0.993237 -0.0345163 -0.0290548 -0.291717 0.956063 -0.134921 0.118947 0.983691 0.129838 0.0783588 0.988434 -0.15604 0.364608 0.917994 -0.216098 0.395041 0.892885 -0.0506098 0.517661 0.854088 -0.143394 0.713106 0.686235 -0.273781 0.642763 0.715472 -0.142481 0.756243 0.638589 -0.354223 -0.00807841 0.935126 -0.457114 0.290056 0.840782 -0.363191 0.285965 0.886745 -0.490849 0.560494 0.667019 -0.397293 0.575037 0.715186 -0.522595 0.757323 0.391608 -0.442825 0.786969 0.429635 -0.546596 0.836619 0.0360629 -0.493393 0.868059 0.0551082 -0.553362 0.759818 -0.341273 -0.546228 0.765272 -0.340579 -0.176403 0.0160254 0.984187 -0.302659 0.375509 0.876009 -0.18633 0.365557 0.911948 -0.325672 0.664895 0.6722 -0.208479 0.669643 0.712822 -0.343265 0.865267 0.365352 -0.241865 0.883745 0.40062 -0.351516 0.936077 -0.0140106 -0.282645 0.959201 0.0067855 -0.345025 0.844717 -0.409159 -0.333672 0.850318 -0.406966 -0.879552 -0.348535 0.3239 -0.763489 -0.455769 0.457559 -0.693959 -0.472146 0.543598 -0.651406 -0.518785 0.553654 -0.484424 -0.589886 0.64604 -0.918287 -0.15657 0.363642 -0.901027 -0.18292 0.393308 -0.758732 -0.0900991 0.645142 -0.805284 -0.0929138 0.585564 -0.700528 -0.0421818 0.712377 -0.633825 -0.339972 0.694755 -0.461117 -0.360618 0.810756 -0.425663 -0.583038 0.69201 -0.341496 -0.619194 0.707092 -0.172203 -0.337485 0.925446 -0.179196 -0.335588 0.924808 -0.424091 -0.328927 0.843774 -0.486865 -0.0928054 0.868533 -0.502671 -0.0886526 0.85992 -0.601397 0.192567 0.775397 -0.531855 0.191157 0.824978 -0.642826 0.430044 0.633906 -0.575091 0.448374 0.684274 -0.685231 0.608992 0.399484 -0.62921 0.642399 0.437513 -0.721674 0.68688 0.085919 -0.685621 0.720594 0.103286 -0.739938 0.620152 -0.260583 -0.725683 0.637485 -0.258839 -0.14895 -0.962759 0.22563 -0.826271 -0.317856 -0.465019 -0.651412 -0.747727 0.128715 -0.992269 -0.121901 -0.0233024 -0.992328 -0.121909 0.0205896 -0.976263 -0.201453 -0.0795495 -0.978909 -0.194356 -0.0629535 -0.963219 -0.252695 -0.0914033 -0.851017 -0.494365 0.177125 -0.880894 -0.470017 0.0557657 -0.902136 -0.431112 -0.017099 -0.895768 -0.444331 -0.0130161 -0.919311 -0.388308 -0.0639048 -0.740532 -0.546029 -0.391746 -0.783612 -0.489939 -0.381983 -0.707955 -0.665583 -0.236217 -0.918517 -0.390172 -0.0639724 -0.938742 -0.331342 -0.0947448 -0.785901 -0.36896 -0.496213 -0.847487 -0.207096 -0.488751 -0.793259 -0.0767385 -0.604029 -0.856962 0.14572 -0.494349 -0.844208 0.178506 -0.505419 -0.884163 0.36834 -0.287368 -0.877676 0.384148 -0.286558 -0.945947 -0.311902 -0.0888862 -0.960044 -0.262241 -0.0976986 -0.891347 -0.182559 -0.414937 -0.944831 -0.00301559 -0.327544 -0.94185 0.0204024 -0.335413 -0.970926 0.153098 -0.18402 -0.965173 0.185583 -0.184392 -0.0641056 -0.0483834 -0.99677 -0.216849 -0.187093 -0.958109 -0.144753 0.191365 -0.970786 -0.171083 0.199615 -0.964824 -0.0910068 0.382424 -0.919494 -0.146469 0.570464 -0.808157 -0.0954265 0.594102 -0.798709 -0.105834 0.859283 -0.500431 -0.113068 0.857116 -0.502562 -0.334011 0.809925 -0.48214 -0.149337 -0.987346 -0.0533518 -0.172205 -0.958513 -0.227152 -0.0691389 -0.961078 -0.267488 -0.0821586 -0.79926 -0.595344 0.0810567 -0.757721 -0.647525 -0.191792 -0.528176 -0.827191 -0.0380339 -0.458471 -0.887895 -0.122139 -0.240962 -0.962818 -0.341495 -0.931103 0.128173 -0.169165 -0.977109 0.129 -0.269504 -0.961053 0.0611859 -0.693994 -0.713651 0.0952631 -0.714751 -0.695705 -0.0715856 -0.41219 -0.897644 -0.155995 -0.486903 -0.776297 -0.400361 -0.35418 -0.785325 -0.507761 -0.447646 -0.57391 -0.685741 -0.378519 -0.552642 -0.742503 -0.480138 -0.287123 -0.828872 -0.413113 -0.2444 -0.877272 -0.514073 0.0547801 -0.855995 -0.455181 0.106459 -0.884012 -0.542687 0.409204 -0.733514 -0.49964 0.450503 -0.739869 -0.553286 0.70119 -0.449673 -0.546675 0.707058 -0.448571 -0.344678 0.803677 -0.485079 -0.288261 0.543052 -0.78867 -0.346235 0.504535 -0.790927 -0.253713 0.186806 -0.94907 -0.332839 0.133741 -0.933451 -0.224033 -0.187697 -0.956336 -0.313033 -0.236905 -0.919721 -0.201531 -0.528151 -0.824889 -0.291646 -0.558966 -0.776208 -0.187833 -0.794079 -0.578063 -0.269299 -0.802203 -0.532868 -0.17921 -0.956934 -0.228386 -0.463845 -0.867165 -0.181309 -0.425694 -0.898607 0.106258 -0.484448 -0.863982 0.137277 -0.87538 -0.467631 0.1226 -0.889599 -0.454604 0.044147 -0.689728 -0.722125 -0.0530165 -0.745699 -0.619131 -0.24619 -0.502666 -0.766848 -0.399088 -0.59328 -0.569252 -0.569184 -0.546278 -0.555746 -0.626679 -0.633759 -0.32699 -0.701019 -0.589991 -0.292025 -0.75275 -0.678233 -0.0298014 -0.734242 -0.640943 0.016339 -0.767415 -0.718701 0.287036 -0.633308 -0.691734 0.326295 -0.644232 -0.739911 0.553319 -0.382584 -0.727055 0.571007 -0.381238 -0.572884 -0.721585 0.38874 -0.850726 -0.489516 0.191415 -0.879517 -0.388523 0.274773 -0.654677 -0.61807 0.435188 -0.765001 -0.526591 0.370777 -0.845143 -0.439027 0.30494 -0.851115 -0.445934 0.277031 -0.850697 -0.462773 0.24931 -0.850697 -0.462773 0.249311 -0.851115 -0.476659 0.22 -0.345807 -0.767206 0.540196 -0.488398 -0.713499 0.502381 -0.149207 -0.808498 0.56927 -0.201916 -0.802815 0.560997 -0.201876 -0.862246 0.464519 -0.844348 -0.498596 0.196159 -0.654679 -0.703426 0.276744 -0.573005 -0.760984 0.304249 -0.488417 -0.812027 0.31947 -0.345803 -0.873163 0.343522 -0.573006 -0.672701 0.468122 -0.572885 -0.721584 0.38874 -0.201876 -0.862246 0.464519 -0.201916 -0.910121 0.361816 -0.149217 -0.920154 0.36201 -0.340893 0.874833 -0.344179 -0.994035 -0.0960152 0.0517264 -0.994036 -0.10156 0.0397132 -0.994251 -0.0996446 0.0392025 -0.991754 -0.104634 0.0739999 -0.996676 -0.0692047 0.0429931 -0.65868 0.662413 -0.356863 -0.93179 0.319572 -0.172164 -0.994046 -0.0901915 0.0611464 -0.993745 0.0913084 -0.064291 -0.971837 0.192684 -0.13567 -0.994056 -0.0988497 0.0456236 -0.994035 -0.0960151 0.0517264 -0.93179 0.319572 -0.172164 -0.931639 0.293318 -0.214508 -0.558464 0.776942 -0.290654 -0.739294 0.626631 -0.246531 -0.93179 0.337795 -0.132896 -0.888073 0.431896 -0.157459 -0.971843 0.219272 -0.0862667 -0.237288 0.855228 -0.460738 -0.237288 0.903995 -0.355652 -0.108127 0.930358 -0.350346 -0.887837 0.376249 -0.26492 -0.739299 0.550588 -0.387673 -0.658468 0.611514 -0.438714 -0.558102 0.678464 -0.477712 -0.340892 0.768676 -0.54123 -0.658679 0.700185 -0.275469 -0.658679 0.662413 -0.356863 -0.237287 0.855228 -0.460738 -0.23719 0.790469 -0.564712 -0.108036 0.812865 -0.572345 -0.939508 -0.279657 0.19778 -0.939609 -0.26653 0.214701 -0.939482 -0.266715 0.215027 -0.939572 -0.26669 0.214664 -0.93969 -0.267078 0.213662 -0.939848 -0.266002 0.214311 -0.939867 -0.265931 0.214312 -0.939728 -0.266275 0.214498 -0.939515 -0.318989 0.124734 -0.940501 -0.323113 0.105144 -0.939696 -0.325546 0.104834 -0.939887 -0.325224 0.104123 -0.93969 -0.325413 0.105305 -0.939536 -0.326106 0.104534 -0.939493 -0.326256 0.10445 -0.939514 -0.326188 0.104477 -0.939749 -0.325538 0.104387 -0.939508 -0.319006 0.124741 -0.939511 -0.318998 0.124737 -0.939694 -0.310537 0.143327 -0.939694 -0.310537 0.143327 -0.939498 -0.301576 0.162468 -0.939498 -0.301576 0.162469 -0.939693 -0.29052 0.180484 -0.939694 -0.290521 0.180483 -0.939511 -0.279649 0.197776 -0.939514 -0.279642 0.19777 -0.939697 -0.266917 0.213835 0 -0.989813 0.142371 0.0420467 -0.973127 0.226399 0 -0.998399 0.0565653 -0.701806 -0.705111 0.10142 -0.701806 -0.705111 0.10142 1.46889e-05 0.643359 0.765565 0.00376816 0.891606 0.452796 -0.0244211 0.966449 0.255693 -0.0191987 0.961757 0.273231 -0.00404164 0.991043 0.133479 0 0.997708 0.0676654 1.67895e-05 0.784787 0.619766 -0.016838 0.740166 0.672214 -0.00323749 0.812633 0.582767 -0.0172159 0.50507 0.862907 0.0205194 0.609025 0.792886 -0.0146336 0.353926 0.935159 -2.25751e-06 0.415285 0.909691 2.49442e-05 0.179912 0.983683 0.0147048 0.114031 0.993368 -0.00456831 -0.0458214 0.998939 -0.000649317 -0.101445 0.994841 0.00313955 -0.319347 0.947633 0.0143281 -0.288985 0.957226 -0.0159705 -0.63247 0.774421 0 -0.663597 0.74809 0.696093 -0.45414 0.556067 0.492755 0.260954 0.830118 0.696092 -0.454141 0.556068 0.7034 -0.20543 0.680461 0.500117 -0.163657 0.850353 0.705223 -0.0324871 0.708241 0.70439 0.127704 0.698231 0.704388 0.294776 0.645713 0.70522 0.431883 0.562266 0.500115 0.62077 0.603764 0.703401 0.557821 0.440526 0.69755 0.685897 0.207291 0.733222 0.654105 0.185829 0.707053 0.706408 0.0326218 0.702128 0.634328 -0.323487 0.702131 0.634325 -0.323486 0.702132 0.70532 -0.0976437 0.702132 0.705321 -0.0976435 0.458493 -0.0780174 -0.885267 0.694739 0.588923 -0.412925 0.694742 0.58892 -0.412924 0.705702 0.405057 -0.581303 0.754939 0.339504 -0.561075 0.624889 0.265344 -0.734239 0.705015 0.197596 -0.681109 0.703698 0.0252309 -0.710051 0.704395 -0.159249 -0.691714 0.704395 -0.323436 -0.631837 0.458493 -0.510198 -0.727656 0.694741 -0.716483 0.0631424 0.694741 -0.716483 0.0631424 0.702915 -0.673529 -0.228623 0.466756 -0.801763 -0.373249 0.705014 -0.589677 -0.394 0.703697 -0.47641 -0.527109 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706176 0.597478 -0.379916 0.706176 0.597477 -0.379916 0.706177 0.645942 -0.289953 0.706176 0.645943 -0.289954 0 0.921896 -0.387438 0.0420202 0.911496 -0.409156 0 0.891534 -0.452954 0 0.843851 -0.536577 0.0629302 0.829043 -0.555632 0 0.868699 -0.49534 0.706179 -0.597475 0.379914 0.706177 -0.597477 0.379916 0.706177 -0.645942 0.289953 0.706177 -0.645942 0.289953 0 0.818788 -0.574097 0 -0.97931 0.202368 -0.0323173 -0.995619 0.0877422 -0.0129598 -0.999916 -8.53463e-05 0.015622 -0.968205 -0.24967 -0.00369061 -0.946927 -0.321426 0.00326067 -0.831471 -0.555558 0.0251178 -0.774086 -0.632581 -3.36953e-05 -0.224354 -0.974508 4.07248e-05 -0.477875 -0.878428 0.00666539 -0.455656 -0.890131 -0.00509175 -0.670519 -0.741875 -0.0225155 0.849363 -0.527329 0.0133484 0.563299 -0.826145 1.50902e-05 0.517698 -0.855564 -3.72546e-07 0.349535 -0.936923 -0.00405121 0.27862 -0.960393 0.0086717 0.176198 -0.984317 -0.00792446 0.0355104 -0.999338 0.00306862 -0.0625938 -0.998034 -0.00558334 -0.249775 -0.968288 0 0.891415 -0.453187 0.000328393 0.890847 -0.454303 -7.92852e-05 0.964334 -0.26469 -0.0072711 0.990527 -0.137127 0 0.994771 -0.102127 0.994042 -0.090541 0.0606814 0.97185 0.19571 -0.131167 0.658911 0.662234 -0.356767 0.108089 0.916495 -0.385168 0.558296 0.764843 -0.321434 0.341053 0.866623 -0.364208 0.237325 0.898756 -0.368666 0.237621 0.865999 -0.43998 0.153989 0.869871 -0.468627 0.237621 0.843818 -0.481152 0.237426 0.806937 -0.540816 0.887897 0.424111 -0.178238 0.739449 0.620632 -0.260828 0.108164 0.815493 -0.568571 0.34105 0.780886 -0.523357 0.65891 0.624863 -0.418789 0.558605 0.679094 -0.476226 0.739456 0.559224 -0.374797 0.971845 0.217218 -0.0912885 0.931702 0.337937 -0.133153 0.931867 0.3194 -0.172071 0.658688 0.696839 -0.283806 0.65891 0.662235 -0.356767 0.931867 0.3194 -0.172071 0.931867 0.301375 -0.201984 0.888088 0.373558 -0.267871 0.994042 -0.100482 0.0422288 0.994042 -0.100482 0.0422288 0.994053 -0.0970895 0.0493271 0.994978 -0.0881211 0.0474736 0.994053 -0.0946028 0.0539429 0.994042 -0.0905411 0.0606814 0 -0.912302 0.409518 -0.126161 -0.91909 0.373306 0 -0.896922 0.442189 0 -0.843851 0.536577 -0.126161 -0.855781 0.501719 0 -0.823928 0.566694 0.0684088 -0.0702061 -0.995184 0.0983799 0.339085 -0.935598 0.73816 -0.646975 -0.191163 0.933081 -0.352494 -0.0714633 0.885792 -0.459702 0.063611 0.902775 -0.430111 0.00130151 0.900887 -0.433331 -0.0250424 0.89372 -0.447712 0.0286165 0.982611 -0.177096 -0.0557848 0.968948 -0.235745 -0.0745976 0.959187 -0.268348 -0.089165 0.978164 -0.200826 -0.05352 0.993506 -0.11312 0.0122653 0.993503 -0.113653 0.00594079 0.955084 -0.284797 -0.0818877 0.937215 -0.337994 -0.0859552 0.81278 -0.380989 -0.440723 0.759738 -0.51985 -0.390581 0.532649 -0.602138 -0.594739 0.600309 -0.563634 -0.567403 0.364128 -0.605264 -0.70786 0.456006 -0.568882 -0.684421 0.187419 -0.585155 -0.788966 0.145513 -0.989335 0.00652741 0.172306 -0.965344 -0.196016 0.884955 -0.462014 0.0582953 0.71267 -0.701151 -0.0220818 0.69772 -0.714515 -0.051521 0.461104 -0.879625 -0.116804 0.423349 -0.892178 -0.157458 0.17969 -0.963781 -0.197072 0.27527 -0.802714 -0.529034 0.918216 -0.391931 -0.0571722 0.916084 -0.396971 -0.0565991 0.771366 -0.54022 -0.336388 0.722822 -0.648115 -0.239741 0.503311 -0.778686 -0.374602 0.487236 -0.787936 -0.376508 0.353639 -0.802828 -0.480006 0.177316 -0.830065 -0.528726 0.301518 -0.554708 -0.775491 0.275284 -0.273455 -0.921651 0.87644 0.370757 -0.307232 0.884046 0.363342 -0.294015 0.72568 0.553266 -0.409006 0.739821 0.545199 -0.394238 0.546206 0.689499 -0.475657 0.553288 0.68708 -0.470949 0.333632 0.790249 -0.514001 0.344987 0.788944 -0.508479 0.105762 0.840297 -0.53171 0.121175 0.841367 -0.526704 0.145479 0.159818 -0.976368 0.171344 0.166334 -0.971069 0.342315 0.13602 -0.929688 0.242325 0.12079 -0.962647 0.521636 0.0575937 -0.851222 0.443199 0.0453245 -0.895277 0.684256 -0.0261845 -0.728772 0.629493 -0.0369797 -0.776126 0.792145 -0.0991145 -0.602231 0.839076 0.148353 -0.523396 0.858963 0.143874 -0.49141 0.68563 0.287994 -0.668559 0.721186 0.283013 -0.632293 0.493428 0.406087 -0.76917 0.546142 0.40348 -0.734121 0.282722 0.494981 -0.821622 0.351083 0.49795 -0.792961 0.0859289 0.551255 -0.8299 0.106818 0.554486 -0.825309 0.147941 -0.967999 0.20271 0.205583 -0.965135 0.162019 0.341461 -0.92612 0.16033 0.424997 -0.894302 0.140007 0.48435 -0.858914 0.166349 0.687666 -0.710172 0.150901 0.647365 -0.754216 0.109895 0.870205 -0.453741 0.191996 0.850012 -0.510008 0.131804 0.0290121 -0.968147 -0.248696 0.135841 -0.774521 -0.61779 -0.181676 -0.789122 -0.586754 0.289895 -0.488103 -0.823236 0.0131303 -0.545942 -0.83772 0.143539 -0.213453 -0.966351 0.32442 -0.230641 -0.917364 0.209391 -0.256461 -0.943601 0.489615 -0.280288 -0.825661 0.398069 -0.308022 -0.864097 0.64164 -0.319696 -0.697204 0.575707 -0.347916 -0.739943 0.805188 -0.341256 -0.484992 0.849347 -0.215767 -0.48172 0.891416 -0.195596 -0.408803 0.946585 -0.00264229 -0.322443 0.938297 -0.000295754 -0.345831 0.97139 0.157333 -0.177898 0.963017 0.17286 -0.206681 0.146444 -0.659179 0.737589 0.112059 0.959593 -0.258115 0.824719 0.192873 0.531638 0.651396 -0.537824 0.53519 0.942262 -0.0699043 0.327499 0.971801 -0.0713186 0.224758 0.978816 -0.0545114 0.197351 0.98931 -0.0773959 0.123594 0.993672 -0.0708207 0.0871773 0.851107 -0.424165 0.309358 0.873456 -0.332675 0.355532 0.889412 -0.286733 0.355993 0.901406 -0.237367 0.362111 0.895299 -0.24648 0.371063 0.918227 -0.17448 0.355551 0.741739 0.00736627 0.670648 0.782191 0.0248846 0.622542 0.708896 -0.188784 0.679579 0.911965 -0.180766 0.368299 0.938587 -0.1205 0.323316 0.786964 0.193967 0.585717 0.849348 0.283583 0.445183 0.792189 0.448397 0.413976 0.856724 0.488042 0.166851 0.84357 0.516116 0.148372 0.884011 0.447757 -0.134309 0.87748 0.456592 -0.146811 0.921872 -0.123913 0.367147 0.959989 -0.0981513 0.262274 0.891439 0.23378 0.388179 0.944652 0.266207 0.191746 0.941308 0.286186 0.178987 0.970892 0.238666 -0.0201787 0.965073 0.258227 -0.0442012 0.177801 0.682291 0.70913 0.111573 0.983469 0.14262 0.0785787 0.961129 0.264683 0.233476 0.887381 0.397548 0.10321 0.881784 0.460222 0.089168 0.802984 0.589293 0.0726526 0.997345 -0.00489671 0.351192 0.933433 -0.0732617 0.155872 0.984577 0.0794472 0.333936 0.86215 -0.38103 0.105758 0.906315 -0.409156 0.233615 0.868959 -0.436272 -0.0904565 0.0454617 0.994862 0.249284 0.0855697 0.964643 0.280793 0.685706 0.671537 0.113659 0.628381 0.769558 0.0130977 0.3996 0.916596 0.402523 0.417415 0.814702 0.1513 0.331467 0.931256 0.0873524 -0.10897 0.9902 0.0301577 -0.320989 0.946603 0.178758 -0.365938 0.91331 0.111634 -0.674202 0.730061 0.341453 -0.643412 0.68515 0.692777 -0.495303 0.524151 0.714413 -0.345748 0.608335 0.412917 -0.38945 0.823303 0.487267 -0.118945 0.865115 0.353596 -0.0407125 0.934512 0.447579 0.228661 0.864516 0.377674 0.285282 0.880895 0.480035 0.51097 0.713075 0.412116 0.573577 0.707934 0.513926 0.730393 0.449895 0.454266 0.782363 0.426088 0.542565 0.835156 0.0902094 0.499059 0.864347 0.0620061 0.553199 0.772468 -0.311871 0.546586 0.775087 -0.316993 0.344666 0.860738 -0.374612 0.287817 0.957574 0.0146296 0.346279 0.937022 0.04562 0.253016 0.881822 0.397962 0.33286 0.839075 0.430299 0.223302 0.670848 0.707177 0.313045 0.613864 0.724689 0.200937 0.366681 0.908388 0.291654 0.310779 0.904629 0.187454 0.0115866 0.982205 0.269276 -0.0283707 0.962645 0.179698 -0.365715 0.913215 0.463497 -0.355811 0.811523 0.42502 -0.608916 0.66976 0.484353 -0.611451 0.625723 0.870903 -0.380364 0.311209 0.892969 -0.297887 0.337445 0.690171 -0.372206 0.620586 0.744778 -0.160247 0.647786 0.503287 -0.115467 0.85637 0.59314 0.136607 0.793425 0.545204 0.189051 0.816708 0.633559 0.383943 0.671707 0.588803 0.444557 0.675041 0.677987 0.582391 0.448502 0.639891 0.635293 0.432367 0.718479 0.682924 0.131923 0.691091 0.714641 0.108084 0.739778 0.632228 -0.230254 0.726919 0.64169 -0.244588 0.939621 -0.281962 0.193932 0.939565 -0.315629 0.132647 0.938423 -0.324619 0.118262 0.939692 -0.32186 0.115698 0.939392 -0.322986 0.114991 0.939414 -0.322907 0.115032 0.939897 -0.321581 0.114803 0.939966 -0.321472 0.114542 0.939946 -0.321508 0.114603 0.939758 -0.321964 0.114867 0.939564 -0.322465 0.11505 0.939621 -0.273342 0.205904 0.939838 -0.272864 0.205549 0.940952 -0.271773 0.201862 0.939692 -0.273694 0.205112 0.939968 -0.272493 0.205444 0.939975 -0.272467 0.205449 0.939693 -0.273981 0.204725 0.939471 -0.273651 0.206175 0.939449 -0.27367 0.206252 0.939566 -0.284403 0.190609 0.94337 -0.274603 0.186135 0.936007 -0.305767 0.174349 0.939622 -0.295219 0.173078 0.939661 -0.305002 0.154958 0.937285 -0.312634 0.154131 0.94337 -0.306501 0.126925 0.939621 -0.317061 0.12878 0.939692 -0.321675 0.116202 0.149347 -0.814688 0.560339 0.488785 -0.718798 0.494386 0.346108 -0.869231 0.353054 0.655057 -0.700039 0.284334 0.850962 -0.486619 0.197649 0.850962 -0.486619 0.197649 0.850962 -0.471087 0.23225 0.850962 -0.471087 0.23225 0.850962 -0.453099 0.265639 0.850963 -0.453099 0.265639 0.850963 -0.432749 0.297643 0.850962 -0.43275 0.297643 0.655066 -0.622536 0.428178 0.573439 -0.679223 0.458066 0.573328 -0.706811 0.414383 0.573328 -0.706811 0.414383 0.573328 -0.734871 0.362297 0.573328 -0.734871 0.362297 0.573439 -0.756174 0.315227 0.488786 -0.808276 0.328296 0.346096 -0.773009 0.531672 0.20213 -0.81019 0.550214 0.202091 -0.844874 0.495325 0.202089 -0.844875 0.495325 0.202089 -0.878416 0.433066 0.202091 -0.878415 0.433066 0.202129 -0.905173 0.373907 0.149343 -0.916103 0.372092 -0.7071 0.671737 -0.220861 -0.67118 0.689148 -0.273115 -0.706471 0.658605 -0.25911 -0.706471 0.623076 -0.335671 -0.70647 0.623077 -0.335671 -0.706522 0.579659 -0.405983 -0.672817 0.604906 -0.425919 -0.707102 0.553967 -0.439463 -0.70647 -0.658606 0.259111 -0.706471 -0.658605 0.25911 -0.706471 -0.623076 0.335671 -0.706471 -0.623076 0.335671 -0.706471 -0.578686 0.407457 -0.706473 -0.578684 0.407456 -0.694743 0.659261 -0.287588 -0.487516 0.702476 0.518514 -0.694742 0.659262 -0.287589 -0.702916 0.711268 0.00270156 -0.494619 0.863639 0.0973595 -0.705012 0.684328 0.186152 -0.703695 0.61924 0.348361 -0.704396 0.50748 0.496277 -0.704395 0.370839 0.605232 -0.487518 0.349106 0.800282 -0.694742 -0.427144 0.57869 -0.694742 -0.427144 0.57869 -0.702917 -0.155718 0.694017 -0.494623 -0.0973594 0.863637 -0.705015 0.0291253 0.708594 -0.703698 0.201753 0.681252 -0.697344 -0.692179 -0.186011 -0.697344 -0.692179 -0.186011 -0.697344 -0.534718 -0.477272 -0.642339 -0.583523 -0.496892 -0.707007 -0.417971 -0.570474 -0.697346 -0.263146 -0.66668 -0.697346 -0.263146 -0.666681 -0.697346 0.0645814 -0.71382 -0.697344 0.0645808 -0.713822 -0.707005 0.240249 -0.66515 -0.650495 0.401116 -0.644952 -0.700892 0.625394 -0.342976 -0.607904 0.677642 -0.413829 -0.706716 0.524982 -0.474285 -0.699221 0.391605 -0.59811 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.916585 -0.39984 0 -0.682176 0.731188 0.0478512 -0.593186 0.803642 0.0190414 -0.519853 0.854044 -0.0231314 -0.291448 0.956307 0.00914237 0.283948 0.958796 -0.0343172 0.128461 0.991121 -0.00482559 0.0410678 0.999145 0.0054595 -0.218926 0.975726 0.00782438 0.714932 0.69915 1.77404e-05 0.688853 0.724901 -2.37645e-05 0.52245 0.85267 1.35254e-05 0.522553 0.852607 9.31127e-06 0.382967 0.923762 0.0166621 0.980097 0.197818 -0.0109409 0.928426 0.371355 0.0114738 0.871495 0.49027 -2.49628e-05 0.834583 0.550882 -1.84125e-05 0.772935 0.634486 0.026423 0.897044 -0.44115 -0.0156565 0.999063 -0.0403485 -1.76483e-05 0.999993 0.00379821 6.726e-06 0.964937 0.262483 0.35024 0.194602 0.916221 0.0814619 0.828662 0.55379 0.0286762 0.980394 0.194949 0.0286763 0.980394 0.194947 0.0649336 0.894942 0.441432 0.0771597 0.790939 0.60701 0.142791 0.193105 0.970732 0.14279 0.193101 0.970733 0.121399 0.551482 0.825306 0.105909 0.439783 0.891838 0.115908 0.604719 0.787959 0.479849 0.194592 0.855499 0.424239 0.0113261 0.905479 0.353913 0.551497 0.755379 0.353914 0.551483 0.755388 0.237482 0.82866 0.506878 0.237481 0.828662 0.506875 0.0835988 0.980395 0.178431 0.0835992 0.980394 0.178433 0.6545 0.193093 0.730989 0.654501 0.193095 0.730988 0.599505 0.438492 0.669566 0.563051 0.550896 0.616025 0.531272 0.604711 0.593358 0.373385 0.82866 0.41702 0.417031 0.790939 0.447774 0.117792 0.980724 0.155902 0.174363 0.965233 0.194739 0.142792 0.193101 -0.970733 0.149317 0.25656 -0.954925 0.644783 0.256253 -0.720132 0.644781 0.256258 -0.720131 0.474198 0.70331 -0.529614 0.474196 0.703313 -0.529612 0.174361 0.965233 -0.194737 0.174362 0.965233 -0.194739 0.410097 0.256258 -0.875301 0.4101 0.256249 -0.875303 0.301602 0.703313 -0.643729 0.301597 0.703321 -0.643723 0.110898 0.965233 -0.2367 0.1109 0.965232 -0.236702 0.130795 0.438471 -0.889177 0.115906 0.60472 -0.787959 0.115194 0.704152 -0.700643 0.0891995 0.790142 -0.606399 0.0380407 0.965233 -0.25861 0.0380408 0.965233 -0.25861 0 0.980797 0.19503 0.000921105 0.965931 0.258797 0 0.896835 0.442366 0 0.793304 0.608825 0.00122844 0.707112 0.7071 0 0.608823 0.793306 0 0.258826 0.965924 0.00364234 0.442268 0.896876 0 0.1951 0.980783 0.670429 0.257378 -0.695903 0.492071 0.704976 -0.510759 0.180562 0.965542 -0.187421 0.180564 0.965541 -0.187422 0.135516 0.965541 -0.222185 0.135515 0.965541 -0.222184 0.08399 0.965541 -0.246324 0.0839899 0.965541 -0.246324 0.02845 0.965541 -0.25869 0.0284497 0.965541 -0.258689 0.492059 0.704988 -0.510755 0.369299 0.704988 -0.605484 0.369302 0.704984 -0.605486 0.228887 0.704984 -0.671274 0.228891 0.704979 -0.671278 0.0775309 0.704978 -0.704978 0.077531 0.704978 -0.704978 0.670432 0.257373 -0.695903 0.503172 0.257374 -0.824971 0.503173 0.257372 -0.824971 0.31186 0.257371 -0.914606 0.311855 0.257384 -0.914604 0.105634 0.257385 -0.960518 0.105637 0.257377 -0.960519 -0.670434 0.257378 0.695899 -0.492062 0.704985 0.510756 -0.180563 0.965541 0.187423 -0.180563 0.965541 0.187423 -0.135516 0.965541 0.222185 -0.135515 0.965541 0.222184 -0.08399 0.965541 0.246324 -0.0839906 0.965541 0.246325 -0.0284501 0.965541 0.25869 -0.0284511 0.965541 0.258692 -0.492068 0.704979 0.510758 -0.369303 0.704979 0.605491 -0.369307 0.704976 0.605493 -0.22889 0.704976 0.671281 -0.228888 0.704979 0.671279 -0.0775337 0.704979 0.704978 -0.0775303 0.704984 0.704972 -0.670429 0.257389 0.6959 -0.50317 0.257389 0.824967 -0.503173 0.257381 0.824968 -0.311856 0.257381 0.914604 -0.311858 0.257377 0.914605 -0.105635 0.257375 0.96052 -0.105634 0.257378 0.96052 0 0.965932 -0.258794 0 0.965932 -0.258794 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258826 -0.965924 0 0.258826 -0.965924 -0.184254 0.965683 0.183052 -0.502591 0.705753 0.499315 -0.685416 0.257899 0.68095 -0.685417 0.257896 0.68095 -0.556186 0.257895 0.79003 -0.556186 0.257896 0.79003 -0.409915 0.257895 0.874906 -0.409913 0.257901 0.874905 -0.251078 0.257901 0.932978 -0.251081 0.257893 0.932979 -0.0845592 0.257893 0.962466 -0.0845537 0.25791 0.962462 -0.502594 0.70575 0.499316 -0.407832 0.70575 0.579302 -0.40783 0.705751 0.579301 -0.300575 0.705751 0.641538 -0.300574 0.705751 0.641537 -0.184108 0.705751 0.68412 -0.184108 0.705751 0.68412 -0.0620003 0.705752 0.705741 -0.0620033 0.705746 0.705746 -0.184254 0.965682 0.183052 -0.149513 0.965682 0.212376 -0.149514 0.965682 0.212376 -0.110192 0.965683 0.235191 -0.110193 0.965682 0.235192 -0.0674952 0.965682 0.250802 -0.0674947 0.965683 0.250802 -0.0227306 0.965683 0.258728 -0.0227301 0.965683 0.258727 -0.105634 0.257378 -0.96052 -0.0775309 0.704978 -0.704978 -0.02845 0.965542 -0.258689 -0.0284498 0.965541 -0.25869 -0.0839903 0.965541 -0.246325 -0.0839903 0.965541 -0.246324 -0.135516 0.965541 -0.222183 -0.135516 0.965541 -0.222185 -0.180563 0.965541 -0.187423 -0.180562 0.965542 -0.187421 -0.077531 0.704978 -0.704978 -0.228889 0.704979 -0.671278 -0.22889 0.704982 -0.671275 -0.369302 0.704981 -0.605489 -0.369302 0.704984 -0.605486 -0.492064 0.704983 -0.510755 -0.492065 0.70498 -0.510759 -0.105637 0.257386 -0.960517 -0.311859 0.257387 -0.914602 -0.311854 0.257371 -0.914608 -0.503172 0.257372 -0.824971 -0.503174 0.25738 -0.824968 -0.670431 0.257381 -0.6959 -0.670431 0.257378 -0.695902 0.0981595 0.440135 0.89255 0.0668092 0.791532 0.607465 0.021444 0.980572 0.194985 -0.011991 0.89677 0.442334 0.0438482 0.608237 0.792543 0.0846532 0.1944 0.977263 0.0284509 0.965541 0.258691 0.0839903 0.965541 0.246326 0.0839903 0.965541 0.246324 0.135515 0.965541 0.222184 0.135516 0.965541 0.222185 0.180564 0.965541 0.187423 0.180564 0.965541 0.187423 0.077531 0.704978 0.704978 0.228889 0.704979 0.671278 0.228889 0.704978 0.671279 0.369302 0.704979 0.605492 0.369302 0.704982 0.605488 0.492064 0.704983 0.510756 0.492064 0.704985 0.510754 0.105634 0.257375 0.960521 0.311857 0.257377 0.914605 0.311857 0.257378 0.914605 0.50317 0.257376 0.824971 0.503171 0.257383 0.824968 0.670433 0.257381 0.695898 0.670433 0.257378 0.6959 0.174361 0.965234 -0.194737 0.474195 0.703314 -0.529611 0.644782 0.256253 -0.720133 0.644782 0.25625 -0.720133 0.410098 0.256254 -0.875302 0.4101 0.256244 -0.875304 0.140672 0.256249 -0.95632 0.140671 0.256252 -0.956319 -0.140671 0.256252 -0.956319 -0.140671 0.256253 -0.956319 -0.410098 0.256254 -0.875302 -0.410098 0.256258 -0.875301 -0.644782 0.256258 -0.720131 -0.644782 0.256253 -0.720132 0.474197 0.703313 -0.529612 0.301602 0.703313 -0.643729 0.301598 0.703319 -0.643725 0.103454 0.703319 -0.703306 0.103454 0.703319 -0.703307 -0.103454 0.703319 -0.703307 -0.103454 0.703319 -0.703306 -0.301599 0.703319 -0.643724 -0.3016 0.703315 -0.643728 -0.474194 0.703317 -0.529609 -0.474195 0.703314 -0.529611 0.174361 0.965234 -0.194737 0.110898 0.965233 -0.236699 0.1109 0.965233 -0.2367 0.0380406 0.965233 -0.258609 0.0380408 0.965233 -0.25861 -0.0380407 0.965233 -0.25861 -0.0380407 0.965233 -0.258609 -0.110899 0.965233 -0.236701 -0.110899 0.965233 -0.236701 -0.174363 0.965232 -0.19474 -0.174361 0.965234 -0.194737 0 0.980797 0.19503 0 0.980797 0.19503 0 0.896835 0.442366 0 0.896835 0.442366 0 0.793304 0.608825 0 0.793304 0.608825 0 0.608823 0.793306 0 0.608823 0.793306 0 0.44227 0.896882 0 0.44227 0.896882 0 0.1951 0.980783 0 0.1951 0.980783 0.670431 0.257378 -0.695901 0.492068 0.70498 -0.510756 0.180562 0.965542 -0.187421 0.180564 0.965541 -0.187422 0.135516 0.965541 -0.222185 0.135515 0.965541 -0.222184 0.0839897 0.965541 -0.246324 0.0839909 0.965541 -0.246326 0.0284502 0.965541 -0.258691 0.0284497 0.965541 -0.258689 0.0668081 0.791523 -0.607477 0.49206 0.704988 -0.510753 0.369298 0.704988 -0.605485 0.369301 0.704984 -0.605486 0.228888 0.704984 -0.671274 0.228892 0.704979 -0.671278 0.0555115 0.703578 -0.708446 0.0869148 0.606519 -0.790304 0.670434 0.257373 -0.695901 0.50317 0.257374 -0.824972 0.503174 0.257366 -0.824972 0.311862 0.257367 -0.914606 0.311853 0.257387 -0.914604 0.105634 0.257386 -0.960517 0.105638 0.257377 -0.960519 -0.670434 0.257378 0.695899 -0.492061 0.704984 0.510758 -0.492071 0.704975 0.510761 -0.369306 0.704976 0.605493 -0.369304 0.704979 0.605491 -0.228889 0.704978 0.671279 -0.228889 0.704979 0.671279 -0.021444 0.980572 0.194985 -0.0127051 0.964973 0.26204 -0.0839909 0.965541 0.246326 -0.0839897 0.965541 0.246324 -0.135516 0.965541 0.222183 -0.135517 0.965541 0.222184 -0.180563 0.965541 0.187424 -0.180563 0.965541 0.187424 -0.048594 0.895775 0.441843 -0.0668092 0.791532 0.607465 -0.0555115 0.703578 0.708446 -0.0869148 0.606519 0.790304 -0.0981595 0.440135 0.89255 -0.670432 0.257381 0.695899 -0.503169 0.257383 0.82497 -0.503172 0.257376 0.82497 -0.311857 0.257378 0.914605 -0.311858 0.257377 0.914605 -0.0885578 0.256867 0.962381 -0.10724 0.193975 0.975127 0 0.980797 -0.19503 -0.000921062 0.965932 -0.258794 0.000616049 0.831423 -0.55564 0 0.793295 -0.608837 0 0.555603 -0.831448 0.000921056 0.608823 -0.793306 -0.00122119 0.1951 -0.980783 0 0.258826 -0.965924 -0.184254 0.965683 0.183052 -0.502592 0.705753 0.499314 -0.685417 0.257899 0.680948 -0.685419 0.257896 0.680948 -0.556186 0.257895 0.79003 -0.556186 0.257896 0.79003 -0.409913 0.257895 0.874907 -0.409914 0.257892 0.874907 -0.25108 0.257895 0.932979 -0.251081 0.257893 0.932979 -0.0858504 0.19438 0.977162 -0.0991389 0.258186 0.960995 -0.0785473 0.440942 0.894092 -0.0695255 0.607335 0.791398 -0.502591 0.705754 0.499313 -0.40783 0.705753 0.579299 -0.407832 0.705751 0.5793 -0.300575 0.705751 0.641538 -0.300574 0.705751 0.641537 -0.184108 0.705751 0.68412 -0.184106 0.705754 0.684117 -0.0818615 0.706491 0.702972 -0.0534124 0.792172 0.607956 -0.184256 0.965682 0.183053 -0.149515 0.965682 0.212377 -0.14951 0.965683 0.212374 -0.110191 0.965683 0.235189 -0.110192 0.965683 0.23519 -0.0674943 0.965683 0.250801 -0.0674956 0.965682 0.250803 -0.0227308 0.965683 0.258729 -0.0227301 0.965683 0.258727 -0.0835988 0.980395 -0.17843 -0.0835998 0.980394 -0.178434 -0.237482 0.82866 -0.506878 -0.237483 0.828657 -0.506881 -0.35391 0.551493 -0.755382 -0.35391 0.551496 -0.75538 -0.0286762 0.980394 -0.194949 -0.0286763 0.980395 -0.194946 -0.0814622 0.82866 -0.553793 -0.0814623 0.828661 -0.553791 -0.121401 0.551494 -0.825298 -0.121401 0.551493 -0.825298 -0.142794 0.193101 -0.970733 -0.142792 0.193089 -0.970735 -0.416277 0.193106 -0.888495 -0.481814 -0.17317 -0.858992 -0.350239 0.194588 -0.916225 -0.6545 0.193093 -0.730989 -0.654501 0.193106 -0.730985 -0.599507 0.438492 -0.669564 -0.563052 0.550896 -0.616024 -0.53128 0.604701 -0.593362 -0.37339 0.828657 -0.417022 -0.417025 0.790944 -0.447769 -0.117794 0.980724 -0.155903 -0.174361 0.965233 -0.194738 0.0981595 0.440135 0.89255 0.0668097 0.791532 0.607465 0.021444 0.980572 0.194985 0.0438485 0.608237 0.792543 0.0846532 0.1944 0.977263 0.180564 0.965541 0.187423 0.135516 0.965541 0.222185 0.135516 0.965541 0.222183 0.0839897 0.965541 0.246324 0.0839897 0.965541 0.246324 0.028451 0.965541 0.25869 -0.011991 0.89677 0.442334 0.0775311 0.704977 0.70498 0.228889 0.704975 0.671283 0.228889 0.704978 0.671279 0.369305 0.704979 0.60549 0.369305 0.704976 0.605494 0.180566 0.96554 0.187427 0.423992 0.791543 0.440102 0.50883 0.703574 0.49606 0.551635 0.6065 0.572588 0.622985 0.440155 0.646648 0.105634 0.257375 0.960521 0.311857 0.257377 0.914605 0.311857 0.257378 0.914605 0.50317 0.257376 0.824971 0.503173 0.257395 0.824963 0.682789 0.256889 0.683964 0.680626 0.193967 0.706488 0.174364 0.965232 -0.19474 0.474195 0.703314 -0.529611 0.644784 0.256253 -0.720131 0.64478 0.256265 -0.72013 0.410097 0.256263 -0.8753 0.410099 0.256254 -0.875302 0.140671 0.256253 -0.956319 0.140671 0.256252 -0.956319 -0.140671 0.256252 -0.956319 -0.140671 0.256253 -0.956319 -0.410099 0.256254 -0.875302 -0.410099 0.256254 -0.875302 -0.654501 0.193093 -0.730988 -0.638177 0.256559 -0.725884 -0.599506 0.438492 -0.669565 -0.531278 0.604701 -0.593364 0.474197 0.703313 -0.529612 0.301602 0.703313 -0.643729 0.301598 0.703319 -0.643725 0.103454 0.703319 -0.703306 0.103454 0.703319 -0.703307 -0.103454 0.703319 -0.703307 -0.103454 0.703319 -0.703306 -0.3016 0.703319 -0.643724 -0.301601 0.703312 -0.64373 -0.464637 0.704144 -0.53693 -0.40885 0.790147 -0.456629 0.17436 0.965234 -0.194737 0.110898 0.965233 -0.236699 0.1109 0.965233 -0.2367 0.0380406 0.965233 -0.258609 0.0380408 0.965233 -0.25861 -0.0380407 0.965233 -0.25861 -0.0380407 0.965233 -0.258609 -0.110899 0.965233 -0.236701 -0.110899 0.965233 -0.236698 -0.174361 0.965234 -0.194737 -0.174361 0.965233 -0.194737 0 0.980797 0.19503 0 0.980797 0.19503 0 0.896835 0.442366 0 0.896835 0.442366 0 0.793304 0.608825 0 0.793304 0.608825 0 0.608823 0.793306 0 0.608823 0.793306 0 0.44227 0.896882 0 0.44227 0.896882 0 0.1951 0.980783 0 0.1951 0.980783 0.670431 0.257378 -0.695901 0.492065 0.70498 -0.510759 0.180565 0.96554 -0.187424 0.180563 0.965541 -0.187423 0.135517 0.965541 -0.222184 0.135516 0.965541 -0.222183 0.0839897 0.965541 -0.246324 0.0839896 0.965541 -0.246324 0.0284502 0.965541 -0.25869 0.0284499 0.965541 -0.258689 0.0668086 0.791523 -0.607477 0.492066 0.704979 -0.51076 0.369304 0.704981 -0.605488 0.369301 0.704984 -0.605486 0.228886 0.704984 -0.671274 0.228893 0.704975 -0.671281 0.0555118 0.703577 -0.708447 0.0869148 0.606519 -0.790304 0.670427 0.257389 -0.695902 0.503169 0.257385 -0.824969 0.503177 0.257366 -0.82497 0.311862 0.257367 -0.914606 0.311853 0.257387 -0.914604 0.105634 0.257386 -0.960517 0.105638 0.257377 -0.960519 -0.622985 0.440155 0.646648 -0.423992 0.791543 0.440102 -0.136095 0.980573 0.141264 -0.580907 0.60824 0.540916 -0.69673 0.194392 0.690492 -0.492065 0.704983 0.510755 -0.369301 0.704982 0.605489 -0.369304 0.704979 0.605491 -0.228889 0.704978 0.671279 -0.228889 0.704979 0.671279 -0.0214439 0.980572 0.194985 -0.012705 0.964973 0.26204 -0.0839903 0.965541 0.246324 -0.0839903 0.965541 0.246324 -0.135515 0.965541 0.222184 -0.135516 0.965541 0.222185 -0.180563 0.965541 0.187424 -0.347593 0.896748 0.273902 -0.048594 0.895775 0.441843 -0.0668092 0.791532 0.607465 -0.0555115 0.703578 0.708446 -0.0869148 0.606519 0.790304 -0.0981595 0.440135 0.89255 -0.670432 0.257381 0.695899 -0.503169 0.257383 0.82497 -0.503172 0.257376 0.82497 -0.311857 0.257378 0.914605 -0.311858 0.257377 0.914605 -0.0885578 0.256867 0.962381 -0.10724 0.193975 0.975127 0 0.980797 -0.19503 -0.000921062 0.965932 -0.258794 0.000616049 0.831423 -0.55564 0 0.793295 -0.608837 0 0.555603 -0.831448 0.000921056 0.608823 -0.793306 -0.00122119 0.1951 -0.980783 0 0.258826 -0.965924 -0.6545 0.193093 0.730989 -0.654504 0.193074 0.73099 -0.599506 0.438492 0.669565 -0.551855 0.551886 0.625202 -0.368374 0.829068 0.420651 -0.408845 0.790154 0.456622 -0.531268 0.604722 0.593351 -0.131443 0.980394 0.146803 -0.131439 0.980395 0.146799 -0.297656 0.894921 0.332442 -0.416282 0.193079 0.888498 -0.416278 0.193101 0.888496 -0.35391 0.551497 0.75538 -0.353916 0.551484 0.755387 -0.237482 0.828662 0.506875 -0.23748 0.828664 0.506872 -0.0835999 0.980394 0.178434 -0.0835994 0.980394 0.178433 -0.142793 0.193094 0.970734 -0.142792 0.193101 0.970733 -0.121399 0.55149 0.825301 -0.121398 0.551494 0.825298 -0.0814603 0.828662 0.55379 -0.0814614 0.82866 0.553793 -0.0286762 0.980394 0.194947 -0.0286759 0.980395 0.194946 -0.350239 0.194588 -0.916225 -0.131441 0.980394 -0.146802 -0.131439 0.980395 -0.146799 -0.297647 0.894928 -0.332431 -0.379997 0.828073 -0.412186 -0.0286762 0.980394 -0.194949 -0.0286763 0.980394 -0.194947 -0.0814617 0.82866 -0.553793 -0.081462 0.828663 -0.553789 -0.121401 0.551494 -0.825298 -0.121401 0.551493 -0.825298 -0.142794 0.193101 -0.970733 -0.142792 0.193089 -0.970735 -0.479852 0.194605 -0.855494 -0.424235 0.0113153 -0.905481 -0.35391 0.551496 -0.75538 -0.35391 0.551493 -0.755382 -0.237483 0.828657 -0.506881 -0.237481 0.828664 -0.506871 -0.0836002 0.980394 -0.178434 -0.0835999 0.980394 -0.178433 -0.40885 0.790147 -0.456629 -0.531267 0.604722 -0.593352 -0.563052 0.550896 -0.616024 -0.599506 0.438493 -0.669564 -0.654501 0.193106 -0.730985 -0.6545 0.193093 -0.730989 -0.312178 0.938442 -0.14789 0.231213 0.861954 -0.451194 0.682996 0.193082 -0.70444 0.144783 0.980727 0.131199 0.2566 0.930735 0.260554 0.245183 0.961119 0.12703 0.182188 0.959622 0.214322 0.196185 0.945196 0.260991 -0.020677 0.995996 0.0869737 -0.0316181 0.997738 0.0593229 0.0235466 0.997964 0.0592779 0.0214 0.998616 0.0480384 0.0654246 0.994532 0.0814019 0.0659473 0.995251 0.071594 0.116531 0.988645 0.0948789 -0.122597 0.987639 0.0976674 -0.172437 0.983847 0.0480797 -0.148723 0.979493 0.135922 -0.257514 0.932805 0.252113 -0.947322 0.104015 -0.302922 -0.965599 0.087183 -0.244987 -0.934838 0.353691 0.0313153 -0.989292 0.139692 -0.0422687 -0.974715 0.222574 -0.0197877 -0.950807 0.309582 0.0111871 -0.911562 0.409182 0.0403126 -0.889234 0.453809 0.0576217 -0.804879 0.584551 0.102323 -0.652343 0.515379 -0.555728 -0.61647 0.592303 -0.518789 -0.755929 0.101931 -0.64667 -0.597404 0.338334 -0.727075 -0.700946 0.257987 -0.664919 -0.696816 0.270481 -0.664294 -0.63554 0.204469 -0.744501 0.300921 0.62851 -0.717232 0.298911 0.619001 -0.726285 0.102787 0.630868 -0.769051 0.10167 0.627683 -0.771801 -0.104101 0.627592 -0.771552 -0.102516 0.631003 -0.768977 -0.303979 0.618543 -0.72457 -0.298404 0.628738 -0.718083 0.805503 0.583171 0.105244 0.782751 0.612162 0.112061 0.911782 0.408459 0.0426099 0.976217 0.216778 -0.00270047 0.744293 0.628495 -0.225881 0.712219 0.672176 -0.202295 0.833661 0.445052 -0.327015 0.80648 0.508163 -0.302258 0.878756 0.247885 -0.40785 0.862335 0.328361 -0.385431 0.787533 0.543283 -0.290921 0.794276 0.0888611 -0.601024 0.755778 0.101851 -0.646859 0.594531 0.33878 -0.729219 0.697237 0.260426 -0.667862 0.652071 0.515448 -0.555982 0.616274 0.592242 -0.519092 0.582999 0.692148 -0.425491 0.183195 0.967256 0.175657 0.44949 0.893219 0.0109 0.310658 0.938681 -0.149562 -0.782767 0.61163 0.114824 -0.600954 0.779981 0.174598 -0.572557 0.80007 0.179071 -0.199171 0.941652 0.271333 -0.181743 0.959989 0.213051 -0.583192 0.692129 -0.425258 -0.476175 0.835239 -0.275015 -0.278179 0.955102 -0.101966 -0.322551 0.931838 -0.166251 -0.170736 0.956176 -0.237859 -0.0687083 0.994977 0.0727953 -0.0868653 0.995081 0.0476183 -0.860778 0.0626896 -0.505106 -0.783223 0.552026 -0.286059 -0.876199 0.249408 -0.412396 -0.865271 0.327047 -0.37993 -0.831262 0.446581 -0.331011 -0.809087 0.506985 -0.297228 -0.742101 0.629927 -0.229082 -0.71406 0.671574 -0.197753 -0.61122 0.783411 -0.112594 -0.511089 0.859178 -0.0245069 -0.449503 0.89321 0.0110881 -0.240134 0.960147 0.143017 -0.177021 0.96964 0.168708 0.9706 0.198306 -0.136417 0.9656 0.0870944 -0.245014 0.902655 0.134487 -0.408811 0.927374 0.373445 0.0227292 0.764097 0.636759 0.10341 0.992323 0.121133 0.0249258 0.329176 0.147284 -0.932711 0.344087 0.20659 -0.915928 0.112208 0.221293 -0.96873 0.111164 0.217713 -0.969662 -0.113351 0.213923 -0.970252 -0.101617 0.254981 -0.961592 -0.331171 0.170708 -0.928 -0.266748 0.405909 -0.874119 -0.384349 0.219047 -0.896824 0.601171 0.780965 0.169372 0.573228 0.798968 0.181824 0.511019 0.859215 -0.0246927 0.611162 0.783423 -0.112828 0.426034 0.843776 -0.326401 0.230015 0.972997 0.0192527 0.372031 0.843931 -0.386488 0.47893 0.620401 -0.62107 0.478258 0.605772 -0.635854 0.530541 0.225034 -0.817243 0.539348 0.263303 -0.799859 0.191281 0.981285 0.0221788 0.323629 0.931579 -0.165605 0.169946 0.956302 -0.23792 0.18501 0.914455 -0.359921 0.0697314 0.920402 -0.384704 0.0691222 0.919434 -0.387121 -0.0706863 0.919379 -0.386969 -0.0696804 0.92034 -0.384863 -0.185972 0.914324 -0.359758 -0.232179 0.861901 -0.450799 -0.372684 0.843856 -0.386024 -0.484429 0.604645 -0.632245 -0.474473 0.621065 -0.623822 -0.531597 0.198582 -0.82339 -0.525007 0.226039 -0.820533 -0.919381 0.110963 0.377395 0.24738 0.908632 0.336438 -0.0327121 0.890675 0.453462 0.892471 0.27694 0.356089 0.977178 0.0697626 0.200639 0.769711 0.513851 0.378817 0.416137 0.425829 0.80343 0.557822 0.572932 0.600486 0.844297 0.065365 0.531875 0.919264 0.111769 0.377442 0.889058 0.286797 0.356824 0.765362 0.212246 0.607596 0.669168 0.390227 0.632406 0.672247 0.16969 0.720617 0.560971 0.138777 0.816121 -0.172101 0.133461 0.975997 -0.744994 0.19036 0.639333 -0.741361 0.199696 0.640707 -0.840758 0.0632706 0.537701 -0.542839 0.589538 0.59814 -0.292271 0.810124 0.50821 -0.49895 0.122143 0.85798 -0.436465 0.473423 0.765094 -0.384411 0.160581 0.909089 -0.750381 0.530152 0.3948 -0.756615 0.520776 0.395381 -0.632747 0.448357 0.631354 -0.611364 0.494328 0.617959 -0.406217 0.437378 0.802302 -0.397835 0.469197 0.788405 -0.13855 0.438024 0.888223 -0.138554 0.449467 0.882486 0.138521 0.449675 0.882385 0.141777 0.438307 0.887573 0.39482 0.469115 0.789967 0.411274 0.438637 0.799031 0.607574 0.493426 0.622403 0.637778 0.45082 0.6245 0.757048 0.521017 0.394232 0.750035 0.529594 0.396204 -0.031971 0.89624 0.442415 -0.0700849 0.901113 0.427882 -0.129529 0.867835 0.479671 -0.24586 0.904815 0.347652 -0.176682 0.932134 0.316086 -0.148726 0.91678 0.370669 -0.195535 0.885567 0.421352 -0.125341 0.911397 0.391976 -0.0985141 0.903964 0.416106 0.16952 0.928259 0.331055 0.149496 0.917006 0.369799 0.195303 0.886024 0.420497 0.126023 0.911573 0.391349 0.0984288 0.903902 0.41626 0.129369 0.86841 0.478673 0.0698914 0.901036 0.428077 0.0308729 0.895976 0.443028 0.0472998 0.872475 0.486364 0.00366476 0.89797 0.440041 -0.977151 0.0697772 0.200764 -0.769332 0.514255 0.379039 -0.889292 0.285909 0.356954 -0.912762 0.210061 0.350343 -0.854297 0.362242 0.372771 -0.173057 0.155755 0.972518 0.0263862 0.153027 0.98787 0.157387 0.313665 0.936399 0.201228 0.137184 0.969891 0.404444 0.162716 0.899972 -0.57288 0.711686 0.406585 -0.494746 0.779744 0.3837 -0.411524 0.731225 0.54402 -0.394333 0.750257 0.530675 -0.261782 0.713507 0.649906 -0.25502 0.726922 0.637612 -0.0888234 0.706966 0.701647 -0.0885864 0.711748 0.696827 0.088709 0.711869 0.696688 0.0907492 0.707125 0.70124 0.253343 0.726888 0.638319 0.264648 0.714268 0.647906 0.392108 0.749809 0.532952 0.414278 0.732769 0.539837 0.490663 0.777602 0.393172 0.575784 0.717502 0.392001 -0.312178 0.938442 -0.14789 0.231214 0.861954 -0.451194 0.682993 0.193068 -0.704447 0.144785 0.980727 0.131197 0.2566 0.930735 0.260555 0.245183 0.961119 0.12703 0.182185 0.959621 0.214326 0.196181 0.945196 0.260992 -0.0206771 0.995996 0.0869737 -0.0316182 0.997738 0.0593229 0.0235465 0.997964 0.0592779 0.0213555 0.998628 0.0478065 0.0654778 0.994541 0.0812458 0.0659911 0.995247 0.0716159 0.11653 0.988645 0.0948811 -0.122596 0.987639 0.0976669 -0.172443 0.983846 0.048071 -0.148727 0.979493 0.135921 -0.257514 0.932805 0.252113 -0.94733 0.103965 -0.302913 -0.9656 0.0871375 -0.244999 -0.934852 0.353654 0.0313068 -0.989299 0.139642 -0.0422804 -0.97472 0.222553 -0.0197921 -0.950793 0.309623 0.0112049 -0.911547 0.409214 0.0403283 -0.889274 0.453734 0.0575953 -0.804858 0.584578 0.102331 -0.65234 0.51538 -0.55573 -0.616472 0.592294 -0.518797 -0.755906 0.101939 -0.646696 -0.59736 0.338365 -0.727097 -0.700946 0.257987 -0.664919 -0.696812 0.270493 -0.664294 -0.63555 0.204493 -0.744485 0.300922 0.628514 -0.717228 0.298911 0.619001 -0.726285 0.102786 0.630868 -0.769051 0.101669 0.627683 -0.771802 -0.104101 0.627592 -0.771552 -0.102516 0.631003 -0.768977 -0.303982 0.618543 -0.724569 -0.298405 0.628743 -0.718078 0.805504 0.58317 0.105247 0.782751 0.612162 0.112064 0.911798 0.408423 0.0426012 0.976217 0.216778 -0.00270047 0.744292 0.628496 -0.225883 0.712218 0.672176 -0.202297 0.833649 0.445082 -0.327003 0.806495 0.508133 -0.30227 0.878762 0.247849 -0.407859 0.862335 0.328361 -0.385431 0.787533 0.543283 -0.290921 0.794276 0.0888611 -0.601024 0.755801 0.101844 -0.646833 0.594577 0.338749 -0.729197 0.697237 0.260426 -0.667862 0.652065 0.515471 -0.555969 0.616272 0.592251 -0.519084 0.582999 0.692148 -0.425491 0.183198 0.967256 0.175655 0.449489 0.893219 0.0108988 0.310658 0.938681 -0.149562 -0.782767 0.611631 0.11482 -0.600954 0.779981 0.174595 -0.572556 0.800071 0.179068 -0.199178 0.941652 0.27133 -0.181749 0.959988 0.213049 -0.583192 0.692129 -0.425258 -0.476175 0.835239 -0.275015 -0.278179 0.955102 -0.101966 -0.322551 0.931838 -0.166251 -0.170736 0.956176 -0.237859 -0.0687083 0.994977 0.0727953 -0.0868653 0.995081 0.0476183 -0.860777 0.0626899 -0.505107 -0.783216 0.552039 -0.286052 -0.876195 0.249444 -0.412384 -0.865273 0.32703 -0.37994 -0.831261 0.446582 -0.331015 -0.809073 0.507015 -0.297215 -0.7421 0.629927 -0.229083 -0.714045 0.671595 -0.197737 -0.61122 0.783411 -0.112593 -0.511089 0.859178 -0.0245062 -0.449504 0.89321 0.0110887 -0.240143 0.960145 0.143012 -0.177024 0.969639 0.168706 0.970601 0.198291 -0.136432 0.9656 0.0870944 -0.245014 0.902655 0.134487 -0.408811 0.927364 0.373468 0.0227332 0.764085 0.636773 0.103412 0.992323 0.121133 0.0249258 0.329176 0.147284 -0.932711 0.344086 0.206583 -0.915931 0.112208 0.221291 -0.968731 0.111165 0.217715 -0.969661 -0.113351 0.213921 -0.970252 -0.101617 0.254979 -0.961592 -0.331172 0.1707 -0.928001 -0.266745 0.405918 -0.874116 -0.384349 0.219055 -0.896822 0.601171 0.780964 0.169374 0.573229 0.798967 0.181826 0.511018 0.859215 -0.0246943 0.611161 0.783423 -0.112829 0.426034 0.843776 -0.326401 0.230015 0.972997 0.0192527 0.372031 0.843931 -0.386488 0.478928 0.620408 -0.621065 0.478256 0.605779 -0.635848 0.530541 0.225023 -0.817246 0.539352 0.263304 -0.799857 0.191282 0.981284 0.0221784 0.323644 0.93157 -0.165624 0.169948 0.956298 -0.237933 0.185012 0.914455 -0.359921 0.0697309 0.920402 -0.384704 0.0691218 0.919434 -0.387121 -0.0706868 0.919379 -0.386969 -0.0696803 0.92034 -0.384862 -0.185972 0.914326 -0.359755 -0.232183 0.861896 -0.450805 -0.372687 0.843849 -0.386036 -0.484424 0.604653 -0.632241 -0.474478 0.621057 -0.623826 -0.531599 0.198593 -0.823385 -0.525006 0.226061 -0.820527 -0.919377 0.110988 0.377397 0.24738 0.908633 0.336437 -0.0327121 0.890675 0.453462 0.892463 0.276964 0.356091 0.977176 0.0697598 0.200649 0.769723 0.513832 0.378819 0.416137 0.425829 0.80343 0.557792 0.572968 0.600479 0.844289 0.0654103 0.531882 0.919256 0.111819 0.377446 0.889074 0.286753 0.356821 0.765376 0.212209 0.607591 0.669169 0.390223 0.632408 0.672248 0.169711 0.720611 0.560965 0.138792 0.816122 -0.172101 0.133466 0.975996 -0.744993 0.19036 0.639334 -0.741367 0.199678 0.640706 -0.840756 0.0632942 0.537702 -0.542786 0.589597 0.59813 -0.29229 0.810111 0.50822 -0.49895 0.122143 0.85798 -0.436461 0.473436 0.765088 -0.384409 0.160592 0.909088 -0.750381 0.530151 0.394803 -0.756609 0.520783 0.395383 -0.632743 0.448364 0.631353 -0.611364 0.494328 0.61796 -0.406217 0.437378 0.802302 -0.397835 0.469197 0.788405 -0.13855 0.438024 0.888223 -0.138554 0.449471 0.882484 0.138522 0.449672 0.882387 0.141777 0.438307 0.887573 0.39482 0.469115 0.789967 0.411274 0.438637 0.799031 0.607572 0.493425 0.622404 0.637777 0.450819 0.624502 0.757049 0.521018 0.394229 0.750035 0.529595 0.396202 -0.031971 0.89624 0.442416 -0.0700865 0.901112 0.427884 -0.129529 0.867835 0.479671 -0.24586 0.904815 0.347653 -0.176686 0.932132 0.316088 -0.14873 0.916778 0.370671 -0.195539 0.885565 0.421354 -0.125345 0.911396 0.391977 -0.0985152 0.903963 0.416109 0.16952 0.928259 0.331055 0.149496 0.917006 0.369799 0.195303 0.886024 0.420497 0.126026 0.911572 0.39135 0.09843 0.903901 0.416263 0.12937 0.868408 0.478676 0.0698923 0.901035 0.428078 0.0308732 0.895976 0.443028 0.0472998 0.872475 0.486364 0.00366476 0.89797 0.440041 -0.977158 0.0697294 0.200748 -0.769338 0.514245 0.37904 -0.8893 0.285887 0.356952 -0.91275 0.210104 0.350347 -0.854334 0.362166 0.372759 -0.173057 0.15575 0.972519 0.0263862 0.153027 0.98787 0.157387 0.31367 0.936398 0.201227 0.13719 0.96989 0.404445 0.162728 0.899969 -0.572879 0.711685 0.406589 -0.494735 0.779751 0.3837 -0.411518 0.731233 0.544015 -0.394333 0.750257 0.530675 -0.261782 0.713507 0.649906 -0.25502 0.726922 0.637612 -0.0888234 0.706966 0.701647 -0.0885864 0.711748 0.696827 0.0887094 0.711869 0.696688 0.0907496 0.707126 0.70124 0.253342 0.726888 0.63832 0.264652 0.714263 0.64791 0.392116 0.749802 0.532956 0.414277 0.732769 0.539838 0.490664 0.777603 0.393171 0.575784 0.717502 0.391999 -0.312178 0.938442 -0.14789 0.231214 0.861954 -0.451194 0.682993 0.193068 -0.704447 0.144782 0.980726 0.131202 0.256591 0.930738 0.260555 0.245183 0.961119 0.12703 0.182191 0.959622 0.214317 0.19619 0.945194 0.260992 -0.0206768 0.995996 0.0869738 -0.0316179 0.997738 0.0593229 0.0235468 0.997964 0.0592779 0.0214002 0.998616 0.0480386 0.0654242 0.994532 0.0814017 0.0659468 0.995251 0.0715954 0.116529 0.988645 0.0948809 -0.122597 0.987639 0.0976674 -0.172437 0.983847 0.0480797 -0.148724 0.979493 0.135918 -0.257514 0.932805 0.252113 -0.947319 0.104062 -0.302917 -0.965597 0.0872284 -0.244975 -0.934822 0.353732 0.0313282 -0.989298 0.139644 -0.0422863 -0.974719 0.222555 -0.0197978 -0.950793 0.309624 0.0111992 -0.911578 0.409147 0.0403022 -0.889221 0.453833 0.0576342 -0.804859 0.584576 0.102336 -0.65234 0.51538 -0.55573 -0.616472 0.592294 -0.518797 -0.755949 0.101856 -0.646658 -0.59736 0.338365 -0.727097 -0.700946 0.257987 -0.664919 -0.696812 0.270493 -0.664294 -0.635529 0.204471 -0.74451 0.300922 0.628514 -0.717228 0.298911 0.619001 -0.726285 0.102787 0.630868 -0.769051 0.101669 0.62768 -0.771804 -0.104101 0.627595 -0.771549 -0.102516 0.631006 -0.768975 -0.303977 0.618552 -0.724563 -0.298405 0.628743 -0.718078 0.805503 0.583172 0.105242 0.782751 0.612163 0.112059 0.911765 0.408494 0.0426185 0.976236 0.216692 -0.00272011 0.744263 0.62854 -0.225855 0.71222 0.672175 -0.202293 0.833673 0.445021 -0.327026 0.806466 0.508192 -0.302246 0.878759 0.24785 -0.407864 0.862351 0.328289 -0.385458 0.787507 0.543336 -0.290894 0.794279 0.0889332 -0.601009 0.755757 0.101927 -0.646871 0.594577 0.338749 -0.729197 0.697237 0.260426 -0.667862 0.652078 0.515426 -0.555995 0.616276 0.592232 -0.5191 0.582986 0.692179 -0.425458 0.183192 0.967256 0.17566 0.44952 0.893204 0.0108816 0.310672 0.938673 -0.149583 -0.782767 0.61163 0.114825 -0.600954 0.779981 0.174599 -0.572557 0.80007 0.179072 -0.199169 0.941653 0.271333 -0.181741 0.959989 0.213052 -0.583192 0.692129 -0.425258 -0.476175 0.835239 -0.275015 -0.278179 0.955102 -0.101966 -0.322551 0.931838 -0.166251 -0.170736 0.956176 -0.237859 -0.0687083 0.994977 0.0727953 -0.0868653 0.995081 0.0476183 -0.860773 0.0626121 -0.505124 -0.783223 0.552028 -0.286054 -0.876197 0.249442 -0.41238 -0.865276 0.327029 -0.379935 -0.831263 0.44658 -0.33101 -0.809099 0.506956 -0.297244 -0.7421 0.629927 -0.229083 -0.714045 0.671595 -0.197737 -0.61122 0.783411 -0.112593 -0.511089 0.859178 -0.0245062 -0.449504 0.89321 0.0110887 -0.240129 0.960148 0.143019 -0.177025 0.969639 0.168707 0.970601 0.198291 -0.136432 0.965611 0.087171 -0.244942 0.902653 0.134571 -0.408789 0.927383 0.373422 0.0227197 0.764085 0.636773 0.103412 0.992323 0.121133 0.0249258 0.329176 0.147284 -0.932711 0.344086 0.206583 -0.915931 0.112208 0.221291 -0.968731 0.111165 0.217715 -0.969661 -0.113351 0.213921 -0.970252 -0.101617 0.254979 -0.961592 -0.331172 0.1707 -0.928001 -0.266745 0.405918 -0.874116 -0.384359 0.219038 -0.896822 0.601171 0.780965 0.16937 0.573228 0.798968 0.181822 0.511018 0.859215 -0.0246943 0.611161 0.783423 -0.112829 0.426034 0.843776 -0.326401 0.230007 0.972998 0.0192666 0.372027 0.843932 -0.38649 0.478927 0.620394 -0.621079 0.478256 0.605779 -0.635848 0.530541 0.225023 -0.817246 0.539352 0.263304 -0.799857 0.191277 0.981285 0.0221835 0.323642 0.931571 -0.165625 0.169948 0.956298 -0.237933 0.185012 0.914455 -0.359921 0.0697319 0.920402 -0.384704 0.0691226 0.919434 -0.387121 -0.0706858 0.919379 -0.386969 -0.0696805 0.920339 -0.384864 -0.185972 0.914323 -0.359761 -0.232181 0.861897 -0.450806 -0.372687 0.843849 -0.386036 -0.484424 0.604653 -0.632241 -0.474478 0.621057 -0.623826 -0.531599 0.19857 -0.823391 -0.525007 0.226039 -0.820533 -0.919377 0.110988 0.377397 0.247371 0.908635 0.336437 -0.0327121 0.890675 0.453462 0.892479 0.276916 0.356088 0.97718 0.0697655 0.20063 0.769684 0.513887 0.378821 0.416144 0.42581 0.803437 0.557827 0.57293 0.600483 0.844289 0.0654103 0.531882 0.919252 0.111816 0.377455 0.889074 0.286753 0.356821 0.76538 0.212211 0.607585 0.669168 0.390232 0.632403 0.672245 0.16967 0.720624 0.560971 0.138761 0.816123 -0.172101 0.133456 0.975997 -0.744993 0.19036 0.639334 -0.741367 0.199678 0.640706 -0.840756 0.0632942 0.537702 -0.542786 0.589597 0.59813 -0.29229 0.810111 0.50822 -0.49895 0.122143 0.85798 -0.436469 0.47341 0.7651 -0.384412 0.16057 0.90909 -0.750382 0.530153 0.394798 -0.756611 0.520784 0.395378 -0.632743 0.448364 0.631353 -0.611364 0.494328 0.61796 -0.406217 0.437378 0.802302 -0.397835 0.469197 0.788405 -0.13855 0.438024 0.888223 -0.138554 0.449464 0.882488 0.138521 0.449679 0.882384 0.141776 0.438314 0.88757 0.39481 0.469135 0.789961 0.411274 0.438637 0.799031 0.607575 0.493426 0.622401 0.63778 0.450821 0.624498 0.757047 0.521017 0.394234 0.750034 0.529593 0.396207 -0.0319709 0.896241 0.442414 -0.0700833 0.901114 0.427881 -0.129529 0.867835 0.479671 -0.24586 0.904816 0.347651 -0.176686 0.932132 0.316087 -0.14873 0.916778 0.370671 -0.195539 0.885565 0.421354 -0.125345 0.911396 0.391977 -0.0985152 0.903963 0.416109 0.16952 0.928259 0.331055 0.149496 0.917006 0.369799 0.195303 0.886024 0.420497 0.126026 0.911572 0.39135 0.09843 0.903901 0.416263 0.129367 0.868412 0.47867 0.0698905 0.901037 0.428075 0.0308726 0.895977 0.443027 0.0472998 0.872475 0.486364 0.00366476 0.89797 0.440041 -0.977158 0.0697294 0.200748 -0.769338 0.514245 0.37904 -0.8893 0.285887 0.356952 -0.91275 0.210104 0.350347 -0.854285 0.362269 0.372771 -0.173057 0.15576 0.972517 0.0263862 0.153026 0.98787 0.157388 0.313661 0.9364 0.201228 0.137178 0.969891 0.404449 0.162704 0.899971 -0.57288 0.711686 0.406585 -0.494736 0.779752 0.383697 -0.411518 0.731233 0.544015 -0.394333 0.750257 0.530675 -0.261782 0.713507 0.649906 -0.25502 0.726922 0.637612 -0.0888234 0.706966 0.701647 -0.0885864 0.711748 0.696827 0.0887087 0.711869 0.696688 0.0907504 0.707122 0.701244 0.25335 0.726878 0.638327 0.264644 0.714272 0.647904 0.392101 0.749815 0.532949 0.414279 0.73277 0.539835 0.490662 0.777602 0.393174 0.575783 0.717501 0.392003 0.978433 0.0721937 -0.193539 -0.312178 0.938442 -0.14789 0.231207 0.861963 -0.45118 0.79426 0.0887939 -0.601055 -0.947319 0.104062 -0.302917 0.144782 0.980726 0.131202 0.256591 0.930737 0.260556 0.245183 0.961119 0.12703 0.182178 0.959621 0.214335 0.196171 0.945198 0.260993 -0.0206775 0.995996 0.0869727 -0.0316182 0.997738 0.0593229 0.0235462 0.997964 0.0592779 0.0213997 0.998616 0.0480393 0.0654233 0.994532 0.0814042 0.0659461 0.995251 0.0715951 0.116529 0.988645 0.0948809 -0.122601 0.987639 0.0976633 -0.172437 0.983847 0.0480797 -0.148724 0.979493 0.135918 -0.257505 0.932807 0.252114 -0.804818 0.584631 0.10235 -0.889327 0.453634 0.0575619 -0.911611 0.409077 0.0402814 -0.950765 0.309709 0.0112236 -0.974701 0.222639 -0.0197747 -0.99693 0.0359041 -0.0695855 -0.988758 0.141316 -0.0488625 -0.65234 0.51538 -0.55573 -0.616462 0.592314 -0.518786 -0.635551 0.204466 -0.744492 -0.708405 0.283838 -0.646219 -0.677998 0.124753 -0.7244 -0.692341 0.318486 -0.64748 0.300919 0.628514 -0.717229 0.298909 0.61901 -0.726278 0.102786 0.630872 -0.769049 0.101669 0.627686 -0.771799 -0.104103 0.627588 -0.771554 -0.102515 0.631006 -0.768975 -0.30398 0.618552 -0.724562 -0.298409 0.628743 -0.718077 0.976236 0.216692 -0.00272011 0.911765 0.408494 0.0426185 0.782716 0.612205 0.112074 0.616277 0.592249 -0.519079 0.583004 0.692147 -0.425486 0.744292 0.628496 -0.225883 0.902653 0.134571 -0.408789 0.78753 0.543294 -0.290911 0.862353 0.328288 -0.385453 0.878762 0.247849 -0.407859 0.806469 0.508191 -0.302241 0.692102 0.120724 -0.711632 0.686039 0.192262 -0.701702 0.692073 0.318445 -0.647787 0.652051 0.515516 -0.555943 0.833628 0.445142 -0.326977 0.712218 0.672176 -0.202297 0.805504 0.58317 0.105247 0.183192 0.967256 0.17566 0.44952 0.893204 0.0108816 0.310671 0.938674 -0.149584 -0.782732 0.611673 0.114834 -0.60099 0.779956 0.174585 -0.572576 0.800058 0.179061 -0.199169 0.941653 0.271332 -0.181742 0.959988 0.213057 -0.583174 0.692162 -0.42523 -0.476175 0.835239 -0.275015 -0.278184 0.9551 -0.10197 -0.322539 0.931846 -0.16623 -0.170733 0.95618 -0.237847 -0.0687093 0.994978 0.0727923 -0.0868668 0.995081 0.0476143 -0.86078 0.0626885 -0.505101 -0.783223 0.552028 -0.286054 -0.876197 0.249442 -0.41238 -0.865263 0.3271 -0.379903 -0.831266 0.446579 -0.331006 -0.809125 0.506897 -0.297274 -0.742071 0.629971 -0.229056 -0.714012 0.671638 -0.197708 -0.61122 0.783411 -0.112593 -0.511105 0.859168 -0.0245193 -0.449502 0.893211 0.0110864 -0.240146 0.960145 0.143008 -0.177023 0.96964 0.168705 0.927383 0.373422 0.0227197 0.764085 0.636773 0.103412 0.99231 0.121235 0.0249415 0.329176 0.14727 -0.932714 0.344089 0.206583 -0.915929 0.112208 0.221291 -0.968731 0.111165 0.217715 -0.969661 -0.11335 0.213921 -0.970252 -0.101617 0.254975 -0.961593 -0.331176 0.170685 -0.928003 -0.318136 0.225973 -0.92072 0.601207 0.780939 0.169362 0.573249 0.798953 0.18182 0.511035 0.859205 -0.0247043 0.611193 0.783395 -0.112854 0.426047 0.843759 -0.326428 0.230007 0.972998 0.0192666 0.372021 0.843946 -0.386466 0.478928 0.620408 -0.621065 0.478256 0.605779 -0.635848 0.530541 0.225001 -0.817252 0.539353 0.263282 -0.799863 0.191277 0.981285 0.0221835 0.323656 0.931562 -0.165645 0.169952 0.956294 -0.237945 0.185015 0.914452 -0.359927 0.0697303 0.920401 -0.384707 0.0691218 0.919434 -0.387121 -0.0706877 0.919379 -0.386969 -0.0696811 0.92034 -0.384862 -0.185969 0.914326 -0.359755 -0.232188 0.861888 -0.45082 -0.372698 0.843834 -0.386058 -0.484424 0.604653 -0.632241 -0.474468 0.621073 -0.623818 -0.531594 0.198593 -0.823389 -0.525007 0.226039 -0.820533 -0.919377 0.110988 0.377397 0.247372 0.908636 0.336435 -0.0327119 0.890675 0.453462 0.892479 0.276916 0.356088 0.977165 0.0698581 0.200672 0.769699 0.51387 0.378815 0.416144 0.425818 0.803433 0.557852 0.572895 0.600493 0.844281 0.0654062 0.531895 0.919256 0.111819 0.377446 0.889043 0.286841 0.356827 0.765348 0.212284 0.6076 0.669168 0.390232 0.632403 0.672248 0.169711 0.720611 0.560965 0.138792 0.816122 -0.172101 0.133456 0.975997 -0.745005 0.190319 0.639332 -0.741392 0.199605 0.640699 -0.840756 0.0632942 0.537702 -0.542786 0.589597 0.59813 -0.29229 0.810111 0.50822 -0.498955 0.122115 0.857981 -0.436477 0.473392 0.765107 -0.384422 0.160571 0.909086 -0.750349 0.530194 0.394805 -0.756586 0.520814 0.395386 -0.63273 0.448393 0.631345 -0.611364 0.494328 0.61796 -0.406217 0.437378 0.802302 -0.397835 0.469197 0.788405 -0.138549 0.438023 0.888223 -0.138553 0.449471 0.882485 0.138522 0.449672 0.882387 0.141775 0.438314 0.88757 0.394812 0.469135 0.789959 0.411277 0.438638 0.79903 0.607572 0.493425 0.622404 0.637795 0.450793 0.624503 0.757074 0.520988 0.394222 0.750002 0.529636 0.396211 -0.0319706 0.896241 0.442414 -0.0700846 0.901114 0.42788 -0.129524 0.867841 0.479663 -0.245851 0.904818 0.347651 -0.176677 0.932135 0.316086 -0.148723 0.916781 0.370667 -0.195528 0.885571 0.421346 -0.125346 0.911396 0.391976 -0.0985142 0.903962 0.41611 0.169511 0.928262 0.331053 0.149491 0.917009 0.369793 0.195307 0.886021 0.420501 0.126025 0.911571 0.391351 0.098431 0.903901 0.416262 0.129376 0.868403 0.478684 0.0698909 0.901035 0.428079 0.0308734 0.895976 0.443028 0.0472989 0.872477 0.48636 0.00366489 0.89797 0.440041 -0.97717 0.0696311 0.200725 -0.769361 0.514208 0.379043 -0.889331 0.285799 0.356946 -0.912727 0.21019 0.350356 -0.854384 0.362066 0.372741 -0.173057 0.15575 0.972519 0.0263875 0.153027 0.98787 0.157387 0.31366 0.936401 0.201227 0.137178 0.969892 0.404449 0.162704 0.899971 -0.572912 0.711656 0.406593 -0.494755 0.779737 0.383703 -0.411532 0.731219 0.544022 -0.394335 0.750257 0.530673 -0.261782 0.713507 0.649906 -0.25502 0.726922 0.637612 -0.0888228 0.706966 0.701647 -0.0885857 0.711748 0.696827 0.0887101 0.711869 0.696688 0.0907487 0.707129 0.701237 0.253335 0.726898 0.638311 0.264645 0.714273 0.647902 0.392099 0.749815 0.532951 0.414277 0.732769 0.539838 0.490664 0.777603 0.393171 0.575818 0.717476 0.391998 0.00117008 0.960865 0.277016 0.00262096 0.960962 0.27667 0.00335207 0.961038 0.276395 0.00330017 0.961027 0.276433 0.00240862 0.960799 0.277235 0.00140074 0.960316 0.278911 0 0.959441 0.281909 0 0.959437 0.281924 -0.00142539 0.960327 0.278874 -0.00232872 0.960777 0.277314 -0.00338115 0.961046 0.276369 -0.00334431 0.961039 0.276394 -0.00233854 0.960933 0.27677 -0.000715641 0.960865 0.277018 -0.00155419 0.956447 0.291903 -0.00254112 0.956322 0.292304 -0.00269298 0.956294 0.292395 -0.00197625 0.956511 0.291689 -0.00119223 0.956902 0.29041 0 0.957769 0.287539 0 0.957786 0.287481 0.00127583 0.956863 0.290537 0.00204552 0.956487 0.291767 0.00264023 0.956308 0.29235 0.00262726 0.95631 0.292343 0.00137531 0.956467 0.291837 -0.000114984 0.956477 0.291806 0.0278516 0 0.999612 0.167508 -0.00168061 0.985869 0.70527 1.08568e-05 0.708939 0.584668 -0.00323895 0.811266 0.550888 -0.00603384 0.834557 0.427083 -0.000634155 0.904212 0.210762 0.00101195 0.977537 0.778479 -3.69781e-06 0.627671 0.880585 -0.00477871 0.473865 0.854792 -0.00884018 0.518895 0.977424 0.000537684 -0.211287 0.999967 -0.00420976 -0.00690058 0.999989 -0.00473467 0 0.982954 5.83814e-06 0.183853 0.935057 1.96745e-05 0.354496 0.897885 -0.00173986 -0.440227 0.880586 -0.0045288 -0.473865 0.786865 -0.000339382 -0.617125 0.682611 0.00051134 -0.730782 0.550887 -0.0055941 -0.834561 0.529261 -0.00403163 -0.848449 0.335744 0.00158944 -0.941952 0.167508 -0.00253366 -0.985868 0.108138 0 -0.994136 0.00117007 0.960865 0.277016 0.00262096 0.960962 0.27667 0.00335204 0.961038 0.276395 0.00330017 0.961027 0.276433 0.00240865 0.960799 0.277235 0.00140073 0.960316 0.278911 0 0.959441 0.281909 0 0.959437 0.281924 -0.00142534 0.960327 0.278874 -0.00232872 0.960777 0.277314 -0.00338115 0.961046 0.276369 -0.00334431 0.961039 0.276394 -0.00233856 0.960933 0.27677 -0.000715652 0.960864 0.277018 -0.00155418 0.956447 0.291903 -0.00254117 0.956322 0.292304 -0.00269295 0.956294 0.292395 -0.00197626 0.956511 0.291689 -0.00119221 0.956902 0.29041 0 0.957769 0.287539 0 0.957786 0.287481 0.00127583 0.956863 0.290537 0.00204551 0.956487 0.291767 0.00264026 0.956308 0.29235 0.00262721 0.95631 0.292343 0.00137532 0.956467 0.291837 -0.00011498 0.956477 0.291806 0.0278503 0 0.999612 0.167507 -0.00168069 0.98587 0.210764 0.00101206 0.977536 0.550893 -0.00407091 0.834566 0.585204 -0.00759934 0.810851 0.427083 -0.000633911 0.904212 0.935054 1.96753e-05 0.354506 0.8548 -0.00883896 0.518882 0.880585 -0.00477871 0.473865 0.778479 -3.69781e-06 0.627671 0.705257 1.08594e-05 0.708952 0.982958 5.83649e-06 0.183832 0.999989 -0.00473412 0 0.999967 -0.00420999 -0.00689037 0.747393 -2.57395e-07 -0.664382 0.786879 -0.000339913 -0.617108 0.897512 -0.0054201 -0.440956 0.880593 -0.00208863 -0.473869 0.963903 4.879e-06 -0.266253 0.982088 -2.79517e-06 -0.188421 0.672575 1.32563e-05 -0.740029 0.550887 -0.0055941 -0.834561 0.529261 -0.00403163 -0.848449 0.335741 0.00158953 -0.941953 0.167506 -0.0025336 -0.985868 0.108138 0 -0.994136 0.00117008 0.960865 0.277016 0.00262096 0.960962 0.27667 0.00335201 0.961038 0.276395 0.00330023 0.961027 0.276433 0.00240863 0.960799 0.277235 0.00140073 0.960316 0.278911 0 0.959441 0.281909 0 0.959437 0.281924 -0.00142536 0.960327 0.278874 -0.00232872 0.960777 0.277314 -0.003383 0.961046 0.276367 -0.00334279 0.961039 0.276394 -0.00229605 0.960929 0.276786 -0.000777291 0.960864 0.277018 -0.00155418 0.956447 0.291903 -0.00254117 0.956322 0.292304 -0.00269295 0.956294 0.292395 -0.00197626 0.956511 0.291689 -0.00119221 0.956902 0.29041 0 0.957769 0.287539 0 0.957786 0.287481 0.00127583 0.956863 0.290537 0.00204551 0.956487 0.291767 0.00264026 0.956308 0.29235 0.00262726 0.95631 0.292343 0.00137531 0.956467 0.291837 -0.00011498 0.956477 0.291806 0.0278503 0 0.999612 0.167507 -0.00168069 0.98587 0.210764 0.00101206 0.977536 0.550893 -0.00407091 0.834566 0.585204 -0.00759934 0.810851 0.427083 -0.000633911 0.904212 0.935057 1.96745e-05 0.354496 0.8548 -0.00883943 0.518882 0.880587 -0.00477883 0.473861 0.778468 -3.25882e-06 0.627684 0.70527 1.12525e-05 0.708939 0.982954 5.83814e-06 0.183853 0.999989 -0.00473467 0 0.999967 -0.00421053 -0.0068905 0.747441 -2.66624e-07 -0.664328 0.786879 -0.000339502 -0.617108 0.897512 -0.00541963 -0.440956 0.880595 -0.00208858 -0.473865 0.963889 4.36939e-06 -0.266305 0.982088 -3.31968e-06 -0.188422 0.672575 1.32563e-05 -0.740029 0.550887 -0.0055941 -0.834561 0.529261 -0.00403163 -0.848449 0.335741 0.00158953 -0.941953 0.167506 -0.0025336 -0.985868 0.108138 0 -0.994136 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.667055 0 0.745009 0.667055 0 0.745009 0.424264 0 0.905539 0.424264 0 0.905539 0.145533 0 0.989353 0.145533 0 0.989353 0.14553 0 0.989354 0.217084 0.0471387 0.975014 0.667054 0 0.745009 0.610241 0.0471385 0.790812 0.4892 0 0.872172 0.357067 0 0.934079 0 0 1 0 0 1 -0.693805 0 0.720163 -0.610062 0.0530371 0.790577 -0.109316 0 0.994007 -0.21702 0.0530392 0.974725 -0.32273 0 0.946491 -0.520716 0 0.85373 0.709416 0 0.70479 0.644171 -0.050997 0.763179 0.575655 0 0.817693 0.424267 0 0.905537 0.34294 -0.0509972 0.937972 0.25987 0 0.965644 0.0875197 0 0.996163 0 -0.0509969 0.998699 -0.0875197 0 0.996163 -0.343385 0 0.939195 -0.258534 -0.101214 0.960685 -0.424267 0 0.905537 -0.645011 0 0.764173 -0.572703 -0.101209 0.813491 -0.709414 0 0.704792 0.109316 0 0.994007 0.21702 0.0530392 0.974725 0.693807 0 0.720161 0.610062 0.0530384 0.790577 0.520714 0 0.853731 0.32273 0 0.946491 0 0 1 0 0 1 -0.693807 0 0.720161 -0.610062 0.0530384 0.790577 -0.109316 0 0.994007 -0.21702 0.0530392 0.974725 -0.32273 0 0.946491 -0.520714 0 0.853731 0.667056 0 0.745008 0.644753 -0.0283247 0.763866 0.424155 0.0226915 0.905305 0.343032 -0.0453294 0.938229 0.231558 0 0.972821 0 0 1 0.0870702 -0.101212 0.991047 -0.0875197 0 0.996163 -0.343385 0 0.939195 -0.258536 -0.101212 0.960685 -0.709416 0 0.70479 -0.644173 -0.0509957 0.763178 -0.575659 0 0.81769 -0.424264 0 0.905538 0.109316 0 0.994007 0.21702 0.0530392 0.974725 0.693802 0 0.720165 0.610062 0.0530359 0.790577 0.520718 0 0.853729 0.32273 0 0.946491 0 0 1 0 0 1 -0.693807 0 0.720161 -0.610062 0.0530384 0.790577 -0.109316 0 0.994007 -0.21702 0.0530392 0.974725 -0.32273 0 0.946491 -0.520714 0 0.853731 -0.667055 0 -0.745009 -0.667055 0 -0.745009 -0.424266 0 -0.905538 -0.424266 0 -0.905538 -0.14553 0 -0.989354 -0.14553 0 -0.989354 -0.145531 0 -0.989354 -0.217084 0.0471382 -0.975014 -0.667054 0 -0.745009 -0.610242 0.0471373 -0.790811 -0.489205 0 -0.872169 -0.357064 0 -0.93408 0 0 -1 0 0 -1 0.693802 0 -0.720165 0.610062 0.0530359 -0.790577 0.109321 0 -0.994007 0.21702 0.0530372 -0.974725 0.322726 0 -0.946492 0.520718 0 -0.853729 -0.667055 0 -0.745009 -0.667055 0 -0.745009 -0.424266 0 -0.905538 -0.424266 0 -0.905538 -0.14553 0 -0.989354 -0.14553 0 -0.989354 -0.145531 0 -0.989354 -0.217084 0.0471382 -0.975014 -0.667054 0 -0.745009 -0.610242 0.0471373 -0.790811 -0.489205 0 -0.872169 -0.357064 0 -0.93408 0 0 -1 0 0 -1 0.693807 0 -0.720161 0.610062 0.0530384 -0.790577 0.109321 0 -0.994007 0.21702 0.0530372 -0.974725 0.322726 0 -0.946492 0.520714 0 -0.853731 -0.667056 0 -0.745008 -0.667056 0 -0.745008 -0.424264 0 -0.905539 -0.424264 0 -0.905539 -0.14553 0 -0.989354 -0.14553 0 -0.989354 -0.109321 0 -0.994007 -0.21702 0.0530372 -0.974725 -0.693805 0 -0.720163 -0.610062 0.0530371 -0.790577 -0.520716 0 -0.85373 -0.322726 0 -0.946492 0 0 -1 0 0 -1 0.693805 0 -0.720163 0.610061 0.0530378 -0.790578 0.10932 0 -0.994007 0.21702 0.0530376 -0.974725 0.322727 0 -0.946492 0.520714 0 -0.853731 0.00117008 0.960865 0.277016 0.00262096 0.960962 0.27667 0.00335204 0.961038 0.276395 0.0033002 0.961027 0.276433 0.00240864 0.960799 0.277235 0.00140073 0.960316 0.278911 0 0.959441 0.281909 0 0.959437 0.281924 -0.00142535 0.960327 0.278874 -0.00232872 0.960777 0.277314 -0.003383 0.961046 0.276367 -0.00334279 0.961039 0.276394 -0.00233856 0.960933 0.27677 -0.000715646 0.960864 0.277018 -0.00155418 0.956447 0.291903 -0.00254117 0.956322 0.292304 -0.00269297 0.956294 0.292395 -0.00197625 0.956511 0.291688 -0.00119221 0.956902 0.29041 0 0.957769 0.28754 0 0.957786 0.287481 0.00127583 0.956863 0.290537 0.0020455 0.956487 0.291767 0.00264027 0.956308 0.29235 0.00262724 0.95631 0.292343 0.00137531 0.956467 0.291837 -0.00011498 0.956477 0.291806 0.0278503 0 0.999612 0.167507 -0.00168069 0.98587 0.210764 0.00101206 0.977536 0.550893 -0.00407091 0.834566 0.585206 -0.00759964 0.810849 0.42708 -0.000633883 0.904214 0.935056 1.96749e-05 0.354501 0.8548 -0.00883919 0.518882 0.880586 -0.00477877 0.473863 0.778474 -3.47831e-06 0.627677 0.705264 1.10559e-05 0.708945 0.982956 5.83731e-06 0.183842 0.999989 -0.00473439 0 0.999967 -0.00421026 -0.00689044 0.747417 -2.6201e-07 -0.664355 0.786879 -0.000339707 -0.617108 0.897512 -0.00541987 -0.440956 0.880594 -0.0020886 -0.473867 0.963889 4.36939e-06 -0.266305 0.98209 -3.32078e-06 -0.18841 0.672578 1.32557e-05 -0.740026 0.550887 -0.00559424 -0.834561 0.529258 -0.00403153 -0.848452 0.335742 0.00158948 -0.941953 0.167506 -0.00253365 -0.985868 0.108138 0 -0.994136 -0.880595 -2.12196e-05 0.473869 -0.777174 -0.0193918 0.628987 -0.851 -0.00924252 0.525085 -0.167507 0 0.985871 -0.182754 0.00113048 0.983158 -0.405723 -0.000442314 0.913996 -0.550891 -0.00507002 0.834562 -0.564457 -0.00379198 0.825454 -0.704909 1.96678e-05 0.709298 -0.0988534 0 -0.995102 -0.167506 -0.00268787 -0.985867 -0.514071 -0.00292571 -0.857743 -0.375151 1.04754e-06 -0.926964 -0.264699 1.49895e-05 -0.964331 -0.855575 -0.00101931 -0.517678 -0.747565 9.71044e-09 -0.664189 -0.550896 3.71728e-05 -0.834574 -0.691424 -0.0174351 -0.722239 -0.623467 -0.0110109 -0.781772 -0.935013 2.35755e-05 0.354613 -0.982932 9.16151e-06 0.183969 -0.999989 -0.00473439 0 -0.998075 -9.11786e-06 -0.0620129 -0.880595 1.76999e-05 -0.473869 -0.962264 -0.0215963 -0.271258 -0.943339 -0.0160377 -0.331443 0.145531 0 -0.989354 0.145531 0 -0.989354 0.424264 0 -0.905539 0.424264 0 -0.905539 0.667055 0 -0.745009 0.667055 0 -0.745009 0.14553 0 -0.989354 0.14553 0 -0.989354 0.424264 0 -0.905539 0.424264 0 -0.905539 0.667057 0 -0.745007 0.667057 0 -0.745007 0.142315 0 -0.989821 0.194841 -0.0507175 -0.979523 0.62747 0 -0.778641 0.554453 -0.0633911 -0.829797 0.463506 0 -0.886094 0.332689 0 -0.943037 0.73188 0 -0.681434 0.840504 -0.0422171 -0.540158 0.831282 -0.0211223 -0.55545 0.916897 0 -0.399123 0.964371 0 -0.264555 0.979068 -0.0591619 -0.194748 0.997451 0 -0.0713491 0.997451 0 0.0713491 0.979068 -0.0591619 0.194748 0.964371 0 0.264555 0.916897 0 0.399123 0.831282 -0.0211223 0.55545 0.840504 -0.0422172 0.540158 0.73188 0 0.681434 0.555571 0 0.831469 0.623296 -0.115155 0.773461 0.142317 0 0.989821 0.194841 -0.0507155 0.979523 0.332684 0 0.943038 0.463506 0 0.886094 -0.145532 0 0.989354 -0.145532 0 0.989354 -0.424266 0 0.905538 -0.424266 0 0.905538 -0.667054 0 0.74501 -0.667054 0 0.74501 0.145531 0 -0.989354 0.145531 0 -0.989354 0.424264 0 -0.905539 0.424264 0 -0.905539 0.667056 0 -0.745008 0.667056 0 -0.745008 -0.142317 0 0.989821 -0.19484 -0.0507154 0.979523 -0.332682 0 0.943039 -0.463506 0 0.886094 -0.554453 -0.0633911 0.829797 -0.841101 -0.0190313 0.540543 -0.830868 -0.0380352 0.555169 -0.731893 0 0.68142 -0.62747 0 0.778641 -0.916904 0 0.399108 -0.964369 0 0.264562 -0.979067 -0.0591667 0.194749 -0.964369 0 -0.264562 -0.979067 -0.0591667 -0.194749 -0.997452 0 -0.0713404 -0.997452 0 0.0713404 -0.916904 0 -0.399108 -0.841101 -0.0190313 -0.540543 -0.830868 -0.0380352 -0.555169 -0.731893 0 -0.68142 -0.555571 0 -0.831469 -0.623296 -0.115155 -0.773461 -0.142315 0 -0.989821 -0.19484 -0.0507174 -0.979523 -0.332687 0 -0.943037 -0.463506 0 -0.886094 -0.880595 -2.09724e-05 0.47387 -0.777162 -0.0193933 0.629001 -0.851002 -0.00924234 0.525081 -0.167507 0 0.985871 -0.182754 0.00113043 0.983158 -0.405723 -0.00044243 0.913996 -0.550891 -0.00507018 0.834562 -0.564459 -0.00379192 0.825452 -0.704916 1.98643e-05 0.709291 -0.0988534 0 -0.995102 -0.167506 -0.00268787 -0.985867 -0.514071 -0.00292584 -0.857743 -0.375151 9.50742e-07 -0.926964 -0.264697 1.49215e-05 -0.964332 -0.855574 -0.00101952 -0.51768 -0.747541 1.48523e-08 -0.664216 -0.550896 3.71728e-05 -0.834574 -0.691424 -0.0174351 -0.722239 -0.623478 -0.0110119 -0.781763 -0.935014 2.37023e-05 0.35461 -0.982933 9.29572e-06 0.183964 -0.999989 -0.00473412 0 -0.998075 -8.98471e-06 -0.0620111 -0.880595 1.78176e-05 -0.47387 -0.962264 -0.0215963 -0.271258 -0.943346 -0.0160397 -0.331423 -0.880595 -2.09724e-05 0.47387 -0.777162 -0.0193933 0.629001 -0.851002 -0.00924234 0.525081 -0.167507 0 0.985871 -0.182755 0.00113053 0.983158 -0.405723 -0.000442199 0.913996 -0.550891 -0.00506987 0.834562 -0.564454 -0.00379203 0.825456 -0.704916 1.98643e-05 0.709291 -0.0988534 0 -0.995102 -0.167506 -0.00268787 -0.985867 -0.514071 -0.00292557 -0.857743 -0.37516 9.49503e-07 -0.92696 -0.264697 1.49215e-05 -0.964332 -0.855574 -0.00101908 -0.51768 -0.747588 4.5683e-09 -0.664162 -0.550896 3.71728e-05 -0.834574 -0.691424 -0.0174351 -0.722239 -0.623456 -0.0110099 -0.781781 -0.935014 2.37023e-05 0.35461 -0.982933 9.29572e-06 0.183964 -0.999989 -0.00473412 0 -0.998075 -8.98471e-06 -0.0620111 -0.880595 1.78176e-05 -0.47387 -0.962264 -0.0215963 -0.271258 -0.943336 -0.0160371 -0.33145 -0.935014 2.42143e-05 0.35461 -0.982933 9.83427e-06 0.183964 -0.999989 -0.00473358 0 -0.407386 -0.0177462 0.913084 -0.564454 -0.00379172 0.825456 -0.704916 2.02598e-05 0.709291 -0.880595 -2.04783e-05 0.47387 -0.777162 -0.0193929 0.629001 -0.851002 -0.00924187 0.525082 -0.550897 -0.00154624 0.834572 -0.167505 0.0012334 0.98587 -0.182808 0 0.983149 -0.0988534 0 -0.995102 -0.167505 -0.00268782 -0.985868 -0.310239 0.00130729 -0.950658 -0.514071 -0.00292558 -0.857743 -0.9964 0.00172919 -0.0847548 -0.944655 -0.000603315 -0.328064 -0.880585 -0.0047221 -0.473865 -0.855577 -0.00101956 -0.517674 -0.550896 0.00145068 -0.834573 -0.701197 -0.0183928 -0.71273 -0.623478 -0.0110116 -0.781763 0.0280299 0.980413 0.19495 0.0796348 0.828783 0.553875 0.1187 0.551675 0.825569 0.139634 0.193194 -0.971174 0.569782 0.418834 0.707054 0.642525 0.193189 0.741512 0.454667 0.194354 0.869197 0.379361 0.407498 0.830681 0.32631 0.194815 0.92497 0.139635 0.193178 0.971177 0.139636 0.193189 0.971175 0.717828 0.195013 0.668351 0.825401 0.193224 0.530451 0.825404 0.193187 0.530459 0.899283 0.195069 0.391456 0.915642 0.298855 0.268859 0.946127 0.19359 0.25955 0.978388 0.194573 0.0699855 0.907497 0.420059 0 0.978388 0.194573 -0.0699855 0.941426 0.193142 -0.276429 0.916028 0.312642 -0.251293 0.899283 0.195069 -0.391456 0.825407 0.193188 -0.530455 0.8254 0.193216 -0.530455 0.71783 0.195002 -0.668352 0.608797 0.368418 -0.702591 0.615546 0.194025 -0.763844 0.407591 0.19319 -0.892495 0.398644 0.510188 -0.762096 0.326314 0.194829 -0.924965 0.118699 0.551666 0.825575 0.346485 0.551666 0.758692 0.346483 0.551681 0.758682 0.546191 0.55168 0.630337 0.546199 0.551652 0.630354 0.701668 0.55165 0.450938 0.70165 0.551687 0.45092 0.800265 0.551688 0.234981 0.800264 0.551691 0.23498 0.834049 0.551691 0 0.834049 0.551691 0 0.800266 0.551687 -0.234981 0.800265 0.551688 -0.234981 0.701647 0.551687 -0.450924 0.701668 0.551655 -0.450931 0.546198 0.551661 -0.630348 0.546192 0.551672 -0.630343 0.346483 0.55167 -0.758689 0.346485 0.551666 -0.758691 0.139635 0.193189 -0.971175 0.127894 0.438638 -0.889516 0.124643 0.552056 -0.824438 0.113325 0.604901 -0.788196 0.087202 0.790282 -0.606506 0.079635 0.828788 0.553868 0.232451 0.828791 0.508991 0.232456 0.828778 0.509009 0.366444 0.828777 0.422904 0.366433 0.828792 0.422884 0.470728 0.828794 0.302516 0.470751 0.828773 0.302538 0.536919 0.828772 0.157654 0.536906 0.828782 0.157648 0.559572 0.828782 0 0.559572 0.828782 0 0.536904 0.828783 -0.15765 0.53692 0.828772 -0.157652 0.470754 0.828773 -0.302533 0.470725 0.828794 -0.30252 0.366431 0.828792 -0.422886 0.366444 0.82878 -0.422897 0.232455 0.828783 -0.509002 0.232448 0.828791 -0.508992 0.0857778 0.829191 -0.552345 0.063475 0.895026 -0.441474 0.0280299 0.980412 0.194951 0.0818186 0.980412 0.179158 0.081818 0.980413 0.179156 0.128978 0.980413 0.148848 0.12898 0.980412 0.148851 0.165691 0.980412 0.106485 0.165684 0.980414 0.106478 0.188971 0.980414 0.0554862 0.188979 0.980412 0.0554899 0.196957 0.980412 0 0.196957 0.980412 0 0.188979 0.980412 -0.0554886 0.188971 0.980414 -0.0554876 0.165685 0.980413 -0.106481 0.165692 0.980412 -0.106484 0.12898 0.980412 -0.14885 0.128977 0.980413 -0.148848 0.0818178 0.980413 -0.179156 0.0818205 0.980412 -0.179161 0.0280305 0.980412 -0.194954 0.0280301 0.980412 -0.194953 -0.142791 0.193101 -0.970733 -0.149317 0.256565 -0.954923 -0.654501 0.193093 -0.730988 -0.638177 0.256559 -0.725884 -0.0649332 0.894942 -0.441432 -0.0891992 0.790142 -0.606399 -0.115194 0.704151 -0.700644 -0.115906 0.60472 -0.787959 -0.130795 0.438471 -0.889177 -0.410098 0.256263 -0.875299 -0.410098 0.256254 -0.875302 -0.301598 0.703319 -0.643724 -0.301599 0.703318 -0.643725 -0.0286764 0.980394 -0.194949 -0.599506 0.438492 -0.669565 -0.531267 0.604722 -0.593352 -0.464632 0.704152 -0.536923 -0.40885 0.790147 -0.456629 -0.297647 0.894928 -0.332431 -0.0470991 0.965536 -0.255972 -0.1109 0.965232 -0.236703 -0.1109 0.965232 -0.236703 -0.166541 0.965535 -0.200015 -0.131439 0.980395 -0.146798 0.654502 0.193095 0.730987 0.142792 0.193101 0.970733 0.0737532 0.538376 0.839471 0.227124 0.194768 0.954191 0.654502 0.193093 0.730987 0.599506 0.438492 0.669565 0.551856 0.551886 0.625202 0.130792 0.438509 0.889159 0.127202 0.551883 0.824163 0.115908 0.604705 0.787971 0.0814606 0.828662 0.553789 0.0985203 0.789445 0.605864 0.0168156 0.979972 0.198426 0.0380403 0.965233 0.258607 0.41628 0.193088 0.888498 0.41628 0.193092 0.888497 0.353913 0.551493 0.755381 0.353912 0.551497 0.755379 0.237481 0.828664 0.506871 0.237482 0.828662 0.506875 0.0835995 0.980394 0.178433 0.083599 0.980395 0.178431 0.531277 0.604701 0.593364 0.408844 0.790153 0.456623 0.368373 0.829068 0.420652 0.180466 0.965536 0.187545 0.131439 0.980395 0.1468 0.0227307 0.965683 0.258727 0.0620008 0.705746 0.705746 0.0845588 0.25791 0.962462 0.0845541 0.257893 0.962467 0.25108 0.257893 0.932979 0.25108 0.257895 0.932979 0.409916 0.257892 0.874906 0.409915 0.257885 0.874909 0.556184 0.257883 0.790035 0.556186 0.257895 0.79003 0.685418 0.257896 0.680949 0.685418 0.257899 0.680948 0.0620032 0.705753 0.705739 0.184108 0.705754 0.684117 0.184107 0.705751 0.68412 0.300575 0.705751 0.641537 0.300575 0.705751 0.641538 0.407831 0.705751 0.579301 0.407831 0.705753 0.579299 0.502591 0.705754 0.499313 0.502592 0.705753 0.499314 0.0227304 0.965683 0.258728 0.0674945 0.965683 0.250802 0.0674945 0.965683 0.250801 0.110192 0.965683 0.23519 0.110192 0.965683 0.235189 0.149512 0.965683 0.212373 0.149514 0.965682 0.212378 0.184255 0.965682 0.183054 0.184254 0.965682 0.183051 0.142794 0.193101 0.970733 0.149319 0.25656 0.954924 0.130792 0.438509 0.889159 0.654501 0.193093 0.730988 0.638177 0.256558 0.725884 0.115908 0.604705 0.787971 0.115195 0.704146 0.700649 0.0891994 0.790142 0.606399 0.0649334 0.894942 0.441432 0.0470989 0.965537 0.255968 0.0286761 0.980395 0.194946 0.410098 0.256249 0.875303 0.410098 0.256248 0.875304 0.3016 0.703316 0.643727 0.301599 0.703318 0.643725 0.110899 0.965233 0.236699 0.110899 0.965233 0.2367 0.599506 0.438492 0.669565 0.531272 0.604712 0.593358 0.464634 0.704149 0.536926 0.408854 0.790141 0.456634 0.174362 0.965233 0.194739 0.174362 0.965233 0.194739 -0.127894 0.438639 -0.889516 -0.139636 0.193183 0.971176 -0.569784 0.418829 -0.707056 -0.642523 0.193194 -0.741513 -0.454667 0.194358 -0.869197 -0.379357 0.407508 -0.830677 -0.326311 0.19484 -0.924964 -0.139635 0.193198 -0.971173 -0.139634 0.193189 -0.971175 -0.717846 0.194974 -0.668342 -0.825406 0.193184 -0.530457 -0.825406 0.193188 -0.530456 -0.89929 0.195069 -0.391441 -0.915646 0.298843 -0.268858 -0.946117 0.193634 -0.259555 -0.97838 0.194619 -0.0699764 -0.907491 0.420071 0 -0.97838 0.194619 0.0699764 -0.941418 0.193187 0.276425 -0.916032 0.312623 0.251301 -0.89929 0.195069 0.391441 -0.825406 0.193188 0.530456 -0.825405 0.193192 0.530456 -0.717845 0.194985 0.668341 -0.608795 0.36843 0.702587 -0.615546 0.194029 0.763843 -0.407588 0.193193 0.892495 -0.39864 0.510203 0.762089 -0.326307 0.194825 0.924969 -0.113325 0.604901 -0.788196 -0.124643 0.552056 -0.824438 -0.346483 0.551666 -0.758693 -0.346483 0.551668 -0.758691 -0.546195 0.551668 -0.630344 -0.546193 0.551675 -0.63034 -0.701656 0.551674 -0.450927 -0.701654 0.551678 -0.450925 -0.800273 0.551677 -0.234981 -0.800276 0.551672 -0.234983 -0.83406 0.551674 0 -0.83406 0.551674 0 -0.800274 0.551675 0.234981 -0.800273 0.551677 0.234981 -0.701653 0.551678 0.450926 -0.701659 0.551668 0.450928 -0.546196 0.551667 0.630344 -0.546191 0.551676 0.63034 -0.34648 0.551678 0.758685 -0.346485 0.551666 0.758692 -0.0967343 0.789584 -0.60597 -0.139635 0.193189 0.971175 -0.127891 0.438677 0.889498 -0.124641 0.552056 0.824438 -0.113326 0.604886 0.788207 -0.087202 0.790282 0.606506 -0.0796343 0.828785 -0.553871 -0.232453 0.828785 -0.509 -0.232452 0.828786 -0.508999 -0.366438 0.828785 -0.422892 -0.36644 0.828784 -0.422894 -0.47074 0.828783 -0.302526 -0.470742 0.828781 -0.302528 -0.536905 0.828782 -0.15765 -0.536904 0.828783 -0.157649 -0.559572 0.828782 0 -0.559572 0.828782 0 -0.536906 0.828781 0.15765 -0.536905 0.828782 0.15765 -0.470742 0.828782 0.302527 -0.47074 0.828783 0.302526 -0.366439 0.828784 0.422895 -0.366442 0.828782 0.422897 -0.232456 0.828782 0.509004 -0.232453 0.828785 0.509 -0.0857779 0.829189 0.552348 -0.0634746 0.895026 0.441474 -0.0371837 0.965264 -0.258618 -0.0158842 0.979986 -0.198432 -0.0818195 0.980412 -0.179159 -0.0818189 0.980412 -0.179157 -0.128978 0.980412 -0.148849 -0.128978 0.980412 -0.148849 -0.16569 0.980412 -0.106482 -0.165691 0.980412 -0.106483 -0.188979 0.980412 -0.0554892 -0.188978 0.980412 -0.0554887 -0.196955 0.980413 0 -0.196955 0.980413 0 -0.188978 0.980412 0.0554889 -0.188978 0.980412 0.0554889 -0.165689 0.980412 0.106482 -0.16569 0.980412 0.106482 -0.128978 0.980412 0.148849 -0.128979 0.980412 0.148849 -0.0818186 0.980412 0.179157 -0.0818182 0.980412 0.179157 -0.0280298 0.980412 0.194951 -0.0280296 0.980413 0.19495 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.99863 0 -0.052336 -0.99863 0 -0.052336 -0.995559 0.0783527 -0.0521751 -0.996064 0.0712392 -0.0527432 -0.983091 0.175543 -0.052122 -0.984309 0.16852 -0.0523175 -0.966278 0.252144 -0.0522457 -0.969734 0.238321 -0.0530939 -0.936946 0.345661 -0.0514786 -0.941752 0.332222 -0.0522614 -0.906901 0.418085 -0.052296 -0.915598 0.398567 -0.0531377 -0.861638 0.505014 -0.0504088 -0.87645 0.478579 -0.0528931 -0.819286 0.571018 -0.0520533 -0.799501 0.598494 -0.0510238 -0.759303 0.648509 -0.0538084 -0.598498 0.799498 -0.0510238 -0.648508 0.759303 -0.053808 -0.68048 0.730898 -0.0523029 -0.730892 0.680486 -0.052303 -0.0712413 0.996092 -0.0522031 -0.0783505 0.995531 -0.0527194 -0.168544 0.984312 -0.0521822 -0.175561 0.983077 -0.0523258 -0.238318 0.969779 -0.0522839 -0.252134 0.966244 -0.052926 -0.332242 0.941775 -0.0517206 -0.345645 0.936907 -0.0522956 -0.398568 0.915645 -0.0523275 -0.418073 0.906883 -0.0527039 -0.478619 0.87653 -0.0511709 -0.504955 0.861534 -0.0527216 -0.571021 0.819283 -0.0520532 0 0.99863 -0.052336 0 0.99863 -0.052336 0.0783527 0.995559 -0.0521751 0.0712393 0.996064 -0.0527432 0.175557 0.983088 -0.0521218 0.168539 0.984306 -0.0523172 0.252146 0.966278 -0.0522454 0.23831 0.969737 -0.0530944 0.34566 0.936947 -0.051479 0.332233 0.941748 -0.052261 0.418082 0.906903 -0.0522956 0.398551 0.915606 -0.0531378 0.505015 0.861637 -0.0504085 0.478573 0.876453 -0.0528935 0.571021 0.819283 -0.0520536 0.598502 0.799495 -0.051024 0.648504 0.759307 -0.0538078 0.799501 0.598494 -0.0510238 0.759307 0.648504 -0.0538081 0.730892 0.680486 -0.0523025 0.68048 0.730898 -0.0523025 0.996092 0.0712412 -0.0522024 0.995531 0.0783505 -0.0527188 0.984316 0.168521 -0.0521818 0.983075 0.175573 -0.0523262 0.969776 0.238331 -0.0522842 0.966244 0.252135 -0.0529257 0.941779 0.332231 -0.0517204 0.936906 0.345646 -0.052296 0.915638 0.398585 -0.0523279 0.906882 0.418076 -0.052704 0.876529 0.478622 -0.0511711 0.861535 0.504954 -0.0527216 0.819286 0.571018 -0.0520533 0.99863 0 -0.0523354 0.99863 0 -0.0523354 0.995559 -0.0783527 -0.0521745 0.996064 -0.0712392 -0.0527426 0.983085 -0.175574 -0.0521211 0.984309 -0.16852 -0.0523175 0.966278 -0.252144 -0.0522457 0.969734 -0.23832 -0.053094 0.936946 -0.345661 -0.0514787 0.941752 -0.332223 -0.0522614 0.906901 -0.418085 -0.052296 0.915598 -0.398567 -0.0531377 0.861638 -0.505014 -0.0504088 0.87645 -0.478579 -0.0528931 0.819286 -0.571018 -0.0520533 0.799501 -0.598494 -0.0510238 0.759307 -0.648504 -0.0538081 0.5985 -0.799496 -0.0510239 0.648504 -0.759307 -0.0538078 0.68048 -0.730898 -0.0523025 0.730892 -0.680486 -0.0523025 0.0712433 -0.996092 -0.052203 0.0783504 -0.995531 -0.0527193 0.16853 -0.984314 -0.0521821 0.175548 -0.983079 -0.0523258 0.238324 -0.969777 -0.0522839 0.252142 -0.966242 -0.0529261 0.332242 -0.941775 -0.0517207 0.345641 -0.936908 -0.0522956 0.398561 -0.915648 -0.0523275 0.418077 -0.906882 -0.0527041 0.478619 -0.87653 -0.0511712 0.504953 -0.861535 -0.0527218 0.571021 -0.819283 -0.0520535 0 -0.99863 -0.052336 0 -0.99863 -0.052336 -0.0783527 -0.995559 -0.0521751 -0.0712413 -0.996064 -0.052743 -0.175555 -0.983089 -0.0521217 -0.168532 -0.984307 -0.0523172 -0.252148 -0.966277 -0.0522454 -0.23831 -0.969737 -0.0530945 -0.345656 -0.936948 -0.0514792 -0.332233 -0.941748 -0.052261 -0.418086 -0.906901 -0.0522956 -0.398544 -0.915608 -0.0531383 -0.505013 -0.861638 -0.0504088 -0.478579 -0.87645 -0.052893 -0.571021 -0.819283 -0.0520531 -0.598497 -0.799499 -0.0510237 -0.648508 -0.759304 -0.053808 -0.799501 -0.598494 -0.0510238 -0.759303 -0.648509 -0.0538084 -0.730892 -0.680486 -0.052303 -0.68048 -0.730898 -0.0523029 -0.996092 -0.0712412 -0.0522031 -0.995531 -0.0783505 -0.0527194 -0.984316 -0.168521 -0.0521824 -0.983081 -0.175541 -0.0523261 -0.969776 -0.23833 -0.0522842 -0.966244 -0.252135 -0.0529257 -0.941779 -0.332232 -0.0517205 -0.936906 -0.345646 -0.052296 -0.915638 -0.398585 -0.0523279 -0.906882 -0.418076 -0.052704 -0.876529 -0.478622 -0.0511711 -0.861535 -0.504954 -0.0527216 -0.819286 -0.571018 -0.0520533 -0.99863 0 -0.052336 -0.99863 0 -0.052336 0.201517 0 0.979485 0.201517 0 0.979485 0.571749 0 0.820429 0.571749 0 0.820429 0.849199 0 0.528073 0.849199 0 0.528073 0.988702 0 0.149895 0.988702 0 0.149895 0.201496 0.0144099 0.979383 0.571271 0.0408593 0.819744 0.847637 0.060628 0.527102 0.898977 0.317132 0.302104 0.926416 0.345534 0.149534 0.960152 0.235966 0.14976 0.934163 0.203212 0.293334 0.974523 0.166845 0.149891 0.986232 0.0705412 0.149569 0.986239 0.0705365 0.149522 0.906535 0.394622 0.149889 0.86781 0.473861 0.14954 0.8678 0.473862 0.149593 0.791536 0.592531 0.149594 0.791533 0.592531 0.149611 0.723625 0.673721 0.149889 0.674008 0.67401 0.302365 0.203215 0.934166 0.293321 0.673717 0.723634 0.149863 0.59254 0.791531 0.149582 0.592534 0.791529 0.149615 0.47385 0.867804 0.14961 0.473858 0.867807 0.149563 0.394605 0.906539 0.149915 0.336896 0.903253 0.265772 0.328936 0.932402 0.149759 0.235953 0.960145 0.149826 0.166863 0.974514 0.14993 0.0705357 0.986226 0.149606 0.0705372 0.986228 0.149594 0.847647 0.0606266 0.527085 0.830392 0.180638 0.527085 0.830374 0.180638 0.527114 0.796216 0.296972 0.527113 0.796212 0.296972 0.527118 0.745843 0.407267 0.527117 0.745866 0.407274 0.527078 0.680315 0.509275 0.527078 0.680298 0.509267 0.527107 0.600899 0.6009 0.527105 0.600904 0.600904 0.527096 0.50927 0.680302 0.527099 0.509262 0.680295 0.527116 0.407263 0.745847 0.527114 0.407276 0.745863 0.527081 0.296979 0.796232 0.527084 0.296976 0.796228 0.527093 0.18064 0.830388 0.527091 0.180635 0.830378 0.527109 0.0606245 0.847631 0.527111 0.060626 0.847637 0.527102 0.57131 0.0408569 0.819717 0.559679 0.121751 0.819717 0.559661 0.12175 0.81973 0.536638 0.200156 0.81973 0.536634 0.200155 0.819733 0.502688 0.274488 0.819732 0.502699 0.274493 0.819724 0.458517 0.343243 0.819724 0.458525 0.343247 0.819717 0.405007 0.405007 0.819718 0.405007 0.405007 0.819718 0.343246 0.458524 0.819718 0.343255 0.458533 0.819709 0.274504 0.502712 0.819712 0.274494 0.502697 0.819725 0.200158 0.536647 0.819724 0.200152 0.536636 0.819732 0.121745 0.55966 0.819731 0.121751 0.559677 0.819718 0.040862 0.571308 0.819718 0.0408615 0.571306 0.819719 0.201484 0.0144104 0.979386 0.197383 0.0429391 0.979386 0.197387 0.0429396 0.979385 0.189268 0.0705934 0.979385 0.189275 0.0705952 0.979383 0.177301 0.0968134 0.979383 0.177292 0.0968097 0.979385 0.161711 0.121055 0.979385 0.161717 0.121059 0.979384 0.142842 0.142842 0.979384 0.142838 0.142839 0.979385 0.121057 0.161712 0.979385 0.121056 0.161711 0.979385 0.0968092 0.177293 0.979385 0.0968121 0.177297 0.979384 0.0705931 0.18927 0.979384 0.0705965 0.189277 0.979383 0.0429411 0.197396 0.979383 0.0429392 0.19739 0.979384 0.0144113 0.201492 0.979384 0.0144108 0.201489 0.979385 0.014411 -0.201493 0.979384 0.0408601 -0.571297 0.819725 0.0606248 -0.847637 0.527102 0.317146 -0.898984 0.30207 0.345531 -0.926407 0.149595 0.235956 -0.960144 0.149826 0.203214 -0.934161 0.293337 0.166853 -0.974519 0.149912 0.0705373 -0.986229 0.149588 0.0705378 -0.986228 0.149594 0.394597 -0.906539 0.149932 0.473855 -0.867806 0.149579 0.473856 -0.8678 0.14961 0.592536 -0.791528 0.149615 0.592536 -0.791534 0.149582 0.673717 -0.723634 0.149863 0.674008 -0.67401 0.302365 0.934163 -0.203212 0.293334 0.723625 -0.673721 0.149889 0.791534 -0.592529 0.149611 0.791535 -0.592532 0.149594 0.867803 -0.473857 0.149593 0.867807 -0.473866 0.14954 0.906535 -0.394622 0.149889 0.90325 -0.336894 0.265786 0.932414 -0.328928 0.149703 0.960152 -0.235965 0.149764 0.974523 -0.166845 0.149891 0.986232 -0.070536 0.149569 0.986239 -0.0705417 0.149522 0.0606245 -0.84764 0.527097 0.180639 -0.830385 0.527095 0.180639 -0.830388 0.527091 0.296977 -0.796227 0.527093 0.296977 -0.796225 0.527096 0.40727 -0.745858 0.527093 0.407269 -0.745852 0.527103 0.509267 -0.6803 0.527105 0.509271 -0.68031 0.527088 0.600907 -0.600909 0.527086 0.6009 -0.600899 0.527105 0.680301 -0.509264 0.527107 0.680312 -0.509278 0.527078 0.745864 -0.407279 0.527078 0.745845 -0.407263 0.527117 0.796213 -0.296971 0.527118 0.796215 -0.296973 0.527113 0.830375 -0.180634 0.527114 0.830391 -0.180642 0.527085 0.847647 -0.0606288 0.527085 0.847637 -0.0606259 0.527102 0.0408599 -0.5713 0.819724 0.121748 -0.559669 0.819724 0.121748 -0.559668 0.819725 0.200158 -0.536643 0.819726 0.200159 -0.536647 0.819724 0.274495 -0.502697 0.819725 0.274501 -0.502714 0.819712 0.343253 -0.458535 0.819709 0.343243 -0.458517 0.819723 0.405004 -0.405002 0.819723 0.405007 -0.405007 0.819718 0.458524 -0.343248 0.819717 0.458517 -0.343242 0.819724 0.502699 -0.274494 0.819724 0.502688 -0.274487 0.819732 0.536634 -0.200154 0.819733 0.536638 -0.200156 0.81973 0.559662 -0.121748 0.81973 0.559679 -0.121754 0.819717 0.571309 -0.040862 0.819717 0.571272 -0.0408542 0.819744 0.014411 -0.201492 0.979384 0.0429394 -0.19739 0.979384 0.0429393 -0.197389 0.979384 0.070594 -0.18927 0.979384 0.0705938 -0.18927 0.979384 0.0968113 -0.177297 0.979384 0.0968106 -0.177296 0.979384 0.121058 -0.161713 0.979384 0.121057 -0.161712 0.979385 0.142838 -0.142838 0.979385 0.142841 -0.142842 0.979384 0.161716 -0.121059 0.979384 0.161712 -0.121055 0.979385 0.177293 -0.0968088 0.979385 0.177301 -0.0968144 0.979383 0.189275 -0.070596 0.979383 0.189268 -0.0705926 0.979385 0.197387 -0.0429401 0.979385 0.197383 -0.0429386 0.979386 0.201485 -0.0144091 0.979386 0.201496 -0.0144113 0.979383 0 0.20151 0.979486 0 0.20151 0.979486 0 0.571784 0.820405 0 0.571784 0.820405 0 0.849199 0.528073 0 0.849199 0.528073 0 0.988691 0.149967 0 0.988691 0.149967 0 -0.201514 0.979486 0 -0.201514 0.979486 0 -0.571775 0.82041 0 -0.571775 0.82041 0 -0.849199 0.528073 0 -0.849199 0.528073 0 -0.988691 0.149967 0 -0.988691 0.149967 -0.0144111 0.201489 0.979385 -0.0408618 0.571306 0.819719 -0.0606248 0.847637 0.527102 -0.317146 0.898984 0.30207 -0.345531 0.926407 0.149595 -0.23595 0.960146 0.149826 -0.203216 0.93417 0.293308 -0.166866 0.974514 0.14993 -0.0705371 0.986226 0.149606 -0.0705359 0.986228 0.149594 -0.394605 0.906539 0.149915 -0.473857 0.867808 0.149563 -0.473857 0.867806 0.149575 -0.592537 0.791535 0.149572 -0.592537 0.791533 0.149582 -0.673717 0.723634 0.149863 -0.674008 0.67401 0.302365 -0.934163 0.203212 0.293334 -0.723625 0.673721 0.149889 -0.791534 0.592529 0.149611 -0.791535 0.592532 0.149594 -0.867803 0.473857 0.149593 -0.867802 0.473855 0.149603 -0.906526 0.394618 0.149956 -0.903235 0.336896 0.265833 -0.932415 0.328928 0.149697 -0.960152 0.235966 0.14976 -0.974523 0.166845 0.149891 -0.986232 0.070536 0.149569 -0.986229 0.0705329 0.149594 -0.0606256 0.847631 0.527111 -0.180637 0.830377 0.527108 -0.180638 0.830389 0.527091 -0.296977 0.796227 0.527093 -0.296976 0.796221 0.527103 -0.407265 0.745851 0.527107 -0.407263 0.745846 0.527114 -0.509264 0.680294 0.527116 -0.509268 0.680304 0.527099 -0.600903 0.600904 0.527096 -0.600899 0.600899 0.527105 -0.680301 0.509264 0.527107 -0.680312 0.509278 0.527078 -0.745867 0.407273 0.527078 -0.74587 0.407276 0.527071 -0.796239 0.296988 0.527068 -0.796215 0.296973 0.527113 -0.830375 0.180634 0.527114 -0.830391 0.180642 0.527085 -0.847648 0.0606219 0.527085 -0.847637 0.060619 0.527102 -0.0408617 0.571308 0.819718 -0.121749 0.559678 0.819718 -0.121747 0.55966 0.819731 -0.200155 0.536635 0.819732 -0.200161 0.536659 0.819715 -0.274502 0.502712 0.819713 -0.274496 0.502697 0.819724 -0.343241 0.458517 0.819724 -0.343245 0.458524 0.819718 -0.405007 0.405007 0.819718 -0.405007 0.405007 0.819718 -0.458524 0.343248 0.819717 -0.458517 0.343242 0.819724 -0.502699 0.274494 0.819724 -0.502688 0.274487 0.819732 -0.536634 0.200154 0.819733 -0.536638 0.200156 0.81973 -0.559662 0.121748 0.81973 -0.559646 0.121742 0.819741 -0.571275 0.0408549 0.819741 -0.571306 0.0408614 0.819719 -0.014411 0.201492 0.979384 -0.0429398 0.19739 0.979384 -0.0429405 0.197396 0.979383 -0.0705957 0.189277 0.979383 -0.0705926 0.189265 0.979385 -0.096809 0.177291 0.979386 -0.0968097 0.177292 0.979385 -0.121055 0.161711 0.979385 -0.121056 0.161713 0.979385 -0.142838 0.142838 0.979385 -0.142841 0.142842 0.979384 -0.161716 0.121059 0.979384 -0.161712 0.121055 0.979385 -0.177293 0.0968088 0.979385 -0.177301 0.0968144 0.979383 -0.189275 0.070596 0.979383 -0.189268 0.0705926 0.979385 -0.197388 0.0429385 0.979385 -0.197397 0.0429417 0.979383 -0.201499 0.0144118 0.979383 -0.201496 0.0144113 0.979383 -0.201496 -0.0144116 0.979383 -0.571306 -0.0408571 0.819719 -0.847637 -0.0606212 0.527102 -0.898959 -0.317127 0.302164 -0.926412 -0.345541 0.14954 -0.960152 -0.235965 0.149764 -0.934163 -0.203212 0.293334 -0.974523 -0.166845 0.149891 -0.986232 -0.0705332 0.149569 -0.986228 -0.0705357 0.149594 -0.906526 -0.394618 0.149956 -0.867801 -0.473856 0.149604 -0.867803 -0.473856 0.149593 -0.791536 -0.592531 0.149594 -0.791533 -0.592531 0.149611 -0.723625 -0.673721 0.149889 -0.674008 -0.67401 0.302365 -0.203215 -0.934165 0.293324 -0.673717 -0.723634 0.149863 -0.592535 -0.791535 0.149582 -0.592537 -0.791536 0.149572 -0.473859 -0.867805 0.149575 -0.473858 -0.867804 0.149579 -0.394597 -0.906539 0.149932 -0.336896 -0.903253 0.265772 -0.328936 -0.932402 0.149759 -0.235953 -0.960145 0.149826 -0.166856 -0.974518 0.149912 -0.0705379 -0.986229 0.149588 -0.0705372 -0.986228 0.149594 -0.847648 -0.0606197 0.527085 -0.830392 -0.180638 0.527085 -0.830374 -0.180638 0.527114 -0.796214 -0.296978 0.527113 -0.796242 -0.296982 0.527068 -0.745871 -0.407276 0.527071 -0.745866 -0.407274 0.527078 -0.680315 -0.509275 0.527078 -0.680298 -0.509267 0.527107 -0.600899 -0.6009 0.527105 -0.600909 -0.600907 0.527086 -0.509273 -0.680308 0.527088 -0.509265 -0.680301 0.527105 -0.407267 -0.745853 0.527103 -0.407261 -0.745845 0.527119 -0.296972 -0.796214 0.527115 -0.29698 -0.796226 0.527093 -0.18064 -0.830388 0.527091 -0.180639 -0.830385 0.527095 -0.060625 -0.84764 0.527098 -0.0606243 -0.847637 0.527102 -0.571274 -0.0408591 0.819742 -0.559646 -0.121744 0.819741 -0.559662 -0.121746 0.81973 -0.536638 -0.200156 0.81973 -0.536634 -0.200155 0.819733 -0.502688 -0.274488 0.819732 -0.502699 -0.274493 0.819724 -0.458517 -0.343243 0.819724 -0.458525 -0.343247 0.819717 -0.405008 -0.405007 0.819718 -0.405003 -0.405003 0.819723 -0.343241 -0.458519 0.819723 -0.34324 -0.458518 0.819724 -0.274494 -0.502699 0.819724 -0.274503 -0.502711 0.819713 -0.200165 -0.536657 0.819715 -0.200157 -0.536643 0.819726 -0.121748 -0.559668 0.819725 -0.121748 -0.559669 0.819724 -0.0408602 -0.5713 0.819724 -0.0408597 -0.571297 0.819725 -0.201499 -0.0144115 0.979383 -0.197397 -0.0429406 0.979383 -0.197387 -0.0429396 0.979385 -0.189268 -0.0705934 0.979385 -0.189275 -0.0705952 0.979383 -0.177301 -0.0968134 0.979383 -0.177292 -0.0968097 0.979385 -0.161711 -0.121055 0.979385 -0.161717 -0.121059 0.979384 -0.142842 -0.142842 0.979384 -0.142838 -0.142839 0.979385 -0.121056 -0.161713 0.979385 -0.121057 -0.161714 0.979384 -0.0968111 -0.177295 0.979384 -0.0968081 -0.177291 0.979386 -0.070592 -0.189265 0.979385 -0.0705946 -0.18927 0.979384 -0.0429392 -0.197389 0.979384 -0.0429396 -0.19739 0.979384 -0.0144109 -0.201492 0.979384 -0.0144111 -0.201493 0.979384 -0.201517 0 0.979485 -0.201517 0 0.979485 -0.571784 0 0.820404 -0.571784 0 0.820404 -0.849199 0 0.528073 -0.849199 0 0.528073 -0.988691 0 0.149967 -0.988691 0 0.149967 -0.201517 0 0.979485 -0.201517 0 0.979485 -0.571784 0 0.820404 -0.571784 0 0.820404 -0.849199 0 0.528073 -0.849199 0 0.528073 -0.988691 0 0.149967 -0.988691 0 0.149967 0 0.126202 -0.992005 0 0.126202 -0.992005 0 0.311084 -0.950382 0 0.311084 -0.950382 0 0.428543 -0.903522 0 0.428543 -0.903522 0 0.591309 -0.806445 0 0.591309 -0.806445 0 0.774394 -0.632703 0 0.774394 -0.632703 0 0.879852 -0.475248 0 0.879852 -0.475248 0 0.932797 -0.360401 0 0.932797 -0.360401 0 0.984041 -0.177942 0 0.984041 -0.177942 -0.893673 0.411987 -0.17781 -0.807309 0.56267 -0.177916 -0.497615 0.849011 -0.177649 -0.172997 0.968721 -0.177908 -0.126194 0.00993235 -0.991956 -0.00993208 0.126196 -0.991956 -0.00993172 0.126195 -0.991956 -0.0244753 0.310991 -0.950098 -0.0511282 0.367067 -0.928788 -0.116951 0.0484418 -0.991956 -0.116949 0.0484424 -0.991956 -0.343261 0.142185 -0.928415 -0.343261 0.142186 -0.928415 -0.547389 0.226739 -0.805577 -0.547397 0.226737 -0.805572 -0.716333 0.296711 -0.63153 -0.716326 0.296714 -0.631536 -0.839465 0.34772 -0.417598 -0.123087 0.0295507 -0.991956 -0.123087 0.0295507 -0.991956 -0.361278 0.0867354 -0.928415 -0.361279 0.0867348 -0.928415 -0.576127 0.138315 -0.805572 -0.576124 0.138317 -0.805574 -0.753923 0.181003 -0.631536 -0.753925 0.181001 -0.631534 -0.0891467 0.904033 -0.418063 -0.0690787 0.87775 -0.474113 -0.0608316 0.772959 -0.631533 -0.060833 0.77296 -0.631531 -0.0464865 0.590669 -0.805573 -0.0464864 0.590669 -0.805574 -0.0337077 0.428299 -0.903008 -0.0484428 0.11695 -0.991956 -0.0484426 0.11695 -0.991956 -0.142184 0.343261 -0.928416 -0.142182 0.34326 -0.928416 -0.226738 0.547394 -0.805574 -0.226738 0.547394 -0.805574 -0.296713 0.71633 -0.631533 -0.296714 0.71633 -0.631532 -0.347719 0.839466 -0.417598 -0.34772 0.839467 -0.417596 -0.126195 0.00993169 -0.991956 -0.310991 0.0244752 -0.950098 -0.367069 0.0511291 -0.928787 -0.428302 0.0337088 -0.903007 -0.590668 0.0464875 -0.805575 -0.590666 0.046489 -0.805576 -0.772958 0.0608365 -0.631534 -0.772964 0.0608316 -0.631527 -0.87775 0.0690782 -0.474113 -0.839467 0.347719 -0.417596 -0.883528 0.212116 -0.417595 -0.883528 0.212115 -0.417594 -0.904034 0.0891465 -0.418063 -0.930299 0.0732122 -0.359421 -0.0772149 0.981103 -0.17741 -0.0772144 0.981103 -0.177411 -0.0732156 0.930294 -0.359434 -0.248472 0.95221 -0.177643 -0.228575 0.952089 -0.203175 -0.212115 0.883527 -0.417597 -0.212116 0.883527 -0.417596 -0.181001 0.753927 -0.631533 -0.181002 0.753927 -0.631532 -0.138315 0.576124 -0.805574 -0.138316 0.576124 -0.805574 -0.0867352 0.361277 -0.928416 -0.0867351 0.361277 -0.928416 -0.029551 0.123089 -0.991956 -0.0295506 0.123088 -0.991956 -0.376614 0.909223 -0.177415 -0.405949 0.880583 -0.244497 -0.340603 0.923241 -0.177808 -0.562674 0.807307 -0.177915 -0.511602 0.834853 -0.203187 -0.474763 0.774738 -0.41759 -0.47476 0.774737 -0.417595 -0.405119 0.661095 -0.631532 -0.405119 0.661094 -0.631532 -0.309577 0.505185 -0.805574 -0.309579 0.505185 -0.805574 -0.19413 0.316791 -0.928416 -0.19413 0.316791 -0.928417 -0.0661414 0.107933 -0.991956 -0.0661405 0.107933 -0.991956 -0.0822119 0.0962571 -0.991956 -0.082211 0.096257 -0.991956 -0.241297 0.282523 -0.928416 -0.241296 0.282522 -0.928416 -0.384794 0.450537 -0.805575 -0.384797 0.450537 -0.805573 -0.503551 0.58958 -0.631532 -0.50355 0.58958 -0.631533 -0.590113 0.690931 -0.417589 -0.59011 0.690932 -0.417592 -0.639145 0.748343 -0.177417 -0.639147 0.748342 -0.177414 -0.0962568 0.0822113 -0.991956 -0.096256 0.0822113 -0.991956 -0.282521 0.241298 -0.928417 -0.282526 0.241298 -0.928415 -0.45054 0.384795 -0.805572 -0.450534 0.384795 -0.805576 -0.589579 0.503551 -0.631533 -0.589585 0.50355 -0.631527 -0.690933 0.590109 -0.417592 -0.69093 0.59011 -0.417595 -0.748344 0.639145 -0.177414 -0.748341 0.639146 -0.177418 -0.849013 0.497615 -0.177643 -0.834851 0.511604 -0.203186 -0.774734 0.474763 -0.417598 -0.774735 0.474762 -0.417595 -0.661094 0.405122 -0.63153 -0.661098 0.405122 -0.631527 -0.505181 0.309576 -0.805577 -0.505184 0.309576 -0.805576 -0.316794 0.194131 -0.928415 -0.316796 0.19413 -0.928415 -0.107933 0.0661406 -0.991956 -0.107932 0.0661408 -0.991956 -0.909715 0.335615 -0.244501 -0.909224 0.376613 -0.177412 -0.95221 0.248473 -0.177644 -0.952089 0.228575 -0.203177 -0.968726 0.172978 -0.177901 -0.981105 0.0772105 -0.177403 -0.981103 0.0772149 -0.177411 0.248475 0.95221 -0.177643 0.411983 0.893673 -0.177814 0.562675 0.807308 -0.177906 0.849013 0.497615 -0.177643 0.92324 0.340604 -0.17781 0.968718 0.173008 -0.177915 0.00993204 0.126195 -0.991956 0.126195 0.00993243 -0.991956 0.126194 0.00993161 -0.991956 0.310991 0.0244752 -0.950098 0.367069 0.0511291 -0.928787 0.00993175 0.126196 -0.991956 0.0244753 0.310991 -0.950098 0.0511282 0.367067 -0.928788 0.0337077 0.428299 -0.903008 0.0464864 0.590669 -0.805574 0.0464865 0.590669 -0.805574 0.0608329 0.772958 -0.631534 0.904034 0.0891465 -0.418063 0.87775 0.0690782 -0.474113 0.772958 0.0608312 -0.631534 0.772964 0.0608369 -0.631527 0.590668 0.0464891 -0.805575 0.590666 0.0464874 -0.805576 0.428302 0.0337088 -0.903007 0.981102 0.0772148 -0.177417 0.981101 0.0772102 -0.177425 0.930299 0.0732122 -0.359421 0.95221 0.248473 -0.177644 0.952089 0.228575 -0.203177 0.883528 0.212115 -0.417595 0.883528 0.212116 -0.417594 0.75393 0.181003 -0.631528 0.753926 0.180997 -0.631534 0.576122 0.138311 -0.805577 0.576124 0.138314 -0.805574 0.361278 0.0867345 -0.928415 0.361279 0.0867357 -0.928415 0.123089 0.0295511 -0.991956 0.123087 0.0295492 -0.991956 0.893673 0.411987 -0.177809 0.902943 0.374012 -0.211681 0.839466 0.347718 -0.417598 0.839467 0.347721 -0.417596 0.716331 0.296716 -0.63153 0.716332 0.296718 -0.631528 0.547395 0.226741 -0.805573 0.547391 0.226735 -0.805577 0.343258 0.142181 -0.928417 0.343261 0.142185 -0.928415 0.11695 0.0484431 -0.991956 0.11695 0.0484432 -0.991956 0.807311 0.562672 -0.177905 0.834857 0.511599 -0.203177 0.774738 0.474758 -0.417595 0.774738 0.474756 -0.417598 0.661094 0.405116 -0.631534 0.661096 0.40512 -0.63153 0.505188 0.30958 -0.805572 0.505187 0.309578 -0.805573 0.316791 0.194129 -0.928416 0.316791 0.194127 -0.928417 0.107932 0.0661402 -0.991956 0.107933 0.0661413 -0.991956 0.0962563 0.0822109 -0.991956 0.0962564 0.0822116 -0.991956 0.282521 0.241298 -0.928416 0.282521 0.241298 -0.928417 0.450538 0.384799 -0.805572 0.450537 0.384797 -0.805573 0.589578 0.50355 -0.631534 0.589578 0.503551 -0.631533 0.690928 0.590112 -0.417595 0.690928 0.590108 -0.417601 0.748344 0.639146 -0.177407 0.748346 0.639142 -0.177413 0.0822114 0.0962566 -0.991956 0.0822115 0.0962575 -0.991956 0.241296 0.282522 -0.928416 0.241296 0.282523 -0.928416 0.384796 0.450539 -0.805573 0.384795 0.450535 -0.805575 0.50355 0.589579 -0.631533 0.50355 0.58958 -0.631532 0.590109 0.690928 -0.4176 0.590109 0.69093 -0.417597 0.639145 0.748344 -0.177414 0.639143 0.748346 -0.177408 0.497615 0.849011 -0.177649 0.511599 0.834856 -0.203181 0.474759 0.774738 -0.417595 0.474759 0.774737 -0.417597 0.405119 0.661094 -0.631532 0.405119 0.661095 -0.631532 0.309578 0.505186 -0.805574 0.309578 0.505184 -0.805574 0.194131 0.316793 -0.928415 0.194132 0.31679 -0.928416 0.0661417 0.107932 -0.991956 0.0661416 0.107933 -0.991956 0.340603 0.923241 -0.177808 0.374013 0.902943 -0.211681 0.34772 0.839466 -0.417598 0.347719 0.839467 -0.417596 0.296715 0.716332 -0.631529 0.296716 0.716329 -0.631532 0.226739 0.547391 -0.805576 0.226738 0.547394 -0.805574 0.142183 0.343261 -0.928416 0.142183 0.343262 -0.928416 0.0484421 0.11695 -0.991956 0.0484422 0.11695 -0.991956 0.172992 0.968722 -0.177908 0.228575 0.952088 -0.203178 0.212115 0.883529 -0.417593 0.212117 0.883527 -0.417597 0.181003 0.753925 -0.631534 0.181001 0.753928 -0.63153 0.138314 0.576125 -0.805574 0.138315 0.576122 -0.805575 0.0867352 0.361277 -0.928416 0.0867352 0.361277 -0.928416 0.0295509 0.123088 -0.991956 0.0295507 0.123089 -0.991956 0.0608312 0.77296 -0.631531 0.0690781 0.87775 -0.474113 0.0891464 0.904034 -0.418062 0.0732156 0.930294 -0.359434 0.0772144 0.981103 -0.17741 0.0772149 0.981103 -0.177411 -0.126202 0 -0.992005 -0.188642 -0.0159552 -0.981916 -0.311084 0 -0.950383 -0.428545 0 -0.90352 -0.539068 -0.0159551 -0.842111 -0.591305 0 -0.806448 -0.774398 0 -0.632699 -0.812745 -0.0159547 -0.582401 -0.879852 0 -0.475248 -0.932802 0 -0.360388 -0.970699 -0.0159547 -0.239768 -0.984041 0 -0.177942 0.984038 0 -0.177957 0.984038 0 -0.177957 0.932802 0 -0.360388 0.932802 0 -0.360388 0.879852 0 -0.475248 0.879852 0 -0.475248 0.774398 0 -0.632699 0.774398 0 -0.632699 0.591305 0 -0.806448 0.591305 0 -0.806448 0.428545 0 -0.90352 0.428545 0 -0.90352 0.311084 0 -0.950383 0.311084 0 -0.950383 0.126202 0 -0.992005 0.126202 0 -0.992005 -0.126202 0 -0.992005 -0.188642 0.0159552 -0.981916 -0.311084 0 -0.950383 -0.428545 0 -0.90352 -0.539068 0.0159551 -0.842111 -0.591305 0 -0.806448 -0.774398 0 -0.632699 -0.812745 0.0159547 -0.582401 -0.984041 0 -0.177942 -0.970699 0.0159547 -0.239768 -0.932802 0 -0.360388 -0.879852 0 -0.475248 0.95221 -0.248473 -0.177644 0.893673 -0.411987 -0.17781 0.807311 -0.562672 -0.177905 0.497613 -0.849012 -0.177649 0.3406 -0.923242 -0.177808 0.172984 -0.968723 -0.177912 0.126194 -0.00993235 -0.991956 0.00993208 -0.126196 -0.991956 0.00993172 -0.126195 -0.991956 0.0244753 -0.310991 -0.950098 0.0511282 -0.367067 -0.928788 0.126195 -0.00993169 -0.991956 0.310991 -0.0244752 -0.950098 0.367069 -0.0511291 -0.928787 0.428302 -0.0337088 -0.903007 0.590668 -0.0464875 -0.805575 0.590666 -0.046489 -0.805576 0.772958 -0.0608365 -0.631534 0.0891464 -0.904034 -0.418062 0.0690823 -0.877756 -0.474102 0.0608346 -0.772962 -0.631529 0.060833 -0.77296 -0.631531 0.0464863 -0.590668 -0.805575 0.0464863 -0.590668 -0.805575 0.0337077 -0.428299 -0.903008 0.0772149 -0.981103 -0.177414 0.0772164 -0.981103 -0.177411 0.0732174 -0.930291 -0.35944 0.24848 -0.952208 -0.177643 0.228575 -0.952087 -0.203185 0.212115 -0.883527 -0.417597 0.212118 -0.883528 -0.417593 0.181004 -0.753929 -0.631528 0.181003 -0.753929 -0.631529 0.138315 -0.576123 -0.805575 0.138315 -0.576123 -0.805575 0.0867352 -0.361277 -0.928416 0.0867351 -0.361277 -0.928416 0.029551 -0.123089 -0.991956 0.0295506 -0.123088 -0.991956 0.411987 -0.893672 -0.177814 0.374013 -0.902942 -0.211684 0.347721 -0.839469 -0.41759 0.347715 -0.839468 -0.417598 0.296711 -0.71633 -0.631533 0.296717 -0.716333 -0.631527 0.22674 -0.547394 -0.805574 0.226737 -0.547392 -0.805576 0.142183 -0.343262 -0.928416 0.142182 -0.343261 -0.928416 0.0484421 -0.11695 -0.991956 0.0484422 -0.11695 -0.991956 0.562675 -0.807308 -0.177906 0.511597 -0.834857 -0.203182 0.474757 -0.774738 -0.417597 0.474762 -0.774738 -0.41759 0.405121 -0.661094 -0.631532 0.405118 -0.661093 -0.631534 0.309577 -0.505185 -0.805574 0.309579 -0.505185 -0.805574 0.194131 -0.316792 -0.928416 0.194132 -0.316792 -0.928415 0.0661416 -0.107932 -0.991956 0.0661413 -0.107932 -0.991956 0.0822117 -0.0962569 -0.991956 0.0822112 -0.0962568 -0.991956 0.241298 -0.282523 -0.928416 0.241296 -0.282522 -0.928416 0.384794 -0.450537 -0.805575 0.384797 -0.450537 -0.805573 0.503551 -0.58958 -0.631532 0.50355 -0.58958 -0.631533 0.59011 -0.690929 -0.417597 0.590108 -0.690929 -0.4176 0.639146 -0.748344 -0.177408 0.639143 -0.748346 -0.177414 0.0962568 -0.0822113 -0.991956 0.096256 -0.0822113 -0.991956 0.282521 -0.241298 -0.928417 0.282521 -0.241298 -0.928416 0.450537 -0.384798 -0.805573 0.450538 -0.384798 -0.805572 0.589579 -0.503551 -0.631533 0.589578 -0.503551 -0.631534 0.690926 -0.590111 -0.417601 0.69093 -0.59011 -0.417595 0.748344 -0.639145 -0.177414 0.748347 -0.639143 -0.177407 0.849013 -0.497615 -0.177643 0.834857 -0.511599 -0.203177 0.774737 -0.474758 -0.417598 0.774739 -0.474757 -0.417595 0.661097 -0.405118 -0.63153 0.661093 -0.405119 -0.631534 0.505187 -0.309579 -0.805573 0.505189 -0.309579 -0.805571 0.31679 -0.194128 -0.928417 0.316792 -0.194128 -0.928416 0.107933 -0.0661406 -0.991956 0.107932 -0.0661408 -0.991956 0.92324 -0.340604 -0.17781 0.902943 -0.374012 -0.211681 0.839467 -0.347719 -0.417596 0.839465 -0.34772 -0.417598 0.716332 -0.296716 -0.631528 0.71633 -0.296717 -0.63153 0.54739 -0.226739 -0.805577 0.547397 -0.226737 -0.805572 0.343262 -0.142182 -0.928416 0.343257 -0.142184 -0.928417 0.11695 -0.0484431 -0.991956 0.11695 -0.0484431 -0.991956 0.968718 -0.173008 -0.177915 0.952089 -0.228575 -0.203177 0.883528 -0.212115 -0.417594 0.883528 -0.212116 -0.417595 0.753926 -0.181001 -0.631534 0.753932 -0.180998 -0.631528 0.576125 -0.138311 -0.805574 0.576121 -0.138313 -0.805577 0.361279 -0.0867348 -0.928415 0.361278 -0.0867354 -0.928415 0.123087 -0.0295507 -0.991956 0.123089 -0.0295497 -0.991956 0.772964 -0.0608316 -0.631527 0.87775 -0.0690782 -0.474113 0.904034 -0.0891465 -0.418063 0.930299 -0.0732122 -0.359421 0.981102 -0.0772103 -0.177417 0.9811 -0.0772147 -0.177425 -0.248477 -0.952209 -0.177643 -0.411987 -0.893672 -0.177814 -0.562674 -0.807307 -0.177915 -0.849013 -0.497615 -0.177643 -0.968726 -0.172978 -0.177901 -0.00993204 -0.126195 -0.991956 -0.126195 -0.00993243 -0.991956 -0.126194 -0.00993161 -0.991956 -0.310991 -0.0244752 -0.950098 -0.367069 -0.0511291 -0.928787 -0.00993175 -0.126196 -0.991956 -0.0244753 -0.310991 -0.950098 -0.0511282 -0.367067 -0.928788 -0.0337077 -0.428299 -0.903008 -0.0464863 -0.590668 -0.805575 -0.0464863 -0.590668 -0.805575 -0.0608332 -0.772962 -0.631529 -0.904034 -0.0891465 -0.418063 -0.87775 -0.0690782 -0.474113 -0.772958 -0.0608312 -0.631534 -0.772964 -0.0608369 -0.631527 -0.590668 -0.0464891 -0.805575 -0.590666 -0.0464874 -0.805576 -0.428302 -0.0337088 -0.903007 -0.116949 -0.0484411 -0.991956 -0.11695 -0.0484431 -0.991956 -0.343261 -0.142185 -0.928415 -0.343261 -0.142186 -0.928415 -0.547395 -0.226742 -0.805572 -0.547391 -0.226734 -0.805577 -0.716328 -0.296709 -0.631536 -0.716331 -0.296716 -0.63153 -0.839467 -0.347721 -0.417596 -0.839466 -0.347718 -0.417598 -0.981104 -0.077215 -0.177403 -0.981103 -0.0772104 -0.177411 -0.930299 -0.0732122 -0.359421 -0.95221 -0.248473 -0.177644 -0.952089 -0.228575 -0.203177 -0.883528 -0.212115 -0.417595 -0.883528 -0.212116 -0.417594 -0.753923 -0.181001 -0.631536 -0.753925 -0.181003 -0.631534 -0.576127 -0.138317 -0.805572 -0.576124 -0.138314 -0.805574 -0.361278 -0.0867345 -0.928415 -0.361279 -0.0867357 -0.928415 -0.123087 -0.0295507 -0.991956 -0.123087 -0.0295507 -0.991956 -0.909224 -0.376613 -0.177411 -0.880581 -0.405951 -0.244502 -0.92324 -0.340604 -0.17781 -0.807309 -0.56267 -0.177916 -0.834851 -0.511604 -0.203186 -0.774734 -0.474764 -0.417595 -0.774734 -0.474762 -0.417598 -0.661097 -0.405124 -0.631527 -0.661096 -0.40512 -0.63153 -0.505183 -0.309577 -0.805576 -0.505182 -0.309575 -0.805577 -0.316795 -0.194132 -0.928415 -0.316794 -0.19413 -0.928415 -0.107932 -0.0661402 -0.991956 -0.107933 -0.0661413 -0.991956 -0.0962563 -0.0822109 -0.991956 -0.0962564 -0.0822116 -0.991956 -0.282524 -0.241301 -0.928415 -0.282523 -0.241296 -0.928416 -0.450536 -0.384792 -0.805576 -0.450537 -0.384797 -0.805573 -0.589583 -0.503554 -0.631527 -0.589582 -0.503547 -0.631533 -0.690932 -0.590108 -0.417595 -0.690932 -0.590111 -0.417592 -0.748343 -0.639144 -0.177418 -0.748342 -0.639147 -0.177414 -0.0822114 -0.0962566 -0.991956 -0.0822114 -0.096257 -0.991956 -0.241297 -0.282522 -0.928416 -0.241297 -0.282523 -0.928416 -0.384796 -0.450539 -0.805573 -0.384795 -0.450535 -0.805575 -0.50355 -0.589579 -0.631533 -0.50355 -0.58958 -0.631532 -0.590112 -0.69093 -0.417592 -0.590111 -0.690933 -0.417589 -0.639145 -0.748344 -0.177414 -0.639146 -0.748342 -0.177417 -0.497613 -0.849012 -0.177649 -0.5116 -0.834853 -0.203188 -0.474762 -0.774739 -0.41759 -0.474762 -0.774738 -0.41759 -0.405119 -0.661092 -0.631534 -0.405119 -0.661095 -0.631532 -0.309578 -0.505186 -0.805574 -0.309578 -0.505184 -0.805574 -0.19413 -0.316791 -0.928417 -0.19413 -0.316793 -0.928416 -0.0661408 -0.107932 -0.991956 -0.0661407 -0.107933 -0.991956 -0.3406 -0.923242 -0.177808 -0.374013 -0.902942 -0.211684 -0.34772 -0.839466 -0.417598 -0.347717 -0.839471 -0.41759 -0.296711 -0.716332 -0.631531 -0.296712 -0.716329 -0.631533 -0.226738 -0.547394 -0.805574 -0.226738 -0.547394 -0.805574 -0.142183 -0.343261 -0.928416 -0.142183 -0.343259 -0.928416 -0.0484427 -0.11695 -0.991956 -0.0484427 -0.11695 -0.991956 -0.172989 -0.968722 -0.177912 -0.228575 -0.952088 -0.203181 -0.212115 -0.883527 -0.417596 -0.212115 -0.883527 -0.417597 -0.181002 -0.753931 -0.631527 -0.181004 -0.753928 -0.63153 -0.138316 -0.576123 -0.805575 -0.138316 -0.576124 -0.805574 -0.0867352 -0.361277 -0.928416 -0.0867352 -0.361277 -0.928416 -0.0295509 -0.123088 -0.991956 -0.0295507 -0.123089 -0.991956 -0.060835 -0.77296 -0.631531 -0.0690829 -0.877756 -0.474102 -0.0891467 -0.904033 -0.418063 -0.0732174 -0.930291 -0.35944 -0.0772164 -0.981102 -0.177414 -0.0772149 -0.981103 -0.177411 0 -0.126202 -0.992005 0 -0.126202 -0.992005 0 -0.311084 -0.950382 0 -0.311084 -0.950382 0 -0.428543 -0.903522 0 -0.428543 -0.903522 0 -0.591307 -0.806447 0 -0.591307 -0.806447 0 -0.774394 -0.632703 0 -0.774394 -0.632703 0 -0.879858 -0.475237 0 -0.879858 -0.475237 0 -0.932795 -0.360407 0 -0.932795 -0.360407 0 -0.984041 -0.177942 0 -0.984041 -0.177942 -0.130527 0.99144 -0.00297081 -0.382682 0.923875 -0.00318887 -0.333139 0.942878 0.000227987 -0.169003 0.985616 -0.000247593 -0.699577 0.714557 0 -0.628215 0.77804 -0.00080237 -0.60876 0.79335 -0.00267306 -0.530328 0.847793 0 -0.456509 0.889719 0 -0.757645 0.652667 0 -0.793348 0.608759 -0.00332738 -0.836345 0.548204 0 -0.879831 0.475286 0 -0.923878 0.38268 -0.00229665 -0.927887 0.372859 -0.00143588 -0.991439 0.130525 -0.00338713 -0.98113 0.193352 0 -0.961202 0.275847 0 -0.972036 -0.234833 0 -0.991899 -0.127012 -0.00214813 -0.991443 -0.130525 -0.00184095 -0.999775 -0.0212285 0 -0.997973 0.0636401 0 -0.948622 -0.316411 0 -0.923875 -0.382679 -0.00336725 -0.89921 -0.437518 0 -0.858855 -0.512219 0 -0.793352 -0.608762 -0.00130606 -0.803992 -0.594633 -0.0029383 -0.608759 -0.793349 -0.00326811 -0.668602 -0.74362 0 -0.729264 -0.684232 0 -0.296204 -0.955125 0 -0.411898 -0.911222 -0.00380783 -0.382683 -0.923879 -0.000692468 -0.493846 -0.86955 0 -0.565825 -0.824525 0 -0.214139 -0.976803 0 -0.130527 -0.99144 -0.00308982 -0.0848059 -0.996397 0 0.084805 -0.996398 0 0.130527 -0.99144 -0.00308991 0.214143 -0.976802 0 0.382681 -0.92388 -0.000692482 0.411898 -0.911222 -0.00380812 0.296197 -0.955127 0 0.608759 -0.793349 -0.00326811 0.565825 -0.824525 0 0.493846 -0.86955 0 0.858882 -0.512173 0 0.803995 -0.594635 -0.00110944 0.793353 -0.608757 -0.00249483 0.729264 -0.684232 0 0.668602 -0.74362 0 0.899205 -0.437528 0 0.923873 -0.382685 -0.00336755 0.948622 -0.316411 0 0.991443 -0.130525 -0.00184095 0.991898 -0.127023 -0.00214723 0.972044 -0.234799 0 0.991439 0.130525 -0.00338713 0.997973 0.0636401 0 0.999775 -0.0212285 0 0.879818 0.475311 0 0.927889 0.372849 -0.00253404 0.923877 0.382687 -0.00158315 0.961188 0.275893 0 0.98113 0.193352 0 0.836352 0.548193 0 0.793351 0.608755 -0.0033277 0.757645 0.652667 0 0.60876 0.79335 -0.00267306 0.62822 0.778035 -0.000801873 0.699535 0.714598 0 0.382679 0.923876 -0.00318897 0.456509 0.889719 0 0.530328 0.847793 0 -0.0424407 0.999099 0 0.0424398 0.999099 0 0.130527 0.99144 -0.0029709 0.169003 0.985616 -0.000247711 0.333139 0.942878 0.000227753 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.21249 -0.969262 -0.124012 0.290514 -0.936801 -0.19495 0.404042 -0.893841 -0.194417 0.404042 -0.893841 -0.194417 0.484357 -0.852842 -0.195089 0.550524 -0.81452 -0.182978 0.555017 -0.808775 -0.19452 0.678733 -0.708185 -0.194412 0.662299 -0.73661 -0.136993 0.715264 -0.671097 -0.195002 0.788653 -0.583289 -0.194422 0.788655 -0.583288 -0.194419 0.842381 -0.502333 -0.195076 0.879373 -0.443368 -0.173577 0.88201 -0.429162 -0.194623 0.937922 -0.287236 -0.194417 0.937903 -0.312836 -0.149908 0.953375 -0.23029 -0.195045 0.972971 -0.124599 -0.194427 0.972977 -0.124588 -0.194406 0.980574 -0.0208208 -0.19504 0.985205 0.0418463 -0.166195 0.978872 0.0624221 -0.194712 0.958902 0.206663 -0.194416 0.968052 0.190775 -0.16273 0.942724 0.270593 -0.195064 0.910187 0.365736 -0.194416 0.910186 0.365743 -0.194403 0.862927 0.466186 -0.195005 0.84043 0.517474 -0.16093 0.820332 0.537692 -0.194788 0.736353 0.648065 -0.194413 0.745888 0.642539 -0.175483 0.686094 0.700868 -0.195089 0.616232 0.763189 -0.194423 0.61623 0.763193 -0.194416 0.52015 0.831522 -0.194975 0.481589 0.862083 -0.157752 0.165778 0.96681 -0.194413 0.326782 0.924888 -0.194412 0.326782 0.924887 -0.194414 0.447758 0.872664 -0.194859 0.0421459 0.992181 -0.117478 0 0.98092 -0.194413 0.165777 0.96681 -0.194411 -0.326782 0.924887 -0.194418 -0.165775 0.96681 -0.194417 -0.165778 0.96681 -0.194411 -0.0416267 0.979936 -0.194919 -0.452604 0.882109 -0.130508 -0.47839 0.856355 -0.194422 -0.326781 0.924887 -0.19442 -0.520149 0.83152 -0.194985 -0.616227 0.763192 -0.194427 -0.616236 0.763189 -0.194411 -0.686137 0.700829 -0.195076 -0.738681 0.650124 -0.178016 -0.743163 0.640192 -0.194586 -0.835279 0.514302 -0.194428 -0.827694 0.542533 -0.143456 -0.862938 0.46616 -0.195022 -0.910182 0.365744 -0.194421 -0.910191 0.365735 -0.194399 -0.942741 0.270549 -0.195046 -0.96339 0.20763 -0.169615 -0.96236 0.189653 -0.194669 -0.980035 0.0416368 -0.194416 -0.985701 0.0628575 -0.156344 -0.980571 -0.0208207 -0.195058 -0.972973 -0.124589 -0.194424 -0.972975 -0.124598 -0.194408 -0.953371 -0.230324 -0.195027 -0.943331 -0.288892 -0.163304 -0.930458 -0.310353 -0.194754 -0.875889 -0.441611 -0.194417 -0.886257 -0.431216 -0.169121 -0.842354 -0.502379 -0.195076 -0.788654 -0.583289 -0.194419 -0.788655 -0.583287 -0.194422 -0.715264 -0.671097 -0.195002 -0.683129 -0.712761 -0.159082 -0.655789 -0.72937 -0.194836 -0.549288 -0.812701 -0.194423 -0.556394 -0.810782 -0.181819 -0.484357 -0.852842 -0.195089 -0.404042 -0.893841 -0.194417 -0.404042 -0.893841 -0.194417 -0.290521 -0.936799 -0.19495 -0.248854 -0.955738 -0.156963 0.24717 -0.949269 -0.194413 0.0831879 -0.977386 -0.194414 0.0831869 -0.977385 -0.194416 -0.0831887 -0.977385 -0.194416 -0.0831878 -0.977386 -0.194414 -0.210033 -0.958073 -0.194891 -0.0705928 -0.829396 -0.554183 -0.209744 -0.805536 -0.554183 -0.209744 -0.805535 -0.554184 -0.342865 -0.7585 -0.554185 -0.342865 -0.758502 -0.554183 -0.466118 -0.689649 -0.554182 -0.466118 -0.689648 -0.554184 -0.57597 -0.600949 -0.554184 -0.57597 -0.600954 -0.554178 -0.669243 -0.494976 -0.554177 -0.669242 -0.49497 -0.554184 -0.743267 -0.374746 -0.554184 -0.743266 -0.374745 -0.554186 -0.795906 -0.243744 -0.554186 -0.795906 -0.243744 -0.554186 -0.825651 -0.105725 -0.554186 -0.825657 -0.105733 -0.554176 -0.83165 0.0353288 -0.554176 -0.831645 0.0353325 -0.554182 -0.813713 0.175366 -0.554182 -0.813706 0.17537 -0.554191 -0.772365 0.310363 -0.554191 -0.772377 0.310358 -0.554177 -0.708813 0.43643 -0.554178 -0.708809 0.436431 -0.554182 -0.624856 0.549942 -0.554183 -0.624853 0.549942 -0.554186 -0.522925 0.647632 -0.554186 -0.52293 0.647633 -0.55418 -0.405957 0.726693 -0.554181 -0.405956 0.726692 -0.554182 -0.277302 0.784847 -0.554183 -0.277302 0.784847 -0.554183 -0.140676 0.820421 -0.554183 -0.140674 0.82042 -0.554185 0 0.832394 -0.554184 0 0.832394 -0.554184 0.140676 0.82042 -0.554185 0.140676 0.82042 -0.554186 0.277301 0.784844 -0.554187 0.277301 0.784844 -0.554187 0.405954 0.726688 -0.554189 0.405954 0.72669 -0.554187 0.522928 0.647628 -0.554188 0.522927 0.647638 -0.554178 0.624855 0.54995 -0.554177 0.624854 0.549935 -0.554193 0.708804 0.436425 -0.554194 0.708805 0.436429 -0.554189 0.772366 0.310363 -0.55419 0.772365 0.310362 -0.554191 0.813708 0.175364 -0.554191 0.813712 0.175371 -0.554182 0.831646 0.0353287 -0.554182 0.831641 0.0353237 -0.554189 0.825649 -0.105725 -0.55419 0.825651 -0.105723 -0.554186 0.795906 -0.243744 -0.554186 0.795906 -0.243744 -0.554186 0.743266 -0.374746 -0.554186 0.743267 -0.374745 -0.554184 0.66924 -0.494973 -0.554184 0.669246 -0.494973 -0.554177 0.575968 -0.600955 -0.554178 0.575963 -0.600955 -0.554184 0.466121 -0.689646 -0.554184 0.466123 -0.689646 -0.554182 0.342863 -0.758503 -0.554183 0.342866 -0.758504 -0.554179 0.209747 -0.805537 -0.554181 0.209745 -0.805536 -0.554183 0.0705921 -0.829396 -0.554183 0.0705921 -0.829396 -0.554183 -0.0705928 -0.829396 -0.554183 -0.047234 -0.554954 -0.830539 -0.140341 -0.538989 -0.830539 -0.140341 -0.538989 -0.830539 -0.229414 -0.507518 -0.830539 -0.229414 -0.507519 -0.830539 -0.311884 -0.461447 -0.830539 -0.311884 -0.461451 -0.830536 -0.385385 -0.402105 -0.830536 -0.385384 -0.402097 -0.83054 -0.447793 -0.331186 -0.83054 -0.447795 -0.331192 -0.830537 -0.497327 -0.250747 -0.830537 -0.497327 -0.250746 -0.830537 -0.532549 -0.163093 -0.830537 -0.532547 -0.163091 -0.830539 -0.55245 -0.0707414 -0.830539 -0.55245 -0.0707418 -0.830539 -0.556459 0.0236363 -0.830539 -0.556455 0.0236385 -0.830541 -0.544457 0.117338 -0.830541 -0.544457 0.117338 -0.830541 -0.516794 0.207667 -0.830541 -0.516796 0.207667 -0.83054 -0.474266 0.29202 -0.83054 -0.474274 0.29202 -0.830535 -0.4181 0.367971 -0.830536 -0.418096 0.36797 -0.830538 -0.349894 0.433336 -0.830539 -0.349893 0.433335 -0.830539 -0.271625 0.486234 -0.83054 -0.27163 0.486237 -0.830537 -0.185548 0.525148 -0.830537 -0.185544 0.525144 -0.83054 -0.0941254 0.548948 -0.83054 -0.0941272 0.54895 -0.830539 0 0.55696 -0.830539 0 0.55696 -0.830539 0.0941258 0.54895 -0.830539 0.0941268 0.548947 -0.83054 0.185547 0.525143 -0.83054 0.185546 0.525149 -0.830537 0.271627 0.486238 -0.830537 0.271627 0.486233 -0.83054 0.349893 0.433335 -0.830539 0.349892 0.43333 -0.830542 0.418092 0.367965 -0.830543 0.418096 0.367976 -0.830536 0.474271 0.292023 -0.830535 0.474268 0.292016 -0.83054 0.516798 0.207663 -0.83054 0.516802 0.207669 -0.830535 0.544464 0.117344 -0.830535 0.544457 0.117337 -0.830541 0.556456 0.0236362 -0.830541 0.556459 0.0236386 -0.830539 0.55245 -0.0707415 -0.830539 0.55245 -0.0707417 -0.830539 0.532546 -0.163092 -0.830539 0.53255 -0.163092 -0.830537 0.497327 -0.250747 -0.830537 0.497328 -0.250747 -0.830537 0.447797 -0.331189 -0.830537 0.447791 -0.331189 -0.83054 0.385381 -0.4021 -0.83054 0.385381 -0.4021 -0.83054 0.311883 -0.461446 -0.83054 0.311885 -0.461447 -0.830539 0.229412 -0.507519 -0.830538 0.229412 -0.507519 -0.830539 0.140343 -0.538989 -0.830539 0.140342 -0.538988 -0.830539 0.0472331 -0.554954 -0.830539 0.0472336 -0.554955 -0.830539 -0.0472336 -0.554955 -0.830539 -0.016602 -0.19506 -0.980651 -0.0493282 -0.189448 -0.980651 -0.0493282 -0.189448 -0.980651 -0.0806355 -0.178386 -0.980651 -0.0806355 -0.178385 -0.980651 -0.109622 -0.162191 -0.980651 -0.109622 -0.162191 -0.980651 -0.135456 -0.141332 -0.980651 -0.135456 -0.141333 -0.980651 -0.157394 -0.116407 -0.980651 -0.157394 -0.116408 -0.980651 -0.174803 -0.0881339 -0.980651 -0.174804 -0.0881341 -0.980651 -0.187184 -0.0573249 -0.980651 -0.187184 -0.0573251 -0.980651 -0.194179 -0.0248655 -0.980651 -0.194178 -0.0248645 -0.980651 -0.195587 0.0083083 -0.980651 -0.195588 0.00830785 -0.980651 -0.19137 0.0412439 -0.980651 -0.191373 0.0412434 -0.980651 -0.181649 0.072993 -0.980651 -0.181649 0.072993 -0.980651 -0.1667 0.102641 -0.980651 -0.166698 0.102641 -0.980651 -0.146954 0.129336 -0.980651 -0.146956 0.129336 -0.980651 -0.122983 0.152312 -0.980651 -0.122983 0.152312 -0.980651 -0.095474 0.170905 -0.980651 -0.0954723 0.170904 -0.980651 -0.0652163 0.184581 -0.980651 -0.0652178 0.184583 -0.980651 -0.0330846 0.192949 -0.980651 -0.0330839 0.192948 -0.980651 0 0.195764 -0.980651 0 0.195764 -0.980651 0.0330844 0.192948 -0.980651 0.0330841 0.192949 -0.980651 0.0652169 0.184583 -0.980651 0.0652171 0.184581 -0.980651 0.0954731 0.170904 -0.980651 0.0954732 0.170906 -0.980651 0.122983 0.152312 -0.980651 0.122983 0.152312 -0.980651 0.146955 0.129337 -0.980651 0.146955 0.129335 -0.980651 0.166698 0.10264 -0.980651 0.1667 0.102642 -0.980651 0.181649 0.0729927 -0.980651 0.181647 0.0729905 -0.980651 0.191369 0.0412436 -0.980651 0.19137 0.0412446 -0.980651 0.195588 0.00830834 -0.980651 0.195587 0.00830781 -0.980651 0.194178 -0.0248653 -0.980651 0.19418 -0.0248648 -0.980651 0.187184 -0.057325 -0.980651 0.187184 -0.057325 -0.980651 0.174804 -0.088134 -0.980651 0.174803 -0.088134 -0.980651 0.157394 -0.116408 -0.980651 0.157393 -0.116408 -0.980651 0.135456 -0.141333 -0.980651 0.135457 -0.141334 -0.980651 0.109623 -0.162193 -0.980651 0.109623 -0.162193 -0.980651 0.0806356 -0.178386 -0.980651 0.0806354 -0.178386 -0.980651 0.0493286 -0.189448 -0.980651 0.0493287 -0.189448 -0.980651 0.0166021 -0.19506 -0.980651 0.0166018 -0.195059 -0.980651 -0.0166022 -0.195059 -0.980651 0.258822 0.965925 0 0.258822 0.965925 0 0.422612 0.906311 0 0.422612 0.906311 0 0.573583 0.819147 0 0.573583 0.819147 0 0.707107 0.707107 0 0.707107 0.707107 0 0.819152 0.573577 0 0.819152 0.573577 0 0.906305 0.422624 0 0.906305 0.422624 0 0.965926 0.258817 0 0.965926 0.258817 0 0.996194 0.0871612 0 0.996194 0.0871612 0 0.996194 -0.0871612 0 0.996194 -0.0871612 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.906305 -0.422624 0 0.906305 -0.422624 0 0.819152 -0.573577 0 0.819152 -0.573577 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.573583 -0.819147 0 0.573583 -0.819147 0 0.422612 -0.906311 0 0.422612 -0.906311 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.0871523 -0.996195 0 0.0871523 -0.996195 0 -0.0871538 -0.996195 0 -0.0871538 -0.996195 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.422612 -0.906311 0 -0.422612 -0.906311 0 -0.573583 -0.819147 0 -0.573583 -0.819147 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.819152 -0.573577 0 -0.819152 -0.573577 0 -0.906305 -0.422624 0 -0.906305 -0.422624 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.996194 -0.0871612 0 -0.996194 -0.0871612 0 -0.996194 0.0871612 0 -0.996194 0.0871612 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.906305 0.422624 0 -0.906305 0.422624 0 -0.819152 0.573577 0 -0.819152 0.573577 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.573583 0.819147 0 -0.573583 0.819147 0 -0.422612 0.906311 0 -0.422612 0.906311 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.0871538 0.996195 0 -0.0871538 0.996195 0 0.0871523 0.996195 0 0.0871523 0.996195 0 -0.222426 0.974516 -0.0290719 -0.623227 0.781501 -0.0290702 -0.532035 0.846722 0 -0.330279 0.943883 0 -0.900586 0.433705 -0.0290702 -0.846724 0.532033 0 -0.707104 0.70711 0 -0.999577 0 -0.0290688 -0.993713 0.111955 0 -0.94388 0.330288 0 -0.900586 -0.433705 -0.0290702 -0.94388 -0.330288 0 -0.993713 -0.111954 0 -0.623227 -0.781501 -0.0290702 -0.707104 -0.70711 0 -0.846724 -0.532033 0 -0.222426 -0.974516 -0.0290719 -0.330279 -0.943883 0 -0.532035 -0.846722 0 0.222428 -0.974516 -0.0290725 0.111961 -0.993713 0 -0.111961 -0.993713 0 0.623227 -0.781501 -0.0290702 0.532035 -0.846722 0 0.330286 -0.943881 0 0.900586 -0.433705 -0.0290702 0.846724 -0.532033 0 0.707104 -0.70711 0 0.999577 0 -0.0290688 0.993713 -0.111954 0 0.94388 -0.330288 0 0.900586 0.433705 -0.0290702 0.94388 0.330288 0 0.993713 0.111955 0 0.623227 0.781501 -0.0290702 0.707104 0.70711 0 0.846724 0.532033 0 -0.111961 0.993713 0 0.111961 0.993713 0 0.222428 0.974516 -0.0290725 0.330286 0.943881 0 0.532035 0.846722 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.222426 0.974516 -0.0290719 -0.623227 0.781501 -0.0290702 -0.532035 0.846722 0 -0.330279 0.943883 0 -0.900586 0.433705 -0.0290702 -0.846724 0.532033 0 -0.707104 0.70711 0 -0.999577 0 -0.0290688 -0.993713 0.111954 0 -0.94388 0.330288 0 -0.900586 -0.433705 -0.0290702 -0.94388 -0.330288 0 -0.993713 -0.111955 0 -0.623227 -0.781501 -0.0290702 -0.707104 -0.70711 0 -0.846724 -0.532033 0 -0.222426 -0.974516 -0.0290719 -0.330279 -0.943883 0 -0.532035 -0.846722 0 0.222428 -0.974516 -0.0290725 0.111961 -0.993713 0 -0.111961 -0.993713 0 0.623227 -0.781501 -0.0290702 0.532035 -0.846722 0 0.330286 -0.943881 0 0.900586 -0.433705 -0.0290702 0.846724 -0.532033 0 0.707104 -0.70711 0 0.999577 0 -0.0290688 0.993713 -0.111955 0 0.94388 -0.330288 0 0.900586 0.433705 -0.0290702 0.94388 0.330288 0 0.993713 0.111954 0 0.623227 0.781501 -0.0290702 0.707104 0.70711 0 0.846724 0.532033 0 -0.111961 0.993713 0 0.111961 0.993713 0 0.222428 0.974516 -0.0290725 0.330286 0.943881 0 0.532035 0.846722 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.029151 -0.258712 0.965515 0.0859894 -0.24574 0.965514 0.0859888 -0.245741 0.965514 0.138512 -0.220448 0.965514 0.138513 -0.220443 0.965515 0.184097 -0.184091 0.965515 0.184097 -0.18409 0.965515 0.220441 -0.138516 0.965515 0.220441 -0.138514 0.965515 0.245736 -0.0859874 0.965515 0.245738 -0.085994 0.965514 0.258713 -0.029149 0.965514 0.258708 -0.0291417 0.965516 0.258708 0.0291484 0.965516 0.258715 0.0291423 0.965514 0.24574 0.0859884 0.965514 0.245733 0.0859922 0.965516 0.22044 0.138515 0.965515 0.220442 0.138515 0.965515 0.184096 0.184091 0.965515 0.184098 0.184091 0.965515 0.13851 0.220446 0.965515 0.138515 0.220446 0.965514 0.0859896 0.24574 0.965514 0.0859884 0.24574 0.965514 0.029151 0.258712 0.965515 0.029151 0.258712 0.965515 -0.0291502 0.258712 0.965515 -0.0291509 0.258711 0.965515 -0.0859886 0.245737 0.965515 -0.085986 0.245742 0.965514 -0.138515 0.220446 0.965514 -0.138515 0.220446 0.965514 -0.184096 0.184098 0.965514 -0.184097 0.18409 0.965515 -0.220441 0.138516 0.965515 -0.220441 0.138514 0.965515 -0.245736 0.0859868 0.965515 -0.245735 0.0859835 0.965516 -0.258706 0.0291482 0.965516 -0.258708 0.0291506 0.965516 -0.258708 -0.0291484 0.965516 -0.258706 -0.0291506 0.965516 -0.245733 -0.0859865 0.965516 -0.245737 -0.0859844 0.965515 -0.22044 -0.138515 0.965515 -0.220442 -0.138515 0.965515 -0.184093 -0.184095 0.965515 -0.184101 -0.184094 0.965513 -0.138515 -0.220446 0.965514 -0.138515 -0.220446 0.965514 -0.0859896 -0.24574 0.965514 -0.0859847 -0.245738 0.965515 -0.0291501 -0.258711 0.965515 -0.029151 -0.258712 0.965515 0.029151 -0.258712 0.965515 0.0794231 -0.704871 0.704875 0.23428 -0.669525 0.704875 0.234281 -0.669525 0.704876 0.377382 -0.60061 0.704876 0.377379 -0.600617 0.704872 0.501577 -0.501573 0.704872 0.501579 -0.501564 0.704878 0.600604 -0.377388 0.704879 0.600604 -0.377396 0.704874 0.669531 -0.234268 0.704874 0.669536 -0.234283 0.704864 0.704883 -0.0794215 0.704864 0.70488 -0.0794182 0.704866 0.70488 0.0794208 0.704866 0.704883 0.0794184 0.704864 0.669539 0.23427 0.704866 0.669527 0.234278 0.704874 0.600607 0.37739 0.704874 0.6006 0.377393 0.704879 0.501574 0.501569 0.704877 0.501583 0.501568 0.704872 0.377384 0.600614 0.704872 0.377377 0.600613 0.704877 0.23428 0.669525 0.704876 0.234281 0.669525 0.704875 0.0794207 0.704871 0.704875 0.0794234 0.704873 0.704873 -0.079419 0.704873 0.704873 -0.0794209 0.704871 0.704875 -0.23428 0.669525 0.704875 -0.234281 0.669525 0.704876 -0.377382 0.60061 0.704876 -0.377384 0.600604 0.70488 -0.50157 0.501566 0.704882 -0.501569 0.501574 0.704877 -0.600604 0.377388 0.704879 -0.600604 0.377396 0.704874 -0.669531 0.234268 0.704874 -0.669536 0.234281 0.704865 -0.704882 0.0794209 0.704864 -0.70488 0.0794182 0.704866 -0.70488 -0.0794212 0.704866 -0.704883 -0.0794185 0.704864 -0.66954 -0.234271 0.704864 -0.669526 -0.234279 0.704874 -0.600607 -0.37739 0.704874 -0.6006 -0.377393 0.704879 -0.501574 -0.501569 0.704877 -0.501565 -0.50157 0.704883 -0.37738 -0.600607 0.70488 -0.377386 -0.600608 0.704876 -0.23428 -0.669525 0.704876 -0.234281 -0.669525 0.704875 -0.0794188 -0.704872 0.704875 -0.0794211 -0.704873 0.704873 0.0794209 -0.704873 0.704873 0.108196 -0.960254 0.257305 0.319165 -0.9121 0.257307 0.319163 -0.912102 0.257303 0.514122 -0.818214 0.257303 0.514115 -0.818222 0.25729 0.683299 -0.683305 0.257287 0.683303 -0.683297 0.257297 0.818217 -0.514121 0.257295 0.818216 -0.514124 0.257291 0.912104 -0.319168 0.25729 0.912105 -0.319144 0.257318 0.960252 -0.108185 0.257317 0.960254 -0.108195 0.257306 0.960255 0.108185 0.257306 0.960251 0.108194 0.257317 0.912097 0.319166 0.257317 0.912112 0.319146 0.25729 0.818218 0.514121 0.257291 0.818215 0.514123 0.257295 0.683298 0.683303 0.257296 0.683305 0.683299 0.257287 0.514124 0.818217 0.25729 0.514113 0.818219 0.257303 0.319166 0.912101 0.257303 0.319162 0.912101 0.257307 0.108191 0.960255 0.257305 0.108196 0.960256 0.257299 -0.108191 0.960256 0.257299 -0.108193 0.960255 0.257302 -0.319159 0.912105 0.257298 -0.319163 0.912102 0.257303 -0.514122 0.818214 0.257303 -0.514115 0.818222 0.25729 -0.683299 0.683305 0.257287 -0.683303 0.683297 0.257297 -0.818217 0.514121 0.257295 -0.818216 0.514124 0.257291 -0.912104 0.319168 0.25729 -0.912105 0.319144 0.257318 -0.960252 0.108185 0.257317 -0.960254 0.108194 0.257306 -0.960255 -0.108186 0.257306 -0.960251 -0.108195 0.257317 -0.912097 -0.319166 0.257317 -0.912112 -0.319146 0.25729 -0.818218 -0.514121 0.257291 -0.818215 -0.514123 0.257295 -0.683298 -0.683303 0.257296 -0.683305 -0.683299 0.257287 -0.514124 -0.818217 0.25729 -0.514113 -0.818219 0.257303 -0.319159 -0.912104 0.257303 -0.319163 -0.912104 0.257298 -0.108191 -0.960255 0.257302 -0.108193 -0.960256 0.257299 0.108191 -0.960256 0.257299 0.029151 -0.258712 0.965515 0.0859894 -0.24574 0.965514 0.0859888 -0.245741 0.965514 0.138512 -0.220448 0.965514 0.138513 -0.220443 0.965515 0.184097 -0.184091 0.965515 0.184097 -0.18409 0.965515 0.220441 -0.138516 0.965515 0.220441 -0.138514 0.965515 0.245736 -0.0859868 0.965515 0.245739 -0.0859942 0.965514 0.258714 -0.029149 0.965514 0.258708 -0.0291415 0.965516 0.258708 0.0291484 0.965516 0.258715 0.0291425 0.965514 0.24574 0.0859888 0.965514 0.245733 0.0859922 0.965516 0.22044 0.138515 0.965515 0.220442 0.138515 0.965515 0.184096 0.184091 0.965515 0.184098 0.184091 0.965515 0.13851 0.220446 0.965515 0.138515 0.220446 0.965514 0.0859896 0.24574 0.965514 0.0859884 0.24574 0.965514 0.029151 0.258712 0.965515 0.029151 0.258712 0.965515 -0.0291502 0.258712 0.965515 -0.0291509 0.258711 0.965515 -0.0859886 0.245737 0.965515 -0.085986 0.245742 0.965514 -0.138515 0.220446 0.965514 -0.138515 0.220446 0.965514 -0.184096 0.184098 0.965514 -0.184097 0.18409 0.965515 -0.220441 0.138516 0.965515 -0.220441 0.138514 0.965515 -0.245736 0.0859874 0.965515 -0.245734 0.0859833 0.965516 -0.258706 0.0291482 0.965516 -0.258708 0.0291509 0.965516 -0.258708 -0.0291484 0.965516 -0.258706 -0.0291503 0.965516 -0.245734 -0.0859861 0.965516 -0.245737 -0.0859844 0.965515 -0.22044 -0.138515 0.965515 -0.220442 -0.138515 0.965515 -0.184093 -0.184095 0.965515 -0.184101 -0.184094 0.965513 -0.138515 -0.220446 0.965514 -0.138515 -0.220446 0.965514 -0.0859896 -0.24574 0.965514 -0.0859847 -0.245738 0.965515 -0.0291501 -0.258711 0.965515 -0.029151 -0.258712 0.965515 0.029151 -0.258712 0.965515 0.0794231 -0.704871 0.704875 0.23428 -0.669525 0.704875 0.234281 -0.669525 0.704876 0.377382 -0.60061 0.704876 0.377379 -0.600617 0.704872 0.501577 -0.501573 0.704872 0.501579 -0.501564 0.704878 0.600604 -0.377388 0.704879 0.600604 -0.377396 0.704874 0.669531 -0.234268 0.704874 0.669536 -0.234281 0.704865 0.704882 -0.0794209 0.704864 0.70488 -0.0794182 0.704866 0.70488 0.0794212 0.704866 0.704883 0.0794185 0.704864 0.66954 0.234271 0.704864 0.669526 0.234279 0.704874 0.600607 0.37739 0.704874 0.6006 0.377393 0.704879 0.501574 0.501569 0.704877 0.501583 0.501568 0.704872 0.377384 0.600614 0.704872 0.377377 0.600613 0.704877 0.23428 0.669525 0.704876 0.234281 0.669525 0.704875 0.0794207 0.704871 0.704875 0.0794234 0.704873 0.704873 -0.079419 0.704873 0.704873 -0.0794209 0.704871 0.704875 -0.23428 0.669525 0.704875 -0.234281 0.669525 0.704876 -0.377382 0.60061 0.704876 -0.377384 0.600604 0.70488 -0.50157 0.501566 0.704882 -0.501569 0.501574 0.704877 -0.600604 0.377388 0.704879 -0.600604 0.377396 0.704874 -0.669531 0.234268 0.704874 -0.669536 0.234283 0.704864 -0.704883 0.0794215 0.704864 -0.70488 0.0794182 0.704866 -0.70488 -0.0794208 0.704866 -0.704883 -0.0794184 0.704864 -0.669539 -0.23427 0.704866 -0.669527 -0.234278 0.704874 -0.600607 -0.37739 0.704874 -0.6006 -0.377393 0.704879 -0.501574 -0.501569 0.704877 -0.501565 -0.50157 0.704883 -0.37738 -0.600607 0.70488 -0.377386 -0.600608 0.704876 -0.23428 -0.669525 0.704876 -0.234281 -0.669525 0.704875 -0.0794188 -0.704872 0.704875 -0.0794211 -0.704873 0.704873 0.0794209 -0.704873 0.704873 0.108196 -0.960254 0.257305 0.319165 -0.9121 0.257307 0.319163 -0.912102 0.257303 0.514122 -0.818214 0.257303 0.514115 -0.818222 0.25729 0.683299 -0.683305 0.257287 0.683303 -0.683297 0.257297 0.818217 -0.514121 0.257295 0.818216 -0.514124 0.257291 0.912104 -0.319168 0.25729 0.912105 -0.319144 0.257318 0.960252 -0.108185 0.257317 0.960254 -0.108194 0.257306 0.960255 0.108186 0.257306 0.960251 0.108195 0.257317 0.912097 0.319166 0.257317 0.912112 0.319146 0.25729 0.818218 0.514121 0.257291 0.818215 0.514123 0.257295 0.683298 0.683303 0.257296 0.683305 0.683299 0.257287 0.514124 0.818217 0.25729 0.514113 0.818219 0.257303 0.319166 0.912101 0.257303 0.319162 0.912101 0.257307 0.108191 0.960255 0.257305 0.108196 0.960256 0.257299 -0.108191 0.960256 0.257299 -0.108193 0.960255 0.257302 -0.319159 0.912105 0.257298 -0.319163 0.912102 0.257303 -0.514122 0.818214 0.257303 -0.514115 0.818222 0.25729 -0.683299 0.683305 0.257287 -0.683303 0.683297 0.257297 -0.818217 0.514121 0.257295 -0.818216 0.514124 0.257291 -0.912104 0.319168 0.25729 -0.912105 0.319144 0.257318 -0.960252 0.108185 0.257317 -0.960254 0.108195 0.257306 -0.960255 -0.108185 0.257306 -0.960251 -0.108194 0.257317 -0.912097 -0.319166 0.257317 -0.912112 -0.319146 0.25729 -0.818218 -0.514121 0.257291 -0.818215 -0.514123 0.257295 -0.683298 -0.683303 0.257296 -0.683305 -0.683299 0.257287 -0.514124 -0.818217 0.25729 -0.514113 -0.818219 0.257303 -0.319159 -0.912104 0.257303 -0.319163 -0.912104 0.257298 -0.108191 -0.960255 0.257302 -0.108193 -0.960256 0.257299 0.108191 -0.960256 0.257299 -0.0226387 0.258757 -0.965677 -0.0672273 0.250896 -0.965677 -0.0672258 0.250894 -0.965678 -0.109774 0.235408 -0.965677 -0.109772 0.235406 -0.965678 -0.148982 0.212767 -0.965678 -0.14898 0.212765 -0.965679 -0.183659 0.183664 -0.96568 -0.183669 0.183669 -0.965677 -0.212773 0.148983 -0.965677 -0.212775 0.148984 -0.965676 -0.235413 0.109776 -0.965676 -0.235412 0.109776 -0.965676 -0.250899 0.0672282 -0.965676 -0.250898 0.0672282 -0.965676 -0.258761 0.0226363 -0.965676 -0.258759 0.0226367 -0.965677 -0.258759 -0.0226361 -0.965677 -0.258761 -0.0226369 -0.965676 -0.250899 -0.067228 -0.965676 -0.250899 -0.0672283 -0.965676 -0.235412 -0.109776 -0.965676 -0.235414 -0.109778 -0.965676 -0.212776 -0.148986 -0.965676 -0.212774 -0.148983 -0.965677 -0.183667 -0.183671 -0.965677 -0.183662 -0.183662 -0.965679 -0.14898 -0.212765 -0.965679 -0.148981 -0.212767 -0.965678 -0.109773 -0.235405 -0.965678 -0.109774 -0.235411 -0.965677 -0.0672275 -0.250897 -0.965677 -0.0672275 -0.250896 -0.965677 -0.0226381 -0.258758 -0.965677 -0.0226385 -0.258755 -0.965678 0.0226379 -0.258755 -0.965678 0.0226382 -0.258756 -0.965677 0.0672264 -0.250892 -0.965678 0.0672267 -0.250893 -0.965678 0.109771 -0.235406 -0.965678 0.109771 -0.235406 -0.965678 0.148982 -0.212767 -0.965678 0.14898 -0.212765 -0.965679 0.183662 -0.183662 -0.965679 0.183671 -0.183667 -0.965677 0.212771 -0.148986 -0.965677 0.212775 -0.148987 -0.965676 0.235416 -0.109774 -0.965675 0.2354 -0.109771 -0.96568 0.250886 -0.0672245 -0.96568 0.250885 -0.0672245 -0.96568 0.258746 -0.0226392 -0.96568 0.258759 -0.0226367 -0.965677 0.258759 0.0226404 -0.965677 0.258747 0.0226357 -0.96568 0.250885 0.0672244 -0.96568 0.250886 0.0672247 -0.96568 0.235402 0.109767 -0.96568 0.235412 0.109777 -0.965676 0.212773 0.148987 -0.965676 0.212772 0.148986 -0.965677 0.183669 0.183669 -0.965677 0.183664 0.18366 -0.965679 0.14898 0.212765 -0.965679 0.148981 0.212767 -0.965678 0.109771 0.235406 -0.965678 0.10977 0.235403 -0.965679 0.0672256 0.25089 -0.965679 0.0672256 0.250893 -0.965678 0.022638 0.258756 -0.965677 0.0226382 0.258755 -0.965678 -0.0226379 0.258755 -0.965678 -0.0617455 0.705762 -0.705754 -0.183363 0.684316 -0.705755 -0.183361 0.684313 -0.705758 -0.299406 0.642074 -0.70576 -0.299408 0.642076 -0.705757 -0.406349 0.580334 -0.705757 -0.406361 0.580341 -0.705744 -0.500965 0.500962 -0.705742 -0.50094 0.500951 -0.705767 -0.580318 0.406351 -0.705769 -0.580347 0.406358 -0.705741 -0.642096 0.299405 -0.70574 -0.642061 0.299403 -0.705773 -0.684296 0.183357 -0.705776 -0.684298 0.183357 -0.705774 -0.705741 0.0617447 -0.705775 -0.705758 0.0617394 -0.705758 -0.705758 -0.0617462 -0.705758 -0.705741 -0.061738 -0.705774 -0.684297 -0.183357 -0.705774 -0.684296 -0.183356 -0.705776 -0.642066 -0.29939 -0.705774 -0.64209 -0.299416 -0.705741 -0.580341 -0.406367 -0.705741 -0.580325 -0.406342 -0.705768 -0.500947 -0.500944 -0.705767 -0.500957 -0.500969 -0.705742 -0.406357 -0.580344 -0.705744 -0.406354 -0.580331 -0.705757 -0.299407 -0.642077 -0.705757 -0.299407 -0.642074 -0.70576 -0.183362 -0.684312 -0.705758 -0.183362 -0.684316 -0.705755 -0.0617468 -0.705761 -0.705754 -0.0617458 -0.705765 -0.70575 0.0617461 -0.705765 -0.70575 0.0617457 -0.705764 -0.705751 0.183365 -0.684323 -0.705747 0.183363 -0.68432 -0.705751 0.299411 -0.642085 -0.705748 0.299404 -0.642078 -0.705757 0.406349 -0.580334 -0.705757 0.406361 -0.580341 -0.705744 0.500965 -0.500962 -0.705742 0.50096 -0.50096 -0.705747 0.580344 -0.406357 -0.705745 0.580323 -0.406352 -0.705764 0.642067 -0.299403 -0.705767 0.642088 -0.299404 -0.705747 0.684323 -0.183364 -0.705748 0.684325 -0.183364 -0.705746 0.705769 -0.0617472 -0.705746 0.705757 -0.0617509 -0.705757 0.705758 0.0617462 -0.705758 0.705769 0.0617519 -0.705746 0.684324 0.183365 -0.705746 0.684323 0.183364 -0.705748 0.642085 0.299412 -0.705747 0.642071 0.299396 -0.705767 0.580327 0.406345 -0.705765 0.580339 0.406363 -0.705745 0.500961 0.500958 -0.705747 0.500963 0.500963 -0.705742 0.406357 0.580344 -0.705744 0.406354 0.580331 -0.705757 0.299407 0.642077 -0.705757 0.299408 0.642087 -0.705748 0.183364 0.68432 -0.705751 0.183364 0.684323 -0.705747 0.061746 0.705764 -0.705751 0.0617458 0.705765 -0.70575 -0.0617471 0.705765 -0.70575 -0.0842084 0.962496 -0.257897 -0.250067 0.933249 -0.2579 -0.250065 0.933248 -0.257905 -0.408314 0.87565 -0.25791 -0.408326 0.875653 -0.257878 -0.554184 0.791443 -0.257873 -0.554167 0.791441 -0.257917 -0.683183 0.683183 -0.257919 -0.683187 0.683183 -0.25791 -0.791439 0.554172 -0.257912 -0.791428 0.554174 -0.25794 -0.875636 0.408322 -0.257944 -0.875657 0.408312 -0.257886 -0.933254 0.250063 -0.257885 -0.933252 0.250065 -0.257894 -0.962496 0.0842128 -0.257895 -0.962501 0.0842085 -0.257879 -0.9625 -0.0842131 -0.257879 -0.962496 -0.0842081 -0.257895 -0.933252 -0.250062 -0.257894 -0.933254 -0.250065 -0.257885 -0.87565 -0.408329 -0.257886 -0.875643 -0.408306 -0.257944 -0.791433 -0.554167 -0.257941 -0.791434 -0.554178 -0.257912 -0.683185 -0.683185 -0.25791 -0.683185 -0.683181 -0.257919 -0.554177 -0.791433 -0.257917 -0.554173 -0.79145 -0.257873 -0.408318 -0.875657 -0.257878 -0.408323 -0.875646 -0.25791 -0.250066 -0.933248 -0.257905 -0.250065 -0.93325 -0.2579 -0.0842056 -0.962496 -0.257897 -0.0842082 -0.962493 -0.257906 0.084204 -0.962494 -0.257906 0.084207 -0.962496 -0.257897 0.250067 -0.933249 -0.2579 0.250065 -0.933248 -0.257905 0.408314 -0.87565 -0.25791 0.408326 -0.875653 -0.257878 0.554184 -0.791443 -0.257873 0.554167 -0.791441 -0.257917 0.683183 -0.683183 -0.257919 0.683187 -0.683183 -0.25791 0.791439 -0.554172 -0.257912 0.791445 -0.55417 -0.257897 0.875648 -0.408327 -0.257896 0.875651 -0.408326 -0.257886 0.933254 -0.250063 -0.257885 0.933252 -0.250065 -0.257894 0.962496 -0.0842128 -0.257895 0.962501 -0.0842085 -0.257879 0.9625 0.0842131 -0.257879 0.962496 0.0842081 -0.257895 0.933252 0.250062 -0.257894 0.933254 0.250065 -0.257885 0.87565 0.408329 -0.257886 0.875649 0.408325 -0.257895 0.791442 0.554174 -0.257896 0.791442 0.554168 -0.257912 0.683185 0.683185 -0.25791 0.683185 0.683181 -0.257919 0.554177 0.791433 -0.257917 0.554173 0.79145 -0.257873 0.408318 0.875657 -0.257878 0.408323 0.875646 -0.25791 0.250066 0.933248 -0.257905 0.250065 0.93325 -0.2579 0.0842042 0.962496 -0.257897 0.0842068 0.962493 -0.257906 -0.0842054 0.962494 -0.257906 -0.0226387 -0.258757 0.965677 -0.0672273 -0.250896 0.965677 -0.0672277 -0.250897 0.965677 -0.109775 -0.235411 0.965677 -0.109771 -0.235406 0.965678 -0.148982 -0.212767 0.965678 -0.14898 -0.212765 0.965679 -0.183659 -0.183664 0.96568 -0.183669 -0.183669 0.965677 -0.212773 -0.148983 0.965677 -0.212777 -0.148985 0.965676 -0.235414 -0.109777 0.965676 -0.235412 -0.109777 0.965676 -0.250899 -0.0672282 0.965676 -0.250898 -0.0672282 0.965676 -0.258761 -0.0226363 0.965676 -0.258759 -0.0226367 0.965677 -0.258759 0.0226361 0.965677 -0.258761 0.0226369 0.965676 -0.250899 0.067228 0.965676 -0.250899 0.0672283 0.965676 -0.235412 0.109776 0.965676 -0.235412 0.109777 0.965676 -0.212775 0.148984 0.965676 -0.212774 0.148983 0.965677 -0.183667 0.183671 0.965677 -0.183662 0.183662 0.965679 -0.14898 0.212765 0.965679 -0.148981 0.212767 0.965678 -0.109773 0.235405 0.965678 -0.109773 0.235408 0.965677 -0.0672266 0.250893 0.965678 -0.0672265 0.250896 0.965677 -0.0226381 0.258758 0.965677 -0.0226385 0.258755 0.965678 0.0226379 0.258755 0.965678 0.0226382 0.258756 0.965677 0.0672264 0.250892 0.965678 0.0672249 0.25089 0.965679 0.109769 0.235403 0.965679 0.109772 0.235406 0.965678 0.148982 0.212767 0.965678 0.14898 0.212765 0.965679 0.183662 0.183662 0.965679 0.183671 0.183667 0.965677 0.212771 0.148986 0.965677 0.212773 0.148987 0.965676 0.235414 0.109773 0.965676 0.2354 0.109771 0.96568 0.250886 0.0672245 0.96568 0.250885 0.0672245 0.96568 0.258746 0.0226392 0.96568 0.258759 0.0226367 0.965677 0.258759 -0.0226404 0.965677 0.258747 -0.0226357 0.96568 0.250885 -0.0672244 0.96568 0.250886 -0.0672247 0.96568 0.235402 -0.109767 0.96568 0.235414 -0.109778 0.965676 0.212775 -0.148989 0.965676 0.212772 -0.148985 0.965677 0.183669 -0.183669 0.965677 0.183664 -0.18366 0.965679 0.14898 -0.212765 0.965679 0.148981 -0.212767 0.965678 0.109771 -0.235406 0.965678 0.109771 -0.235406 0.965678 0.0672265 -0.250893 0.965678 0.0672265 -0.250892 0.965678 0.022638 -0.258756 0.965677 0.0226382 -0.258755 0.965678 -0.0226379 -0.258755 0.965678 -0.0617442 -0.705747 0.705768 -0.183359 -0.684302 0.705769 -0.183357 -0.684299 0.705773 -0.2994 -0.642061 0.705774 -0.299402 -0.642063 0.705771 -0.406341 -0.580322 0.705772 -0.406353 -0.580329 0.705759 -0.500955 -0.500952 0.705756 -0.50093 -0.500941 0.705781 -0.580306 -0.406343 0.705783 -0.580335 -0.406349 0.705756 -0.642083 -0.299399 0.705755 -0.642048 -0.299397 0.705788 -0.684282 -0.183353 0.70579 -0.684284 -0.183353 0.705789 -0.705726 -0.0617435 0.705789 -0.705744 -0.0617381 0.705772 -0.705743 0.061745 0.705772 -0.705727 0.0617367 0.705789 -0.684284 0.183354 0.705788 -0.684282 0.183353 0.70579 -0.642053 0.299384 0.705788 -0.642077 0.29941 0.705755 -0.580329 0.406359 0.705755 -0.580313 0.406334 0.705783 -0.500937 0.500934 0.705782 -0.500947 0.500959 0.705757 -0.406349 0.580332 0.705759 -0.406346 0.580319 0.705771 -0.299401 0.642064 0.705771 -0.299401 0.642061 0.705774 -0.183358 0.684299 0.705773 -0.183358 0.684302 0.705769 -0.0617455 0.705747 0.705768 -0.0617445 0.70575 0.705765 0.0617448 0.70575 0.705765 0.0617445 0.70575 0.705765 0.183361 0.684309 0.705762 0.183359 0.684306 0.705765 0.299405 0.642072 0.705762 0.299398 0.642065 0.705771 0.406341 0.580322 0.705772 0.406353 0.580329 0.705759 0.500955 0.500952 0.705756 0.50095 0.50095 0.705761 0.580332 0.406348 0.705759 0.580311 0.406344 0.705779 0.642054 0.299397 0.705782 0.642075 0.299398 0.705762 0.684309 0.183361 0.705762 0.684311 0.18336 0.705761 0.705755 0.061746 0.70576 0.705743 0.0617496 0.705772 0.705743 -0.061745 0.705772 0.705754 -0.0617506 0.70576 0.68431 -0.183361 0.705761 0.684309 -0.18336 0.705762 0.642072 -0.299406 0.705762 0.642058 -0.29939 0.705781 0.580315 -0.406337 0.705779 0.580327 -0.406355 0.70576 0.500951 -0.500948 0.705761 0.500953 -0.500953 0.705756 0.406349 -0.580332 0.705759 0.406346 -0.580319 0.705771 0.299401 -0.642064 0.705771 0.299402 -0.642074 0.705762 0.18336 -0.684306 0.705765 0.18336 -0.684309 0.705762 0.0617447 -0.70575 0.705765 0.0617445 -0.70575 0.705765 -0.0617458 -0.70575 0.705765 -0.0842086 -0.962498 0.25789 -0.250067 -0.933251 0.257893 -0.250065 -0.93325 0.257898 -0.408315 -0.875651 0.257902 -0.408327 -0.875655 0.257871 -0.554185 -0.791444 0.257866 -0.554168 -0.791442 0.257909 -0.683184 -0.683184 0.257912 -0.683188 -0.683184 0.257903 -0.79144 -0.554173 0.257905 -0.791429 -0.554175 0.257933 -0.875638 -0.408323 0.257937 -0.875659 -0.408313 0.257879 -0.933256 -0.250063 0.257878 -0.933253 -0.250065 0.257886 -0.962498 -0.0842129 0.257887 -0.962502 -0.0842086 0.257872 -0.962502 0.0842133 0.257872 -0.962498 0.0842083 0.257887 -0.933254 0.250063 0.257886 -0.933256 0.250066 0.257878 -0.875652 0.408329 0.257879 -0.875645 0.408307 0.257937 -0.791434 0.554168 0.257933 -0.791435 0.55418 0.257905 -0.683186 0.683186 0.257902 -0.683186 0.683182 0.257912 -0.554178 0.791435 0.25791 -0.554174 0.791452 0.257866 -0.408319 0.875659 0.257871 -0.408324 0.875647 0.257902 -0.250067 0.93325 0.257898 -0.250066 0.933251 0.257893 -0.0842058 0.962498 0.25789 -0.0842084 0.962495 0.257899 0.0842041 0.962496 0.257899 0.0842072 0.962498 0.25789 0.250067 0.933251 0.257893 0.250065 0.93325 0.257898 0.408315 0.875651 0.257902 0.408327 0.875655 0.257871 0.554185 0.791444 0.257866 0.554168 0.791442 0.257909 0.683184 0.683184 0.257912 0.683188 0.683184 0.257903 0.79144 0.554173 0.257905 0.791447 0.554171 0.257889 0.875649 0.408328 0.257888 0.875653 0.408327 0.257879 0.933256 0.250063 0.257878 0.933253 0.250065 0.257886 0.962498 0.0842129 0.257887 0.962502 0.0842086 0.257872 0.962502 -0.0842133 0.257872 0.962498 -0.0842083 0.257887 0.933254 -0.250063 0.257886 0.933256 -0.250066 0.257878 0.875652 -0.408329 0.257879 0.875651 -0.408326 0.257888 0.791444 -0.554175 0.257889 0.791443 -0.554169 0.257905 0.683186 -0.683186 0.257902 0.683186 -0.683182 0.257912 0.554178 -0.791435 0.25791 0.554174 -0.791452 0.257866 0.408319 -0.875659 0.257871 0.408324 -0.875647 0.257902 0.250067 -0.93325 0.257898 0.250066 -0.933251 0.257893 0.0842043 -0.962498 0.25789 0.0842069 -0.962495 0.257899 -0.0842056 -0.962496 0.257899 -0.987688 0.0509304 -0.147913 -0.987688 0.0509304 -0.147913 -0.891007 0.147804 -0.429255 -0.891007 0.147804 -0.429255 -0.707105 0.230212 -0.668584 -0.707105 0.230212 -0.668584 -0.453991 0.290083 -0.842463 -0.453991 0.290083 -0.842463 -0.156433 0.32156 -0.933878 -0.156433 0.32156 -0.933878 0 0.325568 -0.945519 0 0.325568 -0.945519 0 0.325568 -0.945519 0 0.325568 -0.945519 0 0.325568 -0.945519 0 0.325568 -0.945519 0 0.325568 -0.945519 0 0.325568 -0.945519 0.156433 0.32156 -0.933878 0.156433 0.32156 -0.933878 0.45399 0.290083 -0.842464 0.45399 0.290083 -0.842464 0.707107 0.230211 -0.668582 0.707107 0.230211 -0.668582 0.891007 0.147804 -0.429255 0.891007 0.147804 -0.429255 0.987688 0.0509304 -0.147913 0.987688 0.0509304 -0.147913 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.987688 -0.0509305 0.147913 0.987688 -0.0509305 0.147913 0.891007 -0.147805 0.429256 0.891007 -0.147805 0.429256 0.707107 -0.230211 0.668582 0.707107 -0.230211 0.668582 0.45399 -0.290083 0.842463 0.45399 -0.290083 0.842463 0.156435 -0.32156 0.933878 0.156435 -0.32156 0.933878 0 -0.325568 0.945519 0 -0.325568 0.945519 0 -0.325568 0.945519 0 -0.325568 0.945519 0 -0.325568 0.945519 0 -0.325568 0.945519 0 -0.325568 0.945519 0 -0.325568 0.945519 -0.156435 -0.32156 0.933878 -0.156435 -0.32156 0.933878 -0.453991 -0.290083 0.842463 -0.453991 -0.290083 0.842463 -0.707105 -0.230212 0.668584 -0.707105 -0.230212 0.668584 -0.891007 -0.147805 0.429256 -0.891007 -0.147805 0.429256 -0.987688 -0.0509305 0.147913 -0.987688 -0.0509305 0.147913 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 2.58971e-06 -0.945519 -0.325567 1.58809e-06 -0.945518 -0.32557 -2.32654e-07 -0.945517 -0.325573 1.31971e-06 -0.945519 -0.325567 2.03846e-06 -0.94552 -0.325565 -2.57629e-06 -0.945515 -0.325578 0 -0.945521 -0.325561 1.22611e-06 -0.945518 -0.325569 9.79436e-07 -0.945518 -0.325568 -8.86529e-08 -0.945519 -0.325568 -1.10187e-06 -0.945518 -0.325569 0 -0.945519 -0.325568 -5.98122e-06 -0.945519 -0.325566 -1.11668e-06 -0.945519 -0.325567 2.68186e-06 -0.945519 -0.325566 -2.76377e-06 -0.945516 -0.325577 0 -0.945521 -0.325561 2.52602e-06 -0.945515 -0.325578 -2.24395e-06 -0.94552 -0.325565 2.81877e-06 -0.945516 -0.325576 -2.43627e-06 -0.945519 -0.325566 0 -0.945519 -0.325566 2.33822e-07 -0.945519 -0.325568 6.58278e-07 -0.945518 -0.325569 -1.78762e-06 -0.945519 -0.325566 0 -0.945519 -0.325567 -6.2663e-07 -0.945518 -0.325569 1.0714e-07 -0.945518 -0.325569 3.41977e-07 -0.945519 -0.325567 1.58438e-06 -0.945519 -0.325568 -1.87836e-07 -0.945518 -0.325569 8.1214e-08 -0.945519 -0.325567 2.76868e-07 -0.945519 -0.325568 -1.14605e-06 -0.945519 -0.325568 1.07734e-06 -0.945519 -0.325567 -2.80577e-07 -0.945518 -0.325569 -2.27563e-07 -0.945519 -0.325568 1.18186e-06 -0.945519 -0.325568 -1.28966e-06 -0.945519 -0.325567 -6.10745e-07 -0.945518 -0.325569 -2.37185e-06 -0.945519 -0.325566 1.62905e-06 -0.945519 -0.325568 2.25298e-07 -0.945519 -0.325566 -1.13357e-06 -0.945514 -0.325582 0 -0.945532 -0.32553 2.00807e-06 -0.945515 -0.325579 -4.7686e-07 -0.945519 -0.325566 -1.21556e-05 -0.945518 -0.32557 3.62033e-06 -0.945519 -0.325567 -9.81938e-07 -0.945518 -0.325568 3.63517e-06 -0.945518 -0.325569 2.25985e-06 -0.945518 -0.325569 0 -0.945519 -0.325568 -3.53174e-06 -0.945519 -0.325568 -3.15452e-06 -0.945519 -0.325568 0 -0.945517 -0.325572 -6.22136e-07 -0.945519 -0.325567 5.56081e-07 -0.945518 -0.325568 -1.90753e-06 -0.945519 -0.325567 1.64741e-06 -0.945519 -0.325567 -5.73458e-07 -0.945518 -0.325568 7.42917e-07 -0.945519 -0.325566 0 -0.945517 -0.325573 -9.24552e-06 -0.94552 -0.325563 -9.58955e-06 -0.945521 -0.32556 2.50055e-06 -0.945518 -0.325569 3.85505e-06 -0.945518 -0.32557 -2.81878e-06 -0.945516 -0.325576 0 -0.945521 -0.325561 1.65235e-06 -0.945513 -0.325583 -9.88898e-07 -0.94552 -0.325563 4.13373e-07 -0.945519 -0.325567 1.28803e-06 -0.945518 -0.325569 4.09037e-07 -0.945519 -0.325568 -1.82132e-06 -0.945518 -0.325569 -9.7944e-07 -0.945518 -0.325569 -1.23849e-06 -0.945518 -0.325569 -4.88532e-07 -0.945519 -0.325568 1.08858e-06 -0.94552 -0.325563 -1.62011e-06 -0.945513 -0.325583 0 -0.945521 -0.325561 2.76206e-06 -0.945516 -0.325576 -2.68186e-06 -0.945519 -0.325566 0 -0.945519 -0.325566 6.86394e-07 -0.945519 -0.325568 1.93253e-06 -0.945518 -0.325568 1.92773e-06 -0.945519 -0.325568 -2.46112e-07 -0.945519 -0.325568 -1.04585e-06 -0.945519 -0.325568 8.17168e-06 -0.945518 -0.32557 -2.16869e-06 -0.945519 -0.325568 -2.00983e-06 -0.945519 -0.325568 0 -0.945519 -0.325567 -1.5126e-06 -0.945519 -0.325566 2.43627e-06 -0.945519 -0.325566 -2.95451e-06 -0.945518 -0.325569 9.29373e-07 -0.945519 -0.325567 7.659e-07 -0.945519 -0.325567 -2.69067e-07 -0.945518 -0.325569 0 -0.945519 -0.325568 -1.08389e-06 -0.945518 -0.325569 -5.74754e-06 -0.945518 -0.325571 9.31e-09 -0.945518 -0.325568 2.84778e-06 -0.945519 -0.325567 2.79241e-06 -0.945519 -0.325568 0 -0.945512 -0.325587 0 -0.945512 -0.325587 -1.84184e-06 -0.945519 -0.325566 -1.58893e-06 -0.945519 -0.325567 1.14818e-06 -0.945519 -0.325567 3.12881e-06 -0.94552 -0.325564 0 -0.945518 -0.325571 -3.34731e-06 -0.94552 -0.325565 -1.27606e-06 -0.945519 -0.325567 1.10336e-06 -0.945518 -0.325568 5.36156e-07 -0.945518 -0.325569 -1.0335e-06 -0.945518 -0.32557 -1.29337e-06 -0.945518 -0.32557 1.58893e-06 -0.945519 -0.325567 1.84184e-06 -0.945519 -0.325566 0 -0.945512 -0.325587 1.05292e-06 -0.945518 -0.325569 0 -0.945512 -0.325587 -2.7924e-06 -0.945519 -0.325568 -4.35309e-07 -0.945518 -0.325571 -1.34825e-06 -0.945519 -0.325566 1.74733e-06 -0.945518 -0.325571 0 -0.945518 -0.325571 -3.1288e-06 -0.94552 -0.325564 -1.12148e-06 -0.945519 -0.325567 7.42001e-07 -0.945519 -0.325566 3.11709e-07 -0.945518 -0.32557 -7.65547e-08 -0.945519 -0.325567 -3.75363e-07 -0.945518 -0.325569 -3.53025e-07 -0.945518 -0.325569 -1.37866e-07 -0.945519 -0.325568 6.73053e-07 -0.945519 -0.325566 2.38912e-06 -0.945521 -0.325561 -7.36157e-06 -0.945518 -0.32557 2.99211e-06 -0.945519 -0.325567 2.36005e-06 -0.945519 -0.325567 0 -0.945518 -0.325569 0 -0.945518 -0.325569 -1.81062e-06 -0.945519 -0.325566 4.91721e-08 -0.945519 -0.325568 -5.14603e-07 -0.94552 -0.325565 9.43061e-07 -0.945518 -0.325569 1.04634e-06 -0.945518 -0.325571 -2.04392e-06 -0.945519 -0.325568 6.52835e-06 -0.94552 -0.325563 -1.63024e-06 -0.945517 -0.325572 2.04728e-07 -0.945519 -0.325567 1.91764e-07 -0.945519 -0.325568 -8.90693e-08 -0.94552 -0.325565 -2.33694e-06 -0.945515 -0.325577 9.6374e-08 -0.945531 -0.325533 1.5282e-06 -0.945514 -0.32558 -3.28053e-07 -0.945519 -0.325566 9.71211e-07 -0.945518 -0.325568 0 -0.945519 -0.325567 0 -0.945519 -0.325568 6.77531e-07 -0.945518 -0.325569 -9.97301e-06 -0.94551 -0.325593 1.21853e-07 -0.945519 -0.325568 -1.37071e-06 -0.945519 -0.325568 -7.48885e-07 -0.945519 -0.325568 3.28052e-07 -0.945519 -0.325566 -2.99211e-06 -0.945519 -0.325567 1.79123e-06 -0.945515 -0.325579 -9.71209e-07 -0.945518 -0.325568 0 -0.945518 -0.325569 0 -0.945518 -0.325569 -2.36005e-06 -0.945519 -0.325567 -0.00148434 -0.942423 -0.334419 0 -0.945505 -0.325608 0 -0.945532 -0.32553 -1.5282e-06 -0.945514 -0.32558 -4.02749e-07 -0.945519 -0.325566 1.29237e-06 -0.945518 -0.325568 6.93429e-07 -0.945519 -0.325568 -9.81535e-06 -0.945518 -0.32557 3.34034e-06 -0.945519 -0.325567 -2.49334e-06 -0.945521 -0.325562 0 -0.945519 -0.325567 -6.44111e-07 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 1.04051e-06 -0.945519 -0.325568 0 -0.945519 -0.325568 0 -0.945519 -0.325568 1.11693e-06 -0.945519 -0.325568 -4.349e-06 -0.945517 -0.325571 -1.41297e-06 -0.945519 -0.325567 1.55275e-06 -0.945518 -0.325568 2.41502e-06 -0.945519 -0.325567 2.5005e-06 -0.945519 -0.325567 0 -0.945512 -0.325587 0 -0.945512 -0.325587 -1.32986e-06 -0.94552 -0.325565 -1.05933e-06 -0.945519 -0.325566 1.52753e-08 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 2.02217e-06 -0.945518 -0.325569 -2.46341e-06 -0.945518 -0.32557 -7.37093e-07 -0.945518 -0.325569 8.70915e-07 -0.945519 -0.325567 0 -0.945518 -0.325568 7.73101e-06 -0.945514 -0.325582 -3.44382e-06 -0.94552 -0.325565 9.11227e-07 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 3.44069e-08 -0.945518 -0.325569 -2.71679e-06 -0.945518 -0.325571 4.52127e-07 -0.945519 -0.325568 0 -0.945519 -0.325568 0 -0.945519 -0.325568 0 -0.945519 -0.325568 0 -0.945519 -0.325568 6.28961e-07 -0.945519 -0.325568 -2.2326e-06 -0.945518 -0.325571 0 -0.945505 -0.325608 0 -0.945505 -0.325608 0 -0.945505 -0.325608 0 -0.945505 -0.325608 0 -0.945505 -0.325608 0 -0.945505 -0.325608 0 -0.945505 -0.325608 0 -0.945505 -0.325608 0 -0.945505 -0.325608 0 -0.945505 -0.325608 -1.0474e-06 -0.945485 -0.325665 2.12297e-06 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 0 -0.945518 -0.325569 0 0.945519 0.325568 3.32845e-07 0.945519 0.325567 0 0.945518 0.325569 0 0.945519 0.325568 -3.62885e-06 0.945519 0.325568 0 0.945519 0.325568 4.83155e-07 0.945518 0.32557 9.81772e-07 0.945518 0.325571 -1.02688e-06 0.945518 0.325569 -1.13985e-06 0.945518 0.325569 3.1006e-06 0.94552 0.325565 -1.75134e-06 0.945518 0.325569 -6.71796e-07 0.94552 0.325565 -4.09748e-07 0.945518 0.325568 3.19054e-07 0.945519 0.325568 -3.0661e-06 0.945518 0.32557 3.11098e-07 0.945519 0.325567 -3.9699e-06 0.945514 0.325583 -9.09124e-07 0.945518 0.325569 -1.21989e-05 0.945515 0.32558 6.25729e-06 0.94552 0.325563 9.67889e-07 0.945518 0.32557 0 0.945519 0.325568 9.41263e-06 0.945517 0.325573 -7.27571e-06 0.94552 0.325565 4.6226e-06 0.945514 0.32558 6.81233e-08 0.945518 0.325569 -8.53227e-07 0.945519 0.325568 -2.33005e-06 0.945521 0.325562 -9.32093e-07 0.945518 0.325569 2.85856e-07 0.94552 0.325565 -4.83087e-07 0.945516 0.325577 3.47857e-07 0.945517 0.325571 2.98501e-08 0.945519 0.325568 1.34505e-07 0.945518 0.325569 6.48767e-06 0.94552 0.325564 -2.87487e-07 0.945518 0.325569 -5.25674e-07 0.945519 0.325568 3.00308e-06 0.94552 0.325564 -9.95175e-06 0.945516 0.325575 4.49423e-06 0.945519 0.325568 -5.16607e-06 0.945521 0.325562 8.10299e-08 0.945518 0.32557 5.33279e-07 0.945516 0.325577 -4.16332e-07 0.945518 0.325571 4.57938e-06 0.945521 0.325562 1.64392e-07 0.945519 0.325567 -1.22717e-07 0.945519 0.325568 -1.74083e-06 0.945519 0.325568 5.2779e-06 0.945521 0.32556 0 0.945519 0.325568 -5.04112e-06 0.945522 0.325559 1.57528e-06 0.945519 0.325568 3.1477e-06 0.94552 0.325565 0 0.945519 0.325567 -9.90245e-07 0.945519 0.325566 1.28106e-06 0.945518 0.32557 -6.37511e-06 0.94552 0.325565 2.34639e-06 0.945518 0.325568 4.13968e-07 0.945518 0.325569 -1.19014e-06 0.945518 0.32557 1.63247e-06 0.945519 0.325568 -7.75414e-06 0.945519 0.325566 1.13515e-05 0.94552 0.325564 -9.86161e-06 0.945517 0.325574 1.41605e-06 0.945518 0.325571 -4.84225e-06 0.945515 0.32558 0 0.945519 0.325568 3.13726e-06 0.945513 0.325586 -6.61774e-07 0.945518 0.32557 4.68753e-06 0.94552 0.325565 -1.32127e-06 0.945519 0.325568 -3.56727e-06 0.945518 0.325569 3.19001e-06 0.945519 0.325567 8.05913e-06 0.945519 0.325567 -2.94435e-06 0.945518 0.325569 2.11424e-06 0.945518 0.325569 2.51557e-06 0.945519 0.325568 -5.51168e-06 0.945519 0.325566 0 0.945518 0.325569 -6.74679e-07 0.945517 0.325571 0 0.945519 0.325568 -3.12719e-07 0.945516 0.325575 -2.71924e-06 0.945519 0.325568 5.71462e-07 0.945518 0.325568 -8.09602e-08 0.945518 0.325571 1.02766e-07 0.945518 0.325569 1.90078e-07 0.945519 0.325568 -3.53288e-06 0.94552 0.325563 -1.64238e-06 0.945524 0.325553 0 0.945516 0.325576 3.46247e-06 0.94552 0.325563 5.80599e-07 0.945518 0.32557 -1.4392e-06 0.945519 0.325566 9.93601e-07 0.945518 0.325569 1.80504e-06 0.945519 0.325568 -1.34325e-06 0.945518 0.325571 -7.37846e-07 0.945518 0.32557 -9.30992e-08 0.945519 0.325568 1.67474e-06 0.945524 0.325553 1.0718e-06 0.945518 0.32557 2.18714e-06 0.945518 0.325571 -2.42789e-06 0.945518 0.325569 -8.6835e-07 0.945519 0.325568 2.34337e-06 0.945519 0.325566 0 0.945518 0.325568 -4.37295e-06 0.945519 0.325567 -6.94017e-07 0.945519 0.325567 -3.39927e-07 0.945519 0.325567 3.53286e-06 0.94552 0.325563 0 0.945516 0.325577 0 0.945516 0.325576 3.10038e-06 0.945521 0.325561 3.23638e-07 0.94552 0.325564 1.08064e-06 0.945517 0.325571 -3.60875e-07 0.945519 0.325566 -1.12136e-07 0.945519 0.325568 3.19936e-07 0.945518 0.32557 0 0.945519 0.325567 6.94017e-07 0.945519 0.325567 -3.46459e-06 0.94552 0.325563 -1.1776e-06 0.945518 0.325569 -3.16342e-06 0.945521 0.325561 2.65759e-07 0.945519 0.325568 0 0.945519 0.325567 7.37847e-07 0.945518 0.32557 1.34326e-06 0.945518 0.325571 -4.21176e-07 0.945519 0.325568 1.43921e-06 0.945519 0.325566 0 0.945518 0.325568 -2.59128e-06 0.945519 0.325568 -5.42591e-07 0.945519 0.325568 0 0.945516 0.325577 0 0.945519 0.325566 0 0.945519 0.325566 0 0.945518 0.32557 -4.77601e-06 0.945522 0.325558 0 0.945519 0.325567 0 0.945519 0.325566 0 0.945519 0.325566 0 0.945519 0.325568 0 0.945519 0.325568 1.43719e-06 0.945519 0.325568 2.63934e-06 0.945518 0.325568 0 0.945518 0.325568 0 0.945518 0.325568 -7.49512e-07 0.945518 0.325568 0 0.945518 0.325569 8.69037e-08 0.945518 0.325569 -3.79486e-06 0.945521 0.325562 -1.55939e-05 0.945517 0.325573 2.12174e-06 0.945519 0.325567 -3.43889e-07 0.945518 0.325569 7.03377e-06 0.945519 0.325566 0 0.945518 0.32557 -5.82645e-06 0.945521 0.325562 1.98872e-07 0.945518 0.325569 1.07241e-06 0.945519 0.325566 1.38798e-07 0.945516 0.325575 -3.41681e-07 0.945519 0.325566 0 0.945519 0.325566 0 0.945519 0.325568 -8.47211e-07 0.945519 0.325568 -1.23428e-05 0.945514 0.32558 3.22581e-06 0.945521 0.325561 -1.14447e-06 0.945518 0.325568 0 0.945519 0.325566 1.16302e-05 0.945514 0.325582 -5.73852e-06 0.945521 0.325561 -6.48767e-06 0.94552 0.325564 0 0.945518 0.32557 6.81317e-06 0.94552 0.325565 -2.93029e-05 0.945513 0.325585 1.88869e-06 0.945519 0.325568 -6.87405e-06 0.945521 0.325562 6.92353e-06 0.945519 0.325568 -1.28023e-05 0.945517 0.325574 -2.90386e-07 0.945518 0.325569 2.87485e-07 0.945518 0.325569 -1.49956e-06 0.945519 0.325568 0 0.945519 0.325568 0 0.945519 0.325568 1.04559e-05 0.945519 0.325568 -8.77895e-06 0.94552 0.325563 5.16607e-06 0.945521 0.325562 -1.57527e-06 0.945519 0.325568 0 0.945519 0.325566 1.3036e-05 0.945512 0.325587 -5.44859e-06 0.945521 0.32556 -9.67884e-07 0.945518 0.32557 3.96653e-06 0.945514 0.325583 0 0.945519 0.325568 -4.46704e-06 0.945514 0.325581 -1.70508e-05 0.945517 0.325572 -1.25426e-06 0.945519 0.325568 0 0.945519 0.325568 9.12159e-06 0.945517 0.325572 -7.45975e-06 0.94552 0.325566 -6.29305e-06 0.94552 0.325563 -1.56213e-07 0.945518 0.325568 0 0.945518 0.325568 0 0.945518 0.325568 3.63434e-07 0.945518 0.325568 2.35352e-05 0.945518 0.325571 1.55139e-06 0.945519 0.325568 2.12217e-05 0.945517 0.325572 2.75031e-07 0.945518 0.325568 8.63309e-06 0.94552 0.325563 1.20199e-06 0.945518 0.325571 8.54824e-07 0.945517 0.325574 0 0.945519 0.325568 0 0.945519 0.325568 0 0.945519 0.325568 0 0.945519 0.325568 0 0.945519 0.325568 0 0.945519 0.325568 0 0.945519 0.325568 0 0.945519 0.325568 0 0.945519 0.325568 0 0.945519 0.325568 0 0.945519 0.325568 0 0.945519 0.325568 -2.77558e-06 0.94552 0.325563 7.02145e-07 0.945519 0.325566 0 0.945519 0.325566 0 0.945519 0.325566 0 0.945519 0.325566 0 0.945519 0.325566 0 0.945519 0.325566 0 0.945519 0.325566 0.258671 0.28242 -0.923758 0.482458 0.285174 -0.828197 0.678063 0.239296 -0.694959 0.705757 0.17133 -0.687425 0.845177 0.174008 -0.505368 0.948535 0.103096 -0.29942 0.962492 0.00430535 -0.271276 0.998177 0.0196511 -0.0570703 0.983619 -0.0586881 0.170441 0.960987 -0.179331 0.210582 0.903457 -0.139562 0.405326 0.707109 -0.230207 0.668582 0.762073 -0.371975 0.529981 0.584526 -0.264154 0.767172 0.258814 -0.314471 0.913304 0.36477 -0.496813 0.787477 0.120534 -0.323198 0.938624 -0.120538 -0.323197 0.938624 -0.257017 -0.4236 0.868623 -0.373364 -0.30202 0.877145 -0.584526 -0.264154 0.767172 -0.702647 -0.334803 0.627849 -0.774606 -0.2059 0.597989 -0.903436 -0.139576 0.405366 -0.960984 -0.179357 0.210572 -0.983623 -0.0586806 0.170419 -0.998177 0.0196511 -0.0570703 -0.962492 0.00430537 -0.271276 -0.948535 0.103096 -0.29942 -0.845177 0.174008 -0.505368 -0.705757 0.17133 -0.687425 -0.678063 0.239296 -0.694959 -0.482458 0.285174 -0.828197 -0.258675 0.282421 -0.923756 -0.239319 0.31611 -0.918042 0.239315 0.316111 -0.918043 -0.478221 -0.47928 -0.735931 -0.485359 -0.488981 -0.724793 -0.597888 -0.545228 -0.587585 -0.677158 -0.568392 -0.467319 -0.677527 -0.588079 -0.441724 -0.706461 -0.654059 -0.270405 -0.721315 -0.67813 -0.140871 -0.701247 -0.704873 -0.106803 -0.639861 -0.766354 0.0572706 -0.599399 -0.782598 0.168108 -0.551289 -0.810752 0.196879 -0.414366 -0.854146 0.314223 -0.338948 -0.857116 0.387901 -0.265332 -0.879864 0.394257 -0.0855439 -0.895498 0.436767 0 -0.884078 0.46734 0.0855409 -0.895498 0.436767 0.333416 -0.865478 0.373874 0.279487 -0.853041 0.44069 0.414366 -0.854146 0.314223 0.590451 -0.791344 0.158564 0.574728 -0.786689 0.225404 0.639872 -0.766347 0.0572384 0.712221 -0.686811 -0.145028 0.723514 -0.683716 -0.0951836 0.706461 -0.654059 -0.270405 0.670831 -0.575824 -0.467347 0.691805 -0.571681 -0.441119 0.597891 -0.545224 -0.587586 0.475761 -0.483816 -0.734556 0.490454 -0.479821 -0.72748 0.341176 -0.466845 -0.815877 0.171696 -0.43186 -0.885448 0.171692 -0.431861 -0.885448 -0.171696 -0.431861 -0.885447 -0.171695 -0.431861 -0.885447 -0.341175 -0.466847 -0.815876 0.258675 0.282421 -0.923756 0.482458 0.285174 -0.828197 0.678058 0.239297 -0.694963 0.705752 0.17133 -0.68743 0.845177 0.174008 -0.505368 0.948538 0.103093 -0.299411 0.962493 0.00431892 -0.271272 0.998175 0.0196625 -0.0571035 0.983619 -0.0586881 0.170441 0.960987 -0.179331 0.210582 0.903457 -0.139562 0.405326 0.707105 -0.230208 0.668586 0.762071 -0.371985 0.529976 0.584516 -0.264157 0.767178 0.258818 -0.31447 0.913303 0.36477 -0.496804 0.787482 0.120538 -0.323197 0.938624 -0.120536 -0.323197 0.938624 -0.257015 -0.423602 0.868622 -0.373364 -0.30202 0.877145 -0.584526 -0.264154 0.767172 -0.702647 -0.334803 0.627849 -0.774606 -0.2059 0.597989 -0.903446 -0.139569 0.405346 -0.960986 -0.179344 0.210577 -0.983621 -0.0586843 0.17043 -0.998177 0.0196511 -0.0570703 -0.962492 0.00430537 -0.271276 -0.948535 0.103096 -0.29942 -0.845201 0.173996 -0.505332 -0.705756 0.17132 -0.687428 -0.678058 0.239297 -0.694963 -0.482458 0.285174 -0.828197 -0.258673 0.282421 -0.923757 -0.239317 0.316111 -0.918042 0.239319 0.31611 -0.918042 -0.478222 -0.479279 -0.735932 -0.485358 -0.488976 -0.724797 -0.597908 -0.545232 -0.587561 -0.677157 -0.56839 -0.467324 -0.677525 -0.588081 -0.441724 -0.706459 -0.654061 -0.270406 -0.721314 -0.678131 -0.140871 -0.701241 -0.70488 -0.106797 -0.639865 -0.766352 0.0572534 -0.599398 -0.7826 0.168106 -0.551288 -0.810753 0.196877 -0.414365 -0.854147 0.314222 -0.338947 -0.857116 0.3879 -0.265332 -0.879864 0.394256 0 -0.892233 0.451576 -0.0910399 -0.863781 0.495574 0.0855439 -0.895498 0.436767 0.333416 -0.865479 0.373873 0.279487 -0.853042 0.440689 0.414359 -0.854147 0.314228 0.590451 -0.791344 0.158564 0.574728 -0.786689 0.225404 0.639872 -0.766347 0.0572384 0.712221 -0.686811 -0.145028 0.723514 -0.683716 -0.0951836 0.706457 -0.654054 -0.270429 0.670829 -0.575826 -0.467347 0.691809 -0.571682 -0.441113 0.597891 -0.545224 -0.587586 0.475761 -0.483816 -0.734556 0.490449 -0.479822 -0.727482 0.341175 -0.466846 -0.815877 0.171697 -0.43186 -0.885447 0.171695 -0.431861 -0.885447 -0.171696 -0.431861 -0.885447 -0.171694 -0.43186 -0.885448 -0.341175 -0.466846 -0.815877 0.258675 0.282421 -0.923756 0.482458 0.285174 -0.828197 0.678058 0.239297 -0.694963 0.705752 0.17133 -0.68743 0.845177 0.174008 -0.505368 0.948538 0.103093 -0.299411 0.962493 0.00431892 -0.271272 0.998175 0.0196625 -0.0571035 0.983619 -0.0586881 0.170441 0.960987 -0.179331 0.210582 0.903457 -0.139562 0.405326 0.707105 -0.230208 0.668586 0.762071 -0.371985 0.529976 0.584516 -0.264157 0.767178 0.258818 -0.31447 0.913303 0.36477 -0.496804 0.787482 0.120538 -0.323197 0.938624 -0.120536 -0.323197 0.938624 -0.257015 -0.423602 0.868622 -0.373364 -0.30202 0.877145 -0.584526 -0.264154 0.767172 -0.702647 -0.334803 0.627849 -0.774606 -0.2059 0.597989 -0.903446 -0.139569 0.405346 -0.960986 -0.179344 0.210577 -0.983621 -0.0586843 0.17043 -0.998177 0.0196511 -0.0570703 -0.962492 0.00430537 -0.271276 -0.948535 0.103096 -0.29942 -0.845201 0.173996 -0.505332 -0.705756 0.17132 -0.687428 -0.678058 0.239297 -0.694963 -0.482458 0.285174 -0.828197 -0.258673 0.282421 -0.923757 -0.239317 0.316111 -0.918042 0.239319 0.31611 -0.918042 -0.478222 -0.479279 -0.735932 -0.485358 -0.488976 -0.724797 -0.597908 -0.545232 -0.587561 -0.677158 -0.56839 -0.467321 -0.677527 -0.588079 -0.441724 -0.706461 -0.654059 -0.270405 -0.721315 -0.678129 -0.140874 -0.701241 -0.70488 -0.106797 -0.639865 -0.766352 0.0572534 -0.599397 -0.7826 0.168109 -0.551289 -0.810752 0.196879 -0.414366 -0.854146 0.314223 -0.338949 -0.857116 0.3879 -0.265332 -0.879864 0.394256 0 -0.892233 0.451576 -0.0910399 -0.863781 0.495574 0.0855439 -0.895498 0.436767 0.333416 -0.865479 0.373873 0.279487 -0.853042 0.440689 0.414359 -0.854147 0.314228 0.590451 -0.791344 0.158564 0.574728 -0.786689 0.225404 0.639872 -0.766347 0.0572384 0.712221 -0.686811 -0.145028 0.723514 -0.683716 -0.0951836 0.706457 -0.654054 -0.270429 0.67083 -0.575827 -0.467344 0.691807 -0.571684 -0.441113 0.597889 -0.545226 -0.587586 0.475759 -0.483817 -0.734558 0.490449 -0.479822 -0.727482 0.341175 -0.466846 -0.815877 0.171697 -0.43186 -0.885447 0.171695 -0.431861 -0.885447 -0.171696 -0.431861 -0.885447 -0.171694 -0.43186 -0.885448 -0.341175 -0.466846 -0.815877 0.258665 0.282417 -0.92376 0.482477 0.285171 -0.828187 0.678064 0.239296 -0.694959 0.705757 0.171332 -0.687425 0.845185 0.174009 -0.505354 0.948535 0.1031 -0.29942 0.962492 0.00430667 -0.271276 0.998177 0.0196508 -0.0570712 0.983619 -0.0586862 0.170441 0.960986 -0.17933 0.210584 0.90346 -0.139564 0.405318 0.707109 -0.230213 0.66858 0.762066 -0.371968 0.529995 0.584538 -0.264157 0.767161 0.258812 -0.314478 0.913302 0.364754 -0.496802 0.787491 0.120536 -0.323197 0.938624 -0.12054 -0.323197 0.938623 -0.257016 -0.423597 0.868624 -0.373353 -0.302029 0.877147 -0.584538 -0.264157 0.767161 -0.702648 -0.3348 0.62785 -0.774601 -0.205908 0.597993 -0.903439 -0.139578 0.405359 -0.960984 -0.179357 0.210574 -0.983623 -0.0586787 0.170419 -0.998177 0.0196508 -0.0570712 -0.962492 0.00430665 -0.271276 -0.948535 0.1031 -0.29942 -0.845185 0.174009 -0.505354 -0.705757 0.171332 -0.687425 -0.678064 0.239296 -0.694959 -0.482477 0.285171 -0.828187 -0.258669 0.282417 -0.923759 -0.239316 0.316102 -0.918046 0.239312 0.316102 -0.918046 -0.478221 -0.47928 -0.735932 -0.485359 -0.488982 -0.724792 -0.597854 -0.545213 -0.587634 -0.677161 -0.56839 -0.467319 -0.677529 -0.588085 -0.441713 -0.706461 -0.654059 -0.270408 -0.721315 -0.67813 -0.14087 -0.701246 -0.704874 -0.106802 -0.639877 -0.766343 0.0572347 -0.599402 -0.782595 0.168112 -0.551273 -0.810759 0.196893 -0.414395 -0.85414 0.3142 -0.33895 -0.857112 0.387906 -0.265306 -0.879869 0.394264 -0.0855448 -0.895498 0.436767 0 -0.884077 0.46734 0.0855418 -0.895498 0.436767 0.333416 -0.865478 0.373874 0.279466 -0.853035 0.440715 0.414395 -0.85414 0.3142 0.590451 -0.791344 0.158564 0.574722 -0.786687 0.22543 0.639887 -0.766337 0.0572025 0.71222 -0.686811 -0.145027 0.723514 -0.683716 -0.0951832 0.706461 -0.654059 -0.270408 0.67083 -0.575824 -0.467347 0.691814 -0.571679 -0.441108 0.597856 -0.545209 -0.587635 0.47576 -0.483817 -0.734556 0.490455 -0.479821 -0.727479 0.341195 -0.466848 -0.815867 0.171699 -0.43186 -0.885447 0.171689 -0.431864 -0.885447 -0.171698 -0.431863 -0.885446 -0.171693 -0.43186 -0.885448 -0.341194 -0.46685 -0.815867 0.258669 0.282417 -0.923759 0.482477 0.285171 -0.828187 0.678059 0.239297 -0.694963 0.705753 0.171331 -0.687429 0.845185 0.174009 -0.505354 0.948538 0.103097 -0.299411 0.962493 0.00432021 -0.271272 0.998175 0.0196622 -0.0571044 0.983619 -0.0586862 0.170441 0.960986 -0.17933 0.210584 0.90346 -0.139564 0.405318 0.707105 -0.230214 0.668584 0.762065 -0.371978 0.52999 0.584528 -0.26416 0.767168 0.258816 -0.314478 0.913301 0.364755 -0.496793 0.787497 0.12054 -0.323197 0.938623 -0.120538 -0.323197 0.938624 -0.257014 -0.423599 0.868624 -0.373353 -0.302029 0.877147 -0.584538 -0.264157 0.767161 -0.702648 -0.3348 0.62785 -0.774601 -0.205908 0.597993 -0.90345 -0.139571 0.405338 -0.960985 -0.179343 0.210579 -0.983621 -0.0586824 0.17043 -0.998177 0.0196508 -0.0570712 -0.962492 0.00430665 -0.271276 -0.948535 0.1031 -0.29942 -0.845209 0.173997 -0.505318 -0.705756 0.171322 -0.687428 -0.678059 0.239297 -0.694963 -0.482477 0.285171 -0.828187 -0.258667 0.282417 -0.92376 -0.239314 0.316102 -0.918046 0.239316 0.316102 -0.918046 -0.478222 -0.479279 -0.735932 -0.485358 -0.488977 -0.724796 -0.597874 -0.545217 -0.58761 -0.677159 -0.568387 -0.467325 -0.677527 -0.588087 -0.441713 -0.706459 -0.65406 -0.270409 -0.721314 -0.678131 -0.140871 -0.701241 -0.70488 -0.106797 -0.639881 -0.766341 0.0572175 -0.599401 -0.782597 0.16811 -0.551272 -0.81076 0.196892 -0.414395 -0.854141 0.314198 -0.33895 -0.857113 0.387905 -0.265305 -0.879869 0.394264 0 -0.892233 0.451576 -0.0910411 -0.863781 0.495575 0.0855448 -0.895498 0.436767 0.333416 -0.865478 0.373873 0.279466 -0.853036 0.440714 0.414389 -0.854141 0.314205 0.590451 -0.791344 0.158564 0.574722 -0.786687 0.22543 0.639887 -0.766337 0.0572025 0.71222 -0.686811 -0.145027 0.723514 -0.683716 -0.0951832 0.706456 -0.654053 -0.270433 0.670829 -0.575826 -0.467347 0.691818 -0.57168 -0.441101 0.597856 -0.545209 -0.587635 0.47576 -0.483817 -0.734556 0.49045 -0.479822 -0.727482 0.341194 -0.466848 -0.815867 0.1717 -0.431861 -0.885447 0.171692 -0.431864 -0.885447 -0.171698 -0.431863 -0.885446 -0.171691 -0.431859 -0.885449 -0.341194 -0.466848 -0.815867 0.258669 0.282417 -0.923759 0.482477 0.285171 -0.828187 0.678059 0.239297 -0.694963 0.705753 0.171331 -0.687429 0.845185 0.174009 -0.505354 0.948538 0.103097 -0.299411 0.962493 0.00432021 -0.271272 0.998175 0.0196622 -0.0571044 0.983619 -0.0586862 0.170441 0.960986 -0.17933 0.210584 0.90346 -0.139564 0.405318 0.707105 -0.230214 0.668584 0.762065 -0.371978 0.52999 0.584528 -0.26416 0.767168 0.258816 -0.314478 0.913301 0.364755 -0.496793 0.787497 0.12054 -0.323197 0.938623 -0.120538 -0.323197 0.938624 -0.257014 -0.423599 0.868624 -0.373353 -0.302029 0.877147 -0.584538 -0.264157 0.767161 -0.702648 -0.3348 0.62785 -0.774601 -0.205908 0.597993 -0.90345 -0.139571 0.405338 -0.960985 -0.179343 0.210579 -0.983621 -0.0586824 0.17043 -0.998177 0.0196508 -0.0570712 -0.962492 0.00430665 -0.271276 -0.948535 0.1031 -0.29942 -0.845209 0.173997 -0.505318 -0.705756 0.171322 -0.687428 -0.678059 0.239297 -0.694963 -0.482477 0.285171 -0.828187 -0.258667 0.282417 -0.92376 -0.239314 0.316102 -0.918046 0.239316 0.316102 -0.918046 -0.478222 -0.479279 -0.735932 -0.485358 -0.488977 -0.724796 -0.597874 -0.545217 -0.58761 -0.67716 -0.568387 -0.467322 -0.677529 -0.588085 -0.441713 -0.706461 -0.654059 -0.270408 -0.721315 -0.678129 -0.140874 -0.701241 -0.70488 -0.106797 -0.639881 -0.766341 0.0572175 -0.5994 -0.782597 0.168113 -0.551273 -0.810759 0.196893 -0.414395 -0.85414 0.3142 -0.338951 -0.857112 0.387905 -0.265305 -0.879869 0.394264 0 -0.892233 0.451576 -0.0910411 -0.863781 0.495575 0.0855448 -0.895498 0.436767 0.333416 -0.865478 0.373873 0.279466 -0.853036 0.440714 0.414389 -0.854141 0.314205 0.590451 -0.791344 0.158564 0.574722 -0.786687 0.22543 0.639887 -0.766337 0.0572025 0.71222 -0.686811 -0.145027 0.723514 -0.683716 -0.0951832 0.706456 -0.654053 -0.270433 0.670829 -0.575828 -0.467344 0.691816 -0.571682 -0.441101 0.597855 -0.545211 -0.587635 0.475758 -0.483818 -0.734558 0.49045 -0.479822 -0.727482 0.341194 -0.466848 -0.815867 0.1717 -0.431861 -0.885447 0.171692 -0.431864 -0.885447 -0.171698 -0.431863 -0.885446 -0.171691 -0.431859 -0.885449 -0.341194 -0.466848 -0.815867 0.564443 0.268742 -0.780501 0.295423 -0.311031 0.903319 0.156088 -0.383735 0.910156 0.428361 -0.29418 0.85438 0.450755 -0.400711 0.797653 0.564443 -0.26875 0.780499 0.676177 -0.239861 0.6966 0.698213 -0.3768 0.608705 0.783097 -0.202467 0.588019 0.863636 -0.164121 0.476652 0.875847 -0.318968 0.362148 0.931865 -0.118119 0.343039 0.974011 -0.0737422 0.214161 0.968461 -0.235594 0.0811073 0.997452 -0.0232252 0.0674503 0.987688 0.0509297 -0.147914 0.914654 -0.255778 -0.313026 0.997452 0.0232252 -0.0674502 0.707106 0.230207 -0.668585 0.660419 0.0313455 -0.750243 0.783098 0.202472 -0.588016 0.891008 0.147806 -0.429254 0.828811 -0.108289 -0.548949 0.931865 0.118116 -0.343041 0.423836 0.153999 -0.892551 0.453992 0.290086 -0.842462 0.295409 0.311041 -0.90332 0.156087 0.257964 -0.953463 0.142315 0.322248 -0.935897 -0.142315 0.322248 -0.935897 -0.156087 0.257964 -0.953463 -0.295409 0.311041 -0.90332 -0.428362 0.294188 -0.854377 -0.450755 0.175317 -0.875262 -0.564443 0.268742 -0.780501 -0.676176 0.239855 -0.696603 -0.698212 0.077825 -0.711648 -0.783098 0.202472 -0.588016 -0.863636 0.164125 -0.47665 -0.875847 -0.028387 -0.481753 -0.931865 0.118116 -0.343041 -0.974012 0.0737386 -0.214157 -0.968465 -0.1357 -0.208954 -0.997452 0.0232273 -0.0674561 -0.987688 -0.050931 0.147913 -0.914662 -0.394256 0.0891973 -0.997452 -0.0232273 0.0674562 -0.707106 -0.230214 0.668583 -0.660424 -0.437181 0.610503 -0.783097 -0.202467 0.588019 -0.891008 -0.147801 0.429256 -0.828807 -0.423311 0.365906 -0.931865 -0.118119 0.343039 0.142315 -0.322257 0.935894 -0.142314 -0.322257 0.935894 -0.156087 -0.383735 0.910156 -0.295423 -0.311031 0.903319 -0.453991 -0.290078 0.842465 -0.423835 -0.428155 0.798152 -0.564443 -0.26875 0.780499 0.615677 0.25655 -0.745066 0.325574 -0.307824 0.894005 0.173216 -0.386266 0.905977 0.469471 -0.287454 0.834846 0.496122 -0.397334 0.772003 0.61568 -0.256542 0.745067 0.731352 -0.222033 0.644845 0.755879 -0.360018 0.54684 0.838672 -0.177313 0.514965 0.913545 -0.132418 0.384579 0.923494 -0.284232 0.257627 0.970293 -0.0787663 0.228752 1 0 0 0.927961 -0.317479 -0.195181 0.996195 -0.0283754 0.0824073 0.766045 0.209273 -0.607767 0.71204 0.000324429 -0.702138 0.838673 0.177318 -0.514962 0.939691 0.111354 -0.323391 0.871961 -0.15563 -0.464179 0.970293 0.0787662 -0.228751 0.463834 0.137936 -0.875118 0.500002 0.281953 -0.818841 0.325567 0.307834 -0.894005 0.173217 0.253394 -0.951729 0.156434 0.321554 -0.93388 -0.156435 0.321554 -0.93388 -0.173218 0.253395 -0.951728 -0.325567 0.307834 -0.894005 -0.469471 0.287462 -0.834843 -0.496119 0.162198 -0.85297 -0.615661 0.256554 -0.745078 -0.731358 0.222038 -0.644837 -0.755881 0.0529848 -0.652562 -0.838663 0.177323 -0.514977 -0.913549 0.132419 -0.38457 -0.923498 -0.0653551 -0.377996 -0.970293 0.0787662 -0.228751 -0.996195 0.0283754 -0.0824073 -0.981332 -0.181845 -0.0626143 -0.996195 -0.0283754 0.0824073 -0.766044 -0.209267 0.607769 -0.712052 -0.431988 0.553506 -0.838662 -0.177318 0.51498 -0.939693 -0.111348 0.323386 -0.871964 -0.408414 0.269959 -0.970293 -0.0787663 0.228752 0.156433 -0.321563 0.933877 -0.156434 -0.321563 0.933877 -0.173218 -0.386265 0.905977 -0.325574 -0.307824 0.894005 -0.5 -0.281945 0.818845 -0.463835 -0.430067 0.774531 -0.615664 -0.256546 0.745079 0.615669 0.256552 -0.745072 0.325584 -0.307823 0.894002 0.173217 -0.386268 0.905976 0.469471 -0.287454 0.834846 0.496121 -0.397329 0.772006 0.615672 -0.256544 0.745073 0.731352 -0.222033 0.644845 0.755879 -0.360018 0.54684 0.838672 -0.177313 0.514965 0.913545 -0.132418 0.384579 0.923493 -0.284239 0.257621 0.970295 -0.0787638 0.228744 0.996195 -0.0283754 0.0824073 0.981332 -0.181845 -0.0626143 0.996195 0.0283754 -0.0824073 0.766045 0.209273 -0.607767 0.71204 0.000324429 -0.702138 0.838673 0.177318 -0.514962 0.939692 0.111353 -0.323388 0.871958 -0.155642 -0.464182 0.970295 0.0787636 -0.228744 0.463835 0.137942 -0.875117 0.500001 0.281953 -0.818842 0.325577 0.307833 -0.894001 0.173218 0.253392 -0.951729 0.156434 0.321554 -0.93388 -0.156434 0.321554 -0.93388 -0.173218 0.253392 -0.951729 -0.325577 0.307833 -0.894001 -0.469471 0.287462 -0.834843 -0.496119 0.162198 -0.85297 -0.615661 0.256554 -0.745078 -0.731355 0.222038 -0.64484 -0.75588 0.052974 -0.652564 -0.838668 0.17732 -0.51497 -0.913546 0.132421 -0.384575 -0.923495 -0.0653679 -0.377999 -0.970295 0.0787637 -0.228744 -1 0 0 -0.927961 -0.370343 -0.0416551 -0.996195 0.0283754 -0.0824073 -0.766044 -0.209267 0.607769 -0.712047 -0.432001 0.553501 -0.838667 -0.177315 0.514972 -0.939693 -0.111348 0.323386 -0.871956 -0.408433 0.269954 -0.970295 -0.0787638 0.228744 0.156433 -0.321563 0.933877 -0.156433 -0.321563 0.933877 -0.173217 -0.386268 0.905976 -0.325584 -0.307823 0.894002 -0.5 -0.281945 0.818845 -0.463835 -0.430067 0.774531 -0.615664 -0.256546 0.745079 -0.326394 -0.44865 -0.831973 -0.333586 -0.461047 -0.822287 -0.435469 -0.486912 -0.757155 -0.512368 -0.484812 -0.708827 -0.519078 -0.508488 -0.687021 -0.59343 -0.542653 -0.594448 -0.649007 -0.540167 -0.535734 -0.647748 -0.572858 -0.502251 -0.686933 -0.612005 -0.391884 -0.721311 -0.608713 -0.330424 -0.705759 -0.647204 -0.288154 -0.702715 -0.700663 -0.123546 -0.747663 -0.646141 -0.153303 -0.686938 -0.723529 -0.0679866 -0.633927 -0.769588 0.0766212 -0.676422 -0.733557 0.0659319 -0.593427 -0.793598 0.134336 -0.503084 -0.828221 0.246894 -0.534306 -0.807851 0.248785 -0.435475 -0.849842 0.296866 -0.322999 -0.870816 0.37061 -0.338445 -0.862505 0.376219 -0.230257 -0.886212 0.402007 -0.111303 -0.893208 0.435651 -0.111297 -0.893211 0.435646 0.111302 -0.89321 0.435646 0.111297 -0.893208 0.435652 0.230257 -0.886212 0.402007 0.326389 -0.865756 0.37939 0.333584 -0.869562 0.36412 0.435486 -0.849839 0.296858 0.512367 -0.818438 0.260076 0.519075 -0.823668 0.228324 0.593437 -0.793592 0.134328 0.649001 -0.755493 0.089602 0.647743 -0.760638 0.0431115 0.686938 -0.723529 -0.0679866 0.72131 -0.683101 -0.114384 0.705759 -0.687409 -0.17139 0.702715 -0.628192 -0.334016 0.747664 -0.603548 -0.276999 0.686933 -0.612005 -0.391884 0.633923 -0.559271 -0.534188 0.676429 -0.537454 -0.503574 0.59344 -0.542653 -0.594438 0.50309 -0.500637 -0.704459 0.5343 -0.483428 -0.693413 0.43548 -0.486914 -0.757147 0.323004 -0.458041 -0.828171 0.338446 -0.448041 -0.827474 0.230203 -0.450846 -0.862406 0.111296 -0.43565 -0.893209 0.1113 -0.435647 -0.89321 -0.111297 -0.435647 -0.89321 -0.1113 -0.43565 -0.893208 -0.230203 -0.450846 -0.862406 -0.298208 -0.445666 -0.84407 -0.304149 -0.456929 -0.835888 -0.399209 -0.478376 -0.782169 -0.473771 -0.474739 -0.74173 -0.479687 -0.496232 -0.72364 -0.553989 -0.525042 -0.646086 -0.612016 -0.520671 -0.595263 -0.61221 -0.550566 -0.567517 -0.659465 -0.584447 -0.472787 -0.700366 -0.579327 -0.416974 -0.689994 -0.615116 -0.381498 -0.706202 -0.651285 -0.277679 -0.730747 -0.645456 -0.222249 -0.706203 -0.684174 -0.18216 -0.681924 -0.730344 -0.0397071 -0.727132 -0.684148 -0.0567414 -0.659466 -0.751626 0.0127415 -0.597893 -0.790249 0.134276 -0.636784 -0.759742 0.13152 -0.553985 -0.811512 0.185874 -0.465416 -0.840026 0.278827 -0.49246 -0.822616 0.28423 -0.399196 -0.858519 0.32185 -0.295244 -0.875629 0.382237 -0.30817 -0.868379 0.388522 -0.208926 -0.888493 0.40857 -0.101147 -0.894184 0.436124 -0.101144 -0.894185 0.436122 0.101147 -0.894185 0.436122 0.101145 -0.894184 0.436125 0.208926 -0.888493 0.40857 0.298211 -0.870852 0.390752 0.304149 -0.874688 0.377378 0.399196 -0.858519 0.32185 0.473771 -0.830752 0.292218 0.47969 -0.836554 0.264716 0.553985 -0.811512 0.185874 0.612015 -0.776776 0.148514 0.612209 -0.783251 0.108254 0.659466 -0.751626 0.0127415 0.700367 -0.71323 -0.028087 0.689995 -0.719591 -0.0780747 0.710716 -0.665153 -0.229031 0.753957 -0.636592 -0.162169 0.706205 -0.651285 -0.277674 0.681926 -0.599964 -0.418353 0.727128 -0.574053 -0.376495 0.659465 -0.584447 -0.472787 0.597891 -0.540058 -0.592338 0.636791 -0.51771 -0.571379 0.553989 -0.525042 -0.646086 0.46542 -0.490284 -0.73689 0.49245 -0.473246 -0.730432 0.399209 -0.478376 -0.782169 0.332386 -0.463798 -0.821225 0.296803 -0.477935 -0.826732 0.240657 -0.448004 -0.861032 0.208873 -0.448599 -0.868983 0.101147 -0.436124 -0.894184 0.101146 -0.436125 -0.894184 -0.101147 -0.436125 -0.894184 -0.101146 -0.436124 -0.894184 -0.208873 -0.448599 -0.868983 -0.326393 -0.448651 -0.831974 -0.333586 -0.461049 -0.822286 -0.435468 -0.486913 -0.757155 -0.512369 -0.484813 -0.708826 -0.519077 -0.508485 -0.687024 -0.593435 -0.542653 -0.594443 -0.649007 -0.540167 -0.535734 -0.647748 -0.572855 -0.502254 -0.686936 -0.612005 -0.391879 -0.721309 -0.608713 -0.330426 -0.705757 -0.647205 -0.288154 -0.702713 -0.700665 -0.123545 -0.747663 -0.646141 -0.153303 -0.686941 -0.723526 -0.0679907 -0.633929 -0.769587 0.0766224 -0.676419 -0.733559 0.0659342 -0.593432 -0.793595 0.134332 -0.503085 -0.82822 0.246894 -0.534303 -0.807853 0.248785 -0.435474 -0.849843 0.296865 -0.322998 -0.870817 0.370609 -0.338445 -0.862505 0.376219 -0.230264 -0.886211 0.402005 -0.111304 -0.893207 0.435651 -0.111297 -0.893211 0.435646 0.111303 -0.89321 0.435646 0.111297 -0.893208 0.435653 0.230264 -0.886211 0.402005 0.326389 -0.865756 0.37939 0.333584 -0.869562 0.36412 0.435481 -0.849841 0.296862 0.512365 -0.818438 0.260079 0.519074 -0.823669 0.228323 0.593435 -0.793594 0.134327 0.649002 -0.755492 0.0895983 0.647744 -0.760637 0.0431126 0.686941 -0.723526 -0.0679907 0.72131 -0.683101 -0.114384 0.705759 -0.687409 -0.17139 0.702715 -0.628192 -0.334016 0.747664 -0.603548 -0.276999 0.686936 -0.612005 -0.391879 0.633926 -0.559271 -0.534185 0.676428 -0.537456 -0.503574 0.593439 -0.542655 -0.594438 0.503088 -0.500637 -0.704461 0.534301 -0.483426 -0.693413 0.435474 -0.486913 -0.757151 0.323004 -0.458041 -0.828171 0.338446 -0.448041 -0.827474 0.230211 -0.450846 -0.862404 0.111297 -0.435649 -0.893209 0.1113 -0.435647 -0.89321 -0.111297 -0.435647 -0.89321 -0.1113 -0.43565 -0.893209 -0.230211 -0.450846 -0.862404 0 -0.438375 -0.898792 0 -0.438375 -0.898792 0 -0.438375 -0.898792 0 -0.438375 -0.898792 0 -0.438375 -0.898792 0 -0.438375 -0.898792 0 -0.438375 -0.898792 -0.702704 -0.628202 -0.33402 -0.702714 -0.628193 -0.334015 -0.633927 -0.559269 -0.534186 -0.633933 -0.559264 -0.534185 -0.50309 -0.500633 -0.704462 -0.503088 -0.500636 -0.704462 -0.323004 -0.458039 -0.828172 -0.323002 -0.458042 -0.828171 -0.1113 -0.435647 -0.89321 -0.111298 -0.435651 -0.893208 0.1113 -0.435651 -0.893208 0.111299 -0.435647 -0.89321 0.323002 -0.458042 -0.828171 0.323002 -0.458038 -0.828173 0.50309 -0.500636 -0.70446 0.503091 -0.500633 -0.704462 0.633932 -0.559263 -0.534187 0.633928 -0.55927 -0.534184 0.702714 -0.628192 -0.334018 0.70271 -0.628197 -0.334017 -0.707097 -0.668591 -0.230214 -0.707097 -0.668592 -0.230215 -0.707099 -0.66859 -0.230214 -0.707097 -0.668592 -0.230215 -0.707097 -0.668591 -0.230215 0.707103 -0.668587 -0.230213 0.707103 -0.668586 -0.230213 0.707102 -0.668587 -0.230213 0.707104 -0.668585 -0.230212 0.707102 -0.668587 -0.230213 -0.0523007 -0.897565 0.437769 -0.194383 -0.768621 0.609457 -0.111301 -0.893208 0.435651 -0.323003 -0.870813 0.370612 -0.323002 -0.870819 0.370599 -0.503082 -0.828223 0.246891 -0.503084 -0.82822 0.246898 -0.633927 -0.769588 0.0766198 -0.633933 -0.769583 0.0766285 -0.702719 -0.70066 -0.12354 -0.702704 -0.700672 -0.123553 0.702709 -0.700669 -0.123545 0.70272 -0.700658 -0.123544 0.633934 -0.769582 0.0766256 0.633925 -0.769589 0.0766223 0.503086 -0.828219 0.246895 0.503081 -0.828223 0.246892 0.322998 -0.87082 0.370602 0.323006 -0.870813 0.370611 0.111301 -0.893208 0.435651 0.111299 -0.893211 0.435646 0 -0.898795 0.438369 0 -0.898795 0.438369 0 -0.898795 0.438369 0 -0.898795 0.438369 0 -0.898795 0.438369 0 -0.898795 0.438369 0 -0.898795 0.438369 0 -0.452237 -0.891898 0 -0.246493 -0.969145 0.0173264 -0.21619 -0.976198 0 -0.123085 -0.992396 0 0.0333778 -0.999443 0 0.0333778 -0.999443 0 0.28088 -0.959743 0 0.28088 -0.959743 0 0.510734 -0.859739 0 0.510734 -0.859739 0 0.708497 -0.705714 0 0.708497 -0.705714 0 0.804448 -0.594024 0.0132911 0.861666 -0.507301 0 0.872555 -0.488516 0 0.960841 -0.277102 0 0.960841 -0.277102 0 0.999566 -0.029443 0 0.999566 -0.029443 0 0.975486 0.220063 0 0.975486 0.220063 0 0.890111 0.455743 0 0.890111 0.455743 0 0.786233 0.61793 0.0231412 0.748608 0.662609 0 0.702586 0.711599 0 0.560455 0.828185 0 0.560455 0.828185 0 0.336886 0.941546 0 0.336886 0.941546 0 0.0921491 0.995745 0 0.0921491 0.995745 0 -0.158378 0.987379 0 -0.158378 0.987379 0 -0.398953 0.916971 0 -0.398953 0.916971 0 -0.591892 0.806018 0.0162263 -0.61438 0.788844 0 -0.688245 0.725479 0 -0.79136 0.611351 0 -0.79136 0.611351 0 -0.918534 0.395341 0 -0.918534 0.395341 0 -0.987994 0.154491 0 -0.987994 0.154491 0 -0.995375 -0.096067 0 -0.995375 -0.096067 0 -0.940212 -0.340589 0 -0.940212 -0.340589 0 -0.825973 -0.56371 0 -0.825973 -0.56371 0 -0.729754 -0.683709 0.0162263 -0.659747 -0.751312 0 -0.638309 -0.76978 0 -0.452237 -0.891898 0.851304 0.514734 0.101638 0.853125 0.405288 0.32851 0.854595 0.20387 0.477602 0.855727 -0.0427711 0.515657 0.856529 -0.278052 0.434793 0.851305 -0.507858 0.131759 0.857008 -0.448301 0.254092 0.853126 -0.385244 0.3518 0.854596 -0.175403 0.488774 0.855727 0.07305 0.512245 0.856529 0.303152 0.417681 0.857007 0.462481 0.227267 0 0.981058 0.193716 -0.00442577 0.973119 0.230262 0 0.89749 0.441034 0 0.776851 0.629684 -0.00739031 0.727599 0.685963 0 0.587391 0.809303 0 0.39259 0.919713 -0.00887578 0.287137 0.957848 0 0.141179 0.989984 0 -0.0826611 0.996578 -0.0088757 -0.230257 0.973089 0 -0.337771 0.941228 0 -0.538757 0.842461 -0.00738933 -0.68596 0.727602 0 -0.738433 0.674327 0 -0.869977 0.493093 -0.00442561 -0.957878 0.28714 0 -0.967954 0.251126 0 0.981057 0.193718 0 0.981057 0.193718 0 0.799853 0.600196 0 0.799853 0.600196 0 0.460221 0.887804 0 0.460221 0.887804 0 0.0294447 0.999566 0 0.0294447 0.999566 0 -0.407169 0.913353 0 -0.407169 0.913353 0 -0.763134 0.64624 0 -0.763134 0.64624 0 -0.967953 0.251132 0 -0.967953 0.251132 0.851304 0.514734 0.101638 0.851305 0.0154488 0.524444 0.851304 0.241465 0.465806 0.851304 0.419661 0.314906 0.851305 -0.507857 0.131762 0.851305 -0.400395 0.339064 0.851305 -0.21363 0.47921 0 0.973126 0.230271 0 0.973126 0.230271 0 0.727622 0.685979 0 0.727622 0.685979 0 0.287148 0.957886 0 0.287148 0.957886 0 -0.230265 0.973128 0 -0.230265 0.973128 0 -0.685982 0.727619 0 -0.685982 0.727619 0 -0.957888 0.287143 0 -0.957888 0.287143 0.849119 0.151672 0.505957 0.849119 0.384331 0.362335 0.849119 0.514006 0.12163 0.849119 -0.505958 0.151669 0.849119 -0.362336 0.384329 0.849119 -0.121626 0.514008 0 0.973129 0.230261 0 0.973129 0.230261 0 0.727621 0.685979 0 0.727621 0.685979 0 0.287147 0.957887 0 0.287147 0.957887 0 -0.230265 0.973128 0 -0.230265 0.973128 0 -0.685982 0.727618 0 -0.685982 0.727618 0 -0.957888 0.287143 0 -0.957888 0.287143 0.849119 0.151671 0.505957 0.849119 0.384331 0.362335 0.849119 0.514009 0.121624 0.849119 -0.505958 0.15167 0.849119 -0.362337 0.384329 0.849119 -0.121626 0.514008 0 0.981057 0.193717 0 0.981057 0.193717 0 0.799852 0.600198 0 0.799852 0.600198 0 0.460227 0.887801 0 0.460227 0.887801 0 0.029441 0.999567 0 0.029441 0.999567 0 -0.407166 0.913354 0 -0.407166 0.913354 0 -0.763134 0.64624 0 -0.763134 0.64624 0 -0.967956 0.251121 0 -0.967956 0.251121 0.851304 0.514734 0.101638 0.851305 0.0154469 0.524444 0.851305 0.241468 0.465804 0.851305 0.41966 0.314907 0.851305 -0.507859 0.131756 0.851305 -0.400394 0.339063 0.851305 -0.213628 0.479211 0 0.973129 0.230261 0 0.973129 0.230261 0 0.727619 0.685982 0 0.727619 0.685982 0 0.287148 0.957886 0 0.287148 0.957886 0 -0.230265 0.973128 0 -0.230265 0.973128 0 -0.685982 0.727619 0 -0.685982 0.727619 0 -0.957888 0.287143 0 -0.957888 0.287143 0.849119 0.151672 0.505957 0.849119 0.384329 0.362336 0.849119 0.514009 0.121624 0.849119 -0.505958 0.151669 0.849119 -0.362336 0.384329 0.849119 -0.121626 0.514008 0 0.981058 0.193716 0 0.981058 0.193716 0 0.799851 0.600199 0 0.799851 0.600199 0 0.460221 0.887804 0 0.460221 0.887804 0 0.0294447 0.999566 0 0.0294447 0.999566 0 -0.407169 0.913353 0 -0.407169 0.913353 0 -0.763134 0.64624 0 -0.763134 0.64624 0 -0.967952 0.251134 0 -0.967952 0.251134 0.851304 0.514734 0.101638 0.851305 0.0154488 0.524444 0.851304 0.241465 0.465806 0.851304 0.419659 0.314908 0.851305 -0.507856 0.131763 0.851305 -0.400395 0.339064 0.851305 -0.21363 0.47921 0 0.981057 0.193718 -0.00442574 0.973118 0.230264 0 0.89749 0.441034 0 0.776847 0.629689 -0.00738935 0.727602 0.68596 0 0.587414 0.809287 0 0.39259 0.919713 -0.00887621 0.287132 0.95785 0 0.141166 0.989986 0 -0.0826479 0.996579 -0.00887647 -0.230257 0.973089 0 -0.33778 0.941225 0 -0.538742 0.842471 -0.00738991 -0.68596 0.727602 0 -0.738436 0.674323 0 -0.869977 0.493093 -0.00442561 -0.957878 0.28714 0 -0.967954 0.251126 0.851305 0.514733 0.101638 0.853126 0.405286 0.328512 0.854596 0.20387 0.477601 0.855727 -0.0427642 0.515657 0.856529 -0.278044 0.434798 0.851304 -0.507859 0.131759 0.857008 -0.448302 0.254093 0.853125 -0.385247 0.351798 0.854596 -0.175407 0.488773 0.855727 0.0730432 0.512246 0.856529 0.303163 0.417672 0.857008 0.46248 0.227266 0 0.981057 0.193717 0.00442583 0.973118 0.230264 -0.00369741 0.799845 0.600196 0 0.77685 0.629686 0 0.587401 0.809296 -0.00592425 0.460216 0.887787 0 0.392592 0.919713 0 0.141174 0.989985 -0.00666794 0.0294423 0.999544 0 -0.0826578 0.996578 0 -0.337773 0.941227 -0.00592438 -0.40716 0.913337 0 -0.53875 0.842466 0 -0.763134 0.64624 -0.00442592 -0.738428 0.674318 0.00514738 -0.967941 0.251126 0 -0.957887 0.287146 0.849119 0.514008 0.121627 0.856529 0.303157 0.417677 0.855727 0.0730471 0.512246 0.854595 -0.175404 0.488774 0.849119 -0.505957 0.151671 0.853125 -0.385246 0.351799 0.856529 -0.278048 0.434796 0.855727 -0.0427694 0.515657 0.854595 0.203871 0.477602 0.853125 0.405287 0.328511 0 0.973128 0.230266 0 0.973128 0.230266 0 0.727621 0.685979 0 0.727621 0.685979 0 0.287147 0.957887 0 0.287147 0.957887 0 -0.230266 0.973128 0 -0.230266 0.973128 0 -0.685981 0.72762 0 -0.685981 0.72762 0 -0.957886 0.287149 0 -0.957886 0.287149 0.849119 0.151671 0.505957 0.849119 0.384331 0.362336 0.849119 0.514008 0.121627 0.849119 -0.505957 0.151672 0.849119 -0.362336 0.38433 0.849119 -0.121627 0.514008 -0.939849 0.33923 0.0400718 -0.939658 0.339425 0.0428315 -0.939687 0.33936 0.0427061 -0.939719 0.339269 0.0427152 -0.939762 0.339263 0.041807 -0.939691 0.33913 0.044404 -0.940705 0.336298 0.0444638 -0.940499 0.336871 0.0444904 -0.939716 0.339229 0.0431077 -0.940045 0.338962 0.0376923 -0.940593 0.337868 0.0336294 -0.940962 0.337 0.0319628 -0.939576 0.342293 0.0056591 -0.938802 0.344432 0.00409512 -0.93981 0.340971 0.0222708 -0.940119 0.339817 0.0264723 -0.940395 0.325223 0.099436 -0.940244 0.325638 0.0995032 -0.939696 0.327606 0.0982104 -0.939685 0.327681 0.0980637 -0.93974 0.327579 0.097883 -0.939782 0.327363 0.0982007 -0.939727 0.327363 0.0987253 -0.939824 0.327676 0.0967463 -0.939964 0.327683 0.0953545 -0.940224 0.327619 0.0929792 -0.940773 0.326771 0.0903669 -0.941064 0.326288 0.0890793 -0.942087 0.324358 0.0852251 -0.941622 0.325363 0.086522 -0.944164 0.322987 0.0650611 -0.939064 0.338359 0.0606049 -0.939771 0.332997 0.0770924 -0.940194 0.331024 0.0803619 -0.941649 0.331013 0.0610553 -0.940555 0.33467 0.0578932 -0.939668 0.337875 0.0535241 -0.940374 0.336407 0.0502605 -0.93967 0.337992 0.0527394 -0.939707 0.336789 0.0593562 -0.939773 0.336623 0.0592625 -0.939553 0.338264 0.053081 -0.941731 0.332368 0.0517076 -0.941633 0.332638 0.0517603 -0.939689 0.336888 0.0590848 -0.939795 0.336626 0.0588923 -0.939883 0.24173 0.241219 -0.939796 0.241075 0.242212 -0.940267 0.24318 0.238246 -0.941316 0.244021 0.233191 -0.942082 0.244032 0.230067 -0.941391 0.24684 0.229899 -0.940148 0.252635 0.228685 -0.937958 0.271082 0.216215 -0.943047 0.25544 0.213101 -0.940656 0.268272 0.207837 -0.939635 0.269355 0.211032 -0.939722 0.261961 0.219772 -0.93975 0.261918 0.2197 -0.939425 0.269619 0.211628 -0.943049 0.261941 0.205048 -0.942934 0.262194 0.205255 -0.939666 0.262238 0.219679 -0.93988 0.261974 0.219077 -0.939698 0.23461 0.248849 -0.946019 0.205785 0.250403 -0.939771 0.23441 0.24876 -0.940298 0.216047 0.26299 -0.942699 0.214906 0.255215 -0.927048 0.226761 0.298599 -0.941551 0.228059 0.247933 -0.93998 0.228107 0.25378 -0.939695 0.238235 0.245393 -0.939686 0.239959 0.243741 -0.944499 0.116819 0.307041 -0.932708 0.140928 0.331956 -0.941868 0.104744 0.319239 -0.941584 0.105557 0.319809 -0.940165 0.0995175 0.325861 -0.940932 0.13232 0.311671 -0.939576 0.132178 0.315793 -0.939731 0.116991 0.321276 -0.939737 0.116991 0.321259 -0.939276 0.132211 0.316672 -0.944295 0.127188 0.303528 -0.944183 0.127307 0.303827 -0.939659 0.117257 0.32139 -0.939874 0.11733 0.320735 -0.939698 0.078766 0.332813 -0.945386 0.0557646 0.321149 -0.939792 0.0784683 0.332617 -0.940221 0.0602409 0.335196 -0.939493 0.0587398 0.337494 -0.939105 0.0592245 0.338489 -0.945478 0.0557153 0.320884 -0.93973 0.0790349 0.332658 -0.939685 0.0789496 0.332804 -0.941267 0.079591 0.328148 -0.932885 0.0550551 0.355942 -0.943339 0.0643753 0.325528 -0.942118 0.063153 0.32928 -0.942239 0.0812134 0.324947 -0.942759 0.0820115 0.323232 -0.940603 0.0794261 0.330088 -0.939642 0.0925302 0.329409 -0.939751 0.0963828 0.327991 -0.931685 -0.0343002 0.361645 -0.941189 -0.0365907 0.335893 -0.939499 -0.0387659 0.340351 -0.939734 -0.0593184 0.336722 -0.939754 -0.059289 0.33667 -0.939105 -0.0391979 0.341389 -0.945483 -0.0367292 0.323594 -0.945381 -0.0367661 0.323887 -0.939673 -0.0591156 0.336928 -0.939848 -0.0587966 0.336495 -0.944291 -0.109105 0.310502 -0.944188 -0.109199 0.310782 -0.939697 -0.0982103 0.327604 -0.939683 -0.0980208 0.327701 -0.939726 -0.0978798 0.327621 -0.93977 -0.0982145 0.327394 -0.940123 -0.111128 0.32221 -0.94152 -0.106351 0.319732 -0.942444 -0.103816 0.31784 -0.942785 -0.102903 0.317124 -0.936863 -0.11747 0.329376 -0.940304 -0.0925988 0.327495 -0.940771 -0.0903806 0.326775 -0.941064 -0.0890794 0.326288 -0.942088 -0.0852253 0.324357 -0.941623 -0.0865218 0.325362 -0.940194 -0.0803596 0.331025 -0.939771 -0.0770871 0.332999 -0.939691 -0.0748407 0.333736 -0.939623 -0.0603353 0.336852 -0.943785 -0.0644484 0.324217 -0.941649 -0.0610549 0.331014 -0.946017 -0.190691 0.262084 -0.939671 -0.219669 0.26223 -0.939844 -0.219182 0.262017 -0.941427 -0.195505 0.274761 -0.939397 -0.200098 0.278377 -0.964079 -0.14006 0.225688 -0.939001 -0.202697 0.277833 -0.946113 -0.190525 0.261861 -0.93973 -0.219742 0.261957 -0.939751 -0.219689 0.261926 -0.943049 -0.249418 0.220112 -0.942938 -0.24965 0.220326 -0.939699 -0.248852 0.234603 -0.939685 -0.248737 0.234782 -0.939728 -0.248572 0.234783 -0.939781 -0.248783 0.234347 -0.940005 -0.254529 0.227167 -0.940915 -0.250379 0.228011 -0.941549 -0.247943 0.228059 -0.942469 -0.244451 0.228026 -0.938637 -0.256516 0.230566 -0.939796 -0.242207 0.241078 -0.939883 -0.241222 0.241728 -0.939928 -0.227303 0.254692 -0.939663 -0.225687 0.257095 -0.939761 -0.21315 0.267238 -0.942016 -0.21312 0.259201 -0.924376 -0.212433 0.316861 -0.940267 -0.238246 0.24318 -0.941316 -0.233191 0.244021 -0.942082 -0.230067 0.244032 -0.94139 -0.229899 0.246845 -0.940295 -0.228827 0.251961 -0.939902 -0.32156 0.114815 -0.940421 -0.321425 0.110877 -0.939699 -0.332813 0.0787485 -0.941625 -0.329035 0.071255 -0.939779 -0.332628 0.0785768 -0.939685 -0.332803 0.0789589 -0.939728 -0.332661 0.0790415 -0.941745 -0.328711 0.0711716 -0.939553 -0.334554 0.0729009 -0.939673 -0.334296 0.0725329 -0.93987 -0.333419 0.0740028 -0.940325 -0.331559 0.0765309 -0.94069 -0.330233 0.0777688 -0.940838 -0.329704 0.0782318 -0.941413 -0.327671 0.0798332 -0.939643 -0.329409 0.0925299 -0.940603 -0.330088 0.079426 -0.942759 -0.323234 0.0820107 -0.942239 -0.324945 0.0812143 -0.939751 -0.32799 0.096383 -0.940165 -0.325861 0.0995178 -0.941584 -0.319809 0.105557 -0.942158 -0.318655 0.10391 -0.94118 -0.320288 0.107682 -0.939688 -0.32071 0.118875 -0.939728 -0.321286 0.116993 -0.93975 -0.32122 0.116992 -0.939659 -0.320879 0.118646 -0.940386 -0.31883 0.118412 -0.940248 -0.319206 0.118496 -0.939672 -0.321352 0.117261 -0.939854 -0.320795 0.117323 -0.939598 -0.341422 0.024208 -0.938904 -0.343202 0.0259355 -0.940223 -0.336558 0.0520568 -0.942586 -0.330949 0.0447676 -0.940989 -0.334517 0.0513694 -0.940252 -0.335874 0.0558103 -0.940495 -0.333679 0.0642414 -0.939647 -0.336313 0.0628979 -0.939939 -0.335471 0.0630302 -0.939974 -0.336203 0.0584593 -0.93985 -0.336284 0.0599691 -0.939688 -0.336156 0.0631304 -0.940105 -0.334776 0.0642456 -0.940694 -0.333128 0.0641833 -0.939701 -0.33622 0.0626013 -0.939714 -0.336183 0.0626028 -0.939753 -0.321145 0.117178 -0.939691 -0.32069 0.118904 -0.939599 -0.315062 0.133756 -0.938046 -0.315987 0.142204 -0.940362 -0.30108 0.158338 -0.939671 -0.299288 0.165667 -0.939599 -0.288749 0.183789 -0.939163 -0.288615 0.18621 -0.939988 -0.271734 0.206358 -0.939625 -0.27125 0.208637 -0.939634 -0.256467 0.226522 -0.939425 -0.256695 0.227131 -0.94363 -0.199008 0.264497 -0.939371 -0.200794 0.277963 -0.939599 -0.166474 0.299067 -0.938156 -0.162324 0.305802 -0.940362 -0.140341 0.309878 -0.939667 -0.13489 0.314372 -0.939574 -0.11336 0.323033 -0.939276 -0.113342 0.323905 -0.942918 -0.0447585 0.330003 -0.939477 -0.0395748 0.340318 -0.939599 -0.00406921 0.342254 -0.941835 -0.0153195 0.335725 -0.934773 0.0251251 0.354357 -0.940342 0.0100177 0.340084 -0.939689 0.0356778 0.340163 -0.942123 0.123118 0.311844 -0.939562 0.131451 0.31614 -0.939599 0.159316 0.30294 -0.940951 0.151573 0.302716 -0.937335 0.187091 0.293938 -0.939486 0.178157 0.29262 -0.939391 0.216151 0.266127 -0.964079 0.153102 0.217053 -0.939001 0.218699 0.26542 -0.946108 0.205616 0.250202 -0.939726 0.234784 0.248579 -0.939685 0.234783 0.248737 -0.941325 0.261692 0.213131 -0.939625 0.26888 0.211679 -0.939599 0.284298 0.190602 -0.940026 0.282148 0.191688 -0.939068 0.300338 0.167181 -0.939569 0.298108 0.168352 -0.939599 0.311792 0.141209 -0.941047 0.305089 0.14612 -0.937104 0.328768 0.117253 -0.939476 0.320169 0.121971 -0.939691 0.327136 0.0998125 -0.939659 0.327307 0.099551 0 -0.992586 0.121547 0 -0.992586 0.121547 0 -0.953351 0.301864 0 -0.953351 0.301864 0 -0.881651 0.471902 0 -0.881651 0.471902 0 -0.779927 0.62587 0 -0.779927 0.62587 0 -0.651644 0.758525 0 -0.651644 0.758525 0 -0.50117 0.865349 0 -0.50117 0.865349 0 -0.33363 0.942704 0 -0.33363 0.942704 0 -0.154727 0.987957 0 -0.154727 0.987957 0 0.0294439 0.999566 0 0.0294439 0.999566 0 0.212612 0.977137 0 0.212612 0.977137 0 0.388541 0.921432 0 0.388541 0.921432 0 0.551238 0.834348 0 0.551238 0.834348 0 0.695163 0.718852 0 0.695163 0.718852 0 0.815415 0.578877 0 0.815415 0.578877 0 0.907899 0.419188 0 0.907899 0.419188 0 0.969466 0.245225 0 0.969466 0.245225 0 0.998019 0.0629101 0 0.998019 0.0629101 0 -0.992586 0.121547 0 -0.992586 0.121547 0 -0.953351 0.301864 0 -0.953351 0.301864 0 -0.881651 0.471902 0 -0.881651 0.471902 0 -0.779927 0.62587 0 -0.779927 0.62587 0 -0.651644 0.758525 0 -0.651644 0.758525 0 -0.50117 0.865349 0 -0.50117 0.865349 0 -0.33363 0.942704 0 -0.33363 0.942704 0 -0.154727 0.987957 0 -0.154727 0.987957 0 0.0294439 0.999566 0 0.0294439 0.999566 0 0.212612 0.977137 0 0.212612 0.977137 0 0.388541 0.921432 0 0.388541 0.921432 0 0.551238 0.834348 0 0.551238 0.834348 0 0.695163 0.718852 0 0.695163 0.718852 0 0.815415 0.578877 0 0.815415 0.578877 0 0.907899 0.419188 0 0.907899 0.419188 0 0.969466 0.245225 0 0.969466 0.245225 0 0.998019 0.0629101 0 0.998019 0.0629101 0 -0.991867 0.127277 0 -0.991867 0.127277 0 -0.947978 0.318335 0 -0.947978 0.318335 0 -0.867659 0.49716 0 -0.867659 0.49716 0 -0.753996 0.656879 0 -0.753996 0.656879 0 -0.611358 0.791354 0 -0.611358 0.791354 0 -0.445225 0.895419 0 -0.445225 0.895419 0 -0.261983 0.965073 0 -0.261983 0.965073 0 -0.0686725 0.997639 0 -0.0686725 0.997639 0 0.127277 0.991867 0 0.127277 0.991867 0 0.318335 0.947978 0 0.318335 0.947978 0 0.497159 0.867659 0 0.497159 0.867659 0 0.656879 0.753996 0 0.656879 0.753996 0 0.791354 0.611358 0 0.791354 0.611358 0 0.895419 0.445225 0 0.895419 0.445225 0 0.965073 0.261983 0 0.965073 0.261983 0 0.997639 0.0686725 0 0.997639 0.0686725 0 0.999929 0.0118898 -0.100445 0.990498 0.0939424 -0.0112198 0.998266 0.0577825 0 0.990148 0.140028 0 0.938766 0.344557 0 0.952201 0.305473 -0.0211933 0.972909 0.230215 -0.0844669 0.96296 0.256074 0 0.983514 0.180829 -0.0696553 0.908721 0.411552 -0.0299157 0.917948 0.395572 0 0.886823 0.46211 0 0.795894 0.605436 -0.0373882 0.835101 0.548825 -0.0560277 0.829301 0.555987 0 0.866969 0.498362 0 0.651232 0.758879 0 0.682037 0.731317 -0.0436109 0.726928 0.685327 -0.0436109 0.726928 0.685327 0 0.770196 0.637807 -0.0324139 0.60447 0.795968 -0.0485854 0.596741 0.800962 0 0.548531 0.83613 0 0.399219 0.916856 -0.0523161 0.448505 0.892248 -0.0224492 0.465341 0.884847 0 0.513507 0.858085 0 0.198066 0.980189 0 0.238407 0.971165 -0.0548011 0.286716 0.956447 -0.0137215 0.313403 0.949521 0 0.360985 0.932572 -0.00623806 0.152854 0.988229 -0.0560443 0.116267 0.991636 0 0.0707254 0.997496 0 -0.180828 0.983515 0 -0.140028 0.990148 -0.0112198 -0.0577824 0.998266 -0.100448 -0.0939439 0.990497 0 -0.0118883 0.999929 -0.0844677 -0.256074 0.96296 -0.0211927 -0.230215 0.972909 0 -0.305471 0.952201 0 -0.498362 0.866969 0 -0.46211 0.886823 -0.0299155 -0.395573 0.917947 -0.0696538 -0.411552 0.908721 0 -0.344558 0.938765 -0.056028 -0.555987 0.829301 -0.0373876 -0.548825 0.835101 0 -0.605435 0.795895 0 -0.731317 0.682037 -0.0436107 -0.685328 0.726928 -0.0436105 -0.685328 0.726928 0 -0.637808 0.770195 0 -0.858085 0.513508 0 -0.836131 0.548529 -0.0485868 -0.800962 0.596741 -0.032414 -0.795968 0.60447 0 -0.758878 0.651232 -0.0224497 -0.884847 0.465341 -0.0523162 -0.892248 0.448505 0 -0.916856 0.399219 0 -0.980188 0.19807 0 -0.971165 0.238407 -0.0548018 -0.956447 0.286716 -0.0137227 -0.949521 0.313403 0 -0.93257 0.360989 -0.0062387 -0.988229 0.152854 -0.0560442 -0.991636 0.116267 0 -0.997496 0.0707257 0 -0.993197 0.116449 0 -0.993197 0.116449 0 -0.957886 0.287148 0 -0.957886 0.287148 0 -0.893471 0.44912 0 -0.893471 0.44912 0 -0.801909 0.597447 0 -0.801909 0.597447 0 -0.68598 0.72762 0 -0.68598 0.72762 0 -0.549209 0.835685 0 -0.549209 0.835685 0 -0.39575 0.918358 0 -0.39575 0.918358 0 -0.230266 0.973128 0 -0.230266 0.973128 0 -0.0577863 0.998329 0 -0.0577863 0.998329 0 0.11645 0.993197 0 0.11645 0.993197 0 0.287147 0.957886 0 0.287147 0.957886 0 0.44912 0.893471 0 0.44912 0.893471 0 0.597447 0.801909 0 0.597447 0.801909 0 0.72762 0.68598 0 0.72762 0.68598 0 0.835685 0.549209 0 0.835685 0.549209 0 0.918358 0.39575 0 0.918358 0.39575 0 0.973128 0.230266 0 0.973128 0.230266 0 0.998329 0.0577862 0 0.998329 0.0577862 0 0.998019 0.0629099 0 0.998019 0.0629099 0 0.969466 0.245225 0 0.969466 0.245225 0 0.9079 0.419188 0 0.9079 0.419188 0 0.815415 0.578877 0 0.815415 0.578877 0 0.695163 0.718853 0 0.695163 0.718853 0 0.551238 0.834348 0 0.551238 0.834348 0 0.38854 0.921432 0 0.38854 0.921432 0 0.212612 0.977137 0 0.212612 0.977137 0 0.0294438 0.999566 0 0.0294438 0.999566 0 -0.154727 0.987957 0 -0.154727 0.987957 0 -0.333629 0.942704 0 -0.333629 0.942704 0 -0.50117 0.865349 0 -0.50117 0.865349 0 -0.651644 0.758525 0 -0.651644 0.758525 0 -0.779927 0.62587 0 -0.779927 0.62587 0 -0.881651 0.471902 0 -0.881651 0.471902 0 -0.953351 0.301864 0 -0.953351 0.301864 0 -0.992586 0.121546 0 -0.992586 0.121546 0 0.997639 0.0686726 0 0.997639 0.0686726 0 0.965073 0.261983 0 0.965073 0.261983 0 0.895418 0.445226 0 0.895418 0.445226 0 0.791354 0.611358 0 0.791354 0.611358 0 0.656879 0.753996 0 0.656879 0.753996 0 0.497159 0.867659 0 0.497159 0.867659 0 0.318335 0.947978 0 0.318335 0.947978 0 0.127277 0.991867 0 0.127277 0.991867 0 -0.0686726 0.997639 0 -0.0686726 0.997639 0 -0.261983 0.965073 0 -0.261983 0.965073 0 -0.445225 0.895419 0 -0.445225 0.895419 0 -0.611358 0.791354 0 -0.611358 0.791354 0 -0.753996 0.656879 0 -0.753996 0.656879 0 -0.867659 0.497159 0 -0.867659 0.497159 0 -0.947978 0.318335 0 -0.947978 0.318335 0 -0.991867 0.127277 0 -0.991867 0.127277 0 -0.991867 0.127277 0 -0.991867 0.127277 0 -0.947978 0.318335 0 -0.947978 0.318335 0 -0.867659 0.497159 0 -0.867659 0.497159 0 -0.753996 0.656879 0 -0.753996 0.656879 0 -0.611358 0.791354 0 -0.611358 0.791354 0 -0.445225 0.895419 0 -0.445225 0.895419 0 -0.261983 0.965073 0 -0.261983 0.965073 0 -0.0686726 0.997639 0 -0.0686726 0.997639 0 0.127277 0.991867 0 0.127277 0.991867 0 0.318335 0.947978 0 0.318335 0.947978 0 0.49716 0.867659 0 0.49716 0.867659 0 0.656879 0.753996 0 0.656879 0.753996 0 0.791354 0.611358 0 0.791354 0.611358 0 0.895419 0.445225 0 0.895419 0.445225 0 0.965073 0.261983 0 0.965073 0.261983 0 0.997639 0.0686726 0 0.997639 0.0686726 -0.202046 0.976923 -0.0692674 -0.202049 0.976923 -0.0692672 -0.202049 0.967866 -0.149702 -0.202026 0.967871 -0.149705 -0.20219 0.959942 -0.193988 -0.148194 0.960442 -0.235775 -0.202065 0.952195 -0.229116 -0.202064 0.930022 -0.306968 -0.20207 0.930021 -0.306967 -0.202227 0.913304 -0.353525 -0.0930116 0.912881 -0.39749 -0.202063 0.901497 -0.382719 -0.202062 0.866813 -0.455857 -0.202049 0.866815 -0.455859 -0.202197 0.840362 -0.5029 -0.0930743 0.839948 -0.534626 -0.202132 0.818872 -0.537207 -0.202041 0.779963 -0.592316 -0.202045 0.779962 -0.592315 -0.202178 0.743206 -0.637785 -0.0806851 0.741299 -0.666308 -0.202156 0.716219 -0.667955 -0.202042 0.671833 -0.712614 -0.202045 0.671833 -0.712613 -0.20216 0.624637 -0.754294 -0.0806894 0.621517 -0.779234 -0.202179 0.592932 -0.779458 -0.202046 0.545378 -0.813474 -0.202039 0.545378 -0.813476 -0.202131 0.488075 -0.849073 -0.0930741 0.484259 -0.86996 -0.202196 0.452563 -0.868506 -0.202049 0.404045 -0.892146 -0.202048 0.404045 -0.892146 -0.202114 0.337447 -0.919391 -0.117737 0.333584 -0.935339 -0.202205 0.299161 -0.932532 -0.202048 0.251692 -0.946482 -0.202057 0.251693 -0.94648 -0.202091 0.177097 -0.963222 -0.154299 0.174198 -0.972547 -0.202209 0.137142 -0.969693 -0.202045 0.0924741 -0.975001 -0.202043 0.0924739 -0.975001 -0.202043 0.0116431 -0.979308 -0.202046 0.0116434 -0.979307 -0.202046 -0.0692675 -0.976923 -0.20205 -0.0692671 -0.976923 -0.202052 -0.149704 -0.967866 -0.202043 -0.149705 -0.967867 -0.202206 -0.193981 -0.959939 -0.148205 -0.235774 -0.960441 -0.202049 -0.229118 -0.952198 -0.202049 -0.306968 -0.930025 -0.202044 -0.306969 -0.930026 -0.202201 -0.353534 -0.913306 -0.0930108 -0.397488 -0.912881 -0.202047 -0.38272 -0.9015 -0.202047 -0.455859 -0.866816 -0.202051 -0.455858 -0.866815 -0.202199 -0.502902 -0.84036 -0.0930838 -0.534626 -0.839947 -0.20214 -0.537206 -0.818871 -0.202048 -0.592314 -0.779962 -0.202045 -0.592315 -0.779962 -0.202178 -0.637785 -0.743206 -0.0806865 -0.666308 -0.741299 -0.202162 -0.667954 -0.716217 -0.202048 -0.712614 -0.671832 -0.202051 -0.712613 -0.671832 -0.202166 -0.754292 -0.624638 -0.0806879 -0.779234 -0.621518 -0.202179 -0.779458 -0.592932 -0.202046 -0.813475 -0.545377 -0.202047 -0.813474 -0.545377 -0.202139 -0.849072 -0.488074 -0.0930771 -0.86996 -0.484258 -0.202196 -0.868506 -0.452563 -0.202049 -0.892145 -0.404046 -0.202046 -0.892146 -0.404046 -0.202112 -0.919391 -0.337448 -0.117734 -0.93534 -0.333585 -0.202207 -0.932532 -0.299159 -0.850905 0.524005 -0.0371537 -0.850905 0.524004 -0.0371536 -0.850905 0.519146 -0.0802993 -0.850913 0.519133 -0.0802959 -0.850913 0.510729 -0.122891 -0.8509 0.510749 -0.122898 -0.8509 0.498856 -0.164654 -0.850904 0.49885 -0.164652 -0.850904 0.483549 -0.205285 -0.850905 0.483548 -0.205285 -0.850905 0.464944 -0.244515 -0.850912 0.464935 -0.244509 -0.850911 0.443156 -0.282068 -0.850909 0.443159 -0.28207 -0.850909 0.418352 -0.317703 -0.850909 0.418352 -0.317703 -0.850909 0.390688 -0.351165 -0.850908 0.390689 -0.351166 -0.850908 0.360356 -0.38223 -0.850906 0.360357 -0.382232 -0.850906 0.327562 -0.410684 -0.850907 0.327562 -0.410683 -0.850907 0.292529 -0.43633 -0.850906 0.292529 -0.436331 -0.850907 0.255498 -0.458997 -0.850907 0.255498 -0.458997 -0.850907 0.216721 -0.478528 -0.850909 0.216721 -0.478526 -0.850909 0.176464 -0.494788 -0.850911 0.176463 -0.494784 -0.850911 0.135001 -0.507667 -0.850906 0.135003 -0.507675 -0.850906 0.0926183 -0.51709 -0.850907 0.0926181 -0.517088 -0.850907 0.0496011 -0.52297 -0.850909 0.0496011 -0.522967 -0.850909 0.00624516 -0.525276 -0.850907 0.00624489 -0.525279 -0.850907 -0.0371535 -0.524001 -0.850907 -0.0371534 -0.524 -0.850907 -0.0802979 -0.519143 -0.850906 -0.0802985 -0.519145 -0.850905 -0.122895 -0.510741 -0.850908 -0.122894 -0.510738 -0.850908 -0.16465 -0.498845 -0.850907 -0.164651 -0.498846 -0.850907 -0.205283 -0.483546 -0.850908 -0.205283 -0.483544 -0.850908 -0.244512 -0.46494 -0.850908 -0.244512 -0.46494 -0.850908 -0.282071 -0.443161 -0.850908 -0.282072 -0.443161 -0.850908 -0.317704 -0.418354 -0.850907 -0.317705 -0.418355 -0.850907 -0.351167 -0.39069 -0.850909 -0.351165 -0.390688 -0.850909 -0.382229 -0.360355 -0.850908 -0.38223 -0.360356 -0.850908 -0.410682 -0.327561 -0.850909 -0.410681 -0.32756 -0.850908 -0.436329 -0.292528 -0.850908 -0.436329 -0.292528 -0.850908 -0.458996 -0.255497 -0.850907 -0.458997 -0.255498 -0.850907 -0.478528 -0.216721 -0.850907 -0.478527 -0.216721 -0.850908 -0.49479 -0.176464 -0.850907 -0.49479 -0.176464 -0.850907 -0.507672 -0.135002 -0.850908 -0.507671 -0.135002 -0.850908 -0.517085 -0.0926179 -0.850908 -0.517087 -0.092618 -0.573266 0.817318 -0.0579506 -0.573266 0.817318 -0.0579506 -0.573266 0.809741 -0.125246 -0.573258 0.809746 -0.125248 -0.573258 0.796638 -0.191686 -0.573258 0.796638 -0.191686 -0.573258 0.778087 -0.256819 -0.573265 0.778083 -0.256817 -0.573264 0.754217 -0.320194 -0.57326 0.75422 -0.320195 -0.57326 0.725202 -0.381385 -0.573258 0.725204 -0.381386 -0.573258 0.691233 -0.439969 -0.573263 0.69123 -0.439967 -0.573263 0.652537 -0.495546 -0.57326 0.652538 -0.495547 -0.573261 0.609387 -0.547741 -0.573264 0.609385 -0.547739 -0.573265 0.562072 -0.59619 -0.573261 0.562074 -0.596192 -0.573261 0.510921 -0.640572 -0.573263 0.51092 -0.64057 -0.573263 0.456277 -0.680574 -0.573266 0.456276 -0.680572 -0.573266 0.398517 -0.715927 -0.573261 0.398518 -0.71593 -0.573261 0.338035 -0.746394 -0.57326 0.338036 -0.746394 -0.57326 0.275244 -0.77176 -0.57326 0.275244 -0.77176 -0.57326 0.210573 -0.791853 -0.573262 0.210573 -0.791852 -0.573262 0.144463 -0.806536 -0.57326 0.144463 -0.806538 -0.57326 0.0773662 -0.815713 -0.573261 0.0773663 -0.815712 -0.573261 0.0097412 -0.819315 -0.573259 0.00974108 -0.819316 -0.57326 -0.0579509 -0.817322 -0.573259 -0.057951 -0.817322 -0.573258 -0.125247 -0.809746 -0.573264 -0.125246 -0.809742 -0.573265 -0.191686 -0.796633 -0.573258 -0.191688 -0.796638 -0.573258 -0.256819 -0.778087 -0.573265 -0.256816 -0.778082 -0.573266 -0.320193 -0.754217 -0.573258 -0.320196 -0.754222 -0.573257 -0.381385 -0.725204 -0.573257 -0.381385 -0.725204 -0.573258 -0.439969 -0.691233 -0.573261 -0.439968 -0.691231 -0.573261 -0.495547 -0.652538 -0.57326 -0.495547 -0.652538 -0.573261 -0.54774 -0.609387 -0.57326 -0.547741 -0.609387 -0.57326 -0.596192 -0.562074 -0.573259 -0.596193 -0.562074 -0.573259 -0.640572 -0.510921 -0.573259 -0.640573 -0.510921 -0.57326 -0.680576 -0.456278 -0.57326 -0.680576 -0.456278 -0.57326 -0.71593 -0.398518 -0.573261 -0.71593 -0.398518 -0.573261 -0.746394 -0.338036 -0.573262 -0.746393 -0.338035 -0.573262 -0.771759 -0.275244 -0.57326 -0.77176 -0.275244 -0.57326 -0.791853 -0.210573 -0.573259 -0.791854 -0.210573 -0.57326 -0.806538 -0.144463 -0.573262 -0.806537 -0.144463 -0.20205 -0.946481 -0.251692 -0.202049 -0.946481 -0.251692 -0.202084 -0.963223 -0.177098 -0.154294 -0.972547 -0.174198 -0.202211 -0.969693 -0.137137 -0.850907 -0.522969 -0.049601 -0.850908 -0.522969 -0.049601 -0.573261 -0.815712 -0.0773662 -0.573262 -0.815711 -0.0773663 -0.202049 -0.975 -0.092474 -0.202048 -0.975 -0.0924739 -0.850908 -0.525278 -0.00624517 -0.850907 -0.525279 -0.0062451 -0.57326 -0.819316 -0.00974094 -0.573261 -0.819315 -0.00974104 -0.202049 -0.979306 -0.0116432 -0.202049 -0.979306 -0.0116433 0 -0.997331 0.0730167 0.0535565 -0.994316 0.0920153 -0.0300356 -0.986727 0.159588 0 -0.983925 0.178585 0 -0.9695 0.245091 -0.0146267 -0.970666 0.239986 0.0163838 -0.944322 0.328614 0 -0.946157 0.323708 0 -0.912212 0.409719 -0.0826115 -0.920807 0.381168 0.137846 -0.864696 0.483011 -0.0490692 -0.890824 0.451691 0 -0.856381 0.516345 0 -0.827206 0.561899 0.0243767 -0.822026 0.568928 -0.0195028 -0.774938 0.631737 0 -0.769542 0.638596 0 -0.717066 0.697006 -0.0438465 -0.727226 0.684997 0.0595634 -0.652429 0.755506 0.0132598 -0.662728 0.748743 -0.00897268 -0.585114 0.810901 0.0582225 -0.562753 0.824572 -0.0304199 -0.511997 0.858448 0 -0.492618 0.870246 0 -0.435431 0.900222 -0.00487621 -0.436997 0.89945 0.00507184 -0.35531 0.934735 0 -0.356946 0.934125 0 -0.272495 0.962157 -0.0729424 -0.296794 0.952152 0.116176 -0.186329 0.975594 -0.0311789 -0.219956 0.975011 0 -0.151481 0.98846 0 -0.101278 0.994858 0.0341154 -0.0890643 0.995441 -0.0245738 -0.0141804 0.999597 0 -0.00196774 0.999998 0 0.0730168 0.997331 -0.0341148 0.0607917 0.997567 0.0436418 0.159509 0.986231 0 0.147589 0.989049 0 0.2094 0.97783 -0.0163848 0.245059 0.96937 0.0613274 0.276579 0.959032 -0.0292523 0.328516 0.944045 0 0.353268 0.935522 0 0.40972 0.912211 0.00487612 0.411306 0.911484 -0.00468195 0.48766 0.873021 0 0.489189 0.872178 0 0.561899 0.827206 -0.0632635 0.5419 0.838059 0.0958685 0.628946 0.771515 -0.0148175 0.611284 0.791273 0.0105316 0.696967 0.717026 0.0473421 0.704923 0.707702 -0.0280828 0.756551 0.653331 0 0.767023 0.64162 0 0.810934 0.585138 -0.0243766 0.805557 0.592017 0.0292414 0.858479 0.512015 0 0.999443 0.0333775 0.0769849 0.996932 0.0141424 -0.0535619 0.991306 0.120185 0 0.994858 0.101278 0 0.983214 0.182454 -0.0128737 0.982164 0.187584 0.0146283 0.963468 0.267424 0 0.962157 0.272494 0 0.944876 0.327429 -0.0265224 0.934418 0.35519 0.0628802 0.915157 0.398164 -0.0222339 0.899999 0.435324 0 0.88529 0.465039 0 0.854343 0.519709 0.19502 -0.00192996 0.980797 0.830974 0.510122 0.221942 0.96578 0.259218 0.00865693 0.980699 0.193054 0.0309663 0.9807 -0.194688 0.0180167 0.980699 -0.194692 0.018017 0.9807 0.179287 0.0780035 0.980699 0.17929 0.078005 0.980699 0.1681 0.099861 0.896499 -0.441161 0.0408255 0.830992 -0.553852 0.0519656 0.792828 -0.606853 0.0561592 0.554779 0.798504 0.233692 0.830974 0.533916 0.156257 0.830974 0.533916 0.156257 0.9807 0.187649 0.0549179 0.9807 0.187649 0.0549177 0.554755 -0.783379 0.280294 0.195129 -0.839919 0.50642 0.194771 -0.874817 0.443575 0.55477 -0.742063 0.376262 0.554768 -0.78337 0.280291 0.830984 -0.523778 0.187408 0.980698 -0.184098 0.0658702 0.980698 -0.17439 0.0884242 0.830976 -0.496171 0.251583 0.830976 -0.460726 0.311786 0.554779 -0.689048 0.466297 0.554783 -0.62517 0.548979 0.980699 -0.161929 0.109581 0.980699 -0.146918 0.129013 0.83097 -0.418023 0.367077 0.83097 -0.36872 0.416575 0.554795 -0.55143 0.622999 0.554791 -0.469001 0.687201 0.194711 -0.552921 0.810164 0.195042 -0.483157 0.853533 0.980701 -0.129583 0.146402 0.980701 -0.110213 0.161489 0.830981 -0.313592 0.459489 0.830981 -0.25353 0.49517 0.554769 -0.37918 0.740577 0.55477 -0.283371 0.78226 0.980699 -0.110218 0.161496 0.980699 -0.0891078 0.174036 0.830981 -0.25353 0.49517 0.83098 -0.189471 0.523043 0.554772 -0.283371 0.782259 0.554775 -0.183093 0.811605 0.194735 -0.21585 0.956811 0.195103 -0.14857 0.969465 0.9807 -0.0430266 0.190726 0.9807 -0.018783 0.194615 0.83098 -0.0534422 0.55373 0.83098 0.0163796 0.556061 0.55477 0.0244974 0.831643 0.554768 0.128537 0.822016 0.980699 -0.0187835 0.19462 0.980699 0.00575697 0.195441 0.830976 0.0163797 0.556067 0.830977 0.0859442 0.549628 0.554786 0.128535 0.822004 0.554788 0.230546 0.799412 0.194738 0.271796 0.942446 0.19508 0.346481 0.917548 0.9807 0.030206 0.193173 0.9807 0.054179 0.187865 0.830977 0.154153 0.534522 0.830978 0.21993 0.510985 0.554772 0.328925 0.764223 0.554773 0.422113 0.716971 0.980699 0.0772982 0.179595 0.980699 0.0991979 0.16849 0.830971 0.282245 0.479401 0.830971 0.340105 0.440246 0.554782 0.508641 0.658408 0.554784 0.58715 0.589465 0.19474 0.692203 0.694933 0.195036 0.752293 0.629298 0.980699 0.119533 0.154729 0.980699 0.137984 0.138528 0.830972 0.392598 0.394147 0.830972 0.438903 0.341834 0.554776 0.656404 0.511231 0.554778 0.715301 0.42493 0.9807 0.137981 0.138525 0.9807 0.154255 0.12014 0.830975 0.438899 0.34183 0.830974 0.478282 0.284127 0.554784 0.715298 0.424928 0.554783 0.762915 0.331927 0.194727 0.899418 0.391316 0.195079 0.926723 0.321138 0.607961 -0.790589 0.0731625 0.554731 -0.828425 0.0773747 0.441494 -0.893447 0.0826821 0.19484 -0.976662 0.0903831 0.19475 -0.97668 0.0903832 0.9807 -0.190895 0.0422761 0.830985 -0.543135 0.120284 0.830971 -0.543155 0.120288 0.554755 -0.812332 0.1799 0.554711 -0.81236 0.179906 0.75193 -0.643648 0.142543 0.195154 -0.965006 0.175151 0.194769 -0.874818 0.443576 0.195122 -0.906206 0.375124 0.662131 -0.705583 0.252458 0.194934 -0.928006 0.317498 0.195022 -0.95213 0.235403 0.980701 -0.19089 0.042275 0.980701 -0.184086 0.0658662 0.830977 -0.523788 0.187412 0.830977 -0.496169 0.251582 0.554755 -0.742071 0.376266 0.554757 -0.689061 0.466305 0.599479 -0.662872 0.448582 0.194748 -0.650096 0.734471 0.195047 -0.713945 0.672487 0.762148 -0.486466 0.427179 0.19495 -0.754777 0.626343 0.194807 -0.806517 0.558194 0.980701 -0.17438 0.0884192 0.980701 -0.161923 0.109578 0.830982 -0.460719 0.311781 0.83098 -0.418011 0.367067 0.554788 -0.625168 0.548977 0.554788 -0.551433 0.623002 0.194733 -0.650099 0.734473 0.194738 -0.552918 0.81016 0.9807 -0.146916 0.129011 0.9807 -0.129588 0.146407 0.830965 -0.368725 0.416581 0.830966 -0.313605 0.459507 0.554778 -0.469006 0.687208 0.554778 -0.379177 0.740571 0.733553 -0.309738 0.604949 0.194724 -0.215851 0.956813 0.195067 -0.29187 0.936355 0.704866 -0.241594 0.666931 0.19491 -0.3501 0.91621 0.19494 -0.428618 0.882205 0.980699 -0.0891088 0.174038 0.980699 -0.0665931 0.183834 0.830978 -0.189471 0.523044 0.830976 -0.122423 0.542671 0.554768 -0.183094 0.811609 0.55477 -0.0799285 0.828156 0.508113 -0.082742 0.857307 0.194818 -0.0874087 0.976937 0.9807 -0.0665908 0.183827 0.9807 -0.043026 0.190724 0.830973 -0.122424 0.542676 0.830972 -0.0534436 0.553741 0.554778 -0.0799278 0.82815 0.55478 0.0244974 0.831636 0.765443 0.0189473 0.643225 0.194727 0.271796 0.942448 0.195093 0.205376 0.959041 0.508106 0.133062 0.850954 0.194815 0.144761 0.970099 0.195012 0.0596593 0.978985 0.9807 0.00575689 0.195435 0.9807 0.0302059 0.193172 0.830975 0.0859446 0.549631 0.830975 0.154154 0.534526 0.554774 0.230548 0.799421 0.554774 0.328924 0.764221 0.704859 0.280434 0.65156 0.194744 0.599646 0.776208 0.195072 0.532556 0.823609 0.733555 0.344808 0.585666 0.19495 0.479803 0.855444 0.194923 0.403422 0.894011 0.9807 0.0541782 0.187861 0.9807 0.0772963 0.17959 0.830976 0.219931 0.510988 0.830976 0.282241 0.479394 0.554775 0.422113 0.71697 0.554777 0.508644 0.658411 0.194754 0.599645 0.776207 0.194753 0.692201 0.694931 0.9807 0.0991967 0.168488 0.9807 0.119532 0.154727 0.830973 0.340103 0.440244 0.830973 0.392598 0.394146 0.554784 0.58715 0.589466 0.554783 0.6564 0.511228 0.762144 0.51077 0.397806 0.194729 0.899418 0.391316 0.19509 0.86828 0.456103 0.599476 0.688129 0.408788 0.194858 0.837967 0.509747 0.195001 0.790327 0.580825 0.9807 0.154256 0.12014 0.9807 0.168097 0.099859 0.830975 0.478281 0.284126 0.830975 0.51012 0.221942 0.554784 0.762915 0.331927 0.554782 0.798502 0.233691 0.662132 0.719219 0.210488 0.194878 0.945097 0.262325 0.195047 0.973664 0.118046 0.9807 0.193052 0.030966 0.830975 0.549288 0.088107 0.830974 0.54929 0.0881074 0.554781 0.821496 0.13177 0.554779 0.821497 0.13177 0.75191 0.650945 0.104413 0.194962 0.964347 0.178953 0.980682 0.195544 0.00512307 0.792782 0.60913 0.0214025 0.830975 0.555999 0.0185683 0.607968 0.793519 0.0265005 0.554801 0.831496 0.0284762 0.258364 0.965544 0.031189 0.194733 0.98031 0.0327385 -0.793116 0.60901 0.00863952 -0.896679 -0.441501 0.0323221 -0.608353 -0.791548 0.057949 -0.194941 -0.978197 0.0716159 -0.441857 -0.894691 0.0655001 -0.258532 -0.963312 0.0720492 -0.258517 -0.953614 0.154237 -0.258655 -0.953578 0.154226 -0.258654 -0.936508 0.23675 -0.258628 -0.936515 0.236752 -0.258628 -0.912317 0.317474 -0.258569 -0.912331 0.317481 -0.25857 -0.881189 0.395787 -0.258602 -0.881182 0.395782 -0.258602 -0.843334 0.471077 -0.258585 -0.843337 0.47108 -0.258586 -0.799071 0.542788 -0.258601 -0.799068 0.542786 -0.258601 -0.74872 0.610364 -0.258606 -0.748719 0.610363 -0.258605 -0.692673 0.673296 -0.258607 -0.692673 0.673295 -0.258605 -0.631357 0.731104 -0.258595 -0.631358 0.731106 -0.258597 -0.565235 0.78335 -0.2586 -0.565234 0.78335 -0.258599 -0.49481 0.829632 -0.2586 -0.49481 0.829632 -0.258598 -0.42062 0.869601 -0.258595 -0.420621 0.869602 -0.258594 -0.343229 0.902952 -0.258605 -0.343228 0.90295 -0.258605 -0.263226 0.929428 -0.258592 -0.263226 0.929431 -0.258593 -0.181219 0.948836 -0.258582 -0.181219 0.948839 -0.258582 -0.097833 0.961022 -0.258598 -0.0978331 0.961018 -0.258597 -0.0137017 0.965888 -0.258611 -0.0137021 0.965884 -0.258611 0.0705319 0.963403 -0.258582 0.0705334 0.963411 -0.258581 0.154231 0.953598 -0.258587 0.154231 0.953596 -0.258586 0.236756 0.936525 -0.258603 0.236754 0.936521 -0.258603 0.317477 0.912323 -0.25859 0.317478 0.912326 -0.25859 0.395785 0.881184 -0.258607 0.395782 0.88118 -0.258607 0.471076 0.843332 -0.258599 0.471077 0.843334 -0.258599 0.542786 0.799068 -0.258601 0.542786 0.799068 -0.258601 0.610363 0.74872 -0.258589 0.610366 0.748723 -0.258589 0.673299 0.692676 -0.258591 0.673298 0.692676 -0.25859 0.731107 0.631358 -0.258586 0.731108 0.631359 -0.258588 0.783352 0.565236 -0.258596 0.78335 0.565235 -0.258597 0.829633 0.494811 -0.258595 0.829633 0.494811 -0.258593 0.869602 0.420621 -0.258605 0.869599 0.42062 -0.258605 0.90295 0.343228 -0.258599 0.902951 0.343229 -0.258599 0.929429 0.263225 -0.258599 0.929429 0.263225 -0.258599 0.948834 0.181219 -0.258598 0.948835 0.181219 -0.258598 0.961018 0.0978327 -0.258602 0.961017 0.0978327 -0.258602 0.965887 0.0137023 -0.258594 0.965889 0.013702 -0.60836 0.793581 0.0112579 -0.706816 0.707294 0.0120697 -0.706773 0.703803 0.0716479 -0.706772 0.703804 0.071648 -0.706772 0.694881 0.132716 -0.706772 0.694882 0.132716 -0.706772 0.68067 0.192774 -0.706774 0.680669 0.192773 -0.706773 0.661277 0.251364 -0.706769 0.661281 0.251365 -0.706769 0.636857 0.308043 -0.706772 0.636855 0.308042 -0.706772 0.607583 0.362376 -0.706772 0.607583 0.362376 -0.706772 0.573688 0.413951 -0.706772 0.573688 0.413951 -0.706772 0.535427 0.462376 -0.70678 0.535421 0.462371 -0.70678 0.493085 0.507276 -0.706781 0.493084 0.507275 -0.706781 0.446996 0.54832 -0.706767 0.447005 0.548331 -0.706767 0.397514 0.585204 -0.706776 0.397508 0.585197 -0.706775 0.344993 0.617615 -0.706769 0.344996 0.617621 -0.706769 0.289854 0.645339 -0.706772 0.289853 0.645336 -0.706773 0.232505 0.668142 -0.706774 0.232504 0.668141 -0.706774 0.173388 0.685862 -0.706783 0.173385 0.685854 -0.706783 0.112949 0.698355 -0.706775 0.112951 0.698363 -0.706776 0.0516541 0.705549 -0.706767 0.0516551 0.705558 -0.706767 -0.0100346 0.707375 -0.706773 -0.0100347 0.707369 -0.706774 -0.0716477 0.703802 -0.706779 -0.0716475 0.703797 -0.706779 -0.132714 0.694874 -0.706784 -0.132714 0.694869 -0.706785 -0.192771 0.680658 -0.706774 -0.192773 0.680668 -0.706773 -0.251364 0.661278 -0.706771 -0.251365 0.66128 -0.706769 -0.308044 0.636857 -0.706772 -0.308042 0.636854 -0.706772 -0.362376 0.607583 -0.706771 -0.362376 0.607584 -0.70677 -0.413952 0.57369 -0.706772 -0.413951 0.573688 -0.706772 -0.462376 0.535427 -0.706776 -0.462374 0.535423 -0.706776 -0.507279 0.493088 -0.706773 -0.507281 0.49309 -0.706772 -0.548327 0.447002 -0.706758 -0.548338 0.447011 -0.706757 -0.585212 0.397519 -0.706772 -0.585199 0.39751 -0.706772 -0.617618 0.344995 -0.706772 -0.617618 0.344995 -0.706772 -0.645336 0.289853 -0.706775 -0.645333 0.289852 -0.706775 -0.66814 0.232504 -0.706785 -0.66813 0.2325 -0.706786 -0.685851 0.173383 -0.70676 -0.685876 0.173391 -0.70676 -0.698378 0.112955 -0.706776 -0.698362 0.112952 -0.706819 -0.705354 0.0536801 -0.793129 -0.607428 0.0444695 -0.980737 -0.19481 0.0142621 -0.965863 -0.258246 0.0204373 -0.965847 -0.255787 0.0413699 -0.965842 -0.255806 0.0413735 -0.965843 -0.251226 0.063511 -0.965847 -0.25121 0.0635063 -0.965847 -0.244719 0.085159 -0.965848 -0.244717 0.0851581 -0.965848 -0.236364 0.106163 -0.965847 -0.236367 0.106164 -0.965847 -0.226215 0.126361 -0.965848 -0.226211 0.126359 -0.965848 -0.214337 0.145594 -0.965848 -0.214336 0.145593 -0.965848 -0.200831 0.16372 -0.965847 -0.200835 0.163723 -0.965847 -0.185801 0.180603 -0.965845 -0.185806 0.180608 -0.965845 -0.169357 0.196114 -0.965848 -0.169351 0.196106 -0.965848 -0.151615 0.21012 -0.965846 -0.151618 0.210126 -0.965846 -0.132728 0.222541 -0.965846 -0.132728 0.222541 -0.965846 -0.112827 0.233261 -0.965847 -0.112826 0.233259 -0.965847 -0.0920666 0.242205 -0.965847 -0.0920671 0.242206 -0.965847 -0.0706073 0.249309 -0.965846 -0.0706077 0.249311 -0.965846 -0.0486103 0.254516 -0.965846 -0.0486106 0.254518 -0.965846 -0.0262428 0.257785 -0.965846 -0.0262427 0.257783 -0.965846 -0.0036754 0.259089 -0.965847 -0.00367542 0.259088 -0.965847 0.0189195 0.258422 -0.965846 0.0189198 0.258425 -0.965846 0.0413709 0.255792 -0.965846 0.0413712 0.255794 -0.965846 0.0635074 0.251214 -0.965846 0.0635078 0.251215 -0.965846 0.085161 0.244724 -0.965847 0.0851598 0.244721 -0.965847 0.106165 0.236367 -0.965847 0.106164 0.236367 -0.965847 0.126361 0.226215 -0.965846 0.126362 0.226216 -0.965846 0.145597 0.214343 -0.965847 0.145596 0.21434 -0.965847 0.163722 0.200835 -0.965847 0.163722 0.200835 -0.965847 0.180603 0.185801 -0.965846 0.180605 0.185803 -0.965846 0.196111 0.169355 -0.965847 0.196111 0.169354 -0.965847 0.210125 0.151618 -0.965847 0.210124 0.151617 -0.965847 0.222538 0.132727 -0.965846 0.22254 0.132728 -0.965846 0.233261 0.112827 -0.965847 0.233261 0.112827 -0.965847 0.242207 0.0920674 -0.965846 0.242207 0.0920676 -0.965846 0.24931 0.0706075 -0.965846 0.24931 0.0706075 -0.965846 0.254515 0.04861 -0.965846 0.254515 0.0486099 -0.965846 0.257783 0.0262426 -0.965846 0.257783 0.0262426 -0.965846 0.259089 0.0036755 -0.965846 0.25909 0.00367549 0.705614 0.707193 0.0445779 0.705614 0.707193 0.0445779 0.705614 0.68696 0.173765 0.705614 0.68696 0.173765 0.705615 0.643333 0.297035 0.705614 0.643334 0.297035 0.705614 0.5778 0.41019 0.705615 0.5778 0.41019 0.705615 0.492589 0.509376 0.705613 0.49259 0.509377 0.705613 0.390605 0.591217 0.705612 0.390606 0.591218 0.705612 0.275319 0.652925 0.705618 0.275317 0.652919 0.705618 0.150656 0.692392 0.705615 0.150656 0.692395 0.705614 0.0208639 0.708289 0.705616 0.0208639 0.708287 0.705614 -0.109639 0.700063 0.705609 -0.10964 0.700068 0.70561 -0.23641 0.668 0.70562 -0.236407 0.667992 0.70562 -0.355124 0.613177 0.705618 -0.355126 0.61318 0.705617 -0.461751 0.537486 0.705622 -0.461748 0.537482 0.705622 -0.552647 0.443485 0.705614 -0.552654 0.443489 0.705615 -0.624734 0.334388 0.705608 -0.62474 0.334391 0.705608 -0.675547 0.213902 0.705604 -0.675551 0.213903 0.705603 -0.703353 0.0861291 0.705615 -0.703341 0.0861281 -0.705615 -0.703341 0.0861277 -0.705603 -0.703353 0.0861295 -0.705604 -0.675551 0.213903 -0.705608 -0.675547 0.213902 -0.705608 -0.62474 0.334391 -0.705615 -0.624734 0.334388 -0.705614 -0.552653 0.44349 -0.705622 -0.552648 0.443484 -0.705622 -0.461748 0.537482 -0.705617 -0.461751 0.537486 -0.705618 -0.355126 0.61318 -0.705621 -0.355124 0.613177 -0.70562 -0.236407 0.667992 -0.70561 -0.23641 0.668 -0.705609 -0.10964 0.700068 -0.705614 -0.109639 0.700063 -0.705616 0.0208638 0.708287 -0.705614 0.0208639 0.708289 -0.705615 0.150656 0.692395 -0.705618 0.150655 0.692392 -0.705618 0.275317 0.652919 -0.705612 0.275319 0.652925 -0.705612 0.390606 0.591218 -0.705613 0.390605 0.591217 -0.705613 0.49259 0.509377 -0.705615 0.492589 0.509376 -0.705615 0.5778 0.41019 -0.705614 0.5778 0.41019 -0.705614 0.643334 0.297035 -0.705615 0.643333 0.297035 -0.705615 0.68696 0.173765 -0.705614 0.68696 0.173765 -0.705614 0.707193 0.0445779 -0.705614 0.707193 0.0445779 0 -0.994858 -0.101281 0 -0.994858 -0.101281 0 -0.957886 0.287149 0 -0.957886 0.287149 0 -0.685982 0.727619 0 -0.685982 0.727619 0 -0.230263 0.973128 0 -0.230263 0.973128 0 0.287144 0.957887 0 0.287144 0.957887 0 0.727623 0.685977 0 0.727623 0.685977 0 0.973127 0.230268 0 0.973127 0.230268 0 -0.994858 -0.101275 0 -0.994858 -0.101275 0 -0.99806 -0.0622661 -0.0219602 -0.979162 -0.201888 -0.0173177 -0.778999 -0.626786 -0.00502862 -0.80966 -0.586878 0.00417803 -0.951553 -0.307456 -0.000587706 -0.235647 -0.971839 -0.0138214 -0.383191 -0.923566 -0.0176718 -0.398922 -0.916814 0.00250064 -0.561619 -0.827392 -0.00225522 -0.677849 -0.735198 0.00154672 -0.0117432 -0.99993 -0.0180515 0.0723591 -0.997215 9.7376e-05 0.23498 -0.972 -0.000134844 0.409579 -0.912275 -0.022135 0.527053 -0.849544 0.000127999 0.615653 -0.788017 -5.32263e-05 0.752874 -0.658164 -0.0178968 0.861316 -0.507754 0 0.888146 -0.459561 0 -0.993729 -0.111817 -0.0190916 -0.978643 -0.204677 -0.00602337 -0.954377 -0.298543 -0.00266441 -0.690027 -0.723779 -0.0195396 -0.793385 -0.608407 -0.0137666 -0.779125 -0.626718 3.04135e-05 -0.879197 -0.476459 -2.57657e-05 -0.922767 -0.385359 0.0049177 -0.509735 -0.860318 -0.0185591 -0.40965 -0.912054 0.000113855 -0.271337 -0.962484 -0.000123062 -0.0898623 -0.995954 -0.0205991 0.0490627 -0.998583 0.000124106 0.144867 -0.989451 -4.42943e-05 0.328378 -0.944546 -0.0160159 0.497102 -0.867545 0 0.539373 -0.842067 0 -1 0.000395379 -0.0052455 -0.991564 -0.129508 -0.0176945 -0.979987 -0.198272 -0.00601184 -0.959483 -0.281704 0.00773924 -0.871399 -0.490515 -0.0184399 -0.79122 -0.611254 0.000129098 -0.707037 -0.707177 -0.000104402 -0.565062 -0.825049 -0.0186158 -0.439271 -0.898161 0.0106296 -0.319403 -0.947559 -0.0138941 0.00327667 -0.999898 0 0.0460789 -0.998938 0 -0.997909 -0.0646285 -0.0162606 -0.982603 -0.185003 0.00013899 -0.960772 -0.277339 -7.27705e-05 -0.893452 -0.449158 -0.0152285 -0.813131 -0.581882 0.00884436 -0.75087 -0.660391 -0.0107833 -0.488779 -0.872341 0 -0.459556 -0.888149 0 -1 0.000460464 -0.00751501 -0.986077 -0.166122 0.00292939 -0.978607 -0.205716 -0.003279 -0.847462 -0.530847 0 -0.842061 -0.539383 0 -0.957886 0.287149 0 -0.957886 0.287149 0 -0.685981 0.727619 0 -0.685981 0.727619 0 -0.230267 0.973127 0 -0.230267 0.973127 0 0.287147 0.957886 0 0.287147 0.957886 0 0.727619 0.685982 0 0.727619 0.685982 0 0.973129 0.23026 0 0.973129 0.23026 0 -0.957886 0.287149 0 -0.957886 0.287149 0 -0.685984 0.727617 0 -0.685984 0.727617 0 -0.230267 0.973127 0 -0.230267 0.973127 0 0.28715 0.957886 0 0.28715 0.957886 0 0.727621 0.685979 0 0.727621 0.685979 0 0.973127 0.230268 0 0.973127 0.230268 0 -0.967951 0.25114 0 -0.967951 0.25114 0 -0.763137 0.646237 0 -0.763137 0.646237 0 -0.407164 0.913355 0 -0.407164 0.913355 0 0.0294439 0.999566 0 0.0294439 0.999566 0 0.460228 0.887801 0 0.460228 0.887801 0 0.799842 0.600211 0 0.799842 0.600211 0 0.981057 0.193718 0 0.981057 0.193718 0 -0.957891 0.287132 0 -0.957891 0.287132 0 -0.685978 0.727622 0 -0.685978 0.727622 0 -0.230265 0.973128 0 -0.230265 0.973128 0 0.28715 0.957886 0 0.28715 0.957886 0 0.727623 0.685977 0 0.727623 0.685977 0 0.973125 0.230276 0 0.973125 0.230276 0 -0.957886 0.287149 0 -0.957886 0.287149 0 -0.685979 0.727621 0 -0.685979 0.727621 0 -0.230263 0.973128 0 -0.230263 0.973128 0 0.287146 0.957887 0 0.287146 0.957887 0 0.727621 0.685979 0 0.727621 0.685979 0 0.973127 0.230268 0 0.973127 0.230268 0 -0.957886 0.287147 0 -0.957886 0.287147 0 -0.685984 0.727617 0 -0.685984 0.727617 0 -0.230267 0.973127 0 -0.230267 0.973127 0 0.287147 0.957886 0 0.287147 0.957886 0 0.727621 0.685979 0 0.727621 0.685979 0 0.973129 0.230259 0 0.973129 0.230259 0 -0.967953 0.251131 0 -0.967953 0.251131 0 -0.763137 0.646236 0 -0.763137 0.646236 0 -0.407161 0.913357 0 -0.407161 0.913357 0 0.0294438 0.999566 0 0.0294438 0.999566 0 0.46022 0.887805 0 0.46022 0.887805 0 0.799848 0.600203 0 0.799848 0.600203 0 0.981057 0.193717 0 0.981057 0.193717 0 -0.957887 0.287147 0 -0.957887 0.287147 0 -0.685978 0.727622 0 -0.685978 0.727622 0 -0.230268 0.973127 0 -0.230268 0.973127 0 0.287149 0.957886 0 0.287149 0.957886 0 0.72762 0.68598 0 0.72762 0.68598 0 0.973127 0.230268 0 0.973127 0.230268 0 -0.957887 0.287147 0 -0.957887 0.287147 0 -0.68598 0.72762 0 -0.68598 0.72762 0 -0.230265 0.973128 0 -0.230265 0.973128 0 0.287149 0.957886 0 0.287149 0.957886 0 0.72762 0.685981 0 0.72762 0.685981 0 0.973128 0.230267 0 0.973128 0.230267 0 -0.957886 0.287148 0 -0.957886 0.287148 0 -0.685981 0.72762 0 -0.685981 0.72762 0 -0.230265 0.973128 0 -0.230265 0.973128 0 0.287147 0.957887 0 0.287147 0.957887 0 0.72762 0.68598 0 0.72762 0.68598 0 0.973128 0.230266 0 0.973128 0.230266 0 -0.957886 0.287149 0 -0.957886 0.287149 0 -0.685982 0.727619 0 -0.685982 0.727619 0 -0.230263 0.973128 0 -0.230263 0.973128 0 0.287144 0.957887 0 0.287144 0.957887 0 0.727621 0.685979 0 0.727621 0.685979 0 0.973128 0.230266 0 0.973128 0.230266 6.65016e-07 -0.757958 -0.652303 -1.31268e-06 -0.595037 -0.803698 0.00257143 -0.545623 -0.838027 -0.00580636 -0.397788 -0.917459 0 -0.3412 -0.939991 0 -0.999282 -0.0378868 0.0102397 -0.978746 -0.204823 0.00906788 -0.980296 -0.197326 2.32111e-06 -0.933211 -0.359329 1.36523e-06 -0.885815 -0.464039 -0.00276216 -0.859389 -0.511315 0.00849655 -0.721762 -0.69209 0 -0.999973 0.00737195 -0.00295993 -0.990307 -0.138862 0.00516122 -0.980114 -0.198366 -0.00508197 -0.87931 -0.476222 -0.0128219 -0.846199 -0.532712 0 -0.760132 -0.649769 0 -0.991404 -0.130833 0 -0.991404 -0.130833 -0.000263166 -0.905735 -0.423845 0.00198867 -0.798939 -0.601409 0.00249272 -0.800748 -0.598996 -0.00317853 -0.488803 -0.872388 0.0137244 -0.556938 -0.830441 0 -0.349495 -0.936938 3.39281e-07 -0.910715 -0.413036 -2.26703e-06 -0.982734 -0.185026 1.44371e-07 -0.982731 -0.18504 0 -0.764283 -0.644881 0.0109788 -0.888019 -0.459675 -0.00531069 -0.848079 -0.529843 0.00402045 -0.986292 -0.164961 0 -0.9903 -0.138945 -0.70539 -0.703055 0.0902162 -0.70539 -0.703054 0.0902161 -0.705391 -0.671945 0.225642 -0.705393 -0.671943 0.225641 -0.705393 -0.615011 0.352395 -0.705395 -0.61501 0.352394 -0.705395 -0.534444 0.465605 -0.705392 -0.534446 0.465607 -0.705392 -0.433341 0.560926 -0.705393 -0.433341 0.560925 -0.705393 -0.315583 0.634688 -0.705385 -0.315587 0.634695 -0.705385 -0.1857 0.684066 -0.705392 -0.185698 0.684061 -0.705392 -0.0486764 0.707144 -0.705394 -0.0486762 0.707142 -0.705393 0.0902158 0.703052 -0.70539 0.090216 0.703054 -0.705391 0.225641 0.671944 -0.705395 0.22564 0.671941 -0.705397 0.352393 0.615008 -0.7054 0.352391 0.615005 -0.705401 0.465601 0.534439 -0.705383 0.465612 0.534452 -0.705382 0.560934 0.433348 -0.705391 0.560927 0.433342 -0.705391 0.634689 0.315584 -0.705392 0.634688 0.315584 -0.705393 0.68406 0.185698 -0.705398 0.684054 0.185696 -0.705398 0.707138 0.0486759 -0.705393 0.707143 0.0486765 -0.705615 -0.703341 0.0861277 -0.705603 -0.703353 0.0861295 -0.705604 -0.675551 0.213903 -0.705608 -0.675547 0.213902 -0.705608 -0.62474 0.334391 -0.705615 -0.624734 0.334388 -0.705614 -0.552653 0.44349 -0.705622 -0.552648 0.443484 -0.705622 -0.461748 0.537482 -0.705617 -0.461751 0.537486 -0.705618 -0.355126 0.61318 -0.705621 -0.355124 0.613177 -0.70562 -0.236407 0.667992 -0.70561 -0.23641 0.668 -0.705609 -0.10964 0.700068 -0.705614 -0.109639 0.700063 -0.705616 0.0208638 0.708287 -0.705614 0.0208639 0.708289 -0.705615 0.150656 0.692395 -0.705618 0.150655 0.692392 -0.705618 0.275317 0.652919 -0.705612 0.275319 0.652925 -0.705612 0.390606 0.591218 -0.705613 0.390605 0.591217 -0.705613 0.49259 0.509377 -0.705615 0.492589 0.509376 -0.705615 0.5778 0.41019 -0.705614 0.5778 0.41019 -0.705614 0.643334 0.297035 -0.705615 0.643333 0.297035 -0.705615 0.68696 0.173765 -0.705614 0.68696 0.173765 -0.705614 0.707193 0.0445779 -0.705614 0.707193 0.0445779 -0.705779 -0.703612 0.0824962 -0.705764 -0.703627 0.0824985 -0.705765 -0.678611 0.203429 -0.705785 -0.678592 0.203422 -0.705785 -0.632959 0.318169 -0.705778 -0.632965 0.318172 -0.705777 -0.568099 0.423251 -0.705772 -0.568103 0.423254 -0.705773 -0.485975 0.515474 -0.70578 -0.48597 0.515468 -0.70578 -0.389077 0.592025 -0.705777 -0.389078 0.592028 -0.705778 -0.280362 0.650595 -0.705781 -0.280361 0.650593 -0.705779 -0.163128 0.689395 -0.705778 -0.163128 0.689396 -0.705778 -0.0409378 0.707249 -0.705779 -0.0409377 0.707248 -0.705779 0.0824968 0.703613 -0.705778 0.0824969 0.703613 -0.705779 0.203424 0.678598 -0.70578 0.203424 0.678597 -0.70578 0.318171 0.632963 -0.705779 0.318171 0.632964 -0.705779 0.42325 0.568098 -0.705772 0.423254 0.568103 -0.705773 0.515474 0.485975 -0.70578 0.515468 0.48597 -0.70578 0.592025 0.389077 -0.705779 0.592027 0.389077 -0.705779 0.650594 0.280362 -0.705777 0.650597 0.280363 -0.705777 0.689397 0.163128 -0.705778 0.689396 0.163128 -0.705778 0.70725 0.0409376 -0.705779 0.707248 0.0409376 -0.705778 -0.703614 0.0824969 -0.705778 -0.703614 0.0824969 -0.705777 -0.678599 0.203425 -0.705777 -0.678599 0.203425 -0.705777 -0.632965 0.318172 -0.705777 -0.632966 0.318172 -0.705777 -0.5681 0.423252 -0.705782 -0.568096 0.423249 -0.705782 -0.485968 0.515467 -0.705781 -0.485969 0.515468 -0.70578 -0.389076 0.592025 -0.705775 -0.389079 0.59203 -0.705774 -0.280364 0.650599 -0.705775 -0.280363 0.650598 -0.705776 -0.163129 0.689398 -0.705778 -0.163128 0.689396 -0.705778 -0.0409376 0.70725 -0.705779 -0.0409375 0.707249 -0.70578 0.0824965 0.703611 -0.705778 0.0824966 0.703613 -0.705779 0.203424 0.678598 -0.70578 0.203424 0.678597 -0.70578 0.318171 0.632963 -0.705782 0.31817 0.632961 -0.705783 0.423248 0.568094 -0.705782 0.423249 0.568096 -0.705782 0.515467 0.485968 -0.705776 0.515472 0.485972 -0.705774 0.59203 0.38908 -0.705775 0.59203 0.38908 -0.705774 0.650599 0.280363 -0.705778 0.650596 0.280362 -0.705778 0.689396 0.163129 -0.705784 0.68939 0.163127 -0.705784 0.707243 0.0409372 -0.705779 0.707248 0.0409377 0.705393 0.707143 0.0486762 0.705392 0.707144 0.0486764 0.705392 0.68406 0.185698 0.705393 0.68406 0.185698 0.705392 0.634688 0.315583 0.705391 0.634689 0.315584 0.705391 0.560926 0.433342 0.705396 0.560923 0.433339 0.705397 0.465604 0.534442 0.705388 0.46561 0.534449 0.705387 0.352398 0.615016 0.705393 0.352395 0.615011 0.705393 0.225641 0.671943 0.705391 0.225641 0.671945 0.705391 0.0902161 0.703054 0.705393 0.0902159 0.703052 0.705394 -0.0486761 0.707142 0.705391 -0.0486764 0.707145 0.70539 -0.185698 0.684062 0.705387 -0.185699 0.684065 0.705388 -0.315585 0.634692 0.705393 -0.315583 0.634688 0.705393 -0.43334 0.560925 0.705392 -0.433341 0.560926 0.705392 -0.534446 0.465607 0.705393 -0.534445 0.465607 0.705393 -0.615011 0.352395 0.705392 -0.615012 0.352396 0.705392 -0.671944 0.225641 0.705391 -0.671945 0.225642 0.70539 -0.703054 0.0902161 0.705393 -0.703051 0.0902158 -0.70542 -0.703025 0.0902124 -0.705417 -0.703028 0.0902129 -0.705417 -0.67192 0.225634 -0.705418 -0.671919 0.225633 -0.705418 -0.614989 0.352383 -0.70542 -0.614988 0.352382 -0.705419 -0.534426 0.465589 -0.705418 -0.534426 0.46559 -0.705418 -0.433325 0.560905 -0.70542 -0.433324 0.560904 -0.705419 -0.315571 0.634664 -0.705414 -0.315573 0.634669 -0.705414 -0.185692 0.68404 -0.705417 -0.185692 0.684037 -0.705418 -0.0486745 0.707119 -0.70542 -0.0486744 0.707116 -0.705419 0.0902125 0.703026 -0.705417 0.0902128 0.703028 -0.705417 0.225633 0.67192 -0.705419 0.225632 0.671918 -0.70542 0.352381 0.614988 -0.705414 0.352385 0.614993 -0.705414 0.465593 0.534429 -0.705423 0.465587 0.534423 -0.705423 0.560902 0.433323 -0.705418 0.560906 0.433325 -0.705418 0.634665 0.315572 -0.705419 0.634665 0.315572 -0.705419 0.684034 0.185691 -0.705418 0.684035 0.185691 -0.705418 0.707118 0.0486745 -0.70542 0.707116 0.0486744 -0.705393 -0.703051 0.0902158 -0.70539 -0.703054 0.0902164 -0.70539 -0.671945 0.225642 -0.705388 -0.671947 0.225643 -0.705388 -0.615015 0.352397 -0.70539 -0.615013 0.352396 -0.705391 -0.534447 0.465608 -0.705392 -0.534446 0.465607 -0.705392 -0.433341 0.560926 -0.705388 -0.433343 0.560929 -0.705389 -0.315585 0.634691 -0.70539 -0.315585 0.63469 -0.705391 -0.185698 0.684061 -0.705389 -0.185699 0.684063 -0.705389 -0.0486765 0.707147 -0.705389 -0.0486765 0.707147 -0.705389 0.0902163 0.703055 -0.705391 0.0902161 0.703054 -0.705391 0.225641 0.671944 -0.705388 0.225643 0.671947 -0.705388 0.352397 0.615015 -0.705392 0.352396 0.615012 -0.705392 0.465607 0.534446 -0.705392 0.465607 0.534446 -0.705392 0.560926 0.433341 -0.705392 0.560926 0.433341 -0.705392 0.634688 0.315583 -0.705393 0.634688 0.315583 -0.705393 0.684059 0.185698 -0.705392 0.68406 0.185698 -0.705392 0.707144 0.0486764 -0.705391 0.707145 0.0486764 -0.705604 -0.703352 0.0861286 -0.705606 -0.703351 0.0861285 -0.705606 -0.675549 0.213902 -0.705606 -0.675549 0.213902 -0.705606 -0.624742 0.334392 -0.705605 -0.624743 0.334392 -0.705605 -0.552661 0.443495 -0.705607 -0.552659 0.443494 -0.705607 -0.461757 0.537493 -0.705605 -0.461759 0.537495 -0.705605 -0.355132 0.613191 -0.705608 -0.355131 0.613188 -0.705607 -0.236411 0.668003 -0.705606 -0.236411 0.668004 -0.705606 -0.10964 0.70007 -0.705605 -0.109641 0.700072 -0.705605 0.0208641 0.708298 -0.705603 0.020864 0.7083 -0.705603 0.150659 0.692407 -0.705604 0.150658 0.692405 -0.705603 0.275322 0.652933 -0.705608 0.275321 0.652928 -0.705609 0.390608 0.59122 -0.705601 0.390612 0.591227 -0.7056 0.492599 0.509386 -0.705606 0.492596 0.509382 -0.705605 0.577807 0.410195 -0.70561 0.577804 0.410192 -0.70561 0.643338 0.297036 -0.705603 0.643344 0.29704 -0.705603 0.686971 0.173768 -0.705611 0.686964 0.173766 -0.705611 0.707196 0.0445779 -0.705607 0.7072 0.0445784 0 0.997155 -0.0753784 -1.33331e-08 0.997155 -0.0753787 0 0.531913 -0.846799 -0.00906334 0.631881 -0.775013 0 0.985018 -0.172454 0.00119446 0.983518 -0.180804 -0.000909828 0.90682 -0.421518 4.98122e-05 0.903087 -0.429458 -3.09461e-05 0.810968 -0.585091 -0.00245008 0.829802 -0.558053 0.00422415 0.704514 -0.709677 0 -0.999863 -0.0165289 0 -0.999863 -0.0165289 0 -0.998818 -0.0486098 0 -0.998818 -0.0486098 0 -0.665846 -0.746089 -0.00106934 -0.674256 -0.738497 0.000458618 -0.836259 -0.548334 -0.00379715 -0.889025 -0.457842 0.00851648 -0.973092 -0.230258 0 -0.99036 -0.13852 0.701602 -0.474461 -0.53164 0.729384 -0.497768 -0.469282 0.705784 -0.592429 -0.388455 0.69474 -0.699932 -0.165621 0.694741 -0.699932 -0.165621 0.69474 -0.523349 -0.493399 0.703419 -0.706127 -0.0811587 0.558632 -0.807127 -0.190987 0.704633 -0.659941 -0.260711 0.694741 -0.523348 -0.493398 0.706727 -0.70739 -0.011694 0.706727 -0.70739 -0.011694 0.706727 -0.70739 -0.0116934 0.706727 -0.70739 -0.0116936 0.706021 -0.707353 -0.034425 0.706021 -0.707354 -0.0344242 -0.42225 0.903902 -0.0683068 -0.422255 0.9039 -0.0683076 0.504735 -0.863156 -0.014269 0.504734 -0.863157 -0.0142689 -0.706041 0.704084 -0.0759682 -0.706039 0.704087 -0.0759589 -0.706745 0.705455 -0.0533278 -0.706754 0.705449 -0.0533076 -0.706746 0.705456 -0.0533105 -0.706754 0.705448 -0.0533107 -0.701687 0.697715 -0.144326 -0.734371 0.668578 -0.117057 -0.653831 0.643851 -0.397444 -0.719557 0.607056 -0.337226 -0.680587 0.45422 -0.574879 -0.700673 0.450852 -0.552983 -0.694763 0.493385 -0.523331 -0.658246 0.481917 -0.578332 -0.723181 0.632054 -0.278418 -0.700513 0.634651 -0.326343 -0.704167 0.701724 -0.108316 -0.704453 0.701568 -0.107462 0 -0.998818 -0.0486098 0 -0.998818 -0.0486098 -0.00111294 -0.914682 -0.404173 0.000519219 -0.767624 -0.6409 -0.00596493 -0.68426 -0.729214 0 -0.616943 -0.787007 0 -0.997901 -0.0647659 -0.00190544 -0.995674 -0.0928995 0.00124296 -0.969226 -0.246168 -0.00849846 -0.886978 -0.461733 0 -0.999863 -0.0165289 0 -0.999863 -0.0165289 -2.74893e-09 0.998424 -0.0561148 0.00158907 0.99403 -0.109095 0.00723067 0.979243 -0.202562 -0.00261656 0.962 -0.273038 0.00252241 0.870877 -0.491495 0.00794276 0.850906 -0.525257 -0.00183721 0.766696 -0.642007 0.00476343 0.619947 -0.78463 0 0.59902 -0.800734 0 0.998612 -0.0526739 0.000591448 0.997155 -0.0753784 0 0.995123 -0.0986377 0 -0.967953 0.251131 0 -0.967953 0.251131 0 -0.763136 0.646238 0 -0.763136 0.646238 0 -0.407168 0.913353 0 -0.407168 0.913353 0 0.0294446 0.999566 0 0.0294446 0.999566 0 0.460225 0.887802 0 0.460225 0.887802 0 0.799849 0.600201 0 0.799849 0.600201 0 0.981057 0.19372 0 0.981057 0.19372 0 -0.967953 0.25113 0 -0.967953 0.25113 0 -0.763135 0.646239 0 -0.763135 0.646239 0 -0.407168 0.913353 0 -0.407168 0.913353 0 0.0294446 0.999566 0 0.0294446 0.999566 0 0.460225 0.887802 0 0.460225 0.887802 0 0.79985 0.6002 0 0.79985 0.6002 0 0.981057 0.193719 0 0.981057 0.193719 0 -0.967954 0.251129 0 -0.967954 0.251129 0 -0.763134 0.646241 0 -0.763134 0.646241 0 -0.407168 0.913353 0 -0.407168 0.913353 0 0.0294446 0.999566 0 0.0294446 0.999566 0 0.460222 0.887804 0 0.460222 0.887804 0 0.799851 0.600198 0 0.799851 0.600198 0 0.981057 0.193719 0 0.981057 0.193719 0 -0.967954 0.251129 0 -0.967954 0.251129 0 -0.763134 0.64624 0 -0.763134 0.64624 0 -0.407169 0.913353 0 -0.407169 0.913353 0 0.0294446 0.999566 0 0.0294446 0.999566 0 0.460224 0.887803 0 0.460224 0.887803 0 0.799851 0.600198 0 0.799851 0.600198 0 0.981057 0.193718 0 0.981057 0.193718 0 -0.967954 0.251126 0 -0.967954 0.251126 0 -0.763134 0.64624 0 -0.763134 0.64624 0 -0.407163 0.913355 0 -0.407163 0.913355 0 0.0294378 0.999567 0 0.0294378 0.999567 0 0.460227 0.887801 0 0.460227 0.887801 0 0.799852 0.600197 0 0.799852 0.600197 0 0.981057 0.193718 0 0.981057 0.193718 0 -0.355469 0.934688 0 -0.957888 0.287143 0 -0.957888 0.287143 0 -0.685982 0.727619 0.0184925 -0.587703 0.808865 0 -0.775556 0.631279 0.0190721 -0.100534 0.994751 0 -0.23027 0.973127 0 0.160563 0.987026 0.0094705 0.287141 0.957842 0 0.410564 0.911832 0 0.727619 0.685982 0 0.727619 0.685982 0 0.973127 0.23027 0 0.973127 0.23027 0 -0.967953 0.251132 0 -0.967953 0.251132 0 -0.763134 0.64624 0 -0.763134 0.64624 0 -0.407169 0.913353 0 -0.407169 0.913353 0 0.0294447 0.999566 0 0.0294447 0.999566 0 0.460221 0.887804 0 0.460221 0.887804 0 0.799851 0.600199 0 0.799851 0.600199 0 0.981058 0.193716 0 0.981058 0.193716 0 -0.96795 0.251145 0 -0.96795 0.251145 0 -0.763133 0.646242 0 -0.763133 0.646242 0 -0.407169 0.913353 0 -0.407169 0.913353 0 0.0294451 0.999566 0 0.0294451 0.999566 0 0.460213 0.887808 0 0.460213 0.887808 0 0.799853 0.600196 0 0.799853 0.600196 0 0.981057 0.193717 0 0.981057 0.193717 0 -0.967949 0.251145 0 -0.967949 0.251145 0 -0.763134 0.64624 0 -0.763134 0.64624 0 -0.407168 0.913354 0 -0.407168 0.913354 0 0.0294451 0.999566 0 0.0294451 0.999566 0 0.460215 0.887808 0 0.460215 0.887808 0 0.799852 0.600198 0 0.799852 0.600198 0 0.981057 0.193717 0 0.981057 0.193717 0 -0.967956 0.251121 0 -0.967956 0.251121 0 -0.763134 0.64624 0 -0.763134 0.64624 0 -0.407169 0.913353 0 -0.407169 0.913353 0 0.0294443 0.999566 0 0.0294443 0.999566 0 0.460227 0.887801 0 0.460227 0.887801 0 0.79985 0.600199 0 0.799851 0.600199 0 0.981058 0.193716 0 0.981058 0.193716 0 -0.967953 0.251132 0 -0.967953 0.251132 0 -0.763141 0.646232 0 -0.763141 0.646232 0 -0.407164 0.913355 0 -0.407164 0.913355 0 0.0294447 0.999566 0 0.0294447 0.999566 0 0.460227 0.887801 0 0.460227 0.887801 0 0.799853 0.600196 0 0.799853 0.600196 0 0.981055 0.193731 0 0.981055 0.193731 0 -0.967954 0.251128 0 -0.967954 0.251128 0 -0.763134 0.64624 0 -0.763134 0.64624 0 -0.407169 0.913353 0 -0.407169 0.913353 0 0.0294445 0.999566 0 0.0294445 0.999566 0 0.460224 0.887803 0 0.460224 0.887803 0 0.799851 0.600199 0 0.799851 0.600199 0 0.981058 0.193716 0 0.981058 0.193716 0.705156 0.707045 0.0533212 0.705156 0.707044 0.0533211 0.705156 0.680508 0.199159 0.705155 0.680508 0.199159 0.705155 0.62423 0.336293 0.705158 0.624228 0.336291 0.705158 0.540668 0.458727 0.705155 0.54067 0.458729 0.705155 0.433481 0.561116 0.705154 0.433481 0.561117 0.705154 0.307345 0.638981 0.705158 0.307344 0.638977 0.705158 0.167777 0.688914 0.705155 0.167777 0.688918 0.705155 0.0208773 0.708746 0.705157 0.0208775 0.708744 0.705156 -0.126935 0.697597 0.705158 -0.126935 0.697596 0.705158 -0.269199 0.65596 0.705153 -0.269201 0.655964 0.705153 -0.399702 0.58566 0.705156 -0.399699 0.585658 0.705157 -0.51273 0.489757 0.705159 -0.512729 0.489756 0.705159 -0.60335 0.372451 0.705157 -0.603352 0.372452 0.705157 -0.667604 0.23887 0.705156 -0.667605 0.23887 0.705156 -0.70268 0.0948467 0.705157 -0.702679 0.0948466 0.705755 0.707272 0.0409388 0.705758 0.707269 0.0409396 0.705758 0.689415 0.163133 0.705759 0.689415 0.163133 0.705758 0.650613 0.28037 0.705757 0.650615 0.28037 0.705757 0.592044 0.389089 0.705756 0.592045 0.38909 0.705756 0.515486 0.485986 0.705757 0.515485 0.485986 0.705757 0.423263 0.568115 0.705757 0.423264 0.568115 0.705757 0.318181 0.632983 0.705757 0.318181 0.632984 0.705757 0.203431 0.678619 0.705757 0.203431 0.678619 0.705757 0.0824993 0.703635 0.705757 0.0824991 0.703634 0.705757 -0.0409387 0.70727 0.705757 -0.0409389 0.70727 0.705757 -0.163133 0.689416 0.705757 -0.163133 0.689416 0.705757 -0.280371 0.650614 0.705757 -0.280371 0.650615 0.705757 -0.389089 0.592045 0.705757 -0.389089 0.592044 0.705757 -0.485986 0.515485 0.705756 -0.485986 0.515486 0.705756 -0.568116 0.423264 0.705757 -0.568115 0.423264 0.705757 -0.632983 0.318181 0.705757 -0.632983 0.318181 0.705757 -0.678619 0.203431 0.705757 -0.678619 0.203431 0.705757 -0.703634 0.0824993 0.705757 -0.703634 0.0824993 0.202051 0.967886 -0.14957 0.837552 0.542922 -0.061179 0.839719 0.539295 -0.0635074 0.839504 0.541974 -0.0386912 0.203238 0.976644 -0.0697193 0.202039 0.976885 -0.0698316 0.576261 0.815198 -0.0580986 0.202031 0.967891 -0.149569 0.202186 0.960061 -0.1934 0.146828 0.962252 -0.229156 0.202114 0.951523 -0.23185 0.202076 0.931403 -0.302742 0.202059 0.931407 -0.302742 0.202202 0.914302 -0.35095 0.09836 0.918622 -0.382699 0.202165 0.899449 -0.387454 0.202084 0.87085 -0.448087 0.202052 0.870857 -0.448088 0.202175 0.842879 -0.498678 0.0782949 0.846933 -0.525903 0.20218 0.822137 -0.532179 0.202067 0.787793 -0.581852 0.202064 0.787793 -0.581852 0.202157 0.747797 -0.632402 0.087155 0.751155 -0.654347 0.202197 0.721745 -0.661967 0.20206 0.68437 -0.700578 0.202062 0.68437 -0.700578 0.202062 0.625838 -0.753324 0.105544 0.641434 -0.759884 0.202212 0.601098 -0.77317 0.202061 0.563257 -0.801195 0.202067 0.563256 -0.801194 0.202067 0.497029 -0.843879 0.189369 0.499207 -0.845536 0.20222 0.46357 -0.862676 0.202063 0.427585 -0.881102 0.202074 0.427584 -0.881101 0.202073 0.355372 -0.912621 0.202074 0.355372 -0.912621 0.202227 0.313046 -0.927958 0.142092 0.283866 -0.948277 0.202097 0.27547 -0.939826 0.202056 0.204533 -0.957779 0.202076 0.20453 -0.957775 0.202218 0.153724 -0.9672 0.0957953 0.128953 -0.987013 0.202133 0.114696 -0.972619 0.202051 0.0484039 -0.978178 0.202057 0.0484033 -0.978177 0.202178 -0.00991086 -0.979299 0.0779427 -0.0309295 -0.996478 0.202179 -0.0492964 -0.978107 0.202065 -0.108977 -0.97329 0.202068 -0.108977 -0.973289 0.202159 -0.173269 -0.963903 0.0890591 -0.190039 -0.977729 0.202206 -0.211903 -0.956143 0.202068 -0.263539 -0.943248 0.202062 -0.263539 -0.943249 0.202062 -0.33851 -0.919012 0.112159 -0.336623 -0.934936 0.202216 -0.368557 -0.907345 0.202064 -0.411289 -0.888826 0.202062 -0.41129 -0.888826 0.202062 -0.481408 -0.852888 0.202063 -0.481408 -0.852888 0.202062 -0.54841 -0.811429 0.202058 -0.54841 -0.81143 0.202059 -0.611862 -0.76472 0.202061 -0.611862 -0.76472 0.202214 -0.646729 -0.735426 0.137506 -0.678983 -0.721162 0.202111 -0.675803 -0.708831 0.202066 -0.726501 -0.656784 0.202068 -0.726501 -0.656784 0.202208 -0.760434 -0.617132 0.0933715 -0.789845 -0.606157 0.202146 -0.784654 -0.58605 0.202061 -0.822363 -0.531874 0.202063 -0.822363 -0.531874 0.202183 -0.852799 -0.481515 0.0777745 -0.877954 -0.472385 0.202181 -0.871478 -0.446821 0.202064 -0.896968 -0.393215 0.202066 -0.896968 -0.393215 0.202154 -0.921226 -0.332381 0.091132 -0.941238 -0.325217 0.202205 -0.93384 -0.295052 0.202066 -0.948389 -0.244393 0.202065 -0.948389 -0.244393 0.202065 -0.964966 -0.167365 0.11875 -0.977143 -0.176324 0.202217 -0.969991 -0.135002 0.202065 -0.975297 -0.0892542 0.202064 -0.975297 -0.0892543 0.202064 -0.979315 -0.0105654 0.202063 -0.979315 -0.0105655 0.84084 0.539921 -0.0383755 0.573261 0.817279 -0.0585326 0.573282 0.809746 -0.125134 0.573264 0.809759 -0.125134 0.573264 0.797079 -0.189823 0.573244 0.797094 -0.189824 0.573244 0.779255 -0.253285 0.573271 0.779236 -0.253282 0.573271 0.756354 -0.315101 0.57324 0.756375 -0.315107 0.573241 0.728596 -0.37489 0.573265 0.728581 -0.374884 0.573265 0.696088 -0.432237 0.573258 0.696092 -0.432239 0.573259 0.659093 -0.486797 0.573258 0.659094 -0.486797 0.573258 0.617829 -0.538203 0.573263 0.617826 -0.538201 0.573263 0.572563 -0.586124 0.573258 0.572566 -0.586126 0.573258 0.523597 -0.630255 0.573262 0.523595 -0.630253 0.573262 0.471237 -0.670303 0.573255 0.47124 -0.670307 0.573255 0.415833 -0.706018 0.573265 0.415828 -0.706013 0.573266 0.357729 -0.737154 0.573256 0.357732 -0.73716 0.573257 0.297317 -0.763531 0.573258 0.297317 -0.76353 0.573259 0.234977 -0.784959 0.573263 0.234976 -0.784956 0.573263 0.171117 -0.801304 0.573255 0.171119 -0.80131 0.573255 0.10615 -0.812472 0.57326 0.106149 -0.812469 0.573261 0.0404963 -0.818372 0.573263 0.040496 -0.81837 0.573264 -0.0254204 -0.818977 0.57326 -0.0254201 -0.818979 0.57326 -0.0911738 -0.814285 0.573257 -0.0911738 -0.814287 0.573257 -0.156335 -0.804323 0.573255 -0.156335 -0.804324 0.573255 -0.220485 -0.789154 0.573262 -0.220485 -0.78915 0.573262 -0.283207 -0.768872 0.573259 -0.283208 -0.768874 0.573259 -0.344098 -0.74362 0.573259 -0.344098 -0.74362 0.57326 -0.402761 -0.713553 0.57326 -0.40276 -0.713552 0.57326 -0.458816 -0.678867 0.573263 -0.458816 -0.678866 0.573262 -0.511902 -0.639787 0.573261 -0.511902 -0.639788 0.573261 -0.561676 -0.596567 0.573261 -0.561675 -0.596567 0.573261 -0.607813 -0.549486 0.573258 -0.607815 -0.549488 0.573258 -0.650019 -0.49885 0.573261 -0.650017 -0.498848 0.573262 -0.688014 -0.444981 0.57326 -0.688014 -0.444982 0.57326 -0.721558 -0.388236 0.573259 -0.721559 -0.388236 0.573259 -0.750432 -0.328976 0.57326 -0.750431 -0.328976 0.57326 -0.774448 -0.267587 0.573259 -0.774449 -0.267588 0.573259 -0.793453 -0.204467 0.573261 -0.793452 -0.204467 0.573261 -0.80732 -0.140023 0.57326 -0.807321 -0.140023 0.57326 -0.815964 -0.0746729 0.573261 -0.815963 -0.0746728 0.573261 -0.819326 -0.0088394 0.573261 -0.819325 -0.00883934 0.850935 -0.525241 -0.00566663 0.850935 -0.525241 -0.0056666 0.850935 -0.523086 -0.0478702 0.850935 -0.523085 -0.0478701 0.850935 -0.517545 -0.0897638 0.850934 -0.517546 -0.089764 0.850934 -0.508655 -0.131077 0.850935 -0.508654 -0.131076 0.850935 -0.496471 -0.171541 0.850935 -0.496472 -0.171541 0.850935 -0.481075 -0.210895 0.850935 -0.481075 -0.210895 0.850935 -0.462565 -0.248884 0.850934 -0.462566 -0.248885 0.850934 -0.441063 -0.285263 0.850935 -0.441062 -0.285262 0.850935 -0.416703 -0.319794 0.850936 -0.416702 -0.319793 0.850936 -0.389647 -0.352255 0.850935 -0.389648 -0.352256 0.850935 -0.360071 -0.382438 0.850936 -0.36007 -0.382437 0.850936 -0.328162 -0.410144 0.850935 -0.328162 -0.410145 0.850935 -0.294131 -0.435197 0.850936 -0.29413 -0.435196 0.850936 -0.258194 -0.457431 0.850936 -0.258195 -0.457432 0.850936 -0.220588 -0.476707 0.850937 -0.220588 -0.476705 0.850936 -0.181554 -0.492895 0.850935 -0.181554 -0.492897 0.850935 -0.141345 -0.505896 0.850937 -0.141344 -0.505893 0.850937 -0.10022 -0.515618 0.850936 -0.10022 -0.51562 0.850936 -0.0584481 -0.522008 0.850932 -0.0584482 -0.522013 0.850933 -0.0162963 -0.525022 0.850936 -0.0162966 -0.525016 0.850937 0.0259606 -0.524627 0.850935 0.025961 -0.524629 0.850935 0.0680488 -0.520844 0.850937 0.068048 -0.520841 0.850937 0.109696 -0.513685 0.850936 0.109697 -0.513687 0.850936 0.150635 -0.503207 0.850933 0.150637 -0.503211 0.850933 0.1906 -0.489473 0.850935 0.190598 -0.489471 0.850935 0.229328 -0.472565 0.850932 0.229331 -0.472569 0.850932 0.266577 -0.452605 0.850937 0.266572 -0.452599 0.850937 0.302092 -0.429705 0.850936 0.302093 -0.429707 0.850936 0.335658 -0.404032 0.850937 0.335657 -0.404031 0.850937 0.367049 -0.375742 0.850937 0.367049 -0.375742 0.850937 0.396065 -0.34502 0.850936 0.396067 -0.345021 0.850936 0.42252 -0.312067 0.850934 0.422522 -0.312068 0.850934 0.44624 -0.277094 0.850934 0.44624 -0.277094 0.850934 0.467071 -0.240325 0.850941 0.46706 -0.240321 0.850942 0.484866 -0.201998 0.850935 0.484876 -0.202001 0.850935 0.499545 -0.16237 0.850941 0.499537 -0.162368 0.850941 0.510972 -0.121687 0.850935 0.510981 -0.121688 0.850935 0.519109 -0.0802206 0.878473 0.471501 -0.0772724 0.817753 0.573465 -0.0491639 0 0.999521 0.0309615 0.00671596 0.998307 0.0577847 0 0.993018 0.117959 0 0.984085 0.1777 0.00746246 0.973101 0.230259 0.00671284 0.923567 0.383377 0.00223791 0.918356 0.395749 0 0.947226 0.320568 0 0.964852 0.262792 0 0.889744 0.456459 0 0.86056 0.509348 0.00783584 0.835659 0.549192 0.00410333 0.727614 0.685975 0.00410345 0.727614 0.685974 0 0.776246 0.63043 0 0.812893 0.582413 0 0.55912 0.829087 0.00783579 0.597428 0.801884 0 0.629252 0.777201 0 0.67503 0.737791 0 0.508041 0.861333 0.00671306 0.437075 0.8994 0.00223784 0.449119 0.893469 0 0.37577 0.926713 0 0.31913 0.947711 0.0074624 0.287139 0.95786 0 0.235318 0.971919 0 0.176205 0.984353 0.0067159 0.116447 0.993174 0 0.0897421 0.995965 0 -0.030962 0.999521 0.00671585 -0.0577847 0.998307 0 -0.262792 0.964852 0.0074624 -0.23026 0.973101 0 -0.1777 0.984085 0 -0.117958 0.993019 0 -0.320571 0.947225 0.00186545 -0.383384 0.923587 0.00559607 -0.395744 0.918344 0 -0.45646 0.889744 0 -0.509348 0.860561 0.00783582 -0.549192 0.83566 0.00410338 -0.685975 0.727614 0.00410334 -0.685975 0.727614 0 -0.630432 0.776245 0 -0.582413 0.812893 0 -0.737791 0.675029 0 -0.777201 0.629252 0.0078358 -0.801884 0.597429 0.00186548 -0.899419 0.437084 0.00559602 -0.893457 0.449113 0 -0.861333 0.50804 0 -0.829087 0.55912 0 -0.926713 0.37577 0 -0.947711 0.31913 0.00746241 -0.95786 0.287139 0 -0.995965 0.0897425 0.00671582 -0.993174 0.116447 0 -0.984354 0.176205 0 -0.971919 0.235317 0.938494 0.330166 -0.10109 0.937011 0.33475 -0.0997674 0.938858 0.328742 -0.102347 0.944806 0.304551 -0.120791 0.933765 0.334886 -0.126231 0.937603 0.324464 -0.124999 0.941143 0.320249 -0.108119 0.943473 0.314661 -0.104148 0.94673 0.306257 -0.0995448 0.941636 0.322316 -0.0971266 0.939972 0.327725 -0.095128 0.947051 0.316856 -0.0519282 0.940947 0.330485 -0.0734776 0.94326 0.32428 -0.0714349 0.939691 0.329 -0.0934889 0.939501 0.334634 -0.0731908 0.918767 0.38406 -0.0914624 0.941314 0.332713 -0.0568278 0.942647 0.329207 -0.0551281 0.939577 0.333503 -0.0772767 0.939694 0.329025 -0.0933651 0.939565 0.328842 -0.0952889 0.942953 0.32509 -0.0718081 0.941912 0.327728 -0.0734651 0.938512 0.33618 -0.0786005 0.941424 0.329157 -0.0733248 0.941704 0.328431 -0.0729887 0.939606 -0.342238 -0.00369226 0.862581 -0.50585 -0.00836225 0.964232 -0.263957 -0.024156 0.953212 -0.300957 -0.0284891 0.943332 -0.33013 -0.0337507 0.940994 -0.336469 -0.0363084 0.940283 -0.338266 -0.0379969 0.94017 -0.338033 -0.0425901 0.940094 -0.338246 -0.042576 0.940158 -0.338069 -0.042571 0.939472 -0.332089 -0.0843144 0.940498 -0.326948 -0.0925666 0.939127 -0.331349 -0.0908206 0.940127 -0.327948 -0.0927977 0.938987 -0.333895 -0.0825688 0.937374 -0.339084 -0.0797008 0.930024 -0.360504 -0.0713641 0.93228 -0.355092 -0.0690137 0.936604 -0.344557 -0.0636645 0.939597 -0.337162 -0.0589927 0.939686 -0.339532 -0.041323 0.940015 -0.338903 -0.0389432 0.939758 -0.333807 -0.0736762 0.938786 -0.339434 -0.0588721 0.94066 -0.334133 -0.0592862 0.938536 -0.340254 -0.0581124 0.940186 -0.332245 -0.0752596 0.942437 -0.325266 -0.0775559 0.947247 -0.310365 -0.0799789 0.943205 -0.321106 -0.0851742 0.941032 -0.326493 -0.0886686 0.939668 -0.329582 -0.0916521 0.939603 -0.323499 -0.111776 0.936316 -0.329144 -0.122377 0.940945 -0.310074 -0.135931 0.939677 -0.31 -0.144595 0.939603 -0.301406 -0.162172 0.936377 -0.30521 -0.173337 0.940953 -0.284264 -0.183851 0.939676 -0.282903 -0.19229 0.939691 -0.244709 -0.238954 0.939704 -0.244993 -0.238608 0.939638 -0.245771 -0.23807 0.939336 -0.247878 -0.237073 0.93877 -0.250329 -0.236741 0.939215 -0.250421 -0.234872 0.943 -0.25939 -0.20849 0.940343 -0.255863 -0.224251 0.926824 -0.297884 -0.228608 0.938528 -0.269764 -0.215391 0.939482 -0.26722 -0.2144 0.935384 -0.27382 -0.223786 0.929104 -0.284182 -0.236656 0.941594 -0.252212 -0.223137 0.94485 -0.243679 -0.218812 0.946999 -0.238295 -0.215427 0.941038 -0.245329 -0.232939 0.939912 -0.245741 -0.237017 0.939693 -0.244542 -0.239114 0.939693 -0.244342 -0.239321 0.939603 -0.234621 -0.249196 0.936497 -0.234695 -0.260559 0.940966 -0.211479 -0.264311 0.939674 -0.207765 -0.271746 0.939603 -0.191655 -0.283574 0.936558 -0.189941 -0.294588 0.940971 -0.166383 -0.294773 0.939673 -0.161656 -0.301465 0.939603 -0.143735 -0.310622 0.936618 -0.140345 -0.321015 0.940974 -0.116991 -0.317617 0.939673 -0.11139 -0.323431 0.939513 -0.102316 -0.326875 0.939661 -0.103749 -0.325997 0.939695 -0.10481 -0.325559 0.939692 -0.104687 -0.325606 0.939731 -0.103707 -0.325807 0.939934 -0.102414 -0.325631 0.940339 -0.100914 -0.324929 0.941351 -0.0983628 -0.322774 0.947077 -0.0863798 -0.309167 0.949102 -0.0857584 -0.303069 0.943981 -0.086837 -0.318371 0.93962 -0.0719365 -0.334573 0.952735 -0.0517408 -0.299366 0.937775 -0.0819667 -0.33743 0.934978 -0.0862481 -0.34406 0.931666 -0.0904547 -0.351876 0.936782 -0.096637 -0.336304 0.938947 -0.100322 -0.32911 0.942069 -0.0868717 -0.323975 0.940707 -0.0865173 -0.328001 0.925879 -0.0720868 -0.370878 0.939491 -0.0721496 -0.334889 0.939603 -0.0380844 -0.34014 0.936738 -0.0318369 -0.348581 0.940978 -0.0105011 -0.338305 0.939671 -0.00362785 -0.342061 0.939603 0.0169161 -0.341847 0.936798 0.0242811 -0.349028 0.940978 0.0438481 -0.335615 0.93967 0.0510953 -0.338245 0.937278 0.0709951 -0.341276 0.938548 0.0684245 -0.338299 0.939666 0.0652945 -0.335804 0.939627 0.065226 -0.335925 0.940698 0.0663982 -0.332685 0.939372 0.0980762 -0.328575 0.942353 0.067169 -0.327811 0.947848 0.0673297 -0.31153 0.946194 0.0675803 -0.316464 0.940342 0.0805222 -0.330565 0.935167 0.101579 -0.33933 0.943938 0.0916248 -0.317154 0.94452 0.100344 -0.312751 0.9387 0.0896099 -0.332886 0.937589 0.0885822 -0.336274 0.936143 0.0876986 -0.340506 0.932867 0.086406 -0.349703 0.927835 0.0850307 -0.36317 0.931718 0.0797401 -0.35432 0.935609 0.0738802 -0.345221 0.941271 0.0953961 -0.323894 0.939605 0.0982521 -0.327856 0.939603 0.124194 -0.318938 0.936917 0.133066 -0.323234 0.940975 0.147775 -0.304512 0.939668 0.155231 -0.304839 0.939603 0.173699 -0.294914 0.936977 0.18294 -0.297671 0.940973 0.194668 -0.276903 0.939667 0.201965 -0.276108 0.93976 0.230207 -0.252695 0.938655 0.220371 -0.265261 0.940026 0.2188 -0.261684 0.939596 0.219189 -0.262901 0.938055 0.223427 -0.264828 0.940076 0.230815 -0.250961 0.941542 0.230097 -0.246076 0.947569 0.223298 -0.228586 0.944475 0.230811 -0.233866 0.941443 0.238582 -0.238251 0.939414 0.244 -0.240761 0.938612 0.244188 -0.243678 0.939755 0.243332 -0.240106 0.939675 0.237085 -0.246578 0.939346 0.235881 -0.248976 0.934521 0.232425 -0.269536 0.928781 0.244353 -0.278672 0.935464 0.229788 -0.268522 0.94029 0.241955 -0.2394 0.939672 0.244073 -0.239679 0.939603 0.258077 -0.224816 0.937095 0.267287 -0.224522 0.940963 0.272292 -0.201111 0.939665 0.278783 -0.198265 0.939604 0.290768 -0.180553 0.937155 0.299603 -0.178828 0.940957 0.301017 -0.154885 0.939664 0.306894 -0.151154 0.939603 0.315945 -0.131624 0.93463 0.332786 -0.125384 0.940056 0.322607 -0.110541 0 -0.991013 0.133765 0 -0.991013 0.133765 0 -0.941545 0.336886 0 -0.941545 0.336886 0 -0.850928 0.525282 0 -0.850928 0.525282 0 -0.723121 0.690721 0 -0.723121 0.690721 0 -0.56371 0.825973 0 -0.56371 0.825973 0 -0.379662 0.925125 0 -0.379662 0.925125 0 -0.179021 0.983845 0 -0.179021 0.983845 0 0.0294438 0.999566 0 0.0294438 0.999566 0 0.236622 0.971602 0 0.236622 0.971602 0 0.433458 0.901174 0 0.433458 0.901174 0 0.611351 0.79136 0 0.611351 0.79136 0 0.762525 0.646959 0 0.762525 0.646959 0 0.880372 0.474284 0 0.880372 0.474284 0 0.959743 0.28088 0 0.959743 0.28088 0 0.997168 0.0752006 0 0.997168 0.0752006 -0.851305 -0.507857 0.131759 -0.851307 0.0154502 0.524441 -0.851306 -0.213631 0.479207 -0.851306 -0.400393 0.339063 -0.851307 0.514728 0.101641 -0.851307 0.419657 0.314904 -0.851307 0.241463 0.465803 -0.851307 -0.507853 0.131763 -0.851307 0.0154474 0.524441 -0.851307 -0.213626 0.479208 -0.851307 -0.400393 0.33906 -0.851307 0.51473 0.101635 -0.851307 0.419655 0.314908 -0.851307 0.241466 0.465802 -0.849121 -0.121627 0.514004 -0.849121 -0.362331 0.384332 -0.849121 -0.505953 0.151673 -0.849122 0.514003 0.121626 -0.849121 0.384325 0.362336 -0.849121 0.151672 0.505953 -0.849121 -0.121626 0.514005 -0.849121 -0.362334 0.384328 -0.849121 -0.505955 0.151669 -0.849122 0.514003 0.121626 -0.849122 0.384328 0.362332 -0.849121 0.151671 0.505954 -0.705513 -0.703244 0.0877476 -0.705513 -0.703244 0.0877476 -0.705513 -0.674154 0.218559 -0.705511 -0.674156 0.21856 -0.70551 -0.620962 0.341557 -0.705511 -0.620961 0.341556 -0.705511 -0.545565 0.452341 -0.705512 -0.545565 0.452341 -0.705512 -0.450662 0.546952 -0.705509 -0.450664 0.546954 -0.705393 0.703051 -0.090216 -0.70539 0.703055 -0.0902163 -0.705391 0.671945 -0.225641 -0.705393 0.671943 -0.225641 -0.705393 0.615011 -0.352395 -0.705383 0.61502 -0.352399 -0.705385 0.534451 -0.465612 -0.705392 0.534446 -0.465607 -0.705392 0.433341 -0.560926 -0.705385 0.433345 -0.560931 -0.705387 0.315586 -0.634693 -0.705387 0.315586 -0.634692 -0.70539 0.185699 -0.684062 -0.705393 0.185697 -0.684059 -0.705392 0.0486762 -0.707144 -0.705386 0.0486769 -0.70715 -0.705388 -0.0902165 -0.703057 -0.705391 -0.0902162 -0.703054 -0.705391 -0.225642 -0.671944 -0.705391 -0.225642 -0.671945 -0.70539 -0.352396 -0.615014 -0.705387 -0.352398 -0.615017 -0.705388 -0.46561 -0.534449 -0.705391 -0.465608 -0.534446 -0.705392 -0.560926 -0.433341 -0.705393 -0.560925 -0.433341 -0.705393 -0.634688 -0.315583 -0.705391 -0.634689 -0.315584 -0.70539 -0.684062 -0.185698 -0.705391 -0.684061 -0.185698 -0.705392 -0.707144 -0.0486764 -0.705393 -0.707143 -0.0486762 0.706951 -0.561655 -0.429841 0.756782 -0.543967 -0.362465 0.746961 -0.55089 -0.37225 0.707012 -0.61061 -0.356777 0.707065 -0.624246 -0.332228 0.669697 -0.679283 -0.300136 0.706168 -0.652157 -0.275713 0.70693 -0.676769 -0.20551 0.647191 -0.740866 -0.179615 0.706536 -0.692756 -0.144554 0.705703 -0.707247 -0.0422385 0.572957 -0.815446 -0.0822676 0.706814 -0.707353 -0.00809735 0.705524 0.707179 0.0462005 0.705522 0.70718 0.0462002 0.705522 0.685841 0.178496 0.705523 0.68584 0.178496 0.705523 0.639979 0.304408 0.705521 0.639981 0.304409 0.705521 0.571237 0.419438 0.705522 0.571236 0.419438 0.705522 0.482068 0.51947 0.705521 0.482069 0.51947 0.705402 -0.634679 -0.315579 0.705402 -0.68405 -0.185695 0.705403 -0.68405 -0.185695 0.705403 -0.707133 -0.0486757 0.705403 -0.707134 -0.0486756 0.705403 -0.35239 -0.615003 0.705403 -0.4656 -0.534438 0.705402 -0.4656 -0.534438 0.707079 -0.520949 -0.478174 0.664013 -0.591712 -0.457125 0.705836 -0.566302 -0.425555 0.705402 -0.634679 -0.315579 0.705403 0.185695 -0.68405 0.705402 0.0486754 -0.707134 0.705403 0.0486755 -0.707134 0.705403 -0.0902145 -0.703042 0.705402 -0.0902146 -0.703043 0.70679 -0.187621 -0.68209 0.610542 -0.252116 -0.750784 0.706564 -0.253654 -0.660626 0.705401 -0.352391 -0.615004 0.705403 0.534437 -0.4656 0.705403 0.433334 -0.560917 0.705402 0.433335 -0.560918 0.707034 0.362822 -0.607012 0.644293 0.340499 -0.684797 0.706053 0.301994 -0.640538 0.705403 0.185695 -0.684049 0.641878 0.671647 -0.369978 0.707061 0.582968 -0.400266 0.705403 0.534438 -0.4656 0.705403 0.615002 -0.35239 0.705403 0.671933 -0.225638 0.705401 0.671935 -0.225639 0.705401 0.703044 -0.0902151 0.705404 0.703041 -0.090214 0.891902 -0.451767 -0.020449 0.706885 -0.707308 -0.00528107 0.15933 -0.677218 0.718324 0.159332 -0.677219 0.718323 0.446435 -0.539016 0.714253 0.446432 -0.539016 0.714255 0.645116 -0.289977 0.706921 0.645115 -0.289978 0.706922 0.716024 0.020554 0.697773 0.716024 0.0205538 0.697773 0.645115 0.331089 0.688627 0.645114 0.331086 0.688629 0.446431 0.58012 0.681292 0.446431 0.580123 0.681291 0.159339 0.71832 0.67722 0.159332 0.718327 0.677214 0.222532 -0.974503 0.0287051 0.22252 -0.974505 0.028706 0.623489 -0.781493 0.0230204 0.623489 -0.781493 0.0230204 0.900969 -0.433695 0.0127753 0.900972 -0.433689 0.0127748 1 0 0 1 0 0 0.900969 0.433695 -0.0127753 0.900969 0.433695 -0.0127753 0.623489 0.781493 -0.0230204 0.623489 0.781493 -0.0230204 0.22252 0.974505 -0.028706 0.222532 0.974503 -0.0287051 0.116756 -0.486227 0.865997 0.524675 0.0250654 0.850934 0.472715 -0.202482 0.857637 0.327128 -0.384963 0.863013 0.11675 0.53636 0.835875 0.327127 0.435093 0.838857 0.472715 0.252614 0.844232 0.186157 -0.673988 0.714903 0.18616 -0.673989 0.714901 0.508595 -0.487914 0.709416 0.508592 -0.487914 0.709418 0.694746 -0.165626 0.699926 0.694746 -0.165626 0.699926 0.694746 0.206539 0.688963 0.694745 0.206538 0.688964 0.508593 0.528823 0.67947 0.508592 0.528827 0.679468 0.186157 0.714901 0.67399 0.186157 0.714901 0.67399 0.222526 -0.974504 0.0287055 0.258819 -0.965572 0.0261433 0.467218 -0.883759 0.0260325 0.652298 -0.757634 0.0223173 0.707105 -0.706904 0.016984 0.826225 -0.563095 0.0165869 0.930879 -0.365169 0.0107566 0.965914 -0.258847 0.00301397 0.993708 -0.111957 0.00329787 0.993707 0.111958 -0.00329791 0.965913 0.258577 -0.0122275 0.930879 0.365169 -0.0107566 0.826225 0.563095 -0.0165869 0.707105 0.706678 -0.0246553 0.652303 0.75763 -0.0223175 0.467218 0.883759 -0.0260329 0.258819 0.965437 -0.0307379 0.22252 0.974505 -0.0287056 0.116753 -0.486228 0.865997 0.340308 -0.370143 0.864398 0.483402 -0.164468 0.85981 0.514172 0.0831271 0.853649 0.426416 0.315833 0.847596 0.11675 0.53636 0.835875 0.240759 0.480638 0.843222 0.34031 0.420379 0.841112 0.483402 0.214793 0.848638 0.514173 -0.0327349 0.857062 0.426415 -0.265395 0.864717 0.24076 -0.43017 0.870051 0.159332 0.718327 0.677214 0.159331 0.718329 0.677213 0.330491 0.645945 0.688136 0.455132 0.590599 0.666369 0.465285 0.561044 0.684646 0.585042 0.419514 0.694071 0.665351 0.340126 0.664546 0.661914 0.280361 0.695175 0.704866 0.100172 0.702232 0.741351 0.0197603 0.670826 0.704867 -0.0586604 0.70691 0.645119 -0.289976 0.70692 0.704667 -0.257191 0.661284 0.585042 -0.377931 0.717562 0.446429 -0.539013 0.714259 0.159339 -0.677217 0.718323 0.159331 -0.677213 0.718329 0.330486 -0.604314 0.724972 0.480121 -0.537721 0.693065 0.22252 -0.974505 0.028706 0.222532 -0.974503 0.0287051 0.467218 -0.883759 0.0260321 0.467218 -0.883759 0.0260321 0.652298 -0.757634 0.022317 0.652298 -0.757634 0.022317 0.826225 -0.563095 0.0165866 0.826225 -0.563095 0.0165866 0.930879 -0.365169 0.0107565 0.930879 -0.365169 0.0107565 0.993708 -0.111957 0.00329782 0.993708 -0.111957 0.00329782 0.993708 0.111957 -0.00329782 0.993707 0.11196 -0.003298 0.930879 0.365169 -0.0107568 0.930879 0.365169 -0.0107568 0.826225 0.563095 -0.0165871 0.826225 0.563095 -0.0165871 0.652298 0.757634 -0.0223176 0.652308 0.757626 -0.0223167 0.467218 0.883759 -0.0260321 0.467218 0.883759 -0.0260321 0.222532 0.974503 -0.0287051 0.22252 0.974505 -0.028706 0.11675 -0.48623 0.865997 0.340309 -0.370143 0.864398 0.483402 -0.164469 0.85981 0.514173 0.0831246 0.853649 0.426415 0.315832 0.847597 0.116756 0.536358 0.835876 0.240762 0.480636 0.843222 0.340308 0.420382 0.841112 0.483401 0.214794 0.848638 0.514173 -0.0327335 0.857062 0.426415 -0.265395 0.864717 0.24076 -0.43017 0.870051 -0.830791 -0.490002 -0.263979 -0.980669 -0.195473 -0.00887117 -0.980668 -0.191971 -0.0379064 -0.980671 0.194603 -0.0203607 -0.980668 -0.17227 -0.0928071 -0.980668 -0.172272 -0.0928081 -0.980668 -0.156514 -0.117447 -0.554436 -0.783314 -0.281105 -0.830791 -0.523873 -0.188 -0.830792 -0.523872 -0.188 -0.980668 -0.184177 -0.0660949 -0.980668 -0.184178 -0.0660953 -0.554466 0.765391 -0.326717 -0.19503 0.785045 -0.587935 -0.194523 0.834674 -0.515248 -0.55443 0.708168 -0.437156 -0.554431 0.765412 -0.326727 -0.830775 0.51192 -0.21852 -0.980668 0.179966 -0.0768209 -0.980668 0.166507 -0.102785 -0.830796 0.473608 -0.29236 -0.830795 0.424745 -0.359684 -0.554425 0.635106 -0.537823 -0.554426 0.547853 -0.626473 -0.980668 0.14933 -0.126456 -0.980668 0.128814 -0.147299 -0.83079 0.366398 -0.418977 -0.830789 0.29986 -0.468906 -0.554451 0.448355 -0.701114 -0.554451 0.338852 -0.760108 -0.194549 0.399388 -0.895902 -0.19499 0.303525 -0.932658 -0.980668 0.105423 -0.164855 -0.980668 0.079675 -0.178726 -0.830801 0.226617 -0.508344 -0.8308 0.148322 -0.536444 -0.55445 0.221779 -0.802122 -0.554453 0.0997518 -0.826215 -0.980669 0.0796717 -0.178718 -0.980669 0.0521452 -0.188597 -0.830786 0.148327 -0.536465 -0.830786 0.0667147 -0.55258 -0.55444 0.0997526 -0.826223 -0.554438 -0.0245041 -0.831864 -0.194554 -0.0288815 -0.980466 -0.195061 -0.116641 -0.973831 -0.980668 0.0234543 -0.194266 -0.980668 -0.00576146 -0.195593 -0.830795 -0.0163877 -0.556337 -0.830794 -0.0991226 -0.547683 -0.554435 -0.148213 -0.818923 -0.554431 -0.268613 -0.787688 -0.980667 -0.0348498 -0.192555 -0.980667 -0.063159 -0.185209 -0.830793 -0.179644 -0.526793 -0.830793 -0.256152 -0.494135 -0.554433 -0.383011 -0.738855 -0.554432 -0.488854 -0.673518 -0.194589 -0.576175 -0.793824 -0.195028 -0.655937 -0.729185 -0.980668 -0.0900571 -0.173726 -0.980668 -0.114943 -0.158363 -0.830797 -0.326935 -0.450434 -0.830797 -0.390417 -0.396676 -0.55442 -0.583782 -0.593141 -0.554419 -0.665666 -0.499509 -0.980669 -0.11494 -0.158359 -0.980669 -0.137259 -0.13946 -0.830799 -0.390414 -0.396673 -0.830801 -0.445173 -0.334053 -0.554425 -0.665662 -0.499506 -0.554422 -0.732677 -0.394716 -0.194593 -0.863543 -0.465218 -0.195098 -0.901676 -0.385898 -0.980668 0.194617 -0.0203623 -0.830778 0.553582 -0.05792 -0.830795 0.553557 -0.057917 -0.554441 0.827705 -0.0866003 -0.554408 0.827727 -0.0866031 -0.194605 0.975556 -0.10207 -0.194626 0.975553 -0.102069 -0.980671 0.189395 -0.0491375 -0.830774 0.538772 -0.139781 -0.830778 0.538766 -0.13978 -0.554466 0.805537 -0.208992 -0.554442 0.805552 -0.208996 0.780057 0.605657 -0.157134 -0.195045 0.959458 -0.203465 -0.194564 0.834667 -0.515244 -0.195067 0.877402 -0.438308 0.607551 0.730511 -0.311828 -0.194766 0.90776 -0.371534 -0.194913 0.941595 -0.274605 -0.980669 0.189402 -0.0491395 -0.980669 0.179963 -0.0768195 -0.830804 0.511881 -0.218503 -0.830803 0.473598 -0.292354 -0.554485 0.708137 -0.437136 -0.554482 0.635078 -0.537797 0.607529 0.606156 -0.513306 -0.194527 0.528457 -0.826373 -0.194967 0.611886 -0.76654 0.78007 0.411889 -0.470997 -0.19495 0.667462 -0.718671 -0.194808 0.738948 -0.644985 -0.980666 0.166515 -0.102791 -0.980667 0.149335 -0.12646 -0.830797 0.424742 -0.359682 -0.830796 0.366391 -0.41897 -0.554467 0.547836 -0.626452 -0.554465 0.44835 -0.701107 -0.194538 0.528456 -0.826371 -0.194538 0.399389 -0.895904 -0.980669 0.12881 -0.147294 -0.980669 0.105419 -0.164848 -0.83079 0.29986 -0.468906 -0.830791 0.226623 -0.508359 -0.554426 0.338858 -0.760123 -0.554431 0.221782 -0.802134 0.780063 0.166744 -0.603073 -0.194599 -0.0288807 -0.980458 -0.195106 0.0591159 -0.978999 0.60752 0.0952077 -0.788578 -0.194755 0.132122 -0.971913 -0.194903 0.232983 -0.952749 -0.980668 0.0521461 -0.188601 -0.980668 0.0234543 -0.194266 -0.830783 0.0667152 -0.552584 -0.830786 -0.0163883 -0.55635 -0.554445 -0.0245039 -0.83186 -0.554439 -0.148213 -0.81892 0.607534 -0.141457 -0.781596 -0.194585 -0.451427 -0.870833 -0.195028 -0.357894 -0.913168 0.780049 -0.201959 -0.59223 -0.194934 -0.288659 -0.937378 -0.194784 -0.1891 -0.962445 -0.980669 -0.00576129 -0.195589 -0.980669 -0.0348479 -0.192545 -0.830789 -0.0991239 -0.547689 -0.830789 -0.179646 -0.526798 -0.554421 -0.268615 -0.787695 -0.554422 -0.383015 -0.738861 -0.194582 -0.451427 -0.870834 -0.194578 -0.576177 -0.793826 -0.980669 -0.0631561 -0.185201 -0.980669 -0.0900535 -0.173719 -0.830792 -0.256153 -0.494136 -0.830793 -0.326938 -0.450438 -0.554433 -0.488854 -0.673518 -0.554433 -0.583776 -0.593135 0.780059 -0.438909 -0.445945 -0.194578 -0.863545 -0.465219 -0.195079 -0.818283 -0.5407 0.60752 -0.635325 -0.476741 -0.194761 -0.775639 -0.600376 -0.19491 -0.708612 -0.678144 -0.980668 -0.137261 -0.139462 -0.980668 -0.156515 -0.117447 -0.830798 -0.445176 -0.334056 -0.830797 -0.489993 -0.263975 -0.554422 -0.732677 -0.394716 -0.554419 -0.783325 -0.281108 0.60752 -0.747621 -0.268295 -0.194768 -0.928055 -0.317458 -0.195029 -0.969774 -0.146637 -0.980668 -0.191972 -0.0379067 -0.830788 -0.546046 -0.107822 -0.830792 -0.54604 -0.107821 -0.554437 -0.816461 -0.161218 -0.554436 -0.816462 -0.161218 0.78006 -0.613852 -0.121211 -0.194916 -0.956126 -0.218704 -0.980668 -0.195476 -0.00887126 -0.830788 -0.556018 -0.0252337 -0.830788 -0.556017 -0.0252336 -0.554441 -0.831367 -0.0377298 -0.554437 -0.83137 -0.0377299 -0.19458 -0.979878 -0.0444696 -0.194589 -0.979876 -0.0444696 -0.705184 -0.702653 0.0948432 -0.705182 -0.702654 0.0948433 -0.705182 -0.66758 0.238861 -0.70518 -0.667583 0.238862 -0.70518 -0.603332 0.37244 -0.705184 -0.603329 0.372438 -0.705183 -0.512711 0.489739 -0.705182 -0.512712 0.48974 -0.705183 -0.399685 0.585636 -0.705181 -0.399686 0.585637 -0.705182 -0.26919 0.655938 -0.705178 -0.269192 0.655942 -0.705178 -0.126932 0.697576 -0.705187 -0.12693 0.697567 -0.705189 0.0208765 0.708712 -0.705178 0.0208763 0.708722 -0.705179 0.167772 0.688894 -0.705186 0.16777 0.688887 -0.705188 0.307331 0.63895 -0.705181 0.307334 0.638957 -0.70518 0.433465 0.561097 -0.705178 0.433466 0.561098 -0.705177 0.540653 0.458715 -0.70518 0.540651 0.458713 -0.705181 0.624208 0.336281 -0.705187 0.624203 0.336277 -0.705187 0.680478 0.19915 -0.705183 0.680482 0.199151 -0.705184 0.707017 0.053319 -0.705184 0.707017 0.053319 0 0.994583 -0.103944 0 0.994583 -0.103944 0.694795 0.699881 0.16561 0.694797 0.699879 0.165609 0.694796 0.523309 0.493361 0.694795 0.52331 0.493362 0.694795 0.206519 0.688919 0.694796 0.206519 0.688919 0.694795 -0.16561 0.699881 0.694794 -0.16561 0.699882 0.694794 -0.493363 0.523311 0.694795 -0.493362 0.52331 0.694795 -0.688919 0.206518 0.694795 -0.68892 0.206518 0 0.981057 0.19372 -0.01479 0.973021 0.230242 0 0.89749 0.441035 0 0.776849 0.629687 -0.0246912 0.727399 0.685771 0 0.587405 0.809293 0 0.392591 0.919713 -0.0296535 0.287021 0.957465 0 0.141175 0.989985 0 -0.0826574 0.996578 -0.0296536 -0.230165 0.9727 0 -0.337775 0.941227 0 -0.538747 0.842468 -0.0246917 -0.685771 0.727399 0 -0.738437 0.674322 0 -0.869977 0.493093 -0.0147897 -0.957782 0.287115 0 -0.967953 0.25113 -0.698069 0.702467 0.138709 -0.698072 0.702463 0.138709 -0.706857 0.634845 0.311969 -0.601266 0.639119 0.479589 -0.700857 0.554127 0.449157 -0.706111 0.415942 0.573061 -0.526018 0.391408 0.755053 -0.703117 0.279161 0.653984 -0.704866 0.100141 0.702236 -0.497663 0.0255386 0.866994 -0.704866 -0.0586322 0.706913 -0.698067 -0.291545 0.653991 -0.38993 -0.311038 0.866724 -0.706112 -0.381487 0.596551 -0.698069 -0.546428 0.462727 -0.698068 -0.693085 0.179817 -0.69807 -0.693083 0.179816 -0.706856 -0.615385 0.348793 -0.573277 -0.605047 0.552513 0.698115 -0.693041 0.179805 0.698117 -0.693039 0.179805 0.706903 -0.615339 0.348779 0.601319 -0.609752 0.516351 0.700908 -0.526691 0.480961 0.706162 -0.38146 0.596509 0.526077 -0.346271 0.776749 0.70317 -0.240165 0.669232 0.704919 -0.0586279 0.70686 0.497719 0.0255377 0.866962 0.704919 0.100134 0.702184 0.698119 0.329511 0.635651 0.389969 0.361509 0.846897 0.706164 0.415911 0.573018 0.698123 0.572676 0.429729 0.698116 0.702422 0.138701 0.698119 0.702419 0.138699 0.706905 0.634802 0.311948 0.573336 0.636488 0.515915 0 -0.967953 0.25113 0 -0.967953 0.25113 0 -0.86997 0.493105 0 -0.86997 0.493105 0 -0.738437 0.674322 0 -0.738437 0.674322 0 -0.538747 0.842468 0 -0.538747 0.842468 0 -0.337775 0.941227 0 -0.337775 0.941227 0 -0.0826574 0.996578 0 -0.0826574 0.996578 0 0.141175 0.989985 0 0.141175 0.989985 0 0.392591 0.919713 0 0.392591 0.919713 0 0.587405 0.809293 0 0.587405 0.809293 0 0.776849 0.629686 0 0.776849 0.629686 0 0.89749 0.441035 0 0.89749 0.441035 0 0.981057 0.19372 0 0.981057 0.19372 -0.698063 0.702473 0.13871 -0.698066 0.702469 0.13871 -0.706853 0.634849 0.311971 -0.601263 0.639122 0.479589 -0.700857 0.554128 0.449156 -0.706111 0.415942 0.573061 -0.526018 0.391408 0.755053 -0.703117 0.279161 0.653984 -0.704866 0.100141 0.702236 -0.497663 0.0255386 0.866994 -0.704866 -0.0586322 0.706913 -0.698066 -0.291546 0.653991 -0.389923 -0.311039 0.866726 -0.706109 -0.381488 0.596554 -0.698067 -0.546429 0.462728 -0.698062 -0.693091 0.179819 -0.698064 -0.693089 0.179818 -0.70685 -0.615385 0.348804 -0.573277 -0.605047 0.552513 0.698123 0.702415 0.138697 0.69811 0.702427 0.138703 0.698107 0.572686 0.429741 0.698126 0.572674 0.429726 0.698122 0.329511 0.635648 0.698128 0.32951 0.635642 0.69813 0.0210809 0.71566 0.698121 0.0210786 0.71567 0.69812 -0.291522 0.653944 0.698114 -0.291526 0.653949 0.698119 -0.546391 0.462695 0.698123 -0.546387 0.462694 0.698124 -0.693033 0.179803 0.698124 -0.693032 0.179803 0 0.981057 0.193717 0.0147912 0.973021 0.230242 -0.0123562 0.799787 0.600157 0 0.776848 0.629688 0 0.587402 0.809296 -0.0197966 0.460134 0.887629 0 0.392593 0.919713 0 0.141177 0.989984 -0.0222813 0.0294365 0.999318 0 -0.0826608 0.996578 0 -0.337774 0.941227 -0.0197962 -0.407085 0.913176 0 -0.538742 0.842471 0 -0.763135 0.646239 -0.0147886 -0.73836 0.674245 0.0172029 -0.96781 0.251092 0 -0.957886 0.287149 -0.694743 0.69993 0.16562 -0.694749 0.699925 0.16562 -0.694743 0.523346 0.493397 -0.309053 0.738818 0.598861 -0.706115 0.415937 0.57306 -0.703123 0.27916 0.653979 -0.396523 0.26361 0.879363 -0.70487 0.100142 0.702233 -0.704868 -0.0586345 0.706911 -0.396532 -0.211388 0.893352 -0.694744 -0.688966 0.206534 -0.694744 -0.688966 0.206534 -0.700862 -0.526727 0.48099 -0.462291 -0.60828 0.645199 -0.706122 -0.381478 0.596545 -0.70313 -0.240178 0.669271 0.698121 0.702418 0.138698 0.698126 0.702413 0.138696 0.698127 0.572674 0.429725 0.698105 0.572688 0.429743 0.698109 0.329513 0.635661 0.698122 0.329511 0.635648 0.698117 0.0210814 0.715673 0.69812 0.0210821 0.71567 0.69812 -0.291525 0.653943 0.698126 -0.291521 0.653938 0.698128 -0.546382 0.462692 0.698103 -0.546406 0.462703 0.698097 -0.693057 0.17981 0.69812 -0.693034 0.179811 0 0.981057 0.193718 0.0147911 0.973021 0.230243 -0.0123558 0.799791 0.600151 0 0.776854 0.629681 0 0.587394 0.809301 -0.0197963 0.46013 0.887631 0 0.39259 0.919714 0 0.14117 0.989985 -0.0222793 0.0294366 0.999318 0 -0.0826497 0.996579 0 -0.337774 0.941227 -0.0197974 -0.407089 0.913174 0 -0.538753 0.842464 0 -0.763132 0.646242 -0.0147906 -0.738353 0.674252 0.0172023 -0.96781 0.251093 0 -0.957886 0.287149 -0.69474 0.699933 0.165623 -0.694738 0.699934 0.165623 -0.694743 0.523347 0.493397 -0.308983 0.73884 0.598869 -0.706108 0.415936 0.573069 -0.703117 0.27916 0.653985 -0.396512 0.263608 0.879368 -0.704868 0.100137 0.702235 -0.704869 -0.0586265 0.70691 -0.396504 -0.21139 0.893364 -0.69474 -0.68897 0.206535 -0.69474 -0.68897 0.206535 -0.700852 -0.52673 0.481001 -0.462297 -0.608276 0.645199 -0.70611 -0.381492 0.59655 -0.703117 -0.240182 0.669282 0.694796 0.69988 0.16561 0.694815 0.699863 0.165601 0.694807 0.523304 0.493352 0.69479 0.523313 0.493366 0.694793 0.206519 0.688921 0.694794 0.206519 0.688921 0.694796 -0.16561 0.69988 0.694799 -0.165609 0.699878 0.694787 -0.49337 0.523314 0.6948 -0.493359 0.523306 0.694797 -0.688917 0.206519 0.694798 -0.688917 0.206519 0 0.981057 0.193717 -0.0147912 0.973021 0.230242 0 0.897482 0.441051 0 0.776851 0.629684 -0.024691 0.727402 0.685768 0 0.587409 0.80929 0 0.39259 0.919714 -0.0296532 0.287021 0.957465 0 0.141177 0.989984 0 -0.08266 0.996578 -0.0296532 -0.230166 0.9727 0 -0.337774 0.941227 0 -0.538742 0.842471 -0.0246928 -0.685775 0.727395 0 -0.738443 0.674316 0 -0.869966 0.493112 -0.0147909 -0.957781 0.287117 0 -0.967954 0.251129 -0.69807 0.702466 0.138707 -0.69807 0.702466 0.138707 -0.706853 0.634844 0.311982 -0.601271 0.639118 0.479584 -0.70086 0.554127 0.449153 -0.706113 0.415944 0.573058 -0.526007 0.391408 0.75506 -0.703109 0.279164 0.653992 -0.704861 0.100143 0.702241 -0.497654 0.0255399 0.867 -0.704867 -0.058634 0.706912 -0.698066 -0.291548 0.653991 -0.389901 -0.311041 0.866736 -0.70609 -0.381495 0.596572 -0.698045 -0.546443 0.462745 -0.698071 -0.693082 0.179816 -0.69807 -0.693083 0.179816 -0.706856 -0.615377 0.348806 -0.573299 -0.605041 0.552498 0.698122 0.702416 0.138698 0.698125 0.702414 0.138696 0.698122 0.572676 0.429729 0.698105 0.572688 0.429743 0.69811 0.329516 0.635659 0.69811 0.329516 0.635659 0.698116 0.0210812 0.715674 0.69812 0.0210821 0.71567 0.69812 -0.291525 0.653943 0.698126 -0.291521 0.653938 0.698128 -0.546385 0.462689 0.698123 -0.546389 0.462691 0.698124 -0.693033 0.179803 0.698123 -0.693034 0.179803 0 0.981057 0.193718 0.0147911 0.973021 0.230242 -0.0123559 0.799791 0.600152 0 0.776853 0.629683 0 0.587394 0.809301 -0.0197956 0.460134 0.887629 0 0.392595 0.919711 0 0.141172 0.989985 -0.0222803 0.0294363 0.999318 0 -0.0826548 0.996578 0 -0.337774 0.941227 -0.0197974 -0.407089 0.913174 0 -0.538753 0.842464 0 -0.763137 0.646237 -0.0147893 -0.73836 0.674245 0.0172026 -0.96781 0.251093 0 -0.957886 0.287149 -0.694741 0.699931 0.165623 -0.694737 0.699936 0.165623 -0.694738 0.523353 0.493397 -0.309037 0.738826 0.59886 -0.706123 0.415927 0.573057 -0.703128 0.27916 0.653973 -0.39651 0.263608 0.879369 -0.704868 0.100139 0.702235 -0.704869 -0.0586302 0.70691 -0.396511 -0.211391 0.89336 -0.694742 -0.688968 0.206534 -0.694742 -0.688968 0.206534 -0.700857 -0.526731 0.480992 -0.462289 -0.608282 0.645199 -0.70611 -0.381492 0.59655 -0.703117 -0.240182 0.669282 0.694795 0.699881 0.16561 0.694816 0.699862 0.165601 0.694809 0.5233 0.493354 0.694811 0.523299 0.493352 0.694801 0.206518 0.688913 0.694791 0.206519 0.688924 0.694793 -0.16561 0.699883 0.694789 -0.165611 0.699887 0.694779 -0.493375 0.523319 0.694795 -0.493362 0.52331 0.694795 -0.688919 0.206519 0.694795 -0.688919 0.206519 0 0.973127 0.230268 0 0.973127 0.230268 0 0.72762 0.685981 0 0.72762 0.685981 0 0.287149 0.957886 0 0.287149 0.957886 0 -0.230266 0.973128 0 -0.230266 0.973128 0 -0.685983 0.727617 0 -0.685983 0.727617 0 -0.957886 0.287149 0 -0.957886 0.287149 -0.694741 -0.688969 0.206534 -0.694742 -0.688968 0.206534 -0.694742 -0.493399 0.523345 -0.694726 -0.493407 0.523359 -0.694735 -0.165622 0.699937 -0.69474 -0.165622 0.699933 -0.694737 0.206536 0.688973 -0.694748 0.206531 0.688964 -0.694757 0.523336 0.493388 -0.694756 0.523338 0.493389 -0.694763 0.699911 0.165617 -0.694742 0.699932 0.165617 0.694797 0.69988 0.165603 0.694788 0.699888 0.165607 0.694786 0.523315 0.493369 0.69479 0.523313 0.493366 0.694793 0.206519 0.688921 0.694794 0.206519 0.688921 0.694796 -0.16561 0.69988 0.694786 -0.165614 0.699889 0.694777 -0.493377 0.523321 0.6948 -0.493358 0.523308 0.694797 -0.688917 0.206519 0.694798 -0.688917 0.206519 0 0.981057 0.193718 -0.0147872 0.973023 0.230233 0 0.897513 0.440988 0 0.776845 0.629692 -0.0246901 0.727397 0.685772 0 0.587409 0.80929 0 0.39259 0.919714 -0.0296532 0.287021 0.957465 0 0.141177 0.989984 0 -0.08266 0.996578 -0.0296532 -0.230166 0.9727 0 -0.337774 0.941227 0 -0.538753 0.842464 -0.0246913 -0.685775 0.727395 0 -0.738441 0.674319 0 -0.869966 0.493112 -0.0147909 -0.957781 0.287117 0 -0.967954 0.251129 -0.69807 0.702466 0.138707 -0.698073 0.702463 0.138707 -0.706859 0.634859 0.311935 -0.601241 0.639136 0.479598 -0.700861 0.554122 0.449158 -0.706113 0.415944 0.573058 -0.526015 0.391409 0.755054 -0.703119 0.27916 0.653983 -0.704865 0.100143 0.702237 -0.497655 0.0255397 0.866999 -0.704867 -0.058634 0.706912 -0.698066 -0.291548 0.653991 -0.389901 -0.311041 0.866736 -0.706102 -0.381497 0.596557 -0.698054 -0.546437 0.462739 -0.698071 -0.693082 0.179816 -0.69807 -0.693083 0.179816 -0.706856 -0.615377 0.348806 -0.573296 -0.60504 0.552502 0.698121 0.702418 0.138698 0.698126 0.702413 0.138696 0.698126 0.572673 0.429727 0.698113 0.572681 0.429738 0.698121 0.329508 0.63565 0.698134 0.329505 0.635637 0.698131 0.021081 0.71566 0.698134 0.0210817 0.715657 0.698133 -0.291517 0.653933 0.698126 -0.291521 0.653938 0.698128 -0.546382 0.462692 0.698103 -0.546406 0.462703 0.698097 -0.693057 0.17981 0.69812 -0.693034 0.179811 0 0.981057 0.193718 0.0147911 0.973021 0.230243 -0.012356 0.79979 0.600153 0 0.776851 0.629684 0 0.587394 0.809301 -0.0197963 0.46013 0.887631 0 0.39259 0.919714 0 0.14118 0.989984 -0.0222814 0.0294366 0.999318 0 -0.08266 0.996578 0 -0.337774 0.941227 -0.0197962 -0.407085 0.913176 0 -0.538742 0.842471 0 -0.763132 0.646242 -0.0147906 -0.738353 0.674252 0.0172023 -0.96781 0.251093 0 -0.957886 0.287149 -0.69474 0.699933 0.165623 -0.694738 0.699934 0.165623 -0.694742 0.523346 0.493399 -0.308992 0.738836 0.59887 -0.706108 0.415936 0.573069 -0.703117 0.27916 0.653985 -0.396527 0.26361 0.879361 -0.704868 0.100144 0.702234 -0.704869 -0.0586338 0.70691 -0.396532 -0.211388 0.893352 -0.69474 -0.68897 0.206535 -0.69474 -0.68897 0.206535 -0.700852 -0.52673 0.481001 -0.462297 -0.608276 0.645199 -0.706122 -0.381478 0.596545 -0.70313 -0.240178 0.669271 0.694796 0.69988 0.16561 0.694802 0.699875 0.165607 0.694797 0.52331 0.49336 0.69479 0.523313 0.493366 0.694793 0.20652 0.688921 0.694794 0.20652 0.68892 0.694796 -0.16561 0.69988 0.694789 -0.165613 0.699886 0.694786 -0.493369 0.523315 0.6948 -0.493358 0.523308 0.694797 -0.688917 0.206519 0.694798 -0.688917 0.206519 0 0.973127 0.230267 0 0.973127 0.230267 0 0.727621 0.685979 0 0.727621 0.685979 0 0.287149 0.957886 0 0.287149 0.957886 0 -0.230267 0.973127 0 -0.230267 0.973127 0 -0.685982 0.727619 0 -0.685982 0.727619 0 -0.957886 0.287149 0 -0.957886 0.287149 -0.694744 -0.688966 0.206534 -0.694744 -0.688966 0.206534 -0.694747 -0.493395 0.523343 -0.694733 -0.493402 0.523355 -0.694735 -0.165623 0.699937 -0.694743 -0.165623 0.69993 -0.69474 0.206535 0.68897 -0.69474 0.206535 0.68897 -0.694737 0.523352 0.4934 -0.694743 0.523346 0.493397 -0.694749 0.699925 0.16562 -0.694743 0.69993 0.16562 3.05434e-05 0.133145 0.991096 -0.320219 0.410635 0.853721 0 0.421466 0.906844 0 0.503557 0.863962 -0.000481609 0.505217 0.862992 -0.0061506 0.512514 0.858657 -6.20422e-05 0.13565 0.990757 0 0.135261 0.99081 -0.0432973 0.2364 0.970691 -0.166632 0.229123 0.959029 0 0.331342 0.943511 -0.0414665 -0.174568 0.983772 -0.159794 -0.176721 0.971203 0 -0.275239 0.961376 -0.0129435 0.0294412 0.999483 -0.0129368 0.0294417 0.999483 3.54507e-05 -0.0745761 0.997215 -4.74973e-05 -0.0768339 0.997044 0 -0.0770223 0.997029 -0.00885032 -0.464665 0.885442 -0.000476475 -0.453544 0.891234 0 -0.451848 0.892095 0 -0.367356 0.930081 -0.320216 -0.359671 0.876413 0 -0.462564 0.886586 0 -0.56371 0.825973 0 -0.56371 0.825973 0 -0.723121 0.690722 0 -0.723121 0.690722 0 -0.850928 0.525282 0 -0.850928 0.525282 0 -0.941546 0.336886 0 -0.941546 0.336886 0 -0.991013 0.133766 0 -0.991013 0.133766 0 0.516002 0.856588 0 0.611351 0.79136 0 0.611351 0.79136 0 0.762524 0.64696 0 0.762524 0.64696 0 0.880372 0.474284 0 0.880372 0.474284 0 0.959743 0.28088 0 0.959743 0.28088 0 0.997168 0.0752004 0 0.997168 0.0752004 0 0.997527 -0.0702846 0.179823 0.971222 -0.15618 0 0.992981 -0.11827 0 0.965195 -0.261532 0.0915357 0.952278 -0.291183 0 0.938094 -0.34638 0 0.889318 -0.457289 0.0716561 0.894246 -0.441803 -0.0844529 0.79134 -0.605515 0 0.803839 -0.594847 0 0.997873 0.0651917 0 0.997873 0.0651917 0 0.967762 0.251868 0 0.967762 0.251868 0 0.903049 0.429538 0 0.903049 0.429538 0 0.806048 0.591851 0 0.806048 0.591851 0 0.680227 0.733002 0 0.680227 0.733002 0 -0.997639 -0.0686726 0 -0.997639 -0.0686726 0 -0.965073 -0.261983 0 -0.965073 -0.261983 0 -0.895419 -0.445225 0 -0.895419 -0.445225 0 -0.791354 -0.611358 0 -0.791354 -0.611358 0 -0.656879 -0.753996 0 -0.656879 -0.753996 0 -0.497159 -0.867659 0 -0.497159 -0.867659 0 -0.318335 -0.947978 0 -0.318335 -0.947978 0 -0.127277 -0.991867 0 -0.127277 -0.991867 0 0.0686724 -0.997639 0 0.0686724 -0.997639 0 0.261983 -0.965073 0 0.261983 -0.965073 0 0.445226 -0.895419 0 0.445226 -0.895419 0 0.611358 -0.791355 0 0.611358 -0.791355 0 0.753996 -0.656878 0 0.753996 -0.656878 0 0.867659 -0.49716 0 0.867659 -0.49716 0 0.947978 -0.318334 0 0.947978 -0.318334 0 0.991867 -0.127277 0 0.991867 -0.127277 0 0.998972 0.0453356 -0.293501 0.953252 0.0718881 0 0.988761 0.149508 0 0.974823 0.222982 -0.345753 0.900551 0.263557 0 0.946175 0.323656 -0.181115 0.865812 0.46644 -0.181106 0.865814 0.466441 0 0.919341 0.393462 -0.34575 0.715497 0.607059 0 0.790782 0.612098 0 0.834313 0.551291 -0.293501 0.584426 0.756507 0 0.66878 0.743461 0 0.722469 0.691403 -0.293499 0.414369 0.861485 0 0.460223 0.887803 0 0.587403 0.809294 0 0.118925 0.992903 0 0.192793 0.981239 -0.345755 0.222028 0.911678 0 0.294304 0.955712 0 0.364902 0.931046 -0.181112 0.0289572 0.983036 -0.181112 0.0289572 0.983036 0 -0.0602739 0.998182 0 -0.134701 0.990886 -0.345756 -0.16798 0.923166 0 -0.237539 0.971378 0 -0.309467 0.95091 -0.293498 -0.362942 0.884382 0 -0.407167 0.913354 0 -0.538748 0.842467 -0.2935 -0.538884 0.789596 0 -0.623858 0.781537 0 -0.680519 0.732731 -0.345755 -0.678522 0.648121 0 -0.753382 0.657583 0 -0.894589 0.446891 -0.181114 -0.836856 0.516595 -0.181112 -0.836856 0.516595 0 -0.800417 0.599444 0 -0.925483 0.378789 -0.345756 -0.883475 0.316108 0 -0.960007 0.279975 0 -0.978246 0.20745 -0.293502 -0.947367 0.127874 0 -0.994571 0.104059 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.998972 -0.0453362 -0.2935 -0.953252 -0.0718886 0 -0.919342 -0.393459 0 -0.946175 -0.323656 -0.345756 -0.90055 -0.263557 0 -0.974823 -0.222981 0 -0.988761 -0.149508 -0.181112 -0.865813 -0.46644 -0.181115 -0.865812 -0.46644 0 -0.834313 -0.551291 0 -0.790783 -0.612097 -0.345758 -0.715495 -0.607058 0 -0.722468 -0.691404 0 -0.668779 -0.743461 -0.293499 -0.584427 -0.756508 0 -0.587404 -0.809294 0 -0.460224 -0.887803 -0.293504 -0.414368 -0.861484 0 -0.364901 -0.931046 0 -0.294305 -0.955712 -0.345757 -0.222028 -0.911677 0 -0.192793 -0.981239 -0.181111 -0.0289568 -0.983036 -0.181113 -0.0289566 -0.983036 0 -0.118925 -0.992903 -0.345756 0.16798 -0.923166 0 0.134701 -0.990886 0 0.0602743 -0.998182 -0.293502 0.362941 -0.884381 0 0.309465 -0.950911 0 0.237539 -0.971378 -0.293499 0.538884 -0.789596 0 0.538749 -0.842467 0 0.407167 -0.913354 0 0.800415 -0.599446 0 0.753382 -0.657583 -0.345753 0.678523 -0.648121 0 0.680519 -0.73273 0 0.623858 -0.781538 -0.181119 0.836855 -0.516594 -0.181109 0.836856 -0.516596 0 0.894587 -0.446893 0 0.925483 -0.378788 -0.345754 0.883476 -0.316108 0 0.960007 -0.279975 0 0.978246 -0.20745 -0.2935 0.947368 -0.127874 0 0.994571 -0.104059 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.635901 0.771771 0 -0.635901 0.771771 0 -0.769812 0.63827 0 -0.769812 0.63827 0 -0.876199 0.481949 0 -0.876199 0.481949 0 -0.951258 0.308395 0 -0.951258 0.308395 0 -0.992305 0.123815 0 -0.992305 0.123815 0 -0.828136 0.560527 0 -0.82857 -0.559885 0.0716578 -0.835306 -0.545095 0 -0.882766 -0.469814 0 -0.921069 -0.3894 0.116998 -0.926696 -0.357136 0 -0.956856 -0.290563 0 -0.978916 -0.204266 0.136559 -0.978369 -0.155389 0 -0.994949 -0.100377 0 -0.998605 0.0528018 0.210811 -0.973237 0.0914813 0 -0.999934 -0.0114466 0 -0.889979 0.456001 0.128344 -0.871258 0.473747 0 -0.923815 0.382839 0 -0.965573 0.260134 0.170027 -0.942619 0.287332 0 -0.98187 0.189556 0.0859627 -0.76189 0.641977 0 -0.775158 0.631768 0 -0.698726 0.71539 0.0397656 -0.625674 0.779071 0 -0.619771 0.784782 0 0.66489 0.746941 -0.0397669 0.670446 0.740892 0.0364274 0.795875 0.604365 0 0.801323 0.598232 0 0.898044 0.439907 0.0793427 0.902265 0.423818 0 0.859695 0.510808 0 0.99772 0.0674892 0.157188 0.98697 0.0343848 0 0.991325 0.131432 0 0.965999 0.258547 0.118545 0.965197 0.233113 0 0.944748 0.327797 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.0294437 0.999566 0 0.0294437 0.999566 0 -0.997168 -0.0752006 0 -0.997168 -0.0752006 0 -0.959743 -0.28088 0 -0.959743 -0.28088 0 -0.880372 -0.474284 0 -0.880372 -0.474284 0 -0.762524 -0.646959 0 -0.762524 -0.646959 0 -0.611351 -0.79136 0 -0.611351 -0.79136 0 -0.433459 -0.901174 0 -0.433459 -0.901174 0 -0.236622 -0.971602 0 -0.236622 -0.971602 0 -0.0294437 -0.999566 0 -0.0294437 -0.999566 0 0.179021 -0.983845 0 0.179021 -0.983845 0 0.379662 -0.925125 0 0.379662 -0.925125 0 0.56371 -0.825973 0 0.56371 -0.825973 0 0.72312 -0.690722 0 0.72312 -0.690722 0 0.850928 -0.525282 0 0.850928 -0.525282 0 0.941546 -0.336885 0 0.941546 -0.336885 0 0.991013 -0.133766 0 0.991013 -0.133766 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.290989 -0.956726 0 -0.290989 -0.956726 0 -0.117778 -0.99304 0 -0.117778 -0.99304 0 0.0591217 -0.998251 0 0.0591217 -0.998251 0 0.23417 -0.972196 0 0.23417 -0.972196 0 0.999566 -0.029444 0 0.999566 -0.029444 -1.65707e-07 0.0294438 0.999566 -6.67252e-08 0.0294438 0.999566 2.12104e-08 0.0294438 0.999566 -4.26719e-09 0.0294439 0.999566 8.07159e-08 0.0294437 0.999566 1.09364e-07 0.0294436 0.999566 -2.5078e-08 0.0294438 0.999566 2.57392e-09 0.0294441 0.999566 0 0.029444 0.999566 3.14347e-08 0.0294435 0.999566 -3.93744e-08 0.0294441 0.999566 -2.09955e-08 0.029444 0.999566 6.68207e-08 0.0294438 0.999566 4.04015e-08 0.0294439 0.999566 7.81277e-08 0.0294439 0.999566 -1.39979e-07 0.0294435 0.999566 1.89642e-08 0.0294437 0.999566 9.40725e-08 0.0294437 0.999566 0 0.0294437 0.999566 -5.79303e-09 0.0294437 0.999566 -1.02898e-07 0.0294438 0.999566 -2.40971e-07 0.0294438 0.999566 -8.09396e-08 0.0294437 0.999566 2.2062e-08 0.0294439 0.999566 -7.55893e-08 0.0294439 0.999566 3.97523e-07 0.0294436 0.999566 -5.07402e-09 0.0294438 0.999566 -1.43849e-07 0.0294439 0.999566 -3.98899e-08 0.0294438 0.999566 2.97744e-08 0.0294442 0.999566 0 0.0294439 0.999566 -1.59084e-08 0.029444 0.999566 3.88675e-08 0.0294438 0.999566 -5.35579e-09 0.0294439 0.999566 4.79278e-08 0.0294438 0.999566 1.22473e-07 0.0294438 0.999566 1.9289e-07 0.0294438 0.999566 2.72387e-08 0.0294437 0.999566 1.05863e-07 0.0294436 0.999566 0 0.0294437 0.999566 -6.39257e-08 0.0294436 0.999566 -9.05325e-08 0.0294437 0.999566 1.20683e-07 0.029444 0.999566 1.27519e-07 0.029444 0.999566 -5.5319e-08 0.0294439 0.999566 6.86842e-08 0.0294438 0.999566 4.39805e-07 0.0294438 0.999566 -2.17698e-07 0.0294438 0.999566 1.32531e-07 0.0294438 0.999566 8.9813e-08 0.0294438 0.999566 0 0.0294439 0.999566 0 0.0294438 0.999566 6.37871e-08 0.0294438 0.999566 5.82181e-08 0.0294438 0.999566 0 0.0294434 0.999566 0 0.0294434 0.999566 -4.08933e-08 0.0294439 0.999566 -3.04724e-08 0.0294438 0.999566 1.71616e-07 0.0294438 0.999566 -4.39805e-07 0.0294438 0.999566 -5.72698e-07 0.0294438 0.999566 4.46448e-07 0.0294439 0.999566 -1.79969e-07 0.0294438 0.999566 -1.66853e-07 0.0294435 0.999566 1.24658e-07 0.029444 0.999566 3.13545e-07 0.0294437 0.999566 6.18516e-09 0.0294439 0.999566 2.18101e-07 0.0294442 0.999566 5.15653e-09 0.0294438 0.999566 1.99879e-08 0.0294442 0.999566 2.74616e-09 0.0294441 0.999566 0 0.029444 0.999566 7.00085e-09 0.0294439 0.999566 -1.75387e-08 0.0294441 0.999566 1.36513e-07 0.0294436 0.999566 -1.88006e-08 0.0294439 0.999566 2.47963e-07 0.029444 0.999566 -4.53582e-07 0.0294434 0.999566 -1.4816e-07 0.0294435 0.999566 1.55721e-08 0.0294437 0.999566 -1.93514e-07 0.0294441 0.999566 0 0.0294442 0.999566 5.51399e-08 0.0294442 0.999566 4.15505e-08 0.0294438 0.999566 -1.88899e-07 0.0294439 0.999566 3.14976e-07 0.0294438 0.999566 2.41886e-07 0.0294438 0.999566 -1.33923e-07 0.0294437 0.999566 0 -0.999566 0.0294438 0 -0.999566 0.0294438 0 -0.287147 -0.957887 0 -0.287147 -0.957887 0 -0.992818 -0.119638 0 -0.992818 -0.119638 8.95349e-08 -0.992818 -0.119639 0 -0.992818 -0.119637 -1.87025e-07 -0.992818 -0.119638 -3.63516e-07 -0.992818 -0.119638 -1.28806e-07 -0.992818 -0.119638 -7.22859e-07 -0.992818 -0.119637 0 0.984054 -0.17787 5.08721e-07 0.984054 -0.17787 0 0.984054 -0.177869 0 0.984054 -0.177869 5.01183e-07 0.984054 -0.177871 -3.92386e-07 0.984054 -0.177869 0 0.230267 -0.973128 0 0.230267 -0.973128 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.999566 -0.0294446 0 0.999566 -0.0294446 0 -0.029444 -0.999566 0 -0.029444 -0.999566 0 0.999566 -0.0294436 2.71049e-06 0.999566 -0.0294442 0 0.999566 -0.0294462 -2.14142e-06 0.999566 -0.0294526 4.13647e-06 0.999566 -0.029444 1.26772e-07 0.999566 -0.0294439 0 0.999566 -0.0294437 0 -0.029444 -0.999566 0 -0.029444 -0.999566 0 -0.999566 0.0294465 -2.70451e-06 -0.999566 0.0294442 0 -0.999566 0.0294436 0 -0.999566 0.0294437 -4.78137e-07 -0.999566 0.0294444 -4.25633e-06 -0.999566 0.0294439 1.97475e-06 -0.999566 0.0294524 0 -0.0294435 -0.999566 0 -0.0294435 -0.999566 0 -0.999566 0.0294425 0 -0.999566 0.0294425 0 -0.68598 0.72762 0 -0.68598 0.72762 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.727619 0.685982 0 0.727619 0.685982 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.406387 0.913701 0 0.406387 0.913701 0 -0.0512595 0.998685 0 -0.0512595 0.998685 0 -0.4978 0.867292 0 -0.4978 0.867292 0 0.547988 0.836486 0 0.547988 0.836486 0 0.109955 0.993937 0 0.109955 0.993937 0 -0.3519 0.936038 0 -0.3519 0.936038 0 -0.256974 0.966418 0 -0.256974 0.966418 0 -0.697909 0.716186 0 -0.697909 0.716186 0 -0.959453 0.281869 0 -0.959453 0.281869 0 0.974381 0.224903 0 0.974381 0.224903 0 0.738853 0.673866 0 0.738853 0.673866 0 0.313415 0.949616 0 0.313415 0.949616 0 -0.964053 -0.265709 0.160339 -0.98661 -0.0298736 0.0135669 -0.973037 -0.230251 0 -0.999938 0.0111184 0 -0.964053 -0.265709 0 -0.727623 -0.685977 0 -0.727623 -0.685977 0 -0.287146 -0.957887 0 -0.287146 -0.957887 0 0.946742 -0.321992 0.0251247 0.957584 -0.287057 0.00206895 0.996436 -0.0843266 0 0.998865 -0.0476378 0 0.946742 -0.321992 0 0.685982 -0.727619 0 0.685982 -0.727619 0 0.230265 -0.973128 0 0.230265 -0.973128 0 0.396973 -0.917831 0 0.396973 -0.917831 0 0.265248 -0.96418 0 0.265248 -0.96418 0 -0.321542 -0.946895 0 -0.321542 -0.946895 0 -0.45031 -0.892872 0 -0.45031 -0.892872 0 -0.951354 -0.3081 0 -0.951354 -0.3081 0 -0.765011 -0.644017 0 -0.765011 -0.644017 0 -0.465782 -0.884899 0 -0.465782 -0.884899 0 0.412888 -0.910782 0 0.412888 -0.910782 0 0.725776 -0.687931 0 0.725776 -0.687931 0 0.931569 -0.363566 0 0.931569 -0.363566 0 -0.982245 -0.187601 0 -0.982245 -0.187601 0 -0.810934 -0.585138 0 -0.810934 -0.585138 0 -0.487666 -0.87303 0 -0.487666 -0.87303 0 0.435431 -0.900222 0 0.435431 -0.900222 0 0.775084 -0.631858 0 0.775084 -0.631858 0 0.9695 -0.24509 0 0.9695 -0.24509 0 0.481881 -0.876237 0 0.481881 -0.876237 0 0.756844 -0.653595 0 0.756844 -0.653595 0 0.93707 -0.349141 0 0.93707 -0.349141 0 -0.955996 -0.29338 0 -0.955996 -0.29338 0 -0.794004 -0.607912 0 -0.794004 -0.607912 0 -0.532624 -0.846352 0 -0.532624 -0.846352 0 -0.230267 0.973127 0 -0.230267 0.973127 0 -0.685979 0.727622 0 -0.685979 0.727622 0 -0.957886 0.287149 0 -0.957886 0.287149 0 0.973128 0.230266 0 0.973128 0.230266 0 0.727615 0.685986 0 0.727615 0.685986 0 0.287149 0.957886 0 0.287149 0.957886 0 -0.974616 0.223885 0 -0.81475 0.579812 0.120402 -0.758328 0.640658 0 -0.841111 0.540863 0.00668926 -0.855253 0.518167 0.0159609 -0.862286 0.50617 0 -0.890756 0.454482 0 -0.974616 0.223885 0.0551866 0.914569 0.400648 0.00667743 0.88426 0.466948 0 0.8715 0.490396 0 0.80055 0.599266 0.0701504 0.84538 0.529539 0 0.902077 0.431575 0 0.986104 0.166128 0 0.986104 0.166128 0 -0.936709 -0.35011 0 -0.223884 -0.974616 -0.0636676 -0.286565 -0.955943 0 -0.468505 -0.883461 0 -0.631858 -0.775084 -0.0848766 -0.724995 -0.683504 0 -0.810933 -0.585138 0 -0.936709 -0.35011 -0.0593043 -0.907902 -0.414967 0.070181 -0.989065 -0.129712 0.0233168 -0.985837 -0.166079 0 -0.999935 0.0113815 0 0.938985 -0.343958 0.0545022 0.973168 -0.223549 0.016956 0.984265 -0.175882 0 0.998871 -0.0475083 0 0.938985 -0.343958 0 0.814751 -0.579812 0 0.814751 -0.579812 0 0.530848 -0.847467 0 0.530848 -0.847467 0 0.166128 -0.986104 0 0.166128 -0.986104 0 -0.67439 -0.738375 -0.00524018 -0.67528 -0.737543 0.00522208 -0.911287 -0.411739 0 -0.911801 -0.410632 0 0.885483 -0.464672 0.00525783 0.886038 -0.463583 -0.00526641 0.629749 -0.776781 0 0.630702 -0.776025 0 -0.017122 -0.999853 -0.00591178 -0.0184162 -0.999813 0.00586816 -0.433638 -0.901068 -0.0117568 -0.437111 -0.899331 0.0116709 -0.770655 -0.637145 -0.0175178 -0.774695 -0.632092 0.017408 -0.96639 -0.256491 0 -0.967525 -0.252776 0 0.949759 -0.312981 0.0177369 0.950819 -0.30924 -0.0180323 0.731748 -0.681337 0.0120257 0.736207 -0.67665 -0.011959 0.379826 -0.924981 0.00598912 0.383438 -0.923547 -0.00593689 -0.0417599 -0.99911 0 -0.0404691 -0.999181 0 -0.999566 0.0294442 0 -0.999566 0.0294442 -0.258818 0.965507 -0.0284406 -0.258818 0.965507 -0.0284406 -0.707108 0.706799 -0.0208199 -0.707108 0.706799 -0.0208199 -0.965926 0.258706 -0.00762062 -0.965926 0.258706 -0.00762062 0 0.999566 -0.0294439 0 0.999566 -0.0294439 0.980787 0.194998 -0.00574398 0.965869 0.25901 0.00319619 0.896864 0.442114 -0.0130232 0.793359 0.608491 -0.0179241 0.707034 0.707151 -0.00637682 0.195089 0.98036 -0.0288781 0.258803 0.965769 -0.0176237 0.442286 0.896485 -0.0264074 0.608758 0.793012 -0.0233595 1 0 0 1 0 0 0.258819 -0.965507 0.028441 0.195071 -0.980682 0.0145281 0.608725 -0.792645 0.0341737 0.555565 -0.831113 0.0244814 0.793356 -0.608494 0.0179239 0.831447 -0.555103 0.023593 0.965869 -0.25901 -0.00319619 0.980787 -0.194998 0.00574405 -0.965926 -0.258706 0.00762072 -0.965926 -0.258706 0.00762072 -0.707109 -0.706798 0.0208202 -0.707107 -0.7068 0.0208197 -0.258816 -0.965508 0.0284402 -0.258819 -0.965507 0.028441 -1 0 0 -1 0 0 0 0.999566 -0.0294442 0 0.999566 -0.0294442 -0.258819 0.965507 -0.028441 -0.258816 0.965508 -0.0284402 -0.707107 0.7068 -0.0208197 -0.707109 0.706798 -0.0208202 -0.965926 0.258706 -0.00762072 -0.965926 0.258706 -0.00762072 0.965926 0.258706 -0.00762072 0.965926 0.258706 -0.00762072 0.707107 0.7068 -0.0208202 0.707109 0.706798 -0.0208196 0.258819 0.965507 -0.0284402 0.258816 0.965508 -0.028441 1 0 0 1 0 0 0.258819 -0.965507 0.028441 0.195071 -0.980682 0.0145281 0.608725 -0.792645 0.0341737 0.555565 -0.831113 0.0244814 0.793359 -0.608491 0.0179238 0.831447 -0.555103 0.0235926 0.965869 -0.25901 -0.00319639 0.980787 -0.194998 0.0057439 0 -0.999566 0.0294442 0 -0.999566 0.0294442 -0.965926 -0.258706 0.00762052 -0.980684 -0.195409 -0.00860355 -0.793305 -0.608145 0.0287384 -0.831469 -0.555331 0.0163579 -0.608767 -0.793005 0.0233589 -0.555555 -0.830875 0.0317178 -0.258804 -0.965769 0.0176242 -0.195091 -0.98036 0.0288785 -1 0 0 -1 0 0 0.707102 -0.706805 0.0208201 0.707102 -0.706805 0.0208201 0.69857 -0.702837 -0.134236 0.69857 -0.702838 -0.134236 0.69857 -0.580257 -0.418691 0.698571 -0.580256 -0.41869 0.69857 -0.348945 -0.624689 0.698571 -0.348945 -0.624689 0.69474 -0.165622 0.699932 0.694741 -0.165623 0.699932 0.69474 -0.493398 0.52335 0.694741 -0.493399 0.523347 0.694742 -0.688969 0.206534 0.694742 -0.688969 0.206534 0.707101 -0.203045 -0.677334 0.707102 -0.203045 -0.677333 0.707101 0.0208201 0.706806 0.707101 0.0208201 0.706806 0.707101 0.0208201 0.706806 0.700426 -0.679005 -0.219899 0.700426 -0.679005 -0.219899 0.700426 -0.546008 -0.459652 0.700425 -0.546008 -0.459652 0.700425 -0.332441 -0.631575 0.700425 -0.332441 -0.631575 0.694742 0.699931 0.165621 0.694742 0.699931 0.165621 0.694741 0.523345 0.493402 0.694741 0.523345 0.493402 0.69474 0.206535 0.68897 0.694741 0.206534 0.68897 0.707101 -0.702033 -0.0845974 0.707102 -0.702033 -0.0845974 0.707102 0.706805 -0.0208202 0.707102 0.706805 -0.0208202 0.701459 -0.681348 -0.209095 0.70146 -0.681347 -0.209095 0.701458 -0.565895 -0.433265 0.701459 -0.565895 -0.433265 0.701459 -0.379607 -0.603204 0.701458 -0.379608 -0.603204 0.69857 0.311569 -0.644147 0.698569 0.311569 -0.644148 0.698568 0.554607 -0.452122 0.69857 0.554606 -0.452119 0.69857 0.693718 -0.175372 0.698571 0.693717 -0.175372 0.70571 -0.206166 -0.677842 0.70571 -0.206166 -0.677841 0.70571 -0.083446 -0.70357 0.705711 -0.0834457 -0.703569 0.705711 0.0418877 -0.70726 0.705709 0.0418876 -0.707262 0.705709 0.16591 -0.688802 0.70571 0.16591 -0.688802 0.707101 0.162825 -0.688111 0.707101 0.162825 -0.688111 0.701458 0.343442 -0.624504 0.701461 0.343443 -0.6245 0.70146 0.539409 -0.465823 0.701463 0.539409 -0.46582 0.701463 0.667856 -0.248834 0.701459 0.667858 -0.248838 0.700425 0.294689 -0.650048 0.700428 0.294686 -0.650047 0.700429 0.518002 -0.490991 0.700428 0.518004 -0.490992 0.700429 0.664881 -0.259485 0.700427 0.664884 -0.259485 0.707102 0.695836 -0.125774 0.707102 0.695836 -0.125774 -0.69474 -0.699933 -0.16562 -0.694752 -0.699921 -0.16562 -0.694753 -0.52334 -0.493391 -0.309044 -0.738822 -0.59886 -0.706115 -0.415937 -0.57306 -0.703123 -0.27916 -0.653979 -0.396507 -0.263608 -0.879371 -0.70487 -0.100135 -0.702233 -0.704868 0.0586272 -0.706912 -0.396501 0.211392 -0.893365 -0.69474 0.68897 -0.206535 -0.69474 0.68897 -0.206535 -0.700853 0.526732 -0.480998 -0.462279 0.608283 -0.645206 -0.706103 0.381496 -0.596556 -0.703113 0.240184 -0.669286 0 -0.981057 -0.193718 0.0147911 -0.973021 -0.230243 -0.012356 -0.799789 -0.600154 0 -0.776851 -0.629685 0 -0.587402 -0.809296 -0.0197966 -0.460134 -0.887629 0 -0.392593 -0.919713 0 -0.141167 -0.989986 -0.0222793 -0.0294365 -0.999318 0 0.0826505 -0.996579 0 0.337774 -0.941227 -0.0197974 0.407089 -0.913174 0 0.538753 -0.842464 0 0.763135 -0.646239 -0.0147903 0.738357 -0.674248 0.0172023 0.96781 -0.251093 0 0.957886 -0.287149 0.698121 -0.702418 -0.138698 0.698113 -0.702425 -0.138702 0.698115 -0.572681 -0.429734 0.698126 -0.572674 -0.429726 0.698122 -0.329511 -0.635648 0.698116 -0.329512 -0.635654 0.698117 -0.0210813 -0.715674 0.69812 -0.0210821 -0.71567 0.69812 0.291525 -0.653943 0.698126 0.291521 -0.653938 0.698128 0.546384 -0.46269 0.698123 0.546389 -0.462692 0.698124 0.693032 -0.179804 0.698121 0.693035 -0.179804 -0.698069 -0.702466 -0.138714 -0.698071 -0.702464 -0.138714 -0.706853 -0.634861 -0.311946 -0.601241 -0.639136 -0.479598 -0.700861 -0.554122 -0.449158 -0.706113 -0.415944 -0.573058 -0.526015 -0.391409 -0.755054 -0.703119 -0.27916 -0.653983 -0.704865 -0.100143 -0.702237 -0.497655 -0.0255397 -0.866999 -0.704867 0.058634 -0.706912 -0.698066 0.291548 -0.653991 -0.389931 0.311042 -0.866722 -0.706101 0.381487 -0.596564 -0.698054 0.546437 -0.462739 -0.698071 0.693082 -0.179816 -0.69807 0.693083 -0.179816 -0.706856 0.615377 -0.348806 -0.573296 0.60504 -0.552502 0 -0.981055 -0.193727 -0.0147872 -0.973021 -0.230242 0 -0.897507 -0.441001 0 -0.776845 -0.629692 -0.0246901 -0.727397 -0.685772 0 -0.587409 -0.80929 0 -0.39259 -0.919714 -0.0296532 -0.287021 -0.957465 0 -0.141177 -0.989984 0 0.08266 -0.996578 -0.0296537 0.230168 -0.972699 0 0.337779 -0.941226 0 0.538739 -0.842473 -0.0246934 0.68577 -0.727399 0 0.738441 -0.674319 0 0.869966 -0.493112 -0.0147909 0.957781 -0.287117 0 0.967954 -0.251129 0.694796 -0.69988 -0.16561 0.694789 -0.699886 -0.165613 0.694786 -0.523315 -0.493369 0.69479 -0.523313 -0.493366 0.694793 -0.206519 -0.688921 0.694794 -0.206519 -0.688921 0.694796 0.165611 -0.699879 0.694792 0.165613 -0.699883 0.694796 0.493361 -0.52331 0.6948 0.493358 -0.523308 0.694797 0.688917 -0.206519 0.694798 0.688917 -0.206519 -0.694741 0.688971 -0.206529 -0.694739 0.688973 -0.206529 -0.694737 0.4934 -0.523352 -0.694743 0.493397 -0.523347 -0.694738 0.16562 -0.699935 -0.694743 0.16562 -0.69993 -0.69474 -0.206533 -0.68897 -0.694747 -0.206529 -0.688964 -0.694757 -0.523338 -0.493387 -0.694743 -0.523349 -0.493394 -0.694738 -0.699934 -0.165623 -0.69474 -0.699933 -0.165623 0 -0.973127 -0.230268 0 -0.973127 -0.230268 0 -0.727621 -0.685979 0 -0.727621 -0.685979 0 -0.287146 -0.957887 0 -0.287146 -0.957887 0 0.230263 -0.973128 0 0.230263 -0.973128 0 0.685979 -0.727621 0 0.685979 -0.727621 0 0.957889 -0.28714 0 0.957889 -0.28714 0.694793 -0.699883 -0.165611 0.694792 -0.699884 -0.165612 0.694796 -0.52331 -0.493361 0.69481 -0.523302 -0.49335 0.694801 -0.206516 -0.688914 0.694794 -0.206516 -0.688921 0.694797 0.165606 -0.69988 0.694791 0.165609 -0.699885 0.694796 0.493361 -0.52331 0.69479 0.493366 -0.523313 0.694793 0.688923 -0.206514 0.694794 0.688921 -0.206514 -0.698069 -0.702467 -0.138707 -0.698072 -0.702464 -0.138707 -0.706857 -0.634841 -0.311978 -0.601277 -0.639115 -0.479581 -0.700862 -0.554126 -0.449151 -0.706115 -0.415943 -0.573056 -0.526013 -0.391407 -0.755057 -0.703112 -0.279162 -0.65399 -0.704864 -0.100139 -0.702238 -0.497669 -0.0255386 -0.866991 -0.704866 0.0586304 -0.706913 -0.698066 0.291545 -0.653991 -0.38992 0.311039 -0.866728 -0.706113 0.381489 -0.596549 -0.698072 0.546427 -0.462723 -0.698069 0.693084 -0.179817 -0.698071 0.693082 -0.179816 -0.706857 0.615379 -0.348801 -0.573293 0.605042 -0.552503 0 -0.981057 -0.193718 -0.014791 -0.973021 -0.230242 0 -0.897484 -0.441048 0 -0.776853 -0.629683 -0.0246912 -0.727403 -0.685767 0 -0.587409 -0.80929 0 -0.39259 -0.919714 -0.0296538 -0.287019 -0.957466 0 -0.141172 -0.989985 0 0.0826548 -0.996578 -0.0296538 0.230164 -0.9727 0 0.337774 -0.941227 0 0.53875 -0.842466 -0.0246917 0.685775 -0.727395 0 0.738441 -0.674318 0 0.86997 -0.493105 -0.0147906 0.957781 -0.287117 0 0.967953 -0.25113 0.694796 -0.69988 -0.16561 0.694817 -0.699862 -0.165601 0.694812 -0.523301 -0.493348 0.694788 -0.523314 -0.493368 0.69479 -0.206519 -0.688925 0.694794 -0.206518 -0.688921 0.694797 0.165608 -0.69988 0.694789 0.165611 -0.699887 0.694779 0.493375 -0.523319 0.694795 0.493362 -0.52331 0.694795 0.688919 -0.206519 0.694796 0.688919 -0.206519 -0.698069 -0.702467 -0.138707 -0.698073 -0.702463 -0.138707 -0.706859 -0.634841 -0.311975 -0.601277 -0.639115 -0.479582 -0.700862 -0.554126 -0.449151 -0.706115 -0.415943 -0.573056 -0.526013 -0.391407 -0.755057 -0.703112 -0.279162 -0.65399 -0.704864 -0.100141 -0.702238 -0.497663 -0.0255387 -0.866994 -0.704866 0.0586322 -0.706913 -0.698066 0.291547 -0.653991 -0.389908 0.31104 -0.866733 -0.706102 0.381495 -0.596559 -0.698054 0.546437 -0.462738 -0.698069 0.693084 -0.179817 -0.69807 0.693083 -0.179816 -0.706856 0.61538 -0.348802 -0.573289 0.605044 -0.552505 0 -0.981057 -0.193718 -0.0147909 -0.973021 -0.230242 0 -0.897485 -0.441045 0 -0.776852 -0.629683 -0.0246911 -0.727402 -0.685767 0 -0.587409 -0.80929 0 -0.39259 -0.919714 -0.0296535 -0.28702 -0.957466 0 -0.141174 -0.989985 0 0.0826574 -0.996578 -0.0296535 0.230165 -0.9727 0 0.337774 -0.941227 0 0.53875 -0.842466 -0.0246916 0.685774 -0.727396 0 0.738441 -0.674319 0 0.86997 -0.493105 -0.0147906 0.957781 -0.287117 0 0.967953 -0.25113 0.694795 -0.699881 -0.16561 0.694816 -0.699862 -0.165601 0.69481 -0.523303 -0.49335 0.69479 -0.523313 -0.493366 0.694793 -0.206518 -0.688921 0.694791 -0.206519 -0.688924 0.694793 0.16561 -0.699883 0.694789 0.165611 -0.699887 0.694779 0.493375 -0.523319 0.694795 0.493362 -0.52331 0.694795 0.688919 -0.206519 0.694796 0.688919 -0.206519 -0.69474 0.68897 -0.206535 -0.69474 0.68897 -0.206535 -0.694737 0.493402 -0.52335 -0.694752 0.493394 -0.523337 -0.694752 0.16562 -0.699922 -0.694743 0.16562 -0.69993 -0.69474 -0.206536 -0.68897 -0.694748 -0.206532 -0.688963 -0.694757 -0.523336 -0.493388 -0.694743 -0.523348 -0.493396 -0.694738 -0.699934 -0.165623 -0.69474 -0.699933 -0.165623 0 -0.981057 -0.193718 0.0147911 -0.973021 -0.230243 0 -0.897482 -0.441051 0 -0.776851 -0.629684 0.0246931 -0.727397 -0.685772 0 -0.587394 -0.809301 0 -0.392595 -0.919711 0.0296537 -0.287024 -0.957464 0 -0.141177 -0.989984 0 0.08266 -0.996578 0.0296532 0.230166 -0.9727 0 0.337774 -0.941227 0 0.538742 -0.842471 0.0246924 0.685772 -0.727397 0 0.967953 -0.251131 0.0147903 0.957781 -0.287117 0 0.869974 -0.493098 0 0.738441 -0.674319 0.698121 0.693035 -0.179804 0.698124 0.693032 -0.179804 0.706908 0.615337 -0.348771 0.601324 0.609752 -0.516345 0.700915 0.526689 -0.480954 0.706168 0.381453 -0.596506 0.526089 0.346263 -0.776744 0.703171 0.240164 -0.669233 0.704919 0.0586297 -0.70686 0.497722 -0.0255345 -0.866961 0.704927 -0.100134 -0.702176 0.698122 -0.329511 -0.635648 0.389999 -0.361508 -0.846884 0.70616 -0.415906 -0.573027 0.698113 -0.572681 -0.429738 0.698121 -0.702418 -0.138698 0.698126 -0.702413 -0.138696 0.706911 -0.634791 -0.311956 0.573358 -0.636478 -0.515903 -0.698069 -0.702466 -0.138714 -0.698046 -0.702489 -0.138712 -0.706835 -0.634864 -0.311981 -0.601241 -0.639136 -0.479598 -0.700861 -0.554122 -0.449158 -0.706113 -0.415944 -0.573058 -0.526015 -0.391409 -0.755054 -0.703119 -0.27916 -0.653983 -0.704865 -0.100143 -0.702237 -0.497655 -0.0255397 -0.866999 -0.704869 0.0586351 -0.70691 -0.698077 0.291543 -0.653981 -0.38992 0.311039 -0.866728 -0.706116 0.381489 -0.596545 -0.698075 0.546421 -0.462726 -0.698071 0.693082 -0.179816 -0.69807 0.693083 -0.179816 -0.706856 0.615377 -0.348806 -0.573288 0.605039 -0.552511 0 -0.981057 -0.193718 -0.0147907 -0.973021 -0.230242 0 -0.897488 -0.441039 0 -0.776845 -0.629692 -0.0246901 -0.727397 -0.685772 0 -0.587409 -0.80929 0 -0.39259 -0.919714 -0.0296532 -0.287021 -0.957465 0 -0.141177 -0.989984 0 0.0826617 -0.996578 -0.0296527 0.230168 -0.972699 0 0.337774 -0.941227 0 0.538753 -0.842464 -0.0246905 0.68577 -0.727399 0 0.738434 -0.674325 0 0.869966 -0.493112 -0.0147909 0.957781 -0.287117 0 0.967954 -0.251129 0.694796 -0.69988 -0.16561 0.694789 -0.699886 -0.165613 0.694786 -0.523315 -0.493369 0.69479 -0.523313 -0.493366 0.694793 -0.206519 -0.688921 0.694802 -0.206519 -0.688913 0.69479 0.165613 -0.699885 0.694792 0.165612 -0.699884 0.694796 0.493361 -0.52331 0.6948 0.493358 -0.523308 0.694797 0.688917 -0.206519 0.694798 0.688917 -0.206519 -0.69474 0.68897 -0.206535 -0.69474 0.68897 -0.206535 -0.694737 0.4934 -0.523352 -0.694743 0.493397 -0.523346 -0.694749 0.16562 -0.699925 -0.694743 0.16562 -0.69993 -0.69474 -0.206535 -0.68897 -0.69474 -0.206535 -0.68897 -0.694737 -0.523352 -0.4934 -0.694743 -0.523346 -0.493397 -0.694749 -0.699924 -0.165621 -0.69474 -0.699933 -0.165621 0 -0.973127 -0.230268 0 -0.973127 -0.230268 0 -0.727621 -0.685979 0 -0.727621 -0.685979 0 -0.287149 -0.957886 0 -0.287149 -0.957886 0 0.230267 -0.973127 0 0.230267 -0.973127 0 0.685979 -0.727621 0 0.685979 -0.727621 0 0.957886 -0.287149 0 0.957886 -0.287149 0.694793 -0.699883 -0.165611 0.694802 -0.699875 -0.165607 0.694797 -0.52331 -0.49336 0.69479 -0.523313 -0.493366 0.694793 -0.20652 -0.688921 0.694794 -0.20652 -0.68892 0.694796 0.16561 -0.69988 0.694802 0.165607 -0.699875 0.694797 0.49336 -0.52331 0.69479 0.493366 -0.523313 0.694793 0.688921 -0.20652 0.694794 0.68892 -0.20652 -0.694734 0.688975 -0.206536 -0.694741 0.68897 -0.206533 -0.694739 0.493399 -0.52335 -0.69474 0.493398 -0.523349 -0.69474 0.165622 -0.699933 -0.69474 0.165622 -0.699933 -0.694737 -0.206535 -0.688973 -0.694736 -0.206535 -0.688974 -0.694734 -0.523354 -0.493402 -0.694743 -0.523346 -0.493398 -0.694743 -0.699929 -0.165622 -0.694736 -0.699937 -0.165622 0 -0.973127 -0.230268 0 -0.973127 -0.230268 0 -0.727621 -0.685979 0 -0.727621 -0.685979 0 -0.287148 -0.957886 0 -0.287148 -0.957886 0 0.230267 -0.973128 0 0.230267 -0.973128 0 0.68598 -0.727621 0 0.68598 -0.727621 0 0.957886 -0.287149 0 0.957886 -0.287149 0.694789 -0.699887 -0.165612 0.694797 -0.69988 -0.165608 0.694797 -0.52331 -0.493361 0.694788 -0.523314 -0.493368 0.69479 -0.20652 -0.688924 0.69479 -0.20652 -0.688924 0.694793 0.16561 -0.699883 0.694793 0.16561 -0.699882 0.694794 0.493363 -0.523311 0.694793 0.493364 -0.523312 0.694794 0.68892 -0.20652 0.694788 0.688926 -0.20652 -0.694742 0.688968 -0.206534 -0.694742 0.688968 -0.206534 -0.694742 0.493398 -0.523347 -0.694738 0.493401 -0.52335 -0.694736 0.165622 -0.699936 -0.694741 0.165622 -0.699931 -0.694742 -0.206533 -0.688968 -0.694745 -0.206532 -0.688966 -0.694744 -0.523345 -0.493397 -0.694743 -0.523347 -0.493397 -0.694743 -0.69993 -0.16562 -0.694742 -0.699931 -0.16562 0 -0.973128 -0.230265 0 -0.973128 -0.230265 0 -0.72762 -0.685981 0 -0.72762 -0.685981 0 -0.287148 -0.957886 0 -0.287148 -0.957886 0 0.230265 -0.973128 0 0.230265 -0.973128 0 0.685982 -0.727619 0 0.685982 -0.727619 0 0.957886 -0.287149 0 0.957886 -0.287149 0.694796 -0.69988 -0.165609 0.694797 -0.69988 -0.165608 0.694796 -0.523309 -0.493362 0.694798 -0.523308 -0.493361 0.694799 -0.206518 -0.688916 0.694796 -0.206518 -0.688919 0.694795 0.165609 -0.699881 0.69479 0.165611 -0.699885 0.694791 0.493366 -0.523312 0.694795 0.493362 -0.52331 0.694795 0.688919 -0.206519 0.694796 0.688919 -0.206519 0.939691 0.0100705 0.341877 0.939691 0.0100705 0.341877 0.183735 0.933193 0.308856 0.183733 0.933194 0.308854 0.415717 0.852683 0.316404 0.529894 0.801553 0.276992 0.572616 0.755925 0.317313 0.783072 0.532902 0.320647 0.923695 0.193546 0.330648 0.923696 0.193555 0.33064 0.842988 0.425607 0.328982 0.762192 0.592759 0.260192 0.911249 -0.234299 0.338718 0.244169 -0.90109 0.358354 0.244168 -0.90109 0.358356 0.572618 -0.735935 0.36126 0.68303 -0.675113 0.278732 0.746255 -0.562374 0.356146 0.91125 -0.234297 0.338715 0 0.949355 0.314205 0 0.949355 0.314205 0 -0.929215 0.369539 0 -0.929215 0.369539 -0.244168 0.920621 0.304695 -0.244169 0.920621 0.304693 -0.667084 0.676557 0.31188 -0.66708 0.676559 0.311884 -0.91125 0.253828 0.324337 -0.911248 0.25383 0.32434 -0.911249 -0.234296 0.338718 -0.91125 -0.234299 0.338715 -0.667082 -0.657027 0.351166 -0.667081 -0.657029 0.351163 -0.244169 -0.90109 0.358354 -0.244169 -0.90109 0.358354 -0.939691 0.0100705 0.341877 -0.939691 0.0100705 0.341877 0.939691 0.0100705 0.341877 0.939691 0.0100705 0.341877 0.911249 0.253828 0.324341 0.911249 0.253831 0.324338 0.667083 0.676555 0.311886 0.667082 0.676558 0.311883 0.244166 0.920623 0.304691 0.244168 0.920622 0.304693 0.911248 -0.234299 0.338719 0.244169 -0.90109 0.358354 0.244168 -0.90109 0.358356 0.572618 -0.735935 0.36126 0.68303 -0.675113 0.278732 0.746256 -0.56237 0.356148 0.91125 -0.234297 0.338716 0 0.949356 0.314203 0 0.949356 0.314203 0 -0.929215 0.369539 0 -0.929215 0.369539 -0.244166 0.920622 0.304693 -0.24417 0.920622 0.30469 -0.667085 0.676557 0.311877 -0.667078 0.67656 0.311886 -0.91125 0.253828 0.324337 -0.911248 0.25383 0.32434 -0.244169 -0.90109 0.358354 -0.911249 -0.234296 0.338719 -0.911249 -0.234299 0.338716 -0.74625 -0.562379 0.356148 -0.683027 -0.675115 0.278735 -0.572626 -0.735931 0.361255 -0.244169 -0.90109 0.358354 -0.939691 0.0100705 0.341877 -0.939691 0.0100705 0.341877 0 -0.241537 -0.970392 0 -0.241537 -0.970392 0 -0.623294 -0.781987 0 -0.623294 -0.781987 0 0.576184 -0.81732 0 0.576184 -0.81732 0 0.183998 -0.982927 0 0.183998 -0.982927 0 -0.346924 0.937893 -0.0153917 -0.331523 0.943322 0.0142497 0.0799553 0.996697 -0.0284881 0.128628 0.991284 0.0262029 0.491836 0.870293 -0.0392756 0.560939 0.826925 0.0358399 0.812155 0.58234 0 0.840239 0.542217 0 0.942896 0.333086 0.0431582 0.981517 0.186447 0 0.992518 0.122095 0 -0.998977 -0.0452181 0.0511095 -0.992415 0.111802 0 -0.982591 0.185782 0 -0.919479 0.393138 0.0447597 -0.837591 0.544462 0 -0.804391 0.5941 0 -0.657488 0.753465 0.0364694 -0.505354 0.862141 -0.0243261 -0.439776 0.897778 0.0262402 -0.0658948 0.997482 -0.0131231 -0.0211505 0.99969 0.0140803 0.387768 0.92165 0 0.401532 0.915845 -0.705184 0.702653 -0.0948433 -0.70518 0.702657 -0.0948437 -0.70518 0.667583 -0.238861 -0.705186 0.667577 -0.23886 -0.705185 0.603327 -0.372437 -0.705183 0.60333 -0.372438 -0.705183 0.512711 -0.48974 -0.705173 0.512718 -0.489746 -0.705173 0.39969 -0.585644 -0.705183 0.399684 -0.585636 -0.705181 0.269191 -0.655939 -0.705185 0.269189 -0.655936 -0.705184 0.12693 -0.69757 -0.705183 0.126931 -0.697571 -0.705182 -0.0208764 -0.708719 -0.705185 -0.0208764 -0.708716 -0.705186 -0.16777 -0.688888 -0.705183 -0.167771 -0.688891 -0.705182 -0.307333 -0.638956 -0.705181 -0.307334 -0.638957 -0.70518 -0.433465 -0.561097 -0.705181 -0.433465 -0.561096 -0.705179 -0.540652 -0.458713 -0.705182 -0.54065 -0.458711 -0.705182 -0.624207 -0.33628 -0.705187 -0.624203 -0.336278 -0.705187 -0.680478 -0.19915 -0.70518 -0.680484 -0.199152 -0.70518 -0.70702 -0.0533194 -0.705184 -0.707017 -0.053319 -0.830791 0.490002 0.263979 -0.980668 0.195478 0.00887127 -0.98067 0.191962 0.0379046 -0.980668 -0.194617 0.0203622 -0.98067 0.172262 0.0928034 -0.980667 0.172274 0.0928091 -0.980667 0.156517 0.117448 -0.554467 0.783294 0.281098 -0.830791 0.523873 0.188 -0.830799 0.523862 0.187996 -0.98067 0.184169 0.0660921 -0.980668 0.184178 0.0660953 -0.554438 -0.765408 0.326724 -0.195067 -0.785041 0.587929 -0.194562 -0.834667 0.515245 -0.55443 -0.708168 0.437156 -0.554431 -0.765413 0.326726 -0.830795 -0.511892 0.218507 -0.980668 -0.179966 0.0768209 -0.980668 -0.166507 0.102786 -0.830794 -0.473609 0.292361 -0.830795 -0.424745 0.359684 -0.554425 -0.635106 0.537823 -0.554426 -0.547854 0.626472 -0.980668 -0.14933 0.126456 -0.980668 -0.128814 0.147299 -0.830791 -0.366397 0.418975 -0.830789 -0.29986 0.468906 -0.554425 -0.448364 0.701129 -0.55442 -0.33886 0.760126 -0.194609 -0.399383 0.895891 -0.195048 -0.303523 0.932647 -0.980669 -0.105419 0.164848 -0.980669 -0.0796716 0.178718 -0.830782 -0.226629 0.508371 -0.830782 -0.148329 0.53647 -0.554418 -0.221784 0.802142 -0.55442 -0.0997539 0.826237 -0.980669 -0.079673 0.178722 -0.980669 -0.0521459 0.188599 -0.8308 -0.148322 0.536444 -0.8308 -0.066712 0.552558 -0.55444 -0.0997525 0.826224 -0.554438 0.0245037 0.831864 -0.194597 0.0288807 0.980458 -0.195096 0.11664 0.973824 -0.980668 -0.0234546 0.194268 -0.980668 0.00576155 0.195592 -0.83078 0.0163887 0.55636 -0.830779 0.0991269 0.547704 -0.554434 0.148214 0.818923 -0.554431 0.268613 0.787688 -0.980669 0.0348481 0.192546 -0.980669 0.063156 0.185201 -0.830793 0.179644 0.526793 -0.830793 0.256152 0.494135 -0.554449 0.383007 0.738845 -0.554452 0.488846 0.673508 -0.194545 0.57618 0.793832 -0.19498 0.655944 0.729191 -0.980669 0.0900533 0.173719 -0.980669 0.114939 0.158357 -0.830791 0.32694 0.450441 -0.830791 0.390422 0.396681 -0.55443 0.583778 0.593136 -0.554428 0.665661 0.499505 -0.980668 0.114943 0.158363 -0.980667 0.137264 0.139464 -0.830778 0.390437 0.396695 -0.830777 0.445201 0.334074 -0.554425 0.665663 0.499506 -0.554422 0.732677 0.394716 -0.194553 0.86355 0.465221 -0.195056 0.901682 0.385904 -0.980669 -0.194612 0.0203617 -0.830793 -0.55356 0.0579173 -0.830788 -0.553568 0.0579183 -0.554441 -0.827705 0.0866005 -0.554441 -0.827705 0.0866005 -0.194561 -0.975565 0.102071 -0.19458 -0.975562 0.10207 -0.980668 -0.189408 0.0491409 -0.830796 -0.538741 0.139773 -0.830793 -0.538745 0.139774 -0.554437 -0.805556 0.208997 -0.554441 -0.805553 0.208996 0.78006 -0.605653 0.157133 -0.195002 -0.959466 0.203468 -0.1946 -0.834661 0.51524 -0.195108 -0.877396 0.438302 0.607511 -0.730539 0.311839 -0.194766 -0.90776 0.371535 -0.194913 -0.941595 0.274605 -0.980668 -0.189407 0.0491405 -0.980668 -0.179967 0.0768212 -0.83079 -0.511899 0.218511 -0.830791 -0.473614 0.292364 -0.554456 -0.708153 0.437147 -0.554457 -0.63509 0.537808 0.607533 -0.606154 0.513304 -0.194593 -0.52845 0.826362 -0.195031 -0.611879 0.76653 0.780058 -0.411899 0.471007 -0.194919 -0.667466 0.718676 -0.194774 -0.738953 0.644989 -0.980668 -0.166509 0.102787 -0.980668 -0.14933 0.126456 -0.830797 -0.424742 0.359682 -0.830796 -0.366392 0.418969 -0.554446 -0.547846 0.626462 -0.554447 -0.448356 0.701117 -0.194574 -0.528451 0.826366 -0.19458 -0.399385 0.895896 -0.980668 -0.128814 0.147299 -0.980668 -0.105421 0.164853 -0.830797 -0.299854 0.468897 -0.830797 -0.22662 0.50835 -0.554439 -0.338855 0.760115 -0.554439 -0.221781 0.802129 0.78006 -0.166745 0.603077 -0.194553 0.0288815 0.980467 -0.19506 -0.0591161 0.979008 0.607545 -0.0952049 0.788559 -0.194755 -0.132122 0.971913 -0.194903 -0.232983 0.952749 -0.980668 -0.0521462 0.1886 -0.980668 -0.0234543 0.194266 -0.830801 -0.066712 0.552557 -0.8308 0.0163873 0.55633 -0.554447 0.0245034 0.831859 -0.554451 0.148212 0.818912 0.607522 0.141459 0.781605 -0.194585 0.451426 0.870833 -0.195028 0.357895 0.913168 0.78006 0.201954 0.592217 -0.19492 0.288659 0.93738 -0.194775 0.189101 0.962447 -0.980669 0.00576141 0.195589 -0.980669 0.034848 0.192545 -0.830789 0.099124 0.54769 -0.830789 0.179646 0.526798 -0.554462 0.268606 0.78767 -0.554466 0.383001 0.738835 -0.194542 0.451431 0.870841 -0.19454 0.576181 0.793832 -0.980667 0.063159 0.185209 -0.980668 0.0900574 0.173727 -0.830786 0.256157 0.494144 -0.830784 0.326946 0.450449 -0.554464 0.488841 0.673501 -0.554468 0.58376 0.593119 0.780066 0.438902 0.445939 -0.194538 0.863553 0.465222 -0.195041 0.81829 0.540704 0.607537 0.635314 0.476733 -0.19482 0.77563 0.60037 -0.194961 0.708606 0.678136 -0.980669 0.137257 0.139457 -0.980669 0.156509 0.117443 -0.830797 0.445178 0.334057 -0.830797 0.489993 0.263975 -0.554451 0.73266 0.394707 -0.554451 0.783305 0.281101 0.607564 0.74759 0.268284 -0.194725 0.928063 0.31746 -0.194962 0.969787 0.146639 -0.980668 0.191972 0.0379065 -0.830795 0.546035 0.107819 -0.830799 0.546029 0.107818 -0.554436 0.816462 0.161217 -0.554468 0.816441 0.161214 0.780078 0.613831 0.121207 -0.194871 0.956134 0.218707 -0.98067 0.195467 0.0088709 -0.830795 0.556006 0.0252333 -0.830795 0.556006 0.0252333 -0.554408 0.831389 0.0377311 -0.554436 0.83137 0.0377306 -0.194626 0.979869 0.0444701 -0.19452 0.97989 0.0444696 -0.510203 0.161643 0.844727 -0.373489 0.398337 0.837755 -0.136711 0.534981 0.83373 -0.136706 -0.484981 0.863773 -0.37349 -0.348334 0.859749 -0.510204 -0.11164 0.852777 -0.258825 0.965505 -0.0284409 -0.258814 0.965508 -0.0284402 -0.707099 0.706808 -0.0208198 -0.707105 0.706802 -0.0208203 -0.96593 0.258693 -0.00762031 -0.965929 0.258696 -0.00762019 -0.96593 -0.258693 0.0076201 -0.96593 -0.258693 0.0076201 -0.707099 -0.706808 0.0208198 -0.707099 -0.706808 0.0208198 -0.258814 -0.965508 0.0284402 -0.258825 -0.965505 0.0284409 -0.186154 0.714904 0.673987 -0.186151 0.714903 0.673989 -0.508586 0.528824 0.679475 -0.50859 0.528824 0.679472 -0.69475 0.206525 0.688963 -0.694749 0.206526 0.688964 -0.694747 -0.16561 0.699929 -0.69475 -0.165616 0.699924 -0.508586 -0.487921 0.709418 -0.508587 -0.487909 0.709425 -0.18616 -0.673985 0.714904 -0.186157 -0.67399 0.714901 -0.136706 0.534983 0.833729 -0.426413 0.315831 0.847599 -0.514173 0.0830997 0.853651 -0.483398 -0.164466 0.859812 -0.136709 -0.48498 0.863774 -0.340299 -0.370149 0.864399 -0.426412 -0.265392 0.86472 -0.514173 -0.0327074 0.857062 -0.483398 0.214792 0.848641 -0.340301 0.420385 0.841113 -0.22252 0.974505 -0.0287056 -0.258814 0.965573 -0.0261433 -0.623488 0.781435 -0.0249396 -0.652287 0.757643 -0.0223176 -0.826225 0.563095 -0.0165869 -0.900965 0.433602 -0.0158511 -0.930879 0.365169 -0.0107566 -0.993713 0.111906 -0.00329636 -0.999994 -0.000101948 -0.00346115 -0.993714 -0.111904 0.00329632 -0.930879 -0.365169 0.0107566 -0.900965 -0.433783 0.00969913 -0.826225 -0.563095 0.0165869 -0.623489 -0.781493 0.0230201 -0.652281 -0.757713 0.0200205 -0.222519 -0.974423 0.0313778 -0.25882 -0.965507 0.0284405 -0.15933 0.718325 0.677217 -0.159328 0.718324 0.677219 -0.446432 0.580122 0.681291 -0.44643 0.580122 0.681292 -0.645113 0.331088 0.688629 -0.645118 0.331085 0.688626 -0.716024 0.0205539 0.697773 -0.716024 0.020554 0.697773 -0.645117 -0.289982 0.706919 -0.645116 -0.289976 0.706923 -0.446432 -0.539013 0.714257 -0.446431 -0.539016 0.714256 -0.159331 -0.677216 0.718326 -0.159332 -0.677215 0.718327 -0.510203 0.161643 0.844727 -0.373489 0.398337 0.837755 -0.136706 0.534983 0.833729 -0.136711 -0.484979 0.863774 -0.37349 -0.348334 0.859749 -0.510203 -0.111641 0.852777 -0.258814 0.965508 -0.0284402 -0.258825 0.965505 -0.0284409 -0.707099 0.706808 -0.0208204 -0.707099 0.706808 -0.0208204 -0.96593 0.258693 -0.00762031 -0.96593 0.258693 -0.00762031 -0.96593 -0.258693 0.00762031 -0.965929 -0.258696 0.00762019 -0.707099 -0.706808 0.0208198 -0.707105 -0.706802 0.0208203 -0.258825 -0.965505 0.0284409 -0.258814 -0.965508 0.0284402 -0.186162 0.714903 0.673986 -0.186157 0.714901 0.67399 -0.508581 0.528828 0.679475 -0.508587 0.528827 0.679471 -0.694751 0.206522 0.688963 -0.694747 0.206525 0.688966 -0.694748 -0.165612 0.699927 -0.694749 -0.165614 0.699925 -0.508587 -0.487913 0.709422 -0.508587 -0.487915 0.709421 -0.186154 -0.673994 0.714898 -0.186157 -0.67399 0.7149 0.707111 -0.0208199 -0.706796 0.707111 -0.0208199 -0.706796 0.694752 -0.699921 -0.165624 0.69475 -0.699924 -0.165619 0.69475 -0.523344 -0.49339 0.694751 -0.523341 -0.493391 0.694751 -0.20653 -0.68896 0.694751 -0.20653 -0.68896 0.694751 0.165618 -0.699922 0.694751 0.165617 -0.699923 0.69475 0.493393 -0.52334 0.694751 0.493394 -0.523339 0.69475 0.688961 -0.206531 0.694749 0.688961 -0.206533 0.70711 -0.706797 0.0208196 0.707113 -0.706794 0.02082 0.707113 0.706794 -0.02082 0.70711 0.706797 -0.0208196 0.695276 -0.184698 0.694606 0.695275 -0.184697 0.694607 0.695276 -0.501618 0.514754 0.695275 -0.501617 0.514754 0.695275 -0.689601 0.202591 0.695274 -0.689601 0.202593 0.695277 0.700329 0.161647 0.695277 0.700329 0.161647 0.695277 0.531045 0.484336 0.695275 0.531048 0.484336 0.695275 0.225265 0.682531 0.695276 0.225263 0.68253 0.706919 0.0208254 0.706988 0.706919 0.0208256 0.706988 0.698673 -0.693792 0.174667 0.639687 -0.755255 0.142799 0.706481 -0.650745 0.278236 0.701816 -0.573015 0.423212 0.698659 0.287278 0.655245 0.698659 0.287278 0.655246 0.698659 -0.0151335 0.715295 0.698659 -0.0151337 0.715295 0.698659 -0.314733 0.64251 0.698658 -0.314734 0.64251 0.706756 -0.465145 0.533045 0.687539 -0.54162 0.483672 0.736836 -0.565428 0.370626 0.70515 0.475762 0.525751 0.70515 0.475762 0.525751 0.70662 0.551351 0.443508 0.755394 0.525084 0.392004 0.707038 0.588108 0.392717 0.706993 0.607939 0.361347 0.707065 0.607932 0.361218 0.70515 0.648985 0.285625 0.617251 0.712117 0.3345 0.707004 0.668135 0.231821 0.705149 0.694318 0.143831 0.581327 0.790929 0.191024 0.706922 0.701156 0.0929606 0.706382 0.707401 0.0246885 0.706495 0.707289 0.0246411 0.706743 0.705724 -0.0496812 0.706815 0.705649 -0.0497192 0.7067 0.698539 -0.112331 0.612039 0.772382 -0.169807 0.706955 0.535235 -0.462319 0.762731 0.519856 -0.384697 0.706537 0.683045 -0.18508 0.706928 0.6635 -0.24499 0.627535 0.708764 -0.322262 0.706168 0.634798 -0.313622 0.706854 0.595494 -0.381764 0.776011 0.503839 -0.379411 0.698868 0.131605 -0.703039 0.698868 0.131605 -0.703039 0.698868 0.412116 -0.584589 0.698868 0.412115 -0.584589 0.707112 -0.0208199 -0.706795 0.707111 -0.0208196 -0.706796 0.70022 0.118603 -0.704007 0.700219 0.118603 -0.704008 0.70022 0.378987 -0.60503 0.70022 0.378987 -0.60503 0.70022 0.581673 -0.413943 0.700219 0.581673 -0.413944 0.700219 0.695806 -0.159836 0.700219 0.695806 -0.159835 0.707111 0.706796 -0.0208203 0.707111 0.706796 -0.0208203 0.700219 0.704008 0.118604 0.700219 0.704008 0.118604 0.700219 0.605031 0.378987 0.70022 0.60503 0.378987 0.707111 0.514501 0.485059 0.707112 0.514501 0.485058 0.6972 0.39284 0.599658 0.6972 0.39284 0.599658 0.697199 0.0788245 0.712531 0.697199 0.0788244 0.712531 0.6972 -0.252269 0.671024 0.697199 -0.252269 0.671024 0.705521 -0.450656 0.546945 0.705522 -0.450656 0.546945 0.705522 -0.545557 0.452335 0.705522 -0.545557 0.452334 0.705522 -0.620952 0.341551 0.705523 -0.620952 0.341551 0.705523 -0.674145 0.218556 0.705523 -0.674145 0.218556 0.705522 -0.703234 0.0877464 0.705522 -0.703235 0.0877465 0.697199 0.29133 0.655012 0.6972 0.291329 0.655012 0.6972 -0.0367467 0.715935 0.697199 -0.0367464 0.715935 0.697199 -0.356862 0.621742 0.697201 -0.356862 0.62174 0.70711 -0.485059 0.514503 0.707112 -0.485057 0.514503 0.700218 -0.581674 0.413945 0.700219 -0.581675 0.413942 0.700219 -0.695805 0.159838 0.70022 -0.695805 0.159835 0.70711 -0.706797 0.0208189 0.707113 -0.706794 0.0208203 0.700218 -0.704009 -0.118601 0.70022 -0.704006 -0.118603 0.706354 -0.643799 -0.294256 0.723839 -0.584726 -0.366268 0.704066 -0.575872 -0.415527 0.704066 -0.448705 -0.550414 0.723841 -0.400049 -0.562153 0.706354 -0.331635 -0.625366 0.70022 -0.159837 -0.695805 0.70022 -0.159837 -0.695805 0.707111 -0.0208196 -0.706796 0.707112 -0.0208199 -0.706795 0.698869 -0.445811 -0.559317 0.698868 -0.445811 -0.559317 0.698868 -0.172759 -0.694073 0.698868 -0.172759 -0.694073 0.705442 -0.703109 0.0893755 0.593252 -0.801484 0.075337 0.706923 -0.694467 0.134071 0.705445 -0.672692 0.223232 0.625461 -0.746351 0.227505 0.707004 -0.653331 0.270747 0.705443 -0.617047 0.348716 0.654747 -0.664031 0.361067 0.707064 -0.585616 0.396377 0.787166 -0.453733 0.417729 0.708923 -0.561848 0.426328 0.707111 -0.578212 0.40702 0.705443 -0.439273 0.556227 0.705444 -0.439273 0.556227 0.707099 -0.494079 0.505862 0.681329 -0.559758 0.471659 0.30801 0.94623 -0.0988906 0.697318 -0.237653 0.676216 0.69732 -0.23765 0.676215 0.69732 0.0922342 0.710801 0.697319 0.0922331 0.710802 0.697318 0.402369 0.593166 0.69732 0.402369 0.593164 0.704547 0.577141 0.412943 0.720054 0.583057 0.376254 0.693541 0.672211 0.259102 0.706359 0.667432 0.235776 0.70301 0.705859 0.0868312 0.699627 0.450642 -0.554477 0.699623 0.450645 -0.554479 0.699803 0.632937 -0.331159 0.874977 0.397233 -0.276807 0.706238 0.187789 -0.682615 0.706239 0.187789 -0.682615 0.706238 0.281047 -0.649801 0.706235 0.281048 -0.649803 0.813682 -0.536039 -0.224907 0.95017 -0.300979 -0.0811732 0.991527 -0.125685 -0.0328364 0.856116 -0.497581 -0.139569 0.704236 -0.66925 -0.236972 0.698663 -0.554341 -0.4523 0.698661 -0.554343 -0.452302 0.698663 -0.312753 -0.643471 0.698671 -0.312752 -0.643464 0.698667 -0.0131761 -0.715326 0.698662 -0.0131747 -0.715331 0.704997 0.295077 0.644909 0.701657 0.165568 0.693011 0.705432 0.164879 0.689333 0.707097 0.234298 0.667172 0.775055 0.264558 0.573846 0.704177 0.299251 0.643882 0.704172 -0.260834 0.660385 0.705227 -0.260423 0.659421 0.773338 -0.229391 0.59104 0.701638 -0.124675 0.701541 0.705425 -0.123838 0.697883 0.707098 -0.194626 0.679804 0.759274 0.603939 -0.242405 0.856117 0.488499 -0.168617 0.950204 0.295581 -0.0987146 0.991523 0.123557 -0.0401853 0.698659 -0.0289538 -0.714868 0.698656 -0.028953 -0.714872 0.698657 0.274338 -0.66077 0.698657 0.274338 -0.66077 0.698656 0.526763 -0.484149 0.69866 0.526759 -0.484147 0.706229 0.635593 -0.311869 0.706236 -0.318809 -0.632133 0.706232 -0.31881 -0.632136 0.706232 -0.227645 -0.670383 0.706232 -0.227645 -0.670383 0.793259 -0.555182 -0.250028 0.706096 -0.603796 -0.369945 0.699628 -0.482499 -0.526987 0.699627 -0.482499 -0.526988 -0.707056 0.706851 -0.0208213 -0.707102 0.706805 -0.0208207 -0.707147 0.70676 -0.0208137 -0.707163 0.706744 -0.0208188 -0.695267 0.225267 0.682538 -0.69526 0.225268 0.682545 -0.695261 0.531056 0.484347 -0.695265 0.531054 0.484343 -0.695264 0.700341 0.16165 -0.695266 0.700339 0.161649 -0.706909 0.0208256 0.706998 -0.706912 0.0208259 0.706995 -0.695267 -0.689609 0.202594 -0.695267 -0.689608 0.202594 -0.695267 -0.501624 0.51476 -0.695264 -0.501626 0.514761 -0.695264 -0.184701 0.694618 -0.695268 -0.184699 0.694614 -0.707147 -0.70676 0.0208193 -0.707102 -0.706805 0.0208207 -0.707135 -0.706772 0.0208239 -0.707043 -0.706864 0.0208217 -0.707077 0.520135 0.479064 -0.7031 0.573279 0.420716 -0.692048 0.579709 0.430126 -0.702386 0.569829 0.426555 -0.707096 0.514513 0.485069 -0.7071 0.514509 0.485067 -0.697187 -0.252273 0.671035 -0.697191 -0.252271 0.671032 -0.697188 0.0788256 0.712542 -0.697187 0.0788256 0.712542 -0.69719 0.392845 0.599665 -0.697185 0.392847 0.59967 -0.705514 0.482074 0.519475 -0.705506 0.482079 0.519481 -0.705507 0.571249 0.419446 -0.705508 0.571248 0.419446 -0.705508 0.639993 0.304415 -0.705504 0.639996 0.304416 -0.705504 0.685858 0.1785 -0.705512 0.685851 0.178498 -0.705512 0.707191 0.0462012 -0.705513 0.707189 0.0462011 -0.697184 -0.356869 0.621755 -0.697182 -0.35687 0.621756 -0.697184 -0.0367475 0.71595 -0.697185 -0.0367474 0.715949 -0.697185 0.291335 0.655024 -0.697191 0.291334 0.655019 -0.7071 -0.485067 0.514509 -0.707096 -0.485069 0.514513 -0.707077 -0.490981 0.508901 -0.691159 -0.556464 0.461137 -0.702518 -0.543607 0.459304 -0.702393 -0.543725 0.459355 -0.851308 0.507854 -0.131757 -0.851307 -0.0154474 -0.524441 -0.851307 0.213626 -0.479208 -0.851308 0.40039 -0.339063 -0.851306 -0.51473 -0.101641 -0.851306 -0.419658 -0.314904 -0.851307 -0.241466 -0.465802 -0.851308 0.507854 -0.131758 -0.851307 -0.0154502 -0.524441 -0.851307 0.213629 -0.479207 -0.851307 0.40039 -0.339063 -0.851307 -0.514728 -0.101641 -0.851307 -0.419658 -0.314902 -0.851307 -0.241463 -0.465803 -0.849121 0.121624 -0.514006 -0.849121 0.362334 -0.384328 -0.849121 0.505955 -0.151669 -0.849122 -0.514003 -0.121626 -0.849121 -0.384326 -0.362335 -0.849121 -0.15167 -0.505955 -0.849121 0.121627 -0.514004 -0.849122 0.362335 -0.384326 -0.849121 0.505953 -0.151673 -0.849119 -0.514007 -0.121627 -0.84912 -0.384331 -0.362332 -0.849121 -0.151669 -0.505955 0 0.0294439 0.999566 2.39797e-07 0.0294438 0.999566 0 0.0294439 0.999566 0 0.0294438 0.999566 2.05792e-08 0.0294437 0.999566 1.33377e-07 0.0294436 0.999566 0 0.0294438 0.999566 0 0.0294438 0.999566 -5.54513e-08 0.0294439 0.999566 0 0.0294437 0.999566 2.63584e-08 0.0294435 0.999566 -1.50513e-07 0.029444 0.999566 -1.99007e-07 0.029444 0.999566 0 0.0294438 0.999566 2.14782e-07 0.0294436 0.999566 5.22196e-07 0.0294432 0.999566 -2.36036e-07 0.0294434 0.999566 0 0.0294439 0.999566 3.36274e-07 0.0294439 0.999566 -2.46166e-07 0.0294436 0.999566 0 0.0294438 0.999566 4.23812e-07 0.0294436 0.999566 0 0.0294438 0.999566 -2.20089e-08 0.0294437 0.999566 1.99007e-07 0.029444 0.999566 2.34419e-07 0.0294434 0.999566 0 0.0294438 0.999566 0 0.0294438 0.999566 -3.69946e-08 0.0294439 0.999566 1.32476e-08 0.0294438 0.999566 3.37305e-08 0.0294438 0.999566 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.991013 -0.133766 0 0.991013 -0.133766 0 0.941546 -0.336886 0 0.941546 -0.336886 0 0.850928 -0.525282 0 0.850928 -0.525282 0 0.723121 -0.690721 0 0.723121 -0.690721 0 0.56371 -0.825973 0 0.56371 -0.825973 0 0.379662 -0.925125 0 0.379662 -0.925125 0 0.179021 -0.983845 0 0.179021 -0.983845 0 -0.0294439 -0.999566 0 -0.0294439 -0.999566 0 -0.236622 -0.971602 0 -0.236622 -0.971602 0 -0.433459 -0.901173 0 -0.433459 -0.901173 0 -0.611351 -0.79136 0 -0.611351 -0.79136 0 -0.762525 -0.646959 0 -0.762525 -0.646959 0 -0.880372 -0.474284 0 -0.880372 -0.474284 0 -0.959743 -0.28088 0 -0.959743 -0.28088 0 -0.997168 -0.0752009 0 -0.997168 -0.0752009 0.939695 0.333951 0.0738182 0.939752 0.333816 0.0737114 0.940167 0.33229 0.075296 0.942367 0.325459 0.0775922 0.951831 0.295299 0.0825632 0.948243 0.305462 0.0867673 0.939565 0.333881 0.07577 0.939511 0.331788 0.0850634 0.941634 0.319688 0.105478 0.939358 0.326262 0.105641 0.939221 0.332905 0.0839004 0.9388 0.334364 0.0827995 0.938169 0.336402 0.0816892 0.938422 0.335894 0.0808648 0.939136 0.334555 0.0780828 0.9438 0.325819 0.0555253 0.939539 0.337602 0.0573722 0.941897 0.331533 0.0539941 0.938576 0.340066 0.0585706 0.940247 0.339353 0.0278549 0.934408 0.352108 0.0538634 0.947249 0.317082 0.0466623 0.944875 0.323834 0.048394 0.938495 0.341045 0.0539906 0.943048 0.328508 0.0523748 0.940997 0.334098 0.0538728 0.941703 0.332158 0.0535301 0.941424 0.332903 0.0538227 0.939849 -0.336271 0.0600524 0.93969 -0.336287 0.0624034 0.940065 -0.335234 0.0624114 0.940187 -0.3349 0.0623822 0.939549 -0.338674 0.0504822 0.940214 -0.335655 0.0577336 0.940417 -0.335151 0.0573487 0.940015 -0.336023 0.0588243 0.939579 -0.341359 0.0257962 0.985127 -0.171133 0.0154201 0.948572 -0.313808 0.0416675 0.940592 -0.336279 0.046926 0.94455 0.315427 0.0912754 0.941846 0.322386 0.0948359 0.905055 0.398842 0.147653 0.939477 0.325913 0.105661 0.939609 0.313201 0.137984 0.941652 0.31018 0.130688 0.93623 0.309136 0.16706 0.939508 0.30394 0.157937 0.939673 0.290573 0.180505 0.939456 0.290457 0.181816 0.940163 0.274285 0.202144 0.939281 0.275287 0.204863 0.939753 0.257595 0.224743 0.939319 0.259207 0.224704 0.940331 0.255809 0.224364 0.949924 0.224267 0.217596 0.957628 0.20956 0.197567 0.944763 0.243796 0.219058 0.94156 0.252205 0.223288 0.940044 0.233005 0.24905 0.938054 0.23863 0.251218 0.935465 0.245193 0.25453 0.933473 0.249794 0.257353 0.938023 0.249505 0.240543 0.939346 0.250128 0.23466 0.940781 0.254912 0.223498 0.937145 0.25945 0.233333 0.938612 0.258108 0.228885 0.942683 0.236218 0.23569 0.940836 0.238576 0.240641 0.929365 0.24705 0.274311 0.939594 0.234387 0.249452 0.939608 0.213268 0.267681 0.941844 0.214021 0.259085 0.935831 0.196754 0.292419 0.939501 0.196223 0.280776 0.939672 0.173477 0.294824 0.939547 0.173074 0.29546 0.939886 0.14926 0.307142 0.939313 0.149042 0.308994 0.938798 0.0875343 0.333162 0.939717 0.084737 0.331288 0.937528 0.0905223 0.335927 0.934186 0.0966125 0.343456 0.927833 0.106261 0.357539 0.933932 0.106906 0.34109 0.937524 0.108108 0.330697 0.946744 0.116243 0.300272 0.937483 0.116766 0.327859 0.939734 0.117339 0.321142 0.939343 0.118164 0.321982 0.94131 0.114565 0.317506 0.944041 0.110331 0.310827 0.951587 0.0999056 0.29069 0.951129 0.100508 0.291981 0.940793 0.0955387 0.325241 0.935846 0.0872141 0.341447 0.942353 0.0863479 0.323288 0.939661 -0.0843833 0.331537 0.939691 -0.0853413 0.331206 0.939513 -0.0828959 0.332332 0.938947 -0.0807736 0.334446 0.932627 -0.0691114 0.354161 0.926746 -0.0749618 0.368133 0.934979 -0.0658451 0.348537 0.956713 -0.0325995 0.289201 0.936658 -0.0558938 0.345758 0.939638 -0.0520956 0.338182 0.939348 -0.011036 0.342788 0.939592 -0.0105984 0.342132 0.93964 0.0165166 0.341765 0.939672 0.0166784 0.341671 0.939492 0.0438489 0.339752 0.935414 0.0385284 0.351449 0.942037 0.0695542 0.328222 0.939607 0.0645248 0.336117 0.939666 0.0849208 0.331384 0.940698 0.0858654 0.328198 0.939619 -0.0520886 0.338235 0.942608 -0.052574 0.329736 0.936933 -0.0528511 0.34549 0.93988 -0.0744735 0.333286 0.940792 -0.0762283 0.330302 0.942378 -0.0772468 0.32551 0.940659 -0.0805825 0.329647 0.939871 -0.0832211 0.331236 0.939717 -0.084643 0.331311 0.939692 -0.0853957 0.331189 0.939606 -0.098989 0.32763 0.942231 -0.0902433 0.32258 0.934979 -0.12955 0.330197 0.939484 -0.118521 0.321438 0.939671 -0.14394 0.310321 0.939736 -0.14356 0.310302 0.939282 -0.1688 0.298759 0.917995 -0.299768 0.259662 0.938622 -0.255424 0.231836 0.935384 -0.260172 0.239515 0.94028 -0.252308 0.228505 0.939652 -0.237587 0.246183 0.939514 -0.236872 0.247396 0.939211 -0.236276 0.249111 0.938773 -0.235954 0.25106 0.938971 -0.235149 0.251074 0.939382 -0.233131 0.251419 0.939577 -0.231803 0.251916 0.939683 -0.23062 0.252606 0.939695 -0.229636 0.253459 0.939384 -0.168513 0.298597 0.939704 -0.191364 0.283438 0.942105 -0.198936 0.269931 0.936601 -0.218778 0.273705 0.939669 -0.224555 0.258063 0.939692 -0.230025 0.253114 0.939699 -0.230501 0.252657 0.939912 -0.231364 0.251071 0.941038 -0.231193 0.246976 0.946917 -0.225287 0.229335 0.944764 -0.230477 0.233027 0.941559 -0.238627 0.237747 0.941583 -0.249017 0.226744 0.939486 -0.254258 0.229608 0.939671 -0.271616 0.207951 0.939833 -0.270752 0.208346 0.938954 -0.289058 0.186579 0.939423 -0.287567 0.186519 0.93969 -0.300919 0.162574 0.941987 -0.301889 0.146707 0.936524 -0.320863 0.141316 0.93967 -0.31873 0.124225 0.936025 -0.342605 0.0804901 0.93873 -0.335186 0.0802285 0.939601 -0.333162 0.0784449 0.94066 -0.330064 0.0788511 0.942921 -0.323518 0.0789721 0.936498 -0.33651 0.098655 0.930024 -0.355678 0.0924603 0.932281 -0.350413 0.0897952 0.936604 -0.340212 0.0838356 0.9382 -0.331102 0.100761 0.938934 -0.32861 0.102068 0.941863 -0.317342 0.110402 0.93742 -0.330787 0.108737 0.938616 -0.327118 0.109514 0.939669 -0.323573 0.111012 0.939631 -0.32364 0.111132 0.940736 -0.321374 0.108325 0.942121 -0.318142 0.105798 0.944102 -0.313261 0.102656 0.947181 -0.305293 0.0982058 0.94237 -0.32032 0.0966136 0.940168 -0.327278 0.0947225 0 -0.981427 -0.191837 -0.0572597 -0.976443 -0.208038 0 -0.962086 -0.272748 0 -0.93719 -0.348819 -0.0646911 -0.928065 -0.366756 0 -0.904954 -0.42551 0 -0.868024 -0.496523 -0.071103 -0.854111 -0.515208 0 -0.82375 -0.566954 0 -0.775767 -0.631019 -0.0764985 -0.756656 -0.649322 0 -0.720633 -0.693317 0 -0.662875 -0.74873 -0.0808796 -0.638412 -0.765433 0 -0.598348 -0.801236 0 -0.53235 -0.846524 -0.0842485 -0.502648 -0.860376 0 -0.460147 -0.887843 0 -0.387664 -0.921801 -0.0866083 -0.353099 -0.931569 0 -0.309706 -0.950832 0 -0.232667 -0.972556 -0.0879637 -0.193872 -0.977075 0 -0.151025 -0.98853 0 -0.0294434 -0.999566 -0.17249 0.0114975 -0.984944 0 -0.0714802 -0.997442 0 0.298776 -0.954323 -0.146683 0.328226 -0.933141 0 0.252259 -0.96766 0 0.136552 -0.990633 -0.159629 0.171826 -0.972108 0 0.0916068 -0.995795 0 0.594197 -0.80432 -0.120569 0.612388 -0.781309 0 0.549336 -0.835602 0 0.452742 -0.891642 -0.133663 0.476432 -0.868992 0 0.406199 -0.913785 0 0.82439 -0.566022 -0.0941976 0.833039 -0.545136 0 0.788351 -0.615226 0 0.719232 -0.69477 -0.107412 0.732359 -0.672393 0 0.677859 -0.735192 0 0.964086 -0.265589 -0.0676256 0.965974 -0.249642 0 0.944042 -0.329827 0 0.906768 -0.421631 -0.0809329 0.91164 -0.402943 0 0.877873 -0.478894 0 0.98124 0.192792 -0.0547583 0.97658 0.208068 0 0.961819 0.273686 0 0.93685 0.349731 -0.0625053 0.928195 0.366807 0 0.904539 0.426392 0 0.86754 0.497368 -0.069229 0.854224 0.515275 0 0.823199 0.567754 0 0.775152 0.631775 -0.074938 0.756746 0.649399 0 0.719959 0.694016 0 0.662146 0.749375 -0.0796338 0.638476 0.765511 0 0.597568 0.801818 0 0.531526 0.847042 -0.0833157 0.502687 0.860444 0 0.459282 0.88829 0 0.386768 0.922177 -0.085989 0.353118 0.931619 0 0.308779 0.951134 0 0.231721 0.972782 -0.0876545 0.193877 0.977102 0 0.150062 0.988677 0 0.0705105 0.997511 -0.0883122 0.029329 0.995661 0 -0.0126457 0.99992 0 -0.298775 0.954323 -0.150693 -0.328934 0.932252 0 -0.253199 0.967414 0 -0.136553 0.990633 -0.163611 -0.172659 0.971298 0 -0.0925766 0.995706 0 -0.594197 0.80432 -0.124622 -0.612839 0.780319 0 -0.550148 0.835067 0 -0.452742 0.891642 -0.137694 -0.477012 0.868044 0 -0.407089 0.913389 0 -0.82439 0.566022 -0.0982853 -0.833238 0.544109 0 -0.78895 0.614458 0 -0.719231 0.694771 -0.111483 -0.732683 0.671377 0 -0.678574 0.734532 0 -0.964086 0.265589 -0.0717386 -0.965938 0.248631 0 -0.944363 0.328905 0 -0.906767 0.421631 -0.0850351 -0.911718 0.401919 0 -0.878338 0.478039 0.42266 0.891871 -0.161009 0.427253 0.888635 -0.166681 0.422569 0.891246 -0.164669 0.444713 0.867182 -0.224111 0.421781 -0.9001 -0.109178 0.42744 -0.896807 -0.114162 0.424201 -0.898502 -0.112908 0.423091 -0.899431 -0.109623 0.422435 -0.900135 -0.106325 0.227017 0.635996 -0.737545 0.422536 0.535093 -0.731531 0.422475 0.497904 -0.757368 0.503855 0.452274 -0.73592 0.354685 0.449491 -0.819852 0.422545 0.411276 -0.807656 0.422447 0.368174 -0.828243 0.504661 0.328644 -0.798317 0.362304 0.309272 -0.879254 0.422541 0.276891 -0.863012 0.422405 0.22865 -0.877094 0.503954 0.196904 -0.840987 0.369596 0.161734 -0.915009 0.422548 0.135376 -0.896173 0.422369 0.0830346 -0.902613 0.501736 0.0600324 -0.862935 0.376586 0.0108131 -0.926319 0.422548 -0.00961192 -0.90629 0.422323 -0.0647929 -0.904127 0.497986 -0.0788743 -0.863591 0.383268 -0.139492 -0.913043 0.422557 -0.154358 -0.893095 0.422282 -0.210905 -0.881588 0.492668 -0.216657 -0.842815 0.389652 -0.285228 -0.875681 0.422557 -0.295131 -0.856938 0.422229 -0.351414 -0.835602 0.485729 -0.350152 -0.800912 0.395741 -0.422582 -0.815361 0.422558 -0.428315 -0.798744 0.422174 -0.482584 -0.767387 0.477113 -0.476238 -0.73862 0.401545 -0.547991 -0.733804 0.422563 -0.550483 -0.720006 0.42212 -0.600923 -0.678754 0.46674 -0.591897 -0.657124 0.407064 -0.658226 -0.633275 0.422565 -0.658496 -0.622754 0.422058 -0.703286 -0.572062 0.454525 -0.694267 -0.558033 0.412312 -0.750471 -0.516519 0.422566 -0.749573 -0.509488 0.421993 -0.786949 -0.450147 0.440356 -0.780704 -0.443382 0.417287 -0.822399 -0.386693 0.422569 -0.821374 -0.383119 0.421926 -0.849685 -0.31625 0.424116 -0.848836 -0.3156 0.421997 -0.872224 -0.247272 0.422572 -0.872052 -0.246898 0.421855 -0.889824 -0.173931 0.405676 -0.896618 -0.177491 0.423538 -0.89878 -0.113178 0.594072 0.496232 -0.633113 0.422508 0.614384 -0.666348 0.422536 0.645146 -0.636592 0.222931 0.746434 -0.627007 0.575948 0.602178 -0.552871 0.422533 0.71452 -0.557609 0.422532 0.738609 -0.525284 0.218821 0.837861 -0.500106 0.556933 0.694976 -0.454789 0.422557 0.795648 -0.434039 0.422531 0.813079 -0.400464 0.320933 0.866257 -0.382884 0.485208 0.812802 -0.322375 0.422573 0.855612 -0.298931 0.422525 0.866639 -0.265348 0.256058 0.940585 -0.22301 0.406249 0.890178 -0.206265 0.397677 0.901265 0.17197 0.466205 0.868382 0.169011 0.531469 0.831186 0.16331 0.427302 0.896879 0.11411 0.42018 -0.892096 0.166172 0.423901 -0.8906 0.164741 0.423036 -0.891472 0.16223 0.422462 -0.892317 0.159048 0.406065 0.900857 0.153522 0.264924 0.949197 0.169825 0.422522 0.880757 0.213876 0.42257 0.871726 0.24805 0.485206 0.83037 0.273973 0.320929 0.887294 0.331232 0.422529 0.835241 0.351911 0.422556 0.819817 0.386455 0.492256 0.772395 0.401361 0.329876 0.818978 0.469527 0.422529 0.76825 0.480896 0.42253 0.746105 0.514583 0.497683 0.695827 0.517819 0.338477 0.729399 0.594484 0.422536 0.681498 0.597515 0.422507 0.652542 0.629028 0.501538 0.602559 0.620791 0.346748 0.621065 0.702882 0.422539 0.577224 0.698766 0.422478 0.54162 0.726747 0.503855 0.494808 0.708023 0.354685 0.496969 0.791972 0.422542 0.458105 0.782047 0.422444 0.416288 0.805137 0.504658 0.375066 0.77759 0.362301 0.360491 0.859526 0.422547 0.327206 0.845216 0.422551 0.187892 0.88665 0.421999 0.258277 0.869028 0.555078 0.256842 0.791151 0.369596 0.215314 0.903902 0.42255 0.0437501 0.905283 0.421992 0.116045 0.899142 0.542887 0.126023 0.830296 0.376585 0.0653197 0.924076 0.421979 -0.029173 0.906136 0.530153 -0.0107223 0.847834 0.341356 -0.105285 0.934019 0.422356 -0.0839142 0.902538 0.421971 -0.173642 0.889825 0.516858 -0.149828 0.842858 0.359133 -0.251438 0.898778 0.422395 -0.229503 0.876876 0.421961 -0.313647 0.850632 0.502981 -0.287581 0.81505 0.374662 -0.389301 0.841471 0.422435 -0.368982 0.827889 0.421955 -0.445586 0.789561 0.488497 -0.420227 0.764709 0.388051 -0.515712 0.763844 0.422469 -0.498642 0.756886 0.421946 -0.566069 0.708186 0.47339 -0.544062 0.692747 0.399401 -0.627849 0.668045 0.422497 -0.615036 0.665753 0.421935 -0.671996 0.608599 0.457639 -0.655543 0.600692 0.408794 -0.723272 0.556565 0.422524 -0.715066 0.556915 0.421926 -0.760641 0.493359 0.441221 -0.751385 0.490658 0.416301 -0.799947 0.432179 0.422549 -0.796073 0.433266 0.421918 -0.829726 0.365431 0.424121 -0.828659 0.365303 0.421983 -0.856266 0.297891 0.422569 -0.855905 0.298097 0.421909 -0.877474 0.228104 0.406322 -0.884887 0.227768 0.423779 -0.890616 0.164968 0.424937 -0.88974 0.166707 0.424619 -0.889994 0.166159 -0.705894 0.68288 -0.188122 -0.705891 0.682882 -0.188122 -0.705891 0.642282 -0.29865 -0.705893 0.64228 -0.298649 -0.705892 0.583931 -0.400924 -0.705889 0.583934 -0.400926 -0.70589 0.509447 -0.492121 -0.705894 0.509444 -0.492118 -0.705894 0.42088 -0.569714 -0.705895 0.42088 -0.569713 -0.705894 0.320685 -0.631565 -0.705888 0.320688 -0.631571 -0.705888 0.21163 -0.675969 -0.7059 0.211626 -0.675958 -0.7059 0.0967215 -0.701677 -0.705889 0.0967234 -0.701687 -0.705891 -0.0208554 -0.708014 -0.705891 -0.0208554 -0.708013 -0.705891 -0.137858 -0.694776 -0.705898 -0.137857 -0.694769 -0.705898 -0.251048 -0.662331 -0.705893 -0.25105 -0.662336 -0.705893 -0.357305 -0.611595 -0.705893 -0.357305 -0.611595 -0.705893 -0.453686 -0.543953 -0.705891 -0.453687 -0.543954 -0.705891 -0.53753 -0.46128 -0.705892 -0.537529 -0.461279 -0.705892 -0.606518 -0.365857 -0.705892 -0.606519 -0.365858 -0.705892 -0.658747 -0.260326 -0.705891 -0.658747 -0.260326 -0.705891 -0.692771 -0.1476 -0.705892 -0.692771 -0.1476 -0.705892 -0.682881 0.188122 -0.705891 -0.682882 0.188122 -0.705891 -0.642282 0.29865 -0.705894 -0.64228 0.298649 -0.705894 -0.58393 0.400923 -0.705894 -0.58393 0.400923 -0.705894 -0.509444 0.492118 -0.705893 -0.509445 0.492119 -0.705893 -0.420881 0.569715 -0.705891 -0.420882 0.569716 -0.70589 -0.320687 0.631569 -0.705891 -0.320686 0.631568 -0.705891 -0.211629 0.675967 -0.70589 -0.211629 0.675968 -0.705891 -0.0967232 0.701686 -0.705891 -0.0967232 0.701686 -0.705891 0.0208558 0.708014 -0.705891 0.0208558 0.708013 -0.705892 0.137858 0.694775 -0.705888 0.137858 0.694778 -0.705888 0.251052 0.662341 -0.705891 0.251051 0.662338 -0.705891 0.357306 0.611597 -0.705889 0.357307 0.611598 -0.70589 0.453688 0.543956 -0.705896 0.453684 0.543951 -0.705896 0.537526 0.461277 -0.70589 0.537531 0.461281 -0.705889 0.606521 0.365859 -0.705894 0.606517 0.365856 -0.705894 0.658745 0.260325 -0.705894 0.658745 0.260325 -0.705894 0.692768 0.1476 -0.705904 0.692758 0.147597 0 0.47335 -0.880875 0.00132326 -0.995838 -0.0911341 0.00783465 -0.998298 -0.0577844 0 -0.999942 -0.010788 0 -0.990453 -0.13785 0 -0.984106 -0.17758 0.00745222 -0.973101 -0.23026 0.0030284 -0.96836 -0.24954 0 -0.953537 -0.301275 0 -0.940646 -0.339388 0.00737778 -0.915835 -0.401486 0.00564316 -0.918344 -0.395744 0 -0.889855 -0.456243 0 -0.870782 -0.491669 0.00554047 -0.835672 -0.5492 0.00758294 -0.83966 -0.54306 0 -0.801194 -0.598404 0 -0.776474 -0.630149 0.00288238 -0.7418 -0.670615 0.00749551 -0.7276 -0.685961 0 -0.690044 -0.723767 0 -0.660371 -0.750939 0.00210069 -0.597445 -0.801907 0.0136595 -0.624691 -0.780753 8.89754e-05 -0.55996 -0.82852 -8.67436e-05 -0.491547 -0.870851 0.0131336 -0.419916 -0.907468 0.00242228 -0.449119 -0.893469 0.00317663 -0.269088 -0.96311 0.0074066 -0.28714 -0.95786 0 -0.338761 -0.940873 0 -0.376332 -0.926485 0 -0.216372 -0.976311 0 -0.176922 -0.984225 0.00661198 -0.116447 -0.993175 0.00529308 -0.111271 -0.993776 0 -0.050336 -0.998732 0 -0.0101198 -0.999949 0.00476623 0.0494221 -0.998767 0.0068313 0.0577853 -0.998306 0.0106684 0.208827 -0.977895 0.00387682 0.230264 -0.97312 0 0.156967 -0.987604 0 0.117114 -0.993119 0 0.281274 -0.959628 0 0.31965 -0.947536 0.00193637 0.395749 -0.918357 0.0139258 0.362823 -0.931754 0.000180291 0.43659 -0.89966 0 0.508406 -0.861117 0.012874 0.575072 -0.818001 0.00257961 0.549207 -0.835682 0.00332716 0.69878 -0.715329 0.00735861 0.685961 -0.727601 0 0.645037 -0.764152 0 0.613777 -0.789479 0 0.736967 -0.675928 0 0.763562 -0.645735 0.00653446 0.801892 -0.597434 0.00547314 0.804374 -0.594098 0 0.839473 -0.543401 0 0.860652 -0.509193 0.00459541 0.889188 -0.45752 0.00689945 0.89345 -0.44911 0.0109075 0.950967 -0.3091 0.00373972 0.95788 -0.287145 0 0.933586 -0.358353 0 0.918413 -0.395623 0 0.971574 -0.236736 0 0.980307 -0.197478 0.00177028 0.993195 -0.11645 0.0141943 0.98817 -0.152703 0 0.997462 -0.0712054 0.201867 -0.975467 0.0878299 0.203413 0.367914 0.907338 0.575885 -0.628422 0.522916 0.575879 0.522919 0.628426 0.575876 0.808136 0.123625 0.852354 0.265212 0.450727 0.852351 -0.220055 0.474419 0.85197 -0.310632 0.42149 0.851971 -0.439908 0.283948 0.850692 -0.523532 0.0473011 0.904325 -0.417406 0.0892698 0.85235 -0.515403 0.0886507 0.851971 -0.521476 0.0469881 0.851971 -0.470927 0.228853 0.852349 -0.487272 0.189914 0.904555 -0.403141 0.138773 0.852209 -0.498066 0.160217 0.852207 -0.509337 0.119661 0.852212 -0.366648 0.373236 0.852205 -0.395472 0.342562 0.904088 -0.328494 0.273343 0.852351 -0.415244 0.317914 0.852213 -0.15132 0.500834 0.852202 -0.191097 0.487066 0.852345 -0.120755 0.508848 0.85197 -0.0791751 0.51757 0.851971 -0.0791747 0.517569 0.85197 -0.0162118 0.523339 0.851973 -0.0162114 0.523335 0.852355 0.0254978 0.522341 0.903597 0.0384443 0.426656 0.8522 0.0570172 0.5201 0.852216 0.0986361 0.513808 0.905207 0.0888779 0.415574 0.852344 0.129427 0.506713 0.85197 0.170421 0.49508 0.851973 0.170419 0.495074 0.851974 0.228851 0.470922 0.85197 0.380975 0.359173 0.852343 0.34999 0.38861 0.905413 0.271543 0.326331 0.852219 0.326013 0.409191 0.852199 0.292084 0.434101 0.852224 0.478773 0.210928 0.852199 0.460304 0.248752 0.851971 0.504251 0.140984 0.852343 0.490453 0.181568 0.868559 0.49481 0.0277006 0.851977 0.517558 0.0791729 0.851973 0.517565 0.0791745 0.852388 0.521157 0.0427778 0.880403 0.473804 0.0200185 0.575893 0.817133 0.0253122 0.575883 0.658114 0.48502 0.852354 0.44423 0.275956 0.85197 0.421491 0.310633 0.575888 0.658111 0.485018 0.575889 0.59485 0.560808 0.20306 0.712461 0.671689 0.203399 0.660919 0.722368 0.575888 -0.123623 0.808128 0.575883 -0.123624 0.808131 0.575883 -0.0253126 0.81714 0.575887 -0.0253123 0.817138 0.575887 0.0733672 0.814231 0.575882 0.0733672 0.814234 0.575882 0.170977 0.799454 0.57589 0.170977 0.799449 0.575889 0.266093 0.773011 0.575879 0.266095 0.773018 0.575885 -0.48502 0.658113 0.851973 -0.25756 0.455856 0.851973 -0.310629 0.421487 0.575887 -0.485019 0.658112 0.575887 -0.560809 0.594851 0.203057 -0.671689 0.712462 0.203395 -0.722369 0.660919 0.572874 -0.816348 0.0734258 0.575886 -0.814225 0.0734331 0.575884 -0.799452 0.170977 0.575886 -0.799451 0.170977 0.575886 -0.773013 0.266094 0.575885 -0.773014 0.266094 0.203053 0.978698 0.0303165 0.203044 0.9787 0.030317 0.20333 0.972275 0.115495 0.840792 0.541284 0.0089489 0.893229 0.449387 0.0139207 0.575889 0.817136 0.0253125 0.575889 0.808127 0.123622 -0.0764892 0.985605 0.150772 0.203304 0.963533 0.173988 0.203395 0.927426 0.313867 0.851977 0.504242 0.140981 0.575872 0.787345 0.220134 0.575876 0.787343 0.220133 0.0933424 0.958862 0.268088 0.203133 0.944736 0.257313 0.905612 0.3917 0.162596 0.57589 0.755059 0.313427 0.575873 0.75507 0.313433 0.203047 0.904349 0.3754 0.203044 0.90435 0.3754 0.903076 0.373924 0.211268 0.575882 0.711779 0.402157 0.57589 0.711775 0.402154 -0.0482498 0.869629 0.491342 0.203364 0.871152 0.446921 0.203052 0.712462 0.67169 0.203391 0.760021 0.617252 0.00853797 0.804971 0.593252 0.203199 0.795934 0.570263 0.203257 0.842597 0.498716 0.851968 0.421494 0.310635 0.851968 0.380978 0.359175 0.575886 0.594851 0.56081 0.575886 0.522916 0.628422 0.00853662 0.639606 0.768656 0.203202 0.616124 0.760987 0.203372 0.497424 0.843332 0.90334 0.232611 0.360373 0.575883 0.443357 0.686872 0.575879 0.443358 0.686875 -0.0482378 0.54168 0.8392 0.20326 0.547448 0.81178 0.851971 0.228853 0.470927 0.575878 0.357332 0.735308 0.575884 0.357331 0.735305 0.203062 0.427979 0.880682 0.203055 0.427979 0.880683 0.0792391 0.318126 0.944731 0.203056 0.318704 0.925849 0.203303 0.230403 0.951621 -0.0764871 0.208526 0.975021 0.203345 0.172524 0.963787 0.203059 0.0878724 0.975216 0.203061 0.0878725 0.975215 0.203061 -0.0303169 0.978697 0.203062 -0.0303169 0.978697 0.203346 -0.115494 0.972271 -0.0764881 -0.150773 0.985605 0.203305 -0.173989 0.963533 0.203412 -0.313869 0.927421 0.904996 -0.11455 0.409709 0.575884 -0.220131 0.787337 0.575887 -0.220131 0.787335 0.0933516 -0.268087 0.958861 0.203134 -0.257313 0.944736 0.903845 -0.164035 0.395166 0.575886 -0.313429 0.755061 0.575884 -0.313429 0.755063 0.203057 -0.375398 0.904347 0.20306 -0.375398 0.904347 0.85197 -0.257563 0.455861 0.575885 -0.402157 0.711777 0.575886 -0.402156 0.711776 -0.0482408 -0.491343 0.869629 0.203373 -0.446921 0.871149 0.203056 -0.67169 0.712462 0.203394 -0.617254 0.760019 0.0085288 -0.593252 0.804972 0.203192 -0.570263 0.795935 0.203249 -0.498717 0.842598 0.852347 -0.343298 0.394525 0.904778 -0.292148 0.309881 0.575886 -0.56081 0.594851 0.575886 -0.628422 0.522916 0.00853662 -0.768656 0.639606 0.203198 -0.760987 0.616124 0.203374 -0.843333 0.497423 0.851971 -0.439908 0.283948 0.575887 -0.68687 0.443355 0.575885 -0.686871 0.443356 -0.0482432 -0.8392 0.54168 0.203256 -0.81178 0.547449 0.851971 -0.470927 0.228853 0.575885 -0.735304 0.35733 0.575886 -0.735303 0.35733 0.203058 -0.880682 0.427979 0.203057 -0.880683 0.427979 0.203059 -0.975216 0.0878728 0.203344 -0.963788 0.172523 -0.0764889 -0.975021 0.208526 0.203305 -0.95162 0.230403 0.203059 -0.925848 0.318704 0.079237 -0.944731 0.318127 0.20341 -0.907339 0.367914 0.705757 -0.70727 -0.0409389 0.705757 -0.70727 -0.0409389 0.705757 -0.689416 -0.163133 0.705757 -0.689416 -0.163133 0.705757 -0.650615 -0.280371 0.705757 -0.650615 -0.280371 0.705757 -0.592044 -0.389089 0.705757 -0.592045 -0.389089 0.705757 -0.515486 -0.485986 0.705757 -0.515485 -0.485986 0.705757 -0.423264 -0.568115 0.705757 -0.423264 -0.568116 0.705757 -0.318181 -0.632984 0.705757 -0.318181 -0.632984 0.705757 -0.203431 -0.678619 0.705757 -0.203431 -0.678618 0.705757 -0.0824994 -0.703634 0.705757 -0.0824993 -0.703634 0.705757 0.0409392 -0.70727 0.705757 0.0409389 -0.707271 0.705756 0.163133 -0.689417 0.705757 0.163133 -0.689416 0.705757 0.280371 -0.650615 0.705757 0.280371 -0.650615 0.705757 0.389089 -0.592044 0.705756 0.389089 -0.592045 0.705756 0.485986 -0.515486 0.705757 0.485985 -0.515485 0.705757 0.568115 -0.423263 0.705756 0.568116 -0.423264 0.705756 0.632984 -0.318182 0.705757 0.632984 -0.318181 0.705757 0.678619 -0.20343 0.705756 0.678619 -0.20343 0.705757 0.703635 -0.0824995 0.705755 0.703636 -0.0825 0.705158 0.399698 -0.585656 0.705156 0.3997 -0.585658 0.705156 0.512731 -0.489758 0.705157 0.51273 -0.489757 0.705157 0.603352 -0.372452 0.705157 0.603352 -0.372452 0.705157 0.667604 -0.238869 0.705157 0.667604 -0.238869 0.705157 0.702679 -0.0948468 0.705156 0.70268 -0.0948468 0.705157 0.126935 -0.697596 0.705155 0.126936 -0.697599 0.705155 0.269201 -0.655963 0.759497 0.241052 -0.604201 0.707086 0.329248 -0.6258 0.714703 -0.0205939 -0.699125 0.714702 -0.0205938 -0.699126 0.707101 0.0520635 -0.705193 0.755265 -0.284097 -0.590646 0.705504 -0.300907 -0.641653 0.705156 -0.167777 -0.688917 0.705157 -0.167777 -0.688915 0.707102 -0.0934884 -0.700904 0.705157 -0.707043 -0.0533212 0.705157 -0.707043 -0.0533212 0.705157 -0.680506 -0.199158 0.705155 -0.680508 -0.199159 0.705155 -0.62423 -0.336292 0.705156 -0.62423 -0.336292 0.705156 -0.54067 -0.458728 0.705154 -0.540671 -0.45873 0.705154 -0.433481 -0.561117 0.70516 -0.433478 -0.561112 0.707087 -0.365512 -0.605334 0 0.967954 -0.251126 0 0.967954 -0.251126 0 0.763134 -0.64624 0 0.763134 -0.64624 0 0.407163 -0.913355 0 0.407163 -0.913355 0 -0.0294378 -0.999567 0 -0.0294378 -0.999567 0 -0.460224 -0.887803 0 -0.460224 -0.887803 0 -0.799855 -0.600193 0 -0.799855 -0.600193 0 -0.981057 -0.193718 0 -0.981057 -0.193718 0 0.967953 -0.251132 0 0.967953 -0.251132 0 0.763131 -0.646243 0 0.763131 -0.646243 0 0.407175 -0.91335 0 0.407175 -0.91335 0 -0.0294514 -0.999566 0 -0.0294514 -0.999566 0 -0.460221 -0.887804 0 -0.460221 -0.887804 0 -0.799851 -0.600199 0 -0.799851 -0.600199 0 -0.981057 -0.193718 0 -0.981057 -0.193718 0 0.967956 -0.251121 0 0.967956 -0.251121 0 0.763134 -0.64624 0 0.763134 -0.64624 0 0.407169 -0.913353 0 0.407169 -0.913353 0 -0.0294443 -0.999566 0 -0.0294443 -0.999566 0 -0.460227 -0.887801 0 -0.460227 -0.887801 0 -0.799851 -0.600199 0 -0.799851 -0.600199 0 -0.981058 -0.193716 0 -0.981058 -0.193716 0 0.987038 -0.160489 0.00805788 0.957853 -0.287144 0 0.911889 -0.410438 0 0.685982 -0.727618 0 0.685982 -0.727618 0 0.230265 -0.973128 0 0.230265 -0.973128 0 -0.287147 -0.957887 0 -0.287147 -0.957887 0 -0.973126 -0.230271 0.0190776 -0.994754 -0.100496 0 -0.934723 -0.355377 0 -0.727621 -0.685979 0.0184384 -0.808647 -0.588006 0 -0.630969 -0.775808 0 0.967949 -0.251146 0 0.967949 -0.251146 0 0.763147 -0.646224 0 0.763147 -0.646224 0 0.407159 -0.913357 -0.0008242 0.400034 -0.9165 0.000798335 -0.0294451 -0.999566 0 -0.0370033 -0.999315 0 -0.460227 -0.887801 -0.00149125 -0.471859 -0.881673 0.00141187 -0.799851 -0.600197 0 -0.807361 -0.590058 0 -0.981052 -0.193743 0 -0.981052 -0.193743 0 0.967953 -0.251132 0 0.967953 -0.251132 0 0.763134 -0.64624 0 0.763134 -0.64624 0 0.407163 -0.913355 0 0.407163 -0.913355 0 -0.0294447 -0.999566 0 -0.0294447 -0.999566 0 -0.460222 -0.887804 0 -0.460222 -0.887804 0 -0.799846 -0.600205 0 -0.799846 -0.600205 0 -0.981057 -0.193718 0 -0.981057 -0.193718 0 0.967952 -0.251136 0 0.967952 -0.251136 0 0.763134 -0.64624 0 0.763134 -0.64624 0 0.407175 -0.91335 0 0.407175 -0.91335 0 -0.029451 -0.999566 0 -0.029451 -0.999566 0 -0.460227 -0.887801 0 -0.460227 -0.887801 0 -0.799851 -0.600199 0 -0.799851 -0.600199 0 -0.981057 -0.193718 0 -0.981057 -0.193718 0 0.957886 -0.287148 0 0.957886 -0.287148 0 0.685982 -0.727619 0 0.685982 -0.727619 0 0.356336 -0.934358 0.00805964 0.230258 -0.973096 0 0.102356 -0.994748 0 -0.159717 -0.987163 0.00796552 -0.287139 -0.957856 0 -0.409767 -0.91219 0 -0.632527 -0.774538 0.00805992 -0.727595 -0.685959 0 -0.811449 -0.584423 0 -0.973128 -0.230265 0 -0.973128 -0.230265 0 0.967954 -0.251129 0 0.967954 -0.251129 0 0.763136 -0.646238 0 0.763136 -0.646238 0 0.407168 -0.913353 0 0.407168 -0.913353 0 -0.0294446 -0.999566 0 -0.0294446 -0.999566 0 -0.460225 -0.887802 0 -0.460226 -0.887802 0 -0.799851 -0.600198 0 -0.799851 -0.600198 0 -0.981057 -0.193721 0 -0.981057 -0.193721 0 0.967953 -0.25113 0 0.967953 -0.25113 0 0.763134 -0.64624 0 0.763134 -0.64624 0 0.407168 -0.913353 0 0.407168 -0.913353 0 -0.0294446 -0.999566 0 -0.0294446 -0.999566 0 -0.460223 -0.887803 0 -0.460223 -0.887803 0 -0.799851 -0.600199 0 -0.799851 -0.600199 0 -0.981057 -0.193719 0 -0.981057 -0.193719 0 0.987188 -0.159564 0.0190802 0.911721 -0.410366 0 0.957886 -0.287148 0 0.77451 -0.632562 0.0094699 0.685949 -0.727588 0 0.584402 -0.811464 0 0.230266 -0.973128 0 0.230266 -0.973128 0 -0.287146 -0.957887 0 -0.287146 -0.957887 0 -0.727621 -0.685979 0 -0.727621 -0.685979 0 -0.934313 -0.356453 0.00805949 -0.973096 -0.230258 0 -0.994735 -0.102485 0 0.98733 -0.158681 0.0184592 0.913492 -0.406437 0 0.957886 -0.287148 0 0.77507 -0.631875 0.00959925 0.685948 -0.727587 0 0.585116 -0.81095 0 0.354432 -0.935082 0.00946962 0.230256 -0.973084 0 0.100346 -0.994953 0 -0.287148 -0.957886 0 -0.287148 -0.957886 0 -0.727619 -0.685982 0 -0.727619 -0.685982 0 -0.973128 -0.230265 0 -0.973128 -0.230265 0 0.997157 -0.075354 0 0.997157 -0.075354 0 0.999863 0.0165283 0 0.999863 0.0165283 0 0.656253 0.754541 0.019462 0.727483 0.68585 0 0.999994 -0.00341192 0.00154865 0.998762 0.0497227 0.0122274 0.97363 0.227804 0.0128267 0.973046 0.230253 -2.92056e-05 0.904405 0.426675 6.12407e-05 0.828895 0.559404 0 0.999864 0.0165222 8.98531e-10 0.999864 0.0165222 0 0.525281 0.850929 7.06918e-07 0.525282 0.850928 0 0.525284 0.850927 0 0.474282 -0.880373 3.94602e-07 0.474282 -0.880373 0 -0.999736 -0.0229669 0.00635215 -0.991882 0.127005 -0.00301668 -0.982809 0.184599 0.00344318 -0.874166 0.485614 -0.00235948 -0.858646 0.512564 0.00245465 -0.631904 0.775043 0 -0.6225 0.78262 0 -0.997157 0.0753543 0 -0.997157 0.0753543 0 -0.612026 -0.790837 0.0104743 -0.676394 -0.736466 -0.00699416 -0.794915 -0.60668 0.0094945 -0.9012 -0.4333 -0.00446631 -0.942211 -0.33499 0.00584328 -0.997641 -0.0684003 0 -0.999438 -0.0335152 0 -0.474284 0.880372 -6.0104e-09 -0.474284 0.880372 0 -0.474284 0.880372 0 -0.525282 -0.850928 3.60624e-08 -0.525282 -0.850928 0 -0.525282 -0.850928 0 -0.989344 0.1456 -0.00114305 -0.994224 0.107317 0 -0.997697 0.0678346 0.0153512 -0.864208 0.502901 -0.012461 -0.55577 0.831243 0 -0.640161 0.76824 0 -0.988481 0.151347 -0.00243816 -0.992183 0.124768 0.00161493 -0.947181 0.320696 0 -0.955823 0.293943 0 -0.808171 0.588948 -0.221331 -0.672091 0.706616 -0.00519278 0.992088 0.125437 -0.00313773 0.989492 0.144551 0.00170085 0.996924 -0.0783558 0 0.994229 -0.107274 0.00187982 0.949638 0.313342 -0.00422154 0.880364 0.47428 -0.00204551 0.867051 0.498214 0.000275233 0.790733 0.612161 -0.00165144 0.665066 0.746783 0 0.65296 0.757393 -0.0110195 0.685941 -0.727574 3.61352e-07 0.591655 -0.806191 0 0.998817 0.0486217 0.00174692 0.999822 0.0188084 -0.0020755 0.988294 -0.15255 0 0.983246 -0.182283 0 0.915147 -0.40312 -0.00301803 0.92722 -0.374504 0.00274314 0.801231 -0.598349 -0.706039 -0.707336 -0.0344234 -0.706039 -0.707336 -0.0344242 -0.701686 -0.697715 0.144328 -0.699924 -0.457214 0.54869 -0.688856 -0.449403 0.568784 -0.710656 -0.608076 0.353853 -0.701685 -0.606275 0.374257 -0.706639 -0.670202 0.226916 -0.719062 -0.68694 0.105178 -0.707118 -0.335364 0.622507 -0.707119 -0.335364 0.622506 -0.694758 -0.493387 0.523336 -0.528401 -0.536485 0.65801 -0.753345 -0.574877 0.319354 -0.558652 -0.794473 0.238161 -0.742805 -0.664087 0.0850327 -0.706745 -0.707372 -0.0116933 -0.706745 -0.707372 -0.0116937 -0.706745 -0.707372 -0.0116937 -0.706745 -0.705457 0.0533108 -0.706745 -0.705457 0.0533108 -0.706745 -0.705457 0.0533108 -0.770129 -0.620747 -0.146884 -0.700679 -0.482618 -0.52548 -0.590045 -0.587459 -0.55384 -0.753345 -0.592678 -0.284962 -0.281186 -0.957406 -0.0656418 -0.707118 -0.371425 -0.601687 -0.707118 -0.371425 -0.601687 -0.694758 -0.523336 -0.493387 -0.725418 -0.47099 -0.501934 -0.685035 -0.666355 -0.294444 -0.733469 -0.661458 -0.156517 -0.704455 -0.70668 -0.0659355 -0.706039 -0.704084 0.0759999 -0.706039 -0.704083 0.0759987 -0.706052 0.707322 0.034432 -0.706037 0.707334 0.0345001 -0.707114 0.335365 -0.622512 -0.707122 0.335363 -0.622504 -0.706756 0.707361 0.0116888 -0.706746 0.707371 0.0116661 -0.706756 0.707361 0.0116931 -0.706746 0.707371 0.0116943 -0.694767 0.52333 0.493381 -0.703437 0.706108 0.081162 -0.790821 0.595599 0.140937 -0.64116 0.691617 0.332534 -0.793647 0.411529 0.448072 -0.707124 0.371421 0.601682 -0.707124 0.371421 0.601682 -0.701688 0.705001 0.102991 -0.681917 0.728268 0.067926 -0.720632 0.610377 0.32883 -0.68531 0.666117 0.294344 -0.710284 0.468151 0.525673 -0.699933 0.48871 0.520823 0.546262 0.70398 -0.453883 0.552719 0.611116 -0.566603 0.590581 0.538622 -0.600916 0.539988 0.713881 -0.445855 0.543779 0.706951 -0.452244 0.579545 0.547624 -0.60352 0.576719 0.548702 -0.605245 0.577464 0.548243 -0.60495 0.52911 0.655524 -0.538824 0.567902 0.625912 -0.534529 0.524189 0.747344 -0.408294 0.544124 0.726834 -0.419097 0.510375 0.803664 -0.30601 0.540783 0.776067 -0.324458 0.478723 0.861893 -0.167228 0.512781 0.838661 -0.183583 0.48323 0.874777 0.0354234 0.505506 0.861213 -0.0526846 0.491969 0.870603 -0.00405285 0.490331 0.871315 -0.019621 0.486869 0.873082 0.0261764 0.483306 0.869444 -0.102386 0.455064 0.888198 -0.063408 0.482914 0.873178 -0.065985 0.482914 0.875548 0.0144733 0.482928 0.87554 0.0144751 0.500446 0.864453 -0.0476965 0.485674 0.874132 0.00368831 0.490025 0.871115 -0.0321501 0.486149 0.869522 -0.0871273 0.478487 0.875802 -0.0634151 0.483262 0.870615 -0.092123 0.512306 0.850926 0.116052 0.520805 0.847275 0.104339 0.513354 0.821759 0.247345 0.505983 0.820017 0.267495 0.539594 0.775955 0.326699 0.532843 0.7619 0.368222 0.555598 0.686585 0.468948 0.535402 0.674427 0.508422 0.577725 0.582255 0.572025 0.578433 0.582764 0.57079 0.578522 0.582542 0.570927 0.579212 0.583027 0.569731 0.576977 0.588581 0.566277 0.574601 0.638543 0.511953 0.544793 0.73706 0.399929 0.542084 0.742044 0.394355 0.578008 0.683426 0.44591 0.543525 0.75312 0.370662 0.551689 -0.657834 0.512732 0.562802 -0.587631 0.581329 0.58466 -0.549836 0.596534 0.554656 -0.662859 0.502965 0.552349 -0.665452 0.50208 0.579086 -0.547687 0.603903 0.577999 -0.548155 0.60452 0.578318 -0.547326 0.604966 0.577206 -0.547809 0.60559 0.555247 -0.600805 0.575094 0.594977 -0.645061 0.479477 0.493116 -0.731177 0.4714 0.593436 -0.7732 0.223596 0.432591 -0.822726 0.368765 0.541905 -0.834682 0.0982127 0.466266 -0.882852 0.056285 0.504968 -0.862669 -0.0284596 0.504735 -0.86082 0.0650514 0.504735 -0.86082 0.0650514 0.504493 -0.861698 0.0544436 0.544099 -0.838982 0.00811014 0.449608 -0.884737 -0.122858 0.548565 -0.816897 -0.178204 0.482834 -0.804898 -0.344978 0.562973 -0.745551 -0.356672 0.522108 -0.670712 -0.526829 0.545004 -0.654933 -0.523482 0.577359 -0.58212 -0.572532 0.578164 -0.582371 -0.571464 0.578148 -0.582411 -0.571439 0.578951 -0.582654 -0.570377 0.574218 -0.594331 -0.563067 0.575267 -0.618465 -0.535321 0.559617 -0.684508 -0.467202 0.551435 -0.70057 -0.452903 0.552188 -0.699683 -0.453357 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.42237 -0.896548 0.133438 -0.424938 -0.903666 0.0530578 -0.42522 -0.902756 0.0649519 -0.422909 -0.888675 -0.177213 -0.428219 -0.89605 -0.117142 -0.464425 -0.800855 -0.378074 -0.464755 -0.794745 -0.390362 -0.509015 -0.66895 -0.541673 -0.520137 -0.594961 -0.612764 -0.522617 -0.588794 -0.616598 -0.521075 -0.589965 -0.616783 -0.521659 -0.588503 -0.617687 -0.520078 -0.589715 -0.617863 -0.422483 -0.902418 0.0845569 -0.405 -0.914275 -0.0087155 -0.438946 -0.896813 -0.0552562 -0.423126 -0.87339 -0.241152 -0.465248 -0.838724 -0.282994 -0.451223 -0.769333 -0.452244 -0.501722 -0.713689 -0.488799 -0.497 -0.643261 -0.582414 -0.422252 -0.906355 -0.0149831 -0.422252 -0.906355 -0.0149831 -0.422252 -0.903901 0.068307 -0.422252 -0.903901 0.068307 -0.474064 -0.655798 0.587531 -0.475609 -0.654306 0.587945 -0.474164 -0.741041 0.475423 -0.431549 -0.815132 0.386426 -0.419313 -0.808892 0.412154 -0.452527 -0.857931 0.243258 -0.398855 -0.905453 0.145156 -0.438714 -0.897444 0.0460953 -0.422342 -0.906206 -0.0204556 -0.520525 -0.55116 0.652132 -0.521211 -0.552287 0.65063 -0.521508 -0.551515 0.651046 -0.522185 -0.552599 0.649582 -0.484462 -0.639125 0.59734 -0.529396 -0.543152 0.65171 -0.456701 -0.779539 0.428652 -0.491232 -0.707546 0.508006 -0.414089 -0.880196 0.231914 -0.44874 -0.832778 0.324212 -0.427253 -0.897943 0.105612 -0.425693 -0.904868 0.000169693 -0.421618 -0.905606 -0.0460089 -0.419795 0.906083 -0.0527844 -0.416594 0.908877 -0.0197866 -0.441294 0.880752 0.171862 -0.443497 0.854821 0.269428 -0.471465 0.798425 0.374485 -0.492278 0.702685 0.513708 -0.506403 0.669414 0.543545 -0.544069 0.530206 0.650285 -0.52262 0.588791 0.616599 -0.521074 0.589965 0.616784 -0.521656 0.588506 0.617686 -0.520079 0.589716 0.617862 -0.422408 0.903031 -0.0781415 -0.402505 0.915374 0.00890748 -0.438656 0.896537 0.0616593 -0.423126 0.873386 0.241166 -0.465248 0.838721 0.283005 -0.451228 0.76933 0.452245 -0.501724 0.713689 0.488796 -0.497005 0.643253 0.582418 -0.42226 0.906351 0.0149825 -0.42225 0.906356 0.0149847 -0.487098 0.629332 -0.605539 -0.466251 0.655522 -0.594055 -0.422413 0.906064 0.0248235 -0.421502 0.906597 0.0204593 -0.426432 0.897581 -0.111821 -0.408432 0.901466 -0.143323 -0.448565 0.848103 -0.281977 -0.423611 0.817629 -0.389917 -0.426113 0.815249 -0.39217 -0.48776 0.731602 -0.476286 -0.520524 0.551158 -0.652135 -0.521212 0.552287 -0.650629 -0.52151 0.551513 -0.651046 -0.522187 0.552599 -0.64958 -0.484491 0.639073 -0.597373 -0.529362 0.543236 -0.651668 -0.456684 0.779604 -0.428552 -0.471102 0.752176 -0.460753 -0.435828 0.871391 -0.225236 -0.429056 0.881049 -0.199159 -0.424666 0.90535 -0.000344609 -0.421131 0.90647 0.0309852 0.69991 0.45723 -0.548695 0.699906 0.457227 -0.548703 0.699906 0.635171 -0.326633 0.699918 0.63517 -0.32661 0.704451 0.70157 -0.107463 0.68315 0.728288 -0.0538865 0.706037 0.707334 0.0345001 0.707104 0.335369 -0.62252 0.707096 0.335375 -0.622526 0.706738 0.707379 0.0116663 0.706728 0.707389 0.0116893 0.70342 0.700124 -0.12258 0.703415 0.700131 -0.122577 0.700658 0.623721 -0.346483 0.700655 0.450866 -0.552995 0.70066 0.45086 -0.552993 0.706183 0.574189 -0.414261 0.590013 0.732161 -0.340331 0.706736 0.705466 -0.0533112 0.706728 0.705474 -0.0533126 0.706728 0.707389 0.0116936 0.706738 0.707378 0.0116944 0.706737 0.705464 -0.0533285 0.706728 0.705474 -0.0533095 0.703421 0.706126 0.0811537 0.703407 0.706138 0.0811654 0.700649 0.643037 0.309184 0.700662 0.643028 0.309172 0.700662 0.482629 0.525492 0.700669 0.482628 0.525484 0.707107 0.371431 0.601697 0.707107 0.371431 0.601697 0.706021 0.704105 -0.0759608 0.66439 0.744156 0.0694078 0.699908 0.714153 0.0106848 0.699907 0.653296 0.288676 0.699909 0.653293 0.288678 0.699909 0.488735 0.520833 0.699915 0.488722 0.520836 0.701668 -0.44172 0.559058 0.701668 -0.441719 0.559059 0.705751 -0.56812 0.423266 0.719306 -0.591134 0.36491 0.705751 -0.632988 0.318183 0.701668 -0.697733 0.144332 0.701668 -0.697732 0.144331 0.707101 -0.335372 0.622522 0.707101 -0.335372 0.622522 0.694741 -0.68897 0.206534 0.69474 -0.493399 0.523349 0.694741 -0.493398 0.523348 0.704633 -0.643451 0.299104 0.372177 -0.914254 0.160073 0.706727 -0.705475 0.0533121 0.706727 -0.705475 0.0533121 0.706727 -0.705475 0.0533129 0.706727 -0.705475 0.0533122 0.707101 -0.371434 -0.601702 0.707101 -0.371434 -0.601702 0.706021 -0.704101 0.0760007 0.706021 -0.704101 0.0760018 0 -0.994225 0.107317 0.00166673 -0.989261 0.14615 0 -0.997648 0.0685518 0 -0.992316 0.12373 0.00411366 -0.97926 0.202568 -0.00379197 -0.926506 0.376261 -1.15999e-06 -0.893471 0.44912 1.22313e-06 -0.801909 0.597446 -0.000272065 -0.798451 0.60206 0.00052452 -0.619954 0.784638 0 -0.61543 0.788191 0 0.999502 0.0315408 0.00545254 0.997259 -0.0737879 -0.00362976 0.97317 -0.23006 0.00471316 0.889293 -0.457314 -0.00235517 0.841985 -0.539496 0.00289083 0.640169 -0.768229 0 0.615507 -0.788131 0 0.604848 0.796341 0.0136378 0.791807 0.61062 -0.00916293 0.684251 0.729189 0.00475189 0.914671 0.404171 -0.00237874 0.949397 0.314069 0.00293995 0.999884 0.0149597 0 0.999852 -0.0172031 0 -0.525282 -0.850928 3.30918e-08 -0.525282 -0.850928 0 -0.525282 -0.850928 0 -0.474284 0.880372 1.65459e-08 -0.474284 0.880372 0 -0.474284 0.880372 0 -0.996411 0.0846506 -0.000335402 -0.997157 0.0753553 0.00145691 -0.992679 -0.120774 0.0025137 -0.993457 -0.114183 -0.00161194 -0.930054 -0.367419 0.00860161 -0.888642 -0.458522 -0.0154589 -0.727533 -0.685898 0 -0.669055 -0.743213 0 -0.997157 0.0753543 0 -0.997157 0.0753543 0 -0.574034 0.818832 -0.018242 -0.685866 0.727499 0 -0.999863 -0.0165281 0.00474478 -0.996039 0.088794 -0.00403638 -0.985008 0.172461 0.00424086 -0.925344 0.379105 -0.000943682 -0.906815 0.421527 0.000627791 -0.815395 0.578904 -0.0106921 -0.72051 0.693362 0 0.474283 -0.880373 2.15096e-07 0.474282 -0.880373 0 0.474281 -0.880373 0 0.525285 0.850926 -9.48633e-07 0.525282 0.850928 0 0.52528 0.85093 0 0.999864 0.0165222 0 0.999864 0.0165222 2.00795e-08 0.99346 0.114177 0.00226263 0.991495 0.130127 -0.00273845 0.901232 0.433329 0.00181827 0.889541 0.456851 -0.00188387 0.67643 0.736504 0 0.669055 0.743213 0 0.997157 -0.075354 0 0.997157 -0.075354 0 0.999863 0.0165283 0 0.999863 0.0165283 -0.705607 0.70335 -0.0861283 -0.705608 0.703349 -0.0861282 -0.705608 0.675547 -0.213902 -0.705599 0.675555 -0.213904 -0.7056 0.624747 -0.334395 -0.705603 0.624744 -0.334394 -0.705603 0.552662 -0.443496 -0.705607 0.552659 -0.443494 -0.705607 0.461758 -0.537493 -0.705608 0.461757 -0.537493 -0.705607 0.355131 -0.613189 -0.705604 0.355133 -0.613192 -0.705603 0.236412 -0.668007 -0.705602 0.236413 -0.668008 -0.705602 0.109641 -0.700075 -0.705605 0.109641 -0.700072 -0.705605 -0.020864 -0.708298 -0.705607 -0.0208641 -0.708296 -0.705607 -0.150658 -0.692402 -0.705605 -0.150658 -0.692404 -0.705605 -0.275322 -0.652931 -0.705605 -0.275322 -0.652931 -0.705604 -0.39061 -0.591224 -0.705606 -0.390609 -0.591223 -0.705606 -0.492595 -0.509382 -0.705606 -0.492596 -0.509382 -0.705606 -0.577806 -0.410194 -0.705605 -0.577807 -0.410195 -0.705605 -0.643343 -0.297039 -0.705605 -0.643342 -0.297039 -0.705605 -0.686969 -0.173767 -0.705606 -0.686968 -0.173767 -0.705606 -0.707201 -0.0445784 -0.705604 -0.707202 -0.0445786 -0.705391 0.703054 -0.090216 -0.705392 0.703052 -0.0902158 -0.705392 0.671943 -0.225641 -0.705392 0.671943 -0.225641 -0.705392 0.615012 -0.352395 -0.705392 0.615012 -0.352395 -0.705392 0.534446 -0.465607 -0.705389 0.534448 -0.465609 -0.705389 0.433343 -0.560928 -0.705393 0.433341 -0.560925 -0.705393 0.315583 -0.634688 -0.705394 0.315583 -0.634687 -0.705394 0.185698 -0.684059 -0.705393 0.185698 -0.684059 -0.705394 0.0486762 -0.707142 -0.705394 0.0486762 -0.707142 -0.705393 -0.0902159 -0.703052 -0.705395 -0.0902154 -0.70305 -0.705395 -0.22564 -0.671941 -0.705391 -0.225642 -0.671945 -0.70539 -0.352396 -0.615014 -0.705394 -0.352394 -0.61501 -0.705395 -0.465605 -0.534443 -0.705395 -0.465605 -0.534443 -0.705395 -0.560924 -0.43334 -0.705395 -0.560923 -0.433339 -0.705396 -0.634685 -0.315582 -0.705393 -0.634688 -0.315583 -0.705393 -0.684059 -0.185698 -0.705385 -0.684067 -0.185699 -0.705385 -0.707151 -0.0486765 -0.705393 -0.707143 -0.0486765 -0.70542 0.703025 -0.0902124 -0.705417 0.703028 -0.0902129 -0.705417 0.67192 -0.225633 -0.705418 0.671919 -0.225633 -0.705418 0.614989 -0.352382 -0.705414 0.614993 -0.352385 -0.705414 0.534429 -0.465593 -0.705423 0.534423 -0.465587 -0.705423 0.433323 -0.560902 -0.70542 0.433324 -0.560904 -0.705419 0.315571 -0.634664 -0.70542 0.315571 -0.634663 -0.70542 0.185691 -0.684033 -0.705418 0.185691 -0.684035 -0.705418 0.0486745 -0.707118 -0.705419 0.0486745 -0.707117 -0.705421 -0.0902122 -0.703024 -0.705417 -0.0902129 -0.703028 -0.705417 -0.225633 -0.67192 -0.705417 -0.225633 -0.67192 -0.705416 -0.352383 -0.614991 -0.70542 -0.352382 -0.614988 -0.705419 -0.46559 -0.534425 -0.705418 -0.46559 -0.534426 -0.705418 -0.560905 -0.433325 -0.705418 -0.560906 -0.433325 -0.705418 -0.634665 -0.315572 -0.705419 -0.634665 -0.315572 -0.705419 -0.684034 -0.185691 -0.705412 -0.684041 -0.185693 -0.705411 -0.707125 -0.048675 -0.70542 -0.707116 -0.0486747 0.705393 -0.707143 -0.0486762 0.705385 -0.707151 -0.0486771 0.705385 -0.684067 -0.1857 0.705393 -0.68406 -0.185698 0.705392 -0.634688 -0.315583 0.705391 -0.634689 -0.315584 0.705391 -0.560926 -0.433342 0.705392 -0.560926 -0.433341 0.705392 -0.465607 -0.534446 0.705393 -0.465607 -0.534445 0.705393 -0.352395 -0.615011 0.70539 -0.352396 -0.615014 0.705391 -0.225642 -0.671945 0.705391 -0.225642 -0.671944 0.705391 -0.090216 -0.703054 0.705394 -0.0902157 -0.70305 0.705393 0.0486762 -0.707143 0.705392 0.0486764 -0.707144 0.705392 0.185698 -0.68406 0.705394 0.185698 -0.684059 0.705394 0.315583 -0.634687 0.705393 0.315583 -0.634688 0.705393 0.43334 -0.560925 0.705396 0.433339 -0.560923 0.705397 0.534442 -0.465604 0.705388 0.534449 -0.46561 0.705387 0.615016 -0.352398 0.705392 0.615012 -0.352396 0.705392 0.671944 -0.225641 0.705391 0.671945 -0.225642 0.70539 0.703054 -0.0902161 0.705393 0.703051 -0.0902158 -0.705779 0.703612 -0.0824966 -0.705791 0.7036 -0.0824957 -0.705791 0.678586 -0.203421 -0.705786 0.678591 -0.203422 -0.705786 0.632957 -0.318168 -0.705779 0.632964 -0.318171 -0.705779 0.568097 -0.42325 -0.705773 0.568103 -0.423254 -0.705773 0.485975 -0.515474 -0.705771 0.485976 -0.515475 -0.705773 0.389081 -0.592031 -0.705784 0.389074 -0.592022 -0.705783 0.28036 -0.650591 -0.705775 0.280363 -0.650598 -0.705776 0.163129 -0.689398 -0.705778 0.163128 -0.689396 -0.705778 0.0409378 -0.707249 -0.70578 0.0409377 -0.707248 -0.705779 -0.0824969 -0.703613 -0.705777 -0.082497 -0.703614 -0.705777 -0.203425 -0.678599 -0.705778 -0.203425 -0.678598 -0.705777 -0.318172 -0.632965 -0.705779 -0.318171 -0.632963 -0.705779 -0.42325 -0.568098 -0.705772 -0.423254 -0.568103 -0.705773 -0.515474 -0.485975 -0.705776 -0.515472 -0.485972 -0.705776 -0.592028 -0.389079 -0.70578 -0.592025 -0.389077 -0.705781 -0.650593 -0.280361 -0.70578 -0.650594 -0.280362 -0.705779 -0.689395 -0.163128 -0.705778 -0.689396 -0.163128 -0.705778 -0.70725 -0.0409377 -0.705778 -0.70725 -0.0409377 -0.705779 0.703612 -0.0824967 -0.705778 0.703614 -0.0824969 -0.705777 0.678599 -0.203425 -0.705776 0.678601 -0.203425 -0.705776 0.632967 -0.318173 -0.705778 0.632965 -0.318172 -0.705777 0.568099 -0.423252 -0.705782 0.568096 -0.423249 -0.705782 0.485968 -0.515467 -0.70578 0.485969 -0.515469 -0.70578 0.389077 -0.592025 -0.705775 0.389079 -0.59203 -0.705774 0.280364 -0.650599 -0.705778 0.280362 -0.650595 -0.705778 0.163128 -0.689396 -0.705778 0.163128 -0.689396 -0.705778 0.0409375 -0.70725 -0.705779 0.0409375 -0.707249 -0.70578 -0.0824966 -0.703611 -0.705777 -0.0824971 -0.703615 -0.705775 -0.203425 -0.678601 -0.705774 -0.203426 -0.678603 -0.705774 -0.318173 -0.632968 -0.705782 -0.31817 -0.632961 -0.705783 -0.423248 -0.568095 -0.705774 -0.423254 -0.568102 -0.705772 -0.515474 -0.485975 -0.705771 -0.515475 -0.485976 -0.705771 -0.592033 -0.389081 -0.705786 -0.59202 -0.389074 -0.705787 -0.650588 -0.280359 -0.70579 -0.650584 -0.280358 -0.70579 -0.689384 -0.163125 -0.705784 -0.68939 -0.163126 -0.705784 -0.707243 -0.0409374 -0.705779 -0.707248 -0.0409375 -0.705614 0.703343 -0.0861275 -0.705615 0.703342 -0.0861273 -0.705615 0.67554 -0.2139 -0.705614 0.675541 -0.2139 -0.705614 0.624735 -0.334388 -0.705616 0.624733 -0.334387 -0.705616 0.552652 -0.443488 -0.705613 0.552655 -0.44349 -0.705612 0.461754 -0.537489 -0.705616 0.461751 -0.537486 -0.705615 0.355127 -0.613182 -0.705611 0.355129 -0.613185 -0.705611 0.23641 -0.668 -0.705614 0.236409 -0.667997 -0.705615 0.109639 -0.700062 -0.70561 0.10964 -0.700067 -0.705609 -0.020864 -0.708294 -0.705614 -0.0208637 -0.708289 -0.705615 -0.150656 -0.692395 -0.70561 -0.150657 -0.6924 -0.70561 -0.27532 -0.652927 -0.705615 -0.275318 -0.652922 -0.705616 -0.390604 -0.591215 -0.70561 -0.390607 -0.59122 -0.705609 -0.492594 -0.50938 -0.705619 -0.492586 -0.509372 -0.70562 -0.577795 -0.410187 -0.705612 -0.577802 -0.410191 -0.705613 -0.643335 -0.297036 -0.705609 -0.643339 -0.297037 -0.705608 -0.686966 -0.173766 -0.705611 -0.686963 -0.173766 -0.705611 -0.707196 -0.0445787 -0.705615 -0.707191 -0.0445785 -0.705393 0.703051 -0.090216 -0.70539 0.703054 -0.0902163 -0.705391 0.671945 -0.225641 -0.705393 0.671943 -0.225641 -0.705393 0.615011 -0.352395 -0.705395 0.61501 -0.352394 -0.705395 0.534444 -0.465605 -0.705397 0.534442 -0.465604 -0.705395 0.433339 -0.560923 -0.705393 0.433341 -0.560925 -0.705393 0.315583 -0.634688 -0.705393 0.315583 -0.634687 -0.705394 0.185698 -0.684059 -0.70539 0.185699 -0.684062 -0.705391 0.0486764 -0.707145 -0.705393 0.0486762 -0.707143 -0.705394 -0.0902156 -0.70305 -0.705397 -0.0902154 -0.703048 -0.705397 -0.22564 -0.671938 -0.705393 -0.225641 -0.671943 -0.705393 -0.352395 -0.615011 -0.705387 -0.352397 -0.615016 -0.705388 -0.46561 -0.534449 -0.705391 -0.465607 -0.534446 -0.705392 -0.560926 -0.433341 -0.705391 -0.560927 -0.433342 -0.705391 -0.634689 -0.315584 -0.705394 -0.634686 -0.315582 -0.705394 -0.684059 -0.185698 -0.705395 -0.684058 -0.185697 -0.705395 -0.707141 -0.048676 -0.70539 -0.707146 -0.0486766 -0.42183 0.533435 -0.733148 -0.422225 0.301657 -0.854827 -0.415759 0.301491 -0.858048 -0.425443 0.357973 -0.831176 -0.422537 0.357383 -0.83291 -0.421923 0.426594 -0.799999 -0.409793 0.42768 -0.805705 -0.423783 0.479071 -0.768699 -0.42261 0.4779 -0.770073 -0.421827 0.533436 -0.733149 -0.451876 -0.181901 -0.873338 -0.494359 -0.393348 -0.775168 -0.401282 -0.216696 -0.889953 -0.551321 -0.596164 -0.583639 -0.460495 -0.483555 -0.744392 -0.610545 -0.714198 -0.342281 -0.529909 -0.670832 -0.518827 -0.435648 -0.0374869 -0.899336 -0.425242 0.106614 -0.898778 -0.419422 0.141322 -0.896724 -0.417344 0.69495 -0.585549 -0.418479 0.688428 -0.592403 -0.444964 0.830489 -0.335106 -0.451364 0.835576 -0.313183 -0.483914 0.864979 -0.132809 -0.512344 0.858735 0.00885439 -0.502313 0.864388 -0.0227174 -0.5523 0.80386 0.22085 -0.563967 0.786854 0.250605 -0.609441 0.667886 0.427212 -0.587415 -0.71063 -0.387231 -0.587081 -0.71081 -0.387408 -0.587416 0.714297 0.380423 -0.587067 0.714554 0.380478 -0.509149 0.766495 -0.391474 -0.52967 0.815512 -0.233218 -0.549762 0.806689 -0.21683 -0.571965 0.817491 -0.0675651 -0.443094 0.741461 -0.503888 -0.492398 0.735722 -0.465035 -0.448899 0.610115 -0.652878 -0.445292 0.609219 -0.656176 -0.44195 0.511145 -0.737164 -0.467804 -0.230501 -0.853246 -0.438095 0.499035 -0.747688 -0.433941 0.42221 -0.795886 -0.45079 0.382608 -0.806473 -0.432124 0.341177 -0.834786 -0.411974 0.246394 -0.87725 -0.421841 0.264383 -0.867267 -0.421616 0.138351 -0.896158 -0.426459 0.147487 -0.892402 -0.421749 -0.00320316 -0.906707 -0.422553 -0.00161332 -0.906337 -0.439975 -0.103893 -0.89198 -0.43814 -0.125393 -0.890118 -0.44896 -0.17563 -0.876122 -0.450501 -0.281806 -0.847133 -0.481538 -0.376219 -0.791569 -0.493579 -0.39686 -0.773874 -0.492648 -0.405747 -0.769849 -0.490042 -0.502429 -0.712337 -0.484172 -0.529296 -0.696724 -0.550309 -0.575896 -0.604569 -0.530416 -0.682841 -0.502382 -0.554087 -0.688125 -0.468478 -0.554088 -0.361696 -0.749775 -0.530414 -0.340165 -0.776498 -0.550306 -0.196458 -0.811521 -0.484169 -0.110025 -0.868029 -0.490042 -0.0789364 -0.868117 -0.492648 0.0335265 -0.869583 -0.49358 0.0432458 -0.868625 -0.440716 0.153944 -0.884348 -0.467803 0.227002 -0.854184 -0.448957 0.285966 -0.846558 -0.438138 0.336467 -0.833562 -0.439974 0.356029 -0.824419 -0.422554 0.451768 -0.785718 -0.42175 0.450576 -0.786834 -0.426461 0.573929 -0.699097 -0.421616 0.567891 -0.706922 -0.42184 0.662602 -0.618878 -0.411975 0.652016 -0.636516 -0.445435 0.758265 -0.476048 -0.403705 0.757386 -0.513214 -0.441952 0.811243 -0.382836 -0.445294 0.855687 -0.263654 -0.448901 0.854813 -0.26035 -0.4924 0.86967 -0.0348694 -0.443089 0.894071 -0.0656523 -0.509148 0.859542 0.0442244 -0.529668 0.822863 0.205786 -0.54976 0.807029 0.215567 -0.571961 0.741757 0.350223 -0.587415 0.808812 -0.0276932 -0.587069 0.80906 -0.0277733 -0.587416 -0.421809 -0.690667 -0.587081 -0.421876 -0.69091 -0.417341 0.309107 -0.854564 -0.418482 0.299986 -0.857252 -0.444968 0.551676 -0.705448 -0.451351 0.567003 -0.68905 -0.48391 0.682677 -0.547525 -0.512348 0.74812 -0.421683 -0.502318 0.73723 -0.45185 -0.552299 0.806587 -0.210672 -0.563968 0.806737 -0.176392 -0.609441 0.792013 0.036029 -0.45188 0.279135 -0.847283 -0.49436 0.0469412 -0.867989 -0.401249 0.257385 -0.879063 -0.551323 -0.224477 -0.803525 -0.460502 -0.0465871 -0.886435 -0.610543 -0.44737 -0.653527 -0.529912 -0.321549 -0.784729 -0.43565 0.417213 -0.797585 -0.425248 0.541697 -0.725071 -0.419426 0.570739 -0.705931 -0.421997 0.102256 -0.900812 -0.423619 0.102414 -0.900032 -0.422391 0.0413179 -0.905472 -0.422607 0.0415601 -0.90536 -0.421828 -0.0266957 -0.906283 -0.422003 -0.155343 -0.893186 -0.42362 -0.154973 -0.892485 -0.422401 -0.0947874 -0.901439 -0.422608 -0.0945336 -0.901369 -0.421829 -0.0266958 -0.906282 -0.422615 0.84965 -0.315422 -0.424486 0.850078 -0.311736 -0.394031 0.838135 -0.377187 -0.42184 0.828305 -0.368731 -0.422546 0.792963 -0.438935 -0.429561 0.791608 -0.43455 -0.403893 0.768701 -0.495953 -0.42217 0.763458 -0.488778 -0.422406 0.718462 -0.552617 -0.432834 0.716183 -0.547482 -0.411782 0.683251 -0.602996 -0.422404 0.681377 -0.597746 -0.61201 -0.785678 0.0903009 -0.562649 -0.816735 -0.127946 -0.58317 -0.809812 -0.0641675 -0.548324 -0.811875 -0.2005 -0.521812 -0.786532 -0.330271 -0.507146 -0.75918 -0.40798 -0.491274 -0.737638 -0.463184 -0.458031 -0.631148 -0.625987 -0.456277 -0.604263 -0.653206 -0.441923 -0.525433 -0.727065 -0.417815 -0.358995 -0.834598 -0.417438 -0.357516 -0.835421 -0.417329 0.894668 -0.159392 -0.41849 0.892398 -0.168795 -0.44497 0.886776 0.125023 -0.451337 0.880256 0.146438 -0.483913 0.815506 0.317456 -0.512353 0.739234 0.437067 -0.502315 0.759933 0.412531 -0.552299 0.585735 0.593195 -0.563955 0.556159 0.610443 -0.609437 0.364811 0.703917 -0.587415 -0.80904 0.0199636 -0.587081 -0.809283 0.0199007 -0.587413 0.428388 0.686607 -0.587068 0.428581 0.686782 -0.511481 0.47908 -0.713351 -0.52967 0.589645 -0.609729 -0.549761 0.590198 -0.591125 -0.571963 0.67418 -0.467268 -0.450501 -0.667618 -0.592735 -0.467804 -0.626243 -0.623682 -0.457593 0.394537 -0.796837 -0.492401 0.404636 -0.770592 -0.455539 0.227458 -0.860667 -0.431597 0.204741 -0.878524 -0.448221 0.100777 -0.888224 -0.438097 0.0583374 -0.897033 -0.431209 -0.0693458 -0.899583 -0.44204 -0.0582599 -0.895101 -0.411977 -0.225238 -0.882917 -0.421841 -0.204673 -0.883266 -0.421617 -0.328265 -0.84527 -0.426461 -0.318472 -0.846586 -0.42175 -0.456128 -0.783629 -0.422553 -0.454568 -0.784102 -0.439974 -0.535959 -0.720535 -0.438138 -0.55365 -0.708171 -0.448958 -0.590155 -0.670935 -0.538125 -0.837255 -0.0970881 -0.48154 -0.721603 -0.497402 -0.497113 -0.733217 -0.463974 -0.505523 -0.736507 -0.449448 -0.484171 -0.806747 -0.338728 -0.521413 -0.805111 -0.28271 -0.545556 -0.829078 -0.122469 -0.554091 0.0616431 -0.83017 -0.530414 0.0936569 -0.84255 -0.550306 0.235625 -0.801027 -0.48417 0.33873 -0.806747 -0.505522 0.449451 -0.736506 -0.497122 0.463958 -0.733221 -0.440718 0.575493 -0.688894 -0.442834 0.579207 -0.68441 -0.456043 0.669382 -0.586474 -0.452388 0.657662 -0.602351 -0.438138 0.708161 -0.553663 -0.439975 0.720533 -0.535962 -0.422552 0.784107 -0.454563 -0.421753 0.783636 -0.456113 -0.426463 0.846585 -0.31847 -0.421613 0.845267 -0.328276 -0.421838 0.883268 -0.204673 -0.411969 0.882918 -0.225249 -0.427726 0.891901 -0.146847 -0.412573 0.910466 -0.0288817 -0.415598 0.909186 -0.025675 -0.466929 0.863407 0.191063 -0.384948 0.910838 0.148959 -0.460754 0.852048 0.248438 -0.492674 0.769494 0.40639 -0.49391 0.770121 0.40369 -0.529671 0.609726 0.589647 -0.549756 0.591128 0.5902 -0.571959 0.467264 0.674186 -0.587418 0.686604 -0.428387 -0.587067 0.686781 -0.428583 -0.587417 -0.019964 -0.809038 -0.58708 -0.0199004 -0.809284 -0.417342 -0.159584 -0.894628 -0.418484 -0.168835 -0.892394 -0.44497 0.125041 -0.886773 -0.451334 0.146443 -0.880257 -0.484819 0.323741 -0.812492 -0.514405 0.4422 -0.734743 -0.502337 0.412583 -0.75989 -0.552301 0.593191 -0.585737 -0.563958 0.610442 -0.556159 -0.60944 0.70392 -0.364802 -0.451882 0.665378 -0.594201 -0.494361 0.474646 -0.72823 -0.401245 0.662443 -0.632592 -0.551323 0.207359 -0.808112 -0.460523 0.402831 -0.790978 -0.610545 -0.0606745 -0.789654 -0.529892 0.113935 -0.840377 -0.435653 0.760104 -0.482129 -0.425253 0.831651 -0.357095 -0.419426 0.847245 -0.325971 -0.422252 -0.350316 -0.836052 -0.415965 -0.352571 -0.838252 -0.425269 -0.40522 -0.809286 -0.42255 -0.406885 -0.809874 -0.421968 -0.471468 -0.774378 -0.410202 -0.475742 -0.778077 -0.423427 -0.522179 -0.740296 -0.422615 -0.523802 -0.739613 -0.421829 -0.575665 -0.700478 -0.42183 -0.575665 -0.700478 -0.529887 -0.784762 0.321511 -0.610554 -0.653506 0.447386 -0.541549 -0.809437 0.227015 -0.505728 -0.862274 0.026903 -0.511786 -0.857745 0.0484612 -0.42669 -0.866108 -0.26037 -0.472735 -0.87007 -0.139639 -0.390391 -0.739434 -0.548482 -0.411992 -0.767916 -0.490476 -0.417334 0.854531 0.309208 -0.418487 0.857249 0.299988 -0.444972 0.705453 0.551668 -0.451327 0.689129 0.566926 -0.484818 0.541782 0.686603 -0.514415 0.415165 0.750344 -0.502347 0.451753 0.73727 -0.5523 0.21067 0.806587 -0.563949 0.176453 0.806738 -0.609439 -0.0360265 0.792014 -0.587417 -0.690665 0.421809 -0.58708 -0.690911 0.421877 -0.587417 0.0276926 0.808811 -0.587068 0.0277732 0.809061 -0.51213 0.0622146 -0.856652 -0.529672 0.205784 -0.822861 -0.549759 0.215562 -0.80703 -0.571961 0.350223 -0.741757 -0.461628 -0.0542404 -0.885414 -0.4924 -0.0348719 -0.86967 -0.45735 -0.225681 -0.860174 -0.429779 -0.261723 -0.864171 -0.449927 -0.349448 -0.821859 -0.438098 -0.397987 -0.806025 -0.431209 -0.509846 -0.744389 -0.442039 -0.498007 -0.74605 -0.411977 -0.636515 -0.652015 -0.421839 -0.618884 -0.662597 -0.421614 -0.706923 -0.567893 -0.426459 -0.699097 -0.573931 -0.423579 -0.769494 -0.477975 -0.413514 -0.789918 -0.452809 -0.429786 -0.801592 -0.415614 -0.465879 -0.853528 -0.233338 -0.439973 -0.824423 -0.35602 -0.438138 -0.833561 -0.33647 -0.448957 -0.846557 -0.285969 -0.538125 -0.773629 0.334544 -0.454883 -0.867938 -0.199412 -0.475417 -0.875395 -0.0875301 -0.48334 -0.872439 -0.07233 -0.485118 -0.873907 -0.0307764 -0.497779 -0.864429 0.070561 -0.487435 -0.866405 0.10839 -0.529034 -0.828078 0.1855 -0.542101 -0.776665 0.320807 -0.55408 0.468497 -0.688118 -0.531247 0.501234 -0.683038 -0.55031 0.604579 -0.575885 -0.484675 0.694915 -0.53121 -0.505523 0.757489 -0.413107 -0.498276 0.766806 -0.404635 -0.440766 0.841866 -0.311427 -0.444001 0.843431 -0.302469 -0.455697 0.872566 -0.175981 -0.452729 0.870591 -0.192635 -0.438024 0.889989 -0.126708 -0.439979 0.891979 -0.103883 -0.422792 0.906222 -0.00282903 -0.422689 0.90627 -0.00303741 -0.425836 0.892892 0.146316 -0.421623 0.896152 0.138371 -0.421876 0.867591 0.263263 -0.412761 0.876919 0.246253 -0.427711 0.845839 0.318779 -0.411754 0.804325 0.428392 -0.41667 0.799887 0.431933 -0.465487 0.654064 0.596257 -0.386826 0.714075 0.583492 -0.461279 0.613634 0.640839 -0.49162 0.463027 0.737507 -0.494406 0.467235 0.732976 -0.528415 0.235457 0.815682 -0.550514 0.217197 0.806077 -0.571484 0.0687632 0.817727 -0.587417 0.380423 -0.714297 -0.58707 0.380478 -0.714553 -0.587417 0.38723 -0.71063 -0.587083 0.387406 -0.710809 -0.41734 -0.585509 -0.694987 -0.418482 -0.592405 -0.688425 -0.444967 -0.335104 -0.830488 -0.451354 -0.313227 -0.835565 -0.48482 -0.125881 -0.865507 -0.514409 0.015599 -0.857403 -0.502325 -0.0226735 -0.864382 -0.5523 0.220848 -0.80386 -0.563963 0.250594 -0.78686 -0.60944 0.427205 -0.667892 -0.451883 0.873329 -0.181928 -0.494355 0.775186 -0.393319 -0.401209 0.890022 -0.216546 -0.551325 0.583628 -0.59617 -0.460552 0.744308 -0.483629 -0.610547 0.342281 -0.714196 -0.529911 0.518827 -0.67083 -0.435653 0.899334 -0.0374872 -0.425248 0.898776 0.106609 -0.419432 0.896723 0.141296 -0.422437 -0.713709 -0.558718 -0.412724 -0.718891 -0.559334 -0.431996 -0.745996 -0.506823 -0.422438 -0.751244 -0.507128 -0.422226 -0.78932 -0.445757 -0.405224 -0.797624 -0.446755 -0.428346 -0.814967 -0.39032 -0.422572 -0.818786 -0.388616 -0.421935 -0.847229 -0.322759 -0.395842 -0.859475 -0.323438 -0.422874 -0.866632 -0.264814 -0.422619 -0.867813 -0.261333 -0.42244 0.713708 0.558718 -0.412723 0.718891 0.559334 -0.431996 0.745997 0.506822 -0.422438 0.751245 0.507127 -0.422226 0.78932 0.445757 -0.405223 0.797624 0.446755 -0.428344 0.814966 0.390323 -0.422568 0.818787 0.388618 -0.421931 0.847231 0.322759 -0.39584 0.859476 0.323438 -0.422873 0.866633 0.264812 -0.422625 0.867779 0.261434 -0.529897 -0.518848 0.670825 -0.610553 -0.342262 0.714201 -0.460493 -0.744374 0.483584 -0.551355 -0.583548 0.596221 -0.501556 -0.742856 0.443403 -0.44157 -0.874163 0.202125 -0.482407 -0.81524 0.320419 -0.442471 -0.88478 0.146233 -0.421606 -0.900507 -0.10647 -0.418375 -0.899939 -0.122772 -0.417346 0.585545 0.694953 -0.418481 0.592402 0.688428 -0.444966 0.335114 0.830484 -0.451349 0.313253 0.835558 -0.484824 0.125856 0.865509 -0.514404 -0.015582 0.857406 -0.50234 0.0226285 0.864374 -0.552302 -0.220855 0.803857 -0.563953 -0.25057 0.786874 -0.609437 -0.427202 0.667896 -0.587417 -0.38723 0.71063 -0.58708 -0.387407 0.710811 -0.587417 -0.380423 0.714296 -0.587068 -0.380478 0.714554 -0.493911 -0.4651 -0.734666 -0.529671 -0.233218 -0.815511 -0.549761 -0.216832 -0.806689 -0.571963 -0.0675715 -0.817491 -0.432875 -0.901454 0.000240128 -0.405881 -0.912818 0.0449849 -0.424437 -0.904186 -0.047973 -0.42646 -0.892401 -0.147491 -0.421614 -0.896159 -0.138349 -0.421839 -0.867268 -0.264381 -0.411976 -0.877247 -0.246399 -0.442039 -0.804312 -0.397095 -0.431209 -0.813735 -0.389737 -0.438098 -0.747682 -0.499041 -0.451812 -0.707577 -0.543324 -0.42884 -0.658892 -0.618027 -0.459353 -0.618625 -0.637415 -0.492676 -0.46321 -0.736686 -0.438544 -0.889935 0.125279 -0.455255 -0.873294 0.173495 -0.473398 -0.855341 0.210443 -0.4404 -0.842951 0.309001 -0.478305 -0.79645 0.36999 -0.484104 -0.772524 0.410914 -0.498582 -0.732298 0.463848 -0.484293 -0.6967 0.529216 -0.51123 -0.660452 0.549951 -0.563069 -0.503425 0.655376 -0.521208 -0.536377 0.663808 -0.55408 0.749787 -0.361684 -0.531248 0.775598 -0.340915 -0.550311 0.811523 -0.196438 -0.484675 0.867419 -0.112579 -0.505521 0.862559 0.0209787 -0.498297 0.866381 0.0329369 -0.473807 0.876458 0.085604 -0.463418 0.870459 0.165966 -0.448266 0.871945 0.196899 -0.454674 0.849129 0.268797 -0.449636 0.847033 0.283482 -0.438019 0.834112 0.335256 -0.439974 0.824422 0.356021 -0.422787 0.786228 0.450663 -0.422685 0.78637 0.450509 -0.425832 0.700114 0.573155 -0.421614 0.706918 0.567898 -0.421868 0.61973 0.661787 -0.412769 0.636287 0.651737 -0.427712 0.573133 0.698986 -0.411754 0.482368 0.773162 -0.416675 0.476748 0.774011 -0.465488 0.26831 0.843405 -0.386829 0.326662 0.862354 -0.461279 0.211009 0.861799 -0.49162 0.0322413 0.870213 -0.494405 0.0381475 0.868394 -0.528415 -0.203929 0.824131 -0.550515 -0.214941 0.806681 -0.571485 -0.349313 0.742553 -0.587416 -0.0276923 -0.808811 -0.587068 -0.027773 -0.809061 -0.587416 0.690667 -0.421809 -0.58708 0.690911 -0.421876 -0.41734 -0.854557 -0.309127 -0.418482 -0.857248 -0.299997 -0.444967 -0.705455 -0.551668 -0.451348 -0.689063 -0.566989 -0.48482 -0.541767 -0.686613 -0.514407 -0.415197 -0.750331 -0.502333 -0.451802 -0.737249 -0.552301 -0.210666 -0.806588 -0.563954 -0.176435 -0.806738 -0.609439 0.0360265 -0.792014 -0.451875 0.84728 0.27915 -0.494361 0.867989 0.0469327 -0.401247 0.879064 0.257384 -0.551318 0.803532 -0.224465 -0.460527 0.88642 -0.0466304 -0.610549 0.653517 -0.447377 -0.529885 0.784764 -0.321508 -0.435653 0.797606 0.417171 -0.425249 0.725065 0.541705 -0.419427 0.705926 0.570745 -0.422252 0.350317 0.836051 -0.415965 0.352572 0.838252 -0.425269 0.405219 0.809286 -0.422549 0.406885 0.809875 -0.421966 0.471469 0.774378 -0.410201 0.475742 0.778078 -0.423427 0.52218 0.740296 -0.422617 0.523799 0.739615 -0.421831 0.575665 0.700478 -0.42183 0.575665 0.700478 -0.451877 -0.665383 0.5942 -0.494358 -0.474653 0.728227 -0.40125 -0.662432 0.632599 -0.551323 -0.207358 0.808112 -0.460512 -0.402852 0.790973 -0.610545 0.0606737 0.789654 -0.529899 -0.11392 0.840374 -0.435651 -0.760095 0.482145 -0.425246 -0.831667 0.357066 -0.419426 -0.847241 0.325981 -0.417343 0.159593 0.894626 -0.418481 0.168815 0.892399 -0.444965 -0.125023 0.886778 -0.451359 -0.146531 0.880229 -0.484822 -0.323733 0.812493 -0.514414 -0.442215 0.734728 -0.502313 -0.412521 0.759939 -0.552302 -0.593195 0.585732 -0.563956 -0.610442 0.55616 -0.60944 -0.703919 0.364802 -0.587416 0.0199639 0.809039 -0.587081 0.0199006 0.809284 -0.587416 -0.686604 0.428388 -0.587067 -0.686781 0.428583 -0.494406 -0.771125 -0.401159 -0.528415 -0.611754 -0.588672 -0.550514 -0.591138 -0.589483 -0.571485 -0.468411 -0.673792 -0.42415 -0.786606 0.448718 -0.424605 -0.846946 0.319988 -0.408243 -0.841742 0.353281 -0.422494 -0.860089 0.285913 -0.421869 -0.882987 0.205816 -0.437219 -0.882764 0.171952 -0.412543 -0.909184 0.0565079 -0.434929 -0.900314 0.0164739 -0.438066 -0.897122 -0.0571824 -0.454043 -0.881555 -0.129253 -0.429406 -0.879957 -0.203193 -0.462676 -0.8493 -0.254206 -0.49162 -0.769747 -0.407185 -0.420487 -0.78417 0.456364 -0.445091 -0.70558 0.551409 -0.457069 -0.686613 0.565377 -0.452991 -0.668291 0.590073 -0.446581 -0.582605 0.679071 -0.451679 -0.591596 0.667833 -0.481228 -0.496273 0.722587 -0.477906 -0.50317 0.720018 -0.484584 -0.461292 0.743228 -0.497666 -0.410606 0.764023 -0.484788 -0.336231 0.807422 -0.500692 -0.314373 0.806522 -0.576046 -0.112776 0.809601 -0.515471 -0.144235 0.844681 -0.554088 0.830172 0.0616511 -0.531242 0.842149 0.092561 -0.550306 0.801022 0.235643 -0.484675 0.8075 0.336206 -0.505523 0.736506 0.449449 -0.498276 0.733828 0.461755 -0.440766 0.690638 0.573362 -0.444009 0.683647 0.579208 -0.455705 0.588651 0.667699 -0.452728 0.60213 0.65763 -0.438022 0.55473 0.707398 -0.439975 0.535973 0.720524 -0.422785 0.455563 0.7834 -0.422689 0.455754 0.783341 -0.425835 0.319737 0.846424 -0.421614 0.328262 0.845272 -0.421868 0.205816 0.882987 -0.412768 0.225182 0.882562 -0.427714 0.146849 0.891906 -0.411756 0.0311596 0.910761 -0.416674 0.0258711 0.908688 -0.465489 -0.189342 0.864563 -0.386825 -0.148281 0.910153 -0.461275 -0.24816 0.851846 -0.491617 -0.407189 0.769747 -0.494405 -0.401159 0.771126 -0.528414 -0.588672 0.611755 -0.550514 -0.589484 0.591137 -0.571485 -0.673791 0.468413 -0.587416 -0.428388 -0.686605 -0.587067 -0.428583 -0.686781 -0.587416 0.809039 -0.0199627 -0.587083 0.809282 -0.0198997 -0.41734 -0.894631 0.159568 -0.41928 -0.89074 0.175461 -0.443257 -0.883304 -0.152634 -0.442185 -0.884349 -0.149664 -0.49229 -0.796956 -0.350016 -0.506911 -0.758475 -0.409581 -0.518066 -0.700101 -0.491392 -0.582954 -0.480635 -0.655099 -0.550018 -0.556851 -0.622412 -0.626783 -0.306823 -0.716242 -0.451878 0.594199 0.665383 -0.494359 0.728225 0.474655 -0.401246 0.632591 0.662442 -0.551324 0.80811 0.207367 -0.460495 0.790964 0.402889 -0.610549 0.789651 -0.0606782 -0.52991 0.84037 0.113904 -0.435652 0.482141 0.760097 -0.425251 0.357105 0.831648 -0.419425 0.325988 0.847239 -0.422615 -0.849655 0.315409 -0.424521 -0.850091 0.311653 -0.394028 -0.838135 0.377188 -0.421845 -0.828303 0.368729 -0.422551 -0.792962 0.438933 -0.429554 -0.791609 0.434555 -0.403889 -0.768702 0.495954 -0.422167 -0.763459 0.488779 -0.422404 -0.718462 0.552618 -0.432838 -0.716182 0.54748 -0.411786 -0.68325 0.602994 -0.422405 -0.681377 0.597745 -0.421997 -0.102256 0.900812 -0.423619 -0.102414 0.900032 -0.422391 -0.0413176 0.905472 -0.422607 -0.0415598 0.90536 -0.421828 0.0266957 0.906283 -0.422003 0.155343 0.893186 -0.42362 0.154972 0.892485 -0.422401 0.0947936 0.901438 -0.422609 0.0945393 0.901368 -0.42183 0.0266959 0.906282 -0.451876 -0.279135 0.847285 -0.494356 -0.0469515 0.86799 -0.40125 -0.257385 0.879063 -0.551322 0.224473 0.803527 -0.460503 0.0465881 0.886435 -0.610548 0.44738 0.653516 -0.529899 0.321532 0.784745 -0.435652 -0.417176 0.797603 -0.425246 -0.541717 0.725057 -0.419428 -0.570741 0.705928 -0.41734 -0.309123 0.854559 -0.418478 -0.30002 0.857242 -0.440673 -0.475425 0.761432 -0.456241 -0.564384 0.687979 -0.458874 -0.61315 0.643025 -0.504371 -0.738811 0.446954 -0.502716 -0.736967 0.451837 -0.54514 -0.797515 0.258441 -0.583172 -0.804628 0.111735 -0.562619 -0.807787 0.175898 -0.612019 -0.78962 -0.043968 -0.587416 0.421809 0.690666 -0.587079 0.421877 0.690911 -0.587417 -0.80881 0.0276927 -0.587067 -0.809062 0.0277738 -0.571485 -0.742553 -0.349314 -0.550514 -0.806682 -0.21494 -0.528414 -0.824131 -0.203928 -0.496819 -0.86746 0.0261595 -0.490225 -0.871051 0.030806 -0.470348 -0.866696 0.166167 -0.475513 -0.866845 0.149892 -0.44099 -0.857366 0.265429 -0.459642 -0.836192 0.299186 -0.438049 -0.80553 0.399043 -0.436254 -0.782383 0.444476 -0.412568 -0.759112 0.503525 -0.442407 -0.698502 0.562469 -0.417816 -0.663247 0.620913 -0.426905 -0.590966 0.684479 -0.417904 -0.575247 0.703169 -0.429079 -0.500743 0.751763 -0.414102 -0.451654 0.790271 -0.433693 -0.412405 0.801144 -0.439438 -0.335283 0.833355 -0.450939 -0.30551 0.838641 -0.449261 -0.283437 0.847247 -0.451551 -0.176995 0.874514 -0.441598 -0.151415 0.884344 -0.478875 -0.0728921 0.874852 -0.484545 -0.0278695 0.874322 -0.496238 0.0234899 0.867869 -0.485282 0.112279 0.867118 -0.501137 0.129306 0.855653 -0.57195 0.310331 0.759321 -0.517421 0.300566 0.801209 -0.536073 0.594426 0.599402 -0.536668 0.678613 0.50147 -0.540887 0.678575 0.496969 -0.514446 0.558917 0.650352 -0.492083 0.53418 0.687391 -0.485559 0.530606 0.694759 -0.495723 0.453618 0.7406 -0.484544 0.413036 0.771115 -0.479198 0.374725 0.793694 -0.436131 -0.443121 0.78322 -0.424559 -0.342099 0.838283 -0.428564 -0.29856 0.852757 -0.416461 -0.264159 0.869931 -0.429332 -0.180528 0.88492 -0.416973 -0.146624 0.897014 -0.432672 -0.0396762 0.900678 -0.416037 0.00373406 0.90934 -0.438226 0.0743274 0.895787 -0.438018 0.12671 0.889992 -0.449086 0.161042 0.878856 -0.448256 0.178478 0.875907 -0.453405 0.278576 0.846652 -0.452045 0.282399 0.846113 -0.48096 0.377792 0.791171 -0.401477 -0.419236 0.814283 -0.446012 -0.507478 0.737251 -0.436027 -0.612443 0.659389 -0.447916 -0.616633 0.647406 -0.496721 -0.731351 0.467325 -0.5304 -0.831967 0.162808 -0.619598 -0.779365 0.0932174 -0.465296 -0.837889 0.285381 -0.530676 -0.814009 0.236161 -0.500755 -0.751973 0.428697 -0.398409 -0.74174 0.53953 -0.587416 -0.714297 -0.380423 -0.587067 -0.714554 -0.380478 -0.587416 0.71063 0.38723 -0.587079 0.710812 0.387408 -0.417339 -0.694997 0.585497 -0.418478 -0.688452 0.592377 -0.445577 -0.843441 0.300115 -0.441254 -0.84121 0.312506 -0.494409 -0.865168 0.0839234 -0.507352 -0.861385 0.0247037 -0.521604 -0.848164 -0.0924506 -0.587403 -0.73397 -0.340948 -0.547246 -0.794724 -0.262556 -0.629032 -0.617448 -0.47231 -0.451876 0.181898 0.873339 -0.494357 0.393333 0.775177 -0.401253 0.216633 0.889981 -0.551324 0.596162 0.583638 -0.460511 0.483571 0.744372 -0.610548 0.714199 0.342274 -0.529882 0.670815 0.518875 -0.435655 0.0375386 0.899331 -0.425249 -0.106609 0.898776 -0.419428 -0.14132 0.896721 -0.421828 -0.533436 0.733149 -0.422231 -0.301657 0.854824 -0.415758 -0.301491 0.858049 -0.425443 -0.357972 0.831176 -0.42254 -0.357384 0.832908 -0.421927 -0.426593 0.799997 -0.409793 -0.42768 0.805705 -0.423783 -0.479069 0.768701 -0.422612 -0.4779 0.770072 -0.421829 -0.533435 0.733149 -0.671496 -0.481865 0.562938 -0.698092 -0.466235 0.543408 -0.7042 -0.463001 0.538267 -0.678257 -0.504076 0.534674 -0.751442 -0.455853 0.477004 -0.650513 -0.526766 0.54713 -0.478561 -0.609649 0.631907 -0.539195 -0.806714 0.24183 -0.687822 -0.69531 0.208434 -0.678329 -0.703841 0.210898 -0.673026 -0.708422 0.212541 -0.635406 -0.739687 0.221634 -0.385679 -0.883396 0.266202 -0.539201 -0.819546 -0.193925 -0.678256 -0.715079 -0.169206 -0.386806 -0.897076 -0.213624 -0.635413 -0.751445 -0.177709 -0.67324 -0.719515 -0.17043 -0.687749 -0.706568 -0.166621 -0.479244 -0.645514 -0.594674 -0.650503 -0.558064 -0.515181 -0.683878 -0.535562 -0.495463 -0.74594 -0.484605 -0.456872 -0.704204 -0.493884 -0.510073 -0.698199 -0.497348 -0.51494 -0.671592 -0.514106 -0.533534 -0.553719 -0.257928 -0.79175 -0.667207 -0.229984 -0.708479 -0.690892 -0.222477 -0.687875 -0.781961 -0.178987 -0.597077 -0.698223 -0.182489 -0.69223 -0.686226 -0.184611 -0.703571 -0.628774 -0.196452 -0.752363 -0.616729 0.153697 -0.772025 -0.682931 0.143387 -0.716272 -0.697658 0.141407 -0.702337 -0.78196 0.143532 -0.606578 -0.690898 0.1816 -0.699773 -0.667218 0.18788 -0.720778 -0.553145 0.210973 -0.805928 -0.669884 0.482813 -0.564045 -0.697632 0.466501 -0.54377 -0.704121 0.463012 -0.538362 -0.678256 0.504076 -0.534674 -0.75144 0.455854 -0.477006 -0.650502 0.526772 -0.547137 -0.47849 0.609677 -0.631935 -0.67824 0.703894 -0.211007 -0.67825 0.703885 -0.211005 -0.63527 0.739766 -0.221761 -0.372193 0.889954 -0.263542 -0.633688 0.740781 -0.222897 -0.39672 0.879282 -0.263583 -0.678258 0.715078 0.169205 -0.678259 0.715076 0.169205 -0.635174 0.751614 0.177851 -0.372082 0.902537 0.216753 -0.633642 0.753021 0.177364 -0.396954 0.893174 0.211346 -0.479368 0.645464 0.594628 -0.650504 0.558063 0.515179 -0.683871 0.535568 0.495467 -0.745943 0.484602 0.45687 -0.704117 0.493899 0.510179 -0.69769 0.497665 0.515323 -0.669622 0.515341 0.534818 -0.553681 0.257935 0.791775 -0.66722 0.229979 0.708468 -0.690889 0.222477 0.687878 -0.781955 0.178989 0.597084 -0.697661 0.182504 0.692792 -0.68293 0.185301 0.706591 -0.616453 0.19893 0.761848 -0.0532446 -0.997255 0.0514487 0.00989788 -0.947232 0.320395 0 -0.997377 0.0723774 0 -0.720255 0.693709 -0.00533948 -0.760956 0.648781 0.00215686 -0.850045 0.526705 -0.00810338 -0.964434 0.2642 -0.00486668 -0.00747104 0.99996 0.00850035 0.202068 0.979335 -0.00422754 0.302776 0.953052 0.00530572 0.573728 0.819029 0 0.601895 0.798575 -0.00647199 -0.0304424 0.999516 0.0164933 -0.298367 0.954309 1.57722e-06 -0.209759 0.977753 -4.15084e-07 -0.454911 0.890537 0.0019015 -0.486007 0.873953 -0.00302755 -0.625761 0.780009 0 -0.653253 0.757139 -1.45683e-07 -0.981984 0.188963 0 -0.981984 0.188962 -0.00487265 -0.506522 0.862214 0.00849976 -0.31467 0.949163 -0.00422891 -0.214307 0.976757 0.005304 0.087346 0.996164 0 0.121956 0.992536 -0.00647189 -0.526118 0.850387 0.0164939 -0.73555 0.67727 1.55437e-06 -0.670533 0.74188 -4.52865e-07 -0.839242 0.543759 0.00190088 -0.857874 0.513857 -0.00302803 -0.931929 0.362627 0 -0.944306 0.32907 0 -0.961982 -0.273112 -0.00547192 -0.942351 -0.334582 0.0187231 -0.458305 -0.888598 0.00145905 -0.370007 -0.929028 -0.000531712 -0.601603 -0.798795 -0.00413912 -0.556381 -0.830917 0.0134132 -0.778565 -0.627421 -0.00671185 -0.71566 -0.698417 0.00189837 -0.886539 -0.46265 -0.00600171 -0.217652 -0.976008 0.0114561 0.0914871 -0.99574 0 0.0285589 -0.999592 0 -0.984373 0.176098 0.00911667 -0.968316 0.249563 -9.6862e-07 -0.922921 0.384989 8.14666e-08 -0.883592 0.468258 -0.00151391 -0.845067 0.534658 0.00838432 -0.761281 0.648368 -0.00534215 -0.673941 0.738766 0.00749726 -0.435418 0.900197 0 -0.390619 0.920552 0 -0.696552 -0.717506 -0.00547224 -0.648814 -0.760928 0.0187222 0.0474009 -0.9987 0.00145854 0.144083 -0.989565 -0.000532303 -0.121611 -0.992578 -0.00413499 -0.0664585 -0.997781 0.0134125 -0.360542 -0.932647 -0.00671163 -0.27057 -0.962677 0.00189849 -0.536439 -0.843937 -0.00600164 0.299507 -0.954075 0.0114563 0.577099 -0.816594 0 0.524526 -0.851394 0 -0.996459 0.084085 0.00705714 -0.974592 0.223875 -0.00350962 -0.953011 0.302916 0.0041748 -0.814741 0.579809 0 -0.798561 0.601914 0 -0.244468 -0.969657 -0.00547044 -0.181436 -0.983388 0.0187244 0.540387 -0.841208 0.00145973 0.619554 -0.784953 -0.000531107 0.390974 -0.920401 -0.00414783 0.441534 -0.897235 0.0134119 0.154091 -0.987966 -0.00670997 0.247013 -0.968989 0.00190033 -0.042608 -0.99909 -0.00600141 0.73642 -0.676498 0.0114568 0.908083 -0.418634 0 0.879953 -0.475061 0 -0.987172 0.159658 0 -0.987172 0.159658 0 0.273092 -0.961988 -0.00547261 0.33457 -0.942355 0.0194959 0.884822 -0.465521 3.81747e-06 0.929028 -0.37001 1.26825e-06 0.793843 -0.608123 -0.00414081 0.830932 -0.556359 0.0134126 0.62743 -0.778557 -0.00671169 0.698423 -0.715653 0.00189863 0.462653 -0.886537 -0.00600005 0.976006 -0.217659 0.0114584 0.99574 0.0914908 0 0.999592 0.0285498 -0.00489331 -0.493189 -0.869909 0.00849859 -0.664677 -0.747083 -0.00422711 -0.738738 -0.67398 0.00530553 -0.906373 -0.422446 0 -0.920539 -0.39065 -0.00647145 -0.473411 -0.880818 0.0164958 -0.218759 -0.97564 2.87633e-06 -0.307225 -0.951637 4.79994e-07 -0.051271 -0.998685 0.00190185 -0.0160588 -0.999869 -0.00302708 0.15193 -0.988387 0 0.18717 -0.982328 0 0.71751 -0.696548 -0.00547205 0.76093 -0.648811 0.0194971 0.99904 0.0392382 1.72176e-06 0.989567 0.144074 -1.55003e-06 0.991553 -0.129703 -0.00413449 0.99778 -0.0664671 0.0134126 0.932646 -0.360544 -0.00671333 0.962679 -0.270563 0.00189765 0.843929 -0.536452 -0.00600154 0.954075 0.299509 0.0114569 0.816588 0.577108 0 0.85139 0.524533 -0.00486833 0.00747008 -0.99996 0.00849897 -0.20207 -0.979334 -0.0042292 -0.302782 -0.95305 0.00530369 -0.573724 -0.819032 0 -0.60188 -0.798586 -0.00647294 0.0304308 -0.999516 0.0164935 0.298367 -0.954309 1.74104e-06 0.209759 -0.977753 -6.04988e-08 0.454951 -0.890516 0.00190003 0.486018 -0.873947 -0.00302886 0.625758 -0.780012 0 0.653262 -0.757132 0 0.969665 -0.244439 -0.00547141 0.983396 -0.181393 0.0194938 0.84555 0.53354 6.34631e-06 0.784952 0.619557 3.92759e-06 0.92357 0.383429 -0.00417553 0.897031 0.441948 0.0134128 0.987969 0.154071 -0.00670944 0.968993 0.246995 0.00189921 0.999092 -0.0425703 -0.00600117 0.676495 0.736423 0.0114562 0.418644 0.908078 0 0.475068 0.879949 -0.00485984 0.506361 -0.862308 0.00850007 0.314673 -0.949162 -0.0042289 0.214309 -0.976757 0.00530401 -0.087347 -0.996164 0 -0.121957 -0.992535 -0.00647147 0.526111 -0.850392 0.0164955 0.735547 -0.677273 4.62501e-06 0.670536 -0.741877 3.39364e-06 0.839252 -0.543742 0.00190312 0.857868 -0.513867 -0.00302638 0.931934 -0.362616 0 0.944303 -0.329077 0 0.961978 0.273127 -0.0054698 0.942354 0.334574 0.0187184 0.458271 0.888616 0.00145927 0.369999 0.929031 -0.000531607 0.60162 0.798783 -0.00412687 0.556552 0.830802 0.0134135 0.778564 0.627422 -0.00671177 0.715658 0.698418 0.00189936 0.886552 0.462626 -0.00600196 0.217657 0.976007 0.0114561 -0.0914874 0.99574 0 -0.028559 0.999592 -0.00486303 0.869719 -0.493523 0.00850262 0.747094 -0.664664 -0.00422727 0.673969 -0.738748 0.00530489 0.422442 -0.906374 0 0.39065 -0.920539 -0.00647077 0.880836 -0.473376 0.0164901 0.975633 -0.218789 2.39631e-06 0.951637 -0.307226 4e-07 0.998685 -0.0512717 0.00190184 0.999869 -0.0160588 -0.00302613 0.988391 0.151902 0 0.982335 0.18713 0 0.696539 0.717519 -0.005471 0.64881 0.760931 0.0187256 -0.0473818 0.998701 0.00145878 -0.144081 0.989565 -0.000532303 0.121583 0.992581 -0.00413379 0.06645 0.997781 0.0134148 0.360553 0.932642 -0.0067111 0.270574 0.962676 0.00189933 0.536438 0.843937 -0.00600164 -0.299516 0.954073 0.0114549 -0.577092 0.816598 0 -0.524526 0.851394 -0.00485201 0.999962 0.0072125 0.00849851 0.979335 -0.202068 -0.00422813 0.953056 -0.302766 0.00530523 0.819029 -0.573728 0 0.798577 -0.601893 -0.00647387 0.999516 0.0304205 0.0164944 0.954304 0.298383 1.4134e-06 0.977751 0.209768 -7.69931e-07 0.89054 0.454905 0.00190126 0.873955 0.486003 -0.00302815 0.780006 0.625764 0 0.757132 0.653262 0 0.244473 0.969656 -0.00547256 0.181414 0.983392 0.0187231 -0.540407 0.841195 0.00145883 -0.61957 0.78494 -0.000531844 -0.390966 0.920405 -0.00414196 -0.441431 0.897285 0.0134128 -0.154071 0.987969 -0.00671339 -0.247013 0.968989 0.00189726 0.0426073 0.99909 -0.00600095 -0.736426 0.676492 0.0114569 -0.908083 0.418633 0 -0.879953 0.475061 -0.00487662 0.862176 0.506586 0.00850043 0.949161 0.314675 -0.00422759 0.976755 0.214319 0.00530555 0.996164 -0.0873425 0 0.992535 -0.121963 -0.00647083 0.850385 0.526121 0.0164946 0.677269 0.735551 4.49544e-07 0.741886 0.670526 -1.84422e-06 0.543755 0.839244 0.00189982 0.513847 0.85788 -0.00302863 0.362635 0.931926 0 0.329071 0.944305 0 0.957887 -0.287147 0 0.957887 -0.287147 0 0.68598 -0.72762 0 0.68598 -0.72762 0 0.230268 -0.973127 0 0.230268 -0.973127 0 -0.287149 -0.957886 0 -0.287149 -0.957886 0 -0.72762 -0.68598 0 -0.72762 -0.68598 0 -0.973127 -0.230267 0 -0.973127 -0.230267 0 0.957886 -0.287148 0 0.957886 -0.287148 0 0.68598 -0.727621 0 0.68598 -0.727621 0 0.230268 -0.973127 0 0.230268 -0.973127 0 -0.287149 -0.957886 0 -0.287149 -0.957886 0 -0.72762 -0.685981 0 -0.72762 -0.685981 0 -0.973128 -0.230267 0 -0.973128 -0.230267 0 0.957886 -0.287148 0 0.957886 -0.287148 0 0.685981 -0.72762 0 0.685981 -0.72762 0 0.230265 -0.973128 0 0.230265 -0.973128 0 -0.287148 -0.957886 0 -0.287148 -0.957886 0 -0.72762 -0.685981 0 -0.72762 -0.685981 0 -0.973128 -0.230265 0 -0.973128 -0.230265 0 0.957886 -0.287147 0 0.957886 -0.287147 0 0.685979 -0.727621 0 0.685979 -0.727621 0 0.230268 -0.973127 0 0.230268 -0.973127 0 -0.287149 -0.957886 0 -0.287149 -0.957886 0 -0.727619 -0.685982 0 -0.727619 -0.685982 0 -0.973128 -0.230265 0 -0.973128 -0.230265 0 0.957886 -0.287149 0 0.957886 -0.287149 0 0.685982 -0.727619 0 0.685982 -0.727619 0 0.230267 -0.973127 0 0.230267 -0.973127 0 -0.287149 -0.957886 0 -0.287149 -0.957886 0 -0.727621 -0.685979 0 -0.727621 -0.685979 0 -0.973127 -0.230267 0 -0.973127 -0.230267 0 0.967953 -0.251131 0 0.967953 -0.251131 0 0.763135 -0.646239 0 0.763135 -0.646239 0 0.407169 -0.913353 0 0.407169 -0.913353 0 -0.0294436 -0.999566 0 -0.0294436 -0.999566 0 -0.46022 -0.887805 0 -0.46022 -0.887805 0 -0.799854 -0.600194 0 -0.799854 -0.600194 0 -0.981057 -0.193719 0 -0.981057 -0.193719 0 0.967954 -0.251129 0 0.967954 -0.251129 0 0.76313 -0.646245 0 0.76313 -0.646245 0 0.407169 -0.913353 0 0.407169 -0.913353 0 -0.0294439 -0.999566 0 -0.0294439 -0.999566 0 -0.460224 -0.887803 0 -0.460224 -0.887803 0 -0.799847 -0.600203 0 -0.799847 -0.600203 0 -0.981057 -0.193718 0 -0.981057 -0.193718 0 0.967951 -0.25114 0 0.967951 -0.25114 0 0.763138 -0.646236 0 0.763138 -0.646236 0 0.407171 -0.913352 0 0.407171 -0.913352 0 -0.0294433 -0.999566 0 -0.0294433 -0.999566 0 -0.460228 -0.887801 0 -0.460228 -0.887801 0 -0.799851 -0.600198 0 -0.799851 -0.600198 0 -0.981057 -0.193718 0 -0.981057 -0.193718 0 0.957886 -0.287149 0 0.957886 -0.287149 0 0.685978 -0.727622 0 0.685978 -0.727622 0 0.230269 -0.973127 0 0.230269 -0.973127 0 -0.287144 -0.957887 0 -0.287144 -0.957887 0 -0.727625 -0.685976 0 -0.727625 -0.685976 0 -0.973125 -0.230276 0 -0.973125 -0.230276 0 0.957886 -0.287149 0 0.957886 -0.287149 0 0.685984 -0.727617 0 0.685984 -0.727617 0 0.230263 -0.973128 0 0.230263 -0.973128 0 -0.287143 -0.957888 0 -0.287143 -0.957888 0 -0.727626 -0.685975 0 -0.727626 -0.685975 0 -0.973127 -0.230268 0 -0.973127 -0.230268 0 0.967954 -0.251129 0 0.967954 -0.251129 0 0.763135 -0.646239 0 0.763135 -0.646239 0 0.407169 -0.913353 0 0.407169 -0.913353 0 -0.0294436 -0.999566 0 -0.0294436 -0.999566 0 -0.46022 -0.887805 0 -0.46022 -0.887805 0 -0.799852 -0.600197 0 -0.799852 -0.600197 0 -0.981057 -0.193717 0 -0.981057 -0.193717 0 -0.957886 0.287148 0 -0.957886 0.287148 0 0.957887 -0.287147 0 0.957886 -0.287147 0 0.971129 -0.238554 -0.0171511 0.99762 -0.0667881 -0.000512025 0.999839 -0.0179565 0.000466562 0.951106 0.308864 -0.0160227 0.927821 0.372682 -5.59476e-05 0.857826 0.51394 7.29339e-05 0.770501 0.637439 -0.0170236 0.674225 0.73833 -0.0173317 0.675365 0.73728 3.27994e-05 0.124022 0.99228 -0.00905275 0.235845 0.971749 -0.0172986 0.287104 0.957743 -0.0016005 0.383797 0.923416 0.00130774 0.561461 0.827502 -6.55452e-05 -0.0463631 0.998925 -0.0179052 -0.156874 0.987456 0.000136122 -0.267914 0.963443 -8.92236e-05 -0.440368 0.897817 -0.017039 -0.569788 0.821615 0.00980293 -0.660679 0.750605 -0.0123805 -0.869907 0.49306 0 -0.888149 0.459555 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.727621 -0.68598 0 -0.727621 -0.68598 0 0.727619 0.685981 0 0.727619 0.685981 0 0.599006 0.800745 -0.0195927 0.546088 0.837499 -3.99125e-05 0.394543 0.918878 4.67812e-05 0.259619 0.965711 -0.0198233 0.103543 0.994427 -0.0220624 0.112379 0.99342 -1.90542e-05 -0.511168 0.859481 -0.0141367 -0.383033 0.923627 -0.0188549 -0.361849 0.932046 0.000119104 -0.221439 0.975174 -0.00012353 -0.036815 0.999322 2.52533e-05 -0.64338 0.765547 -0.018308 -0.747439 0.664078 0.000101859 -0.805576 0.592492 -4.43942e-05 -0.910588 0.413316 -0.0149165 -0.966433 0.256484 0 -0.980732 0.195359 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.287147 -0.957886 0 -0.287147 -0.957886 0 0.287148 0.957886 0 0.287148 0.957886 0 0.112293 0.993675 -0.0157764 0.0621252 0.997944 -2.72781e-05 -0.115974 0.993252 4.83827e-05 -0.25319 0.967417 -0.0198642 -0.385633 0.922439 -0.0160542 -0.401457 0.915737 2.6863e-05 -0.910052 0.414495 -4.31095e-05 -0.833495 0.552527 -0.0180887 -0.753873 0.656771 0.000197434 -0.68571 0.727875 -0.000117536 -0.519194 0.854657 -0.00812988 -0.94613 0.323684 -0.0176133 -0.966619 0.255613 0 -0.987028 0.160549 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.230266 -0.973128 0 0.230266 -0.973128 0 -0.230266 0.973128 0 -0.230266 0.973128 0 -0.382907 0.923787 -0.016458 -0.435372 0.9001 -3.78018e-05 -0.573469 0.819227 6.49578e-05 -0.69377 0.720196 -0.0187807 -0.774949 0.631745 -0.00925763 -0.80565 0.59232 0.00946219 -0.921503 0.388257 -0.0167174 -0.969365 0.245057 0 -0.992072 0.125671 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.685981 -0.727619 0 0.685981 -0.727619 0 -0.68598 0.72762 0 -0.68598 0.72762 0 -0.767328 0.641255 -0.0170075 -0.814633 0.579728 -0.000724213 -0.875256 0.483659 0.000946843 -0.947185 0.320685 -0.0155381 -0.974498 0.223856 0 -0.992281 0.124013 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.957886 -0.287148 0 0.957886 -0.287148 0 -0.957886 0.287148 0 -0.957886 0.287148 0 -0.987172 0.159661 0 -0.987172 0.159661 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.973128 0.230267 0 0.973128 0.230267 0 -0.973128 -0.230267 0 -0.973128 -0.230267 0 -0.960296 -0.278985 -0.0207809 -0.880181 -0.474183 -0.0136013 -0.871896 -0.489502 -2.55826e-05 -0.754157 -0.656695 7.75698e-05 -0.639848 -0.768501 -0.0260755 -0.525104 -0.850638 0.00215358 -0.409695 -0.91222 -0.000902158 -0.219729 -0.975561 -0.016839 -0.0294399 -0.999425 -0.0278922 -0.0681673 -0.997284 -0.0165742 0.48758 -0.872921 6.75933e-05 0.281857 -0.959457 -0.00012594 0.129255 -0.991611 -0.0769712 0.643831 -0.761286 0.000217867 0.474284 -0.880372 -0.00012461 0.786156 -0.618029 -0.0258757 0.850643 -0.525108 0.000128872 0.919401 -0.393321 -8.47493e-05 0.976962 -0.213414 -0.0244932 0.999267 -0.0294352 0 0.998938 0.0460814 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.727621 0.68598 0 0.727621 0.68598 0 -0.727621 -0.68598 0 -0.727621 -0.68598 0 -0.692151 -0.721753 -0.0207812 -0.525167 -0.850745 -0.0136021 -0.510334 -0.859868 -2.53521e-05 -0.324757 -0.945798 7.77322e-05 -0.169874 -0.985466 -0.0260755 -0.0294342 -0.999227 0.00215315 0.101301 -0.994853 -0.000902741 0.297505 -0.95472 -0.0168381 0.474217 -0.880247 -0.0278927 0.439603 -0.897759 -0.0165738 0.858717 -0.512181 6.72357e-05 0.723831 -0.689977 -0.000126161 0.607741 -0.794135 -0.0769683 0.938215 -0.337385 0.000218328 0.850927 -0.525283 -0.000123716 0.989845 -0.142149 -0.0258757 0.999232 -0.0294294 0.000126897 0.992886 0.119068 -8.64524e-05 0.95278 0.303663 -0.0244938 0.880108 0.474141 0 0.842064 0.539377 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.287146 0.957887 0 0.287146 0.957887 0 -0.287146 -0.957887 0 -0.287146 -0.957887 0 -0.238548 -0.971131 -0.0171478 -0.0667899 -0.99762 -0.000514378 -0.0179771 -0.999838 0.000467471 0.308856 -0.951109 -0.0160231 0.372681 -0.927821 -5.49249e-05 0.513933 -0.857831 7.43278e-05 0.637421 -0.770516 -0.017024 0.738332 -0.674222 -0.0173314 0.737285 -0.675359 3.36472e-05 0.992282 -0.124004 -0.00905616 0.971744 -0.235865 -0.0172988 0.957743 -0.287104 -0.00159851 0.92341 -0.383811 0.00130715 0.827503 -0.56146 -6.46775e-05 0.998925 0.0463558 -0.0179041 0.987456 0.156874 0.000135257 0.963448 0.267894 -9.00461e-05 0.89782 0.440362 -0.0170385 0.821613 0.569791 0.00979994 0.750617 0.660665 -0.0123786 0.493063 0.869905 0 0.459566 0.888144 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.230267 0.973127 0 -0.230267 0.973127 0 0.230265 -0.973128 0 0.230265 -0.973128 0 0.278996 -0.960292 -0.0171483 0.440969 -0.897358 -0.000511628 0.484362 -0.874868 0.00046696 0.743039 -0.669248 -0.0160223 0.786664 -0.617173 -5.73323e-05 0.873992 -0.485941 7.15051e-05 0.937292 -0.348545 -0.0170243 0.976526 -0.214726 -0.0173288 0.976191 -0.216221 3.4461e-05 0.92135 0.388734 -0.00905248 0.959486 0.28161 -0.0172966 0.972983 0.230226 -0.00160269 0.991598 0.12935 0.00130583 0.997367 -0.0725037 -6.39787e-05 0.841917 0.539607 -0.0179062 0.77672 0.629591 0.000134218 0.700409 0.713742 -9.07478e-05 0.557339 0.830285 -0.0170388 0.426645 0.904259 0.00980255 0.319705 0.947466 -0.0123808 -0.0079515 0.999892 0 -0.0460886 0.998937 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.685981 0.72762 0 -0.685981 0.72762 0 0.685981 -0.72762 0 0.685981 -0.72762 0 0.721763 -0.692141 -0.0171488 0.83057 -0.55665 -0.000511268 0.856905 -0.515474 0.000467107 0.978114 -0.208071 -0.0160232 0.989858 -0.141156 -5.66068e-05 0.999869 0.0161741 7.21979e-05 0.985994 0.166782 -0.0170249 0.953061 0.302299 -0.0173289 0.953518 0.300839 3.33298e-05 0.60355 0.797325 -0.00905093 0.690114 0.723644 -0.0172987 0.727512 0.685877 -0.00160134 0.794085 0.607805 0.00130682 0.899995 0.435898 -6.4908e-05 0.459311 0.888276 -0.017905 0.357868 0.9336 0.000136046 0.2497 0.968323 -8.92174e-05 0.0675326 0.997717 -0.0170381 -0.0826455 0.996433 0.00980237 -0.196858 0.980383 -0.0123812 -0.506833 0.861956 0 -0.539384 0.84206 -0.62908 -0.151779 0.762379 -0.686233 -0.142877 0.713211 -0.698211 -0.141429 0.701783 -0.781955 -0.143533 0.606585 -0.690897 -0.181599 0.699774 -0.667216 -0.187879 0.72078 -0.553186 -0.210965 0.805903 0 -0.285538 0.958367 -0.00493375 -0.334612 0.942343 0.00256215 -0.495608 0.868543 6.36671e-07 -0.539109 0.842236 3.53e-06 -0.718239 0.695797 0.00348747 -0.702718 0.71146 -0.00158683 -0.856961 0.515379 -0.00330281 -0.869083 0.494655 0.00764344 -0.966994 0.254685 0.0110211 -0.961537 0.274453 0 -0.995314 0.0967006 -0.00486197 0.493579 0.869688 0.00850026 0.664667 0.747092 -0.00422711 0.738738 0.67398 0.00530577 0.906376 0.422439 0 0.920543 0.390642 -0.00647282 0.473394 0.880827 0.0164928 0.218755 0.97564 -5.75265e-07 0.307223 0.951638 -2.71607e-06 0.0513287 0.998682 0.00190182 0.0160588 0.999869 -0.00302679 -0.151928 0.988387 0 -0.187163 0.982329 0 0.967953 -0.251131 0 0.967953 -0.251131 0 0.763137 -0.646236 0 0.763137 -0.646236 0 0.407161 -0.913357 0 0.407161 -0.913357 0 -0.0294438 -0.999566 0 -0.0294438 -0.999566 0 -0.46022 -0.887805 0 -0.46022 -0.887805 0 -0.799848 -0.600203 0 -0.799848 -0.600203 0 -0.981057 -0.193717 0 -0.981057 -0.193717 0 -0.973128 -0.230265 0 -0.973128 -0.230265 0 0.973127 0.230267 0 0.973127 0.230267 0.00051691 -0.19051 0.981685 -3.18976e-05 0.788181 0.615443 0 0.946574 0.322486 -0.0259636 0.890208 0.454813 -0.0174213 0.875531 0.482848 -0.00595517 0.828885 0.559388 4.71189e-05 0.706529 0.707684 -0.0196155 0.579701 0.814593 -0.0243231 0.594116 0.804012 -0.000609179 0.0136156 0.999907 -0.0255273 0.172788 0.984628 -0.017087 0.138068 0.990275 7.73021e-05 0.303438 0.952851 -0.000110128 0.462176 0.886788 -0.0206999 -0.731944 0.681051 -0.00409204 -0.656451 0.754358 0.0100155 -0.334822 0.942228 -0.060883 -0.506346 0.860179 -0.0221606 -0.358849 0.933133 0 -0.963923 0.266183 -0.06506 -0.990799 0.118681 -0.0155058 -0.960899 0.276464 0.00126123 -0.892853 0.450347 -0.00292737 -0.79249 0.609878 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.705614 0.703343 -0.0861275 -0.705615 0.703342 -0.0861273 -0.705615 0.67554 -0.2139 -0.705614 0.675541 -0.2139 -0.705614 0.624735 -0.334388 -0.705616 0.624733 -0.334387 -0.705616 0.552652 -0.443488 -0.705613 0.552655 -0.44349 -0.705612 0.461754 -0.537489 -0.705616 0.461751 -0.537486 -0.705615 0.355127 -0.613182 -0.705611 0.355129 -0.613185 -0.705611 0.23641 -0.668 -0.705614 0.236409 -0.667997 -0.705615 0.109639 -0.700062 -0.70561 0.10964 -0.700067 -0.705609 -0.020864 -0.708294 -0.705614 -0.0208637 -0.708289 -0.705615 -0.150656 -0.692395 -0.70561 -0.150657 -0.6924 -0.70561 -0.27532 -0.652927 -0.705615 -0.275318 -0.652922 -0.705616 -0.390604 -0.591215 -0.70561 -0.390607 -0.59122 -0.705609 -0.492594 -0.50938 -0.705619 -0.492586 -0.509372 -0.70562 -0.577795 -0.410187 -0.705612 -0.577802 -0.410191 -0.705613 -0.643335 -0.297036 -0.705609 -0.643339 -0.297037 -0.705608 -0.686966 -0.173766 -0.705611 -0.686963 -0.173766 -0.705611 -0.707196 -0.0445787 -0.705615 -0.707191 -0.0445785 0.705615 -0.707191 -0.0445784 0.705611 -0.707196 -0.0445788 0.705611 -0.686963 -0.173766 0.705608 -0.686966 -0.173766 0.705609 -0.643339 -0.297037 0.705613 -0.643335 -0.297036 0.705612 -0.577801 -0.410191 0.70562 -0.577795 -0.410186 0.705619 -0.492586 -0.509372 0.705609 -0.492593 -0.50938 0.70561 -0.390607 -0.59122 0.705616 -0.390604 -0.591214 0.705615 -0.275318 -0.652922 0.70561 -0.27532 -0.652927 0.70561 -0.150657 -0.6924 0.705615 -0.150656 -0.692395 0.705614 -0.0208639 -0.708289 0.705609 -0.0208638 -0.708294 0.70561 0.10964 -0.700067 0.705615 0.109639 -0.700062 0.705614 0.236408 -0.667997 0.705611 0.23641 -0.668 0.705611 0.355129 -0.613185 0.705615 0.355127 -0.613182 0.705616 0.461751 -0.537486 0.705612 0.461754 -0.537489 0.705613 0.552655 -0.44349 0.705616 0.552652 -0.443488 0.705616 0.624733 -0.334387 0.705614 0.624735 -0.334388 0.705614 0.675541 -0.2139 0.705615 0.67554 -0.2139 0.705615 0.703342 -0.0861274 0.705614 0.703343 -0.0861275 -0.830975 0.496172 -0.251583 -0.830977 -0.154153 -0.534522 -0.96578 0.258259 -0.0239001 -0.980699 0.190896 -0.0422761 -0.9807 -0.195408 -0.00652582 -0.980699 -0.195415 -0.00652594 -0.980699 -0.0541802 -0.187869 -0.980699 -0.0541798 -0.187867 -0.980699 -0.0772985 -0.179595 -0.980699 0.174386 -0.0884224 -0.9807 0.174385 -0.0884216 -0.9807 0.161927 -0.109581 -0.896499 -0.442799 -0.0147874 -0.830983 -0.555963 -0.0192756 -0.792828 -0.609106 -0.020342 -0.55479 -0.128535 -0.822002 -0.830976 -0.0859443 -0.549629 -0.830977 -0.0859442 -0.549628 -0.980699 -0.0302069 -0.193178 -0.980699 -0.0302068 -0.193178 -0.554782 0.783362 -0.280288 -0.830974 0.523792 -0.187413 -0.830975 0.523791 -0.187413 -0.980699 0.184093 -0.0658688 -0.980699 0.184092 -0.0658683 -0.554762 -0.798515 -0.233695 -0.195076 -0.868281 -0.456108 -0.194716 -0.89942 -0.391317 -0.554799 -0.762906 -0.331923 -0.5548 -0.79849 -0.233689 -0.830998 -0.533881 -0.156247 -0.9807 -0.187646 -0.0549171 -0.9807 -0.179283 -0.0780019 -0.830966 -0.510133 -0.221947 -0.830967 -0.478292 -0.284133 -0.55477 -0.715306 -0.424933 -0.554773 -0.656406 -0.511232 -0.980699 -0.168099 -0.0998603 -0.980699 -0.154257 -0.120141 -0.83098 -0.438893 -0.341826 -0.830979 -0.392591 -0.394139 -0.5548 -0.587143 -0.589458 -0.554796 -0.508635 -0.6584 -0.194719 -0.599649 -0.776212 -0.195046 -0.532559 -0.823613 -0.980701 -0.137978 -0.138522 -0.980701 -0.119529 -0.154723 -0.83097 -0.340105 -0.440246 -0.830971 -0.282245 -0.479401 -0.554781 -0.422111 -0.716966 -0.554783 -0.328922 -0.764217 -0.9807 -0.119532 -0.154727 -0.9807 -0.0991966 -0.168488 -0.830981 -0.282237 -0.479388 -0.83098 -0.219929 -0.510982 -0.554766 -0.328926 -0.764227 -0.554768 -0.23055 -0.799425 -0.194734 -0.271796 -0.942446 -0.195099 -0.205376 -0.95904 -0.5548 0.0799265 -0.828135 -0.195096 0.29187 -0.936349 -0.194754 0.21585 -0.956807 -0.554794 0.18309 -0.811592 -0.554794 0.0799268 -0.82814 -0.83097 0.0534439 -0.553744 -0.9807 0.0187831 -0.194616 -0.9807 0.0430268 -0.190727 -0.830971 0.122424 -0.542677 -0.830971 0.189475 -0.523054 -0.554797 0.283365 -0.782243 -0.554799 0.379171 -0.740559 -0.980699 0.0665924 -0.183831 -0.980699 0.0891073 -0.174036 -0.830968 0.253539 -0.495187 -0.830968 0.313604 -0.459506 -0.554796 0.468999 -0.687198 -0.554797 0.551429 -0.622998 -0.194727 0.650099 -0.734474 -0.195024 0.713948 -0.672491 -0.980699 0.11022 -0.161499 -0.980699 0.129592 -0.146411 -0.830981 0.368709 -0.416563 -0.83098 0.418012 -0.367067 -0.554776 0.625174 -0.548982 -0.554777 0.689049 -0.466298 -0.980699 0.129591 -0.146411 -0.980699 0.14692 -0.129014 -0.830973 0.418019 -0.367074 -0.830973 0.46073 -0.311788 -0.554791 0.689042 -0.466292 -0.55479 0.742051 -0.376256 -0.194727 0.874825 -0.443579 -0.195079 0.906213 -0.37513 -0.607961 -0.793525 -0.026501 -0.554801 -0.831496 -0.0284764 -0.441493 -0.896765 -0.0299483 -0.194802 -0.980296 -0.0327379 -0.19475 -0.980307 -0.0327374 -0.9807 -0.193049 -0.0309656 -0.830999 -0.549253 -0.0881017 -0.830963 -0.549306 -0.0881091 -0.554763 -0.821508 -0.13177 -0.55478 -0.821496 -0.131769 -0.751899 -0.650957 -0.104414 -0.195115 -0.97365 -0.118048 -0.19469 -0.899425 -0.391318 -0.19504 -0.92673 -0.32114 -0.662108 -0.71924 -0.210494 -0.194884 -0.945095 -0.262326 -0.19497 -0.964346 -0.178951 -0.980697 -0.193068 -0.0309682 -0.980697 -0.187664 -0.0549219 -0.830974 -0.533916 -0.156257 -0.830974 -0.510122 -0.221942 -0.554813 -0.762897 -0.331919 -0.554812 -0.715281 -0.424919 -0.599455 -0.688142 -0.408797 -0.194727 -0.692205 -0.694934 -0.195025 -0.752294 -0.629301 -0.762157 -0.510758 -0.397797 -0.194995 -0.790329 -0.580824 -0.194855 -0.837967 -0.509747 -0.9807 -0.179284 -0.0780023 -0.9807 -0.168094 -0.0998576 -0.830977 -0.478278 -0.284125 -0.830976 -0.438897 -0.341829 -0.554784 -0.6564 -0.511228 -0.554783 -0.587151 -0.589466 -0.194709 -0.692208 -0.694937 -0.194711 -0.59965 -0.776214 -0.980698 -0.15426 -0.120143 -0.980698 -0.137986 -0.13853 -0.830973 -0.392598 -0.394145 -0.830974 -0.340101 -0.440242 -0.554794 -0.508636 -0.658402 -0.554795 -0.422106 -0.716959 -0.733547 -0.344813 -0.585674 -0.194747 -0.271795 -0.942444 -0.19509 -0.346478 -0.917547 -0.70487 -0.28043 -0.65155 -0.194895 -0.403425 -0.894016 -0.194923 -0.479805 -0.855448 -0.980699 -0.0991994 -0.168493 -0.980699 -0.0772993 -0.179597 -0.830978 -0.219931 -0.510986 -0.830978 -0.154153 -0.534521 -0.554782 -0.230547 -0.799416 -0.554783 -0.128536 -0.822006 -0.508106 -0.133062 -0.850954 -0.194806 -0.144762 -0.9701 -0.980699 -0.00575707 -0.195441 -0.83097 -0.0163803 -0.556076 -0.830976 -0.0163798 -0.556067 -0.554802 -0.0244967 -0.831622 -0.554792 -0.0244971 -0.831629 -0.765434 -0.0189477 -0.643236 -0.195008 -0.0596583 -0.978986 -0.194742 0.21585 -0.95681 -0.195107 0.148569 -0.969464 -0.508113 0.0827419 -0.857307 -0.194793 0.0874086 -0.976942 -0.19499 0.00192997 -0.980803 -0.9807 -0.00575678 -0.195434 -0.9807 0.018783 -0.194615 -0.830972 0.0534436 -0.553741 -0.830973 0.122424 -0.542676 -0.554779 0.183092 -0.811602 -0.554779 0.283369 -0.782255 -0.704863 0.241594 -0.666934 -0.194754 0.552916 -0.810157 -0.195083 0.483152 -0.853526 -0.733557 0.309736 -0.604944 -0.194927 0.428619 -0.882207 -0.194899 0.350101 -0.916212 -0.980699 0.0430272 -0.190729 -0.980699 0.0665928 -0.183833 -0.830977 0.189472 -0.523047 -0.830976 0.253534 -0.495176 -0.554778 0.379178 -0.740571 -0.554779 0.469005 -0.687208 -0.194729 0.552919 -0.810162 -0.194731 0.650099 -0.734473 -0.9807 0.0891052 -0.174031 -0.9807 0.110215 -0.161491 -0.830972 0.3136 -0.459501 -0.830972 0.368718 -0.416573 -0.554772 0.55144 -0.623011 -0.554773 0.625175 -0.548984 -0.762146 0.486467 -0.42718 -0.194729 0.874825 -0.443579 -0.19509 0.839927 -0.506422 -0.599475 0.662874 -0.448584 -0.194849 0.80651 -0.558189 -0.194993 0.75477 -0.626339 -0.9807 0.146915 -0.12901 -0.9807 0.161926 -0.10958 -0.830968 0.460735 -0.311792 -0.830969 0.496179 -0.251587 -0.554788 0.742052 -0.376257 -0.554789 0.783358 -0.280286 -0.662131 0.705583 -0.252458 -0.194878 0.928017 -0.317501 -0.195047 0.965028 -0.175153 -0.980699 0.190896 -0.0422761 -0.830974 0.543151 -0.120287 -0.830975 0.54315 -0.120287 -0.554781 0.812315 -0.179896 -0.554782 0.812314 -0.179896 -0.751911 0.64367 -0.142548 -0.194964 0.952141 -0.235406 -0.980681 0.194904 -0.0166244 -0.792782 0.606814 -0.05722 -0.830974 0.553945 -0.0512636 -0.607968 0.790584 -0.0731628 -0.554802 0.828377 -0.0773703 -0.258364 0.962034 -0.0879689 -0.194732 0.976683 -0.0903849 0.793116 0.607445 -0.0444721 0.896679 -0.442638 -0.00627925 0.608353 -0.793587 -0.0112575 0.194942 -0.980716 -0.0139111 0.441857 -0.896995 -0.0127245 0.258635 -0.965855 -0.015222 0.258619 -0.961013 -0.0978334 0.258604 -0.961016 -0.0978343 0.258604 -0.948833 -0.181218 0.258617 -0.94883 -0.181217 0.258617 -0.929425 -0.263223 0.25858 -0.929434 -0.263227 0.25858 -0.902956 -0.343231 0.258632 -0.902943 -0.343225 0.25863 -0.869593 -0.420616 0.258589 -0.869603 -0.420622 0.258589 -0.829634 -0.494812 0.258587 -0.829635 -0.494812 0.258587 -0.783352 -0.565236 0.25861 -0.783348 -0.565232 0.25861 -0.731103 -0.631355 0.25859 -0.731107 -0.631359 0.258591 -0.673298 -0.692676 0.258604 -0.673296 -0.692674 0.258603 -0.610363 -0.74872 0.258601 -0.610363 -0.74872 0.258601 -0.542786 -0.799067 0.258593 -0.542787 -0.799069 0.258591 -0.471079 -0.843336 0.258588 -0.471079 -0.843337 0.258586 -0.395785 -0.881185 0.258601 -0.395784 -0.881181 0.258604 -0.317477 -0.912323 0.258582 -0.317478 -0.912328 0.258582 -0.236756 -0.936527 0.258591 -0.236755 -0.936524 0.25859 -0.154231 -0.953595 0.258603 -0.154231 -0.953592 0.258604 -0.0705328 -0.963405 0.258586 -0.0705325 -0.96341 0.258589 0.0137025 -0.96589 0.258597 0.0137022 -0.965888 0.258598 0.0978325 -0.961018 0.258604 0.0978321 -0.961017 0.258604 0.181218 -0.948833 0.258593 0.181219 -0.948836 0.258592 0.263226 -0.929431 0.258605 0.263225 -0.929428 0.258605 0.343228 -0.90295 0.258594 0.343229 -0.902952 0.258595 0.420621 -0.869602 0.258609 0.420619 -0.869598 0.258608 0.494809 -0.82963 0.258587 0.494812 -0.829635 0.258587 0.565236 -0.783352 0.258578 0.565238 -0.783354 0.258578 0.631361 -0.731109 0.25859 0.631359 -0.731107 0.258591 0.692676 -0.673298 0.258589 0.692677 -0.673299 0.258589 0.748723 -0.610366 0.258601 0.74872 -0.610364 0.258601 0.799067 -0.542786 0.258596 0.799069 -0.542787 0.258595 0.843335 -0.471078 0.258597 0.843335 -0.471078 0.258597 0.881183 -0.395784 0.2586 0.881182 -0.395783 0.2586 0.912324 -0.317477 0.258593 0.912326 -0.317477 0.258593 0.936524 -0.236755 0.2586 0.936522 -0.236755 0.2586 0.953593 -0.154231 0.258599 0.953593 -0.154231 0.258599 0.963406 -0.0705327 0.258594 0.963408 -0.0705326 0.60836 0.791543 -0.0579502 0.706816 0.705357 -0.0536816 0.706774 0.698365 -0.112951 0.706771 0.698367 -0.112951 0.706771 0.685865 -0.173388 0.706774 0.685862 -0.173388 0.706774 0.668141 -0.232505 0.706775 0.66814 -0.232504 0.706775 0.645333 -0.289852 0.706775 0.645334 -0.289852 0.706774 0.617616 -0.344994 0.706777 0.617613 -0.344992 0.706777 0.585195 -0.397508 0.706767 0.585204 -0.397513 0.706767 0.548331 -0.447005 0.706776 0.548324 -0.446999 0.706777 0.507279 -0.493087 0.706768 0.507285 -0.493093 0.706767 0.462379 -0.53543 0.706781 0.46237 -0.53542 0.706782 0.413945 -0.57368 0.706777 0.413948 -0.573684 0.706777 0.362373 -0.607579 0.706772 0.362376 -0.607584 0.706772 0.308042 -0.636854 0.706774 0.308041 -0.636852 0.706775 0.251363 -0.661276 0.706766 0.251367 -0.661284 0.706766 0.192776 -0.680676 0.706773 0.192773 -0.680669 0.706773 0.132716 -0.694881 0.706779 0.132714 -0.694874 0.706779 0.0716472 -0.703797 0.706771 0.0716482 -0.703804 0.706773 0.010035 -0.707369 0.706779 0.0100346 -0.707363 0.706779 -0.0516544 -0.705546 0.706778 -0.0516544 -0.705547 0.706779 -0.11295 -0.698359 0.706769 -0.112951 -0.698369 0.706769 -0.173389 -0.685868 0.706774 -0.173387 -0.685862 0.706774 -0.232505 -0.668141 0.70677 -0.232506 -0.668145 0.706771 -0.289853 -0.645337 0.706769 -0.289854 -0.645339 0.706769 -0.344996 -0.617621 0.706763 -0.344999 -0.617626 0.706762 -0.397516 -0.585207 0.706767 -0.397514 -0.585203 0.706767 -0.447005 -0.548331 0.706781 -0.446996 -0.54832 0.706781 -0.493084 -0.507276 0.706776 -0.493087 -0.507279 0.706776 -0.535424 -0.462373 0.706772 -0.535427 -0.462376 0.706772 -0.573688 -0.413951 0.706767 -0.573692 -0.413954 0.706766 -0.607588 -0.362378 0.706772 -0.607584 -0.362376 0.706772 -0.636855 -0.308042 0.706755 -0.636869 -0.30805 0.706755 -0.661295 -0.251371 0.706781 -0.66127 -0.25136 0.706781 -0.680662 -0.192771 0.706771 -0.680671 -0.192774 0.706771 -0.694882 -0.132716 0.706743 -0.69491 -0.132723 0.706742 -0.703833 -0.0716519 0.706785 -0.703791 -0.0716458 0.706828 -0.707282 -0.0120695 0.793129 -0.608992 -0.00863916 0.980737 -0.195312 -0.00277038 0.965859 -0.259017 -0.00520159 0.965843 -0.257795 -0.0262442 0.965849 -0.257772 -0.0262412 0.965849 -0.254505 -0.0486075 0.965841 -0.254533 -0.048614 0.965841 -0.249328 -0.070613 0.965846 -0.24931 -0.0706074 0.965846 -0.242207 -0.0920674 0.965847 -0.242207 -0.0920671 0.965847 -0.233261 -0.112827 0.965846 -0.233264 -0.112828 0.965846 -0.222542 -0.132729 0.965848 -0.222536 -0.132725 0.965848 -0.210122 -0.151616 0.965846 -0.210126 -0.151618 0.965846 -0.196112 -0.169355 0.965846 -0.196111 -0.169355 0.965846 -0.180605 -0.185803 0.965845 -0.180609 -0.185807 0.965845 -0.163728 -0.200841 0.965846 -0.163725 -0.200838 0.965846 -0.145597 -0.214343 0.965848 -0.145594 -0.214337 0.965848 -0.126359 -0.226211 0.965847 -0.126361 -0.226215 0.965847 -0.106164 -0.236367 0.965847 -0.106164 -0.236367 0.965847 -0.0851593 -0.244719 0.965847 -0.0851592 -0.244719 0.965847 -0.0635063 -0.25121 0.965848 -0.0635057 -0.251207 0.965848 -0.0413701 -0.255787 0.965846 -0.041371 -0.255794 0.965846 -0.0189199 -0.258426 0.965845 -0.01892 -0.258428 0.965845 0.00367567 -0.259094 0.965846 0.00367543 -0.259089 0.965847 0.0262425 -0.257782 0.965846 0.0262428 -0.257785 0.965846 0.0486102 -0.254517 0.965846 0.0486103 -0.254517 0.965846 0.0706083 -0.249312 0.965847 0.0706073 -0.249309 0.965847 0.0920673 -0.242206 0.965847 0.0920675 -0.242207 0.965847 0.112827 -0.233261 0.965846 0.112828 -0.233264 0.965846 0.132729 -0.222542 0.965846 0.132728 -0.222541 0.965846 0.151619 -0.210126 0.965846 0.151619 -0.210127 0.965846 0.169356 -0.196112 0.965846 0.169355 -0.196111 0.965846 0.185803 -0.180605 0.965846 0.185803 -0.180605 0.965846 0.200836 -0.163724 0.965847 0.200836 -0.163723 0.965847 0.214341 -0.145596 0.965846 0.214343 -0.145598 0.965846 0.226217 -0.126363 0.965846 0.226217 -0.126362 0.965846 0.23637 -0.106165 0.965847 0.236367 -0.106165 0.965846 0.244721 -0.0851599 0.965846 0.244722 -0.0851601 0.965846 0.251213 -0.0635071 0.965846 0.251212 -0.063507 0.965846 0.255791 -0.0413707 0.965846 0.255792 -0.0413708 0.965846 0.258424 -0.0189197 0.965846 0.258424 -0.0189197 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.0292509 -0.328516 -0.944045 0 0.995745 -0.092149 -0.0769847 0.994371 -0.0727995 0.0535617 0.982512 -0.178327 0 0.987172 -0.159662 0 0.97077 -0.240012 0.0128743 0.96942 -0.245071 -0.0146276 0.946056 -0.323672 0 0.94445 -0.328656 0 0.923965 -0.382478 0.0265226 0.91189 -0.409576 -0.0628796 0.890133 -0.451341 0.0222343 0.872815 -0.487545 0.0163849 0.187575 -0.982114 -0.0613266 0.219649 -0.97365 0.0292524 0.272378 -0.961746 0 0.297588 -0.954694 0 0.355315 -0.934747 -0.00487574 0.356941 -0.934114 0.00468221 0.435426 -0.900212 0 0.437002 -0.899461 0 0.512234 -0.858846 0.0632638 0.49163 -0.868503 -0.0958685 0.582443 -0.807198 0.0148177 0.563648 -0.825882 -0.0105312 0.653553 -0.756808 -0.0473421 0.662044 -0.747968 0.0280822 0.716783 -0.696731 0 0.727925 -0.685656 0 0.775085 -0.631857 0.024376 0.769313 -0.638407 -0.029242 0.826852 -0.561659 0 0.822271 -0.569097 0 0.856382 -0.516343 -0.116174 -0.243432 -0.962935 0.0311795 -0.276966 -0.960374 0 -0.2094 -0.97783 0 -0.159662 -0.987172 -0.0341157 -0.147504 -0.988473 0.0245737 -0.0729939 -0.99703 0 -0.0608261 -0.998148 0 0.0141847 -0.999899 0.0341156 0.00196659 -0.999416 -0.0436417 0.101181 -0.99391 0 0.0891157 -0.996021 0 0.15148 -0.98846 0 -0.858846 -0.512234 -0.0243741 -0.85409 -0.519555 0.0195051 -0.81078 -0.585026 0 -0.805797 -0.592192 0 -0.756849 -0.653589 0.0438426 -0.766284 -0.641004 -0.0595657 -0.695768 -0.715792 -0.0132603 -0.705652 -0.708435 0.00897234 -0.631831 -0.775054 -0.0582221 -0.610314 -0.790017 0.0304208 -0.561639 -0.826823 0 -0.542987 -0.839741 0 -0.487665 -0.873031 0.00487691 -0.489183 -0.872168 -0.00507096 -0.409715 -0.912199 0 -0.411312 -0.911495 0 -0.353266 -0.935523 0 -0.999899 -0.0141832 -0.0535629 -0.998008 -0.0333286 0.0300333 -0.994409 -0.101234 0 -0.99273 -0.120361 0 -0.982246 -0.187599 0.0146331 -0.98311 -0.182433 -0.0163775 -0.962028 -0.272458 0 -0.963571 -0.267454 0 -0.934747 -0.355314 0.0826038 -0.941647 -0.326309 -0.137849 -0.891627 -0.431275 0.0490699 -0.915867 -0.398472 0 -0.885289 -0.465042 -0.202049 -0.976923 0.069267 -0.202047 -0.976923 0.0692672 -0.202047 -0.967867 0.149704 -0.202048 -0.967866 0.149704 -0.202212 -0.959939 0.193979 -0.148206 -0.96044 0.235774 -0.202048 -0.952198 0.229119 -0.202048 -0.930025 0.306968 -0.202049 -0.930025 0.306968 -0.202207 -0.913306 0.353532 -0.0930105 -0.912881 0.397488 -0.202051 -0.901499 0.38272 -0.202051 -0.866815 0.455858 -0.202049 -0.866816 0.455858 -0.202196 -0.840361 0.502902 -0.0930813 -0.839947 0.534626 -0.202135 -0.818872 0.537206 -0.202043 -0.779962 0.592315 -0.202051 -0.779962 0.592314 -0.202184 -0.743206 0.637783 -0.0806831 -0.741299 0.666308 -0.202163 -0.716217 0.667955 -0.202048 -0.671832 0.712614 -0.202045 -0.671833 0.712614 -0.202159 -0.624639 0.754293 -0.0806805 -0.621518 0.779234 -0.202179 -0.592932 0.779459 -0.202046 -0.545377 0.813475 -0.202051 -0.545377 0.813474 -0.202143 -0.488074 0.849071 -0.0930838 -0.484258 0.86996 -0.202196 -0.452565 0.868505 -0.202049 -0.404045 0.892146 -0.202044 -0.404045 0.892147 -0.202109 -0.337448 0.919392 -0.117735 -0.333585 0.935339 -0.202205 -0.299161 0.932532 -0.202048 -0.251692 0.946482 -0.202046 -0.251692 0.946482 -0.202081 -0.177098 0.963224 -0.154291 -0.174198 0.972548 -0.20221 -0.137135 0.969693 -0.202046 -0.0924741 0.975001 -0.202051 -0.0924744 0.974999 -0.202051 -0.0116431 0.979306 -0.202046 -0.0116427 0.979307 -0.202046 0.0692668 0.976923 -0.20204 0.0692673 0.976925 -0.20204 0.149705 0.967868 -0.20205 0.149704 0.967866 -0.202213 0.193975 0.959939 -0.148202 0.235774 0.960441 -0.202049 0.229119 0.952198 -0.202049 0.306968 0.930025 -0.202058 0.306967 0.930024 -0.202216 0.353527 0.913306 -0.0930083 0.397489 0.912881 -0.202043 0.382721 0.9015 -0.202043 0.455859 0.866817 -0.20204 0.45586 0.866817 -0.202187 0.502902 0.840363 -0.0930703 0.534626 0.839948 -0.202147 0.537206 0.818869 -0.202055 0.592313 0.779961 -0.202045 0.592315 0.779962 -0.202178 0.637783 0.743207 -0.0806777 0.666308 0.7413 -0.202163 0.667955 0.716217 -0.202048 0.712614 0.671832 -0.202052 0.712613 0.671832 -0.202167 0.754292 0.624637 -0.080691 0.779234 0.621517 -0.202179 0.779458 0.592933 -0.202046 0.813475 0.545377 -0.202046 0.813475 0.545377 -0.202138 0.849072 0.488075 -0.0930742 0.869961 0.484258 -0.202186 0.868507 0.452566 -0.202039 0.892147 0.404046 -0.202052 0.892145 0.404046 -0.202117 0.919391 0.337446 -0.117739 0.93534 0.333583 -0.202197 0.932533 0.299164 -0.850908 -0.524 0.0371533 -0.850907 -0.524 0.0371533 -0.850908 -0.519142 0.080298 -0.850908 -0.519142 0.080298 -0.850908 -0.510738 0.122894 -0.850907 -0.510738 0.122894 -0.850908 -0.498845 0.164651 -0.850908 -0.498845 0.164651 -0.850908 -0.483544 0.205282 -0.850908 -0.483545 0.205283 -0.850907 -0.464941 0.244512 -0.850908 -0.46494 0.244512 -0.850908 -0.44316 0.282071 -0.850907 -0.443162 0.282073 -0.850907 -0.418355 0.317705 -0.850908 -0.418354 0.317704 -0.850908 -0.390689 0.351166 -0.850907 -0.39069 0.351167 -0.850907 -0.360357 0.382231 -0.850907 -0.360357 0.382231 -0.850907 -0.327562 0.410683 -0.850907 -0.327562 0.410683 -0.850907 -0.292529 0.43633 -0.850906 -0.29253 0.436332 -0.850906 -0.255498 0.458999 -0.850909 -0.255496 0.458994 -0.850909 -0.21672 0.478525 -0.850909 -0.21672 0.478526 -0.850909 -0.176464 0.494788 -0.850908 -0.176464 0.494789 -0.850908 -0.135002 0.507672 -0.850908 -0.135002 0.507671 -0.850908 -0.092618 0.517085 -0.850907 -0.0926181 0.517087 -0.850907 -0.0496011 0.52297 -0.850907 -0.049601 0.52297 -0.850907 -0.0062448 0.52528 -0.85091 -0.00624523 0.525275 -0.85091 0.0371528 0.523997 -0.850907 0.0371534 0.524 -0.850907 0.0802983 0.519143 -0.850909 0.0802978 0.519141 -0.850909 0.122894 0.510737 -0.850908 0.122894 0.510737 -0.850908 0.16465 0.498844 -0.850908 0.16465 0.498844 -0.850908 0.205282 0.483544 -0.850907 0.205283 0.483545 -0.850907 0.244513 0.464942 -0.850907 0.244513 0.464942 -0.850907 0.282072 0.443162 -0.850908 0.282071 0.44316 -0.850909 0.317703 0.418353 -0.850907 0.317705 0.418355 -0.850907 0.351167 0.39069 -0.850909 0.351165 0.390687 -0.85091 0.382227 0.360354 -0.85091 0.382228 0.360354 -0.85091 0.41068 0.327559 -0.850909 0.410681 0.327559 -0.850909 0.436327 0.292527 -0.850909 0.436328 0.292527 -0.850909 0.458995 0.255496 -0.850908 0.458996 0.255497 -0.850908 0.478527 0.216721 -0.85091 0.478523 0.21672 -0.85091 0.494785 0.176463 -0.850907 0.49479 0.176464 -0.850907 0.507673 0.135002 -0.850911 0.507667 0.135001 -0.850911 0.517081 0.0926177 -0.850904 0.517092 0.0926185 -0.57326 -0.817322 0.0579509 -0.573261 -0.817321 0.0579507 -0.573261 -0.809744 0.125247 -0.573259 -0.809745 0.125247 -0.573259 -0.796636 0.191687 -0.573261 -0.796636 0.191687 -0.573261 -0.778085 0.256818 -0.57326 -0.778086 0.256818 -0.57326 -0.75422 0.320195 -0.57326 -0.75422 0.320195 -0.57326 -0.725203 0.381384 -0.57326 -0.725203 0.381384 -0.57326 -0.691231 0.439968 -0.573264 -0.691229 0.439967 -0.573264 -0.652536 0.495545 -0.573259 -0.652539 0.495547 -0.573259 -0.609388 0.547741 -0.57326 -0.609387 0.547741 -0.57326 -0.562074 0.596193 -0.573264 -0.562072 0.596191 -0.573264 -0.51092 0.64057 -0.573263 -0.51092 0.64057 -0.573263 -0.456277 0.680574 -0.573263 -0.456277 0.680574 -0.573263 -0.398517 0.715929 -0.573256 -0.398519 0.715933 -0.573256 -0.338037 0.746397 -0.57326 -0.338036 0.746394 -0.57326 -0.275245 0.77176 -0.57326 -0.275245 0.77176 -0.57326 -0.210573 0.791853 -0.573262 -0.210573 0.791852 -0.573262 -0.144463 0.806536 -0.573266 -0.144463 0.806534 -0.573266 -0.0773664 0.815708 -0.573261 -0.0773662 0.815712 -0.573261 -0.00974058 0.819315 -0.573259 -0.00974046 0.819316 -0.57326 0.0579509 0.817322 -0.573266 0.05795 0.817318 -0.573266 0.125246 0.80974 -0.573258 0.125247 0.809746 -0.573259 0.191688 0.796637 -0.573262 0.191687 0.796635 -0.573262 0.256817 0.778085 -0.573258 0.256819 0.778087 -0.573258 0.320196 0.754222 -0.57326 0.320195 0.75422 -0.57326 0.381384 0.725203 -0.573266 0.381382 0.725199 -0.573266 0.439965 0.691228 -0.573258 0.439969 0.691233 -0.573258 0.495548 0.652539 -0.573265 0.495545 0.652535 -0.573265 0.547738 0.609385 -0.573256 0.547743 0.609389 -0.573256 0.596195 0.562076 -0.573257 0.596194 0.562076 -0.573256 0.640574 0.510923 -0.573258 0.640573 0.510922 -0.573258 0.680577 0.456279 -0.573266 0.680572 0.456276 -0.573266 0.715926 0.398516 -0.573261 0.71593 0.398517 -0.573261 0.746393 0.338036 -0.573255 0.746398 0.338038 -0.573254 0.771764 0.275244 -0.573272 0.771752 0.275242 -0.573272 0.791845 0.210572 -0.573257 0.791856 0.210573 -0.573257 0.80654 0.144464 -0.57326 0.806537 0.144464 -0.202039 0.946483 0.251693 -0.202053 0.94648 0.251693 -0.202088 0.963222 0.177098 -0.154298 0.972547 0.174198 -0.202218 0.969692 0.137135 -0.850902 0.522978 0.0496018 -0.850904 0.522974 0.0496018 -0.573273 0.815704 0.077366 -0.57326 0.815713 0.0773656 -0.20206 0.974998 0.0924729 -0.202054 0.974999 0.0924725 -0.850905 0.525283 0.00624533 -0.850901 0.525288 0.00624491 -0.573266 0.819312 0.00974042 -0.573273 0.819307 0.0097411 -0.202046 0.979307 0.0116434 -0.20206 0.979304 0.0116446 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.991867 -0.127277 0 0.991867 -0.127277 0 0.947978 -0.318335 0 0.947978 -0.318335 0 0.867659 -0.49716 0 0.867659 -0.49716 0 0.753996 -0.656879 0 0.753996 -0.656879 0 0.611358 -0.791354 0 0.611358 -0.791354 0 0.445225 -0.895419 0 0.445225 -0.895419 0 0.261983 -0.965073 0 0.261983 -0.965073 0 0.0686726 -0.997639 0 0.0686726 -0.997639 0 -0.127277 -0.991867 0 -0.127277 -0.991867 0 -0.318335 -0.947978 0 -0.318335 -0.947978 0 -0.49716 -0.867659 0 -0.49716 -0.867659 0 -0.656879 -0.753996 0 -0.656879 -0.753996 0 -0.791354 -0.611358 0 -0.791354 -0.611358 0 -0.895418 -0.445226 0 -0.895418 -0.445226 0 -0.965073 -0.261983 0 -0.965073 -0.261983 0 -0.997639 -0.0686722 0 -0.997639 -0.0686722 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.997639 -0.0686725 0 -0.997639 -0.0686725 0 -0.965073 -0.261983 0 -0.965073 -0.261983 0 -0.895419 -0.445225 0 -0.895419 -0.445225 0 -0.791354 -0.611358 0 -0.791354 -0.611358 0 -0.656878 -0.753996 0 -0.656878 -0.753996 0 -0.497159 -0.867659 0 -0.497159 -0.867659 0 -0.318335 -0.947978 0 -0.318335 -0.947978 0 -0.127277 -0.991867 0 -0.127277 -0.991867 0 0.0686726 -0.997639 0 0.0686726 -0.997639 0 0.261983 -0.965073 0 0.261983 -0.965073 0 0.445225 -0.895419 0 0.445225 -0.895419 0 0.611358 -0.791354 0 0.611358 -0.791354 0 0.753996 -0.656879 0 0.753996 -0.656879 0 0.867659 -0.497159 0 0.867659 -0.497159 0 0.947978 -0.318334 0 0.947978 -0.318334 0 0.991867 -0.127277 0 0.991867 -0.127277 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.998019 -0.0629101 0 -0.998019 -0.0629101 0 -0.969466 -0.245225 0 -0.969466 -0.245225 0 -0.907899 -0.419188 0 -0.907899 -0.419188 0 -0.815415 -0.578877 0 -0.815415 -0.578877 0 -0.695163 -0.718852 0 -0.695163 -0.718852 0 -0.551238 -0.834348 0 -0.551238 -0.834348 0 -0.388541 -0.921432 0 -0.388541 -0.921432 0 -0.212612 -0.977137 0 -0.212612 -0.977137 0 -0.0294438 -0.999566 0 -0.0294438 -0.999566 0 0.154728 -0.987957 0 0.154728 -0.987957 0 0.333629 -0.942704 0 0.333629 -0.942704 0 0.50117 -0.865349 0 0.50117 -0.865349 0 0.651644 -0.758525 0 0.651644 -0.758525 0 0.779928 -0.62587 0 0.779928 -0.62587 0 0.881651 -0.471902 0 0.881651 -0.471902 0 0.953351 -0.301865 0 0.953351 -0.301865 0 0.992586 -0.121546 0 0.992586 -0.121546 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.993197 -0.11645 0 0.993197 -0.11645 0 0.957886 -0.287147 0 0.957886 -0.287147 0 0.893471 -0.44912 0 0.893471 -0.44912 0 0.801909 -0.597447 0 0.801909 -0.597447 0 0.68598 -0.72762 0 0.68598 -0.72762 0 0.549209 -0.835685 0 0.549209 -0.835685 0 0.39575 -0.918358 0 0.39575 -0.918358 0 0.230266 -0.973128 0 0.230266 -0.973128 0 0.057786 -0.998329 0 0.057786 -0.998329 0 -0.11645 -0.993197 0 -0.11645 -0.993197 0 -0.287147 -0.957886 0 -0.287147 -0.957886 0 -0.44912 -0.893471 0 -0.44912 -0.893471 0 -0.597447 -0.801909 0 -0.597447 -0.801909 0 -0.72762 -0.68598 0 -0.72762 -0.68598 0 -0.835685 -0.549208 0 -0.835685 -0.549208 0 -0.918358 -0.39575 0 -0.918358 -0.39575 0 -0.973128 -0.230266 0 -0.973128 -0.230266 0 -0.998329 -0.0577863 0 -0.998329 -0.0577863 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.983515 -0.180828 0 -0.990147 -0.14003 -0.01122 -0.998266 -0.0577825 -0.100448 -0.990497 -0.0939437 0 -0.999929 -0.0118885 -0.0844679 -0.96296 -0.256074 -0.0211923 -0.972909 -0.230215 0 -0.952202 -0.305469 0 -0.866969 -0.498362 0 -0.886824 -0.462108 -0.0299146 -0.917947 -0.395573 -0.069654 -0.908721 -0.411552 0 -0.938765 -0.344559 -0.0560282 -0.8293 -0.555987 -0.0373879 -0.835101 -0.548825 0 -0.795895 -0.605435 0 -0.682037 -0.731318 -0.043611 -0.726928 -0.685328 -0.0436108 -0.726928 -0.685328 0 -0.770196 -0.637808 0 -0.548529 -0.836131 -0.0485867 -0.596741 -0.800961 -0.0324152 -0.60447 -0.795968 0 -0.651234 -0.758877 0 -0.36099 -0.93257 0 -0.399218 -0.916856 -0.052317 -0.448505 -0.892248 -0.0224495 -0.465341 -0.884847 0 -0.513508 -0.858085 -0.0137231 -0.313403 -0.949521 -0.054802 -0.286716 -0.956447 0 -0.238406 -0.971166 0 -0.0707261 -0.997496 -0.0560438 -0.116267 -0.991636 -0.00623909 -0.152853 -0.988229 0 -0.198073 -0.980187 0 0.140035 -0.990147 -0.0112207 0.0577828 -0.998266 -0.100448 0.0939439 -0.990497 0 0.0118883 -0.999929 0 0.344558 -0.938765 0 0.305471 -0.952201 -0.0211926 0.230215 -0.972909 -0.0844675 0.256074 -0.96296 0 0.180829 -0.983515 -0.0696542 0.411552 -0.908721 -0.0299148 0.395572 -0.917948 0 0.462108 -0.886824 0 0.637807 -0.770197 0 0.605435 -0.795895 -0.0373878 0.548825 -0.835101 -0.0560289 0.555988 -0.8293 0 0.498362 -0.866969 -0.043612 0.685328 -0.726928 -0.0436114 0.685328 -0.726928 0 0.731318 -0.682037 0 0.836131 -0.548529 -0.048587 0.800961 -0.596741 -0.0324149 0.795968 -0.60447 0 0.758877 -0.651234 0 0.916855 -0.39922 -0.052315 0.892248 -0.448505 -0.022449 0.884847 -0.46534 0 0.858086 -0.513507 0 0.971165 -0.238407 -0.0548011 0.956447 -0.286716 -0.0137207 0.949521 -0.313404 0 0.932572 -0.360983 0 0.997496 -0.0707261 -0.0560435 0.991636 -0.116267 -0.00624009 0.988229 -0.152852 0 0.980186 -0.198079 0 0.991867 -0.127277 0 0.991867 -0.127277 0 0.947978 -0.318335 0 0.947978 -0.318335 0 0.867659 -0.497159 0 0.867659 -0.497159 0 0.753996 -0.656879 0 0.753996 -0.656879 0 0.611358 -0.791354 0 0.611358 -0.791354 0 0.445225 -0.895419 0 0.445225 -0.895419 0 0.261983 -0.965073 0 0.261983 -0.965073 0 0.0686725 -0.997639 0 0.0686725 -0.997639 0 -0.127277 -0.991867 0 -0.127277 -0.991867 0 -0.318335 -0.947978 0 -0.318335 -0.947978 0 -0.497159 -0.867659 0 -0.497159 -0.867659 0 -0.656879 -0.753996 0 -0.656879 -0.753996 0 -0.791354 -0.611358 0 -0.791354 -0.611358 0 -0.895419 -0.445225 0 -0.895419 -0.445225 0 -0.965072 -0.261983 0 -0.965072 -0.261983 0 -0.997639 -0.0686725 0 -0.997639 -0.0686725 0 0.992586 -0.121547 0 0.992586 -0.121547 0 0.953351 -0.301864 0 0.953351 -0.301864 0 0.881651 -0.471902 0 0.881651 -0.471902 0 0.779927 -0.62587 0 0.779927 -0.62587 0 0.651644 -0.758525 0 0.651644 -0.758525 0 0.50117 -0.865349 0 0.50117 -0.865349 0 0.333629 -0.942704 0 0.333629 -0.942704 0 0.154728 -0.987957 0 0.154728 -0.987957 0 -0.0294439 -0.999566 0 -0.0294439 -0.999566 0 -0.212612 -0.977137 0 -0.212612 -0.977137 0 -0.388541 -0.921432 0 -0.388541 -0.921432 0 -0.551237 -0.834348 0 -0.551237 -0.834348 0 -0.695163 -0.718852 0 -0.695163 -0.718852 0 -0.815415 -0.578877 0 -0.815415 -0.578877 0 -0.907899 -0.419188 0 -0.907899 -0.419188 0 -0.969466 -0.245224 0 -0.969466 -0.245224 0 -0.998019 -0.0629109 0 -0.998019 -0.0629109 0 0.992586 -0.121547 0 0.992586 -0.121547 0 0.953351 -0.301864 0 0.953351 -0.301864 0 0.881651 -0.471902 0 0.881651 -0.471902 0 0.779927 -0.62587 0 0.779927 -0.62587 0 0.651644 -0.758525 0 0.651644 -0.758525 0 0.50117 -0.865349 0 0.50117 -0.865349 0 0.333629 -0.942704 0 0.333629 -0.942704 0 0.154728 -0.987957 0 0.154728 -0.987957 0 -0.0294439 -0.999566 0 -0.0294439 -0.999566 0 -0.212612 -0.977137 0 -0.212612 -0.977137 0 -0.388541 -0.921432 0 -0.388541 -0.921432 0 -0.551237 -0.834348 0 -0.551237 -0.834348 0 -0.695163 -0.718852 0 -0.695163 -0.718852 0 -0.815415 -0.578877 0 -0.815415 -0.578877 0 -0.907899 -0.419188 0 -0.907899 -0.419188 0 -0.969466 -0.245224 0 -0.969466 -0.245224 0 -0.998019 -0.0629109 0 -0.998019 -0.0629109 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.705887 0.692775 0.147601 0.705876 0.692786 0.147603 0.705876 0.658761 0.260331 0.705876 0.658761 0.260331 0.705876 0.606532 0.365866 0.705872 0.606536 0.365868 0.705872 0.537544 0.461292 0.705879 0.537539 0.461288 0.705878 0.453695 0.543965 0.705872 0.453699 0.543969 0.705872 0.357316 0.611614 0.705873 0.357315 0.611612 0.705874 0.251057 0.662354 0.70587 0.251058 0.662357 0.705871 0.137862 0.694795 0.705874 0.137861 0.694792 0.705874 0.0208563 0.70803 0.705873 0.0208564 0.708031 0.705873 -0.0967256 0.701703 0.705873 -0.0967256 0.701703 0.705873 -0.211634 0.675984 0.705873 -0.211634 0.675984 0.705874 -0.320694 0.631583 0.705873 -0.320695 0.631584 0.705873 -0.420892 0.569731 0.705875 -0.420891 0.569729 0.705875 -0.509458 0.492131 0.705877 -0.509457 0.49213 0.705876 -0.583944 0.400933 0.705876 -0.583945 0.400933 0.705876 -0.642296 0.298656 0.705873 -0.642298 0.298657 0.705874 -0.682899 0.188127 0.705874 -0.682898 0.188127 0.705874 -0.692788 -0.147604 0.705874 -0.692788 -0.147604 0.705874 -0.658763 -0.260332 0.705874 -0.658763 -0.260332 0.705874 -0.606534 -0.365867 0.705875 -0.606533 -0.365866 0.705875 -0.537543 -0.461291 0.705874 -0.537543 -0.461291 0.705874 -0.453698 -0.543968 0.705875 -0.453697 -0.543966 0.705875 -0.357314 -0.61161 0.705875 -0.357314 -0.61161 0.705875 -0.251056 -0.662352 0.70588 -0.251054 -0.662348 0.70588 -0.13786 -0.694786 0.705873 -0.137862 -0.694793 0.705874 -0.0208559 -0.708031 0.705873 -0.0208559 -0.708031 0.705872 0.0967253 -0.701704 0.705882 0.0967244 -0.701694 0.705882 0.211632 -0.675975 0.705871 0.211634 -0.675986 0.70587 0.320696 -0.631587 0.705877 0.320693 -0.631581 0.705877 0.42089 -0.569728 0.705876 0.420891 -0.569728 0.705877 0.509457 -0.49213 0.705872 0.50946 -0.492133 0.705872 0.583948 -0.400936 0.705875 0.583946 -0.400934 0.705875 0.642296 -0.298656 0.705873 0.642298 -0.298657 0.705874 0.682899 -0.188127 0.705876 0.682897 -0.188126 -0.422559 0.895558 0.139354 -0.413968 0.900101 0.135827 -0.422614 0.898507 0.118665 -0.422526 0.88669 -0.187756 -0.411776 0.89064 -0.192875 -0.422612 0.889966 -0.171345 -0.422527 -0.88669 0.187756 -0.411777 -0.89064 0.192874 -0.422615 -0.889966 0.171341 -0.42256 -0.895558 -0.139354 -0.413966 -0.900102 -0.135826 -0.422615 -0.898508 -0.118658 -0.93985 -0.33923 -0.0400709 -0.939677 -0.339366 -0.0428668 -0.939714 -0.339284 -0.0427068 -0.939702 -0.339319 -0.0427033 -0.939762 -0.339263 -0.0418074 -0.939691 -0.33913 -0.0444041 -0.940695 -0.336328 -0.0444633 -0.940495 -0.336881 -0.044489 -0.939737 -0.339165 -0.0431493 -0.940046 -0.338961 -0.0376815 -0.940591 -0.337871 -0.0336349 -0.940962 -0.337001 -0.0319628 -0.939576 -0.342294 -0.00565851 -0.938802 -0.344432 -0.00409505 -0.93981 -0.340973 -0.0222583 -0.94012 -0.339813 -0.0264818 -0.940387 -0.325246 -0.0994395 -0.940247 -0.325629 -0.0995016 -0.939699 -0.327599 -0.0982078 -0.939685 -0.327696 -0.0980203 -0.939728 -0.327615 -0.0978779 -0.93978 -0.327349 -0.0982698 -0.939728 -0.32737 -0.0986892 -0.939825 -0.327677 -0.0967337 -0.939975 -0.327681 -0.0952464 -0.940231 -0.327612 -0.0929258 -0.940766 -0.326783 -0.0904014 -0.941077 -0.326264 -0.0890315 -0.942097 -0.324339 -0.0851888 -0.941616 -0.325381 -0.0865268 -0.940188 -0.331052 -0.0803152 -0.939767 -0.333015 -0.0770609 -0.93909 -0.338287 -0.0605923 -0.944609 -0.321606 -0.0654497 -0.942944 -0.326918 -0.0631034 -0.941633 -0.331066 -0.0610189 -0.940548 -0.334695 -0.0578646 -0.939668 -0.337877 -0.0535108 -0.940358 -0.336444 -0.0503291 -0.939669 -0.337996 -0.0527429 -0.939727 -0.336738 -0.0593254 -0.93975 -0.336681 -0.0592932 -0.939553 -0.338265 -0.0530819 -0.941745 -0.332331 -0.0516996 -0.941626 -0.332658 -0.0517635 -0.939671 -0.336931 -0.0591259 -0.939855 -0.336476 -0.0587914 -0.939888 -0.241748 -0.24118 -0.939793 -0.241052 -0.242245 -0.941378 -0.246892 -0.229896 -0.942082 -0.244032 -0.230067 -0.941333 -0.244021 -0.233122 -0.940271 -0.243192 -0.23822 -0.943023 -0.255522 -0.213109 -0.937987 -0.271022 -0.216167 -0.939927 -0.254705 -0.227296 -0.94029 -0.251994 -0.228809 -0.940637 -0.268288 -0.207905 -0.939628 -0.269363 -0.211049 -0.939732 -0.261958 -0.21973 -0.939746 -0.261938 -0.219696 -0.939425 -0.269619 -0.211628 -0.94305 -0.261939 -0.205046 -0.942939 -0.262183 -0.205246 -0.93967 -0.262226 -0.219677 -0.939865 -0.261987 -0.219129 -0.939701 -0.234598 -0.248849 -0.946018 -0.205785 -0.250403 -0.939781 -0.234345 -0.248784 -0.940313 -0.216046 -0.262938 -0.942724 -0.21489 -0.255136 -0.926975 -0.22687 -0.298744 -0.941577 -0.228059 -0.247834 -0.939972 -0.228122 -0.253797 -0.939696 -0.238211 -0.245412 -0.939687 -0.240004 -0.243692 -0.940169 -0.0995467 -0.325841 -0.941592 -0.10555 -0.319787 -0.944467 -0.116898 -0.30711 -0.932765 -0.140871 -0.331822 -0.941174 -0.107705 -0.320298 -0.942146 -0.103955 -0.318675 -0.940908 -0.132311 -0.311747 -0.939567 -0.132179 -0.315819 -0.939731 -0.116991 -0.321276 -0.939754 -0.11699 -0.32121 -0.939276 -0.132211 -0.316672 -0.944295 -0.127188 -0.303529 -0.944185 -0.127306 -0.303823 -0.93967 -0.117276 -0.32135 -0.939842 -0.117334 -0.320827 -0.939702 -0.0787203 -0.332812 -0.945377 -0.0557689 -0.321172 -0.939775 -0.0785723 -0.33264 -0.940233 -0.0602659 -0.335158 -0.939493 -0.0587399 -0.337494 -0.939105 -0.0592242 -0.338488 -0.945478 -0.0557153 -0.320884 -0.93972 -0.0790709 -0.332676 -0.939683 -0.0789997 -0.332798 -0.942137 -0.0631778 -0.32922 -0.94338 -0.0644149 -0.325401 -0.932838 -0.0550738 -0.356063 -0.94084 -0.0782383 -0.329695 -0.941423 -0.0798598 -0.327637 -0.942237 -0.0812109 -0.324952 -0.942779 -0.0820347 -0.32317 -0.940603 -0.0794259 -0.330088 -0.93964 -0.0925598 -0.329407 -0.939757 -0.0964226 -0.327964 -0.941633 0.0610188 -0.331066 -0.931736 0.034288 -0.361513 -0.941161 0.036634 -0.335968 -0.939487 0.0387794 -0.340383 -0.939722 0.0593325 -0.336753 -0.939754 0.0592872 -0.336672 -0.939105 0.0391974 -0.341388 -0.945475 0.0367321 -0.323618 -0.945381 0.0367661 -0.323887 -0.939673 0.0591156 -0.336928 -0.939853 0.0587882 -0.336483 -0.944289 0.109107 -0.310506 -0.944196 0.109191 -0.31076 -0.93971 0.0982134 -0.327564 -0.939693 0.0979786 -0.327685 -0.939723 0.0978786 -0.327628 -0.939791 0.0983951 -0.327278 -0.940132 0.11109 -0.322196 -0.941534 0.106308 -0.319706 -0.942479 0.10372 -0.317766 -0.942792 0.102886 -0.317109 -0.936863 0.11747 -0.329376 -0.940309 0.0925601 -0.327492 -0.940766 0.0904008 -0.326783 -0.941077 0.0890307 -0.326264 -0.942097 0.0851894 -0.32434 -0.941616 0.0865265 -0.325381 -0.940188 0.080314 -0.331053 -0.939767 0.0770618 -0.333014 -0.939692 0.0748129 -0.333741 -0.939623 0.0603352 -0.336852 -0.944196 0.0648637 -0.322934 -0.942943 0.063102 -0.326921 -0.946015 0.190696 -0.26209 -0.939664 0.219691 -0.262237 -0.939886 0.219065 -0.261962 -0.941394 0.195586 -0.274817 -0.939383 0.200128 -0.278404 -0.964079 0.14006 -0.225688 -0.939001 0.202697 -0.277833 -0.94611 0.190529 -0.261866 -0.939727 0.219749 -0.261962 -0.939742 0.219711 -0.261939 -0.943046 0.249425 -0.220118 -0.942939 0.249647 -0.220324 -0.939699 0.248849 -0.234608 -0.939685 0.248737 -0.234782 -0.939726 0.248579 -0.234783 -0.939771 0.248758 -0.234414 -0.940012 0.254494 -0.227179 -0.940924 0.250343 -0.228016 -0.941578 0.247829 -0.228059 -0.942492 0.244369 -0.228018 -0.938611 0.256569 -0.230614 -0.939793 0.242248 -0.241051 -0.939889 0.241178 -0.241749 -0.941379 0.229896 -0.246888 -0.942082 0.230067 -0.244032 -0.941333 0.233122 -0.244021 -0.940271 0.23822 -0.243192 -0.939699 0.33281 -0.0787619 -0.941629 0.329024 -0.0712528 -0.93977 0.332632 -0.0786685 -0.941282 0.328096 -0.0796289 -0.94071 0.330161 -0.0778343 -0.939687 0.3328 -0.0789453 -0.93973 0.332658 -0.0790289 -0.941744 0.328715 -0.0711731 -0.939552 0.334554 -0.0729015 -0.939673 0.334296 -0.0725331 -0.939874 0.3334 -0.0740352 -0.940329 0.331544 -0.07655 -0.942235 0.324959 -0.0812081 -0.94278 0.323164 -0.0820377 -0.940603 0.330088 -0.0794267 -0.94449 0.313869 -0.09708 -0.940988 0.321385 -0.106077 -0.939757 0.327963 -0.0964219 -0.939641 0.329407 -0.0925565 -0.941846 0.319279 -0.104822 -0.940413 0.321434 -0.110926 -0.9399 0.321557 -0.114846 -0.939688 0.320711 -0.118875 -0.939733 0.321259 -0.117024 -0.939744 0.321227 -0.117024 -0.939659 0.32088 -0.118649 -0.940379 0.31885 -0.118416 -0.940262 0.319168 -0.118487 -0.939681 0.321333 -0.117241 -0.939799 0.320972 -0.117281 -0.939599 0.341422 -0.0242079 -0.938904 0.343202 -0.0259357 -0.940223 0.336557 -0.0520564 -0.942584 0.330955 -0.0447755 -0.940991 0.334511 -0.0513554 -0.940251 0.335876 -0.0558207 -0.940519 0.333613 -0.0642306 -0.939695 0.336177 -0.0629231 -0.939881 0.335639 -0.0630076 -0.939974 0.336203 -0.0584517 -0.939849 0.336284 -0.0599696 -0.939688 0.336156 -0.0631296 -0.940105 0.334776 -0.0642448 -0.940678 0.333174 -0.0641842 -0.939718 0.336162 -0.0626556 -0.939754 0.336061 -0.0626597 -0.939752 0.321142 -0.117192 -0.939691 0.320688 -0.118909 -0.939599 0.315062 -0.133756 -0.938046 0.315987 -0.142204 -0.940362 0.30108 -0.158338 -0.939671 0.299288 -0.165667 -0.939599 0.288749 -0.183789 -0.939163 0.288615 -0.18621 -0.939988 0.271734 -0.206359 -0.939625 0.27125 -0.208636 -0.939634 0.256467 -0.226523 -0.939425 0.256695 -0.227131 -0.940139 0.228659 -0.252692 -0.939662 0.225652 -0.25713 -0.939771 0.213132 -0.267217 -0.941312 0.213125 -0.261741 -0.93036 0.204173 -0.30454 -0.939372 0.200782 -0.27797 -0.939599 0.166474 -0.299067 -0.938156 0.162324 -0.305802 -0.940362 0.140341 -0.309878 -0.939667 0.13489 -0.314372 -0.939574 0.11336 -0.323033 -0.939276 0.113342 -0.323905 -0.942895 0.044729 -0.330074 -0.939477 0.0395614 -0.340319 -0.939599 0.00406896 -0.342254 -0.941835 0.0153196 -0.335725 -0.934773 -0.0251251 -0.354357 -0.940342 -0.0100177 -0.340084 -0.93969 -0.0356756 -0.340163 -0.942105 -0.123171 -0.311877 -0.939562 -0.131463 -0.316134 -0.939599 -0.159316 -0.30294 -0.940951 -0.151574 -0.302716 -0.937335 -0.187091 -0.293938 -0.939486 -0.178157 -0.29262 -0.939391 -0.216151 -0.266127 -0.964079 -0.153101 -0.217052 -0.939001 -0.218699 -0.26542 -0.94611 -0.205614 -0.250199 -0.939729 -0.234775 -0.248576 -0.939687 -0.234774 -0.248735 -0.941312 -0.261742 -0.213125 -0.939625 -0.268888 -0.211668 -0.939599 -0.284298 -0.190602 -0.940026 -0.282148 -0.191688 -0.939068 -0.300338 -0.167181 -0.939569 -0.298108 -0.168352 -0.939599 -0.311793 -0.141208 -0.941047 -0.30509 -0.14612 -0.937104 -0.328767 -0.117253 -0.939476 -0.320169 -0.121971 -0.939691 -0.327135 -0.0998153 -0.939659 -0.327307 -0.0995532 0 -0.0458559 0.998948 0 0.957491 0.288462 0 -0.751734 0.659467 0 -0.978308 0.207156 0 -0.978308 0.207156 0.211514 -0.936214 0.280651 0.00594394 -0.964069 0.265584 0.188718 -0.706308 0.682287 0 -0.588342 0.808612 0 -0.528912 0.848677 0.0109142 -0.585941 0.81028 0.0934732 -0.591595 0.800798 0 -0.650283 0.759692 0 -0.694319 0.719668 0.189521 -0.293361 0.937028 0 -0.113059 0.993588 0 -0.113059 0.993588 0.158232 -0.134833 0.978153 0 -0.195254 0.980753 0 -0.253242 0.967403 0.158233 0.192175 0.96852 0 0.387705 0.921783 0 0.387705 0.921783 0.189521 0.348007 0.918136 0 0.309746 0.950819 0 0.252645 0.967559 0.093474 0.637706 0.764587 0 0.634919 0.772579 0 0.789248 0.614075 0 0.789248 0.614075 0.188715 0.745244 0.639529 0 0.735476 0.67755 0 0.693873 0.720097 0 0.988805 0.149213 0 0.988805 0.149213 0.15578 0.966107 0.205837 0.00434053 0.973119 0.230263 0 0.957491 0.288462 0 0.930013 0.367526 0.0507852 0.934715 0.351752 0 0.903408 0.428782 0 0.856278 0.516515 0.0992306 0.86816 0.486263 0 0.82883 0.559501 0.0109145 0.63262 0.774386 0 0.577948 0.816074 0 0.504441 0.863446 0.0619699 0.520647 0.85152 0 0.448931 0.893566 0.0221248 0.0294363 0.999322 0.0221262 0.0294368 0.999322 0 0.104581 0.994516 0 0.171348 0.985211 0 0.171348 0.985211 0 -0.470527 0.882386 0.0471002 -0.452239 0.890652 0 -0.395556 0.918442 0 -0.332775 0.943006 0 -0.332775 0.943006 0 -0.751734 0.659467 0 -0.794459 0.607318 0.0610585 -0.822852 0.564966 0 -0.938893 0.344209 0 -0.938893 0.344209 0 -0.913568 0.406686 0.0407988 -0.906012 0.42128 0 -0.876604 0.481213 0 -0.842189 0.539183 0 -0.957525 -0.288349 0 0.751734 -0.659467 0 0.978308 -0.207156 0 0.978308 -0.207156 0.211511 0.936215 -0.28065 0.00595066 0.964069 -0.265584 0.188717 0.706308 -0.682287 0 0.588342 -0.808612 0 0.528914 -0.848675 0.0109136 0.585941 -0.81028 0.0934732 0.591596 -0.800798 0 0.650283 -0.759692 0 0.694319 -0.719667 0.189516 0.293361 -0.937029 0 0.253244 -0.967403 0 0.195252 -0.980753 0.158228 0.134832 -0.978154 0 0.113059 -0.993588 0 -0.171348 -0.985211 0 -0.171348 -0.985211 0.158227 -0.192175 -0.968521 0 -0.387705 -0.921784 0 -0.387705 -0.921784 0.189516 -0.348008 -0.918136 0 -0.309748 -0.950819 0 -0.252643 -0.96756 0.0934761 -0.637706 -0.764587 0 -0.634919 -0.772579 0 -0.789248 -0.614075 0 -0.789248 -0.614075 0.188717 -0.745244 -0.639529 0 -0.735476 -0.677551 0 -0.693874 -0.720096 0 -0.988805 -0.149211 0 -0.988805 -0.149211 0.155782 -0.966107 -0.205836 0.00433176 -0.973119 -0.230264 0 -0.957525 -0.288349 0 -0.930013 -0.367526 0.0507838 -0.934715 -0.351752 0 -0.903409 -0.42878 0 -0.856278 -0.516515 0.0992315 -0.86816 -0.486263 0 -0.828829 -0.559502 0.010914 -0.63262 -0.774386 0 -0.57795 -0.816072 0 -0.504441 -0.863446 0.0619689 -0.520647 -0.85152 0 -0.448932 -0.893566 0 -0.104575 -0.994517 0.0221243 -0.0294363 -0.999322 0.0221247 -0.0294362 -0.999322 0 0.0458562 -0.998948 0 0.113059 -0.993588 0 0.470526 -0.882386 0.0470995 0.452239 -0.890652 0 0.395557 -0.918442 0 0.332774 -0.943006 0 0.332775 -0.943006 0 0.751734 -0.659467 0 0.794458 -0.607319 0.0610592 0.822852 -0.564966 0 0.938862 -0.344295 0 0.938862 -0.344295 0 0.913568 -0.406687 0.0407963 0.906013 -0.42128 0 0.876606 -0.481209 0 0.842189 -0.539183 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.851305 -0.514733 -0.10164 0.853125 -0.405286 -0.328512 0.854595 -0.203871 -0.477602 0.855727 0.0427694 -0.515657 0.856529 0.278046 -0.434798 0.851304 0.507858 -0.131761 0.857007 0.448303 -0.254093 0.853125 0.385247 -0.351798 0.854595 0.175405 -0.488774 0.855727 -0.0730488 -0.512245 0.856529 -0.303158 -0.417676 0.857008 -0.462483 -0.22726 0 -0.981057 -0.19372 -0.00442541 -0.973118 -0.230263 0 -0.897496 -0.441022 0 -0.776847 -0.629689 -0.00738975 -0.727599 -0.685963 0 -0.587403 -0.809295 0 -0.392592 -0.919713 -0.0088759 -0.287138 -0.957848 0 -0.141177 -0.989984 0 0.0826578 -0.996578 -0.00887597 0.230258 -0.973089 0 0.337776 -0.941227 0 0.538745 -0.842469 -0.00738993 0.685961 -0.727601 0 0.738437 -0.674322 0 0.869977 -0.493093 -0.00442555 0.957877 -0.287143 0 0.967954 -0.25113 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.851305 -0.514733 -0.101638 0.853126 -0.405287 -0.328511 0.854596 -0.20387 -0.477602 0.855727 0.0427694 -0.515657 0.856529 0.278048 -0.434796 0.851304 0.507858 -0.131761 0.857007 0.448303 -0.254093 0.853125 0.385247 -0.351799 0.854595 0.175404 -0.488774 0.855727 -0.0730488 -0.512245 0.856529 -0.303157 -0.417677 0.857008 -0.462478 -0.22727 0 -0.981057 -0.193717 -0.00442583 -0.973118 -0.230264 0 -0.897487 -0.441042 0 -0.77685 -0.629686 -0.00738994 -0.7276 -0.685962 0 -0.587401 -0.809296 0 -0.39259 -0.919713 -0.00887582 -0.287136 -0.957849 0 -0.141177 -0.989984 0 0.0826578 -0.996578 -0.00887589 0.230257 -0.973089 0 0.337773 -0.941227 0 0.53875 -0.842466 -0.0073897 0.685961 -0.7276 0 0.738436 -0.674323 0 0.869977 -0.493093 -0.00442555 0.957877 -0.287143 0 0.967954 -0.25113 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.849118 -0.514009 -0.121627 0.856529 -0.303159 -0.417676 0.855726 -0.0730433 -0.512247 0.854595 0.175407 -0.488773 0.849119 0.505957 -0.151672 0.853125 0.385249 -0.351796 0.856529 0.278045 -0.434798 0.855727 0.0427643 -0.515658 0.854595 -0.20387 -0.477602 0.853125 -0.405289 -0.32851 0 -0.981057 -0.193718 0.00442574 -0.973118 -0.230264 -0.00369755 -0.799847 -0.600192 0 -0.776851 -0.629684 0 -0.587404 -0.809294 -0.00592442 -0.460216 -0.887787 0 -0.39259 -0.919713 0 -0.141166 -0.989986 -0.00666743 -0.0294439 -0.999544 0 0.0826479 -0.996579 0 0.33778 -0.941225 -0.00592395 0.407162 -0.913337 0 0.538742 -0.842471 0 0.763134 -0.64624 -0.00442505 0.738433 -0.674312 0.00514827 0.967942 -0.251123 0 0.957886 -0.287148 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.849119 -0.151672 -0.505957 0.849119 -0.384331 -0.362335 0.849119 -0.514006 -0.12163 0.849119 0.505958 -0.151669 0.849119 0.362334 -0.384333 0.849119 0.121628 -0.514008 0 -0.973126 -0.230271 0 -0.973126 -0.230271 0 -0.727622 -0.685979 0 -0.727622 -0.685979 0 -0.287148 -0.957886 0 -0.287148 -0.957886 0 0.230267 -0.973127 0 0.230267 -0.973127 0 0.685976 -0.727624 0 0.685976 -0.727624 0 0.957888 -0.287143 0 0.957888 -0.287143 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.851304 -0.514734 -0.101638 0.853125 -0.405286 -0.328513 0.854595 -0.20387 -0.477602 0.855727 0.0427638 -0.515658 0.856529 0.278045 -0.434798 0.851305 0.507859 -0.131755 0.857008 0.448294 -0.254108 0.853125 0.385249 -0.351796 0.854595 0.175407 -0.488773 0.855727 -0.0730433 -0.512247 0.856529 -0.303164 -0.417672 0.857007 -0.462489 -0.22725 0 -0.981057 -0.193718 -0.00442508 -0.973119 -0.230258 0 -0.897506 -0.441002 0 -0.776847 -0.629689 -0.00738935 -0.727602 -0.68596 0 -0.587414 -0.809287 0 -0.39259 -0.919713 -0.00887621 -0.287132 -0.95785 0 -0.141166 -0.989986 0 0.0826468 -0.996579 -0.00887658 0.230256 -0.97309 0 0.33778 -0.941225 0 0.538742 -0.842471 -0.00739006 0.685963 -0.727599 0 0.73844 -0.674319 0 0.869959 -0.493123 -0.00442637 0.957878 -0.28714 0 0.967956 -0.25112 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.849119 -0.151671 -0.505957 0.849119 -0.384331 -0.362335 0.849119 -0.514009 -0.121624 0.849119 0.505958 -0.15167 0.849119 0.362337 -0.384329 0.849119 0.121626 -0.514008 0 -0.973129 -0.23026 0 -0.973129 -0.23026 0 -0.727621 -0.685979 0 -0.727621 -0.685979 0 -0.287147 -0.957887 0 -0.287147 -0.957887 0 0.230265 -0.973128 0 0.230265 -0.973128 0 0.685982 -0.727618 0 0.685982 -0.727618 0 0.957888 -0.287143 0 0.957888 -0.287143 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.851304 -0.514734 -0.101638 0.853125 -0.405286 -0.328512 0.854596 -0.20387 -0.477602 0.855727 0.0427688 -0.515657 0.856529 0.278048 -0.434796 0.851305 0.507859 -0.131756 0.857008 0.448293 -0.254108 0.853125 0.385248 -0.351797 0.854596 0.175405 -0.488773 0.855727 -0.0730483 -0.512245 0.856529 -0.303162 -0.417673 0.857007 -0.462488 -0.227252 0 -0.981057 -0.193717 -0.00442513 -0.97312 -0.230258 0 -0.897504 -0.441006 0 -0.776847 -0.629689 -0.00738944 -0.727601 -0.685961 0 -0.587411 -0.809289 0 -0.39259 -0.919713 -0.00887589 -0.287136 -0.957849 0 -0.141176 -0.989985 0 0.0826567 -0.996578 -0.00887608 0.230257 -0.973089 0 0.337776 -0.941227 0 0.53875 -0.842466 -0.00738981 0.685964 -0.727598 0 0.738439 -0.67432 0 0.869959 -0.493123 -0.00442636 0.957878 -0.28714 0 0.967956 -0.25112 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.851304 -0.514734 -0.101638 0.851305 -0.0154488 -0.524444 0.851304 -0.241465 -0.465806 0.851304 -0.419659 -0.314908 0.851305 0.507856 -0.131763 0.851305 0.400395 -0.339064 0.851305 0.21363 -0.47921 0 -0.981058 -0.193716 0 -0.981058 -0.193716 0 -0.799851 -0.600199 0 -0.799851 -0.600199 0 -0.460221 -0.887804 0 -0.460221 -0.887804 0 -0.0294447 -0.999566 0 -0.0294447 -0.999566 0 0.407169 -0.913353 0 0.407169 -0.913353 0 0.763134 -0.64624 0 0.763134 -0.64624 0 0.967952 -0.251134 0 0.967952 -0.251134 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.849119 -0.151672 -0.505957 0.849119 -0.384329 -0.362336 0.84912 -0.514006 -0.12163 0.849119 0.505958 -0.151669 0.849119 0.362334 -0.384333 0.849119 0.121628 -0.514008 0 -0.973126 -0.230271 0 -0.973126 -0.230271 0 -0.727619 -0.685982 0 -0.727619 -0.685982 0 -0.287148 -0.957886 0 -0.287148 -0.957886 0 0.230267 -0.973127 0 0.230267 -0.973127 0 0.685976 -0.727624 0 0.685976 -0.727624 0 0.957888 -0.287143 0 0.957888 -0.287143 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.981058 -0.193716 0.00442592 -0.973118 -0.230264 -0.00369726 -0.799842 -0.600199 0 -0.776847 -0.629689 0 -0.587414 -0.809287 -0.00592466 -0.460219 -0.887786 0 -0.39259 -0.919713 0 -0.141179 -0.989984 -0.00666823 -0.0294439 -0.999544 0 0.0826611 -0.996578 0 0.337771 -0.941228 -0.00592468 0.407162 -0.913337 0 0.538757 -0.842461 0 0.763134 -0.64624 -0.00442575 0.738429 -0.674317 0.00514747 0.967941 -0.251124 0 0.957887 -0.287145 0.849119 -0.514008 -0.121627 0.856529 -0.303164 -0.417672 0.855727 -0.07305 -0.512245 0.854595 0.175403 -0.488775 0.849119 0.505958 -0.15167 0.853125 0.385247 -0.351799 0.856529 0.278052 -0.434794 0.855727 0.0427711 -0.515657 0.854595 -0.20387 -0.477602 0.853125 -0.405286 -0.328513 0.705589 -0.707218 -0.0445795 0.705584 -0.707223 -0.04458 0.705584 -0.686989 -0.173772 0.705581 -0.686992 -0.173773 0.705581 -0.643364 -0.297049 0.705588 -0.643358 -0.297046 0.705588 -0.577821 -0.410205 0.705594 -0.577817 -0.410202 0.705593 -0.492605 -0.509391 0.705587 -0.492609 -0.509395 0.705589 -0.390619 -0.591237 0.705582 -0.390622 -0.591243 0.705583 -0.27533 -0.652951 0.705583 -0.27533 -0.652951 0.705583 -0.150663 -0.692425 0.705588 -0.150662 -0.692421 0.705588 -0.0208648 -0.708315 0.705583 -0.0208647 -0.70832 0.705583 0.109644 -0.700093 0.705589 0.109643 -0.700088 0.705588 0.236417 -0.668021 0.705585 0.236418 -0.668024 0.705585 0.355142 -0.613208 0.705586 0.355142 -0.613207 0.705586 0.461771 -0.537509 0.705591 0.461768 -0.537505 0.70559 0.552672 -0.443504 0.705585 0.552676 -0.443507 0.705585 0.62476 -0.334402 0.705588 0.624758 -0.334401 0.705588 0.675566 -0.213908 0.705587 0.675567 -0.213908 0.705587 0.703369 -0.0861308 0.705587 0.703369 -0.0861307 0.705589 -0.707218 -0.0445802 0.705584 -0.707222 -0.0445807 0.705584 -0.686989 -0.173772 0.705594 -0.68698 -0.17377 0.705593 -0.643353 -0.297044 0.705588 -0.643358 -0.297046 0.705588 -0.577821 -0.410205 0.705583 -0.577825 -0.410208 0.705584 -0.492611 -0.509398 0.705592 -0.492606 -0.509392 0.705591 -0.390618 -0.591236 0.705582 -0.390622 -0.591243 0.705583 -0.27533 -0.652951 0.705589 -0.275328 -0.652946 0.70559 -0.150662 -0.692419 0.705585 -0.150662 -0.692423 0.705587 -0.0208644 -0.708316 0.70559 -0.0208645 -0.708313 0.705588 0.109643 -0.700089 0.70559 0.109643 -0.700087 0.70559 0.236417 -0.668019 0.705591 0.236416 -0.668018 0.705591 0.355139 -0.613203 0.705586 0.355142 -0.613207 0.705586 0.461771 -0.537509 0.705588 0.46177 -0.537507 0.705589 0.552673 -0.443505 0.705585 0.552676 -0.443507 0.705585 0.62476 -0.334402 0.705585 0.624761 -0.334402 0.705584 0.675569 -0.213909 0.705587 0.675567 -0.213908 0.705587 0.703369 -0.0861307 0.705589 0.703367 -0.0861306 0.705751 -0.707276 -0.0409392 0.705751 -0.707276 -0.0409392 0.705752 -0.689421 -0.163134 0.70575 -0.689423 -0.163135 0.70575 -0.650621 -0.280373 0.705752 -0.65062 -0.280373 0.705751 -0.592049 -0.389092 0.705754 -0.592047 -0.389091 0.705754 -0.515488 -0.485987 0.705755 -0.515487 -0.485987 0.705755 -0.423264 -0.568117 0.705753 -0.423266 -0.568119 0.705753 -0.318183 -0.632987 0.705748 -0.318185 -0.632991 0.705747 -0.203434 -0.678628 0.705751 -0.203432 -0.678624 0.705751 -0.0824999 -0.70364 0.705752 -0.0824997 -0.703639 0.705753 0.0409391 -0.707274 0.705751 0.0409392 -0.707276 0.705752 0.163134 -0.689422 0.70575 0.163135 -0.689423 0.705749 0.280374 -0.650622 0.705752 0.280373 -0.65062 0.70575 0.389093 -0.59205 0.705754 0.389091 -0.592047 0.705754 0.485987 -0.515488 0.70576 0.485983 -0.515483 0.705761 0.568113 -0.423261 0.705753 0.568119 -0.423266 0.705753 0.632987 -0.318183 0.705758 0.632982 -0.31818 0.705759 0.678617 -0.20343 0.705738 0.678636 -0.203436 0.705738 0.703653 -0.0825015 0.705753 0.703638 -0.0824992 0.705589 -0.707218 -0.0445795 0.705587 -0.707219 -0.0445796 0.705587 -0.686986 -0.173772 0.705588 -0.686985 -0.173772 0.705589 -0.643357 -0.297046 0.705587 -0.643358 -0.297046 0.705588 -0.577821 -0.410205 0.705588 -0.577821 -0.410205 0.705588 -0.492608 -0.509395 0.705587 -0.492609 -0.509396 0.705587 -0.39062 -0.591239 0.705586 -0.39062 -0.591239 0.705586 -0.275329 -0.652949 0.705586 -0.275329 -0.652949 0.705585 -0.150663 -0.692424 0.705595 -0.15066 -0.692414 0.705594 -0.0208642 -0.708309 0.705589 -0.0208646 -0.708314 0.70559 0.109643 -0.700087 0.705581 0.109644 -0.700096 0.70558 0.23642 -0.668029 0.705582 0.236419 -0.668027 0.705582 0.355144 -0.613211 0.705585 0.355142 -0.613208 0.705586 0.461771 -0.53751 0.705591 0.461768 -0.537505 0.705591 0.552671 -0.443503 0.70559 0.552672 -0.443504 0.70559 0.624756 -0.334399 0.705581 0.624763 -0.334404 0.705581 0.675572 -0.21391 0.70559 0.675564 -0.213907 0.70559 0.703366 -0.0861302 0.705589 0.703367 -0.0861304 0.705589 -0.707218 -0.0445792 0.705584 -0.707223 -0.0445797 0.705584 -0.686989 -0.173773 0.705581 -0.686992 -0.173774 0.705581 -0.643364 -0.297049 0.705588 -0.643358 -0.297046 0.705588 -0.577821 -0.410205 0.705594 -0.577817 -0.410201 0.705593 -0.492605 -0.509391 0.705582 -0.492612 -0.509399 0.705583 -0.390622 -0.591242 0.70559 -0.390618 -0.591236 0.705589 -0.275328 -0.652947 0.705595 -0.275326 -0.652941 0.705593 -0.150661 -0.692416 0.705588 -0.150662 -0.692421 0.705588 -0.0208646 -0.708315 0.70559 -0.0208646 -0.708313 0.705588 0.109643 -0.700089 0.705582 0.109644 -0.700095 0.705582 0.23642 -0.668027 0.705591 0.236416 -0.668019 0.705591 0.355139 -0.613203 0.705586 0.355142 -0.613208 0.705586 0.461771 -0.537509 0.705586 0.461771 -0.537509 0.705586 0.552675 -0.443507 0.70559 0.552673 -0.443504 0.70559 0.624756 -0.3344 0.705588 0.624758 -0.334401 0.705588 0.675566 -0.213908 0.705587 0.675567 -0.213908 0.705587 0.703369 -0.0861307 0.705589 0.703367 -0.0861305 0.705751 -0.707276 -0.0409392 0.705751 -0.707276 -0.0409392 0.705752 -0.689421 -0.163134 0.705753 -0.68942 -0.163134 0.705753 -0.650618 -0.280372 0.705754 -0.650617 -0.280372 0.705754 -0.592047 -0.389091 0.70575 -0.59205 -0.389093 0.70575 -0.515491 -0.485991 0.705747 -0.515493 -0.485993 0.705746 -0.42327 -0.568124 0.705753 -0.423266 -0.568119 0.705753 -0.318183 -0.632987 0.705751 -0.318184 -0.632989 0.705752 -0.203432 -0.678624 0.705751 -0.203433 -0.678625 0.705751 -0.0825001 -0.70364 0.705752 -0.0824999 -0.703639 0.705753 0.0409393 -0.707274 0.705751 0.0409393 -0.707276 0.705751 0.163134 -0.689422 0.70575 0.163135 -0.689424 0.705749 0.280374 -0.650622 0.705757 0.280371 -0.650615 0.705758 0.389089 -0.592044 0.705746 0.389095 -0.592053 0.705745 0.485994 -0.515494 0.705747 0.485993 -0.515493 0.705746 0.568124 -0.42327 0.705753 0.568119 -0.423266 0.705753 0.632987 -0.318183 0.70576 0.632981 -0.318179 0.70576 0.678616 -0.20343 0.705764 0.678612 -0.203429 0.705765 0.703627 -0.0824983 0.705753 0.703638 -0.0825001 0.698069 -0.702467 -0.138708 0.69806 -0.702476 -0.138711 0.698062 -0.572722 -0.429766 0.698066 -0.57272 -0.429763 0.698069 -0.329535 -0.635694 0.698066 -0.329536 -0.635697 0.698067 -0.0210825 -0.715722 0.698067 -0.0210825 -0.715722 0.698066 0.291545 -0.653991 0.698067 0.291545 -0.653991 0.698067 0.54643 -0.462728 0.69807 0.546427 -0.462727 0.69807 0.693083 -0.179817 0.698063 0.69309 -0.179817 0.694741 0.688969 -0.206533 0.322022 0.218001 -0.921291 0.694742 0.688969 -0.206533 0.700857 0.526729 -0.480995 0.406508 0.626744 -0.664788 0.70611 0.38149 -0.596552 0.703118 0.240182 -0.669281 0.704868 0.0586315 -0.706911 0.704869 -0.10014 -0.702234 0.32202 -0.271852 -0.906862 0.694742 -0.699931 -0.165622 0.694743 -0.699929 -0.165622 0.700858 -0.554127 -0.449156 0.406509 -0.664788 -0.626743 0.706109 -0.415944 -0.573063 0.703117 -0.279161 -0.653985 0.698069 -0.702467 -0.138709 0.698072 -0.702464 -0.138707 0.698071 -0.572716 -0.429759 0.698069 -0.572717 -0.429761 0.698069 -0.329535 -0.635694 0.698066 -0.329535 -0.635696 0.698068 -0.0210827 -0.715721 0.698068 -0.0210827 -0.715721 0.698067 0.291545 -0.653991 0.698068 0.291545 -0.65399 0.698068 0.546429 -0.462728 0.69807 0.546427 -0.462727 0.69807 0.693083 -0.179817 0.698069 0.693084 -0.179817 0.698069 -0.702467 -0.138707 0.698065 -0.70247 -0.138709 0.698065 -0.57272 -0.429764 0.698069 -0.572717 -0.429761 0.698069 -0.329534 -0.635694 0.698067 -0.329535 -0.635696 0.698069 -0.0210828 -0.71572 0.698067 -0.0210825 -0.715722 0.698066 0.291546 -0.653991 0.698066 0.291546 -0.653992 0.698063 0.546432 -0.462731 0.698064 0.546431 -0.46273 0.698064 0.693089 -0.179819 0.698062 0.69309 -0.179819 0.698068 0.693085 -0.179817 0.69807 0.693083 -0.179817 0.706856 0.615385 -0.348793 0.581211 0.621003 -0.52588 0.700855 0.52673 -0.480996 0.706109 0.381488 -0.596554 0.486771 0.355673 -0.797842 0.703118 0.240182 -0.669282 0.704866 0.0586317 -0.706913 0.450652 -0.0262842 -0.892313 0.704867 -0.10014 -0.702235 0.70312 -0.27916 -0.653982 0.486768 -0.40202 -0.775524 0.706107 -0.415943 -0.573065 0.698064 -0.572721 -0.429765 0.698069 -0.702467 -0.138709 0.698072 -0.702464 -0.138708 0.706857 -0.634846 -0.311966 0.547286 -0.650181 -0.527013 0.698068 0.693086 -0.179817 0.69807 0.693083 -0.179817 0.706856 0.615385 -0.348793 0.581211 0.621003 -0.52588 0.450652 -0.0262842 -0.892313 0.700858 0.526728 -0.480995 0.706112 0.38149 -0.596549 0.486768 0.355674 -0.797843 0.70312 0.240181 -0.66928 0.704867 0.0586317 -0.706912 0.704869 -0.100141 -0.702233 0.70312 -0.27916 -0.653982 0.486764 -0.402022 -0.775525 0.706105 -0.415945 -0.573067 0.698062 -0.572723 -0.429766 0.69807 -0.702466 -0.138707 0.69806 -0.702476 -0.138711 0.706847 -0.634849 -0.311984 0.547287 -0.650181 -0.527012 0.694743 -0.69993 -0.165622 0.69475 -0.699923 -0.165619 0.694748 -0.523344 -0.493392 0.694732 -0.523353 -0.493405 0.694733 -0.206535 -0.688977 0.694744 -0.206534 -0.688966 0.69474 0.165622 -0.699933 0.694738 0.165622 -0.699934 0.694743 0.493397 -0.523347 0.694742 0.493398 -0.523347 0.694742 0.688968 -0.206536 0.694727 0.688982 -0.206537 0.698068 0.693084 -0.179818 0.698071 0.693082 -0.179818 0.706856 0.615389 -0.348786 0.581203 0.621007 -0.525883 0.450646 -0.0262843 -0.892316 0.70085 0.526733 -0.481 0.706106 0.381488 -0.596558 0.486771 0.355673 -0.797842 0.703117 0.240182 -0.669282 0.704867 0.0586335 -0.706913 0.704868 -0.100142 -0.702234 0.703122 -0.279158 -0.65398 0.486768 -0.40202 -0.775524 0.706107 -0.415943 -0.573065 0.698064 -0.572721 -0.429764 0.698069 -0.702466 -0.13871 0.698073 -0.702463 -0.138709 0.706859 -0.634846 -0.311964 0.547287 -0.650181 -0.527012 0.698069 -0.702467 -0.138707 0.698059 -0.702476 -0.138711 0.698061 -0.572723 -0.429766 0.698064 -0.572721 -0.429764 0.698066 -0.329536 -0.635697 0.698066 -0.329536 -0.635697 0.698067 -0.0210825 -0.715722 0.698069 -0.0210828 -0.71572 0.698068 0.291545 -0.65399 0.698071 0.291543 -0.653987 0.698074 0.546424 -0.462725 0.69807 0.546427 -0.462727 0.698071 0.693082 -0.179818 0.698056 0.693097 -0.179819 0.694742 0.688969 -0.206533 0.322019 0.218001 -0.921292 0.694741 0.688969 -0.206533 0.700856 0.526729 -0.480996 0.406502 0.626745 -0.664791 0.706107 0.381491 -0.596555 0.703117 0.240183 -0.669283 0.704868 0.0586313 -0.706911 0.704867 -0.100141 -0.702235 0.322024 -0.271851 -0.906861 0.694742 -0.699931 -0.165619 0.694736 -0.699936 -0.165622 0.700853 -0.55413 -0.449161 0.406511 -0.664787 -0.626743 0.706115 -0.415938 -0.57306 0.703122 -0.27916 -0.65398 0.694741 0.688969 -0.206533 0.509837 0.832702 -0.216039 0.32202 0.218001 -0.921292 0.706853 0.615384 -0.3488 0.700855 0.52673 -0.480997 0.406501 0.626745 -0.664791 0.706106 0.381492 -0.596555 0.703116 0.240183 -0.669283 0.704865 0.0586331 -0.706914 0.704864 -0.100142 -0.702238 0.322024 -0.271851 -0.906862 0.703117 -0.27916 -0.653985 0.706107 -0.415947 -0.573062 0.406512 -0.664788 -0.626742 0.698069 -0.702466 -0.13871 0.547283 -0.814457 -0.192723 0.706849 -0.634855 -0.311968 0.700851 -0.554132 -0.449162 0.698069 0.693084 -0.179815 0.69807 0.693083 -0.179815 0.706856 0.615381 -0.3488 0.581219 0.620999 -0.525876 0.700858 0.526728 -0.480994 0.70611 0.381488 -0.596553 0.486773 0.355673 -0.79784 0.703117 0.240183 -0.669282 0.704866 0.058632 -0.706913 0.450649 -0.0262852 -0.892314 0.704866 -0.100141 -0.702236 0.703117 -0.279162 -0.653984 0.486771 -0.402019 -0.775522 0.70611 -0.415941 -0.573063 0.698066 -0.57272 -0.429763 0.698069 -0.702467 -0.138708 0.69806 -0.702476 -0.138711 0.706847 -0.634857 -0.311969 0.547266 -0.650189 -0.527023 -0.69474 0.68897 -0.206534 -0.694742 0.688969 -0.206533 -0.694742 0.493398 -0.523347 -0.694738 0.4934 -0.523351 -0.694736 0.165622 -0.699936 -0.694743 0.165622 -0.69993 -0.69474 -0.206534 -0.68897 -0.69474 -0.206534 -0.688971 -0.694737 -0.523352 -0.493401 -0.694748 -0.523342 -0.493395 -0.69475 -0.699923 -0.16562 -0.694743 -0.69993 -0.16562 -0.694741 0.688969 -0.206533 -0.694735 0.688974 -0.206536 -0.694737 0.4934 -0.523351 -0.69474 0.493399 -0.523349 -0.69474 0.165621 -0.699933 -0.694743 0.165621 -0.69993 -0.69474 -0.206534 -0.68897 -0.694738 -0.206534 -0.688972 -0.694739 -0.523349 -0.493399 -0.694743 -0.523346 -0.493397 -0.694743 -0.69993 -0.165621 -0.694742 -0.699931 -0.165621 -0.694742 -0.699931 -0.165621 -0.32202 -0.271852 -0.906862 -0.694743 -0.69993 -0.165621 -0.700858 -0.554127 -0.449156 -0.406501 -0.66479 -0.626746 -0.70611 -0.415941 -0.573064 -0.703118 -0.279161 -0.653983 -0.704867 -0.100141 -0.702235 -0.704867 0.0586317 -0.706913 -0.32202 0.218 -0.921292 -0.694735 0.688975 -0.206536 -0.694742 0.688969 -0.206533 -0.700857 0.526729 -0.480994 -0.406501 0.626746 -0.66479 -0.706111 0.381487 -0.596552 -0.70312 0.240182 -0.66928 -0.694742 -0.699931 -0.165621 -0.322021 -0.271852 -0.906862 -0.694743 -0.69993 -0.165621 -0.700858 -0.554127 -0.449156 -0.406503 -0.664789 -0.626746 -0.70611 -0.415941 -0.573063 -0.703118 -0.279161 -0.653983 -0.704868 -0.10014 -0.702234 -0.704867 0.058632 -0.706912 -0.322022 0.218001 -0.921291 -0.694742 0.688969 -0.206534 -0.694742 0.688969 -0.206534 -0.700857 0.52673 -0.480995 -0.406498 0.626747 -0.664791 -0.70611 0.381488 -0.596554 -0.703118 0.240182 -0.669281 -0.698069 0.693085 -0.179816 -0.698064 0.693089 -0.179818 -0.698064 0.546431 -0.462731 -0.698067 0.546429 -0.462729 -0.698067 0.291546 -0.653991 -0.698066 0.291546 -0.653991 -0.698067 -0.0210825 -0.715722 -0.698067 -0.0210825 -0.715722 -0.698066 -0.329536 -0.635697 -0.698069 -0.329534 -0.635695 -0.698069 -0.572717 -0.429761 -0.698065 -0.57272 -0.429763 -0.698066 -0.70247 -0.13871 -0.698069 -0.702467 -0.13871 -0.694741 -0.699932 -0.165621 -0.322019 -0.271853 -0.906863 -0.694736 -0.699937 -0.165621 -0.700853 -0.55413 -0.449161 -0.406506 -0.664788 -0.626745 -0.706111 -0.415941 -0.573062 -0.70312 -0.279162 -0.653981 -0.704869 -0.10014 -0.702234 -0.704868 0.0586315 -0.706911 -0.322022 0.218001 -0.921291 -0.694735 0.688974 -0.206536 -0.69474 0.688971 -0.206534 -0.700853 0.526732 -0.480998 -0.406497 0.626748 -0.664791 -0.70611 0.381488 -0.596554 -0.703118 0.240182 -0.669281 -0.694742 0.688968 -0.206533 -0.694742 0.688969 -0.206533 -0.694742 0.493398 -0.523347 -0.694747 0.493395 -0.523343 -0.694745 0.165621 -0.699928 -0.694737 0.165621 -0.699936 -0.694741 -0.206534 -0.688969 -0.694744 -0.206532 -0.688967 -0.694747 -0.523343 -0.493395 -0.694738 -0.523351 -0.4934 -0.694736 -0.699937 -0.165621 -0.694741 -0.699932 -0.165621 -0.694742 -0.69993 -0.165623 -0.509842 -0.843972 -0.166652 -0.322024 -0.271851 -0.906862 -0.706849 -0.634855 -0.311968 -0.700851 -0.554132 -0.449162 -0.406512 -0.664788 -0.626742 -0.706107 -0.415947 -0.573062 -0.703117 -0.27916 -0.653985 -0.704864 -0.100142 -0.702238 -0.704865 0.0586331 -0.706914 -0.32202 0.218001 -0.921292 -0.703116 0.240183 -0.669283 -0.706106 0.381492 -0.596555 -0.406501 0.626745 -0.664791 -0.698069 0.693085 -0.179816 -0.547279 0.801703 -0.240328 -0.706853 0.615384 -0.3488 -0.700855 0.52673 -0.480997 -0.698069 0.693084 -0.179816 -0.69807 0.693083 -0.179815 -0.698069 0.546427 -0.462728 -0.698073 0.546425 -0.462725 -0.69807 0.291544 -0.653987 -0.698066 0.291545 -0.653991 -0.698067 -0.0210829 -0.715722 -0.698068 -0.0210827 -0.715721 -0.698066 -0.329536 -0.635696 -0.698072 -0.329532 -0.635692 -0.698075 -0.572712 -0.429758 -0.698072 -0.572715 -0.429759 -0.698072 -0.702464 -0.138707 -0.698069 -0.702467 -0.138707 -0.694742 -0.699931 -0.165621 -0.322018 -0.271853 -0.906863 -0.69475 -0.699923 -0.16562 -0.700864 -0.554124 -0.449152 -0.406497 -0.664791 -0.626749 -0.706106 -0.415944 -0.573066 -0.703116 -0.279162 -0.653985 -0.704868 -0.10014 -0.702234 -0.704866 0.0586328 -0.706913 -0.322024 0.218 -0.921291 -0.694728 0.68898 -0.206539 -0.694741 0.688969 -0.206533 -0.700856 0.526729 -0.480996 -0.406515 0.626743 -0.664785 -0.706113 0.381488 -0.596549 -0.70312 0.240181 -0.669279 -0.694741 0.688969 -0.206533 -0.694729 0.68898 -0.206539 -0.694732 0.493403 -0.523355 -0.694745 0.493396 -0.523345 -0.694742 0.165622 -0.699931 -0.69474 0.165622 -0.699933 -0.694737 -0.206535 -0.688973 -0.69474 -0.206533 -0.688971 -0.694737 -0.523352 -0.493401 -0.694745 -0.523344 -0.493396 -0.694749 -0.699924 -0.16562 -0.694742 -0.699931 -0.165621 -0.69807 -0.702466 -0.13871 -0.698058 -0.702478 -0.138709 -0.706844 -0.63485 -0.311989 -0.581215 -0.650879 -0.488412 -0.70085 -0.554135 -0.449159 -0.706105 -0.415945 -0.573067 -0.486764 -0.402022 -0.775525 -0.70312 -0.27916 -0.653982 -0.704869 -0.100141 -0.702233 -0.450653 -0.0262842 -0.892312 -0.704866 0.058632 -0.706913 -0.703117 0.240182 -0.669282 -0.486771 0.355673 -0.797842 -0.706109 0.381488 -0.596555 -0.698064 0.546431 -0.46273 -0.698054 0.693098 -0.179822 -0.69807 0.693083 -0.179815 -0.706856 0.615381 -0.3488 -0.547293 0.61803 -0.564366 -0.707102 0.686779 -0.168351 -0.705157 0.702679 -0.0948468 -0.705157 0.702679 -0.0948468 -0.688908 0.682109 -0.245223 -0.705155 0.667606 -0.23887 -0.706818 0.62474 -0.331825 -0.266142 0.820238 -0.506338 -0.706363 0.587011 -0.395563 -0.70516 0.512727 -0.489755 -0.705157 0.51273 -0.489757 -0.705157 0.399699 -0.585657 -0.705155 0.3997 -0.585658 -0.705156 0.2692 -0.655962 -0.705154 0.269201 -0.655964 -0.705153 0.126936 -0.6976 -0.705153 0.126936 -0.6976 -0.705153 -0.0208772 -0.708747 -0.705156 -0.0208774 -0.708744 -0.705156 -0.167777 -0.688916 -0.705155 -0.167777 -0.688917 -0.705156 -0.307345 -0.638979 -0.705156 -0.307345 -0.638979 -0.705156 -0.43348 -0.561115 -0.705156 -0.43348 -0.561115 -0.705155 -0.54067 -0.458728 -0.705155 -0.540671 -0.458729 -0.705155 -0.624231 -0.336293 -0.705157 -0.624229 -0.336292 -0.705156 -0.680507 -0.199159 -0.705157 -0.680506 -0.199158 -0.705157 -0.707043 -0.0533211 -0.705157 -0.707043 -0.0533211 0.705157 -0.707043 -0.0533211 0.705157 -0.624229 -0.336292 0.706883 -0.663406 -0.245377 0.300696 -0.915326 -0.267881 0.706246 -0.686037 -0.174845 0.705157 -0.707043 -0.0533211 0.705155 -0.43348 -0.561116 0.707021 -0.499213 -0.500907 0.633293 -0.562816 -0.531205 0.587904 -0.594191 -0.548914 0.329721 -0.719883 -0.61078 0.706161 -0.554248 -0.44062 0.705155 -0.624231 -0.336293 0.268069 -0.417594 -0.86819 0.672235 -0.358301 -0.647858 0.707089 -0.366465 -0.604755 0.705156 -0.43348 -0.561115 0.707022 0.468862 -0.529422 0.705157 0.399699 -0.585657 0.705155 0.3997 -0.585658 0.705156 0.2692 -0.655962 0.705154 0.269201 -0.655964 0.705153 0.126936 -0.6976 0.705153 0.126936 -0.6976 0.705153 -0.0208775 -0.708747 0.705156 -0.0208772 -0.708744 0.705156 -0.167777 -0.688916 0.705155 -0.167777 -0.688917 0.707049 -0.249546 -0.661671 0.567029 -0.340197 -0.750163 0.511615 0.627891 -0.586517 0.342809 0.679303 -0.648868 0.632091 0.531416 -0.563966 0.657352 0.51163 -0.553285 0.707039 0.551122 -0.443126 0.705161 0.603348 -0.37245 0.705155 0.603353 -0.372453 0.706882 0.647813 -0.284001 0.300701 0.897969 -0.321294 0.706245 0.674556 -0.214924 0.705157 0.702679 -0.0948468 0.705157 0.702679 -0.0948468 0 0.957886 -0.287149 0.0279056 0.967576 -0.251033 -0.0239935 0.738226 -0.674127 0 0.763135 -0.646239 0 0.538747 -0.842468 -0.0321119 0.406957 -0.912883 0 0.337774 -0.941227 0 0.0826572 -0.996578 -0.036138 -0.0294245 -0.998914 0 -0.141174 -0.989985 0 -0.392592 -0.919713 -0.0321119 -0.459987 -0.887345 0 -0.587403 -0.809295 0 -0.776849 -0.629687 -0.0200485 -0.79969 -0.600078 0.0239936 -0.972848 -0.2302 0 -0.981057 -0.193719 0 0.967954 -0.251129 -0.0239947 0.957611 -0.287064 0.0200477 0.76298 -0.646111 0 0.738437 -0.674322 0 0.53875 -0.842466 0.0321123 0.406958 -0.912882 0 0.337774 -0.941227 0 0.0826567 -0.996578 0.0361378 -0.0294242 -0.998914 0 -0.141173 -0.989985 0 -0.392591 -0.919713 0.0321127 -0.459987 -0.887345 0 -0.587406 -0.809292 0 -0.79985 -0.6002 0.0239931 -0.776626 -0.629505 -0.0279061 -0.980675 -0.193644 0 -0.973127 -0.230268 0 0.957886 -0.287148 0.0279054 0.967576 -0.251033 -0.0239943 0.738225 -0.674127 0 0.763135 -0.646239 0 0.538747 -0.842468 -0.0321119 0.406957 -0.912883 0 0.337774 -0.941227 0 0.0826567 -0.996578 -0.0361378 -0.0294242 -0.998914 0 -0.141173 -0.989985 0 -0.392593 -0.919712 -0.0321118 -0.459988 -0.887344 0 -0.587403 -0.809294 0 -0.776848 -0.629689 -0.0200491 -0.799689 -0.600079 0.0239936 -0.972848 -0.230198 0 -0.981057 -0.193717 0 0.967954 -0.251129 0.0239947 0.957611 -0.287064 0 0.869971 -0.493103 0 0.738438 -0.674322 0.0400446 0.68543 -0.727036 0 0.538747 -0.842467 0 0.337776 -0.941227 0.0480814 0.230001 -0.972002 0 0.082657 -0.996578 0 -0.141175 -0.989985 0.0480814 -0.286815 -0.956779 0 -0.392592 -0.919713 0 -0.587403 -0.809294 0.0400442 -0.727035 -0.685431 0 -0.776848 -0.629689 0 -0.897493 -0.441029 0.0239936 -0.972848 -0.230198 0 -0.981057 -0.193717 0 0.967954 -0.251129 0 0.967954 -0.251129 0 0.869973 -0.4931 0 0.869973 -0.4931 0 0.738437 -0.674323 0 0.738437 -0.674323 0 0.53875 -0.842466 0 0.53875 -0.842466 0 0.337774 -0.941227 0 0.337774 -0.941227 0 0.0826585 -0.996578 0 0.0826585 -0.996578 0 -0.141176 -0.989985 0 -0.141176 -0.989985 0 -0.392589 -0.919714 0 -0.392589 -0.919714 0 -0.587409 -0.80929 0 -0.587409 -0.80929 0 -0.776848 -0.629689 0 -0.776848 -0.629689 0 -0.897493 -0.441029 0 -0.897493 -0.441029 0 -0.981057 -0.193721 0 -0.981057 -0.193721 0 0.967954 -0.251128 -0.0239946 0.957611 -0.287064 0.020048 0.76298 -0.646111 0 0.738437 -0.674323 0 0.53875 -0.842466 0.0321122 0.406958 -0.912882 0 0.337775 -0.941227 0 0.0826563 -0.996578 0.036138 -0.0294248 -0.998914 0 -0.141175 -0.989985 0 -0.392592 -0.919713 0.0321119 -0.459987 -0.887345 0 -0.587403 -0.809295 0 -0.79985 -0.6002 0.0239947 -0.776624 -0.629507 -0.0279048 -0.980675 -0.193642 0 -0.973128 -0.230264 0 0.957886 -0.28715 0.0279054 0.967576 -0.251035 -0.0239937 0.738224 -0.674129 0 0.763134 -0.646241 0 0.53875 -0.842466 -0.0321123 0.406958 -0.912882 0 0.337774 -0.941227 0 0.0826581 -0.996578 -0.0361381 -0.0294242 -0.998914 0 -0.141174 -0.989985 0 -0.392592 -0.919713 -0.032112 -0.459987 -0.887345 0 -0.587403 -0.809294 0 -0.77685 -0.629685 -0.0200466 -0.799689 -0.600079 0.0239961 -0.972847 -0.230201 0 -0.981057 -0.193717 0 0.967953 -0.251133 0.023992 0.957611 -0.287064 0 0.869982 -0.493083 0 0.738437 -0.674322 0.0400454 0.685429 -0.727038 0 0.538743 -0.84247 0 0.337774 -0.941227 0.0480807 0.230001 -0.972002 0 0.0826593 -0.996578 0 -0.141176 -0.989985 0.0480806 -0.286815 -0.956779 0 -0.392589 -0.919714 0 -0.587403 -0.809294 0.0400448 -0.727037 -0.685429 0 -0.77685 -0.629686 0 -0.897493 -0.441029 0.0239933 -0.972847 -0.230201 0 -0.981057 -0.193721 0 0.967953 -0.251133 -0.0239943 0.95761 -0.287068 0 0.869971 -0.493103 0 0.738439 -0.67432 -0.0400455 0.68543 -0.727036 0 0.538746 -0.842468 0 0.337774 -0.941227 -0.0480811 0.23 -0.972002 0 0.082657 -0.996578 0 -0.141175 -0.989985 -0.0480811 -0.286814 -0.956779 0 -0.39259 -0.919713 0 -0.587403 -0.809294 -0.0400451 -0.727038 -0.685428 0 -0.981058 -0.193717 -0.0239964 -0.972847 -0.230201 0 -0.89748 -0.441055 0 -0.776851 -0.629684 0 0.967953 -0.251131 0.0239933 0.957611 -0.287064 0 0.869977 -0.493093 0 0.738437 -0.674323 0.0400435 0.68543 -0.727036 0 0.538752 -0.842465 0 0.337773 -0.941228 0.0480811 0.229999 -0.972002 0 0.0826567 -0.996578 0 -0.141175 -0.989985 0.0480809 -0.286815 -0.956779 0 -0.39259 -0.919713 0 -0.587403 -0.809294 0.0400448 -0.727037 -0.685429 0 -0.77685 -0.629686 0 -0.897483 -0.44105 0.0239961 -0.972847 -0.230201 0 -0.981058 -0.193717 0 0.967953 -0.251131 0.0239933 0.957611 -0.287064 0 0.869977 -0.493093 0 0.738437 -0.674322 0.0400447 0.685429 -0.727037 0 0.538747 -0.842468 0 0.337774 -0.941227 0.0480813 0.23 -0.972002 0 0.0826567 -0.996578 0 -0.141174 -0.989985 0.0480812 -0.286815 -0.956779 0 -0.392591 -0.919713 0 -0.587403 -0.809294 0.0400446 -0.727037 -0.68543 0 -0.776849 -0.629687 0 -0.897492 -0.441031 0.0239936 -0.972848 -0.2302 0 -0.981057 -0.193719 0 0.957886 -0.287149 0.0279056 0.967576 -0.251033 -0.0239935 0.738226 -0.674127 0 0.763135 -0.646239 0 0.538747 -0.842468 -0.0321118 0.406958 -0.912882 0 0.337775 -0.941227 0 0.0826567 -0.996578 -0.0361379 -0.0294248 -0.998914 0 -0.141174 -0.989985 0 -0.392592 -0.919713 -0.0321118 -0.459986 -0.887345 0 -0.587402 -0.809295 0 -0.776849 -0.629687 -0.0200475 -0.799689 -0.600079 0.023995 -0.972848 -0.2302 0 -0.981057 -0.193717 -0.694746 -0.699927 -0.16562 -0.694746 -0.699928 -0.165619 -0.694746 -0.523345 -0.493396 -0.694745 -0.523345 -0.493395 -0.694745 -0.206532 -0.688965 -0.694746 -0.206532 -0.688965 -0.694745 0.165621 -0.699928 -0.694746 0.165621 -0.699927 -0.694746 0.493395 -0.523345 -0.694745 0.493395 -0.523345 -0.700225 0.668945 -0.249396 -0.711388 0.673201 -0.201808 -0.706344 0.704674 -0.0671858 0 0.957886 -0.287148 0 0.957886 -0.287148 0 0.68598 -0.72762 0 0.68598 -0.72762 0 0.230268 -0.973127 0 0.230268 -0.973127 0 -0.287147 -0.957887 0 -0.287147 -0.957887 0 -0.72762 -0.68598 0 -0.72762 -0.68598 0 -0.973128 -0.230265 0 -0.973128 -0.230265 -0.694746 0.688965 -0.206531 -0.694746 0.688965 -0.206532 -0.694745 0.493395 -0.523345 -0.694746 0.493395 -0.523345 -0.694746 0.16562 -0.699928 -0.694746 0.16562 -0.699928 -0.694745 -0.206532 -0.688965 -0.694746 -0.206532 -0.688965 -0.694746 -0.523345 -0.493395 -0.694746 -0.523345 -0.493395 -0.694746 -0.699927 -0.165621 -0.694745 -0.699928 -0.16562 0 0.957887 -0.287145 0 0.957887 -0.287145 0 0.68598 -0.72762 0 0.68598 -0.72762 0 0.230266 -0.973128 0 0.230266 -0.973128 0 -0.287147 -0.957886 0 -0.287147 -0.957886 0 -0.72762 -0.68598 0 -0.72762 -0.68598 0 -0.973127 -0.230268 0 -0.973127 -0.230268 -0.694744 0.688965 -0.206535 -0.694746 0.688965 -0.206531 -0.694746 0.493396 -0.523344 -0.694746 0.493396 -0.523345 -0.694745 0.165619 -0.699928 -0.694746 0.16562 -0.699927 -0.694746 -0.206531 -0.688966 -0.694745 -0.206531 -0.688965 -0.694746 -0.523344 -0.493396 -0.694746 -0.523345 -0.493396 -0.694745 -0.699929 -0.165617 -0.694746 -0.699927 -0.165619 0 0.957885 -0.287151 0 0.957885 -0.287151 0 0.685982 -0.727619 0 0.685982 -0.727619 0 0.230264 -0.973128 0 0.230264 -0.973128 0 -0.287146 -0.957887 0 -0.287146 -0.957887 0 -0.727619 -0.685982 0 -0.727619 -0.685982 0 -0.973129 -0.230261 0 -0.973129 -0.230261 -0.694745 0.688964 -0.206535 -0.694746 0.688964 -0.206533 -0.694746 0.493396 -0.523344 -0.694746 0.493395 -0.523345 -0.694745 0.16562 -0.699928 -0.694746 0.16562 -0.699928 -0.694745 -0.206534 -0.688965 -0.694746 -0.206532 -0.688965 -0.694746 -0.523346 -0.493394 -0.694746 -0.523346 -0.493394 -0.694746 -0.699927 -0.165621 -0.694746 -0.699927 -0.165621 0 0.957885 -0.287152 0 0.957885 -0.287152 0 0.685982 -0.727619 0 0.685982 -0.727619 0 0.230266 -0.973128 0 0.230266 -0.973128 0 -0.287149 -0.957886 0 -0.287149 -0.957886 0 -0.727621 -0.685979 0 -0.727621 -0.685979 0 -0.973127 -0.230268 0 -0.973127 -0.230268 -0.694746 0.688965 -0.206531 -0.694745 0.688965 -0.206533 -0.694745 0.493394 -0.523347 -0.694746 0.493395 -0.523345 -0.694746 0.16562 -0.699928 -0.694746 0.16562 -0.699927 -0.694745 -0.206533 -0.688965 -0.694746 -0.206532 -0.688965 -0.694745 -0.523346 -0.493394 -0.694746 -0.523346 -0.493394 -0.694746 -0.699927 -0.165621 -0.694746 -0.699927 -0.165621 0 0.957887 -0.287145 0 0.957887 -0.287145 0 0.685978 -0.727622 0 0.685978 -0.727622 0 0.230266 -0.973128 0 0.230266 -0.973128 0 -0.287148 -0.957886 0 -0.287148 -0.957886 0 -0.727622 -0.685979 0 -0.727622 -0.685979 0 -0.973127 -0.230268 0 -0.973127 -0.230268 -0.694746 0.688965 -0.206531 -0.694745 0.688965 -0.206533 -0.694745 0.493394 -0.523347 -0.694746 0.493395 -0.523345 -0.694746 0.16562 -0.699928 -0.694746 0.16562 -0.699927 -0.694745 -0.206534 -0.688965 -0.694746 -0.206532 -0.688965 -0.694746 -0.523346 -0.493394 -0.694746 -0.523345 -0.493395 -0.694746 -0.699927 -0.165621 -0.694746 -0.699927 -0.165621 0 0.957887 -0.287145 0 0.957887 -0.287145 0 0.685978 -0.727622 0 0.685978 -0.727622 0 0.230266 -0.973128 0 0.230266 -0.973128 0 -0.287149 -0.957886 0 -0.287149 -0.957886 0 -0.727621 -0.685979 0 -0.727621 -0.685979 0 -0.973127 -0.230268 0 -0.973127 -0.230268 -0.694745 0.688965 -0.206535 -0.694746 0.688964 -0.206533 -0.694746 0.493396 -0.523344 -0.694746 0.493396 -0.523345 -0.694745 0.165619 -0.699928 -0.694746 0.16562 -0.699927 -0.694746 -0.206531 -0.688965 -0.694746 -0.206532 -0.688965 -0.694745 -0.523346 -0.493394 -0.694746 -0.523346 -0.493394 -0.694746 -0.699927 -0.165621 -0.694746 -0.699927 -0.165621 0 0.957885 -0.287151 0 0.957885 -0.287151 0 0.685982 -0.727619 0 0.685982 -0.727619 0 0.230264 -0.973128 0 0.230264 -0.973128 0 -0.287146 -0.957887 0 -0.287146 -0.957887 0 -0.727622 -0.685978 0 -0.727622 -0.685978 0 -0.973127 -0.230268 0 -0.973127 -0.230268 -0.694745 0.688965 -0.206534 -0.694746 0.688965 -0.206532 -0.694746 0.493397 -0.523343 -0.694745 0.493396 -0.523345 -0.694745 0.165619 -0.699928 -0.694746 0.16562 -0.699927 -0.694746 -0.20653 -0.688965 -0.694745 -0.206532 -0.688965 -0.694745 -0.523345 -0.493395 -0.694746 -0.523345 -0.493396 -0.694745 -0.699928 -0.165619 -0.694746 -0.699927 -0.16562 0 0.957886 -0.287149 0 0.957886 -0.287149 0 0.685983 -0.727618 0 0.685983 -0.727618 0 0.230264 -0.973128 0 0.230264 -0.973128 0 -0.287145 -0.957887 0 -0.287145 -0.957887 0 -0.72762 -0.68598 0 -0.72762 -0.68598 0 -0.973128 -0.230264 0 -0.973128 -0.230264 -0.698073 0.69308 -0.179816 -0.698073 0.69308 -0.179816 -0.698073 0.546425 -0.462724 -0.698073 0.546425 -0.462725 -0.698072 0.291542 -0.653987 -0.698073 0.291543 -0.653986 -0.698073 -0.0210822 -0.715716 -0.698073 -0.0210825 -0.715716 -0.698073 -0.329532 -0.635691 -0.698072 -0.329533 -0.635691 -0.698072 -0.572715 -0.429759 -0.698073 -0.572714 -0.429759 -0.698073 -0.702463 -0.138709 -0.698072 -0.702464 -0.138707 0 0.967953 -0.251131 0 0.967953 -0.251131 0 0.763136 -0.646238 0 0.763136 -0.646238 0 0.407166 -0.913354 0 0.407166 -0.913354 0 -0.0294433 -0.999566 0 -0.0294433 -0.999566 0 -0.460223 -0.887804 0 -0.460223 -0.887804 0 -0.799851 -0.600199 0 -0.799851 -0.600199 0 -0.981057 -0.19372 0 -0.981057 -0.19372 0.980541 -0.0351426 -0.193143 0.980398 -0.196563 -0.0135304 0.980398 -0.196563 -0.0135304 0.980398 -0.176423 -0.0877218 0.979269 -0.180183 -0.0925529 0.980578 -0.182406 -0.0720822 0.980398 -0.190146 -0.0516179 0.979846 -0.192431 -0.0535928 0.98058 -0.193177 -0.0338461 0.980398 -0.129423 -0.148558 0.978034 -0.132764 -0.160699 0.980568 -0.139173 -0.138267 0.980398 -0.155919 -0.120455 0.978666 -0.160094 -0.128778 0.980573 -0.164156 -0.107371 0.980398 -0.0627209 -0.186778 0.976678 -0.0603063 -0.206068 0.980552 -0.0733215 -0.182051 0.980398 -0.0979543 -0.170953 0.977372 -0.0991025 -0.186878 0.980561 -0.108477 -0.163505 0.97595 -0.0178139 -0.217267 0.980398 -0.0250771 -0.195426 0.980529 0.00449892 -0.196323 0.978323 0.0142211 -0.206596 0.980541 0.0237128 -0.194877 0.980515 0.0439823 -0.191457 0.978403 0.054154 -0.199489 0.980552 0.0624784 -0.186051 0.9805 0.0816915 -0.178737 0.978561 0.0916981 -0.18442 0.980561 0.0986646 -0.169607 0.980483 0.116083 -0.158678 0.978794 0.125234 -0.162105 0.980568 0.130793 -0.146219 0.980464 0.145745 -0.132094 0.9791 0.153346 -0.133595 0.980573 0.157551 -0.116847 0.980444 0.16946 -0.100068 0.979473 0.174897 -0.100214 0.980578 0.177847 -0.0826933 0.980422 0.186252 -0.0639037 0.979908 0.189074 -0.0634919 0.98058 0.19085 -0.0451591 0.980398 0.195426 -0.025077 0.980398 0.195426 -0.0250771 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.992586 -0.121547 0 0.992586 -0.121547 0 0.953351 -0.301864 0 0.953351 -0.301864 0 0.881651 -0.471902 0 0.881651 -0.471902 0 0.779927 -0.62587 0 0.779927 -0.62587 0 0.651644 -0.758525 0 0.651644 -0.758525 0 0.50117 -0.865349 0 0.50117 -0.865349 0 0.33363 -0.942704 0 0.33363 -0.942704 0 0.154727 -0.987957 0 0.154727 -0.987957 0 -0.0294439 -0.999566 0 -0.0294439 -0.999566 0 -0.212612 -0.977137 0 -0.212612 -0.977137 0 -0.388541 -0.921432 0 -0.388541 -0.921432 0 -0.551237 -0.834348 0 -0.551237 -0.834348 0 -0.695163 -0.718852 0 -0.695163 -0.718852 0 -0.815415 -0.578877 0 -0.815415 -0.578877 0 -0.907899 -0.419188 0 -0.907899 -0.419188 0 -0.969466 -0.245225 0 -0.969466 -0.245225 0 -0.998019 -0.0629097 0 -0.998019 -0.0629097 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.998019 -0.0629102 0 -0.998019 -0.0629102 0 -0.969466 -0.245225 0 -0.969466 -0.245225 0 -0.907899 -0.419188 0 -0.907899 -0.419188 0 -0.815415 -0.578877 0 -0.815415 -0.578877 0 -0.695163 -0.718852 0 -0.695163 -0.718852 0 -0.551237 -0.834348 0 -0.551237 -0.834348 0 -0.388541 -0.921432 0 -0.388541 -0.921432 0 -0.212613 -0.977137 0 -0.212613 -0.977137 0 -0.0294436 -0.999566 0 -0.0294436 -0.999566 0 0.154728 -0.987957 0 0.154728 -0.987957 0 0.333629 -0.942704 0 0.333629 -0.942704 0 0.50117 -0.865349 0 0.50117 -0.865349 0 0.651644 -0.758525 0 0.651644 -0.758525 0 0.779927 -0.62587 0 0.779927 -0.62587 0 0.881651 -0.471902 0 0.881651 -0.471902 0 0.953351 -0.301865 0 0.953351 -0.301865 0 0.992586 -0.121546 0 0.992586 -0.121546 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.992586 -0.121547 0 0.992586 -0.121547 0 0.953351 -0.301864 0 0.953351 -0.301864 0 0.881651 -0.471902 0 0.881651 -0.471902 0 0.779927 -0.62587 0 0.779927 -0.62587 0 0.651644 -0.758525 0 0.651644 -0.758525 0 0.501171 -0.865349 0 0.501171 -0.865349 0 0.333629 -0.942704 0 0.333629 -0.942704 0 0.154727 -0.987957 0 0.154727 -0.987957 0 -0.0294441 -0.999566 0 -0.0294441 -0.999566 0 -0.212612 -0.977137 0 -0.212612 -0.977137 0 -0.388541 -0.921432 0 -0.388541 -0.921432 0 -0.551238 -0.834348 0 -0.551238 -0.834348 0 -0.695163 -0.718852 0 -0.695163 -0.718852 0 -0.815415 -0.578877 0 -0.815415 -0.578877 0 -0.907899 -0.419189 0 -0.907899 -0.419189 0 -0.969466 -0.245224 0 -0.969466 -0.245224 0 -0.998019 -0.0629102 0 -0.998019 -0.0629102 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.992586 -0.121547 0 0.992586 -0.121547 0 0.953351 -0.301864 0 0.953351 -0.301864 0 0.881651 -0.471902 0 0.881651 -0.471902 0 0.779927 -0.62587 0 0.779927 -0.62587 0 0.651644 -0.758525 0 0.651644 -0.758525 0 0.50117 -0.865349 0 0.50117 -0.865349 0 0.33363 -0.942704 0 0.33363 -0.942704 0 0.154727 -0.987957 0 0.154727 -0.987957 0 -0.0294436 -0.999566 0 -0.0294436 -0.999566 0 -0.212613 -0.977137 0 -0.212613 -0.977137 0 -0.38854 -0.921432 0 -0.38854 -0.921432 0 -0.551238 -0.834348 0 -0.551238 -0.834348 0 -0.695163 -0.718853 0 -0.695163 -0.718853 0 -0.815415 -0.578877 0 -0.815415 -0.578877 0 -0.907899 -0.419188 0 -0.907899 -0.419188 0 -0.969466 -0.245224 0 -0.969466 -0.245224 0 -0.998019 -0.0629112 0 -0.998019 -0.0629112 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.998329 -0.0577862 0 -0.998329 -0.0577862 0 -0.973128 -0.230266 0 -0.973128 -0.230266 0 -0.918358 -0.39575 0 -0.918358 -0.39575 0 -0.835685 -0.549209 0 -0.835685 -0.549209 0 -0.72762 -0.68598 0 -0.72762 -0.68598 0 -0.597447 -0.801909 0 -0.597447 -0.801909 0 -0.44912 -0.893471 0 -0.44912 -0.893471 0 -0.287148 -0.957886 0 -0.287148 -0.957886 0 -0.11645 -0.993197 0 -0.11645 -0.993197 0 0.0577863 -0.998329 0 0.0577863 -0.998329 0 0.230266 -0.973128 0 0.230266 -0.973128 0 0.39575 -0.918358 0 0.39575 -0.918358 0 0.549209 -0.835685 0 0.549209 -0.835685 0 0.68598 -0.72762 0 0.68598 -0.72762 0 0.801909 -0.597446 0 0.801909 -0.597446 0 0.893471 -0.44912 0 0.893471 -0.44912 0 0.957887 -0.287147 0 0.957887 -0.287147 0 0.993197 -0.11645 0 0.993197 -0.11645 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.998329 -0.0577862 0 -0.998329 -0.0577862 0 -0.973128 -0.230266 0 -0.973128 -0.230266 0 -0.918358 -0.39575 0 -0.918358 -0.39575 0 -0.835685 -0.549209 0 -0.835685 -0.549209 0 -0.72762 -0.68598 0 -0.72762 -0.68598 0 -0.597447 -0.801909 0 -0.597447 -0.801909 0 -0.44912 -0.893471 0 -0.44912 -0.893471 0 -0.287147 -0.957886 0 -0.287147 -0.957886 0 -0.11645 -0.993197 0 -0.11645 -0.993197 0 0.0577864 -0.998329 0 0.0577864 -0.998329 0 0.230266 -0.973128 0 0.230266 -0.973128 0 0.395749 -0.918359 0 0.395749 -0.918359 0 0.549209 -0.835685 0 0.549209 -0.835685 0 0.68598 -0.72762 0 0.68598 -0.72762 0 0.801908 -0.597447 0 0.801908 -0.597447 0 0.893471 -0.44912 0 0.893471 -0.44912 0 0.957886 -0.287147 0 0.957886 -0.287147 0 0.993197 -0.11645 0 0.993197 -0.11645 -0.809968 0.582484 -0.0682946 -0.809969 0.582483 -0.0682948 -0.809969 0.561775 -0.168404 -0.809969 0.561775 -0.168404 -0.809969 0.523997 -0.263397 -0.809969 0.523996 -0.263397 -0.809969 0.470297 -0.350386 -0.809968 0.470298 -0.350387 -0.809968 0.402309 -0.42673 -0.809968 0.40231 -0.42673 -0.809968 0.322097 -0.490107 -0.809969 0.322096 -0.490107 -0.809969 0.232096 -0.538593 -0.809968 0.232097 -0.538593 -0.809968 0.135045 -0.570714 -0.809969 0.135045 -0.570713 -0.809969 0.0338902 -0.585493 -0.809968 0.0338902 -0.585493 -0.809968 -0.0682948 -0.582483 -0.809968 -0.0682948 -0.582483 -0.809968 -0.168404 -0.561775 -0.809968 -0.168404 -0.561775 -0.809968 -0.263397 -0.523997 -0.809969 -0.263397 -0.523997 -0.809969 -0.350387 -0.470298 -0.809969 -0.350387 -0.470298 -0.809969 -0.42673 -0.402309 -0.809968 -0.42673 -0.402309 -0.809968 -0.490107 -0.322096 -0.809969 -0.490107 -0.322096 -0.809969 -0.538593 -0.232097 -0.809969 -0.538593 -0.232097 -0.809969 -0.570713 -0.135045 -0.809969 -0.570713 -0.135045 -0.809969 -0.585493 -0.0338901 -0.809969 -0.585493 -0.03389 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.997168 -0.0752006 0 -0.997168 -0.0752006 0 -0.959743 -0.28088 0 -0.959743 -0.28088 0 -0.880372 -0.474284 0 -0.880372 -0.474284 0 -0.762524 -0.646959 0 -0.762524 -0.646959 0 -0.611351 -0.791359 0 -0.611351 -0.791359 0 -0.433459 -0.901173 0 -0.433459 -0.901173 0 -0.236622 -0.971602 0 -0.236622 -0.971602 0 -0.0294438 -0.999566 0 -0.0294438 -0.999566 0 0.179021 -0.983845 0 0.179021 -0.983845 0 0.379662 -0.925125 0 0.379662 -0.925125 0 0.56371 -0.825973 0 0.56371 -0.825973 0 0.723121 -0.690722 0 0.723121 -0.690722 0 0.850928 -0.525282 0 0.850928 -0.525282 0 0.941546 -0.336885 0 0.941546 -0.336885 0 0.991013 -0.133766 0 0.991013 -0.133766 0 -0.997168 -0.0752006 0.142206 -0.9875 -0.0679747 0 -0.984996 -0.172579 0 -0.959743 -0.28088 0.276149 -0.925878 -0.257861 0 -0.930016 -0.367519 0 -0.889514 -0.456908 0.330675 -0.830846 -0.447603 0.443079 -0.548066 -0.70944 0 -0.836881 -0.547385 0 -0.779199 -0.626777 0.396034 -0.700177 -0.594061 0 -0.709413 -0.704793 0 -0.636916 -0.770933 0.492702 -0.205908 -0.845486 0 -0.552843 -0.833286 0 -0.468504 -0.883461 0.474609 -0.381529 -0.79321 0 -0.373591 -0.927593 0 -0.280872 -0.959745 0 -0.179012 -0.983847 0 -0.0817167 -0.996656 0.498596 -0.0255229 -0.866459 0 0.0229099 -0.999738 0 0.12079 -0.992678 0.492706 0.155783 -0.856138 0 0.223893 -0.974614 0 0.318343 -0.947976 0.474611 0.334177 -0.814291 0 0.41569 -0.909507 0 0.502834 -0.864383 0.443085 0.505354 -0.740468 0 0.590434 -0.807086 0 0.666699 -0.745327 0.396028 0.663997 -0.634247 0 0.740954 -0.671556 0 0.80321 -0.595696 0.330673 0.803059 -0.495733 0 0.861077 -0.508474 0 0.906772 -0.421621 0.243908 0.913109 -0.326711 0 0.991867 -0.127277 0.133517 0.98214 -0.132568 0 0.973128 -0.230263 0 0.945875 -0.324533 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.997168 0.0752008 0.142215 0.987499 0.0679743 0 0.984995 0.172585 0 0.959743 0.28088 0.27615 0.925877 0.257861 0.396033 0.700177 0.594062 0 0.930016 0.36752 0 0.889514 0.456907 0.330676 0.830846 0.447603 0 0.836881 0.547385 0 0.779198 0.626777 0.474616 0.381527 0.793207 0 0.709413 0.704793 0 0.636917 0.770933 0.44308 0.548065 0.70944 0 0.552843 0.833286 0 0.468505 0.883461 0.498596 0.0255229 0.866459 0 0.37359 0.927594 0 0.280873 0.959745 0.492705 0.205908 0.845484 0 0.179012 0.983847 0 0.0817166 0.996656 0 -0.0229099 0.999738 0 -0.120791 0.992678 0.4927 -0.155784 0.856142 0 -0.223892 0.974614 0 -0.318343 0.947976 0.474613 -0.334177 0.81429 0 -0.41569 0.909506 0 -0.502835 0.864382 0.443078 -0.505356 0.740471 0 -0.590433 0.807087 0 -0.666699 0.745327 0.396028 -0.663997 0.634247 0 -0.740954 0.671556 0 -0.80321 0.595697 0.330674 -0.803059 0.495733 0 -0.861077 0.508474 0 -0.906771 0.421624 0.243915 -0.913108 0.326711 0 -0.991867 0.127277 0.133508 -0.982141 0.132568 0 -0.97313 0.230256 0 -0.945875 0.324533 0 0.997168 0.0752008 0 0.997168 0.0752008 0 0.959743 0.28088 0 0.959743 0.28088 0 0.880372 0.474284 0 0.880372 0.474284 0 0.762524 0.64696 0 0.762524 0.64696 0 0.611351 0.791359 0 0.611351 0.791359 0 0.433458 0.901174 0 0.433458 0.901174 0 0.236622 0.971602 0 0.236622 0.971602 0 0.0294438 0.999566 0 0.0294438 0.999566 0 -0.179021 0.983845 0 -0.179021 0.983845 0 -0.379662 0.925125 0 -0.379662 0.925125 0 -0.56371 0.825973 0 -0.56371 0.825973 0 -0.723121 0.690721 0 -0.723121 0.690721 0 -0.850928 0.525282 0 -0.850928 0.525282 0 -0.941546 0.336886 0 -0.941546 0.336886 0 -0.991013 0.133766 0 -0.991013 0.133766 -0.809969 -0.582483 0.0682947 -0.809969 -0.582483 0.0682947 -0.809969 -0.561775 0.168404 -0.809969 -0.561775 0.168404 -0.809968 -0.523997 0.263397 -0.809968 -0.523997 0.263397 -0.809969 -0.470298 0.350387 -0.809969 -0.470298 0.350386 -0.809969 -0.402309 0.42673 -0.809969 -0.402309 0.42673 -0.809969 -0.322096 0.490107 -0.809969 -0.322096 0.490107 -0.809969 -0.232097 0.538593 -0.809968 -0.232097 0.538593 -0.809968 -0.135045 0.570714 -0.809968 -0.135045 0.570713 -0.809968 -0.03389 0.585494 -0.809969 -0.03389 0.585493 -0.809969 0.0682946 0.582483 -0.809969 0.0682947 0.582483 -0.809969 0.168404 0.561774 -0.809969 0.168404 0.561774 -0.809969 0.263397 0.523997 -0.809969 0.263397 0.523997 -0.809969 0.350386 0.470298 -0.809969 0.350386 0.470298 -0.809969 0.42673 0.402309 -0.809968 0.42673 0.40231 -0.809968 0.490107 0.322097 -0.809969 0.490107 0.322096 -0.809969 0.538592 0.232096 -0.809968 0.538593 0.232097 -0.809968 0.570714 0.135046 -0.809969 0.570713 0.135044 -0.809969 0.585493 0.03389 -0.809968 0.585494 0.0338907 0 0.998329 0.0577861 0 0.998329 0.0577861 0 0.973128 0.230267 0 0.973128 0.230267 0 0.918359 0.395749 0 0.918359 0.395749 0 0.835685 0.549209 0 0.835685 0.549209 0 0.72762 0.68598 0 0.72762 0.68598 0 0.597447 0.801909 0 0.597447 0.801909 0 0.44912 0.893471 0 0.44912 0.893471 0 0.287147 0.957886 0 0.287147 0.957886 0 0.11645 0.993197 0 0.11645 0.993197 0 -0.0577861 0.998329 0 -0.0577861 0.998329 0 -0.230266 0.973128 0 -0.230266 0.973128 0 -0.39575 0.918358 0 -0.39575 0.918358 0 -0.549209 0.835685 0 -0.549209 0.835685 0 -0.68598 0.72762 0 -0.68598 0.72762 0 -0.801909 0.597447 0 -0.801909 0.597447 0 -0.893471 0.44912 0 -0.893471 0.44912 0 -0.957886 0.287147 0 -0.957886 0.287147 0 -0.993197 0.11645 0 -0.993197 0.11645 0 0.998329 0.0577851 0 0.998329 0.0577851 0 0.973128 0.230267 0 0.973128 0.230267 0 0.918359 0.39575 0 0.918359 0.39575 0 0.835685 0.549209 0 0.835685 0.549209 0 0.72762 0.68598 0 0.72762 0.68598 0 0.597447 0.801908 0 0.597447 0.801908 0 0.44912 0.893472 0 0.44912 0.893472 0 0.287147 0.957886 0 0.287147 0.957886 0 0.11645 0.993197 0 0.11645 0.993197 0 -0.0577859 0.998329 0 -0.0577859 0.998329 0 -0.230266 0.973128 0 -0.230266 0.973128 0 -0.39575 0.918358 0 -0.39575 0.918358 0 -0.549209 0.835685 0 -0.549209 0.835685 0 -0.68598 0.72762 0 -0.68598 0.72762 0 -0.801909 0.597447 0 -0.801909 0.597447 0 -0.893471 0.44912 0 -0.893471 0.44912 0 -0.957886 0.287147 0 -0.957886 0.287147 0 -0.993197 0.11645 0 -0.993197 0.11645 0 -0.992586 0.121548 0 -0.992586 0.121548 0 -0.953351 0.301864 0 -0.953351 0.301864 0 -0.881651 0.471902 0 -0.881651 0.471902 0 -0.779927 0.62587 0 -0.779927 0.62587 0 -0.651644 0.758525 0 -0.651644 0.758525 0 -0.501171 0.865349 0 -0.501171 0.865349 0 -0.333629 0.942704 0 -0.333629 0.942704 0 -0.154727 0.987957 0 -0.154727 0.987957 0 0.029444 0.999566 0 0.029444 0.999566 0 0.212612 0.977137 0 0.212612 0.977137 0 0.388541 0.921432 0 0.388541 0.921432 0 0.551237 0.834348 0 0.551237 0.834348 0 0.695163 0.718852 0 0.695163 0.718852 0 0.815415 0.578877 0 0.815415 0.578877 0 0.907899 0.419188 0 0.907899 0.419188 0 0.969466 0.245224 0 0.969466 0.245224 0 0.998019 0.0629101 0 0.998019 0.0629101 0 -0.992586 0.121547 0 -0.992586 0.121547 0 -0.953351 0.301864 0 -0.953351 0.301864 0 -0.881651 0.471903 0 -0.881651 0.471903 0 -0.779928 0.62587 0 -0.779928 0.62587 0 -0.651644 0.758525 0 -0.651644 0.758525 0 -0.50117 0.865349 0 -0.50117 0.865349 0 -0.33363 0.942704 0 -0.33363 0.942704 0 -0.154727 0.987957 0 -0.154727 0.987957 0 0.0294437 0.999566 0 0.0294437 0.999566 0 0.212613 0.977137 0 0.212613 0.977137 0 0.388541 0.921432 0 0.388541 0.921432 0 0.551237 0.834348 0 0.551237 0.834348 0 0.695163 0.718852 0 0.695163 0.718852 0 0.815415 0.578877 0 0.815415 0.578877 0 0.907899 0.419188 0 0.907899 0.419188 0 0.969466 0.245224 0 0.969466 0.245224 0 0.998019 0.0629102 0 0.998019 0.0629102 0 0.998019 0.0629102 0 0.998019 0.0629102 0 0.969466 0.245224 0 0.969466 0.245224 0 0.907899 0.419188 0 0.907899 0.419188 0 0.815415 0.578877 0 0.815415 0.578877 0 0.695163 0.718852 0 0.695163 0.718852 0 0.551238 0.834348 0 0.551238 0.834348 0 0.388541 0.921432 0 0.388541 0.921432 0 0.212612 0.977137 0 0.212612 0.977137 0 0.0294436 0.999566 0 0.0294436 0.999566 0 -0.154727 0.987957 0 -0.154727 0.987957 0 -0.33363 0.942704 0 -0.33363 0.942704 0 -0.50117 0.865349 0 -0.50117 0.865349 0 -0.651644 0.758525 0 -0.651644 0.758525 0 -0.779927 0.62587 0 -0.779927 0.62587 0 -0.881651 0.471902 0 -0.881651 0.471902 0 -0.953351 0.301864 0 -0.953351 0.301864 0 -0.992586 0.121547 0 -0.992586 0.121547 0 -0.992586 0.121547 0 -0.992586 0.121547 0 -0.953351 0.301864 0 -0.953351 0.301864 0 -0.881651 0.471902 0 -0.881651 0.471902 0 -0.779927 0.62587 0 -0.779927 0.62587 0 -0.651644 0.758525 0 -0.651644 0.758525 0 -0.50117 0.865349 0 -0.50117 0.865349 0 -0.333629 0.942704 0 -0.333629 0.942704 0 -0.154728 0.987957 0 -0.154728 0.987957 0 0.0294439 0.999566 0 0.0294439 0.999566 0 0.212612 0.977137 0 0.212612 0.977137 0 0.38854 0.921432 0 0.38854 0.921432 0 0.551238 0.834348 0 0.551238 0.834348 0 0.695163 0.718852 0 0.695163 0.718852 0 0.815415 0.578877 0 0.815415 0.578877 0 0.907899 0.419188 0 0.907899 0.419188 0 0.969466 0.245225 0 0.969466 0.245225 0 0.998019 0.0629101 0 0.998019 0.0629101 0.980541 0.0351427 0.193143 0.980398 0.196563 0.0135305 0.980398 0.196563 0.0135304 0.980398 0.176423 0.087722 0.979269 0.180183 0.0925527 0.980578 0.182406 0.0720822 0.980398 0.190146 0.0516178 0.979846 0.192431 0.0535928 0.98058 0.193177 0.0338475 0.980398 0.129424 0.148559 0.978034 0.132764 0.160699 0.980568 0.139173 0.138267 0.980398 0.155919 0.120455 0.978665 0.160094 0.128778 0.980573 0.164156 0.107371 0.980398 0.0627209 0.186778 0.976678 0.0603064 0.206068 0.980552 0.0733213 0.182051 0.980398 0.0979545 0.170953 0.977372 0.0991027 0.186878 0.980561 0.108477 0.163505 0.97595 0.0178139 0.217267 0.980398 0.0250771 0.195426 0.980529 -0.00449893 0.196323 0.978323 -0.014221 0.206596 0.980541 -0.023713 0.194876 0.980515 -0.043982 0.191456 0.978403 -0.0541541 0.199489 0.980552 -0.0624784 0.186051 0.9805 -0.0816916 0.178737 0.978561 -0.0916982 0.18442 0.980561 -0.0986648 0.169606 0.980483 -0.116082 0.158678 0.978794 -0.125234 0.162105 0.980568 -0.130793 0.146219 0.980464 -0.145745 0.132094 0.9791 -0.153346 0.133595 0.980573 -0.157551 0.116847 0.980444 -0.16946 0.100068 0.979473 -0.174897 0.100214 0.980578 -0.177847 0.0826939 0.980422 -0.186252 0.0639037 0.979908 -0.189074 0.0634919 0.98058 -0.19085 0.0451578 0.980398 -0.195426 0.025077 0.980398 -0.195426 0.0250771 0 -0.957886 0.287148 0 -0.957886 0.287148 0 -0.68598 0.72762 0 -0.68598 0.72762 0 -0.230266 0.973128 0 -0.230266 0.973128 0 0.287147 0.957887 0 0.287147 0.957887 0 0.72762 0.685981 0 0.72762 0.685981 0 0.973128 0.230265 0 0.973128 0.230265 -0.694745 -0.688965 0.206533 -0.694746 -0.688965 0.206532 -0.694745 -0.493395 0.523345 -0.694746 -0.493395 0.523345 -0.694745 -0.16562 0.699928 -0.694746 -0.165621 0.699927 -0.694746 0.206532 0.688965 -0.694746 0.206532 0.688965 -0.694745 0.523345 0.493396 -0.694745 0.523345 0.493396 -0.694745 0.699928 0.165619 -0.694746 0.699927 0.16562 0 -0.957886 0.287149 0 -0.957886 0.287149 0 -0.685982 0.727619 0 -0.685982 0.727619 0 -0.230266 0.973128 0 -0.230266 0.973128 0 0.287147 0.957886 0 0.287147 0.957886 0 0.72762 0.685981 0 0.72762 0.685981 0 0.973127 0.230268 0 0.973127 0.230268 -0.704845 0.706895 0.0591048 -0.71628 0.679061 0.160684 -0.694746 -0.688965 0.206533 -0.694746 -0.688965 0.206533 -0.694746 -0.493396 0.523344 -0.694745 -0.493395 0.523345 -0.694745 -0.16562 0.699928 -0.694746 -0.165621 0.699927 -0.694746 0.206532 0.688965 -0.694746 0.206533 0.688965 -0.694746 0.523344 0.493395 -0.694745 0.523345 0.493395 -0.703159 0.669083 0.240615 0 -0.957887 0.287146 0 -0.957887 0.287146 0 -0.685978 0.727622 0 -0.685978 0.727622 0 -0.230269 0.973127 0 -0.230269 0.973127 0 0.287147 0.957887 0 0.287147 0.957887 0 0.727622 0.685978 0 0.727622 0.685978 0 0.973127 0.230268 0 0.973127 0.230268 -0.694746 -0.688965 0.206531 -0.694745 -0.688965 0.206533 -0.694745 -0.493394 0.523347 -0.694746 -0.493395 0.523345 -0.694746 -0.165622 0.699927 -0.694745 -0.165621 0.699928 -0.694746 0.206532 0.688965 -0.694745 0.206533 0.688965 -0.694745 0.523347 0.493394 -0.694746 0.523345 0.493396 -0.694746 0.699927 0.165622 -0.694746 0.699927 0.165621 0 -0.957887 0.287146 0 -0.957887 0.287146 0 -0.685978 0.727622 0 -0.685978 0.727622 0 -0.230267 0.973127 0 -0.230267 0.973127 0 0.287146 0.957887 0 0.287146 0.957887 0 0.727622 0.685979 0 0.727622 0.685979 0 0.973127 0.230268 0 0.973127 0.230268 -0.694746 -0.688965 0.206531 -0.694745 -0.688965 0.206533 -0.694745 -0.493394 0.523347 -0.694746 -0.493395 0.523345 -0.694746 -0.165621 0.699927 -0.694745 -0.16562 0.699928 -0.694746 0.206532 0.688965 -0.694745 0.206533 0.688965 -0.694745 0.523347 0.493395 -0.694745 0.523345 0.493396 -0.694746 0.699927 0.165621 -0.694746 0.699927 0.165621 0 -0.957887 0.287146 0 -0.957887 0.287146 0 -0.685978 0.727622 0 -0.685978 0.727622 0 -0.230268 0.973127 0 -0.230268 0.973127 0 0.287146 0.957887 0 0.287146 0.957887 0 0.727622 0.685979 0 0.727622 0.685979 0 0.973127 0.230268 0 0.973127 0.230268 -0.694746 -0.688965 0.206531 -0.694745 -0.688965 0.206533 -0.694745 -0.493394 0.523347 -0.694746 -0.493395 0.523345 -0.694746 -0.165621 0.699927 -0.694745 -0.165621 0.699928 -0.694746 0.206531 0.688965 -0.694745 0.206533 0.688965 -0.694745 0.523347 0.493394 -0.694746 0.523345 0.493396 -0.694746 0.699927 0.165621 -0.694746 0.699927 0.165621 0 -0.967954 0.251128 0 -0.967954 0.251128 0 -0.763136 0.646238 0 -0.763136 0.646238 0 -0.407166 0.913354 0 -0.407166 0.913354 0 0.0294453 0.999566 0 0.0294453 0.999566 0 0.460223 0.887804 0 0.460223 0.887804 0 0.799853 0.600197 0 0.799853 0.600197 0 0.981056 0.193724 0 0.981056 0.193724 -0.698073 -0.693081 0.179814 -0.698073 -0.693081 0.179816 -0.698073 -0.546426 0.462724 -0.698072 -0.546425 0.462725 -0.698072 -0.291542 0.653987 -0.698073 -0.291543 0.653986 -0.698072 0.0210836 0.715717 -0.698073 0.0210825 0.715716 -0.698073 0.329532 0.635691 -0.698072 0.329533 0.635691 -0.698072 0.572717 0.429757 -0.698073 0.572714 0.429759 -0.698073 0.702462 0.138711 -0.698073 0.702463 0.13871 0 -0.957887 0.287146 0 -0.957887 0.287146 0 -0.685982 0.727619 0 -0.685982 0.727619 0 -0.230268 0.973127 0 -0.230268 0.973127 0 0.287149 0.957886 0 0.287149 0.957886 0 0.727619 0.685982 0 0.727619 0.685982 0 0.973127 0.230268 0 0.973127 0.230268 -0.694746 -0.688965 0.206531 -0.694746 -0.688965 0.206531 -0.694746 -0.493396 0.523343 -0.694746 -0.493395 0.523345 -0.694746 -0.165621 0.699927 -0.694745 -0.16562 0.699928 -0.694745 0.206534 0.688965 -0.694746 0.206532 0.688965 -0.694746 0.523344 0.493396 -0.694746 0.523345 0.493396 -0.694746 0.699927 0.165622 -0.694745 0.699928 0.165619 0 -0.957886 0.287149 0 -0.957886 0.287149 0 -0.685982 0.727619 0 -0.685982 0.727619 0 -0.230265 0.973128 0 -0.230265 0.973128 0 0.287148 0.957886 0 0.287148 0.957886 0 0.727619 0.685982 0 0.727619 0.685982 0 0.973128 0.230264 0 0.973128 0.230264 -0.694745 -0.688965 0.206534 -0.694746 -0.688965 0.206532 -0.694746 -0.493396 0.523344 -0.694746 -0.493396 0.523345 -0.694745 -0.16562 0.699928 -0.694746 -0.16562 0.699927 -0.694746 0.206533 0.688965 -0.694746 0.206533 0.688965 -0.694746 0.523344 0.493396 -0.694745 0.523345 0.493396 -0.694745 0.699928 0.165619 -0.694746 0.699927 0.16562 0 -0.957886 0.287148 0 -0.957886 0.287148 0 -0.685982 0.727619 0 -0.685982 0.727619 0 -0.230266 0.973128 0 -0.230266 0.973128 0 0.287147 0.957886 0 0.287147 0.957886 0 0.72762 0.68598 0 0.72762 0.68598 0 0.973127 0.230268 0 0.973127 0.230268 -0.694746 -0.688965 0.206533 -0.694746 -0.688965 0.206533 -0.694746 -0.493396 0.523344 -0.694745 -0.493396 0.523344 -0.694746 -0.16562 0.699928 -0.694746 -0.16562 0.699928 -0.694745 0.206532 0.688965 -0.694746 0.206532 0.688965 -0.694746 0.523345 0.493395 -0.694746 0.523345 0.493395 -0.694746 0.699927 0.165621 -0.694745 0.699928 0.16562 0 -0.957887 0.287147 0 -0.957887 0.287147 0 -0.68598 0.72762 0 -0.68598 0.72762 0 -0.230266 0.973128 0 -0.230266 0.973128 0 0.287147 0.957887 0 0.287147 0.957887 0 0.727621 0.685979 0 0.727621 0.685979 0 0.973127 0.230268 0 0.973127 0.230268 0 -0.967953 0.251131 -0.0239931 -0.957611 0.287064 0.0200491 -0.762981 0.646109 0 -0.738437 0.674323 0 -0.53875 0.842466 0.0321125 -0.406957 0.912883 0 -0.337773 0.941228 0 -0.0826593 0.996578 0.0361385 0.0294243 0.998914 0 0.141175 0.989985 0 0.392591 0.919713 0.0321127 0.459987 0.887345 0 0.587406 0.809292 0 0.79985 0.6002 0.023995 0.776624 0.629507 -0.0279045 0.980675 0.193644 0 0.973128 0.230266 0 -0.967954 0.251129 -0.0239947 -0.957611 0.287064 0.0200477 -0.76298 0.646111 0 -0.738437 0.674322 0 -0.53875 0.842466 0.0321123 -0.406958 0.912882 0 -0.337774 0.941227 0 -0.0826563 0.996578 0.0361382 0.0294253 0.998914 0 0.141176 0.989985 0 0.392591 0.919713 0.0321118 0.459985 0.887346 0 0.587401 0.809296 0 0.799851 0.600199 0.0239937 0.776626 0.629505 -0.0279048 0.980675 0.193644 0 0.973128 0.230266 0 -0.957887 0.287147 0.0279059 -0.967577 0.251031 -0.0239934 -0.738225 0.674128 0 -0.763134 0.646241 0 -0.53875 0.842466 -0.0321123 -0.406958 0.912882 0 -0.337774 0.941227 0 -0.0826563 0.996578 -0.0361378 0.0294242 0.998914 0 0.141174 0.989985 0 0.392589 0.919714 -0.0321133 0.459987 0.887345 0 0.587409 0.80929 0 0.776848 0.629688 -0.0200486 0.799689 0.600079 0.0239934 0.972847 0.230201 0 0.981057 0.193721 0 -0.957887 0.287147 0 -0.957887 0.287147 0 -0.685981 0.72762 0 -0.685981 0.72762 0 -0.230266 0.973128 0 -0.230266 0.973128 0 0.287147 0.957886 0 0.287147 0.957886 0 0.727621 0.68598 0 0.727621 0.68598 0 0.973127 0.230268 0 0.973127 0.230268 0 -0.957887 0.287147 0 -0.957887 0.287147 0 -0.685981 0.72762 0 -0.685981 0.72762 0 -0.230266 0.973128 0 -0.230266 0.973128 0 0.287147 0.957887 0 0.287147 0.957887 0 0.727621 0.685979 0 0.727621 0.685979 0 0.973127 0.230268 0 0.973127 0.230268 0 -0.967954 0.251129 0.0239946 -0.957611 0.287064 0 -0.869972 0.493102 0 -0.738437 0.674322 0.040044 -0.68543 0.727036 0 -0.53875 0.842466 0 -0.337774 0.941227 0.0480811 -0.23 0.972002 0 -0.082657 0.996578 0 0.141174 0.989985 0.0480816 0.286815 0.956779 0 0.392592 0.919713 0 0.587402 0.809295 0.0400451 0.727037 0.685429 0 0.776851 0.629685 0 0.897481 0.441053 0.0239962 0.972847 0.230201 0 0.981057 0.193717 0 -0.967953 0.251133 0.0239943 -0.95761 0.287068 0 -0.869971 0.493103 0 -0.73844 0.674319 0.040046 -0.68543 0.727036 0 -0.538743 0.84247 0 -0.337774 0.941227 0.0480807 -0.230001 0.972002 0 -0.0826593 0.996578 0 0.141175 0.989985 0.0480814 0.286815 0.956779 0 0.392592 0.919713 0 0.587403 0.809294 0.0400448 0.727037 0.685429 0 0.77685 0.629686 0 0.897483 0.44105 0.0239961 0.972847 0.230201 0 0.981057 0.193717 0 -0.967954 0.251129 -0.0239944 -0.957611 0.287064 0 -0.869974 0.493097 0 -0.738437 0.674323 -0.0400443 -0.685429 0.727037 0 -0.538747 0.842467 0 -0.337777 0.941226 -0.0480821 -0.230001 0.972002 0 -0.0826563 0.996578 0 0.141176 0.989985 -0.0480812 0.286817 0.956778 0 0.392593 0.919712 0 0.587399 0.809298 -0.0400452 0.727035 0.685431 0 0.981057 0.193717 -0.0239936 0.972848 0.230198 0 0.897493 0.441029 0 0.776849 0.629687 0 -0.957887 0.287147 0 -0.957887 0.287147 0 -0.685981 0.72762 0 -0.685981 0.72762 0 -0.230266 0.973128 0 -0.230266 0.973128 0 0.287146 0.957887 0 0.287146 0.957887 0 0.727621 0.68598 0 0.727621 0.68598 0 0.973127 0.230268 0 0.973127 0.230268 0 -0.967953 0.251131 0.0239943 -0.95761 0.287066 0 -0.869973 0.4931 0 -0.738438 0.674322 0.0400449 -0.68543 0.727037 0 -0.538747 0.842468 0 -0.337774 0.941227 0.0480809 -0.230001 0.972002 0 -0.0826589 0.996578 0 0.141175 0.989985 0.0480812 0.286816 0.956778 0 0.392592 0.919713 0 0.587403 0.809294 0.0400445 0.727036 0.68543 0 0.776849 0.629687 0 0.897493 0.441029 0.0239935 0.972848 0.230199 0 0.981057 0.193719 0 -0.957887 0.287147 0 -0.957887 0.287147 0 -0.68598 0.72762 0 -0.68598 0.72762 0 -0.230266 0.973128 0 -0.230266 0.973128 0 0.287147 0.957887 0 0.287147 0.957887 0 0.727621 0.685979 0 0.727621 0.685979 0 0.973127 0.230268 0 0.973127 0.230268 0.705157 0.680507 0.199158 0.705157 0.707043 0.0533212 0.705157 0.707043 0.0533212 0.707033 0.576254 0.409922 0.705687 0.618503 0.34563 0.521917 0.750954 0.404563 0.707055 0.649988 0.278548 0.705152 0.680512 0.19916 0.511611 0.661328 0.548543 0.342801 0.716321 0.607759 0.632092 0.56369 0.531708 0.705158 -0.126935 0.697596 0.705158 0.020877 0.708743 0.705156 0.0208772 0.708744 0.705156 0.167777 0.688916 0.705155 0.167778 0.688917 0.705156 0.307345 0.638979 0.705158 0.307344 0.638977 0.705159 0.433478 0.561113 0.705156 0.43348 0.561115 0.707021 0.499213 0.500907 0.657477 0.543206 0.52216 0.705158 -0.399699 0.585656 0.70574 -0.280109 0.650745 0.501519 -0.328463 0.800369 0.707051 -0.210164 0.675211 0.705158 -0.126935 0.697596 0.633296 -0.53057 0.56341 0.707024 -0.468861 0.529421 0.705158 -0.399699 0.585656 0.587832 -0.560895 0.582966 0.329729 -0.682681 0.652093 0.706159 -0.527353 0.472482 0.705152 -0.603355 0.372455 0.705157 -0.603352 0.372452 0.706882 -0.647812 0.284001 0.300694 -0.897972 0.321295 0.706245 -0.674556 0.214924 0.705157 -0.702679 0.0948467 0.705157 -0.702679 0.0948467 -0.705157 -0.702679 0.0948467 -0.705157 -0.702679 0.0948467 -0.705157 -0.667604 0.238869 -0.705156 -0.667605 0.238869 -0.705156 -0.603352 0.372452 -0.705153 -0.603355 0.372454 -0.706046 -0.525437 0.474778 -0.373128 -0.670897 0.640837 -0.628644 -0.533513 0.565837 -0.705157 -0.2692 0.655961 -0.705158 -0.399699 0.585656 -0.705158 -0.399698 0.585656 -0.70706 -0.465833 0.532039 -0.665755 -0.505267 0.549068 -0.705159 0.433478 0.561113 -0.705158 0.307344 0.638977 -0.705156 0.307345 0.638979 -0.705155 0.167778 0.688917 -0.705156 0.167777 0.688916 -0.705156 0.0208771 0.708744 -0.705158 0.0208771 0.708743 -0.707093 -0.0583432 0.70471 -0.622905 -0.140048 0.76966 -0.705421 -0.131999 0.696388 -0.705158 -0.269199 0.65596 -0.665756 0.536708 0.518376 -0.707058 0.496344 0.503699 -0.705156 0.43348 0.561115 -0.628658 0.565882 0.533448 -0.373115 0.707458 0.60024 -0.706049 0.552471 0.443025 -0.705155 0.624231 0.336293 -0.705153 0.624233 0.336294 -0.706647 0.695558 0.129805 -0.67329 0.709613 0.207677 -0.697822 0.686983 0.202729 -0.707097 0.654361 0.268003 -0.707102 0.695502 0.127611 -0.705157 0.707043 0.0533212 -0.705157 0.707043 0.0533212 -0.69473 0.699943 0.165623 -0.32202 0.271852 0.906862 -0.694737 0.699936 0.165623 -0.700853 0.55413 0.44916 -0.406509 0.664788 0.626743 -0.706105 0.415949 0.573064 -0.703114 0.279161 0.653988 -0.704868 0.10014 0.702235 -0.704869 -0.0586312 0.70691 -0.32202 -0.218001 0.921292 -0.69474 -0.68897 0.206534 -0.694742 -0.688969 0.206533 -0.700857 -0.526729 0.480995 -0.406501 -0.626745 0.664791 -0.706106 -0.381492 0.596555 -0.703116 -0.240183 0.669283 -0.694741 -0.688969 0.206533 -0.694742 -0.688969 0.206533 -0.694742 -0.493398 0.523347 -0.694736 -0.493401 0.523352 -0.694738 -0.165622 0.699934 -0.69474 -0.165622 0.699933 -0.694737 0.206535 0.688973 -0.69474 0.206533 0.688971 -0.694737 0.523352 0.493401 -0.694736 0.523353 0.493401 -0.694736 0.699936 0.165623 -0.694742 0.69993 0.165623 -0.694742 -0.688969 0.206533 -0.694741 -0.688969 0.206533 -0.694741 -0.493398 0.523348 -0.694736 -0.493401 0.523352 -0.694739 -0.165621 0.699934 -0.694742 -0.165621 0.699931 -0.694739 0.206534 0.688971 -0.694739 0.206534 0.688971 -0.694736 0.523352 0.493401 -0.694737 0.523351 0.4934 -0.694737 0.699936 0.165623 -0.694728 0.699944 0.165624 -0.694742 -0.688969 0.206533 -0.694742 -0.688969 0.206533 -0.694742 -0.493398 0.523347 -0.694745 -0.493396 0.523345 -0.694742 -0.165621 0.699931 -0.69474 -0.165621 0.699933 -0.694744 0.206532 0.688967 -0.694742 0.206533 0.688968 -0.694746 0.523345 0.493394 -0.694748 0.523344 0.493393 -0.69475 0.699923 0.16562 -0.694742 0.699931 0.165621 -0.694741 -0.688969 0.206536 -0.694742 -0.688968 0.206535 -0.694742 -0.493398 0.523347 -0.694745 -0.493396 0.523345 -0.694742 -0.165622 0.699931 -0.694736 -0.165622 0.699936 -0.694741 0.206534 0.688969 -0.69474 0.206534 0.68897 -0.694737 0.523352 0.493401 -0.694745 0.523344 0.493396 -0.694749 0.699924 0.16562 -0.694742 0.699931 0.165621 -0.698069 0.702467 0.138707 -0.698073 0.702463 0.138707 -0.706859 0.634846 0.311964 -0.581212 0.650879 0.488416 -0.450645 0.0262862 0.892316 -0.70085 0.554133 0.449162 -0.706105 0.415942 0.57307 -0.486771 0.402019 0.775522 -0.703114 0.279164 0.653987 -0.704863 0.100142 0.702239 -0.704866 -0.0586314 0.706913 -0.703117 -0.240184 0.669281 -0.486782 -0.35567 0.797836 -0.706116 -0.381485 0.596548 -0.698075 -0.546424 0.462723 -0.698069 -0.693084 0.179816 -0.69807 -0.693083 0.179815 -0.706856 -0.615383 0.348796 -0.547282 -0.618033 0.564373 -0.694742 -0.688968 0.206533 -0.694742 -0.688969 0.206533 -0.694742 -0.493398 0.523347 -0.694743 -0.493397 0.523346 -0.694743 -0.165621 0.69993 -0.694741 -0.165621 0.699932 -0.694742 0.206533 0.688968 -0.694742 0.206533 0.688969 -0.694742 0.523348 0.493397 -0.694743 0.523347 0.493397 -0.694743 0.699929 0.165622 -0.694735 0.699938 0.165622 -0.694741 -0.688969 0.206534 -0.694741 -0.688969 0.206535 -0.694739 -0.493399 0.523349 -0.69474 -0.493399 0.523349 -0.69474 -0.165622 0.699933 -0.694738 -0.165622 0.699935 -0.694739 0.206535 0.688971 -0.694742 0.206533 0.688969 -0.694742 0.523347 0.493398 -0.694743 0.523346 0.493397 -0.694743 0.69993 0.16562 -0.694742 0.699931 0.16562 -0.694742 -0.688969 0.206533 -0.694741 -0.688969 0.206533 -0.694741 -0.493399 0.523348 -0.694742 -0.493398 0.523347 -0.694742 -0.165621 0.699931 -0.69474 -0.165621 0.699933 -0.694741 0.206533 0.68897 -0.69474 0.206534 0.68897 -0.694741 0.523349 0.493398 -0.694743 0.523347 0.493397 -0.694743 0.699929 0.165622 -0.694742 0.699931 0.165622 -0.694742 -0.688969 0.206533 -0.694741 -0.688969 0.206533 -0.694741 -0.493398 0.523348 -0.694741 -0.493398 0.523348 -0.694741 -0.165621 0.699932 -0.69474 -0.165622 0.699933 -0.694741 0.206534 0.68897 -0.694739 0.206534 0.688971 -0.694736 0.523352 0.493401 -0.694742 0.523347 0.493398 -0.694743 0.699929 0.165622 -0.694735 0.699937 0.165622 -0.698068 -0.693085 0.179817 -0.69807 -0.693083 0.179816 -0.69807 -0.546427 0.462727 -0.698069 -0.546428 0.462727 -0.69807 -0.291544 0.653988 -0.698072 -0.291543 0.653986 -0.69807 0.0210824 0.715719 -0.698067 0.0210832 0.715722 -0.698069 0.329535 0.635694 -0.698069 0.329535 0.635694 -0.698069 0.572717 0.429761 -0.698067 0.572718 0.429762 -0.698066 0.702469 0.138709 -0.698069 0.702467 0.138709 -0.698068 -0.693086 0.179816 -0.698057 -0.693095 0.179821 -0.698059 -0.546434 0.462734 -0.698062 -0.546433 0.462732 -0.698064 -0.291547 0.653993 -0.698066 -0.291546 0.653991 -0.698067 0.0210833 0.715722 -0.69807 0.0210824 0.715719 -0.698072 0.329532 0.635692 -0.698066 0.329536 0.635697 -0.698064 0.572722 0.429764 -0.698069 0.572717 0.429762 -0.698072 0.702464 0.138708 -0.69807 0.702466 0.138708 0.694742 0.699932 0.16562 0.694736 0.699936 0.165622 0.694738 0.52335 0.493401 0.694747 0.523344 0.493394 0.694744 0.206534 0.688966 0.694734 0.206535 0.688976 0.694736 -0.165623 0.699936 0.694742 -0.165621 0.699931 0.694738 -0.4934 0.52335 0.694737 -0.493401 0.523351 0.69474 -0.688971 0.206533 0.694742 -0.688968 0.206533 0.698068 -0.693084 0.179818 0.698071 -0.693082 0.179818 0.706856 -0.615381 0.3488 0.581219 -0.620999 0.525876 0.450646 0.0262843 0.892316 0.70085 -0.526735 0.480998 0.706106 -0.381488 0.596558 0.486771 -0.355673 0.797842 0.703117 -0.240182 0.669282 0.704867 -0.0586335 0.706913 0.704866 0.100141 0.702236 0.703117 0.279162 0.653984 0.486768 0.40202 0.775524 0.706107 0.415943 0.573065 0.698064 0.572721 0.429764 0.698069 0.702467 0.138707 0.69806 0.702476 0.138711 0.706847 0.634849 0.311984 0.547287 0.650181 0.527012 0.698069 -0.693084 0.179815 0.698071 -0.693083 0.179815 0.706856 -0.615381 0.348799 0.581219 -0.620999 0.525876 0.450653 0.0262842 0.892312 0.70086 -0.526726 0.480993 0.706113 -0.381488 0.596549 0.486771 -0.355673 0.797842 0.703117 -0.240182 0.669282 0.704866 -0.058632 0.706913 0.704868 0.10014 0.702235 0.703118 0.279161 0.653983 0.486771 0.40202 0.775522 0.706107 0.415942 0.573066 0.698064 0.572722 0.429764 0.698069 0.702467 0.138707 0.698059 0.702476 0.138711 0.706845 0.63485 0.311987 0.547288 0.650181 0.527011 0.694728 0.699944 0.165625 0.694736 0.699936 0.165622 0.694737 0.523351 0.4934 0.694736 0.523352 0.493401 0.694739 0.206534 0.688971 0.694739 0.206534 0.688971 0.694742 -0.165621 0.699931 0.694739 -0.165622 0.699933 0.694736 -0.493402 0.523351 0.694741 -0.493398 0.523349 0.694741 -0.688969 0.206533 0.694742 -0.688969 0.206533 0.694742 0.699931 0.165622 0.694736 0.699936 0.165624 0.694735 0.523352 0.493401 0.694737 0.523352 0.4934 0.69474 0.206534 0.688971 0.694737 0.206534 0.688973 0.69474 -0.165622 0.699933 0.694738 -0.165622 0.699934 0.694736 -0.493402 0.523352 0.694742 -0.493397 0.523348 0.694742 -0.688969 0.206533 0.694741 -0.688969 0.206533 0.698056 0.702479 0.138713 0.698072 0.702464 0.138706 0.698071 0.572716 0.42976 0.698075 0.572713 0.429757 0.698072 0.329533 0.635691 0.698066 0.329535 0.635697 0.698067 0.0210825 0.715722 0.698067 0.0210825 0.715722 0.698066 -0.291546 0.653991 0.698064 -0.291547 0.653993 0.698062 -0.546432 0.462732 0.698059 -0.546435 0.462734 0.698057 -0.693096 0.179819 0.698067 -0.693085 0.179818 0.69474 -0.68897 0.206533 0.32202 -0.218001 0.921292 0.694742 -0.688969 0.206533 0.700857 -0.526729 0.480995 0.406501 -0.626745 0.664791 0.706106 -0.381492 0.596555 0.703116 -0.240183 0.669283 0.704869 -0.0586312 0.70691 0.704868 0.100142 0.702234 0.322028 0.271851 0.90686 0.694743 0.69993 0.165621 0.694737 0.699936 0.165623 0.700853 0.554132 0.449159 0.406497 0.664792 0.626747 0.706111 0.415939 0.573063 0.70312 0.27916 0.653982 0.694741 -0.688969 0.206533 0.322026 -0.218 0.92129 0.694741 -0.68897 0.206533 0.700855 -0.52673 0.480997 0.406508 -0.626744 0.664788 0.70611 -0.38149 0.596552 0.703118 -0.240181 0.669282 0.704865 -0.0586336 0.706914 0.704865 0.100142 0.702237 0.322024 0.271851 0.906862 0.694742 0.699931 0.165621 0.694737 0.699936 0.165623 0.700853 0.55413 0.449161 0.406514 0.664787 0.626742 0.706111 0.415943 0.573061 0.70312 0.27916 0.653982 0.694735 0.699937 0.165624 0.694743 0.69993 0.16562 0.694742 0.523348 0.493397 0.694736 0.523351 0.493402 0.694739 0.206534 0.688971 0.694741 0.206534 0.68897 0.69474 -0.165622 0.699933 0.694741 -0.165621 0.699932 0.694741 -0.493398 0.523348 0.694741 -0.493398 0.523348 0.694741 -0.688969 0.206533 0.694742 -0.688969 0.206533 0.694742 0.699931 0.165622 0.694743 0.699929 0.165621 0.694743 0.523347 0.493396 0.694741 0.523349 0.493398 0.69474 0.206534 0.68897 0.694741 0.206534 0.68897 0.69474 -0.165622 0.699933 0.694742 -0.165621 0.699931 0.694742 -0.493398 0.523348 0.694741 -0.493399 0.523348 0.694741 -0.688969 0.206533 0.694742 -0.688969 0.206533 0.698068 -0.693085 0.179817 0.69807 -0.693083 0.179817 0.706856 -0.615382 0.348798 0.581216 -0.621 0.525877 0.450649 0.0262852 0.892314 0.700858 -0.526729 0.480994 0.706112 -0.381486 0.596551 0.486777 -0.355671 0.797839 0.703121 -0.240181 0.669279 0.70487 -0.058633 0.706909 0.704866 0.100141 0.702236 0.703117 0.279162 0.653984 0.486772 0.402019 0.775522 0.706111 0.415941 0.573062 0.698069 0.572717 0.429761 0.698069 0.702467 0.138709 0.698073 0.702463 0.138707 0.706859 0.634846 0.311964 0.547285 0.650181 0.527014 0.694734 0.699938 0.165624 0.694743 0.69993 0.16562 0.694743 0.523347 0.493396 0.694742 0.523348 0.493397 0.694742 0.206533 0.688969 0.694742 0.206533 0.688968 0.694741 -0.165621 0.699932 0.694743 -0.16562 0.69993 0.694743 -0.493397 0.523347 0.694742 -0.493398 0.523347 0.694742 -0.688969 0.206533 0.694742 -0.688968 0.206533 0.705753 0.707274 0.040939 0.705758 0.707269 0.0409389 0.705758 0.689415 0.163133 0.705751 0.689422 0.163135 0.705752 0.65062 0.280372 0.705748 0.650623 0.280374 0.705748 0.592052 0.389094 0.705748 0.592052 0.389094 0.705749 0.515491 0.485991 0.705756 0.515486 0.485986 0.705755 0.423265 0.568117 0.705757 0.423264 0.568116 0.705756 0.318182 0.632985 0.705754 0.318182 0.632986 0.705753 0.203432 0.678622 0.705753 0.203432 0.678623 0.705752 0.0824998 0.703639 0.705754 0.0824995 0.703637 0.705752 -0.0409391 0.707275 0.705751 -0.0409391 0.707276 0.705751 -0.163134 0.689422 0.70575 -0.163135 0.689423 0.705749 -0.280374 0.650622 0.705748 -0.280374 0.650623 0.705748 -0.389094 0.592052 0.705754 -0.389091 0.592047 0.705754 -0.485988 0.515488 0.705755 -0.485987 0.515487 0.705755 -0.568117 0.423264 0.70575 -0.568121 0.423268 0.70575 -0.63299 0.318184 0.705751 -0.632989 0.318184 0.705751 -0.678624 0.203432 0.705751 -0.678624 0.203432 0.705751 -0.70364 0.0825 0.705751 -0.70364 0.0825 0.705589 0.707218 0.0445794 0.705587 0.707219 0.0445796 0.705587 0.686986 0.173772 0.705587 0.686986 0.173772 0.705587 0.643359 0.297046 0.705588 0.643358 0.297046 0.705588 0.577821 0.410205 0.705588 0.577821 0.410205 0.705588 0.492608 0.509394 0.705587 0.492609 0.509396 0.705587 0.39062 0.591239 0.705586 0.39062 0.591239 0.705586 0.275329 0.652949 0.705589 0.275328 0.652946 0.70559 0.150662 0.692419 0.705588 0.150662 0.692421 0.705588 0.0208646 0.708315 0.705583 0.0208646 0.70832 0.705583 -0.109644 0.700093 0.70559 -0.109643 0.700087 0.70559 -0.236416 0.668019 0.705583 -0.236419 0.668026 0.705582 -0.355144 0.613211 0.705586 -0.355142 0.613208 0.705586 -0.461771 0.537509 0.70559 -0.461768 0.537506 0.705591 -0.552671 0.443503 0.70559 -0.552673 0.443504 0.70559 -0.624756 0.334399 0.705593 -0.624753 0.334398 0.705594 -0.67556 0.213906 0.705591 -0.675563 0.213907 0.70559 -0.703366 0.0861304 0.705589 -0.703367 0.0861305 0.705589 0.707218 0.0445795 0.705584 0.707222 0.0445796 0.705584 0.686989 0.173772 0.705594 0.68698 0.173771 0.705593 0.643353 0.297044 0.705588 0.643358 0.297046 0.705588 0.577821 0.410205 0.705589 0.57782 0.410204 0.705588 0.492608 0.509395 0.705583 0.492611 0.509398 0.705583 0.390622 0.591242 0.705582 0.390623 0.591243 0.705583 0.27533 0.652951 0.705589 0.275328 0.652946 0.70559 0.150661 0.692419 0.705585 0.150663 0.692423 0.705587 0.0208644 0.708316 0.705583 0.0208648 0.70832 0.705583 -0.109644 0.700093 0.705588 -0.109643 0.700088 0.705588 -0.236417 0.668021 0.705585 -0.236418 0.668024 0.705585 -0.355142 0.613208 0.705589 -0.35514 0.613205 0.70559 -0.461769 0.537506 0.705586 -0.461771 0.537509 0.705586 -0.552675 0.443507 0.70559 -0.552672 0.443504 0.70559 -0.624756 0.3344 0.705587 -0.624758 0.334401 0.705588 -0.675566 0.213908 0.705587 -0.675567 0.213908 0.705587 -0.703369 0.0861309 0.705589 -0.703368 0.0861306 0.705753 0.707274 0.0409384 0.705758 0.707269 0.0409383 0.705758 0.689415 0.163133 0.70575 0.689423 0.163135 0.70575 0.650621 0.280373 0.705748 0.650623 0.280374 0.705748 0.592052 0.389094 0.705745 0.592055 0.389096 0.705745 0.515494 0.485994 0.705751 0.515489 0.485989 0.70575 0.423268 0.568121 0.705757 0.423264 0.568116 0.705756 0.318181 0.632985 0.705748 0.318185 0.632991 0.70575 0.203433 0.678626 0.705753 0.203432 0.678623 0.705752 0.0824999 0.703639 0.705746 0.0825008 0.703645 0.705747 -0.0409393 0.707281 0.705751 -0.0409392 0.707276 0.705752 -0.163134 0.689422 0.705751 -0.163134 0.689422 0.705752 -0.280373 0.65062 0.705754 -0.280372 0.650617 0.705754 -0.389091 0.592047 0.705754 -0.389091 0.592047 0.705754 -0.485987 0.515488 0.705751 -0.485989 0.51549 0.705751 -0.56812 0.423267 0.705753 -0.568119 0.423266 0.705753 -0.632987 0.318183 0.705752 -0.632988 0.318183 0.705753 -0.678623 0.203432 0.705751 -0.678624 0.203433 0.705751 -0.70364 0.0824999 0.705751 -0.70364 0.0824999 0.705589 0.707218 0.0445794 0.705587 0.707219 0.0445796 0.705587 0.686986 0.173772 0.705587 0.686986 0.173772 0.705587 0.643359 0.297046 0.705586 0.643359 0.297047 0.705586 0.577823 0.410206 0.705588 0.577821 0.410205 0.705588 0.492608 0.509395 0.705587 0.492609 0.509396 0.705587 0.39062 0.591239 0.705592 0.390617 0.591235 0.705592 0.275327 0.652943 0.705589 0.275328 0.652946 0.70559 0.150661 0.692419 0.705595 0.15066 0.692414 0.705594 0.0208645 0.708309 0.705589 0.0208645 0.708314 0.70559 -0.109643 0.700087 0.705588 -0.109644 0.700089 0.705586 -0.236418 0.668023 0.705583 -0.236419 0.668026 0.705582 -0.355144 0.613211 0.705592 -0.355138 0.613202 0.705594 -0.461766 0.537503 0.70559 -0.461768 0.537506 0.705591 -0.552671 0.443503 0.705588 -0.552674 0.443506 0.705588 -0.624757 0.3344 0.705593 -0.624753 0.334398 0.705594 -0.67556 0.213906 0.70559 -0.675564 0.213907 0.70559 -0.703366 0.0861311 0.705589 -0.703367 0.0861313 0.705587 0.707219 0.0445796 0.705588 0.707219 0.0445796 0.705588 0.686986 0.173772 0.705587 0.686986 0.173772 0.705587 0.643358 0.297046 0.705591 0.643355 0.297045 0.705591 0.577819 0.410203 0.705588 0.577821 0.410205 0.705588 0.492608 0.509395 0.705587 0.492609 0.509396 0.705587 0.39062 0.591239 0.705592 0.390617 0.591235 0.705592 0.275327 0.652943 0.705589 0.275328 0.652946 0.70559 0.150662 0.692419 0.705588 0.150662 0.692421 0.705588 0.0208645 0.708315 0.70559 0.0208645 0.708313 0.705588 -0.109643 0.700089 0.70559 -0.109643 0.700087 0.70559 -0.236417 0.668019 0.705593 -0.236415 0.668016 0.705594 -0.355137 0.6132 0.705586 -0.355142 0.613207 0.705586 -0.461771 0.53751 0.705582 -0.461774 0.537512 0.705581 -0.55268 0.44351 0.705588 -0.552674 0.443506 0.705588 -0.624757 0.334401 0.705582 -0.624763 0.334403 0.705581 -0.675572 0.213909 0.70559 -0.675564 0.213907 0.70559 -0.703366 0.0861307 0.705589 -0.703367 0.0861308 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.939621 -0.0470035 -0.338973 0.939565 0.0228714 -0.341605 0.938423 0.0397588 -0.343194 0.939692 0.0408142 -0.339579 0.939394 0.0419416 -0.340263 0.939413 0.0418802 -0.340219 0.939897 0.0414916 -0.338927 0.939961 0.0416628 -0.338729 0.939948 0.0416369 -0.338768 0.939758 0.0416048 -0.3393 0.939563 0.0416661 -0.339832 0.939622 -0.061567 -0.33663 0.939837 -0.061465 -0.33605 0.940956 -0.0586522 -0.333411 0.939692 -0.0607031 -0.336593 0.939965 -0.0615269 -0.33568 0.939976 -0.0615544 -0.335644 0.939692 -0.0602289 -0.336676 0.939472 -0.0616702 -0.33703 0.939449 -0.0617318 -0.337083 0.939565 -0.042939 -0.339666 0.94337 -0.0433306 -0.328901 0.936007 -0.0188294 -0.351477 0.939622 -0.0224198 -0.341479 0.93966 -0.00183715 -0.342104 0.937285 0.00232276 -0.348556 0.94337 0.023896 -0.330881 0.939621 0.0269696 -0.341152 0.939692 0.0402799 -0.33964 0.149349 -0.13581 -0.979413 0.488787 -0.119824 -0.864135 0.346109 0.0739375 -0.935276 0.655058 0.0595459 -0.753229 0.850962 0.0413923 -0.523594 0.850962 0.0413925 -0.523594 0.850962 0.00350009 -0.525216 0.850962 0.0035 -0.525215 0.850962 -0.0344093 -0.524099 0.850963 -0.0344095 -0.524097 0.850963 -0.0721398 -0.520247 0.850963 -0.0721398 -0.520248 0.65507 -0.103778 -0.748407 0.573439 -0.105091 -0.81248 0.573328 -0.0536765 -0.817566 0.57333 -0.0536768 -0.817564 0.57333 0.00545994 -0.819306 0.573332 0.00545965 -0.819305 0.573443 0.0570863 -0.817254 0.488794 0.0687523 -0.869686 0.346068 -0.128863 -0.929318 0.202126 -0.128775 -0.970856 0.202088 -0.0641617 -0.977263 0.202089 -0.0641619 -0.977263 0.202089 0.00652613 -0.979346 0.202081 0.00652727 -0.979347 0.20212 0.0714039 -0.976754 0.149334 0.0779242 -0.985712 -0.707101 -0.103598 0.699483 -0.671186 -0.064694 0.73846 -0.706467 -0.0635255 0.704889 -0.706467 0.0208389 0.707439 -0.70647 0.020839 0.707436 -0.706522 0.103151 0.700133 -0.672813 0.10966 0.731641 -0.7071 0.144599 0.692171 -0.706472 0.0635257 -0.704885 -0.706467 0.0635259 -0.704889 -0.706467 -0.0208388 -0.707439 -0.70647 -0.0208385 -0.707436 -0.706471 -0.104907 -0.699924 -0.706478 -0.104905 -0.699917 -0.69474 -0.0383624 0.718237 -0.487525 -0.778344 0.395601 -0.694741 -0.0383628 0.718236 -0.702913 -0.321177 0.634633 -0.494624 -0.474077 0.728422 -0.705019 -0.473094 0.528328 -0.703702 -0.588931 0.397447 -0.704388 -0.671085 0.231262 -0.704389 -0.70725 0.0602763 -0.487505 -0.871877 -0.0465664 -0.694748 -0.325892 -0.641186 -0.694746 -0.325893 -0.641187 -0.70292 -0.550631 -0.450231 -0.49462 -0.728424 -0.474078 -0.705005 -0.646511 -0.291532 -0.70369 -0.699434 -0.12495 -0.698526 0.0494648 0.713873 -0.698523 0.0494661 0.713876 -0.698523 0.347224 0.625701 -0.698524 0.347224 0.6257 -0.698524 0.579593 0.419686 -0.698527 0.57959 0.419685 -0.698529 0.702801 0.134636 -0.698525 0.702806 0.134635 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.0533365 0.998577 0 -0.347928 -0.937521 0.0478509 -0.452579 -0.89044 0.0190429 -0.530496 -0.847473 -0.0231314 -0.72428 -0.689117 0.00914016 -0.984374 -0.175853 -0.0343187 -0.943589 -0.329335 -0.00482422 -0.911593 -0.411065 0.00546018 -0.774142 -0.632988 0.00782588 -0.945408 0.325796 1.51227e-05 -0.956746 0.290923 -2.63592e-05 -0.996388 0.0849183 1.0411e-05 -0.996378 0.0850367 6.00821e-06 -0.997432 -0.0716171 0.0166607 -0.616085 0.787504 -0.0109405 -0.748052 0.66355 0.0114755 -0.828847 0.559357 -2.32356e-05 -0.866489 0.499196 -1.65663e-05 -0.913596 0.406624 0.0264242 -0.00764855 0.999622 -0.0156564 -0.411667 0.9112 -1.72582e-05 -0.45155 0.892246 7.52024e-06 -0.667091 0.744976 0 0.0452385 0.998976 0.0104368 0.0691212 0.997554 -0.00978239 0.431738 0.901946 0.0153981 0.485172 0.874283 -0.00079663 0.642605 0.766197 0.00343834 0.777914 0.628362 0.0232002 0.809737 0.586334 0.00015271 0.891151 0.453707 -0.000283363 0.961062 0.276332 0.0289655 0.981728 0.18807 0 0.998178 0.0603399 0 0.0897584 -0.995964 0 0.0897584 -0.995964 0 -0.0294439 -0.999566 0 -0.0294439 -0.999566 0 -0.148227 -0.988953 0 -0.148227 -0.988953 0 0.148226 0.988953 0 0.148226 0.988953 0 0.029444 0.999566 0 0.029444 0.999566 0 -0.0897576 0.995964 0 -0.0897576 0.995964 -0.879241 -0.134577 -0.456973 -0.887084 -0.197577 -0.417188 -0.95499 -0.219651 -0.199368 -0.960101 -0.214612 -0.179298 -0.978435 -0.15367 -0.138021 -0.978976 -0.152149 -0.135856 -0.991397 -0.0655077 -0.113319 -0.990797 -0.0700129 -0.115841 -0.965171 -0.0668582 0.252933 -0.793206 -0.561557 0.235538 -0.859466 -0.338847 0.382755 -0.839107 -0.365858 0.402552 -0.884192 -0.0560235 0.463753 -0.876485 -0.064353 0.477109 -0.859292 -0.493392 -0.13484 -0.938545 -0.248791 -0.239241 -0.933192 -0.246147 -0.261849 -0.821648 -0.569994 0.000946435 -0.847486 -0.526817 0.0650486 -0.891282 -0.450751 0.0493868 -0.947044 -0.273143 0.168818 -0.938317 -0.293728 0.18244 -0.970911 -0.0827485 0.224689 -0.989048 -0.0722719 0.128689 -0.807336 -0.445014 -0.38752 -0.693241 -0.68534 -0.222992 -0.770719 -0.637139 -0.00677621 -0.902135 -0.24595 -0.354488 -0.887849 -0.191805 -0.418252 -0.749525 -0.355387 -0.558491 -0.710142 -0.366398 -0.601207 -0.276 -0.874577 -0.398672 -0.145874 -0.520235 -0.841473 -0.19781 -0.374075 -0.906057 -0.147939 -0.342118 -0.927938 -0.111689 -0.413994 0.903402 -0.0948733 -0.0102102 0.995437 -0.105773 -0.00639126 0.99437 -0.0780672 -0.867484 0.491301 -0.143548 -0.747879 0.648129 -0.177898 -0.735447 0.653812 -0.097288 -0.620045 0.778511 -0.110856 -0.41427 0.903378 -0.0290549 -0.723942 -0.689249 -0.134931 -0.932682 -0.33451 0.129821 -0.918737 -0.372921 -0.156068 -0.984043 -0.0854471 -0.216091 -0.975241 -0.0470104 -0.0505889 -0.99551 0.0800017 -0.143374 -0.933047 0.329951 -0.273796 -0.927657 0.253945 -0.142481 -0.909784 0.389863 -0.354223 -0.832343 -0.4263 -0.457107 -0.881614 -0.117512 -0.363195 -0.920865 -0.141765 -0.490855 -0.84747 0.202128 -0.397297 -0.897049 0.193542 -0.522597 -0.689478 0.501511 -0.442831 -0.736756 0.51097 -0.546599 -0.407173 0.731737 -0.493386 -0.438295 0.751311 -0.553358 -0.0354369 0.832189 -0.546229 -0.038499 0.836751 -0.176398 -0.887005 -0.426739 -0.302654 -0.9514 -0.0569087 -0.186322 -0.979068 -0.0819123 -0.32567 -0.898893 0.29314 -0.208474 -0.937336 0.279179 -0.34326 -0.714386 0.609774 -0.241868 -0.754192 0.610487 -0.351516 -0.406985 0.843089 -0.282653 -0.435936 0.85444 -0.345035 -0.0127926 0.938503 -0.333667 -0.0172688 0.942533 -0.879551 -0.133357 -0.456734 -0.763483 -0.204787 -0.6125 -0.693963 -0.274353 -0.665692 -0.651408 -0.26244 -0.711894 -0.484426 -0.313164 -0.81686 -0.918281 -0.254916 -0.30295 -0.901026 -0.269622 -0.339788 -0.758729 -0.536351 -0.369673 -0.805285 -0.481824 -0.345486 -0.700527 -0.617929 -0.356967 -0.633826 -0.468722 -0.615276 -0.461111 -0.563173 -0.68572 -0.425655 -0.357336 -0.831342 -0.341505 -0.354615 -0.870415 -0.172211 -0.676057 -0.716443 -0.179188 -0.676336 -0.714466 -0.424098 -0.606876 -0.672192 -0.486873 -0.734834 -0.472201 -0.502666 -0.729 -0.464635 -0.601394 -0.779471 -0.175356 -0.531857 -0.82316 -0.198835 -0.642828 -0.759409 0.100352 -0.575085 -0.812656 0.094164 -0.685229 -0.630045 0.365383 -0.629211 -0.67901 0.378205 -0.721674 -0.38464 0.575533 -0.685627 -0.41527 0.597885 -0.739941 -0.0449753 0.671167 -0.725685 -0.0543033 0.685881 -0.146143 0.351412 -0.924744 -0.826271 0.558156 -0.0757463 -0.651406 0.220036 -0.726122 -0.992269 0.0754621 -0.0985316 -0.992328 0.0362275 -0.118209 -0.976263 0.161395 -0.14444 -0.978909 0.143381 -0.145533 -0.963219 0.194959 -0.184936 -0.851018 0.0632127 -0.521318 -0.880972 0.160821 -0.445 -0.902082 0.208623 -0.377789 -0.895846 0.210829 -0.391166 -0.919311 0.231151 -0.31849 -0.740533 0.594909 -0.312561 -0.783611 0.561046 -0.266796 -0.707954 0.509454 -0.489139 -0.918516 0.232048 -0.320128 -0.938741 0.233192 -0.253744 -0.785899 0.608947 -0.107453 -0.847486 0.529734 0.0339052 -0.79326 0.574366 0.202095 -0.856963 0.376619 0.351814 -0.844209 0.371822 0.386082 -0.884163 0.0918214 0.458065 -0.877674 0.0840099 0.471839 -0.945949 0.21924 -0.238988 -0.960044 0.204862 -0.190647 -0.891348 0.452748 0.0227593 -0.944831 0.29416 0.144095 -0.94185 0.2907 0.168557 -0.970927 0.0958943 0.219331 -0.965173 0.0816692 0.248537 -0.0803399 0.891671 0.445498 -0.171672 0.947392 0.270142 -0.146978 0.777484 0.611487 -0.158081 0.773848 0.613327 -0.09291 0.64506 0.758463 -0.146468 0.466795 0.872152 -0.0593294 0.433488 0.899204 -0.106169 0.0470256 0.993236 -0.150214 0.0658595 0.986457 -0.334005 0.0680382 0.940112 -0.13828 0.955473 0.260672 -0.0626523 0.996569 0.0540864 -0.205194 0.973303 -0.10284 -0.119305 0.982872 -0.140462 -0.0122574 0.896509 -0.442856 -0.365913 0.862587 -0.349358 -0.180218 0.860825 -0.475923 -0.0941775 0.836977 -0.539073 -0.0329226 0.692278 -0.720879 -0.190433 0.63359 -0.749866 -0.0911595 0.328113 -0.94023 -0.341515 0.302701 -0.889797 -0.693993 0.23467 -0.680664 -0.714749 0.375777 -0.589852 -0.412184 0.541735 -0.732549 -0.4869 0.705809 -0.51455 -0.35417 0.80587 -0.474486 -0.44764 0.870227 -0.205728 -0.378519 0.911434 -0.16128 -0.480141 0.869648 0.114788 -0.413116 0.89377 0.174672 -0.514075 0.740671 0.43259 -0.455183 0.742556 0.491345 -0.54269 0.472338 0.694539 -0.49964 0.459511 0.734309 -0.553285 0.0877462 0.828358 -0.546675 0.0841319 0.833108 -0.344677 0.073468 0.935842 -0.288261 0.461659 0.838914 -0.346234 0.48094 0.805493 -0.253711 0.764708 0.592328 -0.332835 0.774527 0.537893 -0.224028 0.93904 0.260796 -0.313027 0.928361 0.200398 -0.20153 0.974108 -0.102463 -0.291651 0.944398 -0.151829 -0.187838 0.872632 -0.45081 -0.26929 0.835877 -0.478322 -0.179199 0.633024 -0.753106 -0.463845 0.550706 -0.693953 -0.425695 0.307727 -0.850933 -0.48445 0.26448 -0.833881 -0.875378 0.09997 -0.472989 -0.889598 0.164269 -0.426181 -0.68973 0.371018 -0.621786 -0.745702 0.49755 -0.44314 -0.502673 0.700433 -0.506669 -0.593284 0.763936 -0.253803 -0.546279 0.809284 -0.21596 -0.633759 0.773222 0.021853 -0.589993 0.803796 0.0762921 -0.678236 0.669735 0.302409 -0.640941 0.678713 0.358529 -0.718701 0.437511 0.540419 -0.691732 0.429682 0.580414 -0.73991 0.0940374 0.666101 -0.727058 0.0849097 0.681305 -0.572888 -0.024133 -0.819279 -0.850726 0.0482632 -0.523388 -0.879517 -0.0715153 -0.470463 -0.654678 -0.112046 -0.747557 -0.764994 -0.0954636 -0.636923 -0.845143 -0.0758494 -0.529131 -0.851114 -0.047813 -0.522799 -0.850696 -0.0154773 -0.52543 -0.850697 -0.0154772 -0.525429 -0.851114 0.0169472 -0.524707 -0.345811 -0.139082 -0.927939 -0.488399 -0.129346 -0.862981 -0.149211 -0.146568 -0.977882 -0.201922 -0.141718 -0.969094 -0.201883 -0.0288376 -0.978985 -0.844347 0.0480917 -0.533634 -0.654674 0.0678486 -0.75286 -0.573009 0.0690551 -0.816635 -0.488419 0.0783238 -0.869087 -0.345821 0.0842201 -0.934513 -0.573004 -0.117004 -0.811158 -0.572883 -0.0241336 -0.819282 -0.201879 -0.028838 -0.978986 -0.201918 0.0844297 -0.975756 -0.149207 0.0887536 -0.984815 -0.340888 -0.0843818 0.936309 -0.994035 -0.00321123 -0.109014 -0.994036 0.0100133 -0.108589 -0.994251 0.00961112 -0.106646 -0.991754 -0.01926 -0.126702 -0.996676 -0.00741751 -0.0811267 -0.658678 0.0221543 0.752099 -0.93179 0.010688 0.362839 -0.994046 -0.0142421 -0.10803 -0.993745 0.0165527 0.110438 -0.971837 0.0349305 0.233053 -0.994056 0.00351565 -0.108813 -0.994035 -0.0032112 -0.109014 -0.93179 0.0106881 0.36284 -0.931639 0.0603076 0.358347 -0.558462 -0.0883607 0.824811 -0.739298 -0.0604407 0.67066 -0.93179 -0.0325817 0.361532 -0.888071 -0.0527967 0.456665 -0.971843 -0.0211496 0.234679 -0.237288 0.0286031 0.971018 -0.237288 -0.087194 0.967518 -0.108127 -0.103752 0.988708 -0.887837 0.0682076 0.455075 -0.7393 0.0998121 0.665938 -0.658466 0.118137 0.743281 -0.558103 0.122994 0.820606 -0.340885 0.139349 0.92972 -0.658678 -0.0675362 0.749388 -0.658678 0.0221543 0.752099 -0.237289 0.0286029 0.971018 -0.237193 0.150573 0.959723 -0.108044 0.147359 0.983164 -0.939507 -0.0514766 -0.338639 -0.939608 -0.072484 -0.334488 -0.939483 -0.0726898 -0.334796 -0.939571 -0.0723812 -0.334614 -0.93969 -0.0713108 -0.334511 -0.939848 -0.0723738 -0.333838 -0.939868 -0.0724077 -0.333773 -0.939721 -0.0724203 -0.334187 -0.939515 0.0314503 -0.341061 -0.940467 0.0508403 -0.336062 -0.939697 0.0521522 -0.338009 -0.939903 0.0526786 -0.337355 -0.93969 0.0516963 -0.338098 -0.939536 0.0526971 -0.338372 -0.939492 0.0528429 -0.33847 -0.939515 0.0527833 -0.338417 -0.939749 0.0525736 -0.337799 -0.939508 0.0314521 -0.34108 -0.939511 0.0314522 -0.341071 -0.939693 0.0110445 -0.341839 -0.939693 0.0110409 -0.34184 -0.939497 -0.0100863 -0.342407 -0.939498 -0.010086 -0.342406 -0.939694 -0.0311412 -0.340597 -0.939693 -0.0311495 -0.340597 -0.939511 -0.0514761 -0.338629 -0.939514 -0.0514737 -0.33862 -0.939697 -0.0715374 -0.334444 0.0420365 0.695096 -0.717687 0.00148413 0.844537 -0.535494 -0.000287576 0.882023 -0.471207 0.00686676 0.966002 -0.258444 0.056789 0.939192 -0.338663 0 0.991485 -0.130225 -0.010557 0.748226 -0.66336 0.00927873 0.372302 -0.928065 0 0.358123 -0.933674 -0.697442 0.692293 -0.185216 -0.697443 0.692292 -0.185215 -0.69744 0.536241 -0.475419 -0.697435 0.536243 -0.475423 -0.697431 0.266823 -0.665128 -0.69744 0.266822 -0.665119 0.000649807 -0.894439 -0.447189 0 -1 -0.000142633 -0.0049005 -0.978378 -0.206769 -0.0463864 -0.951411 -0.304409 -0.0061162 -0.993057 -0.117478 0 -0.400096 -0.916473 -0.0139886 -0.371649 -0.928268 -0.000713391 -0.56977 -0.821804 0.00557349 -0.775212 -0.631677 -0.0339583 -0.719044 -0.694135 -0.00401193 -0.852756 -0.522295 0.696947 -0.701625 -0.148281 0.696935 -0.701636 -0.148287 0.696935 -0.555939 -0.453004 0.696948 -0.555932 -0.452993 0.696944 -0.286919 -0.657226 0.696946 -0.286919 -0.657225 0.698866 -0.559444 0.445655 0.698863 -0.559447 0.445656 0.698865 -0.694093 0.172693 0.698865 -0.694093 0.172693 0.698862 -0.0289667 0.71467 0.698864 -0.028966 0.714668 0.698864 -0.323494 0.637919 0.819613 -0.218463 0.529631 0.70602 -0.40316 0.582235 0.458492 0.826353 0.326996 0.694743 0.105206 0.711522 0.694744 0.105206 0.711522 0.705702 0.33813 0.622617 0.754938 0.349425 0.554952 0.624884 0.537464 0.566262 0.705012 0.52033 0.481887 0.703695 0.623448 0.340771 0.704392 0.689731 0.167637 0.704393 0.709785 -0.00597771 0.458498 0.879137 -0.129989 0.694752 0.264644 -0.668792 0.694733 0.264655 -0.668807 0.702909 0.506233 -0.499647 0.466767 0.692977 -0.549464 0.70502 0.61648 -0.350569 0.703701 0.684714 -0.189661 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706175 0.0718644 0.70438 0.706171 0.071865 0.704384 0.706172 -0.0302784 0.707393 0.706181 -0.0302784 0.707383 0 -0.0668019 0.997766 0.0420198 -0.0427259 0.998203 0 0.00537307 0.999986 0 0.101498 0.994836 0.0629317 0.125169 0.990138 0 0.0534965 0.998568 0.706181 -0.0718639 -0.704375 0.706178 -0.0718641 -0.704378 0.706179 0.0302785 -0.707386 0.706187 0.0302777 -0.707377 0 0.14627 0.989245 0 0.25797 -0.966153 -0.0323184 0.367753 -0.929362 -0.0129574 0.448206 -0.893836 0.0156224 0.6571 -0.753641 -0.00369192 0.711716 -0.702457 0.00325949 0.869272 -0.494323 0.0251174 0.912412 -0.408503 -3.35077e-05 0.971711 0.236172 4.06102e-05 0.999438 -0.0335258 0.00666452 0.999942 -0.00842135 -0.00509208 0.9637 -0.266938 -0.00405097 0.733684 0.679478 0.00867165 0.80097 0.598642 -0.00792449 0.877449 0.479605 0.003069 0.920251 0.391318 -0.00558233 0.977543 0.210663 -0.0225146 0.0907614 0.995618 0.0120844 0.47317 0.880888 -0.00323352 0.532823 0.846221 3.83297e-06 0.64489 0.764276 -1.71822e-07 0.680922 0.732356 0 -0.0114745 0.999934 -0.00839064 -0.0404968 0.999144 0.00844867 -0.401051 0.916017 -0.00838047 -0.452262 0.891846 0.000413351 -0.616771 0.787142 -0.0024584 -0.756616 0.653854 -0.0133773 -0.782093 0.623018 0.000411626 -0.876515 0.481374 -0.00121354 -0.951872 0.306494 -0.0176839 -0.970263 0.241406 0 -0.994795 0.101896 0.994042 -0.0136699 -0.108135 0.97185 0.0295483 0.23374 0.658909 0.0221482 0.751897 0.108086 -0.0664105 0.991921 0.558294 -0.055422 0.82779 0.341051 -0.0627971 0.937945 0.237326 -0.0732125 0.968667 0.237622 0.00521918 0.971344 0.153991 0.0290924 0.987644 0.23762 0.0519642 0.969967 0.237425 0.121831 0.963736 0.887897 -0.0307319 0.459014 0.73945 -0.0449721 0.671707 0.108176 0.142806 0.983821 0.341049 0.117898 0.932623 0.658909 0.0943417 0.746283 0.558603 0.121384 0.820505 0.739455 0.0844313 0.66789 0.971845 -0.01574 0.235094 0.931702 -0.0324161 0.361773 0.931867 0.0106823 0.362643 0.658689 -0.0585833 0.750131 0.658911 0.0221484 0.751895 0.931867 0.0106823 0.362643 0.931867 0.0455013 0.359936 0.888088 0.0720516 0.453992 0.994042 0.00728124 -0.108752 0.994042 0.00728109 -0.108751 0.994053 -0.000584807 -0.1089 0.994978 -0.00294721 -0.100052 0.994053 -0.00582575 -0.108746 0.994042 -0.0136699 -0.108135 0 -0.13735 -0.990523 -0.126161 -0.0649902 -0.989879 0 -0.101498 -0.994836 0 0.00666477 -0.999978 -0.0635014 0.0426779 -0.997069 0 0.0788079 -0.99689 0.738162 0.460836 -0.492694 0.933081 0.221856 -0.283089 0.885793 0.149156 -0.439459 0.902775 0.191595 -0.385083 0.900886 0.216598 -0.376152 0.893714 0.175049 -0.413077 0.982611 0.129236 -0.133315 0.96895 0.172331 -0.177307 0.959187 0.199971 -0.199928 0.978164 0.137847 -0.155545 0.993506 0.0397308 -0.106622 0.993503 0.0456233 -0.104264 0.955083 0.200837 -0.217901 0.937215 0.228312 -0.263632 0.812778 0.564731 -0.143075 0.759737 0.582138 -0.28968 0.53265 0.801522 -0.271747 0.60031 0.759828 -0.249577 0.36413 0.904048 -0.223846 0.456004 0.866791 -0.201827 0.187414 0.967543 -0.169521 0.145508 0.437553 -0.887341 0.172302 0.607855 -0.775129 0.884955 0.154943 -0.439144 0.712671 0.333969 -0.6169 0.697722 0.366272 -0.615653 0.461106 0.498628 -0.733997 0.42335 0.540598 -0.727 0.1797 0.608099 -0.773255 0.275277 0.832672 -0.480499 0.918217 0.226754 -0.324747 0.916083 0.228501 -0.329513 0.771366 0.542817 -0.332181 0.722824 0.504774 -0.471942 0.503314 0.683849 -0.528229 0.487235 0.6897 -0.535645 0.353635 0.788899 -0.502574 0.177323 0.844655 -0.505088 0.301519 0.94185 -0.148341 0.175528 0.799184 0.574886 0.0983813 0.68442 0.72242 0.100534 0.648588 0.754471 0.275273 0.946467 0.168596 0.876441 0.108495 0.469127 0.884048 0.100001 0.456573 0.725681 0.117682 0.677892 0.739821 0.108095 0.664063 0.546205 0.116211 0.829551 0.553284 0.113088 0.82528 0.333631 0.105338 0.9368 0.344984 0.100987 0.93316 0.10576 0.0987402 0.989477 0.121173 0.0937861 0.988191 0.0684068 0.921114 0.383236 0.148724 0.794735 0.588453 0.34232 0.770139 0.53824 0.242325 0.806431 0.539396 0.521632 0.735145 0.432968 0.443201 0.780023 0.441743 0.684257 0.663222 0.303197 0.62949 0.710396 0.314769 0.792147 0.582785 0.181288 0.839078 0.401405 0.367182 0.858964 0.374819 0.348844 0.685632 0.468594 0.557072 0.721184 0.438409 0.536368 0.493423 0.505615 0.707734 0.546143 0.475448 0.689694 0.282717 0.512663 0.810708 0.351081 0.48571 0.800517 0.0859262 0.494842 0.864724 0.151881 0.476483 0.865966 0.147932 0.252596 -0.956196 0.205583 0.287693 -0.935397 0.341464 0.271718 -0.899762 0.425001 0.275627 -0.862209 0.484359 0.236216 -0.842377 0.687666 0.183368 -0.70249 0.647366 0.239762 -0.723486 0.870204 0.0317099 -0.49167 0.850012 0.110734 -0.514994 0.0290107 0.656204 -0.754026 0.135837 0.899384 -0.41552 -0.181676 0.878182 -0.442481 0.289897 0.954681 -0.0674043 0.0131425 0.993552 -0.112618 0.143547 0.959534 0.242257 0.324416 0.923447 0.204939 0.209394 0.958471 0.193617 0.489617 0.863716 0.11946 0.398063 0.910509 0.111892 0.64164 0.766543 0.0266612 0.575709 0.817395 0.0205873 0.805187 0.586498 -0.0877149 0.849347 0.527334 0.0230019 0.891416 0.453109 0.00835523 0.946585 0.289434 0.142145 0.938296 0.309291 0.154724 0.97139 0.088523 0.220376 0.963018 0.107295 0.247154 0.484356 -0.285342 -0.82703 0.146448 -0.363952 -0.919833 0.546586 -0.0639828 0.834955 0.824719 -0.561697 -0.0658395 0.942262 -0.261441 -0.209264 0.971802 -0.168959 -0.164482 0.978816 -0.151991 -0.137175 0.98931 -0.0758021 -0.124578 0.993672 -0.046194 -0.10238 0.851108 -0.0864602 -0.517823 0.873457 -0.16874 -0.456727 0.889404 -0.189729 -0.415888 0.901405 -0.217334 -0.37448 0.8953 -0.221251 -0.386634 0.918228 -0.239652 -0.315317 0.651399 -0.237406 -0.720637 0.69278 -0.246594 -0.677678 0.714416 -0.388874 -0.58171 0.741744 -0.602827 -0.293964 0.782189 -0.567679 -0.25675 0.708893 -0.522908 -0.473327 0.911963 -0.248234 -0.326654 0.938586 -0.23503 -0.252621 0.786959 -0.610538 -0.0891003 0.849347 -0.525065 0.0540002 0.79219 -0.571029 0.215319 0.856725 -0.367874 0.361513 0.843572 -0.363937 0.394886 0.884012 -0.080599 0.460463 0.877481 -0.0733822 0.473964 0.921875 -0.272674 -0.275311 0.959989 -0.190473 -0.205284 0.891439 -0.451786 0.0350244 0.944652 -0.290714 0.152047 0.941308 -0.288261 0.175624 0.970892 -0.0889213 0.222401 0.965072 -0.0762124 0.250654 0.139294 -0.947733 0.287055 0.170813 -0.940573 0.293506 0.0818637 -0.878142 0.471344 0.148648 -0.75867 0.63429 0.14877 -0.758635 0.634302 0.0946666 -0.620861 0.778184 0.146655 -0.444881 0.883501 0.0322453 -0.402364 0.914912 0.106341 -0.0138651 0.994233 0.174509 -0.0422339 0.983749 0.333935 -0.0457532 0.941485 0.183911 -0.870964 -0.45563 0.234215 -0.87159 -0.430667 0.0680753 -0.993306 0.0933179 0.154388 -0.98783 -0.0189026 0.226174 -0.970577 -0.0826158 0.114484 -0.984776 -0.130807 0.0516869 -0.947869 -0.314441 0.0913972 -0.844588 -0.527557 0.0352435 -0.715557 -0.697665 0.511447 -0.467862 -0.720783 0.553199 -0.067388 0.830319 0.499063 -0.442794 0.744896 0.542562 -0.454922 0.706167 0.454259 -0.731528 0.508444 0.513916 -0.72952 0.45132 0.412102 -0.889919 0.195492 0.480027 -0.866456 0.137216 0.377664 -0.915336 -0.139747 0.447579 -0.875313 -0.183029 0.353595 -0.817168 -0.4552 0.487271 -0.720066 -0.494037 0.412924 -0.561459 -0.717117 0.463493 -0.566003 -0.681773 0.425018 -0.32585 -0.844501 0.344667 -0.0508588 0.937346 0.287819 -0.442221 0.849471 0.346282 -0.460715 0.817209 0.253023 -0.750954 0.609957 0.332873 -0.760705 0.557247 0.22332 -0.932827 0.282776 0.313054 -0.922944 0.223991 0.200948 -0.976387 -0.0793047 0.291663 -0.947973 -0.127593 0.187466 -0.883237 -0.429824 0.269275 -0.847849 -0.456774 0.179546 -0.652148 -0.736523 0.178806 -0.652644 -0.736264 0.111643 -0.350491 -0.929888 0.341425 -0.324147 -0.882246 0.870901 -0.107741 -0.479503 0.892969 -0.16816 -0.417527 0.690172 -0.387968 -0.610855 0.74478 -0.507274 -0.433562 0.503288 -0.713809 -0.487009 0.59314 -0.770508 -0.233457 0.545211 -0.81482 -0.197014 0.633564 -0.772539 0.0421929 0.588806 -0.802686 0.0948869 0.677988 -0.661943 0.319629 0.639891 -0.671229 0.374155 0.71848 -0.42399 0.551379 0.691088 -0.416893 0.590422 0.739776 -0.0775004 0.668375 0.726917 -0.0689269 0.683257 0 -0.366108 0.930572 0 -0.366108 0.930572 0 -0.474284 0.880372 0 -0.474284 0.880372 0 -0.575714 0.817651 0 -0.575714 0.817651 0 -0.54548 0.838124 0 0.167446 -0.985881 0.0478518 0.0532725 -0.997433 0.0190463 -0.0356811 -0.999182 -0.0231288 -0.28269 -0.958933 0.00914109 -0.764568 -0.644478 -0.0343191 -0.652504 -0.757008 -0.00482346 -0.583926 -0.811792 0.00546111 -0.353932 -0.935255 0.00782561 -0.981644 -0.190562 1.64982e-05 -0.974029 -0.226424 -2.47733e-05 -0.905357 -0.424652 1.23471e-05 -0.905407 -0.424544 8.16842e-06 -0.827985 -0.560751 0.0166627 -0.927292 0.373967 -0.0109405 -0.979608 0.200621 0.0114751 -0.997481 0.0699937 -2.2663e-05 -1 -0.000921681 -1.62533e-05 -0.994508 -0.104661 0.0264231 -0.506437 0.861872 -0.0156564 -0.812114 0.583289 -1.71177e-05 -0.837177 0.546932 7.28174e-06 -0.950205 0.311625 0 0.575714 -0.817651 0 0.575714 -0.817651 0 0.474284 -0.880372 0 0.474284 -0.880372 0 0.366109 -0.930572 0 0.366109 -0.930572 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.998029 -0.0627479 0.0196616 0.961132 -0.275389 -0.000198358 0.969772 -0.244012 0.000205867 0.777193 -0.629262 0 0.77698 -0.629525 -0.698656 0.693831 -0.17458 -0.698657 0.69383 -0.174579 -0.698658 0.556048 -0.45021 -0.698657 0.556048 -0.45021 0 -0.998856 -0.0478298 -0.0215572 -0.976899 -0.21261 -0.0224926 -0.977589 -0.209318 0.0284614 -0.828076 -0.559894 -0.0230708 -0.898769 -0.437816 -0.00843506 -0.458092 -0.888865 0.0119176 -0.668694 -0.743442 2.35825e-05 -0.636172 -0.771547 -8.75755e-06 -0.783604 -0.62126 -1.15689e-05 -0.495166 -0.868799 2.44008e-05 -0.270854 -0.96262 0.00961766 -0.23435 -0.972105 -0.0145584 0.105746 -0.994287 0 0.142635 -0.989775 0.696417 0.0758945 -0.713613 0.696413 0.0758959 -0.713616 0.703788 -0.192418 -0.683856 0.504588 -0.321462 -0.801283 0.696417 -0.701222 -0.152612 0.696415 -0.701224 -0.152614 0.703789 -0.588511 -0.397914 0.504583 -0.659345 -0.557369 0.705062 -0.474235 -0.527246 0.705062 -0.351144 -0.616104 0 -0.556736 0.83069 0.0420206 -0.536103 0.843106 0 -0.495339 0.8687 0 -0.409518 0.912302 0.0629302 -0.38667 0.920069 0 -0.452954 0.891534 0.706179 0.289952 -0.64594 0.70618 0.289952 -0.64594 0.70618 0.379914 -0.597474 0.706178 0.379915 -0.597476 0 -0.367949 0.929846 0 0.70649 -0.707723 -0.0323172 0.783166 -0.620972 -0.0129604 0.835068 -0.549994 0.015622 0.945887 -0.324119 -0.00369029 0.967592 -0.252492 0.003261 0.999973 0.00654199 0.0251184 0.994423 0.102432 -3.39258e-05 0.723443 0.690384 4.05505e-05 0.882301 0.470685 0.00666569 0.870183 0.492683 -0.00509145 0.968057 0.250677 -0.0225153 -0.419209 0.90761 0.0133489 -0.0159384 0.999784 1.49584e-05 0.0383289 0.999265 -5.63753e-07 0.223524 0.974698 -0.00405113 0.295652 0.955287 0.00867145 0.394341 0.918923 -0.00792453 0.52009 0.854075 0.00306859 0.601299 0.799018 -0.00558314 0.741249 0.671207 0 -0.47206 0.881567 -0.0125347 -0.521204 0.85334 0.000324697 -0.639657 0.768661 -0.00111461 -0.810803 0.585318 -0.00397686 -0.805252 0.592919 0.00430265 -0.974098 0.226084 0 -0.971133 0.238538 0.994042 0.0422289 -0.100482 0.97185 -0.0912802 0.217198 0.658911 -0.356767 0.662234 0.108083 -0.553474 0.825823 0.558294 -0.461892 0.689176 0.341055 -0.523355 0.780884 0.237323 -0.547738 0.802284 0.237619 -0.481152 0.843819 0.15399 -0.468627 0.869871 0.237622 -0.43998 0.865998 0.237427 -0.376359 0.895535 0.887896 -0.256122 0.382153 0.739452 -0.3748 0.559229 0.108167 -0.368236 0.923419 0.34105 -0.364209 0.866624 0.658911 -0.291439 0.693469 0.558599 -0.305131 0.771273 0.739456 -0.260825 0.620625 0.971845 -0.131179 0.195729 0.931703 -0.208959 0.297096 0.931867 -0.17207 0.319399 0.658687 -0.425801 0.620342 0.658909 -0.356767 0.662235 0.931867 -0.172071 0.3194 0.931867 -0.140563 0.334465 0.888089 -0.164596 0.429192 0.994042 0.0606814 -0.090541 0.994042 0.0606814 -0.090541 0.994053 0.0539434 -0.0946023 0.994978 0.0474735 -0.0881209 0.994053 0.0493277 -0.0970893 0.994042 0.0422289 -0.100482 0 0.376313 -0.926493 -0.0635015 0.408691 -0.910461 0 0.442189 -0.896922 0 0.536577 -0.843851 -0.126161 0.562166 -0.817345 0 0.505761 -0.862674 0.0684069 0.606088 0.792451 0.0983822 0.231522 0.967842 0.73816 0.645445 -0.196268 0.933082 0.333678 -0.134231 0.885792 0.348903 -0.306006 0.902775 0.358468 -0.237694 0.900887 0.375646 -0.21747 0.89372 0.358138 -0.270187 0.982611 0.178579 -0.0508364 0.968947 0.237908 -0.0673899 0.959187 0.273145 -0.0731594 0.978164 0.19715 -0.0657818 0.993506 0.0877184 -0.072471 0.993503 0.0916422 -0.067483 0.955084 0.282879 -0.0882862 0.937215 0.329541 -0.114153 0.812779 0.560607 0.158459 0.759738 0.648985 0.0401971 0.532648 0.830013 0.165422 0.600307 0.782821 0.163774 0.364128 0.894852 0.258168 0.456009 0.851573 0.258608 0.187422 0.922675 0.336962 0.145513 0.822594 -0.549696 0.172307 0.913982 -0.367352 0.884955 0.353756 -0.302841 0.712671 0.597673 -0.36727 0.69772 0.625028 -0.350037 0.461104 0.798823 -0.386347 0.423351 0.83167 -0.359305 0.179682 0.913259 -0.365613 0.275266 0.961368 0.000211646 0.918217 0.358748 -0.167858 0.916084 0.362645 -0.171112 0.771366 0.636184 -0.0162639 0.722822 0.67312 -0.156327 0.503311 0.856347 -0.115535 0.487238 0.865119 -0.119032 0.35364 0.934492 -0.0407926 0.177317 0.984038 -0.0150903 0.301518 0.889837 0.342457 0.275281 0.735369 0.619236 0.876439 -0.140605 0.460526 0.884048 -0.141684 0.445405 0.725683 -0.237031 0.645911 0.739821 -0.238419 0.629143 0.546204 -0.314134 0.776519 0.55328 -0.314704 0.771261 0.333636 -0.377172 0.863961 0.344991 -0.37912 0.858632 0.105755 -0.409227 0.906283 0.121177 -0.412876 0.90269 0.145476 0.403647 0.903275 0.171343 0.39529 0.902434 0.342314 0.397841 0.851201 0.242329 0.428689 0.870346 0.521635 0.420168 0.742534 0.443201 0.454648 0.772573 0.684257 0.422769 0.594187 0.629492 0.457835 0.627795 0.792145 0.414063 0.448396 0.839077 0.164035 0.518692 0.858962 0.150181 0.489519 0.685631 0.127279 0.716736 0.721184 0.11149 0.683713 0.493419 0.0840088 0.865725 0.546142 0.0669021 0.835017 0.282727 0.0386255 0.958422 0.351088 0.0203793 0.936121 0.0859307 -0.00381512 0.996294 0.10682 -0.00903863 0.994237 0.147943 0.696857 -0.701786 0.205582 0.716848 -0.666232 0.341461 0.685196 -0.643359 0.424998 0.669805 -0.608882 0.484347 0.625765 -0.611413 0.687667 0.510048 -0.516687 0.647366 0.569386 -0.506673 0.870204 0.2733 -0.409942 0.850012 0.353396 -0.39063 0.0290103 0.945303 -0.3249 0.135837 0.986649 0.0898414 -0.181683 0.981768 0.0558906 0.289891 0.860481 0.418969 0.0131286 0.91675 0.399247 0.143538 0.709851 0.689571 0.324423 0.697256 0.639205 0.209393 0.733253 0.646912 0.489615 0.68827 0.535314 0.398064 0.732577 0.552156 0.641638 0.650515 0.406362 0.575709 0.697591 0.426528 0.805188 0.551779 0.217286 0.849347 0.445184 0.283586 0.891417 0.388226 0.233788 0.946585 0.179585 0.267816 0.938296 0.190492 0.28864 0.97139 -0.0335247 0.235112 0.963017 -0.0306568 0.267691 0.146448 0.144722 -0.978575 0.82472 -0.453524 -0.337866 0.651394 0.154719 -0.742797 0.942263 -0.121782 -0.311946 0.971801 -0.0640828 -0.226926 0.978816 -0.0630417 -0.194793 0.98931 -0.0033572 -0.145789 0.993672 0.0111848 -0.111761 0.851106 0.184036 -0.49168 0.873458 0.0822313 -0.479906 0.889414 0.0436113 -0.455018 0.901407 -0.00097543 -0.432972 0.8953 0.00171009 -0.445461 0.918228 -0.0498849 -0.392898 0.741743 -0.375081 -0.555997 0.782192 -0.363248 -0.506189 0.708896 -0.216191 -0.671363 0.911963 -0.0516489 -0.407008 0.938587 -0.0772317 -0.336289 0.786961 -0.48419 -0.382429 0.849348 -0.481719 -0.215766 0.792191 -0.602183 -0.0990422 0.856726 -0.499344 0.129139 0.843572 -0.512623 0.160014 0.884013 -0.300032 0.358472 0.877481 -0.300533 0.373774 0.921873 -0.0984919 -0.374767 0.959989 -0.0623145 -0.273018 0.89144 -0.408768 -0.195559 0.944652 -0.327788 -0.0136829 0.941309 -0.337454 0.00796184 0.970892 -0.188208 0.148143 0.965072 -0.191329 0.178965 0.333936 -0.510366 0.792473 0.105763 -0.531776 0.840255 0.307671 -0.453962 0.836216 0.013238 -0.577435 -0.816329 0.284304 -0.586411 -0.758481 0.115719 -0.639101 0.760368 0.0794158 -0.806124 0.586393 0.183105 -0.823745 0.536579 0.0104365 -0.971337 0.237477 0.144764 -0.974644 0.170622 0.0751045 -0.995569 -0.0565811 0.208448 -0.952959 -0.220043 0.18133 -0.95609 -0.230243 -0.0831661 -0.842528 -0.532194 0.373392 -0.811631 -0.449259 0.105705 -0.771485 -0.627405 0.0688722 -0.45083 -0.889949 0.10011 -0.227222 -0.968684 0.178763 -0.196828 -0.964003 0.11164 0.161408 -0.980553 0.341453 0.160401 -0.926111 0.692776 0.125282 -0.710187 0.714411 -0.0459159 -0.698218 0.412914 -0.127675 -0.901777 0.487266 -0.376578 -0.787884 0.3536 -0.480083 -0.8028 0.447584 -0.666529 -0.59616 0.377675 -0.722828 -0.57869 0.480036 -0.818976 -0.314395 0.412112 -0.868433 -0.275659 0.513923 -0.85744 0.0260938 0.454269 -0.887739 0.0745583 0.542569 -0.747057 0.384088 0.499052 -0.755922 0.423709 0.553193 -0.473521 0.685387 0.546579 -0.47289 0.691105 0.344668 -0.512718 0.786336 0.287821 -0.80771 0.514552 0.346278 -0.807595 0.477369 0.253017 -0.955325 0.152762 0.332866 -0.937415 0.102238 0.223308 -0.949243 -0.221518 0.313049 -0.91129 -0.267489 0.200944 -0.805924 -0.556873 0.291654 -0.757177 -0.584484 0.187452 -0.549996 -0.813859 0.269274 -0.505867 -0.819506 0.179695 -0.196961 -0.963803 0.463499 -0.149289 -0.873431 0.425022 0.14006 -0.894282 0.484352 0.166401 -0.858903 0.870902 0.146442 -0.469132 0.892968 0.0631338 -0.44567 0.690169 -0.0305606 -0.723002 0.744778 -0.222532 -0.629115 0.503283 -0.374673 -0.778669 0.593137 -0.550555 -0.587434 0.545203 -0.607156 -0.578028 0.633556 -0.690143 -0.349727 0.588801 -0.742593 -0.319168 0.677986 -0.733077 -0.0541629 0.639888 -0.768381 -0.0115847 0.718475 -0.642879 0.265517 0.691091 -0.65625 0.302867 0.739779 -0.401303 0.540077 0.72692 -0.40132 0.557252 0.939622 0.12878 -0.31706 0.939566 0.190609 -0.284402 0.938421 0.20603 -0.27734 0.939692 0.205135 -0.273675 0.939393 0.206464 -0.273705 0.939414 0.206377 -0.273696 0.939897 0.205397 -0.272775 0.939965 0.205449 -0.272499 0.939946 0.205446 -0.272569 0.939759 0.205679 -0.273037 0.939563 0.205999 -0.273468 0.939622 0.114996 -0.322315 0.939837 0.114793 -0.321759 0.940955 0.115909 -0.318071 0.939692 0.115725 -0.321849 0.939969 0.114539 -0.321465 0.939975 0.114515 -0.321455 0.939692 0.116178 -0.321684 0.939472 0.115106 -0.322712 0.939449 0.115079 -0.322788 0.939565 0.132647 -0.315629 0.94337 0.126925 -0.306501 0.936007 0.159432 -0.313803 0.939622 0.151323 -0.306939 0.93966 0.169461 -0.297189 0.937285 0.17629 -0.300697 0.94337 0.186135 -0.274603 0.939621 0.193933 -0.281962 0.939692 0.204705 -0.273998 0.149351 0.372092 -0.916101 0.488785 0.328296 -0.808276 0.346108 0.53167 -0.773005 0.655059 0.428182 -0.622542 0.850962 0.297643 -0.432749 0.850962 0.297644 -0.43275 0.850962 0.26564 -0.4531 0.850962 0.265639 -0.453099 0.850962 0.23225 -0.471087 0.850963 0.232249 -0.471086 0.850963 0.197649 -0.486617 0.850961 0.19765 -0.48662 0.655065 0.284331 -0.700033 0.573439 0.315227 -0.756174 0.573328 0.362298 -0.734871 0.57333 0.362297 -0.73487 0.57333 0.414382 -0.70681 0.57333 0.414382 -0.70681 0.573442 0.458065 -0.679221 0.488782 0.494388 -0.718799 0.346094 0.353056 -0.869235 0.202127 0.373906 -0.905173 0.202089 0.433066 -0.878416 0.202089 0.433066 -0.878416 0.202089 0.495325 -0.844875 0.202089 0.495325 -0.844875 0.202127 0.550214 -0.810191 0.149345 0.560339 -0.814688 -0.707099 -0.439462 0.553971 -0.671183 -0.425258 0.607181 -0.70647 -0.407458 0.578687 -0.70647 -0.335671 0.623077 -0.706474 -0.335669 0.623073 -0.706525 -0.260733 0.657906 -0.672809 -0.270853 0.688452 -0.707094 -0.220865 0.671742 -0.694735 -0.392343 0.602835 -0.487524 -0.871867 -0.0465681 -0.694741 -0.392341 0.602829 -0.702915 -0.595462 0.389019 -0.494623 -0.774775 0.393791 -0.705012 -0.673881 0.221003 -0.703696 -0.708758 0.0497339 -0.704398 -0.696797 -0.135266 -0.704399 -0.642626 -0.30142 -0.487516 -0.731777 -0.476266 -0.694748 0.0383604 -0.718229 -0.694747 0.0383601 -0.71823 -0.702923 -0.251744 -0.665226 -0.494626 -0.393792 -0.774773 -0.705004 -0.414127 -0.575732 -0.703688 -0.543256 -0.457927 -0.697825 -0.308842 0.646264 -0.697831 -0.308841 0.646257 -0.697833 0.00635592 0.716233 -0.697831 0.0063565 0.716234 -0.69783 0.320261 0.640676 -0.697828 0.320262 0.640677 -0.697827 0.569093 0.434937 -0.697828 0.569092 0.434937 -0.697827 0.702287 0.140819 -0.697824 0.702291 0.140819 -0.70647 0.407458 -0.578687 -0.70647 0.407458 -0.578687 -0.70647 0.335671 -0.623077 -0.706471 0.335671 -0.623076 -0.706471 0.25911 -0.658605 -0.706477 0.259108 -0.658599 -0.879242 0.111938 -0.463037 -0.887084 0.0374895 -0.460082 -0.954988 -0.0905372 -0.282491 -0.960101 -0.0962102 -0.262582 -0.978436 -0.0640712 -0.196364 -0.978976 -0.0638362 -0.19373 -0.991397 -7.26325e-05 -0.130892 -0.990797 -0.00271267 -0.135328 -0.965171 -0.184367 0.185616 -0.793208 -0.604088 -0.0768029 -0.859467 -0.484825 0.16205 -0.839104 -0.518122 0.16569 -0.884191 -0.280395 0.373612 -0.876484 -0.294287 0.381014 -0.859293 -0.359865 -0.363474 -0.938545 -0.0958353 -0.331585 -0.933194 -0.0822466 -0.349835 -0.821647 -0.494106 -0.284175 -0.847485 -0.488764 -0.207073 -0.891281 -0.415059 -0.182604 -0.947044 -0.320961 0.00962797 -0.938319 -0.345592 0.0111325 -0.970911 -0.184006 0.153209 -0.989049 -0.126932 0.0753077 -0.807337 -0.191635 -0.558107 -0.693244 -0.482023 -0.535785 -0.770721 -0.548391 -0.324433 -0.902135 -0.0357515 -0.42997 -0.88785 0.0430198 -0.458118 -0.749521 -0.0285285 -0.661366 -0.710137 -0.0167062 -0.703866 -0.276008 -0.558065 -0.782549 -0.145874 -0.0297952 -0.988854 -0.197809 0.129072 -0.971706 -0.147939 0.167687 -0.974677 -0.111689 -0.81023 0.575372 -0.0948755 -0.506563 0.856967 -0.105769 -0.502724 0.857952 -0.078067 -0.996914 -0.00825689 -0.143546 -0.971747 0.187353 -0.177907 -0.96382 0.198495 -0.097289 -0.926226 0.364199 -0.110855 -0.810457 0.575213 -0.0290478 -0.282331 -0.958877 -0.13492 -0.640472 -0.756037 0.129835 -0.609187 -0.782326 -0.156044 -0.809479 -0.566033 -0.216095 -0.82108 -0.528329 -0.0506006 -0.902137 -0.428471 -0.143383 -0.973015 -0.180783 -0.273789 -0.93035 -0.243904 -0.142489 -0.982825 -0.117271 -0.354221 -0.507679 -0.785359 -0.457111 -0.704745 -0.542572 -0.363197 -0.726611 -0.583202 -0.490852 -0.834996 -0.248688 -0.397282 -0.873644 -0.280917 -0.522588 -0.847866 0.0895841 -0.442826 -0.893537 0.074138 -0.546595 -0.718495 0.430115 -0.493394 -0.755226 0.431505 -0.553361 -0.446781 0.702978 -0.546233 -0.451713 0.705397 -0.176408 -0.554796 -0.813069 -0.302659 -0.795483 -0.52498 -0.186328 -0.806943 -0.560468 -0.325673 -0.925032 -0.195584 -0.208486 -0.951343 -0.226895 -0.343268 -0.923561 0.170887 -0.241871 -0.958392 0.151601 -0.351524 -0.774002 0.526642 -0.282647 -0.804755 0.521996 -0.345026 -0.480335 0.806371 -0.333674 -0.486219 0.807622 -0.879552 0.112875 -0.46222 -0.763479 0.128898 -0.632839 -0.693958 0.0952472 -0.713688 -0.65141 0.128659 -0.747738 -0.484426 0.137212 -0.864005 -0.918288 -0.0692941 -0.389803 -0.901026 -0.0636083 -0.429076 -0.758733 -0.279656 -0.588317 -0.805283 -0.244533 -0.540114 -0.700535 -0.356652 -0.618102 -0.633832 -0.0982745 -0.767202 -0.461116 -0.144848 -0.875437 -0.425663 0.106203 -0.898628 -0.341483 0.128103 -0.931117 -0.172213 -0.227261 -0.958486 -0.179201 -0.228493 -0.956911 -0.424088 -0.189479 -0.885577 -0.486864 -0.40029 -0.776358 -0.502662 -0.399021 -0.766886 -0.601389 -0.58737 -0.541597 -0.531846 -0.613468 -0.583778 -0.64282 -0.707848 -0.292803 -0.575099 -0.750854 -0.324775 -0.685236 -0.72832 0.00140787 -0.629206 -0.777146 -0.0119744 -0.721673 -0.620875 0.306109 -0.685623 -0.658579 0.310152 -0.73994 -0.374532 0.558762 -0.725681 -0.389971 0.566843 -0.340892 -0.54123 0.768676 -0.994035 0.0517264 -0.0960151 -0.994036 0.0629659 -0.0890336 -0.994251 0.0616469 -0.0875533 -0.991754 0.0466713 -0.119357 -0.996676 0.0341415 -0.0739732 -0.658678 -0.356863 0.662414 -0.93179 -0.172164 0.319572 -0.994046 0.0416811 -0.100678 -0.993745 -0.0408835 0.103917 -0.971837 -0.086275 0.219293 -0.994056 0.0574517 -0.0924772 -0.994035 0.0517262 -0.0960149 -0.931791 -0.172163 0.319572 -0.931639 -0.126945 0.340491 -0.558461 -0.488928 0.670127 -0.739297 -0.387674 0.550589 -0.93179 -0.208982 0.296805 -0.888071 -0.274056 0.369085 -0.971843 -0.135656 0.192663 -0.237285 -0.460739 0.855228 -0.237285 -0.559272 0.794299 -0.108128 -0.584206 0.80437 -0.887836 -0.168469 0.428212 -0.739297 -0.24653 0.626629 -0.658466 -0.269331 0.702768 -0.558108 -0.303785 0.772159 -0.340892 -0.34418 0.874833 -0.65868 -0.433181 0.61522 -0.65868 -0.356863 0.662412 -0.237286 -0.460739 0.855228 -0.237189 -0.349461 0.906432 -0.10804 -0.363965 0.925125 -0.572885 0.38874 -0.721584 -0.850725 0.303493 -0.429138 -0.879518 0.173297 -0.443189 -0.654682 0.276743 -0.703424 -0.764991 0.235789 -0.599326 -0.845143 0.198878 -0.496166 -0.851115 0.219998 -0.476659 -0.850698 0.24931 -0.462772 -0.850698 0.24931 -0.462772 -0.851115 0.277027 -0.445936 -0.345797 0.343523 -0.873164 -0.488398 0.319474 -0.812037 -0.149208 0.36201 -0.920155 -0.201916 0.361816 -0.91012 -0.201876 0.464519 -0.862246 -0.844348 0.308465 -0.438094 -0.65468 0.435186 -0.618067 -0.573006 0.468122 -0.672701 -0.488415 0.502375 -0.713492 -0.345802 0.540197 -0.767208 -0.573005 0.30425 -0.760984 -0.572884 0.38874 -0.721585 -0.201875 0.464519 -0.862246 -0.201915 0.560997 -0.802815 -0.149219 0.569269 -0.808497 -0.146154 0.766702 -0.625146 -0.826271 0.521251 0.213479 -0.651412 0.553614 -0.518819 -0.992269 0.114618 -0.0475996 -0.992328 0.0904791 -0.0842574 -0.976262 0.211994 -0.04439 -0.978909 0.196937 -0.0543453 -0.963219 0.261304 -0.0626797 -0.851017 0.315403 -0.419871 -0.880973 0.361773 -0.304969 -0.902083 0.369565 -0.222865 -0.895846 0.378165 -0.233348 -0.919312 0.359427 -0.160245 -0.740532 0.671487 0.0267695 -0.783613 0.619277 0.0494724 -0.707955 0.685769 -0.16888 -0.918517 0.361022 -0.161215 -0.938741 0.328822 -0.103155 -0.7859 0.58109 0.211415 -0.847486 0.441811 0.294228 -0.793261 0.396365 0.462204 -0.856963 0.150257 0.492988 -0.844207 0.128964 0.520272 -0.884162 -0.149515 0.442609 -0.877674 -0.163164 0.450629 -0.945947 0.309364 -0.0973528 -0.960044 0.27274 -0.0626741 -0.891349 0.380711 0.246082 -0.944831 0.182705 0.271869 -0.94185 0.167477 0.291326 -0.970926 -0.0266201 0.237894 -0.965173 -0.0535419 0.256074 -0.130882 0.362145 0.922887 -0.0963532 0.166565 0.981312 -0.146462 -0.0318169 0.988705 -0.0515371 -0.0779264 0.995626 -0.106238 -0.458812 0.88216 -0.157404 -0.435519 0.886311 -0.334009 -0.411135 0.848178 -0.0122585 0.997827 0.0647333 -0.240104 0.964835 0.106975 -0.150994 0.355436 0.922424 -0.0723946 0.568909 0.819208 -0.201887 0.684162 0.700831 -0.130404 0.713883 0.688016 -0.0119052 0.903786 0.427819 -0.320802 0.828682 0.458663 -0.105196 0.938178 0.329781 -0.0889249 0.99365 -0.0689368 -0.0329025 0.959973 -0.278153 -0.190436 0.923637 -0.332608 -0.0911618 0.754265 -0.65021 -0.341495 0.707048 -0.619245 -0.693994 0.54356 -0.47214 -0.714751 0.620359 -0.322933 -0.412189 0.835431 -0.363532 -0.486902 0.868522 -0.0927093 -0.354182 0.935142 -0.00798852 -0.447646 0.856501 0.256943 -0.378516 0.869965 0.316047 -0.480134 0.695745 0.534238 -0.413113 0.686693 0.598156 -0.514074 0.425144 0.74497 -0.455182 0.3974 0.796795 -0.542689 0.0617883 0.837658 -0.49964 0.030795 0.865686 -0.553284 -0.338191 0.761251 -0.546673 -0.343697 0.763558 -0.344681 -0.404298 0.847194 -0.288263 -0.0196448 0.95735 -0.346234 0.013761 0.938047 -0.253712 0.36609 0.895326 -0.33284 0.401814 0.853091 -0.224034 0.682833 0.695376 -0.313039 0.703785 0.637725 -0.201536 0.894834 0.398315 -0.291644 0.893788 0.340715 -0.187827 0.981129 0.0459079 -0.269299 0.96305 0.00369425 -0.179211 0.924766 -0.335695 -0.463844 0.823903 -0.325626 -0.425694 0.691966 -0.583068 -0.484446 0.64599 -0.589923 -0.875382 0.323073 -0.359625 -0.889599 0.35535 -0.286948 -0.689728 0.632207 -0.352974 -0.745699 0.652464 -0.134999 -0.502664 0.859932 -0.0885745 -0.59328 0.788492 0.162172 -0.546281 0.80884 0.217612 -0.633761 0.658703 0.405533 -0.589992 0.657962 0.46797 -0.678233 0.428801 0.596766 -0.640943 0.408517 0.649851 -0.718702 0.108684 0.686772 -0.691736 0.0819105 0.71749 -0.739913 -0.251609 0.623876 -0.727058 -0.267121 0.632482 -0.939507 0.124739 -0.319008 -0.939609 0.104468 -0.325915 -0.939482 0.104443 -0.326292 -0.939572 0.104623 -0.325973 -0.93969 0.105496 -0.325351 -0.939848 0.104241 -0.325299 -0.939867 0.104183 -0.325262 -0.939729 0.104366 -0.325603 -0.939515 0.197767 -0.279643 -0.940463 0.212073 -0.26562 -0.939697 0.214173 -0.266646 -0.939902 0.214301 -0.265819 -0.93969 0.213819 -0.266952 -0.939535 0.214826 -0.266689 -0.939496 0.214984 -0.2667 -0.939513 0.214925 -0.266687 -0.939748 0.214432 -0.266255 -0.939508 0.197778 -0.279658 -0.939511 0.197774 -0.27965 -0.939694 0.180485 -0.290518 -0.939693 0.18048 -0.290523 -0.939498 0.162469 -0.301576 -0.939498 0.162469 -0.301576 -0.939693 0.143325 -0.310538 -0.939694 0.143326 -0.310538 -0.939511 0.124735 -0.318999 -0.939514 0.124732 -0.31899 -0.939697 0.105268 -0.325405 0 -0.463218 0.886244 0.015359 -0.431131 0.902159 -0.0139701 -0.0801031 0.996689 0.0215391 0.0088717 0.999729 0.00266733 0.16013 0.987092 -0.00681582 0.347971 0.937481 0.0292775 0.446936 0.894087 0.000647917 0.564705 0.825292 0 0.980483 0.196602 0.0389777 0.990218 0.133975 0.00184365 0.940041 0.341056 -0.00669224 0.79451 0.607215 0.0594581 0.853939 0.516966 -0.000756919 0.711068 0.703123 0.700052 -0.695602 0.161446 0.700047 -0.695607 0.161446 0.700049 -0.372219 0.609414 0.700048 -0.372219 0.609414 0.700048 -0.578991 0.417974 0.776292 -0.493406 0.392329 0.706721 -0.629757 0.322414 0.458499 0.552143 0.69636 0.69474 -0.264652 0.668802 0.694739 -0.264652 0.668803 0.705697 -0.0184809 0.708273 0.754936 0.0251361 0.655317 0.624885 0.182324 0.759129 0.705018 0.209675 0.677485 0.703701 0.369533 0.606836 0.704399 0.513503 0.490038 0.704398 0.617674 0.349717 0.458494 0.826352 0.326995 0.694741 0.563595 -0.446874 0.69474 0.563595 -0.446874 0.702915 0.688227 -0.179592 0.466758 0.874873 -0.12936 0.705014 0.709178 0.00463956 0.703696 0.687815 0.178108 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706179 -0.289952 0.64594 0.706177 -0.289953 0.645942 0.706176 -0.379916 0.597477 0.706176 -0.379916 0.597478 -0.69474 0.325898 0.641192 -0.487519 -0.476264 0.731777 -0.694741 0.325897 0.641191 -0.702915 0.0391697 0.710194 -0.494619 -0.0463545 0.867873 -0.705016 -0.14555 0.694095 -0.7037 -0.311303 0.638668 -0.704401 -0.465543 0.535807 -0.704401 -0.582349 0.405818 -0.487526 -0.778342 0.395604 -0.694745 -0.602825 -0.39234 -0.694735 -0.602836 -0.392343 -0.70291 -0.701987 -0.114598 -0.494617 -0.867874 -0.0463573 -0.705021 -0.705645 0.0707887 -0.703704 -0.668191 0.2415 -0.699625 0.390626 0.598278 -0.699633 0.390619 0.598273 -0.699634 0.596221 0.393743 -0.69963 0.596225 0.393743 -0.69963 0.703603 0.124341 -0.69963 0.703603 0.124341 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.4531 0.89146 0 -0.770077 -0.637951 0.0478487 -0.837163 -0.544856 0.0190461 -0.883151 -0.468702 -0.0231318 -0.971805 -0.234648 0.00914278 -0.940421 0.33989 -0.0343164 -0.981841 0.186577 -0.00482768 -0.994994 0.0998156 0.00545754 -0.986921 -0.161113 0.00782466 -0.655857 0.754845 1.76602e-05 -0.6831 0.730325 -2.4066e-05 -0.820439 0.571735 1.39526e-05 -0.820368 0.571836 9.55602e-06 -0.899618 0.436679 0.0166608 -0.139792 0.990041 -0.010941 -0.316061 0.948676 0.0114734 -0.438119 0.898844 -2.50253e-05 -0.500797 0.865565 -1.83963e-05 -0.587888 0.808943 0.0264241 0.49319 0.86952 -0.0156564 0.0990853 0.994956 -1.75342e-05 0.0550698 0.998483 6.13825e-06 -0.205234 0.978713 0 0.499444 0.866346 0.0184744 0.546611 0.837183 0.000259963 0.663429 0.74824 -0.000964766 0.834457 0.551073 0.00813307 0.823423 0.567369 -0.00869857 0.984704 0.174017 0 0.981614 0.190878 0 -0.420249 -0.907409 0 -0.420249 -0.907409 0 -0.525282 -0.850928 0 -0.525282 -0.850928 0 -0.622845 -0.782345 0 -0.622845 -0.782345 0 0.622845 0.782346 0 0.622845 0.782346 0 0.525282 0.850928 0 0.525282 0.850928 0 0.420249 0.907409 0 0.420249 0.907409 -0.87924 -0.345039 -0.32846 -0.887085 -0.379695 -0.262509 -0.954988 -0.289912 -0.0628387 -0.960102 -0.275506 -0.0479702 -0.978436 -0.202089 -0.0426942 -0.978976 -0.199694 -0.041582 -0.991396 -0.113394 -0.0653836 -0.990797 -0.118552 -0.065315 -0.965171 0.0685661 0.252474 -0.793204 -0.368556 0.484761 -0.859465 -0.102075 0.5009 -0.839106 -0.115568 0.53155 -0.884191 0.183359 0.429634 -0.876485 0.182824 0.445363 -0.859292 -0.494712 0.129911 -0.938544 -0.33508 -0.0827988 -0.933194 -0.34409 -0.10369 -0.821646 -0.493159 0.28582 -0.847484 -0.423714 0.319747 -0.891285 -0.365663 0.268144 -0.947045 -0.152141 0.28277 -0.938318 -0.163157 0.304859 -0.970911 0.0406797 0.235958 -0.989048 0.00175484 0.147585 -0.807335 -0.579154 -0.113094 -0.693239 -0.705019 0.149557 -0.770717 -0.555168 0.312704 -0.902135 -0.390245 -0.184015 -0.887849 -0.375236 -0.26631 -0.749537 -0.587009 -0.305965 -0.710133 -0.61792 -0.33747 -0.276011 -0.956739 0.092022 -0.145875 -0.871264 -0.468636 -0.197803 -0.77699 -0.597629 -0.14793 -0.760254 -0.632559 -0.111693 0.0931704 0.989365 -0.0948823 0.488878 0.867177 -0.105766 0.491648 0.864347 -0.0780595 -0.505606 0.859226 -0.143539 -0.323621 0.935236 -0.177907 -0.310005 0.933941 -0.0972946 -0.147718 0.984232 -0.110862 0.0929201 0.989482 -0.0290493 -0.971578 -0.234931 -0.134914 -0.974985 0.176643 0.129832 -0.982108 0.136406 -0.156047 -0.894939 0.418011 -0.216103 -0.868083 0.446913 -0.0506101 -0.822135 0.567039 -0.143393 -0.643072 0.752261 -0.273783 -0.676399 0.683759 -0.14248 -0.592966 0.792522 -0.354232 -0.933977 0.046975 -0.457122 -0.822247 0.339043 -0.363187 -0.868376 0.337664 -0.490845 -0.632874 0.598783 -0.397301 -0.680097 0.616134 -0.5226 -0.346346 0.77906 -0.442823 -0.382565 0.810896 -0.546594 0.0132445 0.837293 -0.493391 -0.0039171 0.869799 -0.55336 0.385406 0.738414 -0.546232 0.385034 0.743895 -0.176396 -0.981539 0.0739271 -0.302651 -0.852388 0.426423 -0.186331 -0.888848 0.418605 -0.325671 -0.631899 0.703308 -0.208471 -0.672173 0.710439 -0.343262 -0.313785 0.885274 -0.241869 -0.347901 0.905795 -0.351519 0.0690841 0.933628 -0.28265 0.0496854 0.957935 -0.345029 0.458172 0.819167 -0.33367 0.456312 0.82489 -0.879553 -0.343852 -0.328866 -0.76349 -0.483589 -0.428048 -0.693955 -0.57045 -0.439333 -0.651406 -0.583232 -0.485294 -0.48443 -0.679641 -0.550832 -0.91828 -0.372239 -0.134904 -0.901026 -0.403393 -0.159453 -0.758736 -0.649322 -0.0519735 -0.805293 -0.590004 -0.0582906 -0.700523 -0.71363 -0.000173541 -0.633816 -0.713568 -0.298493 -0.461117 -0.830576 -0.312274 -0.425664 -0.725133 -0.541288 -0.341502 -0.742316 -0.576492 -0.172217 -0.943703 -0.282427 -0.179202 -0.942955 -0.280574 -0.424089 -0.861672 -0.278694 -0.486864 -0.872491 -0.0415187 -0.502659 -0.863654 -0.0378825 -0.60139 -0.762722 0.237877 -0.531854 -0.812296 0.239388 -0.642826 -0.607494 0.466612 -0.575089 -0.656697 0.487875 -0.685232 -0.362943 0.631451 -0.629209 -0.398941 0.66704 -0.721675 -0.0453395 0.690746 -0.685619 -0.060693 0.725426 -0.739938 0.296636 0.603738 -0.72568 0.295915 0.621146 -0.146152 -0.158041 -0.976557 -0.826272 0.445504 -0.344675 -0.651409 -0.172504 -0.738856 -0.992269 0.0160866 -0.123062 -0.992328 -0.0277297 -0.120486 -0.976263 0.0675532 -0.205786 -0.978909 0.0514048 -0.197725 -0.963219 0.076371 -0.257636 -0.851018 -0.205913 -0.483082 -0.880974 -0.0832228 -0.465789 -0.902083 -0.00822347 -0.431485 -0.895846 -0.0130026 -0.444175 -0.919311 0.040936 -0.391397 -0.740531 0.358925 -0.568143 -0.783612 0.352481 -0.511576 -0.707956 0.19663 -0.678333 -0.918516 0.0408937 -0.393263 -0.938742 0.0750768 -0.336344 -0.785899 0.473637 -0.397531 -0.847485 0.475716 -0.235506 -0.793259 0.598464 -0.112164 -0.856964 0.502067 0.11637 -0.844209 0.515047 0.148449 -0.884163 0.308552 0.350787 -0.877676 0.308673 0.366615 -0.945947 0.0703729 -0.316594 -0.960044 0.0820933 -0.267537 -0.891348 0.403471 -0.206665 -0.944831 0.326798 -0.0222899 -0.94185 0.336034 0.000626682 -0.970926 0.192713 0.142002 -0.965173 0.194997 0.174408 -0.261305 0.948164 -0.180843 -0.0792487 0.96966 -0.231256 -0.103111 0.983088 0.151347 -0.0250769 0.981703 0.188759 -0.165511 0.838564 0.519054 -0.0785576 0.823631 0.561659 -0.114886 0.661981 0.740664 -0.334007 0.528977 0.780142 -0.105776 0.552418 0.826829 -0.273937 0.48384 0.831178 -0.300409 0.571308 -0.763781 -0.0388377 0.552364 -0.832698 -0.115213 0.809843 -0.575222 -0.0235757 0.839444 -0.542934 -0.107891 0.935693 -0.335913 -0.0615576 0.434853 -0.898395 -0.111865 0.20728 -0.971865 -0.190437 0.173772 -0.966197 -0.0911628 -0.185964 -0.978318 -0.341506 -0.182755 -0.921941 -0.693996 -0.137102 -0.706805 -0.714752 0.03051 -0.698712 -0.41219 0.102887 -0.90527 -0.486905 0.353972 -0.798516 -0.354178 0.460657 -0.81385 -0.447646 0.650769 -0.613281 -0.378512 0.70869 -0.595388 -0.48013 0.810539 -0.335412 -0.413115 0.861363 -0.295617 -0.514076 0.857734 0.00429773 -0.455181 0.888746 0.0542403 -0.542687 0.756327 0.365321 -0.499637 0.765103 0.406177 -0.553283 0.490169 0.673508 -0.546676 0.489415 0.679425 -0.344685 0.531546 0.773726 -0.288269 0.819268 0.495683 -0.346226 0.819254 0.457111 -0.253702 0.958422 0.130623 -0.332834 0.939707 0.0785663 -0.224026 0.943632 -0.243662 -0.313036 0.904179 -0.290635 -0.201536 0.792372 -0.575787 -0.291656 0.741959 -0.603684 -0.187842 0.530316 -0.826729 -0.269294 0.484729 -0.832177 -0.179205 0.171662 -0.96872 -0.463844 0.12995 -0.876334 -0.425693 -0.158969 -0.890794 -0.484448 -0.187895 -0.854404 -0.87538 -0.149912 -0.459605 -0.889599 -0.0708293 -0.451217 -0.68973 0.0104187 -0.723992 -0.7457 0.20932 -0.632548 -0.502668 0.353258 -0.789008 -0.593283 0.534686 -0.60177 -0.546279 0.592878 -0.591671 -0.633762 0.680555 -0.367683 -0.589996 0.734252 -0.335825 -0.678237 0.73121 -0.0729752 -0.640943 0.767046 -0.0288618 -0.718701 0.649104 0.249265 -0.691737 0.662319 0.287809 -0.739913 0.414489 0.529837 -0.727057 0.414187 0.547575 -0.572883 -0.430541 -0.697452 -0.850726 -0.219897 -0.477399 -0.879516 -0.297167 -0.371677 -0.654678 -0.470813 -0.591381 -0.765 -0.401131 -0.503854 -0.845143 -0.330253 -0.420317 -0.851115 -0.3028 -0.428854 -0.850697 -0.276118 -0.447295 -0.850698 -0.276118 -0.447295 -0.851115 -0.247675 -0.462882 -0.345811 -0.584418 -0.734078 -0.488403 -0.543506 -0.682689 -0.1492 -0.615874 -0.773588 -0.201914 -0.60728 -0.768403 -0.201874 -0.514467 -0.833409 -0.844348 -0.225167 -0.486184 -0.654675 -0.317671 -0.685919 -0.573004 -0.348515 -0.741757 -0.488417 -0.366714 -0.791814 -0.345811 -0.394322 -0.851425 -0.573008 -0.506906 -0.643979 -0.572887 -0.430539 -0.69745 -0.201877 -0.514467 -0.833408 -0.201917 -0.41476 -0.887245 -0.149215 -0.415545 -0.89725 -0.340891 0.395077 0.853058 -0.994035 -0.0572883 -0.0928039 -0.994036 -0.0456223 -0.0990466 -0.994251 -0.0449999 -0.0971645 -0.991754 -0.0800303 -0.100097 -0.996676 -0.0469925 -0.0665545 -0.658678 0.395236 0.640259 -0.931791 0.190675 0.308883 -0.994046 -0.0663492 -0.0864358 -0.993745 0.0695561 0.0873682 -0.971837 0.146777 0.184364 -0.994056 -0.0513643 -0.0959928 -0.994035 -0.0572887 -0.0928044 -0.931791 0.190676 0.308884 -0.931639 0.231401 0.280183 -0.558464 0.335882 0.758486 -0.739296 0.282988 0.611032 -0.931791 0.152549 0.329386 -0.888073 0.182608 0.421878 -0.971842 0.0990241 0.213815 -0.237287 0.51028 0.826625 -0.237288 0.408247 0.881493 -0.10813 0.404502 0.908122 -0.887838 0.286606 0.360002 -0.739295 0.419412 0.526817 -0.658467 0.473949 0.584632 -0.558106 0.516818 0.649167 -0.340888 0.585539 0.735486 -0.658678 0.316206 0.682757 -0.658679 0.395235 0.640259 -0.237287 0.51028 0.826625 -0.23719 0.610262 0.755858 -0.108037 0.619199 0.777766 -0.939508 -0.213899 -0.267531 -0.93961 -0.230015 -0.25343 -0.939482 -0.230353 -0.253596 -0.939572 -0.229988 -0.253593 -0.93969 -0.229015 -0.254037 -0.939848 -0.229596 -0.252927 -0.939868 -0.229593 -0.252853 -0.939724 -0.229806 -0.253197 -0.939515 -0.143294 -0.311093 -0.940467 -0.123998 -0.31646 -0.939697 -0.123836 -0.318802 -0.939901 -0.123058 -0.3185 -0.93969 -0.124278 -0.318651 -0.939535 -0.123546 -0.319391 -0.939494 -0.123474 -0.319539 -0.939514 -0.123496 -0.319471 -0.939749 -0.123368 -0.31883 -0.939507 -0.143303 -0.311112 -0.939511 -0.143297 -0.311103 -0.939693 -0.161361 -0.301561 -0.939694 -0.161357 -0.301562 -0.939498 -0.179938 -0.29149 -0.939498 -0.179938 -0.29149 -0.939693 -0.197272 -0.279392 -0.939693 -0.197271 -0.279393 -0.939511 -0.213894 -0.267523 -0.939515 -0.213887 -0.267516 -0.939697 -0.229177 -0.253866 0 0.986855 -0.161609 0.0350283 0.963479 -0.265482 0.0183698 0.945179 -0.326037 -0.0224803 0.839523 -0.542859 0.00106768 0.800673 -0.599101 -0.00104865 0.62006 -0.784553 -0.00807498 0.635738 -0.771863 0.00656411 0.440101 -0.897924 8.16986e-06 0.460268 -0.88778 -3.11619e-05 0.236605 -0.971606 -0.00855941 0.214113 -0.976771 0.0138193 -0.13421 -0.990857 0 -0.156694 -0.987647 -0.696797 -0.0962746 -0.710778 -0.696799 -0.0962735 -0.710776 -0.6968 0.242051 -0.67519 -0.324156 0.223829 -0.919143 -0.696796 0.691498 -0.190539 -0.696799 0.691496 -0.190537 -0.703908 0.568711 -0.425537 -0.535519 0.619235 -0.574254 -0.705132 0.450801 -0.547327 -0.70513 0.326366 -0.629505 0 -0.999777 -0.0211319 -0.0226697 -0.965016 -0.26121 0.00884586 -0.980768 -0.194975 -0.00748611 -0.797504 -0.603268 0 -0.785854 -0.618412 0.697963 -0.702389 -0.139633 0.697957 -0.702394 -0.139636 0.697958 -0.571139 -0.432035 0.697967 -0.571134 -0.432028 0.698115 -0.293207 0.653196 0.698105 -0.293214 0.653204 0.698102 -0.547117 0.461862 0.698105 -0.547115 0.461861 0.698103 -0.693145 0.17945 0.698111 -0.693137 0.179451 0.698108 0.326567 0.637181 0.698111 0.326567 0.637178 0.698112 0.0185011 0.71575 0.842205 0.0660951 0.53509 0.705434 -0.0714563 0.705165 0.458492 0.87914 -0.129992 0.694747 0.446871 0.56359 0.694739 0.446874 0.563597 0.705696 0.604144 0.370139 0.754934 0.580092 0.30589 0.624887 0.748584 0.221669 0.705023 0.691551 0.157158 0.703707 0.710296 -0.0166031 0.704399 0.681135 -0.199691 0.704399 0.6117 -0.360065 0.458501 0.696359 -0.552142 0.694745 -0.105208 -0.71152 0.694736 -0.105207 -0.711529 0.702915 0.188583 -0.685818 0.466758 0.325409 -0.822342 0.705016 0.358608 -0.611844 0.703699 0.498151 -0.506609 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706174 0.414427 0.57408 0.70617 0.41443 0.574084 0.70617 0.327476 0.627761 0.706183 0.327469 0.62775 0 0.441031 0.897492 0.0420206 0.4621 0.885832 0 0.504647 0.863326 0 0.585318 0.810804 0.0629307 0.603468 0.7949 0 0.545614 0.838037 0.706182 -0.414423 -0.574074 0.706175 -0.414427 -0.57408 0.706175 -0.327473 -0.627756 0.706183 -0.327469 -0.62775 0 0.621295 0.783577 0 -0.259664 -0.965699 -0.0323174 -0.146197 -0.988728 -0.0129592 -0.0587712 -0.998187 0.0156222 0.192248 -0.981222 -0.00369067 0.265132 -0.964205 0.00326088 0.505655 -0.86273 0.0251174 0.58592 -0.80998 -3.37662e-05 0.95961 -0.281333 4.07248e-05 0.848778 -0.528749 0.00666405 0.861767 -0.507261 -0.00509262 0.701121 -0.713024 -0.0225156 0.576408 0.816852 0.0133492 0.85787 0.513693 1.5442e-05 0.884554 0.466437 -1.91933e-07 0.955869 0.293794 -0.00405203 0.975129 0.221603 0.00867028 0.992981 0.117955 -0.00792546 0.999696 -0.0233678 0.00306966 0.992618 -0.121244 -0.0055816 0.951908 -0.306335 0.00101483 -0.241559 0.970386 0 0.600477 0.799642 -0.0140746 0.456059 0.889838 -0.000858438 -0.139084 0.99028 -0.0120157 0.0085665 0.999891 -0.016323 0.0258365 0.999533 0.00344474 0.215911 0.976407 -0.00894518 0.438733 0.898573 -0.0133972 -0.389255 0.921033 -0.0187234 -0.409443 0.912143 0.00146403 -0.547831 0.836588 -0.00147688 -0.670535 0.741876 -0.0193631 -0.763989 0.644939 -0.00546912 -0.798963 0.601355 0 -0.968083 0.25063 -0.0315528 -0.984019 0.175247 0.00301905 -0.914021 0.405656 0.994042 -0.0659059 -0.0868126 0.97185 0.14246 0.187651 0.658913 0.395128 0.640085 0.10809 0.438447 0.892234 0.558301 0.365896 0.744594 0.341045 0.414589 0.843685 0.237323 0.42093 0.875497 0.237619 0.490193 0.838599 0.153989 0.519017 0.840779 0.237619 0.529987 0.814034 0.237424 0.587377 0.773704 0.887898 0.202892 0.412882 0.739448 0.296908 0.604204 0.108171 0.615585 0.780611 0.34105 0.568413 0.748726 0.658913 0.454842 0.599127 0.558606 0.515373 0.649885 0.739453 0.407067 0.536196 0.971845 0.103917 0.21147 0.931703 0.152813 0.329512 0.931867 0.190572 0.308717 0.658689 0.324331 0.678925 0.658911 0.395128 0.640086 0.931867 0.190572 0.308717 0.931867 0.219373 0.288963 0.88809 0.289392 0.35714 0.994042 -0.0480701 -0.0978223 0.994042 -0.0480701 -0.0978222 0.994053 -0.0549563 -0.0940176 0.994978 -0.0525782 -0.0851737 0.994053 -0.0594182 -0.0912638 0.994042 -0.065906 -0.0868126 0 -0.61421 -0.789142 -0.063502 -0.584136 -0.809168 0 -0.555662 -0.831408 0 -0.462508 -0.886615 -0.126162 -0.426758 -0.895523 0 -0.494217 -0.869338 0.0684066 0.989325 -0.128675 0.0983725 0.953931 0.283441 0.73816 0.152747 -0.657106 0.933081 0.050589 -0.356092 0.885792 -0.0905598 -0.45516 0.902775 -0.0266163 -0.429288 0.900887 -0.000508714 -0.434054 0.893721 -0.0549137 -0.445249 0.982611 0.0452642 -0.180073 0.968947 0.0605931 -0.23973 0.959187 0.0732149 -0.27313 0.978164 0.0416065 -0.203628 0.993506 -0.0189023 -0.112202 0.993503 -0.0126211 -0.113106 0.955084 0.0649825 -0.289122 0.937215 0.0659119 -0.342467 0.81278 0.417533 -0.406269 0.759738 0.359304 -0.54194 0.532648 0.558264 -0.636103 0.600312 0.53324 -0.596054 0.364132 0.671004 -0.64588 0.456 0.64975 -0.608185 0.187405 0.753156 -0.630583 0.145511 -0.0647495 -0.987235 0.172306 0.138854 -0.975208 0.884954 -0.0853878 -0.457782 0.712671 -0.0192252 -0.701235 0.697721 0.00937464 -0.716308 0.461103 0.0648269 -0.884975 0.423352 0.104668 -0.899899 0.179683 0.139999 -0.973711 0.275263 0.48087 -0.832463 0.918217 0.034003 -0.394615 0.916084 0.0331339 -0.399615 0.771365 0.304008 -0.559084 0.722821 0.201176 -0.661103 0.503312 0.328116 -0.799385 0.48724 0.329474 -0.80873 0.353638 0.431921 -0.829689 0.177317 0.478953 -0.859746 0.301517 0.741495 -0.599393 0.275266 0.903964 -0.327228 0.876442 0.328519 0.352028 0.884047 0.314892 0.345405 0.725679 0.440863 0.528232 0.739821 0.425645 0.521048 0.546212 0.515415 0.660303 0.553284 0.510579 0.658168 0.333622 0.559629 0.758625 0.344985 0.554036 0.757647 0.105764 0.580249 0.807543 0.121183 0.575314 0.808906 0.145481 0.984082 0.102071 0.171344 0.979176 0.108887 0.34233 0.936077 0.0810586 0.242331 0.968086 0.0639133 0.521624 0.853144 0.00738983 0.443202 0.896391 -0.00744806 0.684256 0.725967 -0.0690327 0.62949 0.772606 -0.0825971 0.792148 0.595349 -0.134391 0.839075 0.531223 0.117286 0.858965 0.499023 0.114697 0.685632 0.68435 0.248142 0.721181 0.647861 0.245305 0.49342 0.791744 0.360107 0.546145 0.756595 0.359568 0.282719 0.849333 0.445762 0.35109 0.820892 0.450414 0.0859376 0.860906 0.501453 0.106808 0.856517 0.504946 0.147936 -0.25934 -0.954389 0.205582 -0.218549 -0.953925 0.341467 -0.214565 -0.915075 0.424997 -0.192406 -0.88451 0.484347 -0.216618 -0.847635 0.687666 -0.192442 -0.700058 0.647368 -0.154102 -0.746436 0.870205 -0.218373 -0.441653 0.850011 -0.161596 -0.501366 0.0290091 0.191279 -0.981107 0.135835 0.57113 -0.809543 -0.181674 0.539288 -0.822291 0.289906 0.793076 -0.53571 0.0131283 0.804132 -0.594305 0.143536 0.952111 -0.269967 0.324409 0.9022 -0.284242 0.20941 0.926866 -0.311554 0.48962 0.80773 -0.328397 0.398057 0.844474 -0.35835 0.641639 0.677178 -0.36018 0.575705 0.718182 -0.390868 0.805189 0.464062 -0.369212 0.849348 0.468184 -0.243745 0.891417 0.396579 -0.219317 0.946585 0.32173 -0.0216187 0.938297 0.345212 -0.0206531 0.97139 0.186849 0.146589 0.963016 0.2165 0.160397 0.146449 -0.77511 -0.614619 0.824719 -0.519364 0.223831 0.651393 -0.565922 -0.50539 0.942263 -0.331043 -0.0505076 0.971801 -0.228566 -0.0579663 0.978817 -0.200216 -0.0428006 0.98931 -0.127934 -0.0699866 0.993672 -0.0911956 -0.0655665 0.851107 -0.333788 -0.405219 0.873455 -0.374496 -0.311173 0.889415 -0.372252 -0.265274 0.901407 -0.375453 -0.215639 0.895299 -0.384928 -0.22421 0.918227 -0.365205 -0.153247 0.741741 -0.66905 0.0468308 0.782192 -0.619996 0.0614871 0.708899 -0.689511 -0.148451 0.911966 -0.378299 -0.158772 0.938587 -0.329849 -0.101261 0.786964 -0.573284 0.228107 0.849349 -0.427718 0.309296 0.792189 -0.386864 0.471988 0.856724 -0.137834 0.497018 0.843569 -0.117735 0.523955 0.884012 0.160432 0.439073 0.877481 0.173431 0.447156 0.921868 -0.373814 -0.102088 0.959988 -0.267598 -0.0825427 0.891437 -0.373748 0.256226 0.944652 -0.175743 0.277034 0.941308 -0.161831 0.296225 0.970892 0.0341928 0.237065 0.965072 0.0593254 0.255179 0.0704104 -0.553306 0.829997 0.218142 -0.666683 0.712705 0.12813 -0.400465 0.90731 0.235926 -0.344729 0.908571 0.12275 -0.251614 0.960012 0.153997 0.42909 0.890037 0.0814421 0.210795 0.974132 0.241034 0.0468047 0.969388 0.132206 -0.00296838 0.991218 0.0950309 -0.14725 0.984524 0.108061 0.596381 0.795394 0.222496 0.449396 0.865181 0.333938 0.431119 0.838226 0.30752 -0.942424 0.131413 0.0132439 -0.995679 0.0919115 0.118471 -0.913045 0.390273 0.217944 -0.883021 0.415661 0.0215325 -0.800788 0.598561 0.197915 -0.675209 0.710579 0.092651 -0.995259 -0.029581 0.0301407 -0.963856 -0.264713 0.178757 -0.933265 -0.311548 0.111634 -0.768479 -0.630062 0.341433 -0.72184 -0.601973 0.692776 -0.552399 -0.463591 0.714411 -0.627632 -0.309346 0.412911 -0.8448 -0.34032 0.487263 -0.870618 -0.0678177 0.353582 -0.935293 0.0143696 0.447569 -0.849559 0.279162 0.377671 -0.862575 0.336643 0.48003 -0.681764 0.552059 0.41212 -0.672947 0.614247 0.513931 -0.40612 0.755607 0.454274 -0.379297 0.806082 0.542569 -0.0408947 0.839015 0.499063 -0.0110219 0.866495 0.5532 0.3568 0.752771 0.546585 0.362068 0.755084 0.344669 0.424629 0.837194 0.287818 0.0417597 0.956774 0.346277 0.00961429 0.938083 0.253016 -0.345369 0.903716 0.332854 -0.380164 0.862951 0.223293 -0.666463 0.711313 0.313051 -0.687303 0.655449 0.200949 -0.885227 0.419515 0.291664 -0.884764 0.363489 0.187467 -0.979818 0.0693818 0.26929 -0.962642 0.0283415 0.179711 -0.933155 -0.311328 0.463501 -0.831057 -0.307426 0.425023 -0.704442 -0.568435 0.484357 -0.660628 -0.573558 0.870903 -0.333058 -0.361387 0.892969 -0.354393 -0.277511 0.690169 -0.641418 -0.335036 0.744778 -0.656095 -0.121837 0.503294 -0.861678 -0.064858 0.593146 -0.784004 0.183073 0.545205 -0.804162 0.236802 0.633557 -0.647944 0.422818 0.588802 -0.647704 0.48352 0.677988 -0.413443 0.60778 0.639891 -0.394222 0.659643 0.718479 -0.0914958 0.689505 0.691091 -0.0658317 0.719763 0.739777 0.267069 0.617579 0.726917 0.281937 0.626182 0.939621 -0.210193 -0.270058 0.939565 -0.150995 -0.307274 0.938421 -0.137169 -0.317098 0.939692 -0.134442 -0.314491 0.939392 -0.133804 -0.315657 0.939414 -0.13384 -0.315575 0.939897 -0.133533 -0.314266 0.939967 -0.133263 -0.314172 0.939946 -0.133328 -0.314205 0.939759 -0.133618 -0.314643 0.939562 -0.133832 -0.315137 0.939619 -0.22164 -0.260751 0.939838 -0.221254 -0.260291 0.940952 -0.217509 -0.259422 0.939692 -0.220866 -0.261147 0.939969 -0.221127 -0.259924 0.939975 -0.22113 -0.2599 0.939693 -0.220496 -0.261455 0.939471 -0.221926 -0.26104 0.93945 -0.222001 -0.261054 0.939566 -0.207019 -0.272689 0.94337 -0.201975 -0.263171 0.936007 -0.192045 -0.294973 0.939622 -0.190156 -0.28452 0.93966 -0.172643 -0.295352 0.937285 -0.172266 -0.30302 0.94337 -0.144746 -0.298499 0.939621 -0.14722 -0.308931 0.939693 -0.134935 -0.314278 0.149351 -0.607321 -0.780292 0.488788 -0.535838 -0.688451 0.346112 -0.403607 -0.846941 0.655062 -0.325045 -0.682085 0.850961 -0.225951 -0.474142 0.850961 -0.225951 -0.474143 0.850961 -0.259577 -0.456602 0.850963 -0.259576 -0.456599 0.850963 -0.291848 -0.436677 0.850963 -0.291848 -0.436677 0.850963 -0.322599 -0.414478 0.850963 -0.322599 -0.414478 0.655064 -0.464081 -0.596255 0.573434 -0.497254 -0.651085 0.573324 -0.45527 -0.681197 0.573326 -0.45527 -0.681195 0.573326 -0.404925 -0.712273 0.573327 -0.404925 -0.712272 0.573439 -0.359191 -0.736308 0.488783 -0.375305 -0.787552 0.346078 -0.576255 -0.740379 0.202133 -0.596949 -0.776398 0.202095 -0.544197 -0.814252 0.20209 -0.544197 -0.814254 0.20209 -0.48402 -0.851402 0.202093 -0.48402 -0.851401 0.202131 -0.426539 -0.881594 0.149338 -0.425371 -0.892613 -0.707099 0.260015 0.657574 -0.671176 0.313208 0.671881 -0.706468 0.297429 0.642214 -0.706468 0.371766 0.60224 -0.706468 0.371766 0.60224 -0.706519 0.4394 0.554759 -0.672822 0.460783 0.578782 -0.7071 0.471303 0.527146 -0.70647 -0.297429 -0.642213 -0.706468 -0.297429 -0.642214 -0.706468 -0.371766 -0.60224 -0.706468 -0.371766 -0.60224 -0.706468 -0.440816 -0.553701 -0.706476 -0.44081 -0.553695 0 0.99564 -0.0932825 0.0265352 0.962534 -0.269859 0.0347834 0.967484 -0.250529 -2.25158e-05 0.660588 -0.750748 -2.37594e-05 0.752833 -0.658212 0.0119364 0.790224 -0.612702 -0.00013064 0.839186 -0.543844 0.000178027 0.906846 -0.421462 0.0156649 0.556312 -0.830826 -0.0106422 0.618893 -0.785403 0.00969856 0.401734 -0.915705 6.5776e-06 0.429374 -0.903127 -2.8041e-05 0.170427 -0.98537 -0.0116959 0.198547 -0.980022 0.00783407 -0.0516362 -0.998635 1.12265e-05 -0.0236695 -0.99972 -2.74208e-05 -0.264403 -0.964412 -0.0108591 -0.290996 -0.956663 0.0165423 -0.608087 -0.793698 0 -0.629527 -0.776979 -0.696409 -0.43645 -0.569672 -0.696407 -0.436451 -0.569673 -0.696405 -0.118552 -0.70779 -0.332779 -0.249334 -0.909445 -0.705276 -0.0167801 -0.708735 -0.704469 0.140926 -0.695603 -0.524005 0.269414 -0.807982 -0.696401 0.691009 -0.193734 -0.6964 0.691009 -0.193734 -0.703498 0.56165 -0.435476 -0.530103 0.613943 -0.584864 -0.705274 0.43878 -0.556831 -0.704464 0.304744 -0.640985 0 -0.987206 -0.15945 -0.03422 -0.967233 -0.251573 0 -0.997871 -0.0652243 0.700682 -0.704346 -0.113763 0.700696 -0.704333 -0.113756 0.994042 -0.100482 -0.0422291 0.971851 0.217196 0.0912796 0.658909 0.662235 0.356767 0.108091 0.825823 0.553474 0.558294 0.689176 0.461892 0.341054 0.780885 0.523356 0.237323 0.802285 0.547738 0.237619 0.843819 0.481151 0.153992 0.869871 0.468627 0.237614 0.865999 0.439984 0.237419 0.895537 0.37636 0.887899 0.382149 0.25612 0.739446 0.559233 0.374803 0.108166 0.923419 0.368237 0.341043 0.866626 0.36421 0.658909 0.693471 0.291439 0.558613 0.771263 0.30513 0.739449 0.620632 0.260828 0.971845 0.195728 0.131178 0.931702 0.297098 0.20896 0.931866 0.319401 0.172071 0.658688 0.620342 0.425801 0.65891 0.662235 0.356767 0.931866 0.319401 0.172071 0.931866 0.334466 0.140563 0.888088 0.429195 0.164598 0.994042 -0.0905411 -0.0606814 0.994042 -0.0905407 -0.0606811 0.994053 -0.094602 -0.0539431 0.994978 -0.0881208 -0.0474734 0.994053 -0.0970882 -0.0493273 0.994042 -0.100481 -0.0422283 0 -0.926493 -0.376312 -0.063503 -0.910461 -0.408691 0 -0.896922 -0.44219 0 -0.862674 -0.50576 -0.0635019 -0.842148 -0.535494 0 -0.823928 -0.566694 0.0983621 0.967844 -0.231523 0.738159 -0.196268 -0.645446 0.933081 -0.134233 -0.333679 0.885794 -0.306011 -0.348894 0.902775 -0.237694 -0.358467 0.900887 -0.217468 -0.375647 0.893721 -0.270185 -0.358139 0.982611 -0.0508366 -0.178579 0.968947 -0.0673903 -0.237909 0.959187 -0.0731598 -0.273146 0.978164 -0.0657827 -0.19715 0.993506 -0.0724714 -0.0877185 0.993503 -0.0674821 -0.0916434 0.955084 -0.0882855 -0.282879 0.937215 -0.114154 -0.329542 0.812781 0.158458 -0.560605 0.759739 0.0401931 -0.648985 0.532645 0.165418 -0.830015 0.600313 0.163771 -0.782818 0.364123 0.258169 -0.894854 0.456007 0.258609 -0.851575 0.187414 0.336964 -0.922676 0.145516 -0.549694 -0.822594 0.17231 -0.367354 -0.913981 0.884955 -0.302839 -0.353757 0.712668 -0.367269 -0.597677 0.697719 -0.350037 -0.62503 0.461104 -0.386347 -0.798823 0.423351 -0.359305 -0.83167 0.179693 -0.365613 -0.913257 0.275272 0.000210876 -0.961366 0.918218 -0.167858 -0.358748 0.916084 -0.171111 -0.362644 0.771365 -0.0162612 -0.636185 0.722821 -0.156328 -0.673121 0.503313 -0.115536 -0.856345 0.487237 -0.119033 -0.865119 0.35364 -0.0407944 -0.934492 0.177317 -0.0150922 -0.984038 0.301515 0.342459 -0.889837 0.275276 0.619236 -0.73537 0.144757 0.737438 -0.65972 0.0773229 0.807335 -0.585005 0.876444 0.460518 0.140605 0.884046 0.445409 0.141683 0.725677 0.645917 0.237031 0.739819 0.629146 0.238419 0.546203 0.776519 0.314133 0.553285 0.771257 0.314703 0.333632 0.863961 0.377174 0.344992 0.858631 0.379123 0.105764 0.906281 0.409229 0.121177 0.90269 0.412876 0.145479 0.903278 -0.403639 0.171323 0.902438 -0.39529 0.34232 0.851199 -0.397841 0.24233 0.870345 -0.428691 0.521634 0.742533 -0.42017 0.4432 0.772572 -0.45465 0.684261 0.594183 -0.422769 0.629486 0.627796 -0.457841 0.792147 0.448389 -0.414065 0.839074 0.518697 -0.164038 0.858966 0.489515 -0.150179 0.685627 0.716741 -0.127275 0.721184 0.683714 -0.111485 0.493427 0.865721 -0.0840034 0.546143 0.835017 -0.0668992 0.282728 0.958422 -0.0386222 0.351088 0.936121 -0.0203761 0.085931 0.996294 0.00381856 0.106799 0.99424 0.00903678 0.147948 -0.701785 -0.696857 0.205586 -0.66623 -0.716848 0.341455 -0.643359 -0.685199 0.424999 -0.60888 -0.669806 0.484352 -0.611411 -0.625763 0.687663 -0.51669 -0.51005 0.647362 -0.506674 -0.569389 0.870207 -0.409941 -0.273293 0.850013 -0.390626 -0.353397 0.0290058 -0.3249 -0.945303 0.135838 0.089841 -0.986649 -0.181681 0.0558905 -0.981768 0.289904 0.418969 -0.860477 0.0131347 0.399248 -0.916749 0.14354 0.689567 -0.709855 0.324412 0.639206 -0.697261 0.209396 0.646912 -0.733252 0.489612 0.535315 -0.688271 0.398065 0.552157 -0.732576 0.641638 0.406363 -0.650514 0.575714 0.426528 -0.697587 0.805189 0.217286 -0.551776 0.849347 0.283585 -0.445185 0.891415 0.23379 -0.388229 0.946585 0.267816 -0.179587 0.938298 0.288635 -0.190491 0.971391 0.235108 0.033525 0.963017 0.26769 0.0306567 0.148806 -0.956492 -0.250958 0.824717 -0.337867 0.453528 0.651389 -0.742803 -0.154716 0.942264 -0.311943 0.121776 0.9718 -0.22693 0.0640826 0.978817 -0.194791 0.0630414 0.98931 -0.145788 0.003358 0.993672 -0.111761 -0.0111836 0.851108 -0.49168 -0.184027 0.873459 -0.479905 -0.0822233 0.889399 -0.455044 -0.0436457 0.901403 -0.43298 0.000978161 0.895298 -0.445464 -0.00170642 0.918225 -0.392904 0.0498856 0.741735 -0.556005 0.375084 0.782191 -0.50619 0.363248 0.708894 -0.671366 0.216188 0.911968 -0.406998 0.0516475 0.938588 -0.336286 0.0772283 0.786963 -0.382424 0.484191 0.849347 -0.215769 0.481719 0.792188 -0.0990411 0.602187 0.856726 0.129138 0.499344 0.84357 0.160018 0.512625 0.884009 0.358477 0.300036 0.877479 0.373775 0.300537 0.921868 -0.374777 0.0984954 0.959988 -0.273018 0.0623146 0.89144 -0.195562 0.408767 0.944652 -0.0136828 0.327788 0.941308 0.00796189 0.337454 0.970891 0.148146 0.188208 0.965073 0.178964 0.191328 0.0661974 -0.0762833 0.994886 0.226444 -0.221827 0.948428 0.146323 0.16274 0.975759 0.165353 0.167411 0.971922 0.092662 0.356571 0.929662 0.146644 0.542696 0.827029 0.0760558 0.573732 0.815504 0.10598 0.845444 0.523444 0.133547 0.836948 0.530739 0.33393 0.792478 0.510363 0.30611 -0.949228 -0.0725416 0.276858 -0.739048 0.614132 -0.207845 -0.782944 0.586344 0.216176 -0.556893 0.801959 0.0427269 -0.477464 0.877612 0.123737 -0.269233 0.955093 0.087987 -0.885582 0.456074 0.0256148 -0.971273 0.236586 0.152051 -0.969357 0.192947 0.145459 -0.976041 -0.161823 0.341435 -0.926117 -0.160402 0.692781 -0.710184 -0.125271 0.714415 -0.698215 0.0459148 0.412913 -0.901777 0.127676 0.487263 -0.78789 0.37657 0.353576 -0.802807 0.480089 0.447567 -0.596159 0.666542 0.377666 -0.57869 0.722832 0.480029 -0.314394 0.81898 0.412113 -0.275661 0.868432 0.513923 0.0260941 0.85744 0.454265 0.0745614 0.887741 0.542564 0.384093 0.747059 0.49906 0.423702 0.75592 0.553201 0.685383 0.473517 0.546594 0.691096 0.472886 0.344675 0.786333 0.512717 0.287825 0.514552 0.807709 0.346295 0.47736 0.807593 0.253023 0.152761 0.955324 0.332867 0.10224 0.937415 0.223307 -0.221522 0.949243 0.313045 -0.267492 0.911291 0.200939 -0.55687 0.805928 0.291658 -0.584483 0.757176 0.187457 -0.813855 0.55 0.269304 -0.819502 0.505857 0.179732 -0.963797 0.196956 0.463499 -0.873431 0.149289 0.425023 -0.894282 -0.140056 0.484351 -0.858904 -0.166397 0.870894 -0.469143 -0.146451 0.892965 -0.445678 -0.0631313 0.690173 -0.722999 0.0305593 0.744781 -0.629112 0.22253 0.503308 -0.778659 0.374661 0.593155 -0.587429 0.550541 0.545213 -0.578022 0.607153 0.633561 -0.349727 0.690138 0.588805 -0.319167 0.742591 0.677988 -0.0541638 0.733075 0.639891 -0.0115857 0.768379 0.718475 0.26552 0.642879 0.691092 0.302869 0.656249 0.739781 0.540073 0.401306 0.726912 0.55726 0.401322 0.939622 -0.317058 -0.12878 0.939565 -0.284405 -0.19061 0.938424 -0.277331 -0.206029 0.939691 -0.273678 -0.205137 0.939387 -0.273708 -0.206484 0.939415 -0.273696 -0.206374 0.939896 -0.272781 -0.205393 0.939967 -0.272494 -0.205448 0.939947 -0.272568 -0.205444 0.939758 -0.273041 -0.205681 0.939563 -0.27347 -0.205999 0.939619 -0.322322 -0.115 0.939839 -0.321753 -0.114793 0.940963 -0.318045 -0.115909 0.939693 -0.321847 -0.115723 0.939962 -0.321473 -0.114569 0.939976 -0.321452 -0.114518 0.939692 -0.321686 -0.11618 0.93947 -0.322718 -0.115104 0.939451 -0.322782 -0.115081 0.939565 -0.315631 -0.132647 0.94337 -0.306502 -0.126925 0.936006 -0.313804 -0.159434 0.939623 -0.306938 -0.151322 0.939661 -0.297188 -0.16946 0.937285 -0.300696 -0.176289 0.94337 -0.274602 -0.186134 0.939621 -0.281961 -0.193932 0.939693 -0.273995 -0.204706 0.149344 -0.916103 -0.372091 0.488784 -0.808277 -0.328296 0.346098 -0.773008 -0.531672 0.655054 -0.622545 -0.428185 0.850963 -0.432748 -0.297642 0.850962 -0.432749 -0.297644 0.850962 -0.453101 -0.265639 0.850959 -0.453104 -0.265641 0.850959 -0.471091 -0.232253 0.850966 -0.471083 -0.232246 0.850966 -0.486613 -0.197647 0.850963 -0.486617 -0.19765 0.65506 -0.700036 -0.284333 0.573439 -0.756174 -0.315227 0.573328 -0.734871 -0.362299 0.573327 -0.734871 -0.362299 0.573327 -0.706813 -0.414382 0.573325 -0.706813 -0.414383 0.573437 -0.679224 -0.458067 0.488791 -0.718796 -0.494385 0.346078 -0.869241 -0.353058 0.202121 -0.905175 -0.373906 0.202083 -0.878416 -0.433068 0.202095 -0.878414 -0.433066 0.202095 -0.844874 -0.495324 0.202091 -0.844875 -0.495324 0.20213 -0.81019 -0.550214 0.14935 -0.814687 -0.560338 -0.707099 0.553964 0.439471 -0.671172 0.607189 0.425264 -0.70647 0.578687 0.407458 -0.70647 0.623077 0.335671 -0.706455 0.62309 0.335679 -0.706506 0.657925 0.26074 -0.672824 0.688439 0.270849 -0.707107 0.671729 0.220861 -0.706481 -0.578678 -0.407452 -0.706481 -0.578678 -0.407452 -0.706482 -0.623067 -0.335666 -0.706478 -0.62307 -0.335667 -0.706479 -0.658598 -0.259108 -0.706477 -0.658599 -0.259108 -0.698075 0.614301 0.367867 -0.69807 0.614305 0.367868 -0.698069 0.393862 0.597973 -0.618516 0.454064 0.641298 -0.706908 0.270003 0.653742 -0.698072 0.0954033 0.709643 -0.698069 0.095405 0.709646 -0.698063 -0.221948 0.68077 -0.698071 -0.221948 0.680761 -0.698076 -0.495335 0.517043 -0.698076 -0.713077 -0.0649005 -0.698065 -0.713087 -0.0648977 -0.700599 -0.676343 0.227423 -0.634906 -0.723597 0.270742 -0.706903 -0.603448 0.368969 -0.698069 -0.495338 0.517049 -0.701596 0.626199 0.340055 -0.701598 0.626197 0.340055 -0.701595 0.704974 0.103805 -0.7016 0.70497 0.103806 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.857933 0.513761 0 -0.985881 -0.167446 0.0323297 -0.995363 -0.0905928 0.0047742 -0.999369 0.0352099 -0.0109507 -0.95894 0.283397 0.00691185 -0.947827 0.31871 -0.00189274 -0.853158 0.52165 -0.023332 -0.756643 0.653412 0.0208225 -0.691633 0.721949 0.00129687 -0.560639 0.82806 -0.00323836 -0.424832 0.905267 0.0314897 -0.309817 0.950274 0.00698285 -0.225754 0.974159 -0.000754076 0.372782 0.927919 0.00320226 0.201825 0.979416 0.0274204 0.133191 0.990711 0.00213113 -0.000719163 0.999997 -0.000711952 -0.104715 0.994502 0.00389594 0.861925 0.507021 -0.00331138 0.583945 0.811787 -2.12748e-05 0.577857 0.816138 -5.39862e-07 0.381735 0.924272 0 0.879459 0.475975 -0.000562012 0.878783 0.477221 0.000569032 0.989332 0.145676 0 0.989544 0.144232 0 -0.817651 -0.575714 0 -0.817651 -0.575714 0 -0.880372 -0.474284 0 -0.880372 -0.474284 0 -0.930572 -0.366109 0 -0.930572 -0.366109 0 0.930572 0.366109 0 0.930572 0.366109 0 0.880372 0.474283 0 0.880372 0.474283 0 0.817651 0.575715 0 0.817651 0.575715 -0.879238 -0.463046 -0.111931 -0.887086 -0.46008 -0.0374912 -0.954991 -0.28248 0.090536 -0.960102 -0.262579 0.0962069 -0.978434 -0.196371 0.0640734 -0.978976 -0.193729 0.0638376 -0.991397 -0.130889 7.16341e-05 -0.990797 -0.135326 0.0027125 -0.965171 0.185616 0.184367 -0.793205 -0.0767995 0.604093 -0.859466 0.162049 0.484827 -0.839105 0.165689 0.518121 -0.884191 0.373611 0.280394 -0.876482 0.381015 0.294289 -0.859292 -0.363474 0.359867 -0.938545 -0.331585 0.0958353 -0.933195 -0.349831 0.0822499 -0.821647 -0.284177 0.494106 -0.847484 -0.207075 0.488765 -0.891285 -0.182604 0.415052 -0.947044 0.00962794 0.320959 -0.938319 0.0111326 0.345592 -0.970911 0.15321 0.184007 -0.989047 0.0753144 0.126936 -0.807335 -0.558109 0.191637 -0.693239 -0.535785 0.48203 -0.770718 -0.324437 0.548393 -0.902132 -0.429975 0.0357591 -0.887849 -0.458121 -0.0430041 -0.74955 -0.661333 0.0285375 -0.710137 -0.703866 0.0167063 -0.276015 -0.78255 0.558061 -0.145874 -0.988854 0.0297954 -0.197809 -0.971706 -0.129072 -0.14794 -0.974677 -0.167687 -0.111696 0.575373 0.810228 -0.0948897 0.856969 0.506558 -0.105772 0.857952 0.502723 -0.0780616 -0.00825629 0.996914 -0.143539 0.187354 0.971748 -0.177902 0.198497 0.963821 -0.0972884 0.364191 0.926229 -0.110855 0.575213 0.810457 -0.0290722 -0.958877 0.282329 -0.134936 -0.756035 0.640471 0.129842 -0.782327 0.609184 -0.156051 -0.566022 0.809485 -0.216083 -0.528329 0.821083 -0.0505947 -0.428474 0.902137 -0.143385 -0.180781 0.973015 -0.273799 -0.243906 0.930346 -0.142479 -0.117257 0.982828 -0.354247 -0.785361 0.507658 -0.457131 -0.542564 0.704738 -0.363201 -0.583202 0.726609 -0.490855 -0.24869 0.834994 -0.397292 -0.280917 0.873639 -0.522594 0.0895825 0.847862 -0.442823 0.0741344 0.893539 -0.546588 0.430117 0.718499 -0.493399 0.431508 0.755221 -0.553373 0.702971 0.446777 -0.546241 0.705391 0.451712 -0.176377 -0.813081 0.554789 -0.302646 -0.524981 0.795487 -0.186332 -0.560464 0.806946 -0.325671 -0.195583 0.925033 -0.208473 -0.226895 0.951345 -0.343269 0.170888 0.92356 -0.24187 0.151602 0.958392 -0.35153 0.526642 0.773999 -0.282646 0.521995 0.804756 -0.345022 0.806373 0.480335 -0.33367 0.807624 0.486218 -0.879553 -0.462217 -0.112882 -0.763481 -0.632835 -0.128907 -0.693957 -0.713688 -0.0952565 -0.651398 -0.747745 -0.128676 -0.484428 -0.864001 -0.137231 -0.918283 -0.389814 0.0692924 -0.901024 -0.429081 0.0636074 -0.758729 -0.588323 0.279654 -0.805298 -0.540099 0.244516 -0.700525 -0.618107 0.356664 -0.63382 -0.767211 0.0982866 -0.461107 -0.87544 0.14486 -0.42565 -0.898633 -0.106215 -0.341517 -0.931105 -0.128103 -0.172214 -0.958484 0.227268 -0.179206 -0.956908 0.228501 -0.424079 -0.885579 0.189489 -0.486855 -0.77636 0.400296 -0.502648 -0.766891 0.399027 -0.601382 -0.5416 0.587375 -0.531848 -0.583775 0.613469 -0.64282 -0.292803 0.707848 -0.575092 -0.324778 0.750858 -0.685233 0.00140566 0.728323 -0.629212 -0.0119745 0.777142 -0.721679 0.306108 0.620869 -0.685619 0.310152 0.658584 -0.739934 0.558767 0.374537 -0.725677 0.566846 0.389972 -0.14615 -0.625148 -0.766701 -0.106527 0.875342 0.471623 -0.826272 0.213479 -0.52125 -0.651413 -0.518822 -0.553611 -0.992269 -0.0475993 -0.114618 -0.992328 -0.0842575 -0.0904797 -0.976262 -0.0443896 -0.211994 -0.978909 -0.0543446 -0.196937 -0.963217 -0.06268 -0.261314 -0.851017 -0.419869 -0.315404 -0.880972 -0.304971 -0.361775 -0.902082 -0.222864 -0.369566 -0.895846 -0.233347 -0.378166 -0.919311 -0.160246 -0.359428 -0.740532 0.0267667 -0.671487 -0.783613 0.0494702 -0.619276 -0.707956 -0.168881 -0.685768 -0.918518 -0.161213 -0.361019 -0.938742 -0.103156 -0.328821 -0.7859 0.211415 -0.58109 -0.847486 0.294228 -0.441811 -0.793259 0.462207 -0.396365 -0.856962 0.492992 -0.150252 -0.844211 0.520265 -0.128967 -0.884165 0.442603 0.149513 -0.877677 0.450623 0.163161 -0.945947 -0.097354 -0.309363 -0.960045 -0.0626745 -0.272739 -0.89135 0.246081 -0.38071 -0.944832 0.271866 -0.182706 -0.94185 0.291328 -0.167473 -0.970926 0.237895 0.0266222 -0.965173 0.256074 0.053542 -0.244564 0.714116 -0.655917 -0.169566 0.708097 -0.685453 -0.0807652 0.832306 -0.548401 -0.126152 0.894827 -0.428218 -0.225593 0.902982 -0.365693 -0.0935114 0.961226 -0.259424 -0.334009 0.848181 0.411129 -0.185741 0.882238 0.432615 0.00743806 0.999004 0.0439959 -0.309731 0.942996 0.121756 -0.104026 0.989544 -0.0999069 -0.333483 0.132332 -0.933422 0.0466933 0.070588 -0.996412 -0.150609 0.383191 -0.911308 -0.201218 0.398378 -0.894878 -0.0642506 0.548698 -0.833548 -0.110747 0.648295 -0.753292 -0.0768469 -0.0576783 -0.995373 -0.0754055 -0.293609 -0.952947 -0.190434 -0.332605 -0.923639 -0.0911586 -0.650212 -0.754264 -0.341495 -0.619246 -0.707047 -0.693998 -0.472138 -0.543556 -0.714754 -0.322931 -0.620356 -0.412188 -0.36353 -0.835432 -0.486902 -0.0927094 -0.868523 -0.354182 -0.00798847 -0.935142 -0.447651 0.256939 -0.856499 -0.378523 0.316042 -0.869964 -0.480141 0.534236 -0.695742 -0.41312 0.598155 -0.68669 -0.514078 0.744968 -0.425144 -0.455179 0.796799 -0.397396 -0.542683 0.837662 -0.0617878 -0.499645 0.865683 -0.0308022 -0.553292 0.761247 0.338188 -0.546682 0.763553 0.343693 -0.344665 0.847199 0.404301 -0.288246 0.957355 0.0196463 -0.346233 0.938048 -0.0137682 -0.253712 0.895326 -0.36609 -0.332831 0.853096 -0.40181 -0.224025 0.69538 -0.682832 -0.31303 0.63773 -0.703784 -0.201527 0.398317 -0.894836 -0.291644 0.340711 -0.893789 -0.187832 0.0459053 -0.981128 -0.269299 0.00369424 -0.96305 -0.179212 -0.335691 -0.924767 -0.463845 -0.325622 -0.823904 -0.425692 -0.58307 -0.691966 -0.484449 -0.589926 -0.645985 -0.875379 -0.359632 -0.323072 -0.889598 -0.286949 -0.355352 -0.689729 -0.352974 -0.632205 -0.745699 -0.135 -0.652463 -0.50266 -0.0885757 -0.859935 -0.593275 0.162173 -0.788496 -0.546275 0.217612 -0.808844 -0.63376 0.405535 -0.658703 -0.58999 0.467973 -0.657961 -0.678232 0.596768 -0.4288 -0.640943 0.649851 -0.408517 -0.718701 0.686772 -0.108687 -0.691732 0.717493 -0.0819103 -0.739908 0.623881 0.251612 -0.727052 0.632487 0.267124 -0.572883 -0.721585 -0.388741 -0.850726 -0.429137 -0.303492 -0.879514 -0.443195 -0.1733 -0.654669 -0.703434 -0.276747 -0.764993 -0.599325 -0.235788 -0.845144 -0.496164 -0.198878 -0.851112 -0.476672 -0.219983 -0.850695 -0.462777 -0.249312 -0.850698 -0.462772 -0.249311 -0.851115 -0.445931 -0.277035 -0.345826 -0.873155 -0.343518 -0.4884 -0.812036 -0.319473 -0.149209 -0.920155 -0.362011 -0.20191 -0.910122 -0.361816 -0.201871 -0.862247 -0.46452 -0.84435 -0.438091 -0.308463 -0.65468 -0.618067 -0.435186 -0.573004 -0.672702 -0.468123 -0.488416 -0.713491 -0.502374 -0.345802 -0.767208 -0.540197 -0.573006 -0.760984 -0.304249 -0.572885 -0.721584 -0.38874 -0.201875 -0.862246 -0.46452 -0.201915 -0.802816 -0.560997 -0.149212 -0.808497 -0.569269 -0.340892 0.768675 0.541231 -0.994035 -0.0960147 -0.0517262 -0.994036 -0.0890336 -0.0629659 -0.994251 -0.087553 -0.0616467 -0.991754 -0.119356 -0.0466708 -0.996677 -0.0739602 -0.0341377 -0.658681 0.662411 0.356862 -0.93179 0.319572 0.172164 -0.994046 -0.100678 -0.0416809 -0.993745 0.103924 0.040886 -0.971837 0.219293 0.0862751 -0.994056 -0.0924796 -0.0574493 -0.994035 -0.0960157 -0.0517266 -0.931789 0.319575 0.172165 -0.931638 0.340494 0.126946 -0.55847 0.670122 0.488924 -0.739292 0.550594 0.387678 -0.93179 0.296804 0.208983 -0.888074 0.36908 0.274052 -0.971843 0.192663 0.135656 -0.237287 0.855228 0.460738 -0.237287 0.794298 0.559272 -0.108127 0.80437 0.584207 -0.887835 0.428215 0.168469 -0.739293 0.626633 0.246531 -0.65847 0.702765 0.26933 -0.558115 0.772155 0.303784 -0.340889 0.874834 0.34418 -0.65868 0.615219 0.433181 -0.658681 0.662412 0.356862 -0.237293 0.855227 0.460738 -0.237197 0.90643 0.349461 -0.108042 0.925125 0.363966 -0.939507 -0.319009 -0.124739 -0.939611 -0.325909 -0.104472 -0.939485 -0.326281 -0.104447 -0.939569 -0.325983 -0.104616 -0.939689 -0.32535 -0.105504 -0.939849 -0.325296 -0.104243 -0.939868 -0.32526 -0.104186 -0.939725 -0.325612 -0.104375 -0.939514 -0.279644 -0.197768 -0.940465 -0.26562 -0.212066 -0.939696 -0.266648 -0.214171 -0.939902 -0.265818 -0.2143 -0.93969 -0.266951 -0.213824 -0.939537 -0.26669 -0.214819 -0.939489 -0.266704 -0.215009 -0.939514 -0.266686 -0.214925 -0.93975 -0.266252 -0.21443 -0.939507 -0.27966 -0.19778 -0.93951 -0.279652 -0.197775 -0.939693 -0.290526 -0.180478 -0.939694 -0.290519 -0.180485 -0.939498 -0.301576 -0.162469 -0.939498 -0.301575 -0.162468 -0.939694 -0.310533 -0.143333 -0.939693 -0.310545 -0.143316 -0.93951 -0.319001 -0.124735 -0.939516 -0.318985 -0.124731 -0.939699 -0.325402 -0.105263 0.697588 -0.692482 0.183956 0.697603 -0.692466 0.183957 0.697599 -0.538633 0.472472 0.638172 -0.590317 0.494229 0.707017 -0.424325 0.565752 0.697593 -0.272621 0.662602 0.697588 -0.272625 0.662606 0.697588 0.0501692 0.71474 0.697589 0.0501692 0.71474 0.707008 0.224674 0.670567 0.685364 0.290246 0.667857 0.825864 0.336824 0.452215 0.701059 0.613876 0.362866 0.60012 0.669136 0.438308 0.706722 0.510822 0.489494 0.699414 0.375706 0.608001 0.698072 0.655479 0.288169 0.698062 0.655487 0.288176 0.704261 0.708511 0.0450436 0.7716 0.636108 -0.00059903 0.684052 0.720011 -0.116866 0.706897 0.689441 -0.158012 0.698065 0.633991 -0.332806 0.698062 0.633994 -0.332807 0.698067 0.426808 -0.574925 0.698063 0.426811 -0.574927 0.698065 0.135089 -0.703176 0.698061 -0.465538 -0.544046 0.698073 -0.465533 -0.544034 0.700605 -0.205859 -0.68321 0.627456 -0.19942 -0.752682 0.7069 -0.0482332 -0.705667 0.69807 0.135087 -0.703172 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706191 0.645929 0.289948 0.706174 0.645945 0.289954 0.706174 0.597479 0.379917 0.706182 0.597473 0.379913 0 0.83069 0.556736 0.0420211 0.843106 0.536103 0 0.8687 0.495338 0 0.912302 0.409519 0.0629332 0.920069 0.386669 0 0.891533 0.452956 0.706191 -0.64593 -0.289947 0.706174 -0.645945 -0.289955 0.706174 -0.597479 -0.379917 0.70617 -0.597482 -0.379919 0 0.915438 0.40246 0 -0.707722 -0.706491 -0.0219199 -0.650001 -0.759617 -0.00326179 -0.550374 -0.834912 0.00738514 -0.323609 -0.946162 -0.00467347 -0.288497 -0.957469 0.00127731 -0.068192 -0.997671 0.0165181 0.103355 -0.994507 -0.0121504 0.188647 -0.98197 0.0072259 0.469904 -0.882688 -0.0216174 0.595935 -0.802742 -0.00297507 0.670975 -0.741474 6.69319e-06 0.974698 -0.223527 3.35103e-05 0.919327 -0.393494 -0.0189455 0.885262 -0.464707 -0.00146821 0.815197 -0.579181 0.000306247 0.756948 -0.653476 -0.00626355 0.907998 0.418928 0.00534472 0.999849 0.0165188 1.80154e-05 1 -0.000941703 -5.52825e-07 0.974728 -0.223396 0 0.85164 0.524128 0.00561809 0.860839 0.508847 -0.000788392 0.722019 0.691873 0.00753381 0.579358 0.815038 -0.0100093 0.525645 0.850645 0.000485222 0.366173 0.930546 -0.000208253 0.317693 0.948194 0.00316849 0.179815 0.983695 -0.0212952 0.0700041 0.997319 0.000796322 -0.0686567 0.99764 -0.000778235 -0.2564 0.96657 -0.0220045 -0.380403 0.924559 0.00200263 -0.473522 0.88078 -0.000195703 -0.60001 0.799993 0.00580453 -0.766739 0.641933 -0.00515296 -0.748477 0.663141 0 -0.966478 0.256749 -0.00804725 -0.971015 0.238882 0.00044817 -0.885356 0.464913 0 0.86733 -0.497734 0.0376704 0.803995 -0.593441 0.0154232 0.749796 -0.661489 -0.028332 0.496501 -0.867574 -1.42312e-05 -0.477206 -0.878792 0.0268123 -0.549251 -0.835227 -7.05572e-05 -0.444246 -0.895905 0.000101351 -0.248023 -0.968754 1.1131e-05 -0.24774 -0.968827 5.42575e-06 0.0111627 -0.999938 0.0341687 -0.0904154 -0.995318 -0.0536313 0.254787 -0.965509 -0.00712225 0.166174 -0.986071 0.00710009 0.559847 -0.828565 0 -0.993705 0.112029 0.0329096 -0.987219 0.155934 -0.0251276 -0.954181 -0.298174 0.00777303 -0.970381 -0.241452 -5.20502e-06 -0.903909 -0.427725 8.10155e-06 -0.844758 -0.535148 0.0188723 -0.876926 -0.480254 -0.0358099 -0.687954 -0.72487 0.0352498 -0.775813 -0.629977 -2.81077e-05 -0.634959 -0.772546 0 -0.907409 0.420248 0 -0.907409 0.420248 0 -0.850928 0.525282 0 -0.850928 0.525282 0 -0.782345 0.622845 0 -0.782345 0.622845 0 0.782345 -0.622845 0 0.782345 -0.622845 0 0.850928 -0.525283 0 0.850928 -0.525283 0 0.907409 -0.420249 0 0.907409 -0.420249 -0.879241 -0.328462 0.345034 -0.887084 -0.262499 0.379705 -0.954989 -0.0628367 0.28991 -0.960101 -0.0479717 0.275507 -0.978435 -0.0426954 0.202092 -0.978976 -0.0415814 0.199692 -0.991396 -0.0653831 0.113393 -0.990797 -0.0653145 0.118554 -0.965171 0.252476 -0.0685674 -0.793209 0.484755 0.368554 -0.859467 0.500896 0.102075 -0.839105 0.531551 0.115571 -0.884191 0.429634 -0.183359 -0.876485 0.445363 -0.182824 -0.859291 0.129918 0.494712 -0.938545 -0.0827973 0.335079 -0.933194 -0.10369 0.34409 -0.821647 0.285818 0.493157 -0.847486 0.319745 0.423711 -0.891282 0.268149 0.365668 -0.947044 0.282774 0.152143 -0.938319 0.304858 0.163156 -0.970911 0.235959 -0.0406787 -0.989049 0.147577 -0.00175065 -0.807334 -0.11309 0.579157 -0.693242 0.149552 0.705018 -0.770718 0.312702 0.555167 -0.902135 -0.184031 0.390237 -0.887851 -0.266315 0.375229 -0.749522 -0.305976 0.587023 -0.710138 -0.337464 0.617917 -0.0480144 0.280182 0.958745 -0.183253 0.48312 0.856162 -0.0895018 0.469837 0.878204 -0.276011 0.0920257 0.956739 -0.162562 -0.357954 0.91948 -0.244217 0.0443323 0.968707 -0.0759104 0.116548 0.99028 -0.0762302 -0.182497 0.980247 -0.129185 -0.561285 0.817478 -0.195883 -0.597823 0.777327 -0.149367 -0.710864 0.687286 -0.105783 0.864345 -0.491648 -0.0427642 0.952839 0.300447 -0.117369 0.992702 0.0276829 -0.222626 0.971379 -0.082834 -0.040521 0.978904 -0.200263 -0.201102 0.834376 -0.5132 -0.0855156 0.640838 0.762898 -0.110702 0.691092 0.714239 -0.210366 0.737562 0.641677 -0.00618524 0.840195 0.542249 -0.24149 0.938789 0.245677 -0.354223 0.0469808 0.93398 -0.457113 0.339043 0.822252 -0.363187 0.337664 0.868376 -0.490845 0.598785 0.632872 -0.397295 0.616137 0.680098 -0.522597 0.779061 0.346347 -0.442815 0.810898 0.382568 -0.546587 0.837297 -0.0132454 -0.493392 0.869798 0.00391366 -0.55336 0.738413 -0.385407 -0.546232 0.743894 -0.385035 -0.176399 0.0739314 0.981538 -0.302656 0.426422 0.852387 -0.186324 0.418603 0.88885 -0.325664 0.703311 0.6319 -0.208473 0.71044 0.672171 -0.34326 0.885273 0.313791 -0.24188 0.905791 0.347903 -0.351527 0.933625 -0.0690864 -0.28265 0.957935 -0.0496854 -0.345029 0.819166 -0.458173 -0.33367 0.82489 -0.456313 -0.879551 -0.328864 0.343858 -0.763478 -0.42805 0.483605 -0.693959 -0.439333 0.570445 -0.651411 -0.485294 0.583227 -0.484424 -0.550836 0.679642 -0.918287 -0.134893 0.372228 -0.901026 -0.159451 0.403394 -0.758732 -0.0519688 0.649326 -0.805285 -0.0582855 0.590017 -0.700529 -0.000176547 0.713624 -0.633829 -0.298491 0.713557 -0.461117 -0.312274 0.830576 -0.425663 -0.541293 0.72513 -0.341502 -0.576496 0.742313 -0.233087 -0.265685 0.935458 -0.179206 -0.280572 0.942955 -0.424087 -0.278692 0.861674 -0.486863 -0.0415186 0.872491 -0.50267 -0.0378799 0.863648 -0.601396 0.237873 0.762718 -0.531855 0.239384 0.812296 -0.64283 0.466609 0.607492 -0.57509 0.487873 0.656698 -0.68523 0.631452 0.362945 -0.629214 0.667036 0.398939 -0.721679 0.690741 0.0453375 -0.685619 0.725426 0.060693 -0.739938 0.603737 -0.296637 -0.725678 0.621148 -0.295916 -0.146153 -0.976555 0.158048 -0.826269 -0.344679 -0.445507 -0.651422 -0.738847 0.172495 -0.992269 -0.123061 -0.0160868 -0.992328 -0.120485 0.0277294 -0.976264 -0.205782 -0.0675503 -0.97891 -0.197721 -0.0514018 -0.963213 -0.257656 -0.0763774 -0.851016 -0.483082 0.205922 -0.880899 -0.465912 0.0833253 -0.902138 -0.431368 0.00830595 -0.895771 -0.444321 0.013159 -0.919311 -0.391398 -0.0409321 -0.740526 -0.568148 -0.358929 -0.783609 -0.511578 -0.352485 -0.707952 -0.678334 -0.196636 -0.918519 -0.393256 -0.0408899 -0.938743 -0.336342 -0.0750713 -0.7859 -0.397529 -0.473637 -0.847487 -0.235503 -0.475715 -0.79326 -0.112159 -0.598464 -0.856962 0.116372 -0.502069 -0.84421 0.148445 -0.515047 -0.884167 0.35078 -0.308549 -0.877678 0.366612 -0.30867 -0.945947 -0.316596 -0.0703687 -0.960044 -0.267539 -0.0820898 -0.891345 -0.206665 -0.403477 -0.944831 -0.0222907 -0.326798 -0.94185 0.000625272 -0.336033 -0.970925 0.142004 -0.192715 -0.965172 0.17441 -0.194999 -0.115188 0.741947 -0.660489 -0.0771231 0.554256 -0.828765 -0.146468 0.521908 -0.840333 -0.0440725 0.162922 -0.985654 -0.0575956 0.156846 -0.985942 -0.0997427 -0.102668 -0.989702 -0.181851 -0.240556 -0.953448 -0.334021 0.780133 -0.528982 -0.10576 0.826826 -0.552426 -0.278912 0.830879 -0.481506 -0.0122833 -0.831775 -0.554976 -0.315832 -0.754966 -0.574697 -0.112718 -0.87619 -0.4686 -0.136046 -0.258323 -0.956431 -0.0636777 -0.448927 -0.891297 -0.202698 -0.57577 -0.792087 -0.248177 -0.554098 -0.794597 -0.108798 -0.63901 -0.761466 -0.0842378 -0.903248 -0.420769 -0.0329078 -0.970439 -0.239093 -0.190429 -0.966199 -0.173771 -0.0911517 -0.978317 0.185977 -0.341453 -0.921957 0.18277 -0.693987 -0.706812 0.13711 -0.714746 -0.698719 -0.0305079 -0.412193 -0.905269 -0.102881 -0.486908 -0.798514 -0.353973 -0.354192 -0.813848 -0.46065 -0.447655 -0.613278 -0.650765 -0.378529 -0.595389 -0.708681 -0.480144 -0.335413 -0.810531 -0.413122 -0.295614 -0.861361 -0.514076 0.00429774 -0.857734 -0.455181 0.0542396 -0.888745 -0.54269 0.365318 -0.756327 -0.499639 0.406175 -0.765103 -0.553281 0.673509 -0.490169 -0.546666 0.679434 -0.489413 -0.344667 0.773735 -0.531543 -0.288255 0.495692 -0.819267 -0.346229 0.457109 -0.819254 -0.253712 0.130619 -0.95842 -0.33284 0.0785642 -0.939705 -0.224027 -0.24366 -0.943632 -0.313032 -0.290631 -0.904182 -0.201528 -0.575794 -0.792369 -0.291637 -0.603688 -0.741963 -0.187822 -0.826726 -0.530327 -0.269306 -0.832177 -0.484722 -0.179219 -0.968717 -0.171665 -0.46386 -0.876326 -0.129951 -0.42571 -0.890787 0.158964 -0.484454 -0.854402 0.187886 -0.875373 -0.459611 0.149936 -0.889596 -0.451223 0.0708312 -0.689721 -0.724 -0.0104156 -0.745696 -0.632551 -0.209325 -0.502674 -0.789004 -0.353258 -0.593283 -0.601769 -0.534686 -0.546279 -0.59167 -0.592879 -0.63376 -0.367688 -0.680554 -0.589988 -0.335825 -0.734259 -0.678231 -0.0729677 -0.731217 -0.640943 -0.0288618 -0.767046 -0.718701 0.249261 -0.649106 -0.691733 0.28781 -0.662322 -0.739909 0.529842 -0.414491 -0.727053 0.547578 -0.414188 -0.572885 -0.697451 0.43054 -0.850724 -0.477402 0.219898 -0.879517 -0.371675 0.297166 -0.654682 -0.591379 0.470811 -0.764989 -0.503864 0.401139 -0.845142 -0.420318 0.330254 -0.851112 -0.428854 0.302807 -0.850695 -0.447299 0.27612 -0.850696 -0.447298 0.276119 -0.851113 -0.462883 0.24768 -0.345811 -0.734078 0.584418 -0.488399 -0.682691 0.543507 -0.149204 -0.773588 0.615873 -0.201925 -0.768401 0.607278 -0.201885 -0.833407 0.514466 -0.844346 -0.486188 0.225169 -0.654689 -0.685909 0.317665 -0.573005 -0.741756 0.348515 -0.488423 -0.791811 0.366713 -0.345761 -0.851442 0.39433 -0.573006 -0.64398 0.506906 -0.572885 -0.697451 0.43054 -0.201887 -0.833406 0.514466 -0.201929 -0.887243 0.414758 -0.149217 -0.89725 0.415543 -0.340905 0.853053 -0.395075 -0.994035 -0.0928046 0.0572887 -0.994036 -0.0990463 0.045622 -0.994251 -0.0971636 0.0449994 -0.991754 -0.100097 0.0800305 -0.996676 -0.0665548 0.0469927 -0.65868 0.640258 -0.395235 -0.93179 0.308886 -0.190677 -0.994045 -0.0864364 0.0663497 -0.993746 0.0873614 -0.0695508 -0.971836 0.184365 -0.146778 -0.994056 -0.0959913 0.0513676 -0.994035 -0.0928046 0.0572887 -0.931791 0.308884 -0.190676 -0.931639 0.280183 -0.231401 -0.558453 0.758494 -0.335884 -0.739293 0.611035 -0.282988 -0.93179 0.329389 -0.15255 -0.888075 0.421875 -0.182606 -0.971842 0.213818 -0.0990255 -0.237288 0.826625 -0.510281 -0.237288 0.881493 -0.408247 -0.108112 0.908125 -0.404501 -0.887838 0.360001 -0.286606 -0.739294 0.526817 -0.419413 -0.658469 0.58463 -0.473948 -0.558106 0.649167 -0.516818 -0.340888 0.735486 -0.585539 -0.658681 0.682755 -0.316205 -0.658681 0.640257 -0.395234 -0.23729 0.826624 -0.51028 -0.237193 0.755858 -0.610261 -0.108052 0.777765 -0.619198 -0.939507 -0.267532 0.2139 -0.93961 -0.25343 0.230015 -0.939482 -0.253596 0.230353 -0.939572 -0.253593 0.229991 -0.93969 -0.254038 0.229016 -0.93985 -0.252919 0.229597 -0.939866 -0.25286 0.229595 -0.939729 -0.253185 0.229796 -0.939513 -0.311097 0.143295 -0.940518 -0.316311 0.123986 -0.939695 -0.318815 0.123815 -0.939888 -0.318531 0.123081 -0.939691 -0.318648 0.124275 -0.939538 -0.319379 0.123552 -0.939488 -0.319562 0.123463 -0.939513 -0.319476 0.123491 -0.939749 -0.31883 0.123362 -0.939509 -0.311108 0.143301 -0.939511 -0.311104 0.143298 -0.939693 -0.301556 0.161371 -0.939694 -0.30156 0.161359 -0.939498 -0.291489 0.179937 -0.939498 -0.291489 0.179938 -0.939694 -0.279391 0.197271 -0.939694 -0.27939 0.197273 -0.939511 -0.267522 0.213893 -0.939515 -0.267515 0.213886 -0.939697 -0.253867 0.229173 0 0.979299 -0.202419 0.000495478 0.979041 -0.203661 -0.000539009 0.849169 -0.528121 0 0.849887 -0.526966 -0.701598 0.697639 -0.145124 -0.701594 0.697642 -0.145126 -0.701593 0.605099 -0.376328 -0.701591 0.6051 -0.376329 0.000338782 -0.249376 -0.968407 -0.00613578 -0.344123 -0.938905 -0.0220223 -0.434162 -0.900566 0.00551356 -0.537517 -0.843235 -7.13642e-06 -0.646085 -0.763265 -5.56883e-06 -0.682158 -0.731205 -0.00814467 -0.803179 -0.595683 0.0204041 -0.852254 -0.52273 -0.0192342 -0.979736 -0.199367 0 -0.990241 -0.139368 -0.000849511 -0.117181 -0.99311 -0.0212856 0.0111779 -0.999711 0.00327054 0.121879 -0.99254 -0.000184506 0.261359 -0.965242 0.000478995 0.310869 -0.950453 -0.0100176 0.474662 -0.880111 0.00633026 0.526664 -0.85005 -0.00763592 0.802785 -0.59622 0 0.816721 -0.577032 0.697568 0.575231 -0.42721 0.697589 0.575211 -0.427203 0.704523 0.389686 -0.59312 0.786902 0.292919 -0.543125 0.685366 0.250432 -0.683782 0.707003 0.184835 -0.682629 0.697586 0.00801104 -0.716456 0.697587 0.00801081 -0.716455 0.697584 -0.311155 -0.645414 0.697589 -0.702109 -0.142873 0.697598 -0.702101 -0.142868 0.699425 -0.574055 -0.425752 0.646806 -0.601944 -0.468301 0.706998 -0.456921 -0.539793 0.697581 -0.311155 -0.645417 0.698069 -0.432703 0.570498 0.698068 -0.432704 0.570498 0.698067 -0.142325 0.701745 0.609303 -0.183676 0.771371 0.706899 -0.00661841 0.707284 0.698069 0.176245 0.694001 0.698069 0.176245 0.694001 0.698074 0.459905 0.548799 0.698073 0.459905 0.5488 0.698074 0.652475 0.294906 0.69807 0.652477 0.294909 0.706902 0.697537 0.11718 0.698063 0.637387 -0.326259 0.698072 0.637378 -0.326258 0.700605 0.712351 -0.041333 0.796082 0.600663 -0.0738753 0.684043 0.72565 0.0742796 0.700683 -0.69643 0.155013 0.700682 -0.69643 0.155013 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706173 0.574081 -0.414428 0.706179 0.574077 -0.414425 0.706178 0.627754 -0.327471 0.706157 0.627773 -0.327482 0 0.897493 -0.44103 0.0420204 0.885832 -0.462099 0 0.863327 -0.504646 0 0.810804 -0.585318 0.0629298 0.7949 -0.603468 0 0.838036 -0.545615 0.706177 -0.574078 0.414425 0.706179 -0.574077 0.414425 0.706179 -0.627753 0.327472 0.70618 -0.627752 0.327471 0 -0.951149 0.308734 -0.0173632 -0.975965 0.217233 0 -0.99245 0.122649 0 0.851654 -0.524104 -0.0178419 0.890019 -0.455574 -0.0027252 0.939588 -0.342298 0.00733969 0.998294 -0.0579243 -0.0049378 0.995481 -0.0948308 0.00112315 0.986181 0.165669 0.0112952 0.955718 0.294068 -0.0189627 0.91108 0.411793 -0.00489016 0.861508 0.50772 0.00688658 0.748551 0.663041 -0.038892 0.569506 0.821067 -0.00580967 0.642291 0.766439 0.000323664 0.459574 0.88814 0 -0.604308 0.796751 -0.0075706 -0.618248 0.785947 0.00704655 -0.231635 0.972777 -0.00552195 -0.262428 0.964936 4.07213e-06 -0.0571739 0.998364 -4.26057e-07 -0.0093571 0.999956 1.20178e-05 -0.00915779 0.999958 2.37751e-06 0.246142 0.969234 -0.0308313 0.172619 0.984506 -0.00153042 0.374478 0.927234 0.994042 -0.0868126 0.0659059 0.97185 0.18765 -0.142459 0.658909 0.640087 -0.395129 0.108088 0.892234 -0.438446 0.558281 0.744606 -0.365903 0.341075 0.843674 -0.414586 0.23732 0.875499 -0.420929 0.237616 0.8386 -0.490192 0.153985 0.84078 -0.519017 0.237622 0.814033 -0.529987 0.237427 0.773704 -0.587376 0.887896 0.412886 -0.202893 0.739449 0.604203 -0.296907 0.108165 0.780611 -0.615586 0.341054 0.748725 -0.568413 0.658909 0.599129 -0.454844 0.558597 0.649889 -0.515378 0.73946 0.53619 -0.407061 0.971846 0.211465 -0.103915 0.931703 0.329512 -0.152812 0.931867 0.308716 -0.190572 0.658689 0.678924 -0.324331 0.658911 0.640086 -0.395128 0.931866 0.308718 -0.190573 0.931867 0.288964 -0.219374 0.888087 0.357144 -0.289395 0.994042 -0.0978216 0.0480701 0.994042 -0.0978232 0.0480706 0.994052 -0.0940186 0.0549568 0.994978 -0.0851739 0.0525784 0.994053 -0.0912634 0.0594177 0.994042 -0.0868121 0.0659056 0 -0.789143 0.61421 -0.0635017 -0.809168 0.584136 0 -0.831408 0.555662 0 -0.869338 0.494218 -0.0635024 -0.884825 0.461575 0 -0.902736 0.430196 0.891415 -0.219317 -0.396585 0.893721 -0.445249 0.0549136 0.900887 -0.434054 0.000508713 0.982611 -0.180077 -0.0452635 0.968947 -0.239729 -0.0605905 0.959187 -0.273131 -0.0732123 0.955083 -0.289128 -0.0649766 0.937213 -0.342474 -0.0659048 0.963018 0.160393 -0.216496 0.97139 0.146589 -0.186852 0.876439 0.352029 -0.328527 0.88405 0.345401 -0.314887 0.858962 0.1147 -0.499028 0.839078 0.117288 -0.531217 0.946585 -0.0216172 -0.321728 0.938297 -0.0206514 -0.345215 0.978164 -0.203625 -0.041607 0.993506 -0.112201 0.0189015 0.993503 -0.113105 0.0126207 0.71267 -0.701236 0.0192342 0.884953 -0.457785 0.085393 0.885789 -0.455167 0.0905572 0.792146 -0.134391 -0.595352 0.849347 -0.243744 -0.468187 0.805188 -0.369208 -0.464067 0.812781 -0.406279 -0.417521 0.759742 -0.541943 -0.359291 0.771364 -0.559081 -0.304016 0.722818 -0.661105 -0.201182 0.103164 -0.687214 -0.719092 0.199235 -0.603654 -0.77195 -0.0424663 -0.848342 -0.527743 -0.0162654 -0.847031 -0.531295 0.275267 -0.832461 -0.480871 0.149106 -0.980714 0.126358 0.15198 -0.98004 -0.128154 0.933084 -0.356082 -0.0505996 0.918212 -0.394626 -0.0340058 0.916085 -0.399612 -0.033139 0.902775 -0.429288 0.0266166 0.738158 -0.657108 -0.152751 0.697717 -0.716312 -0.00937239 0.461103 -0.884976 -0.064823 0.105761 0.807538 -0.580256 0.121185 0.808902 -0.575319 0.0859336 0.50145 -0.860909 0.151896 0.511706 -0.845627 0.092705 0.301328 -0.949003 0.164553 0.109902 -0.980226 0.146507 0.105288 -0.98359 0.0375652 -0.540434 -0.840548 0.112556 -0.35566 -0.927813 0.225703 -0.27759 -0.93381 0.211654 -0.26868 -0.939688 0.0696144 -0.125212 -0.989685 0.353644 -0.829689 -0.431917 0.456011 -0.608181 -0.649747 0.364135 -0.645879 -0.671003 0.489618 -0.328403 -0.807729 0.398071 -0.358351 -0.844467 0.521634 0.00738905 -0.853137 0.443201 -0.00745133 -0.896391 0.546134 0.359571 -0.756602 0.493428 0.360111 -0.791738 0.553288 0.658168 -0.510575 0.546192 0.66031 -0.515427 0.177303 -0.859748 -0.478954 0.301506 -0.599394 -0.741499 0.187409 -0.63058 -0.753158 0.324416 -0.28424 -0.902198 0.209391 -0.311558 -0.926869 0.342317 0.0810598 -0.936081 0.242327 0.063916 -0.968087 0.351085 0.450411 -0.820895 0.282722 0.44576 -0.849333 0.344987 0.757642 -0.554042 0.333652 0.758617 -0.559621 0.148816 -0.940026 0.306929 0.230476 -0.94831 0.218148 0.341433 -0.915088 0.214563 0.425 -0.884511 0.192394 0.484371 -0.847622 0.216616 0.687666 -0.700058 0.192441 0.64736 -0.746445 0.154094 0.870202 -0.44166 0.218369 0.850007 -0.501374 0.16159 0.172917 -0.975087 -0.138943 0.179682 -0.973713 -0.139992 0.423355 -0.899898 -0.10466 0.487243 -0.808729 -0.329472 0.503326 -0.799377 -0.328113 0.600318 -0.596051 -0.533236 0.532627 -0.636116 -0.55827 0.641631 -0.360181 -0.677185 0.575707 -0.390864 -0.718183 0.684256 -0.0690349 -0.725967 0.629491 -0.082599 -0.772605 0.721186 0.245306 -0.647854 0.685625 0.248144 -0.684356 0.739811 0.521054 -0.425655 0.725681 0.528232 -0.440861 0.146444 -0.614622 0.775109 0.824719 0.223832 0.519363 0.651397 -0.505386 0.565921 0.942262 -0.0505059 0.331047 0.971801 -0.0579655 0.228566 0.978816 -0.0428003 0.200217 0.98931 -0.0699866 0.127934 0.993672 -0.0655665 0.0911956 0.851106 -0.405219 0.33379 0.873459 -0.311166 0.374494 0.889406 -0.265304 0.372252 0.901406 -0.215641 0.375455 0.895301 -0.224208 0.384925 0.918227 -0.153249 0.365203 0.741741 0.046831 0.66905 0.782192 0.0614875 0.619996 0.708896 -0.148455 0.689512 0.911964 -0.158776 0.378303 0.938587 -0.10126 0.329849 0.786962 0.228108 0.573287 0.849348 0.309297 0.42772 0.792191 0.471981 0.386868 0.856726 0.497013 0.137835 0.843571 0.523954 0.117733 0.884011 0.439075 -0.160431 0.877479 0.44716 -0.173433 0.921874 -0.102087 0.373799 0.959989 -0.0825438 0.267597 0.891441 0.256222 0.373743 0.944652 0.27703 0.175746 0.941308 0.296225 0.161831 0.970892 0.237065 -0.0341928 0.965073 0.255177 -0.0593233 0.115178 0.935051 -0.335282 0.0767997 0.993086 -0.0887831 0.146682 0.987571 -0.0564655 0.0529837 0.953146 0.297834 0.148676 0.928658 0.339838 0.0857669 0.852906 0.514971 0.14632 0.729853 0.667761 0.333941 0.838225 -0.431117 0.105759 0.88066 -0.461794 0.296916 0.816067 -0.495859 0.0132426 0.0919113 0.995679 0.298948 0.130384 0.94532 0.108602 -0.0192276 0.993899 0.14311 0.72969 0.668634 0.0595833 0.558946 0.82706 0.223299 0.414413 0.882269 0.243333 0.419584 0.874493 0.107832 0.360397 0.926545 0.0837852 -0.0644203 0.994399 0.0301574 -0.264714 0.963855 0.178764 -0.311546 0.933265 0.11164 -0.63006 0.76848 0.341446 -0.601968 0.721837 0.692776 -0.463591 0.552399 0.714411 -0.309345 0.627633 0.412917 -0.340318 0.844798 0.487268 -0.0678168 0.870615 0.353592 0.0143679 0.935289 0.447577 0.279157 0.849557 0.377674 0.336642 0.862574 0.480035 0.552055 0.681764 0.412111 0.614255 0.672946 0.513921 0.755612 0.406122 0.454267 0.806085 0.379301 0.542569 0.839015 0.0408945 0.499057 0.866499 0.011018 0.553197 0.752774 -0.356798 0.546576 0.755089 -0.36207 0.344672 0.837194 -0.424627 0.287825 0.956772 -0.0417557 0.34627 0.938086 -0.0096186 0.253009 0.90372 0.345364 0.332865 0.862945 0.380167 0.223308 0.711311 0.666461 0.31306 0.65545 0.687298 0.200952 0.419511 0.885228 0.291658 0.363491 0.884765 0.187456 0.069383 0.97982 0.269278 0.0283434 0.962645 0.179698 -0.31133 0.933157 0.463499 -0.307428 0.831057 0.425025 -0.568433 0.704441 0.484356 -0.573556 0.660631 0.870901 -0.361389 0.33306 0.892968 -0.277511 0.354395 0.69017 -0.335034 0.641419 0.744778 -0.12184 0.656095 0.503284 -0.0648597 0.861683 0.593138 0.183079 0.784009 0.545203 0.2368 0.804163 0.633557 0.422818 0.647943 0.588806 0.483516 0.647704 0.677989 0.607775 0.413448 0.639886 0.659647 0.394224 0.718475 0.689509 0.0914922 0.691091 0.719764 0.0658314 0.739779 0.617577 -0.267069 0.726923 0.626177 -0.28193 0.939622 -0.270056 0.210192 0.939565 -0.307274 0.150996 0.938415 -0.317112 0.137179 0.939692 -0.314492 0.134439 0.939392 -0.315659 0.1338 0.939413 -0.31558 0.133835 0.939896 -0.314268 0.133532 0.939966 -0.314174 0.133262 0.939946 -0.314206 0.133326 0.939755 -0.314651 0.133621 0.939566 -0.315127 0.133827 0.939623 -0.260745 0.221631 0.939836 -0.260296 0.221255 0.940956 -0.259414 0.2175 0.939692 -0.261144 0.220866 0.939964 -0.259946 0.221122 0.939976 -0.259898 0.221129 0.939692 -0.261457 0.220496 0.939471 -0.261042 0.221926 0.939449 -0.261056 0.222002 0.939565 -0.27269 0.20702 0.94337 -0.26317 0.201976 0.936007 -0.294974 0.192045 0.939622 -0.284519 0.190155 0.93966 -0.295352 0.172642 0.937285 -0.303019 0.172266 0.94337 -0.298499 0.144747 0.939621 -0.308931 0.14722 0.939692 -0.31428 0.134931 0.149347 -0.780293 0.607321 0.48879 -0.68845 0.535837 0.34608 -0.846951 0.403613 0.655053 -0.682092 0.325048 0.850959 -0.474146 0.225952 0.850963 -0.47414 0.22595 0.850963 -0.456599 0.259576 0.850961 -0.456602 0.259577 0.850961 -0.43668 0.29185 0.850961 -0.436679 0.29185 0.850961 -0.41448 0.322601 0.850962 -0.41448 0.3226 0.655069 -0.596252 0.464078 0.573442 -0.651081 0.497251 0.57333 -0.681193 0.455267 0.573328 -0.681195 0.455268 0.573328 -0.712271 0.404926 0.573326 -0.712272 0.404926 0.573437 -0.73631 0.359191 0.488806 -0.78754 0.3753 0.346088 -0.740375 0.576253 0.202126 -0.776399 0.59695 0.202088 -0.814254 0.544197 0.202092 -0.814254 0.544197 0.202092 -0.851401 0.484021 0.202095 -0.8514 0.484021 0.202133 -0.881593 0.426538 0.149352 -0.892611 0.425371 -0.707107 0.657561 -0.260025 -0.671199 0.671863 -0.313198 -0.70647 0.642212 -0.297428 -0.70647 0.602238 -0.371765 -0.706466 0.602241 -0.371767 -0.706518 0.55476 -0.439401 -0.672806 0.578794 -0.460792 -0.707095 0.527142 -0.471315 -0.706478 -0.642205 0.297424 -0.706471 -0.642211 0.297427 -0.706471 -0.602237 0.371764 -0.706463 -0.602244 0.371769 -0.706463 -0.553705 0.440819 -0.706476 -0.553695 0.44081 -0.696403 0.701211 0.152725 -0.430465 0.894618 0.11983 -0.705932 0.658525 0.260776 -0.696403 0.547846 0.46356 -0.332787 0.777959 0.532947 -0.705264 0.4708 0.530046 -0.704455 0.341945 0.621945 -0.524008 0.316507 0.79072 -0.696406 -0.402165 0.594375 -0.6964 -0.402167 0.594381 -0.703498 -0.147234 0.695279 -0.530091 -0.0906054 0.843086 -0.705268 0.0249585 0.708501 -0.704459 0.181636 0.686109 -0.694749 -0.714725 0.0805742 -0.487512 -0.518512 -0.702479 -0.694741 -0.714733 0.0805777 -0.702916 -0.678897 -0.21215 -0.494612 -0.796618 -0.347505 -0.705013 -0.599097 -0.379524 -0.703696 -0.489106 -0.515352 -0.704394 -0.338725 -0.623774 -0.704396 -0.176049 -0.687629 -0.487518 -0.0978075 -0.867617 -0.694748 0.578687 -0.427138 -0.694724 0.578701 -0.427157 -0.702904 0.353295 -0.617339 -0.49462 0.347505 -0.796612 -0.70501 0.180955 -0.685723 -0.703697 0.00793109 -0.710456 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.0086563 0.650267 0.759657 0.00529718 0.664077 0.747645 -0.00897022 0.506249 0.862341 1.88995e-05 0.481784 0.87629 -5.00525e-06 0.284593 0.958648 0.00734607 0.255911 0.966672 -0.00815668 0.0644475 0.997888 2.63267e-05 0.0352053 0.99938 -1.69599e-05 -0.178527 0.983935 0.00925517 -0.207159 0.978263 -0.00336066 -0.356045 0.934463 0.023676 -0.560236 0.827994 0.0218067 -0.562979 0.826184 0 -0.718556 0.695469 1.65935e-05 0.70321 0.710983 8.06512e-06 0.824981 0.56516 -0.00956496 0.839998 0.542505 0.00357791 0.929748 0.36818 -0.0141992 0.971996 0.234567 0.0128889 0.991066 0.132749 0 0.999803 0.0198692 0.939621 -0.128781 0.317062 0.939565 -0.19061 0.284404 0.938421 -0.20603 0.27734 0.939691 -0.205136 0.273677 0.939386 -0.206491 0.273707 0.939414 -0.206377 0.273695 0.939896 -0.205394 0.27278 0.939967 -0.205448 0.272496 0.939947 -0.205444 0.272568 0.939756 -0.205683 0.273045 0.939566 -0.205994 0.273465 0.93962 -0.114996 0.32232 0.939838 -0.114791 0.321757 0.940957 -0.115913 0.318063 0.939691 -0.115728 0.32185 0.93997 -0.114534 0.321463 0.939975 -0.114516 0.321456 0.939693 -0.116177 0.321684 0.939472 -0.115104 0.322714 0.93945 -0.115079 0.322786 0.939566 -0.132647 0.315628 0.94337 -0.126925 0.306501 0.936007 -0.159432 0.313802 0.939622 -0.151323 0.306939 0.939661 -0.169461 0.297188 0.937285 -0.17629 0.300697 0.94337 -0.186135 0.274603 0.939621 -0.193932 0.281961 0.939693 -0.204706 0.273995 0.149347 -0.372092 0.916102 0.488782 -0.328297 0.808278 0.346113 -0.531669 0.773004 0.655062 -0.42818 0.622539 0.850961 -0.297644 0.43275 0.850963 -0.297642 0.432748 0.850963 -0.265639 0.453099 0.850962 -0.26564 0.4531 0.850962 -0.23225 0.471088 0.850962 -0.23225 0.471088 0.850962 -0.19765 0.486619 0.850963 -0.197648 0.486617 0.655061 -0.284333 0.700035 0.573439 -0.315227 0.756174 0.573328 -0.362297 0.734871 0.573327 -0.362298 0.734872 0.573327 -0.414383 0.706812 0.573328 -0.414382 0.706811 0.57344 -0.458066 0.679222 0.488784 -0.494387 0.718799 0.34611 -0.353054 0.86923 0.202127 -0.373907 0.905173 0.202089 -0.433066 0.878416 0.202092 -0.433065 0.878415 0.202092 -0.495325 0.844874 0.202094 -0.495324 0.844874 0.202132 -0.550213 0.81019 0.149341 -0.56034 0.814688 -0.707103 0.43946 -0.553968 -0.671188 0.425256 -0.607177 -0.70647 0.407458 -0.578687 -0.70647 0.335671 -0.623077 -0.706468 0.335672 -0.623079 -0.706519 0.260735 -0.657912 -0.672816 0.270851 -0.688446 -0.707102 0.22086 -0.671735 -0.706466 -0.40746 0.57869 -0.706475 -0.407455 0.578682 -0.706476 -0.335669 0.623072 -0.706474 -0.335669 0.623073 -0.706474 -0.259109 0.658603 -0.70648 -0.259107 0.658597 -0.696797 0.701514 0.149507 -0.45772 0.881202 0.118218 -0.706057 0.659517 0.257919 -0.69679 0.553731 0.455923 -0.324177 0.78948 0.521183 -0.696805 -0.0542714 0.715204 -0.6968 -0.0542701 0.71521 -0.703912 0.208391 0.67903 -0.535529 0.331294 0.776822 -0.705132 0.36285 0.609203 -0.705134 0.482234 0.519842 -0.698062 -0.559795 0.446475 -0.698063 -0.559794 0.446474 -0.698061 -0.698077 0.159372 -0.61851 -0.759747 0.200576 -0.706893 -0.706918 0.0238478 -0.69806 -0.698095 -0.159295 -0.698056 -0.6981 -0.159294 -0.698058 -0.559851 -0.44641 -0.698067 -0.559842 -0.446407 -0.698066 -0.310711 -0.645106 -0.69807 0.310637 -0.645138 -0.698071 0.310637 -0.645137 -0.700603 0.023973 -0.713149 -0.634905 -4.47727e-05 -0.77259 -0.706899 -0.134136 -0.694479 -0.698067 -0.31071 -0.645106 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.0828072 0.996566 0.00465906 -0.0756641 0.997122 -0.00282064 0.293389 0.955989 0.00398826 0.69058 0.723245 -0.000102752 0.608251 0.793745 0.000788509 0.511723 0.85915 3.48955e-05 0.509384 0.860539 -1.28839e-05 0.286631 0.958041 -1.61584e-05 0.68009 0.733128 1.3057e-05 0.834548 0.550935 -0.00757393 0.846174 0.532852 0.0030355 0.931312 0.36421 0.00129139 0.93583 0.352449 -0.00405556 0.991113 0.132964 0 0.989825 0.142291 0 0.502253 -0.864721 0.0254433 0.433692 -0.900702 0.00386059 0.31827 -0.947992 -0.0105374 0.0335948 -0.99938 0.00709923 0.0705628 -0.997482 -0.00161474 -0.189641 -0.981852 -0.0200922 -0.350095 -0.936499 0.0193183 -0.433852 -0.900777 0.00122961 -0.578856 -0.815429 -0.00305462 -0.699173 -0.714946 0.0538709 -0.828526 -0.557353 0.0129823 -0.781801 -0.623393 -0.000757059 -0.894793 -0.446482 0 -0.781796 0.623535 0.00483614 -0.777037 0.629437 -0.00428302 -0.966864 0.255256 0.00777431 -0.961101 0.276087 -4.60465e-06 -0.996672 0.0815173 5.94434e-07 -0.999431 0.0337157 -0.00088783 -0.99971 0.0240794 0.00553195 -0.974926 -0.222461 0.0432332 -0.986444 -0.158304 0.00223935 -0.936087 -0.35176 0 -0.575714 0.817651 0 -0.575714 0.817651 0 -0.474284 0.880372 0 -0.474284 0.880372 0 -0.366108 0.930572 0 -0.366108 0.930572 0 0.366109 -0.930572 0 0.366109 -0.930572 0 0.474284 -0.880372 0 0.474284 -0.880372 0 0.575714 -0.817651 0 0.575714 -0.817651 -0.879242 -0.111942 0.463035 -0.887083 -0.0374887 0.460085 -0.954989 0.090537 0.282488 -0.960101 0.0962091 0.262583 -0.978436 0.06407 0.196364 -0.978976 0.063835 0.193729 -0.991397 7.26332e-05 0.130892 -0.990797 0.00271266 0.135328 -0.965171 0.184368 -0.185616 -0.793207 0.604089 0.076805 -0.859469 0.484823 -0.162052 -0.839105 0.518121 -0.165692 -0.88419 0.280397 -0.37361 -0.876485 0.294287 -0.381011 -0.859293 0.359866 0.363471 -0.938546 0.0958352 0.331584 -0.933192 0.0822425 0.34984 -0.821648 0.494106 0.284172 -0.847484 0.488765 0.207075 -0.89128 0.41506 0.182606 -0.947044 0.32096 -0.00962947 -0.938318 0.345595 -0.0111344 -0.970911 0.184007 -0.153212 -0.989049 0.126931 -0.075308 -0.807335 0.191636 0.558109 -0.693243 0.482022 0.535788 -0.770721 0.548392 0.324431 -0.902134 0.035754 0.429972 -0.887848 -0.0430189 0.458121 -0.749532 0.0285238 0.661354 -0.710143 0.0166993 0.70386 -0.105513 0.836459 0.537776 -0.138996 0.837965 0.527726 -0.276015 0.558063 0.782548 -0.109022 0.279102 0.954053 -0.0571251 0.50493 0.861268 -0.220839 0.571132 0.790594 -0.206092 0.581903 0.786711 -0.0677991 0.684498 0.725855 -0.146984 -0.128746 0.980724 -0.074166 -0.0842396 0.993682 -0.106181 0.486608 -0.867144 -0.151437 0.50083 -0.852195 -0.105041 0.663225 -0.741013 -0.111703 0.810227 -0.575373 -0.0784087 0.930156 0.358695 -0.152085 0.976096 0.155264 -0.0787932 0.981566 0.174124 -0.101819 0.979603 -0.173234 -0.178452 0.963735 -0.198416 -0.0897456 0.921361 -0.378206 -0.14994 0.799108 -0.58219 -0.35422 0.507677 0.785361 -0.457112 0.704745 0.542571 -0.363189 0.726613 0.583205 -0.490844 0.835 0.248691 -0.397294 0.873639 0.280913 -0.522595 0.847861 -0.0895855 -0.442817 0.893542 -0.0741363 -0.546589 0.718497 -0.430119 -0.493389 0.755227 -0.431509 -0.553358 0.446785 -0.702978 -0.546235 0.451713 -0.705395 -0.176411 0.554793 0.813071 -0.302656 0.795484 0.524981 -0.186331 0.806943 0.560467 -0.325681 0.925029 0.195585 -0.208482 0.951343 0.226898 -0.34327 0.92356 -0.170888 -0.24188 0.95839 -0.151603 -0.351526 0.774 -0.526644 -0.282648 0.804754 -0.521997 -0.345026 0.480335 -0.806371 -0.333666 0.486223 -0.807623 -0.879551 -0.112875 0.462222 -0.763481 -0.128897 0.632837 -0.693965 -0.0952497 0.713681 -0.651408 -0.128668 0.747738 -0.484429 -0.137223 0.864001 -0.918294 0.0692961 0.389788 -0.901025 0.063608 0.429077 -0.758732 0.279655 0.588319 -0.80529 0.244525 0.540106 -0.700521 0.356666 0.618109 -0.633819 0.0982869 0.767211 -0.461118 0.144858 0.875435 -0.425661 -0.106211 0.898628 -0.341482 -0.128111 0.931116 -0.206897 0.233279 0.950144 -0.179206 0.228501 0.956908 -0.42409 0.189487 0.885574 -0.486863 0.400289 0.776359 -0.502661 0.399019 0.766887 -0.601389 0.587369 0.5416 -0.531845 0.613467 0.583781 -0.642821 0.707849 0.292799 -0.575098 0.750856 0.324771 -0.685236 0.72832 -0.00140483 -0.629205 0.777147 0.0119778 -0.721673 0.620875 -0.30611 -0.685629 0.658573 -0.310152 -0.739942 0.374531 -0.55876 -0.725678 0.389975 -0.566843 -0.146159 -0.766703 0.625144 -0.826274 -0.521247 -0.213479 -0.651412 -0.553618 0.518816 -0.992269 -0.114618 0.0475992 -0.992328 -0.0904786 0.0842578 -0.976262 -0.211994 0.0443894 -0.978909 -0.196938 0.0543446 -0.963217 -0.261312 0.0626797 -0.851019 -0.315402 0.419866 -0.880893 -0.36183 0.305133 -0.902136 -0.369425 0.222881 -0.895771 -0.378214 0.233558 -0.919313 -0.359424 0.160243 -0.740539 -0.67148 -0.0267731 -0.783611 -0.619279 -0.0494718 -0.707952 -0.685771 0.168884 -0.918517 -0.361022 0.161215 -0.938741 -0.328822 0.103154 -0.7859 -0.58109 -0.211415 -0.847485 -0.441815 -0.294225 -0.793257 -0.396369 -0.462206 -0.856961 -0.150254 -0.492992 -0.844208 -0.128966 -0.520269 -0.884164 0.149513 -0.442605 -0.877676 0.163162 -0.450626 -0.945947 -0.309364 0.0973525 -0.960044 -0.27274 0.0626741 -0.891349 -0.380713 -0.246079 -0.944832 -0.182704 -0.271867 -0.94185 -0.167475 -0.291324 -0.970926 0.02662 -0.237894 -0.965173 0.0535421 -0.256075 -0.115169 0.312312 -0.942973 -0.0771109 0.0656215 -0.994861 -0.146472 0.031816 -0.988703 -0.044076 -0.351733 -0.935062 -0.0575953 -0.357138 -0.932274 -0.0997429 -0.583766 -0.805772 -0.181848 -0.685051 -0.705433 -0.334006 0.411135 -0.848179 -0.105773 0.439847 -0.891822 -0.278872 0.478807 -0.832451 -0.0122664 -0.997827 -0.0647345 -0.315861 -0.941158 -0.120226 -0.112688 -0.993105 0.0323147 -0.136044 -0.70193 -0.699133 -0.0636784 -0.834428 -0.547426 -0.202703 -0.894674 -0.398083 -0.248158 -0.877169 -0.411086 -0.108788 -0.934133 -0.339942 -0.0842361 -0.992622 0.0872108 -0.0329008 -0.959971 0.278159 -0.190432 -0.923637 0.332613 -0.0911586 -0.754264 0.650212 -0.341482 -0.707051 0.619249 -0.693994 -0.543563 0.472135 -0.71475 -0.620359 0.322935 -0.412188 -0.83543 0.363534 -0.486902 -0.868522 0.0927093 -0.354191 -0.935139 0.00799386 -0.447656 -0.856498 -0.256935 -0.378519 -0.869964 -0.316046 -0.480139 -0.695744 -0.534235 -0.413114 -0.686691 -0.598158 -0.514074 -0.425144 -0.74497 -0.455181 -0.397399 -0.796796 -0.542688 -0.0617883 -0.837658 -0.49964 -0.0307949 -0.865686 -0.553286 0.338186 -0.761252 -0.546673 0.343694 -0.763559 -0.344683 0.404294 -0.847195 -0.288263 0.0196448 -0.95735 -0.346234 -0.013761 -0.938047 -0.253708 -0.36609 -0.895327 -0.332834 -0.401813 -0.853093 -0.224025 -0.682832 -0.69538 -0.31303 -0.703784 -0.63773 -0.201527 -0.894836 -0.398317 -0.291635 -0.89379 -0.340718 -0.187822 -0.98113 -0.0459106 -0.26931 -0.963047 -0.00368846 -0.179223 -0.924764 0.335695 -0.463846 -0.823902 0.325626 -0.425696 -0.691967 0.583065 -0.484443 -0.645994 0.589921 -0.87538 -0.323071 0.359631 -0.8896 -0.355349 0.286949 -0.689727 -0.632207 0.352974 -0.745698 -0.652464 0.135 -0.502659 -0.859935 0.0885759 -0.593276 -0.788495 -0.162172 -0.54628 -0.808842 -0.217609 -0.633763 -0.6587 -0.405536 -0.589999 -0.657959 -0.467965 -0.678237 -0.428803 -0.59676 -0.640943 -0.408517 -0.649851 -0.718701 -0.108687 -0.686772 -0.691733 -0.08191 -0.717493 -0.739908 0.251612 -0.623881 -0.727057 0.267118 -0.632484 -0.572883 -0.388741 0.721585 -0.850727 -0.30349 0.429135 -0.879518 -0.173297 0.443189 -0.654677 -0.276744 0.703428 -0.764994 -0.235787 0.599323 -0.845145 -0.198877 0.496164 -0.851115 -0.219992 0.476662 -0.850698 -0.24931 0.462772 -0.850698 -0.24931 0.462771 -0.851116 -0.277026 0.445935 -0.345791 -0.343524 0.873167 -0.488404 -0.319473 0.812034 -0.149208 -0.36201 0.920155 -0.201919 -0.361816 0.91012 -0.201878 -0.464519 0.862245 -0.844349 -0.308464 0.438093 -0.65468 -0.435186 0.618068 -0.573004 -0.468122 0.672702 -0.488412 -0.502376 0.713493 -0.345791 -0.540199 0.767211 -0.573004 -0.30425 0.760985 -0.572883 -0.388741 0.721586 -0.201875 -0.464519 0.862246 -0.201915 -0.560997 0.802815 -0.149222 -0.569268 0.808496 -0.340888 0.541232 -0.768677 -0.994035 -0.0517265 0.0960153 -0.994036 -0.0629657 0.0890334 -0.994251 -0.0616469 0.0875532 -0.991754 -0.0466713 0.119357 -0.996676 -0.0341406 0.0739702 -0.658679 0.356863 -0.662413 -0.93179 0.172164 -0.319572 -0.994046 -0.0416811 0.100678 -0.993745 0.0408835 -0.103917 -0.971837 0.0862754 -0.219295 -0.994056 -0.0574514 0.0924775 -0.994035 -0.0517264 0.096015 -0.931791 0.172163 -0.319571 -0.931639 0.126945 -0.340491 -0.558461 0.488929 -0.670127 -0.739297 0.387674 -0.550589 -0.93179 0.208982 -0.296805 -0.888073 0.274054 -0.369082 -0.971842 0.135656 -0.192664 -0.237287 0.460738 -0.855228 -0.237287 0.559272 -0.794298 -0.108127 0.584206 -0.80437 -0.887838 0.168467 -0.428209 -0.739295 0.246531 -0.62663 -0.658467 0.269331 -0.702767 -0.558107 0.303786 -0.77216 -0.340887 0.34418 -0.874835 -0.658678 0.433182 -0.615221 -0.658678 0.356863 -0.662414 -0.237287 0.460738 -0.855228 -0.237191 0.349461 -0.906431 -0.108044 0.363966 -0.925125 -0.939508 -0.124738 0.319006 -0.939608 -0.104468 0.32592 -0.939483 -0.104444 0.326286 -0.939572 -0.104621 0.325973 -0.939691 -0.105497 0.325349 -0.939848 -0.104242 0.3253 -0.939867 -0.104183 0.325262 -0.939732 -0.104363 0.325596 -0.939514 -0.197769 0.279644 -0.940502 -0.211987 0.265553 -0.939696 -0.214192 0.266633 -0.939887 -0.214314 0.26586 -0.93969 -0.213821 0.266952 -0.939536 -0.214823 0.266689 -0.939492 -0.214999 0.266702 -0.939514 -0.214925 0.266686 -0.939749 -0.214432 0.266253 -0.939508 -0.197779 0.279659 -0.939511 -0.197774 0.27965 -0.939694 -0.180484 0.290519 -0.939693 -0.18048 0.290523 -0.939497 -0.162469 0.301577 -0.939498 -0.162469 0.301576 -0.939694 -0.143327 0.310537 -0.939693 -0.143323 0.310541 -0.939511 -0.124735 0.319 -0.939514 -0.124733 0.318991 -0.939696 -0.105271 0.325406 0 0.983132 -0.182897 0.0179221 0.972633 -0.231655 -0.000940213 0.922527 -0.385932 0.00366266 0.800571 -0.599227 0.0054115 0.802882 -0.596114 -0.000281858 0.66379 -0.747919 0.00443762 0.496464 -0.868046 0 0.487584 -0.873076 -0.699629 0.695064 -0.165546 -0.699634 0.69506 -0.165543 -0.699633 0.572014 -0.428152 -0.699635 0.572013 -0.428151 -0.699635 0.354727 -0.620226 -0.699631 0.354728 -0.62023 0 -0.987116 -0.160004 -0.0113417 -0.981094 -0.193201 0.00654493 -0.880353 -0.474274 -0.021514 -0.800591 -0.598826 -0.0027366 -0.739475 -0.673178 0.00186513 -0.598789 -0.800905 -0.0187068 -0.462425 -0.886461 0.000308103 -0.391498 -0.920179 -8.78127e-05 -0.207082 -0.978324 -0.0133099 -0.0330458 -0.999365 0.00481157 0.0311836 -0.999502 -0.00560083 0.402925 -0.915216 0 0.418789 -0.908084 0.698111 0.288494 -0.655296 0.698109 0.288495 -0.655297 0.704241 0.0454097 -0.708507 0.798048 -0.019915 -0.602264 0.698111 -0.702498 -0.138339 0.698111 -0.702498 -0.138339 0.69811 -0.573348 -0.428853 0.698115 -0.573345 -0.428848 0.698113 -0.331149 -0.634806 0.698115 -0.331148 -0.634804 0.705434 -0.11284 -0.699735 0.69807 -0.089484 0.710417 0.69807 -0.089484 0.710416 0.698071 0.227614 0.678888 0.609313 0.226616 0.759857 0.7069 0.347896 0.615842 0.698069 0.499636 0.512898 0.698066 0.499637 0.5129 0.698067 0.672694 0.245328 0.698067 0.672693 0.245328 0.698066 0.71252 -0.070843 0.698065 0.712521 -0.0708429 0.706898 0.662677 -0.247296 0.698063 0.388866 -0.601241 0.698066 0.388864 -0.60124 0.700598 0.596254 -0.391975 0.796091 0.483238 -0.364308 0.684045 0.665572 -0.29849 0.697966 -0.544712 0.464902 0.697964 -0.544713 0.464902 0.697964 -0.692951 0.180734 0.697964 -0.692951 0.180734 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706173 0.289955 -0.645946 0.706177 0.289953 -0.645943 0.706178 0.379915 -0.597476 0.706179 0.379914 -0.597475 0 0.556735 -0.83069 0.04202 0.536103 -0.843106 0 0.495339 -0.868699 0 0.409518 -0.912302 0.0629313 0.386669 -0.920069 0 0.452954 -0.891534 0.706179 -0.289952 0.64594 0.706177 -0.289953 0.645942 0.706176 -0.379916 0.597477 0.706179 -0.379914 0.597475 0 -0.745255 0.66678 -0.0089721 -0.7606 0.649159 0.000619015 -0.882155 0.470959 -0.00470131 -0.957896 0.287078 -0.0163904 -0.9675 0.252341 0 -0.996803 0.0799012 0 0.475504 -0.879713 -0.0178418 0.542995 -0.839547 -0.00272559 0.642557 -0.766233 0.00733956 0.835586 -0.549311 -0.00493644 0.814699 -0.579863 0.001124 0.936889 -0.349626 0.0112965 0.974709 -0.223193 -0.0189616 0.994915 -0.0989202 -0.00489017 0.999948 0.00893161 0.00688737 0.979785 0.199935 -0.0388899 0.903742 0.426307 -0.00581134 0.939458 0.342616 0.000321431 0.842071 0.539367 0 -0.124972 0.99216 -0.00757067 -0.142446 0.989774 0.00704567 0.285789 0.958267 -0.00552123 0.255204 0.966872 2.0841e-06 0.449595 0.893233 -2.44954e-06 0.491855 0.870677 1.20895e-05 0.492058 0.870563 2.34107e-06 0.697785 0.716308 -0.0308331 0.641745 0.766298 -0.00153294 0.787922 0.615774 0.994042 -0.0422287 0.100482 0.97185 0.0912805 -0.217199 0.65891 0.356767 -0.662235 0.108091 0.553474 -0.825823 0.55829 0.461894 -0.689178 0.34105 0.523357 -0.780886 0.237326 0.547737 -0.802284 0.237622 0.481152 -0.843818 0.153991 0.468627 -0.869871 0.237622 0.439981 -0.865998 0.237427 0.376359 -0.895535 0.887898 0.256121 -0.382151 0.739454 0.374799 -0.559226 0.108177 0.368237 -0.923417 0.34105 0.364209 -0.866624 0.65891 0.291439 -0.69347 0.558599 0.305131 -0.771273 0.739456 0.260825 -0.620624 0.971844 0.13118 -0.19573 0.931702 0.20896 -0.297097 0.931867 0.172071 -0.3194 0.658688 0.425801 -0.620341 0.658911 0.356767 -0.662234 0.931867 0.172071 -0.3194 0.931867 0.140563 -0.334465 0.888088 0.164597 -0.429194 0.994042 -0.0606812 0.0905408 0.994042 -0.0606816 0.0905413 0.994053 -0.0539437 0.0946027 0.994978 -0.0474736 0.088121 0.994053 -0.0493277 0.0970893 0.994042 -0.0422289 0.100482 0 -0.376313 0.926493 -0.0635016 -0.408691 0.910461 0 -0.442189 0.896922 0 -0.536577 0.843851 -0.126163 -0.562167 0.817344 0 -0.50576 0.862674 0.0694108 -0.603759 -0.79414 0.0923945 -0.21465 -0.972311 0.812778 -0.560609 -0.158461 0.893721 -0.35814 0.270182 0.900887 -0.375647 0.217468 0.982611 -0.178579 0.0508356 0.968942 -0.237927 0.0673943 0.959187 -0.273144 0.0731605 0.955084 -0.282878 0.0882888 0.937215 -0.329539 0.114156 0.978164 -0.19715 0.0657817 0.993506 -0.0877179 0.072471 0.993503 -0.091642 0.0674827 0.712674 -0.597667 0.367273 0.884953 -0.353756 0.302844 0.885792 -0.348898 0.306013 0.759737 -0.648986 -0.0402009 0.771367 -0.636182 0.016272 0.722825 -0.673116 0.156329 0.187427 -0.922675 -0.336961 0.301507 -0.889842 -0.342455 0.0388831 -0.956263 0.289914 0.491538 -0.755834 0.432556 0.146929 -0.725925 0.671897 0.123003 -0.737581 0.663961 0.0926484 -0.991796 0.0880723 0.219687 -0.975542 -0.00739303 0.275273 -0.961366 -0.00021441 0.177305 -0.98404 0.0150905 0.35364 -0.934492 0.0407946 0.456007 -0.851575 -0.258609 0.364131 -0.894851 -0.258169 0.172303 -0.913981 0.367355 0.179693 -0.913257 0.365613 0.423346 -0.831672 0.359305 0.487233 -0.865122 0.119031 0.503306 -0.85635 0.115535 0.600305 -0.782822 -0.163777 0.532651 -0.830011 -0.165424 0.268229 -0.734408 -0.623457 0.876442 0.140606 -0.460522 0.884046 0.141684 -0.445409 0.725684 0.237029 -0.645911 0.739821 0.238416 -0.629145 0.546201 0.314132 -0.776522 0.553288 0.314702 -0.771256 0.333629 0.377175 -0.863962 0.344981 0.379122 -0.858635 0.105764 0.409226 -0.906283 0.121181 0.412874 -0.90269 0.146154 -0.401659 -0.904051 0.16694 -0.395059 -0.90336 0.342321 -0.397839 -0.8512 0.242322 -0.428691 -0.870347 0.521634 -0.42017 -0.742533 0.4432 -0.45465 -0.772572 0.684257 -0.42277 -0.594187 0.629493 -0.457836 -0.627794 0.792144 -0.414063 -0.448396 0.839074 -0.164037 -0.518697 0.858962 -0.150181 -0.489519 0.685631 -0.127279 -0.716736 0.721188 -0.111488 -0.68371 0.493426 -0.0840068 -0.865722 0.546142 -0.0669021 -0.835017 0.282719 -0.0386246 -0.958425 0.351079 -0.0203786 -0.936124 0.0859307 0.00381513 -0.996294 0.151877 0.0203341 -0.98819 0.484347 -0.625763 0.611415 0.68767 -0.510044 0.516687 0.647371 -0.56938 0.506672 0.870205 -0.273297 0.409943 0.850011 -0.3534 0.390629 0.933084 -0.333674 0.134226 0.918214 -0.358753 0.167865 0.916083 -0.362646 0.171115 0.902775 -0.358469 0.237692 0.738161 -0.645445 0.196264 0.697721 -0.625029 0.350035 0.461097 -0.798828 0.386346 0.424991 -0.669808 0.608884 0.341467 -0.685197 0.643354 -0.0661725 -0.983772 -0.166773 0.30561 -0.85497 -0.419082 0.0131112 -0.916751 -0.399244 0.143532 -0.709851 -0.689572 0.324427 -0.697256 -0.639204 0.209396 -0.733252 -0.646912 0.489613 -0.688271 -0.535315 0.398064 -0.732576 -0.552156 0.641641 -0.650514 -0.40636 0.575708 -0.697592 -0.426527 0.805187 -0.55178 -0.217286 0.849346 -0.445185 -0.283587 0.891417 -0.388226 -0.233789 0.946585 -0.179586 -0.267817 0.938297 -0.190491 -0.288637 0.97139 0.0335249 -0.23511 0.963017 0.0306568 -0.267691 0.146442 -0.144725 0.978575 0.824717 0.453528 0.337867 0.65139 -0.154723 0.7428 0.942264 0.12178 0.311944 0.971801 0.0640838 0.226928 0.978816 0.0630426 0.194793 0.98931 0.00335758 0.145788 0.993672 -0.0111844 0.11176 0.851108 -0.184035 0.491677 0.873455 -0.0822318 0.47991 0.889413 -0.0436082 0.455019 0.901405 0.000974702 0.432975 0.8953 -0.0017101 0.445461 0.918228 0.0498845 0.392898 0.741738 0.375082 0.556002 0.782193 0.363247 0.506187 0.708896 0.216188 0.671364 0.911966 0.0516478 0.407003 0.938587 0.0772291 0.336288 0.786962 0.484191 0.382427 0.849348 0.481719 0.215765 0.792191 0.602183 0.0990428 0.856725 0.499345 -0.129139 0.843569 0.512626 -0.160018 0.88401 0.300034 -0.358477 0.877481 0.300534 -0.373774 0.921867 0.0984963 0.374779 0.959989 0.062314 0.273017 0.891441 0.408767 0.195558 0.944652 0.327789 0.0136845 0.941308 0.337456 -0.00796349 0.970892 0.188209 -0.148145 0.965072 0.191329 -0.178967 0.115188 0.642136 -0.757887 0.0768078 0.815648 -0.573427 0.146658 0.827026 -0.542696 0.0529587 0.974365 -0.218649 0.148669 0.974162 -0.170019 0.0857648 0.996124 0.0195123 0.146324 0.96595 0.213378 0.333936 0.510368 -0.792472 0.105771 0.531777 -0.840253 0.296921 0.458807 -0.837457 0.0132454 0.577434 0.81633 0.298957 0.585573 0.753478 0.108627 0.480305 0.870349 0.143129 0.966244 0.214212 0.0595986 0.897593 0.436778 0.223317 0.800024 0.556859 0.243341 0.800613 0.547543 0.107836 0.775381 0.622218 0.0837615 0.441339 0.893423 0.0301579 0.252684 0.967079 0.178765 0.196831 0.964002 0.111639 -0.161409 0.980553 0.34147 -0.160402 0.926104 0.692779 -0.12528 0.710184 0.714415 0.0459147 0.698214 0.412913 0.127676 0.901777 0.487264 0.37658 0.787884 0.353595 0.480085 0.802801 0.447577 0.666532 0.596163 0.377661 0.722834 0.578691 0.480022 0.818986 0.31439 0.412118 0.868429 0.275665 0.513931 0.857435 -0.0260951 0.45427 0.887738 -0.0745648 0.542567 0.747058 -0.384091 0.499065 0.75592 -0.423697 0.553205 0.473519 -0.685379 0.546579 0.472887 -0.691107 0.344653 0.512716 -0.786344 0.287803 0.807712 -0.514559 0.346284 0.807597 -0.477361 0.253026 0.955323 -0.15276 0.332858 0.937417 -0.102247 0.223299 0.949245 0.221521 0.313047 0.911289 0.267495 0.200944 0.805924 0.556873 0.291654 0.757177 0.584483 0.187452 0.549996 0.813859 0.26927 0.50587 0.819506 0.179685 0.196962 0.963805 0.463498 0.14929 0.873431 0.425022 -0.140064 0.894281 0.484351 -0.166405 0.858903 0.870899 -0.14645 0.469135 0.892968 -0.0631329 0.445672 0.690173 0.0305592 0.722999 0.744781 0.22253 0.629112 0.503279 0.374675 0.778671 0.593137 0.550556 0.587432 0.545212 0.607147 0.578027 0.633566 0.690133 0.349729 0.588803 0.742594 0.319164 0.677986 0.733077 0.0541631 0.639884 0.768384 0.0115803 0.718474 0.64288 -0.26552 0.691092 0.65625 -0.302868 0.739779 0.401305 -0.540076 0.726919 0.401321 -0.557252 -0.146146 -0.351407 0.924746 -0.826272 -0.558156 0.0757436 -0.651407 -0.220027 0.726125 -0.992269 -0.0754647 0.0985307 -0.992328 -0.0362277 0.118209 -0.976263 -0.161395 0.14444 -0.978909 -0.14338 0.145533 -0.963225 -0.19494 0.184923 -0.851018 -0.0632125 0.521318 -0.880894 -0.160789 0.445165 -0.902137 -0.208492 0.377731 -0.895768 -0.210766 0.39138 -0.919311 -0.231151 0.31849 -0.740533 -0.594909 0.312561 -0.783609 -0.561049 0.266799 -0.707952 -0.509456 0.48914 -0.918517 -0.232047 0.320126 -0.938741 -0.233191 0.253747 -0.7859 -0.608947 0.107451 -0.847485 -0.529736 -0.0339026 -0.793258 -0.574367 -0.202097 -0.856962 -0.376621 -0.351813 -0.844208 -0.371823 -0.386085 -0.884162 -0.0918174 -0.458069 -0.877675 -0.08401 -0.471835 -0.945946 -0.219243 0.238995 -0.960045 -0.204863 0.190645 -0.891347 -0.452751 -0.0227574 -0.944831 -0.29416 -0.144098 -0.94185 -0.290701 -0.168556 -0.970926 -0.0958948 -0.219331 -0.965172 -0.0816674 -0.248542 -0.115171 -0.201028 -0.972792 -0.0771108 -0.440597 -0.894387 -0.146472 -0.466795 -0.872151 -0.0440684 -0.77214 -0.633922 -0.0575972 -0.77543 -0.628802 -0.0997504 -0.908448 -0.405921 -0.181846 -0.945989 -0.268398 -0.333998 -0.0680377 -0.940115 -0.105774 -0.0649944 -0.992264 -0.278887 -0.0015634 -0.960323 -0.0122587 -0.896511 0.442853 -0.315845 -0.875183 0.366465 -0.112674 -0.843899 0.524538 -0.136042 -0.957456 -0.254502 -0.0636749 -0.996349 -0.0568748 -0.202699 -0.973853 0.102583 -0.248194 -0.965186 0.0825522 -0.108773 -0.978953 0.17268 -0.0842364 -0.816047 0.571814 -0.0328951 -0.692284 0.720875 -0.190438 -0.633586 0.749868 -0.0911701 -0.328111 0.940229 -0.34151 -0.302701 0.8898 -0.694 -0.234664 0.680659 -0.714757 -0.375778 0.589842 -0.412187 -0.541743 0.732541 -0.4869 -0.705809 0.51455 -0.354187 -0.805859 0.474492 -0.447653 -0.87022 0.20573 -0.378529 -0.91143 0.16128 -0.480148 -0.869645 -0.114782 -0.413118 -0.893769 -0.174673 -0.514078 -0.74067 -0.432587 -0.455183 -0.742556 -0.491345 -0.54269 -0.472338 -0.694539 -0.49964 -0.459511 -0.734309 -0.553285 -0.0877495 -0.828357 -0.546673 -0.0841343 -0.833108 -0.344677 -0.0734709 -0.935842 -0.288261 -0.461659 -0.838914 -0.346234 -0.48094 -0.805493 -0.253711 -0.764708 -0.592328 -0.332832 -0.774528 -0.537894 -0.224023 -0.93904 -0.260801 -0.313028 -0.928361 -0.200399 -0.20153 -0.974108 0.102463 -0.291647 -0.944399 0.151828 -0.187829 -0.872636 0.450806 -0.269311 -0.835867 0.478328 -0.179227 -0.633021 0.753102 -0.463837 -0.550711 0.693954 -0.425684 -0.307727 0.850939 -0.484453 -0.26447 0.833883 -0.875378 -0.0999686 0.47299 -0.889598 -0.164268 0.426182 -0.689728 -0.371017 0.62179 -0.7457 -0.497552 0.443141 -0.502673 -0.700433 0.506669 -0.593282 -0.763936 0.253807 -0.546272 -0.809289 0.21596 -0.633754 -0.773225 -0.0218593 -0.589996 -0.803794 -0.0762876 -0.678237 -0.669734 -0.30241 -0.640946 -0.678711 -0.358525 -0.718704 -0.43751 -0.540416 -0.691735 -0.429681 -0.580411 -0.739911 -0.0940378 -0.6661 -0.727062 -0.0849122 -0.681301 -0.572881 0.0241339 0.819283 -0.850727 -0.0482631 0.523388 -0.879517 0.0715152 0.470463 -0.654678 0.112045 0.747558 -0.765008 0.0954605 0.636907 -0.845143 0.0758494 0.529131 -0.851114 0.047813 0.522799 -0.850696 0.0154778 0.52543 -0.850699 0.0154771 0.525425 -0.851117 -0.0169475 0.524702 -0.345808 0.139082 0.92794 -0.488398 0.129346 0.862981 -0.149198 0.146568 0.977884 -0.201914 0.141718 0.969096 -0.201873 0.0288376 0.978987 -0.844351 -0.0480917 0.533628 -0.654674 -0.0678493 0.75286 -0.573002 -0.069056 0.81664 -0.488419 -0.0783237 0.869087 -0.345819 -0.0842201 0.934514 -0.573011 0.117003 0.811153 -0.57289 0.0241327 0.819277 -0.201879 0.0288371 0.978986 -0.201918 -0.0844298 0.975756 -0.149208 -0.0887536 0.984815 -0.340881 0.0843826 -0.936312 -0.994035 0.00321126 0.109015 -0.994036 -0.0100131 0.108588 -0.99425 -0.0096113 0.106647 -0.991754 0.01926 0.126702 -0.996676 0.00741752 0.0811267 -0.658675 -0.0221547 -0.752101 -0.931791 -0.0106881 -0.362838 -0.994046 0.0142424 0.108031 -0.993745 -0.016553 -0.110439 -0.971836 -0.034931 -0.233055 -0.994056 -0.00351568 0.108814 -0.994035 0.00321122 0.109015 -0.931791 -0.010688 -0.362837 -0.93164 -0.0603072 -0.358344 -0.558464 0.0883609 -0.82481 -0.739302 0.0604404 -0.670656 -0.931791 0.0325815 -0.36153 -0.888072 0.0527962 -0.456662 -0.971842 0.0211502 -0.234683 -0.237288 -0.0286031 -0.971018 -0.237288 0.087194 -0.967518 -0.108125 0.103753 -0.988708 -0.887837 -0.0682074 -0.455075 -0.7393 -0.0998119 -0.665938 -0.658464 -0.118137 -0.743283 -0.558103 -0.122994 -0.820605 -0.340893 -0.139348 -0.929717 -0.658678 0.0675366 -0.749388 -0.658678 -0.0221543 -0.752099 -0.237289 -0.0286029 -0.971018 -0.237193 -0.150573 -0.959723 -0.108042 -0.147359 -0.983164 -0.939507 0.0514766 0.338638 -0.939609 0.0724838 0.334487 -0.939483 0.0726906 0.334796 -0.939572 0.0723805 0.334613 -0.93969 0.071312 0.334511 -0.939848 0.0723738 0.333838 -0.939866 0.0724045 0.333779 -0.939727 0.0724164 0.334168 -0.939513 -0.0314506 0.341065 -0.940506 -0.0508029 0.335959 -0.939695 -0.0521807 0.338009 -0.939886 -0.0526714 0.337401 -0.93969 -0.0517048 0.338096 -0.939537 -0.0526991 0.338368 -0.9395 -0.0528216 0.338451 -0.939512 -0.0527895 0.338422 -0.939749 -0.0525777 0.337798 -0.939508 -0.0314518 0.34108 -0.939511 -0.0314518 0.341072 -0.939693 -0.0110445 0.341839 -0.939693 -0.0110412 0.34184 -0.939497 0.0100863 0.342407 -0.939498 0.010086 0.342406 -0.939694 0.0311412 0.340597 -0.939693 0.0311495 0.340597 -0.939511 0.0514761 0.338629 -0.939514 0.0514736 0.338619 -0.939697 0.0715381 0.334443 0 0.992925 -0.118741 0.0289431 0.968957 -0.24553 0.00936128 0.952651 -0.303922 -0.00448622 0.878364 -0.477971 0.0231675 0.773821 -0.63298 0.0032545 0.739345 -0.673319 -0.000779973 0.596214 -0.802825 0.0154092 0.43287 -0.901325 -0.000838723 0.397589 -0.917563 0.00100317 0.0102868 -0.999947 0 0.00822053 -0.999966 -0.698525 0.693662 -0.175772 -0.698526 0.693661 -0.175771 -0.698528 0.553882 -0.453071 -0.698522 0.553885 -0.453077 -0.698523 0.309793 -0.645053 -0.69853 0.309792 -0.645047 -0.698529 0.00736107 -0.715544 -0.698525 0.00735952 -0.715548 0 -0.999078 -0.0429379 -0.0176535 -0.98279 -0.18388 -0.00801399 -0.974872 -0.222622 0.00276849 -0.915505 -0.402297 -0.0133484 -0.817412 -0.575899 -0.00232065 -0.793577 -0.608466 0.00040502 -0.661878 -0.749611 -0.00838759 -0.503973 -0.863679 0.00230323 -0.47259 -0.881279 -0.0025495 -0.0992411 -0.99506 0 -0.0913601 -0.995818 0.698862 -0.0709805 -0.711726 0.69887 -0.0709823 -0.711718 0.703802 -0.309076 -0.639637 0.78784 -0.310398 -0.531941 0.698867 -0.703052 -0.131541 0.698864 -0.703055 -0.131542 0.698866 -0.584708 -0.41195 0.698858 -0.584713 -0.411957 0.706013 -0.436736 -0.557501 0 0.0668025 -0.997766 0.0420201 0.0427264 -0.998203 0 -0.00537309 -0.999986 0 -0.101498 -0.994836 0.0629304 -0.125169 -0.990138 0 -0.0534976 -0.998568 0.706168 0.0718652 0.704388 0.706166 0.0718653 0.70439 0.706165 -0.0302791 0.7074 0.706175 -0.0302783 0.70739 0.00152333 -0.546002 0.837783 -0.0135952 -0.345428 0.938347 -0.0104198 -0.337665 0.941209 0 -0.140819 0.990035 -0.00712822 -0.701222 0.712908 -0.0225391 -0.736511 0.67605 0.00163125 -0.843114 0.537733 0 -0.989076 0.147407 -0.0252473 -0.964213 0.263924 -0.00606041 -0.936829 0.349736 -0.000610019 -0.893741 0.448582 0 -0.0280606 -0.999606 -0.0262988 0.0877584 -0.995795 -0.0108381 0.172999 -0.984862 0.0197298 0.481997 -0.875951 -0.0045962 0.998716 -0.0504605 6.69912e-05 0.996956 -0.0779625 -8.65303e-05 0.956125 -0.292958 0.00524272 0.948432 -0.316937 -0.00480695 0.847716 -0.530429 -0.0129968 0.869922 -0.493017 0.020839 0.692272 -0.721336 0.0041652 0.732058 -0.681229 -0.00493712 0.415619 -0.909526 0 0.422047 0.906574 -0.0272105 0.371859 0.92789 0.0218237 0.75165 0.659201 -0.00552114 0.704444 0.709738 5.12061e-06 0.836032 0.54868 -6.35312e-06 0.896868 0.442298 -0.014715 0.862005 0.506686 0.0291928 0.977338 0.209663 -0.0251784 0.93886 0.343377 0.00322821 0.993581 0.113076 0.994042 0.0136699 0.108135 0.971849 -0.0295486 -0.233743 0.658909 -0.0221482 -0.751897 0.108088 0.0664111 -0.991921 0.558288 0.0554218 -0.827794 0.341059 0.0627964 -0.937942 0.237322 0.0732129 -0.968668 0.237618 -0.0052192 -0.971345 0.153986 -0.0290925 -0.987645 0.237619 -0.0519653 -0.969967 0.237424 -0.121831 -0.963736 0.887896 0.0307318 -0.459017 0.739454 0.0449715 -0.671704 0.108166 -0.142807 -0.983822 0.341056 -0.117897 -0.93262 0.658909 -0.0943412 -0.746283 0.558598 -0.121385 -0.820509 0.739455 -0.0844314 -0.667891 0.971846 0.0157397 -0.235092 0.931702 0.0324161 -0.361773 0.931867 -0.0106823 -0.362643 0.658689 0.0585833 -0.750131 0.658911 -0.0221484 -0.751895 0.931867 -0.0106823 -0.362643 0.931867 -0.0455013 -0.359936 0.88809 -0.0720504 -0.453987 0.994042 -0.00728107 0.108752 0.994042 -0.00728103 0.108751 0.994053 0.000584807 0.1089 0.994978 0.0029472 0.100052 0.994053 0.00582545 0.108745 0.994042 0.0136699 0.108134 0 0.137351 0.990523 -0.126162 0.0649901 0.989879 0 0.101498 0.994836 0 -0.00666479 0.999978 -0.0635014 -0.0426779 0.997069 0 -0.0788078 0.99689 0.127347 -0.331339 0.934878 0.05693 -0.932896 0.355617 0.891414 -0.453113 -0.00835613 0.893722 -0.175071 0.41305 0.900887 -0.216583 0.376157 0.982611 -0.129237 0.133318 0.968948 -0.172336 0.177314 0.959187 -0.199971 0.199932 0.955083 -0.200837 0.217901 0.937215 -0.228312 0.263632 0.963018 -0.107295 -0.247152 0.971391 -0.0885227 -0.220373 0.876438 -0.108495 -0.469132 0.884046 -0.100001 -0.456577 0.858962 -0.37482 -0.348846 0.839074 -0.401409 -0.367187 0.946585 -0.289435 -0.142144 0.938298 -0.309288 -0.154721 0.978164 -0.137846 0.155543 0.993506 -0.0397312 0.106621 0.993503 -0.0456233 0.104263 0.712671 -0.333959 0.616904 0.884953 -0.154939 0.43915 0.885791 -0.149147 0.439465 0.792147 -0.582784 -0.181291 0.849348 -0.527331 -0.0230014 0.805187 -0.586497 0.0877181 0.812778 -0.564731 0.143076 0.75974 -0.582137 0.289675 0.771369 -0.542816 0.332177 0.722825 -0.504771 0.471944 0.133809 -0.982607 0.128758 0.275288 -0.832671 0.480496 0.447044 -0.467893 0.762383 0.0443566 -0.697787 0.714931 0.119356 -0.869688 0.478954 0.332106 -0.777916 0.533434 0.193003 -0.867845 0.457816 0.933083 -0.221858 0.283081 0.918216 -0.226757 0.324747 0.916084 -0.228504 0.329509 0.902775 -0.191595 0.385083 0.738162 -0.460836 0.492694 0.69772 -0.366268 0.615658 0.461105 -0.498622 0.734001 0.105758 -0.0987402 -0.989477 0.121172 -0.0937857 -0.988191 0.0859211 -0.494844 -0.864724 0.151877 -0.476484 -0.865966 0.0947203 -0.665438 -0.740419 0.147687 -0.794778 -0.588657 0.148846 -0.79446 -0.588794 0.223977 -0.959661 0.169957 0.0681527 -0.99708 -0.0344534 0.14354 -0.959536 -0.242253 0.246945 -0.951194 -0.185064 0.0723562 -0.916398 -0.393674 0.353644 -0.788893 0.502576 0.456009 -0.866789 0.201825 0.36412 -0.904051 0.223848 0.489608 -0.863721 -0.11946 0.398082 -0.9105 -0.111894 0.521641 -0.73514 -0.432966 0.443193 -0.780028 -0.441743 0.546139 -0.475449 -0.689696 0.493423 -0.505614 -0.707735 0.553284 -0.113088 -0.82528 0.546198 -0.116215 -0.829555 0.177309 -0.844657 0.505091 0.301516 -0.941851 0.148342 0.187418 -0.967542 0.16952 0.324411 -0.923449 -0.204936 0.209395 -0.958472 -0.193614 0.342325 -0.770137 -0.538241 0.242331 -0.806428 -0.539397 0.351088 -0.48571 -0.800514 0.282729 -0.512662 -0.810704 0.344993 -0.100987 -0.933157 0.333638 -0.105339 -0.936797 0.149393 -0.138772 0.978991 0.188407 -0.289278 0.938521 0.341469 -0.271719 0.89976 0.425001 -0.275627 0.862209 0.484341 -0.236228 0.842384 0.687668 -0.183374 0.702486 0.647364 -0.239774 0.723483 0.870205 -0.0317157 0.491668 0.850011 -0.110742 0.514992 0.172312 -0.607853 0.775127 0.179707 -0.608097 0.773255 0.423341 -0.540601 0.727002 0.487229 -0.689705 0.535644 0.503295 -0.683859 0.528234 0.600298 -0.759837 0.24958 0.53266 -0.801517 0.271742 0.641647 -0.766536 -0.0266648 0.575695 -0.817405 -0.0205891 0.684248 -0.663231 -0.3032 0.629496 -0.710391 -0.314769 0.721187 -0.438407 -0.536366 0.685632 -0.468594 -0.557072 0.739822 -0.108098 -0.664062 0.725687 -0.117681 -0.677887 0.146446 0.363957 0.919831 0.824721 0.561694 0.0658358 0.651397 0.237408 0.720638 0.942263 0.261439 0.209263 0.971801 0.16896 0.164483 0.978816 0.151992 0.137175 0.98931 0.0758014 0.124578 0.993672 0.0461935 0.10238 0.851105 0.086458 0.517827 0.873462 0.168739 0.456719 0.889409 0.189729 0.415878 0.901407 0.21733 0.374478 0.895302 0.221247 0.386631 0.918229 0.239648 0.315318 0.741743 0.602827 0.293967 0.782189 0.567679 0.256753 0.708892 0.522911 0.473324 0.911963 0.248231 0.326657 0.938587 0.235027 0.252619 0.786961 0.610537 0.0890967 0.849347 0.525065 -0.054 0.792188 0.57103 -0.21532 0.856723 0.367877 -0.361514 0.84357 0.36394 -0.394888 0.884012 0.0805974 -0.460464 0.877482 0.0733822 -0.473962 0.921871 0.272682 0.275315 0.959989 0.190473 0.205283 0.891439 0.451785 -0.0350242 0.944652 0.290714 -0.152044 0.941309 0.288262 -0.175622 0.970892 0.0889222 -0.222399 0.965072 0.0762117 -0.250655 0.115192 0.177158 -0.977418 0.0768107 0.419659 -0.904426 0.146669 0.444881 -0.883498 0.052974 0.7345 -0.676537 0.148679 0.758637 -0.634322 0.0857688 0.872432 -0.481151 0.146322 0.943225 -0.298187 0.333942 0.0457565 -0.941482 0.10576 0.0404065 -0.99357 0.296923 -0.0213925 -0.954662 0.143117 0.943899 -0.297611 0.0595891 0.995728 -0.0705319 0.223305 0.971273 0.082245 0.116201 0.985257 0.125559 0.0132472 0.908239 0.418241 0.298954 0.883862 0.359742 0.108587 0.851122 0.513615 0.0837889 0.828975 0.552974 0.0301556 0.702366 0.711177 0.178766 0.652456 0.73644 0.111645 0.350498 0.929885 0.341464 0.324148 0.882231 0.692773 0.246594 0.677685 0.71441 0.388874 0.581718 0.412917 0.561457 0.717123 0.487269 0.720066 0.494039 0.353594 0.817167 0.455203 0.447576 0.875317 0.183021 0.377674 0.915332 0.139747 0.480035 0.866452 -0.137213 0.412115 0.889914 -0.195486 0.513925 0.729516 -0.451317 0.454266 0.731524 -0.508443 0.542565 0.454925 -0.706163 0.499059 0.442795 -0.744898 0.553199 0.067388 -0.830319 0.546579 0.0639796 -0.83496 0.34466 0.0508551 -0.937349 0.287811 0.442222 -0.849473 0.346277 0.460717 -0.81721 0.253017 0.750953 -0.60996 0.332865 0.760705 -0.557252 0.223305 0.932829 -0.282781 0.313051 0.922945 -0.223989 0.200947 0.976386 0.0793086 0.291649 0.947978 0.12759 0.187446 0.883243 0.429821 0.269275 0.847848 0.456778 0.179695 0.652471 0.736201 0.463496 0.566002 0.681772 0.42502 0.325848 0.844501 0.484354 0.285344 0.827031 0.870902 0.107742 0.479502 0.892969 0.16816 0.417528 0.690169 0.387968 0.610858 0.744778 0.507277 0.433562 0.503295 0.713805 0.487008 0.593146 0.770502 0.233462 0.545199 0.814829 0.197006 0.633554 0.772547 -0.0422052 0.588807 0.802685 -0.0948866 0.67799 0.661942 -0.319628 0.639891 0.671228 -0.374156 0.71848 0.423992 -0.551378 0.69109 0.416895 -0.590418 0.739777 0.0775004 -0.668374 0.726918 0.0689269 -0.683257 0.939621 0.0470035 0.338973 0.939565 -0.0228709 0.341605 0.938417 -0.0397583 0.34321 0.939692 -0.0408184 0.339578 0.939395 -0.0419449 0.340263 0.939414 -0.0418825 0.340217 0.939895 -0.0414865 0.338933 0.939967 -0.0416771 0.338712 0.939946 -0.0416368 0.338774 0.939758 -0.041605 0.3393 0.939565 -0.0416654 0.339825 0.939622 0.0615697 0.336631 0.939836 0.0614677 0.33605 0.940959 0.0586498 0.3334 0.939692 0.0607067 0.336592 0.939965 0.0615307 0.335679 0.939975 0.0615571 0.335644 0.939693 0.0602286 0.336674 0.939472 0.0616719 0.337029 0.939449 0.0617336 0.337081 0.939566 0.0429391 0.339664 0.94337 0.0433306 0.328901 0.936007 0.0188286 0.351478 0.939622 0.0224197 0.341478 0.939661 0.00183714 0.342103 0.937285 -0.00232331 0.348556 0.94337 -0.0238955 0.330881 0.939621 -0.026969 0.341152 0.939692 -0.0402858 0.33964 0.149348 0.13581 0.979414 0.488786 0.119824 0.864136 0.34611 -0.0739375 0.935276 0.655058 -0.0595448 0.753229 0.850962 -0.0413915 0.523593 0.850962 -0.0413916 0.523594 0.850962 -0.0035009 0.525216 0.850962 -0.00350083 0.525216 0.850962 0.03441 0.524099 0.850961 0.0344098 0.524101 0.850961 0.0721404 0.520251 0.85096 0.0721404 0.520252 0.655069 0.103778 0.748408 0.573439 0.105092 0.81248 0.573328 0.0536778 0.817566 0.573323 0.0536771 0.817569 0.573323 -0.00546124 0.819311 0.573332 -0.00545965 0.819305 0.573443 -0.057085 0.817254 0.488778 -0.068753 0.869695 0.346106 0.128861 0.929304 0.202136 0.128773 0.970855 0.202098 0.0641616 0.977261 0.202098 0.0641617 0.977261 0.202099 -0.00652611 0.979343 0.202091 -0.00652727 0.979345 0.202129 -0.0714041 0.976752 0.149347 -0.077924 0.985709 -0.707108 0.103605 -0.699474 -0.671187 0.064694 -0.73846 -0.706467 0.0635255 -0.704889 -0.706467 -0.0208389 -0.707439 -0.70647 -0.020839 -0.707436 -0.706522 -0.103152 -0.700133 -0.672814 -0.10966 -0.731639 -0.7071 -0.144598 -0.692171 -0.706471 -0.0635258 0.704885 -0.706467 -0.0635259 0.704889 -0.706467 0.0208387 0.707439 -0.70647 0.0208385 0.707436 -0.706471 0.104907 0.699924 -0.706477 0.104905 0.699917 -0.697446 0.305506 0.648256 -0.697437 0.305512 0.648262 -0.697435 0.563298 0.443034 -0.697442 0.563291 0.443032 -0.69744 0.701997 0.144144 -0.697441 0.701997 0.144144 -0.69474 -0.287589 0.659265 -0.487527 -0.867612 0.0978101 -0.694737 -0.287589 0.659268 -0.70291 -0.523181 0.481871 -0.494601 -0.699262 0.516141 -0.705007 -0.628232 0.329075 -0.70369 -0.690867 0.165901 -0.704396 -0.709565 -0.0185347 -0.704396 -0.683528 -0.191355 -0.487512 -0.800284 -0.34911 -0.694747 -0.0805687 -0.714727 -0.694735 -0.0805739 -0.714739 -0.702908 -0.357976 -0.614633 -0.494601 -0.516141 -0.699263 -0.705009 -0.503382 -0.499569 -0.703693 -0.61131 -0.362101 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.428779 0.903409 -0.00179748 0.426305 0.904578 0.00133612 0.747379 0.664397 0.0291317 0.785684 0.617941 -0.00212724 0.884506 0.466524 0.00441388 0.957962 0.28686 0.0346933 0.978973 0.201016 0 0.997421 0.0717794 0 0.00260725 -0.999997 0.0376682 -0.111938 -0.993001 0.0154209 -0.19797 -0.980087 -0.0283327 -0.503082 -0.863774 -1.01735e-05 -0.999659 -0.0261124 0.0268086 -0.997954 0.0580376 -7.32726e-05 -0.997999 -0.0632327 9.85315e-05 -0.962976 -0.269586 9.47478e-06 -0.962898 -0.269864 3.38268e-06 -0.860388 -0.509639 0.034173 -0.907185 -0.419342 -0.0536295 -0.708769 -0.703399 -0.00712462 -0.770876 -0.636946 0.00709768 -0.437629 -0.899128 0 -0.399838 0.916586 0.0329115 -0.358569 0.932923 -0.025127 -0.735317 0.677257 0.00777199 -0.694298 0.719646 -7.76547e-06 -0.822401 0.568908 5.56468e-06 -0.885831 0.464009 0.0188817 -0.854354 0.519348 -0.0358087 -0.971734 0.233347 0.0352499 -0.933485 0.35688 -2.37544e-05 -0.986521 0.163633 0 -0.0897584 0.995964 0 -0.0897584 0.995964 0 0.0294438 0.999566 0 0.0294438 0.999566 0 0.148227 0.988953 0 0.148227 0.988953 0 -0.148227 -0.988953 0 -0.148227 -0.988953 0 -0.029444 -0.999566 0 -0.029444 -0.999566 0 0.0897576 -0.995964 0 0.0897576 -0.995964 -0.879241 0.134579 0.456972 -0.887086 0.197572 0.417185 -0.954989 0.219652 0.199371 -0.960101 0.214612 0.1793 -0.978436 0.153668 0.138021 -0.978976 0.152147 0.135856 -0.991397 0.0655088 0.11332 -0.990797 0.0700126 0.115841 -0.96517 0.0668569 -0.252936 -0.793209 0.561556 -0.235532 -0.859469 0.338844 -0.38275 -0.839104 0.365863 -0.402553 -0.88419 0.0560235 -0.463756 -0.876485 0.0643506 -0.477109 -0.859293 0.493389 0.134845 -0.938545 0.24879 0.239243 -0.933193 0.246147 0.261845 -0.821647 0.569995 -0.000948916 -0.847485 0.526818 -0.0650517 -0.891281 0.450753 -0.0493898 -0.947044 0.273146 -0.168817 -0.938319 0.293726 -0.182437 -0.970911 0.0827507 -0.224686 -0.989048 0.0722732 -0.128685 -0.807334 0.445022 0.387516 -0.693241 0.68534 0.222992 -0.77072 0.637138 0.00677317 -0.902136 0.245941 0.354492 -0.887851 0.191801 0.418249 -0.749525 0.355387 0.558491 -0.710136 0.3664 0.601213 -0.27601 0.874572 0.398675 -0.037656 0.745343 0.665617 -0.0992966 0.8767 0.470677 -0.22088 0.889902 0.399108 -0.0485202 0.955526 0.290889 -0.133709 0.990314 0.037418 -0.146973 0.378874 0.913703 -0.070126 0.426285 0.901867 -0.105773 0.00639494 -0.99437 -0.0948735 0.0102138 -0.995437 -0.111689 0.413996 -0.903401 -0.149949 0.400949 -0.903745 -0.0929545 0.599121 -0.795244 -0.157222 0.736525 -0.657885 -0.147191 0.73989 -0.656428 -0.245704 0.964901 0.0927103 -0.062728 0.991682 -0.112396 -0.143398 0.933046 -0.329942 -0.246734 0.930563 -0.270508 -0.0700977 0.879166 -0.471332 -0.354222 0.832342 0.426303 -0.457108 0.881614 0.117509 -0.363198 0.920864 0.141761 -0.490852 0.847473 -0.202125 -0.397297 0.897049 -0.193539 -0.522601 0.689475 -0.50151 -0.442819 0.736763 -0.510971 -0.54659 0.407177 -0.731742 -0.493396 0.438287 -0.751308 -0.553364 0.0354342 -0.832185 -0.546229 0.0384992 -0.836751 -0.176407 0.887001 0.426743 -0.302667 0.951396 0.0569026 -0.186324 0.979068 0.0819087 -0.325666 0.898895 -0.293136 -0.208469 0.937338 -0.279175 -0.343255 0.714385 -0.609778 -0.241862 0.754191 -0.610491 -0.351513 0.406987 -0.84309 -0.282645 0.435939 -0.854441 -0.345026 0.0127958 -0.938506 -0.333674 0.0172658 -0.94253 -0.879553 0.13335 0.456731 -0.763496 0.204773 0.612489 -0.693958 0.274358 0.665695 -0.651407 0.262447 0.711892 -0.484425 0.313173 0.816857 -0.918285 0.254915 0.302938 -0.901026 0.269625 0.339785 -0.758736 0.536345 0.369668 -0.805285 0.481826 0.345484 -0.700533 0.617924 0.356965 -0.633828 0.468714 0.615281 -0.461119 0.563162 0.685725 -0.425666 0.357336 0.831336 -0.341498 0.354615 0.870418 -0.209212 0.677134 0.705492 -0.1792 0.67634 0.714459 -0.424086 0.606887 0.67219 -0.486861 0.734843 0.4722 -0.50267 0.729003 0.464627 -0.601395 0.779471 0.175352 -0.531849 0.823165 0.198834 -0.642821 0.759414 -0.100351 -0.575092 0.812651 -0.094165 -0.68523 0.630046 -0.365379 -0.629214 0.67901 -0.378199 -0.721677 0.384635 -0.575534 -0.685625 0.415268 -0.597888 -0.739941 0.0449755 -0.671167 -0.725685 0.0543033 -0.685881 0.694732 0.303561 0.652073 0.458488 0.88527 0.0780187 0.694749 0.303558 0.652056 0.702921 0.534752 0.468981 0.466749 0.724128 0.507724 0.70501 0.636057 0.313677 0.703692 0.6947 0.14903 0.694738 0.0631432 -0.716486 0.694742 0.0631416 -0.716482 0.702917 0.342898 -0.62316 0.782477 0.264442 -0.563738 0.561452 0.572986 -0.597042 0.701772 0.459169 -0.544683 0.703696 0.60231 -0.376875 0.458505 0.805666 -0.375068 0.704402 0.678659 -0.207942 0.704401 0.708898 -0.0358174 0.696945 -0.247738 0.672974 0.69695 -0.247735 0.672969 0.69695 -0.528301 0.484931 0.696947 -0.528304 0.484933 0.696945 -0.691682 0.189327 0.696944 -0.691682 0.189327 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706175 -0.0718645 -0.704381 0.706178 -0.071864 -0.704378 0.706179 0.0302784 -0.707386 0.706174 0.0302784 -0.707391 -0.698658 0.581583 0.416699 -0.69866 0.581581 0.416698 -0.69866 0.702901 0.133435 -0.698658 0.702902 0.133435 -0.694749 0.0805704 0.714725 -0.487525 -0.702472 0.51851 -0.694742 0.0805734 0.714732 -0.702915 -0.21215 0.678898 -0.494611 -0.347505 0.796618 -0.705013 -0.379524 0.599097 -0.703696 -0.515353 0.489105 -0.704397 -0.623769 0.338727 -0.704397 -0.687629 0.176044 -0.487524 -0.867614 0.0978052 -0.694742 -0.427143 -0.57869 -0.69474 -0.427145 -0.578691 -0.702915 -0.617329 -0.353294 -0.494623 -0.796612 -0.347503 -0.705009 -0.685724 -0.180956 -0.70369 -0.710462 -0.0079273 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.814246 0.58052 -0.00144101 0.812884 0.582423 0.00122345 0.976231 0.21673 0.0167216 0.982317 0.186478 0 0.999993 0.00384675 0 -0.497742 -0.867325 0.0376689 -0.593444 -0.803993 0.0154238 -0.661486 -0.749799 -0.0283313 -0.867571 -0.496506 -1.14266e-05 -0.878789 0.477211 0.0268125 -0.835229 0.549248 -7.14172e-05 -0.895908 0.444239 0.000100872 -0.968756 0.248017 1.16e-05 -0.968827 0.247737 5.40475e-06 -0.999938 -0.0111572 0.0341679 -0.995317 0.0904197 -0.0536335 -0.965508 -0.254788 -0.00712259 -0.986071 -0.166173 0.00709917 -0.828564 -0.55985 0 0.112023 0.993706 0.0329088 0.155927 0.98722 -0.0251276 -0.298174 0.954181 0.00777303 -0.241452 0.970382 -9.04101e-06 -0.427813 0.903867 4.50658e-06 -0.535148 0.844758 0.0188869 -0.480199 0.876956 -0.0358073 -0.724872 0.687952 0.0352433 -0.629992 0.775801 -2.47787e-05 -0.772525 0.634985 0 0.420249 0.907409 0 0.420249 0.907409 0 0.525282 0.850928 0 0.525282 0.850928 0 0.622845 0.782345 0 0.622845 0.782345 0 -0.622845 -0.782346 0 -0.622845 -0.782346 0 -0.525282 -0.850928 0 -0.525282 -0.850928 0 -0.420249 -0.907409 0 -0.420249 -0.907409 -0.879242 0.345034 0.32846 -0.887085 0.379698 0.262507 -0.954989 0.289909 0.0628357 -0.960101 0.275507 0.0479714 -0.978435 0.202092 0.0426952 -0.978976 0.199692 0.0415812 -0.991397 0.113391 0.0653834 -0.990797 0.118553 0.0653148 -0.965171 -0.0685648 -0.252475 -0.793207 0.368556 -0.484756 -0.859467 0.102073 -0.500896 -0.839105 0.115569 -0.531551 -0.884191 -0.183359 -0.429634 -0.876483 -0.182824 -0.445368 -0.859293 0.49471 -0.129915 -0.938545 0.335079 0.0827963 -0.933192 0.344092 0.103694 -0.821647 0.493156 -0.28582 -0.847485 0.423712 -0.319746 -0.891282 0.365668 -0.268149 -0.947044 0.152142 -0.282774 -0.938318 0.163156 -0.304859 -0.970911 -0.0406811 -0.23596 -0.989048 -0.00175486 -0.147585 -0.807335 0.579156 0.113091 -0.69324 0.705019 -0.149555 -0.770717 0.555167 -0.312705 -0.902135 0.390242 0.184022 -0.88785 0.375234 0.266312 -0.749529 0.587017 0.30597 -0.710138 0.617918 0.337465 -0.011939 0.877221 -0.479938 -0.276011 0.956739 -0.092022 -0.0335974 0.97525 0.218539 -0.0889126 0.995986 0.0102822 -0.188284 0.976653 -0.103427 0.0533249 0.97171 -0.230078 -0.267917 0.820205 -0.505454 -0.146984 0.784963 0.601855 -0.095337 0.809359 0.579524 -0.093754 0.118227 -0.988551 -0.149948 -0.104643 -0.983141 -0.111693 -0.093174 -0.989365 -0.0948801 -0.488876 -0.867178 -0.105766 -0.491646 -0.864348 -0.110859 0.174072 -0.978473 -0.174401 0.30983 -0.93466 -0.144209 0.321601 -0.935829 -0.143393 0.643072 -0.752261 -0.266612 0.674934 -0.688028 -0.0669739 0.533449 -0.843176 -0.354222 0.933981 -0.0469788 -0.457112 0.822253 -0.339041 -0.363192 0.868375 -0.337663 -0.490849 0.632871 -0.598784 -0.397288 0.680101 -0.616138 -0.522589 0.346351 -0.779064 -0.442823 0.382566 -0.810895 -0.546594 -0.0132445 -0.837293 -0.493391 0.00391709 -0.869799 -0.55336 -0.385407 -0.738413 -0.546232 -0.385036 -0.743894 -0.176404 0.981538 -0.0739285 -0.302661 0.852386 -0.426421 -0.186323 0.888851 -0.418601 -0.325668 0.631899 -0.703309 -0.20848 0.67217 -0.710439 -0.34327 0.313787 -0.88527 -0.241867 0.347906 -0.905793 -0.351519 -0.0690875 -0.933628 -0.282642 -0.0496864 -0.957938 -0.345022 -0.458172 -0.81917 -0.333671 -0.456313 -0.824889 -0.879553 0.343855 0.328864 -0.763484 0.483599 0.428047 -0.693959 0.570446 0.439331 -0.651409 0.58323 0.485294 -0.484422 0.679643 0.550836 -0.918285 0.37223 0.134896 -0.901026 0.403393 0.159453 -0.758734 0.649325 0.0519711 -0.805287 0.590013 0.0582878 -0.700529 0.713624 0.00017774 -0.633827 0.71356 0.29849 -0.461117 0.830577 0.312272 -0.425663 0.72513 0.541293 -0.341495 0.742314 0.576499 -0.193429 0.941276 0.27674 -0.179204 0.942957 0.280569 -0.424087 0.861674 0.278689 -0.486861 0.872492 0.0415193 -0.502665 0.863651 0.0378812 -0.601391 0.762721 -0.237876 -0.531854 0.812296 -0.239387 -0.642825 0.607495 -0.46661 -0.575094 0.656694 -0.487872 -0.685234 0.362943 -0.631448 -0.629211 0.398941 -0.667037 -0.721675 0.0453395 -0.690746 -0.685624 0.060691 -0.725421 -0.739941 -0.296636 -0.603734 -0.725682 -0.295915 -0.621144 -0.146152 0.158041 0.976557 -0.826272 -0.445503 0.344677 -0.651409 0.172505 0.738856 -0.992269 -0.0160863 0.123062 -0.992328 0.0277292 0.120486 -0.976263 -0.0675526 0.205785 -0.978909 -0.051404 0.197724 -0.963217 -0.0763734 0.257643 -0.851017 0.205914 0.483082 -0.880894 0.0833344 0.465919 -0.902136 0.00830733 0.431371 -0.895768 0.0131612 0.444326 -0.919312 -0.0409383 0.391395 -0.740534 -0.358928 0.568137 -0.78361 -0.352484 0.511576 -0.707952 -0.196631 0.678336 -0.918518 -0.0408961 0.393259 -0.938741 -0.075076 0.336346 -0.785898 -0.473637 0.397534 -0.847486 -0.475715 0.235504 -0.793261 -0.598463 0.112162 -0.856963 -0.502069 -0.116369 -0.844209 -0.515049 -0.148446 -0.884164 -0.308552 -0.350784 -0.877674 -0.308673 -0.366618 -0.945948 -0.0703714 0.316593 -0.960044 -0.0820919 0.267537 -0.891347 -0.403473 0.206665 -0.944831 -0.326799 0.0222896 -0.94185 -0.336033 -0.000623835 -0.970926 -0.192712 -0.142002 -0.965173 -0.194996 -0.174405 -0.11517 -0.660487 -0.741952 -0.0771111 -0.828764 -0.55426 -0.146468 -0.840334 -0.521907 -0.0440722 -0.985654 -0.162921 -0.0575841 -0.985942 -0.15685 -0.0997325 -0.989703 0.102672 -0.181839 -0.953449 0.240561 -0.334013 -0.528979 -0.780139 -0.105768 -0.55242 -0.826828 -0.278882 -0.481517 -0.830883 -0.0122385 -0.554975 0.831777 -0.315875 -0.574701 0.754945 -0.112667 -0.46855 0.876223 -0.136053 -0.956431 0.258321 -0.0636858 -0.891299 0.448921 -0.20271 -0.792087 0.575766 -0.248186 -0.794596 0.554095 -0.108755 -0.76145 0.639035 -0.0842652 -0.420855 0.903206 -0.0329095 -0.239093 0.970439 -0.19043 -0.173771 0.966199 -0.0911544 0.185969 0.978318 -0.341489 0.18276 0.921946 -0.693996 0.137103 0.706805 -0.714752 -0.0305061 0.698712 -0.412183 -0.102883 0.905274 -0.486898 -0.353974 0.798519 -0.354177 -0.460655 0.813853 -0.447646 -0.650769 0.613281 -0.378517 -0.708686 0.59539 -0.480138 -0.810535 0.335413 -0.413117 -0.861363 0.295614 -0.514076 -0.857734 -0.00429771 -0.455181 -0.888746 -0.0542401 -0.542687 -0.756329 -0.365318 -0.499636 -0.765105 -0.406175 -0.553283 -0.490168 -0.673509 -0.546671 -0.489412 -0.679431 -0.344674 -0.531543 -0.773732 -0.288259 -0.819267 -0.49569 -0.346233 -0.819254 -0.457106 -0.253711 -0.95842 -0.130622 -0.332843 -0.939704 -0.0785643 -0.224034 -0.943629 0.243667 -0.313027 -0.904184 0.29063 -0.201526 -0.792372 0.57579 -0.291646 -0.74196 0.603687 -0.187836 -0.530319 0.826728 -0.269303 -0.484723 0.832177 -0.179218 -0.171665 0.968717 -0.463849 -0.129953 0.876331 -0.425699 0.158968 0.890792 -0.484455 0.187895 0.8544 -0.875378 0.149918 0.459607 -0.889597 0.0708321 0.45122 -0.689728 -0.0104135 0.723994 -0.745701 -0.209322 0.632546 -0.502674 -0.353259 0.789004 -0.593284 -0.534687 0.601768 -0.546284 -0.592875 0.59167 -0.633763 -0.680552 0.367686 -0.589993 -0.734254 0.335825 -0.678234 -0.731214 0.0729707 -0.640943 -0.767046 0.0288617 -0.718702 -0.649104 -0.24926 -0.691736 -0.66232 -0.287807 -0.739913 -0.414487 -0.529839 -0.727058 -0.414185 -0.547575 -0.572885 0.43054 0.697451 -0.850726 0.219897 0.4774 -0.879517 0.297165 0.371675 -0.65468 0.470812 0.59138 -0.764996 0.401134 0.503858 -0.845144 0.330252 0.420316 -0.851115 0.302805 0.428851 -0.850697 0.276118 0.447296 -0.850697 0.276118 0.447296 -0.851115 0.247673 0.462885 -0.345806 0.584419 0.73408 -0.488394 0.543509 0.682693 -0.14921 0.615872 0.773588 -0.201917 0.607279 0.768402 -0.201877 0.514467 0.833408 -0.844349 0.225167 0.486184 -0.654676 0.317671 0.685919 -0.573005 0.348515 0.741756 -0.488425 0.366712 0.79181 -0.345796 0.394324 0.85143 -0.573004 0.506907 0.643981 -0.572883 0.430541 0.697452 -0.201874 0.514468 0.833408 -0.201915 0.41476 0.887245 -0.149216 0.415544 0.89725 -0.340897 -0.395076 -0.853056 -0.994035 0.0572885 0.0928042 -0.994036 0.0456225 0.0990472 -0.994251 0.0449998 0.0971643 -0.991754 0.0800305 0.100097 -0.996676 0.0469925 0.0665546 -0.65868 -0.395235 -0.640258 -0.93179 -0.190676 -0.308884 -0.994046 0.0663495 0.0864361 -0.993745 -0.0695561 -0.0873683 -0.971837 -0.146776 -0.184363 -0.994056 0.0513634 0.0959928 -0.994035 0.0572884 0.092804 -0.931791 -0.190676 -0.308884 -0.931639 -0.231401 -0.280183 -0.558458 -0.335883 -0.75849 -0.739297 -0.282987 -0.61103 -0.93179 -0.152549 -0.329386 -0.888071 -0.182609 -0.421881 -0.971843 -0.0990229 -0.213812 -0.23729 -0.51028 -0.826625 -0.237289 -0.408247 -0.881492 -0.108121 -0.404501 -0.908124 -0.887836 -0.286609 -0.360004 -0.739297 -0.419411 -0.526815 -0.658469 -0.473948 -0.58463 -0.558106 -0.516818 -0.649167 -0.34089 -0.585538 -0.735485 -0.658678 -0.316206 -0.682757 -0.658679 -0.395236 -0.640259 -0.237287 -0.51028 -0.826625 -0.23719 -0.610262 -0.755858 -0.108037 -0.619199 -0.777766 -0.939508 0.213899 0.26753 -0.939608 0.230019 0.253433 -0.939483 0.23035 0.253596 -0.939572 0.229991 0.253593 -0.93969 0.22901 0.25404 -0.939848 0.229597 0.252924 -0.939868 0.229594 0.252855 -0.939726 0.229801 0.253191 -0.939515 0.143294 0.311094 -0.940504 0.123982 0.316354 -0.939696 0.123814 0.318811 -0.939887 0.123087 0.318531 -0.93969 0.124277 0.31865 -0.939537 0.123551 0.319384 -0.939489 0.123468 0.319555 -0.939514 0.123495 0.319473 -0.93975 0.123366 0.318827 -0.939508 0.143302 0.31111 -0.939511 0.143298 0.311103 -0.939693 0.161359 0.301562 -0.939694 0.161356 0.301563 -0.939498 0.179938 0.29149 -0.939498 0.179938 0.29149 -0.939694 0.197272 0.279392 -0.939694 0.197274 0.279391 -0.939511 0.213894 0.267523 -0.939515 0.213887 0.267516 -0.939697 0.229175 0.253867 0 0.974141 -0.22594 0.0148615 0.967104 -0.253946 -0.00923946 0.837281 -0.546694 0.0320469 0.757019 -0.652606 -5.1331e-05 0.166629 -0.98602 0.000460085 0.313089 -0.949724 0.0292584 0.393531 -0.918846 -0.00285326 0.529479 -0.848318 0.00336195 0.680371 -0.73286 0.00141531 0.111702 -0.993741 0.0215484 -0.0499872 -0.998517 -0.00415948 -0.114269 -0.993441 0.00518558 -0.483539 -0.875308 0 -0.492868 -0.870104 -0.697828 0.69278 -0.181913 -0.697826 0.692781 -0.181913 -0.697827 0.542506 -0.46768 -0.697824 0.542508 -0.467683 -0.697823 0.281996 -0.658424 -0.697829 0.281995 -0.658417 -0.697831 -0.0358123 -0.715367 -0.697824 -0.0358149 -0.715373 -0.697824 -0.346348 -0.626964 -0.697831 -0.346343 -0.626959 0 -0.993057 -0.117637 -0.0121579 -0.985654 -0.168341 -0.000277885 -0.951406 -0.307939 0.00108169 -0.843852 -0.536575 -0.00248106 -0.849734 -0.527205 0.000125074 -0.719867 -0.694112 -0.00291315 -0.570571 -0.821243 0 -0.562413 -0.826856 0.700048 -0.703903 -0.120221 0.700044 -0.407446 -0.586452 0.700045 -0.407445 -0.586451 0.702983 -0.581764 -0.409103 0.763184 -0.545281 -0.346725 0.706719 -0.647649 -0.284777 0.700047 -0.703904 -0.120221 0.694743 0.58892 0.412923 0.458493 0.805672 -0.375069 0.694739 0.588923 0.412926 0.702914 0.697606 0.13877 0.466759 0.88097 0.0776386 0.705015 0.707675 -0.0463747 0.703697 0.676138 -0.218284 0.694737 -0.30356 -0.652067 0.694738 -0.30356 -0.652066 0.702913 -0.0146213 -0.711125 0.782475 -0.0528555 -0.620435 0.561448 0.1977 -0.803549 0.701773 0.125309 -0.701294 0.703698 0.333175 -0.627537 0.4585 0.510195 -0.727653 0.704399 0.483767 -0.519414 0.704398 0.596018 -0.385468 0.696417 -0.691024 0.193623 0.696415 -0.691025 0.193623 0.703792 -0.564066 0.431865 0.504592 -0.625391 0.595209 0.696411 0.117769 0.707914 0.696414 0.11777 0.707911 0.703789 -0.151831 0.693995 0.50459 -0.273738 0.818814 0.705063 -0.314269 0.635705 0.705064 -0.442379 0.554243 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706175 -0.414427 -0.57408 0.706179 -0.414425 -0.574077 0.706178 -0.327471 -0.627754 0.706174 -0.327473 -0.627757 0 -0.441031 -0.897492 0.0420194 -0.462099 -0.885832 0 -0.504645 -0.863327 0 -0.585318 -0.810804 0.0629309 -0.603468 -0.7949 0 -0.545614 -0.838037 0.70618 0.414424 0.574075 0.706178 0.414425 0.574077 0.706179 0.327471 0.627753 0.706174 0.327473 0.627758 0 0.204823 0.978799 -0.0159034 0.164085 0.986318 -2.53337e-05 -0.0371525 0.99931 -5.30585e-06 -0.213723 0.976894 2.33433e-05 -0.213831 0.976871 -3.01448e-05 -0.443167 0.896439 0.00193344 -0.451955 0.892039 -0.00175557 -0.62382 0.781566 -9.8177e-06 -0.631455 0.775412 1.24798e-05 -0.79269 0.609625 -0.00049217 -0.794004 0.607912 0.000221595 -0.893829 0.448408 -0.0176339 -0.962765 0.269763 0 -0.976146 0.217117 0 -0.524106 -0.851653 -0.0262989 -0.421897 -0.906262 -0.0108372 -0.342605 -0.939417 0.0197298 -0.0205525 -0.999594 -0.00459547 0.839684 -0.543056 6.76391e-05 0.82441 -0.565994 -8.61126e-05 0.68155 -0.731771 0.00524318 0.662898 -0.748691 -0.00480644 0.468926 -0.883224 -0.0129958 0.506861 -0.86193 0.0208394 0.238857 -0.970831 0.00416573 0.293366 -0.955991 -0.00493646 -0.0948235 -0.995482 0 0.818788 0.574097 -0.0272096 0.785983 0.617649 0.021825 0.98055 0.195054 -0.00552155 0.964936 0.262426 3.42277e-06 0.998363 0.057201 -8.10327e-06 0.99786 -0.0653909 -0.0147151 0.999861 0.00779415 0.0291926 0.951231 -0.307095 -0.025179 0.984765 -0.172057 0.0032283 0.917004 -0.398865 0.994042 0.0659055 0.086812 0.97185 -0.14246 -0.187651 0.658909 -0.395129 -0.640087 0.108086 -0.438447 -0.892234 0.558293 -0.365899 -0.744599 0.341058 -0.414587 -0.843681 0.237328 -0.420929 -0.875496 0.237624 -0.490191 -0.838599 0.153989 -0.519017 -0.840779 0.237619 -0.529987 -0.814034 0.237424 -0.587377 -0.773704 0.887896 -0.202894 -0.412886 0.739452 -0.296906 -0.6042 0.10817 -0.615585 -0.780611 0.341051 -0.568414 -0.748726 0.658909 -0.454844 -0.599129 0.5586 -0.515376 -0.649888 0.739456 -0.407064 -0.536193 0.971845 -0.103916 -0.211469 0.931702 -0.152813 -0.329513 0.931867 -0.190573 -0.308717 0.658687 -0.324332 -0.678926 0.65891 -0.395129 -0.640087 0.931867 -0.190573 -0.308717 0.931867 -0.219373 -0.288963 0.888088 -0.289394 -0.357142 0.994042 0.0480701 0.097822 0.994042 0.0480702 0.0978224 0.994053 0.0549564 0.0940178 0.994978 0.0525783 0.0851738 0.994053 0.0594177 0.0912634 0.994042 0.0659055 0.0868121 0 0.61421 0.789143 -0.0635015 0.584136 0.809168 0 0.555662 0.831408 0 0.494218 0.869338 -0.0635022 0.461575 0.884826 0 0.430195 0.902736 0.891416 -0.396582 0.219319 0.893719 0.0549268 0.445252 0.900887 0.000508711 0.434054 0.982611 -0.0452641 0.180072 0.968947 -0.0605931 0.23973 0.959187 -0.0732151 0.27313 0.955083 -0.064981 0.289125 0.937215 -0.06591 0.342467 0.963017 -0.216499 -0.160395 0.97139 -0.18685 -0.146589 0.87644 -0.328523 -0.352031 0.884045 -0.314894 -0.345407 0.858962 -0.499027 -0.1147 0.839075 -0.531222 -0.117289 0.946585 -0.321729 0.0216173 0.938296 -0.345215 0.0206514 0.978164 -0.0416064 0.203628 0.993506 0.0189025 0.112202 0.993503 0.012621 0.113106 0.71267 0.0192295 0.701236 0.884955 0.0853906 0.457781 0.885792 0.0905598 0.45516 0.792145 -0.595353 0.134393 0.849346 -0.468187 0.243748 0.805188 -0.464066 0.369209 0.81278 -0.417533 0.406269 0.759739 -0.359304 0.541939 0.771367 -0.304004 0.559084 0.722823 -0.201175 0.661102 0.182167 -0.765971 0.616525 0.133806 -0.786584 0.602811 0.0550195 -0.625836 0.778012 0.275269 -0.480867 0.832463 0.329664 -0.398898 0.855688 0.0482263 -0.52416 0.850253 0.0957298 -0.206166 0.973823 0.146936 0.218919 0.964616 0.12301 0.206218 0.970743 0.158584 -0.0283414 0.986939 0.10626 -0.561292 -0.820768 0.166741 -0.576958 -0.799573 0.107769 -0.719264 -0.686327 0.0859288 -0.860908 -0.501452 0.0736702 -0.887304 0.455264 0.156277 -0.959844 0.232975 0.0282402 -0.9662 0.256244 0.141803 -0.9847 -0.101279 0.170943 -0.979239 -0.108947 0.0918723 -0.950005 -0.298413 0.15188 -0.845629 -0.511706 0.35364 -0.431915 0.829692 0.456008 -0.64975 0.608178 0.364126 -0.671009 0.645879 0.489612 -0.807733 0.328403 0.39806 -0.844471 0.358352 0.521631 -0.853139 -0.00739133 0.443193 -0.896395 0.00744961 0.546136 -0.756601 -0.359569 0.493424 -0.791741 -0.360108 0.553283 -0.510577 -0.658171 0.546203 -0.515418 -0.660308 0.177304 -0.478949 0.85975 0.301511 -0.741498 0.599393 0.187424 -0.753157 0.630577 0.324421 -0.902196 0.284242 0.209398 -0.926867 0.31156 0.342321 -0.93608 -0.0810605 0.242332 -0.968086 -0.0639169 0.351089 -0.820893 -0.450411 0.282718 -0.849334 -0.44576 0.344985 -0.554038 -0.757646 0.333637 -0.559624 -0.758622 0.484355 0.216616 0.847631 0.687666 0.192441 0.700059 0.647367 0.1541 0.746438 0.870205 0.218372 0.441653 0.85001 0.161593 0.501368 0.933082 -0.0505905 0.356088 0.918217 -0.034003 0.394615 0.916084 -0.0331339 0.399615 0.902775 0.0266167 0.429289 0.73816 -0.152749 0.657105 0.69772 -0.00937154 0.716309 0.461103 -0.0648231 0.884976 0.424998 0.192401 0.88451 0.34145 0.214565 0.915081 0.222902 -0.146576 0.963758 0.179686 -0.14 0.973711 0.423347 -0.104669 0.899901 0.487234 -0.329475 0.808733 0.503309 -0.328117 0.799387 0.600308 -0.533245 0.596054 0.532644 -0.558269 0.636103 0.641636 -0.67718 0.360182 0.575715 -0.718176 0.390864 0.684261 -0.725962 0.0690366 0.629493 -0.772603 0.0826018 0.721187 -0.647855 -0.245303 0.685633 -0.684349 -0.248141 0.739824 -0.425643 -0.521046 0.725682 -0.440861 -0.52823 0.146444 0.77511 0.614621 0.82472 0.519361 -0.223832 0.651395 0.56592 0.50539 0.942262 0.331045 0.0505066 0.971801 0.228566 0.0579658 0.978816 0.200217 0.0428007 0.98931 0.127935 0.0699867 0.993672 0.0911947 0.0655664 0.851107 0.333788 0.405219 0.873457 0.374496 0.311169 0.889412 0.372252 0.265283 0.901406 0.375454 0.215642 0.8953 0.384926 0.224211 0.918228 0.365203 0.153248 0.741742 0.669049 -0.0468299 0.78219 0.619999 -0.0614853 0.708895 0.689514 0.148456 0.911964 0.378302 0.158775 0.938587 0.329849 0.101261 0.786961 0.573289 -0.228108 0.849347 0.427719 -0.309298 0.792189 0.386866 -0.471987 0.856724 0.137834 -0.497017 0.84357 0.117735 -0.523955 0.884011 -0.160432 -0.439074 0.877481 -0.173432 -0.447157 0.921871 0.373808 0.102088 0.959989 0.267597 0.0825434 0.89144 0.373744 -0.256223 0.944652 0.175744 -0.277031 0.941309 0.161832 -0.296223 0.970892 -0.0341905 -0.237064 0.965072 -0.0593253 -0.255179 0.115187 -0.335281 -0.93505 0.0768084 -0.0887752 -0.993086 0.146662 -0.0564709 -0.987573 0.052967 0.297827 -0.953149 0.148674 0.339838 -0.928658 0.0857655 0.514967 -0.852908 0.146321 0.667763 -0.729851 0.333936 -0.431118 -0.838227 0.105765 -0.461794 -0.880659 0.296924 -0.495858 -0.816064 0.143114 0.668636 -0.729688 0.0595846 0.827061 -0.558945 0.223299 0.882269 -0.414414 0.116193 0.916037 -0.383894 0.0132364 0.995679 -0.091909 0.29896 0.945316 -0.130384 0.108604 0.993899 0.0192381 0.0837783 0.994398 0.0644471 0.0301579 0.963856 0.264712 0.178761 0.933266 0.311543 0.111637 0.76848 0.63006 0.341453 0.721835 0.601967 0.692778 0.552396 0.463591 0.714414 0.627631 0.309341 0.412918 0.844799 0.340314 0.487268 0.870615 0.0678171 0.353596 0.935288 -0.0143653 0.44758 0.849556 -0.279152 0.377674 0.862575 -0.336641 0.480036 0.681761 -0.552057 0.412116 0.672944 -0.614253 0.513927 0.406121 -0.755609 0.454269 0.379298 -0.806085 0.542568 0.0408976 -0.839015 0.499057 0.011021 -0.866499 0.553197 -0.3568 -0.752773 0.546581 -0.362069 -0.755086 0.344665 -0.424629 -0.837195 0.287817 -0.0417599 -0.956774 0.346277 -0.00961429 -0.938083 0.253017 0.345365 -0.903718 0.332866 0.380164 -0.862946 0.223307 0.666463 -0.71131 0.31305 0.687298 -0.655455 0.200943 0.885229 -0.419513 0.291654 0.884767 -0.363491 0.187454 0.97982 -0.0693802 0.269271 0.962647 -0.0283426 0.179693 0.933159 0.311328 0.463498 0.831059 0.307427 0.425021 0.704441 0.568436 0.484356 0.660628 0.573559 0.870902 0.333059 0.361388 0.892969 0.354394 0.27751 0.69017 0.641419 0.335034 0.744778 0.656095 0.121839 0.503288 0.861681 0.0648592 0.593141 0.784008 -0.183072 0.545202 0.804165 -0.236798 0.633557 0.647942 -0.422819 0.588804 0.647702 -0.48352 0.677986 0.413446 -0.607781 0.639886 0.394223 -0.659647 0.718475 0.091495 -0.689509 0.69109 0.0658341 -0.719764 0.739778 -0.267069 -0.617578 0.726919 -0.281935 -0.62618 0.939621 0.210193 0.270058 0.939565 0.150995 0.307274 0.938418 0.137175 0.317104 0.939692 0.134442 0.314491 0.939392 0.133804 0.315657 0.939414 0.133839 0.315577 0.939897 0.133533 0.314267 0.939964 0.133272 0.314175 0.939946 0.133329 0.314204 0.939759 0.133618 0.314642 0.939564 0.133831 0.315134 0.93962 0.221638 0.260749 0.939837 0.221255 0.260293 0.940954 0.217505 0.259418 0.939692 0.220867 0.261146 0.939968 0.221127 0.259929 0.939975 0.221131 0.259901 0.939693 0.220497 0.261456 0.939471 0.221926 0.261041 0.93945 0.222002 0.261055 0.939566 0.207019 0.27269 0.94337 0.201976 0.263171 0.936007 0.192045 0.294974 0.939622 0.190155 0.284519 0.93966 0.172643 0.295352 0.937285 0.172266 0.30302 0.94337 0.144746 0.298499 0.939621 0.14722 0.308931 0.939693 0.134933 0.314278 0.149347 0.607322 0.780292 0.48879 0.535838 0.68845 0.346096 0.403609 0.846946 0.655059 0.325046 0.682087 0.850961 0.225951 0.474143 0.850963 0.22595 0.47414 0.850963 0.259576 0.456599 0.850962 0.259576 0.4566 0.850962 0.291849 0.436678 0.850961 0.29185 0.436679 0.850961 0.322601 0.41448 0.850962 0.3226 0.414479 0.655066 0.46408 0.596254 0.57344 0.497252 0.651081 0.573329 0.455268 0.681193 0.573328 0.455269 0.681195 0.573328 0.404925 0.712272 0.573329 0.404925 0.712271 0.57344 0.35919 0.736307 0.48879 0.375303 0.787548 0.346094 0.576252 0.740374 0.202128 0.59695 0.776399 0.20209 0.544197 0.814254 0.202092 0.544197 0.814253 0.202092 0.484021 0.851401 0.202091 0.48402 0.851401 0.202129 0.426538 0.881595 0.149347 0.425371 0.892612 -0.707101 -0.260021 -0.657569 -0.671186 -0.313204 -0.671873 -0.706468 -0.297429 -0.642214 -0.706468 -0.371766 -0.60224 -0.706472 -0.371764 -0.602236 -0.706524 -0.439397 -0.554756 -0.672818 -0.460786 -0.578786 -0.707105 -0.471309 -0.527135 -0.706478 0.297425 0.642205 -0.706471 0.297428 0.642211 -0.706471 0.371764 0.602237 -0.70647 0.371765 0.602238 -0.70647 0.440814 0.5537 -0.706471 0.440814 0.553699 0.0340208 0.965178 -0.259374 0.0129853 0.977367 -0.211151 0 0.998233 -0.059416 2.023e-06 0.226942 -0.973908 0.0270243 0.34687 -0.937524 0.0339815 0.366934 -0.929626 -0.00635808 0.503721 -0.863843 1.91658e-06 0.591019 -0.806657 -5.32048e-06 0.669646 -0.742681 0.0273489 0.761077 -0.648085 -0.0167719 0.836673 -0.547445 0.0102807 0.932547 -0.360903 -2.33068e-06 0.0585898 -0.998282 0.0300929 -0.0900631 -0.995481 -0.00808355 -0.195786 -0.980613 9.41786e-07 -0.339714 -0.940529 -1.06891e-06 -0.383664 -0.923473 0.0102318 -0.547743 -0.836584 -0.00702908 -0.580977 -0.81389 0.00814345 -0.853413 -0.521171 0 -0.862079 -0.506774 -0.697344 -0.611693 -0.373555 -0.697345 -0.611692 -0.373555 -0.697344 -0.378526 -0.608629 -0.642338 -0.419824 -0.64121 -0.707005 -0.240249 -0.66515 -0.697344 -0.0645815 -0.713821 -0.697346 -0.0645806 -0.713819 -0.697345 0.263146 -0.666681 -0.697344 0.692179 -0.186011 -0.697343 0.692179 -0.186011 -0.699221 0.544301 -0.463493 -0.650496 0.566628 -0.505755 -0.707006 0.417973 -0.570474 -0.697346 0.263146 -0.66668 0 -0.994764 -0.102202 -0.00725963 -0.990527 -0.137127 -4.30261e-05 -0.96414 -0.265394 0.000319796 -0.890847 -0.454303 0 -0.891401 -0.453216 0.702132 -0.70532 -0.0976438 0.702129 -0.705323 -0.0976452 0.702129 -0.634328 -0.323486 0.702128 -0.634328 -0.323487 0.994042 0.100482 0.0422288 0.97185 -0.217199 -0.0912803 0.65891 -0.662235 -0.356767 0.108087 -0.825823 -0.553474 0.558294 -0.689176 -0.461892 0.341053 -0.780885 -0.523356 0.237325 -0.802284 -0.547738 0.237621 -0.843818 -0.481152 0.153988 -0.869871 -0.468627 0.237621 -0.865999 -0.43998 0.237426 -0.895535 -0.376359 0.887897 -0.382152 -0.256122 0.739452 -0.559228 -0.3748 0.108166 -0.923419 -0.368236 0.341053 -0.866623 -0.364209 0.65891 -0.69347 -0.291439 0.558601 -0.771272 -0.305131 0.739455 -0.620626 -0.260825 0.971845 -0.195729 -0.131179 0.931702 -0.297097 -0.20896 0.931867 -0.3194 -0.172071 0.658688 -0.620342 -0.425801 0.65891 -0.662234 -0.356767 0.931867 -0.319399 -0.172071 0.931867 -0.334464 -0.140563 0.888089 -0.429193 -0.164597 0.994042 0.090541 0.0606814 0.994042 0.090541 0.0606814 0.994053 0.0946024 0.0539434 0.994978 0.088121 0.0474736 0.994053 0.0970892 0.0493277 0.994042 0.100482 0.0422288 0 0.926493 0.376313 -0.126161 0.889755 0.438656 0 0.912302 0.409518 0 0.862674 0.50576 -0.0635017 0.842148 0.535494 0 0.823928 0.566694 0.891418 -0.233787 0.388224 0.893719 0.270193 0.358139 0.900886 0.217465 0.37565 0.982611 0.0508358 0.178579 0.968945 0.067391 0.237915 0.959187 0.0731593 0.273145 0.955084 0.0882869 0.282879 0.937215 0.114154 0.32954 0.963017 -0.26769 -0.0306574 0.97139 -0.235112 -0.0335252 0.876441 -0.460524 -0.140606 0.884047 -0.445407 -0.141684 0.858963 -0.489519 0.15018 0.839076 -0.518694 0.164035 0.946586 -0.267815 0.179585 0.938296 -0.28864 0.190493 0.978164 0.0657816 0.19715 0.993506 0.0724708 0.0877185 0.993503 0.067483 0.0916422 0.712672 0.367269 0.597672 0.884954 0.30284 0.353757 0.885792 0.306006 0.348903 0.792144 -0.448396 0.414064 0.849346 -0.283587 0.445186 0.805187 -0.217288 0.551778 0.812779 -0.158459 0.560607 0.759738 -0.040197 0.648985 0.771366 0.0162666 0.636184 0.722823 0.156328 0.673119 0.116223 -0.408514 0.905323 0.185756 -0.369547 0.910456 0.0296769 -0.190309 0.981276 0.27526 -0.000212418 0.96137 0.127916 0.641235 0.756608 0.161199 0.451043 0.877824 0.286362 0.057926 0.956369 0.0901154 -0.023674 0.99565 0.0666489 0.276495 0.958702 0.933082 0.13423 0.333676 0.918216 0.167862 0.35875 0.916084 0.171113 0.362644 0.902775 0.237695 0.358467 0.738161 0.196269 0.645443 0.697722 0.350036 0.625027 0.461103 0.386347 0.798824 0.10666 -0.887328 -0.448634 0.207978 -0.892825 -0.39951 0.0433236 -0.921685 0.385512 0.121174 -0.987037 0.105241 0.245829 -0.969255 0.0106688 0.0874123 -0.991511 -0.0962523 0.112139 -0.959394 -0.25882 0.0815365 -0.558374 0.825573 0.113658 -0.628009 0.769862 0.227265 -0.669485 0.707206 0.0281143 -0.784431 0.619578 0.212717 -0.913601 0.346534 0.35365 0.040796 0.934488 0.456015 -0.258606 0.851571 0.364132 -0.258165 0.894851 0.489619 -0.535313 0.688269 0.398072 -0.552155 0.732574 0.521638 -0.742531 0.420169 0.4432 -0.772572 0.45465 0.546142 -0.835017 0.0669035 0.493426 -0.865721 0.0840081 0.553285 -0.771257 -0.314703 0.546204 -0.776519 -0.314133 0.177305 0.0150905 0.98404 0.301508 -0.342458 0.88984 0.187417 -0.336962 0.922676 0.324419 -0.639206 0.697257 0.209393 -0.646913 0.733252 0.342316 -0.8512 0.397842 0.242331 -0.870345 0.42869 0.351088 -0.936121 0.0203793 0.282722 -0.958424 0.0386267 0.344988 -0.858632 -0.379122 0.333633 -0.863961 -0.377174 0.149373 0.77633 0.612371 0.19285 0.667668 0.719047 0.341467 0.643355 0.685196 0.424997 0.608882 0.669806 0.48435 0.611413 0.625763 0.687668 0.516688 0.510046 0.647366 0.506672 0.569386 0.870204 0.409942 0.273299 0.850011 0.390629 0.353398 0.2381 0.35099 0.905602 0.179679 0.365613 0.91326 0.423351 0.359305 0.83167 0.487238 0.11903 0.865119 0.503306 0.115534 0.85635 0.600305 -0.163774 0.782823 0.532647 -0.165421 0.830014 0.641639 -0.406364 0.650514 0.57571 -0.426529 0.697589 0.684257 -0.594187 0.42277 0.629491 -0.627795 0.457837 0.721184 -0.683713 0.111489 0.685631 -0.716736 0.127277 0.739821 -0.629144 -0.238418 0.725682 -0.645911 -0.23703 0.146445 0.978575 0.144722 0.824719 0.337865 -0.453525 0.651395 0.742796 0.15472 0.942262 0.311947 -0.121783 0.971801 0.226927 -0.0640833 0.978816 0.194793 -0.0630421 0.98931 0.145789 -0.0033574 0.993672 0.11176 0.0111846 0.851107 0.491678 0.184036 0.873457 0.479907 0.0822317 0.88941 0.455024 0.043619 0.901406 0.432974 -0.000976106 0.895301 0.445459 0.00170866 0.918228 0.392899 -0.049884 0.741741 0.555999 -0.375081 0.782191 0.50619 -0.363248 0.708895 0.671364 -0.21619 0.911964 0.407007 -0.0516477 0.938587 0.336288 -0.0772305 0.786963 0.382427 -0.48419 0.849348 0.215767 -0.481718 0.792189 0.099042 -0.602185 0.856724 -0.12914 -0.499346 0.84357 -0.160015 -0.512625 0.884011 -0.358475 -0.300033 0.877481 -0.373774 -0.300533 0.921872 0.374769 -0.0984922 0.959989 0.273017 -0.0623139 0.89144 0.195561 -0.408768 0.944652 0.0136829 -0.327789 0.941309 -0.00796183 -0.337453 0.970892 -0.148143 -0.188208 0.965073 -0.178965 -0.191328 0.115182 -0.757886 -0.642138 0.0768033 -0.573427 -0.815649 0.146663 -0.542692 -0.827028 0.0529673 -0.218647 -0.974366 0.14867 -0.170021 -0.974161 0.0857621 0.0195202 -0.996124 0.146319 0.213375 -0.965951 0.333939 -0.792472 -0.510366 0.10576 -0.840255 -0.531776 0.296924 -0.837459 -0.458802 0.0132434 0.816328 -0.577436 0.298955 0.753477 -0.585575 0.1086 0.87036 -0.480291 0.143119 0.21421 -0.966246 0.0595891 0.436781 -0.897592 0.223306 0.556861 -0.800025 0.243335 0.547543 -0.800615 0.107836 0.622214 -0.775385 0.0837765 0.893396 -0.441391 0.0301536 0.96708 -0.25268 0.178762 0.964004 -0.196827 0.111638 0.980553 0.161407 0.341455 0.92611 0.1604 0.692777 0.710186 0.125283 0.714413 0.698216 -0.0459174 0.412917 0.901775 -0.127677 0.487267 0.787884 -0.376577 0.353593 0.802801 -0.480087 0.447576 0.596162 -0.666534 0.37767 0.578692 -0.722828 0.480032 0.314394 -0.818978 0.412112 0.27566 -0.868433 0.513923 -0.0260954 -0.857439 0.454269 -0.07456 -0.887739 0.542568 -0.384091 -0.747057 0.49906 -0.423704 -0.75592 0.5532 -0.685383 -0.473519 0.546583 -0.691104 -0.472888 0.344665 -0.786338 -0.512717 0.287818 -0.514552 -0.807711 0.346278 -0.477367 -0.807596 0.253017 -0.152763 -0.955325 0.332866 -0.10224 -0.937415 0.223308 0.22152 -0.949243 0.313048 0.26749 -0.91129 0.200942 0.556875 -0.805924 0.291654 0.584486 -0.757176 0.187454 0.813858 -0.549997 0.269274 0.819505 -0.505869 0.179694 0.963803 -0.196959 0.463496 0.873432 -0.149289 0.42502 0.894283 0.14006 0.484352 0.858902 0.166403 0.870902 0.469131 0.146443 0.892969 0.445669 0.0631328 0.690171 0.723001 -0.0305618 0.744779 0.629114 -0.222531 0.503287 0.778668 -0.374671 0.59314 0.587433 -0.550551 0.545205 0.578027 -0.607154 0.633559 0.349726 -0.690141 0.588805 0.319167 -0.742591 0.677988 0.054164 -0.733075 0.639888 0.0115833 -0.76838 0.718477 -0.265515 -0.642879 0.691089 -0.30287 -0.656251 0.739777 -0.540079 -0.401305 0.726918 -0.557254 -0.401321 0.939621 0.317061 0.12878 0.939566 0.284403 0.190609 0.938421 0.27734 0.20603 0.939692 0.273676 0.205135 0.93939 0.273706 0.206475 0.939414 0.273695 0.206377 0.939897 0.272775 0.205397 0.939965 0.272502 0.205449 0.939946 0.272568 0.205445 0.939758 0.273039 0.205681 0.939564 0.273468 0.205998 0.939621 0.322317 0.114997 0.939837 0.32176 0.114793 0.940955 0.31807 0.115911 0.939692 0.321849 0.115726 0.939968 0.321466 0.114544 0.939976 0.321454 0.114514 0.939692 0.321684 0.116178 0.939471 0.322714 0.115105 0.93945 0.322787 0.115079 0.939565 0.315629 0.132647 0.94337 0.306501 0.126925 0.936007 0.313803 0.159432 0.939622 0.306939 0.151323 0.939661 0.297189 0.169461 0.937285 0.300697 0.17629 0.94337 0.274603 0.186135 0.939621 0.281962 0.193932 0.939692 0.273996 0.204705 0.149348 0.916102 0.372092 0.488784 0.808277 0.328297 0.346113 0.773004 0.531668 0.655059 0.622542 0.428182 0.850962 0.43275 0.297644 0.850962 0.432749 0.297643 0.850962 0.453099 0.265639 0.850962 0.453099 0.265639 0.850962 0.471087 0.23225 0.850962 0.471087 0.23225 0.850962 0.486619 0.197649 0.850962 0.486619 0.197649 0.655065 0.700032 0.284331 0.573439 0.756174 0.315228 0.573328 0.734871 0.362297 0.573328 0.734871 0.362297 0.573328 0.706811 0.414383 0.573328 0.706811 0.414383 0.573439 0.679223 0.458066 0.488785 0.718798 0.494386 0.346096 0.869235 0.353056 0.202129 0.905173 0.373906 0.202091 0.878415 0.433065 0.202089 0.878416 0.433066 0.202089 0.844874 0.495325 0.202091 0.844874 0.495325 0.20213 0.810191 0.550213 0.149341 0.814688 0.56034 -0.707102 -0.553967 -0.439463 -0.671183 -0.607181 -0.425258 -0.706473 -0.578684 -0.407456 -0.706473 -0.623075 -0.33567 -0.706472 -0.623075 -0.33567 -0.706524 -0.657907 -0.260734 -0.672814 -0.688448 -0.270851 -0.7071 -0.671737 -0.220861 -0.706473 0.578684 0.407456 -0.706471 0.578685 0.407457 -0.706471 0.623076 0.335671 -0.706471 0.623076 0.335671 -0.706471 0.658605 0.259111 -0.70647 0.658606 0.259111 -0.701806 0.705112 0.10142 -0.701806 0.705111 0.10142 -0.694742 0.427144 0.57869 -0.487518 -0.349106 0.800282 -0.694742 0.427144 0.57869 -0.702917 0.155718 0.694017 -0.494623 0.0973594 0.863637 -0.705015 -0.0291253 0.708594 -0.703698 -0.201753 0.681252 -0.704395 -0.370839 0.605232 -0.704396 -0.50748 0.496277 -0.487516 -0.702476 0.518514 -0.694743 -0.659261 -0.287588 -0.694742 -0.659262 -0.287588 -0.702916 -0.711268 0.00270156 -0.49462 -0.863639 0.0973595 -0.705012 -0.684328 0.186152 -0.703695 -0.61924 0.348361 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.989813 0.142371 0 0.989813 0.142371 0 -0.864721 -0.502253 0.0376681 -0.915934 -0.399556 0.0154231 -0.947763 -0.318602 -0.0283316 -0.999591 0.00379668 -1.279e-05 -0.52245 0.85267 0.026812 -0.448705 0.893277 -7.17902e-05 -0.553759 0.832677 0.000100132 -0.714954 0.699171 1.17872e-05 -0.715154 0.698967 5.46713e-06 -0.871553 0.490302 0.0341628 -0.816772 0.575948 -0.0536321 -0.963548 0.262106 -0.0071231 -0.937049 0.349126 0.00709917 -0.997482 -0.0705648 0 0.593866 0.804564 0.0329098 0.628647 0.776994 -0.0251273 0.21886 0.975433 0.00777417 0.276084 0.961102 -4.60465e-06 0.0815173 0.996672 8.70866e-06 -0.0410682 0.999156 0.0188835 0.0225915 0.999566 -0.0358063 -0.283778 0.958221 0.035247 -0.15768 0.986861 -2.61002e-05 -0.351551 0.936169 0 0.817651 0.575715 0 0.817651 0.575715 0 0.880372 0.474284 0 0.880372 0.474284 0 0.930572 0.366109 0 0.930572 0.366109 0 -0.930572 -0.366109 0 -0.930572 -0.366109 0 -0.880372 -0.474284 0 -0.880372 -0.474284 0 -0.817651 -0.575714 0 -0.817651 -0.575714 -0.879241 0.463039 0.111938 -0.105439 0.929953 -0.352235 -0.0895377 0.0669712 -0.993729 -0.0979759 -0.187269 -0.97741 -0.150375 -0.202448 -0.967679 -0.275057 0.244572 -0.9298 -0.143299 0.180774 -0.973029 -0.0795294 0.355652 -0.931229 -0.132376 0.52752 -0.839166 -0.188263 0.509732 -0.839482 0.0290752 0.794932 -0.606002 -0.204981 0.826805 -0.523809 -0.055925 0.672317 -0.738148 -0.214587 0.956993 -0.195235 -0.147366 0.978653 0.143256 -0.169267 0.977101 0.128928 -0.887085 0.460082 0.0374862 -0.954989 0.282487 -0.0905372 -0.960101 0.262582 -0.096209 -0.978436 0.196364 -0.0640706 -0.978976 0.193729 -0.0638355 -0.991397 0.130893 -7.30398e-05 -0.990797 0.135328 -0.00271275 -0.965171 -0.185617 -0.184367 -0.793205 0.0767999 -0.604092 -0.859465 -0.162051 -0.484828 -0.839106 -0.16569 -0.51812 -0.884191 -0.37361 -0.280394 -0.876485 -0.381012 -0.294285 -0.859292 0.363474 -0.359867 -0.938545 0.331584 -0.0958357 -0.933193 0.349838 -0.0822446 -0.821647 0.284177 -0.494106 -0.847484 0.207074 -0.488765 -0.891283 0.182604 -0.415055 -0.947045 -0.00962704 -0.320958 -0.938318 -0.0111318 -0.345593 -0.970911 -0.15321 -0.184006 -0.989048 -0.0753118 -0.126934 -0.807335 0.558109 -0.191636 -0.693243 0.535786 -0.482024 -0.770721 0.324434 -0.54839 -0.902135 0.42997 -0.0357521 -0.88785 0.458117 0.0430177 -0.749527 0.661358 -0.028529 -0.710137 0.703865 -0.0167048 -0.0995205 -0.374841 -0.921732 -0.100581 -0.573556 -0.812968 -0.110657 -0.575504 -0.810278 -0.0958646 -0.857062 -0.506217 -0.105772 -0.857952 -0.502723 -0.354222 0.785361 -0.507675 -0.457112 0.542571 -0.704745 -0.363194 0.583202 -0.726612 -0.49085 0.24869 -0.834997 -0.397292 0.280915 -0.87364 -0.522595 -0.0895823 -0.847862 -0.442824 -0.0741344 -0.893538 -0.546595 -0.430117 -0.718494 -0.493389 -0.431508 -0.755227 -0.553359 -0.702978 -0.446783 -0.546232 -0.705397 -0.451714 -0.190683 0.945238 -0.264888 -0.276015 0.782549 -0.558062 -0.176406 0.813072 -0.554792 -0.302662 0.524979 -0.795483 -0.186329 0.560467 -0.806944 -0.325674 0.195584 -0.925032 -0.208478 0.226896 -0.951344 -0.343265 -0.170889 -0.923562 -0.241866 -0.151602 -0.958393 -0.351518 -0.526644 -0.774003 -0.282649 -0.521998 -0.804753 -0.345028 -0.806372 -0.480334 -0.333669 -0.807623 -0.486221 -0.879552 0.46222 0.112878 -0.763484 0.632832 0.128902 -0.693959 0.713687 0.0952494 -0.651407 0.747739 0.128663 -0.484426 0.864004 0.137217 -0.918286 0.389808 -0.0692915 -0.901026 0.429075 -0.0636062 -0.758732 0.588319 -0.279656 -0.805287 0.54011 -0.244529 -0.700528 0.618105 -0.356659 -0.633824 0.767208 -0.0982816 -0.461116 0.875436 -0.144854 -0.425663 0.898627 0.106208 -0.341495 0.931112 0.128105 -0.149325 0.987345 -0.0533964 -0.172458 0.957947 -0.229336 -0.424088 0.885576 -0.189484 -0.486862 0.77636 -0.400289 -0.502663 0.766885 -0.399019 -0.601392 0.541597 -0.587368 -0.531849 0.583778 -0.613466 -0.642822 0.292801 -0.707847 -0.575095 0.324776 -0.750857 -0.685233 -0.00140567 -0.728323 -0.629212 0.0119746 -0.777142 -0.721676 -0.306107 -0.620872 -0.685622 -0.31015 -0.658581 -0.739939 -0.558762 -0.374533 -0.725681 -0.566842 -0.38997 -0.146152 0.625146 0.766702 -0.82627 -0.213479 0.521253 -0.65141 0.51882 0.553616 -0.992269 0.0475998 0.114618 -0.992328 0.0842575 0.0904788 -0.976263 0.0443903 0.211991 -0.978909 0.0543444 0.196936 -0.963217 0.0626797 0.261312 -0.851018 0.419869 0.315401 -0.880894 0.30513 0.361832 -0.902136 0.222879 0.369426 -0.895767 0.233562 0.378219 -0.919311 0.160246 0.359429 -0.74053 -0.0267685 0.67149 -0.783611 -0.0494718 0.619279 -0.707954 0.168879 0.685771 -0.918518 0.161213 0.361019 -0.938742 0.103153 0.32882 -0.785902 -0.211415 0.581086 -0.847487 -0.294227 0.441811 -0.79326 -0.462205 0.396365 -0.856962 -0.49299 0.150256 -0.844209 -0.520268 0.128967 -0.884164 -0.442606 -0.149514 -0.877675 -0.450627 -0.163163 -0.945948 0.0973519 0.309364 -0.960044 0.0626741 0.272741 -0.891347 -0.246083 0.380714 -0.944831 -0.27187 0.182703 -0.94185 -0.291325 0.167476 -0.970926 -0.237894 -0.0266195 -0.965173 -0.256076 -0.0535424 -0.115167 -0.942975 -0.312306 -0.0771069 -0.994861 -0.0656237 -0.146472 -0.988703 -0.0318162 -0.0440755 -0.935062 0.351734 -0.0575901 -0.932275 0.357138 -0.0997356 -0.805784 0.583751 -0.181854 -0.70543 0.685053 -0.334009 -0.848179 -0.411133 -0.105773 -0.891823 -0.439845 -0.278876 -0.83245 -0.478806 -0.0122519 -0.0647318 0.997828 -0.315861 -0.120226 0.941157 -0.112688 0.0323147 0.993105 -0.136042 -0.699128 0.701934 -0.0636792 -0.547428 0.834427 -0.202702 -0.398087 0.894673 -0.248176 -0.411095 0.87716 -0.10877 -0.339933 0.934139 -0.0842361 0.0872108 0.992622 -0.0329018 0.278155 0.959972 -0.190432 0.33261 0.923638 -0.091159 0.650211 0.754265 -0.341495 0.619245 0.707048 -0.693992 0.47214 0.543561 -0.714749 0.322935 0.62036 -0.412188 0.363534 0.83543 -0.486902 0.0927093 0.868522 -0.354182 0.00798848 0.935142 -0.447649 -0.256942 0.8565 -0.378516 -0.316048 0.869965 -0.480134 -0.534238 0.695744 -0.413113 -0.598157 0.686692 -0.514074 -0.74497 0.425144 -0.455181 -0.796796 0.397399 -0.542688 -0.837658 0.0617883 -0.499643 -0.865684 0.030797 -0.553287 -0.76125 -0.338189 -0.546673 -0.763558 -0.343697 -0.344676 -0.847196 -0.404299 -0.288259 -0.957351 -0.0196453 -0.346234 -0.938047 0.0137629 -0.253712 -0.895326 0.36609 -0.332838 -0.853092 0.401813 -0.224031 -0.695376 0.682834 -0.313033 -0.637728 0.703785 -0.201531 -0.398319 0.894834 -0.291645 -0.340716 0.893788 -0.187832 -0.0459053 0.981128 -0.269299 -0.00369424 0.96305 -0.179211 0.335695 0.924766 -0.463845 0.325626 0.823902 -0.425694 0.583068 0.691966 -0.484446 0.589923 0.64599 -0.875379 0.359637 0.323069 -0.889599 0.286948 0.355351 -0.689728 0.352973 0.632207 -0.745699 0.134997 0.652464 -0.50267 0.088573 0.859929 -0.593282 -0.162169 0.78849 -0.546282 -0.217611 0.808839 -0.633762 -0.40553 0.658704 -0.58999 -0.467972 0.657962 -0.678232 -0.596768 0.4288 -0.640943 -0.649851 0.408517 -0.718701 -0.686772 0.108687 -0.691732 -0.717494 0.0819099 -0.73991 -0.623879 -0.251611 -0.727055 -0.632485 -0.267121 -0.572885 0.721584 0.38874 -0.850727 0.429136 0.303491 -0.879516 0.443191 0.173298 -0.654678 0.703427 0.276744 -0.764996 0.599321 0.235787 -0.845143 0.496166 0.198878 -0.851115 0.476661 0.219996 -0.850697 0.462773 0.249311 -0.850697 0.462773 0.24931 -0.851115 0.445934 0.277031 -0.345806 0.873161 0.343522 -0.488399 0.812037 0.319474 -0.149209 0.920155 0.36201 -0.201916 0.91012 0.361816 -0.201876 0.862246 0.464519 -0.844349 0.438093 0.308464 -0.654678 0.618069 0.435187 -0.573006 0.672701 0.468122 -0.488416 0.713491 0.502375 -0.345802 0.767208 0.540197 -0.573005 0.760984 0.30425 -0.572884 0.721585 0.38874 -0.201876 0.862246 0.464519 -0.201916 0.802815 0.560997 -0.149216 0.808497 0.569269 -0.340892 -0.768676 -0.54123 -0.994035 0.0960151 0.0517264 -0.994036 0.0890335 0.0629658 -0.994251 0.0875532 0.0616469 -0.991754 0.119357 0.0466713 -0.996676 0.0739731 0.0341414 -0.658679 -0.662413 -0.356863 -0.93179 -0.319572 -0.172164 -0.994046 0.100678 0.0416811 -0.993745 -0.10392 -0.0408845 -0.971837 -0.219294 -0.0862755 -0.994056 0.0924779 0.0574511 -0.994035 0.0960152 0.0517264 -0.93179 -0.319572 -0.172164 -0.931639 -0.340491 -0.126945 -0.558461 -0.670127 -0.488928 -0.739296 -0.55059 -0.387675 -0.93179 -0.296805 -0.208982 -0.888072 -0.369084 -0.274055 -0.971843 -0.192664 -0.135656 -0.237285 -0.855229 -0.460738 -0.237285 -0.794299 -0.559272 -0.108127 -0.80437 -0.584206 -0.887837 -0.42821 -0.168468 -0.739297 -0.626628 -0.24653 -0.658467 -0.702767 -0.269331 -0.558106 -0.772161 -0.303786 -0.340888 -0.874835 -0.34418 -0.65868 -0.61522 -0.433181 -0.65868 -0.662413 -0.356863 -0.237287 -0.855228 -0.460738 -0.23719 -0.906431 -0.349461 -0.108042 -0.925125 -0.363965 -0.939508 0.319007 0.124739 -0.939609 0.325917 0.104469 -0.939482 0.326288 0.104444 -0.939572 0.325973 0.104623 -0.93969 0.325351 0.105496 -0.939848 0.325299 0.104239 -0.939867 0.325262 0.104182 -0.939727 0.325609 0.104369 -0.939514 0.279644 0.197768 -0.940505 0.265549 0.211977 -0.939696 0.266633 0.214191 -0.939887 0.265863 0.214312 -0.93969 0.266952 0.21382 -0.939536 0.26669 0.214822 -0.939492 0.266702 0.214999 -0.939514 0.266686 0.214924 -0.93975 0.266253 0.214429 -0.939508 0.279658 0.197779 -0.939511 0.279651 0.197774 -0.939693 0.29052 0.180483 -0.939693 0.290521 0.180483 -0.939498 0.301576 0.162469 -0.939498 0.301576 0.162469 -0.939694 0.310538 0.143325 -0.939693 0.310539 0.143324 -0.939511 0.318999 0.124735 -0.939515 0.318989 0.124732 -0.939697 0.325405 0.105268 0.698067 0.710419 0.089485 0.698068 0.710418 0.0894848 0.698069 0.67889 -0.227615 0.609309 0.75986 -0.226617 0.706901 0.615833 -0.347909 0.698069 0.512899 -0.499634 0.698067 0.512901 -0.499635 0.698067 0.245325 -0.672695 0.698066 0.245325 -0.672695 0.698066 -0.0708419 -0.71252 0.698066 -0.0708418 -0.712521 0.706899 -0.24729 -0.662677 0.698068 -0.601239 -0.388862 0.69807 -0.601237 -0.388861 0.700603 -0.391972 -0.596249 0.79609 -0.364307 -0.483241 0.684044 -0.298489 -0.665573 0.380733 -0.907276 0.178585 0.734317 -0.649781 0.196376 0.707053 -0.706408 0.0326218 0.705899 -0.640331 0.302792 0.703401 -0.557821 0.440526 0.500115 -0.62077 0.603764 0.705219 -0.431883 0.562266 0.704388 -0.294775 0.645713 0.492757 -0.260954 0.830117 0.696094 0.454141 0.556067 0.69609 0.454142 0.55607 0.703399 0.20543 0.680462 0.500117 0.163657 0.850353 0.705222 0.032487 0.708241 0.70439 -0.127704 0.698231 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706177 -0.645942 -0.289953 0.706177 -0.645942 -0.289953 0.706177 -0.597477 -0.379916 0.706176 -0.597477 -0.379916 0 -0.83069 -0.556736 0.0420199 -0.843106 -0.536103 0 -0.868699 -0.49534 0 -0.912302 -0.409518 0.0629304 -0.920069 -0.38667 0 -0.891534 -0.452954 0.706177 0.645943 0.289953 0.706178 0.645941 0.289953 0.706178 0.597475 0.379915 0.706179 0.597475 0.379914 -0.00948919 -0.569516 0.821925 -0.00154309 -0.609152 0.793052 0.0020751 -0.423917 0.905699 -2.08892e-05 -0.415284 0.909692 8.44993e-06 -0.193625 0.981076 -0.00278484 -0.179912 0.983679 0.00262141 0.0320417 0.999483 -2.18786e-05 0.0458218 0.99895 2.64894e-05 0.272319 0.962207 -0.00416126 0.289012 0.957316 0.00144342 0.449099 0.893481 -0.0172865 0.632456 0.774403 -0.0118231 0.643472 0.765378 0 0.784801 0.619748 -9.85804e-06 -0.642987 0.765877 4.12527e-07 -0.784787 0.619766 0.00078397 -0.786765 0.617253 -0.000435809 -0.904023 0.427483 0.0126652 -0.94223 0.334728 -0.010482 -0.981119 0.19312 0 -0.995395 0.0958562 0 -0.879716 -0.4755 -0.0178427 -0.839548 -0.542993 -0.00272591 -0.766231 -0.64256 0.00733863 -0.549311 -0.835586 -0.00493703 -0.579862 -0.8147 0.00112356 -0.349618 -0.936892 0.0112955 -0.223192 -0.974709 -0.0189626 -0.0989186 -0.994915 -0.00489025 0.00893987 -0.999948 0.00688684 0.199935 -0.979785 -0.0388911 0.426311 -0.90374 -0.00580968 0.342611 -0.939459 0.000323481 0.539367 -0.842071 0 0.99216 0.124973 -0.00756882 0.989774 0.142443 0.00704766 0.958266 -0.285789 -0.00552134 0.966873 -0.2552 3.8341e-06 0.893206 -0.449648 -6.35328e-07 0.870666 -0.491874 1.12793e-05 0.870572 -0.49204 1.86415e-06 0.71631 -0.697782 -0.0308316 0.766297 -0.641746 -0.0015307 0.61577 -0.787925 0 -0.834235 0.55141 -0.0110687 -0.846926 0.531596 0.0012252 -0.70128 0.712885 -0.00871444 -0.552687 0.833344 0.0162802 -0.497509 0.867306 -0.00109746 -0.33537 0.942086 0.000330635 -0.283769 0.958893 -0.00358641 -0.147447 0.989063 0.0321401 -0.0313082 0.998993 -0.00116095 0.101224 0.994863 0.00093827 0.287802 0.95769 0.0315928 0.42105 0.906487 -0.00427792 0.507479 0.861654 0.000330049 0.637486 0.770462 -0.00703166 0.798183 0.602374 -0.0104215 0.801695 0.597642 0.009557 0.976536 0.215141 0.0171095 0.979195 0.2022 0 1 0.000476635 0 0.907409 -0.420249 0 0.907409 -0.420249 0 0.850928 -0.525282 0 0.850928 -0.525282 0 0.782345 -0.622845 0 0.782345 -0.622845 0 -0.782345 0.622845 0 -0.782345 0.622845 0 -0.850928 0.525282 0 -0.850928 0.525282 0 -0.907409 0.420249 0 -0.907409 0.420249 -0.879242 0.328461 -0.345033 -0.887084 0.262505 -0.379701 -0.954989 0.0628361 -0.289909 -0.960101 0.0479716 -0.275507 -0.978436 0.0426953 -0.202092 -0.978976 0.0415814 -0.199692 -0.991396 0.0653831 -0.113393 -0.990797 0.0653145 -0.118554 -0.965171 -0.252475 0.0685657 -0.793207 -0.484756 -0.368557 -0.859466 -0.500898 -0.102074 -0.839105 -0.531551 -0.115569 -0.884192 -0.429633 0.183359 -0.876485 -0.445364 0.182823 -0.859293 -0.12992 -0.494709 -0.938546 0.0827955 -0.335077 -0.933194 0.103692 -0.344089 -0.821647 -0.285821 -0.493155 -0.847484 -0.319746 -0.423713 -0.891282 -0.268148 -0.365667 -0.947044 -0.282772 -0.152143 -0.938319 -0.304857 -0.163156 -0.970911 -0.235959 0.0406809 -0.989048 -0.147585 0.00175486 -0.807335 0.113093 -0.579155 -0.693239 -0.149558 -0.705019 -0.770716 -0.312707 -0.555167 -0.902135 0.184023 -0.390241 -0.88785 0.266314 -0.375232 -0.749525 0.305974 -0.58702 -0.710139 0.337464 -0.617916 -0.276011 -0.0920218 -0.956739 -0.145864 0.468609 -0.87128 -0.197806 0.597635 -0.776984 -0.147937 0.632561 -0.760251 -0.111688 -0.989366 0.0931705 -0.0948735 -0.86718 0.488875 -0.10577 -0.864347 0.491648 -0.0780596 -0.859226 -0.505606 -0.143538 -0.935235 -0.323623 -0.177909 -0.93394 -0.310007 -0.097295 -0.984233 -0.147712 -0.110862 -0.989482 0.092922 -0.0290589 0.234939 -0.971576 -0.13493 -0.176648 -0.974982 0.129845 -0.136407 -0.982107 -0.156022 -0.418 -0.894949 -0.216098 -0.446912 -0.868085 -0.0506089 -0.567036 -0.822137 -0.143394 -0.752262 -0.643071 -0.27378 -0.683762 -0.676398 -0.14248 -0.792522 -0.592966 -0.354223 -0.0469807 -0.93398 -0.457112 -0.33904 -0.822254 -0.363196 -0.337662 -0.868374 -0.490852 -0.598783 -0.63287 -0.397294 -0.616136 -0.680099 -0.522596 -0.77906 -0.34635 -0.442822 -0.810895 -0.382568 -0.546594 -0.837293 0.0132461 -0.493391 -0.869799 -0.00391538 -0.55336 -0.738414 0.385406 -0.546229 -0.743897 0.385034 -0.17641 -0.0739296 -0.981537 -0.302665 -0.426418 -0.852386 -0.186327 -0.418598 -0.888852 -0.325671 -0.703309 -0.631898 -0.20848 -0.710439 -0.67217 -0.343265 -0.885273 -0.313786 -0.241863 -0.905795 -0.347905 -0.351515 -0.93363 0.0690843 -0.282651 -0.957935 0.0496872 -0.345033 -0.819165 0.458171 -0.333673 -0.82489 0.456311 -0.879552 0.328864 -0.343857 -0.763484 0.428046 -0.4836 -0.693961 0.439329 -0.570446 -0.651404 0.485298 -0.583231 -0.484431 0.550836 -0.679637 -0.918286 0.134896 -0.372228 -0.901026 0.159454 -0.403393 -0.758731 0.0519707 -0.649328 -0.805285 0.0582875 -0.590016 -0.700529 0.000178852 -0.713624 -0.633826 0.298488 -0.713561 -0.461117 0.31227 -0.830578 -0.425663 0.541292 -0.72513 -0.341488 0.576501 -0.742316 -0.172202 0.282427 -0.943706 -0.179204 0.280569 -0.942957 -0.42409 0.27869 -0.861673 -0.486864 0.0415187 -0.872491 -0.50266 0.0378824 -0.863654 -0.601388 -0.237878 -0.762723 -0.531855 -0.239389 -0.812295 -0.642826 -0.466611 -0.607494 -0.575095 -0.487872 -0.656694 -0.685234 -0.631447 -0.362945 -0.629213 -0.667035 -0.398942 -0.721677 -0.690744 -0.0453386 -0.685622 -0.725423 -0.060692 -0.739938 -0.603738 0.296635 -0.725682 -0.621145 0.295914 -0.148949 0.947809 -0.28191 -0.826271 0.344678 0.445504 -0.651412 0.738854 -0.172504 -0.992269 0.123062 0.0160864 -0.992328 0.120486 -0.0277296 -0.976262 0.205787 0.067554 -0.978909 0.197725 0.0514042 -0.963218 0.257639 0.0763715 -0.851017 0.483081 -0.205916 -0.880894 0.465919 -0.0833348 -0.902136 0.431371 -0.00830657 -0.895768 0.444327 -0.0131607 -0.919311 0.391397 0.0409372 -0.740532 0.568141 0.358926 -0.783613 0.511574 0.352483 -0.707955 0.678333 0.19663 -0.918517 0.393261 0.0408949 -0.938742 0.336345 0.0750766 -0.7859 0.39753 0.473635 -0.847486 0.235506 0.475714 -0.793259 0.11216 0.598465 -0.856962 -0.11637 0.502069 -0.844209 -0.148445 0.515048 -0.884164 -0.350785 0.308551 -0.877676 -0.366616 0.308672 -0.945948 0.316592 0.0703721 -0.960044 0.267537 0.0820924 -0.891348 0.206665 0.40347 -0.944831 0.0222915 0.326798 -0.94185 -0.000625257 0.336033 -0.970926 -0.142001 0.192713 -0.965173 -0.174407 0.194997 -0.0641083 0.106974 0.992193 -0.216847 0.243164 0.945436 -0.144758 -0.133894 0.980366 -0.171079 -0.142477 0.974901 -0.0910062 -0.327631 0.940413 -0.14647 -0.521905 0.840334 -0.0954259 -0.546059 0.832294 -0.105836 -0.828336 0.550143 -0.113067 -0.826048 0.552141 -0.334009 -0.780141 0.528978 -0.149337 0.988774 -0.00485892 -0.172205 0.970222 0.170337 -0.0691396 0.975156 0.210452 -0.082156 0.832917 0.547266 0.0810562 0.794522 0.601801 -0.19179 0.575952 0.794667 -0.0380323 0.509941 0.859368 -0.122139 0.297217 0.946966 -0.341495 0.921944 -0.182758 -0.169165 0.967822 -0.186291 -0.269504 0.955786 -0.11765 -0.693995 0.706806 -0.137104 -0.714752 0.698712 0.0305109 -0.41219 0.90527 0.102888 -0.486903 0.798516 0.353973 -0.354182 0.813851 0.460654 -0.447647 0.613281 0.650768 -0.378519 0.59539 0.708685 -0.480138 0.335413 0.810534 -0.413117 0.295614 0.861364 -0.514076 -0.00429772 0.857734 -0.455181 -0.0542402 0.888746 -0.542688 -0.365319 0.756328 -0.499642 -0.406172 0.765103 -0.553286 -0.673506 0.490167 -0.546676 -0.679427 0.489412 -0.344679 -0.77373 0.531544 -0.288262 -0.495688 0.819267 -0.346235 -0.457104 0.819254 -0.253714 -0.130617 0.95842 -0.332838 -0.0785653 0.939705 -0.224032 0.243663 0.94363 -0.313032 0.29063 0.904182 -0.20153 0.575791 0.79237 -0.291647 0.603687 0.741959 -0.187835 0.826728 0.53032 -0.2693 0.832177 0.484725 -0.179211 0.968718 0.171663 -0.463845 0.876334 0.129951 -0.425694 0.890794 -0.158968 -0.484449 0.854403 -0.187895 -0.87538 0.459604 -0.149915 -0.889599 0.451218 -0.0708299 -0.689727 0.723994 0.010418 -0.745699 0.632549 0.209319 -0.502662 0.789011 0.353259 -0.593278 0.601769 0.534693 -0.54628 0.591671 0.592877 -0.633761 0.367687 0.680553 -0.589989 0.335825 0.734258 -0.678232 0.0729681 0.731217 -0.640943 0.0288618 0.767046 -0.718701 -0.24926 0.649105 -0.691732 -0.287811 0.662323 -0.73991 -0.529841 0.41449 -0.727055 -0.547577 0.414187 -0.572883 0.697452 -0.430541 -0.850726 0.4774 -0.219897 -0.879517 0.371675 -0.297165 -0.654676 0.591383 -0.470815 -0.764996 0.503858 -0.401134 -0.845144 0.420316 -0.330252 -0.851115 0.428852 -0.302802 -0.850697 0.447295 -0.276118 -0.850697 0.447295 -0.276118 -0.851115 0.462883 -0.247675 -0.3458 0.734081 -0.58442 -0.488403 0.682689 -0.543506 -0.149207 0.773588 -0.615873 -0.201915 0.768402 -0.60728 -0.201875 0.833409 -0.514467 -0.844348 0.486185 -0.225167 -0.654679 0.685916 -0.317669 -0.573005 0.741756 -0.348515 -0.488418 0.791814 -0.366714 -0.3458 0.851429 -0.394323 -0.573005 0.64398 -0.506907 -0.572885 0.697451 -0.43054 -0.201876 0.833408 -0.514467 -0.201916 0.887245 -0.41476 -0.149217 0.89725 -0.415544 -0.340892 -0.853057 0.395077 -0.994035 0.092804 -0.0572884 -0.994036 0.0990467 -0.0456224 -0.994251 0.0971642 -0.0449998 -0.991754 0.100097 -0.0800305 -0.996676 0.0665547 -0.0469926 -0.658679 -0.640259 0.395235 -0.93179 -0.308884 0.190676 -0.994046 0.086436 -0.0663493 -0.993745 -0.087368 0.0695558 -0.971837 -0.184364 0.146777 -0.994056 0.0959928 -0.0513631 -0.994035 0.0928039 -0.0572884 -0.931791 -0.308884 0.190676 -0.931639 -0.280183 0.231401 -0.558464 -0.758486 0.335882 -0.739295 -0.611033 0.282988 -0.93179 -0.329386 0.152549 -0.888072 -0.421879 0.182608 -0.971843 -0.213814 0.0990237 -0.237286 -0.826625 0.51028 -0.237286 -0.881493 0.408247 -0.108128 -0.908123 0.404502 -0.887838 -0.360002 0.286606 -0.739298 -0.526815 0.419411 -0.658467 -0.584631 0.473949 -0.558103 -0.649168 0.516819 -0.340892 -0.735485 0.585538 -0.658679 -0.682756 0.316206 -0.658679 -0.640259 0.395235 -0.237287 -0.826625 0.51028 -0.237191 -0.755858 0.610262 -0.108041 -0.777766 0.619199 -0.939508 0.267531 -0.213899 -0.939609 0.253431 -0.230017 -0.939483 0.253595 -0.230352 -0.939572 0.253592 -0.229989 -0.93969 0.254037 -0.229015 -0.939849 0.252923 -0.229597 -0.939867 0.252857 -0.229594 -0.939728 0.253188 -0.229799 -0.939515 0.311094 -0.143294 -0.940503 0.31636 -0.123981 -0.939696 0.318811 -0.123814 -0.939887 0.318531 -0.123086 -0.93969 0.31865 -0.124277 -0.939536 0.319387 -0.123548 -0.939493 0.319542 -0.123473 -0.939514 0.319473 -0.123495 -0.939749 0.318829 -0.123367 -0.939508 0.311111 -0.143302 -0.939511 0.311103 -0.143297 -0.939694 0.301562 -0.161358 -0.939694 0.301562 -0.161358 -0.939498 0.29149 -0.179938 -0.939498 0.29149 -0.179938 -0.939694 0.279392 -0.197272 -0.939693 0.279392 -0.197272 -0.939511 0.267523 -0.213894 -0.939515 0.267516 -0.213887 -0.939697 0.253868 -0.229174 0 0.979717 -0.200387 0.0420467 0.958113 -0.283288 0 0.993338 -0.115235 -0.701807 0.697918 -0.142749 -0.701808 0.697918 -0.142749 1.49033e-05 -0.68731 -0.726364 0.00376804 -0.916713 -0.39953 -0.0244211 -0.979824 -0.198363 -0.0191989 -0.976172 -0.216147 -0.0040414 -0.997182 -0.0749106 0 -0.999961 -0.00882448 1.70768e-05 -0.819906 -0.572498 -0.016839 -0.778446 -0.627485 -0.00323795 -0.845526 -0.533924 -0.0172162 -0.554988 -0.83168 0.0205198 -0.654643 -0.75566 -0.0146346 -0.40835 -0.912708 -2.05228e-06 -0.468109 -0.883671 2.52414e-05 -0.237504 -0.971386 0.0147053 -0.172307 -0.984934 -0.004568 -0.0130557 -0.999904 -0.000649197 0.0427096 -0.999087 0.00313958 0.263014 -0.964787 0.014328 0.23214 -0.972577 -0.0159706 0.585789 -0.810306 0 0.618412 -0.785854 0.696088 0.420624 -0.581839 0.492749 -0.309364 -0.813322 0.696089 0.420624 -0.581838 0.703396 0.165022 -0.691377 0.500107 0.113319 -0.858517 0.705214 -0.00925653 -0.708935 0.704381 -0.168586 -0.689512 0.704384 -0.332273 -0.627246 0.705217 -0.464234 -0.535869 0.500116 -0.655232 -0.566176 0.703398 -0.582786 -0.406929 0.697549 -0.69691 -0.16656 0.733224 -0.663907 -0.147004 0.707049 -0.707106 0.00902783 0.702132 -0.614184 0.360262 0.702129 -0.614187 0.360263 0.702129 -0.698352 0.138992 0.702127 -0.698355 0.138991 0.458492 0.12999 0.87914 0.69474 -0.563596 0.446874 0.694741 -0.563595 0.446874 0.7057 -0.370138 0.60414 0.754936 -0.30589 0.580088 0.624884 -0.221666 0.748588 0.705014 -0.15716 0.69156 0.703697 0.016607 0.710306 0.704396 0.199688 0.681139 0.704397 0.360065 0.611702 0.458492 0.552145 0.696362 0.69474 0.711525 -0.105207 0.694741 0.711524 -0.105207 0.702916 0.685818 0.188581 0.466756 0.822343 0.325408 0.705015 0.611846 0.358608 0.703697 0.506611 0.498152 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.706179 -0.574076 0.414424 0.706179 -0.574077 0.414425 0.706178 -0.627754 0.327471 0.706177 -0.627755 0.327472 0 -0.897492 0.441031 0.0420203 -0.885832 0.462099 0 -0.863326 0.504646 0 -0.810804 0.585318 0.0629306 -0.7949 0.603468 0 -0.838037 0.545614 0.706176 0.574079 -0.414427 0.706175 0.57408 -0.414427 0.706175 0.627756 -0.327473 0.706177 0.627755 -0.327472 0 -0.783576 0.621296 0 0.9657 -0.259661 -0.0323172 0.988728 -0.146194 -0.0129596 0.998187 -0.0587715 0.015622 0.981222 0.192248 -0.00369027 0.964206 0.26513 0.00326107 0.862731 0.505654 0.0251181 0.809979 0.58592 -3.33551e-05 0.281327 0.959612 4.09199e-05 0.528752 0.848776 0.00666574 0.50726 0.861767 -0.00509138 0.713026 0.70112 -0.0225151 -0.81685 0.57641 0.0133491 -0.513695 0.857869 1.55485e-05 -0.46644 0.884553 9.83739e-08 -0.293783 0.955872 -0.00405105 -0.221603 0.975129 0.00867163 -0.117953 0.992981 -0.00792429 0.023373 0.999695 0.00306858 0.121229 0.99262 -0.00558355 0.30634 0.951906 0 -0.863194 0.504872 0.000328586 -0.862561 0.505953 -7.92115e-05 -0.947082 0.320991 -0.0072709 -0.980738 0.195194 0 -0.987035 0.160506 0.994042 0.0868122 -0.0659056 0.97185 -0.18765 0.142459 0.65891 -0.640087 0.395129 0.108088 -0.892234 0.438447 0.558294 -0.744598 0.365898 0.341054 -0.843682 0.414588 0.237324 -0.875497 0.42093 0.23762 -0.838599 0.490192 0.15399 -0.840779 0.519017 0.237621 -0.814034 0.529986 0.237426 -0.773704 0.587376 0.887897 -0.412884 0.202893 0.739451 -0.604201 0.296907 0.108163 -0.780611 0.615587 0.341053 -0.748725 0.568413 0.65891 -0.599129 0.454843 0.558604 -0.649886 0.515374 0.739455 -0.536194 0.407065 0.971845 -0.211469 0.103916 0.931702 -0.329513 0.152814 0.931867 -0.308717 0.190573 0.658689 -0.678925 0.324331 0.658911 -0.640086 0.395128 0.931867 -0.308718 0.190573 0.931867 -0.288963 0.219374 0.888088 -0.357142 0.289394 0.994042 0.0978222 -0.0480702 0.994042 0.0978223 -0.0480702 0.994053 0.0940177 -0.0549564 0.994978 0.0851738 -0.0525783 0.994053 0.0912635 -0.0594178 0.994042 0.0868122 -0.0659056 0 0.789143 -0.61421 -0.0635015 0.809168 -0.584137 0 0.831408 -0.555663 0 0.869338 -0.494217 -0.0635016 0.884826 -0.461574 0 0.902736 -0.430195 0.0684061 0.12866 0.989327 0.0983791 -0.283429 0.953934 0.73816 0.657106 0.152749 0.933082 0.356089 0.0505905 0.885792 0.455161 -0.0905591 0.902775 0.429289 -0.0266163 0.900887 0.434054 -0.000508122 0.893719 0.445252 -0.0549232 0.982611 0.180073 0.045264 0.968947 0.23973 0.0605928 0.959187 0.273131 0.0732147 0.978164 0.203628 0.0416062 0.993506 0.112202 -0.0189025 0.993503 0.113106 -0.0126207 0.955084 0.289123 0.0649816 0.937215 0.342467 0.0659107 0.81278 0.40627 0.417533 0.759738 0.54194 0.359304 0.532647 0.636103 0.558266 0.600307 0.596056 0.533243 0.364127 0.645882 0.671006 0.456011 0.60818 0.649747 0.187419 0.630579 0.753156 0.145513 0.987235 -0.06475 0.172307 0.975208 0.138854 0.884955 0.457782 -0.0853893 0.71267 0.701236 -0.0192274 0.69772 0.716309 0.00937408 0.461103 0.884975 0.0648261 0.423351 0.899899 0.104668 0.179688 0.973711 0.139999 0.275268 0.832462 0.480868 0.918217 0.394615 0.0340037 0.916084 0.399615 0.0331345 0.771366 0.559084 0.304006 0.722822 0.661103 0.201175 0.503309 0.799387 0.328117 0.487237 0.808731 0.329475 0.353643 0.82969 0.431916 0.17731 0.859749 0.47895 0.301511 0.599394 0.741497 0.275286 0.327234 0.903956 0.876441 -0.35203 0.328522 0.884046 -0.345406 0.314892 0.725682 -0.52823 0.440861 0.73982 -0.521048 0.425646 0.546204 -0.660306 0.515419 0.553286 -0.658169 0.510577 0.333634 -0.758622 0.559626 0.344989 -0.757645 0.554036 0.10576 -0.807542 0.58025 0.121175 -0.808906 0.575316 0.145475 -0.10207 0.984083 0.171345 -0.108887 0.979176 0.342321 -0.0810604 0.93608 0.242327 -0.0639159 0.968087 0.521631 -0.00738979 0.853139 0.443197 0.00745047 0.896393 0.684258 0.069036 0.725965 0.629494 0.0826002 0.772603 0.792145 0.134391 0.595353 0.839075 -0.117288 0.531222 0.858962 -0.1147 0.499027 0.68563 -0.248143 0.684352 0.721186 -0.245305 0.647855 0.493426 -0.360109 0.79174 0.54614 -0.35957 0.756598 0.282724 -0.445761 0.849332 0.351086 -0.450412 0.820895 0.0859274 -0.501451 0.860908 0.106816 -0.504947 0.856516 0.147942 0.954389 -0.259336 0.205583 0.953925 -0.218548 0.34146 0.915077 -0.214565 0.424998 0.88451 -0.192404 0.484351 0.847633 -0.216617 0.687666 0.700058 -0.192441 0.647365 0.74644 -0.154099 0.870205 0.441654 -0.218371 0.850012 0.501365 -0.161596 0.0290103 0.981107 0.191279 0.135839 0.809542 0.57113 -0.181677 0.822291 0.539288 0.289896 0.535713 0.793077 0.0131297 0.594306 0.804132 0.143537 0.269965 0.952111 0.32442 0.28424 0.902197 0.209398 0.311558 0.926868 0.489615 0.328402 0.807731 0.398062 0.358351 0.844471 0.641638 0.360181 0.677178 0.57571 0.390866 0.718179 0.805188 0.369211 0.464064 0.849347 0.243748 0.468185 0.891416 0.219319 0.396581 0.946585 0.0216173 0.321729 0.938296 0.0206515 0.345215 0.97139 -0.146589 0.18685 0.963017 -0.160395 0.216498 0.146444 0.61462 -0.775111 0.112061 -0.942737 0.314148 0.824721 -0.223832 -0.51936 0.651393 0.505391 -0.565921 0.942263 0.0505076 -0.331043 0.971801 0.0579663 -0.228566 0.978816 0.0428012 -0.200217 0.98931 0.0699868 -0.127936 0.993672 0.0655664 -0.0911949 0.851107 0.405219 -0.333788 0.873457 0.311168 -0.374496 0.889407 0.265298 -0.372253 0.901405 0.215642 -0.375456 0.895301 0.224209 -0.384925 0.918228 0.153248 -0.365203 0.741743 -0.046829 -0.669048 0.782191 -0.0614846 -0.619997 0.708896 0.148456 -0.689512 0.911964 0.158775 -0.378302 0.938587 0.101262 -0.32985 0.78696 -0.228108 -0.57329 0.849347 -0.309299 -0.427719 0.79219 -0.471985 -0.386866 0.856724 -0.497017 -0.137834 0.843571 -0.523953 -0.117736 0.884012 -0.439073 0.160431 0.87748 -0.447158 0.173433 0.921869 0.102089 -0.373811 0.959989 0.0825437 -0.267597 0.891439 -0.256226 -0.373745 0.944652 -0.277033 -0.175744 0.941308 -0.296225 -0.161831 0.970892 -0.237064 0.0341915 0.965073 -0.255178 0.0593243 0.177801 -0.722848 -0.66774 0.111576 -0.990158 -0.0844817 0.0785817 -0.975042 -0.207651 0.233476 -0.909243 -0.344624 0.103207 -0.907345 -0.407521 0.0891687 -0.836278 -0.541007 0.0726537 -0.995328 0.0635935 0.351197 -0.9275 0.128079 0.155871 -0.987547 -0.0213584 0.333938 -0.838227 0.431116 0.105758 -0.88066 0.461793 0.233619 -0.841772 0.486664 -0.0904702 -0.103943 -0.99046 0.249284 -0.142204 -0.957933 0.280781 -0.724045 -0.630017 0.113662 -0.672593 -0.731232 0.0131004 -0.452862 -0.891484 0.402523 -0.464649 -0.788719 0.151282 -0.385704 -0.910135 0.0873499 0.0504943 -0.994897 0.0301556 0.264713 -0.963856 0.178758 0.311544 -0.933266 0.111635 0.63006 -0.76848 0.341466 0.601964 -0.721831 0.692777 0.463591 -0.552397 0.714413 0.309343 -0.627631 0.412912 0.340317 -0.8448 0.487263 0.0678141 -0.870618 0.353601 -0.0143627 -0.935286 0.447583 -0.27915 -0.849556 0.377674 -0.336641 -0.862575 0.480036 -0.552057 -0.681761 0.412114 -0.614255 -0.672943 0.513924 -0.75561 -0.406122 0.454265 -0.806087 -0.379298 0.542566 -0.839017 -0.0408941 0.49906 -0.866497 -0.0110214 0.553202 -0.75277 0.356798 0.546585 -0.755084 0.362068 0.344662 -0.837196 0.42463 0.287817 -0.956775 0.0417601 0.346277 -0.938083 0.00961428 0.253017 -0.903718 -0.345365 0.332866 -0.862946 -0.380164 0.223307 -0.711309 -0.666464 0.313043 -0.655458 -0.687298 0.200937 -0.419517 -0.885229 0.291656 -0.36349 -0.884767 0.187454 -0.0693799 -0.97982 0.269277 -0.0283398 -0.962646 0.179699 0.311327 -0.933158 0.463498 0.307426 -0.831059 0.425021 0.568438 -0.70444 0.484351 0.573561 -0.66063 0.870903 0.361387 -0.333058 0.89297 0.277508 -0.354394 0.690174 0.335031 -0.641416 0.744781 0.121838 -0.656092 0.503285 0.0648561 -0.861683 0.593138 -0.183074 -0.78401 0.545202 -0.236797 -0.804165 0.633558 -0.42282 -0.647941 0.588806 -0.483519 -0.647701 0.677988 -0.607779 -0.413445 0.63989 -0.659643 -0.394223 0.718479 -0.689505 -0.0914971 0.691089 -0.719765 -0.0658314 0.739775 -0.61758 0.267071 0.726918 -0.626181 0.281935 0.939621 0.270058 -0.210193 0.939565 0.307274 -0.150995 0.93842 0.317099 -0.137169 0.939692 0.314491 -0.134442 0.939392 0.315656 -0.133803 0.939414 0.315576 -0.133839 0.939897 0.314266 -0.133533 0.939965 0.314174 -0.13327 0.939946 0.314204 -0.133328 0.939758 0.314644 -0.133619 0.939564 0.315134 -0.133831 0.93962 0.260749 -0.221638 0.939837 0.260293 -0.221255 0.940955 0.259416 -0.217503 0.939692 0.261146 -0.220868 0.939965 0.25994 -0.221125 0.939976 0.259899 -0.22113 0.939692 0.261455 -0.220498 0.939471 0.261041 -0.221926 0.93945 0.261055 -0.222002 0.939565 0.27269 -0.207019 0.94337 0.263171 -0.201976 0.936007 0.294974 -0.192045 0.939622 0.284519 -0.190155 0.939661 0.295352 -0.172643 0.937285 0.30302 -0.172266 0.94337 0.298499 -0.144746 0.939621 0.308931 -0.14722 0.939692 0.314278 -0.134935 0.149347 0.780292 -0.607322 0.488783 0.688452 -0.53584 0.346108 0.846942 -0.403607 0.655058 0.682088 -0.325047 0.850962 0.474141 -0.22595 0.850962 0.474141 -0.22595 0.850962 0.4566 -0.259576 0.850962 0.4566 -0.259576 0.850962 0.436678 -0.291849 0.850962 0.436678 -0.291849 0.850962 0.414479 -0.322599 0.850963 0.414478 -0.322599 0.655064 0.596255 -0.464081 0.57344 0.651082 -0.497252 0.573329 0.681194 -0.455268 0.57333 0.681193 -0.455268 0.57333 0.712271 -0.404925 0.573328 0.712271 -0.404925 0.57344 0.736308 -0.359191 0.488786 0.78755 -0.375304 0.346106 0.74037 -0.576249 0.202128 0.776399 -0.59695 0.202091 0.814253 -0.544197 0.202091 0.814253 -0.544197 0.202091 0.851401 -0.48402 0.202091 0.851401 -0.48402 0.202129 0.881594 -0.426539 0.149344 0.892612 -0.425371 -0.7071 -0.657572 0.260017 -0.671179 -0.671878 0.313207 -0.706473 -0.64221 0.297427 -0.706473 -0.602236 0.371764 -0.706472 -0.602237 0.371764 -0.706524 -0.554756 0.439397 -0.67281 -0.578791 0.46079 -0.707095 -0.527144 0.471313 -0.706472 0.642211 -0.297428 -0.706471 0.642211 -0.297428 -0.706471 0.602237 -0.371764 -0.706472 0.602237 -0.371764 -0.706472 0.553698 -0.440813 -0.706473 0.553697 -0.440812 -0.694737 -0.641195 0.325898 -0.487519 -0.731778 -0.476264 -0.694742 -0.641192 0.325895 -0.702915 -0.710194 0.0391701 -0.494619 -0.867873 -0.0463548 -0.705015 -0.694096 -0.145549 -0.703697 -0.63867 -0.311306 -0.704394 -0.535815 -0.465544 -0.704394 -0.405821 -0.582356 -0.487516 -0.395605 -0.778347 -0.694743 0.392341 -0.602827 -0.69474 0.392342 -0.60283 -0.702916 0.114597 -0.70198 -0.494615 0.0463525 -0.867875 -0.705014 -0.0707894 -0.705652 -0.703696 -0.241503 -0.668198 -0.697345 0.701927 0.144945 -0.697344 0.701928 0.144945 -0.697344 0.561883 0.44497 -0.642341 0.611758 0.461682 -0.707005 0.450835 0.544877 -0.697344 0.301932 0.650037 -0.697343 0.301933 0.650038 -0.697343 -0.0224505 0.716386 -0.697345 -0.0224513 0.716384 -0.707006 -0.200684 0.678136 -0.650498 -0.362456 0.667441 -0.700892 -0.604122 0.379193 -0.607903 -0.652109 0.452999 -0.706716 -0.496155 0.504365 -0.69922 -0.355719 0.620125 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.891461 0.453098 0 0.637955 -0.770074 0.0478509 0.544855 -0.837164 0.0190384 0.468675 -0.883166 -0.0231329 0.234656 -0.971803 0.00914088 -0.33989 -0.940421 -0.0343166 -0.186584 -0.98184 -0.00482556 -0.0998156 -0.994994 0.00545963 0.161113 -0.986921 0.0078248 -0.754849 -0.655852 1.69484e-05 -0.730327 -0.683098 -2.46243e-05 -0.571732 -0.82044 1.33774e-05 -0.571833 -0.82037 9.1164e-06 -0.436664 -0.899624 0.0166627 -0.990042 -0.139785 -0.0109406 -0.948675 -0.316063 0.0114739 -0.898843 -0.438121 -2.4206e-05 -0.865565 -0.500797 -1.76306e-05 -0.808943 -0.587888 0.0264228 -0.869523 0.493185 -0.0156571 -0.994956 0.0990872 -1.77322e-05 -0.998482 0.0550704 6.87683e-06 -0.978713 -0.205232 0.258826 0.965924 0 0.258826 0.965924 0 0.707111 0.707102 0 0.707111 0.707102 0 0.965918 0.258849 0 0.965918 0.258849 0 0.965918 -0.258849 0 0.965918 -0.258849 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.258826 -0.965924 0 0.258826 -0.965924 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.707111 0.707102 0 -0.707111 0.707102 0 -0.258814 0.965927 0 -0.258814 0.965927 0 0.258826 0.965924 0 0.258826 0.965924 0 0.707111 0.707102 0 0.707111 0.707102 0 0.965918 0.258849 0 0.965918 0.258849 0 0.965918 -0.258849 0 0.965918 -0.258849 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.258826 -0.965924 0 0.258826 -0.965924 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.707111 0.707102 0 -0.707111 0.707102 0 -0.258814 0.965927 0 -0.258814 0.965927 0 -0.297125 -0.091925 -0.950404 0.0128739 -0.0154481 -0.999798 -0.487307 -0.348157 -0.800824 -0.490083 -0.352383 -0.797273 -0.670125 -0.237119 -0.703354 -0.768752 -0.192171 -0.609993 -0.681824 -0.127182 -0.720376 -0.816972 -0.0646363 -0.573044 -0.787386 -0.0340628 -0.615519 -0.324003 -0.0346135 -0.945423 -0.307171 -0.0294685 -0.951198 -0.0446749 -0.0098387 -0.998953 -0.160908 -0.134055 -0.977823 -0.145651 -0.12977 -0.980788 -0.162274 -0.0996858 -0.981697 -0.156521 -0.0993715 -0.982663 -0.177464 -0.0359685 -0.98347 -0.0374894 -0.029036 -0.998875 -0.0407578 -0.00869909 -0.999131 -0.581648 -0.049732 -0.811919 -0.553852 -0.0559137 -0.830736 -0.539517 -0.144438 -0.829494 -0.514948 -0.145593 -0.844767 -0.485386 -0.233561 -0.842526 -0.677713 -0.257342 -0.688825 -0.560046 -0.28247 -0.77882 -0.433162 -0.41463 -0.800282 -0.435779 -0.429235 -0.79111 -0.144965 -0.153585 -0.977444 -0.145262 -0.154193 -0.977304 0.0037918 -0.00409248 -0.999984 -0.337157 -0.43823 -0.833234 -0.341902 -0.459359 -0.819813 -0.113316 -0.154255 -0.981511 -0.113658 -0.156773 -0.981073 -0.788085 0.000476192 -0.615567 -0.787913 0.000553563 -0.615786 -0.583399 0.00126628 -0.812185 -0.582495 0.00158717 -0.812833 -0.326067 0.00196992 -0.945345 -0.324285 0.00251091 -0.945956 -0.0473008 0.00248649 -0.998878 -0.0447002 0.00319988 -0.998995 -0.233 -0.524446 -0.818943 -0.026908 -0.165052 -0.985918 -0.222446 -0.510781 -0.830434 -0.0750227 -0.549774 -0.831938 -0.0755182 -0.54553 -0.834682 -0.0264428 -0.171964 -0.984748 -0.0784294 -0.158265 -0.984277 -0.0821827 -0.175961 -0.980961 -0.788319 0.00044221 -0.615266 -0.788085 0.000547527 -0.615567 -0.584276 0.0012421 -0.811554 -0.5834 0.00155177 -0.812184 -0.327803 0.00192854 -0.944744 -0.326068 0.00245309 -0.945343 -0.0498881 0.00243612 -0.998752 -0.0473019 0.00314226 -0.998876 0.149694 -0.153958 -0.976672 0.138228 -0.147024 -0.979427 0.419384 -0.434922 -0.796844 0.31253 -0.560925 -0.766608 0.335281 -0.472916 -0.814823 0.398111 -0.424282 -0.813322 0.0652788 -0.1721 -0.982914 0.0586346 -0.161621 -0.985109 0.0216982 -0.169044 -0.98537 0.0202208 -0.165078 -0.986073 0.110083 -0.168346 -0.979562 0.0986371 -0.157195 -0.982629 0.295079 -0.481536 -0.825258 0.178527 -0.533755 -0.826579 0.17256 -0.525432 -0.833153 0.0597035 -0.548252 -0.834179 0.0587844 -0.546147 -0.835625 -0.0499072 0.0179999 -0.998592 -0.125427 0.158539 -0.979354 -0.796424 0.296974 -0.526797 -0.637368 0.309328 -0.705747 -0.711965 0.234235 -0.661996 -0.741469 0.100857 -0.663364 -0.785109 0.0926487 -0.612389 -0.371139 0.458829 -0.807299 -0.157369 0.131789 -0.978707 -0.127882 0.163347 -0.978245 -0.364891 0.445178 -0.817723 -0.0467947 0.0542804 -0.997429 -0.259069 0.172272 -0.950371 -0.28315 0.126175 -0.95074 -0.290939 0.130263 -0.947832 -0.310303 0.0466116 -0.949494 -0.327489 0.0511213 -0.943471 -0.0547822 0.0192687 -0.998312 -0.0507005 0.0369375 -0.998031 -0.0420114 0.0373045 -0.99842 -0.0628664 0.0519767 -0.996668 -0.0590471 0.059214 -0.996498 -0.482442 0.363629 -0.796883 -0.592311 0.393299 -0.703196 -0.425357 0.31645 -0.847898 -0.485372 0.202737 -0.850478 -0.516238 0.207552 -0.830915 -0.546504 0.0779513 -0.833821 -0.582843 0.0741141 -0.809198 0.173883 -0.125287 -0.976764 0.182059 -0.127607 -0.974972 0.200058 -0.0962959 -0.975041 0.212153 -0.0972479 -0.972386 0.237896 -0.0607254 -0.969391 0.224766 -0.0623051 -0.972419 0.566097 -0.141409 -0.812119 0.753917 -0.132694 -0.64343 0.173632 -0.0149684 -0.984697 0.247647 -0.00171197 -0.968849 0.49924 -0.0548323 -0.864727 0.581928 -0.0461421 -0.811931 0.764074 -0.0721767 -0.641079 0.76286 -0.0725221 -0.642484 0.495912 -0.344459 -0.797132 0.508112 -0.363953 -0.780615 0.56975 -0.256739 -0.780686 0.58905 -0.278813 -0.758474 0.627687 -0.171184 -0.759411 -0.221317 0.516216 -0.827369 -0.230612 0.528099 -0.81727 -0.0774027 0.181211 -0.980393 -0.0808294 0.186162 -0.979189 -0.0736127 0.553073 -0.829874 -0.0748085 0.556123 -0.827726 -0.0257277 0.193865 -0.980691 -0.0261417 0.195096 -0.980436 0.766072 0 -0.642755 0.766072 0 -0.642755 0.499992 0 -0.86603 0.499992 0 -0.86603 0.173652 0 -0.984807 0.173652 0 -0.984807 0.760683 0.118402 -0.638234 0.213103 0.0576802 -0.975326 0.217199 0.117356 -0.969047 0.196214 0.0986338 -0.975588 0.168709 0.140425 -0.975612 0.151503 0.115528 -0.981682 0.155364 0.189922 -0.969428 0.130707 0.145658 -0.980663 0.0983641 0.18682 -0.977457 0.0950521 0.173963 -0.980154 0.0551147 0.19027 -0.980184 0.0546814 0.168919 -0.984112 0.0213899 0.221389 -0.974951 0.0237702 0.193875 -0.980738 0.499574 0.0408872 -0.865306 0.575278 0.0744308 -0.814565 0.173646 -0.00833411 -0.984773 0.524132 0.0441913 -0.85049 0.707529 0.160301 -0.688263 0.559337 0.157522 -0.813836 0.234152 0.0718892 -0.969539 0.24324 0.0231084 -0.969691 0.0535819 0.553781 -0.830937 0.0541403 0.555019 -0.830074 0.151138 0.536658 -0.830154 0.162952 0.552373 -0.817515 0.251653 0.490679 -0.834209 0.275255 0.511466 -0.814025 0.603812 0.222153 -0.765545 0.593845 0.247319 -0.765625 0.574713 0.295382 -0.763187 0.472035 0.28927 -0.83277 0.50273 0.403239 -0.764632 0.421721 0.397477 -0.814962 0.393474 0.470437 -0.789852 0.356628 0.452466 -0.817368 0.317156 0.47971 -0.818101 0.766072 0 -0.642755 0.766072 0 -0.642755 0.499992 0 -0.86603 0.499992 0 -0.86603 0.173652 0 -0.984807 0.173652 0 -0.984807 -0.0628481 -0.189199 -0.979926 -0.062388 -0.185687 -0.980626 -0.0210317 -0.194599 -0.980657 -0.0210913 -0.193886 -0.980797 -0.0520758 -0.553825 -0.831003 -0.0637363 -0.583696 -0.809467 -0.108647 -0.545902 -0.830775 -0.178649 -0.529713 -0.829149 -0.17942 -0.538581 -0.823249 0.0186738 -0.193896 -0.980844 0.0188368 -0.194399 -0.980742 0.0546053 -0.187581 -0.98073 0.042294 -0.165294 -0.985337 0.118521 -0.224147 -0.967322 0.0892036 -0.183199 -0.97902 0.147802 -0.128047 -0.980693 0.226573 -0.122199 -0.966298 0.201568 -0.114032 -0.972814 0.233811 -0.0718233 -0.969626 0.198464 -0.0506469 -0.978799 0.215964 -0.0785602 -0.973236 0.462034 -0.373904 -0.804189 0.161027 -0.134288 -0.977771 0.132462 -0.163025 -0.977689 0.118333 -0.134936 -0.983763 0.117584 -0.164256 -0.979384 0.672474 -0.182245 -0.717332 0.742299 -0.172702 -0.64743 0.558136 -0.160061 -0.814165 0.528699 -0.474585 -0.703738 0.493812 -0.367071 -0.788295 0.547214 -0.284757 -0.787064 0.568735 -0.306428 -0.76331 0.599723 -0.230617 -0.766256 0.258745 -0.0249071 -0.965625 0.242125 -0.028145 -0.969837 0.608985 -0.0559632 -0.791205 0.577287 -0.059561 -0.814366 0.792159 -0.0724716 -0.605996 0.758918 -0.0785256 -0.646434 0.0538527 -0.553773 -0.830925 0.0579987 -0.529021 -0.846625 0.16544 -0.559847 -0.811912 0.165623 -0.542374 -0.82365 0.264719 -0.494374 -0.82796 0.27591 -0.544427 -0.792132 0.345234 -0.416182 -0.841193 0.370789 -0.470279 -0.800845 0.416715 -0.421051 -0.805646 -0.265418 -0.120006 -0.956636 -0.0282211 0.0149224 -0.99949 -0.0203998 -0.0151994 -0.999676 -0.0210498 -0.0153535 -0.999661 -0.283955 -0.0478472 -0.957643 -0.307687 -0.0534537 -0.949985 -0.408529 -0.364955 -0.836607 -0.495864 -0.372024 -0.784676 -0.6 -0.355409 -0.716718 -0.666321 -0.352845 -0.656899 -0.59238 -0.252524 -0.765061 -0.697439 -0.250397 -0.671476 -0.7202 -0.164433 -0.673999 -0.893567 -0.111728 -0.434804 -0.784043 -0.0682442 -0.616944 -0.0949095 -0.174204 -0.980125 -0.102111 -0.180919 -0.978183 -0.112364 -0.160568 -0.980608 -0.114297 -0.161656 -0.980206 -0.124961 -0.126316 -0.984088 -0.127748 -0.12633 -0.983728 -0.13801 -0.108904 -0.984425 -0.163221 -0.11128 -0.980294 -0.12274 -0.0643189 -0.990352 -0.274848 -0.494719 -0.824446 -0.283401 -0.501507 -0.817419 -0.354379 -0.453726 -0.817648 -0.340611 -0.445245 -0.828095 -0.430086 -0.426171 -0.795867 -0.126825 -0.150158 -0.980494 -0.13136 -0.152221 -0.979578 -0.581884 -0.386426 -0.715602 -0.523082 -0.0909231 -0.847419 -0.439917 -0.255337 -0.860974 -0.454863 -0.258335 -0.852269 -0.482486 -0.191523 -0.854708 -0.501794 -0.192355 -0.843328 -0.529078 -0.0834842 -0.844456 -0.572362 -0.0817977 -0.815911 0.794248 0 -0.607594 0.706732 -0.0322254 -0.706747 0.609941 0 -0.792447 0.258825 0 -0.965924 0.258825 0 -0.965924 -0.786053 0.00041786 -0.618159 -0.786007 0.000439833 -0.618218 -0.574937 0.00113947 -0.818197 -0.57448 0.00131212 -0.818518 -0.309121 0.00179963 -0.951021 -0.30825 0.00208138 -0.951303 -0.0223343 0.00227998 -0.999748 -0.0210814 0.00264801 -0.999774 0.794248 0 -0.607594 0.706732 0.0322254 -0.706747 0.609941 0 -0.792447 0.258825 0 -0.965924 0.258825 0 -0.965924 -0.786159 0.000325613 -0.618025 -0.786053 0.000376183 -0.61816 -0.575258 0.000925296 -0.817972 -0.574937 0.00104563 -0.818197 -0.309785 0.00143476 -0.950806 -0.30912 0.00164884 -0.951021 -0.0233519 0.00181647 -0.999726 -0.0223341 0.00211451 -0.999748 0.462188 0.373831 -0.804135 0.17812 0.126105 -0.975895 0.258714 0.0293056 -0.965509 0.24306 0.0232639 -0.969732 0.23394 0.0716118 -0.96961 0.197977 0.050135 -0.978924 0.146684 0.127221 -0.980968 0.380376 0.456532 -0.804297 0.445167 0.497369 -0.744615 0.338215 0.465291 -0.817995 0.273127 0.508137 -0.816822 0.223754 0.457387 -0.860658 0.172442 0.581023 -0.795409 0.790857 0.0923089 -0.604999 0.690538 0.0662815 -0.720253 0.593656 0.246768 -0.765949 0.573566 0.297067 -0.763396 0.25233 0.134868 -0.958196 0.198333 0.0953127 -0.975489 0.612499 0.198223 -0.765214 0.669383 0.189306 -0.718394 0.59254 -0.0643575 -0.802966 0.578386 0.0534022 -0.814013 0.608796 0.0612602 -0.790958 0.0520805 0.553829 -0.831 0.0549161 0.561151 -0.82589 0.102568 0.546585 -0.831098 0.140929 0.538847 -0.830532 0.565335 0.296042 -0.769906 0.464493 0.37475 -0.802377 0.161252 0.134087 -0.977762 0.13272 0.16285 -0.977684 0.128104 0.153671 -0.979783 0.0963908 0.182577 -0.978455 0.0940168 0.174381 -0.98018 0.0555807 0.190119 -0.980186 0.0532075 0.156927 -0.986176 0.0248487 0.255519 -0.966485 0.0261615 0.193848 -0.980683 -0.755735 0.0697437 -0.651153 -0.784749 0.0614038 -0.616764 -0.549206 0.0542977 -0.833921 -0.574629 0.0493347 -0.816926 -0.295363 0.0344048 -0.954765 -0.309666 0.0323883 -0.950294 -0.0231102 0.0125861 -0.999654 -0.0233612 0.0125594 -0.999648 -0.709521 0.180715 -0.681118 -0.73973 0.17718 -0.649158 -0.513574 0.138957 -0.846719 -0.53675 0.138139 -0.832356 -0.278325 0.0869259 -0.956546 -0.287559 0.0870824 -0.953796 -0.0276996 0.0301035 -0.999163 -0.0205749 0.0297252 -0.999346 -0.176203 0.530343 -0.82927 -0.181053 0.537887 -0.823345 -0.0615917 0.185877 -0.980641 -0.063357 0.188963 -0.979938 -0.0596715 0.553594 -0.830646 -0.0602909 0.555301 -0.829461 -0.0208368 0.193873 -0.980805 -0.021051 0.194562 -0.980664 -0.0231551 0.044942 -0.998721 -0.685925 0.260426 -0.679474 -0.41392 0.313393 -0.854667 -0.140905 0.132781 -0.981079 -0.767743 0.366591 -0.52553 -0.293096 0.485535 -0.82362 -0.100153 0.171725 -0.980041 -0.101155 0.17468 -0.979415 -0.120249 0.160131 -0.979744 -0.115187 0.145376 -0.982648 -0.125994 0.148073 -0.980918 -0.13989 0.131731 -0.981365 -0.273178 0.104028 -0.956322 -0.140145 0.0952022 -0.985543 -0.485011 0.231057 -0.843432 -0.461314 0.22636 -0.857875 -0.639965 0.290549 -0.711356 -0.588665 0.387804 -0.709282 -0.542936 0.377722 -0.750031 -0.316148 0.567194 -0.760487 -0.329814 0.476316 -0.815074 -0.390575 0.428893 -0.814556 -0.427759 0.498983 -0.753683 -0.424154 0.390751 -0.81695 -0.117053 0.154738 -0.980997 -0.12429 0.159927 -0.979273 -0.136829 0.141689 -0.980409 -0.134985 0.137143 -0.981311 -0.146729 0.135231 -0.97989 -0.444027 0.413968 -0.794651 -0.433707 0.393972 -0.810361 -0.35286 0.470698 -0.808661 -0.348204 0.454974 -0.819605 -0.495296 0.217694 -0.841006 -0.0555179 0.0436375 -0.997504 -0.156971 0.121114 -0.980149 -0.0583398 0.0182486 -0.99813 -0.0307969 0.0242516 -0.999231 -0.290526 0.081315 -0.953406 -0.294673 0.0672485 -0.953229 -0.154634 0.0900331 -0.983861 -0.159198 0.123548 -0.979486 -0.507587 0.326998 -0.797137 -0.608389 0.114142 -0.785388 -0.78641 0.0591976 -0.614862 -0.555812 0.0525056 -0.829648 -0.581762 0.0460103 -0.812057 -0.324033 0.0323434 -0.945493 -0.0446946 4.86714e-05 -0.999001 -0.0343458 0.00837906 -0.999375 -0.308119 0.0272599 -0.950957 -0.299409 0.0855021 -0.950286 -0.543592 0.133756 -0.828624 -0.520502 0.135752 -0.843 -0.717545 0.168935 -0.675715 -0.697772 0.23062 -0.67818 -0.563571 0.256502 -0.785235 -0.519036 0.344559 -0.782228 -0.0784754 0.158268 -0.984273 -0.0822468 0.176041 -0.980941 -0.226626 0.509474 -0.830106 -0.229326 0.526487 -0.81867 -0.0745628 0.54557 -0.834742 -0.0761332 0.549566 -0.831974 -0.0255589 0.165058 -0.985953 -0.0278158 0.171637 -0.984767 -0.787913 -0.000477107 -0.615786 -0.788085 -0.000552833 -0.615567 -0.582494 -0.00126891 -0.812834 -0.5834 -0.00158542 -0.812184 -0.324284 -0.0019719 -0.945958 -0.326068 -0.0025104 -0.945343 -0.044699 -0.00248533 -0.998997 -0.047302 -0.00320279 -0.998875 0.0213685 0.165074 -0.98605 0.0597216 0.546116 -0.835578 0.0207389 0.169286 -0.985349 0.0617928 0.160993 -0.985019 0.0625386 0.173336 -0.982875 0.102507 0.15546 -0.982509 0.107068 0.170786 -0.979474 0.141178 0.144866 -0.979328 0.147594 0.156425 -0.9766 0.0592413 0.5484 -0.834115 0.175945 0.524633 -0.832949 0.175918 0.534834 -0.826441 0.295527 0.481311 -0.82523 0.299584 0.498819 -0.813283 0.404537 0.419142 -0.812816 0.414636 0.440122 -0.796473 -0.788085 -0.000443444 -0.615567 -0.788319 -0.000546551 -0.615266 -0.583399 -0.00124459 -0.812185 -0.584276 -0.0015501 -0.811553 -0.326067 -0.00193046 -0.945345 -0.327804 -0.00245255 -0.944743 -0.0473007 -0.00243506 -0.998878 -0.0498892 -0.00314506 -0.99875 0.21094 0.10097 -0.97227 0.173636 -0.0133453 -0.984719 0.244562 0.0210279 -0.969406 0.202154 0.0925336 -0.974972 0.18063 0.130003 -0.974922 0.175621 0.123209 -0.976717 0.22619 0.0576577 -0.972375 0.23715 0.0651866 -0.969284 0.566168 0.141396 -0.812072 0.578167 0.0723463 -0.812704 0.499688 0.0348754 -0.865503 0.489617 0.352414 -0.797546 0.513096 0.356382 -0.780848 0.557462 0.280145 -0.781508 0.607606 0.272898 -0.745883 0.604919 0.237496 -0.760045 0.637391 0.139401 -0.757826 0.742058 0.19318 -0.641897 0.762971 0.0718643 -0.642426 0.764062 0.0723889 -0.641069 -0.291067 -0.13007 -0.947819 -0.785129 -0.0923678 -0.612406 -0.0547495 -0.0192242 -0.998315 -0.0499072 -0.0179635 -0.998592 -0.310352 -0.0464868 -0.949484 -0.32749 -0.0509869 -0.943478 -0.686089 -0.1097 -0.719199 -0.740175 -0.255217 -0.622098 -0.795697 -0.296144 -0.528361 -0.636841 -0.310574 -0.705675 -0.593652 -0.391201 -0.703234 -0.128712 -0.162476 -0.978281 -0.14901 -0.140775 -0.978764 -0.141005 -0.120311 -0.982671 -0.158459 -0.123171 -0.979653 -0.184114 -0.0741996 -0.9801 -0.0300913 -0.0375132 -0.998843 -0.0506176 -0.0371712 -0.998026 -0.421115 -0.419639 -0.804093 -0.124445 -0.159154 -0.979379 -0.393785 -0.47907 -0.784491 -0.35309 -0.453152 -0.818523 -0.582852 -0.0738925 -0.809212 -0.546601 -0.0777542 -0.833776 -0.516461 -0.207211 -0.830862 -0.485586 -0.202415 -0.850432 -0.425615 -0.316222 -0.847854 -0.597114 -0.394894 -0.698222 -0.447141 -0.391523 -0.804223 0.766072 0 -0.642755 0.766072 0 -0.642755 0.499992 0 -0.86603 0.499992 0 -0.86603 0.173652 0 -0.984807 0.173652 0 -0.984807 -0.0744132 -0.55633 -0.827623 -0.0747478 -0.553026 -0.829804 -0.0260297 -0.195166 -0.980425 -0.0261018 -0.193863 -0.980681 -0.22782 -0.529648 -0.81705 -0.225217 -0.514931 -0.827118 -0.0799686 -0.186688 -0.979159 -0.078664 -0.180829 -0.980364 0.766072 0 -0.642755 0.766072 0 -0.642755 0.499992 0 -0.86603 0.499992 0 -0.86603 0.173652 0 -0.984807 0.173652 0 -0.984807 0.188064 -0.156176 -0.96966 0.0185674 -0.193896 -0.980846 0.018744 -0.194363 -0.980751 0.054117 -0.187692 -0.980736 0.0493601 -0.17998 -0.982431 0.0988697 -0.188433 -0.977097 0.0925042 -0.181051 -0.979114 0.166387 -0.144628 -0.975396 0.191622 -0.10491 -0.975846 0.204635 -0.107099 -0.972962 0.222272 -0.0683075 -0.972589 0.220137 -0.0684175 -0.973067 0.559077 -0.158091 -0.813904 0.745242 -0.160699 -0.64714 0.258844 -0.520507 -0.813678 0.247086 -0.461553 -0.852008 0.155111 -0.579886 -0.799795 0.157201 -0.535361 -0.829866 0.0533473 -0.555085 -0.830081 0.0536538 -0.553779 -0.830933 0.173619 -0.0194594 -0.984621 0.269135 -0.010848 -0.963041 0.499144 -0.0582301 -0.86456 0.578811 -0.052003 -0.813802 0.763722 -0.0782687 -0.640783 0.759142 -0.0793717 -0.646067 0.316769 -0.479741 -0.818234 0.369177 -0.443337 -0.816799 0.12753 -0.157566 -0.979239 0.115379 -0.149325 -0.982033 0.393963 -0.512412 -0.763038 0.404686 -0.42608 -0.809126 0.475852 -0.383384 -0.791569 0.47878 -0.388752 -0.787173 0.548222 -0.283315 -0.786883 0.561009 -0.298027 -0.772301 0.627619 -0.186621 -0.755822 -0.275841 0.387171 0.879779 -0.331317 0.557738 0.761024 -0.139312 0.662815 0.73571 -0.139313 0.662815 0.735709 -0.293414 0.60192 0.742698 0 0.669342 0.742954 0 0.669342 0.742954 0.611881 -0.293593 0.734442 0.611882 -0.293593 0.734441 0.678673 0.000749066 0.73444 0.678666 0.000745944 0.734447 0.611225 0.294942 0.734447 0.611237 0.294955 0.734432 0.422898 0.530811 0.734436 0.422898 0.53081 0.734438 0.150912 0.661678 0.734444 0.150912 0.661676 0.734446 0.650927 -0.160632 0.741951 0.570124 -0.247481 0.783398 0.63258 -0.218904 0.742916 0.650993 -0.160659 0.741887 0.617892 -0.259877 0.742074 0.590378 -0.315578 0.742876 0.590764 -0.316095 0.742349 0.563052 -0.359852 0.743962 0.617479 -0.40677 0.673245 0.556478 -0.396798 0.729989 0.497229 -0.387867 0.776094 0.525192 -0.415031 0.742915 0.520059 -0.421374 0.742955 0.520072 -0.42139 0.742937 0.157776 -0.660957 0.733651 0.157776 -0.660957 0.73365 0.439312 -0.518426 0.733648 0.439318 -0.51843 0.733642 0.626117 -0.264102 0.73364 0.626121 -0.264102 0.733637 0 -0.66934 0.742956 0 -0.66934 0.742956 -0.266266 -0.66923 0.69371 -0.257728 -0.714876 0.650022 -0.283684 -0.660426 0.695242 -0.259238 -0.688886 0.676928 -0.264523 -0.67872 0.685104 -0.246643 -0.662113 0.707654 -0.242085 -0.669301 0.702446 -0.215829 -0.66926 0.710991 -0.213739 -0.620703 0.754349 -0.198409 -0.647344 0.735921 -0.168769 -0.680534 0.713015 -0.155632 -0.657034 0.737622 -0.142855 -0.630197 0.76318 -0.146913 -0.619537 0.771097 -0.11916 -0.661329 0.74057 -0.0772713 -0.686613 0.722905 -0.0769691 -0.684545 0.724896 -0.0205505 -0.648652 0.760808 -0.0223607 -0.636562 0.770901 -0.000803542 -0.66934 0.742956 -0.285984 -0.66883 0.686207 -0.447411 -0.576213 0.683961 -0.360964 -0.715142 0.598563 -0.353131 -0.702502 0.617891 -0.31379 -0.675401 0.66736 -0.660426 -0.175171 0.730173 -0.67074 -0.187735 0.71754 -0.631517 -0.204118 0.748013 -0.640547 -0.211476 0.738226 -0.655537 -0.258773 0.709442 -0.683869 -0.28822 0.670264 -0.588003 -0.434751 0.682088 -0.578322 -0.382886 0.720376 -0.624552 -0.392266 0.675324 -0.59658 -0.331372 0.730948 -0.63298 -0.330548 0.700053 -0.618955 -0.288406 0.73056 -0.674004 -0.287593 0.680448 -0.591521 -0.452734 0.667184 -0.595194 -0.464088 0.656023 -0.54622 -0.44454 0.709949 -0.547761 -0.482976 0.683149 -0.533298 -0.490948 0.688885 -0.526812 -0.531253 0.663505 -0.526731 -0.530044 0.664535 -0.503483 -0.528965 0.683155 -0.493421 -0.559662 0.665818 -0.490412 -0.556794 0.67043 -0.177628 0.394893 0.901392 -0.222305 0.601198 0.767555 -0.286397 0.651273 0.702724 -0.318433 0.602023 0.732235 -0.351454 0.587385 0.729012 -0.398228 0.561204 0.725579 -0.415273 0.563685 0.714008 -0.494842 0.444051 0.746961 -0.645318 0.312553 0.697048 -0.563818 0.389355 0.728363 -0.49924 0.470616 0.727517 -0.548185 0.312083 0.775949 -0.674781 0.21334 0.70651 -0.671491 0.202148 0.712907 -0.644216 0.0543631 0.762909 -0.691918 0.0922983 0.716052 -0.679959 -0.0936494 0.727245 -0.686877 -0.10143 0.719661 -0.68195 -0.018835 0.731156 -0.0605935 -0.709129 0.70247 -0.453528 -0.561376 0.692221 -0.695955 -0.116446 0.708581 -0.132772 -0.592514 0.794544 -0.148911 -0.659773 0.736563 -0.15789 -0.671974 0.723548 -0.66598 -0.135232 0.73361 -0.6783 -0.248207 0.691594 -0.613345 -0.291392 0.734097 -0.62214 -0.367664 0.691206 -0.589655 -0.391264 0.706554 -0.480447 -0.412263 0.774087 -0.512609 -0.521951 0.681762 -0.56851 -0.417561 0.708829 -0.311272 -0.671966 0.671991 -0.382459 -0.594238 0.707535 -0.411908 -0.576087 0.706014 -0.325513 -0.577616 0.7486 -0.237914 -0.683211 0.690377 -0.220609 -0.679453 0.699768 -0.167083 -0.678551 0.715299 -0.165238 -0.678149 0.716108 -0.702235 -0.0481073 0.710318 -0.702353 -0.0482874 0.710189 -0.702242 -0.0499443 0.710184 -0.702363 -0.0501343 0.710051 -0.167108 0.645453 0.745296 -0.147094 0.696437 0.702381 -0.598263 0.279319 0.751041 -0.583761 0.438182 0.683535 -0.583676 0.432229 0.687386 -0.47253 0.486275 0.735018 -0.474135 0.520367 0.710221 -0.406726 0.580023 0.705796 -0.376055 0.618665 0.689809 -0.356141 0.61419 0.704226 -0.249384 0.659906 0.708754 -0.278222 0.679282 0.679095 -0.157839 0.66973 0.725636 -0.127057 0.628152 0.767647 -0.730458 0.111279 0.673831 -0.669497 0.219186 0.709741 -0.628419 0.327421 0.70561 -0.610079 0.146585 0.778664 -0.724318 0.0246248 0.689026 -0.703829 -0.0212207 0.710052 -0.0755557 0.676629 0.732437 -0.0643668 0.699125 0.712096 -0.0617851 -0.699837 0.711625 -0.0612092 -0.700819 0.710708 -0.0725375 -0.698833 0.711597 -0.702119 -0.0689205 0.708717 -0.675734 -0.0872723 0.731961 -0.69151 -0.2085 0.691622 -0.612863 -0.258851 0.746589 -0.635388 -0.335658 0.695425 -0.595673 -0.377208 0.709146 -0.553166 -0.443602 0.705142 -0.553219 -0.443954 0.704878 -0.484245 -0.513735 0.708225 -0.471575 -0.552897 0.686966 -0.453697 -0.555739 0.696645 -0.344254 -0.591985 0.728727 -0.350092 -0.595054 0.723427 -0.242191 -0.677814 0.694198 -0.268401 -0.690171 0.67203 -0.0766999 -0.699703 0.710304 -0.152931 -0.658519 0.736861 -0.146285 -0.648576 0.74696 -0.150373 -0.651907 0.74324 -0.703792 0 0.710406 -0.703792 0 0.710406 -0.14989 0.643456 0.750664 -0.143505 0.697165 0.702401 -0.117858 0.633268 0.764906 -0.143893 0.66801 0.730108 -0.243796 0.681705 0.689813 -0.297176 0.601822 0.74128 -0.359635 0.621692 0.695818 -0.403378 0.579861 0.707847 -0.468172 0.538013 0.700968 -0.459953 0.536552 0.707499 -0.533828 0.464366 0.706676 -0.566473 0.454139 0.687652 -0.570573 0.429843 0.699772 -0.607013 0.319114 0.727806 -0.605866 0.316761 0.729787 -0.68979 0.207206 0.693726 -0.700049 0.230814 0.675764 -0.645465 0.0628796 0.761197 -0.699931 0.104609 0.706508 -0.0616664 0.699838 0.711635 -0.0617104 0.700768 0.710715 -0.0725294 0.69887 0.711562 -0.0747526 -0.685049 0.724651 -0.0639607 -0.703767 0.707545 -0.0624312 -0.698715 0.712671 -0.704958 -0.0241044 0.708839 -0.0873812 -0.698453 0.710301 -0.0882785 -0.697759 0.710873 -0.134844 -0.69043 0.71072 -0.197431 -0.650225 0.733641 -0.164317 -0.62227 0.765363 -0.324971 -0.708313 0.626647 -0.248871 -0.65937 0.709433 -0.399915 -0.592301 0.699462 -0.346063 -0.561038 0.751981 -0.498988 -0.536906 0.680253 -0.487487 -0.537346 0.688198 -0.536965 -0.415686 0.73408 -0.561961 -0.41577 0.715077 -0.621131 -0.338252 0.706953 -0.654886 -0.307506 0.690336 -0.646959 -0.278473 0.709857 -0.686813 -0.16605 0.707612 -0.703635 -0.189884 0.68472 -0.681425 -0.0422014 0.73067 -0.701974 0.0499249 0.710451 -0.701828 0.0500947 0.710583 -0.701962 0.0480879 0.710589 -0.701821 0.0482496 0.710717 -0.543947 0.470288 0.694947 -0.167458 0.677479 0.716226 -0.139946 0.566638 0.811996 -0.159915 0.657421 0.736359 -0.17342 0.670004 0.721818 -0.238396 0.682159 0.69125 -0.290285 0.618003 0.730621 -0.350415 0.631036 0.692101 -0.380519 0.596188 0.706941 -0.397451 0.482523 0.780515 -0.512809 0.531016 0.674573 -0.406755 0.578059 0.707388 -0.673408 0.324923 0.664038 -0.58654 0.3927 0.708349 -0.565272 0.422366 0.708572 -0.560666 0.328688 0.760012 -0.678888 0.247629 0.691224 -0.675572 0.220771 0.703465 -0.679896 0.113139 0.724528 -0.694018 0.12872 0.708358 0.0631118 -0.686213 -0.724658 -0.314077 -0.632489 0.708035 -0.28379 -0.398327 0.872238 -0.36835 -0.591696 0.717087 -0.345786 -0.658491 0.668447 -0.154288 -0.734063 0.661322 -0.154289 -0.73406 0.661325 0 -0.742956 0.66934 0 -0.742956 0.66934 0.167068 -0.732514 0.659933 0.167071 -0.732519 0.659927 0.468175 -0.587641 0.659917 0.468168 -0.587638 0.659924 0.676674 -0.326523 0.659921 0.67665 -0.326523 0.659945 0.751312 -0.000829239 0.659947 0.75133 -0.00082067 0.659927 0.677388 0.325025 0.659927 0.677389 0.325026 0.659926 0.577368 0.467609 0.669319 0.577361 0.467606 0.669328 0.585224 0.457842 0.669249 0.55081 0.435746 0.711852 0.61537 0.439249 0.654507 0.600993 0.436846 0.669308 0.627421 0.398708 0.668861 0.618587 0.394781 0.679337 0.659062 0.350466 0.66544 0.655231 0.35038 0.669258 0.682158 0.295893 0.668661 0.646452 0.271655 0.712954 0.702136 0.242964 0.669308 0.722347 0.178231 0.668168 0.72229 0.178227 0.668231 0.692977 0.292305 0.659046 0.692973 0.292301 0.659051 0.486227 0.573788 0.659053 0.486229 0.573797 0.659043 0.174626 0.731546 0.659049 0.174627 0.73154 0.659055 0 0.742956 0.66934 0 0.742956 0.66934 -0.0373536 0.739226 0.67242 -0.231472 0.724998 0.64869 -0.213992 0.74294 0.63423 -0.228618 0.761494 0.606515 -0.261372 0.721101 0.641637 -0.234219 0.771241 0.591886 -0.236249 0.764189 0.600168 -0.229377 0.742944 0.628825 -0.18892 0.742809 0.642296 -0.189441 0.734828 0.65126 -0.152646 0.747309 0.646706 -0.151216 0.741148 0.65409 -0.138149 0.742957 0.654928 -0.0542147 0.746903 0.66272 -0.0671267 0.769361 0.635277 -0.108963 0.677786 0.72714 -0.112604 0.702727 0.702492 -0.125079 0.742899 0.657614 -0.0201656 0.709433 0.704484 -0.0183519 0.699369 0.714526 -0.00298391 0.742953 0.669337 -0.49232 0.642231 0.587504 -0.461121 0.663929 0.588698 -0.351564 0.766 0.538189 -0.376787 0.838324 0.39401 -0.309978 0.739851 0.597105 -0.739161 0.344805 0.578576 -0.708204 0.339501 0.61902 -0.707073 0.294824 0.642749 -0.717932 0.289361 0.633122 -0.707707 0.248387 0.661403 -0.746515 0.248287 0.617308 -0.721292 0.20199 0.662524 -0.732435 0.197689 0.651505 -0.679851 0.353628 0.642456 -0.685583 0.389499 0.615033 -0.684694 0.386013 0.618214 -0.64817 0.412171 0.640305 -0.690393 0.428393 0.582956 -0.651027 0.440909 0.61787 -0.639367 0.470878 0.607851 -0.640463 0.471116 0.606511 -0.616748 0.496477 0.610846 -0.619429 0.496865 0.607809 -0.59403 0.536792 0.599151 -0.596118 0.548868 0.585993 -0.569146 0.563675 0.598618 -0.549193 0.601607 0.580048 -0.547678 0.558703 0.622816 -0.523485 0.637471 0.565326 -0.509156 0.620346 0.5966 -0.492602 0.642099 0.587411 -0.625162 -0.362232 0.691347 -0.743654 -0.237477 0.624967 -0.731609 -0.201086 0.651393 -0.754575 -0.0918876 0.649748 -0.777175 -0.06669 0.625741 -0.727401 0.0722499 0.682399 -0.75421 0.104841 0.648209 -0.543762 -0.55387 0.630516 -0.610037 -0.452203 0.650667 -0.685648 -0.35816 0.633726 -0.535087 -0.487711 0.689797 -0.448959 -0.638685 0.624914 -0.457066 -0.639069 0.618613 -0.361352 -0.646005 0.672385 -0.162144 -0.766016 0.622036 -0.243573 -0.712822 0.65769 -0.271546 -0.714067 0.645269 -0.336602 -0.635397 0.69496 -0.341459 -0.639468 0.68883 -0.362779 -0.646061 0.671563 0.707176 0 0.707037 0.707101 0 0.707113 0.707101 0 0.707113 0.707176 0 0.707037 -0.707089 0 0.707124 -0.707089 0 0.707124 -0.700198 -0.139274 0.700233 -0.700222 -0.139285 0.700206 -0.593619 -0.396644 0.700207 -0.593617 -0.396642 0.70021 -0.396641 -0.593617 0.70021 -0.396644 -0.593625 0.700202 -0.139284 -0.700224 0.700204 -0.139284 -0.700223 0.700206 -0.186158 0.694751 0.694742 -0.186158 0.694752 0.694741 -0.508594 0.508598 0.694738 -0.508584 0.508592 0.69475 -0.694743 0.186152 0.694752 -0.69473 0.186152 0.694764 0 -0.707116 0.707098 0 -0.707116 0.707098 0 0.707111 0.707102 0 0.707111 0.707102 0.139282 -0.700223 0.700206 0.139283 -0.700225 0.700204 0.396649 -0.593622 0.700202 0.396643 -0.593616 0.70021 0.593617 -0.396643 0.70021 0.593619 -0.396644 0.700207 0.700222 -0.139286 0.700206 0.700231 -0.139286 0.700197 0.139283 0.700219 0.70021 0.139282 0.700225 0.700204 0.313086 0.634874 0.706337 0.447435 0.669638 0.592779 0.432309 0.563393 0.704058 0.593617 0.396642 0.70021 0.700232 0.139285 0.700197 0.700224 0.13928 0.700206 0.634863 0.313102 0.70634 0.680238 0.521955 0.514626 0.707124 0 0.707089 0.707124 0 0.707089 -0.70708 0 0.707133 -0.70708 0 0.707133 -0.70019 -0.139268 0.700242 -0.700215 -0.13928 0.700214 -0.593614 -0.396642 0.700213 -0.59361 -0.396637 0.700219 -0.396638 -0.593609 0.700219 -0.39664 -0.593613 0.700214 -0.13928 -0.700212 0.700217 -0.13928 -0.70021 0.700219 -0.139279 0.70021 0.700219 -0.139282 0.700216 0.700213 -0.396643 0.593616 0.700211 -0.396637 0.59361 0.700219 -0.593609 0.396638 0.700219 -0.593612 0.396639 0.700216 -0.700216 0.139274 0.700214 -0.700189 0.139275 0.700241 0 -0.707102 0.707111 0 -0.707102 0.707111 0 0.707102 0.707111 0 0.707102 0.707111 0.139281 -0.70021 0.700219 0.139282 -0.700211 0.700218 0.396641 -0.593613 0.700214 0.396637 -0.59361 0.700219 0.593609 -0.396638 0.700219 0.593614 -0.39664 0.700213 0.700215 -0.139282 0.700214 0.700223 -0.139282 0.700206 0.700223 0.139284 0.700206 0.700215 0.13928 0.700215 0.593612 0.39664 0.700216 0.59361 0.396637 0.700219 0.396638 0.593609 0.700219 0.396641 0.593617 0.700211 0.139282 0.700216 0.700213 0.139282 0.70021 0.700219 0.707116 0 0.707098 0.707116 0 0.707098 -0.0803214 0.704827 0.704818 -0.0803235 0.704831 0.704813 -0.32487 0.639814 0.696489 -0.32487 0.639815 0.696489 -0.586015 0.414122 0.696484 -0.585999 0.414118 0.696499 -0.711555 0.0926031 0.696502 -0.71155 0.092604 0.696506 -0.672472 -0.250324 0.696505 -0.672493 -0.250341 0.696479 -0.477815 -0.535355 0.696483 -0.477819 -0.535366 0.696472 -0.172579 -0.696508 0.696486 -0.17258 -0.696501 0.696493 0 0.707111 0.707102 0 0.707111 0.707102 0 -0.707111 0.707102 0 -0.707111 0.707102 0.0803219 0.704831 0.704813 0.080323 0.704826 0.704818 0.172578 -0.696502 0.696493 0.172577 -0.6965 0.696495 0.477806 -0.535346 0.696496 0.477796 -0.53534 0.696507 0.67246 -0.250332 0.696514 0.672504 -0.250333 0.696471 0.711585 0.0926071 0.69647 0.711589 0.0926091 0.696466 0.586026 0.41413 0.69647 0.586018 0.414119 0.696483 0.324865 0.639818 0.696488 0.324865 0.639816 0.69649 -0.70712 0 0.707094 -0.70712 0 0.707094 -0.69476 -0.186152 0.694734 -0.69474 -0.186152 0.694755 -0.508585 -0.508587 0.694752 -0.508595 -0.508593 0.69474 -0.186157 -0.69475 0.694743 -0.186156 -0.694749 0.694744 -0.139282 0.700216 0.700213 -0.139282 0.700217 0.700211 -0.396641 0.593619 0.700209 -0.39664 0.593614 0.700213 -0.593615 0.396638 0.700214 -0.593617 0.396641 0.700211 -0.70022 0.139278 0.70021 -0.700227 0.139282 0.700201 0 -0.707109 0.707105 0 -0.707109 0.707105 0 0.707108 0.707105 0 0.707108 0.707105 0.186159 -0.694748 0.694744 0.186159 -0.694749 0.694743 0.508593 -0.508595 0.694741 0.508587 -0.508585 0.694752 0.694738 -0.186155 0.694755 0.694758 -0.186167 0.694732 0.694759 0.186161 0.694733 0.694735 0.186161 0.694757 0.508584 0.508586 0.694753 0.508595 0.508593 0.694741 0.186159 0.694749 0.694744 0.186159 0.694748 0.694745 0.70712 0 0.707094 0.70712 0 0.707094 -0.70712 0 0.707094 -0.70712 0 0.707094 -0.694758 -0.186166 0.694732 -0.694739 -0.186153 0.694755 -0.508586 -0.508586 0.694753 -0.508591 -0.508596 0.694741 -0.186159 -0.694749 0.694744 -0.186159 -0.694748 0.694745 -0.186158 0.694746 0.694746 -0.186159 0.694747 0.694746 -0.508593 0.508593 0.694742 -0.508583 0.508588 0.694753 -0.694736 0.18616 0.694757 -0.694759 0.186159 0.694733 0 -0.707108 0.707105 0 -0.707108 0.707105 0 0.707107 0.707107 0 0.707107 0.707107 0.139283 -0.700216 0.700213 0.13928 -0.700211 0.700218 0.396631 -0.593602 0.700229 0.396644 -0.593611 0.700214 0.59361 -0.396645 0.700214 0.593614 -0.396646 0.70021 0.70022 -0.139279 0.70021 0.700228 -0.139277 0.700202 0.69476 0.186154 0.694734 0.694772 0.186162 0.69472 0.508603 0.508603 0.694727 0.508596 0.50859 0.694741 0.186156 0.694748 0.694745 0.186156 0.694747 0.694747 0.70712 0 0.707094 0.70712 0 0.707094 0 0.707109 0.707105 0 0.707109 0.707105 -0.139282 0.700217 0.700212 -0.139282 0.700218 0.700211 -0.396641 0.59362 0.700208 -0.39664 0.593614 0.700214 -0.593615 0.396638 0.700214 -0.593617 0.396641 0.70021 -0.70022 0.139278 0.700209 -0.700227 0.139282 0.700201 0.700228 0.139279 0.700202 0.700219 0.13928 0.70021 0.593613 0.396649 0.700209 0.593639 0.396655 0.700184 0.396654 0.593627 0.700195 0.396643 0.593619 0.700208 0.139282 0.700218 0.700211 0.139282 0.700217 0.700212 -0.70712 0 0.707094 -0.70712 0 0.707094 0.70712 0 0.707094 0.70712 0 0.707094 -0.69476 -0.186152 0.694734 -0.694739 -0.186152 0.694756 -0.508584 -0.508586 0.694753 -0.508595 -0.508593 0.694741 -0.186157 -0.69475 0.694744 -0.186156 -0.694748 0.694745 0.186159 -0.694748 0.694745 0.186159 -0.694749 0.694744 0.432309 -0.563393 0.704057 0.398527 -0.398524 0.826048 0.563382 -0.432304 0.70407 0.694738 -0.186155 0.694756 0.694758 -0.186167 0.694732 0 -0.707108 0.707105 0 -0.707108 0.707105 0.139282 -0.700214 0.700214 0.13928 -0.700211 0.700218 0.396631 -0.593602 0.700228 0.396643 -0.59361 0.700215 0.593609 -0.396645 0.700215 0.593615 -0.396646 0.70021 0.70022 -0.139279 0.70021 0.700228 -0.139277 0.700202 0.70712 0 0.707094 0.70712 0 0.707094 0 -0.707107 0.707107 0 -0.707107 0.707107 0.69476 0.186154 0.694734 0.694772 0.186162 0.69472 0.508604 0.508603 0.694727 0.508598 0.508591 0.69474 0.186156 0.69475 0.694743 0.186156 0.694748 0.694745 -0.700226 -0.139296 0.7002 -0.700187 -0.139269 0.700245 -0.593596 -0.39662 0.700241 -0.593611 -0.396643 0.700215 -0.396639 -0.593614 0.700214 -0.39664 -0.59362 0.700208 -0.139283 -0.700218 0.700211 -0.139284 -0.700214 0.700214 0 0.707108 0.707105 0 0.707108 0.707105 -0.70712 0 0.707094 -0.70712 0 0.707094 -0.186159 0.694748 0.694745 -0.18616 0.694749 0.694743 -0.508594 0.508594 0.69474 -0.508584 0.508588 0.694752 -0.694736 0.18616 0.694757 -0.694759 0.186159 0.694733 0.707085 0 0.707129 0.707085 0 0.707129 0.700194 0.139274 0.700237 0.700216 0.13929 0.700211 0.59362 0.396636 0.700211 0.593619 0.396634 0.700213 0.396639 0.593615 0.700213 0.39664 0.59362 0.700208 0.13928 0.700219 0.700211 0.139281 0.700215 0.700215 0.186156 -0.694748 0.694745 0.186157 -0.69475 0.694743 0.508594 -0.508594 0.69474 0.508606 -0.5086 0.694728 0.694774 -0.186158 0.694719 0.694725 -0.186161 0.694768 0 0.707107 0.707107 0 0.707107 0.707107 0 -0.707108 0.707105 0 -0.707108 0.707105 -0.694759 0.186159 0.694733 -0.186158 0.694746 0.694746 -0.186159 0.694748 0.694744 -0.432305 0.563396 0.704058 -0.611736 0.611741 0.501549 -0.563387 0.432297 0.70407 -0.694736 0.18616 0.694757 -0.139284 -0.700216 0.700213 -0.139283 -0.700217 0.700212 -0.313083 -0.634868 0.706344 -0.43652 -0.653305 0.618581 -0.432303 -0.563393 0.704061 -0.593611 -0.396644 0.700214 -0.700226 -0.139296 0.7002 -0.700186 -0.139269 0.700245 -0.634844 -0.313057 0.706377 -0.657034 -0.504153 0.560479 -0.70712 0 0.707094 -0.70712 0 0.707094 0 0.707108 0.707105 0 0.707108 0.707105 -0.186158 0.694748 0.694745 -0.276682 0.360579 0.890747 -0.508592 0.508595 0.694741 -0.186158 0.694749 0.694744 -0.563378 0.43231 0.704069 -0.694738 0.186154 0.694756 -0.694726 0.186147 0.694769 0.700228 0.139281 0.700202 0.700218 0.139282 0.70021 0.593616 0.396642 0.700211 0.593613 0.396641 0.700214 0.39664 0.593615 0.700213 0.396644 0.593618 0.700208 0.139283 0.700217 0.700211 0.139282 0.700216 0.700213 -0.707085 0 0.707129 -0.707085 0 0.707129 0.70712 0 0.707094 0.70712 0 0.707094 -0.700192 -0.139286 0.700236 -0.700218 -0.139282 0.70021 -0.593616 -0.396642 0.700211 -0.593612 -0.396641 0.700215 -0.396644 -0.59361 0.700215 -0.396633 -0.593602 0.700228 -0.139279 -0.700212 0.700218 -0.139281 -0.700215 0.700215 0.186158 -0.694746 0.694746 0.186158 -0.69475 0.694743 0.432308 -0.563395 0.704057 0.394343 -0.394339 0.830055 0.563386 -0.432299 0.704069 0.694738 -0.186154 0.694756 0.694758 -0.186166 0.694732 0 -0.707107 0.707107 0 -0.707107 0.707107 0.707085 0 0.707129 0.707085 0 0.707129 0.694727 0.186145 0.69477 0.694768 0.186172 0.694721 0.508604 0.508603 0.694727 0.508597 0.508591 0.69474 0.186156 0.69475 0.694743 0.186156 0.694748 0.694745 0.186155 -0.694747 0.694747 0.186156 -0.694749 0.694744 0.508594 -0.508593 0.694741 0.508606 -0.5086 0.694727 0.694774 -0.186158 0.694719 0.694725 -0.186161 0.694768 0 0.707108 0.707105 0 0.707108 0.707105 0 -0.707107 0.707107 0 -0.707107 0.707107 -0.694759 0.186159 0.694733 -0.186159 0.694748 0.694745 -0.186159 0.694749 0.694744 -0.432305 0.563396 0.704058 -0.611736 0.611742 0.501549 -0.563387 0.432297 0.70407 -0.694736 0.18616 0.694757 -0.694758 -0.186166 0.694732 -0.694739 -0.186153 0.694756 -0.508586 -0.508585 0.694753 -0.508591 -0.508595 0.694742 -0.186159 -0.694748 0.694744 -0.186159 -0.694746 0.694746 -0.70712 0 0.707094 -0.70712 0 0.707094 0 0.707107 0.707107 0 0.707107 0.707107 -0.186158 0.694746 0.694746 -0.276682 0.360579 0.890747 -0.508592 0.508596 0.694741 -0.186158 0.69475 0.694743 -0.563379 0.43231 0.704069 -0.694738 0.186154 0.694756 -0.694726 0.186147 0.694769 0.694759 0.18616 0.694733 0.360575 0.276677 0.89075 0.508588 0.508582 0.694753 0.694736 0.18616 0.694757 0.432308 0.563395 0.704057 0.186158 0.69475 0.694743 0.186157 0.694747 0.694747 -0.707085 0 0.707129 -0.707085 0 0.707129 0.70712 0 0.707094 0.70712 0 0.707094 -0.694726 -0.186151 0.694769 -0.36058 -0.276692 0.890743 -0.508584 -0.508587 0.694753 -0.694739 -0.186151 0.694755 -0.432308 -0.563395 0.704057 -0.186158 -0.69475 0.694743 -0.186157 -0.694748 0.694745 0.186158 -0.694748 0.694745 0.276675 -0.36057 0.890753 0.508597 -0.508591 0.69474 0.186158 -0.69475 0.694743 0.563386 -0.432299 0.70407 0.694738 -0.186154 0.694756 0.694758 -0.186166 0.694732 0 -0.707108 0.707105 0 -0.707108 0.707105 -0.552625 0.73157 -0.399263 0.468574 0.438361 -0.766993 -0.608369 0.754649 -0.245747 -0.959428 0.2766 0.0546844 -0.856215 0.498804 -0.134501 -0.793758 0.606042 -0.0515925 -0.775507 0.629366 0.0498782 -0.715034 0.642837 -0.274749 -0.59497 0.76392 -0.249874 -0.601073 0.758765 -0.250972 -0.458445 0.583569 -0.67028 -0.73747 0.514879 -0.437079 -0.574508 0.602433 -0.55409 -0.408038 0.635216 -0.655748 -0.350358 0.653169 -0.671282 -0.223372 0.509288 -0.831102 -0.231545 0.622311 -0.747741 -0.0742633 0.678885 -0.73048 -0.276047 0.493129 -0.824998 0.0713317 0.635151 -0.769087 0.63005 0.306581 -0.713474 0.531282 0.399281 -0.747204 0.521653 0.478748 -0.706172 0.335492 0.488101 -0.805731 0.142747 0.562398 -0.814452 -0.508902 0.718637 -0.473899 -0.592326 0.66419 -0.456072 -0.842114 0.458924 -0.283254 -0.763073 0.546024 -0.345799 -0.875887 0.450663 -0.172409 -0.947991 0.313152 -0.0569915 0.289885 0.76014 -0.58151 -0.0521092 0.725676 -0.68606 -0.906715 0.396107 0.144803 -0.913691 0.406148 0.0145695 -0.854668 0.491658 -0.16678 -0.860175 0.490574 -0.139415 -0.722098 0.588395 -0.363822 -0.710976 0.601269 -0.364676 -0.817803 0.529724 -0.224924 -0.449774 0.71284 -0.538109 -0.41616 0.737012 -0.532564 -0.552431 0.674792 -0.489363 0.0518143 0.52829 -0.847482 0.346553 0.668384 -0.658152 0.486049 0.549625 -0.679462 -0.639655 0.766615 0.056061 -0.366017 0.757781 -0.540185 -0.579782 0.806725 -0.114225 -0.34752 0.903362 -0.251332 -0.399609 0.893736 -0.203834 -0.21341 0.951879 -0.21996 -0.196341 0.953894 -0.227018 -0.0701322 0.979052 -0.191152 0.0285403 0.980042 -0.19673 0.185638 0.881937 -0.433273 0.170429 0.838343 -0.517817 -0.108189 0.783329 -0.61212 -0.0703465 0.815262 -0.574803 -0.330514 0.739583 -0.586325 -0.269265 0.540741 -0.796929 0.106919 0.991065 -0.0797393 0.478314 0.832359 -0.27999 0.528149 0.803032 -0.27604 0.295848 0.939273 -0.173896 0.327788 0.928713 -0.173341 0.0990048 0.993288 -0.0598111 0.610618 0.62832 -0.482037 0.691006 0.627691 -0.358491 0.631592 0.6817 -0.369293 0.665871 0.575904 -0.47429 0.499427 0.775219 -0.386793 0.481387 0.804187 -0.348639 0.311427 0.918656 -0.243071 0.299001 0.929159 -0.217401 0.0972088 0.992159 -0.0785536 0.109418 0.992183 -0.0600087 0.118286 0.986725 -0.111273 0.0908457 0.990919 -0.0991338 0.333021 0.89426 -0.298991 0.282204 0.918174 -0.278061 0.465044 0.774765 -0.428339 0.464843 0.774942 -0.428237 0.599782 0.553663 -0.577684 0.582029 0.575429 -0.574563 0.17986 0.974825 0.131784 0.790894 0.611953 -0.000846626 0.321723 0.939846 -0.114816 0.520147 0.853408 -0.0337876 0.552391 0.827424 -0.101163 0.71703 0.678629 -0.159155 0.717243 0.67782 -0.161626 0.893786 0.40729 -0.187781 0.849631 0.318046 -0.420682 0.892983 0.447951 -0.043828 0.849649 0.318262 -0.420483 0.824708 0.366992 -0.430319 0.828755 0.385986 -0.405192 0.803345 0.435258 -0.406432 0.815654 0.457563 -0.354039 0.795767 0.497114 -0.345879 0.801165 0.513467 -0.307386 0.785239 0.544297 -0.295197 0.794663 0.551153 -0.254442 0.88805 0.435455 -0.147468 0.887916 0.435711 -0.147519 0.886941 0.439845 -0.14097 0.879162 0.456236 -0.13756 0.878703 0.461761 -0.121069 0.872116 0.474774 -0.118336 0.871882 0.475844 -0.115731 0.868554 0.486547 -0.0942646 0.868876 0.486647 -0.0907149 0.400605 -0.879319 -0.257516 0.243383 -0.967071 -0.0744171 0.125802 -0.989703 -0.0682775 0.948196 0.284441 -0.141483 0.963455 0.267011 0.021431 0.0417751 -0.998385 -0.0384879 0.189631 -0.981765 -0.0132952 0.201585 -0.977821 -0.0568321 0.293508 -0.950318 -0.10368 0.444382 -0.765905 -0.464666 0.824318 -0.560398 -0.0803347 0.666208 -0.738574 -0.103321 0.685349 -0.726382 -0.0516406 0.514153 -0.854014 -0.0794206 0.367688 -0.924314 -0.102219 0.963726 0.215714 0.157162 0.94437 -0.143768 -0.295798 0.995842 -0.0692429 -0.0591965 0.912689 0.180315 -0.366723 0.928648 0.144195 -0.341791 0.93482 0.070915 -0.34797 0.947051 -0.0431164 -0.318176 0.928188 -0.111306 -0.355076 0.879092 -0.325832 -0.347894 0.804619 -0.494484 -0.328746 0.865954 -0.403145 -0.295971 0.894096 -0.420873 -0.15316 0.914335 -0.394053 -0.0933515 0.38819 -0.895109 0.21929 0.341977 -0.900484 -0.268664 0.664148 -0.712889 -0.225158 0.669872 -0.698833 -0.250808 0.746031 -0.588483 -0.31165 0.781056 0.183272 -0.596962 0.624453 0.00325295 -0.781056 0.668 -0.0165902 -0.743976 0.606386 -0.220447 -0.764002 0.571849 -0.462088 -0.677837 0.488998 -0.621442 -0.612119 0.435052 -0.71959 -0.541221 0.38239 -0.810651 -0.443422 0.394543 -0.801073 -0.450131 0.0520732 -0.996451 -0.0661277 0.159062 -0.971648 -0.174928 0.128162 -0.98005 -0.151911 0.223422 -0.933111 -0.281755 0.302199 -0.873182 -0.3824 0.10186 -0.983698 -0.148199 0.551424 -0.72322 -0.415795 0.558311 -0.70633 -0.435187 0.405338 -0.863459 -0.300234 0.371973 -0.901003 -0.223224 0.157372 -0.97377 -0.164337 0.133042 -0.980286 -0.146081 0.13353 -0.979985 -0.147649 0.33046 -0.86729 -0.372295 0.369148 -0.810689 -0.454438 0.455439 -0.730888 -0.508308 0.786165 -0.0152757 -0.617828 0.749 0.0719624 -0.658651 0.790405 -0.113564 -0.601966 0.688747 -0.500376 -0.524644 0.717976 -0.0155281 -0.695894 0.720855 -0.0205334 -0.692782 0.687878 -0.332166 -0.64536 0.74972 -0.331821 -0.572551 0.74974 -0.331063 -0.572963 0.64936 -0.0448153 -0.75916 0.660024 -0.0705294 -0.747927 0.625549 -0.348885 -0.697831 0.678492 -0.349004 -0.646408 0.613035 -0.541521 -0.575276 0.661256 -0.541361 -0.519296 0.63877 -0.593899 -0.489139 0.572439 -0.474657 -0.668591 0.566134 -0.474695 -0.673912 0.55258 -0.553271 -0.623335 0.603112 -0.553518 -0.574346 0.497763 -0.730924 -0.466886 0.499816 -0.723651 -0.475935 0.362876 -0.867362 -0.340593 0.364951 -0.863876 -0.347174 0.150748 -0.978651 -0.139706 0.148486 -0.977066 -0.152626 0.0436342 -0.998411 -0.0356461 0.371973 0.901003 -0.223224 0.157475 0.973748 -0.164366 0.643214 0.0758935 -0.761916 0.640919 -0.0875187 -0.762603 0.65198 0.0584192 -0.755982 0.659879 0.0755084 -0.747568 0.625549 0.348885 -0.697831 0.778505 -0.183215 -0.600302 0.784621 0.0112182 -0.619875 0.101859 0.983698 -0.148199 0.139158 0.978572 -0.151765 0.0446239 0.998421 -0.0341328 0.124186 0.980053 -0.155161 0.1172 0.985184 -0.125207 0.0840719 0.990548 -0.108384 0.395907 0.794932 -0.459717 0.27958 0.892668 -0.353524 0.201065 0.946293 -0.253183 0.641753 0.382443 -0.664748 0.592736 0.456942 -0.663226 0.519744 0.559555 -0.645573 0.467491 0.663905 -0.58368 0.661256 0.541361 -0.519296 0.688747 0.500376 -0.524644 0.74974 0.331063 -0.572963 0.74972 0.331821 -0.572551 0.790405 0.113564 -0.601966 0.749 -0.0719623 -0.658651 0.55258 0.553271 -0.623335 0.566134 0.474695 -0.673912 0.557341 0.474695 -0.681201 0.609586 0.239919 -0.755542 0.145868 0.979487 -0.139021 0.150169 0.978819 -0.139146 0.364951 0.863876 -0.347174 0.405338 0.863459 -0.300234 0.558311 0.70633 -0.435187 0.131904 0.980037 -0.148758 0.136104 0.979184 -0.150582 0.33046 0.86729 -0.372295 0.362877 0.867362 -0.340593 0.499816 0.723651 -0.475934 0.551423 0.72322 -0.415795 0.63877 0.593899 -0.489139 0.712533 0.0276026 -0.701095 0.720522 0.00128041 -0.693431 0.687878 0.332166 -0.64536 0.678492 0.349004 -0.646409 0.613035 0.541521 -0.575276 0.603112 0.553518 -0.574346 0.497763 0.730923 -0.466886 0.455439 0.730888 -0.508309 0.369148 0.810689 -0.454438 0.368053 0.810681 -0.455338 0.483673 0.725013 -0.490323 0.201587 0.977821 -0.0568318 0.948374 -0.284355 -0.140457 0.97514 -0.218269 0.0382167 0.951559 -0.241109 0.19079 0.980169 0.0567283 -0.189871 0.894096 0.420873 -0.15316 0.914335 0.394052 -0.0933515 0.986304 0.150152 -0.068256 0.367688 0.924314 -0.10222 0.514178 0.853999 -0.0794171 0.685349 0.726382 -0.0516406 0.666208 0.738574 -0.103321 0.824318 0.560399 -0.0803348 0.400605 0.879319 -0.257516 0.293507 0.950318 -0.103678 0.243383 0.967071 -0.074416 0.0417735 0.998385 -0.0384904 0.189628 0.981766 -0.0132979 0.125802 0.989703 -0.0682775 0.341977 0.900484 -0.268664 0.38819 0.895158 0.219092 0.444382 0.765905 -0.464666 0.684662 0.694678 -0.220594 0.660582 0.710078 -0.243764 0.746031 0.588483 -0.31165 0.804619 0.494484 -0.328746 0.865954 0.403145 -0.295971 0.879092 0.325832 -0.347894 0.928188 0.111306 -0.355076 0.947051 0.0431165 -0.318176 0.93482 -0.0709148 -0.34797 0.928518 -0.14528 -0.341685 0.913074 -0.180279 -0.365781 0.869641 -0.485222 -0.0910134 0.893825 -0.407608 -0.186902 0.86276 -0.496021 -0.0980175 0.874949 -0.472152 -0.107413 0.869657 -0.480251 -0.114261 0.881028 -0.455763 -0.126768 0.876292 -0.461518 -0.138251 0.888822 -0.437092 -0.137645 0.883554 -0.442082 -0.154582 0.888327 -0.434828 -0.147645 0.892538 -0.448807 -0.0441393 0.80371 -0.532177 -0.266154 0.775473 -0.562345 -0.287072 0.812254 -0.490756 -0.315282 0.784554 -0.518318 -0.340326 0.825929 -0.436048 -0.357356 0.793021 -0.454493 -0.405652 0.835113 -0.373536 -0.403802 0.818514 -0.379068 -0.431674 0.849936 -0.318585 -0.419658 0.849779 -0.318594 -0.419968 0.790894 -0.611953 -0.000176472 0.717426 -0.677763 -0.161053 0.717267 -0.678359 -0.159242 0.518344 -0.850453 -0.0897158 0.179861 -0.974824 0.131787 0.321725 -0.939846 -0.114813 0.58326 -0.812271 -0.00490185 0.0998878 -0.992196 -0.0746247 0.464943 -0.774769 -0.428441 0.464939 -0.774776 -0.428433 0.32129 -0.894597 -0.310595 0.292623 -0.918504 -0.265937 0.112343 -0.986753 -0.11704 0.647057 -0.576372 -0.499111 0.589697 -0.575561 -0.566556 0.594689 -0.553764 -0.58283 0.629246 -0.628874 -0.456692 0.467291 -0.803155 -0.36957 0.513783 -0.774472 -0.369079 0.290575 -0.928718 -0.230323 0.320302 -0.91836 -0.232426 0.103987 -0.991079 -0.0833644 0.0972369 -0.991046 -0.0915069 0.100912 -0.99335 -0.0554361 0.10698 -0.992207 -0.0638798 0.301752 -0.939741 -0.160725 0.320484 -0.928976 -0.185185 0.488126 -0.833414 -0.259141 0.516716 -0.80362 -0.295295 0.644765 -0.683166 -0.342874 0.676724 -0.628382 -0.383641 0.185638 -0.881937 -0.433273 -0.906715 -0.396107 0.144803 -0.860175 -0.490574 -0.139415 0.486048 -0.549625 -0.679463 0.273176 -0.718758 -0.639345 -0.269265 -0.540741 -0.796929 0.0754911 -0.801692 -0.592951 -0.0212784 -0.554476 -0.831928 0.356584 -0.649726 -0.671345 -0.817803 -0.529725 -0.224924 -0.710976 -0.601269 -0.364676 -0.722098 -0.588395 -0.363822 -0.913691 -0.406148 0.0145695 -0.854668 -0.491658 -0.16678 -0.639655 -0.766615 0.056061 -0.586422 -0.800494 -0.123767 -0.425277 -0.88047 -0.209552 -0.403585 -0.887707 -0.221578 -0.351121 -0.912722 -0.208933 -0.197385 -0.955106 -0.220932 -0.212826 -0.949276 -0.231473 0.00941328 -0.985913 -0.166995 -0.0684809 -0.955999 -0.285265 0.289885 -0.76014 -0.58151 0.170429 -0.838343 -0.517817 -0.0663063 -0.796276 -0.601289 -0.117549 -0.806085 -0.580008 -0.330514 -0.739583 -0.586325 -0.449774 -0.71284 -0.538109 -0.41616 -0.737012 -0.532564 -0.552431 -0.674792 -0.489363 -0.959428 -0.2766 0.0546844 0.564767 -0.350325 -0.747202 0.551994 -0.396384 -0.733609 0.476025 -0.479799 -0.737016 0.228788 -0.453409 -0.861438 -0.259855 -0.596589 -0.759314 -0.030874 -0.597348 -0.801387 0.0397528 -0.625237 -0.779422 0.162361 -0.535321 -0.828897 0.403421 -0.494834 -0.769669 -0.203625 -0.560975 -0.802399 -0.210293 -0.624011 -0.752587 -0.280065 -0.617263 -0.735221 -0.454304 -0.604015 -0.654808 -0.346063 -0.656297 -0.670459 -0.589033 -0.534901 -0.605739 -0.728988 -0.54707 -0.411449 -0.455752 -0.643391 -0.615092 -0.407833 -0.655712 -0.635385 -0.561133 -0.728283 -0.393361 -0.722724 -0.629499 -0.285311 -0.60035 -0.759168 -0.251483 -0.622921 -0.772724 -0.121933 -0.807702 -0.58562 -0.0683118 -0.8777 -0.448005 -0.170101 -0.930747 -0.365247 -0.0174564 -0.549616 -0.736081 -0.395105 -0.592262 -0.664226 -0.456103 -0.765537 -0.539958 -0.349856 -0.830141 -0.497063 -0.252576 -0.875887 -0.450663 -0.172409 -0.127342 0.104424 -0.986347 -0.129339 0.0499121 -0.990344 -0.174106 0.0377348 -0.984004 -0.150175 0.03475 -0.988048 -0.153172 0.015989 -0.98807 -0.152597 0.0159889 -0.988159 -0.133941 0.0961508 -0.986314 -0.105201 0.0706519 -0.991938 -0.167789 0.0922685 -0.981495 -0.143499 0.0725233 -0.98699 -0.151241 0.0558659 -0.986917 -0.500834 0.414825 -0.759662 -0.725475 0.630292 -0.276438 -0.878673 0.00299663 -0.477414 -0.692822 0.00238588 -0.721105 -0.146895 0.000729027 -0.989152 -0.145937 0.000771805 -0.989294 -0.435225 0.00153826 -0.90032 -0.820791 0.44917 -0.352915 -0.760168 0.545435 -0.353053 -0.764747 0.54695 -0.3406 -0.712705 0.6131 -0.340823 -0.64439 0.565279 -0.514996 -0.447027 0.00223111 -0.894518 -0.444707 0.0464402 -0.894471 -0.456262 0.0462257 -0.888644 -0.447093 0.103247 -0.888509 -0.45818 0.104385 -0.882709 -0.438627 0.168792 -0.882675 -0.447369 0.170927 -0.877864 -0.41953 0.230801 -0.87791 -0.425689 0.23321 -0.874301 -0.394236 0.282887 -0.874387 -0.39834 0.285087 -0.871809 -0.36266 0.329646 -0.871671 -0.126764 0.10341 -0.986528 -0.106749 0.0890257 -0.990292 -0.0355144 0.0316487 -0.998868 -0.708941 0.00352498 -0.705259 -0.705205 0.0736552 -0.705168 -0.721028 0.0727891 -0.689072 -0.706344 0.163122 -0.688817 -0.721424 0.164078 -0.672775 -0.690528 0.265742 -0.67272 -0.702466 0.268135 -0.659276 -0.65874 0.362357 -0.659362 -0.666964 0.365164 -0.649473 -0.617688 0.44321 -0.649636 -0.623275 0.445886 -0.642428 -0.569545 0.512914 -0.642291 -0.282882 0.228221 -0.931608 -0.893223 0.00442478 -0.449592 -0.888447 0.0928082 -0.449499 -0.902304 0.0908681 -0.421416 -0.883715 0.204107 -0.421176 -0.896592 0.203685 -0.393238 -0.868929 0.29975 -0.393843 -0.799932 0.306237 -0.51607 -0.854592 0.363946 -0.370427 -0.81408 0.447745 -0.369862 -0.106753 -0.0885605 -0.990334 -0.0355152 -0.0308741 -0.998892 -0.14928 -0.0599393 -0.986977 -0.141527 -0.0766928 -0.986959 -0.14734 -0.0807133 -0.985787 -0.129551 -0.0920551 -0.987291 -0.134007 -0.0959983 -0.98632 -0.127528 -0.10413 -0.986354 -0.234576 -0.206394 -0.949935 -0.152107 -0.0215639 -0.988129 -0.149746 -0.0366367 -0.988046 -0.125539 -0.0286973 -0.991674 -0.171845 -0.0655059 -0.982944 -0.174858 -0.0151042 -0.984478 -0.149105 -0.0151161 -0.988706 -0.149758 -0.00182466 -0.988721 -0.165888 -0.000678811 -0.986144 -0.145937 0.00149831 -0.989293 -0.878677 -0.000695853 -0.477417 -0.864887 -0.00232624 -0.501962 -0.920727 -0.0891273 -0.379893 -0.892031 -0.0812009 -0.444619 -0.894922 -0.199906 -0.398939 -0.861453 -0.18542 -0.472777 -0.889262 -0.294563 -0.349922 -0.799261 -0.303274 -0.518851 -0.838679 -0.344049 -0.422193 -0.850275 -0.462554 -0.251148 -0.780998 -0.403514 -0.476675 -0.793658 -0.565944 -0.223192 -0.725186 -0.490742 -0.482989 -0.743808 -0.598138 -0.298295 -0.687992 -0.597674 -0.411647 -0.699947 -0.627762 -0.340571 -0.591564 -0.509743 -0.624671 -0.578644 -0.502156 -0.642659 -0.623703 -0.445261 -0.642446 -0.618052 -0.442554 -0.649737 -0.667613 -0.363802 -0.64957 -0.659272 -0.360965 -0.659595 -0.70307 -0.26597 -0.659509 -0.691007 -0.263575 -0.67308 -0.721694 -0.161362 -0.673142 -0.706461 -0.160437 -0.689328 -0.720787 -0.07023 -0.689589 -0.704918 -0.0711372 -0.705713 -0.708403 -0.0017914 -0.705806 -0.692818 -0.0029483 -0.721106 -0.42702 -0.360286 -0.829366 -0.367676 -0.323429 -0.871899 -0.398564 -0.284651 -0.871849 -0.394411 -0.282427 -0.874457 -0.426037 -0.232311 -0.874371 -0.419844 -0.229897 -0.877997 -0.447729 -0.169536 -0.87795 -0.438853 -0.167389 -0.88283 -0.458268 -0.102645 -0.882868 -0.447114 -0.101533 -0.888696 -0.456053 -0.0446038 -0.888834 -0.444475 -0.0448499 -0.894668 -0.446635 -0.00118954 -0.894715 -0.435223 -0.00183811 -0.900321 -0.915791 -0.324628 -0.236523 -0.777968 -0.419033 -0.468163 -0.758202 -0.423178 -0.496034 -0.759848 -0.403552 -0.509684 -0.767417 -0.429602 -0.475934 -0.879864 -0.403289 -0.25139 -0.799922 -0.42334 -0.425333 -0.80477 -0.402593 -0.436193 -0.82069 -0.419397 -0.388038 -0.819779 -0.414941 -0.394699 -0.84476 -0.41441 -0.338592 -0.824638 -0.472453 -0.311065 -0.879128 -0.396456 -0.264493 -0.871038 -0.411813 -0.267775 -0.883365 -0.403985 -0.237619 -0.89158 -0.388508 -0.232697 -0.532945 -0.490666 -0.68936 -0.0566096 -0.705979 -0.705966 -0.0720186 -0.674366 -0.734877 -0.203055 -0.59897 -0.774599 -0.19053 -0.624443 -0.757476 -0.40081 -0.487766 -0.775523 -0.410947 -0.622628 -0.665926 -0.321225 -0.54912 -0.771546 -0.637919 -0.417109 -0.647363 -0.61773 -0.591404 -0.518316 -0.565768 -0.499351 -0.656167 0 -0.707113 -0.7071 0 -0.707113 -0.7071 -0.260341 -0.660434 -0.704308 -0.0886201 -0.704331 -0.704318 -0.0886195 -0.70433 -0.70432 -0.19699 -0.679304 -0.706924 -0.33013 -0.764992 -0.552993 -0.703944 -0.0947302 -0.703909 -0.703941 -0.0947303 -0.703913 -0.677511 -0.202814 -0.706997 -0.725126 -0.307688 -0.616053 -0.378689 -0.598034 -0.706364 -0.501823 -0.681914 -0.532134 -0.646268 -0.29219 -0.704956 -0.59112 -0.38872 -0.706734 -0.654426 -0.517237 -0.551537 -0.534725 -0.464713 -0.70577 -0.455139 -0.542276 -0.706247 -0.707124 0 -0.707089 -0.707124 0 -0.707089 -0.707124 0 -0.707089 -0.707124 0 -0.707089 -0.378689 0.598034 -0.706364 -0.501823 0.681914 -0.532135 -0.455139 0.542275 -0.706248 -0.534724 0.464713 -0.705771 -0.654426 0.517236 -0.551538 -0.59112 0.38872 -0.706734 -0.653832 0.277436 -0.703941 -0.703944 0.0947308 -0.703909 -0.703941 0.0947297 -0.703913 -0.677512 0.202814 -0.706997 -0.734269 0.331977 -0.592149 -0.0886197 0.704331 -0.704318 -0.280791 0.65066 -0.705548 -0.293313 0.744077 -0.600264 -0.19699 0.679304 -0.706924 -0.0886198 0.70433 -0.70432 0 0.707113 -0.7071 0 0.707113 -0.7071 -0.638296 0.417149 -0.646966 -0.623103 0.567016 -0.538735 -0.50778 0.443376 -0.738633 -0.371775 0.589654 -0.717002 -0.360953 0.572907 -0.735861 -0.214959 0.535362 -0.816811 -0.236935 0.653302 -0.719067 -0.122073 0.628967 -0.767788 -0.0563222 0.711375 -0.700552 -0.0507676 0.706201 -0.706188 -0.753079 0.423248 -0.50372 -0.757747 0.474072 -0.448415 -0.718888 0.535018 -0.443797 -0.801449 0.4142 -0.431414 -0.818665 0.416502 -0.395366 -0.820324 0.415086 -0.39341 -0.834646 0.414932 -0.362211 -0.833985 0.415985 -0.362528 -0.858765 0.406787 -0.311523 -0.843994 0.430569 -0.319819 -0.882041 0.385488 -0.270928 -0.871686 0.403585 -0.277997 -0.87882 0.405745 -0.251091 -0.903089 0.360583 -0.233262 -0.887034 0.397878 -0.234233 -0.877516 0.411724 -0.245866 -0.882042 0.404984 -0.240809 -0.879847 0.405926 -0.247171 0.563914 0.436321 -0.70116 0.563902 0.436319 -0.701171 0.382673 0.600136 -0.702423 0.356403 0.584754 -0.728725 0.136031 0.737275 -0.661756 0.628483 0.324063 -0.707102 0.628483 0.324063 -0.707101 0.70136 0.156988 -0.695305 0.701356 0.156988 -0.695309 0.688392 -0.206549 -0.695309 0.688384 -0.206544 -0.695318 0.499061 -0.51718 -0.695315 0.499067 -0.517193 -0.695301 0.181891 -0.695319 -0.695304 0.181891 -0.695317 -0.695305 0 -0.707113 -0.707101 0 -0.707113 -0.707101 -0.700232 -0.139278 -0.700197 -0.700224 -0.13928 -0.700206 -0.634859 -0.313112 -0.706339 -0.653289 -0.43652 -0.618598 -0.563397 -0.432304 -0.704057 -0.39664 -0.59362 -0.700209 -0.139284 -0.70022 -0.700208 -0.139285 -0.700221 -0.700207 -0.313085 -0.634872 -0.706339 -0.504172 -0.657055 -0.560437 -0.707124 0 -0.707089 -0.707124 0 -0.707089 -0.264931 0.250317 -0.93121 -0.560503 0.41934 -0.714136 -0.695563 0.180093 -0.695528 -0.695567 0.180096 -0.695523 -0.615007 0.349024 -0.70707 0.563492 -0.436982 -0.701087 0.135116 -0.741412 -0.657306 0.353082 -0.583613 -0.731252 0.381989 -0.600509 -0.702477 0.563494 -0.436987 -0.701083 0.628483 -0.324063 -0.707102 0.628483 -0.324063 -0.707101 0.181891 0.695317 -0.695305 0.181892 0.695319 -0.695303 0.499071 0.517191 -0.6953 0.499058 0.517184 -0.695314 0.688383 0.206547 -0.695318 0.688393 0.206546 -0.695309 0.701356 -0.156987 -0.695309 0.701359 -0.156989 -0.695306 0 0.707113 -0.707101 0 0.707113 -0.707101 -0.18616 0.694752 -0.69474 -0.694762 0.186167 -0.694728 -0.694743 0.186154 -0.694751 -0.563391 0.432299 -0.704065 -0.611738 0.611744 -0.501544 -0.432308 0.5634 -0.704053 -0.18616 0.694753 -0.694739 -0.707124 0 -0.707089 -0.707124 0 -0.707089 -0.484348 -0.274873 -0.830573 -0.264933 -0.250319 -0.93121 -0.569644 -0.424262 -0.703923 -0.695567 -0.180094 -0.695523 -0.695562 -0.180094 -0.695528 0.694731 -0.186146 -0.694765 0.694772 -0.186173 -0.694717 0.508607 -0.508606 -0.694722 0.5086 -0.508594 -0.694736 0.186157 -0.694754 -0.694739 0.186157 -0.694752 -0.694741 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0.707089 0 -0.707124 0.707089 0 -0.707124 -0.69473 -0.186151 -0.694765 -0.186157 -0.694753 -0.694741 -0.186158 -0.694754 -0.694739 -0.432308 -0.5634 -0.704053 -0.611738 -0.611744 -0.501544 -0.563391 -0.432299 -0.704065 -0.694744 -0.18615 -0.694751 0.694729 0.186162 -0.694763 0.186157 0.694753 -0.694741 0.186158 0.694754 -0.694739 0.43232 0.563391 -0.704052 0.611735 0.611728 -0.501567 0.563403 0.432332 -0.704036 0.694778 0.186159 -0.694715 -0.707089 0 -0.707124 -0.707089 0 -0.707124 0 0.707113 -0.707101 0 0.707113 -0.707101 -0.700198 0.139275 -0.700233 -0.700221 0.13929 -0.700207 -0.593623 0.396638 -0.700207 -0.593622 0.396636 -0.700209 -0.396642 0.593619 -0.700209 -0.396643 0.593623 -0.700204 -0.139281 0.700222 -0.700207 -0.139282 0.70022 -0.700208 -0.152374 -0.653694 -0.74126 -0.29595 -0.642333 -0.706981 -0.456888 -0.552244 -0.697338 -0.456896 -0.552249 -0.697328 -0.65642 -0.287841 -0.697324 -0.656427 -0.287841 -0.697317 0.654445 -0.291869 -0.697506 0.654438 -0.291868 -0.697512 0.467118 -0.541018 -0.699357 0.432343 -0.524793 -0.733261 0.327241 -0.626941 -0.707007 0.161218 -0.698201 -0.697513 0.161219 -0.698202 -0.697512 -0.16703 -0.696833 -0.697513 -0.167029 -0.696836 -0.69751 -0.332464 -0.62419 -0.707004 -0.436708 -0.521173 -0.733256 -0.471601 -0.5371 -0.699368 -0.656837 -0.286393 -0.697527 -0.656863 -0.28642 -0.697492 0.239154 -0.663847 -0.708599 0.212138 -0.662219 -0.718654 0.118099 -0.613555 -0.780771 -0.0558454 -0.998439 -3.19308e-05 0.650157 -0.305227 -0.695796 0.650157 -0.305227 -0.695796 0.423623 -0.580007 -0.695798 0.42362 -0.579998 -0.695808 0.257853 -0.658429 -0.707095 -0.019665 0.707099 -0.706841 -0.0217184 0.388261 -0.921294 -0.656721 0.286883 -0.697435 -0.656707 0.286883 -0.697448 -0.459116 0.550252 -0.697449 -0.459114 0.550251 -0.697451 -0.164624 0.697466 -0.697453 -0.164623 0.697465 -0.697454 -0.656426 0.287843 -0.697317 -0.656421 0.287838 -0.697324 -0.456894 0.552251 -0.697328 -0.456891 0.552242 -0.697337 -0.162631 0.697697 -0.697689 -0.184502 0.400444 -0.897554 0.18616 0.694753 -0.69474 0.18616 0.694753 -0.694739 0.508597 0.508597 -0.694736 0.508586 0.508591 -0.694749 0.69474 0.18616 -0.694752 0.694763 0.18616 -0.694729 0.694763 -0.186166 -0.694728 0.694742 -0.186155 -0.694751 0.508588 -0.508588 -0.694749 0.508595 -0.508599 -0.694736 0.18616 -0.694754 -0.694739 0.18616 -0.694753 -0.69474 0.18616 0.694753 -0.69474 0.18616 0.694753 -0.694739 0.508597 0.508597 -0.694736 0.508586 0.508591 -0.694749 0.69474 0.18616 -0.694752 0.694763 0.18616 -0.694729 0.694763 -0.186166 -0.694728 0.694742 -0.186155 -0.694751 0.508588 -0.508588 -0.694749 0.508595 -0.508599 -0.694736 0.18616 -0.694754 -0.694739 0.18616 -0.694753 -0.69474 0.705816 -0.68285 -0.188519 0.698141 -0.6903 -0.189962 0.707093 -0.638352 -0.30418 0.705726 -0.639166 -0.305642 0.709769 -0.64688 -0.278879 0.736979 -0.62389 -0.260044 0.700034 -0.667215 -0.254513 0.705424 -0.665449 -0.244038 0.702859 -0.676687 -0.219282 0.704906 -0.674848 -0.218376 0.702502 -0.686248 -0.188561 0.702278 -0.68644 -0.188696 0.702724 -0.688166 -0.180575 0.706251 -0.26142 -0.657928 0.749134 -0.253216 -0.612112 0.707087 -0.31459 -0.633294 0.706732 -0.352452 -0.613439 0.70675 -0.352439 -0.613426 0.706786 -0.405517 -0.579663 0.706801 -0.405505 -0.579653 0.707112 -0.431365 -0.560283 0.715383 -0.448077 -0.536148 0.580611 -0.549242 -0.60102 0.706856 -0.496518 -0.50381 0.707082 -0.522381 -0.476605 0.731553 -0.51495 -0.446829 0.626458 -0.614376 -0.47968 0.706878 -0.567791 -0.421826 0.706877 -0.597191 -0.379063 0.734449 -0.56935 -0.369358 0.666662 -0.656627 -0.352708 0.706744 -0.619925 -0.340889 0.475945 0.362125 -0.801462 0.695178 0.459556 -0.552753 0.542696 0.45362 -0.706902 0.618867 0.356274 -0.700052 0.624466 0.284821 -0.727268 0.614223 0.270258 -0.741411 0.740628 0.192199 -0.643839 0.584004 0.164377 -0.794933 0.717156 0.103285 -0.689217 0.663435 0.0100601 -0.748167 0.656022 0.0114602 -0.754655 0.763557 -0.0454852 -0.644136 0.762727 -0.0453451 -0.64513 0.680849 -0.150889 -0.716713 0.718231 -0.172937 -0.673971 0.707091 -0.205166 -0.676705 0.452518 0.548643 -0.703006 0.45251 0.54863 -0.703022 0.416771 0.573046 -0.705634 0.416743 0.573033 -0.705662 0.526077 -0.476025 -0.70473 0.864911 -0.186952 -0.465808 0.70954 -0.526751 -0.468067 0.614154 -0.353781 -0.705446 0.674083 -0.220492 -0.704979 0.705199 -0.0730666 -0.705234 0.705199 0.0730667 -0.705234 0.864911 0.186952 -0.465809 0.526077 0.476025 -0.70473 0.70954 0.526751 -0.468067 0.614154 0.353781 -0.705446 0.674083 0.220492 -0.704979 0.416754 -0.573024 -0.705663 0.416758 -0.573055 -0.705635 0.704165 -0.0913904 -0.70413 0.704147 -0.0913911 -0.704148 0.657492 -0.268106 -0.704147 0.657512 -0.268111 -0.704127 0.567285 -0.427072 -0.704129 0.567272 -0.427065 -0.704143 0.439461 -0.557725 -0.704143 0.439473 -0.557736 -0.704126 0.707124 0 -0.707089 0.707124 0 -0.707089 0.707124 0 -0.707089 0.707124 0 -0.707089 0.439471 0.557738 -0.704127 0.439463 0.557723 -0.704143 0.567274 0.427064 -0.704143 0.567283 0.427073 -0.70413 0.65751 0.268114 -0.704128 0.657493 0.268103 -0.704148 0.704148 0.0913882 -0.704148 0.704165 0.0913934 -0.70413 0.416771 0.573046 -0.705634 0.416743 0.573033 -0.705662 0.526077 -0.476025 -0.70473 0.864911 -0.186952 -0.465808 0.70954 -0.526751 -0.468067 0.614154 -0.353781 -0.705446 0.674083 -0.220492 -0.704979 0.705199 -0.0730666 -0.705234 0.705199 0.0730667 -0.705234 0.864911 0.186952 -0.465809 0.526077 0.476025 -0.70473 0.70954 0.526751 -0.468067 0.614154 0.353781 -0.705446 0.674083 0.220492 -0.704979 0.416754 -0.573024 -0.705663 0.416758 -0.573055 -0.705635 0.452509 -0.548631 -0.703022 0.45252 -0.548642 -0.703006 0.626885 0.145752 -0.765357 0.843548 0.0145843 -0.536856 0.706686 0.180691 -0.684066 0.69463 0.0349205 -0.718519 0.714752 -0.00392499 -0.699367 0.675033 -0.0662263 -0.734809 0.790198 -0.184188 -0.584519 0.708413 -0.188057 -0.680283 0.64919 -0.230958 -0.724714 0.661672 -0.28989 -0.691487 0.578699 -0.298083 -0.759114 0.605575 -0.343608 -0.717783 0.575505 -0.433999 -0.693137 0.563246 -0.429306 -0.70601 0.706891 0.623118 -0.334707 0.654336 0.660361 -0.368467 0.732222 0.575011 -0.364985 0.638347 0.627309 -0.44609 0.706868 0.567799 -0.421831 0.70685 0.534269 -0.463594 0.745218 0.509957 -0.429643 0.641514 0.538461 -0.546369 0.706584 0.504357 -0.49635 0.706879 0.456567 -0.540248 0.719462 0.445383 -0.532925 0.707111 0.432517 -0.559395 0.706804 0.405507 -0.579649 0.706789 0.405512 -0.579663 0.706753 0.352442 -0.613421 0.70673 0.352448 -0.613443 0.707112 0.319312 -0.630899 0.72861 0.26182 -0.632911 0.706049 0.266563 -0.656079 0.680125 0.699654 -0.218892 0.705476 0.683372 -0.187901 0.772238 0.607094 -0.18731 0.714511 0.667704 -0.208915 0.678867 0.700777 -0.219206 0.707096 0.638471 -0.303926 0.732701 0.622015 -0.276128 0.761745 0.596121 -0.25374 0.709181 0.655308 -0.260065 0.699286 0.679711 -0.221343 -0.00494032 0.779227 0.626722 -0.00349145 0.776803 0.629734 -0.00747495 0.778293 0.627857 -0.0052728 0.77829 0.627883 -0.00399487 0.779485 0.626408 -0.00260139 0.778526 0.627607 -0.000415361 0.778166 0.628059 -0.000579415 0.778349 0.627832 0 0.778349 0.627832 0 0.778349 0.627832 -0.672362 0.0843623 0.7354 -0.697893 0.107022 0.708161 -0.617054 0.265157 0.740903 -0.531207 0.271425 0.802588 -0.648911 0.227013 0.726209 -0.540644 0.469856 0.69781 -0.557075 0.470219 0.684516 -0.612811 0.385979 0.689553 -0.366331 0.601969 0.709531 -0.462626 0.582539 0.6683 -0.501136 0.549858 0.668221 -0.00676464 0.778331 0.627818 -0.119817 0.753729 0.646171 -0.133616 0.719778 0.681224 -0.248368 0.725363 0.641998 -0.36449 0.665548 0.6513 -0.321319 0.000219017 0.946971 -0.305145 0.00408465 0.952297 -0.338403 0.00694065 0.940976 -0.305959 0.0209504 0.951814 -0.262047 0.0223938 0.964795 -0.382521 0.0512049 0.922527 -0.257079 0.0537526 0.964894 -0.304688 0.0687092 0.949971 -0.377737 0.2723 0.884967 -0.37262 0.243949 0.895346 -0.350916 0.227582 0.908331 -0.36324 0.193857 0.911305 -0.303708 0.156624 0.939803 -0.38392 0.155315 0.91021 -0.260645 0.0942898 0.960819 -0.322624 0.102541 0.940956 -0.332752 0.0934018 0.938377 -0.357503 0.271978 0.893431 -0.378639 0.283879 0.880934 -0.409127 0.328023 0.851479 -0.401606 0.325161 0.856144 -0.437753 0.364374 0.821951 -0.520399 0.422069 0.742323 -0.498644 0.383652 0.777281 -0.571159 0.412939 0.709408 -0.554809 0.391788 0.733954 -0.567073 0.373675 0.734027 -0.629934 0.384287 0.674912 -0.584326 0.340493 0.736633 -0.665199 0.312425 0.67816 -0.642455 0.296302 0.706722 -0.668437 0.223013 0.709547 -0.724568 0.229453 0.649887 -0.678996 0.17428 0.713156 -0.687716 0.137169 0.712903 -0.758105 0.131469 0.638743 -0.641253 0.0712304 0.764016 -0.733141 0.0463923 0.678492 -0.675219 0.0288839 0.737051 -0.675496 -0.0195303 0.737105 -0.701499 -0.03799 0.711657 -0.729647 -0.0459429 0.682279 -0.649149 -0.0740063 0.757052 -0.755668 -0.12966 0.641992 -0.687824 -0.135486 0.713121 -0.749637 -0.234813 0.618795 -0.702513 -0.202143 0.682359 -0.679749 -0.170397 0.713377 -0.71691 -0.357348 0.598618 -0.652135 -0.269402 0.70862 -0.666109 -0.233182 0.708467 -0.604173 -0.282087 0.745253 -0.61429 -0.373628 0.695018 -0.576011 -0.358325 0.734721 -0.559622 -0.385942 0.733398 -0.566777 -0.408705 0.715349 -0.490295 -0.370995 0.788653 -0.52205 -0.422291 0.741036 -0.52404 -0.424632 0.738289 -0.440456 -0.368163 0.818813 -0.37914 -0.26989 0.885106 -0.371881 -0.280058 0.885026 -0.327976 -0.256219 0.909276 -0.404151 -0.325754 0.85472 -0.438426 -0.367283 0.820296 -0.354689 -0.232259 0.905677 -0.346482 -0.225999 0.910426 -0.368546 -0.20197 0.907404 -0.290423 -0.150754 0.944948 -0.357807 -0.163505 0.919369 -0.31546 -0.124898 0.940684 -0.25971 -0.0948548 0.961017 -0.327318 -0.10781 0.938744 -0.332517 -0.0897971 0.938813 -0.266397 -0.0566112 0.9622 -0.327339 -0.0636607 0.94276 -0.32364 -0.0417348 0.945259 -0.275458 -0.0239765 0.961014 -0.363737 -0.0243945 0.931182 -0.300879 -0.00409388 0.953654 -0.321317 -0.00295396 0.946967 -0.0864348 -0.775432 0.625487 -0.129782 -0.70118 0.701073 -0.219378 -0.733333 0.643503 -0.314665 -0.697438 0.643869 -0.354405 -0.611267 0.707637 -0.358976 -0.584615 0.727573 -0.470125 -0.599491 0.647761 -0.514111 -0.528364 0.675664 -0.528642 -0.517624 0.672758 -0.67457 -0.0457929 0.736789 -0.625992 -0.144581 0.76631 -0.655467 -0.13778 0.742549 -0.657679 -0.269206 0.703553 -0.589237 -0.382436 0.711718 -0.568985 -0.353188 0.74264 -0.55217 -0.48007 0.681645 0 -0.778345 0.627837 0 -0.778345 0.627837 -0.00496896 -0.777491 0.628875 -0.000559044 -0.778345 0.627837 -0.000155341 -0.77879 0.627285 -0.00105661 -0.778328 0.627857 -0.00261735 -0.778344 0.627833 -0.00382306 -0.777684 0.628644 -0.00537616 -0.77853 0.627584 -0.00678053 -0.778294 0.627864 -0.00747861 -0.778294 0.627855 0.72098 0 0.692956 0.720967 2.97529e-06 0.69297 0.720999 -1.91516e-06 0.692936 0.720828 1.25811e-05 0.693114 0.721117 0 0.692813 0.433193 -0.637494 0.637138 0.110814 -0.8069 0.5802 0.144566 -0.777626 0.611881 0.772245 -0.322387 0.547452 0.618363 -0.464537 0.633903 0.52947 -0.562198 0.635291 0.393727 -0.729712 0.559017 0.60543 -0.391804 0.69278 0.75114 -0.143447 0.644369 0.719987 -0.0524626 0.692002 -0.276988 -0.743683 0.608452 -0.266232 -0.754322 0.600099 -0.267611 -0.734278 0.623875 -0.234221 -0.778747 0.581974 -0.229867 -0.734215 0.638819 -0.190954 -0.793627 0.577662 -0.181241 -0.765901 0.616885 -0.168496 -0.774622 0.609565 -0.151275 -0.779292 0.608128 -0.130296 -0.806928 0.576099 -0.111691 -0.743389 0.659468 -0.102925 -0.759617 0.642174 -0.0646843 -0.808792 0.584526 -0.0464196 -0.755973 0.652955 -0.0370646 -0.773358 0.632885 -0.0258795 -0.787239 0.616104 0.755045 -0.14243 0.640016 0.776258 -0.132332 0.61637 0.762939 -0.108451 0.637308 0.786509 -0.0973023 0.609865 0.768277 -0.075429 0.635658 0.780766 -0.0674802 0.621169 0.719865 -0.263843 0.642013 0.745985 -0.219126 0.628879 0.705576 -0.1883 0.683158 0.731466 -0.183525 0.656716 0.768512 -0.166107 0.617898 0.73929 -0.263529 0.61968 0.710047 -0.288719 0.642241 0.70859 -0.320286 0.628743 0.649942 -0.320871 0.688924 0.668789 -0.35251 0.654567 0.658209 -0.397624 0.639262 0.649664 -0.39748 0.648032 0.611259 -0.438761 0.658674 0.57579 -0.435863 0.691729 0.58842 -0.507175 0.629711 0.590811 -0.507277 0.627386 0.482017 -0.510705 0.711927 0.510479 -0.565451 0.647825 0.421414 -0.588744 0.689776 0.459267 -0.712716 0.530198 0.389448 -0.604486 0.69493 0.336901 -0.659626 0.671857 0.316457 -0.659165 0.68217 0.298513 -0.681008 0.668669 0.287392 -0.717566 0.634432 0.202005 -0.673185 0.711348 0.186744 -0.716646 0.671971 0.161791 -0.722025 0.672684 0.143785 -0.740497 0.656499 0.103497 -0.720235 0.685967 0.0913153 -0.737199 0.669476 0.063536 -0.74851 0.660072 0.0619205 -0.778012 0.625191 -0.0331512 -0.715863 0.697453 -0.0323387 -0.727886 0.684935 -0.0403934 -0.766334 0.641171 -0.0672422 -0.753782 0.653675 -0.0945953 -0.760121 0.642859 -0.116001 -0.741679 0.660649 -0.14831 -0.77413 0.615408 -0.132602 -0.79118 0.597035 -0.189666 -0.74861 0.635303 -0.237937 -0.753233 0.613209 -0.200531 -0.804413 0.559203 -0.266271 -0.744126 0.61268 0.788125 -0.00466995 0.615498 0.794984 -0.00642865 0.606597 0.766749 -0.0215304 0.641586 0.823441 -0.0279888 0.566711 0.750757 -0.0460983 0.658968 0.85035 -0.0643108 0.522273 0.791322 -0.0717318 0.607177 0.780723 -0.0680082 0.621166 0.788117 -0.00034949 0.615525 0.788105 -0.000405838 0.615541 0.788135 -0.000540668 0.615502 0.788132 0.000527357 0.615506 0.788105 0.000405767 0.615541 0.788117 0.000349437 0.615525 0.788087 0.010249 0.615479 0.821974 0.0142876 0.569346 0.767474 0.0283444 0.640453 0.805519 0.0359989 0.591476 0.757574 0.0466888 0.651077 0.823616 0.0620138 0.563747 0.780777 0.0702973 0.620842 0.779251 0.0699113 0.6228 0.779315 0.0691486 0.622806 0.777325 0.152215 0.610407 0.529081 0.57505 0.624012 -0.26527 0.744195 0.61303 -0.249465 0.682497 0.686997 -0.216681 0.82365 0.524071 -0.208608 0.757325 0.618823 -0.171125 0.735909 0.655099 -0.171153 0.735786 0.655229 -0.0627416 0.779495 0.623258 0.0027029 0.684397 0.729104 -0.0190928 0.759951 0.6497 -0.103154 0.734414 0.670817 0.0537969 0.789737 0.611082 0.104985 0.718148 0.687926 0.129795 0.731351 0.669536 0.213907 0.706616 0.674491 0.212461 0.703627 0.678063 0.291654 0.67803 0.674695 0.297879 0.627095 0.719736 0.3962 0.666874 0.631113 0.407339 0.576222 0.70855 0.413035 0.591574 0.692418 0.479752 0.577165 0.660847 0.45233 0.436338 0.777822 0.536926 0.548748 0.64077 0.572959 0.461191 0.677511 0.586973 0.481491 0.650868 0.61163 0.438063 0.658794 0.666476 0.419931 0.61601 0.63431 0.383508 0.671247 0.73103 0.180532 0.65803 0.756075 0.197363 0.624018 0.741798 0.219572 0.633659 0.738818 0.229709 0.633547 0.70899 0.245896 0.66096 0.716937 0.252738 0.649712 0.716739 0.316133 0.621567 0.701467 0.303516 0.644842 0.681681 0.347271 0.643983 0.681052 0.345104 0.645811 0.671725 0.361326 0.646707 0.82922 0.118376 0.546243 0.693056 0.0769471 0.716765 0.79309 0.146891 0.591127 -0.0260132 0.787234 0.616105 -0.0589726 0.827421 0.558477 -0.0474225 0.718178 0.694241 -0.0967149 0.805609 0.584501 -0.100289 0.814484 0.571452 -0.144794 0.738114 0.658956 -0.152825 0.770416 0.618953 -0.177404 0.778157 0.602494 -0.203897 0.74397 0.636345 -0.209742 0.792786 0.572275 -0.256605 0.725549 0.638539 -0.256241 0.731633 0.631707 -0.264213 0.77059 0.579985 -0.271277 0.730947 0.626199 -0.274991 0.743782 0.609236 0.719309 0.0680366 0.69135 0.715391 0.0762481 0.694552 0.721511 0.210726 0.659558 0.661478 0.341689 0.667604 0.665654 0.337938 0.665359 0.605976 0.482353 0.632557 0.488789 0.583185 0.64883 0.508879 0.576332 0.639441 0.374141 0.694379 0.6147 0.21634 0.735161 0.642445 0.265606 0.740043 0.617891 0.0626602 0.789484 0.610564 0.0433308 0.786108 0.616568 0.720935 0.000159426 0.693003 0.721117 0 0.692813 0.720934 -7.9525e-06 0.693003 0.72098 -9.62939e-07 0.692956 0.720966 0 0.692971 0.187182 -0.899885 -0.393916 0.158077 -0.951343 -0.264497 0.83724 -0.51374 -0.187351 0.987894 -0.136804 -0.0731449 0.981962 -0.170897 -0.080904 0.893994 -0.418207 -0.160864 0.759897 -0.617531 -0.203008 0.188322 -0.928408 -0.320301 0.0124158 -0.955269 -0.295478 0.55053 -0.790005 -0.269832 0.453895 -0.848943 -0.270694 0.645052 -0.723183 -0.246806 0.981923 -0.169994 -0.0832485 0.982934 -0.164944 -0.0814549 0.836415 -0.495928 -0.233379 0.838696 -0.492571 -0.2323 0.549031 -0.757546 -0.353113 0.551319 -0.756057 -0.352741 0.0322379 -0.907052 -0.419782 0.188511 -0.87242 -0.450939 0.188598 -0.676351 -0.712026 0.982941 -0.122025 -0.137613 0.982215 -0.0771422 -0.17118 0.982899 -0.0751066 -0.168134 0.982873 -0.155019 -0.099647 0.981493 -0.161406 -0.103047 0.838519 -0.459256 -0.293206 0.186566 -0.828151 -0.528544 0.188119 -0.827826 -0.528503 0.188057 -0.742582 -0.642811 0.190871 -0.742005 -0.642648 0.550986 -0.630811 -0.546344 0.551117 -0.703318 -0.449015 0.551142 -0.703303 -0.449008 0.551643 -0.499143 -0.668242 0.551699 -0.559216 -0.618793 0.83889 -0.364948 -0.403828 0.838344 -0.412059 -0.356912 0.982856 -0.139366 -0.120714 0.984124 -0.133766 -0.116646 0.551503 -0.426947 -0.716631 0.551591 -0.499153 -0.668276 0.838841 -0.325767 -0.436144 0.838878 -0.364957 -0.403845 0.98433 -0.118231 -0.130828 0.982958 -0.127839 -0.132099 0.984146 -0.0897724 -0.152961 0.982907 -0.0942223 -0.158164 0.838722 -0.278702 -0.467835 0.838641 -0.221565 -0.497584 0.83531 -0.224681 -0.501773 0.982913 -0.109257 -0.148139 0.981479 -0.114637 -0.153485 0.838808 -0.325789 -0.436192 0.838751 -0.278688 -0.467793 0.551453 -0.426954 -0.716665 0.551344 -0.339865 -0.761913 0.54827 -0.341333 -0.763474 0.838501 -0.459282 -0.293218 0.838416 -0.411985 -0.356831 0.550866 -0.630862 -0.546406 0.551708 -0.559214 -0.618788 0.130627 -0.664745 -0.735561 0.399945 -0.548489 -0.734305 0.188067 -0.609186 -0.770405 0.188344 -0.502661 -0.843717 0.0861076 -0.525854 -0.846205 0.324262 -0.385808 -0.863716 0.186763 -0.418663 -0.88873 0.187179 -0.300782 -0.935144 0.670423 0.426298 -0.607292 0.161311 0.0748833 -0.984058 0.221537 0.136256 -0.965586 0.826928 0.529358 -0.189658 0.827124 0.530098 -0.186714 0.905348 0.376 -0.197404 0.906383 0.379277 -0.186061 0.78001 0.301709 -0.548231 0.703659 0.447164 -0.552185 0.746256 0.504148 -0.43467 0.201881 -0.101128 -0.974175 0.176985 -0.112856 -0.977722 0.534567 0.000767841 -0.845126 0.186891 0.0263477 -0.982027 0.164458 0.0114446 -0.986318 0.502649 0.169138 -0.847783 0.557196 0.00383867 -0.830372 0.816739 0.113939 -0.565646 0.958017 0.200569 -0.20488 0.960867 0.209822 -0.18086 0.83128 0.116253 -0.543561 0.770604 0.300028 -0.562275 0.520953 0.173627 -0.83574 0.460642 0.288526 -0.839382 0.508351 0.336556 -0.79266 0.978816 0.0132985 -0.204311 0.9853 0.032537 -0.167703 0.831746 -0.0991047 -0.546239 0.848803 -0.0838709 -0.522014 0.546389 -0.19979 -0.813353 0.565216 -0.190481 -0.802651 0.0803162 -0.279091 -0.9569 0.19425 -0.218389 -0.956333 0.397478 0.585546 -0.706504 0.145582 0.214466 -0.965821 0.145592 0.214474 -0.965818 0.542565 0.799276 -0.25842 0.542561 0.799276 -0.258428 0.631541 0.731006 -0.25843 0.46266 0.535529 -0.706509 0.169466 0.196157 -0.965818 0.169464 0.196156 -0.965818 0.193877 0.172436 -0.965752 0.193875 0.172434 -0.965753 0.455641 0.405252 -0.792567 0.540402 0.458584 -0.705454 0.5934 0.527775 -0.607726 0.673054 0.59862 -0.434342 0.397474 0.585543 -0.706508 0.462661 0.53553 -0.706508 0.631539 0.731006 -0.258433 0.73082 0.631962 -0.257926 0.734053 0.652877 -0.186864 0.57824 0.774152 -0.257541 0.578246 0.774151 -0.257529 0.724697 0.639135 -0.257528 0.724696 0.639135 -0.25753 0.840343 0.476972 -0.25753 0.84033 0.476979 -0.257557 0.920275 0.294544 -0.25756 0.920285 0.294535 -0.257535 0.961122 0.0995951 -0.257535 0.961131 0.0995841 -0.257508 0.96113 -0.0995957 -0.257508 0.961124 -0.0995832 -0.257535 0.920282 -0.294546 -0.257534 0.920279 -0.294533 -0.257559 0.840336 -0.476969 -0.257557 0.840337 -0.476983 -0.25753 0.724697 -0.639134 -0.25753 0.724697 -0.639135 -0.257528 0.578242 -0.774155 -0.257529 0.578244 -0.774149 -0.257541 0.424289 0.56803 -0.705209 0.424277 0.568025 -0.705221 0.53173 0.468962 -0.705221 0.531747 0.468965 -0.705207 0.616606 0.349975 -0.705206 0.616596 0.349975 -0.705214 0.675253 0.216117 -0.705214 0.675244 0.216119 -0.705222 0.705211 0.0730756 -0.705222 0.705209 0.0730764 -0.705223 0.705209 -0.0730753 -0.705223 0.705211 -0.0730764 -0.705222 0.675246 -0.216114 -0.705222 0.675252 -0.216121 -0.705214 0.616598 -0.34997 -0.705215 0.616603 -0.349979 -0.705206 0.531741 -0.468972 -0.705207 0.531736 -0.468956 -0.705221 0.424283 -0.568021 -0.705221 0.424284 -0.568034 -0.70521 0.155646 0.208382 -0.965584 0.155653 0.208385 -0.965582 0.195074 0.172042 -0.965582 0.195068 0.172041 -0.965583 0.226195 0.128392 -0.965583 0.226211 0.128393 -0.965579 0.247733 0.0792814 -0.965579 0.24772 0.0792834 -0.965582 0.258712 0.0268117 -0.965582 0.258719 0.0268091 -0.965581 0.258719 -0.0268124 -0.965581 0.258712 -0.0268083 -0.965582 0.247721 -0.0792776 -0.965582 0.24773 -0.0792869 -0.965579 0.226208 -0.1284 -0.965579 0.226199 -0.128386 -0.965583 0.195069 -0.172039 -0.965583 0.195072 -0.172044 -0.965582 0.15565 -0.208388 -0.965581 0.155649 -0.20838 -0.965583 0.608316 -0.0393123 -0.792721 0.195072 -0.0126049 -0.980708 0.793233 -0.0145692 -0.608744 0.979819 -0.044451 -0.194884 0.44206 -0.0285681 -0.896531 0.260453 -0.0030868 -0.965482 0.254464 -0.0498838 -0.965795 0.254474 -0.0498887 -0.965792 0.245935 -0.0822302 -0.965792 0.245921 -0.082221 -0.965796 0.233295 -0.113187 -0.965796 0.23331 -0.1132 -0.965791 0.216801 -0.142284 -0.965791 0.216799 -0.142282 -0.965792 0.196682 -0.169003 -0.965792 0.19668 -0.169001 -0.965793 0.173294 -0.192907 -0.965793 0.173295 -0.192911 -0.965792 0.147024 -0.213611 -0.965792 0.14702 -0.213599 -0.965795 0.895395 -0.0578522 -0.441499 0.706388 -0.0456403 -0.706352 0.694637 -0.136181 -0.706353 0.694618 -0.136169 -0.706374 0.671311 -0.22445 -0.706374 0.671327 -0.224463 -0.706354 0.636859 -0.308987 -0.706355 0.636851 -0.308978 -0.706366 0.591782 -0.388381 -0.706367 0.59178 -0.388378 -0.70637 0.536868 -0.461318 -0.70637 0.536864 -0.461311 -0.706377 0.473028 -0.526571 -0.706377 0.473026 -0.526563 -0.706384 0.401321 -0.583066 -0.706382 0.401325 -0.583085 -0.706363 0.547729 -0.795777 -0.258324 0.547727 -0.795784 -0.258308 0.645594 -0.71867 -0.258306 0.645594 -0.718675 -0.258293 0.73272 -0.629609 -0.258291 0.732719 -0.62959 -0.258338 0.807653 -0.530054 -0.25834 0.807653 -0.530056 -0.258335 0.869159 -0.421693 -0.258336 0.86916 -0.421695 -0.258332 0.916203 -0.306328 -0.258333 0.916201 -0.306325 -0.258341 0.948007 -0.185854 -0.258342 0.948013 -0.185864 -0.258313 0.964051 -0.0622944 -0.258313 0.980788 0 -0.195077 0.980788 0 -0.195077 0.896897 0 -0.44224 0.896897 0 -0.44224 0.793317 0 -0.608808 0.793317 0 -0.608808 0.608786 0 -0.793334 0.608786 0 -0.793334 0.44224 0 -0.896897 0.44224 0 -0.896897 0.195088 0 -0.980786 0.195088 0 -0.980786 0.978824 0.063249 -0.194686 0.792277 0.0511897 -0.60801 0.147017 0.213601 -0.965795 0.147026 0.213608 -0.965792 0.173296 0.19291 -0.965792 0.173294 0.192909 -0.965793 0.19668 0.169001 -0.965793 0.196682 0.169002 -0.965792 0.216799 0.142282 -0.965792 0.216802 0.142283 -0.965791 0.233313 0.113195 -0.965791 0.233293 0.113192 -0.965796 0.24592 0.0822251 -0.965796 0.245936 0.0822259 -0.965792 0.254474 0.0498858 -0.965792 0.254464 0.0498867 -0.965795 0.258768 0.0167207 -0.965795 0.195084 -0.00578545 -0.980769 0.44206 0.0285681 -0.896531 0.608316 0.0393124 -0.792721 0.708071 0.0270137 -0.705624 0.694638 0.136173 -0.706353 0.694616 0.136177 -0.706374 0.671309 0.224457 -0.706373 0.67133 0.224456 -0.706354 0.636861 0.308983 -0.706355 0.636849 0.308982 -0.706366 0.591783 0.38838 -0.706367 0.59178 0.388379 -0.70637 0.53687 0.461316 -0.70637 0.536862 0.461313 -0.706378 0.47303 0.526568 -0.706377 0.473023 0.526565 -0.706384 0.401315 0.583071 -0.706382 0.401331 0.583081 -0.706363 0.895395 0.0578522 -0.441499 0.964931 0.0481019 -0.258057 0.948015 0.185855 -0.258313 0.948006 0.185862 -0.258342 0.916201 0.306327 -0.258341 0.916203 0.306326 -0.258333 0.86916 0.421693 -0.258332 0.869159 0.421694 -0.258336 0.807654 0.530055 -0.258335 0.807652 0.530055 -0.25834 0.73271 0.629601 -0.258338 0.732729 0.629599 -0.25829 0.645597 0.718672 -0.258293 0.645591 0.718672 -0.258306 0.547731 0.795781 -0.258308 0.547725 0.79578 -0.258324 0.117335 -0.15709 -0.980589 0.365545 -0.489385 -0.791757 0.537281 -0.719315 -0.440358 0.587048 -0.785935 -0.194116 0.594718 -0.761407 -0.25801 0.724697 -0.639135 -0.257528 0.724697 -0.639134 -0.25753 0.840337 -0.476983 -0.25753 0.840336 -0.476969 -0.257557 0.920279 -0.294533 -0.257559 0.920282 -0.294545 -0.257535 0.961124 -0.0995832 -0.257535 0.96113 -0.0995958 -0.257508 0.961131 0.0995841 -0.257508 0.961123 0.0995951 -0.257535 0.920285 0.294535 -0.257535 0.920275 0.294544 -0.25756 0.84033 0.476979 -0.257557 0.840343 0.476972 -0.25753 0.724696 0.639135 -0.25753 0.724697 0.639135 -0.257528 0.578246 0.774151 -0.257529 0.57824 0.774152 -0.257541 0.475693 -0.636861 -0.606732 0.446386 -0.549278 -0.706423 0.531736 -0.468956 -0.705221 0.531741 -0.46897 -0.705208 0.616602 -0.349979 -0.705207 0.616598 -0.349971 -0.705215 0.675252 -0.216121 -0.705214 0.675246 -0.216115 -0.705221 0.705211 -0.0730765 -0.705222 0.705209 -0.0730753 -0.705223 0.705209 0.0730764 -0.705223 0.705211 0.0730756 -0.705222 0.675244 0.216119 -0.705222 0.675253 0.216117 -0.705214 0.616596 0.349975 -0.705214 0.616606 0.349975 -0.705206 0.531747 0.468965 -0.705207 0.53173 0.468962 -0.705221 0.424277 0.568025 -0.705221 0.424289 0.56803 -0.705209 0.265822 -0.355877 -0.89593 0.172709 -0.192785 -0.965922 0.195072 -0.172044 -0.965582 0.19507 -0.172039 -0.965583 0.226199 -0.128387 -0.965583 0.226208 -0.1284 -0.965579 0.24773 -0.0792869 -0.965579 0.247721 -0.0792776 -0.965582 0.258712 -0.0268083 -0.965582 0.258719 -0.0268124 -0.965581 0.258719 0.0268091 -0.965581 0.258712 0.0268117 -0.965582 0.24772 0.0792834 -0.965582 0.247733 0.0792814 -0.965579 0.226211 0.128393 -0.965579 0.226195 0.128392 -0.965583 0.195068 0.172041 -0.965583 0.195074 0.172042 -0.965582 0.155653 0.208385 -0.965582 0.155646 0.208382 -0.965584 0.732929 -0.651877 -0.194607 0.580298 -0.790893 -0.194274 0.580298 -0.790898 -0.194254 0.667936 -0.718203 -0.195052 0.531036 -0.723754 -0.440659 0.487448 -0.675262 -0.553549 0.470096 -0.640697 -0.607057 0.361159 -0.492227 -0.792008 0.324832 -0.453375 -0.830021 0.262591 -0.357892 -0.89608 0.115901 -0.157964 -0.980619 0.115896 -0.157956 -0.980621 0.730166 -0.678024 -0.0845034 0.610135 -0.566565 -0.553841 0.610135 -0.566564 -0.553842 0.408379 -0.379216 -0.830314 0.408378 -0.379215 -0.830316 0.143574 -0.133321 -0.980618 0.14357 -0.133317 -0.980619 0.182111 0.0408073 -0.982431 0.19758 0.241101 -0.950175 0.0999985 0.277097 -0.955624 0.18849 0.32296 -0.927453 0.985771 -0.0254657 -0.166154 0.979001 -0.019862 -0.202888 0.961968 -0.205177 -0.180333 0.957054 -0.204148 -0.205842 0.817947 -0.108741 -0.564924 0.849133 0.0895613 -0.52053 0.834609 0.0925958 -0.543004 0.163116 -0.0153169 -0.986488 0.188883 -0.022254 -0.981747 0.519317 -0.176841 -0.836084 0.177367 0.115325 -0.977364 0.166243 0.116275 -0.979206 0.556037 -0.00803231 -0.831119 0.504174 -0.165178 -0.847658 0.778904 -0.304084 -0.54849 0.907305 -0.3771 -0.185992 0.904741 -0.377395 -0.197529 0.771923 -0.296893 -0.562129 0.830275 -0.12038 -0.544199 0.535583 0.00455202 -0.844471 0.565468 0.194597 -0.801485 0.549231 0.195599 -0.812457 0.82636 -0.528509 -0.194441 0.827569 -0.528348 -0.18968 0.702024 -0.447327 -0.554131 0.703302 -0.447688 -0.552215 0.472273 -0.295819 -0.830331 0.459404 -0.29064 -0.839331 0.169918 -0.0988885 -0.980484 0.152529 -0.0911329 -0.984088 0.189317 0.568661 -0.80049 0.982955 0.14549 -0.112395 0.98712 0.121502 -0.104071 0.97561 0.15142 -0.158926 0.986157 0.101571 -0.131062 0.982937 0.0787562 -0.166229 0.982862 0.0974262 -0.156491 0.551362 0.339951 -0.761862 0.551342 0.339952 -0.761876 0.838666 0.221932 -0.497378 0.83864 0.22194 -0.497419 0.985477 0.0691916 -0.155074 0.982952 0.0683831 -0.170674 0.975409 0.112625 -0.189454 0.838757 0.278242 -0.468047 0.838726 0.278275 -0.468082 0.551511 0.426273 -0.717026 0.551455 0.426303 -0.717051 0.982922 0.109943 -0.147572 0.838831 0.325239 -0.436557 0.838806 0.325269 -0.436583 0.551624 0.498328 -0.668865 0.551586 0.49835 -0.66888 0.352836 0.559032 -0.750327 0.115453 0.507612 -0.853815 0.350452 0.409261 -0.84243 0.18819 0.400205 -0.896895 0.188622 0.679557 -0.70896 0.982926 0.123182 -0.136682 0.838884 0.3644 -0.404334 0.838866 0.364423 -0.404351 0.551705 0.558372 -0.61955 0.551677 0.558389 -0.619559 0.138827 0.663002 -0.735632 0.189676 0.647672 -0.737932 0.189142 0.780898 -0.595334 0.988178 0.1158 -0.100473 0.83841 0.411681 -0.357193 0.838338 0.411773 -0.357256 0.550983 0.630342 -0.546888 0.550863 0.630411 -0.54693 0.0740048 0.753277 -0.653526 0.188229 0.733888 -0.65267 0.188106 0.827622 -0.528827 0.188701 0.827555 -0.52872 0.551133 0.703159 -0.449244 0.551108 0.703171 -0.449255 0.838516 0.459164 -0.293359 0.838493 0.459192 -0.293382 0.982879 0.155265 -0.0992004 0.982877 0.155276 -0.0992086 0.188202 0.923667 -0.333796 0.0896137 0.956242 -0.278515 -0.0232897 0.958454 -0.284296 0.331895 0.895732 -0.29582 0.550444 0.792894 -0.2614 0.622081 0.740577 -0.254087 0.837223 0.514858 -0.184332 0.853522 0.489113 -0.179633 0.981924 0.17003 -0.0831599 0.981989 0.169687 -0.0830883 0.186672 0.891192 -0.413438 0.188165 0.89099 -0.413196 0.549026 0.757432 -0.353365 0.551311 0.756177 -0.352494 0.836399 0.495772 -0.233766 0.838687 0.49276 -0.23193 0.981914 0.169822 -0.0837 0.98293 0.165175 -0.0810321 0.18616 -0.694745 0.694748 0.186156 -0.694742 0.694752 0.508579 -0.508583 0.694759 0.508596 -0.508585 0.694746 0.694744 -0.186169 0.694746 0.694741 -0.18617 0.694748 0.694742 0.186169 0.694749 0.694743 0.186171 0.694746 0.50859 0.508592 0.694745 0.508589 0.508576 0.694757 0.186158 0.694742 0.694751 0.186156 0.694746 0.694748 0.258823 -0.965925 0 0.258823 -0.965925 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.965921 -0.258836 0 0.965921 -0.258836 0 0.965921 0.258836 0 0.965921 0.258836 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258822 0.965925 0 0.258822 0.965925 0 0.5102 -0.136717 0.84912 0.373494 -0.373496 0.849119 0.136711 -0.510202 0.84912 0.13671 0.510202 0.84912 0.373495 0.373496 0.849119 0.5102 0.136717 0.84912 0.18616 -0.694745 0.694747 0.186155 -0.694742 0.694752 0.50858 -0.508582 0.694759 0.508596 -0.508584 0.694746 0.694744 -0.186169 0.694746 0.694741 -0.18617 0.694748 0.694742 0.186168 0.694749 0.694743 0.186171 0.694746 0.50859 0.508593 0.694744 0.508588 0.508576 0.694758 0.186158 0.69474 0.694752 0.186156 0.694745 0.694748 0.258823 -0.965925 0 0.258823 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965921 -0.258836 0 0.965921 -0.258836 0 0.965921 0.258836 0 0.965921 0.258836 0 0.707105 0.707109 0 0.707105 0.707109 0 0.258823 0.965925 0 0.258823 0.965925 0 0.5102 -0.136717 0.84912 0.373494 -0.373496 0.849119 0.136711 -0.510202 0.84912 0.136711 0.510202 0.84912 0.373494 0.373496 0.849119 0.5102 0.136717 0.84912 -0.0714498 0.997444 0 -0.227005 0.97387 0.00682489 -0.218761 0.975749 0.00763028 -0.359045 0.93332 0.00052619 -0.434934 0.900463 -1.88372e-05 -0.640663 0.767822 0.000392994 -0.637451 0.770491 -0.000198198 -0.916373 0.400327 0.0001938 -0.91582 0.401588 0 -0.0558503 0.998439 0 -0.0558503 0.998439 0 -0.0558454 -0.998439 0 -0.0558454 -0.998439 0 -0.916373 -0.400327 0 -0.91582 -0.401588 0.000192665 -0.640663 -0.767822 -0.000194767 -0.637451 -0.770491 0.000386112 -0.434934 -0.900463 -1.88372e-05 -0.359045 -0.93332 0.00052619 -0.227005 -0.973867 0.0072238 -0.218763 -0.975757 0.00646128 -0.0714498 -0.997444 0 -0.916379 0.400312 0 -0.524771 0.834332 -0.168837 -0.640858 0.767658 0.00129899 -0.836812 0.54749 -0.0002881 -0.933517 0.35848 -0.00613726 -0.218421 0.975855 0 -0.229719 0.973256 -0.00115257 -0.640656 0.767827 0.00127009 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.936602 -0.350394 0 -0.553996 -0.814079 -0.174252 0.913291 -0.407308 0 0.931121 -0.364679 -0.00481601 0.687787 -0.725899 0.00434251 0.247437 -0.968901 0.00240862 0.462724 -0.886503 0 0.653519 -0.75691 0 -0.916644 -0.399675 -0.00484557 -0.659786 -0.751421 0.00707017 -0.698813 -0.715305 0 -0.470107 -0.882609 0 -0.255501 -0.966806 0.00240874 -0.233095 -0.972454 0 0.224986 -0.974362 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.186162 0.694746 -0.694746 0.186158 0.694743 -0.694749 0.508588 0.508582 -0.694753 0.508572 0.50858 -0.694767 0.694711 0.18617 -0.694779 0.694767 0.186147 -0.694729 0.694762 -0.186184 -0.694724 0.694725 -0.186136 -0.694774 0.508578 -0.508572 -0.694769 0.50858 -0.508589 -0.694755 0.186161 -0.694742 -0.69475 0.186159 -0.694746 -0.694746 0.186162 0.694746 -0.694746 0.186158 0.694743 -0.694749 0.508588 0.508582 -0.694753 0.508572 0.50858 -0.694767 0.694711 0.18617 -0.694779 0.694767 0.186147 -0.694729 0.694762 -0.186184 -0.694724 0.694725 -0.186136 -0.694774 0.508578 -0.508572 -0.694769 0.50858 -0.508589 -0.694755 0.186161 -0.694742 -0.69475 0.186159 -0.694746 -0.694746 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258821 0.965925 0 0.258821 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965924 0.258825 0 0.965924 0.258825 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258821 0.965925 0 0.258821 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965924 0.258825 0 0.965924 0.258825 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.591566 -0.806256 0 0.635337 -0.770297 -0.0546783 0.680875 -0.732116 -0.0203935 0.747145 -0.66452 0.0136898 0.79596 -0.605133 -0.0161848 0.841461 -0.540028 0.0176984 0.859461 -0.511191 0.00328443 0.898805 -0.438336 -0.00322624 0.918687 -0.394603 0.0174117 0.996963 -0.0778732 0 0.99684 -0.0794295 0.000986514 0.988049 -0.154139 3.04842e-05 0.971298 -0.237866 -0.000731497 0.980725 -0.189621 0.0471416 0.953826 -0.29934 -0.0247234 0.970679 0.240129 0.0109274 0.996832 0.0795409 0 0.998392 0.0412627 0.0388709 0.99222 0.124209 -0.00842874 0.976974 0.210799 0.0329548 0.964777 0.263048 0.00320695 0.919178 0.3938 -0.00571073 0.930523 0.365447 0.0239791 0.892458 0.451128 -0.00179921 0.841432 0.540338 0.00517429 0.856618 0.515175 0.0282873 0.746588 0.664026 -0.040931 0.792221 0.608963 0.0393616 0.653381 0.756287 -0.0335281 0.635319 0.770274 -0.0552011 0.561642 0.82738 0 0.899699 -0.436511 0 0.836032 -0.548681 0 0.798191 -0.600906 -0.0424685 0.758466 -0.651713 0 0.618908 -0.785464 0 0.665878 -0.741255 -0.0845369 0.566969 -0.823739 0 0.945001 -0.315954 -0.0845355 0.925975 -0.377586 0 0.981318 -0.192393 0 0.990788 -0.12859 -0.0424744 0.997919 -0.0644828 0 0.588181 -0.80873 0 0.598423 -0.801164 -0.00511507 0.741488 -0.670941 0.00583936 0.749993 -0.661445 0 0.866515 -0.499152 0 0.869667 -0.493631 -0.00273321 0.950442 -0.310889 0.00292389 0.952411 -0.304817 0 0.994675 -0.10306 0 0.994675 -0.10306 0 0.994675 0.10306 0 0.994675 0.10306 0 0.950446 0.31089 0 0.952406 0.304816 0.00310359 0.866511 0.49915 -0.00291233 0.869671 0.493633 0 0.7415 0.670952 0 0.749977 0.661431 0.00655686 0.588171 0.808716 -0.00583271 0.598431 0.801175 0 0.948396 0.317089 0 0.991683 0.128706 0 0.977805 0.191704 -0.0845447 0.997919 0.0644828 0 0.896478 0.434949 -0.0845357 0.925975 0.377586 0 0.836032 0.548681 0 0.798191 0.600906 -0.0424685 0.758466 0.651713 0 0.618908 0.785464 0 0.564939 0.820791 -0.084537 0.668271 0.743918 0 0.598431 0.801175 0 0.588171 0.808716 -0.00583271 0.749977 0.661431 0.00655686 0.7415 0.670952 0 0.869671 0.493633 0 0.866511 0.49915 -0.00291233 0.952406 0.304816 0.0031036 0.950446 0.31089 0 0.994675 0.10306 0 0.994675 0.10306 0 0.994675 -0.10306 0 0.994675 -0.10306 0 0.952411 -0.304817 0 0.950442 -0.310889 0.00292389 0.869667 -0.493631 -0.00273321 0.866515 -0.499152 0 0.749993 -0.661445 0 0.741488 -0.670941 0.00583936 0.598423 -0.801164 -0.00511507 0.588181 -0.80873 0 0.382727 -0.923861 8.02626e-06 0.216995 -0.950717 -0.221474 0.252588 -0.87353 -0.416107 0.107849 -0.994167 0 0.704259 -0.709882 -0.00934992 0.602782 -0.755866 -0.255579 0.575063 -0.806665 -0.13636 0.479883 -0.877332 -1.84108e-05 0.917269 -0.386741 -0.0951253 0.884872 -0.426129 -0.188192 0.869383 -0.483676 -0.101151 0.812141 -0.583443 0.00459148 0.995567 -0.0761978 -0.0551337 0.985318 -0.170717 0.00177489 0.958468 -0.285194 -0.00202648 0.995567 0.0761978 -0.0551338 0.992781 0 -0.119945 0.988625 0.0205939 -0.148987 0.994679 -0.023137 -0.100393 0.90068 0.433742 -0.0253511 0.828439 0.475973 -0.295192 0.927796 0.366753 -0.068465 0.96234 0.271849 2.19839e-05 0.985836 0.167713 -5.38457e-05 0.338799 0.94084 0.00595342 0.490924 0.871195 -0.00350529 0.608613 0.763177 -0.217141 0.627466 0.761467 -0.16265 0.750453 0.660893 0.00645643 0.165527 0.907349 -0.386418 0.216387 0.948053 -0.233177 0.0586283 0.99828 0 0.38273 -0.92386 1.12532e-05 0.216995 -0.950717 -0.221474 0.252586 -0.873534 -0.416099 0.10785 -0.994167 0 0.704259 -0.709881 -0.00934984 0.602782 -0.755865 -0.25558 0.575062 -0.806667 -0.136355 0.479883 -0.877332 -1.53457e-05 0.917269 -0.386741 -0.0951253 0.884872 -0.426129 -0.188192 0.869383 -0.483674 -0.101153 0.81214 -0.583445 0.00459136 0.995567 -0.0761978 -0.0551338 0.985318 -0.170718 0.00177488 0.958468 -0.285194 -0.00202648 0.995567 0.0761983 -0.0551334 0.992781 0 -0.119945 0.988625 0.0205938 -0.148987 0.994679 -0.023137 -0.100393 0.90068 0.433742 -0.02535 0.828439 0.475973 -0.295193 0.927796 0.366753 -0.068465 0.96234 0.271848 2.24702e-05 0.985836 0.167713 -5.35454e-05 0.338798 0.94084 0.00595026 0.490926 0.871194 -0.00350846 0.608613 0.763178 -0.217141 0.627466 0.761467 -0.162648 0.750453 0.660893 0.00645823 0.16553 0.90735 -0.386413 0.216387 0.948053 -0.23318 0.0586258 0.99828 0 0.892416 0.450913 0.0164836 0.331972 -0.943289 -8.78749e-07 0.189699 -0.953684 -0.233454 0.201716 -0.932603 -0.299269 0.0690597 -0.997613 0 0.537533 -0.804478 -0.252732 0.518928 -0.842818 -0.142725 0.420378 -0.907349 -1.2354e-05 0.938252 -0.345573 0.0162309 0.869413 -0.49307 -0.0316554 0.813332 -0.543447 -0.207742 0.773949 -0.632659 -0.0272934 0.65455 -0.755564 0.0262218 0.974181 -0.158827 -0.160451 0.976728 -0.194289 -0.0908547 0.997798 -0.0651383 -0.0125277 0.980164 0.194972 -0.0355621 0.932016 0.253807 -0.258704 0.986991 0.148033 -0.0627291 0.997798 0.0651383 -0.0125277 0.999754 0.0221666 0 0.999754 -0.0221666 0 0.790611 0.560941 -0.245519 0.822478 0.549557 -0.146688 0.734504 0.678604 8.21203e-06 0.35676 0.934196 9.1258e-08 0.444168 0.895944 -1.1524e-05 0.538664 0.80617 -0.244807 0.561266 0.807587 -0.181062 0.666548 0.745463 2.88747e-05 0.260664 0.961592 -0.0859901 0.186723 0.938719 -0.289726 0.0954352 0.995436 0 0.86602 0 -0.50001 0.866045 -6.90689e-05 -0.499965 0.86603 9.57428e-06 -0.499992 0.847749 -0.0818328 -0.524048 0.844838 -0.0841817 -0.528358 0.799151 -0.208334 -0.563875 0.723251 -0.2701 -0.635574 0.798483 -0.223887 -0.558837 0.688757 -0.36356 -0.627246 0.717885 -0.352028 -0.600598 0.616631 -0.450755 -0.645434 0.612961 -0.452664 -0.647591 0.564643 -0.504779 -0.652975 0.526999 -0.525203 -0.668158 0.447558 -0.562373 -0.695291 0.527651 -0.564254 -0.634982 0.15688 -0.712602 -0.683804 0.244964 -0.668611 -0.702106 0.329175 -0.644948 -0.6897 0.319268 -0.653738 -0.686072 0.394875 -0.606056 -0.690485 0.205271 -0.667509 -0.715748 0.0787377 -0.713277 -0.696445 0.0522235 -0.706142 -0.706142 0.866009 5.93388e-05 -0.500029 0.866032 0 -0.499989 0.86603 -9.62369e-06 -0.499992 0.342246 0.653818 -0.674826 0.265588 0.665731 -0.697327 0.180483 0.684956 -0.705876 0.191279 0.686433 -0.701585 0.131459 0.696615 -0.705299 0.0708822 0.703201 -0.707449 0.0666966 0.705532 -0.705532 0.323901 0.652103 -0.685456 0.43216 0.587647 -0.684038 0.432306 0.587498 -0.684075 0.523533 0.540233 -0.658834 0.493207 0.548071 -0.675548 0.583808 0.491953 -0.645872 0.844178 0.0950443 -0.52757 0.606904 0.481592 -0.632247 0.679404 0.348617 -0.64566 0.676567 0.449537 -0.583243 0.730716 0.294782 -0.615757 0.728509 0.302823 -0.614469 0.788609 0.243292 -0.564717 0.804175 0.174541 -0.568189 0.875287 0.0723804 -0.478157 -0.866021 1.02332e-05 -0.500008 -0.866022 1.26924e-05 -0.500006 -0.866023 1.02445e-05 -0.500004 -0.0666897 -0.705533 -0.705533 -0.0708821 -0.703198 -0.707452 -0.139296 -0.695567 -0.704829 -0.190501 -0.683462 -0.704691 -0.230495 -0.686027 -0.690101 -0.265849 -0.666393 -0.696595 -0.352849 -0.627116 -0.694423 -0.337369 -0.643331 -0.687247 -0.432621 -0.587998 -0.683446 -0.465489 -0.580055 -0.668473 -0.517971 -0.533329 -0.668779 -0.590502 -0.493493 -0.638571 -0.588814 -0.497171 -0.637274 -0.643821 -0.417549 -0.641208 -0.6426 -0.419862 -0.640923 -0.851165 -0.0685433 -0.520404 -0.679547 -0.389779 -0.621521 -0.743269 -0.294247 -0.600808 -0.74546 -0.314118 -0.587894 -0.808381 -0.174829 -0.562098 -0.808625 -0.176845 -0.561117 -0.856149 -0.0645276 -0.512685 -0.866029 2.49938e-06 -0.499994 -0.866023 -9.7432e-06 -0.500004 -0.866023 -1.02349e-05 -0.500004 -0.850882 0.0697136 -0.520712 -0.83656 0.0808001 -0.541884 -0.812915 0.194462 -0.548957 -0.786629 0.217201 -0.577961 -0.760135 0.278317 -0.587141 -0.704249 0.345147 -0.620409 -0.706646 0.34391 -0.618366 -0.644563 0.432383 -0.630543 -0.5485 0.485099 -0.681049 -0.628441 0.467331 -0.621822 -0.476404 0.549462 -0.68639 -0.512462 0.544797 -0.663761 -0.420913 0.597236 -0.682746 -0.347058 0.619838 -0.703812 -0.403194 0.620828 -0.672315 -0.0764109 0.70504 -0.70504 -0.0531045 0.719804 -0.692143 -0.151874 0.688536 -0.709121 -0.229999 0.685999 -0.690294 -0.2468 0.674056 -0.696232 -0.315413 0.644899 -0.696146 0.866027 0 -0.499998 0.866002 6.71242e-05 -0.50004 0.866015 9.10367e-08 -0.500017 0.866037 -5.53675e-05 -0.49998 0.866015 0 -0.500017 0.866015 -1.67848e-07 -0.500017 0.405652 -0.60583 -0.68441 0.854395 -0.0553334 -0.516669 0.857197 -0.0814806 -0.508501 0.450739 -0.581539 -0.677234 0.449439 -0.582858 -0.676964 0.518635 -0.536645 -0.665605 0.554853 -0.497841 -0.666553 0.59919 -0.477138 -0.642892 0.660731 -0.405646 -0.631575 0.71096 -0.365492 -0.600792 0.722518 -0.336524 -0.603919 0.787696 -0.220876 -0.575107 0.786768 -0.260518 -0.559578 0.818303 -0.150246 -0.554803 0.0682349 -0.705459 -0.705459 0.0803389 -0.699794 -0.709813 0.185691 -0.68953 -0.700048 0.201519 -0.681808 -0.703226 0.324786 -0.645649 -0.691123 0.296321 -0.673767 -0.676928 0.369403 -0.623506 -0.689044 0.0455547 0.706373 -0.706373 0.0757709 0.711598 -0.698489 0.129614 0.694903 -0.707326 0.223262 0.682637 -0.695817 0.252356 0.66228 -0.70548 0.378233 0.626981 -0.681054 0.381036 0.624297 -0.681956 0.492187 0.549538 -0.6751 0.518401 0.542679 -0.660879 0.60202 0.466275 -0.648197 0.635356 0.445627 -0.630665 0.69498 0.353631 -0.626058 0.84994 0.073416 -0.521739 0.864081 0.0573798 -0.500071 0.823771 0.139433 -0.549509 0.807074 0.20496 -0.553736 0.784344 0.23002 -0.576103 0.755284 0.284024 -0.590658 0.709311 0.344036 -0.615238 -0.0455565 -0.706373 -0.706373 -0.133815 -0.719275 -0.681716 -0.0952118 -0.706617 -0.701162 -0.253602 -0.66595 -0.701568 -0.290622 -0.667856 -0.685206 -0.37725 -0.616908 -0.690729 -0.463114 -0.582799 -0.667736 -0.490863 -0.547686 -0.677565 -0.536752 -0.521669 -0.663143 -0.60655 -0.471013 -0.640502 -0.572651 -0.485917 -0.660269 -0.653895 -0.423311 -0.62708 -0.693706 -0.352623 -0.628036 -0.714133 -0.337884 -0.613065 -0.78959 -0.233485 -0.567479 -0.758901 -0.259259 -0.597373 -0.834997 -0.145774 -0.530594 -0.862224 -0.117021 -0.492824 -0.854951 -0.052972 -0.515997 -0.866022 -1.31593e-05 -0.500006 -0.866032 1.09712e-05 -0.499988 -0.866035 -2.0536e-06 -0.499983 -0.866025 -1.47831e-05 -0.500001 -0.866039 1.88014e-05 -0.499977 -0.866035 2.09117e-06 -0.499983 -0.558446 0.502043 -0.660372 -0.658883 0.416369 -0.626507 -0.66302 0.407658 -0.627869 -0.738796 0.309434 -0.598691 -0.731562 0.343584 -0.58887 -0.769972 0.24902 -0.58748 -0.850843 0.131081 -0.508806 -0.866659 0.179723 -0.465406 -0.854391 0.0553312 -0.516676 -0.556808 0.505186 -0.659357 -0.445979 0.587448 -0.675284 -0.451514 0.586195 -0.672689 -0.0949956 0.703909 -0.703909 -0.0816776 0.712892 -0.696502 -0.201031 0.680009 -0.705105 -0.291043 0.668944 -0.683965 -0.293608 0.666755 -0.685005 -0.368635 0.621927 -0.69088 0.866037 -5.53673e-05 -0.49998 0.866015 0 -0.500017 0.866015 -1.67849e-07 -0.500018 0.866027 0 -0.499998 0.866002 6.71242e-05 -0.50004 0.866015 9.10367e-08 -0.500017 0.0455565 0.706373 -0.706373 0.0691959 0.710416 -0.700372 0.129558 0.694589 -0.707645 0.196079 0.689132 -0.697603 0.251448 0.659603 -0.708307 0.336779 0.64682 -0.684254 0.377744 0.617872 -0.689597 0.405877 0.605339 -0.684711 0.497827 0.557445 -0.664397 0.450749 0.563609 -0.692221 0.555955 0.513023 -0.654004 0.601201 0.465419 -0.649571 0.687411 0.402459 -0.60456 0.698821 0.356734 -0.619992 0.745247 0.297862 -0.596561 0.78915 0.233194 -0.56821 0.75283 0.264515 -0.602726 0.83845 0.147816 -0.524549 0.860286 0.125597 -0.494099 0.854953 0.052973 -0.515993 0.854395 -0.0553332 -0.516669 0.856422 -0.0736082 -0.511003 0.0748261 -0.705124 -0.705125 0.0805754 -0.702116 -0.707489 0.202255 -0.684512 -0.700383 0.223559 -0.684963 -0.693431 0.288642 -0.653857 -0.699398 0.354102 -0.634604 -0.686942 0.369393 -0.623485 -0.689068 0.425611 -0.595501 -0.681347 0.447437 -0.57967 -0.681016 0.520587 -0.545609 -0.656735 0.554892 -0.497887 -0.666486 0.635866 -0.445487 -0.630251 0.660527 -0.405463 -0.631905 0.728044 -0.333298 -0.599053 0.726163 -0.339361 -0.597931 0.790712 -0.202143 -0.577852 0.792698 -0.26466 -0.549168 0.81856 -0.150393 -0.554384 -0.854393 0.0553324 -0.516673 -0.866358 0.179526 -0.466041 -0.840242 0.103377 -0.532265 -0.775074 0.252478 -0.579237 -0.77595 0.246928 -0.580455 -0.721426 0.335677 -0.605694 -0.720325 0.33839 -0.605495 -0.661532 0.406326 -0.630297 -0.633307 0.457175 -0.624431 -0.554555 0.497494 -0.66706 -0.478094 0.579739 -0.659794 -0.451498 0.586173 -0.672719 -0.0943903 0.70395 -0.70395 -0.0816279 0.712394 -0.697016 -0.201056 0.680101 -0.70501 -0.290682 0.669216 -0.683852 -0.2936 0.666734 -0.68503 -0.36864 0.621938 -0.690867 -0.866026 -1.09326e-05 -0.499998 -0.866039 1.88013e-05 -0.499977 -0.866035 2.09118e-06 -0.499983 -0.86602 -1.24313e-05 -0.50001 -0.866031 1.47184e-05 -0.49999 -0.866035 -2.0536e-06 -0.499983 -0.703253 -0.332866 -0.628201 -0.0952429 -0.706682 -0.701091 -0.133884 -0.719667 -0.681289 -0.0455547 -0.706372 -0.706373 -0.64442 -0.440079 -0.625342 -0.602071 -0.466328 -0.648112 -0.55152 -0.51384 -0.65711 -0.490259 -0.546843 -0.678682 -0.458283 -0.584934 -0.6692 -0.377245 -0.616895 -0.690744 -0.29051 -0.667961 -0.685151 -0.309393 -0.6686 -0.676203 -0.220576 -0.676031 -0.703085 -0.860017 -0.0303403 -0.509362 -0.850025 -0.0506457 -0.524301 -0.839481 -0.13911 -0.525281 -0.833727 -0.145043 -0.532786 -0.761523 -0.257081 -0.594972 -0.789672 -0.23354 -0.567343 -0.698547 -0.356532 -0.620417 0.232185 -0.972672 0 0.232185 -0.972672 0 0.646494 -0.762919 0 0.646494 -0.762919 0 0.921386 -0.388649 0 0.921386 -0.388649 0 0.901586 -0.4326 0 0.901586 -0.4326 0 0.999999 0.00110372 0 0.999999 0.00110372 0 0.900628 0.43459 0 0.900628 0.43459 0 0.623121 0.782126 0 0.623121 0.782126 0 0.222364 0.974964 0 0.222364 0.974964 0 0.222364 -0.974964 0 0.222364 -0.974964 0 0.623121 -0.782126 0 0.623121 -0.782126 0 0.900628 -0.43459 0 0.900628 -0.43459 0 0.999999 -0.00110372 0 0.999999 -0.00110372 0 0.901586 0.4326 0 0.901586 0.4326 0 0.921385 0.38865 0 0.921385 0.38865 0 0.646495 0.762918 0 0.646495 0.762918 0 0.232185 0.972672 0 0.232185 0.972672 0 -0.579246 0.815153 0 -0.58025 0.814438 0.000727897 -0.204478 0.978871 -0.000734474 -0.205689 0.978617 0 -0.204478 -0.978871 0 -0.205689 -0.978617 -0.000742017 -0.579245 -0.815153 0.000735343 -0.58025 -0.814438 0 0 -1 0 0 -1 0 0.777101 0.629376 0 0.781515 0.623758 -0.012648 0.784262 0.620429 0 0.808888 0.587963 0 0.834688 0.549858 -0.0308386 0.84296 0.537976 0 0.881836 0.471556 0 0.894696 0.446288 -0.0186069 0.92812 0.368502 0.0529183 0.97088 0.239567 0 0.967688 0.251022 -0.023812 0.945021 0.32701 0 0.917413 0.397937 0 0 1 0 0 1 0 0.945017 -0.327023 0 0.967698 -0.251025 -0.0233701 0.970871 -0.239603 0 0.91606 -0.397646 -0.0520702 0.892627 -0.445256 0.0704617 0.929422 -0.369018 0 0.88172 -0.471774 0 0.835086 -0.55012 0 0.835086 -0.55012 0 0.781578 -0.623808 0 0.784392 -0.619862 -0.0223895 0.776968 -0.62954 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 -0.258817 -0.965926 0 -0.195082 -0.980755 0.00793829 -0.608747 -0.793342 -0.00598346 -0.555569 -0.831471 0 -0.793357 -0.608756 0 -0.831469 -0.555558 -0.00400364 -0.965911 -0.258806 0.00598333 -0.980786 -0.195086 0 -1 0 0 -1 0 0 -0.980786 0.195086 0 -0.980786 0.195086 0 -0.831475 0.555562 0 -0.831475 0.555562 0 -0.555569 0.831471 0 -0.555569 0.831471 0 -0.195088 0.980786 0 -0.195088 0.980786 0 0 1 0 0 1 0 0.258817 0.965926 0 0.195082 0.980755 0.00793829 0.608763 0.793329 -0.00598407 0.555579 0.831464 0 0.793341 0.608777 0 0.831458 0.555573 -0.00400421 0.965911 0.258806 0.00598333 0.980786 0.195086 0 1 0 0 1 0 0 0.965928 -0.258811 0 0.965928 -0.258811 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.630741 0.204956 -0.748437 0.771792 0.22881 -0.593282 0.739025 0.428554 -0.519792 0.758244 0.32842 -0.56321 0.753964 0.323256 -0.571878 0.787476 0.217026 -0.576872 0.729945 0.514723 -0.449712 0.712636 0.580914 -0.393304 0.703018 0.437892 -0.560371 0.717133 0.445851 -0.535665 0.728552 0.433196 -0.530616 0.636069 0.433455 -0.638383 0.704579 0.299097 -0.643513 0.653608 0.279138 -0.703476 0.654963 0.264401 -0.707895 0.646728 0.226662 -0.728263 0.652641 0.16203 -0.740139 0.615105 0.147255 -0.774572 0.688729 0.242644 -0.683211 0.731155 0.175064 -0.659368 0.710514 0.304744 -0.634272 0.723779 0.291817 -0.625289 0.704474 0.375337 -0.60236 0.652187 0.347356 -0.673793 0.680239 0.268963 -0.68186 -0.195093 -0.980785 0 -0.258817 -0.965908 -0.00598361 -0.44229 -0.896872 0 -0.608758 -0.793356 0 -0.707085 -0.707084 -0.00798988 -0.980786 -0.195086 0 -0.965906 -0.258822 -0.00598483 -0.896854 -0.442327 0 -0.793357 -0.608756 0 -1 0 0 -1 0 0 -0.968077 0.250651 0 -0.968456 0.249186 0.000177902 -0.72687 0.686775 -0.000176356 -0.727906 0.685677 0 0.181442 0.983402 0 0.181442 0.983402 0 0.520444 0.853896 0 0.520444 0.853896 0 0.790894 0.611953 0 0.790894 0.611953 0 0.888801 0.458294 0 0.888804 0.458288 0 0.888805 0.458286 -6.67498e-07 0.888803 0.45829 1.6848e-06 0.888802 0.458291 1.53654e-06 0.888789 0.458317 -5.87188e-06 0.975853 0.218429 0 0.975853 0.218429 0 0.988609 -0.150503 0 0.957674 -0.287346 0.017087 0.918345 -0.395781 0 0.826991 -0.562215 0 0.694385 -0.719595 0.00357512 0.514848 -0.855168 0.0601633 0.66974 -0.74249 0.0125128 0.0418061 -0.999126 0 0.126096 -0.992011 0.00374521 0.2019 -0.979349 0.0106098 0.244028 -0.969636 0.0160047 0.29502 -0.955212 0.0230942 0.253049 -0.967334 0.0152318 0.414587 -0.91001 0 0.501851 -0.864954 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.697097 -0.421891 -0.57971 0.729794 -0.514849 -0.449812 0.712218 -0.581098 -0.39379 0.727839 -0.43366 -0.531215 0.717092 -0.445514 -0.536 0.731908 -0.45398 -0.508146 0.759042 -0.325419 -0.563878 0.752833 -0.325717 -0.571972 0.69473 -0.181418 -0.696015 0.636932 -0.130723 -0.759756 0.638283 -0.206247 -0.741658 0.64797 -0.179245 -0.740274 0.650433 -0.262606 -0.712723 0.653243 -0.254444 -0.713114 0.653629 -0.289387 -0.699303 0.769682 -0.226892 -0.596749 0.789587 -0.210401 -0.57644 0.723288 -0.235145 -0.649278 0.710519 -0.304747 -0.634265 0.723776 -0.291829 -0.625287 0.704477 -0.375327 -0.602364 0.660867 -0.351988 -0.662842 0.636325 -0.432703 -0.638638 0.704379 -0.299247 -0.643662 -0.72687 -0.686775 0 -0.727906 -0.685677 -0.000175323 -0.968077 -0.250651 0.000176862 -0.968456 -0.249186 0 -1 0 0 -1 0 0 -0.965924 0.258827 0 -0.980755 0.19508 0.00793976 -0.793343 0.608746 -0.00598234 -0.831465 0.555577 0 -0.608758 0.793356 0 -0.555565 0.831464 -0.00400331 -0.258817 0.965908 0.00598364 -0.195092 0.980785 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.244028 0.969636 0.0160047 0.25304 0.967302 0.017254 0.295078 0.955405 0.0113792 0.201902 0.979348 0.01061 0.126096 0.992011 0.00374528 0.0418044 0.999126 0 0.669788 0.742544 0.00348917 0.694349 0.719558 0.0107846 0.515808 0.856705 0.000242019 0.501851 0.864954 0 0.414587 0.91001 0 0.957674 0.287346 0.017087 0.918345 0.395781 0 0.826991 0.562216 0 0.975853 -0.218429 0 0.975853 -0.218429 0 0.988609 0.150503 0 0.888801 -0.458293 -4.7982e-07 0.888803 -0.45829 0 0.888802 -0.458292 0 0.888803 -0.45829 -7.17416e-07 0.888808 -0.45828 7.41749e-06 0.8888 -0.458295 -9.58006e-07 0.790227 -0.612814 0 0.790894 -0.611953 0.000214748 0.517634 -0.855602 -0.000217997 0.520443 -0.853897 0.00043413 0.179289 -0.983796 -0.000429725 0.181444 -0.983401 0 -0.965279 -0.0362553 0.258693 -0.980035 -0.195003 0.0387887 -0.980035 -0.165315 0.11046 -0.980035 -0.165317 0.110461 -0.980035 -0.110461 0.165317 -0.980035 -0.110461 0.165317 -0.980035 -0.0387887 0.195004 -0.601359 -0.155873 0.783627 -0.787597 -0.120213 0.604351 -0.827292 -0.11907 0.549009 -0.826436 -0.312803 0.468143 -0.826437 -0.312802 0.468142 -0.826436 -0.468142 0.312804 -0.826435 -0.468144 0.312804 -0.191476 -0.191482 0.962638 -0.435433 -0.175626 0.882923 -0.980035 -0.195004 0.0387886 -0.893423 -0.440585 0.0876377 -0.827291 -0.54901 0.11907 -0.787597 -0.604351 0.120213 -0.601353 -0.783631 0.155874 -0.548942 -0.171775 0.81802 -0.548153 -0.464666 0.695423 -0.548154 -0.464666 0.695422 -0.548155 -0.695422 0.464667 -0.548151 -0.695424 0.464667 -0.548941 -0.818021 0.171774 -0.435433 -0.882923 0.175625 -0.191479 -0.191481 0.962637 -0.191478 -0.54529 0.816085 -0.191475 -0.545291 0.816085 -0.191475 -0.816086 0.545291 -0.191476 -0.816085 0.545291 -0.191475 -0.962638 0.191481 -0.19147 -0.962639 0.19148 -0.790815 0.60682 0.079889 -0.256749 0.95821 0.126149 -0.605495 0.789041 0.103878 -0.965353 0.0340597 0.258714 -0.965353 0.0998591 0.241083 -0.965354 0.0998592 0.241081 -0.965354 0.158853 0.207021 -0.965354 0.158853 0.207021 -0.965354 0.207021 0.158853 -0.965354 0.207021 0.158853 -0.965354 0.241081 0.0998593 -0.965354 0.241081 0.0998591 -0.965354 0.258711 0.0340599 -0.965354 0.258713 0.0340607 -0.705627 0.698375 0.119847 -0.704078 0.656068 0.271753 -0.704079 0.656067 0.271752 -0.704078 0.563378 0.432296 -0.704078 0.563378 0.432296 -0.704078 0.432296 0.563378 -0.704075 0.432296 0.563381 -0.704075 0.271752 0.656071 -0.704078 0.271752 0.656068 -0.965354 0.03406 0.258713 -0.790815 0.0798889 0.60682 -0.705627 0.119847 0.698375 -0.605506 0.103879 0.789032 -0.439257 0.117261 0.890676 -0.256744 0.958211 0.126151 -0.256745 0.89291 0.369856 -0.256747 0.89291 0.369855 -0.256748 0.766758 0.588355 -0.256747 0.766758 0.588356 -0.256747 0.588354 0.76676 -0.256753 0.588355 0.766757 -0.256753 0.369855 0.892908 -0.256752 0.369854 0.892909 -0.257347 0.145678 0.955275 -0.193479 0.12806 0.972711 0.193496 0.778359 0.597258 0.827291 0.11907 0.549009 0.965298 0.0362367 0.258626 0.980054 0.0387704 0.194912 0.548897 0.171777 0.818049 0.60129 0.155884 0.783678 0.787597 0.120213 0.604351 0.980054 0.110408 0.165238 0.980054 0.11041 0.165239 0.826435 0.312804 0.468144 0.826437 0.312802 0.468142 0.548109 0.464682 0.695447 0.54811 0.464682 0.695446 0.191498 0.19148 0.962634 0.191494 0.191481 0.962634 0.435433 0.175626 0.882923 0.191493 0.545288 0.816083 0.46525 0.538864 0.702259 0.194707 0.433822 0.879709 0.194697 0.879711 0.433822 0.385818 0.767093 0.512556 0.548107 0.695448 0.464684 0.548111 0.695445 0.464683 0.826435 0.468143 0.312805 0.826436 0.468142 0.312804 0.980054 0.165237 0.110409 0.980054 0.165239 0.110409 0.980054 0.194912 0.0387704 0.980054 0.194914 0.0387704 0.826436 0.552213 0.109841 0.826439 0.552208 0.109841 0.548108 0.820336 0.163175 0.548105 0.820338 0.163175 0.191487 0.962636 0.19148 0.191494 0.962635 0.191481 0.254181 -0.948573 0.188684 0.700194 -0.700234 0.139285 0.964655 -0.0514094 0.258453 0.964655 -0.146402 0.219105 0.964655 -0.146402 0.219106 0.964655 -0.219106 0.146402 0.964655 -0.219106 0.146402 0.964655 -0.258454 0.0514097 0.964655 -0.258454 0.0514097 0.700193 -0.700235 0.139286 0.700193 -0.593631 0.396651 0.700194 -0.59363 0.396651 0.700194 -0.396651 0.59363 0.700193 -0.396651 0.593631 0.964655 -0.0514093 0.258454 0.787597 -0.120212 0.604351 0.701904 -0.156977 0.694759 0.60129 -0.155884 0.783678 0.435434 -0.175625 0.882923 0.254185 -0.948572 0.188682 0.254185 -0.804161 0.537322 0.254183 -0.804161 0.537323 0.254183 -0.537323 0.804161 0.254185 -0.537323 0.804161 0.254803 -0.201459 0.945775 0.191494 -0.191481 0.962635 0.193496 0.77836 0.597257 0.827292 0.11907 0.549009 0.965298 0.0362367 0.258626 0.980054 0.0387705 0.194912 0.548897 0.171777 0.818049 0.60129 0.155884 0.783678 0.787597 0.120213 0.604351 0.980054 0.110409 0.165239 0.980054 0.110409 0.165239 0.826436 0.312803 0.468143 0.826437 0.312802 0.468142 0.548109 0.464682 0.695447 0.54811 0.464682 0.695446 0.191497 0.191481 0.962634 0.191494 0.191481 0.962634 0.435433 0.175626 0.882923 0.191493 0.545288 0.816083 0.46525 0.538864 0.702259 0.194704 0.433821 0.87971 0.194702 0.879709 0.433824 0.385817 0.767094 0.512555 0.548107 0.695448 0.464683 0.548111 0.695446 0.464683 0.826435 0.468144 0.312804 0.826436 0.468142 0.312804 0.980054 0.165238 0.110409 0.980054 0.165239 0.110409 0.980054 0.194912 0.0387704 0.980054 0.194912 0.0387704 0.826436 0.552213 0.109842 0.826437 0.552211 0.109842 0.548108 0.820336 0.163175 0.548109 0.820336 0.163175 0.191493 0.962635 0.19148 0.191488 0.962636 0.19148 0.787597 -0.604351 0.120212 0.964655 -0.0514094 0.258453 0.964655 -0.146401 0.219106 0.964655 -0.146401 0.219106 0.964655 -0.219105 0.146401 0.964655 -0.219105 0.146401 0.964655 -0.258453 0.0514091 0.964655 -0.258454 0.0514097 0.254177 -0.948574 0.188684 0.60129 -0.783678 0.155884 0.701904 -0.694759 0.156977 0.700193 -0.593631 0.396651 0.700194 -0.59363 0.396651 0.700194 -0.396651 0.593631 0.700193 -0.396651 0.593631 0.964655 -0.0514093 0.258454 0.787597 -0.120212 0.604351 0.701904 -0.156977 0.694759 0.60129 -0.155884 0.783678 0.435434 -0.175625 0.882923 0.254185 -0.948572 0.188681 0.254185 -0.804161 0.537322 0.254183 -0.804161 0.537323 0.254183 -0.537322 0.804162 0.254187 -0.537323 0.80416 0.254804 -0.201459 0.945774 0.191494 -0.19148 0.962635 -0.827291 -0.11907 0.549009 -0.965279 -0.0362553 0.258693 -0.980035 -0.0387887 0.195004 -0.548942 -0.171775 0.81802 -0.601359 -0.155873 0.783627 -0.787597 -0.120213 0.604351 -0.19148 -0.191481 0.962637 -0.191476 -0.191482 0.962638 -0.435433 -0.175626 0.882923 -0.980035 -0.11046 0.165316 -0.980035 -0.110461 0.165317 -0.826435 -0.312804 0.468144 -0.826438 -0.312801 0.468141 -0.548153 -0.464666 0.695423 -0.548154 -0.464665 0.695423 -0.191481 -0.545289 0.816085 -0.191475 -0.545291 0.816085 -0.980035 -0.165317 0.110461 -0.980035 -0.165315 0.11046 -0.826438 -0.46814 0.312802 -0.826435 -0.468144 0.312804 -0.548154 -0.695422 0.464666 -0.548151 -0.695425 0.464667 -0.191475 -0.816086 0.54529 -0.191481 -0.816084 0.54529 -0.980035 -0.195003 0.0387887 -0.980035 -0.195003 0.0387887 -0.826436 -0.552213 0.109842 -0.826435 -0.552214 0.109842 -0.548153 -0.820308 0.16317 -0.548157 -0.820305 0.16317 -0.19148 -0.962637 0.191482 -0.191465 -0.962641 0.19148 -0.256745 0.958211 0.126151 -0.704078 0.704047 0.0926892 -0.965353 0.0340598 0.258713 -0.965353 0.0998591 0.241083 -0.965354 0.0998592 0.241081 -0.965354 0.158853 0.207021 -0.965354 0.158853 0.207021 -0.965354 0.207021 0.158853 -0.965354 0.207021 0.158853 -0.965354 0.241081 0.0998588 -0.965354 0.241082 0.0998595 -0.965354 0.258712 0.03406 -0.965354 0.258713 0.0340602 -0.704078 0.704048 0.0926897 -0.704078 0.656068 0.271752 -0.704077 0.656069 0.271753 -0.704076 0.563379 0.432297 -0.704078 0.563379 0.432295 -0.704078 0.432295 0.563378 -0.704077 0.432295 0.563379 -0.704076 0.271752 0.65607 -0.704078 0.271752 0.656067 -0.965354 0.03406 0.258713 -0.790815 0.079889 0.60682 -0.705627 0.119847 0.698375 -0.605506 0.103879 0.789032 -0.439257 0.117261 0.890676 -0.256748 0.95821 0.126149 -0.256749 0.892909 0.369855 -0.256747 0.892909 0.369856 -0.256749 0.766759 0.588354 -0.256747 0.766759 0.588355 -0.256747 0.588354 0.76676 -0.256753 0.588355 0.766757 -0.256753 0.369855 0.892908 -0.25675 0.369854 0.89291 -0.257346 0.145678 0.955275 -0.193479 0.12806 0.972711 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965928 0.258811 0 0.965928 0.258811 0 1 0 0 1 0 0 0.980786 -0.195086 0 0.980786 -0.195086 0 0.831465 -0.555577 0 0.831465 -0.555577 0 0.555569 -0.831471 0 0.555569 -0.831471 0 0.195092 -0.980785 0 0.195092 -0.980785 0 0 -1 0 0 -1 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965924 -0.258827 0 -0.965924 -0.258827 0 -1 0 0 -1 0 0 -0.965924 0.258827 0 -0.965924 0.258827 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -1 0 0 -1 0 0 -0.195091 0.980785 0 -0.195091 0.980785 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.980787 0.195084 0 -0.980787 0.195084 0 0 1 0 0 1 0 0.707105 0.707108 0 0.258821 0.965925 0 0.258821 0.965925 0 0.995694 0.0927034 0 0.962675 0.270028 0.0184945 0.965801 0.258786 0.0160413 0.901524 0.432729 0 0.707105 0.707108 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0 -1 0 0 -1 0 -0.62386 -0.781536 0 -0.768204 -0.639364 0.0328102 -0.707053 -0.707055 0.0122395 -0.837744 -0.546064 0 -0.965929 -0.258808 0 -0.971397 -0.237373 0.00654285 -0.876894 -0.480684 0 -0.62386 -0.781536 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 -0.965924 0.258827 0 -0.965924 0.258827 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0 1 0 0 1 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965928 0.258811 0 0.965928 0.258811 0 1 0 0 1 0 0 0.980786 -0.195086 0 0.980786 -0.195086 0 0.831464 -0.555578 0 0.831464 -0.555578 0 0.555569 -0.83147 0 0.555569 -0.83147 0 0.195092 -0.980785 0 0.195092 -0.980785 0 0 -1 0 0 -1 0 -0.195092 -0.980785 0 -0.195092 -0.980785 0 -0.555569 -0.83147 0 -0.555569 -0.83147 0 -0.831475 -0.555562 0 -0.831475 -0.555562 0 -0.980782 -0.195107 0 -0.980782 -0.195107 0 0 1 0 0 1 0 0.980787 0.195084 0 0.980787 0.195084 0 0.831464 0.555579 0 0.831464 0.555579 0 0.555575 0.831466 0 0.555575 0.831466 0 0.195091 0.980785 0 0.195091 0.980785 0 0.927123 -0.372494 0.0411295 0.962675 -0.270028 0.0184945 0.995694 -0.0927034 0 0.965823 -0.258792 0.0145824 0.793265 -0.608702 -0.0145799 0.831463 -0.55558 0 0.608763 -0.793352 0 0.55555 -0.831426 -0.00975519 0.258794 -0.965823 0.0145812 0.195091 -0.980785 0 0 -1 0 0 -1 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -1 0 0 -1 0 0 -0.980787 0.195084 0 -0.720561 0.693392 0 -0.780971 0.624565 0.00191846 -0.858007 0.513401 0.0156171 -0.831454 0.555555 0.00652923 -0.909612 0.41546 0 -0.980787 0.195084 0 -0.72056 0.693392 0 -0.555567 0.831472 0 -0.555567 0.831472 0 -0.195091 0.980785 0 -0.195091 0.980785 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.113226 0.993569 0 -0.113226 0.993569 0 0 1 0 0 1 0 0.113226 0.993569 0 0.113226 0.993569 0 0.240505 -0.970648 0 0.240505 -0.970648 0 0.665875 -0.746063 0 0.665875 -0.746063 0 0.93717 -0.348874 0 0.93717 -0.348874 0 0.991638 0.129054 0 0.991638 0.129054 0 0.816663 0.577115 0 0.816663 0.577115 0 0.45273 0.891648 0 0.45273 0.891648 0 0 -1 0 0 -1 0 -0.452738 0.891644 0 -0.452738 0.891644 0 -0.816663 0.577115 0 -0.816663 0.577115 0 -0.991638 0.129054 0 -0.991638 0.129054 0 -0.937176 -0.348858 0 -0.937176 -0.348858 0 -0.665875 -0.746063 0 -0.665875 -0.746063 0 -0.240505 -0.970648 0 -0.240505 -0.970648 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.103389 -0.991434 0.0798142 -0.119008 -0.990379 0.0706132 -0.119784 -0.990198 0.0718282 -0.126188 -0.990195 0.0599202 -0.128013 -0.989832 0.0620052 -0.132184 -0.989781 0.0534844 -0.133 -0.989626 0.0543205 -0.22913 -0.865478 0.445474 -0.291774 -0.925865 0.240087 -0.0540145 -0.996988 0.0556524 -0.124096 -0.990853 0.0530106 -0.102692 -0.991726 0.0770378 -0.292242 -0.926255 0.238003 -0.315571 -0.919977 0.232501 -0.33712 -0.919487 0.202221 -0.347552 -0.912086 0.217502 -0.369568 -0.912245 0.176718 -0.374975 -0.908732 0.1833 -0.386621 -0.908781 0.156974 -0.389225 -0.907178 0.159789 -0.211897 -0.963526 -0.163457 -0.395306 -0.907212 0.143871 -0.59636 -0.798357 0.083552 -0.515258 -0.84732 0.128676 -0.513323 -0.855423 0.0689216 -0.597246 -0.797525 0.0851526 -0.648332 -0.752836 0.113593 -0.674709 -0.731045 0.101693 -0.700287 -0.699674 0.141612 -0.720981 -0.684197 0.109822 -0.740249 -0.662006 0.117385 -0.784532 -0.611597 0.102266 -0.77916 -0.613623 0.127973 -0.84745 -0.518689 0.113096 -0.844241 -0.520849 0.126388 -0.885526 -0.448597 0.120853 -0.890306 -0.429411 0.151529 -0.904867 -0.406974 0.124854 -0.926951 -0.35454 0.122736 -0.926165 -0.355453 0.12598 -0.950797 -0.283752 0.124374 -0.950328 -0.284403 0.126459 -0.376281 0.907396 -0.187205 -0.0494845 0.960558 0.273641 -0.147273 0.986043 0.0776477 -0.265753 0.963495 0.0324426 -0.333647 0.936995 0.103537 -0.231827 0.972259 0.0311226 -0.42064 0.702833 0.573662 -0.990123 -0.0329578 0.136273 -0.993394 -0.0186307 0.113227 -0.947249 0.291569 0.13307 -0.90969 0.415188 0.00908586 -0.392633 0.876298 0.279178 -0.209372 0.977235 0.0342814 -0.890114 0.453024 0.0496604 -0.819379 0.562771 0.109122 -0.696977 0.711766 0.0872505 -0.708234 0.702562 0.0693658 -0.585986 0.80634 0.080227 -0.603672 0.793512 0.0769277 -0.502707 0.861059 0.0765646 -0.895076 0.2987 0.331085 -0.648008 0.721203 0.244853 -0.800424 0.512681 0.31061 -0.833931 0.457932 0.307991 -0.75064 0.597171 0.282713 -0.935476 0.131312 0.328089 -0.885912 0.291537 0.360786 -0.941259 -0.0350253 0.335864 -0.94126 -0.0350741 0.335856 -0.925254 -0.154226 0.346582 -0.117187 0.992492 0.0350157 -0.197353 0.977568 0.0735753 -0.140684 0.988615 0.0533616 -0.200734 0.977577 0.0636291 -0.417975 0.892946 0.167165 -0.484534 0.855697 0.181684 -0.660881 0.706326 0.253652 -0.957509 -0.0331966 0.286485 -0.957589 -0.0350619 0.285997 -0.915909 0.293412 0.273897 -0.916407 0.291938 0.273806 -0.850466 0.4605 0.254259 -0.821096 0.512964 0.250339 -0.31464 0.944539 0.0940615 -0.485212 0.862293 0.144984 -0.495242 0.855746 0.149782 -0.579935 0.796009 0.173336 -0.678117 0.706473 0.202616 -0.677443 0.707133 0.202565 -0.790042 0.565768 0.236094 -0.481075 0.87668 3.35056e-05 -0.237742 0.945086 0.224257 -0.159209 0.987196 0.00983087 -0.234381 0.953635 0.188802 -0.117788 0.930648 0.346441 -0.0884277 0.992447 0.0850216 -0.106386 0.991087 0.0801725 -0.107192 0.991854 0.0688111 -0.119918 0.990228 0.0711953 -0.125843 0.990175 0.0609625 -0.128627 0.989807 0.0611288 -0.131815 0.989807 0.053907 -0.133168 0.989627 0.0538909 -0.389799 0.907192 0.158304 -0.385981 0.908798 0.158446 -0.37638 0.908777 0.180172 -0.367934 0.912302 0.179805 -0.350887 0.912235 0.211438 -0.332987 0.919677 0.208121 -0.314917 0.919967 0.233426 -0.329823 0.915527 0.230275 -0.395304 0.907212 0.143877 -0.211897 0.963528 -0.163445 -0.926726 0.354005 0.125938 -0.950602 0.284404 0.124378 -0.950589 0.283533 0.126449 -0.880355 0.443135 0.169137 -0.904967 0.406745 0.12487 -0.926639 0.355329 0.122805 -0.893883 0.432068 0.119543 -0.846836 0.516688 0.126102 -0.845227 0.522169 0.113719 -0.784566 0.606905 0.126974 -0.779501 0.617669 0.104222 -0.740383 0.661842 0.117464 -0.7211 0.684102 0.109631 -0.680892 0.712456 0.169685 -0.69619 0.711992 0.0915768 -0.619308 0.774958 0.126087 -0.596548 0.798207 0.0836409 -0.530086 0.839277 0.120925 -0.499003 0.863037 0.0785062 -0.961836 0.242967 0.125853 -0.957449 0.0350625 0.286465 -0.957649 0.0331971 0.286018 -0.916341 -0.291942 0.274024 -0.932343 0.093463 0.349288 -0.940171 0.0350716 0.338894 -0.891009 -0.291758 0.347822 -0.914676 -0.221638 0.338 -0.802482 -0.512793 0.305068 -0.803828 -0.510683 0.305064 -0.662828 -0.706443 0.248189 -0.63781 -0.730463 0.244178 -0.147106 -0.988376 0.0383769 -0.417973 -0.892947 0.167164 -0.314635 -0.944541 0.0940606 -0.196969 -0.977559 0.0747102 -0.197356 -0.977567 0.0735757 -0.117191 -0.992492 0.035017 -0.484534 -0.855697 0.181683 -0.495242 -0.855746 0.149782 -0.485212 -0.862293 0.144985 -0.915974 -0.293413 0.273679 -0.850464 -0.460503 0.254259 -0.821097 -0.512962 0.250339 -0.790044 -0.565764 0.236095 -0.678072 -0.706477 0.202752 -0.677483 -0.707136 0.202427 -0.579935 -0.796009 0.173337 -0.43209 -0.891949 0.133135 -0.12217 -0.987852 0.0960382 -0.196402 -0.980438 0.0129466 -0.643408 0.712163 0.280802 -0.844678 0.414595 0.338571 -0.817359 0.49422 0.296094 -0.539476 0.790806 0.28912 -0.91299 0.270107 0.305764 -0.888974 0.292234 0.352597 -0.922996 0.168977 0.345724 -0.900418 0.340542 0.2707 -0.894072 0.351613 0.277497 -0.869457 0.413487 0.270321 -0.850881 0.444294 0.280365 -0.728333 0.62927 0.271202 -0.728485 0.629168 0.27103 -0.736298 0.6205 0.2699 -0.796855 0.543108 0.26468 -0.771514 0.569754 0.283101 -0.827582 0.492063 0.270151 -0.635562 0.732769 0.243127 -0.530675 0.82502 0.194229 -0.559516 0.79643 0.229437 -0.812536 0.407807 0.416508 -0.895465 0.319731 0.3097 -0.888346 0.324132 0.325238 -0.909923 0.276364 0.309295 -0.930928 0.248835 0.267311 -0.921821 0.272676 0.27549 -0.868621 0.325109 0.373901 -0.853094 0.400197 0.334773 -0.854791 0.408108 0.320594 -0.810988 0.476765 0.339106 -0.791343 0.518088 0.324593 -0.762169 0.548314 0.344167 -0.722848 0.614296 0.316434 -0.692963 0.636975 0.337736 -0.639236 0.706457 0.303802 -0.630577 0.711545 0.309962 -0.553522 0.773114 0.309691 -0.441991 0.828722 0.343311 -0.469345 0.833659 0.29108 -0.454644 0.840805 0.293845 -0.492253 0.836978 0.239072 -0.548913 0.796676 0.252988 -0.540342 0.800464 0.259402 -0.619311 0.742257 0.255946 -0.623636 0.74843 0.225679 -0.702888 0.668588 0.242774 -0.0528494 -0.998603 0 -0.100391 -0.994844 -0.0144203 -0.150614 -0.988592 -0.00110022 -0.20899 -0.977918 0.000215716 -0.224506 -0.974472 -0.000604161 -0.229981 -0.973195 -0.000255527 -0.266277 -0.963896 0.000566217 -0.334519 -0.942346 -0.00903748 -0.381435 -0.924007 -0.0267848 -0.403936 -0.91462 -0.017465 -0.533655 -0.845565 0.0152387 -0.509867 -0.860232 0.00611892 -0.666358 -0.745544 -0.0114655 -0.692463 -0.72139 0.00958988 -0.782237 -0.622981 -0.000424923 -0.821739 -0.569863 0.00135716 -0.875078 -0.483475 -0.0221707 -0.929453 -0.367374 0.0339615 -0.969545 0.244915 0 -0.994612 0.10346 -0.00658193 -0.998641 0.0173486 0.0491385 -0.992039 -0.125935 1.56234e-06 -0.961044 -0.276394 3.42893e-06 -0.460069 0.887883 0 -0.776487 0.62967 0.0241506 -0.474106 0.880417 0.00946129 -0.540775 0.841131 -0.00778571 -0.581202 0.813533 0.0192065 -0.597168 0.802084 0.00712597 -0.656886 0.75388 -0.0129194 -0.649474 0.760384 -2.78799e-07 -0.710199 0.704001 1.65565e-06 -0.709658 0.704546 0.000547665 -0.750098 0.661326 -0.000531786 -0.783074 0.621767 0.0141881 -0.817919 0.575252 -0.00968021 -0.846646 0.531721 0.0215103 -0.843355 0.536654 0.0274815 -0.864432 0.502698 -0.00724062 -0.889649 0.456604 0.00614272 -0.893292 0.449476 -3.20106e-05 -0.91032 0.413905 -3.47019e-05 -0.911789 0.410655 -0.00201647 -0.932676 0.360682 0.00487621 -0.936501 0.350502 -0.0107414 -0.957454 0.288457 0.00864548 -0.959499 0.281711 0 -0.399889 0.916564 0 -0.348406 0.937338 0.00340423 -0.270474 0.962575 0.0170916 -0.214643 0.976013 0.0364388 -0.107802 0.994172 0 -0.647772 -0.71825 0.253986 -0.547354 -0.79575 0.259204 -0.886148 -0.315873 0.339067 -0.895321 -0.293267 0.335252 -0.926413 -0.255132 0.276887 -0.807399 -0.449286 0.382425 -0.866812 -0.382628 0.319739 -0.848766 -0.383178 0.364377 -0.559386 -0.796537 0.229383 -0.651565 -0.716034 0.250515 -0.530724 -0.824936 0.194455 -0.539192 -0.80402 0.250646 -0.492262 -0.83697 0.239078 -0.460726 -0.840451 0.285261 -0.729402 -0.632653 0.260236 -0.661974 -0.703807 0.257772 -0.626235 -0.734912 0.260257 -0.852018 -0.452745 0.262846 -0.771305 -0.569988 0.2832 -0.796862 -0.543144 0.264588 -0.736188 -0.620622 0.269918 -0.702038 -0.657112 0.274493 -0.923679 -0.273461 0.268397 -0.900283 -0.340843 0.270771 -0.894077 -0.351644 0.27744 -0.869265 -0.413861 0.270367 -0.822333 -0.487116 0.294085 -0.890324 -0.291077 0.350138 -0.919721 -0.263182 0.291289 -0.853135 -0.400404 0.334421 -0.846532 -0.422022 0.32447 -0.814489 -0.471699 0.337798 -0.791052 -0.517035 0.326974 -0.774607 -0.532897 0.340594 -0.722052 -0.612338 0.321997 -0.711768 -0.619346 0.331356 -0.637328 -0.703875 0.313644 -0.646558 -0.699225 0.305037 -0.531591 -0.785448 0.31699 -0.569491 -0.772835 0.280012 -0.472202 -0.829748 0.297562 -0.460638 -0.82705 0.322181 -0.401447 -0.863145 0.306302 -0.394199 -0.855732 0.335158 -0.969545 -0.244915 0 -0.952998 0.302726 0.012349 -0.990089 0.139057 -0.0196605 -0.998467 -0.0187258 0.0520869 -0.998477 -0.0289356 0.0469654 -0.988128 -0.153575 -0.00416783 -0.88792 0.45609 0.0598317 -0.909609 0.41515 0.0161611 -0.79923 0.601025 -0.000393309 -0.699642 0.714487 0.00311123 -0.686838 0.726771 -0.0076127 -0.587881 0.808947 -0.000282035 -0.509224 0.860632 0.0019735 -0.513544 0.858063 -2.09772e-05 -0.408891 0.912583 1.54458e-05 -0.371127 0.928555 -0.00705773 -0.33545 0.942058 0.000618834 -0.265893 0.964002 -0.000515897 -0.231934 0.972711 -0.00625439 -0.209483 0.977754 -0.010651 -0.148301 0.988548 -0.0279091 -0.147663 0.988654 -0.0275628 -0.0514482 0.998676 0 -0.957416 -0.288713 0 -0.962701 -0.268975 0.029318 -0.930921 -0.361805 -0.0498389 -0.944235 -0.327916 0.0298698 -0.918503 -0.395391 -0.00432303 -0.91024 -0.414076 0.00198764 -0.906319 -0.422593 -2.84287e-05 -0.889434 -0.457064 -3.25029e-05 -0.884452 -0.466522 -0.010104 -0.846198 -0.532693 0.0136827 -0.580792 -0.813846 0.0183263 -0.834771 -0.550505 -0.0100514 -0.769091 -0.638994 0.013624 -0.774219 -0.632917 -0.000944685 -0.727779 -0.685812 6.22541e-05 -0.710325 -0.703871 0.00194615 -0.715641 -0.698445 0.00570396 -0.657224 -0.753613 -0.0111159 -0.657062 -0.753752 -0.0112901 -0.590206 -0.807207 0.00858516 -0.441714 -0.897156 0 -0.475346 -0.8797 0.0131715 -0.491187 -0.871053 0.00108802 -0.542349 -0.840153 -0.000898501 -0.318303 -0.947989 0 -0.0225337 -0.999746 0 -0.214762 -0.976554 0.0147931 -0.110486 -0.990368 0.0834472 -0.180175 -0.982494 0.0473485 -0.914605 -0.207639 0.346963 -0.909003 -0.246497 0.336086 -0.760385 -0.587022 0.277885 -0.796944 -0.519681 0.307915 -0.871646 -0.362491 0.3299 -0.493245 -0.85183 0.176335 -0.561091 -0.799365 0.214923 -0.671649 -0.694744 0.25733 -0.103167 -0.993842 0.0404393 -0.224588 -0.972013 0.0689294 -0.167257 -0.984253 0.057196 -0.281388 -0.953382 0.109013 -0.405668 -0.900405 0.157176 -0.926481 -0.246422 0.284445 -0.925484 -0.251819 0.28296 -0.773799 -0.586879 0.238342 -0.772484 -0.589013 0.237344 -0.501103 -0.851704 0.153288 -0.508205 -0.846675 0.1577 -0.169823 -0.984187 0.0503696 -0.176373 -0.982838 0.0540518 -0.241505 -0.947507 -0.209535 -0.497504 -0.845482 0.194035 -0.584227 -0.807947 0.0768106 -0.763804 -0.637016 0.103993 -0.788085 -0.58885 0.179381 -0.869216 -0.480655 0.115909 -0.959445 -0.249887 0.130466 -0.959109 -0.250619 0.131527 -0.988653 -0.0705592 0.132616 -0.988654 -0.0704118 0.132689 -0.988786 -0.0685424 0.132678 -0.988816 -0.0677412 0.132868 -0.988848 -0.067432 0.132784 -0.0168578 0.998058 0.0599619 -0.0584114 0.998259 0.0082508 -0.0675941 0.997675 0.00873258 -0.0523442 0.998567 0.0111416 -0.0825937 0.99638 0.0201172 -0.139415 0.979098 0.148088 -0.302388 0.952901 0.023244 -0.572699 0.811475 0.116293 -0.566958 0.820414 0.0740274 -0.848591 0.516188 0.115945 -0.849993 0.511424 0.126324 -0.983027 0.138368 0.120467 -0.982515 0.129717 0.133555 -0.187018 0.958587 0.214792 -0.153747 0.949943 0.271974 -0.0952522 0.994646 0.0400674 -0.0744394 0.997141 0.0129487 -0.0424602 0.998946 0.0174357 -0.538364 0.826777 0.16311 -0.544416 0.822852 0.162867 -0.818731 0.518247 0.247184 -0.821582 0.514006 0.246577 -0.948882 0.133585 0.285968 -0.94945 0.130791 0.285374 -0.182723 0.981687 0.0538747 -0.194708 0.978939 0.0613818 -0.212315 0.974012 0.0788834 -0.0308799 0.999484 0.00884473 -0.931493 0.102553 0.349004 -0.59987 0.775548 0.196676 -0.420393 0.905938 0.0504598 -0.301571 0.95124 0.0647862 -0.560328 0.815255 0.146259 -0.687318 0.706159 0.1701 -0.942044 0.0613754 0.329828 -0.913741 0.221044 0.340905 -0.823974 0.477502 0.305056 -0.876855 0.398343 0.269163 -0.787963 0.556546 0.263382 -0.307569 0.950271 0.0488596 -0.178628 0.981684 0.0662433 -0.610488 0.773913 0.168413 -0.531216 0.826832 0.184819 -0.837813 0.475473 0.268319 -0.80804 0.518344 0.279983 -0.936277 0.138935 0.322618 -0.938313 0.133629 0.318923 -0.464421 -0.87783 0.117164 -0.315588 -0.948507 0.0271609 -0.365215 -0.930332 0.0331587 -0.321975 -0.946411 0.0252462 -0.927577 -0.0801655 0.364931 -0.933594 -0.113753 0.339798 -0.837082 -0.475604 0.27036 -0.857212 -0.40455 0.318632 -0.909787 -0.239223 0.339205 -0.575148 -0.804137 0.150228 -0.619973 -0.768854 0.156512 -0.614922 -0.772984 0.1561 -0.697294 -0.678758 0.230367 -0.779061 -0.570323 0.260376 -0.936729 -0.109136 0.332609 -0.936978 -0.132391 0.323335 -0.830865 -0.476607 0.287245 -0.815529 -0.51509 0.263808 -0.59747 -0.775811 0.202847 -0.546316 -0.82305 0.155331 -0.290815 -0.952274 0.0927363 -0.195766 -0.980315 0.0256644 -0.185085 -0.980989 0.0583482 -0.949253 -0.132351 0.285312 -0.949332 -0.13079 0.285767 -0.820938 -0.514953 0.246746 -0.821395 -0.513999 0.247217 -0.543737 -0.82319 0.163428 -0.544169 -0.822842 0.163743 -0.190556 -0.980004 0.0572669 -0.212315 -0.974012 0.0788834 -0.0308799 -0.999484 0.00884473 -0.989057 0.0643347 0.132767 -0.988812 0.0679642 0.132787 -0.988842 0.0677438 0.132674 -0.988693 0.0698616 0.132686 -0.988636 0.0704099 0.132823 -0.988606 0.0712021 0.13262 -0.241505 0.947507 -0.209535 -0.555875 0.768738 0.316299 -0.531067 0.844526 0.0688834 -0.763804 0.637016 0.103993 -0.788085 0.58885 0.179381 -0.869216 0.480655 0.115909 -0.959445 0.249887 0.130466 -0.959109 0.250619 0.131527 -0.880652 0.331061 0.338895 -0.164474 0.984265 0.0645785 -0.295349 0.95181 0.0826235 -0.132497 0.989822 0.0519358 -0.758583 0.58698 0.282854 -0.81887 0.501894 0.278484 -0.712483 0.645872 0.274258 -0.489882 0.851733 0.18592 -0.59428 0.781008 0.191986 -0.446196 0.878221 0.172154 -0.930585 0.166826 0.325854 -0.908785 0.246471 0.336692 -0.930266 0.100703 0.352794 -0.169255 0.984206 0.0518711 -0.176779 0.982846 0.0525709 -0.500452 0.851733 0.155235 -0.508782 0.846705 0.155663 -0.773962 0.586884 0.237803 -0.77232 0.589004 0.237898 -0.926829 0.24639 0.283339 -0.925154 0.251811 0.284046 -0.955599 0.0647664 0.287466 -0.95537 0.0673029 0.287641 -0.924938 0.0619224 0.37504 -0.925118 0.0645796 0.374146 -0.934085 0.113805 0.338429 -0.934781 0.023684 0.354434 -0.951647 0.0955561 0.291953 -0.0424667 -0.999097 -0.0011444 -0.0363653 -0.999337 -0.00178392 -0.0168882 -0.999857 0 -0.0523475 -0.998629 -0.000568013 -0.0584133 -0.998293 -0.000258044 -0.0675966 -0.997713 -7.93236e-06 -0.0744456 -0.997225 4.61016e-06 -0.0826104 -0.996582 -7.71153e-05 -0.0953287 -0.995446 -0.000601661 -0.140968 -0.990005 -0.00419425 -0.191454 -0.981321 -0.0188328 -0.215656 -0.976082 -0.0274983 -0.302458 -0.953121 0.00894361 -0.378036 -0.925791 -6.7932e-07 -0.527877 -0.849321 -4.61213e-06 -0.576112 -0.81631 0.041623 -0.662951 -0.748592 0.0103165 -0.778721 -0.62707 -0.0194308 -0.853286 -0.519043 0.0499784 -0.872856 -0.486865 0.0329334 -0.997891 0.0649094 0 -0.998022 -0.0628408 -0.00185377 -0.989233 -0.139241 0.045061 -0.964374 -0.264543 6.95058e-07 -0.915406 -0.402532 1.05761e-06 -0.982656 0.18544 0 -0.966845 0.25264 0.037207 -0.767893 0.640426 0.0139615 -0.822767 0.568379 2.99378e-06 -0.875114 0.483917 2.5489e-06 -0.896777 0.442222 -0.0152024 -0.948654 0.315932 0.0155729 -0.502397 0.864637 1.28898e-07 -0.544403 0.838798 0.0066276 -0.585855 0.810198 0.0187789 -0.676457 0.736025 -0.0259648 -0.790789 0.611351 0.0300633 -0.370982 0.92864 1.11464e-05 -0.246214 0.965983 0.0790912 -0.131463 0.991321 0.000892515 -0.99736 0.0726095 0 -0.997406 0.0719749 -0.000106932 -0.997459 0.0712392 4.16154e-06 -0.997595 0.0693102 -4.47896e-06 -0.997596 0.0692963 0 -0.953874 -0.0671724 0.292597 -0.933043 -0.0651327 0.353821 -0.955599 -0.0647664 0.287466 -0.952092 -0.0981509 0.289633 -0.944396 -0.0599973 0.323291 -0.930774 -0.0848506 0.355612 -0.931564 -0.0623659 0.358188 -0.112392 -0.993664 0 -0.246217 -0.965992 0.078972 -0.249018 -0.965434 0.076986 -0.374727 -0.927135 1.3363e-05 -0.58585 -0.810191 0.0192599 -0.551418 -0.834188 0.00827707 -0.505905 -0.862589 2.16788e-06 -0.767907 -0.640437 0.0126401 -0.795954 -0.604434 0.0334333 -0.682634 -0.730296 -0.0260569 -0.967515 -0.252815 0 -0.978306 -0.202311 0.0445873 -0.874742 -0.483711 -0.0291512 -0.898848 -0.43826 1.73085e-06 -0.825241 -0.56478 2.23053e-06 -0.999532 -0.0305948 -0.000499316 -0.997891 -0.0649094 0 -0.987837 0.152656 0.0295512 -0.990079 0.13936 0.0179315 -0.948626 0.316401 -0.000109496 -0.882126 0.471013 0.000794926 -0.85365 0.519265 0.0405729 -0.790634 0.612211 0.00974058 -0.676381 0.736307 -0.0190091 -0.575859 0.815953 0.0510558 -0.544595 0.838028 0.0335367 -0.463015 0.886351 -1.60382e-05 -0.30247 0.953159 8.5743e-06 -0.32965 0.943988 0.01474 -0.191485 0.981479 -0.00572264 -0.128413 0.991542 -0.0188291 -0.140925 0.989705 -0.0249974 -0.0953215 0.995371 -0.0122778 -0.0826069 0.99654 -0.00921939 -0.0744435 0.997197 -0.00751586 -0.0675954 0.997694 -0.00616967 -0.0584127 0.998282 -0.00460243 -0.0523471 0.998622 -0.00371479 -0.0424666 0.999095 -0.00234214 -0.0168882 0.999857 0 -0.997634 -0.0687481 0 -0.997595 -0.0693105 -9.48259e-05 -0.997555 -0.0698902 -1.97181e-06 -0.997406 -0.0719745 7.35914e-06 -0.997408 -0.0719518 0 -0.19502 0.980419 0.0273172 -0.553814 0.828844 0.0794189 -0.553683 0.829003 0.0786796 -0.825659 0.551698 0.117973 -0.825581 0.551909 0.11753 -0.971282 0.193323 0.138702 -0.971283 0.193463 0.138496 -0.186465 0.980808 0.0569803 -0.933624 0.195272 0.300359 -0.93536 0.188656 0.299184 -0.790968 0.555613 0.256249 -0.795073 0.549954 0.255755 -0.671284 0.709043 0.215952 -0.528982 0.831523 0.169555 -0.174181 0.982953 0.0588534 -0.186769 0.980733 0.0572761 -0.354313 0.928155 0.113978 -0.527018 0.832778 0.169507 -0.989985 6.77927e-05 0.14117 -0.989985 7.2972e-05 0.14117 -0.919248 0.188722 0.345495 -0.933801 0.136024 0.330927 -0.892958 0.305164 0.33091 -0.782854 0.550097 0.290747 -0.835933 0.475637 0.273836 -0.661277 0.709176 0.244503 -0.73619 0.625691 0.257943 -0.520075 0.832891 0.189246 -0.621318 0.762842 0.178989 -0.352619 0.928197 0.118789 -0.486348 0.861434 0.14628 -0.174516 0.98295 0.057911 -0.338904 0.939279 0.0538483 -0.989985 0 0.14117 -0.989985 -6.83868e-05 0.14117 -0.989985 -7.55564e-05 0.14117 -0.174181 -0.982953 0.0588534 -0.934854 -0.188666 0.300755 -0.934109 -0.19528 0.29884 -0.793232 -0.552054 0.256941 -0.791299 -0.555627 0.255195 -0.518111 -0.839047 0.166014 -0.527949 -0.831473 0.172983 -0.186769 -0.980733 0.0572761 -0.186465 -0.980808 0.0569803 -0.395972 -0.910121 0.122005 -0.185411 -0.982292 0.026921 -0.299767 -0.953132 0.0409636 -0.246142 -0.968701 0.0321327 -0.926157 -0.142033 0.349371 -0.923788 -0.188749 0.33315 -0.789929 -0.552161 0.266704 -0.830533 -0.461321 0.312086 -0.894902 -0.299635 0.33071 -0.512656 -0.844893 0.152773 -0.565841 -0.808787 0.160275 -0.521659 -0.838838 0.155635 -0.646621 -0.727142 0.230534 -0.736907 -0.624889 0.257842 -0.920737 -0.253971 0.296214 -0.941847 -0.149768 0.300821 -0.953595 -0.000161149 0.301092 -0.953599 0 0.30108 -0.953459 -0.0168772 0.30105 -0.93638 0.0225862 0.35026 -0.920123 0.187107 0.344041 -0.93643 0 0.350855 -0.899065 0.273195 0.342121 -0.93438 -0.000300226 0.356279 -0.93438 0.000300226 0.356279 -0.93438 0 0.356278 -0.915868 -0.209332 0.342588 -0.925782 0.232854 0.297837 -0.953599 0.000156148 0.30108 -0.63719 0.770707 1.29164e-06 -0.988717 0.149793 -4.17325e-05 -0.946928 0.316461 0.0563824 -0.980721 0.195202 0.00907782 -0.881738 0.471694 -0.006487 -0.8313 0.555467 0.0199238 -0.790257 0.612716 0.00848435 -0.742847 0.669461 -7.1517e-07 -0.543787 0.838872 0.0242876 -0.55545 0.831293 0.0206949 -0.39451 0.918814 -0.011926 -0.195055 0.980598 0.0194993 -0.129534 0.991575 0 -1 0 0 -1 0 0 -1 0 0 -0.148939 -0.988846 0 -0.195068 -0.980663 0.0157748 -0.315665 -0.948867 0.00261713 -0.469836 -0.882728 -0.00677352 -0.555456 -0.831302 0.0201669 -0.611589 -0.791127 0.00872928 -0.831278 -0.555453 0.0211767 -0.770219 -0.63778 -2.93246e-06 -0.668892 -0.74336 -1.19482e-06 -0.991527 -0.129903 0 -0.980611 -0.195051 0.0188941 -0.918176 -0.395999 -0.0117171 -0.838757 -0.544205 0.0181343 0 -0.980785 0.19509 0 -0.980785 0.19509 0 -0.83147 0.55557 0 -0.83147 0.55557 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.195091 0.980785 0 -0.195091 0.980785 -0.00670947 0.923859 0.382674 0.0133899 0.980697 0.195074 0 0.991445 0.130527 0 0.130527 0.991445 0.0133899 0.195073 0.980697 -0.00670961 0.382674 0.923859 0 0.442287 0.896874 0 0.608763 0.793352 0 0.608763 0.793352 0 0.793352 0.608763 0 0.793352 0.608763 0 0.896874 0.442286 0 -0.195091 0.980785 0 -0.195091 0.980785 0 -0.55557 0.83147 0 -0.55557 0.83147 0 -0.83147 0.55557 0 -0.83147 0.55557 0 -0.980786 0.195089 0 -0.980786 0.195089 0 0.130527 0.991445 0.0133899 0.195074 0.980697 -0.00670954 0.382674 0.923859 0 0.442286 0.896874 0 0.608763 0.793352 0 0.608763 0.793352 0 0.793353 0.608762 0 0.793353 0.608762 0 0.896873 0.442288 -0.00670964 0.923858 0.382676 0.0133901 0.980697 0.195072 0 0.991445 0.130525 0.694743 -0.69475 -0.186158 0.694744 -0.694749 -0.186157 0.694745 -0.50859 -0.508592 0.694745 -0.50859 -0.508591 0.694745 -0.186158 -0.694748 0.694746 -0.186159 -0.694746 0.694747 0.186157 -0.694747 0.694744 0.186159 -0.694748 0.694744 0.508591 -0.508592 0.694745 0.50859 -0.508592 0.694744 0.694749 -0.186157 0.694745 0.694748 -0.186157 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.258818 0 0.965926 -0.258818 0.694745 -0.694748 -0.186156 0.694743 -0.69475 -0.186158 0.694744 -0.508591 -0.508593 0.694744 -0.508591 -0.508592 0.694744 -0.186158 -0.694749 0.694746 -0.186159 -0.694746 0.694746 0.186158 -0.694746 0.694745 0.186159 -0.694748 0.694745 0.50859 -0.508592 0.694745 0.50859 -0.508592 0.694745 0.694748 -0.186158 0.694743 0.69475 -0.186157 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0.965928 0.258811 0 0.965928 0.258811 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258817 0.965926 0 0.258817 0.965926 0 0 1 0 0 1 0 -0.258821 0.965925 0 -0.195086 0.980755 -0.00783018 -0.608748 0.793342 0.00590205 -0.555569 0.83147 0 -0.793357 0.608756 0 -0.831469 0.555558 0.00394918 -0.965907 0.258822 -0.00590144 -0.980782 0.195107 0 -1 0 0 -1 0 0 -0.965924 -0.258827 0 -0.965924 -0.258827 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0 -1 0 0 -1 0 0.258817 -0.965927 0 0.258817 -0.965927 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965928 -0.258811 0 0.965928 -0.258811 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0.980786 0.195086 0 0.980786 0.195086 0 0.831475 0.555562 0 0.831475 0.555562 0 0.555569 0.831471 0 0.555569 0.831471 0 0.195088 0.980786 0 0.195088 0.980786 0 0 1 0 0 1 0 -0.258821 0.965925 0 -0.195086 0.980755 -0.00783016 -0.608748 0.793342 0.00590207 -0.555569 0.831471 0 -0.793357 0.608756 0 -0.831469 0.555558 0.00394917 -0.965907 0.258822 -0.00590145 -0.980782 0.195107 0 -1 0 0 -1 0 0 -0.980782 -0.195107 0 -0.965907 -0.258822 0.00590145 -0.89688 -0.442273 0 -0.793357 -0.608756 0 -0.707085 -0.707084 0.00788118 -0.195093 -0.980785 0 -0.258817 -0.965908 0.0059022 -0.44229 -0.896872 0 -0.608758 -0.793356 0 0 -1 0 0 -1 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965928 -0.258811 0 0.965928 -0.258811 0 -0.195089 -0.980786 0 -0.322381 -0.946271 0.0253487 -0.980783 -0.195103 0 -0.984423 -0.175811 0.00164441 -0.842216 -0.539138 -0.00164464 -0.831469 -0.555571 0 -0.539145 -0.842213 0 -0.555576 -0.831464 -0.00180659 -0.248327 -0.968676 0.00102687 -0.116742 -0.993118 0.00939167 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.994165 -0.10787 0 0.966582 -0.255791 0.0170292 0.965778 -0.258779 0.0175145 0.940389 -0.340016 0.00763411 0.793348 -0.608753 0.00441799 0.827831 -0.560976 0.000887074 0.89026 -0.455452 -0.00101225 0.608757 -0.793348 0.00358264 0.595964 -0.802995 0.00516271 0.722295 -0.691574 -0.00402521 0.184429 -0.98281 0.00838669 0.0783743 -0.996924 0 0.242896 -0.969937 0.0149456 0.298105 -0.954253 0.0231432 0.258787 -0.965804 0.0158922 0.360117 -0.932887 0.00609392 0.474648 -0.880173 -0.00247723 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.25882 0.965926 0 -0.984424 0.175811 0 -0.965906 0.258813 0.00641315 -0.793319 0.608756 -0.00782093 -0.842217 0.539138 0 -0.608762 0.793353 0 -0.539139 0.842204 -0.00476214 -0.198438 0.980076 0.00862857 -0.279848 0.959211 0.039994 0.314864 0.948778 0.0260874 0.19509 0.98078 0.00337304 0.441868 0.897079 -0.0015852 0.274282 0.961453 0.0194362 0.193082 0.981146 0.00843279 0.0660019 0.997819 0 0.555511 0.831383 -0.0144823 0.695415 0.717869 0.0326001 0.565807 0.824466 0.0108689 0.980786 0.195087 0 0.991966 0.12568 0.0144246 0.956898 0.290418 0.00204707 0.831452 0.555559 -0.00647409 0.894263 0.446959 0.022827 0.80687 0.590702 0.00569193 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.25882 -0.965926 0 -0.965926 -0.258819 0 -0.98438 -0.175803 0.00944161 -0.842208 -0.539132 -0.00476353 -0.793343 -0.608775 0 -0.539144 -0.842213 0 -0.608743 -0.793329 -0.00781864 -0.280068 -0.959964 0.00562041 -0.16502 -0.9862 0.0133425 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.965774 -0.258778 0.0177139 0.969418 -0.24492 0.0155499 0.994753 -0.102311 0 0.793348 -0.608754 0.0042887 0.834078 -0.551647 0.000495692 0.914745 -0.40403 -0.00112135 0.608757 -0.793347 0.00388985 0.604911 -0.796281 0.0043389 0.729968 -0.68347 -0.00386634 0.193082 -0.981146 0.00843277 0.0660022 -0.997819 0 0.274283 -0.961453 0.0194364 0.314864 -0.948778 0.0260873 0.258789 -0.965811 0.0153863 0.365322 -0.930864 0.00571579 0.479575 -0.877497 -0.00285761 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.153346 0.988028 0.0169171 -0.25882 0.965926 0 -0.984424 0.175811 0 -0.965906 0.258813 0.00641314 -0.793319 0.608756 -0.00782092 -0.842217 0.539138 0 -0.608761 0.793354 0 -0.539138 0.842204 -0.00476214 -0.264252 0.964434 0.00621209 -0.322388 0.946268 0.0253505 0.109091 0.994032 0 0.242806 0.96996 0.0149365 0.566157 0.824297 0.00112234 0.458211 0.888843 -0.00121448 0.258797 0.965841 0.0132644 0.358057 0.933069 0.0343037 0.297907 0.954315 0.0231131 0.696137 0.717814 0.0116902 0.608726 0.793308 -0.0107694 0.806869 0.590702 0.00569179 0.793351 0.608755 0.00337378 0.894606 0.446844 -0.00320779 0.956799 0.290449 0.0132384 0.965771 0.258777 0.017898 0.992073 0.125664 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0266733 0.999644 0.000915135 -0.965914 0.258863 0 -0.965914 0.258863 0 -0.707123 0.707091 0 -0.707123 0.707091 0 -0.258812 0.965928 0 -0.258812 0.965928 0 -0.195074 -0.980789 0 -0.235362 -0.971773 0.0162109 -0.195074 -0.980789 0 -0.555603 -0.831448 0 -0.555603 -0.831448 0 -0.831466 -0.555576 0 -0.831466 -0.555576 0 -0.980773 -0.19515 0 -0.980773 -0.19515 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0133356 0.999911 0 0.0401704 0.999193 0.000103887 0.195098 0.980783 0.00130826 0.182717 0.983164 0.00192487 0.875068 0.483984 0.00385463 0.765458 0.643486 0.000523598 0.555554 0.831478 -0.00210861 0.67742 0.735546 0.00866932 0.467813 0.883826 -0.0015058 0.831466 0.555572 -0.00193032 0.98079 0.195059 0.00145615 0.98587 0.167513 0 0.994022 -0.109179 0 0.965919 -0.258792 0.00514389 0.953628 -0.300972 0.00308183 0.889526 -0.456884 -0.000329717 0.79335 -0.608765 0.000578788 0.74836 -0.66329 -0.00192602 0.608731 -0.793376 0.00128529 0.485913 -0.874004 -0.00218323 0.258823 -0.965913 0.00480176 0.168218 -0.98575 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.897606 -0.440798 -3.27414e-06 0.965924 -0.258794 0.00402813 0.975736 -0.218944 0.00156928 0.99967 -0.0257069 0 0.811095 -0.584915 -2.15044e-06 0.707078 -0.707118 0.005 0.665992 -0.745956 0.00220779 0.0133356 -0.999911 0 -0.0132358 -0.999912 -0.000102838 0.192902 -0.981217 0.00149879 0.258827 -0.965912 0.00470576 0.41343 -0.910536 -5.2732e-05 0.541052 -0.840989 2.56043e-05 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.666049 0.74588 0.00647454 0.458962 0.888456 -8.46086e-08 0.195104 0.980783 1.69569e-06 0.302992 0.95297 0.00669137 0.111846 0.993726 0 0.555546 0.831475 -0.00433595 0.831467 0.555569 0.00242412 0.875157 0.483838 -0.00121318 0.98079 0.19506 0.00145614 0.98587 0.167514 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.19508 -0.980787 0 -0.258812 -0.965927 -0.00115173 -0.442308 -0.896863 0 -0.608794 -0.793328 0 -0.707122 -0.70709 -0.00153738 -0.980773 -0.195151 0 -0.965913 -0.258863 -0.00115134 -0.896874 -0.442287 0 -0.79335 -0.608766 0 -0.235362 0.971773 0.0162063 -0.965914 0.258863 0 -0.980772 0.195152 0.00152741 -0.79335 0.608765 -0.00115172 -0.83147 0.55557 0 -0.608789 0.793332 0 -0.555595 0.831453 -0.000770505 -0.258816 0.965926 0.0011517 -0.195086 0.980786 0 0.195089 0.980786 0 0.258777 0.965769 0.0180377 0.44229 0.896872 0 0.608763 0.793352 0 0.706906 0.706898 0.0240818 0.793359 0.608754 0 0.89686 0.442314 0 0.965767 0.258785 0.0180394 0.980785 0.195091 0 0 1 0 0 1 0 -0.965927 0.258814 0 -0.965927 0.258814 0 -0.707104 0.707109 0 -0.707104 0.707109 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -1 0 0 -1 0 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -0.555569 -0.83147 0 -0.555569 -0.83147 0 -0.831469 -0.555571 0 -0.831469 -0.555571 0 -0.980786 -0.195085 0 -0.980786 -0.195085 0 0 -1 0 0 -1 0 0.980784 -0.195095 0 0.980784 -0.195095 0 0.831469 -0.555571 0 0.831469 -0.555571 0 0.555574 -0.831467 0 0.555574 -0.831467 0 0.195089 -0.980786 0 0.195089 -0.980786 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0.980785 0.195091 0 0.980785 0.195091 0 0.831469 0.555571 0 0.831469 0.555571 0 0.555572 0.831469 0 0.555572 0.831469 0 0.195091 0.980785 0 0.195091 0.980785 0 1 0 0 1 0 0 0.195091 -0.980785 0 0.195091 -0.980785 0 0.555572 -0.831469 0 0.555572 -0.831469 0 0.831468 -0.555572 0 0.831468 -0.555572 0 0.980785 -0.195091 0 0.980785 -0.195091 0 0 -1 0 0 -1 0 -0.980787 -0.195079 0 -0.980787 -0.195079 0 -0.831468 -0.555572 0 -0.831468 -0.555572 0 -0.555572 -0.831469 0 -0.555572 -0.831469 0 -0.195089 -0.980786 0 -0.195089 -0.980786 0 -1 0 0 -1 0 0 -0.195089 0.980786 0 -0.195089 0.980786 0 -0.555572 0.831469 0 -0.555572 0.831469 0 -0.831469 0.555571 0 -0.831469 0.555571 0 -0.980787 0.19508 0 -0.980787 0.19508 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -6.29694e-07 -1 -1.2393e-06 0 -1 0 4.96547e-07 -1 2.91553e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0.186158 0.69475 -0.694743 0.186158 0.69475 -0.694743 0.508587 0.508597 -0.694743 0.508588 0.508597 -0.694743 0.694753 0.186149 -0.694742 0.694732 0.186157 -0.694761 0.694734 -0.186143 -0.694763 0.694748 -0.186161 -0.694744 0.508588 -0.508597 -0.694743 0.508588 -0.508596 -0.694743 0.186158 -0.69475 -0.694743 0.186158 -0.69475 -0.694743 0.258819 0.965926 0 0.258819 0.965926 0 0.7071 0.707113 0 0.7071 0.707113 0 0.965929 0.258806 0 0.965929 0.258806 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.7071 -0.707113 0 0.7071 -0.707113 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.510203 0.136701 -0.849121 0.37349 0.373497 -0.849121 0.136708 0.510202 -0.84912 0.136708 -0.510202 -0.84912 0.37349 -0.373497 -0.849121 0.510203 -0.136701 -0.849121 0.186158 0.69475 -0.694743 0.186158 0.69475 -0.694743 0.508587 0.508597 -0.694743 0.508588 0.508597 -0.694743 0.694753 0.186149 -0.694742 0.694732 0.186157 -0.694761 0.694734 -0.186143 -0.694763 0.694748 -0.186161 -0.694744 0.508588 -0.508597 -0.694743 0.508588 -0.508596 -0.694743 0.186158 -0.69475 -0.694743 0.186158 -0.69475 -0.694743 0.258819 0.965926 0 0.258819 0.965926 0 0.7071 0.707113 0 0.7071 0.707113 0 0.965929 0.258806 0 0.965929 0.258806 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.7071 -0.707113 0 0.7071 -0.707113 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.510203 0.136701 -0.849121 0.37349 0.373497 -0.849121 0.136708 0.510202 -0.84912 0.136708 -0.510202 -0.84912 0.37349 -0.373497 -0.849121 0.510203 -0.136701 -0.849121 -0.211354 0.977409 0 -0.991066 0.133369 0 -0.98764 0.156429 -0.0098517 -0.957997 0.286777 0 -0.911198 0.411969 0 -0.890888 0.453931 -0.0162784 -0.83553 0.549444 0 -0.754791 0.655966 0 -0.73346 0.679675 -0.00879454 -0.642879 0.765958 0.00384273 -0.618521 0.785768 5.94046e-05 -0.534985 0.844861 -9.88369e-05 -0.561199 0.827658 0.0061011 -0.396199 0.918088 -0.0119001 -0.42485 0.905264 0 -0.0402561 0.999189 0 -0.0885383 0.996055 0.00595005 -0.124829 0.992114 0.0112905 -0.10406 0.994439 0.0161941 -0.27845 0.960214 -0.0213272 -0.211354 0.97741 0 -0.42485 0.905264 0 -1 0 0 -1 0 0 -1 0 0 -0.42485 -0.905264 0 -0.27845 -0.960214 -0.0213272 -0.0594243 -0.997905 0.0255966 -0.124837 -0.992177 0 -0.211354 -0.977409 0 -0.211354 -0.97741 0 -0.42485 -0.905264 0 -0.396199 -0.918088 -0.0119001 -0.561201 -0.827657 0.00610128 -0.534985 -0.844861 -9.90352e-05 -0.61852 -0.785769 5.922e-05 -0.642879 -0.765958 0.00384273 -0.73346 -0.679675 -0.00879453 -0.754791 -0.655966 0 -0.83553 -0.549444 0 -0.890888 -0.453931 -0.0162784 -0.991066 -0.133369 0 -0.98764 -0.156429 -0.00985172 -0.957997 -0.286778 0 -0.911198 -0.411969 0 0 0 -1 0 0 -1 3.1551e-06 -0.738733 -0.673998 -0.00126746 -0.205288 -0.978701 1.622e-05 -0.217331 -0.976098 -5.35378e-05 -0.2627 -0.964878 0 -0.00936504 -0.999956 -0.0032753 -0.00357616 -0.999988 0.012449 -0.0481793 -0.998761 -0.0145133 -0.0224777 -0.999642 -0.00343443 -0.0473792 -0.998871 0.00616863 -0.130232 -0.991464 -0.0120877 -0.102915 -0.994617 0.00256456 -0.16829 -0.985734 -0.000653558 -0.260813 -0.965389 6.78779e-05 -0.297619 -0.954685 -0.00184377 -0.35546 -0.93469 0.00646975 -0.369249 -0.929308 3.77602e-06 -0.422357 -0.90643 -4.30861e-06 -0.444885 -0.895588 -0.004881 -0.475889 -0.879492 0.00472729 -0.498167 -0.867068 -0.00582706 -0.561403 -0.827522 0.00135898 -0.573222 -0.819399 -0.000123568 -0.607961 -0.793967 2.10604e-06 -0.610046 -0.792366 2.08587e-06 -0.644423 -0.764669 0.0225953 -0.674422 -0.738001 -0.00192539 -0.704652 -0.70955 0.000732657 -0.740769 -0.671759 0.00281147 -0.838924 -0.544241 0.00136779 -0.836904 -0.547349 -0.0044947 -0.788204 -0.615397 0.0252246 -0.802674 -0.595885 3.96858e-06 -0.763073 -0.646312 0.00417988 -0.91939 -0.393326 -0.00210447 -0.909847 -0.414939 0.000720116 -0.902824 -0.430009 -0.00188342 -0.890037 -0.455884 0.0109328 -0.876205 -0.481815 -5.85004e-07 -0.865974 -0.50009 -8.98971e-07 -0.849368 -0.527801 7.12043e-05 -0.974325 -0.225148 1.97809e-05 -0.974315 -0.225189 2.61375e-06 -0.97431 -0.22521 0 -0.974309 -0.225214 -0.0194596 -0.95906 -0.282534 0.0132817 -0.965307 -0.260779 -0.00718537 -0.937831 -0.347019 3.25728e-06 -0.941292 -0.337593 -1.56895e-07 -0.924188 -0.381938 7.64522e-05 0.974628 -0.223831 -0.00167086 0.891115 -0.453775 0.0130302 0.873184 -0.487217 -4.52257e-07 0.864058 -0.503393 4.23585e-05 0.974625 -0.223846 0 0.966807 -0.255507 3.39541e-05 0.966803 -0.255523 -0.0193221 0.970299 -0.241138 0.0340818 0.948884 -0.313779 0.00474879 0.958407 -0.285367 -0.00284708 0.934914 -0.354864 0.00165618 0.932176 -0.362002 -0.00143214 0.912409 -0.409277 -0.00423558 0.914667 -0.404185 0.000754416 0.902993 -0.429656 -0.000974208 0.74836 -0.663292 0.00209864 0.764758 -0.644314 0.00066334 0.76786 -0.640617 -0.00234809 0.814951 -0.579525 0.0166037 0.804809 -0.593301 -8.10024e-07 0.839044 -0.544064 0.00668659 0.709439 -0.704735 0.00303468 0.712738 -0.701424 -0.00247369 0.644932 -0.764236 -0.00288766 0.645473 -0.763778 3.83508e-05 0.611676 -0.791109 -0.000382323 0.566329 -0.824179 -0.00565594 0.573214 -0.819386 0.00391506 0.498168 -0.867072 -0.0024017 0.484807 -0.874618 -2.01191e-06 0.451579 -0.892231 7.18619e-06 0.431536 -0.902096 0.00977123 0.376396 -0.926407 -0.000869818 0.359625 -0.933097 0.000276133 0.282896 -0.959151 -0.000549886 0.278246 -0.96051 0.00115308 0.21935 -0.975646 0.00108763 0.219176 -0.975685 -0.00102729 0.142951 -0.989729 -0.00364191 0.135849 -0.990723 0 0.0045217 -0.99999 0.000561023 0.0934041 -0.995628 -0.000965521 0.0657974 -0.997833 -0.00275449 0.0572286 -0.998357 0.00144935 0.0305986 -0.999531 -0.000496044 0.0163502 -0.999866 0.000619738 0.00245096 -0.999997 -0.828652 -0.557428 0.0510879 -0.624683 -0.00569366 0.780858 -0.619187 -0.0411849 0.784163 -0.62995 -0.0565702 0.774573 -0.625742 -0.0797208 0.775946 -0.625567 -0.138611 0.767759 -0.64198 -0.12316 0.756765 -0.646832 -0.251386 0.72001 -0.647261 -0.250569 0.719908 -0.632232 -0.204971 0.747175 -0.632141 -0.168285 0.756358 -0.640103 -0.288052 0.712246 -0.648894 -0.365427 0.667383 -0.658244 -0.354869 0.663915 -0.645058 -0.467739 0.604252 -0.685307 -0.439573 0.580629 -0.674687 -0.471329 0.568019 -0.653484 -0.557768 0.511717 -0.70955 -0.522686 0.472587 -0.796256 -0.592861 0.120384 -0.772801 -0.615836 0.153381 -0.737454 -0.634294 0.23202 -0.717771 -0.589715 0.370191 -0.717834 -0.590666 0.368549 -0.896037 -0.443978 0.000530774 -0.895678 -0.444702 -0.000523357 -0.851576 -0.524223 -0.00308345 -0.969494 -0.245106 0.00199035 -0.960617 -0.277799 0.00648785 -0.953762 -0.299952 0.0191417 -0.943624 -0.33087 -0.00997084 -0.924283 -0.381285 -0.0179309 -0.980613 -0.195765 0.00857456 -0.986961 -0.154093 0.0465115 -0.992734 -0.116562 0.0298641 -0.996366 -0.0565839 0.0636652 -0.996142 -0.0479798 0.0734848 -0.996802 -0.0312756 0.0735403 -0.734981 -0.671962 0.090935 -0.728467 -0.681388 0.0710307 -0.695196 -0.716843 0.0532757 -0.669917 -0.739729 0.0633437 -0.652492 -0.757694 0.0124204 -0.629952 -0.775501 0.0419401 -0.81719 -0.564271 0.117469 -0.818913 -0.560377 0.123931 -0.780967 -0.621425 0.062624 -0.897936 -0.415897 0.14402 -0.886419 -0.451686 0.101195 -0.851396 -0.516629 0.0906571 -0.985248 0.0101374 0.17083 -0.992067 -0.0154235 0.124764 -0.987406 -0.10234 0.12065 -0.98867 -0.116241 0.0949733 -0.958318 -0.248834 0.140388 -0.957147 -0.265349 0.116011 -0.92302 -0.369915 0.105819 -0.638196 0.00904 0.76982 -0.681859 -0.0277357 0.730958 -0.68089 -0.0603179 0.729898 -0.685791 -0.0687215 0.724546 -0.67986 -0.149233 0.717997 -0.690044 -0.170869 0.703309 -0.676644 -0.260848 0.688557 -0.69055 -0.301693 0.65736 -0.672009 -0.377297 0.637221 -0.684745 -0.438752 0.581911 -0.668672 -0.483417 0.564966 -0.674301 -0.560432 0.480868 -0.669473 -0.570262 0.476033 -0.663577 -0.653327 0.364458 -0.726671 -0.683938 0.0646428 -0.703858 -0.708642 0.0490937 -0.658001 -0.71654 0.23153 -0.99769 -0.0502774 0.0456747 -0.997676 -0.0493342 0.0469998 -0.986409 -0.164269 0.00357806 -0.987914 -0.153349 0.0225834 -0.944687 -0.324867 -0.0450365 -0.954112 -0.299432 0.00321517 -0.873034 -0.481903 -0.0747004 -0.895944 -0.444126 0.00601819 -0.794115 -0.603628 -0.0708159 -0.829288 -0.557493 0.0384989 -0.75212 -0.658814 -0.0167558 -0.693451 -0.548456 0.467249 -0.6824 -0.635658 0.360928 -0.731513 -0.58271 0.354032 -0.691769 -0.649657 0.31528 -0.755365 -0.647314 0.102026 -0.637207 -0.691417 0.340455 -0.711014 -0.647055 0.275278 -0.699824 -0.650169 0.29585 -0.674986 -0.685255 0.273531 -0.729982 -0.679774 0.0709551 -0.76967 -0.630375 0.10117 -0.768593 -0.629767 0.112511 -0.793975 -0.607004 0.0338974 -0.796837 -0.544327 0.262218 -0.90103 -0.433739 -0.00396198 -0.93024 -0.365962 -0.0269398 -0.992409 -0.121376 -0.0198033 -0.995824 -0.0737629 0.0537934 -0.974726 -0.221916 -0.0257464 -0.980561 -0.196019 0.00874921 -0.952522 -0.304455 0.00315305 -0.92972 -0.367191 -0.0281482 -0.849205 -0.526972 -0.0339248 -0.849829 -0.526026 -0.0329644 -0.875809 -0.482482 -0.0130378 -0.84946 -0.0857992 0.52063 -0.85244 -0.0895327 0.515103 -0.837428 -0.211622 0.503916 -0.842012 -0.21931 0.492868 -0.806648 -0.362484 0.466824 -0.811643 -0.375516 0.447463 -0.759551 -0.504944 0.410017 -0.762925 -0.523488 0.379349 -0.708841 -0.616881 0.342056 -0.708676 -0.639338 0.29837 -0.6674 -0.693433 0.271529 -0.662748 -0.717105 0.215696 -0.643383 -0.73787 0.203976 -0.634333 -0.760537 0.138584 -0.63054 -0.764065 0.136468 -0.637597 -0.770344 0.0063414 -0.687634 -0.721832 0.0782164 -0.647389 -0.76046 -0.0508651 -0.760101 -0.647809 0.0509025 -0.725567 -0.686508 -0.0475299 -0.804821 -0.593503 -0.00421552 -0.616512 -0.787169 0.0166404 -0.601919 -0.795418 0.0707346 -0.628222 -0.773761 0.0814339 -0.636144 -0.762323 0.119095 -0.665026 -0.73511 0.131736 -0.67035 -0.724151 0.161979 -0.724406 -0.663486 0.187143 -0.727105 -0.65388 0.209188 -0.797379 -0.552142 0.243568 -0.797949 -0.544728 0.25797 -0.866991 -0.403205 0.292837 -0.866299 -0.397847 0.302066 -0.914386 -0.239137 0.326668 -0.913091 -0.235232 0.333062 -0.933889 -0.098543 0.343716 -0.932513 -0.0958436 0.348187 -0.93626 -0.0294179 0.350074 -0.851717 0.0365194 0.522728 -0.883363 -0.0198168 0.46827 -0.744533 0.0147456 0.667423 -0.770341 -0.00919513 0.637565 -0.768312 -0.0753764 0.635621 -0.772429 -0.0795365 0.630101 -0.761938 -0.18643 0.620237 -0.769786 -0.19658 0.607278 -0.744766 -0.322827 0.584044 -0.755289 -0.341817 0.559195 -0.71758 -0.45762 0.525035 -0.727739 -0.486021 0.483921 -0.687697 -0.570393 0.449138 -0.694061 -0.60548 0.389451 -0.663562 -0.653315 0.364507 -0.663884 -0.690255 0.28776 -0.651816 -0.705344 0.278614 -0.645553 -0.739958 0.189007 -0.662968 -0.721117 0.201156 -0.655937 -0.754551 0.0200001 -0.726964 -0.684075 0.0597012 -0.690399 -0.722602 -0.0345684 -0.794296 -0.607022 0.0248662 -0.760873 -0.645682 -0.0645515 -0.873896 -0.485994 0.0107556 -0.848069 -0.525107 -0.0709985 -0.944574 -0.327805 0.0179803 -0.929616 -0.364818 -0.0521753 -0.985479 -0.16562 0.0374354 -0.980635 -0.195221 -0.0156096 -0.997445 -0.0499076 0.051109 -0.997175 -0.0728692 0.0182014 -0.890477 -0.000567637 -0.455029 -0.892388 -0.37126 -0.256535 -0.99066 -0.132644 0.0316022 -0.99866 -0.015526 -0.0493764 -0.969787 -0.000606885 -0.243952 -0.952915 -0.285165 -0.10312 -0.962664 -0.266878 -0.0453271 -0.992362 -0.116675 -0.0400518 -0.824548 -0.564233 -0.0419765 -0.854185 -0.518321 -0.0413683 -0.883062 -0.459985 -0.092823 -0.888452 -0.452722 -0.0754669 -0.927713 -0.371796 -0.0334145 -0.721107 -0.687802 -0.0832615 -0.694668 -0.716298 -0.065985 -0.645047 -0.761324 -0.0655743 -0.649652 -0.754396 -0.094016 -0.61986 -0.783022 -0.0514766 -0.616506 -0.787161 -0.017239 -0.654229 -0.752336 -0.0772951 -0.647927 -0.761091 -0.0305198 -0.713359 -0.700168 -0.0297256 -0.723227 -0.684293 -0.0931981 -0.790226 -0.612208 0.0272902 -0.804512 -0.593275 -0.0280185 -0.900629 -0.433546 -0.0301009 -0.874658 -0.48275 0.0438822 -0.874973 -0.482022 0.0455746 -0.849979 -0.526119 -0.0271057 -0.992002 -0.121327 0.0348091 -0.974142 -0.221784 -0.043114 -0.94949 -0.312131 0.0322984 -0.951261 -0.304052 0.0515207 -0.9297 -0.367183 -0.0288952 -0.986094 -0.135321 -0.0964685 -0.984514 -0.153517 -0.08465 -0.986413 -0.155347 -0.0534443 -0.925268 -0.312002 -0.215717 -0.957583 -0.227346 -0.177056 -0.964387 -0.192637 -0.181242 -0.600657 -0.704272 -0.378434 -0.660637 -0.641139 -0.390512 -0.654241 -0.657123 -0.374377 -0.72627 -0.59166 -0.349957 -0.734386 -0.575446 -0.359915 -0.790802 -0.528995 -0.30789 -0.834488 -0.465044 -0.295573 -0.555991 -0.72432 -0.407718 -0.575306 -0.721647 -0.38503 -0.60853 -0.676152 -0.415342 -0.654473 -0.668218 -0.353766 -0.643938 -0.652844 -0.398922 -0.55601 -0.724327 -0.407681 -0.596658 -0.711972 -0.370264 -0.597656 -0.725986 -0.340223 -0.613676 -0.666456 -0.423366 -0.615426 -0.671467 -0.412775 -0.683403 -0.681877 -0.260777 -0.67502 -0.676191 -0.295149 -0.769346 -0.617975 -0.161906 -0.735084 -0.658503 -0.161322 -0.722656 -0.688166 -0.0647789 -0.691206 -0.700379 -0.178056 -0.682734 -0.704731 -0.192947 -0.728268 -0.681203 -0.0747551 -0.801281 -0.593627 -0.0745416 -0.803638 -0.59477 -0.0203345 -0.8086 -0.545292 -0.220959 -0.883888 -0.453384 -0.11483 -0.885856 -0.452328 -0.103239 -0.905532 -0.369333 -0.208818 -0.929571 -0.306372 -0.205022 -0.95459 -0.277717 -0.107851 -0.944989 -0.200545 -0.258412 -0.972099 -0.0857881 -0.218322 -0.965273 -0.0936249 -0.243891 -0.960729 -0.0281268 -0.276061 -0.962142 -0.00728426 -0.27245 -0.939544 0.00562514 -0.342382 -0.938162 -0.290117 -0.188904 -0.934139 -0.279594 -0.221838 -0.898302 -0.375555 -0.228063 -0.841622 -0.454564 -0.291623 -0.658193 -0.682716 -0.317303 -0.644321 -0.689345 -0.33114 -0.604016 -0.726911 -0.32675 -0.614431 -0.725799 -0.309339 -0.581514 -0.753983 -0.305534 -0.591583 -0.752905 -0.288382 -0.620911 -0.727665 -0.291501 -0.627541 -0.724878 -0.284156 -0.675009 -0.679196 -0.288195 -0.680403 -0.676465 -0.281865 -0.750404 -0.596164 -0.285452 -0.757367 -0.591637 -0.276334 -0.832055 -0.481199 -0.275921 -0.829559 -0.479477 -0.286241 -0.891198 -0.377489 -0.251533 -0.997334 -0.012922 -0.0718131 -0.99064 -0.0241933 -0.134341 -0.983897 -0.108861 -0.14176 -0.983588 -0.109249 -0.143592 -0.947657 -0.278816 -0.155591 -0.951867 -0.274227 -0.136924 -0.87844 -0.455532 -0.144337 -0.883984 -0.450451 -0.125167 -0.762657 -0.634171 -0.127211 -0.77706 -0.618316 -0.117739 -0.669426 -0.711017 -0.215229 -0.681963 -0.702442 -0.20372 -0.625756 -0.753846 -0.200363 -0.63809 -0.74981 -0.175004 -0.603442 -0.778423 -0.172957 -0.614246 -0.774664 -0.150326 -0.644669 -0.749242 -0.151782 -0.65032 -0.745818 -0.144357 -0.702073 -0.696943 -0.146162 -0.702569 -0.696589 -0.145466 -0.780318 -0.60791 -0.146798 -0.774985 -0.612628 -0.155194 -0.867864 -0.472409 -0.153762 -0.867205 -0.473194 -0.15506 -0.944022 -0.294829 -0.147984 -0.930615 -0.316417 -0.183946 -0.972498 -0.21012 -0.100488 -0.967341 -0.203404 -0.151253 -0.976642 -0.167463 -0.134638 0.0097431 -0.00936459 -0.999909 0 -0.00205802 -0.999998 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.634692 0.768176 0.0841005 -0.660585 0.713485 0.233597 -0.985183 0.0153165 0.170819 -0.996616 0.0453072 0.0685815 -0.996339 0.0487436 0.0702271 -0.99312 0.113774 0.0277162 -0.986968 0.154089 0.0463778 -0.948233 0.317139 0.0166276 -0.96812 0.250481 0.00177854 -0.980158 0.198085 0.00719621 -0.954213 0.299018 -0.00807729 -0.896124 0.443146 -0.0241612 -0.908382 0.417447 0.0240845 -0.719002 0.588033 0.370478 -0.725185 0.511576 0.460865 -0.639689 0.255572 0.724901 -0.643087 0.337741 0.687292 -0.657839 0.370027 0.655994 -0.650807 0.418747 0.633326 -0.670948 0.484923 0.560961 -0.647813 0.553319 0.523619 -0.671518 0.209777 0.710674 -0.631811 0.245146 0.735336 -0.632168 0.174892 0.754836 -0.635749 0.141092 0.758892 -0.636047 0.140668 0.758721 -0.620988 0.0824236 0.779475 -0.631537 0.0566876 0.773271 -0.624274 0.0422501 0.780062 -0.620812 0.0126282 0.783858 -0.636931 -0.0100681 0.770855 -0.638223 0.000430136 0.769852 -0.650912 0.755859 0.0706476 -0.638666 0.764691 0.0857459 -0.625992 0.771346 0.114716 -0.673347 0.726816 0.13543 -0.695196 0.716844 0.0532751 -0.728467 0.681389 0.0710301 -0.734981 0.671962 0.0909357 -0.780967 0.621424 0.0626244 -0.816888 0.564098 0.120364 -0.819744 0.560948 0.115573 -0.851398 0.516627 0.0906574 -0.902404 0.417557 0.10636 -0.985992 0.115926 0.119921 -0.990643 0.10244 0.0901819 -0.953384 0.264305 0.145611 -0.961258 0.24939 0.117418 -0.92302 0.369915 0.105819 -0.877921 0.447356 0.170667 -0.991814 -0.0197342 0.126158 -0.93626 0.0294179 0.350074 -0.932284 0.0984114 0.348083 -0.934108 0.0959595 0.343853 -0.912331 0.238659 0.332707 -0.915133 0.235671 0.327094 -0.864581 0.402183 0.301245 -0.868712 0.398802 0.293764 -0.794588 0.550374 0.256356 -0.800795 0.546398 0.245308 -0.721418 0.660994 0.206502 -0.799674 0.558789 0.219721 -0.800698 0.582642 0.139325 -0.729231 0.679322 0.0821153 -0.697134 0.654159 0.293394 -0.699824 0.650169 0.29585 -0.660638 0.657795 0.36175 -0.699436 0.593416 0.398305 -0.637064 0.629941 0.444211 -0.699596 0.503788 0.506718 -0.645589 0.538862 0.54115 -0.699545 0.391364 0.597889 -0.6582 0.42336 0.622526 -0.697254 0.268027 0.66483 -0.670206 0.293695 0.681591 -0.69213 0.151621 0.705667 -0.677798 0.168194 0.715752 -0.686135 0.060701 0.724937 -0.680542 0.0682918 0.72952 -0.681859 0.0277357 0.730958 -0.707253 0.525496 0.472914 -0.694954 0.546976 0.46675 -0.676232 0.630455 0.381101 -0.730573 0.584464 0.353081 -0.713153 0.615352 0.33579 -0.74506 0.640016 0.187791 -0.790481 0.598639 0.129506 -0.679927 0.689612 0.249267 -0.703711 0.70857 0.0521464 -0.76967 0.630375 0.10117 -0.774262 0.632329 0.0260472 -0.828651 0.557428 0.0510988 -0.837469 0.545597 0.0311364 -0.865936 0.499992 -0.0127926 -0.930232 0.365939 -0.0275151 -0.929761 0.367206 -0.0265262 -0.90103 0.433739 -0.00396197 -0.99729 0.0726908 0.0113746 -0.992199 0.121351 0.0285372 -0.980665 0.19537 -0.0112942 -0.975022 0.221984 0.00743042 -0.952521 0.304456 0.00315262 -0.730237 0.656264 0.189926 -0.662261 0.73236 0.158302 -0.671636 0.740751 -0.0138906 -0.629952 0.775501 0.0419399 -0.616512 0.787169 0.0166403 -0.623522 0.781708 -0.0123823 -0.64809 0.761283 0.0206842 -0.69055 0.723139 -0.0145216 -0.726272 0.687175 0.0178498 -0.761722 0.647269 -0.0286919 -0.804821 0.593503 -0.00421618 -0.849205 0.526973 -0.0339252 -0.84983 0.526025 -0.0329631 -0.875808 0.482484 -0.0130382 -0.744595 0.0070808 0.667479 -0.769859 -0.0334316 0.637337 -0.768093 0.0791759 0.635425 -0.772637 0.0757193 0.630316 -0.760767 0.194548 0.619181 -0.770943 0.188359 0.608415 -0.741304 0.336122 0.580939 -0.758824 0.328256 0.562524 -0.710432 0.475593 0.518746 -0.735238 0.467669 0.490622 -0.676139 0.591453 0.43934 -0.706386 0.584145 0.399742 -0.647899 0.675547 0.351942 -0.680672 0.668051 0.300656 -0.632983 0.72757 0.264528 -0.665672 0.718085 0.203062 -0.662968 0.721117 0.201156 -0.678678 0.733713 0.032574 -0.726671 0.683938 0.0646428 -0.75212 0.658814 -0.0167558 -0.794685 0.606895 0.0123834 -0.830131 0.555611 -0.0466856 -0.874299 0.485217 -0.01292 -0.895391 0.441622 -0.056963 -0.945077 0.326748 -0.00807518 -0.95398 0.297912 -0.0342077 -0.986148 0.164873 0.0181322 -0.988218 0.15285 0.00793725 -0.997619 0.0510704 0.0463513 -0.997788 0.0489596 0.0449622 -0.883437 -0.0149895 0.468309 -0.852306 0.0166162 0.52278 -0.84921 0.0892647 0.520456 -0.852676 0.0860532 0.515305 -0.836278 0.217991 0.50311 -0.843139 0.212872 0.493763 -0.803521 0.372123 0.464627 -0.814796 0.365718 0.449842 -0.753351 0.517545 0.40572 -0.769313 0.510668 0.383896 -0.699029 0.631519 0.335473 -0.718913 0.624527 0.305172 -0.654275 0.708992 0.263163 -0.676498 0.701511 0.224128 -0.627719 0.753719 0.194619 -0.650721 0.744793 0.147803 -0.63054 0.764065 0.136468 -0.655937 0.75455 0.0200002 -0.689618 0.723159 0.0383262 -0.729222 0.68414 -0.0137214 -0.761627 0.647997 0.00484322 -0.794894 0.605123 -0.0443765 -0.849303 0.527845 -0.00798941 -0.873906 0.483374 -0.0513638 -0.930237 0.366957 0.00104584 -0.944939 0.325475 -0.0340107 -0.98022 0.196458 0.0239308 -0.986449 0.164066 -0.00114198 -0.996485 0.0733353 0.0404817 -0.998277 0.0508955 0.029206 -0.938889 0.287961 -0.188589 -0.630662 0.65657 -0.413741 -0.613142 0.668997 -0.420119 -0.601121 0.715534 -0.3559 -0.588401 0.714713 -0.378115 -0.555989 0.724317 -0.407726 -0.555992 0.724308 -0.407739 -0.575301 0.721642 -0.385048 -0.593073 0.698071 -0.401201 -0.618771 0.686266 -0.38231 -0.649609 0.65353 -0.388468 -0.667262 0.64618 -0.370421 -0.726265 0.591656 -0.349975 -0.734381 0.575437 -0.359942 -0.791152 0.528676 -0.307539 -0.826551 0.477375 -0.298206 -0.841334 0.462466 -0.279789 -0.981695 0.144676 -0.12387 -0.984507 0.154749 -0.0824598 -0.992217 0.121353 -0.0279042 -0.988056 0.153791 0.00963892 -0.974141 0.221783 -0.0431578 -0.952219 0.304359 0.0253852 -0.949007 0.312659 0.0403705 -0.929696 0.36718 -0.0290636 -0.643089 0.761122 -0.084438 -0.615939 0.786437 -0.0462242 -0.622127 0.782485 -0.025989 -0.646853 0.759831 -0.0651041 -0.658337 0.752103 -0.0305477 -0.726068 0.686982 -0.0296728 -0.705446 0.698496 -0.120206 -0.803576 0.592585 0.0557609 -0.789675 0.612866 -0.0284313 -0.849976 0.526115 -0.0272797 -0.874652 0.482759 0.0439071 -0.875097 0.482092 0.0423414 -0.900624 0.433543 -0.0302708 -0.780309 0.6209 -0.0748384 -0.728261 0.681196 -0.0748836 -0.721116 0.687781 -0.0833563 -0.694662 0.716293 -0.0661005 -0.65113 0.756113 -0.0657528 -0.956875 0.265273 -0.11841 -0.927705 0.371792 -0.0336827 -0.883856 0.46089 -0.0798741 -0.886549 0.451752 -0.0997548 -0.85418 0.518315 -0.0415469 -0.998658 0.015526 -0.0494033 -0.992969 0.116746 0.019547 -0.991545 0.123265 -0.0405582 -0.95557 0.291095 -0.0463645 -0.939544 -0.00565594 -0.342382 -0.969711 0.0125511 -0.243934 -0.962692 -0.00530667 -0.270548 -0.846771 0.00475404 -0.531936 -0.9603 0.0322338 -0.277103 -0.96938 0.0984505 -0.224966 -0.968098 0.0955866 -0.231624 -0.943551 0.215848 -0.251241 -0.954713 0.277837 -0.106446 -0.925548 0.317262 -0.206654 -0.799141 0.59232 -0.102615 -0.793763 0.588891 -0.152144 -0.871692 0.440343 -0.21506 -0.877444 0.479679 0.000332181 -0.900005 0.381741 -0.210391 -0.673581 0.709008 -0.208799 -0.691275 0.700306 -0.178073 -0.722731 0.688157 -0.0640277 -0.738325 0.641161 -0.209258 -0.813253 0.581521 -0.021276 -0.637234 0.691445 -0.340349 -0.660801 0.681672 -0.314111 -0.963187 0.199187 -0.18054 -0.958487 0.224092 -0.17631 -0.925431 0.312065 -0.214925 -0.934117 0.279657 -0.221849 -0.855017 0.46392 -0.231785 -0.888266 0.378198 -0.260674 -0.893711 0.372152 -0.250566 -0.868558 0.355487 -0.345305 -0.832057 0.481158 -0.275984 -0.752613 0.597703 -0.276271 -0.755123 0.590072 -0.285664 -0.676613 0.680335 -0.281674 -0.678758 0.675286 -0.288578 -0.622846 0.729051 -0.283809 -0.625558 0.723442 -0.292075 -0.586096 0.757378 -0.287871 -0.58694 0.749457 -0.306294 -0.608935 0.730628 -0.308839 -0.609449 0.722028 -0.327486 -0.657571 0.67605 -0.332501 -0.646344 0.655705 -0.390244 -0.996715 0.0375414 -0.071765 -0.991079 0.0056217 -0.13316 -0.983743 0.1094 -0.142413 -0.983608 0.108572 -0.143969 -0.949684 0.271803 -0.155639 -0.949764 0.281084 -0.137626 -0.881984 0.448582 -0.144495 -0.880403 0.457277 -0.12565 -0.762291 0.634548 -0.127515 -0.824541 0.56423 -0.0421551 -0.687277 0.671418 -0.277215 -0.678308 0.705969 -0.203731 -0.633425 0.747224 -0.201072 -0.630376 0.75636 -0.174771 -0.610392 0.772845 -0.173587 -0.60726 0.780182 -0.150172 -0.649147 0.745283 -0.15219 -0.645799 0.74973 -0.144389 -0.702436 0.696529 -0.146393 -0.702142 0.696974 -0.145686 -0.776054 0.613293 -0.147012 -0.779189 0.607204 -0.155463 -0.867337 0.473289 -0.154025 -0.867675 0.472267 -0.155254 -0.935288 0.320742 -0.149537 -0.941827 0.292608 -0.165356 -0.972505 0.210036 -0.100595 -0.985942 0.136307 -0.0966333 -0.978037 0.163983 -0.128655 -1.87831e-05 0.0163502 -0.999866 0.000523971 0.00245096 -0.999997 0 0.00205801 -0.999998 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.186634 0.9002 -0.393457 -0.76973 0.628247 -0.113235 -0.979509 0.190774 -0.064555 -0.970935 0.216046 -0.103006 -0.83243 0.477895 -0.280494 -0.814127 0.492195 -0.308127 -0.547095 0.699461 -0.459828 -0.529342 0.703487 -0.474239 -0.178801 0.797147 -0.576704 -0.21179 0.802335 -0.558036 -0.18619 0.828611 -0.527955 -0.185925 0.852993 -0.487684 -0.482125 0.853234 -0.198864 -0.325833 0.917182 -0.229368 -0.205167 0.944247 -0.257498 -0.161251 0.955846 -0.245677 -0.0153038 0.967 -0.254318 -0.545381 0.817277 -0.186057 -0.668925 0.710054 -0.219916 -0.61985 0.755805 -0.211057 -0.981024 0.192746 0.020991 -0.990946 0.134125 0.00601913 -0.949844 0.312573 -0.00970366 -0.833215 0.545843 -0.0883594 -0.895336 0.429727 -0.117081 -0.850119 0.514798 -0.110821 -0.252682 0.909705 -0.329528 -0.186733 0.937244 -0.294457 -0.191559 0.91286 -0.360544 -0.552862 0.782815 -0.28556 -0.547129 0.787137 -0.28472 -0.83836 0.521486 -0.158763 -0.834907 0.527076 -0.158497 -0.980823 0.194358 -0.014533 -0.981783 0.18943 -0.0148064 -0.189309 0.878879 -0.437874 -0.223003 0.858878 -0.461084 -0.552993 0.74097 -0.381002 -0.542336 0.749244 -0.380138 -0.839216 0.493286 -0.228879 -0.829152 0.509698 -0.229596 -0.982538 0.179717 -0.0481751 -0.978669 0.199358 -0.0496429 -0.189426 -0.877804 -0.439976 -0.28877 -0.927727 -0.236506 -0.186921 -0.826467 -0.531049 -0.229334 -0.78834 -0.570899 -0.177669 -0.807169 -0.562949 -0.547293 -0.69448 -0.467085 -0.528588 -0.7089 -0.466964 -0.832764 -0.470149 -0.292342 -0.812917 -0.501204 -0.29658 -0.980038 -0.181908 -0.0802244 -0.969699 -0.227682 -0.0885683 -0.996459 -0.049795 0.0677428 -0.980971 -0.193904 0.00989499 -0.97877 -0.204622 0.0118006 -0.931684 -0.362388 -0.0252956 -0.85719 -0.508954 -0.0786876 -0.834941 -0.540024 -0.106052 -0.759651 -0.638899 -0.121403 -0.412877 -0.885661 -0.212455 -0.503804 -0.838751 -0.206587 -0.547404 -0.810973 -0.206572 -0.619627 -0.767245 -0.16552 -0.719057 -0.682131 -0.132868 -0.247555 -0.844312 -0.47524 -0.115447 -0.961486 -0.249433 -0.198496 -0.94418 -0.262913 -0.179534 -0.929696 -0.32161 -0.230691 -0.904002 -0.359949 -0.186999 -0.897611 -0.399156 -0.221943 -0.907541 -0.356527 -0.547356 -0.786069 -0.287221 -0.552744 -0.783819 -0.283022 -0.835128 -0.526025 -0.160806 -0.838261 -0.522365 -0.156375 -0.981169 -0.192657 -0.0138233 -0.981115 -0.192914 -0.0140798 -0.98283 -0.180452 -0.0384994 -0.979101 -0.195346 -0.0565863 -0.839027 -0.496635 -0.222234 -0.829729 -0.505796 -0.23605 -0.552856 -0.743368 -0.376502 -0.542723 -0.746675 -0.384613 -0.200228 -0.862761 -0.464277 -0.185866 -0.838674 -0.511937 -0.176392 0.741972 -0.64681 -0.960329 0.251475 -0.120533 -0.972071 0.200199 -0.122466 -0.798613 0.492873 -0.34539 -0.817037 0.458642 -0.349427 -0.51801 0.672885 -0.528101 -0.533887 0.656428 -0.53298 -0.188792 0.754018 -0.629138 -0.182317 0.760706 -0.622967 -0.182719 -0.755904 -0.628668 -0.176085 -0.734509 -0.655356 -0.188293 -0.751744 -0.632003 -0.517322 -0.661828 -0.542551 -0.533408 -0.663571 -0.524547 -0.798389 -0.476811 -0.36773 -0.816138 -0.472389 -0.332818 -0.961268 -0.232172 -0.148524 -0.97064 -0.219138 -0.0991827 -0.179142 0.703179 -0.688076 -0.522004 0.618631 -0.587202 -0.8024 0.442106 -0.400871 -0.963534 0.209524 -0.166442 -0.169402 0.707995 -0.685599 -0.173276 0.639573 -0.748948 -0.164148 0.644146 -0.747082 -0.168222 0.56437 -0.808201 -0.156521 0.570036 -0.806573 -0.163749 0.490552 -0.855888 -0.170947 0.486405 -0.856847 -0.153363 0.44357 -0.883021 -0.164385 0.381104 -0.909801 -0.130734 0.391949 -0.910651 -0.154379 0.309483 -0.93829 -0.164575 0.301439 -0.939175 -0.130145 0.255118 -0.958111 -0.154956 0.1964 -0.968202 -0.104772 0.200204 -0.974136 -0.14205 0.135855 -0.980492 -0.102441 0.134228 -0.985641 -0.501929 0.636508 -0.585597 -0.505892 0.568228 -0.648991 -0.487404 0.584154 -0.649 -0.491291 0.510798 -0.705491 -0.470194 0.527879 -0.707291 -0.476663 0.457412 -0.750711 -0.449792 0.476065 -0.755678 -0.463634 0.400429 -0.790379 -0.422671 0.422884 -0.801572 -0.44462 0.345942 -0.826219 -0.391333 0.366631 -0.844062 -0.415875 0.309598 -0.855101 -0.363207 0.32082 -0.874732 -0.384114 0.284912 -0.878227 -0.3421 0.287734 -0.894526 -0.778653 0.480011 -0.404089 -0.782373 0.418471 -0.461275 -0.760168 0.451516 -0.467202 -0.763569 0.391161 -0.513766 -0.738632 0.425078 -0.523194 -0.742824 0.381635 -0.55006 -0.713729 0.415064 -0.564192 -0.721103 0.374886 -0.582641 -0.678536 0.413357 -0.607227 -0.689629 0.374916 -0.619556 -0.636194 0.410553 -0.653226 -0.643254 0.394225 -0.656362 -0.592511 0.415526 -0.690122 -0.595972 0.4096 -0.690685 -0.554907 0.419011 -0.718685 -0.947411 0.267432 -0.175764 -0.950443 0.218727 -0.220944 -0.934239 0.26907 -0.234091 -0.936738 0.226675 -0.26672 -0.917357 0.27801 -0.284896 -0.918808 0.263594 -0.293786 -0.895392 0.312516 -0.317185 -0.896142 0.308435 -0.319058 -0.860489 0.364188 -0.356265 -0.86065 0.363634 -0.356442 -0.814548 0.416048 -0.404247 -0.804837 0.438457 -0.39999 -0.761286 0.471027 -0.445619 -0.748466 0.492974 -0.443594 -0.712475 0.510241 -0.481699 -0.156744 -0.297065 -0.941904 -0.163873 -0.482524 -0.860416 -0.172626 -0.639167 -0.749443 -0.169295 -0.699116 -0.694676 -0.17834 -0.701971 -0.689516 -0.501679 -0.622443 -0.600735 -0.520058 -0.624191 -0.583031 -0.778788 -0.460815 -0.425605 -0.799899 -0.456137 -0.39 -0.948349 -0.244927 -0.201607 -0.961351 -0.231045 -0.149738 -0.165856 -0.604045 -0.7795 -0.174412 -0.638147 -0.749899 -0.487235 -0.570517 -0.661144 -0.504435 -0.573381 -0.645585 -0.760326 -0.432935 -0.484223 -0.780468 -0.43152 -0.452394 -0.934948 -0.247097 -0.254589 -0.948703 -0.238842 -0.207166 -0.15659 -0.560217 -0.813411 -0.167708 -0.564576 -0.808163 -0.470551 -0.513149 -0.717816 -0.490055 -0.518202 -0.700937 -0.739542 -0.404896 -0.537715 -0.761805 -0.407168 -0.503853 -0.918787 -0.253588 -0.30253 -0.934743 -0.25049 -0.252011 -0.153819 -0.435486 -0.886957 -0.164274 -0.482316 -0.860457 -0.451899 -0.459127 -0.764846 -0.474844 -0.468597 -0.744943 -0.716798 -0.393214 -0.575833 -0.739902 -0.401309 -0.539904 -0.899102 -0.286556 -0.33091 -0.914883 -0.291131 -0.279701 -0.134647 -0.374074 -0.917572 -0.161868 -0.391241 -0.905941 -0.428291 -0.399589 -0.81049 -0.459589 -0.418403 -0.783401 -0.685998 -0.383787 -0.618154 -0.715184 -0.401699 -0.57197 -0.869182 -0.329242 -0.368947 -0.888291 -0.343232 -0.305173 -0.133897 -0.24398 -0.960492 -0.156203 -0.297334 -0.941909 -0.402223 -0.339613 -0.850223 -0.436924 -0.369832 -0.819952 -0.649612 -0.37711 -0.660146 -0.67917 -0.407052 -0.610767 -0.829615 -0.376908 -0.411921 -0.847349 -0.403128 -0.345671 -0.116107 -0.179951 -0.976799 -0.146365 -0.214829 -0.965622 -0.376923 -0.29659 -0.877476 -0.405014 -0.333169 -0.851447 -0.60831 -0.38717 -0.692862 -0.629798 -0.422845 -0.651581 -0.778283 -0.43951 -0.448449 -0.78903 -0.470934 -0.394529 -0.11322 -0.119438 -0.986365 -0.133045 -0.150756 -0.979577 -0.35511 -0.269797 -0.895045 -0.373036 -0.303271 -0.876853 -0.569801 -0.39799 -0.718979 -0.582741 -0.431127 -0.688871 -0.728389 -0.487031 -0.481923 -0.733553 -0.516612 -0.441601 -0.108197 0.0923981 -0.989826 -0.652263 0.552046 -0.519422 -0.685112 0.547484 -0.480502 -0.508737 0.434381 -0.743303 -0.54215 0.4364 -0.718072 -0.317365 0.276641 -0.907055 -0.346231 0.282078 -0.894738 -0.110801 0.105583 -0.988218 -0.123851 0.104759 -0.986755 -0.325953 -0.266966 -0.906909 -0.338857 -0.292148 -0.89433 -0.520242 -0.421112 -0.742976 -0.531965 -0.449902 -0.717358 -0.665906 -0.535883 -0.519035 -0.672548 -0.563577 -0.479646 -0.102192 -0.0990901 -0.989817 -0.123065 -0.104809 -0.986849 -0.123851 -0.104759 -0.986755 -0.326754 0.361972 -0.873045 -0.489828 0.543413 -0.681741 -0.576785 0.629639 -0.520455 -0.496976 0.605672 -0.621431 -0.425978 0.488322 -0.761633 -0.20946 0.115523 -0.970969 -0.14322 0.173968 -0.974281 -0.0587784 0.0927837 -0.99395 -0.0777964 0.101161 -0.991824 -0.0815319 0.104805 -0.991145 -0.0816313 0.102575 -0.99137 -0.0842097 0.104557 -0.990947 -0.0892446 0.100264 -0.99095 -0.0874734 0.0993596 -0.991199 -0.0991548 0.0997218 -0.990063 -0.100808 0.10063 -0.989804 -0.562174 0.613755 -0.554316 -0.529044 0.642462 -0.554396 -0.528809 0.642389 -0.554705 -0.507053 0.659678 -0.554727 -0.50496 0.65826 -0.55831 -0.516691 0.649158 -0.558233 -0.518869 0.650508 -0.55463 -0.553811 0.620931 -0.554742 -0.56349 0.622636 -0.542958 -0.597103 0.590488 -0.542947 -0.616751 0.591502 -0.519368 -0.421932 0.487812 -0.764207 -0.410046 0.497966 -0.764128 -0.409829 0.497869 -0.764308 -0.392969 0.511254 -0.764326 -0.39106 0.509747 -0.766309 -0.400166 0.502728 -0.766245 -0.402166 0.504207 -0.764223 -0.429237 0.481225 -0.764315 -0.437633 0.48401 -0.757767 -0.463735 0.459063 -0.757767 -0.482743 0.46324 -0.743214 -0.234598 0.327735 -0.915179 -0.255383 0.310152 -0.915743 -0.255234 0.310074 -0.915811 -0.244739 0.318398 -0.91582 -0.243466 0.317312 -0.916536 -0.249135 0.312967 -0.916506 -0.250478 0.314056 -0.915767 -0.267328 0.299713 -0.91581 -0.272724 0.302049 -0.913448 -0.288832 0.28666 -0.913456 -0.303891 0.291611 -0.906981 -0.120333 -0.13598 -0.983377 -0.100494 -0.100979 -0.9898 -0.117635 -0.142881 -0.982724 -0.0976799 -0.0949117 -0.990682 -0.0905626 -0.101714 -0.990683 -0.0900086 -0.100292 -0.990878 -0.0832245 -0.104571 -0.991029 -0.0833122 -0.104738 -0.991004 -0.0815627 -0.106074 -0.991007 -0.0830903 -0.109078 -0.990554 -0.0847582 -0.119377 -0.989225 -0.0317728 -0.0398775 -0.998699 -0.369107 -0.412747 -0.832706 -0.258926 -0.306293 -0.916047 -0.465093 -0.505891 -0.726472 -0.572273 -0.62475 -0.531218 -0.260967 -0.30536 -0.915779 -0.255333 -0.310194 -0.915743 -0.255285 -0.310033 -0.915811 -0.244464 -0.318615 -0.915818 -0.243745 -0.317098 -0.916535 -0.249428 -0.312741 -0.916503 -0.250196 -0.314294 -0.915763 -0.269163 -0.298134 -0.915788 -0.270992 -0.303688 -0.913421 -0.293637 -0.282015 -0.91337 -0.299501 -0.296432 -0.906877 -0.415541 -0.493298 -0.764188 -0.409965 -0.498035 -0.764127 -0.409912 -0.497802 -0.764307 -0.392495 -0.511625 -0.764322 -0.39154 -0.50938 -0.766308 -0.400669 -0.502337 -0.766239 -0.401678 -0.504612 -0.764213 -0.432455 -0.478421 -0.764261 -0.434558 -0.486873 -0.757703 -0.470624 -0.45228 -0.757599 -0.476319 -0.470144 -0.743025 -0.554041 -0.620999 -0.554436 -0.52894 -0.642548 -0.554396 -0.528913 -0.642303 -0.554705 -0.506414 -0.660172 -0.554723 -0.505603 -0.657766 -0.558309 -0.51736 -0.648632 -0.558225 -0.518212 -0.651042 -0.554618 -0.558163 -0.617083 -0.554673 -0.559267 -0.626503 -0.542876 -0.605533 -0.582022 -0.542752 -0.6087 -0.599965 -0.519159 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.999026 0 -0.0441332 0.999464 -0.00374602 -0.0325238 0.999585 -0.000727908 -0.0288075 0.99989 4.31658e-05 -0.0148366 0.999986 -0.000661198 -0.00527792 0.999982 -0.00115527 -0.00590791 1 0 -0.00017583 0.999988 0 -0.00499304 0.999988 -2.61409e-05 -0.00496108 0.999506 5.47746e-05 -0.0314271 0.999508 0 -0.0313713 -0.0523903 -0.154169 -0.986655 0.551764 -0.0678827 -0.831233 0.946832 -0.159017 -0.279683 0.611628 -0.764289 -0.204384 0.425862 -0.890606 -0.15957 0.0241496 -0.672335 -0.739853 0.0431838 -0.748425 -0.661812 0.00459627 -0.826707 -0.562614 -0.0441671 -0.776718 -0.628298 0.00858655 -0.929488 -0.368752 0.159204 -0.983929 -0.0808547 0.226559 -0.965013 -0.131987 0.236589 -0.967216 -0.0922938 0.301342 -0.943264 -0.139453 0.30052 -0.943726 -0.138091 0.330064 -0.934453 -0.133622 0.501198 -0.845779 -0.182917 0.89088 -0.378772 -0.250727 0.873065 -0.424683 -0.239586 0.851637 -0.467171 -0.237626 0.952938 -0.202007 -0.226061 0.944595 -0.230967 -0.233226 0.923572 -0.270663 -0.271581 0.923142 -0.262497 -0.280899 0.923873 -0.107485 -0.367296 0.945152 -0.0705163 -0.318929 0.950185 -0.155806 -0.26995 0.882926 -0.110849 -0.45624 0.636759 -0.108995 -0.76332 0.721468 -0.0320676 -0.691704 0.779975 -0.174911 -0.60087 0.493802 -0.0594123 -0.867542 0.121949 0.0229359 -0.992271 0.0645644 -0.0324176 -0.997387 0.0368059 -0.0280879 -0.998928 0.038438 -0.108936 -0.993305 0.0415497 -0.0276278 -0.998754 0.00843437 -0.0393927 -0.999188 0.0361614 -0.048882 -0.99815 0.03577 -0.313414 -0.948943 0.0510657 -0.338096 -0.939725 -0.0400277 -0.411743 -0.910421 -0.0329935 -0.624134 -0.78062 0.0468891 -0.536209 -0.842782 0.0301202 -0.539779 -0.841268 0.847492 -0.301968 -0.436547 0.873767 -0.25515 -0.414042 0.888469 -0.303429 -0.344316 0.909811 -0.256218 -0.326491 0.704405 -0.518279 -0.484975 0.74489 -0.474901 -0.468623 0.767084 -0.522044 -0.372896 0.799681 -0.479863 -0.360892 0.808246 -0.509995 -0.294354 0.838524 -0.464774 -0.284362 0.842128 -0.486313 -0.233069 0.817777 -0.514765 -0.257407 0.845537 -0.204438 -0.493226 0.888369 -0.124847 -0.441831 0.90433 -0.168801 -0.392039 0.931875 -0.187394 -0.310632 0.914785 -0.233838 -0.329376 0.900854 -0.188034 -0.391287 0.879107 -0.234406 -0.415001 0.837495 -0.135436 -0.529396 0.82748 -0.25134 -0.502101 0.763265 -0.33732 -0.551037 0.957606 -0.117379 -0.263083 0.953282 -0.171066 -0.248976 0.939609 -0.217484 -0.264264 0.926071 -0.28161 -0.251172 0.918324 -0.2934 -0.265703 0.888369 -0.360173 -0.284739 0.880973 -0.328152 -0.340886 0.855576 -0.374758 -0.357137 0.839559 -0.325298 -0.435111 0.808685 -0.371715 -0.455914 0.760388 -0.273563 -0.589044 0.557518 -0.805077 -0.202547 0.588978 -0.786443 -0.186042 0.578517 -0.776215 -0.250618 0.543904 -0.800318 -0.252308 0.516778 -0.784685 -0.34236 0.481707 -0.805237 -0.345763 0.470392 -0.808504 -0.353628 0.311866 -0.876849 -0.365889 0.371907 -0.867308 -0.33085 0.191226 -0.92058 -0.340537 0.268047 -0.915597 -0.299722 0.0705591 -0.949138 -0.306854 0.167515 -0.951745 -0.257139 0.635545 -0.594241 -0.49291 0.681176 -0.553554 -0.479143 0.70956 -0.596991 -0.374334 0.745277 -0.558233 -0.364606 0.75579 -0.585845 -0.292519 0.788665 -0.544823 -0.284914 0.792473 -0.563531 -0.233281 0.782522 -0.574509 -0.239999 0.0417196 -0.966668 -0.25261 0.0287448 -0.964706 -0.261756 0.0319004 -0.982391 -0.184093 0.168184 -0.969646 -0.177487 0.0781609 -0.97072 -0.227142 0.272705 -0.936815 -0.219111 0.19893 -0.944571 -0.261175 0.374467 -0.891799 -0.253908 0.314634 -0.903609 -0.290683 0.433979 -0.854557 -0.285298 0.226156 -0.965189 -0.13139 0.344345 -0.929386 -0.132922 0.289026 -0.942625 -0.167098 0.401225 -0.900237 -0.169089 0.41086 -0.901434 -0.136419 0.381835 -0.910385 -0.159379 0.463367 -0.866104 -0.187498 0.50275 -0.848206 -0.166698 0.489356 -0.842303 -0.225955 0.448756 -0.864432 -0.226661 0.458444 -0.861103 -0.219843 0.306289 -0.925558 -0.222553 0.365232 -0.912204 -0.185715 0.196225 -0.962365 -0.188014 0.266049 -0.952694 -0.14694 0.109024 -0.982512 -0.150943 0.137849 -0.980393 -0.140809 0.0507744 -0.993865 -0.0982598 0.00768636 -0.985908 -0.167112 0.663792 -0.716224 -0.215415 0.665069 -0.715183 -0.214936 0.658677 -0.702847 -0.268609 0.62362 -0.732924 -0.271883 0.604258 -0.712951 -0.355771 0.563144 -0.743123 -0.361437 0.530277 -0.722637 -0.443399 0.415624 -0.785828 -0.457965 0.462943 -0.77608 -0.428233 0.299466 -0.845275 -0.442528 0.361159 -0.837878 -0.409298 0.177921 -0.890845 -0.418019 0.257454 -0.888604 -0.379605 0.0627385 -0.921694 -0.382811 0.162867 -0.927611 -0.336174 0.0172514 -0.941249 -0.337274 0.0728 -0.950005 -0.303628 0.73018 -0.643533 -0.22957 0.733452 -0.640327 -0.228099 0.728818 -0.624879 -0.27991 0.694331 -0.660729 -0.285206 0.680381 -0.636595 -0.363082 0.641803 -0.671343 -0.370658 0.604139 -0.633015 -0.484054 0.570848 -0.657668 -0.491534 0.54523 -0.664599 -0.510914 0.398922 -0.746389 -0.532695 0.448555 -0.738193 -0.503854 0.279963 -0.808353 -0.517866 0.344669 -0.802907 -0.486358 0.160688 -0.855862 -0.49161 0.242708 -0.856068 -0.456334 0.0533204 -0.889486 -0.453841 0.154364 -0.897941 -0.412158 0.0390199 -0.911352 -0.409775 0.0278393 -0.90362 -0.427429 0.297215 0.650962 -0.698507 0.384645 -0.0507611 -0.921668 0.274032 -0.0225414 -0.961456 0.240687 -0.0547496 -0.969057 0.194244 -0.0568172 -0.979306 0.124319 -0.0947801 -0.987705 0.148738 -0.0953498 -0.984269 0.0287088 -0.167191 -0.985506 0.119526 -0.166711 -0.978734 0.0373689 -0.222019 -0.974326 0.131389 -0.244974 -0.960585 0.447935 -0.0706633 -0.891269 0.426701 -0.0829107 -0.900584 0.416974 -0.082207 -0.905193 0.325686 -0.133913 -0.935946 0.333043 -0.134272 -0.933302 0.21613 -0.199706 -0.955722 0.259391 -0.200776 -0.944672 0.106257 -0.288751 -0.95149 0.198294 -0.289031 -0.936558 0.0179328 -0.393406 -0.91919 0.139926 -0.394037 -0.908381 0.035511 -0.454111 -0.890237 0.132492 -0.479298 -0.867594 0.770713 -0.0661034 -0.633744 0.670895 -0.160528 -0.723969 0.676193 -0.163 -0.718466 0.562728 -0.252192 -0.787233 0.57779 -0.252436 -0.776167 0.473621 -0.324373 -0.818819 0.503649 -0.323894 -0.800894 0.36778 -0.408365 -0.835449 0.419293 -0.406434 -0.811791 0.248479 -0.499737 -0.829772 0.32354 -0.497546 -0.804841 0.13709 -0.58421 -0.799941 0.23068 -0.585032 -0.777511 0.0465256 -0.656084 -0.753252 0.152544 -0.662264 -0.733578 0.0218406 -0.705119 -0.708753 0.0392666 -0.710979 -0.702116 0.0314421 -0.796948 -0.603229 0.113141 -0.779392 -0.616236 0.00548313 -0.767274 -0.641296 0.179642 -0.722961 -0.667125 0.0842063 -0.717755 -0.691185 0.267623 -0.655374 -0.706303 0.184566 -0.655938 -0.731903 0.367831 -0.575902 -0.730094 0.301126 -0.579842 -0.757038 0.468009 -0.489288 -0.735911 0.419617 -0.493356 -0.761919 0.554058 -0.405921 -0.726807 0.522505 -0.408318 -0.748509 0.626754 -0.329749 -0.706006 0.607779 -0.330678 -0.721981 0.718895 -0.231861 -0.65531 0.707837 -0.226881 -0.668949 0.803182 -0.121618 -0.583187 0.813745 -0.127153 -0.567143 0.826718 -0.0933448 -0.55482 0.852383 -0.0558341 -0.519928 0.0163042 -0.632633 -0.77428 0.122185 -0.588625 -0.799119 0.00326409 -0.58264 -0.812724 0.187398 -0.49882 -0.846203 0.0805045 -0.497298 -0.863837 0.266993 -0.401834 -0.875925 0.182247 -0.402408 -0.897136 0.350589 -0.308636 -0.884212 0.299556 -0.308542 -0.902811 0.430929 -0.231175 -0.872272 0.408358 -0.230519 -0.883236 0.508517 -0.168087 -0.844486 0.502918 -0.167759 -0.847898 0.597448 -0.103985 -0.795137 0.632558 -0.106037 -0.76722 0.96553 -0.0843926 -0.246232 0.957886 -0.125311 -0.258364 0.951925 -0.105868 -0.287457 0.934973 -0.166229 -0.313358 0.92011 -0.119985 -0.372829 0.924783 -0.114828 -0.362755 0.911523 -0.0788315 -0.403623 0.888372 -0.0896751 -0.450281 0.881395 -0.067999 -0.46746 0.825963 -0.161656 -0.540048 0.832879 -0.16642 -0.527841 0.735817 -0.289124 -0.612357 0.749376 -0.294687 -0.592955 0.640994 -0.400695 -0.654653 0.660662 -0.398237 -0.636344 0.558439 -0.480529 -0.676193 0.588774 -0.47628 -0.653072 0.458282 -0.564168 -0.686798 0.502605 -0.558346 -0.660029 0.342009 -0.645629 -0.682784 0.40172 -0.640174 -0.654827 0.222978 -0.715306 -0.662283 0.297838 -0.713241 -0.634492 0.114888 -0.770171 -0.627405 0.204164 -0.774049 -0.599304 0.0254358 -0.812723 -0.582095 0.129645 -0.824167 -0.551308 0.0153635 -0.842519 -0.538448 0.0639702 -0.852704 -0.518462 0.915637 -0.320917 -0.242116 0.882874 -0.409555 -0.229779 0.879074 -0.386333 -0.279241 0.852223 -0.434476 -0.291456 0.84457 -0.402882 -0.352687 0.815409 -0.44774 -0.366929 0.797092 -0.398597 -0.453613 0.761514 -0.443849 -0.472329 0.733967 -0.392923 -0.553988 0.664516 -0.462069 -0.587292 0.683928 -0.458048 -0.567833 0.584459 -0.542167 -0.603708 0.612876 -0.536296 -0.580319 0.487401 -0.623422 -0.61138 0.527631 -0.616157 -0.58477 0.374443 -0.700333 -0.607722 0.428154 -0.693523 -0.579405 0.254505 -0.765415 -0.591072 0.323362 -0.761748 -0.561406 0.139738 -0.815794 -0.561208 0.225068 -0.818033 -0.529308 0.0413687 -0.853274 -0.519819 0.143266 -0.863472 -0.483622 0.0218972 -0.879256 -0.475847 0.0301759 -0.881467 -0.471281 0.119522 0.16668 -0.97874 0.122189 0.588607 -0.799131 0.735948 0.351102 -0.578885 0.0351039 0.0282374 -0.998985 0.160494 0.266816 -0.95029 -0.0476788 0.399731 -0.915391 0.0492991 0.714586 -0.697808 0.580098 0.788615 -0.203896 0.732285 0.641874 -0.2275 0.912549 0.273612 -0.30396 0.963608 0.10597 -0.245418 0.944436 0.240298 -0.224271 0.955334 0.174231 -0.238705 0.95345 0.170424 -0.248774 0.917606 0.309895 -0.248926 0.869904 0.43125 -0.239355 0.877994 0.41296 -0.242057 0.800385 0.550939 -0.236328 0.229186 0.972084 -0.0502671 0.342721 0.916752 -0.205204 0.303392 0.943852 -0.130757 0.384814 0.91263 -0.137929 0.404813 0.900786 -0.157197 0.0343658 0.98529 -0.167397 0.0280672 0.964719 -0.26178 0.0214659 0.963646 -0.266318 0.0326916 0.947544 -0.317949 -0.0221521 0.846045 -0.532652 0.0699564 0.893433 -0.443715 -0.000906948 0.880739 -0.473602 0.0630766 0.926828 -0.370149 -0.0284577 0.913497 -0.405848 0.0399025 0.940448 -0.337587 0.0403507 0.545514 -0.83713 0.0403891 0.545504 -0.837135 -0.0756086 0.663711 -0.744158 0.0146665 0.624217 -0.781114 0.0248949 0.67599 -0.736491 0.0217428 0.0371764 -0.999072 0.0150429 0.0457104 -0.998842 0.0364618 0.107489 -0.993537 0.648606 0.116564 -0.752145 0.634759 0.106334 -0.765359 0.694725 0.0592352 -0.716832 0.804884 0.113984 -0.582382 0.888115 0.095462 -0.449598 0.905325 0.0802856 -0.417062 0.957245 0.122957 -0.261846 0.955174 0.115937 -0.272398 0.949021 0.117433 -0.292521 0.945625 0.0765586 -0.316122 0.928215 0.0979606 -0.358916 0.837186 0.458957 -0.297453 0.841892 0.48414 -0.238384 0.843898 0.481522 -0.236586 0.685367 0.694199 -0.219911 0.733556 0.64064 -0.226884 0.72666 0.618876 -0.298257 0.809572 0.516294 -0.279345 0.797335 0.473141 -0.374692 0.879201 0.322017 -0.351156 0.889363 0.36605 -0.273938 0.877856 0.380823 -0.290418 0.88199 0.402386 -0.245313 0.900697 0.367849 -0.231153 0.635144 0.745025 -0.203787 0.664523 0.714 -0.220482 0.655535 0.697226 -0.290087 0.757683 0.592006 -0.274674 0.742252 0.551381 -0.380842 0.817477 0.454759 -0.353449 0.801168 0.408081 -0.43772 0.824137 0.218386 -0.522595 0.769988 0.290394 -0.568146 0.822004 0.410188 -0.395038 0.922559 0.266649 -0.278895 0.922432 0.266172 -0.279769 0.930917 0.26053 -0.255964 0.918972 0.212216 -0.332347 0.928063 0.209229 -0.308095 0.909735 0.149173 -0.387465 0.929212 0.152436 -0.336644 0.919616 0.0999518 -0.379889 0.914249 0.0855352 -0.396021 0.850044 0.160868 -0.501545 0.891259 0.279084 -0.357449 0.853095 0.255177 -0.455097 0.869013 0.300688 -0.392941 0.817333 0.275248 -0.506168 0.857268 0.381558 -0.345695 0.695436 0.195676 -0.691433 0.113141 0.779384 -0.616247 -0.0837346 0.811968 -0.577664 0.134907 0.863687 -0.485638 0.682462 0.266879 -0.680457 0.607803 0.330645 -0.721976 0.672683 0.414589 -0.612873 0.704959 0.356427 -0.613182 0.67073 0.470335 -0.573503 0.0584383 0.0978253 -0.993486 -0.0279101 0.155682 -0.987413 0.0582217 0.208178 -0.976357 -0.00189092 0.302987 -0.952993 0.139934 0.394007 -0.908393 0.0499597 0.446194 -0.893541 0.0293712 0.489015 -0.87178 0.39302 0.710624 -0.583565 0.409076 0.683711 -0.604314 0.363934 0.658652 -0.658581 0.379546 0.627696 -0.679664 0.301143 0.579817 -0.757051 0.46802 0.489263 -0.735921 0.367789 0.408332 -0.835462 0.503656 0.323858 -0.800904 0.408379 0.230493 -0.883233 0.508538 0.168063 -0.844478 0.426722 0.0828862 -0.900576 0.460645 0.0632112 -0.885331 0.0480945 0.0398829 -0.998046 0.0561814 0.0261433 -0.998078 0.148726 0.0953249 -0.984273 0.0287066 0.167159 -0.985512 0.198289 0.288998 -0.936569 0.0179295 0.393375 -0.919203 0.187403 0.498797 -0.846216 0.00326323 0.582622 -0.812737 0.152546 0.662248 -0.733592 0.0210118 0.705333 -0.708565 0.0433828 0.748512 -0.6617 -0.0442105 0.777633 -0.627163 0.18808 0.820786 -0.539385 0.401243 0.900228 -0.169099 0.329881 0.928935 -0.168102 0.30267 0.943824 -0.132617 0.226168 0.965185 -0.1314 0.224342 0.965975 -0.128698 0.161458 0.982582 -0.0919997 0.293163 0.0153534 -0.955939 0.243374 0.0569917 -0.968257 0.333054 0.134244 -0.933302 0.216142 0.199676 -0.955726 0.350598 0.308606 -0.884219 0.182261 0.402375 -0.897148 0.32356 0.497518 -0.80485 0.137096 0.584191 -0.799954 0.267634 0.655356 -0.706315 0.0842087 0.717742 -0.691199 0.164848 0.757549 -0.631621 0.152001 0.788211 -0.596339 0.189117 0.804328 -0.563287 0.173622 0.83098 -0.528515 0.209489 0.845018 -0.491995 0.19177 0.868365 -0.457347 0.226458 0.880136 -0.417225 0.206665 0.900793 -0.381919 0.239248 0.909787 -0.339187 0.217583 0.927898 -0.302759 0.107031 0.959714 -0.259795 0.127982 0.943366 -0.306075 0.10174 0.9358 -0.33753 0.120435 0.915681 -0.383436 0.0941664 0.906479 -0.411616 0.109851 0.882991 -0.456354 0.0842175 0.872807 -0.480744 0.0965318 0.845865 -0.52459 0.0712928 0.834967 -0.545662 0.0799351 0.803853 -0.589433 0.005481 0.767264 -0.641308 0.179648 0.722949 -0.667137 0.0465277 0.656068 -0.753266 0.230679 0.585013 -0.777526 0.0804999 0.497274 -0.863851 0.266998 0.401802 -0.875938 0.106266 0.288717 -0.951499 0.25939 0.200748 -0.944678 0.124326 0.0947554 -0.987707 0.195642 0.0560265 -0.979074 0.145539 -0.00978817 -0.989304 0.482318 0.72016 -0.498737 0.42998 0.792579 -0.432362 0.487743 0.813614 -0.316447 0.406681 0.843458 -0.350983 0.572362 0.748195 -0.335569 0.502156 0.7029 -0.503756 0.642877 0.601769 -0.473903 0.593529 0.551307 -0.58633 0.604008 0.527067 -0.597808 0.56894 0.491138 -0.659614 0.578585 0.465644 -0.669639 0.52251 0.408291 -0.74852 0.626763 0.329718 -0.706013 0.56274 0.252161 -0.787235 0.674035 0.164852 -0.72007 0.67315 0.158601 -0.722299 0.752818 0.0847137 -0.652755 0.744586 0.0548966 -0.665265 0.0850082 0.990332 -0.109619 0.120773 0.984018 -0.130851 0.131208 0.979845 -0.150627 0.217192 0.964748 -0.148623 0.242667 0.951722 -0.187983 0.321907 0.928142 -0.186894 0.348256 0.910626 -0.222436 0.443685 0.868658 -0.220403 0.456065 0.860619 -0.226582 0.551344 0.803681 -0.223868 0.508257 0.778942 -0.36732 0.647847 0.677414 -0.348432 0.596787 0.625453 -0.502647 0.457269 0.741985 -0.490269 0.56423 0.677059 -0.472479 0.500588 0.633131 -0.590387 0.514453 0.606553 -0.606162 0.473835 0.576116 -0.666011 0.487245 0.546548 -0.681086 0.419646 0.493328 -0.761921 0.554084 0.405893 -0.726803 0.473639 0.324336 -0.818824 0.577797 0.252405 -0.776172 0.502932 0.167734 -0.847894 0.597724 0.103772 -0.794958 0.559065 0.0588781 -0.827031 0.521684 0.834394 -0.177857 0.586573 0.784124 -0.202685 0.573802 0.771299 -0.275409 0.697261 0.666377 -0.264138 0.676205 0.629897 -0.382068 0.769852 0.529101 -0.356903 0.753166 0.490958 -0.437837 0.77775 0.415648 -0.471531 0.768613 0.397012 -0.501613 0.843692 0.291143 -0.451021 0.814461 0.223745 -0.535342 0.857525 0.156669 -0.490006 0.287887 -0.715524 -0.636511 0.394108 0.0598607 -0.917113 0.416975 0.0821809 -0.905195 0.325693 0.133885 -0.935948 0.430935 0.231149 -0.872276 0.299572 0.30851 -0.902817 0.419302 0.406401 -0.811803 0.248486 0.499709 -0.829787 0.367837 0.575878 -0.73011 0.184567 0.65592 -0.731918 0.267603 0.699363 -0.662782 0.25225 0.730237 -0.63492 0.296683 0.750754 -0.59021 0.280044 0.777376 -0.563261 0.320606 0.794235 -0.516143 0.302694 0.817957 -0.489206 0.339198 0.83125 -0.440418 0.319921 0.852857 -0.412658 0.375068 0.867933 -0.325602 0.384279 0.862329 -0.329725 0.331799 0.907798 -0.25654 0.246221 0.933656 -0.260118 0.222633 0.949274 -0.222065 0.132675 0.965094 -0.225811 0.110599 0.977297 -0.180716 -0.00380273 0.982682 -0.185261 0.0269056 0.990267 -0.136555 0.455207 0.875408 -0.162629 0.499461 0.84696 -0.1822 0.482283 0.838332 -0.254171 0.628327 0.737606 -0.247271 0.598321 0.70666 -0.377682 0.713557 0.603758 -0.355406 0.68119 0.553531 -0.479149 0.653081 0.592675 -0.471404 0.693261 0.50175 -0.517336 0.75659 0.433918 -0.48917 0.714752 0.361735 -0.598563 0.783896 0.282982 -0.552655 0.736626 0.197887 -0.646701 0.786275 0.142449 -0.601232 0.790315 0.0789584 -0.607592 0.828366 0.0932978 -0.552363 0.858804 0.0374035 -0.510936 0.875553 0.115253 -0.469173 0.882471 0.110807 -0.457129 0.90127 0.159411 -0.402865 0.922909 0.159065 -0.350623 0.877064 0.264395 -0.401066 0.890016 0.309956 -0.334363 0.842616 0.396441 -0.364463 0.853298 0.440622 -0.278812 0.78706 0.53878 -0.300422 0.79215 0.561236 -0.239818 0.773765 0.58893 -0.233342 0.0023005 0.62428 -0.781197 -0.00327434 0.579131 -0.815228 -0.00197563 0.676151 -0.73676 0 0.659647 -0.751576 0 0.715444 -0.69867 0.00454701 0.691971 -0.721911 -0.00826008 0.778277 -0.627867 0.00472313 0.747236 -0.664542 0.000291701 0.795253 -0.606278 -0.00096343 0.836853 -0.547426 -0.00307311 0.842661 -0.538436 0.000274809 0.872799 -0.48808 0.00358621 0.960701 -0.277561 0.00128525 0.960998 -0.276553 -0.000558247 0.896321 -0.443406 -0.00389795 0.907509 -0.420014 0.00219722 0.929356 -0.369178 -0.000320844 0.941805 -0.33616 -8.6973e-08 0.94842 -0.317016 8.86732e-07 0.962422 -0.271559 0.00347571 0.966906 -0.255111 0.00530181 0.969025 -0.246908 0.0102492 0.972256 -0.233696 -0.0117846 0.964163 -0.265051 0.00459666 0.98456 -0.174986 0.0150802 0.985925 -0.166509 0 0.545945 -0.837821 0 0.489226 -0.872157 -0.00404733 0.43697 -0.899467 0.000955861 0.400181 -0.916436 -0.000169486 0.332613 -0.943063 0.00122178 0.270374 -0.962755 0.00069429 0.265872 -0.964008 -0.0006762 0.155728 -0.9878 -1.40212e-05 0.161126 -0.986934 0.0100606 0.0457169 -0.998904 -0.0325042 0.0979969 -0.994656 0.00368529 0.0640722 -0.997939 -0.00473803 0.0831101 -0.996529 9.42619e-06 0.0693495 -0.997593 -0.00441325 0.042461 -0.999088 -0.00797031 0.0276027 -0.999587 0 0.00800305 -0.999968 -0.00104554 0.00359383 -0.999993 0.00377295 0.0559933 -0.998424 0.0183053 0.0978063 -0.995037 0.00147846 -0.965141 -0.261726 0.011461 -0.0489042 -0.998738 0.00291685 -0.0583096 -0.998294 0 -0.00793036 -0.999969 0.0105907 -0.0528169 -0.998548 -0.0108613 -0.0138015 -0.999846 -0.00677858 -0.0255463 -0.999651 -0.00363605 -0.0400175 -0.999192 -0.00164627 -0.0536802 -0.998557 -0.000149115 -0.0666733 -0.997775 0.000287685 -0.15538 -0.987855 0.000145219 -0.154362 -0.988014 4.15536e-05 -0.246939 -0.969031 7.42507e-05 -0.247452 -0.9689 5.86033e-05 -0.314012 -0.949419 3.03505e-05 -0.313654 -0.949537 3.84861e-05 -0.426161 -0.904647 -0.00254913 -0.412068 -0.91115 4.09135e-05 -0.483612 -0.875282 4.09678e-05 -0.527815 -0.84936 0.000916409 -0.536776 -0.843724 -0.00180294 -0.624486 -0.781034 -0.000800299 -0.620253 -0.784401 0 -0.672498 -0.740099 0 -0.68871 -0.725037 0.00171333 -0.711495 -0.702689 -0.00462597 -0.756064 -0.654481 0.000578164 -0.777348 -0.629071 -0.000828549 -0.842951 -0.53799 -0.00788063 -0.826764 -0.562494 -0.00165069 -0.854889 -0.518808 0.0017903 -0.888385 -0.459097 0.00361042 -0.972479 -0.232962 0.0186836 -0.985672 -0.167636 0.00897359 -0.985408 -0.169972 -0.0225019 -0.967951 -0.250128 0.00973711 -0.976859 -0.213663 0.00524227 -0.974048 -0.22628 2.70489e-05 -0.882134 -0.470998 2.69327e-05 -0.904273 -0.426955 -0.0014563 -0.916598 -0.399808 0.00221572 -0.929592 -0.368584 -0.00140649 -0.946845 -0.321688 1.60716e-05 -0.953313 -0.301984 1.67035e-05 -0.965976 -0.258631 0.00206746 -0.970556 -0.240868 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.311367 0.00485031 0.950277 -0.352708 -0.00461001 0.935722 -0.0878878 -0.000106148 0.99613 -0.324439 0.00362011 0.9459 -0.304309 -0.00366435 0.952566 -0.304821 -0.00434829 0.9524 -0.290771 0.00423168 0.956783 -0.287547 0.00821088 0.957731 -0.259214 -0.00887683 0.965779 -0.250828 0.00178935 0.96803 -0.238729 -6.93221e-05 0.971086 -0.228018 0.000208324 0.973657 -0.220791 0.00610842 0.975302 -0.209092 0.000809757 0.977896 -0.180381 -0.000931547 0.983596 -0.0784523 -0.00132164 0.996917 -0.0866152 0.0111177 0.99618 -0.0829671 0.00612988 0.996533 -0.0865429 -0.0147246 0.996139 -0.0576536 0.0107709 0.998279 -0.0523622 -0.00528392 0.998614 -0.0376708 0.00771337 0.99926 -0.0434728 -0.0041414 0.999046 -0.0390231 0.00291584 0.999234 -0.0334678 -0.00241147 0.999437 -0.0279264 0.00211773 0.999608 -0.0301891 -0.0010636 0.999544 -0.0302935 -0.00239095 0.999538 -0.0313134 -0.00472467 0.999498 -0.0306281 -0.0137418 0.999436 -0.0308165 0 0.999525 -0.031412 -0.000887792 0.999506 -0.0356032 -0.00724121 0.99934 -0.0791823 0.00261008 0.996857 -0.0765527 0.00102051 0.997065 -0.0599318 -0.00447511 0.998192 -0.0708006 0.00287745 0.997486 -0.0301063 -0.0151041 0.999433 -0.0501735 0.0107755 0.998682 -0.0375647 -0.00329879 0.999289 -0.0352726 0.00551395 0.999363 -0.036681 -0.00225888 0.999325 -0.0368636 -0.00264343 0.999317 -0.0140143 0.00210659 0.9999 -0.0704491 -0.000124665 0.997515 -0.0614352 0.000939955 0.998111 -0.0632958 -0.00282253 0.997991 -0.0116234 0.0727176 0.997285 0.47735 0.830517 0.287016 0.0320214 0.0901991 0.995409 -0.00554285 0.020275 0.999779 -0.0107511 0.00664087 0.99992 -0.0109501 0.00243932 0.999937 -0.01013 0.000855368 0.999948 -0.00948397 0.000342561 0.999955 -0.0094211 0.000307013 0.999956 -0.00800306 -0.000304404 0.999968 -0.00765606 -0.000212526 0.999971 -0.0105205 -0.0011137 0.999944 -0.0682241 -0.000364106 0.99767 -0.0644934 -0.00897972 0.997878 -0.068245 0.000425699 0.997669 -0.0443211 -8.55576e-05 0.999017 -0.0550657 0.000198611 0.998483 -0.0596789 0.00595633 0.9982 -0.0663811 -0.00290712 0.99779 -0.0134662 -0.00235995 0.999907 -0.0176426 -0.00494862 0.999832 -0.0234906 -0.0105145 0.999669 -0.00642984 0 0.999979 -0.00697188 -0.000212132 0.999976 -0.00905647 0.000863203 0.999959 -0.00654892 -0.000925982 0.999978 -0.00586101 -0.00276721 0.999979 -0.00313351 -0.00775774 0.999965 -0.0249283 0.00715664 0.999664 -0.00369613 -0.00711384 0.999968 -0.0401293 0.00284308 0.99919 0.0851598 -0.0732758 0.993669 -0.0288273 -0.00509502 0.999571 -0.0180636 0.0037149 0.99983 -0.0132819 0.00194201 0.99991 -0.00605915 -7.13351e-05 0.999982 -0.00425875 0.00278253 0.999987 -0.00486885 0.000683325 0.999988 -0.00476158 -2.45149e-06 0.999989 -0.00476142 0 0.999989 -0.00476158 2.45192e-06 0.999989 -0.00486787 -0.000677221 0.999988 -0.00507111 2.76309e-05 0.999987 -0.00781771 -0.0016871 0.999968 -0.00992597 -0.00371521 0.999944 -0.0125547 -0.00821377 0.999887 -0.0153928 -0.018747 0.999706 -0.0135786 0.00416276 0.999899 -0.010584 0.00212761 0.999942 -0.00850476 0.000933096 0.999963 -0.00657359 0.000157032 0.999978 -0.00718143 0 0.999974 -0.0080828 -0.000818298 0.999967 -0.00869391 -0.00219716 0.99996 -0.00895927 -0.00348651 0.999954 -0.00890866 -0.00670664 0.999938 -0.00697587 -0.0130608 0.99989 -0.0558713 -0.00186675 0.998436 -0.057904 0.00122715 0.998321 -0.0446846 -0.000691029 0.999001 -0.044472 -0.000780399 0.99901 -0.0356381 0.000729091 0.999365 -0.0378457 -0.000876923 0.999283 -0.0263851 0.0010306 0.999651 -0.0139339 0.00404878 0.999895 -0.0462412 0.00245051 0.998927 -0.0403488 -0.00227988 0.999183 -0.0554957 0.00150251 0.998458 -0.0104602 0.00216517 0.999943 -0.0128373 0.00514611 0.999904 -0.00916217 0.00643284 0.999937 -0.0586497 0.00125106 0.998278 -0.0582039 0.000325817 0.998305 -0.0480083 -0.000127587 0.998847 -0.0445439 0.000981643 0.999007 -0.0379056 -0.000938816 0.999281 -0.0253178 0.00181231 0.999678 -0.00994875 -0.00576964 0.999934 -0.0252102 0.00857627 0.999645 -0.0186117 0.00422516 0.999818 -0.070463 0.000712854 0.997514 -0.0108155 0.00104251 0.999941 -0.00761572 0.000215878 0.999971 -0.00798704 0.000299116 0.999968 -0.00988867 -0.000274407 0.999951 -0.00997617 -0.00030691 0.99995 -0.0108641 -0.000726172 0.999941 -0.0123331 -0.00190653 0.999922 -0.0137974 -0.00475243 0.999894 -0.0141621 -0.0124593 0.999822 -0.00928 -0.0360354 0.999307 -0.0530619 -0.0298159 0.998146 -0.0636716 0.0032846 0.997966 -0.022276 -0.0512596 0.998437 0.0141172 -0.108504 0.993996 -0.0340465 0.00572275 0.999404 -0.0323266 0.00222914 0.999475 -0.0356093 0 0.999366 -0.0367775 0.00246199 0.99932 -0.0371358 -0.0033171 0.999305 -0.0370946 0.00326463 0.999306 -0.0302968 0.00531584 0.999527 -0.022193 0.019391 0.999566 -0.043757 -0.00767807 0.999013 -0.0460958 -0.0118954 0.998866 -0.0381411 0.00385883 0.999265 -0.0577188 -0.0126153 0.998253 -0.0155263 0.0277756 0.999494 -0.0638509 0.00121385 0.997959 -0.0307881 0.00107649 0.999525 -0.0292025 -0.00204086 0.999571 -0.0332958 0.00189621 0.999444 -0.0424423 -0.00134082 0.999098 -0.040493 0.000847517 0.999179 -0.0559887 -0.00132485 0.998431 -0.0571223 0.00449734 0.998357 -0.0590235 -0.000579244 0.998256 -0.0759496 0.000208112 0.997112 -0.0798206 -0.000547138 0.996809 -0.0979108 0.00142254 0.995194 -0.100788 -0.00199861 0.994906 -0.118866 0.000657865 0.99291 -0.121675 0.000155488 0.99257 -0.139468 -0.000684207 0.990226 -0.140223 -0.00389325 0.990112 -0.168716 0.00169578 0.985663 -0.18193 -0.00489808 0.983299 -0.0764161 -0.000468129 0.997076 -0.0819478 -0.00387618 0.996629 -0.0859732 -0.00882075 0.996258 -0.0866194 -0.00511299 0.996228 -0.0890303 0.00196685 0.996027 -0.186389 -0.00082942 0.982476 -0.084078 -0.0102 0.996407 -0.0820755 -0.00151366 0.996625 -0.1072 0.00130945 0.994237 -0.105834 -0.00516429 0.99437 -0.125113 0.0115177 0.992076 -0.141218 -0.019403 0.989788 -0.143607 0.0005413 0.989635 -0.317845 0.0277041 0.947738 -0.28334 -0.0267246 0.958647 -0.190969 -0.0270257 0.981224 -0.189622 -0.00625462 0.981837 -0.218916 0.00509584 0.97573 -0.219268 0.00688277 0.97564 -0.261285 -0.00665196 0.965239 -0.273657 0.0440287 0.960819 -0.37854 0.000638957 0.925584 -0.377798 0.000183918 0.925888 -0.312294 -0.0182996 0.949809 -0.334409 0.00873245 0.942388 -0.358318 -0.0109597 0.933535 -0.365164 -0.000191737 0.930943 -0.377904 7.65928e-05 0.925845 -0.374026 -0.000767339 0.927418 -0.365565 0.0027551 0.930782 -0.36018 0.00701966 0.932857 -0.348296 -0.00229227 0.937382 -0.325825 0.00195579 0.945428 -0.322879 0.000306833 0.94644 -0.290473 -0.000563127 0.956883 -0.278763 -0.0113175 0.960293 -0.260311 -0.00223754 0.965522 -0.230335 0.00299237 0.973107 -0.225494 1.72181e-06 0.974245 -0.206446 1.98765e-07 0.978458 -0.18996 -0.000704913 0.981792 -0.187154 0.000911711 0.98233 -0.158881 -0.000628011 0.987298 -0.130056 -0.011876 0.991435 -0.106271 0.0135269 0.994245 -0.0289855 -0.0228099 0.99932 -0.0548716 0.0379536 0.997772 -0.0212814 0.00811887 0.999741 -0.0170266 0.00488154 0.999843 -0.0138716 0.00290546 0.9999 -0.00108153 -0.00348424 0.999993 -0.00934489 0.00422112 0.999947 -0.00747511 0.00273576 0.999968 -0.0060537 0.00177176 0.99998 -0.00486318 0.00107321 0.999988 -0.00360617 0.000420323 0.999993 -0.00271965 0 0.999996 -0.00438361 0.000437142 0.99999 -0.000517423 0 1 -0.377869 -0.000215335 0.925859 -0.371513 0.00117996 0.928427 -0.366274 0.00712322 0.93048 -0.363533 0.00484192 0.931569 -0.342678 -0.00606824 0.939433 -0.345137 -0.00349737 0.938546 -0.325514 0.00235862 0.945534 -0.354767 -0.00176467 0.934953 -0.371886 0.000222526 0.928278 -0.377252 -0.00113012 0.92611 -0.377217 -0.00117514 0.926124 -0.379308 0.000248266 0.925271 -0.319667 0.0138451 0.947429 -0.282169 -0.00907711 0.959322 -0.250375 0.0102707 0.968094 -0.229726 -0.00265079 0.973252 -0.212087 -3.19713e-07 0.977251 -0.206396 -9.58415e-08 0.978469 -0.169215 0.00163082 0.985578 -0.186789 0.0244126 0.982097 -0.158288 0.00583259 0.987376 -0.00624896 0 0.999981 -0.00327842 -0.000431524 0.999995 -0.00350039 -0.000366182 0.999994 -0.000699085 0 1 -0.00436732 -0.000772788 0.99999 -0.00686752 -0.00222049 0.999974 -0.004456 -0.000334073 0.99999 -0.0143366 8.02511e-05 0.999897 -0.0201863 -0.000713044 0.999796 -0.0286127 -0.0038355 0.999583 -0.0319069 -0.00185683 0.999489 -0.0554654 0.00185494 0.998459 -0.044987 -0.00370498 0.998981 -0.105064 0.0151929 0.994349 -0.0830877 -0.0257992 0.996208 -0.124378 -0.00455021 0.992225 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.889685 0.0730016 -0.450701 0.957958 0.000291626 -0.28691 0.124994 0.00444056 -0.992148 0.11357 -0.00181465 -0.993528 0.122945 0.000805348 -0.992413 0.136144 0.00209049 -0.990687 0.366162 0.0136923 -0.93045 0.223821 -0.00187108 -0.974629 0.209777 0.00274401 -0.977745 0.143094 0.00260277 -0.989706 0.142913 0.00261638 -0.989732 0.947557 0.0165069 -0.319161 0.923467 0.00628807 -0.383627 0.919838 0.013122 -0.392079 0.870103 0.0136596 -0.492681 0.870793 0.0126369 -0.491487 0.830791 0.0142982 -0.556401 0.807509 0.0151697 -0.589661 0.782895 0.00175572 -0.622152 0.741263 0.0180412 -0.670972 0.657156 0.00789299 -0.753713 0.647672 0.0120644 -0.761824 0.566063 0.0129154 -0.824261 0.520349 0.0170013 -0.853785 0.49518 0.00998624 -0.868733 0.381436 0.0102738 -0.924338 0.971792 -0.0372016 -0.232887 0.957666 0.0166341 -0.2874 0.957956 0.000663253 -0.286916 0.965393 0.0860918 -0.246178 0.963045 0.0789135 -0.257522 0.958159 0.0835603 -0.273767 0.94589 0.0769497 -0.315232 0.945557 0.0775393 -0.316085 0.905801 0.0729195 -0.417381 0.915355 0.0688042 -0.396726 0.918608 0.0660198 -0.389616 0.921845 0.069798 -0.381221 0.929831 0.0770385 -0.359831 0.858391 0.0504735 -0.510508 0.870109 0.0703999 -0.487806 0.808029 0.066036 -0.58543 0.801379 0.0609397 -0.595045 0.744559 0.0574212 -0.665083 0.744504 0.0574318 -0.665143 0.0981312 -0.000641855 -0.995173 0.0885018 -0.00458555 -0.996065 0.101934 -0.000150203 -0.994791 0.16095 0.00290197 -0.986958 0.694864 0.0542121 -0.717095 0.656083 0.049303 -0.753077 0.651324 0.0497476 -0.757167 0.536244 0.0434541 -0.842944 0.559254 0.0403658 -0.828013 0.389266 0.030867 -0.920608 0.433633 0.0257654 -0.900721 0.234083 0.0190082 -0.972031 0.293106 0.0112875 -0.956013 0.138222 0.0080834 -0.990368 0.16115 0.00284853 -0.986926 0.146802 0.00745058 -0.989138 0.131975 0.0144412 -0.991148 0.145719 0.00231183 -0.989323 0.0637028 0.00156411 -0.997968 0.0480419 0.00932312 -0.998802 0.00942203 -0.00688014 -0.999932 0.0194004 -0.00244218 -0.999809 0.0309323 0.00033374 -0.999521 0.050477 0.00135193 -0.998724 0.00272144 0 -0.999996 0.0165785 0.00400328 -0.999855 0.0174022 0.00354943 -0.999842 0.0374978 -0.000399752 -0.999297 0.0669185 0.00321619 -0.997753 0.0980653 0.00899216 -0.995139 0.100698 0.00824036 -0.994883 0.96433 0.0724383 -0.254597 0.961602 0.0589387 -0.268043 0.947028 0.0594052 -0.315609 0.946345 0.0575285 -0.317996 0.919056 0.0582816 -0.389795 0.918463 0.0570309 -0.391373 0.870817 0.0579741 -0.488177 0.869823 0.0563939 -0.490131 0.808044 0.0570777 -0.586351 0.124352 0.00815958 -0.992205 0.123654 0.00628132 -0.992306 0.209776 0.00734471 -0.977722 0.234088 0.0155178 -0.972091 0.366145 0.0174738 -0.930394 0.389307 0.0254325 -0.920757 0.520224 0.0268993 -0.853606 0.536461 0.0329655 -0.843281 0.647288 0.0333603 -0.761515 0.656469 0.0372712 -0.753431 0.740804 0.0367917 -0.670713 0.745318 0.0390272 -0.665566 0.80692 0.0381088 -0.58943 0.808838 0.0392134 -0.586723 0.87016 0.0376684 -0.491328 0.870647 0.0383962 -0.490407 0.919245 0.0366203 -0.391979 0.919394 0.0369099 -0.391603 0.947056 0.0356075 -0.319089 0.94733 0.0362848 -0.318197 0.962654 0.0354526 -0.268404 0.964341 0.0430676 -0.261136 0.552095 -0.0385447 -0.83289 0.919925 -0.00492626 -0.392063 0.962444 -0.00777779 -0.271369 0.965634 -0.0328006 -0.257827 0.964447 -0.0353412 -0.261902 0.960571 -0.0724595 -0.268428 0.969729 -0.0585605 -0.237056 0.962946 -0.0829206 -0.256631 0.957958 -0.000291514 -0.28691 0.923406 -0.0130704 -0.383602 0.870778 -0.0136539 -0.491487 0.870114 -0.0126674 -0.492687 0.830791 -0.014298 -0.556401 0.807449 -0.0151716 -0.589742 0.782895 -0.00178789 -0.622152 0.741317 -0.0180478 -0.670912 0.64772 -0.0068128 -0.761848 0.381435 -0.0102738 -0.924339 0.49518 -0.00998617 -0.868733 0.520351 -0.0170018 -0.853783 0.566062 -0.0129161 -0.824261 0.65713 -0.0119528 -0.753682 0.359445 -0.0151869 -0.933043 0.234093 -0.00746264 -0.972186 0.223818 -0.00516887 -0.974617 0.104926 -0.00430014 -0.994471 0.113561 -0.0124074 -0.993454 0.00492047 -0.0026132 -0.999985 0.0173622 -0.00115066 -0.999849 0.0981402 0.0020782 -0.99517 0.0427025 -0.0124645 -0.99901 0.0648311 -0.00795911 -0.997864 0.019709 0.00231047 -0.999803 0.00943321 0.00686375 -0.999932 0.0139464 0 -0.999903 0.14835 -0.00416109 -0.988926 0.152907 -0.00291614 -0.988236 0.101984 0.000138849 -0.994786 0.0881657 0.00469465 -0.996095 0.0981306 0.00054705 -0.995173 0.0501278 -0.00132969 -0.998742 0.0314757 -0.000367559 -0.999504 0.0368101 -0.00770669 -0.999293 0.0424865 0.00138617 -0.999096 0.122361 -0.0106212 -0.992429 0.117692 -0.0165243 -0.992913 0.133409 -0.00855577 -0.991024 0.409533 -0.0261305 -0.911921 0.273984 -0.0185366 -0.961556 0.234094 -0.0105175 -0.972157 0.135246 -0.0069211 -0.990788 0.115502 -0.00292446 -0.993303 0.634736 -0.0316026 -0.772083 0.744689 -0.0553946 -0.665108 0.720903 -0.0579308 -0.69061 0.656089 -0.0490847 -0.753086 0.535839 -0.0581678 -0.842314 0.869745 -0.057824 -0.490101 0.852096 -0.062323 -0.519661 0.807722 -0.0623039 -0.586262 0.828786 -0.0559026 -0.556766 0.789728 -0.0622251 -0.610293 0.918392 -0.0582974 -0.391354 0.915798 -0.062787 -0.396701 0.912405 -0.0642609 -0.404213 0.886198 -0.0662656 -0.458543 0.96617 -0.0757593 -0.246529 0.958287 -0.0834374 -0.273358 0.944744 -0.0767263 -0.318702 0.919234 -0.0369161 -0.391976 0.919405 -0.0366128 -0.391605 0.870133 -0.038411 -0.491318 0.870676 -0.0376514 -0.490414 0.80682 -0.0392518 -0.589492 0.808839 -0.0380604 -0.586797 0.740784 -0.0390667 -0.670606 0.745429 -0.0367472 -0.665572 0.647183 -0.0372908 -0.761422 0.656573 -0.0333644 -0.753524 0.520127 -0.0328599 -0.853457 0.536557 -0.0270489 -0.84343 0.389305 -0.025433 -0.920758 0.389231 -0.034404 -0.920497 0.493785 -0.0189548 -0.869378 0.957956 -0.000657167 -0.286916 0.957993 0.00389559 -0.286765 0.947557 -0.0165067 -0.319161 0.947031 -0.0363022 -0.319084 0.947356 -0.0355903 -0.318197 0.946238 -0.0594241 -0.317966 0.947134 -0.0575017 -0.315644 0.945669 -0.0799007 -0.31516 0.926456 -0.0754028 -0.368772 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 -3.97795e-07 -1 -2.44304e-06 0 -1 0 4.59016e-07 -1 1.66016e-06 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.25402e-05 1 -2.58676e-06 -1.1141e-07 1 -3.13348e-06 1.15653e-07 1 -3.10285e-06 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.510202 -0.136713 -0.849119 -0.373497 -0.373492 -0.84912 -0.136708 -0.510202 -0.84912 -0.136708 0.510202 -0.84912 -0.373497 0.373492 -0.84912 -0.510202 0.136713 -0.849119 -0.222526 -0.974927 0 -0.258817 -0.965917 -0.00438999 -0.467218 -0.884142 0 -0.652299 -0.757962 0 -0.707093 -0.707083 -0.00733035 -0.826228 -0.563337 0 -0.930866 -0.365362 0 -0.965886 -0.258817 -0.00880682 -0.993713 -0.111954 0 -0.993713 0.111954 0 -0.965886 0.258818 -0.00880682 -0.930866 0.365362 0 -0.826228 0.563337 0 -0.707093 0.707083 -0.00733036 -0.222526 0.974927 0 -0.258817 0.965916 -0.00439001 -0.467219 0.884142 0 -0.652299 0.757962 0 -0.159332 0.698077 -0.69807 -0.159334 0.698073 -0.698074 -0.330487 0.625398 -0.706863 -0.461437 0.578616 -0.672518 -0.465283 0.540652 -0.700862 -0.585048 0.398896 -0.706116 -0.680117 0.327532 -0.655869 -0.661919 0.259801 -0.703112 -0.704886 0.0794141 -0.704861 -0.759867 0 -0.650079 -0.704886 -0.0794141 -0.704861 -0.645125 -0.310681 -0.698062 -0.727874 -0.285688 -0.623364 -0.585048 -0.398896 -0.706116 -0.446439 -0.559809 -0.698073 -0.159335 -0.698077 -0.69807 -0.159331 -0.698074 -0.698073 -0.330487 -0.625399 -0.706863 -0.488074 -0.567134 -0.663433 -0.510202 -0.136713 -0.849119 -0.373497 -0.373492 -0.84912 -0.136708 -0.510202 -0.84912 -0.136708 0.510202 -0.84912 -0.373497 0.373492 -0.84912 -0.510202 0.136713 -0.849119 -0.222526 -0.974927 0 -0.258817 -0.965917 -0.00438999 -0.467218 -0.884142 0 -0.652299 -0.757962 0 -0.707093 -0.707083 -0.00733035 -0.826228 -0.563337 0 -0.930879 -0.365327 0 -0.965886 -0.258817 -0.00880378 -0.993707 -0.112007 0 -0.993707 0.112007 0 -0.965886 0.258818 -0.00880378 -0.930879 0.365327 0 -0.826228 0.563337 0 -0.707093 0.707083 -0.00733036 -0.222526 0.974927 0 -0.258817 0.965916 -0.00439001 -0.467219 0.884142 0 -0.652299 0.757962 0 -0.159332 0.698077 -0.69807 -0.159334 0.698073 -0.698074 -0.330487 0.625398 -0.706863 -0.461437 0.578616 -0.672518 -0.465283 0.540652 -0.700862 -0.585048 0.398896 -0.706116 -0.680117 0.327532 -0.655869 -0.661909 0.259769 -0.703133 -0.70486 0.0794489 -0.704883 -0.759867 0 -0.650079 -0.70486 -0.0794489 -0.704883 -0.645109 -0.310673 -0.698081 -0.727897 -0.285666 -0.623346 -0.585048 -0.398896 -0.706116 -0.446439 -0.559809 -0.698073 -0.159335 -0.698077 -0.69807 -0.159331 -0.698074 -0.698073 -0.330487 -0.625399 -0.706863 -0.488074 -0.567134 -0.663433 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.258818 0 -0.965926 0.258818 0.694743 0.69475 0.186158 0.694744 0.694749 0.186157 0.694745 0.508592 0.50859 0.694745 0.508592 0.50859 0.694745 0.186158 0.694748 0.694743 0.186157 0.69475 0.694743 -0.186158 0.69475 0.694744 -0.186157 0.694749 0.694744 -0.508593 0.508591 0.694744 -0.508592 0.508591 0.694743 -0.694751 0.186157 0.694745 -0.694748 0.186158 0 0.965926 0.258818 0 0.965926 0.258818 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.25882 0 -0.965926 0.25882 0.694745 0.694748 0.186156 0.694744 0.694749 0.186157 0.694745 0.508592 0.50859 0.694744 0.508592 0.508592 0.694744 0.186158 0.694749 0.694743 0.186157 0.69475 0.694743 -0.186158 0.69475 0.694744 -0.186157 0.694749 0.694745 -0.508592 0.50859 0.694745 -0.508591 0.50859 0.694745 -0.694748 0.186158 0.694743 -0.69475 0.186157 -0.19502 -0.980419 0.0273172 -0.553513 -0.82905 0.0793751 -0.553845 -0.828892 0.0787028 -0.825502 -0.551937 0.11795 -0.8257 -0.551726 0.117548 -0.971253 -0.193468 0.138698 -0.971357 -0.19321 0.138332 -0.0952522 -0.994646 0.0400674 -0.0675941 -0.997675 0.00873258 -0.0584114 -0.998259 0.0082508 -0.0744394 -0.997141 0.0129487 -0.0424602 -0.998946 0.0174357 -0.0168578 -0.998058 0.0599619 -0.0523442 -0.998567 0.0111416 -0.0825937 -0.99638 0.0201172 -0.153747 -0.949943 0.271974 -0.187018 -0.958587 0.214792 -0.139415 -0.979098 0.148088 -0.302388 -0.952901 0.023244 -0.558161 -0.822267 0.111057 -0.574979 -0.814705 0.0751999 -0.851738 -0.510869 0.116427 -0.847515 -0.515533 0.126273 -0.984282 -0.129473 0.120108 -0.981378 -0.138135 0.133474 -0.989057 -0.0643347 0.132767 -0.332755 -0.937375 0.102966 -0.266136 -0.963387 0.0325247 -0.389348 -0.881589 0.266851 -0.150206 -0.985916 0.0735385 -0.0509023 -0.961811 0.26894 -0.20886 -0.977306 0.0353777 -0.22987 -0.972727 0.0310103 -0.691297 -0.720175 0.0588006 -0.703986 -0.70425 0.0918416 -0.817002 -0.566578 0.107227 -0.819239 -0.562816 0.109935 -0.882104 -0.457417 0.112522 -0.928251 -0.366898 0.0611238 -0.947096 -0.291602 0.134083 -0.993437 0.0328356 0.109567 -0.990449 0.0172063 0.136805 -0.376208 -0.907508 -0.186806 -0.502665 -0.861068 0.076743 -0.603685 -0.793509 0.076869 -0.422631 -0.71305 0.559413 -0.961836 -0.242967 0.125853 -0.892414 -0.450916 0.0165142 -0.974186 0.158855 -0.160398 -0.976728 0.194279 -0.0908737 -0.997803 0.0650574 -0.0125041 -0.980167 -0.194963 -0.0355308 -0.931998 -0.253819 -0.258757 -0.98699 -0.14803 -0.0627521 -0.997803 -0.0650574 -0.0125041 -0.999754 -0.0221666 0 -0.999754 0.0221666 0 -0.790615 -0.560946 -0.245492 -0.822474 -0.549564 -0.146681 -0.734529 -0.678577 -2.65567e-05 -0.356783 -0.934187 2.1234e-05 -0.444156 -0.895949 1.45662e-05 -0.538667 -0.806165 -0.244817 -0.561264 -0.807582 -0.181088 -0.666549 -0.745462 -2.69133e-06 -0.260663 -0.961592 -0.085991 -0.186723 -0.938719 -0.289725 -0.0954355 -0.995436 0 -0.331972 0.943289 1.88639e-05 -0.1897 0.953687 -0.233443 -0.201717 0.932606 -0.299258 -0.0690616 0.997612 0 -0.537535 0.804472 -0.252747 -0.518919 0.842832 -0.142679 -0.420378 0.907349 1.23909e-05 -0.93825 0.345576 0.0162631 -0.869413 0.493073 -0.0316254 -0.81333 0.543455 -0.207728 -0.773963 0.632641 -0.0273363 -0.654551 0.755564 0.0261908 -0.985318 0.170722 0.00180312 -0.995564 0.0762947 -0.0550506 -0.995564 -0.0762943 -0.055051 -0.992781 0 -0.119945 -0.988625 -0.0205939 -0.148987 -0.994679 0.0231369 -0.100393 -0.900681 -0.433743 -0.0253112 -0.828424 -0.475983 -0.295217 -0.927796 -0.366753 -0.068465 -0.962351 -0.27181 4.95265e-05 -0.985835 -0.167718 -2.5598e-05 -0.338798 -0.94084 0.00597234 -0.490923 -0.871196 -0.00347784 -0.608618 -0.763183 -0.21711 -0.627468 -0.761471 -0.16262 -0.750451 -0.660894 0.00649083 -0.165535 -0.907357 -0.386396 -0.216387 -0.948053 -0.233177 -0.0586283 -0.99828 0 -0.382714 0.923867 8.02965e-06 -0.216995 0.950719 -0.221465 -0.252588 0.873538 -0.41609 -0.107851 0.994167 0 -0.704259 0.709882 -0.00934992 -0.602782 0.755866 -0.255579 -0.575047 0.806687 -0.136301 -0.479903 0.877322 -1.84162e-05 -0.958467 0.285198 -0.00199901 -0.91727 0.386745 -0.0950988 -0.884877 0.426132 -0.18816 -0.869384 0.483682 -0.101112 -0.81216 0.583417 0.00459418 -0.985317 0.170723 0.0018031 -0.995564 -0.0762943 -0.0550509 -0.994679 -0.023137 -0.100393 -0.992009 0 -0.12617 -0.994679 0.023137 -0.100393 -0.995564 0.0762943 -0.055051 -0.900681 -0.433743 -0.0253112 -0.828424 -0.475983 -0.295217 -0.927796 -0.366753 -0.068465 -0.962351 -0.271809 5.00127e-05 -0.985835 -0.167718 -2.52976e-05 -0.608617 -0.763183 -0.21711 -0.627468 -0.761472 -0.162621 -0.750451 -0.660894 0.00649083 -0.297248 -0.949288 -0.102451 -0.398516 -0.917158 0.00234961 -0.490925 -0.871195 -0.003481 -0.165538 -0.907358 -0.386391 -0.216387 -0.948053 -0.23318 -0.0586258 -0.99828 0 -0.382714 0.923867 1.12573e-05 -0.216995 0.950719 -0.221462 -0.252588 0.873539 -0.416087 -0.107852 0.994167 0 -0.704259 0.709882 -0.00935185 -0.602782 0.755865 -0.25558 -0.575045 0.806688 -0.136296 -0.479903 0.877322 -1.53512e-05 -0.958467 0.285198 -0.00199901 -0.91727 0.386745 -0.0950988 -0.884877 0.426132 -0.18816 -0.869384 0.48368 -0.101115 -0.81216 0.583417 0.00459259 -0.222519 -0.974928 0 -0.222519 -0.974928 0 -0.623492 -0.781829 0 -0.623492 -0.781829 0 -0.900972 -0.433877 0 -0.900972 -0.433877 0 -1 0 0 -1 0 0 -0.900972 0.433877 0 -0.900972 0.433877 0 -0.623492 0.781829 0 -0.623492 0.781829 0 -0.222519 0.974928 0 -0.222519 0.974928 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.186153 -0.694747 -0.694747 -0.186152 -0.694746 -0.694749 -0.508588 -0.508582 -0.694753 -0.508603 -0.508584 -0.694741 -0.694759 -0.18615 -0.694736 -0.694727 -0.186163 -0.694765 -0.69473 0.186142 -0.694767 -0.694751 0.18617 -0.694739 -0.508597 0.508591 -0.69474 -0.508595 0.508577 -0.694752 -0.186153 0.694746 -0.694749 -0.186152 0.694747 -0.694747 -0.186153 -0.694747 -0.694747 -0.186152 -0.694746 -0.694749 -0.508588 -0.508582 -0.694753 -0.508603 -0.508584 -0.694741 -0.694759 -0.18615 -0.694736 -0.694727 -0.186163 -0.694765 -0.69473 0.186142 -0.694767 -0.694751 0.18617 -0.694739 -0.508597 0.508591 -0.69474 -0.508595 0.508577 -0.694752 -0.186153 0.694746 -0.694749 -0.186152 0.694747 -0.694747 0.228365 0.973576 0 0.228365 0.973576 0 0.637458 0.770485 0 0.637458 0.770485 0 0.913573 0.406675 0 0.913573 0.406675 0 0.228364 -0.973576 0 0.189012 -0.981965 -0.00430821 0.637448 -0.770477 0.00504452 0.589807 -0.80754 -0.00252287 0.913572 -0.40667 0.00233853 0.905209 -0.424966 0 0.228366 0.973575 0 0.228366 0.973575 0 0.637456 0.770487 0 0.637456 0.770487 0 0.913574 0.406671 0 0.913574 0.406671 0 -0.5102 0.136717 0.84912 -0.373494 0.373496 0.849119 -0.136711 0.510202 0.84912 -0.136711 -0.510202 0.84912 -0.373494 -0.373496 0.849119 -0.5102 -0.136717 0.84912 -0.258823 0.965925 0 -0.258823 0.965925 0 -0.707105 0.707109 0 -0.707105 0.707109 0 -0.965921 0.258836 0 -0.965921 0.258836 0 -0.965921 -0.258836 0 -0.965921 -0.258836 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258823 -0.965925 0 -0.258823 -0.965925 0 -0.18616 0.694745 0.694748 -0.186156 0.694742 0.694752 -0.508579 0.508583 0.694759 -0.508596 0.508585 0.694746 -0.694744 0.186169 0.694746 -0.694741 0.18617 0.694748 -0.694742 -0.186169 0.694749 -0.694743 -0.186171 0.694746 -0.50859 -0.508592 0.694745 -0.508588 -0.508576 0.694758 -0.186158 -0.69474 0.694752 -0.186156 -0.694746 0.694748 -0.5102 0.136717 0.84912 -0.373495 0.373496 0.849119 -0.13671 0.510202 0.84912 -0.136711 -0.510202 0.84912 -0.373494 -0.373496 0.849119 -0.5102 -0.136717 0.84912 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965921 0.258836 0 -0.965921 0.258836 0 -0.965921 -0.258836 0 -0.965921 -0.258836 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.258823 -0.965925 0 -0.258823 -0.965925 0 -0.186159 0.694745 0.694747 -0.186155 0.694743 0.694751 -0.508581 0.508582 0.694759 -0.508596 0.508584 0.694746 -0.694744 0.186169 0.694746 -0.694741 0.18617 0.694748 -0.694742 -0.186168 0.694749 -0.694743 -0.186171 0.694746 -0.50859 -0.508593 0.694744 -0.508588 -0.508576 0.694758 -0.186158 -0.69474 0.694752 -0.186156 -0.694745 0.694748 -0.186157 -0.694753 -0.69474 -0.186158 -0.694754 -0.694739 -0.508597 -0.508597 -0.694736 -0.508608 -0.508604 -0.694723 -0.694777 -0.18616 -0.694715 -0.694729 -0.18616 -0.694763 -0.694731 0.186148 -0.694765 -0.694772 0.186171 -0.694717 -0.508606 0.508606 -0.694723 -0.5086 0.508595 -0.694736 -0.186158 0.694754 -0.694738 -0.186158 0.694753 -0.69474 -0.159331 -0.69808 -0.698067 -0.159332 -0.698083 -0.698064 -0.446448 -0.559825 -0.698055 -0.446441 -0.559819 -0.698064 -0.64513 -0.310672 -0.698061 -0.645121 -0.310671 -0.69807 -0.71603 0 -0.69807 -0.71603 0 -0.69807 -0.645122 0.310668 -0.698071 -0.645128 0.310674 -0.698062 -0.446442 0.559816 -0.698066 -0.446446 0.559826 -0.698055 -0.159332 0.698083 -0.698064 -0.159332 0.69808 -0.698067 0.163627 0.697582 -0.697571 0.163627 0.697583 -0.69757 0.45675 0.552067 -0.697568 0.456753 0.552075 -0.69756 0.654603 0.291395 -0.697555 0.654596 0.291388 -0.697565 0.258416 0.58904 -0.765672 0.163655 0.6977 -0.697446 0.126134 0.549707 -0.82578 0.219415 0.631943 -0.743307 0.270186 0.654378 -0.70625 0.456749 0.552068 -0.697568 0.456755 0.552072 -0.697561 0.654604 0.291393 -0.697555 0.654595 0.291392 -0.697564 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 1 0 0 1 0 0.996917 -0.0784671 0 0.987513 -0.15641 0.0188187 0.890848 -0.453911 0.0188212 0.923881 -0.382679 0 0.97237 -0.233445 0 0.706982 -0.706982 0.0188199 0.760406 -0.649448 0 0.852637 -0.522505 0 0.319174 -0.947696 -0.000187839 0.353945 -0.935265 0.00166504 0.397451 -0.917598 0.00681168 0.430509 -0.90249 0.0132089 0.437825 -0.89894 0.0147047 0.440599 -0.897574 0.0152989 0.439736 -0.898 0.0151107 0.435236 -0.900206 0.0141132 0.431423 -0.902053 0.0132612 0.429172 -0.903133 0.012754 0.427519 -0.903921 0.0123777 0.453916 -0.890853 0.0184817 0.51351 -0.858084 0 0.649448 -0.760406 0 0.22804 -0.973651 0.00104429 0.156397 -0.987458 0.0216112 0.0766138 -0.997061 0 -0.0766138 -0.997061 0 -0.156397 -0.987458 0.0216112 -0.397451 -0.917598 0.00681168 -0.430341 -0.90257 0.0131761 -0.439736 -0.898 0.0151107 -0.441045 -0.897353 0.0153959 -0.437827 -0.898939 0.0147066 -0.432386 -0.901665 0.00650966 -0.433462 -0.901068 0.0137208 -0.429172 -0.903133 0.012754 -0.427519 -0.903922 0.0123778 -0.353967 -0.935256 0.00166764 -0.319155 -0.947702 -0.000187576 -0.22804 -0.973651 0.00104429 -0.513233 -0.857634 0.0324968 -0.45399 -0.891007 0 -0.649448 -0.760406 0 -0.706982 -0.706982 0.0188199 -0.760406 -0.649448 0 -0.852643 -0.522494 0 -0.890851 -0.453905 0.0188196 -0.923881 -0.382679 0 -0.97237 -0.233445 0 -0.987513 -0.15641 0.0188187 -0.996917 -0.0784671 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.996917 0.0784674 0 -0.987513 0.15641 0.0188186 -0.890851 0.453906 0.0188194 -0.923881 0.38268 0 -0.97237 0.233444 0 -0.706982 0.706982 0.0188199 -0.760406 0.649448 0 -0.852643 0.522494 0 -0.319155 0.947703 -0.000187576 -0.353967 0.935256 0.00166764 -0.39744 0.917603 0.00681032 -0.43043 0.902527 0.0131943 -0.437827 0.898939 0.0147066 -0.441045 0.897353 0.0153959 -0.439551 0.898091 0.0150706 -0.434922 0.900359 0.0140452 -0.432166 0.901694 0.0134283 -0.429172 0.903133 0.012754 -0.427165 0.90409 0.0122965 -0.453913 0.890855 0.0184818 -0.513506 0.858086 0 -0.649448 0.760406 0 -0.22804 0.973651 0.00104429 -0.156397 0.987458 0.0216112 -0.0766138 0.997061 0 0.0766138 0.997061 0 0.156397 0.987458 0.0216112 0.39744 0.917603 0.00681033 0.430598 0.902447 0.0132271 0.439551 0.898091 0.0150706 0.440599 0.897574 0.0152989 0.437825 0.89894 0.0147047 0.431788 0.901974 0.0014293 0.433641 0.900981 0.0137613 0.429172 0.903133 0.012754 0.427163 0.904091 0.0122968 0.353945 0.935265 0.00166504 0.319174 0.947696 -0.000187838 0.22804 0.973651 0.00104429 0.513241 0.857629 0.0324995 0.453993 0.891005 0 0.649448 0.760406 0 0.706982 0.706982 0.0188199 0.760406 0.649448 0 0.852637 0.522505 0 0.890848 0.453912 0.018821 0.923881 0.38268 0 0.97237 0.233444 0 0.987513 0.15641 0.0188186 0.996917 0.0784674 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.980785 0.195094 0 0.980785 0.195094 0 0.831469 0.555572 0 0.831469 0.555572 0 0.555573 0.831468 0 0.555573 0.831468 0 0.19509 0.980785 0 0.19509 0.980785 0 0 1 0 0 1 0 -0.19509 0.980785 0 -0.19509 0.980785 0 -0.555573 0.831468 0 -0.555573 0.831468 0 -0.831469 0.555572 0 -0.831469 0.555572 0 -0.980785 0.195094 0 -0.980785 0.195094 0 -1 0 0 -1 0 0 -0.980785 -0.195094 0 -0.980785 -0.195094 0 -0.831469 -0.555572 0 -0.831469 -0.555572 0 -0.555573 -0.831468 0 -0.555573 -0.831468 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 0 -1 0 0 -1 0 0.19509 -0.980785 0 0.19509 -0.980785 0 0.555573 -0.831468 0 0.555573 -0.831468 0 0.831469 -0.555572 0 0.831469 -0.555572 0 0.980785 -0.195094 0 0.980785 -0.195094 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.980785 0.195094 0 0.980785 0.195094 0 0.831468 0.555572 0 0.831468 0.555572 0 0.555573 0.831468 0 0.555573 0.831468 0 0.19509 0.980785 0 0.19509 0.980785 0 0 1 0 0 1 0 -0.19509 0.980785 0 -0.19509 0.980785 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.831473 0.555565 0 -0.831473 0.555565 0 -0.980785 0.195094 0 -0.980785 0.195094 0 -1 0 0 -1 0 0 -0.980785 -0.195094 0 -0.980785 -0.195094 0 -0.831473 -0.555565 0 -0.831473 -0.555565 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195089 -0.980785 0 -0.195089 -0.980785 0 0 -1 0 0 -1 0 0.195089 -0.980785 0 0.195089 -0.980785 0 0.555573 -0.831468 0 0.555573 -0.831468 0 0.831469 -0.555572 0 0.831469 -0.555572 0 0.980785 -0.195094 0 0.980785 -0.195094 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.980786 0.195085 0 0.980786 0.195085 0 0.831469 0.555572 0 0.831469 0.555572 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195092 0.980785 0 0.195092 0.980785 0 0 1 0 0 1 0 -0.19509 0.980785 0 -0.19509 0.980785 0 -0.555573 0.831468 0 -0.555573 0.831468 0 -0.831469 0.555572 0 -0.831469 0.555572 0 -0.980785 0.195094 0 -0.980785 0.195094 0 -1 0 0 -1 0 0 -0.980785 -0.195094 0 -0.980785 -0.195094 0 -0.831468 -0.555572 0 -0.831468 -0.555572 0 -0.555573 -0.831468 0 -0.555573 -0.831468 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 0 -1 0 0 -1 0 0.195092 -0.980785 0 0.195092 -0.980785 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831468 -0.555572 0 0.831468 -0.555572 0 0.980786 -0.195085 0 0.980786 -0.195085 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.707109 0 -0.707105 0.707109 0 -0.707105 0.441787 -0.587622 -0.677882 0.369013 -0.618929 -0.693365 0.420299 -0.492111 -0.762349 0.426615 -0.584775 -0.689955 0.530267 -0.45289 -0.716734 0.706225 -0.0499884 -0.706221 0.707787 -0.0557014 -0.704226 0.69026 -0.148564 -0.708146 0.691703 -0.166062 -0.70283 0.661106 -0.243799 -0.709578 0.658125 -0.272604 -0.701825 0.619327 -0.334051 -0.710524 0.607879 -0.372513 -0.701225 0.565727 -0.417664 -0.710992 0.516727 -0.508414 -0.688846 0.369011 0.61893 -0.693366 0.420299 0.492108 -0.762351 0.426869 0.591949 -0.683652 0.542274 0.463144 -0.701026 0.501257 0.493196 -0.710984 0.433652 0.576801 -0.692276 0.706017 0.0555621 -0.706012 0.708631 0.0501588 -0.703794 0.686524 0.16482 -0.70818 0.697339 0.150088 -0.70085 0.64993 0.269208 -0.710716 0.672451 0.247982 -0.697363 0.597314 0.36604 -0.713604 0.634244 0.342099 -0.693328 0.565728 0.417663 -0.710992 -0.369011 -0.618925 -0.69337 -0.420298 -0.4921 -0.762356 -0.426869 -0.591949 -0.683652 -0.542266 -0.463149 -0.701028 -0.501259 -0.493194 -0.710985 -0.433652 -0.576801 -0.692276 -0.706017 -0.0555621 -0.706012 -0.708631 -0.0501588 -0.703794 -0.686524 -0.164819 -0.70818 -0.69734 -0.150087 -0.70085 -0.64993 -0.269209 -0.710716 -0.67245 -0.247983 -0.697363 -0.59732 -0.366032 -0.713603 -0.634253 -0.342087 -0.693325 -0.565719 -0.417672 -0.710994 -0.441787 0.587622 -0.677882 -0.369009 0.618926 -0.693371 -0.420298 0.492097 -0.762358 -0.426615 0.584775 -0.689955 -0.530263 0.452896 -0.716733 -0.706225 0.0499884 -0.706221 -0.707787 0.0557014 -0.704226 -0.69026 0.148564 -0.708146 -0.691703 0.166063 -0.70283 -0.661106 0.243798 -0.709578 -0.658126 0.272603 -0.701825 -0.619333 0.334042 -0.710523 -0.607884 0.372507 -0.701224 -0.56572 0.417671 -0.710993 -0.516724 0.508414 -0.688848 -0.707109 0 -0.707105 -0.707109 0 -0.707105 -0.555145 -0.0392974 -0.830825 -0.195069 -0.0138069 -0.980692 -0.195074 -0.0138088 -0.980691 -0.191184 -0.041148 -0.980691 -0.191175 -0.0411426 -0.980693 -0.183473 -0.0676604 -0.980693 -0.183485 -0.0676697 -0.980691 -0.172124 -0.0928388 -0.980691 -0.172116 -0.0928303 -0.980693 -0.157324 -0.116148 -0.980693 -0.157329 -0.116155 -0.980691 -0.139398 -0.137159 -0.980691 -0.139397 -0.137157 -0.980692 -0.117582 -0.156393 -0.980671 -0.117584 -0.156398 -0.98067 -0.234892 -0.31243 -0.920442 -0.555138 -0.0392941 -0.83083 -0.54407 -0.117089 -0.83083 -0.544093 -0.117104 -0.830812 -0.522173 -0.192579 -0.830812 -0.522144 -0.192554 -0.830836 -0.489816 -0.264181 -0.830836 -0.489823 -0.264188 -0.83083 -0.447725 -0.330553 -0.830829 -0.44773 -0.330561 -0.830824 -0.396705 -0.390329 -0.830824 -0.396699 -0.390317 -0.830832 -0.336284 -0.443555 -0.830766 -0.338444 -0.450165 -0.826322 -0.555574 0 -0.831467 -0.555574 0 -0.831467 -0.195088 0 -0.980786 -0.195088 0 -0.980786 -0.234823 0.312338 -0.920491 -0.117584 0.156398 -0.98067 -0.338448 0.45017 -0.826317 -0.117582 0.156396 -0.980671 -0.139398 0.137159 -0.980691 -0.139398 0.137159 -0.980691 -0.157331 0.116153 -0.980691 -0.157325 0.116151 -0.980693 -0.172116 0.0928342 -0.980693 -0.172126 0.0928358 -0.980691 -0.183487 0.0676653 -0.980691 -0.183473 0.067665 -0.980693 -0.191174 0.041146 -0.980693 -0.191184 0.0411449 -0.980691 -0.195074 0.0138073 -0.980691 -0.195069 0.0138085 -0.980692 -0.336285 0.443554 -0.830766 -0.396694 0.390322 -0.830833 -0.396707 0.390327 -0.830824 -0.447733 0.330557 -0.830823 -0.447724 0.330554 -0.830829 -0.489824 0.264186 -0.83083 -0.489814 0.264185 -0.830836 -0.522139 0.192565 -0.830837 -0.522177 0.192565 -0.830813 -0.544096 0.117095 -0.830812 -0.544068 0.1171 -0.83083 -0.555137 0.0392969 -0.83083 -0.555145 0.0392946 -0.830825 0.234892 -0.31243 -0.920442 0.117585 -0.156398 -0.98067 0.338444 -0.450165 -0.826322 0.117581 -0.156395 -0.980671 0.139399 -0.137155 -0.980692 0.139393 -0.137152 -0.980693 0.157321 -0.11615 -0.980693 0.157323 -0.116151 -0.980693 0.172114 -0.0928335 -0.980693 0.172126 -0.0928354 -0.980691 0.183487 -0.0676653 -0.980691 0.183472 -0.067665 -0.980693 0.191174 -0.0411459 -0.980693 0.191184 -0.0411446 -0.980691 0.195074 -0.0138073 -0.980691 0.195069 -0.0138085 -0.980692 0.336284 -0.443555 -0.830766 0.396696 -0.39032 -0.830832 0.396708 -0.390326 -0.830824 0.447732 -0.330558 -0.830823 0.447747 -0.330562 -0.830814 0.489848 -0.264198 -0.830812 0.489811 -0.264193 -0.830836 0.522139 -0.192566 -0.830837 0.522177 -0.192566 -0.830813 0.544096 -0.117095 -0.830812 0.544068 -0.117099 -0.83083 0.555137 -0.0392969 -0.83083 0.555145 -0.0392946 -0.830825 0.555574 0 -0.831467 0.555574 0 -0.831467 0.195088 0 -0.980786 0.195088 0 -0.980786 0.555145 0.0392974 -0.830825 0.195069 0.0138069 -0.980692 0.195074 0.0138088 -0.980691 0.191184 0.041148 -0.980691 0.191175 0.041143 -0.980693 0.183474 0.0676608 -0.980693 0.183485 0.0676694 -0.980691 0.172124 0.0928388 -0.980691 0.172117 0.0928314 -0.980693 0.157324 0.116152 -0.980693 0.157322 0.116149 -0.980693 0.139394 0.137151 -0.980693 0.139398 0.137159 -0.980691 0.117583 0.156396 -0.980671 0.117584 0.156398 -0.98067 0.234822 0.312338 -0.920491 0.555138 0.0392941 -0.83083 0.54407 0.11709 -0.83083 0.544093 0.117105 -0.830812 0.522173 0.192578 -0.830812 0.522145 0.192553 -0.830836 0.489816 0.264182 -0.830836 0.48984 0.26421 -0.830813 0.447745 0.330565 -0.830814 0.447737 0.330552 -0.830823 0.396704 0.390331 -0.830824 0.396698 0.390318 -0.830832 0.336285 0.443554 -0.830766 0.338448 0.45017 -0.826317 -0.424665 0.712275 -0.55886 -0.504377 0.834859 -0.220487 -0.528981 0.843189 -0.0959795 -0.5421 0.839852 -0.0278539 -0.53963 0.84088 -0.041481 -0.537157 0.841707 -0.0546993 -0.534005 0.842487 -0.0710955 -0.472343 0.792247 -0.386312 -0.49975 0.838217 -0.21827 -0.561789 0.797276 -0.220782 -0.4273 0.71447 -0.554029 -0.54052 0.632857 -0.554374 -0.54051 0.632852 -0.554389 -0.632848 0.540514 -0.55439 -0.632861 0.540518 -0.554372 -0.70963 0.434856 -0.554369 -0.709623 0.434855 -0.554379 -0.768912 0.318492 -0.554379 -0.768915 0.318492 -0.554376 -0.809271 0.194289 -0.554375 -0.809265 0.19429 -0.554385 -0.829695 0.0652953 -0.554386 -0.829678 0.0653009 -0.55441 -0.503714 0.841723 -0.194357 -0.637044 0.745878 -0.194526 -0.637039 0.745878 -0.194542 -0.745875 0.637042 -0.194548 -0.74588 0.637041 -0.19453 -0.836353 0.512515 -0.194532 -0.836356 0.512514 -0.194519 -0.906233 0.375371 -0.194519 -0.906234 0.375371 -0.194519 -0.953796 0.228989 -0.194518 -0.9538 0.228986 -0.1945 -0.977879 0.0769652 -0.194499 -0.977875 0.0769686 -0.194515 -0.980785 0 -0.195094 -0.980785 0 -0.195094 -0.831453 0 -0.555596 -0.831453 0 -0.555596 -0.829678 -0.0652941 -0.55441 -0.514673 -0.842217 -0.160567 -0.499506 -0.837801 -0.220416 -0.503985 -0.835097 -0.220482 -0.511698 -0.853114 -0.101791 -0.512575 -0.855618 -0.0719972 -0.513091 -0.857042 -0.0470852 -0.51319 -0.857349 -0.0398617 -0.513387 -0.857892 -0.0213439 -0.506213 -0.840208 -0.194419 -0.63704 -0.745879 -0.194538 -0.63704 -0.745877 -0.194542 -0.745877 -0.637039 -0.194547 -0.745877 -0.637044 -0.19453 -0.836354 -0.512512 -0.194532 -0.836355 -0.512516 -0.194519 -0.906234 -0.375369 -0.194519 -0.906235 -0.375371 -0.194513 -0.953798 -0.228986 -0.194514 -0.953799 -0.22899 -0.1945 -0.977878 -0.0769686 -0.194499 -0.977875 -0.0769647 -0.194515 -0.424678 -0.712292 -0.558828 -0.829693 -0.0653018 -0.554387 -0.809264 -0.194286 -0.554387 -0.809271 -0.194291 -0.554375 -0.768914 -0.318494 -0.554376 -0.76891 -0.31849 -0.554383 -0.709622 -0.43485 -0.554385 -0.709628 -0.434859 -0.55437 -0.632857 -0.540522 -0.554371 -0.632851 -0.54051 -0.55439 -0.540512 -0.63285 -0.554389 -0.540515 -0.632861 -0.554374 -0.427296 -0.714472 -0.554029 -0.47227 -0.79212 -0.38666 0.829678 0.0652941 -0.55441 0.514219 0.842133 -0.162455 0.499507 0.83781 -0.220381 0.505311 0.8343 -0.220464 0.512138 0.854389 -0.0879498 0.512896 0.856461 -0.0584092 0.513081 0.85701 -0.0477721 0.513279 0.857552 -0.0338965 0.51339 0.857878 -0.0218085 0.506225 0.840211 -0.194374 0.637047 0.745886 -0.194487 0.637047 0.745882 -0.194503 0.745884 0.637045 -0.194501 0.745884 0.63705 -0.194483 0.836357 0.512528 -0.19448 0.836355 0.512516 -0.194519 0.906233 0.375371 -0.194519 0.906234 0.375371 -0.194519 0.953797 0.228985 -0.194518 0.953799 0.22899 -0.1945 0.977878 0.0769689 -0.194499 0.977875 0.0769649 -0.194515 0.424664 0.712275 -0.558861 0.829694 0.0653021 -0.554386 0.809265 0.194287 -0.554385 0.809271 0.194291 -0.554375 0.768915 0.318493 -0.554376 0.768913 0.318491 -0.554379 0.709619 0.434862 -0.554379 0.709607 0.434845 -0.554407 0.632846 0.5405 -0.554405 0.632851 0.54051 -0.55439 0.540507 0.632854 -0.554389 0.540504 0.632845 -0.554403 0.427288 0.714459 -0.554051 0.472351 0.792262 -0.386272 0.980785 0 -0.195094 0.980785 0 -0.195094 0.831453 0 -0.555596 0.831453 0 -0.555596 0.424667 -0.712274 -0.55886 0.504919 -0.834539 -0.220459 0.528194 -0.843246 -0.099739 0.54218 -0.839815 -0.0274149 0.539377 -0.840973 -0.0428595 0.536955 -0.841767 -0.0557443 0.534522 -0.842381 -0.0684158 0.472147 -0.791914 -0.387233 0.499692 -0.838113 -0.218801 0.551944 -0.804127 -0.220766 0.42729 -0.714458 -0.554051 0.5405 -0.632849 -0.554403 0.540508 -0.632853 -0.554389 0.632854 -0.540507 -0.554389 0.632843 -0.540504 -0.554405 0.709604 -0.434851 -0.554407 0.70962 -0.434853 -0.554385 0.768909 -0.318492 -0.554384 0.768915 -0.318492 -0.554376 0.809271 -0.194288 -0.554375 0.809263 -0.194289 -0.554387 0.829694 -0.0652953 -0.554387 0.829678 -0.0653006 -0.55441 0.50372 -0.841724 -0.194338 0.637046 -0.745884 -0.194498 0.637045 -0.745884 -0.194503 0.745882 -0.637048 -0.194501 0.745887 -0.637047 -0.194483 0.836361 -0.51252 -0.19448 0.83635 -0.512524 -0.194519 0.906233 -0.375371 -0.194519 0.906235 -0.37537 -0.194513 0.953797 -0.228989 -0.194514 0.9538 -0.228987 -0.1945 0.977879 -0.0769649 -0.194499 0.977875 -0.0769684 -0.194515 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.995185 -0.0980189 0 0.995185 -0.0980189 0 0.956938 -0.290293 0 0.956938 -0.290293 0 0.881922 -0.471396 0 0.881922 -0.471396 0 0.773015 -0.634388 0 0.773015 -0.634388 0 0.634391 -0.773012 0 0.634391 -0.773012 0 0.471397 -0.881921 0 0.471397 -0.881921 0 0.290282 -0.956941 0 0.290282 -0.956941 0 0.0980167 -0.995185 0 0.0980167 -0.995185 0 -0.0980167 -0.995185 0 -0.0980167 -0.995185 0 -0.290282 -0.956941 0 -0.290282 -0.956941 0 -0.471397 -0.881921 0 -0.471397 -0.881921 0 -0.6344 -0.773005 0 -0.6344 -0.773005 0 -0.773006 -0.634399 0 -0.773006 -0.634399 0 -0.881922 -0.471396 0 -0.881922 -0.471396 0 -0.956943 -0.290276 0 -0.956943 -0.290276 0 -0.995185 -0.0980189 0 -0.995185 -0.0980189 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.995185 0.0980186 0 -0.995185 0.0980186 0 -0.956943 0.290276 0 -0.956943 0.290276 0 -0.881922 0.471396 0 -0.881922 0.471396 0 -0.773006 0.634399 0 -0.773006 0.634399 0 -0.6344 0.773005 0 -0.6344 0.773005 0 -0.471397 0.881921 0 -0.471397 0.881921 0 -0.290282 0.956941 0 -0.290282 0.956941 0 -0.0980167 0.995185 0 -0.0980167 0.995185 0 0.0980167 0.995185 0 0.0980167 0.995185 0 0.290282 0.956941 0 0.290282 0.956941 0 0.471397 0.881921 0 0.471397 0.881921 0 0.634391 0.773012 0 0.634391 0.773012 0 0.773015 0.634388 0 0.773015 0.634388 0 0.881922 0.471396 0 0.881922 0.471396 0 0.956938 0.290293 0 0.956938 0.290293 0 0.995185 0.0980186 0 0.995185 0.0980186 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 0.984807 0 0.173652 0.984807 0 0.173652 0.984807 0 0.173652 -0.984807 0 0.173652 -0.984807 0 0.173652 -0.984807 0 0.173652 -0.967212 0.175706 0.183383 -0.816274 0.554337 0.162501 -0.96608 0.123576 0.226758 -0.896046 0.416309 0.154235 -0.911325 0.366525 0.187472 -0.800918 0.570169 0.182859 -0.794262 0.585612 0.161886 -0.816271 -0.554342 0.162502 -0.794262 -0.585612 0.161885 -0.800918 -0.570171 0.182855 -0.898234 -0.397551 0.187425 -0.913991 -0.367598 0.171732 -0.966293 -0.157101 0.203955 -0.975511 -0.124782 0.181127 0.816266 0.554346 0.162512 0.794262 0.585612 0.161886 0.800918 0.570169 0.182859 0.890824 0.413939 0.187316 0.914585 0.367827 0.16804 0.960737 0.174195 0.215967 0.975511 0.124782 0.181127 0.970398 -0.158006 0.182652 0.81627 -0.554341 0.162511 0.970216 -0.124105 0.208037 0.901775 -0.399092 0.165916 0.911328 -0.366517 0.187476 0.800919 -0.570167 0.182861 0.794262 -0.585612 0.161885 -0.802072 0.575395 0.160005 -0.847633 0.519226 0.109187 -0.998708 0.0491551 0.0129062 -0.991837 0.125739 0.0211858 -0.98236 0.185656 0.0223837 -0.954814 0.28424 0.0868179 -0.892779 0.437294 0.108258 -0.999979 0.00617022 0.00170067 -0.98269 0.176677 0.0557268 -0.989475 0.104986 0.099588 -0.964273 0.2544 0.0738828 -0.90525 0.409974 0.111548 -0.847569 0.502574 0.170428 -0.8164 0.554163 0.162466 -0.883761 -0.451063 0.124536 -0.990244 -0.134775 0.0353866 -0.954286 -0.298792 0.00786204 -0.796718 -0.597862 0.0883327 -0.740709 -0.649076 0.17335 -0.847885 -0.516207 0.120918 -0.847569 -0.502571 0.170439 -0.816367 -0.554209 0.162475 -0.982681 -0.180922 0.0400706 -0.982718 -0.178456 0.049187 -0.989386 -0.0354414 0.140923 -0.989024 -0.110925 0.0976102 -0.962843 -0.259689 0.0741274 -0.903828 -0.412646 0.113218 0.883761 0.451063 0.124536 0.990244 0.134775 0.0353866 0.954286 0.298792 0.00786204 0.796718 0.597862 0.0883327 0.740659 0.64913 0.173361 0.847876 0.516224 0.120912 0.84756 0.502587 0.170434 0.816392 0.554171 0.162477 0.982681 0.180922 0.0400706 0.982718 0.178456 0.049187 0.989398 0.035662 0.140785 0.989057 0.11027 0.0980159 0.963272 0.258119 0.0740409 0.90426 0.41184 0.112702 0.802062 -0.575409 0.160006 0.847624 -0.519241 0.109188 0.998712 -0.0490774 0.0128858 0.99186 -0.125562 0.0211874 0.98236 -0.185651 0.022402 0.954865 -0.284085 0.0867627 0.892808 -0.437234 0.108257 0.999946 -0.00999168 0.00275396 0.982654 -0.175651 0.0594824 0.989024 -0.110925 0.0976102 0.962834 -0.259724 0.0741216 0.903831 -0.412644 0.113204 0.84756 -0.502586 0.170437 0.816384 -0.554182 0.16248 0.802051 0.399042 0.444386 0.882078 0.383902 0.273054 0.889359 0.322115 0.324472 0.987991 0.111783 0.106673 0.979398 0.170078 0.108873 0.936331 0.277847 0.214676 0.881056 0.421384 0.214885 0.999754 0.0130382 0.0179203 0.999849 0.0124871 0.0120982 0.998692 0.0492956 0.0135879 0.772352 0.554539 0.309772 0.806862 0.523497 0.273724 0.705818 0.493877 0.507845 0.758027 0.471629 0.450512 0.625812 0.475413 0.618339 0.911487 0.163557 0.377412 0.749051 0.430152 0.503877 0.356256 0.109097 0.927998 0.298781 0.0113384 0.954254 0.684504 0.393704 0.613557 0.666133 0.379908 0.641824 0.601472 0.293164 0.743159 0.585252 0.288197 0.757907 0.378596 0.184776 0.90693 0.669996 0.120242 0.732562 0.662174 0.122101 0.739335 0.496861 0.0903059 0.863119 0.370549 0.0667525 0.926411 0.343381 0.0548248 0.937595 0.810037 0.147244 0.56759 0.905929 0.166514 0.389315 0.806675 0.442959 0.391231 0.722417 0.33666 0.603965 0.785905 0.535449 0.309268 0.2988 0 0.954316 0.2988 0 0.954316 0.4989 0 0.86666 0.4989 0 0.86666 0.674893 0 0.737916 0.674893 0 0.737916 0.818964 0 0.573845 0.818964 0 0.573845 0.923929 0 0.382563 0.923929 0 0.382563 0.700604 -0.36866 0.610937 0.358241 -0.0487773 0.932354 0.343268 -0.0989795 0.934008 0.397335 -0.185223 0.898787 0.538447 -0.25241 0.803968 0.606739 -0.284397 0.742285 0.298781 -0.0113384 0.954254 0.343795 -0.0552345 0.937419 0.49726 -0.0810129 0.863811 0.663257 -0.109978 0.740267 0.67097 -0.107656 0.733627 0.811768 -0.132272 0.568803 0.908462 -0.150034 0.39011 0.913946 -0.146605 0.37843 0.608259 -0.287042 0.740019 0.684927 -0.377449 0.623224 0.80734 -0.443719 0.388993 0.776911 -0.38359 0.499268 0.711498 -0.315482 0.627886 0.785909 -0.535445 0.309268 0.802074 -0.399043 0.444344 0.999769 -0.0126914 0.0173626 0.999851 -0.0122062 0.0121827 0.995238 -0.0962222 0.0155502 0.988391 -0.107446 0.107415 0.957478 -0.265624 0.112605 0.948606 -0.232535 0.21465 0.735584 -0.504399 0.452214 0.719132 -0.475206 0.506979 0.625822 -0.4754 0.618338 0.940452 -0.262945 0.215428 0.87405 -0.423627 0.237858 0.882075 -0.383907 0.273055 0.785335 -0.555704 0.272842 0.795509 -0.521356 0.308795 -0.802074 -0.399043 0.444344 -0.882086 -0.383903 0.273025 -0.889357 -0.322263 0.324332 -0.987775 -0.112689 0.10771 -0.979068 -0.171301 0.109916 -0.935604 -0.279477 0.215726 -0.88043 -0.42218 0.215887 -0.999674 -0.0134923 0.0216988 -0.999846 -0.0126027 0.0121988 -0.998671 -0.0496898 0.0136954 -0.772327 -0.554574 0.309773 -0.806863 -0.523508 0.273698 -0.705814 -0.493883 0.507845 -0.758061 -0.471616 0.450468 -0.625822 -0.4754 0.618338 -0.757385 -0.416738 0.50269 -0.913946 -0.146605 0.37843 -0.34326 -0.0989677 0.934012 -0.298788 -0.0113448 0.954252 -0.397335 -0.185223 0.898787 -0.692437 -0.381527 0.612347 -0.682724 -0.374663 0.627308 -0.606475 -0.285066 0.742243 -0.611484 -0.286619 0.73752 -0.538447 -0.25241 0.803968 -0.67097 -0.107656 0.733627 -0.663257 -0.109978 0.740267 -0.496447 -0.0808717 0.864291 -0.355777 -0.0572413 0.932816 -0.336272 -0.0478144 0.94055 -0.811768 -0.132272 0.568803 -0.908462 -0.150034 0.39011 -0.814268 -0.430014 0.389944 -0.711498 -0.315482 0.627886 -0.785909 -0.535445 0.309268 -0.923929 0 0.382563 -0.923929 0 0.382563 -0.818964 0 0.573845 -0.818964 0 0.573845 -0.674893 0 0.737916 -0.674893 0 0.737916 -0.498079 0 0.867132 -0.498079 0 0.867132 -0.298807 0 0.954314 -0.298807 0 0.954314 -0.374006 0.0561902 0.925723 -0.356269 0.109098 0.927993 -0.37861 0.184776 0.906925 -0.585268 0.288195 0.757895 -0.601475 0.293158 0.74316 -0.785912 0.53544 0.309268 -0.722439 0.336683 0.603926 -0.771192 0.393565 0.500369 -0.911487 0.163557 0.377412 -0.90592 0.166519 0.389335 -0.798661 0.458038 0.39031 -0.669998 0.385492 0.634427 -0.700603 0.36866 0.610937 -0.298788 0.0113448 0.954252 -0.351915 0.0632817 0.93389 -0.496051 0.0901546 0.863601 -0.662173 0.122106 0.739336 -0.669996 0.120247 0.732562 -0.810037 0.14725 0.56759 -0.802092 0.399021 0.444332 -0.999875 0.00833457 0.0134039 -0.999938 0.0082492 0.00745355 -0.995984 0.0889347 0.0103017 -0.989278 0.102557 0.103978 -0.95944 0.259875 0.10927 -0.950371 0.228594 0.211043 -0.735595 0.50438 0.452218 -0.719134 0.475204 0.506979 -0.625816 0.475407 0.618338 -0.942009 0.260252 0.211869 -0.874589 0.421372 0.239875 -0.882094 0.383871 0.273043 -0.785352 0.555687 0.272828 -0.795522 0.521336 0.308794 -1 0 0 -1 0 0 -0.991766 -0.0919632 0.0891213 -0.925767 -0.2947 0.236869 -0.926421 -0.281845 0.249613 -0.931376 -0.257217 0.257637 -0.989187 -0.104586 0.102816 -0.994247 0.0528636 -0.0931529 -0.991745 -0.0830855 0.0976647 -0.971628 -0.164434 0.170004 -0.846913 -0.32686 0.419406 -0.851429 -0.320746 0.41496 -0.704338 -0.451077 0.548123 -0.702002 -0.34014 0.625698 -0.328859 -0.0118465 0.944305 -0.96961 -0.00344232 0.244633 -0.737523 -0.00830528 0.675271 -0.349855 -0.00454391 0.936793 -0.349757 -0.0436051 0.935825 -0.376101 -0.0495464 0.925253 -0.473961 -0.104822 0.874284 -0.472578 -0.186249 0.861384 -0.578 -0.150905 0.801963 -0.579713 -0.249663 0.775629 -0.57891 -0.258899 0.773198 -0.635119 -0.283332 0.718573 -0.632487 -0.389657 0.669423 -0.746472 -0.00382862 0.665405 -0.746013 -0.0480099 0.664199 -0.797658 -0.0322999 0.602245 -0.797265 -0.128796 0.589729 -0.840019 -0.101347 0.533008 -0.840386 -0.192693 0.506577 -0.862498 -0.164604 0.478543 -0.861406 -0.256595 0.438335 -0.850617 -0.269893 0.45123 -0.970697 -0.00191178 0.240299 -0.970595 -0.0190163 0.239965 -0.976791 -0.0129327 0.213803 -0.976665 -0.0479881 0.209337 -0.981785 -0.0373373 0.18629 -0.981775 -0.0693848 0.176929 -0.9844 -0.0590739 0.165734 -0.984432 -0.0622489 0.164377 -0.9718 -0.115294 0.205702 -0.328882 0 0.944371 -0.328882 0 0.944371 -0.737548 0 0.675294 -0.737548 0 0.675294 -0.969615 0 0.244635 -0.969615 0 0.244635 -0.969613 0.00194627 0.244634 -0.737543 0.0038269 0.675289 -0.349878 0.0121933 0.936716 -0.328879 0.00433394 0.944362 -0.9707 0.00343473 0.240272 -0.97065 0.0145209 0.240059 -0.976848 0.0179726 0.213178 -0.976772 0.0421104 0.210104 -0.981871 0.0438125 0.184416 -0.981857 0.0636654 0.178616 -0.98445 0.0650129 0.163193 -0.984291 0.0863212 0.15401 -0.987512 0.0821282 0.134444 -0.922336 0.187004 0.338122 -0.746493 0.0083885 0.665341 -0.74631 0.0343875 0.66471 -0.7981 0.0476478 0.600638 -0.79791 0.110936 0.59248 -0.840747 0.121341 0.527657 -0.84091 0.175082 0.512071 -0.862976 0.183201 0.47086 -0.861234 0.259396 0.437023 -0.850325 0.264234 0.455113 -0.349626 0.0551026 0.935268 -0.3979 0.0445971 0.916344 -0.473966 0.114133 0.873115 -0.473473 0.155877 0.866906 -0.579278 0.185315 0.793785 -0.579563 0.258796 0.772743 -0.635093 0.28174 0.719222 -0.633925 0.364342 0.682198 -0.703749 0.367565 0.607975 -0.926439 0.281396 0.250055 -1 0 0 -0.999995 0.00218105 -0.00231862 -0.997735 -0.0273938 -0.0614434 -0.991166 0.0953264 0.0922077 -0.932725 0.254265 0.255684 -0.851428 0.32077 0.414942 -0.704337 0.451083 0.548118 -0.923043 0.24668 0.295196 -0.926536 0.242009 0.288032 -0.769758 0.417082 0.483234 -0.991768 0.0917397 0.0893367 -0.991772 0.08675 0.0941415 -0.987516 0.102069 0.119979 0.99396 0.0545378 -0.0952273 0.989146 -0.104759 0.103032 0.931382 -0.257189 0.257647 0.926421 -0.281845 0.249613 0.926536 -0.242021 0.288022 0.769754 -0.417096 0.483229 0.851513 -0.32065 0.41486 0.704338 -0.451077 0.548123 0.99998 -0.00457561 0.00430992 0.999854 -0.0154851 -0.0072888 0.991768 -0.0917397 0.0893367 0.991573 -0.103315 0.078157 0.971991 -0.152283 0.179005 0.349688 -0.0484046 0.935615 0.349858 -0.0121857 0.936724 0.328879 -0.00433394 0.944362 0.746493 -0.0083885 0.665341 0.737543 -0.0038269 0.675289 0.9707 -0.00343473 0.240272 0.969613 -0.00194628 0.244634 0.47399 -0.104839 0.874267 0.365941 -0.0439452 0.9296 0.798066 -0.0476388 0.600684 0.74631 -0.0343875 0.66471 0.976848 -0.0179726 0.213178 0.97065 -0.0145209 0.24006 0.976772 -0.0421104 0.210104 0.981871 -0.0438125 0.184416 0.797876 -0.110943 0.592524 0.840747 -0.121357 0.527652 0.473502 -0.155885 0.866888 0.575686 -0.290972 0.764148 0.579713 -0.249663 0.775629 0.579278 -0.185315 0.793785 0.85041 -0.264177 0.454987 0.861236 -0.259374 0.437033 0.971091 -0.0996513 0.216916 0.984291 -0.0863212 0.15401 0.981857 -0.0636654 0.178616 0.98445 -0.0650129 0.163193 0.84091 -0.175082 0.512071 0.862976 -0.183201 0.47086 0.634157 -0.249377 0.731885 0.633925 -0.364342 0.682198 0.703749 -0.367565 0.607975 0.969615 0 0.244635 0.969615 0 0.244635 0.737548 0 0.675294 0.737548 0 0.675294 0.328882 0 0.944371 0.328882 0 0.944371 0.922267 0.187078 0.338267 0.328859 0.0118396 0.944305 0.96961 0.00344232 0.244633 0.737523 0.00830528 0.675271 0.349835 0.00454371 0.9368 0.349737 0.0436006 0.935833 0.41278 0.0578691 0.908991 0.473995 0.114134 0.873099 0.472607 0.186249 0.861368 0.578 0.150916 0.80196 0.578684 0.288942 0.762652 0.634157 0.249377 0.731885 0.632487 0.389657 0.669423 0.702002 0.34014 0.625698 0.746472 0.00382862 0.665405 0.746013 0.0480012 0.664199 0.797624 0.0323014 0.60229 0.797231 0.128816 0.58977 0.840019 0.101347 0.533008 0.840386 0.192693 0.506577 0.862498 0.164604 0.478543 0.861406 0.256595 0.438335 0.8507 0.269793 0.451133 0.970697 0.00191178 0.240299 0.970595 0.0190163 0.239965 0.976791 0.0129327 0.213803 0.976665 0.0479881 0.209337 0.981785 0.0373373 0.18629 0.981775 0.0693848 0.176929 0.9844 0.0590739 0.165734 0.984182 0.091152 0.151914 0.987421 0.0773053 0.137925 0.925768 0.294684 0.236885 0.926427 0.281691 0.249765 0.931771 0.256344 0.25708 0.989513 0.103191 0.101069 0.997147 -0.0326406 -0.0680611 0.999977 0.00642796 0.00234071 0.99998 0.00457561 0.00430992 0.991768 0.0917397 0.0893367 0.991745 0.0830855 0.0976647 0.987457 0.105409 0.117545 0.922976 0.24678 0.295323 0.846965 0.326826 0.419327 0.851513 0.320667 0.414848 0.704337 0.451087 0.548114 -0.951827 -0.292058 -0.0934205 -0.956027 -0.280893 -0.0843282 -0.842881 -0.518191 -0.145015 -0.692279 -0.694931 -0.194476 -0.686798 -0.703931 -0.181081 -0.271748 -0.93165 -0.241208 -0.268475 -0.9337 -0.236908 0.186012 -0.906787 -0.378335 -0.0297961 -0.968855 -0.245828 0.179373 -0.952728 -0.245224 0.203149 -0.955129 -0.215543 0.133453 -0.828144 -0.544397 0.182643 -0.788613 -0.587138 -0.094877 -0.798487 -0.594489 -0.273976 -0.805027 -0.526184 -0.867873 -0.398471 -0.296678 -0.727205 -0.550575 -0.409926 -0.695372 -0.611949 -0.376797 -0.538917 -0.675659 -0.503044 -0.330386 -0.757062 -0.563651 -0.0967313 -0.662517 -0.742774 -0.336161 -0.611009 -0.716704 0.148096 -0.640692 -0.75338 -0.971428 -0.157725 -0.17734 -0.971427 -0.154927 -0.179796 -0.970136 -0.157006 -0.184891 -0.752663 -0.431101 -0.497645 -0.741793 -0.435152 -0.510281 0.13784 -0.65523 -0.742748 0.106001 -0.651618 -0.751105 0.106002 -0.6537 -0.749293 -0.0957648 -0.650117 -0.753776 -0.336158 -0.623645 -0.705737 -0.364365 -0.610598 -0.703142 -0.364366 -0.611071 -0.702731 -0.554583 -0.543335 -0.630258 -0.954053 -0.0748346 -0.290144 -0.972293 -0.154378 -0.175541 -0.872002 -0.325666 -0.365449 -0.752658 -0.430167 -0.49846 -0.733842 -0.449916 -0.508971 -0.546388 -0.557319 -0.625184 0.0501445 -0.198836 -0.978749 0.0612725 -0.41624 -0.907188 0.059082 -0.603046 -0.795515 -0.329508 -0.206897 -0.921205 -0.298711 -0.166373 -0.93973 -0.0452328 -0.174154 -0.983679 0.145879 -0.496419 -0.855738 -0.0942928 -0.499551 -0.861137 -0.327777 -0.468834 -0.820218 -0.968874 -0.0431518 -0.243763 -0.870203 -0.0858831 -0.48515 -0.736576 -0.157187 -0.657836 -0.723132 -0.120384 -0.680139 -0.520563 -0.148813 -0.840755 -0.331589 -0.473411 -0.816046 -0.54881 -0.419479 -0.72308 -0.734056 -0.336554 -0.589824 -0.736993 -0.342841 -0.582496 -0.96905 -0.120085 -0.21569 -0.969778 0 -0.24399 -0.873257 0.0199126 -0.486853 -0.96592 0 -0.258842 -0.728429 0 -0.685121 -0.707105 0.0022101 -0.707105 -0.526424 0 -0.850222 -0.302933 0 -0.953012 -0.258812 0.00310062 -0.965923 -0.0459347 0 -0.998945 -0.25873 -0.0254838 -0.965614 -0.705398 -0.0694815 -0.705398 -0.961578 -0.0947088 -0.257679 -0.961581 -0.0947154 -0.257663 -0.924632 -0.280475 -0.257663 -0.924632 -0.280475 -0.257662 -0.852144 -0.455479 -0.257661 -0.852145 -0.455488 -0.257644 -0.746908 -0.612982 -0.257646 -0.74691 -0.612968 -0.257674 -0.612978 -0.746902 -0.257672 -0.612976 -0.74691 -0.257656 -0.455481 -0.852145 -0.257656 -0.455479 -0.852148 -0.257648 -0.280482 -0.924633 -0.257652 -0.280482 -0.924632 -0.257652 -0.0947074 -0.961584 -0.257656 -0.0947076 -0.961584 -0.257656 0.0947074 -0.961584 -0.257656 0.0947057 -0.961583 -0.25766 0.280481 -0.924629 -0.257665 0.280487 -0.924631 -0.257652 0.455482 -0.852147 -0.257648 0.455478 -0.852146 -0.257656 0.612972 -0.746913 -0.257656 0.612978 -0.746912 -0.257643 0.746919 -0.612972 -0.25764 0.746915 -0.612973 -0.257647 0.852148 -0.455482 -0.257644 0.852141 -0.455485 -0.257661 0.924627 -0.280491 -0.257662 0.924627 -0.280491 -0.257662 0.961582 -0.0947092 -0.257663 0.961591 -0.0946984 -0.257634 -0.705393 -0.0694784 -0.705403 -0.678288 -0.20575 -0.705403 -0.678294 -0.205756 -0.705395 -0.625116 -0.334137 -0.705395 -0.625104 -0.334118 -0.705415 -0.547909 -0.449653 -0.705413 -0.547917 -0.449675 -0.705393 -0.449669 -0.547921 -0.705394 -0.449668 -0.547915 -0.705399 -0.334129 -0.625116 -0.705399 -0.334129 -0.625114 -0.705401 -0.205755 -0.678288 -0.705401 -0.205756 -0.678284 -0.705405 -0.0694752 -0.705395 -0.705401 -0.0694751 -0.705395 -0.705401 0.0694739 -0.705395 -0.705401 0.0694753 -0.705397 -0.705399 0.205759 -0.67829 -0.705398 0.205757 -0.678287 -0.705401 0.334128 -0.625115 -0.705401 0.33413 -0.625116 -0.705399 0.449666 -0.547917 -0.705399 0.449656 -0.547912 -0.705409 0.547911 -0.449655 -0.705411 0.547908 -0.449654 -0.705413 0.625098 -0.334127 -0.705416 0.625121 -0.334127 -0.705396 0.678291 -0.205764 -0.705395 0.678308 -0.20576 -0.70538 0.705419 -0.0694703 -0.705378 0.705398 -0.0694788 -0.705398 -0.258731 -0.0254845 -0.965613 -0.248789 -0.0754684 -0.965613 -0.248792 -0.0754709 -0.965612 -0.229289 -0.122555 -0.965612 -0.229293 -0.12256 -0.965611 -0.200975 -0.16494 -0.965611 -0.200971 -0.164933 -0.965613 -0.164934 -0.20097 -0.965613 -0.164934 -0.200971 -0.965612 -0.122556 -0.229287 -0.965613 -0.122555 -0.229284 -0.965613 -0.0754696 -0.248789 -0.965613 -0.0754694 -0.248793 -0.965612 -0.025483 -0.258734 -0.965612 -0.0254833 -0.258733 -0.965613 0.0254828 -0.258733 -0.965613 0.0254829 -0.258733 -0.965613 0.0754696 -0.248789 -0.965613 0.0754696 -0.248789 -0.965613 0.122554 -0.229284 -0.965613 0.122557 -0.229287 -0.965613 0.164932 -0.200972 -0.965612 0.164931 -0.200972 -0.965613 0.200971 -0.164932 -0.965613 0.200978 -0.164935 -0.965611 0.229295 -0.122558 -0.965611 0.229288 -0.122557 -0.965612 0.248792 -0.0754695 -0.965612 0.248788 -0.0754698 -0.965613 0.258731 -0.025484 -0.965613 0.25873 -0.0254844 -0.965614 0.969778 0 -0.24399 0.965931 0.0011758 -0.258797 0.873775 0 -0.486331 0.728429 0 -0.685121 0.707105 0.0022101 -0.707105 0.0459347 0 -0.998945 0.258812 0.00310062 -0.965923 0.302933 0 -0.953012 0.526424 0 -0.850222 0.0444053 -0.25589 -0.965686 -0.0612725 -0.41624 -0.907188 -0.0487507 -0.174125 -0.983516 0.298711 -0.166373 -0.93973 0.329508 -0.206897 -0.921205 0.96905 -0.120085 -0.21569 0.737019 -0.342826 -0.582472 0.734082 -0.336539 -0.589801 0.334594 -0.477015 -0.812714 0.327777 -0.468834 -0.820218 0.0942928 -0.499551 -0.861137 -0.0606692 -0.500863 -0.863398 -0.147419 -0.561781 -0.814045 0.520563 -0.148813 -0.840755 0.723132 -0.120384 -0.680139 0.736608 -0.157277 -0.657779 0.870554 -0.0857748 -0.484539 0.968874 -0.0431518 -0.243763 0.97144 -0.157693 -0.177303 -0.13783 -0.655229 -0.74275 -0.106001 -0.651618 -0.751105 0.0967313 -0.662517 -0.742774 0.336158 -0.623645 -0.705737 0.364364 -0.610598 -0.703142 0.546388 -0.557319 -0.625184 0.733842 -0.449916 -0.508972 0.752658 -0.430167 -0.49846 0.872002 -0.325666 -0.365449 0.972305 -0.154344 -0.175503 0.954027 -0.0746869 -0.290267 0.970134 -0.158344 -0.183761 0.971434 -0.153536 -0.180949 0.741794 -0.439158 -0.506835 0.752635 -0.427016 -0.501197 0.338902 -0.616966 -0.710281 0.364333 -0.603639 -0.709142 0.0957648 -0.650117 -0.753776 -0.106002 -0.6537 -0.749293 -0.148096 -0.640692 -0.75338 -0.135219 -0.794753 -0.591679 -0.184076 -0.814188 -0.550648 0.0297956 -0.968863 -0.245799 -0.186012 -0.906877 -0.378118 -0.179396 -0.952731 -0.245194 -0.203149 -0.955129 -0.215543 0.84597 -0.513507 -0.143688 0.684744 -0.701826 -0.196383 0.690891 -0.700175 -0.180069 0.0948766 -0.798502 -0.594469 0.273976 -0.805035 -0.526171 0.271509 -0.932883 -0.23667 0.268167 -0.932628 -0.241436 0.330385 -0.757079 -0.563629 0.538915 -0.675674 -0.503026 0.69537 -0.611956 -0.37679 0.727204 -0.550587 -0.409914 0.999574 -0.0234056 -0.0174255 0.857044 -0.459161 -0.233765 0.951817 -0.292106 -0.0933742 0.951818 0.292102 -0.0933777 0.956073 0.280785 -0.0841619 0.845968 0.513506 -0.143704 0.692279 0.694931 -0.194476 0.686798 0.703931 -0.181081 0.271748 0.93165 -0.241208 0.268475 0.9337 -0.236908 -0.186011 0.906941 -0.377967 0.0297961 0.968855 -0.245828 -0.179386 0.952726 -0.245223 -0.203148 0.955126 -0.21556 -0.133444 0.828146 -0.544396 -0.182643 0.788606 -0.587148 0.0948773 0.798479 -0.594499 0.273975 0.805019 -0.526195 0.867888 0.398449 -0.296662 0.727199 0.550581 -0.40993 0.695372 0.611943 -0.376808 0.538918 0.675651 -0.503054 0.330387 0.757053 -0.563662 0.0967313 0.662517 -0.742774 0.336161 0.61101 -0.716702 -0.148104 0.640691 -0.753379 0.971441 0.157691 -0.177302 0.97144 0.154893 -0.179757 0.970136 0.156993 -0.184902 0.752659 0.431093 -0.497658 0.741818 0.435133 -0.51026 -0.13783 0.655229 -0.74275 -0.106001 0.651618 -0.751105 -0.106002 0.653702 -0.749291 0.0957648 0.650119 -0.753774 0.336158 0.623645 -0.705737 0.364365 0.610598 -0.703142 0.364366 0.611073 -0.702729 0.55506 0.543121 -0.630022 0.954027 0.0746898 -0.290265 0.972304 0.154346 -0.175504 0.872014 0.325653 -0.365433 0.752655 0.430169 -0.498463 0.733837 0.449919 -0.508975 0.546388 0.557319 -0.625184 -0.0501445 0.198836 -0.978749 -0.0612647 0.416071 -0.907266 -0.0590694 0.603061 -0.795505 0.329508 0.206897 -0.921205 0.298711 0.166373 -0.93973 0.0452328 0.174154 -0.983679 -0.145885 0.496411 -0.855742 0.094293 0.499543 -0.861142 0.327777 0.468827 -0.820222 0.968874 0.0431501 -0.243763 0.870555 0.0857715 -0.484539 0.736606 0.157272 -0.657782 0.723132 0.120384 -0.680139 0.520563 0.148813 -0.840755 0.331588 0.473402 -0.816051 0.549181 0.419349 -0.722874 0.734079 0.336541 -0.589803 0.73702 0.342837 -0.582464 0.96905 0.120088 -0.215687 0.969778 0 -0.24399 0.873602 -0.0198601 -0.486235 0.965932 0 -0.258797 0.728429 0 -0.685121 0.707105 -0.00221011 -0.707105 0.526424 0 -0.850222 0.302933 0 -0.953012 0.258812 -0.00310062 -0.965923 0.0459347 0 -0.998944 0.25873 0.0254837 -0.965614 0.705399 0.0694681 -0.705399 0.96159 0.0947098 -0.257634 0.961583 0.0946974 -0.257663 0.924627 0.280491 -0.257662 0.924627 0.280491 -0.257662 0.852144 0.455479 -0.257661 0.852145 0.455488 -0.257644 0.746917 0.612971 -0.257647 0.746917 0.612974 -0.25764 0.612974 0.746916 -0.257643 0.612976 0.74691 -0.257656 0.455481 0.852145 -0.257656 0.455479 0.852148 -0.257648 0.280482 0.924633 -0.257652 0.280486 0.924628 -0.257665 0.0947073 0.961583 -0.25766 0.0947058 0.961584 -0.257656 -0.0947074 0.961584 -0.257656 -0.0947076 0.961584 -0.257656 -0.280482 0.924633 -0.257652 -0.280482 0.924633 -0.257652 -0.455482 0.852147 -0.257648 -0.455478 0.852146 -0.257656 -0.612981 0.746906 -0.257656 -0.612974 0.746906 -0.257671 -0.746902 0.612977 -0.257675 -0.746915 0.612973 -0.257647 -0.852148 0.455482 -0.257644 -0.852141 0.455485 -0.257661 -0.924632 0.280475 -0.257662 -0.924632 0.280475 -0.257663 -0.961582 0.094709 -0.257663 -0.961577 0.0947148 -0.257678 0.705417 0.0694805 -0.705379 0.678306 0.205769 -0.705379 0.678294 0.205756 -0.705395 0.625116 0.334137 -0.705395 0.625104 0.334118 -0.705415 0.547909 0.449653 -0.705413 0.54791 0.449656 -0.705411 0.44966 0.547909 -0.705409 0.449662 0.54792 -0.705399 0.334129 0.625116 -0.705399 0.334129 0.625114 -0.705401 0.205758 0.678287 -0.705401 0.205758 0.67829 -0.705398 0.0694742 0.705397 -0.705399 0.0694751 0.705395 -0.705401 -0.0694752 0.705395 -0.705401 -0.0694751 0.705395 -0.705401 -0.205754 0.678284 -0.705405 -0.205757 0.678287 -0.705401 -0.334128 0.625115 -0.705401 -0.33413 0.625116 -0.705399 -0.449666 0.547917 -0.705399 -0.449671 0.547919 -0.705394 -0.547925 0.449667 -0.705392 -0.547902 0.449662 -0.705413 -0.625098 0.334127 -0.705416 -0.625121 0.334127 -0.705396 -0.678295 0.205752 -0.705395 -0.678286 0.205754 -0.705403 -0.705393 0.0694808 -0.705403 -0.705398 0.0694787 -0.705398 0.258731 0.0254845 -0.965613 0.248789 0.0754684 -0.965613 0.248792 0.0754709 -0.965612 0.229289 0.122555 -0.965612 0.229293 0.12256 -0.965611 0.200977 0.164937 -0.965611 0.200973 0.16493 -0.965613 0.164932 0.200972 -0.965613 0.164932 0.200973 -0.965612 0.122556 0.229287 -0.965613 0.122555 0.229284 -0.965613 0.0754696 0.248789 -0.965613 0.0754696 0.248789 -0.965613 0.0254828 0.258733 -0.965613 0.0254829 0.258733 -0.965613 -0.0254828 0.258733 -0.965613 -0.0254834 0.258734 -0.965613 -0.0754706 0.248792 -0.965612 -0.0754684 0.248789 -0.965613 -0.122554 0.229284 -0.965613 -0.122557 0.229287 -0.965613 -0.164935 0.200971 -0.965612 -0.164933 0.20097 -0.965613 -0.200969 0.164935 -0.965613 -0.200976 0.164937 -0.965611 -0.229295 0.122558 -0.965611 -0.229288 0.122557 -0.965612 -0.248792 0.0754695 -0.965612 -0.248788 0.0754698 -0.965613 -0.258731 0.0254839 -0.965613 -0.25873 0.0254843 -0.965614 -0.969778 0 -0.24399 -0.965919 -0.00117937 -0.258842 -0.87343 0 -0.486949 -0.728429 0 -0.685121 -0.707105 -0.00221011 -0.707105 -0.0459347 0 -0.998944 -0.258812 -0.00310062 -0.965923 -0.302933 0 -0.953012 -0.526424 0 -0.850222 -0.0444053 0.25589 -0.965686 0.0612647 0.416071 -0.907266 0.0487507 0.174125 -0.983516 -0.298711 0.166373 -0.93973 -0.329508 0.206897 -0.921205 -0.96905 0.120088 -0.215687 -0.736994 0.342851 -0.582488 -0.734053 0.336556 -0.589827 -0.334599 0.477014 -0.812712 -0.327777 0.468827 -0.820222 -0.094293 0.499543 -0.861142 0.0606591 0.500855 -0.863403 0.147426 0.561786 -0.814041 -0.520563 0.148813 -0.840755 -0.723132 0.120384 -0.680139 -0.736575 0.157182 -0.657839 -0.870203 0.0858798 -0.48515 -0.968874 0.0431502 -0.243763 -0.971429 0.157724 -0.177339 0.13784 0.65523 -0.742748 0.106001 0.651618 -0.751105 -0.0967313 0.662517 -0.742774 -0.336158 0.623645 -0.705737 -0.364364 0.610598 -0.703142 -0.546388 0.557319 -0.625184 -0.733837 0.449919 -0.508975 -0.752655 0.430169 -0.498463 -0.872014 0.325653 -0.365433 -0.972292 0.154379 -0.175541 -0.954053 0.0748375 -0.290141 -0.970134 0.158344 -0.183761 -0.971423 0.153579 -0.180974 -0.741769 0.439185 -0.506849 -0.752631 0.427018 -0.5012 -0.338909 0.616964 -0.710279 -0.364333 0.603641 -0.70914 -0.0957648 0.650119 -0.753774 0.106002 0.653702 -0.749291 0.148104 0.640691 -0.753379 0.135229 0.794744 -0.591688 0.184076 0.814174 -0.55067 -0.0297956 0.968863 -0.245799 0.186008 0.907066 -0.377666 0.17941 0.952729 -0.245194 0.203148 0.955126 -0.21556 -0.842883 0.518193 -0.144999 -0.684744 0.701826 -0.196383 -0.690886 0.700176 -0.180083 -0.0948768 0.798494 -0.594479 -0.273986 0.805028 -0.526177 -0.271521 0.932879 -0.23667 -0.268165 0.932624 -0.241453 -0.330385 0.757079 -0.563629 -0.538915 0.675674 -0.503026 -0.695364 0.611959 -0.376795 -0.727198 0.550592 -0.409918 -0.999563 0.0237054 -0.0176488 -0.857073 0.459093 -0.233795 -0.951828 0.292055 -0.093424 -0.195098 0.00473488 -0.980772 -0.188015 0.0131976 -0.982078 -0.442181 0.00763856 -0.896893 -0.427912 0.0147114 -0.903701 -0.608718 0.00651041 -0.79336 -0.590241 0.0271509 -0.80677 -0.793374 0.00585855 -0.608707 -0.772878 0.0370405 -0.633473 -0.896787 0.0112554 -0.442319 -0.878623 0.0334337 -0.476344 -0.980774 -0.00704376 -0.195022 -0.968278 0.0655619 -0.241122 -0.980798 0 -0.195027 -0.965932 0.00151184 -0.258791 -0.896844 0 -0.442347 -0.793387 0 -0.608717 -0.707105 0.00201828 -0.707105 -0.608731 0 -0.793377 -0.442194 0 -0.896919 -0.258803 0.00151032 -0.965929 -0.1951 0 -0.980783 0.153146 0.925929 -0.345256 0.161294 0.847283 -0.506059 0.151422 0.721306 -0.675862 0.143843 0.676297 -0.722449 0.405039 0.90911 -0.0972787 0.432648 0.900121 -0.0509741 -0.254254 0.884245 -0.391747 -0.0337005 0.978875 -0.201662 -0.0301073 0.978972 -0.201758 0.0503025 0.97852 -0.199923 0.105351 0.967908 -0.228158 -0.202541 0.148163 -0.968 -0.122463 0.164052 -0.978821 -0.266997 0.239084 -0.933569 -0.289805 0.703907 -0.648481 -0.339951 0.891859 -0.298363 -0.668876 0.683012 -0.293427 -0.668346 0.685019 -0.289934 -0.812134 0.49929 -0.301907 -0.913935 0.280428 -0.293398 -0.937193 0.257102 -0.235728 -0.846408 0.259762 -0.464884 -0.668299 0.205101 -0.71506 -0.512228 0.469255 -0.719321 -0.453593 0.463179 -0.761393 -0.282489 0.707451 -0.647853 -0.757977 0.179908 -0.62698 -0.576372 0.176878 -0.797815 -0.24621 0.0755575 -0.966267 -0.425138 0.0637287 -0.902882 -0.185665 0.0569755 -0.98096 -0.961592 0.0947068 -0.257628 -0.961595 0.0947103 -0.257613 -0.924641 0.280487 -0.257615 -0.924633 0.280475 -0.257657 -0.852143 0.455483 -0.257658 -0.852141 0.455478 -0.257675 -0.746908 0.612971 -0.257672 -0.746911 0.612984 -0.257634 -0.612977 0.746915 -0.257637 -0.612976 0.7469 -0.257683 -0.455476 0.852141 -0.257676 -0.455477 0.852137 -0.25769 -0.280485 0.924625 -0.257677 -0.280482 0.924633 -0.257652 -0.0947084 0.961584 -0.257655 -0.0947075 0.961586 -0.25765 0.0947086 0.961585 -0.25765 0.0947074 0.961584 -0.257655 0.280482 0.924633 -0.257652 0.280482 0.924633 -0.257651 0.455487 0.852144 -0.257647 0.455478 0.85214 -0.257676 0.612969 0.746906 -0.257683 0.612966 0.746905 -0.257694 0.746902 0.612966 -0.257703 0.746912 0.612966 -0.257672 0.852139 0.455481 -0.257675 0.852145 0.45548 -0.257658 0.924631 0.280483 -0.257657 0.924617 0.280488 -0.257701 0.961572 0.0947049 -0.257702 0.961568 0.0947076 -0.257717 -0.705398 0.0694687 -0.705398 -0.705418 0.0694764 -0.705379 -0.678307 0.205767 -0.705379 -0.678293 0.205758 -0.705395 -0.625118 0.334134 -0.705395 -0.625118 0.334135 -0.705394 -0.547918 0.449672 -0.705394 -0.547907 0.449656 -0.705413 -0.449659 0.547906 -0.705411 -0.449664 0.547918 -0.705399 -0.334129 0.625116 -0.705399 -0.334128 0.625114 -0.705401 -0.205758 0.678287 -0.705401 -0.205758 0.678286 -0.705402 -0.0694745 0.705398 -0.705398 -0.0694755 0.705392 -0.705404 0.0694739 0.705392 -0.705404 0.0694761 0.705398 -0.705398 0.205754 0.678287 -0.705402 0.205755 0.678288 -0.705401 0.334134 0.625112 -0.7054 0.334135 0.625112 -0.7054 0.44966 0.547921 -0.7054 0.449676 0.547932 -0.705381 0.54794 0.449675 -0.705375 0.547921 0.449667 -0.705395 0.625119 0.334135 -0.705394 0.625117 0.334134 -0.705395 0.678292 0.205762 -0.705395 0.678308 0.205762 -0.705379 0.705419 0.0694707 -0.705378 0.705398 0.0694744 -0.705398 -0.258719 0.0254812 -0.965616 -0.258709 0.0254781 -0.965619 -0.248767 0.0754634 -0.965619 -0.24877 0.0754652 -0.965618 -0.229268 0.122548 -0.965618 -0.229264 0.122545 -0.965619 -0.200952 0.164919 -0.965619 -0.200952 0.16492 -0.965619 -0.16492 0.200951 -0.965619 -0.164925 0.20096 -0.965616 -0.122547 0.229273 -0.965617 -0.122546 0.229269 -0.965618 -0.0754634 0.24877 -0.965618 -0.0754631 0.248766 -0.965619 -0.0254811 0.258709 -0.965619 -0.0254806 0.258713 -0.965618 0.0254811 0.258713 -0.965618 0.0254804 0.258711 -0.965619 0.0754659 0.248773 -0.965618 0.0754606 0.248763 -0.96562 0.122539 0.229259 -0.965621 0.12255 0.229271 -0.965617 0.164924 0.20096 -0.965616 0.164917 0.200955 -0.965619 0.200955 0.164917 -0.965619 0.200954 0.164916 -0.965619 0.229264 0.122546 -0.965619 0.229268 0.122547 -0.965618 0.24877 0.0754645 -0.965618 0.248767 0.0754642 -0.965619 0.258709 0.0254802 -0.965619 0.258719 0.0254791 -0.965617 0.225662 0.868286 -0.441764 0.442891 0.894644 -0.0588208 0.433336 0.899425 -0.0570405 0.442866 0.896184 -0.0269261 0.445415 0.894382 -0.0410595 0.441005 0.8974 -0.013674 0.445609 0.894911 -0.0238174 0.441437 0.896922 -0.0257567 0.438311 0.8988 -0.00645102 -0.16428 0.824382 -0.54167 0.047475 0.975013 -0.217016 0.0468315 0.976776 -0.209082 0.118832 0.944622 -0.305888 0.145154 0.981906 -0.121615 0.223525 0.947285 -0.229537 0.260909 0.963895 -0.0532197 0.32232 0.937532 -0.130937 0.326956 0.943111 -0.0603474 0.369133 0.923217 -0.106824 0.37365 0.926393 -0.0467033 0.411532 0.908768 -0.0691526 0.409686 0.91053 -0.055605 0.432471 0.899699 -0.0592497 -0.294924 0.685732 -0.665426 -0.148625 0.624417 -0.76682 -0.324459 0.409458 -0.852684 -0.260589 0.442345 -0.858152 -0.120008 0.394323 -0.911102 -0.0238353 0.211427 -0.977103 0.00577365 0.458066 -0.888899 0.444871 0.894624 -0.0416767 0.433486 0.900072 -0.0442796 0.432606 0.900609 -0.0418947 0.41558 0.908711 -0.0392028 0.417267 0.907347 -0.0510904 0.39014 0.920094 -0.0349024 0.385349 0.919749 -0.0746211 0.357081 0.93306 -0.0435008 0.351365 0.931695 -0.0921228 0.312126 0.949093 -0.0424178 0.277978 0.947275 -0.15937 0.229196 0.968993 -0.0923129 0.202877 0.955188 -0.215537 0.106812 0.990467 -0.0869856 -0.0738605 0.835918 -0.543862 -0.0706585 0.834667 -0.546203 -0.054401 0.694253 -0.717672 0.0901093 0.639978 -0.763092 0.0995087 0.604594 -0.790293 0.441458 0.896981 -0.0232453 0.432611 0.901226 -0.0253053 0.433128 0.900944 -0.0264652 0.421815 0.906347 -0.0246278 0.422699 0.905753 -0.0306168 0.405978 0.913649 -0.0206662 0.401717 0.914687 -0.0443877 0.38562 0.922274 -0.0266298 0.380717 0.923134 -0.0536441 0.359487 0.932768 -0.0266989 0.333882 0.938067 -0.0924802 0.30792 0.949714 -0.0568286 0.287545 0.949334 -0.126816 0.238528 0.969183 -0.061554 0.101817 0.935731 -0.3377 0.115638 0.930417 -0.347781 0.111898 0.876287 -0.468616 0.171714 0.855319 -0.488819 0.216139 0.763494 -0.608573 0.437329 0.899246 -0.0099808 0.43767 0.899083 -0.00976362 0.436442 0.899693 -0.0084457 0.432921 0.901385 -0.00924869 0.432026 0.901829 -0.00762566 0.427962 0.90377 -0.00698507 0.428395 0.903538 -0.00980037 0.421395 0.90686 -0.0056382 0.41908 0.907833 -0.0145648 0.412673 0.910848 -0.00751307 0.410139 0.911861 -0.0171892 0.402228 0.915512 -0.0071376 0.390795 0.920006 -0.0294777 0.380944 0.92446 -0.0159528 0.371454 0.927546 -0.0409961 0.349522 0.936854 -0.0117957 0.288301 0.950309 -0.117457 0.279587 0.953665 -0.111145 0.27543 0.947044 -0.165065 0.277005 0.946492 -0.165593 0.285324 0.938366 -0.195088 0.980774 0 -0.195149 0.965908 0.00151113 -0.25888 0.896844 0 -0.442347 0.793387 0 -0.608717 0.707105 0.00201828 -0.707105 0.1951 0 -0.980783 0.258803 0.00151032 -0.965929 0.442194 0 -0.896919 0.608731 0 -0.793377 0.0339697 0.442092 -0.896326 0.139081 0.593824 -0.792484 0.0446141 0.190486 -0.980676 0.204646 0.87376 -0.441206 0.212807 0.942352 -0.258234 0.223683 0.955048 -0.194547 0.0149896 0.195072 -0.980674 0.0277314 0.257607 -0.965852 0.051351 0.253955 -0.965852 0.101114 0.431719 -0.896323 0.0467265 0.608112 -0.792475 0.0645815 0.704833 -0.706428 0.151266 0.691431 -0.706429 0.181116 0.773295 -0.607628 0.0751502 0.978012 -0.194536 0.0816858 0.962622 -0.258235 0.0687518 0.89476 -0.441224 0.0608461 0.791871 -0.607649 0.188435 0.00457317 -0.982075 0.195083 0.0130594 -0.9807 0.428212 0.00797834 -0.903643 0.44215 0.0141188 -0.89683 0.590976 0.00738742 -0.806655 0.608531 0.0256065 -0.793117 0.774039 0.00837267 -0.633083 0.792942 0.0334999 -0.608375 0.879204 0.0156455 -0.476189 0.896484 0.0283345 -0.442169 0.970554 -0.000659676 -0.240884 0.979203 0.0565797 -0.194836 0 0.195094 -0.980785 0 0.195094 -0.980785 0 0.442347 -0.896844 0 0.442347 -0.896844 0 0.608777 -0.793341 0 0.608777 -0.793341 0 0.793341 -0.608777 0 0.793341 -0.608777 0 0.896882 -0.442271 0 0.896882 -0.442271 0 0.980786 -0.195088 0 0.980786 -0.195088 0.289786 0.703844 -0.648558 0.537378 0.548735 -0.640402 0.322313 0.442415 -0.836889 0.512228 0.469255 -0.719321 0.266997 0.239084 -0.933569 0.175287 0.191807 -0.965652 0.121785 0.0890883 -0.98855 -0.432182 0.900299 -0.0517742 -0.405039 0.90911 -0.0972787 -0.143843 0.676297 -0.722449 -0.151399 0.721169 -0.676013 -0.161282 0.847271 -0.506083 -0.153136 0.925922 -0.34528 0.846408 0.259762 -0.464884 -0.105333 0.967912 -0.228149 -0.0503025 0.97852 -0.199923 0.0301073 0.978972 -0.201758 0.0337005 0.978875 -0.201662 0.254254 0.884245 -0.391747 0.339951 0.891859 -0.298362 0.667575 0.684229 -0.293554 0.669589 0.68374 -0.290087 0.81493 0.494665 -0.301987 0.920692 0.259165 -0.29182 0.929421 0.285229 -0.23414 0.74899 0.229865 -0.621431 0.679482 0.179878 -0.7113 0.576284 0.176851 -0.797885 0.419845 0.128843 -0.898404 0.255732 0.0592987 -0.964927 0.185665 0.0569819 -0.98096 -0.101115 0.431718 -0.896323 -0.0467258 0.608112 -0.792475 -0.0149894 0.195072 -0.980674 -0.0687518 0.89476 -0.441224 -0.0816858 0.962622 -0.258235 -0.0751502 0.978012 -0.194536 -0.0446153 0.190491 -0.980675 -0.0513518 0.253955 -0.965852 -0.027731 0.257607 -0.965852 -0.0339692 0.442092 -0.896326 -0.139083 0.593823 -0.792484 -0.15127 0.691441 -0.706418 -0.0645813 0.704837 -0.706423 -0.060846 0.791871 -0.607649 -0.223683 0.955048 -0.194547 -0.212807 0.942352 -0.258234 -0.204651 0.873795 -0.441136 -0.181109 0.773275 -0.607656 -0.00577365 0.458066 -0.888899 -0.432519 0.901232 -0.0266078 -0.438311 0.8988 -0.00645102 -0.443724 0.895318 -0.0389129 -0.437025 0.899392 -0.010174 -0.445196 0.893556 -0.0579452 -0.433354 0.899496 -0.0557732 -0.432024 0.899919 -0.0591781 -0.413671 0.908688 -0.056242 -0.408338 0.910265 -0.0683907 -0.384558 0.921508 -0.0542041 -0.362586 0.926704 -0.0987487 -0.343768 0.935811 -0.0779879 -0.310844 0.943396 -0.115673 -0.290834 0.952508 -0.0902484 -0.207579 0.956012 -0.207251 -0.186664 0.966089 -0.178407 -0.0900179 0.959366 -0.267422 0.29486 0.685839 -0.665344 0.0521615 0.905623 -0.420864 -0.0314264 0.999175 -0.0257356 -0.0468315 0.976776 -0.209082 -0.437502 0.899191 -0.00690446 -0.432783 0.901463 -0.00799522 -0.432306 0.901682 -0.00896285 -0.42825 0.903622 -0.00831129 -0.427469 0.903983 -0.00924841 -0.424165 0.905555 -0.00728308 -0.4177 0.908492 -0.0130417 -0.416095 0.909251 -0.0112741 -0.407734 0.912981 -0.0147749 -0.407281 0.913193 -0.0141968 -0.387792 0.921388 -0.0257039 -0.387998 0.921294 -0.0259868 -0.366281 0.929881 -0.0340502 -0.364658 0.930596 -0.0318784 -0.28017 0.953445 -0.111567 -0.296284 0.947114 -0.123249 -0.259851 0.952322 -0.159875 -0.290358 0.941679 -0.170099 -0.272755 0.942106 -0.195042 -0.22568 0.868321 -0.441688 -0.433125 0.900982 -0.0251685 -0.424254 0.905232 -0.0237537 -0.420616 0.906763 -0.0293714 -0.412041 0.910842 -0.0242627 -0.398817 0.916143 -0.0403329 -0.393878 0.9185 -0.0348847 -0.375199 0.925773 -0.0465876 -0.373249 0.926682 -0.0441038 -0.326484 0.941618 -0.0822432 -0.32632 0.941694 -0.0820168 -0.274553 0.955335 -0.109341 -0.278222 0.953696 -0.114262 -0.0820636 0.94279 -0.323129 -0.159308 0.911565 -0.379039 -0.0727356 0.887846 -0.454356 -0.223225 0.833977 -0.504632 -0.148998 0.781316 -0.60609 -0.436631 0.899554 -0.0124746 -0.438866 0.898508 -0.00900224 -0.444796 0.895361 -0.0220165 -0.441455 0.896973 -0.0235862 -0.44141 0.896848 -0.0286625 -0.442389 0.896493 -0.0243385 -0.445499 0.894319 -0.0415325 -0.43311 0.900249 -0.0443651 -0.433494 0.900114 -0.0433347 -0.418642 0.907228 -0.040941 -0.414725 0.908659 -0.0484037 -0.399247 0.916005 -0.039197 -0.380118 0.922314 -0.069616 -0.3694 0.927474 -0.0577588 -0.342617 0.935985 -0.0809078 -0.333962 0.939992 -0.0698902 -0.266244 0.953226 -0.143089 -0.259011 0.956659 -0.133102 -0.182022 0.965252 -0.187499 -0.173362 0.969027 -0.175878 0.104604 0.847212 -0.520855 -0.00706296 0.800058 -0.599881 0.120228 0.713161 -0.690613 -0.107015 0.632465 -0.767161 -0.075638 0.610579 -0.788335 0.288152 0.683554 -0.670613 0.186569 0.47684 -0.858962 0.260589 0.442345 -0.858152 0.00765265 0.3498 -0.936793 0.122457 0.239731 -0.963085 0.195098 -0.0047347 -0.980772 0.188015 -0.0131971 -0.982078 0.442181 -0.00763825 -0.896893 0.427911 -0.0147114 -0.903701 0.608718 -0.00651041 -0.79336 0.590143 -0.0272587 -0.806838 0.793373 -0.00599328 -0.608706 0.772974 -0.037024 -0.633356 0.896787 -0.0112554 -0.442319 0.878623 -0.0334337 -0.476344 0.980749 0.00702681 -0.195144 0.96829 -0.0653852 -0.241121 0.980774 0 -0.195149 0.965908 -0.00151113 -0.25888 0.896844 0 -0.442347 0.793387 0 -0.608717 0.707105 -0.00201828 -0.707105 0.608731 0 -0.793377 0.442194 0 -0.896919 0.258803 -0.00151032 -0.965929 0.1951 0 -0.980783 -0.153136 -0.925922 -0.34528 -0.161282 -0.847271 -0.506083 -0.151399 -0.721169 -0.676013 -0.143843 -0.676297 -0.722449 -0.405039 -0.90911 -0.0972787 -0.43194 -0.900391 -0.0521905 0.254252 -0.884236 -0.391768 0.0336721 -0.978876 -0.201663 0.0301073 -0.978972 -0.201758 -0.0503025 -0.97852 -0.199923 -0.105333 -0.967912 -0.228149 0.202559 -0.148171 -0.967995 0.122476 -0.164056 -0.978818 0.266987 -0.239074 -0.933574 0.289799 -0.703838 -0.648559 0.339967 -0.891853 -0.298363 0.668876 -0.683012 -0.293427 0.668346 -0.685019 -0.289934 0.814929 -0.494666 -0.301987 0.913894 -0.280467 -0.293489 0.937195 -0.257102 -0.23572 0.846408 -0.259762 -0.464884 0.668299 -0.205101 -0.71506 0.512228 -0.469255 -0.719321 0.453593 -0.463179 -0.761393 0.28268 -0.707236 -0.648004 0.758071 -0.179878 -0.626875 0.57629 -0.176853 -0.79788 0.246233 -0.0755646 -0.96626 0.425131 -0.0637439 -0.902884 0.185665 -0.0569824 -0.98096 0.961568 -0.0947047 -0.257717 0.961572 -0.0947082 -0.257702 0.92462 -0.28048 -0.257701 0.924628 -0.280492 -0.257658 0.852143 -0.455483 -0.257658 0.852141 -0.455478 -0.257675 0.746908 -0.612971 -0.257672 0.746906 -0.612961 -0.257703 0.612967 -0.746904 -0.257694 0.612967 -0.746907 -0.257683 0.455484 -0.852137 -0.257677 0.455482 -0.852147 -0.257647 0.280482 -0.924633 -0.257651 0.280482 -0.924633 -0.257652 0.0947084 -0.961584 -0.257655 0.0947075 -0.961586 -0.25765 -0.0947086 -0.961585 -0.25765 -0.0947074 -0.961584 -0.257655 -0.280487 -0.924631 -0.257651 -0.28048 -0.924626 -0.257677 -0.455474 -0.852138 -0.25769 -0.455478 -0.85214 -0.257676 -0.612969 -0.746906 -0.257683 -0.612984 -0.746909 -0.257637 -0.746916 -0.612978 -0.257634 -0.746903 -0.612977 -0.257672 -0.852139 -0.455481 -0.257675 -0.852145 -0.45548 -0.257658 -0.924631 -0.280483 -0.257657 -0.924644 -0.280478 -0.257615 -0.961596 -0.0947075 -0.257613 -0.961591 -0.0947102 -0.257628 0.705398 -0.0694689 -0.705398 0.705418 -0.0694765 -0.705379 0.678307 -0.205767 -0.705379 0.678293 -0.205758 -0.705395 0.625118 -0.334134 -0.705395 0.625118 -0.334135 -0.705394 0.547925 -0.449663 -0.705395 0.547936 -0.449679 -0.705376 0.449672 -0.547936 -0.70538 0.449664 -0.547918 -0.705399 0.334134 -0.625113 -0.7054 0.334134 -0.625112 -0.705401 0.205753 -0.678289 -0.705401 0.205753 -0.678281 -0.705408 0.0694756 -0.705392 -0.705404 0.0694755 -0.705392 -0.705404 -0.0694756 -0.705392 -0.705404 -0.0694755 -0.705392 -0.705405 -0.205755 -0.678281 -0.705408 -0.205758 -0.678287 -0.705401 -0.334128 -0.625115 -0.705401 -0.334129 -0.625116 -0.705399 -0.449667 -0.547916 -0.705399 -0.449657 -0.547909 -0.705411 -0.547904 -0.44966 -0.705413 -0.547921 -0.449667 -0.705395 -0.625119 -0.334135 -0.705394 -0.625117 -0.334134 -0.705395 -0.678292 -0.205762 -0.705395 -0.678308 -0.205762 -0.705379 -0.705419 -0.0694709 -0.705378 -0.705398 -0.0694746 -0.705398 0.258719 -0.0254813 -0.965616 0.25871 -0.0254782 -0.965619 0.248767 -0.0754634 -0.965619 0.24877 -0.0754652 -0.965618 0.229268 -0.122548 -0.965618 0.229264 -0.122545 -0.965619 0.200954 -0.164916 -0.965619 0.200955 -0.164917 -0.965619 0.164918 -0.200954 -0.965619 0.164922 -0.200962 -0.965616 0.122547 -0.229273 -0.965617 0.122542 -0.229258 -0.965621 0.0754628 -0.248762 -0.96562 0.0754639 -0.248776 -0.965617 0.0254811 -0.258714 -0.965618 0.0254812 -0.258713 -0.965618 -0.0254816 -0.258713 -0.965618 -0.0254811 -0.258712 -0.965618 -0.0754631 -0.248769 -0.965619 -0.0754635 -0.24877 -0.965618 -0.122545 -0.229269 -0.965618 -0.122548 -0.229273 -0.965617 -0.164927 -0.200959 -0.965616 -0.164919 -0.200953 -0.965619 -0.200952 -0.164919 -0.965619 -0.200952 -0.164919 -0.965619 -0.229264 -0.122546 -0.965619 -0.229268 -0.122547 -0.965618 -0.24877 -0.0754645 -0.965618 -0.248767 -0.0754642 -0.965619 -0.258709 -0.0254803 -0.965619 -0.258719 -0.0254791 -0.965617 -0.444311 -0.8952 -0.034703 -0.44564 -0.894023 -0.0461374 -0.441916 -0.895353 -0.0552537 -0.433024 -0.899732 -0.0545246 -0.441585 -0.896993 -0.0201433 -0.438439 -0.898741 -0.00598958 0.167515 -0.818259 -0.549901 -0.0663067 -0.964637 -0.255104 -0.0553112 -0.980868 -0.186649 -0.135353 -0.946067 -0.29434 -0.150926 -0.982898 -0.105509 -0.233841 -0.947184 -0.219455 -0.263711 -0.963575 -0.0444849 -0.328335 -0.936103 -0.126124 -0.328769 -0.942873 -0.0538642 -0.372409 -0.92246 -0.101877 -0.374189 -0.926271 -0.0447604 -0.413044 -0.908178 -0.0678797 -0.409925 -0.910563 -0.0532705 -0.431844 -0.900159 -0.0567821 0.283864 -0.723588 -0.629159 0.110702 -0.653046 -0.749183 0.31933 -0.477366 -0.818627 0.256421 -0.497422 -0.828746 0.118194 -0.452102 -0.884101 -0.00143153 -0.270191 -0.962806 -0.443023 -0.89591 -0.0328078 -0.433182 -0.900624 -0.0350702 -0.432504 -0.900998 -0.0338188 -0.418364 -0.907731 -0.0315759 -0.420309 -0.906505 -0.0398542 -0.396701 -0.917584 -0.0258344 -0.39386 -0.917264 -0.0591665 -0.369298 -0.928754 -0.0321716 -0.366636 -0.927475 -0.0732662 -0.332149 -0.942761 -0.0296395 -0.306161 -0.943605 -0.125997 -0.2633 -0.96237 -0.0672034 -0.246164 -0.95382 -0.172136 -0.162598 -0.984808 -0.0609484 -0.0116094 -0.896166 -0.443567 -0.00852348 -0.897323 -0.441293 -0.0303047 -0.797236 -0.602906 -0.0900942 -0.776643 -0.623465 -0.144812 -0.693956 -0.705305 -0.43561 -0.899991 -0.0161014 -0.439711 -0.898051 -0.0125877 -0.437076 -0.899365 -0.010326 -0.432321 -0.901647 -0.0114242 -0.432881 -0.901368 -0.0122173 -0.426161 -0.904579 -0.0111308 -0.426582 -0.904359 -0.0127434 -0.417711 -0.908549 -0.00746843 -0.415731 -0.909277 -0.0195608 -0.406741 -0.913493 -0.00966209 -0.404834 -0.914099 -0.0230958 -0.392846 -0.919571 -0.00787227 -0.380471 -0.923973 -0.0389385 -0.365681 -0.930553 -0.0186661 -0.356759 -0.93264 -0.0538956 -0.325989 -0.945283 -0.0130621 -0.255082 -0.95475 -0.152922 -0.246181 -0.958093 -0.14647 -0.248138 -0.943966 -0.217612 -0.254765 -0.941682 -0.21984 -0.271451 -0.927016 -0.258758 -0.980798 0 -0.195027 -0.965932 -0.00151184 -0.258791 -0.896844 0 -0.442347 -0.793387 0 -0.608717 -0.707105 -0.00201828 -0.707105 -0.1951 0 -0.980783 -0.258803 -0.00151032 -0.965929 -0.442194 0 -0.896919 -0.608731 0 -0.793377 -0.0198852 -0.258786 -0.96573 -0.0591893 -0.252721 -0.965727 -0.0591886 -0.25271 -0.96573 -0.161487 -0.689479 -0.706074 -0.161487 -0.689497 -0.706057 -0.220312 -0.940661 -0.258108 -0.220313 -0.940658 -0.258116 -0.0198848 -0.258791 -0.965729 -0.046724 -0.608089 -0.792493 -0.064584 -0.704837 -0.706423 -0.060849 -0.791871 -0.607649 -0.0740199 -0.963274 -0.258118 -0.0740179 -0.963278 -0.258104 -0.188435 -0.00457299 -0.982075 -0.195083 -0.0130589 -0.9807 -0.428212 -0.00797803 -0.903643 -0.44215 -0.0141188 -0.89683 -0.591071 -0.0073828 -0.806586 -0.608533 -0.025502 -0.793119 -0.773945 -0.00825203 -0.633199 -0.792942 -0.0334999 -0.608375 -0.879204 -0.0156455 -0.476189 -0.896484 -0.0283345 -0.442169 -0.970554 0.000659673 -0.240884 -0.979218 -0.0567291 -0.194713 0 -0.195088 -0.980786 -0.00186801 -0.258842 -0.965918 0.00124856 -0.555595 -0.831452 0 -0.608754 -0.793359 0 -0.831467 -0.555574 0.00186769 -0.79334 -0.608776 -0.00247712 -0.980783 -0.195087 0 -0.965927 -0.258814 -0.289812 -0.703883 -0.648505 -0.536224 -0.547556 -0.642375 -0.322167 -0.442387 -0.83696 -0.512228 -0.469255 -0.719321 -0.266987 -0.239074 -0.933574 -0.175274 -0.191797 -0.965657 -0.121773 -0.0890765 -0.988553 0.432405 -0.900214 -0.0513907 0.405039 -0.90911 -0.0972787 0.143843 -0.676297 -0.722449 0.151422 -0.721306 -0.675861 0.161294 -0.847283 -0.506059 0.153146 -0.925929 -0.345256 -0.846408 -0.259762 -0.464884 0.105351 -0.967908 -0.228158 0.0503025 -0.97852 -0.199923 -0.0301073 -0.978972 -0.201758 -0.0336721 -0.978876 -0.201663 -0.254252 -0.884236 -0.391768 -0.339967 -0.891853 -0.298363 -0.667575 -0.684229 -0.293554 -0.669589 -0.68374 -0.290087 -0.812135 -0.499289 -0.301908 -0.920721 -0.259163 -0.291731 -0.929435 -0.285188 -0.234133 -0.748894 -0.229835 -0.621557 -0.67947 -0.179907 -0.711305 -0.576379 -0.17688 -0.79781 -0.419834 -0.128839 -0.89841 -0.255709 -0.0592896 -0.964934 -0.185665 -0.0569759 -0.98096 0.0149891 -0.195066 -0.980676 0.014989 -0.195065 -0.980676 0.0426537 -0.55509 -0.830696 0.0426523 -0.555084 -0.8307 0.0637595 -0.829775 -0.554443 0.0637594 -0.829775 -0.554444 0.0751499 -0.978012 -0.194536 0.0751502 -0.978013 -0.194534 0.0446126 -0.190482 -0.980676 0.0446138 -0.190486 -0.980676 0.126956 -0.542059 -0.830695 0.126959 -0.542067 -0.830689 0.189781 -0.810291 -0.554447 0.189781 -0.810293 -0.554445 0.223686 -0.955051 -0.194531 0.223683 -0.955048 -0.194548 -0.288083 -0.683324 -0.670878 0.433428 -0.900857 -0.0244484 0.438439 -0.898741 -0.00598958 0.445393 -0.894379 -0.0413758 0.437025 -0.899392 -0.010174 0.44358 -0.894294 -0.0589493 0.433336 -0.899425 -0.0570405 0.432223 -0.899776 -0.0598838 0.413241 -0.908845 -0.0568539 0.408389 -0.910278 -0.0679139 0.38472 -0.92146 -0.0538679 0.362335 -0.926749 -0.0992449 0.34365 -0.935804 -0.0785889 0.310646 -0.943381 -0.116327 0.290583 -0.952532 -0.0908014 0.207471 -0.955972 -0.207543 0.186507 -0.966081 -0.178612 0.0900295 -0.95936 -0.267437 0.437206 -0.899317 -0.00893881 0.432085 -0.901776 -0.0101082 0.433215 -0.901257 -0.0078133 0.428891 -0.903328 -0.00713147 0.42724 -0.904092 -0.00911257 0.424278 -0.905502 -0.00735019 0.417784 -0.908451 -0.0131348 0.415928 -0.90933 -0.0110903 0.407972 -0.912881 -0.0144268 0.407575 -0.913066 -0.0139219 0.387819 -0.92138 -0.0255932 0.388082 -0.921259 -0.0259551 0.366281 -0.929881 -0.0340502 0.364662 -0.930594 -0.0318849 0.280177 -0.953443 -0.111572 0.432348 -0.901302 -0.0270128 0.423581 -0.905497 -0.0255917 0.42128 -0.906462 -0.0291376 0.412389 -0.910696 -0.0238364 0.398248 -0.91636 -0.0410194 0.393365 -0.918692 -0.0356231 0.375213 -0.925747 -0.046981 0.373071 -0.926747 -0.0442519 0.326588 -0.941589 -0.0821598 0.326409 -0.941673 -0.0819123 0.274522 -0.955349 -0.1093 0.278227 -0.953694 -0.114269 0.0820606 -0.942785 -0.323144 0.436227 -0.899729 -0.0139121 0.43975 -0.898081 -0.00843914 0.446546 -0.894455 -0.0233811 0.441198 -0.897037 -0.0258679 0.441195 -0.897029 -0.02619 0.442038 -0.896715 -0.0224454 0.445499 -0.894319 -0.0415325 0.432327 -0.900616 -0.0445432 0.43351 -0.900199 -0.0413633 0.419576 -0.906876 -0.0391541 0.41426 -0.908823 -0.0492849 0.39865 -0.916232 -0.0399564 0.380344 -0.922263 -0.0690611 0.369795 -0.927338 -0.0574137 0.342797 -0.935932 -0.0807539 0.334123 -0.939948 -0.0697106 0.266244 -0.953226 -0.143089 0.258981 -0.956673 -0.13306 0.181991 -0.965266 -0.187457 0.173364 -0.969026 -0.17588 -0.104594 -0.847209 -0.520862 -0.294924 -0.685732 -0.665426 -0.0521404 -0.905632 -0.420846 0.031432 -0.999173 -0.0258002 0.0468315 -0.976776 -0.209082 -0.26057 -0.442354 -0.858153 -0.186595 -0.476828 -0.858963 -0.120259 -0.713137 -0.690633 0.00706296 -0.800058 -0.599881 0.0727432 -0.887855 -0.454338 0.159285 -0.911562 -0.379056 0.259838 -0.952327 -0.159868 0.29627 -0.94712 -0.123239 -0.122445 -0.239743 -0.963084 -0.00764314 -0.349809 -0.93679 0.0204442 -0.569518 -0.821725 0.10701 -0.632461 -0.767165 0.15991 -0.81763 -0.553091 0.210905 -0.839369 -0.500978 0.272771 -0.942101 -0.195042 0.290376 -0.941674 -0.170096 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965924 -0.258825 0 -0.965924 -0.258825 0 -0.965924 0.258825 0 -0.965924 0.258825 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965927 0.258813 0 0.965927 0.258813 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965924 -0.258826 0 -0.965924 -0.258826 0 -0.965924 0.258825 0 -0.965924 0.258825 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965927 0.258813 0 0.965927 0.258813 0 0.965927 -0.258814 0 0.965927 -0.258814 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.939693 0 0.34202 -0.939693 0 0.34202 -0.183734 0.923695 0.336198 -0.183733 0.923696 0.336197 -0.523229 0.783072 0.336197 -0.523232 0.78307 0.336199 -0.783073 0.523226 0.3362 -0.783071 0.523233 0.336196 -0.923695 0.183738 0.336196 -0.923695 0.183735 0.336197 -0.923695 -0.183738 0.336197 -0.923696 -0.183736 0.336196 -0.783075 -0.523227 0.336196 -0.78307 -0.523232 0.3362 -0.523229 -0.783072 0.336199 -0.523232 -0.783071 0.336197 -0.183734 -0.923695 0.336198 -0.183734 -0.923695 0.336198 0 0.939692 0.34202 0 0.939692 0.34202 0 -0.939693 0.34202 0 -0.939693 0.34202 0.923695 0.183738 0.336197 0.923696 0.183736 0.336195 0.78307 0.523234 0.336196 0.783071 0.523233 0.336195 0.523234 0.78307 0.336196 0.523233 0.78307 0.336197 0.183734 0.923695 0.336197 0.183733 0.923695 0.336198 0.183734 -0.923695 0.336198 0.183734 -0.923695 0.336198 0.523234 -0.78307 0.336197 0.523232 -0.783071 0.336196 0.783071 -0.523233 0.336195 0.783071 -0.523233 0.336196 0.923695 -0.183738 0.336196 0.923695 -0.183735 0.336197 0.939693 0 0.34202 0.939693 0 0.34202 -0.939693 0 0.34202 -0.939693 0 0.34202 -0.183734 0.923695 0.336198 -0.183733 0.923696 0.336197 -0.523234 0.78307 0.336197 -0.523233 0.783071 0.336196 -0.783071 0.523233 0.336196 -0.783071 0.523233 0.336196 -0.923695 0.183738 0.336196 -0.923695 0.183735 0.336197 -0.923695 -0.183738 0.336197 -0.923696 -0.183736 0.336195 -0.783071 -0.523233 0.336196 -0.783071 -0.523233 0.336195 -0.523234 -0.78307 0.336196 -0.523233 -0.78307 0.336197 -0.183734 -0.923695 0.336198 -0.183733 -0.923695 0.336198 0 0.939693 0.34202 0 0.939693 0.34202 0 -0.939693 0.34202 0 -0.939693 0.34202 0.923693 0.183738 0.336203 0.923698 0.183724 0.336195 0.783071 0.523233 0.336196 0.783071 0.523233 0.336195 0.523234 0.78307 0.336196 0.523227 0.783073 0.336201 0.183734 0.923695 0.336199 0.183735 0.923695 0.336198 0.183734 -0.923695 0.336198 0.183735 -0.923695 0.336199 0.523233 -0.783069 0.3362 0.523228 -0.783074 0.336196 0.783071 -0.523233 0.336196 0.783071 -0.523233 0.336196 0.923695 -0.183738 0.336196 0.923695 -0.183724 0.336203 0.939691 0 0.342025 0.939691 0 0.342025 -0.939691 0 0.342025 -0.939691 0 0.342025 -0.183734 0.923695 0.336198 -0.183735 0.923695 0.336199 -0.523233 0.783069 0.3362 -0.523228 0.783074 0.336196 -0.783071 0.523233 0.336195 -0.783071 0.523233 0.336196 -0.923695 0.183738 0.336196 -0.923695 0.183724 0.336203 -0.923693 -0.183738 0.336203 -0.923698 -0.183724 0.336195 -0.78307 -0.523234 0.336196 -0.783071 -0.523233 0.336195 -0.523234 -0.78307 0.336196 -0.523227 -0.783073 0.336201 -0.183734 -0.923695 0.336198 -0.183737 -0.923695 0.336197 0 0.939692 0.34202 0 0.939692 0.34202 0 -0.939693 0.34202 0 -0.939693 0.34202 0.923696 0.183729 0.336198 0.923694 0.183735 0.336201 0.783069 0.523232 0.3362 0.783069 0.523232 0.3362 0.523229 0.783072 0.336199 0.523233 0.78307 0.336197 0.183736 0.923695 0.336197 0.183735 0.923695 0.336198 0.183736 -0.923695 0.336197 0.183737 -0.923695 0.336197 0.523229 -0.783072 0.336197 0.523232 -0.78307 0.336199 0.783069 -0.523233 0.3362 0.783069 -0.523232 0.3362 0.923695 -0.183729 0.336201 0.923695 -0.183735 0.336197 0.939693 0 0.34202 0.939693 0 0.34202 -0.098017 0 0.995185 -0.290285 0 0.95694 -0.290285 0 0.95694 -0.471397 0 0.881921 -0.471397 0 0.881921 -0.634392 0 0.773011 -0.634392 0 0.773011 -0.773012 0 0.634392 -0.773012 0 0.634392 -0.881921 0 0.471397 -0.881921 0 0.471397 -0.95694 0 0.290284 -0.95694 0 0.290284 -0.995185 0 0.098018 -0.995185 0 0.098018 -0.995185 0 -0.098018 -0.995185 0 -0.098018 -0.95694 0 -0.290284 -0.95694 0 -0.290284 -0.881921 0 -0.471397 -0.881921 0 -0.471397 -0.773012 0 -0.634392 -0.773012 0 -0.634392 -0.634392 0 -0.773011 -0.634392 0 -0.773011 -0.471398 0 -0.881921 -0.471398 0 -0.881921 -0.290284 0 -0.956941 -0.290284 0 -0.956941 -0.0980175 0 -0.995185 -0.0980175 0 -0.995185 0.0980173 0 -0.995185 0.0980173 0 -0.995185 0.290285 0 -0.95694 0.290285 0 -0.95694 0.471397 0 -0.881921 0.471397 0 -0.881921 0.634393 0 -0.77301 0.634393 0 -0.77301 0.77301 0 -0.634393 0.77301 0 -0.634393 0.881921 0 -0.471397 0.881921 0 -0.471397 0.95694 0 -0.290284 0.95694 0 -0.290284 0.995185 0 -0.098018 0.995185 0 -0.098018 0.995185 0 0.098018 0.995185 0 0.098018 0.95694 0 0.290284 0.95694 0 0.290284 0.881921 0 0.471397 0.881921 0 0.471397 0.77301 0 0.634393 0.77301 0 0.634393 0.634393 0 0.77301 0.634393 0 0.77301 0.471396 0 0.881921 0.471396 0 0.881921 0.290285 0 0.95694 0.290285 0 0.95694 0.0980167 0 0.995185 0.0980167 0 0.995185 -0.098017 0 0.995185 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0825795 0 -0.996585 -0.245486 0 -0.9694 -0.245486 0 -0.9694 -0.401696 0 -0.915773 -0.401696 0 -0.915773 -0.546948 0 -0.837167 -0.546948 0 -0.837167 -0.677282 0 -0.735724 -0.677282 0 -0.735724 -0.78914 0 -0.614213 -0.78914 0 -0.614213 -0.879474 0 -0.475947 -0.879474 0 -0.475947 -0.945817 0 -0.324699 -0.945817 0 -0.324699 -0.986361 0 -0.164595 -0.986361 0 -0.164595 -1 0 0 -1 0 0 -0.986361 0 0.164595 -0.986361 0 0.164595 -0.945817 0 0.324699 -0.945817 0 0.324699 -0.879474 0 0.475947 -0.879474 0 0.475947 -0.78914 0 0.614213 -0.78914 0 0.614213 -0.677282 0 0.735724 -0.677282 0 0.735724 -0.546948 0 0.837167 -0.546948 0 0.837167 -0.401696 0 0.915773 -0.401696 0 0.915773 -0.245485 0 0.9694 -0.245485 0 0.9694 -0.0825795 0 0.996585 -0.0825795 0 0.996585 0.0825794 0 0.996584 0.0825794 0 0.996584 0.245485 0 0.9694 0.245485 0 0.9694 0.401696 0 0.915773 0.401696 0 0.915773 0.546948 0 0.837167 0.546948 0 0.837167 0.677282 0 0.735724 0.677282 0 0.735724 0.78914 0 0.614213 0.78914 0 0.614213 0.879474 0 0.475947 0.879474 0 0.475947 0.945817 0 0.324699 0.945817 0 0.324699 0.986361 0 0.164596 0.986361 0 0.164596 1 0 0 1 0 0 0.986361 0 -0.164596 0.986361 0 -0.164596 0.945817 0 -0.324699 0.945817 0 -0.324699 0.879474 0 -0.475947 0.879474 0 -0.475947 0.78914 0 -0.614213 0.78914 0 -0.614213 0.677282 0 -0.735724 0.677282 0 -0.735724 0.546948 0 -0.837167 0.546948 0 -0.837167 0.401696 0 -0.915773 0.401696 0 -0.915773 0.245486 0 -0.9694 0.245486 0 -0.9694 0.0825794 0 -0.996584 0.0825794 0 -0.996584 -0.0825795 0 -0.996585 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.0185061 -0.965767 -0.258751 0.050509 -0.706198 -0.706211 0.0689197 -0.258207 -0.963628 0.0689198 -0.258207 -0.963628 0.205358 -0.258207 -0.944011 0.205358 -0.258207 -0.944012 0.337613 -0.258206 -0.905178 0.337613 -0.258207 -0.905178 0.462998 -0.258207 -0.847916 0.462999 -0.258209 -0.847915 0.578955 -0.25821 -0.773395 0.578955 -0.25821 -0.773394 0.68313 -0.258211 -0.683126 0.683128 -0.2582 -0.683132 0.773394 -0.258199 -0.578961 0.773395 -0.258215 -0.578952 0.847917 -0.258216 -0.462992 0.847917 -0.258197 -0.463003 0.90518 -0.258197 -0.337616 0.905179 -0.258202 -0.337613 0.944013 -0.258202 -0.205358 0.944011 -0.25821 -0.205353 0.963627 -0.25821 -0.0689191 0.963627 -0.25821 -0.0689193 0.963627 -0.25821 0.0689191 0.963627 -0.25821 0.0689192 0.944011 -0.25821 0.205357 0.944014 -0.258202 0.205354 0.905178 -0.258202 0.337615 0.90518 -0.258197 0.337613 0.847921 -0.258197 0.462995 0.847912 -0.258216 0.463 0.77339 -0.258215 0.578958 0.773398 -0.258199 0.578955 0.683132 -0.2582 0.683128 0.683126 -0.258211 0.68313 0.578955 -0.25821 0.773395 0.578955 -0.258209 0.773395 0.462998 -0.258208 0.847916 0.462999 -0.258207 0.847916 0.337613 -0.258207 0.905178 0.337613 -0.258207 0.905178 0.205358 -0.258207 0.944011 0.205358 -0.258207 0.944011 0.0689197 -0.258207 0.963628 0.0689198 -0.258207 0.963628 0.0505088 -0.706198 -0.706211 0.1505 -0.706198 -0.691834 0.150499 -0.706197 -0.691835 0.247426 -0.706196 -0.663376 0.247426 -0.706198 -0.663374 0.339316 -0.706198 -0.621409 0.339316 -0.706197 -0.62141 0.424297 -0.706197 -0.566796 0.424297 -0.706196 -0.566797 0.500642 -0.706196 -0.500645 0.500641 -0.706199 -0.500641 0.566796 -0.706199 -0.424295 0.566797 -0.706196 -0.424298 0.62141 -0.706196 -0.339319 0.621407 -0.706201 -0.339314 0.663372 -0.706201 -0.247424 0.663374 -0.706197 -0.247427 0.691836 -0.706197 -0.150497 0.691835 -0.706197 -0.150496 0.706211 -0.706197 -0.0505087 0.706211 -0.706197 -0.0505089 0.706211 -0.706197 0.0505087 0.706211 -0.706197 0.0505089 0.691835 -0.706198 0.150497 0.691836 -0.706197 0.150497 0.663375 -0.706197 0.247425 0.663371 -0.706201 0.247426 0.621406 -0.7062 0.339317 0.621412 -0.706196 0.339316 0.566798 -0.706196 0.424296 0.566794 -0.706199 0.424296 0.50064 -0.706199 0.500643 0.500644 -0.706196 0.500643 0.424298 -0.706196 0.566797 0.424296 -0.706198 0.566796 0.339316 -0.706198 0.621409 0.339316 -0.706198 0.621409 0.247425 -0.706198 0.663374 0.247427 -0.706196 0.663376 0.1505 -0.706196 0.691835 0.150499 -0.706199 0.691834 0.050509 -0.706198 0.70621 0.0505091 -0.706198 0.706211 0.0185061 -0.965767 -0.258751 0.0551418 -0.965767 -0.253484 0.0551419 -0.965767 -0.253483 0.0906552 -0.965767 -0.243056 0.0906552 -0.965767 -0.243056 0.124323 -0.965767 -0.22768 0.124323 -0.965766 -0.227682 0.15546 -0.965766 -0.207672 0.15546 -0.965767 -0.20767 0.183432 -0.965767 -0.183432 0.183431 -0.965767 -0.18343 0.207669 -0.965767 -0.155459 0.207669 -0.965767 -0.155459 0.227679 -0.965767 -0.124322 0.227681 -0.965766 -0.124325 0.243057 -0.965766 -0.0906561 0.243055 -0.965767 -0.0906536 0.253482 -0.965767 -0.0551405 0.253486 -0.965766 -0.0551438 0.258754 -0.965766 -0.0185063 0.258754 -0.965766 -0.0185065 0.258754 -0.965766 0.0185063 0.258754 -0.965766 0.0185064 0.253486 -0.965766 0.0551415 0.253481 -0.965767 0.0551428 0.243054 -0.965767 0.0906551 0.243058 -0.965766 0.0906546 0.227682 -0.965766 0.124323 0.227679 -0.965767 0.124323 0.207669 -0.965767 0.155459 0.207669 -0.965767 0.155459 0.183431 -0.965767 0.183431 0.183432 -0.965767 0.183431 0.155459 -0.965767 0.20767 0.155461 -0.965766 0.207671 0.124324 -0.965766 0.227681 0.124323 -0.965767 0.227681 0.0906554 -0.965767 0.243056 0.0906551 -0.965767 0.243056 0.0551417 -0.965767 0.253483 0.0551422 -0.965767 0.253484 0.0185062 -0.965767 0.258751 0.0185061 -0.965767 0.258751 -0.0185063 -0.965767 0.258751 -0.0505093 -0.706198 0.706211 -0.0689201 -0.258207 0.963628 -0.0689203 -0.258207 0.963628 -0.205357 -0.258207 0.944012 -0.205357 -0.258207 0.944012 -0.337615 -0.258206 0.905177 -0.337615 -0.258207 0.905177 -0.462998 -0.258207 0.847916 -0.462997 -0.258202 0.847919 -0.578956 -0.258201 0.773396 -0.578958 -0.25821 0.773392 -0.68313 -0.258211 0.683126 -0.683128 -0.258199 0.683132 -0.773394 -0.258199 0.578961 -0.773395 -0.258215 0.578952 -0.847917 -0.258216 0.462992 -0.847917 -0.258197 0.463002 -0.90518 -0.258197 0.337616 -0.905179 -0.258202 0.337613 -0.944013 -0.258202 0.205358 -0.944013 -0.258197 0.20536 -0.963631 -0.258197 0.0689193 -0.963631 -0.258197 0.0689195 -0.963631 -0.258197 -0.0689194 -0.963631 -0.258197 -0.0689195 -0.944014 -0.258197 -0.205358 -0.944012 -0.258202 -0.20536 -0.905178 -0.258202 -0.337615 -0.905181 -0.258197 -0.337613 -0.847921 -0.258197 -0.462995 -0.847912 -0.258216 -0.463 -0.77339 -0.258215 -0.578958 -0.773398 -0.258199 -0.578955 -0.683132 -0.2582 -0.683128 -0.683126 -0.258211 -0.68313 -0.578955 -0.25821 -0.773395 -0.578959 -0.258202 -0.773394 -0.462999 -0.258203 -0.847917 -0.462996 -0.258207 -0.847917 -0.337615 -0.258207 -0.905177 -0.337615 -0.258206 -0.905177 -0.205356 -0.258207 -0.944012 -0.205356 -0.258207 -0.944012 -0.0689201 -0.258207 -0.963628 -0.0689203 -0.258207 -0.963628 -0.0505094 -0.706198 0.70621 -0.150499 -0.706199 0.691834 -0.150499 -0.706198 0.691834 -0.247426 -0.706198 0.663373 -0.247426 -0.706198 0.663374 -0.339314 -0.706198 0.62141 -0.339315 -0.706201 0.621406 -0.424297 -0.706202 0.56679 -0.424297 -0.706196 0.566797 -0.500642 -0.706196 0.500645 -0.500641 -0.706199 0.500641 -0.566795 -0.706199 0.424295 -0.566797 -0.706196 0.424298 -0.62141 -0.706196 0.339319 -0.621407 -0.7062 0.339314 -0.663372 -0.706201 0.247424 -0.663374 -0.706197 0.247427 -0.691835 -0.706197 0.150501 -0.691828 -0.706205 0.150495 -0.706204 -0.706205 0.0505082 -0.706211 -0.706197 0.0505138 -0.706211 -0.706197 -0.0505087 -0.706204 -0.706205 -0.0505132 -0.691828 -0.706204 -0.1505 -0.691836 -0.706197 -0.150497 -0.663375 -0.706197 -0.247425 -0.663371 -0.706201 -0.247426 -0.621406 -0.7062 -0.339317 -0.621412 -0.706196 -0.339316 -0.566798 -0.706196 -0.424297 -0.566794 -0.706199 -0.424296 -0.50064 -0.706199 -0.500643 -0.500643 -0.706196 -0.500643 -0.4243 -0.706196 -0.566795 -0.424294 -0.706201 -0.566793 -0.339313 -0.706201 -0.621408 -0.339316 -0.706198 -0.621409 -0.247427 -0.706198 -0.663374 -0.247426 -0.706199 -0.663373 -0.150499 -0.706198 -0.691834 -0.150499 -0.706198 -0.691834 -0.0505094 -0.706198 -0.706211 -0.0505091 -0.706198 -0.706211 -0.0185063 -0.965767 0.258751 -0.0551418 -0.965767 0.253484 -0.055142 -0.965767 0.253483 -0.0906552 -0.965767 0.243056 -0.0906552 -0.965767 0.243056 -0.124323 -0.965767 0.22768 -0.124323 -0.965766 0.227682 -0.15546 -0.965766 0.207672 -0.15546 -0.965767 0.20767 -0.183432 -0.965767 0.183432 -0.183432 -0.965766 0.183433 -0.207671 -0.965766 0.155461 -0.207671 -0.965766 0.155461 -0.227682 -0.965766 0.124324 -0.227682 -0.965766 0.124323 -0.243057 -0.965766 0.0906561 -0.243055 -0.965767 0.0906535 -0.253482 -0.965767 0.0551405 -0.253486 -0.965766 0.0551438 -0.258754 -0.965766 0.0185081 -0.25875 -0.965767 0.0185062 -0.258751 -0.965767 -0.0185079 -0.258754 -0.965766 -0.0185064 -0.253486 -0.965766 -0.0551415 -0.253481 -0.965767 -0.0551428 -0.243054 -0.965767 -0.0906551 -0.243058 -0.965766 -0.0906547 -0.227682 -0.965766 -0.124323 -0.227682 -0.965766 -0.124323 -0.207671 -0.965766 -0.155461 -0.207671 -0.965766 -0.155461 -0.183433 -0.965766 -0.183433 -0.183431 -0.965767 -0.183432 -0.155459 -0.965767 -0.20767 -0.155461 -0.965766 -0.207671 -0.124324 -0.965766 -0.227681 -0.124323 -0.965767 -0.227681 -0.0906554 -0.965767 -0.243056 -0.0906551 -0.965767 -0.243056 -0.0551417 -0.965767 -0.253483 -0.055142 -0.965767 -0.253484 -0.0185062 -0.965767 -0.258751 -0.0185063 -0.965767 -0.258751 -0.0713392 0 0.997452 -0.142285 0.0203528 0.989616 -0.212565 0 0.977147 -0.349465 0 0.936949 -0.41533 0.0203528 0.909443 -0.47925 0 0.877679 -0.599277 0 0.800542 -0.654726 0.0203534 0.755593 -0.707109 0 0.707105 -0.800539 0 0.599281 -0.841079 0.0203542 0.540529 -0.877681 0 0.479245 -0.936949 0 0.349465 -0.959294 0.020353 0.281675 -0.977147 0 0.212566 -0.997452 0 0.0713383 -0.999793 0.0203526 0 -0.997452 0 -0.0713383 -0.977147 0 -0.212566 -0.959294 0.020353 -0.281675 -0.936949 0 -0.349465 -0.877681 0 -0.479245 -0.841079 0.0203542 -0.540529 -0.800539 0 -0.599281 -0.707109 0 -0.707105 -0.654726 0.0203534 -0.755593 -0.599277 0 -0.800542 -0.47925 0 -0.877679 -0.41533 0.0203527 -0.909443 -0.349465 0 -0.936949 -0.212564 0 -0.977147 -0.142285 0.0203527 -0.989616 -0.0713392 0 -0.997452 0.0713388 0 -0.997452 0.142285 0.020353 -0.989616 0.212566 0 -0.977147 0.349463 0 -0.93695 0.415329 0.0203531 -0.909444 0.47925 0 -0.877679 0.599277 0 -0.800542 0.654726 0.0203534 -0.755593 0.707109 0 -0.707105 0.800539 0 -0.599281 0.841079 0.0203542 -0.540529 0.877681 0 -0.479245 0.936949 0 -0.349465 0.959294 0.020353 -0.281675 0.977147 0 -0.212566 0.997452 0 -0.0713383 0.999793 0.0203526 0 0.997452 0 0.0713383 0.977147 0 0.212566 0.959294 0.020353 0.281675 0.936949 0 0.349465 0.877681 0 0.479245 0.841079 0.0203542 0.540529 0.800539 0 0.599281 0.707109 0 0.707105 0.654726 0.0203534 0.755593 0.599277 0 0.800542 0.47925 0 0.877679 0.415329 0.0203531 0.909444 0.349463 0 0.93695 0.212567 0 0.977147 0.142285 0.0203531 0.989616 0.0713388 0 0.997452 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.99863 0 -0.052336 -0.99863 0 -0.052336 -0.995559 0.0783525 -0.0521751 -0.996064 0.0712392 -0.0527432 -0.983091 0.175544 -0.0521219 -0.984305 0.168541 -0.0523169 -0.966276 0.252154 -0.0522451 -0.969737 0.238308 -0.0530947 -0.936947 0.34566 -0.0514793 -0.941749 0.332232 -0.0522614 -0.906901 0.418085 -0.0522959 -0.915611 0.398537 -0.0531389 -0.861637 0.505015 -0.0504093 -0.87645 0.478579 -0.0528937 -0.819301 0.570996 -0.0520542 -0.799497 0.598499 -0.0510237 -0.759303 0.648509 -0.053808 -0.598497 0.799499 -0.051024 -0.648505 0.759306 -0.0538083 -0.68049 0.730888 -0.0523025 -0.73089 0.680488 -0.0523025 -0.0712413 0.996092 -0.0522029 -0.0783504 0.995531 -0.0527193 -0.168535 0.984313 -0.0521821 -0.175555 0.983078 -0.0523258 -0.238321 0.969778 -0.0522839 -0.252137 0.966243 -0.052926 -0.33224 0.941776 -0.0517206 -0.345645 0.936907 -0.0522957 -0.398568 0.915645 -0.0523276 -0.418079 0.90688 -0.0527041 -0.478621 0.876529 -0.0511713 -0.504955 0.861534 -0.0527219 -0.571016 0.819287 -0.0520537 0 0.99863 -0.0523359 0 0.99863 -0.0523359 0.0783527 0.995559 -0.052175 0.0712387 0.996064 -0.0527431 0.175557 0.983088 -0.0521218 0.168538 0.984306 -0.0523172 0.252146 0.966278 -0.0522454 0.23831 0.969737 -0.0530944 0.34566 0.936947 -0.051479 0.332231 0.941749 -0.0522612 0.418088 0.9069 -0.0522957 0.398551 0.915605 -0.0531382 0.505015 0.861637 -0.050409 0.478578 0.876451 -0.0528934 0.571001 0.819298 -0.0520539 0.598497 0.799499 -0.0510237 0.648509 0.759302 -0.0538081 0.799497 0.598499 -0.0510237 0.759303 0.648509 -0.053808 0.73089 0.680488 -0.0523025 0.68049 0.730888 -0.0523025 0.996092 0.0712412 -0.0522031 0.995531 0.0783503 -0.0527194 0.984312 0.168542 -0.0521822 0.98308 0.175543 -0.0523255 0.969779 0.238318 -0.0522836 0.966241 0.252145 -0.0529262 0.941775 0.332242 -0.0517209 0.936912 0.345631 -0.0522953 0.915651 0.398555 -0.0523273 0.906876 0.41809 -0.0527043 0.876529 0.478622 -0.0511716 0.861534 0.504955 -0.0527222 0.819301 0.570996 -0.0520542 0.99863 0 -0.052336 0.99863 0 -0.052336 0.995559 -0.0783525 -0.0521751 0.996064 -0.0712392 -0.0527432 0.983091 -0.175544 -0.0521219 0.984305 -0.168541 -0.0523169 0.966276 -0.252154 -0.0522451 0.969737 -0.238308 -0.0530947 0.936952 -0.345645 -0.0514796 0.941749 -0.332232 -0.0522608 0.906895 -0.418099 -0.0522953 0.915611 -0.398537 -0.0531389 0.861637 -0.505015 -0.0504093 0.87645 -0.478579 -0.0528937 0.819301 -0.570996 -0.0520542 0.799497 -0.598499 -0.0510237 0.759303 -0.648509 -0.053808 0.598498 -0.799498 -0.0510236 0.648509 -0.759302 -0.053808 0.680488 -0.73089 -0.0523025 0.73089 -0.680488 -0.0523025 0.0712408 -0.996092 -0.0522031 0.0783505 -0.995531 -0.0527195 0.168534 -0.984314 -0.0521823 0.17554 -0.983081 -0.0523258 0.238324 -0.969777 -0.0522839 0.252139 -0.966243 -0.052926 0.332242 -0.941775 -0.0517206 0.345645 -0.936907 -0.0522956 0.398555 -0.915651 -0.0523275 0.418079 -0.90688 -0.0527043 0.478622 -0.876528 -0.0511714 0.504955 -0.861534 -0.0527219 0.571001 -0.819298 -0.0520539 0 -0.99863 -0.052336 0 -0.99863 -0.052336 -0.0783527 -0.995559 -0.0521751 -0.0712393 -0.996064 -0.0527432 -0.175542 -0.983091 -0.0521219 -0.168529 -0.984307 -0.0523172 -0.252148 -0.966277 -0.0522454 -0.238314 -0.969736 -0.0530943 -0.34566 -0.936947 -0.051479 -0.332233 -0.941748 -0.052261 -0.418088 -0.9069 -0.0522956 -0.398537 -0.915611 -0.0531386 -0.505015 -0.861637 -0.0504091 -0.478579 -0.87645 -0.0528934 -0.571016 -0.819287 -0.0520536 -0.598498 -0.799498 -0.051024 -0.648505 -0.759306 -0.0538081 -0.799497 -0.598499 -0.0510237 -0.759303 -0.648509 -0.053808 -0.73089 -0.680488 -0.0523025 -0.680488 -0.73089 -0.0523025 -0.996092 -0.0712412 -0.0522031 -0.995531 -0.0783503 -0.0527194 -0.984312 -0.168542 -0.0521822 -0.98308 -0.175543 -0.0523255 -0.969779 -0.238318 -0.0522836 -0.966241 -0.252145 -0.0529262 -0.941775 -0.332242 -0.0517209 -0.936907 -0.345645 -0.0522959 -0.915651 -0.398555 -0.0523279 -0.906882 -0.418076 -0.0527046 -0.876529 -0.478622 -0.0511716 -0.861534 -0.504955 -0.0527222 -0.819301 -0.570996 -0.0520542 -0.99863 0 -0.052336 -0.99863 0 -0.052336 0.201517 0 0.979485 0.201517 0 0.979485 0.571784 0 0.820404 0.571784 0 0.820404 0.849199 0 0.528073 0.849199 0 0.528073 0.988691 0 0.149967 0.988691 0 0.149967 0.201496 0.0144116 0.979383 0.571306 0.0408617 0.819719 0.847637 0.0606211 0.527102 0.89898 0.317144 0.302082 0.926406 0.345531 0.149601 0.960145 0.235951 0.14983 0.934174 0.203222 0.29329 0.97452 0.166865 0.149888 0.986233 0.0705331 0.149567 0.986228 0.0705357 0.149594 0.906538 0.394588 0.149963 0.8678 0.473855 0.149612 0.867804 0.473855 0.149593 0.791532 0.592536 0.149594 0.79154 0.592536 0.149553 0.723629 0.673728 0.149836 0.674018 0.674022 0.302313 0.203215 0.934166 0.293323 0.673726 0.723623 0.149876 0.592534 0.791533 0.149597 0.592538 0.791535 0.149572 0.473857 0.867806 0.149575 0.473851 0.867803 0.149613 0.394602 0.906533 0.149961 0.336894 0.903243 0.265808 0.328933 0.932402 0.149766 0.235953 0.960145 0.149826 0.166861 0.974514 0.14993 0.0705352 0.986227 0.149606 0.0705366 0.986228 0.149594 0.847614 0.0606241 0.527138 0.830359 0.180638 0.527137 0.830372 0.180638 0.527117 0.796213 0.296972 0.527118 0.796212 0.296972 0.527118 0.745846 0.407261 0.527117 0.745837 0.407258 0.527131 0.680289 0.509256 0.527129 0.680298 0.50926 0.527114 0.600894 0.600897 0.527114 0.600909 0.600907 0.527086 0.509274 0.680308 0.527088 0.509261 0.680296 0.527116 0.40726 0.745849 0.527114 0.407273 0.745865 0.527081 0.296981 0.796232 0.527084 0.296973 0.79622 0.527105 0.180638 0.83038 0.527104 0.18064 0.830385 0.527095 0.0606246 0.84764 0.527097 0.0606238 0.847637 0.527102 0.571308 0.0408615 0.819718 0.559677 0.121751 0.819718 0.559697 0.121753 0.819704 0.536672 0.200168 0.819705 0.536667 0.200167 0.819708 0.502718 0.274505 0.819708 0.502726 0.274508 0.819702 0.458541 0.343256 0.819704 0.458505 0.343236 0.819733 0.404995 0.404994 0.819731 0.40499 0.40499 0.819736 0.343233 0.458508 0.819733 0.343242 0.458517 0.819724 0.274494 0.502699 0.819724 0.274494 0.502697 0.819725 0.200158 0.536647 0.819724 0.200162 0.536654 0.819718 0.12175 0.559675 0.81972 0.121748 0.559669 0.819724 0.0408599 0.5713 0.819724 0.0408612 0.571306 0.819719 0.201484 0.0144121 0.979386 0.197383 0.0429374 0.979386 0.197387 0.0429378 0.979385 0.189267 0.0705929 0.979385 0.18926 0.0705914 0.979386 0.177289 0.0968065 0.979386 0.177293 0.0968084 0.979385 0.161711 0.121056 0.979385 0.161714 0.121058 0.979384 0.14284 0.14284 0.979384 0.142846 0.142845 0.979383 0.121062 0.161719 0.979383 0.121057 0.161714 0.979384 0.0968108 0.177296 0.979384 0.0968118 0.177297 0.979384 0.070594 0.18927 0.979384 0.0705935 0.189269 0.979384 0.0429393 0.197389 0.979384 0.0429395 0.19739 0.979384 0.0144112 0.201492 0.979384 0.0144107 0.201489 0.979385 0.014411 -0.201489 0.979385 0.0408592 -0.571306 0.819719 0.0606243 -0.847637 0.527102 0.317144 -0.898977 0.302091 0.34553 -0.926403 0.14962 0.235956 -0.960142 0.149843 0.203215 -0.934159 0.293345 0.166856 -0.974515 0.14993 0.0705365 -0.986226 0.149606 0.0705353 -0.986228 0.149594 0.394587 -0.906536 0.149977 0.473855 -0.867797 0.149629 0.473854 -0.867808 0.149575 0.592537 -0.791535 0.149572 0.592537 -0.791533 0.149582 0.673725 -0.723626 0.149863 0.674018 -0.674022 0.302313 0.934174 -0.203222 0.29329 0.723629 -0.673728 0.149836 0.791537 -0.59254 0.149553 0.791535 -0.592532 0.149594 0.867803 -0.473857 0.149593 0.867801 -0.473854 0.149612 0.906538 -0.394588 0.149963 0.90325 -0.336895 0.265784 0.932401 -0.328935 0.149765 0.960145 -0.235951 0.14983 0.97452 -0.166865 0.149888 0.986232 -0.070536 0.149568 0.986229 -0.0705328 0.149594 0.0606228 -0.847648 0.527084 0.180642 -0.830393 0.527082 0.180642 -0.830387 0.527091 0.296977 -0.796227 0.527093 0.296978 -0.796233 0.527084 0.40727 -0.745867 0.527081 0.407263 -0.745846 0.527114 0.509264 -0.680294 0.527116 0.509274 -0.680316 0.527077 0.60091 -0.600914 0.527077 0.600897 -0.600894 0.527115 0.680297 -0.509261 0.527115 0.68029 -0.509254 0.527129 0.745838 -0.407257 0.527131 0.745845 -0.407263 0.527117 0.796212 -0.296972 0.527118 0.796213 -0.296972 0.527118 0.830371 -0.18064 0.527117 0.83036 -0.180635 0.527137 0.847615 -0.0606195 0.527138 0.847637 -0.0606257 0.527102 0.0408601 -0.571291 0.81973 0.121748 -0.559661 0.81973 0.12175 -0.559684 0.819714 0.200164 -0.536662 0.819712 0.20016 -0.536646 0.819724 0.274494 -0.502697 0.819725 0.274494 -0.502699 0.819724 0.34324 -0.458518 0.819724 0.34323 -0.458501 0.819738 0.404987 -0.404985 0.81974 0.404994 -0.404994 0.819731 0.458509 -0.343232 0.819733 0.458538 -0.343261 0.819704 0.502725 -0.274509 0.819702 0.502719 -0.274504 0.819708 0.536668 -0.200167 0.819708 0.536672 -0.200169 0.819705 0.559696 -0.121755 0.819705 0.55968 -0.121749 0.819717 0.571309 -0.0408619 0.819717 0.571306 -0.0408613 0.819719 0.0144109 -0.201492 0.979384 0.042939 -0.19739 0.979384 0.0429386 -0.197386 0.979385 0.0705928 -0.189265 0.979385 0.0705938 -0.18927 0.979384 0.0968116 -0.177297 0.979384 0.0968122 -0.177299 0.979384 0.121059 -0.161716 0.979384 0.121061 -0.16172 0.979383 0.142845 -0.142845 0.979383 0.142841 -0.142839 0.979384 0.161714 -0.121059 0.979384 0.161711 -0.121056 0.979385 0.177293 -0.096809 0.979385 0.177289 -0.096806 0.979386 0.189261 -0.0705907 0.979386 0.189266 -0.0705936 0.979385 0.197387 -0.0429383 0.979385 0.197382 -0.0429368 0.979386 0.201484 -0.0144107 0.979386 0.201496 -0.014413 0.979383 0 0.20151 0.979486 0 0.20151 0.979486 0 0.571784 0.820404 0 0.571784 0.820404 0 0.849199 0.528073 0 0.849199 0.528073 0 0.988691 0.149967 0 0.988691 0.149967 0 -0.20151 0.979486 0 -0.20151 0.979486 0 -0.571784 0.820404 0 -0.571784 0.820404 0 -0.849199 0.528073 0 -0.849199 0.528073 0 -0.988691 0.149967 0 -0.988691 0.149967 -0.014411 0.201489 0.979385 -0.0408603 0.571306 0.819719 -0.0606243 0.847637 0.527102 -0.31714 0.898972 0.302112 -0.345533 0.926405 0.149603 -0.235953 0.960145 0.149826 -0.203215 0.934166 0.293323 -0.166858 0.974517 0.149918 -0.0705366 0.986227 0.149601 -0.0705359 0.986228 0.149594 -0.394602 0.906533 0.149961 -0.473855 0.8678 0.149614 -0.473854 0.867808 0.149575 -0.592536 0.791536 0.149572 -0.592536 0.791532 0.149597 -0.673726 0.723623 0.149876 -0.674017 0.674013 0.302336 -0.934164 0.203212 0.29333 -0.723623 0.673723 0.149889 -0.79153 0.592534 0.149611 -0.791531 0.592538 0.149594 -0.867803 0.473857 0.149593 -0.867801 0.473854 0.149612 -0.906538 0.394588 0.149963 -0.90325 0.336895 0.265784 -0.932401 0.328935 0.149765 -0.960145 0.235951 0.14983 -0.97451 0.166864 0.149959 -0.986221 0.0705352 0.14964 -0.986228 0.0705407 0.149594 -0.060624 0.84764 0.527097 -0.180639 0.830385 0.527095 -0.180639 0.83038 0.527104 -0.296976 0.796219 0.527105 -0.296978 0.796233 0.527084 -0.40727 0.745867 0.527081 -0.407263 0.745846 0.527114 -0.509264 0.680294 0.527116 -0.509263 0.680291 0.52712 -0.600893 0.60089 0.527124 -0.600909 0.600915 0.527077 -0.680314 0.509281 0.527072 -0.68029 0.509254 0.527129 -0.745838 0.407257 0.527131 -0.745845 0.407263 0.527117 -0.796212 0.296972 0.527118 -0.796213 0.296972 0.527118 -0.830373 0.180634 0.527117 -0.830391 0.180642 0.527085 -0.847647 0.0606286 0.527085 -0.847637 0.0606257 0.527102 -0.0408607 0.5713 0.819724 -0.121749 0.559669 0.819724 -0.12175 0.559675 0.81972 -0.200161 0.536655 0.819718 -0.200159 0.536647 0.819724 -0.274494 0.502697 0.819725 -0.274494 0.502699 0.819724 -0.343243 0.458516 0.819724 -0.343247 0.458523 0.819718 -0.405006 0.405009 0.819718 -0.404994 0.404994 0.819731 -0.458509 0.343232 0.819733 -0.458518 0.343241 0.819724 -0.502699 0.274494 0.819724 -0.502717 0.274508 0.819708 -0.536668 0.200167 0.819708 -0.536672 0.200169 0.819705 -0.559696 0.121755 0.819705 -0.559678 0.121749 0.819718 -0.571308 0.0408618 0.819718 -0.571306 0.0408614 0.819719 -0.0144109 0.201492 0.979384 -0.0429394 0.19739 0.979384 -0.0429394 0.197389 0.979384 -0.0705936 0.189269 0.979384 -0.0705938 0.18927 0.979384 -0.0968116 0.177297 0.979384 -0.0968109 0.177295 0.979384 -0.121057 0.161713 0.979384 -0.121057 0.161712 0.979385 -0.142838 0.142838 0.979385 -0.14284 0.14284 0.979384 -0.161715 0.121058 0.979384 -0.16172 0.121063 0.979383 -0.177303 0.0968164 0.979383 -0.177289 0.096806 0.979386 -0.189261 0.0705907 0.979386 -0.189266 0.0705936 0.979385 -0.197387 0.0429383 0.979385 -0.197383 0.042937 0.979386 -0.201484 0.0144107 0.979386 -0.201482 0.0144102 0.979386 -0.201482 -0.0144105 0.979386 -0.571306 -0.0408617 0.819719 -0.847637 -0.0606279 0.527102 -0.89898 -0.317144 0.302082 -0.926406 -0.345531 0.149601 -0.960145 -0.235951 0.14983 -0.934164 -0.203212 0.29333 -0.97451 -0.166864 0.149959 -0.986221 -0.0705402 0.14964 -0.986228 -0.0705357 0.149594 -0.906538 -0.394588 0.149963 -0.8678 -0.473855 0.149612 -0.867804 -0.473855 0.149593 -0.791532 -0.592536 0.149594 -0.791529 -0.592536 0.149611 -0.723623 -0.673723 0.149889 -0.674017 -0.674013 0.302336 -0.203215 -0.934159 0.293345 -0.673725 -0.723626 0.149863 -0.592536 -0.791534 0.149582 -0.592538 -0.791535 0.149572 -0.473859 -0.867805 0.149575 -0.47385 -0.8678 0.149629 -0.394587 -0.906536 0.149977 -0.336893 -0.903247 0.265796 -0.328935 -0.932399 0.149783 -0.235956 -0.960142 0.149843 -0.166853 -0.974518 0.149918 -0.0705358 -0.986227 0.149601 -0.0705366 -0.986228 0.149594 -0.847647 -0.0606265 0.527085 -0.830392 -0.180638 0.527085 -0.830372 -0.180638 0.527117 -0.796213 -0.296972 0.527118 -0.796212 -0.296972 0.527118 -0.745846 -0.407261 0.527117 -0.745837 -0.407258 0.527131 -0.680286 -0.50926 0.527129 -0.680319 -0.509275 0.527072 -0.600914 -0.60091 0.527077 -0.600894 -0.600897 0.527115 -0.509266 -0.680297 0.527109 -0.509263 -0.680294 0.527116 -0.40726 -0.745849 0.527114 -0.407273 -0.745865 0.527081 -0.296979 -0.796232 0.527084 -0.296976 -0.796228 0.527093 -0.180641 -0.830388 0.527091 -0.180643 -0.830393 0.527082 -0.0606251 -0.847648 0.527084 -0.0606221 -0.847637 0.527102 -0.571309 -0.0408615 0.819717 -0.559679 -0.121752 0.819717 -0.559697 -0.121753 0.819704 -0.536672 -0.200168 0.819705 -0.536667 -0.200167 0.819708 -0.502718 -0.274505 0.819708 -0.502697 -0.274497 0.819724 -0.458519 -0.343239 0.819724 -0.458507 -0.343233 0.819733 -0.404993 -0.404996 0.819731 -0.405003 -0.405003 0.819723 -0.343243 -0.458518 0.819723 -0.343242 -0.458517 0.819724 -0.274494 -0.502699 0.819724 -0.274494 -0.502697 0.819725 -0.200158 -0.536647 0.819724 -0.200166 -0.536662 0.819712 -0.121753 -0.559683 0.819714 -0.121745 -0.559661 0.81973 -0.0408581 -0.571291 0.81973 -0.0408612 -0.571306 0.819719 -0.201484 -0.0144104 0.979386 -0.197382 -0.0429373 0.979386 -0.197387 -0.0429378 0.979385 -0.189267 -0.0705929 0.979385 -0.18926 -0.0705914 0.979386 -0.177288 -0.0968078 0.979386 -0.177305 -0.0968146 0.979383 -0.161721 -0.121062 0.979383 -0.161714 -0.121058 0.979384 -0.14284 -0.14284 0.979384 -0.142838 -0.142838 0.979385 -0.121056 -0.161712 0.979385 -0.121059 -0.161715 0.979384 -0.0968123 -0.177298 0.979384 -0.0968114 -0.177297 0.979384 -0.0705943 -0.189269 0.979384 -0.0705923 -0.189265 0.979385 -0.0429382 -0.197386 0.979385 -0.0429395 -0.19739 0.979384 -0.0144112 -0.201492 0.979384 -0.0144107 -0.201489 0.979385 -0.201503 0 0.979488 -0.201503 0 0.979488 -0.571784 0 0.820404 -0.571784 0 0.820404 -0.849199 0 0.528073 -0.849199 0 0.528073 -0.988691 0 0.149967 -0.988691 0 0.149967 -0.201503 0 0.979488 -0.201503 0 0.979488 -0.571784 0 0.820404 -0.571784 0 0.820404 -0.849199 0 0.528073 -0.849199 0 0.528073 -0.988691 0 0.149967 -0.988691 0 0.149967 0 0.98404 -0.177946 0 0.98404 -0.177946 0 0.932797 -0.360401 0 0.932797 -0.360401 0 0.879855 -0.475243 0 0.879855 -0.475243 0 0.774394 -0.632703 0 0.774394 -0.632703 0 0.591309 -0.806445 0 0.591309 -0.806445 0 0.42854 -0.903523 0 0.42854 -0.903523 0 0.311086 -0.950382 0 0.311086 -0.950382 0 0.126202 -0.992005 0 0.126202 -0.992005 -0.893672 0.411987 -0.177811 -0.807324 0.562649 -0.177914 -0.497616 0.849012 -0.177642 -0.340603 0.92324 -0.177813 -0.172992 0.968722 -0.177912 -0.126196 0.00993094 -0.991956 -0.00993165 0.126195 -0.991956 -0.00993209 0.126196 -0.991956 -0.0244763 0.310993 -0.950097 -0.0511279 0.367066 -0.928789 -0.116949 0.0484425 -0.991956 -0.116951 0.0484419 -0.991956 -0.343263 0.142182 -0.928415 -0.343262 0.142182 -0.928416 -0.547397 0.226737 -0.805572 -0.54739 0.226739 -0.805577 -0.716325 0.296715 -0.631537 -0.716334 0.296711 -0.631528 -0.839473 0.347716 -0.417587 -0.123089 0.0295511 -0.991956 -0.123089 0.029551 -0.991956 -0.361278 0.0867352 -0.928415 -0.361274 0.0867369 -0.928417 -0.576119 0.138318 -0.805577 -0.576123 0.138316 -0.805575 -0.75393 0.181004 -0.631528 -0.753932 0.181003 -0.631525 -0.0891464 0.904034 -0.418062 -0.0690802 0.877753 -0.474107 -0.0608329 0.77296 -0.631532 -0.060833 0.77296 -0.631531 -0.0464864 0.590668 -0.805574 -0.0464874 0.590669 -0.805573 -0.0337082 0.428296 -0.90301 -0.126195 0.00993169 -0.991956 -0.310991 0.0244752 -0.950098 -0.367064 0.0511268 -0.928789 -0.428302 0.0337046 -0.903007 -0.590669 0.0464817 -0.805574 -0.590666 0.0464835 -0.805576 -0.772966 0.0608299 -0.631525 -0.772956 0.0608375 -0.631536 -0.877762 0.0690865 -0.47409 -0.839468 0.347719 -0.417594 -0.883528 0.212116 -0.417595 -0.883528 0.212116 -0.417594 -0.904033 0.0891463 -0.418063 -0.930289 0.0732189 -0.359446 -0.0772149 0.981103 -0.177414 -0.0772143 0.981102 -0.177415 -0.0732156 0.930294 -0.359434 -0.248474 0.952209 -0.177646 -0.228575 0.952088 -0.203181 -0.212115 0.883528 -0.417594 -0.212116 0.883529 -0.417593 -0.181001 0.753927 -0.631533 -0.181002 0.753927 -0.631532 -0.138315 0.576124 -0.805574 -0.138316 0.576124 -0.805574 -0.0867355 0.361278 -0.928415 -0.0867329 0.361276 -0.928416 -0.0295502 0.123088 -0.991956 -0.029551 0.123089 -0.991956 -0.41199 0.893671 -0.177808 -0.37401 0.902943 -0.211683 -0.347717 0.839467 -0.417598 -0.347721 0.839468 -0.417593 -0.296715 0.716331 -0.63153 -0.296713 0.71633 -0.631533 -0.226737 0.547393 -0.805575 -0.226738 0.547394 -0.805574 -0.142183 0.34326 -0.928416 -0.142185 0.343262 -0.928415 -0.0484429 0.11695 -0.991956 -0.0484418 0.116949 -0.991956 -0.562669 0.807311 -0.177909 -0.511603 0.834854 -0.203179 -0.474762 0.774736 -0.417594 -0.474759 0.774736 -0.417599 -0.405119 0.661095 -0.631532 -0.405122 0.661095 -0.63153 -0.30958 0.505186 -0.805573 -0.309576 0.505184 -0.805575 -0.19413 0.316793 -0.928416 -0.19413 0.316793 -0.928416 -0.0661405 0.107932 -0.991956 -0.0661413 0.107932 -0.991956 -0.0822107 0.0962561 -0.991956 -0.0822103 0.0962561 -0.991956 -0.241297 0.282523 -0.928416 -0.241301 0.282524 -0.928415 -0.384799 0.450537 -0.805572 -0.384791 0.450535 -0.805577 -0.503547 0.589583 -0.631532 -0.503549 0.589583 -0.631531 -0.590108 0.690932 -0.417595 -0.59011 0.690932 -0.417592 -0.639145 0.748344 -0.177411 -0.639144 0.748345 -0.177414 -0.0962557 0.0822104 -0.991956 -0.0962566 0.0822104 -0.991956 -0.282526 0.241299 -0.928415 -0.282522 0.241299 -0.928416 -0.450532 0.384794 -0.805577 -0.45054 0.384794 -0.805573 -0.589583 0.503547 -0.631531 -0.58958 0.503548 -0.631534 -0.690932 0.59011 -0.417592 -0.69093 0.59011 -0.417595 -0.748343 0.639146 -0.177414 -0.748342 0.639147 -0.177416 -0.849012 0.497615 -0.177645 -0.834857 0.511598 -0.203176 -0.774741 0.474759 -0.417588 -0.774736 0.474761 -0.417595 -0.66109 0.405119 -0.631536 -0.661093 0.405119 -0.631534 -0.505187 0.309579 -0.805573 -0.505188 0.309579 -0.805572 -0.316794 0.194131 -0.928415 -0.316791 0.194131 -0.928416 -0.107931 0.0661407 -0.991956 -0.107932 0.0661406 -0.991956 -0.909715 0.335613 -0.244503 -0.909224 0.376613 -0.177412 -0.952207 0.248483 -0.177644 -0.952086 0.228575 -0.20319 -0.968723 0.172979 -0.177915 -0.981102 0.0772182 -0.177417 -0.981103 0.0772148 -0.177411 0.41199 0.893671 -0.177808 0.562654 0.807321 -0.177917 0.849012 0.497615 -0.177645 0.968723 0.172979 -0.177915 0.0099317 0.126196 -0.991956 0.126197 0.00993255 -0.991955 0.126196 0.00993176 -0.991956 0.310991 0.0244752 -0.950098 0.367064 0.0511268 -0.928789 0.0484422 0.11695 -0.991956 0.0484425 0.116949 -0.991956 0.142185 0.34326 -0.928416 0.142184 0.343262 -0.928415 0.226738 0.547393 -0.805575 0.226738 0.547394 -0.805574 0.296714 0.716332 -0.63153 0.296715 0.716329 -0.631533 0.34772 0.839466 -0.417598 0.0295508 0.123088 -0.991956 0.0295504 0.123089 -0.991956 0.0867336 0.361279 -0.928415 0.0867349 0.361276 -0.928416 0.138316 0.576124 -0.805574 0.138315 0.576124 -0.805574 0.181002 0.753926 -0.631533 0.181001 0.753927 -0.631532 0.904033 0.0891463 -0.418063 0.877762 0.0690865 -0.47409 0.772965 0.0608382 -0.631525 0.772957 0.0608292 -0.631536 0.590668 0.0464837 -0.805574 0.590673 0.0464879 -0.805571 0.42829 0.0337079 -0.903012 0.11695 0.0484433 -0.991956 0.116949 0.0484412 -0.991956 0.343258 0.14218 -0.928417 0.343261 0.142186 -0.928415 0.547395 0.226742 -0.805572 0.547391 0.226734 -0.805577 0.716334 0.296712 -0.631528 0.716334 0.296711 -0.631529 0.83947 0.347715 -0.417595 0.839471 0.34772 -0.417587 0.00993206 0.126195 -0.991956 0.0244763 0.310993 -0.950097 0.0511279 0.367066 -0.928789 0.0337082 0.428296 -0.90301 0.0464873 0.590668 -0.805574 0.0464865 0.590669 -0.805574 0.060833 0.77296 -0.631532 0.0608329 0.77296 -0.631531 0.0690802 0.877753 -0.474107 0.347718 0.839469 -0.417593 0.212116 0.883528 -0.417594 0.212115 0.883529 -0.417593 0.0891464 0.904034 -0.418062 0.0732156 0.930294 -0.359434 0.981102 0.0772147 -0.177417 0.981103 0.0772182 -0.177411 0.930289 0.0732189 -0.359446 0.952207 0.248483 -0.177644 0.952086 0.228575 -0.20319 0.883528 0.212116 -0.417595 0.883528 0.212116 -0.417594 0.75393 0.181003 -0.631528 0.753932 0.181005 -0.631525 0.576127 0.138317 -0.805572 0.576124 0.138314 -0.805575 0.361273 0.0867332 -0.928417 0.361274 0.0867343 -0.928417 0.123089 0.029551 -0.991956 0.123089 0.0295511 -0.991956 0.909224 0.376613 -0.177413 0.880569 0.405962 -0.244527 0.923246 0.340589 -0.17781 0.807324 0.562649 -0.177914 0.834857 0.511598 -0.203176 0.774738 0.474757 -0.417595 0.774739 0.474763 -0.417588 0.661097 0.405123 -0.631527 0.661096 0.405121 -0.631529 0.505182 0.309576 -0.805577 0.505182 0.309575 -0.805577 0.316792 0.19413 -0.928416 0.316793 0.194133 -0.928415 0.107932 0.0661411 -0.991956 0.107931 0.0661401 -0.991956 0.096257 0.0822099 -0.991956 0.0962572 0.0822109 -0.991956 0.282524 0.241296 -0.928416 0.282524 0.241296 -0.928416 0.450535 0.384791 -0.805577 0.450537 0.384797 -0.805573 0.589583 0.503554 -0.631527 0.589582 0.503549 -0.631531 0.690931 0.590109 -0.417595 0.690931 0.590111 -0.417592 0.748342 0.639146 -0.177416 0.748342 0.639147 -0.177414 0.0822105 0.0962575 -0.991956 0.0822105 0.0962563 -0.991956 0.241297 0.282523 -0.928416 0.241297 0.282523 -0.928416 0.384795 0.450538 -0.805574 0.384795 0.450534 -0.805576 0.503551 0.58958 -0.631531 0.503551 0.589586 -0.631526 0.590109 0.690933 -0.417592 0.59011 0.690931 -0.417595 0.639145 0.748344 -0.177414 0.639147 0.74834 -0.17742 0.497616 0.849012 -0.177642 0.511603 0.834854 -0.203179 0.474761 0.774734 -0.417599 0.47476 0.774738 -0.417594 0.40512 0.661096 -0.63153 0.40512 0.661099 -0.631527 0.309576 0.505185 -0.805575 0.309576 0.505184 -0.805575 0.19413 0.316793 -0.928416 0.19413 0.316793 -0.928416 0.0661408 0.107932 -0.991956 0.0661409 0.107932 -0.991956 0.335613 0.909715 -0.244503 0.376611 0.909224 -0.177415 0.248474 0.952209 -0.177646 0.228575 0.952088 -0.203181 0.172992 0.968722 -0.177912 0.0772143 0.981103 -0.177414 0.0772149 0.981102 -0.177415 -0.126202 0 -0.992005 -0.188642 -0.0159552 -0.981916 -0.311084 0 -0.950383 -0.428545 0 -0.90352 -0.539068 -0.0159551 -0.842111 -0.591305 0 -0.806448 -0.774391 0 -0.632708 -0.812745 -0.0159577 -0.582401 -0.879864 0 -0.475226 -0.932793 0 -0.360414 -0.970697 -0.0159571 -0.239777 -0.984041 0 -0.177942 0.126203 0 -0.992004 0.126203 0 -0.992004 0.311084 0 -0.950383 0.311084 0 -0.950383 0.428534 0 -0.903526 0.428534 0 -0.903526 0.591312 0 -0.806443 0.591312 0 -0.806443 0.774391 0 -0.632708 0.774391 0 -0.632708 0.879864 0 -0.475226 0.879864 0 -0.475226 0.932793 0 -0.360414 0.932793 0 -0.360414 0.984041 0 -0.177942 0.984041 0 -0.177942 -0.126202 0 -0.992005 -0.188642 0.0159552 -0.981916 -0.311084 0 -0.950382 -0.428545 0 -0.90352 -0.539068 0.0159551 -0.842111 -0.591305 0 -0.806448 -0.774391 0 -0.632708 -0.812745 0.0159577 -0.582401 -0.984041 0 -0.177942 -0.970697 0.0159571 -0.239777 -0.932793 0 -0.360414 -0.879864 0 -0.475226 0.952207 -0.248483 -0.177644 0.893666 -0.412 -0.177811 0.807324 -0.562649 -0.177914 0.497616 -0.849012 -0.177642 0.340603 -0.92324 -0.177813 0.172976 -0.968725 -0.177908 0.126196 -0.00993248 -0.991956 0.00993165 -0.126195 -0.991956 0.00993209 -0.126196 -0.991956 0.0244763 -0.310993 -0.950097 0.0511279 -0.367066 -0.928789 0.126197 -0.00993183 -0.991955 0.310991 -0.0244752 -0.950098 0.367064 -0.0511268 -0.928789 0.42829 -0.0337079 -0.903012 0.590668 -0.0464875 -0.805575 0.590673 -0.0464841 -0.805571 0.772966 -0.0608299 -0.631525 0.0891464 -0.904034 -0.418062 0.0690823 -0.877756 -0.474102 0.0608346 -0.772962 -0.631529 0.060833 -0.77296 -0.631531 0.0464863 -0.590667 -0.805576 0.0464873 -0.590668 -0.805575 0.0337082 -0.428296 -0.90301 0.0772149 -0.981103 -0.17741 0.0772144 -0.981103 -0.177411 0.0732156 -0.930294 -0.359434 0.248477 -0.952209 -0.177646 0.228575 -0.952087 -0.203185 0.212115 -0.883528 -0.417594 0.212116 -0.883529 -0.417593 0.181001 -0.753927 -0.631533 0.181004 -0.753928 -0.631529 0.138317 -0.576125 -0.805573 0.138314 -0.576123 -0.805575 0.0867343 -0.361277 -0.928416 0.0867329 -0.361276 -0.928416 0.0295502 -0.123088 -0.991956 0.029551 -0.123089 -0.991956 0.41199 -0.893671 -0.177808 0.37401 -0.902943 -0.211683 0.347718 -0.839468 -0.417595 0.347719 -0.839468 -0.417593 0.296713 -0.71633 -0.631532 0.296713 -0.71633 -0.631533 0.226737 -0.547393 -0.805575 0.22674 -0.547395 -0.805573 0.142184 -0.34326 -0.928416 0.142185 -0.34326 -0.928416 0.0484429 -0.11695 -0.991956 0.0484418 -0.116949 -0.991956 0.562654 -0.807321 -0.177914 0.511601 -0.834855 -0.203177 0.47476 -0.774736 -0.417597 0.474761 -0.774736 -0.417596 0.405122 -0.661097 -0.631527 0.405118 -0.661096 -0.631531 0.309576 -0.505184 -0.805575 0.309576 -0.505184 -0.805575 0.19413 -0.316793 -0.928416 0.19413 -0.316793 -0.928416 0.0661405 -0.107932 -0.991956 0.0661413 -0.107932 -0.991956 0.0822098 -0.0962567 -0.991956 0.082211 -0.096257 -0.991956 0.241297 -0.282523 -0.928416 0.241297 -0.282523 -0.928416 0.384793 -0.450536 -0.805576 0.384796 -0.450536 -0.805574 0.503554 -0.589583 -0.631526 0.503549 -0.589583 -0.631531 0.590108 -0.690931 -0.417597 0.590112 -0.690931 -0.417592 0.639146 -0.748342 -0.177417 0.639148 -0.748341 -0.177414 0.0962576 -0.0822104 -0.991956 0.0962566 -0.0822104 -0.991956 0.282524 -0.241296 -0.928416 0.282524 -0.241296 -0.928416 0.450539 -0.384794 -0.805573 0.450533 -0.384794 -0.805577 0.58958 -0.503551 -0.631531 0.589585 -0.503551 -0.631527 0.690932 -0.59011 -0.417592 0.69093 -0.59011 -0.417595 0.748343 -0.639146 -0.177414 0.748342 -0.639147 -0.177416 0.849012 -0.497615 -0.177645 0.834857 -0.511598 -0.203176 0.774741 -0.474759 -0.417588 0.774736 -0.474761 -0.417595 0.661096 -0.405122 -0.631529 0.661098 -0.405122 -0.631527 0.505181 -0.309576 -0.805577 0.505182 -0.309576 -0.805577 0.316794 -0.194131 -0.928415 0.316791 -0.194131 -0.928416 0.107931 -0.0661407 -0.991956 0.107932 -0.0661406 -0.991956 0.923246 -0.340589 -0.17781 0.902941 -0.37401 -0.211695 0.839468 -0.347719 -0.417594 0.839473 -0.347716 -0.417587 0.716334 -0.296711 -0.631528 0.716334 -0.296712 -0.631529 0.547397 -0.226737 -0.805572 0.547389 -0.226739 -0.805577 0.343257 -0.142184 -0.928417 0.343263 -0.142182 -0.928415 0.116951 -0.0484419 -0.991956 0.116949 -0.0484425 -0.991956 0.968723 -0.172979 -0.177915 0.952086 -0.228575 -0.20319 0.883528 -0.212116 -0.417594 0.883528 -0.212116 -0.417595 0.753932 -0.181003 -0.631525 0.75393 -0.181004 -0.631528 0.576123 -0.138316 -0.805575 0.576127 -0.138315 -0.805572 0.361274 -0.0867334 -0.928417 0.361273 -0.086734 -0.928418 0.123089 -0.029551 -0.991956 0.123089 -0.0295511 -0.991956 0.772956 -0.0608375 -0.631536 0.877762 -0.0690865 -0.47409 0.904034 -0.0891463 -0.418063 0.930289 -0.0732189 -0.359446 0.981102 -0.0772182 -0.177417 0.981103 -0.0772148 -0.177411 -0.41199 -0.893671 -0.177808 -0.56267 -0.807312 -0.177906 -0.849012 -0.497615 -0.177645 -0.968723 -0.172979 -0.177915 -0.0099317 -0.126196 -0.991956 -0.126195 -0.00993084 -0.991956 -0.126196 -0.00993176 -0.991956 -0.310991 -0.0244752 -0.950098 -0.367064 -0.0511268 -0.928789 -0.0484422 -0.11695 -0.991956 -0.0484425 -0.116949 -0.991956 -0.142185 -0.34326 -0.928416 -0.142184 -0.343261 -0.928416 -0.226739 -0.547393 -0.805575 -0.226738 -0.547396 -0.805573 -0.296713 -0.71633 -0.631532 -0.296713 -0.716329 -0.631533 -0.347719 -0.839468 -0.417595 -0.0295508 -0.123088 -0.991956 -0.0295504 -0.123089 -0.991956 -0.0867333 -0.361278 -0.928416 -0.086734 -0.361276 -0.928416 -0.138315 -0.576126 -0.805573 -0.138316 -0.576123 -0.805575 -0.181004 -0.753926 -0.631533 -0.181002 -0.753929 -0.63153 -0.904033 -0.0891463 -0.418063 -0.877762 -0.0690865 -0.47409 -0.772965 -0.0608382 -0.631525 -0.772957 -0.0608292 -0.631536 -0.590668 -0.0464837 -0.805574 -0.590666 -0.0464815 -0.805576 -0.428302 -0.0337046 -0.903007 -0.11695 -0.0484433 -0.991956 -0.116949 -0.0484412 -0.991956 -0.343262 -0.142182 -0.928416 -0.343263 -0.142183 -0.928415 -0.547391 -0.226735 -0.805577 -0.547395 -0.226741 -0.805573 -0.716332 -0.296718 -0.631528 -0.716328 -0.296708 -0.631537 -0.83947 -0.347715 -0.417595 -0.839471 -0.34772 -0.417587 -0.00993206 -0.126195 -0.991956 -0.0244763 -0.310993 -0.950097 -0.0511279 -0.367066 -0.928789 -0.0337082 -0.428296 -0.90301 -0.0464872 -0.590666 -0.805576 -0.0464863 -0.590668 -0.805575 -0.0608331 -0.772962 -0.631529 -0.0608345 -0.77296 -0.631531 -0.0690823 -0.877756 -0.474102 -0.347718 -0.839469 -0.417593 -0.212116 -0.883528 -0.417594 -0.212115 -0.883529 -0.417593 -0.0891464 -0.904034 -0.418062 -0.0732156 -0.930294 -0.359434 -0.981102 -0.0772147 -0.177417 -0.981103 -0.0772182 -0.177411 -0.930289 -0.0732189 -0.359446 -0.952207 -0.248483 -0.177644 -0.952086 -0.228575 -0.20319 -0.883528 -0.212116 -0.417595 -0.883528 -0.212116 -0.417594 -0.75393 -0.181003 -0.631528 -0.753932 -0.181005 -0.631525 -0.57612 -0.138316 -0.805577 -0.576123 -0.138319 -0.805575 -0.361277 -0.0867377 -0.928416 -0.361274 -0.0867343 -0.928417 -0.123089 -0.029551 -0.991956 -0.123089 -0.0295511 -0.991956 -0.909224 -0.376613 -0.177413 -0.88058 -0.405951 -0.244503 -0.923241 -0.340603 -0.17781 -0.807324 -0.562649 -0.177914 -0.834857 -0.511598 -0.203176 -0.774738 -0.474757 -0.417595 -0.774739 -0.474763 -0.417588 -0.661092 -0.40512 -0.631534 -0.661091 -0.405118 -0.631536 -0.505187 -0.309579 -0.805572 -0.505187 -0.309579 -0.805573 -0.316792 -0.19413 -0.928416 -0.316793 -0.194133 -0.928415 -0.107932 -0.0661411 -0.991956 -0.107931 -0.0661401 -0.991956 -0.0962563 -0.0822109 -0.991956 -0.0962561 -0.08221 -0.991956 -0.282524 -0.241296 -0.928416 -0.282525 -0.241301 -0.928415 -0.450537 -0.384798 -0.805573 -0.450535 -0.38479 -0.805577 -0.589582 -0.503546 -0.631534 -0.589582 -0.503549 -0.631531 -0.690931 -0.590109 -0.417595 -0.690931 -0.590111 -0.417592 -0.748342 -0.639146 -0.177416 -0.748342 -0.639147 -0.177414 -0.0822104 -0.0962559 -0.991956 -0.0822105 -0.0962563 -0.991956 -0.241299 -0.282526 -0.928415 -0.241299 -0.282522 -0.928416 -0.384794 -0.450532 -0.805577 -0.384795 -0.45054 -0.805572 -0.503548 -0.589583 -0.631531 -0.503548 -0.589582 -0.631532 -0.590109 -0.690933 -0.417592 -0.59011 -0.690929 -0.417597 -0.639146 -0.748343 -0.177414 -0.639144 -0.748345 -0.177408 -0.497616 -0.849012 -0.177642 -0.511601 -0.834855 -0.203177 -0.47476 -0.774736 -0.417596 -0.474761 -0.774736 -0.417597 -0.405121 -0.661094 -0.631531 -0.405121 -0.661094 -0.631532 -0.309578 -0.505183 -0.805575 -0.309578 -0.505187 -0.805573 -0.19413 -0.316793 -0.928416 -0.19413 -0.316793 -0.928416 -0.0661408 -0.107932 -0.991956 -0.0661409 -0.107932 -0.991956 -0.335613 -0.909715 -0.244503 -0.376611 -0.909224 -0.177415 -0.248477 -0.952209 -0.177646 -0.228575 -0.952087 -0.203185 -0.172976 -0.968725 -0.177908 -0.0772144 -0.981103 -0.17741 -0.0772149 -0.981103 -0.177411 0 -0.984041 -0.177942 0 -0.984041 -0.177942 0 -0.932797 -0.360401 0 -0.932797 -0.360401 0 -0.879858 -0.475237 0 -0.879858 -0.475237 0 -0.774394 -0.632703 0 -0.774394 -0.632703 0 -0.591307 -0.806447 0 -0.591307 -0.806447 0 -0.42854 -0.903523 0 -0.42854 -0.903523 0 -0.311086 -0.950382 0 -0.311086 -0.950382 0 -0.126202 -0.992005 0 -0.126202 -0.992005 -0.130525 0.991441 -0.00297075 -0.382682 0.923875 -0.00318898 -0.333141 0.942877 0.00022776 -0.168998 0.985616 -0.000247724 -0.699577 0.714557 0 -0.62822 0.778035 -0.000802315 -0.60876 0.79335 -0.00267348 -0.530317 0.8478 0 -0.456513 0.889717 0 -0.757639 0.652674 0 -0.793348 0.608759 -0.003328 -0.836353 0.548191 0 -0.879829 0.47529 0 -0.923878 0.382681 -0.0022967 -0.927887 0.372858 -0.0014358 -0.991438 0.130531 -0.00338746 -0.981127 0.193364 0 -0.961201 0.27585 0 -0.972036 -0.234831 0 -0.991898 -0.127023 -0.0021479 -0.991442 -0.130532 -0.00184106 -0.999775 -0.0212285 0 -0.997973 0.0636401 0 -0.948627 -0.316398 0 -0.923875 -0.38268 -0.00336793 -0.899204 -0.43753 0 -0.858859 -0.512213 0 -0.793352 -0.608762 -0.00130616 -0.803996 -0.594628 -0.00293893 -0.608759 -0.793349 -0.0032684 -0.668608 -0.743615 0 -0.729253 -0.684244 0 -0.296203 -0.955125 0 -0.411898 -0.911222 -0.00380796 -0.382683 -0.923879 -0.000692573 -0.493876 -0.869532 0 -0.565822 -0.824528 0 -0.214134 -0.976804 0 -0.130525 -0.99144 -0.00308971 -0.0848059 -0.996397 0 0.0848059 -0.996397 0 0.130525 -0.99144 -0.00308971 0.214134 -0.976804 0 0.382683 -0.923879 -0.000692574 0.411898 -0.911222 -0.00380796 0.296203 -0.955125 0 0.608759 -0.793349 -0.0032684 0.565822 -0.824528 0 0.493876 -0.869532 0 0.858859 -0.512213 0 0.803999 -0.59463 -0.0011089 0.79335 -0.60876 -0.00249517 0.729253 -0.684244 0 0.668608 -0.743615 0 0.899209 -0.437519 0 0.923875 -0.38268 -0.00336728 0.948622 -0.316411 0 0.991443 -0.130525 -0.00184094 0.991899 -0.127012 -0.0021481 0.972036 -0.234831 0 0.991439 0.130525 -0.00338782 0.997974 0.0636262 0 0.999775 -0.0212285 0 0.879829 0.47529 0 0.927885 0.372857 -0.00253326 0.923879 0.382682 -0.00158365 0.961201 0.27585 0 0.981127 0.193364 0 0.836353 0.548191 0 0.793348 0.608759 -0.003328 0.757639 0.652674 0 0.60876 0.79335 -0.00267348 0.62822 0.778035 -0.000802315 0.699577 0.714557 0 0.382682 0.923875 -0.00318898 0.456513 0.889717 0 0.530317 0.8478 0 -0.0424407 0.999099 0 0.0424407 0.999099 0 0.130525 0.991441 -0.00297075 0.168998 0.985616 -0.000247724 0.333141 0.942877 0.00022776 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.212481 -0.969266 -0.124 0.290519 -0.9368 -0.194949 0.404042 -0.893842 -0.194413 0.404042 -0.893842 -0.194413 0.484387 -0.852826 -0.195084 0.550521 -0.814522 -0.182978 0.555014 -0.808778 -0.19452 0.678737 -0.708181 -0.194412 0.662304 -0.736604 -0.136998 0.715255 -0.671109 -0.194992 0.788659 -0.583285 -0.19441 0.788655 -0.583288 -0.194419 0.842358 -0.502372 -0.195076 0.879376 -0.443368 -0.173562 0.882015 -0.429153 -0.194622 0.937922 -0.287236 -0.194415 0.937903 -0.312836 -0.149907 0.953371 -0.230322 -0.195027 0.972976 -0.124589 -0.194408 0.972972 -0.124598 -0.194425 0.980571 -0.0208207 -0.195059 0.985201 0.0418462 -0.166214 0.978873 0.0624085 -0.194712 0.958902 0.206662 -0.194415 0.968045 0.190786 -0.162754 0.942736 0.270551 -0.195065 0.910183 0.365743 -0.194418 0.910183 0.365743 -0.194419 0.862936 0.466164 -0.195019 0.84043 0.517473 -0.160931 0.820333 0.53769 -0.194788 0.736348 0.648071 -0.194413 0.745882 0.642546 -0.175485 0.686137 0.700829 -0.195077 0.616234 0.763191 -0.194411 0.616235 0.763189 -0.194416 0.520139 0.831529 -0.194975 0.481587 0.862083 -0.157759 0.165774 0.96681 -0.194413 0.326784 0.924887 -0.194412 0.326785 0.924887 -0.194414 0.447762 0.872662 -0.194859 0.0421468 0.99218 -0.117481 0 0.980919 -0.194417 0.165777 0.966809 -0.194419 -0.326785 0.924887 -0.194412 -0.165777 0.96681 -0.194413 -0.165774 0.966809 -0.194419 -0.0416266 0.979935 -0.194925 -0.452608 0.882107 -0.130511 -0.478388 0.856358 -0.194413 -0.326784 0.924887 -0.194414 -0.520139 0.831529 -0.194975 -0.616233 0.76319 -0.194416 -0.616236 0.763189 -0.194411 -0.686137 0.700829 -0.195076 -0.738681 0.650124 -0.178016 -0.743159 0.6402 -0.194572 -0.835282 0.514303 -0.194413 -0.827701 0.54252 -0.143466 -0.862936 0.466164 -0.195019 -0.910183 0.365743 -0.194419 -0.910183 0.365743 -0.194418 -0.942736 0.270551 -0.195065 -0.963387 0.207629 -0.169633 -0.962357 0.189665 -0.194668 -0.980036 0.0416268 -0.194416 -0.985704 0.0628577 -0.156325 -0.980574 -0.0208208 -0.19504 -0.972975 -0.124599 -0.194407 -0.972975 -0.124598 -0.194408 -0.953371 -0.230322 -0.195027 -0.943331 -0.288892 -0.163303 -0.930466 -0.310341 -0.194735 -0.875893 -0.441612 -0.194399 -0.88625 -0.431227 -0.169127 -0.842358 -0.502372 -0.195076 -0.788658 -0.583284 -0.194419 -0.788656 -0.583289 -0.19441 -0.715255 -0.671109 -0.194992 -0.683128 -0.712762 -0.159081 -0.655796 -0.729366 -0.194824 -0.549291 -0.812702 -0.194412 -0.556391 -0.810784 -0.181819 -0.484387 -0.852826 -0.195084 -0.404042 -0.893842 -0.194413 -0.404042 -0.893842 -0.194413 -0.290519 -0.9368 -0.194949 -0.248854 -0.955738 -0.156964 0.247169 -0.949268 -0.194417 0.0831879 -0.977385 -0.194416 0.0831877 -0.977385 -0.194416 -0.0831878 -0.977385 -0.194416 -0.0831877 -0.977385 -0.194416 -0.210028 -0.958073 -0.194895 -0.0705921 -0.829396 -0.554183 -0.209744 -0.805536 -0.554183 -0.209745 -0.805535 -0.554184 -0.342864 -0.758501 -0.554185 -0.342864 -0.758501 -0.554185 -0.46612 -0.689644 -0.554186 -0.46612 -0.689647 -0.554184 -0.575966 -0.600952 -0.554184 -0.575966 -0.600951 -0.554185 -0.669242 -0.494967 -0.554186 -0.669243 -0.494971 -0.554182 -0.743267 -0.374748 -0.554182 -0.743266 -0.374743 -0.554187 -0.795906 -0.243743 -0.554187 -0.795906 -0.243744 -0.554187 -0.82565 -0.105733 -0.554187 -0.825648 -0.105732 -0.554189 -0.831641 0.0353285 -0.554189 -0.831646 0.035324 -0.554182 -0.813711 0.175374 -0.554182 -0.813715 0.175372 -0.554177 -0.772374 0.310365 -0.554177 -0.772372 0.310366 -0.554178 -0.708811 0.436431 -0.554179 -0.70881 0.436431 -0.554181 -0.624857 0.549943 -0.55418 -0.624854 0.549943 -0.554184 -0.522927 0.647633 -0.554183 -0.52293 0.647633 -0.55418 -0.405956 0.726694 -0.554181 -0.405954 0.726693 -0.554182 -0.277304 0.784846 -0.554183 -0.277304 0.784846 -0.554183 -0.140676 0.820421 -0.554183 -0.140676 0.820422 -0.554183 0 0.832394 -0.554184 0 0.832394 -0.554184 0.140676 0.820422 -0.554183 0.140676 0.820421 -0.554183 0.277304 0.784846 -0.554183 0.277304 0.784846 -0.554183 0.405955 0.726693 -0.554183 0.405955 0.726694 -0.554181 0.522928 0.647635 -0.55418 0.522929 0.647631 -0.554184 0.624855 0.549942 -0.554184 0.624856 0.549945 -0.55418 0.708811 0.43643 -0.554181 0.708811 0.436431 -0.554179 0.772373 0.310365 -0.554178 0.772373 0.310366 -0.554177 0.813714 0.175375 -0.554177 0.813712 0.175371 -0.554182 0.831645 0.0353287 -0.554182 0.831641 0.0353237 -0.554189 0.825648 -0.105733 -0.554189 0.82565 -0.105732 -0.554187 0.795906 -0.243743 -0.554187 0.795906 -0.243744 -0.554187 0.743264 -0.374746 -0.554187 0.743269 -0.374745 -0.554182 0.669244 -0.494969 -0.554182 0.669241 -0.494969 -0.554186 0.575965 -0.600952 -0.554185 0.575966 -0.600952 -0.554184 0.466121 -0.689646 -0.554184 0.466119 -0.689645 -0.554186 0.342864 -0.758501 -0.554185 0.342864 -0.758501 -0.554185 0.209744 -0.805536 -0.554184 0.209745 -0.805536 -0.554183 0.0705921 -0.829396 -0.554183 0.0705921 -0.829396 -0.554183 -0.0705921 -0.829396 -0.554183 -0.0472336 -0.554954 -0.830539 -0.140341 -0.538989 -0.830539 -0.140341 -0.538989 -0.830539 -0.229412 -0.507519 -0.830539 -0.229412 -0.507517 -0.83054 -0.311883 -0.461446 -0.83054 -0.311883 -0.461444 -0.830541 -0.385381 -0.402099 -0.830541 -0.385381 -0.4021 -0.83054 -0.447793 -0.331186 -0.83054 -0.447792 -0.331184 -0.830542 -0.49732 -0.250744 -0.830542 -0.497319 -0.250743 -0.830543 -0.532543 -0.163086 -0.830543 -0.532547 -0.163091 -0.830539 -0.552449 -0.0707464 -0.830539 -0.55245 -0.070747 -0.830538 -0.556459 0.0236414 -0.830538 -0.556464 0.0236388 -0.830535 -0.544465 0.11734 -0.830535 -0.544456 0.117343 -0.830541 -0.516794 0.207667 -0.830541 -0.516797 0.207666 -0.830539 -0.474269 0.292016 -0.830539 -0.474266 0.292016 -0.830541 -0.418091 0.36797 -0.830541 -0.418096 0.36797 -0.830538 -0.349896 0.433334 -0.830539 -0.349891 0.433332 -0.830542 -0.271625 0.486232 -0.830541 -0.271625 0.486232 -0.830541 -0.185544 0.525144 -0.83054 -0.185546 0.525146 -0.830539 -0.0941278 0.548949 -0.830539 -0.094127 0.548948 -0.83054 0 0.55696 -0.830539 0 0.55696 -0.830539 0.0941276 0.548948 -0.83054 0.0941271 0.548949 -0.830539 0.185545 0.525146 -0.830539 0.185545 0.525143 -0.83054 0.271627 0.486231 -0.830541 0.271627 0.486235 -0.830538 0.349894 0.433336 -0.830538 0.349894 0.433336 -0.830539 0.418094 0.367972 -0.830538 0.418092 0.367968 -0.830541 0.474267 0.292014 -0.830541 0.474269 0.292018 -0.830539 0.516797 0.207668 -0.830539 0.516795 0.207665 -0.830541 0.544457 0.117338 -0.830541 0.544464 0.117345 -0.830535 0.556464 0.0236416 -0.830535 0.556459 0.0236386 -0.830539 0.55245 -0.0707465 -0.830538 0.552449 -0.0707469 -0.830539 0.532547 -0.163092 -0.830539 0.53255 -0.163092 -0.830537 0.497328 -0.250743 -0.830538 0.49732 -0.250744 -0.830542 0.447791 -0.331185 -0.830542 0.447794 -0.331185 -0.83054 0.385382 -0.402099 -0.83054 0.38538 -0.402099 -0.830541 0.311882 -0.461445 -0.830541 0.311884 -0.461445 -0.83054 0.229412 -0.507518 -0.83054 0.229413 -0.507518 -0.830539 0.140342 -0.538989 -0.830539 0.140341 -0.538989 -0.830539 0.0472344 -0.554954 -0.830539 0.0472335 -0.554952 -0.83054 -0.0472343 -0.554952 -0.83054 -0.0166023 -0.195059 -0.980651 -0.0493282 -0.189448 -0.980651 -0.0493282 -0.189448 -0.980651 -0.0806358 -0.178386 -0.980651 -0.0806358 -0.178387 -0.980651 -0.109624 -0.162194 -0.980651 -0.109624 -0.162194 -0.980651 -0.135458 -0.141334 -0.980651 -0.135458 -0.141335 -0.980651 -0.157395 -0.11641 -0.980651 -0.157394 -0.116408 -0.980651 -0.174803 -0.088134 -0.980651 -0.174803 -0.0881343 -0.980651 -0.187184 -0.0573235 -0.980651 -0.187184 -0.0573232 -0.980651 -0.194179 -0.0248655 -0.980651 -0.194181 -0.0248668 -0.98065 -0.195591 0.00830844 -0.98065 -0.195588 0.00830963 -0.980651 -0.191371 0.0412424 -0.980651 -0.191369 0.0412427 -0.980651 -0.181646 0.0729917 -0.980651 -0.181645 0.0729918 -0.980651 -0.166698 0.102639 -0.980651 -0.166699 0.10264 -0.980651 -0.146954 0.129337 -0.980651 -0.146955 0.129337 -0.980651 -0.122983 0.152312 -0.980651 -0.122985 0.152313 -0.980651 -0.0954742 0.170907 -0.980651 -0.0954739 0.170906 -0.980651 -0.0652175 0.184583 -0.980651 -0.0652164 0.184582 -0.980651 -0.0330845 0.192949 -0.980651 -0.0330848 0.192949 -0.980651 0 0.195765 -0.980651 0 0.195765 -0.980651 0.0330846 0.192949 -0.980651 0.0330847 0.192949 -0.980651 0.0652171 0.184582 -0.980651 0.0652169 0.184583 -0.980651 0.095474 0.170906 -0.980651 0.0954739 0.170905 -0.980651 0.122983 0.152312 -0.980651 0.122983 0.152312 -0.980651 0.146955 0.129337 -0.980651 0.146956 0.129339 -0.980651 0.166701 0.102643 -0.980651 0.166698 0.102639 -0.980651 0.181646 0.07299 -0.980651 0.181649 0.0729934 -0.980651 0.191372 0.0412444 -0.980651 0.191371 0.041243 -0.980651 0.195588 0.00830832 -0.980651 0.195591 0.00830975 -0.98065 0.194181 -0.0248658 -0.98065 0.194179 -0.0248665 -0.980651 0.187184 -0.0573234 -0.980651 0.18718 -0.0573239 -0.980652 0.174801 -0.0881327 -0.980652 0.174804 -0.0881328 -0.980651 0.157394 -0.116409 -0.980651 0.157396 -0.116409 -0.980651 0.135459 -0.141334 -0.980651 0.135458 -0.141334 -0.980651 0.109624 -0.162194 -0.980651 0.109624 -0.162194 -0.980651 0.0806362 -0.178387 -0.980651 0.0806354 -0.178386 -0.980651 0.0493282 -0.189448 -0.980651 0.0493282 -0.189448 -0.980651 0.0166018 -0.195059 -0.980651 0.0166024 -0.19506 -0.980651 -0.0166019 -0.19506 -0.980651 0.258818 0.965926 0 0.258818 0.965926 0 0.422622 0.906306 0 0.422622 0.906306 0 0.573573 0.819155 0 0.573573 0.819155 0 0.707109 0.707105 0 0.707109 0.707105 0 0.819152 0.573577 0 0.819152 0.573577 0 0.906312 0.42261 0 0.906312 0.42261 0 0.965922 0.258833 0 0.965922 0.258833 0 0.996196 0.0871446 0 0.996196 0.0871446 0 0.996196 -0.0871442 0 0.996196 -0.0871442 0 0.965922 -0.258833 0 0.965922 -0.258833 0 0.906312 -0.42261 0 0.906312 -0.42261 0 0.819152 -0.573577 0 0.819152 -0.573577 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.573573 -0.819155 0 0.573573 -0.819155 0 0.422622 -0.906306 0 0.422622 -0.906306 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.0871566 -0.996195 0 0.0871566 -0.996195 0 -0.0871566 -0.996195 0 -0.0871566 -0.996195 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.422622 -0.906306 0 -0.422622 -0.906306 0 -0.573573 -0.819155 0 -0.573573 -0.819155 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.819152 -0.573577 0 -0.819152 -0.573577 0 -0.906305 -0.422624 0 -0.906305 -0.422624 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.996196 -0.0871442 0 -0.996196 -0.0871442 0 -0.996196 0.0871446 0 -0.996196 0.0871446 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.906305 0.422624 0 -0.906305 0.422624 0 -0.819152 0.573577 0 -0.819152 0.573577 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.573573 0.819155 0 -0.573573 0.819155 0 -0.422622 0.906306 0 -0.422622 0.906306 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.0871566 0.996195 0 -0.0871566 0.996195 0 0.0871566 0.996195 0 0.0871566 0.996195 0 -0.222426 0.974516 -0.0290704 -0.623227 0.781501 -0.0290702 -0.532035 0.846722 0 -0.330274 0.943885 0 -0.900591 0.433694 -0.0290726 -0.846725 0.53203 0 -0.707104 0.70711 0 -0.999577 0 -0.0290747 -0.993711 0.111978 0 -0.943888 0.330267 0 -0.900591 -0.433694 -0.0290726 -0.943888 -0.330267 0 -0.993711 -0.111978 0 -0.623227 -0.781501 -0.0290702 -0.707104 -0.70711 0 -0.846725 -0.53203 0 -0.222426 -0.974516 -0.0290704 -0.330274 -0.943885 0 -0.532035 -0.846722 0 0.222426 -0.974516 -0.0290704 0.111966 -0.993712 0 -0.111966 -0.993712 0 0.623227 -0.781501 -0.0290702 0.532035 -0.846722 0 0.330274 -0.943885 0 0.900591 -0.433694 -0.0290726 0.846725 -0.53203 0 0.707104 -0.70711 0 0.999577 0 -0.0290747 0.993711 -0.111978 0 0.943888 -0.330267 0 0.900591 0.433694 -0.0290726 0.943888 0.330267 0 0.993711 0.111978 0 0.623227 0.781501 -0.0290702 0.707104 0.70711 0 0.846725 0.53203 0 -0.111966 0.993712 0 0.111966 0.993712 0 0.222426 0.974516 -0.0290704 0.330274 0.943885 0 0.532035 0.846722 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.222426 0.974516 -0.0290704 -0.623227 0.781501 -0.0290702 -0.532035 0.846722 0 -0.330274 0.943885 0 -0.900591 0.433694 -0.0290726 -0.846725 0.53203 0 -0.707104 0.70711 0 -0.999577 0 -0.0290747 -0.993711 0.111978 0 -0.943888 0.330267 0 -0.900591 -0.433694 -0.0290726 -0.943888 -0.330267 0 -0.993711 -0.111978 0 -0.623227 -0.781501 -0.0290702 -0.707104 -0.70711 0 -0.846725 -0.53203 0 -0.222426 -0.974516 -0.0290704 -0.330274 -0.943885 0 -0.532035 -0.846722 0 0.222426 -0.974516 -0.0290704 0.111966 -0.993712 0 -0.111966 -0.993712 0 0.623227 -0.781501 -0.0290702 0.532035 -0.846722 0 0.330274 -0.943885 0 0.900591 -0.433694 -0.0290726 0.846725 -0.53203 0 0.707104 -0.70711 0 0.999577 0 -0.0290747 0.993711 -0.111978 0 0.943888 -0.330267 0 0.900591 0.433694 -0.0290726 0.943888 0.330267 0 0.993711 0.111978 0 0.623227 0.781501 -0.0290702 0.707104 0.70711 0 0.846725 0.53203 0 -0.111966 0.993712 0 0.111966 0.993712 0 0.222426 0.974516 -0.0290704 0.330274 0.943885 0 0.532035 0.846722 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.0291487 -0.258711 0.965515 0.0859886 -0.245737 0.965515 0.085988 -0.245739 0.965515 0.138515 -0.220443 0.965515 0.138514 -0.220445 0.965514 0.184094 -0.184096 0.965515 0.184094 -0.184096 0.965514 0.220445 -0.138513 0.965515 0.220446 -0.138517 0.965514 0.245742 -0.0859891 0.965514 0.245741 -0.0859858 0.965514 0.258714 -0.029149 0.965514 0.258715 -0.0291514 0.965514 0.258715 0.0291492 0.965514 0.258713 0.0291512 0.965514 0.24574 0.085989 0.965514 0.245743 0.0859873 0.965514 0.220448 0.138513 0.965514 0.220444 0.138514 0.965515 0.184094 0.184096 0.965515 0.184091 0.184096 0.965515 0.138515 0.220442 0.965515 0.138515 0.220442 0.965515 0.0859873 0.245739 0.965515 0.0859882 0.245739 0.965515 0.0291503 0.258713 0.965514 0.0291487 0.258712 0.965515 -0.029151 0.258712 0.965515 -0.029149 0.258714 0.965514 -0.085986 0.245742 0.965514 -0.085988 0.245739 0.965515 -0.138515 0.220443 0.965515 -0.138515 0.220442 0.965515 -0.184093 0.184095 0.965515 -0.184093 0.184097 0.965514 -0.220446 0.138512 0.965514 -0.220446 0.138516 0.965514 -0.245742 0.0859896 0.965514 -0.245741 0.0859865 0.965514 -0.258714 0.029149 0.965514 -0.258715 0.0291514 0.965514 -0.258715 -0.0291492 0.965514 -0.258713 -0.0291512 0.965514 -0.24574 -0.0859884 0.965514 -0.245744 -0.0859867 0.965514 -0.220447 -0.138514 0.965514 -0.220443 -0.138515 0.965515 -0.184094 -0.184096 0.965515 -0.184093 -0.184096 0.965515 -0.138515 -0.220444 0.965514 -0.138513 -0.220443 0.965515 -0.0859867 -0.245739 0.965515 -0.0859884 -0.24574 0.965514 -0.0291492 -0.258712 0.965515 -0.0291487 -0.258712 0.965515 0.0291484 -0.258712 0.965515 0.0794167 -0.704877 0.70487 0.234273 -0.669536 0.704867 0.234281 -0.669525 0.704876 0.377393 -0.600604 0.704876 0.377391 -0.600609 0.704872 0.501575 -0.501575 0.704872 0.501575 -0.50158 0.704869 0.600614 -0.377391 0.704868 0.600613 -0.377384 0.704873 0.669526 -0.234284 0.704873 0.669523 -0.234276 0.704879 0.704868 -0.0794193 0.704879 0.704866 -0.0794166 0.704881 0.704866 0.0794191 0.70488 0.704868 0.0794168 0.704878 0.669521 0.234283 0.704878 0.669526 0.234279 0.704874 0.600609 0.377388 0.704874 0.600618 0.377385 0.704868 0.501577 0.501577 0.70487 0.501573 0.501577 0.704872 0.377395 0.600606 0.704873 0.377389 0.600606 0.704876 0.234271 0.669529 0.704875 0.234278 0.669531 0.70487 0.0794209 0.704873 0.704873 0.0794211 0.704873 0.704873 -0.0794209 0.704873 0.704873 -0.0794231 0.704871 0.704875 -0.234271 0.669528 0.704876 -0.23427 0.669529 0.704875 -0.377393 0.600604 0.704876 -0.377391 0.600609 0.704872 -0.501575 0.501575 0.704872 -0.501575 0.50158 0.704869 -0.600614 0.377391 0.704868 -0.600613 0.377381 0.704875 -0.669524 0.234284 0.704875 -0.669522 0.234278 0.704879 -0.704868 0.0794193 0.704879 -0.704866 0.0794166 0.704881 -0.704866 -0.0794191 0.70488 -0.704868 -0.0794168 0.704878 -0.669521 -0.234283 0.704878 -0.669528 -0.234278 0.704873 -0.60061 -0.377389 0.704872 -0.600617 -0.377387 0.704868 -0.501577 -0.501577 0.70487 -0.501573 -0.501577 0.704872 -0.377395 -0.600606 0.704873 -0.377389 -0.600606 0.704876 -0.234271 -0.669529 0.704875 -0.234276 -0.66953 0.704872 -0.0794211 -0.704875 0.704871 -0.0794185 -0.704873 0.704873 0.0794209 -0.704873 0.704873 0.108196 -0.960254 0.257305 0.319153 -0.912104 0.257307 0.31915 -0.912107 0.257302 0.514122 -0.818214 0.257303 0.514127 -0.818209 0.25731 0.683295 -0.6833 0.257311 0.683297 -0.683297 0.257316 0.818214 -0.514115 0.257318 0.818213 -0.514118 0.257314 0.912105 -0.319146 0.257315 0.912104 -0.319169 0.257289 0.960257 -0.108208 0.25729 0.960254 -0.108194 0.257306 0.960253 0.108207 0.257306 0.960258 0.108195 0.25729 0.912111 0.319148 0.25729 0.912097 0.319167 0.257316 0.818214 0.514115 0.257314 0.818212 0.514118 0.257318 0.683294 0.683299 0.257315 0.683298 0.683298 0.257311 0.514121 0.818212 0.25731 0.514128 0.81821 0.257302 0.319154 0.912105 0.257303 0.31915 0.912106 0.257307 0.108197 0.960254 0.257305 0.108196 0.960254 0.257306 -0.108197 0.960254 0.257306 -0.108196 0.960254 0.257305 -0.319153 0.912104 0.257307 -0.31915 0.912107 0.257302 -0.514122 0.818214 0.257303 -0.514127 0.818209 0.25731 -0.683295 0.6833 0.257311 -0.683297 0.683297 0.257316 -0.818214 0.514115 0.257318 -0.818213 0.514118 0.257314 -0.912105 0.319146 0.257315 -0.912104 0.319169 0.257289 -0.960257 0.108208 0.25729 -0.960254 0.108194 0.257306 -0.960253 -0.108207 0.257306 -0.960258 -0.108195 0.25729 -0.912111 -0.319148 0.25729 -0.912097 -0.319167 0.257316 -0.818214 -0.514115 0.257314 -0.818212 -0.514118 0.257318 -0.683294 -0.683299 0.257315 -0.683298 -0.683298 0.257311 -0.514121 -0.818212 0.25731 -0.514128 -0.81821 0.257302 -0.319154 -0.912105 0.257303 -0.31915 -0.912106 0.257307 -0.108197 -0.960254 0.257305 -0.108196 -0.960254 0.257306 0.108197 -0.960254 0.257306 0.0291489 -0.258713 0.965514 0.0859875 -0.245739 0.965515 0.085988 -0.245739 0.965515 0.138515 -0.220443 0.965515 0.138515 -0.220442 0.965515 0.184093 -0.184095 0.965515 0.184093 -0.184097 0.965514 0.220446 -0.138512 0.965514 0.220447 -0.138518 0.965513 0.245743 -0.0859898 0.965514 0.245741 -0.0859858 0.965514 0.258714 -0.029149 0.965514 0.258715 -0.0291514 0.965514 0.258715 0.0291492 0.965514 0.258713 0.0291512 0.965514 0.24574 0.0859884 0.965514 0.245744 0.0859867 0.965514 0.220447 0.138514 0.965514 0.220443 0.138515 0.965515 0.184094 0.184096 0.965515 0.184091 0.184096 0.965515 0.138515 0.220442 0.965515 0.138515 0.220442 0.965515 0.0859889 0.245738 0.965515 0.0859876 0.245738 0.965515 0.0291484 0.258711 0.965515 0.0291487 0.258712 0.965515 -0.0291492 0.258712 0.965515 -0.0291488 0.258712 0.965515 -0.0859871 0.24574 0.965514 -0.085988 0.245739 0.965515 -0.138515 0.220443 0.965515 -0.138515 0.220442 0.965515 -0.184093 0.184095 0.965515 -0.184093 0.184097 0.965514 -0.220445 0.138513 0.965515 -0.220446 0.138517 0.965514 -0.245742 0.0859891 0.965514 -0.245741 0.0859858 0.965514 -0.258714 0.029149 0.965514 -0.258715 0.0291514 0.965514 -0.258715 -0.0291492 0.965514 -0.258713 -0.0291512 0.965514 -0.24574 -0.085989 0.965514 -0.245744 -0.0859869 0.965513 -0.220449 -0.138514 0.965514 -0.220443 -0.138515 0.965515 -0.184094 -0.184096 0.965515 -0.184091 -0.184096 0.965515 -0.138515 -0.220442 0.965515 -0.138515 -0.220442 0.965515 -0.0859851 -0.24574 0.965515 -0.085989 -0.245741 0.965514 -0.0291512 -0.258714 0.965514 -0.0291487 -0.258712 0.965515 0.0291502 -0.258712 0.965515 0.0794211 -0.704873 0.704873 0.234272 -0.669532 0.704871 0.234276 -0.669526 0.704875 0.377393 -0.600604 0.704876 0.377391 -0.600609 0.704872 0.501575 -0.501575 0.704872 0.501575 -0.50158 0.704869 0.600614 -0.377391 0.704868 0.600613 -0.377381 0.704875 0.669524 -0.234284 0.704875 0.669522 -0.234278 0.704879 0.704868 -0.0794193 0.704879 0.704866 -0.0794166 0.704881 0.704866 0.0794191 0.70488 0.704868 0.0794168 0.704878 0.669521 0.234283 0.704878 0.669528 0.234278 0.704873 0.60061 0.377389 0.704872 0.600617 0.377387 0.704868 0.501577 0.501577 0.70487 0.501573 0.501577 0.704872 0.377395 0.600606 0.704873 0.377389 0.600606 0.704876 0.234271 0.669529 0.704875 0.234283 0.669533 0.704867 0.0794213 0.704877 0.70487 0.0794163 0.704873 0.704873 -0.0794209 0.704873 0.704873 -0.0794187 0.704875 0.704871 -0.234272 0.669531 0.704872 -0.234274 0.669527 0.704875 -0.377393 0.600604 0.704876 -0.377391 0.600609 0.704872 -0.501575 0.501575 0.704872 -0.501575 0.50158 0.704869 -0.600614 0.377391 0.704868 -0.600613 0.377384 0.704873 -0.669526 0.234284 0.704873 -0.669523 0.234276 0.704879 -0.704868 0.0794193 0.704879 -0.704866 0.0794166 0.704881 -0.704866 -0.0794191 0.70488 -0.704868 -0.0794168 0.704878 -0.669521 -0.234283 0.704878 -0.669526 -0.234279 0.704874 -0.600609 -0.377388 0.704874 -0.600618 -0.377385 0.704868 -0.501577 -0.501577 0.70487 -0.501573 -0.501577 0.704872 -0.377395 -0.600606 0.704873 -0.377389 -0.600606 0.704876 -0.234271 -0.669529 0.704875 -0.23427 -0.669528 0.704876 -0.0794207 -0.704871 0.704875 -0.0794234 -0.704873 0.704873 0.0794209 -0.704873 0.704873 0.108196 -0.960254 0.257305 0.319153 -0.912104 0.257307 0.31915 -0.912107 0.257302 0.514122 -0.818214 0.257303 0.514127 -0.818209 0.25731 0.683295 -0.6833 0.257311 0.683297 -0.683297 0.257316 0.818214 -0.514115 0.257318 0.818213 -0.514118 0.257314 0.912105 -0.319146 0.257315 0.912104 -0.319169 0.257289 0.960257 -0.108208 0.25729 0.960254 -0.108194 0.257306 0.960253 0.108207 0.257306 0.960258 0.108195 0.25729 0.912111 0.319148 0.25729 0.912097 0.319167 0.257316 0.818214 0.514115 0.257314 0.818212 0.514118 0.257318 0.683294 0.683299 0.257315 0.683298 0.683298 0.257311 0.514121 0.818212 0.25731 0.514128 0.81821 0.257302 0.319154 0.912105 0.257303 0.31915 0.912106 0.257307 0.108197 0.960254 0.257305 0.108196 0.960254 0.257306 -0.108197 0.960254 0.257306 -0.108196 0.960254 0.257305 -0.319153 0.912104 0.257307 -0.31915 0.912107 0.257302 -0.514122 0.818214 0.257303 -0.514127 0.818209 0.25731 -0.683295 0.6833 0.257311 -0.683297 0.683297 0.257316 -0.818214 0.514115 0.257318 -0.818213 0.514118 0.257314 -0.912105 0.319146 0.257315 -0.912104 0.319169 0.257289 -0.960257 0.108208 0.25729 -0.960254 0.108194 0.257306 -0.960253 -0.108207 0.257306 -0.960258 -0.108195 0.25729 -0.912111 -0.319148 0.25729 -0.912097 -0.319167 0.257316 -0.818214 -0.514115 0.257314 -0.818212 -0.514118 0.257318 -0.683294 -0.683299 0.257315 -0.683298 -0.683298 0.257311 -0.514121 -0.818212 0.25731 -0.514128 -0.81821 0.257302 -0.319154 -0.912105 0.257303 -0.31915 -0.912106 0.257307 -0.108197 -0.960254 0.257305 -0.108196 -0.960254 0.257306 0.108197 -0.960254 0.257306 -0.0226384 0.258754 -0.965678 -0.0672264 0.250893 -0.965678 -0.0672267 0.250893 -0.965678 -0.109772 0.235408 -0.965677 -0.109775 0.235411 -0.965676 -0.148987 0.212774 -0.965676 -0.148982 0.21277 -0.965677 -0.183667 0.183667 -0.965677 -0.183667 0.183667 -0.965677 -0.212771 0.148983 -0.965677 -0.212766 0.148981 -0.965679 -0.235402 0.109772 -0.965679 -0.235415 0.109774 -0.965676 -0.2509 0.0672281 -0.965676 -0.250898 0.0672282 -0.965676 -0.25876 0.0226405 -0.965676 -0.258759 0.0226408 -0.965677 -0.258759 -0.0226404 -0.965677 -0.25876 -0.0226408 -0.965676 -0.250898 -0.0672275 -0.965676 -0.2509 -0.0672288 -0.965676 -0.235414 -0.109777 -0.965676 -0.235404 -0.109769 -0.965679 -0.212766 -0.148979 -0.965679 -0.21277 -0.148984 -0.965677 -0.183667 -0.183667 -0.965677 -0.183667 -0.183667 -0.965677 -0.148983 -0.212769 -0.965678 -0.148985 -0.212775 -0.965676 -0.109774 -0.235412 -0.965676 -0.109773 -0.235408 -0.965677 -0.0672266 -0.250893 -0.965678 -0.0672266 -0.250893 -0.965678 -0.0226388 -0.258754 -0.965678 -0.0226378 -0.258759 -0.965677 0.0226393 -0.258759 -0.965677 0.0226374 -0.258754 -0.965678 0.0672264 -0.250893 -0.965678 0.0672267 -0.250893 -0.965678 0.109772 -0.235408 -0.965677 0.109775 -0.235411 -0.965676 0.148987 -0.212774 -0.965676 0.148982 -0.21277 -0.965677 0.183667 -0.183667 -0.965677 0.183667 -0.183667 -0.965677 0.212771 -0.148983 -0.965677 0.212766 -0.148981 -0.965679 0.235402 -0.109772 -0.965679 0.235415 -0.109774 -0.965676 0.2509 -0.0672281 -0.965676 0.250898 -0.0672282 -0.965676 0.258761 -0.0226363 -0.965676 0.258745 -0.0226394 -0.96568 0.258745 0.022635 -0.965681 0.25876 0.0226409 -0.965676 0.250898 0.0672275 -0.965676 0.2509 0.0672288 -0.965676 0.235414 0.109777 -0.965676 0.235404 0.109769 -0.965679 0.212766 0.148979 -0.965679 0.21277 0.148984 -0.965677 0.183667 0.183667 -0.965677 0.183667 0.183667 -0.965677 0.148983 0.212769 -0.965678 0.148985 0.212775 -0.965676 0.109774 0.235412 -0.965676 0.109773 0.235408 -0.965677 0.0672266 0.250893 -0.965678 0.0672266 0.250893 -0.965678 0.0226388 0.258754 -0.965678 0.0226385 0.258755 -0.965678 -0.022639 0.258755 -0.965678 -0.061749 0.705768 -0.705747 -0.183362 0.684323 -0.705748 -0.183365 0.684327 -0.705744 -0.299414 0.642091 -0.705741 -0.299407 0.642084 -0.70575 -0.406359 0.580335 -0.705751 -0.406355 0.580332 -0.705755 -0.500948 0.500957 -0.705757 -0.500963 0.500963 -0.705742 -0.580348 0.406358 -0.705741 -0.580343 0.406357 -0.705745 -0.642088 0.299413 -0.705744 -0.642082 0.299413 -0.70575 -0.684321 0.183364 -0.70575 -0.684326 0.183364 -0.705744 -0.70577 0.0617473 -0.705745 -0.705757 0.0617511 -0.705757 -0.705758 -0.0617459 -0.705758 -0.705769 -0.0617519 -0.705745 -0.684326 -0.183366 -0.705744 -0.684322 -0.183362 -0.705749 -0.642083 -0.29941 -0.70575 -0.642087 -0.299415 -0.705744 -0.580344 -0.406355 -0.705745 -0.580347 -0.406359 -0.705741 -0.500959 -0.500968 -0.705741 -0.500953 -0.500953 -0.705757 -0.406356 -0.580331 -0.705755 -0.406357 -0.580336 -0.705751 -0.29941 -0.642083 -0.70575 -0.299411 -0.642092 -0.705741 -0.183363 -0.684327 -0.705744 -0.183364 -0.684323 -0.705748 -0.0617474 -0.705769 -0.705746 -0.0617486 -0.705765 -0.70575 0.0617471 -0.705765 -0.70575 0.061749 -0.705768 -0.705747 0.183365 -0.684322 -0.705748 0.183363 -0.684319 -0.705751 0.299404 -0.642082 -0.705754 0.299407 -0.642084 -0.70575 0.406359 -0.580335 -0.705751 0.406355 -0.580332 -0.705755 0.500948 -0.500957 -0.705757 0.500963 -0.500963 -0.705742 0.580348 -0.406358 -0.705741 0.580343 -0.406357 -0.705745 0.642088 -0.299413 -0.705744 0.642082 -0.299413 -0.70575 0.684321 -0.183364 -0.70575 0.684326 -0.183364 -0.705744 0.70577 -0.061747 -0.705745 0.705786 -0.0617419 -0.705729 0.705786 0.0617487 -0.705729 0.705771 0.0617408 -0.705745 0.684326 0.183366 -0.705744 0.684322 0.183362 -0.705749 0.642083 0.29941 -0.70575 0.642087 0.299415 -0.705744 0.580344 0.406355 -0.705745 0.580347 0.406359 -0.705741 0.500959 0.500968 -0.705741 0.500953 0.500953 -0.705757 0.406356 0.580331 -0.705755 0.406357 0.580336 -0.705751 0.299406 0.642085 -0.70575 0.299405 0.642081 -0.705753 0.183364 0.684319 -0.705751 0.183364 0.684323 -0.705748 0.0617474 0.705769 -0.705746 0.0617486 0.705765 -0.70575 -0.0617471 0.705765 -0.70575 -0.0842082 0.962493 -0.257906 -0.250063 0.93325 -0.2579 -0.250061 0.933249 -0.257905 -0.408324 0.875645 -0.257909 -0.408323 0.875645 -0.257913 -0.554167 0.791441 -0.257915 -0.554179 0.791442 -0.257886 -0.683192 0.683188 -0.257881 -0.683177 0.683189 -0.257919 -0.791437 0.55417 -0.25792 -0.791446 0.554168 -0.257897 -0.875648 0.408327 -0.257896 -0.875651 0.408326 -0.257886 -0.933254 0.250063 -0.257885 -0.93325 0.250065 -0.257897 -0.962497 0.0841967 -0.257895 -0.962486 0.0842072 -0.257933 -0.962487 -0.0841955 -0.257933 -0.962496 -0.0842077 -0.257896 -0.933251 -0.250062 -0.257897 -0.933253 -0.250066 -0.257885 -0.87565 -0.408329 -0.257886 -0.875649 -0.408325 -0.257895 -0.791442 -0.554174 -0.257896 -0.791441 -0.554164 -0.25792 -0.683185 -0.683181 -0.257919 -0.683184 -0.683196 -0.257881 -0.554172 -0.791447 -0.257886 -0.554175 -0.791436 -0.257915 -0.408324 -0.875644 -0.257913 -0.408323 -0.875646 -0.25791 -0.250062 -0.933249 -0.257905 -0.250061 -0.933251 -0.2579 -0.0842081 -0.962494 -0.257906 -0.0842082 -0.962493 -0.257906 0.0842081 -0.962493 -0.257906 0.0842082 -0.962493 -0.257906 0.250063 -0.93325 -0.2579 0.250066 -0.933252 -0.257891 0.408327 -0.875651 -0.257887 0.408316 -0.875648 -0.257913 0.554167 -0.791441 -0.257915 0.554179 -0.791442 -0.257886 0.683192 -0.683188 -0.257881 0.683177 -0.683189 -0.257919 0.791437 -0.55417 -0.25792 0.791446 -0.554168 -0.257897 0.875654 -0.408314 -0.257895 0.875639 -0.40832 -0.257935 0.933237 -0.250075 -0.257937 0.93325 -0.250065 -0.257897 0.962497 -0.0841964 -0.257895 0.962486 -0.0842069 -0.257933 0.962487 0.0841959 -0.257933 0.962496 0.0842081 -0.257896 0.933247 0.250077 -0.257897 0.93324 0.250063 -0.257937 0.875644 0.408309 -0.257935 0.875649 0.408325 -0.257895 0.791442 0.554174 -0.257896 0.791441 0.554164 -0.25792 0.683185 0.683181 -0.257919 0.683184 0.683196 -0.257881 0.554172 0.791447 -0.257886 0.554175 0.791436 -0.257915 0.408324 0.875644 -0.257913 0.408319 0.875654 -0.257887 0.250063 0.933253 -0.257891 0.250065 0.93325 -0.2579 0.0842081 0.962494 -0.257906 0.0842082 0.962493 -0.257906 -0.0842081 0.962493 -0.257906 -0.0226374 -0.258754 0.965678 -0.0672264 -0.250893 0.965678 -0.0672267 -0.250893 0.965678 -0.109772 -0.235408 0.965677 -0.109775 -0.235411 0.965676 -0.148987 -0.212774 0.965676 -0.148982 -0.21277 0.965677 -0.183667 -0.183667 0.965677 -0.183667 -0.183667 0.965677 -0.212771 -0.148983 0.965677 -0.212766 -0.148981 0.965679 -0.235402 -0.109772 0.965679 -0.235415 -0.109774 0.965676 -0.2509 -0.0672281 0.965676 -0.250898 -0.0672282 0.965676 -0.25876 -0.0226404 0.965676 -0.258759 -0.0226407 0.965677 -0.258759 0.0226404 0.965677 -0.25876 0.0226409 0.965676 -0.250898 0.0672275 0.965676 -0.2509 0.0672288 0.965676 -0.235414 0.109777 0.965676 -0.235404 0.109769 0.965679 -0.212766 0.148979 0.965679 -0.21277 0.148984 0.965677 -0.183667 0.183667 0.965677 -0.183667 0.183667 0.965677 -0.148983 0.212769 0.965678 -0.148985 0.212775 0.965676 -0.109774 0.235412 0.965676 -0.109773 0.235408 0.965677 -0.0672266 0.250893 0.965678 -0.0672266 0.250893 0.965678 -0.0226388 0.258754 0.965678 -0.0226385 0.258755 0.965678 0.022639 0.258755 0.965678 0.0226384 0.258754 0.965678 0.0672264 0.250893 0.965678 0.0672267 0.250893 0.965678 0.109772 0.235408 0.965677 0.109775 0.235411 0.965676 0.148987 0.212774 0.965676 0.148982 0.21277 0.965677 0.183667 0.183667 0.965677 0.183667 0.183667 0.965677 0.212771 0.148983 0.965677 0.212766 0.148981 0.965679 0.235402 0.109772 0.965679 0.235415 0.109774 0.965676 0.2509 0.0672281 0.965676 0.250898 0.0672282 0.965676 0.258761 0.0226364 0.965676 0.258745 0.0226395 0.96568 0.258745 -0.0226349 0.965681 0.25876 -0.0226408 0.965676 0.250898 -0.0672275 0.965676 0.2509 -0.0672288 0.965676 0.235414 -0.109777 0.965676 0.235404 -0.109769 0.965679 0.212766 -0.148979 0.965679 0.21277 -0.148984 0.965677 0.183667 -0.183667 0.965677 0.183667 -0.183667 0.965677 0.148983 -0.212769 0.965678 0.148985 -0.212775 0.965676 0.109774 -0.235412 0.965676 0.109773 -0.235408 0.965677 0.0672266 -0.250893 0.965678 0.0672266 -0.250893 0.965678 0.0226388 -0.258754 0.965678 0.0226378 -0.258759 0.965677 -0.0226393 -0.258759 0.965677 -0.0617477 -0.705754 0.705761 -0.183358 -0.684309 0.705763 -0.183361 -0.684313 0.705758 -0.299408 -0.642078 0.705755 -0.299401 -0.642071 0.705765 -0.40635 -0.580323 0.705765 -0.406347 -0.580321 0.705769 -0.500938 -0.500947 0.705772 -0.500953 -0.500953 0.705756 -0.580336 -0.406349 0.705755 -0.580331 -0.406348 0.70576 -0.642075 -0.299407 0.705758 -0.642069 -0.299407 0.705764 -0.684307 -0.183361 0.705764 -0.684313 -0.18336 0.705759 -0.705756 -0.0617458 0.70576 -0.705743 -0.0617496 0.705772 -0.705743 0.061745 0.705772 -0.705755 0.0617509 0.70576 -0.684312 0.183362 0.705759 -0.684308 0.183359 0.705764 -0.64207 0.299404 0.705765 -0.642074 0.299409 0.705758 -0.580332 0.406347 0.70576 -0.580335 0.406351 0.705755 -0.500949 0.500958 0.705756 -0.500942 0.500942 0.705772 -0.406348 0.58032 0.70577 -0.406349 0.580324 0.705765 -0.299404 0.64207 0.705765 -0.299404 0.642079 0.705756 -0.183359 0.684313 0.705758 -0.18336 0.684309 0.705762 -0.0617462 0.705754 0.705761 -0.0617474 0.70575 0.705765 0.0617458 0.70575 0.705765 0.0617477 0.705754 0.705761 0.183361 0.684308 0.705762 0.183359 0.684306 0.705766 0.299398 0.642069 0.705768 0.299401 0.642071 0.705765 0.40635 0.580323 0.705765 0.406347 0.580321 0.705769 0.500938 0.500947 0.705772 0.500953 0.500953 0.705756 0.580336 0.406349 0.705755 0.580331 0.406348 0.70576 0.642075 0.299407 0.705758 0.642069 0.299407 0.705764 0.684307 0.183361 0.705764 0.684313 0.18336 0.705759 0.705756 0.061746 0.70576 0.705772 0.0617409 0.705743 0.705772 -0.0617472 0.705743 0.705756 -0.0617393 0.705759 0.684312 -0.183362 0.705759 0.684308 -0.183359 0.705764 0.64207 -0.299404 0.705765 0.642074 -0.299409 0.705758 0.580332 -0.406347 0.70576 0.580335 -0.406351 0.705755 0.500949 -0.500958 0.705756 0.500942 -0.500942 0.705772 0.406348 -0.58032 0.70577 0.406349 -0.580324 0.705765 0.299399 -0.642072 0.705765 0.299399 -0.642068 0.705768 0.18336 -0.684305 0.705766 0.18336 -0.684309 0.705762 0.0617462 -0.705754 0.705761 0.0617474 -0.70575 0.705765 -0.0617458 -0.70575 0.705765 -0.0842084 -0.962495 0.257898 -0.250063 -0.933252 0.257892 -0.250061 -0.933251 0.257898 -0.408325 -0.875647 0.257902 -0.408323 -0.875646 0.257906 -0.554168 -0.791442 0.257908 -0.55418 -0.791444 0.257879 -0.683194 -0.683189 0.257874 -0.683178 -0.68319 0.257912 -0.791439 -0.554171 0.257913 -0.791448 -0.554169 0.257889 -0.875649 -0.408328 0.257888 -0.875653 -0.408327 0.257879 -0.933256 -0.250063 0.257878 -0.933252 -0.250066 0.25789 -0.962499 -0.0841965 0.257888 -0.962488 -0.084207 0.257926 -0.962489 0.084196 0.257926 -0.962498 0.0842082 0.257888 -0.933253 0.250062 0.25789 -0.933255 0.250067 0.257878 -0.875652 0.408329 0.257879 -0.875651 0.408326 0.257888 -0.791444 0.554175 0.257889 -0.791443 0.554166 0.257913 -0.683186 0.683182 0.257912 -0.683185 0.683197 0.257874 -0.554173 0.791449 0.257879 -0.554176 0.791437 0.257908 -0.408324 0.875646 0.257906 -0.408324 0.875647 0.257902 -0.250063 0.933251 0.257898 -0.250062 0.933253 0.257892 -0.0842082 0.962495 0.257898 -0.0842084 0.962495 0.257899 0.0842082 0.962495 0.257899 0.0842084 0.962495 0.257898 0.250063 0.933252 0.257892 0.250066 0.933254 0.257884 0.408327 0.875652 0.25788 0.408317 0.875649 0.257906 0.554168 0.791442 0.257908 0.55418 0.791444 0.257879 0.683194 0.683189 0.257874 0.683178 0.68319 0.257912 0.791439 0.554171 0.257913 0.791448 0.554169 0.257889 0.875656 0.408315 0.257888 0.875641 0.408321 0.257927 0.933239 0.250075 0.25793 0.933252 0.250066 0.25789 0.962499 0.0841969 0.257888 0.962488 0.0842074 0.257926 0.962489 -0.0841957 0.257926 0.962498 -0.0842079 0.257889 0.933249 -0.250078 0.25789 0.933242 -0.250063 0.25793 0.875646 -0.40831 0.257928 0.875651 -0.408326 0.257888 0.791444 -0.554175 0.257889 0.791443 -0.554166 0.257913 0.683186 -0.683182 0.257912 0.683185 -0.683197 0.257874 0.554173 -0.791449 0.257879 0.554176 -0.791437 0.257908 0.408324 -0.875646 0.257906 0.40832 -0.875656 0.25788 0.250064 -0.933254 0.257884 0.250066 -0.933252 0.257892 0.0842082 -0.962495 0.257898 0.0842084 -0.962495 0.257899 -0.0842082 -0.962495 0.257899 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.99863 0 -0.052336 -0.99863 0 -0.052336 -0.995559 0.0783527 -0.0521751 -0.996064 0.0712392 -0.0527432 -0.983091 0.175543 -0.052122 -0.984305 0.168541 -0.0523169 -0.966276 0.252154 -0.0522451 -0.969737 0.238309 -0.0530947 -0.936946 0.345661 -0.0514792 -0.941749 0.332231 -0.0522614 -0.906901 0.418085 -0.052296 -0.91561 0.39854 -0.0531388 -0.861638 0.505014 -0.0504093 -0.87645 0.478579 -0.0528936 -0.819301 0.570996 -0.0520541 -0.799497 0.598499 -0.0510236 -0.759303 0.648509 -0.0538079 -0.598498 0.799498 -0.0510241 -0.648504 0.759307 -0.0538082 -0.680488 0.73089 -0.0523025 -0.730892 0.680486 -0.0523025 -0.0712413 0.996092 -0.0522031 -0.0783505 0.995531 -0.0527194 -0.16854 0.984313 -0.0521822 -0.175555 0.983078 -0.0523258 -0.238318 0.969779 -0.0522839 -0.252134 0.966244 -0.052926 -0.332242 0.941775 -0.0517206 -0.345645 0.936907 -0.0522956 -0.398568 0.915645 -0.0523275 -0.418079 0.90688 -0.052704 -0.478619 0.87653 -0.0511712 -0.504955 0.861534 -0.0527219 -0.571021 0.819283 -0.0520536 0 0.99863 -0.052336 0 0.99863 -0.052336 0.0783527 0.995559 -0.0521751 0.0712387 0.996064 -0.0527432 0.175557 0.983088 -0.0521219 0.168543 0.984305 -0.0523172 0.252143 0.966279 -0.0522454 0.238307 0.969737 -0.0530944 0.34566 0.936947 -0.051479 0.332233 0.941748 -0.052261 0.418088 0.9069 -0.0522956 0.398551 0.915606 -0.0531381 0.505015 0.861637 -0.0504088 0.478576 0.876451 -0.0528934 0.571006 0.819294 -0.0520538 0.598498 0.799498 -0.0510238 0.648508 0.759304 -0.053808 0.799497 0.598499 -0.0510236 0.759303 0.648509 -0.0538079 0.730892 0.680486 -0.0523025 0.680488 0.73089 -0.0523025 0.996092 0.0712412 -0.0522031 0.995531 0.0783505 -0.0527194 0.984312 0.168542 -0.0521822 0.983081 0.175541 -0.0523255 0.969779 0.238319 -0.0522836 0.966241 0.252145 -0.0529262 0.941776 0.332241 -0.0517208 0.936912 0.345632 -0.0522954 0.915649 0.398558 -0.0523273 0.906876 0.41809 -0.0527043 0.876529 0.478622 -0.0511716 0.861535 0.504954 -0.0527221 0.819301 0.570996 -0.0520541 0.99863 0 -0.052336 0.99863 0 -0.052336 0.995559 -0.0783527 -0.0521751 0.996064 -0.0712392 -0.0527432 0.983091 -0.175543 -0.052122 0.984305 -0.168541 -0.0523169 0.966276 -0.252154 -0.0522451 0.969737 -0.238308 -0.0530947 0.936952 -0.345647 -0.0514795 0.941749 -0.332232 -0.0522608 0.906895 -0.418099 -0.0522954 0.91561 -0.39854 -0.0531388 0.861638 -0.505014 -0.0504093 0.87645 -0.478579 -0.0528936 0.819301 -0.570996 -0.0520541 0.799497 -0.598499 -0.0510236 0.759303 -0.648509 -0.0538079 0.598497 -0.799499 -0.0510237 0.648508 -0.759303 -0.053808 0.680488 -0.73089 -0.0523025 0.730892 -0.680486 -0.0523025 0.0712427 -0.996092 -0.052203 0.0783504 -0.995531 -0.0527193 0.168534 -0.984314 -0.0521822 0.175548 -0.983079 -0.0523258 0.238321 -0.969778 -0.0522839 0.252139 -0.966243 -0.0529261 0.332242 -0.941775 -0.0517207 0.345641 -0.936908 -0.0522956 0.398561 -0.915648 -0.0523275 0.418083 -0.906879 -0.0527042 0.478622 -0.876528 -0.0511714 0.504953 -0.861535 -0.0527218 0.571006 -0.819294 -0.0520536 0 -0.99863 -0.052336 0 -0.99863 -0.052336 -0.0783527 -0.995559 -0.0521751 -0.0712413 -0.996064 -0.052743 -0.175549 -0.98309 -0.0521217 -0.168529 -0.984307 -0.0523172 -0.252148 -0.966277 -0.0522454 -0.23831 -0.969737 -0.0530945 -0.345656 -0.936948 -0.0514792 -0.332233 -0.941748 -0.052261 -0.418092 -0.906898 -0.0522956 -0.398544 -0.915608 -0.0531385 -0.505013 -0.861638 -0.0504091 -0.478579 -0.87645 -0.0528933 -0.571021 -0.819283 -0.0520535 -0.598497 -0.799499 -0.051024 -0.648504 -0.759307 -0.0538082 -0.799497 -0.598499 -0.0510236 -0.759303 -0.648509 -0.0538079 -0.730892 -0.680486 -0.0523025 -0.680488 -0.73089 -0.0523025 -0.996092 -0.0712412 -0.0522031 -0.995531 -0.0783505 -0.0527194 -0.984312 -0.168542 -0.0521822 -0.983081 -0.175541 -0.0523255 -0.969779 -0.238318 -0.0522836 -0.966241 -0.252145 -0.0529262 -0.941775 -0.332242 -0.0517209 -0.936906 -0.345646 -0.052296 -0.915649 -0.398558 -0.0523279 -0.906882 -0.418076 -0.0527046 -0.876529 -0.478622 -0.0511716 -0.861535 -0.504954 -0.0527221 -0.819301 -0.570996 -0.0520541 -0.99863 0 -0.052336 -0.99863 0 -0.052336 0.201517 0 0.979485 0.201517 0 0.979485 0.571784 0 0.820404 0.571784 0 0.820404 0.849199 0 0.528073 0.849199 0 0.528073 0.988691 0 0.149967 0.988691 0 0.149967 0.201496 0.0144116 0.979383 0.571306 0.0408618 0.819719 0.847637 0.0606212 0.527102 0.89898 0.317143 0.302084 0.926406 0.34553 0.149601 0.960145 0.235952 0.14983 0.934173 0.203222 0.293294 0.97452 0.166865 0.149891 0.986232 0.0705332 0.149569 0.986228 0.0705357 0.149594 0.906538 0.394592 0.149956 0.867801 0.473856 0.149604 0.867803 0.473856 0.149593 0.791532 0.592536 0.149594 0.79154 0.592536 0.149553 0.723631 0.673726 0.149836 0.674018 0.67402 0.302319 0.203217 0.934168 0.293313 0.673725 0.723626 0.149863 0.592536 0.791534 0.149582 0.592538 0.791535 0.149572 0.473856 0.867806 0.149575 0.473852 0.867805 0.149598 0.394603 0.906535 0.149944 0.336893 0.903247 0.265796 0.328935 0.932399 0.149783 0.23595 0.960143 0.149843 0.166866 0.974514 0.14993 0.0705352 0.986227 0.149606 0.0705366 0.986228 0.149594 0.847614 0.0606242 0.527138 0.830359 0.180638 0.527137 0.830374 0.180638 0.527114 0.796216 0.296972 0.527113 0.796212 0.296972 0.527118 0.745845 0.407262 0.527117 0.745841 0.40726 0.527125 0.680293 0.509259 0.527121 0.680302 0.509263 0.527106 0.600899 0.6009 0.527105 0.600904 0.600904 0.527096 0.50927 0.680302 0.527099 0.509262 0.680295 0.527116 0.40726 0.745849 0.527114 0.407273 0.745865 0.527081 0.296979 0.796232 0.527084 0.296976 0.796228 0.527093 0.180641 0.830388 0.527091 0.180637 0.830378 0.527109 0.060624 0.847631 0.527111 0.0606255 0.847637 0.527102 0.571309 0.0408616 0.819717 0.559679 0.121751 0.819717 0.559695 0.121753 0.819706 0.536669 0.200167 0.819707 0.536665 0.200166 0.81971 0.502714 0.274503 0.819711 0.502726 0.274508 0.819702 0.458541 0.343256 0.819704 0.4585 0.343234 0.819737 0.40499 0.40499 0.819736 0.40499 0.40499 0.819736 0.343234 0.458507 0.819733 0.343243 0.458516 0.819724 0.274494 0.502699 0.819724 0.274494 0.502697 0.819725 0.200158 0.536647 0.819724 0.200158 0.536647 0.819724 0.121748 0.559667 0.819726 0.121751 0.559677 0.819718 0.0408617 0.571308 0.819718 0.0408612 0.571306 0.819719 0.201484 0.0144121 0.979386 0.197383 0.0429375 0.979386 0.197388 0.042938 0.979385 0.189268 0.0705934 0.979385 0.189262 0.0705918 0.979386 0.17729 0.0968072 0.979386 0.177293 0.0968084 0.979385 0.16171 0.121056 0.979385 0.161716 0.12106 0.979384 0.142842 0.142842 0.979384 0.142846 0.142845 0.979383 0.121062 0.161719 0.979383 0.121055 0.161711 0.979385 0.0968092 0.177293 0.979385 0.0968121 0.177297 0.979384 0.0705936 0.18927 0.979384 0.0705947 0.189272 0.979384 0.0429405 0.197393 0.979384 0.0429395 0.19739 0.979384 0.0144112 0.201492 0.979384 0.0144107 0.201489 0.979385 0.0144108 -0.201493 0.979384 0.0408597 -0.571297 0.819725 0.0606243 -0.847637 0.527102 0.317144 -0.898977 0.302091 0.34553 -0.926403 0.14962 0.235953 -0.960142 0.149843 0.203216 -0.934163 0.293329 0.166856 -0.974518 0.149912 0.0705367 -0.986229 0.149588 0.0705373 -0.986228 0.149594 0.394595 -0.906535 0.149961 0.473856 -0.8678 0.149614 0.473855 -0.867807 0.149575 0.592536 -0.791536 0.149572 0.592536 -0.791534 0.149582 0.673725 -0.723626 0.149863 0.674018 -0.67402 0.302319 0.934173 -0.203222 0.293294 0.723631 -0.673726 0.149836 0.791537 -0.59254 0.149553 0.791535 -0.592532 0.149594 0.867803 -0.473857 0.149593 0.867802 -0.473855 0.149603 0.906538 -0.394592 0.149956 0.90325 -0.336894 0.265786 0.932401 -0.328934 0.149771 0.960144 -0.235951 0.149834 0.97452 -0.166865 0.149891 0.986232 -0.070536 0.149569 0.986229 -0.0705329 0.149594 0.060624 -0.84764 0.527097 0.180641 -0.830385 0.527095 0.180641 -0.830388 0.527091 0.296977 -0.796227 0.527093 0.296977 -0.796225 0.527096 0.407267 -0.745859 0.527093 0.407266 -0.745854 0.527103 0.509267 -0.6803 0.527105 0.509271 -0.68031 0.527088 0.600907 -0.600909 0.527086 0.6009 -0.600899 0.527105 0.680301 -0.509264 0.527107 0.680294 -0.509257 0.527121 0.745841 -0.407259 0.527125 0.745845 -0.407263 0.527117 0.796213 -0.296971 0.527118 0.796215 -0.296973 0.527113 0.830373 -0.180641 0.527115 0.83036 -0.180635 0.527138 0.847615 -0.0606196 0.527138 0.847637 -0.0606259 0.527102 0.0408596 -0.5713 0.819724 0.121749 -0.559669 0.819724 0.12175 -0.559675 0.81972 0.200162 -0.536654 0.819718 0.20016 -0.536646 0.819724 0.274493 -0.502698 0.819725 0.274493 -0.502699 0.819724 0.343241 -0.458518 0.819724 0.343231 -0.4585 0.819738 0.404986 -0.404985 0.81974 0.40499 -0.40499 0.819736 0.458504 -0.343229 0.819736 0.458537 -0.343261 0.819704 0.502725 -0.274509 0.819702 0.502715 -0.274502 0.819711 0.536665 -0.200165 0.81971 0.536669 -0.200168 0.819707 0.559695 -0.121755 0.819706 0.55968 -0.121749 0.819717 0.571309 -0.040862 0.819717 0.571306 -0.0408614 0.819719 0.0144109 -0.201492 0.979384 0.0429394 -0.19739 0.979384 0.042939 -0.197386 0.979385 0.0705928 -0.189265 0.979385 0.0705938 -0.18927 0.979384 0.0968113 -0.177297 0.979384 0.0968106 -0.177296 0.979384 0.121058 -0.161713 0.979384 0.121061 -0.16172 0.979383 0.142845 -0.142845 0.979383 0.142842 -0.142841 0.979384 0.161716 -0.12106 0.979384 0.161711 -0.121056 0.979385 0.177293 -0.0968088 0.979385 0.17729 -0.0968068 0.979386 0.189262 -0.0705912 0.979386 0.189268 -0.0705941 0.979385 0.197388 -0.0429385 0.979385 0.197383 -0.042937 0.979386 0.201484 -0.0144107 0.979386 0.201496 -0.014413 0.979383 0 0.20151 0.979486 0 0.20151 0.979486 0 0.571784 0.820404 0 0.571784 0.820404 0 0.849199 0.528073 0 0.849199 0.528073 0 0.988691 0.149967 0 0.988691 0.149967 0 -0.201514 0.979486 0 -0.201514 0.979486 0 -0.571775 0.820411 0 -0.571775 0.820411 0 -0.849199 0.528073 0 -0.849199 0.528073 0 -0.988691 0.149967 0 -0.988691 0.149967 -0.014411 0.201489 0.979385 -0.0408615 0.571306 0.819719 -0.0606243 0.847637 0.527102 -0.317144 0.898977 0.302091 -0.34553 0.926403 0.14962 -0.23595 0.960143 0.149843 -0.203217 0.934168 0.293313 -0.166863 0.974516 0.149918 -0.0705366 0.986227 0.149601 -0.0705359 0.986228 0.149594 -0.394603 0.906535 0.149944 -0.473854 0.867803 0.149598 -0.473854 0.867808 0.149575 -0.592537 0.791535 0.149572 -0.592537 0.791533 0.149582 -0.673725 0.723626 0.149863 -0.674017 0.674011 0.302342 -0.934163 0.203212 0.293334 -0.723625 0.673721 0.149889 -0.79153 0.592534 0.149611 -0.791531 0.592538 0.149594 -0.867803 0.473857 0.149593 -0.867802 0.473855 0.149603 -0.906538 0.394592 0.149956 -0.90325 0.336894 0.265786 -0.932402 0.328934 0.149765 -0.960145 0.235952 0.14983 -0.974509 0.166864 0.149962 -0.986221 0.0705352 0.149641 -0.986228 0.0705409 0.149594 -0.0606251 0.847631 0.527111 -0.180639 0.830377 0.527108 -0.180639 0.830388 0.527091 -0.296977 0.796227 0.527093 -0.296978 0.796233 0.527084 -0.40727 0.745867 0.527081 -0.407263 0.745846 0.527114 -0.509264 0.680294 0.527116 -0.50926 0.680285 0.527131 -0.60089 0.600884 0.527133 -0.600913 0.60092 0.527067 -0.680318 0.509284 0.527064 -0.680294 0.509257 0.527121 -0.745841 0.407259 0.527125 -0.745845 0.407263 0.527117 -0.796213 0.296971 0.527118 -0.796215 0.296973 0.527113 -0.830375 0.180634 0.527114 -0.830391 0.180642 0.527085 -0.847647 0.0606288 0.527085 -0.847637 0.0606259 0.527102 -0.0408614 0.571308 0.819718 -0.12175 0.559677 0.819718 -0.121749 0.559667 0.819726 -0.200158 0.536647 0.819724 -0.200158 0.536647 0.819724 -0.274494 0.502697 0.819725 -0.274494 0.502699 0.819724 -0.343244 0.458516 0.819724 -0.343248 0.458523 0.819718 -0.405005 0.40501 0.819718 -0.40499 0.40499 0.819736 -0.458504 0.343229 0.819736 -0.458517 0.343242 0.819724 -0.502699 0.274494 0.819724 -0.502713 0.274505 0.819711 -0.536665 0.200165 0.81971 -0.536669 0.200168 0.819707 -0.559695 0.121755 0.819706 -0.55968 0.121749 0.819717 -0.571309 0.040862 0.819717 -0.571306 0.0408614 0.819719 -0.0144109 0.201492 0.979384 -0.0429398 0.19739 0.979384 -0.0429401 0.197393 0.979384 -0.0705944 0.189272 0.979384 -0.0705938 0.18927 0.979384 -0.0968116 0.177297 0.979384 -0.0968097 0.177292 0.979385 -0.121056 0.161711 0.979385 -0.121057 0.161712 0.979385 -0.142838 0.142838 0.979385 -0.142841 0.142842 0.979384 -0.161716 0.121059 0.979384 -0.16172 0.121063 0.979383 -0.177304 0.0968162 0.979383 -0.17729 0.0968068 0.979386 -0.189262 0.0705912 0.979386 -0.189268 0.0705941 0.979385 -0.197388 0.0429385 0.979385 -0.197383 0.042937 0.979386 -0.201484 0.0144107 0.979386 -0.201482 0.0144102 0.979386 -0.201482 -0.0144105 0.979386 -0.571306 -0.0408618 0.819719 -0.847637 -0.060628 0.527102 -0.89898 -0.317144 0.302082 -0.926405 -0.34553 0.149608 -0.960144 -0.235951 0.149834 -0.934163 -0.203212 0.293334 -0.974509 -0.166864 0.149962 -0.986221 -0.0705404 0.149641 -0.986228 -0.0705357 0.149594 -0.906538 -0.394592 0.149956 -0.867801 -0.473856 0.149604 -0.867803 -0.473856 0.149593 -0.791532 -0.592536 0.149594 -0.791529 -0.592536 0.149611 -0.723625 -0.673721 0.149889 -0.674017 -0.674011 0.302342 -0.203216 -0.934163 0.293329 -0.673725 -0.723626 0.149863 -0.592535 -0.791535 0.149582 -0.592537 -0.791536 0.149572 -0.473859 -0.867805 0.149575 -0.473852 -0.867802 0.149614 -0.394595 -0.906535 0.149961 -0.336893 -0.903247 0.265796 -0.328935 -0.932399 0.149783 -0.235953 -0.960142 0.149843 -0.166853 -0.97452 0.1499 -0.070538 -0.98623 0.149583 -0.0705366 -0.986228 0.149594 -0.847647 -0.0606266 0.527085 -0.830392 -0.180638 0.527085 -0.830374 -0.180638 0.527114 -0.796216 -0.296972 0.527113 -0.796212 -0.296972 0.527118 -0.745845 -0.407262 0.527117 -0.745841 -0.40726 0.527125 -0.68029 -0.509263 0.527121 -0.680323 -0.509278 0.527064 -0.600919 -0.600913 0.527067 -0.600889 -0.600894 0.527124 -0.509261 -0.680292 0.52712 -0.509268 -0.680299 0.527105 -0.407265 -0.745854 0.527102 -0.407268 -0.745859 0.527093 -0.296976 -0.796225 0.527096 -0.296978 -0.796227 0.527093 -0.180641 -0.830388 0.527091 -0.18064 -0.830385 0.527095 -0.0606246 -0.84764 0.527097 -0.0606238 -0.847637 0.527102 -0.571309 -0.0408616 0.819717 -0.559679 -0.121751 0.819717 -0.559695 -0.121753 0.819706 -0.536669 -0.200167 0.819707 -0.536665 -0.200166 0.81971 -0.502714 -0.274503 0.819711 -0.502697 -0.274497 0.819724 -0.458519 -0.343239 0.819724 -0.458503 -0.343231 0.819737 -0.404988 -0.404992 0.819735 -0.405003 -0.405003 0.819723 -0.343243 -0.458517 0.819723 -0.343243 -0.458516 0.819724 -0.274494 -0.502699 0.819724 -0.274493 -0.502698 0.819725 -0.200159 -0.536647 0.819724 -0.200163 -0.536654 0.819718 -0.12175 -0.559675 0.81972 -0.121748 -0.559669 0.819724 -0.0408599 -0.5713 0.819724 -0.0408594 -0.571297 0.819725 -0.201484 -0.0144104 0.979386 -0.197383 -0.0429375 0.979386 -0.197388 -0.042938 0.979385 -0.189268 -0.0705934 0.979385 -0.189262 -0.0705918 0.979386 -0.17729 -0.0968085 0.979386 -0.177305 -0.0968146 0.979383 -0.161721 -0.121062 0.979383 -0.161716 -0.12106 0.979384 -0.142842 -0.142842 0.979384 -0.142838 -0.142839 0.979385 -0.121057 -0.161712 0.979385 -0.121058 -0.161713 0.979385 -0.0968105 -0.177296 0.979384 -0.0968114 -0.177297 0.979384 -0.0705943 -0.189269 0.979384 -0.0705923 -0.189265 0.979385 -0.0429386 -0.197386 0.979385 -0.0429399 -0.19739 0.979384 -0.0144108 -0.201492 0.979384 -0.0144109 -0.201493 0.979384 -0.201503 0 0.979488 -0.201503 0 0.979488 -0.571784 0 0.820404 -0.571784 0 0.820404 -0.849199 0 0.528073 -0.849199 0 0.528073 -0.988691 0 0.149967 -0.988691 0 0.149967 -0.201503 0 0.979488 -0.201503 0 0.979488 -0.571784 0 0.820404 -0.571784 0 0.820404 -0.849199 0 0.528073 -0.849199 0 0.528073 -0.988691 0 0.149967 -0.988691 0 0.149967 0 0.984041 -0.177942 0 0.984041 -0.177942 0 0.932797 -0.360401 0 0.932797 -0.360401 0 0.879852 -0.475248 0 0.879852 -0.475248 0 0.774394 -0.632703 0 0.774394 -0.632703 0 0.591309 -0.806445 0 0.591309 -0.806445 0 0.428543 -0.903522 0 0.428543 -0.903522 0 0.311084 -0.950383 0 0.311084 -0.950383 0 0.126202 -0.992005 0 0.126202 -0.992005 -0.952207 0.248483 -0.177644 -0.893673 0.411987 -0.17781 -0.807324 0.562649 -0.177916 -0.497616 0.849012 -0.177642 -0.340603 0.92324 -0.177813 -0.172992 0.968722 -0.177908 -0.126196 0.00993097 -0.991956 -0.00993208 0.126196 -0.991956 -0.00993172 0.126195 -0.991956 -0.0244753 0.310991 -0.950098 -0.0511279 0.367066 -0.928789 -0.126195 0.00993169 -0.991956 -0.310991 0.0244752 -0.950098 -0.367064 0.0511268 -0.928789 -0.428302 0.0337046 -0.903007 -0.590669 0.0464818 -0.805574 -0.590666 0.0464836 -0.805576 -0.772966 0.0608301 -0.631525 -0.0891464 0.904034 -0.418062 -0.0690781 0.87775 -0.474113 -0.0608311 0.772958 -0.631534 -0.060833 0.77296 -0.631531 -0.0464865 0.59067 -0.805573 -0.046486 0.590669 -0.805574 -0.0337073 0.428299 -0.903008 -0.0772149 0.981103 -0.17741 -0.0772144 0.981103 -0.177411 -0.0732156 0.930294 -0.359434 -0.248472 0.95221 -0.177646 -0.228575 0.952088 -0.203178 -0.212115 0.883528 -0.417594 -0.212116 0.883529 -0.417593 -0.181001 0.753927 -0.631533 -0.181 0.753926 -0.631534 -0.138314 0.576125 -0.805574 -0.138316 0.576126 -0.805573 -0.0867352 0.361277 -0.928416 -0.0867339 0.361276 -0.928416 -0.0295506 0.123088 -0.991956 -0.0295506 0.123088 -0.991956 -0.41199 0.893671 -0.177808 -0.37401 0.902943 -0.211683 -0.347717 0.839466 -0.417601 -0.347722 0.839467 -0.417593 -0.296717 0.716332 -0.631528 -0.296713 0.71633 -0.631533 -0.226737 0.547392 -0.805576 -0.22674 0.547394 -0.805574 -0.142184 0.343261 -0.928416 -0.142184 0.343261 -0.928416 -0.0484426 0.11695 -0.991956 -0.048442 0.11695 -0.991956 -0.562675 0.807308 -0.177906 -0.511603 0.834854 -0.203179 -0.474761 0.774735 -0.417597 -0.474758 0.774735 -0.417601 -0.405119 0.661095 -0.631532 -0.405124 0.661096 -0.631528 -0.309581 0.505186 -0.805572 -0.309574 0.505184 -0.805576 -0.194129 0.316792 -0.928416 -0.194131 0.316793 -0.928415 -0.0661409 0.107932 -0.991956 -0.0661413 0.107932 -0.991956 -0.0822111 0.0962562 -0.991956 -0.0822103 0.0962561 -0.991956 -0.241297 0.282523 -0.928416 -0.2413 0.282523 -0.928415 -0.3848 0.450538 -0.805571 -0.384792 0.450536 -0.805576 -0.503547 0.589583 -0.631532 -0.503547 0.589583 -0.631532 -0.590106 0.690932 -0.417597 -0.59011 0.690932 -0.417592 -0.639146 0.748344 -0.177408 -0.639143 0.748346 -0.177414 -0.0962557 0.0822104 -0.991956 -0.0962566 0.0822104 -0.991956 -0.282526 0.241298 -0.928415 -0.282521 0.241298 -0.928416 -0.450533 0.384794 -0.805577 -0.450541 0.384795 -0.805572 -0.589583 0.503547 -0.631532 -0.589581 0.503547 -0.631534 -0.690933 0.590109 -0.417592 -0.69093 0.59011 -0.417595 -0.748344 0.639145 -0.177414 -0.748341 0.639146 -0.177418 -0.849013 0.497615 -0.177643 -0.834857 0.511599 -0.203177 -0.774741 0.47476 -0.417588 -0.774735 0.474762 -0.417595 -0.661089 0.405119 -0.631537 -0.661093 0.405119 -0.631534 -0.505187 0.309579 -0.805573 -0.505189 0.309579 -0.805571 -0.316794 0.194131 -0.928415 -0.31679 0.194131 -0.928416 -0.107931 0.0661409 -0.991956 -0.107932 0.0661408 -0.991956 -0.92324 0.340604 -0.17781 -0.902943 0.374012 -0.211681 -0.839467 0.347719 -0.417596 -0.839473 0.347715 -0.417587 -0.716335 0.296711 -0.631528 -0.716324 0.296715 -0.631538 -0.54739 0.226739 -0.805577 -0.547397 0.226737 -0.805572 -0.343262 0.142182 -0.928416 -0.343263 0.142182 -0.928415 -0.116951 0.0484419 -0.991956 -0.116949 0.0484425 -0.991956 -0.968723 0.172977 -0.177915 -0.952086 0.228574 -0.203191 -0.883528 0.212115 -0.417594 -0.883528 0.212116 -0.417595 -0.753932 0.181003 -0.631525 -0.75393 0.181004 -0.631528 -0.576124 0.138317 -0.805574 -0.576119 0.138319 -0.805577 -0.361274 0.0867371 -0.928417 -0.361278 0.0867354 -0.928415 -0.123089 0.0295511 -0.991956 -0.123089 0.0295511 -0.991956 -0.772956 0.0608377 -0.631536 -0.877762 0.0690867 -0.47409 -0.904034 0.0891465 -0.418063 -0.930289 0.0732191 -0.359446 -0.981102 0.0772183 -0.177417 -0.981103 0.0772149 -0.177411 0.248472 0.95221 -0.177646 0.41199 0.893671 -0.177808 0.562659 0.807317 -0.177914 0.849013 0.497615 -0.177643 0.968723 0.172977 -0.177915 0.00993204 0.126195 -0.991956 0.126197 0.00993258 -0.991955 0.126196 0.00993176 -0.991956 0.310991 0.0244752 -0.950098 0.367064 0.0511268 -0.928789 0.00993175 0.126196 -0.991956 0.0244753 0.310991 -0.950098 0.0511279 0.367066 -0.928789 0.0337073 0.428299 -0.903008 0.046486 0.59067 -0.805573 0.0464865 0.590669 -0.805574 0.0608329 0.772958 -0.631534 0.904034 0.0891465 -0.418063 0.877762 0.0690867 -0.47409 0.772965 0.0608383 -0.631525 0.772957 0.0608294 -0.631536 0.590668 0.0464838 -0.805574 0.590673 0.0464879 -0.805571 0.42829 0.0337079 -0.903012 0.11695 0.0484432 -0.991956 0.116949 0.0484413 -0.991956 0.343258 0.14218 -0.928417 0.343261 0.142186 -0.928415 0.547395 0.226742 -0.805572 0.547391 0.226734 -0.805577 0.716334 0.296712 -0.631528 0.716333 0.29671 -0.63153 0.839469 0.347714 -0.417596 0.839471 0.34772 -0.417587 0.981102 0.0772148 -0.177417 0.981103 0.0772184 -0.177411 0.930289 0.0732191 -0.359446 0.952207 0.248483 -0.177644 0.952086 0.228574 -0.203191 0.883528 0.212115 -0.417595 0.883528 0.212116 -0.417594 0.75393 0.181003 -0.631528 0.753932 0.181005 -0.631525 0.576127 0.138317 -0.805572 0.576124 0.138314 -0.805574 0.361273 0.0867334 -0.928417 0.361274 0.0867345 -0.928417 0.123089 0.0295511 -0.991956 0.123089 0.0295511 -0.991956 0.909224 0.376613 -0.177411 0.880569 0.405962 -0.244526 0.923245 0.34059 -0.17781 0.807324 0.562649 -0.177916 0.834857 0.511599 -0.203177 0.774738 0.474758 -0.417595 0.774738 0.474764 -0.417587 0.661097 0.405124 -0.631527 0.661096 0.40512 -0.63153 0.505183 0.309577 -0.805576 0.505182 0.309575 -0.805577 0.316791 0.194129 -0.928416 0.316793 0.194133 -0.928415 0.107932 0.0661411 -0.991956 0.107931 0.0661405 -0.991956 0.096257 0.0822099 -0.991956 0.0962572 0.0822109 -0.991956 0.282523 0.241296 -0.928416 0.282523 0.241296 -0.928416 0.450536 0.384792 -0.805576 0.450537 0.384797 -0.805573 0.589583 0.503554 -0.631527 0.589582 0.503547 -0.631533 0.690932 0.590108 -0.417595 0.690932 0.590111 -0.417592 0.748343 0.639144 -0.177418 0.748342 0.639147 -0.177414 0.0822107 0.0962573 -0.991956 0.0822107 0.0962565 -0.991956 0.241296 0.282522 -0.928416 0.241296 0.282523 -0.928416 0.384796 0.450539 -0.805573 0.384795 0.450535 -0.805575 0.50355 0.589579 -0.631533 0.50355 0.589586 -0.631526 0.590108 0.690934 -0.417592 0.590109 0.69093 -0.417597 0.639145 0.748344 -0.177414 0.639146 0.748342 -0.177417 0.497616 0.849012 -0.177642 0.511603 0.834854 -0.203179 0.47476 0.774733 -0.417601 0.474759 0.774737 -0.417597 0.405121 0.661097 -0.631528 0.405121 0.661098 -0.631527 0.309576 0.505183 -0.805576 0.309575 0.505186 -0.805574 0.19413 0.316794 -0.928416 0.19413 0.316791 -0.928416 0.066141 0.107932 -0.991956 0.0661411 0.107932 -0.991956 0.340603 0.92324 -0.177813 0.37401 0.902943 -0.211683 0.347718 0.839469 -0.417593 0.347721 0.839464 -0.417601 0.296716 0.716328 -0.631533 0.296714 0.716333 -0.631528 0.226738 0.547394 -0.805574 0.226739 0.547391 -0.805576 0.142184 0.343261 -0.928416 0.142184 0.343261 -0.928416 0.0484424 0.11695 -0.991956 0.0484422 0.11695 -0.991956 0.172992 0.968722 -0.177908 0.228575 0.952088 -0.203178 0.212115 0.883529 -0.417593 0.212116 0.883528 -0.417594 0.181001 0.753926 -0.631534 0.181 0.753927 -0.631532 0.138315 0.576126 -0.805573 0.138316 0.576124 -0.805574 0.0867349 0.361276 -0.928416 0.0867343 0.361277 -0.928416 0.0295506 0.123088 -0.991956 0.0295506 0.123088 -0.991956 0.0608312 0.77296 -0.631531 0.0690781 0.87775 -0.474113 0.0891464 0.904034 -0.418062 0.0732156 0.930294 -0.359434 0.0772144 0.981103 -0.17741 0.0772149 0.981103 -0.177411 -0.126202 0 -0.992005 -0.188642 -0.0159552 -0.981916 -0.311084 0 -0.950383 -0.428545 0 -0.90352 -0.539068 -0.0159551 -0.842111 -0.591305 0 -0.806448 -0.774391 0 -0.632708 -0.812745 -0.0159577 -0.582401 -0.879864 0 -0.475226 -0.932793 0 -0.360414 -0.970697 -0.0159571 -0.239777 -0.984041 0 -0.177942 0.126203 0 -0.992004 0.126203 0 -0.992004 0.311084 0 -0.950383 0.311084 0 -0.950383 0.428534 0 -0.903526 0.428534 0 -0.903526 0.591312 0 -0.806443 0.591312 0 -0.806443 0.774391 0 -0.632708 0.774391 0 -0.632708 0.879864 0 -0.475226 0.879864 0 -0.475226 0.932793 0 -0.360414 0.932793 0 -0.360414 0.984041 0 -0.177942 0.984041 0 -0.177942 -0.126202 0 -0.992005 -0.188642 0.0159552 -0.981916 -0.311084 0 -0.950383 -0.428545 0 -0.90352 -0.539068 0.0159551 -0.842111 -0.591305 0 -0.806448 -0.774391 0 -0.632708 -0.812745 0.0159577 -0.582401 -0.984041 0 -0.177942 -0.970697 0.0159571 -0.239777 -0.932793 0 -0.360414 -0.879864 0 -0.475226 0.952207 -0.248483 -0.177644 0.893667 -0.412 -0.17781 0.807324 -0.562649 -0.177916 0.497614 -0.849014 -0.177642 0.340599 -0.923241 -0.177813 0.172984 -0.968723 -0.177912 0.126196 -0.0099325 -0.991956 0.00993208 -0.126196 -0.991956 0.00993172 -0.126195 -0.991956 0.0244753 -0.310991 -0.950098 0.0511279 -0.367066 -0.928789 0.126197 -0.00993183 -0.991955 0.310991 -0.0244752 -0.950098 0.367064 -0.0511268 -0.928789 0.42829 -0.0337079 -0.903012 0.590668 -0.0464875 -0.805575 0.590673 -0.0464842 -0.805571 0.772966 -0.0608301 -0.631525 0.0891464 -0.904034 -0.418062 0.0690823 -0.877756 -0.474102 0.0608346 -0.772962 -0.631529 0.060833 -0.77296 -0.631531 0.0464864 -0.590668 -0.805574 0.0464858 -0.590668 -0.805575 0.0337073 -0.428299 -0.903008 0.0772149 -0.981103 -0.177414 0.0772164 -0.981103 -0.177411 0.0732174 -0.930291 -0.35944 0.248477 -0.952209 -0.177646 0.228575 -0.952087 -0.203185 0.212115 -0.883528 -0.417594 0.212116 -0.883529 -0.417593 0.181002 -0.753928 -0.63153 0.181003 -0.753929 -0.631529 0.138315 -0.576124 -0.805574 0.138316 -0.576124 -0.805574 0.0867352 -0.361277 -0.928416 0.0867339 -0.361276 -0.928416 0.0295506 -0.123088 -0.991956 0.0295506 -0.123088 -0.991956 0.411993 -0.89367 -0.177808 0.37401 -0.902943 -0.211686 0.347718 -0.839468 -0.417595 0.347719 -0.839468 -0.417593 0.296714 -0.716331 -0.63153 0.296713 -0.716331 -0.631531 0.226737 -0.547392 -0.805576 0.22674 -0.547394 -0.805574 0.142184 -0.343261 -0.928416 0.142184 -0.343261 -0.928416 0.0484426 -0.11695 -0.991956 0.048442 -0.11695 -0.991956 0.562659 -0.807317 -0.177914 0.511601 -0.834855 -0.20318 0.47476 -0.774736 -0.417597 0.474761 -0.774736 -0.417596 0.405122 -0.661097 -0.631527 0.40512 -0.661096 -0.63153 0.309577 -0.505185 -0.805574 0.309574 -0.505184 -0.805576 0.194129 -0.316793 -0.928416 0.19413 -0.316793 -0.928415 0.0661405 -0.107932 -0.991956 0.0661413 -0.107932 -0.991956 0.0822101 -0.0962566 -0.991956 0.0822112 -0.0962568 -0.991956 0.241298 -0.282523 -0.928416 0.241296 -0.282522 -0.928416 0.384794 -0.450537 -0.805575 0.384797 -0.450537 -0.805573 0.503554 -0.589583 -0.631526 0.503547 -0.589583 -0.631532 0.590106 -0.690932 -0.417597 0.59011 -0.690932 -0.417592 0.639145 -0.748343 -0.177417 0.639147 -0.748342 -0.177414 0.0962576 -0.0822104 -0.991956 0.0962566 -0.0822104 -0.991956 0.282523 -0.241296 -0.928416 0.282523 -0.241296 -0.928416 0.45054 -0.384795 -0.805572 0.450534 -0.384795 -0.805576 0.589579 -0.503551 -0.631533 0.589585 -0.50355 -0.631527 0.690933 -0.590109 -0.417592 0.69093 -0.59011 -0.417595 0.748344 -0.639145 -0.177414 0.748341 -0.639146 -0.177418 0.849013 -0.497615 -0.177643 0.834857 -0.511599 -0.203177 0.774741 -0.47476 -0.417588 0.774735 -0.474762 -0.417595 0.661094 -0.405122 -0.63153 0.661098 -0.405122 -0.631527 0.505181 -0.309576 -0.805577 0.505184 -0.309576 -0.805576 0.316794 -0.194131 -0.928415 0.31679 -0.194131 -0.928416 0.107931 -0.0661409 -0.991956 0.107932 -0.0661408 -0.991956 0.923245 -0.34059 -0.17781 0.902941 -0.374011 -0.211693 0.839467 -0.347719 -0.417596 0.839473 -0.347715 -0.417587 0.716335 -0.296711 -0.631528 0.716333 -0.296711 -0.63153 0.547397 -0.226737 -0.805572 0.547389 -0.226739 -0.805577 0.343257 -0.142184 -0.928417 0.343263 -0.142182 -0.928415 0.116951 -0.0484419 -0.991956 0.116949 -0.0484425 -0.991956 0.968723 -0.172977 -0.177915 0.952086 -0.228574 -0.203191 0.883528 -0.212115 -0.417594 0.883528 -0.212116 -0.417595 0.753932 -0.181003 -0.631525 0.75393 -0.181004 -0.631528 0.576124 -0.138317 -0.805574 0.576127 -0.138315 -0.805572 0.361274 -0.0867336 -0.928417 0.361273 -0.0867342 -0.928418 0.123089 -0.0295511 -0.991956 0.123089 -0.0295511 -0.991956 0.772956 -0.0608377 -0.631536 0.877762 -0.0690867 -0.47409 0.904034 -0.0891465 -0.418063 0.930289 -0.0732191 -0.359446 0.981102 -0.0772183 -0.177417 0.981103 -0.0772149 -0.177411 -0.248477 -0.952209 -0.177646 -0.411993 -0.89367 -0.177808 -0.562675 -0.807308 -0.177906 -0.849013 -0.497615 -0.177643 -0.92324 -0.340604 -0.17781 -0.968723 -0.172977 -0.177915 -0.00993204 -0.126195 -0.991956 -0.126195 -0.00993087 -0.991956 -0.126196 -0.00993176 -0.991956 -0.310991 -0.0244752 -0.950098 -0.367064 -0.0511268 -0.928789 -0.00993175 -0.126196 -0.991956 -0.0244753 -0.310991 -0.950098 -0.0511279 -0.367066 -0.928789 -0.0337073 -0.428299 -0.903008 -0.0464859 -0.590668 -0.805574 -0.0464863 -0.590668 -0.805575 -0.0608331 -0.772962 -0.631529 -0.904034 -0.0891465 -0.418063 -0.877762 -0.0690867 -0.47409 -0.772965 -0.0608383 -0.631525 -0.772957 -0.0608294 -0.631536 -0.590668 -0.0464838 -0.805574 -0.590666 -0.0464815 -0.805576 -0.428302 -0.0337046 -0.903007 -0.981102 -0.0772148 -0.177417 -0.981103 -0.0772184 -0.177411 -0.930289 -0.0732191 -0.359446 -0.952207 -0.248483 -0.177644 -0.952086 -0.228574 -0.203191 -0.883528 -0.212115 -0.417595 -0.883528 -0.212116 -0.417594 -0.75393 -0.181003 -0.631528 -0.753932 -0.181005 -0.631525 -0.57612 -0.138316 -0.805577 -0.576123 -0.13832 -0.805574 -0.361277 -0.0867379 -0.928416 -0.361274 -0.0867345 -0.928417 -0.123089 -0.0295511 -0.991956 -0.123089 -0.0295511 -0.991956 -0.893673 -0.411987 -0.177809 -0.902943 -0.374012 -0.211681 -0.839471 -0.34772 -0.417587 -0.839469 -0.347714 -0.417596 -0.716327 -0.296708 -0.631538 -0.716332 -0.296718 -0.631528 -0.547395 -0.226741 -0.805573 -0.547391 -0.226735 -0.805577 -0.343263 -0.142183 -0.928415 -0.343262 -0.142182 -0.928416 -0.116949 -0.0484413 -0.991956 -0.11695 -0.0484432 -0.991956 -0.807324 -0.562649 -0.177916 -0.834857 -0.511599 -0.203177 -0.774738 -0.474758 -0.417595 -0.774738 -0.474764 -0.417587 -0.661091 -0.405121 -0.631534 -0.66109 -0.405117 -0.631537 -0.505188 -0.30958 -0.805572 -0.505187 -0.309578 -0.805573 -0.316791 -0.194129 -0.928416 -0.316793 -0.194133 -0.928415 -0.107932 -0.0661411 -0.991956 -0.107931 -0.0661405 -0.991956 -0.0962563 -0.0822109 -0.991956 -0.0962561 -0.08221 -0.991956 -0.282523 -0.241296 -0.928416 -0.282524 -0.2413 -0.928415 -0.450538 -0.384799 -0.805572 -0.450536 -0.384791 -0.805576 -0.589582 -0.503546 -0.631534 -0.589582 -0.503547 -0.631533 -0.690932 -0.590108 -0.417595 -0.690932 -0.590111 -0.417592 -0.748343 -0.639144 -0.177418 -0.748342 -0.639147 -0.177414 -0.0822106 -0.0962557 -0.991956 -0.0822107 -0.0962561 -0.991956 -0.241299 -0.282524 -0.928415 -0.241299 -0.282522 -0.928416 -0.384795 -0.450533 -0.805576 -0.384796 -0.450541 -0.805571 -0.503547 -0.589582 -0.631532 -0.503547 -0.589583 -0.631532 -0.590108 -0.690934 -0.417592 -0.590109 -0.69093 -0.417597 -0.639145 -0.748344 -0.177414 -0.639143 -0.748346 -0.177408 -0.497614 -0.849014 -0.177642 -0.511601 -0.834855 -0.20318 -0.47476 -0.774736 -0.417596 -0.474761 -0.774736 -0.417597 -0.405121 -0.661095 -0.63153 -0.405122 -0.661093 -0.631532 -0.309578 -0.505181 -0.805576 -0.309577 -0.505189 -0.805572 -0.19413 -0.316794 -0.928416 -0.19413 -0.316793 -0.928416 -0.0661408 -0.107932 -0.991956 -0.0661409 -0.107932 -0.991956 -0.340599 -0.923241 -0.177813 -0.37401 -0.902943 -0.211686 -0.347718 -0.839469 -0.417593 -0.347719 -0.839468 -0.417595 -0.296714 -0.716331 -0.631531 -0.296714 -0.716332 -0.63153 -0.226738 -0.547394 -0.805574 -0.226739 -0.547391 -0.805576 -0.142184 -0.343261 -0.928416 -0.142184 -0.343261 -0.928416 -0.0484424 -0.11695 -0.991956 -0.0484422 -0.11695 -0.991956 -0.172984 -0.968723 -0.177912 -0.228575 -0.952087 -0.203185 -0.212115 -0.883529 -0.417593 -0.212116 -0.883528 -0.417594 -0.181002 -0.753929 -0.63153 -0.181002 -0.753928 -0.63153 -0.138315 -0.576124 -0.805574 -0.138316 -0.576124 -0.805574 -0.0867349 -0.361276 -0.928416 -0.0867343 -0.361277 -0.928416 -0.0295506 -0.123088 -0.991956 -0.0295506 -0.123088 -0.991956 -0.0608345 -0.77296 -0.631531 -0.0690823 -0.877756 -0.474102 -0.0891464 -0.904034 -0.418062 -0.0732174 -0.930291 -0.35944 -0.0772164 -0.981102 -0.177414 -0.0772149 -0.981103 -0.177411 0 -0.984041 -0.177942 0 -0.984041 -0.177942 0 -0.932795 -0.360407 0 -0.932795 -0.360407 0 -0.879858 -0.475237 0 -0.879858 -0.475237 0 -0.774394 -0.632703 0 -0.774394 -0.632703 0 -0.591307 -0.806447 0 -0.591307 -0.806447 0 -0.428543 -0.903522 0 -0.428543 -0.903522 0 -0.311084 -0.950383 0 -0.311084 -0.950383 0 -0.126202 -0.992005 0 -0.126202 -0.992005 -0.130527 0.99144 -0.00297081 -0.382682 0.923875 -0.00318914 -0.333139 0.942878 0.000227753 -0.169001 0.985616 -0.000247716 -0.699577 0.714557 0 -0.62822 0.778035 -0.000802315 -0.60876 0.79335 -0.00267348 -0.530317 0.8478 0 -0.456516 0.889715 0 -0.757639 0.652674 0 -0.793348 0.60876 -0.00332794 -0.836352 0.548193 0 -0.879831 0.475286 0 -0.923878 0.38268 -0.00229665 -0.927887 0.372859 -0.00143588 -0.991438 0.130531 -0.00338746 -0.981127 0.193364 0 -0.961202 0.275847 0 -0.972036 -0.234833 0 -0.991898 -0.127023 -0.00214792 -0.991442 -0.130532 -0.00184106 -0.999775 -0.0212285 0 -0.997973 0.0636401 0 -0.948627 -0.316398 0 -0.923875 -0.382679 -0.0033679 -0.899205 -0.437528 0 -0.858855 -0.512219 0 -0.793352 -0.608762 -0.00130606 -0.803997 -0.594627 -0.00293908 -0.608759 -0.793349 -0.00326854 -0.66861 -0.743613 0 -0.72925 -0.684247 0 -0.296197 -0.955127 0 -0.411898 -0.911222 -0.00380812 -0.382683 -0.923879 -0.000692737 -0.4939 -0.869519 0 -0.56582 -0.824529 0 -0.214139 -0.976803 0 -0.130527 -0.99144 -0.00308982 -0.0848059 -0.996397 0 0.0848059 -0.996397 0 0.130527 -0.99144 -0.00308982 0.214139 -0.976803 0 0.382683 -0.923879 -0.000692736 0.411898 -0.911222 -0.00380812 0.296197 -0.955127 0 0.608759 -0.793349 -0.00326854 0.56582 -0.824529 0 0.4939 -0.869519 0 0.858855 -0.512219 0 0.804 -0.594629 -0.00110878 0.79335 -0.608761 -0.00249525 0.72925 -0.684247 0 0.66861 -0.743613 0 0.89921 -0.437518 0 0.923875 -0.382679 -0.00336725 0.948622 -0.316411 0 0.991443 -0.130525 -0.00184095 0.991899 -0.127012 -0.00214813 0.972036 -0.234833 0 0.991439 0.130525 -0.00338782 0.997974 0.0636262 0 0.999775 -0.0212285 0 0.879831 0.475286 0 0.927885 0.372858 -0.00253317 0.923879 0.382681 -0.00158371 0.961202 0.275847 0 0.981127 0.193364 0 0.836352 0.548193 0 0.793348 0.60876 -0.00332794 0.757639 0.652674 0 0.699577 0.714557 0 0.608762 0.793353 -0.00100937 0.628217 0.778031 -0.00336357 0.382682 0.923875 -0.00318914 0.456516 0.889715 0 0.530317 0.8478 0 -0.0424407 0.999099 0 0.0424407 0.999099 0 0.130527 0.99144 -0.0029708 0.169001 0.985616 -0.000247716 0.333139 0.942878 0.000227753 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.212486 -0.969264 -0.124004 0.290515 -0.936802 -0.194944 0.404043 -0.893843 -0.194409 0.404043 -0.893843 -0.194409 0.48441 -0.852813 -0.19508 0.550519 -0.814523 -0.182979 0.555012 -0.808779 -0.19452 0.678738 -0.70818 -0.194412 0.662306 -0.736601 -0.137 0.715253 -0.671113 -0.194989 0.788661 -0.583284 -0.194408 0.788655 -0.583288 -0.194419 0.842354 -0.502379 -0.195076 0.879375 -0.443369 -0.17356 0.882015 -0.429152 -0.194624 0.937922 -0.287236 -0.194417 0.937903 -0.312836 -0.149908 0.953371 -0.230324 -0.195027 0.972976 -0.124589 -0.194408 0.972972 -0.124598 -0.194424 0.980571 -0.0208207 -0.195058 0.985201 0.0418462 -0.166214 0.978873 0.0624085 -0.194712 0.958902 0.206663 -0.194416 0.968045 0.190786 -0.162754 0.942738 0.270548 -0.195063 0.910183 0.365745 -0.194416 0.910183 0.365742 -0.19442 0.862938 0.46616 -0.195022 0.84043 0.517474 -0.16093 0.820332 0.537692 -0.194788 0.736348 0.648071 -0.194413 0.745882 0.642546 -0.175485 0.686137 0.700829 -0.195077 0.616234 0.763191 -0.194411 0.616235 0.763189 -0.194416 0.520139 0.831529 -0.194975 0.481588 0.862081 -0.157761 0.165776 0.96681 -0.194413 0.326782 0.924888 -0.194412 0.326782 0.924887 -0.194414 0.447765 0.87266 -0.194859 0.0421468 0.992181 -0.117476 0 0.98092 -0.194413 0.165777 0.96681 -0.194414 -0.326782 0.924888 -0.194412 -0.165777 0.96681 -0.194413 -0.165776 0.96681 -0.194414 -0.0416267 0.979935 -0.19492 -0.452611 0.882105 -0.130514 -0.47839 0.856356 -0.194413 -0.326782 0.924888 -0.194414 -0.520139 0.831529 -0.194975 -0.616233 0.76319 -0.194416 -0.616236 0.763189 -0.194411 -0.686137 0.700829 -0.195076 -0.738681 0.650124 -0.178016 -0.743159 0.6402 -0.194572 -0.835282 0.514304 -0.194413 -0.8277 0.542522 -0.143464 -0.862938 0.46616 -0.195022 -0.910182 0.365744 -0.194421 -0.910184 0.365742 -0.194416 -0.942738 0.270548 -0.195063 -0.963387 0.207629 -0.169634 -0.962357 0.189665 -0.194669 -0.980036 0.0416268 -0.194416 -0.985704 0.0628577 -0.156325 -0.980574 -0.0208208 -0.19504 -0.972976 -0.124599 -0.194406 -0.972975 -0.124598 -0.194408 -0.953371 -0.230324 -0.195027 -0.943331 -0.288892 -0.163304 -0.930466 -0.310341 -0.194736 -0.875892 -0.441613 -0.194401 -0.886251 -0.431226 -0.169125 -0.842354 -0.502379 -0.195076 -0.788659 -0.583283 -0.194419 -0.788657 -0.583289 -0.194408 -0.715253 -0.671113 -0.194989 -0.683129 -0.712761 -0.159082 -0.655799 -0.729364 -0.194824 -0.549289 -0.812703 -0.194412 -0.556389 -0.810786 -0.18182 -0.48441 -0.852813 -0.19508 -0.404043 -0.893843 -0.194409 -0.404043 -0.893843 -0.194409 -0.290515 -0.936802 -0.194944 -0.248856 -0.955737 -0.156966 0.247172 -0.949267 -0.194417 0.0831879 -0.977385 -0.194416 0.0831877 -0.977385 -0.194416 -0.0831878 -0.977385 -0.194416 -0.0831877 -0.977385 -0.194416 -0.210032 -0.958072 -0.194895 -0.0705921 -0.829396 -0.554183 -0.209746 -0.805536 -0.554183 -0.209747 -0.805535 -0.554184 -0.342862 -0.758502 -0.554185 -0.342863 -0.758499 -0.554188 -0.466119 -0.689643 -0.554189 -0.466118 -0.689648 -0.554184 -0.575966 -0.600952 -0.554184 -0.575966 -0.600949 -0.554187 -0.669241 -0.494967 -0.554188 -0.669242 -0.49497 -0.554184 -0.743267 -0.374746 -0.554184 -0.743266 -0.374745 -0.554186 -0.795906 -0.243744 -0.554186 -0.795906 -0.243744 -0.554186 -0.82565 -0.105733 -0.554187 -0.825648 -0.105731 -0.554189 -0.831641 0.0353285 -0.554189 -0.831646 0.035324 -0.554182 -0.813712 0.175374 -0.554182 -0.813715 0.175372 -0.554178 -0.772372 0.310366 -0.554178 -0.772374 0.310365 -0.554177 -0.708813 0.43643 -0.554178 -0.708809 0.436431 -0.554182 -0.624856 0.549942 -0.554183 -0.624853 0.549942 -0.554186 -0.522925 0.647632 -0.554186 -0.52293 0.647633 -0.55418 -0.405957 0.726693 -0.554181 -0.405956 0.726692 -0.554182 -0.277302 0.784847 -0.554183 -0.277302 0.784847 -0.554183 -0.140676 0.820421 -0.554183 -0.140676 0.820422 -0.554183 0 0.832394 -0.554184 0 0.832394 -0.554184 0.140676 0.820422 -0.554183 0.140676 0.820421 -0.554183 0.277302 0.784847 -0.554183 0.277302 0.784847 -0.554183 0.405956 0.726692 -0.554182 0.405956 0.726693 -0.554181 0.522927 0.647636 -0.55418 0.522928 0.64763 -0.554186 0.624854 0.549941 -0.554186 0.624855 0.549944 -0.554182 0.70881 0.436429 -0.554182 0.708811 0.436433 -0.554178 0.772373 0.310366 -0.554177 0.772373 0.310365 -0.554179 0.813714 0.175374 -0.554178 0.813712 0.175371 -0.554182 0.831646 0.0353287 -0.554182 0.831641 0.0353237 -0.554189 0.825648 -0.105733 -0.554189 0.82565 -0.105732 -0.554187 0.795906 -0.243744 -0.554186 0.795906 -0.243744 -0.554186 0.743266 -0.374746 -0.554186 0.743267 -0.374745 -0.554184 0.669243 -0.494968 -0.554184 0.66924 -0.494968 -0.554188 0.575964 -0.600951 -0.554187 0.575967 -0.600951 -0.554184 0.466121 -0.689646 -0.554184 0.466116 -0.689645 -0.554189 0.342861 -0.7585 -0.554188 0.342864 -0.758501 -0.554185 0.209746 -0.805535 -0.554184 0.209747 -0.805536 -0.554183 0.0705921 -0.829396 -0.554183 0.0705921 -0.829396 -0.554183 -0.0705921 -0.829396 -0.554183 -0.0472336 -0.554954 -0.830539 -0.140343 -0.538988 -0.830539 -0.140342 -0.538989 -0.830539 -0.229412 -0.507519 -0.830539 -0.229412 -0.50752 -0.830538 -0.311884 -0.461447 -0.830539 -0.311884 -0.461446 -0.83054 -0.385381 -0.4021 -0.83054 -0.385381 -0.4021 -0.83054 -0.447793 -0.331186 -0.83054 -0.447792 -0.331184 -0.830542 -0.49732 -0.250744 -0.830542 -0.49732 -0.250743 -0.830543 -0.532543 -0.163086 -0.830543 -0.532547 -0.163091 -0.830539 -0.552449 -0.0707464 -0.830539 -0.55245 -0.0707472 -0.830539 -0.556459 0.0236414 -0.830538 -0.556464 0.0236388 -0.830535 -0.544465 0.11734 -0.830535 -0.544456 0.117343 -0.830541 -0.516794 0.207667 -0.830541 -0.516796 0.207667 -0.83054 -0.474268 0.292016 -0.83054 -0.474267 0.292016 -0.83054 -0.418092 0.36797 -0.83054 -0.418096 0.36797 -0.830538 -0.349896 0.433334 -0.830539 -0.349889 0.433331 -0.830543 -0.271623 0.486231 -0.830542 -0.271627 0.486233 -0.83054 -0.185546 0.525145 -0.830539 -0.185544 0.525144 -0.83054 -0.0941262 0.548947 -0.83054 -0.094127 0.548948 -0.83054 0 0.55696 -0.830539 0 0.55696 -0.830539 0.0941264 0.548948 -0.83054 0.0941268 0.548947 -0.83054 0.185545 0.525144 -0.83054 0.185545 0.525146 -0.830539 0.271627 0.486233 -0.83054 0.271627 0.486233 -0.83054 0.349893 0.433335 -0.830539 0.349893 0.433336 -0.830539 0.418095 0.367972 -0.830538 0.418094 0.367968 -0.83054 0.474268 0.292016 -0.83054 0.474268 0.292016 -0.83054 0.516796 0.207668 -0.83054 0.516795 0.207666 -0.830541 0.544457 0.117338 -0.830541 0.544464 0.117345 -0.830535 0.556464 0.0236416 -0.830535 0.556459 0.0236386 -0.830539 0.55245 -0.0707465 -0.830538 0.552449 -0.070747 -0.830539 0.532546 -0.163092 -0.830539 0.53255 -0.163092 -0.830537 0.497328 -0.250743 -0.830538 0.497321 -0.250743 -0.830542 0.447791 -0.331185 -0.830542 0.447794 -0.331185 -0.83054 0.385381 -0.4021 -0.83054 0.385381 -0.4021 -0.83054 0.311883 -0.461446 -0.83054 0.311885 -0.461447 -0.830539 0.229412 -0.507519 -0.830538 0.229412 -0.507519 -0.830539 0.140343 -0.538989 -0.830539 0.140342 -0.538988 -0.830539 0.0472331 -0.554954 -0.830539 0.0472336 -0.554955 -0.830539 -0.0472332 -0.554955 -0.830539 -0.0166019 -0.19506 -0.980651 -0.0493285 -0.189449 -0.980651 -0.0493286 -0.189448 -0.980651 -0.0806355 -0.178386 -0.980651 -0.0806355 -0.178386 -0.980651 -0.109623 -0.162193 -0.980651 -0.109623 -0.162193 -0.980651 -0.135458 -0.141333 -0.980651 -0.135458 -0.141335 -0.980651 -0.157395 -0.11641 -0.980651 -0.157394 -0.116408 -0.980651 -0.174803 -0.0881339 -0.980651 -0.174804 -0.0881341 -0.980651 -0.187184 -0.0573235 -0.980651 -0.187184 -0.0573234 -0.980651 -0.194179 -0.0248655 -0.980651 -0.194181 -0.0248668 -0.98065 -0.195591 0.00830846 -0.98065 -0.195588 0.00830963 -0.980651 -0.191371 0.0412423 -0.980651 -0.191369 0.0412426 -0.980651 -0.181646 0.0729917 -0.980651 -0.181645 0.0729918 -0.980651 -0.166698 0.102639 -0.980651 -0.166699 0.102639 -0.980651 -0.146953 0.129337 -0.980651 -0.146955 0.129337 -0.980651 -0.122983 0.152312 -0.980651 -0.122986 0.152313 -0.98065 -0.0954749 0.170907 -0.98065 -0.0954731 0.170906 -0.980651 -0.0652172 0.184582 -0.980651 -0.0652168 0.184582 -0.980651 -0.0330845 0.192949 -0.980651 -0.0330842 0.192948 -0.980651 0 0.195764 -0.980651 0 0.195764 -0.980651 0.0330844 0.192948 -0.980651 0.0330843 0.192949 -0.980651 0.0652171 0.184582 -0.980651 0.065217 0.184582 -0.980651 0.095474 0.170905 -0.980651 0.095474 0.170905 -0.980651 0.122983 0.152312 -0.980651 0.122983 0.152312 -0.980651 0.146955 0.129337 -0.980651 0.146956 0.129338 -0.980651 0.1667 0.102643 -0.980651 0.166698 0.102639 -0.980651 0.181646 0.07299 -0.980651 0.181649 0.0729934 -0.980651 0.191372 0.0412444 -0.980651 0.19137 0.0412429 -0.980651 0.195588 0.00830834 -0.980651 0.195591 0.00830975 -0.98065 0.194181 -0.0248658 -0.98065 0.194179 -0.0248665 -0.980651 0.187184 -0.0573234 -0.980651 0.18718 -0.057324 -0.980652 0.174801 -0.0881325 -0.980651 0.174804 -0.0881326 -0.980651 0.157394 -0.116409 -0.980651 0.157396 -0.116409 -0.980651 0.135459 -0.141334 -0.980651 0.135457 -0.141334 -0.980651 0.109623 -0.162193 -0.980651 0.109623 -0.162193 -0.980651 0.0806356 -0.178386 -0.980651 0.0806354 -0.178386 -0.980651 0.0493282 -0.189448 -0.980651 0.0493289 -0.189449 -0.980651 0.0166023 -0.19506 -0.980651 0.0166018 -0.195059 -0.980651 -0.0166022 -0.195059 -0.980651 0.258822 0.965925 0 0.258822 0.965925 0 0.422618 0.906308 0 0.422618 0.906308 0 0.573575 0.819153 0 0.573575 0.819153 0 0.707107 0.707107 0 0.707107 0.707107 0 0.819152 0.573577 0 0.819152 0.573577 0 0.906312 0.42261 0 0.906312 0.42261 0 0.965922 0.258833 0 0.965922 0.258833 0 0.996196 0.0871442 0 0.996196 0.0871442 0 0.996196 -0.0871442 0 0.996196 -0.0871442 0 0.965922 -0.258833 0 0.965922 -0.258833 0 0.906312 -0.42261 0 0.906312 -0.42261 0 0.819152 -0.573577 0 0.819152 -0.573577 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.573575 -0.819153 0 0.573575 -0.819153 0 0.422618 -0.906308 0 0.422618 -0.906308 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.0871523 -0.996195 0 0.0871523 -0.996195 0 -0.0871523 -0.996195 0 -0.0871523 -0.996195 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.422618 -0.906308 0 -0.422618 -0.906308 0 -0.573575 -0.819153 0 -0.573575 -0.819153 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.819152 -0.573577 0 -0.819152 -0.573577 0 -0.906305 -0.422624 0 -0.906305 -0.422624 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.996196 -0.0871442 0 -0.996196 -0.0871442 0 -0.996196 0.0871442 0 -0.996196 0.0871442 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.906305 0.422624 0 -0.906305 0.422624 0 -0.819152 0.573577 0 -0.819152 0.573577 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.573575 0.819153 0 -0.573575 0.819153 0 -0.422618 0.906308 0 -0.422618 0.906308 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.0871523 0.996195 0 -0.0871523 0.996195 0 0.0871523 0.996195 0 0.0871523 0.996195 0 -0.222426 0.974516 -0.0290719 -0.623227 0.781501 -0.0290702 -0.532035 0.846722 0 -0.330279 0.943883 0 -0.900591 0.433695 -0.0290729 -0.846724 0.532033 0 -0.707104 0.70711 0 -0.999577 0 -0.0290747 -0.993711 0.111978 0 -0.943888 0.330267 0 -0.900591 -0.433695 -0.0290729 -0.943888 -0.330267 0 -0.993711 -0.111977 0 -0.623227 -0.781501 -0.0290702 -0.707104 -0.70711 0 -0.846724 -0.532033 0 -0.222426 -0.974516 -0.0290719 -0.330279 -0.943883 0 -0.532035 -0.846722 0 0.222426 -0.974516 -0.0290719 0.111961 -0.993713 0 -0.111961 -0.993713 0 0.623227 -0.781501 -0.0290702 0.532035 -0.846722 0 0.330279 -0.943883 0 0.900591 -0.433695 -0.0290729 0.846724 -0.532033 0 0.707104 -0.70711 0 0.999577 0 -0.0290747 0.993711 -0.111977 0 0.943888 -0.330267 0 0.900591 0.433695 -0.0290729 0.943888 0.330267 0 0.993711 0.111978 0 0.623227 0.781501 -0.0290702 0.707104 0.70711 0 0.846724 0.532033 0 -0.111961 0.993713 0 0.111961 0.993713 0 0.222426 0.974516 -0.0290719 0.330279 0.943883 0 0.532035 0.846722 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.222426 0.974516 -0.0290719 -0.623227 0.781501 -0.0290702 -0.532035 0.846722 0 -0.330279 0.943883 0 -0.900591 0.433695 -0.0290729 -0.846724 0.532033 0 -0.707104 0.70711 0 -0.999577 0 -0.0290747 -0.993711 0.111977 0 -0.943888 0.330267 0 -0.900591 -0.433695 -0.0290729 -0.943888 -0.330267 0 -0.993711 -0.111978 0 -0.623227 -0.781501 -0.0290702 -0.707104 -0.70711 0 -0.846724 -0.532033 0 -0.222426 -0.974516 -0.0290719 -0.330279 -0.943883 0 -0.532035 -0.846722 0 0.222426 -0.974516 -0.0290719 0.111961 -0.993713 0 -0.111961 -0.993713 0 0.623227 -0.781501 -0.0290702 0.532035 -0.846722 0 0.330279 -0.943883 0 0.900591 -0.433695 -0.0290729 0.846724 -0.532033 0 0.707104 -0.70711 0 0.999577 0 -0.0290747 0.993711 -0.111978 0 0.943888 -0.330267 0 0.900591 0.433695 -0.0290729 0.943888 0.330267 0 0.993711 0.111977 0 0.623227 0.781501 -0.0290702 0.707104 0.70711 0 0.846724 0.532033 0 -0.111961 0.993713 0 0.111961 0.993713 0 0.222426 0.974516 -0.0290719 0.330279 0.943883 0 0.532035 0.846722 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.0291509 -0.258711 0.965515 0.0859886 -0.245737 0.965515 0.085988 -0.245739 0.965515 0.138513 -0.220443 0.965515 0.138513 -0.220443 0.965515 0.184093 -0.184095 0.965515 0.184093 -0.184095 0.965515 0.220445 -0.138511 0.965515 0.220446 -0.138517 0.965514 0.245742 -0.0859896 0.965514 0.24574 -0.0859856 0.965514 0.258713 -0.029149 0.965514 0.258715 -0.0291517 0.965514 0.258715 0.0291492 0.965514 0.258713 0.0291512 0.965514 0.24574 0.0859884 0.965514 0.245744 0.0859867 0.965514 0.220448 0.138513 0.965514 0.220442 0.138515 0.965515 0.184093 0.184095 0.965515 0.184093 0.184095 0.965515 0.138513 0.220443 0.965515 0.138513 0.220443 0.965515 0.0859889 0.245738 0.965515 0.0859876 0.245738 0.965515 0.0291501 0.258711 0.965515 0.029151 0.258712 0.965515 -0.029151 0.258712 0.965515 -0.029151 0.258712 0.965515 -0.0859871 0.24574 0.965514 -0.085988 0.245739 0.965515 -0.138513 0.220443 0.965515 -0.138513 0.220443 0.965515 -0.184093 0.184095 0.965515 -0.184093 0.184095 0.965515 -0.220445 0.138511 0.965515 -0.220446 0.138517 0.965514 -0.245742 0.0859891 0.965514 -0.245741 0.0859858 0.965514 -0.258714 0.029149 0.965514 -0.258715 0.0291514 0.965514 -0.258715 -0.0291492 0.965514 -0.258713 -0.0291514 0.965514 -0.24574 -0.0859888 0.965514 -0.245744 -0.0859867 0.965514 -0.220448 -0.138513 0.965514 -0.220442 -0.138515 0.965515 -0.184093 -0.184095 0.965515 -0.184093 -0.184095 0.965515 -0.138513 -0.220443 0.965515 -0.138513 -0.220443 0.965515 -0.0859867 -0.245739 0.965515 -0.0859884 -0.24574 0.965514 -0.029151 -0.258712 0.965515 -0.029151 -0.258712 0.965515 0.0291502 -0.258712 0.965515 0.0794211 -0.704873 0.704873 0.234276 -0.669531 0.704871 0.234281 -0.669525 0.704876 0.37739 -0.600605 0.704876 0.377388 -0.600611 0.704872 0.501577 -0.501573 0.704872 0.501576 -0.501581 0.704867 0.600614 -0.377394 0.704866 0.600613 -0.377381 0.704875 0.669525 -0.234283 0.704874 0.669523 -0.234278 0.704877 0.704868 -0.0794199 0.704878 0.704866 -0.0794166 0.704881 0.704866 0.0794191 0.70488 0.704868 0.0794168 0.704878 0.669521 0.234281 0.704878 0.669527 0.234278 0.704874 0.600607 0.37739 0.704874 0.60062 0.377386 0.704866 0.501581 0.501577 0.704867 0.501573 0.501577 0.704872 0.377392 0.600608 0.704872 0.377386 0.600608 0.704876 0.234275 0.669527 0.704875 0.234282 0.66953 0.70487 0.0794209 0.704873 0.704873 0.0794211 0.704873 0.704873 -0.0794209 0.704873 0.704873 -0.0794231 0.704871 0.704875 -0.234275 0.669527 0.704875 -0.234274 0.669527 0.704875 -0.37739 0.600605 0.704876 -0.377388 0.600611 0.704872 -0.501577 0.501573 0.704872 -0.501576 0.501581 0.704867 -0.600614 0.377394 0.704866 -0.600613 0.377381 0.704875 -0.669525 0.234283 0.704874 -0.669523 0.234276 0.704879 -0.704868 0.0794193 0.704879 -0.704866 0.0794166 0.704881 -0.704866 -0.0794196 0.70488 -0.704869 -0.0794169 0.704878 -0.669522 -0.234282 0.704877 -0.669526 -0.234279 0.704874 -0.600607 -0.37739 0.704874 -0.60062 -0.377386 0.704866 -0.501581 -0.501577 0.704867 -0.501573 -0.501577 0.704872 -0.377392 -0.600608 0.704872 -0.377386 -0.600608 0.704876 -0.234275 -0.669527 0.704875 -0.234274 -0.669527 0.704875 -0.0794207 -0.704871 0.704875 -0.0794234 -0.704873 0.704873 0.0794209 -0.704873 0.704873 0.108196 -0.960254 0.257305 0.319158 -0.912103 0.257307 0.319155 -0.912105 0.257303 0.514122 -0.818214 0.257303 0.514123 -0.818213 0.257305 0.683296 -0.683301 0.257306 0.6833 -0.683294 0.257316 0.818212 -0.514117 0.257318 0.818211 -0.514121 0.257314 0.912105 -0.319146 0.257315 0.912104 -0.319167 0.257292 0.960256 -0.108208 0.257291 0.960254 -0.108195 0.257306 0.960253 0.108207 0.257306 0.960258 0.108195 0.257291 0.91211 0.319148 0.257292 0.912098 0.319165 0.257316 0.818213 0.514118 0.257314 0.81821 0.51412 0.257318 0.683294 0.683299 0.257315 0.683301 0.683296 0.257306 0.514122 0.818213 0.257304 0.514124 0.818213 0.257303 0.319159 0.912104 0.257303 0.319155 0.912104 0.257307 0.108191 0.960255 0.257305 0.108196 0.960256 0.257299 -0.108191 0.960256 0.257299 -0.108196 0.960254 0.257305 -0.319158 0.912103 0.257307 -0.319155 0.912105 0.257303 -0.514122 0.818214 0.257303 -0.514123 0.818213 0.257305 -0.683296 0.683301 0.257306 -0.6833 0.683294 0.257316 -0.818212 0.514117 0.257318 -0.818211 0.514121 0.257314 -0.912105 0.319146 0.257315 -0.912104 0.319167 0.257292 -0.960257 0.108207 0.257291 -0.960254 0.108194 0.257306 -0.960253 -0.108207 0.257306 -0.960258 -0.108195 0.257291 -0.91211 -0.319148 0.257292 -0.912098 -0.319165 0.257316 -0.818213 -0.514118 0.257314 -0.81821 -0.51412 0.257318 -0.683294 -0.683299 0.257315 -0.683301 -0.683296 0.257306 -0.514122 -0.818213 0.257304 -0.514124 -0.818213 0.257303 -0.319159 -0.912104 0.257303 -0.319155 -0.912104 0.257307 -0.108191 -0.960255 0.257305 -0.108196 -0.960256 0.257299 0.108191 -0.960256 0.257299 0.0291509 -0.258711 0.965515 0.0859886 -0.245737 0.965515 0.085988 -0.245739 0.965515 0.138513 -0.220443 0.965515 0.138513 -0.220443 0.965515 0.184093 -0.184095 0.965515 0.184093 -0.184095 0.965515 0.220445 -0.138511 0.965515 0.220446 -0.138517 0.965514 0.245742 -0.0859891 0.965514 0.245741 -0.0859858 0.965514 0.258714 -0.029149 0.965514 0.258715 -0.0291514 0.965514 0.258715 0.0291492 0.965514 0.258713 0.0291514 0.965514 0.24574 0.0859888 0.965514 0.245744 0.0859867 0.965514 0.220448 0.138513 0.965514 0.220442 0.138515 0.965515 0.184093 0.184095 0.965515 0.184093 0.184095 0.965515 0.138513 0.220443 0.965515 0.138513 0.220443 0.965515 0.0859889 0.245738 0.965515 0.0859876 0.245738 0.965515 0.0291501 0.258711 0.965515 0.029151 0.258712 0.965515 -0.029151 0.258712 0.965515 -0.029151 0.258712 0.965515 -0.0859871 0.24574 0.965514 -0.085988 0.245739 0.965515 -0.138513 0.220443 0.965515 -0.138513 0.220443 0.965515 -0.184093 0.184095 0.965515 -0.184093 0.184095 0.965515 -0.220445 0.138511 0.965515 -0.220446 0.138517 0.965514 -0.245742 0.0859896 0.965514 -0.24574 0.0859856 0.965514 -0.258713 0.029149 0.965514 -0.258715 0.0291517 0.965514 -0.258715 -0.0291492 0.965514 -0.258713 -0.0291512 0.965514 -0.24574 -0.0859884 0.965514 -0.245744 -0.0859867 0.965514 -0.220448 -0.138513 0.965514 -0.220442 -0.138515 0.965515 -0.184093 -0.184095 0.965515 -0.184093 -0.184095 0.965515 -0.138513 -0.220443 0.965515 -0.138513 -0.220443 0.965515 -0.0859867 -0.245739 0.965515 -0.0859884 -0.24574 0.965514 -0.029151 -0.258712 0.965515 -0.029151 -0.258712 0.965515 0.0291502 -0.258712 0.965515 0.0794211 -0.704873 0.704873 0.234276 -0.669531 0.704871 0.234281 -0.669525 0.704876 0.37739 -0.600605 0.704876 0.377388 -0.600611 0.704872 0.501577 -0.501573 0.704872 0.501576 -0.501581 0.704867 0.600614 -0.377394 0.704866 0.600613 -0.377381 0.704875 0.669525 -0.234283 0.704874 0.669523 -0.234276 0.704879 0.704868 -0.0794193 0.704879 0.704866 -0.0794166 0.704881 0.704866 0.0794196 0.70488 0.704869 0.0794169 0.704878 0.669522 0.234282 0.704877 0.669526 0.234279 0.704874 0.600607 0.37739 0.704874 0.60062 0.377386 0.704866 0.501581 0.501577 0.704867 0.501573 0.501577 0.704872 0.377392 0.600608 0.704872 0.377386 0.600608 0.704876 0.234275 0.669527 0.704875 0.234282 0.66953 0.70487 0.0794209 0.704873 0.704873 0.0794211 0.704873 0.704873 -0.0794209 0.704873 0.704873 -0.0794231 0.704871 0.704875 -0.234275 0.669527 0.704875 -0.234274 0.669527 0.704875 -0.37739 0.600605 0.704876 -0.377388 0.600611 0.704872 -0.501577 0.501573 0.704872 -0.501576 0.501581 0.704867 -0.600614 0.377394 0.704866 -0.600613 0.377381 0.704875 -0.669525 0.234283 0.704874 -0.669523 0.234278 0.704877 -0.704868 0.0794199 0.704878 -0.704866 0.0794166 0.704881 -0.704866 -0.0794191 0.70488 -0.704868 -0.0794168 0.704878 -0.669521 -0.234281 0.704878 -0.669527 -0.234278 0.704874 -0.600607 -0.37739 0.704874 -0.60062 -0.377386 0.704866 -0.501581 -0.501577 0.704867 -0.501573 -0.501577 0.704872 -0.377392 -0.600608 0.704872 -0.377386 -0.600608 0.704876 -0.234275 -0.669527 0.704875 -0.234274 -0.669527 0.704875 -0.0794207 -0.704871 0.704875 -0.0794234 -0.704873 0.704873 0.0794209 -0.704873 0.704873 0.108196 -0.960254 0.257305 0.319158 -0.912103 0.257307 0.319155 -0.912105 0.257303 0.514122 -0.818214 0.257303 0.514123 -0.818213 0.257305 0.683296 -0.683301 0.257306 0.6833 -0.683294 0.257316 0.818212 -0.514117 0.257318 0.818211 -0.514121 0.257314 0.912105 -0.319146 0.257315 0.912104 -0.319167 0.257292 0.960257 -0.108207 0.257291 0.960254 -0.108194 0.257306 0.960253 0.108207 0.257306 0.960258 0.108195 0.257291 0.91211 0.319148 0.257292 0.912098 0.319165 0.257316 0.818213 0.514118 0.257314 0.81821 0.51412 0.257318 0.683294 0.683299 0.257315 0.683301 0.683296 0.257306 0.514122 0.818213 0.257304 0.514124 0.818213 0.257303 0.319159 0.912104 0.257303 0.319155 0.912104 0.257307 0.108191 0.960255 0.257305 0.108196 0.960256 0.257299 -0.108191 0.960256 0.257299 -0.108196 0.960254 0.257305 -0.319158 0.912103 0.257307 -0.319155 0.912105 0.257303 -0.514122 0.818214 0.257303 -0.514123 0.818213 0.257305 -0.683296 0.683301 0.257306 -0.6833 0.683294 0.257316 -0.818212 0.514117 0.257318 -0.818211 0.514121 0.257314 -0.912105 0.319146 0.257315 -0.912104 0.319167 0.257292 -0.960256 0.108208 0.257291 -0.960254 0.108195 0.257306 -0.960253 -0.108207 0.257306 -0.960258 -0.108195 0.257291 -0.91211 -0.319148 0.257292 -0.912098 -0.319165 0.257316 -0.818213 -0.514118 0.257314 -0.81821 -0.51412 0.257318 -0.683294 -0.683299 0.257315 -0.683301 -0.683296 0.257306 -0.514122 -0.818213 0.257304 -0.514124 -0.818213 0.257303 -0.319159 -0.912104 0.257303 -0.319155 -0.912104 0.257307 -0.108191 -0.960255 0.257305 -0.108196 -0.960256 0.257299 0.108191 -0.960256 0.257299 -0.0226387 0.258757 -0.965677 -0.0672273 0.250896 -0.965677 -0.0672258 0.250894 -0.965678 -0.109772 0.235408 -0.965677 -0.109775 0.235411 -0.965676 -0.148987 0.212774 -0.965676 -0.148985 0.212772 -0.965677 -0.183669 0.183669 -0.965677 -0.183669 0.183669 -0.965677 -0.212773 0.148983 -0.965677 -0.212764 0.14898 -0.965679 -0.235401 0.109771 -0.96568 -0.235413 0.109773 -0.965676 -0.250899 0.0672282 -0.965676 -0.250898 0.0672282 -0.965676 -0.25876 0.0226405 -0.965676 -0.258759 0.0226408 -0.965677 -0.258759 -0.0226404 -0.965677 -0.25876 -0.0226409 -0.965676 -0.250899 -0.067228 -0.965676 -0.250899 -0.0672283 -0.965676 -0.235412 -0.109776 -0.965676 -0.235404 -0.109769 -0.965679 -0.212767 -0.148979 -0.965679 -0.212772 -0.148985 -0.965677 -0.183669 -0.183669 -0.965677 -0.183669 -0.183669 -0.965677 -0.148985 -0.212772 -0.965677 -0.148986 -0.212774 -0.965676 -0.109774 -0.235412 -0.965676 -0.109774 -0.235411 -0.965677 -0.0672275 -0.250897 -0.965677 -0.0672275 -0.250896 -0.965677 -0.0226381 -0.258758 -0.965677 -0.0226385 -0.258755 -0.965678 0.0226379 -0.258755 -0.965678 0.0226387 -0.258757 -0.965677 0.0672273 -0.250896 -0.965677 0.0672277 -0.250897 -0.965677 0.109773 -0.235411 -0.965677 0.109774 -0.235412 -0.965676 0.148987 -0.212774 -0.965676 0.148985 -0.212772 -0.965677 0.183669 -0.183669 -0.965677 0.183669 -0.183669 -0.965677 0.212773 -0.148983 -0.965677 0.212766 -0.148981 -0.965679 0.235402 -0.109772 -0.965679 0.235413 -0.109773 -0.965676 0.250899 -0.0672282 -0.965676 0.250898 -0.0672282 -0.965676 0.258761 -0.0226363 -0.965676 0.258745 -0.0226395 -0.96568 0.258745 0.0226349 -0.965681 0.25876 0.0226409 -0.965676 0.250899 0.067228 -0.965676 0.250899 0.0672283 -0.965676 0.235412 0.109776 -0.965676 0.235402 0.109768 -0.965679 0.212765 0.148978 -0.965679 0.212772 0.148986 -0.965677 0.183669 0.183669 -0.965677 0.183669 0.183669 -0.965677 0.148985 0.212772 -0.965677 0.148986 0.212774 -0.965676 0.109774 0.235412 -0.965676 0.109773 0.235408 -0.965677 0.0672266 0.250893 -0.965678 0.0672265 0.250896 -0.965677 0.0226381 0.258758 -0.965677 0.0226385 0.258755 -0.965678 -0.0226379 0.258755 -0.965678 -0.0617455 0.705762 -0.705754 -0.18336 0.684316 -0.705755 -0.183363 0.68432 -0.705751 -0.299411 0.642085 -0.705748 -0.299404 0.642078 -0.705757 -0.406355 0.58033 -0.705757 -0.406351 0.580327 -0.705761 -0.500944 0.500953 -0.705762 -0.50096 0.50096 -0.705747 -0.580344 0.406357 -0.705745 -0.580347 0.406358 -0.705741 -0.642091 0.299414 -0.705741 -0.642084 0.299414 -0.705747 -0.684323 0.183364 -0.705748 -0.684325 0.183364 -0.705746 -0.705769 0.0617472 -0.705746 -0.705757 0.0617509 -0.705757 -0.705758 -0.0617462 -0.705758 -0.705769 -0.0617519 -0.705746 -0.684324 -0.183365 -0.705746 -0.684323 -0.183364 -0.705748 -0.642085 -0.299412 -0.705747 -0.64209 -0.299416 -0.705741 -0.580346 -0.406359 -0.705741 -0.580344 -0.406356 -0.705745 -0.500956 -0.500965 -0.705747 -0.500949 -0.500949 -0.705762 -0.406353 -0.580326 -0.705761 -0.406354 -0.580331 -0.705757 -0.299407 -0.642077 -0.705757 -0.299408 -0.642087 -0.705748 -0.183361 -0.684321 -0.705751 -0.183362 -0.684316 -0.705755 -0.0617468 -0.705761 -0.705754 -0.0617458 -0.705765 -0.70575 0.0617471 -0.705765 -0.70575 0.0617455 -0.705762 -0.705754 0.183363 -0.684316 -0.705755 0.183361 -0.684313 -0.705758 0.299401 -0.642076 -0.70576 0.299404 -0.642078 -0.705757 0.406355 -0.58033 -0.705757 0.406351 -0.580327 -0.705761 0.500944 -0.500953 -0.705762 0.50096 -0.50096 -0.705747 0.580344 -0.406357 -0.705745 0.580347 -0.406358 -0.705741 0.642091 -0.299414 -0.705741 0.642084 -0.299414 -0.705747 0.684323 -0.183364 -0.705748 0.684325 -0.183364 -0.705746 0.705769 -0.0617472 -0.705746 0.705786 -0.0617419 -0.705729 0.705786 0.0617487 -0.705729 0.70577 0.0617405 -0.705746 0.684324 0.183365 -0.705746 0.684323 0.183364 -0.705748 0.642085 0.299412 -0.705747 0.64209 0.299416 -0.705741 0.580346 0.406359 -0.705741 0.580344 0.406356 -0.705745 0.500956 0.500965 -0.705747 0.500949 0.500949 -0.705762 0.406353 0.580326 -0.705761 0.406354 0.580331 -0.705757 0.299403 0.642079 -0.705757 0.299403 0.642075 -0.70576 0.183362 0.684312 -0.705758 0.183362 0.684316 -0.705755 0.0617468 0.705761 -0.705754 0.0617458 0.705765 -0.70575 -0.0617471 0.705765 -0.70575 -0.0842085 0.962497 -0.257892 -0.250068 0.933253 -0.257887 -0.250061 0.933249 -0.257905 -0.408321 0.875647 -0.25791 -0.408324 0.875648 -0.257901 -0.554172 0.791441 -0.257904 -0.554179 0.791442 -0.257886 -0.68319 0.68319 -0.257881 -0.683179 0.683191 -0.25791 -0.791439 0.554172 -0.257912 -0.791445 0.55417 -0.257897 -0.875648 0.408327 -0.257896 -0.875651 0.408326 -0.257886 -0.933254 0.250063 -0.257885 -0.933252 0.250065 -0.257894 -0.962498 0.0841964 -0.257894 -0.962486 0.0842072 -0.257933 -0.962487 -0.0841955 -0.257933 -0.962496 -0.0842081 -0.257895 -0.933252 -0.250062 -0.257894 -0.933254 -0.250065 -0.257885 -0.87565 -0.408329 -0.257886 -0.875649 -0.408325 -0.257895 -0.791442 -0.554174 -0.257896 -0.791442 -0.554168 -0.257912 -0.683185 -0.683185 -0.25791 -0.683184 -0.683196 -0.257881 -0.554174 -0.791445 -0.257886 -0.554176 -0.791438 -0.257904 -0.408322 -0.875649 -0.257901 -0.408323 -0.875646 -0.25791 -0.250066 -0.933248 -0.257905 -0.250062 -0.933254 -0.257887 -0.0842043 -0.962497 -0.257892 -0.0842082 -0.962493 -0.257906 0.084204 -0.962494 -0.257906 0.0842085 -0.962497 -0.257892 0.250068 -0.933253 -0.257887 0.250066 -0.933252 -0.257891 0.408323 -0.875652 -0.257887 0.408318 -0.875651 -0.257901 0.554172 -0.791441 -0.257904 0.554179 -0.791442 -0.257886 0.68319 -0.68319 -0.257881 0.683179 -0.683191 -0.25791 0.791439 -0.554172 -0.257912 0.791445 -0.55417 -0.257897 0.875654 -0.408314 -0.257895 0.875639 -0.40832 -0.257935 0.933237 -0.250075 -0.257937 0.933252 -0.250065 -0.257894 0.962498 -0.0841964 -0.257894 0.962486 -0.0842072 -0.257933 0.962487 0.0841955 -0.257933 0.962496 0.0842081 -0.257895 0.933248 0.250078 -0.257893 0.93324 0.250062 -0.257937 0.875644 0.408309 -0.257935 0.875649 0.408325 -0.257895 0.791442 0.554174 -0.257896 0.791442 0.554168 -0.257912 0.683185 0.683185 -0.25791 0.683184 0.683196 -0.257881 0.554174 0.791445 -0.257886 0.554176 0.791438 -0.257904 0.408322 0.875649 -0.257901 0.408319 0.875654 -0.257887 0.250067 0.933252 -0.257891 0.250066 0.933253 -0.257887 0.0842043 0.962497 -0.257892 0.0842082 0.962493 -0.257906 -0.084204 0.962494 -0.257906 -0.0226387 -0.258757 0.965677 -0.0672273 -0.250896 0.965677 -0.0672277 -0.250897 0.965677 -0.109773 -0.235411 0.965677 -0.109774 -0.235412 0.965676 -0.148987 -0.212774 0.965676 -0.148985 -0.212772 0.965677 -0.183669 -0.183669 0.965677 -0.183669 -0.183669 0.965677 -0.212773 -0.148983 0.965677 -0.212766 -0.148981 0.965679 -0.235402 -0.109772 0.965679 -0.235413 -0.109773 0.965676 -0.250899 -0.0672282 0.965676 -0.250898 -0.0672282 0.965676 -0.25876 -0.0226405 0.965676 -0.258759 -0.0226408 0.965677 -0.258759 0.0226404 0.965677 -0.25876 0.0226409 0.965676 -0.250899 0.067228 0.965676 -0.250899 0.0672283 0.965676 -0.235412 0.109776 0.965676 -0.235402 0.109768 0.965679 -0.212765 0.148978 0.965679 -0.212772 0.148986 0.965677 -0.183669 0.183669 0.965677 -0.183669 0.183669 0.965677 -0.148985 0.212772 0.965677 -0.148986 0.212774 0.965676 -0.109774 0.235412 0.965676 -0.109773 0.235408 0.965677 -0.0672266 0.250893 0.965678 -0.0672265 0.250896 0.965677 -0.0226381 0.258758 0.965677 -0.0226385 0.258755 0.965678 0.0226379 0.258755 0.965678 0.0226387 0.258757 0.965677 0.0672273 0.250896 0.965677 0.0672258 0.250894 0.965678 0.109772 0.235408 0.965677 0.109775 0.235411 0.965676 0.148987 0.212774 0.965676 0.148985 0.212772 0.965677 0.183669 0.183669 0.965677 0.183669 0.183669 0.965677 0.212773 0.148983 0.965677 0.212764 0.14898 0.965679 0.235401 0.109771 0.96568 0.235413 0.109773 0.965676 0.250899 0.0672282 0.965676 0.250898 0.0672282 0.965676 0.258761 0.0226363 0.965676 0.258745 0.0226395 0.96568 0.258745 -0.0226349 0.965681 0.25876 -0.0226409 0.965676 0.250899 -0.067228 0.965676 0.250899 -0.0672283 0.965676 0.235412 -0.109776 0.965676 0.235404 -0.109769 0.965679 0.212767 -0.148979 0.965679 0.212772 -0.148985 0.965677 0.183669 -0.183669 0.965677 0.183669 -0.183669 0.965677 0.148985 -0.212772 0.965677 0.148986 -0.212774 0.965676 0.109774 -0.235412 0.965676 0.109774 -0.235411 0.965677 0.0672275 -0.250897 0.965677 0.0672275 -0.250896 0.965677 0.0226381 -0.258758 0.965677 0.0226385 -0.258755 0.965678 -0.0226379 -0.258755 0.965678 -0.0617442 -0.705747 0.705768 -0.183356 -0.684302 0.70577 -0.183359 -0.684306 0.705765 -0.299405 -0.642072 0.705762 -0.299398 -0.642065 0.705771 -0.406347 -0.580318 0.705771 -0.406343 -0.580316 0.705775 -0.500934 -0.500943 0.705777 -0.50095 -0.50095 0.705761 -0.580332 -0.406348 0.705759 -0.580335 -0.406349 0.705756 -0.642078 -0.299408 0.705755 -0.642071 -0.299408 0.705761 -0.684309 -0.183361 0.705762 -0.684311 -0.18336 0.705761 -0.705755 -0.061746 0.70576 -0.705743 -0.0617496 0.705772 -0.705743 0.061745 0.705772 -0.705754 0.0617506 0.70576 -0.68431 0.183361 0.705761 -0.684309 0.18336 0.705762 -0.642072 0.299406 0.705762 -0.642077 0.29941 0.705755 -0.580335 0.406351 0.705756 -0.580333 0.406347 0.705759 -0.500945 0.500954 0.705761 -0.500939 0.500939 0.705777 -0.406345 0.580315 0.705775 -0.406346 0.580319 0.705771 -0.299401 0.642064 0.705771 -0.299402 0.642074 0.705762 -0.183357 0.684307 0.705765 -0.183358 0.684302 0.705769 -0.0617455 0.705747 0.705768 -0.0617445 0.70575 0.705765 0.0617458 0.70575 0.705765 0.0617442 0.705747 0.705768 0.183359 0.684302 0.705769 0.183357 0.684299 0.705773 0.299395 0.642063 0.705774 0.299398 0.642065 0.705771 0.406347 0.580318 0.705771 0.406343 0.580316 0.705775 0.500934 0.500943 0.705777 0.50095 0.50095 0.705761 0.580332 0.406348 0.705759 0.580335 0.406349 0.705756 0.642078 0.299408 0.705755 0.642071 0.299408 0.705761 0.684309 0.183361 0.705762 0.684311 0.18336 0.705761 0.705755 0.061746 0.70576 0.705772 0.0617406 0.705743 0.705772 -0.0617474 0.705743 0.705756 -0.0617392 0.70576 0.68431 -0.183361 0.705761 0.684309 -0.18336 0.705762 0.642072 -0.299406 0.705762 0.642077 -0.29941 0.705755 0.580335 -0.406351 0.705756 0.580333 -0.406347 0.705759 0.500945 -0.500954 0.705761 0.500939 -0.500939 0.705777 0.406345 -0.580315 0.705775 0.406346 -0.580319 0.705771 0.299397 -0.642066 0.705771 0.299397 -0.642062 0.705774 0.183358 -0.684299 0.705773 0.183358 -0.684302 0.705769 0.0617455 -0.705747 0.705768 0.0617445 -0.70575 0.705765 -0.0617458 -0.70575 0.705765 -0.0842087 -0.962499 0.257885 -0.250068 -0.933255 0.257879 -0.250061 -0.933251 0.257898 -0.408321 -0.875648 0.257902 -0.408325 -0.875649 0.257894 -0.554173 -0.791443 0.257897 -0.55418 -0.791444 0.257879 -0.683191 -0.683191 0.257874 -0.68318 -0.683192 0.257902 -0.79144 -0.554173 0.257905 -0.791447 -0.554171 0.257889 -0.875649 -0.408328 0.257888 -0.875653 -0.408327 0.257879 -0.933256 -0.250063 0.257878 -0.933253 -0.250065 0.257886 -0.962499 -0.0841966 0.257887 -0.962488 -0.0842074 0.257926 -0.962489 0.0841957 0.257926 -0.962498 0.0842083 0.257887 -0.933254 0.250063 0.257886 -0.933256 0.250066 0.257878 -0.875652 0.408329 0.257879 -0.875651 0.408326 0.257888 -0.791444 0.554175 0.257889 -0.791443 0.554169 0.257905 -0.683186 0.683186 0.257902 -0.683185 0.683197 0.257874 -0.554175 0.791447 0.257879 -0.554177 0.79144 0.257897 -0.408322 0.87565 0.257894 -0.408324 0.875647 0.257902 -0.250067 0.93325 0.257898 -0.250063 0.933256 0.257879 -0.0842044 0.962499 0.257885 -0.0842084 0.962495 0.257899 0.0842041 0.962496 0.257899 0.0842087 0.962499 0.257885 0.250068 0.933255 0.257879 0.250066 0.933254 0.257884 0.408324 0.875654 0.25788 0.408319 0.875652 0.257894 0.554173 0.791443 0.257897 0.55418 0.791444 0.257879 0.683191 0.683191 0.257874 0.68318 0.683192 0.257902 0.79144 0.554173 0.257905 0.791447 0.554171 0.257889 0.875656 0.408315 0.257888 0.875641 0.408321 0.257927 0.933239 0.250075 0.25793 0.933253 0.250065 0.257886 0.962499 0.0841966 0.257887 0.962488 0.0842074 0.257926 0.962489 -0.0841957 0.257926 0.962498 -0.0842083 0.257887 0.93325 -0.250078 0.257886 0.933242 -0.250062 0.25793 0.875646 -0.40831 0.257928 0.875651 -0.408326 0.257888 0.791444 -0.554175 0.257889 0.791443 -0.554169 0.257905 0.683186 -0.683186 0.257902 0.683185 -0.683197 0.257874 0.554175 -0.791447 0.257879 0.554177 -0.79144 0.257897 0.408322 -0.87565 0.257894 0.40832 -0.875656 0.25788 0.250068 -0.933253 0.257884 0.250067 -0.933255 0.257879 0.0842044 -0.962499 0.257885 0.0842084 -0.962495 0.257899 -0.0842041 -0.962496 0.257899 -0.00533302 -0.988902 0.148472 -0.00574256 -0.987691 0.156315 0.00436253 -0.96772 0.251991 -0.00819131 -0.935192 0.354047 -0.00480254 -0.934185 0.356757 -0.0029124 -0.938776 0.344516 0.0426482 -0.942481 0.331528 -0.932895 -0.343041 0.109683 0.327542 -0.902785 0.27874 -0.0117413 -0.965687 0.259444 -0.0100062 -0.893379 0.449193 -0.00441646 -0.891377 0.453241 -0.00438648 -0.885328 0.464947 -0.00374985 -0.881303 0.472538 -0.00228026 -0.881952 0.471334 -0.00251019 -0.881879 0.47147 -0.00367978 -0.883914 0.467635 -0.00710912 -0.880094 0.474747 -0.000528506 -0.880615 0.473833 -0.0309158 -0.887408 0.459946 -0.00699275 -0.883931 0.467566 -0.00608492 -0.875824 0.482592 -0.00832579 -0.88174 0.471662 0.0175601 -0.887788 0.459918 -0.00950028 -0.879384 0.476018 -0.0029442 -0.879918 0.475116 -0.0323613 -0.886458 0.461676 -0.00950617 -0.882993 0.469291 -0.00845991 -0.875123 0.483827 -0.0107239 -0.881063 0.472877 0.014148 -0.886955 0.461638 -0.0118847 -0.878463 0.477662 -0.0053392 -0.879011 0.476771 -0.0333699 -0.885219 0.463976 -0.0119939 -0.881763 0.47154 -0.0108392 -0.874195 0.485454 -0.0131314 -0.880176 0.474466 0.0103031 -0.885814 0.463927 -0.0142714 -0.877318 0.479697 -0.00772789 -0.877881 0.478816 -0.0340561 -0.883698 0.466817 -0.0144623 -0.880235 0.474317 -0.0132101 -0.873055 0.487442 -0.0155261 -0.879067 0.476445 0.00624281 -0.88439 0.466708 -0.0166315 -0.875961 0.482094 -0.0101091 -0.876538 0.481226 -0.0155598 -0.871683 0.489824 -0.0168145 -0.882353 0.470289 -0.0175608 -0.878252 0.477876 0.00191702 -0.882671 0.469987 -0.0179046 -0.877741 0.4788 -0.0362909 -0.880219 0.473178 -0.0186518 -0.870259 0.492242 -0.0133382 -0.875185 0.483604 -0.0202163 -0.874192 0.485159 -0.0178925 -0.870103 0.492545 -0.0201999 -0.876043 0.48181 -0.0184554 -0.876559 0.480941 -0.0214334 -0.916863 0.398627 -0.0234925 -0.917784 0.396384 -0.0249238 -0.921224 0.388234 -0.0200659 -0.919404 0.392803 -0.0453002 -0.911421 0.408975 0.0227062 -0.907318 0.419832 -0.0964165 -0.973745 0.206217 -0.0365054 -0.968384 0.24678 -0.023881 -0.969611 0.243485 -0.0905971 -0.974304 0.206213 0.199943 -0.962656 0.182529 -0.0329568 -0.969725 0.241964 0.473622 -0.867922 0.149647 -0.0949472 -0.973991 0.205736 -0.0343463 -0.989098 0.143199 -0.0318158 -0.988857 0.145432 -0.0317922 -0.988123 0.150339 -0.0313494 -0.98751 0.154406 -0.0255385 -0.987571 0.155088 -0.0314435 -0.9869 0.158238 -0.0327988 -0.984193 0.174036 0.0789706 -0.979317 0.186282 0.0199391 -0.981614 0.189834 -0.0285371 -0.990985 0.1309 -0.0284982 -0.990963 0.131077 -0.0284768 -0.990668 0.133291 -0.02855 -0.990628 0.133569 -0.0282863 -0.990698 0.133105 -0.0246306 -0.99127 0.129529 -0.0245918 -0.991251 0.129676 -0.0245722 -0.99094 0.132041 -0.0246474 -0.9909 0.132327 -0.0244019 -0.990964 0.131893 -0.020697 -0.991518 0.12831 -0.0206556 -0.991501 0.128447 -0.0206383 -0.991176 0.130935 -0.0207437 -0.991121 0.131334 -0.020472 -0.991191 0.130852 -0.0167481 -0.991717 0.127347 -0.0167139 -0.991704 0.12745 -0.0166993 -0.991365 0.13006 -0.0167953 -0.991316 0.130423 -0.0165442 -0.991379 0.129977 -0.0127971 -0.991878 0.126551 -0.0127677 -0.991867 0.126633 -0.012756 -0.991514 0.129375 -0.0128484 -0.991467 0.129723 -0.0126197 -0.991523 0.129316 -0.0088553 -0.99183 0.127256 -0.00966214 -0.991978 0.12604 -0.00869702 -0.991563 0.129336 -0.00892779 -0.991624 0.128853 -0.5 7.55007e-07 0.866025 -0.5 0 0.866026 0.500001 0 -0.866025 0.499999 1.29126e-06 -0.866026 0.500001 0 0.866025 0.500001 0 0.866025 0.500006 -4.75513e-06 0.866022 0.500012 1.40495e-05 0.866019 0.500001 0 0.866025 0.500001 0 0.866025 0.500001 0 0.866025 0.5 6.25006e-07 0.866025 0.5 0 0.866026 0.500001 0 0.866025 0.5 6.24247e-07 0.866025 0.5 0 0.866026 0.5 0 0.866025 0.5 -1.71936e-07 0.866025 0.500001 0 0.866025 0.5 0 0.866026 0.5 -1.0297e-06 0.866025 0.500002 0 0.866024 0.5 0 0.866025 0.5 -1.71258e-07 0.866025 0.500001 0 0.866025 0.5 0 0.866026 0.499999 -3.47137e-07 0.866026 0.5 3.12865e-06 0.866025 -0.500002 0 0.866024 -0.500001 -1.20402e-06 0.866025 -0.500004 0 0.866023 0.500012 0 -0.866019 0.500003 -2.0873e-06 -0.866024 0.499998 0 -0.866027 -0.499995 0 -0.866028 -0.499996 -4.14926e-07 -0.866028 -0.499997 0 -0.866027 -0.500003 0 0.866024 -0.5 -1.27178e-06 0.866025 -0.5 0 0.866026 0.500006 0 -0.866022 0.500002 -4.1203e-07 -0.866024 0.500001 0 -0.866025 -0.500002 0 -0.866024 -0.500002 -1.89717e-07 -0.866024 -0.500004 0 -0.866023 -0.499999 0 0.866026 -0.5 7.28399e-07 0.866025 -0.500001 0 0.866025 -0.499999 0 0.866026 -0.500001 1.07342e-06 0.866025 -0.500001 0 0.866025 -0.5 0 0.866026 -0.5 7.95764e-07 0.866025 -0.500001 0 0.866025 -0.500001 0 0.866025 -0.5 -1.27078e-06 0.866025 -0.499999 0 0.866026 1 0 0 1 0 0 1 0 0 -0.499999 0 -0.866026 -0.5 1.89076e-06 -0.866025 -0.500004 -3.61514e-05 0.866023 -0.499995 0 0.866028 -0.499995 0 0.866028 0.499999 0 -0.866026 0.499999 0 -0.866026 0.500004 5.88684e-06 -0.866023 -0.500002 4.17682e-06 0.866024 -0.499997 0 0.866027 0.500003 -2.55081e-06 -0.866023 0.5 0 -0.866025 0.5 0 -0.866025 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0.499998 0 0.866027 0.499998 0 0.866027 0.499999 0 -0.866026 0.499999 0 -0.866026 -0.500002 0 -0.866024 -0.500002 0 -0.866024 0.500002 0 -0.866024 0.500002 0 -0.866024 -0.500002 0 -0.866024 -0.500002 0 -0.866024 0.500002 0 -0.866024 0.500002 0 -0.866024 -0.500002 0 -0.866024 -0.500002 0 -0.866024 0.500002 0 -0.866024 0.500002 0 -0.866024 -0.500002 0 -0.866024 -0.500002 0 -0.866024 -0.5 0 0.866025 -0.5 0 0.866025 -0.499999 0 0.866026 -0.499999 0 0.866026 -1 0 0 -1 0 0 0.00209405 -0.190808 0.981625 0.473375 -0.169421 0.864415 0.986687 -0.0310317 0.159643 0.984475 -0.00419646 0.175476 0.986969 -0.0303174 0.158026 0.885612 -0.0889908 0.455821 0.887742 -0.0873902 0.45197 0.667033 -0.17501 0.724182 0.511494 -0.107775 0.852501 0.689379 -0.1387 0.710999 0.20464 -0.187325 0.960745 0.0553832 -0.139929 0.988611 0.196997 -0.184269 0.962931 -0.986691 -0.0306458 0.159691 -0.98698 -0.030691 0.15789 -0.983827 -0.00485235 0.179056 -0.756214 -0.125058 0.642262 -0.885362 -0.0882802 0.456443 -0.871444 -0.0870708 0.482706 -0.936133 -0.0671806 0.345168 -0.396501 -0.165074 0.903071 -0.670539 -0.168944 0.722382 -0.516877 -0.109848 0.848983 -0.640388 -0.130787 0.756834 -0.00203314 -0.190809 0.981625 -0.00244047 -0.190808 0.981624 -0.194436 -0.187167 0.962893 -0.194546 -0.187141 0.962876 -0.464836 -0.168953 0.869127 0.0197419 0.650811 0.758983 0.0248564 0.993454 -0.111493 -6.09774e-05 0.697108 0.716966 -7.13148e-05 0.815437 0.578846 -2.63719e-08 0.115101 -0.993354 0.000136671 0.868743 -0.495262 0.0156233 0.716217 0.697702 -0.000136894 0.186989 0.982362 -0.00819817 0.0963557 -0.995313 -0.00304821 0.125445 -0.992096 -0.000194106 0.253934 -0.967221 -0.000150833 0.197324 -0.980338 -0.00122113 0.135861 -0.990727 -0.000695275 0.132452 -0.991189 -4.38715e-06 0.0764916 -0.99707 -4.96804e-07 0.0763338 -0.997082 -0.0121571 0.0754632 -0.997074 -0.0151726 0.0611798 -0.998011 -0.0173372 0.0517528 -0.998509 -0.0178384 0.0497388 -0.998603 -0.0135997 0.0658017 -0.99774 -0.00458638 0.0985939 -0.995117 -0.00116077 0.410789 -0.91173 -0.0180799 0.560452 -0.827989 -0.00942508 0.517738 -0.855488 -0.00542097 0.486518 -0.873654 -0.00366445 0.467292 -0.884095 -0.00268174 0.452742 -0.891638 -0.00121304 0.429287 -0.903167 -0.000834641 0.433234 -0.901281 -0.000397745 0.436494 -0.899707 0.00251558 0.449708 -0.893172 0.00597667 0.462619 -0.886537 0.0136627 0.48191 -0.876114 0.0235421 0.4962 -0.867889 -0.00597411 0.457535 -0.889171 0.00373061 0.536076 -0.844161 0.0114818 0.548276 -0.836219 0.00127521 0.575356 -0.817902 -8.9114e-05 0.595422 -0.803413 0.00141193 0.62126 -0.783603 0.0155866 0.641929 -0.766605 0.0044127 0.658121 -0.7529 -0.00400882 0.700519 -0.713623 -0.0449799 0.753608 -0.655783 -0.012158 0.854828 -0.51877 0.0157848 0.825324 -0.564439 -0.0153839 0.792635 -0.609502 0.0445131 0.715595 -0.697096 0.0116711 0.941505 -0.336797 -0.00585335 0.915807 -0.401576 -0.0153878 0.907029 -0.420788 0.000632779 0.89633 -0.443387 -1.17336e-05 0.868743 -0.495262 0.0115381 0.987763 -0.155537 0.0070331 0.988607 -0.150355 -0.00685928 0.978466 -0.206295 0.0110969 0.973717 -0.227489 0.00112706 0.964407 -0.26442 -0.00217266 0.947029 -0.321142 0.00518263 0.989976 -0.141139 0.000741522 0.991609 -0.129268 -0.000978613 0.996632 -0.0819991 0.0178811 0.994497 -0.10323 -0.0630984 0.998 -0.00375526 0.0432832 0.997258 -0.060034 0.02999 0.998278 -0.050408 -0.00996052 0.999392 -0.0334075 0.0199319 0.998887 -0.0427472 0.0111669 0.999361 -0.0339502 0.00431113 0.999631 -0.0268078 -0.0191968 0.998828 -0.044438 -0.0259401 0.998399 -0.050255 -0.0338078 0.997823 -0.0566202 -0.038407 0.997429 0.0604975 -0.0295459 0.998032 0.0553078 -0.0225557 0.998553 0.0488238 -0.0174518 0.998888 0.0437975 -0.00996018 0.999354 0.0345456 -0.00468419 0.999862 -0.0159212 -0.00346205 0.999826 -0.0183369 -0.00816367 0.999379 0.0342837 -0.00468376 0.999749 0.0218922 0.000848601 0.997808 0.0661656 0.00330258 0.997339 0.072824 0.00612406 0.996771 0.0800605 0.010041 0.99619 0.0866323 0.0159157 0.995273 0.0958074 0.00504784 0.996361 0.085088 0.000747501 0.992654 0.120989 -0.000374565 0.990869 0.134831 0.00283855 0.989087 0.147306 0.0065752 0.987255 0.159013 0.0152193 0.98493 0.172283 -0.0106125 0.978248 0.207167 0.00488625 0.968574 0.248676 0.000340132 0.96349 0.267744 0.000336917 0.954384 0.298582 -0.0091669 0.946239 0.323337 0.0157522 0.92813 0.371924 -0.0156202 0.907156 0.420505 0.0159804 0.87848 0.477512 -0.0155269 0.851584 0.523988 0.0131058 0.476689 0.878974 0.0300965 0.503372 0.863545 -0.0598535 0.422439 0.904413 0.0538853 0.544947 0.836737 -0.042063 0.486476 0.872681 0.0227479 0.600522 0.799284 0.00181055 0.582492 0.812834 -0.000941472 0.649288 0.760542 0.00230251 0.653516 0.756909 -0.00324832 0.711801 0.702374 -0.0222485 0.696535 0.717178 0.038641 0.784255 0.619234 -0.038297 0.752241 0.657774 0.0126211 0.82047 0.57155 0.00608358 0.459557 0.888127 0.0022876 0.445653 0.895203 -0.000396537 0.434506 0.900669 -0.00298914 0.45466 0.89066 -0.00405333 0.468664 0.883367 -0.00622676 0.490554 0.871389 -0.00875002 0.507793 0.861435 -0.0130003 0.534334 0.845174 -0.00855683 0.516066 0.856506 -0.000830906 0.431541 0.902093 -0.00118579 0.428157 0.903703 -0.00102311 0.369418 0.929263 -0.00428817 0.314755 0.949163 -0.00336252 0.304035 0.952655 -0.000178444 0.243743 0.96984 -0.0127231 0.0685617 0.997566 -0.0184479 0.0429838 0.998905 -0.017181 0.0480416 0.998698 -0.0145937 0.059429 0.998126 -0.0102995 0.0808678 0.996672 -0.00603675 0.104779 0.994477 -0.00152741 0.13143 0.991324 -4.26184e-06 0.119878 0.992789 -4.71769e-07 0.119864 0.99279 -2.98551e-08 0.110332 0.993895 -0.0103447 0.0732895 0.997257 -0.0171025 0.0482434 0.998689 0.00292118 0.123204 0.992377 4.71769e-07 0.119864 0.99279 0.000178444 0.243743 0.96984 0.000136894 0.186989 0.982362 0.00152741 0.13143 0.991324 4.26217e-06 0.119878 0.992789 0.00776813 0.0948713 0.995459 0.0114946 0.0745533 0.997151 0.0145937 0.0594288 0.998126 0.017181 0.0480418 0.998698 0.0179176 0.0451011 0.998822 0.0136369 0.0612177 0.998031 -0.00286265 0.448032 0.894013 0.00592618 0.516075 0.856523 0.0188993 0.560167 0.828164 0.00996738 0.517439 0.855662 0.000396535 0.434506 0.900669 0.0057724 0.486207 0.873825 0.00389628 0.466899 0.884302 0.00280362 0.45195 0.892039 0.00336252 0.304035 0.952655 0.00428817 0.314755 0.949163 0.00102311 0.369417 0.929263 0.00118579 0.428157 0.903703 0.000830904 0.431541 0.902093 -0.00676168 0.461432 0.88715 -0.0149925 0.480809 0.876697 -0.0253223 0.495096 0.868469 -0.0251023 0.656957 0.75351 -0.00897486 0.67096 0.74144 0.00392151 0.617221 0.78678 0.00136979 0.61168 0.791104 -0.00149216 0.575293 0.817946 -0.00464625 0.567188 0.823575 0.0024728 0.538849 0.842399 -0.00716931 0.486893 0.873432 0.0312266 0.42299 0.905596 -0.000336916 0.954384 0.298582 0.00918007 0.946228 0.323371 -0.0157573 0.928129 0.371924 0.0157622 0.907023 0.420786 -0.00173449 0.891859 0.452311 0.00243208 0.854888 0.518806 0.0182559 0.863703 0.50367 -0.0297746 0.792377 0.609304 0.0384013 0.819932 0.571171 -0.0156706 0.752698 0.658179 -0.00034193 0.968586 0.248679 -0.011423 0.963714 0.266693 0.0218512 0.984809 0.17226 -0.0373991 0.977804 0.206156 -0.00492933 0.987669 0.156482 -0.00160099 0.989826 0.142273 0.000515579 0.991525 0.129912 -0.00560126 0.996358 0.0850877 -0.0210764 0.994681 0.100825 -0.0131559 0.99566 0.0921295 -0.00816467 0.996481 0.0834216 -0.00483064 0.997007 0.0771573 -0.00224029 0.997552 0.0698965 -0.000208379 0.997956 0.063903 0.00816367 0.999379 0.0342837 0.00468377 0.999749 0.0218922 0.00996016 0.999354 0.0345455 0.0190065 0.998774 0.0457171 0.0255243 0.998346 0.0515226 0.0331398 0.997773 0.0578817 0.029062 0.997731 -0.0607304 0.0731485 0.994719 -0.0719953 0.0523536 0.996441 -0.0660686 0.0392332 0.997472 -0.0592409 0.0300974 0.998085 -0.0540431 0.0228687 0.998607 -0.047551 0.0175917 0.998941 -0.0425213 0.00287124 0.999685 -0.024938 0.00996491 0.999935 -0.00548099 0.0046842 0.999862 -0.0159212 -0.00632354 0.999552 -0.0292428 -0.0148612 0.999182 -0.0376145 -0.00048801 0.992633 -0.121157 0.0016728 0.996631 -0.081999 -0.013253 0.995072 -0.0982645 0.0395945 0.999209 -0.00375983 -0.0350987 0.997921 -0.0540594 -0.0240221 0.998641 -0.0462475 -0.00175395 0.990992 -0.133908 -0.00745607 0.989234 -0.146151 -0.00968474 0.988585 -0.150352 -0.00120728 0.907266 -0.420556 -0.0048448 0.987233 -0.159208 0.00707849 0.978279 -0.207173 -0.0105461 0.973723 -0.227491 -0.00106739 0.964123 -0.265455 0.00309501 0.941565 -0.336818 -0.0158803 0.946923 -0.321068 0.00588054 0.915807 -0.401576 0.0267168 0.896011 -0.443227 0.0368111 0.82487 -0.564123 -0.0365481 0.851118 -0.523701 0.0359499 0.753883 -0.656024 -0.0362453 0.784326 -0.61929 0.01935 0.700394 -0.713494 0.00632871 0.71179 -0.702364 -0.0075011 0.64199 -0.766677 -0.0150065 0.64806 -0.761441 -0.000863591 0.611843 -0.790979 0.0027473 0.54831 -0.83627 -0.0407229 0.583508 -0.811086 -0.015278 0.558739 -0.829203 0.0235864 0.457417 -0.88894 -0.0280925 0.504512 -0.862947 -0.0118852 0.477785 -0.878397 -0.00536364 0.460796 -0.88749 -0.00201114 0.447427 -0.894318 0.000397754 0.436494 -0.899707 0.00284653 0.455356 -0.890305 0.00380939 0.469034 -0.883172 0.00584954 0.490863 -0.871217 0.00826607 0.508091 -0.861264 0.012351 0.534629 -0.844997 0.000834632 0.433234 -0.901281 0.00121304 0.429287 -0.903167 0.00116077 0.410789 -0.91173 0.00140781 0.352011 -0.935995 0.0151726 0.0611798 -0.998011 0.0170287 0.0528808 -0.998456 0.0183666 0.0476158 -0.998697 0.0173372 0.0517527 -0.998509 0.0134469 0.0693574 -0.997501 0.0108946 0.0819235 -0.996579 0.00634972 0.106581 -0.994284 0.000150833 0.197324 -0.980338 0.00122113 0.135861 -0.990727 0.000695277 0.132452 -0.991189 4.38715e-06 0.0764916 -0.99707 4.96899e-07 0.0763338 -0.997082 -0.024971 0.846079 -0.532473 -0.0157191 0.83778 -0.545781 -0.00778356 0.82971 -0.55814 7.23008e-05 0.81964 -0.572879 -2.26808e-05 0.819458 -0.573139 0.000995465 0.961358 -0.2753 -0.014644 0.951336 -0.307807 -0.04207 0.935459 -0.350923 -0.0466949 0.936539 -0.34744 -0.0203739 0.924408 -0.38086 -0.00413641 0.912745 -0.408508 -0.000126117 0.900699 -0.434443 0.000514703 0.895859 -0.444338 -4.97775e-05 0.839786 -0.542918 -0.0500494 0.860426 -0.507112 -0.0366486 0.853295 -0.520139 -0.0427924 0.984489 -0.17015 -0.0223432 0.984028 -0.176605 0.00101751 0.982647 -0.185485 -0.00815603 0.982078 -0.188296 0.000450174 0.982511 -0.186203 0.000196817 0.990106 -0.140323 0.000162998 0.989519 -0.144402 -0.00172336 0.989046 -0.147598 -0.00539674 0.988496 -0.151153 -0.0166611 0.985737 -0.167466 -0.169783 0.961843 -0.214551 -0.000499085 0.99001 -0.140997 -0.00111335 0.989977 -0.141227 -0.000153519 0.989921 -0.141619 -0.0810341 0.983783 -0.160013 -0.0334696 0.984735 -0.17081 -0.00140176 0.992497 -0.122261 0.0312881 0.998056 -0.0539044 -0.104395 0.991535 -0.0771969 -0.0414534 0.980886 0.190114 -0.00112519 0.988479 0.151354 0.000338083 0.98905 0.14758 -0.000624398 0.989343 0.145602 -0.00103526 0.989346 0.145577 -0.000306244 0.98941 0.145148 -0.0475059 0.980534 0.190517 0.000175878 0.982907 0.184103 -0.29242 0.926543 0.236661 0.000469322 0.981671 0.190583 0.00101148 0.981697 0.190448 -0.00438133 0.982164 0.187973 -0.0166195 0.982992 0.182893 -0.0345072 0.983655 0.176729 -0.0644126 0.983646 0.168199 -0.0406773 0.983923 0.173901 -0.00337752 0.991768 0.128005 0.036958 0.997728 0.0563256 -0.13002 0.987909 0.0844391 0.0422244 0.999094 0.00532499 -0.00635707 0.913422 0.406965 -0.0267638 0.925969 0.37665 -0.0463651 0.933632 0.355221 -0.0273305 0.941468 0.335993 0.000988653 0.959546 0.281549 -0.011908 0.830401 0.557038 -0.00486476 0.822075 0.569358 -0.0213961 0.839862 0.542378 -0.0343656 0.848898 0.527439 -0.0135525 0.837073 0.546924 0.00123961 0.887142 0.461496 -0.000215387 0.899756 0.436394 -0.00447274 0.810849 0.585238 -0.00612622 0.815046 0.579363 -0.0124383 0.810024 0.586264 0.0462586 0.7938 0.606417 0.0128606 0.80507 0.59304 -0.00448303 0.809543 0.587044 0.0100109 0.865033 0.501615 -0.00776019 0.931245 0.364312 0.00124636 0.944214 0.32933 -0.013182 0.916779 0.399178 -0.0167364 0.902584 0.430188 -0.0172788 0.88931 0.456978 -0.00616551 0.988486 0.151184 -0.0109132 0.98628 0.164719 -0.0232144 0.979105 0.202028 -0.0323827 0.987603 0.153596 0.00263648 0.977408 0.211344 -0.0235475 0.978866 0.203141 0.109999 0.965791 0.234835 -0.0325374 0.983702 0.176839 -0.0138186 0.983059 0.182768 -0.0271045 0.986137 0.163706 -0.0298519 0.986493 0.161059 -0.0318261 0.986962 0.157778 -0.0316589 0.987518 0.154295 -0.0307531 0.987493 0.154635 -0.0315266 0.987419 0.154948 0.00839986 0.998389 0.0561113 -0.00627899 0.997673 0.067891 -0.0178826 0.996664 0.0796351 0.0340512 0.99862 0.0399918 -0.0121401 0.997909 0.0634787 -0.0209179 0.999777 0.00275579 -0.00152151 0.990319 0.1388 -0.0223399 0.981176 0.191817 -0.0257033 0.991603 0.126738 -0.0258089 0.995678 0.0892101 -0.0315098 0.996553 0.0767455 -0.0398046 0.997377 0.0604486 -0.048349 0.997769 0.0460313 -0.0221035 0.996282 0.0832709 -0.0338495 0.999265 0.0179993 -0.0379487 0.999274 0.00329413 -0.0436705 0.997261 -0.0596919 -0.0387653 0.999233 0.00559109 -0.0361787 0.99934 -0.00318908 -0.0153323 0.996339 -0.0841005 -0.0694575 0.997278 -0.02476 -0.0540375 0.997556 -0.0443008 -0.0212829 0.996395 -0.082122 -0.00978943 0.997536 -0.069467 0.00298004 0.998299 -0.0582213 -0.000718443 0.998152 -0.0607544 -0.0164521 0.999609 -0.0225941 -0.0197077 0.999762 -0.00931761 0.00992369 0.980793 -0.1948 -0.0310745 0.988181 -0.150109 -0.0320488 0.988239 -0.149524 0.0156072 0.980638 -0.195208 -0.0306486 0.987294 -0.15592 -0.0321797 0.987857 -0.151998 -0.0312573 0.988174 -0.150117 -0.0180643 0.983103 -0.182162 -0.0233161 0.979754 -0.198841 -0.0272599 0.979882 -0.197705 0.196936 0.948591 -0.247771 -0.032605 0.981541 -0.18845 -0.0323313 0.981539 -0.188509 -0.034732 0.996568 -0.0751343 -0.0271976 0.995592 -0.0897559 -0.0253316 0.990782 -0.133073 -0.021571 0.981834 -0.188514 -0.00768225 0.988429 -0.151491 -0.0125008 0.98617 -0.165267 -0.0172632 0.880944 -0.472906 -0.0174601 0.889592 -0.456423 -0.0172644 0.896875 -0.441947 -0.015706 0.911408 -0.411203 -0.0107338 0.925914 -0.377582 -0.00998541 0.927473 -0.373757 -0.0173699 0.940853 -0.33837 -0.0227884 0.957581 -0.287263 0.00439068 0.811821 -0.583889 -0.00870534 0.814068 -0.580704 -0.00616873 0.81392 -0.580944 -0.00760323 0.818498 -0.574459 -0.0133861 0.998627 -0.0506495 0.00306536 0.997995 -0.0632109 0.0144617 0.99713 -0.0743209 -0.0443291 0.998502 -0.0320837 0.0136575 0.99806 -0.0607495 0.0204005 0.999788 -0.00275858 0.0349352 0.997618 -0.0594771 0.0406627 0.99835 0.0405516 0.039046 0.998269 -0.043984 0.043829 0.99864 -0.02822 0.0340023 0.997837 -0.0562523 0.0318674 0.999445 -0.00974637 0.0305212 0.997803 0.0587961 0.0533385 0.998568 0.00420707 0.0459979 0.998652 0.0240465 0.0342714 0.994465 0.0993212 0.0171573 0.99674 0.0788344 0.00557183 0.99772 0.0672523 -0.00949791 0.998423 0.05533 0.00369302 0.997976 0.0634825 0.0189926 0.999678 0.0168152 0.0205746 0.999778 0.00460662 -0.00319903 0.969298 -0.245866 0.0211824 0.978589 -0.204733 0.0545665 0.983849 -0.170483 0.0637012 0.982697 -0.173921 0.0359934 0.986101 -0.1622 0.0228354 0.988053 -0.152416 0.014886 0.989235 -0.145577 0.0108204 0.990256 -0.138838 0.00881068 0.990809 -0.13498 0.00799933 0.991201 -0.132122 0.0080835 0.991158 -0.132438 0.00486978 0.90463 -0.42617 0.0109288 0.910062 -0.414328 0.020683 0.917068 -0.398193 0.0463887 0.92398 -0.379618 0.0958139 0.932114 -0.349262 0.104938 0.929604 -0.353305 0.017892 0.954714 -0.296986 0.00920591 0.838199 -0.545286 0.00581051 0.822963 -0.568065 0.0159918 0.827314 -0.561512 0.0158248 0.842025 -0.539206 0.0270973 0.847114 -0.53072 0.00986063 0.839762 -0.542865 0.00285251 0.894188 -0.447683 0.00339665 0.898208 -0.439557 -0.0186829 0.809015 -0.587491 0.0119633 0.826786 -0.562389 -0.00543922 0.856137 -0.516721 0.00894425 0.923896 -0.382538 0.0133806 0.913636 -0.406313 0.0155648 0.903221 -0.428894 0.016889 0.894267 -0.447215 0.0282341 0.995477 -0.090708 0.0276363 0.995567 -0.0899019 0.0275442 0.992248 -0.121182 0.0300294 0.99072 -0.132563 0.0274911 0.992151 -0.121987 0.0267932 0.990916 -0.131785 0.0259397 0.98983 -0.139869 0.0246598 0.98826 -0.150781 0.0227608 0.986644 -0.161293 0.0201936 0.984449 -0.174506 0.0202121 0.975999 -0.216836 0.022675 0.964067 -0.264688 0.0150308 0.927414 -0.373734 -0.00817172 0.948436 -0.316863 0.00418438 0.932841 -0.360263 -0.0219488 0.990046 0.139022 -0.0147872 0.991574 0.128698 -0.0339433 0.997408 0.0634482 -0.0714901 0.994747 0.0732645 -0.0511745 0.996417 0.0673323 -0.014613 0.947225 0.320236 -0.0148799 0.964527 0.263566 -0.0962962 0.976858 0.190985 -0.18342 0.96246 0.200071 -0.0347932 0.98772 0.152308 -0.0226587 0.955666 0.293579 -0.0129583 0.925662 0.378129 -0.234634 0.899877 0.367651 -0.025912 0.908291 0.417537 -0.0168487 0.823129 0.567604 -0.234336 0.800291 0.551925 0.000840918 0.856708 0.515802 -0.00532906 0.576566 0.817033 -0.00518753 0.617972 0.786183 -0.00847673 0.650909 0.759108 -0.00783212 0.660099 0.751138 -0.00776315 0.717606 0.696406 -0.0023721 0.718438 0.695587 -0.0114424 0.794769 0.606804 -0.00754548 0.650979 -0.759058 -0.00813886 0.654597 -0.755935 -0.00755213 0.719311 -0.694647 -0.0446704 0.713232 -0.699504 0.0246982 0.786702 -0.616838 0.00416541 0.857106 -0.515123 -0.0120269 0.825875 -0.563725 -0.235077 0.802757 -0.548015 -0.00668037 0.853499 -0.521051 -0.0155297 0.90855 -0.417489 -0.23725 0.901018 -0.363152 -0.0146771 0.947928 -0.318147 -0.0443267 0.997102 -0.0618244 -0.0598089 0.995834 -0.0688367 -0.0265477 0.997801 -0.0607345 -0.0172227 0.992691 -0.119452 -0.0164841 0.990991 -0.132913 -0.0289397 0.989306 -0.142957 -0.046246 0.986965 -0.15415 -0.152731 0.970536 -0.186366 -0.0632873 0.976882 -0.204197 -0.0149382 0.964795 -0.262578 0.0433609 0.997066 0.0630816 0.058447 0.995826 0.0701035 0.0317515 0.99748 0.0634526 0.0177418 0.992722 0.119114 0.0155344 0.990951 0.133325 0.026586 0.989286 0.143551 0.041876 0.987079 0.154664 0.150211 0.970282 0.189709 0.0768661 0.975948 0.204004 0.235946 0.79997 0.551704 -0.0162252 0.786838 0.616947 0.0148745 0.964173 0.264856 0.0146122 0.947174 0.320386 0.234829 0.899834 0.367634 0.0274192 0.908316 0.417385 -0.00377264 0.853513 0.521057 0.00512918 0.617981 -0.786176 0.0385504 0.987666 -0.151753 0.0236484 0.990083 -0.138478 0.0152498 0.991598 -0.128459 0.0158269 0.98164 -0.190084 0.0163107 0.981932 -0.188532 0.152731 0.970536 -0.186366 0.0695241 0.976705 -0.203013 0.00844252 0.856676 -0.515785 0.0140507 0.908507 -0.417633 0.237116 0.901048 -0.363164 0.0146778 0.947978 -0.317997 0.0149436 0.965145 -0.261289 0.016958 0.88554 -0.464254 0.0157168 0.825833 -0.563697 0.235729 0.802626 -0.547926 0.000515721 0.794823 -0.606841 9.67843e-05 0.314756 0.949173 0.000368306 0.316664 0.948538 0.000600245 0.516081 0.856539 0.00124096 0.520135 0.854083 0.00167353 0.701441 0.712726 6.09663e-05 0.697108 0.716966 7.13128e-05 0.815413 0.578879 0 0.81527 0.579081 0.0321114 0.713578 0.699839 0.0102918 0.717209 0.696783 0.0118126 0.823189 0.567644 0.0163956 0.832291 0.554096 0.0182334 0.925586 0.378099 0.0227087 0.931419 0.363239 0.023921 0.98114 0.19181 0.0272434 0.983279 0.180056 0.0275826 0.995521 0.0904291 0.0363495 0.997779 0.0558254 0.013917 0.986364 -0.16399 0.0143411 0.985245 -0.17055 0.0145331 0.998439 -0.0539371 0.0151758 0.9983 -0.0562812 0.0151757 0.998294 0.056374 0.0145014 0.998163 0.0588198 0.0143052 0.984656 0.173922 0.0125705 0.983565 0.180115 0.0119451 0.934628 0.355427 0.00961657 0.931614 0.363323 0.00864155 0.837157 0.546894 0.00625653 0.832383 0.554166 0.00549146 0.730597 0.682787 0.00773961 0.730587 0.682776 0.00783834 0.650912 0.759113 0.00784563 0.650955 0.759076 0.00512548 0.606831 0.794815 0.00631732 0.833525 -0.552445 0.00556219 0.733891 -0.679244 0.0106188 0.733863 -0.679214 0.00755213 0.719311 -0.694647 0.0137378 0.71837 -0.695526 -0.0051464 0.606825 -0.794819 -0.00649974 0.52025 -0.853989 -0.000617358 0.520258 -0.854009 -0.000381295 0.321325 -0.946969 0.00010315 0.321325 -0.946969 0.00125663 0.520258 -0.854008 0.00893936 0.520241 -0.853973 0.0055613 0.576499 -0.817079 -7.23023e-05 0.819611 -0.572921 -6.18013e-05 0.700612 -0.713542 6.18013e-05 0.700612 -0.713542 0.00170285 0.705 -0.709205 0.0198081 0.654496 -0.755806 0.008521 0.654595 -0.755932 0.00809328 0.660086 -0.751146 -0.00140781 0.352011 -0.935995 -0.00417787 0.319368 -0.947622 -0.000102518 0.319369 -0.94763 -3.70251e-05 0.115342 -0.993326 3.70629e-05 0.115459 -0.993312 2.00677e-08 0.115101 -0.993354 0.010328 0.0778779 -0.996909 0.000194105 0.253934 -0.967221 0.00417787 0.319368 -0.947622 0.000378975 0.319369 -0.94763 0.000622215 0.524352 -0.851501 -0.00126652 0.524352 -0.851501 -0.00170285 0.705 -0.709205 -0.0198081 0.654495 -0.755806 -0.00556219 0.733891 -0.679244 -0.0106188 0.733863 -0.679214 -0.0118091 0.816126 -0.577753 -0.00103525 0.845986 -0.533204 0.00388663 0.853266 0.521461 -0.0117489 0.818753 0.574026 -0.0104835 0.73057 0.682758 -0.00549147 0.730597 0.682787 -0.0197419 0.650811 0.758983 -0.00167353 0.701441 0.712726 -0.00123129 0.516081 0.856539 -0.000604959 0.520135 0.854084 -0.000366087 0.314756 0.949172 -9.73709e-05 0.316664 0.948538 -3.40267e-05 0.11066 0.993858 3.39934e-05 0.110553 0.99387 3.91005e-08 0.110332 0.993895 0.00458924 0.0939191 0.995569 0.862977 0.498391 -0.0829322 0.842993 0.537867 -0.00785648 0.839127 0.543517 0.0213484 0.802496 0.57506 0.15908 0.777194 0.596658 0.199921 0.731279 0.623654 0.276203 0.685173 0.647813 0.33298 0.642506 0.65605 0.39596 0.528072 0.699431 0.481598 0.525442 0.700406 0.483055 0.400039 0.71564 0.572563 0.38464 0.720673 0.576786 0.265719 0.74254 0.61484 0.167933 0.756087 0.632559 0.124141 0.748872 0.650984 2.58469e-07 0.75471 0.656059 0 0.75471 0.656058 -1.67212e-07 0.75471 0.656059 -0.106792 0.750394 0.652307 -0.220092 0.764932 0.605341 -0.234249 0.761034 0.604941 -0.37847 0.719226 0.582644 -0.606165 0.684204 0.405499 -0.604919 0.684027 0.407652 -0.500637 0.70498 0.50236 -0.860533 0.50637 -0.0554267 -0.810945 0.581657 0.0635885 -0.824961 0.563797 0.0396563 -0.774611 0.594101 0.216845 -0.698305 0.64189 0.316777 0.866025 0.47276 -0.162784 0.866026 0.472759 -0.162785 0.866026 0.472759 -0.162783 -0.866026 0.472759 -0.162782 -0.866025 0.47276 -0.162785 -0.866025 0.47276 -0.162785 0.0854113 0.190111 -0.97804 0.220232 0.229107 -0.94816 0.20058 0.234641 -0.951163 0.352642 0.206159 -0.912766 0.486166 0.241095 -0.839949 0.607338 0.286505 -0.740983 0.599677 0.28848 -0.746436 0.860784 0.434133 -0.265668 0.815046 0.417208 -0.402042 0.825936 0.418208 -0.378062 0.773386 0.333767 -0.538956 0.695511 0.309837 -0.648279 -0.740344 0.325895 -0.587948 -0.807476 0.367384 -0.461532 -0.821458 0.425758 -0.37939 -0.840682 0.431637 -0.327022 -0.86372 0.447764 -0.23129 -0.226045 0.18587 -0.95622 -0.127122 0.253839 -0.958856 -0.270122 0.228371 -0.935351 -0.408283 0.206945 -0.889089 -0.60482 0.292923 -0.740532 -0.521976 0.319469 -0.790873 -0.648172 0.291176 -0.703626 -6.01499e-09 0.190809 -0.981627 0 0.190809 -0.981627 7.48502e-08 0.190809 -0.981627 0.49989 0 0.866089 0.499982 -4.92135e-06 0.866036 -0.500004 0 0.866023 0.499998 0 -0.866026 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.500041 0 -0.866002 -0.0310166 -0.984579 0.172171 -0.033671 -0.982854 0.181283 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.5 -1.68271e-06 -0.866026 0.499998 0 -0.866027 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.999745 0 0.0225964 -0.784525 -0.0281434 0.619458 -0.839185 0.0407775 0.542315 -0.845546 6.88303e-05 0.533902 -0.0657557 0 0.997836 -0.152533 0.450163 0.879822 -0.191433 -0.0333749 0.980938 -0.277382 0.0120942 0.960684 -0.328039 -0.150377 0.932618 -0.42479 0.105601 0.899112 -0.486072 0.000132119 0.873919 -0.517274 -0.000130959 0.85582 -0.531837 -0.0361401 0.846075 -0.546481 -0.0172315 0.837294 -0.697483 0.0766348 0.712492 -0.676733 0.0192987 0.735976 -0.777115 -0.0038893 0.629347 -0.904604 -0.000162057 0.426252 -0.890466 -0.0388982 0.453383 -0.941082 0.0106765 0.338011 -0.973587 -0.0905816 0.209577 -0.986736 0.150807 0.0600744 -0.952007 -0.0235254 0.30517 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.070402 0 0.997519 0.0923923 -0.235502 0.967472 0.193629 0.0311788 0.980579 0.259001 -0.0220578 0.965625 0.396661 0.272452 0.876602 0.376327 -0.12533 0.917971 0.530272 0.0431279 0.84673 0.538968 -0.00181121 0.842324 0.669359 0.007431 0.742902 0.675195 0.0525486 0.735765 0.78057 -0.0208395 0.62472 0.777697 0.0349727 0.627665 0.857578 -0.105426 0.503434 0.879745 0.137756 0.455053 0.941088 -0.0700099 0.330836 0.940635 0.0519137 0.335427 0.977867 -0.117829 0.172893 0.980204 0.145623 0.134142 0.999344 0 0.0362265 1 0 0 1 0 0 1 0 0 1 0 0 0.999699 0 -0.0245329 0.0682557 0 -0.997668 0.144527 0.452249 -0.880104 0.194841 -0.0357357 -0.980184 0.276925 0.0127967 -0.960806 0.332938 -0.148185 -0.931232 0.458801 0.241243 -0.855163 0.510516 -0.0652008 -0.857393 0.545741 -0.0183923 -0.837752 0.66338 0.0574845 -0.746072 0.640056 4.18021e-05 -0.768328 0.733715 -1.7682e-05 -0.679457 0.737196 0.00534214 -0.675658 0.790744 -0.00703467 -0.612107 0.762737 -0.0554628 -0.644326 0.905993 0.1742 -0.385787 0.847809 -0.0781559 -0.52451 0.939909 0.0106286 -0.34126 0.970543 -0.103785 -0.21743 0.984144 0.168806 -0.0544531 0.952117 -0.0231612 -0.304856 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.0635126 0 -0.997981 -0.0837725 -0.256373 -0.962941 -0.182822 0.0239083 -0.982855 -0.258023 -0.0163633 -0.966 -0.398235 0.30525 -0.865004 -0.365442 -0.141914 -0.919952 -0.527791 0.0508209 -0.847853 -0.536263 -0.000487351 -0.844051 -0.665329 0.00201582 -0.746548 -0.673488 0.0538311 -0.737236 -0.777704 -0.0218211 -0.628251 -0.776035 0.0387878 -0.629496 -0.851086 -0.116078 -0.512033 -0.879879 0.142615 -0.453292 -0.938862 -0.07557 -0.335897 -0.940152 0.0569907 -0.335956 -0.975735 -0.126358 -0.178817 -0.98004 0.14873 -0.13191 -0.999258 0 -0.0385121 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 -0.0355294 -0.907274 0.419037 -0.0366256 -0.932763 0.358625 -0.00358136 -0.983435 0.181226 -5.31651e-05 -0.0454268 -0.998968 -0.0147833 -0.913631 -0.406276 -0.0154364 -0.98062 -0.195312 0.00570572 -0.632757 -0.77433 0.00315065 -0.511586 -0.859226 -0.0244676 -0.975693 0.217774 0.014087 -0.937685 0.347201 0.0378858 -0.744682 0.666343 0.00662278 -0.983545 0.180539 0.0117619 -0.971056 -0.238561 -0.0135873 -0.937663 -0.347279 0.0112802 -0.971763 0.235691 0.00176188 -0.925429 -0.378918 0.025735 -0.990311 -0.136464 0.014632 -0.859713 0.510567 -7.17039e-05 -0.868153 0.496297 1.26699e-05 -0.869335 0.494223 0.000601504 -0.874791 0.484501 0.00120004 -0.905725 0.423865 0.00694714 -0.891171 0.453614 0.00725289 -0.891471 0.45302 0.00263855 -0.881431 0.472305 0.0160703 -0.879269 0.476054 0.0109628 -0.896568 0.44277 0.0136056 -0.886853 0.461852 0.0148242 -0.877233 0.479837 0.0150468 -0.87516 0.483599 0.0155263 -0.869921 0.492947 0.0164155 -0.936181 0.351134 0.0116179 -0.947122 0.320664 0.0184003 -0.923492 0.383177 0.0190522 -0.915603 0.401631 0.0188143 -0.905499 0.42393 0.0173205 -0.991098 0.132006 0.0182997 -0.990476 0.136464 0.019106 -0.989937 0.14021 0.0203181 -0.989082 0.145962 0.0106966 -0.983837 0.178746 0.0273883 -0.98508 0.169903 0.0330058 -0.989772 0.138786 0.0319066 -0.989581 0.140394 0.0311821 -0.989551 0.140769 0.0324672 -0.989196 0.142955 0.0300042 -0.988409 0.148822 0.0293709 -0.988288 0.149746 0.0281074 -0.987893 0.152573 0.0259559 -0.987329 0.156548 -0.0131271 -0.998343 0.0560223 0.0207444 -0.999783 -0.00196039 0.0206163 -0.999778 0.0042628 0.0118047 -0.997686 0.0669514 -0.0417983 -0.99839 0.0383429 -0.026064 -0.998509 0.0479534 -0.00104578 -0.997881 0.0650518 0.00597657 -0.997479 0.0707117 0.0167711 -0.996629 0.0803105 0.0401395 -0.997211 0.062922 0.044446 -0.997469 0.0555054 0.0512731 -0.997698 0.0443727 0.0231391 -0.996131 0.0847791 0.0331638 -0.999333 0.0153119 0.0322694 -0.999289 0.0194892 0.0314506 -0.999497 0.00413021 0.031207 -0.999231 -0.023725 0.0360979 -0.999321 -0.00732743 0.0174764 -0.995788 -0.0900103 0.0632395 -0.99751 -0.0312282 0.056722 -0.997581 -0.0401933 0.048999 -0.997476 -0.0513881 0.0437855 -0.997244 -0.0598879 0.0391842 -0.996952 -0.0674666 0.0261823 -0.995524 -0.0908078 0.0316625 -0.99482 -0.0965994 0.0214124 -0.996026 -0.086447 0.0111837 -0.996989 -0.0767311 0.00281976 -0.997549 -0.0699213 -0.00481537 -0.997943 -0.0639227 -0.0198121 -0.99836 -0.053706 0.00709389 -0.997543 -0.069701 0.0188313 -0.999655 -0.0183039 0.0204641 -0.999741 -0.00997303 0.031834 -0.988664 -0.146733 0.0299609 -0.988553 -0.14787 0.0314321 -0.987651 -0.153486 0.0314446 -0.988152 -0.15022 0.0303098 -0.98854 -0.147886 0.032845 -0.988777 -0.145743 0.0222891 -0.985838 -0.16621 0.0290753 -0.986754 -0.159594 0.0233494 -0.986032 -0.164913 0.0210757 -0.987971 -0.153194 0.0320462 -0.987863 -0.151984 0.0233841 -0.986 -0.165097 0.0269548 -0.979056 -0.201797 0.0204144 -0.96514 -0.260937 0.0181345 -0.922816 -0.384815 0.0157429 -0.936323 -0.350788 0.0194866 -0.927596 -0.373075 0.0218668 -0.948646 -0.315584 0.0221463 -0.959741 -0.280014 0.0155765 -0.858476 -0.512617 0.0155497 -0.863496 -0.504117 0.0150924 -0.870725 -0.491539 0.013881 -0.88208 -0.470896 0.0150832 -0.877 -0.480254 0.0177908 -0.895309 -0.44509 0.0192947 -0.909338 -0.41561 -2.82281e-06 -0.866708 -0.498815 0.0109323 -0.892535 -0.450846 -0.0103157 -0.889 -0.45779 0.0271202 -0.906868 -0.420541 0.0147248 -0.896323 -0.443157 0.00527982 -0.8852 -0.46518 0.00269447 -0.878904 -0.476992 0.000647748 -0.872961 -0.48779 0.00968829 -0.937365 -0.348215 0.00815623 -0.93655 -0.350439 0.000970498 -0.9485 -0.316777 -0.00935292 -0.970721 -0.240028 0.00509451 -0.967105 -0.254328 0.0251617 -0.989584 -0.141738 0.00203101 -0.987937 -0.154843 -0.00166977 -0.991896 -0.127043 -0.00179464 -0.992055 -0.125792 0.0176001 -0.989099 -0.146194 0.010192 -0.988496 -0.150901 0.00339412 -0.98782 -0.155562 -0.000323675 -0.987393 -0.158288 0.00371696 -0.987982 -0.154523 0.007506 -0.988597 -0.1504 0.00881636 -0.988824 -0.14883 0.00944913 -0.988941 -0.148011 0.0092412 -0.988894 -0.148336 0.00855538 -0.988734 -0.149436 0.00703153 -0.988299 -0.152365 -0.00248066 -0.984808 -0.173631 -0.00376984 -0.996296 -0.0859038 0.0530346 -0.99667 -0.0619403 -0.00198552 -0.999709 -0.0240504 0.0100138 -0.988958 0.147857 0.0431319 -0.981551 0.186274 0.00222286 -0.989217 0.146443 -0.000685502 -0.990313 0.13885 0.00119749 -0.990858 0.134907 0.00205692 -0.990864 0.134853 0.000626092 -0.990981 0.134003 0.0560488 -0.980574 0.187971 -0.00032276 -0.984675 0.174399 -0.0184433 -0.985669 0.16768 0.00210094 -0.9882 0.153154 0.00645 -0.988636 0.150192 -0.00174762 -0.992308 0.12378 -0.00188133 -0.992556 0.121777 -0.00146677 -0.998226 0.0595211 0.0692701 -0.994552 0.0779018 -0.00198581 -0.999849 0.0172439 -0.00230955 -0.919629 0.392781 0.00429575 -0.931421 0.363918 0.010783 -0.938157 0.346041 0.00260028 -0.944105 0.329635 -0.00369759 -0.962895 0.269852 -0.0546876 -0.998478 0.00720136 -0.0318126 -0.997567 0.062038 -0.0490946 -0.998562 0.02155 -0.0461086 -0.998489 0.029912 -0.0431237 -0.998332 0.0383757 -0.0396576 -0.997999 0.0492393 -0.0371638 -0.997663 0.0573439 -0.0274071 -0.995528 0.0903994 -0.0353025 -0.994445 0.0991646 -0.0159469 -0.996705 0.0795264 -0.00559714 -0.997503 0.0704061 0.00146176 -0.997903 0.0647164 0.0142447 -0.99837 0.0552593 -0.00473732 -0.997745 0.066956 -0.0192852 -0.999713 0.014193 -0.0206238 -0.99978 0.00389894 -0.020829 -0.999765 -0.0060986 -0.0112639 -0.997505 -0.069698 0.0384251 -0.998353 -0.0426035 0.0236397 -0.998397 -0.0514255 0.00843744 -0.998089 -0.0612089 -0.000551793 -0.997676 -0.0681401 -0.00755805 -0.997256 -0.0736408 -0.018783 -0.996302 -0.0838405 -0.0349245 -0.997182 -0.0663967 -0.0384812 -0.997747 -0.0549498 -0.0410279 -0.998058 -0.0468764 -0.0450035 -0.998368 -0.0351456 -0.0478627 -0.99848 -0.0273275 -0.0338611 -0.997337 -0.0645895 -0.0316624 -0.999442 -0.0106684 -0.0316017 -0.999498 -0.00208428 -0.00287163 -0.445605 -0.895225 0.0020693 -0.467043 -0.884232 0.00049599 -0.451916 -0.892061 -0.000560612 -0.410762 -0.911743 0.00368325 -0.544768 -0.838579 -0.000370146 -0.510987 -0.859588 9.98471e-05 -0.501738 -0.86502 -0.00025097 -0.487809 -0.87295 0.00321073 -0.461724 -0.887018 0.00978655 -0.578493 -0.815629 0.0146256 -0.584149 -0.811515 -0.0129511 -0.517781 -0.855415 -0.00650015 -0.639496 -0.768767 -0.00142461 -0.631109 -0.775693 0.000647898 -0.663311 -0.748343 -0.0025592 -0.676503 -0.736436 0.0019321 -0.776815 -0.629726 -0.0391861 -0.821368 -0.56905 0.009563 -0.821954 -0.569474 -0.0104131 -0.785387 -0.618918 -0.0135951 -0.781543 -0.623703 -0.0103352 -0.776722 -0.629759 0.0236076 -0.719622 -0.693965 -0.0126287 -0.745912 -0.665925 0.0032667 -0.694611 -0.719378 -0.0157909 -0.85205 -0.523221 -0.00923915 -0.845846 -0.533347 -0.0135749 -0.849965 -0.526664 -0.0052531 -0.860906 -0.508737 0.0146969 -0.913632 -0.406277 -0.000559199 -0.937746 -0.347322 -0.000273491 -0.937985 -0.346676 0.000453613 -0.925229 -0.37941 -0.00660911 -0.905471 -0.424357 -0.0216202 -0.913503 -0.406258 0.00655035 -0.886996 -0.461731 0.0283803 -0.886653 -0.461563 0.0140471 -0.991712 -0.127712 0.0061913 -0.989374 -0.145259 0.000966842 -0.986721 -0.16242 -0.0005932 -0.981769 -0.190078 0.000999033 -0.953363 -0.301825 -0.00347035 -0.957134 -0.289624 -0.003104 -0.956829 -0.290633 0.000342543 -0.963079 -0.269218 0.000209055 -0.972376 -0.233421 -0.00209468 -0.971125 -0.238562 0.0018797 -0.980733 -0.195344 0.0154363 -0.98062 -0.195312 -0.00543018 -0.988458 -0.1514 -0.00173012 -0.98847 -0.151406 -0.00965901 -0.985418 -0.169878 -0.0126226 -0.984458 -0.175169 -0.00740498 -0.999886 -0.0131339 -0.0260743 -0.998083 -0.0561264 -0.0177556 -0.998668 -0.0484353 0.00121807 -0.992137 -0.125147 -0.000753622 -0.993324 -0.115358 -9.22134e-05 -0.992937 -0.118643 0.000252208 -0.994317 -0.106458 -0.000179786 -0.994877 -0.101095 0.000632786 -0.996847 -0.0793413 0.0176304 -0.997416 -0.069648 -0.0079757 -0.999463 -0.0317932 -0.00729465 -0.999303 -0.0366023 0.00576548 -0.999965 0.00607415 -0.0109628 -0.997545 -0.0691603 -0.694618 -0.717656 -0.0497554 0.00300714 -0.999283 -0.0377498 -0.0196729 -0.987618 -0.155642 -0.0152374 -0.991148 -0.131887 -0.0443617 -0.996586 -0.0696305 -0.0503089 -0.996163 -0.0716066 -0.0339151 -0.997503 -0.0619451 -0.0426691 -0.98424 -0.171611 0.108677 -0.959612 -0.259488 -0.122417 -0.969751 -0.21118 0.0311372 -0.944701 -0.32645 -0.0562184 -0.926311 -0.372542 -0.0119794 -0.914021 -0.405491 -0.011612 -0.887978 -0.459739 -0.0534602 -0.875853 -0.479608 0.0218627 -0.845367 -0.533738 -0.0525124 -0.812832 -0.580126 0.0362663 -0.781904 -0.622343 -0.0503441 -0.738247 -0.672649 0.0389915 -0.702307 -0.710806 -0.00384624 -0.458875 -0.888493 -0.00540065 -0.475482 -0.879709 -0.00385965 -0.462845 -0.886431 -0.00319755 -0.494337 -0.869264 -0.00313648 -0.525939 -0.850516 -0.00555711 -0.559073 -0.8291 -0.00684687 -0.571088 -0.82086 -0.00643025 -0.567504 -0.823346 0.00012414 -0.993497 0.113854 -0.00694233 -0.99989 -0.0131345 -0.00702328 -0.999889 0.0131166 -0.00706184 -0.999881 0.0137313 -0.0443516 -0.998511 0.0317629 0.0184579 -0.995667 0.0911355 0.010038 -0.996809 0.0791951 -0.00729494 -0.999343 0.0355051 -0.00867104 -0.999167 0.0398656 0.00123573 -0.998022 0.0628467 0.00594822 -0.997368 0.072267 0.00682603 -0.998991 0.0443866 0.0138255 -0.996995 0.0762225 -0.0325271 -0.998482 0.0444517 -0.007818 -0.997061 0.0762137 -0.000862003 -0.994317 0.106458 -7.33372e-05 -0.993497 0.113856 0.00163761 -0.99013 0.140144 -0.00455374 -0.988233 0.152886 0.0244676 -0.975692 0.217774 0.0067535 -0.975964 0.217825 -0.00400928 -0.983554 0.180571 -0.000515605 -0.982034 0.188705 0.000536953 -0.985434 0.170056 -0.000624313 -0.987361 0.158485 0.00685686 -0.991568 0.129404 -0.011258 -0.953327 0.301729 0.001644 -0.95339 0.301737 -0.00896269 -0.96304 0.269208 0.00342878 -0.955653 0.294477 -0.0028082 -0.971389 0.237477 -0.909916 -0.379558 0.167298 0.00511061 -0.919877 0.392174 -0.000682468 -0.85875 0.512394 0.0022065 -0.887637 0.460538 -0.0016776 -0.937776 0.347236 -0.00691201 -0.933672 0.358061 -0.00366341 -0.936235 0.351356 0.000492703 -0.925229 0.37941 -0.000288603 -0.913711 0.406366 -0.00246139 -0.916391 0.400277 0.00563463 -0.890036 0.455854 0.0327602 -0.889568 0.455626 -0.0221834 -0.8092 0.587114 -0.00192205 -0.860916 0.508743 -7.20518e-06 -0.852344 0.522981 0.0043154 -0.832066 0.55466 -0.00444281 -0.840525 0.541754 0.00268485 -0.809389 0.587267 -0.0033711 -0.797716 0.603024 0.000289261 -0.785429 0.618951 -0.000174885 -0.760687 0.649119 0.010103 -0.745176 0.666792 -0.00289838 -0.720786 0.693151 0.00131251 -0.698379 0.715727 -0.0023591 -0.679956 0.73325 -0.0115612 -0.668673 0.743467 0.00578208 -0.641741 0.766899 -0.00298916 -0.678255 0.734821 -0.00616407 -0.657888 0.753091 0.0110619 -0.606667 0.794879 0.00505116 -0.599397 0.800436 -0.00321207 -0.543854 0.839173 0.00397949 -0.559805 0.828615 -0.00229008 -0.526057 0.850446 -0.00392921 -0.463596 0.886038 -0.00288611 -0.448723 0.893666 -0.00184384 -0.431889 0.901925 -0.000582116 -0.426518 0.904479 0.00244333 -0.4408 0.897602 0.00729341 -0.47902 0.877774 -0.00512545 -0.512647 0.858584 0.00466621 -0.454608 0.890679 -0.00440215 -0.495905 0.868366 0.0050977 -0.451304 0.892356 0.00052596 -0.571544 0.820571 -0.0158147 -0.631898 0.77489 -0.00830668 -0.588007 0.808813 -0.00402321 -0.54721 0.836986 -0.00217596 -0.467201 0.884149 -0.00923857 -0.508361 0.861095 -0.00609354 -0.48556 0.874182 -0.0206565 -0.998527 0.0501654 -0.0363884 -0.997389 0.0623814 -0.0458893 -0.996705 0.0668823 -0.0213274 -0.993428 0.11245 -0.0163096 -0.990969 0.133093 -0.0378858 -0.744682 0.666343 0.00764848 -0.74519 0.666808 -0.00131251 -0.698379 0.715727 0.0104133 -0.785387 0.618918 0.0135951 -0.781543 0.623703 -0.0248564 -0.721255 0.692223 0.00514579 -0.795356 0.606121 -0.00248747 -0.809396 0.587258 0.00212324 -0.83263 0.553826 -0.00254219 -0.84053 0.541758 7.20518e-06 -0.852344 0.522981 0.00267185 -0.86421 0.503125 0.00525309 -0.860906 0.508737 -0.00800189 -0.890022 0.455848 -0.0328963 -0.889564 0.455624 -0.00513794 -0.919877 0.392174 0.0246959 -0.914725 0.403322 0.0331638 -0.9193 0.392157 0.00660906 -0.905471 0.424357 -0.000453612 -0.925229 0.37941 0.000322921 -0.93881 0.344434 0.0016783 -0.937773 0.347245 -0.0190493 -0.99274 0.11876 -0.00796753 -0.990202 0.139412 -0.00096684 -0.986721 0.16242 0.000515604 -0.982034 0.188705 -0.00164316 -0.953386 0.301748 0.00277926 -0.957557 0.28823 0.00273556 -0.957521 0.288351 -0.000342543 -0.963079 0.269218 -0.000201187 -0.972881 0.231304 -0.0067535 -0.975964 0.217825 0.0040093 -0.983554 0.180571 -0.00662283 -0.983545 0.180539 0.0120816 -0.990059 0.140134 -0.00308763 -0.990125 0.140152 0.00965899 -0.985418 0.169878 0.0126225 -0.984458 0.175169 0.0264794 -0.998144 0.0548404 0.0178963 -0.998728 0.0471378 0.00729493 -0.999343 0.0355051 -0.0259331 -0.99722 -0.0698622 -0.00342059 -0.999985 0.00435654 0.00105794 -0.993497 0.113854 0.000753622 -0.993324 0.115358 9.22062e-05 -0.992937 0.118643 -0.000252216 -0.994317 0.106458 -8.71823e-05 -0.994534 0.10441 1.95967e-05 -0.995303 0.0968103 0.00741572 -0.999887 0.0131166 -0.0138174 -0.996995 0.0762225 -0.00685039 -0.998991 0.0443865 0.0130068 -0.997007 0.0762063 0.00926346 -0.99897 0.0444215 0.00817423 -0.999461 0.0317932 0.0215784 -0.987629 0.155318 0.0148282 -0.991124 0.132112 0.0408144 -0.996925 0.0668975 0.051423 -0.996197 0.0703436 0.0345677 -0.997559 0.0606741 -0.0296847 -0.944743 0.326465 0.109773 -0.971195 0.211495 -0.0945188 -0.962209 0.255381 0.042845 -0.984704 0.168888 0.0256782 -0.985283 0.168991 0.0259572 -0.995631 0.0896985 0.0326345 -0.99653 0.0765649 0.0120513 -0.914984 0.403309 0.0547454 -0.928153 0.36815 0.0199743 -0.929357 0.368642 0.0237054 -0.966275 0.256419 0.0234029 -0.965938 0.257714 0.0253365 -0.985002 0.170671 0.0079299 -0.983473 0.180879 0.0116839 -0.889071 0.457621 0.0517647 -0.878211 0.475464 -0.0212469 -0.845379 0.533745 0.0531413 -0.815569 0.576214 -0.0368359 -0.781888 0.622329 0.0510271 -0.741437 0.669079 -0.0395628 -0.702291 0.71079 0.00547224 -0.56162 0.827377 0.00655818 -0.57154 0.820548 -0.00321024 -0.46172 0.88702 0.000560688 -0.410817 0.911718 0.00419194 -0.495905 0.868366 -0.00514573 -0.451304 0.892355 -0.00296142 -0.443016 0.896509 -0.000598677 -0.432106 0.901823 0.0027307 -0.446325 0.894867 0.00360961 -0.459241 0.888305 0.00430838 -0.467199 0.884142 0.00341638 -0.484457 0.874808 0.00309029 -0.52596 0.850504 0.0121258 -0.519826 0.854186 -0.00252261 -0.545181 0.838315 0.00104891 -0.503797 0.863822 -0.000326306 -0.510622 0.859805 0.000250993 -0.487809 0.87295 0.00235779 -0.679962 0.733243 0.00846863 -0.663297 0.748309 -0.00163325 -0.678257 0.734823 0.00142204 -0.631109 0.775693 -0.0130776 -0.606658 0.794856 -0.00261887 -0.586718 0.809787 0.00230751 -0.543856 0.839176 0.00330325 -0.462846 -0.886433 0.00730002 -0.49096 -0.871152 0.00580077 -0.478725 -0.877946 -0.000404006 -0.450759 -0.892646 0.00419198 -0.463258 -0.886214 0.00304894 -0.448131 -0.893963 0.00187108 -0.430593 -0.902544 -0.0012708 -0.45984 -0.888001 -0.0039548 -0.474357 -0.880324 -0.00153668 -0.467042 -0.884234 0.000137509 -0.494232 -0.86933 -0.000473548 -0.512652 -0.858597 0.00521354 -0.567507 -0.823352 0.00874514 -0.587913 -0.808877 0.00419969 -0.547147 -0.837026 0.0170609 -0.989276 -0.145059 0.0250668 -0.986896 -0.159398 0.0426691 -0.98424 -0.171611 0.0250372 -0.984828 -0.171717 0.0194839 -0.989198 -0.145283 0.00647165 -0.992117 -0.125145 -0.00301824 -0.999283 -0.0377495 0.00702328 -0.999889 0.0131171 0.00694233 -0.99989 -0.013134 0.00698289 -0.99988 -0.0138643 0.000862012 -0.994317 -0.106458 -0.000302246 -0.993763 -0.11151 -0.01187 -0.996579 -0.0817943 0.0232971 -0.999223 -0.0317855 0.000774355 -0.997605 -0.0691644 0.694618 -0.717657 -0.0497555 -0.0176304 -0.997416 -0.069648 0.00729464 -0.999303 -0.0366023 0.00845041 -0.999149 -0.0403778 -0.00123573 -0.998022 -0.0628467 -0.00751791 -0.997125 -0.0754033 0.0204344 -0.998466 -0.0514643 0.0356831 -0.997334 -0.0636532 0.0479595 -0.99642 -0.0696186 0.0240334 -0.993636 -0.110049 0.016634 -0.990986 -0.132927 -0.0123827 -0.992936 -0.118001 -0.00113081 -0.992139 -0.125139 0.00383534 -0.988465 -0.151401 0.00455374 -0.988233 -0.152886 -0.0117619 -0.971056 -0.238561 0.00209468 -0.971125 -0.238562 -0.0018797 -0.980733 -0.195344 0.000593199 -0.981769 -0.190078 -0.000536952 -0.985434 -0.170056 0.000624312 -0.987361 -0.158485 -0.00516188 -0.990695 -0.136006 0.011184 -0.953304 -0.301806 -0.0009994 -0.953366 -0.301814 0.0109224 -0.963022 -0.269202 -0.0036801 -0.954947 -0.296755 0.00257427 -0.97086 -0.239632 0.000558849 -0.937749 -0.347312 0.00578 -0.933268 -0.359133 0.00333399 -0.935394 -0.353592 -0.000492702 -0.925229 -0.37941 0.000352258 -0.912737 -0.408547 0.00123526 -0.913724 -0.406335 -0.00272452 -0.887013 -0.461737 -0.0285685 -0.886649 -0.46156 0.00113809 -0.852156 -0.523287 0.0168069 -0.852015 -0.523248 0.0264577 -0.860617 -0.508566 0.00207024 -0.843784 -0.536679 -0.0020907 -0.886536 -0.462654 -0.0094045 -0.821962 -0.569465 0.00512943 -0.794242 -0.60758 0.012093 -0.780309 -0.625278 0.0172249 -0.785313 -0.618859 0.0151797 -0.694542 -0.719292 -0.00835953 -0.745945 -0.665955 0.0111603 -0.776712 -0.629758 -0.0019321 -0.776815 -0.629726 0.0115589 -0.668668 -0.743471 -0.00578799 -0.64174 -0.766901 0.00860115 -0.700748 -0.713357 0.00617021 -0.6579 -0.75308 -0.000132726 -0.639514 -0.76878 3.29667e-05 -0.600267 -0.799799 -0.0125304 -0.578471 -0.815606 -0.00795691 -0.568528 -0.822625 -0.00351244 -0.557322 -0.830289 0.0022903 -0.526056 -0.850447 0.0003238 -0.11637 -0.993206 -0.00710102 -0.0691352 -0.997582 -0.00483154 -0.0857586 -0.996304 -0.00231846 -0.105805 -0.994384 4.44969e-05 -0.445567 -0.895249 -0.00131109 -0.425856 -0.90479 -1.92012e-05 -0.382756 -0.923849 -0.00161808 -0.351404 -0.936222 -0.000375621 -0.306179 -0.951974 -0.000491267 -0.235197 -0.971948 3.30569e-05 -0.228121 -0.973633 -0.000199744 -0.122849 -0.992425 -0.000761642 -0.127177 -0.99188 -4.57928e-06 -0.121357 -0.992609 -1.27476e-06 -0.121345 -0.99261 0 -0.121342 -0.992611 -0.00280392 -0.0243386 -0.9997 -0.000353598 -0.0191732 -0.999816 -8.31533e-07 -0.0345518 -0.999403 -4.10408e-08 -0.0345167 -0.999404 -0.000510258 -0.0261894 -0.999657 -0.00908712 -0.0405374 -0.999137 2.71114e-06 -0.0549383 -0.99849 5.31651e-05 -0.0454268 -0.998968 0.000378894 -0.0317198 -0.999497 0.000727189 -0.0236014 -0.999721 0.000922084 -0.0194661 -0.99981 0.00108057 -0.0199241 -0.999801 0 -0.121342 -0.992611 1.27476e-06 -0.121345 -0.99261 4.57874e-06 -0.121357 -0.992609 1.26469e-05 -0.0630381 -0.998011 0.000813122 -0.11637 -0.993206 0.00386086 -0.0933076 -0.99563 0.000199724 -0.122858 -0.992424 -4.89015e-05 -0.235197 -0.971948 0.000502539 -0.228121 -0.973633 0.000375621 -0.306179 -0.951974 0.00161808 -0.351404 -0.936222 1.92012e-05 -0.382756 -0.923849 0.00110426 -0.419012 -0.90798 0.00059545 -0.436288 -0.899807 0 -0.0765734 0.997064 0.00115538 -0.423799 0.905755 0.000928025 -0.355994 0.934488 0.000526032 -0.351075 0.936347 0.000336225 -0.239933 0.970789 0.000160413 -0.237665 0.971347 4.51928e-05 -0.126516 0.991965 0.000611021 -0.130471 0.991452 4.49018e-06 -0.076747 0.997051 1.22942e-06 -0.0766023 0.997062 0.000122438 -0.0466975 0.998909 -1.79254e-05 -0.0589884 0.998259 0.000324213 -0.12117 0.992632 0.00519853 -0.0870636 0.996189 0.0021187 -0.110541 0.993869 0.002787 -0.0290839 0.999573 0.000371508 -0.0239933 0.999712 0.00825616 -0.0432764 0.999029 0.000571914 -0.0299121 0.999552 8.25139e-08 -0.0393097 0.999227 -2.80107e-05 -0.0549669 0.998488 -0.000122438 -0.0466975 0.998909 -0.000426334 -0.0353503 0.999375 -0.00072304 -0.0283869 0.999597 0 -0.0765734 0.997064 -1.22942e-06 -0.0766023 0.997062 -0.00121744 -0.130471 0.991451 -4.58891e-06 -0.126232 0.992001 1.08891e-05 -0.0629951 0.998014 -0.000517371 -0.12117 0.992632 -0.00428727 -0.0938687 0.995575 -0.00114403 -0.420424 0.907327 -0.000911586 -0.351075 0.936347 -0.000534456 -0.355994 0.934488 -0.000332362 -0.237665 0.971347 -0.000162776 -0.239933 0.970789 -4.51928e-05 -0.126516 0.991965 -0.000684878 -0.121595 0.99258 -0.0257624 -0.991674 0.12617 -0.025243 -0.991402 0.128393 -0.0246638 -0.990605 0.134515 -0.0217096 -0.991792 0.126002 -0.0218105 -0.991603 0.127465 -0.0201323 -0.962746 0.269657 -0.0225769 -0.985802 0.166385 -0.0226766 -0.990154 0.138133 -0.0236247 -0.991614 0.127056 -0.0235175 -0.991452 0.128332 -0.0177416 -0.992007 0.124931 -0.0178563 -0.991798 0.126566 -0.0156213 -0.991846 0.126483 -0.0157487 -0.992043 0.124908 -0.00867331 -0.670957 0.741446 -0.0139002 -0.991944 0.12591 -0.0137758 -0.992166 0.124164 -0.014781 -0.990811 0.134446 -0.0115605 -0.774931 0.63194 -0.0144758 -0.855904 0.516932 -0.0175438 -0.927539 0.373313 -0.0187352 -0.99053 0.136013 -0.0196964 -0.991856 0.125832 -0.0195738 -0.991669 0.12732 -0.00983689 -0.992276 0.123661 -0.00996341 -0.992055 0.125409 -0.00844101 -0.942805 0.333237 -0.00684617 -0.990221 0.13934 -0.00667467 -0.990394 0.138115 -0.00581865 -0.991305 0.131456 -0.00890984 -0.991816 0.127365 -0.00893737 -0.989638 0.143304 -0.00587534 -0.990643 0.136356 -0.00589867 -0.989111 0.14705 0.0155105 -0.989401 0.14438 0.001892 -0.988329 0.152321 -0.0146748 -0.988229 0.152274 -0.010402 -0.98928 0.14566 -0.00673523 -0.987815 0.155484 -0.0098713 -0.987267 0.158765 -0.0101003 -0.987339 0.158304 -0.00457489 -0.984908 0.173017 -0.0267395 -0.991939 0.123861 -0.027592 -0.995952 0.0855438 -0.0272943 -0.991915 0.123934 -0.0284235 -0.985553 0.166963 -0.0272934 -0.990926 0.13161 -0.0274367 -0.991174 0.129696 -0.0312995 -0.98991 0.138196 -0.0315517 -0.990142 0.136465 -0.0313815 -0.989809 0.138902 -0.0341344 -0.980861 0.191692 -0.0297031 -0.990609 0.13346 -0.0291083 -0.991115 0.129783 -0.0186809 -0.966377 0.256448 -0.0206629 -0.970093 0.241854 -0.0227508 -0.975318 0.219629 -0.0241213 -0.98931 0.14382 -0.0259434 -0.988978 0.145771 -0.0223157 -0.984879 0.171802 -0.0228974 -0.98535 0.169003 -0.0239508 -0.9796 0.199525 -0.0224449 -0.974525 0.223155 -0.0573458 -0.953355 0.296355 -0.0232326 -0.954482 0.297364 -0.0174231 -0.933148 0.359071 -0.0157868 -0.929426 0.368672 -0.0174749 -0.921239 0.388605 -0.0166954 -0.869044 0.494454 -0.0242154 -0.871437 0.489909 -0.0167243 -0.867514 0.497132 -0.0187111 -0.87548 0.482892 -0.017759 -0.876345 0.481356 -0.0175837 -0.875528 0.482847 -0.0174368 -0.868214 0.495884 -0.0181582 -0.869375 0.493818 -0.0186777 -0.870431 0.491935 -0.0187883 -0.875583 0.482702 -0.016377 -0.856703 0.515551 -0.0155948 -0.864813 0.501852 -0.0137982 -0.881262 0.472427 -0.0147779 -0.873918 0.485849 -0.0130601 -0.883796 0.46769 -0.0144318 -0.879291 0.476066 -0.0171529 -0.896759 0.442186 -0.0181959 -0.909729 0.414804 -0.0177702 -0.893317 0.449076 -0.00819705 -0.882418 0.470396 -0.00602217 -0.882831 0.469652 -0.0108697 -0.881494 0.47207 -0.00419265 -0.891625 0.452756 -0.0120023 -0.873128 0.487343 -0.00968542 -0.882823 0.469606 -0.0073554 -0.896797 0.442382 -0.00672672 -0.881708 0.471748 -0.00686781 -0.9002 0.435422 -0.00637436 -0.903754 0.428005 -0.005653 -0.909158 0.416412 -0.00551561 -0.883293 0.468789 -0.0066043 -0.884157 0.467143 -0.00811033 -0.88206 0.471067 -0.00793991 -0.881628 0.471878 -0.00803588 -0.892284 0.451402 -0.00871818 -0.888149 0.459474 -0.00919669 -0.885441 0.46466 -0.00915079 -0.881024 0.472982 -0.0105698 -0.881053 0.472899 -0.0103722 -0.880513 0.473909 -0.0103603 -0.879502 0.475782 -0.0110327 -0.876638 0.481023 -0.0115132 -0.874815 0.48432 -0.0115833 -0.880141 0.474571 -0.0143354 -0.867999 0.496358 -0.0140074 -0.879035 0.476551 -0.0138428 -0.868707 0.495133 -0.0133572 -0.869576 0.493618 -0.0126778 -0.871122 0.490904 -0.0127943 -0.879123 0.476423 -0.0130078 -0.879775 0.475213 -0.0154085 -0.878199 0.478047 -0.015204 -0.877464 0.479402 -0.0150285 -0.867338 0.497493 -0.0157212 -0.867149 0.497801 0.00284552 -0.863369 0.504564 -0.0254239 -0.93599 0.351107 -0.0316426 -0.937785 0.34577 -0.0124096 -0.945386 0.325716 -0.0176964 -0.943233 0.331659 -0.0124356 -0.895855 0.444172 -0.0185237 -0.893943 0.447797 -0.039786 -0.903522 0.426691 0.0111372 -0.891131 0.453609 -0.00489958 -0.923519 0.38352 -0.0087442 -0.928257 0.371837 0.00249015 -0.930611 0.366001 0.00161154 -0.973266 0.229676 -0.0243324 -0.956703 0.290047 0.00751443 -0.957161 0.289459 -0.0206528 -0.96883 0.246863 -0.0320228 -0.971352 0.23548 -0.0197253 -0.974344 0.224198 -0.00291744 -0.979968 0.199135 -0.000161984 -0.864595 -0.502469 -9.59249e-05 -0.867605 -0.497254 -9.12597e-05 -0.828149 -0.560508 -7.67407e-05 -0.828206 -0.560424 -6.94502e-05 -0.754387 -0.65643 -5.62216e-05 -0.754449 -0.656359 -4.94099e-05 -0.668653 -0.743574 -0.028015 -0.995273 -0.0929883 -0.0273457 -0.995356 -0.0923006 -0.027023 -0.984777 -0.171708 -0.025415 -0.986691 -0.160609 -0.0248016 -0.965045 -0.26091 -0.0228382 -0.968692 -0.247213 -0.0217843 -0.927553 -0.373057 -0.0196119 -0.933429 -0.358225 -0.0183341 -0.876953 -0.480227 -0.0160941 -0.884852 -0.465594 -0.0147112 -0.813858 -0.580877 -0.0125327 -0.823212 -0.567595 -0.0111669 -0.739129 -0.673472 -0.00916318 -0.749109 -0.662384 -0.00822066 -0.676751 -0.736167 -0.00913918 -0.663455 -0.74816 -0.00692114 -0.643733 -0.765219 -0.00483109 -0.601578 -0.798799 -2.95833e-06 -0.116674 -0.99317 -2.50134e-05 -0.11637 -0.993206 -5.34422e-05 -0.236343 -0.97167 -0.000137427 -0.235197 -0.971948 -0.000212555 -0.353707 -0.935356 -0.000385925 -0.351404 -0.936224 -0.000522124 -0.466364 -0.884593 -0.000799108 -0.462846 -0.886439 -0.00100202 -0.572052 -0.820217 -0.00138412 -0.56751 -0.823366 -0.00167171 -0.677148 -0.735845 -0.00421109 -0.663471 -0.74819 -0.00483166 -0.754389 -0.65641 -0.00592945 -0.749123 -0.662404 -0.00660284 -0.828143 -0.560477 -0.00779798 -0.823247 -0.567629 -0.00847031 -0.889013 -0.457804 -0.00969681 -0.88492 -0.465641 -0.0103101 -0.93655 -0.350381 -0.0114937 -0.933543 -0.358282 -0.0119938 -0.970695 -0.240015 -0.0130547 -0.968859 -0.247269 -0.0133379 -0.987856 -0.1548 -0.0141999 -0.986909 -0.160654 -0.0143799 -0.997975 -0.0619635 -0.015168 -0.997794 -0.0646268 -0.0151732 -0.998113 0.059503 -0.0144091 -0.997968 0.0620699 -0.0113455 -0.793668 0.608245 -0.0063382 -0.579692 0.814811 -0.0108356 -0.991022 0.133258 -0.0118181 -0.992205 0.124053 -0.0116738 -0.991978 0.12587 -5.69901e-05 -0.757595 0.652725 -7.03018e-05 -0.757657 0.652653 -7.75946e-05 -0.830848 0.556499 -9.19661e-05 -0.830904 0.556415 -9.63375e-05 -0.867678 0.497126 0 -0.864953 0.501854 -3.61808e-06 -0.12117 0.992632 -2.75039e-05 -0.121498 0.992592 -5.70635e-05 -0.239933 0.97079 -0.000145363 -0.241122 0.970495 -0.000220406 -0.355994 0.934488 -0.000402128 -0.358347 0.933589 -0.000533807 -0.4672 0.884152 -0.000826097 -0.470765 0.882259 -0.00101628 -0.571546 0.82057 -0.0014232 -0.576121 0.817363 -0.00486323 -0.75234 0.658757 -0.00604743 -0.757595 0.652697 -0.00663485 -0.825977 0.563664 -0.0079244 -0.830837 0.556459 -0.00848193 -0.88503 0.465456 -0.00600427 -0.878687 0.477361 -0.00916081 -0.742363 0.669935 -0.0114675 -0.752307 0.658714 -0.0125209 -0.81665 0.576997 -0.0150379 -0.82591 0.563601 -0.0157727 -0.863449 0.504189 -0.0189402 -0.871044 0.490839 0.00494746 -0.601558 0.798814 0.00674437 -0.643742 0.765213 0.00920787 -0.667109 0.744903 0.00832301 -0.678636 0.734427 0.0092922 -0.752321 0.658731 0.0113052 -0.742347 0.66992 0.0126738 -0.825935 0.563623 0.014857 -0.816625 0.576978 0.0157436 -0.861969 0.506717 0.0156824 -0.864908 0.501686 0.0133583 -0.858504 0.512633 0.0088858 -0.923742 0.382912 0.00787465 -0.825971 0.563658 0.00667689 -0.830842 0.556468 0.00600248 -0.752337 0.658752 0.00489963 -0.757597 0.652704 0.00427599 -0.667126 0.744933 0.00170154 -0.68093 0.732347 0.00141109 -0.571546 0.820569 0.00102494 -0.576121 0.817364 0.000819386 -0.4672 0.884151 0.000538127 -0.470765 0.882259 0.000399287 -0.355994 0.934488 0.000221944 -0.358347 0.933589 0.000144587 -0.239933 0.970789 5.73605e-05 -0.241122 0.970495 2.7422e-05 -0.12117 0.992632 3.62805e-06 -0.121498 0.992592 1.13242e-06 -0.0393564 0.999225 -1.13191e-06 -0.0393393 0.999226 -1.0974e-07 -0.0393093 0.999227 -0.000917896 -0.0242245 0.999706 -0.00109184 -0.0247271 0.999694 -0.0178749 -0.989299 0.144802 -0.0275133 -0.986877 0.159114 -0.0428451 -0.984704 0.168888 0.0174511 -0.978078 0.207505 -0.0593984 -0.964843 0.256027 0.0304628 -0.949013 0.313763 -0.0576912 -0.927999 0.368088 0.0287135 -0.9065 0.421229 -0.0551811 -0.878051 0.475375 0.0351842 -0.851339 0.523434 -0.0529846 -0.815576 0.576219 0.0365697 -0.78318 0.620719 -0.0508389 -0.741444 0.669086 0.0410631 -0.702994 0.710009 -0.00832301 -0.678636 0.734427 -0.00920787 -0.667109 0.744903 -0.00427599 -0.667126 0.744933 -0.00170154 -0.68093 0.732347 -5.01696e-05 -0.672323 0.740258 5.01696e-05 -0.672323 0.740258 5.6995e-05 -0.757657 0.652653 7.02957e-05 -0.757595 0.652725 7.76002e-05 -0.830904 0.556415 9.19594e-05 -0.830848 0.556499 9.63786e-05 -0.868023 0.496524 0.0042146 -0.796052 0.605213 0.0152649 -0.857229 -0.514709 0.0155759 -0.858383 -0.512772 0.0148918 -0.823188 -0.567574 0.0123803 -0.813883 -0.580897 0.011328 -0.749094 -0.662367 0.00903299 -0.739144 -0.673487 0.00778234 -0.829497 -0.558457 0.00796783 -0.839951 -0.542603 0.00784766 -0.828138 -0.560469 0.00656094 -0.823254 -0.567636 0.00597409 -0.754387 -0.656403 0.00479559 -0.749127 -0.662409 0.00421109 -0.663471 -0.74819 0.00804819 -0.66346 -0.748168 0.0105107 -0.67545 -0.737331 -0.10706 -0.734899 -0.669673 0.113232 -0.699063 -0.706038 -0.0978994 -0.81001 -0.578186 0.114771 -0.778525 -0.617031 -0.0971743 -0.872926 -0.478077 0.11625 -0.846091 -0.520208 -0.0934192 -0.923698 -0.371556 0.129488 -0.899239 -0.417855 -0.106471 -0.959843 -0.25955 0.135651 -0.940677 -0.311007 -0.0178731 -0.978071 -0.207504 5.43975e-08 -0.0345165 -0.999404 8.31212e-07 -0.0345394 -0.999403 2.95045e-06 -0.11637 -0.993206 2.50854e-05 -0.116674 -0.99317 5.31705e-05 -0.235197 -0.971948 0.000138152 -0.236343 -0.97167 0.000211094 -0.351404 -0.936224 0.000388649 -0.353707 -0.935356 0.000517948 -0.462845 -0.886439 0.00080563 -0.466364 -0.884593 0.000993556 -0.56751 -0.823366 0.00139599 -0.572051 -0.820217 0.00167171 -0.677148 -0.735845 4.94099e-05 -0.668653 -0.743574 5.62167e-05 -0.754387 -0.65643 6.94562e-05 -0.754448 -0.656359 7.6735e-05 -0.828149 -0.560508 9.12665e-05 -0.828206 -0.560424 9.58319e-05 -0.866822 -0.498618 2.67442e-05 -0.859432 -0.51125 0.229354 -0.949966 0.212041 0.213714 -0.974054 0.0744715 0.209582 -0.958954 -0.191004 0.21065 -0.893223 -0.397214 0.144132 -0.462164 -0.875003 0.168593 -0.0754733 0.982792 0.199551 -0.666274 0.718511 0.321631 -0.434783 0.841141 0.503747 -0.462424 0.72966 0.550609 -0.45562 0.699457 0.310639 -0.569119 0.761319 0.552218 -0.534602 0.639731 0.401707 -0.617037 0.676681 0.668522 -0.446188 0.594974 0.564659 -0.0636605 0.822865 0.417913 -0.0699801 0.905788 0.998492 -0.0072043 0.05442 0.982818 -0.0822447 -0.165243 0.743298 -0.0893375 -0.662968 0.85528 -0.0638801 -0.514213 0.931364 -0.04489 -0.361312 0.16668 -0.119644 -0.978725 0.326992 -0.439276 -0.836727 0.514648 -0.419714 -0.747648 0.328788 -0.55164 -0.766545 0.141252 -0.754943 -0.640397 0.277681 -0.669755 -0.68871 0.517337 -0.574852 -0.633962 0.434052 -0.5691 -0.698372 0.488846 -0.497346 -0.716712 0.149686 -0.768058 -0.62264 0.485863 -0.237842 -0.841052 0.258925 -0.856755 -0.446013 0.243703 -0.864208 -0.440174 0.467248 -0.777209 -0.421457 0.419581 -0.746684 -0.516155 0.431336 -0.741308 -0.51421 0.499759 -0.193084 -0.844369 0.282795 -0.723955 -0.629219 0.258722 -0.720563 -0.643313 0.25888 -0.670926 -0.694866 0.259123 -0.869316 -0.420886 0.551253 -0.775395 -0.308029 0.36786 -0.878797 -0.303965 0.514691 -0.826528 -0.227914 0.233815 -0.950498 -0.204655 0.259192 -0.963479 -0.0672815 0.225709 -0.972747 -0.0530997 0.506688 -0.859143 -0.0716999 0.4089 -0.903739 -0.126716 0.54624 -0.825213 -0.143689 0.259243 -0.942994 -0.2087 0.259186 -0.937935 -0.230436 0.199727 -0.979152 -0.037013 0.258018 -0.95645 -0.136489 0.488845 -0.87237 0 0.533286 -0.845917 0.00557419 0.231854 -0.967984 0.0961827 0.259304 -0.964844 0.0428736 0.259301 -0.964048 0.0580948 0.45351 -0.88813 0.0745308 0.434899 -0.891756 0.125036 0.502449 -0.854732 0.130298 0.235267 -0.942216 0.238494 0.520031 -0.803303 0.290295 0.437278 -0.849921 0.293977 0.449535 -0.869567 0.204382 0.259193 -0.944609 0.201328 0.259256 -0.949937 0.174376 0.246514 -0.865318 0.436413 0.414322 -0.805659 0.42338 0.46685 -0.728457 0.501399 0.318608 -0.711942 0.625802 0.37188 -0.522289 0.767411 0.451858 -0.733828 0.507268 0.244996 -0.395316 0.885269 0.25852 -0.126035 0.957749 0.258521 -0.126035 0.957748 0.2584 -0.229591 0.938359 0.258408 -0.229594 0.938356 0.2584 -0.339148 0.904549 0.25842 -0.339154 0.90454 0.258549 -0.435959 0.862028 0.258571 -0.435966 0.862018 0.258872 -0.480013 0.838196 0.251366 -0.33899 0.906588 0.258829 -0.684971 0.681045 0.258921 -0.674556 0.691328 0.258937 -0.674568 0.69131 0.258667 -0.719847 0.644137 0.127383 -0.696423 0.706235 0.258861 -0.859703 0.440344 0.259145 -0.883739 0.389678 0.25915 -0.883744 0.389664 0.259158 -0.888455 0.378794 0.245967 -0.854785 0.456993 0.25885 -0.428099 -0.865868 0.258427 -0.36975 -0.892469 0.258407 -0.36976 -0.892471 0.258778 -0.295746 -0.919548 0.25877 -0.295756 -0.919547 0.258406 -0.220372 -0.940565 0.258399 -0.220375 -0.940566 0.258776 -0.145924 -0.954851 0.415181 -0.11084 -0.902962 0.561285 -0.100842 -0.821456 0.707087 -0.112405 -0.698136 0.70649 -0.161445 -0.689063 0.706495 -0.161446 -0.689058 0.707028 -0.216527 -0.673222 0.707027 -0.216527 -0.673223 0.706483 -0.270885 -0.653838 0.706494 -0.270886 -0.653825 0.706502 -0.346433 -0.617121 0.706519 -0.346433 -0.617102 0.706641 -0.413296 -0.574322 0.706653 -0.413295 -0.574307 0.706524 -0.475368 -0.52426 0.706549 -0.475362 -0.524232 0.706557 -0.534103 -0.464232 0.70658 -0.534094 -0.464206 0.70676 -0.58129 -0.403228 0.706782 -0.58128 -0.403203 0.706594 -0.622041 -0.337327 0.706622 -0.622024 -0.3373 0.70663 -0.657592 -0.26124 0.706655 -0.657575 -0.261218 0.706834 -0.681926 -0.188048 0.706851 -0.681913 -0.188033 0.706906 -0.696822 -0.121338 0.706971 -0.696763 -0.121298 0.706959 -0.704805 -0.0588223 0.706965 -0.704799 -0.0588193 0.706966 -0.707233 0.00466068 0.706964 -0.707234 0.00466015 0.707137 -0.7046 0.0591324 0.707132 -0.704605 0.0591297 0.707095 -0.699042 0.106569 0.70708 -0.699058 0.106563 0.706954 -0.688496 0.161832 0.706717 -0.688756 0.161757 0.706652 -0.66544 0.240483 0.706626 -0.665469 0.240478 0.707243 -0.646872 0.285242 0.70724 -0.646881 0.285231 0.706621 -0.626363 0.329173 0.706593 -0.626396 0.329172 0.706606 -0.582873 0.401207 0.706581 -0.582902 0.401209 0.706579 -0.531482 0.467196 0.706554 -0.531511 0.467202 0.70712 -0.493816 0.50609 0.707115 -0.493828 0.506086 0.706539 -0.453785 0.543031 0.706519 -0.453806 0.543039 0.706531 -0.386254 0.592978 0.706512 -0.386273 0.592988 0.706689 -0.319309 0.631373 0.70668 -0.319319 0.631379 0.706492 -0.248461 0.662674 0.706484 -0.248468 0.66268 0.706495 -0.168198 0.68744 0.706487 -0.168204 0.687447 0.706664 -0.0923134 0.701502 0.706667 -0.0923112 0.701499 0.699368 -0.203605 0.685149 0.924524 0.0699185 0.374657 0.683442 -0.714258 0.150807 0.950466 -0.0405515 0.308173 0.96589 -0.0550625 0.253029 0.965813 -0.061613 0.251811 0.965813 -0.0616127 0.251812 0.965811 -0.091014 0.242747 0.965812 -0.0910143 0.242741 0.965847 -0.116939 0.231226 0.965848 -0.116939 0.231222 0.965815 -0.141489 0.217214 0.965817 -0.141488 0.217207 0.965815 -0.166227 0.198923 0.965818 -0.166223 0.198909 0.965924 -0.180758 0.185251 0.965924 -0.180758 0.185249 0.96582 -0.194686 0.171139 0.965823 -0.194681 0.171128 0.965824 -0.213508 0.146966 0.965827 -0.213501 0.146954 0.965825 -0.229441 0.120579 0.965828 -0.229434 0.120571 0.965941 -0.236765 0.104407 0.965941 -0.236766 0.104399 0.965828 -0.243753 0.0880908 0.965832 -0.243743 0.0880816 0.965844 -0.252261 0.0592494 0.965887 -0.252119 0.0591451 0.965909 -0.255925 0.0390165 0.965911 -0.255919 0.039013 0.965917 -0.257944 0.0216477 0.965918 -0.257942 0.0216469 0.965886 -0.258961 0.00170733 0.965887 -0.258957 0.00170596 0.965887 -0.258066 -0.0215399 0.965885 -0.258074 -0.0215379 0.965887 -0.255125 -0.0444173 0.965878 -0.255161 -0.0444122 0.965868 -0.249713 -0.068863 0.965866 -0.249722 -0.0688611 0.965833 -0.240854 -0.0956848 0.96583 -0.240867 -0.0956844 0.965829 -0.227836 -0.123556 0.965824 -0.227853 -0.123557 0.965859 -0.212867 -0.147662 0.965857 -0.212875 -0.147663 0.965824 -0.195628 -0.170039 0.96582 -0.195644 -0.170044 0.965819 -0.174122 -0.192031 0.965816 -0.174131 -0.192035 0.96584 -0.151362 -0.210339 0.965838 -0.15137 -0.210344 0.965816 -0.126897 -0.226047 0.965815 -0.1269 -0.226049 0.965813 -0.0992239 -0.239499 0.965812 -0.0992286 -0.239503 0.965911 -0.0792586 -0.246441 0.965911 -0.0792622 -0.246443 0.965813 -0.0591371 -0.252405 0.965812 -0.0591394 -0.252408 0.965853 -0.0561326 -0.252938 0.998496 -0.00692732 -0.0543805 -0.322551 -0.552895 -0.768289 -0.219525 -0.677626 -0.701878 -0.216596 -0.948068 -0.232922 -0.217366 -0.973719 -0.0679959 -0.203269 -0.978158 0.0434625 -0.402019 -0.596024 0.69508 -0.416893 -0.0700041 0.906256 -0.73213 -0.190127 0.654092 -0.998492 -0.0072043 0.05442 -0.562752 -0.10072 -0.820467 -0.416207 -0.110782 -0.902496 -0.931365 -0.0448884 -0.36131 -0.856629 -0.0636041 -0.511997 -0.998496 -0.00692732 -0.0543805 -0.922488 0.085557 0.376425 -0.683486 -0.714212 0.150826 -0.950466 -0.0405535 0.308173 -0.139597 -0.548838 0.82419 -0.194779 -0.787127 0.585229 -0.274962 -0.668421 0.691093 -0.552218 -0.534602 0.639731 -0.505576 -0.545028 0.668833 -0.273609 -0.524986 0.805933 -0.572079 -0.467602 0.67385 -0.328657 -0.436171 0.837699 -0.398525 -0.68886 0.605516 -0.54035 -0.795215 0.275055 -0.435314 -0.84669 0.30597 -0.449528 -0.86957 0.204382 -0.236358 -0.95077 0.200427 -0.528666 -0.840607 0.117864 -0.259126 -0.942647 0.210408 -0.258906 -0.938094 0.230104 -0.201854 -0.96332 0.176834 -0.430663 -0.892206 0.136009 -0.453503 -0.888133 0.0745311 -0.224648 -0.972886 0.0550028 -0.254314 -0.957153 -0.138501 -0.488845 -0.87237 0 -0.533281 -0.84592 0.0055735 -0.259112 -0.961762 0.0887404 -0.259236 -0.963004 0.0736273 -0.259181 -0.947222 -0.188669 -0.22269 -0.95085 -0.215159 -0.546237 -0.825215 -0.143688 -0.4089 -0.903739 -0.126716 -0.506688 -0.859143 -0.0716999 -0.259268 -0.964209 -0.0555017 -0.259313 -0.965105 -0.0364585 -0.259242 -0.943267 -0.207464 -0.514683 -0.826533 -0.227916 -0.367854 -0.878799 -0.303966 -0.551246 -0.7754 -0.308031 -0.229622 -0.873456 -0.429359 -0.259102 -0.882521 -0.392457 -0.258994 -0.859981 -0.439722 -0.237388 -0.86165 -0.448561 -0.46724 -0.777212 -0.421459 -0.4188 -0.746145 -0.517565 -0.430935 -0.742295 -0.513121 -0.0507814 -0.775812 -0.628917 -0.51733 -0.574855 -0.633965 -0.415493 -0.621938 -0.663746 -0.258955 -0.681153 -0.684816 -0.258553 -0.729101 -0.63369 -0.289506 -0.714015 -0.63747 -0.499753 -0.193111 -0.844367 -0.393065 -0.468262 -0.791348 -0.184701 -0.411819 -0.892351 -0.31891 -0.439674 -0.839633 -0.514648 -0.419714 -0.747648 -0.433622 -0.482361 -0.761118 -0.493193 -0.520855 -0.696757 -0.258817 -0.0739643 0.96309 -0.258519 -0.126036 0.957749 -0.258521 -0.126034 0.957749 -0.2584 -0.229595 0.938358 -0.258408 -0.229591 0.938357 -0.2584 -0.339156 0.904546 -0.25842 -0.339146 0.904543 -0.258548 -0.435969 0.862023 -0.258571 -0.435956 0.862023 -0.256275 -0.350885 0.900668 -0.112685 -0.493199 0.862587 -0.258949 -0.656587 0.708406 -0.258921 -0.67457 0.691314 -0.258936 -0.674551 0.691326 -0.258855 -0.707413 0.657693 -0.178525 -0.73324 0.656115 -0.451851 -0.733831 0.50727 -0.466843 -0.72846 0.501402 -0.334391 -0.890294 0.309126 -0.279248 -0.850001 0.446676 -0.258861 -0.859702 0.440344 -0.259145 -0.883745 0.389665 -0.259149 -0.88374 0.389674 -0.258405 -0.854427 0.450757 -0.202883 -0.900753 0.384034 -0.965889 -0.0550634 0.253033 -0.965812 -0.0616133 0.251815 -0.965813 -0.0616117 0.251813 -0.965811 -0.0910165 0.242746 -0.965812 -0.0910119 0.242742 -0.965847 -0.11694 0.231225 -0.965848 -0.116937 0.231223 -0.965815 -0.141491 0.217213 -0.965817 -0.141486 0.217209 -0.965815 -0.166232 0.198919 -0.965817 -0.166223 0.198915 -0.965923 -0.180762 0.185253 -0.965924 -0.180753 0.185254 -0.96582 -0.194689 0.171135 -0.965823 -0.194678 0.171132 -0.965824 -0.213512 0.146962 -0.965826 -0.213502 0.14696 -0.965824 -0.229447 0.120577 -0.965827 -0.229432 0.120576 -0.965941 -0.236768 0.1044 -0.965941 -0.236763 0.104406 -0.965828 -0.243755 0.0880859 -0.965832 -0.243741 0.0880867 -0.965843 -0.25228 0.059183 -0.965886 -0.252106 0.0592131 -0.965909 -0.255925 0.039014 -0.965911 -0.255919 0.0390156 -0.965917 -0.257944 0.021647 -0.965918 -0.257942 0.0216476 -0.965886 -0.258961 0.00170599 -0.965886 -0.258961 0.00170601 -0.965886 -0.25807 -0.0215376 -0.965885 -0.258074 -0.0215393 -0.965887 -0.255127 -0.0444063 -0.965877 -0.255162 -0.044425 -0.965867 -0.249718 -0.0688601 -0.965866 -0.249721 -0.0688631 -0.965833 -0.240856 -0.0956801 -0.965829 -0.240868 -0.0956922 -0.965827 -0.227843 -0.123552 -0.965825 -0.22785 -0.123561 -0.965859 -0.212869 -0.147659 -0.965856 -0.212875 -0.14767 -0.965823 -0.195635 -0.170037 -0.96582 -0.19564 -0.170048 -0.965819 -0.174125 -0.192028 -0.965815 -0.174129 -0.192041 -0.965839 -0.151367 -0.21034 -0.965838 -0.151368 -0.210345 -0.965816 -0.126898 -0.226047 -0.965814 -0.126899 -0.226054 -0.965812 -0.0992278 -0.239501 -0.96581 -0.0992277 -0.239508 -0.96591 -0.0792627 -0.246444 -0.965911 -0.0792639 -0.246442 -0.965813 -0.0591386 -0.252404 -0.965812 -0.0591379 -0.252408 -0.965853 -0.0561326 -0.252938 -0.982815 -0.0822389 -0.165263 -0.746282 -0.0879274 -0.659797 -0.707089 -0.112787 -0.698072 -0.70649 -0.161447 -0.689062 -0.706492 -0.161445 -0.68906 -0.707025 -0.216531 -0.673223 -0.707029 -0.216524 -0.673221 -0.706485 -0.27089 -0.653833 -0.706494 -0.270882 -0.653827 -0.706502 -0.34644 -0.617117 -0.706517 -0.346426 -0.617109 -0.706638 -0.413305 -0.574318 -0.706655 -0.413286 -0.574311 -0.706526 -0.475377 -0.52425 -0.706549 -0.475352 -0.524242 -0.706557 -0.534113 -0.464221 -0.706582 -0.534084 -0.464215 -0.706762 -0.581296 -0.403216 -0.706782 -0.581272 -0.403215 -0.706594 -0.62205 -0.337312 -0.706624 -0.622015 -0.337313 -0.706632 -0.657595 -0.261227 -0.706654 -0.65757 -0.261231 -0.706834 -0.68193 -0.188036 -0.706853 -0.681908 -0.188044 -0.706907 -0.696826 -0.12131 -0.706968 -0.696761 -0.121326 -0.706956 -0.704807 -0.058819 -0.706965 -0.704799 -0.0588218 -0.706966 -0.707233 0.00465918 -0.706964 -0.707234 0.00465974 -0.707137 -0.7046 0.0591292 -0.707132 -0.704605 0.0591328 -0.707095 -0.699043 0.106561 -0.70708 -0.699057 0.106572 -0.706957 -0.688524 0.161702 -0.706721 -0.688722 0.161885 -0.706653 -0.665445 0.240469 -0.706627 -0.665464 0.240492 -0.707244 -0.646878 0.28523 -0.70724 -0.646876 0.285243 -0.706622 -0.62637 0.32916 -0.706596 -0.626386 0.329185 -0.706609 -0.58288 0.401192 -0.706581 -0.582893 0.401221 -0.70658 -0.531491 0.467185 -0.706555 -0.531501 0.467212 -0.70712 -0.493821 0.506085 -0.707115 -0.493817 0.506096 -0.706539 -0.453794 0.543022 -0.706517 -0.453799 0.543047 -0.706529 -0.386264 0.592973 -0.706512 -0.386265 0.592993 -0.706689 -0.319315 0.631371 -0.706678 -0.319313 0.631384 -0.70649 -0.248466 0.662674 -0.706482 -0.248465 0.662683 -0.706493 -0.168202 0.687441 -0.706489 -0.1682 0.687446 -0.706666 -0.0923128 0.701499 -0.706667 -0.092313 0.701499 -0.664171 -0.395729 0.634252 -0.563187 -0.0637216 0.823869 -0.258721 -0.451154 -0.854121 -0.258429 -0.369758 -0.892465 -0.258407 -0.369752 -0.892474 -0.258778 -0.295754 -0.919545 -0.258771 -0.295747 -0.91955 -0.258407 -0.220375 -0.940564 -0.258398 -0.220372 -0.940567 -0.258775 -0.145774 -0.954875 -0.167788 -0.119622 -0.978539 0 -0.340477 -0.940253 0 -0.340477 -0.940253 0 -0.461044 -0.887377 0 -0.461044 -0.887377 0 -0.542388 -0.840128 0 -0.542388 -0.840128 0 -0.648053 -0.761595 0 -0.648053 -0.761595 0 -0.71675 -0.69733 0 -0.71675 -0.69733 0 -0.790765 -0.61212 0 -0.790765 -0.61212 0 -0.854705 -0.519115 0 -0.854705 -0.519115 0 -0.899704 -0.436501 0 -0.899704 -0.436501 0 -0.949248 -0.314528 0 -0.949248 -0.314528 0 -0.974603 -0.223939 0 -0.974603 -0.223939 0 -0.995575 -0.0939661 0 -0.995575 -0.0939661 0 -0.995575 0.0939661 0 -0.995575 0.0939661 0 -0.974603 0.223939 0 -0.974603 0.223939 0 -0.949248 0.314528 0 -0.949248 0.314528 0 -0.899704 0.436501 0 -0.899704 0.436501 0 -0.854704 0.519115 0 -0.854704 0.519115 0 -0.790765 0.61212 0 -0.790765 0.61212 0 -0.71675 0.69733 0 -0.71675 0.69733 0 -0.648053 0.761595 0 -0.648053 0.761595 0 -0.542388 0.840128 0 -0.542388 0.840128 0 -0.461043 0.887378 0 -0.461043 0.887378 0 -0.340477 0.940253 0 -0.340477 0.940253 0 -0.340477 -0.940253 0 -0.340477 -0.940253 0 -0.461044 -0.887377 0 -0.461044 -0.887377 0 -0.542388 -0.840128 0 -0.542388 -0.840128 0 -0.648053 -0.761595 0 -0.648053 -0.761595 0 -0.71675 -0.69733 0 -0.71675 -0.69733 0 -0.790765 -0.61212 0 -0.790765 -0.61212 0 -0.854705 -0.519114 0 -0.854705 -0.519114 0 -0.899704 -0.436501 0 -0.899704 -0.436501 0 -0.949248 -0.314528 0 -0.949248 -0.314528 0 -0.974603 -0.223939 0 -0.974603 -0.223939 0 -0.995575 -0.0939661 0 -0.995575 -0.0939661 0 -0.995575 0.0939661 0 -0.995575 0.0939661 0 -0.974603 0.223939 0 -0.974603 0.223939 0 -0.949248 0.314528 0 -0.949248 0.314528 0 -0.899704 0.436501 0 -0.899704 0.436501 0 -0.854704 0.519115 0 -0.854704 0.519115 0 -0.790765 0.61212 0 -0.790765 0.61212 0 -0.71675 0.69733 0 -0.71675 0.69733 0 -0.648053 0.761595 0 -0.648053 0.761595 0 -0.542388 0.840128 0 -0.542388 0.840128 0 -0.461043 0.887378 0 -0.461043 0.887378 0 -0.340477 0.940253 0 -0.340477 0.940253 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.998683 0.00683413 -0.0508431 -0.998688 0.00640745 0.0508039 -0.920365 -0.124523 -0.370706 -0.575149 0.810867 -0.108155 -0.951494 0.0407492 -0.304958 -0.416908 0.0698313 -0.906262 -0.563209 0.0635478 -0.823867 -0.568815 0.0990194 0.816483 -0.422783 0.109098 0.89964 -0.930776 0.0405123 0.363339 -0.75589 0.0843305 0.649245 -0.258494 0.12795 -0.957502 -0.258817 0.0737327 -0.963108 -0.130462 0.634836 -0.761553 -0.258416 0.340058 -0.904202 -0.258595 0.245294 -0.934323 -0.276601 0.231189 -0.932761 -0.258798 0.190599 -0.94694 -0.258495 0.127949 -0.957502 -0.258625 0.797352 -0.545292 -0.258624 0.728692 -0.634131 -0.258567 0.728724 -0.634117 -0.258925 0.676623 -0.689304 -0.258907 0.676647 -0.689287 -0.258542 0.620168 -0.74064 -0.258496 0.620195 -0.740633 -0.258504 0.529665 -0.807856 -0.258465 0.529689 -0.807853 -0.258606 0.441971 -0.858944 -0.265534 0.436832 -0.859459 -0.258846 0.396784 -0.880659 -0.258434 0.340047 -0.904201 -0.298906 0.855343 -0.423136 -0.259025 0.839083 -0.478378 -0.258682 0.797321 -0.54531 -0.258735 0.855523 -0.448482 -0.259138 0.884544 -0.387851 -0.25915 0.884528 -0.387881 -0.258745 0.909509 -0.325338 -0.258799 0.909485 -0.325361 -0.258847 0.94061 -0.219663 -0.259033 0.940538 -0.219752 -0.259115 0.954867 -0.145218 -0.259144 0.954857 -0.145232 -0.259153 0.962584 -0.0791926 -0.259173 0.962578 -0.0792031 -0.259073 0.965851 -0.00363612 -0.259069 0.965852 -0.00363471 -0.259069 0.962356 0.0821803 -0.259046 0.962362 0.0821905 -0.259057 0.95142 0.166402 -0.258989 0.951433 0.166434 -0.259119 0.935501 0.2402 -0.277772 0.925576 0.2572 -0.259155 0.921773 0.288398 -0.258793 0.896627 0.359285 -0.258737 0.896629 0.35932 -0.259037 0.86141 0.436891 -0.284125 0.842389 0.457879 -0.258987 0.834363 0.486585 -0.25876 0.792598 0.552115 -0.258706 0.79259 0.552152 -0.258622 0.727188 0.635856 -0.258567 0.727179 0.635888 -0.258562 0.648179 0.716247 -0.258511 0.648167 0.716276 -0.258883 0.590816 0.764144 -0.278765 0.559409 0.780609 -0.258727 0.547872 0.795548 -0.258478 0.470366 0.843768 -0.258446 0.470354 0.843785 -0.258833 0.408767 0.875166 -0.276449 0.366956 0.888211 -0.258589 0.356847 0.897659 -0.258765 0.293686 0.920211 -0.258758 0.293678 0.920216 -0.965833 0.0611969 -0.251835 -0.965817 0.0623629 -0.251612 -0.965817 0.0623612 -0.251611 -0.965815 0.0912533 -0.242639 -0.965816 0.0912498 -0.242636 -0.96584 0.117412 -0.231012 -0.965841 0.117408 -0.23101 -0.965819 0.142132 -0.216775 -0.965822 0.142123 -0.216771 -0.96582 0.166419 -0.198739 -0.965822 0.166408 -0.198736 -0.96592 0.181324 -0.184716 -0.965921 0.181318 -0.184717 -0.965825 0.19553 -0.170149 -0.965828 0.195517 -0.170147 -0.965828 0.213937 -0.146313 -0.96583 0.213926 -0.146312 -0.965828 0.229553 -0.120339 -0.965832 0.229536 -0.12034 -0.96594 0.236983 -0.103918 -0.96594 0.236981 -0.10392 -0.965832 0.244027 -0.0872916 -0.965835 0.244012 -0.0872946 -0.965846 0.25236 -0.0587853 -0.965888 0.252185 -0.0588398 -0.96591 0.255937 -0.038925 -0.965911 0.255929 -0.0389278 -0.965914 0.257992 -0.0212262 -0.965915 0.257989 -0.0212278 -0.965888 0.258959 -0.000974786 -0.965889 0.258957 -0.000975745 -0.965888 0.25802 0.0220347 -0.965887 0.258024 0.0220371 -0.96589 0.255083 0.0445933 -0.96588 0.255118 0.0446174 -0.965861 0.249602 0.0693632 -0.965859 0.249607 0.0693695 -0.965837 0.240556 0.0963962 -0.965834 0.240564 0.0964063 -0.965832 0.227703 0.12377 -0.965828 0.227712 0.123785 -0.965852 0.212594 0.148097 -0.96585 0.212598 0.148106 -0.965828 0.195112 0.170611 -0.965825 0.195116 0.170623 -0.965823 0.173921 0.192189 -0.96582 0.173924 0.192204 -0.965833 0.150962 0.21066 -0.965832 0.150962 0.210665 -0.96582 0.126212 0.226411 -0.965818 0.126212 0.226419 -0.965817 0.098982 0.239584 -0.965815 0.0989808 0.239591 -0.965908 0.0787107 0.246631 -0.965907 0.0787088 0.246634 -0.965817 0.0582534 0.252596 -0.965816 0.0582526 0.252598 -0.965712 0.064132 0.25157 -0.982055 0.109791 0.153341 -0.707099 0.123604 0.696228 -0.70651 0.159031 0.689604 -0.706516 0.159034 0.689597 -0.70701 0.215015 0.673725 -0.70701 0.215016 0.673725 -0.706505 0.270222 0.654088 -0.706516 0.270225 0.654075 -0.706524 0.344573 0.618137 -0.706536 0.344575 0.618122 -0.706599 0.412173 0.57518 -0.706616 0.412174 0.575157 -0.706546 0.474827 0.524721 -0.706568 0.474825 0.524693 -0.706576 0.532695 0.465819 -0.706601 0.532689 0.465787 -0.706724 0.580513 0.404408 -0.706747 0.580506 0.404379 -0.706615 0.621684 0.337941 -0.706643 0.62167 0.337909 -0.70665 0.656787 0.263204 -0.706676 0.65677 0.263175 -0.706799 0.681583 0.189417 -0.706816 0.681571 0.189398 -0.70692 0.696715 0.121868 -0.706979 0.696664 0.121823 -0.706962 0.704686 0.0601834 -0.706973 0.704676 0.0601764 -0.706973 0.707235 -0.00266321 -0.706972 0.707237 -0.00266223 -0.707118 0.704714 -0.0579837 -0.707111 0.704721 -0.0579789 -0.707098 0.699076 -0.106328 -0.707085 0.69909 -0.106321 -0.706966 0.688712 -0.160854 -0.706736 0.688976 -0.160734 -0.706671 0.666196 -0.238326 -0.706644 0.666229 -0.238316 -0.707236 0.647463 -0.283918 -0.707233 0.647471 -0.283907 -0.706643 0.626672 -0.32854 -0.706617 0.626704 -0.328534 -0.706629 0.584052 -0.399449 -0.706603 0.584084 -0.399447 -0.706603 0.533791 -0.464521 -0.706577 0.533824 -0.464523 -0.707102 0.49534 -0.504623 -0.707094 0.49536 -0.504616 -0.706559 0.454312 -0.542564 -0.706537 0.454339 -0.54257 -0.706549 0.388015 -0.591805 -0.706533 0.388034 -0.591812 -0.706653 0.320584 -0.630768 -0.706643 0.320596 -0.630773 -0.706512 0.249115 -0.662407 -0.706501 0.249126 -0.662414 -0.706513 0.170252 -0.686916 -0.70651 0.170255 -0.686918 -0.70663 0.0937185 -0.701349 -0.70663 0.093719 -0.70135 -0.640969 0.472716 -0.60473 -0.727556 0.227798 -0.647124 -0.25865 0.235446 0.936838 -0.280816 0.215676 0.935215 -0.258774 0.180618 0.948901 -0.258811 0.153417 0.953667 -0.174712 0.11802 0.977521 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.258759 0.293686 0.920213 0.17539 0.0751505 -0.981627 0.930225 -0.0479432 -0.363844 0.998683 0.00683413 -0.0508431 0.982054 0.109784 0.153356 0.743558 0.091075 0.66244 0.855514 0.0631224 0.513918 0.933997 0.0435598 0.354615 0.561664 0.0996078 0.821348 0.415525 0.1095 0.902967 0.258814 0.155009 0.953408 0.166843 0.118183 0.978875 0.570357 0.0631773 -0.818964 0.424176 0.0695749 -0.902903 0.238751 0.456864 -0.856897 0.258494 0.127949 -0.957502 0.258495 0.12795 -0.957501 0.258798 0.190599 -0.94694 0.276601 0.231188 -0.932761 0.258595 0.245293 -0.934323 0.258417 0.34005 -0.904205 0.258433 0.340057 -0.904198 0.258845 0.39678 -0.880662 0.265534 0.436832 -0.859459 0.258607 0.44197 -0.858944 0.258466 0.529671 -0.807864 0.258504 0.529683 -0.807844 0.258496 0.620176 -0.740649 0.258542 0.620187 -0.740624 0.258907 0.676625 -0.689308 0.258926 0.676643 -0.689283 0.258567 0.728703 -0.634141 0.258625 0.728713 -0.634106 0.258625 0.797333 -0.545319 0.258683 0.797339 -0.545283 0.259025 0.839084 -0.478377 0.283278 0.849402 -0.445275 0.259003 0.865736 -0.428274 0.259139 0.884531 -0.387882 0.25915 0.884541 -0.387852 0.258745 0.909499 -0.325366 0.2588 0.909495 -0.325333 0.258849 0.940586 -0.219763 0.259034 0.940561 -0.219652 0.259115 0.954865 -0.145233 0.259144 0.954859 -0.145217 0.259153 0.962583 -0.0792035 0.259172 0.962579 -0.0791926 0.259072 0.965851 -0.00363471 0.259069 0.965852 -0.00363578 0.259069 0.962356 0.0821897 0.259047 0.962362 0.0821808 0.259058 0.951415 0.166431 0.288893 0.927282 0.238093 0.258919 0.930637 0.258606 0.258989 0.951438 0.166405 0.259155 0.921773 0.288398 0.258793 0.896616 0.359315 0.258736 0.896642 0.359291 0.25873 0.848667 0.461328 0.25867 0.848697 0.461307 0.258759 0.792579 0.552144 0.258704 0.79261 0.552124 0.258621 0.727169 0.635878 0.258568 0.727199 0.635865 0.258911 0.672937 0.692908 0.282932 0.643579 0.711165 0.258775 0.631246 0.731138 0.258559 0.562675 0.785204 0.258521 0.562699 0.785199 0.258478 0.47035 0.843777 0.258445 0.47037 0.843776 0.258832 0.408767 0.875166 0.276448 0.366956 0.888212 0.258588 0.356847 0.897659 0.258765 0.293678 0.920214 0.258422 0.217086 0.941324 0.291691 0.23314 0.927665 0.258774 0.180618 0.948901 0.707106 0.121181 0.696647 0.706509 0.159035 0.689603 0.706514 0.159031 0.689599 0.707008 0.215017 0.673727 0.70701 0.215012 0.673726 0.706505 0.270231 0.654085 0.706517 0.270217 0.654077 0.706525 0.34458 0.618132 0.706537 0.344566 0.618126 0.7066 0.412183 0.575171 0.706616 0.412163 0.575166 0.706545 0.474841 0.524709 0.706568 0.474814 0.524704 0.706575 0.532708 0.465804 0.706602 0.532674 0.465802 0.706725 0.580523 0.404392 0.706746 0.580495 0.404395 0.706615 0.621694 0.337922 0.706642 0.621661 0.337928 0.70665 0.656795 0.263185 0.706674 0.656765 0.263194 0.706797 0.681589 0.189403 0.706816 0.681567 0.189414 0.706919 0.696723 0.121832 0.706978 0.696658 0.121857 0.706962 0.704687 0.0601773 0.706972 0.704676 0.0601826 0.706973 0.707235 -0.00266126 0.706972 0.707237 -0.00266227 0.707118 0.704714 -0.0579783 0.70711 0.704722 -0.0579856 0.707096 0.699079 -0.106319 0.707084 0.69909 -0.10633 0.706969 0.68875 -0.160681 0.70674 0.688933 -0.160906 0.70667 0.666204 -0.238307 0.706644 0.666221 -0.238334 0.707236 0.647468 -0.283906 0.707232 0.647464 -0.283926 0.706642 0.626682 -0.328523 0.706616 0.626696 -0.328552 0.706628 0.584064 -0.399433 0.706602 0.584073 -0.399464 0.706602 0.533804 -0.464507 0.706579 0.53381 -0.464535 0.707104 0.495353 -0.504609 0.707095 0.495345 -0.504628 0.706561 0.454323 -0.542551 0.706539 0.454324 -0.542579 0.706551 0.388025 -0.591796 0.706532 0.388023 -0.59182 0.706652 0.320592 -0.630765 0.706643 0.32059 -0.630776 0.706512 0.249121 -0.662405 0.706503 0.249118 -0.662415 0.706515 0.170254 -0.686914 0.70651 0.170252 -0.686919 0.70663 0.0937204 -0.701349 0.70663 0.0937199 -0.701349 0.702495 0.170443 -0.690978 0.626014 0.568417 -0.533862 0.575185 0.81084 -0.108169 0.951494 0.0407511 -0.304958 0.965833 0.0611977 -0.251838 0.965816 0.0623624 -0.251615 0.965817 0.0623631 -0.251613 0.965815 0.0912505 -0.242643 0.965816 0.0912519 -0.242636 0.96584 0.11741 -0.231013 0.965841 0.117411 -0.231009 0.965819 0.142129 -0.216777 0.965821 0.142129 -0.21677 0.965819 0.166416 -0.198745 0.965822 0.166414 -0.198734 0.965919 0.181322 -0.184721 0.96592 0.181324 -0.184716 0.965824 0.195526 -0.170157 0.965828 0.195521 -0.170142 0.965828 0.213934 -0.146317 0.965831 0.213929 -0.146308 0.965828 0.229548 -0.120347 0.965832 0.22954 -0.120332 0.96594 0.236981 -0.103921 0.96594 0.236982 -0.103918 0.965832 0.244024 -0.0872988 0.965835 0.244014 -0.0872872 0.965847 0.252334 -0.0588745 0.965889 0.252203 -0.0587487 0.96591 0.255936 -0.0389288 0.965911 0.25593 -0.038924 0.965914 0.257992 -0.021228 0.965915 0.257989 -0.021226 0.965888 0.258959 -0.000974441 0.965888 0.25896 -0.000974795 0.965888 0.258023 0.0220369 0.965886 0.258027 0.0220353 0.965889 0.255084 0.04461 0.96588 0.255122 0.0446001 0.965861 0.249601 0.0693677 0.965859 0.249609 0.0693651 0.965837 0.240554 0.0964024 0.965834 0.240567 0.0964003 0.965832 0.2277 0.123778 0.965828 0.227716 0.123777 0.965852 0.212591 0.148103 0.96585 0.212603 0.148103 0.965827 0.19511 0.170618 0.965824 0.195123 0.17062 0.965823 0.173919 0.192195 0.96582 0.173931 0.192199 0.965833 0.150958 0.210663 0.965831 0.150966 0.210666 0.965819 0.12621 0.226416 0.965818 0.126217 0.226419 0.965816 0.0989812 0.239588 0.965815 0.0989845 0.23959 0.965908 0.0787083 0.246632 0.965907 0.0787112 0.246633 0.965817 0.0582521 0.252596 0.965816 0.0582539 0.252598 0.965712 0.064132 0.25157 0.998688 0.00640745 0.0508039 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.707109 -0.707104 0 0.707105 -0.707109 2.10579e-05 0.707107 -0.707107 2.1058e-05 0.707112 -0.707102 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.707113 -0.707101 0 -0.707107 -0.707106 -2.10561e-05 -0.707101 -0.707113 -2.1056e-05 -0.707107 -0.707107 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707109 -0.707104 0 -0.707109 -0.707104 0 -0.167633 -0.98585 0 -0.666457 -0.745543 0 -0.666463 -0.745538 7.05818e-06 -0.483974 -0.875082 3.49099e-05 -0.483968 -0.875086 1.16288e-05 -0.167623 -0.985851 2.43278e-05 -0.578407 -0.815748 0 -0.0553601 -0.998466 0 -0.0553601 -0.998466 0 -0.275826 -0.961207 0 -0.275826 -0.961207 0 -0.578407 -0.815748 0 0.167633 -0.98585 0 0.666474 -0.745528 0 0.666464 -0.745538 1.27714e-05 0.483975 -0.875082 -2.05104e-05 0.483968 -0.875086 2.7607e-06 0.167625 -0.985851 -1.93441e-05 0.578407 -0.815749 0 0.0553619 -0.998466 0 0.05536 -0.998466 1.64561e-06 0.275826 -0.961208 8.19911e-06 0.275826 -0.961208 8.20264e-06 0.578411 -0.815745 1.72011e-05 0.0554198 -0.998463 0 0.0554198 -0.998463 0 0.275905 -0.961185 0 0.275907 -0.961184 -8.21141e-06 0.57841 -0.815746 -1.72341e-05 0.578415 -0.815743 0 0.666885 -0.74516 0 0.666876 -0.745169 1.11014e-05 0.484665 -0.8747 1.30311e-05 0.484669 -0.874697 0 0.167862 -0.985811 0 0.167862 -0.985811 0 -0.0553955 -0.998465 0 -0.0553806 -0.998465 -1.32268e-05 -0.275869 -0.961195 -6.10091e-06 -0.275866 -0.961196 -1.4307e-05 -0.578399 -0.815754 -1.21542e-05 -0.578395 -0.815757 0 -0.666872 -0.745173 0 -0.666862 -0.745181 -1.11002e-05 -0.48463 -0.874719 -1.30298e-05 -0.484634 -0.874717 0 -0.167853 -0.985812 0 -0.167853 -0.985812 0 -0.198073 -0.728108 0.65622 0.225437 -0.443743 0.867335 0 -0.433139 0.901327 0 -0.999308 0.037184 -5.57673e-05 -0.99931 0.0371442 4.09677e-05 -0.993738 0.111736 0 -0.993741 0.111711 0 -0.941344 0.337448 -0.419882 -0.868543 0.263309 0.374604 -0.733185 0.567549 0 -0.99931 0.0371526 5.57244e-05 -0.999309 0.0371761 -4.09371e-05 -0.993741 0.111713 0 -0.993738 0.111734 0 -0.956989 0.290123 0 -0.956989 0.290123 0 -0.8828 0.46975 0 -0.8828 0.46975 0 -0.759281 0.650763 0 -0.759281 0.650763 0 -0.619063 0.785341 0 -0.619063 0.785341 0 -0.433139 0.901327 0 -0.433139 0.901327 0 -0.99931 -0.0371526 -5.5726e-05 -0.999309 -0.0371761 4.09383e-05 -0.993741 -0.111713 0 -0.993738 -0.111734 0 -0.941344 -0.337447 0.419879 -0.868544 -0.26331 -0.374611 -0.733183 -0.567547 0.198064 -0.72811 -0.656222 -0.225449 -0.443742 -0.867333 0 -0.433138 -0.901328 0 -0.790765 -0.61212 0 -0.455468 -0.890252 0 -0.455468 -0.890252 0 -0.999308 -0.037184 5.57657e-05 -0.99931 -0.0371442 -4.09665e-05 -0.993738 -0.111736 0 -0.993741 -0.111711 0 -0.956989 -0.290123 0 -0.956989 -0.290123 0 -0.790765 -0.61212 0.0544726 -0.97889 -0.196994 0.0545753 -0.978907 -0.196883 0.0463593 -0.826935 -0.560383 0.0465315 -0.827026 -0.560234 0.0310416 -0.546301 -0.837014 0.0312368 -0.546447 -0.836911 0.0108258 -0.180281 -0.983556 0.0111032 -0.1805 -0.983512 0.271293 -0.942295 -0.196164 0.27198 -0.942514 -0.19415 0.231658 -0.79752 -0.557043 0.232776 -0.798651 -0.554952 0.155681 -0.527837 -0.834956 0.157306 -0.52996 -0.833305 0.0542748 -0.172209 -0.983564 0.05641 -0.175108 -0.982932 0.568684 -0.798321 -0.198198 0.570474 -0.798291 -0.19311 0.485585 -0.67216 -0.558935 0.488712 -0.673718 -0.554315 0.326235 -0.44067 -0.83629 0.330644 -0.443582 -0.833012 0.11354 -0.137339 -0.983995 0.119007 -0.141069 -0.982821 1.51721e-08 -0.980369 -0.19717 0 -0.980368 -0.197177 0 -0.827914 -0.560854 3.18542e-08 -0.827923 -0.560841 2.1034e-08 -0.546696 -0.837331 6.3104e-08 -0.546713 -0.83732 2.08329e-08 -0.18049 -0.983577 6.56233e-08 -0.180511 -0.983573 -1.99392e-08 -0.980368 -0.197177 0 -0.980369 -0.19717 0 -0.827923 -0.560842 -4.18607e-08 -0.827914 -0.560854 -2.76427e-08 -0.546713 -0.83732 -8.29255e-08 -0.546696 -0.837331 -2.73808e-08 -0.180511 -0.983573 -8.62346e-08 -0.18049 -0.983577 0.696469 -0.689578 -0.198527 0.696827 -0.689503 -0.19753 0.593235 -0.574133 -0.564309 0.59513 -0.574685 -0.561745 0.39637 -0.368143 -0.841048 0.400567 -0.37004 -0.838222 0.13691 -0.104167 -0.985091 0.143553 -0.107495 -0.983787 0.697495 -0.688258 -0.199503 0.697862 -0.688185 -0.19847 0.595343 -0.569573 -0.566705 0.597226 -0.57014 -0.564147 0.398272 -0.360165 -0.8436 0.402442 -0.36207 -0.840801 0.137646 -0.0934394 -0.986064 0.144303 -0.0967744 -0.98479 -0.655882 -0.728875 -0.196367 -0.657018 -0.727309 -0.198366 -0.559199 -0.610893 -0.560451 -0.559878 -0.608721 -0.562135 -0.375009 -0.397637 -0.837409 -0.375422 -0.394808 -0.838561 -0.131853 -0.122076 -0.983724 -0.132226 -0.11881 -0.984073 -0.476858 -0.857405 -0.193553 -0.477549 -0.856122 -0.197491 -0.408049 -0.725152 -0.554663 -0.408063 -0.722246 -0.558431 -0.275307 -0.479483 -0.833248 -0.274717 -0.47498 -0.836017 -0.0976497 -0.155831 -0.982945 -0.09674 -0.150039 -0.983936 -0.165086 -0.966917 -0.194472 -0.165402 -0.966623 -0.195658 -0.141086 -0.819642 -0.555232 -0.141407 -0.818723 -0.556503 -0.095 -0.544241 -0.833533 -0.0953331 -0.542646 -0.834534 -0.0334208 -0.18041 -0.983023 -0.0338274 -0.178221 -0.983409 0.0114823 -0.133274 -0.991013 0.0112259 -0.132977 -0.991055 0.0321584 -0.517432 -0.85512 0.0320876 -0.517367 -0.855162 0.0474798 -0.815187 -0.577249 0.0475886 -0.815249 -0.577151 0.05489 -0.977447 -0.203925 0.0552115 -0.9775 -0.203581 0.0581536 -0.13217 -0.98952 0.0558931 -0.128268 -0.990163 0.161195 -0.50193 -0.849754 0.160549 -0.500937 -0.850462 0.236724 -0.785588 -0.571676 0.237415 -0.786368 -0.570315 0.273326 -0.940019 -0.204099 0.274803 -0.940556 -0.199594 0.120814 -0.110179 -0.986542 0.11477 -0.104964 -0.987831 0.334416 -0.420806 -0.843261 0.332806 -0.419537 -0.844529 0.492385 -0.661055 -0.566183 0.494 -0.662003 -0.563663 0.571384 -0.795227 -0.202815 0.574065 -0.79534 -0.194638 -0.697619 -0.688429 -0.19848 -0.697735 -0.688026 -0.199466 -0.59651 -0.570859 -0.564177 -0.596045 -0.568855 -0.566687 -0.401269 -0.363265 -0.840846 -0.399462 -0.358998 -0.843535 -0.142637 -0.0984352 -0.984868 -0.139299 -0.0917818 -0.985988 -0.696593 -0.689737 -0.197537 -0.696702 -0.689345 -0.198517 -0.594428 -0.575408 -0.561748 -0.593949 -0.57342 -0.564281 -0.399377 -0.371216 -0.83827 -0.397558 -0.366977 -0.840997 -0.141899 -0.109151 -0.983845 -0.138554 -0.102519 -0.985034 -8.80062e-07 -0.978996 -0.203882 -1.03421e-06 -0.978993 -0.203892 -2.40245e-06 -0.816191 -0.577782 -2.84292e-06 -0.816174 -0.577806 -3.65048e-06 -0.517665 -0.855583 -4.20912e-06 -0.517633 -0.855603 -3.99464e-06 -0.133044 -0.99111 -4.86847e-06 -0.132986 -0.991118 -1.10008e-07 -0.978996 -0.203882 -1.10008e-07 -0.978996 -0.203882 -3.11749e-07 -0.816194 -0.577778 -3.7607e-07 -0.816191 -0.577782 -3.7048e-07 -0.517671 -0.85558 -4.61643e-07 -0.517665 -0.855583 -5.34769e-07 -0.133049 -0.991109 -6.06555e-07 -0.133044 -0.99111 -0.133721 -0.0936605 -0.986583 -0.134016 -0.0970537 -0.986215 -0.379692 -0.377519 -0.844579 -0.379655 -0.378459 -0.844175 -0.564257 -0.600295 -0.566798 -0.564582 -0.599123 -0.567713 -0.657933 -0.726519 -0.19823 -0.659636 -0.724177 -0.20112 -0.0983291 -0.113419 -0.98867 -0.100176 -0.12034 -0.987666 -0.2802 -0.452109 -0.846809 -0.280543 -0.453957 -0.845706 -0.413921 -0.712754 -0.566261 -0.413921 -0.71102 -0.568437 -0.479148 -0.855473 -0.196425 -0.480584 -0.852992 -0.203577 -0.0348773 -0.132905 -0.990515 -0.0346581 -0.135708 -0.990143 -0.0980234 -0.51514 -0.851482 -0.0979161 -0.515872 -0.851052 -0.144179 -0.807643 -0.571773 -0.144384 -0.807017 -0.572606 -0.166271 -0.965366 -0.201054 -0.167065 -0.964641 -0.203856 0.564685 -0.145613 -0.812359 0.0363167 -0.97845 -0.203263 0.0363339 -0.978349 -0.203747 0.102536 -0.812762 -0.573502 0.102553 -0.811891 -0.574732 0.151011 -0.513869 -0.844473 0.150918 -0.511741 -0.84578 0.17447 -0.134411 -0.975445 0.174118 -0.131017 -0.97597 0.102267 -0.978796 -0.17748 0.102769 -0.978512 -0.178751 0.289079 -0.815559 -0.501295 0.29027 -0.81315 -0.50451 0.426684 -0.520295 -0.739752 0.427665 -0.514404 -0.743298 0.45348 -0.417378 -0.787497 0.420683 -0.136009 -0.896954 0.153705 -0.97925 -0.132076 0.155118 -0.978807 -0.1337 0.43493 -0.819431 -0.373321 0.438477 -0.815588 -0.377563 0.643717 -0.529631 -0.552376 0.647136 -0.520329 -0.5572 0.749325 -0.159213 -0.642778 0.749808 -0.144109 -0.645771 0.186073 -0.979846 -0.0726549 0.188556 -0.979266 -0.0740601 0.527345 -0.824428 -0.205488 0.533571 -0.819483 -0.209164 0.783178 -0.541851 -0.305008 0.789695 -0.529689 -0.309535 0.916865 -0.178901 -0.356866 0.919101 -0.159244 -0.36041 1.10008e-07 -0.978996 -0.203882 1.10008e-07 -0.978996 -0.203882 3.11751e-07 -0.816191 -0.577782 3.7607e-07 -0.816194 -0.577778 3.70479e-07 -0.517665 -0.855583 4.61641e-07 -0.517671 -0.85558 5.34769e-07 -0.133044 -0.99111 6.06557e-07 -0.133049 -0.991109 8.80106e-07 -0.978993 -0.203892 1.03417e-06 -0.978996 -0.203882 2.40254e-06 -0.816174 -0.577806 2.84284e-06 -0.816191 -0.577782 3.65052e-06 -0.517633 -0.855603 4.20911e-06 -0.517666 -0.855583 3.99455e-06 -0.132986 -0.991118 4.86858e-06 -0.133044 -0.99111 0.191433 -0.981459 0.00962646 0.201669 -0.979448 0.00321537 0.550977 -0.832956 -0.0510712 0.559594 -0.826784 -0.0572974 0.824964 -0.555643 -0.103418 0.830471 -0.546236 -0.109289 0.971388 -0.192306 -0.13937 0.972753 -0.18108 -0.14478 0.194895 -0.975638 0.100731 0.200342 -0.974817 0.0979577 0.554651 -0.829383 0.0669777 0.562409 -0.824523 0.062117 0.829976 -0.557313 0.023284 0.837127 -0.546765 0.0163201 0.979392 -0.200587 -0.0235706 0.982317 -0.184371 -0.0325572 -0.413502 -0.135632 -0.900344 -0.188492 -0.979156 -0.0756638 -0.185585 -0.979767 -0.074938 -0.533059 -0.818687 -0.21354 -0.525672 -0.823881 -0.21187 -0.78823 -0.528318 -0.315553 -0.780012 -0.541063 -0.314377 -0.916815 -0.157909 -0.366762 -0.91252 -0.178567 -0.367997 -0.152965 -0.978781 -0.136344 -0.151201 -0.979215 -0.135186 -0.432345 -0.815409 -0.38495 -0.427786 -0.819141 -0.38211 -0.6381 -0.519854 -0.567962 -0.632914 -0.528979 -0.565333 -0.739365 -0.143457 -0.657845 -0.736313 -0.158185 -0.657891 -0.0999724 -0.978499 -0.180402 -0.0991696 -0.978773 -0.179355 -0.282354 -0.813065 -0.509118 -0.280271 -0.815398 -0.506531 -0.416053 -0.514175 -0.750016 -0.413587 -0.519852 -0.747462 -0.441325 -0.412619 -0.796855 -0.557663 -0.145084 -0.81729 -0.0347173 -0.978406 -0.203758 -0.0345821 -0.978496 -0.203346 -0.0980386 -0.812262 -0.574995 -0.0976604 -0.813062 -0.573928 -0.144377 -0.512247 -0.846616 -0.143878 -0.514179 -0.845529 -0.166693 -0.131188 -0.977243 -0.166201 -0.134302 -0.976903 0.192398 -0.745095 0.638605 0.193133 -0.938972 0.284661 0.194863 -0.865877 0.460745 0.542686 -0.790668 0.283434 0.548248 -0.787261 0.282213 0.548248 -0.787261 0.282213 0.826532 -0.529873 0.189946 0.826532 -0.529873 0.189946 0.980056 -0.187064 0.0670576 0.980056 -0.187065 0.067058 0.195026 -0.607176 0.770261 0.41729 -0.675061 0.608409 0.548242 -0.62124 0.559903 0.548247 -0.621238 0.5599 0.826537 -0.418124 0.37684 0.826531 -0.418131 0.376848 0.980056 -0.147616 0.133042 0.980056 -0.147614 0.133039 0.980056 -0.0860748 0.179115 0.980056 -0.0860745 0.179114 0.826537 -0.243807 0.507341 0.82653 -0.24381 0.507351 0.548244 -0.362241 0.753797 0.548247 -0.362241 0.753795 0.191534 -0.425119 0.88464 0.191547 -0.425119 0.884638 -0.200554 -0.97453 0.100346 -0.194865 -0.975891 0.0983083 -0.562693 -0.824023 0.0660495 -0.554536 -0.829772 0.0629887 -0.837393 -0.546165 0.0218196 -0.829665 -0.55798 0.0177248 -0.982644 -0.183761 -0.0253639 -0.978991 -0.20156 -0.0308201 -0.202607 -0.979228 0.00797692 -0.190897 -0.981598 0.00481263 -0.560416 -0.826538 -0.052618 -0.550361 -0.833061 -0.055783 -0.831184 -0.546071 -0.104591 -0.824237 -0.555827 -0.108115 -0.97346 -0.181066 -0.139969 -0.970629 -0.192611 -0.144155 0.440701 -0.30563 -0.844022 0.194249 -0.333991 -0.922343 -0.298206 -0.632139 -0.715174 0.194265 -0.33399 -0.92234 0.194963 -0.452197 -0.870349 -0.49378 -0.443826 -0.747797 0.194788 -0.531998 -0.824036 0.194556 -0.635669 -0.747042 -0.493778 -0.835163 -0.242251 0.195067 -0.702981 -0.683934 0.19427 -0.775699 -0.600458 0.194279 -0.775698 -0.600457 0.195077 -0.838284 -0.509141 -0.298209 -0.850774 -0.432729 0.194573 -0.882509 -0.428159 0.194806 -0.931062 -0.308502 -0.298213 -0.850773 0.432729 0.194956 -0.955903 -0.219642 0.194258 -0.97661 -0.0921761 0.194287 -0.976604 -0.0921765 0.194287 -0.976605 0.0921756 0.194258 -0.97661 0.092177 0.194955 -0.955903 0.219642 -0.493779 -0.835163 0.242251 0.194806 -0.931062 0.308502 0.194573 -0.882509 0.428159 -0.493783 -0.443825 0.747795 0.195077 -0.838284 0.509142 0.194278 -0.775698 0.600457 0.19427 -0.775699 0.600459 0.195067 -0.702981 0.683934 -0.298205 -0.632139 0.715174 0.194563 -0.635669 0.747041 0.194795 -0.531998 0.824035 0.194963 -0.452196 0.870349 0.194265 -0.33399 0.92234 0.194266 -0.33399 0.92234 0.792052 -0.207845 -0.573981 0.607056 -0.270562 -0.74718 0.553804 -0.282264 -0.783344 0.553862 -0.424952 -0.715997 0.553865 -0.424951 -0.715996 0.553864 -0.551411 -0.623843 0.553854 -0.551416 -0.623848 0.553853 -0.658402 -0.509661 0.553851 -0.658403 -0.509661 0.553851 -0.742135 -0.377472 0.553864 -0.742127 -0.377468 0.553865 -0.799646 -0.231949 0.55385 -0.799656 -0.231951 0.553849 -0.828933 -0.0782386 0.553852 -0.828931 -0.0782385 0.553852 -0.828931 0.0782384 0.553849 -0.828933 0.0782386 0.55385 -0.799655 0.231952 0.553865 -0.799646 0.231948 0.553865 -0.742127 0.377468 0.553854 -0.742133 0.377471 0.553855 -0.658401 0.50966 0.553852 -0.658402 0.509661 0.553854 -0.551416 0.623848 0.553864 -0.551412 0.623843 0.553865 -0.424951 0.715996 0.553868 -0.42495 0.715994 0.553868 -0.283482 0.782859 0.55386 -0.283484 0.782864 0.980614 -0.0667154 -0.18424 0.896111 -0.151114 -0.417313 0.830277 -0.188537 -0.524494 0.830335 -0.28442 -0.479217 0.830335 -0.28442 -0.479217 0.830335 -0.36906 -0.417538 0.830335 -0.36906 -0.417538 0.830336 -0.440664 -0.341112 0.830332 -0.440668 -0.341115 0.830332 -0.49671 -0.252642 0.830331 -0.496711 -0.252642 0.830331 -0.535209 -0.155245 0.830344 -0.53519 -0.15524 0.830345 -0.554784 -0.0523632 0.830339 -0.554793 -0.0523637 0.830339 -0.554793 0.052364 0.830345 -0.554784 0.0523629 0.830344 -0.53519 0.155239 0.830331 -0.535209 0.155245 0.830331 -0.496711 0.252642 0.83033 -0.496713 0.252643 0.830331 -0.44067 0.341117 0.830338 -0.440662 0.34111 0.830338 -0.369058 0.417535 0.830333 -0.369062 0.417541 0.830333 -0.284422 0.47922 0.830332 -0.284423 0.47922 0.830332 -0.189737 0.523973 0.830332 -0.189737 0.523974 0.980614 -0.066716 -0.184242 0.980614 -0.10001 -0.168506 0.980614 -0.10001 -0.168505 0.980614 -0.129771 -0.146817 0.980615 -0.12977 -0.146816 0.980614 -0.154948 -0.119943 0.980615 -0.154946 -0.119941 0.980615 -0.17465 -0.0888323 0.980615 -0.17465 -0.0888324 0.980615 -0.188186 -0.0545863 0.980614 -0.18819 -0.0545873 0.980614 -0.19508 -0.0184125 0.980614 -0.195084 -0.0184128 0.980614 -0.195084 0.0184129 0.980614 -0.19508 0.0184124 0.980614 -0.18819 0.0545874 0.980615 -0.188186 0.0545861 0.980615 -0.17465 0.0888324 0.980615 -0.174649 0.088832 0.980615 -0.154945 0.119941 0.980614 -0.154949 0.119944 0.980614 -0.129771 0.146817 0.980614 -0.129771 0.146817 0.980614 -0.10001 0.168505 0.980615 -0.100008 0.168503 0.980615 -0.0667148 0.184238 0.980614 -0.0667154 0.18424 -0.191543 -0.923915 0.3312 -0.191541 -0.923915 0.3312 -0.548265 -0.78725 0.282209 -0.548266 -0.78725 0.282209 -0.826514 -0.529898 0.189955 -0.826514 -0.529898 0.189955 -0.980064 -0.18703 0.0670453 -0.980064 -0.187029 0.0670451 -0.191542 -0.729072 0.657089 -0.191531 -0.729074 0.65709 -0.548265 -0.621229 0.559893 -0.54826 -0.621232 0.559895 -0.826513 -0.418151 0.376865 -0.826519 -0.418143 0.376859 -0.980064 -0.147586 0.133015 -0.980063 -0.147589 0.133017 -0.191527 -0.425121 0.884641 -0.19154 -0.425119 0.884639 -0.548261 -0.362236 0.753787 -0.548264 -0.362235 0.753785 -0.826519 -0.243817 0.507365 -0.826512 -0.243823 0.507374 -0.980063 -0.0860587 0.179081 -0.980063 -0.0860583 0.17908 0.964317 -0.209355 -0.162059 0.433674 -0.41041 -0.802179 0.979852 -0.090968 -0.177805 0.964596 -0.124672 -0.232402 0.892554 -0.205389 -0.401451 0.786136 -0.281503 -0.550223 0.190566 -0.447121 -0.873938 0.698456 -0.565913 -0.438066 0.980384 -0.18862 -0.0571821 0.965493 -0.246865 -0.0829512 0.964317 -0.209354 -0.162058 0.698454 -0.565914 -0.438067 0.699175 -0.331505 -0.63345 0.599433 -0.364569 -0.712579 0.895035 -0.426814 -0.129394 0.790241 -0.586439 -0.177786 0.70407 -0.676607 -0.215614 0.604726 -0.762178 -0.231063 0.438537 -0.860059 -0.260737 0.253274 -0.444892 -0.859025 0.253017 -0.765034 -0.592204 0.253009 -0.765036 -0.592204 0.256547 -0.922802 -0.287438 0.193133 -0.938972 -0.284661 -0.194788 -0.531999 0.824036 -0.19506 -0.702982 0.683935 -0.194565 -0.88251 0.428159 -0.194549 -0.63567 -0.747043 -0.194956 -0.452197 -0.87035 -0.980622 -0.195044 -0.0184089 -0.980623 -0.188151 -0.0545759 -0.980622 -0.188155 -0.0545771 -0.830314 -0.535235 -0.155253 -0.830317 -0.189744 -0.523994 -0.980622 -0.0667029 -0.184205 -0.980621 -0.0667034 -0.184207 -0.896065 -0.151145 -0.4174 -0.792139 -0.205975 -0.574535 -0.980623 -0.174617 -0.0888156 -0.980623 -0.174617 -0.0888155 -0.830314 -0.496734 -0.252654 -0.830314 -0.496735 -0.252654 -0.553868 -0.742124 -0.377467 -0.553867 -0.799644 -0.231948 -0.553869 -0.82892 -0.0782373 -0.553867 -0.828921 -0.0782376 -0.830321 -0.554819 -0.0523665 -0.980621 -0.195047 0.0184093 -0.980622 -0.195044 0.018409 -0.830321 -0.554819 0.0523661 -0.830327 -0.554811 0.0523657 -0.553869 -0.828919 0.0782374 -0.553867 -0.828921 0.0782375 -0.194258 -0.333991 -0.922342 -0.194242 -0.333991 -0.922345 -0.55388 -0.283479 -0.782852 -0.440843 -0.301937 -0.845276 -0.607084 -0.270555 -0.747161 -0.980621 -0.0999911 -0.168474 -0.980622 -0.0999907 -0.168473 -0.830317 -0.284434 -0.479239 -0.830318 -0.284433 -0.479239 -0.55388 -0.424946 -0.715987 -0.553882 -0.424946 -0.715986 0.493766 -0.44383 -0.747804 -0.194781 -0.531999 -0.824037 -0.19506 -0.702982 -0.683935 0.298196 -0.632141 -0.715177 -0.553871 -0.551408 -0.623839 -0.553882 -0.551404 -0.623834 -0.830318 -0.369077 -0.417558 -0.830317 -0.369078 -0.417558 -0.980622 -0.129746 -0.146788 -0.980622 -0.129747 -0.14679 -0.980622 -0.154919 -0.119921 -0.980622 -0.154916 -0.119919 -0.830318 -0.440685 -0.341128 -0.830315 -0.440689 -0.341132 -0.55387 -0.658393 -0.509653 -0.553869 -0.658394 -0.509654 -0.194263 -0.7757 -0.600459 -0.19427 -0.775699 -0.600458 -0.980621 -0.195047 -0.0184094 -0.830327 -0.55481 -0.0523654 -0.830327 -0.535215 -0.155247 -0.553883 -0.799635 -0.231945 -0.553882 -0.742116 -0.377462 0.298199 -0.850777 -0.432731 -0.19507 -0.838285 -0.509142 -0.194948 -0.955904 0.219642 -0.19425 -0.976612 0.0921763 -0.194279 -0.976606 0.0921766 -0.194279 -0.976606 -0.0921757 -0.194251 -0.976612 -0.0921771 -0.194948 -0.955904 -0.219642 0.493763 -0.835171 -0.242253 -0.194798 -0.931064 -0.308503 -0.194566 -0.88251 -0.428159 -0.980622 -0.188155 0.054577 -0.980623 -0.188151 0.054576 -0.830327 -0.535216 0.155247 -0.830314 -0.535235 0.155252 -0.553868 -0.799644 0.231948 -0.553883 -0.799634 0.231945 0.493764 -0.835171 0.242253 -0.194798 -0.931064 0.308503 -0.19507 -0.838285 0.509143 0.298202 -0.850776 0.43273 -0.553871 -0.742123 0.377466 -0.553883 -0.742116 0.377463 -0.830313 -0.496736 0.252655 -0.830314 -0.496734 0.252654 -0.980623 -0.174616 0.0888152 -0.980623 -0.174617 0.0888156 -0.980623 -0.154915 0.119918 -0.980622 -0.15492 0.119921 -0.830313 -0.440691 0.341133 -0.83032 -0.440682 0.341127 -0.553873 -0.658392 0.509653 -0.553871 -0.658392 0.509653 -0.194271 -0.775699 0.600458 -0.194263 -0.7757 0.600459 -0.980622 -0.129746 0.146789 -0.980622 -0.129747 0.14679 -0.83032 -0.369075 0.417555 -0.830315 -0.36908 0.41756 -0.553872 -0.551409 0.623839 -0.553882 -0.551404 0.623834 0.298194 -0.632141 0.715177 -0.194556 -0.635669 0.747042 -0.194956 -0.452197 0.870351 0.493769 -0.443829 0.747802 -0.553886 -0.424944 0.715984 -0.553883 -0.424946 0.715986 -0.830315 -0.284436 0.479243 -0.830315 -0.284436 0.479243 -0.980622 -0.0999895 0.168471 -0.980622 -0.0999907 0.168473 -0.980622 -0.0667022 0.184204 -0.980622 -0.0667029 0.184205 -0.830315 -0.189746 0.523998 -0.830314 -0.189746 0.523999 -0.553886 -0.283478 0.782848 -0.553878 -0.28348 0.782853 -0.194258 -0.333991 0.922342 -0.194258 -0.333991 0.922342 0.200562 -0.974529 -0.100345 0.978984 -0.201596 0.0308162 0.982644 -0.18376 0.0253486 0.89514 -0.445767 -0.00395618 0.836209 -0.54841 -0.000354735 0.194872 -0.97589 -0.0983078 0.441596 -0.893745 -0.0788245 0.561286 -0.826298 -0.0467952 0.607597 -0.792206 -0.056887 0.791876 -0.609929 -0.0303241 0.202607 -0.979228 -0.00797363 0.190904 -0.981597 -0.00481159 0.560399 -0.82655 0.0526152 0.550344 -0.833072 0.0557802 0.831185 -0.546069 0.104591 0.824237 -0.555827 0.108116 0.973466 -0.181032 0.139972 0.970626 -0.192612 0.14417 -0.25301 -0.765036 -0.592204 -0.892507 -0.205431 -0.401534 -0.190559 -0.447121 -0.873939 -0.253267 -0.444893 -0.859026 -0.433674 -0.41041 -0.802179 -0.599461 -0.36456 -0.712561 -0.97986 -0.0909509 -0.177772 -0.698471 -0.565902 -0.438057 -0.193126 -0.938973 -0.284661 -0.25654 -0.922803 -0.287439 -0.253002 -0.765037 -0.592206 -0.698469 -0.565903 -0.438058 -0.699189 -0.331498 -0.633438 -0.786136 -0.281503 -0.550223 -0.438537 -0.860059 -0.260737 -0.604754 -0.762158 -0.231057 -0.704084 -0.676593 -0.215609 -0.790241 -0.586439 -0.177786 -0.894989 -0.426902 -0.12942 -0.964597 -0.124674 -0.2324 -0.964317 -0.209355 -0.162059 -0.964317 -0.209354 -0.162058 -0.965493 -0.246863 -0.0829553 -0.980391 -0.188584 -0.0571713 0.413503 -0.135617 0.900346 0.84535 -0.160386 0.509569 0.891738 -0.297123 0.341353 0.188486 -0.979157 0.0756614 0.185585 -0.979767 0.0749372 0.533072 -0.818678 0.213543 0.525656 -0.823892 0.211866 0.788214 -0.528344 0.31555 0.780015 -0.541058 0.314378 0.91349 -0.178623 0.365554 0.152964 -0.978781 0.136342 0.151197 -0.979217 0.135182 0.432345 -0.815409 0.38495 0.427793 -0.819136 0.382113 0.638102 -0.519854 0.56796 0.632905 -0.528999 0.565324 0.739365 -0.143457 0.657845 0.736316 -0.158173 0.657891 0.0999706 -0.9785 0.180399 0.099168 -0.978774 0.179352 0.282354 -0.813065 0.509118 0.280271 -0.815398 0.506531 0.416053 -0.514175 0.750016 0.413587 -0.519852 0.747462 0.441328 -0.412607 0.79686 0.557659 -0.145084 0.817292 0.0347177 -0.978405 0.203759 0.0345817 -0.978496 0.203345 0.0980381 -0.812262 0.574995 0.0976599 -0.813062 0.573928 0.144378 -0.512234 0.846624 0.143875 -0.514178 0.84553 0.16669 -0.131206 0.977241 0.166201 -0.134296 0.976904 -0.972749 -0.181119 0.144763 -0.830472 -0.546234 0.10929 -0.191426 -0.98146 -0.00963064 -0.201669 -0.979448 -0.00321537 -0.550994 -0.832945 0.051074 -0.971388 -0.192306 0.139372 -0.982317 -0.184371 0.0325569 -0.979399 -0.200552 0.0235898 -0.895094 -0.445859 -0.00395306 -0.836209 -0.54841 -0.000354735 -0.824964 -0.555643 0.103418 -0.559611 -0.826772 0.0573003 -0.194887 -0.975639 -0.100731 -0.200334 -0.974818 -0.0979581 -0.441596 -0.893745 -0.0788245 -0.561303 -0.826286 -0.0467903 -0.607625 -0.792185 -0.0568837 -0.791876 -0.609929 -0.0303241 -1.10008e-07 -0.978996 0.203882 -1.10008e-07 -0.978996 0.203882 -3.11756e-07 -0.816185 0.57779 -5.31944e-07 -0.816194 0.577778 -6.013e-07 -0.517679 0.855575 -2.30823e-07 -0.517657 0.855588 -2.67385e-07 -0.133044 0.99111 -6.06566e-07 -0.133067 0.991107 -8.80106e-07 -0.978993 0.203892 -1.03417e-06 -0.978996 0.203882 -2.40254e-06 -0.816174 0.577806 -2.68699e-06 -0.816185 0.57779 -3.4197e-06 -0.517633 0.855603 -4.2091e-06 -0.517679 0.855575 -3.99455e-06 -0.132986 0.991118 -4.86858e-06 -0.133044 0.99111 -0.564684 -0.145628 0.812357 -0.0363165 -0.97845 0.203263 -0.0363336 -0.978349 0.203746 -0.102536 -0.812762 0.573502 -0.102553 -0.811891 0.574732 -0.151013 -0.513851 0.844484 -0.15092 -0.511728 0.845788 -0.17447 -0.134435 0.975442 -0.174117 -0.131035 0.975968 -0.102269 -0.978796 0.177484 -0.10277 -0.978512 0.178751 -0.289076 -0.815565 0.501287 -0.29027 -0.81315 0.50451 -0.426692 -0.52027 0.739766 -0.427673 -0.514379 0.743311 -0.453477 -0.41739 0.787492 -0.420685 -0.136041 0.896949 -0.153705 -0.97925 0.132075 -0.155122 -0.978806 0.133704 -0.43493 -0.819431 0.373321 -0.438468 -0.815597 0.377553 -0.643709 -0.529652 0.552365 -0.647147 -0.5203 0.557215 -0.749325 -0.159185 0.642785 -0.749807 -0.144121 0.64577 -0.186072 -0.979846 0.0726559 -0.188555 -0.979266 0.0740609 -0.527359 -0.824417 0.205497 -0.533571 -0.819483 0.209164 -0.783181 -0.541846 0.305009 -0.789682 -0.529713 0.309526 -0.91686 -0.178942 0.356859 -0.919104 -0.159211 0.360416 0.133736 -0.0936718 0.98658 0.134031 -0.097071 0.986211 0.379675 -0.3775 0.844595 0.379638 -0.37844 0.844191 0.564268 -0.600309 0.566772 0.564597 -0.599126 0.567695 0.657935 -0.726516 0.19823 0.659652 -0.724155 0.201143 0.0983361 -0.113432 0.988667 0.100184 -0.120356 0.987663 0.280191 -0.452099 0.846818 0.280532 -0.453938 0.84572 0.413928 -0.712767 0.56624 0.413927 -0.711033 0.568416 0.479148 -0.855473 0.196425 0.480584 -0.852992 0.203577 0.034877 -0.132905 0.990515 0.0346564 -0.135726 0.99014 0.0980192 -0.51514 0.851483 0.0979139 -0.515858 0.85106 0.144179 -0.807646 0.571769 0.144382 -0.807026 0.572593 0.16627 -0.965366 0.201054 0.167064 -0.964641 0.203856 8.80062e-07 -0.978996 0.203882 1.03421e-06 -0.978993 0.203892 2.40248e-06 -0.816185 0.57779 2.68704e-06 -0.816174 0.577806 3.41963e-06 -0.517679 0.855575 4.20912e-06 -0.517633 0.855603 3.99464e-06 -0.133044 0.99111 4.86847e-06 -0.132986 0.991118 1.10008e-07 -0.978996 0.203882 1.10008e-07 -0.978996 0.203882 3.11749e-07 -0.816194 0.577778 5.31949e-07 -0.816185 0.57779 6.01301e-07 -0.517657 0.855588 2.30819e-07 -0.517679 0.855575 2.67384e-07 -0.133067 0.991107 6.06555e-07 -0.133044 0.99111 0.697523 -0.688583 0.198283 0.697615 -0.688138 0.199497 0.59642 -0.571462 0.563661 0.595714 -0.569203 0.566686 0.401369 -0.364389 0.840312 0.398941 -0.35948 0.843576 0.143088 -0.100059 0.984639 0.138726 -0.0923868 0.986012 0.696297 -0.690148 0.197147 0.696378 -0.689728 0.198327 0.593903 -0.576908 0.560764 0.593185 -0.574698 0.563785 0.399119 -0.373985 0.837161 0.396663 -0.369095 0.840492 0.14219 -0.112951 0.983374 0.137826 -0.105321 0.984841 -0.0114823 -0.133273 0.991013 -0.0112263 -0.132977 0.991055 -0.0321594 -0.517433 0.855119 -0.0320876 -0.517367 0.855162 -0.0474798 -0.815187 0.577249 -0.047587 -0.815248 0.577153 -0.0548882 -0.977447 0.203925 -0.0552097 -0.9775 0.203581 -0.0581446 -0.132155 0.989522 -0.055892 -0.128266 0.990164 -0.161198 -0.501944 0.849746 -0.160546 -0.500942 0.85046 -0.23672 -0.785583 0.571684 -0.237415 -0.786368 0.570315 -0.273327 -0.94002 0.204095 -0.274802 -0.940556 0.199594 -0.120825 -0.110187 0.98654 -0.114756 -0.104951 0.987834 -0.334413 -0.420804 0.843263 -0.332817 -0.419546 0.84452 -0.492382 -0.661044 0.566198 -0.494002 -0.661995 0.563671 -0.571391 -0.795228 0.202794 -0.574066 -0.79534 0.194634 0.65558 -0.729216 0.196108 0.656533 -0.727901 0.197798 0.558415 -0.612528 0.559449 0.559033 -0.610543 0.560999 0.374292 -0.400675 0.836281 0.374671 -0.39807 0.837354 0.131583 -0.126411 0.983212 0.131951 -0.123178 0.983573 0.476626 -0.857598 0.193271 0.4772 -0.856525 0.196585 0.407404 -0.726383 0.553525 0.40741 -0.7238 0.556894 0.274687 -0.48217 0.831901 0.274126 -0.47793 0.834529 0.0974104 -0.159991 0.9823 0.0965173 -0.154338 0.983293 0.164998 -0.967049 0.193888 0.165257 -0.966808 0.194864 0.140849 -0.820646 0.553807 0.141128 -0.819848 0.554916 0.0947718 -0.546746 0.831918 0.095092 -0.545208 0.83289 0.0333415 -0.184488 0.982269 0.0337407 -0.18233 0.982658 -0.696141 -0.689965 0.198336 -0.696525 -0.689919 0.197142 -0.592468 -0.575395 0.563829 -0.594609 -0.576199 0.560745 -0.39549 -0.370281 0.840523 -0.4003 -0.372799 0.837127 -0.136184 -0.106961 0.984893 -0.143837 -0.111301 0.983322 -0.697382 -0.688378 0.199484 -0.697764 -0.68834 0.198274 -0.594992 -0.569904 0.56674 -0.597126 -0.570735 0.563651 -0.397767 -0.360667 0.843624 -0.402562 -0.363208 0.840252 -0.137069 -0.0940347 0.986088 -0.144751 -0.0983938 0.984564 0 -0.980487 0.196586 -7.59022e-09 -0.980487 0.196583 -2.15976e-08 -0.828921 0.559366 2.15983e-08 -0.828909 0.559384 3.22668e-08 -0.549196 0.835694 -2.12058e-08 -0.549218 0.835679 -7.12636e-09 -0.184569 0.98282 -5.22017e-08 -0.184591 0.982816 0 -0.980487 0.196583 9.94091e-09 -0.980487 0.196586 2.82867e-08 -0.828909 0.559384 -2.82858e-08 -0.828921 0.559366 -4.22584e-08 -0.549218 0.835679 2.77716e-08 -0.549196 0.835694 9.33432e-09 -0.184591 0.982816 6.83653e-08 -0.184569 0.98282 -0.0544009 -0.979013 0.196402 -0.0545042 -0.97903 0.19629 -0.0462683 -0.827947 0.558895 -0.0463993 -0.828016 0.558781 -0.0309391 -0.548809 0.835375 -0.0311303 -0.548951 0.835274 -0.0107902 -0.184362 0.982799 -0.011065 -0.184579 0.982755 -0.271111 -0.94252 0.195332 -0.271673 -0.942698 0.193686 -0.231258 -0.798732 0.55547 -0.232256 -0.79974 0.5536 -0.155323 -0.530521 0.83332 -0.156855 -0.532521 0.831756 -0.0541334 -0.176347 0.982838 -0.0562346 -0.179202 0.982204 -0.568442 -0.798725 0.19726 -0.569956 -0.798694 0.19297 -0.484963 -0.673813 0.557482 -0.487773 -0.675204 0.553333 -0.325659 -0.443748 0.834886 -0.329829 -0.446496 0.831778 -0.113322 -0.141647 0.983409 -0.118674 -0.1453 0.982245 0.0140272 -0.272751 0.961982 0.0143345 -0.272517 0.962044 0.0387489 -0.712728 0.700369 0.038989 -0.712576 0.700511 0.0532534 -0.965321 0.255575 0.0533973 -0.965282 0.255695 0.0711199 -0.269676 0.960321 0.0717404 -0.266091 0.961275 0.194353 -0.692977 0.69427 0.194911 -0.69082 0.696259 0.265315 -0.930949 0.250884 0.265961 -0.930198 0.252976 0.150186 -0.238832 0.959377 0.149084 -0.232211 0.961172 0.407984 -0.595177 0.692324 0.407578 -0.590548 0.696515 0.556357 -0.792841 0.248737 0.55721 -0.790618 0.253852 0.677962 -0.689805 0.25404 0.677829 -0.690436 0.252678 0.491326 -0.522974 0.696489 0.492182 -0.526166 0.693474 0.177838 -0.220882 0.95895 0.180464 -0.227578 0.956891 0.679174 -0.688099 0.255426 0.679033 -0.688735 0.254084 0.493308 -0.516919 0.699601 0.49415 -0.520152 0.696604 0.178737 -0.210638 0.961085 0.18135 -0.217371 0.959095 9.80142e-09 -0.96666 0.256064 0 -0.966661 0.256061 0 -0.713133 0.701029 5.45924e-08 -0.713118 0.701044 2.08672e-08 -0.27258 0.962133 1.15385e-07 -0.272545 0.962143 -1.30353e-08 -0.966661 0.256061 0 -0.96666 0.256064 0 -0.713118 0.701044 -7.26069e-08 -0.713133 0.701029 -2.77489e-08 -0.272545 0.962143 -1.53463e-07 -0.27258 0.962133 0.0524216 -0.967722 0.246507 0.0527317 -0.967634 0.246788 0.0377543 -0.731745 0.680532 0.0377741 -0.731731 0.680546 0.0138021 -0.316329 0.948549 0.0135656 -0.316597 0.948463 0.26216 -0.934377 0.241272 0.263247 -0.933008 0.24535 0.190038 -0.710522 0.677528 0.19006 -0.710387 0.677663 0.0693269 -0.306026 0.949496 0.0692112 -0.309914 0.948242 0.552539 -0.797226 0.243169 0.553471 -0.794312 0.250479 0.402049 -0.608847 0.683859 0.401992 -0.608537 0.684167 0.146069 -0.261538 0.954076 0.148151 -0.268108 0.951929 -0.168583 -0.217499 0.961392 -0.172371 -0.216978 0.960837 -0.465524 -0.541681 0.699906 -0.468559 -0.540986 0.698418 -0.640168 -0.72432 0.256019 -0.642379 -0.723058 0.254039 -0.122789 -0.246549 0.96132 -0.12763 -0.249978 0.959803 -0.339945 -0.631821 0.696591 -0.343344 -0.633792 0.693126 -0.465552 -0.847914 0.253582 -0.467487 -0.848033 0.249594 -0.0427868 -0.272296 0.961262 -0.0440823 -0.274121 0.960684 -0.117973 -0.708139 0.696148 -0.118862 -0.709185 0.69493 -0.161345 -0.953996 0.252706 -0.16189 -0.954229 0.251473 1.44877e-06 -0.31658 0.948566 1.33348e-07 -0.96898 0.24714 1.33348e-07 -0.96898 0.24714 3.67479e-07 -0.732223 0.681065 3.81281e-07 -0.732223 0.681065 3.4131e-07 -0.316553 0.948575 0 -0.316562 0.948572 1.06676e-06 -0.968982 0.247133 1.19485e-06 -0.96898 0.24714 2.76978e-06 -0.732253 0.681033 3.56006e-06 -0.732223 0.681065 4.00974e-06 -0.316626 0.948551 4.86318e-06 -0.31658 0.948566 -0.679438 -0.688329 0.2541 -0.678758 -0.688514 0.255413 -0.495376 -0.518907 0.696662 -0.492071 -0.518151 0.699561 -0.183419 -0.215297 0.959169 -0.176674 -0.212697 0.961013 -0.678248 -0.690016 0.2527 -0.677556 -0.69021 0.254023 -0.493414 -0.524929 0.693536 -0.490092 -0.524189 0.696445 -0.182521 -0.225517 0.956989 -0.175787 -0.222928 0.958855 -0.15982 -0.312493 0.936379 -0.732342 -0.61092 0.300753 -0.890432 -0.268694 0.367334 -0.563467 -0.793403 0.230254 -0.240074 -0.965674 0.0991872 -0.88706 -0.287228 0.361422 -0.713739 -0.287355 0.638752 -0.712695 -0.301084 0.633573 -0.536406 -0.30426 0.787206 -0.481957 -0.127275 0.866902 -0.396049 -0.312443 0.863438 -0.159312 -0.309614 0.937421 -0.652184 -0.714884 0.252184 -0.520118 -0.716215 0.46531 -0.516649 -0.72232 0.459703 -0.334529 -0.7223 0.605288 -0.33363 -0.726065 0.601266 -0.115237 -0.726059 0.677907 -0.115401 -0.727331 0.676515 -0.236732 -0.966727 0.096934 -0.19053 -0.966735 0.170653 -0.188744 -0.967508 0.168238 -0.122254 -0.967491 0.221395 -0.121697 -0.967969 0.219603 -0.0420492 -0.967962 0.247551 -0.0420716 -0.968122 0.246921 -0.00337765 -0.316624 0.948545 -0.636104 -0.728974 0.252921 -0.638969 -0.72736 0.250332 -0.461634 -0.555665 0.69147 -0.461884 -0.555625 0.691335 -0.16978 -0.241639 0.955398 -0.166522 -0.241458 0.956017 -0.460416 -0.852135 0.248764 -0.463539 -0.852279 0.242388 -0.335102 -0.650427 0.681654 -0.33533 -0.650574 0.681401 -0.124918 -0.284953 0.950367 -0.12034 -0.280728 0.952213 -0.158999 -0.956655 0.243989 -0.16006 -0.957111 0.241494 -0.115282 -0.727371 0.676492 -0.115332 -0.727438 0.676411 -0.0408646 -0.306404 0.951024 -0.0447288 -0.313112 0.948662 -0.965752 -0.197097 0.168747 -0.953463 -0.271665 0.130791 -0.814903 -0.551953 0.176861 -0.773417 -0.616452 0.147694 -0.546928 -0.828058 0.123247 -0.584054 -0.797474 0.151377 -0.198064 -0.979619 0.0334361 -0.246112 -0.966497 0.0728866 -0.979555 -0.185187 0.0785967 -0.976301 -0.204366 0.0712163 -0.831161 -0.545064 0.109891 -0.823423 -0.557827 0.103941 -0.555564 -0.82201 0.125094 -0.547213 -0.828256 0.120625 -0.19504 -0.973216 0.121701 -0.189151 -0.974727 0.118868 0 -0.316562 0.948572 -1.06679e-06 -0.96898 0.24714 -1.19483e-06 -0.968982 0.247133 -2.7699e-06 -0.732223 0.681065 -3.55998e-06 -0.732253 0.681033 -4.00974e-06 -0.31658 0.948566 -4.86323e-06 -0.316626 0.948551 -1.33348e-07 -0.96898 0.24714 -1.33348e-07 -0.96898 0.24714 -3.6748e-07 -0.732223 0.681065 -3.81281e-07 -0.732223 0.681065 -3.4131e-07 -0.316553 0.948575 -1.44877e-06 -0.31658 0.948566 -0.195026 -0.607176 0.770261 -0.62349 -0.748205 0.226827 -0.444685 -0.680078 0.58288 -0.980064 -0.187029 0.0670451 -0.980064 -0.18703 0.0670453 -0.826532 -0.529873 0.189946 -0.826532 -0.529873 0.189946 -0.548248 -0.787261 0.282213 -0.548248 -0.787261 0.282213 -0.19155 -0.923913 0.331199 -0.194863 -0.865877 0.460745 -0.191549 -0.729072 0.657087 -0.548247 -0.621238 0.559901 -0.548242 -0.621241 0.559902 -0.826531 -0.418131 0.376847 -0.826537 -0.418123 0.376841 -0.980064 -0.147586 0.133015 -0.980063 -0.147589 0.133017 -0.191534 -0.42512 0.88464 -0.191547 -0.425118 0.884638 -0.548244 -0.362241 0.753797 -0.548247 -0.36224 0.753795 -0.826537 -0.243806 0.507342 -0.82653 -0.243811 0.507351 -0.980063 -0.0860587 0.179081 -0.980063 -0.0860583 0.17908 0.160208 -0.312473 0.936319 0.0422281 -0.968116 0.24692 0.115777 -0.727299 0.676485 0.161045 -0.309566 0.937141 0.464019 -0.309539 0.829983 0.419003 0.042013 0.907013 0.537837 -0.304097 0.786293 0.71327 -0.30108 0.632927 0.718705 -0.287205 0.633226 0.886315 -0.287286 0.363198 0.892935 -0.268972 0.361001 0.116404 -0.726006 0.677765 0.334325 -0.726102 0.600835 0.337309 -0.722307 0.603734 0.517321 -0.722386 0.458843 0.523403 -0.716216 0.46161 0.64574 -0.716329 0.264373 0.654401 -0.708162 0.265078 0.0424612 -0.967953 0.247515 0.121985 -0.967976 0.219413 0.123223 -0.967494 0.220841 0.189028 -0.96752 0.16785 0.191666 -0.96674 0.169348 0.236488 -0.966778 0.0970219 0.24041 -0.96574 0.0977165 -0.194796 -0.531998 0.824035 -0.195067 -0.702981 0.683934 -0.194573 -0.882509 0.428159 -0.194556 -0.635669 -0.747042 -0.194964 -0.452197 -0.870349 -0.980622 -0.195044 -0.0184089 -0.980623 -0.188151 -0.0545759 -0.980622 -0.188155 -0.0545771 -0.830331 -0.535209 -0.155245 -0.830335 -0.189735 -0.52397 -0.980622 -0.0667029 -0.184205 -0.980621 -0.0667034 -0.184207 -0.896065 -0.151145 -0.4174 -0.792167 -0.205963 -0.574501 -0.980623 -0.174617 -0.0888156 -0.980623 -0.174617 -0.0888155 -0.830332 -0.49671 -0.252642 -0.830331 -0.496711 -0.252642 -0.553851 -0.742135 -0.377472 -0.553849 -0.799656 -0.231952 -0.553852 -0.828931 -0.0782384 -0.553849 -0.828933 -0.0782387 -0.830339 -0.554793 -0.052364 -0.980621 -0.195047 0.0184093 -0.980622 -0.195044 0.018409 -0.830339 -0.554793 0.0523637 -0.830345 -0.554784 0.0523632 -0.553852 -0.828931 0.0782385 -0.553849 -0.828933 0.0782386 -0.194265 -0.33399 -0.92234 -0.194249 -0.333991 -0.922343 -0.553862 -0.283483 -0.782863 -0.440843 -0.301938 -0.845276 -0.607056 -0.270562 -0.74718 -0.980621 -0.0999911 -0.168474 -0.980622 -0.0999907 -0.168473 -0.830335 -0.28442 -0.479217 -0.830336 -0.28442 -0.479216 -0.553862 -0.424952 -0.715997 -0.553864 -0.424952 -0.715996 0.49378 -0.443826 -0.747797 -0.194788 -0.531998 -0.824036 -0.195067 -0.702981 -0.683934 0.298206 -0.632139 -0.715174 -0.553854 -0.551416 -0.623848 -0.553864 -0.551412 -0.623843 -0.830335 -0.36906 -0.417538 -0.830335 -0.36906 -0.417538 -0.980622 -0.129746 -0.146788 -0.980622 -0.129747 -0.14679 -0.980622 -0.154919 -0.119921 -0.980622 -0.154916 -0.119919 -0.830336 -0.440664 -0.341112 -0.830332 -0.440668 -0.341115 -0.553853 -0.658402 -0.509661 -0.553851 -0.658403 -0.509661 -0.19427 -0.775699 -0.600459 -0.194277 -0.775698 -0.600457 -0.980621 -0.195047 -0.0184094 -0.830345 -0.554784 -0.0523629 -0.830345 -0.53519 -0.155239 -0.553865 -0.799646 -0.231948 -0.553865 -0.742127 -0.377468 0.298209 -0.850774 -0.432729 -0.195077 -0.838284 -0.509141 -0.194955 -0.955903 0.219642 -0.194258 -0.97661 0.0921761 -0.194287 -0.976604 0.0921765 -0.194287 -0.976605 -0.0921756 -0.194258 -0.97661 -0.092177 -0.194956 -0.955903 -0.219642 0.493778 -0.835164 -0.242251 -0.194806 -0.931062 -0.308502 -0.194573 -0.882509 -0.428159 -0.980622 -0.188155 0.054577 -0.980623 -0.188151 0.054576 -0.830344 -0.53519 0.15524 -0.830331 -0.535209 0.155245 -0.55385 -0.799656 0.231951 -0.553865 -0.799646 0.231949 0.493779 -0.835163 0.242251 -0.194805 -0.931062 0.308502 -0.195077 -0.838284 0.509142 0.298213 -0.850773 0.432729 -0.553854 -0.742133 0.377471 -0.553865 -0.742126 0.377468 -0.83033 -0.496712 0.252643 -0.830331 -0.496711 0.252642 -0.980623 -0.174616 0.0888152 -0.980623 -0.174617 0.0888156 -0.980623 -0.154915 0.119918 -0.980622 -0.15492 0.119921 -0.830331 -0.44067 0.341117 -0.830338 -0.440662 0.34111 -0.553855 -0.658401 0.50966 -0.553853 -0.658402 0.50966 -0.194278 -0.775698 0.600457 -0.19427 -0.775699 0.600458 -0.980622 -0.129746 0.146789 -0.980622 -0.129747 0.14679 -0.830338 -0.369058 0.417536 -0.830333 -0.369062 0.41754 -0.553854 -0.551416 0.623848 -0.553864 -0.551412 0.623843 0.298205 -0.632139 0.715174 -0.194563 -0.635669 0.747041 -0.194963 -0.452196 0.870349 0.493783 -0.443825 0.747795 -0.553868 -0.42495 0.715994 -0.553865 -0.424951 0.715996 -0.830333 -0.284422 0.47922 -0.830332 -0.284423 0.47922 -0.980622 -0.0999895 0.168471 -0.980622 -0.0999907 0.168473 -0.980622 -0.0667022 0.184204 -0.980622 -0.0667029 0.184205 -0.830332 -0.189737 0.523973 -0.830332 -0.189737 0.523974 -0.553868 -0.283482 0.782859 -0.55386 -0.283484 0.782864 -0.194265 -0.33399 0.92234 -0.194265 -0.33399 0.92234 0.959809 -0.266166 0.0890015 0.965282 -0.250325 0.0746228 0.697788 -0.705852 0.121926 0.707094 -0.697978 0.113337 0.251862 -0.959737 0.124384 0.258741 -0.958407 0.120453 0.947124 -0.272267 0.169787 0.951831 -0.260729 0.161361 0.68631 -0.713083 0.143147 0.696212 -0.704759 0.136394 0.244526 -0.96635 0.0798486 0.257253 -0.963472 0.074447 -0.190566 -0.447121 -0.873938 -0.253274 -0.444892 -0.859025 -0.433674 -0.41041 -0.802179 -0.599433 -0.364569 -0.712579 -0.699189 -0.3315 -0.633437 -0.786165 -0.281487 -0.550191 -0.892507 -0.205431 -0.401534 -0.964597 -0.124674 -0.2324 -0.97986 -0.0909509 -0.177772 -0.253017 -0.765035 -0.592203 -0.253009 -0.765036 -0.592205 -0.698469 -0.565903 -0.438058 -0.698471 -0.565902 -0.438057 -0.964317 -0.209355 -0.162059 -0.964317 -0.209354 -0.162058 -0.256288 -0.925026 -0.280433 -0.256291 -0.925026 -0.280432 -0.703388 -0.680234 -0.206221 -0.703388 -0.680234 -0.206221 -0.965237 -0.250134 -0.075831 -0.965238 -0.250132 -0.0758301 0.964318 -0.120584 0.235692 0.965238 -0.250131 0.0758296 0.965237 -0.250135 0.0758315 0.703388 -0.680234 0.206221 0.70339 -0.680232 0.20622 0.256284 -0.925028 0.280433 0.964317 -0.209356 0.16206 0.964318 -0.209354 0.162058 0.698475 -0.565898 0.438054 0.698469 -0.565903 0.438059 0.964317 -0.120585 0.235694 0.786127 -0.281509 0.550234 0.699189 -0.331497 0.633439 0.599461 -0.364559 0.712561 0.433675 -0.410408 0.802179 0.256281 -0.925028 0.280433 0.253002 -0.765037 0.592206 0.25301 -0.765036 0.592204 0.253267 -0.444892 0.859027 0.190576 -0.44712 0.873936 -0.95981 -0.266166 -0.0890006 -0.965282 -0.250326 -0.0746229 -0.697789 -0.70585 -0.121926 -0.707094 -0.697978 -0.113338 -0.251867 -0.959735 -0.124385 -0.258749 -0.958405 -0.120453 -0.947113 -0.272293 -0.169806 -0.951831 -0.260729 -0.161361 -0.68631 -0.713083 -0.143147 -0.696213 -0.704758 -0.136392 -0.244532 -0.966348 -0.0798488 -0.257259 -0.96347 -0.0744478 0.792042 -0.20785 0.573993 0.83032 -0.189743 -0.523991 0.607084 -0.270555 0.747161 0.553878 -0.28348 -0.782853 0.194241 -0.333992 -0.922345 -0.298196 -0.632141 -0.715177 0.194258 -0.33399 -0.922342 0.194956 -0.452198 -0.87035 -0.493766 -0.44383 -0.747804 0.19478 -0.531999 -0.824037 0.194549 -0.63567 -0.747044 -0.493763 -0.835171 -0.242253 0.19506 -0.702982 -0.683935 0.194263 -0.7757 -0.600459 0.194271 -0.775699 -0.600458 0.19507 -0.838285 -0.509142 -0.298199 -0.850777 -0.432731 0.194566 -0.88251 -0.428159 0.194798 -0.931064 -0.308503 -0.298202 -0.850776 0.43273 0.194948 -0.955904 -0.219642 0.19425 -0.976612 -0.0921763 0.194279 -0.976606 -0.0921766 0.194279 -0.976606 0.0921757 0.19425 -0.976612 0.0921772 0.194948 -0.955904 0.219642 -0.493764 -0.835171 0.242253 0.194798 -0.931064 0.308503 0.194566 -0.88251 0.428159 -0.493769 -0.443829 0.747802 0.19507 -0.838285 0.509143 0.194271 -0.775699 0.600458 0.194263 -0.7757 0.600459 0.19506 -0.702982 0.683935 -0.298194 -0.632141 0.715177 0.194556 -0.635669 0.747043 0.194788 -0.531999 0.824036 0.194956 -0.452197 0.870351 0.194258 -0.333991 0.922342 0.194259 -0.333991 0.922341 0.55388 -0.283479 -0.782852 0.55388 -0.424946 -0.715987 0.553883 -0.424946 -0.715986 0.553882 -0.551404 -0.623834 0.553872 -0.551408 -0.623839 0.55387 -0.658393 -0.509653 0.553869 -0.658394 -0.509654 0.553868 -0.742125 -0.377467 0.553882 -0.742116 -0.377463 0.553883 -0.799634 -0.231945 0.553867 -0.799644 -0.231948 0.553867 -0.828921 -0.0782375 0.553869 -0.82892 -0.0782374 0.553869 -0.82892 0.0782373 0.553867 -0.828921 0.0782375 0.553867 -0.799644 0.231948 0.553883 -0.799635 0.231945 0.553882 -0.742116 0.377462 0.553872 -0.742122 0.377466 0.553873 -0.658392 0.509652 0.55387 -0.658393 0.509654 0.553872 -0.551408 0.623839 0.553882 -0.551404 0.623834 0.553882 -0.424946 0.715986 0.553886 -0.424944 0.715984 0.553886 -0.283478 0.782848 0.440844 -0.301937 0.845275 0.830317 -0.189744 -0.523994 0.830317 -0.284434 -0.479239 0.830317 -0.284434 -0.479239 0.830317 -0.369078 -0.417558 0.830317 -0.369078 -0.417558 0.830318 -0.440685 -0.341128 0.830315 -0.440689 -0.341131 0.830314 -0.496734 -0.252654 0.830314 -0.496734 -0.252654 0.830314 -0.535235 -0.155252 0.830327 -0.535216 -0.155247 0.830327 -0.55481 -0.0523657 0.830321 -0.554819 -0.0523661 0.830322 -0.554819 0.0523665 0.830327 -0.554811 0.0523654 0.830327 -0.535216 0.155247 0.830314 -0.535235 0.155253 0.830314 -0.496734 0.252654 0.830312 -0.496736 0.252655 0.830313 -0.440691 0.341133 0.83032 -0.440683 0.341127 0.83032 -0.369075 0.417555 0.830315 -0.36908 0.417561 0.830315 -0.284436 0.479242 0.830315 -0.284436 0.479243 0.830257 -0.188547 0.524522 0.965588 -0.0903807 0.243865 0.980622 -0.0667022 0.184204 0.980622 -0.0999896 0.168471 0.980622 -0.0999907 0.168473 0.980622 -0.129747 0.14679 0.980622 -0.129746 0.146789 0.980622 -0.15492 0.119921 0.980623 -0.154916 0.119918 0.980623 -0.174616 0.0888152 0.980623 -0.174617 0.0888157 0.980623 -0.188151 0.0545759 0.980622 -0.188155 0.0545771 0.980622 -0.195044 0.0184089 0.980621 -0.195047 0.0184094 0.980621 -0.195047 -0.0184093 0.980622 -0.195044 -0.018409 0.980622 -0.188155 -0.054577 0.980623 -0.188151 -0.054576 0.980623 -0.174617 -0.0888156 0.980623 -0.174617 -0.0888157 0.980622 -0.154916 -0.119919 0.980622 -0.154919 -0.119921 0.980622 -0.129745 -0.146788 0.980622 -0.129747 -0.14679 0.980622 -0.0999908 -0.168473 0.980621 -0.0999911 -0.168474 0.980621 -0.0667035 -0.184207 0.980622 -0.0667029 -0.184205 -0.160208 -0.312473 -0.936319 -0.0422281 -0.968116 -0.24692 -0.115779 -0.727298 -0.676485 -0.161049 -0.309553 -0.937145 -0.464018 -0.309527 -0.829988 -0.419008 0.0419866 -0.907011 -0.896946 -0.269468 -0.350535 -0.903311 -0.225558 -0.364901 -0.820124 -0.290918 -0.49271 -0.718705 -0.287206 -0.633226 -0.713262 -0.301101 -0.632926 -0.537836 -0.304112 -0.786288 -0.116403 -0.726013 -0.677758 -0.33432 -0.726108 -0.60083 -0.337319 -0.722294 -0.603744 -0.517333 -0.722371 -0.458854 -0.523404 -0.716211 -0.461616 -0.645743 -0.716326 -0.264374 -0.654401 -0.708162 -0.265079 -0.0424612 -0.967953 -0.247515 -0.121986 -0.967976 -0.219412 -0.123222 -0.967495 -0.220838 -0.189025 -0.967521 -0.16785 -0.191668 -0.966739 -0.16935 -0.236493 -0.966777 -0.0970242 -0.240416 -0.965739 -0.0977191 0.980063 -0.0860583 -0.17908 0.980063 -0.0860587 -0.179081 0.826517 -0.243819 -0.507367 0.826519 -0.243818 -0.507365 0.548264 -0.362236 -0.753784 0.548261 -0.362238 -0.753786 0.191524 -0.425121 -0.884642 0.191544 -0.425118 -0.884639 0.980063 -0.147589 -0.133017 0.980063 -0.147588 -0.133016 0.826519 -0.418143 -0.376859 0.826517 -0.418146 -0.376861 0.54826 -0.621232 -0.559895 0.548265 -0.621229 -0.559893 0.191543 -0.729072 -0.657089 0.191542 -0.729072 -0.657089 0.980064 -0.18703 -0.0670455 0.980063 -0.187031 -0.0670457 0.826516 -0.529895 -0.189954 0.826514 -0.529898 -0.189955 0.548266 -0.78725 -0.282209 0.548265 -0.787251 -0.282209 0.191541 -0.923915 -0.331199 0.191543 -0.923915 -0.331199 0 -0.316562 -0.948572 1.13346e-06 -0.96898 -0.24714 1.19484e-06 -0.968981 -0.247137 2.76987e-06 -0.73223 -0.681057 3.37625e-06 -0.732253 -0.681033 3.75383e-06 -0.316567 -0.94857 4.86323e-06 -0.316626 -0.948551 1.33348e-07 -0.96898 -0.24714 1.33348e-07 -0.96898 -0.24714 3.6748e-07 -0.732223 -0.681065 5.65018e-07 -0.73223 -0.681057 5.97219e-07 -0.316546 -0.948577 1.44876e-06 -0.316567 -0.94857 0.546913 -0.828068 -0.123246 0.183454 -0.980942 -0.0640155 0.194336 -0.978368 -0.0709179 0.42577 -0.899025 -0.102342 0.584049 -0.797477 -0.151385 0.965748 -0.197135 -0.168728 0.964213 -0.209404 -0.162614 0.817617 -0.553781 -0.157572 0.864847 -0.452888 -0.216638 0.773419 -0.616449 -0.147696 0.979555 -0.185188 -0.0785961 0.976294 -0.204404 -0.0712017 0.831144 -0.545093 -0.109878 0.82344 -0.5578 -0.103953 0.555582 -0.821996 -0.125103 0.547198 -0.828267 -0.120617 0.195032 -0.973217 -0.121699 0.189149 -0.974727 -0.118868 0.636103 -0.728968 -0.25294 0.638983 -0.727346 -0.250337 0.461652 -0.555662 -0.691461 0.461896 -0.555623 -0.691328 0.169787 -0.241626 -0.9554 0.166517 -0.241445 -0.956021 0.460414 -0.852132 -0.248777 0.463537 -0.852276 -0.242402 0.335105 -0.650433 -0.681647 0.335333 -0.65058 -0.681394 0.124918 -0.284953 -0.950367 0.120337 -0.280725 -0.952214 0.158999 -0.956655 -0.243988 0.160058 -0.95711 -0.241499 0.115281 -0.727371 -0.676492 0.115333 -0.727441 -0.676408 0.0425852 -0.316338 -0.94769 0.0414668 -0.314207 -0.948448 0.159822 -0.312493 -0.936379 0.911427 -0.207278 -0.355439 0.911335 -0.207981 -0.355263 0.827652 -0.447781 -0.338356 0.732347 -0.610913 -0.300755 0.409969 -0.896479 -0.16808 0.563462 -0.793407 -0.230252 0.18115 -0.980654 -0.0741749 0.818779 -0.291153 -0.494805 0.713741 -0.287334 -0.638759 0.712695 -0.301084 -0.633573 0.536413 -0.30426 -0.787202 0.481959 -0.12726 -0.866903 0.396045 -0.312442 -0.86344 0.159313 -0.309605 -0.937424 0.652184 -0.714884 -0.252183 0.520118 -0.716215 -0.46531 0.516652 -0.722316 -0.459708 0.334532 -0.722294 -0.605293 0.333632 -0.726064 -0.601266 0.115237 -0.726064 -0.677902 0.115401 -0.727331 -0.676515 0.241798 -0.966272 -0.0886146 0.190526 -0.966736 -0.17065 0.188742 -0.967509 -0.168237 0.122253 -0.967492 -0.221392 0.121698 -0.967968 -0.219607 0.0420499 -0.967961 -0.247554 0.0420723 -0.968122 -0.246921 0.679842 -0.687818 -0.254406 0.679113 -0.687953 -0.255981 0.496216 -0.51725 -0.697296 0.492469 -0.516073 -0.700816 0.184178 -0.212634 -0.959617 0.176475 -0.209075 -0.961844 0.678394 -0.689868 -0.252711 0.677641 -0.690017 -0.254321 0.493827 -0.524524 -0.693549 0.490084 -0.52338 -0.697059 0.18308 -0.224937 -0.957019 0.175406 -0.221404 -0.959277 -1.44876e-06 -0.316567 -0.94857 -1.33348e-07 -0.96898 -0.24714 -1.33348e-07 -0.96898 -0.24714 -3.67475e-07 -0.73223 -0.681057 -5.65021e-07 -0.732223 -0.681065 -5.97219e-07 -0.316546 -0.948577 0 -0.316562 -0.948572 -1.13345e-06 -0.968981 -0.247137 -1.19485e-06 -0.96898 -0.24714 -2.76978e-06 -0.732253 -0.681033 -3.3763e-06 -0.73223 -0.681057 -3.75384e-06 -0.316626 -0.948551 -4.86317e-06 -0.316567 -0.94857 0.168975 -0.213359 -0.96225 0.172685 -0.212847 -0.961705 0.466445 -0.539263 -0.701159 0.469237 -0.538624 -0.699786 0.640808 -0.723591 -0.25648 0.64271 -0.722506 -0.254772 0.123148 -0.242599 -0.962279 0.127885 -0.245954 -0.960808 0.340769 -0.629836 -0.697985 0.343898 -0.631656 -0.694798 0.466121 -0.847462 -0.254047 0.467761 -0.847566 -0.250664 0.0429078 -0.268461 -0.962335 0.0441881 -0.270263 -0.961772 0.118277 -0.706451 -0.697809 0.119095 -0.707415 -0.696693 0.161555 -0.95376 -0.253459 0.162004 -0.953954 -0.252443 -0.0169036 -0.315996 -0.94861 -0.0524215 -0.967721 -0.24651 -0.0527334 -0.967632 -0.246793 -0.0377555 -0.731744 -0.680533 -0.0377741 -0.731731 -0.680546 -0.013663 -0.313868 -0.949368 -0.00337765 -0.316624 -0.948545 -0.262159 -0.934374 -0.241283 -0.263244 -0.933008 -0.245354 -0.190037 -0.710527 -0.677523 -0.190061 -0.710383 -0.677667 -0.0693314 -0.306039 -0.949491 -0.069216 -0.309915 -0.948241 -0.552533 -0.797229 -0.243172 -0.553467 -0.794308 -0.250498 -0.402053 -0.608852 -0.683851 -0.401997 -0.608544 -0.684158 -0.146064 -0.261525 -0.954081 -0.148154 -0.268121 -0.951925 0 -0.966456 -0.256833 0 -0.966456 -0.256833 0 -0.711452 -0.702735 -2.73279e-08 -0.711445 -0.702742 -1.03222e-08 -0.268725 -0.963217 -5.76423e-08 -0.268708 -0.963222 0 -0.966456 -0.256833 0 -0.966456 -0.256833 0 -0.711445 -0.702742 3.62222e-08 -0.711452 -0.702735 1.36808e-08 -0.268708 -0.963222 7.64037e-08 -0.268725 -0.963217 -0.67806 -0.689607 -0.254318 -0.677983 -0.690281 -0.25269 -0.49131 -0.522147 -0.697121 -0.492596 -0.52576 -0.693488 -0.177452 -0.219364 -0.95937 -0.181027 -0.226995 -0.956923 -0.679521 -0.687546 -0.255991 -0.679432 -0.688235 -0.254371 -0.493706 -0.514843 -0.70085 -0.494967 -0.518491 -0.697262 -0.17854 -0.207016 -0.961908 -0.182106 -0.214711 -0.95955 -0.0140491 -0.268921 -0.96306 -0.0143654 -0.268681 -0.963122 -0.0388344 -0.711029 -0.70209 -0.039034 -0.710903 -0.702206 -0.0532837 -0.965112 -0.256358 -0.0534136 -0.965076 -0.256466 -0.0712963 -0.265738 -0.961405 -0.0719031 -0.262251 -0.962317 -0.194758 -0.691097 -0.696028 -0.195279 -0.689092 -0.697867 -0.265577 -0.9306 -0.251898 -0.266119 -0.929972 -0.253639 -0.150488 -0.234713 -0.960345 -0.149412 -0.228204 -0.962081 -0.408686 -0.592793 -0.693954 -0.408319 -0.588523 -0.697794 -0.556828 -0.792163 -0.249842 -0.557565 -0.790255 -0.254201 0 0 -1 0 0 -1 0 0 -1 -0.989145 0 -0.146945 -0.979111 -0.080404 -0.186754 -0.955079 0.0792129 -0.285568 -0.941344 -0.00385327 -0.337427 -0.873607 0.000309496 -0.486631 -0.79642 -0.0153664 -0.604549 -0.773488 -0.0819455 -0.628491 -0.739033 0.14715 -0.657402 -0.608935 -0.107373 -0.785919 -0.550897 0.00305893 -0.834568 -0.424591 -0.00594879 -0.905366 -0.424591 -0.00565885 -0.905368 -0.237332 0.00738946 -0.971401 -0.242041 -0.0330652 -0.969703 -0.065567 0.0262667 -0.997502 -0.0825533 0 -0.996587 0.0160822 0 -0.999871 0.0813394 -0.01585 -0.99656 0.114915 0.0125007 -0.993297 0.25525 -0.0148283 -0.966761 0.325972 0.039812 -0.944541 0.414931 -0.0209941 -0.909611 0.458378 -0.000284635 -0.888758 0.533125 0.000197023 -0.846036 0.549691 0.00642819 -0.835343 0.579913 -0.00171925 -0.814676 0.648638 0.00762303 -0.761059 0.656439 -0.0563834 -0.75227 0.8329 0.0591738 -0.55025 0.83796 0.00455244 -0.545713 0.876233 -0.00105865 -0.481887 0.922256 0.0131202 -0.386358 0.919262 -0.0503095 -0.390418 0.994307 0.0548948 -0.0913271 0.995451 0 -0.0952744 -0.374805 0.0065285 0.927081 -0.325357 0.0395224 0.944765 -0.255216 -0.0145417 0.966775 -0.114386 0.0122502 0.993361 -0.0812691 -0.0156662 0.996569 -0.015913 0 0.999873 -0.461508 -0.017366 0.886966 -0.513038 0.0154852 0.858226 -0.5798 -0.00176425 0.814757 -0.648189 0.00788665 0.761439 -0.656427 -0.0561069 0.7523 -0.832214 0.0587211 0.551336 -0.838716 -0.0115211 0.544448 -0.922503 0.0140531 0.385735 -0.919712 -0.0501031 0.389383 -0.994334 0.0547025 0.0911437 -0.995508 0 0.0946739 0 0 1 0 0 1 0 0 1 0.989141 0 0.146967 0.979224 -0.0800026 0.186334 0.954776 0.0783214 0.286825 0.941832 -0.00173661 0.336081 0.810102 0.00147076 0.586288 0.774675 -0.0911228 0.625759 0.755621 0.0669112 0.651583 0.0826013 0 0.996583 0.0666408 0.0246138 0.997473 0.24334 -0.0308755 0.96945 0.238931 0.00490612 0.971024 0.469935 -0.00589899 0.882682 0.495894 0.0876489 0.863948 0.583052 -0.0478516 0.811025 -0.374974 0.00673053 0.927011 -0.325967 0.0398098 0.944542 -0.255251 -0.0148259 0.966761 -0.114915 0.0125052 0.993297 -0.0813404 -0.0158447 0.99656 -0.0161053 0 0.99987 -0.461408 -0.0177348 0.887011 -0.513859 0.0158165 0.857729 -0.57992 -0.00172317 0.814671 -0.648633 0.00761691 0.761063 -0.656433 -0.0563889 0.752274 -0.832896 0.0591668 0.550258 -0.838918 -0.0107708 0.544152 -0.922252 0.0131131 0.386366 -0.919258 -0.0503154 0.390426 -0.994306 0.0548883 0.0913349 -0.99545 0 0.0952818 0 0 1 0 0 1 0 0 1 0.989144 0 0.14695 0.97911 -0.0804008 0.186758 0.955079 0.0792114 0.285569 0.941342 -0.00385941 0.337431 0.810949 0.00327042 0.585107 0.774027 -0.091861 0.626453 0.755895 0.0667798 0.651278 0.082557 0 0.996586 0.0655719 0.026265 0.997502 0.242037 -0.0330641 0.969703 0.23733 0.00738169 0.971401 0.467672 -0.00881401 0.883858 0.496539 0.0926228 0.863059 0.579693 -0.0494004 0.813336 0 0 -1 0 0 -1 0 0 -1 -0.989141 0 -0.146967 -0.979224 -0.0800026 -0.186334 -0.954776 0.0783219 -0.286825 -0.941833 -0.00173051 -0.336078 -0.873183 0.00014852 -0.487393 -0.796393 -0.0161831 -0.604564 -0.774098 -0.0816713 -0.627775 -0.738707 0.145397 -0.658158 -0.61387 -0.102874 -0.782675 -0.551575 0.00400698 -0.834116 -0.426071 -0.00795561 -0.904655 -0.426013 -0.00376538 -0.904709 -0.238931 0.00490612 -0.971024 -0.24334 -0.0308755 -0.96945 -0.0666344 0.0246158 -0.997474 -0.0825961 0 -0.996583 0.374805 0.00652941 -0.927081 0.325359 0.0395236 -0.944764 0.255213 -0.0145438 -0.966776 0.114385 0.0122459 -0.993361 0.0812674 -0.0156714 -0.996569 0.0158896 0 -0.999874 0.46151 -0.0173668 -0.886965 0.513041 0.0154845 -0.858225 0.579788 -0.00176107 -0.814766 0.648188 0.0078919 -0.76144 0.656427 -0.0561055 -0.752301 0.832219 0.058726 -0.551328 0.83872 -0.0115145 -0.544441 0.922503 0.0140593 -0.385733 0.919713 -0.0501063 -0.389382 0.994334 0.0546957 -0.0911523 0.995508 0 -0.0946821 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.145105 0 0.989416 -0.108482 -0.0680424 0.991767 -0.30768 0.0277418 0.951085 -0.409951 0.112244 0.905175 -0.361811 -3.31496e-05 0.932251 -0.512857 3.09571e-06 0.858474 -0.54447 -0.00689309 0.838752 -0.603085 0.0272398 0.797211 -0.712353 0.146485 0.686364 -0.663721 -0.0912655 0.742391 -0.831237 0.0254487 0.555335 -0.823736 0.0147095 0.566783 -0.855799 1.21174e-05 0.517308 -0.921664 -9.39572e-05 0.387988 -0.910099 -0.0523054 0.411076 -0.967402 0.0225499 0.252241 -0.980421 0.0793398 0.180223 -0.993422 0 0.114512 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0.640283 -0.0257296 0.767708 0.989427 0 0.145035 0.992803 -0.0591583 0.104127 0.949489 0.022474 0.312995 0.951179 0.0191029 0.308049 0.736753 0.0787188 0.671564 0.735617 0.0805668 0.67259 0.791428 0.0242573 0.610781 0.889649 -0.049854 0.453915 0.872197 7.41842e-05 0.489154 0.933871 -1.68571e-05 0.357611 0.167299 0 0.985906 0.103423 0.125032 0.986748 0.234715 0.0285087 0.971646 0.485924 -0.0966571 0.86864 0.383739 0.149701 0.911227 0.543156 0.0268887 0.839201 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.989452 0 -0.144865 -0.992817 -0.0565039 -0.10546 -0.949795 0.0209579 -0.312171 -0.839157 -0.00833338 -0.543825 -0.898483 0.0994342 -0.427599 -0.92983 6.57549e-05 -0.36799 -0.855598 -1.43144e-05 -0.51764 -0.562009 0.0112934 -0.827054 -0.545152 0.0253661 -0.837953 -0.746132 -0.0880343 -0.659952 -0.664779 0.139741 -0.733854 -0.792433 0.0228427 -0.609531 -0.167149 0 -0.985932 -0.107036 0.121129 -0.986849 -0.237779 0.0266773 -0.970953 -0.418111 -0.0591962 -0.906465 -0.38345 4.54151e-05 -0.923562 -0.513331 -7.72197e-06 -0.858191 0 0 -1 0 0 -1 0 0 -1 0.145106 0 -0.989416 0.108077 -0.0709531 -0.991607 0.307299 0.0296805 -0.95115 0.297759 0.0216836 -0.954395 0.456936 -0.056586 -0.887698 0.488275 -2.05786e-05 -0.87269 0.356527 4.49747e-06 -0.934285 0.831406 0.0268621 -0.555015 0.768558 -0.0242896 -0.639319 0.653234 0.0769614 -0.753235 0.657585 0.0878981 -0.748236 0.602997 0.0289376 -0.797218 0.895513 0.146501 -0.420232 0.874777 -0.0885419 -0.476366 0.96766 0.0240057 -0.251115 0.980109 0.0815103 -0.180947 0.993519 0 -0.113663 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 -0.640284 -0.0257357 -0.767707 -0.989427 0 -0.145035 -0.992803 -0.0591461 -0.104136 -0.949488 0.0224832 -0.312996 -0.951178 0.0191123 -0.308051 -0.736756 0.0787144 -0.671561 -0.735617 0.0805663 -0.67259 -0.791427 0.024259 -0.610783 -0.889649 -0.0498536 -0.453915 -0.872197 7.47711e-05 -0.489154 -0.933861 -1.64117e-05 -0.357635 -0.167299 0 -0.985906 -0.103423 0.125031 -0.986748 -0.234708 0.0285122 -0.971648 -0.485924 -0.0966571 -0.86864 -0.383739 0.149701 -0.911227 -0.543172 0.0268761 -0.839192 0.145105 0 -0.989416 0.108482 -0.0680424 -0.991767 0.307673 0.027738 -0.951088 0.299458 0.0211377 -0.953875 0.457155 -0.0543211 -0.887727 0.488105 -1.6e-05 -0.872785 0.356403 1.50741e-06 -0.934333 0.831237 0.0254493 -0.555335 0.768168 -0.0237357 -0.639808 0.655178 0.0765239 -0.751589 0.658613 0.0847884 -0.74769 0.6031 0.0272547 -0.7972 0.896383 0.141618 -0.420049 0.875065 -0.084691 -0.476539 0.967395 0.0225272 -0.252269 0.980421 0.0793398 -0.180223 0.993422 0 -0.114512 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.640593 -0.0249376 0.767476 0.989451 0 0.14487 0.992816 -0.0565015 0.105467 0.949795 0.0209579 0.312171 0.950947 0.0187188 0.308787 0.736898 0.0780235 0.671486 0.736987 0.0778788 0.671406 0.792435 0.0228344 0.609529 0.889289 -0.0477037 0.45485 0.872473 8.24395e-05 0.488663 0.934014 -1.85224e-05 0.357236 0.167148 0 0.985932 0.107035 0.121129 0.986849 0.237779 0.0266773 0.970953 0.484488 -0.092505 0.869893 0.388376 0.144457 0.910108 0.545137 0.0253781 0.837963 -0.145106 0 0.989416 -0.108077 -0.0709531 0.991607 -0.307289 0.0296755 0.951153 -0.297758 0.021686 0.954395 -0.456937 -0.0565858 0.887698 -0.488277 -1.65069e-05 0.872688 -0.356527 7.29659e-06 0.934285 -0.831394 0.0268432 0.555035 -0.768558 -0.0242963 0.639318 -0.653232 0.0769575 0.753237 -0.65759 0.0879107 0.74823 -0.602982 0.028928 0.79723 -0.895514 0.146504 0.420228 -0.874777 -0.0885499 0.476365 -0.967653 0.0239832 0.251142 -0.980109 0.0815103 0.180947 -0.993519 0 0.113663 0 0 1 0 0 1 0 0 1 -0.499995 -2.08146e-05 0.866028 -0.499998 -2.39142e-06 0.866027 -0.5 0 0.866025 -0.499999 0 0.866026 -0.499935 -4.303e-05 0.866063 -0.500027 -0.000135018 0.86601 -0.498518 -0.000134061 0.866879 -0.5 0 0.866025 -0.499931 -0.000223686 0.866065 -0.498164 -0.00022081 0.867083 -0.499998 0 0.866026 -0.499826 -0.000449783 0.866126 -0.499782 -0.00044971 0.866151 -0.5 0 0.866026 -0.500036 8.13829e-05 0.866005 -0.498714 8.74018e-05 0.866767 -0.499999 0 0.866026 -0.500288 0.000576472 0.865859 -0.499313 0.000582891 0.866421 -0.499998 0 0.866026 -0.500359 0.000610219 0.865818 -0.499793 0.000613765 0.866145 -0.499999 0 0.866026 -0.500332 0.000423127 0.865834 -0.498367 0.00043115 0.866966 -0.499988 0 0.866032 -0.500118 2.41474e-05 0.865957 -0.500109 0.000156838 0.865963 -0.500003 -9.85205e-06 -0.866024 -0.499995 -6.51957e-06 -0.866028 -0.5 0 -0.866025 0.500127 0 -0.865952 0.500059 -9.52422e-05 -0.865992 0.500012 -1.3575e-05 0.866019 0.499999 0 0.866026 -0.498377 0.000270526 -0.86696 -0.499917 0.000266619 -0.866073 -0.500082 0.000204616 -0.865978 -0.499999 0 -0.866026 0.499575 -0.0004069 -0.86627 0.500518 -0.000403268 -0.865726 0.499998 0 -0.866027 0.500001 0 0.866025 0.500237 -0.000310137 0.865889 0.498226 -0.000315727 0.867047 -0.498027 0.000542898 -0.867162 -0.500164 0.000531696 -0.865931 -0.5 0 -0.866025 0.499223 -0.000602183 -0.866473 0.500615 -0.000593624 -0.86567 0.500001 0 -0.866025 0.5 0 0.866025 0.500422 -0.000554714 0.865781 0.498459 -0.000565367 0.866913 -0.499703 0.000601507 -0.866196 -0.500227 0.000598023 -0.865894 -0.499998 0 -0.866026 0.49923 -0.000607911 -0.86647 0.500554 -0.000599105 -0.865705 0.499999 0 -0.866026 0.499998 0 0.866026 0.500468 -0.000579882 0.865755 0.499758 -0.000584613 0.866165 -0.498634 0.000379261 -0.866813 -0.500162 0.00037015 -0.865932 -0.5 0 -0.866025 0.499589 -0.00013218 -0.866262 0.50011 -0.000129672 -0.865962 0.499999 0 -0.866026 0.499999 0 0.866026 0.500289 -0.000337711 0.865858 0.499549 -0.000342002 0.866286 -0.499275 -0.000290891 -0.866443 -0.499853 -0.000292483 -0.86611 -0.499999 0 -0.866026 0.499831 0.000456206 -0.866123 0.499629 0.000455869 -0.866239 0.499998 0 -0.866026 0.5 0 0.866026 0.499665 0.000362019 0.866219 0.499181 0.000360856 0.866497 -0.499709 -0.000115297 -0.866193 -0.49993 -0.000115716 -0.866066 -0.499998 0 -0.866026 0.499438 0.000232042 -0.866349 0.499823 0.000232681 -0.866128 0.5 0 -0.866025 0.500001 0 0.866025 0.499765 0.000227324 0.866161 0.498742 0.000225467 0.86675 -0.498232 -0.0001101 -0.867044 -0.499911 -0.000112239 -0.866077 -0.5 0 -0.866026 0.496988 0.000149876 -0.867758 0.499885 0.000152 -0.866092 0.500001 0 -0.866025 0.499998 0 0.866027 0.499898 7.74302e-05 0.866085 0.500551 7.82149e-05 0.865707 -0.499947 0 -0.866056 -0.499944 -7.22037e-05 -0.866058 -0.499963 -7.66685e-05 -0.866047 0.499963 3.96266e-05 -0.866047 0.5 0 -0.866025 0.499999 0 0.866026 0.499959 2.13151e-05 0.866049 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0.499999 5.40608e-06 0.866026 0.500001 4.6115e-06 0.866025 0.499997 0 0.866027 0.500009 0 -0.86602 0.500112 1.9199e-05 -0.865961 0.500104 0.000149513 -0.865966 -0.500007 -8.49856e-06 -0.866022 -0.499999 0 -0.866026 -0.500223 0 0.865897 -0.500104 -0.00016662 0.865966 0.498354 0.000336193 0.866974 0.499903 0.000331802 0.866082 0.500104 0.000256002 0.865965 0.500001 0 0.866025 0.5 0 -0.866026 0.500547 0.00069622 -0.865709 0.500875 0.000694557 -0.865519 -0.499997 0 -0.866027 -0.500275 -0.000366904 -0.865866 -0.50003 -0.000367675 -0.866008 -0.50075 -0.000672146 0.865592 -0.500865 -0.000671598 0.865525 -0.499998 0 0.866027 0.499957 0.000917988 0.86605 0.500282 0.000915743 0.865862 0.5 0 0.866025 0.500001 0 -0.866025 0.500843 0.00142357 -0.865537 0.499887 0.00143229 -0.866089 -0.5 0 -0.866026 -0.500726 -0.000953981 -0.865605 -0.499233 -0.000964787 -0.866467 -0.500664 -0.00125403 0.865641 -0.501289 -0.00124854 0.865279 -0.499996 0 0.866027 0.499642 0.00142198 0.866231 0.500541 0.00141267 0.865712 0.500001 0 0.866025 0.500001 0 -0.866025 0.500787 0.00157212 -0.865569 0.499356 0.0015886 -0.866395 -0.499998 0 -0.866026 -0.501155 -0.00143214 -0.865356 -0.499697 -0.00144754 -0.866199 -0.499277 -0.00156498 0.866441 -0.501422 -0.00154055 0.865201 -0.499999 0 0.866026 0.500097 0.0016931 0.865968 0.500736 0.00168537 0.865598 0.5 0 0.866025 0.5 0 -0.866025 0.50074 0.00169313 -0.865596 0.500021 0.00170188 -0.866012 -0.499999 0 -0.866026 -0.501443 -0.00168471 -0.865189 -0.499571 -0.00170745 -0.866271 -0.499533 -0.00171306 0.866293 -0.501448 -0.0016897 0.865186 -0.499999 0 0.866026 0.49936 0.00168328 0.866393 0.500835 0.00166596 0.865541 0.500001 0 0.866025 0.500001 0 -0.866025 0.500557 0.00145369 -0.865703 0.499639 0.00146349 -0.866233 -0.5 0 -0.866026 -0.501526 -0.00165013 -0.865141 -0.499282 -0.00167622 -0.866438 -0.499694 -0.00147955 0.866201 -0.501182 -0.00146341 0.865341 -0.499998 0 0.866026 0.49987 0.00128381 0.866099 0.500754 0.00127548 0.865589 0.500001 0 0.866025 0.5 0 -0.866025 0.500308 0.00099776 -0.865847 0.499943 0.00100046 -0.866058 -0.499996 0 -0.866027 -0.501268 -0.00122864 -0.865291 -0.501036 -0.00123076 -0.865426 -0.498373 -0.00106152 0.866962 -0.500794 -0.00104282 0.865566 -0.5 0 0.866025 0.500886 0.000737173 0.865513 0.50058 0.000738868 0.86569 0.5 0 0.866026 0.500568 0.000429856 -0.865697 0.500004 0 -0.866023 0.500001 -1.52031e-06 -0.866025 0.500001 -1.08681e-06 -0.866025 0.498789 -0.000913267 -0.866723 -0.499998 0 -0.866027 -0.500886 -0.000687997 -0.865513 -0.499652 -0.000694415 -0.866226 -0.501385 -0.000494589 0.865224 -0.500375 -0.000498252 0.865809 -0.499997 0 0.866027 0.500154 0 0.865937 0.500163 0.000214389 0.865931 0.500103 0.000228963 0.865966 0.500001 -3.19275e-06 -0.866025 0.500001 1.37334e-06 -0.866025 0.5 0 -0.866026 -0.499999 0 -0.866026 -0.500287 -0.00015285 -0.86586 -0.500024 -2.63043e-05 0.866012 -0.499999 0 0.866026 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0.0220512 -0.644965 0.763894 0.00109781 -0.480746 0.876859 -0.000342788 -0.507871 0.861433 0.0571007 -0.549942 0.833248 -0.0757532 -0.567823 0.819658 0.0119106 -0.61621 0.787492 -0.0106591 -0.635317 0.772178 0.0124299 -0.854398 0.519471 -0.00567915 -0.849535 0.527501 0.0342588 -0.816767 0.57595 0.0367995 -0.816443 0.576253 2.78242e-05 -0.787044 0.616898 0.000617899 -0.774846 0.63215 0.0098684 -0.96145 0.274804 -0.00419441 -0.959195 0.282714 0.0266719 -0.94314 0.331323 0.0272901 -0.943084 0.331432 0.000306642 -0.928162 0.372177 0.00073877 -0.921844 0.38756 0.00631192 -0.994155 0.107774 -0.00185107 -0.993629 0.112688 0.0140096 -0.990088 0.139747 0.0140974 -0.990084 0.139765 0.000594638 -0.986694 0.16259 0.000826359 -0.985112 0.171912 0.00546183 -0.99947 -0.0320879 -0.00191035 -0.999617 -0.0276035 0.0140931 -0.999901 0.000108507 0.0140699 -0.999901 0.000103689 0.000554452 -0.999723 0.023509 0.00076467 -0.999477 0.0323275 0.000603693 -0.994169 -0.10783 0.000406564 -0.993202 -0.1164 0.0143108 -0.990032 -0.140113 0.0143229 -0.990032 -0.140111 0.000551721 -0.986562 -0.163385 0.000683621 -0.985595 -0.169121 0.00225886 -0.984638 -0.174594 0.0105417 -0.921844 -0.387417 -0.00468793 -0.92517 -0.379525 0.0274892 -0.943217 -0.331037 0.0274782 -0.943217 -0.33104 0.000656929 -0.957378 -0.288839 0.00104387 -0.961922 -0.273321 0.0144299 -0.774875 -0.631949 -0.00688904 -0.781287 -0.624134 0.0370829 -0.816768 -0.575774 0.034346 -0.816581 -0.576209 0.000301356 -0.844793 -0.535094 0.000797102 -0.854367 -0.519669 0.0348331 -0.480515 -0.876294 -0.0182809 -0.494553 -0.868955 0.0124475 -0.51794 -0.855327 -0.0674839 -0.56831 -0.820042 0.0476894 -0.584304 -0.810133 -6.64329e-05 -0.626239 -0.779631 0.000813531 -0.644831 -0.764325 -0.0221522 -0.644697 -0.764118 -0.000719114 -0.480801 -0.87683 0.00074424 -0.508004 -0.861354 -0.0567827 -0.550177 -0.833115 0.0754562 -0.567985 -0.819573 -0.0118354 -0.616079 -0.787595 0.0105734 -0.635048 -0.772401 -0.0127517 -0.854331 -0.519573 0.00563281 -0.849395 -0.527728 -0.0340305 -0.816857 -0.575836 -0.0367443 -0.816511 -0.57616 -5.56469e-05 -0.78718 -0.616723 -0.000651838 -0.774926 -0.632052 -0.0104691 -0.961899 -0.273203 0.0040356 -0.959589 -0.281376 -0.0274773 -0.943218 -0.331037 -0.0274882 -0.943217 -0.331039 -0.000258066 -0.928168 -0.372162 -0.000702768 -0.921858 -0.387527 -0.00544876 -0.994161 -0.10777 0.00201068 -0.993676 -0.112268 -0.0143096 -0.990032 -0.140111 -0.0143216 -0.990032 -0.140113 -0.00054411 -0.98656 -0.163398 -0.000774431 -0.985073 -0.172138 -0.00568623 -0.99946 0.0323739 0.00189622 -0.999613 0.0277509 -0.0140673 -0.999901 0.000108507 -0.0140905 -0.999901 0.000103689 -0.000470978 -0.999724 -0.0234816 -0.000697197 -0.999483 -0.0321386 -0.00615995 -0.985087 0.171945 0.00206558 -0.985942 0.167073 -0.0141081 -0.990087 0.139747 -0.0140202 -0.990085 0.139765 -0.000783576 -0.993109 0.117191 -0.00103402 -0.994179 0.107732 -0.010688 -0.921777 0.387573 0.00467703 -0.925141 0.379596 -0.0273659 -0.943123 0.331317 -0.0267454 -0.943098 0.331437 -0.000338686 -0.957051 0.289918 -0.000759584 -0.961508 0.274775 -0.000247971 -0.76966 0.638454 -0.0124473 -0.854411 0.519448 0.00568547 -0.84954 0.527494 -0.0345549 -0.816508 0.576299 -0.0371174 -0.816683 0.575891 0.00517208 -0.78264 0.622453 -0.00710974 -0.781041 0.62444 -0.000292674 -0.777795 0.628518 -0.0351278 -0.480448 0.87632 -0.000739063 -0.645127 0.764075 0.000161659 -0.626517 0.779408 -0.0480567 -0.584162 0.810213 0.0673458 -0.568166 0.820154 -0.0126038 -0.517613 0.855522 0.0178441 -0.494461 0.869017 -0.0867363 -0.806345 0.585051 -0.150061 -0.815479 0.558996 -0.0853229 -0.837466 0.539788 -0.0898851 -0.93398 0.345835 -0.138444 -0.936585 0.321936 -0.089315 -0.949576 0.300546 -0.0885873 -0.986238 0.139595 -0.0957727 -0.98582 0.137791 -0.101496 -0.988367 0.11327 -0.095055 -0.995386 0.0130576 -0.120349 -0.992732 0 -0.0950648 -0.995385 -0.0130748 -0.0876085 -0.986565 -0.137896 -0.145756 -0.977915 -0.149789 -0.0948444 -0.987665 -0.124586 -0.0762945 -0.942935 -0.324118 -0.184923 -0.921573 -0.341331 -0.0892647 -0.949556 -0.300624 -0.0694701 -0.822826 -0.564032 -0.0960405 -0.818196 -0.566862 -0.101286 -0.847771 -0.520601 -0.0385666 -0.591105 -0.805672 -0.157669 -0.571269 -0.805476 -0.0927191 -0.636784 -0.765447 0.092756 -0.636749 -0.765472 0.157658 -0.571281 -0.80547 0.0386175 -0.591104 -0.80567 0.101286 -0.847771 -0.520601 0.0960406 -0.818196 -0.566862 0.0694709 -0.822826 -0.564032 0.0892654 -0.949556 -0.300625 0.184923 -0.921573 -0.341331 0.0762945 -0.942935 -0.324118 0.0948447 -0.987665 -0.124585 0.145759 -0.977915 -0.14979 0.0876085 -0.986565 -0.137896 0.0875839 -0.996157 0 0.145351 -0.989295 0.0129783 0.095065 -0.995385 -0.0130752 0.0876085 -0.986565 0.137896 0.095369 -0.985618 0.139508 0.101496 -0.988367 0.11327 0.0762945 -0.942935 0.324118 0.18456 -0.921664 0.34128 0.0893158 -0.949576 0.300547 0.0694709 -0.822826 0.564032 0.209307 -0.791463 0.574262 0.0853229 -0.837466 0.539788 0.0916423 -0.54155 0.835659 0.172994 -0.597551 0.782947 0.0312257 -0.591257 0.805879 -0.0311509 -0.591258 0.805881 -0.173018 -0.597569 0.782928 -0.0916419 -0.54155 0.835659 -0.886485 -0.0182342 0.462398 -0.74614 0.0136761 0.665648 -0.744918 0.0141376 0.667006 -0.617112 -0.00800004 0.786834 -0.483561 0.015151 0.875179 -0.366439 -0.0162803 0.9303 -0.168053 0.0163573 0.985642 -0.104157 0 0.994561 -0.993658 0 0.112446 -0.984716 -0.0127643 0.1737 -0.952749 0.00303231 0.303745 -0.93358 1.82817e-06 0.35837 -0.8594 -1.17786e-05 0.511304 -0.993597 0 -0.112978 -0.98576 0.0127144 -0.167677 -0.952156 -0.00300765 -0.305599 -0.870299 -0.0254774 -0.491865 -0.790194 0.0502435 -0.610793 -0.888391 0.00591088 -0.459049 -0.104044 0 -0.994573 -0.164581 -0.0163056 -0.986229 -0.37065 0.0164934 -0.928626 -0.36017 0.0194707 -0.932684 -0.653803 -0.0457935 -0.755278 -0.519373 0.059738 -0.852457 -0.668085 0.012442 -0.743981 0.985343 -0.0109989 0.17023 0.955116 0.0442786 0.292904 0.993423 0 0.114504 0.106567 0 0.994305 0.165735 -0.0158139 0.986044 0.298689 0.00427845 0.954341 0.356039 -1.28439e-05 0.934471 0.454844 2.74115e-05 0.890571 0.504807 -0.0110321 0.863162 0.661386 0.015253 0.749891 0.667214 0.0131929 0.744749 0.871273 -0.026634 0.490076 0.787711 0.0532801 0.613737 0.888024 0.00633923 0.459753 0.105951 0 -0.994371 0.16711 0.016143 -0.985806 0.370211 -0.0161155 -0.928808 0.482264 0.0153244 -0.875892 0.618257 -0.00811969 -0.785934 0.743515 0.0146449 -0.668559 0.745877 0.0137369 -0.665942 0.886108 -0.0183755 -0.463114 0.859638 -2.21661e-05 -0.510904 0.952027 1.63176e-05 -0.306013 0.934716 0.00930562 -0.355275 0.992949 -0.0197335 -0.116889 0.985603 0 -0.169078 0.985564 0 -0.169303 0.992584 0.0591436 -0.106203 0.905642 -0.0494785 -0.421147 0.166697 0 -0.986008 0.104344 -0.0757589 -0.991652 0.418887 0.0724157 -0.905146 0.371047 0.014171 -0.928506 0.561372 -0.00545458 -0.827545 0.659622 0.0471231 -0.750119 0.738549 -0.0428414 -0.672837 0.824156 0.00838078 -0.5663 0.854932 -2.627e-06 -0.51874 0.929635 1.41368e-05 -0.368483 0.166626 0 0.98602 0.106728 0.0752918 0.991434 0.354556 -0.0405539 0.934155 0.369272 -0.0512883 0.927905 0.506979 0.0335991 0.861303 0.65566 -0.0461009 0.753648 0.66285 -0.0393501 0.747717 0.780343 0.0202419 0.625024 0.869234 -0.0428499 0.49254 0.886207 -0.0191948 0.462893 0.951888 0.0091725 0.30631 0.983876 -0.0390027 0.17455 0.993321 0 0.11538 -0.993573 0 0.113196 -0.985263 0.0385764 0.166639 -0.951939 -0.00897219 0.306156 -0.933431 -4.90504e-06 0.358757 -0.887622 -3.4991e-05 0.460573 -0.859535 0.0327983 0.510024 -0.739196 -0.0421995 0.672167 -0.739693 -0.0428004 0.671582 -0.487723 0.0869127 0.868662 -0.601117 -0.166353 0.781655 -0.368484 0.0496748 0.928306 -0.164248 -0.0490355 0.985199 -0.102736 0 0.994709 -0.166903 0 -0.985973 -0.106217 0.0798782 -0.991129 -0.411998 -0.0757405 -0.908031 -0.365993 -0.0123525 -0.930536 -0.562008 0.00482576 -0.827118 -0.651757 -0.0464773 -0.757003 -0.985476 0 -0.169817 -0.991216 -0.0588325 -0.118448 -0.910042 0.0497798 -0.411516 -0.930202 6.31685e-05 -0.367049 -0.823383 -2.94502e-05 -0.567486 -0.853573 -0.0310311 -0.520049 -0.743938 0.0423368 -0.666906 0.714509 0.673423 -0.189678 0.987312 0.157462 -0.0205194 0.989917 0.141537 -0.00554016 0.913244 0.395558 -0.097565 0.898096 0.423388 -0.119023 0.83839 0.527054 -0.138986 0.707026 0.679251 -0.196804 0.158157 0.941244 -0.298407 0.156431 0.941273 -0.299225 0.459502 0.850158 -0.25708 0.406685 0.866231 -0.29026 0.544565 0.803508 -0.240466 0.158517 0.937935 -0.308464 0.158874 0.937916 -0.308338 0.471897 0.854858 -0.215711 0.456904 0.861004 -0.223407 0.731081 0.675149 -0.0984572 0.708014 0.696567 -0.116236 0.906925 0.420235 0.0298341 0.886788 0.462172 0.00184924 0.980688 0.119474 0.154845 0.976088 0.182075 0.118749 0.15882 0.934676 -0.318051 0.161076 0.934882 -0.316308 0.463719 0.868781 -0.173738 0.459723 0.870067 -0.177869 0.713705 0.700391 -0.00881808 0.706667 0.707271 -0.0197273 0.87926 0.449606 0.157341 0.874202 0.464895 0.140157 0.940972 0.146143 0.305308 0.943683 0.17023 0.283699 0.150112 0.932816 -0.327598 0.159826 0.933721 -0.320346 0.452068 0.883264 -0.124413 0.444988 0.885827 -0.131514 0.69229 0.715327 0.0950854 0.676775 0.732648 0.0721329 0.83904 0.45296 0.301395 0.828124 0.493403 0.266016 0.873983 0.131773 0.467749 0.882332 0.196867 0.427473 0.801596 0.17987 0.570166 0.793053 0.164897 0.586409 0.771945 0.498542 0.394406 0.770325 0.489821 0.408258 0.639744 0.750551 0.165533 0.641082 0.747446 0.174181 0.42245 0.902313 -0.0858324 0.423186 0.902162 -0.0837695 0.148899 0.933559 -0.326033 0.130545 0.934188 -0.33204 0.145342 0.933249 -0.328515 0.14678 0.932454 -0.330129 0.581359 0.195114 0.789907 0.57119 0.183216 0.800108 0.582432 0.541258 0.606475 0.578056 0.534673 0.616423 0.4946 0.80418 0.329644 0.493591 0.802192 0.335942 0.331185 0.943564 0.0018881 0.331191 0.94356 0.00265757 0.449776 0.220693 0.865446 0.436755 0.180712 0.881242 0.455215 0.57041 0.683675 0.45203 0.547941 0.703867 0.390213 0.831798 0.394773 0.391392 0.824375 0.408924 0.263946 0.963607 0.0423559 0.264252 0.963462 0.0437219 0.290964 0.209029 0.93362 0.284489 0.199993 0.937587 0.300887 0.579808 0.757159 0.297403 0.57487 0.762284 0.260388 0.852731 0.452822 0.259067 0.851262 0.456331 0.176141 0.981745 0.071765 0.176097 0.98174 0.0719494 0.0777169 0.992486 0.0945073 0.077733 0.992504 0.0943099 0.113719 0.863859 0.49073 0.114297 0.865986 0.486832 0.129735 0.586184 0.799723 0.131332 0.592882 0.794508 0.123203 0.207679 0.970407 0.126272 0.219804 0.967337 0.703887 0.210625 0.678366 0.687909 0.153195 0.709445 0.686108 0.531666 0.496574 0.687569 0.498007 0.528429 0.574843 0.780476 0.245789 0.582049 0.768071 0.266994 0.384145 0.92239 -0.0403627 0.386353 0.921634 -0.0363575 0.128017 0.933851 -0.333967 0.117034 0.937949 -0.326427 0.116508 0.936359 -0.331147 0.0954545 0.943086 -0.318556 0.0913854 0.939255 -0.330829 0.062193 0.9448 -0.321692 0.0628028 0.9436 -0.325076 0.0275752 0.948068 -0.316869 0.0277788 0.946728 -0.320833 -2.60329e-05 0.94708 -0.320998 -2.63282e-05 0.947094 -0.320957 -2.7463e-05 0.995499 0.0947688 -2.76363e-05 0.995497 0.094794 -2.39883e-05 0.869507 0.493921 -2.40884e-05 0.869499 0.493934 -1.63017e-05 0.591192 0.806531 -1.63996e-05 0.59118 0.806539 -5.77735e-06 0.209279 0.977856 -5.81688e-06 0.209273 0.977857 -0.00870848 0.944328 -0.328891 -0.00881586 0.947042 -0.320988 -0.00919683 0.996052 0.088296 -0.00925552 0.995457 0.0947656 -0.00805372 0.871773 0.489843 -0.00807877 0.869476 0.493909 -0.00548256 0.593409 0.804882 -0.00548948 0.591179 0.806522 -0.00193912 0.210187 0.977659 -0.00194 0.209276 0.977855 0.258775 0.952293 -0.161784 0.980778 0.192369 -0.032681 0.965924 0.253854 -0.0504854 0.258766 0.952295 -0.161785 0.608702 0.782191 -0.132886 0.707093 0.69545 -0.12794 0.793289 0.600245 -0.101974 0.896852 0.436082 -0.0740851 0.837605 0.533984 -0.115235 0.706516 0.686586 -0.171567 0.913273 0.395197 -0.0987538 0.965884 0.252513 -0.0574991 0.987646 0.152028 -0.0379876 0.706375 0.687578 -0.168138 0.543918 0.814104 -0.203438 0.258422 0.937213 -0.234202 0.405813 0.889807 -0.20871 0.550548 0.814779 -0.181747 0.156381 0.94953 -0.271913 -0.424289 0.86693 -0.261555 -0.841121 0.533354 -0.0897186 -0.077583 0.208291 0.974985 -0.0880126 0.590181 0.802459 -0.0831057 0.868471 0.488724 -0.0636495 0.994067 0.0882047 -0.0329301 0.943806 -0.328856 -0.0756327 0.214868 0.97371 -0.222102 0.200433 0.9542 -0.218622 0.216004 0.951602 -0.405755 0.180925 0.895896 -0.404835 0.224315 0.886449 -0.529673 0.186134 0.827527 -0.557102 0.144742 0.817733 -0.0331988 0.944015 -0.328229 -0.0641851 0.940975 -0.332334 -0.0660224 0.941901 -0.329338 -0.10064 0.935515 -0.338649 -0.107063 0.938045 -0.329559 -0.130728 0.930467 -0.34226 -0.137602 0.931513 -0.336674 -0.589975 0.198295 0.782693 -0.712076 0.144516 0.687068 -0.714462 0.21278 0.666535 -0.822589 0.150444 0.548375 -0.819437 0.185654 0.542269 -0.870201 0.149627 0.469428 -0.879281 -0.0142165 0.476092 -0.921396 0.180337 0.344251 -0.962315 0.134295 0.236461 -0.95792 0.171344 0.230285 -0.990932 0.110222 0.0768491 -0.981938 0.180023 0.0582226 -0.0864098 0.594135 0.79971 -0.239072 0.579069 0.779438 -0.235562 0.588102 0.773723 -0.426929 0.550243 0.71761 -0.420959 0.575419 0.701204 -0.585216 0.525253 0.617763 -0.577748 0.545902 0.606793 -0.714415 0.485463 0.503921 -0.702389 0.526641 0.478851 -0.800425 0.471322 0.370373 -0.790931 0.493241 0.362135 -0.866381 0.434556 0.246059 -0.84696 0.483336 0.22146 -0.897295 0.43096 0.0955746 -0.885729 0.455454 0.089698 -0.914205 0.403472 -0.0379452 -0.912672 0.406835 -0.0389217 -0.0820222 0.869982 0.486213 -0.214661 0.85691 0.468642 -0.212116 0.860157 0.463829 -0.376271 0.827117 0.41749 -0.370179 0.836235 0.404571 -0.506267 0.795141 0.333835 -0.499329 0.802988 0.325392 -0.609505 0.754247 0.244162 -0.595614 0.770751 0.226246 -0.670227 0.728491 0.141763 -0.66097 0.738034 0.135738 -0.717835 0.694375 0.0505524 -0.696408 0.716833 0.0341478 -0.73157 0.679419 -0.0565319 -0.719638 0.691725 -0.0603127 -0.740511 0.655223 -0.149419 -0.714974 0.681163 -0.157572 -0.0631905 0.994198 0.0870521 -0.15285 0.985385 0.0751847 -0.152213 0.985573 0.0740032 -0.261297 0.96424 0.0443367 -0.25985 0.964744 0.041807 -0.346394 0.93808 -0.00422857 -0.344822 0.93865 -0.00582822 -0.411609 0.90975 -0.0541662 -0.407445 0.911373 -0.0582029 -0.449232 0.887039 -0.106549 -0.446015 0.888465 -0.108168 -0.476286 0.865967 -0.152491 -0.466576 0.8703 -0.157748 -0.483512 0.851557 -0.202651 -0.477015 0.854909 -0.203929 -0.48717 0.838074 -0.245554 -0.558385 0.796513 -0.23189 -0.149753 0.926422 -0.345421 -0.14955 0.926334 -0.345746 -0.166582 0.925567 -0.339966 -0.167195 0.925193 -0.340681 -0.173699 0.924859 -0.338325 -0.172361 0.925819 -0.33638 -0.183158 0.92522 -0.332296 -0.180875 0.927845 -0.326171 -0.183616 0.927391 -0.325931 -0.181063 0.931443 -0.315642 -0.179873 0.93165 -0.315712 0.500718 0.218275 0.837638 0.768888 0.215986 0.601798 0.934981 0.209601 0.286143 0.978193 0.182008 0.100059 0.258689 0.9593 -0.11324 0.218683 0.953362 -0.208036 0.602624 0.79768 0.0234706 0.56339 0.824729 -0.0491288 0.79038 0.612599 -0.00476111 0.831835 0.551854 0.0592222 0.891692 0.450791 0.0409031 0.975673 0.207074 0.0719888 0.87586 0.193514 0.442065 0.90417 0.264159 0.335703 0.790035 0.553616 0.263352 0.783109 0.574232 0.238742 0.53639 0.836415 0.112677 0.528221 0.843848 0.0943586 0.18934 0.98022 -0.0576047 0.186117 0.980348 -0.0654123 0.658004 0.20329 0.725054 0.738892 0.25788 0.622525 0.643702 0.569574 0.51111 0.644776 0.586183 0.490564 0.43923 0.852427 0.283631 0.437806 0.858486 0.267072 0.154904 0.987918 0.00468006 0.154552 0.98798 -0.00306526 0.352749 0.209761 0.911904 0.485171 0.239505 0.840979 0.420466 0.582633 0.69552 0.425316 0.59364 0.683153 0.287797 0.86469 0.411684 0.290452 0.868795 0.401041 0.101283 0.993548 0.0510393 0.102895 0.993638 0.045779 0.165339 0.209088 0.963818 0.169453 0.215601 0.961666 0.146011 0.591491 0.792981 0.148933 0.595458 0.789461 0.100052 0.871917 0.479322 0.102117 0.873432 0.476119 0.0351265 0.996546 0.0752527 0.0363245 0.996624 0.0736318 -0.843757 0.51558 -0.14917 -0.988087 0.147835 -0.0427754 -0.716054 0.672161 -0.188327 -0.717029 0.671156 -0.188202 -0.558363 0.796902 -0.230603 -0.281775 0.928267 -0.242742 -0.424169 0.869912 -0.251663 -0.314725 0.913642 -0.257308 -0.179821 0.942189 -0.282746 -0.981521 0.18769 -0.0372645 -0.967119 0.248619 -0.0535685 -0.967154 0.246479 -0.0621362 -0.916301 0.384703 -0.111334 -0.283874 0.940464 -0.18693 -0.281466 0.941202 -0.18686 -0.622939 0.767275 -0.152437 -0.716854 0.682784 -0.141162 -0.801067 0.587113 -0.116573 -0.900774 0.425968 -0.0846016 0.000455529 0.997159 0.0753223 0.000475342 0.997161 0.075299 0.00041567 0.876315 0.481738 0.000416818 0.876316 0.481737 0.000283222 0.597914 0.80156 0.000285159 0.597916 0.801559 0.000101112 0.212009 0.977268 0.000101088 0.212009 0.977268 0.000198219 0.997161 0.075299 0.000178394 0.997159 0.0753223 0.000156775 0.876315 0.481738 0.000156756 0.876315 0.481738 0.000106953 0.597903 0.801569 0.000118816 0.597914 0.80156 4.21311e-05 0.212014 0.977267 3.79082e-05 0.212009 0.977268 -0.0550456 0.9962 0.0674978 -0.113744 0.594508 0.796004 -0.114266 0.208237 0.971381 -0.105442 0.217014 0.970457 -0.381869 0.197202 0.902933 -0.366544 0.222798 0.903331 -0.6147 0.194941 0.764292 -0.662348 0.266546 0.700178 -0.735108 0.210189 0.644544 -0.106742 0.599757 0.793031 -0.34923 0.579705 0.736194 -0.334771 0.595368 0.730387 -0.599118 0.562601 0.569682 -0.577279 0.586275 0.568358 -0.771925 0.543685 0.329453 -0.747531 0.572878 0.336166 -0.851212 0.18236 0.492121 -0.866191 0.246038 0.434946 -0.919829 0.201495 0.336621 -0.0528578 0.996385 0.0665002 -0.112844 0.992147 0.0539429 -0.10721 0.992899 0.0515462 -0.173167 0.984825 0.0115065 -0.164243 0.986361 0.0108208 -0.21324 0.975753 -0.0493429 -0.203724 0.977903 -0.0469254 -0.229261 0.966099 -0.118712 -0.28406 0.946318 -0.154246 -0.576919 0.8168 -0.00161807 -0.518364 0.840529 0.15751 -0.53957 0.827778 0.153782 -0.406382 0.856852 0.317268 -0.424833 0.846763 0.320171 -0.243359 0.869217 0.430394 -0.254983 0.862827 0.436478 -0.0880055 0.876606 0.473094 -0.0930956 0.874583 0.475855 -0.965371 0.214236 0.148869 -0.978056 0.164395 0.127987 -0.889991 0.447883 0.0855418 -0.84049 0.534517 0.0887012 -0.794706 0.606121 0.0325376 -0.619475 0.78488 -0.0146572 0.162993 0.209079 0.96422 0.608412 0.792812 -0.0358353 0.978099 0.201887 0.0506405 0.790573 0.590724 -0.16137 0.442728 0.894798 -0.0576853 0.196433 0.975224 -0.101746 0.893254 0.447878 0.0387637 0.975945 0.18558 0.114416 0.901867 0.215847 0.374226 0.955683 0.118033 0.269699 0.895063 0.187835 0.404452 0.795786 0.209911 0.568034 0.727403 0.181458 0.661784 0.684635 0.199229 0.701129 0.526781 0.215471 0.822237 0.470598 0.191383 0.861342 0.372456 0.208403 0.904348 0.175422 0.215367 0.960648 0.835561 0.547837 0.0413834 0.788413 0.569912 0.23153 0.786644 0.553973 0.272591 0.653908 0.582295 0.483049 0.640898 0.568971 0.515288 0.434658 0.591639 0.678996 0.419296 0.582253 0.696543 0.153158 0.595108 0.788916 0.146052 0.591447 0.793007 0.574361 0.812926 -0.0962321 0.530556 0.841495 0.101964 0.535551 0.835632 0.122081 0.441715 0.855543 0.270064 0.440029 0.850968 0.286752 0.294587 0.866967 0.401977 0.289943 0.863877 0.411886 0.104225 0.872965 0.476518 0.101568 0.87177 0.479272 0.199454 0.975072 -0.0972284 0.188576 0.980745 -0.0507796 0.19082 0.980521 -0.0465422 0.157519 0.987499 0.0058116 0.157901 0.987418 0.00854634 0.105213 0.993181 0.0502251 0.104962 0.993146 0.0514289 0.0374466 0.996485 0.0749302 0.0372539 0.996469 0.0752485 -0.0327651 0.997188 0.0673926 -0.032869 0.997177 0.0675147 -0.0288637 0.87856 0.47676 -0.0289445 0.878511 0.476845 -0.0197211 0.600315 0.799521 -0.0197753 0.600261 0.79956 -0.00699496 0.213005 0.977026 -0.00701134 0.212985 0.97703 -0.0330425 0.997189 0.0672467 -0.0331668 0.997175 0.0673926 -0.0291264 0.878598 0.476674 -0.0292083 0.878548 0.47676 -0.019902 0.600361 0.799481 -0.0199558 0.600307 0.799521 -0.00705904 0.213022 0.977022 -0.00707553 0.213002 0.977026 0.793533 0.606317 0.0518231 0.896942 0.440541 0.0376545 0.259912 0.962124 0.0822356 0.965941 0.258758 0.00137882 0.965975 0.257966 0.0186047 0.980794 0.194339 0.0166105 0.70739 0.706814 0.00376645 0.980789 0.194481 -0.015141 0.96597 0.258102 -0.0169235 0.965944 0.258749 0.00137939 0.707401 0.706803 0.00376737 0.707514 0.704506 0.0556335 0.609178 0.790152 0.0675392 0.896916 0.440867 -0.0343243 0.793484 0.606755 -0.0472388 0.707457 0.704938 -0.0506646 0.609145 0.790666 -0.0615591 0.442961 0.893836 -0.0695903 0.259965 0.96211 0.0822382 0.259943 0.96561 0.0051453 0.259963 0.965605 0.00514664 0.259985 0.962938 -0.0718188 0.196288 0.977588 -0.076114 -0.462106 0.885827 -0.0420504 -0.794077 0.604801 0.06048 -0.123302 0.593689 0.795192 -0.0982318 0.874194 0.475537 -0.0577413 0.996066 0.0672264 -0.875022 0.199016 0.441281 -0.856294 0.181125 0.483689 -0.769768 0.202632 0.605308 -0.644982 0.192385 0.739585 -0.649882 0.188971 0.736168 -0.362773 0.222661 0.904886 -0.401143 0.195086 0.895 -0.101687 0.217336 0.970786 -0.127009 0.207479 0.969959 -0.938014 0.192845 0.287995 -0.98015 0.163808 0.111681 -0.964574 0.209983 0.159701 -0.10707 0.599687 0.793039 -0.363406 0.577375 0.731146 -0.336649 0.594098 0.730558 -0.610905 0.558914 0.560723 -0.578269 0.583313 0.570395 -0.777276 0.540406 0.322186 -0.747454 0.569024 0.342817 -0.849759 0.524801 0.0499281 -0.9009 0.432736 -0.0334455 -0.0906286 0.876464 0.472861 -0.262119 0.861679 0.434516 -0.248502 0.86788 0.430152 -0.42976 0.844786 0.318814 -0.41098 0.854109 0.318736 -0.540658 0.826278 0.157967 -0.52085 0.837689 0.164292 -0.587026 0.809219 -0.023776 -0.623295 0.780311 -0.0511669 -0.0559474 0.996237 0.0661979 -0.115871 0.991824 0.0534655 -0.11306 0.992231 0.051913 -0.174674 0.984524 0.014226 -0.17057 0.985254 0.0134468 -0.213379 0.976173 -0.0394337 -0.208067 0.977347 -0.0387339 -0.229556 0.968198 -0.0994811 -0.223505 0.96991 -0.0965423 0.786022 0.614938 -0.063402 0.0979558 0.596296 -0.796766 0.066586 0.875674 -0.47829 0.0239922 0.997153 -0.0714914 0.870451 0.201113 -0.449298 0.856146 0.186915 -0.481744 0.762074 0.206332 -0.613735 0.646043 0.192912 -0.738521 0.640686 0.196276 -0.742292 0.364326 0.21897 -0.905162 0.389681 0.202573 -0.898395 0.103522 0.214096 -0.971312 0.111915 0.21114 -0.971028 0.935402 0.197391 -0.293361 0.978835 0.170538 -0.113135 0.963826 0.213063 -0.160134 0.0927674 0.598029 -0.796088 0.341267 0.585101 -0.735658 0.324155 0.594782 -0.735635 0.593706 0.569841 -0.568149 0.567583 0.587749 -0.576542 0.765904 0.552572 -0.328718 0.739383 0.576443 -0.347888 0.842162 0.536626 -0.0528765 0.896979 0.44024 0.0402076 0.0644867 0.876232 -0.477555 0.232514 0.867627 -0.4395 0.22438 0.870976 -0.437098 0.404032 0.854548 -0.326352 0.389745 0.861047 -0.326645 0.519973 0.838105 -0.164947 0.502817 0.84734 -0.170851 0.569775 0.821562 0.0198109 0.608761 0.791751 0.0503981 0.0238082 0.997165 -0.071385 0.0827347 0.994844 -0.0586493 0.0818776 0.994942 -0.0581913 0.143344 0.989462 -0.0204436 0.141057 0.989798 -0.0200471 0.184369 0.982285 0.0335402 0.180126 0.983093 0.0329128 0.174615 0.984479 0.0176268 0.259885 0.962356 0.0795728 -0.801436 0.595962 -0.050298 -0.900958 0.432368 -0.0365033 -0.223387 0.971272 -0.0820325 -0.967371 0.253362 0.000835285 -0.967396 0.252611 -0.0182598 -0.981553 0.190511 -0.0160817 -0.719089 0.694914 0.00229259 -0.286749 0.954672 0.0798537 -0.286688 0.958019 0.00316036 -0.286738 0.958004 0.00315695 -0.286755 0.954861 -0.0775316 -0.462952 0.883243 -0.0745492 -0.981553 0.190422 0.017149 -0.967391 0.252528 0.0196012 -0.967364 0.25339 0.000837217 -0.719105 0.694898 0.00229104 -0.719165 0.692708 -0.0543893 -0.623682 0.778906 -0.0657708 -0.285419 0.950658 0.121593 -0.360338 0.929064 0.0836425 -0.623634 0.778564 0.0701378 -0.719165 0.692401 0.0581695 -0.801412 0.595703 0.0536369 -0.90095 0.432174 0.0389255 0.000178446 0.997441 -0.0714879 0.00019827 0.99744 -0.0715111 0.000174452 0.87762 -0.479356 0.000156991 0.87763 -0.479338 0.00010719 0.599228 -0.800579 0.000119075 0.599216 -0.800587 4.22357e-05 0.21254 -0.977152 4.22258e-05 0.21254 -0.977152 0.000475503 0.99744 -0.0715109 0.000455845 0.997441 -0.0714879 0.000400055 0.877631 -0.479337 0.000418639 0.87762 -0.479356 0.000285836 0.599216 -0.800587 0.000273877 0.599227 -0.800579 9.71416e-05 0.21254 -0.977152 9.71189e-05 0.21254 -0.977152 -0.162434 0.205822 -0.965014 -0.979322 0.197921 -0.0419094 -0.798519 0.578251 0.167312 -0.623008 0.780736 0.0480896 -0.283844 0.9586 0.0227691 -0.897573 0.439828 -0.0302311 -0.977006 0.180664 -0.113227 -0.903513 0.21595 -0.370175 -0.958023 0.107375 -0.265823 -0.900637 0.180676 -0.395234 -0.728485 0.221495 -0.648266 -0.801546 0.138599 -0.581648 -0.696223 0.193431 -0.691273 -0.543052 0.216394 -0.811337 -0.469742 0.18848 -0.862449 -0.389511 0.205678 -0.897763 -0.194499 0.220293 -0.955846 -0.842998 0.536821 -0.034308 -0.799041 0.561693 -0.214557 -0.797055 0.543078 -0.264141 -0.671615 0.577196 -0.464519 -0.654121 0.56057 -0.507825 -0.4596 0.590883 -0.663042 -0.434999 0.57741 -0.690922 -0.181395 0.599535 -0.779522 -0.162374 0.590839 -0.790281 -0.590984 0.799792 0.105219 -0.549662 0.831085 -0.0846756 -0.555841 0.824095 -0.109124 -0.466196 0.848277 -0.251173 -0.463872 0.842437 -0.274086 -0.324837 0.86407 -0.384532 -0.316969 0.859455 -0.401083 -0.137286 0.87522 -0.463834 -0.129501 0.872174 -0.471743 -0.226794 0.96767 0.110356 -0.216606 0.974009 0.0662384 -0.219609 0.973698 0.0606895 -0.187804 0.98215 0.0105219 -0.188501 0.982056 0.00572494 -0.138018 0.989837 -0.0342582 -0.137262 0.98981 -0.0378979 -0.0715351 0.995582 -0.0608209 -0.0700907 0.995537 -0.0631891 0.104384 0.214092 -0.97122 0.107259 0.211309 -0.971516 0.092046 0.598237 -0.796015 0.0943927 0.596538 -0.797015 0.0628571 0.876458 -0.477358 0.0646405 0.875794 -0.478337 0.0219896 0.997232 -0.0710276 0.022988 0.997176 -0.0714922 0.367145 0.219503 -0.903893 0.377173 0.203647 -0.903476 0.322919 0.596194 -0.735035 0.332404 0.586456 -0.738632 0.220731 0.8723 -0.436314 0.228465 0.868335 -0.440226 0.0774 0.995396 -0.0565405 0.0815364 0.994967 -0.0582512 0.142858 0.989605 -0.0165213 0.135506 0.990647 -0.0160378 0.400855 0.856146 -0.326082 0.386036 0.863738 -0.323934 0.584682 0.572693 -0.574605 0.567132 0.590833 -0.573828 0.666153 0.192815 -0.72046 0.875942 0.295148 -0.381593 0.814513 0.197026 -0.545664 0.650215 0.222122 -0.726555 0.201777 0.97272 0.114463 0.194923 0.97464 0.109916 0.441031 0.895292 0.0627991 0.559339 0.828934 -0.00298289 0.885862 0.455623 -0.0875051 0.832883 0.545815 -0.0916119 0.786666 0.616345 -0.0357065 0.605036 0.796116 0.0114402 0.184522 0.981826 0.0443678 0.176144 0.983462 0.04214 0.519416 0.839494 -0.159551 0.500674 0.850145 -0.163034 0.761399 0.555435 -0.33431 0.739758 0.580339 -0.340537 0.868916 0.21897 -0.443889 0.976837 0.170848 -0.12884 0.964662 0.217247 -0.149102 -0.032913 0.997447 -0.0633772 -0.033037 0.997452 -0.0632327 -0.0290444 0.879921 -0.474232 -0.0291322 0.879966 -0.474143 -0.0198605 0.601683 -0.798488 -0.0199192 0.601735 -0.798448 -0.00704721 0.213564 -0.976904 -0.00706511 0.213583 -0.9769 -0.0326349 0.997447 -0.0635226 -0.0327597 0.997452 -0.0633772 -0.0288003 0.879873 -0.474335 -0.0289029 0.879926 -0.474232 -0.0197034 0.601647 -0.798519 -0.0197487 0.601687 -0.798488 -0.00698484 0.213543 -0.976909 -0.00700498 0.213565 -0.976904 0.896741 0.434474 0.0841876 0.987673 0.150543 0.0428822 0.706887 0.680266 0.193777 0.258818 0.935879 0.239046 0.308911 0.912616 0.267779 0.156226 0.953935 0.256127 0.980759 0.191659 0.0371282 0.965888 0.253387 0.0534298 0.965927 0.251273 0.0620296 0.913449 0.391384 0.111488 0.793143 0.597914 0.115857 0.706773 0.693422 0.140136 0.706877 0.680276 0.193778 0.406532 0.878683 0.250294 0.194948 0.962894 0.186627 0.258566 0.947535 0.18794 0.442018 0.88062 0.170671 0.608488 0.779066 0.150989 -0.91435 0.216673 -0.342078 -0.979442 0.176617 -0.0974677 -0.221824 0.965568 0.135914 -0.225396 0.965645 0.129329 -0.461522 0.881916 0.0960325 -0.572597 0.819523 0.0226835 -0.976762 0.203772 -0.066427 -0.89587 0.443028 -0.0337934 -0.839582 0.540884 -0.0504719 -0.798437 0.601898 0.0147114 -0.621391 0.78174 0.0524929 -0.845853 0.19895 -0.494927 -0.918659 0.205645 -0.337307 -0.800825 0.54226 -0.25423 -0.792752 0.566478 -0.225049 -0.556559 0.824742 -0.100213 -0.546901 0.833498 -0.0786158 -0.217775 0.973422 0.0708808 -0.213878 0.973574 0.0800609 -0.184181 0.982726 0.0180632 -0.18468 0.982762 0.0084834 -0.460985 0.851359 -0.250361 -0.462762 0.843887 -0.271489 -0.659407 0.581725 -0.476213 -0.657802 0.560738 -0.502861 -0.75062 0.220465 -0.622868 -0.406306 0.337253 -0.849221 -0.558694 0.21537 -0.800923 -0.738312 0.185022 -0.648585 -0.163611 0.590649 -0.790168 -0.170804 0.599858 -0.781662 -0.127316 0.872348 -0.472016 -0.13216 0.875622 -0.464565 -0.0666277 0.995756 -0.0634856 -0.0688633 0.995793 -0.0604565 -0.134421 0.990431 -0.0312706 -0.132271 0.990471 -0.0383674 -0.318162 0.866025 -0.385711 -0.314201 0.860352 -0.401338 -0.444868 0.593402 -0.670795 -0.437348 0.577429 -0.689422 -0.497257 0.193286 -0.845799 -0.179615 0.221068 -0.958576 -0.169182 0.205411 -0.963942 0.0801791 0.59164 -0.802206 0.0700235 0.869769 -0.488466 0.0475453 0.994998 -0.0878595 0.0166221 0.944088 0.329275 0.569323 0.174734 -0.80333 0.40271 0.223999 -0.887496 0.404313 0.183903 -0.895941 0.21846 0.215397 -0.951777 0.221785 0.202202 -0.9539 0.074891 0.214395 -0.973872 0.0763435 0.209619 -0.974798 0.650913 0.0103577 -0.759082 0.703013 0.151676 -0.694814 0.566074 0.20717 -0.797898 0.770364 0.183651 -0.610583 0.821296 0.153409 -0.549489 0.817812 0.187591 -0.544052 0.903958 0.124246 -0.409174 0.901233 0.198527 -0.385183 0.961717 0.137631 -0.236977 0.957202 0.173506 -0.231648 0.990548 0.11364 -0.0768216 0.981421 0.182522 -0.0591528 0.0790944 0.594268 -0.800369 0.232136 0.581696 -0.779578 0.229005 0.589122 -0.774915 0.418918 0.554886 -0.718756 0.413036 0.577733 -0.704007 0.577462 0.530914 -0.620216 0.570122 0.549911 -0.610376 0.707421 0.492439 -0.507011 0.695301 0.531648 -0.483639 0.794836 0.478226 -0.373544 0.785303 0.499465 -0.365832 0.861942 0.4423 -0.247842 0.842462 0.489687 -0.224643 0.893368 0.438669 -0.0972809 0.88185 0.462469 -0.0919977 0.910755 0.411249 0.0374059 0.909744 0.413425 0.0380161 0.0694141 0.87061 -0.487052 0.202187 0.85978 -0.468933 0.200163 0.862214 -0.46532 0.362755 0.832322 -0.419105 0.357278 0.840205 -0.407931 0.493205 0.801981 -0.33701 0.486746 0.809012 -0.329512 0.597222 0.762742 -0.248095 0.583824 0.778202 -0.231413 0.659467 0.737462 -0.145788 0.650312 0.746643 -0.140068 0.70807 0.704114 -0.0534838 0.686728 0.725931 -0.0377885 0.722321 0.689439 0.054095 0.710381 0.70146 0.0575644 0.730384 0.668161 0.141777 0.705237 0.693363 0.147944 0.0475147 0.995006 -0.0877812 0.136926 0.9877 -0.0755036 0.136797 0.987735 -0.075274 0.244298 0.968614 -0.0458746 0.243624 0.968839 -0.0447131 0.329551 0.944137 0.00118834 0.328468 0.944512 0.00226089 0.394977 0.91731 0.0503554 0.391321 0.918678 0.0538358 0.43341 0.895347 0.102513 0.430258 0.896689 0.104057 0.46087 0.874884 0.148916 0.450857 0.879181 0.154174 0.467982 0.860894 0.199638 0.461211 0.864259 0.200851 0.472374 0.846192 0.24662 0.406639 0.876006 0.259343 0.0172043 0.944567 0.327869 0.0475296 0.942065 0.332047 0.0497516 0.943194 0.328496 0.0829049 0.937681 0.337462 0.0898416 0.940519 0.327647 0.112444 0.933741 0.339829 0.119497 0.934902 0.334185 0.130776 0.930446 0.342299 0.143864 0.931991 0.332709 0.147545 0.929871 0.337001 0.153847 0.929658 0.334765 0.15218 0.930801 0.332342 0.161924 0.930432 0.328751 0.15955 0.933069 0.322376 0.161613 0.932766 0.322224 0.159126 0.936586 0.312228 0.156416 0.936998 0.312361 -0.282505 0.932056 0.226854 -0.981539 0.188043 0.0349586 -0.967197 0.248427 0.0530412 -0.900836 0.426843 0.0793679 -0.80115 0.588384 0.109372 -0.717508 0.683125 0.136101 -0.623066 0.768985 0.143009 -0.461983 0.87195 0.162096 -0.282599 0.941841 0.181861 -0.221835 0.95864 0.178321 -0.279733 0.917703 0.282083 -0.428994 0.871417 0.237901 -0.715687 0.67373 0.184064 -0.716914 0.672554 0.183589 -0.966937 0.245998 0.0672213 -0.967087 0.245459 0.0670216 -0.0143614 0.942422 0.334118 -0.014486 0.941315 0.337218 -0.015203 0.996349 -0.0840133 -0.0153166 0.99656 -0.081452 -0.0133317 0.873187 -0.487202 -0.0134238 0.874077 -0.485603 -0.00908247 0.59484 -0.803793 -0.00914345 0.595729 -0.803134 -0.00321355 0.210759 -0.977533 -0.003235 0.211122 -0.977454 -0.00516825 0.944206 0.329316 -0.00521019 0.94252 0.334109 -0.00545966 0.996109 -0.0879577 -0.00550137 0.99645 -0.0840108 -0.00478184 0.871899 -0.489662 -0.00481784 0.873282 -0.487192 -0.00325558 0.593547 -0.804792 -0.00328005 0.594912 -0.803784 -0.0011515 0.210232 -0.977651 -0.0011602 0.210786 -0.977532 0 0.944218 0.32932 0 0.944218 0.32932 0 0.996124 -0.087959 0 0.996124 -0.087959 0 0.871909 -0.489668 0 0.871909 -0.489668 0 0.593551 -0.804797 0 0.593551 -0.804797 0 0.210232 -0.977651 0 0.210232 -0.977651 -0.717824 0.684254 0.128554 -0.890873 0.454222 0.00532023 -0.966769 0.248795 0.0588131 -0.279624 0.921149 0.27073 -0.976556 0.180414 -0.117426 -0.980831 0.114382 -0.157757 -0.944193 0.168191 -0.283217 -0.940914 0.142165 -0.30736 -0.883065 0.196259 -0.426237 -0.872668 0.127237 -0.471446 -0.802254 0.177918 -0.569854 -0.792717 0.162636 -0.587494 -0.706162 0.211085 -0.675854 -0.687225 0.149685 -0.710856 -0.583755 0.194337 -0.78833 -0.572343 0.182157 -0.799526 -0.454381 0.222581 -0.862552 -0.438642 0.178553 -0.880745 -0.295016 0.210306 -0.932061 -0.287207 0.200005 -0.936755 -0.130609 0.223267 -0.965967 -0.126175 0.207411 -0.970083 -0.91168 0.4101 -0.0256552 -0.879396 0.457201 -0.132781 -0.884714 0.440702 -0.151861 -0.834211 0.487551 -0.257654 -0.845041 0.444628 -0.297006 -0.77958 0.492704 -0.386649 -0.777556 0.483821 -0.401653 -0.69533 0.528535 -0.486997 -0.69599 0.492311 -0.522712 -0.593178 0.538572 -0.598398 -0.588106 0.531816 -0.609347 -0.467737 0.570886 -0.674768 -0.463435 0.545771 -0.698113 -0.313206 0.581517 -0.750826 -0.308883 0.575772 -0.757019 -0.142948 0.597603 -0.788946 -0.140489 0.588382 -0.796285 -0.741639 0.661852 0.109195 -0.717652 0.695622 0.0329424 -0.725192 0.688227 0.0209739 -0.688641 0.722786 -0.0579146 -0.704937 0.704364 -0.0832793 -0.6535 0.741631 -0.151399 -0.654805 0.73849 -0.160821 -0.589765 0.774006 -0.230417 -0.597448 0.760463 -0.254462 -0.511395 0.799309 -0.315564 -0.510122 0.797281 -0.322674 -0.408148 0.829922 -0.380321 -0.409318 0.821315 -0.397366 -0.278258 0.853254 -0.441056 -0.276487 0.851444 -0.445644 -0.130937 0.869597 -0.476084 -0.129914 0.866273 -0.482384 -0.984934 0.161247 -0.0624883 -0.902313 0.413245 0.122716 -0.715642 0.674163 0.182648 -0.72256 0.668856 0.174754 -0.477071 0.831011 0.28605 -0.47348 0.847467 0.240037 -0.488535 0.841142 0.231978 -0.476652 0.857073 0.195523 -0.480873 0.855706 0.191126 -0.46225 0.874 0.14983 -0.469807 0.871267 0.142041 -0.440598 0.891605 0.104468 -0.441432 0.891472 0.102054 -0.40275 0.913376 0.0594761 -0.405676 0.912416 0.0540686 -0.350877 0.936277 0.0164459 -0.35087 0.936302 0.0151363 -0.284024 0.958514 -0.0240913 -0.284766 0.958203 -0.0274729 -0.195962 0.979036 -0.0555698 -0.195735 0.979027 -0.0565132 -0.0963041 0.992214 -0.078973 -0.0961126 0.992053 -0.0811973 -0.181117 0.930681 0.317852 -0.181916 0.9269 0.328273 -0.180307 0.927007 0.328859 -0.182935 0.92363 0.336812 -0.180193 0.923401 0.338911 -0.18106 0.922516 0.340854 -0.170712 0.921579 0.348639 -0.169157 0.922613 0.346657 -0.167023 0.921437 0.350796 -0.159408 0.925961 0.342323 -0.149675 0.922696 0.355289 -0.136233 0.928232 0.346158 -0.135764 0.926639 0.350583 -0.114192 0.934281 0.337756 -0.110328 0.930552 0.349143 -0.0802226 0.937078 0.339778 -0.0807376 0.935964 0.342713 -0.0446803 0.941383 0.334368 -0.0448111 0.940409 0.33708 -0.0820656 -0.743468 -0.663718 1.43005e-05 -0.754675 -0.656099 0.866026 -0.472759 0.162784 0.866025 -0.47276 0.162784 0.86495 -0.488396 0.115463 0.863931 -0.489358 0.118962 -0.863346 -0.447287 0.233598 -0.308743 -0.802225 -0.510992 -0.216942 -0.779247 -0.587972 -0.0884186 -0.75714 -0.647241 -0.0181937 -0.754585 -0.65595 -0.266753 -0.730966 -0.628117 -0.275128 -0.744764 -0.607973 -0.519834 -0.688458 -0.505765 -0.59765 -0.699901 -0.391093 -0.707112 -0.629899 -0.321278 -0.786324 -0.588919 -0.186732 -0.77673 -0.598411 -0.196455 -0.797928 -0.587882 -0.133062 -0.814409 -0.579448 -0.0312749 -0.788108 -0.612593 -0.0601373 -0.858668 -0.511091 0.0384076 -0.851375 -0.521802 0.0536872 -0.805044 -0.583229 0.10839 0 -0.754708 -0.65606 7.80128e-06 -0.754722 -0.656045 -3.42541e-06 -0.754716 -0.656052 4.98037e-06 -0.754684 -0.656088 6.45362e-05 -0.754657 -0.65612 -8.0989e-07 -0.754709 -0.65606 2.23402e-07 -0.75471 -0.656059 -1.13998e-06 -0.75471 -0.656059 9.01919e-07 -0.754713 -0.656055 8.73745e-06 -0.754703 -0.656067 1.69684e-06 -0.754707 -0.656062 -1.31102e-05 -0.754703 -0.656067 -5.10451e-08 -0.754712 -0.656056 -3.01168e-07 -0.754712 -0.656056 1.3281e-07 -0.754714 -0.656054 3.3349e-07 -0.754706 -0.656064 -5.82191e-06 -0.754748 -0.656015 -4.61863e-07 -0.754712 -0.656056 -4.35437e-07 -0.754711 -0.656058 1.76313e-05 -0.754699 -0.656071 -5.7516e-06 -0.754708 -0.656061 7.7784e-06 -0.754708 -0.656061 -4.59324e-07 -0.754712 -0.656056 -2.05162e-06 -0.75471 -0.656058 -1.01081e-06 -0.754709 -0.656059 4.8396e-07 -0.754709 -0.65606 6.68687e-07 -0.754712 -0.656057 -4.64931e-07 -0.754708 -0.656061 -5.23231e-07 -0.754711 -0.656057 8.85363e-07 -0.754707 -0.656062 3.94133e-07 -0.754708 -0.656061 4.50022e-07 -0.754704 -0.656065 -4.74695e-07 -0.754713 -0.656056 0.866022 -0.472764 0.162788 0.866025 -0.47276 0.162783 0.866026 -0.472757 0.162785 0.866025 -0.47276 0.162784 0.862942 -0.498523 0.0824941 0.830502 -0.556756 0.0169906 0.830991 -0.556274 -0.00354996 0.827485 -0.553445 -0.0946942 0.822627 -0.560182 -0.09737 0.788836 -0.58922 -0.174807 0.716431 -0.635713 -0.287396 0.714745 -0.634759 -0.293635 0.345946 -0.73136 -0.587736 0.356241 -0.730365 -0.582803 0.477503 -0.715978 -0.50928 0.40122 -0.770165 -0.495851 0.55602 -0.682335 -0.474615 0.550721 -0.668307 -0.500073 0.550998 -0.664926 -0.504256 0.313706 -0.735146 -0.600957 0.167972 -0.755842 -0.632842 0.146381 -0.746579 -0.648993 -0.863286 -0.445384 0.237425 -0.833815 -0.443857 0.328245 -0.833853 -0.437866 0.336098 -0.821881 -0.37734 0.426763 -0.70592 -0.357027 0.611726 -0.368579 -0.207367 0.906172 -0.393545 -0.222113 0.89207 -0.49251 -0.295174 0.818722 -0.473431 -0.264108 0.840304 -0.606979 -0.263712 0.749688 -0.712382 -0.332623 0.61796 -0.702266 -0.337905 0.626612 -0.762368 -0.34155 0.549671 -0.271551 -0.209844 0.939269 -0.166544 -0.219836 0.961215 -0.130769 -0.189171 0.973198 2.21401e-07 -0.190809 0.981627 -1.79179e-08 -0.190808 0.981627 7.05456e-07 -0.19081 0.981627 -3.59999e-07 -0.190808 0.981627 0 -0.19081 0.981627 4.84514e-07 -0.190812 0.981627 -1.3069e-06 -0.190808 0.981627 -4.21359e-07 -0.190809 0.981627 -1.8868e-06 -0.190808 0.981627 1.54601e-06 -0.19081 0.981627 -3.95229e-07 -0.190809 0.981627 1.521e-07 -0.190806 0.981628 5.66745e-07 -0.190795 0.98163 4.41751e-07 -0.190799 0.981629 1.34344e-07 -0.190809 0.981627 -1.78978e-07 -0.190808 0.981627 2.47398e-06 -0.190756 0.981638 -7.10598e-07 -0.190828 0.981624 -7.0924e-07 -0.190827 0.981624 -2.59234e-07 -0.190809 0.981627 -8.22343e-07 -0.190806 0.981628 1.10404e-06 -0.190792 0.98163 -2.78894e-06 -0.190861 0.981617 2.1295e-07 -0.190805 0.981628 1.36109e-07 -0.190809 0.981627 -1.16125e-07 -0.190808 0.981627 -1.59361e-06 -0.190813 0.981626 1.18134e-07 -0.190811 0.981627 -2.8958e-07 -0.190812 0.981627 -2.62941e-07 -0.19081 0.981627 -2.96297e-07 -0.19081 0.981627 7.65562e-07 -0.190803 0.981628 -1.11947e-06 -0.190822 0.981625 3.30341e-07 -0.190805 0.981628 2.54622e-07 -0.19081 0.981627 2.64251e-08 -0.190809 0.981627 0.542212 -0.260169 0.798948 0.127008 -0.189806 0.973572 0.0240087 -0.190758 0.981344 0.210561 -0.293982 0.93233 0.250905 -0.185304 0.95011 0.579453 -0.353247 0.734473 0.5846 -0.437768 0.683083 0.53068 -0.268321 0.803979 0.279023 -0.137975 0.95032 0.304028 -0.53807 0.78616 0.211945 -0.334867 0.91812 0.858918 -0.427254 0.282336 0.789449 -0.450213 0.417228 0.811718 -0.441698 0.382122 0.787188 -0.353067 0.505647 0.715479 -0.312494 0.62485 0.715775 -0.313821 0.623845 0.668495 -0.29324 0.683465 -0.866024 -0.47274 0.162849 -0.866026 -0.472758 0.162784 -0.866023 -0.472762 0.162789 -0.866026 -0.472759 0.162783 -0.866025 -0.47276 0.162783 -0.412671 -2.30009e-06 -0.91088 -0.610722 3.07119e-06 -0.791845 0.176764 0.0331204 0.983696 0.261202 -0.0329754 0.964721 0.421617 0.0119823 0.906695 0.460018 2.14679e-06 0.88791 0.567954 3.43485e-06 0.823061 0.602452 -0.0210919 0.797877 0.752884 0.0329733 0.657327 -0.561035 0.0501125 -0.826274 -0.738238 -0.0397764 -0.673367 -0.79504 0.0143519 -0.606387 -0.854402 1.28136e-06 -0.519612 -0.885495 1.14582e-06 -0.464648 -0.928817 -0.0252275 -0.36968 -0.962089 0.0393759 -0.269877 -0.993031 -0.0198127 -0.116177 -0.998613 1.12872e-06 -0.0526425 -0.998643 -1.11694e-06 0.0520873 -0.993122 0.019588 0.11543 -0.977758 -0.0160232 0.209123 -0.92942 0.0259692 0.368108 -0.913035 -8.03331e-06 0.407882 -0.854617 -1.12055e-06 0.519258 -0.831382 -0.00574226 0.555672 -0.740868 0.0321199 0.670882 -0.678495 -0.0326418 0.73388 -0.560297 0.00723624 0.82826 -0.52378 7.15226e-07 0.851854 -0.413032 -7.10743e-07 0.910716 -0.372239 -0.0256516 0.927782 -0.159349 0.0330584 0.986669 -0.120744 0.0037383 0.992677 0.0476308 -0.00127479 0.998864 -0.467587 -0.0375731 -0.883148 -0.281536 0.040467 -0.958697 -0.156032 -0.0407541 -0.986911 -0.0577869 -0.00204413 -0.998327 0.178172 0.00561026 -0.983983 0.111623 -0.0672339 -0.991474 0.42092 0.0587593 -0.905193 0.363949 1.78283e-06 -0.931419 0.568256 1.57502e-06 -0.822852 0.788521 -0.00981725 0.61493 0.880638 0.003348 0.473778 0.928022 0.0328605 0.371074 0.95626 -0.0327943 0.290673 0.994265 0.0164681 0.105668 0.998007 0 0.0631059 0.985806 0 -0.167891 0.99237 0.0646152 -0.105009 0.907087 -0.0598971 -0.416659 0.928666 -0.0118421 -0.370727 0.825799 0.00480294 -0.563944 0.753037 -0.0407404 -0.656716 0.664281 0.040953 -0.74636 0.515046 -0.0313589 -0.856589 -0.412754 3.33487e-06 -0.910842 0.178174 0.0333499 0.983434 0.261047 -0.03327 0.964753 0.42194 0.0118756 0.906546 0.46092 5.56912e-07 0.887442 0.567829 5.16564e-07 0.823147 0.602408 -0.0211758 0.797907 0.753513 0.032779 0.656616 -0.610595 2.9054e-06 -0.791943 -0.558958 0.0511671 -0.827616 -0.792611 -0.0730313 -0.605338 -0.740012 0.026299 -0.67208 -0.854549 2.88274e-07 -0.51937 -0.885339 2.58066e-07 -0.464946 -0.929228 -0.0259582 -0.368595 -0.961704 0.0404492 -0.271088 -0.993106 -0.0202866 -0.115448 -0.998593 4.29238e-08 -0.053028 -0.998598 -4.39091e-08 0.0529331 -0.993124 0.020243 0.115301 -0.977435 -0.0166588 0.210579 -0.929292 0.0272698 0.368337 -0.912696 0 0.40864 -0.854579 0 0.519321 -0.831138 -0.00600228 0.556034 -0.739883 0.033346 0.671909 -0.678729 -0.0333216 0.733633 -0.55982 0.00727695 0.828582 -0.523387 2.71833e-07 0.852095 -0.412827 2.90564e-07 0.910809 -0.373089 -0.0261441 0.927427 -0.157536 0.0334212 0.986947 -0.119994 0.00370677 0.992768 0.0483428 -0.00129199 0.99883 -0.468974 -0.0378035 -0.882403 -0.279438 0.0409243 -0.959291 -0.158882 -0.0406438 -0.986461 -0.0576863 -0.00187903 -0.998333 0.177549 0.0051867 -0.984098 0.108847 -0.0652485 -0.991915 0.423284 0.0571742 -0.904191 0.788902 -0.00945507 0.614446 0.880988 0.00329052 0.473127 0.928325 0.0322012 0.370372 0.956414 -0.0318124 0.290277 0.994299 0.0159158 0.105433 0.998028 0 0.0627664 0.985838 0 -0.167699 0.992558 0.0619723 -0.10482 0.906771 -0.0577581 -0.417649 0.928373 -0.0118031 -0.371462 0.82611 0.00473848 -0.563489 0.751454 -0.0396549 -0.658593 0.666136 0.0397284 -0.744772 0.567528 -0.00680255 -0.823326 0.515611 -7.38753e-07 -0.856823 0.364344 -2.77025e-06 -0.931265 2.41434e-05 -0.945525 0.325549 6.2351e-06 -0.945523 0.325555 -6.60574e-06 -0.945515 0.325579 0 -0.945515 0.325579 0 -0.945515 0.325579 2.34296e-06 -0.945515 0.325579 6.18809e-08 -0.945519 0.325567 0 -0.945519 0.325567 0 -0.945519 0.325568 0 -0.945519 0.325568 0 -0.945519 0.325567 6.18518e-06 -0.945518 0.32557 7.35091e-07 -0.945517 0.325571 -2.54554e-06 -0.945519 0.325566 5.08079e-06 -0.945518 0.32557 2.34032e-06 -0.945515 0.325579 -1.58607e-06 -0.945519 0.325568 -6.69097e-07 -0.945519 0.325568 -5.10521e-07 -0.945519 0.325568 0 -0.945519 0.325568 0 -0.945519 0.325568 0 -0.945519 0.325568 0 -0.945519 0.325567 4.61801e-06 -0.945518 0.32557 2.26565e-06 -0.945517 0.325574 -4.34636e-06 -0.94552 0.325564 1.34314e-06 -0.945521 0.325561 2.1477e-06 -0.945515 0.325578 0 -0.945515 0.325578 0 -0.945515 0.325578 -6.24248e-06 -0.945515 0.325578 -1.81131e-06 -0.945518 0.32557 3.90917e-06 -0.945519 0.325568 5.39264e-06 -0.945519 0.325567 -1.15804e-07 -0.945519 0.325568 -0.00317612 -0.943252 0.332063 0.0286737 -0.955182 0.294626 -0.0152394 -0.804043 0.594376 0.0496481 -0.727903 0.683881 0.0124638 -0.634334 0.772958 0.0166935 -0.495393 0.868509 0.0621076 -0.389233 0.919043 0.0217842 -0.305208 0.952037 -0.229426 -0.89959 0.37162 0.48492 -0.639726 0.596325 -0.110548 -0.764068 0.635594 0.00102781 -0.631473 0.775398 -0.0140159 -0.389309 0.921001 -0.00291668 -0.377006 0.926206 -1.89736e-05 -0.192727 0.981252 -0.00812447 -0.943218 0.332076 -0.00812438 -0.943218 0.332076 -0.00551397 -0.728507 0.685016 -0.00550258 -0.728491 0.685033 -0.00194807 -0.38945 0.921045 -0.00194852 -0.389451 0.921045 -0.987325 -0.0302839 0.155796 -0.987055 -0.0302456 0.157507 -0.757995 -0.124662 0.640236 -0.88771 -0.0874397 0.452023 -0.87288 -0.0861575 0.480269 -0.936845 -0.0668212 0.343303 -0.397641 -0.164292 0.902712 -0.674136 -0.169507 0.718894 -0.521039 -0.108914 0.846556 -0.64322 -0.129709 0.754615 -0.00218577 -0.190809 0.981625 -0.00196114 -0.19081 0.981625 -0.194232 -0.187177 0.962933 -0.194355 -0.187148 0.962913 -0.467503 -0.168686 0.867748 -0.00866884 -0.86812 0.496279 -0.00982714 -0.986289 0.164735 -2.88075e-05 -0.193115 0.981176 -0.00404869 -0.379134 0.925333 -0.00499863 -0.628496 0.777797 -0.01248 -0.729593 0.683768 -0.00535394 -0.816283 0.577627 -0.00487503 -0.949395 0.314047 -0.00605677 -0.944188 0.329351 -0.014492 -0.94409 0.329368 -0.0109375 -0.960112 0.279401 -0.00277274 -0.389972 0.920822 -0.00221328 -0.389979 0.920821 0.0220235 -0.214699 0.976432 -0.000417124 -0.379207 0.925312 -0.00409209 -0.556947 0.830538 -0.00653778 -0.729672 0.683766 0.00706159 -0.647125 0.762351 -0.0050985 -0.769992 0.638034 0.00234968 -0.190809 0.981624 0.476363 -0.169236 0.862808 0.986996 -0.0306721 0.157794 0.987306 -0.0299416 0.15598 0.887466 -0.0882992 0.452335 0.889469 -0.0867803 0.448681 0.670295 -0.175753 0.720982 0.513218 -0.107276 0.851527 0.692789 -0.138062 0.707801 0.205224 -0.187309 0.960624 0.0546946 -0.139504 0.98871 0.197092 -0.184098 0.962945 -0.0239327 -0.82098 0.570456 0.0138624 -0.955667 0.294122 -0.0114839 -0.943036 0.332492 -0.00270195 -0.389365 0.92108 0.070826 -0.123481 0.989816 -0.00169969 -0.387868 0.921713 -0.0465086 -0.797947 0.600931 -0.00432861 -0.628791 0.777562 -0.00743173 -0.389299 0.921082 -0.00321045 -0.377499 0.926005 -3.40759e-05 -0.193174 0.981165 -0.00671311 -0.636703 0.77108 0.0121144 -0.728431 0.685012 0.0253518 -0.728349 0.684737 -0.0318909 -0.942572 0.332476 -0.0120286 -0.958961 0.283283 -0.987285 -0.0303305 0.156037 -0.98701 -0.0302909 0.157777 -0.757802 -0.124709 0.640456 -0.887433 -0.0875437 0.452547 -0.872682 -0.0862676 0.480607 -0.93677 -0.0668548 0.343501 -0.397525 -0.164387 0.902746 -0.673729 -0.16943 0.719293 -0.520485 -0.109043 0.846879 -0.64286 -0.129845 0.754898 -0.00240341 -0.190809 0.981624 -0.00240487 -0.190809 0.981624 -0.194262 -0.187175 0.962927 -0.194391 -0.187145 0.962907 -0.467197 -0.168715 0.867907 -0.0118009 -0.867928 0.49655 -0.0137103 -0.986178 0.165124 -4.15683e-05 -0.193297 0.98114 -0.00485181 -0.379105 0.925341 -0.00694926 -0.628128 0.778079 -0.014902 -0.729341 0.683989 -0.008218 -0.815783 0.578299 -0.00849816 -0.949256 0.314389 -0.00965806 -0.943993 0.329823 -0.0180694 -0.943862 0.329847 -0.0146337 -0.959861 0.280092 -0.00363197 -0.389871 0.920862 -0.00307031 -0.38988 0.920861 0.0218624 -0.214915 0.976388 -0.00124355 -0.379214 0.925308 -0.00570564 -0.55702 0.830479 -0.00896091 -0.729443 0.683982 0.0050481 -0.646784 0.762657 -0.00773446 -0.769736 0.638316 0.00212601 -0.190808 0.981625 0.475846 -0.169268 0.863087 0.986941 -0.0307356 0.158121 0.987257 -0.0299936 0.156279 0.887142 -0.0884182 0.452947 0.889165 -0.0868869 0.449263 0.6697 -0.175626 0.721566 0.512972 -0.107353 0.851666 0.692193 -0.138174 0.708362 0.205111 -0.187312 0.960648 0.0550202 -0.139627 0.988674 0.19707 -0.184129 0.962943 -0.026808 -0.8204 0.571161 0.0101344 -0.955505 0.294802 -0.0150529 -0.942791 0.333045 -0.00355561 -0.389242 0.921129 0.0709982 -0.123429 0.98981 -0.00254965 -0.387752 0.92176 -0.0490777 -0.7973 0.601585 -0.00629766 -0.628352 0.777904 -0.00824785 -0.389157 0.921135 -0.00402092 -0.377517 0.925994 -4.47922e-05 -0.193163 0.981167 -0.00867988 -0.636233 0.771448 0.00961216 -0.728239 0.685256 0.0226776 -0.728213 0.684975 -0.0353831 -0.942247 0.333045 -0.0157213 -0.958678 0.284058 -0.98723 -0.0303956 0.156372 -0.986951 -0.0303548 0.158136 -0.757493 -0.124777 0.640808 -0.887059 -0.0876774 0.453253 -0.872458 -0.0864131 0.480989 -0.936638 -0.0669195 0.343847 -0.397226 -0.164509 0.902856 -0.673158 -0.169335 0.71985 -0.519778 -0.109199 0.847294 -0.642415 -0.130025 0.755246 -0.00240031 -0.190809 0.981624 -0.00240017 -0.190809 0.981624 -0.19431 -0.187172 0.962918 -0.194424 -0.187146 0.9629 -0.466769 -0.16876 0.868128 -0.0149406 -0.867642 0.496964 -0.0176136 -0.986052 0.165505 -3.79633e-05 -0.192668 0.981264 -0.00565134 -0.379081 0.925346 -0.00889861 -0.627614 0.778474 -0.0173245 -0.729028 0.684264 -0.0110839 -0.815129 0.579173 -0.0121343 -0.949084 0.314789 -0.0132797 -0.943727 0.330458 -0.0216515 -0.943562 0.330488 -0.018333 -0.959553 0.280932 -0.00449112 -0.389739 0.920915 -0.00393122 -0.38975 0.920913 0.021735 -0.214829 0.97641 -0.00208021 -0.379233 0.925299 -0.00731971 -0.556738 0.830656 -0.0113916 -0.729155 0.684254 0.0030312 -0.646358 0.763029 -0.0103803 -0.769372 0.638717 0.00189853 -0.190809 0.981625 0.475152 -0.169309 0.863461 0.986872 -0.0308166 0.158538 0.987192 -0.0300661 0.156677 0.886726 -0.0885738 0.45373 0.888774 -0.0870271 0.450008 0.66896 -0.175459 0.722293 0.512603 -0.107463 0.851874 0.691429 -0.138318 0.70908 0.20498 -0.187318 0.960674 0.054709 -0.139567 0.9887 0.19705 -0.184166 0.96294 -0.0296869 -0.819706 0.572014 0.00634675 -0.955262 0.295694 -0.0186238 -0.942485 0.33373 -0.00441001 -0.389097 0.921186 0.0711485 -0.123398 0.989803 -0.00340365 -0.387623 0.921812 -0.0515805 -0.796532 0.602392 -0.00827692 -0.62785 0.77829 -0.00905457 -0.388994 0.921196 -0.00483068 -0.377532 0.925984 -3.5245e-05 -0.192363 0.981324 -0.0106406 -0.635549 0.771987 0.00710397 -0.727948 0.685595 0.0199955 -0.727977 0.68531 -0.0388213 -0.941863 0.333746 -0.0194125 -0.958302 0.285096 -0.987159 -0.03048 0.156806 -0.98688 -0.0304384 0.158564 -0.757129 -0.124856 0.641222 -0.886583 -0.0878461 0.454151 -0.872174 -0.0865972 0.48147 -0.936523 -0.0669829 0.344148 -0.397008 -0.164668 0.902923 -0.672437 -0.169221 0.720551 -0.518942 -0.109386 0.847782 -0.64184 -0.13024 0.755697 -0.00221668 -0.190808 0.981625 -0.00158893 -0.19081 0.981626 -0.194345 -0.187173 0.96291 -0.194464 -0.187145 0.962892 -0.466238 -0.168814 0.868403 -0.0180781 -0.867315 0.497431 -0.0215192 -0.985948 0.16566 -6.718e-05 -0.193489 0.981103 -0.00644738 -0.379052 0.925353 -0.0108438 -0.627038 0.778913 -0.0197339 -0.728622 0.684632 -0.0139336 -0.814308 0.580266 -0.0157756 -0.94884 0.315364 -0.0169005 -0.943412 0.331192 -0.0252213 -0.943214 0.331228 -0.0220225 -0.959184 0.281923 -0.00534805 -0.389582 0.920976 -0.0047913 -0.389595 0.920974 0.0216147 -0.214645 0.976453 -0.00291781 -0.379227 0.925299 -0.0089363 -0.556673 0.830684 -0.0138155 -0.728773 0.684616 0.00102816 -0.645788 0.763516 -0.0130265 -0.768936 0.639193 0.00232131 -0.190808 0.981625 0.474342 -0.169362 0.863896 0.986787 -0.0309151 0.159044 0.987111 -0.0301578 0.15717 0.886223 -0.0887633 0.454675 0.888307 -0.0871935 0.450898 0.66806 -0.175255 0.723175 0.5121 -0.107605 0.852159 0.690483 -0.138496 0.709966 0.204822 -0.187318 0.960708 0.0554188 -0.139858 0.98862 0.197026 -0.184214 0.962936 -0.0325306 -0.818827 0.573118 0.00256577 -0.954956 0.296738 -0.0221946 -0.942105 0.334584 -0.00526266 -0.388914 0.921259 0.0710809 -0.124103 0.98972 -0.00426236 -0.387466 0.921874 -0.0540041 -0.795645 0.603351 -0.0102352 -0.627197 0.778794 -0.00983743 -0.388794 0.921272 -0.00563652 -0.37756 0.925968 -4.71452e-05 -0.192582 0.981281 -0.0125977 -0.634767 0.772601 0.00457354 -0.727618 0.685968 0.017262 -0.7277 0.685678 -0.0422364 -0.941407 0.334617 -0.0230581 -0.957878 0.286248 -0.987079 -0.0305736 0.157288 -0.986797 -0.0305304 0.15906 -0.756725 -0.124943 0.641682 -0.886011 -0.0880481 0.455228 -0.87183 -0.0868176 0.482052 -0.936347 -0.0670729 0.344611 -0.396907 -0.164864 0.902931 -0.67157 -0.169092 0.721388 -0.517971 -0.109602 0.848347 -0.641149 -0.130491 0.756241 -0.00243666 -0.190809 0.981624 -0.00180757 -0.190811 0.981625 -0.194379 -0.187172 0.962904 -0.194513 -0.18714 0.962883 -0.46559 -0.168876 0.868739 -0.0211969 -0.866926 0.497985 -0.0254009 -0.98574 0.166347 -7.16857e-05 -0.193265 0.981147 -0.00723376 -0.379028 0.925357 -0.0127684 -0.626277 0.779496 -0.022125 -0.728145 0.685066 -0.0167578 -0.813364 0.581514 -0.0194004 -0.948577 0.315951 -0.0205129 -0.943036 0.332057 -0.0287641 -0.942806 0.3321 -0.0256876 -0.958743 0.283111 -0.00619858 -0.389385 0.921054 -0.00564327 -0.389401 0.921051 0.0214394 -0.21481 0.976421 -0.00375501 -0.379214 0.925301 -0.010548 -0.556666 0.83067 -0.0162235 -0.728319 0.685046 -0.000959408 -0.645136 0.764067 -0.0156569 -0.768378 0.639805 -0.0353343 -0.817802 0.574414 -0.00121355 -0.954574 0.297971 -0.0257215 -0.941665 0.335568 -0.00610613 -0.388701 0.921344 0.0711803 -0.12412 0.989711 -0.00510904 -0.387278 0.921949 -0.0563479 -0.79462 0.604487 -0.0121944 -0.626474 0.779347 -0.0106114 -0.388564 0.921361 -0.00643795 -0.377562 0.925962 -7.50471e-05 -0.193193 0.981161 -0.0145185 -0.633834 0.773332 0.00205816 -0.727192 0.686432 0.014513 -0.727325 0.68614 -0.0456119 -0.940894 0.335616 -0.0267007 -0.957371 0.287624 -0.0287295 -0.985575 0.166784 -0.0186282 -0.942832 0.332748 -0.0143577 -0.949763 0.312639 -0.0250984 -0.866199 0.499069 -0.0063756 -0.389242 0.921113 0.0758539 -0.268273 0.960352 -0.000626648 -0.38293 0.923777 -0.0118854 -0.556822 0.830547 -0.0190833 -0.727936 0.68538 0.0206016 -0.660217 0.750792 -0.0149989 -0.769458 0.638521 -0.00646683 -0.389199 0.921131 -0.00647934 -0.389239 0.921114 -0.0182962 -0.727879 0.685462 -0.0183295 -0.727959 0.685375 -0.0270089 -0.942546 0.332984 -0.0270591 -0.942606 0.332809 -0.0873739 -0.941567 0.325296 -0.310779 -0.51097 0.801452 -0.247396 -0.730234 0.63683 -0.227996 -0.759377 0.609397 -0.254482 -0.400207 0.880382 -0.349236 -0.399679 0.84752 -0.361612 -0.27204 0.891757 -0.252346 -0.398156 0.881926 -0.186175 -0.730044 0.657552 -0.184939 -0.730707 0.657165 -0.0871438 -0.941462 0.325662 -0.103776 -0.941544 0.320509 -0.106181 -0.940076 0.32401 -0.0565731 -0.941221 0.33302 -0.0565723 -0.941014 0.333605 -0.0994998 -0.722953 0.683695 -0.0997521 -0.727274 0.679059 -0.125088 -0.382756 0.915342 -0.126295 -0.394736 0.910073 0.0514159 -0.996245 0.0696582 0.139282 -0.890036 -0.434093 0.139282 -0.890033 -0.4341 0.396641 -0.855326 -0.333306 0.396643 -0.855322 -0.333315 0.593619 -0.791193 -0.147072 0.593612 -0.7912 -0.147061 0.700212 -0.707414 0.0962758 0.700211 -0.707414 0.0962763 0.0514154 -0.996244 0.0696764 0.146408 -0.983433 0.106881 0.146408 -0.983433 0.106881 0.219116 -0.959762 0.175627 0.219116 -0.959762 0.175627 0.258467 -0.928833 0.265449 0.258474 -0.928832 0.265446 0 -0.987688 0.156436 0.000560582 -0.997564 0.0697505 0 -0.99452 -0.104549 0 -0.898797 -0.438366 0.00166481 -0.961269 -0.275607 0 -0.857164 -0.515043 0.258816 -0.913302 0.314475 0.258818 -0.913301 0.314475 0.707104 -0.668585 0.230212 0.707103 -0.668586 0.230213 -0.201069 -0.839664 -0.504515 -0.7504 -0.660816 0.0148819 -0.75039 -0.660828 0.0148873 -0.566891 -0.815009 0.119979 -0.493987 -0.856261 0.150974 -0.173449 -0.945281 0.276333 -0.173477 -0.945277 0.276327 -0.419903 -0.888134 0.186816 -0.549328 -0.774203 -0.314402 -0.549333 -0.774197 -0.314409 -0.362789 -0.9297 -0.0635727 -0.362797 -0.929696 -0.0635814 -0.126972 -0.971488 0.200221 -0.126974 -0.971488 0.20022 -0.201072 -0.839658 -0.504524 -0.151901 -0.950115 -0.272409 -0.136027 -0.9728 -0.187501 -0.112526 -0.988203 -0.103885 -0.0464764 -0.98662 0.156274 -0.046479 -0.986621 0.156267 0.258198 -0.888588 0.379136 0.694743 -0.596292 0.402204 0.694751 -0.596284 0.402202 0.508593 -0.491311 0.70707 0.508587 -0.491318 0.707068 0.20107 -0.351044 0.914516 0.192557 -0.432428 0.880868 0.151911 -0.58095 0.799638 0.112522 -0.714773 0.690245 0.258194 -0.88859 0.379136 0.189011 -0.849577 0.492437 0.189021 -0.849571 0.492443 0.0757019 -0.82867 0.554594 0.0464749 -0.87368 0.484275 -0.173664 -0.931151 0.320621 -0.25882 -0.912062 0.318049 -0.422588 -0.856944 0.29507 -0.573547 -0.774543 0.266697 -0.707091 -0.667356 0.233791 -0.766046 -0.607766 0.209271 0 -0.874625 0.484799 0 -0.874625 0.484799 0 -0.719341 0.694657 0 -0.719341 0.694657 0 -0.587771 0.809027 0 -0.587771 0.809027 0 -0.358363 0.933582 0 -0.358363 0.933582 -0.150637 -0.354274 0.922929 -0.083768 -0.716813 0.692216 -0.113359 -0.583983 0.803812 -0.0345192 -0.874104 0.48451 -0.148109 -0.435808 0.88777 -0.396642 -0.468799 0.789241 -0.396641 -0.468805 0.789239 -0.593612 -0.532932 0.603 -0.593606 -0.532943 0.602996 -0.700204 -0.616732 0.359662 -0.700204 -0.616732 0.359662 -0.0604776 -0.829548 0.555152 -0.146407 -0.840762 0.521233 -0.146419 -0.840746 0.521256 -0.219136 -0.86442 0.452502 -0.219136 -0.86442 0.452502 -0.258489 -0.89535 0.362674 -0.25848 -0.895353 0.362671 0.914189 0.186408 -0.359877 0.742534 0.196454 -0.640351 0.12284 0.982582 -0.139435 0.169186 0.980328 -0.101655 0.172894 0.979465 -0.103714 0.201566 0.977823 -0.0568707 0.204587 0.977165 -0.0573879 0.414507 -0.10966 -0.903415 0.564214 0.198654 -0.801373 0.745209 0.187181 -0.640021 0.489357 0.189985 -0.851138 0.178991 0.20173 -0.962947 0.181217 0.193186 -0.964282 -0.151914 0.201517 -0.967633 -0.83801 0.199181 -0.508002 -0.726096 0.19736 -0.65866 -0.726101 0.197517 -0.658608 -0.54809 0.199736 -0.812221 -0.475849 0.0438857 -0.878431 -0.40264 0.200836 -0.893054 -0.150753 0.196012 -0.968944 -0.924064 0.110926 -0.365788 -0.903443 0.196407 -0.381071 -0.9739 0.196976 -0.112783 -0.996358 0.0579834 -0.0625129 -0.978818 0.198096 0.0516986 -0.958442 0.19753 0.205841 -0.958517 0.197268 0.205745 -0.895043 0.198147 0.399544 -0.883016 0.0445209 0.467226 -0.815163 0.198901 0.544011 -0.666108 0.197509 0.719229 -0.665914 0.198092 0.719248 0.460048 0.19608 0.865972 0.26511 0.201447 0.94294 0.262908 0.192442 0.945434 0.053882 0.20093 0.978123 -0.0714329 0.0701081 0.994978 -0.112997 0.197464 0.973776 -0.388868 0.200318 0.899252 -0.370271 0.0946352 0.924091 -0.512086 0.200286 0.835257 0.603873 0.0162829 0.796914 0.561364 0.199163 0.803246 0.779817 0.188777 0.596866 0.804954 0.0980193 0.585185 0.867309 0.194291 0.458285 0.941126 0.186668 0.281845 0.940653 0.191218 0.280369 0.213544 0.976804 -0.0158818 0.191597 0.981458 -0.00555942 0.213915 0.976807 0.00942023 0.209341 0.976801 0.0451138 0.207184 0.977316 0.0439059 0.182566 0.978758 0.0932918 0.179864 0.979546 0.0902136 0.136795 0.981751 0.13211 0.135395 0.982409 0.128613 0.0767621 0.984799 0.155814 0.0767034 0.985027 0.1544 0.0101885 0.986925 0.160858 0.00962466 0.986629 0.1627 -0.0542779 0.987644 0.147018 -0.0570693 0.986914 0.150813 -0.10912 0.987135 0.116868 -0.113854 0.98621 0.120116 -0.149044 0.98603 0.0743741 -0.153481 0.985257 0.0755849 -0.167425 0.985319 0.0333994 -0.168831 0.985085 0.0332175 -0.173398 0.9848 -0.0100812 -0.172781 0.98491 -0.00990347 -0.160146 0.985048 -0.0635099 -0.156911 0.985714 -0.0612142 -0.125224 0.985925 -0.11077 -0.121967 0.986839 -0.106172 -0.0720448 0.986764 -0.145281 -0.0706256 0.987584 -0.140322 -0.00738561 0.986797 -0.161792 -0.00754533 0.987242 -0.15905 0.0597212 0.985568 -0.158393 0.0599517 0.985465 -0.158947 0.441547 0.82779 -0.346122 0.534972 0.822403 -0.193541 0.534945 0.822421 -0.193538 0.571743 0.82013 -0.0222815 0.571768 0.820113 -0.0222758 0.549894 0.821503 0.150829 0.54989 0.821506 0.150827 0.470828 0.826198 0.309382 0.47096 0.826058 0.309556 0.340281 0.832802 0.436634 0.34057 0.832202 0.437552 0.170299 0.839171 0.516517 0.170239 0.837978 0.51847 -0.0198413 0.843387 0.53694 -0.0209141 0.841556 0.539764 -0.20632 0.844452 0.4943 -0.20864 0.84224 0.497093 -0.366046 0.842839 0.394504 -0.368978 0.84072 0.396289 -0.48105 0.840091 0.250675 -0.483454 0.838554 0.251196 -0.530763 0.840092 0.111968 -0.5315 0.839646 0.111813 -0.545623 0.837359 -0.0335499 -0.54531 0.837567 -0.0334403 -0.503821 0.83806 -0.209334 -0.502177 0.839373 -0.208017 -0.402881 0.840092 -0.363225 -0.401159 0.842099 -0.360473 -0.252482 0.841925 -0.476881 -0.25166 0.844185 -0.473307 -0.0696905 0.841944 -0.535045 -0.0700228 0.84392 -0.531879 0.122484 0.839112 -0.529989 0.121546 0.840523 -0.527965 0.299795 0.833796 -0.463582 0.78238 0.546027 -0.29956 0.839372 0.542463 -0.034485 0.839167 0.542774 -0.0345649 0.80541 0.544973 0.233066 0.806471 0.542984 0.234035 0.685493 0.550264 0.476769 0.686757 0.546535 0.479233 0.489555 0.556817 0.671037 0.490014 0.552132 0.674563 0.236205 0.562578 0.792284 0.235473 0.557824 0.795855 -0.0463017 0.565832 0.823219 -0.0478549 0.561787 0.825897 -0.323445 0.566006 0.758301 -0.32514 0.563016 0.759801 -0.561348 0.563801 0.60582 -0.562646 0.561913 0.606369 -0.732856 0.560849 0.385187 -0.733548 0.559912 0.385235 -0.80872 0.562324 0.172525 -0.808887 0.562105 0.172454 -0.827904 0.558502 -0.0514934 -0.827817 0.558634 -0.0514478 -0.764351 0.559455 -0.32059 -0.763996 0.560159 -0.320205 -0.61356 0.561361 -0.555354 -0.613077 0.562987 -0.55424 -0.390469 0.562831 -0.728529 -0.390305 0.565522 -0.726531 -0.120026 0.562247 -0.818213 -0.120698 0.566107 -0.815448 0.165011 0.558951 -0.812616 0.16321 0.563651 -0.809729 0.429705 0.553513 -0.713426 0.42702 0.558408 -0.711221 0.64345 0.547679 -0.534808 0.120673 0.983192 -0.137006 0.298987 0.834552 -0.462741 0.441889 0.827535 -0.346295 0.640711 0.551845 -0.533814 0.784144 0.543497 -0.299547 0.912662 0.192206 -0.3607 0.981307 0.187879 -0.0416885 0.992386 -0.0629912 -0.105841 0.979596 0.191603 0.0606604 0.911151 0.195786 -0.362592 0.73944 0.197315 -0.643657 0.0766009 0.986766 -0.142915 0.123624 0.986811 -0.1045 0.128575 0.985892 -0.107171 0.158024 0.985672 -0.0589806 0.161734 0.985034 -0.059579 0.420421 -0.110537 -0.900571 0.556449 0.199585 -0.806554 0.73941 0.197409 -0.643664 0.483472 0.199644 -0.852289 0.172132 0.196202 -0.965337 0.170435 0.201463 -0.964554 -0.15957 0.193489 -0.968039 -0.841993 0.193363 -0.503645 -0.731358 0.196669 -0.653022 -0.730809 0.187469 -0.656333 -0.5564 0.198557 -0.806842 -0.475173 0.039213 -0.879018 -0.412852 0.194233 -0.889847 -0.1618 0.201766 -0.965977 -0.925886 0.0980806 -0.364849 -0.90504 0.192494 -0.379274 -0.975388 0.189815 -0.112201 -0.996774 0.0484179 -0.0640152 -0.980131 0.191858 0.0503342 -0.960185 0.192107 0.20283 -0.960775 0.189926 0.202087 -0.89808 0.19395 0.39476 -0.883816 0.0336387 0.466624 -0.820196 0.192036 0.538888 -0.671313 0.197647 0.714335 -0.674158 0.187844 0.714301 0.4494 0.200772 0.870477 0.252483 0.196631 0.947411 0.253329 0.201088 0.94625 0.0411262 0.199214 0.979093 -0.0735044 0.0681013 0.994967 -0.125253 0.201661 0.971414 -0.397117 0.191025 0.897668 -0.375659 0.0961541 0.921757 -0.521365 0.197937 0.83006 0.602338 0.0264144 0.797804 0.554345 0.197565 0.808498 0.773555 0.197846 0.602055 0.802562 0.104797 0.587293 0.863543 0.199104 0.463304 0.938551 0.195572 0.284384 0.938494 0.196079 0.284223 0.171005 0.985132 -0.0164971 0.148595 0.988881 -0.00577209 0.171486 0.985137 0.00986305 0.166686 0.984879 0.0472229 0.164003 0.9854 0.0457143 0.138296 0.985618 0.0971113 0.134772 0.986493 0.093104 0.0902269 0.986555 0.136267 0.0881352 0.987445 0.131088 0.0282323 0.986918 0.158731 0.0280645 0.987494 0.155139 -0.039106 0.986088 0.161556 -0.0389737 0.986166 0.161112 -0.102778 0.984023 0.145381 -0.104283 0.983554 0.14747 -0.155666 0.981222 0.113894 -0.159116 0.980384 0.116313 -0.193416 0.9785 0.0716127 -0.196855 0.977742 0.0725827 -0.21027 0.977126 0.0317909 -0.211438 0.976879 0.0316491 -0.21574 0.976401 -0.00989062 -0.215177 0.976527 -0.00972966 -0.203015 0.977271 -0.0610491 -0.200449 0.977912 -0.059223 -0.169911 0.979641 -0.106925 -0.1675 0.980425 -0.103492 -0.118944 0.982763 -0.141526 -0.118083 0.983305 -0.138451 -0.055903 0.985606 -0.159547 -0.0559299 0.98567 -0.159142 0.0109363 0.987308 -0.158443 0.0120811 0.986861 -0.161117 0.411005 0.840027 -0.35416 0.506211 0.83927 -0.198436 0.508222 0.838003 -0.198651 0.545946 0.837513 -0.0226852 0.546145 0.837384 -0.0226383 0.523436 0.837662 0.156006 0.522128 0.838633 0.155168 0.440253 0.83938 0.318776 0.438416 0.841228 0.316427 0.303774 0.841469 0.446823 0.302601 0.843705 0.44339 0.128812 0.842207 0.523541 0.128818 0.844329 0.520111 -0.0630983 0.840308 0.538424 -0.0622617 0.841925 0.535991 -0.247479 0.835655 0.490341 -0.246576 0.836602 0.489181 -0.402349 0.829468 0.387425 -0.401864 0.82985 0.387111 -0.51178 0.823764 0.243914 -0.511693 0.823824 0.243893 -0.557686 0.823012 0.107877 -0.557706 0.822999 0.107874 -0.571167 0.820158 -0.0333035 -0.571151 0.82017 -0.0332979 -0.530801 0.82269 -0.20355 -0.530839 0.822657 -0.203582 -0.434492 0.828177 -0.354033 -0.434685 0.827937 -0.354357 -0.289752 0.834965 -0.467844 -0.290004 0.834174 -0.469096 -0.110969 0.840815 -0.529826 -0.110652 0.8394 -0.532131 0.0806871 0.844063 -0.530138 0.08216 0.842084 -0.533052 0.260962 0.844174 -0.468262 0.77081 0.559371 -0.304887 0.828706 0.558599 -0.0348272 0.828761 0.558519 -0.0348052 0.793955 0.558991 0.239093 0.793657 0.559525 0.238831 0.669183 0.560764 0.487584 0.6687 0.562082 0.486727 0.466414 0.562556 0.682633 0.4661 0.564872 0.680933 0.207503 0.562724 0.800178 0.207863 0.56623 0.797607 -0.076768 0.560269 0.824746 -0.0753257 0.564746 0.82182 -0.351402 0.555336 0.753737 -0.348927 0.56026 0.751238 -0.583846 0.549396 0.597736 -0.58099 0.553926 0.596336 -0.749061 0.544537 0.377342 -0.746922 0.547623 0.377116 -0.820579 0.546424 0.167542 -0.819894 0.547366 0.167822 -0.838227 0.542881 -0.0515269 -0.838516 0.542421 -0.0516809 -0.776323 0.546376 -0.314317 -0.77755 0.543813 -0.315726 -0.630762 0.552327 -0.545046 -0.63187 0.548156 -0.547965 -0.4141 0.558812 -0.718505 -0.414184 0.55403 -0.722151 -0.148007 0.563945 -0.812441 -0.146946 0.559352 -0.815802 0.136664 0.566215 -0.812849 0.138344 0.562467 -0.815164 0.404785 0.565473 -0.718602 0.406391 0.562851 -0.719754 0.624112 0.56284 -0.541937 0.0730341 0.987593 -0.139016 0.263577 0.841941 -0.470812 0.408105 0.842015 -0.35279 0.625205 0.561304 -0.54227 0.7703 0.560062 -0.304906 0.911002 0.196312 -0.36268 0.979853 0.195371 -0.0414587 0.993253 -0.0485526 -0.10531 0.978265 0.197987 0.0616389 -0.207559 -0.905325 0.370548 -0.15558 -0.566592 0.809178 -0.0556222 -0.85585 0.514225 -0.0556267 -0.855838 0.514244 -0.120738 -0.689638 0.714018 -0.163148 -0.522805 0.836695 -0.207603 -0.905311 0.370558 -0.450517 -0.797074 0.402128 -0.581637 -0.705386 0.405128 -0.246942 0.583184 0.773897 -0.258489 0.361837 0.895688 -0.255179 0.217606 0.942089 -0.255842 0.167865 0.952033 -0.226045 -0.185863 0.956221 -0.231616 -0.084804 0.969104 -0.211853 -0.285755 0.934592 -0.151968 -0.873947 0.461652 -0.151945 -0.873962 0.46163 -0.425049 -0.617244 0.662075 -0.425053 -0.617238 0.662078 -0.617568 -0.259453 0.742491 -0.617561 -0.259475 0.742489 -0.70349 0.133506 0.698053 -0.703491 0.133537 0.698047 -0.620577 -0.670425 0.406711 -0.790634 -0.474202 0.387338 -0.844623 -0.387582 0.369314 -0.887356 -0.296121 0.35343 -0.960986 -0.0116626 0.27635 -0.955616 -0.0608421 0.288263 -0.964689 0.131989 0.227935 -0.24694 0.583196 0.773888 -0.674655 0.502801 0.5404 -0.674662 0.502778 0.540413 -0.921602 0.36353 0.135999 -0.921599 0.36354 0.135995 0 -0.857177 0.515023 0 -0.857177 0.515023 0 -0.69472 0.71928 0 -0.69472 0.71928 0 -0.529905 0.848057 0 -0.529905 0.848057 0 -0.292392 0.956298 0 -0.292392 0.956298 0 -0.087174 0.996193 0 -0.087174 0.996193 0 0.173644 0.984809 0 0.173644 0.984809 0 0.374567 0.9272 0 0.374567 0.9272 0 0.601822 0.79863 0 0.601822 0.79863 -0.207925 -0.924854 0.318453 -0.258847 -0.91285 0.315758 -0.453834 -0.842538 0.290111 -0.629339 -0.734791 0.25301 -0.707081 -0.667939 0.232152 -0.808999 -0.555786 0.191372 -0.913551 -0.384564 0.132416 -0.965922 -0.244058 0.0861972 -0.987685 -0.147932 0.0509369 -0.998627 0.0495246 -0.0170527 -0.965927 0.245152 -0.0829742 -0.951053 0.292191 -0.10061 0.853138 0.428619 0.297391 0.0413218 -0.856434 0.514601 0.0413159 -0.856445 0.514583 0.089922 -0.691906 0.716366 0.113111 -0.569097 0.814454 0.117684 -0.866724 0.484706 0.117675 -0.866731 0.484696 0.330703 -0.59863 0.729574 0.330696 -0.59864 0.729569 0.48344 -0.230353 0.844525 0.483443 -0.230345 0.844526 0.552643 0.17234 0.815405 0.55264 0.172315 0.815412 0.124213 -0.525801 0.841489 0.158877 -0.288679 0.944152 0.165597 -0.187354 0.968234 0.178785 -0.0857696 0.980143 0.194062 0.220666 0.955849 0.188555 0.170529 0.967144 0.194834 0.367389 0.909431 0.20774 -0.910613 0.357251 0.207718 -0.910618 0.35725 0.583791 -0.721972 0.371409 0.583812 -0.721956 0.371406 0.853465 -0.410611 0.32093 0.853459 -0.410622 0.320933 0.975612 -0.0338075 0.216884 0.975611 -0.0338107 0.216886 0.934468 0.347646 0.0768834 0.934472 0.347634 0.0768894 0.176094 -0.885762 0.429438 0.176125 -0.885749 0.429452 0.494933 -0.652096 0.574293 0.494928 -0.6521 0.574292 0.723525 -0.308502 0.617526 0.72352 -0.308512 0.617527 0.827084 0.0829376 0.555926 0.827091 0.0829896 0.555907 0.62603 0.758443 0.181245 0.75515 0.478531 0.448059 0.579445 0.535743 0.614185 0.418278 0.8261 0.377626 0.420721 0.56938 0.706258 0.18588 0.591332 0.784714 0.18588 0.591334 0.784712 -0.0556276 -0.991013 0.121652 -0.0663432 -0.995474 0.0680425 -0.120769 -0.983012 -0.13821 -0.166268 -0.92663 -0.337213 -0.181702 -0.88306 -0.432654 -0.258227 -0.933632 0.248296 -0.258226 -0.933632 0.248296 -0.694722 -0.717525 0.0501867 -0.694732 -0.717516 0.050182 -0.935112 -0.318493 -0.155334 -0.935114 -0.318485 -0.155337 -0.935115 0.155331 -0.318485 -0.935116 0.155328 -0.318484 -0.189037 -0.972648 0.134984 -0.189008 -0.97265 0.135011 -0.508578 -0.822488 -0.254678 -0.508595 -0.822472 -0.254697 -0.684551 -0.459782 -0.565677 -0.684549 -0.459789 -0.565674 -0.684552 0.0140373 -0.728829 -0.684552 0.0140379 -0.728829 -0.211863 -0.800523 -0.560605 -0.23776 -0.662466 -0.710359 -0.245962 -0.5415 -0.803915 -0.255845 -0.453823 -0.853574 -0.250563 -0.0675295 -0.965742 -0.243315 -0.26734 -0.932377 -0.246943 -0.016912 -0.968883 0.207918 -0.924856 0.318453 0.258847 -0.91285 0.315758 0.587766 -0.765286 0.262428 0.629259 -0.734853 0.25303 0.809035 -0.555739 0.191356 0.866035 -0.473187 0.161487 0.91355 -0.384567 0.132417 0.994518 -0.0988651 0.034042 0.987677 -0.148419 0.049665 0.951041 0.292773 -0.0990186 0.965921 0.244735 -0.0842696 0 -0.99255 0.12184 0 -0.99255 0.12184 0 -0.99026 -0.139229 0 -0.99026 -0.139229 0 -0.93971 -0.341973 0 -0.93971 -0.341973 0 -0.819117 -0.573626 0 -0.819117 -0.573626 0 -0.682023 -0.731331 0 -0.682023 -0.731331 0 -0.469448 -0.88296 0 -0.469448 -0.88296 0 -0.275624 -0.961266 0 -0.275624 -0.961266 0 -0.0174525 -0.999848 0 -0.0174525 -0.999848 0.23776 -0.662465 -0.710359 0.258233 -0.933631 0.248293 0.186157 -0.883079 -0.430718 0.200392 -0.802502 -0.561991 0.166268 -0.92663 -0.337213 0.0691819 -0.995173 0.0695971 0.10539 -0.984745 -0.138453 0.0556277 -0.991013 0.121652 0.258227 -0.933632 0.248296 0.620499 -0.778756 0.0923042 0.696542 -0.715466 0.0541916 0.248219 -0.454756 -0.855327 0.250563 -0.541378 -0.802576 0.258489 -0.266256 -0.928596 0.247492 -0.0680038 -0.966501 0.246943 -0.016912 -0.968883 0.189015 -0.972649 0.135008 0.189039 -0.972649 0.134977 0.508593 -0.822473 -0.254699 0.508573 -0.822496 -0.254665 0.684547 -0.459805 -0.565663 0.684551 -0.459782 -0.565678 0.684548 0.0140572 -0.728832 0.684553 0.0140381 -0.728828 0.79067 -0.612098 -0.0133063 0.887351 -0.45095 -0.0961926 0.936417 -0.316692 -0.151093 0.954807 -0.226343 -0.192645 0.935116 0.155328 -0.318484 0.935108 0.155355 -0.318494 -0.0958263 0.86628 0.490282 -0.0616411 0.991472 0.114819 -0.0175346 0.959662 -0.280609 -0.0951562 0.867148 0.488877 -0.213861 0.858565 0.465973 -0.212058 0.859381 0.465292 -0.341619 0.83688 0.427702 -0.337188 0.842061 0.420996 -0.451278 0.816381 0.360375 -0.447881 0.818274 0.360319 -0.550173 0.782094 0.292642 -0.542953 0.789679 0.285673 -0.624925 0.754687 0.199792 -0.621964 0.756866 0.200783 -0.690395 0.714595 0.112736 -0.68388 0.721391 0.109101 -0.733952 0.679191 -0.00385577 -0.732093 0.681197 -0.00326776 -0.764112 0.634381 -0.117021 -0.762304 0.6365 -0.1173 -0.0620063 0.991351 0.115664 -0.140365 0.985105 0.0993311 -0.140671 0.985047 0.0994728 -0.225004 0.971332 0.076724 -0.225683 0.971098 0.077687 -0.297103 0.954089 0.0379948 -0.297412 0.953992 0.0380204 -0.360552 0.932737 -0.00200162 -0.361536 0.932357 -0.00118576 -0.409297 0.91085 -0.0531872 -0.409597 0.910711 -0.0532627 -0.449889 0.887122 -0.103027 -0.450943 0.88664 -0.102567 -0.478215 0.862238 -0.166901 -0.478507 0.862062 -0.166974 -0.497369 0.836512 -0.229936 -0.497892 0.83621 -0.229904 -0.0189817 0.960579 -0.277359 -0.045078 0.958076 -0.282945 -0.0474643 0.958285 -0.281845 -0.0725754 0.954741 -0.288448 -0.080023 0.956903 -0.279164 -0.0994963 0.951789 -0.290169 -0.103744 0.951436 -0.289838 -0.116982 0.947339 -0.298101 -0.129718 0.948377 -0.289403 -0.138583 0.94407 -0.29921 -0.142591 0.943159 -0.300197 -0.147379 0.94055 -0.306016 -0.159442 0.939828 -0.302162 -0.162354 0.937042 -0.309183 -0.165514 0.936212 -0.310021 -0.166903 0.934461 -0.314525 -0.170818 0.933713 -0.314644 0.0137026 0.958047 -0.286284 0.0141126 0.955 -0.296271 0.00920933 0.993686 0.111814 0.0094847 0.994368 0.105557 0.00322475 0.870578 0.492021 0.00332109 0.871605 0.490198 0.00790703 0.959803 -0.280565 0.00811836 0.958094 -0.286339 0.0053066 0.993309 0.115366 0.0054426 0.993718 0.111777 0.00185684 0.87 0.493049 0.00190342 0.870589 0.492008 -0.16986 0.940062 -0.295686 -0.170802 0.939853 -0.295808 -0.49797 0.825418 -0.265915 -0.498481 0.825104 -0.265932 -0.765556 0.610252 -0.203758 -0.765672 0.610109 -0.203748 -0.169102 0.95341 -0.249828 -0.171406 0.952895 -0.250224 -0.497764 0.834565 -0.236076 -0.49898 0.833805 -0.236194 -0.765606 0.613548 -0.19341 -0.765907 0.61317 -0.193415 0.581217 0.781029 -0.228431 0.766196 0.625835 -0.14586 0.43571 0.856716 -0.276035 0.194737 0.922913 -0.332129 0.769287 0.62282 -0.14245 0.749439 0.659719 -0.055784 0.750709 0.658598 -0.0518037 0.712204 0.700065 0.0517076 0.71877 0.692346 0.0634576 0.655615 0.739034 0.15491 0.655538 0.737539 0.162192 0.57629 0.778198 0.249596 0.580206 0.769351 0.267321 0.481228 0.809817 0.335583 0.4786 0.808427 0.342619 0.365036 0.839303 0.402889 0.364372 0.831802 0.418733 0.246635 0.856657 0.453111 0.243345 0.85604 0.456046 0.117848 0.868807 0.480923 0.115811 0.864674 0.488802 0.514013 0.815966 -0.264555 0.499655 0.84181 -0.204206 0.50001 0.841755 -0.203567 0.478663 0.866225 -0.143301 0.480181 0.865667 -0.141585 0.441487 0.892992 -0.087489 0.441682 0.893005 -0.0863679 0.392843 0.919089 -0.0308007 0.394025 0.918672 -0.0280513 0.329286 0.944111 0.015003 0.329019 0.944183 0.0162942 0.253897 0.965506 0.0577501 0.254279 0.965174 0.0614964 0.174144 0.981198 0.083208 0.173332 0.981267 0.0840894 0.0880865 0.990804 0.102702 0.0874555 0.990468 0.106415 0.192164 0.923018 -0.333334 0.19106 0.924847 -0.328868 0.18945 0.924435 -0.330951 0.18639 0.928178 -0.322094 0.178003 0.927421 -0.328945 0.170834 0.93221 -0.319063 0.169426 0.930939 -0.323492 0.15663 0.938162 -0.308737 0.149353 0.935358 -0.320624 0.130248 0.942401 -0.308083 0.130719 0.940891 -0.31247 0.104828 0.948799 -0.297978 0.102897 0.945991 -0.30743 0.0744674 0.95105 -0.299931 0.0755839 0.95055 -0.301233 0.0442385 0.954728 -0.294171 0.0444371 0.954245 -0.295706 -0.761148 0.601321 -0.243038 -0.49652 0.830596 -0.252147 -0.170458 0.958214 -0.229716 -0.770258 0.587165 -0.248878 -0.752579 0.573098 -0.32432 -0.754659 0.56602 -0.331831 -0.714859 0.542103 -0.441703 -0.727264 0.515727 -0.452893 -0.663416 0.501033 -0.555738 -0.661803 0.494097 -0.563813 -0.582623 0.47488 -0.659575 -0.587568 0.450242 -0.672343 -0.486688 0.440664 -0.754288 -0.482696 0.435403 -0.759888 -0.368049 0.421424 -0.828819 -0.36722 0.405195 -0.837237 -0.247815 0.401729 -0.88159 -0.24467 0.400296 -0.883119 -0.117627 0.391842 -0.912482 -0.116615 0.387726 -0.914368 -0.503076 0.825587 -0.255578 -0.492394 0.817337 -0.299181 -0.494203 0.814877 -0.302886 -0.470515 0.800056 -0.372192 -0.479939 0.790974 -0.379497 -0.437748 0.78153 -0.444508 -0.437803 0.779188 -0.448547 -0.387018 0.766534 -0.512487 -0.391635 0.758733 -0.520525 -0.323221 0.752543 -0.573766 -0.322074 0.750918 -0.576533 -0.245247 0.74117 -0.624916 -0.245953 0.736348 -0.630316 -0.163675 0.734407 -0.658678 -0.162586 0.733989 -0.659414 -0.0759622 0.727737 -0.681637 -0.0757148 0.726719 -0.682749 -0.170623 0.958165 -0.2298 -0.169275 0.957103 -0.23516 -0.169035 0.957243 -0.234761 -0.1632 0.953726 -0.252532 -0.162185 0.954105 -0.251755 -0.150245 0.951183 -0.269589 -0.150123 0.95147 -0.268641 -0.134298 0.947812 -0.289165 -0.132252 0.94909 -0.285897 -0.109562 0.946681 -0.302969 -0.109919 0.94707 -0.301624 -0.0827998 0.944018 -0.319333 -0.0820898 0.945268 -0.3158 -0.0523875 0.944129 -0.325386 -0.0530161 0.944275 -0.324861 -0.021256 0.942443 -0.333689 -0.0214551 0.942979 -0.332161 0.769094 0.608298 -0.196133 0.279193 0.923398 -0.263414 0.278949 0.923452 -0.263483 0.768732 0.605305 -0.206534 0.712121 0.669094 -0.212596 0.711861 0.665537 -0.224309 0.583106 0.777582 -0.235274 0.194452 0.929979 -0.311975 0.27861 0.914819 -0.292374 0.435965 0.852849 -0.287373 0.58218 0.770159 -0.260618 0.0128205 0.942572 -0.333758 0.0127862 0.943065 -0.332361 0.00868249 0.727743 -0.685795 0.00866609 0.728348 -0.685152 0.00307071 0.389113 -0.921185 0.003066 0.389383 -0.921071 0.0224624 0.941516 -0.336218 0.0224175 0.942379 -0.333795 0.0152028 0.726556 -0.686939 0.0151882 0.727612 -0.68582 0.00537524 0.388601 -0.92139 0.00537269 0.389067 -0.921194 0.0861645 0.384855 -0.918946 0.072372 0.723724 -0.686285 0.0464717 0.940606 -0.336305 0.0830076 0.391475 -0.916437 0.192555 0.391723 -0.899709 0.187765 0.395481 -0.899077 0.330682 0.393366 -0.857853 0.321624 0.413119 -0.851992 0.44976 0.422018 -0.787157 0.441937 0.427279 -0.788749 0.55807 0.432443 -0.708203 0.542541 0.45796 -0.704217 0.633644 0.474101 -0.611329 0.626171 0.4779 -0.616053 0.703558 0.489524 -0.515143 0.684836 0.51448 -0.516053 0.744655 0.539589 -0.392852 0.73666 0.546278 -0.398638 0.776185 0.567676 -0.274373 0.761062 0.584776 -0.280752 0.0707291 0.726225 -0.683809 0.144057 0.726564 -0.671828 0.141802 0.727864 -0.670899 0.237228 0.726057 -0.645418 0.232209 0.732536 -0.639899 0.315049 0.738619 -0.595975 0.311403 0.740261 -0.595854 0.3865 0.743343 -0.545948 0.377468 0.751486 -0.541099 0.433348 0.761642 -0.48178 0.429693 0.762779 -0.483253 0.478275 0.769887 -0.422525 0.466277 0.77835 -0.420424 0.501257 0.793376 -0.345391 0.496184 0.795622 -0.347544 0.519773 0.808057 -0.277273 0.581034 0.769861 -0.264033 0.0464599 0.940615 -0.336281 0.0718724 0.940573 -0.331898 0.0722812 0.940455 -0.332145 0.104073 0.94024 -0.324218 0.105726 0.939294 -0.326417 0.131875 0.940877 -0.312026 0.133162 0.940617 -0.312262 0.154659 0.941808 -0.29846 0.158043 0.940516 -0.300753 0.172879 0.942954 -0.284518 0.173914 0.942846 -0.284246 0.185383 0.944746 -0.270347 0.18702 0.944287 -0.270826 0.194658 0.947422 -0.253969 0.194571 0.947434 -0.253992 0.187777 0.943414 -0.273331 0.279389 0.925369 -0.256191 0.130495 0.652477 -0.746488 0.030167 0.644441 -0.764059 0.0832896 0.907334 -0.412078 0.119933 0.99263 0.0173591 0.133242 0.887474 0.441176 0.120816 0.613048 0.780753 0.0847594 0.219255 0.971979 0.0300013 0.645115 -0.763496 0.0994609 0.628098 -0.771752 0.10079 0.631295 -0.768965 0.142078 0.60401 -0.78421 0.145659 0.60779 -0.780625 0.156341 0.596738 -0.787058 0.162329 0.599984 -0.78337 0.157202 0.608342 -0.777951 0.159483 0.609043 -0.776938 0.154419 0.621958 -0.767674 0.178506 0.630425 -0.755447 0.148464 0.631455 -0.761067 0.143241 0.652832 -0.743836 0.0838435 0.906347 -0.414131 0.281491 0.854365 -0.436833 0.278484 0.848385 -0.45021 0.410544 0.763149 -0.499056 0.403072 0.757713 -0.513229 0.466763 0.691495 -0.551332 0.447445 0.686249 -0.57346 0.47261 0.645503 -0.599971 0.446083 0.643514 -0.622012 0.452567 0.627167 -0.633911 0.426589 0.627923 -0.650949 0.428955 0.618089 -0.658759 0.382676 0.625655 -0.679791 0.121525 0.992512 0.0123165 0.406894 0.913169 -0.0236472 0.405652 0.912367 -0.0550654 0.604743 0.786277 -0.126705 0.595917 0.785891 -0.165104 0.701111 0.675547 -0.228212 0.673101 0.680975 -0.288459 0.724929 0.597546 -0.34266 0.684875 0.608514 -0.40082 0.704524 0.559467 -0.436627 0.665623 0.57167 -0.479728 0.675881 0.52805 -0.514147 0.608518 0.555481 -0.566698 0.136167 0.89042 0.434294 0.454427 0.801647 0.388404 0.461426 0.816942 0.345965 0.691343 0.671649 0.266333 0.694345 0.688998 0.207766 0.822867 0.553205 0.129822 0.809996 0.585497 0.0331588 0.880926 0.471518 -0.0404931 0.850328 0.507944 -0.137607 0.880826 0.43248 -0.192629 0.845033 0.46383 -0.266048 0.861642 0.391221 -0.323295 0.792358 0.446872 -0.415301 0.125265 0.62039 0.774225 0.417065 0.543058 0.728796 0.437788 0.58063 0.686448 0.656184 0.440484 0.612696 0.683808 0.482922 0.546986 0.814207 0.345003 0.466948 0.841207 0.412813 0.349223 0.920737 0.284613 0.266906 0.925314 0.352681 0.139321 0.9629 0.26005 0.0720987 0.948943 0.314085 -0.0292874 0.96991 0.220338 -0.103564 0.921741 0.307446 -0.236367 0.0908245 0.231176 0.968663 0.299634 0.179669 0.936984 0.338632 0.241186 0.909482 0.504656 0.132143 0.853147 0.566188 0.199395 0.799795 0.676529 0.0833688 0.731681 0.763314 0.185267 0.618892 0.839556 0.0615804 0.539773 0.902377 0.159219 0.400455 0.942214 0.0607971 0.329449 0.96837 0.135716 0.209384 0.991606 0.0308668 0.125559 0.988283 0.146681 -0.0422087 0.000423033 0.220049 0.975489 0.000421566 0.220012 0.975497 0.00118932 0.61756 0.786523 0.0011838 0.617445 0.786613 0.00172491 0.895429 0.445202 0.00171643 0.895327 0.445405 0.00192715 0.999843 0.0176391 0.0019159 0.999837 0.0179477 0.00175757 0.910581 -0.413326 0.00174276 0.910753 -0.412948 0.00124805 0.644929 -0.764241 0.00123106 0.645301 -0.763928 0.000200564 0.220084 0.975481 0.000199266 0.22005 0.975489 0.000562882 0.617607 0.786486 0.000560677 0.617561 0.786523 0.000816844 0.89547 0.44512 0.000813496 0.89543 0.445202 0.000913382 0.999847 0.0174853 0.000907779 0.999844 0.0176391 0.000832487 0.910503 -0.413502 0.000825531 0.910583 -0.413326 0.000591207 0.644743 -0.764399 0.000582455 0.64493 -0.764241 0.194892 0.959545 -0.203203 0.923697 0.271932 -0.269884 0.382254 0.656977 -0.649818 0.130352 0.705731 -0.696385 0.608237 0.564998 -0.557516 0.79295 0.433692 -0.427949 0.991427 0.0930049 -0.0917732 0.194838 0.699696 -0.68736 0.194754 0.769813 -0.607831 0.194755 0.769813 -0.607831 0.194749 0.83538 -0.514017 0.194756 0.835379 -0.514016 0.194753 0.889894 -0.412504 0.194717 0.8899 -0.412508 0.194824 0.928895 -0.314955 0.362189 0.88572 -0.290379 0.195056 0.945605 -0.260356 0.194832 0.959556 -0.203208 0.555098 0.593604 -0.582667 0.55492 0.652913 -0.515528 0.554916 0.652915 -0.51553 0.554906 0.70853 -0.435964 0.554879 0.708545 -0.435975 0.554872 0.754787 -0.349877 0.554877 0.754784 -0.349875 0.554893 0.790522 -0.259169 0.554878 0.790532 -0.259173 0.55505 0.81377 -0.172332 0.555294 0.813613 -0.172286 0.831162 0.397328 -0.388974 0.831026 0.436555 -0.344697 0.831025 0.436557 -0.344698 0.831017 0.473749 -0.291502 0.831014 0.473752 -0.291504 0.83101 0.504674 -0.233938 0.831022 0.504658 -0.23393 0.831033 0.528544 -0.173281 0.831036 0.528539 -0.173279 0.831152 0.543983 -0.11519 0.831251 0.54384 -0.115151 0.980757 0.140512 -0.135545 0.980725 0.153354 -0.121086 0.980726 0.15335 -0.121082 0.980725 0.166415 -0.102397 0.980724 0.166417 -0.102398 0.980724 0.17728 -0.0821767 0.980723 0.177284 -0.0821787 0.980724 0.185673 -0.060872 0.980725 0.18567 -0.0608708 0.980742 0.191072 -0.0404572 0.980762 0.190976 -0.0404323 -0.614921 0.194016 0.76435 -0.998211 0.044275 0.0401818 -0.989443 0.134521 -0.053909 -0.957816 0.229046 -0.173569 -0.922152 0.298045 -0.246587 -0.839257 0.395243 -0.373405 -0.791523 0.441398 -0.422682 -0.651909 0.529306 -0.543 -0.606366 0.554537 -0.56992 -0.410944 0.62011 -0.668273 -0.379372 0.629531 -0.678062 -0.136271 0.660084 -0.738728 -0.126156 0.661118 -0.739599 -0.956563 0.0310106 0.28987 -0.977081 0.161367 0.138827 -0.971709 0.233083 0.0381284 -0.939873 0.330005 -0.0879569 -0.885087 0.411172 -0.21808 -0.825998 0.47199 -0.308146 -0.705 0.54649 -0.452022 -0.644175 0.575561 -0.503755 -0.449856 0.624328 -0.638627 -0.409032 0.631838 -0.658387 -0.146788 0.636076 -0.757536 -0.140177 0.635894 -0.75894 -0.888627 0.0676847 0.453609 -0.91499 0.146794 0.375824 -0.941374 0.281319 0.186213 -0.933751 0.338749 0.115576 -0.881246 0.461086 -0.103952 -0.854393 0.495382 -0.156874 -0.715135 0.585339 -0.382047 -0.685004 0.600139 -0.41304 -0.462698 0.639011 -0.614472 -0.443234 0.641734 -0.625877 -0.154365 0.615527 -0.77285 -0.15468 0.615556 -0.772764 -0.755317 0.059385 0.652664 -0.823525 0.188922 0.534898 -0.871181 0.3063 0.383698 -0.87864 0.397082 0.265176 -0.859265 0.508219 0.058107 -0.82887 0.558238 -0.0366797 -0.720478 0.635639 -0.277262 -0.679381 0.652829 -0.335048 -0.473758 0.668839 -0.572895 -0.447307 0.668701 -0.593932 -0.155165 0.601739 -0.783475 -0.160666 0.603183 -0.781253 -0.678903 0.122918 0.723866 -0.683128 0.15483 0.713697 -0.800502 0.384765 0.459514 -0.79675 0.407657 0.446099 -0.799989 0.586994 0.124319 -0.791659 0.600513 0.112516 -0.677257 0.698765 -0.230327 -0.668696 0.704553 -0.237596 -0.45096 0.702992 -0.549943 -0.44618 0.704154 -0.55235 -0.155603 0.599122 -0.785392 -0.157247 0.599151 -0.785043 -0.473945 0.162113 0.865503 -0.496365 0.0691059 0.865359 -0.694054 0.413431 0.589375 -0.706084 0.484122 0.51679 -0.724432 0.643925 0.246087 -0.710987 0.679621 0.180592 -0.630038 0.763674 -0.140905 -0.607576 0.772673 -0.183925 -0.424855 0.750449 -0.506286 -0.410386 0.747713 -0.522024 -0.142904 0.603553 -0.784412 -0.148989 0.60667 -0.780867 -0.344929 0.167779 0.923512 -0.360577 0.237517 0.901981 -0.467292 0.524298 0.711863 -0.468591 0.569641 0.675227 -0.503051 0.780888 0.370342 -0.49473 0.802586 0.333312 -0.44643 0.893921 -0.040069 -0.434944 0.897984 -0.0666963 -0.30574 0.840446 -0.447409 -0.298495 0.837354 -0.457972 -0.105168 0.62473 -0.773726 -0.108265 0.627437 -0.771104 -0.119939 0.218706 0.968392 -0.117407 0.241047 0.963386 -0.165739 0.609155 0.775539 -0.162389 0.623173 0.765039 -0.180151 0.880768 0.437942 -0.176534 0.887053 0.426582 -0.160743 0.986838 0.0177089 -0.157645 0.987454 0.00905639 -0.110473 0.905225 -0.41032 -0.108831 0.903743 -0.41401 -0.0381799 0.644887 -0.763324 -0.0387973 0.645957 -0.762387 0.554765 0.809077 -0.193985 0.828281 0.53072 -0.179684 0.975207 0.173083 -0.137892 0.967931 0.203179 -0.14774 0.945142 0.186097 -0.268468 0.942704 0.19087 -0.27364 0.892948 0.167447 -0.417859 0.884123 0.198336 -0.423072 0.809284 0.183883 -0.557895 0.80647 0.187608 -0.560722 0.743794 0.176572 -0.644665 0.733366 -0.0904854 -0.673786 0.643166 0.187972 -0.742296 0.586429 0.18356 -0.788927 0.584308 0.185977 -0.789934 0.541928 0.81717 -0.196334 0.528763 0.809243 -0.255999 0.525779 0.810567 -0.257948 0.503765 0.797721 -0.331453 0.487985 0.808626 -0.328625 0.447916 0.802362 -0.394444 0.444725 0.803769 -0.395189 0.397721 0.793804 -0.460101 0.386102 0.803487 -0.453139 0.323493 0.800332 -0.504798 0.320999 0.801527 -0.504494 0.251514 0.794425 -0.552838 0.24602 0.800946 -0.545857 0.165613 0.800741 -0.575662 0.164451 0.801405 -0.575071 0.0294696 0.962745 -0.2688 0.0580232 0.963773 -0.260334 0.0591494 0.963504 -0.261077 0.0846843 0.963994 -0.252081 0.0905399 0.961262 -0.260341 0.111834 0.963051 -0.245 0.114152 0.962634 -0.245571 0.131453 0.963853 -0.231749 0.142452 0.960413 -0.239404 0.154794 0.962735 -0.221767 0.157425 0.96237 -0.221497 0.166941 0.964123 -0.206393 0.178882 0.961278 -0.209632 0.183743 0.963958 -0.192412 0.185555 0.963784 -0.191546 0.188506 0.965648 -0.178857 0.195015 0.964443 -0.17838 0.0285807 0.963663 -0.265588 0.0632534 0.867609 -0.493207 0.0746104 0.796563 -0.599934 0.086315 0.760059 -0.644096 0.112679 0.577134 -0.808838 0.814686 0.549512 -0.185269 0.794886 0.536741 -0.282957 0.791577 0.539805 -0.286386 0.753313 0.518902 -0.404054 0.738275 0.540088 -0.404048 0.675817 0.530165 -0.512051 0.67254 0.532786 -0.513643 0.595707 0.51688 -0.614792 0.585655 0.533042 -0.610634 0.48843 0.528193 -0.694585 0.486046 0.53008 -0.69482 0.376852 0.519055 -0.767179 0.372365 0.528822 -0.762687 0.249424 0.528564 -0.811423 0.248346 0.5295 -0.811144 0.113177 0.522354 -0.845185 0.127529 0.416846 -0.899986 0.472645 0.177079 -0.863278 0.464251 0.00573603 -0.885685 0.344399 0.185471 -0.920321 0.299216 0.184167 -0.936244 0.298223 0.185273 -0.936342 0.141091 0.179694 -0.973552 0.140584 0.182752 -0.973056 -0.180937 0.962922 -0.200106 -0.5468 0.819749 -0.170355 -0.827877 0.549178 -0.114119 -0.980357 0.193106 -0.0401199 -0.182104 0.9627 -0.200115 -0.182296 0.949089 -0.2569 -0.36846 0.884679 -0.285623 -0.547358 0.819386 -0.17031 -0.54713 0.796572 -0.257143 -0.548136 0.795929 -0.256991 -0.548138 0.759954 -0.349305 -0.549263 0.759258 -0.349051 -0.549421 0.715837 -0.430945 -0.550452 0.715223 -0.430649 -0.550318 0.663662 -0.506659 -0.551412 0.663052 -0.506267 -0.183735 0.931954 -0.312576 -0.18363 0.893167 -0.410528 -0.185505 0.892811 -0.410458 -0.185578 0.84185 -0.506802 -0.187225 0.841539 -0.506714 -0.187164 0.780805 -0.596081 -0.189003 0.780474 -0.595934 -0.188997 0.705521 -0.683023 -0.125928 0.714728 -0.687972 -0.378838 0.664204 -0.644449 -0.551453 0.600702 -0.57884 -0.605864 0.571558 -0.553399 -0.791622 0.438985 -0.425002 -0.828035 0.548946 -0.114085 -0.82788 0.533782 -0.17231 -0.82831 0.533167 -0.172148 -0.828313 0.509066 -0.233988 -0.828755 0.508456 -0.233746 -0.828862 0.479301 -0.288547 -0.829268 0.478766 -0.288268 -0.829178 0.444307 -0.339197 -0.829626 0.443757 -0.338822 -0.82967 0.402445 -0.386892 -0.923224 0.275379 -0.268001 -0.980379 0.192998 -0.0401028 -0.980357 0.187697 -0.0605883 -0.9804 0.187489 -0.0605316 -0.9804 0.179014 -0.0822776 -0.980454 0.178765 -0.0821766 -0.98047 0.168495 -0.101432 -0.98052 0.168273 -0.101313 -0.980507 0.156176 -0.119226 -0.980555 0.155979 -0.11909 -0.980574 0.142298 -0.135 -0.99136 0.0942365 -0.0912393 0.00407221 0.869375 -0.494136 0.00357587 0.762986 -0.646406 0.00570228 0.677258 -0.735724 0.00272095 0.581005 -0.813896 0.00197019 0.420512 -0.907285 0.00304581 0.245469 -0.9694 0.000866117 0.184909 -0.982755 0.00943666 0.94577 -0.3247 0.00632398 0.945796 -0.324701 0.00452063 0.964051 -0.265679 0.00244801 0.245543 -0.969383 0.00245021 0.245474 -0.9694 0.0057926 0.581177 -0.813757 0.00422162 0.677268 -0.735724 0.00761072 0.7632 -0.646117 0.00942288 0.94589 -0.324351 -0.842101 0.197581 -0.501824 -0.0141975 0.945868 -0.324241 -0.0428865 0.762787 -0.645226 -0.0748285 0.580232 -0.811006 -0.0203755 0.964217 -0.26433 -0.0307387 0.964559 -0.26207 -0.0302982 0.964297 -0.263085 -0.0590109 0.965052 -0.255327 -0.0616648 0.962595 -0.263833 -0.0870828 0.964771 -0.248262 -0.0869805 0.964184 -0.250568 -0.0466327 0.799448 -0.598922 -0.114753 0.802877 -0.584995 -0.114167 0.802194 -0.586047 -0.199652 0.803066 -0.561448 -0.202172 0.796614 -0.569677 -0.279103 0.804525 -0.524253 -0.278783 0.803079 -0.526635 -0.0726815 0.525101 -0.84793 -0.183031 0.530843 -0.827469 -0.182257 0.529731 -0.828352 -0.311834 0.531011 -0.7879 -0.313472 0.520694 -0.794111 -0.432457 0.532804 -0.727393 -0.431687 0.530445 -0.729572 -0.614428 0.191094 -0.765481 -0.524534 0.184222 -0.83122 -0.52595 0.187241 -0.829649 -0.380822 0.175107 -0.907916 -0.380771 0.18847 -0.905258 -0.225183 0.184469 -0.956694 -0.2262 0.185942 -0.956169 -0.101143 0.181 -0.978268 -0.109301 0.245403 -0.96324 -0.71865 0.18154 -0.671257 -0.683657 -0.084341 -0.724914 -0.546363 0.519457 -0.657003 -0.540037 0.536138 -0.64878 -0.357773 0.796951 -0.48669 -0.349609 0.806823 -0.476245 -0.116724 0.962258 -0.245836 -0.108857 0.965755 -0.235517 -0.766932 0.184482 -0.614639 -0.768038 0.189401 -0.611755 -0.635824 0.532827 -0.558411 -0.635673 0.536381 -0.555172 -0.414435 0.805696 -0.423198 -0.413644 0.807759 -0.420028 -0.134157 0.964351 -0.2281 -0.133276 0.965098 -0.225441 -0.907422 0.185644 -0.37699 -0.886083 0.0098455 -0.463423 -0.722508 0.521635 -0.45374 -0.7105 0.543501 -0.446986 -0.476503 0.80102 -0.36237 -0.462919 0.812542 -0.354234 -0.158098 0.963326 -0.216813 -0.147363 0.966552 -0.209909 -0.924822 0.18643 -0.331584 -0.924907 0.192874 -0.327637 -0.773251 0.539202 -0.333683 -0.771782 0.543491 -0.330105 -0.507518 0.812484 -0.286872 -0.505659 0.814643 -0.284019 -0.166776 0.965923 -0.197938 -0.165428 0.966523 -0.196132 -0.970562 0.168756 -0.171848 -0.962863 0.207972 -0.172172 -0.822507 0.529716 -0.207085 -0.806357 0.55473 -0.205093 -0.545638 0.811095 -0.210722 -0.529806 0.822263 -0.20782 -0.181029 0.966599 -0.181427 -0.172313 0.968574 -0.179368 0.843705 0.195075 0.500107 0.0846967 0.578791 0.811066 0.0478251 0.868366 0.493613 0.022284 0.963818 0.265626 0.0554145 0.761766 0.645478 0.0758137 0.41916 0.904742 0.0221936 0.96331 0.267473 0.0459993 0.963903 0.262252 0.0455637 0.963655 0.263235 0.0742932 0.963977 0.2554 0.0769171 0.961495 0.263841 0.102311 0.963288 0.248211 0.102196 0.962701 0.250524 0.0595928 0.799002 0.598368 0.128185 0.801459 0.584151 0.127702 0.80092 0.584996 0.212771 0.800499 0.560294 0.214935 0.794773 0.567573 0.291382 0.801489 0.522218 0.291059 0.800148 0.524451 0.0886605 0.525755 0.846003 0.192869 0.52948 0.826107 0.192318 0.528725 0.826719 0.321156 0.528041 0.78615 0.322378 0.519673 0.791209 0.44059 0.529956 0.724588 0.439905 0.527976 0.726447 0.61731 0.1889 0.763705 0.52835 0.183459 0.828969 0.529555 0.185924 0.827649 0.385222 0.175946 0.905896 0.385316 0.185923 0.903861 0.230601 0.184304 0.955435 0.231223 0.185164 0.955118 0.105542 0.182043 0.97761 0.105769 0.183634 0.977288 0.720659 0.180461 0.669391 0.683774 -0.0894784 0.724187 0.55301 0.516768 0.653552 0.547404 0.531985 0.646019 0.368958 0.793353 0.484211 0.361303 0.802807 0.4743 0.131763 0.960311 0.245848 0.123905 0.963935 0.235536 0.769071 0.183155 0.612359 0.770107 0.187646 0.609692 0.641776 0.529003 0.555229 0.641655 0.532329 0.552182 0.425055 0.801311 0.420986 0.424318 0.803268 0.417989 0.149023 0.96212 0.22829 0.148136 0.962887 0.225621 0.908319 0.183841 0.375711 0.886802 0.00465006 0.462125 0.727168 0.517467 0.45106 0.715784 0.538538 0.444556 0.486075 0.796062 0.360578 0.47295 0.807421 0.35269 0.172695 0.960712 0.217274 0.161973 0.964103 0.210406 0.925643 0.184641 0.330291 0.92574 0.19087 0.326456 0.777299 0.534431 0.331949 0.775895 0.538602 0.328474 0.516614 0.807058 0.28595 0.514816 0.809185 0.28317 0.18117 0.963141 0.19884 0.179843 0.963755 0.19706 0.971046 0.166489 0.171323 0.963446 0.205642 0.171704 0.825967 0.524537 0.206494 0.810057 0.549501 0.204586 0.554166 0.805278 0.210779 0.538568 0.816514 0.207964 0.195002 0.963623 0.182769 0.186541 0.965668 0.180798 0.00407221 0.869377 0.494133 0.00943782 0.94589 0.324351 0.00419469 0.420668 0.907205 0.000553093 0.245487 0.9694 0.00184424 0.184983 0.98274 0.00452063 0.964051 0.265679 0.00632396 0.945796 0.3247 0.0094217 0.94577 0.324699 0.00761072 0.7632 0.646117 0.00357587 0.762986 0.646406 0.00570228 0.677258 0.735724 0.00422162 0.677268 0.735724 0.00579264 0.581174 0.813759 0.000866128 0.184912 0.982755 0.00304574 0.245469 0.9694 0.00197016 0.420506 0.907288 0.00272095 0.581005 0.813896 0.194898 0.959725 0.202344 0.555306 0.813757 0.171565 0.831259 0.543929 0.114669 0.980763 0.191006 0.040264 0.194816 0.959742 0.202343 0.195021 0.945271 0.261589 0.403428 0.86977 0.284159 0.194883 0.928124 0.317185 0.19475 0.889767 0.41278 0.194724 0.889772 0.412781 0.1948 0.838514 0.508869 0.194811 0.838512 0.508868 0.194748 0.777551 0.597903 0.194742 0.777552 0.597904 0.194738 0.702591 0.684428 0.194763 0.702587 0.684426 0.555101 0.813894 0.171583 0.554879 0.790797 0.258358 0.554853 0.790815 0.258362 0.554857 0.754688 0.350113 0.554885 0.754671 0.350107 0.555038 0.71112 0.431557 0.555054 0.71111 0.431552 0.554923 0.659473 0.507106 0.554907 0.659482 0.507112 0.554896 0.595908 0.580504 0.554918 0.595896 0.580494 0.831158 0.54408 0.114692 0.83101 0.528755 0.172746 0.831011 0.528753 0.172746 0.831013 0.504596 0.234092 0.831013 0.504597 0.234093 0.831116 0.475404 0.288509 0.831117 0.475403 0.288508 0.83103 0.440938 0.339062 0.831029 0.440939 0.339062 0.831022 0.398436 0.388138 0.831014 0.398446 0.388146 0.980744 0.191098 0.0402791 0.980723 0.185743 0.0606831 0.980723 0.185742 0.0606828 0.980723 0.177256 0.0822325 0.980723 0.177259 0.0822339 0.980738 0.166986 0.101339 0.980737 0.166987 0.101339 0.980725 0.154895 0.119107 0.980726 0.154891 0.119105 0.980724 0.139963 0.136345 0.980724 0.139966 0.136347 -0.181042 0.967457 0.176782 -0.546257 0.815026 0.193223 -0.82491 0.536087 0.179262 -0.974856 0.175489 0.13733 -0.967579 0.205265 0.147165 -0.945009 0.188002 0.267608 -0.942489 0.192911 0.272947 -0.892714 0.168979 0.417742 -0.883389 0.201028 0.423334 -0.8086 0.185417 0.558379 -0.805542 0.189383 0.561459 -0.742618 0.17742 0.645787 -0.734565 -0.0855005 0.673129 -0.641196 0.189805 0.743533 -0.584895 0.184554 0.789834 -0.582362 0.187357 0.791045 -0.174369 0.968591 0.177276 -0.171369 0.966659 0.19027 -0.16951 0.966812 0.191154 -0.164543 0.96401 0.208832 -0.152542 0.966677 0.205588 -0.142807 0.964747 0.221065 -0.140204 0.965066 0.221337 -0.127733 0.962536 0.239184 -0.116749 0.965785 0.23158 -0.0993183 0.964292 0.245515 -0.0969426 0.96468 0.244937 -0.0757218 0.96257 0.260241 -0.0697863 0.965225 0.251935 -0.0443581 0.964346 0.2609 -0.043183 0.964609 0.260125 -0.533345 0.822975 0.195592 -0.520183 0.814886 0.255676 -0.517123 0.816207 0.257662 -0.494927 0.802961 0.332115 -0.478651 0.813936 0.329245 -0.438259 0.807059 0.395707 -0.434941 0.80847 0.396488 -0.387688 0.797746 0.461844 -0.375346 0.807768 0.454563 -0.312501 0.803649 0.506449 -0.309864 0.804865 0.506139 -0.240347 0.796686 0.554549 -0.234129 0.803854 0.546811 -0.153757 0.802416 0.576617 -0.152404 0.803165 0.575933 -0.0148203 0.963156 0.268535 -0.0305537 0.945543 0.324059 -0.0626493 0.796954 0.600782 -0.0746327 0.761529 0.64382 -0.103951 0.578954 0.808706 -0.811235 0.554724 0.184878 -0.791533 0.541747 0.282818 -0.788144 0.544844 0.28631 -0.749684 0.523384 0.405022 -0.733962 0.545154 0.405101 -0.671261 0.53428 0.513765 -0.667733 0.537034 0.515486 -0.590707 0.519979 0.616999 -0.579616 0.537383 0.612589 -0.482272 0.531029 0.696722 -0.479495 0.533161 0.697011 -0.370384 0.520478 0.769362 -0.36485 0.532087 0.764047 -0.241999 0.529935 0.812777 -0.240517 0.531187 0.812399 -0.105366 0.521982 0.846423 -0.121084 0.418887 0.899929 -0.470571 0.176771 0.864474 -0.464573 0.00941769 0.885485 -0.341668 0.186492 0.921132 -0.296952 0.184513 0.936896 -0.295443 0.186149 0.93705 -0.138707 0.178227 0.974164 -0.137483 0.18493 0.973087 0.615427 0.193502 -0.764073 0.195077 0.654707 0.730277 0.139026 0.663552 0.735099 0.413858 0.616316 0.669983 0.555428 0.577555 0.598273 0.653569 0.526606 0.54363 0.830655 0.406616 0.380362 0.998246 0.0440346 -0.0395591 0.978836 0.177835 0.101267 0.957901 0.229085 0.173049 0.839592 0.396862 0.370926 0.956848 0.0305472 -0.288978 0.977429 0.160634 -0.13722 0.972119 0.231533 -0.0370997 0.940355 0.328234 0.0894091 0.885913 0.40881 0.219162 0.826974 0.469467 0.309378 0.7065 0.543679 0.453068 0.645955 0.572672 0.504767 0.452163 0.621573 0.639684 0.41181 0.62907 0.659306 0.149811 0.633919 0.758751 0.143814 0.633769 0.760036 0.888787 0.0668691 -0.453416 0.915605 0.146419 -0.374471 0.942002 0.279584 -0.185649 0.934466 0.337264 -0.114136 0.882436 0.458632 0.104704 0.855462 0.493093 0.158254 0.716908 0.58258 0.38294 0.686644 0.597437 0.414233 0.465025 0.63639 0.615435 0.445546 0.639124 0.626904 0.157015 0.613503 0.773926 0.15757 0.613553 0.773773 0.755307 0.0588908 -0.65272 0.824045 0.188308 -0.534313 0.871838 0.304869 -0.383346 0.879583 0.3956 -0.264261 0.860572 0.506077 -0.0574687 0.830278 0.556075 0.037682 0.722329 0.633166 0.278106 0.681247 0.650363 0.336052 0.475938 0.666464 0.573854 0.449596 0.666354 0.59484 0.157473 0.599906 0.78442 0.163159 0.601388 0.78212 0.679043 0.122361 -0.723829 0.683504 0.154443 -0.713421 0.801401 0.383364 -0.459116 0.797758 0.406391 -0.445453 0.801545 0.585019 -0.123603 0.793261 0.598558 -0.11165 0.679315 0.696486 0.231167 0.670711 0.702307 0.23856 0.453189 0.700848 0.550847 0.448359 0.702018 0.553304 0.157725 0.597492 0.78621 0.159378 0.597523 0.785853 0.474357 0.161633 -0.865367 0.496113 0.0686369 -0.865541 0.69503 0.412173 -0.589107 0.70735 0.482964 -0.516141 0.726206 0.642143 -0.245515 0.712837 0.677928 -0.179659 0.632299 0.761663 0.141661 0.609787 0.770696 0.184897 0.427211 0.748557 0.507102 0.412639 0.745818 0.522958 0.144951 0.602127 0.785132 0.151001 0.605212 0.781612 0.345267 0.167258 -0.92348 0.361273 0.237384 -0.901738 0.468833 0.523309 -0.711578 0.470312 0.568941 -0.674621 0.505469 0.779578 -0.36981 0.497168 0.801437 -0.33245 0.449251 0.892474 0.0407762 0.437678 0.896582 0.0676725 0.308432 0.839082 0.448119 0.301044 0.835943 0.458881 0.107188 0.623669 0.774305 0.110178 0.62627 0.771781 0.120608 0.218425 -0.968372 0.118101 0.241216 -0.963259 0.167653 0.608827 -0.775385 0.164279 0.623152 -0.764653 0.182925 0.880345 -0.437643 0.179229 0.886811 -0.425962 0.163834 0.986337 -0.0172491 0.160633 0.986979 -0.00830072 0.113282 0.904631 0.410864 0.111551 0.903075 0.414744 0.0401597 0.644222 0.763784 0.040709 0.645168 0.762956 -0.180929 0.962687 0.201244 -0.946494 0.230411 0.225967 -0.190729 0.700875 0.687312 -0.552551 0.595085 0.583576 -0.83012 0.398103 0.390404 -0.991366 0.0936165 0.0918128 -0.189247 0.701026 0.687567 -0.189187 0.772756 0.605852 -0.187381 0.772977 0.606131 -0.187375 0.838427 0.511793 -0.185489 0.838687 0.512053 -0.185487 0.892911 0.410249 -0.183647 0.89319 0.410469 -0.183767 0.931157 0.314922 -0.37524 0.881667 0.286111 -0.182313 0.94813 0.260406 -0.182109 0.962485 0.201147 -0.551651 0.595473 0.584032 -0.551525 0.656453 0.514674 -0.550445 0.656978 0.515161 -0.550436 0.712602 0.434993 -0.549292 0.713212 0.435438 -0.54929 0.75932 0.348875 -0.548159 0.759969 0.349241 -0.548172 0.795536 0.258127 -0.547166 0.796146 0.258382 -0.547339 0.819212 0.171205 -0.546783 0.819562 0.171309 -0.82976 0.398463 0.390802 -0.829675 0.439321 0.344436 -0.829225 0.439824 0.344877 -0.829218 0.477066 0.291215 -0.828761 0.477624 0.291599 -0.828759 0.508501 0.233635 -0.828323 0.509072 0.233936 -0.828332 0.532887 0.172906 -0.827912 0.533467 0.17313 -0.82803 0.548828 0.114691 -0.827866 0.549063 0.114753 -0.980597 0.141514 0.135659 -0.980564 0.154403 0.12105 -0.980509 0.154612 0.12123 -0.980508 0.167704 0.102367 -0.980456 0.16792 0.102513 -0.980456 0.178776 0.0821354 -0.980401 0.179016 0.0822598 -0.980402 0.187389 0.0607996 -0.980358 0.187594 0.0608769 -0.980376 0.192972 0.0403189 -0.980356 0.193067 0.0403434 0.000200548 0.220066 -0.975485 0.000199898 0.220084 -0.975481 0.000563323 0.617561 -0.786523 0.00056073 0.617618 -0.786478 0.000816807 0.89543 -0.445202 0.000813534 0.89547 -0.44512 0.000913378 0.999844 -0.0176394 0.000907773 0.999847 -0.0174853 0.000832814 0.910586 0.41332 0.000825204 0.9105 0.413508 0.000590893 0.64492 0.76425 0.000582769 0.644753 0.764391 0.000422992 0.220028 -0.975493 0.000421669 0.220065 -0.975485 0.0011891 0.617445 -0.786613 0.00118403 0.61756 -0.786523 0.00172471 0.895327 -0.445405 0.00171663 0.895429 -0.445202 0.00192713 0.999837 -0.0179477 0.00191593 0.999843 -0.0176394 0.00175763 0.910753 0.412948 0.00174245 0.910584 0.41332 0.00124875 0.645301 0.763928 0.00122988 0.644919 0.76425 -0.0288495 0.645075 0.763574 -0.119359 0.992691 -0.0178153 -0.133259 0.887409 -0.441303 -0.121455 0.613058 -0.780646 -0.0859229 0.219417 -0.97184 -0.120896 0.992583 -0.0128019 -0.407653 0.912819 0.0240896 -0.406314 0.912048 0.055474 -0.604407 0.786418 0.127434 -0.595456 0.786086 0.165833 -0.699392 0.677168 0.22868 -0.67166 0.682524 0.288157 -0.723225 0.599888 0.34217 -0.682952 0.610926 0.400432 -0.702592 0.562126 0.436324 -0.663751 0.57427 0.479217 -0.136125 0.89038 -0.434389 -0.4561 0.801078 -0.387618 -0.462986 0.816424 -0.345102 -0.692005 0.671499 -0.264987 -0.694818 0.688946 -0.206354 -0.822074 0.554657 -0.128642 -0.809219 0.586563 -0.0332881 -0.879934 0.473384 0.0403063 -0.849089 0.510038 0.137507 -0.879664 0.43476 0.192808 -0.84397 0.465969 0.265683 -0.12585 0.620482 -0.774057 -0.419411 0.542489 -0.727874 -0.440085 0.580192 -0.685349 -0.657902 0.440237 -0.611029 -0.685338 0.482837 -0.545142 -0.814663 0.346195 -0.465267 -0.841074 0.413236 -0.349043 -0.920456 0.285777 -0.266632 -0.924771 0.354176 -0.13913 -0.962513 0.261646 -0.0714887 -0.948516 0.315402 0.0289752 -0.0919427 0.231484 -0.968484 -0.302302 0.179323 -0.936193 -0.341366 0.241033 -0.9085 -0.507281 0.131923 -0.851623 -0.568717 0.199402 -0.797997 -0.678357 0.0841612 -0.729897 -0.763736 0.184887 -0.618485 -0.839934 0.0618035 -0.539158 -0.902477 0.15992 -0.399952 -0.942515 0.061516 -0.328454 -0.96829 0.136042 -0.209541 -0.028663 0.645862 0.762916 -0.0982873 0.628717 0.771398 -0.0997105 0.632105 0.768441 -0.14045 0.605149 0.783625 -0.14411 0.608992 0.779975 -0.154281 0.598469 0.78615 -0.160098 0.601633 0.782564 -0.154662 0.610445 0.776812 -0.156643 0.611057 0.775933 -0.149009 0.630345 0.76188 -0.145958 0.62979 0.762929 -0.139725 0.655239 0.742387 -0.190971 0.655666 0.730502 -0.988195 0.147357 0.0419011 -0.991629 0.0313183 -0.125267 -0.94398 0.272453 0.186204 -0.970272 0.216858 0.107443 -0.828914 0.421175 0.368122 -0.86065 0.393479 0.323196 -0.552964 0.578343 0.599792 -0.672788 0.5367 0.509224 -0.426819 0.618471 0.659788 -0.423905 0.630559 0.650154 -0.449959 0.629843 0.633115 -0.443564 0.645897 0.621343 -0.470353 0.647919 0.59914 -0.44548 0.687985 0.572909 -0.464593 0.693192 0.551034 -0.401901 0.758345 0.513215 -0.409401 0.763746 0.499082 -0.278214 0.848528 0.450108 -0.281232 0.854421 0.436891 -0.0827612 0.906744 0.413481 -0.0822383 0.907704 0.411474 0.0288495 0.645075 -0.763574 0.0822386 0.907705 -0.411472 0.119359 0.992691 0.0178153 0.133258 0.887409 0.441303 0.121457 0.613061 0.780644 0.0859197 0.219398 0.971845 0.028663 0.645862 -0.762916 0.0982868 0.628717 -0.771398 0.0997057 0.632095 -0.76845 0.140441 0.605141 -0.783633 0.144109 0.608993 -0.779974 0.154281 0.598468 -0.786151 0.160094 0.60163 -0.782567 0.154656 0.610445 -0.776813 0.156627 0.611053 -0.77594 0.148993 0.630343 -0.761885 0.145976 0.629793 -0.762923 0.139743 0.65524 -0.742383 0.126138 0.654824 -0.745181 0.0827615 0.906745 -0.413479 0.281235 0.854424 -0.436882 0.278217 0.848531 -0.450101 0.409406 0.763748 -0.499076 0.401898 0.75834 -0.513224 0.464586 0.69319 -0.551042 0.4455 0.68799 -0.572886 0.470378 0.647919 -0.599121 0.443592 0.645897 -0.621323 0.449988 0.629842 -0.633095 0.423887 0.630559 -0.650165 0.42623 0.620887 -0.657897 0.379375 0.628464 -0.67905 0.120897 0.992583 0.0127978 0.407651 0.91282 -0.0241036 0.406311 0.912048 -0.0554891 0.604402 0.786418 -0.127457 0.595456 0.786087 -0.16583 0.699392 0.677169 -0.228676 0.671658 0.682526 -0.288156 0.723225 0.599888 -0.34217 0.682934 0.61093 -0.400457 0.702572 0.562133 -0.436347 0.663774 0.574263 -0.479193 0.674063 0.53078 -0.513724 0.606312 0.558295 -0.566297 0.136126 0.890383 0.434382 0.4561 0.80108 0.387612 0.462986 0.816427 0.345097 0.692006 0.6715 0.264983 0.694818 0.688946 0.206354 0.822073 0.55466 0.128644 0.809212 0.586575 0.0332586 0.879925 0.473397 -0.0403396 0.849089 0.510039 -0.137507 0.879663 0.434763 -0.192806 0.843969 0.465972 -0.265681 0.86065 0.393478 -0.323196 0.791133 0.449274 -0.415043 0.125848 0.620479 0.77406 0.419408 0.542478 0.727883 0.440079 0.580173 0.685368 0.657893 0.440215 0.611054 0.685339 0.482829 0.545149 0.814661 0.346191 0.465274 0.841069 0.41322 0.349074 0.920454 0.285755 0.266663 0.924773 0.354174 0.139128 0.962512 0.261649 0.0714911 0.948506 0.315427 -0.0290143 0.969566 0.22179 -0.103683 0.921281 0.30906 -0.236059 0.0919496 0.231486 0.968483 0.302303 0.179333 0.93619 0.341376 0.241058 0.90849 0.5073 0.131947 0.851608 0.568715 0.199404 0.797998 0.678355 0.0841629 0.729898 0.763753 0.184914 0.618456 0.839953 0.0618287 0.539125 0.902474 0.159916 0.399959 0.942513 0.0615114 0.32846 0.96829 0.136041 0.20954 0.991629 0.0313185 0.125267 0.988196 0.147357 -0.0419002 -0.000200533 0.22005 0.975489 -0.000199297 0.220084 0.975481 -0.000562839 0.617561 0.786523 -0.000560719 0.617608 0.786486 -0.000816806 0.89543 0.445202 -0.000813534 0.89547 0.44512 -0.000913378 0.999844 0.0176392 -0.000907784 0.999847 0.0174854 -0.000832557 0.910583 -0.413326 -0.00082546 0.910503 -0.413502 -0.000591372 0.64493 -0.764241 -0.00058229 0.644743 -0.764399 -0.00042296 0.220012 0.975497 -0.000421639 0.220049 0.975489 -0.0011891 0.617445 0.786613 -0.00118403 0.61756 0.786523 -0.00172471 0.895327 0.445405 -0.00171663 0.895429 0.445202 -0.00192713 0.999837 0.0179477 -0.00191591 0.999843 0.0176392 -0.00175789 0.910753 -0.412948 -0.00174245 0.910581 -0.413326 -0.00124875 0.645301 -0.763928 -0.00123037 0.644929 -0.764241 0.180929 0.962687 -0.201243 0.378954 0.659927 -0.648761 0.125994 0.708281 -0.694596 0.791728 0.436144 -0.427721 0.606029 0.567896 -0.556976 0.923252 0.273515 -0.269806 0.991338 0.0960751 -0.089547 0.189275 0.702582 -0.685969 0.189194 0.772755 -0.605851 0.187374 0.772978 -0.606133 0.187368 0.838428 -0.511793 0.185491 0.838687 -0.512053 0.18549 0.892911 -0.410248 0.18365 0.89319 -0.410469 0.183751 0.931901 -0.312722 0.348696 0.89147 -0.289298 0.182316 0.948741 -0.258169 0.182108 0.962485 -0.201146 0.551704 0.597018 -0.582402 0.551525 0.656452 -0.514675 0.550449 0.656975 -0.515159 0.55044 0.7126 -0.434991 0.549292 0.713213 -0.435437 0.54929 0.75932 -0.348875 0.548159 0.759969 -0.349241 0.548172 0.795536 -0.258128 0.547167 0.796145 -0.258383 0.54734 0.819212 -0.171204 0.546766 0.819573 -0.171311 0.829812 0.399967 -0.389151 0.829675 0.43932 -0.344437 0.829225 0.439823 -0.344878 0.829217 0.477067 -0.291214 0.828743 0.477647 -0.291613 0.828741 0.508525 -0.233646 0.828306 0.509096 -0.233947 0.828315 0.532912 -0.172915 0.82793 0.533443 -0.17312 0.828048 0.548802 -0.114685 0.827866 0.549063 -0.114755 0.980569 0.140058 -0.13736 0.980557 0.154432 -0.121075 0.980509 0.154612 -0.12123 0.980508 0.167704 -0.102367 0.980456 0.167919 -0.102513 0.980456 0.178775 -0.0821351 0.980401 0.179016 -0.0822599 0.980402 0.18739 -0.060798 0.980351 0.187629 -0.0608881 0.980368 0.193008 -0.040328 0.980356 0.193067 -0.0403434 -0.615419 0.193493 0.764081 -0.154051 0.622877 -0.767002 -0.998247 0.0440301 0.0395567 -0.989534 0.133652 -0.0544039 -0.958039 0.227701 -0.174106 -0.922619 0.296243 -0.24701 -0.840021 0.39308 -0.373968 -0.792751 0.438839 -0.423043 -0.653554 0.526612 -0.543642 -0.608601 0.551594 -0.570394 -0.413685 0.617327 -0.669157 -0.382653 0.62666 -0.678877 -0.190708 0.6386 -0.745534 -0.956858 0.0305803 0.288941 -0.977429 0.160632 0.137223 -0.97212 0.231532 0.0371003 -0.940369 0.328205 -0.0893694 -0.885914 0.408807 -0.219164 -0.82697 0.469468 -0.309386 -0.7065 0.543678 -0.453069 -0.64594 0.572677 -0.50478 -0.452163 0.621572 -0.639685 -0.411795 0.629071 -0.659314 -0.143861 0.633462 -0.760283 -0.139988 0.65775 -0.740114 -0.130514 0.658749 -0.740956 -0.888803 0.0668979 0.45338 -0.915616 0.146449 0.374432 -0.942002 0.279584 0.185649 -0.934466 0.337262 0.114138 -0.882435 0.458633 -0.104706 -0.855462 0.493093 -0.158254 -0.716913 0.582578 -0.382934 -0.686644 0.597437 -0.414233 -0.46504 0.636391 -0.615422 -0.445545 0.639127 -0.626902 -0.156992 0.613501 -0.773932 -0.15757 0.613553 -0.773773 -0.755315 0.0589005 0.652709 -0.82406 0.188338 0.534279 -0.871837 0.304869 0.383346 -0.879583 0.3956 0.264261 -0.860572 0.506077 0.0574687 -0.830278 0.556075 -0.0376827 -0.722329 0.633166 -0.278106 -0.681251 0.650361 -0.336047 -0.475961 0.666465 -0.573834 -0.449611 0.666355 -0.594828 -0.157468 0.599904 -0.784422 -0.163138 0.601381 -0.782129 -0.679045 0.122342 0.72383 -0.68351 0.154452 0.713414 -0.801401 0.383364 0.459116 -0.797758 0.406391 0.445453 -0.801549 0.585008 0.123628 -0.793252 0.598569 0.111657 -0.679303 0.696499 -0.231164 -0.670703 0.702317 -0.238554 -0.453183 0.700855 -0.550843 -0.448382 0.702018 -0.553286 -0.157725 0.597484 -0.786216 -0.159377 0.597515 -0.785859 -0.474357 0.161633 0.865367 -0.496113 0.0686369 0.865541 -0.695026 0.412164 0.589118 -0.707348 0.482966 0.516142 -0.726202 0.642155 0.245492 -0.712842 0.677917 0.179679 -0.6323 0.761661 -0.141664 -0.609788 0.770695 -0.184901 -0.427212 0.748556 -0.507103 -0.41264 0.745817 -0.522959 -0.144961 0.602134 -0.785125 -0.150995 0.60521 -0.781615 -0.345268 0.167258 0.92348 -0.361274 0.237384 0.901737 -0.468836 0.523321 0.711567 -0.470314 0.568936 0.674623 -0.505472 0.779573 0.369815 -0.497166 0.801445 0.332434 -0.449252 0.892474 -0.0407763 -0.437677 0.896582 -0.0676737 -0.308435 0.839085 -0.448112 -0.301043 0.835944 -0.45888 -0.107181 0.623663 -0.77431 -0.110187 0.626278 -0.771774 -0.120609 0.218421 0.968373 -0.118101 0.241216 0.963259 -0.167652 0.608822 0.77539 -0.164275 0.623157 0.764649 -0.182923 0.880345 0.437643 -0.179229 0.886808 0.425969 -0.163834 0.986337 0.0172546 -0.160631 0.98698 0.00830093 -0.113282 0.904633 -0.410861 -0.111552 0.903077 -0.414738 -0.0401576 0.644213 -0.763791 -0.0407069 0.645159 -0.762963 0.54624 0.815038 -0.193223 0.82491 0.536088 -0.179257 0.974857 0.17549 -0.137324 0.96757 0.205301 -0.14717 0.944994 0.188031 -0.26764 0.942504 0.192881 -0.272914 0.89272 0.168947 -0.41774 0.883387 0.201027 -0.423338 0.808599 0.185415 -0.55838 0.805563 0.189355 -0.561439 0.742624 0.177391 -0.645788 0.734565 -0.0855326 -0.673125 0.64119 0.189803 -0.743539 0.584896 0.184552 -0.789833 0.582381 0.187335 -0.791036 0.533345 0.822975 -0.195589 0.520179 0.814884 -0.255691 0.517118 0.816205 -0.257678 0.494927 0.802961 -0.332115 0.478651 0.813935 -0.329245 0.43826 0.807059 -0.395707 0.43494 0.80847 -0.396488 0.387687 0.797746 -0.461843 0.375346 0.807768 -0.454563 0.312508 0.80365 -0.506444 0.309858 0.804872 -0.506132 0.240344 0.796691 -0.554544 0.234124 0.803861 -0.546804 0.15375 0.80242 -0.576614 0.152404 0.803165 -0.575933 0.0148202 0.963156 -0.268535 0.0431811 0.964609 -0.260125 0.0443568 0.964346 -0.260901 0.0697863 0.965225 -0.251935 0.0757232 0.962569 -0.260243 0.0969466 0.96468 -0.244938 0.0993183 0.964292 -0.245515 0.116749 0.965785 -0.23158 0.12773 0.962537 -0.239182 0.1402 0.965067 -0.221334 0.142802 0.964748 -0.221062 0.152536 0.966678 -0.205586 0.164543 0.96401 -0.208831 0.169509 0.966812 -0.191159 0.171368 0.966658 -0.190275 0.174369 0.968591 -0.177276 0.181041 0.967457 -0.176782 0.0138307 0.964145 -0.265016 0.0500395 0.868699 -0.492806 0.0626495 0.796954 -0.600782 0.0746329 0.761529 -0.64382 0.103951 0.578957 -0.808705 0.811235 0.554725 -0.184873 0.791526 0.541744 -0.282842 0.788138 0.544841 -0.286333 0.749684 0.523384 -0.405022 0.733962 0.545155 -0.405101 0.671259 0.534281 -0.513765 0.667732 0.537035 -0.515487 0.590706 0.51998 -0.616999 0.579615 0.537385 -0.612588 0.482271 0.531031 -0.696722 0.479496 0.533161 -0.69701 0.370383 0.520478 -0.769362 0.36485 0.532086 -0.764048 0.242 0.529933 -0.812777 0.240516 0.531187 -0.812399 0.105366 0.521982 -0.846423 0.121086 0.418868 -0.899938 0.470572 0.176752 -0.864477 0.464573 0.00941769 -0.885485 0.341668 0.186492 -0.921132 0.29695 0.184513 -0.936897 0.295454 0.186135 -0.937049 0.138709 0.178219 -0.974165 0.137483 0.18493 -0.973087 -0.194906 0.959723 -0.202344 -0.555289 0.813768 -0.171568 -0.831277 0.543903 -0.114665 -0.980756 0.191042 -0.0402716 -0.194816 0.959742 -0.202343 -0.195027 0.945889 -0.259343 -0.37841 0.879871 -0.287458 -0.555101 0.813893 -0.171584 -0.554879 0.790798 -0.258357 -0.55487 0.790803 -0.258359 -0.554875 0.754678 -0.350109 -0.554903 0.75466 -0.350102 -0.555055 0.711109 -0.431552 -0.555054 0.71111 -0.431552 -0.554923 0.659473 -0.507106 -0.554907 0.659482 -0.507112 -0.194855 0.928878 -0.314987 -0.194743 0.889768 -0.41278 -0.194729 0.889771 -0.412781 -0.194804 0.838513 -0.508869 -0.194811 0.838511 -0.508869 -0.194748 0.777551 -0.597903 -0.194749 0.777551 -0.597903 -0.194745 0.70259 -0.684428 -0.130284 0.712226 -0.689754 -0.382117 0.661265 -0.645534 -0.554947 0.597242 -0.579081 -0.608101 0.568645 -0.553946 -0.792846 0.436532 -0.425247 -0.831158 0.54408 -0.114692 -0.83101 0.528755 -0.172746 -0.831011 0.528753 -0.172746 -0.831013 0.504596 -0.234092 -0.831012 0.504599 -0.234093 -0.831114 0.475406 -0.28851 -0.831115 0.475405 -0.28851 -0.831028 0.440941 -0.339063 -0.831028 0.440941 -0.339064 -0.831071 0.39975 -0.386679 -0.923669 0.273795 -0.268091 -0.980737 0.191134 -0.0402867 -0.980715 0.185778 -0.0606945 -0.980716 0.185777 -0.0606942 -0.980716 0.177289 -0.082248 -0.980715 0.177293 -0.0822494 -0.98073 0.167017 -0.101358 -0.98073 0.167017 -0.101358 -0.980718 0.154923 -0.119129 -0.980718 0.154921 -0.119127 -0.980737 0.141282 -0.134883 -0.991414 0.0936659 -0.0912446 -0.0086666 0.869575 -0.493725 -0.00761073 0.7632 -0.646117 -0.00422162 0.677268 -0.735724 -0.0057926 0.581177 -0.813757 -0.00419456 0.420662 -0.907208 -0.000553092 0.245487 -0.9694 -0.00184424 0.184983 -0.98274 -0.00443615 0.945807 -0.3247 -0.00753 0.945787 -0.324701 -0.0096179 0.964172 -0.265105 -0.00114968 0.245448 -0.969409 -0.00115133 0.245483 -0.9694 -0.00272095 0.581005 -0.813896 -0.00570229 0.677257 -0.735724 -0.00357587 0.762986 -0.646405 -0.00442792 0.945743 -0.324885 -0.0289401 0.94535 -0.32477 -0.0554147 0.761768 -0.645476 -0.0846967 0.578791 -0.811066 -0.23123 0.185173 -0.955115 -0.105543 0.182047 -0.977609 -0.114165 0.24359 -0.963136 -0.035137 0.963703 -0.264654 -0.0459984 0.963903 -0.262252 -0.0455625 0.963655 -0.263236 -0.0742934 0.963977 -0.255401 -0.0769171 0.961495 -0.263841 -0.102311 0.963288 -0.248211 -0.102196 0.962701 -0.250524 -0.123905 0.963935 -0.235536 -0.131767 0.960309 -0.245852 -0.148141 0.962885 -0.225625 -0.149028 0.962119 -0.228293 -0.0595928 0.799002 -0.598368 -0.128181 0.801459 -0.584152 -0.127698 0.80092 -0.584997 -0.212771 0.800499 -0.560294 -0.214933 0.794778 -0.567566 -0.291376 0.801496 -0.522211 -0.291054 0.800155 -0.524442 -0.361294 0.802817 -0.474291 -0.368957 0.793353 -0.484213 -0.424319 0.803268 -0.417988 -0.425052 0.801322 -0.420969 -0.0819263 0.52531 -0.846958 -0.192864 0.529474 -0.826112 -0.192323 0.528732 -0.826713 -0.321154 0.528052 -0.786143 -0.32238 0.519662 -0.791216 -0.440597 0.529941 -0.724595 -0.439917 0.527976 -0.72644 -0.547402 0.531984 -0.646022 -0.553008 0.516769 -0.653553 -0.641666 0.532332 -0.552167 -0.641788 0.529005 -0.555214 -0.811427 0.190023 -0.5527 -0.769077 0.183124 -0.612361 -0.770121 0.187648 -0.609674 -0.659581 0.171033 -0.731915 -0.657842 0.190713 -0.72861 -0.528363 0.18346 -0.82896 -0.529569 0.185924 -0.827641 -0.496148 0.183984 -0.848521 -0.395339 0.0705322 -0.915824 -0.370409 0.185984 -0.910059 -0.230601 0.184304 -0.955435 -0.161979 0.964101 -0.210409 -0.172701 0.960711 -0.217277 -0.472936 0.807431 -0.352684 -0.486061 0.796073 -0.360573 -0.715784 0.538538 -0.444556 -0.727168 0.517467 -0.45106 -0.888855 -0.0749242 -0.452021 -0.88457 0.174871 -0.432384 -0.925644 0.18464 -0.33029 -0.92574 0.190832 -0.326479 -0.777308 0.534404 -0.331971 -0.775895 0.538602 -0.328474 -0.516598 0.807069 -0.285946 -0.514799 0.809196 -0.283167 -0.181176 0.963139 -0.198841 -0.179849 0.963753 -0.197062 -0.971039 0.166526 -0.171324 -0.963447 0.205641 -0.171704 -0.825984 0.52451 -0.206492 -0.810075 0.549476 -0.204584 -0.554149 0.80529 -0.210778 -0.53855 0.816526 -0.207964 -0.195009 0.963622 -0.182769 -0.186548 0.965666 -0.180799 0.842101 0.197582 0.501824 0.0748282 0.58023 0.811008 0.0340153 0.869236 0.493226 0.0073592 0.964205 0.265055 0.0428862 0.762787 0.645226 0.0680284 0.420446 0.904764 0.00725731 0.963628 0.267148 0.0307389 0.964559 0.262071 0.0302987 0.964297 0.263085 0.0590108 0.965052 0.255327 0.0616645 0.962596 0.263832 0.0870829 0.964771 0.248261 0.0869805 0.964184 0.250568 0.0466324 0.799448 0.598923 0.114754 0.802876 0.584998 0.114168 0.802191 0.586051 0.199655 0.803061 0.561454 0.202173 0.796614 0.569677 0.279103 0.804525 0.524253 0.278783 0.803079 0.526635 0.0794017 0.52564 0.846994 0.18303 0.530847 0.827467 0.182258 0.529737 0.828348 0.311833 0.531022 0.787894 0.313474 0.520682 0.794119 0.432464 0.532788 0.727401 0.431699 0.530446 0.729564 0.614432 0.19107 0.765484 0.524523 0.184201 0.831231 0.525961 0.187264 0.829637 0.38082 0.175124 0.907914 0.380769 0.18847 0.905259 0.22519 0.184469 0.956693 0.226203 0.185936 0.956169 0.101143 0.180999 0.978269 0.101697 0.18529 0.977407 0.71865 0.181536 0.671257 0.683655 -0.0843529 0.724914 0.54636 0.519458 0.657004 0.540035 0.536138 0.648782 0.357781 0.796942 0.4867 0.349609 0.806824 0.476245 0.11672 0.962259 0.245832 0.108856 0.965755 0.235517 0.766933 0.184484 0.614637 0.768038 0.189398 0.611756 0.635836 0.532805 0.558419 0.635684 0.536384 0.555157 0.41443 0.805709 0.42318 0.413648 0.807748 0.420046 0.13416 0.964348 0.228108 0.133273 0.9651 0.225434 0.907431 0.185647 0.376967 0.886087 0.00981711 0.463416 0.722509 0.521635 0.453737 0.710516 0.543476 0.446991 0.476503 0.80102 0.36237 0.462905 0.812554 0.354226 0.158099 0.963326 0.216812 0.147369 0.96655 0.209912 0.924822 0.18643 0.331584 0.924907 0.192874 0.327637 0.773251 0.539202 0.333683 0.771782 0.543491 0.330105 0.507518 0.812484 0.286872 0.505659 0.814643 0.284019 0.16677 0.965924 0.197936 0.165427 0.966522 0.196136 0.970562 0.168756 0.171848 0.962863 0.207972 0.172172 0.822507 0.529716 0.207085 0.806357 0.55473 0.205093 0.545621 0.811107 0.210721 0.529805 0.822263 0.207822 0.181029 0.966599 0.181428 0.172306 0.968575 0.179367 -0.0086666 0.869575 0.493725 -0.00443585 0.945743 0.324884 -0.00197016 0.420506 0.907288 -0.00304574 0.245469 0.9694 -0.000866128 0.184912 0.982755 -0.00961788 0.964172 0.265105 -0.00753 0.945787 0.3247 -0.00442821 0.945807 0.324699 -0.00357587 0.762986 0.646405 -0.00761073 0.7632 0.646117 -0.00422162 0.677268 0.735724 -0.00570229 0.677257 0.735724 -0.00272095 0.581005 0.813896 -0.00184424 0.184983 0.98274 -0.000553092 0.245487 0.9694 -0.0041947 0.420668 0.907205 -0.00579264 0.581174 0.813759 0.180937 0.962922 0.200106 0.546783 0.819761 0.170356 0.827877 0.549178 0.114119 0.980357 0.193105 0.0401216 0.182105 0.9627 0.200115 0.182292 0.948481 0.25914 0.393256 0.87496 0.28248 0.183752 0.93121 0.314775 0.183626 0.893167 0.410529 0.185494 0.892813 0.410459 0.185567 0.841852 0.506803 0.187225 0.841539 0.506714 0.187164 0.780805 0.596081 0.189003 0.780474 0.595934 0.188997 0.705521 0.683022 0.190664 0.705237 0.682853 0.547358 0.819386 0.17031 0.547129 0.796572 0.257143 0.548156 0.795916 0.256988 0.548158 0.759942 0.3493 0.549263 0.759259 0.34905 0.549421 0.715837 0.430946 0.550466 0.715215 0.430645 0.550331 0.663655 0.506653 0.551409 0.663055 0.506268 0.551397 0.599376 0.580267 0.552433 0.598844 0.57983 0.828053 0.54892 0.114081 0.827898 0.533757 0.172304 0.828292 0.533194 0.172155 0.828294 0.509092 0.233998 0.828757 0.508454 0.233745 0.828863 0.479298 0.288547 0.829269 0.478763 0.288268 0.82918 0.444306 0.339194 0.829628 0.443756 0.33882 0.82962 0.401139 0.388352 0.83001 0.400701 0.387971 0.980372 0.193034 0.0401102 0.980349 0.187732 0.0605979 0.9804 0.187489 0.0605314 0.9804 0.179013 0.0822773 0.980454 0.178765 0.0821769 0.98047 0.168495 0.101434 0.980513 0.168305 0.101332 0.9805 0.156206 0.119247 0.980555 0.155979 0.11909 0.980554 0.141002 0.136501 0.980604 0.140814 0.136335 -0.195022 0.964441 0.17838 -0.554748 0.809089 0.193985 -0.828299 0.530695 0.179676 -0.975199 0.173117 0.137903 -0.967931 0.203179 0.14774 -0.945149 0.186102 0.268438 -0.942712 0.190874 0.273609 -0.898803 0.169935 0.404073 -0.909867 0.0630245 0.410086 -0.828888 0.187731 0.526974 -0.809284 0.183885 0.557895 -0.80647 0.187609 0.560722 -0.710007 0.17044 0.683257 -0.703876 0.191774 0.683946 -0.586429 0.18356 0.788927 -0.584289 0.185999 0.789944 -0.188505 0.965648 0.178857 -0.185554 0.963784 0.191546 -0.183743 0.963959 0.192412 -0.178881 0.961278 0.209633 -0.166947 0.964121 0.206395 -0.157433 0.962369 0.221496 -0.154794 0.962735 0.221768 -0.142452 0.960413 0.239404 -0.131449 0.963854 0.231746 -0.114149 0.962635 0.245567 -0.111836 0.963052 0.244998 -0.0905399 0.961262 0.260341 -0.084684 0.963994 0.25208 -0.059147 0.963504 0.261078 -0.058024 0.963773 0.260337 -0.541929 0.81717 0.196331 -0.528763 0.809243 0.255999 -0.525757 0.810577 0.257962 -0.50375 0.797733 0.331448 -0.487987 0.808626 0.328623 -0.447915 0.802362 0.394445 -0.444705 0.803778 0.395194 -0.39771 0.793813 0.460095 -0.386113 0.803477 0.453145 -0.323508 0.800325 0.5048 -0.321 0.801527 0.504494 -0.251515 0.794424 0.552839 -0.246015 0.800952 0.545851 -0.165611 0.800745 0.575657 -0.164449 0.801409 0.575066 -0.02947 0.962745 0.268801 -0.0449944 0.944785 0.324588 -0.0746101 0.796565 0.599931 -0.0863144 0.760063 0.644092 -0.112679 0.577134 0.808838 -0.814667 0.549537 0.185277 -0.794863 0.536763 0.282982 -0.791601 0.539783 0.286361 -0.75333 0.518878 0.404054 -0.738274 0.540089 0.404048 -0.675805 0.530163 0.512069 -0.672553 0.532764 0.513649 -0.595718 0.516861 0.614796 -0.585655 0.533042 0.610634 -0.488431 0.528193 0.694584 -0.486045 0.530081 0.69482 -0.37685 0.519056 0.767179 -0.372369 0.528809 0.762694 -0.249426 0.528556 0.811428 -0.24834 0.529498 0.811147 -0.113177 0.522353 0.845186 -0.127531 0.416826 0.899995 -0.526295 0.181688 0.830664 -0.466298 -0.0860524 0.880432 -0.402505 0.186549 0.896208 -0.299208 0.184176 0.936245 -0.298232 0.185263 0.936342 -0.141092 0.17969 0.973553 -0.140584 0.182754 0.973056 0.190975 0.657255 0.729071 0.135273 0.665872 0.7337 0.41112 0.61911 0.669091 0.552946 0.580507 0.597715 0.651883 0.529322 0.543016 0.829641 0.409029 0.379988 0.998211 0.044272 -0.0401779 0.978681 0.178953 0.100797 0.957704 0.230375 0.172428 0.838823 0.39902 0.37035 0.140151 0.635893 0.758945 0.146788 0.636076 0.757536 0.409052 0.631835 0.658377 0.449887 0.624322 0.638611 0.64415 0.57557 0.503776 0.704971 0.546503 0.452051 0.826002 0.471986 0.30814 0.885087 0.411172 0.218079 0.939885 0.32998 0.0879188 0.971714 0.233058 -0.0381641 0.977081 0.16137 -0.138824 0.884581 0.0790305 -0.459641 0.931411 0.107874 -0.347616 0.956562 0.0310062 -0.289875 0.160666 0.603184 0.781253 0.155179 0.601743 0.78347 0.447322 0.668702 0.59392 0.473735 0.668839 0.572913 0.679359 0.652836 0.335076 0.720481 0.635638 0.277258 0.82887 0.558238 0.0366799 0.859273 0.508203 -0.0581354 0.878641 0.397083 -0.26517 0.871185 0.306315 -0.383677 0.157257 0.599159 0.785034 0.155596 0.59913 0.785387 0.446152 0.704161 0.552363 0.45096 0.702992 0.549943 0.668698 0.704552 0.237592 0.677259 0.698765 0.230323 0.791664 0.600501 -0.112544 0.799981 0.587004 -0.124328 0.796746 0.407678 -0.446087 0.800502 0.384765 -0.459514 0.15468 0.615555 0.772766 0.154365 0.615526 0.772852 0.443263 0.641732 0.625858 0.462714 0.63901 0.61446 0.684978 0.600148 0.41307 0.715111 0.585349 0.382077 0.854393 0.495382 0.156874 0.881245 0.461086 0.103953 0.933755 0.338727 -0.11561 0.941372 0.281326 -0.186212 0.883922 0.0781147 -0.461065 0.82351 0.188893 -0.534931 0.755303 0.0593664 -0.652682 0.683116 0.154813 -0.713713 0.473926 0.0581354 -0.878644 0.651257 0.154797 -0.742901 0.678893 0.122915 -0.723876 0.108267 0.627439 0.771102 0.105177 0.624738 0.773719 0.298492 0.83735 0.457982 0.305739 0.840442 0.447415 0.434951 0.897982 0.0666821 0.446423 0.893924 0.0400835 0.494726 0.802597 -0.333292 0.503052 0.780888 -0.370341 0.468591 0.569632 -0.675235 0.467293 0.524308 -0.711856 0.165743 0.609159 -0.775535 0.162392 0.623183 -0.765031 0.180152 0.880768 -0.437942 0.176536 0.887053 -0.426582 0.160744 0.986837 -0.0177089 0.157645 0.987454 -0.00905097 0.110473 0.905227 0.410317 0.108828 0.903741 0.414016 0.0381762 0.644887 0.763324 0.0387994 0.645967 0.762379 0.148989 0.60667 0.780867 0.142909 0.603555 0.78441 0.410387 0.747712 0.522024 0.424846 0.750446 0.506298 0.607578 0.772672 0.183921 0.630048 0.763669 0.140886 0.71099 0.679617 -0.180593 0.72443 0.643938 -0.24606 0.706083 0.484123 -0.516791 0.694052 0.413424 -0.589383 0.531941 0.11953 -0.838303 0.360575 0.237521 -0.901981 0.344924 0.167769 -0.923515 0.117411 0.241042 -0.963386 0.119941 0.218718 -0.968389 -0.194899 0.959543 0.203202 -0.946783 0.229111 0.226077 -0.194822 0.698165 0.688919 -0.555055 0.592089 0.584247 -0.831123 0.395826 0.390585 -0.99142 0.0930448 0.0918127 -0.194825 0.698165 0.688919 -0.194761 0.769812 0.60783 -0.194756 0.769813 0.607831 -0.194749 0.83538 0.514017 -0.194755 0.835379 0.514016 -0.194753 0.889895 0.412503 -0.194705 0.889902 0.412509 -0.194835 0.928145 0.317154 -0.388491 0.875598 0.28706 -0.195051 0.944985 0.262601 -0.194832 0.959556 0.203208 -0.555025 0.592102 0.584262 -0.554898 0.652924 0.515537 -0.55492 0.652913 0.515527 -0.554909 0.708528 0.435964 -0.554896 0.708535 0.435969 -0.55489 0.754776 0.349872 -0.554895 0.754773 0.349871 -0.554911 0.790511 0.259164 -0.554877 0.790532 0.259173 -0.55505 0.81377 0.172332 -0.555276 0.813625 0.172289 -0.831131 0.395818 0.390576 -0.831045 0.436534 0.344677 -0.831025 0.436557 0.344698 -0.831017 0.473749 0.291502 -0.831013 0.473754 0.291506 -0.831008 0.504676 0.233939 -0.831022 0.504658 0.23393 -0.831033 0.528544 0.173281 -0.831036 0.528539 0.173279 -0.831152 0.543983 0.115191 -0.831268 0.543815 0.115146 -0.980749 0.140539 0.135573 -0.980717 0.153384 0.121109 -0.980718 0.153379 0.121105 -0.980717 0.166446 0.102416 -0.980717 0.166448 0.102418 -0.980716 0.177313 0.0821921 -0.980716 0.177317 0.0821938 -0.980717 0.185707 0.0608833 -0.980718 0.185705 0.0608823 -0.980735 0.191108 0.0404648 -0.980754 0.191012 0.0404399 -0.000423063 0.220065 -0.975485 -0.000421598 0.220028 -0.975493 -0.00118932 0.61756 -0.786523 -0.0011838 0.617445 -0.786613 -0.00172491 0.895429 -0.445202 -0.00171643 0.895327 -0.445405 -0.00192714 0.999843 -0.0176395 -0.00191591 0.999837 -0.0179477 -0.00175732 0.910584 0.41332 -0.00174276 0.910753 0.412948 -0.00124803 0.644919 0.76425 -0.00123059 0.645301 0.763928 -0.000200564 0.220084 -0.975481 -0.000199882 0.220066 -0.975485 -0.000563376 0.617618 -0.786478 -0.000560676 0.617561 -0.786523 -0.000816843 0.89547 -0.44512 -0.000813496 0.89543 -0.445202 -0.000913382 0.999847 -0.0174854 -0.000907768 0.999844 -0.0176395 -0.000832739 0.9105 0.413508 -0.000825278 0.910586 0.41332 -0.000590744 0.644753 0.764391 -0.000582917 0.64492 0.76425 -0.0301643 0.644452 0.76405 -0.119934 0.99263 -0.0173632 -0.133244 0.887474 -0.441175 -0.120823 0.613061 -0.780742 -0.084758 0.219253 -0.97198 -0.121527 0.992512 -0.0123165 -0.406892 0.91317 0.0236473 -0.40565 0.912368 0.0550644 -0.604743 0.786277 0.126705 -0.595917 0.785891 0.165104 -0.701111 0.675547 0.228212 -0.673091 0.680976 0.288478 -0.724917 0.597551 0.342678 -0.684856 0.608519 0.400845 -0.704503 0.559476 0.436649 -0.665623 0.571672 0.479726 -0.13617 0.890421 -0.434291 -0.454424 0.801645 -0.388412 -0.461427 0.816948 -0.345949 -0.691341 0.671659 -0.266311 -0.694342 0.689001 -0.207768 -0.822869 0.553203 -0.129821 -0.810004 0.585485 -0.0331898 -0.880936 0.471503 0.0404626 -0.850342 0.50793 0.137573 -0.880841 0.432465 0.192595 -0.845014 0.463844 0.266084 -0.125264 0.62039 -0.774225 -0.417065 0.543058 -0.728796 -0.437793 0.580637 -0.686439 -0.656184 0.440494 -0.612689 -0.683811 0.482938 -0.546967 -0.814213 0.345021 -0.466924 -0.841206 0.412819 -0.349219 -0.920737 0.284617 -0.266901 -0.925312 0.352702 -0.13928 -0.962897 0.260072 -0.0720588 -0.948951 0.314063 0.0292448 -0.0908184 0.231164 -0.968667 -0.299634 0.179663 -0.936985 -0.338621 0.241162 -0.909493 -0.504637 0.132119 -0.853162 -0.566179 0.199379 -0.799806 -0.676516 0.0833527 -0.731696 -0.76331 0.185258 -0.618901 -0.839552 0.0615714 -0.539779 -0.902368 0.159194 -0.400486 -0.942203 0.0607743 -0.329485 -0.968369 0.135713 -0.209388 -0.030004 0.645104 0.763505 -0.0994569 0.628088 0.77176 -0.10079 0.631295 0.768965 -0.142078 0.60401 0.78421 -0.145659 0.60779 0.780625 -0.156341 0.596738 0.787058 -0.162342 0.599991 0.783362 -0.157217 0.608346 0.777945 -0.159483 0.609041 0.776939 -0.152003 0.628019 0.763208 -0.149393 0.62755 0.764109 -0.143241 0.652832 0.743836 -0.195066 0.653133 0.731688 -0.988276 0.146713 0.0422555 -0.991606 0.030865 -0.125562 -0.94429 0.271107 0.186595 -0.970609 0.215427 0.107281 -0.829925 0.418917 0.36842 -0.861621 0.391241 0.323327 -0.555462 0.575484 0.600233 -0.674649 0.533914 0.50969 -0.429516 0.615699 0.660628 -0.426589 0.627923 0.650949 -0.452568 0.627167 0.633911 -0.446083 0.643514 0.622012 -0.472601 0.645502 0.599979 -0.447436 0.686248 0.573468 -0.466762 0.691496 0.551332 -0.403072 0.757713 0.513229 -0.410544 0.763149 0.499056 -0.278483 0.848386 0.45021 -0.28149 0.854365 0.436835 -0.0838414 0.90635 0.414127 -0.083291 0.90733 0.412087 0.740781 0 0.671746 0.744704 -0.00463343 0.667379 0.780591 0 0.625043 -0.0601759 0 -0.998188 -0.09703 -0.0248852 -0.99497 -0.154913 0 -0.987928 -0.969421 0 -0.245406 -0.960807 0.0195987 -0.276526 -0.905842 -0.0330618 -0.422323 -0.889488 0 -0.456958 -1 0 0 -1 0 0 1 0 0 1 0 0 0.994974 0 -0.100135 0.994974 0 -0.100135 0.0727981 0 -0.997347 0.149712 0.0528467 -0.987316 0.156337 0.0595969 -0.985904 0.333596 -0.0666144 -0.94036 0.387114 0.00449537 -0.922021 0.46529 0 -0.885158 1 6.12489e-05 -0.000187001 1 2.38318e-05 -3.99136e-05 0.999999 0.000766427 -0.00101528 0.999999 -5.97519e-06 -0.00139945 0.999999 0.000906423 0.000531811 0.999999 0.00101784 -0.000927191 0.999999 0.000928475 -0.000731677 0.999999 0.00143866 -0.000850147 0.999998 0.00152671 -0.00101426 0.999998 0.00201807 -0.000902209 0.999998 0.00195454 -0.0008015 0.999997 0.00224052 -0.000626312 0.999997 0.00227217 -0.000670946 0.999997 0.00231066 -0.000381725 0.999997 0.00232616 -0.000401425 0.999998 0.00214932 -0.000230121 0.999998 0.00209286 -0.000162353 0.999999 0.00152913 6.88217e-05 0.999999 0.00163771 -5.20959e-05 1 0.00089402 2.8439e-05 1 0.000725046 0.000206126 1 -0.000552828 0.000165823 1 -0.000346065 -3.7052e-05 1 -0.000920923 -0.000158024 1 -0.000921232 -0.000158813 1 -0.000909932 -0.000181395 1 -0.000909384 -0.00016181 1 -0.000590372 -0.000210759 1 -0.000631002 -0.00017639 1 -0.000414695 -0.000170054 1 -0.00038368 -0.000193507 1 -0.000304456 -0.000185185 1 -0.000308658 -0.000182396 1 -0.000289621 -0.000228234 1 -0.000291611 -0.000227069 1 0.000153219 0.000181612 1 0.000204857 0.000155837 1 3.33671e-05 0.00104648 1 -0.000117035 -0.000288702 1 3.06412e-05 -0.000499105 -0.393634 0 0.919267 -0.393634 0 0.919267 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 5.1049e-06 6.30819e-05 -1 -1.90694e-05 -3.19378e-05 -1 0.000319162 0.00051808 -1 0.000412143 0.000471769 -1 0.000416331 0.000462905 -0.999999 0.00126045 0.00118939 -0.999999 0.00112032 0.000882857 -0.999997 0.00197063 0.00116451 -0.999997 0.00212592 0.0014542 -0.999994 0.0031799 0.00148733 -0.999995 0.00302364 0.00123991 -0.999992 0.00387556 0.00108337 -0.999991 0.00400516 0.00126658 -0.999988 0.00480115 0.000946534 -0.999989 0.00469335 0.000809928 -0.999986 0.00521407 0.000558253 -0.999986 0.00527945 0.000636831 -0.999984 0.0056027 0.000201664 -0.999984 0.00558093 0.000177531 -0.999984 0.00564052 -0.000179427 -0.999984 0.00562765 -0.000193042 -0.999986 0.00534344 -0.000643552 -0.999985 0.00540939 -0.000579165 -0.999988 0.0049162 -0.000874759 -0.999988 0.00491853 -0.000944561 -0.999987 0.00500326 -0.000862519 -0.99999 0.00416594 -0.0013088 -0.99999 0.00429512 -0.00120065 -0.999993 0.00350144 -0.00143584 -0.999993 0.00335235 -0.00154937 -0.999996 0.00230148 -0.0015605 -0.999996 0.00246185 -0.00145478 -0.99998 0.00157283 -0.0060571 -1 -0.000643806 0.000507346 -0.999976 0.00140914 0.0067497 -1 0.000523696 -0.000781528 -1 0.000641009 -0.000723165 -1 4.76633e-05 -8.17247e-05 -1 7.02609e-05 -0.000235708 -1 0.000102074 -0.000167729 -0.000362142 0.000293034 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.901325 0 0.433144 -0.908603 0.0209795 0.417134 -0.948314 0 0.317335 0 0.425779 -0.904827 0 0.217851 -0.975982 -0.0173266 0.187353 -0.98214 0 0.0938103 -0.99559 0 -0.0627905 -0.998027 0 -0.0627905 -0.998027 0 -0.309017 -0.951057 0 -0.309017 -0.951057 0 -0.535827 -0.844328 0 -0.535827 -0.844328 0 -0.728969 -0.684547 0 -0.728969 -0.684547 0 -0.821588 -0.570081 -0.0132912 -0.876229 -0.481711 0 -0.88656 -0.462613 0 -0.968583 -0.24869 0 -0.968583 -0.24869 0 -1 0 0 -1 0 0 -0.968583 0.24869 0 -0.968583 0.24869 0 -0.876307 0.481754 0 -0.876307 0.481754 0 -0.767698 0.640812 -0.0231411 -0.728774 0.684364 0 -0.681329 0.731977 0 -0.535827 0.844328 0 -0.535827 0.844328 0 -0.309017 0.951057 0 -0.309017 0.951057 0 -0.0627905 0.998027 0 -0.0627905 0.998027 0 0.187381 0.982287 0 0.187381 0.982287 0 0.425779 0.904827 0 0.425779 0.904827 0 0.615367 0.788241 -0.0162264 0.63734 0.770412 0 0.709308 0.704899 0 0.809017 0.587785 0 0.809017 0.587785 0 0.929777 0.368124 0 0.929777 0.368124 0 0.992115 0.125334 0 0.992115 0.125334 0 0.992115 -0.125334 0 0.992115 -0.125334 0 0.929777 -0.368124 0 0.929777 -0.368124 0 0.809017 -0.587786 0 0.809017 -0.587786 0 0.709308 -0.704899 -0.0162264 0.63734 -0.770412 0 0.615367 -0.788241 0 0.425779 -0.904827 -0.849118 -0.136711 0.510204 -0.849119 -0.373494 0.373497 -0.84912 -0.510202 0.136713 -0.849119 0.510204 0.136708 -0.849119 0.373494 0.373497 -0.849118 0.136711 0.510204 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.707104 0.70711 0 -0.707104 0.70711 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707104 0.70711 0 0.707104 0.70711 0 0.965926 0.258817 0 0.965926 0.258817 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258817 0 0.965926 0.258817 -0.849119 -0.136708 0.510204 -0.849119 -0.373495 0.373495 -0.849119 -0.510204 0.136708 -0.849119 0.510204 0.136708 -0.849119 0.373495 0.373495 -0.849119 0.136708 0.510204 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965925 0.258822 0 0.965925 0.258822 -0.849119 -0.13671 0.510204 -0.849119 -0.373495 0.373495 -0.849119 -0.510203 0.13671 -0.849118 0.510204 0.136711 -0.849118 0.373496 0.373496 -0.849118 0.136711 0.510204 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 -0.849119 -0.136709 0.510204 -0.849119 -0.373495 0.373496 -0.849119 -0.510203 0.136709 -0.849119 0.510203 0.136709 -0.849119 0.373495 0.373496 -0.849119 0.136709 0.510204 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 -0.849119 -0.136709 0.510204 -0.849119 -0.373495 0.373496 -0.849119 -0.510203 0.136709 -0.849119 0.510203 0.136709 -0.849119 0.373495 0.373496 -0.849119 0.136709 0.510204 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965925 0.258822 0 0.965925 0.258822 -0.849119 -0.13671 0.510204 -0.849119 -0.373495 0.373495 -0.849119 -0.510203 0.13671 -0.849118 0.510204 0.136711 -0.849118 0.373496 0.373496 -0.849118 0.136711 0.510204 0 -0.965927 0.258816 0 -0.965927 0.258816 0 -0.707104 0.70711 0 -0.707104 0.70711 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707104 0.70711 0 0.707104 0.70711 0 0.965927 0.258816 0 0.965927 0.258816 -0.849119 -0.13671 0.510203 -0.849119 -0.373493 0.373496 -0.849119 -0.510204 0.136707 -0.849119 0.510204 0.136707 -0.849119 0.373493 0.373496 -0.849119 0.13671 0.510203 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.707104 0.70711 0 -0.707104 0.70711 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707104 0.70711 0 0.707104 0.70711 0 0.965926 0.258817 0 0.965926 0.258817 -0.849118 -0.136711 0.510204 -0.849119 -0.373494 0.373497 -0.84912 -0.510202 0.136713 -0.849119 0.510204 0.136708 -0.849119 0.373494 0.373497 -0.849118 0.136711 0.510204 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.258817 0 0.965926 0.258817 -0.849119 -0.136709 0.510204 -0.849119 -0.373495 0.373496 -0.849119 -0.510204 0.136708 -0.849119 0.510204 0.136708 -0.849119 0.373495 0.373496 -0.849119 0.136709 0.510204 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.258817 0 0.965926 0.258817 -0.849119 -0.136709 0.510204 -0.849119 -0.373495 0.373496 -0.849119 -0.510204 0.136708 -0.849119 0.510204 0.136708 -0.849119 0.373495 0.373496 -0.849119 0.136709 0.510204 0.939848 -0.337905 0.0500604 0.939677 -0.337956 0.0528412 0.939715 -0.337878 0.0526762 0.939822 -0.337576 0.0526975 0.939762 -0.337887 0.051775 0.939691 -0.337679 0.0543524 0.940789 -0.334611 0.0543268 0.940496 -0.335424 0.0543886 0.939736 -0.33775 0.053115 0.940046 -0.337704 0.0476422 0.940591 -0.336735 0.0435708 0.940962 -0.335914 0.0418716 0.939576 -0.341979 0.0157345 0.938802 -0.344162 0.0142347 0.93981 -0.340166 0.0323052 0.940119 -0.33889 0.0364679 0.940387 -0.322176 0.108973 0.940248 -0.322558 0.109046 0.939699 -0.324567 0.107809 0.939685 -0.324668 0.107626 0.939728 -0.324591 0.107481 0.939663 -0.324939 0.106998 0.939729 -0.324326 0.10827 0.939822 -0.324682 0.10638 0.939969 -0.324733 0.104909 0.940225 -0.324739 0.102576 0.940754 -0.323997 0.100035 0.941064 -0.323524 0.0986483 0.942088 -0.321707 0.0947389 0.941623 -0.322674 0.0960642 0.944165 -0.320929 0.074544 0.939063 -0.336428 0.0705416 0.939772 -0.330577 0.0868814 0.940189 -0.328534 0.0900526 0.941649 -0.329073 0.0707748 0.940555 -0.33282 0.0677222 0.939668 -0.336152 0.0634492 0.940374 -0.334783 0.0601472 0.939672 -0.336289 0.0626619 0.939728 -0.334845 0.0692132 0.93965 -0.335038 0.0693294 0.939553 -0.336555 0.0630187 0.941745 -0.330665 0.0614624 0.941626 -0.33099 0.0615359 0.93961 -0.335167 0.0692483 0.940016 -0.334185 0.0684803 0.939883 -0.234521 0.248233 0.939789 -0.233786 0.24928 0.940267 -0.236059 0.245303 0.941321 -0.237054 0.24025 0.94208 -0.237156 0.237156 0.941395 -0.239941 0.237072 0.940149 -0.24579 0.236024 0.937959 -0.264597 0.224103 0.943048 -0.249054 0.22053 0.940656 -0.262036 0.215646 0.939634 -0.263025 0.218872 0.939731 -0.255373 0.227355 0.939646 -0.255493 0.227572 0.939425 -0.263271 0.219475 0.943051 -0.255787 0.212669 0.942939 -0.256027 0.212878 0.939608 -0.255639 0.227566 0.94002 -0.255165 0.226392 0.9397 -0.227176 0.255646 0.94602 -0.198321 0.25635 0.939663 -0.227897 0.25514 0.940301 -0.20821 0.269225 0.942693 -0.207302 0.26145 0.927055 -0.217861 0.305133 0.941558 -0.22066 0.254516 0.93998 -0.220536 0.260386 0.939694 -0.230917 0.252293 0.939686 -0.232692 0.250688 0.944499 -0.107729 0.310348 0.932708 -0.131093 0.335962 0.941868 -0.0952985 0.322185 0.941584 -0.0960953 0.322778 0.940161 -0.0898606 0.328668 0.940932 -0.123086 0.315432 0.939576 -0.122822 0.319549 0.939736 -0.107477 0.324569 0.939646 -0.107472 0.32483 0.939276 -0.12283 0.320428 0.944299 -0.118192 0.307132 0.944183 -0.118306 0.307444 0.939603 -0.107618 0.324907 0.940042 -0.107807 0.323572 0.939692 -0.0689344 0.335003 0.94538 -0.0462869 0.322666 0.939662 -0.0697859 0.334912 0.940224 -0.0503529 0.336813 0.939493 -0.0487772 0.339077 0.939105 -0.0492324 0.340086 0.945481 -0.0462418 0.322378 0.939721 -0.0692488 0.334857 0.939677 -0.0691609 0.334998 0.941269 -0.0699002 0.330343 0.932885 -0.044551 0.357408 0.943348 -0.0547727 0.327252 0.942112 -0.0534226 0.331015 0.942215 -0.0715723 0.327274 0.942759 -0.0724581 0.325508 0.940603 -0.0696724 0.332284 0.939643 -0.0827897 0.33199 0.939752 -0.086705 0.330679 0.931685 0.0449335 0.360478 0.94119 0.0464636 0.334669 0.939497 0.0487722 0.339067 0.939723 0.0692431 0.334852 0.939645 0.0693606 0.335047 0.939105 0.0492324 0.340086 0.945482 0.0462416 0.322376 0.945381 0.0462866 0.322665 0.939602 0.0692744 0.335184 0.940018 0.0684884 0.334179 0.944298 0.118194 0.307136 0.944185 0.118305 0.30744 0.939696 0.107821 0.324572 0.939678 0.107594 0.324697 0.939721 0.107449 0.324621 0.939665 0.10703 0.324923 0.940126 0.120554 0.318794 0.941515 0.115735 0.316472 0.942452 0.113105 0.314628 0.9428 0.112155 0.313926 0.936862 0.127119 0.325777 0.940303 0.102202 0.32463 0.940754 0.100038 0.323998 0.941064 0.0986476 0.323523 0.942088 0.0947379 0.321707 0.941623 0.0960644 0.322674 0.94019 0.0900542 0.328533 0.939772 0.0868808 0.330577 0.939691 0.0846333 0.331388 0.939623 0.0702271 0.334929 0.943785 0.0739667 0.322179 0.941649 0.0707745 0.329073 0.946017 0.198326 0.256356 0.939615 0.227533 0.255642 0.939985 0.226479 0.255217 0.941427 0.203509 0.268885 0.939397 0.208208 0.272366 0.96408 0.146642 0.221465 0.939001 0.21079 0.271744 0.946113 0.198151 0.256136 0.939728 0.227372 0.25537 0.939662 0.22754 0.255463 0.943046 0.255798 0.212679 0.942944 0.256016 0.212869 0.939701 0.255638 0.227179 0.939691 0.255553 0.227319 0.939735 0.255386 0.227325 0.939665 0.255125 0.227904 0.940008 0.261091 0.21958 0.94091 0.257003 0.220538 0.941556 0.254521 0.22066 0.942471 0.251052 0.22073 0.938637 0.263193 0.222913 0.939789 0.249276 0.23379 0.939883 0.248231 0.234523 0.939928 0.234704 0.247888 0.939663 0.233159 0.250339 0.939761 0.220926 0.260846 0.942022 0.220659 0.252794 0.924377 0.22167 0.310468 0.940267 0.245303 0.23606 0.941321 0.240251 0.237054 0.94208 0.237156 0.237156 0.941396 0.237072 0.23994 0.940295 0.236146 0.245115 0.939902 0.324802 0.105295 0.940421 0.324552 0.101366 0.939707 0.334973 0.0688785 0.941623 0.330997 0.0615376 0.939658 0.334903 0.069876 0.93969 0.334968 0.069127 0.939731 0.334835 0.06921 0.941748 0.330656 0.0614605 0.939553 0.336556 0.0630193 0.939673 0.336286 0.0626586 0.939872 0.335443 0.0641735 0.940322 0.333681 0.0667209 0.940697 0.332355 0.0680353 0.940847 0.33183 0.0685224 0.941412 0.329882 0.0701515 0.939642 0.331991 0.0827906 0.940602 0.332284 0.0696726 0.94276 0.325506 0.0724593 0.942217 0.327266 0.0715763 0.939752 0.330681 0.0867017 0.940161 0.328669 0.0898587 0.941584 0.322778 0.0960951 0.942158 0.321577 0.0944828 0.941179 0.323323 0.0982109 0.93969 0.324058 0.1094 0.939725 0.324591 0.107508 0.93967 0.324751 0.107505 0.939659 0.324233 0.109149 0.940374 0.322212 0.108978 0.94025 0.322553 0.109043 0.939628 0.324825 0.107645 0.94001 0.323664 0.107809 0.939599 0.341986 0.0141448 0.938904 0.343816 0.0158192 0.940223 0.337944 0.0421242 0.942586 0.332123 0.0350038 0.940989 0.335885 0.0414984 0.940252 0.337371 0.0458956 0.940488 0.335446 0.0543912 0.939621 0.338098 0.0529389 0.940006 0.336993 0.0531462 0.939973 0.337779 0.048538 0.939848 0.337905 0.0500624 0.939688 0.337871 0.053192 0.940104 0.336527 0.054345 0.940782 0.33463 0.0543291 0.939775 0.337718 0.0526324 0.939694 0.337945 0.0526163 0.939752 0.324456 0.107673 0.939691 0.324053 0.109408 0.939599 0.318863 0.124421 0.938046 0.320037 0.132839 0.940362 0.305611 0.149404 0.939671 0.304036 0.156782 0.939599 0.294035 0.175207 0.939163 0.293973 0.177631 0.939988 0.277692 0.198268 0.939625 0.277275 0.200559 0.939634 0.263025 0.218873 0.939425 0.263271 0.219475 0.94363 0.20671 0.258524 0.939371 0.208891 0.27193 0.939599 0.175207 0.294036 0.938156 0.171258 0.30089 0.940362 0.149404 0.305611 0.939667 0.144088 0.310264 0.939574 0.122822 0.319555 0.939276 0.12283 0.320428 0.942918 0.0544554 0.328543 0.939477 0.0495778 0.339005 0.939599 0.0141448 0.341986 0.941836 0.025199 0.335128 0.934773 -0.0146807 0.354943 0.940342 0 0.340232 0.93969 -0.0256455 0.341066 0.942123 -0.113883 0.315334 0.939562 -0.122085 0.319873 0.939599 -0.150327 0.3075 0.940951 -0.142595 0.307048 0.937335 -0.178356 0.29932 0.939486 -0.169464 0.297739 0.939391 -0.208221 0.272376 0.964079 -0.146644 0.221466 0.939001 -0.21079 0.271744 0.946111 -0.198156 0.256141 0.939727 -0.227368 0.255377 0.939686 -0.227363 0.255533 0.941325 -0.255304 0.220743 0.939625 -0.262531 0.219504 0.939599 -0.278563 0.19889 0.940026 -0.276381 0.199913 0.939068 -0.295285 0.175952 0.939569 -0.293022 0.177057 0.939599 -0.3075 0.150327 0.941047 -0.300655 0.155039 0.937104 -0.325173 0.126883 0.939476 -0.316439 0.131345 0.939691 -0.324054 0.109404 0.939659 -0.324234 0.109147 0 0.995734 0.0922684 0 0.995734 0.0922684 0 0.961826 0.273663 0 0.961826 0.273663 0 0.895163 0.445738 0 0.895163 0.445738 0 0.798017 0.602635 0 0.798017 0.602635 0 0.673696 0.739009 0 0.673696 0.739009 0 0.526432 0.850217 0 0.526432 0.850217 0 0.361242 0.932472 0 0.361242 0.932472 0 0.18375 0.982973 0 0.18375 0.982973 0 0 1 0 0 1 0 -0.18375 0.982973 0 -0.18375 0.982973 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.995734 0.0922682 0 -0.995734 0.0922682 0 0.995734 0.0922684 0 0.995734 0.0922684 0 0.961826 0.273663 0 0.961826 0.273663 0 0.895163 0.445738 0 0.895163 0.445738 0 0.798017 0.602635 0 0.798017 0.602635 0 0.673696 0.739009 0 0.673696 0.739009 0 0.526432 0.850217 0 0.526432 0.850217 0 0.361242 0.932472 0 0.361242 0.932472 0 0.18375 0.982973 0 0.18375 0.982973 0 0 1 0 0 1 0 -0.18375 0.982973 0 -0.18375 0.982973 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.995734 0.0922682 0 -0.995734 0.0922682 0 0.995185 0.0980171 0 0.995185 0.0980171 0 0.95694 0.290285 0 0.95694 0.290285 0 0.881921 0.471397 0 0.881921 0.471397 0 0.77301 0.634393 0 0.77301 0.634393 0 0.634393 0.77301 0 0.634393 0.77301 0 0.471397 0.881921 0 0.471397 0.881921 0 0.290285 0.95694 0 0.290285 0.95694 0 0.0980169 0.995185 0 0.0980169 0.995185 0 -0.098017 0.995185 0 -0.098017 0.995185 0 -0.290285 0.95694 0 -0.290285 0.95694 0 -0.471397 0.881921 0 -0.471397 0.881921 0 -0.634393 0.77301 0 -0.634393 0.77301 0 -0.77301 0.634394 0 -0.77301 0.634394 0 -0.881921 0.471397 0 -0.881921 0.471397 0 -0.95694 0.290284 0 -0.95694 0.290284 0 -0.995185 0.0980173 0 -0.995185 0.0980173 0 -0.985595 0.169124 0.0112203 -0.996132 0.0871503 0.100448 -0.987302 0.123067 0 -0.999146 0.041325 0 -0.928213 0.37205 0 -0.942794 0.333375 0.0211928 -0.965709 0.258761 0.0844684 -0.955002 0.284316 0 -0.977764 0.209708 0.0696542 -0.896209 0.43813 0.0299153 -0.905902 0.422429 0 -0.872832 0.48802 0 -0.751082 0.660209 0 -0.777724 0.628606 0.0373873 -0.818579 0.573175 0.0560286 -0.81257 0.580164 0 -0.851919 0.523673 0.0436114 -0.706434 0.706434 0.0436101 -0.706434 0.706434 0 -0.66021 0.751081 0 -0.523673 0.851919 0.0485864 -0.572899 0.818185 0.0324142 -0.580772 0.813421 0 -0.628606 0.777724 0 -0.333372 0.942795 0 -0.37205 0.928213 0.0523162 -0.422039 0.905067 0.022449 -0.439086 0.898165 0 -0.488019 0.872833 0.0137223 -0.285309 0.958337 0.0548014 -0.25843 0.964474 0 -0.209709 0.977764 0 -0.0413255 0.999146 0.0560439 -0.087019 0.994629 0.00623842 -0.12369 0.992301 0 -0.169122 0.985595 0 0.169122 0.985595 0.01122 0.0871505 0.996132 0.100448 0.123067 0.987302 0 0.0413256 0.999146 0 0.37205 0.928213 0 0.333373 0.942795 0.0211923 0.258761 0.965709 0.0844676 0.284316 0.955002 0 0.209709 0.977764 0.0696542 0.43813 0.896209 0.0299154 0.422429 0.905902 0 0.488021 0.872832 0 0.660209 0.751082 0 0.628606 0.777724 0.0373874 0.573175 0.818579 0.0560282 0.580164 0.812571 0 0.523673 0.851919 0.0436107 0.706434 0.706434 0.0436112 0.706434 0.706434 0 0.751083 0.660208 0 0.872832 0.488021 0 0.85192 0.523673 0.048587 0.818185 0.572899 0.0324139 0.813421 0.580772 0 0.777724 0.628606 0.0224501 0.898165 0.439086 0.0523163 0.905066 0.42204 0 0.928212 0.372051 0 0.977764 0.209706 0.0548032 0.964474 0.258429 0.0137214 0.958337 0.28531 0 0.942796 0.33337 0 0.999146 0.0413248 0.0560453 0.994629 0.0870193 0.00624038 0.992301 0.12369 0 0.985593 0.169136 0 0.996195 0.0871558 0 0.996195 0.0871558 0 0.965926 0.258819 0 0.965926 0.258819 0 0.906308 0.422618 0 0.906308 0.422618 0 0.819152 0.573576 0 0.819152 0.573576 0 0.707107 0.707107 0 0.707107 0.707107 0 0.573576 0.819152 0 0.573576 0.819152 0 0.422618 0.906308 0 0.422618 0.906308 0 0.258819 0.965926 0 0.258819 0.965926 0 0.0871559 0.996195 0 0.0871559 0.996195 0 -0.0871559 0.996195 0 -0.0871559 0.996195 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.422618 0.906308 0 -0.422618 0.906308 0 -0.573576 0.819152 0 -0.573576 0.819152 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.819152 0.573576 0 -0.819152 0.573576 0 -0.906308 0.422619 0 -0.906308 0.422619 0 -0.965926 0.258818 0 -0.965926 0.258818 0 -0.996195 0.0871555 0 -0.996195 0.0871555 0 -0.995734 0.0922684 0 -0.995734 0.0922684 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.18375 0.982973 0 -0.18375 0.982973 0 0 1 0 0 1 0 0.18375 0.982973 0 0.18375 0.982973 0 0.361242 0.932472 0 0.361242 0.932472 0 0.526432 0.850217 0 0.526432 0.850217 0 0.673695 0.739009 0 0.673695 0.739009 0 0.798018 0.602634 0 0.798018 0.602634 0 0.895163 0.445739 0 0.895163 0.445739 0 0.961826 0.273663 0 0.961826 0.273663 0 0.995734 0.0922682 0 0.995734 0.0922682 0 -0.995185 0.0980172 0 -0.995185 0.0980172 0 -0.95694 0.290285 0 -0.95694 0.290285 0 -0.881921 0.471397 0 -0.881921 0.471397 0 -0.77301 0.634393 0 -0.77301 0.634393 0 -0.634393 0.77301 0 -0.634393 0.77301 0 -0.471397 0.881921 0 -0.471397 0.881921 0 -0.290285 0.95694 0 -0.290285 0.95694 0 -0.0980172 0.995185 0 -0.0980172 0.995185 0 0.0980172 0.995185 0 0.0980172 0.995185 0 0.290285 0.95694 0 0.290285 0.95694 0 0.471397 0.881921 0 0.471397 0.881921 0 0.634393 0.77301 0 0.634393 0.77301 0 0.77301 0.634393 0 0.77301 0.634393 0 0.881921 0.471397 0 0.881921 0.471397 0 0.95694 0.290285 0 0.95694 0.290285 0 0.995185 0.0980175 0 0.995185 0.0980175 0 0.995185 0.0980172 0 0.995185 0.0980172 0 0.95694 0.290285 0 0.95694 0.290285 0 0.881921 0.471397 0 0.881921 0.471397 0 0.77301 0.634393 0 0.77301 0.634393 0 0.634393 0.773011 0 0.634393 0.773011 0 0.471397 0.881921 0 0.471397 0.881921 0 0.290285 0.95694 0 0.290285 0.95694 0 0.0980172 0.995185 0 0.0980172 0.995185 0 -0.0980172 0.995185 0 -0.0980172 0.995185 0 -0.290285 0.95694 0 -0.290285 0.95694 0 -0.471397 0.881921 0 -0.471397 0.881921 0 -0.634393 0.773011 0 -0.634393 0.773011 0 -0.773011 0.634393 0 -0.773011 0.634393 0 -0.881921 0.471397 0 -0.881921 0.471397 0 -0.95694 0.290285 0 -0.95694 0.290285 0 -0.995185 0.0980172 0 -0.995185 0.0980172 0.202048 -0.978539 -0.0404727 0.202048 -0.978539 -0.0404727 0.202048 -0.971855 -0.121141 0.202048 -0.971855 -0.121142 0.202211 -0.965234 -0.165631 0.148207 -0.966966 -0.207392 0.202049 -0.958531 -0.200983 0.202048 -0.93866 -0.279451 0.202047 -0.938661 -0.279451 0.202204 -0.923319 -0.326488 0.0930114 -0.924189 -0.370437 0.202046 -0.912378 -0.356011 0.202046 -0.879863 -0.430139 0.202047 -0.879862 -0.430139 0.202195 -0.854804 -0.47794 0.0930804 -0.855325 -0.509663 0.202143 -0.834332 -0.512862 0.202051 -0.797063 -0.569092 0.202055 -0.797063 -0.569091 0.202188 -0.761662 -0.615623 0.0806875 -0.760596 -0.644192 0.202164 -0.735574 -0.646576 0.20205 -0.692523 -0.692523 0.20205 -0.692523 -0.692523 0.202164 -0.646577 -0.735573 0.0806799 -0.644193 -0.760596 0.202183 -0.615624 -0.761662 0.20205 -0.569092 -0.797063 0.202046 -0.569093 -0.797064 0.202138 -0.512863 -0.834333 0.0930766 -0.509663 -0.855325 0.202198 -0.477939 -0.854804 0.202051 -0.430138 -0.879862 0.202052 -0.430138 -0.879861 0.202118 -0.364371 -0.909056 0.117738 -0.36098 -0.925112 0.202214 -0.326485 -0.923318 0.202057 -0.279452 -0.938659 0.202042 -0.279451 -0.938662 0.202076 -0.205382 -0.957593 0.1543 -0.202758 -0.966996 0.202219 -0.165628 -0.965233 0.202055 -0.121141 -0.971853 0.202049 -0.121141 -0.971854 0.20205 -0.0404732 -0.978539 0.202042 -0.0404726 -0.97854 0.202042 0.0404733 -0.97854 0.202051 0.0404725 -0.978538 0.202052 0.121141 -0.971854 0.202055 0.121141 -0.971853 0.202219 0.165628 -0.965233 0.148211 0.207392 -0.966965 0.202041 0.200984 -0.958533 0.202042 0.279452 -0.938662 0.202054 0.27945 -0.93866 0.202211 0.326486 -0.923319 0.093014 0.370437 -0.924189 0.202049 0.356011 -0.912377 0.202048 0.430138 -0.879862 0.202047 0.430139 -0.879862 0.202194 0.477941 -0.854804 0.0930814 0.509663 -0.855324 0.202143 0.512863 -0.834332 0.202051 0.569092 -0.797063 0.20205 0.569092 -0.797063 0.202183 0.615624 -0.761662 0.0806799 0.644193 -0.760596 0.202158 0.646578 -0.735574 0.202044 0.692524 -0.692524 0.20205 0.692523 -0.692523 0.202164 0.735574 -0.646576 0.080693 0.760595 -0.644192 0.202195 0.76166 -0.615622 0.202062 0.797061 -0.569091 0.202044 0.797065 -0.569092 0.202135 0.834334 -0.512863 0.0930844 0.855324 -0.509663 0.202198 0.854803 -0.477941 0.202051 0.879862 -0.430138 0.202042 0.879864 -0.430138 0.202108 0.909057 -0.364373 0.117722 0.925113 -0.36098 0.202204 0.923321 -0.326484 0.850924 -0.52484 -0.0217076 0.850924 -0.52484 -0.0217075 0.850924 -0.521254 -0.0649742 0.850924 -0.521255 -0.0649743 0.850924 -0.514109 -0.107797 0.850925 -0.514108 -0.107797 0.850925 -0.50345 -0.149884 0.850924 -0.503452 -0.149884 0.850924 -0.489355 -0.190947 0.850924 -0.489355 -0.190947 0.850924 -0.471915 -0.230705 0.850925 -0.471914 -0.230705 0.850925 -0.451251 -0.268887 0.850924 -0.451251 -0.268888 0.850924 -0.427506 -0.305233 0.850924 -0.427506 -0.305233 0.850924 -0.40084 -0.339494 0.850924 -0.400839 -0.339494 0.850924 -0.371435 -0.371435 0.850923 -0.371436 -0.371436 0.850923 -0.339494 -0.40084 0.850923 -0.339495 -0.400841 0.850923 -0.305234 -0.427507 0.850926 -0.305231 -0.427503 0.850926 -0.268886 -0.451248 0.850923 -0.268888 -0.451253 0.850923 -0.230706 -0.471916 0.850925 -0.230705 -0.471913 0.850925 -0.190946 -0.489353 0.850925 -0.190946 -0.489353 0.850925 -0.149883 -0.50345 0.850924 -0.149883 -0.503451 0.850924 -0.107797 -0.514108 0.850924 -0.107797 -0.514109 0.850924 -0.0649747 -0.521255 0.850923 -0.0649747 -0.521257 0.850923 -0.0217073 -0.524842 0.850926 -0.0217076 -0.524837 0.850926 0.0217071 -0.524837 0.850922 0.0217079 -0.524843 0.850922 0.064975 -0.521258 0.850924 0.0649745 -0.521255 0.850924 0.107797 -0.51411 0.850925 0.107797 -0.514107 0.850925 0.149883 -0.503449 0.850924 0.149884 -0.503451 0.850924 0.190947 -0.489354 0.850926 0.190946 -0.489352 0.850926 0.230704 -0.471912 0.850923 0.230706 -0.471916 0.850923 0.268889 -0.451253 0.850925 0.268887 -0.45125 0.850925 0.305232 -0.427505 0.850923 0.305234 -0.427507 0.850923 0.339495 -0.400841 0.850925 0.339493 -0.400838 0.850925 0.371434 -0.371434 0.850925 0.371434 -0.371434 0.850925 0.400838 -0.339493 0.850921 0.400843 -0.339497 0.850921 0.42751 -0.305236 0.850926 0.427503 -0.305231 0.850926 0.451248 -0.268886 0.850924 0.451252 -0.268888 0.850923 0.471916 -0.230705 0.850927 0.47191 -0.230703 0.850927 0.489349 -0.190945 0.850927 0.48935 -0.190945 0.850927 0.503446 -0.149882 0.85093 0.503443 -0.149881 0.85093 0.5141 -0.107796 0.850922 0.514113 -0.107798 0.573244 -0.818685 -0.0338611 0.573243 -0.818685 -0.0338611 0.573243 -0.813093 -0.101352 0.573244 -0.813092 -0.101352 0.573244 -0.801946 -0.16815 0.573242 -0.801947 -0.168151 0.573242 -0.785322 -0.233801 0.573245 -0.78532 -0.2338 0.573245 -0.763331 -0.297853 0.573245 -0.763331 -0.297853 0.573245 -0.736127 -0.359871 0.573243 -0.736129 -0.359872 0.573242 -0.703897 -0.419431 0.573242 -0.703897 -0.419432 0.573241 -0.666857 -0.476126 0.573241 -0.666857 -0.476127 0.573241 -0.625261 -0.529569 0.573241 -0.625261 -0.529569 0.573241 -0.579394 -0.579394 0.573247 -0.579391 -0.579391 0.573247 -0.529567 -0.625257 0.573243 -0.529568 -0.62526 0.573243 -0.476126 -0.666856 0.573242 -0.476126 -0.666856 0.573242 -0.419432 -0.703897 0.573246 -0.419431 -0.703895 0.573245 -0.359871 -0.736127 0.573242 -0.359871 -0.736129 0.573242 -0.297853 -0.763333 0.573242 -0.297853 -0.763333 0.573242 -0.2338 -0.785322 0.573244 -0.2338 -0.785321 0.573244 -0.168151 -0.801945 0.573238 -0.168151 -0.80195 0.573238 -0.101352 -0.813097 0.573246 -0.101352 -0.813091 0.573246 -0.0338609 -0.818683 0.573242 -0.0338606 -0.818686 0.573242 0.033861 -0.818686 0.573246 0.0338604 -0.818683 0.573246 0.101351 -0.813091 0.573238 0.101353 -0.813096 0.573239 0.168152 -0.801949 0.573244 0.16815 -0.801945 0.573244 0.2338 -0.785321 0.573244 0.2338 -0.785321 0.573244 0.297853 -0.763331 0.573242 0.297854 -0.763333 0.573242 0.359872 -0.736129 0.573245 0.35987 -0.736127 0.573246 0.41943 -0.703895 0.573245 0.41943 -0.703895 0.573246 0.476125 -0.666854 0.573247 0.476124 -0.666854 0.573247 0.529567 -0.625258 0.573243 0.529569 -0.625259 0.573243 0.579393 -0.579393 0.573243 0.579393 -0.579393 0.573243 0.62526 -0.529568 0.573243 0.62526 -0.529568 0.573243 0.666856 -0.476125 0.573239 0.666859 -0.476127 0.573239 0.703898 -0.419433 0.573237 0.7039 -0.419434 0.573237 0.736133 -0.359873 0.573237 0.736133 -0.359873 0.573236 0.763337 -0.297855 0.573242 0.763333 -0.297854 0.573242 0.785322 -0.2338 0.573239 0.785324 -0.2338 0.573239 0.801949 -0.168153 0.573238 0.80195 -0.168153 0.202047 0.938661 -0.279452 0.202032 0.938664 -0.279452 0.202066 0.957595 -0.20538 0.154325 0.966992 -0.202759 0.202227 0.965229 -0.165641 0.85092 0.521262 -0.0649745 0.850922 0.521259 -0.0649744 0.573234 0.813099 -0.101352 0.573238 0.813097 -0.101352 0.202059 0.971852 -0.121141 0.202063 0.971852 -0.121141 0.850921 0.524845 -0.021708 0.85092 0.524847 -0.0217079 0.573255 0.818677 -0.0338608 0.573234 0.818692 -0.0338593 0.202033 0.978542 -0.0404704 0.202059 0.978537 -0.0404724 0 0.998027 0.0627906 0 0.998027 0.0627906 0 0.988756 0.149535 0 0.988756 0.149535 0 0.977416 0.211325 0 0.977416 0.211325 0 0.955278 0.295708 0 0.955278 0.295708 0 0.934826 0.355107 0 0.934826 0.355107 0 0.904827 0.425779 0 0.904827 0.425779 0 0.871214 0.490903 0 0.871214 0.490903 0 0.838671 0.544639 0 0.838671 0.544639 0 0.788011 0.615662 0 0.788011 0.615662 0 0.747798 0.663926 0 0.747798 0.663926 0 0.687087 0.726575 0 0.687087 0.726575 0 0.640108 0.768285 0 0.640108 0.768285 0 0.587785 0.809017 0 0.587785 0.809017 0 0.518027 0.855365 0 0.518027 0.855365 0 0.463296 0.886203 0 0.463296 0.886203 0 0.384295 0.92321 0 0.384295 0.92321 0 0.325568 0.945518 0 0.325568 0.945518 0 0.24869 0.968583 0 0.24869 0.968583 0 0.180517 0.983572 0 0.180517 0.983572 0 0.118404 0.992966 0 0.118404 0.992966 0 0.0314108 0.999507 0 0.0314108 0.999507 0 -0.0314108 0.999507 0 -0.0314108 0.999507 0 -0.118404 0.992966 0 -0.118404 0.992966 0 -0.180517 0.983572 0 -0.180517 0.983572 0 -0.24869 0.968583 0 -0.24869 0.968583 0 -0.325568 0.945518 0 -0.325568 0.945518 0 -0.384295 0.92321 0 -0.384295 0.92321 0 -0.463296 0.886203 0 -0.463296 0.886203 0 -0.518027 0.855364 0 -0.518027 0.855364 0 -0.587785 0.809017 0 -0.587785 0.809017 0 -0.640108 0.768285 0 -0.640108 0.768285 0 -0.687088 0.726574 0 -0.687088 0.726574 0 -0.747798 0.663926 0 -0.747798 0.663926 0 -0.78801 0.615662 0 -0.78801 0.615662 0 -0.838671 0.544639 0 -0.838671 0.544639 0 -0.871214 0.490904 0 -0.871214 0.490904 0 -0.904827 0.42578 0 -0.904827 0.42578 0 -0.934825 0.355108 0 -0.934825 0.355108 0 -0.955279 0.295707 0 -0.955279 0.295707 0 -0.977416 0.211324 0 -0.977416 0.211324 0 -0.988756 0.149539 0 -0.988756 0.149539 0 -0.998027 0.0627888 0 -0.998027 0.0627888 -0.195028 -0.733438 0.651178 -0.83098 -0.503358 0.236862 -0.830973 0.138349 0.538835 -0.830977 0.503362 0.236864 -0.965802 -0.258769 0.0162803 -0.980721 -0.191954 0.0366173 -0.980724 0.195013 0.0122692 -0.980724 0.195013 0.0122692 -0.980724 0.176801 0.0831965 -0.980724 0.176802 0.0831969 -0.980724 0.185836 0.0603817 -0.980724 0.0485935 0.189259 -0.980723 0.0485945 0.189263 -0.980723 0.0719323 0.18168 -0.980722 -0.17681 0.0832005 -0.980724 -0.176802 0.0831964 -0.980724 -0.16498 0.1047 -0.896492 0.442185 0.0278199 -0.830995 0.555137 0.0356361 -0.792811 0.608266 0.0382688 -0.554774 0.702482 0.445808 -0.830976 0.469707 0.298085 -0.830974 0.469709 0.298086 -0.980724 0.16498 0.1047 -0.980724 0.16498 0.104699 -0.554773 0.104277 0.825441 -0.830973 0.0697245 0.551927 -0.830979 0.0697231 0.551917 -0.980724 0.0244898 0.193857 -0.980724 0.0244898 0.193857 -0.554775 -0.791279 0.257103 -0.83098 -0.529075 0.171907 -0.831001 -0.529046 0.171897 -0.980722 -0.185844 0.0603844 -0.980722 -0.185844 0.0603845 -0.554785 0.791273 0.2571 -0.195081 0.854476 0.481471 -0.19472 0.887508 0.417629 -0.554785 0.752811 0.354246 -0.554785 0.791273 0.2571 -0.830973 0.529085 0.17191 -0.554783 0.56954 0.606498 -0.195046 0.508077 0.838937 -0.194718 0.576535 0.793532 -0.554764 0.489042 0.673109 -0.554765 0.569549 0.606507 -0.830971 0.380825 0.405537 -0.980723 0.133761 0.142441 -0.980723 0.114854 0.158083 -0.830975 0.326991 0.450064 -0.830975 0.268004 0.487498 -0.554767 0.400822 0.729092 -0.554768 0.306282 0.773579 -0.980724 0.114854 0.158082 -0.980724 0.0941349 0.171231 -0.830979 0.268001 0.487493 -0.830979 0.204789 0.517238 -0.554791 0.306276 0.773565 -0.554792 0.206907 0.805851 -0.194742 0.243928 0.950039 -0.195109 0.177048 0.964669 -0.554779 -0.104277 0.825437 -0.195069 -0.319314 0.927355 -0.194728 -0.243929 0.950042 -0.554774 -0.20691 0.805862 -0.554771 -0.104278 0.825442 -0.830979 -0.0697233 0.551917 -0.980724 -0.0244897 0.193857 -0.980724 -0.0485931 0.189258 -0.830968 -0.138351 0.538842 -0.830967 -0.204796 0.517255 -0.554784 -0.306277 0.773569 -0.554787 -0.400815 0.72908 -0.980724 -0.0485941 0.189261 -0.980724 -0.0719315 0.181678 -0.830979 -0.204789 0.517238 -0.830979 -0.268001 0.487493 -0.554798 -0.400812 0.729074 -0.554797 -0.489029 0.67309 -0.19476 -0.57653 0.793525 -0.195128 -0.627804 0.753517 -0.980723 -0.114854 0.158083 -0.980724 -0.133761 0.142441 -0.830964 -0.380832 0.405544 -0.830964 -0.428657 0.354616 -0.554755 -0.641077 0.530346 -0.554756 -0.702492 0.445815 -0.980724 -0.133758 0.142438 -0.980724 -0.150555 0.12455 -0.83099 -0.428627 0.354591 -0.830991 -0.469688 0.298073 -0.554793 -0.702472 0.445801 -0.554792 -0.752806 0.354244 -0.194742 -0.887504 0.417628 -0.195094 -0.916862 0.348285 -0.607974 0.79239 0.0498529 -0.554804 0.830295 0.0529461 -0.441568 0.895457 0.0563374 -0.194725 0.978923 0.0615886 -0.19473 0.978921 0.0615886 -0.980724 0.191938 0.0366141 -0.830973 0.54646 0.104243 -0.830975 0.546457 0.104242 -0.554785 0.817257 0.1559 -0.554783 0.817258 0.1559 -0.751908 0.64759 0.123534 -0.195039 0.969768 0.146664 -0.194727 0.887506 0.417629 -0.19508 0.916865 0.348285 -0.662131 0.712711 0.231574 -0.194879 0.936963 0.290039 -0.194964 0.95866 0.207269 -0.980724 0.191936 0.0366137 -0.980724 0.185833 0.0603809 -0.830971 0.529087 0.171911 -0.830971 0.50337 0.236868 -0.554782 0.752812 0.354246 -0.554783 0.702477 0.445805 -0.599477 0.675794 0.428872 -0.194863 0.822594 0.534198 -0.980724 0.150557 0.124551 -0.830971 0.428649 0.354609 -0.830975 0.428644 0.354605 -0.554782 0.641064 0.530334 -0.554772 0.641069 0.530338 -0.762151 0.49883 0.412668 -0.195008 0.772882 0.603842 -0.194742 0.576532 0.793528 -0.195109 0.627806 0.75352 -0.376551 0.634161 0.675313 -0.194784 0.673927 0.712658 -0.19504 0.733437 0.651176 -0.980724 0.150559 0.124553 -0.980724 0.133761 0.142441 -0.830983 0.380812 0.405524 -0.830983 0.326984 0.450055 -0.554785 0.489033 0.673097 -0.554787 0.400815 0.729081 -0.733547 0.327418 0.595572 -0.194728 0.243929 0.950042 -0.195069 0.319314 0.927355 -0.704861 0.261128 0.659533 -0.194918 0.376924 0.905503 -0.194946 0.454408 0.869201 -0.980724 0.0941328 0.171227 -0.980724 0.0719303 0.181675 -0.830974 0.204792 0.517245 -0.830973 0.138349 0.538835 -0.554769 0.206911 0.805866 -0.554768 0.104278 0.825444 -0.508108 0.107949 0.854502 -0.194807 0.116136 0.973942 -0.980724 0 0.195399 -0.83098 0 0.556302 -0.83098 0 0.556302 -0.554774 0 0.832001 -0.554774 0 0.832001 -0.765439 0 0.643508 -0.195009 0.0308077 0.980317 -0.194743 -0.243928 0.950039 -0.195109 -0.177048 0.964669 -0.508108 -0.107949 0.854502 -0.194807 -0.116136 0.973942 -0.195009 -0.0308077 0.980317 -0.980724 0 0.195399 -0.980724 -0.02449 0.193859 -0.83097 -0.0697247 0.55193 -0.830968 -0.138351 0.538842 -0.554803 -0.206906 0.805843 -0.554806 -0.306272 0.773555 -0.704861 -0.261128 0.659533 -0.1947 -0.576536 0.793535 -0.19503 -0.50808 0.838939 -0.733547 -0.327418 0.595572 -0.194946 -0.454408 0.869201 -0.194918 -0.376924 0.905503 -0.980723 -0.071932 0.181679 -0.980723 -0.0941357 0.171232 -0.83098 -0.268 0.487491 -0.830981 -0.326986 0.450057 -0.554776 -0.489037 0.673102 -0.55478 -0.569541 0.6065 -0.376569 -0.634157 0.675308 -0.194772 -0.673929 0.712659 -0.980723 -0.0941364 0.171233 -0.980723 -0.114855 0.158085 -0.830971 -0.326994 0.450069 -0.83097 -0.380826 0.405538 -0.554791 -0.569536 0.606494 -0.554791 -0.641059 0.53033 -0.762151 -0.49883 0.412668 -0.194733 -0.887505 0.417628 -0.195094 -0.854473 0.481471 -0.599477 -0.675794 0.428872 -0.194876 -0.822592 0.534197 -0.19502 -0.77288 0.603841 -0.980724 -0.150559 0.124553 -0.980724 -0.164982 0.104701 -0.830972 -0.469711 0.298088 -0.830972 -0.503368 0.236867 -0.554806 -0.752798 0.35424 -0.554806 -0.79126 0.257096 -0.662142 -0.712701 0.231571 -0.194835 -0.936972 0.29004 -0.195115 -0.969752 0.146665 -0.980722 -0.191947 0.0366159 -0.830975 -0.546457 0.104242 -0.831002 -0.546417 0.104234 -0.5548 -0.817247 0.155897 -0.554774 -0.817264 0.155901 -0.751901 -0.647599 0.123536 -0.19492 -0.958668 0.207271 -0.980703 -0.195203 0.0108713 -0.792809 -0.6082 0.0393262 -0.830975 -0.555213 0.0349318 -0.607914 -0.792436 0.0498569 -0.554821 -0.830284 0.0529455 -0.258343 -0.964213 0.059605 -0.194801 -0.978907 0.0615859 0.195016 0.733441 0.651179 0.194985 -0.0308079 0.980322 0.830971 0.50337 0.236868 0.830972 -0.503368 0.236867 0.965805 0.25876 0.0162798 0.980699 0.192058 0.0366371 0.980696 -0.195153 0.0122779 0.980697 -0.195147 0.0122776 0.9807 -0.176912 0.0832487 0.980698 -0.176921 0.0832525 0.980698 -0.185961 0.0604223 0.980699 0.176913 0.0832492 0.9807 0.176912 0.0832487 0.9807 0.165084 0.104765 0.896648 -0.441871 0.0278003 0.830995 -0.555137 0.0356381 0.792749 -0.608345 0.0382746 0.554814 -0.702459 0.445794 0.830972 -0.469712 0.298088 0.830991 -0.469688 0.298073 0.9807 -0.165083 0.104765 0.980699 -0.165085 0.104766 0.554844 0.791236 0.257088 0.830971 0.529088 0.171911 0.830972 0.529086 0.17191 0.980699 0.185952 0.0604196 0.9807 0.18595 0.0604187 0.554834 -0.791242 0.25709 0.195069 -0.854477 0.481473 0.19471 -0.887509 0.41763 0.554864 -0.752763 0.354223 0.554864 -0.791222 0.257085 0.831001 -0.529046 0.171898 0.554849 -0.56951 0.606466 0.195005 -0.508082 0.838943 0.194676 -0.57654 0.793538 0.554836 -0.489014 0.673069 0.554838 -0.569515 0.606471 0.830964 -0.380832 0.405544 0.980699 -0.133846 0.142531 0.980699 -0.114926 0.158182 0.83098 -0.326986 0.450058 0.83098 -0.268001 0.487492 0.554847 -0.400796 0.729046 0.554843 -0.306263 0.773532 0.980698 -0.114928 0.158184 0.980699 -0.0941954 0.171341 0.830979 -0.268001 0.487493 0.830979 -0.204789 0.517238 0.554866 -0.306257 0.773518 0.554861 -0.206895 0.805806 0.194717 -0.243929 0.950044 0.195085 -0.177049 0.964674 0.9807 -0.0486235 0.189376 0.9807 -0.0245051 0.193978 0.830979 -0.069723 0.551917 0.83098 0 0.556302 0.554832 0 0.831962 0.554832 0.104273 0.825402 0.980699 -0.0245054 0.19398 0.980699 0 0.195521 0.83098 0 0.556302 0.830979 0.0697233 0.551917 0.554827 0.104273 0.825405 0.554827 0.206901 0.805828 0.194704 0.24393 0.950047 0.195045 0.319316 0.927359 0.9807 0.0245052 0.193979 0.9807 0.048624 0.189378 0.830973 0.138349 0.538835 0.830974 0.204792 0.517245 0.554826 0.306267 0.773543 0.554825 0.400803 0.729058 0.980699 0.0486249 0.189382 0.980699 0.0719774 0.181794 0.83098 0.204789 0.517237 0.830979 0.268001 0.487493 0.554845 0.400797 0.729046 0.554843 0.489011 0.673066 0.194717 0.576535 0.793532 0.195084 0.627809 0.753524 0.980699 0.114926 0.158182 0.980699 0.133845 0.142531 0.830971 0.380825 0.405537 0.830971 0.428648 0.354609 0.554832 0.641038 0.530313 0.554833 0.702448 0.445787 0.980699 0.133845 0.14253 0.980699 0.150653 0.124631 0.830975 0.428644 0.354605 0.830974 0.469709 0.298086 0.554841 0.702444 0.445785 0.554841 0.752777 0.35423 0.194703 0.887511 0.417631 0.195055 0.91687 0.348287 0.608006 -0.792366 0.0498525 0.554879 -0.830245 0.0529434 0.441644 -0.89542 0.0563355 0.194777 -0.978912 0.0615884 0.194644 -0.978939 0.0615879 0.980696 -0.192075 0.0366402 0.831002 -0.546417 0.104235 0.830975 -0.546457 0.104241 0.554833 -0.817226 0.155893 0.554859 -0.817209 0.15589 0.751858 -0.647646 0.123545 0.19509 -0.969757 0.146666 0.194717 -0.887508 0.41763 0.19507 -0.916867 0.348287 0.662094 -0.712742 0.231584 0.194811 -0.936976 0.290042 0.194895 -0.958673 0.207272 0.980698 -0.192068 0.036639 0.980698 -0.185961 0.0604224 0.83098 -0.529074 0.171907 0.83098 -0.503358 0.236862 0.554851 -0.75277 0.354227 0.554851 -0.702438 0.445781 0.599427 -0.675825 0.428892 0.194851 -0.822596 0.534199 0.980699 -0.150653 0.124631 0.830964 -0.428657 0.354615 0.83099 -0.428626 0.354591 0.554848 -0.641029 0.530306 0.554814 -0.641047 0.53032 0.76211 -0.498867 0.412699 0.194995 -0.772884 0.603844 0.194734 -0.576532 0.79353 0.195104 -0.627807 0.753521 0.376527 -0.634168 0.675321 0.194749 -0.673932 0.712663 0.195004 -0.733442 0.651181 0.9807 -0.15065 0.124628 0.9807 -0.133842 0.142527 0.83097 -0.380825 0.405538 0.830971 -0.326994 0.450069 0.554856 -0.489006 0.673059 0.554856 -0.400793 0.72904 0.733503 -0.327441 0.595613 0.194704 -0.24393 0.950047 0.195045 -0.319316 0.927359 0.704815 -0.261144 0.659575 0.194894 -0.376926 0.905507 0.194922 -0.45441 0.869205 0.980699 -0.0941947 0.171339 0.980699 -0.0719771 0.181793 0.830967 -0.204796 0.517255 0.830968 -0.138351 0.538842 0.554833 -0.206901 0.805824 0.55483 -0.104273 0.825404 0.508059 -0.107952 0.85453 0.194783 -0.116136 0.973947 0.980699 -0.0719766 0.181792 0.980699 -0.0486246 0.18938 0.830968 -0.138351 0.538842 0.83097 -0.069725 0.55193 0.554838 -0.104272 0.825398 0.554833 0 0.831962 0.765398 0 0.643557 0.194717 0.24393 0.950044 0.195085 0.177049 0.964674 0.508059 0.107952 0.85453 0.194783 0.116136 0.973947 0.194985 0.0308079 0.980322 0.980699 0 0.195521 0.9807 0.0245052 0.193979 0.830973 0.0697243 0.551926 0.830973 0.138349 0.538835 0.554851 0.206898 0.805813 0.554849 0.306262 0.773529 0.704815 0.261144 0.659575 0.194695 0.576537 0.793536 0.195021 0.50808 0.838941 0.733503 0.327441 0.595613 0.194922 0.45441 0.869205 0.194894 0.376926 0.905507 0.9807 0.0719755 0.181789 0.9807 0.094192 0.171335 0.830975 0.268004 0.487498 0.830975 0.32699 0.450064 0.554822 0.489019 0.673077 0.554823 0.569521 0.606479 0.37651 0.634173 0.675326 0.19476 0.67393 0.712661 0.980699 0.0941941 0.171339 0.980699 0.114926 0.158181 0.830983 0.326984 0.450055 0.830983 0.380812 0.405524 0.554841 0.569514 0.60647 0.554841 0.641033 0.530309 0.76211 0.498867 0.412699 0.194697 0.887512 0.417631 0.195056 0.85448 0.481474 0.599427 0.675825 0.428892 0.194839 0.822598 0.534201 0.194983 0.772886 0.603845 0.9807 0.150651 0.124629 0.9807 0.165083 0.104765 0.830977 0.469706 0.298084 0.830976 0.503362 0.236864 0.554844 0.752775 0.354229 0.554843 0.791236 0.257088 0.662082 0.712751 0.231587 0.194855 0.936968 0.29004 0.195015 0.969773 0.146664 0.9807 0.192056 0.0366366 0.830975 0.546456 0.104242 0.830972 0.54646 0.104243 0.554842 0.817219 0.155893 0.554844 0.817218 0.155893 0.751866 0.647638 0.123544 0.19494 0.958664 0.20727 0.980681 0.195309 0.0108804 0.792686 0.60836 0.0393386 0.830975 0.555213 0.034931 0.608066 0.79232 0.0498485 0.554863 0.830255 0.052944 0.258342 0.964213 0.059605 0.1947 0.978927 0.0615889 -0.705594 -0.705594 0.0653828 -0.705581 -0.705606 0.0653844 -0.705582 -0.681577 0.193925 -0.705589 -0.68157 0.193923 -0.705589 -0.634332 0.31586 -0.705591 -0.63433 0.315859 -0.705591 -0.56549 0.427039 -0.705593 -0.565489 0.427038 -0.705592 -0.477393 0.523675 -0.705579 -0.477402 0.523685 -0.705581 -0.373045 0.602489 -0.705582 -0.373045 0.602488 -0.705582 -0.255986 0.660776 -0.70559 -0.255983 0.660769 -0.70559 -0.130209 0.696555 -0.705588 -0.130209 0.696557 -0.705587 0 0.708623 -0.705587 0 0.708623 -0.705585 0.13021 0.696559 -0.70559 0.130209 0.696555 -0.70559 0.255983 0.660769 -0.705582 0.255986 0.660776 -0.705582 0.373045 0.602488 -0.705588 0.373042 0.602483 -0.705588 0.477396 0.523678 -0.705588 0.477396 0.523678 -0.705587 0.565493 0.427041 -0.705588 0.565493 0.42704 -0.705588 0.634333 0.31586 -0.705586 0.634334 0.315861 -0.705586 0.681573 0.193924 -0.705585 0.681574 0.193925 -0.705585 0.705603 0.0653837 -0.705587 0.7056 0.0653836 0.705587 0.7056 0.0653835 0.705585 0.705603 0.0653838 0.705585 0.681574 0.193925 0.705586 0.681573 0.193924 0.705586 0.634334 0.315861 0.705588 0.634333 0.31586 0.705588 0.565493 0.42704 0.705587 0.565493 0.427041 0.705588 0.477396 0.523678 0.705588 0.477396 0.523678 0.705588 0.373042 0.602483 0.705582 0.373044 0.602488 0.705582 0.255986 0.660776 0.70559 0.255983 0.660769 0.70559 0.130209 0.696555 0.705585 0.13021 0.696559 0.705587 0 0.708623 0.705587 0 0.708623 0.705588 -0.130209 0.696557 0.70559 -0.130209 0.696555 0.70559 -0.255983 0.660769 0.705582 -0.255986 0.660776 0.705582 -0.373044 0.602488 0.705581 -0.373045 0.602489 0.705579 -0.477402 0.523685 0.705592 -0.477393 0.523675 0.705593 -0.565489 0.427038 0.705591 -0.56549 0.427039 0.705591 -0.63433 0.315859 0.705589 -0.634331 0.315859 0.705589 -0.68157 0.193923 0.705582 -0.681577 0.193925 0.705581 -0.705606 0.0653839 0.705594 -0.705594 0.0653832 0 0.991445 -0.130526 0 0.991445 -0.130526 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707105 0.707109 0 -0.707105 0.707109 0 -0.965928 0.258811 0 -0.965928 0.258811 0 0.991446 -0.130517 0 0.991446 -0.130517 0 0.995793 -0.0916275 0.023072 0.971084 -0.23762 0.0179384 0.751717 -0.659242 0.00299074 0.792403 -0.609991 -0.00272128 0.941902 -0.335877 0.00102434 0.206942 -0.978353 0.0151653 0.355761 -0.934454 0.0168069 0.362389 -0.931875 -0.00290407 0.537061 -0.843539 0.00305551 0.655781 -0.754945 -0.00245921 -0.0178273 -0.999838 0.0182314 -0.10885 -0.993891 -0.000101903 -0.266284 -0.963894 0.000132016 -0.438855 -0.898558 0.0217734 -0.555439 -0.831272 -0.000127312 -0.639689 -0.768634 5.1042e-05 -0.772842 -0.634598 0.0174294 -0.876594 -0.480915 0 -0.901291 -0.433214 0 0.990005 -0.141031 0.0190913 0.972192 -0.233405 0.00602296 0.945172 -0.326516 0.00266448 0.66842 -0.743779 0.0195396 0.775128 -0.631502 0.0137661 0.760334 -0.649387 -3.08793e-05 0.864787 -0.502139 2.54046e-05 0.91102 -0.412363 -0.00491788 0.484185 -0.874952 0.0185597 0.382617 -0.923721 -0.000114266 0.242872 -0.970058 0.000122703 0.0605033 -0.998168 0.0205992 -0.0784431 -0.996706 -0.000123935 -0.173937 -0.984757 4.47399e-05 -0.356049 -0.934467 0.0160163 -0.522431 -0.852531 0 -0.563935 -0.825819 0 0.999578 -0.0290659 0.00524488 0.987321 -0.15865 0.0176949 0.973723 -0.227048 0.00601339 0.950772 -0.309832 -0.0077379 0.856578 -0.515959 0.0184406 0.772881 -0.634283 -0.000130492 0.6859 -0.727696 0.000103271 0.540535 -0.841321 0.0186163 0.412636 -0.910706 -0.0106292 0.291364 -0.956553 0.0138944 -0.0327162 -0.999368 0 -0.0754724 -0.997148 0 0.995573 -0.0939954 0.0162593 0.97673 -0.213858 -0.000138423 0.952192 -0.305501 7.32651e-05 0.879836 -0.475278 0.015228 0.795647 -0.605569 -0.00884475 0.731102 -0.682211 0.0107835 0.462881 -0.886355 0 0.433204 -0.901296 0 0.999574 -0.0291756 0.00755006 0.980756 -0.19509 -0.00292591 0.972087 -0.234601 0.00327959 0.831466 -0.555566 0 0.825815 -0.563942 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.25882 0 -0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707106 0.707108 0 0.707106 0.707108 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258818 0 -0.965926 0.258818 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707106 0.707107 0 0.707106 0.707107 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258818 0 -0.965926 0.258818 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707106 0.707107 0 0.707106 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258818 0 -0.965926 0.258818 0 0.965925 0.258821 0 0.965925 0.258821 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258816 0.965927 0 0.258816 0.965927 0 -0.258816 0.965927 0 -0.258816 0.965927 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.965925 0.258821 0 0.965925 0.258821 0 0.707105 0.707109 0 0.707105 0.707109 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707105 0.707109 0 -0.707105 0.707109 0 -0.965925 0.258821 0 -0.965925 0.258821 0 0.965925 0.258821 0 0.965925 0.258821 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.965928 0.258813 0 -0.965928 0.258813 0 0.965925 0.258821 0 0.965925 0.258821 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258814 0.965927 0 0.258814 0.965927 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965925 0.258821 0 -0.965925 0.258821 0 0.965928 0.258812 0 0.965928 0.258812 0 0.707103 0.70711 0 0.707103 0.70711 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707103 0.70711 0 -0.707103 0.70711 0 -0.965928 0.258812 0 -0.965928 0.258812 0 0.965928 0.258812 0 0.965928 0.258812 0 0.707103 0.70711 0 0.707103 0.70711 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707103 0.70711 0 -0.707103 0.70711 0 -0.965928 0.258812 0 -0.965928 0.258812 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.25882 0 -0.965926 0.25882 -4.19122e-07 0.739336 -0.673336 1.55998e-06 0.572235 -0.820089 -0.00260922 0.522513 -0.852628 0.00577312 0.370608 -0.928771 0 0.314076 -0.949398 0 0.997736 -0.0672538 -0.0102425 0.972286 -0.233568 -0.00864794 0.974681 -0.223431 7.8087e-07 0.92327 -0.384151 2.00827e-06 0.873116 -0.487512 0.00290112 0.845433 -0.534073 -0.00842708 0.702047 -0.712081 0 0.999756 -0.0220745 0.00295976 0.98579 -0.167957 -0.00516232 0.973848 -0.227142 0.00508045 0.864915 -0.501893 0.0128235 0.830141 -0.557406 0 0.740652 -0.671889 0 0.987119 -0.159987 0 0.987119 -0.159987 0.000261548 0.892875 -0.450304 -0.00199038 0.78089 -0.624666 -0.00249221 0.782761 -0.622318 0.00317882 0.462908 -0.886401 -0.0137237 0.532246 -0.846478 0 0.321765 -0.94682 1.60541e-06 0.898101 -0.43979 4.41753e-06 0.976859 -0.213883 0 0.976854 -0.213908 0 0.744944 -0.667127 -0.0109812 0.874106 -0.485611 0.0053116 0.832109 -0.554587 -0.00401896 0.981007 -0.193933 0 0.985778 -0.168056 0.705425 0.705372 0.0694734 0.705409 0.705388 0.0694743 0.705409 0.67828 0.205754 0.705417 0.678272 0.205752 0.705417 0.625099 0.334122 0.705423 0.625094 0.33412 0.705423 0.547899 0.44965 0.705414 0.547907 0.449655 0.705414 0.449655 0.547906 0.705422 0.44965 0.5479 0.705421 0.334121 0.625096 0.705418 0.334122 0.625098 0.705418 0.205751 0.678272 0.705416 0.205752 0.678273 0.705415 0.069474 0.705381 0.705418 0.0694736 0.705378 0.705418 -0.0694737 0.705379 0.705415 -0.0694739 0.705382 0.705414 -0.205752 0.678275 0.705416 -0.205752 0.678274 0.705416 -0.334123 0.6251 0.705417 -0.334123 0.625099 0.705418 -0.449653 0.547903 0.705418 -0.449653 0.547903 0.705419 -0.547902 0.449652 0.705418 -0.547903 0.449653 0.705418 -0.625099 0.334122 0.70542 -0.625097 0.334121 0.70542 -0.67827 0.205751 0.705419 -0.678271 0.205751 0.705419 -0.705378 0.0694737 0.705418 -0.705378 0.0694738 0.705587 0.7056 0.0653835 0.705585 0.705603 0.0653838 0.705585 0.681574 0.193925 0.705586 0.681573 0.193924 0.705586 0.634334 0.315861 0.705588 0.634333 0.31586 0.705588 0.565493 0.42704 0.705587 0.565493 0.427041 0.705588 0.477396 0.523678 0.705588 0.477396 0.523678 0.705588 0.373042 0.602483 0.705582 0.373044 0.602488 0.705582 0.255986 0.660776 0.70559 0.255983 0.660769 0.70559 0.130209 0.696555 0.705585 0.13021 0.696559 0.705587 0 0.708623 0.705587 0 0.708623 0.705588 -0.130209 0.696557 0.70559 -0.130209 0.696555 0.70559 -0.255983 0.660769 0.705582 -0.255986 0.660776 0.705582 -0.373044 0.602488 0.705581 -0.373045 0.602489 0.705579 -0.477402 0.523685 0.705592 -0.477393 0.523675 0.705593 -0.565489 0.427038 0.705591 -0.56549 0.427039 0.705591 -0.63433 0.315859 0.705589 -0.634331 0.315859 0.705589 -0.68157 0.193923 0.705582 -0.681577 0.193925 0.705581 -0.705606 0.0653839 0.705594 -0.705594 0.0653832 0.705751 0.705764 0.0617464 0.705752 0.705763 0.0617463 0.705752 0.684319 0.183363 0.705753 0.684318 0.183362 0.705754 0.64208 0.299407 0.705752 0.642082 0.299408 0.705752 0.580336 0.406355 0.705752 0.580336 0.406356 0.705751 0.500957 0.500957 0.705751 0.500957 0.500957 0.70575 0.406356 0.580337 0.705757 0.406353 0.580332 0.705756 0.299406 0.642078 0.705749 0.299409 0.642084 0.705749 0.183363 0.684322 0.705754 0.183362 0.684317 0.705755 0.0617461 0.70576 0.705751 0.0617463 0.705764 0.705751 -0.0617465 0.705764 0.705755 -0.061746 0.70576 0.705754 -0.183362 0.684317 0.705749 -0.183363 0.684322 0.705749 -0.299409 0.642084 0.705757 -0.299406 0.642078 0.705757 -0.406353 0.580332 0.705742 -0.406361 0.580343 0.705742 -0.500964 0.500963 0.705746 -0.50096 0.50096 0.705746 -0.58034 0.406359 0.705749 -0.580338 0.406357 0.705749 -0.642084 0.299409 0.705745 -0.642089 0.299411 0.705744 -0.684327 0.183364 0.705755 -0.684316 0.183362 0.705755 -0.70576 0.0617458 0.705758 -0.705758 0.0617457 0.705758 0.705758 0.0617462 0.705729 0.705786 0.0617476 0.705729 0.684341 0.183368 0.705768 0.684303 0.183359 0.705767 0.642068 0.299402 0.70575 0.642083 0.299408 0.705751 0.580336 0.406356 0.705747 0.58034 0.406358 0.705746 0.50096 0.50096 0.705756 0.500953 0.500953 0.705755 0.406353 0.580333 0.705749 0.406357 0.580338 0.705751 0.299408 0.642083 0.705749 0.299409 0.642085 0.705749 0.183363 0.684322 0.705748 0.183364 0.684323 0.705748 0.0617468 0.705767 0.705758 0.0617456 0.705758 0.705758 -0.0617459 0.705758 0.705749 -0.0617464 0.705766 0.705749 -0.183363 0.684322 0.705751 -0.183363 0.68432 0.705752 -0.299408 0.642082 0.705757 -0.299406 0.642078 0.705757 -0.406353 0.580332 0.705755 -0.406353 0.580333 0.705756 -0.500954 0.500953 0.705751 -0.500957 0.500957 0.705752 -0.580336 0.406356 0.705751 -0.580337 0.406356 0.705751 -0.642083 0.299408 0.705749 -0.642084 0.299409 0.705749 -0.684322 0.183363 0.70575 -0.684321 0.183363 0.70575 -0.705765 0.0617465 0.705751 -0.705764 0.0617463 -0.705385 -0.705411 0.0694771 -0.705395 -0.705401 0.0694756 -0.705395 -0.678293 0.205758 -0.705389 -0.678299 0.20576 -0.705389 -0.625124 0.334136 -0.705385 -0.625127 0.334137 -0.705386 -0.547927 0.449673 -0.705398 -0.547919 0.449665 -0.705396 -0.449667 0.54792 -0.705396 -0.449667 0.547921 -0.705394 -0.334133 0.625119 -0.705386 -0.334137 0.625126 -0.705387 -0.20576 0.6783 -0.705389 -0.20576 0.678299 -0.705389 -0.0694764 0.705407 -0.705392 -0.0694763 0.705405 -0.705392 0.0694761 0.705405 -0.705389 0.0694765 0.705407 -0.705389 0.20576 0.678299 -0.705391 0.205759 0.678297 -0.705392 0.334134 0.625121 -0.705391 0.334135 0.625122 -0.705391 0.44967 0.547924 -0.705392 0.449669 0.547924 -0.705393 0.547923 0.449669 -0.705391 0.547924 0.449669 -0.705391 0.625122 0.334135 -0.705392 0.625121 0.334134 -0.705392 0.678296 0.205759 -0.705392 0.678296 0.205759 -0.705392 0.705404 0.0694762 -0.705392 0.705405 0.0694763 0.705392 0.705405 0.0694763 0.705392 0.705404 0.0694762 0.705392 0.678296 0.205759 0.705392 0.678296 0.205759 0.705392 0.625121 0.334134 0.705391 0.625122 0.334135 0.705391 0.547924 0.449669 0.705393 0.547923 0.449669 0.705392 0.449669 0.547923 0.705391 0.449669 0.547924 0.705391 0.334135 0.625122 0.705392 0.334134 0.625121 0.705391 0.205759 0.678297 0.705389 0.20576 0.678299 0.705389 0.0694764 0.705407 0.705392 0.0694762 0.705405 0.705392 -0.0694762 0.705405 0.705389 -0.0694766 0.705407 0.705389 -0.20576 0.678299 0.705387 -0.20576 0.6783 0.705386 -0.334137 0.625126 0.705394 -0.334133 0.625119 0.705396 -0.449667 0.547921 0.705396 -0.449667 0.54792 0.705398 -0.547919 0.449666 0.705386 -0.547928 0.449672 0.705385 -0.625127 0.334137 0.705389 -0.625123 0.334136 0.705389 -0.678299 0.205759 0.705395 -0.678293 0.205758 0.705395 -0.705401 0.0694761 0.705385 -0.705411 0.0694766 0.705409 0.705387 0.0694746 0.705411 0.705386 0.0694744 0.705411 0.678278 0.205753 0.70541 0.678279 0.205754 0.70541 0.625106 0.334126 0.705411 0.625105 0.334125 0.705411 0.547909 0.449657 0.705408 0.547911 0.449659 0.705408 0.449659 0.547911 0.705412 0.449656 0.547908 0.705412 0.334125 0.625104 0.705412 0.334125 0.625104 0.705412 0.205753 0.678277 0.705408 0.205754 0.678281 0.705408 0.0694747 0.705388 0.705411 0.0694746 0.705385 0.705411 -0.0694744 0.705385 0.705408 -0.0694749 0.705388 0.705408 -0.205754 0.678281 0.705412 -0.205753 0.678277 0.705412 -0.334125 0.625104 0.70541 -0.334126 0.625106 0.705409 -0.449658 0.54791 0.705402 -0.449663 0.547915 0.705402 -0.547916 0.449663 0.705407 -0.547911 0.449659 0.705407 -0.625108 0.334127 0.705416 -0.6251 0.334123 0.705416 -0.678273 0.205752 0.705404 -0.678284 0.205755 0.705404 -0.705392 0.0694751 0.705407 -0.705389 0.069475 0.705585 0.705603 0.0653836 0.70559 0.705597 0.0653834 0.70559 0.681569 0.193923 0.705585 0.681574 0.193924 0.705585 0.634335 0.315861 0.705585 0.634335 0.315861 0.705586 0.565495 0.427041 0.705592 0.56549 0.427038 0.705591 0.477394 0.523676 0.705587 0.477396 0.523679 0.705587 0.373042 0.602484 0.705588 0.373041 0.602483 0.705588 0.255984 0.660771 0.705586 0.255985 0.660773 0.705586 0.130209 0.696559 0.705587 0.130209 0.696558 0.705587 0 0.708623 0.705587 0 0.708623 0.705587 -0.130209 0.696558 0.705586 -0.130209 0.696559 0.705586 -0.255985 0.660773 0.705587 -0.255984 0.660772 0.705586 -0.373042 0.602484 0.705589 -0.373041 0.602482 0.70559 -0.477395 0.523677 0.705588 -0.477396 0.523679 0.705588 -0.565493 0.42704 0.705588 -0.565493 0.427041 0.705588 -0.634333 0.31586 0.705587 -0.634333 0.31586 0.705587 -0.681572 0.193924 0.705588 -0.681571 0.193924 0.705588 -0.705599 0.0653834 0.705587 -0.7056 0.0653836 0 -0.998943 -0.0459622 4.03504e-09 -0.998943 -0.0459622 0 -0.556602 -0.83078 0.0090647 -0.654425 -0.756073 0 -0.989667 -0.143385 -0.00119319 -0.988416 -0.151767 0.000911101 -0.918833 -0.394644 -4.86924e-05 -0.915336 -0.402692 3.19411e-05 -0.827847 -0.560954 0.00245043 -0.845872 -0.533381 -0.00422359 -0.725108 -0.688622 0 0.998943 -0.0459615 0 0.998943 -0.0459615 0 0.99695 -0.0780433 1.9812e-08 0.99695 -0.0780428 0 0.642785 -0.766047 0.00116072 0.652212 -0.758036 -0.00050245 0.819136 -0.573599 0.00379679 0.875157 -0.483824 -0.00851697 0.96589 -0.258813 0 0.985852 -0.167618 -0.701664 0.45799 -0.545814 -0.729583 0.483592 -0.483578 -0.70576 0.580318 -0.406367 -0.694753 0.694738 -0.186166 -0.694746 0.694746 -0.186159 -0.694749 0.508589 -0.508587 -0.703407 0.703442 -0.101923 -0.558636 0.801152 -0.214664 -0.704643 0.651969 -0.280028 -0.694748 0.508589 -0.508588 -0.706715 0.70675 -0.0325177 -0.706716 0.706749 -0.0325177 -0.706715 0.706751 -0.0325099 -0.706716 0.70675 -0.0325084 -0.706026 0.706026 -0.0552691 -0.706028 0.706023 -0.0552787 0.422252 -0.90552 -0.0416631 0.422252 -0.905521 -0.041663 -0.504714 0.862374 -0.0396779 -0.50471 0.862377 -0.0396777 0.706021 -0.706033 -0.055238 0.706021 -0.706033 -0.0552372 0.706726 -0.706739 -0.0325176 0.706727 -0.706739 -0.0325152 0.706727 -0.706738 -0.0325171 0.706727 -0.706738 -0.0325171 0.701798 -0.701811 -0.122233 0.732051 -0.674211 -0.0976809 0.681424 -0.663963 -0.30792 0.641139 -0.681543 -0.352761 0.775458 -0.446466 -0.446466 0.700661 -0.466948 -0.539475 0.69474 -0.508594 -0.508595 0.658223 -0.498749 -0.563908 0.723159 -0.639997 -0.259701 0.700484 -0.644003 -0.307541 0.704139 -0.704638 -0.0876013 0.704437 -0.704449 -0.086717 0 0.99695 -0.0780433 0 0.99695 -0.0780432 0.00111206 0.902391 -0.430918 -0.000519977 0.748428 -0.663216 0.00596531 0.662484 -0.749052 0 0.593492 -0.80484 0 0.995561 -0.0941222 0.00190748 0.992503 -0.122208 -0.00124095 0.961549 -0.27463 0.00849915 0.872999 -0.487649 0 0.998943 -0.0459615 0 0.998943 -0.0459615 0 -0.999643 -0.0267095 -0.00158879 -0.996811 -0.0797864 -0.00710585 -0.985144 -0.171581 0.00285648 -0.969612 -0.244633 -0.00284993 -0.885005 -0.465572 0.00419277 -0.907183 -0.420716 -0.00395696 -0.786405 -0.617698 -0.0204606 -0.706959 -0.706959 0 -0.622331 -0.782754 -4.00213e-07 -0.999729 -0.0232986 -0.000589925 -0.998943 -0.0459621 0 -0.997602 -0.0692114 0 0.974927 0.222524 0 0.974927 0.222524 0 0.781831 0.623491 0 0.781831 0.623491 0 0.433884 0.900969 0 0.433884 0.900969 0 0 1 0 0 1 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.781831 0.623491 0 -0.781831 0.623491 0 -0.974927 0.222524 0 -0.974927 0.222524 0 0.97493 0.222513 0 0.97493 0.222513 0 0.781827 0.623495 0 0.781827 0.623495 0 0.433881 0.90097 0 0.433881 0.90097 0 0 1 0 0 1 0 -0.433881 0.90097 0 -0.433881 0.90097 0 -0.781827 0.623496 0 -0.781827 0.623496 0 -0.97493 0.222513 0 -0.97493 0.222513 0 0.97493 0.222512 0 0.97493 0.222512 0 0.781826 0.623497 0 0.781826 0.623497 0 0.433881 0.90097 0 0.433881 0.90097 0 0 1 0 0 1 0 -0.433881 0.90097 0 -0.433881 0.90097 0 -0.781826 0.623497 0 -0.781826 0.623497 0 -0.97493 0.222512 0 -0.97493 0.222512 0 -0.608675 0.79342 0 0.965923 0.258828 0 0.965923 0.258828 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 -0.0184926 -0.379576 0.924976 0 -0.129787 0.991542 -0.0190734 -0.793661 0.608061 0 -0.707107 0.707107 0 -0.924209 0.381888 -0.00946966 -0.965883 0.258805 0 -0.991555 0.129684 0 0.974927 0.222527 0 0.974927 0.222527 0 0.781834 0.623487 0 0.781834 0.623487 0 0.433884 0.900969 0 0.433884 0.900969 0 0 1 0 0 1 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.781827 0.623495 0 -0.781827 0.623496 0 -0.974929 0.222514 0 -0.974929 0.222514 0 0.38282 0.923823 0 0.965926 0.258817 0 0.965926 0.258817 0 0.707107 0.707107 -0.0184934 0.611259 0.791215 0 0.79381 0.608165 -0.0190696 0.12979 0.991358 0 0.258817 0.965926 0 -0.131446 0.991323 -0.00946885 -0.258805 0.965883 0 -0.383513 0.923535 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258817 0 -0.965926 0.258817 0 0.991573 0.129546 -0.0184583 0.925066 0.379359 0 0.965926 0.25882 0 0.793334 0.608786 -0.0095985 0.707076 0.707073 0 0.60875 0.793362 0 0.381807 0.924242 -0.00946954 0.258805 0.965883 0 0.129597 0.991567 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258817 0 -0.965926 0.258817 0 0.974928 0.22252 0 0.974928 0.22252 0 0.781831 0.623491 0 0.781831 0.623491 0 0.433884 0.900969 0 0.433884 0.900969 0 0 1 0 0 1 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.781831 0.623491 0 -0.781831 0.623491 0 -0.974928 0.22252 0 -0.974928 0.22252 0 0.974928 0.222521 0 0.974928 0.222521 0 0.781832 0.623489 0 0.781832 0.623489 0 0.433884 0.900969 0 0.433884 0.900969 0 0 1 0 0 1 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.781832 0.623489 0 -0.781832 0.623489 0 -0.974928 0.222521 0 -0.974928 0.222521 0 0.974928 0.222521 0 0.974928 0.222521 0 0.781829 0.623493 0 0.781829 0.623493 0 0.433886 0.900968 0 0.433887 0.900968 0 0 1 0 0 1 0 -0.433886 0.900968 0 -0.433886 0.900968 0 -0.781829 0.623493 0 -0.781829 0.623493 0 -0.974929 0.222518 0 -0.974929 0.222518 0 0.974929 0.222518 0 0.974929 0.222518 0 0.78183 0.623491 0 0.78183 0.623491 0 0.433884 0.900969 0 0.433884 0.900969 0 0 1 0 0 1 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.78183 0.623491 0 -0.78183 0.623491 0 -0.974929 0.222518 0 -0.974929 0.222518 0 0.974927 0.222524 0 0.974927 0.222524 0 0.781834 0.623487 0 0.781834 0.623487 0 0.433884 0.900969 0 0.433884 0.900969 0 0 1 0 0 1 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.781827 0.623496 0 -0.781827 0.623496 0 -0.97493 0.222511 0 -0.97493 0.222511 -0.705162 -0.705162 0.0741156 -0.705165 -0.705159 0.0741151 -0.705165 -0.67434 0.219107 -0.705166 -0.674339 0.219106 -0.705166 -0.614048 0.354521 -0.705166 -0.614049 0.354521 -0.705166 -0.526921 0.474442 -0.705164 -0.526923 0.474443 -0.705164 -0.416766 0.573629 -0.705168 -0.416764 0.573625 -0.705168 -0.288393 0.647741 -0.705166 -0.288393 0.647743 -0.705167 -0.147418 0.693547 -0.705166 -0.147418 0.693548 -0.705165 0 0.709043 -0.705165 0 0.709043 -0.705166 0.147418 0.693548 -0.705168 0.147418 0.693546 -0.705168 0.288392 0.647741 -0.705167 0.288393 0.647742 -0.705167 0.416764 0.573627 -0.705166 0.416765 0.573627 -0.705166 0.526921 0.474442 -0.705168 0.526919 0.47444 -0.705168 0.614047 0.35452 -0.705166 0.614049 0.354521 -0.705166 0.674339 0.219106 -0.705166 0.674339 0.219106 -0.705166 0.705158 0.0741151 -0.705167 0.705157 0.0741151 -0.705757 -0.705758 0.0617458 -0.705757 -0.705758 0.0617459 -0.705757 -0.684314 0.183361 -0.705757 -0.684314 0.183361 -0.705757 -0.642078 0.299406 -0.705757 -0.642078 0.299406 -0.705757 -0.580332 0.406353 -0.705757 -0.580332 0.406353 -0.705757 -0.500953 0.500953 -0.705757 -0.500953 0.500953 -0.705757 -0.406353 0.580332 -0.705757 -0.406352 0.580331 -0.705757 -0.299405 0.642077 -0.705757 -0.299406 0.642078 -0.705757 -0.183362 0.684314 -0.705757 -0.183362 0.684314 -0.705757 -0.0617458 0.705758 -0.705757 -0.0617459 0.705758 -0.705757 0.0617459 0.705758 -0.705757 0.0617459 0.705758 -0.705757 0.183362 0.684314 -0.705757 0.183362 0.684314 -0.705757 0.299406 0.642078 -0.705757 0.299406 0.642078 -0.705756 0.406353 0.580332 -0.705757 0.406353 0.580332 -0.705757 0.500953 0.500953 -0.705756 0.500953 0.500953 -0.705756 0.580332 0.406353 -0.705758 0.580331 0.406352 -0.705758 0.642077 0.299405 -0.705756 0.642078 0.299406 -0.705756 0.684315 0.183362 -0.705755 0.684316 0.183362 -0.705755 0.70576 0.0617462 -0.705758 0.705758 0.0617451 -0.202057 -0.97187 -0.121007 -0.837541 -0.544506 -0.045153 -0.83973 -0.540913 -0.0476117 -0.839515 -0.542861 -0.0227146 -0.203243 -0.978272 -0.0409331 -0.202045 -0.978516 -0.0410381 -0.576236 -0.816573 -0.0340729 -0.202057 -0.97187 -0.121007 -0.202211 -0.965337 -0.165032 -0.146828 -0.968582 -0.200726 -0.202094 -0.957941 -0.203734 -0.202056 -0.939918 -0.275186 -0.202056 -0.939918 -0.275186 -0.202199 -0.924238 -0.323883 -0.0983727 -0.92949 -0.355487 -0.202136 -0.910474 -0.360803 -0.202056 -0.883672 -0.422253 -0.202056 -0.883672 -0.422253 -0.202179 -0.857196 -0.473644 -0.0782956 -0.86205 -0.500739 -0.202166 -0.837452 -0.507742 -0.202053 -0.804585 -0.558406 -0.202054 -0.804585 -0.558406 -0.202147 -0.766094 -0.610112 -0.0871576 -0.770096 -0.631946 -0.202193 -0.740924 -0.640429 -0.202056 -0.704702 -0.680124 -0.202057 -0.704702 -0.680124 -0.202058 -0.647748 -0.734571 -0.105544 -0.66353 -0.740668 -0.202209 -0.623603 -0.755137 -0.202058 -0.586603 -0.784264 -0.202061 -0.586603 -0.784263 -0.20206 -0.521661 -0.828879 -0.189365 -0.523887 -0.830472 -0.202218 -0.488764 -0.848656 -0.202061 -0.453343 -0.868131 -0.202059 -0.453343 -0.868131 -0.202059 -0.382091 -0.901764 -0.202064 -0.38209 -0.901764 -0.202218 -0.340231 -0.918341 -0.142089 -0.311664 -0.939508 -0.202094 -0.303023 -0.931308 -0.202053 -0.232644 -0.951342 -0.202058 -0.232644 -0.951341 -0.2022 -0.182137 -0.962259 -0.0957841 -0.157961 -0.982789 -0.202148 -0.143282 -0.968817 -0.202065 -0.077183 -0.976326 -0.202063 -0.0771832 -0.976327 -0.202184 -0.0189289 -0.979165 -0.07794 0.00157694 -0.996957 -0.202166 0.0204761 -0.979137 -0.202051 0.0802713 -0.97608 -0.202059 0.0802718 -0.976078 -0.20215 0.144814 -0.968589 -0.0890583 0.161169 -0.9829 -0.202196 0.183658 -0.96197 -0.202059 0.235652 -0.9506 -0.202058 0.235652 -0.9506 -0.202059 0.311304 -0.928581 -0.11215 0.308949 -0.944443 -0.202204 0.341682 -0.917805 -0.202052 0.384941 -0.900553 -0.202054 0.384941 -0.900552 -0.202054 0.456088 -0.866694 -0.195722 0.456229 -0.868072 -0.202211 0.490108 -0.847883 -0.202053 0.524281 -0.827227 -0.20205 0.524281 -0.827227 -0.20205 0.589082 -0.782406 -0.202058 0.589081 -0.782404 -0.202211 0.624798 -0.754148 -0.137509 0.657455 -0.74084 -0.202093 0.654642 -0.728425 -0.202048 0.70685 -0.677893 -0.202062 0.706849 -0.677891 -0.202202 0.741935 -0.639255 -0.0933711 0.771655 -0.62915 -0.202133 0.76706 -0.608902 -0.202047 0.806349 -0.555859 -0.202044 0.806349 -0.555859 -0.202163 0.838255 -0.506418 -0.0777522 0.863667 -0.498031 -0.202174 0.857947 -0.472284 -0.202057 0.885003 -0.419456 -0.202053 0.885003 -0.419457 -0.202141 0.911043 -0.359361 -0.0911297 0.931255 -0.352789 -0.202177 0.924752 -0.322426 -0.202038 0.940787 -0.272215 -0.202082 0.940779 -0.272209 -0.202082 0.959616 -0.195703 -0.118744 0.971528 -0.205019 -0.202192 0.965599 -0.163513 -0.20204 0.972251 -0.117933 -0.202069 0.972245 -0.11793 -0.202069 0.978579 -0.0393945 -0.202042 0.978584 -0.0393969 -0.840836 -0.540824 -0.0224624 -0.573239 -0.818664 -0.034445 -0.57326 -0.813095 -0.101238 -0.57326 -0.813095 -0.101238 -0.57326 -0.802326 -0.166272 -0.573261 -0.802325 -0.166272 -0.573261 -0.786363 -0.230229 -0.57326 -0.786363 -0.230229 -0.57326 -0.765312 -0.292696 -0.573261 -0.765311 -0.292696 -0.573261 -0.739305 -0.353269 -0.57326 -0.739306 -0.353269 -0.57326 -0.708516 -0.411556 -0.573261 -0.708515 -0.411556 -0.573261 -0.673139 -0.467178 -0.573264 -0.673137 -0.467177 -0.573264 -0.633404 -0.519776 -0.573261 -0.633406 -0.519777 -0.573261 -0.589574 -0.569012 -0.573256 -0.589577 -0.569014 -0.573256 -0.541928 -0.614566 -0.573261 -0.541926 -0.614564 -0.573261 -0.49077 -0.656138 -0.573261 -0.490769 -0.656138 -0.573262 -0.436437 -0.693465 -0.573259 -0.436438 -0.693467 -0.573259 -0.379281 -0.726306 -0.573259 -0.379281 -0.726306 -0.573259 -0.319669 -0.754444 -0.573258 -0.319669 -0.754445 -0.573258 -0.257988 -0.7777 -0.573263 -0.257986 -0.777697 -0.573263 -0.194636 -0.795919 -0.573262 -0.194637 -0.795919 -0.573262 -0.130026 -0.80899 -0.573261 -0.130026 -0.80899 -0.573261 -0.0645738 -0.816824 -0.573262 -0.0645736 -0.816823 -0.573263 0.00129609 -0.819371 -0.573262 0.00129605 -0.819371 -0.573263 0.0671574 -0.816615 -0.57326 0.0671573 -0.816617 -0.57326 0.132584 -0.808576 -0.573258 0.132584 -0.808577 -0.573258 0.197154 -0.795302 -0.57326 0.197154 -0.795301 -0.57326 0.260447 -0.776879 -0.573262 0.260446 -0.776877 -0.573262 0.322053 -0.753428 -0.573261 0.322053 -0.753428 -0.573261 0.381576 -0.725101 -0.573263 0.381576 -0.7251 -0.573262 0.438628 -0.692081 -0.573263 0.438628 -0.69208 -0.573264 0.492842 -0.654581 -0.573257 0.492844 -0.654585 -0.573256 0.543869 -0.612849 -0.57327 0.543863 -0.612841 -0.57327 0.591367 -0.56714 -0.573262 0.59137 -0.567144 -0.573262 0.635047 -0.51777 -0.573262 0.635047 -0.51777 -0.573262 0.674613 -0.465046 -0.573254 0.674618 -0.465049 -0.573254 0.709818 -0.409315 -0.573263 0.709813 -0.409311 -0.573263 0.740418 -0.350928 -0.573254 0.740424 -0.350931 -0.573254 0.766238 -0.290276 -0.573261 0.766233 -0.290273 -0.573261 0.787086 -0.227742 -0.573259 0.787088 -0.227742 -0.573259 0.802849 -0.163734 -0.573276 0.802837 -0.163729 -0.573276 0.8134 -0.0986628 -0.573257 0.813414 -0.0986664 -0.573257 0.818713 -0.0329603 -0.573272 0.818702 -0.0329584 -0.850931 0.524852 -0.0211298 -0.850939 0.524839 -0.0211282 -0.850939 0.521442 -0.0632493 -0.850927 0.521462 -0.0632535 -0.850927 0.51469 -0.104966 -0.850931 0.514684 -0.104964 -0.850931 0.50458 -0.145999 -0.850936 0.504572 -0.145996 -0.850936 0.491203 -0.186084 -0.850939 0.491198 -0.186081 -0.850939 0.474651 -0.224965 -0.850939 0.474651 -0.224965 -0.850939 0.455031 -0.262392 -0.850942 0.455027 -0.26239 -0.850942 0.432462 -0.298118 -0.850937 0.432469 -0.298124 -0.850937 0.407105 -0.331923 -0.850935 0.407107 -0.331925 -0.850935 0.379107 -0.363576 -0.850933 0.379109 -0.363578 -0.850933 0.348655 -0.392876 -0.850936 0.348652 -0.392872 -0.850936 0.315943 -0.419628 -0.850934 0.315945 -0.419632 -0.850933 0.28119 -0.443671 -0.850936 0.281189 -0.443668 -0.850936 0.244614 -0.464836 -0.850934 0.244615 -0.464838 -0.850934 0.206457 -0.482997 -0.850936 0.206456 -0.482994 -0.850936 0.166962 -0.498028 -0.850935 0.166963 -0.498029 -0.850935 0.126388 -0.509839 -0.850933 0.126388 -0.509842 -0.850933 0.0849956 -0.518352 -0.850937 0.0849952 -0.518346 -0.850937 0.0430521 -0.523501 -0.850933 0.043052 -0.523507 -0.850933 0.000830883 -0.525273 -0.850934 0.000830976 -0.525272 -0.850934 -0.0413961 -0.523639 -0.850934 -0.0413961 -0.523639 -0.850934 -0.0833556 -0.518617 -0.850935 -0.083355 -0.518615 -0.850935 -0.124775 -0.510236 -0.850935 -0.124775 -0.510236 -0.850935 -0.165387 -0.498555 -0.850934 -0.165387 -0.498556 -0.850934 -0.204929 -0.483648 -0.850935 -0.204928 -0.483647 -0.850935 -0.243143 -0.465608 -0.850935 -0.243143 -0.465609 -0.850935 -0.279785 -0.444557 -0.850933 -0.279786 -0.444559 -0.850933 -0.314617 -0.420629 -0.850935 -0.314615 -0.420628 -0.850935 -0.34741 -0.393975 -0.850936 -0.347408 -0.393973 -0.850936 -0.377953 -0.364772 -0.850936 -0.377954 -0.364773 -0.850935 -0.406054 -0.33321 -0.850934 -0.406055 -0.333211 -0.850934 -0.431527 -0.299492 -0.850935 -0.431527 -0.299492 -0.850934 -0.454205 -0.263834 -0.850935 -0.454204 -0.263834 -0.850935 -0.473943 -0.226469 -0.850934 -0.473944 -0.226469 -0.850934 -0.490615 -0.187638 -0.850934 -0.490615 -0.187638 -0.850934 -0.50411 -0.147592 -0.850935 -0.50411 -0.147592 -0.850935 -0.514343 -0.106591 -0.850935 -0.514343 -0.106591 -0.850935 -0.521247 -0.0649002 -0.878472 -0.473574 -0.0633551 -0.817792 -0.574608 -0.0322757 0 -0.998176 0.0603785 -0.00671583 -0.996172 0.0871538 0 -0.989115 0.147145 0 -0.978426 0.206598 -0.00746244 -0.965899 0.258812 -0.00671304 -0.911879 0.410403 -0.00223785 -0.906306 0.422617 0 -0.937376 0.34832 0 -0.956696 0.291088 0 -0.875918 0.48246 0 -0.84519 0.534466 -0.00783581 -0.819127 0.573559 -0.00410336 -0.707101 0.707101 -0.00410332 -0.707101 0.707101 0 -0.757346 0.653014 0 -0.795392 0.606095 0 -0.534466 0.84519 -0.00783572 -0.573559 0.819127 0 -0.606095 0.795392 0 -0.653013 0.757346 0 -0.482459 0.875919 -0.00671292 -0.410404 0.911879 -0.0022379 -0.422617 0.906306 0 -0.348319 0.937376 0 -0.291088 0.956696 -0.00746241 -0.258812 0.965899 0 -0.206599 0.978426 0 -0.147146 0.989115 -0.00671584 -0.0871538 0.996172 0 -0.0603785 0.998176 0 0.0603785 0.998176 -0.00671582 0.0871538 0.996172 0 0.291088 0.956696 -0.00746241 0.258812 0.965899 0 0.206599 0.978426 0 0.147145 0.989115 0 0.34832 0.937376 -0.00186549 0.410412 0.911898 -0.00559611 0.422612 0.906294 0 0.48246 0.875918 0 0.534466 0.84519 -0.00783583 0.573559 0.819127 -0.00410334 0.707101 0.707101 -0.00410345 0.707101 0.707101 0 0.653012 0.757347 0 0.606095 0.795392 0 0.757346 0.653013 0 0.795392 0.606096 -0.00783586 0.819127 0.573559 -0.00186561 0.911899 0.410411 -0.00559611 0.906294 0.422611 0 0.875919 0.482459 0 0.84519 0.534466 0 0.937377 0.348316 0 0.956696 0.291088 -0.00746252 0.965899 0.258812 0 0.998176 0.0603785 -0.00671591 0.996172 0.0871541 0 0.989115 0.147146 0 0.978426 0.206598 -0.941992 -0.244069 -0.230394 -0.947053 -0.318243 -0.0425748 -0.939632 -0.331553 -0.0846391 -0.939476 -0.331636 -0.0860355 -0.938491 -0.333008 -0.0913275 -0.937019 -0.337515 -0.0898818 -0.938857 -0.331615 -0.0926241 -0.944805 -0.307977 -0.111772 -0.933766 -0.338456 -0.116315 -0.937604 -0.327999 -0.115391 -0.941152 -0.323273 -0.0986297 -0.943474 -0.31759 -0.094838 -0.946731 -0.309053 -0.0904838 -0.942968 -0.320949 -0.0883366 -0.940726 -0.32795 -0.0865082 -0.940037 -0.330209 -0.0853999 -0.939777 -0.331205 -0.0843936 -0.942647 -0.330687 -0.0454108 -0.941685 -0.330522 -0.0631256 -0.939453 -0.336281 -0.0659005 -0.941472 -0.330957 -0.0640099 -0.941855 -0.329982 -0.0634084 -0.9397 -0.3317 -0.0833001 -0.939394 -0.336124 -0.0675222 -0.942829 -0.327492 -0.0618197 -0.93968 -0.331769 -0.0832511 -0.939887 -0.335367 -0.0643602 -0.933321 -0.351573 -0.072859 -0.940456 -0.336453 -0.0483907 -0.941314 -0.334242 -0.0470065 -0.93962 0.341943 -0.0137654 -0.862599 0.505353 -0.0232511 -0.964236 0.263118 -0.0319163 -0.953233 0.299921 -0.0373293 -0.943325 0.329011 -0.0434653 -0.940994 0.335254 -0.0462009 -0.940283 0.337002 -0.0479424 -0.94017 0.336633 -0.0525238 -0.940102 0.336825 -0.0525167 -0.940164 0.336651 -0.0525067 -0.939472 0.329461 -0.0940579 -0.940498 0.324081 -0.102152 -0.939125 0.328538 -0.100534 -0.940118 0.325103 -0.102398 -0.938987 0.331317 -0.092367 -0.937382 0.336562 -0.0896664 -0.93002 0.358257 -0.0819503 -0.930503 0.357121 -0.0814167 -0.934436 0.347778 -0.0766767 -0.937222 0.341032 -0.0728779 -0.939599 0.335306 -0.0687262 -0.939687 0.338167 -0.0513024 -0.940015 0.337609 -0.0489043 -0.939512 0.335561 -0.0686685 -0.941858 0.328771 -0.0693822 -0.937296 0.341506 -0.0696466 -0.939889 0.330979 -0.0840262 -0.940264 0.32967 -0.0849745 -0.941169 0.326809 -0.0860067 -0.946864 0.308962 -0.089397 -0.949312 0.30229 -0.0861803 -0.943204 0.318462 -0.0945938 -0.941041 0.323718 -0.0982282 -0.939668 0.326739 -0.101322 -0.939604 0.320068 -0.121252 -0.936316 0.325398 -0.132015 -0.940945 0.305937 -0.145001 -0.939677 0.305608 -0.153662 -0.939603 0.296501 -0.170976 -0.936377 0.299974 -0.182248 -0.940953 0.278727 -0.192142 -0.939676 0.277118 -0.200538 -0.939691 0.237294 -0.246316 -0.939683 0.237959 -0.245706 -0.938557 0.243122 -0.244953 -0.938823 0.243147 -0.243907 -0.939381 0.240427 -0.244456 -0.93958 0.23909 -0.245001 -0.939206 0.243513 -0.242059 -0.939518 0.244073 -0.240281 -0.941678 0.25597 -0.218453 -0.940344 0.249148 -0.231687 -0.926825 0.291024 -0.237279 -0.938536 0.263285 -0.223231 -0.939482 0.260793 -0.222173 -0.935375 0.267126 -0.23177 -0.931 0.274135 -0.241016 -0.941585 0.245557 -0.230475 -0.944867 0.23709 -0.225865 -0.946999 0.231849 -0.222351 -0.941037 0.238366 -0.240064 -0.939912 0.238657 -0.244149 -0.939702 0.237853 -0.245735 -0.939692 0.237163 -0.246439 -0.939603 0.227182 -0.255996 -0.936497 0.226922 -0.267356 -0.940966 0.203605 -0.270423 -0.939674 0.199674 -0.277745 -0.939603 0.183222 -0.289093 -0.936558 0.181185 -0.300053 -0.940971 0.157631 -0.299544 -0.939673 0.15271 -0.306094 -0.939603 0.134527 -0.314719 -0.936618 0.130832 -0.325008 -0.940974 0.107589 -0.320924 -0.939673 0.101819 -0.326571 -0.940339 0.091303 -0.32776 -0.941332 0.0888645 -0.325573 -0.947084 0.0772337 -0.311555 -0.949061 0.0768028 -0.305588 -0.944007 0.0774221 -0.320714 -0.939611 0.0620666 -0.336569 -0.952735 0.0429038 -0.300759 -0.937775 0.0719964 -0.339697 -0.934979 0.0760801 -0.346449 -0.931666 0.0800548 -0.354386 -0.936764 0.0866682 -0.339061 -0.938952 0.0906052 -0.331902 -0.939512 0.0926443 -0.329747 -0.93966 0.0941051 -0.328911 -0.939689 0.0950087 -0.328568 -0.939692 0.095131 -0.328525 -0.939735 0.0940422 -0.328715 -0.939934 0.0927825 -0.328506 -0.942053 0.0772889 -0.32644 -0.940714 0.0768239 -0.330386 -0.925884 0.0611342 -0.372829 -0.939491 0.0622562 -0.336869 -0.939603 0.0280524 -0.341114 -0.936738 0.0215592 -0.349367 -0.940978 0.000535452 -0.338467 -0.939671 -0.00644429 -0.342019 -0.939603 -0.0269735 -0.341201 -0.936798 -0.0345472 -0.348162 -0.940978 -0.0537114 -0.334178 -0.93967 -0.0610334 -0.336594 -0.939365 -0.107706 -0.325566 -0.944519 -0.109508 -0.309663 -0.938699 -0.0993727 -0.330104 -0.937603 -0.0984573 -0.333476 -0.936141 -0.09769 -0.337782 -0.932859 -0.0966669 -0.347029 -0.927831 -0.0956895 -0.360519 -0.931713 -0.0901424 -0.35183 -0.935611 -0.0840067 -0.342893 -0.937288 -0.0809916 -0.339016 -0.938548 -0.0783537 -0.336136 -0.939666 -0.0751528 -0.333736 -0.939619 -0.0750743 -0.333885 -0.940707 -0.0761684 -0.330557 -0.942344 -0.0767883 -0.325718 -0.947868 -0.0764678 -0.309353 -0.946195 -0.0768682 -0.314335 -0.940352 -0.090199 -0.328028 -0.935174 -0.11152 -0.336175 -0.943938 -0.100925 -0.314318 -0.941272 -0.104892 -0.320942 -0.939605 -0.107865 -0.32482 -0.939604 -0.13353 -0.315143 -0.936917 -0.142526 -0.319176 -0.940976 -0.156677 -0.300029 -0.939668 -0.16414 -0.300137 -0.939603 -0.182307 -0.289672 -0.936976 -0.191625 -0.292156 -0.940972 -0.202737 -0.271051 -0.939667 -0.210007 -0.270042 -0.939631 -0.250958 -0.232622 -0.938683 -0.251197 -0.236164 -0.939755 -0.250296 -0.232837 -0.939682 -0.244621 -0.239077 -0.939587 -0.243882 -0.240205 -0.939335 -0.243232 -0.241844 -0.938801 -0.242723 -0.244416 -0.933952 -0.241266 -0.263676 -0.930212 -0.249312 -0.269348 -0.934257 -0.240357 -0.263425 -0.937147 -0.233499 -0.259294 -0.939594 -0.226911 -0.25627 -0.939506 -0.226992 -0.256523 -0.938802 -0.227821 -0.258357 -0.939755 -0.237537 -0.24584 -0.939978 -0.237929 -0.244606 -0.940428 -0.237953 -0.242846 -0.941499 -0.237144 -0.239462 -0.94729 -0.230526 -0.222486 -0.948828 -0.226666 -0.219883 -0.943888 -0.239176 -0.227749 -0.940685 -0.247653 -0.231906 -0.939671 -0.250969 -0.232449 -0.939603 -0.264584 -0.217119 -0.937095 -0.273782 -0.216555 -0.940963 -0.278096 -0.193006 -0.939665 -0.284501 -0.18997 -0.939603 -0.295958 -0.171913 -0.937154 -0.304739 -0.16993 -0.940956 -0.305447 -0.145955 -0.939664 -0.311211 -0.142052 -0.939603 -0.319683 -0.122264 -0.93463 -0.336333 -0.11553 -0.940047 -0.325741 -0.10102 0 0.994522 0.104528 0 0.994522 0.104528 0 0.951056 0.309017 0 0.951056 0.309017 0 0.866025 0.5 0 0.866025 0.5 0 0.743145 0.66913 0 0.743145 0.66913 0 0.587785 0.809017 0 0.587785 0.809017 0 0.406736 0.913546 0 0.406736 0.913546 0 0.207912 0.978148 0 0.207912 0.978148 0 0 1 0 0 1 0 -0.207912 0.978148 0 -0.207912 0.978148 0 -0.406737 0.913546 0 -0.406737 0.913546 0 -0.587785 0.809017 0 -0.587785 0.809017 0 -0.743145 0.66913 0 -0.743145 0.66913 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.951056 0.309017 0 -0.951056 0.309017 0 -0.994522 0.104529 0 -0.994522 0.104529 0.849121 0.136707 0.5102 0.849122 0.373492 0.373492 0.849122 0.5102 0.136706 0.84912 -0.510202 0.136706 0.849121 -0.373493 0.373493 0.849121 -0.136709 0.5102 0.849121 0.136707 0.5102 0.849121 0.373495 0.37349 0.849122 0.510198 0.136715 0.84912 -0.510202 0.136706 0.84912 -0.373491 0.373496 0.849121 -0.13671 0.5102 0.849121 0.136707 0.5102 0.849122 0.373492 0.373492 0.849122 0.5102 0.136706 0.84912 -0.510202 0.136706 0.849121 -0.373493 0.373493 0.849121 -0.136709 0.5102 0.849121 0.136707 0.5102 0.849121 0.373495 0.37349 0.849122 0.510198 0.136715 0.84912 -0.510202 0.136706 0.84912 -0.373491 0.373496 0.849121 -0.13671 0.5102 0.705518 0.705518 0.0670032 0.705503 0.705532 0.067004 0.705503 0.680306 0.198617 0.70551 0.680299 0.198615 0.70551 0.63075 0.323125 0.705513 0.630748 0.323124 0.705513 0.558646 0.43608 0.705515 0.558645 0.436079 0.705514 0.466569 0.533445 0.705514 0.466569 0.533444 0.705392 -0.705405 -0.0694763 0.705392 -0.705404 -0.0694763 0.705392 -0.678296 -0.205759 0.705393 -0.678295 -0.205758 0.705394 -0.62512 -0.334133 0.705392 -0.625122 -0.334134 0.705391 -0.547924 -0.449669 0.705396 -0.54792 -0.449666 0.705397 -0.449666 -0.54792 0.705392 -0.449669 -0.547924 0.705391 -0.334135 -0.625122 0.70539 -0.334135 -0.625123 0.705389 -0.20576 -0.678299 0.70539 -0.20576 -0.678298 0.705389 -0.0694766 -0.705407 0.705392 -0.0694762 -0.705405 0.705392 0.0694764 -0.705405 0.705388 0.0694766 -0.705409 0.705385 0.205761 -0.678302 0.705388 0.20576 -0.6783 0.705386 0.334137 -0.625126 0.705395 0.334133 -0.625119 0.705396 0.449667 -0.54792 0.705392 0.449669 -0.547923 0.705392 0.547924 -0.449669 0.705386 0.547928 -0.449673 0.705385 0.625127 -0.334137 0.705391 0.625122 -0.334135 0.70539 0.678298 -0.205759 0.705382 0.678305 -0.205762 0.705382 0.705414 -0.0694775 0.705398 0.705398 -0.0694753 -0.706946 0.548759 -0.446196 -0.756777 0.533063 -0.378329 -0.746956 0.539695 -0.388312 -0.707007 0.599844 -0.374604 -0.70706 0.614198 -0.350466 -0.669692 0.670155 -0.320008 -0.706162 0.643762 -0.294798 -0.706924 0.67043 -0.225349 -0.647187 0.73526 -0.201352 -0.706532 0.688203 -0.16489 -0.7057 0.7057 -0.0630442 -0.572954 0.812672 -0.106242 -0.70681 0.706812 -0.0289213 -0.705517 -0.705518 0.067003 -0.705517 -0.705519 0.067003 -0.705517 -0.680293 0.198613 -0.705517 -0.680293 0.198613 -0.705517 -0.630744 0.323122 -0.705517 -0.630744 0.323122 -0.705517 -0.558643 0.436078 -0.705518 -0.558642 0.436078 -0.705518 -0.466567 0.533442 -0.705517 -0.466567 0.533442 -0.705397 0.625116 -0.334132 -0.705398 0.678291 -0.205757 -0.705395 0.678293 -0.205758 -0.705395 0.705401 -0.0694756 -0.705398 0.705398 -0.0694759 -0.705398 0.334131 -0.625116 -0.705399 0.449665 -0.547918 -0.705397 0.449666 -0.547919 -0.707075 0.506649 -0.493308 -0.664008 0.577999 -0.474352 -0.705831 0.553531 -0.442047 -0.705398 0.625116 -0.334132 -0.705397 -0.205757 -0.678291 -0.705397 -0.0694758 -0.705399 -0.705397 -0.0694758 -0.705399 -0.705397 0.0694758 -0.705399 -0.705397 0.0694759 -0.7054 -0.706784 0.167459 -0.687324 -0.610537 0.229902 -0.757885 -0.70656 0.234095 -0.667812 -0.705398 0.334132 -0.625116 -0.705398 -0.547919 -0.449665 -0.705398 -0.449665 -0.547918 -0.705397 -0.449666 -0.54792 -0.707029 -0.38054 -0.596071 -0.644288 -0.360516 -0.674479 -0.706048 -0.320726 -0.631373 -0.705398 -0.205757 -0.678291 -0.641875 -0.682251 -0.350043 -0.707056 -0.594506 -0.382928 -0.705398 -0.547919 -0.449665 -0.705398 -0.625116 -0.334132 -0.705397 -0.678291 -0.205757 -0.705397 -0.678291 -0.205757 -0.705397 -0.705399 -0.0694758 -0.705397 -0.705399 -0.0694757 -0.891954 0.450865 -0.0337361 -0.706866 0.706866 -0.0260915 -0.186155 0.694746 0.694747 -0.186155 0.694746 0.694747 -0.508583 0.508591 0.694751 -0.50859 0.50859 0.694746 -0.694751 0.186148 0.694745 -0.694747 0.186151 0.694748 -0.694748 -0.186147 0.694748 -0.69475 -0.186152 0.694745 -0.508587 -0.508595 0.694745 -0.508587 -0.508587 0.69475 -0.186159 -0.694745 0.694748 -0.186156 -0.694749 0.694744 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707101 0.707113 0 -0.707101 0.707113 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.707101 -0.707113 0 -0.707101 -0.707113 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.510203 0.136701 0.84912 -0.37349 0.373497 0.84912 -0.136707 0.510203 0.84912 -0.13671 -0.510202 0.84912 -0.37349 -0.373497 0.84912 -0.510203 -0.136701 0.84912 -0.159324 0.698074 0.698075 -0.159331 0.698077 0.69807 -0.44644 0.55981 0.698071 -0.446427 0.559811 0.698079 -0.645111 0.310669 0.69808 -0.645117 0.310666 0.698077 -0.716024 0 0.698076 -0.716024 0 0.698076 -0.645115 -0.310671 0.698076 -0.645114 -0.310665 0.69808 -0.446429 -0.559809 0.69808 -0.446428 -0.559812 0.698077 -0.159332 -0.698071 0.698076 -0.15933 -0.698073 0.698074 -0.222511 0.97493 0 -0.222511 0.97493 0 -0.623495 0.781827 0 -0.623495 0.781827 0 -0.900969 0.433884 0 -0.900969 0.433884 0 -1 0 0 -1 0 0 -0.900969 -0.433884 0 -0.900969 -0.433884 0 -0.623487 -0.781834 0 -0.623487 -0.781834 0 -0.222524 -0.974927 0 -0.222524 -0.974927 0 -0.116745 0.511516 0.851306 -0.52467 0 0.851306 -0.472711 0.227646 0.851306 -0.327129 0.410201 0.851306 -0.116752 -0.511516 0.851305 -0.327125 -0.410205 0.851306 -0.472711 -0.227646 0.851306 -0.159324 0.698074 0.698075 -0.159331 0.698077 0.69807 -0.44644 0.55981 0.698071 -0.446427 0.559811 0.698079 -0.645111 0.310669 0.69808 -0.645117 0.310666 0.698077 -0.716024 0 0.698076 -0.716024 0 0.698076 -0.645117 -0.310672 0.698074 -0.645115 -0.310662 0.69808 -0.446429 -0.559809 0.69808 -0.446428 -0.559812 0.698077 -0.159332 -0.698071 0.698076 -0.15933 -0.698073 0.698074 -0.222511 0.97493 0 -0.222511 0.97493 0 -0.623495 0.781827 0 -0.623495 0.781827 0 -0.900969 0.433884 0 -0.900969 0.433884 0 -1 0 0 -1 0 0 -0.900969 -0.433884 0 -0.900969 -0.433884 0 -0.623487 -0.781834 0 -0.623487 -0.781834 0 -0.222524 -0.974927 0 -0.222524 -0.974927 0 -0.116745 0.511516 0.851306 -0.52467 0 0.851306 -0.472711 0.227646 0.851306 -0.327129 0.410201 0.851306 -0.116752 -0.511516 0.851305 -0.327125 -0.410205 0.851306 -0.472711 -0.227646 0.851306 0.258771 0.876454 -0.406036 0.258123 0.836678 -0.483056 0.258803 0.0865865 -0.962042 0.258153 0 -0.966104 0.706065 0.659195 -0.258715 0.706109 0.105537 -0.700195 0.706095 -0.553629 -0.441504 0.965752 0.258743 -0.0193901 0.965751 0.252964 -0.0577375 0.965751 0.0764799 -0.247942 0.965751 -0.176485 -0.190206 0.96575 -0.258749 -0.0193906 0.965751 -0.202863 -0.161778 0.96575 -0.202865 -0.161779 0.96575 -0.224711 -0.129737 0.965751 -0.146166 -0.214385 0.965749 -0.146169 -0.21439 0.965749 -0.112583 -0.233781 0.965751 -0.112581 -0.233776 0.965751 -0.0764808 -0.247944 0.965748 -0.0764831 -0.247952 0.965749 -0.0386732 -0.25658 0.96575 0.0386729 -0.256578 0.965749 0.038673 -0.256578 0.965749 0 -0.259477 0.965752 0.112579 -0.233773 0.96575 0.112581 -0.233777 0.965751 0.146166 -0.214386 0.965749 0.146168 -0.21439 0.965749 0.176489 -0.19021 0.965751 0.176486 -0.190206 0.965751 0.202863 -0.161778 0.965753 0.241528 -0.0947927 0.965752 0.24153 -0.0947933 0.965752 0.224704 -0.129733 0.706098 -0.659165 -0.258703 0.965751 -0.252966 -0.0577379 0.965751 -0.241536 -0.0947957 0.7061 -0.659163 -0.258702 0.706101 -0.613242 -0.354055 0.258145 -0.836673 -0.483053 0.258795 -0.789862 -0.556007 0.706085 -0.398902 -0.585083 0.706114 -0.398886 -0.585058 0.706114 -0.307233 -0.637974 0.706086 -0.307244 -0.638 0.706086 -0.208724 -0.676666 0.706117 -0.208715 -0.676637 0.706114 -0.105537 -0.700189 0.706096 -0.105539 -0.700207 0.706097 0 -0.708115 0.706078 0.307248 -0.638007 0.706114 0.307232 -0.637975 0.706114 0.398885 -0.585058 0.706085 0.398903 -0.585082 0.706085 0.481649 -0.519093 0.706082 0.481651 -0.519096 0.70608 0.55364 -0.441513 0.706089 0.553633 -0.441508 0.706089 0.613253 -0.354062 0.96575 -0.258747 -0.0193905 0.706098 -0.706134 -0.0529176 0.706098 -0.706134 -0.0529175 0.258144 -0.963405 -0.0721973 0.258149 -0.963404 -0.0721972 0.96575 -0.252969 -0.0577384 0.706099 -0.690359 -0.15757 0.706098 -0.690361 -0.15757 -0.642622 -0.746973 -0.170492 0.258712 -0.950431 -0.172477 0.258152 -0.836671 -0.483052 0.258802 -0.876445 -0.406037 -0.425345 -0.84247 -0.330645 0.258377 -0.904444 -0.339444 0.258566 -0.934922 -0.243031 0.96575 -0.241537 -0.0947964 0.96575 -0.224711 -0.129737 0.706089 -0.613253 -0.354062 0.706089 -0.553633 -0.441508 -0.425338 -0.707584 -0.56428 0.25837 -0.74619 -0.613551 0.965751 -0.176486 -0.190207 0.706086 -0.481648 -0.519093 0.706095 -0.481642 -0.519087 -0.642617 -0.52114 -0.561655 0.258562 -0.677933 -0.688151 -0.64261 -0.225839 -0.732154 0.258725 -0.325844 -0.909333 0.258158 -0.419177 -0.870428 0.258132 -0.419179 -0.870435 0.258131 -0.544229 -0.798238 0.258162 -0.544225 -0.798231 0.258729 -0.624582 -0.736856 0.258153 0 -0.966104 0.258803 -0.086586 -0.962042 -0.425327 -0.13489 -0.894931 0.258368 -0.158256 -0.952996 0.258555 -0.256991 -0.931185 0.965749 -0.038673 -0.256579 0.965749 0 -0.259477 0.706097 0 -0.708115 0.706096 0.10554 -0.700207 -0.425318 0.13489 -0.894935 0.258378 0.158255 -0.952993 0.96575 0.0764816 -0.247947 0.706081 0.208726 -0.676671 0.706106 0.208718 -0.676647 -0.64261 0.225839 -0.732154 0.258573 0.256989 -0.93118 -0.642595 0.521153 -0.561669 0.258751 0.624579 -0.736851 0.258181 0.544221 -0.798227 0.258131 0.544229 -0.798237 0.258132 0.41918 -0.870434 0.258158 0.419176 -0.870429 0.258725 0.325844 -0.909333 0.258176 0.836665 -0.48305 0.258822 0.789857 -0.556001 -0.425334 0.707586 -0.564281 0.258423 0.746179 -0.613542 0.258609 0.677924 -0.688142 0.965752 0.202859 -0.161775 0.965752 0.224704 -0.129733 0.706085 0.613256 -0.354064 0.706084 0.659178 -0.258709 -0.425314 0.842483 -0.330651 0.258408 0.904436 -0.339441 0.258695 0.950436 -0.172479 0.965753 0.252958 -0.0577361 0.706106 0.690352 -0.157569 0.706064 0.690394 -0.157577 -0.642604 0.746988 -0.170494 0.258599 0.934914 -0.243028 0.965751 0.258744 -0.0193902 0.70608 0.706152 -0.0529189 0.706107 0.706125 -0.0529175 0.258183 0.963395 -0.0721975 0.258127 0.963409 -0.0721976 0.705162 0.705162 0.0741154 0.705157 0.705168 0.0741157 0.705156 0.674348 0.219109 0.705158 0.674346 0.219109 0.705158 0.614055 0.354525 0.705158 0.614055 0.354525 0.705157 0.526927 0.474448 0.705146 0.526936 0.474455 0.705148 0.416775 0.573642 0.705156 0.416771 0.573636 0.705155 0.288398 0.647752 0.705159 0.288396 0.647749 0.705159 0.147419 0.693555 0.705156 0.14742 0.693557 0.705156 0 0.709052 0.705156 0 0.709052 0.705156 -0.14742 0.693557 0.70516 -0.147419 0.693553 0.705161 -0.288396 0.647746 0.705152 -0.288399 0.647755 0.705152 -0.416773 0.573639 0.705155 -0.416771 0.573636 0.705156 -0.526928 0.474448 0.705157 -0.526928 0.474448 0.705157 -0.614056 0.354525 0.705158 -0.614056 0.354525 0.705159 -0.674346 0.219108 0.705156 -0.674349 0.219109 0.705157 -0.705167 0.0741161 0.705159 -0.705165 0.0741158 0 -0.997212 -0.0746167 0 -0.997212 -0.0746167 -0.69472 -0.694771 0.186165 -0.694725 -0.694767 0.186162 -0.694729 -0.508603 0.508601 -0.694724 -0.508606 0.508605 -0.694735 -0.186159 0.694758 -0.69474 -0.186159 0.694753 -0.69474 0.186159 0.694753 -0.694742 0.186158 0.694751 -0.694743 0.508593 0.508591 -0.694748 0.508589 0.508588 -0.694751 0.694742 0.186157 -0.694747 0.694747 0.186157 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707108 0.707105 0 0.707108 0.707105 0 0.965925 0.258821 0 0.965925 0.258821 0.694746 0.694746 0.186158 0.694751 0.694742 0.186156 0.694748 0.50859 0.508587 0.694743 0.508592 0.508592 0.694742 0.186158 0.694751 0.69474 0.186159 0.694753 0.69474 -0.186157 0.694753 0.694735 -0.18616 0.694757 0.694723 -0.508607 0.508604 0.694729 -0.508602 0.508602 0.694725 -0.694767 0.186163 0.69472 -0.694772 0.186164 -0.69472 -0.694771 0.186165 -0.694725 -0.694767 0.186162 -0.694729 -0.508603 0.508601 -0.694724 -0.508606 0.508605 -0.694735 -0.186158 0.694758 -0.694743 -0.186158 0.69475 -0.694743 0.186157 0.69475 -0.694742 0.186158 0.694751 -0.694743 0.508593 0.508591 -0.694748 0.508589 0.508588 -0.694751 0.694742 0.186157 -0.694747 0.694747 0.186157 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.258817 0.965927 0 -0.258817 0.965927 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707108 0.707105 0 0.707108 0.707105 0 0.965925 0.258821 0 0.965925 0.258821 0.694746 0.694746 0.186158 0.694751 0.694742 0.186156 0.694748 0.50859 0.508587 0.694743 0.508592 0.508592 0.694742 0.186158 0.694751 0.694743 0.186158 0.69475 0.694744 -0.186156 0.69475 0.694735 -0.18616 0.694757 0.694723 -0.508607 0.508604 0.694729 -0.508602 0.508602 0.694725 -0.694767 0.186163 0.69472 -0.694772 0.186164 -0.69472 -0.694771 0.186165 -0.694725 -0.694766 0.186162 -0.694731 -0.508602 0.508599 -0.694721 -0.508607 0.508607 -0.694731 -0.186157 0.694762 -0.694747 -0.186157 0.694747 -0.694747 0.186155 0.694747 -0.694739 0.186159 0.694754 -0.694741 0.508596 0.508592 -0.694751 0.508587 0.508587 -0.694752 0.694741 0.186157 -0.694747 0.694747 0.186157 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258814 0.965927 0 -0.258814 0.965927 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965925 0.258821 0 0.965925 0.258821 0.694746 0.694746 0.186158 0.694752 0.694741 0.186155 0.694751 0.508588 0.508585 0.694741 0.508594 0.508594 0.694739 0.186157 0.694755 0.694747 0.186157 0.694747 0.694747 -0.186153 0.694747 0.694732 -0.186161 0.694761 0.694721 -0.508609 0.508606 0.694731 -0.5086 0.5086 0.694726 -0.694766 0.186163 0.69472 -0.694772 0.186164 -0.694747 -0.694747 0.186157 -0.694752 -0.694742 0.186155 -0.694751 -0.508587 0.508587 -0.694751 -0.508587 0.508587 -0.694752 -0.186157 0.694741 -0.694747 -0.186157 0.694747 -0.694746 0.186158 0.694746 -0.694752 0.186155 0.694741 -0.694751 0.508583 0.50859 -0.694731 0.5086 0.5086 -0.694725 0.694766 0.186163 -0.69472 0.694772 0.186163 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258821 0.965925 0 0.258821 0.965925 0 0.707102 0.707111 0 0.707102 0.707111 0 0.965926 0.25882 0 0.965926 0.25882 0.69472 0.694772 0.186164 0.694725 0.694767 0.186161 0.69473 0.508598 0.508604 0.694751 0.508587 0.508587 0.694752 0.186157 0.694741 0.694747 0.186157 0.694747 0.694746 -0.186158 0.694746 0.694752 -0.186155 0.694741 0.694751 -0.508587 0.508587 0.694751 -0.508587 0.508587 0.694752 -0.694741 0.186156 0.694747 -0.694747 0.186156 -0.694746 -0.694746 0.186158 -0.694752 -0.694741 0.186155 -0.694751 -0.508588 0.508585 -0.694741 -0.508594 0.508594 -0.694738 -0.186156 0.694755 -0.694747 -0.186156 0.694747 -0.694747 0.186155 0.694747 -0.694739 0.186159 0.694754 -0.694741 0.508594 0.508594 -0.694741 0.508594 0.508594 -0.694739 0.694755 0.186157 -0.694747 0.694747 0.186157 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258816 0.965927 0 -0.258816 0.965927 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258817 0 0.965926 0.258817 0.694747 0.694747 0.186155 0.694739 0.694754 0.186159 0.694741 0.508594 0.508594 0.694741 0.508594 0.508594 0.694739 0.186157 0.694755 0.694747 0.186157 0.694747 0.694747 -0.186154 0.694747 0.694739 -0.186158 0.694754 0.694741 -0.508596 0.508592 0.694751 -0.508587 0.508587 0.694752 -0.694741 0.186157 0.694747 -0.694747 0.186157 -0.694747 -0.694747 0.186156 -0.694738 -0.694754 0.18616 -0.694738 -0.508596 0.508595 -0.694738 -0.508596 0.508595 -0.69474 -0.186158 0.694753 -0.694743 -0.186158 0.69475 -0.694743 0.186157 0.69475 -0.69474 0.186158 0.694752 -0.694738 0.508596 0.508595 -0.694743 0.508592 0.508593 -0.694745 0.694748 0.186158 -0.69474 0.694753 0.186159 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965925 0.258821 0 0.965925 0.258821 0.69474 0.694753 0.18616 0.694745 0.694749 0.186157 0.694743 0.508592 0.508592 0.694739 0.508595 0.508596 0.69474 0.186158 0.694753 0.694743 0.186158 0.69475 0.694743 -0.186157 0.69475 0.69474 -0.186158 0.694752 0.694738 -0.508596 0.508595 0.694738 -0.508596 0.508595 0.694738 -0.694755 0.186159 0.694746 -0.694746 0.186158 -0.694747 -0.694747 0.186156 -0.694738 -0.694754 0.18616 -0.694738 -0.508596 0.508595 -0.694738 -0.508596 0.508595 -0.69474 -0.186159 0.694752 -0.69474 -0.186159 0.694753 -0.69474 0.186159 0.694753 -0.69474 0.186158 0.694752 -0.694738 0.508596 0.508595 -0.694743 0.508592 0.508593 -0.694745 0.694748 0.186158 -0.69474 0.694753 0.186159 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965925 0.258821 0 0.965925 0.258821 0.69474 0.694753 0.18616 0.694745 0.694749 0.186157 0.694743 0.508592 0.508592 0.694739 0.508595 0.508596 0.69474 0.186159 0.694752 0.69474 0.186159 0.694753 0.69474 -0.186159 0.694753 0.69474 -0.186158 0.694752 0.694738 -0.508596 0.508595 0.694738 -0.508596 0.508595 0.694738 -0.694755 0.186159 0.694746 -0.694746 0.186158 -0.694746 -0.694746 0.186158 -0.694752 -0.694741 0.186155 -0.694751 -0.508588 0.508585 -0.694741 -0.508594 0.508594 -0.694738 -0.186156 0.694755 -0.694747 -0.186156 0.694747 -0.694747 0.186155 0.694747 -0.694739 0.186159 0.694754 -0.694741 0.508594 0.508594 -0.694741 0.508594 0.508594 -0.694739 0.694755 0.186157 -0.694747 0.694747 0.186157 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258816 0.965927 0 -0.258816 0.965927 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258817 0 0.965926 0.258817 0.694747 0.694747 0.186155 0.694739 0.694754 0.186159 0.694741 0.508594 0.508594 0.694741 0.508594 0.508594 0.694739 0.186157 0.694755 0.694747 0.186157 0.694747 0.694747 -0.186154 0.694747 0.694739 -0.186158 0.694754 0.694741 -0.508596 0.508592 0.694751 -0.508587 0.508587 0.694752 -0.694741 0.186157 0.694747 -0.694747 0.186157 -0.694746 -0.694746 0.186158 -0.694752 -0.694741 0.186155 -0.694751 -0.508588 0.508585 -0.694741 -0.508594 0.508594 -0.694739 -0.186157 0.694755 -0.694747 -0.186157 0.694747 -0.694747 0.186155 0.694747 -0.694739 0.186159 0.694754 -0.694741 0.508592 0.508595 -0.694731 0.5086 0.5086 -0.694726 0.694766 0.186163 -0.69472 0.694772 0.186164 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707105 0.707109 0 0.707105 0.707109 0 0.965925 0.258821 0 0.965925 0.258821 0.69472 0.694771 0.186165 0.694725 0.694766 0.186162 0.694731 0.508599 0.508602 0.694741 0.508594 0.508594 0.694739 0.186157 0.694755 0.694747 0.186157 0.694747 0.694747 -0.186155 0.694747 0.694739 -0.186159 0.694754 0.694741 -0.508596 0.508592 0.694751 -0.508587 0.508587 0.694752 -0.694741 0.186157 0.694747 -0.694747 0.186157 -0.69472 -0.694771 0.186165 -0.694725 -0.694766 0.186162 -0.694731 -0.508602 0.508599 -0.694721 -0.508607 0.508607 -0.694731 -0.186157 0.694762 -0.694747 -0.186157 0.694747 -0.694747 0.186155 0.694747 -0.694739 0.186159 0.694754 -0.694741 0.508596 0.508592 -0.694751 0.508587 0.508587 -0.694752 0.694741 0.186157 -0.694747 0.694747 0.186157 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258814 0.965927 0 -0.258814 0.965927 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965925 0.258821 0 0.965925 0.258821 0.694746 0.694746 0.186158 0.694752 0.694741 0.186155 0.694751 0.508588 0.508585 0.694741 0.508594 0.508594 0.694739 0.186157 0.694755 0.694747 0.186157 0.694747 0.694747 -0.186153 0.694747 0.694732 -0.186161 0.694761 0.694721 -0.508609 0.508606 0.694731 -0.5086 0.5086 0.694726 -0.694766 0.186163 0.69472 -0.694772 0.186164 -3.68258e-05 -0.103912 0.994587 0.320229 -0.385318 0.865438 0 -0.394582 0.918861 0 -0.477911 0.878408 0.000476868 -0.479583 0.877496 0.00614898 -0.487009 0.873375 5.39745e-05 -0.106377 0.994326 0 -0.106037 0.994362 0.0432957 -0.207717 0.97723 0.166635 -0.200787 0.965359 0 -0.303415 0.952859 0.0414762 0.203459 0.978205 0.159781 0.20524 0.965581 0 0.303413 0.952859 0.0129382 0 0.999916 0.0129382 0 0.999916 -3.65331e-05 0.10392 0.994586 4.51438e-05 0.106137 0.994352 0 0.106316 0.994332 0.00886121 0.490534 0.871377 0.000487601 0.479589 0.877493 0 0.47788 0.878425 0 0.394582 0.918861 0.320221 0.385319 0.865441 0 0.488465 0.872583 0 0.587786 0.809017 0 0.587786 0.809017 0 0.743145 0.669131 0 0.743145 0.669131 0 0.866025 0.5 0 0.866025 0.5 0 0.951057 0.309017 0 0.951057 0.309017 0 0.994522 0.104528 0 0.994522 0.104528 0 -0.490555 0.87141 0 -0.587785 0.809017 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.743145 0.669131 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.951057 0.309017 0 -0.951057 0.309017 0 -0.994522 0.104529 0 -0.994522 0.104529 0 -0.999164 -0.0408815 -0.179827 -0.975398 -0.127515 0 -0.996033 -0.0889806 0 -0.972476 -0.233001 -0.0915341 -0.960439 -0.263018 0 -0.947887 -0.318608 0 -0.902396 -0.430907 -0.07166 -0.906866 -0.415281 0.0844505 -0.808826 -0.581952 0 -0.821005 -0.570921 0 -0.995521 0.0945445 0 -0.995521 0.0945445 0 -0.959926 0.280253 0 -0.959926 0.280253 0 -0.89001 0.455941 0 -0.89001 0.455941 0 -0.788272 0.615327 0 -0.788272 0.615327 0 -0.658349 0.752713 0 -0.658349 0.752713 0 0.995185 -0.0980176 0 0.995185 -0.0980176 0 0.95694 -0.290284 0 0.95694 -0.290284 0 0.881921 -0.471397 0 0.881921 -0.471397 0 0.773011 -0.634393 0 0.773011 -0.634393 0 0.634393 -0.77301 0 0.634393 -0.77301 0 0.471397 -0.881921 0 0.471397 -0.881921 0 0.290285 -0.95694 0 0.290285 -0.95694 0 0.0980172 -0.995185 0 0.0980172 -0.995185 0 -0.0980171 -0.995185 0 -0.0980171 -0.995185 0 -0.290285 -0.95694 0 -0.290285 -0.95694 0 -0.471397 -0.881921 0 -0.471397 -0.881921 0 -0.634393 -0.773011 0 -0.634393 -0.773011 0 -0.773011 -0.634393 0 -0.773011 -0.634393 0 -0.881921 -0.471397 0 -0.881921 -0.471397 0 -0.95694 -0.290285 0 -0.95694 -0.290285 0 -0.995185 -0.0980172 0 -0.995185 -0.0980172 0 -0.997204 0.0747301 0.293499 -0.950723 0.0999248 0 -0.98393 0.178556 0 -0.967835 0.251587 0.345755 -0.8924 0.289958 0 -0.936235 0.351375 0.181113 -0.851703 0.491731 0.18111 -0.851704 0.491731 0 -0.907358 0.420359 0.345757 -0.697311 0.627861 0 -0.772417 0.635116 0 -0.81772 0.575617 0.293499 -0.561899 0.773387 0 -0.646599 0.76283 0 -0.701798 0.712376 0.293502 -0.388823 0.873312 0 -0.433884 0.900969 0 -0.56332 0.826239 0 -0.08964 0.995974 0 -0.163818 0.986491 0.345758 -0.195089 0.917819 0 -0.266037 0.963963 0 -0.33733 0.941387 0.181116 0 0.983462 0.181116 0 0.983462 0 0.0896406 0.995974 0 0.163818 0.986491 0.345757 0.195088 0.917819 0 0.266037 0.963963 0 0.33733 0.941387 0.293502 0.388823 0.873311 0 0.433884 0.900969 0 0.56332 0.826239 0.293501 0.561899 0.773387 0 0.6466 0.762829 0 0.701798 0.712376 0.345755 0.697311 0.627862 0 0.772417 0.635116 0 0.90736 0.420354 0.18112 0.851702 0.49173 0.181106 0.851704 0.491733 0 0.817721 0.575615 0 0.936235 0.351375 0.34576 0.892398 0.289958 0 0.967835 0.251586 0 0.983929 0.178558 0.293503 0.950721 0.099925 0 0.997204 0.0747301 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.997204 -0.0747301 0.293503 0.950721 -0.099925 0 0.90736 -0.420354 0 0.936235 -0.351375 0.34576 0.892398 -0.289958 0 0.967835 -0.251586 0 0.983929 -0.178558 0.181122 0.851701 -0.491731 0.181108 0.851704 -0.491731 0 0.817721 -0.575615 0 0.772417 -0.635116 0.345755 0.697311 -0.627862 0 0.701798 -0.712376 0 0.6466 -0.762829 0.293501 0.561899 -0.773387 0 0.56332 -0.826239 0 0.433884 -0.900969 0.293502 0.388823 -0.873311 0 0.33733 -0.941387 0 0.266037 -0.963963 0.345757 0.195088 -0.917819 0 0.163818 -0.986491 0.181116 0 -0.983462 0.181116 0 -0.983462 0 0.0896406 -0.995974 0.345758 -0.195089 -0.917819 0 -0.163818 -0.986491 0 -0.08964 -0.995974 0.293502 -0.388823 -0.873312 0 -0.33733 -0.941387 0 -0.266037 -0.963963 0.293499 -0.561899 -0.773387 0 -0.56332 -0.826239 0 -0.433884 -0.900969 0 -0.81772 -0.575617 0 -0.772417 -0.635116 0.345757 -0.697311 -0.627861 0 -0.701798 -0.712376 0 -0.646599 -0.76283 0.181113 -0.851703 -0.491731 0.18111 -0.851704 -0.491731 0 -0.907358 -0.420359 0 -0.936235 -0.351375 0.345756 -0.8924 -0.289958 0 -0.967835 -0.251587 0 -0.98393 -0.178556 0.293499 -0.950723 -0.0999248 0 -0.997204 -0.0747301 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.658349 0.752713 0 0.658349 0.752713 0 0.788272 0.615327 0 0.788272 0.615327 0 0.89001 0.455941 0 0.89001 0.455941 0 0.959926 0.280253 0 0.959926 0.280253 0 0.995521 0.0945449 0 0.995521 0.0945449 0 0.844282 0.5359 0 0.811725 -0.584039 -0.071659 0.818894 -0.569454 0 0.86855 -0.495602 0 0.909204 -0.416351 -0.116999 0.915779 -0.384266 0 0.947886 -0.318609 0 0.972477 -0.233 -0.136561 0.973369 -0.184129 0 0.991563 -0.129628 0 0.999727 0.0233756 -0.210812 0.975508 0.062785 0 0.999164 -0.0408838 0 0.90302 0.429598 -0.128348 0.884829 0.447889 0 0.934688 0.35547 0 0.972813 0.231591 -0.17003 0.95067 0.259454 0 0.987025 0.160564 -0.0859646 0.780461 0.619266 0 0.793423 0.60867 0 0.719491 0.694502 -0.0397682 0.648341 0.760311 0 0.642609 0.766194 0 -0.642609 0.766194 0.0397654 -0.648341 0.760311 -0.03643 -0.777734 0.627537 0 -0.783361 0.621567 0 -0.884702 0.466158 -0.0793435 -0.889395 0.450201 0 -0.844282 0.5359 0 -0.9953 0.0968359 -0.15719 -0.985529 0.0634293 0 -0.987026 0.160563 0 -0.957967 0.286878 -0.118542 -0.957915 0.261432 0 -0.934688 0.35547 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0.994522 -0.104528 0 0.994522 -0.104528 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.866025 -0.5 0 0.866025 -0.5 0 0.743145 -0.669131 0 0.743145 -0.669131 0 0.587786 -0.809017 0 0.587786 -0.809017 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.207912 -0.978148 0 0.207912 -0.978148 0 0 -1 0 0 -1 0 -0.207912 -0.978148 0 -0.207912 -0.978148 0 -0.406737 -0.913545 0 -0.406737 -0.913545 0 -0.587785 -0.809017 0 -0.587785 -0.809017 0 -0.743145 -0.669131 0 -0.743145 -0.669131 0 -0.866025 -0.5 0 -0.866025 -0.5 0 -0.951057 -0.309017 0 -0.951057 -0.309017 0 -0.994522 -0.104529 0 -0.994522 -0.104529 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.262694 -0.964879 0 0.262694 -0.964879 0 0.0884884 -0.996077 0 0.0884884 -0.996077 0 -0.0884883 -0.996077 0 -0.0884883 -0.996077 0 -0.262694 -0.964879 0 -0.262694 -0.964879 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.988865 -0.148818 0 0.988865 -0.148818 2.68603e-07 0.988865 -0.148817 0 0.988865 -0.148818 -7.67283e-08 0.988865 -0.148818 -1.01894e-06 0.988864 -0.14882 4.80094e-07 0.988865 -0.148817 -1.66257e-06 0.988864 -0.14882 0 -0.988865 -0.148819 5.59593e-07 -0.988865 -0.148818 0 -0.988864 -0.148819 0 -0.988864 -0.148819 2.21301e-07 -0.988865 -0.148818 -8.06092e-07 -0.988864 -0.14882 0 -0.258819 -0.965926 0 -0.258819 -0.965926 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0.707107 0.707107 0 0.707107 0.707107 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.707107 0.707107 0 -0.707107 0.707107 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.379309 0.92527 0 -0.379309 0.92527 0 0.0806425 0.996743 0 0.0806425 0.996743 0 0.523122 0.852258 0 0.523122 0.852258 0 -0.523121 0.852259 0 -0.523121 0.852259 0 -0.0806428 0.996743 0 -0.0806428 0.996743 0 0.379308 0.92527 0 0.379308 0.92527 0 0.285317 0.958433 0 0.285317 0.958433 0 0.718693 0.695327 0 0.718693 0.695327 0 0.967336 0.253496 0 0.967336 0.253496 0 -0.967336 0.253496 0 -0.967336 0.253496 0 -0.718693 0.695327 0 -0.718693 0.695327 0 -0.285317 0.958433 0 -0.285317 0.958433 0 0.955813 -0.293975 -0.160303 0.985305 -0.058963 -0.0135698 0.965836 -0.258798 0 0.999833 -0.0182595 0 0.955813 -0.293975 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.955811 -0.293983 -0.0251274 -0.96562 -0.25874 -0.0020603 -0.998492 -0.0548502 0 -0.999833 -0.0182595 -0.0364937 -0.972345 -0.230679 0.0318792 -0.792951 -0.608451 0 -0.831467 -0.555575 0 -0.608761 -0.793354 0.0213376 -0.555443 -0.831281 -0.0318819 -0.258689 -0.965434 0 -0.195092 -0.980785 0 -0.423825 -0.905744 0 -0.423825 -0.905744 0 -0.293522 -0.955952 0 -0.293522 -0.955952 0 0.293523 -0.955952 0 0.293523 -0.955952 0 0.423825 -0.905744 0 0.423825 -0.905744 0 0.941869 -0.33598 0 0.941869 -0.33598 0 0.745717 -0.666263 0 0.745717 -0.666263 0 0.439525 -0.89823 0 0.439525 -0.89823 0 -0.439524 -0.898231 0 -0.439524 -0.898231 0 -0.745718 -0.666262 0 -0.745718 -0.666262 0 -0.94187 -0.335978 0 -0.94187 -0.335978 0 0.976296 -0.216441 0 0.976296 -0.216441 0 0.793354 -0.608761 0 0.793354 -0.608761 0 0.461748 -0.887011 0 0.461748 -0.887011 0 -0.461749 -0.887011 0 -0.461749 -0.887011 0 -0.793353 -0.608762 0 -0.793353 -0.608762 0 -0.976296 -0.216439 0 -0.976296 -0.216439 0 -0.507473 -0.861668 0 -0.507473 -0.861668 0 -0.775762 -0.631026 0 -0.775762 -0.631026 0 -0.946943 -0.3214 0 -0.946943 -0.3214 0 0.946943 -0.3214 0 0.946943 -0.3214 0 0.775759 -0.631029 0 0.775759 -0.631029 0 0.507473 -0.861668 0 0.507473 -0.861668 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707108 0.707106 0 0.707108 0.707106 0 0.965925 0.258822 0 0.965925 0.258822 0 -0.965927 0.258816 0 -0.965927 0.258816 0 -0.707104 0.70711 0 -0.707104 0.70711 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.980786 0.195089 0 0.831469 0.555572 -0.1204 0.776864 0.618051 0 0.856677 0.515853 -0.00668096 0.870128 0.49278 -0.0159633 0.876813 0.480567 0 0.903753 0.428055 0 0.980786 0.195089 -0.0552039 -0.902384 0.427381 -0.00665503 -0.870109 0.492814 0 -0.85671 0.515798 0 -0.782554 0.622583 -0.0701572 -0.829421 0.5542 0 -0.888984 0.457938 0 -0.980784 0.195095 0 -0.980784 0.195095 0 0.925996 -0.377534 -0.167273 0.969438 -0.179472 -0.031722 0.96544 -0.258689 0 0.999837 -0.0180763 0 0.925996 -0.377534 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.948705 -0.316164 -0.0545023 -0.979327 -0.194801 -0.0169484 -0.989018 -0.146818 0 -0.999836 -0.0181278 0 -0.948705 -0.316164 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.555569 -0.83147 0 -0.555569 -0.83147 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 0.652356 -0.757913 0.00524628 0.65327 -0.757107 -0.00520982 0.898769 -0.438392 0 0.899314 -0.437303 0 -0.898781 -0.438398 -0.00526326 -0.899304 -0.437293 0.00526099 -0.652348 -0.757901 0 -0.653278 -0.757118 0 -0.0123248 -0.999924 0.00591084 -0.0110302 -0.999922 -0.0058786 0.406919 -0.913445 0.0117656 0.410445 -0.911809 -0.0116571 0.751562 -0.659559 0.0175217 0.755747 -0.654629 -0.0174101 0.958418 -0.284835 0 0.959662 -0.281155 0 -0.958564 -0.284878 -0.0177242 -0.959512 -0.281111 0.0180447 -0.751491 -0.659497 -0.0120248 -0.755811 -0.654679 0.0119648 -0.406899 -0.913395 -0.00597319 -0.410464 -0.911857 0.00594546 0.0123245 -0.999906 0 0.0110304 -0.999939 0 1 0 0 1 0 0.258823 -0.965925 0 0.258823 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0 -1 0 0 -1 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -0.831468 -0.555573 0 -0.831468 -0.555573 0 -0.555573 -0.831468 0 -0.555573 -0.831468 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -1 0 0 -1 0 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258818 0 -0.965926 0.258818 0 0.980787 0.195082 0 0.980787 0.195082 0 0.831468 0.555573 0 0.831468 0.555573 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195093 0.980785 0 0.195093 0.980785 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965926 -0.258818 0 0.965926 -0.258818 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.555569 -0.83147 0 -0.555569 -0.83147 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -1 0 0 -1 0 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0 1 0 0 1 0 0.980787 0.195083 0 0.980787 0.195083 0 0.831469 0.555571 0 0.831469 0.555571 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195091 0.980785 0 0.195091 0.980785 0 1 0 0 1 0 0 -0.707112 0.707102 0 -0.707112 0.707102 0 -0.698581 0.69857 -0.15487 -0.698579 0.698572 -0.15487 -0.698579 0.567671 -0.435588 -0.698582 0.567668 -0.435588 -0.698581 0.330395 -0.634684 -0.69858 0.330396 -0.634684 -0.694751 0.186155 0.694742 -0.694752 0.186157 0.694741 -0.694753 0.508586 0.508584 -0.69475 0.508582 0.508592 -0.694752 0.694741 0.186158 -0.694752 0.694741 0.186158 -0.707112 0.183012 -0.683008 -0.707112 0.183012 -0.683008 -0.707111 0 0.707102 -0.707111 0 0.707102 -0.707111 0 0.707102 -0.700433 0.672229 -0.239795 -0.700434 0.672229 -0.239794 -0.700434 0.532231 -0.475523 -0.700437 0.53223 -0.47552 -0.700436 0.313696 -0.64108 -0.700436 0.313696 -0.64108 -0.694752 -0.694742 0.186153 -0.69475 -0.694745 0.186148 -0.694751 -0.508585 0.508589 -0.694753 -0.508581 0.508591 -0.694752 -0.186156 0.694742 -0.694751 -0.186158 0.694742 -0.707114 0.699226 -0.105229 -0.707108 0.699231 -0.105231 -0.707112 -0.707102 0 -0.707112 -0.707102 0 -0.701471 0.674885 -0.229061 -0.701472 0.674884 -0.229062 -0.701471 0.552882 -0.449733 -0.701468 0.552886 -0.449733 -0.701468 0.361676 -0.614111 -0.701465 0.36168 -0.614113 -0.69858 -0.330396 -0.634684 -0.69858 -0.330396 -0.634685 -0.698579 -0.56767 -0.435589 -0.698581 -0.567669 -0.435587 -0.698581 -0.69857 -0.154869 -0.698581 -0.69857 -0.154869 -0.705717 0.186117 -0.683611 -0.705721 0.186115 -0.683608 -0.705721 0.0626931 -0.705711 -0.705721 0.0626931 -0.705711 -0.705721 -0.0626931 -0.705711 -0.705721 -0.062693 -0.705711 -0.705721 -0.186116 -0.683608 -0.705718 -0.186116 -0.68361 -0.707112 -0.183012 -0.683008 -0.707112 -0.183011 -0.683008 -0.701468 -0.361676 -0.614112 -0.70147 -0.361677 -0.614109 -0.70147 -0.552884 -0.449732 -0.70147 -0.552885 -0.449732 -0.701469 -0.674887 -0.229062 -0.701469 -0.674887 -0.229063 -0.700436 -0.313695 -0.641081 -0.700435 -0.313696 -0.641081 -0.700435 -0.532231 -0.475522 -0.700436 -0.53223 -0.475522 -0.700436 -0.672227 -0.239792 -0.700436 -0.672228 -0.239792 -0.707111 -0.699229 -0.10523 -0.707111 -0.699229 -0.10523 0.69472 -0.694772 -0.186164 0.694725 -0.694767 -0.186161 0.694731 -0.508602 -0.508599 0.694721 -0.508607 -0.508607 0.694731 -0.186157 -0.694762 0.694747 -0.186157 -0.694747 0.694747 0.186155 -0.694747 0.694739 0.186159 -0.694754 0.694741 0.508596 -0.508592 0.694751 0.508587 -0.508587 0.694752 0.694741 -0.186156 0.694747 0.694747 -0.186156 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 -0.694747 0.694747 -0.186157 -0.694752 0.694742 -0.186155 -0.694751 0.508588 -0.508585 -0.694741 0.508594 -0.508594 -0.694739 0.186157 -0.694755 -0.694747 0.186157 -0.694747 -0.694747 -0.186153 -0.694747 -0.694732 -0.186161 -0.694761 -0.694721 -0.508609 -0.508606 -0.694731 -0.5086 -0.5086 -0.694725 -0.694766 -0.186163 -0.69472 -0.694772 -0.186163 0.694747 -0.694747 -0.186157 0.694749 -0.694745 -0.186156 0.694741 -0.508594 -0.508594 0.69475 -0.508589 -0.508586 0.694752 -0.186157 -0.694741 0.694747 -0.186157 -0.694747 0.694746 0.186158 -0.694746 0.694752 0.186155 -0.694741 0.694751 0.508583 -0.50859 0.694722 0.508608 -0.508605 0.694722 0.69477 -0.186164 0.69472 0.694772 -0.186164 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707102 -0.707111 0 0.707102 -0.707111 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.25882 0 -0.965926 -0.25882 -0.69472 0.694772 -0.186164 -0.694722 0.69477 -0.186163 -0.694721 0.508604 -0.508611 -0.69475 0.508589 -0.508586 -0.694752 0.186157 -0.694741 -0.694747 0.186157 -0.694747 -0.694746 -0.186158 -0.694746 -0.694752 -0.186155 -0.694741 -0.694751 -0.508587 -0.508587 -0.694741 -0.508595 -0.508592 -0.694749 -0.694745 -0.186157 -0.694747 -0.694747 -0.186157 0.694747 -0.694747 -0.186157 0.694752 -0.694742 -0.186155 0.694751 -0.508588 -0.508585 0.694741 -0.508594 -0.508594 0.694738 -0.186156 -0.694755 0.694747 -0.186156 -0.694747 0.694747 0.186155 -0.694747 0.694739 0.186159 -0.694754 0.694741 0.508594 -0.508594 0.694741 0.508594 -0.508594 0.694738 0.694755 -0.186156 0.694747 0.694747 -0.186156 0 0.965927 -0.258816 0 0.965927 -0.258816 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 -0.694747 0.694747 -0.186154 -0.694739 0.694754 -0.186158 -0.694741 0.508594 -0.508594 -0.694741 0.508594 -0.508594 -0.694739 0.186157 -0.694755 -0.694747 0.186157 -0.694747 -0.694747 -0.186154 -0.694747 -0.694739 -0.186158 -0.694754 -0.694741 -0.508596 -0.508592 -0.694751 -0.508587 -0.508587 -0.694752 -0.694741 -0.186156 -0.694747 -0.694747 -0.186156 0.694747 -0.694747 -0.186156 0.694738 -0.694754 -0.18616 0.694738 -0.508596 -0.508595 0.694736 -0.508597 -0.508597 0.694737 -0.186159 -0.694756 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694737 0.186159 -0.694756 0.694736 0.508598 -0.508597 0.694743 0.508591 -0.508593 0.694745 0.694748 -0.186158 0.69474 0.694753 -0.186158 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.965926 -0.258818 0 -0.965926 -0.258818 -0.69474 0.694753 -0.186159 -0.694745 0.694749 -0.186157 -0.694743 0.508592 -0.508592 -0.694736 0.508596 -0.508598 -0.694737 0.186159 -0.694756 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694737 -0.186159 -0.694756 -0.694736 -0.508598 -0.508597 -0.694738 -0.508595 -0.508595 -0.694738 -0.694755 -0.186158 -0.694746 -0.694746 -0.186158 0.694747 -0.694747 -0.186156 0.694738 -0.694754 -0.18616 0.694738 -0.508596 -0.508595 0.694738 -0.508596 -0.508595 0.69474 -0.186158 -0.694753 0.694743 -0.186158 -0.69475 0.694743 0.186157 -0.69475 0.69474 0.186158 -0.694752 0.694738 0.508596 -0.508595 0.694743 0.508592 -0.508593 0.694745 0.694748 -0.186158 0.69474 0.694753 -0.186158 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.965926 -0.258818 0 -0.965926 -0.258818 -0.69474 0.694753 -0.186159 -0.694745 0.694749 -0.186157 -0.694743 0.508592 -0.508592 -0.694739 0.508595 -0.508596 -0.69474 0.186158 -0.694753 -0.694743 0.186158 -0.69475 -0.694743 -0.186157 -0.69475 -0.69474 -0.186158 -0.694752 -0.694738 -0.508596 -0.508595 -0.694738 -0.508596 -0.508595 -0.694738 -0.694755 -0.186158 -0.694746 -0.694746 -0.186158 0.694747 -0.694747 -0.186157 0.694752 -0.694742 -0.186155 0.694751 -0.508588 -0.508585 0.694741 -0.508594 -0.508594 0.694738 -0.186156 -0.694755 0.694747 -0.186156 -0.694747 0.694747 0.186155 -0.694747 0.694739 0.186159 -0.694754 0.694741 0.508594 -0.508594 0.694741 0.508594 -0.508594 0.694738 0.694755 -0.186156 0.694747 0.694747 -0.186156 0 0.965927 -0.258816 0 0.965927 -0.258816 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 -0.694747 0.694747 -0.186154 -0.694739 0.694754 -0.186158 -0.694741 0.508594 -0.508594 -0.694741 0.508594 -0.508594 -0.694739 0.186157 -0.694755 -0.694747 0.186157 -0.694747 -0.694747 -0.186154 -0.694747 -0.694739 -0.186158 -0.694754 -0.694741 -0.508596 -0.508592 -0.694751 -0.508587 -0.508587 -0.694752 -0.694741 -0.186156 -0.694747 -0.694747 -0.186156 0.694746 -0.694746 -0.186158 0.694752 -0.694741 -0.186155 0.694751 -0.508588 -0.508585 0.694741 -0.508594 -0.508594 0.694739 -0.186157 -0.694755 0.694747 -0.186157 -0.694747 0.694747 0.186155 -0.694747 0.694739 0.186159 -0.694754 0.694741 0.508592 -0.508595 0.694731 0.5086 -0.5086 0.694726 0.694766 -0.186163 0.69472 0.694772 -0.186164 0 0.965925 -0.258821 0 0.965925 -0.258821 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965925 -0.258821 0 -0.965925 -0.258821 -0.69472 0.694771 -0.186165 -0.694725 0.694766 -0.186162 -0.694731 0.508599 -0.508602 -0.694741 0.508594 -0.508594 -0.694739 0.186157 -0.694755 -0.694747 0.186157 -0.694747 -0.694747 -0.186155 -0.694747 -0.694739 -0.186159 -0.694754 -0.694741 -0.508596 -0.508592 -0.694751 -0.508587 -0.508587 -0.694752 -0.694741 -0.186157 -0.694747 -0.694747 -0.186157 0.69472 -0.694772 -0.186164 0.694725 -0.694767 -0.186161 0.694731 -0.508602 -0.508599 0.694721 -0.508607 -0.508607 0.694731 -0.186157 -0.694762 0.694747 -0.186157 -0.694747 0.694747 0.186155 -0.694747 0.694739 0.186159 -0.694754 0.694741 0.508596 -0.508592 0.694751 0.508587 -0.508587 0.694752 0.694741 -0.186156 0.694747 0.694747 -0.186156 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 -0.694747 0.694747 -0.186157 -0.694752 0.694742 -0.186155 -0.694751 0.508588 -0.508585 -0.694741 0.508594 -0.508594 -0.694739 0.186157 -0.694755 -0.694747 0.186157 -0.694747 -0.694747 -0.186153 -0.694747 -0.694732 -0.186161 -0.694761 -0.694721 -0.508609 -0.508606 -0.694731 -0.5086 -0.5086 -0.694725 -0.694766 -0.186163 -0.69472 -0.694772 -0.186163 0.69472 -0.694771 -0.186164 0.694724 -0.694767 -0.186162 0.694729 -0.508603 -0.508601 0.694724 -0.508606 -0.508605 0.694735 -0.186158 -0.694758 0.694743 -0.186158 -0.69475 0.694743 0.186157 -0.69475 0.694742 0.186158 -0.694751 0.694743 0.508593 -0.508591 0.694748 0.508589 -0.508588 0.694751 0.694742 -0.186157 0.694747 0.694747 -0.186157 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258817 -0.965927 0 -0.258817 -0.965927 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 -0.694746 0.694746 -0.186158 -0.694751 0.694742 -0.186156 -0.694748 0.50859 -0.508587 -0.694743 0.508592 -0.508592 -0.694742 0.186158 -0.694751 -0.694743 0.186158 -0.69475 -0.694744 -0.186156 -0.69475 -0.694735 -0.18616 -0.694757 -0.694723 -0.508607 -0.508604 -0.694729 -0.508602 -0.508602 -0.694725 -0.694767 -0.186163 -0.69472 -0.694772 -0.186163 0.69472 -0.694771 -0.186164 0.694724 -0.694767 -0.186162 0.694729 -0.508603 -0.508601 0.694721 -0.508607 -0.508607 0.694731 -0.186159 -0.694761 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694741 0.508595 -0.508593 0.694748 0.508589 -0.508589 0.694751 0.694742 -0.186157 0.694747 0.694747 -0.186157 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258817 -0.965927 0 -0.258817 -0.965927 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 -0.694746 0.694746 -0.186158 -0.694751 0.694742 -0.186156 -0.694748 0.50859 -0.508587 -0.694741 0.508594 -0.508594 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186157 -0.694753 -0.694732 -0.186161 -0.694761 -0.694721 -0.508609 -0.508606 -0.694729 -0.508602 -0.508602 -0.694725 -0.694767 -0.186163 -0.69472 -0.694772 -0.186163 -0.939694 0 0.342018 -0.939694 0 0.342018 -0.923696 -0.183736 0.336195 -0.923695 -0.183728 0.336202 -0.783069 -0.523233 0.3362 -0.783068 -0.523234 0.336199 -0.523233 -0.783069 0.336199 -0.523233 -0.783069 0.336199 -0.183735 -0.923694 0.336199 -0.183731 -0.923697 0.336195 -0.244171 0.911251 0.331666 -0.244168 0.911251 0.331668 -0.667082 0.667082 0.331666 -0.66708 0.667083 0.331668 -0.91125 0.244168 0.331669 -0.911252 0.244166 0.331666 0 -0.939694 0.342018 0 -0.939694 0.342018 0 0.939694 0.342018 0 0.939694 0.342018 0.244173 -0.911251 0.331666 0.244168 -0.91125 0.33167 0.667081 -0.667081 0.331671 0.667083 -0.66708 0.331669 0.91125 -0.244168 0.331669 0.911248 -0.244171 0.331673 0.923695 0.183727 0.336203 0.923696 0.183736 0.336195 0.783071 0.523234 0.336194 0.783072 0.523229 0.336199 0.523229 0.783072 0.336199 0.52323 0.783071 0.336199 0.183737 0.923694 0.336199 0.183733 0.923696 0.336195 0.939691 0 0.342025 0.939691 0 0.342025 -0.939694 0 0.342018 -0.939694 0 0.342018 -0.923696 -0.183736 0.336195 -0.923695 -0.183727 0.336203 -0.783069 -0.52323 0.336203 -0.783068 -0.523234 0.336199 -0.52323 -0.783071 0.336199 -0.523231 -0.783071 0.336199 -0.183735 -0.923694 0.336199 -0.183735 -0.923695 0.336199 -0.244168 0.911251 0.331668 -0.244169 0.911251 0.331667 -0.667084 0.667081 0.331664 -0.66708 0.667083 0.33167 -0.91125 0.244169 0.33167 -0.911252 0.244166 0.331666 0 -0.939692 0.342022 0 -0.939692 0.342022 0 0.939693 0.34202 0 0.939693 0.34202 0.244169 -0.91125 0.331669 0.244168 -0.91125 0.33167 0.667083 -0.667079 0.331671 0.667082 -0.66708 0.331671 0.91125 -0.244168 0.33167 0.911249 -0.24417 0.331673 0.923695 0.183727 0.336203 0.923696 0.183736 0.336196 0.783071 0.523233 0.336196 0.783072 0.52323 0.336199 0.523229 0.783072 0.336199 0.523229 0.783073 0.336198 0.183735 0.923695 0.336197 0.183735 0.923695 0.336197 0.939691 0 0.342025 0.939691 0 0.342025 0 0.21286 -0.977083 0 0.21286 -0.977083 0 0.6 -0.8 0 0.6 -0.8 0 -0.6 -0.8 0 -0.6 -0.8 0 -0.212859 -0.977083 0 -0.212859 -0.977083 0 0.374391 0.927271 0.0153905 0.359157 0.93315 -0.0142515 -0.0505735 0.998619 0.0284884 -0.0993864 0.994641 -0.0262009 -0.465997 0.884398 0.0392781 -0.536347 0.843083 -0.0358381 -0.794658 0.605999 0 -0.823909 0.566723 0 -0.932682 0.360701 -0.0431575 -0.975601 0.215266 0 -0.988493 0.151267 0 0.997212 -0.0746167 -0.0511113 0.995277 0.0825319 0 0.987635 0.156772 0 0.930655 0.365899 -0.0447596 0.853259 0.519564 0 0.821535 0.570158 0 0.67939 0.733777 -0.0364704 0.530518 0.846889 0.0243256 0.466018 0.884441 -0.0262402 0.0952369 0.995109 0.0131255 0.0505746 0.998634 -0.0140775 -0.360464 0.932667 0 -0.374391 0.927271 0.705159 -0.705165 -0.0741159 0.705157 -0.705167 -0.074116 0.705157 -0.674348 -0.219109 0.705158 -0.674346 -0.219109 0.705158 -0.614055 -0.354525 0.705157 -0.614056 -0.354525 0.705157 -0.526928 -0.474448 0.705157 -0.526928 -0.474448 0.705156 -0.416771 -0.573636 0.705151 -0.416773 -0.573639 0.705152 -0.288399 -0.647755 0.705161 -0.288395 -0.647747 0.705161 -0.147419 -0.693553 0.705156 -0.14742 -0.693557 0.705156 0 -0.709052 0.705156 0 -0.709052 0.705156 0.14742 -0.693557 0.705159 0.14742 -0.693555 0.705159 0.288397 -0.647749 0.705155 0.288398 -0.647752 0.705156 0.416771 -0.573635 0.705148 0.416775 -0.573642 0.705147 0.526935 -0.474455 0.705157 0.526928 -0.474447 0.705157 0.614056 -0.354526 0.705159 0.614055 -0.354525 0.705159 0.674346 -0.219108 0.705157 0.674348 -0.219109 0.705157 0.705167 -0.0741159 0.705162 0.705162 -0.0741151 0.258802 -0.876445 0.406037 0.258152 -0.836671 0.483052 0.258803 -0.086586 0.962042 0.258153 0 0.966104 0.706097 -0.659165 0.258703 0.706096 -0.10554 0.700207 0.70608 0.55364 0.441513 0.965751 -0.258747 0.0193905 0.96575 -0.252969 0.0577384 0.965751 -0.0764807 0.247944 0.965749 0.176489 0.19021 0.965751 0.258744 0.0193903 0.965751 0.202863 0.161778 0.965752 0.202859 0.161775 0.965752 0.224704 0.129733 0.965749 0.146168 0.21439 0.965752 0.146162 0.21438 0.965753 0.112578 0.23377 0.965752 0.112579 0.233773 0.965751 0.0764799 0.247942 0.965752 0.076479 0.247939 0.965752 0.0386717 0.256569 0.965751 -0.0386719 0.256572 0.965749 -0.0386731 0.256578 0.965749 0 0.259477 0.965751 -0.112581 0.233776 0.965752 -0.112579 0.233773 0.965751 -0.146165 0.214384 0.965751 -0.146166 0.214385 0.965751 -0.176485 0.190206 0.965751 -0.176486 0.190206 0.965751 -0.202863 0.161778 0.965751 -0.241535 0.0947955 0.96575 -0.241537 0.0947964 0.96575 -0.224711 0.129737 0.706064 0.659196 0.258716 0.965753 0.252957 0.0577359 0.965753 0.241527 0.0947923 0.706084 0.659178 0.258708 0.706086 0.613256 0.354063 0.258174 0.836666 0.483049 0.258822 0.789857 0.556001 0.706085 0.398902 0.585083 0.706099 0.398894 0.58507 0.706098 0.30724 0.637989 0.706078 0.307248 0.638007 0.706081 0.208725 0.676671 0.706089 0.208723 0.676664 0.706091 0.10554 0.700212 0.706096 0.10554 0.700207 0.706097 0 0.708115 0.706086 -0.307245 0.638 0.706098 -0.307239 0.637989 0.706099 -0.398894 0.585071 0.706085 -0.398902 0.585082 0.706085 -0.481649 0.519093 0.706095 -0.481642 0.519087 0.706094 -0.553629 0.441504 0.706089 -0.553633 0.441508 0.706089 -0.613253 0.354062 0.965752 0.258743 0.0193901 0.706107 0.706125 0.0529169 0.70608 0.706152 0.0529195 0.258127 0.963409 0.0721986 0.258183 0.963395 0.0721965 0.965751 0.252964 0.0577376 0.706062 0.690395 0.157578 0.706106 0.690352 0.157568 -0.642605 0.746988 0.170494 0.258695 0.950436 0.172479 0.258123 0.836677 0.483057 0.258771 0.876454 0.406036 -0.425314 0.842483 0.330651 0.258411 0.904436 0.339441 0.258601 0.934913 0.243028 0.965752 0.24153 0.0947934 0.965752 0.224704 0.129733 0.706089 0.613253 0.354061 0.706089 0.553633 0.441507 -0.425334 0.707586 0.564281 0.258423 0.746179 0.613542 0.965751 0.176486 0.190206 0.706085 0.481649 0.519094 0.706082 0.481651 0.519096 -0.642595 0.521153 0.561669 0.258609 0.677924 0.688142 -0.64261 0.225839 0.732154 0.258725 0.325844 0.909333 0.258158 0.419177 0.870428 0.258132 0.419179 0.870435 0.258131 0.544228 0.798238 0.258181 0.544222 0.798226 0.258751 0.624579 0.736851 0.258153 0 0.966104 0.258803 0.0865865 0.962042 -0.425318 0.13489 0.894935 0.258378 0.158255 0.952993 0.258573 0.256989 0.93118 0.965749 0.038673 0.256579 0.965749 0 0.259477 0.706097 0 0.708115 0.706096 -0.10554 0.700207 -0.425327 -0.13489 0.894931 0.258367 -0.158256 0.952996 0.965751 -0.0764806 0.247944 0.706086 -0.208724 0.676666 0.706099 -0.20872 0.676653 -0.64261 -0.225839 0.732154 0.258555 -0.256991 0.931185 -0.642617 -0.52114 0.561655 0.258729 -0.624582 0.736856 0.258162 -0.544224 0.798231 0.258131 -0.544229 0.798237 0.258132 -0.41918 0.870434 0.258158 -0.419176 0.870429 0.258725 -0.325844 0.909333 0.258144 -0.836673 0.483053 0.258795 -0.789862 0.556007 -0.425338 -0.707584 0.56428 0.258371 -0.74619 0.613551 0.258562 -0.677933 0.688151 0.96575 -0.202864 0.161779 0.96575 -0.224711 0.129737 0.7061 -0.613243 0.354056 0.706101 -0.659162 0.258702 -0.425345 -0.84247 0.330645 0.25838 -0.904444 0.339443 0.258711 -0.950432 0.172477 0.965751 -0.252966 0.0577378 0.706097 -0.690361 0.15757 0.706098 -0.69036 0.15757 -0.642622 -0.746973 0.170492 0.258568 -0.934922 0.243031 0.96575 -0.258749 0.0193906 0.706098 -0.706134 0.0529175 0.706098 -0.706134 0.0529176 0.258149 -0.963404 0.0721973 0.258144 -0.963405 0.0721973 0.510202 -0.136713 0.849119 0.373498 -0.373492 0.849119 0.136707 -0.510203 0.84912 0.136707 0.510203 0.84912 0.373498 0.373492 0.849119 0.510202 0.136713 0.849119 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.965923 0.258828 0 0.965923 0.258828 0 0.707113 0.707101 0 0.707113 0.707101 0 0.258817 0.965926 0 0.258817 0.965926 0 0.186155 -0.694746 0.694747 0.186159 -0.694748 0.694744 0.508598 -0.50859 0.694741 0.50859 -0.50859 0.694746 0.694745 -0.186163 0.694747 0.694745 -0.186163 0.694746 0.694745 0.186163 0.694746 0.694745 0.186163 0.694747 0.508594 0.508585 0.694747 0.508593 0.508593 0.694742 0.186156 0.694749 0.694744 0.186158 0.694746 0.694747 0.510202 -0.136713 0.849119 0.373498 -0.373492 0.849119 0.136707 -0.510203 0.84912 0.136707 0.510203 0.84912 0.373498 0.373492 0.849119 0.510202 0.136713 0.849119 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.965923 0.258828 0 0.965923 0.258828 0 0.707113 0.707101 0 0.707113 0.707101 0 0.258817 0.965926 0 0.258817 0.965926 0 0.186155 -0.694746 0.694747 0.186159 -0.694748 0.694744 0.508598 -0.50859 0.694741 0.50859 -0.50859 0.694746 0.694745 -0.186163 0.694747 0.694745 -0.186163 0.694746 0.694745 0.186163 0.694746 0.694745 0.186163 0.694747 0.508594 0.508585 0.694747 0.508593 0.508593 0.694742 0.186156 0.694749 0.694744 0.186158 0.694746 0.694747 0.116755 -0.511515 0.851305 0.52467 0 0.851306 0.472708 -0.227656 0.851305 0.327127 -0.410206 0.851304 0.116752 0.511516 0.851305 0.327129 0.410205 0.851304 0.472708 0.227657 0.851305 0.22253 -0.974926 0 0.22253 -0.974926 0 0.623487 -0.781834 0 0.623487 -0.781834 0 0.90096 -0.433903 0 0.90096 -0.433903 0 1 0 0 1 0 0 0.90096 0.433903 0 0.90096 0.433903 0 0.623491 0.78183 0 0.623491 0.78183 0 0.222523 0.974927 0 0.222523 0.974927 0 0.159338 -0.698075 0.69807 0.159329 -0.698072 0.698076 0.446431 -0.559811 0.698077 0.446431 -0.559811 0.698077 0.645104 -0.310683 0.698081 0.645128 -0.31067 0.698065 0.716036 0 0.698064 0.716036 0 0.698064 0.645119 0.31069 0.698063 0.645115 0.310666 0.698079 0.446434 0.559808 0.698078 0.446432 0.559813 0.698074 0.159333 0.698074 0.698073 0.159333 0.698073 0.698074 -0.707105 0 -0.707108 -0.707105 0 -0.707108 -0.694746 0.694746 -0.186159 -0.694746 0.694746 -0.186159 -0.694746 0.50859 -0.50859 -0.694746 0.50859 -0.50859 -0.694746 0.186156 -0.694747 -0.694745 0.186159 -0.694748 -0.694745 -0.186158 -0.694748 -0.694747 -0.186161 -0.694745 -0.704062 -0.432305 -0.563391 -0.71885 -0.491551 -0.491561 -0.70406 -0.563393 -0.432305 -0.694744 -0.694749 -0.186159 -0.694748 -0.694748 -0.186149 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.695271 0.205071 0.688872 -0.69527 0.20507 0.688873 -0.69527 0.51656 0.499765 -0.69527 0.51656 0.499765 -0.69527 0.695272 0.1822 -0.695271 0.695271 0.182198 -0.695271 -0.695271 0.1822 -0.69527 -0.695272 0.182198 -0.69527 -0.51656 0.499765 -0.69527 -0.51656 0.499765 -0.69527 -0.205071 0.688872 -0.69527 -0.205072 0.688873 -0.706913 0 0.7073 -0.706913 0 0.7073 -0.698654 0.698654 0.154161 -0.639676 0.75914 0.120502 -0.706473 0.658662 0.258961 -0.701807 0.585234 0.406162 -0.698654 -0.267861 0.663425 -0.698655 -0.267862 0.663424 -0.698655 0.0361872 0.714543 -0.698653 0.0361886 0.714545 -0.698654 0.333516 0.632969 -0.698652 0.333518 0.63297 -0.70675 0.480644 0.519121 -0.687533 0.55563 0.467518 -0.736834 0.576102 0.353812 -0.705146 -0.460078 0.539535 -0.705144 -0.460079 0.539536 -0.706614 -0.538058 0.459554 -0.755389 -0.513319 0.407298 -0.707033 -0.576293 0.409866 -0.706989 -0.59704 0.379091 -0.707059 -0.597037 0.378964 -0.705145 -0.640298 0.304613 -0.617247 -0.701962 0.355324 -0.707001 -0.661023 0.251393 -0.705146 -0.689785 0.164212 -0.581317 -0.784968 0.214232 -0.706916 -0.698121 0.113566 -0.706375 -0.706373 0.0455069 -0.706491 -0.706261 0.0454554 -0.706739 -0.706885 -0.0288798 -0.70681 -0.706812 -0.0289197 -0.706695 -0.701549 -0.0917144 -0.612033 -0.777052 -0.146992 -0.706948 -0.54862 -0.446365 -0.762726 -0.530962 -0.369227 -0.706533 -0.688202 -0.16489 -0.706925 -0.67043 -0.225348 -0.627529 -0.71795 -0.301256 -0.706161 -0.643763 -0.294799 -0.706847 -0.606483 -0.364069 -0.776004 -0.514799 -0.364415 -0.698863 -0.152248 -0.698864 -0.698863 -0.152249 -0.698864 -0.698862 -0.429154 -0.572205 -0.698862 -0.429155 -0.572205 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.700214 -0.139281 -0.700215 -0.700215 -0.139282 -0.700214 -0.700215 -0.396639 -0.593614 -0.700215 -0.396639 -0.593613 -0.700215 -0.593612 -0.396639 -0.700214 -0.593612 -0.396642 -0.700214 -0.700215 -0.139282 -0.700215 -0.700215 -0.139281 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.700214 -0.700214 0.139285 -0.700214 -0.700214 0.139285 -0.700214 -0.593614 0.396639 -0.700213 -0.593615 0.396639 -0.707106 -0.500001 0.500001 -0.707106 -0.500001 0.500001 -0.697195 -0.375016 0.610968 -0.697195 -0.375016 0.610968 -0.697195 -0.0578113 0.714547 -0.697196 -0.0578101 0.714546 -0.697196 0.271919 0.663308 -0.697195 0.271918 0.66331 -0.705518 0.466567 0.533442 -0.705518 0.466567 0.533442 -0.705518 0.558642 0.436077 -0.705516 0.558643 0.436079 -0.705516 0.630745 0.323123 -0.705515 0.630745 0.323123 -0.705515 0.680295 0.198614 -0.705516 0.680294 0.198613 -0.705516 0.705519 0.0670034 -0.705518 0.705518 0.0670029 -0.697195 -0.27192 0.663309 -0.697197 -0.271918 0.663308 -0.697196 0.0578111 0.714546 -0.697195 0.0578101 0.714547 -0.697195 0.375016 0.610968 -0.697195 0.375016 0.610968 -0.707106 0.500001 0.500001 -0.707106 0.500001 0.500001 -0.700214 0.593613 0.396641 -0.700214 0.593613 0.396641 -0.700214 0.700216 0.139281 -0.700213 0.700216 0.139282 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.694745 0.694748 -0.186157 -0.694746 0.694747 -0.186157 -0.694746 0.50859 -0.50859 -0.694745 0.508591 -0.50859 -0.694746 0.186157 -0.694748 -0.694746 0.186156 -0.694747 -0.707106 0 -0.707107 -0.707106 0 -0.707107 -0.698863 0.429153 -0.572204 -0.698863 0.429153 -0.572205 -0.698863 0.152249 -0.698864 -0.698863 0.152249 -0.698864 -0.705438 0.705441 0.0686351 -0.593243 0.803361 0.0517054 -0.706917 0.69812 0.113566 -0.705439 0.67898 0.20333 -0.625461 0.752726 0.205432 -0.707 0.661024 0.251393 -0.705439 0.62705 0.330399 -0.654743 0.674377 0.341361 -0.707059 0.597037 0.378964 -0.787161 0.465841 0.404192 -0.708917 0.574162 0.409603 -0.707106 0.589942 0.389833 -0.705439 0.455463 0.543056 -0.705439 0.455463 0.543056 -0.707094 0.508766 0.491096 -0.681325 0.573405 0.454975 -0.307998 -0.948735 -0.0709894 -0.697314 0.257461 0.66893 -0.697313 0.257462 0.66893 -0.697313 -0.0712655 0.713215 -0.697313 -0.0712658 0.713215 -0.697314 -0.384732 0.60476 -0.697314 -0.384732 0.60476 -0.704541 -0.564735 0.429763 -0.720049 -0.571729 0.393262 -0.693537 -0.664293 0.278787 -0.706359 -0.660202 0.255324 -0.70301 -0.702997 0.107578 -0.699627 -0.466772 -0.540967 -0.699624 -0.466775 -0.540969 -0.699804 -0.642413 -0.312378 -0.874981 -0.405204 -0.264988 -0.706244 -0.207805 -0.676785 -0.706239 -0.207806 -0.676789 -0.70624 -0.300057 -0.641242 -0.706235 -0.300059 -0.641246 -0.813711 0.529147 -0.240576 -0.950187 0.298408 -0.089984 -0.991523 0.124689 -0.0365306 -0.856071 0.493326 -0.154183 -0.70423 0.661992 -0.256567 -0.698659 0.540786 -0.46843 -0.698669 0.540781 -0.468421 -0.698665 0.293673 -0.652398 -0.698666 0.293673 -0.652398 -0.698666 -0.00789168 -0.715404 -0.698666 -0.00789165 -0.715404 -0.705053 -0.275939 0.653267 -0.701661 -0.145091 0.697582 -0.705431 -0.144511 0.69389 -0.707095 -0.21455 0.673784 -0.775053 -0.247546 0.581389 -0.704121 -0.280185 0.652464 -0.704111 0.280189 0.652474 -0.705286 0.2797 0.651413 -0.773343 0.246691 0.584024 -0.701642 0.145276 0.697562 -0.70542 0.144334 0.693938 -0.707093 0.214549 0.673786 -0.759301 -0.610791 -0.22449 -0.856075 -0.493318 -0.154184 -0.950189 -0.298403 -0.0899841 -0.99153 -0.124637 -0.0365153 -0.698666 0.00789168 -0.715404 -0.698666 0.00789169 -0.715404 -0.698666 -0.293671 -0.652398 -0.69866 -0.293675 -0.652403 -0.698658 -0.540788 -0.468428 -0.698669 -0.540779 -0.468423 -0.70624 -0.644489 -0.293017 -0.706235 0.300058 -0.641246 -0.706237 0.300058 -0.641245 -0.706237 0.207807 -0.67679 -0.70624 0.207806 -0.676788 -0.793258 0.54758 -0.266268 -0.706092 0.592643 -0.387567 -0.699624 0.466775 -0.540969 -0.699627 0.466774 -0.540966 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.695267 -0.205072 0.688876 0.695268 -0.205072 0.688875 0.69527 -0.51656 0.499766 0.69526 -0.516565 0.499774 0.695257 -0.695284 0.182203 0.695271 -0.695271 0.182196 0.706909 0 0.707304 0.706909 0 0.707304 0.695271 0.695271 0.1822 0.69527 0.695272 0.1822 0.69527 0.51656 0.499766 0.69527 0.51656 0.499766 0.695268 0.205072 0.688875 0.695267 0.205072 0.688876 0.70708 0.707133 0 0.707107 0.707107 0 0.707087 0.707126 -2.43893e-06 0.707133 0.70708 0 0.707077 -0.505806 0.494169 0.703085 -0.560652 0.437425 0.692048 -0.566793 0.447007 0.702407 -0.557003 0.443139 0.707101 -0.500004 0.500004 0.707101 -0.500004 0.500004 0.697192 0.27192 0.663312 0.697189 0.271922 0.663315 0.697194 -0.0578114 0.714547 0.697195 -0.0578114 0.714547 0.697192 -0.375017 0.610971 0.697191 -0.375018 0.610972 0.705514 -0.466569 0.533444 0.70551 -0.466572 0.533448 0.70551 -0.558648 0.436083 0.70551 -0.558648 0.436082 0.70551 -0.63075 0.323125 0.70551 -0.63075 0.323125 0.70551 -0.6803 0.198615 0.705509 -0.6803 0.198615 0.70551 -0.705526 0.0670037 0.705511 -0.705524 0.0670035 0.697191 0.375018 0.610972 0.697195 0.375015 0.610968 0.697195 0.0578111 0.714547 0.697193 0.0578116 0.714548 0.697194 -0.27192 0.66331 0.697192 -0.27192 0.663312 0.707101 0.500004 0.500004 0.707101 0.500004 0.500004 0.707077 0.505785 0.49419 0.691168 0.569791 0.44455 0.702525 0.556888 0.443097 0.702386 0.557021 0.44315 0.849121 -0.136708 -0.510201 0.84912 -0.373491 -0.373496 0.84912 -0.510202 -0.136706 0.849122 0.510198 -0.136715 0.849121 0.373495 -0.37349 0.849121 0.136705 -0.510201 0.851306 -0.511515 -0.116746 0.851307 0 -0.524668 0.851307 -0.227644 -0.47271 0.851307 -0.410203 -0.327124 0.851307 0.511514 -0.116746 0.851307 0.410199 -0.327127 0.851307 0.227644 -0.47271 0.849121 -0.13671 -0.5102 0.84912 -0.373491 -0.373496 0.84912 -0.510202 -0.136706 0.849122 0.510198 -0.136715 0.849121 0.373495 -0.37349 0.849121 0.136707 -0.5102 0.849121 -0.136706 -0.510201 0.849121 -0.373493 -0.373493 0.84912 -0.510202 -0.136706 0.849122 0.5102 -0.136706 0.849122 0.373492 -0.373492 0.849121 0.136705 -0.510201 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.994522 -0.104529 0 -0.994522 -0.104529 0 -0.951056 -0.309017 0 -0.951056 -0.309017 0 -0.866026 -0.5 0 -0.866026 -0.5 0 -0.743145 -0.66913 0 -0.743145 -0.66913 0 -0.587785 -0.809017 0 -0.587785 -0.809017 0 -0.406737 -0.913546 0 -0.406737 -0.913546 0 -0.207912 -0.978148 0 -0.207912 -0.978148 0 0 -1 0 0 -1 0 0.207912 -0.978148 0 0.207912 -0.978148 0 0.406736 -0.913546 0 0.406736 -0.913546 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.743145 -0.66913 0 0.743145 -0.66913 0 0.866026 -0.5 0 0.866026 -0.5 0 0.951056 -0.309017 0 0.951056 -0.309017 0 0.994522 -0.104528 0 0.994522 -0.104528 -0.938953 0.090605 0.331902 -0.939695 -0.331646 0.0835771 -0.939756 -0.331486 0.083516 -0.940168 -0.329925 0.0850449 -0.94237 -0.323025 0.0871401 -0.951832 -0.292737 0.0912206 -0.948236 -0.302793 0.0957313 -0.939561 -0.331515 0.085571 -0.939511 -0.329141 0.0947959 -0.941633 -0.316445 0.114845 -0.939351 -0.323031 0.115203 -0.939228 -0.330262 0.0936945 -0.938798 -0.331784 0.092615 -0.938165 -0.333862 0.0915616 -0.938414 -0.333386 0.0907376 -0.939135 -0.332117 0.0878883 -0.943811 -0.324013 0.0650895 -0.939538 -0.335768 0.0672883 -0.941894 -0.329808 0.0637374 -0.938576 -0.338193 0.0685575 -0.940246 -0.338388 0.0378368 -0.934407 -0.350372 0.064208 -0.947252 -0.315563 0.0559764 -0.944885 -0.322242 0.0579004 -0.938499 -0.339297 0.0640074 -0.943042 -0.326839 0.0620274 -0.940991 -0.332385 0.0636898 -0.941704 -0.330437 0.0632862 -0.941424 -0.331174 0.0636016 -0.939849 0.337894 0.0501267 -0.93969 0.337978 0.0524739 -0.940078 0.336891 0.0525142 -0.940188 0.336587 0.0524967 -0.93955 0.340009 0.0404935 -0.940215 0.337207 0.0478254 -0.940417 0.336695 0.0474578 -0.940015 0.337609 0.0489044 -0.939593 0.341933 0.0157322 -0.98513 0.1715 0.0103739 -0.948563 0.314924 0.0324161 -0.940595 0.337507 0.0370037 -0.944552 -0.312597 0.10052 -0.941853 -0.319435 0.104276 -0.905057 -0.394316 0.159331 -0.939477 -0.32266 0.115213 -0.939609 -0.309003 0.147146 -0.941652 -0.306197 0.139764 -0.93623 -0.304083 0.176089 -0.939508 -0.299158 0.166818 -0.939673 -0.285133 0.188982 -0.939456 -0.284978 0.190289 -0.940163 -0.268214 0.210132 -0.939281 -0.269136 0.21288 -0.93951 -0.227141 0.256376 -0.937147 -0.233499 0.259294 -0.93427 -0.240325 0.263406 -0.933485 -0.242087 0.264573 -0.937503 -0.242331 0.249729 -0.9388 -0.242722 0.244419 -0.939335 -0.243232 0.241843 -0.939586 -0.243879 0.240212 -0.940251 -0.249295 0.231906 -0.937568 -0.252121 0.239585 -0.938606 -0.251262 0.236402 -0.939753 -0.250869 0.232227 -0.939327 -0.252451 0.232235 -0.940331 -0.249091 0.231799 -0.949923 -0.217765 0.224108 -0.957628 -0.203652 0.203653 -0.944779 -0.237201 0.226116 -0.941551 -0.245547 0.230626 -0.942683 -0.229176 0.242543 -0.940752 -0.231488 0.247789 -0.9302 -0.237502 0.27986 -0.939595 -0.226886 0.25629 -0.939608 -0.205295 0.273844 -0.941844 -0.206299 0.265274 -0.935831 -0.188059 0.298086 -0.939501 -0.187871 0.286432 -0.939672 -0.164722 0.299804 -0.939547 -0.164299 0.300428 -0.939886 -0.140151 0.311404 -0.939313 -0.139879 0.313248 -0.927831 -0.0956893 0.360519 -0.932859 -0.0966664 0.347029 -0.936148 -0.0976919 0.337761 -0.937599 -0.0984535 0.333489 -0.947246 -0.106859 0.30217 -0.937299 -0.107 0.331695 -0.939734 -0.107833 0.324458 -0.939335 -0.108649 0.325339 -0.941311 -0.105168 0.320738 -0.944041 -0.101134 0.313941 -0.951607 -0.0912787 0.293448 -0.951129 -0.0918674 0.294813 -0.940805 -0.0859278 0.327875 -0.935853 -0.0771189 0.343848 -0.942343 -0.0767885 0.325718 -0.939622 -0.0752796 0.333831 -0.938548 -0.0783536 0.336137 -0.93728 -0.0810076 0.339034 -0.935624 -0.0839857 0.342863 -0.931717 -0.0901361 0.351822 -0.932624 0.0795116 0.351982 -0.926769 0.0857434 0.365715 -0.934978 0.0760801 0.346449 -0.956713 0.0411001 0.288115 -0.936657 0.0660512 0.343964 -0.939638 0.0620302 0.336501 -0.939348 0.021124 0.342315 -0.939592 0.0206674 0.341671 -0.93964 -0.00644585 0.342103 -0.939672 -0.0066107 0.342013 -0.939493 -0.0338262 0.340895 -0.935414 -0.0281637 0.352431 -0.942037 -0.0598606 0.330126 -0.939607 -0.0545999 0.337872 -0.939666 -0.0751215 0.333743 -0.940707 -0.0761687 0.330557 -0.93961 0.0620222 0.336579 -0.942617 0.0622585 0.328019 -0.936933 0.0630007 0.343785 -0.939877 0.084233 0.330962 -0.940805 0.085928 0.327875 -0.942378 0.086798 0.323094 -0.940671 0.0902297 0.327103 -0.939874 0.092946 0.328632 -0.939686 0.0949001 0.328609 -0.939661 0.0941045 0.328911 -0.939513 0.092644 0.329747 -0.93972 0.0943713 0.328664 -0.939692 0.0951984 0.328505 -0.939606 0.108593 0.324574 -0.942231 0.0997024 0.319783 -0.934979 0.139217 0.32624 -0.939484 0.127934 0.317808 -0.939672 0.153014 0.305948 -0.939736 0.152634 0.305941 -0.939282 0.177523 0.293659 -0.939384 0.177231 0.293506 -0.939704 0.199627 0.277681 -0.942105 0.206797 0.263957 -0.936601 0.226743 0.267145 -0.939669 0.232056 0.25134 -0.946917 0.231942 0.222602 -0.941037 0.238365 0.240064 -0.94478 0.237198 0.226114 -0.94155 0.245548 0.230627 -0.917994 0.307285 0.250724 -0.939577 0.239124 0.24498 -0.938629 0.262129 0.224196 -0.935375 0.267126 0.231769 -0.94028 0.258927 0.220977 -0.939652 0.244731 0.239084 -0.939519 0.244076 0.240274 -0.939206 0.243514 0.242059 -0.938769 0.24325 0.244011 -0.938966 0.242453 0.244048 -0.939388 0.24039 0.244464 -0.939683 0.237959 0.245706 -0.939692 0.237288 0.246321 -0.939692 0.237159 0.246444 -0.939702 0.237853 0.245735 -0.939912 0.238657 0.244149 -0.941584 0.255583 0.219312 -0.939486 0.260908 0.222022 -0.939671 0.277621 0.199863 -0.939833 0.276768 0.200284 -0.938954 0.294426 0.177987 -0.939423 0.292934 0.17797 -0.93969 0.305575 0.153645 -0.941988 0.306077 0.137754 -0.936524 0.324885 0.131807 -0.93967 0.322249 0.114786 -0.936026 0.344823 0.0703669 -0.938731 0.337401 0.0703233 -0.939601 0.335327 0.0686013 -0.94065 0.332271 0.0690939 -0.942931 0.325674 0.0694104 -0.936492 0.339286 0.0887046 -0.93002 0.358257 0.0819503 -0.932278 0.352913 0.07944 -0.936614 0.342511 0.0737669 -0.938199 0.333925 0.0909765 -0.938928 0.33149 0.0923461 -0.941859 0.320467 0.101013 -0.937436 0.333796 0.0989621 -0.938616 0.330201 0.0998349 -0.939669 0.326701 0.101437 -0.939624 0.326785 0.101578 -0.940744 0.324405 0.0988011 -0.94212 0.321123 0.096387 -0.9441 0.316154 0.0933913 -0.947182 0.308049 0.0891733 -0.942369 0.323029 0.0871383 -0.94017 0.329921 0.0850456 0 0.975353 -0.220651 0.0572597 0.969894 -0.236698 0 0.953638 -0.300957 0 0.926513 -0.376262 0.0646923 0.916864 -0.393923 0 0.892032 -0.451971 0 0.853028 -0.521865 0.0711052 0.838571 -0.540132 0 0.806698 -0.590963 0 0.756851 -0.653587 0.0764987 0.73721 -0.67132 0 0.699907 -0.714234 0 0.640542 -0.767923 0.0808792 0.615598 -0.783899 0 0.574498 -0.818506 0 0.507195 -0.861831 0.0842497 0.477097 -0.874803 0 0.433805 -0.901007 0 0.360355 -0.932815 0.0866104 0.325517 -0.941561 0 0.281575 -0.959539 0 0.203931 -0.978985 0.0879638 0.16502 -0.98236 0 0.121854 -0.992548 0 0 -1 0.172489 -0.0404922 -0.984179 0 0.0420809 -0.999114 0 -0.326745 -0.945113 0.146688 -0.35556 -0.923071 0 -0.28064 -0.959813 0 -0.165662 -0.986183 0.159629 -0.200375 -0.966627 0 -0.120888 -0.992666 0 -0.617622 -0.786475 0.12057 -0.635127 -0.762939 0 -0.573701 -0.819065 0 -0.478799 -0.877925 0.133663 -0.501812 -0.854587 0 -0.432929 -0.901428 0 -0.840699 -0.541503 0.0941996 -0.848728 -0.520372 0 -0.806123 -0.591748 0 -0.739376 -0.673292 0.107413 -0.75184 -0.650538 0 -0.699212 -0.714914 0 -0.971488 -0.237087 0.0676234 -0.972906 -0.221093 0 -0.953344 -0.301885 0 -0.918789 -0.39475 0.080933 -0.923108 -0.375927 0 -0.891593 -0.452839 0 -0.975138 0.2216 0.0547577 -0.970031 0.236732 0 -0.953344 0.301885 0 -0.926146 0.377164 0.062505 -0.916992 0.393978 0 -0.891592 0.452839 0 -0.852519 0.522696 0.0692316 -0.838682 0.540204 0 -0.806123 0.591747 0 -0.756215 0.654324 0.0749399 -0.737297 0.671399 0 -0.699212 0.714914 0 -0.639794 0.768546 0.0796335 -0.61566 0.783978 0 -0.573701 0.819065 0 -0.506355 0.862325 0.0833163 -0.477134 0.874872 0 -0.432928 0.901428 0 -0.359447 0.933165 0.0859891 -0.325535 0.941612 0 -0.28064 0.959813 0 -0.202979 0.979183 0.087655 -0.165024 0.982387 0 -0.120887 0.992666 0 -0.0411083 0.999155 0.0883108 0 0.996093 0 0.0420809 0.999114 0 0.326745 0.945113 0.150694 0.356241 0.922163 0 0.281574 0.95954 0 0.165662 0.986183 0.163612 0.201183 0.965793 0 0.121854 0.992548 0 0.617622 0.786475 0.124623 0.635549 0.761936 0 0.574497 0.818506 0 0.478799 0.877925 0.137694 0.502364 0.853622 0 0.433805 0.901007 0 0.840699 0.541503 0.0982883 0.848898 0.519338 0 0.806699 0.590963 0 0.739376 0.673293 0.111483 0.752133 0.649513 0 0.699908 0.714233 0 0.971488 0.237088 0.0717384 0.97284 0.220082 0 0.953638 0.300957 0 0.918789 0.39475 0.085037 0.923157 0.374899 0 0.892032 0.451972 -0.422645 -0.896235 -0.134662 -0.427363 -0.893097 -0.140495 -0.422554 -0.895716 -0.138352 -0.4447 -0.873411 -0.198482 -0.421788 0.896487 -0.135666 -0.427577 0.892982 -0.140576 -0.424188 0.894794 -0.139317 -0.423091 0.895807 -0.136099 -0.422412 0.896636 -0.132707 -0.22702 -0.657435 -0.718499 -0.422538 -0.5564 -0.715458 -0.422477 -0.519987 -0.742379 -0.503856 -0.473746 -0.722284 -0.354687 -0.473435 -0.806261 -0.42254 -0.434881 -0.795197 -0.422443 -0.392402 -0.817045 -0.504656 -0.352009 -0.788297 -0.362299 -0.335028 -0.869768 -0.422547 -0.302177 -0.854484 -0.42241 -0.254373 -0.869979 -0.503953 -0.221581 -0.834825 -0.369597 -0.188606 -0.90985 -0.422544 -0.161707 -0.8918 -0.422365 -0.109576 -0.899778 -0.501737 -0.0854141 -0.860793 -0.376586 -0.0380821 -0.925599 -0.422553 -0.0170741 -0.906178 -0.422327 0.0381439 -0.90564 -0.497986 0.0534118 -0.865539 -0.383265 0.112549 -0.916755 -0.422553 0.127995 -0.897255 -0.422278 0.184857 -0.887417 -0.492664 0.191748 -0.848831 -0.38965 0.25932 -0.8837 -0.422555 0.269771 -0.865258 -0.422227 0.326659 -0.845587 -0.485727 0.326419 -0.810876 -0.395739 0.398391 -0.827451 -0.422559 0.404611 -0.811008 -0.422174 0.459779 -0.781263 -0.477112 0.454284 -0.752323 -0.401542 0.526148 -0.749621 -0.422563 0.529046 -0.735901 -0.422119 0.580678 -0.696153 -0.466741 0.572291 -0.674266 -0.407065 0.639295 -0.652381 -0.422562 0.639874 -0.641874 -0.422055 0.686139 -0.592523 -0.454526 0.677535 -0.578232 -0.412315 0.734936 -0.538392 -0.422565 0.734245 -0.53134 -0.421992 0.773355 -0.473123 -0.440357 0.767311 -0.466176 -0.417289 0.810656 -0.41074 -0.422565 0.809738 -0.407141 -0.421922 0.840007 -0.341132 -0.424113 0.839177 -0.340457 -0.421994 0.864567 -0.272847 -0.422572 0.864405 -0.272465 -0.421856 0.884316 -0.200056 -0.405673 0.891004 -0.203815 -0.423534 0.895059 -0.1396 -0.594072 -0.514658 -0.618227 -0.422508 -0.633737 -0.647969 -0.422536 -0.66361 -0.617321 -0.222929 -0.764573 -0.604757 -0.575948 -0.618196 -0.534901 -0.422534 -0.730628 -0.536329 -0.422533 -0.753756 -0.503307 -0.21883 -0.852221 -0.475219 -0.556931 -0.708067 -0.43413 -0.422556 -0.808083 -0.410424 -0.42253 -0.824517 -0.376351 -0.32093 -0.877156 -0.357213 -0.485212 -0.82194 -0.298302 -0.422575 -0.864043 -0.273607 -0.422527 -0.874075 -0.239715 -0.256066 -0.946741 -0.19522 -0.406314 -0.895837 -0.17996 -0.397676 -0.895812 0.198433 -0.466177 -0.863044 0.194509 -0.531464 -0.826021 0.187713 -0.427383 -0.893085 0.140508 -0.420194 0.896594 0.13984 -0.423914 0.895052 0.138487 -0.422997 0.895897 0.1358 -0.422433 0.896634 0.132653 -0.40606 -0.895947 0.179982 -0.264933 -0.943782 0.1977 -0.422526 -0.874076 0.239715 -0.422575 -0.864043 0.273607 -0.485211 -0.821941 0.298302 -0.32093 -0.877156 0.357213 -0.42253 -0.824517 0.376351 -0.422556 -0.808083 0.410425 -0.492257 -0.760242 0.423929 -0.329876 -0.804799 0.493438 -0.422532 -0.753756 0.503308 -0.422532 -0.730628 0.536329 -0.497681 -0.680279 0.538084 -0.338478 -0.711579 0.615702 -0.422535 -0.66361 0.617321 -0.422507 -0.633738 0.64797 -0.501537 -0.584019 0.638265 -0.346749 -0.6001 0.720864 -0.422538 -0.5564 0.715458 -0.422477 -0.519987 0.742379 -0.503856 -0.473746 0.722284 -0.354687 -0.473435 0.806261 -0.422544 -0.43488 0.795196 -0.422447 -0.392401 0.817044 -0.504658 -0.352009 0.788296 -0.362298 -0.335027 0.869768 -0.422542 -0.302179 0.854486 -0.42255 -0.161706 0.891797 -0.421994 -0.232577 0.876259 -0.555081 -0.233435 0.798369 -0.3696 -0.188606 0.909848 -0.422553 -0.0170741 0.906178 -0.42199 -0.08952 0.90217 -0.54289 -0.101521 0.833645 -0.376586 -0.038082 0.925599 -0.421982 0.0558397 0.904883 -0.530156 0.0356804 0.847149 -0.34136 0.132739 0.930513 -0.422355 0.110452 0.899676 -0.42197 0.199767 0.884327 -0.516858 0.17458 0.838081 -0.359133 0.277793 0.890985 -0.422396 0.255222 0.869738 -0.421962 0.338557 0.841028 -0.502979 0.311455 0.806231 -0.374659 0.413909 0.829644 -0.422434 0.393199 0.816667 -0.421954 0.468641 0.7761 -0.488499 0.44256 0.752004 -0.388052 0.537978 0.748328 -0.422469 0.520711 0.741876 -0.421946 0.586675 0.691212 -0.473391 0.564223 0.676427 -0.399402 0.647246 0.649269 -0.422497 0.634371 0.647356 -0.421934 0.689624 0.588549 -0.45764 0.672945 0.581129 -0.408797 0.739344 0.535029 -0.422524 0.731153 0.53562 -0.421926 0.774838 0.470749 -0.441222 0.765506 0.468321 -0.416304 0.812322 0.408441 -0.422546 0.808486 0.409641 -0.421914 0.840128 0.340843 -0.424117 0.839057 0.340746 -0.421979 0.864668 0.272548 -0.42257 0.864311 0.272766 -0.42191 0.88381 0.202169 -0.40632 0.89121 0.201616 -0.423774 0.895088 0.138686 -0.424989 0.894222 0.140538 -0.4246 0.894513 0.139859 0.705874 -0.688142 -0.167938 0.705874 -0.688141 -0.167938 0.705874 -0.650812 -0.279616 0.705875 -0.650812 -0.279616 0.705875 -0.595497 -0.383566 0.705874 -0.595499 -0.383567 0.705874 -0.523728 -0.476918 0.705874 -0.523728 -0.476918 0.705873 -0.437485 -0.557091 0.705873 -0.437485 -0.557091 0.705873 -0.339152 -0.621868 0.705874 -0.339151 -0.621867 0.705874 -0.231446 -0.669459 0.705874 -0.231446 -0.669459 0.705873 -0.117345 -0.698551 0.705875 -0.117344 -0.69855 0.705874 0 -0.708337 0.705874 0 -0.708337 0.705875 0.117344 -0.698549 0.705873 0.117345 -0.698551 0.705874 0.231446 -0.669459 0.705874 0.231446 -0.669459 0.705874 0.339151 -0.621867 0.705875 0.339151 -0.621866 0.705876 0.437483 -0.557089 0.705875 0.437484 -0.557089 0.705875 0.523727 -0.476918 0.705877 0.523726 -0.476916 0.705877 0.595496 -0.383565 0.705874 0.595498 -0.383567 0.705874 0.650813 -0.279616 0.705871 0.650815 -0.279617 0.70587 0.688145 -0.167939 0.705879 0.688136 -0.167936 0.705879 0.688136 0.167937 0.70587 0.688145 0.167938 0.705871 0.650815 0.279617 0.705872 0.650814 0.279617 0.705872 0.5955 0.383568 0.705878 0.595495 0.383565 0.705877 0.523726 0.476916 0.705875 0.523727 0.476917 0.705875 0.437484 0.557089 0.705876 0.437483 0.557089 0.705875 0.339151 0.621866 0.705874 0.339151 0.621867 0.705874 0.231446 0.669459 0.705874 0.231446 0.669459 0.705873 0.117345 0.698551 0.705875 0.117344 0.69855 0.705874 0 0.708337 0.705874 0 0.708337 0.705875 -0.117344 0.698549 0.705873 -0.117345 0.698551 0.705874 -0.231446 0.669459 0.705874 -0.231446 0.669459 0.705874 -0.339151 0.621867 0.705873 -0.339152 0.621868 0.705873 -0.437485 0.557091 0.705873 -0.437485 0.557091 0.705873 -0.523729 0.476919 0.705875 -0.523728 0.476918 0.705874 -0.595499 0.383567 0.705873 -0.595499 0.383568 0.705873 -0.650813 0.279616 0.705874 -0.650812 0.279616 0.705874 -0.688141 0.167938 0.705874 -0.688142 0.167938 0 -0.499075 -0.866559 -0.00132355 0.992723 -0.120414 -0.00783452 0.996164 -0.0871534 0 0.999191 -0.0402265 0 0.985963 -0.166962 0 0.978451 -0.20648 -0.00745217 0.965899 -0.258812 -0.00302876 0.960593 -0.277942 0 0.944252 -0.329225 0 0.930246 -0.366936 -0.00737807 0.903617 -0.428279 -0.00564291 0.906294 -0.422611 0 0.876038 -0.482243 0 0.855928 -0.517095 -0.00554052 0.819139 -0.573568 -0.00758298 0.823305 -0.567548 0 0.783227 -0.621736 0 0.757584 -0.652738 -0.00288239 0.721733 -0.692165 -0.00749564 0.707087 -0.707087 0 0.668434 -0.743772 0 0.637977 -0.770055 -0.00210076 0.573575 -0.81915 -0.0136597 0.601432 -0.798807 -8.90419e-05 0.535322 -0.844648 0 0.500446 -0.865768 0 0.465226 -0.885192 -0.00781876 0.422605 -0.90628 -0.00144195 0.393048 -0.919517 0 0.348889 -0.937164 0 0.310911 -0.950439 -0.00996434 0.240603 -0.970572 -0.00427381 0.258817 -0.965917 -0.00529299 0.0819613 -0.996621 -0.00661207 0.0871538 -0.996173 0 0.147867 -0.989007 0 0.187531 -0.982259 0 0.0209078 -0.999781 0 -0.0193281 -0.999813 -0.00543537 -0.0871544 -0.99618 -0.00779029 -0.0788065 -0.99686 0 -0.146302 -0.98924 0 -0.185978 -0.982554 -0.00273871 -0.237542 -0.971373 -0.00753665 -0.258812 -0.965898 0 -0.309407 -0.95093 0 -0.347408 -0.937714 -0.00193644 -0.422617 -0.906306 -0.0139259 -0.3901 -0.920667 -0.000180262 -0.462891 -0.886415 0 -0.636756 -0.771065 -0.0025796 -0.573575 -0.819149 -0.012874 -0.598908 -0.800715 0 -0.53354 -0.845775 0 -0.667257 -0.744828 -0.00973435 -0.719509 -0.694415 -0.00440147 -0.7071 -0.7071 0 -0.75655 -0.653935 0 -0.782243 -0.622973 -0.00653452 -0.819135 -0.573564 -0.00547321 -0.821517 -0.570157 0 -0.855109 -0.518448 0 -0.875272 -0.483631 -0.00459532 -0.902273 -0.431141 -0.00689965 -0.906286 -0.422608 0 -0.929664 -0.368408 0 -0.943731 -0.330714 -0.00373996 -0.965919 -0.258817 -0.0109074 -0.959656 -0.280965 0 -0.978123 -0.208026 0 -0.999126 -0.0418056 -0.0078688 -0.996164 -0.087153 -0.000981121 -0.992337 -0.123555 0 -0.985699 -0.168513 -0.201846 0.977634 0.0590697 -0.203411 -0.341037 0.917779 -0.575865 0.643558 0.504196 -0.575868 -0.504194 0.643556 -0.575869 -0.804151 0.147366 -0.852354 -0.251826 0.45834 -0.852351 0.233928 0.467735 -0.851971 0.322907 0.41216 -0.851966 0.448085 0.270877 -0.850689 0.524702 0.031866 -0.904323 0.419858 0.0769423 -0.852345 0.517798 0.0734381 -0.851966 0.522643 0.0316141 -0.851975 0.477455 0.214885 -0.852353 0.492647 0.175482 -0.904555 0.407051 0.126842 -0.85221 0.502566 0.145482 -0.852208 0.512638 0.104612 -0.852212 0.377477 0.362278 -0.852206 0.405386 0.330768 -0.904088 0.336399 0.263552 -0.852349 0.424429 0.305552 -0.852214 0.166 0.496161 -0.852203 0.205355 0.481227 -0.852347 0.135685 0.505068 -0.851972 0.094379 0.515011 -0.85197 0.0943795 0.515013 -0.851971 0.0316136 0.522634 -0.851969 0.031614 0.522637 -0.852351 -0.0101065 0.522872 -0.903596 -0.0258655 0.427604 -0.8522 -0.0416787 0.521553 -0.852216 -0.0834642 0.516489 -0.905208 -0.0766024 0.418007 -0.852346 -0.114451 0.510301 -0.851972 -0.155769 0.49988 -0.85197 -0.15577 0.499883 -0.85197 -0.214888 0.477462 -0.851971 -0.370234 0.370234 -0.852344 -0.338395 0.398746 -0.905412 -0.261818 0.334186 -0.85222 -0.313824 0.418612 -0.852199 -0.279175 0.442513 -0.852221 -0.47236 0.224936 -0.852196 -0.452785 0.262199 -0.851971 -0.499881 0.155769 -0.852343 -0.484894 0.19593 -0.868565 -0.49377 0.0422553 -0.851971 -0.515013 0.0943797 -0.851971 -0.515012 0.0943794 -0.852387 -0.519673 0.0581072 -0.880405 -0.473006 0.0339608 -0.575867 -0.816052 0.049362 -0.575865 -0.643558 0.504196 -0.852356 -0.43591 0.288915 -0.851971 -0.41216 0.322907 -0.575872 -0.643554 0.504192 -0.575872 -0.578088 0.578088 -0.203056 -0.692376 0.692376 -0.203393 -0.639364 0.741516 -0.575867 0.147366 0.804152 -0.575862 0.147367 0.804155 -0.575862 0.0493626 0.816055 -0.575867 0.0493621 0.816052 -0.575867 -0.0493624 0.816052 -0.575862 -0.0493623 0.816055 -0.575862 -0.147367 0.804155 -0.575866 -0.147366 0.804153 -0.575866 -0.243222 0.780527 -0.575866 -0.243222 0.780527 -0.575872 0.504192 0.643554 -0.851971 0.270872 0.448078 -0.851971 0.322908 0.412161 -0.575868 0.504194 0.643556 -0.575868 0.57809 0.57809 -0.203056 0.692376 0.692376 -0.203394 0.741516 0.639363 -0.572884 0.818149 0.0493568 -0.575876 0.816042 0.0494262 -0.575874 0.804147 0.147366 -0.575866 0.804153 0.147367 -0.575866 0.780527 0.243222 -0.575854 0.780535 0.243223 -0.203058 -0.97738 0.0591206 -0.20306 -0.97738 0.0591205 -0.203345 -0.968449 0.144071 -0.840787 -0.540794 0.024882 -0.89323 -0.448779 0.0271461 -0.575866 -0.816052 0.0493621 -0.575867 -0.804152 0.147366 0.0764886 -0.980738 0.179727 -0.203304 -0.957992 0.202284 -0.203409 -0.917779 0.341038 -0.851971 -0.499882 0.155769 -0.575868 -0.780525 0.243222 -0.575868 -0.780525 0.243221 -0.0933522 -0.950552 0.296204 -0.203133 -0.936751 0.285019 -0.905611 -0.386744 0.17406 -0.575866 -0.745518 0.335531 -0.575867 -0.745517 0.33553 -0.203056 -0.892902 0.401863 -0.203057 -0.892902 0.401863 -0.903077 -0.367539 0.222185 -0.575865 -0.69964 0.422947 -0.575866 -0.699639 0.422946 0.0482399 -0.854785 0.516735 -0.203372 -0.857613 0.472377 -0.203052 -0.692376 0.692376 -0.203391 -0.741516 0.639364 -0.0085279 -0.787155 0.616697 -0.203198 -0.778798 0.593451 -0.203255 -0.827548 0.523309 -0.851971 -0.412161 0.322907 -0.851971 -0.370234 0.370234 -0.575868 -0.57809 0.57809 -0.575868 -0.504194 0.643556 -0.00853166 -0.616696 0.787155 -0.203198 -0.59345 0.778798 -0.203374 -0.472376 0.857613 -0.90334 -0.2219 0.367066 -0.57587 -0.422945 0.699636 -0.575868 -0.422946 0.699638 0.0482462 -0.516735 0.854785 -0.203255 -0.52331 0.827547 -0.851971 -0.214888 0.477461 -0.575866 -0.335531 0.745518 -0.57587 -0.33553 0.745516 -0.203059 -0.401863 0.892902 -0.203058 -0.401863 0.892902 -0.079243 -0.290172 0.953688 -0.20306 -0.291305 0.934831 -0.203306 -0.202284 0.957992 0.0764923 -0.179727 0.980738 -0.203339 -0.144071 0.968451 -0.203055 -0.0591206 0.977381 -0.203056 -0.0591207 0.977381 -0.203056 0.0591207 0.977381 -0.203056 0.0591207 0.977381 -0.203341 0.144071 0.96845 0.0764914 0.179727 0.980738 -0.203306 0.202284 0.957992 -0.203414 0.341038 0.917778 -0.904995 0.126564 0.406159 -0.575866 0.243222 0.780526 -0.575868 0.243221 0.780525 -0.0933575 0.296204 0.950551 -0.203134 0.285019 0.93675 -0.903844 0.1756 0.390167 -0.57587 0.335529 0.745516 -0.575866 0.335531 0.745518 -0.203055 0.401863 0.892902 -0.203063 0.401862 0.892901 -0.851969 0.270874 0.44808 -0.575871 0.422945 0.699636 -0.57587 0.422945 0.699636 0.0482411 0.516736 0.854785 -0.20337 0.472378 0.857613 -0.20305 0.692377 0.692376 -0.203388 0.639363 0.741517 -0.00853166 0.616696 0.787155 -0.203193 0.593452 0.778799 -0.203251 0.52331 0.827548 -0.852348 0.354764 0.384245 -0.904779 0.301144 0.301144 -0.575868 0.57809 0.57809 -0.575867 0.643556 0.504195 -0.00853617 0.787154 0.616697 -0.203198 0.778798 0.593451 -0.203361 0.857615 0.472378 -0.851968 0.448082 0.270875 -0.575879 0.699631 0.422942 -0.575865 0.69964 0.422946 0.0482516 0.854785 0.516735 -0.203255 0.827547 0.523309 -0.851965 0.477469 0.214891 -0.575855 0.745526 0.335533 -0.57588 0.745509 0.335527 -0.203068 0.8929 0.401862 -0.203044 0.892905 0.401863 -0.203056 0.977381 0.0591207 -0.203341 0.96845 0.144072 0.0764869 0.980738 0.179727 -0.203298 0.957993 0.202284 -0.203052 0.934832 0.291304 -0.0792603 0.953686 0.290172 -0.203419 0.917778 0.341033 -0.705758 0.705758 -0.061746 -0.705755 0.70576 -0.0617453 -0.705755 0.684316 -0.183362 -0.705756 0.684315 -0.183362 -0.705756 0.642079 -0.299405 -0.705758 0.642076 -0.299405 -0.705758 0.580331 -0.406352 -0.705756 0.580332 -0.406353 -0.705756 0.500953 -0.500953 -0.705757 0.500953 -0.500953 -0.705757 0.406353 -0.580332 -0.705756 0.406353 -0.580332 -0.705757 0.299406 -0.642078 -0.705756 0.299406 -0.642078 -0.705756 0.183362 -0.684315 -0.705757 0.183361 -0.684314 -0.705757 0.0617458 -0.705758 -0.705757 0.0617459 -0.705758 -0.705757 -0.0617458 -0.705758 -0.705757 -0.0617459 -0.705758 -0.705757 -0.183362 -0.684314 -0.705756 -0.183361 -0.684315 -0.705756 -0.299406 -0.642078 -0.705757 -0.299406 -0.642077 -0.705757 -0.406353 -0.580331 -0.705757 -0.406353 -0.580332 -0.705757 -0.500953 -0.500953 -0.705757 -0.500953 -0.500953 -0.705757 -0.580332 -0.406353 -0.705757 -0.580332 -0.406353 -0.705757 -0.642078 -0.299406 -0.705757 -0.642078 -0.299406 -0.705757 -0.684314 -0.183361 -0.705757 -0.684314 -0.183361 -0.705757 -0.705758 -0.0617458 -0.705757 -0.705758 -0.0617459 -0.705168 -0.416763 -0.573625 -0.705164 -0.416766 -0.573628 -0.705164 -0.526923 -0.474443 -0.705166 -0.526921 -0.474442 -0.705166 -0.614049 -0.354521 -0.705167 -0.614048 -0.354521 -0.705167 -0.674338 -0.219106 -0.705164 -0.674341 -0.219107 -0.705165 -0.705159 -0.0741153 -0.705162 -0.705162 -0.0741153 -0.705166 -0.147418 -0.693548 -0.705167 -0.147418 -0.693547 -0.705166 -0.288393 -0.647743 -0.759506 -0.258733 -0.596832 -0.707096 -0.347526 -0.615826 -0.714713 0 -0.699418 -0.714713 0 -0.699418 -0.70711 -0.0728232 -0.703344 -0.755272 0.266579 -0.598748 -0.705517 0.281879 -0.650223 -0.705168 0.147418 -0.693546 -0.705166 0.147418 -0.693548 -0.70711 0.0728232 -0.703344 -0.705167 0.705157 -0.0741149 -0.705166 0.705158 -0.0741152 -0.705166 0.674339 -0.219106 -0.705167 0.674339 -0.219106 -0.705167 0.614048 -0.354521 -0.705168 0.614047 -0.35452 -0.705168 0.52692 -0.47444 -0.705166 0.526921 -0.474442 -0.705166 0.416765 -0.573627 -0.705167 0.416764 -0.573627 -0.707095 0.347527 -0.615827 0 -0.974929 -0.222514 0 -0.974929 -0.222514 0 -0.781827 -0.623496 0 -0.781827 -0.623496 0 -0.433884 -0.900969 0 -0.433884 -0.900969 0 0 -1 0 0 -1 0 0.433884 -0.900969 0 0.433884 -0.900969 0 0.781833 -0.623487 0 0.781833 -0.623487 0 0.974927 -0.222527 0 0.974927 -0.222527 0 -0.383643 -0.923482 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258817 0 -0.965926 -0.258817 -0.0184524 -0.134038 -0.990804 0 -0.258817 -0.965926 0 0.130588 -0.991437 -0.00959876 0.258805 -0.965882 0 0.382733 -0.923859 0 0.609425 -0.792844 -0.00946919 0.707075 -0.707075 0 0.793846 -0.608119 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.608667 -0.793426 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258816 -0.965927 -0.0184934 0.37958 -0.924974 0 0.129785 -0.991542 -0.0190757 0.793672 -0.608047 0 0.707108 -0.707105 0 0.924207 -0.381893 -0.00946986 0.965882 -0.258808 0 0.991555 -0.129684 0 -0.99134 -0.131323 -0.00805951 -0.965895 -0.25881 0 -0.923571 -0.383428 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.965926 -0.25882 -0.019082 0.991369 -0.129707 0 0.923845 -0.382768 0 0.707108 -0.707106 -0.0184375 0.790979 -0.611565 0 0.607856 -0.794047 0 -0.991458 -0.130429 -0.00796566 -0.965895 -0.25881 0 -0.923917 -0.382594 0 -0.792772 -0.609518 -0.00805931 -0.707085 -0.707083 0 -0.608008 -0.793931 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965926 -0.25882 -0.0184318 0.990785 -0.134182 0 0.923426 -0.383777 0 -0.99158 -0.129497 -0.00805947 -0.965895 -0.258809 0 -0.924276 -0.381726 0 -0.793343 -0.608775 -0.00796601 -0.707084 -0.707084 0 -0.608739 -0.793371 0 -0.381764 -0.92426 -0.00805917 -0.258814 -0.965894 0 -0.129548 -0.991573 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.974929 -0.222518 0 -0.974929 -0.222518 0 -0.78183 -0.623491 0 -0.78183 -0.623491 0 -0.433884 -0.900969 0 -0.433884 -0.900969 0 0 -1 0 0 -1 0 0.433884 -0.900969 0 0.433884 -0.900969 0 0.78183 -0.623491 0 0.78183 -0.623491 0 0.974929 -0.222518 0 0.974929 -0.222518 0 -0.965927 -0.258816 0 -0.965927 -0.258816 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.383685 -0.923464 -0.00805931 -0.258809 -0.965895 0 -0.131604 -0.991302 0 0.130583 -0.991437 -0.00796533 0.258809 -0.965896 0 0.382727 -0.923862 0 0.609459 -0.792818 -0.00805917 0.707084 -0.707084 0 0.793883 -0.608071 0 0.965927 -0.258816 0 0.965927 -0.258816 0 -0.974927 -0.222524 0 -0.974927 -0.222524 0 -0.781831 -0.623491 0 -0.781831 -0.623491 0 -0.433884 -0.900969 0 -0.433884 -0.900969 0 0 -1 0 0 -1 0 0.433884 -0.900969 0 0.433884 -0.900969 0 0.781831 -0.623491 0 0.781831 -0.623491 0 0.974927 -0.222524 0 0.974927 -0.222524 0 -0.991348 -0.13126 -0.00947227 -0.96588 -0.258816 0 -0.923575 -0.383418 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.60782 -0.794075 -0.00805866 0.707078 -0.70709 0 0.792615 -0.609722 0 0.923848 -0.382759 -0.00796579 0.965899 -0.258798 0 0.991435 -0.130602 0 -0.991458 -0.130425 -0.019082 -0.923401 -0.383363 0 -0.965923 -0.258828 0 -0.79282 -0.609457 -0.00947144 -0.707081 -0.707069 0 -0.608033 -0.793912 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707101 -0.707113 0 0.707101 -0.707113 0 0.923417 -0.383798 -0.00805956 0.965898 -0.258798 0 0.991288 -0.131715 0 -0.991573 -0.129546 -0.0184579 -0.925068 -0.379354 0 -0.965926 -0.258817 0 -0.793326 -0.608797 -0.00959775 -0.707074 -0.707074 0 -0.608755 -0.793358 0 -0.381801 -0.924244 -0.00946916 -0.258805 -0.965883 0 -0.1296 -0.991566 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965923 -0.258828 0 0.965923 -0.258828 0 -0.998943 -0.0459615 0 -0.998943 -0.0459615 0 -0.998943 0.0459615 0 -0.998943 0.0459615 0 -0.633751 0.773537 -0.0194622 -0.706973 0.706973 -4.00186e-07 -0.999661 0.0260501 -0.00154884 -0.996864 0.0791178 -0.012227 -0.966501 0.25637 -0.0128254 -0.965846 0.258798 3.1901e-05 -0.891442 0.453135 -5.87519e-05 -0.812077 0.58355 0 -0.998943 0.0459621 0 -0.998943 0.0459621 0 -0.5 0.866026 -1.15678e-07 -0.5 0.866025 0 -0.5 0.866025 0 -0.5 -0.866026 1.89441e-07 -0.5 -0.866025 0 0.998629 -0.0523406 -0.00635037 0.99519 0.0977553 0.00301597 0.987819 0.155576 -0.00344385 0.888088 0.459661 0.00235871 0.873368 0.487056 -0.00245535 0.654448 0.756103 0 0.645268 0.763956 0 0.998943 0.0459615 0 0.998943 0.0459615 0 0.58847 -0.808519 -0.0104749 0.654414 -0.756064 0.00699474 0.776713 -0.629816 -0.00949352 0.888053 -0.459643 0.00446592 0.931937 -0.362593 -0.00584359 0.995193 -0.0977555 0 0.998018 -0.0629367 0 0.500003 0.866023 -7.57316e-07 0.500001 0.866025 0 0.499999 0.866026 0 0.499999 -0.866026 -7.57316e-07 0.500001 -0.866025 0 0.500003 -0.866023 0 0.993199 0.116427 0.00114229 0.996949 0.0780427 0 0.999259 0.0385019 -0.0153516 0.878632 0.477252 0.0124603 0.580003 0.814519 0 0.662497 0.749064 0 0.992505 0.122208 0.00243906 0.995424 0.0955227 -0.00161164 0.956241 0.292576 0 0.964074 0.265634 0 0.825151 0.564912 0.221321 0.692602 0.686527 0.00519264 -0.98796 0.154626 0.00313842 -0.984803 0.173647 -0.00170154 -0.998797 -0.0490022 0 -0.996953 -0.0779987 -0.00187992 -0.939991 0.341194 0.0042206 -0.866017 0.499997 0.00204953 -0.852038 0.523476 -0.000272483 -0.772367 0.635177 0.00165381 -0.642787 0.766043 0 -0.630357 0.776306 0.011021 -0.707063 -0.707065 3.15833e-07 -0.615127 -0.788428 0 -0.996953 0.0779983 -0.00174478 -0.998833 0.0482641 0.00207785 -0.992358 -0.123371 0 -0.988184 -0.153274 0 -0.926617 -0.376007 0.00301892 -0.937845 -0.34704 -0.00274228 -0.818506 -0.574492 0.706028 0.706023 -0.0552787 0.706026 0.706026 -0.0552692 0.701674 0.701674 0.123723 0.699903 0.473181 0.53501 0.688834 0.465964 0.555325 0.710635 0.618244 0.335815 0.701677 0.617046 0.356236 0.706628 0.676623 0.207022 0.719041 0.689759 0.0849306 0.707107 0.353554 0.612371 0.707098 0.353557 0.612381 0.69475 0.508589 0.508587 0.52838 0.555633 0.64194 0.753332 0.584046 0.302294 0.558636 0.801152 0.214664 0.742778 0.666331 0.0654522 0.706716 0.70675 -0.0325083 0.706716 0.706749 -0.0325176 0.706715 0.70675 -0.0325178 0.706715 0.70675 0.0325177 0.706716 0.706749 0.0325177 0.706716 0.70675 0.0325083 0.770102 0.616185 -0.165103 0.700669 0.466941 -0.539471 0.590029 0.570907 -0.570904 0.753331 0.584046 -0.302294 0.281213 0.955049 -0.0938122 0.707098 0.353559 -0.61238 0.707106 0.353553 -0.612373 0.694735 0.508605 -0.508591 0.725407 0.456009 -0.515597 0.685025 0.65741 -0.313932 0.733451 0.656578 -0.17594 0.704442 0.704442 -0.0867388 0.706026 0.706026 0.0552784 0.706028 0.706024 0.0552686 0.706021 -0.706033 0.0552377 0.706021 -0.706033 0.0552367 0.707101 -0.353557 -0.612378 0.7071 -0.353557 -0.612378 0.706727 -0.706738 0.0325176 0.706726 -0.706739 0.0325153 0.706727 -0.706738 0.0325171 0.706727 -0.706738 0.0325171 0.694741 -0.508593 0.508593 0.703418 -0.703432 0.101915 0.790807 -0.59121 0.158414 0.641139 -0.681543 0.352761 0.793633 -0.398167 0.46001 0.7071 -0.353557 0.612378 0.707102 -0.353556 0.612377 0.701668 -0.70168 0.123725 0.6819 -0.725965 0.0893657 0.720612 -0.600449 0.34667 0.685283 -0.657187 0.313835 0.710261 -0.452483 0.539248 0.699906 -0.473184 0.535003 -0.546262 -0.717028 -0.432976 -0.552715 -0.62755 -0.54835 -0.590579 -0.556098 -0.584783 -0.540003 -0.726667 -0.424679 -0.543786 -0.719942 -0.431255 -0.579549 -0.565155 -0.587131 -0.576719 -0.566285 -0.588826 -0.57747 -0.565814 -0.588542 -0.529114 -0.671105 -0.519284 -0.567897 -0.641388 -0.515863 -0.524188 -0.759038 -0.38612 -0.544126 -0.738852 -0.397524 -0.510376 -0.812323 -0.28222 -0.540791 -0.785275 -0.301477 -0.478729 -0.86644 -0.141779 -0.512774 -0.843708 -0.158805 -0.483222 -0.873359 0.0611618 -0.5055 -0.862394 -0.0273114 -0.491961 -0.87035 0.0215831 -0.490321 -0.871521 0.0060272 -0.486858 -0.871939 0.0518783 -0.483308 -0.872078 -0.0767612 -0.455051 -0.889687 -0.0372266 -0.48292 -0.874739 -0.0402468 -0.48292 -0.874739 0.0402469 -0.48292 -0.874739 0.0402468 -0.500453 -0.865478 -0.0222489 -0.485678 -0.873643 0.0294148 -0.490024 -0.871685 -0.00645436 -0.486148 -0.871712 -0.0614639 -0.478536 -0.877257 -0.037732 -0.483263 -0.872962 -0.0662874 -0.512316 -0.847134 0.141051 -0.520807 -0.843834 0.129248 -0.513354 -0.814115 0.271448 -0.50599 -0.811782 0.291521 -0.539592 -0.766009 0.349387 -0.532837 -0.75073 0.390499 -0.555594 -0.67248 0.488965 -0.535401 -0.659167 0.528058 -0.577726 -0.565158 0.588922 -0.578433 -0.565704 0.587703 -0.578523 -0.565475 0.587835 -0.579218 -0.565999 0.586644 -0.576983 -0.571653 0.583355 -0.57461 -0.623164 0.530557 -0.544784 -0.724995 0.421418 -0.542151 -0.729997 0.416144 -0.577995 -0.670008 0.465845 -0.543509 -0.741893 0.392673 -0.551715 0.672624 0.49314 -0.562813 0.604464 0.563795 -0.584653 0.567163 0.580092 -0.554666 0.677333 0.483286 -0.552304 0.679959 0.482303 -0.579084 0.565231 0.587517 -0.577994 0.565717 0.588121 -0.578312 0.564905 0.58859 -0.577214 0.5654 0.589192 -0.555254 0.61748 0.557146 -0.594977 0.658895 0.460281 -0.493104 0.744744 0.449671 -0.59343 0.779455 0.200725 -0.432568 0.833236 0.344387 -0.541884 0.837225 0.0735935 -0.466257 0.884131 0.0302715 -0.504943 0.861474 -0.0538027 -0.50471 0.862377 0.0396781 -0.504714 0.862374 0.0396776 -0.504468 0.862941 0.0290645 -0.544095 0.838859 -0.0166039 -0.449603 0.880736 -0.148862 -0.548561 0.811296 -0.202187 -0.482834 0.794393 -0.368524 -0.562969 0.734731 -0.378465 -0.522104 0.654913 -0.546349 -0.545015 0.639229 -0.542536 -0.577364 0.565013 -0.589416 -0.57816 0.565291 -0.588368 -0.578144 0.565333 -0.588344 -0.578949 0.565608 -0.587287 -0.57422 0.577484 -0.58033 -0.575269 0.602395 -0.553341 -0.559611 0.670457 -0.487159 -0.551463 0.686867 -0.473395 -0.552142 0.686054 -0.473781 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.422367 0.900095 0.106934 0.424932 0.904838 0.0264751 0.425215 0.904274 0.0384769 0.422901 0.883046 -0.20343 0.428226 0.89221 -0.143472 0.464432 0.789368 -0.4015 0.464761 0.782902 -0.413595 0.509017 0.652718 -0.561125 0.520142 0.57665 -0.630022 0.522619 0.57038 -0.633668 0.521079 0.571544 -0.633888 0.521658 0.570066 -0.634742 0.520077 0.571274 -0.634953 0.422475 0.904524 0.0578906 0.405002 0.913621 -0.0356311 0.438942 0.8948 -0.081629 0.423122 0.865913 -0.266763 0.46525 0.830026 -0.30757 0.451224 0.755682 -0.474701 0.501721 0.698987 -0.509601 0.497 0.625837 -0.601098 0.422245 0.905524 -0.0416632 0.422243 0.905525 -0.0416638 0.422243 0.905525 0.0416633 0.422245 0.905524 0.0416638 0.474068 0.672807 0.56797 0.475605 0.671337 0.568425 0.47416 0.754723 0.453393 0.431547 0.826157 0.362259 0.419309 0.820676 0.388164 0.452523 0.864722 0.217897 0.398851 0.909335 0.118438 0.438711 0.898413 0.0196536 0.422335 0.905213 -0.0471416 0.520525 0.570129 0.635616 0.52121 0.57121 0.634081 0.521512 0.570442 0.634525 0.522187 0.571482 0.633032 0.484457 0.656446 0.578256 0.529394 0.562111 0.635432 0.456706 0.791815 0.405522 0.366209 0.904263 0.219543 0.450716 0.810526 0.374035 0.427254 0.90066 0.0791597 0.425693 0.904479 -0.0265172 0.421616 0.903856 -0.0726943 0.419802 -0.907239 -0.0261497 0.416592 -0.909067 0.00700644 0.441295 -0.875291 0.197798 0.443494 -0.84652 0.294477 0.471452 -0.787083 0.397785 0.492271 -0.687276 0.534155 0.50644 -0.653031 0.563089 0.544079 -0.510811 0.66562 0.522624 -0.570378 0.633666 0.521075 -0.571549 0.633887 0.521656 -0.570066 0.634744 0.520077 -0.571272 0.634955 0.422405 -0.904942 -0.0515236 0.402502 -0.914717 0.0358548 0.438662 -0.894329 0.0880426 0.423132 -0.865905 0.266772 0.465248 -0.830029 0.307566 0.451227 -0.755677 0.474707 0.501721 -0.698987 0.509601 0.497003 -0.62583 0.601104 0.422252 -0.905521 0.0416631 0.422252 -0.90552 0.041663 0.487107 -0.646875 -0.586754 0.466251 -0.672727 -0.574499 0.422405 -0.904943 0.0514973 0.421495 -0.905604 0.0471565 0.426426 -0.900488 -0.0853375 0.408423 -0.9053 -0.116716 0.44856 -0.856036 -0.256896 0.423609 -0.828756 -0.365675 0.426112 -0.826441 -0.367999 0.48776 -0.745307 -0.454542 0.520524 -0.570128 -0.635617 0.521209 -0.571209 -0.634084 0.52151 -0.57044 -0.634528 0.522189 -0.571486 -0.633026 0.484522 -0.656326 -0.578339 0.529365 -0.562179 -0.635396 0.456721 -0.791818 -0.4055 0.471095 -0.765427 -0.438396 0.435817 -0.877657 -0.199457 0.429054 -0.886529 -0.173145 0.424659 -0.904968 0.0264109 0.421132 -0.905163 0.0576793 -0.699906 -0.473183 -0.535004 -0.699907 -0.473184 -0.535003 -0.699906 -0.644515 -0.307785 -0.699906 -0.644515 -0.307785 -0.704437 -0.704449 -0.086717 -0.683151 -0.729557 -0.0324176 -0.706021 -0.706034 0.0552367 -0.7071 -0.353557 -0.612378 -0.707101 -0.353557 -0.612378 -0.706727 -0.706739 0.0325152 -0.706726 -0.706739 0.0325176 -0.703418 -0.703432 -0.101915 -0.703419 -0.703431 -0.101915 -0.700661 -0.633648 -0.327971 -0.700661 -0.466947 -0.539476 -0.700661 -0.466948 -0.539476 -0.706184 -0.586139 -0.397172 -0.590026 -0.741852 -0.31863 -0.706727 -0.706738 -0.0325171 -0.706727 -0.706738 -0.0325171 -0.706727 -0.706738 0.0325171 -0.706727 -0.706738 0.0325171 -0.706727 -0.706738 -0.0325176 -0.706726 -0.706739 -0.0325153 -0.703418 -0.703432 0.101915 -0.703419 -0.703431 0.101914 -0.700661 -0.633648 0.32797 -0.70066 -0.633648 0.327971 -0.70066 -0.466948 0.539476 -0.700662 -0.466948 0.539474 -0.707102 -0.353556 0.612377 -0.7071 -0.353556 0.612378 -0.706021 -0.706033 -0.0552372 -0.66437 -0.741805 0.0913155 -0.699906 -0.713531 0.0317055 -0.699907 -0.644515 0.307785 -0.699906 -0.644516 0.307785 -0.699906 -0.473184 0.535003 -0.699906 -0.473184 0.535003 -0.701664 0.457991 0.545813 -0.701661 0.457988 0.545819 -0.701661 0.617043 0.356271 -0.701677 0.617046 0.356236 -0.701676 0.701673 0.123719 -0.701674 0.701674 0.123723 -0.707098 0.353559 0.61238 -0.707107 0.353552 0.612373 -0.694729 0.694764 0.186157 -0.69475 0.508589 0.508587 -0.694749 0.508589 0.508587 -0.704643 0.651968 0.280028 -0.372211 0.918556 0.133092 -0.706716 0.706749 0.0325176 -0.706715 0.70675 0.0325178 -0.706716 0.70675 0.0325098 -0.706716 0.706751 0.0325084 -0.707106 0.353555 -0.612372 -0.707098 0.353557 -0.612381 -0.706028 0.706024 0.0552687 -0.706026 0.706026 0.0552784 0 0.99695 0.0780428 -0.00166626 0.993131 0.116995 0 0.999231 0.0392061 -4.41348e-08 0.984809 0.173641 -0.00755343 0.995486 0.0946028 0.0109656 0.865961 0.499992 0.000783768 0.900718 0.434403 -0.00052625 0.642787 0.766045 0 0.638355 0.769742 0 -0.998137 0.0610121 -0.00545531 -0.998999 -0.0443902 0.00362815 -0.979518 -0.201322 -0.00471396 -0.902376 -0.430925 0.00235544 -0.857501 -0.514477 -0.00289073 -0.662501 -0.749056 0 -0.638437 -0.769674 0 -0.581121 0.813817 -0.0136396 -0.773489 0.633663 0.00916374 -0.662477 0.749026 -0.00475135 -0.902375 0.430925 0.00237949 -0.939739 0.341883 -0.00293917 -0.99901 0.0443906 0 -0.999925 0.0122494 0 0.500001 -0.866025 -1.48914e-07 0.500001 -0.866025 0 0.500002 -0.866024 0 0.500002 0.866024 -1.48914e-07 0.500001 0.866025 0 0.500001 0.866025 0 0.998475 0.0552104 0.000333483 0.998944 0.0459505 -0.00145861 0.988694 -0.149939 -0.00251216 0.989662 -0.143394 0.0016133 0.918831 -0.394648 -0.00860042 0.874753 -0.484493 0.0154594 0.707024 -0.707021 0 0.646881 -0.762591 0 0.998943 0.0459615 0 0.998943 0.0459615 0 0.597889 0.801579 0.0182432 0.70699 0.706988 0 0.998944 -0.0459505 -0.00474443 0.998221 0.0594308 0.00403749 0.989658 0.143394 -0.0042396 0.936104 0.351699 0.000945036 0.918832 0.394648 -0.000626554 0.832085 0.554648 0.0106924 0.740618 0.671841 0 -0.5 -0.866025 4.96379e-08 -0.5 -0.866025 0 -0.5 -0.866025 0 -0.5 0.866025 4.96379e-08 -0.5 0.866025 0 -0.5 0.866025 0 -0.998943 0.0459622 0 -0.998943 0.0459622 -1.26082e-08 -0.989667 0.143385 -0.00226257 -0.987232 0.15927 0.00273824 -0.888088 0.459666 -0.00181832 -0.875711 0.482833 0.00188399 -0.654451 0.756102 0 -0.646881 0.762591 0 -0.998943 -0.0459615 0 -0.998943 -0.0459615 0 -0.998943 0.0459615 0 -0.998943 0.0459615 0.705587 -0.7056 -0.0653835 0.705588 -0.705599 -0.0653835 0.705588 -0.681571 -0.193924 0.705587 -0.681572 -0.193924 0.705587 -0.634333 -0.31586 0.705588 -0.634333 -0.31586 0.705588 -0.565493 -0.42704 0.705588 -0.565493 -0.427041 0.705588 -0.477396 -0.523678 0.70559 -0.477395 -0.523677 0.705589 -0.373041 -0.602482 0.705586 -0.373043 -0.602484 0.705587 -0.255984 -0.660772 0.705586 -0.255985 -0.660773 0.705586 -0.13021 -0.696559 0.705587 -0.130209 -0.696558 0.705587 0 -0.708623 0.705587 0 -0.708623 0.705587 0.130209 -0.696558 0.705586 0.130209 -0.696559 0.705586 0.255985 -0.660773 0.705588 0.255984 -0.66077 0.705588 0.373041 -0.602482 0.705587 0.373042 -0.602484 0.705587 0.477396 -0.523679 0.705591 0.477394 -0.523676 0.705591 0.56549 -0.427038 0.705586 0.565494 -0.427041 0.705586 0.634335 -0.315861 0.705585 0.634335 -0.315862 0.705585 0.681574 -0.193925 0.70559 0.681569 -0.193923 0.70559 0.705597 -0.0653831 0.705585 0.705602 -0.0653839 0.705407 -0.705389 -0.0694749 0.705404 -0.705392 -0.0694753 0.705404 -0.678284 -0.205756 0.705415 -0.678274 -0.205752 0.705415 -0.625101 -0.334123 0.705407 -0.625108 -0.334128 0.705407 -0.547912 -0.449659 0.705404 -0.547914 -0.449661 0.705406 -0.44966 -0.547913 0.705409 -0.449658 -0.54791 0.70541 -0.334126 -0.625106 0.705412 -0.334125 -0.625104 0.705412 -0.205753 -0.678277 0.705408 -0.205754 -0.678281 0.705408 -0.0694747 -0.705388 0.705407 -0.0694748 -0.705389 0.705407 0.0694748 -0.705389 0.705408 0.0694746 -0.705388 0.705408 0.205754 -0.678281 0.705412 0.205753 -0.678277 0.705412 0.334125 -0.625104 0.705412 0.334125 -0.625104 0.705412 0.449656 -0.547908 0.705411 0.449657 -0.547908 0.705411 0.547908 -0.449657 0.705411 0.547909 -0.449657 0.705411 0.625105 -0.334125 0.705409 0.625107 -0.334126 0.705409 0.67828 -0.205754 0.70541 0.678278 -0.205754 0.705411 0.705386 -0.0694745 0.705409 0.705387 -0.0694746 0.705385 -0.705411 -0.0694771 0.705395 -0.705401 -0.0694756 0.705395 -0.678293 -0.205758 0.705389 -0.678299 -0.20576 0.705389 -0.625124 -0.334136 0.705385 -0.625127 -0.334137 0.705386 -0.547927 -0.449673 0.705398 -0.547919 -0.449665 0.705396 -0.449667 -0.54792 0.705396 -0.449667 -0.547921 0.705394 -0.334133 -0.625119 0.705392 -0.334134 -0.625121 0.705394 -0.205758 -0.678294 0.705396 -0.205758 -0.678293 0.705396 -0.0694761 -0.705401 0.705392 -0.0694763 -0.705405 0.705392 0.0694764 -0.705405 0.705396 0.0694759 -0.705401 0.705396 0.205758 -0.678293 0.705398 0.205757 -0.678291 0.705398 0.334131 -0.625116 0.705391 0.334135 -0.625122 0.705391 0.44967 -0.547924 0.705392 0.449669 -0.547924 0.705393 0.547923 -0.449669 0.705391 0.547924 -0.449669 0.705391 0.625122 -0.334135 0.705392 0.625121 -0.334134 0.705392 0.678296 -0.205759 0.705392 0.678296 -0.205759 0.705392 0.705404 -0.0694762 0.705392 0.705405 -0.0694763 -0.705392 0.705405 -0.0694763 -0.705392 0.705404 -0.0694762 -0.705392 0.678296 -0.205759 -0.705392 0.678296 -0.205759 -0.705392 0.625121 -0.334134 -0.705391 0.625122 -0.334135 -0.705391 0.547924 -0.449669 -0.705393 0.547923 -0.449669 -0.705392 0.449669 -0.547923 -0.705391 0.449669 -0.547924 -0.705391 0.334134 -0.625122 -0.705398 0.334131 -0.625116 -0.705398 0.205757 -0.678291 -0.705396 0.205758 -0.678293 -0.705396 0.069476 -0.705401 -0.705392 0.0694762 -0.705405 -0.705392 -0.0694765 -0.705405 -0.705396 -0.0694759 -0.705401 -0.705396 -0.205758 -0.678293 -0.705394 -0.205758 -0.678294 -0.705392 -0.334134 -0.625121 -0.705394 -0.334133 -0.625119 -0.705396 -0.449667 -0.547921 -0.705396 -0.449667 -0.54792 -0.705398 -0.547919 -0.449666 -0.705386 -0.547928 -0.449672 -0.705385 -0.625127 -0.334137 -0.705389 -0.625123 -0.334136 -0.705389 -0.678299 -0.205759 -0.705395 -0.678293 -0.205758 -0.705395 -0.705401 -0.0694761 -0.705385 -0.705411 -0.0694766 0.705751 -0.705764 -0.0617464 0.70575 -0.705765 -0.0617464 0.70575 -0.684321 -0.183363 0.705749 -0.684322 -0.183363 0.705749 -0.642084 -0.299409 0.705749 -0.642085 -0.299409 0.705749 -0.580338 -0.406357 0.705752 -0.580336 -0.406356 0.705751 -0.500957 -0.500957 0.705755 -0.500954 -0.500954 0.705756 -0.406353 -0.580333 0.705757 -0.406353 -0.580332 0.705757 -0.299406 -0.642078 0.705752 -0.299408 -0.642082 0.705751 -0.183363 -0.68432 0.705749 -0.183363 -0.684321 0.705749 -0.0617467 -0.705766 0.705751 -0.0617464 -0.705764 0.705751 0.0617465 -0.705764 0.705748 0.0617467 -0.705767 0.705747 0.183364 -0.684323 0.705749 0.183363 -0.684322 0.705749 0.299409 -0.642084 0.705751 0.299408 -0.642083 0.705749 0.406357 -0.580338 0.705756 0.406353 -0.580333 0.705756 0.500954 -0.500953 0.705747 0.50096 -0.50096 0.705746 0.58034 -0.406359 0.70575 0.580338 -0.406357 0.705749 0.642084 -0.299409 0.705767 0.642069 -0.299401 0.705768 0.684303 -0.183358 0.705729 0.684341 -0.183369 0.705729 0.705786 -0.0617487 0.705757 0.705758 -0.0617451 0.705758 -0.705758 -0.0617456 0.705755 -0.70576 -0.0617459 0.705755 -0.684316 -0.183361 0.705743 -0.684328 -0.183365 0.705743 -0.64209 -0.299412 0.705749 -0.642084 -0.299409 0.705749 -0.580338 -0.406357 0.705746 -0.58034 -0.406359 0.705746 -0.50096 -0.50096 0.705742 -0.500963 -0.500963 0.705742 -0.406361 -0.580344 0.705757 -0.406353 -0.580332 0.705756 -0.299406 -0.642078 0.705749 -0.299409 -0.642084 0.705749 -0.183363 -0.684322 0.705754 -0.183362 -0.684317 0.705755 -0.0617461 -0.70576 0.705751 -0.0617463 -0.705764 0.705751 0.0617464 -0.705764 0.705755 0.061746 -0.70576 0.705754 0.183362 -0.684317 0.705749 0.183364 -0.684322 0.705749 0.299409 -0.642084 0.705757 0.299406 -0.642078 0.705757 0.406353 -0.580332 0.70575 0.406357 -0.580337 0.705751 0.500957 -0.500957 0.705751 0.500957 -0.500957 0.705752 0.580336 -0.406356 0.705752 0.580336 -0.406355 0.705752 0.642082 -0.299408 0.705752 0.642082 -0.299408 0.705752 0.684318 -0.183363 0.705752 0.684319 -0.183363 0.705752 0.705763 -0.0617463 0.705751 0.705764 -0.0617464 0.705594 -0.705594 -0.0653828 0.705581 -0.705606 -0.0653844 0.705582 -0.681577 -0.193925 0.705589 -0.68157 -0.193923 0.705589 -0.634332 -0.31586 0.705591 -0.63433 -0.315859 0.705591 -0.56549 -0.427039 0.705593 -0.565489 -0.427038 0.705592 -0.477393 -0.523675 0.705579 -0.477402 -0.523685 0.705581 -0.373045 -0.602489 0.705582 -0.373045 -0.602488 0.705582 -0.255986 -0.660776 0.70559 -0.255983 -0.660769 0.70559 -0.130209 -0.696555 0.705588 -0.130209 -0.696557 0.705587 0 -0.708623 0.705587 0 -0.708623 0.705585 0.13021 -0.696559 0.70559 0.130209 -0.696555 0.70559 0.255983 -0.660769 0.705582 0.255986 -0.660776 0.705582 0.373045 -0.602488 0.705588 0.373042 -0.602483 0.705588 0.477396 -0.523678 0.705588 0.477396 -0.523678 0.705587 0.565493 -0.427041 0.705588 0.565493 -0.42704 0.705588 0.634333 -0.31586 0.705586 0.634334 -0.315861 0.705586 0.681573 -0.193924 0.705585 0.681574 -0.193925 0.705585 0.705603 -0.0653837 0.705587 0.7056 -0.0653836 0.705418 -0.705379 -0.0694737 0.705419 -0.705378 -0.0694737 0.705418 -0.678271 -0.205751 0.705419 -0.67827 -0.205751 0.705419 -0.625098 -0.334122 0.705417 -0.625099 -0.334122 0.705418 -0.547903 -0.449653 0.705423 -0.547899 -0.449649 0.705423 -0.449649 -0.547899 0.705418 -0.449653 -0.547903 0.705418 -0.334122 -0.625099 0.705415 -0.334123 -0.625101 0.705416 -0.205752 -0.678273 0.705414 -0.205753 -0.678275 0.705415 -0.069474 -0.705382 0.705418 -0.0694736 -0.705379 0.705418 0.0694737 -0.705379 0.705415 0.0694739 -0.705381 0.705416 0.205752 -0.678273 0.705418 0.205751 -0.678271 0.705419 0.334122 -0.625098 0.705421 0.334121 -0.625096 0.705422 0.44965 -0.5479 0.705418 0.449652 -0.547903 0.705418 0.547903 -0.449653 0.705423 0.547899 -0.449649 0.705424 0.625094 -0.334119 0.705416 0.6251 -0.334123 0.705416 0.678273 -0.205752 0.705409 0.67828 -0.205754 0.705409 0.705388 -0.0694749 0.705425 0.705372 -0.0694727 0.421828 -0.554791 -0.717125 0.422233 -0.326695 -0.84557 0.415756 -0.326624 -0.848801 0.425441 -0.382291 -0.820277 0.42254 -0.381753 -0.822025 0.421927 -0.449963 -0.78709 0.409794 -0.451217 -0.792762 0.423785 -0.501495 -0.754261 0.422613 -0.500366 -0.755667 0.42183 -0.55479 -0.717124 0.451875 0.156109 -0.878316 0.494355 0.370336 -0.786425 0.40123 0.190296 -0.895992 0.551327 0.578742 -0.600913 0.460568 0.461533 -0.758198 0.610541 0.703802 -0.363185 0.529855 0.655223 -0.538458 0.435644 0.0109682 -0.900052 0.425238 -0.133045 -0.895249 0.419428 -0.167618 -0.892179 0.417337 -0.711947 -0.564766 0.418481 -0.705583 -0.571863 0.444962 -0.839988 -0.310531 0.45137 -0.844433 -0.288442 0.483927 -0.868514 -0.107227 0.51234 -0.858105 0.0341145 0.5023 -0.864689 0.00269763 0.5523 -0.797008 0.244424 0.563958 -0.779148 0.273642 0.609443 -0.655004 0.44671 0.587417 0.69892 -0.407986 0.587079 0.699096 -0.40817 0.587417 -0.702786 0.40129 0.587062 -0.703046 0.401353 0.509151 -0.77769 -0.368732 0.529671 -0.822024 -0.209104 0.549761 -0.812724 -0.192985 0.571963 -0.819127 -0.0434753 0.44309 -0.755975 -0.481843 0.4924 -0.749094 -0.443171 0.448901 -0.629073 -0.634629 0.445294 -0.628275 -0.637952 0.441952 -0.532631 -0.721792 0.46784 0.205261 -0.859648 0.438096 -0.520831 -0.732671 0.433941 -0.445462 -0.783108 0.450788 -0.406194 -0.794856 0.432119 -0.365607 -0.824381 0.411966 -0.272104 -0.869622 0.421844 -0.289811 -0.859103 0.42162 -0.164678 -0.891694 0.426459 -0.173693 -0.887673 0.421748 -0.0234962 -0.906408 0.422551 -0.0250718 -0.905992 0.439973 0.0775826 -0.894653 0.438138 0.0991248 -0.893426 0.448981 0.149864 -0.880884 0.450535 0.256823 -0.85502 0.481552 0.352777 -0.802282 0.493578 0.373904 -0.785224 0.492639 0.38298 -0.78143 0.490114 0.481191 -0.726804 0.48424 0.508606 -0.711921 0.550306 0.557846 -0.621266 0.530414 0.667752 -0.522272 0.554092 0.674035 -0.488528 0.554092 0.339467 -0.760095 0.530413 0.317153 -0.786178 0.550305 0.172476 -0.816956 0.484239 0.0845066 -0.870845 0.490116 0.053306 -0.870026 0.492639 -0.0590492 -0.868228 0.493578 -0.068799 -0.866976 0.440765 -0.179814 -0.879428 0.467841 -0.252065 -0.847105 0.44898 -0.310667 -0.837797 0.43814 -0.360863 -0.823293 0.439976 -0.380133 -0.813585 0.422552 -0.47471 -0.772075 0.421751 -0.473555 -0.773222 0.426461 -0.594259 -0.6819 0.421618 -0.588457 -0.689897 0.421842 -0.680534 -0.599101 0.411967 -0.670462 -0.617061 0.445433 -0.771957 -0.453511 0.403704 -0.772172 -0.490686 0.441952 -0.822168 -0.358773 0.445294 -0.863078 -0.238346 0.4489 -0.862108 -0.23507 0.4924 -0.87032 -0.0092495 0.443091 -0.895615 -0.0392993 0.509151 -0.857865 0.0695147 0.529671 -0.816446 0.229923 0.54976 -0.800332 0.239232 0.571963 -0.731121 0.371914 0.587417 -0.809275 -0.0038657 0.587061 -0.809533 -0.00394057 0.587417 0.401289 -0.702786 0.58708 0.40135 -0.703033 0.417339 -0.334183 -0.845074 0.418483 -0.325121 -0.848038 0.444964 -0.572188 -0.688918 0.451374 -0.587086 -0.672006 0.483931 -0.698555 -0.527098 0.512335 -0.760192 -0.399527 0.50231 -0.7502 -0.429982 0.552302 -0.81244 -0.186828 0.56395 -0.811583 -0.152622 0.609445 -0.790602 0.0593689 0.451876 -0.30396 -0.838699 0.494356 -0.0724888 -0.866232 0.401253 -0.283147 -0.871105 0.551327 0.200743 -0.809778 0.460571 0.0205998 -0.887384 0.610544 0.42792 -0.666424 0.529844 0.298192 -0.793944 0.435642 -0.440541 -0.784946 0.425239 -0.562833 -0.708795 0.419425 -0.591262 -0.688834 0.421999 -0.128734 -0.89741 0.423623 -0.128869 -0.896625 0.422394 -0.0679632 -0.903861 0.422606 -0.0681968 -0.903744 0.421827 0 -0.906676 0.422004 0.128977 -0.897373 0.423621 0.128627 -0.896661 0.422402 0.068204 -0.903839 0.422607 0.0679558 -0.903762 0.421827 0 -0.906676 0.422615 -0.858574 -0.290255 0.424522 -0.858899 -0.286486 0.394029 -0.848878 -0.352346 0.421845 -0.838801 -0.344181 0.42255 -0.805542 -0.415395 0.429554 -0.804061 -0.411059 0.403888 -0.782972 -0.473106 0.422168 -0.77752 -0.466088 0.422405 -0.734422 -0.531224 0.432836 -0.731992 -0.526157 0.411785 -0.700708 -0.582615 0.422403 -0.698682 -0.577424 0.612009 0.787997 0.0671241 0.562633 0.812615 -0.151993 0.583182 0.807566 -0.0879539 0.548325 0.805615 -0.224331 0.522347 0.77708 -0.351141 0.507026 0.746954 -0.430098 0.491559 0.724846 -0.482668 0.458293 0.613206 -0.643386 0.45641 0.584684 -0.670697 0.442017 0.504745 -0.741521 0.417835 0.334354 -0.844761 0.417438 0.332768 -0.845583 0.41734 -0.898943 -0.133152 0.41848 -0.896985 -0.142452 0.444961 -0.882716 0.151069 0.451375 -0.875513 0.172443 0.483926 -0.805771 0.341392 0.512339 -0.726087 0.458592 0.502304 -0.747488 0.434686 0.552302 -0.568014 0.610183 0.563958 -0.537942 0.626554 0.609443 -0.343896 0.714363 0.587417 0.809275 -0.00386707 0.587081 0.809519 -0.0039376 0.587416 -0.407986 0.69892 0.587062 -0.408179 0.699105 0.529674 -0.607342 -0.5921 0.54976 -0.607347 -0.573493 0.571962 -0.687647 -0.447215 0.357336 -0.162049 -0.91981 0.45599 -0.254461 -0.852832 0.4924 -0.427148 -0.758345 0.458593 -0.418102 -0.784145 0.51165 -0.500652 -0.698256 0.450534 0.649929 -0.612056 0.46784 0.607583 -0.641848 0.466923 -0.216403 -0.85741 0.438096 -0.0847267 -0.894926 0.431208 0.0428221 -0.901236 0.442035 0.031878 -0.896431 0.411966 0.199164 -0.889167 0.421844 0.178569 -0.88891 0.42162 0.303234 -0.854568 0.426462 0.29341 -0.855594 0.421752 0.432854 -0.79672 0.422553 0.431284 -0.797147 0.439975 0.514516 -0.736 0.43814 0.532558 -0.724165 0.448983 0.570228 -0.687935 0.538125 0.834032 -0.121702 0.481549 0.706655 -0.51841 0.497151 0.719272 -0.485272 0.505524 0.722957 -0.470934 0.484238 0.796428 -0.362238 0.521412 0.796438 -0.306295 0.545555 0.825113 -0.146827 0.55409 -0.0860637 -0.827996 0.530414 -0.118425 -0.839426 0.550306 -0.259108 -0.793742 0.484239 -0.362238 -0.796427 0.490115 -0.388843 -0.78012 0.492639 -0.485249 -0.722385 0.493578 -0.493073 -0.716421 0.440767 -0.595438 -0.671698 0.467841 -0.641846 -0.607584 0.448978 -0.687946 -0.570218 0.438139 -0.724164 -0.532561 0.439974 -0.736001 -0.514515 0.422552 -0.797148 -0.431283 0.42175 -0.796721 -0.432855 0.42646 -0.855593 -0.293415 0.42162 -0.854567 -0.303235 0.421844 -0.88891 -0.178567 0.411968 -0.889167 -0.199159 0.445434 -0.895289 -0.00677363 0.403705 -0.914064 -0.0388608 0.441951 -0.891406 0.100371 0.445293 -0.866621 0.225126 0.4489 -0.864143 0.227478 0.4924 -0.758344 0.42715 0.44309 -0.795275 0.413774 0.509151 -0.708175 0.489136 0.52967 -0.592103 0.607341 0.54976 -0.573493 0.607347 0.571963 -0.447212 0.687648 0.587416 -0.698919 -0.407987 0.587064 -0.699103 -0.408179 0.587417 -0.00386616 -0.809275 0.587081 -0.0039368 -0.809519 0.417348 0.133213 -0.89893 0.41848 0.142452 -0.896985 0.444962 -0.151074 -0.882715 0.451381 -0.172465 -0.875506 0.484833 -0.347561 -0.802582 0.514405 -0.463629 -0.721413 0.502289 -0.434655 -0.747516 0.552297 -0.610179 -0.568023 0.563979 -0.626586 -0.537883 0.609443 -0.714361 -0.343901 0.451877 -0.682588 -0.574353 0.494358 -0.49589 -0.713936 0.40125 -0.680772 -0.61282 0.551327 -0.23104 -0.80166 0.460552 -0.425885 -0.77879 0.610541 0.0373721 -0.791102 0.529852 -0.138714 -0.836669 0.435644 -0.773989 -0.459516 0.425243 -0.841818 -0.332432 0.419425 -0.856466 -0.300914 0.422253 0.325548 -0.846003 0.415964 0.327738 -0.84827 0.425267 0.381216 -0.820867 0.422551 0.382862 -0.821503 0.421969 0.448463 -0.787923 0.410202 0.452626 -0.791747 0.423427 0.500154 -0.755351 0.422616 0.501795 -0.754717 0.42183 0.554791 -0.717124 0.421828 0.554791 -0.717125 0.529866 0.793915 0.298228 0.61056 0.666388 0.427953 0.541552 0.815771 0.203075 0.505762 0.862671 0.00163148 0.51179 0.858797 0.0232115 0.426697 0.858068 -0.285742 0.472736 0.865582 -0.165194 0.390378 0.722941 -0.570053 0.411992 0.753136 -0.512882 0.41734 -0.845084 0.334157 0.418481 -0.848038 0.325125 0.444961 -0.68892 0.572187 0.451374 -0.672001 0.587091 0.484832 -0.521274 0.70229 0.514401 -0.392964 0.762215 0.502303 -0.430003 0.750193 0.552301 -0.186825 0.812441 0.563958 -0.152595 0.811583 0.609443 0.059363 0.790604 0.587419 0.702785 0.401288 0.58708 0.703033 0.401349 0.587416 -0.00386593 0.809276 0.587062 -0.00394046 0.809533 0.512132 -0.0874329 -0.854445 0.529671 -0.229923 -0.816446 0.54976 -0.239232 -0.800332 0.571963 -0.371911 -0.731123 0.46162 0.0281508 -0.886631 0.492399 0.00925026 -0.870321 0.45735 0.20025 -0.866447 0.429776 0.236164 -0.871504 0.449924 0.325101 -0.831792 0.438096 0.374085 -0.817394 0.431207 0.487704 -0.759082 0.442034 0.475824 -0.760393 0.411966 0.617061 -0.670462 0.421843 0.599099 -0.680536 0.421618 0.689894 -0.588459 0.42646 0.681899 -0.594261 0.42358 0.755087 -0.500423 0.413515 0.776242 -0.475871 0.429786 0.789006 -0.439038 0.465911 0.846267 -0.258377 0.439974 0.813583 -0.38014 0.438139 0.823291 -0.36087 0.44898 0.837798 -0.310664 0.538127 0.783143 0.311618 0.45491 0.861699 -0.224795 0.475423 0.872438 -0.113247 0.483339 0.869933 -0.0979809 0.485118 0.872626 -0.0564292 0.497848 0.866094 0.0450327 0.487487 0.869183 0.0829262 0.529026 0.833189 0.161022 0.542096 0.785769 0.297822 0.554082 -0.488547 -0.674029 0.531249 -0.521123 -0.667986 0.550312 -0.621269 -0.557837 0.484735 -0.71018 -0.510564 0.490948 -0.726691 -0.48051 0.492516 -0.780266 -0.385503 0.493629 -0.785212 -0.373861 0.440822 -0.850613 -0.28659 0.468293 -0.859458 -0.205022 0.449652 -0.880136 -0.152228 0.43802 -0.893335 -0.100449 0.439974 -0.894653 -0.0775846 0.422786 -0.905916 0.023855 0.422686 -0.905968 0.023655 0.425832 -0.888201 0.172527 0.42162 -0.891693 0.164682 0.421874 -0.859464 0.288693 0.412768 -0.86928 0.271982 0.444043 -0.780362 0.440296 0.405215 -0.81055 0.42286 0.442027 -0.721769 0.532599 0.444212 -0.639806 0.627155 0.449883 -0.634539 0.628462 0.491042 -0.445243 0.748757 0.444559 -0.482055 0.754977 0.509441 -0.368814 0.777461 0.528415 -0.211339 0.822261 0.550513 -0.19337 0.812123 0.571484 -0.0446552 0.819397 0.587417 -0.401289 -0.702786 0.587062 -0.401353 -0.703047 0.587417 -0.407985 -0.69892 0.58708 -0.408168 -0.699096 0.417336 0.564767 -0.711948 0.41848 0.571868 -0.705579 0.444962 0.310531 -0.839988 0.451364 0.288464 -0.844429 0.484832 0.100288 -0.868839 0.514399 -0.0407922 -0.85658 0.502307 -0.00271979 -0.864685 0.552301 -0.244423 -0.797008 0.563959 -0.273642 -0.779147 0.609444 -0.446713 -0.655 0.451877 -0.878315 -0.156109 0.494357 -0.786421 -0.370342 0.40125 -0.895975 -0.190333 0.551327 -0.600917 -0.578738 0.460554 -0.75822 -0.461511 0.610541 -0.363184 -0.703801 0.529851 -0.538467 -0.655219 0.435643 -0.900053 -0.0109551 0.425242 -0.895252 0.133016 0.419425 -0.892178 0.167632 0.422435 0.69695 -0.579491 0.412721 0.702111 -0.580259 0.431993 0.730751 -0.528568 0.422437 0.735987 -0.529027 0.422226 0.775853 -0.468804 0.405221 0.784125 -0.470047 0.428343 0.803122 -0.414146 0.422576 0.806986 -0.412558 0.421939 0.837357 -0.347564 0.395842 0.849579 -0.348603 0.422874 0.85846 -0.290214 0.422617 0.859751 -0.286746 0.422438 -0.696949 0.579489 0.412723 -0.702111 0.580258 0.431995 -0.73075 0.528568 0.422439 -0.735986 0.529027 0.422228 -0.775852 0.468804 0.405223 -0.784124 0.470047 0.428345 -0.803121 0.414146 0.422572 -0.806989 0.412556 0.421935 -0.837358 0.347565 0.395842 -0.849579 0.348604 0.422874 -0.858459 0.290216 0.422619 -0.859741 0.286774 0.529854 0.538458 0.655223 0.610559 0.363137 0.703811 0.460494 0.758293 0.461451 0.55136 0.600844 0.578782 0.501562 0.755586 0.421338 0.441591 0.879716 0.176342 0.482399 0.824339 0.296237 0.442468 0.888705 0.120105 0.4216 0.896981 -0.13296 0.418373 0.895935 -0.149216 0.417339 -0.564778 0.711937 0.41848 -0.571858 0.705587 0.444961 -0.310533 0.839988 0.45138 -0.288405 0.84444 0.484834 -0.100288 0.868837 0.514402 0.0407924 0.856579 0.502294 0.00267481 0.864693 0.5523 0.244422 0.797009 0.563961 0.273648 0.779144 0.609445 0.446715 0.654999 0.587416 0.407986 0.69892 0.587079 0.408169 0.699096 0.587417 0.401289 0.702786 0.587061 0.401354 0.703046 0.49391 0.443267 -0.748042 0.52967 0.209104 -0.822025 0.54976 0.192985 -0.812724 0.571963 0.0434728 -0.819127 0.432878 0.901069 -0.0263029 0.405871 0.913751 0.0181071 0.424434 0.902381 -0.0745903 0.426456 0.887675 -0.173692 0.421618 0.891695 -0.164677 0.421842 0.859103 -0.289812 0.411965 0.869623 -0.272106 0.442032 0.792273 -0.420608 0.431206 0.801905 -0.413533 0.438095 0.732663 -0.520843 0.45181 0.691266 -0.563931 0.428843 0.640411 -0.637156 0.459348 0.599601 -0.655346 0.492675 0.441318 -0.750006 0.438546 0.893237 0.0990184 0.455298 0.877981 0.147828 0.473419 0.861157 0.185157 0.440454 0.851631 0.28412 0.478306 0.807002 0.346367 0.484119 0.78423 0.388088 0.498625 0.745625 0.442059 0.48436 0.711896 0.508527 0.511217 0.676377 0.530256 0.563065 0.522503 0.640272 0.521211 0.555685 0.64773 0.554084 -0.760107 -0.339454 0.531249 -0.785299 -0.317932 0.550312 -0.816953 -0.172466 0.484735 -0.870316 -0.0870718 0.505514 -0.861571 0.0463753 0.498335 -0.865019 0.0583438 0.473809 -0.873558 0.111366 0.463425 -0.865195 0.191507 0.448317 -0.865769 0.222388 0.454677 -0.840839 0.293697 0.44965 -0.838332 0.308242 0.438021 -0.823876 0.359674 0.439974 -0.813587 0.38013 0.422785 -0.772619 0.473616 0.422686 -0.772763 0.473471 0.425832 -0.682942 0.593513 0.421622 -0.689884 0.588468 0.421876 -0.599971 0.679747 0.41277 -0.616829 0.670181 0.427715 -0.552302 0.715558 0.411756 -0.459389 0.787031 0.41667 -0.453755 0.787713 0.465485 -0.243359 0.850941 0.386826 -0.301128 0.871601 0.461281 -0.185534 0.867639 0.49162 -0.00660569 0.870785 0.494405 -0.0125633 0.869141 0.528414 0.228105 0.817769 0.550513 0.238598 0.800004 0.571484 0.371024 0.731948 0.587417 0.00386616 -0.809276 0.587062 0.0039407 -0.809532 0.587417 -0.702786 -0.40129 0.58708 -0.703032 -0.40135 0.417346 0.845108 -0.334087 0.418477 0.84804 -0.325123 0.444959 0.688911 -0.5722 0.451372 0.67199 -0.587105 0.484825 0.521295 -0.702279 0.514397 0.392976 -0.762211 0.502304 0.43 -0.750193 0.552302 0.186823 -0.812441 0.563961 0.152584 -0.811582 0.609443 -0.0593583 -0.790605 0.451878 -0.8387 0.303957 0.494357 -0.866231 0.0724891 0.401258 -0.871105 0.28314 0.551328 -0.809776 -0.200747 0.460547 -0.887397 -0.0205582 0.610541 -0.666429 -0.427916 0.529857 -0.793927 -0.298213 0.435643 -0.784945 0.440541 0.425242 -0.708806 0.562817 0.419424 -0.688832 0.591265 0.422255 -0.325547 0.846002 0.415964 -0.327738 0.84827 0.425267 -0.381216 0.820867 0.42255 -0.382862 0.821504 0.421968 -0.448463 0.787924 0.410202 -0.452626 0.791747 0.423428 -0.500156 0.75535 0.422616 -0.501797 0.754715 0.42183 -0.554791 0.717124 0.421828 -0.554791 0.717125 0.451878 0.682584 0.574357 0.494357 0.495886 0.713938 0.40126 0.680751 0.612836 0.551327 0.231039 0.801661 0.460565 0.42586 0.778796 0.610541 -0.0373738 0.791102 0.529851 0.138714 0.83667 0.435635 0.774024 0.459465 0.425228 0.841852 0.332366 0.419425 0.85646 0.30093 0.417349 -0.13322 0.898928 0.418481 -0.142451 0.896985 0.444961 0.151072 0.882715 0.451381 0.172465 0.875506 0.484833 0.347561 0.802582 0.514403 0.463621 0.721419 0.50229 0.434654 0.747516 0.552298 0.610178 0.568022 0.563969 0.62657 0.537911 0.609446 0.714367 0.343883 0.587416 0.00386593 0.809276 0.58708 0.00393658 0.809519 0.587417 0.69892 0.407986 0.587061 0.699106 0.40818 0.494406 0.758978 -0.423694 0.528414 0.594158 -0.606428 0.550517 0.573523 -0.606633 0.571488 0.448362 -0.687294 0.425626 0.800349 0.422237 0.423193 0.856607 0.295182 0.408904 0.852572 0.325451 0.422493 0.868127 0.260489 0.421868 0.888667 0.179715 0.437212 0.887448 0.145884 0.412536 0.910456 0.0297143 0.434929 0.900409 -0.0100534 0.438065 0.895052 -0.0835537 0.454045 0.877367 -0.155146 0.429407 0.873593 -0.22901 0.462683 0.841441 -0.279108 0.491624 0.757424 -0.429667 0.420493 0.797266 0.433073 0.445098 0.721504 0.530396 0.456224 0.704309 0.543883 0.452246 0.685497 0.570585 0.447541 0.603819 0.659629 0.45171 0.610917 0.650183 0.481233 0.517321 0.707668 0.477906 0.52415 0.704892 0.4846 0.482863 0.729387 0.497486 0.43378 0.751227 0.484914 0.359781 0.79713 0.500306 0.338847 0.796791 0.576051 0.136561 0.805926 0.515471 0.169042 0.840068 0.554085 -0.827998 0.0860763 0.531249 -0.839055 0.117312 0.550312 -0.793735 0.259117 0.484735 -0.797251 0.359753 0.505514 -0.722955 0.470948 0.498338 -0.719959 0.48303 0.440822 -0.673501 0.593357 0.4441 -0.666253 0.599068 0.455688 -0.568794 0.684706 0.452724 -0.5825 0.675082 0.43802 -0.533663 0.723424 0.439975 -0.514515 0.736 0.422786 -0.432296 0.796475 0.422685 -0.432497 0.796419 0.425832 -0.294688 0.855468 0.421619 -0.303229 0.85457 0.421873 -0.179721 0.888664 0.412769 -0.199098 0.888809 0.427715 -0.120524 0.895843 0.411757 -0.00432817 0.911284 0.416674 0.000895295 0.909056 0.465487 0.214714 0.858615 0.386824 0.175012 0.905394 0.461282 0.273142 0.844164 0.491621 0.429671 0.757424 0.494405 0.423692 0.758979 0.528414 0.606429 0.594157 0.550515 0.606634 0.573523 0.571486 0.687291 0.448369 0.587416 0.407986 -0.698921 0.58706 0.408179 -0.699107 0.587417 -0.809275 0.0038657 0.58708 -0.80952 0.00393668 0.417343 0.898932 0.133213 0.419275 0.895522 0.149158 0.443252 0.87843 -0.178573 0.442189 0.879552 -0.175662 0.492285 0.786318 -0.373309 0.506901 0.74612 -0.431691 0.518064 0.685327 -0.511797 0.582952 0.461139 -0.668967 0.550007 0.538304 -0.63853 0.626794 0.28554 -0.72498 0.451878 -0.574353 0.682587 0.494358 -0.713934 0.495892 0.401257 -0.612825 0.680763 0.551327 -0.801659 0.231045 0.460551 -0.778787 0.425892 0.610544 -0.7911 -0.0373786 0.529842 -0.836672 0.138735 0.435641 -0.459499 0.774001 0.425243 -0.332456 0.841809 0.419425 -0.300931 0.85646 0.422614 0.858575 0.290253 0.424528 0.858901 0.28647 0.394027 0.848879 0.352346 0.421847 0.8388 0.34418 0.422553 0.805542 0.415394 0.429548 0.804062 0.411063 0.403883 0.782974 0.473107 0.422165 0.777521 0.466088 0.422402 0.734423 0.531224 0.432834 0.731993 0.526157 0.411783 0.700709 0.582617 0.4224 0.698683 0.577426 0.421998 0.128734 0.89741 0.423623 0.128869 0.896625 0.422394 0.0679632 0.903861 0.422606 0.0681968 0.903744 0.421827 0 0.906676 0.422004 -0.128977 0.897373 0.423621 -0.128627 0.896661 0.422402 -0.068204 0.903839 0.422607 -0.0679558 0.903762 0.421827 0 0.906676 0.451878 0.303952 0.838701 0.494355 0.07249 0.866232 0.401243 0.283168 0.871102 0.551327 -0.200743 0.809778 0.460571 -0.0205998 0.887384 0.610544 -0.427918 0.666425 0.529841 -0.298186 0.793948 0.435642 0.440552 0.78494 0.425242 0.562808 0.708813 0.419422 0.591266 0.688832 0.417338 0.334183 0.845074 0.418476 0.325167 0.848024 0.440738 0.498549 0.746458 0.456387 0.584443 0.670923 0.459183 0.632539 0.623734 0.504373 0.751651 0.425005 0.502681 0.749913 0.430048 0.545129 0.804775 0.234886 0.583173 0.807568 0.0879903 0.562622 0.812615 0.152031 0.612024 0.787976 -0.0672261 0.587417 -0.401289 0.702786 0.58708 -0.40135 0.703033 0.587417 0.809275 0.00386707 0.587063 0.809532 0.00394149 0.571486 0.731947 -0.371022 0.550515 0.800003 -0.238596 0.528416 0.817768 -0.228104 0.496843 0.86784 0.000496133 0.490141 0.871628 0.00511502 0.470385 0.871213 0.140449 0.475526 0.870883 0.124249 0.440987 0.86481 0.240072 0.45964 0.844639 0.274439 0.438048 0.816931 0.37515 0.436069 0.793374 0.424738 0.412035 0.773849 0.481025 0.441117 0.713023 0.54499 0.417818 0.681251 0.601103 0.427124 0.608626 0.668685 0.418814 0.595446 0.685594 0.428388 0.520355 0.738725 0.414105 0.474727 0.776628 0.433694 0.435819 0.788652 0.43944 0.359668 0.823123 0.451611 0.32829 0.829623 0.449802 0.308233 0.838254 0.45076 0.200435 0.869852 0.441649 0.177284 0.879498 0.478876 0.0986143 0.872326 0.484561 0.0534656 0.873122 0.496465 0.0011413 0.868056 0.485238 -0.0868245 0.870061 0.501515 -0.104895 0.858767 0.571957 -0.28784 0.768124 0.517422 -0.276844 0.809711 0.536078 -0.57652 0.61664 0.536673 -0.663553 0.521229 0.540888 -0.663647 0.516732 0.514442 -0.539512 0.666541 0.492085 -0.513701 0.702825 0.485634 -0.509955 0.710005 0.495748 -0.431598 0.753629 0.484555 -0.390256 0.782883 0.479199 -0.351213 0.804374 0.480968 -0.354364 0.801933 0.468449 -0.310347 0.827188 0.450471 -0.258153 0.854654 0.453367 -0.24955 0.855677 0.448249 -0.152682 0.880773 0.449083 -0.135088 0.883219 0.438018 -0.100452 0.893336 0.438082 -0.0343606 0.898278 0.414024 0.022799 0.909981 0.431004 0.0794455 0.898846 0.416976 0.172967 0.892308 0.429339 0.20651 0.879217 0.416465 0.289669 0.861771 0.428563 0.323534 0.843599 0.424558 0.366627 0.82785 0.436132 0.465991 0.769832 0.401478 0.443032 0.801584 0.446014 0.528968 0.721987 0.436029 0.631592 0.641069 0.447908 0.635424 0.628979 0.496716 0.744797 0.44559 0.530399 0.836401 0.138244 0.619598 0.781771 0.0702313 0.465302 0.845926 0.260582 0.530677 0.82061 0.21209 0.500755 0.764269 0.406371 0.398418 0.757305 0.517449 0.587419 0.702785 -0.401288 0.587061 0.703047 -0.401353 0.587416 -0.698919 0.407987 0.587083 -0.699094 0.408169 0.417337 0.711947 0.564766 0.418478 0.705601 0.571843 0.445576 0.851909 0.275162 0.441263 0.850048 0.287586 0.494411 0.867262 0.0584255 0.507347 0.861742 -0.00061852 0.521607 0.845071 -0.117394 0.587405 0.723605 -0.362424 0.547252 0.786637 -0.285861 0.629033 0.603258 -0.490303 0.451876 -0.156112 0.878315 0.494357 -0.370339 0.786423 0.401271 -0.190369 0.895958 0.551327 -0.578733 0.600922 0.460533 -0.46148 0.758252 0.610542 -0.703801 0.363185 0.529873 -0.655233 0.538428 0.435644 -0.0109676 0.900052 0.425238 0.133045 0.895249 0.419428 0.167622 0.892179 0.421828 0.554791 0.717124 0.422231 0.326696 0.845571 0.415756 0.326624 0.848801 0.42544 0.38229 0.820277 0.422541 0.381753 0.822024 0.421928 0.449963 0.787089 0.409794 0.451217 0.792762 0.423784 0.501493 0.754263 0.422613 0.500364 0.755668 0.42183 0.554791 0.717124 0.671485 0.498238 0.548513 0.698166 0.481987 0.529389 0.704178 0.478656 0.524425 0.678256 0.5196 0.5196 0.751437 0.469704 0.46338 0.65041 0.542711 0.531443 0.478733 0.627924 0.613617 0.539123 0.813529 0.217985 0.687893 0.70108 0.187854 0.678323 0.709751 0.190084 0.673028 0.714372 0.191589 0.635363 0.745927 0.199767 0.385908 0.890759 0.240049 0.539124 0.813528 -0.217985 0.678248 0.709794 -0.190189 0.386817 0.890393 -0.239943 0.635459 0.745851 -0.199747 0.673276 0.714153 -0.191533 0.687596 0.701493 -0.187399 0.479173 0.627753 -0.61345 0.650512 0.542647 -0.531383 0.683878 0.520742 -0.511018 0.74594 0.470942 -0.470942 0.704188 0.478654 -0.524413 0.698221 0.481952 -0.529349 0.671732 0.498087 -0.548347 0.553656 0.234514 -0.799042 0.667221 0.209019 -0.714932 0.690897 0.202124 -0.694123 0.781954 0.161331 -0.602096 0.698248 0.162031 -0.697278 0.686363 0.163792 -0.708575 0.629478 0.174089 -0.757265 0.616817 -0.176349 -0.767097 0.682912 -0.164419 -0.711757 0.697659 -0.162027 -0.697867 0.781954 -0.161331 -0.602096 0.690895 -0.202124 -0.694125 0.667115 -0.209048 -0.715022 0.55355 -0.234534 -0.79911 0.669888 -0.499209 -0.549582 0.697631 -0.482311 -0.5298 0.704122 -0.478662 -0.524496 0.678256 -0.5196 -0.5196 0.751441 -0.469701 -0.463377 0.65041 -0.542711 -0.531443 0.478813 -0.627893 -0.613587 0.678257 -0.709787 -0.190187 0.678255 -0.709788 -0.190187 0.635218 -0.746017 -0.199894 0.371937 -0.897427 -0.237248 0.633577 -0.747111 -0.201012 0.396883 -0.886594 -0.237562 0.678255 -0.709788 0.190187 0.678257 -0.709787 0.190187 0.635221 -0.746014 0.199894 0.371946 -0.895816 0.243249 0.63357 -0.747528 0.199475 0.396899 -0.886587 0.23756 0.479297 -0.627704 0.613402 0.650503 -0.542653 0.531389 0.683878 -0.520742 0.511017 0.745944 -0.47094 0.47094 0.704121 -0.478662 0.524495 0.6976 -0.482328 0.529825 0.669875 -0.499217 0.549591 0.553907 -0.234467 0.798882 0.667167 -0.209034 0.714978 0.690895 -0.202124 0.694125 0.781954 -0.161331 0.602096 0.697659 -0.162027 0.697867 0.682861 -0.164427 0.711804 0.616693 -0.176371 0.767192 0.0532485 0.998338 0.0220432 -0.00989704 0.956257 0.29236 0 0.999075 0.0429934 0 0.740365 0.672205 0.0053391 0.779722 0.626103 -0.00215785 0.865185 0.501448 0.00810184 0.971793 0.235696 0.00486295 0.0368492 0.999309 -0.00850018 -0.173141 0.98486 0.00422875 -0.274587 0.961553 -0.0053044 -0.549365 0.835566 0 -0.578115 0.815955 0.00647266 0.0598606 0.998186 -0.0164911 0.326325 0.945114 -1.54293e-06 0.238457 0.971153 2.65833e-07 0.480963 0.876741 -0.00190048 0.511538 0.859258 0.00302852 0.648458 0.761244 0 0.675274 0.737567 0 0.987119 0.159987 0 0.987119 0.159987 0.00486613 0.531613 0.846974 -0.00850015 0.342483 0.939486 0.00422858 0.242975 0.970023 -0.00530477 -0.0579764 0.998304 0 -0.092682 0.995696 0.00647138 0.550925 0.834529 -0.0164944 0.755166 0.655326 -4.78503e-06 0.69209 0.721811 -3.44005e-06 0.854922 0.518756 -0.00189978 0.872618 0.488399 0.00302967 0.942196 0.335047 0 0.953586 0.301121 0 0.953523 -0.301319 0.0054716 0.932092 -0.362181 -0.018725 0.431954 -0.901701 -0.00145964 0.342497 -0.939518 0.000530866 0.577842 -0.816148 0.0041444 0.531614 -0.846977 -0.0134106 0.759742 -0.650086 0.00670947 0.69479 -0.719181 -0.0019003 0.872519 -0.488577 0.00600168 0.188818 -0.981994 -0.0114552 -0.120758 -0.992616 0 -0.0579772 -0.998318 0 0.989129 0.147048 -0.00911721 0.975241 0.220957 -3.61672e-06 0.933874 0.357602 -4.47187e-06 0.896981 0.442068 0.00150914 0.860442 0.509546 -0.00838731 0.780052 0.625659 0.0053417 0.695397 0.718606 -0.00749779 0.461733 0.886987 0 0.41755 0.908654 0 0.675132 -0.737697 0.00547265 0.626131 -0.779698 -0.0187219 -0.0767832 -0.996872 -0.00145932 -0.173147 -0.984895 0.000531521 0.0923219 -0.995729 0.00414661 0.0368493 -0.999312 -0.0134135 0.332931 -0.942856 0.0067119 0.24211 -0.970226 -0.0018985 0.511352 -0.859369 0.00600213 -0.327471 -0.944842 -0.0114559 -0.600895 -0.799246 0 -0.549373 -0.835577 0 0.998501 0.0547403 -0.00705598 0.98076 0.19509 0.00350845 0.961519 0.274714 -0.00417629 0.831461 0.555568 0 0.815933 0.578147 0 0.215819 -0.976434 0.00547238 0.152384 -0.988306 -0.0187191 -0.564948 -0.824914 -0.00145996 -0.642397 -0.766371 0.000530648 -0.417905 -0.908491 0.00415828 -0.467908 -0.883768 -0.0134122 -0.183109 -0.983001 0.00671165 -0.275441 -0.961295 -0.0018982 0.0131655 -0.999912 0.00600284 -0.756015 -0.654526 -0.0114544 -0.920008 -0.391733 0 -0.893557 -0.44895 0 0.991446 0.130517 0 0.991446 0.130517 0 -0.301319 -0.953523 0.00547151 -0.36218 -0.932092 -0.0194963 -0.898137 -0.439284 -1.30357e-06 -0.939518 -0.342499 1.83068e-06 -0.811439 -0.584438 0.00413937 -0.846948 -0.53166 -0.0134141 -0.650075 -0.759752 0.00671203 -0.719191 -0.69478 -0.00189862 -0.488546 -0.872536 0.00600221 -0.981993 -0.188824 -0.011457 -0.992614 0.120775 0 -0.998318 0.0579829 0.0048587 0.467799 -0.883821 -0.00850023 0.642375 -0.766344 0.00422956 0.718581 -0.69543 -0.00530367 0.893548 -0.448937 0 0.908639 -0.417583 0.0064732 0.447249 -0.894386 -0.0164914 0.189938 -0.981658 8.19088e-07 0.279069 -0.960271 2.94923e-06 0.0218748 -0.999761 -0.00190062 -0.0133978 -0.999908 0.00302725 -0.18094 -0.983489 0 -0.215988 -0.976396 0 -0.73771 -0.675118 0.00547169 -0.779703 -0.626126 -0.019495 -0.99745 0.0686596 -2.90999e-06 -0.984895 0.173152 3.51096e-07 -0.994942 -0.100446 0.00413886 -0.999308 -0.0369685 -0.0134138 -0.942856 -0.332931 0.0067124 -0.970227 -0.242106 -0.00189822 -0.85936 -0.511367 0.00600204 -0.944842 0.327472 -0.0114556 -0.799249 0.600891 0 -0.83558 0.54937 0.00486231 -0.0368397 -0.999309 -0.00850008 0.173142 -0.98486 0.00422875 0.274587 -0.961553 -0.00530448 0.549367 -0.835564 0 0.578118 -0.815953 0.00647264 -0.0598596 -0.998186 -0.0164924 -0.326333 -0.945111 -1.35626e-06 -0.238457 -0.971153 6.40954e-07 -0.480951 -0.876747 -0.00190087 -0.511538 -0.859258 0.0030279 -0.648455 -0.761247 0 -0.675265 -0.737575 0 -0.976435 -0.215813 0.00547198 -0.988306 -0.152385 -0.019496 -0.829491 0.55818 -2.49172e-06 -0.766368 0.642402 6.60228e-07 -0.91187 0.410478 0.0041403 -0.883904 0.46765 -0.013413 -0.983002 0.183104 0.00671187 -0.961295 0.275441 -0.00189829 -0.999912 -0.0131679 0.00600184 -0.654518 0.756023 -0.0114555 -0.391726 0.920011 0 -0.448949 0.893557 0.00487029 -0.531656 -0.846946 -0.00849973 -0.34248 -0.939487 0.00422866 -0.242975 -0.970023 -0.0053043 0.0579776 -0.998304 0 0.0926806 -0.995696 0.00647229 -0.550929 -0.834527 -0.0164932 -0.75517 -0.655321 -1.67628e-06 -0.692087 -0.721814 3.94507e-07 -0.854887 -0.518814 -0.001901 -0.872631 -0.488377 0.00302801 -0.942203 -0.335029 0 -0.953586 -0.301122 0 -0.953523 0.301319 0.00547181 -0.932091 0.362183 -0.0187231 -0.43194 0.901708 -0.00145903 -0.34249 0.93952 0.000531784 -0.577822 0.816163 0.00414036 -0.531658 0.846949 -0.013413 -0.759753 0.650073 0.00671166 -0.694786 0.719185 -0.00189854 -0.872532 0.488553 0.00600152 -0.18882 0.981993 -0.0114562 0.120766 0.992615 0 0.0579784 0.998318 0.00487429 -0.883929 -0.467595 -0.00849971 -0.766338 -0.642381 0.00422829 -0.695435 -0.718577 -0.00530478 -0.448943 -0.893545 0 -0.417582 -0.908639 0.00647202 -0.894382 -0.447257 -0.0164935 -0.981658 -0.189938 -1.42864e-06 -0.960271 -0.279068 6.09429e-07 -0.999761 -0.02186 -0.00190082 -0.999909 0.0133723 0.003028 -0.983487 0.180956 0 -0.976391 0.216012 0 -0.675118 0.73771 0.00547239 -0.62612 0.779707 -0.0187218 0.076784 0.996872 -0.00145918 0.173148 0.984895 0.000531442 -0.0923219 0.995729 0.00414718 -0.0368398 0.999313 -0.0134134 -0.332933 0.942855 0.00671227 -0.24211 0.970226 -0.00189785 -0.511356 0.859367 0.00600223 0.327469 0.944843 -0.0114561 0.600898 0.799243 0 0.549375 0.835576 0.0048705 -0.999305 0.0369683 -0.00850046 -0.98486 -0.173146 0.00422858 -0.961551 -0.274592 -0.00530428 -0.835568 -0.549362 0 -0.815958 -0.578111 0.00647187 -0.998186 0.0598599 -0.0164924 -0.945112 0.32633 -1.16958e-06 -0.971154 0.238453 1.01617e-06 -0.876747 0.480951 -0.00190048 -0.859258 0.511538 0.00302852 -0.761244 0.648458 0 -0.737567 0.675274 0 -0.215777 0.976443 0.0054689 -0.152384 0.988306 -0.0187211 0.564938 0.824921 -0.00145996 0.642397 0.766371 0.000530648 0.417905 0.908491 0.00415045 0.467801 0.883824 -0.0134126 0.183107 0.983001 0.00671215 0.275443 0.961294 -0.00189933 -0.0132027 0.999911 0.00600156 0.756015 0.654526 -0.0114573 0.920017 0.39171 0 0.89356 0.448943 0.00486995 -0.846945 0.531659 -0.00849948 -0.939484 0.342487 0.00422884 -0.970021 0.242982 -0.00530495 -0.998304 -0.057982 0 -0.995695 -0.0926895 0.00647191 -0.834525 0.550932 -0.0164929 -0.655322 0.75517 -1.90485e-07 -0.72182 0.692081 2.09771e-06 -0.518795 0.854898 -0.00189857 -0.488369 0.872635 0.00302976 -0.335048 0.942196 0 -0.301121 0.953586 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258814 -0.965927 0 0.258814 -0.965927 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965925 -0.258821 0 0.965925 -0.258821 0 -0.965928 -0.258812 0 -0.965928 -0.258812 0 -0.707103 -0.70711 0 -0.707103 -0.70711 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707103 -0.70711 0 0.707103 -0.70711 0 0.965928 -0.258812 0 0.965928 -0.258812 0 -0.965928 -0.258813 0 -0.965928 -0.258813 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.965928 -0.258813 0 0.965928 -0.258813 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.965928 -0.258811 0 -0.965928 -0.258811 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.974927 -0.222523 0 -0.974927 -0.222523 0 -0.781834 -0.623487 0 -0.781834 -0.623487 0 -0.433882 -0.90097 0 -0.433882 -0.90097 0 0 -1 0 0 -1 0 0.433882 -0.90097 0 0.433882 -0.90097 0 0.781834 -0.623487 0 0.781834 -0.623487 0 0.974927 -0.222523 0 0.974927 -0.222523 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 0.258816 -0.965927 0 0.258816 -0.965927 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965925 -0.258821 0 0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.965925 -0.258821 0 0.965925 -0.258821 0 0.965925 0.258821 0 0.965925 0.258821 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.977735 -0.209844 0.0171498 -0.999154 -0.0373861 0.000511865 -0.999934 0.0114859 -0.000466732 -0.941598 0.336738 0.016022 -0.916445 0.39984 5.60288e-05 -0.842324 0.538971 -7.28252e-05 -0.751401 0.659846 0.0170242 -0.652193 0.757862 0.0173297 -0.653353 0.756855 -3.31155e-05 -0.0947511 0.995501 0.00905254 -0.207131 0.978271 0.0172983 -0.258779 0.965782 0.00160064 -0.35644 0.934317 -0.00130742 -0.536857 0.843672 6.5223e-05 0.0757551 0.997126 0.0179051 0.185882 0.982409 -0.000135382 0.296162 0.955138 8.99399e-05 0.466627 0.884454 0.0170378 0.593735 0.80448 -0.00980239 0.68249 0.730829 0.0123813 0.884048 0.467233 0 0.901296 0.433204 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.707108 -0.707106 0 0.707108 -0.707106 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.57517 0.818034 0.0191639 -0.522402 0.852484 3.83388e-05 -0.368623 0.929579 -4.79957e-05 -0.232448 0.972609 0.0198223 -0.0784443 0.996721 0.021067 -0.0834583 0.996289 1.75784e-05 0.532667 0.846325 0.0129184 0.409876 0.91205 0.0188795 0.382614 0.923715 -0.000122006 0.247321 0.968934 0.000120569 0.0634041 0.997988 -2.61902e-05 0.662467 0.749091 0.0184119 0.760277 0.649338 -0.000103381 0.819462 0.573133 4.99917e-05 0.920171 0.391517 0.0162571 0.972241 0.233416 0 0.986058 0.166401 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.0829862 0.996551 0.0162066 -0.031341 0.999377 2.82941e-05 0.146527 0.989207 -4.84884e-05 0.282879 0.959156 0.0199421 0.416379 0.908972 0.0169186 0.428527 0.90337 -2.6293e-05 0.92346 0.383694 4.18657e-05 0.851574 0.524235 0.0184581 0.777216 0.628963 -0.000196787 0.708773 0.705436 0.000122781 0.546438 0.837499 0.00724809 0.955235 0.29576 0.0168691 0.974667 0.223026 0 0.991327 0.131417 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.409936 0.912114 0.01646 0.461687 0.88689 3.78768e-05 0.597362 0.801972 -6.49289e-05 0.714669 0.699463 0.0187814 0.793211 0.608657 0.0092552 0.822748 0.568331 -0.00946367 0.932534 0.360957 0.0167155 0.976159 0.216412 0 0.99534 0.0964234 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 0.707108 0.707106 0 0.707108 0.707106 0 0.785871 0.61839 0.0170097 0.83135 0.555489 0.000725658 0.88912 0.457673 -0.000945226 0.956218 0.292653 0.015538 0.980666 0.195072 0 0.995501 0.0947491 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 0.965926 0.258818 0 0.965926 0.258818 0 0.991445 0.130526 0 0.991445 0.130526 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.965926 0.258818 0 -0.965926 0.258818 0 0.965925 -0.258821 0 0.965925 -0.258821 0 0.951668 -0.307129 0.0207817 0.865839 -0.499891 0.0136001 0.857105 -0.514963 2.54492e-05 0.734501 -0.678607 -7.74324e-05 0.616943 -0.787008 0.0260758 0.499831 -0.865731 -0.00215312 0.382659 -0.923887 0.000902517 0.190904 -0.981608 0.016839 0 -0.999858 0.027892 0.038773 -0.998859 0.016574 -0.513071 -0.858186 -6.77383e-05 -0.309988 -0.95074 0.000125707 -0.158397 -0.987376 0.0769723 -0.66597 -0.741997 -0.000218038 -0.500001 -0.866025 0.00012376 -0.804013 -0.594612 0.025875 -0.865736 -0.499831 -0.000128099 -0.930581 -0.366086 8.52083e-05 -0.982823 -0.18455 0.0244926 -0.9997 0 0 -0.997148 0.0754724 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.707107 0.707107 0 -0.707107 0.707107 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.670603 -0.741816 0.0207817 0.499893 -0.865838 0.0136004 0.484793 -0.874523 2.44607e-05 0.296778 -0.954946 -7.85666e-05 0.140789 -0.99004 0.0260755 0 -0.99966 -0.00215395 -0.130553 -0.991439 0.000901497 -0.325469 -0.945552 0.0168386 -0.49993 -0.865902 0.0278909 -0.465854 -0.884422 0.0165744 -0.873426 -0.486675 -6.7109e-05 -0.74383 -0.668369 0.00012634 -0.630857 -0.775899 0.0769725 -0.947745 -0.309603 -0.00021814 -0.866026 -0.5 0.000124135 -0.993601 -0.112944 0.0258755 -0.999665 0 -0.000128127 -0.988949 0.148253 8.52553e-05 -0.943425 0.331587 0.0244927 -0.865766 0.49985 0 -0.825819 0.563935 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.258818 0.965926 0 -0.258819 0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.209848 -0.977734 0.0207813 0 -0.999784 0.0136008 -0.0174174 -0.999756 2.53035e-05 -0.22045 -0.975398 -7.76438e-05 -0.373098 -0.927792 0.0260755 -0.49983 -0.865731 -0.00215337 -0.60878 -0.793336 0.000902202 -0.754645 -0.656133 0.0168387 -0.865903 -0.499929 0.0278917 -0.845651 -0.533008 0.0165741 -0.999747 0.0152396 -6.73587e-05 -0.97836 -0.206909 0.000126069 -0.934289 -0.356516 0.0769704 -0.975574 0.205743 -0.000217986 -1 0 0.000124007 -0.916956 0.398988 0.0258754 -0.865735 0.499833 -0.000128139 -0.782329 0.622865 8.5281e-05 -0.651235 0.758876 0.0244924 -0.499851 0.865765 0 -0.433214 0.901291 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.307146 -0.951663 0.0207835 -0.499893 -0.865838 0.0135977 -0.514974 -0.857098 2.54671e-05 -0.67862 -0.734489 -7.75257e-05 -0.787013 -0.616936 0.0260757 -0.865731 -0.49983 -0.0021546 -0.923892 -0.382646 0.00090293 -0.981609 -0.190898 0.0168388 -0.999858 0 0.0278901 -0.998859 -0.0387674 0.0165774 -0.858177 0.513086 -6.72114e-05 -0.950737 0.309998 0.000126194 -0.987375 0.1584 0.0769743 -0.741994 0.665973 -0.000218091 -0.866026 0.5 0.000124041 -0.594606 0.804017 0.025875 -0.499833 0.865735 -0.000128275 -0.366076 0.930585 8.51268e-05 -0.184538 0.982825 0.0244942 0 0.9997 0 0.0754803 0.997147 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.707106 0.707107 0 0.707106 0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.741825 -0.670594 0.0171495 -0.8466 -0.531953 0.00051222 -0.871711 -0.49002 -0.000466252 -0.983817 -0.179176 0.0160226 -0.993585 -0.11195 5.61508e-05 -0.99896 0.0456043 -7.27391e-05 -0.980655 0.195743 0.0170241 -0.943747 0.33023 0.0173307 -0.94425 0.328773 -3.31548e-05 -0.579811 0.814751 0.00905219 -0.668517 0.743642 0.017298 -0.707001 0.707001 0.0016013 -0.775841 0.630927 -0.00130705 -0.886768 0.462212 6.51559e-05 -0.43296 0.901413 0.0179056 -0.330225 0.943732 -0.000135692 -0.22108 0.975256 8.97021e-05 -0.0381162 0.999273 0.0170374 0.111947 0.993568 -0.00980339 0.225639 0.974162 0.0123803 0.531992 0.846659 0 0.563942 0.825815 0.629836 0.174024 0.756983 0.686381 0.163787 0.708559 0.698236 0.162031 0.697289 0.781954 0.161331 0.602096 0.690897 0.202124 0.694123 0.667108 0.20905 0.715028 0.55355 0.234534 0.79911 0 0.314339 0.949311 0.00489604 0.362235 0.932074 -0.00258203 0.522777 0.852465 -1.3817e-07 0.564791 0.825234 -2.74192e-06 0.739327 0.673346 -0.00345893 0.724297 0.689479 0.00164489 0.873115 0.487511 0.003217 0.883274 0.468846 -0.00719135 0.974693 0.223434 -0.0110214 0.9692 0.246028 0 0.99773 0.0673447 0.00485187 -0.467906 0.883765 -0.00849914 -0.642375 0.766344 0.00422884 -0.71857 0.695441 -0.00530492 -0.893544 0.448944 0 -0.908639 0.417583 0.00647438 -0.447254 0.894384 -0.0164908 -0.189941 0.981657 3.84778e-07 -0.279067 0.960272 2.91511e-06 -0.0218735 0.999761 -0.00190065 0.013398 0.999908 0.00302683 0.180945 0.983489 0 0.215988 0.976396 0 -0.965928 -0.258813 0 -0.965928 -0.258813 0 -0.707102 -0.707111 0 -0.707102 -0.707111 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965925 -0.258821 0 0.965925 -0.258821 0 0.965926 -0.258818 0 0.965926 -0.258818 0 -0.965926 0.258819 0 -0.965926 0.258819 -0.000516969 0.219337 0.975649 0 -0.936668 0.350218 0.0259634 -0.876432 0.480826 0.0174232 -0.860939 0.50841 0.00595219 -0.812038 0.583575 0.0140981 -0.51479 0.857201 0.0243239 -0.570189 0.821153 0.0196148 -0.555464 0.831309 -4.8234e-05 -0.685389 0.728177 3.08272e-05 -0.769714 0.638389 0.000503246 0.0351988 0.99938 0.0211313 -0.125564 0.99186 0.0170877 -0.108852 0.993911 -7.7543e-05 -0.275258 0.96137 0.000103447 -0.43071 0.90249 0.0206991 0.751677 0.659207 0.00409254 0.678381 0.734699 -0.010015 0.362422 0.93196 0.0608835 0.531456 0.844895 0.0221591 0.386163 0.922164 0 0.971343 0.237683 0.065061 0.993864 0.0894523 0.0155053 0.968623 0.248051 -0.00126204 0.905724 0.423866 0.00292659 0.810102 0.586282 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.705594 -0.705594 -0.0653828 0.705581 -0.705606 -0.0653844 0.705582 -0.681577 -0.193925 0.705589 -0.68157 -0.193923 0.705589 -0.634332 -0.31586 0.705591 -0.63433 -0.315859 0.705591 -0.56549 -0.427039 0.705593 -0.565489 -0.427038 0.705592 -0.477393 -0.523675 0.705579 -0.477402 -0.523685 0.705581 -0.373045 -0.602489 0.705582 -0.373045 -0.602488 0.705582 -0.255986 -0.660776 0.70559 -0.255983 -0.660769 0.70559 -0.130209 -0.696555 0.705588 -0.130209 -0.696557 0.705587 0 -0.708623 0.705587 0 -0.708623 0.705585 0.13021 -0.696559 0.70559 0.130209 -0.696555 0.70559 0.255983 -0.660769 0.705582 0.255986 -0.660776 0.705582 0.373045 -0.602488 0.705588 0.373042 -0.602483 0.705588 0.477396 -0.523678 0.705588 0.477396 -0.523678 0.705587 0.565493 -0.427041 0.705588 0.565493 -0.42704 0.705588 0.634333 -0.31586 0.705586 0.634334 -0.315861 0.705586 0.681573 -0.193924 0.705585 0.681574 -0.193925 0.705585 0.705603 -0.0653837 0.705587 0.7056 -0.0653836 -0.705587 0.7056 -0.0653835 -0.705585 0.705603 -0.0653838 -0.705585 0.681574 -0.193925 -0.705586 0.681573 -0.193924 -0.705586 0.634334 -0.315861 -0.705588 0.634333 -0.31586 -0.705588 0.565493 -0.42704 -0.705587 0.565493 -0.427041 -0.705588 0.477396 -0.523678 -0.705588 0.477396 -0.523678 -0.705588 0.373042 -0.602483 -0.705582 0.373044 -0.602488 -0.705582 0.255986 -0.660776 -0.70559 0.255983 -0.660769 -0.70559 0.130209 -0.696555 -0.705585 0.13021 -0.696559 -0.705587 0 -0.708623 -0.705587 0 -0.708623 -0.705588 -0.130209 -0.696557 -0.70559 -0.130209 -0.696555 -0.70559 -0.255983 -0.660769 -0.705582 -0.255986 -0.660776 -0.705582 -0.373044 -0.602488 -0.705581 -0.373045 -0.602489 -0.705579 -0.477402 -0.523685 -0.705592 -0.477393 -0.523675 -0.705593 -0.565489 -0.427038 -0.705591 -0.56549 -0.427039 -0.705591 -0.63433 -0.315859 -0.705589 -0.634331 -0.315859 -0.705589 -0.68157 -0.193923 -0.705582 -0.681577 -0.193925 -0.705581 -0.705606 -0.0653839 -0.705594 -0.705594 -0.0653832 0.79302 0.608616 -0.0265728 0.896828 -0.441959 -0.0192967 0.608398 -0.792877 -0.0346182 0.194836 -0.979902 -0.0427833 0.442008 -0.896157 -0.0391276 0.258589 -0.965 -0.0436572 0.258573 -0.957728 -0.126086 0.258548 -0.957734 -0.126088 0.258548 -0.9431 -0.20908 0.258542 -0.943102 -0.209081 0.258543 -0.92129 -0.290482 0.258607 -0.921275 -0.290475 0.258606 -0.892452 -0.369665 0.258567 -0.892461 -0.369671 0.258567 -0.856846 -0.446046 0.258581 -0.856843 -0.446044 0.25858 -0.814707 -0.519026 0.258583 -0.814707 -0.519026 0.258584 -0.766371 -0.588056 0.258556 -0.766376 -0.588061 0.258557 -0.712206 -0.652618 0.258589 -0.712201 -0.652612 0.258588 -0.652612 -0.7122 0.258589 -0.652612 -0.7122 0.258588 -0.588056 -0.76637 0.258598 -0.588054 -0.766368 0.258595 -0.519025 -0.814704 0.258555 -0.519029 -0.814713 0.258556 -0.446047 -0.85685 0.258592 -0.446043 -0.85684 0.258592 -0.369668 -0.892455 0.258564 -0.36967 -0.892462 0.258564 -0.290479 -0.921285 0.258582 -0.290478 -0.92128 0.258584 -0.209078 -0.943091 0.258572 -0.209079 -0.943094 0.258571 -0.126088 -0.957728 0.258578 -0.126088 -0.957726 0.258575 -0.0421359 -0.965072 0.258572 -0.0421358 -0.965073 0.258572 0.0421358 -0.965073 0.258573 0.0421358 -0.965072 0.258572 0.126088 -0.957728 0.258571 0.126088 -0.957728 0.258572 0.209079 -0.943094 0.258588 0.209078 -0.94309 0.258589 0.290477 -0.921279 0.258564 0.29048 -0.921285 0.258564 0.36967 -0.892462 0.258592 0.369667 -0.892455 0.258592 0.446043 -0.856841 0.258556 0.446048 -0.856849 0.258555 0.51903 -0.814713 0.258571 0.519027 -0.81471 0.25857 0.588059 -0.766373 0.258574 0.588058 -0.766373 0.258574 0.652615 -0.712204 0.258573 0.652615 -0.712204 0.258573 0.712204 -0.652615 0.258574 0.712204 -0.652615 0.258574 0.766373 -0.588058 0.258584 0.76637 -0.588057 0.258583 0.814707 -0.519026 0.258571 0.81471 -0.519027 0.258571 0.856846 -0.446046 0.258567 0.856847 -0.446046 0.258567 0.892461 -0.369669 0.258575 0.89246 -0.369669 0.258575 0.921282 -0.290479 0.258575 0.921282 -0.290479 0.258575 0.943093 -0.209079 0.25857 0.943095 -0.209079 0.25857 0.957728 -0.126087 0.258573 0.957727 -0.126087 0.258573 0.965072 -0.042136 0.258572 0.965073 -0.042136 0.608458 0.792831 -0.0346158 0.706815 0.706634 -0.0328877 0.706772 0.701389 -0.0923396 0.706774 0.701387 -0.0923394 0.706774 0.690671 -0.153118 0.706775 0.69067 -0.153118 0.706774 0.674697 -0.212731 0.706772 0.674699 -0.212732 0.706772 0.653591 -0.270726 0.706779 0.653584 -0.270723 0.706779 0.627502 -0.326657 0.706776 0.627505 -0.326658 0.706775 0.596647 -0.380106 0.706774 0.596649 -0.380107 0.706774 0.56125 -0.430662 0.706772 0.561251 -0.430663 0.706772 0.52158 -0.47794 0.706767 0.521584 -0.477944 0.706767 0.477944 -0.521584 0.706772 0.47794 -0.52158 0.706772 0.430663 -0.561251 0.706778 0.430659 -0.561246 0.706779 0.380105 -0.596645 0.70677 0.380109 -0.596651 0.70677 0.326661 -0.62751 0.706766 0.326663 -0.627514 0.706766 0.270729 -0.653596 0.706775 0.270725 -0.653588 0.706776 0.21273 -0.674695 0.706775 0.212731 -0.674697 0.706775 0.153118 -0.69067 0.706767 0.15312 -0.690677 0.706767 0.0923405 -0.701394 0.706774 0.0923394 -0.701388 0.706773 0.030858 -0.706768 0.70677 0.0308583 -0.70677 0.70677 -0.0308582 -0.70677 0.706771 -0.0308582 -0.706769 0.70677 -0.09234 -0.701391 0.706767 -0.0923403 -0.701394 0.706767 -0.15312 -0.690677 0.706772 -0.153119 -0.690672 0.706771 -0.212731 -0.6747 0.706779 -0.212729 -0.674692 0.70678 -0.270724 -0.653583 0.70677 -0.270727 -0.653592 0.706772 -0.32666 -0.627509 0.706782 -0.326656 -0.6275 0.706783 -0.380102 -0.59664 0.706772 -0.380108 -0.59665 0.706771 -0.430663 -0.561252 0.706765 -0.430667 -0.561257 0.706764 -0.477946 -0.521586 0.706758 -0.47795 -0.52159 0.706759 -0.52159 -0.47795 0.706772 -0.52158 -0.477941 0.706772 -0.561251 -0.430662 0.706759 -0.561261 -0.430671 0.706758 -0.596661 -0.380116 0.70676 -0.59666 -0.380114 0.70676 -0.627519 -0.326666 0.706769 -0.627511 -0.326661 0.706768 -0.653594 -0.270727 0.706789 -0.653576 -0.270719 0.706789 -0.674683 -0.212727 0.706775 -0.674696 -0.212732 0.706775 -0.69067 -0.153118 0.706768 -0.690676 -0.15312 0.706768 -0.701393 -0.0923394 0.706772 -0.701389 -0.0923386 0.706815 -0.706634 -0.0328892 0.793051 -0.608576 -0.0265715 0.980736 -0.195154 -0.00852094 0.965886 -0.258651 -0.0128196 0.96587 -0.25681 -0.0338098 0.965874 -0.256795 -0.0338074 0.965874 -0.252872 -0.0560597 0.965869 -0.252893 -0.0560651 0.965869 -0.247044 -0.077893 0.965869 -0.247042 -0.0778925 0.965869 -0.239314 -0.0991269 0.965872 -0.239303 -0.0991221 0.965872 -0.229753 -0.119602 0.965873 -0.229752 -0.119601 0.965872 -0.218454 -0.13917 0.965871 -0.218458 -0.139173 0.965871 -0.205497 -0.157683 0.965872 -0.205495 -0.157682 0.965872 -0.19097 -0.174992 0.965871 -0.190973 -0.174994 0.965871 -0.174994 -0.190973 0.96587 -0.174995 -0.190974 0.96587 -0.157685 -0.205499 0.965871 -0.157684 -0.205498 0.965871 -0.139174 -0.218459 0.96587 -0.139175 -0.218461 0.96587 -0.119605 -0.229759 0.96587 -0.119605 -0.229759 0.96587 -0.099125 -0.239309 0.965871 -0.0991244 -0.239307 0.965871 -0.0778902 -0.247036 0.96587 -0.0778906 -0.247038 0.96587 -0.0560636 -0.252886 0.965871 -0.056063 -0.252883 0.965871 -0.0338094 -0.256807 0.965871 -0.0338096 -0.256809 0.96587 -0.0112984 -0.258779 0.965872 -0.0112984 -0.258775 0.965872 0.0112982 -0.258775 0.96587 0.0112986 -0.25878 0.96587 0.0338099 -0.256811 0.965871 0.0338093 -0.256807 0.965871 0.0560628 -0.252883 0.96587 0.056064 -0.252888 0.96587 0.0778911 -0.247039 0.965871 0.0778901 -0.247036 0.965871 0.0991244 -0.239307 0.965871 0.0991241 -0.239307 0.965871 0.119604 -0.229757 0.965871 0.119604 -0.229756 0.965871 0.139173 -0.218458 0.96587 0.139176 -0.218462 0.96587 0.157686 -0.205501 0.96587 0.157685 -0.205499 0.96587 0.174995 -0.190974 0.965871 0.174994 -0.190973 0.965871 0.190973 -0.174994 0.96587 0.190974 -0.174995 0.96587 0.205499 -0.157685 0.96587 0.205499 -0.157685 0.96587 0.21846 -0.139174 0.96587 0.21846 -0.139174 0.96587 0.229759 -0.119605 0.96587 0.22976 -0.119606 0.96587 0.23931 -0.0991256 0.96587 0.239308 -0.0991249 0.96587 0.247037 -0.0778905 0.965871 0.247036 -0.0778901 0.965871 0.252884 -0.0560631 0.96587 0.252886 -0.0560635 0.96587 0.25681 -0.0338096 0.965871 0.256808 -0.0338095 0.965871 0.258778 -0.0112985 0.965871 0.258778 -0.0112985 -0.793143 -0.608456 -0.0265662 -0.896672 0.442274 -0.0193101 -0.608366 0.792901 -0.0346189 -0.194921 0.979885 -0.0427828 -0.441932 0.896195 -0.0391288 -0.258613 0.964994 -0.0436555 -0.258597 0.957721 -0.126086 -0.258594 0.957722 -0.126087 -0.258594 0.943088 -0.209078 -0.258599 0.943087 -0.209077 -0.258599 0.921276 -0.290477 -0.258599 0.921276 -0.290477 -0.258599 0.892454 -0.369666 -0.258591 0.892455 -0.369667 -0.258591 0.856841 -0.446043 -0.258595 0.85684 -0.446043 -0.258595 0.814704 -0.519024 -0.258607 0.814701 -0.519022 -0.258608 0.766365 -0.588053 -0.258598 0.766367 -0.588055 -0.258598 0.712199 -0.65261 -0.258597 0.712199 -0.65261 -0.258597 0.65261 -0.712199 -0.258598 0.65261 -0.712199 -0.258598 0.588054 -0.766368 -0.258594 0.588055 -0.766368 -0.258595 0.519024 -0.814704 -0.258579 0.519026 -0.814708 -0.25858 0.446044 -0.856844 -0.258616 0.446041 -0.856834 -0.258616 0.369665 -0.892449 -0.258588 0.369667 -0.892456 -0.258588 0.290478 -0.921279 -0.258613 0.290476 -0.921272 -0.258612 0.209077 -0.943084 -0.258596 0.209077 -0.943088 -0.258595 0.126087 -0.957722 -0.258596 0.126087 -0.957721 -0.258597 0.0421356 -0.965066 -0.258596 0.0421355 -0.965066 -0.258596 -0.0421356 -0.965066 -0.258599 -0.0421355 -0.965065 -0.258602 -0.126086 -0.95772 -0.258595 -0.126087 -0.957722 -0.258596 -0.209078 -0.943088 -0.258608 -0.209077 -0.943085 -0.258606 -0.290476 -0.921274 -0.258588 -0.290478 -0.921279 -0.258588 -0.369668 -0.892456 -0.258616 -0.369664 -0.892449 -0.258616 -0.446039 -0.856835 -0.25858 -0.446045 -0.856843 -0.258579 -0.519027 -0.814707 -0.258619 -0.51902 -0.814699 -0.258622 -0.58805 -0.766363 -0.258612 -0.588052 -0.766365 -0.258613 -0.652608 -0.712196 -0.258612 -0.652608 -0.712196 -0.258613 -0.712195 -0.652608 -0.258581 -0.712202 -0.652613 -0.25858 -0.766372 -0.588057 -0.258608 -0.766365 -0.588053 -0.258607 -0.814701 -0.519022 -0.258604 -0.814702 -0.519023 -0.258605 -0.856837 -0.446042 -0.258591 -0.856841 -0.446043 -0.258591 -0.892456 -0.369667 -0.25863 -0.892446 -0.369664 -0.258631 -0.921268 -0.290475 -0.258567 -0.921285 -0.290478 -0.258566 -0.943096 -0.209079 -0.258572 -0.943094 -0.209079 -0.258572 -0.957728 -0.126086 -0.258597 -0.957721 -0.126086 -0.258597 -0.965066 -0.0421363 -0.258573 -0.965072 -0.0421358 -0.608306 -0.792947 -0.0346213 -0.706815 -0.706633 -0.0328913 -0.706772 -0.701389 -0.0923388 -0.706768 -0.701393 -0.0923392 -0.706768 -0.690676 -0.153119 -0.706775 -0.69067 -0.153118 -0.706774 -0.674697 -0.212731 -0.706789 -0.674682 -0.212727 -0.706789 -0.653575 -0.27072 -0.706768 -0.653594 -0.270727 -0.706769 -0.627511 -0.326662 -0.70676 -0.627519 -0.326666 -0.70676 -0.59666 -0.380114 -0.706758 -0.596662 -0.380115 -0.706759 -0.561262 -0.43067 -0.706772 -0.561251 -0.430663 -0.706772 -0.52158 -0.477941 -0.706759 -0.52159 -0.47795 -0.706758 -0.47795 -0.52159 -0.706764 -0.477946 -0.521586 -0.706765 -0.430667 -0.561257 -0.706771 -0.430663 -0.561252 -0.706772 -0.380109 -0.59665 -0.706783 -0.380102 -0.59664 -0.706782 -0.326655 -0.6275 -0.706772 -0.32666 -0.627509 -0.706771 -0.270727 -0.653592 -0.70678 -0.270723 -0.653583 -0.706779 -0.212729 -0.674692 -0.706771 -0.212732 -0.6747 -0.706772 -0.153118 -0.690672 -0.706767 -0.15312 -0.690677 -0.706767 -0.0923405 -0.701394 -0.70677 -0.0923399 -0.701391 -0.706771 -0.0308581 -0.706769 -0.70677 -0.0308583 -0.70677 -0.70677 0.0308582 -0.70677 -0.706773 0.0308582 -0.706768 -0.706774 0.0923397 -0.701388 -0.706767 0.0923403 -0.701394 -0.706767 0.15312 -0.690677 -0.706774 0.153118 -0.69067 -0.706774 0.212731 -0.674697 -0.706776 0.21273 -0.674695 -0.706775 0.270725 -0.653588 -0.706766 0.270728 -0.653596 -0.706766 0.326663 -0.627514 -0.70677 0.326661 -0.62751 -0.70677 0.380109 -0.596651 -0.706779 0.380105 -0.596644 -0.706778 0.430659 -0.561246 -0.706772 0.430663 -0.561251 -0.706772 0.47794 -0.52158 -0.706767 0.477944 -0.521585 -0.706767 0.521584 -0.477944 -0.706772 0.52158 -0.47794 -0.706772 0.561251 -0.430663 -0.706774 0.56125 -0.430662 -0.706774 0.596649 -0.380107 -0.706775 0.596647 -0.380106 -0.706776 0.627505 -0.326658 -0.706779 0.627502 -0.326656 -0.706779 0.653584 -0.270723 -0.706772 0.653591 -0.270726 -0.706772 0.674699 -0.212732 -0.706775 0.674697 -0.212731 -0.706775 0.69067 -0.153118 -0.706774 0.690671 -0.153118 -0.706774 0.701387 -0.0923394 -0.706772 0.701389 -0.0923397 -0.706815 0.706633 -0.0328898 -0.793112 0.608497 -0.0265675 -0.980762 0.195021 -0.0085148 -0.965886 0.258649 -0.0128222 -0.965871 0.256808 -0.0338094 -0.96587 0.25681 -0.0338097 -0.96587 0.252886 -0.0560635 -0.965871 0.252884 -0.0560631 -0.965871 0.247036 -0.07789 -0.96587 0.247037 -0.0778905 -0.96587 0.239308 -0.0991248 -0.96587 0.23931 -0.0991257 -0.96587 0.22976 -0.119606 -0.96587 0.229759 -0.119605 -0.96587 0.21846 -0.139174 -0.96587 0.21846 -0.139174 -0.96587 0.205499 -0.157685 -0.96587 0.205499 -0.157685 -0.96587 0.190974 -0.174995 -0.965871 0.190973 -0.174994 -0.965871 0.174994 -0.190973 -0.96587 0.174995 -0.190974 -0.96587 0.157685 -0.205499 -0.96587 0.157686 -0.205501 -0.96587 0.139176 -0.218462 -0.965871 0.139173 -0.218458 -0.965871 0.119604 -0.229756 -0.965871 0.119604 -0.229757 -0.965871 0.0991241 -0.239307 -0.965871 0.0991243 -0.239307 -0.965871 0.0778902 -0.247036 -0.96587 0.077891 -0.247039 -0.96587 0.0560639 -0.252888 -0.965871 0.056063 -0.252883 -0.965871 0.0338094 -0.256807 -0.96587 0.0338098 -0.256811 -0.96587 0.0112984 -0.25878 -0.965872 0.0112984 -0.258775 -0.965872 -0.0112982 -0.258775 -0.96587 -0.0112986 -0.258779 -0.96587 -0.0338097 -0.256809 -0.965871 -0.0338093 -0.256807 -0.965871 -0.0560628 -0.252883 -0.96587 -0.0560637 -0.252886 -0.96587 -0.0778906 -0.247038 -0.965871 -0.0778901 -0.247036 -0.965871 -0.0991244 -0.239307 -0.96587 -0.099125 -0.239309 -0.96587 -0.119605 -0.229759 -0.96587 -0.119605 -0.229759 -0.96587 -0.139175 -0.218461 -0.965871 -0.139174 -0.218459 -0.965871 -0.157684 -0.205498 -0.96587 -0.157685 -0.205499 -0.96587 -0.174995 -0.190974 -0.965871 -0.174994 -0.190973 -0.965871 -0.190973 -0.174994 -0.965872 -0.19097 -0.174992 -0.965872 -0.205495 -0.157682 -0.965871 -0.205497 -0.157683 -0.965871 -0.218458 -0.139173 -0.965872 -0.218454 -0.13917 -0.965873 -0.229752 -0.119601 -0.965872 -0.229753 -0.119602 -0.965872 -0.239303 -0.0991224 -0.965869 -0.239314 -0.0991266 -0.965869 -0.247042 -0.0778925 -0.965869 -0.247044 -0.0778929 -0.965868 -0.252893 -0.0560644 -0.965874 -0.252872 -0.0560604 -0.965874 -0.256795 -0.0338078 -0.96587 -0.25681 -0.0338093 -0.96587 -0.258779 -0.011299 -0.965868 -0.258787 -0.0112991 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.999048 -0.0436194 0 0.999048 -0.0436194 0 0.991445 -0.130526 0 0.991445 -0.130526 0 0.976296 -0.216439 0 0.976296 -0.216439 0 0.953717 -0.300706 0 0.953717 -0.300706 0 0.92388 -0.382683 0 0.92388 -0.382683 0 0.887011 -0.461749 0 0.887011 -0.461749 0 0.843391 -0.5373 0 0.843391 -0.5373 0 0.793353 -0.608762 0 0.793353 -0.608762 0 0.737277 -0.67559 0 0.737277 -0.67559 0 0.67559 -0.737277 0 0.67559 -0.737277 0 0.608761 -0.793353 0 0.608761 -0.793353 0 0.537299 -0.843392 0 0.537299 -0.843392 0 0.461749 -0.88701 0 0.461749 -0.88701 0 0.382683 -0.92388 0 0.382683 -0.92388 0 0.300706 -0.953717 0 0.300706 -0.953717 0 0.216439 -0.976296 0 0.216439 -0.976296 0 0.130527 -0.991445 0 0.130527 -0.991445 0 0.0436192 -0.999048 0 0.0436192 -0.999048 0 -0.0436192 -0.999048 0 -0.0436192 -0.999048 0 -0.130527 -0.991445 0 -0.130527 -0.991445 0 -0.216439 -0.976296 0 -0.216439 -0.976296 0 -0.300706 -0.953717 0 -0.300706 -0.953717 0 -0.382683 -0.92388 0 -0.382683 -0.92388 0 -0.461749 -0.887011 0 -0.461749 -0.887011 0 -0.537299 -0.843392 0 -0.537299 -0.843392 0 -0.608761 -0.793353 0 -0.608761 -0.793353 0 -0.675591 -0.737277 0 -0.675591 -0.737277 0 -0.737277 -0.67559 0 -0.737277 -0.67559 0 -0.793353 -0.608761 0 -0.793353 -0.608761 0 -0.843391 -0.5373 0 -0.843391 -0.5373 0 -0.887011 -0.461749 0 -0.887011 -0.461749 0 -0.923879 -0.382684 0 -0.923879 -0.382684 0 -0.953718 -0.300704 0 -0.953718 -0.300704 0 -0.976296 -0.21644 0 -0.976296 -0.21644 0 -0.991445 -0.130526 0 -0.991445 -0.130526 0 -0.999048 -0.0436192 0 -0.999048 -0.0436192 0.202033 0.978542 0.0404726 0.202059 0.978537 0.0404702 0.202059 0.971852 0.121141 0.202063 0.971852 0.121141 0.202227 0.965229 0.165641 0.148241 0.966961 0.207389 0.202031 0.958534 0.200986 0.202032 0.938664 0.279453 0.202047 0.938661 0.279451 0.202204 0.923321 0.326484 0.092996 0.92419 0.370438 0.202042 0.912379 0.356011 0.202042 0.879863 0.430139 0.202051 0.879862 0.430138 0.202198 0.854803 0.477941 0.0930844 0.855324 0.509663 0.202136 0.834334 0.512863 0.202044 0.797064 0.569094 0.202057 0.797062 0.569091 0.20219 0.761661 0.615623 0.0806897 0.760596 0.644192 0.202164 0.735574 0.646576 0.20205 0.692523 0.692523 0.202044 0.692523 0.692524 0.202159 0.646578 0.735574 0.0806799 0.644193 0.760596 0.202183 0.615624 0.761662 0.20205 0.569092 0.797063 0.202051 0.569092 0.797063 0.202143 0.512863 0.834332 0.0930814 0.509663 0.855324 0.202194 0.477941 0.854804 0.202047 0.430139 0.879862 0.20204 0.430139 0.879864 0.202106 0.364372 0.909058 0.117736 0.36098 0.925112 0.202211 0.326486 0.923319 0.202054 0.279451 0.938659 0.20205 0.279451 0.93866 0.202085 0.205382 0.957591 0.1543 0.202758 0.966996 0.202219 0.165628 0.965233 0.202055 0.121141 0.971853 0.202052 0.121141 0.971854 0.202051 0.0404733 0.978538 0.202042 0.0404726 0.97854 0.202042 -0.0404733 0.97854 0.20205 -0.0404725 0.978539 0.202049 -0.121142 0.971854 0.202055 -0.121141 0.971853 0.202219 -0.165628 0.965233 0.14821 -0.207393 0.966965 0.20205 -0.200983 0.958531 0.20205 -0.279451 0.93866 0.202057 -0.27945 0.938659 0.202214 -0.326485 0.923318 0.093013 -0.370437 0.924189 0.202044 -0.356012 0.912378 0.202044 -0.430139 0.879863 0.202051 -0.430138 0.879862 0.202198 -0.477939 0.854804 0.0930766 -0.509663 0.855325 0.202138 -0.512863 0.834333 0.202046 -0.569093 0.797064 0.20205 -0.569092 0.797063 0.202183 -0.615624 0.761662 0.0806799 -0.644193 0.760596 0.202164 -0.646577 0.735573 0.20205 -0.692523 0.692523 0.20205 -0.692523 0.692523 0.202164 -0.735574 0.646576 0.0806841 -0.760596 0.644192 0.202183 -0.761662 0.615624 0.20205 -0.797063 0.569092 0.202051 -0.797063 0.569092 0.202143 -0.834332 0.512862 0.0930804 -0.855325 0.509663 0.202195 -0.854804 0.47794 0.202047 -0.879862 0.430139 0.202046 -0.879862 0.430139 0.202112 -0.909057 0.364372 0.117735 -0.925112 0.36098 0.202204 -0.923319 0.326488 0.850921 0.524845 0.0217078 0.85092 0.524847 0.021708 0.85092 0.521261 0.0649747 0.850922 0.521259 0.0649742 0.850922 0.514113 0.107799 0.850929 0.5141 0.107795 0.850929 0.503443 0.149881 0.850927 0.503446 0.149882 0.850927 0.48935 0.190945 0.850927 0.489349 0.190945 0.850927 0.47191 0.230703 0.850923 0.471916 0.230706 0.850923 0.451253 0.268889 0.850926 0.451249 0.268886 0.850926 0.427503 0.305231 0.850921 0.42751 0.305236 0.850921 0.400843 0.339497 0.850925 0.400839 0.339492 0.850925 0.371434 0.371434 0.850925 0.371434 0.371434 0.850925 0.339493 0.400838 0.850923 0.339495 0.400841 0.850923 0.305234 0.427507 0.850925 0.305233 0.427505 0.850925 0.268887 0.45125 0.850923 0.268888 0.451253 0.850923 0.230706 0.471916 0.850924 0.230705 0.471915 0.850923 0.190947 0.489355 0.850922 0.190948 0.489358 0.850922 0.149885 0.503455 0.850925 0.149884 0.503449 0.850925 0.107797 0.514107 0.850924 0.107797 0.51411 0.850924 0.0649747 0.521255 0.850922 0.0649748 0.521258 0.850922 0.0217073 0.524843 0.850926 0.0217076 0.524837 0.850926 -0.0217071 0.524837 0.850923 -0.0217078 0.524842 0.850923 -0.0649749 0.521257 0.850924 -0.0649745 0.521255 0.850924 -0.107797 0.514109 0.850925 -0.107797 0.514108 0.850924 -0.149884 0.503451 0.850923 -0.149885 0.503453 0.850923 -0.190947 0.489356 0.850923 -0.190948 0.489357 0.850923 -0.230706 0.471917 0.850923 -0.230706 0.471916 0.850923 -0.268889 0.451253 0.850926 -0.268886 0.451248 0.850926 -0.305231 0.427503 0.850923 -0.305234 0.427507 0.850923 -0.339495 0.400841 0.850923 -0.339494 0.40084 0.850923 -0.371436 0.371436 0.850924 -0.371435 0.371435 0.850924 -0.400839 0.339494 0.850924 -0.40084 0.339494 0.850924 -0.427506 0.305233 0.850924 -0.427506 0.305233 0.850924 -0.451251 0.268887 0.850924 -0.451252 0.268887 0.850924 -0.471915 0.230705 0.850924 -0.471915 0.230705 0.850924 -0.489355 0.190947 0.850924 -0.489355 0.190947 0.850924 -0.503452 0.149884 0.850924 -0.503451 0.149884 0.850925 -0.514108 0.107797 0.850924 -0.514109 0.107797 0.573255 0.818677 0.0338587 0.573234 0.818692 0.0338614 0.573234 0.813099 0.101352 0.573238 0.813097 0.101352 0.573238 0.80195 0.168153 0.573239 0.801949 0.168153 0.573239 0.785324 0.233801 0.573242 0.785322 0.2338 0.573242 0.763333 0.297853 0.573236 0.763336 0.297855 0.573237 0.736133 0.359873 0.573237 0.736133 0.359873 0.573237 0.7039 0.419434 0.573239 0.703899 0.419433 0.573239 0.666858 0.476127 0.573247 0.666854 0.476123 0.573247 0.625258 0.529566 0.573243 0.62526 0.529568 0.573243 0.579393 0.579393 0.573243 0.579393 0.579393 0.573243 0.529568 0.62526 0.573247 0.529567 0.625257 0.573247 0.476124 0.666854 0.573246 0.476124 0.666854 0.573245 0.41943 0.703895 0.573246 0.41943 0.703895 0.573245 0.35987 0.736127 0.573248 0.35987 0.736126 0.573248 0.297852 0.763329 0.573244 0.297853 0.763331 0.573244 0.2338 0.785321 0.573244 0.2338 0.785321 0.573244 0.168151 0.801945 0.573239 0.168151 0.801949 0.573238 0.101352 0.813096 0.573246 0.101352 0.813091 0.573246 0.0338609 0.818683 0.573242 0.0338606 0.818686 0.573242 -0.033861 0.818686 0.573246 -0.0338604 0.818683 0.573246 -0.101351 0.813091 0.573238 -0.101353 0.813097 0.573237 -0.168152 0.80195 0.573244 -0.16815 0.801945 0.573244 -0.2338 0.785321 0.573242 -0.2338 0.785322 0.573242 -0.297854 0.763333 0.573248 -0.297852 0.763329 0.573248 -0.359869 0.736126 0.573245 -0.35987 0.736127 0.573246 -0.41943 0.703895 0.573242 -0.419432 0.703897 0.573242 -0.476126 0.666856 0.573243 -0.476126 0.666856 0.573243 -0.529568 0.62526 0.573247 -0.529566 0.625258 0.573247 -0.579391 0.579391 0.573241 -0.579394 0.579394 0.573241 -0.625261 0.529569 0.573245 -0.625259 0.529567 0.573244 -0.666855 0.476125 0.573241 -0.666857 0.476126 0.573242 -0.703897 0.419432 0.573242 -0.703897 0.419431 0.573243 -0.736129 0.359871 0.573245 -0.736127 0.359871 0.573245 -0.763331 0.297853 0.573245 -0.763331 0.297853 0.573245 -0.78532 0.2338 0.573242 -0.785322 0.2338 0.573242 -0.801947 0.168151 0.573244 -0.801946 0.16815 0.202047 -0.938661 0.279451 0.202048 -0.93866 0.279451 0.202083 -0.957591 0.205382 0.154297 -0.966996 0.202758 0.202211 -0.965234 0.165631 0.850924 -0.521254 0.0649743 0.850924 -0.521255 0.0649743 0.573243 -0.813093 0.101352 0.573244 -0.813092 0.101352 0.202048 -0.971855 0.121142 0.202048 -0.971855 0.121141 0.850924 -0.52484 0.0217075 0.850924 -0.52484 0.0217076 0.573244 -0.818685 0.0338611 0.573243 -0.818685 0.0338611 0.202048 -0.978539 0.0404727 0.202048 -0.978539 0.0404727 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.995185 -0.0980172 0 -0.995185 -0.0980172 0 -0.95694 -0.290285 0 -0.95694 -0.290285 0 -0.881921 -0.471397 0 -0.881921 -0.471397 0 -0.773011 -0.634393 0 -0.773011 -0.634393 0 -0.634393 -0.77301 0 -0.634393 -0.77301 0 -0.471397 -0.881921 0 -0.471397 -0.881921 0 -0.290285 -0.95694 0 -0.290285 -0.95694 0 -0.0980172 -0.995185 0 -0.0980172 -0.995185 0 0.0980172 -0.995185 0 0.0980172 -0.995185 0 0.290285 -0.95694 0 0.290285 -0.95694 0 0.471397 -0.881921 0 0.471397 -0.881921 0 0.634393 -0.77301 0 0.634393 -0.77301 0 0.77301 -0.634393 0 0.77301 -0.634393 0 0.881921 -0.471397 0 0.881921 -0.471397 0 0.95694 -0.290285 0 0.95694 -0.290285 0 0.995185 -0.0980172 0 0.995185 -0.0980172 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.995185 -0.0980175 0 0.995185 -0.0980175 0 0.95694 -0.290285 0 0.95694 -0.290285 0 0.881921 -0.471397 0 0.881921 -0.471397 0 0.77301 -0.634393 0 0.77301 -0.634393 0 0.634393 -0.77301 0 0.634393 -0.77301 0 0.471397 -0.881921 0 0.471397 -0.881921 0 0.290285 -0.95694 0 0.290285 -0.95694 0 0.0980172 -0.995185 0 0.0980172 -0.995185 0 -0.0980172 -0.995185 0 -0.0980172 -0.995185 0 -0.290285 -0.95694 0 -0.290285 -0.95694 0 -0.471397 -0.881921 0 -0.471397 -0.881921 0 -0.634393 -0.773011 0 -0.634393 -0.773011 0 -0.773011 -0.634393 0 -0.773011 -0.634393 0 -0.881921 -0.471397 0 -0.881921 -0.471397 0 -0.95694 -0.290285 0 -0.95694 -0.290285 0 -0.995185 -0.0980172 0 -0.995185 -0.0980172 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.995734 -0.0922682 0 0.995734 -0.0922682 0 0.961826 -0.273663 0 0.961826 -0.273663 0 0.895163 -0.445739 0 0.895163 -0.445739 0 0.798018 -0.602634 0 0.798018 -0.602634 0 0.673695 -0.739009 0 0.673695 -0.739009 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.18375 -0.982973 0 0.18375 -0.982973 0 0 -1 0 0 -1 0 -0.18375 -0.982973 0 -0.18375 -0.982973 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.995734 -0.0922684 0 -0.995734 -0.0922684 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.996195 -0.0871555 0 -0.996195 -0.0871555 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.906308 -0.422619 0 -0.906308 -0.422619 0 -0.819152 -0.573576 0 -0.819152 -0.573576 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.573576 -0.819152 0 -0.573576 -0.819152 0 -0.422618 -0.906308 0 -0.422618 -0.906308 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.0871559 -0.996195 0 -0.0871559 -0.996195 0 0.0871559 -0.996195 0 0.0871559 -0.996195 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.422618 -0.906308 0 0.422618 -0.906308 0 0.573576 -0.819152 0 0.573576 -0.819152 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.819152 -0.573576 0 0.819152 -0.573576 0 0.906308 -0.422618 0 0.906308 -0.422618 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.996195 -0.0871558 0 0.996195 -0.0871558 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.977764 -0.209706 0 0.985593 -0.169136 0.0112218 0.996132 -0.0871508 0.100449 0.987302 -0.123067 0 0.999146 -0.0413248 0.0844714 0.955002 -0.284317 0.0211917 0.965709 -0.25876 0 0.942796 -0.33337 0 0.85192 -0.523673 0 0.872832 -0.488021 0.0299155 0.905902 -0.42243 0.0696534 0.896209 -0.43813 0 0.928212 -0.372051 0.0560295 0.81257 -0.580165 0.0373872 0.818579 -0.573176 0 0.777724 -0.628606 0 0.628606 -0.777724 0 0.660209 -0.751082 0.0436109 0.706434 -0.706434 0.0436114 0.706434 -0.706434 0 0.751083 -0.660208 0.0324144 0.580771 -0.813421 0.0485863 0.572899 -0.818185 0 0.523673 -0.851919 0 0.37205 -0.928213 0.0523168 0.42204 -0.905067 0.0224498 0.439086 -0.898165 0 0.488021 -0.872832 0 0.209708 -0.977764 0.0548023 0.25843 -0.964474 0.0137224 0.28531 -0.958337 0 0.333373 -0.942795 0 -0.0413255 -0.999146 0 0.0413256 -0.999146 0.0560438 0.087019 -0.994629 0.00623844 0.12369 -0.992301 0 0.169122 -0.985595 0.100448 -0.123067 -0.987302 0.01122 -0.0871505 -0.996132 0 -0.169122 -0.985595 0 -0.333372 -0.942795 0.0211921 -0.258761 -0.965709 0.0844695 -0.284317 -0.955002 0 -0.209708 -0.977764 0 -0.523673 -0.851919 0 -0.488019 -0.872833 0.0299147 -0.422429 -0.905902 0.0696538 -0.43813 -0.896209 0 -0.37205 -0.928213 0.0560285 -0.580164 -0.81257 0.0373873 -0.573175 -0.818579 0 -0.628606 -0.777724 0 -0.777724 -0.628606 0 -0.751082 -0.660209 0.0436109 -0.706434 -0.706434 0.0436097 -0.706434 -0.706434 0 -0.66021 -0.751081 0.0324142 -0.813421 -0.580772 0.0485865 -0.818185 -0.572899 0 -0.851919 -0.523673 0 -0.928213 -0.37205 0.0523167 -0.905067 -0.422039 0.0224496 -0.898165 -0.439086 0 -0.872832 -0.48802 0 -0.985595 -0.169124 0 -0.977764 -0.209708 0.0548021 -0.964474 -0.25843 0.013723 -0.958337 -0.285309 0 -0.942794 -0.333375 0.00623875 -0.992301 -0.12369 0.0560444 -0.994629 -0.0870188 0 -0.999146 -0.041325 0 -0.995185 -0.0980173 0 -0.995185 -0.0980173 0 -0.95694 -0.290284 0 -0.95694 -0.290284 0 -0.881921 -0.471397 0 -0.881921 -0.471397 0 -0.77301 -0.634394 0 -0.77301 -0.634394 0 -0.634393 -0.77301 0 -0.634393 -0.77301 0 -0.471397 -0.881921 0 -0.471397 -0.881921 0 -0.290285 -0.95694 0 -0.290285 -0.95694 0 -0.0980174 -0.995185 0 -0.0980174 -0.995185 0 0.0980173 -0.995185 0 0.0980173 -0.995185 0 0.290285 -0.95694 0 0.290285 -0.95694 0 0.471396 -0.881921 0 0.471396 -0.881921 0 0.634393 -0.77301 0 0.634393 -0.77301 0 0.77301 -0.634393 0 0.77301 -0.634393 0 0.881921 -0.471397 0 0.881921 -0.471397 0 0.95694 -0.290285 0 0.95694 -0.290285 0 0.995185 -0.0980171 0 0.995185 -0.0980171 0 -0.995734 -0.0922682 0 -0.995734 -0.0922682 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.18375 -0.982973 0 -0.18375 -0.982973 0 0 -1 0 0 -1 0 0.18375 -0.982973 0 0.18375 -0.982973 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.961826 -0.273663 0 0.961826 -0.273663 0 0.995734 -0.0922684 0 0.995734 -0.0922684 0 -0.995734 -0.0922682 0 -0.995734 -0.0922682 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.18375 -0.982973 0 -0.18375 -0.982973 0 0 -1 0 0 -1 0 0.18375 -0.982973 0 0.18375 -0.982973 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.961826 -0.273663 0 0.961826 -0.273663 0 0.995734 -0.0922684 0 0.995734 -0.0922684 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.705874 -0.688142 0.167938 -0.705874 -0.688141 0.167938 -0.705874 -0.650812 0.279616 -0.705873 -0.650813 0.279616 -0.705873 -0.595499 0.383568 -0.705874 -0.595499 0.383567 -0.705874 -0.523728 0.476918 -0.705874 -0.523728 0.476918 -0.705873 -0.437485 0.557091 -0.705873 -0.437485 0.557091 -0.705873 -0.339152 0.621868 -0.705874 -0.339151 0.621867 -0.705874 -0.231446 0.669459 -0.705874 -0.231446 0.669459 -0.705873 -0.117345 0.698551 -0.705875 -0.117344 0.69855 -0.705874 0 0.708337 -0.705874 0 0.708337 -0.705875 0.117344 0.698549 -0.705873 0.117345 0.698551 -0.705874 0.231446 0.669459 -0.705874 0.231446 0.669459 -0.705874 0.339151 0.621867 -0.705875 0.339151 0.621866 -0.705876 0.437483 0.557089 -0.705875 0.437484 0.557089 -0.705875 0.523727 0.476918 -0.705877 0.523726 0.476916 -0.705877 0.595496 0.383565 -0.705872 0.5955 0.383568 -0.705872 0.650814 0.279617 -0.705871 0.650815 0.279617 -0.70587 0.688145 0.167939 -0.705879 0.688137 0.167936 -0.705879 0.688136 -0.167937 -0.70587 0.688145 -0.167938 -0.705871 0.650816 -0.279617 -0.705874 0.650813 -0.279616 -0.705874 0.595498 -0.383567 -0.705878 0.595495 -0.383565 -0.705877 0.523726 -0.476916 -0.705875 0.523727 -0.476917 -0.705875 0.437484 -0.557089 -0.705876 0.437483 -0.557089 -0.705875 0.339151 -0.621866 -0.705874 0.339151 -0.621867 -0.705874 0.231446 -0.669459 -0.705874 0.231446 -0.669459 -0.705873 0.117345 -0.698551 -0.705875 0.117344 -0.69855 -0.705874 0 -0.708337 -0.705874 0 -0.708337 -0.705875 -0.117344 -0.698549 -0.705873 -0.117345 -0.698551 -0.705874 -0.231446 -0.669459 -0.705874 -0.231446 -0.669459 -0.705874 -0.339151 -0.621867 -0.705873 -0.339152 -0.621868 -0.705873 -0.437485 -0.557091 -0.705873 -0.437485 -0.557091 -0.705873 -0.523729 -0.476919 -0.705875 -0.523728 -0.476918 -0.705874 -0.595499 -0.383567 -0.705875 -0.595497 -0.383566 -0.705875 -0.650812 -0.279616 -0.705874 -0.650812 -0.279616 -0.705874 -0.688141 -0.167938 -0.705874 -0.688142 -0.167938 0.42256 -0.891066 0.165662 0.413966 -0.895712 0.162269 0.422615 -0.894625 0.145062 0.422527 -0.891834 -0.161567 0.411777 -0.895933 -0.166567 0.422615 -0.894625 -0.145062 0.422527 0.891834 0.161566 0.411773 0.895934 0.166568 0.422613 0.894626 0.14506 0.42256 0.891066 -0.165663 0.413963 0.895714 -0.162269 0.422613 0.894626 -0.14506 0.939848 0.337905 -0.0500624 0.93966 0.338017 -0.0527686 0.939694 0.337945 -0.0526163 0.939775 0.337718 -0.0526324 0.939762 0.337887 -0.051768 0.939691 0.337678 -0.0543545 0.940782 0.33463 -0.0543291 0.940488 0.335446 -0.0543911 0.939738 0.337741 -0.0531348 0.940046 0.337704 -0.0476475 0.940591 0.336734 -0.0435686 0.940962 0.335913 -0.0418711 0.939576 0.341978 -0.0157346 0.938803 0.344161 -0.0142348 0.93981 0.340168 -0.032293 0.94012 0.338886 -0.0364742 0.940373 0.322215 -0.108978 0.94025 0.322553 -0.109043 0.939705 0.324547 -0.107816 0.939689 0.32466 -0.107611 0.939721 0.324603 -0.107503 0.939672 0.324865 -0.10714 0.939728 0.324322 -0.108286 0.939825 0.324689 -0.106327 0.93997 0.324735 -0.104899 0.940231 0.324735 -0.102537 0.940767 0.323977 -0.0999781 0.941076 0.323502 -0.0986006 0.942097 0.32169 -0.0947017 0.941616 0.322692 -0.0960696 0.940184 0.328562 -0.0900085 0.939768 0.330594 -0.0868542 0.93909 0.336356 -0.0705263 0.944609 0.319539 -0.0748907 0.942944 0.324917 -0.0727022 0.941632 0.329127 -0.0707394 0.940548 0.332847 -0.0676941 0.939668 0.336154 -0.0634363 0.940358 0.334815 -0.0602109 0.939668 0.336298 -0.062675 0.939737 0.334824 -0.0691884 0.939654 0.335031 -0.0693135 0.939553 0.336556 -0.0630193 0.941748 0.330656 -0.0614605 0.941623 0.330997 -0.0615376 0.939613 0.335163 -0.0692305 0.940039 0.334133 -0.0684249 0.939888 0.234541 -0.248194 0.939793 0.233815 -0.249239 0.941383 0.239991 -0.237071 0.94208 0.237156 -0.237156 0.941338 0.237056 -0.240183 0.940271 0.236073 -0.245277 0.943023 0.249137 -0.22054 0.937986 0.26454 -0.224054 0.939926 0.247903 -0.234697 0.94029 0.245147 -0.236129 0.940636 0.26205 -0.215715 0.939629 0.263032 -0.218889 0.939735 0.255385 -0.227326 0.939658 0.255493 -0.227521 0.939425 0.263271 -0.219475 0.943046 0.255798 -0.212679 0.942944 0.256016 -0.212869 0.939622 0.255629 -0.227516 0.939995 0.255201 -0.226456 0.939703 0.227154 -0.255653 0.946017 0.198325 -0.256356 0.939665 0.227908 -0.255125 0.940313 0.20821 -0.269185 0.942724 0.207284 -0.26135 0.92698 0.217968 -0.305284 0.941562 0.220662 -0.254499 0.939972 0.22055 -0.260403 0.939694 0.230931 -0.25228 0.939686 0.23271 -0.250672 0.940165 0.0898903 -0.328649 0.941592 0.0960885 -0.322756 0.944467 0.107805 -0.31042 0.932765 0.13104 -0.335826 0.941174 0.0982285 -0.323331 0.942147 0.0945267 -0.321597 0.940908 0.123074 -0.315509 0.939568 0.122822 -0.319573 0.939734 0.107477 -0.324576 0.939646 0.107472 -0.32483 0.939276 0.12283 -0.320428 0.944297 0.118194 -0.307136 0.944185 0.118305 -0.30744 0.939604 0.107616 -0.324906 0.940038 0.107802 -0.323584 0.939693 0.068933 -0.335 0.945381 0.0462866 -0.322665 0.939665 0.0697565 -0.334907 0.940233 0.0503713 -0.336787 0.939493 0.0487772 -0.339078 0.939105 0.0492324 -0.340086 0.945482 0.0462415 -0.322376 0.939721 0.0692499 -0.334856 0.939678 0.0691629 -0.334995 0.942138 0.0534584 -0.330934 0.943367 0.054793 -0.327195 0.932838 0.0445662 -0.35753 0.940851 0.0685342 -0.331816 0.941418 0.0701701 -0.32986 0.942237 0.0716071 -0.327204 0.942779 0.0724837 -0.325446 0.940603 0.0696724 -0.332284 0.93964 0.0828211 -0.33199 0.939757 0.0867431 -0.330655 0.941633 -0.0707405 -0.329126 0.931736 -0.0449173 -0.360347 0.941161 -0.0465105 -0.334744 0.939487 -0.0487843 -0.339093 0.939722 -0.0692451 -0.334855 0.939647 -0.0693578 -0.335042 0.939105 -0.0492324 -0.340086 0.945481 -0.0462418 -0.322378 0.94538 -0.0462869 -0.322667 0.939603 -0.0692691 -0.335183 0.940012 -0.0684956 -0.334194 0.944299 -0.118192 -0.307132 0.944183 -0.118307 -0.307444 0.939694 -0.107822 -0.324577 0.93968 -0.107645 -0.324674 0.939733 -0.10747 -0.324581 0.939663 -0.106955 -0.324953 0.940132 -0.120529 -0.318786 0.941535 -0.115672 -0.316435 0.942464 -0.113071 -0.314604 0.942807 -0.112135 -0.313911 0.936862 -0.127119 -0.325777 0.940306 -0.102178 -0.324629 0.940765 -0.0999869 -0.323981 0.941076 -0.0986002 -0.323502 0.942097 -0.0947017 -0.32169 0.941616 -0.0960695 -0.322693 0.940184 -0.0900087 -0.328562 0.939768 -0.086854 -0.330594 0.939691 -0.0846074 -0.331393 0.939622 -0.0702272 -0.334929 0.944196 -0.0743443 -0.320884 0.942942 -0.0727001 -0.324922 0.946019 -0.198322 -0.256351 0.939615 -0.227541 -0.255636 0.94 -0.226445 -0.255193 0.941394 -0.203593 -0.268939 0.939383 -0.208237 -0.27239 0.964079 -0.146644 -0.221466 0.939001 -0.21079 -0.271744 0.946111 -0.198156 -0.256142 0.939734 -0.227338 -0.255378 0.939652 -0.227547 -0.255493 0.943051 -0.255787 -0.212669 0.942939 -0.256027 -0.212878 0.9397 -0.25565 -0.227171 0.939686 -0.255539 -0.227355 0.93973 -0.255373 -0.227361 0.939662 -0.255121 -0.227922 0.940012 -0.261074 -0.219587 0.940925 -0.256942 -0.220547 0.941563 -0.254496 -0.220662 0.942491 -0.25098 -0.220724 0.938613 -0.263243 -0.222956 0.939793 -0.249241 -0.233813 0.939889 -0.248192 -0.234543 0.941383 -0.23707 -0.239992 0.94208 -0.237156 -0.237156 0.941338 -0.240182 -0.237056 0.94027 -0.245278 -0.236072 0.939698 -0.334989 -0.0689185 0.941626 -0.330991 -0.061536 0.939662 -0.334906 -0.0698094 0.941282 -0.3303 -0.0699322 0.940699 -0.33235 -0.0680414 0.939684 -0.334985 -0.0691266 0.939728 -0.334846 -0.0692137 0.941745 -0.330665 -0.0614624 0.939553 -0.336555 -0.0630187 0.939673 -0.336286 -0.0626586 0.939874 -0.335438 -0.0641828 0.940331 -0.333649 -0.066761 0.942236 -0.327207 -0.0716056 0.942779 -0.325445 -0.0724842 0.940603 -0.332284 -0.0696725 0.9445 -0.316571 -0.0877696 0.940986 -0.324375 -0.0965707 0.939757 -0.330654 -0.0867446 0.93964 -0.331989 -0.0828203 0.941846 -0.322227 -0.0953753 0.940413 -0.32456 -0.101414 0.9399 -0.324799 -0.105329 0.939688 -0.324075 -0.109374 0.939728 -0.324589 -0.107483 0.939649 -0.324819 -0.107479 0.939659 -0.324234 -0.109147 0.940386 -0.322178 -0.108973 0.940248 -0.322558 -0.109046 0.93961 -0.324889 -0.107611 0.940017 -0.323651 -0.107786 0.939598 -0.341987 -0.0141447 0.938904 -0.343817 -0.015819 0.940223 -0.337944 -0.0421247 0.942583 -0.33213 -0.035012 0.940989 -0.335884 -0.0414939 0.940252 -0.337371 -0.0458932 0.940496 -0.335424 -0.0543885 0.939648 -0.338017 -0.0529685 0.93994 -0.33718 -0.0531254 0.939974 -0.337778 -0.0485306 0.939848 -0.337905 -0.0500601 0.939688 -0.337871 -0.053194 0.940103 -0.336532 -0.0543428 0.940789 -0.334611 -0.0543267 0.939822 -0.337576 -0.0526975 0.939715 -0.337878 -0.0526762 0.939752 -0.324452 -0.10769 0.939691 -0.324052 -0.109411 0.939599 -0.318863 -0.124421 0.938046 -0.320037 -0.132839 0.940362 -0.305611 -0.149404 0.939671 -0.304036 -0.156783 0.939599 -0.294035 -0.175207 0.939163 -0.293973 -0.177631 0.939988 -0.277692 -0.198268 0.939625 -0.277275 -0.200559 0.939634 -0.263026 -0.218873 0.939425 -0.263271 -0.219475 0.94014 -0.236001 -0.245848 0.939662 -0.233125 -0.250375 0.939771 -0.220908 -0.260825 0.941312 -0.220739 -0.255354 0.93036 -0.213051 -0.298396 0.939372 -0.20888 -0.271937 0.939599 -0.175207 -0.294036 0.938156 -0.171258 -0.30089 0.940362 -0.149404 -0.305611 0.939667 -0.144089 -0.310264 0.939574 -0.122822 -0.319555 0.939276 -0.12283 -0.320428 0.942895 -0.0544279 -0.328615 0.939478 -0.0495644 -0.339007 0.939599 -0.0141448 -0.341986 0.941836 -0.025199 -0.335128 0.934773 0.0146807 -0.354943 0.940342 0 -0.340232 0.93969 0.0256455 -0.341066 0.942105 0.113934 -0.315368 0.939562 0.122098 -0.319868 0.939599 0.150328 -0.3075 0.940951 0.142595 -0.307048 0.937335 0.178356 -0.29932 0.939486 0.169464 -0.297739 0.939391 0.208221 -0.272376 0.96408 0.146642 -0.221465 0.939001 0.21079 -0.271744 0.946113 0.198151 -0.256136 0.93973 0.227361 -0.25537 0.939688 0.227355 -0.255532 0.941312 0.255353 -0.220739 0.939626 0.262539 -0.219493 0.939599 0.278563 -0.19889 0.940026 0.276381 -0.199913 0.939068 0.295285 -0.175951 0.939569 0.293022 -0.177057 0.939599 0.307499 -0.150328 0.941047 0.300655 -0.155039 0.937104 0.325172 -0.126883 0.939476 0.316439 -0.131345 0.939691 0.324054 -0.109406 0.939659 0.324233 -0.109149 0 0.0752464 0.997165 0 -0.948619 0.31642 0 0.770825 0.637047 0 0.983983 0.17826 0 0.983983 0.17826 -0.211517 0.944071 0.252964 -0.00594234 0.971471 0.237083 -0.188715 0.726091 0.661195 0 0.611896 0.790938 0 0.553669 0.832737 -0.0109147 0.609545 0.792677 -0.093473 0.614918 0.783032 0 0.672369 0.740216 0 0.715208 0.698912 -0.189523 0.320823 0.927984 0 0.142265 0.989829 0 0.142265 0.989829 -0.158233 0.163575 0.973758 0 0.224047 0.974578 0 0.281616 0.959527 -0.158233 -0.163575 0.973758 0 -0.360397 0.932799 0 -0.360397 0.932799 -0.189524 -0.320823 0.927984 0 -0.281616 0.959527 0 -0.224047 0.974578 -0.0934732 -0.614917 0.783032 0 -0.611896 0.790938 0 -0.770825 0.637047 0 -0.770825 0.637047 -0.188718 -0.726091 0.661194 0 -0.715208 0.698912 0 -0.672369 0.740216 0 -0.983983 0.178261 0 -0.983983 0.178261 -0.155782 -0.959628 0.234193 -0.00433204 -0.965917 0.258817 0 -0.948619 0.31642 0 -0.918789 0.39475 -0.0507839 -0.923953 0.379121 0 -0.890392 0.455194 0 -0.840699 0.541503 -0.0992326 -0.853466 0.511614 0 -0.811996 0.583663 -0.0109141 -0.609545 0.792677 0 -0.553672 0.832735 0 -0.478799 0.877925 -0.0619695 -0.495349 0.866481 0 -0.422427 0.906397 -0.0221241 0 0.999755 -0.0221241 0 0.999755 0 -0.0752464 0.997165 0 -0.142265 0.989829 0 -0.142265 0.989829 0 0.496303 0.868149 -0.0471006 0.478267 0.87695 0 0.422426 0.906397 0 0.360397 0.932799 0 0.360397 0.932799 0 0.770825 0.637047 0 0.811996 0.583663 -0.0610587 0.83913 0.540493 0 0.948627 0.316396 0 0.948627 0.316396 0 0.925147 0.37961 -0.040801 0.918024 0.394421 0 0.890391 0.455197 0 0.857699 0.514151 0 0.948629 -0.316389 0 -0.770825 -0.637047 0 -0.983983 -0.178261 0 -0.983983 -0.178261 -0.211514 -0.944072 -0.252963 -0.00594387 -0.971471 -0.237083 -0.188718 -0.726091 -0.661194 0 -0.611896 -0.790938 0 -0.553672 -0.832735 -0.010914 -0.609545 -0.792677 -0.0934732 -0.614917 -0.783032 0 -0.672369 -0.740216 0 -0.715208 -0.698912 -0.189524 -0.320823 -0.927984 0 -0.281616 -0.959527 0 -0.224047 -0.974578 -0.158233 -0.163575 -0.973758 0 -0.142265 -0.989829 0 0.142265 -0.989829 0 0.142265 -0.989829 -0.158233 0.163575 -0.973758 0 0.360397 -0.932799 0 0.360397 -0.932799 -0.189523 0.320823 -0.927984 0 0.281616 -0.959527 0 0.224047 -0.974578 -0.093473 0.614918 -0.783032 0 0.611896 -0.790938 0 0.770825 -0.637047 0 0.770825 -0.637047 -0.188715 0.726091 -0.661195 0 0.715208 -0.698912 0 0.672369 -0.740216 0 0.983983 -0.17826 0 0.983983 -0.17826 -0.155784 0.959628 -0.234193 -0.00432961 0.965917 -0.258817 0 0.948629 -0.316389 0 0.918789 -0.39475 -0.0507864 0.923953 -0.37912 0 0.890391 -0.455197 0 0.840699 -0.541503 -0.0992316 0.853466 -0.511614 0 0.811996 -0.583663 -0.0109147 0.609545 -0.792677 0 0.553669 -0.832737 0 0.478799 -0.877925 -0.0619702 0.495349 -0.866481 0 0.422426 -0.906397 0 0.0752464 -0.997165 -0.0221241 0 -0.999755 -0.0221241 0 -0.999755 0 -0.0752464 -0.997165 0 -0.142265 -0.989829 0 -0.496303 -0.868149 -0.0471001 -0.478267 -0.87695 0 -0.422427 -0.906397 0 -0.360397 -0.932799 0 -0.360397 -0.932799 0 -0.770825 -0.637047 0 -0.811996 -0.583663 -0.061059 -0.83913 -0.540493 0 -0.948621 -0.316414 0 -0.948621 -0.316414 0 -0.925146 -0.379611 -0.0407987 -0.918024 -0.394421 0 -0.890392 -0.455194 0 -0.857699 -0.514152 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 0.136709 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136707 -0.849119 -0.510204 -0.136707 -0.849119 -0.373495 -0.373495 -0.849119 -0.136709 -0.510203 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.258817 0 -0.965926 -0.258817 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 0.136709 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136707 -0.849119 -0.510204 -0.136707 -0.849119 -0.373495 -0.373495 -0.849119 -0.136709 -0.510203 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.258817 0 -0.965926 -0.258817 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 0.13671 -0.510203 -0.849119 0.373493 -0.373496 -0.849119 0.510204 -0.136707 -0.84912 -0.510202 -0.136712 -0.849119 -0.373493 -0.373496 -0.849119 -0.13671 -0.510203 0 0.965927 -0.258816 0 0.965927 -0.258816 0 0.707104 -0.70711 0 0.707104 -0.70711 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707104 -0.70711 0 -0.707104 -0.70711 0 -0.965924 -0.258826 0 -0.965924 -0.258826 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 0.136708 -0.510204 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136708 -0.849119 -0.510204 -0.136708 -0.849119 -0.373495 -0.373495 -0.849119 -0.136708 -0.510204 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258817 0 -0.965926 -0.258817 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 0.13671 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.13671 -0.849119 -0.510203 -0.13671 -0.849119 -0.373495 -0.373495 -0.849119 -0.13671 -0.510203 0 0.965925 -0.258821 0 0.965925 -0.258821 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258821 0 -0.965925 -0.258821 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 0.136709 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136709 -0.849119 -0.510204 -0.136709 -0.849119 -0.373495 -0.373495 -0.849119 -0.136709 -0.510203 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.258819 0 -0.965926 -0.258819 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 0.136709 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136709 -0.849119 -0.510204 -0.136709 -0.849119 -0.373495 -0.373495 -0.849119 -0.136709 -0.510203 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.258819 0 -0.965926 -0.258819 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 0.13671 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.13671 -0.849119 -0.510203 -0.13671 -0.849119 -0.373495 -0.373495 -0.849119 -0.13671 -0.510203 0 0.965925 -0.258821 0 0.965925 -0.258821 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258821 0 -0.965925 -0.258821 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 0.13671 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136708 -0.849119 -0.510204 -0.136708 -0.849119 -0.373495 -0.373495 -0.849119 -0.13671 -0.510203 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258817 0 -0.965926 -0.258817 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.965927 -0.258816 0 0.965927 -0.258816 0 0.707104 -0.70711 0 0.707104 -0.70711 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707104 -0.70711 0 -0.707104 -0.70711 0 -0.965924 -0.258826 0 -0.965924 -0.258826 -0.849119 0.13671 -0.510203 -0.849119 0.373493 -0.373496 -0.849119 0.510204 -0.136707 -0.84912 -0.510202 -0.136712 -0.849119 -0.373493 -0.373496 -0.849119 -0.13671 -0.510203 -0.705587 0.7056 -0.0653835 -0.705588 0.705599 -0.0653834 -0.705588 0.681571 -0.193924 -0.70559 0.68157 -0.193923 -0.705589 0.634331 -0.31586 -0.705589 0.634332 -0.31586 -0.705589 0.565492 -0.42704 -0.705587 0.565493 -0.427041 -0.705588 0.477396 -0.523678 -0.705588 0.477396 -0.523678 -0.705588 0.373042 -0.602483 -0.705591 0.37304 -0.60248 -0.705591 0.255983 -0.660768 -0.705584 0.255985 -0.660775 -0.705584 0.13021 -0.696561 -0.705588 0.130209 -0.696557 -0.705587 0 -0.708623 -0.705587 0 -0.708623 -0.705588 -0.130209 -0.696557 -0.705584 -0.13021 -0.696561 -0.705584 -0.255986 -0.660775 -0.705589 -0.255984 -0.66077 -0.705588 -0.373042 -0.602483 -0.705588 -0.373042 -0.602483 -0.705588 -0.477396 -0.523678 -0.705592 -0.477393 -0.523675 -0.705593 -0.565489 -0.427038 -0.705589 -0.565492 -0.42704 -0.705589 -0.634332 -0.31586 -0.705589 -0.634331 -0.31586 -0.70559 -0.68157 -0.193923 -0.705607 -0.681553 -0.193919 -0.705608 -0.70558 -0.0653823 -0.705594 -0.705594 -0.065383 -0.705614 0.705574 -0.0653812 -0.705614 0.705573 -0.0653811 -0.705614 0.681546 -0.193916 -0.705613 0.681548 -0.193917 -0.705613 0.634311 -0.315849 -0.705616 0.634308 -0.315848 -0.705615 0.565471 -0.427024 -0.705616 0.56547 -0.427023 -0.705617 0.477377 -0.523657 -0.70561 0.477381 -0.523662 -0.70561 0.37303 -0.602464 -0.705618 0.373026 -0.602457 -0.705617 0.255974 -0.660743 -0.70561 0.255976 -0.66075 -0.70561 0.130205 -0.696535 -0.705614 0.130204 -0.696531 -0.705614 0 -0.708597 -0.705614 0 -0.708597 -0.705614 -0.130204 -0.696531 -0.70561 -0.130205 -0.696535 -0.70561 -0.255976 -0.66075 -0.705615 -0.255974 -0.660746 -0.705614 -0.373028 -0.602461 -0.705614 -0.373028 -0.602461 -0.705614 -0.477378 -0.523659 -0.705619 -0.477375 -0.523656 -0.705619 -0.565468 -0.427022 -0.705605 -0.56548 -0.42703 -0.705604 -0.634319 -0.315853 -0.705616 -0.634308 -0.315848 -0.705616 -0.681545 -0.193916 -0.705608 -0.681552 -0.193918 -0.705608 -0.70558 -0.0653819 -0.70562 -0.705568 -0.0653813 -0.705784 0.705731 -0.0617443 -0.705755 0.70576 -0.0617456 -0.705756 0.684315 -0.183362 -0.705769 0.684302 -0.183359 -0.70577 0.642066 -0.2994 -0.705775 0.642061 -0.299398 -0.705776 0.580316 -0.406342 -0.705784 0.58031 -0.406338 -0.705782 0.500935 -0.500935 -0.705782 0.500935 -0.500935 -0.705782 0.406338 -0.580311 -0.705777 0.406341 -0.580315 -0.705777 0.299397 -0.642059 -0.705782 0.299395 -0.642055 -0.705782 0.183355 -0.68429 -0.705777 0.183356 -0.684295 -0.705776 0.0617442 -0.70574 -0.705777 0.061744 -0.705738 -0.705777 -0.0617441 -0.705738 -0.705775 -0.0617442 -0.70574 -0.705776 -0.183357 -0.684296 -0.705782 -0.183355 -0.68429 -0.705782 -0.299395 -0.642055 -0.705777 -0.299397 -0.64206 -0.705778 -0.406341 -0.580315 -0.705782 -0.406338 -0.580311 -0.705782 -0.500935 -0.500935 -0.705777 -0.500938 -0.500938 -0.705778 -0.580314 -0.406341 -0.705778 -0.580314 -0.406341 -0.705779 -0.642058 -0.299397 -0.705779 -0.642058 -0.299396 -0.705779 -0.684293 -0.183356 -0.705777 -0.684295 -0.183356 -0.705777 -0.705739 -0.0617442 -0.705779 -0.705736 -0.0617439 -0.705594 0.705594 -0.0653829 -0.705595 0.705593 -0.0653828 -0.705594 0.681565 -0.193922 -0.705577 0.681582 -0.193926 -0.705578 0.634342 -0.315864 -0.705591 0.63433 -0.315859 -0.705591 0.56549 -0.427039 -0.705582 0.565498 -0.427044 -0.705583 0.477399 -0.523681 -0.705593 0.477392 -0.523675 -0.705593 0.373039 -0.602479 -0.705595 0.373038 -0.602477 -0.705593 0.255982 -0.660766 -0.705589 0.255983 -0.660769 -0.70559 0.130209 -0.696555 -0.705588 0.130209 -0.696557 -0.705587 0 -0.708623 -0.705587 0 -0.708623 -0.705585 -0.130209 -0.696559 -0.70559 -0.130209 -0.696554 -0.70559 -0.255983 -0.660769 -0.705589 -0.255984 -0.66077 -0.705588 -0.373042 -0.602483 -0.705589 -0.373041 -0.602482 -0.705588 -0.477396 -0.523678 -0.705588 -0.477396 -0.523678 -0.705587 -0.565493 -0.427041 -0.705588 -0.565493 -0.42704 -0.705588 -0.634333 -0.31586 -0.705589 -0.634331 -0.315859 -0.705589 -0.68157 -0.193923 -0.705588 -0.681571 -0.193924 -0.705588 -0.7056 -0.0653834 -0.705587 -0.7056 -0.0653835 -0.705587 0.7056 -0.0653835 -0.705588 0.705599 -0.0653834 -0.705588 0.681571 -0.193924 -0.70559 0.68157 -0.193923 -0.705589 0.634331 -0.315859 -0.705586 0.634334 -0.315861 -0.705586 0.565494 -0.427041 -0.705587 0.565493 -0.427041 -0.705588 0.477396 -0.523678 -0.705584 0.477399 -0.523682 -0.705584 0.373044 -0.602486 -0.705591 0.37304 -0.60248 -0.705591 0.255983 -0.660768 -0.70559 0.255983 -0.660769 -0.70559 0.130209 -0.696555 -0.705588 0.130209 -0.696557 -0.705587 0 -0.708623 -0.705587 0 -0.708623 -0.705588 -0.130209 -0.696557 -0.70559 -0.130209 -0.696555 -0.70559 -0.255983 -0.660769 -0.705589 -0.255984 -0.66077 -0.705588 -0.373041 -0.602483 -0.705588 -0.373042 -0.602483 -0.705588 -0.477396 -0.523678 -0.705583 -0.477399 -0.523681 -0.705582 -0.565497 -0.427044 -0.705589 -0.565492 -0.42704 -0.705589 -0.634331 -0.31586 -0.705578 -0.634342 -0.315864 -0.705577 -0.681582 -0.193926 -0.705594 -0.681565 -0.193922 -0.705595 -0.705593 -0.0653832 -0.705581 -0.705607 -0.0653839 -0.705784 0.705731 -0.0617439 -0.705755 0.70576 -0.0617453 -0.705756 0.684316 -0.183361 -0.705795 0.684278 -0.183352 -0.705794 0.642044 -0.29939 -0.705775 0.642061 -0.299397 -0.705776 0.580316 -0.406342 -0.705773 0.580319 -0.406343 -0.705773 0.500942 -0.500941 -0.705782 0.500935 -0.500935 -0.705782 0.406338 -0.580311 -0.705776 0.406342 -0.580316 -0.705777 0.299397 -0.642059 -0.705775 0.299398 -0.642061 -0.705775 0.183357 -0.684296 -0.705774 0.183357 -0.684298 -0.705774 0.0617445 -0.705741 -0.705777 0.0617441 -0.705738 -0.705777 -0.0617442 -0.705738 -0.705775 -0.0617443 -0.70574 -0.705776 -0.183357 -0.684296 -0.705777 -0.183356 -0.684295 -0.705778 -0.299397 -0.642058 -0.705783 -0.299395 -0.642054 -0.705783 -0.406338 -0.58031 -0.705782 -0.406338 -0.580311 -0.705782 -0.500935 -0.500935 -0.705777 -0.500938 -0.500938 -0.705778 -0.580314 -0.40634 -0.705775 -0.580316 -0.406342 -0.705775 -0.642061 -0.299398 -0.705775 -0.642061 -0.299398 -0.705775 -0.684296 -0.183357 -0.705776 -0.684295 -0.183356 -0.705777 -0.705739 -0.0617442 -0.705777 -0.705738 -0.0617441 -0.694746 0.694746 -0.186158 -0.69475 0.694743 -0.186156 -0.694746 0.508591 -0.50859 -0.694741 0.508594 -0.508594 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694735 -0.18616 -0.694757 -0.694731 -0.508601 -0.5086 -0.694736 -0.508597 -0.508597 -0.694737 -0.694755 -0.18616 -0.694733 -0.694759 -0.18616 -0.694747 0.694747 -0.186155 -0.694738 0.694755 -0.186159 -0.694738 0.508595 -0.508596 -0.694743 0.508592 -0.508592 -0.694742 0.186158 -0.694751 -0.69474 0.186159 -0.694753 -0.69474 -0.186159 -0.694753 -0.694742 -0.186158 -0.694751 -0.694743 -0.508591 -0.508593 -0.694738 -0.508595 -0.508595 -0.694738 -0.694754 -0.18616 -0.694733 -0.694759 -0.18616 -0.694733 0.694759 -0.186161 -0.694738 0.694755 -0.186159 -0.694739 0.508596 -0.508594 -0.694733 0.508599 -0.508599 -0.694738 0.186159 -0.694755 -0.694741 0.186158 -0.694752 -0.694741 -0.186158 -0.694752 -0.694741 -0.186158 -0.694752 -0.694743 -0.508592 -0.508593 -0.694739 -0.508595 -0.508595 -0.694738 -0.694755 -0.186157 -0.694747 -0.694747 -0.186157 -0.694733 0.694759 -0.186161 -0.694738 0.694755 -0.186159 -0.694739 0.508596 -0.508595 -0.694732 0.5086 -0.5086 -0.694737 0.186159 -0.694756 -0.69474 0.186159 -0.694753 -0.69474 -0.186159 -0.694753 -0.69474 -0.186158 -0.694752 -0.694742 -0.508592 -0.508593 -0.694738 -0.508595 -0.508595 -0.694738 -0.694755 -0.186157 -0.694747 -0.694747 -0.186157 -0.694747 0.694747 -0.186155 -0.694738 0.694755 -0.186159 -0.694738 0.508595 -0.508596 -0.694741 0.508594 -0.508594 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694739 -0.186159 -0.694754 -0.694741 -0.508593 -0.508594 -0.694738 -0.508595 -0.508595 -0.694738 -0.694754 -0.18616 -0.694733 -0.694759 -0.18616 -0.694746 0.694746 -0.186158 -0.694752 0.694741 -0.186155 -0.694751 0.508588 -0.508586 -0.694741 0.508594 -0.508594 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694735 -0.18616 -0.694757 -0.694731 -0.508602 -0.508599 -0.694741 -0.508594 -0.508594 -0.694739 -0.694753 -0.18616 -0.694733 -0.694759 -0.18616 -0.69474 0.694753 -0.18616 -0.694745 0.694748 -0.186157 -0.694746 0.508591 -0.50859 -0.694741 0.508594 -0.508594 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694739 -0.186159 -0.694754 -0.694741 -0.508594 -0.508594 -0.694741 -0.508594 -0.508594 -0.694739 -0.694753 -0.18616 -0.694733 -0.694759 -0.18616 -0.69474 0.694753 -0.186158 -0.694738 0.694755 -0.186159 -0.694739 0.508596 -0.508595 -0.694736 0.508597 -0.508597 -0.694737 0.186159 -0.694756 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694739 -0.186159 -0.694754 -0.694741 -0.508593 -0.508594 -0.694738 -0.508595 -0.508595 -0.694738 -0.694755 -0.186159 -0.69474 -0.694753 -0.186159 -0.69474 0.694753 -0.186158 -0.694738 0.694755 -0.186159 -0.694738 0.508596 -0.508595 -0.694737 0.508596 -0.508596 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186159 -0.694753 -0.69474 -0.186158 -0.694752 -0.694742 -0.508593 -0.508593 -0.694743 -0.508592 -0.508592 -0.694745 -0.694748 -0.186158 -0.69474 -0.694753 -0.186159 -0.698067 0.69808 -0.159332 -0.698071 0.698076 -0.15933 -0.698071 0.559814 -0.446436 -0.698066 0.559817 -0.44644 -0.698066 0.310675 -0.645124 -0.698069 0.310674 -0.645121 -0.698067 0 -0.716032 -0.698067 0 -0.716032 -0.698066 -0.310676 -0.645124 -0.698067 -0.310675 -0.645123 -0.698066 -0.559817 -0.44644 -0.698065 -0.559818 -0.44644 -0.698065 -0.698082 -0.159333 -0.698067 -0.69808 -0.159333 -0.69474 0.694753 -0.186158 -0.694738 0.694755 -0.186159 -0.694738 0.508595 -0.508595 -0.694738 0.508595 -0.508595 -0.69474 0.186159 -0.694752 -0.69474 0.186159 -0.694753 -0.69474 -0.186159 -0.694753 -0.694742 -0.186158 -0.694751 -0.694743 -0.508591 -0.508593 -0.694738 -0.508595 -0.508595 -0.694738 -0.694755 -0.186159 -0.69474 -0.694753 -0.186159 -0.69474 0.694753 -0.186159 -0.694744 0.694749 -0.186158 -0.694741 0.508594 -0.508594 -0.694741 0.508594 -0.508594 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694739 -0.186159 -0.694754 -0.694741 -0.508593 -0.508594 -0.694736 -0.508597 -0.508597 -0.694737 -0.694755 -0.18616 -0.694733 -0.694759 -0.18616 0.694733 -0.694759 -0.186161 0.694739 -0.694754 -0.186159 0.694741 -0.508595 -0.508592 0.694731 -0.5086 -0.5086 0.694735 -0.186159 -0.694758 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694741 0.508595 -0.508593 0.694751 0.508587 -0.508587 0.694752 0.694741 -0.186157 0.694747 0.694747 -0.186157 0.694733 -0.694759 -0.186161 0.694738 -0.694755 -0.186159 0.694738 -0.508595 -0.508596 0.694741 -0.508594 -0.508594 0.694739 -0.186159 -0.694754 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694741 0.508593 -0.508594 0.694738 0.508595 -0.508595 0.694738 0.694755 -0.186157 0.694747 0.694747 -0.186157 0.694747 -0.694747 -0.186155 0.694738 -0.694755 -0.186159 0.694738 -0.508595 -0.508596 0.694742 -0.508593 -0.508593 0.69474 -0.186158 -0.694752 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694737 0.186159 -0.694756 0.694732 0.508601 -0.508599 0.694738 0.508595 -0.508595 0.694738 0.694754 -0.18616 0.694733 0.694759 -0.18616 0.694747 -0.694747 -0.186155 0.694738 -0.694755 -0.186159 0.694739 -0.508595 -0.508596 0.694743 -0.508592 -0.508592 0.694741 -0.186158 -0.694752 0.694741 -0.186158 -0.694752 0.694741 0.186158 -0.694752 0.694738 0.186159 -0.694755 0.694733 0.5086 -0.508598 0.694739 0.508595 -0.508595 0.694738 0.694754 -0.18616 0.694733 0.694759 -0.18616 0.694733 -0.694759 -0.186161 0.694738 -0.694755 -0.186159 0.694738 -0.508595 -0.508596 0.694743 -0.508592 -0.508592 0.694742 -0.186158 -0.694751 0.69474 -0.186159 -0.694753 0.69474 0.186159 -0.694753 0.694742 0.186158 -0.694751 0.694743 0.508591 -0.508593 0.694738 0.508595 -0.508595 0.694738 0.694755 -0.186157 0.694747 0.694747 -0.186157 0.694733 -0.694759 -0.186161 0.694737 -0.694756 -0.186159 0.694736 -0.508598 -0.508596 0.694731 -0.5086 -0.5086 0.694735 -0.186159 -0.694758 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694741 0.508595 -0.508593 0.694746 0.50859 -0.50859 0.69475 0.694743 -0.186157 0.694747 0.694747 -0.186157 0.694733 -0.694759 -0.186161 0.694737 -0.694756 -0.186159 0.694736 -0.508597 -0.508598 0.694741 -0.508594 -0.508594 0.694739 -0.186159 -0.694754 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694741 0.508594 -0.508594 0.694741 0.508594 -0.508594 0.694744 0.694749 -0.186158 0.69474 0.694753 -0.186159 0.69474 -0.694753 -0.186158 0.694738 -0.694755 -0.186159 0.694738 -0.508595 -0.508596 0.694743 -0.508592 -0.508592 0.694742 -0.186158 -0.694751 0.69474 -0.186159 -0.694753 0.69474 0.186159 -0.694753 0.69474 0.186158 -0.694752 0.694738 0.508595 -0.508595 0.694738 0.508595 -0.508595 0.694738 0.694755 -0.186159 0.69474 0.694753 -0.186159 0.698067 -0.69808 -0.159332 0.698065 -0.698082 -0.159333 0.698065 -0.559818 -0.446441 0.698066 -0.559817 -0.44644 0.698067 -0.310675 -0.645123 0.698066 -0.310676 -0.645124 0.698067 0 -0.716032 0.698067 0 -0.716032 0.698069 0.310674 -0.645121 0.698067 0.310675 -0.645123 0.698066 0.559818 -0.446439 0.69807 0.559814 -0.446437 0.698072 0.698076 -0.159331 0.698067 0.69808 -0.159331 0.69474 -0.694753 -0.186159 0.694745 -0.694748 -0.186157 0.694743 -0.508592 -0.508592 0.694742 -0.508593 -0.508593 0.69474 -0.186158 -0.694752 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694737 0.508596 -0.508596 0.694738 0.508595 -0.508595 0.694738 0.694755 -0.186159 0.69474 0.694753 -0.186159 0.69474 -0.694753 -0.186158 0.694738 -0.694755 -0.186159 0.694738 -0.508595 -0.508596 0.694741 -0.508594 -0.508594 0.694739 -0.186159 -0.694754 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694737 0.186159 -0.694756 0.694736 0.508597 -0.508597 0.694738 0.508595 -0.508595 0.694738 0.694755 -0.186159 0.69474 0.694753 -0.186159 0.694733 -0.694759 -0.186161 0.694739 -0.694754 -0.186159 0.694741 -0.508594 -0.508594 0.694741 -0.508594 -0.508594 0.694739 -0.186159 -0.694754 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694741 0.508595 -0.508593 0.694746 0.50859 -0.50859 0.694746 0.694747 -0.186158 0.69474 0.694753 -0.186159 0.707101 -0.691437 -0.148064 0.705157 -0.705167 -0.0741161 0.705155 -0.705169 -0.0741161 0.688909 -0.689032 -0.225032 0.705154 -0.674351 -0.21911 0.706817 -0.634241 -0.313286 0.266126 -0.834795 -0.481969 0.706359 -0.598406 -0.37811 0.705158 -0.526927 -0.474447 0.705153 -0.526931 -0.474451 0.705153 -0.416772 -0.573638 0.705157 -0.41677 -0.573635 0.705157 -0.288397 -0.64775 0.705155 -0.288398 -0.647753 0.705155 -0.14742 -0.693559 0.705154 -0.147421 -0.69356 0.705154 0 -0.709054 0.705154 0 -0.709054 0.705154 0.147421 -0.69356 0.705154 0.147421 -0.69356 0.705153 0.288399 -0.647754 0.705159 0.288397 -0.647749 0.705159 0.416768 -0.573633 0.705156 0.41677 -0.573636 0.705156 0.526928 -0.474448 0.705161 0.526925 -0.474445 0.705162 0.614052 -0.354523 0.705162 0.614052 -0.354523 0.705162 0.674343 -0.219107 0.705152 0.674352 -0.219111 0.705152 0.705172 -0.0741164 0.705153 0.705171 -0.0741163 -0.705153 0.705171 -0.0741163 -0.705162 0.614052 -0.354523 -0.706888 0.655888 -0.264802 -0.300701 0.90704 -0.294715 -0.706241 0.680596 -0.194971 -0.705152 0.705172 -0.0741164 -0.705156 0.416771 -0.573636 -0.707021 0.484249 -0.515387 -0.633307 0.546921 -0.547539 -0.587887 0.577781 -0.566179 -0.329727 0.701585 -0.631711 -0.706168 0.541029 -0.456743 -0.705162 0.614052 -0.354523 -0.268066 0.39185 -0.88011 -0.672244 0.339068 -0.658119 -0.707092 0.348496 -0.615282 -0.705159 0.416768 -0.573633 -0.707018 -0.484251 -0.515389 -0.705153 -0.416772 -0.573638 -0.705157 -0.41677 -0.573634 -0.705157 -0.288397 -0.64775 -0.705155 -0.288398 -0.647753 -0.705155 -0.14742 -0.693559 -0.705154 -0.147421 -0.69356 -0.705154 0 -0.709054 -0.705154 0 -0.709054 -0.705154 0.147421 -0.69356 -0.705154 0.147421 -0.69356 -0.707047 0.229957 -0.668734 -0.567028 0.317962 -0.759855 -0.511605 -0.644893 -0.567779 -0.342804 -0.698115 -0.628586 -0.632101 -0.547784 -0.54807 -0.65733 -0.527718 -0.537988 -0.707036 -0.563933 -0.426707 -0.705158 -0.614056 -0.354525 -0.705154 -0.614059 -0.354527 -0.70688 -0.655896 -0.264804 -0.300696 -0.907042 -0.294716 -0.706245 -0.680592 -0.194969 -0.705157 -0.705167 -0.074116 -0.705155 -0.705169 -0.0741162 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965925 -0.25882 0 0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.258817 0 0.965926 -0.258817 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.781831 -0.62349 0 -0.781831 -0.62349 0 -0.433884 -0.900969 0 -0.433884 -0.900969 0 0 -1 0 0 -1 0 0.433883 -0.900969 0 0.433883 -0.900969 0 0.781832 -0.623489 0 0.781832 -0.623489 0 0.974928 -0.222521 0 0.974928 -0.222521 0 -0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965925 -0.258821 0 0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965925 -0.258821 0 0.965925 -0.258821 0 -0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258817 0 0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965925 -0.25882 0 0.965925 -0.25882 0.694745 0.694747 -0.186158 0.694745 0.694747 -0.186158 0.694745 0.508591 -0.508591 0.694745 0.508591 -0.50859 0.694746 0.186157 -0.694748 0.694746 0.186158 -0.694747 0.694746 -0.186157 -0.694748 0.694745 -0.186156 -0.694748 0.694745 -0.508591 -0.508591 0.694746 -0.508591 -0.50859 0.700225 -0.675998 -0.229592 0.711388 -0.678852 -0.181899 0.706344 -0.706346 -0.0464134 0 -0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965925 -0.25882 0 0.965925 -0.25882 0.694745 -0.694747 -0.186158 0.694746 -0.694747 -0.186156 0.694746 -0.508591 -0.508589 0.694746 -0.508591 -0.50859 0.694746 -0.186157 -0.694748 0.694746 -0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694746 0.508592 -0.508589 0.694746 0.50859 -0.50859 0.694746 0.694747 -0.186158 0.694746 0.694748 -0.186156 0 -0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.965925 -0.25882 0 0.965925 -0.25882 0.694745 -0.694747 -0.186158 0.694745 -0.694747 -0.186158 0.694746 -0.508592 -0.508589 0.694745 -0.508591 -0.508591 0.694745 -0.186156 -0.694748 0.694746 -0.186157 -0.694748 0.694746 0.186156 -0.694748 0.694745 0.186157 -0.694748 0.694746 0.508589 -0.508591 0.694745 0.508591 -0.508591 0.694745 0.694749 -0.186154 0.694746 0.694748 -0.186156 0 -0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965927 -0.258814 0 0.965927 -0.258814 0.694746 -0.694748 -0.186156 0.694745 -0.694748 -0.186157 0.694745 -0.50859 -0.508591 0.694746 -0.508591 -0.50859 0.694746 -0.186157 -0.694747 0.694746 -0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694746 0.186157 -0.694747 0.694746 0.508591 -0.50859 0.694746 0.508591 -0.50859 0.694746 0.694747 -0.186158 0.694746 0.694748 -0.186157 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965925 -0.25882 0 0.965925 -0.25882 0.694745 -0.694747 -0.186158 0.694746 -0.694747 -0.186157 0.694746 -0.508591 -0.50859 0.694746 -0.508591 -0.50859 0.694746 -0.186157 -0.694748 0.694746 -0.186157 -0.694748 0.694746 0.186156 -0.694748 0.694745 0.186157 -0.694748 0.694745 0.508591 -0.50859 0.694746 0.50859 -0.508591 0.694746 0.694747 -0.186158 0.694746 0.694748 -0.186157 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965926 -0.25882 0 0.965926 -0.25882 0.694746 -0.694748 -0.186156 0.694745 -0.694748 -0.186157 0.694745 -0.50859 -0.508591 0.694746 -0.508591 -0.508591 0.694745 -0.186157 -0.694748 0.694746 -0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694745 0.508591 -0.50859 0.694746 0.50859 -0.50859 0.694746 0.694747 -0.186158 0.694746 0.694748 -0.186157 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965925 -0.25882 0 0.965925 -0.25882 0.694745 -0.694747 -0.186158 0.694745 -0.694747 -0.186158 0.694746 -0.508592 -0.508589 0.694745 -0.508591 -0.508591 0.694745 -0.186156 -0.694748 0.694746 -0.186157 -0.694748 0.694746 0.186156 -0.694748 0.694745 0.186157 -0.694748 0.694746 0.508589 -0.508591 0.694745 0.508591 -0.508591 0.694745 0.694749 -0.186154 0.694746 0.694748 -0.186156 0 -0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965927 -0.258814 0 0.965927 -0.258814 0.694745 -0.694747 -0.186158 0.694746 -0.694747 -0.186156 0.694746 -0.508591 -0.508589 0.694746 -0.508591 -0.50859 0.694746 -0.186158 -0.694747 0.694746 -0.186157 -0.694748 0.694745 0.186158 -0.694747 0.694746 0.186157 -0.694747 0.694746 0.508592 -0.508589 0.694746 0.508591 -0.50859 0.694746 0.694746 -0.186158 0.694746 0.694748 -0.186156 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.25882 -0.965925 0 -0.25882 -0.965925 0 0.25882 -0.965925 0 0.25882 -0.965925 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.965925 -0.258821 0 0.965925 -0.258821 0.698072 -0.698074 -0.159335 0.698073 -0.698074 -0.159332 0.698073 -0.559814 -0.446434 0.698073 -0.559813 -0.446435 0.698073 -0.310672 -0.645118 0.698073 -0.310672 -0.645118 0.698073 0 -0.716027 0.698073 0 -0.716027 0.698073 0.310672 -0.645118 0.698073 0.310673 -0.645118 0.698072 0.559814 -0.446434 0.698073 0.559813 -0.446435 0.698073 0.698073 -0.159335 0.698073 0.698074 -0.159333 0 -0.974927 -0.222527 0 -0.974927 -0.222527 0 -0.781833 -0.623487 0 -0.781833 -0.623487 0 -0.433883 -0.900969 0 -0.433883 -0.900969 0 0 -1 0 0 -1 0 0.433883 -0.900969 0 0.433883 -0.900969 0 0.781833 -0.623487 0 0.781833 -0.623487 0 0.974927 -0.222527 0 0.974927 -0.222527 -0.980541 0.0294405 -0.194094 -0.980398 0.196079 -0.0193121 -0.980398 0.196079 -0.0193121 -0.980398 0.173763 -0.0928783 -0.979269 0.17738 -0.0978183 -0.980578 0.180205 -0.0774211 -0.980398 0.188544 -0.0571942 -0.979846 0.190769 -0.0592355 -0.98058 0.192097 -0.0395192 -0.980398 0.124993 -0.152305 -0.978034 0.127975 -0.164538 -0.980568 0.135042 -0.142304 -0.980398 0.152305 -0.124993 -0.978665 0.156233 -0.133436 -0.980573 0.160924 -0.112157 -0.980398 0.0571942 -0.188544 -0.976678 0.0542128 -0.207754 -0.980552 0.0679293 -0.184131 -0.980398 0.0928783 -0.173763 -0.977372 0.0935572 -0.189715 -0.980561 0.103616 -0.166628 -0.97595 0.0114091 -0.217697 -0.980398 0.0193121 -0.196079 -0.980529 -0.0102775 -0.196105 -0.978323 -0.0202979 -0.206088 -0.980541 -0.0294404 -0.194094 -0.980515 -0.0496004 -0.190078 -0.978403 -0.0600043 -0.197808 -0.980552 -0.0679293 -0.184131 -0.9805 -0.0869187 -0.176254 -0.978561 -0.0970884 -0.18164 -0.980561 -0.103616 -0.166628 -0.980483 -0.120704 -0.155191 -0.978794 -0.129952 -0.158347 -0.980568 -0.135042 -0.142305 -0.980464 -0.149571 -0.127746 -0.9791 -0.157213 -0.129022 -0.980573 -0.160924 -0.112157 -0.980444 -0.172333 -0.0950349 -0.979473 -0.177772 -0.0950212 -0.980578 -0.180204 -0.0774216 -0.980422 -0.188053 -0.058392 -0.979908 -0.190862 -0.0578973 -0.98058 -0.192097 -0.0395193 -0.980398 -0.196079 -0.0193121 -0.980398 -0.196079 -0.0193121 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.995734 -0.092269 0 -0.995734 -0.092269 0 -0.961826 -0.273662 0 -0.961826 -0.273662 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.18375 -0.982973 0 -0.18375 -0.982973 0 0 -1 0 0 -1 0 0.18375 -0.982973 0 0.18375 -0.982973 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.961826 -0.273663 0 0.961826 -0.273663 0 0.995734 -0.0922684 0 0.995734 -0.0922684 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.995734 -0.0922684 0 0.995734 -0.0922684 0 0.961825 -0.273664 0 0.961825 -0.273664 0 0.895164 -0.445738 0 0.895164 -0.445738 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.361241 -0.932472 0 0.361241 -0.932472 0 0.183749 -0.982973 0 0.183749 -0.982973 0 0 -1 0 0 -1 0 -0.183749 -0.982973 0 -0.183749 -0.982973 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.995734 -0.0922684 0 -0.995734 -0.0922684 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.995734 -0.0922693 0 -0.995734 -0.0922693 0 -0.961826 -0.273662 0 -0.961826 -0.273662 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.183749 -0.982973 0 -0.183749 -0.982973 0 0 -1 0 0 -1 0 0.183749 -0.982973 0 0.183749 -0.982973 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.961826 -0.273663 0 0.961826 -0.273663 0 0.995734 -0.0922684 0 0.995734 -0.0922684 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.995734 -0.0922688 0 -0.995734 -0.0922688 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.18375 -0.982973 0 -0.18375 -0.982973 0 0 -1 0 0 -1 0 0.18375 -0.982973 0 0.18375 -0.982973 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.961826 -0.273663 0 0.961826 -0.273663 0 0.995734 -0.0922685 0 0.995734 -0.0922685 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.996195 -0.0871568 0 0.996195 -0.0871568 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.906308 -0.422618 0 0.906308 -0.422618 0 0.819152 -0.573576 0 0.819152 -0.573576 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.573576 -0.819152 0 0.573576 -0.819152 0 0.422619 -0.906308 0 0.422619 -0.906308 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.0871557 -0.996195 0 0.0871557 -0.996195 0 -0.0871557 -0.996195 0 -0.0871557 -0.996195 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.422618 -0.906308 0 -0.422618 -0.906308 0 -0.573576 -0.819152 0 -0.573576 -0.819152 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.819152 -0.573576 0 -0.819152 -0.573576 0 -0.906308 -0.422618 0 -0.906308 -0.422618 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.996195 -0.0871558 0 -0.996195 -0.0871558 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.996195 -0.0871563 0 0.996195 -0.0871563 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.906308 -0.422619 0 0.906308 -0.422619 0 0.819152 -0.573577 0 0.819152 -0.573577 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.573576 -0.819152 0 0.573576 -0.819152 0 0.422618 -0.906308 0 0.422618 -0.906308 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.087156 -0.996195 0 0.087156 -0.996195 0 -0.0871559 -0.996195 0 -0.0871559 -0.996195 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.422618 -0.906308 0 -0.422618 -0.906308 0 -0.573576 -0.819152 0 -0.573576 -0.819152 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.819152 -0.573576 0 -0.819152 -0.573576 0 -0.906308 -0.422618 0 -0.906308 -0.422618 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.996195 -0.0871558 0 -0.996195 -0.0871558 0.80997 -0.584239 -0.0511143 0.80997 -0.584239 -0.0511143 0.80997 -0.566487 -0.15179 0.80997 -0.566487 -0.15179 0.80997 -0.531523 -0.247853 0.80997 -0.531523 -0.247853 0.80997 -0.480409 -0.336386 0.80997 -0.480409 -0.336386 0.80997 -0.414697 -0.414697 0.809971 -0.414697 -0.414697 0.809971 -0.336386 -0.480409 0.809971 -0.336386 -0.480409 0.809971 -0.247853 -0.531523 0.809971 -0.247853 -0.531523 0.809971 -0.15179 -0.566487 0.809971 -0.15179 -0.566487 0.80997 -0.0511144 -0.584239 0.809971 -0.0511142 -0.584239 0.809971 0.0511144 -0.584239 0.80997 0.0511143 -0.584239 0.80997 0.15179 -0.566487 0.809971 0.15179 -0.566487 0.809971 0.247853 -0.531523 0.809971 0.247853 -0.531523 0.809971 0.336386 -0.480409 0.80997 0.336386 -0.480409 0.80997 0.414698 -0.414697 0.80997 0.414698 -0.414697 0.80997 0.480409 -0.336386 0.809971 0.480409 -0.336386 0.809971 0.531523 -0.247853 0.809971 0.531522 -0.247853 0.809971 0.566487 -0.151789 0.80997 0.566488 -0.15179 0.80997 0.58424 -0.0511147 0.80997 0.584239 -0.0511143 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.994522 -0.104528 0 0.994522 -0.104528 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.866025 -0.5 0 0.866025 -0.5 0 0.743145 -0.669131 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.406736 -0.913546 0 0.406736 -0.913546 0 0.207912 -0.978148 0 0.207912 -0.978148 0 0 -1 0 0 -1 0 -0.207912 -0.978148 0 -0.207912 -0.978148 0 -0.406736 -0.913546 0 -0.406736 -0.913546 0 -0.587785 -0.809017 0 -0.587785 -0.809017 0 -0.743145 -0.669131 0 -0.743145 -0.669131 0 -0.866025 -0.5 0 -0.866025 -0.5 0 -0.951056 -0.309017 0 -0.951056 -0.309017 0 -0.994522 -0.104528 0 -0.994522 -0.104528 0 0.994522 -0.104528 -0.142211 0.98507 -0.0970208 0 0.979487 -0.201506 0 0.951057 -0.309017 -0.27615 0.917884 -0.28501 0 0.918793 -0.39474 0 0.875675 -0.482901 -0.330673 0.817307 -0.471873 -0.443096 0.526934 -0.725263 0 0.820403 -0.571786 0 0.760406 -0.649448 -0.396042 0.682379 -0.614417 0 0.688355 -0.725374 0 0.613941 -0.789352 -0.492719 0.180922 -0.851173 0 0.528067 -0.849203 0 0.442289 -0.896873 -0.474628 0.358004 -0.804091 0 0.346116 -0.938192 0 0.252492 -0.967599 0 0.149966 -0.988691 0 0.0523362 -0.99863 -0.498611 0 -0.866826 0 -0.0523362 -0.99863 0 -0.149966 -0.988691 -0.492721 -0.180922 -0.851172 0 -0.252492 -0.967599 0 -0.346117 -0.938191 -0.474625 -0.358004 -0.804092 0 -0.442289 -0.896873 0 -0.528068 -0.849202 -0.443093 -0.526935 -0.725264 0 -0.613941 -0.789352 0 -0.688354 -0.725375 -0.396047 -0.682378 -0.614416 0 -0.760406 -0.649448 0 -0.820402 -0.571787 -0.33068 -0.817305 -0.471871 0 -0.875675 -0.4829 0 -0.918792 -0.394743 -0.243925 -0.922329 -0.299683 0 -0.995185 -0.098017 -0.133515 -0.985618 -0.103592 0 -0.979487 -0.201506 0 -0.95502 -0.296542 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.994522 0.104528 -0.142211 -0.98507 0.0970208 0 -0.979487 0.201506 0 -0.951056 0.309017 -0.276157 -0.917881 0.28501 0 -0.918792 0.394743 0 -0.875675 0.4829 -0.33068 -0.817305 0.471871 -0.443094 -0.526935 0.725264 0 -0.820402 0.571787 0 -0.760406 0.649448 -0.396048 -0.682378 0.614416 0 -0.688354 0.725375 0 -0.613941 0.789352 -0.492721 -0.180922 0.851172 0 -0.528068 0.849202 0 -0.442289 0.896873 -0.474625 -0.358005 0.804092 0 -0.346117 0.938191 0 -0.252492 0.967599 0 -0.149966 0.988691 0 -0.0523362 0.99863 -0.498611 0 0.866826 0 0.0523362 0.99863 0 0.149966 0.988691 -0.492719 0.180922 0.851173 0 0.252492 0.967599 0 0.346116 0.938192 -0.474628 0.358004 0.80409 0 0.442289 0.896873 0 0.528067 0.849203 -0.443096 0.526934 0.725263 0 0.613941 0.789352 0 0.688355 0.725374 -0.396042 0.68238 0.614418 0 0.760406 0.649448 0 0.820403 0.571786 -0.330674 0.817307 0.471873 0 0.875675 0.482901 0 0.918793 0.39474 -0.243918 0.922331 0.299683 0 0.995185 0.098017 -0.133515 0.985618 0.103592 0 0.979487 0.201506 0 0.95502 0.296542 0 -0.994522 0.104528 0 -0.994522 0.104528 0 -0.951056 0.309017 0 -0.951056 0.309017 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.743145 0.669131 0 -0.743145 0.669131 0 -0.587785 0.809017 0 -0.587785 0.809017 0 -0.406736 0.913546 0 -0.406736 0.913546 0 -0.207912 0.978148 0 -0.207912 0.978148 0 0 1 0 0 1 0 0.207912 0.978148 0 0.207912 0.978148 0 0.406736 0.913546 0 0.406736 0.913546 0 0.587785 0.809017 0 0.587785 0.809017 0 0.743145 0.669131 0 0.743145 0.669131 0 0.866025 0.5 0 0.866025 0.5 0 0.951057 0.309017 0 0.951057 0.309017 0 0.994522 0.104528 0 0.994522 0.104528 0.80997 0.584239 0.0511146 0.80997 0.58424 0.0511143 0.80997 0.566488 0.151789 0.809971 0.566487 0.15179 0.809971 0.531522 0.247853 0.809971 0.531523 0.247853 0.809971 0.480408 0.336386 0.80997 0.480409 0.336386 0.80997 0.414698 0.414697 0.80997 0.414698 0.414697 0.80997 0.336386 0.480409 0.809971 0.336385 0.480409 0.809971 0.247853 0.531523 0.809971 0.247853 0.531523 0.809971 0.15179 0.566487 0.80997 0.15179 0.566487 0.80997 0.0511144 0.584239 0.809971 0.0511142 0.584239 0.809971 -0.0511144 0.584239 0.80997 -0.0511143 0.584239 0.809971 -0.15179 0.566487 0.809971 -0.15179 0.566487 0.809971 -0.247853 0.531523 0.809971 -0.247853 0.531523 0.809971 -0.336386 0.480409 0.809971 -0.336386 0.480409 0.809971 -0.414697 0.414697 0.80997 -0.414697 0.414697 0.80997 -0.480409 0.336386 0.80997 -0.480409 0.336386 0.80997 -0.531523 0.247853 0.80997 -0.531523 0.247853 0.80997 -0.566487 0.15179 0.80997 -0.566487 0.15179 0.80997 -0.584239 0.0511143 0.80997 -0.584239 0.0511143 0 -0.996195 0.0871558 0 -0.996195 0.0871558 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.906308 0.422618 0 -0.906308 0.422618 0 -0.819152 0.573576 0 -0.819152 0.573576 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.573576 0.819152 0 -0.573576 0.819152 0 -0.422618 0.906308 0 -0.422618 0.906308 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.0871559 0.996195 0 -0.0871559 0.996195 0 0.087156 0.996195 0 0.087156 0.996195 0 0.258819 0.965926 0 0.258819 0.965926 0 0.422618 0.906308 0 0.422618 0.906308 0 0.573576 0.819152 0 0.573576 0.819152 0 0.707107 0.707107 0 0.707107 0.707107 0 0.819152 0.573577 0 0.819152 0.573577 0 0.906308 0.422619 0 0.906308 0.422619 0 0.965926 0.258818 0 0.965926 0.258818 0 0.996195 0.0871563 0 0.996195 0.0871563 0 -0.996195 0.0871558 0 -0.996195 0.0871558 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.906308 0.422618 0 -0.906308 0.422618 0 -0.819152 0.573576 0 -0.819152 0.573576 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.573576 0.819152 0 -0.573576 0.819152 0 -0.422618 0.906308 0 -0.422618 0.906308 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.0871557 0.996195 0 -0.0871557 0.996195 0 0.0871557 0.996195 0 0.0871557 0.996195 0 0.258819 0.965926 0 0.258819 0.965926 0 0.422619 0.906308 0 0.422619 0.906308 0 0.573576 0.819152 0 0.573576 0.819152 0 0.707107 0.707107 0 0.707107 0.707107 0 0.819152 0.573576 0 0.819152 0.573576 0 0.906308 0.422618 0 0.906308 0.422618 0 0.965926 0.258819 0 0.965926 0.258819 0 0.996195 0.0871568 0 0.996195 0.0871568 0 0.995734 0.0922685 0 0.995734 0.0922685 0 0.961826 0.273663 0 0.961826 0.273663 0 0.895163 0.445738 0 0.895163 0.445738 0 0.798017 0.602635 0 0.798017 0.602635 0 0.673696 0.739009 0 0.673696 0.739009 0 0.526432 0.850217 0 0.526432 0.850217 0 0.361242 0.932472 0 0.361242 0.932472 0 0.18375 0.982973 0 0.18375 0.982973 0 0 1 0 0 1 0 -0.18375 0.982973 0 -0.18375 0.982973 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.995734 0.0922688 0 -0.995734 0.0922688 0 0.995734 0.0922684 0 0.995734 0.0922684 0 0.961826 0.273663 0 0.961826 0.273663 0 0.895163 0.445738 0 0.895163 0.445738 0 0.798017 0.602635 0 0.798017 0.602635 0 0.673696 0.739009 0 0.673696 0.739009 0 0.526432 0.850217 0 0.526432 0.850217 0 0.361242 0.932472 0 0.361242 0.932472 0 0.183749 0.982973 0 0.183749 0.982973 0 0 1 0 0 1 0 -0.183749 0.982973 0 -0.183749 0.982973 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.961826 0.273662 0 -0.961826 0.273662 0 -0.995734 0.0922693 0 -0.995734 0.0922693 0 -0.995734 0.0922684 0 -0.995734 0.0922684 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.183749 0.982973 0 -0.183749 0.982973 0 0 1 0 0 1 0 0.183749 0.982973 0 0.183749 0.982973 0 0.361241 0.932472 0 0.361241 0.932472 0 0.526432 0.850217 0 0.526432 0.850217 0 0.673696 0.739009 0 0.673696 0.739009 0 0.798017 0.602635 0 0.798017 0.602635 0 0.895164 0.445738 0 0.895164 0.445738 0 0.961825 0.273664 0 0.961825 0.273664 0 0.995734 0.0922684 0 0.995734 0.0922684 0 0.995734 0.0922684 0 0.995734 0.0922684 0 0.961826 0.273663 0 0.961826 0.273663 0 0.895163 0.445738 0 0.895163 0.445738 0 0.798017 0.602635 0 0.798017 0.602635 0 0.673696 0.739009 0 0.673696 0.739009 0 0.526432 0.850217 0 0.526432 0.850217 0 0.361242 0.932472 0 0.361242 0.932472 0 0.18375 0.982973 0 0.18375 0.982973 0 0 1 0 0 1 0 -0.18375 0.982973 0 -0.18375 0.982973 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.961826 0.273662 0 -0.961826 0.273662 0 -0.995734 0.092269 0 -0.995734 0.092269 -0.980541 -0.0294404 0.194094 -0.980398 -0.196079 0.0193121 -0.980398 -0.196079 0.0193121 -0.980398 -0.173763 0.0928783 -0.979269 -0.17738 0.0978181 -0.980578 -0.180204 0.0774216 -0.980398 -0.188544 0.0571942 -0.979846 -0.190769 0.0592355 -0.98058 -0.192097 0.0395192 -0.980398 -0.124993 0.152305 -0.978034 -0.127974 0.164538 -0.980568 -0.135042 0.142304 -0.980398 -0.152305 0.124993 -0.978665 -0.156233 0.133436 -0.980573 -0.160924 0.112157 -0.980398 -0.0571942 0.188544 -0.976678 -0.0542128 0.207754 -0.980552 -0.0679293 0.184131 -0.980398 -0.0928784 0.173763 -0.977372 -0.0935572 0.189715 -0.980561 -0.103616 0.166628 -0.97595 -0.0114091 0.217697 -0.980398 -0.0193121 0.196079 -0.980529 0.0102775 0.196105 -0.978323 0.0202979 0.206088 -0.980541 0.0294405 0.194094 -0.980515 0.0496004 0.190079 -0.978403 0.0600043 0.197808 -0.980552 0.0679293 0.184131 -0.9805 0.0869188 0.176254 -0.978561 0.0970885 0.18164 -0.98056 0.103616 0.166628 -0.980483 0.120704 0.155191 -0.978794 0.129952 0.158347 -0.980568 0.135042 0.142304 -0.980464 0.149571 0.127746 -0.9791 0.157214 0.129022 -0.980573 0.160924 0.112157 -0.980444 0.172333 0.095035 -0.979473 0.177772 0.0950213 -0.980578 0.180205 0.0774211 -0.980422 0.188053 0.058392 -0.979908 0.190862 0.0578973 -0.98058 0.192097 0.0395193 -0.980398 0.196079 0.0193121 -0.980398 0.196079 0.0193121 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965925 0.25882 0 -0.965925 0.25882 0.694745 0.694747 0.186158 0.694745 0.694747 0.186158 0.694746 0.508591 0.50859 0.694745 0.508591 0.508591 0.694746 0.186157 0.694747 0.694746 0.186157 0.694748 0.694746 -0.186156 0.694748 0.694745 -0.186157 0.694748 0.694745 -0.508591 0.50859 0.694745 -0.508591 0.508591 0.694745 -0.694747 0.186158 0.694745 -0.694747 0.186158 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.25882 0 -0.965926 0.25882 0.704846 -0.704848 0.0798916 0.71628 -0.674035 0.180608 0.694745 0.694747 0.186158 0.694746 0.694747 0.186156 0.694746 0.508591 0.50859 0.694746 0.50859 0.50859 0.694746 0.186157 0.694748 0.694746 0.186157 0.694748 0.694746 -0.186157 0.694748 0.694746 -0.186157 0.694748 0.694746 -0.508591 0.50859 0.694746 -0.50859 0.50859 0.70316 -0.661708 0.26021 0 0.965927 0.258814 0 0.965927 0.258814 0 0.707105 0.707108 0 0.707105 0.707108 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.965925 0.25882 0 -0.965925 0.25882 0.694746 0.694748 0.186153 0.694745 0.694748 0.186156 0.694745 0.50859 0.508592 0.694746 0.508591 0.50859 0.694745 0.186156 0.694748 0.694746 0.186157 0.694747 0.694746 -0.186156 0.694747 0.694745 -0.186157 0.694748 0.694745 -0.508592 0.50859 0.694745 -0.508591 0.50859 0.694745 -0.694747 0.186158 0.694745 -0.694747 0.186158 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258817 0 -0.965926 0.258817 0.694745 0.694747 0.186158 0.694746 0.694747 0.186157 0.694746 0.508591 0.50859 0.694746 0.508591 0.50859 0.694746 0.186157 0.694747 0.694746 0.186157 0.694748 0.694746 -0.186157 0.694748 0.694746 -0.186157 0.694747 0.694746 -0.50859 0.508591 0.694745 -0.508591 0.508591 0.694745 -0.694748 0.186156 0.694746 -0.694748 0.186157 0 0.974927 0.222523 0 0.974927 0.222523 0 0.781832 0.623489 0 0.781832 0.623489 0 0.433883 0.900969 0 0.433883 0.900969 0 0 1 0 0 1 0 -0.433883 0.900969 0 -0.433883 0.900969 0 -0.781832 0.623489 0 -0.781832 0.623489 0 -0.974927 0.222523 0 -0.974927 0.222523 0.698072 0.698074 0.159332 0.698073 0.698074 0.159331 0.698073 0.559813 0.446435 0.698073 0.559812 0.446435 0.698073 0.310672 0.645118 0.698073 0.310672 0.645118 0.698073 0 0.716027 0.698073 0 0.716027 0.698073 -0.310672 0.645118 0.698073 -0.310673 0.645118 0.698073 -0.559813 0.446435 0.698073 -0.559812 0.446435 0.698073 -0.698074 0.159332 0.698073 -0.698075 0.159331 0 0.974928 0.222519 0.1017 0.960917 0.257478 0 0.884107 0.467285 0 0.707108 0.707106 0.231189 0.737438 0.634615 0 0.56332 0.826239 0 0.258819 0.965926 0.335402 0.344179 0.876953 0 0.111964 0.993712 0 -0.111964 0.993712 0.200841 -0.253545 0.946244 0 -0.365341 0.930874 0 -0.563314 0.826243 0.168261 -0.697024 0.697026 0 -0.974928 0.222519 0.101691 -0.960919 0.257476 0 -0.884116 0.467267 0 -0.757973 0.652286 0.698073 -0.698075 0.15933 0.698073 -0.698075 0.15933 0.706859 -0.625384 0.330523 0.693897 -0.562977 0.448959 0.700861 -0.540661 0.465275 0.706115 -0.398881 0.58506 0.691347 -0.313491 0.65097 0.703124 -0.259782 0.661914 0.704872 -0.0794201 0.704874 0.69049 0 0.723342 0.704872 0.0794201 0.704874 0.698073 0.310673 0.645118 0.680457 0.267717 0.682133 0.706115 0.398885 0.585058 0.698073 0.559812 0.446436 0.698073 0.698075 0.15933 0.698072 0.698075 0.159331 0.706858 0.625378 0.330537 0.689671 0.548865 0.472335 0 0.965927 0.258814 0 0.965927 0.258814 0 0.707105 0.707108 0 0.707105 0.707108 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.965925 0.25882 0 -0.965925 0.25882 0.694746 0.694748 0.186153 0.694745 0.694748 0.186156 0.694745 0.50859 0.508592 0.694746 0.50859 0.50859 0.694745 0.186156 0.694748 0.694746 0.186157 0.694748 0.694746 -0.186156 0.694748 0.694745 -0.186157 0.694748 0.694745 -0.508592 0.50859 0.694745 -0.508591 0.508591 0.694745 -0.694747 0.186158 0.694745 -0.694747 0.186158 0 0.965925 0.258821 0 0.965925 0.258821 0 0.707108 0.707105 0 0.707108 0.707105 0 0.25882 0.965925 0 0.25882 0.965925 0 -0.25882 0.965925 0 -0.25882 0.965925 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.965925 0.258821 0 -0.965925 0.258821 0.694745 0.694747 0.186158 0.694746 0.694747 0.186156 0.694746 0.508591 0.508589 0.694746 0.508591 0.50859 0.694746 0.186158 0.694747 0.694746 0.186157 0.694748 0.694745 -0.186158 0.694747 0.694746 -0.186157 0.694747 0.694746 -0.508592 0.508589 0.694746 -0.508591 0.50859 0.694746 -0.694746 0.186158 0.694746 -0.694748 0.186156 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965925 0.25882 0 -0.965925 0.25882 0.694745 0.694747 0.186158 0.694745 0.694747 0.186158 0.694745 0.508591 0.50859 0.694745 0.508591 0.508591 0.694745 0.186157 0.694748 0.694746 0.186157 0.694748 0.694746 -0.186156 0.694748 0.694745 -0.186157 0.694748 0.694745 -0.508591 0.50859 0.694745 -0.508591 0.508591 0.694745 -0.694747 0.186158 0.694745 -0.694747 0.186158 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258817 0 -0.965926 0.258817 0 0.974928 0.222521 0 0.974928 0.222521 0 0.781833 0.623487 0 0.781833 0.623487 0 0.433882 0.90097 0 0.433882 0.90097 0 0 1 0 0 1 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.781831 0.62349 0 -0.781831 0.62349 0 -0.974928 0.222521 0 -0.974928 0.222521 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.25882 0 -0.965926 0.25882 0 0.974928 0.222521 0 0.974928 0.222521 0 0.781831 0.623491 0 0.781831 0.623491 0 0.433884 0.900969 0 0.433884 0.900969 0 0 1 0 0 1 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.781831 0.623491 0 -0.781831 0.623491 0 -0.974928 0.222521 0 -0.974928 0.222521 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965925 0.25882 0 -0.965925 0.25882 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965925 0.25882 0 -0.965925 0.25882 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707106 0 0.707107 0.707106 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.965925 0.258821 0 0.965925 0.258821 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965925 0.258821 0 -0.965925 0.258821 0 0.965925 0.258821 0 0.965925 0.258821 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965925 0.258821 0 -0.965925 0.258821 0 0.965926 0.258817 0 0.965926 0.258817 0 0.707106 0.707107 0 0.707106 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965925 0.25882 0 -0.965925 0.25882 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258817 0 -0.965926 0.258817 -0.705157 -0.674348 0.219109 -0.705157 -0.705167 0.0741161 -0.705155 -0.705169 0.0741161 -0.707036 -0.563933 0.426707 -0.70569 -0.608055 0.36369 -0.521922 -0.738714 0.426497 -0.707058 -0.641502 0.297564 -0.705155 -0.67435 0.21911 -0.511605 -0.644893 0.567779 -0.342803 -0.698115 0.628586 -0.632101 -0.547784 0.54807 -0.705154 0.147421 0.69356 -0.705154 0 0.709054 -0.705154 0 0.709054 -0.705154 -0.147421 0.69356 -0.705155 -0.14742 0.693559 -0.705155 -0.288398 0.647753 -0.705157 -0.288397 0.64775 -0.705157 -0.41677 0.573635 -0.705155 -0.416771 0.573636 -0.70702 -0.484249 0.515389 -0.65733 -0.527718 0.537988 -0.705159 0.416768 0.573633 -0.705742 0.299148 0.642214 -0.501517 0.351887 0.790352 -0.707047 0.229957 0.668734 -0.705154 0.147421 0.69356 -0.633307 0.546921 0.547539 -0.707023 0.484247 0.515386 -0.705158 0.416769 0.573634 -0.587888 0.577781 0.566177 -0.329727 0.701585 0.63171 -0.706168 0.54103 0.456743 -0.705162 0.614052 0.354523 -0.705163 0.614052 0.354523 -0.706889 0.655887 0.264802 -0.300701 0.90704 0.294715 -0.706241 0.680596 0.194971 -0.705152 0.705172 0.0741164 -0.705153 0.705171 0.0741163 0.705153 0.705171 0.0741163 0.705152 0.705172 0.0741164 0.705152 0.674352 0.21911 0.705163 0.674342 0.219107 0.705163 0.614052 0.354523 0.705162 0.614052 0.354523 0.706056 0.539182 0.459095 0.373125 0.689476 0.620807 0.628681 0.549914 0.549867 0.705159 0.288396 0.647749 0.705159 0.416768 0.573633 0.705157 0.41677 0.573634 0.70706 0.481297 0.518092 0.665757 0.521213 0.533952 0.705157 -0.41677 0.573634 0.705157 -0.288397 0.64775 0.705155 -0.288398 0.647753 0.705155 -0.14742 0.693559 0.705154 -0.147421 0.69356 0.705154 0 0.709054 0.705154 0 0.709054 0.707089 0.0790704 0.70269 0.622904 0.162649 0.765203 0.705418 0.152447 0.692204 0.705153 0.288399 0.647754 0.66576 -0.52121 0.533952 0.707057 -0.481299 0.518095 0.705155 -0.416771 0.573636 0.628604 -0.54997 0.5499 0.373125 -0.689476 0.620807 0.706052 -0.539184 0.459098 0.705158 -0.614056 0.354525 0.705155 -0.614058 0.354527 0.706659 -0.691429 0.150199 0.67329 -0.703191 0.228481 0.697827 -0.680711 0.222868 0.7071 -0.646192 0.287134 0.707101 -0.691437 0.148064 0.705157 -0.705167 0.074116 0.705155 -0.705169 0.0741162 0.698067 0.69808 0.159332 0.698065 0.698082 0.159333 0.698066 0.559817 0.44644 0.698065 0.559818 0.446441 0.698065 0.310676 0.645125 0.698069 0.310675 0.645121 0.698071 0 0.716029 0.698071 0 0.716029 0.698069 -0.310674 0.645121 0.698068 -0.310675 0.645122 0.69807 -0.559814 0.446438 0.698066 -0.559818 0.44644 0.698065 -0.698082 0.159333 0.698061 -0.698087 0.159333 0.69474 0.694753 0.186158 0.694738 0.694755 0.186159 0.694738 0.508595 0.508595 0.694738 0.508595 0.508595 0.69474 0.186159 0.694752 0.69474 0.186159 0.694753 0.69474 -0.186159 0.694753 0.694742 -0.186158 0.694751 0.694743 -0.508591 0.508593 0.694738 -0.508595 0.508595 0.694738 -0.694755 0.186159 0.69474 -0.694753 0.186159 0.69474 0.694753 0.186158 0.694738 0.694755 0.186159 0.694738 0.508596 0.508595 0.694738 0.508596 0.508596 0.694739 0.186158 0.694753 0.69474 0.186158 0.694753 0.69474 -0.186159 0.694753 0.694741 -0.186158 0.694752 0.694743 -0.508593 0.508592 0.694743 -0.508592 0.508592 0.694745 -0.694748 0.186158 0.69474 -0.694753 0.186159 0.69474 0.694753 0.186158 0.694738 0.694755 0.186159 0.694738 0.508596 0.508595 0.694738 0.508596 0.508595 0.69474 0.186158 0.694753 0.694742 0.186158 0.694751 0.694742 -0.186158 0.694751 0.694742 -0.186158 0.694751 0.694743 -0.508592 0.508592 0.694743 -0.508592 0.508592 0.694745 -0.694748 0.186158 0.69474 -0.694753 0.186159 0.69474 0.694753 0.186158 0.694738 0.694755 0.186159 0.694739 0.508596 0.508595 0.694736 0.508597 0.508597 0.694737 0.186159 0.694756 0.69474 0.186159 0.694753 0.69474 -0.186158 0.694753 0.694739 -0.186159 0.694754 0.694741 -0.508593 0.508594 0.694738 -0.508595 0.508595 0.694738 -0.694755 0.186159 0.69474 -0.694753 0.186159 0.69474 0.694753 0.18616 0.694745 0.694748 0.186157 0.694746 0.508591 0.50859 0.694741 0.508594 0.508594 0.694739 0.186159 0.694754 0.69474 0.186159 0.694753 0.69474 -0.186158 0.694753 0.694739 -0.186159 0.694754 0.694741 -0.508594 0.508594 0.694741 -0.508594 0.508594 0.694739 -0.694753 0.18616 0.694733 -0.694759 0.18616 0.694746 0.694746 0.186158 0.694752 0.694741 0.186155 0.694751 0.508588 0.508586 0.694741 0.508594 0.508594 0.694739 0.186159 0.694754 0.69474 0.186159 0.694753 0.69474 -0.186158 0.694753 0.694735 -0.18616 0.694757 0.694731 -0.508602 0.508599 0.694741 -0.508594 0.508594 0.694739 -0.694753 0.18616 0.694733 -0.694759 0.18616 0.694747 0.694747 0.186155 0.694738 0.694755 0.186159 0.694738 0.508595 0.508596 0.694741 0.508594 0.508594 0.694739 0.186159 0.694754 0.69474 0.186159 0.694753 0.69474 -0.186158 0.694753 0.694739 -0.186159 0.694754 0.694741 -0.508593 0.508594 0.694738 -0.508595 0.508595 0.694738 -0.694754 0.18616 0.694733 -0.694759 0.18616 0.694733 0.694759 0.186161 0.694738 0.694755 0.186159 0.694739 0.508596 0.508595 0.694733 0.508599 0.508599 0.694738 0.186158 0.694754 0.694742 0.186158 0.694751 0.694742 -0.186158 0.694751 0.694742 -0.186158 0.694751 0.694743 -0.508591 0.508592 0.694738 -0.508596 0.508595 0.694738 -0.694755 0.186157 0.694747 -0.694747 0.186157 0.694733 0.694759 0.186161 0.694738 0.694755 0.186159 0.694739 0.508596 0.508595 0.694733 0.508599 0.508599 0.694738 0.186159 0.694755 0.69474 0.186158 0.694753 0.69474 -0.186159 0.694753 0.694741 -0.186158 0.694752 0.694743 -0.508592 0.508593 0.694738 -0.508596 0.508595 0.694738 -0.694755 0.186157 0.694747 -0.694747 0.186157 0.698074 0.698074 0.159331 0.698078 0.69807 0.159329 0.698077 0.559811 0.446431 0.698059 0.559821 0.446445 0.698062 0.310676 0.645128 0.698072 0.310674 0.645118 0.698067 0 0.716032 0.698067 0 0.716032 0.698066 -0.310675 0.645124 0.698062 -0.310678 0.645127 0.698059 -0.559822 0.446444 0.698066 -0.559817 0.446441 0.698065 -0.698082 0.159333 0.698061 -0.698087 0.159333 0.694746 0.694746 0.186158 0.69475 0.694743 0.186156 0.694746 0.508591 0.50859 0.694741 0.508594 0.508594 0.694739 0.186159 0.694754 0.69474 0.186159 0.694753 0.69474 -0.186158 0.694753 0.694735 -0.18616 0.694757 0.694731 -0.508601 0.5086 0.694736 -0.508597 0.508597 0.694737 -0.694755 0.18616 0.694733 -0.694759 0.18616 -0.694733 -0.694759 0.186161 -0.694739 -0.694754 0.186159 -0.694741 -0.508594 0.508594 -0.694741 -0.508594 0.508594 -0.694739 -0.186159 0.694754 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694739 0.186159 0.694754 -0.694741 0.508595 0.508593 -0.694746 0.50859 0.50859 -0.694746 0.694747 0.186158 -0.69474 0.694753 0.186159 -0.69474 -0.694753 0.186158 -0.694738 -0.694755 0.186159 -0.694738 -0.508595 0.508596 -0.694741 -0.508594 0.508594 -0.694739 -0.186159 0.694754 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694737 0.186159 0.694756 -0.694736 0.508597 0.508597 -0.694738 0.508595 0.508595 -0.694738 0.694755 0.186159 -0.69474 0.694753 0.186159 -0.69474 -0.694753 0.186159 -0.694745 -0.694748 0.186157 -0.694743 -0.508592 0.508592 -0.694743 -0.508592 0.508592 -0.694742 -0.186158 0.694751 -0.694742 -0.186158 0.694751 -0.694742 0.186158 0.694751 -0.69474 0.186158 0.694752 -0.694738 0.508596 0.508595 -0.694738 0.508596 0.508595 -0.694738 0.694755 0.186159 -0.69474 0.694753 0.186159 -0.69474 -0.694753 0.186159 -0.694745 -0.694748 0.186157 -0.694743 -0.508592 0.508592 -0.694743 -0.508593 0.508592 -0.694741 -0.186158 0.694752 -0.69474 -0.186158 0.694753 -0.69474 0.186158 0.694753 -0.694739 0.186159 0.694753 -0.694738 0.508596 0.508596 -0.694738 0.508596 0.508595 -0.694738 0.694755 0.186159 -0.69474 0.694753 0.186159 -0.69474 -0.694753 0.186158 -0.694738 -0.694755 0.186159 -0.694738 -0.508595 0.508596 -0.694743 -0.508592 0.508592 -0.694742 -0.186158 0.694751 -0.69474 -0.186159 0.694753 -0.69474 0.186159 0.694753 -0.69474 0.186158 0.694752 -0.694738 0.508595 0.508595 -0.694738 0.508595 0.508595 -0.694738 0.694755 0.186159 -0.69474 0.694753 0.186159 -0.69806 -0.698086 0.159334 -0.698065 -0.698082 0.159332 -0.698066 -0.559817 0.44644 -0.69807 -0.559815 0.446437 -0.698068 -0.310674 0.645122 -0.698069 -0.310674 0.645121 -0.698071 0 0.716029 -0.698071 0 0.716029 -0.698069 0.310674 0.645121 -0.698065 0.310676 0.645124 -0.698065 0.559818 0.446441 -0.698066 0.559817 0.44644 -0.698065 0.698082 0.159333 -0.698067 0.69808 0.159333 -0.694733 -0.694759 0.186161 -0.694737 -0.694756 0.186159 -0.694736 -0.508598 0.508596 -0.694731 -0.5086 0.5086 -0.694735 -0.186159 0.694758 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694739 0.186159 0.694754 -0.694741 0.508595 0.508593 -0.694746 0.50859 0.50859 -0.69475 0.694743 0.186157 -0.694747 0.694747 0.186157 -0.69806 -0.698086 0.159334 -0.698065 -0.698082 0.159332 -0.698066 -0.559818 0.44644 -0.698059 -0.559821 0.446445 -0.698062 -0.310677 0.645127 -0.698066 -0.310676 0.645124 -0.698067 0 0.716032 -0.698067 0 0.716032 -0.698072 0.310671 0.645119 -0.698062 0.310678 0.645127 -0.698059 0.559824 0.446442 -0.698076 0.559809 0.446435 -0.698078 0.698069 0.15933 -0.698074 0.698074 0.15933 -0.694747 -0.694747 0.186155 -0.694738 -0.694755 0.186159 -0.694738 -0.508595 0.508596 -0.694743 -0.508593 0.508592 -0.694741 -0.186158 0.694752 -0.69474 -0.186158 0.694753 -0.69474 0.186158 0.694753 -0.694738 0.186159 0.694755 -0.694733 0.5086 0.508598 -0.694738 0.508596 0.508595 -0.694738 0.694754 0.18616 -0.694733 0.694759 0.18616 -0.694747 -0.694747 0.186155 -0.694738 -0.694755 0.186159 -0.694738 -0.508595 0.508596 -0.694743 -0.508592 0.508592 -0.694742 -0.186158 0.694751 -0.694742 -0.186158 0.694751 -0.694742 0.186158 0.694751 -0.694739 0.186159 0.694754 -0.694733 0.5086 0.508598 -0.694738 0.508596 0.508595 -0.694738 0.694754 0.18616 -0.694733 0.694759 0.18616 -0.694733 -0.694759 0.186161 -0.694738 -0.694755 0.186159 -0.694738 -0.508595 0.508596 -0.694741 -0.508594 0.508594 -0.694739 -0.186159 0.694754 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694739 0.186159 0.694754 -0.694741 0.508593 0.508594 -0.694738 0.508595 0.508595 -0.694738 0.694755 0.186157 -0.694747 0.694747 0.186157 -0.694733 -0.694759 0.186161 -0.694739 -0.694754 0.186159 -0.694741 -0.508595 0.508592 -0.694731 -0.5086 0.5086 -0.694735 -0.186159 0.694758 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694739 0.186159 0.694754 -0.694741 0.508595 0.508593 -0.694751 0.508587 0.508587 -0.694752 0.694741 0.186157 -0.694747 0.694747 0.186157 -0.705777 -0.705738 0.0617441 -0.705776 -0.705739 0.0617441 -0.705776 -0.684295 0.183356 -0.705775 -0.684296 0.183357 -0.705776 -0.642061 0.299398 -0.705777 -0.642059 0.299397 -0.705778 -0.580315 0.406341 -0.705778 -0.580315 0.406341 -0.705778 -0.500938 0.500938 -0.705782 -0.500935 0.500935 -0.705782 -0.406338 0.580311 -0.705783 -0.406338 0.58031 -0.705783 -0.299395 0.642054 -0.705779 -0.299397 0.642058 -0.705777 -0.183356 0.684295 -0.705776 -0.183357 0.684296 -0.705775 -0.0617444 0.70574 -0.705784 -0.0617433 0.705731 -0.705784 0.0617437 0.705731 -0.705775 0.0617441 0.705741 -0.705774 0.183357 0.684298 -0.705776 0.183357 0.684296 -0.705776 0.299398 0.642061 -0.705777 0.299397 0.642059 -0.705775 0.406342 0.580317 -0.705782 0.406338 0.580311 -0.705782 0.500935 0.500935 -0.705773 0.500941 0.500942 -0.705773 0.580319 0.406344 -0.705778 0.580315 0.40634 -0.705777 0.642059 0.299398 -0.705793 0.642045 0.29939 -0.705795 0.684278 0.183351 -0.705755 0.684315 0.183363 -0.705755 0.70576 0.0617464 -0.705784 0.705732 0.0617428 -0.705581 -0.705607 0.0653845 -0.705595 -0.705593 0.0653827 -0.705594 -0.681565 0.193922 -0.705578 -0.681581 0.193927 -0.705579 -0.634341 0.315864 -0.705589 -0.634332 0.315859 -0.705589 -0.565492 0.42704 -0.705582 -0.565497 0.427044 -0.705583 -0.477399 0.523682 -0.705588 -0.477396 0.523678 -0.705588 -0.373042 0.602483 -0.705588 -0.373041 0.602483 -0.705589 -0.255984 0.66077 -0.70559 -0.255983 0.660769 -0.70559 -0.130209 0.696555 -0.705588 -0.130209 0.696557 -0.705587 0 0.708623 -0.705587 0 0.708623 -0.705588 0.130209 0.696557 -0.70559 0.130209 0.696555 -0.70559 0.255983 0.660769 -0.705591 0.255983 0.660768 -0.705591 0.37304 0.60248 -0.705584 0.373044 0.602486 -0.705584 0.477399 0.523681 -0.705588 0.477396 0.523678 -0.705588 0.565493 0.427041 -0.705586 0.565494 0.427041 -0.705586 0.634334 0.315861 -0.705591 0.63433 0.315859 -0.70559 0.681569 0.193923 -0.705588 0.681571 0.193924 -0.705588 0.705599 0.0653834 -0.705587 0.7056 0.0653835 -0.705587 -0.7056 0.0653835 -0.705588 -0.7056 0.0653835 -0.705588 -0.681571 0.193924 -0.70559 -0.681569 0.193923 -0.705589 -0.634331 0.31586 -0.705586 -0.634334 0.315861 -0.705586 -0.565494 0.427041 -0.705587 -0.565493 0.427041 -0.705588 -0.477396 0.523678 -0.705588 -0.477396 0.523678 -0.70559 -0.373041 0.602481 -0.705588 -0.373042 0.602483 -0.705589 -0.255984 0.66077 -0.70559 -0.255983 0.660769 -0.70559 -0.130209 0.696555 -0.705585 -0.13021 0.696559 -0.705587 0 0.708623 -0.705587 0 0.708623 -0.705588 0.130209 0.696557 -0.70559 0.130209 0.696555 -0.70559 0.255983 0.660769 -0.705593 0.255982 0.660766 -0.705595 0.373038 0.602477 -0.705593 0.373039 0.602478 -0.705593 0.477393 0.523674 -0.705583 0.477399 0.523682 -0.705582 0.565497 0.427044 -0.705589 0.565492 0.42704 -0.705589 0.634332 0.315859 -0.705578 0.634342 0.315865 -0.705577 0.681582 0.193927 -0.705595 0.681565 0.193922 -0.705595 0.705593 0.0653828 -0.705594 0.705594 0.0653829 -0.705779 -0.705736 0.061744 -0.705777 -0.705739 0.0617441 -0.705777 -0.684295 0.183356 -0.705779 -0.684293 0.183356 -0.705779 -0.642058 0.299396 -0.705779 -0.642058 0.299396 -0.705778 -0.580314 0.40634 -0.705778 -0.580314 0.406341 -0.705778 -0.500938 0.500938 -0.705783 -0.500935 0.500935 -0.705782 -0.406338 0.580311 -0.705777 -0.406341 0.580315 -0.705777 -0.299397 0.642059 -0.705781 -0.299395 0.642056 -0.705782 -0.183355 0.68429 -0.705782 -0.183355 0.68429 -0.705782 -0.0617437 0.705734 -0.705777 -0.0617442 0.705738 -0.705777 0.0617441 0.705738 -0.705782 0.0617438 0.705733 -0.705784 0.183354 0.684288 -0.705782 0.183355 0.68429 -0.705782 0.299395 0.642055 -0.705777 0.299397 0.642059 -0.705778 0.406341 0.580315 -0.705782 0.406338 0.580311 -0.705782 0.500935 0.500935 -0.705782 0.500935 0.500935 -0.705784 0.58031 0.406337 -0.705776 0.580316 0.406342 -0.705775 0.642061 0.299397 -0.70577 0.642066 0.2994 -0.705769 0.684302 0.183358 -0.705756 0.684315 0.183362 -0.705755 0.70576 0.0617468 -0.705784 0.705731 0.0617431 -0.70562 -0.705568 0.0653808 -0.705608 -0.70558 0.0653824 -0.705608 -0.681552 0.193918 -0.705616 -0.681545 0.193916 -0.705616 -0.634308 0.315848 -0.705604 -0.634318 0.315853 -0.705605 -0.565479 0.42703 -0.705619 -0.565468 0.427021 -0.705619 -0.477375 0.523656 -0.705619 -0.477375 0.523655 -0.70562 -0.373025 0.602456 -0.705614 -0.373028 0.602461 -0.705615 -0.255974 0.660746 -0.70561 -0.255976 0.66075 -0.70561 -0.130205 0.696535 -0.705614 -0.130204 0.696531 -0.705614 0 0.708597 -0.705614 0 0.708597 -0.705614 0.130204 0.696531 -0.70561 0.130205 0.696535 -0.70561 0.255976 0.66075 -0.705617 0.255973 0.660743 -0.705618 0.373026 0.602458 -0.705616 0.373027 0.602459 -0.705615 0.477378 0.523658 -0.705617 0.477377 0.523657 -0.705617 0.56547 0.427023 -0.705615 0.565471 0.427024 -0.705616 0.634308 0.315848 -0.705613 0.634311 0.315849 -0.705613 0.681547 0.193917 -0.705614 0.681546 0.193917 -0.705614 0.705573 0.0653811 -0.705614 0.705574 0.0653811 -0.705594 -0.705594 0.0653836 -0.705608 -0.70558 0.0653817 -0.705607 -0.681553 0.193918 -0.70559 -0.68157 0.193924 -0.705589 -0.634331 0.31586 -0.705589 -0.634332 0.31586 -0.705589 -0.565492 0.42704 -0.705593 -0.565489 0.427037 -0.705592 -0.477393 0.523675 -0.705588 -0.477396 0.523678 -0.705588 -0.373042 0.602483 -0.705582 -0.373045 0.602488 -0.705582 -0.255986 0.660776 -0.705584 -0.255985 0.660775 -0.705584 -0.13021 0.696561 -0.705588 -0.130209 0.696557 -0.705587 0 0.708623 -0.705587 0 0.708623 -0.705588 0.130209 0.696557 -0.705584 0.13021 0.696561 -0.705584 0.255986 0.660775 -0.705585 0.255985 0.660774 -0.705586 0.373043 0.602485 -0.705588 0.373042 0.602483 -0.705588 0.477396 0.523678 -0.705588 0.477396 0.523678 -0.705587 0.565493 0.427041 -0.705589 0.565492 0.42704 -0.705589 0.634332 0.31586 -0.705589 0.634331 0.31586 -0.70559 0.68157 0.193923 -0.705588 0.681571 0.193924 -0.705588 0.705599 0.0653834 -0.705587 0.7056 0.0653835 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.939621 0.0370023 -0.34021 -0.939565 -0.0329192 -0.340783 -0.938389 -0.0498414 -0.341967 -0.939692 -0.0508148 -0.338227 -0.939429 -0.051827 -0.338801 -0.939408 -0.0518967 -0.338849 -0.939889 -0.051433 -0.337584 -0.939982 -0.0516737 -0.337288 -0.939936 -0.0515865 -0.337431 -0.939771 -0.0515723 -0.337892 -0.939571 -0.0516509 -0.338434 -0.939633 0.0516247 -0.338266 -0.939831 0.0515463 -0.337728 -0.94095 0.0488263 -0.335007 -0.939692 0.0507736 -0.338233 -0.939957 0.0515994 -0.33737 -0.939978 0.0516527 -0.337304 -0.939693 0.0502954 -0.338302 -0.939471 0.0517288 -0.3387 -0.93945 0.0517849 -0.33875 -0.939566 0.0329192 -0.340783 -0.94337 0.0336276 -0.330033 -0.936007 0.008472 -0.351879 -0.939622 0.0123554 -0.341991 -0.939661 -0.0082366 -0.342009 -0.937285 -0.0125847 -0.348336 -0.94337 -0.0336276 -0.330033 -0.939621 -0.0370023 -0.340209 -0.939693 -0.0502913 -0.338303 -0.149348 0.106913 -0.982988 -0.488786 0.0943294 -0.867289 -0.346056 -0.101445 -0.932713 -0.655058 -0.081697 -0.751149 -0.850962 -0.0567903 -0.522148 -0.850961 -0.0567906 -0.522149 -0.850961 -0.0189633 -0.524886 -0.850962 -0.0189631 -0.524885 -0.850962 0.0189632 -0.524885 -0.850961 0.0189631 -0.524886 -0.850962 0.0567904 -0.522149 -0.850962 0.0567904 -0.522148 -0.655066 0.0816963 -0.751142 -0.573444 0.0811231 -0.815219 -0.573333 0.0295814 -0.818788 -0.573333 0.0295814 -0.818788 -0.573333 -0.0295815 -0.818788 -0.573333 -0.0295814 -0.818788 -0.573444 -0.0811235 -0.815218 -0.488786 -0.0943296 -0.867289 -0.346081 0.101444 -0.932704 -0.202125 0.100133 -0.974227 -0.202087 0.0353598 -0.978729 -0.202085 0.0353597 -0.978729 -0.202085 -0.0353598 -0.978729 -0.202086 -0.0353597 -0.978729 -0.202124 -0.100134 -0.974227 -0.149353 -0.106913 -0.982987 0.707097 0.12415 0.696133 0.671182 0.0864092 0.736239 0.706474 0.0842521 0.702706 0.706474 0 0.707739 0.706474 0 0.707739 0.706524 -0.0824922 0.702864 0.672816 -0.0880699 0.734549 0.707097 -0.12415 0.696133 0.706462 -0.0842531 -0.702719 0.706474 -0.0842523 -0.702706 0.706474 0 -0.707739 0.706474 0 -0.707739 0.706474 0.0842516 -0.702706 0.706462 0.0842537 -0.702719 0.698065 0.0325018 0.715296 0.698069 0.032503 0.715292 0.698068 0.339639 0.630354 0.618515 0.349228 0.703902 0.706897 0.447468 0.547786 0.698064 0.579508 0.420567 0.698067 0.579506 0.420565 0.698068 0.704592 0.127481 0.698071 0.70459 0.127479 0.698067 0.690127 -0.190856 0.698058 0.281076 -0.658568 0.698066 0.28107 -0.658562 0.700601 0.520994 -0.487568 0.634905 0.581547 -0.508625 0.706901 0.611037 -0.356265 0.698067 0.690127 -0.190856 0.698523 -0.0284257 0.715023 0.698525 -0.0284246 0.715021 0.69852 -0.328654 0.635654 0.698523 -0.328652 0.635652 0.698518 -0.566989 0.436573 0.698521 -0.566986 0.436572 0.698525 -0.698537 0.155269 0.698531 -0.698531 0.15527 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.0453933 0.998969 0 0.320169 -0.947361 -0.0323316 0.392336 -0.919254 -0.00477553 0.504971 -0.863123 0.0109498 0.7043 -0.709818 -0.00691619 0.730123 -0.68328 0.00188897 0.863884 -0.503687 0.0233484 0.934163 -0.356083 -0.0207686 0.963614 -0.26649 -0.0012961 0.994915 -0.100711 0.00323599 0.998462 0.0553453 -0.0314922 0.983536 0.177948 -0.00693774 0.964649 0.263445 0.000742518 0.639972 0.768398 -0.00314343 0.766426 0.642325 -0.0274187 0.809026 0.587134 -0.00213276 0.880706 0.473658 0.000705634 0.92513 0.37965 -0.00398464 0.037388 0.999293 0.00339376 0.437553 0.899186 2.12144e-05 0.444439 0.895809 4.53473e-07 0.632627 0.774456 0 -0.0157905 0.999875 -0.0104432 -0.0397213 0.999156 0.00978966 -0.404977 0.914275 -0.0153998 -0.459222 0.888188 0.00079543 -0.619772 0.784781 -0.00343899 -0.759076 0.650993 -0.0232002 -0.792122 0.609922 -0.000125847 -0.877492 0.479592 0.000222385 -0.952569 0.304322 -0.0289641 -0.975766 0.216891 0 -0.995968 0.0897057 0 -0.119043 -0.992889 0 -0.119043 -0.992889 0 0 -1 0 0 -1 0 0.119043 -0.992889 0 0.119043 -0.992889 0 -0.119044 0.992889 0 -0.119044 0.992889 0 0 1 0 0 1 0 0.119044 0.992889 0 0.119044 0.992889 0.879241 0.121055 -0.46074 0.887082 0.18521 -0.422827 0.954993 0.213682 -0.205741 0.960101 0.209238 -0.18554 0.978435 0.149538 -0.142487 0.978976 0.148081 -0.140277 0.991397 0.062144 -0.115199 0.990797 0.0665725 -0.117852 0.965171 0.0742756 0.250854 0.793205 0.568251 0.218897 0.859466 0.34997 0.372611 0.839102 0.377559 0.391609 0.884189 0.0696556 0.461908 0.876484 0.0783715 0.475008 0.859293 0.489205 -0.149314 0.938544 0.241642 -0.246463 0.933189 0.238333 -0.268991 0.821646 0.569778 -0.0158331 0.847484 0.528507 0.0495118 0.891283 0.452009 0.0360954 0.947044 0.277998 0.160699 0.938319 0.298971 0.173707 0.970911 0.0893289 0.222152 0.989049 0.0760298 0.1265 0.807335 0.433415 -0.400452 0.69324 0.678479 -0.243071 0.770719 0.636664 -0.0255286 0.902133 0.235401 -0.361583 0.887847 0.179407 -0.423722 0.749549 0.338764 -0.568696 0.710134 0.348522 -0.611753 0.276009 0.862454 -0.424255 0.145857 0.495213 -0.85644 0.197808 0.347224 -0.916683 0.147949 0.314642 -0.937609 0.111223 0.440405 0.890883 0.0953821 0.0393399 0.994663 0.105769 0.0356721 0.993751 0.0780573 0.881567 0.465561 0.14358 0.766536 0.625945 0.177644 0.754392 0.63193 0.0973084 0.642556 0.760035 0.110871 0.440521 0.89087 0.0290627 0.703331 -0.710268 0.134962 0.922479 -0.361688 -0.130555 0.907298 -0.399707 0.156241 0.981086 -0.114272 0.216098 0.973433 -0.075699 0.0506077 0.997433 0.0506532 0.143393 0.942357 0.302328 0.273426 0.934784 0.226751 0.142376 0.920815 0.363081 0.354226 0.819428 -0.450623 0.457112 0.87777 -0.143417 0.363171 0.9163 -0.168822 0.49083 0.853067 0.177092 0.397291 0.90236 0.16705 0.522587 0.703954 0.48099 0.442839 0.75148 0.489052 0.546615 0.428532 0.719425 0.493393 0.460222 0.738078 0.553361 0.0599239 0.830783 0.546232 0.0631192 0.835252 0.176414 0.87405 -0.452675 0.302666 0.949309 -0.0848917 0.186328 0.976231 -0.110701 0.325671 0.907135 0.266541 0.208476 0.94515 0.251454 0.343271 0.732025 0.588476 0.241852 0.771844 0.588017 0.3515 0.431634 0.830747 0.282647 0.460902 0.841237 0.345025 0.0404253 0.937723 0.33367 0.0450126 0.941615 0.879548 0.119854 -0.460468 0.76348 0.186666 -0.618267 0.693958 0.254637 -0.673486 0.651408 0.241371 -0.71931 0.484443 0.28898 -0.825715 0.918295 0.24588 -0.310287 0.901024 0.259509 -0.347579 0.758735 0.525228 -0.385301 0.80531 0.471413 -0.359508 0.700506 0.607179 -0.374999 0.633801 0.45041 -0.628831 0.461125 0.542722 -0.702009 0.425673 0.332705 -0.841493 0.341458 0.328831 -0.880498 0.172202 0.654674 -0.736035 0.179208 0.655012 -0.734059 0.42409 0.58683 -0.689767 0.486868 0.720618 -0.493628 0.502658 0.715011 -0.485895 0.601383 0.773976 -0.198242 0.531877 0.816936 -0.222985 0.642847 0.762018 0.0779482 0.575101 0.815065 0.0701949 0.685239 0.640523 0.346666 0.62921 0.689855 0.358042 0.721675 0.401416 0.56396 0.685622 0.432695 0.585403 0.73994 0.0647174 0.669553 0.72568 0.0744771 0.68399 0.146154 -0.378318 -0.914065 0.826267 -0.56015 -0.0592833 0.651434 -0.241325 -0.719302 0.880896 -0.17383 -0.440233 0.992268 -0.0783359 -0.0962655 0.992327 -0.0396648 -0.117107 0.976264 -0.165556 -0.139645 0.978907 -0.147594 -0.141266 0.963207 -0.200341 -0.179155 0.942932 -0.258264 -0.210185 0.902136 -0.219522 -0.37143 0.895797 -0.222185 -0.384944 0.919326 -0.240406 -0.311521 0.851016 -0.078534 -0.519233 0.740535 -0.603859 -0.294894 0.783617 -0.56866 -0.250141 0.707956 -0.523634 -0.473926 0.912305 -0.248564 -0.325446 0.939734 -0.234481 -0.248833 0.785904 -0.611841 -0.0894745 0.847488 -0.528502 0.0494886 0.793262 -0.568162 0.218923 0.856964 -0.366099 0.362746 0.844207 -0.360293 0.396868 0.884162 -0.0782937 0.460573 0.877675 -0.0700832 0.474105 0.923013 -0.269006 -0.275104 0.960832 -0.19278 -0.199095 0.891326 -0.451924 0.0360885 0.944822 -0.289805 0.152725 0.94184 -0.285627 0.177072 0.97092 -0.0893752 0.222097 0.965173 -0.0743154 0.250835 0.0802871 -0.878253 0.471409 0.171987 -0.938985 0.297873 0.146984 -0.759142 0.634112 0.158085 -0.755454 0.635844 0.0929163 -0.622453 0.777122 0.146474 -0.440916 0.885516 0.0592825 -0.406805 0.911589 0.106169 -0.0177461 0.99419 0.150243 -0.0367853 0.987965 0.33401 -0.0403271 0.941707 0.138183 -0.947452 0.288513 0.0626297 -0.994545 0.0834099 0.205173 -0.975914 -0.0741395 0.119315 -0.986581 -0.111452 0.0122604 -0.909159 -0.416268 0.365935 -0.872493 -0.323803 0.179864 -0.874422 -0.450595 0.0941351 -0.852408 -0.514333 0.0328689 -0.713083 -0.700309 0.190222 -0.65539 -0.730945 0.0915725 -0.35563 -0.93013 0.341493 -0.328769 -0.880508 0.693994 -0.254606 -0.67346 0.714751 -0.392986 -0.578527 0.412203 -0.563069 -0.71627 0.486915 -0.720648 -0.493538 0.354193 -0.819482 -0.450552 0.447657 -0.875896 -0.180027 0.378509 -0.915792 -0.134368 0.480125 -0.865901 0.140343 0.413092 -0.888249 0.200919 0.514055 -0.727614 0.45423 0.455176 -0.727768 0.512999 0.542684 -0.451685 0.708149 0.499641 -0.437693 0.747518 0.553287 -0.0633262 0.83058 0.546658 -0.0595624 0.835235 0.34468 -0.0458793 0.937599 0.288263 -0.436761 0.852141 0.346239 -0.457017 0.819301 0.253718 -0.746936 0.614584 0.332837 -0.758352 0.560465 0.224031 -0.930951 0.288341 0.313055 -0.922051 0.227638 0.201547 -0.976699 -0.0737426 0.291651 -0.94846 -0.123951 0.187833 -0.885527 -0.424924 0.269281 -0.849601 -0.453505 0.179191 -0.654927 -0.73414 0.463855 -0.570897 -0.677433 0.425702 -0.33265 -0.8415 0.484444 -0.28893 -0.825732 0.875354 -0.113817 -0.469894 0.889584 -0.176743 -0.421191 0.689708 -0.389166 -0.610617 0.745683 -0.510389 -0.428323 0.502635 -0.715062 -0.485845 0.59326 -0.771102 -0.23118 0.546289 -0.815283 -0.192047 0.633768 -0.772237 0.0445984 0.590004 -0.801195 0.099912 0.678252 -0.660527 0.321991 0.64095 -0.667851 0.378363 0.718703 -0.421407 0.553066 0.691737 -0.412405 0.592809 0.739912 -0.0743876 0.668579 0.727069 -0.0648234 0.683497 0.572898 0 -0.819627 0.850725 -0.0636532 -0.521743 0.879516 0.0576319 -0.472367 0.654679 0.0899859 -0.750532 0.764993 0.0766687 -0.639459 0.845143 0.0602367 -0.531135 0.851114 0.0323968 -0.52398 0.850696 0 -0.525657 0.850696 0 -0.525657 0.851114 -0.0323833 -0.523981 0.345767 0.111701 -0.931648 0.488417 0.103879 -0.866405 0.149219 0.117711 -0.981773 0.201908 0.113124 -0.972849 0.201869 0 -0.979413 0.844346 -0.0637834 -0.531988 0.654704 -0.0899833 -0.75051 0.573019 -0.0930683 -0.81424 0.488413 -0.103879 -0.866408 0.345795 -0.1117 -0.931638 0.573019 0.0930691 -0.81424 0.572898 0 -0.819627 0.201869 0 -0.979413 0.201908 -0.113123 -0.97285 0.149214 -0.117711 -0.981774 0.340892 0.111913 0.933417 0.994035 0 -0.109062 0.994036 -0.0132062 -0.108246 0.994251 -0.0127471 -0.106317 0.991754 0.0155212 -0.127214 0.996676 0.00502712 -0.0813164 0.65868 0 0.752423 0.931791 0 0.362996 0.994046 0.0110552 -0.108403 0.993745 -0.0132937 0.110877 0.971837 -0.0280534 0.233979 0.994056 -0.00671748 -0.108663 0.994035 0 -0.109062 0.931791 0 0.362996 0.931639 -0.0497305 0.359967 0.558445 0.112612 0.821862 0.739311 0.08016 0.668576 0.931791 0.0432126 0.360415 0.888071 0.0662197 0.454911 0.971843 0.0280504 0.233955 0.237284 0 0.97144 0.237284 0.115644 0.964532 0.108128 0.132819 0.985225 0.887837 -0.0547792 0.456886 0.739295 -0.0801621 0.668593 0.658468 -0.0961999 0.746435 0.558107 -0.0987789 0.823869 0.340889 -0.111913 0.933419 0.65868 0.0895713 0.747073 0.65868 0 0.752423 0.237284 0 0.97144 0.237188 -0.12225 0.963741 0.10804 -0.118347 0.987077 0.939515 0.0414811 -0.339987 0.939606 0.0626264 -0.336479 0.93949 0.0628095 -0.33677 0.939578 0.062508 -0.33658 0.939697 0.0614302 -0.336445 0.939842 0.0625225 -0.33584 0.939863 0.0625588 -0.335775 0.939744 0.0625591 -0.336106 0.939508 -0.0414811 -0.340006 0.939901 -0.0626175 -0.335656 0.939805 -0.0623805 -0.335968 0.93969 -0.0614388 -0.336463 0.939697 -0.0616385 -0.336407 0.939544 -0.0626392 -0.33665 0.939486 -0.0628381 -0.336776 0.939529 -0.0627211 -0.336677 0.939646 -0.0626077 -0.336373 0.939777 -0.0625433 -0.336017 0.939515 -0.0414789 -0.339987 0.939511 -0.0414792 -0.339998 0.939694 -0.0211031 -0.341366 0.939693 -0.0210973 -0.341367 0.939497 0 -0.342556 0.939497 0 -0.342556 0.939693 0.0211039 -0.341367 0.939693 0.0211061 -0.341367 0.939511 0.0414814 -0.339999 0.939508 0.041483 -0.340006 0.93969 0.0616669 -0.336422 -0.0420658 -0.715802 -0.697036 -0.00151189 -0.859857 -0.510533 0.000292519 -0.895397 -0.445269 -0.00687026 -0.973193 -0.229888 -0.0567897 -0.948758 -0.310857 0 -0.99489 -0.100965 0.0106919 -0.767434 -0.641039 -0.00938649 -0.399469 -0.916699 0 -0.385286 -0.922797 0.697444 -0.697444 -0.16475 0.697447 -0.697442 -0.164749 0.697442 -0.550006 -0.459422 0.69744 -0.550007 -0.459423 0.697438 -0.28629 -0.656976 0.697429 -0.286291 -0.656985 -0.000652638 0.880802 -0.473484 0 0.999557 -0.0297563 0.00490114 0.971865 -0.235489 0.0463859 0.942036 -0.33229 0.00614534 0.989147 -0.146803 0 0.372939 -0.927856 0.0140685 0.343991 -0.938868 0.000715614 0.545199 -0.838306 -0.00557459 0.756278 -0.654227 0.0339606 0.69829 -0.715009 0.00403467 0.836921 -0.547308 -0.696944 0.696957 -0.168877 -0.696941 0.69696 -0.168879 -0.696939 0.542358 -0.469173 -0.696947 0.542354 -0.469167 -0.696946 0.267443 -0.665387 -0.696945 0.267444 -0.665389 -0.698864 0.572325 0.42899 -0.698861 0.572328 0.428991 -0.698862 0.698879 0.152183 -0.698864 0.698877 0.152183 -0.698865 0.0499938 0.713504 -0.698864 0.0499942 0.713505 -0.698866 0.342136 0.628116 -0.819612 0.233964 0.52297 -0.70602 0.420126 0.570113 -0.458483 -0.816371 0.351187 -0.694741 -0.08421 0.714313 -0.694739 -0.0842098 0.714315 -0.705701 -0.319651 0.632305 -0.754938 -0.332934 0.564999 -0.624884 -0.520558 0.581841 -0.705015 -0.505915 0.496995 -0.703697 -0.613141 0.358982 -0.704396 -0.684494 0.187867 -0.704397 -0.70965 0.0149301 -0.458481 -0.882592 -0.104051 -0.69474 -0.284228 -0.66072 -0.694738 -0.28423 -0.660721 -0.702912 -0.520721 -0.484526 -0.466749 -0.708864 -0.528826 -0.705016 -0.626542 -0.332262 -0.703697 -0.690005 -0.169422 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 -0.0510932 0.706189 -0.706177 -0.0510933 0.70619 -0.706177 0.0510933 0.70619 -0.706177 0.0510933 0.706189 0 0.0961512 0.995367 -0.0420201 0.0720984 0.996512 0 0.0240723 0.99971 0 -0.072162 0.997393 -0.0629304 -0.0959605 0.993394 0 -0.0240723 0.99971 -0.706177 0.0510935 -0.706189 -0.706183 0.0510933 -0.706183 -0.706183 -0.0510931 -0.706183 -0.706177 -0.0510937 -0.706189 0 -0.117078 0.993123 0 -0.286299 -0.95814 0.0323179 -0.394961 -0.918129 0.0129622 -0.474302 -0.880267 -0.0156222 -0.679006 -0.733967 0.00369083 -0.732088 -0.681201 -0.00326096 -0.883455 -0.468506 -0.0251488 -0.924097 -0.38133 3.44646e-05 -0.964338 0.264674 -3.98677e-05 -0.999992 -0.00394165 -0.00662213 -0.999757 0.0210336 0.00506863 -0.971141 -0.238452 0.00404005 -0.713362 0.700784 -0.00869051 -0.782899 0.622089 0.00792333 -0.862944 0.505237 -0.00305079 -0.908255 0.418405 0.00554929 -0.97088 0.239503 0.0225876 -0.0612251 0.997868 -0.0121227 -0.446876 0.894514 0.00323321 -0.507676 0.861542 -4.50728e-06 -0.622117 0.782925 -5.91902e-07 -0.658931 0.752203 0 0.0408905 0.999164 0.00839492 0.0698941 0.997519 -0.00845272 0.427836 0.903817 0.00838058 0.478326 0.878142 -0.00041377 0.639689 0.768634 0.00245767 0.775539 0.631295 0.0133777 0.800098 0.59972 -0.00042583 0.890393 0.455193 0.00125766 0.960535 0.278156 0.0176826 0.97695 0.212733 0 0.997363 0.0725755 -0.994042 0.0104801 -0.10849 -0.971841 -0.022657 0.234546 -0.658919 0 0.752214 -0.108086 0.0955879 0.989535 -0.558296 0.0797713 0.825798 -0.341054 0.0903866 0.935688 -0.237327 0.101702 0.966091 -0.237623 0.0233828 0.971076 -0.153992 0 0.988072 -0.237623 -0.0233828 0.971076 -0.237429 -0.0934016 0.966904 -0.887883 0.0442364 0.457937 -0.739466 0.0647288 0.670075 -0.108163 -0.113779 0.987601 -0.341053 -0.0903868 0.935689 -0.658919 -0.0723266 0.748729 -0.558604 -0.0971739 0.823722 -0.73947 -0.0647283 0.67007 -0.971845 0.0226551 0.234528 -0.931696 0.0430568 0.360678 -0.931861 0 0.362816 -0.658697 0.0806447 0.748074 -0.658919 0 0.752214 -0.931861 0 0.362816 -0.931861 -0.0348854 0.361135 -0.888089 -0.0586507 0.455914 -0.994042 -0.01048 -0.10849 -0.994042 -0.0104801 -0.108491 -0.994053 -0.00262192 -0.10887 -0.994978 0 -0.100096 -0.994053 0.00262121 -0.10887 -0.994042 0.01048 -0.108491 0 -0.0721624 -0.997393 0.126161 -0.107262 -0.986194 0 -0.0361046 -0.999348 0 0.0721624 -0.997393 0.126162 0.0358161 -0.991363 0 0.108126 -0.994137 -0.738155 -0.475134 -0.47893 -0.933086 -0.230114 -0.276402 -0.885797 -0.161991 -0.434882 -0.902767 -0.202842 -0.379298 -0.900881 -0.227544 -0.369645 -0.893728 -0.187203 -0.407684 -0.982603 -0.133126 -0.129496 -0.968984 -0.17737 -0.172075 -0.959181 -0.205788 -0.193969 -0.978164 -0.142367 -0.151415 -0.993506 -0.0428537 -0.105404 -0.993503 -0.0486698 -0.102875 -0.955077 -0.207183 -0.211905 -0.937213 -0.235986 -0.256793 -0.812787 -0.568684 -0.126394 -0.759742 -0.590401 -0.272431 -0.532645 -0.809175 -0.248042 -0.600333 -0.766828 -0.227101 -0.364117 -0.910252 -0.19713 -0.456018 -0.872352 -0.176212 -0.187425 -0.972113 -0.140953 -0.145507 -0.463464 -0.874088 -0.172302 -0.630416 -0.756893 -0.88495 -0.16783 -0.434392 -0.712672 -0.351994 -0.606793 -0.697723 -0.384248 -0.604596 -0.461109 -0.520025 -0.718994 -0.423352 -0.561772 -0.710764 -0.179688 -0.630605 -0.755016 -0.275273 -0.846459 -0.455777 -0.918223 -0.236236 -0.317898 -0.916087 -0.238126 -0.322616 -0.77136 -0.552386 -0.316028 -0.722808 -0.518468 -0.45688 -0.503335 -0.699094 -0.50786 -0.487235 -0.705169 -0.515111 -0.353651 -0.803343 -0.479136 -0.177298 -0.859163 -0.480005 -0.30151 -0.945813 -0.120543 -0.175111 -0.781845 0.598377 -0.0983751 -0.662725 0.742373 -0.10052 -0.626087 0.773247 -0.274906 -0.941154 0.196609 -0.876426 -0.0946359 0.472146 -0.884046 -0.0865017 0.459325 -0.725698 -0.0976597 0.681047 -0.73982 -0.0884963 0.666959 -0.546207 -0.0917364 0.832612 -0.55329 -0.0887387 0.828249 -0.333632 -0.0777084 0.939495 -0.344985 -0.0734669 0.935729 -0.105759 -0.0695627 0.991956 -0.121708 -0.0644773 0.99047 -0.0684596 -0.909358 0.410343 -0.148721 -0.777067 0.611595 -0.342311 -0.753962 0.560682 -0.242339 -0.790196 0.562905 -0.521628 -0.722079 0.45443 -0.443216 -0.766668 0.464521 -0.684287 -0.653981 0.322583 -0.629469 -0.700838 0.335552 -0.792141 -0.577206 0.198359 -0.839075 -0.390423 0.378845 -0.858963 -0.364386 0.359731 -0.685631 -0.451989 0.570628 -0.721165 -0.422443 0.549056 -0.493427 -0.484563 0.722308 -0.546158 -0.454933 0.703382 -0.282718 -0.488573 0.82545 -0.351093 -0.461927 0.814468 -0.0853922 -0.469146 0.878983 -0.151904 -0.450626 0.879694 -0.147953 -0.280636 -0.948342 -0.205593 -0.315103 -0.926521 -0.341412 -0.298093 -0.891392 -0.425002 -0.300896 -0.853718 -0.484347 -0.260927 -0.83506 -0.687668 -0.203978 -0.696783 -0.647367 -0.260969 -0.716109 -0.87021 -0.0461708 -0.490513 -0.85001 -0.125874 -0.511506 -0.029029 -0.678119 -0.734378 -0.135882 -0.911277 -0.388729 0.182428 -0.890742 -0.416291 -0.290351 -0.956118 -0.0391852 -0.0131399 -0.996437 -0.0833128 -0.14355 -0.951985 0.270404 -0.324421 -0.917011 0.232039 -0.20939 -0.952356 0.221752 -0.489608 -0.859829 0.14484 -0.39806 -0.906821 0.138653 -0.641641 -0.765424 0.049219 -0.57574 -0.816413 0.044647 -0.805193 -0.588821 -0.0703928 -0.849341 -0.526438 0.0385063 -0.891406 -0.452686 0.0216819 -0.946584 -0.285126 0.150606 -0.938296 -0.304601 0.163763 -0.97139 -0.0819955 0.222887 -0.963018 -0.0999699 0.250205 -0.484353 0.260882 -0.835071 -0.146449 0.336549 -0.930208 -0.546585 0.088537 0.83271 -0.824707 0.559531 -0.0823555 -0.942264 0.255157 -0.216872 -0.971801 0.164043 -0.16939 -0.978816 0.147886 -0.141594 -0.989309 0.0721043 -0.126759 -0.993672 0.0431597 -0.103696 -0.851107 0.0711757 -0.520145 -0.873464 0.155215 -0.461486 -0.889402 0.177387 -0.421305 -0.901407 0.206209 -0.380715 -0.895308 0.209764 -0.392968 -0.91823 0.230254 -0.322238 -0.651395 0.216102 -0.727313 -0.692761 0.226547 -0.684659 -0.714395 0.371576 -0.592934 -0.74173 0.593926 -0.31159 -0.782195 0.559872 -0.273338 -0.708895 0.508745 -0.488514 -0.911958 0.238508 -0.333836 -0.938588 0.227488 -0.259428 -0.786962 0.607647 -0.107034 -0.849348 0.526427 0.0385176 -0.79219 0.57712 0.198411 -0.856725 0.37836 0.350522 -0.843571 0.375407 0.384002 -0.884012 0.0941062 0.457894 -0.877483 0.0872924 0.471597 -0.921892 0.264416 -0.283195 -0.959989 0.184343 -0.210805 -0.891439 0.45262 0.0217074 -0.944652 0.295066 0.143421 -0.941308 0.293309 0.16706 -0.970892 0.0954302 0.219687 -0.965065 0.0835444 0.248336 -0.139219 0.955831 0.258855 -0.171161 0.948763 0.265618 -0.0818058 0.891721 0.445131 -0.148643 0.777016 0.61168 -0.148777 0.776978 0.611695 -0.0946793 0.643513 0.759557 -0.146669 0.470704 0.870015 -0.0322193 0.429114 0.902675 -0.106328 0.0431123 0.993396 -0.174551 0.071185 0.982072 -0.333939 0.0734574 0.939728 -0.1836 0.857152 -0.481229 -0.234223 0.85853 -0.456143 -0.0680666 0.995623 0.0640433 -0.15451 0.986818 -0.0481414 -0.226241 0.967707 -0.111167 -0.114452 0.980479 -0.159882 -0.0516964 0.938199 -0.342215 -0.0913642 0.828607 -0.552324 -0.0352487 0.6947 -0.718436 -0.511668 0.446259 -0.734199 -0.553202 0.0918059 0.827973 -0.49906 0.464536 0.731536 -0.542565 0.475521 0.692462 -0.454264 0.746179 0.486683 -0.51392 0.74249 0.429645 -0.412108 0.895287 0.169198 -0.48002 0.870124 0.111648 -0.377666 0.910825 -0.166632 -0.447584 0.869543 -0.208719 -0.353601 0.803407 -0.479065 -0.487267 0.705211 -0.515023 -0.412912 0.540092 -0.733351 -0.463512 0.545678 -0.698135 -0.425037 0.300841 -0.85372 -0.344659 0.0784327 0.935446 -0.28781 0.467046 0.836082 -0.346265 0.484581 0.803294 -0.25301 0.768584 0.587592 -0.332876 0.776781 0.534607 -0.223316 0.940749 0.255187 -0.313057 0.929139 0.196715 -0.200944 0.973629 -0.108019 -0.291651 0.94381 -0.155444 -0.187455 0.870201 -0.455643 -0.269274 0.834031 -0.481543 -0.179512 0.630082 -0.755495 -0.178552 0.630733 -0.755179 -0.112025 0.322935 -0.939768 -0.341441 0.298029 -0.891402 -0.87091 0.0935873 -0.482449 -0.892971 0.155791 -0.422295 -0.690171 0.369813 -0.622015 -0.744778 0.49429 -0.448311 -0.503278 0.699166 -0.507817 -0.593137 0.763307 -0.25603 -0.54522 0.80866 -0.220918 -0.633572 0.77344 0.0194174 -0.588805 0.805132 0.0712124 -0.677989 0.671067 0.3 -0.639889 0.681954 0.354232 -0.718477 0.440042 0.53866 -0.691091 0.434098 0.577886 -0.739778 0.0971353 0.665802 -0.726935 0.0890136 0.680913 0 0.393349 0.919389 0 0.393349 0.919389 0 0.5 0.866025 0 0.5 0.866025 0 0.599539 0.800345 0 0.599539 0.800345 0 0.538797 0.842435 0 -0.196409 -0.980522 -0.032333 -0.119853 -0.992265 -0.00477475 0.00576553 -0.999972 0.0109506 0.255035 -0.96687 -0.00691314 0.290663 -0.956801 0.00189072 0.496277 -0.868162 0.0233531 0.630962 -0.775462 -0.0207693 0.701272 -0.712591 -0.00129384 0.811284 -0.584651 0.00323733 0.892364 -0.451305 -0.0314926 0.940742 -0.337659 -0.0069375 0.967135 -0.25417 0.000744446 0.938432 0.345464 -0.0031409 0.984906 0.173062 -0.0274181 0.994204 0.103959 -0.00213382 0.999543 -0.0301445 0.000704933 0.991009 -0.133793 -0.00398586 0.532024 0.84672 0.00339286 0.828526 0.559941 2.08523e-05 0.8328 0.553574 3.23727e-07 0.935091 0.354407 0 -0.599539 -0.800345 0 -0.599539 -0.800345 0 -0.5 -0.866025 0 -0.5 -0.866025 0 -0.39335 -0.919389 0 -0.39335 -0.919389 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.999444 -0.0333412 -0.0196776 -0.968778 -0.247148 0.000310115 -0.976536 -0.215354 -0.000319745 -0.795386 -0.606103 0 -0.795068 -0.606521 0.698663 -0.698663 -0.154075 0.698662 -0.698665 -0.154076 0.698662 -0.569061 -0.433637 0.698658 -0.569063 -0.433641 9.6556e-06 0.765336 -0.643631 0.0232823 0.885752 -0.463575 -0.0284612 0.81123 -0.584034 0.0225738 0.971146 -0.237417 0.0214642 0.970218 -0.241283 0 0.997062 -0.0766039 -2.27628e-05 0.613025 -0.790064 -0.0119878 0.646519 -0.762804 0.00847055 0.431556 -0.902046 1.06946e-05 0.469369 -0.883002 -2.48668e-05 0.242397 -0.970177 -0.00966471 0.20545 -0.97862 0.0146152 -0.134978 -0.990741 0 -0.171891 -0.985116 -0.696412 -0.0968765 -0.711073 -0.696414 -0.096876 -0.711072 -0.703785 0.172202 -0.689226 -0.504592 0.297729 -0.810398 -0.696408 0.696434 -0.173196 -0.696421 0.696422 -0.173189 -0.703796 0.576533 -0.415067 -0.504597 0.642641 -0.576536 -0.705062 0.458509 -0.540978 -0.705064 0.33285 -0.626176 0 0.580953 0.813937 -0.0420201 0.560695 0.826955 0 0.520703 0.853738 0 0.436202 0.899849 -0.0629303 0.413593 0.908285 0 0.479008 0.877811 -0.706172 -0.308849 -0.637129 -0.706182 -0.308844 -0.63712 -0.706182 -0.39734 -0.586027 -0.706174 -0.397345 -0.586034 0 0.395167 0.918609 0 -0.727016 -0.686621 0.0323181 -0.801113 -0.59764 0.0129636 -0.850891 -0.525183 -0.0156211 -0.955022 -0.296125 0.00368929 -0.974606 -0.223897 -0.00326234 -0.999347 0.0359859 -0.0251501 -0.990957 0.131804 3.42305e-05 -0.7028 0.711387 -4.01632e-05 -0.867989 0.496584 -0.00662204 -0.855298 0.518094 0.00506805 -0.960259 0.279065 0.0225866 0.445908 0.894794 -0.0133914 0.0455452 0.998873 -1.51065e-05 -0.00888615 0.999961 3.13572e-07 -0.19458 0.980887 0.00403911 -0.267394 0.963579 -0.0086912 -0.36696 0.930196 0.00792455 -0.494721 0.869016 -0.00304958 -0.577378 0.816471 0.00555022 -0.721054 0.692856 0 0.497962 0.867199 0.0125113 0.546102 0.837625 -0.000323747 0.662137 0.749382 0.00111473 0.827686 0.561191 0.00391972 0.822469 0.568796 -0.00423492 0.980333 0.197307 0 0.977775 0.209657 -0.994042 -0.045169 -0.099195 -0.971841 0.0976519 0.214452 -0.658921 0.376106 0.651435 -0.108095 0.577549 0.809168 -0.558292 0.481985 0.675279 -0.341051 0.546122 0.765137 -0.237327 0.571122 0.785809 -0.237623 0.505788 0.829285 -0.153991 0.494036 0.855696 -0.237621 0.465288 0.852668 -0.237426 0.402564 0.884065 -0.887885 0.267276 0.374463 -0.739466 0.391095 0.547938 -0.108169 0.395266 0.912176 -0.341042 0.389569 0.855527 -0.658921 0.311727 0.68458 -0.558605 0.327706 0.761951 -0.739472 0.278978 0.61266 -0.971845 0.136885 0.191782 -0.931696 0.217627 0.290828 -0.931861 0.181408 0.314208 -0.658697 0.443878 0.607529 -0.658919 0.376107 0.651436 -0.931861 0.181408 0.314208 -0.931861 0.150356 0.330195 -0.888089 0.177164 0.424159 -0.994042 -0.0633211 -0.0887152 -0.994042 -0.0633211 -0.0887153 -0.994053 -0.0567057 -0.0929732 -0.994978 -0.0500477 -0.0866851 -0.994053 -0.052165 -0.095595 -0.994042 -0.0451692 -0.0991955 0 -0.403429 -0.915011 0.12616 -0.464664 -0.876454 0 -0.436202 -0.899849 0 -0.530941 -0.847409 0.063502 -0.560058 -0.826016 0 -0.590708 -0.806885 -0.0684606 -0.582364 0.81004 -0.098388 -0.202781 0.974269 -0.738159 -0.650938 -0.177202 -0.933087 -0.337484 -0.124313 -0.8858 -0.357715 -0.295631 -0.902765 -0.36532 -0.22706 -0.90088 -0.38188 -0.206357 -0.893729 -0.365969 -0.259451 -0.982603 -0.180037 -0.0455828 -0.968982 -0.239653 -0.0603374 -0.959181 -0.275201 -0.0650878 -0.978164 -0.199003 -0.0599464 -0.993506 -0.0898136 -0.0698562 -0.993503 -0.0935865 -0.0647578 -0.955076 -0.285379 -0.0799252 -0.937213 -0.332765 -0.104398 -0.812788 -0.555692 0.17488 -0.759743 -0.647517 0.0592678 -0.532644 -0.824787 0.189778 -0.600328 -0.777647 0.18674 -0.364131 -0.886863 0.2844 -0.456014 -0.843588 0.283566 -0.187411 -0.912356 0.363983 -0.145511 -0.838414 -0.52525 -0.172306 -0.924401 -0.340284 -0.88495 -0.362544 -0.292274 -0.712672 -0.608238 -0.349493 -0.697728 -0.635061 -0.331471 -0.461104 -0.809855 -0.362655 -0.423346 -0.841894 -0.334654 -0.179707 -0.923624 -0.338561 -0.27529 -0.960938 0.0285193 -0.918229 -0.363525 -0.157177 -0.916086 -0.367535 -0.160329 -0.77136 -0.636394 0.00250566 -0.72281 -0.677445 -0.136434 -0.503332 -0.859365 -0.0902697 -0.487229 -0.868253 -0.093512 -0.353647 -0.935285 -0.0132707 -0.177296 -0.98406 0.0138861 -0.3015 -0.879374 0.36851 -0.274898 -0.71676 0.640848 -0.876428 0.154115 0.456204 -0.884046 0.154749 0.441039 -0.725699 0.255946 0.638634 -0.73982 0.256838 0.621853 -0.546201 0.336859 0.766936 -0.553286 0.337274 0.761657 -0.333631 0.402449 0.852482 -0.344998 0.404241 0.847093 -0.105767 0.435738 0.893838 -0.121692 0.439393 0.890014 -0.145528 -0.376723 0.914823 -0.171012 -0.368528 0.913751 -0.342321 -0.372605 0.862544 -0.242333 -0.402878 0.88259 -0.521635 -0.398124 0.754582 -0.443215 -0.431698 0.785619 -0.684278 -0.405078 0.606362 -0.629469 -0.439167 0.641016 -0.792139 -0.400696 0.46039 -0.839076 -0.148693 0.523299 -0.858963 -0.135702 0.493727 -0.685628 -0.106118 0.720176 -0.721164 -0.0913162 0.68672 -0.493424 -0.0584876 0.86782 -0.546158 -0.0422897 0.836614 -0.282729 -0.0103902 0.959144 -0.351093 0.00719211 0.936313 -0.0853839 0.0331986 0.995795 -0.106821 0.0384891 0.993533 -0.147952 -0.717212 -0.680968 -0.205593 -0.736152 -0.644835 -0.341447 -0.703845 -0.62291 -0.424996 -0.687443 -0.588897 -0.484342 -0.6435 -0.592724 -0.687666 -0.525041 -0.501445 -0.647373 -0.584049 -0.48969 -0.870213 -0.285231 -0.401713 -0.850009 -0.364771 -0.380037 -0.0289974 -0.954461 -0.296922 -0.135856 -0.983557 0.118989 0.18241 -0.979554 0.0848567 -0.29037 -0.84761 0.44412 -0.013129 -0.904599 0.426062 -0.143542 -0.689241 0.710171 -0.324412 -0.678136 0.65946 -0.209401 -0.713884 0.668223 -0.489618 -0.672207 0.555349 -0.398069 -0.715998 0.573488 -0.641642 -0.638264 0.42534 -0.575733 -0.684713 0.446878 -0.805193 -0.54513 0.233449 -0.84934 -0.436658 0.296566 -0.891411 -0.381191 0.245113 -0.946585 -0.171622 0.272987 -0.938296 -0.181912 0.294124 -0.97139 0.0404329 0.234022 -0.963017 0.0385254 0.266671 -0.146447 -0.173643 -0.973859 -0.824707 0.443391 -0.351087 -0.651395 -0.176512 -0.737921 -0.942265 0.112533 -0.315393 -0.9718 0.0573704 -0.22872 -0.978816 0.0572762 -0.196568 -0.989309 -0.00093482 -0.145829 -0.993672 -0.0144704 -0.111383 -0.851107 -0.198433 -0.486046 -0.873464 -0.0963208 -0.477267 -0.889404 -0.0570227 -0.453551 -0.901407 -0.0117741 -0.432813 -0.895309 -0.0148216 -0.445199 -0.91823 0.0382882 -0.394192 -0.741732 0.35856 -0.566805 -0.782192 0.348196 -0.516657 -0.708894 0.196331 -0.677439 -0.911958 0.0396375 -0.408365 -0.938587 0.0672964 -0.338417 -0.786961 0.472722 -0.396518 -0.849347 0.475159 -0.229857 -0.79219 0.599007 -0.116733 -0.856724 0.502932 0.11438 -0.84357 0.517115 0.144852 -0.884011 0.310445 0.349497 -0.877483 0.311395 0.36477 -0.92189 0.0873951 -0.377467 -0.959989 0.0542433 -0.274734 -0.891441 0.40283 -0.207511 -0.944652 0.327243 -0.0233306 -0.941309 0.337542 -0.00197849 -0.970892 0.192488 0.142536 -0.965064 0.196519 0.173294 -0.333926 0.533481 0.777104 -0.105763 0.556286 0.824233 -0.307203 0.478602 0.822537 -0.0132446 0.553151 -0.832976 -0.28363 0.563854 -0.775644 -0.1157 0.661343 0.741106 -0.0793939 0.823146 0.562252 -0.182736 0.839226 0.51216 -0.0109209 0.977953 0.208539 -0.144765 0.979245 0.14185 -0.0752944 0.993508 -0.0852769 -0.207759 0.946235 -0.247941 -0.181752 0.948963 -0.257752 0.0831672 0.826491 -0.556773 -0.375197 0.79755 -0.472378 -0.105892 0.753015 -0.649427 -0.0688825 0.424265 -0.902914 -0.100119 0.198431 -0.974988 -0.1785 0.16832 -0.969436 -0.112024 -0.190212 -0.975331 -0.341454 -0.187598 -0.920987 -0.692765 -0.146136 -0.706201 -0.714401 0.0253317 -0.699278 -0.412917 0.101066 -0.905144 -0.487269 0.353213 -0.79863 -0.353593 0.456241 -0.816588 -0.447578 0.64869 -0.615528 -0.377659 0.705485 -0.59972 -0.480018 0.809378 -0.338365 -0.412123 0.859933 -0.301116 -0.513933 0.85783 0.000829674 -0.45426 0.889554 0.0483964 -0.542561 0.758045 0.361932 -0.499061 0.768069 0.401259 -0.5532 0.493494 0.671143 -0.546586 0.493032 0.676878 -0.344654 0.53565 0.770904 -0.287805 0.822512 0.490553 -0.34628 0.821303 0.453378 -0.253025 0.959407 0.124567 -0.332861 0.940021 0.074601 -0.223301 0.942312 -0.24937 -0.313055 0.903016 -0.29421 -0.200945 0.789176 -0.580364 -0.291644 0.739645 -0.606523 -0.187447 0.525797 -0.829699 -0.269272 0.481521 -0.834045 -0.179694 0.168497 -0.969185 -0.463506 0.123506 -0.877444 -0.42503 -0.166327 -0.889767 -0.484354 -0.191611 -0.853631 -0.870904 -0.160189 -0.464613 -0.892969 -0.0762284 -0.443617 -0.690168 0.00925971 -0.72359 -0.744776 0.203914 -0.635395 -0.503297 0.351579 -0.789357 -0.593151 0.533015 -0.60338 -0.545228 0.589856 -0.595648 -0.63358 0.679521 -0.369903 -0.588804 0.732875 -0.340888 -0.677985 0.731165 -0.0757279 -0.639886 0.767708 -0.0342068 -0.718476 0.650418 0.246471 -0.691087 0.664886 0.283418 -0.739776 0.417023 0.528038 -0.726936 0.417545 0.54518 -0.939621 -0.13806 -0.313132 -0.939566 -0.1989 -0.278666 -0.938393 -0.214143 -0.271221 -0.939692 -0.213118 -0.267506 -0.939424 -0.214307 -0.267497 -0.939409 -0.214369 -0.267502 -0.939887 -0.213334 -0.266647 -0.939984 -0.213396 -0.266255 -0.939934 -0.213392 -0.266435 -0.939773 -0.213605 -0.266831 -0.939573 -0.213946 -0.267264 -0.939635 -0.124423 -0.318756 -0.939831 -0.124224 -0.318256 -0.940958 -0.125221 -0.314513 -0.939692 -0.125147 -0.318304 -0.939959 -0.123991 -0.317967 -0.939978 -0.123917 -0.317939 -0.939692 -0.125595 -0.318126 -0.939471 -0.124551 -0.319189 -0.939449 -0.124528 -0.319261 -0.939565 -0.141883 -0.311587 -0.94337 -0.135894 -0.302631 -0.936007 -0.168603 -0.308972 -0.939622 -0.160295 -0.30235 -0.939661 -0.178138 -0.29207 -0.937285 -0.185067 -0.295375 -0.94337 -0.194139 -0.269003 -0.939621 -0.20215 -0.276129 -0.939692 -0.212709 -0.26783 -0.149345 -0.398905 -0.904749 -0.488788 -0.351953 -0.798258 -0.346091 -0.554204 -0.75702 -0.655063 -0.446324 -0.609661 -0.850961 -0.310258 -0.4238 -0.850962 -0.310257 -0.423799 -0.850962 -0.278865 -0.445083 -0.850961 -0.278866 -0.445083 -0.850961 -0.246021 -0.464046 -0.850962 -0.246019 -0.464045 -0.850962 -0.211892 -0.480588 -0.850963 -0.211891 -0.480588 -0.655066 -0.304819 -0.691356 -0.573439 -0.337356 -0.746564 -0.573328 -0.383778 -0.723885 -0.57333 -0.383777 -0.723884 -0.57333 -0.435013 -0.694303 -0.57333 -0.435013 -0.694303 -0.573441 -0.477866 -0.66544 -0.488779 -0.515339 -0.703932 -0.346096 -0.378497 -0.858462 -0.202126 -0.400397 -0.893771 -0.202088 -0.458742 -0.865284 -0.202088 -0.458742 -0.865284 -0.202088 -0.519987 -0.829924 -0.20209 -0.519986 -0.829924 -0.202128 -0.573831 -0.793639 -0.149353 -0.584083 -0.797835 0.707101 0.45559 0.540783 0.671176 0.442955 0.594402 0.70647 0.42432 0.566439 0.70647 0.353872 0.612923 0.706477 0.353868 0.612917 0.706528 0.279991 0.649941 0.672815 0.291004 0.680174 0.707104 0.240538 0.66494 0.698073 0.385793 0.603207 0.698075 0.385792 0.603205 0.698074 0.609309 0.376079 0.618521 0.654388 0.434981 0.706895 0.661408 0.250678 0.698062 0.712154 0.0744695 0.69807 0.712147 0.074466 0.69807 0.673933 -0.241894 0.698069 0.673934 -0.241894 0.698071 0.502237 -0.510349 0.698062 -0.0858645 -0.710871 0.698069 -0.0858662 -0.710863 0.700598 0.207409 -0.682747 0.6349 0.249322 -0.73126 0.706891 0.351029 -0.614072 0.698059 0.502248 -0.510354 0.697828 0.327735 0.636888 0.697828 0.327735 0.636887 0.697828 0.0147344 0.716114 0.697829 0.0147347 0.716113 0.697829 -0.301259 0.649829 0.697828 -0.30126 0.64983 0.697828 -0.55604 0.451503 0.697834 -0.556035 0.451501 0.697835 -0.697829 0.161435 0.697832 -0.697832 0.161435 0.706472 -0.424319 -0.566437 0.70647 -0.42432 -0.566439 0.70647 -0.353871 -0.612923 0.706477 -0.353868 -0.612917 0.706477 -0.278388 -0.650685 0.706464 -0.278392 -0.650697 0.87924 -0.125535 -0.459541 0.887083 -0.051025 -0.458781 0.954993 0.0821847 -0.285016 0.960102 0.0884359 -0.2653 0.978436 0.0582612 -0.198165 0.978976 0.0581038 -0.195525 0.991396 -0.00377989 -0.130839 0.990797 -0.00127244 -0.135349 0.965171 0.189753 0.180106 0.793208 0.601566 -0.0945519 0.859466 0.489388 0.147706 0.839105 0.522775 0.150364 0.88419 0.291276 0.365192 0.876484 0.305379 0.372182 0.859292 0.349008 -0.373913 0.938544 0.0860376 -0.334265 0.933186 0.0719028 -0.352127 0.821647 0.485524 -0.298603 0.847486 0.482455 -0.221373 0.891282 0.409502 -0.194744 0.947044 0.321104 0.000174469 0.938317 0.345776 0.000953415 0.97091 0.188438 0.147729 0.989049 0.129092 0.071536 0.807334 0.175125 -0.56351 0.69324 0.466044 -0.549747 0.770718 0.538602 -0.340444 0.902132 0.0230724 -0.430844 0.887847 -0.0564834 -0.456659 0.749555 0.00903601 -0.66188 0.710137 -0.004043 -0.704052 0.275999 0.534785 -0.798642 0.145864 0.00065614 -0.989304 0.197816 -0.157628 -0.967483 0.147942 -0.19632 -0.969315 0.111221 0.826844 0.551324 0.0953788 0.5314 0.841735 0.105771 0.527766 0.842779 0.0780595 0.99624 -0.0375878 0.143584 0.976811 0.158821 0.177637 0.969289 0.170073 0.0973044 0.936489 0.336929 0.110869 0.826938 0.551255 0.0290463 0.253972 -0.966775 0.134948 0.618043 -0.774475 -0.130534 0.585892 -0.799807 0.156287 0.792519 -0.589481 0.2161 0.805167 -0.552274 0.0506197 0.889126 -0.454855 0.143407 0.967266 -0.209359 0.273422 0.922925 -0.271016 0.142392 0.978986 -0.145985 0.35422 0.484338 -0.799965 0.457103 0.688466 -0.563091 0.36317 0.709129 -0.604353 0.490831 0.827325 -0.273163 0.397286 0.864995 -0.306508 0.522583 0.850139 0.0645717 0.442844 0.895324 0.0477934 0.546614 0.730833 0.408773 0.493388 0.767607 0.409082 0.553357 0.46729 0.689518 0.546235 0.472287 0.691789 0.176403 0.530617 -0.829053 0.302663 0.77968 -0.548173 0.186317 0.790092 -0.583987 0.325657 0.918877 -0.222739 0.208487 0.94425 -0.254805 0.343273 0.92819 0.143623 0.24185 0.962446 0.123315 0.351501 0.789179 0.503629 0.282647 0.819773 0.49808 0.345029 0.503868 0.791879 0.333662 0.509793 0.792957 0.879549 -0.126443 -0.458701 0.763492 -0.147483 -0.628752 0.69396 -0.116223 -0.710572 0.651407 -0.150626 -0.743627 0.484444 -0.162599 -0.859579 0.918302 0.0577993 -0.391639 0.901023 0.0509532 -0.430769 0.758733 0.262211 -0.596296 0.805313 0.228499 -0.547046 0.700503 0.338338 -0.628349 0.633802 0.0756576 -0.769786 0.46111 0.119018 -0.879325 0.425657 -0.132612 -0.895114 0.341461 -0.155465 -0.926949 0.172207 0.198942 -0.964763 0.179197 0.20022 -0.963224 0.424093 0.163317 -0.890771 0.486872 0.377256 -0.787803 0.50267 0.376266 -0.778298 0.601393 0.571156 -0.558667 0.53188 0.595991 -0.601579 0.642854 0.698895 -0.313502 0.575094 0.740968 -0.346747 0.685234 0.728047 -0.0200357 0.629211 0.776453 -0.0348479 0.721675 0.629618 0.287692 0.685628 0.667423 0.290623 0.739943 0.390821 0.547489 0.725679 0.406495 0.555114 0.340894 0.563628 0.752406 0.994035 -0.054531 -0.0944505 0.994036 -0.0655599 -0.0871409 0.994251 -0.064198 -0.0857 0.991754 -0.0501654 -0.117931 0.996676 -0.0363047 -0.0729359 0.658679 0.376212 0.651618 0.931791 0.181498 0.314364 0.994046 -0.0446274 -0.0994072 0.993745 0.043925 0.102668 0.971837 0.0926945 0.216658 0.994056 -0.0601492 -0.0907459 0.994035 -0.0545309 -0.0944503 0.931791 0.181498 0.314364 0.931639 0.136915 0.336605 0.558439 0.508458 0.655451 0.739316 0.403705 0.538919 0.931791 0.217631 0.290523 0.88807 0.284805 0.360857 0.971843 0.14127 0.188586 0.237291 0.48572 0.84129 0.237291 0.582416 0.777486 0.108135 0.607636 0.78682 0.887837 0.181003 0.423064 0.739296 0.264874 0.619099 0.658467 0.289906 0.694532 0.558108 0.326389 0.76288 0.340881 0.36979 0.864323 0.658677 0.451109 0.6022 0.658677 0.376212 0.65162 0.237283 0.48572 0.841293 0.237186 0.375999 0.89575 0.108041 0.391047 0.914007 0.572899 -0.409813 -0.709817 0.850727 -0.315995 -0.420013 0.879516 -0.186273 -0.437898 0.654679 -0.297336 -0.694973 0.765001 -0.253329 -0.592113 0.845142 -0.213401 -0.490096 0.851114 -0.233936 -0.469977 0.850696 -0.262829 -0.455233 0.850696 -0.262829 -0.455233 0.851114 -0.290043 -0.437585 0.345772 -0.369087 -0.86268 0.488416 -0.343241 -0.802269 0.149213 -0.388946 -0.909096 0.201913 -0.388457 -0.899073 0.201873 -0.489706 -0.848195 0.844347 -0.321231 -0.428822 0.654697 -0.453186 -0.604974 0.57302 -0.48772 -0.658618 0.488423 -0.523162 -0.698387 0.345778 -0.562558 -0.750977 0.573014 -0.326521 -0.75169 0.572893 -0.409815 -0.709821 0.201868 -0.489706 -0.848197 0.201907 -0.584393 -0.785951 0.149213 -0.592828 -0.791385 0.146154 -0.784666 -0.602443 0.826272 -0.514738 0.228735 0.651429 -0.568646 -0.502276 0.880893 -0.370658 -0.294347 0.992268 -0.115974 -0.0442002 0.992327 -0.0929045 -0.0815846 0.976265 -0.213193 -0.0381593 0.978908 -0.198452 -0.0485424 0.963205 -0.263085 -0.0549821 0.942932 -0.328758 -0.0528935 0.902136 -0.375827 -0.211906 0.8958 -0.384886 -0.222273 0.919327 -0.363957 -0.149579 0.851019 -0.327627 -0.4104 0.740543 -0.670395 0.0465453 0.783615 -0.617547 0.0676983 0.707955 -0.690445 -0.148615 0.912307 -0.377984 -0.15756 0.939733 -0.327486 -0.0982578 0.785899 -0.574613 0.228434 0.847486 -0.432955 0.307111 0.793261 -0.382585 0.473673 0.856963 -0.135677 0.497197 0.844209 -0.113592 0.52384 0.884164 0.162481 0.438012 0.877674 0.176363 0.445629 0.923008 -0.37053 -0.103748 0.960832 -0.266499 -0.0760316 0.891326 -0.373334 0.257215 0.944822 -0.174615 0.277166 0.941841 -0.158824 0.29616 0.97092 0.0336479 0.23703 0.965173 0.0610592 0.254388 0.131205 -0.334836 0.933097 0.0963161 -0.137765 0.985771 0.14647 0.0609126 0.987338 0.0518744 0.107048 0.9929 0.106241 0.484462 0.868337 0.157102 0.461458 0.873141 0.334012 0.435931 0.835703 0.0122379 -0.995489 0.094086 0.24009 -0.96127 0.13534 0.150956 -0.328257 0.932448 0.0723452 -0.544679 0.835518 0.202045 -0.66322 0.720636 0.130337 -0.693438 0.70863 0.0119039 -0.890795 0.454249 0.320264 -0.815029 0.482865 0.105111 -0.928138 0.357087 0.0889048 -0.99525 -0.0396549 0.0328378 -0.967704 -0.249941 0.190212 -0.933057 -0.305327 0.091556 -0.773047 -0.627706 0.341474 -0.724978 -0.598166 0.693995 -0.557225 -0.455929 0.714752 -0.629597 -0.304527 0.412194 -0.84577 -0.338776 0.486909 -0.870872 -0.0670896 0.354198 -0.934966 0.0195482 0.447658 -0.848562 0.282037 0.378512 -0.860284 0.341527 0.48013 -0.679719 0.554488 0.413093 -0.668785 0.618127 0.514056 -0.403018 0.757181 0.45518 -0.373768 0.808151 0.542686 -0.0370951 0.839116 0.499644 -0.00529515 0.866215 0.553285 0.360448 0.750968 0.546652 0.366038 0.753119 0.344687 0.429066 0.834921 0.288264 0.0478234 0.956356 0.346237 0.013862 0.938045 0.253715 -0.339572 0.905715 0.33284 -0.376522 0.864551 0.224037 -0.662059 0.715182 0.313048 -0.684699 0.65817 0.20154 -0.882716 0.424493 0.291663 -0.883364 0.366879 0.187843 -0.979349 0.0747702 0.269305 -0.962522 0.0320474 0.179222 -0.934249 -0.308315 0.463857 -0.833129 -0.30122 0.425707 -0.708831 -0.562434 0.484453 -0.663081 -0.570639 0.875353 -0.333512 -0.350039 0.889584 -0.363658 -0.276395 0.689705 -0.642336 -0.334233 0.745683 -0.656171 -0.115743 0.502628 -0.862188 -0.0632203 0.593252 -0.783391 0.185343 0.546278 -0.802086 0.241327 0.633761 -0.646475 0.424754 0.590007 -0.643898 0.487122 0.678252 -0.411041 0.609114 0.640945 -0.389195 0.661601 0.7187 -0.0884182 0.689675 0.69173 -0.0607464 0.719597 0.739909 0.269873 0.6162 0.727074 0.285607 0.624333 0.939514 -0.134071 -0.315179 0.939604 -0.114005 -0.322718 0.939489 -0.113993 -0.323056 0.939579 -0.114161 -0.322737 0.939697 -0.115016 -0.322089 0.939843 -0.113771 -0.322103 0.939864 -0.113707 -0.322065 0.939744 -0.113875 -0.322357 0.939507 -0.205928 -0.273715 0.939903 -0.222055 -0.259372 0.939805 -0.222004 -0.259772 0.93969 -0.221436 -0.260671 0.939697 -0.221585 -0.260518 0.939544 -0.22257 -0.260228 0.939487 -0.222802 -0.260238 0.939528 -0.222658 -0.260212 0.939644 -0.222409 -0.260006 0.939777 -0.222173 -0.259728 0.939515 -0.205916 -0.273699 0.939511 -0.205921 -0.273707 0.939694 -0.18896 -0.285079 0.939693 -0.188959 -0.28508 0.939498 -0.171278 -0.296662 0.939498 -0.171278 -0.296662 0.939694 -0.152407 -0.306184 0.939693 -0.152406 -0.306184 0.939511 -0.134075 -0.315187 0.939508 -0.134077 -0.315195 0.93969 -0.114815 -0.32218 0 0.488987 0.872291 -0.0153093 0.457507 0.889074 0.0139154 0.109279 0.993914 -0.0215401 0.0205663 0.999556 -0.00264738 -0.131163 0.991357 0.00676894 -0.320352 0.947275 -0.0292771 -0.420417 0.906859 -0.000611811 -0.540304 0.841469 0 -0.974269 0.225387 -0.0389781 -0.985844 0.163073 -0.00187803 -0.929663 0.368408 0.0068104 -0.776287 0.630343 -0.0595017 -0.838441 0.541734 0.000715404 -0.690177 0.72364 -0.700053 0.700052 0.140896 -0.70004 0.700066 0.140894 -0.700049 0.389999 0.598191 -0.700048 0.39 0.598191 -0.700047 0.591048 0.400744 -0.776295 0.50474 0.37763 -0.706724 0.638977 0.303727 -0.458503 -0.5314 0.712312 -0.694738 0.28423 0.660721 -0.69474 0.284228 0.660719 -0.7057 0.0393288 0.707418 -0.754938 -0.00582749 0.65577 -0.624885 -0.159895 0.764168 -0.705014 -0.189635 0.683369 -0.703698 -0.35151 0.617454 -0.704397 -0.498852 0.504947 -0.704397 -0.607109 0.367755 -0.45848 -0.816373 0.351187 -0.694736 -0.576514 -0.430086 -0.694743 -0.576507 -0.430083 -0.702915 -0.693216 -0.159253 -0.466749 -0.878307 -0.103546 -0.705015 -0.708734 0.0255211 -0.703697 -0.682273 0.198278 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 0.308846 0.637124 -0.706177 0.308847 0.637125 -0.706177 0.397343 0.586031 -0.706174 0.397344 0.586034 0.694745 -0.306872 0.650506 0.487519 0.497605 0.717436 0.694737 -0.306877 0.650513 0.702913 -0.0182442 0.711042 0.494614 0.0718864 0.866135 0.705016 0.165924 0.689508 0.703698 0.329975 0.629226 0.704394 0.481119 0.521874 0.704395 0.59405 0.3885 0.487515 0.789657 0.372518 0.694743 0.591014 -0.409919 0.694742 0.591015 -0.40992 0.702918 0.6983 -0.135217 0.494617 0.866133 -0.0718872 0.705015 0.707429 0.0499804 0.703699 0.675016 0.221723 0.699629 -0.372838 0.609517 0.699628 -0.372839 0.609518 0.699627 -0.584376 0.411129 0.699627 -0.584376 0.411129 0.699629 -0.699638 0.145007 0.699627 -0.69964 0.145006 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.426654 0.904415 0 0.750948 -0.660361 -0.0478521 0.820759 -0.569267 -0.0190415 0.868976 -0.494489 0.0231323 0.964474 -0.263164 -0.00911222 0.950021 0.312054 0.0343669 0.986883 0.157736 0.00482694 0.997502 0.0704743 -0.00545848 0.981749 -0.190103 -0.00780428 0.677795 0.73521 -1.80568e-05 0.704185 0.710017 2.3653e-05 0.836916 0.547331 -1.20488e-05 0.836853 0.547427 -7.88057e-06 0.912021 0.410144 -0.0167067 0.1687 0.985526 0.0109693 0.343702 0.939015 -0.0114737 0.464397 0.885553 2.36695e-05 0.526062 0.850446 1.70687e-05 0.611314 0.791388 -0.0265314 -0.467535 0.883576 0.0157205 -0.069928 0.997428 1.85691e-05 -0.02565 0.999671 -5.93692e-06 0.233962 0.972246 0 -0.473875 0.880592 -0.018437 -0.521723 0.852916 -0.000259055 -0.641249 0.767333 0.000964894 -0.817871 0.575401 -0.00803964 -0.806483 0.591203 0.00859319 -0.979154 0.202939 0 -0.97561 0.219513 0 0.39335 -0.919389 0 0.39335 -0.919389 0 0.5 -0.866025 0 0.5 -0.866025 0 0.59954 -0.800345 0 0.59954 -0.800345 0 -0.599539 0.800345 0 -0.599539 0.800345 0 -0.5 0.866025 0 -0.5 0.866025 0 -0.393349 0.919389 0 -0.393349 0.919389 0.879241 0.335207 -0.338483 0.887083 0.371803 -0.273581 0.954993 0.287924 -0.0713347 0.960101 0.273975 -0.0560634 0.978435 0.200748 -0.0486277 0.978976 0.198381 -0.0474432 0.991397 0.111419 -0.0686937 0.990797 0.116579 -0.0687771 0.965171 -0.0611028 0.254384 0.793205 0.38267 0.473698 0.859465 0.116777 0.497677 0.839104 0.131169 0.52792 0.88419 -0.17063 0.434848 0.876485 -0.169632 0.450555 0.859292 0.498322 0.115294 0.938544 0.3325 -0.0926224 0.933187 0.340901 -0.113793 0.821646 0.501359 0.271176 0.847484 0.432944 0.307132 0.891283 0.373403 0.257264 0.947045 0.160402 0.278168 0.938319 0.172062 0.299921 0.970911 -0.0337145 0.237054 0.989049 0.00259422 0.147566 0.807334 0.575575 -0.130095 0.693241 0.709116 0.128731 0.770718 0.564133 0.296223 0.902132 0.384657 -0.195439 0.887847 0.367235 -0.277249 0.749549 0.577728 -0.323121 0.710136 0.607706 -0.355529 0.275999 0.959037 0.0638151 0.145867 0.857093 -0.494079 0.197821 0.759049 -0.620251 0.14794 0.741287 -0.654681 0.111229 -0.0640401 0.991729 0.0953847 -0.463265 0.881072 0.105767 -0.465984 0.878449 0.0780614 0.530683 0.843968 0.143589 0.350865 0.925352 0.177641 0.33736 0.924463 0.0973035 0.17645 0.979488 0.110866 -0.0639296 0.991777 0.0290507 0.964238 -0.26344 0.134951 0.979736 0.148007 -0.130548 0.985597 0.107494 0.156261 0.906773 0.391593 0.216095 0.880867 0.42116 0.0506097 0.838478 0.542581 0.143396 0.664941 0.733002 0.273419 0.696169 0.66377 0.142381 0.615914 0.77484 0.354226 0.934957 0.0194649 0.457112 0.831879 0.314684 0.363174 0.877948 0.311948 0.490829 0.650233 0.5799 0.397298 0.697939 0.595849 0.522597 0.369144 0.768521 0.442832 0.406278 0.799273 0.546608 0.0114084 0.837311 0.493396 0.0295227 0.869304 0.553364 -0.363497 0.749439 0.546229 -0.362964 0.754911 0.176404 0.983289 0.0450001 0.30266 0.864573 0.401138 0.186326 0.900791 0.392248 0.325672 0.652331 0.684399 0.208474 0.692797 0.690341 0.343261 0.339717 0.875651 0.241859 0.374425 0.895159 0.351507 -0.0415674 0.935262 0.282646 -0.0214628 0.958984 0.345024 -0.433853 0.832304 0.333672 -0.431827 0.837967 0.87955 0.334027 -0.338849 0.763484 0.470787 -0.442101 0.693959 0.557264 -0.455936 0.651408 0.568688 -0.502256 0.484444 0.66312 -0.570601 0.918302 0.368069 -0.145765 0.901023 0.398533 -0.171258 0.758732 0.647514 -0.0710662 0.805309 0.58801 -0.0756362 0.700506 0.713332 -0.0211688 0.633802 0.704482 -0.319374 0.461116 0.821023 -0.336591 0.425664 0.708883 -0.562401 0.341462 0.725028 -0.598112 0.172209 0.93498 -0.31009 0.179193 0.934287 -0.308216 0.424096 0.853088 -0.303948 0.486875 0.870884 -0.0671881 0.502667 0.86216 -0.0632941 0.601391 0.769398 0.215305 0.531873 0.818983 0.215356 0.64285 0.620951 0.448514 0.575092 0.670775 0.468326 0.685232 0.38138 0.620489 0.629214 0.418408 0.655 0.721678 0.0656556 0.689109 0.685622 0.0820237 0.723322 0.739939 -0.278729 0.61221 0.725683 -0.277496 0.629587 0.146163 0.129402 -0.980761 0.82627 -0.45546 -0.331413 0.651433 0.150658 -0.743597 0.880894 0.06958 -0.46817 0.992268 -0.0197099 -0.122537 0.992327 0.0242019 -0.12125 0.976264 -0.0735501 -0.203711 0.978908 -0.0571869 -0.196136 0.963205 -0.083926 -0.255329 0.942932 -0.118571 -0.31116 0.902137 -0.0043974 -0.431428 0.895801 5.0589e-05 -0.444455 0.919327 -0.0524373 -0.389985 0.851019 0.191601 -0.488934 0.740541 -0.37551 -0.557307 0.783617 -0.367404 -0.500958 0.707955 -0.216518 -0.672249 0.912307 -0.0525395 -0.406123 0.939733 -0.0786477 -0.33274 0.7859 -0.485135 -0.383413 0.847487 -0.482442 -0.221394 0.793262 -0.601503 -0.0944926 0.856964 -0.498424 0.131099 0.844209 -0.510454 0.163547 0.884163 -0.298089 0.35972 0.877676 -0.297744 0.375543 0.923009 -0.0954141 -0.37276 0.960832 -0.0674029 -0.26881 0.891327 -0.409419 -0.194708 0.944822 -0.32734 -0.0126409 0.94184 -0.335897 0.0105366 0.970919 -0.18845 0.147656 0.965173 -0.189777 0.180073 0.262977 -0.952698 -0.152348 0.0792511 -0.976049 -0.202603 0.103117 -0.978205 0.180225 0.0255671 -0.975758 0.217354 0.16512 -0.822954 0.543582 0.0785318 -0.806855 0.585507 0.114866 -0.640029 0.759716 0.334006 -0.505777 0.79538 0.105778 -0.527832 0.842736 0.273499 -0.459361 0.845095 0.300419 -0.593828 -0.746403 0.0368564 -0.576852 -0.816017 0.116737 -0.826174 -0.551188 0.0237755 -0.855354 -0.517498 0.108082 -0.945338 -0.307659 0.0615975 -0.460927 -0.885298 0.111889 -0.235634 -0.96538 0.19022 -0.202111 -0.960712 0.0915633 0.157091 -0.98333 0.341453 0.155543 -0.926939 0.693998 0.116232 -0.710533 0.714755 -0.0510737 -0.697508 0.412209 -0.129499 -0.901839 0.48692 -0.377328 -0.787739 0.354181 -0.484427 -0.799929 0.447644 -0.668545 -0.593854 0.37852 -0.725907 -0.574267 0.480135 -0.820057 -0.311412 0.413097 -0.869704 -0.270122 0.514057 -0.857246 0.0295658 0.455177 -0.886765 0.080386 0.542685 -0.745245 0.387431 0.499638 -0.752814 0.428524 0.553284 -0.470132 0.687643 0.546658 -0.4692 0.693553 0.34468 -0.508532 0.789044 0.288263 -0.804318 0.519593 0.346232 -0.805441 0.481029 0.253712 -0.954158 0.158783 0.33284 -0.936984 0.1062 0.224033 -0.950396 -0.215769 0.313046 -0.912342 -0.263883 0.201536 -0.808978 -0.552211 0.29166 -0.759407 -0.58158 0.18784 -0.554429 -0.810756 0.269275 -0.509032 -0.817543 0.179186 -0.200112 -0.963248 0.463854 -0.155693 -0.872123 0.425703 0.132668 -0.895084 0.484446 0.162646 -0.859569 0.875353 0.136383 -0.46385 0.889583 0.0575358 -0.453135 0.689703 -0.0317137 -0.723397 0.745681 -0.227848 -0.626135 0.502634 -0.376337 -0.778286 0.593258 -0.552206 -0.585758 0.546283 -0.61004 -0.573957 0.633763 -0.691081 -0.347492 0.590004 -0.74381 -0.314072 0.678251 -0.73303 -0.0514149 0.640945 -0.767561 -0.00625309 0.718701 -0.641485 0.268266 0.691734 -0.653561 0.307186 0.739911 -0.39871 0.541814 0.727069 -0.397887 0.559515 0.572893 0.409815 -0.70982 0.850727 0.205745 -0.483666 0.879517 0.286093 -0.380264 0.65468 0.453196 -0.604986 0.764995 0.386125 -0.515452 0.845142 0.317735 -0.429859 0.851114 0.290042 -0.437584 0.850697 0.262828 -0.455232 0.850697 0.262828 -0.455232 0.851115 0.233942 -0.469973 0.345772 0.562559 -0.750979 0.488417 0.523164 -0.69839 0.149209 0.592828 -0.791386 0.20191 0.584392 -0.78595 0.20187 0.489706 -0.848196 0.844347 0.210755 -0.492605 0.654702 0.297328 -0.694955 0.573014 0.326522 -0.75169 0.488416 0.343242 -0.802269 0.345759 0.369089 -0.862684 0.573018 0.487721 -0.658619 0.572897 0.409814 -0.709819 0.201873 0.489706 -0.848196 0.201913 0.388456 -0.899073 0.149221 0.388946 -0.909095 0.340888 -0.369789 0.864321 0.994035 0.0545309 -0.0944504 0.994036 0.0426862 -0.100347 0.994251 0.0421194 -0.098447 0.991754 0.0770489 -0.10241 0.996676 0.0450111 -0.0679078 0.658679 -0.376212 0.651619 0.931791 -0.181498 0.314364 0.994046 0.0637754 -0.0883519 0.993746 -0.0669499 0.0893737 0.971837 -0.141285 0.188606 0.994056 0.0485152 -0.0974634 0.994035 0.0545311 -0.0944507 0.931791 -0.181498 0.314364 0.931639 -0.223051 0.286875 0.558447 -0.313407 0.768058 0.73931 -0.264868 0.619084 0.931791 -0.142784 0.333734 0.888074 -0.170106 0.427071 0.971842 -0.0926858 0.216638 0.237285 -0.48572 0.841292 0.237285 -0.382115 0.893131 0.108132 -0.377588 0.919638 0.887837 -0.275883 0.368286 0.739299 -0.403716 0.538934 0.658467 -0.45653 0.598332 0.558104 -0.49748 0.664103 0.34089 -0.563629 0.752407 0.658678 -0.295966 0.691771 0.658678 -0.376213 0.651619 0.237287 -0.48572 0.841291 0.237189 -0.587742 0.773499 0.108037 -0.59603 0.795661 0.939515 0.205917 -0.273697 0.939603 0.222483 -0.260092 0.93949 0.222776 -0.260247 0.939578 0.222422 -0.260234 0.939697 0.221425 -0.260653 0.939843 0.222065 -0.259582 0.939865 0.222064 -0.259504 0.939743 0.222234 -0.259798 0.939508 0.13408 -0.315195 0.939902 0.113598 -0.321993 0.939805 0.113965 -0.322147 0.93969 0.115027 -0.322104 0.939697 0.11482 -0.322159 0.939545 0.11408 -0.322864 0.939487 0.113973 -0.323069 0.939528 0.114022 -0.322934 0.939641 0.11397 -0.322623 0.939778 0.113842 -0.322268 0.939514 0.134073 -0.315178 0.939511 0.134077 -0.315186 0.939694 0.152411 -0.306182 0.939694 0.15241 -0.306182 0.939498 0.171278 -0.296662 0.939498 0.171278 -0.296662 0.939693 0.188959 -0.285081 0.939693 0.188959 -0.285081 0.939511 0.205923 -0.273706 0.939508 0.205929 -0.273713 0.93969 0.221611 -0.260522 0 -0.991268 -0.131864 -0.0350629 -0.970877 -0.237 -0.0184724 -0.95455 -0.297478 0.0223816 -0.855451 -0.517399 -0.001263 -0.817965 -0.575266 0.00124556 -0.643174 -0.765719 0.0081569 -0.658194 -0.752804 -0.00662102 -0.466165 -0.884673 -8.23474e-06 -0.486198 -0.873849 3.10789e-05 -0.265116 -0.964216 0.00862887 -0.242604 -0.970087 -0.0139218 0.104978 -0.994377 0 0.127732 -0.991809 0.696792 0.0753064 -0.713309 0.696796 0.0753047 -0.713306 0.696797 -0.261827 -0.667772 0.324184 -0.250798 -0.912143 0.696796 -0.696809 -0.170097 0.696799 -0.696806 -0.170095 0.703909 -0.580993 -0.408606 0.535518 -0.635875 -0.555773 0.705124 -0.46673 -0.533819 0.705123 -0.344756 -0.619633 0 0.998721 -0.050563 0.0226858 0.956855 -0.289679 -0.00893465 0.974602 -0.223767 0.00755008 0.779396 -0.626486 0 0.767191 -0.641419 -0.697962 0.697975 -0.160254 -0.697961 0.697975 -0.160254 -0.697963 0.558168 -0.448661 -0.697963 0.558168 -0.448661 -0.69811 0.312316 0.644284 -0.698108 0.312318 0.644285 -0.698107 0.560475 0.445549 -0.69811 0.560472 0.445549 -0.69811 0.698121 0.158964 -0.698109 0.698122 0.158964 -0.69811 -0.307665 0.646518 -0.698111 -0.307665 0.646516 -0.698111 0.00258181 0.715985 -0.842205 -0.0503108 0.536805 -0.705432 0.0921894 0.702757 -0.458488 -0.882589 -0.104048 -0.694738 -0.430087 0.57651 -0.694736 -0.430088 0.576512 -0.705697 -0.59298 0.387771 -0.754937 -0.570829 0.322838 -0.624884 -0.741737 0.243611 -0.705014 -0.686633 0.177455 -0.703697 -0.710487 0.00431557 -0.704394 -0.686725 -0.179547 -0.704394 -0.622038 -0.341903 -0.458503 -0.712313 -0.531399 -0.694739 0.084212 -0.714315 -0.694741 0.0842123 -0.714313 -0.702916 -0.208694 -0.679968 -0.466759 -0.34948 -0.812404 -0.705015 -0.376467 -0.601022 -0.703697 -0.512854 -0.491722 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 -0.397342 0.586031 -0.706173 -0.397345 0.586035 -0.706173 -0.308848 0.637128 -0.706175 -0.308847 0.637127 0 -0.414414 0.910089 -0.0420202 -0.435817 0.899054 0 -0.479008 0.877811 0 -0.561191 0.827687 -0.062931 -0.579801 0.812324 0 -0.520702 0.853739 -0.706178 0.397342 -0.586031 -0.706182 0.39734 -0.586027 -0.706182 0.308844 -0.63712 -0.706175 0.308847 -0.637126 0 -0.597955 0.80153 0 0.231128 -0.972923 0.0323181 0.11702 -0.992604 0.0129598 0.0293646 -0.999485 -0.0156228 -0.221054 -0.975137 0.00369034 -0.293407 -0.955981 -0.0032609 -0.530835 -0.847469 -0.0251501 -0.609626 -0.79229 3.26462e-05 -0.967479 -0.252951 -4.18315e-05 -0.86405 -0.503406 -0.00662006 -0.876327 -0.481672 0.00506926 -0.721813 -0.69207 0.0225875 -0.551958 0.833566 -0.0133913 -0.842277 0.538879 -1.47918e-05 -0.870435 0.492283 5.74971e-07 -0.946761 0.321939 0.00403975 -0.968181 0.250219 -0.00869055 -0.989054 0.147301 0.00792442 -0.99995 0.0060738 -0.00305021 -0.995774 -0.0917856 0.00554986 -0.960556 -0.27803 -0.00101361 0.269991 0.962862 0 -0.576675 0.816974 0.0140745 -0.429662 0.90288 0.000859313 0.168169 0.985758 0.0120156 0.0208776 0.99971 0.0163227 0.00360546 0.99986 -0.00344526 -0.187072 0.98234 0.00894433 -0.412085 0.911102 0.0133874 0.416171 0.909188 0.0187232 0.436125 0.899691 -0.0014639 0.572224 0.820096 0.00147611 0.692057 0.721841 0.0193578 0.782647 0.622165 0.0054668 0.816306 0.577594 0 0.975042 0.22202 0.0315521 0.988751 0.146202 -0.00301713 0.925574 0.378554 -0.994042 0.0633212 -0.0887155 -0.971841 -0.136894 0.191794 -0.658919 -0.376107 0.651436 -0.108084 -0.411986 0.904757 -0.558297 -0.343815 0.755047 -0.341055 -0.389567 0.855523 -0.237325 -0.394969 0.887511 -0.237621 -0.465288 0.852668 -0.15399 -0.494036 0.855696 -0.237618 -0.505788 0.829286 -0.237423 -0.564341 0.790664 -0.887884 -0.190658 0.418701 -0.739466 -0.278981 0.612666 -0.108166 -0.592335 0.798398 -0.341051 -0.546121 0.765137 -0.658919 -0.437 0.612255 -0.558603 -0.496017 0.664778 -0.739469 -0.391093 0.547935 -0.971845 -0.0976448 0.214436 -0.931696 -0.143051 0.333884 -0.931861 -0.181408 0.314208 -0.658697 -0.304197 0.688173 -0.658919 -0.376107 0.651436 -0.931861 -0.181408 0.314208 -0.931861 -0.210779 0.295309 -0.88809 -0.278749 0.365507 -0.994042 0.0451691 -0.0991952 -0.994042 0.0451691 -0.0991953 -0.994053 0.0521642 -0.0955951 -0.994978 0.0500475 -0.0866848 -0.994053 0.0567049 -0.0929734 -0.994042 0.063321 -0.088715 0 0.436202 -0.899849 0.126161 0.400206 -0.9077 0 0.468406 -0.883513 0 0.561191 -0.827687 0.126162 0.526699 -0.840638 0 0.590708 -0.806885 -0.0684643 -0.992698 -0.0993194 -0.0983851 -0.94513 0.311527 -0.738156 -0.172012 -0.652332 -0.933087 -0.0610841 -0.354425 -0.8858 0.0771631 -0.457608 -0.902766 0.0139798 -0.429904 -0.90088 -0.0122354 -0.433896 -0.893728 0.0417167 -0.446666 -0.982603 -0.0505423 -0.178708 -0.968983 -0.0675713 -0.237711 -0.95918 -0.0812338 -0.270877 -0.978164 -0.0475857 -0.202312 -0.993506 0.0155896 -0.112709 -0.993503 0.00928725 -0.113428 -0.955075 -0.0734725 -0.287111 -0.937214 -0.0759716 -0.340381 -0.812787 -0.4293 -0.3938 -0.759743 -0.375089 -0.53113 -0.53265 -0.576746 -0.619394 -0.600326 -0.550547 -0.580092 -0.364126 -0.689732 -0.625845 -0.45601 -0.667373 -0.588785 -0.187418 -0.771396 -0.60813 -0.145505 0.0356609 -0.988715 -0.172299 -0.167507 -0.970698 -0.884951 0.0718475 -0.460109 -0.712673 -0.00144548 -0.701495 -0.697725 -0.0304736 -0.715717 -0.461102 -0.0908648 -0.882683 -0.423351 -0.131126 -0.896426 -0.179697 -0.168611 -0.969164 -0.275282 -0.505165 -0.817941 -0.918228 -0.0456422 -0.393414 -0.916086 -0.0449177 -0.398458 -0.771361 -0.320365 -0.54988 -0.72281 -0.220563 -0.654903 -0.503327 -0.351504 -0.789371 -0.487234 -0.353139 -0.798684 -0.35364 -0.456155 -0.816616 -0.177318 -0.504053 -0.845274 -0.301516 -0.758823 -0.5773 -0.274913 -0.913364 -0.300315 -0.876428 -0.318028 0.36157 -0.884047 -0.304574 0.354535 -0.725698 -0.425099 0.540974 -0.739821 -0.410119 0.533355 -0.546207 -0.495751 0.675195 -0.553285 -0.490976 0.672917 -0.333634 -0.537045 0.774771 -0.344991 -0.531487 0.77363 -0.105757 -0.556221 0.824278 -0.121701 -0.551075 0.825533 -0.145528 -0.980622 0.13116 -0.17101 -0.975597 0.13772 -0.342315 -0.93329 0.108586 -0.242334 -0.965784 0.0923936 -0.521637 -0.852548 0.032507 -0.443211 -0.896217 0.0189481 -0.684279 -0.727663 -0.0476273 -0.629473 -0.774716 -0.0598217 -0.792139 -0.599057 -0.116817 -0.839077 -0.527536 0.132879 -0.858962 -0.495434 0.129344 -0.685631 -0.676748 0.268184 -0.721169 -0.64037 0.264275 -0.493423 -0.780798 0.383259 -0.546156 -0.745674 0.381684 -0.282727 -0.835838 0.470575 -0.351088 -0.807276 0.474386 -0.0853873 -0.845784 0.526648 -0.106822 -0.841181 0.530098 -0.147947 0.231134 -0.961607 -0.205594 0.19037 -0.959943 -0.341424 0.187536 -0.92101 -0.424996 0.166276 -0.889793 -0.484349 0.191565 -0.853644 -0.687667 0.171745 -0.705421 -0.647368 0.132056 -0.75065 -0.870212 0.205277 -0.447875 -0.85001 0.146741 -0.505914 -0.0290107 -0.220082 -0.97505 -0.135872 -0.594826 -0.792288 0.182433 -0.56326 -0.805888 -0.290362 -0.808428 -0.51199 -0.013127 -0.821283 -0.57037 -0.143534 -0.959648 -0.241813 -0.32442 -0.910175 -0.257552 -0.20939 -0.935641 -0.284133 -0.489616 -0.817049 -0.304478 -0.398066 -0.854654 -0.333332 -0.641642 -0.687486 -0.340087 -0.575733 -0.729362 -0.369544 -0.805193 -0.474735 -0.355374 -0.849342 -0.475159 -0.229874 -0.891409 -0.402872 -0.207567 -0.946586 -0.322224 -0.012135 -0.938296 -0.345675 -0.0104779 -0.97139 -0.182454 0.152028 -0.963017 -0.211681 0.1667 -0.146449 0.756566 -0.637307 -0.824707 0.525747 0.208444 -0.651394 0.550802 -0.521826 -0.942264 0.329408 -0.0602401 -0.971801 0.226761 -0.064676 -0.978816 0.19887 -0.0486816 -0.989309 0.125824 -0.0737242 -0.993672 0.0892254 -0.0682233 -0.851107 0.321712 -0.414873 -0.873462 0.365167 -0.322051 -0.889404 0.364277 -0.276159 -0.901406 0.368942 -0.226604 -0.895308 0.378145 -0.235437 -0.91823 0.360525 -0.163938 -0.741732 0.670148 0.0271188 -0.782194 0.621534 0.0432183 -0.708894 0.684844 -0.168694 -0.911959 0.373471 -0.169855 -0.938587 0.326725 -0.110929 -0.786961 0.579756 0.211129 -0.849347 0.436641 0.29657 -0.792188 0.400596 0.460392 -0.856723 0.152409 0.492744 -0.843568 0.133111 0.520263 -0.88401 -0.147451 0.443603 -0.877484 -0.160199 0.45206 -0.921891 0.37059 -0.113048 -0.959989 0.265048 -0.0903923 -0.89144 0.381127 0.245108 -0.944652 0.183826 0.271736 -0.941308 0.170484 0.291331 -0.970892 -0.0271978 0.237968 -0.965065 -0.051817 0.256837 -0.0703929 0.577502 0.813349 -0.218121 0.68738 0.692771 -0.128122 0.426973 0.895142 -0.235908 0.371325 0.898034 -0.122752 0.279739 0.952196 -0.154 -0.402697 0.902286 -0.0814462 -0.182025 0.979915 -0.241039 -0.0182409 0.970344 -0.132202 0.0321553 0.990701 -0.0950346 0.176154 0.979764 -0.108057 -0.572706 0.812608 -0.222496 -0.423725 0.878039 -0.333937 -0.406249 0.850557 -0.307514 0.945886 0.103607 -0.0132373 0.997954 0.0625535 -0.11846 0.924147 0.363209 -0.217943 0.894878 0.389479 -0.0214554 0.818044 0.574756 -0.19798 0.695804 0.690406 -0.0926621 0.993956 -0.0588711 -0.0301073 0.955594 -0.293144 -0.178503 0.923715 -0.338949 -0.112026 0.749556 -0.652392 -0.34147 0.703795 -0.622953 -0.692765 0.53852 -0.479659 -0.7144 0.618258 -0.327704 -0.412913 0.834411 -0.36505 -0.487267 0.868242 -0.0934206 -0.353595 0.935306 -0.0131776 -0.447578 0.857409 0.254017 -0.377656 0.872117 0.311109 -0.480013 0.697726 0.531757 -0.412113 0.690744 0.594168 -0.513927 0.428194 0.743323 -0.454267 0.402867 0.794569 -0.542567 0.0655809 0.837449 -0.499061 0.0365304 0.865796 -0.553201 -0.334481 0.762949 -0.546584 -0.33968 0.765417 -0.344659 -0.399798 0.849336 -0.287811 -0.0135699 0.957591 -0.346267 0.01801 0.937963 -0.253013 0.371822 0.893159 -0.332865 0.405408 0.851379 -0.223306 0.687118 0.691378 -0.313061 0.706302 0.634925 -0.200952 0.897196 0.393265 -0.291658 0.895083 0.337286 -0.187456 0.981438 0.0405011 -0.269273 0.963064 -1.23572e-05 -0.179691 0.923587 -0.338671 -0.463505 0.821642 -0.331764 -0.425028 0.687397 -0.588929 -0.48435 0.643462 -0.592758 -0.870905 0.322273 -0.371031 -0.892969 0.346069 -0.287822 -0.690173 0.631274 -0.353772 -0.744779 0.652222 -0.141104 -0.503287 0.859398 -0.090201 -0.593142 0.789055 0.159922 -0.545226 0.810776 0.213006 -0.633577 0.660108 0.403531 -0.588806 0.661657 0.464239 -0.677989 0.431162 0.595341 -0.639889 0.413474 0.647751 -0.718478 0.111758 0.686513 -0.691091 0.0869961 0.717513 -0.739778 -0.248778 0.62517 -0.726932 -0.26337 0.634197 -0.939621 0.20215 -0.27613 -0.939565 0.141883 -0.311587 -0.938393 0.127812 -0.321064 -0.939692 0.125107 -0.31832 -0.939426 0.124512 -0.319335 -0.939407 0.124479 -0.319404 -0.939888 0.124255 -0.318075 -0.939983 0.123892 -0.317936 -0.939935 0.124042 -0.318018 -0.939773 0.124281 -0.318404 -0.939573 0.124484 -0.318914 -0.939635 0.21384 -0.267132 -0.939831 0.213505 -0.266707 -0.940955 0.209773 -0.265705 -0.939692 0.213086 -0.267533 -0.93996 0.213373 -0.266359 -0.939978 0.213385 -0.266286 -0.939693 0.212708 -0.26783 -0.939472 0.214149 -0.267458 -0.93945 0.214224 -0.267474 -0.939566 0.1989 -0.278666 -0.94337 0.194139 -0.269004 -0.936007 0.183277 -0.300501 -0.939622 0.181696 -0.289995 -0.93966 0.163872 -0.300308 -0.937285 0.163269 -0.30796 -0.94337 0.135894 -0.302631 -0.939621 0.13806 -0.313132 -0.939692 0.125596 -0.318126 -0.149347 0.584083 -0.797836 -0.488783 0.515338 -0.70393 -0.34607 0.378501 -0.858471 -0.655061 0.304821 -0.69136 -0.850962 0.211892 -0.480589 -0.850962 0.211892 -0.480589 -0.850962 0.24602 -0.464046 -0.850962 0.24602 -0.464045 -0.850962 0.278865 -0.445082 -0.850962 0.278865 -0.445083 -0.850962 0.310257 -0.423799 -0.850962 0.310256 -0.423798 -0.655066 0.446323 -0.60966 -0.573443 0.477865 -0.665439 -0.573332 0.435013 -0.694302 -0.573332 0.435013 -0.694301 -0.573332 0.383777 -0.723883 -0.573328 0.383777 -0.723885 -0.573439 0.337355 -0.746565 -0.488784 0.351953 -0.79826 -0.346112 0.554199 -0.757014 -0.202128 0.573831 -0.793639 -0.20209 0.519987 -0.829924 -0.202086 0.519987 -0.829925 -0.202086 0.458742 -0.865285 -0.202088 0.458742 -0.865284 -0.202126 0.400396 -0.893772 -0.149349 0.398904 -0.904749 0.707102 -0.240539 0.664943 0.671178 -0.293289 0.68081 0.706474 -0.278389 0.650688 0.706474 -0.35387 0.61292 0.70647 -0.353871 0.612923 0.706522 -0.422874 0.567454 0.672819 -0.443544 0.592101 0.707105 -0.455583 0.540784 0.706467 0.278392 -0.650694 0.706474 0.278389 -0.650687 0.706474 0.35387 -0.61292 0.706474 0.35387 -0.61292 0.706474 0.424317 -0.566435 0.706474 0.424317 -0.566435 0 -0.997954 -0.0639373 -0.0265339 -0.970062 -0.241405 -0.0347799 -0.974439 -0.221942 2.33936e-05 -0.682407 -0.730972 2.49901e-05 -0.771883 -0.635765 -0.0119372 -0.807924 -0.589166 0.000129947 -0.854838 -0.518895 -0.000178866 -0.918868 -0.394565 -0.0156813 -0.580416 -0.814169 0.0107044 -0.641749 -0.76684 -0.00974445 -0.428389 -0.903542 -7.59231e-06 -0.455774 -0.890096 2.6777e-05 -0.199215 -0.979956 0.0117738 -0.227325 -0.973748 -0.0078768 0.0223697 -0.999719 -1.16243e-05 -0.00576816 -0.999983 2.74585e-05 0.235887 -0.971781 0.0109358 0.262885 -0.964765 -0.0166382 0.584455 -0.811256 0 0.606522 -0.795067 0.696399 0.419495 -0.582282 0.6964 0.419494 -0.582281 0.6964 0.097661 -0.710978 0.3328 0.22244 -0.916387 0.705271 -0.00408926 -0.708926 0.704462 -0.161353 -0.691157 0.52401 -0.293086 -0.799696 0.6964 -0.696413 -0.173306 0.696402 -0.696412 -0.173305 0.703501 -0.574228 -0.418747 0.530093 -0.6309 -0.566539 0.705268 -0.454988 -0.543675 0.704459 -0.323483 -0.63174 0 0.982084 -0.188441 0.0342202 0.959408 -0.279937 0 0.995518 -0.0945701 -0.70068 0.700693 -0.134448 -0.700681 0.700693 -0.134448 -0.994042 0.0991952 -0.0451691 -0.971841 -0.214451 0.0976515 -0.658918 -0.651437 0.376107 -0.108089 -0.809168 0.577549 -0.558293 -0.675278 0.481984 -0.341056 -0.765136 0.546121 -0.237325 -0.785809 0.571123 -0.237621 -0.829285 0.505789 -0.153988 -0.855696 0.494036 -0.23762 -0.852669 0.465288 -0.237425 -0.884065 0.402564 -0.887884 -0.374466 0.267278 -0.739468 -0.547936 0.391093 -0.108167 -0.912176 0.395265 -0.341052 -0.855524 0.389567 -0.658918 -0.684582 0.311728 -0.558602 -0.761953 0.327707 -0.739472 -0.61266 0.278978 -0.971845 -0.191781 0.136885 -0.931696 -0.290828 0.217627 -0.931861 -0.314208 0.181408 -0.658697 -0.607529 0.443877 -0.658919 -0.651436 0.376107 -0.931861 -0.314208 0.181408 -0.931861 -0.330194 0.150356 -0.888088 -0.42416 0.177165 -0.994042 0.088715 -0.0633208 -0.994042 0.0887153 -0.0633211 -0.994053 0.0929732 -0.0567057 -0.994978 0.0866851 -0.0500477 -0.994053 0.0955948 -0.052165 -0.994042 0.0991953 -0.0451691 0 0.915011 -0.403429 0.0635016 0.898033 -0.435322 0 0.883513 -0.468406 0 0.827686 -0.561191 0.12616 0.800438 -0.585988 0 0.847408 -0.530942 -0.0684621 -0.810039 -0.582365 -0.0983863 -0.974271 -0.202771 -0.738155 0.177197 -0.650945 -0.933087 0.124312 -0.337484 -0.8858 0.295633 -0.357715 -0.902767 0.227058 -0.365317 -0.900881 0.206349 -0.381882 -0.89373 0.259447 -0.365969 -0.982603 0.0455829 -0.180037 -0.968982 0.0603372 -0.239652 -0.95918 0.065088 -0.275203 -0.978164 0.0599457 -0.199002 -0.993506 0.0698559 -0.0898138 -0.993503 0.0647569 -0.0935872 -0.955076 0.0799241 -0.285379 -0.937214 0.104396 -0.332764 -0.812787 -0.174885 -0.555691 -0.759742 -0.0592717 -0.647517 -0.532645 -0.189781 -0.824786 -0.600329 -0.186743 -0.777645 -0.364134 -0.284403 -0.88686 -0.456007 -0.283569 -0.843591 -0.187413 -0.363983 -0.912356 -0.145509 0.52525 -0.838415 -0.172305 0.340283 -0.924402 -0.88495 0.292276 -0.362544 -0.712672 0.349495 -0.608237 -0.697724 0.331466 -0.635069 -0.461101 0.362648 -0.80986 -0.423355 0.334656 -0.841889 -0.179692 0.338563 -0.923626 -0.275278 -0.0285175 -0.960942 -0.918222 0.157191 -0.363537 -0.916086 0.160332 -0.367532 -0.771361 -0.00250019 -0.636393 -0.72281 0.136441 -0.677443 -0.503329 0.0902775 -0.859366 -0.487238 0.0935175 -0.868248 -0.353638 0.0132656 -0.935288 -0.177309 -0.0138881 -0.984057 -0.301511 -0.368509 -0.87937 -0.274896 -0.640851 -0.716758 -0.876426 -0.456207 0.154115 -0.884046 -0.441038 0.154749 -0.7257 -0.638632 0.255946 -0.739823 -0.621849 0.256838 -0.546204 -0.766933 0.336861 -0.553286 -0.761656 0.337275 -0.333634 -0.852481 0.402449 -0.344987 -0.847098 0.404239 -0.105762 -0.89384 0.435734 -0.121706 -0.890012 0.439394 -0.145527 -0.914823 -0.376723 -0.171013 -0.913751 -0.368528 -0.342317 -0.862545 -0.372605 -0.242324 -0.882591 -0.402879 -0.521635 -0.754582 -0.398125 -0.443218 -0.785617 -0.431698 -0.684278 -0.606362 -0.405078 -0.629471 -0.641015 -0.439165 -0.79214 -0.460389 -0.400694 -0.839076 -0.5233 -0.148693 -0.858963 -0.493728 -0.135702 -0.685632 -0.720172 -0.106119 -0.721166 -0.686718 -0.0913174 -0.493424 -0.86782 -0.058489 -0.546161 -0.836612 -0.04229 -0.282721 -0.959146 -0.0103892 -0.351084 -0.936316 0.00719298 -0.0853895 -0.995794 0.0331981 -0.106821 -0.993533 0.0384872 -0.147949 0.680969 -0.717211 -0.205592 0.644836 -0.736151 -0.341428 0.622915 -0.70385 -0.424994 0.588896 -0.687445 -0.484351 0.592723 -0.643494 -0.687666 0.501447 -0.525039 -0.647365 0.489689 -0.584058 -0.870213 0.401711 -0.285233 -0.85001 0.380037 -0.364766 -0.0290115 0.296926 -0.95446 -0.135869 -0.118987 -0.983556 0.182413 -0.0848535 -0.979554 -0.290375 -0.444121 -0.847608 -0.0131357 -0.426064 -0.904598 -0.143542 -0.710172 -0.68924 -0.324416 -0.65946 -0.678135 -0.209392 -0.668223 -0.713886 -0.48962 -0.555345 -0.672208 -0.398067 -0.573486 -0.716001 -0.64164 -0.425339 -0.638267 -0.575731 -0.446876 -0.684715 -0.805193 -0.233446 -0.54513 -0.849342 -0.296564 -0.436656 -0.891409 -0.245115 -0.381194 -0.946585 -0.272989 -0.171622 -0.938296 -0.294123 -0.181911 -0.97139 -0.234023 0.0404328 -0.963017 -0.266672 0.0385254 -0.14881 0.948689 -0.279006 -0.824707 0.351087 0.443391 -0.651394 0.737922 -0.176512 -0.942264 0.315396 0.112536 -0.971801 0.228718 0.0573696 -0.978816 0.196567 0.0572755 -0.989309 0.145829 -0.000934777 -0.993672 0.111383 -0.0144705 -0.851107 0.486047 -0.198434 -0.873462 0.477269 -0.0963218 -0.889401 0.453557 -0.0570303 -0.901406 0.432815 -0.0117727 -0.895308 0.445202 -0.0148205 -0.918229 0.394194 0.0382884 -0.741732 0.566806 0.358559 -0.782194 0.516656 0.348195 -0.708895 0.677438 0.196329 -0.911959 0.408362 0.0396371 -0.938587 0.338416 0.0672955 -0.786961 0.396519 0.472721 -0.849347 0.229857 0.475158 -0.792189 0.11673 0.599008 -0.856724 -0.114382 0.502933 -0.84357 -0.144853 0.517115 -0.884012 -0.349496 0.310446 -0.877482 -0.36477 0.311396 -0.921891 0.377464 0.087393 -0.959989 0.274734 0.0542425 -0.89144 0.207511 0.402833 -0.944652 0.023328 0.327243 -0.941309 0.00197792 0.337541 -0.970892 -0.142537 0.192488 -0.965065 -0.173293 0.196519 -0.0661934 0.105544 0.992209 -0.226438 0.249655 0.941487 -0.146316 -0.13394 0.980128 -0.165352 -0.138724 0.976429 -0.092667 -0.329027 0.939763 -0.14666 -0.518106 0.842649 -0.0760683 -0.54947 0.832043 -0.105981 -0.829663 0.548112 -0.133558 -0.820953 0.555157 -0.333937 -0.777101 0.533479 -0.306113 0.946681 -0.100452 -0.276825 0.756814 0.592115 0.207911 0.799855 0.563032 -0.216184 0.580267 0.78521 -0.0427212 0.503084 0.863181 -0.123733 0.297235 0.946753 -0.0880362 0.898611 0.429823 -0.0256591 0.977818 0.207876 -0.152043 0.974617 0.16433 -0.145452 0.970854 -0.19049 -0.341452 0.920987 -0.187599 -0.692764 0.706203 -0.146136 -0.714399 0.69928 0.0253297 -0.412913 0.905146 0.101063 -0.487267 0.79863 0.353216 -0.353597 0.816588 0.456239 -0.447581 0.615528 0.648688 -0.37766 0.59972 0.705485 -0.480017 0.338371 0.809376 -0.412111 0.301116 0.859938 -0.513923 -0.000835632 0.857836 -0.454265 -0.0483903 0.889551 -0.542565 -0.36193 0.758043 -0.499057 -0.401264 0.768068 -0.553199 -0.671144 0.493494 -0.546584 -0.676879 0.493032 -0.344665 -0.7709 0.535648 -0.287817 -0.490545 0.822513 -0.346269 -0.453385 0.821304 -0.253012 -0.124573 0.959409 -0.332868 -0.0745942 0.940018 -0.22331 0.249375 0.942308 -0.313058 0.294212 0.903014 -0.200949 0.580361 0.789177 -0.291653 0.606522 0.739642 -0.187451 0.8297 0.525795 -0.269275 0.834045 0.481519 -0.179697 0.969184 0.168497 -0.463508 0.877444 0.123505 -0.425031 0.889766 -0.166327 -0.484354 0.853631 -0.191611 -0.870907 0.464611 -0.160184 -0.89297 0.443615 -0.0762275 -0.690171 0.723587 0.00926102 -0.744779 0.635393 0.203912 -0.503287 0.789362 0.351582 -0.593143 0.603381 0.533022 -0.545222 0.595649 0.58986 -0.633573 0.369904 0.679526 -0.588804 0.340893 0.732872 -0.677988 0.0757255 0.731162 -0.63989 0.0342047 0.767705 -0.718478 -0.246471 0.650416 -0.691091 -0.283416 0.664883 -0.739777 -0.528035 0.417023 -0.726935 -0.54518 0.417545 -0.939621 0.313132 -0.13806 -0.939565 0.278668 -0.198901 -0.938391 0.271227 -0.214146 -0.939692 0.267506 -0.21312 -0.939425 0.267498 -0.214301 -0.939408 0.267503 -0.21437 -0.939888 0.266648 -0.213331 -0.939986 0.266252 -0.213395 -0.939935 0.266432 -0.213391 -0.93977 0.26684 -0.21361 -0.939573 0.267264 -0.213944 -0.939634 0.318759 -0.124424 -0.939832 0.318252 -0.124222 -0.940954 0.314525 -0.12522 -0.939692 0.318304 -0.125147 -0.939958 0.317968 -0.123995 -0.939978 0.317939 -0.123919 -0.939692 0.318126 -0.125594 -0.939471 0.319187 -0.124552 -0.939449 0.319261 -0.124528 -0.939565 0.311587 -0.141883 -0.94337 0.302631 -0.135894 -0.936007 0.308973 -0.168603 -0.939622 0.30235 -0.160295 -0.939661 0.29207 -0.178138 -0.937285 0.295376 -0.185067 -0.94337 0.269003 -0.194139 -0.939621 0.276129 -0.20215 -0.939693 0.267831 -0.212707 -0.149348 0.904749 -0.398904 -0.488788 0.798258 -0.351953 -0.346074 0.757026 -0.554207 -0.655057 0.609666 -0.446327 -0.850962 0.423798 -0.310256 -0.850963 0.423797 -0.310255 -0.850963 0.445081 -0.278864 -0.850962 0.445082 -0.278865 -0.850962 0.464045 -0.24602 -0.850962 0.464045 -0.246019 -0.850962 0.480588 -0.211892 -0.850962 0.480588 -0.211892 -0.655065 0.691357 -0.30482 -0.57344 0.746564 -0.337355 -0.573329 0.723885 -0.383777 -0.573328 0.723885 -0.383778 -0.573328 0.694304 -0.435014 -0.573327 0.694304 -0.435015 -0.573438 0.665441 -0.477867 -0.488787 0.703929 -0.515336 -0.346093 0.858464 -0.378497 -0.202128 0.893771 -0.400396 -0.20209 0.865283 -0.458742 -0.202091 0.865283 -0.458742 -0.202091 0.829924 -0.519987 -0.20209 0.829924 -0.519987 -0.202128 0.793639 -0.573831 -0.149351 0.797836 -0.584083 0.707098 -0.540789 0.455587 0.671178 -0.594401 0.442954 0.70647 -0.566439 0.42432 0.70647 -0.612923 0.353871 0.706469 -0.612924 0.353872 0.706521 -0.649948 0.279993 0.672813 -0.680175 0.291005 0.707098 -0.664944 0.240545 0.70647 0.566439 -0.42432 0.70647 0.566439 -0.42432 0.70647 0.612923 -0.353871 0.706471 0.612923 -0.353871 0.706471 0.65069 -0.27839 0.70647 0.650692 -0.27839 0.698066 -0.603212 0.385796 0.698068 -0.60321 0.385795 0.698069 -0.376083 0.609313 0.618519 -0.434981 0.65439 0.706899 -0.250663 0.661409 0.698066 -0.074469 0.712151 0.698066 -0.0744687 0.71215 0.698067 0.241896 0.673935 0.698068 0.241896 0.673935 0.698067 0.51035 0.50224 0.698066 0.710866 -0.0858661 0.698068 0.710864 -0.0858665 0.700601 0.682744 0.20741 0.634905 0.731255 0.249321 0.706901 0.614053 0.35104 0.698069 0.510349 0.502239 0.701597 -0.615913 0.358349 0.701594 -0.615915 0.358349 0.701595 -0.701612 0.124518 0.701597 -0.70161 0.124519 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.842436 0.538797 0 0.980521 -0.196414 -0.0323336 0.992265 -0.119856 -0.00477475 0.999972 0.00576553 0.0109504 0.966869 0.255037 -0.00691385 0.9568 0.290666 0.00189076 0.868149 0.4963 0.0233499 0.77546 0.630965 -0.0207687 0.712594 0.70127 -0.00129451 0.584664 0.811275 0.00323699 0.451302 0.892365 -0.0314914 0.337661 0.940741 -0.00693554 0.25417 0.967135 0.000742243 -0.345465 0.938431 -0.0031434 -0.173063 0.984906 -0.0274198 -0.103963 0.994203 -0.00213144 0.0301619 0.999543 0.000706878 0.133793 0.991009 -0.00398559 -0.84672 0.532024 0.00339264 -0.55994 0.828526 2.08372e-05 -0.553573 0.832801 -4.1369e-08 -0.354387 0.935099 0 -0.865062 0.501666 0.000562933 -0.864348 0.502893 -0.000568737 -0.984614 0.174744 0 -0.984868 0.173308 0 0.800345 -0.59954 0 0.800345 -0.59954 0 0.866025 -0.5 0 0.866025 -0.5 0 0.919389 -0.393349 0 0.919389 -0.393349 0 -0.919389 0.393349 0 -0.919389 0.393349 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.800345 0.599539 0 -0.800345 0.599539 0.879241 0.459539 -0.125533 0.887082 0.458782 -0.0510247 0.954993 0.285017 0.0821843 0.960101 0.265301 0.0884357 0.978436 0.198165 0.058261 0.978976 0.195525 0.0581036 0.991396 0.130838 -0.00378078 0.990797 0.135349 -0.00127308 0.965171 -0.180107 0.189752 0.793207 0.0945542 0.601567 0.859467 -0.147705 0.489388 0.839105 -0.150363 0.522775 0.884191 -0.365193 0.291274 0.876484 -0.372183 0.305377 0.859291 0.373912 0.34901 0.938544 0.334264 0.086037 0.933187 0.352125 0.0719021 0.821646 0.298602 0.485525 0.847484 0.221374 0.482456 0.891283 0.194744 0.4095 0.947044 -0.0001729 0.321104 0.938319 -0.00095155 0.34577 0.970911 -0.147725 0.188438 0.989048 -0.0715432 0.129098 0.807335 0.563509 0.175122 0.693242 0.549747 0.46604 0.77072 0.34044 0.538601 0.902132 0.430842 0.0230746 0.887847 0.456659 -0.0564862 0.749551 0.661885 0.00903366 0.710135 0.704054 -0.00404469 0.276 0.798643 0.534783 0.145866 0.989304 0.000656081 0.197818 0.967482 -0.157629 0.147939 0.969315 -0.196325 0.111225 -0.551324 0.826844 0.0953814 -0.841734 0.5314 0.105771 -0.842778 0.527766 0.0780648 0.0376054 0.996239 0.143595 -0.158821 0.976809 0.177642 -0.17007 0.969288 0.0973076 -0.33693 0.936488 0.110871 -0.551253 0.826939 0.0290534 0.966775 0.253973 0.134954 0.774472 0.618045 -0.130548 0.799806 0.585891 0.15626 0.589494 0.792515 0.216095 0.552274 0.805168 0.0506064 0.454851 0.889129 0.143392 0.209354 0.967269 0.273417 0.271016 0.922927 0.142386 0.145985 0.978987 0.354225 0.799965 0.484336 0.457112 0.563087 0.688463 0.363178 0.604351 0.709128 0.490835 0.273168 0.827322 0.397297 0.30651 0.864989 0.522595 -0.0645725 0.850133 0.442834 -0.0477898 0.895329 0.54661 -0.408775 0.730836 0.493392 -0.409084 0.767603 0.553361 -0.689518 0.467287 0.546233 -0.69179 0.472288 0.176406 0.829053 0.530615 0.30266 0.548174 0.779681 0.186327 0.583984 0.790092 0.325671 0.222736 0.918873 0.208476 0.254809 0.944251 0.343263 -0.143623 0.928193 0.241855 -0.123317 0.962444 0.351503 -0.503629 0.789179 0.282648 -0.498079 0.819772 0.345027 -0.791879 0.503868 0.333669 -0.792957 0.509789 0.879549 0.458701 -0.126439 0.763483 0.628764 -0.147478 0.693958 0.710573 -0.116222 0.651408 0.743627 -0.150623 0.484445 0.859579 -0.162596 0.918301 0.391642 0.0577972 0.901023 0.430768 0.0509516 0.758731 0.596299 0.262213 0.805309 0.54705 0.228503 0.700506 0.628348 0.338333 0.633801 0.769788 0.0756557 0.461118 0.879321 0.119014 0.425665 0.895111 -0.132613 0.34147 0.926946 -0.155466 0.172209 0.964762 0.198945 0.179194 0.963224 0.200222 0.424095 0.890769 0.163319 0.486873 0.787802 0.377256 0.502665 0.778301 0.376266 0.601389 0.558666 0.57116 0.531867 0.601584 0.595998 0.642844 0.313504 0.698904 0.575095 0.346743 0.740969 0.685233 0.0200403 0.728048 0.629213 0.0348522 0.776452 0.721677 -0.287694 0.629615 0.685623 -0.290625 0.667426 0.73994 -0.547492 0.390823 0.725681 -0.555114 0.406492 0.14616 0.602444 -0.784665 0.106528 -0.861075 0.497194 0.826272 -0.228735 -0.514738 0.651431 0.502274 -0.568646 0.880894 0.294345 -0.370657 0.992268 0.0442004 -0.115974 0.992327 0.0815851 -0.0929047 0.976265 0.0381605 -0.213193 0.978908 0.0485425 -0.198453 0.963204 0.0549823 -0.263087 0.942932 0.0528938 -0.328758 0.902137 0.211905 -0.375827 0.8958 0.222273 -0.384886 0.919326 0.14958 -0.363957 0.851017 0.410402 -0.327628 0.740543 -0.0465455 -0.670395 0.783615 -0.0676985 -0.617547 0.707955 0.148614 -0.690444 0.912307 0.15756 -0.377983 0.939733 0.0982583 -0.327485 0.7859 -0.228434 -0.574613 0.847486 -0.30711 -0.432956 0.79326 -0.473675 -0.382584 0.856963 -0.497199 -0.135676 0.844209 -0.52384 -0.113592 0.884164 -0.438012 0.162481 0.877676 -0.445627 0.176359 0.923008 0.103749 -0.37053 0.960832 0.0760319 -0.266499 0.891327 -0.257214 -0.373334 0.944822 -0.277165 -0.174617 0.94184 -0.296163 -0.158823 0.970919 -0.23703 0.0336482 0.965173 -0.254388 0.0610589 0.244541 -0.733116 -0.634619 0.169574 -0.727971 -0.664307 0.0807642 -0.848098 -0.523649 0.126153 -0.907052 -0.401673 0.225575 -0.913362 -0.338948 0.0935054 -0.968445 -0.231021 0.334009 -0.835706 0.435929 0.185737 -0.869116 0.45841 -0.00744022 -0.997275 0.0733926 0.309748 -0.938996 0.149475 0.10402 -0.992056 -0.070738 0.333006 -0.159697 -0.929303 -0.0466978 -0.0998978 -0.993901 0.150511 -0.409734 -0.899702 0.201356 -0.424528 -0.882741 0.0641999 -0.572892 -0.817113 0.110746 -0.670194 -0.733877 0.0768315 0.0285093 -0.996636 0.0753855 0.265599 -0.961132 0.190214 0.305328 -0.933056 0.0915598 0.627708 -0.773046 0.341461 0.598171 -0.72498 0.693992 0.455932 -0.557226 0.714749 0.304528 -0.6296 0.412198 0.338776 -0.845768 0.486913 0.0670923 -0.87087 0.354189 -0.0195536 -0.934969 0.447652 -0.282048 -0.848562 0.378522 -0.341523 -0.860281 0.480138 -0.554481 -0.679719 0.413098 -0.618123 -0.668785 0.514059 -0.757179 -0.403018 0.455184 -0.80815 -0.373768 0.542691 -0.839113 -0.0370994 0.499641 -0.866216 -0.00529306 0.553288 -0.750966 0.360449 0.546658 -0.753116 0.366036 0.344676 -0.834924 0.429069 0.288259 -0.956357 0.0478258 0.346233 -0.938046 0.0138643 0.253711 -0.905717 -0.339571 0.332839 -0.864551 -0.376522 0.224037 -0.715181 -0.66206 0.313048 -0.658169 -0.6847 0.201544 -0.42449 -0.882717 0.291661 -0.366879 -0.883365 0.187843 -0.0747701 -0.979349 0.269294 -0.0320532 -0.962525 0.17921 0.308319 -0.93425 0.463856 0.301224 -0.833128 0.425706 0.562434 -0.708832 0.484451 0.570638 -0.663083 0.875356 0.350029 -0.333514 0.889585 0.276391 -0.363656 0.689707 0.334228 -0.642336 0.745684 0.115742 -0.656171 0.502636 0.0632218 -0.862183 0.593259 -0.185339 -0.783386 0.546274 -0.241336 -0.802086 0.633756 -0.424758 -0.646478 0.590006 -0.48712 -0.6439 0.678252 -0.609114 -0.41104 0.640948 -0.661599 -0.389195 0.718701 -0.689675 -0.0884183 0.691734 -0.719593 -0.0607501 0.739911 -0.6162 0.269869 0.727069 -0.624337 0.28561 0.572894 0.70982 -0.409815 0.850725 0.420015 -0.315996 0.879517 0.437896 -0.186272 0.654679 0.694973 -0.297336 0.764994 0.592121 -0.253332 0.845143 0.490095 -0.213401 0.851115 0.469977 -0.233934 0.850697 0.455232 -0.262828 0.850697 0.455231 -0.262828 0.851115 0.437584 -0.29004 0.34578 0.862677 -0.369086 0.488417 0.802268 -0.343241 0.149209 0.909097 -0.388946 0.201912 0.899073 -0.388457 0.201872 0.848196 -0.489706 0.844349 0.42882 -0.32123 0.654699 0.604972 -0.453186 0.573015 0.658621 -0.487722 0.488419 0.698388 -0.523164 0.345769 0.75098 -0.56256 0.573015 0.75169 -0.326521 0.572894 0.70982 -0.409815 0.201872 0.848196 -0.489706 0.201912 0.78595 -0.584392 0.149217 0.791385 -0.592827 0.340892 -0.752407 0.563629 0.994035 0.0944505 -0.054531 0.994036 0.0871409 -0.06556 0.994251 0.0857001 -0.0641981 0.991754 0.117931 -0.0501653 0.996676 0.0729343 -0.0363042 0.658679 -0.651618 0.376212 0.931791 -0.314364 0.181498 0.994046 0.0994072 -0.0446273 0.993745 -0.102672 0.0439271 0.971837 -0.216659 0.0926947 0.994056 0.0907463 -0.060149 0.994035 0.0944505 -0.054531 0.93179 -0.314365 0.181498 0.931639 -0.336606 0.136916 0.558446 -0.655448 0.508455 0.73931 -0.538924 0.403709 0.931791 -0.290522 0.217631 0.888073 -0.360853 0.284802 0.971842 -0.188586 0.14127 0.237289 -0.841291 0.48572 0.237289 -0.777487 0.582416 0.108129 -0.78682 0.607637 0.887837 -0.423064 0.181003 0.739297 -0.619098 0.264874 0.658467 -0.694532 0.289906 0.558107 -0.762881 0.326389 0.340888 -0.864321 0.369789 0.658679 -0.602199 0.451108 0.658678 -0.651619 0.376212 0.237287 -0.841291 0.48572 0.23719 -0.895749 0.375999 0.108041 -0.914007 0.391047 0.939515 0.315179 -0.13407 0.939603 0.322721 -0.114005 0.93949 0.323054 -0.113993 0.939578 0.32274 -0.114158 0.939697 0.322087 -0.115019 0.939843 0.322105 -0.113773 0.939864 0.322065 -0.113706 0.939744 0.322357 -0.113874 0.939508 0.273714 -0.205927 0.939902 0.259373 -0.222056 0.939804 0.259771 -0.222006 0.93969 0.260666 -0.22144 0.939697 0.260515 -0.221587 0.939546 0.260228 -0.222566 0.939486 0.260238 -0.222807 0.939528 0.260211 -0.222658 0.939643 0.260008 -0.222413 0.939777 0.259725 -0.222174 0.939515 0.273698 -0.205915 0.939511 0.273707 -0.205921 0.939693 0.28508 -0.188959 0.939693 0.285081 -0.188958 0.939498 0.296662 -0.171278 0.939498 0.296661 -0.171278 0.939694 0.306183 -0.152407 0.939693 0.306184 -0.152405 0.939511 0.315187 -0.134075 0.939508 0.315196 -0.134078 0.93969 0.322182 -0.114812 -0.697586 0.697599 0.163488 -0.697587 0.697598 0.163488 -0.697588 0.552319 0.456416 -0.638172 0.60461 0.476638 -0.707007 0.440824 0.553005 -0.697587 0.292015 0.654293 -0.697588 0.292015 0.654292 -0.697589 -0.029103 0.715907 -0.697586 -0.0291024 0.71591 -0.707007 -0.20484 0.676892 -0.685363 -0.270461 0.676113 -0.825857 -0.323366 0.461947 -0.701045 -0.602934 0.380797 -0.600135 -0.655933 0.457811 -0.706725 -0.496195 0.504312 -0.699416 -0.357641 0.618798 -0.458499 -0.712315 -0.5314 -0.694741 -0.66072 0.284227 -0.69474 -0.66072 0.284227 -0.7057 -0.707418 0.0393265 -0.754937 -0.655772 -0.00582904 -0.624887 -0.764167 -0.159893 -0.705015 -0.683368 -0.189634 -0.703698 -0.617455 -0.351509 -0.704397 -0.504947 -0.498852 -0.704396 -0.36775 -0.607113 -0.458503 -0.351183 -0.816362 -0.694736 0.430088 -0.576512 -0.694738 0.430087 -0.57651 -0.702914 0.15925 -0.693218 -0.46676 0.103545 -0.878301 -0.705014 -0.0255164 -0.708734 -0.703698 -0.198284 -0.682271 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706177 -0.637125 0.308847 -0.706178 -0.637124 0.308846 -0.706178 -0.586031 0.397343 -0.706178 -0.58603 0.397343 0 -0.813937 0.580953 -0.0420202 -0.826955 0.560695 0 -0.853738 0.520703 0 -0.899849 0.436202 -0.0629305 -0.908285 0.413592 0 -0.877811 0.479008 -0.706177 0.637125 -0.308847 -0.706175 0.637127 -0.308847 -0.706174 0.586033 -0.397344 -0.706174 0.586034 -0.397345 0 -0.91861 0.395166 0 0.686622 -0.727015 0.0323174 0.597643 -0.801111 0.0129621 0.525183 -0.850891 -0.0156222 0.296128 -0.955021 0.0036903 0.223893 -0.974607 -0.00326083 -0.0359793 -0.999347 -0.02515 -0.131804 -0.990957 3.37981e-05 -0.711387 -0.7028 -4.04636e-05 -0.496586 -0.867987 -0.00661953 -0.518087 -0.855302 0.00507006 -0.279074 -0.960256 0.0225877 -0.894793 0.445909 -0.0133915 -0.998873 0.0455433 -1.51064e-05 -0.999961 -0.00888849 3.12715e-07 -0.980889 -0.194569 0.00403957 -0.963579 -0.267392 -0.00869114 -0.930196 -0.366961 0.00792428 -0.869017 -0.494719 -0.00305021 -0.81647 -0.577379 0.00554924 -0.692858 -0.721053 0 -0.835836 0.548979 -0.00561605 -0.845478 0.533981 0.000789678 -0.701347 0.71282 -0.00753315 -0.55511 0.831743 0.01001 -0.500371 0.865753 -0.000485936 -0.338599 0.940931 0.000207359 -0.289646 0.957134 -0.00316909 -0.150774 0.988563 0.021295 -0.0406081 0.998948 -0.000796741 0.0980041 0.995186 0.000778099 0.284746 0.958603 0.0220046 0.407459 0.912958 -0.0019994 0.499237 0.866463 0.000195932 0.623331 0.781958 -0.00580835 0.785303 0.619085 0.0051454 0.767681 0.640812 0 0.97362 0.228176 0.00804784 0.977629 0.210182 -0.000448907 0.898647 0.438673 0 -0.88161 -0.471979 -0.037669 -0.821117 -0.569515 -0.0154261 -0.768961 -0.639109 0.0283305 -0.521837 -0.852574 1.24653e-05 0.451127 -0.89246 -0.0268651 0.524559 -0.85095 7.14961e-05 0.417824 -0.908528 -0.00010055 0.21939 -0.975637 -1.09343e-05 0.219107 -0.975701 -4.67573e-06 -0.0406004 -0.999175 -0.0342197 0.0612259 -0.997537 0.0537476 -0.283099 -0.957584 0.00712829 -0.194985 -0.98078 -0.00709839 -0.584002 -0.811721 0 0.996573 0.0827142 -0.0330449 0.991356 0.126973 0.0252542 0.944983 -0.326142 -0.00777992 0.9629 -0.269746 5.33774e-06 0.890922 -0.454156 -8.04383e-06 0.828636 -0.559788 -0.0189323 0.862508 -0.505689 0.0359315 0.666311 -0.744808 -0.0352756 0.757031 -0.652427 2.57617e-05 0.611953 -0.790894 0 0.919389 0.393349 0 0.919389 0.393349 0 0.866025 0.5 0 0.866025 0.5 0 0.800345 0.59954 0 0.800345 0.59954 0 -0.800345 -0.599539 0 -0.800345 -0.599539 0 -0.866025 -0.5 0 -0.866025 -0.5 0 -0.919389 -0.393349 0 -0.919389 -0.393349 0.87924 0.338485 0.335209 0.887083 0.273581 0.371803 0.954993 0.0713332 0.287922 0.960101 0.0560632 0.273975 0.978436 0.0486275 0.200747 0.978976 0.0474432 0.198381 0.991397 0.0686935 0.111418 0.990797 0.0687769 0.116579 0.965171 -0.254385 -0.0611019 0.793206 -0.473696 0.38267 0.859466 -0.497676 0.116778 0.839106 -0.527917 0.131169 0.884192 -0.434845 -0.170629 0.876485 -0.450556 -0.169631 0.859293 -0.115291 0.498321 0.938544 0.0926215 0.3325 0.933186 0.113794 0.340902 0.821646 -0.271177 0.501358 0.847484 -0.307133 0.432944 0.891282 -0.257266 0.373404 0.947044 -0.27817 0.160402 0.938319 -0.29992 0.17206 0.970911 -0.237055 -0.0337151 0.989048 -0.14757 0.00259267 0.807335 0.130097 0.575574 0.693241 -0.128731 0.709116 0.770719 -0.296224 0.564131 0.902132 0.195436 0.384658 0.887846 0.277248 0.367236 0.74955 0.323119 0.577728 0.710136 0.355528 0.607706 0.0480976 -0.251966 0.96654 0.183345 -0.457831 0.869928 0.0890388 -0.443842 0.89167 0.275998 -0.0638112 0.959038 0.162583 0.384724 0.9086 0.243777 -0.0159821 0.9697 0.0759189 -0.0873327 0.993282 0.076241 0.211139 0.974478 0.129208 0.584999 0.800676 0.19602 0.620438 0.759363 0.149367 0.730714 0.666143 0.105771 -0.878448 -0.465985 0.0427788 -0.94358 0.328369 0.117379 -0.991456 0.0569046 0.222639 -0.973394 -0.0541923 0.040514 -0.984376 -0.171357 0.201097 -0.849125 -0.488412 0.0855579 -0.618202 0.781349 0.1107 -0.669771 0.73427 0.21036 -0.718352 0.663113 0.00586343 -0.823987 0.566578 0.242001 -0.931063 0.273051 0.354226 -0.0194649 0.934957 0.457112 -0.314684 0.831879 0.363173 -0.311947 0.877949 0.490832 -0.579899 0.650232 0.397299 -0.595848 0.697939 0.522594 -0.768523 0.369145 0.442837 -0.799272 0.406276 0.546611 -0.837309 0.0114088 0.493392 -0.869306 0.0295257 0.553361 -0.749441 -0.363497 0.546232 -0.754909 -0.362964 0.176415 -0.0449985 0.983287 0.302667 -0.401135 0.864571 0.186333 -0.392246 0.900791 0.325675 -0.684399 0.65233 0.208474 -0.690341 0.692797 0.343266 -0.875649 0.339716 0.241858 -0.895159 0.374426 0.351506 -0.935262 -0.0415657 0.28265 -0.958983 -0.0214624 0.345026 -0.832303 -0.433854 0.333669 -0.837968 -0.431827 0.879549 0.338851 0.334026 0.763486 0.442101 0.470781 0.693959 0.455938 0.557263 0.651408 0.502257 0.568687 0.484444 0.570602 0.663119 0.918301 0.145767 0.368071 0.901023 0.171258 0.398532 0.758735 0.0710667 0.647511 0.805308 0.0756362 0.588012 0.700506 0.0211698 0.713333 0.633799 0.319372 0.704485 0.461119 0.336589 0.821022 0.425666 0.562402 0.708881 0.341475 0.598109 0.725024 0.233124 0.293097 0.927226 0.179196 0.308211 0.934288 0.424096 0.303943 0.853089 0.486873 0.0671868 0.870885 0.502657 0.0632947 0.862166 0.601384 -0.215307 0.769403 0.531868 -0.215359 0.818985 0.642845 -0.448517 0.620953 0.575096 -0.468327 0.670772 0.685234 -0.620488 0.381378 0.629211 -0.655002 0.418409 0.721675 -0.689111 0.065658 0.685622 -0.723322 0.0820253 0.739939 -0.612209 -0.278731 0.725682 -0.629588 -0.277498 0.146159 0.980762 0.129399 0.826271 0.33141 -0.455459 0.651433 0.743597 0.150659 0.880894 0.468171 0.0695802 0.992268 0.122537 -0.0197088 0.992327 0.12125 0.0242022 0.976264 0.203712 -0.0735513 0.978908 0.196137 -0.0571869 0.963206 0.255324 -0.0839233 0.942932 0.311159 -0.118572 0.902137 0.431428 -0.00439855 0.895799 0.444459 5.06516e-05 0.919326 0.389987 -0.0524387 0.851017 0.488935 0.191604 0.740542 0.557307 -0.375507 0.783616 0.500961 -0.367402 0.707956 0.672249 -0.216518 0.912306 0.406124 -0.052541 0.939733 0.33274 -0.0786492 0.7859 0.383412 -0.485135 0.847486 0.221396 -0.482442 0.793261 0.0944918 -0.601506 0.856963 -0.1311 -0.498425 0.844208 -0.163548 -0.510455 0.884163 -0.35972 -0.298089 0.877675 -0.375545 -0.297744 0.923009 0.372761 -0.0954159 0.960832 0.268811 -0.0674043 0.891327 0.19471 -0.40942 0.944822 0.01264 -0.32734 0.94184 -0.0105358 -0.335895 0.97092 -0.147655 -0.18845 0.965173 -0.180073 -0.189776 0.11517 -0.761084 -0.638347 0.0771104 -0.578421 -0.812086 0.146466 -0.546423 -0.824603 0.044027 -0.191728 -0.98046 0.0571086 -0.185864 -0.980914 0.099841 0.0736482 -0.992274 0.181852 0.212379 -0.960117 0.334007 -0.795379 -0.505778 0.105776 -0.842735 -0.527834 0.278923 -0.844697 -0.456825 0.0122556 0.815076 -0.579225 0.315351 0.737905 -0.596699 0.112606 0.862123 -0.494028 0.136041 0.230053 -0.963623 0.0636199 0.422634 -0.904065 0.202853 0.552193 -0.808661 0.247985 0.530595 -0.810538 0.108764 0.616333 -0.779939 0.0842295 0.890467 -0.447185 0.032851 0.963027 -0.267394 0.190216 0.960713 -0.202108 0.0915608 0.983331 0.157088 0.341468 0.926934 0.15554 0.693995 0.710536 0.116235 0.714752 0.697511 -0.05107 0.412198 0.901845 -0.129495 0.486914 0.787741 -0.377331 0.354186 0.79993 -0.484421 0.447648 0.593853 -0.668543 0.378519 0.574265 -0.725909 0.480136 0.311411 -0.820057 0.4131 0.270123 -0.869702 0.51406 -0.0295648 -0.857244 0.455184 -0.0803828 -0.886762 0.54269 -0.387428 -0.745243 0.499642 -0.428524 -0.752812 0.553286 -0.687642 -0.470132 0.546659 -0.693553 -0.4692 0.344677 -0.789045 -0.508532 0.288259 -0.519597 -0.804317 0.346234 -0.481029 -0.80544 0.253712 -0.158781 -0.954159 0.332839 -0.106198 -0.936985 0.224034 0.215771 -0.950395 0.313043 0.263883 -0.912343 0.201537 0.55221 -0.808979 0.291658 0.581578 -0.759409 0.187839 0.810756 -0.554429 0.269289 0.817544 -0.509024 0.179204 0.963245 -0.200113 0.463856 0.872122 -0.155696 0.425705 0.895084 0.132668 0.484448 0.859568 0.162646 0.875354 0.463849 0.136381 0.889584 0.453134 0.0575345 0.689708 0.723393 -0.0317152 0.745684 0.626131 -0.227849 0.502638 0.778283 -0.37634 0.593259 0.585761 -0.552202 0.546279 0.573959 -0.610042 0.63376 0.347488 -0.691086 0.590005 0.314071 -0.74381 0.678251 0.0514149 -0.73303 0.640945 0.00625309 -0.767561 0.718701 -0.268266 -0.641485 0.691734 -0.307186 -0.653561 0.739911 -0.541814 -0.398709 0.727071 -0.559513 -0.397886 0.572894 0.70982 0.409815 0.850726 0.483668 0.205746 0.879516 0.380266 0.286094 0.654679 0.604987 0.453196 0.764998 0.515449 0.386123 0.845143 0.429858 0.317735 0.851114 0.437583 0.290045 0.850697 0.455232 0.262828 0.850697 0.455232 0.262828 0.851115 0.469975 0.233939 0.345784 0.750975 0.562556 0.488417 0.698389 0.523164 0.149205 0.791386 0.592829 0.201912 0.78595 0.584392 0.201872 0.848196 0.489706 0.844348 0.492604 0.210755 0.654701 0.694955 0.297328 0.573015 0.75169 0.326522 0.488417 0.802268 0.343241 0.345775 0.862679 0.369087 0.573015 0.658621 0.487722 0.572894 0.70982 0.409815 0.201872 0.848196 0.489706 0.201912 0.899074 0.388456 0.149217 0.909096 0.388946 0.34089 -0.86432 -0.369789 0.994035 0.0944506 0.054531 0.994036 0.100347 0.0426863 0.994251 0.098447 0.0421194 0.991754 0.10241 0.0770486 0.996675 0.0679106 0.0450137 0.658678 -0.651619 -0.376212 0.93179 -0.314364 -0.181498 0.994046 0.088352 0.0637755 0.993745 -0.0893768 -0.0669523 0.971837 -0.188606 -0.141285 0.994056 0.0974635 0.0485145 0.994035 0.0944505 0.054531 0.931791 -0.314364 -0.181498 0.931639 -0.286875 -0.223051 0.558446 -0.768059 -0.313406 0.739312 -0.619083 -0.264867 0.93179 -0.333735 -0.142785 0.888072 -0.427073 -0.170107 0.971843 -0.216637 -0.0926854 0.237287 -0.841291 -0.48572 0.237287 -0.893131 -0.382115 0.10813 -0.919639 -0.377588 0.887837 -0.368286 -0.275883 0.739297 -0.538936 -0.403717 0.658467 -0.598333 -0.45653 0.558107 -0.664102 -0.49748 0.340888 -0.752408 -0.56363 0.658679 -0.69177 -0.295966 0.658679 -0.651618 -0.376212 0.237289 -0.841291 -0.485719 0.237192 -0.773499 -0.587742 0.108041 -0.79566 -0.59603 0.939515 0.273697 0.205917 0.939604 0.260091 0.222482 0.93949 0.260247 0.222777 0.939578 0.260233 0.222422 0.939697 0.260653 0.221425 0.939842 0.259585 0.222065 0.939865 0.259504 0.222064 0.939743 0.259798 0.222234 0.939508 0.315196 0.13408 0.939903 0.321992 0.113596 0.939805 0.322147 0.113965 0.93969 0.322105 0.115026 0.939697 0.322158 0.11482 0.939545 0.322865 0.114079 0.939486 0.323073 0.11397 0.939528 0.322933 0.11402 0.939645 0.322613 0.113966 0.939777 0.322272 0.113844 0.939515 0.315178 0.134072 0.939511 0.315186 0.134077 0.939694 0.306182 0.152409 0.939694 0.306183 0.152408 0.939498 0.296661 0.171277 0.939498 0.296661 0.171277 0.939694 0.285079 0.188961 0.939694 0.285079 0.18896 0.939511 0.273705 0.205922 0.939508 0.273713 0.205929 0.93969 0.26052 0.221613 0 -0.984834 -0.173499 -0.00049346 -0.984614 -0.174744 0.000540489 -0.864348 -0.502893 0 -0.865034 -0.501714 0.701597 -0.70161 -0.124518 0.701595 -0.701612 -0.124519 0.701594 -0.615915 -0.35835 0.701596 -0.615913 -0.358348 -0.000353936 0.221074 -0.975257 0.00621427 0.316782 -0.948478 0.0220234 0.407459 -0.912958 -0.00551233 0.512456 -0.858696 8.28103e-06 0.623331 -0.781958 6.71884e-06 0.660694 -0.750656 0.0082844 0.785289 -0.619074 -0.020501 0.837014 -0.546797 0.0193287 0.973438 -0.228134 0 0.985784 -0.168017 0.000876439 0.0877185 -0.996145 0.0212857 -0.0406097 -0.998948 -0.00330555 -0.15121 -0.988496 0.000182572 -0.289632 -0.957138 -0.000469835 -0.338883 -0.940828 0.0100161 -0.500373 -0.865752 -0.00637792 -0.551607 -0.83408 0.00768618 -0.819994 -0.57232 0 -0.833458 -0.552583 -0.697586 -0.587544 -0.410079 -0.697588 -0.587542 -0.410079 -0.704524 -0.406977 -0.581391 -0.786897 -0.308788 -0.534269 -0.685363 -0.270461 -0.676113 -0.70701 -0.204829 -0.676892 -0.69759 -0.029103 -0.715906 -0.697589 -0.0291034 -0.715907 -0.697588 0.292015 -0.654292 -0.697586 0.697599 -0.163489 -0.697587 0.697599 -0.163488 -0.699418 0.561276 -0.442475 -0.646819 0.587889 -0.485811 -0.707007 0.440824 -0.553006 -0.697587 0.292015 -0.654293 -0.694736 0.430089 0.576512 -0.458491 -0.351185 0.816367 -0.694738 0.430087 0.57651 -0.702914 0.15925 0.693218 -0.46676 0.103545 0.878301 -0.705014 -0.0255164 0.708734 -0.703698 -0.198281 0.682271 -0.694741 -0.66072 -0.284227 -0.69474 -0.66072 -0.284227 -0.702916 -0.711245 0.00632214 -0.782472 -0.621726 -0.0345627 -0.561448 -0.79738 0.221272 -0.701772 -0.697301 0.145902 -0.703698 -0.617455 0.351509 -0.458499 -0.712315 0.5314 -0.704397 -0.504947 0.498852 -0.704397 -0.367753 0.607111 -0.700681 0.700693 0.134448 -0.70068 0.700693 0.134448 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 -0.586031 -0.397343 -0.706178 -0.58603 -0.397343 -0.706178 -0.637124 -0.308846 -0.706177 -0.637125 -0.308847 0 -0.910089 -0.414414 -0.0420202 -0.899054 -0.435817 0 -0.877811 -0.479008 0 -0.827686 -0.561191 -0.0629305 -0.812324 -0.579802 0 -0.853738 -0.520703 -0.706174 0.586034 0.397345 -0.706174 0.586033 0.397344 -0.706175 0.637127 0.308847 -0.706177 0.637125 0.308847 0 0.959822 0.280611 0.0173644 0.981936 0.188413 0 0.995631 0.093378 0 -0.86671 -0.498812 0.0262995 -0.918292 -0.395029 0.0108387 -0.949093 -0.31481 -0.0197298 -0.999766 0.00888676 0.00457623 -0.518098 0.855309 -6.76618e-05 -0.541339 0.840804 8.61019e-05 -0.711387 0.7028 -0.00521408 -0.728755 0.684755 0.00478476 -0.869034 0.494729 0.0130121 -0.846554 0.532144 -0.0208406 -0.963378 0.267336 -0.00416534 -0.946938 0.32139 0.00493713 -0.997842 -0.0654749 0 0.597955 0.80153 0.0272977 0.640657 0.767342 -0.0219136 0.22384 0.974379 0.00552666 0.290895 0.956739 -4.17609e-06 0.0865246 0.99625 7.27486e-06 -0.0359795 0.999353 0.0147481 0.0374017 0.999192 -0.0292792 -0.278953 0.959858 0.0251974 -0.142828 0.989427 -0.00320886 -0.37154 0.928412 -0.994042 0.0887149 0.0633209 -0.971841 -0.191796 -0.136896 -0.65892 -0.651436 -0.376107 -0.108088 -0.904757 -0.411986 -0.558294 -0.755049 -0.343816 -0.341055 -0.855523 -0.389567 -0.237324 -0.887511 -0.394969 -0.23762 -0.852669 -0.465288 -0.153988 -0.855696 -0.494036 -0.237621 -0.829285 -0.505789 -0.237426 -0.790663 -0.564341 -0.887884 -0.418702 -0.190658 -0.739467 -0.612666 -0.278981 -0.108172 -0.798398 -0.592334 -0.341051 -0.765137 -0.546122 -0.658919 -0.612255 -0.437001 -0.558599 -0.66478 -0.496019 -0.739474 -0.547931 -0.391089 -0.971845 -0.214436 -0.0976447 -0.931696 -0.333884 -0.143051 -0.931861 -0.314208 -0.181408 -0.658697 -0.688174 -0.304197 -0.658919 -0.651436 -0.376107 -0.931861 -0.314208 -0.181408 -0.931861 -0.29531 -0.210779 -0.888089 -0.365508 -0.27875 -0.994042 0.0991952 0.0451691 -0.994042 0.0991953 0.0451691 -0.994053 0.0955951 0.0521644 -0.994978 0.086685 0.0500477 -0.994053 0.0929736 0.0567051 -0.994042 0.0887153 0.0633211 0 0.806885 0.590708 0.126161 0.840638 0.526699 0 0.827686 0.561191 0 0.883513 0.468406 0.0635016 0.898033 0.435322 0 0.915011 0.403429 -0.891408 0.207567 -0.402874 -0.893729 0.446664 0.0417103 -0.90088 0.433895 -0.0122357 -0.982603 0.178708 -0.0505426 -0.968983 0.237712 -0.0675719 -0.95918 0.270877 -0.081234 -0.955076 0.287109 -0.0734736 -0.937214 0.340379 -0.075973 -0.963017 -0.1667 -0.211682 -0.97139 -0.152027 -0.182453 -0.876427 -0.361571 -0.318029 -0.884047 -0.354536 -0.304575 -0.858963 -0.129343 -0.495432 -0.839076 -0.132878 -0.527537 -0.946585 0.0121349 -0.322226 -0.938297 0.010478 -0.345673 -0.978164 0.202313 -0.0475861 -0.993506 0.112709 0.01559 -0.993503 0.113427 0.00928809 -0.712672 0.701496 -0.00144576 -0.88495 0.46011 0.0718472 -0.885799 0.457609 0.0771627 -0.792141 0.116817 -0.599055 -0.849342 0.229873 -0.475159 -0.805194 0.355372 -0.474735 -0.812788 0.393798 -0.4293 -0.759742 0.531132 -0.375088 -0.771361 0.549882 -0.320362 -0.722811 0.654903 -0.220562 -0.102734 0.666089 -0.738763 -0.199232 0.580665 -0.789389 0.0440615 0.832813 -0.551798 0.0141927 0.831187 -0.555812 -0.275285 0.81794 -0.505166 -0.149109 0.984008 0.0974363 -0.151988 0.97591 -0.156521 -0.933087 0.354425 -0.0610838 -0.918225 0.393422 -0.0456389 -0.916086 0.398459 -0.0449154 -0.902767 0.429904 0.0139796 -0.738156 0.652332 -0.172014 -0.697724 0.715718 -0.0304729 -0.461103 0.882682 -0.0908635 -0.105761 -0.824277 -0.556221 -0.121702 -0.825532 -0.551076 -0.0853857 -0.526648 -0.845785 -0.15191 -0.536526 -0.830098 -0.0927366 -0.329307 -0.939658 -0.164212 -0.138768 -0.976616 -0.146556 -0.134359 -0.980035 -0.0375613 0.515451 -0.856096 -0.112381 0.328639 -0.937746 -0.225439 0.249948 -0.941649 -0.211865 0.241211 -0.947064 -0.0696666 0.0958561 -0.992954 -0.353637 0.816617 -0.456155 -0.456007 0.588786 -0.667374 -0.364128 0.625844 -0.689732 -0.489615 0.304476 -0.81705 -0.398065 0.333331 -0.854655 -0.521633 -0.0325064 -0.852551 -0.443215 -0.0189489 -0.896215 -0.546157 -0.381682 -0.745675 -0.493425 -0.383257 -0.780798 -0.553287 -0.672917 -0.490975 -0.546204 -0.675196 -0.495753 -0.17731 0.845275 -0.504054 -0.301513 0.577302 -0.758823 -0.18742 0.608131 -0.771395 -0.324421 0.25755 -0.910175 -0.209392 0.284132 -0.935641 -0.342314 -0.108586 -0.93329 -0.242329 -0.0923929 -0.965785 -0.351087 -0.474386 -0.807277 -0.282721 -0.470574 -0.83584 -0.344987 -0.773631 -0.531488 -0.333634 -0.774772 -0.537045 -0.148812 0.948653 0.27913 -0.230476 0.954321 0.190139 -0.341433 0.921007 0.187535 -0.424997 0.889792 0.166277 -0.484351 0.853643 0.191566 -0.687666 0.705421 0.171746 -0.647365 0.750653 0.132054 -0.870212 0.447877 0.205275 -0.850011 0.505914 0.146742 -0.174047 0.970341 -0.167767 -0.1797 0.969164 -0.16861 -0.423352 0.896426 -0.131126 -0.487235 0.798684 -0.353137 -0.50333 0.78937 -0.351501 -0.600329 0.58009 -0.550546 -0.532643 0.619397 -0.576748 -0.641639 0.340085 -0.687489 -0.575733 0.369541 -0.729363 -0.684279 0.047626 -0.727663 -0.629471 0.0598209 -0.774718 -0.721166 -0.264276 -0.640373 -0.685631 -0.268185 -0.676747 -0.739822 -0.533354 -0.410119 -0.725699 -0.540973 -0.425099 -0.146451 0.637308 0.756565 -0.824707 -0.208443 0.525746 -0.651392 0.521827 0.550804 -0.942263 0.060238 0.329411 -0.971801 0.0646746 0.226759 -0.978816 0.0486815 0.19887 -0.989309 0.0737238 0.125825 -0.993672 0.0682229 0.0892248 -0.851107 0.414872 0.321712 -0.873464 0.322048 0.365165 -0.8894 0.276172 0.364276 -0.901406 0.226603 0.368942 -0.895306 0.235438 0.378148 -0.918229 0.163937 0.360527 -0.741733 -0.027118 0.670147 -0.782194 -0.043217 0.621535 -0.708895 0.168693 0.684843 -0.91196 0.169852 0.373468 -0.938587 0.11093 0.326726 -0.786961 -0.211128 0.579756 -0.849348 -0.29657 0.43664 -0.79219 -0.460391 0.400594 -0.856724 -0.492743 0.152408 -0.84357 -0.52026 0.133111 -0.884011 -0.443603 -0.147451 -0.877483 -0.452061 -0.160201 -0.921891 0.113049 0.37059 -0.959989 0.0903925 0.265046 -0.891441 -0.245107 0.381125 -0.944652 -0.271737 0.183824 -0.941309 -0.291331 0.170483 -0.970892 -0.237968 -0.0271966 -0.965064 -0.256839 -0.0518175 -0.115181 -0.944512 -0.30762 -0.0768016 -0.995269 -0.0595002 -0.146663 -0.988808 -0.0273673 -0.0529673 -0.943966 0.325764 -0.148665 -0.918252 0.367032 -0.0857136 -0.837307 0.539973 -0.146643 -0.709804 0.688966 -0.333937 -0.850557 -0.406251 -0.105765 -0.893874 -0.435664 -0.296937 -0.830305 -0.471617 -0.143079 -0.709594 0.689931 -0.0595375 -0.53422 0.843246 -0.223397 -0.388236 0.894073 -0.116141 -0.356613 0.927005 -0.0132373 -0.0625532 0.997954 -0.298407 -0.102422 0.948927 -0.108507 0.0486522 0.992904 -0.0837929 0.0936524 0.992073 -0.0301119 0.293144 0.955594 -0.178505 0.338949 0.923715 -0.112026 0.652394 0.749554 -0.341451 0.622959 0.703799 -0.692764 0.479659 0.538522 -0.714398 0.327703 0.61826 -0.412914 0.365048 0.834411 -0.487267 0.0934222 0.868242 -0.353599 0.0131819 0.935304 -0.447582 -0.254016 0.857407 -0.37766 -0.311108 0.872115 -0.480017 -0.531756 0.697725 -0.412111 -0.594171 0.690742 -0.513924 -0.743325 0.428194 -0.454267 -0.794568 0.402869 -0.542567 -0.837449 0.0655809 -0.499059 -0.865798 0.0365285 -0.553198 -0.762952 -0.334479 -0.546581 -0.76542 -0.339679 -0.344669 -0.849334 -0.399793 -0.287819 -0.957589 -0.0135674 -0.346267 -0.937963 0.0180083 -0.25301 -0.89316 0.371821 -0.332867 -0.851377 0.405409 -0.223309 -0.691376 0.687119 -0.313055 -0.634929 0.706301 -0.200946 -0.393268 0.897196 -0.291653 -0.337288 0.895084 -0.18745 -0.0405017 0.981439 -0.269278 1.69862e-05 0.963063 -0.1797 0.338669 0.923586 -0.463506 0.331762 0.821642 -0.42503 0.588927 0.687397 -0.484356 0.592756 0.643459 -0.870905 0.371031 0.322273 -0.89297 0.287822 0.346069 -0.690171 0.353772 0.631276 -0.744778 0.141105 0.652224 -0.503286 0.0902028 0.859399 -0.593143 -0.15992 0.789055 -0.545223 -0.213008 0.810777 -0.633575 -0.403532 0.66011 -0.588801 -0.464243 0.661659 -0.677986 -0.595345 0.431161 -0.639889 -0.64775 0.413475 -0.718478 -0.686513 0.111758 -0.691091 -0.717513 0.0869961 -0.739778 -0.62517 -0.248779 -0.726937 -0.634193 -0.263365 -0.939621 0.276129 0.20215 -0.939565 0.311587 0.141883 -0.93839 0.32107 0.127818 -0.939692 0.31832 0.125107 -0.939425 0.319341 0.124508 -0.939408 0.319401 0.124479 -0.939888 0.318074 0.124255 -0.939984 0.317934 0.123888 -0.939936 0.318018 0.124041 -0.93977 0.318411 0.124285 -0.939573 0.318913 0.124485 -0.939633 0.267135 0.213842 -0.939833 0.266704 0.213502 -0.940957 0.265701 0.209769 -0.939692 0.267532 0.213086 -0.939957 0.266372 0.21337 -0.939978 0.266287 0.213383 -0.939692 0.267831 0.21271 -0.939472 0.267459 0.214147 -0.939449 0.267476 0.214225 -0.939565 0.278668 0.198901 -0.94337 0.269003 0.194139 -0.936007 0.3005 0.183277 -0.939622 0.289995 0.181695 -0.939661 0.300307 0.163872 -0.937285 0.307961 0.163269 -0.94337 0.302631 0.135894 -0.939621 0.313132 0.13806 -0.939692 0.318125 0.125597 -0.149349 0.797836 0.584083 -0.488788 0.703929 0.515335 -0.346078 0.858469 0.378499 -0.655057 0.691363 0.304823 -0.850962 0.480588 0.211892 -0.850962 0.480589 0.211892 -0.850962 0.464045 0.24602 -0.850962 0.464045 0.24602 -0.850962 0.445082 0.278865 -0.850963 0.445081 0.278864 -0.850963 0.423797 0.310255 -0.850962 0.423798 0.310256 -0.655064 0.609661 0.446324 -0.573438 0.665442 0.477867 -0.573327 0.694305 0.435015 -0.573328 0.694304 0.435014 -0.573328 0.723885 0.383777 -0.57333 0.723884 0.383777 -0.573441 0.746564 0.337355 -0.488788 0.798258 0.351952 -0.346093 0.75702 0.554203 -0.202131 0.793638 0.57383 -0.202093 0.829923 0.519987 -0.202091 0.829924 0.519986 -0.202091 0.865283 0.458742 -0.202089 0.865284 0.458742 -0.202127 0.893772 0.400396 -0.149348 0.904749 0.398904 0.707098 -0.664944 -0.240545 0.671179 -0.680809 -0.293288 0.70647 -0.650692 -0.278391 0.70647 -0.612924 -0.353872 0.70647 -0.612923 -0.353871 0.706522 -0.567455 -0.422874 0.672811 -0.592107 -0.443548 0.707098 -0.540789 -0.455587 0.70647 0.650692 0.27839 0.706471 0.65069 0.27839 0.706471 0.612923 0.353871 0.70647 0.612923 0.353871 0.70647 0.566438 0.42432 0.70647 0.566439 0.42432 0.696401 -0.696413 0.173306 0.43046 -0.890704 0.146119 0.70593 -0.650564 0.280053 0.696401 -0.533962 0.47949 0.332789 -0.76193 0.555621 0.705268 -0.454985 0.543677 0.704459 -0.323483 0.63174 0.52401 -0.293086 0.799696 0.696399 0.419495 0.582282 0.6964 0.419494 0.582281 0.7035 0.167643 0.69064 0.53009 0.115391 0.840053 0.705271 -0.00408926 0.708926 0.704462 -0.161353 0.691157 0.694739 0.716797 0.0594934 0.487515 0.497605 -0.717439 0.69474 0.716797 0.0594931 0.702914 0.672357 -0.232051 0.494616 0.786038 -0.37081 0.705013 0.587664 -0.396998 0.703695 0.473721 -0.52953 0.704395 0.320214 -0.633475 0.704395 0.155725 -0.692516 0.487517 0.0722197 -0.870122 0.694739 -0.591018 -0.409922 0.694741 -0.591016 -0.40992 0.702916 -0.371318 -0.606656 0.494621 -0.370809 -0.786035 0.705015 -0.201062 -0.680094 0.703698 -0.0288466 -0.709914 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.00863698 -0.627737 0.778378 -0.00531427 -0.641773 0.766877 0.00902109 -0.480778 0.876796 -1.83404e-05 -0.455774 0.890096 4.86793e-06 -0.256387 0.966574 -0.00737074 -0.227334 0.973789 0.0082007 -0.0351936 0.999347 -2.46845e-05 -0.00576816 0.999983 1.82208e-05 0.207275 0.978283 -0.00928982 0.235876 0.971739 0.00337752 0.383263 0.923633 -0.0236765 0.584372 0.811141 -0.0218878 0.586944 0.809332 0 0.738637 0.674104 -1.4487e-05 -0.681979 0.731372 -5.9403e-06 -0.807984 0.589205 0.00962882 -0.82376 0.566857 -0.00358749 -0.918504 0.395395 0.014151 -0.964717 0.262908 -0.0128892 -0.986728 0.161872 0 -0.998784 0.0492953 -0.939621 0.13806 0.313132 -0.939566 0.1989 0.278666 -0.938389 0.214145 0.271234 -0.939692 0.213117 0.267506 -0.939424 0.214307 0.267498 -0.939408 0.214371 0.267503 -0.939888 0.213334 0.266644 -0.939983 0.213396 0.266258 -0.939935 0.213392 0.266432 -0.939772 0.213608 0.266835 -0.939573 0.213946 0.267264 -0.939634 0.124425 0.318759 -0.939832 0.124222 0.318252 -0.940957 0.125221 0.314516 -0.939692 0.125148 0.318304 -0.939959 0.123991 0.317967 -0.939978 0.12392 0.31794 -0.939692 0.125594 0.318126 -0.939471 0.124553 0.319187 -0.939449 0.124529 0.319262 -0.939565 0.141883 0.311587 -0.94337 0.135894 0.302631 -0.936007 0.168602 0.308972 -0.939622 0.160295 0.30235 -0.93966 0.178138 0.292071 -0.937285 0.185067 0.295376 -0.94337 0.194139 0.269004 -0.939621 0.20215 0.27613 -0.939692 0.212706 0.267833 -0.149345 0.398904 0.90475 -0.488784 0.351953 0.79826 -0.346072 0.554207 0.757026 -0.655058 0.446327 0.609665 -0.850962 0.310256 0.423798 -0.850962 0.310257 0.423799 -0.850962 0.278866 0.445083 -0.850963 0.278864 0.445081 -0.850963 0.246019 0.464044 -0.850962 0.24602 0.464046 -0.850962 0.211892 0.480589 -0.850962 0.211891 0.480589 -0.655069 0.304818 0.691354 -0.573439 0.337356 0.746564 -0.573328 0.383777 0.723885 -0.573329 0.383777 0.723885 -0.573329 0.435014 0.694303 -0.573332 0.435013 0.694302 -0.573443 0.477865 0.665439 -0.48879 0.515335 0.703928 -0.346096 0.378497 0.858462 -0.202131 0.400396 0.893771 -0.202093 0.458741 0.865283 -0.20209 0.458742 0.865284 -0.20209 0.519987 0.829924 -0.20209 0.519987 0.829924 -0.202128 0.573831 0.793638 -0.149351 0.584083 0.797835 0.7071 -0.455581 -0.540792 0.671185 -0.44295 -0.594395 0.70647 -0.42432 -0.566439 0.70647 -0.353872 -0.612923 0.706473 -0.35387 -0.612921 0.706526 -0.279991 -0.649943 0.672812 -0.291005 -0.680177 0.707102 -0.240539 -0.664943 0.706474 0.424317 0.566435 0.706474 0.424317 0.566435 0.706474 0.35387 0.61292 0.706468 0.353873 0.612925 0.706468 0.278391 0.650693 0.706467 0.278392 0.650694 0.696796 -0.696809 0.170096 0.457749 -0.877323 0.144116 0.706064 -0.651631 0.277219 0.696799 -0.540058 0.472026 0.324164 -0.773796 0.544203 0.696792 0.0753051 0.71331 0.696796 0.0753061 0.713306 0.703907 -0.18831 0.684876 0.535526 -0.308278 0.786242 0.705123 -0.344756 0.619633 0.705124 -0.46673 0.533819 0.698071 0.572692 0.429793 0.69807 0.572692 0.429794 0.698068 0.70246 0.138749 0.618518 0.765316 0.17812 0.706901 0.707306 0.00301773 0.698069 0.693095 -0.179777 0.698069 0.693095 -0.179777 0.698071 0.546453 -0.462695 0.698069 0.546454 -0.462696 0.698069 0.291582 -0.653972 0.698067 -0.329499 -0.635714 0.698065 -0.3295 -0.635716 0.700598 -0.0449612 -0.712138 0.634902 -0.0227045 -0.772259 0.706904 0.113643 -0.69812 0.698072 0.29158 -0.65397 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.112721 0.993627 -0.00504595 0.104987 0.994461 0.00308027 -0.265115 0.964212 -0.00404569 -0.669143 0.743122 0.000126143 -0.584336 0.811512 -0.000956059 -0.486198 0.873848 -3.76037e-05 -0.483282 0.875465 9.94089e-06 -0.257695 0.966226 1.52909e-05 -0.658216 0.752829 -1.35061e-05 -0.817966 0.575267 0.00763705 -0.83022 0.557384 -0.00305197 -0.920186 0.391469 -0.00128716 -0.925123 0.379666 0.00405509 -0.986767 0.162093 0 -0.985205 0.171378 0 -0.527509 -0.84955 -0.0254454 -0.460025 -0.887541 -0.00385834 -0.346043 -0.938211 0.0105394 -0.0630066 -0.997958 -0.00709849 -0.0999057 -0.994972 0.00161549 0.160669 -0.987007 0.0201075 0.322515 -0.946351 -0.0192707 0.407143 -0.913161 -0.00122818 0.554716 -0.832039 0.00305228 0.677823 -0.735219 -0.0539172 0.81185 -0.581371 -0.0129093 0.763108 -0.646142 0.000749365 0.881333 -0.472495 0 0.799816 0.600246 -0.00495566 0.795119 0.606434 0.00438694 0.97396 0.226679 -0.00778006 0.968769 0.247842 5.6587e-06 0.99864 0.0521452 4.62989e-07 0.999991 0.00426647 0.000872361 0.999986 -0.00519475 -0.0054373 0.967954 -0.25107 -0.0432671 0.981385 -0.187114 -0.00224292 0.925331 -0.379154 0 0.59954 0.800345 0 0.59954 0.800345 0 0.5 0.866025 0 0.5 0.866025 0 0.393349 0.919389 0 0.393349 0.919389 0 -0.393349 -0.919389 0 -0.393349 -0.919389 0 -0.5 -0.866025 0 -0.5 -0.866025 0 -0.599539 -0.800345 0 -0.599539 -0.800345 0.879243 0.125534 0.459535 0.887083 0.0510251 0.458781 0.954993 -0.0821848 0.285017 0.960102 -0.0884364 0.2653 0.978436 -0.0582609 0.198163 0.978976 -0.0581037 0.195526 0.991396 0.00378026 0.13084 0.990797 0.00127329 0.135349 0.965171 -0.189753 -0.180108 0.793207 -0.601567 0.0945545 0.859466 -0.489388 -0.147706 0.839106 -0.522773 -0.150364 0.884192 -0.291274 -0.365191 0.876485 -0.305377 -0.372181 0.859292 -0.349008 0.373913 0.938544 -0.0860376 0.334265 0.933186 -0.0719028 0.352127 0.821647 -0.485524 0.298603 0.847485 -0.482455 0.221375 0.891283 -0.409498 0.194745 0.947045 -0.321102 -0.000172853 0.938319 -0.34577 -0.000951554 0.970911 -0.188438 -0.147725 0.989048 -0.129097 -0.0715415 0.807333 -0.175126 0.563511 0.693243 -0.466038 0.549748 0.77072 -0.5386 0.340442 0.902132 -0.0230726 0.430844 0.887847 0.0564835 0.456659 0.749555 -0.00903605 0.661881 0.710137 0.00404303 0.704052 0.105538 -0.820363 0.56202 0.138595 -0.822137 0.552162 0.276006 -0.534785 0.79864 0.109156 -0.250284 0.961999 0.0572733 -0.478795 0.876057 0.220802 -0.547617 0.80707 0.206464 -0.55815 0.803643 0.0678386 -0.66298 0.745558 0.146985 0.157558 0.97651 0.0751921 0.114077 0.990622 0.106178 -0.511929 -0.852441 0.15143 -0.525703 -0.837081 0.105074 -0.684625 -0.721283 0.111221 -0.826844 -0.551324 0.0784728 -0.919262 0.385746 0.152082 -0.971101 0.183938 0.0787954 -0.976014 0.20295 0.101832 -0.984256 -0.144466 0.178218 -0.969197 -0.169986 0.0897973 -0.932038 -0.351058 0.14999 -0.815792 -0.558557 0.354224 -0.484335 0.799965 0.45711 -0.688464 0.563087 0.363178 -0.709128 0.60435 0.490837 -0.82732 0.273167 0.397292 -0.864991 0.306512 0.522591 -0.850135 -0.0645733 0.442835 -0.895329 -0.0477916 0.546609 -0.730836 -0.408776 0.493389 -0.767605 -0.409084 0.553357 -0.467289 -0.689519 0.546232 -0.472288 -0.691791 0.176396 -0.530616 0.829054 0.302653 -0.779682 0.548177 0.186327 -0.790091 0.583985 0.325668 -0.918874 0.222735 0.208476 -0.944251 0.254808 0.343263 -0.928194 -0.143621 0.24186 -0.962443 -0.123317 0.351508 -0.789178 -0.503627 0.282654 -0.819771 -0.498078 0.345033 -0.503867 -0.791878 0.33367 -0.50979 -0.792956 0.87955 0.126437 0.4587 0.763479 0.147476 0.628769 0.69396 0.116222 0.710572 0.651406 0.150627 0.743628 0.484446 0.162599 0.859578 0.918302 -0.0577999 0.391637 0.901022 -0.0509534 0.43077 0.758733 -0.262211 0.596296 0.805311 -0.228501 0.547048 0.700509 -0.338331 0.628346 0.633803 -0.0756568 0.769785 0.46111 -0.119018 0.879325 0.425657 0.132612 0.895114 0.341461 0.155465 0.926949 0.206314 -0.205092 0.956751 0.1792 -0.20022 0.963224 0.424092 -0.163318 0.890771 0.48687 -0.377258 0.787803 0.50267 -0.376268 0.778296 0.601393 -0.571157 0.558664 0.531868 -0.595997 0.601584 0.642846 -0.698902 0.313505 0.575094 -0.740968 0.346746 0.685234 -0.728048 0.0200388 0.62921 -0.776454 0.0348513 0.721675 -0.629617 -0.287694 0.685624 -0.667426 -0.290625 0.73994 -0.390822 -0.547491 0.72568 -0.406494 -0.555114 0.146157 0.784664 0.602446 0.826271 0.51474 -0.228734 0.651429 0.568646 0.502276 0.880893 0.370659 0.294345 0.992268 0.115974 0.0442004 0.992327 0.0929046 0.0815849 0.976264 0.213196 0.0381588 0.978908 0.198453 0.0485427 0.963206 0.263081 0.0549822 0.942932 0.328758 0.0528935 0.902136 0.375828 0.211907 0.8958 0.384886 0.222273 0.919327 0.363957 0.149579 0.851018 0.327628 0.410401 0.740542 0.670396 -0.0465462 0.783616 0.617546 -0.0676998 0.707954 0.690445 0.148617 0.912305 0.377986 0.157561 0.939733 0.327487 0.0982577 0.785901 0.574611 -0.228433 0.847487 0.432956 -0.307108 0.793259 0.382584 -0.473677 0.856961 0.135676 -0.497201 0.844206 0.113591 -0.523844 0.884162 -0.162484 -0.438015 0.877675 -0.17636 -0.445628 0.923011 0.370523 0.103747 0.960832 0.266499 0.0760318 0.891326 0.373335 -0.257213 0.944822 0.174616 -0.277165 0.94184 0.158823 -0.296162 0.97092 -0.0336478 -0.237029 0.965173 -0.0610596 -0.254388 0.115157 -0.339935 -0.933372 0.0770982 -0.0948901 -0.992498 0.14647 -0.060913 -0.987338 0.0440315 0.32419 -0.944967 0.0571111 0.329494 -0.942429 0.0998407 0.559907 -0.822518 0.181859 0.663982 -0.725296 0.334012 -0.435928 -0.835705 0.105769 -0.465914 -0.878486 0.278922 -0.503118 -0.81797 0.012257 0.995489 -0.0940841 0.315357 0.937392 -0.147804 0.112607 0.993634 0.00322654 0.136035 0.681046 -0.719493 0.0636171 0.818044 -0.571627 0.202853 0.882545 -0.424224 0.247983 0.864779 -0.436648 0.108766 0.923728 -0.367282 0.0842358 0.994759 0.0579552 0.0328573 0.967703 0.249943 0.190218 0.933057 0.305324 0.0915626 0.773046 0.627708 0.341467 0.724979 0.598169 0.693993 0.557226 0.45593 0.714751 0.629599 0.304527 0.412201 0.845767 0.338775 0.486916 0.870868 0.067094 0.354184 0.934971 -0.0195564 0.447647 0.848563 -0.282049 0.378516 0.860282 -0.341525 0.480132 0.67972 -0.554485 0.413098 0.668786 -0.618123 0.514059 0.403019 -0.757178 0.455179 0.373766 -0.808153 0.542686 0.0370952 -0.839116 0.499644 0.00529513 -0.866215 0.553289 -0.360446 -0.750966 0.546655 -0.366037 -0.753117 0.34468 -0.429068 -0.834923 0.288263 -0.0478237 -0.956356 0.346237 -0.013862 -0.938045 0.253715 0.339571 -0.905715 0.332838 0.376521 -0.864553 0.224034 0.662059 -0.715183 0.31305 0.684701 -0.658167 0.201543 0.882717 -0.424489 0.291658 0.883365 -0.36688 0.187837 0.97935 -0.0747709 0.269282 0.962528 -0.0320571 0.179196 0.934252 0.30832 0.463857 0.833127 0.301225 0.425707 0.708831 0.562434 0.484453 0.663081 0.570639 0.875353 0.333514 0.350036 0.889584 0.363659 0.276392 0.689708 0.642335 0.334228 0.745685 0.656169 0.115743 0.502641 0.862181 0.063223 0.593262 0.783383 -0.185339 0.546281 0.802082 -0.241333 0.633761 0.646478 -0.424752 0.590004 0.6439 -0.487123 0.678251 0.411039 -0.609116 0.64095 0.389196 -0.661597 0.718705 0.0884186 -0.689671 0.691735 0.0607474 -0.719592 0.73991 -0.26987 -0.6162 0.727073 -0.285607 -0.624335 0.572897 0.409814 0.709818 0.850726 0.315995 0.420014 0.879519 0.18627 0.437893 0.654676 0.297337 0.694975 0.764992 0.253333 0.592123 0.845143 0.213401 0.490096 0.851115 0.233939 0.469975 0.850697 0.262828 0.455232 0.850697 0.262828 0.455232 0.851114 0.290042 0.437584 0.345772 0.369087 0.86268 0.488419 0.34324 0.802267 0.14921 0.388946 0.909097 0.201913 0.388456 0.899073 0.201873 0.489706 0.848195 0.844348 0.32123 0.428821 0.654697 0.453187 0.604974 0.573018 0.487721 0.658619 0.488423 0.523163 0.698387 0.345773 0.562559 0.750979 0.573018 0.32652 0.751688 0.572896 0.409814 0.709819 0.20187 0.489706 0.848196 0.20191 0.584393 0.78595 0.149214 0.592828 0.791385 0.340894 -0.563628 -0.752406 0.994035 0.0545311 0.0944507 0.994036 0.06556 0.087141 0.994251 0.064198 0.0857001 0.991754 0.0501654 0.117931 0.996676 0.0363047 0.0729359 0.658678 -0.376212 -0.651619 0.93179 -0.181499 -0.314365 0.994046 0.0446274 0.0994074 0.993745 -0.043926 -0.10267 0.971837 -0.0926948 -0.216659 0.994056 0.0601492 0.0907459 0.994035 0.0545309 0.0944503 0.931791 -0.181498 -0.314364 0.931639 -0.136915 -0.336605 0.558443 -0.508457 -0.655449 0.739314 -0.403707 -0.538921 0.93179 -0.217632 -0.290523 0.888072 -0.284803 -0.360854 0.971842 -0.14127 -0.188587 0.237287 -0.48572 -0.841291 0.237286 -0.582416 -0.777487 0.108123 -0.607637 -0.78682 0.887838 -0.181002 -0.423063 0.739296 -0.264874 -0.619099 0.658466 -0.289907 -0.694533 0.558105 -0.32639 -0.762882 0.340887 -0.369789 -0.864322 0.658681 -0.451107 -0.602198 0.658681 -0.376211 -0.651617 0.237285 -0.48572 -0.841292 0.237188 -0.375999 -0.895749 0.108042 -0.391047 -0.914007 0.939515 0.13407 0.315178 0.939604 0.114004 0.322719 0.93949 0.113991 0.323055 0.939579 0.114158 0.322738 0.939697 0.115017 0.322087 0.939843 0.11377 0.322105 0.939864 0.113705 0.322067 0.939743 0.113875 0.322361 0.939507 0.205927 0.273715 0.939903 0.222055 0.259373 0.939805 0.222005 0.259771 0.93969 0.221437 0.260669 0.939697 0.221586 0.260517 0.939545 0.222568 0.260228 0.939485 0.222807 0.260238 0.939528 0.222658 0.260211 0.939645 0.222407 0.260004 0.939777 0.222173 0.259728 0.939515 0.205916 0.273699 0.939511 0.205921 0.273707 0.939693 0.18896 0.28508 0.939693 0.188959 0.285081 0.939497 0.171278 0.296662 0.939498 0.171278 0.296662 0.939694 0.152407 0.306184 0.939694 0.152408 0.306183 0.939511 0.134075 0.315187 0.939507 0.134078 0.315197 0.939689 0.114815 0.322182 0 -0.988067 -0.154024 -0.0178826 -0.979033 -0.202914 0.000937607 -0.933434 -0.358747 -0.00366202 -0.817866 -0.575397 -0.00532878 -0.81998 -0.572367 0.000278662 -0.685389 -0.728177 -0.00443676 -0.521807 -0.853052 0 -0.513081 -0.85834 0.699627 -0.69964 -0.145007 0.699629 -0.699638 -0.145006 0.699627 -0.584376 -0.411129 0.699627 -0.584376 -0.411129 0.699628 -0.372839 -0.609518 0.699629 -0.372838 -0.609517 0 0.981951 -0.189138 0.0113027 0.97498 -0.222006 -0.00651685 0.865939 -0.500107 0.0215158 0.782614 -0.622136 0.00270887 0.719231 -0.694766 -0.00184638 0.574824 -0.818275 0.0187062 0.436125 -0.899692 -0.00034446 0.364098 -0.931361 9.88253e-05 0.178035 -0.984024 0.0133097 0.00360562 -0.999905 -0.00486026 -0.0607717 -0.99814 0.00565346 -0.429698 -0.902955 0 -0.445505 -0.895279 -0.69811 -0.307665 -0.646517 -0.698111 -0.307664 -0.646516 -0.704245 -0.0662488 -0.706859 -0.798049 0.00217292 -0.602589 -0.698109 0.698122 -0.158965 -0.698112 0.698119 -0.158963 -0.698114 0.56047 -0.445544 -0.698108 0.560474 -0.44555 -0.698107 0.312317 -0.644286 -0.69811 0.312317 -0.644283 -0.705432 0.0921894 -0.702757 -0.698066 0.110364 0.707477 -0.698062 0.110366 0.707481 -0.698061 -0.207529 0.685305 -0.609308 -0.204148 0.766203 -0.706901 -0.329627 0.625809 -0.698069 -0.484315 0.527389 -0.698067 -0.484315 0.527391 -0.698067 -0.66518 0.265025 -0.698071 -0.665177 0.265022 -0.698071 -0.714293 -0.0498312 -0.698069 -0.714294 -0.0498309 -0.706902 -0.66967 -0.227665 -0.698066 -0.406398 -0.58953 -0.698071 -0.406393 -0.589526 -0.700604 -0.607531 -0.374247 -0.796086 -0.493762 -0.349922 -0.684043 -0.674073 -0.278766 -0.697963 0.558168 0.448661 -0.697963 0.558167 0.448661 -0.697961 0.697975 0.160254 -0.697962 0.697975 0.160254 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706175 -0.308847 -0.637126 -0.706174 -0.308848 -0.637128 -0.706173 -0.397345 -0.586035 -0.706178 -0.397342 -0.58603 0 -0.580953 -0.813937 -0.0420205 -0.560695 -0.826955 0 -0.520702 -0.853739 0 -0.436202 -0.899849 -0.0629306 -0.413593 -0.908285 0 -0.479008 -0.877811 -0.706175 0.308847 0.637126 -0.706176 0.308847 0.637126 -0.706177 0.397343 0.586031 -0.706178 0.397343 0.586031 0 0.764564 0.644548 0.00897396 0.779387 0.626479 -0.000625036 0.895719 0.444619 0.00476585 0.965983 0.25856 0.0163909 0.97451 0.223746 0 0.998723 0.0505123 0 -0.501182 -0.865342 0.0178446 -0.567477 -0.823196 0.00272563 -0.664838 -0.746982 -0.00733925 -0.851397 -0.524471 0.00493654 -0.831419 -0.555624 -0.00112432 -0.946782 -0.321874 -0.0112956 -0.980858 -0.194396 0.018963 -0.997396 -0.0695807 0.00487114 -0.999246 0.0385275 -0.00685943 -0.973442 0.22883 0.0389224 -0.890723 0.452877 0.00575501 -0.928965 0.370122 -0.000320397 -0.825732 0.564063 0 0.154134 0.98805 0.00764404 0.171698 0.98512 -0.00712452 -0.257452 0.966265 0.00552672 -0.226447 0.974008 -4.22942e-06 -0.423187 0.906042 2.12015e-07 -0.466028 0.88477 -9.97055e-07 -0.466045 0.884761 -6.89858e-05 -0.676388 0.736546 0.030853 -0.618778 0.784959 0.00153069 -0.769449 0.638706 -0.994042 0.0451691 0.0991952 -0.971841 -0.097652 -0.214452 -0.658919 -0.376107 -0.651436 -0.108089 -0.577549 -0.809169 -0.558292 -0.481984 -0.675279 -0.341051 -0.546121 -0.765137 -0.237322 -0.571123 -0.78581 -0.237618 -0.505788 -0.829286 -0.15399 -0.494036 -0.855696 -0.237621 -0.465288 -0.852668 -0.237426 -0.402564 -0.884065 -0.887886 -0.267276 -0.374464 -0.739465 -0.391095 -0.547938 -0.108169 -0.395266 -0.912176 -0.341048 -0.389568 -0.855525 -0.658919 -0.311728 -0.684581 -0.558605 -0.327706 -0.761951 -0.739471 -0.278979 -0.612662 -0.971845 -0.136885 -0.191781 -0.931696 -0.217626 -0.290827 -0.931861 -0.181408 -0.314208 -0.658697 -0.443877 -0.607529 -0.658919 -0.376107 -0.651436 -0.931861 -0.181408 -0.314208 -0.931861 -0.150356 -0.330195 -0.888089 -0.177164 -0.424158 -0.994042 0.0633213 0.0887154 -0.994042 0.0633209 0.0887151 -0.994053 0.0567055 0.092973 -0.994978 0.0500476 0.086685 -0.994053 0.0521649 0.0955948 -0.994042 0.0451691 0.0991953 0 0.403428 0.915011 0.0635022 0.435321 0.898033 0 0.468406 0.883513 0 0.530942 0.847408 0.0635018 0.560058 0.826016 0 0.590708 0.806885 -0.0694535 0.579996 -0.811653 -0.0924278 0.185776 -0.978235 -0.812788 0.555689 -0.174885 -0.893728 0.365967 0.259456 -0.90088 0.381882 0.206352 -0.982603 0.180036 0.0455824 -0.968982 0.239653 0.0603374 -0.95918 0.275205 0.0650882 -0.955076 0.285382 0.079925 -0.937214 0.332763 0.104395 -0.978164 0.199001 0.0599457 -0.993506 0.0898144 0.0698557 -0.993503 0.0935868 0.0647582 -0.712671 0.608238 0.349495 -0.884951 0.362543 0.292275 -0.885799 0.35772 0.295628 -0.759743 0.647517 -0.0592698 -0.771361 0.636393 -0.00250013 -0.722811 0.677443 0.136439 -0.187417 0.912355 -0.363984 -0.301517 0.879368 -0.36851 -0.0389394 0.964431 0.261451 -0.491278 0.768428 0.410078 -0.14694 0.745388 0.650234 -0.123004 0.756812 0.641955 -0.0926582 0.993959 0.0588229 -0.219674 0.974905 -0.0361108 -0.275277 0.960942 -0.0285157 -0.177315 0.984056 -0.0138872 -0.353638 0.935288 0.0132656 -0.456006 0.843591 -0.283571 -0.364123 0.886864 -0.284405 -0.172303 0.924402 0.340283 -0.179695 0.923626 0.338562 -0.423353 0.84189 0.334655 -0.487236 0.868249 0.093516 -0.503329 0.859366 0.0902754 -0.600329 0.777646 -0.186741 -0.532645 0.824787 -0.18978 -0.267885 0.715679 -0.645012 -0.876428 -0.154115 -0.456204 -0.884046 -0.154749 -0.441038 -0.725699 -0.255946 -0.638633 -0.739818 -0.256838 -0.621854 -0.546201 -0.336859 -0.766936 -0.553286 -0.337274 -0.761657 -0.333631 -0.402449 -0.852482 -0.344994 -0.40424 -0.847094 -0.105763 -0.435737 -0.893839 -0.121701 -0.439395 -0.890012 -0.146197 0.374729 -0.915535 -0.166628 0.368272 -0.914664 -0.34232 0.372604 -0.862545 -0.242328 0.402877 -0.882591 -0.521635 0.398123 -0.754583 -0.443215 0.431697 -0.785619 -0.684278 0.405077 -0.606363 -0.629471 0.439165 -0.641015 -0.792141 0.400694 -0.460388 -0.839075 0.148694 -0.5233 -0.858962 0.135703 -0.493729 -0.685628 0.10612 -0.720176 -0.721167 0.0913167 -0.686716 -0.493424 0.0584876 -0.86782 -0.546158 0.0422897 -0.836614 -0.282729 0.0103902 -0.959144 -0.351084 -0.00718978 -0.936316 -0.0853842 -0.0331951 -0.995795 -0.151911 -0.0495935 -0.987149 -0.484353 0.643492 0.592722 -0.687665 0.52504 0.501447 -0.647365 0.584057 0.48969 -0.870212 0.285233 0.401713 -0.85001 0.364763 0.38004 -0.933087 0.337483 0.124313 -0.918226 0.36353 0.157184 -0.916086 0.367534 0.160332 -0.902766 0.365319 0.227058 -0.738156 0.650943 0.177197 -0.697725 0.635066 0.331469 -0.461104 0.809856 0.362651 -0.424997 0.687445 0.588895 -0.341429 0.703849 0.622915 0.0665007 0.978379 -0.195837 -0.306027 0.842108 -0.444073 -0.0131362 0.904597 -0.426066 -0.143545 0.689242 -0.710169 -0.324416 0.678136 -0.659458 -0.209395 0.713887 -0.668221 -0.489611 0.672211 -0.555349 -0.398069 0.715999 -0.573487 -0.641642 0.638265 -0.42534 -0.575732 0.684714 -0.446877 -0.805194 0.545129 -0.233446 -0.849342 0.436655 -0.296564 -0.891407 0.381197 -0.245118 -0.946584 0.171623 -0.27299 -0.938297 0.18191 -0.294122 -0.97139 -0.040433 -0.234022 -0.963018 -0.0385256 -0.26667 -0.146447 0.173643 0.973859 -0.824707 -0.443391 0.351087 -0.651397 0.176513 0.73792 -0.942264 -0.112535 0.315395 -0.9718 -0.0573706 0.22872 -0.978816 -0.0572764 0.196568 -0.989309 0.000934816 0.145829 -0.993672 0.0144703 0.111383 -0.851107 0.198434 0.486046 -0.873463 0.0963215 0.477268 -0.889404 0.0570225 0.453551 -0.901407 0.011774 0.432813 -0.895307 0.0148227 0.445204 -0.91823 -0.0382901 0.394193 -0.741732 -0.35856 0.566805 -0.782194 -0.348195 0.516655 -0.708894 -0.196331 0.677439 -0.911959 -0.0396389 0.408362 -0.938587 -0.0672964 0.338417 -0.786961 -0.472722 0.396518 -0.849347 -0.475159 0.229857 -0.792187 -0.59901 0.11673 -0.856723 -0.502934 -0.114384 -0.84357 -0.517115 -0.144852 -0.884011 -0.310445 -0.349497 -0.877484 -0.311395 -0.364767 -0.921891 -0.0873938 0.377464 -0.959989 -0.054243 0.274734 -0.891441 -0.40283 0.207511 -0.944652 -0.327243 0.0233306 -0.941308 -0.337543 0.00197575 -0.970892 -0.192488 -0.142538 -0.965064 -0.196519 -0.173294 -0.11518 -0.664171 -0.738655 -0.0768019 -0.832178 -0.549163 -0.146663 -0.842649 -0.518105 -0.0529683 -0.980381 -0.189863 -0.148668 -0.978745 -0.141266 -0.0857167 -0.995115 0.0489769 -0.146646 -0.959192 0.241757 -0.333935 -0.533479 -0.777102 -0.105763 -0.556286 -0.824233 -0.296951 -0.48325 -0.823583 -0.0132369 -0.55315 0.832977 -0.298401 -0.563165 0.770586 -0.108508 -0.454323 0.884204 -0.143077 -0.959493 0.242699 -0.0595358 -0.884271 0.463163 -0.223395 -0.783259 0.580173 -0.243144 -0.784121 0.570995 -0.107828 -0.756726 0.644778 -0.0837889 -0.414926 0.905989 -0.0301111 -0.223926 0.974141 -0.178501 -0.16832 0.969436 -0.112023 0.190213 0.975331 -0.341454 0.187599 0.920987 -0.692766 0.146137 0.706201 -0.714401 -0.0253316 0.699278 -0.412917 -0.101065 0.905144 -0.487267 -0.353213 0.798631 -0.353588 -0.456242 0.81659 -0.447572 -0.648695 0.615527 -0.377659 -0.705485 0.59972 -0.480016 -0.809376 0.338371 -0.412114 -0.859936 0.301118 -0.513927 -0.857834 -0.000834723 -0.454266 -0.889551 -0.0483917 -0.542567 -0.758042 -0.361931 -0.499064 -0.768066 -0.40126 -0.553205 -0.493493 -0.67114 -0.546586 -0.493031 -0.676879 -0.344659 -0.535648 -0.770903 -0.287811 -0.822514 -0.490546 -0.346266 -0.821306 -0.453384 -0.253008 -0.95941 -0.124573 -0.33286 -0.940021 -0.0745977 -0.223301 -0.942312 0.24937 -0.313063 -0.903011 0.294214 -0.200955 -0.789175 0.580362 -0.29166 -0.739639 0.606522 -0.187459 -0.525793 0.829699 -0.269278 -0.481519 0.834044 -0.179696 -0.168497 0.969184 -0.463507 -0.123506 0.877444 -0.425029 0.166328 0.889767 -0.484352 0.191612 0.853632 -0.870904 0.160189 0.464613 -0.892969 0.0762284 0.443617 -0.690168 -0.00925971 0.72359 -0.744776 -0.203913 0.635396 -0.503292 -0.351579 0.78936 -0.593147 -0.53302 0.603379 -0.545224 -0.58986 0.595647 -0.633574 -0.679526 0.369903 -0.588807 -0.73287 0.340893 -0.67799 -0.73116 0.0757265 -0.639892 -0.767703 0.0342055 -0.71848 -0.650415 -0.246469 -0.69109 -0.664883 -0.283417 -0.739775 -0.417025 -0.528037 -0.726933 -0.417546 -0.545182 0.146156 0.378317 0.914065 0.826272 0.560144 0.0592799 0.651436 0.241323 0.719301 0.880895 0.173831 0.440234 0.992268 0.0783359 0.0962658 0.992327 0.039665 0.117107 0.976264 0.165553 0.139644 0.978908 0.147595 0.141266 0.963204 0.200348 0.179159 0.942932 0.258264 0.210185 0.902135 0.219522 0.371432 0.895797 0.222185 0.384944 0.919326 0.240407 0.311519 0.851016 0.0785337 0.519234 0.740541 0.603854 0.29489 0.783616 0.56866 0.250144 0.707954 0.523633 0.47393 0.912307 0.248563 0.325442 0.939734 0.234481 0.248835 0.7859 0.611845 0.089477 0.847486 0.528506 -0.0494866 0.79326 0.568166 -0.218919 0.856964 0.366098 -0.362747 0.844208 0.360292 -0.396865 0.884162 0.0782941 -0.460573 0.877674 0.070083 -0.474106 0.923009 0.269013 0.275111 0.960832 0.19278 0.199095 0.891328 0.451921 -0.0360857 0.944822 0.289804 -0.152723 0.94184 0.285626 -0.177073 0.97092 0.0893758 -0.222097 0.965173 0.0743158 -0.250836 0.115162 0.172286 -0.978292 0.0771042 0.414073 -0.906972 0.146469 0.440916 -0.885517 0.0440294 0.75324 -0.656271 0.0571071 0.756564 -0.651421 0.0998405 0.896163 -0.432347 0.181847 0.937677 -0.296132 0.33401 0.0403271 -0.941707 0.105773 0.0357494 -0.993748 0.278919 -0.0267258 -0.959943 0.0122488 0.90916 0.416267 0.315357 0.885707 0.340695 0.112605 0.858898 0.499615 0.136044 0.949547 -0.282581 0.0636233 0.99426 -0.0860136 0.20285 0.976419 0.0738812 0.247999 0.967241 0.0542306 0.108763 0.983613 0.143791 0.0842416 0.832514 0.547562 0.03286 0.713085 0.700307 0.190222 0.65539 0.730945 0.091572 0.355629 0.93013 0.341487 0.328768 0.88051 0.693994 0.254603 0.67346 0.714752 0.392982 0.578528 0.412193 0.563069 0.716276 0.486909 0.720651 0.49354 0.354176 0.81949 0.45055 0.447642 0.875906 0.180017 0.378517 0.915789 0.134373 0.480132 0.865897 -0.14034 0.4131 0.888246 -0.200916 0.51406 0.727613 -0.454226 0.455185 0.727767 -0.512993 0.542692 0.451685 -0.708142 0.499641 0.437692 -0.747519 0.553287 0.0633262 -0.83058 0.546658 0.0595624 -0.835235 0.34468 0.0458793 -0.937599 0.288263 0.436761 -0.852141 0.346235 0.457016 -0.819303 0.253712 0.746935 -0.614588 0.332843 0.758353 -0.560461 0.224037 0.930952 -0.288332 0.313046 0.922053 -0.22764 0.201538 0.976701 0.0737375 0.29166 0.948456 0.123957 0.187843 0.885525 0.424924 0.269281 0.849602 0.453502 0.179191 0.654927 0.73414 0.463852 0.570898 0.677434 0.425699 0.33265 0.841501 0.484444 0.288929 0.825733 0.875354 0.113817 0.469894 0.889585 0.176744 0.42119 0.689716 0.389162 0.61061 0.745689 0.510385 0.428317 0.502644 0.715059 0.485839 0.593266 0.771096 0.231185 0.546278 0.815292 0.192038 0.633758 0.772244 -0.0446111 0.590004 0.801195 -0.099912 0.678251 0.660531 -0.321986 0.640942 0.667856 -0.378367 0.718697 0.421409 -0.553072 0.691734 0.412408 -0.59281 0.739911 0.0743873 -0.668579 0.727069 0.0648234 -0.683497 0.572898 0 0.819627 0.850725 0.0636532 0.521743 0.879516 -0.057632 0.472367 0.654678 -0.089986 0.750532 0.764994 -0.0766685 0.639457 0.845143 -0.0602367 0.531135 0.851114 -0.0323968 0.52398 0.850696 0 0.525657 0.850696 0 0.525657 0.851114 0.0323824 0.523981 0.345769 -0.111701 0.931647 0.488417 -0.103879 0.866405 0.149218 -0.117711 0.981773 0.201908 -0.113124 0.972849 0.201869 0 0.979413 0.844346 0.0637835 0.531989 0.654705 0.0899833 0.75051 0.573019 0.0930682 0.81424 0.488413 0.103879 0.866407 0.345793 0.1117 0.931638 0.573019 -0.0930691 0.81424 0.572898 0 0.819627 0.201869 0 0.979413 0.201908 0.113123 0.97285 0.149215 0.117711 0.981773 0.340892 -0.111913 -0.933417 0.994035 0 0.109062 0.994036 0.0132062 0.108246 0.994251 0.0127471 0.106317 0.991754 -0.0155211 0.127214 0.996676 -0.00502731 0.0813173 0.65868 0 -0.752423 0.931791 0 -0.362996 0.994046 -0.0110552 0.108402 0.993745 0.0132936 -0.110876 0.971837 0.0280534 -0.233979 0.994056 0.00671749 0.108663 0.994035 0 0.109062 0.931791 0 -0.362996 0.931639 0.0497305 -0.359967 0.558445 -0.112612 -0.821862 0.739311 -0.08016 -0.668576 0.931791 -0.0432126 -0.360415 0.888072 -0.0662197 -0.454911 0.971843 -0.0280504 -0.233955 0.237284 0 -0.97144 0.237285 -0.115644 -0.964532 0.108128 -0.132819 -0.985225 0.887837 0.0547792 -0.456887 0.739296 0.080162 -0.668592 0.658468 0.0961999 -0.746435 0.558106 0.0987789 -0.823869 0.340889 0.111913 -0.933419 0.65868 -0.0895713 -0.747073 0.65868 0 -0.752423 0.237284 0 -0.97144 0.237187 0.12225 -0.963741 0.10804 0.118347 -0.987077 0.939515 -0.0414811 0.339987 0.939603 -0.0626279 0.336489 0.939492 -0.0628018 0.336766 0.939578 -0.0625079 0.336581 0.939697 -0.0614292 0.336445 0.939842 -0.0625229 0.335839 0.939863 -0.0625592 0.335774 0.939743 -0.0625595 0.33611 0.939508 0.0414811 0.340006 0.939901 0.0626175 0.335656 0.939805 0.0623805 0.335968 0.93969 0.0614388 0.336463 0.939697 0.0616385 0.336407 0.939544 0.0626382 0.33665 0.939485 0.06284 0.336778 0.939529 0.0627211 0.336677 0.939645 0.0626084 0.336375 0.939777 0.0625435 0.336017 0.939515 0.0414789 0.339987 0.939511 0.0414791 0.339997 0.939694 0.0211031 0.341366 0.939693 0.0210968 0.341367 0.939497 0 0.342556 0.939497 0 0.342556 0.939693 -0.0211045 0.341367 0.939693 -0.0211061 0.341367 0.939511 -0.0414814 0.339999 0.939508 -0.041483 0.340006 0.93969 -0.0616661 0.336422 0 -0.995991 -0.0894499 -0.0289435 -0.975767 -0.216891 -0.00936235 -0.961188 -0.275735 0.00449042 -0.892064 -0.451886 -0.023165 -0.792122 -0.609923 -0.0032528 -0.75885 -0.651257 0.000781361 -0.6196 -0.784917 -0.0154083 -0.459222 -0.888188 0.000915537 -0.42427 -0.905536 -0.00109223 -0.0397235 -0.99921 0 -0.0374734 -0.999298 0.698531 -0.698531 -0.155268 0.698525 -0.698537 -0.155271 0.698521 -0.566987 -0.436571 0.698518 -0.566988 -0.436574 0.698523 -0.328653 -0.635652 0.69852 -0.328653 -0.635655 0.698525 -0.0284256 -0.715021 0.698523 -0.0284247 -0.715023 0 0.997381 -0.0723272 0.0176542 0.976951 -0.212734 0.00801609 0.967897 -0.25122 -0.00277017 0.90327 -0.429063 0.013348 0.800099 -0.59972 0.00231983 0.775314 -0.631572 -0.000405558 0.639523 -0.768772 0.00838759 0.478326 -0.878142 -0.00235482 0.446283 -0.894889 0.00260422 0.0698963 -0.997551 0 0.0618199 -0.998087 -0.698865 0.0499941 -0.713504 -0.698864 0.0499938 -0.713505 -0.703799 0.290107 -0.648463 -0.787844 0.294599 -0.540845 -0.698864 0.698877 -0.152182 -0.698862 0.698879 -0.152183 -0.698861 0.572328 -0.428992 -0.698864 0.572326 -0.428989 -0.70602 0.420126 -0.570113 0 -0.0961511 -0.995367 -0.0420201 -0.0720983 -0.996512 0 -0.0240723 -0.99971 0 0.0721621 -0.997393 -0.0629305 0.0959606 -0.993394 0 0.0240723 -0.99971 -0.706177 -0.0510935 0.706189 -0.706183 -0.0510933 0.706183 -0.706183 0.0510931 0.706183 -0.706177 0.0510937 0.706189 -0.0015364 0.570579 0.821242 0.0135943 0.372905 0.92777 0.0104861 0.365391 0.930795 0 0.170053 0.985435 0.00718324 0.722034 0.69182 0.0225389 0.756097 0.654071 -0.00163199 0.858582 0.512674 0 0.992988 0.118219 0.0252472 0.971566 0.235417 0.0060983 0.946778 0.32183 0.000614211 0.906658 0.421866 0 -0.00136858 -0.999999 0.0178435 -0.0798494 -0.996647 0.00272522 -0.202269 -0.979326 -0.00733994 -0.475097 -0.879903 0.00493601 -0.442219 -0.896893 -0.00112507 -0.658995 -0.752147 -0.0112968 -0.752247 -0.658784 0.0189628 -0.82898 -0.558957 0.00486872 -0.884644 -0.466242 -0.00686143 -0.957442 -0.288546 0.0389189 -0.997827 -0.0531618 0.0057552 -0.989569 -0.143942 -0.000320122 -0.997136 0.0756345 0 -0.360546 0.932741 0.00764613 -0.343865 0.938988 -0.00712259 -0.706087 0.708089 0.00552742 -0.683109 0.730295 -4.23207e-06 -0.819525 0.573043 2.00534e-07 -0.845974 0.533224 -1.7515e-06 -0.845991 0.533198 -6.93378e-05 -0.954043 0.299669 0.0308526 -0.92836 0.370401 0.00153091 -0.985716 0.16841 -0.994042 -0.01048 0.10849 -0.971841 0.0226569 -0.234546 -0.658919 0 -0.752214 -0.108086 -0.0955878 -0.989535 -0.558296 -0.0797714 -0.825798 -0.341053 -0.0903868 -0.935689 -0.237328 -0.101702 -0.966091 -0.237623 -0.0233828 -0.971076 -0.153992 0 -0.988072 -0.237623 0.0233828 -0.971076 -0.237428 0.0934018 -0.966904 -0.887885 -0.0442361 -0.457933 -0.739466 -0.0647288 -0.670075 -0.108163 0.113779 -0.987601 -0.341054 0.0903866 -0.935688 -0.65892 0.0723265 -0.748728 -0.558603 0.0971742 -0.823723 -0.739471 0.0647283 -0.670069 -0.971845 -0.0226554 -0.23453 -0.931696 -0.0430565 -0.360677 -0.931861 0 -0.362816 -0.658697 -0.0806448 -0.748074 -0.658919 0 -0.752214 -0.931861 0 -0.362816 -0.931861 0.0348854 -0.361136 -0.888089 0.0586506 -0.455914 -0.994042 0.01048 0.10849 -0.994042 0.0104801 0.108491 -0.994053 0.00262192 0.10887 -0.994978 0 0.100096 -0.994053 -0.00262121 0.10887 -0.994042 -0.01048 0.108491 0 -0.108126 0.994137 0.0635018 -0.0720167 0.99538 0 -0.0361046 0.999348 0 0.0721624 0.997393 0.126162 0.107262 0.986194 0 0.0361046 0.999348 -0.12737 0.358878 0.924653 -0.0569883 0.943014 0.327836 -0.891408 0.452684 -0.0216792 -0.893727 0.187204 0.407684 -0.90088 0.227545 0.369646 -0.982603 0.133125 0.129494 -0.968984 0.177371 0.172075 -0.95918 0.205789 0.193968 -0.955076 0.207184 0.211906 -0.937214 0.235985 0.256792 -0.963018 0.0999699 -0.250206 -0.97139 0.0819953 -0.222887 -0.876427 0.0946345 -0.472143 -0.884047 0.0865013 -0.459325 -0.858961 0.364388 -0.359732 -0.839077 0.39042 -0.378843 -0.946585 0.285123 -0.150604 -0.938296 0.304601 -0.163763 -0.978164 0.142367 0.151415 -0.993506 0.0428537 0.105404 -0.993503 0.0486698 0.102875 -0.712671 0.351999 0.606792 -0.884951 0.167832 0.434391 -0.885798 0.161991 0.434881 -0.792139 0.577207 -0.198363 -0.849342 0.526437 -0.0385036 -0.805194 0.588818 0.0703937 -0.812788 0.568683 0.126391 -0.759742 0.590401 0.272431 -0.77136 0.552386 0.316028 -0.722807 0.518468 0.456882 -0.133807 0.985972 0.0997711 -0.275284 0.846457 0.455774 -0.446693 0.49036 0.74834 -0.0444206 0.718652 0.693949 -0.119369 0.883409 0.453143 -0.332075 0.793303 0.510291 -0.192668 0.881117 0.431869 -0.933086 0.230113 0.276403 -0.918225 0.236234 0.317893 -0.916087 0.238126 0.322616 -0.902767 0.202841 0.379299 -0.738155 0.475133 0.478933 -0.697723 0.384249 0.604595 -0.461106 0.520029 0.718994 -0.105759 0.069563 -0.991956 -0.121707 0.0644777 -0.99047 -0.0853874 0.469147 -0.878982 -0.151909 0.450624 -0.879694 -0.0947136 0.643347 -0.759694 -0.147683 0.777104 -0.6118 -0.14887 0.776775 -0.61193 -0.223954 0.964256 0.141618 -0.0681471 0.995634 -0.0637858 -0.143539 0.951986 -0.270406 -0.246988 0.945326 -0.21297 -0.0723699 0.904416 -0.420469 -0.353642 0.803347 0.479136 -0.456007 0.872356 0.176217 -0.364126 0.910248 0.197131 -0.489618 0.859823 -0.144843 -0.398061 0.90682 -0.138657 -0.521627 0.72208 -0.454428 -0.443214 0.76667 -0.464519 -0.546158 0.454932 -0.703383 -0.493427 0.484562 -0.722309 -0.55329 0.0887387 -0.828249 -0.546207 0.0917364 -0.832612 -0.177298 0.859163 0.480005 -0.301509 0.945812 0.120546 -0.187412 0.972115 0.140959 -0.324412 0.917013 -0.232042 -0.209402 0.952352 -0.221756 -0.342319 0.753959 -0.560681 -0.24233 0.790199 -0.562905 -0.351088 0.461929 -0.814468 -0.282723 0.488571 -0.825449 -0.344985 0.0734671 -0.935728 -0.333633 0.0777085 -0.939495 -0.149398 0.167668 0.974458 -0.188634 0.31676 0.929559 -0.341411 0.298095 0.891391 -0.425 0.300899 0.853718 -0.484352 0.260924 0.835058 -0.687667 0.203978 0.696784 -0.647364 0.260969 0.716111 -0.87021 0.0461703 0.490513 -0.850011 0.125872 0.511506 -0.172306 0.630415 0.756894 -0.179696 0.630603 0.755016 -0.423352 0.561772 0.710764 -0.487234 0.705167 0.515114 -0.503334 0.699092 0.507863 -0.600333 0.766828 0.227101 -0.532645 0.809175 0.248042 -0.641642 0.765424 -0.0492219 -0.575734 0.816417 -0.0446497 -0.684282 0.653986 -0.322585 -0.629475 0.700833 -0.335551 -0.721168 0.42244 -0.549054 -0.685628 0.451991 -0.57063 -0.73982 0.0884964 -0.66696 -0.725698 0.0976593 -0.681047 -0.146454 -0.33655 0.930207 -0.824703 -0.559537 0.0823584 -0.651394 -0.216095 0.727316 -0.942266 -0.255152 0.216871 -0.9718 -0.164044 0.169392 -0.978816 -0.147886 0.141594 -0.989309 -0.072105 0.126759 -0.993672 -0.0431599 0.103696 -0.851107 -0.0711759 0.520146 -0.873464 -0.155215 0.461486 -0.889399 -0.177383 0.421312 -0.901406 -0.20621 0.380717 -0.895308 -0.209764 0.392968 -0.91823 -0.230254 0.322238 -0.741727 -0.593931 0.311589 -0.782194 -0.559875 0.273336 -0.708892 -0.508747 0.488518 -0.911959 -0.238507 0.333834 -0.938588 -0.227486 0.259427 -0.786965 -0.607643 0.107032 -0.849349 -0.526424 -0.038517 -0.792191 -0.577118 -0.198413 -0.856725 -0.378362 -0.350521 -0.843571 -0.375409 -0.384001 -0.884012 -0.0941062 -0.457894 -0.877483 -0.0872924 -0.471597 -0.921889 -0.264423 0.2832 -0.959989 -0.184344 0.210804 -0.891439 -0.45262 -0.0217074 -0.944652 -0.295066 -0.143421 -0.941308 -0.293309 -0.167058 -0.970892 -0.0954306 -0.219686 -0.965065 -0.0835444 -0.248336 -0.11518 -0.205855 -0.97178 -0.0768026 -0.446107 -0.891678 -0.146659 -0.470703 -0.870017 -0.0529605 -0.7541 -0.654621 -0.148666 -0.776984 -0.611714 -0.0857106 -0.886291 -0.455128 -0.146632 -0.951565 -0.270229 -0.333938 -0.0734572 -0.939728 -0.105757 -0.069643 -0.99195 -0.296942 -0.00671765 -0.954872 -0.0132325 -0.895532 0.4448 -0.298402 -0.87301 0.38576 -0.10851 -0.83556 0.538576 -0.143059 -0.952297 -0.269563 -0.0595188 -0.997384 -0.0410306 -0.223388 -0.96841 0.110818 -0.243131 -0.964569 0.102441 -0.107825 -0.977734 0.18003 -0.0837992 -0.812343 0.577128 -0.0301146 -0.680992 0.731671 -0.178505 -0.630483 0.755399 -0.112027 -0.322935 0.939767 -0.341441 -0.298029 0.891402 -0.692767 -0.226542 0.684655 -0.714401 -0.371578 0.592926 -0.412921 -0.540096 0.733343 -0.487274 -0.705207 0.515022 -0.353603 -0.803408 0.479062 -0.447583 -0.869543 0.208723 -0.37765 -0.910833 0.166627 -0.480004 -0.870132 -0.111653 -0.412098 -0.895292 -0.169197 -0.513914 -0.742491 -0.42965 -0.45427 -0.746179 -0.486678 -0.542569 -0.47552 -0.69246 -0.499058 -0.464534 -0.731538 -0.553196 -0.0918056 -0.827977 -0.546586 -0.0885399 -0.832709 -0.344666 -0.0784363 -0.935443 -0.287814 -0.467045 -0.836082 -0.346266 -0.484578 -0.803296 -0.253009 -0.768586 -0.58759 -0.332875 -0.776783 -0.534605 -0.223318 -0.940748 -0.25519 -0.313075 -0.929134 -0.196706 -0.200964 -0.973624 0.108026 -0.291652 -0.94381 0.15544 -0.187456 -0.870202 0.45564 -0.269275 -0.834033 0.48154 -0.17969 -0.630511 0.755094 -0.4635 -0.545679 0.698142 -0.425024 -0.300841 0.853727 -0.484353 -0.260873 0.835073 -0.87091 -0.0935885 0.482448 -0.892971 -0.155791 0.422295 -0.690169 -0.369815 0.622016 -0.744776 -0.494291 0.448314 -0.503277 -0.699165 0.50782 -0.593138 -0.763307 0.256027 -0.545232 -0.80865 0.220923 -0.633582 -0.773432 -0.0194056 -0.588805 -0.805132 -0.0712124 -0.67799 -0.671066 -0.300002 -0.63989 -0.681953 -0.354234 -0.718477 -0.440043 -0.538659 -0.691088 -0.434099 -0.577888 -0.739778 -0.0971353 -0.665803 -0.726934 -0.0890133 -0.680914 -0.939621 -0.0370023 0.340209 -0.939566 0.0329192 0.340783 -0.93839 0.0498414 0.341966 -0.939692 0.0508146 0.338226 -0.939429 0.0518271 0.338801 -0.939408 0.0518973 0.338849 -0.939889 0.0514332 0.337584 -0.939982 0.0516739 0.337288 -0.939936 0.0515867 0.337431 -0.939771 0.0515725 0.33789 -0.939571 0.0516513 0.338434 -0.939633 -0.0516247 0.338267 -0.939832 -0.051546 0.337727 -0.940949 -0.0488276 0.335008 -0.939692 -0.0507737 0.338232 -0.939957 -0.0515975 0.337371 -0.939978 -0.0516523 0.337304 -0.939692 -0.0502958 0.338302 -0.939471 -0.0517291 0.3387 -0.93945 -0.0517843 0.33875 -0.939565 -0.0329192 0.340783 -0.94337 -0.0336276 0.330033 -0.936007 -0.008472 0.351879 -0.939622 -0.0123554 0.341991 -0.939661 0.0082366 0.342009 -0.937285 0.0125847 0.348336 -0.94337 0.0336276 0.330033 -0.939621 0.0370023 0.34021 -0.939692 0.050291 0.338303 -0.149349 -0.106913 0.982988 -0.488786 -0.0943296 0.867289 -0.346056 0.101445 0.932713 -0.655057 0.0816972 0.751149 -0.850962 0.0567903 0.522148 -0.850962 0.0567906 0.522149 -0.850961 0.0189632 0.524886 -0.850962 0.0189631 0.524885 -0.850962 -0.0189632 0.524885 -0.850961 -0.0189631 0.524886 -0.850961 -0.0567904 0.522149 -0.850962 -0.0567905 0.522148 -0.655066 -0.0816963 0.751142 -0.573444 -0.0811231 0.815218 -0.573333 -0.0295815 0.818788 -0.573333 -0.0295814 0.818788 -0.573333 0.0295814 0.818788 -0.573333 0.0295814 0.818788 -0.573444 0.0811236 0.815219 -0.488788 0.0943293 0.867288 -0.346081 -0.101444 0.932704 -0.202124 -0.100133 0.974227 -0.202086 -0.0353598 0.978729 -0.202085 -0.0353597 0.978729 -0.202085 0.0353598 0.978729 -0.202087 0.0353596 0.978729 -0.202125 0.100134 0.974227 -0.149352 0.106913 0.982987 0.707097 -0.12415 -0.696133 0.671182 -0.0864093 -0.736239 0.706473 -0.0842522 -0.702708 0.706474 0 -0.707739 0.706474 0 -0.707739 0.706526 0.082492 -0.702863 0.672816 0.08807 -0.734549 0.707097 0.12415 -0.696133 0.706462 0.0842531 0.702719 0.706474 0.0842522 0.702706 0.706474 0 0.707739 0.706474 0 0.707739 0.706474 -0.0842516 0.702706 0.706462 -0.0842538 0.702718 0.697429 -0.286294 0.656985 0.697438 -0.286287 0.656978 0.69744 -0.550008 0.459423 0.69745 -0.549998 0.459419 0.697451 -0.697438 0.164749 0.697445 -0.697445 0.164748 0.694731 0.306879 0.650518 0.487522 0.870119 0.0722171 0.694737 0.306878 0.650513 0.702912 0.537142 0.466254 0.494619 0.714147 0.495325 0.705019 0.637638 0.310429 0.7037 0.695442 0.145488 0.704393 0.708714 -0.0394237 0.704393 0.6776 -0.211397 0.487512 0.78966 -0.372518 0.694738 0.0594932 -0.716798 0.694742 0.0594916 -0.716794 0.702917 0.339719 -0.624898 0.494614 0.495325 -0.71415 0.70501 0.488451 -0.514175 0.703693 0.600385 -0.379941 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.372128 0.928181 -0.016886 -0.39943 0.916608 0.000228779 -0.577753 0.816211 -0.00142358 -0.727623 0.685976 -0.0291333 -0.767152 0.640804 0.0021586 -0.870481 0.492198 -0.00448241 -0.949162 0.314755 -0.0346939 -0.97263 0.229755 0 -0.994875 0.101115 0 -0.0320584 -0.999486 -0.0376686 0.0826555 -0.995866 -0.0154246 0.169008 -0.985494 0.0283308 0.477431 -0.878212 1.22673e-05 0.998456 -0.0555413 -0.0268618 0.999224 0.0287969 7.10368e-05 0.995721 -0.0924111 -0.000100841 0.954622 -0.297821 -1.06206e-05 0.954535 -0.2981 -4.27419e-06 0.845012 -0.534748 -0.0342222 0.89451 -0.445737 0.0537473 0.687743 -0.723962 0.00712828 0.751888 -0.659252 -0.00709885 0.410967 -0.911623 0 0.426656 0.904414 -0.033047 0.385716 0.922026 0.0252534 0.754939 0.655308 -0.00777942 0.71506 0.69902 6.35613e-06 0.83878 0.54447 -6.84695e-06 0.899109 0.437725 -0.0189343 0.869189 0.494117 0.0359324 0.978178 0.204637 -0.035276 0.943533 0.329394 2.51442e-05 0.990911 0.134521 0 0.119043 0.992889 0 0.119043 0.992889 0 0 1 0 0 1 0 -0.119043 0.992889 0 -0.119043 0.992889 0 0.119044 -0.992889 0 0.119044 -0.992889 0 0 -1 0 0 -1 0 -0.119044 -0.992889 0 -0.119044 -0.992889 0.87924 -0.121054 0.460741 0.887082 -0.185212 0.422826 0.954993 -0.213682 0.205741 0.960101 -0.209238 0.18554 0.978435 -0.149538 0.142487 0.978976 -0.148081 0.140277 0.991397 -0.0621429 0.115199 0.990797 -0.0665721 0.117852 0.965171 -0.0742781 -0.250854 0.793206 -0.568249 -0.218899 0.859466 -0.349969 -0.372612 0.839107 -0.377551 -0.391605 0.884192 -0.0696557 -0.461901 0.876484 -0.0783763 -0.475008 0.859294 -0.489201 0.14932 0.938543 -0.241643 0.246465 0.933189 -0.238334 0.26899 0.821646 -0.569778 0.0158331 0.847485 -0.528506 -0.0495142 0.891281 -0.452011 -0.0360981 0.947044 -0.277996 -0.160703 0.938316 -0.298974 -0.173715 0.97091 -0.0893285 -0.222158 0.989048 -0.0760294 -0.126504 0.807332 -0.43342 0.400452 0.693238 -0.678481 0.243074 0.770715 -0.636669 0.0255294 0.902134 -0.235401 0.36158 0.887848 -0.179406 0.423721 0.749547 -0.338767 0.568698 0.710134 -0.348524 0.611752 0.133717 -0.988782 0.0665627 0.275987 -0.862461 0.424256 0.220913 -0.877755 0.425139 0.0485868 -0.946603 0.31872 0.47104 -0.49364 0.731055 0.0377227 -0.725544 0.687141 0.0993556 -0.862548 0.496125 0.146991 -0.351798 0.924463 0.123064 -0.367057 0.922022 0.105769 -0.0356722 -0.993751 0.0953825 -0.0393399 -0.994663 0.111227 -0.440403 -0.890883 0.149994 -0.427216 -0.891621 0.0929529 -0.622283 -0.777254 0.15722 -0.755575 -0.635915 0.147173 -0.758901 -0.634358 0.245705 -0.961753 0.121079 0.0627328 -0.994561 -0.0831443 0.143403 -0.942357 -0.302322 0.246731 -0.938125 -0.242991 0.0700817 -0.892671 -0.445227 0.354235 -0.819424 0.450623 0.457121 -0.877765 0.143417 0.36318 -0.916296 0.168823 0.490839 -0.853062 -0.177093 0.397291 -0.90236 -0.16705 0.522587 -0.703955 -0.480989 0.442848 -0.751475 -0.489051 0.546616 -0.428533 -0.719424 0.493389 -0.460226 -0.738078 0.553361 -0.0599239 -0.830783 0.546233 -0.0631187 -0.835252 0.176394 -0.874054 0.452675 0.302644 -0.949316 0.0848895 0.186306 -0.976236 0.110698 0.325651 -0.907142 -0.266542 0.208478 -0.945149 -0.251458 0.343271 -0.732025 -0.588476 0.24185 -0.771845 -0.588017 0.351504 -0.431632 -0.830746 0.282642 -0.460904 -0.841238 0.345024 -0.0404254 -0.937723 0.33367 -0.0450126 -0.941615 0.879548 -0.119852 0.460469 0.763485 -0.186661 0.618263 0.693958 -0.254637 0.673486 0.651407 -0.241371 0.719312 0.484443 -0.288979 0.825716 0.918289 -0.245884 0.310302 0.901025 -0.259507 0.347577 0.75874 -0.525223 0.385298 0.805306 -0.471418 0.35951 0.700511 -0.607173 0.375 0.633805 -0.450407 0.628828 0.461121 -0.542724 0.70201 0.425671 -0.332705 0.841494 0.341464 -0.328831 0.880496 0.172207 -0.654676 0.736032 0.17919 -0.655014 0.734063 0.42409 -0.586828 0.689769 0.486869 -0.72062 0.493625 0.50266 -0.715012 0.485892 0.601383 -0.773976 0.198242 0.531872 -0.816939 0.222987 0.642848 -0.762017 -0.0779477 0.575092 -0.815071 -0.0701934 0.685236 -0.640524 -0.346672 0.629207 -0.689855 -0.358048 0.721672 -0.40142 -0.56396 0.685628 -0.432692 -0.585399 0.739941 -0.0647169 -0.669552 0.725679 -0.0744774 -0.68399 -0.698068 -0.25816 0.667874 -0.698076 -0.25816 0.667865 -0.698079 -0.522366 0.489714 -0.609306 -0.559896 0.561483 -0.706901 -0.598368 0.377156 -0.698069 -0.683124 0.214572 -0.698071 -0.683122 0.214571 -0.69807 -0.708572 -0.10307 -0.698065 -0.708577 -0.103069 -0.698064 -0.593685 -0.400305 -0.698064 -0.593685 -0.400305 -0.706898 -0.466118 -0.532005 -0.698068 -0.0571838 -0.713744 -0.698062 -0.0571861 -0.71375 -0.700595 -0.339019 -0.62788 -0.796091 -0.252644 -0.549919 -0.684043 -0.444383 -0.578454 -0.696945 0.267444 0.665388 -0.696946 0.267443 0.665387 -0.696947 0.542352 0.469168 -0.696948 0.542351 0.469168 -0.696944 0.696958 0.168878 -0.696944 0.696957 0.168878 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 0.0510933 -0.706189 -0.706177 0.0510934 -0.70619 -0.706177 -0.0510933 -0.70619 -0.706178 -0.0510933 -0.706189 0.698657 -0.569064 0.43364 0.698662 -0.56906 0.433639 0.698662 -0.698665 0.154076 0.698663 -0.698663 0.154076 0.698062 -0.0858671 0.71087 0.69807 -0.0858636 0.710863 0.698065 0.231069 0.677726 0.61851 0.228402 0.75185 0.706891 0.351029 0.614072 0.698059 0.502244 0.510357 0.698066 0.502241 0.51035 0.698067 0.673936 0.241895 0.69807 0.673934 0.241893 0.69807 0.712147 -0.0744687 0.698073 0.385793 -0.603206 0.698074 0.385792 -0.603205 0.700607 0.594242 -0.395001 0.63491 0.657439 -0.405787 0.706895 0.661408 -0.250679 0.698062 0.712155 -0.0744668 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.796801 0.604241 0.00143962 -0.795386 0.606102 -0.00122536 -0.969427 0.245379 -0.0167214 -0.976399 0.215324 0 -0.999446 0.0332923 0 0.471978 -0.88161 -0.0254457 0.538623 -0.842163 -0.0038594 0.63949 -0.76879 0.0105388 0.832754 -0.553543 -0.00709876 0.811719 -0.584005 0.00161368 0.93509 -0.354406 0.0201115 0.980821 -0.193868 -0.0192685 0.994393 -0.103979 -0.00122779 0.997925 0.0643693 0.0030527 0.975632 0.219392 -0.0539228 0.909402 0.412409 -0.012907 0.941131 0.337797 0.000751937 0.849859 0.527011 0 -0.119916 0.992784 -0.00495845 -0.127628 0.99181 0.00438514 0.290667 0.956814 -0.00778128 0.269745 0.9629 6.76092e-06 0.454221 0.890889 1.56611e-06 0.496278 0.868164 0.000875145 0.504485 0.86342 -0.00543462 0.701411 0.712736 -0.0432672 0.652736 0.756349 -0.00224022 0.791029 0.611775 0 -0.393349 0.919389 0 -0.393349 0.919389 0 -0.5 0.866025 0 -0.5 0.866025 0 -0.599539 0.800345 0 -0.599539 0.800345 0 0.599539 -0.800345 0 0.599539 -0.800345 0 0.5 -0.866025 0 0.5 -0.866025 0 0.393349 -0.919389 0 0.393349 -0.919389 0.879242 -0.335205 0.338485 0.887082 -0.371801 0.273585 0.954993 -0.287922 0.0713332 0.960101 -0.273977 0.0560649 0.978436 -0.200747 0.0486286 0.978976 -0.198381 0.0474444 0.991396 -0.111421 0.0686937 0.990797 -0.116578 0.0687771 0.965171 0.061103 -0.254385 0.793207 -0.38267 -0.473694 0.859467 -0.116778 -0.497674 0.839103 -0.131172 -0.527921 0.88419 0.170631 -0.434847 0.876484 0.169633 -0.450556 0.859293 -0.498321 -0.11529 0.938544 -0.3325 0.0926214 0.933188 -0.3409 0.11379 0.821647 -0.501358 -0.271178 0.847484 -0.432943 -0.307133 0.89128 -0.373407 -0.257269 0.947043 -0.160404 -0.278172 0.938319 -0.172061 -0.299921 0.970911 0.0337144 -0.237054 0.989049 -0.00259425 -0.147566 0.807334 -0.575576 0.130093 0.693244 -0.709114 -0.128725 0.770723 -0.564127 -0.296223 0.902133 -0.384658 0.195436 0.887846 -0.367234 0.277252 0.74954 -0.577736 0.323127 0.710135 -0.607708 0.355528 0.0119476 -0.890971 -0.453902 0.275997 -0.959038 -0.0638073 0.0336067 -0.968392 0.247159 0.0889206 -0.995251 0.0396076 0.188289 -0.979275 -0.0746182 -0.0536716 -0.97801 -0.201535 0.268346 -0.834586 -0.481099 0.146987 -0.7669 0.624708 0.0953329 -0.791946 0.603103 0.0937627 -0.14727 -0.984642 0.149996 0.0758295 -0.985774 0.111228 0.06404 -0.991729 0.0953825 0.463263 -0.881073 0.105767 0.465982 -0.87845 0.110841 -0.202705 -0.972947 0.17414 -0.337206 -0.925185 0.144257 -0.348872 -0.926001 0.143402 -0.664939 -0.733002 0.2663 -0.694832 -0.668052 0.0670294 -0.557912 -0.827189 0.354216 -0.934961 -0.0194665 0.457102 -0.831886 -0.314681 0.363192 -0.877942 -0.311945 0.490844 -0.650227 -0.579894 0.397296 -0.697942 -0.595846 0.522597 -0.369145 -0.768521 0.442836 -0.406278 -0.799271 0.546608 -0.0114083 -0.837311 0.493396 -0.0295227 -0.869304 0.553364 0.363498 -0.749438 0.546226 0.362965 -0.754913 0.176427 -0.983285 -0.0449969 0.30268 -0.864566 -0.401136 0.186313 -0.900796 -0.392243 0.325666 -0.65233 -0.684403 0.208468 -0.692796 -0.690344 0.343257 -0.339719 -0.875652 0.241859 -0.374426 -0.895159 0.351507 0.0415673 -0.935262 0.282645 0.0214628 -0.958984 0.345022 0.433852 -0.832305 0.333679 0.431827 -0.837964 0.879549 -0.334027 0.33885 0.763489 -0.47078 0.442098 0.693958 -0.557266 0.455935 0.651406 -0.568691 0.502256 0.484447 -0.66312 0.570599 0.918301 -0.36807 0.145764 0.901023 -0.398533 0.171256 0.758736 -0.64751 0.0710644 0.805303 -0.588019 0.0756336 0.700512 -0.713327 0.0211728 0.633808 -0.704476 0.319376 0.461123 -0.821017 0.336595 0.425671 -0.708881 0.562399 0.341456 -0.725028 0.598116 0.193425 -0.932722 0.30433 0.179195 -0.93429 0.308208 0.424091 -0.853092 0.303941 0.486868 -0.870888 0.0671879 0.502668 -0.86216 0.063292 0.601391 -0.769397 -0.215307 0.531858 -0.818992 -0.215359 0.642838 -0.620958 -0.44852 0.575101 -0.670768 -0.468326 0.685234 -0.381379 -0.620487 0.629213 -0.418409 -0.655 0.721678 -0.0656556 -0.689109 0.685622 -0.0820237 -0.723322 0.739939 0.27873 -0.612209 0.725685 0.277497 -0.629584 0.146163 -0.129402 0.980761 0.82627 0.455461 0.331411 0.651435 -0.150658 0.743596 0.880894 -0.0695808 0.468171 0.992268 0.0197099 0.122537 0.992327 -0.0242031 0.12125 0.976265 0.0735486 0.203711 0.978908 0.0571871 0.196137 0.963207 0.0839233 0.255323 0.94293 0.118575 0.311163 0.902137 0.00439737 0.431428 0.895798 -5.25607e-05 0.444461 0.919326 0.052439 0.389986 0.851017 -0.191602 0.488936 0.740541 0.37551 0.557307 0.783615 0.367404 0.50096 0.707954 0.216517 0.672251 0.912306 0.0525414 0.406125 0.939733 0.0786498 0.33274 0.785901 0.485135 0.38341 0.847486 0.482442 0.221397 0.793261 0.601504 0.0944952 0.856964 0.498422 -0.131101 0.84421 0.510453 -0.163549 0.884163 0.29809 -0.359719 0.877676 0.297745 -0.375543 0.923015 0.0954111 0.372748 0.960832 0.0674035 0.268811 0.891324 0.409425 0.194712 0.944822 0.327341 0.0126354 0.94184 0.335895 -0.0105378 0.970919 0.188451 -0.147654 0.965173 0.189778 -0.180073 0.115156 0.638353 -0.761081 0.0770959 0.812085 -0.578424 0.14646 0.824604 -0.546423 0.0440173 0.980461 -0.191727 0.0570969 0.980915 -0.185864 0.099827 0.992277 0.0736247 0.181851 0.960118 0.212377 0.334002 0.505778 -0.795381 0.105773 0.527832 -0.842737 0.27892 0.456825 -0.844698 0.0122658 0.579223 0.815077 0.315353 0.596696 0.737906 0.112596 0.494018 0.86213 0.13605 0.963623 0.230048 0.0636222 0.904059 0.422645 0.202847 0.808662 0.552194 0.247975 0.81054 0.530598 0.108775 0.779944 0.616324 0.0842628 0.447246 0.890433 0.0328657 0.267392 0.963027 0.19022 0.20211 0.960712 0.0915631 -0.157091 0.98333 0.341456 -0.155544 0.926938 0.693998 -0.116233 0.710533 0.714755 0.051074 0.697508 0.412209 0.129499 0.901839 0.486919 0.377325 0.787741 0.35418 0.484424 0.799931 0.447645 0.668547 0.593851 0.378523 0.725907 0.574264 0.480139 0.820054 0.311414 0.413103 0.8697 0.270126 0.514065 0.857242 -0.0295675 0.455191 0.886758 -0.0803827 0.542696 0.74524 -0.387426 0.499645 0.75281 -0.428524 0.553288 0.470131 -0.687641 0.546666 0.4692 -0.693548 0.34468 0.508534 -0.789043 0.288264 0.804316 -0.519595 0.346232 0.805439 -0.481032 0.253711 0.954159 -0.15878 0.332831 0.936987 -0.106202 0.224024 0.950399 0.215768 0.313045 0.912341 0.263886 0.201536 0.808978 0.552211 0.291652 0.759412 0.581578 0.187834 0.55443 0.810757 0.26928 0.509027 0.817545 0.179189 0.200112 0.963248 0.463853 0.155694 0.872124 0.425704 -0.132669 0.895084 0.484444 -0.162646 0.85957 0.875353 -0.136381 0.46385 0.889583 -0.0575362 0.453135 0.689703 0.0317139 0.723397 0.745681 0.227848 0.626135 0.502641 0.376334 0.778283 0.593267 0.552197 0.585758 0.546284 0.610041 0.573954 0.633762 0.691084 0.347489 0.590009 0.743806 0.314074 0.678255 0.733025 0.05142 0.640941 0.767564 0.00624847 0.718697 0.641487 -0.268271 0.691734 0.653561 -0.307186 0.739911 0.398712 -0.541813 0.727066 0.397888 -0.559517 0.572896 -0.409814 0.709819 0.850726 -0.205746 0.483668 0.879517 -0.286093 0.380263 0.654678 -0.453197 0.604988 0.765 -0.386122 0.515447 0.845141 -0.317736 0.42986 0.851114 -0.290043 0.437585 0.850696 -0.262829 0.455233 0.850696 -0.262829 0.455233 0.851114 -0.233939 0.469976 0.345767 -0.56256 0.75098 0.488419 -0.523164 0.698389 0.149212 -0.592828 0.791386 0.201907 -0.584393 0.785951 0.201868 -0.489707 0.848196 0.844347 -0.210755 0.492605 0.654704 -0.297327 0.694953 0.573018 -0.326521 0.751688 0.488413 -0.343242 0.802271 0.345766 -0.369088 0.862682 0.57302 -0.48772 0.658618 0.572898 -0.409813 0.709817 0.201873 -0.489706 0.848195 0.201913 -0.388456 0.899074 0.149221 -0.388945 0.909095 0.340886 0.36979 -0.864322 0.994035 -0.0545309 0.0944503 0.994036 -0.0426862 0.100347 0.994251 -0.0421194 0.098447 0.991754 -0.0770487 0.10241 0.996676 -0.045011 0.0679077 0.658679 0.376211 -0.651618 0.931791 0.181498 -0.314364 0.994046 -0.0637754 0.0883519 0.993745 0.0669509 -0.0893749 0.971836 0.141286 -0.188607 0.994056 -0.0485145 0.0974635 0.994035 -0.054531 0.0944505 0.93179 0.181499 -0.314365 0.931638 0.223052 -0.286876 0.558451 0.313406 -0.768055 0.739309 0.264868 -0.619086 0.931791 0.142784 -0.333734 0.888074 0.170106 -0.427071 0.971842 0.0926858 -0.216638 0.237283 0.485721 -0.841292 0.237283 0.382116 -0.893132 0.108128 0.377588 -0.919639 0.887836 0.275884 -0.368287 0.739301 0.403715 -0.538932 0.658468 0.45653 -0.598332 0.5581 0.497482 -0.664105 0.340899 0.563627 -0.752405 0.658679 0.295966 -0.691771 0.658679 0.376212 -0.651618 0.237291 0.485719 -0.841291 0.237194 0.587741 -0.773498 0.108037 0.59603 -0.795661 0.939515 -0.205917 0.273697 0.939604 -0.22248 0.26009 0.93949 -0.222777 0.260247 0.939579 -0.22242 0.260233 0.939697 -0.221428 0.260651 0.939842 -0.222064 0.259584 0.939865 -0.222063 0.259503 0.939743 -0.222233 0.259798 0.939507 -0.13408 0.315196 0.939902 -0.113596 0.321993 0.939804 -0.113966 0.322148 0.93969 -0.115025 0.322106 0.939697 -0.114819 0.322158 0.939545 -0.114078 0.322865 0.939488 -0.113971 0.323068 0.939529 -0.11402 0.322932 0.939645 -0.113966 0.322613 0.939777 -0.113844 0.322272 0.939515 -0.134072 0.315177 0.939511 -0.134077 0.315186 0.939694 -0.152409 0.306183 0.939694 -0.152408 0.306183 0.939498 -0.171278 0.296662 0.939498 -0.171278 0.296662 0.939694 -0.188959 0.28508 0.939693 -0.188959 0.28508 0.939511 -0.205922 0.273706 0.939507 -0.20593 0.273713 0.93969 -0.22161 0.260523 0 -0.980343 -0.1973 -0.0147983 -0.974163 -0.225362 0.00919268 -0.852941 -0.521927 -0.0320485 -0.775906 -0.630034 4.71727e-05 -0.195459 -0.980712 -0.000407479 -0.340774 -0.940145 -0.0292571 -0.420417 -0.906859 0.00281937 -0.554091 -0.832452 -0.00332527 -0.701549 -0.712614 -0.00141608 -0.140908 -0.990022 -0.0215486 0.0205663 -0.999556 0.00423099 0.0851483 -0.996359 -0.00527097 0.457554 -0.889166 0 0.467196 -0.884154 0.697832 -0.697832 -0.161436 0.697835 -0.697829 -0.161434 0.697834 -0.556036 -0.4515 0.697829 -0.556039 -0.451504 0.697828 -0.301259 -0.64983 0.697829 -0.301259 -0.649828 0.697829 0.0147343 -0.716113 0.697828 0.0147347 -0.716114 0.697828 0.327735 -0.636887 0.697822 0.327739 -0.636892 0 0.98914 -0.14698 0.0121338 0.980269 -0.197294 0.000276862 0.941878 -0.335956 -0.00108225 0.827686 -0.561191 0.00242649 0.833749 -0.552138 -0.000121323 0.698968 -0.715153 0.00291359 0.546143 -0.837687 0 0.537823 -0.843058 -0.70004 0.700066 -0.140898 -0.700049 0.39 -0.59819 -0.700048 0.39 -0.598192 -0.702984 0.569466 -0.426055 -0.763184 0.534836 -0.362631 -0.706724 0.638977 -0.303727 -0.700053 0.700054 -0.140891 -0.698063 -0.557515 0.449317 -0.69807 -0.55751 0.449311 -0.69807 -0.697247 0.162926 -0.609308 -0.765624 0.206309 -0.706898 -0.706783 0.0274481 -0.698064 -0.698894 -0.155735 -0.69807 -0.698888 -0.155735 -0.698071 -0.562105 -0.443549 -0.698076 -0.5621 -0.443547 -0.698075 -0.31399 -0.643508 -0.698069 -0.313994 -0.643512 -0.706902 -0.137667 -0.693785 -0.698065 0.307349 -0.646716 -0.698066 0.307349 -0.646715 -0.700595 0.0203388 -0.713269 -0.796093 0.056163 -0.602563 -0.684047 -0.0956214 -0.723143 -0.696408 0.696434 0.173192 -0.696421 0.696421 0.173193 -0.703796 0.576533 0.415067 -0.504597 0.642641 0.576536 -0.696412 -0.0968762 0.711073 -0.696414 -0.0968763 0.711072 -0.703785 0.172202 0.689226 -0.504592 0.297729 0.810398 -0.705058 0.332849 0.626183 -0.705057 0.458515 0.540979 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706174 0.397345 -0.586034 -0.706177 0.397343 -0.586031 -0.706176 0.308847 -0.637125 -0.706178 0.308846 -0.637124 0 0.414414 -0.910088 -0.04202 0.435817 -0.899054 0 0.479008 -0.877811 0 0.561191 -0.827686 -0.0629304 0.579801 -0.812324 0 0.520703 -0.853738 -0.706174 -0.397345 0.586034 -0.706177 -0.397343 0.586031 -0.706176 -0.308847 0.637125 -0.706172 -0.308848 0.637129 0 -0.175915 0.984405 0.0159028 -0.134975 0.990721 2.45547e-05 0.0665564 0.997783 3.90994e-06 0.242397 0.970177 -2.35755e-05 0.2425 0.970151 3.01356e-05 0.469364 0.883005 -0.0019339 0.478021 0.878347 0.00175515 0.646568 0.762854 1.0547e-05 0.654014 0.756482 -1.17646e-05 0.810302 0.586012 0.000490295 0.811559 0.584271 -0.000219698 0.906652 0.421879 0.0176341 0.97029 0.241301 0 0.982115 0.188283 0 0.498814 -0.866709 0.017844 0.42917 -0.903048 0.00272634 0.314497 -0.949255 -0.00733951 0.0285025 -0.999567 0.00493709 0.0654728 -0.997842 -0.00112366 -0.194634 -0.980875 -0.0112956 -0.322077 -0.946646 0.0189633 -0.438441 -0.89856 0.00487176 -0.532989 -0.846108 -0.00685875 -0.684895 -0.72861 0.0389231 -0.837565 -0.544949 0.0057548 -0.785016 -0.619448 -0.000320988 -0.901362 -0.433067 0 -0.778614 0.627503 0.00764527 -0.767293 0.641252 -0.00712324 -0.965535 0.260177 0.00552559 -0.956739 0.290895 -5.42064e-06 -0.99625 0.0865247 -9.88257e-07 -0.999247 0.0388061 -2.65226e-06 -0.999248 0.0387795 -7.05661e-05 -0.976061 -0.217498 0.0308518 -0.989184 -0.1434 0.00152982 -0.93786 -0.347009 -0.994042 -0.0633211 0.0887153 -0.971841 0.136895 -0.191795 -0.658919 0.376107 -0.651436 -0.108084 0.411987 -0.904757 -0.558299 0.343814 -0.755046 -0.341049 0.389568 -0.855525 -0.237325 0.394969 -0.887511 -0.237621 0.465288 -0.852668 -0.153991 0.494036 -0.855696 -0.237623 0.505788 -0.829285 -0.237428 0.564341 -0.790663 -0.887884 0.190658 -0.418701 -0.739466 0.278981 -0.612666 -0.108172 0.592334 -0.798398 -0.341051 0.546122 -0.765137 -0.658919 0.437001 -0.612255 -0.558603 0.496017 -0.664778 -0.739469 0.391093 -0.547935 -0.971845 0.0976451 -0.214437 -0.931696 0.143051 -0.333885 -0.931861 0.181408 -0.314208 -0.658698 0.304196 -0.688172 -0.658921 0.376106 -0.651435 -0.931861 0.181408 -0.314208 -0.931861 0.21078 -0.29531 -0.88809 0.278749 -0.365507 -0.994042 -0.045169 0.099195 -0.994042 -0.0451692 0.0991955 -0.994053 -0.0521644 0.0955953 -0.994978 -0.0500477 0.0866851 -0.994053 -0.0567051 0.0929736 -0.994042 -0.0633211 0.0887153 0 -0.436202 0.899849 0.126162 -0.400205 0.9077 0 -0.468406 0.883513 0 -0.561191 0.827687 0.126161 -0.526699 0.840638 0 -0.590708 0.806885 -0.891408 0.402875 0.207566 -0.893727 -0.0417178 0.446667 -0.90088 0.0122353 0.433896 -0.982603 0.0505423 0.178708 -0.968984 0.0675704 0.237708 -0.95918 0.0812342 0.270877 -0.955076 0.0734743 0.287108 -0.937213 0.0759739 0.340382 -0.963016 0.211685 -0.166701 -0.971391 0.182451 -0.152025 -0.876428 0.318027 -0.361571 -0.884045 0.304578 -0.354538 -0.858962 0.495434 -0.129344 -0.839071 0.527545 -0.13288 -0.946584 0.322228 0.0121361 -0.938298 0.345669 0.0104798 -0.978164 0.0475856 0.202314 -0.993506 -0.0155905 0.112709 -0.993503 -0.00928723 0.113428 -0.712673 0.00144546 0.701495 -0.884951 -0.071848 0.460109 -0.885799 -0.0771629 0.457608 -0.792141 0.599056 0.116812 -0.849344 0.475157 0.229871 -0.805194 0.474733 0.355375 -0.812789 0.429296 0.393802 -0.759745 0.375085 0.53113 -0.771362 0.320364 0.549879 -0.72281 0.220562 0.654903 -0.182131 0.783807 0.593696 -0.133809 0.803991 0.579391 -0.0550203 0.648473 0.759246 -0.275275 0.505165 0.817944 -0.329669 0.423916 0.843572 -0.0482324 0.548964 0.834453 -0.0957287 0.23475 0.967331 -0.146939 -0.190425 0.970643 -0.123005 -0.177545 0.976395 -0.158576 0.0573743 0.985678 -0.106258 0.536881 -0.836939 -0.166738 0.553164 -0.816215 -0.107834 0.698594 -0.707346 -0.0853928 0.845783 -0.526649 -0.073669 0.900331 0.428926 -0.156272 0.966288 0.204614 -0.0282638 0.973326 0.227681 -0.141866 0.981263 -0.130375 -0.170635 0.975655 -0.137775 -0.0918965 0.940756 -0.326395 -0.151903 0.8301 -0.536525 -0.353644 0.456152 0.816616 -0.45601 0.667374 0.588784 -0.364119 0.689735 0.625845 -0.489609 0.817053 0.304478 -0.398059 0.854657 0.333332 -0.521629 0.852553 -0.0325027 -0.443227 0.896209 -0.0189478 -0.546165 0.74567 -0.381682 -0.493422 0.7808 -0.383257 -0.553285 0.490978 -0.672916 -0.546211 0.49575 -0.675193 -0.177313 0.504053 0.845275 -0.301518 0.758821 0.577302 -0.187434 0.771393 0.608129 -0.324433 0.910171 0.257549 -0.20939 0.935641 0.284133 -0.342314 0.93329 -0.108583 -0.242323 0.965787 -0.0923887 -0.351086 0.807276 -0.474388 -0.282723 0.835838 -0.470577 -0.344984 0.531489 -0.773631 -0.333626 0.537048 -0.774773 -0.484353 -0.191566 0.853642 -0.687667 -0.171746 0.70542 -0.647366 -0.132053 0.750653 -0.870212 -0.205274 0.447876 -0.850011 -0.146741 0.505914 -0.933087 0.0610862 0.354426 -0.918224 0.0456407 0.393424 -0.916086 0.0449177 0.398458 -0.902766 -0.0139798 0.429904 -0.738156 0.172013 0.652332 -0.697725 0.0304738 0.715717 -0.461102 0.0908653 0.882682 -0.424996 -0.166276 0.889793 -0.341424 -0.187535 0.92101 -0.222901 0.174889 0.959025 -0.179695 0.168611 0.969165 -0.423352 0.131126 0.896426 -0.487236 0.353137 0.798683 -0.503326 0.351503 0.789372 -0.600327 0.550547 0.580092 -0.532643 0.576748 0.619397 -0.641639 0.687489 0.340087 -0.575727 0.729367 0.369545 -0.684275 0.727667 0.047623 -0.629476 0.774715 0.0598157 -0.721169 0.640371 -0.264273 -0.685635 0.676745 -0.268182 -0.739823 0.410117 -0.533353 -0.725698 0.425101 -0.540973 -0.146451 -0.756567 0.637305 -0.824708 -0.525746 -0.208443 -0.651397 -0.550802 0.521824 -0.942262 -0.329414 0.0602365 -0.971802 -0.226758 0.0646739 -0.978816 -0.198871 0.0486824 -0.989309 -0.125825 0.0737247 -0.993672 -0.0892245 0.0682235 -0.851105 -0.321713 0.414874 -0.873463 -0.365167 0.32205 -0.889404 -0.364277 0.276159 -0.901406 -0.368942 0.226604 -0.895306 -0.378148 0.23544 -0.91823 -0.360527 0.163935 -0.741735 -0.670145 -0.0271213 -0.782192 -0.621537 -0.0432185 -0.708892 -0.684847 0.168693 -0.91196 -0.37347 0.16985 -0.938586 -0.326727 0.110928 -0.78696 -0.579757 -0.211128 -0.849347 -0.436643 -0.296569 -0.792187 -0.400597 -0.460392 -0.856724 -0.152406 -0.492745 -0.843571 -0.133111 -0.520259 -0.884012 0.147448 -0.443602 -0.877484 0.160199 -0.452061 -0.921896 -0.370579 0.113047 -0.959989 -0.265047 0.0903926 -0.891443 -0.381123 -0.245102 -0.944653 -0.183825 -0.271733 -0.941309 -0.170482 -0.29133 -0.970892 0.0271965 -0.237968 -0.965064 0.0518163 -0.256838 -0.115185 0.307618 -0.944512 -0.0768062 0.0594979 -0.995269 -0.146659 0.0273694 -0.988809 -0.0529624 -0.325764 -0.943967 -0.148664 -0.367033 -0.918251 -0.0857149 -0.539973 -0.837306 -0.146646 -0.688965 -0.709804 -0.333937 0.406251 -0.850557 -0.105765 0.435664 -0.893874 -0.296942 0.471618 -0.830302 -0.0132385 -0.997954 -0.0625568 -0.298396 -0.948931 -0.102424 -0.108493 -0.992906 0.048651 -0.143079 -0.689931 -0.709594 -0.0595367 -0.843247 -0.534219 -0.223395 -0.894075 -0.388234 -0.243135 -0.886561 -0.393567 -0.107828 -0.936757 -0.332955 -0.0837789 -0.992074 0.0936513 -0.0300968 -0.955595 0.293143 -0.178499 -0.923715 0.338951 -0.112024 -0.749556 0.652393 -0.341465 -0.703797 0.622955 -0.692764 -0.538521 0.47966 -0.714398 -0.618259 0.327705 -0.412908 -0.834413 0.365052 -0.487262 -0.868244 0.0934198 -0.353599 -0.935304 0.0131819 -0.447581 -0.857408 -0.254012 -0.377651 -0.872118 -0.31111 -0.480011 -0.697724 -0.531762 -0.412114 -0.690742 -0.59417 -0.513926 -0.428195 -0.743323 -0.454267 -0.402869 -0.794568 -0.542567 -0.0655809 -0.837449 -0.499061 -0.0365304 -0.865796 -0.553201 0.334481 -0.762949 -0.546584 0.33968 -0.765417 -0.344662 0.399797 -0.849335 -0.287811 0.0135699 -0.957591 -0.346267 -0.01801 -0.937963 -0.253013 -0.371823 -0.893159 -0.332867 -0.405409 -0.851377 -0.22331 -0.687118 -0.691377 -0.313059 -0.706301 -0.634928 -0.200952 -0.897197 -0.393264 -0.291653 -0.895084 -0.337287 -0.187452 -0.981438 -0.0405053 -0.26929 -0.963059 1.88091e-05 -0.179715 -0.923584 0.338667 -0.46351 -0.821641 0.33176 -0.425032 -0.687396 0.588926 -0.484355 -0.643461 0.592755 -0.870904 -0.322274 0.371033 -0.892968 -0.346071 0.287824 -0.690171 -0.631275 0.353775 -0.744778 -0.652224 0.141102 -0.503288 -0.859398 0.0901991 -0.593142 -0.789055 -0.15992 -0.545228 -0.810775 -0.213002 -0.63358 -0.660107 -0.403529 -0.588803 -0.661656 -0.464245 -0.677985 -0.431164 -0.595343 -0.639886 -0.413476 -0.647753 -0.718477 -0.111757 -0.686514 -0.69109 -0.086996 -0.717514 -0.739779 0.248777 -0.625169 -0.726932 0.26337 -0.634197 -0.939621 -0.20215 0.276129 -0.939565 -0.141883 0.311587 -0.938393 -0.127812 0.321064 -0.939692 -0.125107 0.31832 -0.939425 -0.124509 0.31934 -0.939408 -0.124479 0.319401 -0.939888 -0.124255 0.318075 -0.939982 -0.123895 0.317937 -0.939935 -0.124042 0.318018 -0.939772 -0.124283 0.318407 -0.939574 -0.124485 0.318912 -0.939636 -0.213837 0.267128 -0.939833 -0.213502 0.266704 -0.940956 -0.209771 0.265703 -0.939692 -0.213086 0.267532 -0.93996 -0.213373 0.266359 -0.939977 -0.213384 0.266289 -0.939693 -0.212709 0.267829 -0.939472 -0.214145 0.267458 -0.939449 -0.214226 0.267475 -0.939566 -0.1989 0.278666 -0.94337 -0.194139 0.269003 -0.936007 -0.183276 0.3005 -0.939622 -0.181695 0.289995 -0.93966 -0.163871 0.300307 -0.937285 -0.163269 0.30796 -0.94337 -0.135894 0.302631 -0.939621 -0.13806 0.313132 -0.939692 -0.125596 0.318126 -0.149349 -0.584083 0.797836 -0.48879 -0.515335 0.703928 -0.34607 -0.378501 0.858471 -0.655056 -0.304823 0.691364 -0.850963 -0.211891 0.480588 -0.850962 -0.211892 0.480588 -0.850962 -0.246019 0.464045 -0.850963 -0.246019 0.464045 -0.850962 -0.278865 0.445082 -0.850962 -0.278865 0.445083 -0.850962 -0.310257 0.423798 -0.850961 -0.310257 0.4238 -0.655068 -0.446322 0.609658 -0.573441 -0.477866 0.66544 -0.57333 -0.435014 0.694303 -0.573327 -0.435014 0.694304 -0.573327 -0.383778 0.723886 -0.573328 -0.383777 0.723885 -0.573439 -0.337355 0.746565 -0.488791 -0.351952 0.798256 -0.346103 -0.554201 0.757017 -0.202128 -0.573831 0.793639 -0.20209 -0.519986 0.829924 -0.202093 -0.519986 0.829923 -0.202092 -0.458742 0.865283 -0.202093 -0.458742 0.865283 -0.202131 -0.400396 0.893771 -0.149349 -0.398904 0.904749 0.707104 0.240538 -0.66494 0.671181 0.293288 -0.680807 0.706477 0.278388 -0.650685 0.706477 0.353868 -0.612917 0.70647 0.353871 -0.612923 0.706522 0.422874 -0.567455 0.67281 0.443549 -0.592108 0.707096 0.455588 -0.540791 0.706464 -0.278393 0.650697 0.706471 -0.27839 0.650691 0.706471 -0.353871 0.612922 0.70647 -0.353872 0.612923 0.70647 -0.42432 0.566439 0.706472 -0.424318 0.566437 -0.0339853 -0.972398 -0.230839 -0.0129984 -0.98313 -0.182448 0 -0.99955 -0.0300107 -4.11559e-06 -0.255524 -0.966803 -0.0270682 -0.374507 -0.926829 -0.0339718 -0.394143 -0.918421 0.00634638 -0.529108 -0.848531 -3.05681e-07 -0.614498 -0.788918 7.0324e-06 -0.69123 -0.722635 -0.0273449 -0.77983 -0.625393 0.0167732 -0.852426 -0.522579 -0.0102518 -0.942696 -0.333495 1.10465e-06 -0.088364 -0.996088 -0.0300315 0.0607133 -0.997703 0.00810589 0.166422 -0.986021 -2.09808e-07 0.311874 -0.950124 1.96204e-06 0.356623 -0.934249 -0.0103612 0.522873 -0.852348 0.00709813 0.55721 -0.830341 -0.00823655 0.837697 -0.546074 0 0.846894 -0.531762 0.697351 0.600422 -0.391401 0.697349 0.600424 -0.391402 0.697347 0.360441 -0.619507 0.642346 0.400759 -0.653287 0.70701 0.220558 -0.671931 0.697347 0.0435344 -0.715411 0.697345 0.043535 -0.715412 0.697355 -0.28266 -0.658635 0.69735 -0.69735 -0.165545 0.697353 -0.697348 -0.165544 0.699229 -0.557707 -0.447259 0.650489 -0.581276 -0.488858 0.707005 -0.434579 -0.55793 0.697343 -0.282661 -0.658647 0 0.991323 -0.131447 0.00725968 0.98606 -0.166233 4.28663e-05 0.955906 -0.293673 -0.000319819 0.877086 -0.480333 0 0.877672 -0.479262 -0.702136 0.702136 -0.118368 -0.702132 0.702139 -0.11837 -0.702133 0.624525 -0.342019 -0.70213 0.624528 -0.342022 -0.994042 -0.0991947 0.0451689 -0.971842 0.214448 -0.0976502 -0.658918 0.651437 -0.376108 -0.108097 0.809168 -0.577549 -0.558293 0.675278 -0.481984 -0.341049 0.765138 -0.546122 -0.237325 0.785809 -0.571122 -0.237621 0.829285 -0.50579 -0.153985 0.855696 -0.494037 -0.237624 0.852669 -0.465286 -0.237429 0.884065 -0.402563 -0.887885 0.374465 -0.267277 -0.739468 0.547936 -0.391093 -0.108198 0.912172 -0.395267 -0.341027 0.855532 -0.38957 -0.658918 0.684583 -0.311727 -0.558617 0.761943 -0.327704 -0.739468 0.612664 -0.27898 -0.971845 0.191781 -0.136885 -0.931697 0.290826 -0.217626 -0.931861 0.314207 -0.181407 -0.658697 0.607529 -0.443877 -0.658919 0.651436 -0.376107 -0.931861 0.314208 -0.181408 -0.931861 0.330195 -0.150356 -0.888087 0.424162 -0.177165 -0.994042 -0.0887152 0.0633211 -0.994042 -0.0887149 0.0633209 -0.994053 -0.092973 0.0567053 -0.994978 -0.086685 0.0500475 -0.994053 -0.0955945 0.0521648 -0.994042 -0.0991949 0.0451691 0 -0.827687 0.561191 0.12616 -0.800438 0.585988 0 -0.847408 0.530942 0 -0.899849 0.436202 0.126159 -0.876454 0.464663 0 -0.915011 0.403429 -0.89141 0.245114 0.381192 -0.893729 -0.259451 0.365969 -0.90088 -0.206354 0.381881 -0.982603 -0.045583 0.180037 -0.968983 -0.060337 0.23965 -0.95918 -0.0650881 0.275203 -0.955076 -0.0799241 0.28538 -0.937214 -0.104395 0.332764 -0.963018 0.26667 -0.0385255 -0.971391 0.23402 -0.040433 -0.876428 0.456204 -0.154117 -0.884045 0.441041 -0.154751 -0.858962 0.49373 0.135701 -0.839073 0.523304 0.148693 -0.946586 0.272986 0.171623 -0.938298 0.294119 0.181911 -0.978164 -0.0599459 0.199002 -0.993506 -0.0698561 0.0898141 -0.993503 -0.0647572 0.0935874 -0.71267 -0.349493 0.60824 -0.88495 -0.292274 0.362544 -0.885801 -0.295634 0.357711 -0.792139 0.460391 0.400694 -0.849342 0.296564 0.436656 -0.805194 0.233447 0.545128 -0.812789 0.174883 0.555689 -0.759743 0.0592678 0.647517 -0.771361 0.00250009 0.636393 -0.72281 -0.136437 0.677444 -0.116197 0.435008 0.892898 -0.185753 0.396198 0.899179 -0.0296807 0.21913 0.975244 -0.275277 0.0285174 0.960942 -0.12792 -0.618671 0.775166 -0.161199 -0.424991 0.890728 -0.28633 -0.0297293 0.95767 -0.0901178 0.0529802 0.994521 -0.0666521 -0.248137 0.966429 -0.933087 -0.124313 0.337484 -0.918227 -0.157181 0.363528 -0.916086 -0.16033 0.367534 -0.902766 -0.22706 0.365318 -0.738157 -0.177199 0.650942 -0.697725 -0.331469 0.635066 -0.461104 -0.362651 0.809856 -0.106671 0.873735 -0.474562 -0.207975 0.880675 -0.425627 -0.0433279 0.932636 0.358207 -0.121173 0.989707 0.0761322 -0.245827 0.969149 -0.0178747 -0.0874125 0.988247 -0.125404 -0.11214 0.951356 -0.286961 -0.0815491 0.582449 0.808766 -0.113662 0.650397 0.751043 -0.227277 0.690013 0.687188 -0.0280906 0.802347 0.596196 -0.212762 0.923402 0.319471 -0.353638 -0.0132656 0.935288 -0.456009 0.283568 0.843591 -0.364136 0.284402 0.88686 -0.489623 0.555344 0.672207 -0.398073 0.573484 0.715999 -0.521641 0.754578 0.398123 -0.443214 0.785618 0.431701 -0.546158 0.836614 0.0422896 -0.493424 0.86782 0.0584874 -0.553286 0.761656 -0.337275 -0.546205 0.766933 -0.336861 -0.177309 0.0138881 0.984057 -0.301512 0.368511 0.879369 -0.187407 0.363984 0.912356 -0.324406 0.659463 0.678137 -0.209386 0.668225 0.713886 -0.342309 0.862548 0.372607 -0.242324 0.882592 0.402877 -0.351084 0.936316 -0.00719298 -0.282721 0.959146 0.0103892 -0.344987 0.847097 -0.404242 -0.333627 0.852483 -0.402451 -0.149386 -0.757937 0.634993 -0.192869 -0.646208 0.738388 -0.341422 -0.622915 0.703852 -0.424997 -0.588893 0.687446 -0.484353 -0.59272 0.643494 -0.687663 -0.501447 0.525043 -0.647368 -0.489691 0.584053 -0.870214 -0.401712 0.285228 -0.850011 -0.380037 0.364765 -0.238105 -0.324173 0.915542 -0.1797 -0.33856 0.923626 -0.423351 -0.334654 0.841891 -0.487233 -0.0935151 0.86825 -0.503331 -0.0902737 0.859365 -0.600327 0.186744 0.777646 -0.532636 0.189782 0.824792 -0.641633 0.425345 0.63827 -0.575729 0.44688 0.684714 -0.684274 0.606365 0.405081 -0.629474 0.641013 0.439164 -0.721168 0.686716 0.0913165 -0.685632 0.720172 0.106119 -0.739823 0.621849 -0.256838 -0.7257 0.638632 -0.255946 -0.146448 -0.973858 0.17365 -0.824711 -0.351083 -0.443388 -0.65139 -0.737924 0.176516 -0.942264 -0.315397 -0.112536 -0.971801 -0.228718 -0.0573694 -0.978816 -0.196568 -0.0572753 -0.989309 -0.145832 0.000932272 -0.993672 -0.111383 0.0144695 -0.851104 -0.486053 0.19843 -0.87347 -0.477256 0.0963195 -0.889408 -0.453543 0.0570255 -0.90141 -0.432806 0.0117765 -0.895308 -0.4452 0.0148263 -0.918232 -0.394188 -0.0382878 -0.741739 -0.566798 -0.358557 -0.78219 -0.516661 -0.348195 -0.708892 -0.677439 -0.196336 -0.911953 -0.408376 -0.0396384 -0.938586 -0.338418 -0.0673004 -0.786961 -0.396518 -0.472722 -0.849347 -0.229857 -0.475158 -0.792189 -0.116731 -0.599007 -0.856723 0.114385 -0.502933 -0.843571 0.144852 -0.517113 -0.884012 0.349493 -0.310448 -0.877481 0.364771 -0.311399 -0.921904 -0.377436 -0.087383 -0.959989 -0.274735 -0.054242 -0.891439 -0.207512 -0.402835 -0.944652 -0.023328 -0.327243 -0.941309 -0.00197659 -0.337542 -0.970892 0.14254 -0.192489 -0.965065 0.17329 -0.19652 -0.115162 0.738641 -0.664189 -0.0767909 0.549164 -0.832179 -0.146652 0.518107 -0.84265 -0.0529648 0.189865 -0.980381 -0.148666 0.141267 -0.978745 -0.0857099 -0.0489769 -0.995116 -0.146634 -0.24176 -0.959193 -0.333915 0.777111 -0.533478 -0.10579 0.824234 -0.55628 -0.296956 0.823581 -0.48325 -0.0132249 -0.832978 -0.553148 -0.298417 -0.770581 -0.563163 -0.108502 -0.884213 -0.454307 -0.14308 -0.242698 -0.959493 -0.0595377 -0.463172 -0.884266 -0.22338 -0.580172 -0.783264 -0.243229 -0.570947 -0.78413 -0.107815 -0.644788 -0.756719 -0.083815 -0.905969 -0.414964 -0.0301267 -0.97414 -0.223928 -0.178502 -0.969434 -0.168327 -0.112021 -0.975329 0.190221 -0.341418 -0.920998 0.187608 -0.69277 -0.706198 0.146134 -0.714404 -0.699275 -0.0253273 -0.412921 -0.905143 -0.10106 -0.487275 -0.798624 -0.353219 -0.353595 -0.816583 -0.456249 -0.447575 -0.61553 -0.648691 -0.377663 -0.599724 -0.705481 -0.480018 -0.338374 -0.809374 -0.412103 -0.301114 -0.859943 -0.513924 0.000837229 -0.857835 -0.454269 0.04839 -0.88955 -0.542566 0.361928 -0.758043 -0.499064 0.401258 -0.768067 -0.553208 0.67114 -0.49349 -0.546597 0.676872 -0.493028 -0.344655 0.770904 -0.535649 -0.287811 0.490546 -0.822514 -0.346273 0.453379 -0.821305 -0.253011 0.124574 -0.95941 -0.332866 0.0745954 -0.940019 -0.223316 -0.249376 -0.942307 -0.313059 -0.29421 -0.903014 -0.200951 -0.580361 -0.789177 -0.291673 -0.606525 -0.739631 -0.187477 -0.8297 -0.525786 -0.269254 -0.834042 -0.481535 -0.179669 -0.969189 -0.1685 -0.463517 -0.877439 -0.123504 -0.425041 -0.889762 0.166324 -0.484377 -0.853618 0.191614 -0.870908 -0.464612 0.160172 -0.892966 -0.443622 0.0762361 -0.69016 -0.723598 -0.0092481 -0.744775 -0.635396 -0.203918 -0.503287 -0.78936 -0.351586 -0.59314 -0.603386 -0.53302 -0.545212 -0.595653 -0.589866 -0.63357 -0.3699 -0.679532 -0.588811 -0.340896 -0.732865 -0.677989 -0.0757265 -0.731161 -0.639888 -0.0342026 -0.767707 -0.718475 0.246474 -0.650419 -0.69109 0.283415 -0.664884 -0.73978 0.528031 -0.417024 -0.726932 0.545185 -0.417546 -0.939622 -0.31313 0.138059 -0.939565 -0.278667 0.198901 -0.938391 -0.271227 0.214146 -0.939692 -0.267505 0.21312 -0.939427 -0.267497 0.214295 -0.939408 -0.267503 0.214371 -0.939887 -0.26665 0.213332 -0.939984 -0.266255 0.213395 -0.939935 -0.266433 0.213391 -0.939774 -0.26683 0.213604 -0.939573 -0.267264 0.213946 -0.939642 -0.318736 0.124418 -0.939829 -0.31826 0.124229 -0.940949 -0.314541 0.125215 -0.939693 -0.318304 0.125142 -0.93996 -0.317967 0.123988 -0.939977 -0.317941 0.12392 -0.939691 -0.318131 0.125588 -0.939472 -0.319187 0.124552 -0.939449 -0.319262 0.124527 -0.939564 -0.311589 0.141884 -0.94337 -0.302631 0.135894 -0.936007 -0.308972 0.168602 -0.939622 -0.302351 0.160296 -0.93966 -0.292071 0.178138 -0.937285 -0.295376 0.185067 -0.94337 -0.269004 0.194139 -0.939621 -0.27613 0.202151 -0.939692 -0.267832 0.212708 -0.149346 -0.904749 0.398905 -0.488807 -0.798247 0.35195 -0.346067 -0.757028 0.554207 -0.65506 -0.609664 0.446325 -0.850963 -0.423798 0.310255 -0.850959 -0.423801 0.310259 -0.850959 -0.445086 0.278868 -0.850964 -0.445079 0.278863 -0.850964 -0.464042 0.246018 -0.850963 -0.464044 0.24602 -0.850963 -0.480588 0.211891 -0.85096 -0.480592 0.211894 -0.655062 -0.69136 0.30482 -0.57343 -0.74657 0.337358 -0.57332 -0.72389 0.38378 -0.573324 -0.723888 0.383778 -0.573324 -0.694305 0.435017 -0.57333 -0.694302 0.435014 -0.573441 -0.66544 0.477865 -0.48879 -0.703929 0.515334 -0.346061 -0.858474 0.378504 -0.202131 -0.893771 0.400396 -0.202093 -0.865283 0.458741 -0.202092 -0.865283 0.458741 -0.202093 -0.829923 0.519987 -0.202097 -0.829923 0.519986 -0.202135 -0.793638 0.573829 -0.149353 -0.797835 0.584082 0.707096 0.540795 -0.455584 0.671181 0.594398 -0.442953 0.706465 0.566443 -0.424323 0.706465 0.612928 -0.353874 0.70647 0.612924 -0.353871 0.706521 0.649947 -0.279994 0.672813 0.680176 -0.291006 0.707108 0.664939 -0.24053 0.706467 -0.566441 0.424321 0.706475 -0.566434 0.424317 0.706476 -0.612918 0.353869 0.70647 -0.612924 0.353872 0.706469 -0.650692 0.27839 0.706479 -0.650683 0.278387 0.701815 -0.701811 0.122134 0.701813 -0.701813 0.122134 0.698064 -0.429798 0.572696 0.698066 -0.429796 0.572695 0.698067 -0.138749 0.702461 0.618517 -0.178118 0.765317 0.706901 -0.00301766 0.707306 0.698069 0.179777 0.693095 0.698069 0.179777 0.693095 0.698071 0.462694 0.546453 0.698066 0.462696 0.546458 0.698068 0.653973 0.291583 0.698063 0.635719 -0.329498 0.69807 0.635712 -0.329497 0.700605 0.712132 -0.0449608 0.63491 0.772252 -0.0227043 0.706904 0.698123 0.113627 0.698073 0.653969 0.291579 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.985193 0.17145 0 -0.985193 0.17145 0 0.84955 -0.527509 -0.0254467 0.887543 -0.460021 -0.00385986 0.938212 -0.34604 0.0105377 0.997957 -0.0630066 -0.00709827 0.994972 -0.0999015 0.00161459 0.987011 0.160647 0.020109 0.946351 0.322515 -0.019269 0.913162 0.407142 -0.00122729 0.832043 0.554711 0.00305351 0.73522 0.677821 -0.0539174 0.581368 0.811852 -0.0129091 0.64614 0.76311 0.000748752 0.472504 0.881328 0 -0.600246 0.799816 -0.00495657 -0.606435 0.795118 0.00438592 -0.226677 0.97396 -0.00778045 -0.247839 0.96877 5.76668e-06 -0.0521184 0.998641 4.72056e-07 -0.00426637 0.999991 0.000871544 0.00518588 0.999986 -0.00543779 0.25107 0.967954 -0.0432683 0.187113 0.981385 -0.00224385 0.379154 0.925331 0 -0.800346 0.599539 0 -0.800346 0.599539 0 -0.866025 0.500001 0 -0.866025 0.500001 0 -0.919389 0.393349 0 -0.919389 0.393349 0 0.919389 -0.39335 0 0.919389 -0.39335 0 0.866025 -0.5 0 0.866025 -0.5 0 0.800345 -0.599539 0 0.800345 -0.599539 0.87924 -0.459541 0.125535 0.105325 -0.939861 -0.324912 0.0900143 -0.0966468 -0.99124 0.0969642 0.158108 -0.982649 0.150378 0.17387 -0.973219 0.275089 -0.271858 -0.922182 0.143293 -0.209343 -0.967286 0.0794507 -0.383095 -0.920286 0.132819 -0.552019 -0.823186 0.18816 -0.534395 -0.824025 -0.0290994 -0.812422 -0.582343 0.204973 -0.841866 -0.499248 0.0559332 -0.693768 -0.718023 0.214351 -0.962349 -0.167149 0.147367 -0.974011 0.172007 0.169267 -0.972881 0.15764 0.887081 -0.458786 0.0510111 0.954992 -0.285021 -0.0821818 0.960102 -0.2653 -0.0884348 0.978436 -0.198164 -0.05826 0.978976 -0.195524 -0.0581027 0.991397 -0.130836 0.00378307 0.990797 -0.135348 0.00127413 0.965171 0.18011 -0.189753 0.793207 -0.0945553 -0.601566 0.859465 0.147705 -0.489391 0.839107 0.150362 -0.522772 0.884195 0.365189 -0.291268 0.876487 0.37218 -0.305374 0.859289 -0.373913 -0.349015 0.938545 -0.334264 -0.0860336 0.933186 -0.35213 -0.0718952 0.821645 -0.298604 -0.485526 0.847485 -0.221372 -0.482457 0.891281 -0.194744 -0.409503 0.947044 0.0001729 -0.321104 0.938319 0.00095155 -0.34577 0.970911 0.147727 -0.188438 0.989047 0.0715452 -0.1291 0.80734 -0.563505 -0.175113 0.693248 -0.549744 -0.466035 0.770723 -0.340439 -0.538598 0.902133 -0.43084 -0.0230675 0.887848 -0.456656 0.0564917 0.749541 -0.661897 -0.00903114 0.71013 -0.704059 0.00404524 0.0994224 0.347858 -0.932261 0.101533 0.549727 -0.829151 0.110145 0.551454 -0.826901 0.0964061 0.841846 -0.531039 0.105779 0.842783 -0.527757 0.35423 -0.79996 -0.484339 0.457115 -0.563083 -0.688465 0.363154 -0.604358 -0.709134 0.490825 -0.27317 -0.827326 0.397301 -0.306508 -0.864988 0.522594 0.0645721 -0.850133 0.44284 0.0477907 -0.895326 0.546618 0.408772 -0.730832 0.493395 0.409081 -0.767603 0.553367 0.689514 -0.467285 0.546245 0.691785 -0.472282 0.190644 -0.952661 -0.236836 0.276004 -0.798637 -0.53479 0.176398 -0.82905 -0.530622 0.302652 -0.54818 -0.77968 0.186352 -0.583982 -0.790088 0.32568 -0.222734 -0.91887 0.208472 -0.254811 -0.944251 0.343265 0.143624 -0.928192 0.241852 0.123317 -0.962445 0.35149 0.503627 -0.789186 0.28265 0.498079 -0.819772 0.345031 0.791883 -0.50386 0.333654 0.792962 -0.50979 0.879547 -0.458706 0.126437 0.763494 -0.628752 0.147474 0.693955 -0.710578 0.11621 0.651405 -0.743631 0.150611 0.484428 -0.859591 0.162582 0.918308 -0.391625 -0.0577972 0.901025 -0.430766 -0.0509489 0.758725 -0.596303 -0.26222 0.805303 -0.547056 -0.22851 0.700508 -0.628347 -0.338332 0.6338 -0.769789 -0.0756494 0.46112 -0.879322 -0.119006 0.425669 -0.89511 0.132609 0.341462 -0.926949 0.155465 0.149323 -0.98849 -0.0243141 0.172453 -0.964288 -0.201019 0.4241 -0.890769 -0.163308 0.48688 -0.787797 -0.377257 0.502649 -0.778309 -0.376269 0.601379 -0.558674 -0.571163 0.531872 -0.601583 -0.595996 0.642847 -0.313501 -0.698903 0.575094 -0.346742 -0.740971 0.685234 -0.0200388 -0.728048 0.62921 -0.0348514 -0.776454 0.721677 0.287692 -0.629616 0.685619 0.290624 -0.667432 0.739934 0.547498 -0.390824 0.725678 0.555119 -0.40649 0.14616 -0.602447 0.784663 0.826271 0.228733 0.51474 0.651437 -0.502268 0.568645 0.880894 -0.294343 0.37066 0.992268 -0.044201 0.115974 0.992327 -0.0815847 0.0929046 0.976265 -0.0381604 0.213192 0.978908 -0.0485422 0.198453 0.963204 -0.0549821 0.263087 0.942932 -0.0528935 0.328758 0.902135 -0.211907 0.375828 0.895801 -0.22227 0.384884 0.919327 -0.149579 0.363955 0.851017 -0.410402 0.327629 0.740543 0.046545 0.670395 0.783615 0.067698 0.617547 0.707954 -0.148616 0.690445 0.912305 -0.157561 0.377986 0.939733 -0.0982579 0.327486 0.785902 0.228432 0.57461 0.847488 0.307107 0.432955 0.793262 0.473673 0.382583 0.856964 0.497198 0.135677 0.844207 0.523844 0.113589 0.884162 0.438016 -0.162481 0.877672 0.445632 -0.176362 0.923008 -0.103748 0.37053 0.960832 -0.0760316 0.266499 0.891327 0.257212 0.373333 0.944822 0.277164 0.174618 0.94184 0.296164 0.158823 0.970919 0.237031 -0.0336486 0.965173 0.254389 -0.0610584 0.115155 0.933373 -0.339933 0.0770971 0.992498 -0.0948861 0.146469 0.987338 -0.0609092 0.0440332 0.944966 0.32419 0.0571109 0.942429 0.329494 0.0998397 0.822522 0.559902 0.181857 0.725299 0.66398 0.334012 0.835704 -0.43593 0.105774 0.878484 -0.465915 0.278922 0.81797 -0.503118 0.0122505 0.0940844 0.995489 0.31535 0.147804 0.937394 0.112589 -0.00323422 0.993636 0.136032 0.719495 0.681045 0.0636109 0.571625 0.818046 0.202843 0.424226 0.882546 0.24799 0.436655 0.864774 0.10876 0.367282 0.923729 0.084235 -0.0579284 0.994761 0.0328481 -0.24994 0.967704 0.190223 -0.305326 0.933055 0.0915701 -0.627706 0.773046 0.34146 -0.59817 0.724981 0.693992 -0.455932 0.557226 0.714749 -0.304528 0.6296 0.412199 -0.338775 0.845768 0.486913 -0.0670929 0.87087 0.354189 0.0195538 0.934969 0.44765 0.282043 0.848564 0.378511 0.341525 0.860285 0.48013 0.554488 0.679719 0.413093 0.618127 0.668785 0.514053 0.757182 0.40302 0.455171 0.808157 0.373767 0.542679 0.839121 0.0370941 0.499638 0.866218 0.00529429 0.553282 0.750969 -0.360449 0.546655 0.753119 -0.366035 0.34469 0.834922 -0.429062 0.288271 0.956354 -0.0478192 0.346237 0.938045 -0.013862 0.253715 0.905715 0.339571 0.33284 0.864552 0.376521 0.224038 0.715183 0.662057 0.313055 0.658168 0.684698 0.201548 0.424488 0.882716 0.291667 0.366876 0.883364 0.187844 0.0747698 0.979349 0.269293 0.0320535 0.962525 0.179213 -0.308319 0.93425 0.463857 -0.301223 0.833127 0.425708 -0.562432 0.708832 0.484448 -0.570636 0.663087 0.875351 -0.35004 0.333514 0.889583 -0.276392 0.36366 0.689707 -0.334228 0.642337 0.745683 -0.115743 0.656171 0.502636 -0.0632224 0.862183 0.593258 0.185338 0.783387 0.546279 0.241329 0.802085 0.633761 0.424752 0.646478 0.590002 0.487125 0.6439 0.67825 0.609118 0.411039 0.640949 0.661597 0.389196 0.718705 0.689671 0.0884155 0.691739 0.719588 0.0607479 0.739915 0.616196 -0.269868 0.727076 0.624331 -0.285606 0.572906 -0.709812 0.409811 0.850725 -0.420016 0.315997 0.879516 -0.437898 0.186273 0.654678 -0.694974 0.297337 0.765005 -0.592108 0.253327 0.845144 -0.490093 0.2134 0.851117 -0.469969 0.233941 0.8507 -0.455228 0.262827 0.850697 -0.455232 0.262828 0.851114 -0.437594 0.290027 0.345775 -0.862679 0.369086 0.488402 -0.802276 0.343243 0.149209 -0.909097 0.388946 0.201903 -0.899076 0.388457 0.201863 -0.848197 0.489707 0.844344 -0.428826 0.321234 0.654707 -0.604967 0.453181 0.573026 -0.658615 0.487717 0.488417 -0.698389 0.523165 0.345768 -0.75098 0.56256 0.573021 -0.751686 0.32652 0.572899 -0.709817 0.409813 0.201857 -0.848198 0.489708 0.201898 -0.785952 0.584394 0.149217 -0.791385 0.592827 0.340894 0.752406 -0.563628 0.994035 -0.0944506 0.0545309 0.994036 -0.087141 0.0655602 0.99425 -0.0857002 0.0641983 0.991754 -0.117931 0.0501654 0.996676 -0.0729344 0.0363043 0.658679 0.651619 -0.376212 0.931791 0.314362 -0.181497 0.994046 -0.0994073 0.0446274 0.993744 0.102679 -0.0439301 0.971836 0.216661 -0.0926959 0.994056 -0.0907454 0.0601499 0.994035 -0.0944504 0.0545308 0.93179 0.314365 -0.181498 0.931638 0.336607 -0.136916 0.558443 0.655449 -0.508457 0.739317 0.538919 -0.403704 0.931791 0.290521 -0.217629 0.88807 0.360857 -0.284806 0.971843 0.188586 -0.141271 0.237292 0.84129 -0.485719 0.237292 0.777486 -0.582416 0.108129 0.78682 -0.607637 0.887839 0.423061 -0.181002 0.739293 0.619101 -0.264875 0.658467 0.694533 -0.289907 0.558119 0.762873 -0.326386 0.340871 0.864327 -0.369792 0.658678 0.6022 -0.451109 0.658677 0.65162 -0.376212 0.237288 0.841291 -0.485719 0.237192 0.895748 -0.376 0.108051 0.914006 -0.391047 0.939517 -0.315174 0.134068 0.939602 -0.322726 0.114 0.939489 -0.323058 0.113988 0.939579 -0.322737 0.114157 0.939699 -0.32208 0.115024 0.939844 -0.322105 0.113763 0.939864 -0.322069 0.113703 0.939747 -0.32235 0.113865 0.939507 -0.273715 0.205928 0.939904 -0.259368 0.222056 0.939805 -0.25977 0.222005 0.93969 -0.260671 0.221436 0.939698 -0.260518 0.221581 0.939545 -0.260228 0.222566 0.939484 -0.260238 0.222812 0.939528 -0.260211 0.222658 0.939644 -0.260006 0.22241 0.939775 -0.25973 0.222177 0.939516 -0.273696 0.205914 0.939511 -0.273707 0.205921 0.939694 -0.285078 0.188962 0.939693 -0.285089 0.18895 0.939497 -0.296664 0.171279 0.939498 -0.296661 0.171278 0.939694 -0.306183 0.152407 0.939694 -0.306181 0.152411 0.939512 -0.315186 0.134075 0.939507 -0.315197 0.134079 0.939689 -0.322182 0.114815 -0.698079 -0.707465 0.110357 -0.698062 -0.707481 0.110365 -0.698061 -0.685305 -0.207529 -0.60932 -0.766194 -0.204149 -0.706899 -0.625818 -0.329614 -0.698067 -0.527392 -0.484314 -0.698072 -0.527387 -0.484312 -0.69807 -0.265023 -0.665178 -0.698074 -0.26502 -0.665175 -0.69807 0.0498326 -0.714293 -0.698066 0.0498316 -0.714297 -0.706899 0.227662 -0.669675 -0.698054 0.589537 -0.406408 -0.698082 0.589519 -0.406384 -0.700611 0.374244 -0.607525 -0.796085 0.349921 -0.493765 -0.684039 0.278764 -0.674078 -0.380722 0.912146 0.151793 -0.734326 0.655271 0.177159 -0.707058 0.707058 0.0117967 -0.705893 0.648975 0.283807 -0.703395 0.570554 0.423915 -0.500118 0.638278 0.585221 -0.70522 0.448252 0.549303 -0.704388 0.313658 0.636755 -0.492759 0.285282 0.822072 -0.696086 -0.437574 0.569205 -0.69609 -0.437572 0.569201 -0.703396 -0.185307 0.686218 -0.500111 -0.138549 0.854806 -0.70522 -0.0116202 0.708893 -0.704388 0.148209 0.694169 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706163 0.637137 -0.308852 -0.706187 0.637116 -0.308842 -0.706186 0.586024 -0.397338 -0.706178 0.58603 -0.397342 0 0.813937 -0.580953 -0.0420191 0.826955 -0.560696 0 0.853737 -0.520704 0 0.899849 -0.436201 -0.0629294 0.908285 -0.413592 0 0.877812 -0.479006 -0.706187 -0.637116 0.308842 -0.706185 -0.637117 0.308843 -0.706184 -0.586026 0.397339 -0.706174 -0.586034 0.397345 0.00948853 0.593479 0.804794 0.00154468 0.632242 0.77477 -0.0020783 0.45041 0.89282 2.06107e-05 0.441886 0.897071 -8.69238e-06 0.222439 0.974947 0.00278623 0.208798 0.977955 -0.00262463 -0.00257852 0.999993 2.27786e-05 -0.0163898 0.999866 -2.57237e-05 -0.243861 0.96981 0.00416404 -0.2607 0.965411 -0.00144414 -0.422582 0.906323 0.0172871 -0.609378 0.792691 0.0118256 -0.620651 0.783998 0 -0.766188 0.642617 1.05785e-05 0.665256 0.746615 4.43618e-09 0.802693 0.596392 -0.000788686 0.804609 0.593805 0.000436339 0.916219 0.400677 -0.0126632 0.95168 0.30683 0.0104826 0.98638 0.164146 0 0.997786 0.0665001 0 0.865341 -0.501183 0.0178456 0.823192 -0.567482 0.00272435 0.746967 -0.664856 -0.0073393 0.524472 -0.851396 0.00493592 0.555624 -0.831419 -0.00112484 0.321867 -0.946784 -0.0112955 0.194398 -0.980858 0.018963 0.0695814 -0.997396 0.0048711 -0.0385282 -0.999246 -0.00685937 -0.228829 -0.973442 0.0389253 -0.452886 -0.890718 0.00575401 -0.370121 -0.928966 -0.00032008 -0.564018 -0.825763 0 -0.98805 0.154134 0.00764703 -0.985119 0.171705 -0.00712223 -0.966264 -0.257456 0.00552934 -0.974007 -0.22645 -2.76574e-06 -0.906024 -0.423227 1.66961e-06 -0.884781 -0.466007 1.56672e-07 -0.88477 -0.466029 -6.80295e-05 -0.736546 -0.676388 0.0308525 -0.784957 -0.618781 0.00153254 -0.638716 -0.769441 0 0.850115 0.526596 0.0110649 0.862214 0.506423 -0.00122507 0.721944 0.69195 0.00871754 0.576997 0.816699 -0.0162825 0.522832 0.85228 0.00109503 0.362971 0.9318 -0.000331703 0.311874 0.950123 0.00358946 0.176515 0.984291 -0.0321396 0.060711 0.997638 0.00116111 -0.0718864 0.997412 -0.000939381 -0.259484 0.965747 -0.0315931 -0.394176 0.918492 0.00434534 -0.482049 0.876134 -0.00032896 -0.614498 0.788918 0.00692899 -0.780103 0.625613 0.0105259 -0.783977 0.6207 -0.00965724 -0.96982 0.24363 -0.017112 -0.972818 0.230938 0 -0.999553 0.0298823 0 -0.919389 -0.393349 0 -0.919389 -0.393349 0 -0.866025 -0.500001 0 -0.866025 -0.500001 0 -0.800346 -0.599539 0 -0.800346 -0.599539 0 0.800345 0.599539 0 0.800345 0.599539 0 0.866025 0.5 0 0.866025 0.5 0 0.919389 0.39335 0 0.919389 0.39335 0.87924 -0.338483 -0.33521 0.887082 -0.273584 -0.371802 0.954993 -0.0713336 -0.287923 0.960101 -0.0560634 -0.273976 0.978436 -0.0486275 -0.200746 0.978976 -0.0474432 -0.19838 0.991397 -0.0686937 -0.111417 0.990797 -0.0687771 -0.11658 0.96517 0.254386 0.0611039 0.793205 0.473697 -0.382671 0.859465 0.497677 -0.116779 0.839107 0.527916 -0.131169 0.884192 0.434846 0.170631 0.876485 0.450555 0.169632 0.859293 0.11529 -0.498321 0.938544 -0.0926214 -0.3325 0.933187 -0.113793 -0.340901 0.821646 0.271179 -0.501358 0.847483 0.307134 -0.432944 0.891284 0.257264 -0.373401 0.947045 0.278168 -0.160402 0.938318 0.299924 -0.172063 0.970911 0.237056 0.0337153 0.98905 0.147558 -0.00259745 0.807335 -0.130096 -0.575574 0.693241 0.128731 -0.709116 0.770719 0.296226 -0.56413 0.902133 -0.195434 -0.384658 0.887846 -0.277251 -0.367234 0.749546 -0.323124 -0.577731 0.710136 -0.355529 -0.607705 0.275998 0.0638114 -0.959038 0.145874 -0.494095 -0.857083 0.19782 -0.620249 -0.759051 0.147942 -0.654677 -0.741291 0.111229 0.99173 0.0640364 0.095387 0.881072 0.463264 0.105775 0.878448 0.465984 0.0780724 0.84396 -0.530694 0.143606 0.925352 -0.350859 0.17764 0.924463 -0.337361 0.0973132 0.979484 -0.176472 0.110876 0.991776 0.0639288 0.0290676 -0.263441 -0.964238 0.134962 0.148005 -0.979735 -0.13055 0.10749 -0.985598 0.156266 0.391592 -0.906773 0.216097 0.421158 -0.880868 0.0505964 0.54259 -0.838473 0.143381 0.733008 -0.664937 0.273432 0.663762 -0.696172 0.142381 0.774845 -0.615909 0.354226 0.0194649 -0.934957 0.457115 0.314683 -0.831878 0.363172 0.311946 -0.877949 0.490831 0.579897 -0.650234 0.397304 0.595845 -0.697939 0.522601 0.768521 -0.36914 0.442833 0.799274 -0.406276 0.546607 0.837311 -0.0114116 0.493395 0.869304 -0.0295262 0.553364 0.749439 0.363497 0.546235 0.754906 0.362965 0.176415 0.0449985 -0.983287 0.302665 0.401135 -0.864572 0.186336 0.392246 -0.90079 0.32568 0.6844 -0.652326 0.208459 0.690343 -0.6928 0.343249 0.875655 -0.339718 0.24186 0.895161 -0.374421 0.351506 0.935263 0.041564 0.282645 0.958985 0.0214592 0.345022 0.832304 0.433855 0.333669 0.837967 0.431828 0.879549 -0.33885 -0.334027 0.763484 -0.442102 -0.470785 0.693959 -0.455938 -0.557262 0.65141 -0.502256 -0.568686 0.484447 -0.570601 -0.663118 0.9183 -0.145768 -0.368072 0.901024 -0.171257 -0.398531 0.758735 -0.0710662 -0.647512 0.805307 -0.0756357 -0.588013 0.700506 -0.0211698 -0.713333 0.633799 -0.319372 -0.704485 0.461112 -0.33659 -0.821025 0.425659 -0.5624 -0.708887 0.341458 -0.59811 -0.725031 0.172218 -0.310088 -0.934979 0.179193 -0.308216 -0.934287 0.424094 -0.303948 -0.853089 0.486873 -0.067187 -0.870885 0.502658 -0.0632947 -0.862165 0.601382 0.215307 -0.769404 0.531867 0.215359 -0.818986 0.642844 0.448518 -0.620954 0.575099 0.468327 -0.67077 0.685236 0.620486 -0.381378 0.629213 0.655 -0.418409 0.721677 0.689109 -0.0656584 0.685621 0.723322 -0.0820268 0.739939 0.612208 0.278732 0.725682 0.629587 0.277499 0.14894 -0.955696 -0.253892 0.826268 -0.331413 0.455464 0.651421 -0.743607 -0.15066 0.880893 -0.468173 -0.0695792 0.992268 -0.122537 0.0197062 0.992327 -0.12125 -0.0242011 0.976265 -0.203708 0.0735485 0.978908 -0.196133 0.0571855 0.963202 -0.25534 0.0839307 0.942935 -0.311153 0.118565 0.902136 -0.43143 0.00439908 0.895803 -0.444451 -4.67706e-05 0.919325 -0.389989 0.0524331 0.851018 -0.488934 -0.191601 0.740533 -0.557317 0.375512 0.783617 -0.500958 0.367405 0.707955 -0.67225 0.216518 0.912308 -0.406122 0.0525352 0.939734 -0.332739 0.0786442 0.785898 -0.383412 0.485138 0.847486 -0.221395 0.482444 0.793259 -0.0944907 0.601508 0.856963 0.131102 0.498425 0.844208 0.163549 0.510455 0.884163 0.359721 0.298088 0.877675 0.375546 0.297744 0.922993 -0.372798 0.0954264 0.960832 -0.268811 0.0674046 0.891325 -0.19471 0.409424 0.944822 -0.0126387 0.327339 0.941841 0.0105364 0.335895 0.97092 0.147656 0.188449 0.965173 0.180073 0.189776 0.0641093 -0.0777134 0.994912 0.216848 -0.215218 0.952186 0.144757 0.162713 0.975997 0.171056 0.171124 0.970287 0.0910138 0.355184 0.930355 0.146478 0.546419 0.824603 0.0953887 0.570346 0.815847 0.105838 0.844182 0.525504 0.113084 0.841949 0.527574 0.333999 0.795385 0.505774 0.14932 -0.988493 0.0242041 0.172198 -0.964785 0.198841 0.0697312 -0.968548 0.238857 0.0815765 -0.816447 0.57163 -0.0806669 -0.776729 0.624648 0.19157 -0.552307 0.811331 0.03797 -0.484566 0.87393 0.12213 -0.26921 0.955306 0.34149 -0.926926 -0.155542 0.169142 -0.97289 -0.15772 0.269516 -0.958834 -0.0894395 0.693992 -0.710539 -0.116229 0.714748 -0.697514 0.051076 0.412199 -0.901843 0.129501 0.48691 -0.787748 0.377322 0.354176 -0.799938 0.484417 0.447645 -0.59385 0.668548 0.378525 -0.574264 0.725906 0.480139 -0.311411 0.820055 0.413101 -0.270122 0.869702 0.51406 0.029565 0.857244 0.455184 0.0803825 0.886761 0.542693 0.387426 0.745242 0.499642 0.428524 0.752812 0.553286 0.687643 0.47013 0.546666 0.693548 0.469199 0.344685 0.789042 0.508533 0.288264 0.519593 0.804317 0.346232 0.48103 0.80544 0.253711 0.158781 0.954159 0.332839 0.106198 0.936984 0.224033 -0.215769 0.950396 0.313044 -0.263881 0.912343 0.20153 -0.552213 0.808979 0.291643 -0.581579 0.759414 0.187818 -0.810757 0.554435 0.269295 -0.817548 0.509014 0.179217 -0.96324 0.200125 0.463866 -0.872115 0.155706 0.425713 -0.895079 -0.132673 0.484446 -0.859569 -0.162646 0.875356 -0.463847 -0.136375 0.889586 -0.453131 -0.0575301 0.689707 -0.723393 0.0317241 0.745681 -0.626135 0.227848 0.502651 -0.778279 0.376329 0.593271 -0.585754 0.552197 0.546289 -0.573952 0.610038 0.633764 -0.347491 0.691082 0.590005 -0.314071 0.74381 0.678251 -0.0514147 0.733029 0.640945 -0.00625314 0.767561 0.718698 0.268269 0.641487 0.691733 0.307185 0.653561 0.739911 0.541815 0.398709 0.72707 0.559515 0.397885 0.572899 -0.709816 -0.409814 0.850727 -0.483666 -0.205745 0.879516 -0.380266 -0.286094 0.654681 -0.604985 -0.453195 0.764995 -0.515452 -0.386125 0.845141 -0.429861 -0.317736 0.851115 -0.437588 -0.290033 0.850697 -0.455231 -0.262828 0.8507 -0.455228 -0.262826 0.851117 -0.469965 -0.23395 0.345763 -0.750981 -0.562561 0.48842 -0.698388 -0.523164 0.149213 -0.791386 -0.592827 0.201898 -0.785952 -0.584394 0.201857 -0.848198 -0.489708 0.844348 -0.492604 -0.210755 0.65469 -0.694963 -0.297332 0.573021 -0.751686 -0.32652 0.488416 -0.802269 -0.34324 0.345794 -0.862673 -0.369083 0.573026 -0.658614 -0.487717 0.572906 -0.709813 -0.409811 0.201863 -0.848197 -0.489707 0.201903 -0.899075 -0.388457 0.149207 -0.909097 -0.388946 0.34088 0.864324 0.36979 0.994035 -0.0944504 -0.0545308 0.994036 -0.100348 -0.0426864 0.994251 -0.0984458 -0.042119 0.991754 -0.102411 -0.0770492 0.996675 -0.0679148 -0.0450176 0.658677 0.65162 0.376213 0.93179 0.314365 0.181499 0.994046 -0.0883518 -0.0637754 0.993746 0.0893711 0.0669482 0.971836 0.188607 0.141286 0.994056 -0.0974616 -0.0485184 0.994035 -0.0944506 -0.0545309 0.931791 0.314362 0.181497 0.93164 0.286873 0.22305 0.558454 0.768054 0.313405 0.739311 0.619084 0.264868 0.93179 0.333736 0.142785 0.888072 0.427073 0.170108 0.971843 0.216636 0.0926854 0.237289 0.841291 0.48572 0.237289 0.89313 0.382116 0.10813 0.919638 0.377589 0.887837 0.368286 0.275883 0.739296 0.538937 0.403718 0.658466 0.598334 0.45653 0.558109 0.6641 0.497479 0.340888 0.752407 0.56363 0.658679 0.691771 0.295966 0.658679 0.651619 0.376212 0.237293 0.84129 0.485719 0.237195 0.773498 0.587741 0.108045 0.79566 0.59603 0.939516 -0.273695 -0.205916 0.939604 -0.260088 -0.222481 0.93949 -0.260247 -0.22278 0.939579 -0.260233 -0.22242 0.939698 -0.260654 -0.22142 0.939841 -0.259588 -0.222065 0.939864 -0.259505 -0.222064 0.939746 -0.259791 -0.222229 0.939507 -0.315196 -0.13408 0.939904 -0.321992 -0.113588 0.939804 -0.32215 -0.113964 0.93969 -0.322107 -0.115022 0.939699 -0.322152 -0.114824 0.939546 -0.322859 -0.114082 0.939481 -0.323093 -0.113959 0.939531 -0.322926 -0.114019 0.939633 -0.322645 -0.113972 0.939776 -0.322275 -0.113839 0.939516 -0.315173 -0.13407 0.939511 -0.315187 -0.134077 0.939693 -0.306177 -0.152421 0.939694 -0.306178 -0.152416 0.939498 -0.296662 -0.171277 0.939497 -0.296664 -0.171279 0.939692 -0.285079 -0.188966 0.939693 -0.285084 -0.188954 0.939511 -0.273706 -0.205923 0.939507 -0.273713 -0.205929 0.93969 -0.260519 -0.221615 0 -0.985193 -0.17145 -0.0420539 -0.966035 -0.254966 0 -0.996302 -0.0859197 0.701813 -0.701813 -0.122135 0.701815 -0.701811 -0.122133 -1.45397e-05 0.665617 -0.746293 -0.0038351 0.904337 -0.426803 0.0244233 0.973562 -0.227115 0.0191981 0.969385 -0.244793 0.00409277 0.994493 -0.104723 0 0.999251 -0.038699 -1.68043e-05 0.802693 -0.596392 0.0168012 0.759734 -0.650017 0.00328693 0.829265 -0.558846 0.0171992 0.530399 -0.847574 -0.0204511 0.63211 -0.774609 0.0146004 0.381446 -0.924276 2.71193e-06 0.441886 -0.897071 -2.44724e-05 0.208799 -0.977959 -0.0146653 0.143408 -0.989555 0.0045772 -0.0163896 -0.999855 0.000652719 -0.0719331 -0.997409 -0.0031422 -0.291476 -0.956573 -0.0144036 -0.260676 -0.965319 0.0160276 -0.609391 -0.792708 0 -0.641419 -0.767191 -0.696086 -0.437575 -0.569204 -0.492759 0.285282 -0.822072 -0.69609 -0.437571 -0.569201 -0.703396 -0.185307 -0.686218 -0.500111 -0.138549 -0.854806 -0.70522 -0.0116202 -0.708893 -0.704389 0.148209 -0.694169 -0.704388 0.313658 -0.636755 -0.70522 0.448252 -0.549303 -0.500118 0.638278 -0.585221 -0.703395 0.570554 -0.423915 -0.697545 0.691706 -0.18701 -0.73323 0.659284 -0.166485 -0.707058 0.707058 -0.0117968 -0.70213 0.624528 0.34202 -0.702133 0.624525 0.34202 -0.702132 0.70214 0.118369 -0.702136 0.702136 0.11837 -0.458494 -0.104048 0.882586 -0.694727 0.576518 0.430094 -0.694736 0.576509 0.430091 -0.705697 0.387772 0.59298 -0.754937 0.322838 0.570829 -0.624886 0.243612 0.741735 -0.705014 0.177456 0.686633 -0.703697 0.00431374 0.710487 -0.704399 -0.179546 0.68672 -0.7044 -0.341897 0.622035 -0.458499 -0.531401 0.712314 -0.694753 -0.714302 -0.0842103 -0.694741 -0.714314 -0.0842085 -0.702916 -0.679966 0.208697 -0.466774 -0.812396 0.349477 -0.705003 -0.601039 0.376462 -0.703688 -0.491726 0.512863 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 0.58603 0.397343 -0.706185 0.586024 0.397338 -0.706187 0.637116 0.308842 -0.706163 0.637137 0.308853 0 0.910089 0.414413 -0.0420195 0.899054 0.435816 0 0.877812 0.479006 0 0.827686 0.561191 -0.062929 0.812324 0.579801 0 0.853737 0.520704 -0.706174 -0.586034 -0.397344 -0.706184 -0.586025 -0.397339 -0.706185 -0.637117 -0.308843 -0.706187 -0.637116 -0.308842 0 0.801526 0.59796 0 -0.972921 -0.231137 0.0323207 -0.992604 -0.11702 0.0129652 -0.999484 -0.0293769 -0.0156198 -0.975135 0.221061 0.0036927 -0.955979 0.293412 -0.0032582 -0.847479 0.53082 -0.0251503 -0.792293 0.609622 3.35147e-05 -0.252952 0.967479 -4.13922e-05 -0.503399 0.864054 -0.0066191 -0.481668 0.876329 0.00507083 -0.692067 0.721815 0.0225884 0.833564 0.551961 -0.013391 0.538879 0.842277 -1.47279e-05 0.492283 0.870435 4.03469e-07 0.321942 0.94676 0.00403966 0.25022 0.968181 -0.00869072 0.147301 0.989054 0.00792471 0.00607122 0.99995 -0.00305004 -0.0917893 0.995774 0.00554972 -0.278028 0.960557 0 0.877689 0.479231 -0.00032932 0.877086 0.480333 7.8225e-05 0.956116 0.29299 0.00727114 0.98606 0.166233 0 0.991333 0.131372 -0.994042 -0.0887153 -0.0633211 -0.971841 0.191795 0.136895 -0.658919 0.651436 0.376107 -0.108084 0.904757 0.411986 -0.558303 0.755044 0.343812 -0.341053 0.855524 0.389566 -0.237328 0.887511 0.394968 -0.237624 0.852669 0.465286 -0.153985 0.855696 0.494037 -0.237621 0.829285 0.50579 -0.237426 0.790663 0.564341 -0.887887 0.418697 0.190656 -0.739467 0.612665 0.27898 -0.108174 0.798398 0.592334 -0.341049 0.765138 0.546122 -0.658919 0.612255 0.437 -0.558599 0.66478 0.496019 -0.739474 0.547931 0.391089 -0.971844 0.214438 0.0976457 -0.931696 0.333884 0.143051 -0.931861 0.314208 0.181408 -0.658695 0.688175 0.304197 -0.658917 0.651438 0.376108 -0.931861 0.314207 0.181407 -0.931861 0.295308 0.210778 -0.88809 0.365507 0.278749 -0.994042 -0.0991948 -0.045169 -0.994042 -0.0991949 -0.045169 -0.994053 -0.0955949 -0.0521641 -0.994978 -0.0866848 -0.0500474 -0.994053 -0.0929733 -0.0567048 -0.994042 -0.0887149 -0.0633209 0 -0.806886 -0.590708 0.0635005 -0.826016 -0.560058 0 -0.847408 -0.530942 0 -0.899849 -0.436202 0.126159 -0.9077 -0.400206 0 -0.883514 -0.468406 -0.0684631 -0.0993229 0.992697 -0.0983885 0.31153 0.945129 -0.738157 -0.652334 0.172004 -0.933087 -0.354425 0.0610861 -0.8858 -0.457609 -0.0771515 -0.902766 -0.429905 -0.013986 -0.900878 -0.4339 0.0122511 -0.89372 -0.446679 -0.0417383 -0.982603 -0.178707 0.050541 -0.968983 -0.23771 0.0675697 -0.959181 -0.270876 0.081232 -0.978164 -0.202312 0.0475843 -0.993506 -0.11271 -0.0155896 -0.993503 -0.113429 -0.00928195 -0.955078 -0.287103 0.0734737 -0.937213 -0.340381 0.0759735 -0.812788 -0.3938 0.429299 -0.75974 -0.531137 0.375085 -0.532645 -0.619402 0.576741 -0.600347 -0.580084 0.550532 -0.364105 -0.625846 0.689743 -0.456009 -0.58878 0.667379 -0.187435 -0.608124 0.771397 -0.14551 -0.988713 -0.0356735 -0.172307 -0.970696 0.167511 -0.884952 -0.460108 -0.0718386 -0.712671 -0.701497 0.0014602 -0.697729 -0.715713 0.0304758 -0.461108 -0.882679 0.0908678 -0.423354 -0.896424 0.131133 -0.179711 -0.969161 0.168616 -0.275291 -0.817941 0.50516 -0.918217 -0.39344 0.045634 -0.916086 -0.398458 0.0449132 -0.771357 -0.549885 0.320366 -0.722806 -0.654905 0.220569 -0.503359 -0.789357 0.351491 -0.487233 -0.798689 0.353129 -0.353634 -0.816622 0.456149 -0.177307 -0.84528 0.504048 -0.301514 -0.577299 0.758825 -0.274906 -0.300313 0.913367 -0.87643 0.361568 0.318023 -0.884046 0.354537 0.304576 -0.7257 0.540971 0.425099 -0.739821 0.533354 0.410121 -0.546212 0.675191 0.495752 -0.553287 0.672914 0.490979 -0.333632 0.774769 0.53705 -0.344988 0.773628 0.531492 -0.105757 0.824275 0.556225 -0.121706 0.825531 0.551078 -0.145528 0.13116 0.980622 -0.171014 0.137721 0.975596 -0.342321 0.108587 0.933288 -0.242327 0.0923923 0.965785 -0.521632 0.0325063 0.852551 -0.443216 0.0189489 0.896215 -0.684276 -0.0476255 0.727666 -0.629471 -0.0598196 0.774718 -0.792142 -0.116817 0.599054 -0.839075 0.132878 0.527538 -0.858962 0.129343 0.495433 -0.68563 0.268183 0.676749 -0.721167 0.264274 0.640373 -0.493425 0.383256 0.780799 -0.546165 0.381681 0.74567 -0.282723 0.470576 0.835839 -0.35108 0.474387 0.807279 -0.0853882 0.526646 0.845785 -0.106827 0.530097 0.841181 -0.147947 -0.961605 -0.231143 -0.205596 -0.959941 -0.190377 -0.34139 -0.921021 -0.187544 -0.425001 -0.88979 -0.166275 -0.484359 -0.853639 -0.191566 -0.687664 -0.705423 -0.171746 -0.647374 -0.750643 -0.132066 -0.870211 -0.447876 -0.20528 -0.850008 -0.505919 -0.146741 -0.0290112 -0.975048 0.220089 -0.135867 -0.792292 0.594822 0.182426 -0.805892 0.563258 -0.290375 -0.511983 0.808428 -0.013119 -0.570367 0.821285 -0.143534 -0.241813 0.959648 -0.324425 -0.257552 0.910173 -0.209391 -0.284135 0.93564 -0.489604 -0.30448 0.817056 -0.398074 -0.333328 0.854652 -0.641643 -0.340081 0.687488 -0.575725 -0.369542 0.729369 -0.805194 -0.355373 0.474735 -0.849342 -0.229872 0.475159 -0.891409 -0.207566 0.402873 -0.946585 -0.0121348 0.322226 -0.938296 -0.0104778 0.345675 -0.97139 0.152029 0.182453 -0.963017 0.166702 0.211681 -0.146451 -0.637307 -0.756566 -0.112064 0.951573 0.286269 -0.824708 0.208444 -0.525745 -0.651392 -0.521828 -0.550803 -0.942263 -0.060238 -0.32941 -0.971801 -0.0646746 -0.22676 -0.978816 -0.0486812 -0.19887 -0.989309 -0.0737237 -0.125824 -0.993672 -0.0682229 -0.0892252 -0.851107 -0.414873 -0.32171 -0.873461 -0.322053 -0.365167 -0.889404 -0.276159 -0.364277 -0.901406 -0.226604 -0.368942 -0.895308 -0.235437 -0.378145 -0.91823 -0.163938 -0.360525 -0.741733 0.027118 -0.670147 -0.782194 0.0432171 -0.621534 -0.708894 -0.168694 -0.684845 -0.91196 -0.169854 -0.373469 -0.938588 -0.110928 -0.326723 -0.786961 0.211129 -0.579756 -0.849347 0.296569 -0.436643 -0.792186 0.460396 -0.400596 -0.856722 0.492748 -0.152403 -0.843571 0.520259 -0.133111 -0.884012 0.443602 0.147449 -0.877484 0.45206 0.160199 -0.92189 -0.113047 -0.370594 -0.959989 -0.0903912 -0.265049 -0.891441 0.245105 -0.381126 -0.944653 0.271735 -0.183824 -0.941309 0.291333 -0.17048 -0.970892 0.23797 0.0271985 -0.965064 0.256838 0.0518165 -0.177517 0.702939 -0.688741 -0.11143 0.987202 -0.114085 -0.0785656 0.96851 -0.236254 -0.233482 0.898701 -0.371244 -0.102314 0.894863 -0.434457 -0.0894611 0.819767 -0.565667 -0.0726573 0.996768 0.0342643 -0.351205 0.930866 0.100719 -0.155327 0.986555 -0.0508257 -0.333933 0.850558 0.40625 -0.105769 0.893874 0.435662 -0.233608 0.855742 0.461664 0.0904608 0.0747344 -0.993092 -0.249954 0.114003 -0.961523 -0.280974 0.705226 -0.65093 -0.113653 0.650764 -0.750725 -0.0130972 0.426417 -0.904432 -0.402993 0.441197 -0.801837 -0.151403 0.358866 -0.921028 -0.0873974 -0.079591 -0.992989 -0.0301099 -0.293144 -0.955594 -0.178508 -0.33895 -0.923714 -0.112034 -0.65239 -0.749557 -0.341451 -0.622956 -0.703802 -0.692764 -0.47966 -0.538521 -0.714399 -0.327701 -0.618261 -0.412915 -0.365046 -0.834412 -0.487266 -0.0934224 -0.868242 -0.353599 -0.013182 -0.935304 -0.44758 0.254016 -0.857408 -0.377659 0.311107 -0.872116 -0.480017 0.531758 -0.697723 -0.412119 0.594167 -0.690741 -0.513932 0.743318 -0.428197 -0.454267 0.794568 -0.402869 -0.542568 0.837448 -0.0655779 -0.499062 0.865796 -0.0365274 -0.553201 0.762951 0.334477 -0.546581 0.76542 0.339679 -0.344662 0.849336 0.399795 -0.287812 0.957591 0.0135732 -0.346268 0.937963 -0.0180067 -0.25301 0.89316 -0.371821 -0.332867 0.851377 -0.405409 -0.223309 0.691375 -0.68712 -0.313052 0.63493 -0.706302 -0.200944 0.393269 -0.897196 -0.291656 0.337285 -0.895084 -0.187451 0.0405015 -0.981439 -0.269278 -1.69863e-05 -0.963063 -0.179707 -0.33867 -0.923585 -0.463504 -0.331763 -0.821643 -0.425025 -0.588925 -0.687401 -0.484361 -0.592755 -0.643456 -0.870906 -0.371031 -0.322271 -0.892971 -0.287821 -0.346067 -0.69017 -0.353771 -0.631277 -0.744777 -0.141105 -0.652224 -0.503287 -0.0902029 -0.859399 -0.593142 0.159921 -0.789055 -0.545224 0.213007 -0.810777 -0.633578 0.403531 -0.660107 -0.588804 0.464243 -0.661656 -0.677985 0.595346 -0.431162 -0.639892 0.647746 -0.413477 -0.718482 0.686508 -0.111758 -0.691092 0.717513 -0.0869935 -0.739778 0.62517 0.248778 -0.726937 0.634194 0.263364 -0.939621 -0.27613 -0.202151 -0.939564 -0.311589 -0.141884 -0.938408 -0.321034 -0.127777 -0.939691 -0.318323 -0.125105 -0.939426 -0.319337 -0.12451 -0.93941 -0.319395 -0.124483 -0.93989 -0.318072 -0.124248 -0.939978 -0.317942 -0.123909 -0.939937 -0.318013 -0.124039 -0.939765 -0.318423 -0.124292 -0.939573 -0.318913 -0.124488 -0.939632 -0.267136 -0.213845 -0.939833 -0.266703 -0.213503 -0.940955 -0.265706 -0.209772 -0.939692 -0.267534 -0.213086 -0.93996 -0.266359 -0.213373 -0.939978 -0.266287 -0.213384 -0.939692 -0.267831 -0.212707 -0.939471 -0.267459 -0.214149 -0.939449 -0.267475 -0.214225 -0.939565 -0.278667 -0.198901 -0.94337 -0.269004 -0.194139 -0.936007 -0.300501 -0.183277 -0.939622 -0.289996 -0.181696 -0.93966 -0.300308 -0.163872 -0.937285 -0.30796 -0.16327 -0.94337 -0.302631 -0.135894 -0.939622 -0.31313 -0.138059 -0.939693 -0.318123 -0.125596 -0.149349 -0.797836 -0.584082 -0.488794 -0.703927 -0.515332 -0.346038 -0.858481 -0.378507 -0.655064 -0.691358 -0.304819 -0.85096 -0.480593 -0.211893 -0.850963 -0.480587 -0.211891 -0.850963 -0.464044 -0.246019 -0.850964 -0.464041 -0.246018 -0.850964 -0.445078 -0.278864 -0.850959 -0.445086 -0.278867 -0.850959 -0.423802 -0.310258 -0.850963 -0.423797 -0.310256 -0.655064 -0.609662 -0.446323 -0.573441 -0.66544 -0.477865 -0.57333 -0.694302 -0.435015 -0.573324 -0.694306 -0.435016 -0.573324 -0.723888 -0.383779 -0.573319 -0.723891 -0.38378 -0.57343 -0.746571 -0.337358 -0.488795 -0.798254 -0.351953 -0.346093 -0.757021 -0.554202 -0.202132 -0.793639 -0.573829 -0.202094 -0.829923 -0.519987 -0.202093 -0.829923 -0.519987 -0.202092 -0.865284 -0.458741 -0.202094 -0.865283 -0.458741 -0.202132 -0.893771 -0.400396 -0.149349 -0.904749 -0.398904 0.707108 0.664939 0.24053 0.671179 0.680809 0.293289 0.706469 0.650691 0.278391 0.70647 0.612924 0.353872 0.706464 0.612929 0.353874 0.706516 0.567459 0.422877 0.672814 0.592105 0.443546 0.707096 0.540795 0.455584 0.706479 -0.650683 -0.278387 0.706469 -0.650692 -0.278391 0.706469 -0.612924 -0.353872 0.706476 -0.612918 -0.353869 0.706475 -0.566435 -0.424316 0.706467 -0.566441 -0.424322 0.694737 0.650513 0.306878 0.487531 0.71743 -0.497602 0.694747 0.650505 0.30687 0.70292 0.711035 0.0182441 0.494627 0.866127 -0.0718856 0.705023 0.689502 -0.165922 0.703704 0.62922 -0.329974 0.704397 0.521874 -0.481117 0.704398 0.388499 -0.594047 0.487519 0.372517 -0.789656 0.694736 -0.409922 -0.59102 0.694746 -0.409919 -0.591011 0.702919 -0.135215 -0.698299 0.494627 -0.0718882 -0.866127 0.705018 0.0499777 -0.707426 0.7037 0.221723 -0.675015 0.69735 -0.69735 0.165544 0.697352 -0.697349 0.165544 0.697349 -0.548532 0.46132 0.64233 -0.597907 0.479499 0.707005 -0.434579 0.55793 0.697343 -0.282664 0.658645 0.697352 -0.282658 0.658639 0.697342 0.0435347 0.715415 0.697347 0.0435361 0.71541 0.70701 0.220558 0.671931 0.650503 0.38195 0.656476 0.7009 0.61502 0.361233 0.607893 0.665169 0.433608 0.706721 0.51077 0.48955 0.699225 0.373823 0.609378 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.904416 0.426651 0 -0.660357 -0.750952 -0.0478507 -0.569266 -0.82076 -0.0190468 -0.494505 -0.868966 0.0231306 -0.263164 -0.964474 -0.00911407 0.312054 -0.950021 0.0343657 0.157736 -0.986883 0.00482467 0.0704707 -0.997502 -0.00546051 -0.190101 -0.981749 -0.00780539 0.735211 -0.677793 -1.73687e-05 0.710012 -0.704189 2.4469e-05 0.547332 -0.836916 -1.37323e-05 0.547435 -0.836848 -9.71501e-06 0.410144 -0.912021 -0.0167032 0.985522 -0.168721 0.0109688 0.939017 -0.343695 -0.0114758 0.885551 -0.4644 2.31707e-05 0.850439 -0.526073 1.64905e-05 0.791392 -0.611308 -0.0265333 0.883576 0.467535 0.0157187 0.997428 0.0699279 1.67929e-05 0.999671 0.02565 -7.89713e-06 0.972246 -0.233961 0 1 0 0 -1 0 0.113602 0 -0.993526 0.113602 0 -0.993526 -0.113602 0 -0.993526 -0.113602 0 -0.993526 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 1 0 0.113602 0 -0.993526 0.113602 0 -0.993526 -0.113602 0 -0.993526 -0.113602 0 -0.993526 0 1 0 0 -1 0 0.113602 0 -0.993526 0.113602 0 -0.993526 -0.113602 0 -0.993526 -0.113602 0 -0.993526 0 -1 0 0 1 0 0.113602 0 -0.993526 0.113602 0 -0.993526 -0.113602 0 -0.993526 -0.113602 0 -0.993526 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.821426 0 0.570316 0.821426 0 0.570316 0.463507 0 0.886093 0.463507 0 0.886093 0 0 1 0 0 1 -0.463512 0 0.886091 -0.463512 0 0.886091 -0.82142 0 0.570324 -0.82142 0 0.570324 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.82142 0 0.570324 -0.82142 0 0.570324 -0.463512 0 0.886091 -0.463512 0 0.886091 0 0 1 0 0 1 0.463507 0 0.886093 0.463507 0 0.886093 0.821426 0 0.570316 0.821426 0 0.570316 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.82142 0 0.570324 0.82142 0 0.570324 0.463512 0 0.886091 0.463512 0 0.886091 0 0 1 0 0 1 -0.463512 0 0.886091 -0.463512 0 0.886091 -0.82142 0 0.570324 -0.82142 0 0.570324 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.82142 0 0.570324 -0.82142 0 0.570324 -0.463512 0 0.886091 -0.463512 0 0.886091 0 0 1 0 0 1 0.463512 0 0.886091 0.463512 0 0.886091 0.82142 0 0.570324 0.82142 0 0.570324 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.258812 -0.965928 0 -0.258812 -0.965928 0 -0.7071 -0.707114 0 -0.7071 -0.707114 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258808 -0.965929 0 0.258808 -0.965929 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.7071 -0.707114 0 -0.7071 -0.707114 0 -0.258812 -0.965928 0 -0.258812 -0.965928 0 0.195077 -0.980788 0.0231937 0.258739 -0.965669 0 0.442286 -0.896874 0 0.608759 -0.793355 0.030963 0.706768 -0.706768 0 0.980784 -0.195095 0.0231921 0.965665 -0.258752 0 0.896874 -0.442286 0 0.793359 -0.608754 0 0.965925 0.258822 0 0.965925 0.258822 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258822 0.965925 0 0.258822 0.965925 0 -0.258825 0.965924 0 -0.258825 0.965924 0 -0.7071 0.707114 0 -0.7071 0.707114 0 -0.965929 0.258808 0 -0.965929 0.258808 0 0.258822 0.965925 0.0307622 0.195003 0.98032 -0.0231931 0.608595 0.793142 0 0.555568 0.831471 0 0.793359 0.608754 -0.0155193 0.831374 0.555497 0.0231924 0.965665 0.258752 0 0.980784 0.195095 0 -0.980788 0.195077 -0.00300235 -0.965924 0.258807 0.00200884 -0.831464 0.555576 0 -0.793345 0.608772 0 -0.555577 0.831465 0.0030017 -0.608756 0.793352 -0.00398298 -0.195094 0.980777 0 -0.258825 0.965924 -0.201913 -0.979403 0 -0.201912 -0.979404 -3.74502e-07 -0.201912 -0.979404 0 -0.201913 -0.979403 0 -0.201912 -0.979404 6.62355e-08 -0.201912 -0.979404 0 -0.201913 0.979403 0 -0.201913 0.979403 0 -0.201912 0.979404 0 -0.201912 0.979404 -3.74502e-07 -0.201912 0.979404 0 -0.201912 0.979404 8.24125e-08 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.201912 -0.979404 0 -0.201912 -0.979404 0 -0.201912 -0.979404 3.89154e-07 -0.201912 -0.979404 7.82905e-07 -0.201912 -0.979404 0 -0.201912 0.979404 0 -0.201912 0.979404 0 -0.201912 0.979404 7.82905e-07 -0.201912 0.979404 3.89154e-07 -0.201912 0.979404 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965925 0.258824 0 0.965925 0.258824 0 0.965925 -0.258824 0 0.965925 -0.258824 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707104 -0.70711 0 -0.707104 -0.70711 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707104 0.70711 0 -0.707104 0.70711 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965925 0.258824 0 0.965925 0.258824 0 0.965925 -0.258824 0 0.965925 -0.258824 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707104 -0.70711 0 -0.707104 -0.70711 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707104 0.70711 0 -0.707104 0.70711 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.201912 -0.979404 0 0.201912 -0.979404 0 0.201912 -0.979404 -1.30484e-06 0.201912 -0.979404 -1.55662e-06 0.201912 -0.979404 0 0.417983 -0.908455 0 0.417983 -0.908455 0 0.775214 -0.631699 0 0.775214 -0.631699 0 0.97414 -0.225946 0 0.97414 -0.225946 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 0.195091 -0.980785 0 0.195091 -0.980785 0 0.555571 -0.831469 0 0.555571 -0.831469 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.831469 -0.55557 0 0.831469 -0.55557 0 0.980785 -0.19509 0 0.980785 -0.19509 0 0.980785 0.19509 0 0.980785 0.19509 0 0.831469 0.55557 0 0.831469 0.55557 0 0.707107 -0.707107 0 0.707107 -0.707107 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.207912 0.978148 1.21257e-08 0.207912 0.978148 3.03565e-08 0.207911 0.978148 0 0.207912 0.978148 4.76263e-08 0.207911 0.978148 7.10922e-08 0.207911 0.978148 -9.48856e-08 0.207912 0.978148 -1.01821e-07 0.207912 0.978148 4.03992e-07 0.20791 0.978148 -5.69991e-09 0.207912 0.978148 5.61664e-09 0.207912 0.978148 -3.55689e-08 0.207912 0.978148 -3.61621e-08 0.207912 0.978148 -2.6168e-08 0.207912 0.978148 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.207912 -0.978148 0 0.207912 -0.978148 -1.31852e-07 0.207912 -0.978148 -1.71959e-06 0.207908 -0.978148 6.56291e-08 0.207911 -0.978148 1.79503e-07 0.207911 -0.978148 1.50337e-07 0.207911 -0.978148 3.40188e-09 0.207912 -0.978148 1.90299e-06 0.207912 -0.978148 1.45305e-09 0.207912 -0.978148 -1.32759e-07 0.207913 -0.978147 4.21098e-08 0.207912 -0.978148 3.29944e-08 0.207912 -0.978148 5.46114e-08 0.207912 -0.978148 0.939465 0.0457713 0.339574 0.976056 0.199483 0.0867228 0.939384 0.32898 0.096589 0.96612 0.0669304 0.249265 0.938778 0.0678224 0.33778 0.939465 0.13048 0.316828 0.95576 0.129224 0.264244 0.939465 0.169957 0.297522 0.939465 0.206639 0.273323 0.95576 0.192074 0.222781 0.939465 0.239921 0.244628 0.939465 0.269258 0.211909 0.95576 0.242339 0.16672 0.939465 0.294165 0.175704 0.938837 0.323471 0.118114 0.938613 0.324086 0.118209 0.938935 0.3258 -0.110704 0.939463 0.32972 -0.093244 0.936069 0.293289 -0.194311 0.936182 0.293116 -0.194026 0.937364 0.290866 -0.191692 0.969222 0.228849 -0.0907586 0.939119 0.325342 -0.110486 0.939546 0.30361 -0.15835 0.946702 0.280916 -0.15761 0.936415 0.292918 -0.1932 0.923944 0.11367 -0.365249 0.93936 0.0503726 -0.339213 0.93936 0.0503726 -0.339213 0.939688 0.0791379 -0.332751 0.937929 0.0932904 -0.334046 0.0438318 0.994152 0.0986972 0 0.995345 0.0963795 0 0.995345 0.0963795 0.0158768 0.995071 0.0978864 0 0.995345 -0.0963795 0 0.995345 -0.0963795 0.0122999 0.995155 -0.097549 0.0393784 0.994336 -0.0987155 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.939694 0.0238579 0.341184 0.939692 0.0238596 0.341189 0.939674 0.0238622 0.341238 0.939651 0.023866 0.3413 0.939692 0.0238582 -0.341188 0.939694 0.0238591 -0.341184 0.939684 0.0238605 -0.341211 0.939651 0.023866 -0.3413 0.348173 0.93743 0 0.348173 0.93743 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.348173 0.93743 0 0.348174 0.93743 -4.28757e-06 0.348173 0.93743 -1.49307e-06 0.348173 0.93743 0 0.348173 0.93743 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.921417 0.388576 -0.00384181 -0.925382 0.379016 -0.000433248 -0.909366 0.415997 0 -0.904994 0.425424 0 0.826976 0.562237 0 0.826976 0.562237 0 0.467847 0.883809 0 0.467847 0.883809 0 0 1 0 0 1 0 -0.467848 0.883809 0 -0.467848 0.883809 0 -0.826976 0.562238 0 -0.826976 0.562238 0 -0.826976 -0.562238 0 -0.826976 -0.562238 0 -0.467848 -0.883809 0 -0.467848 -0.883809 0 0 -1 0 0 -1 0 0.467847 -0.883809 0 0.467847 -0.883809 0 0.826976 -0.562237 0 0.826976 -0.562237 -0.0160202 -0.90392 -0.427402 -0.0121087 -0.908484 -0.417744 0 -0.925389 -0.379019 -0.0576515 -0.83985 -0.539748 -0.212648 -0.815058 -0.538945 -0.618947 -0.645566 -0.447381 0 -0.789967 -0.61315 -0.0215785 -0.845449 -0.53362 -0.00105018 -0.851449 -0.524436 0.00326149 -0.90569 -0.423928 -0.0244019 -0.896812 -0.441737 -0.0175929 -0.902398 -0.430544 0.97414 -0.225946 0 0.97414 -0.225946 0 0.775214 -0.631699 0 0.775214 -0.631699 0 0.417983 -0.908455 0 0.417983 -0.908455 0 0.201912 -0.979404 0 0.201913 -0.979403 0 0.201913 -0.979403 0 0.201912 -0.979404 5.87786e-08 0.201912 -0.979404 6.33286e-07 0.201912 -0.979404 2.05406e-06 0.201912 -0.979404 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.0330398 0.877589 0.478274 0.00302271 0.900313 0.435233 0.00522322 0.895974 0.444075 0.0114339 0.886638 0.462323 0.000666899 0.907574 0.419892 -0.00401059 0.947234 0.320517 0 0.94565 0.325188 0.0330396 0.877589 -0.478274 0.011434 0.886638 -0.462323 0.00509655 0.89616 -0.443701 0.00275993 0.900948 -0.433918 0.000625735 0.907969 -0.419037 -0.0037957 0.945643 -0.325185 0 0.947242 -0.32052 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.5 0.377902 -0.779224 0.499999 0.377901 -0.779225 0.5 0.3779 -0.779225 0.5 0.377901 -0.779224 0.5 0.377902 0.779224 0.5 0.377903 0.779224 0.499999 0.377903 0.779224 0.500002 0.377899 0.779224 0.5 0.377901 0.779225 0 -0.985153 -0.171679 0 -0.985153 -0.171679 0 -0.869008 -0.494798 0 -0.869008 -0.494798 0 -0.93098 0.36507 0 -0.99882 0.0485559 0.00809198 -0.975371 0.220423 0.0158393 -0.984493 0.17471 0.00680556 -0.966928 0.25496 0 -0.980786 0.195088 -0.167726 -0.952242 0.255152 0.113097 -0.826134 0.552007 0 -0.793353 0.608762 0 -0.55557 0.83147 0.167727 -0.600139 0.782113 -0.220167 -0.190304 0.956719 0 -0.258819 0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0.704917 0.705955 -0.0687022 0.704912 0.705959 -0.068704 0.704917 0.705955 0.0687022 0.705452 0.705453 -0.0683646 0.705445 0.705445 0.068513 0.704896 0.706004 0.068418 0.66479 0.743547 -0.0720563 0.482835 0.871003 -0.0906901 0.194272 0.976678 0.0914261 0.274476 0.956486 0.098987 0.0550083 0.993838 0.0962336 0.576173 0.813517 0.078837 0.553675 0.82862 0.0826558 0.553923 0.828991 -0.0770997 0.19417 0.976167 -0.0969383 0.166941 0.981377 -0.095027 0.99845 0.0553975 -0.00540038 0.960973 0.274724 -0.0325332 0.743207 0.665915 0.0648057 0.830083 0.554642 0.0577343 0.873379 0.484922 0.0453767 0.985642 0.168051 0.0163823 0.980562 0.195058 0.0212095 0.980657 0.195077 -0.0160581 0.830155 0.55469 -0.0562347 0.814233 0.577808 -0.0562312 0.995903 0.0355543 -0.0831404 0.984134 0.110225 -0.139035 0.98456 0.0521714 -0.167094 0.984721 0.051746 -0.166272 0.984719 0.0255805 -0.172261 0.984719 0.0255805 -0.172261 0.962754 0.0188607 -0.269721 1 6.69477e-05 -0.000957403 0.984809 0.0118713 -0.173235 0.998321 -0.0148996 -0.055981 0.988634 0.00227443 -0.150329 0.996173 0.0838665 0.0246008 0.965937 0.253017 0.0542947 0.984755 0.166904 0.0490032 0.984748 0.159562 0.0693678 0.984748 0.159563 0.0693679 0.984748 0.149372 0.0892195 0.984748 0.149372 0.0892195 0.984748 0.136724 0.107604 0.984748 0.136724 0.107604 0.984748 0.121828 0.124218 0.984748 0.121828 0.124218 0.984748 0.104928 0.138789 0.984748 0.104928 0.138789 0.984748 0.0863013 0.151077 0.984748 0.0863013 0.151077 0.984748 0.0662554 0.16088 0.984748 0.0662555 0.16088 0.984748 0.0451197 0.168037 0.984748 0.0451198 0.168037 0.984748 0.023242 0.17243 0.984748 0.0232418 0.172429 0.984809 0.0121127 0.173218 0.999638 -0.0259392 0.00710764 0.998321 -0.0148998 0.0559801 0.988633 0.00227442 0.150329 0.962754 0.0188607 0.269721 0.996179 0.084046 -0.0237455 0.952597 0.254029 -0.167414 0.991309 0.10583 -0.0781406 0.991222 0.110303 -0.0728873 0.984659 0.140737 -0.103149 0.984769 0.154158 -0.0804022 0.984769 0.154158 -0.0804022 0.984769 0.16162 -0.0640963 0.984769 0.16162 -0.0640964 0.984603 0.171013 -0.0362172 0.965782 0.249568 -0.0705773 0 0.398182 -0.917306 0 0.398182 -0.917306 0 0.724098 -0.689697 0 0.724098 -0.689697 0 0.935587 -0.353097 0 0.935587 -0.353097 0 0.999227 0.039301 0 0.999227 0.039301 0 0.999227 -0.039301 0 0.999227 -0.039301 0 0.935587 0.353097 0 0.935587 0.353097 0 0.724098 0.689697 0 0.724098 0.689697 0 0.398182 0.917306 0 0.398182 0.917306 0.0493997 0.998779 0 0.258815 0.965927 0 0.999987 0.00505555 0 0.965927 0.258815 -0.000257588 0.981415 0.191868 -0.00337055 0.793352 0.608757 0.00277913 0.849646 0.527353 -0.000785146 0.608773 0.793344 0.000581984 0.577007 0.816738 0.00160541 0.246303 0.969191 -0.00219192 0.290395 0.956898 -0.0041903 0.146869 0.989155 -0.00104957 0.258815 0.965927 0 0.2907 0.956807 0.00369877 0.146945 0.989144 0.000926429 0.0493997 0.998779 0 0.246625 0.969109 0.00194122 0.608773 0.793343 -0.00178351 0.576439 0.81714 -0.000647956 0.793355 0.60876 0.000364913 0.850507 0.525962 -0.00127216 0.965927 0.258815 0 0.999861 0.0133555 0.0100182 0.981479 0.191548 0.00297568 0.176876 0.984233 0 0.176876 0.984233 0 0.176876 0.984233 0 0.176876 0.984233 0 0.176876 0.984233 0 0.176876 0.984233 0 0.176876 0.984233 0 0.176876 0.984233 0 -0.145262 0.741764 0.65474 0 0.735747 0.677257 0.982697 0.0808227 -0.166654 0.985671 0.088106 -0.143843 0.901245 0.181568 -0.393433 0.908859 0.182021 -0.375292 0.815765 0.252395 -0.520407 0.826027 0.253462 -0.503425 0.638086 0.320875 -0.699918 0.652029 0.330849 -0.6822 0.65205 0.33084 0.682185 0.635965 0.352088 0.686718 0.826012 0.238186 0.510854 0.815082 0.252844 0.521259 0.90887 0.181958 0.375295 0.995481 0.0414353 0.0854386 0.985165 0.104564 0.136077 0.959582 0.115589 0.256596 0.899367 0.199877 0.388829 0.649214 0.3319 -0.684371 0.638774 0.342804 -0.688806 0.871789 0.206578 -0.444194 0.857079 0.233534 -0.459215 0.97817 0.0835215 -0.190282 0.985902 0.0807611 -0.146543 0.999805 0.00862111 -0.0177765 0.999805 0.00862087 0.017776 0.978684 0.0918882 0.183668 0.985248 0.0728031 0.154873 0.907175 0.184331 0.378228 0.855707 0.220786 0.467995 0.703582 0.322127 0.633409 0.63807 0.335991 0.692804 0.891495 0.352546 0.284514 0.131649 0.944515 -0.300933 0.127685 0.942465 -0.308959 0.369463 0.929118 0.0154089 0.367507 0.929964 0.0102572 0.547508 0.770716 0.325933 0.547128 0.771732 0.324161 0.641033 0.498147 0.583889 0.640978 0.497154 0.584795 0.174751 0.924717 -0.338171 0.169524 0.923727 -0.343496 0.492047 0.8631 -0.11379 0.488853 0.864335 -0.118102 0.731261 0.670352 0.126037 0.730035 0.672186 0.123352 0.818971 0.514153 0.254821 0.810511 0.416254 0.412073 0.195029 0.904065 -0.380303 0.191744 0.904042 -0.382023 0.553466 0.790961 -0.260875 0.550114 0.792448 -0.263441 0.823792 0.557563 -0.102421 0.821199 0.560751 -0.10579 0.967607 0.242566 0.0699838 0.966716 0.247161 0.0661263 0.112721 0.930902 -0.347441 0.0940254 0.918701 -0.383599 0.298272 0.954385 0.0135126 0.28741 0.957696 -0.0146347 0.434368 0.820182 0.372325 0.430605 0.829003 0.356838 0.498562 0.550419 0.669683 0.49849 0.555127 0.665839 0.109432 0.947739 -0.299691 0.0907 0.937331 -0.336429 0.289971 0.955667 0.0511547 0.278933 0.960031 0.0231814 0.4252 0.814784 0.394122 0.421184 0.824031 0.378916 0.494095 0.547012 0.675757 0.493888 0.551783 0.672019 0.98063 0.185225 -0.0636947 0.98063 0.185225 -0.0636946 0.830374 0.526923 -0.181197 0.830373 0.526923 -0.181197 0.553943 0.787305 -0.270736 0.553944 0.787304 -0.270736 0.194297 0.927628 -0.31899 0.194295 0.927628 -0.31899 0.99882 0.0465708 -0.0137439 0.998206 -0.028315 0.0527536 0.946947 0.321243 -0.00971978 0.965675 0.241543 0.095544 0.895883 0.444217 0.0080457 0.856019 0.508893 0.0908863 0.563503 0.825319 -0.0362385 0.563071 0.825628 -0.0359176 0.727647 0.677973 0.104314 0.710289 0.703758 0.0146486 0.8501 0.381787 0.362724 0.854605 0.403927 0.326335 0.642411 0.51871 0.564134 0.635132 0.501632 0.587345 0.558186 0.785883 0.266113 0.558212 0.777778 0.288895 0.350349 0.927907 -0.127453 0.340313 0.939441 -0.0404776 0.120314 0.910184 -0.396345 0.980021 0.198739 -0.00781666 0.980021 0.19874 -0.00781677 0.82623 0.562898 -0.0221397 0.82623 0.562898 -0.0221397 0.54783 0.835943 -0.032879 0.54783 0.835943 -0.0328789 0.191338 0.980766 -0.038575 0.191338 0.980766 -0.0385749 0.980021 0.186082 0.0702287 0.980021 0.186082 0.0702287 0.82623 0.527047 0.198911 0.82623 0.527047 0.198911 0.54783 0.782702 0.295398 0.547831 0.782702 0.295398 0.191338 0.918301 0.346574 0.191337 0.918301 0.346573 0.980021 0.144018 0.137176 0.980021 0.144018 0.137176 0.82623 0.407908 0.388529 0.82623 0.407909 0.388529 0.54783 0.605773 0.576993 0.54783 0.605773 0.576993 0.191336 0.71072 0.676954 0.191337 0.71072 0.676954 0.980021 0.0791958 0.182446 0.980021 0.0791958 0.182446 0.82623 0.22431 0.516749 0.82623 0.22431 0.516749 0.54783 0.333116 0.767409 0.547831 0.333115 0.767408 0.191337 0.390826 0.900358 0.191339 0.390825 0.900358 0.605174 0.717402 -0.345107 0.986205 0.165196 -0.0104584 0.984752 0.151889 0.0848128 0.933163 0.357088 0.0411622 0.789458 0.612393 0.041597 0.788792 0.614575 -0.0101943 0.392785 0.911352 -0.123118 0.879623 0.474552 -0.0326269 0.959415 0.28088 -0.0250653 0.960163 0.278823 0.0185461 0.997554 0.0686693 0.0130399 0.997546 0.0698863 0.00416085 0.414905 0.901402 -0.12381 0.417016 0.873394 -0.251557 0.194204 0.866713 -0.459449 0.882383 0.445934 -0.150144 0.792025 0.538624 -0.287368 0.894635 0.406993 -0.184352 1 0 0 0.999996 -0.000386943 0.00287789 0.999727 0.0231575 0.00317068 0.999672 0.0217352 0.0135317 0.995531 0.0938987 0.0100372 0.995537 0.093964 0.00879583 0.98637 0.164001 -0.013334 0.986693 0.154417 -0.0509218 0.980199 0.181601 -0.0789373 0.437299 0.822086 -0.364617 0.683061 0.677912 -0.271776 0.681823 0.728077 -0.0708616 0.889501 0.456149 -0.0267678 0.890509 0.454916 0.00673377 0.992949 0.111406 0.0405165 0.993133 0.116989 -5.18983e-05 0.999928 0.00527374 0.010773 0.999977 0.00681781 -0.000708623 0.965918 0.0538178 0.253193 0.977826 0.116398 0.174092 0.792016 0.0691025 0.606577 0.831458 0.115513 0.543447 0.608781 0.164944 0.776002 0.555137 0.134354 0.820836 0.258364 0.257771 0.931022 0.195087 0.203917 0.959353 0.194402 0.861317 -0.469406 0.257977 0.849378 -0.460439 0.44098 0.788081 -0.429493 0.60734 0.697574 -0.380168 0.705917 0.623312 -0.336396 0.792262 0.53578 -0.291993 0.896247 0.389472 -0.212257 0.96573 0.228937 -0.122281 0.980642 0.171932 -0.0937005 0.257911 0.915195 -0.309676 0.25791 0.915196 -0.309676 0.705763 0.671071 -0.227072 0.705764 0.671071 -0.227071 0.96568 0.246033 -0.0832506 0.96568 0.246033 -0.0832505 0.964144 0.107073 0.242821 0.964603 0.104766 0.242003 0.258519 0.214814 0.941819 0.258784 0.214316 0.94186 0.705938 0.185777 0.683476 0.59117 0.393747 0.703905 0.792629 0.16889 0.585847 0.25109 0.271132 0.929215 0.251922 0.270813 0.929083 0.682119 0.338336 0.648261 0.684158 0.337133 0.646737 0.927776 0.315346 0.199472 0.929372 0.312821 0.195986 0.212542 0.348092 0.913048 0.213302 0.348064 0.912882 0.577582 0.547753 0.605281 0.579466 0.547335 0.603857 0.786436 0.601079 0.142206 0.788238 0.599445 0.139095 0.964597 0.263525 -0.0103647 0.964597 0.263525 -0.0103648 0.964597 0.246741 0.0931217 0.964597 0.246741 0.0931217 0.964597 0.190965 0.181892 0.964597 0.190965 0.181893 0.964597 0.105012 0.24192 0.964597 0.105012 0.24192 0.699939 0.71365 -0.028069 0.69994 0.71365 -0.0280693 0.69994 0.668198 0.252183 0.699939 0.668198 0.252183 0.699939 0.517152 0.492583 0.69994 0.517152 0.492583 0.69994 0.284382 0.655142 0.69994 0.284383 0.655142 0.253995 0.966458 -0.0380127 0.253994 0.966459 -0.0380122 0.253994 0.904905 0.341518 0.253995 0.904905 0.341517 0.253995 0.700352 0.667079 0.253994 0.700352 0.667079 0.253994 0.385124 0.887224 0.253994 0.385124 0.887224 0.181753 0.378688 0.907503 0.18179 0.378708 0.907487 0.497214 0.634145 0.592147 0.497313 0.634174 0.592034 0.681299 0.722046 0.120334 0.681392 0.722001 0.120082 0.181722 0.378656 0.907522 0.181763 0.378679 0.907505 0.497155 0.634096 0.592249 0.49724 0.63412 0.592152 0.681256 0.722049 0.120564 0.681337 0.722009 0.120342 0.980781 0.0405665 0.19085 0.965755 0.0721796 0.249216 0.896896 0.0919472 0.432577 0.793348 0.12657 0.595465 0.706878 0.171513 0.686226 0.608754 0.164949 0.776022 0.442288 0.18647 0.877274 0.258776 0.219174 0.940743 0.195095 0.203917 0.959352 0.171501 0.388337 0.905418 0.171901 0.38821 0.905397 0.468656 0.660553 0.586541 0.469752 0.660083 0.586194 0.641951 0.758302 0.113477 0.643321 0.757255 0.112704 0.125918 0.423027 0.897326 0.126361 0.423218 0.897173 0.342307 0.751835 0.563533 0.343425 0.752089 0.562514 0.466624 0.880212 0.086541 0.467921 0.879726 0.0844523 0.0435884 0.451126 0.891395 0.0437071 0.451237 0.891333 0.118497 0.828305 0.547604 0.118811 0.828511 0.547224 0.161564 0.984713 0.0650961 0.162001 0.984692 0.064328 0.977706 0.122988 0.170189 0.195413 0.220463 0.95562 0.195066 0.220577 0.955665 0.977153 0.124469 0.172278 0.894159 0.168034 0.415024 0.832228 0.1671 0.528653 0.791434 0.194165 0.579596 0.555811 0.219822 0.801719 0.608528 0.191559 0.770064 0.441956 0.224196 0.868569 0.948543 0.287415 0.132886 0.947841 0.288763 0.134956 0.80602 0.325386 0.494425 0.804911 0.326144 0.49573 0.539767 0.313599 0.781222 0.53886 0.313891 0.78173 0.18983 0.253467 0.948535 0.189455 0.253523 0.948595 0 0.451556 0.892243 0 0.451556 0.892243 0 0.834182 0.551489 0 0.834182 0.551489 0 0.997822 0.0659627 0 0.997822 0.0659627 0.938198 0.345751 -0.0155131 0.91833 0.379037 0.114021 0.912172 0.376917 0.160862 0.784822 0.389114 0.482332 0.82199 0.413008 0.392117 0.18396 0.269374 0.945302 0.135718 0.274896 0.951847 0.308116 0.30619 0.900729 0.523807 0.358768 0.7726 0.455029 0.369331 0.810274 0.653777 0.372971 0.658383 0.183955 0.269371 0.945304 0.183961 0.269371 0.945303 0.523646 0.35905 0.772579 0.523704 0.359045 0.772541 0.783098 0.393691 0.481421 0.783136 0.393677 0.481369 0.922502 0.367996 0.116482 0.922529 0.367959 0.116389 0.780219 0.543858 0.308993 0.0241659 0.9904 -0.136106 0.0725189 0.831986 0.550037 0.201735 0.514778 0.833251 0.0765208 0.450232 0.889627 0.132513 0.856135 0.499473 0.257928 0.846915 0.464983 0.293889 0.869877 0.396161 0.341725 0.571667 0.745936 0.466092 0.453992 0.759374 0.349135 0.504284 0.789812 0.634524 0.582801 0.507664 0.596755 0.543796 0.590059 0.450831 0.842251 0.295574 0.452987 0.843081 0.289858 0.0879703 0.991875 0.0919031 0.129691 0.989055 0.0703669 0.136386 0.990413 0.0219436 0.0488344 0.997793 0.0449911 0.0329467 0.99728 0.0659269 0.872877 0.434494 -0.222036 0.230746 0.79476 0.56135 0.237774 0.856157 0.458758 0.60091 0.795084 0.0821475 0.758632 0.647721 -0.0702542 0.901263 0.386018 -0.196762 0.879399 0.47238 -0.0592843 -0.207546 0.966215 0.152815 0.542617 0.794551 0.2725 0.639499 0.740043 0.208273 0.599105 0.769418 0.221515 0.885837 0.459622 -0.063571 0.864098 0.486269 -0.129908 0.924448 0.358779 -0.129127 0.895656 0.403273 -0.18754 0.683537 0.717707 -0.132945 0.252361 0.752902 0.607826 0.229498 0.766448 0.599906 0.658812 0.668115 0.345816 0.654382 0.672793 0.345156 0.907422 0.420215 0.00207517 0.913174 0.407561 0.0026747 0.959092 0.265676 0.0977661 0.94878 0.295297 0.112323 0.704412 0.559875 0.436285 0.689669 0.573692 0.441852 0.258689 0.704709 0.660656 0.252356 0.707234 0.660406 0.258816 0.683013 0.683013 0.258814 0.683014 0.683014 0.707116 0.499993 0.499993 0.707117 0.499993 0.499992 0.965925 0.183015 0.183015 0.965925 0.183015 0.183015 0.964647 0.219129 0.146417 0.700224 0.593606 0.396635 0.254167 0.804164 0.537326 0.254168 0.804164 0.537326 0.254167 0.948577 0.188684 0.254166 0.948577 0.188683 0.254166 0.948577 -0.188684 0.254165 0.948577 -0.188684 0.254164 0.804165 -0.537326 0.254167 0.804165 -0.537325 0.700222 0.593607 0.396635 0.700222 0.700207 0.13928 0.700223 0.700207 0.13928 0.700223 0.700207 -0.13928 0.700222 0.700207 -0.13928 0.700222 0.593607 -0.396635 0.700221 0.593608 -0.396636 0.964647 0.219129 0.146417 0.964647 0.25848 0.0514148 0.964647 0.25848 0.0514148 0.964647 0.25848 -0.0514149 0.964647 0.25848 -0.0514149 0.964647 0.219129 -0.146417 0.964647 0.219129 -0.146417 0.258817 0.683013 -0.683013 0.258816 0.683013 -0.683013 0.707116 0.499993 -0.499993 0.707114 0.499995 -0.499995 0.965925 0.183015 -0.183015 0.965925 0.183015 -0.183015 0.254166 0.188684 -0.948577 0.192158 0.172512 -0.966082 0.435411 0.175626 -0.882934 0.700222 0.139279 -0.700207 0.254167 0.537326 -0.804164 0.254166 0.537326 -0.804165 0.700225 0.396634 -0.593605 0.700222 0.396635 -0.593608 0.964647 0.146417 -0.219129 0.964647 0.146417 -0.219129 0.604349 0.120145 -0.787609 0.787625 0.120207 -0.604316 0.964647 0.0514151 -0.25848 0.896199 0.0381562 -0.442009 0.98005 0.0387743 -0.194932 0.980788 0 -0.195079 0.980788 0 -0.195079 0.896852 0 -0.442331 0.896852 0 -0.442331 0.793378 0 -0.60873 0.793378 0 -0.60873 0.608759 0 -0.793355 0.608759 0 -0.793355 0.442286 0 -0.896874 0.442286 0 -0.896874 0.195082 0 -0.980787 0.195082 0 -0.980787 0.231385 0.0237538 -0.972572 0.860219 0.0630347 -0.506014 0.582985 0.0444153 -0.811268 0.980484 0.0248963 -0.195018 0.915478 0.110986 -0.386759 0.92077 0.0481417 -0.387124 0.896158 0.0393247 -0.441989 0.793152 0.0238443 -0.608557 0.646226 0.0365895 -0.762269 0.643364 0.0738814 -0.761987 0.206336 0.0141472 -0.978379 0.195078 0.00700207 -0.980763 0.231885 0.0167422 -0.972599 0.442238 0.0146983 -0.896777 0.608543 0.0266376 -0.793074 0.847462 0.0839675 -0.524174 0.79958 0.0657284 -0.596952 0.579715 0.0711258 -0.811709 0.204588 0.0272872 -0.978468 0.202432 0.0246137 -0.978987 0.558441 0.0708481 -0.826513 0.623029 0.0440526 -0.780958 0.620981 0.0650944 -0.781118 0.853813 0.0909765 -0.512569 0.852269 0.104548 -0.51255 0.855642 0.105599 -0.506682 0.0888348 0.937847 0.335488 0.111349 0.947206 0.300669 0.277597 0.960402 -0.0238461 0.291337 0.955289 -0.0504488 0.420383 0.824256 -0.379315 0.426018 0.814563 -0.393695 0.493622 0.551865 -0.672147 0.494369 0.546935 -0.67562 0.0921042 0.91929 0.382652 0.114697 0.930295 0.34842 0.286033 0.958118 0.0139685 0.29968 0.953954 -0.0128057 0.429781 0.829259 -0.357237 0.435213 0.819927 -0.371901 0.498215 0.555219 -0.665968 0.498844 0.550341 -0.669537 0.800534 0.422273 -0.425243 0.190779 0.905555 0.37891 0.964917 0.248555 -0.08459 0.96348 0.254602 -0.0829663 0.884953 0.464616 0.031451 0.816847 0.570682 0.084168 0.195021 0.904698 0.378797 0.441027 0.845977 0.299696 0.545641 0.801184 0.245722 0.605383 0.762681 0.22766 0.78532 0.607794 0.117729 0.164768 0.926504 0.338292 0.172124 0.926071 0.335805 0.47825 0.872179 0.102859 0.482709 0.869989 0.10055 0.714941 0.683668 -0.146482 0.716849 0.681366 -0.147878 0.802285 0.527057 -0.280268 0.883969 0.359978 -0.298354 0.123126 0.943824 0.306654 0.129783 0.944496 0.301801 0.358265 0.933496 -0.0152224 0.361744 0.932094 -0.0184871 0.534927 0.777018 -0.331807 0.535858 0.775918 -0.332878 0.627665 0.50268 -0.594432 0.627262 0.503871 -0.593849 0.858058 0.374057 -0.351878 0.796404 0.600899 0.0682704 0.90979 0.394799 -0.128123 0.340313 0.93944 0.0404777 0.120318 0.910184 0.396344 0.528665 0.846607 0.0614029 0.727647 0.677974 -0.104315 0.710289 0.703758 -0.0146484 0.846529 0.411496 -0.337727 0.965675 0.241543 -0.095544 0.946947 0.321243 0.00971978 0.998206 -0.0283118 -0.052753 0.998821 0.0465697 0.0137435 0.643614 0.497576 -0.581531 0.63384 0.522591 -0.570216 0.565083 0.77431 -0.284825 0.551642 0.788688 -0.271407 0.35035 0.927907 0.127452 0.541455 0.83944 0.046561 0.98063 0.185225 0.0636947 0.965595 0.245256 0.0864603 0.896064 0.419797 0.144359 0.792134 0.577175 0.198477 0.70551 0.669304 0.232998 0.194297 0.927628 0.31899 0.257743 0.913043 0.316104 0.44074 0.848848 0.2919 0.607163 0.751391 0.258386 0.805704 0.5816 -0.112173 0.999987 0.00505867 0.000131852 0.999808 0.00241986 -0.0194306 0.984573 0.141153 -0.103399 0.987591 0.15686 0.00769745 0.808338 0.587092 -0.0437337 0.953845 0.298269 -0.0348581 0.993397 0.0829746 -0.0792364 0.9956 0.0936669 -0.00278288 0.99952 0.0306781 -0.00432482 0.991943 0.126271 0.0102664 0.975078 0.221859 0.00128231 0.79342 0.602227 0.0883597 0.46199 0.882016 0.0928047 0.690894 0.717424 0.0892661 0.928728 0.365656 -0.0613228 0.929462 0.368882 -0.00506021 0.992015 0.124794 -0.0182263 0.99952 0.0308193 -0.0032944 0.252563 0.906585 0.338105 0.459247 0.803088 0.37966 0.697378 0.672725 0.247193 0.789882 0.555444 0.259938 0.963679 0.252932 0.0857227 0.975913 0.200077 0.086969 0.699968 0.517132 -0.492564 0.980021 0.0791958 -0.182446 0.896801 0.0951852 -0.432073 0.96459 0.105023 -0.241945 0.96459 0.190985 -0.181912 0.96459 0.190985 -0.181911 0.96459 0.246766 -0.0931314 0.96459 0.246766 -0.0931315 0.964589 0.263552 0.0103658 0.96459 0.263552 0.0103659 0.699968 0.517132 -0.492564 0.699968 0.668172 -0.252173 0.699968 0.668171 -0.252173 0.699969 0.713622 0.028068 0.699969 0.713622 0.0280678 0.192691 0.354249 -0.915084 0.435103 0.358516 -0.825925 0.699968 0.284372 -0.655116 0.606245 0.25341 -0.753824 0.787399 0.245457 -0.565467 0.25398 0.385125 -0.887228 0.25398 0.700354 -0.667082 0.25398 0.700355 -0.667081 0.25398 0.904908 -0.341519 0.25398 0.904908 -0.341519 0.25398 0.966462 0.0380124 0.25398 0.966462 0.0380123 0.25791 0.915196 0.309676 0.257912 0.915195 0.309676 0.705764 0.671071 0.227071 0.705763 0.671071 0.227072 0.96568 0.246033 0.0832505 0.96568 0.246033 0.0832506 0.25793 0.848358 0.462343 0.257932 0.848357 0.462343 0.705797 0.622036 0.339001 0.705796 0.622037 0.339002 0.965685 0.228047 0.124283 0.965686 0.228047 0.124282 0.980788 0.0405588 -0.190814 0.980788 0.0405588 -0.190814 0.896806 0.0919852 -0.432756 0.896806 0.0919852 -0.432756 0.793377 0.126562 -0.595428 0.793377 0.126562 -0.595428 0.608779 0.164945 -0.776003 0.608779 0.164945 -0.776003 0.442243 0.186475 -0.877296 0.442243 0.186475 -0.877296 0.195087 0.203917 -0.959353 0.195087 0.203917 -0.959353 0.601023 0.318241 -0.73314 0.964597 0.105012 -0.24192 0.964597 0.105012 -0.241919 0.964597 0.190965 -0.181892 0.964597 0.190965 -0.181892 0.964597 0.24674 -0.0931221 0.964597 0.246741 -0.0931219 0.964597 0.263525 0.0103646 0.964597 0.263525 0.0103649 0.787371 0.245471 -0.5655 0.704115 0.327908 -0.62984 0.699939 0.517153 -0.492583 0.699939 0.517153 -0.492583 0.699939 0.668198 -0.252183 0.69994 0.668197 -0.252184 0.69994 0.71365 0.028069 0.699939 0.71365 0.0280692 0.253993 0.385125 -0.887224 0.253996 0.385124 -0.887224 0.253996 0.700352 -0.667078 0.253996 0.700351 -0.667079 0.253996 0.904904 -0.341519 0.253994 0.904905 -0.341518 0.253994 0.966459 0.0380127 0.253995 0.966458 0.0380121 0.524895 0.606312 -0.597386 0.844447 0.511128 -0.16018 0.71779 0.684662 -0.126551 0.718722 0.683437 -0.127876 0.62115 0.483555 -0.616723 0.967538 0.200251 -0.154176 0.947064 0.237793 -0.215696 0.844347 0.512517 -0.156219 0.620385 0.482034 -0.618681 0.524501 0.607305 -0.596724 0.192108 0.368555 -0.909539 0.886495 0.238825 -0.396344 0.786281 0.255962 -0.562357 0.690486 0.298737 -0.658776 0.605516 0.265195 -0.750347 0.440998 0.259289 -0.859238 0.191982 0.368954 -0.909404 0.22834 0.323971 -0.918098 0.228701 0.324655 -0.917766 0.247423 0.273307 -0.929562 0.19498 0.236278 -0.951922 0.980781 0.0405664 -0.19085 0.965755 0.0721794 -0.249216 0.831411 0.103195 -0.545992 0.79335 0.12657 -0.595463 0.555565 0.172873 -0.813303 0.608646 0.146538 -0.779793 0.195032 0.228237 -0.953871 0.258821 0.200827 -0.944817 0.181754 0.378685 -0.907504 0.181729 0.378649 -0.907524 0.49722 0.63414 -0.592148 0.497176 0.634076 -0.592253 0.6813 0.722045 -0.120334 0.681293 0.722013 -0.120572 0.181783 0.378715 -0.907485 0.181759 0.37868 -0.907505 0.497289 0.634197 -0.592028 0.497238 0.634122 -0.592152 0.68135 0.722042 -0.120074 0.681341 0.722005 -0.120343 0.948109 0.287777 -0.135183 0.94827 0.288405 -0.132693 0.805085 0.325441 -0.49591 0.805809 0.326089 -0.494305 0.538942 0.313501 -0.78183 0.539637 0.313983 -0.781157 0.189479 0.25339 -0.948626 0.189782 0.253594 -0.948511 0.977242 0.123433 -0.172516 0.97761 0.124029 -0.169985 0.829312 0.185735 -0.527014 0.830166 0.186228 -0.525494 0.554918 0.219869 -0.802324 0.555748 0.220241 -0.801647 0.195064 0.220448 -0.955695 0.19539 0.220592 -0.955595 0.0141949 0.451526 -0.892145 0.0142271 0.45151 -0.892153 0.0388015 0.833584 -0.551028 0.0388878 0.833551 -0.551072 0.0531948 0.996415 -0.0657815 0.0533292 0.996402 -0.0658688 0.0716751 0.445124 -0.892596 0.0717649 0.444878 -0.892711 0.194821 0.811792 -0.55049 0.195088 0.811278 -0.551152 0.265504 0.961664 -0.0686236 0.266052 0.961418 -0.0699379 0.150634 0.408535 -0.900227 0.150629 0.407992 -0.900474 0.409332 0.71202 -0.570504 0.40942 0.71084 -0.571911 0.557358 0.82481 -0.0950796 0.558083 0.823995 -0.0978619 0.526327 0.351945 -0.774025 0.167736 0.271309 -0.947764 0.18396 0.269374 -0.945302 0.779455 0.40343 -0.479264 0.73173 0.383709 -0.563328 0.480197 0.361175 -0.799352 0.922533 0.367947 -0.116392 0.924625 0.380487 0.0173002 0.918005 0.378907 -0.117034 0.895303 0.383046 -0.227395 0.85555 0.389388 -0.341191 0.922511 0.367973 -0.116487 0.92252 0.367982 -0.116385 0.783104 0.393676 -0.481423 0.783131 0.393692 -0.481366 0.523651 0.359034 -0.772582 0.523699 0.359061 -0.772538 0.183954 0.269369 -0.945305 0.183961 0.269373 -0.945302 0 0.997822 -0.0659627 0 0.997822 -0.0659627 0 0.834182 -0.551489 0 0.834182 -0.551489 0 0.451556 -0.892243 0 0.451556 -0.892243 0.494427 0.502828 -0.709018 0.529376 0.766875 -0.362855 0.464414 0.847027 -0.258581 0.0786262 0.996694 0.0204506 0.135861 0.990658 -0.01181 0.19055 0.970699 -0.146403 0.194166 0.968698 -0.154674 0.311382 0.847779 -0.429316 0.336525 0.869779 -0.360881 0.41246 0.583522 -0.699556 0.682721 0.542995 -0.488926 0.699309 0.565811 -0.436834 0.826566 0.483533 -0.28807 0.21343 0.441151 -0.871684 0.121338 0.529801 -0.839398 0.152909 0.824372 -0.545004 0.095314 0.859845 -0.501579 0.0595406 0.996052 -0.0658457 0.0391832 0.998223 -0.0448968 0.258811 0 -0.965928 0.258811 0 -0.965928 0.707118 0 -0.707096 0.707118 0 -0.707096 0.965925 0 -0.258823 0.965925 0 -0.258823 0.96361 -0.0691855 -0.258203 0.783029 -0.600792 -0.160982 0.694758 -0.186153 -0.694736 0.250555 -0.250563 -0.935115 0.250557 -0.250562 -0.935115 0.250557 -0.684551 -0.684552 0.250555 -0.684552 -0.684552 0.250558 -0.935115 -0.250562 0.250559 -0.935114 -0.250563 0.694756 -0.186155 -0.694738 0.694756 -0.508584 -0.508584 0.694754 -0.508585 -0.508584 0.694755 -0.694739 -0.186155 0.601246 -0.783576 -0.156565 0.963611 -0.0691847 -0.258202 0.96361 -0.189017 -0.189017 0.963611 -0.189017 -0.189017 0.96361 -0.258202 -0.069185 0.963611 -0.258202 -0.0691851 0.195087 -0.980786 0 0.258815 -0.965924 0.00226119 0.555564 -0.831472 -0.00151276 0.608753 -0.79336 0 0.831476 -0.55556 0 0.793374 -0.60873 -0.00226023 0.980784 -0.195076 0.00300054 0.965925 -0.258822 0 0.973657 -0.193659 0.120364 0.931234 -0.00473589 0.36439 0.951439 0.151659 0.267888 0.882983 -0.425347 0.198548 0.814172 -0.543998 0.202955 0.619228 -0.772886 0.138582 0.550374 -0.823705 0.136373 0.224211 -0.973334 0.0484885 0.194874 -0.979714 0.0467442 0.748719 0.136573 0.648666 0.737901 -0.00459558 0.674893 0.713022 -0.327754 0.61982 0.669202 -0.424733 0.60973 0.516731 -0.728448 0.449835 0.470057 -0.772553 0.42686 0.190905 -0.96769 0.164719 0.170335 -0.973456 0.152872 0.534554 0.142256 0.833076 0.534556 0.14224 0.833077 0.507886 -0.33994 0.791513 0.507886 -0.339939 0.791513 0.361896 -0.742253 0.563996 0.3619 -0.742246 0.564003 0.130883 -0.970188 0.203974 0.130883 -0.970188 0.203974 0.0899725 -0.946294 0.310537 0.143058 -0.922635 0.358161 0.31086 -0.703466 0.639141 0.343993 -0.666957 0.660937 0.463398 -0.308613 0.830675 0.477788 -0.279529 0.832816 0.51502 0.153217 0.843373 0.517509 0.163291 0.839953 0.097619 -0.969434 0.225095 0.152253 -0.950063 0.272397 0.331762 -0.741777 0.582838 0.365456 -0.706766 0.605743 0.48656 -0.339831 0.804844 0.500717 -0.310857 0.807868 0.526034 0.142233 0.838485 0.528272 0.15243 0.835281 0.807434 0.0669587 0.586145 0.133567 -0.884836 0.446347 0.194016 -0.867357 0.458312 0.469586 -0.668608 0.576588 0.501757 -0.645296 0.57605 0.721051 -0.33598 0.605973 0.729854 -0.323697 0.602108 0.817631 -0.0911691 0.568478 0.88459 0.00889575 0.466285 0.105442 -0.918779 0.380431 0.162055 -0.895331 0.414874 0.375603 -0.669477 0.640877 0.401649 -0.644137 0.650973 0.567261 -0.288051 0.771519 0.570073 -0.283015 0.77131 0.645531 0.145564 0.749734 0.639357 0.122191 0.759139 0.19646 -0.883785 0.42465 0.976351 -0.13794 0.16647 0.97724 -0.135147 0.163514 0.893346 -0.365639 0.261232 0.827915 -0.461599 0.318563 0.195029 -0.883809 0.425259 0.44176 -0.797452 0.410998 0.553307 -0.724417 0.411183 0.607591 -0.696035 0.382581 0.790945 -0.520994 0.320891 0.190365 -0.863622 0.466817 0.187362 -0.863892 0.467532 0.537172 -0.683289 0.494532 0.534783 -0.68438 0.495613 0.800869 -0.399109 0.446453 0.799228 -0.400741 0.44793 0.94213 -0.0552095 0.33067 0.941461 -0.0568575 0.332293 0.194971 -0.90763 0.371745 0.2587 -0.895771 0.36148 0.442023 -0.830077 0.339981 0.608546 -0.734314 0.300758 0.707013 -0.656947 0.261826 0.793196 -0.56353 0.230809 0.896698 -0.409618 0.16777 0.96591 -0.241431 0.09343 0.980765 -0.180629 0.0739816 0.251668 0.800359 0.544141 0.963928 0.124524 0.235237 0.963928 0.124523 0.235237 0.963928 0 0.266162 0.963928 0 0.266162 0.963928 -0.124523 0.235237 0.963928 -0.124524 0.235237 0.963928 -0.22011 0.149647 0.963928 -0.220111 0.149647 0.963928 0.220111 0.149647 0.963928 0.22011 0.149647 0.784463 0.51287 0.348686 0.600665 0.677958 0.423762 0.696472 0.593425 0.403453 0.696472 0.33572 0.634208 0.69647 0.335721 0.634209 0.69647 0 0.717586 0.69647 0 0.717586 0.69647 -0.33572 0.634209 0.696472 -0.33572 0.634208 0.696472 -0.593425 0.403453 0.696472 -0.593424 0.403452 0.251668 0.800359 0.544141 0.251668 0.452789 0.855362 0.251669 0.452789 0.855362 0.251669 0 0.967813 0.251669 0 0.967813 0.251669 -0.452789 0.855362 0.251668 -0.452789 0.855363 0.251668 -0.800359 0.544141 0.251668 -0.800359 0.544141 0.189543 -0.811985 -0.552045 0.823655 -0.265312 -0.501201 0.979639 -0.16603 -0.112879 0.979639 -0.16603 -0.112879 0.979639 -0.0939287 -0.17744 0.979639 -0.0939284 -0.17744 0.979639 0 -0.200767 0.979639 0 -0.200767 0.979639 0.0939285 -0.17744 0.979639 0.0939286 -0.17744 0.979639 0.16603 -0.112879 0.979639 0.16603 -0.112879 0.823654 -0.265313 -0.501201 0.823654 0 -0.567092 0.823654 0 -0.567092 0.823654 0.265313 -0.501201 0.823655 0.265312 -0.501201 0.823655 0.468971 -0.31884 0.823654 0.468971 -0.31884 0.433876 -0.758394 -0.486405 0.597298 -0.663251 -0.450926 0.823655 -0.468971 -0.31884 0.78578 -0.517782 -0.338306 0.891442 -0.374732 -0.25477 0.544086 -0.693857 -0.471734 0.544086 -0.392538 -0.741542 0.544086 -0.392538 -0.741542 0.544086 0 -0.83903 0.544086 0 -0.83903 0.544086 0.392538 -0.741542 0.544086 0.392538 -0.741542 0.544086 0.693857 -0.471734 0.544087 0.693857 -0.471733 0.189543 -0.811985 -0.552045 0.189543 -0.459367 -0.867788 0.189544 -0.459367 -0.867788 0.189544 0 -0.981872 0.189544 0 -0.981872 0.189544 0.459367 -0.867788 0.189543 0.459367 -0.867788 0.189543 0.811985 -0.552045 0.189543 0.811985 -0.552045 0.980765 -0.180629 -0.0739816 0.980765 -0.180629 -0.0739817 0.896699 -0.409616 -0.167769 0.896698 -0.409616 -0.16777 0.793196 -0.563531 -0.23081 0.793195 -0.563532 -0.23081 0.608546 -0.734314 -0.300758 0.608545 -0.734314 -0.300758 0.442023 -0.830077 -0.339981 0.442027 -0.830076 -0.33998 0.194971 -0.90763 -0.371745 0.19497 -0.90763 -0.371745 0.967243 -0.107254 -0.230083 0.731334 -0.317807 -0.603448 0.63891 0.152768 -0.75396 0.584797 -0.0903809 -0.806129 0.549038 -0.216798 -0.80719 0.519015 -0.270948 -0.810685 0.400254 -0.496444 -0.770286 0.131059 -0.806388 -0.576682 0.4898 -0.62871 -0.604003 0.127103 -0.811389 -0.570519 0.176517 -0.838791 -0.515045 0.171386 -0.842219 -0.51117 0.638873 0.154073 -0.753726 0.810021 0.0664715 -0.582621 0.817452 -0.124286 -0.562428 0.891599 0.00236522 -0.452819 0.968096 -0.101555 -0.229078 0.885983 -0.334711 -0.32094 0.823108 -0.433797 -0.366489 0.730141 -0.320926 -0.603242 0.492917 -0.624713 -0.605613 0.370291 -0.556809 -0.743538 0.293118 -0.645803 -0.704997 0.194916 -0.876081 -0.44101 0.198125 -0.874824 -0.442075 0.440717 -0.780599 -0.443209 0.553068 -0.706045 -0.442286 0.605052 -0.673273 -0.424989 0.785701 -0.492445 -0.374394 0.0858007 -0.795062 -0.600429 0.132657 -0.731787 -0.668499 0.208033 -0.625569 -0.751921 0.292557 -0.470816 -0.832312 0.347255 -0.334792 -0.875973 0.38619 -0.237605 -0.891292 0.440613 -0.0516172 -0.896212 0.476769 0.144659 -0.867044 0.48661 0.198256 -0.850826 0.474609 0.15315 -0.866771 0.47373 0.145542 -0.86856 0.342801 -0.309508 -0.886957 0.335295 -0.331307 -0.881937 0.131484 -0.700351 -0.701584 0.114329 -0.726438 -0.677656 0.613407 0.133779 -0.778354 0.615921 0.103269 -0.78101 0.443307 -0.317178 -0.838377 0.439085 -0.338771 -0.832129 0.162751 -0.697772 -0.697586 0.157418 -0.708103 -0.688338 0.831808 0.0259641 -0.554455 0.829337 -0.0156577 -0.558529 0.606017 -0.396571 -0.689547 0.594173 -0.422462 -0.684459 0.223044 -0.72354 -0.653255 0.213169 -0.733138 -0.645808 0.95172 -0.105409 -0.288301 0.942389 -0.155027 -0.296428 0.701969 -0.496277 -0.510832 0.682926 -0.522679 -0.510312 0.258619 -0.757036 -0.600011 0.247354 -0.763595 -0.596438 0.965895 -0.204548 -0.158764 0.965896 -0.204547 -0.158764 0.706956 -0.55871 -0.433655 0.706955 -0.558711 -0.433655 0.258705 -0.763073 -0.592276 0.258706 -0.763073 -0.592276 0.255224 -0.952527 -0.165993 0.192729 -0.968934 -0.154993 0.436981 -0.886117 -0.15442 0.701807 -0.701791 -0.122298 0.255224 -0.840228 -0.478411 0.255224 -0.840228 -0.478411 0.701808 -0.619052 -0.352477 0.701806 -0.619054 -0.352477 0.964944 -0.228077 -0.129863 0.964944 -0.228076 -0.129862 0.604997 -0.788462 -0.11093 0.788951 -0.605333 -0.105489 0.964944 -0.258559 -0.0450582 0.896144 -0.441982 -0.0397256 0.980222 -0.194965 -0.0339758 0.195087 -0.980786 0 0.195087 -0.980786 0 0.442286 -0.896874 0 0.442286 -0.896874 0 0.608754 -0.793359 0 0.608754 -0.793359 0 0.793378 -0.60873 0 0.793378 -0.60873 0 0.896852 -0.442331 0 0.896852 -0.442331 0 0.980788 -0.195078 0 0.980788 -0.195078 0 0.256744 -0.588357 0.766759 0.430042 -0.872047 0.233664 -0.0227027 -0.793148 0.608605 0.595449 -0.776019 0.207933 0.690716 -0.70522 0.159926 0.78303 -0.60079 0.160982 0.890618 -0.439257 0.117699 0.962134 -0.267521 0.0522536 0.979451 -0.194812 0.0521996 0.963611 -0.189017 0.189017 0.963611 -0.189017 0.189017 0.694755 -0.508584 0.508583 0.694754 -0.508585 0.508585 0.250556 -0.684552 0.684552 0.249008 -0.941153 0.228529 0.18868 -0.948577 0.25417 0.250556 -0.250563 0.935115 0.250562 -0.250565 0.935113 0.694756 -0.186156 0.694737 0.694754 -0.186155 0.69474 0.963611 -0.0691851 0.258202 0.963611 -0.0691851 0.258202 0.258818 0 0.965926 0.258818 0 0.965926 0.707114 0 0.7071 0.707114 0 0.7071 0.965925 0 0.258822 0.965925 0 0.258822 0.374852 0.916663 0.13862 0.999992 0.00402268 2.38245e-05 0.994747 0.0312057 0.0974887 0.98554 0.168435 -0.0184612 0.959395 0.219272 0.177427 0.937058 0.348732 0.0175707 0.999992 0.00402972 2.02129e-05 0.998115 0.0201153 0.057979 0.997672 0.0555521 0.039556 0.984101 0.0861549 0.155317 0.984405 0.124987 0.123792 0.585564 0.810464 0.0162015 0.942335 0.240734 0.232489 0.94117 0.162654 0.296213 0.781336 0.622645 0.0427483 0.848384 0.410502 0.334265 0.779353 0.604864 0.16355 0.833524 0.539586 -0.118681 0.908388 0.352165 0.225413 0.95733 0.269636 -0.103994 0.98531 0.0530066 0.162339 0.99997 0.00729728 -0.00270385 0.233307 0.926466 0.295345 0.293495 0.953261 -0.0717869 0.634035 0.678982 0.370113 0.685574 0.712398 0.149923 0.879329 0.264804 0.395804 0.904368 0.277952 0.323823 0.313379 0.907015 0.281279 0.371092 0.925936 -0.070235 0.672478 0.649387 0.355064 0.722614 0.676147 0.143718 0.886952 0.252205 0.386923 0.910993 0.262794 0.317853 0.877682 0.378064 0.294521 0.920386 0.213156 0.327803 0.936266 0.0885903 0.339939 0.243926 0.96687 0.0752496 0.609812 0.756885 0.235063 0.65678 0.715502 0.238112 0.902806 0.277954 0.328151 0.999992 0.00402976 -2.02039e-05 0.998671 0.0175681 -0.048446 0.997656 0.0556306 -0.0398498 0.987749 0.080488 -0.133691 0.982634 0.127492 -0.134823 0.999992 0.00402268 -2.38354e-05 0.998116 0.0201819 -0.0579451 0.985504 0.168776 0.0172338 0.974967 0.199555 -0.0980713 0.931583 0.358832 -0.0582402 0.718524 0.618681 -0.31774 0.827005 0.559914 0.0505946 0.942194 0.322648 -0.0903783 0.957376 0.270267 0.10192 0.994893 0.0343582 -0.0949039 0.99997 0.00729693 0.00270509 0.374855 0.916662 -0.138618 0.648489 0.760775 0.0261511 0.759889 0.636981 -0.129709 0.902774 0.386882 -0.187941 0.934461 0.243219 -0.260051 0.956408 0.152657 -0.248957 0.271478 0.939834 -0.207391 0.426669 0.90439 0.00561844 0.656041 0.681753 -0.323763 0.747783 0.641864 -0.169798 0.885613 0.264575 -0.381692 0.914421 0.247976 -0.319909 0.187984 0.956851 -0.22158 0.351387 0.936197 0.00791219 0.615534 0.711235 -0.339503 0.712975 0.678911 -0.175346 0.877637 0.277317 -0.390958 0.908223 0.263069 -0.325463 0.651065 0.715409 -0.253585 0.243926 0.96687 -0.0752496 0.936266 0.0885902 -0.339939 0.920386 0.213156 -0.327803 0.907114 0.277937 -0.316061 0.860836 0.401447 -0.312733 0.633291 0.739091 -0.229537 -0.00137363 0.999999 0 -0.683293 0.729316 -0.0347666 -0.567027 0.823629 -0.0107932 -0.195049 0.980564 0.0212358 -0.397121 0.916914 -0.039538 -0.169962 0.985451 -0.00030533 -0.555536 0.831416 0.0112941 -0.831452 0.555545 -0.0075061 -0.82846 0.559984 -0.00850808 -0.980785 0.195094 0 -0.993024 0.116159 -0.0202401 -0.937883 0.346926 0.00430807 -0.975512 -0.219946 0 -0.975512 -0.219946 0 -0.786737 -0.617289 0 -0.786737 -0.617289 0 -0.445728 -0.895169 0 -0.445728 -0.895169 0 -0.0184516 -0.99983 0 -0.0184516 -0.99983 0 0.494515 -0.869163 -0.00338422 0.417964 -0.908418 -0.00909806 0.347715 -0.937599 -0.0014992 0.216391 -0.976307 0 0.775183 -0.631675 -0.00884984 0.71687 -0.697205 -0.00191368 0.589092 -0.808066 0.000855009 1 0 0 0.985436 -0.170044 -0.000205037 0.974124 -0.225926 -0.0062468 0.904488 -0.426497 0.00162623 0.820698 -0.571354 -0.00308913 0.974126 -0.225927 -0.00599972 0.911747 -0.410193 0.0214215 0.985431 -0.170076 0.000167757 1 0 0 0.417981 -0.908456 0 0.216309 -0.975935 0.0275997 0.348952 -0.937077 0.0109257 0.494315 -0.869279 0.00265167 0.589155 -0.80802 -0.000670526 0.775211 -0.631697 0.00261663 0.720762 -0.69308 0.01191 0.820459 -0.5717 0.00247064 -0.0184516 -0.99983 0 -0.0184516 -0.99983 0 -0.445728 -0.895169 0 -0.445728 -0.895169 0 -0.786737 -0.617289 0 -0.786737 -0.617289 0 -0.975512 -0.219946 0 -0.975512 -0.219946 0 -0.993228 0.116183 0 -0.965809 0.258783 0.0156221 -0.937522 0.347913 0.00307564 -0.841808 0.539774 -0.00148933 -0.793349 0.608755 0.00376695 -0.773885 0.633323 0.00209222 -0.648631 0.761091 -0.00420125 -0.608752 0.79336 0.000850726 -0.477347 0.878715 -0.00023964 -0.25882 0.965926 0 0.0455199 0.99753 0.0535056 -0.221186 0.975205 0.00718538 0.410348 -0.891866 -0.190238 0.445007 -0.85849 -0.25488 0.942563 -0.218606 -0.252562 0.942563 -0.218605 -0.25256 0.697793 -0.161836 -0.697778 0.697773 -0.161856 -0.697793 0.25834 -0.0599245 -0.964194 0.750082 -0.61122 -0.252561 0.750072 -0.611227 -0.252573 0.555283 -0.452495 -0.697789 0.555304 -0.452487 -0.697777 0.376777 -0.818878 -0.432987 0.334793 -0.72763 -0.598722 0.362786 -0.61005 -0.704433 0.258643 -0.562145 -0.785555 0.188783 -0.410307 -0.892193 0.258354 -0.0599061 -0.964191 0.205592 -0.167526 -0.964193 0.20559 -0.167527 -0.964193 0.178122 -0.189294 -0.96563 0.0836185 -0.181739 -0.979785 0.0393886 -0.19106 -0.980788 0.0393883 -0.191058 -0.980788 0.0893038 -0.433181 -0.896872 0.0893029 -0.433176 -0.896874 0.122917 -0.596226 -0.793351 0.122917 -0.596228 -0.793349 0.160187 -0.777009 -0.608766 0.160186 -0.777007 -0.60877 0.18109 -0.878403 -0.442284 0.181091 -0.878406 -0.442277 0.198032 -0.960584 -0.195093 0.198033 -0.960586 -0.195086 0.258805 0 -0.96593 0.258805 0 -0.96593 0.707114 0 -0.7071 0.707114 0 -0.7071 0.965925 0 -0.258822 0.965925 0 -0.258822 -0.0181137 -0.981523 -0.190487 -0.0147737 -0.80042 -0.599257 -0.0166301 -0.900997 -0.433507 -0.064547 -0.964734 -0.255192 -0.431239 -0.866071 -0.25289 -0.431233 -0.866077 -0.252881 -0.761167 -0.597226 -0.252878 -0.761172 -0.597212 -0.252892 -0.943803 -0.212797 -0.252891 -0.943803 -0.212794 -0.252894 -0.00832639 -0.451072 -0.892449 -0.0114105 -0.618149 -0.785978 -0.0896578 -0.703695 -0.704822 -0.319053 -0.640779 -0.698289 -0.319055 -0.640777 -0.69829 -0.563165 -0.441856 -0.69829 -0.563165 -0.441854 -0.698291 -0.698287 -0.157439 -0.69829 -0.698293 -0.157459 -0.698279 -0.00368817 -0.199748 -0.97984 -0.0894662 -0.244435 -0.96553 -0.118052 -0.237091 -0.964288 -0.118059 -0.237082 -0.964289 -0.208372 -0.163486 -0.964289 -0.20837 -0.163493 -0.964288 -0.258366 -0.0582592 -0.964289 -0.258365 -0.0582552 -0.964289 0.766761 0.588354 -0.256745 0.250558 0.935114 -0.250566 0.250562 0.935111 -0.250571 0.186157 0.694747 -0.694747 0.186156 0.694748 -0.694746 0.0691807 0.258188 -0.963615 0.0691776 0.258191 -0.963614 0.588364 0.766747 -0.256763 0.66794 0.667952 -0.32817 0.508584 0.508593 -0.694749 0.508585 0.508585 -0.694753 0.189008 0.189008 -0.963614 0.189008 0.189008 -0.963614 0.935117 0.250559 -0.250554 0.935116 0.250548 -0.250566 0.694745 0.186145 -0.694752 0.694752 0.186166 -0.694738 0.258188 0.0691841 -0.963614 0.258185 0.0691724 -0.963616 -0.980788 0 -0.195077 -0.965925 -0.000442263 -0.258822 -0.896852 0 -0.442331 -0.793373 0 -0.608736 -0.707114 -0.000590453 -0.707099 -0.608759 0 -0.793355 -0.258805 0 -0.96593 -0.442285 -0.00174984 -0.896873 -0.195073 0 -0.980789 0 0.258808 -0.965929 0 0.258808 -0.965929 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965925 -0.258822 0 0.965925 -0.258822 -0.882913 0.175622 -0.435457 -0.191484 0.962637 -0.191481 -0.545284 0.816088 -0.191483 -0.545292 0.816085 -0.191472 -0.81609 0.545285 -0.191472 -0.816093 0.545282 -0.191467 -0.962641 0.191481 -0.191463 -0.962639 0.191484 -0.191467 -0.604344 0.120219 -0.787602 -0.783673 0.155892 -0.601294 -0.810307 0.199125 -0.551136 -0.695441 0.464671 -0.548127 -0.695429 0.464676 -0.548137 -0.464669 0.695438 -0.548133 -0.464677 0.695437 -0.548126 -0.194926 0.0387796 -0.980051 -0.440583 0.0876518 -0.893422 -0.19148 0.962636 -0.191485 -0.175626 0.882934 -0.435411 -0.199138 0.810304 -0.551137 -0.15589 0.78366 -0.601312 -0.120219 0.604344 -0.787602 -0.533419 0.161803 -0.830231 -0.468135 0.312802 -0.826441 -0.468143 0.312799 -0.826438 -0.312802 0.46814 -0.826438 -0.312797 0.46814 -0.82644 -0.161798 0.533427 -0.830227 -0.0876418 0.440584 -0.893423 -0.194939 0.0387627 -0.980049 -0.165257 0.11042 -0.98005 -0.16526 0.110418 -0.980049 -0.11042 0.165257 -0.98005 -0.110408 0.165258 -0.980051 -0.0387759 0.19493 -0.98005 -0.038776 0.19493 -0.98005 -0.766761 0.588354 0.256745 -0.258198 0.069176 0.963612 -0.258201 0.0691877 0.963611 -0.694752 0.186166 0.694738 -0.694745 0.186145 0.694752 -0.935116 0.250548 0.250566 -0.935117 0.250559 0.250554 -0.588346 0.766766 0.256748 -0.66794 0.667952 0.32817 -0.508584 0.508593 0.694749 -0.508585 0.508585 0.694753 -0.189018 0.189018 0.96361 -0.189018 0.189018 0.96361 -0.0691812 0.258205 0.96361 -0.0691843 0.258202 0.963611 -0.186156 0.694748 0.694746 -0.186157 0.694747 0.694747 -0.250562 0.935113 0.250564 -0.250564 0.935112 0.250565 -0.258818 0 0.965926 -0.258818 0 0.965926 -0.707114 0 0.7071 -0.707114 0 0.7071 -0.965925 0 0.258822 -0.965925 0 0.258822 0 0.965925 0.258822 0 0.965925 0.258822 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258822 0.965925 0 0.258822 0.965925 -0.0178544 -0.967331 0.252888 -0.0132111 -0.715695 0.698288 -0.00488981 -0.264824 0.964284 -0.0048884 -0.264823 0.964285 -0.118068 -0.2371 0.964284 -0.118057 -0.237101 0.964285 -0.208378 -0.163499 0.964286 -0.208384 -0.163496 0.964285 -0.258381 -0.0582587 0.964285 -0.258378 -0.058262 0.964285 -0.0132099 -0.715694 0.698289 -0.319056 -0.640778 0.698289 -0.319053 -0.640778 0.69829 -0.563166 -0.441855 0.69829 -0.563164 -0.441856 0.698291 -0.698281 -0.157456 0.698292 -0.698295 -0.157441 0.698281 -0.0178518 -0.96733 0.252891 -0.431232 -0.866075 0.252891 -0.43124 -0.866073 0.252882 -0.761176 -0.597214 0.252877 -0.761164 -0.597223 0.252891 -0.943803 -0.212795 0.252891 -0.943802 -0.212797 0.252894 0.588364 0.766747 0.256763 0.0691804 0.258202 0.963611 0.0691846 0.258203 0.96361 0.186155 0.694747 0.694747 0.186157 0.694747 0.694746 0.250562 0.935113 0.250565 0.250558 0.935112 0.25057 0.766761 0.588354 0.256745 0.66794 0.667952 0.32817 0.508581 0.50859 0.694753 0.508589 0.508589 0.694748 0.189018 0.189018 0.96361 0.189018 0.189018 0.96361 0.258206 0.0691782 0.96361 0.258198 0.0691869 0.963611 0.694737 0.186162 0.694754 0.694755 0.186148 0.694741 0.935119 0.250549 0.250553 0.935114 0.250558 0.250566 0.195032 -0.946032 0.258818 0.195032 -0.946032 0.258814 0.142773 -0.692542 0.707108 0.142773 -0.692541 0.707108 0.0522595 -0.253492 0.965925 0.0522593 -0.253491 0.965925 0.965925 0 0.258822 0.965925 0 0.258822 0.707114 0 0.7071 0.707114 0 0.7071 0.258818 0 0.965926 0.258818 0 0.965926 0.258353 -0.0599059 0.964191 0.258358 -0.0599288 0.964189 0.69779 -0.161859 0.697776 0.697781 -0.161833 0.69779 0.942563 -0.218605 0.252562 0.942563 -0.218606 0.25256 0.205601 -0.167536 0.964189 0.205602 -0.167534 0.964189 0.555293 -0.452478 0.697791 0.55529 -0.452501 0.697779 0.750075 -0.611229 0.25256 0.75008 -0.611219 0.252572 0.110856 -0.240937 0.964189 0.110855 -0.240937 0.964189 0.299405 -0.650737 0.697781 0.29941 -0.650729 0.697786 0.40444 -0.878999 0.252566 0.404431 -0.879006 0.252555 1 0 0 0.87643 0 0.481529 0.630655 0 0.776064 0.150095 0 0.988672 0.345417 -0.00773456 0.938417 0.196583 0 0.980487 0.196583 0 0.980487 0.150095 0 0.988672 0.150095 0 0.988672 0.46641 0.000887167 0.884568 0.631108 -0.000734754 0.775694 0.465904 0 0.884835 0.341553 0 0.939863 0.176479 0.000338572 0.984304 0.150095 0 0.988672 0.765805 0.000932132 0.643073 0.876752 -0.000653228 0.480942 0.765253 0 0.64373 0.980992 1.85784e-05 0.194049 0.999997 -0.00150405 -0.001714 0.980988 0 0.194069 1 0 0 0.87643 0 -0.481529 0.630655 0 -0.776064 0.341553 0 -0.939863 0.150261 -0.000390502 -0.988646 0.34218 0.0012516 -0.939634 0.150119 0 -0.988668 0.46641 -0.000887167 -0.884568 0.631108 0.000734754 -0.775694 0.465904 0 -0.884835 0.765805 -0.000932132 -0.643073 0.876752 0.000653228 -0.480942 0.765253 0 -0.64373 0.980992 -1.85493e-05 -0.194049 0.999997 0.00150406 0.0017167 0.980988 0 -0.194069 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.201912 0.979404 0 0.201912 0.979404 0 0.201912 0.979404 -1.55662e-06 0.201912 0.979404 -1.30484e-06 0.201912 0.979404 0 0.97414 0.225946 0 0.97414 0.225946 0 0.775214 0.631699 0 0.775214 0.631699 0 0.417983 0.908455 0 0.417983 0.908455 0 0 1 0 0 1 0 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.866025 0.5 0 -0.866025 0.5 0 -1 0 0 -1 0 0 -0.866026 -0.499999 0 -0.866026 -0.499999 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.207912 0.978148 4.03992e-07 -0.20791 0.978148 -5.69991e-09 -0.207912 0.978148 6.81993e-08 -0.207911 0.978148 0 -0.207912 0.978148 3.06169e-08 -0.207911 0.978148 -1.25281e-07 -0.207912 0.978148 3.40701e-07 -0.207911 0.978148 -1.04432e-07 -0.207912 0.978148 -4.55095e-09 -0.207912 0.978148 -2.6168e-08 -0.207912 0.978148 -4.07061e-08 -0.207912 0.978148 -2.55754e-08 -0.207912 0.978148 5.61664e-09 -0.207912 0.978148 0 -0.207912 -0.978148 0 -0.207912 -0.978148 -3.09325e-07 -0.207913 -0.978147 8.01491e-07 -0.207908 -0.978148 1.40315e-07 -0.207911 -0.978148 -1.70094e-08 -0.207912 -0.978148 -3.64278e-08 -0.207912 -0.978148 9.70054e-09 -0.207912 -0.978148 2.8215e-07 -0.20791 -0.978148 -4.47866e-09 -0.207912 -0.978148 4.83922e-08 -0.207911 -0.978148 1.25093e-08 -0.207912 -0.978148 -4.49458e-08 -0.207914 -0.978147 3.35633e-08 -0.207912 -0.978148 0.938608 -0.324059 0.118329 0.939384 -0.32898 0.096589 0.976056 -0.199483 0.0867228 0.938835 -0.323497 0.118062 0.939465 -0.294165 0.175704 0.95576 -0.242339 0.16672 0.939465 -0.269258 0.211909 0.939465 -0.239921 0.244628 0.95576 -0.192074 0.222781 0.939465 -0.206639 0.273323 0.939465 -0.169957 0.297522 0.95576 -0.129224 0.264244 0.939465 -0.13048 0.316828 0.939465 -0.0888563 0.330922 0.95576 -0.0579061 0.288393 0.939465 -0.0457713 0.339574 0.937364 -0.290866 -0.191692 0.93932 -0.299172 -0.167853 0.950218 -0.276268 -0.144089 0.936415 -0.292916 -0.193204 0.936119 -0.293235 -0.194149 0.936392 -0.292281 -0.194275 0.939121 -0.325318 -0.11054 0.93894 -0.325827 -0.110584 0.969222 -0.22885 -0.0907587 0.939463 -0.32972 -0.093244 0.923944 -0.11367 -0.365249 0.937929 -0.0932905 -0.334046 0.93936 -0.0503726 -0.339213 0.93936 -0.0503726 -0.339213 0.939688 -0.0791376 -0.332751 0.0393801 -0.994336 -0.0987156 0 -0.995345 -0.0963795 0 -0.995345 -0.0963795 0.0122999 -0.995155 -0.097549 0 -0.995345 0.0963795 0 -0.995345 0.0963795 0.0158781 -0.995071 0.0978865 0.0438318 -0.994152 0.0986973 0.939692 -0.0238582 0.341189 0.939694 -0.0238593 0.341184 0.939674 -0.0238622 0.341238 0.939651 -0.0238662 0.341302 0.939694 -0.0238579 -0.341184 0.939692 -0.0238593 -0.341188 0.939684 -0.0238605 -0.341211 0.939651 -0.0238662 -0.341302 0.348174 -0.93743 0 0.348174 -0.93743 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.348174 -0.93743 0 0.348174 -0.93743 1.79168e-06 0.348173 -0.93743 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.925389 0.379019 -0.00296682 0.921412 0.388575 -0.000433248 0.909366 0.415997 0 0.904994 0.425424 -0.0215785 0.845449 -0.53362 0 0.789967 -0.61315 -0.618947 0.645566 -0.447381 -0.212648 0.815058 -0.538945 -0.0576515 0.83985 -0.539748 0 0.925389 -0.379019 -0.0248233 0.905801 -0.422975 -0.0121087 0.908484 -0.417744 -0.0166946 0.903121 -0.429062 -0.0135689 0.905612 -0.423891 0.000883466 0.877175 -0.480171 -0.00105018 0.851449 -0.524436 0.417983 0.908455 0 0.417983 0.908455 0 0.775214 0.631699 0 0.775214 0.631699 0 0.97414 0.225946 0 0.97414 0.225946 0 0.201912 0.979404 2.05406e-06 0.201912 0.979404 0 0.201912 0.979404 0 0.201912 0.979404 4.94475e-07 0.201912 0.979404 6.26971e-08 0.201913 0.979403 0 0.201913 0.979403 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.0445861 -0.910165 0.411839 0.0330398 -0.877589 0.478274 0.0114339 -0.886638 0.462323 0.00522301 -0.895975 0.444074 0.00101663 -0.904187 0.427135 -0.0037957 -0.945643 0.325185 0 -0.947242 0.32052 0.0330396 -0.877589 -0.478274 0.011434 -0.886638 -0.462323 0.0248236 -0.90598 -0.422593 0.00348124 -0.898519 -0.438922 0.000625757 -0.907968 -0.419038 -0.00401059 -0.947234 -0.320517 0 -0.94565 -0.325188 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258821 0.965925 0 0.258821 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.5 -0.377901 -0.779224 0.5 -0.3779 -0.779225 0.5 -0.3779 -0.779225 0.499999 -0.377902 -0.779224 0.5 -0.377901 0.779225 0.5 -0.377902 0.779224 0.499999 -0.377901 0.779225 0.500001 -0.377905 0.779222 0.5 -0.377903 0.779224 0 0.869008 -0.494798 0 0.869008 -0.494798 0 0.985153 -0.17168 0 0.985153 -0.17168 0 0.975403 0.22043 0.182714 0.861492 0.473758 0 0.949422 0.314003 0.0158393 0.984493 0.17471 0.0282965 0.994591 0.0999378 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 0.980785 -0.19509 -0.167723 0.952243 -0.255152 0.113099 0.826134 -0.552007 0 0.793352 -0.608763 0 0.55557 -0.83147 0.167725 0.600138 -0.782114 -0.220167 0.190304 -0.956719 0 0.258819 -0.965926 0.704917 -0.705955 0.0687022 0.704912 -0.705959 0.068704 0.704917 -0.705955 -0.0687022 0.705452 -0.705453 0.0683646 0.705445 -0.705445 -0.068513 0.704896 -0.706004 -0.068418 0.274245 -0.957372 0.0907158 0.576309 -0.813153 0.0815445 0.553782 -0.828779 0.0803161 0.0550081 -0.993838 0.0962336 0.194139 -0.976013 0.0985367 0.194215 -0.976392 -0.0945444 0.16699 -0.981095 -0.0978059 0.482465 -0.872026 -0.0824477 0.553601 -0.828508 -0.084263 0.66479 -0.743547 -0.0720563 0.980606 -0.195066 0.0190159 0.743841 -0.663822 0.0777231 0.873379 -0.484922 0.0453767 0.985685 -0.167538 0.0188913 0.814363 -0.577369 -0.0588025 0.830258 -0.554759 -0.0539881 0.830258 -0.554759 0.0539881 0.960769 -0.276215 -0.0250471 0.980531 -0.195052 -0.0226684 0.99845 -0.0553975 -0.00540038 0.995903 -0.0355543 -0.0831403 0.984134 -0.110225 -0.139035 0.98456 -0.0521713 -0.167094 0.984721 -0.051746 -0.166272 0.984719 -0.0255806 -0.172261 0.984719 -0.0255805 -0.172261 0.984809 -0.0121126 -0.173218 0.999638 0.0259395 -0.00710764 0.998321 0.0148996 -0.055981 0.988633 -0.00227442 -0.150329 0.962754 -0.0188607 -0.26972 0.965734 -0.249024 0.0731138 0.996173 -0.0838665 0.0246008 0.984607 -0.170195 0.0397933 0.984748 -0.159563 0.0693679 0.984748 -0.159563 0.0693679 0.984748 -0.149372 0.0892195 0.984748 -0.149372 0.0892194 0.984748 -0.136724 0.107604 0.984748 -0.136724 0.107604 0.984748 -0.121828 0.124218 0.984748 -0.121828 0.124218 0.984748 -0.104928 0.138789 0.984748 -0.104928 0.138789 0.984748 -0.0863012 0.151077 0.984748 -0.0863012 0.151077 0.984748 -0.0662554 0.16088 0.984748 -0.0662554 0.16088 0.984748 -0.0451198 0.168037 0.984748 -0.0451198 0.168037 0.984748 -0.0232419 0.17243 0.984748 -0.0232419 0.172429 0.962754 -0.0188607 0.26972 1 -6.69484e-05 0.000957403 0.984809 -0.0118715 0.173235 0.998321 0.0148998 0.0559801 0.988634 -0.00227443 0.150329 0.996179 -0.084046 -0.0237455 0.991179 -0.110536 -0.0731191 0.965926 -0.254315 -0.0480751 0.984771 -0.167294 -0.0473105 0.984769 -0.16162 -0.0640963 0.984769 -0.16162 -0.0640963 0.984769 -0.154158 -0.0804022 0.984769 -0.154158 -0.0804022 0.984659 -0.140737 -0.103149 0.952597 -0.254029 -0.167414 0 -0.999227 0.039301 0 -0.999227 0.039301 0 -0.935586 -0.353098 0 -0.935586 -0.353098 0 -0.724098 -0.689697 0 -0.724098 -0.689697 0 -0.398182 -0.917306 0 -0.398182 -0.917306 0 -0.398182 0.917306 0 -0.398182 0.917306 0 -0.724098 0.689697 0 -0.724098 0.689697 0 -0.935587 0.353098 0 -0.935587 0.353098 0 -0.999227 -0.039301 0 -0.999227 -0.039301 0.258815 -0.965927 0 0.290395 -0.956898 -0.0041903 0.146869 -0.989155 -0.00104957 0.0493997 -0.998779 0 0.246303 -0.969191 -0.00219192 0.608772 -0.793343 0.00201073 0.576489 -0.817105 0.000732467 0.793355 -0.60876 -0.000412637 0.850577 -0.525848 0.001441 0.965927 -0.258815 0 0.999831 -0.0144569 -0.0113489 0.981414 -0.191871 -0.00337051 0.0493997 -0.998779 0 0.195079 -0.980787 0 0.999987 -0.00505299 0 0.980785 -0.195093 0.000169622 0.981898 -0.189413 0.000342205 0.831476 -0.555561 -0.000373548 0.849684 -0.527292 0.000694576 0.555581 -0.831462 -0.000731427 0.576008 -0.817444 7.69557e-05 0.195673 -0.980669 -7.03345e-05 0.2907 -0.956807 0.00369877 0.146945 -0.989144 0.000926429 0.176876 -0.984233 0 0.176876 -0.984233 0 0.176876 -0.984233 0 0.176876 -0.984233 0 0.176876 -0.984233 0 0.176876 -0.984233 0 0.176876 -0.984233 0 0.176876 -0.984233 0 0 -0.735747 0.677257 -0.145262 -0.741764 0.65474 0.982697 -0.0808226 -0.166654 0.985671 -0.088106 -0.143843 0.856946 -0.20991 -0.470725 0.874853 -0.226264 -0.428295 0.638086 -0.320875 -0.699918 0.652029 -0.330849 -0.6822 0.874885 -0.225525 0.42862 0.959582 -0.115589 0.256596 0.985165 -0.104564 0.136077 0.995481 -0.0414353 0.0854386 0.854793 -0.21429 0.472661 0.635965 -0.352088 0.686718 0.65205 -0.33084 0.682185 0.63807 -0.33599 -0.692804 0.649852 -0.338175 -0.680684 0.855608 -0.219935 -0.468576 0.873175 -0.219905 -0.434979 0.985188 -0.065854 -0.158328 0.979016 -0.098586 -0.178352 0.999805 -0.00862111 -0.0177765 0.979123 -0.101137 0.176322 0.96572 -0.116211 0.232121 0.999805 -0.00862087 0.017776 0.855707 -0.220786 0.467995 0.639776 -0.35321 0.68259 0.708006 -0.308163 0.635424 0.488054 -0.864916 -0.117152 0.640821 -0.498219 0.58406 0.12575 -0.943045 -0.307982 0.366455 -0.930373 0.0108234 0.370311 -0.928795 0.0145125 0.546775 -0.771889 0.324383 0.858887 -0.37893 0.344566 0.85845 -0.380376 0.344059 0.731618 -0.670093 0.125342 0.133078 -0.943798 -0.302549 0.168269 -0.924476 -0.342095 0.175437 -0.923943 -0.339929 0.191419 -0.904469 -0.381176 0.195032 -0.903675 -0.381227 0.441259 -0.843415 -0.306498 0.546592 -0.7982 -0.253206 0.492565 -0.862646 -0.114986 0.729601 -0.672548 0.123943 0.547829 -0.770613 0.325636 0.641191 -0.497063 0.584639 0.967828 -0.242045 0.0687205 0.966472 -0.247784 0.0673403 0.887129 -0.459217 -0.0460684 0.818739 -0.565987 -0.0965656 0.786799 -0.603224 -0.130645 0.606016 -0.759204 -0.237391 0.498844 -0.550336 0.669541 0.498215 -0.555213 0.665973 0.435212 -0.819928 0.371898 0.429779 -0.829261 0.357233 0.29968 -0.953954 0.0128077 0.286033 -0.958118 -0.0139685 0.114696 -0.930294 -0.348421 0.0921024 -0.919289 -0.382655 0.494368 -0.546939 0.675617 0.493623 -0.551861 0.672151 0.426018 -0.814563 0.393695 0.420382 -0.824258 0.379312 0.291337 -0.955289 0.0504487 0.277599 -0.960401 0.023848 0.111349 -0.947206 -0.30067 0.0888338 -0.937846 -0.335489 0.98063 -0.185225 -0.0636946 0.965595 -0.245256 -0.0864603 0.896063 -0.419799 -0.144359 0.792134 -0.577175 -0.198477 0.70551 -0.669304 -0.232999 0.194295 -0.927629 -0.31899 0.257744 -0.913042 -0.316104 0.440745 -0.848845 -0.291899 0.607163 -0.751391 -0.258387 0.858058 -0.374057 0.351878 0.895883 -0.444217 0.00804567 0.727648 -0.677973 0.104314 0.120314 -0.910184 -0.396345 0.340313 -0.939441 -0.0404776 0.353129 -0.92236 -0.156687 0.999341 -0.0359553 -0.0049209 0.998225 0.0278063 0.0526671 0.946947 -0.321243 -0.00971978 0.965675 -0.241543 0.095544 0.846529 -0.411496 0.337727 0.799497 -0.572773 0.180931 0.70409 -0.710022 -0.0112566 0.643614 -0.497571 0.581535 0.633838 -0.522591 0.570217 0.56508 -0.774313 0.284822 0.551642 -0.788688 0.271407 0.448714 -0.892567 0.044501 0.563071 -0.825628 -0.0359176 0.253981 -0.385126 0.887227 0.699968 -0.284371 0.655116 0.96459 -0.105023 0.241945 0.964589 -0.105023 0.241945 0.964589 -0.190985 0.181912 0.964589 -0.190985 0.181912 0.964589 -0.246766 0.0931316 0.96459 -0.246766 0.0931313 0.96459 -0.263552 -0.0103658 0.96459 -0.263552 -0.0103658 0.699969 -0.284371 0.655116 0.699969 -0.517132 0.492563 0.699969 -0.517132 0.492563 0.699969 -0.668171 0.252173 0.699968 -0.668171 0.252173 0.699968 -0.713622 -0.0280677 0.699969 -0.713622 -0.0280678 0.25398 -0.385126 0.887227 0.25398 -0.700355 0.667081 0.25398 -0.700355 0.667081 0.25398 -0.904908 0.341519 0.25398 -0.904908 0.341519 0.25398 -0.966462 -0.0380124 0.25398 -0.966462 -0.0380123 0.804858 -0.580365 0.124016 0.999988 -0.00495106 0.00066618 0.999809 -0.0024225 0.019411 0.983344 -0.139088 0.117002 0.987573 -0.156941 -0.00830632 0.808177 -0.58641 0.0545364 0.930134 -0.366693 0.0196897 0.993396 -0.0829794 0.0792355 0.995596 -0.0937171 0.00241537 0.99952 -0.0306946 0.00420265 0.991943 -0.126271 -0.0102664 0.975078 -0.221859 -0.00128226 0.79342 -0.602227 -0.0883592 0.462259 -0.88139 -0.0973031 0.602666 -0.787833 -0.126933 0.928728 -0.365656 0.0613226 0.929462 -0.368882 0.00506022 0.992015 -0.124794 0.0182264 0.99952 -0.0308192 0.00329437 0.252567 -0.906585 -0.338103 0.45925 -0.803088 -0.379658 0.697376 -0.672727 -0.247194 0.789882 -0.555444 -0.259939 0.963679 -0.252932 -0.0857226 0.975913 -0.200078 -0.0869689 0.258809 -0.200828 0.944821 0.258808 -0.200828 0.944821 0.707129 -0.147011 0.691633 0.707129 -0.147011 0.691633 0.965918 -0.0538178 0.253193 0.965918 -0.0538178 0.253193 0.25791 -0.915196 -0.309676 0.257911 -0.915195 -0.309676 0.705764 -0.671071 -0.227071 0.705763 -0.671071 -0.227072 0.96568 -0.246033 -0.0832505 0.96568 -0.246033 -0.0832506 0.257935 -0.848357 -0.462343 0.257932 -0.848357 -0.462343 0.705794 -0.622039 -0.339003 0.705796 -0.622037 -0.339002 0.965686 -0.228047 -0.124282 0.965686 -0.228047 -0.124282 0.964268 -0.105002 0.243232 0.964494 -0.106825 0.241536 0.706059 -0.184337 0.68374 0.706573 -0.185681 0.682846 0.258573 -0.214315 0.941918 0.258782 -0.214814 0.941747 0.928388 -0.313325 0.199808 0.928808 -0.314813 0.19547 0.682617 -0.33703 0.648417 0.683887 -0.338451 0.646335 0.251306 -0.270675 0.92929 0.251859 -0.271303 0.928957 0.787513 -0.599612 0.142436 0.787197 -0.6009 0.138706 0.578351 -0.546842 0.605372 0.578863 -0.548316 0.603545 0.21285 -0.347781 0.913096 0.213107 -0.348445 0.912782 0.964597 -0.105012 0.24192 0.964597 -0.105012 0.24192 0.964597 -0.190965 0.181893 0.964597 -0.190965 0.181893 0.964597 -0.246741 0.0931217 0.964597 -0.246741 0.0931217 0.964597 -0.263525 -0.0103646 0.964597 -0.263525 -0.0103649 0.69994 -0.284382 0.655142 0.69994 -0.284383 0.655142 0.69994 -0.517152 0.492583 0.699939 -0.517153 0.492583 0.699939 -0.668198 0.252183 0.699939 -0.668198 0.252183 0.699939 -0.713651 -0.028069 0.699939 -0.713651 -0.0280688 0.253994 -0.385124 0.887224 0.253994 -0.385124 0.887224 0.253994 -0.700352 0.667079 0.253994 -0.700352 0.667079 0.253994 -0.904905 0.341518 0.253995 -0.904905 0.341518 0.253995 -0.966458 -0.0380121 0.253995 -0.966458 -0.0380122 0.681342 -0.722005 0.120342 0.68135 -0.722042 0.120074 0.497237 -0.634122 0.592153 0.497289 -0.634197 0.592028 0.18176 -0.378681 0.907504 0.181783 -0.378715 0.907485 0.681293 -0.722013 0.120572 0.6813 -0.722045 0.120333 0.497175 -0.634076 0.592254 0.497219 -0.63414 0.592149 0.181729 -0.378649 0.907524 0.181755 -0.378686 0.907503 0.195095 -0.203917 0.959352 0.258776 -0.219174 0.940743 0.442288 -0.18647 0.877274 0.608754 -0.164949 0.776022 0.706878 -0.171513 0.686226 0.793348 -0.12657 0.595465 0.896896 -0.0919472 0.432577 0.965755 -0.0721796 0.249216 0.980781 -0.0405665 0.19085 0.643147 -0.757258 0.113675 0.642134 -0.758299 0.112459 0.469479 -0.659867 0.586656 0.468972 -0.6608 0.586011 0.171797 -0.388102 0.905463 0.171633 -0.388469 0.905336 0.467645 -0.879663 0.0866054 0.466915 -0.880277 0.0842837 0.343001 -0.751518 0.563535 0.342795 -0.75249 0.562362 0.126186 -0.422929 0.897334 0.126136 -0.423386 0.897125 0.161968 -0.984647 0.0650917 0.1616 -0.98476 0.0642953 0.11876 -0.828279 0.547586 0.118556 -0.828571 0.547188 0.0436865 -0.451125 0.891391 0.043615 -0.451267 0.891323 0.195391 -0.220591 0.955595 0.97761 -0.124028 0.169986 0.977242 -0.123433 0.172516 0.195067 -0.220448 0.955694 0.441956 -0.224196 0.868569 0.558295 -0.202702 0.804499 0.607899 -0.21654 0.763917 0.830166 -0.186228 0.525493 0.792719 -0.165418 0.586714 0.894159 -0.168034 0.415024 0.189783 -0.253595 0.94851 0.189479 -0.25339 0.948626 0.539637 -0.313983 0.781157 0.538942 -0.313501 0.78183 0.805809 -0.326089 0.494306 0.805085 -0.325442 0.495909 0.94827 -0.288405 0.132693 0.948109 -0.287777 0.135184 0 -0.997822 0.0659627 0 -0.997822 0.0659627 0 -0.834182 0.551489 0 -0.834182 0.551489 0 -0.451556 0.892243 0 -0.451556 0.892243 0.129166 -0.251918 0.95909 0.178682 -0.283472 0.942187 0.778815 -0.405099 0.478897 0.653777 -0.372971 0.658383 0.518475 -0.372898 0.7695 0.450748 -0.342716 0.82424 0.308116 -0.30619 0.900729 0.922533 -0.367948 0.116393 0.924625 -0.380487 -0.0173004 0.918005 -0.378907 0.117036 0.895303 -0.383046 0.227393 0.826833 -0.390469 0.404822 0.922511 -0.367973 0.116487 0.92252 -0.367982 0.116385 0.783103 -0.393676 0.481424 0.783131 -0.393692 0.481365 0.523651 -0.359034 0.772582 0.523699 -0.359061 0.772538 0.183956 -0.269369 0.945304 0.183961 -0.269373 0.945302 0.316436 -0.909335 0.270146 0.244246 -0.958875 0.144576 0.169885 -0.985257 -0.0202141 0.104947 -0.994478 0.000608216 0.483207 -0.801712 0.351809 0.580499 -0.5912 0.559913 0.812531 -0.52692 0.249296 0.784969 -0.53224 0.317087 0.182737 -0.443953 0.877219 0.0921913 -0.995173 0.0336374 0.0309209 -0.998288 0.0496482 0.050074 -0.99657 0.06588 0.453341 -0.842981 0.289596 0.24573 -0.871585 0.424212 0.304318 -0.83966 0.449846 0.0713043 -0.855388 0.513057 0.128741 -0.82724 0.5469 0.0856722 -0.514568 0.853159 0.349135 -0.504284 0.789812 0.342651 -0.506753 0.79107 0.473811 -0.56421 0.676144 0.6437 -0.531684 0.55042 0.32532 -0.930248 0.169725 0.591117 -0.706899 0.388426 0.240005 -0.882194 0.405131 0.230746 -0.79476 0.56135 0.686461 -0.720279 -0.0998446 0.744609 -0.664503 -0.0631938 0.636725 -0.768879 0.0583624 0.704601 -0.695688 0.139842 0.613096 -0.750024 0.248148 0.834479 -0.498905 -0.233965 0.885054 -0.421654 -0.197199 0.885403 -0.420224 -0.198678 0.903479 -0.39717 -0.161192 0.871508 -0.47812 -0.108968 0.884567 -0.461442 -0.0679191 0.881064 -0.469669 -0.0560046 0.174379 -0.753116 0.634357 0.229492 -0.797025 0.558645 0.402666 -0.752773 0.520762 0.561101 -0.71169 0.422685 0.635573 -0.713978 0.29374 0.737334 -0.622337 0.262748 0.838991 -0.528005 0.131553 0.891363 -0.451951 -0.0348218 0.929004 -0.367416 -0.0442341 0.195024 -0.711388 0.675198 0.96647 -0.24558 0.0750118 0.972163 -0.230297 0.0431586 0.878608 -0.408268 0.24772 0.827777 -0.457722 0.324463 0.19063 -0.710457 0.67743 0.431204 -0.677078 0.596346 0.554593 -0.628738 0.545083 0.594306 -0.619764 0.512536 0.774797 -0.514216 0.367793 0.965925 -0.183015 0.183015 0.980778 -0.134776 0.141103 0.793374 -0.432816 0.428051 0.831477 -0.39284 0.39284 0.608755 -0.560989 0.560989 0.555564 -0.589534 0.586344 0.258813 -0.680626 0.685394 0.195088 -0.69352 0.69352 0.783031 -0.538653 0.310991 0.188678 -0.850471 -0.491019 0.595444 -0.695762 -0.401698 0.430047 -0.781854 -0.451403 0.249836 -0.833072 -0.493531 0.250558 -0.968102 0 0.250558 -0.968102 0 0.250558 -0.8384 0.484051 0.250558 -0.8384 0.484051 0.890618 -0.393828 -0.227376 0.783031 -0.538653 -0.310991 0.692804 -0.617373 -0.372658 0.694755 -0.719246 0 0.694755 -0.719246 0 0.694755 -0.622885 0.359623 0.598659 -0.67993 0.423442 0.979451 -0.174663 -0.100842 0.962869 -0.22864 -0.143548 0.96361 -0.267311 0 0.96361 -0.267311 0 0.96361 -0.231498 0.133655 0.96361 -0.231498 0.133655 0.980788 -0.137941 -0.137941 0.980788 -0.137941 -0.137941 0.896851 -0.312776 -0.312776 0.89685 -0.312778 -0.312778 0.793379 -0.430436 -0.430436 0.793379 -0.430436 -0.430436 0.608748 -0.560993 -0.560993 0.608753 -0.56099 -0.56099 0.442294 -0.634183 -0.634183 0.442282 -0.634187 -0.634187 0.195091 -0.69352 -0.69352 0.195083 -0.693521 -0.693521 0.254166 -0.537326 -0.804164 0.192166 -0.561137 -0.805107 0.435406 -0.500144 -0.748517 0.700222 -0.396636 -0.593607 0.254163 -0.188684 -0.948578 0.254166 -0.188683 -0.948577 0.700225 -0.139279 -0.700204 0.700222 -0.139281 -0.700207 0.964647 -0.0514154 -0.258481 0.964647 -0.0514148 -0.25848 0.604344 -0.471971 -0.641881 0.787626 -0.342316 -0.512313 0.964647 -0.146417 -0.219129 0.896197 -0.28557 -0.33953 0.98005 -0.110419 -0.165254 0.258811 0 -0.965928 0.258811 0 -0.965928 0.707118 0 -0.707096 0.707118 0 -0.707096 0.965925 0 -0.258823 0.965925 0 -0.258823 0.918499 -0.0805759 -0.387128 0.856679 -0.0971311 -0.506623 0.644894 -0.0554144 -0.76226 0.580496 -0.0650472 -0.811661 0.231829 -0.0175426 -0.972598 0.205418 -0.021088 -0.978447 0.965758 -0.0185658 -0.258779 0.921 -0.0438005 -0.387092 0.707058 -0.0129598 -0.707037 0.646668 -0.029478 -0.762201 0.258811 -0.00218751 -0.965926 0.232468 -0.00834416 -0.972568 0.579416 -0.0733984 -0.81172 0.3096 -0.0385504 -0.950085 0.195398 -0.0159106 -0.980595 0.204589 -0.027287 -0.978468 0.859739 -0.0852252 -0.503573 0.803904 -0.0677567 -0.590887 0.853721 -0.0918294 -0.51257 0.62103 -0.0646958 -0.781112 0.623016 -0.0441687 -0.780961 0.564022 -0.0691708 -0.822858 0.852195 -0.105167 -0.512547 0.855719 -0.104985 -0.506679 0.493888 -0.551788 -0.672015 0.494096 -0.547006 -0.675762 0.421184 -0.824029 -0.378919 0.425199 -0.814786 -0.394119 0.278933 -0.960031 -0.0231835 0.289971 -0.955667 -0.0511544 0.0906988 -0.93733 0.336431 0.109432 -0.947739 0.299691 0.498489 -0.55513 -0.665837 0.498562 -0.550423 -0.669679 0.430606 -0.829002 -0.35684 0.434369 -0.820181 -0.372328 0.28741 -0.957696 0.0146347 0.298273 -0.954385 -0.0135146 0.0940269 -0.918702 0.383596 0.11272 -0.930902 0.347443 0.96374 -0.253997 -0.0818024 0.195014 -0.905112 0.377812 0.191163 -0.905103 0.379797 0.441033 -0.845975 0.299693 0.54564 -0.801185 0.245723 0.964682 -0.249051 -0.0858077 0.884952 -0.464619 0.0314523 0.816847 -0.570681 0.0841675 0.78532 -0.607794 0.117729 0.605384 -0.76268 0.22766 0.841149 -0.393418 -0.371066 0.841197 -0.392571 -0.371854 0.715375 -0.683332 -0.145933 0.716485 -0.681607 -0.148527 0.479085 -0.871612 0.103777 0.482146 -0.870436 0.0993778 0.166126 -0.925748 0.339696 0.171345 -0.926865 0.334008 0.627419 -0.502779 -0.594608 0.627506 -0.503787 -0.593662 0.535265 -0.776876 -0.331595 0.535544 -0.776018 -0.33315 0.359303 -0.933106 -0.014666 0.360883 -0.932411 -0.0193396 0.125048 -0.943255 0.307627 0.128305 -0.945193 0.300247 0.541455 -0.83944 0.046561 0.90979 -0.394799 -0.128123 0.929526 -0.313226 -0.194603 0.961242 -0.269104 -0.0599707 0.946947 -0.321243 0.00971978 0.998225 0.0278063 -0.0526671 0.999341 -0.0359579 0.00492329 0.686376 -0.711816 -0.149014 0.71761 -0.694747 -0.048594 0.710289 -0.703758 -0.0146484 0.8501 -0.381787 -0.362724 0.854605 -0.403927 -0.326335 0.642411 -0.51871 -0.564134 0.635133 -0.501634 -0.587341 0.558186 -0.785883 -0.266113 0.558213 -0.777777 -0.288896 0.35035 -0.927907 0.127452 0.340313 -0.93944 0.0404777 0.120318 -0.910184 0.396344 0.965644 -0.245746 0.0845064 0.896324 -0.416666 0.151633 0.98063 -0.185225 0.0636946 0.257789 -0.913688 0.314197 0.194341 -0.926748 0.321511 0.440745 -0.848846 0.291899 0.705636 -0.670063 0.23042 0.607391 -0.749484 0.263345 0.792134 -0.577175 0.198477 0.703958 -0.638973 0.310093 0.986954 -0.14657 -0.0666281 0.987573 -0.156941 0.00830615 0.941238 -0.335802 -0.0361582 0.808338 -0.587092 -0.0437337 0.806959 -0.589888 0.0291418 0.466242 -0.879776 0.0928062 0.46199 -0.882016 0.0928047 0.465891 -0.856449 0.222352 0.257743 -0.852377 0.454996 0.794881 -0.58228 0.170628 0.789847 -0.612062 0.0390269 0.928227 -0.37044 0.0341924 0.929556 -0.368174 -0.0193552 0.995623 -0.0913203 -0.0199107 0.995603 -0.0936222 -0.00311158 0.999978 -0.00438054 -0.00494297 0.999988 -0.00495189 -0.000666291 0.99952 -0.0306948 -0.00420268 0.99934 -0.0281101 -0.0230161 0.99206 -0.125053 -0.0133674 0.991998 -0.12472 -0.0196061 0.975829 -0.217818 0.0177096 0.976473 -0.207105 0.0600627 0.964918 -0.240789 0.104665 0.25398 -0.966462 0.0380124 0.699969 -0.713622 0.0280677 0.980021 -0.0791958 -0.182446 0.963027 -0.0843824 -0.255849 0.96459 -0.190985 -0.181911 0.96459 -0.190985 -0.181912 0.964589 -0.246766 -0.0931315 0.96459 -0.246766 -0.0931315 0.96459 -0.263552 0.0103658 0.96459 -0.263552 0.0103658 0.699968 -0.713622 0.0280678 0.699968 -0.668172 -0.252173 0.699969 -0.668171 -0.252173 0.699968 -0.517132 -0.492564 0.699968 -0.517132 -0.492564 0.893218 -0.179033 -0.412444 0.787399 -0.245457 -0.565467 0.695755 -0.25189 -0.672663 0.601049 -0.318232 -0.733122 0.435103 -0.358516 -0.825925 0.25398 -0.966462 0.0380123 0.25398 -0.904908 -0.34152 0.25398 -0.904908 -0.34152 0.25398 -0.700355 -0.667081 0.25398 -0.700355 -0.667081 0.252362 -0.357453 -0.899189 0.191338 -0.390826 -0.900358 0.257931 -0.848357 0.462343 0.257932 -0.848357 0.462343 0.705796 -0.622037 0.339002 0.705796 -0.622037 0.339002 0.965686 -0.228047 0.124282 0.965685 -0.228047 0.124283 0.257912 -0.915195 0.309676 0.25791 -0.915196 0.309676 0.705763 -0.671071 0.227072 0.705764 -0.671071 0.227071 0.96568 -0.246033 0.0832506 0.96568 -0.246033 0.0832505 0.195087 -0.203917 -0.959353 0.195087 -0.203917 -0.959353 0.442243 -0.186475 -0.877296 0.442243 -0.186475 -0.877296 0.608779 -0.164945 -0.776003 0.608779 -0.164945 -0.776003 0.793377 -0.126562 -0.595428 0.793377 -0.126562 -0.595428 0.896806 -0.0919851 -0.432756 0.896806 -0.0919853 -0.432756 0.980788 -0.0405589 -0.190814 0.980788 -0.0405589 -0.190814 0.787371 -0.245471 -0.5655 0.964597 -0.263525 0.0103646 0.964597 -0.263525 0.0103648 0.964597 -0.246741 -0.0931222 0.964597 -0.246741 -0.0931218 0.964597 -0.190965 -0.181893 0.964597 -0.190965 -0.181892 0.964597 -0.105012 -0.241919 0.964597 -0.105012 -0.24192 0.699939 -0.713651 0.028069 0.699939 -0.713651 0.0280688 0.69994 -0.668198 -0.252183 0.699939 -0.668198 -0.252183 0.699939 -0.517153 -0.492583 0.699939 -0.517153 -0.492583 0.704115 -0.327908 -0.62984 0.601023 -0.318241 -0.73314 0.253995 -0.966458 0.0380121 0.253995 -0.966458 0.0380121 0.253995 -0.904904 -0.341518 0.253995 -0.904904 -0.341518 0.253995 -0.700352 -0.667079 0.253995 -0.700352 -0.667079 0.253995 -0.385125 -0.887223 0.253994 -0.385124 -0.887224 0.524148 -0.607092 -0.597251 0.228047 -0.324342 -0.91804 0.192231 -0.368654 -0.909473 0.191828 -0.368832 -0.909486 0.621676 -0.482432 -0.617073 0.19498 -0.236278 -0.951922 0.247424 -0.273307 -0.929562 0.228864 -0.324222 -0.917879 0.619668 -0.483102 -0.618566 0.525204 -0.606499 -0.596926 0.717573 -0.684689 -0.127635 0.440998 -0.259289 -0.859238 0.605516 -0.265195 -0.750347 0.690486 -0.298737 -0.658776 0.786281 -0.255962 -0.562357 0.886496 -0.238825 -0.396343 0.718928 -0.683414 -0.126842 0.843484 -0.512799 -0.159912 0.845268 -0.510863 -0.156655 0.947064 -0.237793 -0.215696 0.967538 -0.200251 -0.154176 0.195092 -0.203917 -0.959352 0.258776 -0.219174 -0.940743 0.555521 -0.16056 -0.815853 0.608754 -0.164949 -0.776022 0.831476 -0.115507 -0.54342 0.793209 -0.10816 -0.599267 0.980476 -0.0649302 -0.18561 0.965925 -0.0538121 -0.253166 0.681338 -0.722009 -0.120341 0.681256 -0.722049 -0.120564 0.497239 -0.63412 -0.592153 0.497155 -0.634096 -0.592249 0.181761 -0.378678 -0.907505 0.181722 -0.378656 -0.907522 0.681392 -0.722001 -0.120083 0.6813 -0.722046 -0.120333 0.497313 -0.634174 -0.592034 0.497214 -0.634145 -0.592148 0.181791 -0.378708 -0.907487 0.181752 -0.378687 -0.907503 0.189455 -0.253522 -0.948595 0.189828 -0.253467 -0.948536 0.53886 -0.313892 -0.78173 0.539767 -0.313599 -0.781222 0.804912 -0.326144 -0.495729 0.806021 -0.325386 -0.494424 0.947841 -0.288763 -0.134956 0.948543 -0.287415 -0.132886 0.195064 -0.220578 -0.955665 0.195413 -0.220463 -0.95562 0.554906 -0.220287 -0.802217 0.555811 -0.219822 -0.801719 0.829269 -0.186431 -0.526837 0.830248 -0.185525 -0.525613 0.977153 -0.124469 -0.172278 0.977706 -0.122988 -0.170189 0.0533304 -0.996408 -0.0657851 0.0531935 -0.996409 -0.0658693 0.0388897 -0.833577 -0.551032 0.0387993 -0.833554 -0.551074 0.0142279 -0.451523 -0.892146 0.0141959 -0.451511 -0.892153 0.266143 -0.961483 -0.0686921 0.265409 -0.961597 -0.0699301 0.195227 -0.811649 -0.550557 0.194661 -0.811368 -0.55117 0.0718204 -0.445058 -0.892617 0.0716049 -0.444899 -0.892714 0.558473 -0.824029 -0.0953067 0.556946 -0.824775 -0.0977579 0.410027 -0.711462 -0.570701 0.408637 -0.711307 -0.57189 0.150875 -0.408308 -0.90029 0.150326 -0.40814 -0.900457 0.938198 -0.345751 0.0155131 0.91833 -0.379037 -0.114022 0.912172 -0.376917 -0.160862 0.85555 -0.389388 -0.341191 0.779455 -0.40343 -0.479263 0.73173 -0.383709 -0.563328 0.520649 -0.367188 -0.770777 0.477572 -0.343483 -0.808668 0.181797 -0.275174 -0.944049 0.165582 -0.263601 -0.950314 0.183953 -0.269371 -0.945305 0.183961 -0.269371 -0.945303 0.523646 -0.35905 -0.772579 0.523704 -0.359045 -0.772541 0.783098 -0.393691 -0.48142 0.783136 -0.393677 -0.481369 0.922502 -0.367996 -0.116482 0.922529 -0.367959 -0.11639 0 -0.451556 -0.892243 0 -0.451556 -0.892243 0 -0.834182 -0.551489 0 -0.834182 -0.551489 0 -0.997822 -0.0659627 0 -0.997822 -0.0659627 0.830869 -0.471779 -0.295096 0.712019 -0.517364 -0.474724 0.715537 -0.53164 -0.453173 0.561336 -0.810366 -0.167958 0.482755 -0.826388 -0.28988 0.53928 -0.752449 -0.378152 0.098412 -0.994839 -0.0247014 0.117339 -0.993033 0.0108454 0.311644 -0.847736 -0.429211 0.336602 -0.869643 -0.361137 0.417527 -0.515822 -0.748063 0.496246 -0.578973 -0.646939 0.0425568 -0.996918 -0.065903 0.0569595 -0.99762 -0.038861 0.0983959 -0.830134 -0.548813 0.155693 -0.861005 -0.48418 0.111066 -0.448763 -0.886722 0.235935 -0.530557 -0.814152 0.256745 0.588356 -0.766759 0.250559 0.935114 -0.250563 0.250558 0.935114 -0.250563 0.694755 0.694739 -0.186155 0.694755 0.694739 -0.186155 0.963611 0.258202 -0.0691851 0.963611 0.258202 -0.069185 0.256744 0.766758 -0.588357 0.12161 0.701859 -0.701859 0.694754 0.508584 -0.508584 0.694756 0.508584 -0.508583 0.963611 0.189017 -0.189017 0.963611 0.189017 -0.189017 0.250557 0.250563 -0.935115 0.250555 0.250563 -0.935115 0.694756 0.186154 -0.694738 0.694758 0.186154 -0.694736 0.963611 0.0691851 -0.258202 0.96361 0.069185 -0.258203 0.980788 0.195077 0 0.965923 0.258821 0.00226172 0.896851 0.442333 0 0.793377 0.60873 0 0.707112 0.707095 0.00301973 0.195086 0.980786 0 0.258814 0.965925 0.0022612 0.442288 0.896873 0 0.608753 0.79336 0 0.221845 0.973629 0.0532138 0.962254 0.191391 0.193484 0.966135 0.00465139 0.257995 0.879307 0.43368 0.196828 0.882814 0.425411 0.199161 0.194924 0.979975 0.0406725 0.439779 0.891783 0.106381 0.618242 0.773223 0.141077 0.603299 0.786252 0.133556 0.77881 0.597553 0.190749 0.186673 0.968032 0.167535 0.172954 0.973755 0.147947 0.504842 0.730586 0.459759 0.4795 0.774678 0.412254 0.694872 0.330026 0.638933 0.687724 0.427591 0.586687 0.72372 -0.137959 0.676164 0.764501 0.00464201 0.644606 0.130882 0.970188 0.203973 0.130882 0.970188 0.203973 0.361896 0.742252 0.563997 0.361901 0.742245 0.564003 0.507886 0.339939 0.791513 0.507886 0.33994 0.791513 0.534555 -0.142256 0.833075 0.534556 -0.14224 0.833078 0.517694 -0.153062 0.841763 0.514708 -0.163616 0.841609 0.47153 0.309147 0.825886 0.469353 0.278588 0.837912 0.324502 0.704553 0.631114 0.329842 0.665541 0.669522 0.109003 0.947979 0.29909 0.123134 0.92081 0.370063 0.528856 -0.142237 0.836708 0.525316 -0.15261 0.83711 0.495134 0.339901 0.799569 0.49184 0.310373 0.813488 0.346163 0.742117 0.573963 0.350543 0.706145 0.615206 0.117665 0.970069 0.212419 0.131269 0.949356 0.285466 0.844637 -0.0512233 0.532884 0.844608 -0.0429703 0.533659 0.723272 0.336721 0.602906 0.727995 0.321901 0.605313 0.476262 0.670709 0.568615 0.497239 0.640383 0.585374 0.145822 0.889546 0.432947 0.186468 0.859563 0.475795 0.640734 -0.14634 0.753688 0.644477 -0.120779 0.755024 0.56841 0.288142 0.770639 0.568937 0.282601 0.7723 0.384046 0.669995 0.635307 0.394142 0.641116 0.6585 0.123112 0.920808 0.370076 0.147198 0.890057 0.43143 0.977085 0.134508 0.164959 0.976497 0.138618 0.165039 0.830233 0.468422 0.302148 0.828701 0.471285 0.301902 0.556431 0.731685 0.393727 0.554666 0.733316 0.393184 0.196335 0.883519 0.42526 0.195033 0.884102 0.424647 0.941869 0.0548451 0.331474 0.941717 0.0572444 0.331499 0.80054 0.398713 0.447396 0.799501 0.401221 0.447011 0.536775 0.68287 0.495541 0.535038 0.684905 0.49461 0.189868 0.863109 0.467967 0.187623 0.864478 0.466343 0.194972 0.90763 0.371745 0.2587 0.895771 0.36148 0.555379 0.768274 0.318291 0.608545 0.734314 0.300759 0.831301 0.514352 0.210667 0.793101 0.561717 0.235511 0.980698 0.183368 0.067879 0.965878 0.239674 0.098165 0.194972 0.90763 -0.371745 0.19497 0.90763 -0.371745 0.555328 0.769583 -0.315204 0.555329 0.769582 -0.315203 0.831301 0.514352 -0.210667 0.8313 0.514353 -0.210668 0.980765 0.180629 -0.0739817 0.980765 0.180629 -0.0739817 0.639078 -0.153986 -0.75357 0.174937 0.771407 -0.611824 0.112739 0.802563 -0.585817 0.413934 0.499219 -0.761209 0.363108 0.552435 -0.750312 0.519015 0.270948 -0.810685 0.549038 0.216798 -0.80719 0.584797 0.0903802 -0.806129 0.638701 -0.15284 -0.754122 0.858392 -0.0324189 -0.511969 0.858814 -0.0336677 -0.51118 0.729797 0.320572 -0.603846 0.731745 0.318045 -0.602823 0.489301 0.628097 -0.605044 0.493676 0.625087 -0.604607 0.170736 0.841374 -0.512776 0.177716 0.839397 -0.513643 0.967025 0.106673 -0.231266 0.968325 0.102079 -0.227873 0.822601 0.441169 -0.358744 0.82553 0.43766 -0.356306 0.552658 0.711939 -0.433258 0.556306 0.709967 -0.431822 0.194909 0.875652 -0.441865 0.198435 0.875174 -0.441241 0.137072 0.733029 -0.666243 0.48661 -0.198257 -0.850826 0.476769 -0.144659 -0.867044 0.115681 0.756848 -0.643272 0.292557 0.470816 -0.832312 0.347255 0.334792 -0.875973 0.38619 0.237605 -0.891292 0.440613 0.0516179 -0.896212 0.133636 0.701018 -0.700511 0.112232 0.725806 -0.678683 0.344091 0.309918 -0.886314 0.334034 0.330937 -0.882554 0.47504 -0.153012 -0.866559 0.47331 -0.145665 -0.868769 0.165846 0.700051 -0.694567 0.153126 0.706862 -0.690578 0.449031 0.321179 -0.833795 0.432079 0.336735 -0.836611 0.622397 -0.128691 -0.77205 0.606374 -0.106958 -0.787954 0.224902 0.726668 -0.649132 0.209655 0.730797 -0.6496 0.610534 0.40323 -0.681655 0.587568 0.417862 -0.692933 0.840077 -0.0163556 -0.542221 0.82017 0.00763863 -0.572069 0.258665 0.760023 -0.596203 0.245733 0.760985 -0.60043 0.703012 0.504696 -0.501054 0.679423 0.516042 -0.521618 0.955114 0.118909 -0.271328 0.938101 0.142983 -0.315472 0.980771 0.154172 -0.119664 0.965923 0.208019 -0.154015 0.896772 0.349554 -0.271314 0.793244 0.481014 -0.37335 0.707051 0.563393 -0.427396 0.195003 0.774802 -0.601379 0.258745 0.766628 -0.58765 0.442131 0.708561 -0.549965 0.60858 0.626833 -0.48653 0.192294 0.966767 -0.168476 0.192297 0.966767 -0.168475 0.436992 0.886111 -0.154419 0.54926 0.8244 -0.136671 0.192294 0.85279 -0.485563 0.192299 0.85279 -0.485562 0.549826 0.725865 -0.413294 0.827054 0.55487 -0.090004 0.788951 0.605333 -0.105489 0.603014 0.785887 -0.136953 0.438279 0.770931 -0.462144 0.603017 0.693233 -0.394714 0.827606 0.487783 -0.277734 0.980222 0.194964 -0.0339757 0.980222 0.194965 -0.0339759 0.894199 0.441023 -0.0768557 0.789733 0.528224 -0.311932 0.894199 0.389028 -0.221505 0.980222 0.171979 -0.0979216 0.980222 0.17198 -0.097922 0.980788 0.195078 0 0.965883 0.258811 -0.00935694 0.896852 0.442331 0 0.793378 0.60873 0 0.707059 0.707044 -0.0124928 0.60875 0.793362 0 0.442297 0.896869 0 0.258803 0.965885 -0.00935535 0.195082 0.980787 0 0.250562 0.250562 0.935114 0.250556 0.250565 0.935114 0.694754 0.186157 0.69474 0.694756 0.186155 0.694738 0.963611 0.069185 0.258202 0.963611 0.0691852 0.258202 0.250556 0.684552 0.684552 0.250556 0.684552 0.684552 0.694755 0.508584 0.508584 0.694754 0.508585 0.508584 0.963611 0.189017 0.189017 0.963611 0.189017 0.189017 0.250559 0.935114 0.250564 0.250559 0.935114 0.250564 0.694754 0.694739 0.186156 0.694754 0.69474 0.186155 0.963611 0.258202 0.0691852 0.96361 0.258202 0.0691851 0.999992 -0.00402972 2.02129e-05 0.998672 -0.0174763 0.0484666 0.997656 -0.0556306 0.0398498 0.987749 -0.080488 0.133691 0.982634 -0.127492 0.134823 0.999992 -0.00402268 2.38245e-05 0.998116 -0.0201819 0.0579451 0.985505 -0.168767 -0.0172292 0.974968 -0.199544 0.0980768 0.931583 -0.358834 0.0582453 0.718524 -0.618681 0.31774 0.827005 -0.559914 -0.0505946 0.942189 -0.322665 0.0903692 0.957371 -0.27028 -0.101931 0.994891 -0.034302 0.0949499 0.99997 -0.00728537 -0.00269394 0.374852 -0.916663 0.13862 0.648489 -0.760775 -0.0261511 0.759884 -0.636988 0.129701 0.902775 -0.386881 0.187938 0.934462 -0.243219 0.260049 0.956408 -0.152657 0.248956 0.908213 -0.26307 0.32549 0.877638 -0.277312 0.39096 0.712975 -0.678911 0.175346 0.615558 -0.711231 0.339469 0.351406 -0.936189 -0.00796872 0.187976 -0.956856 0.221566 0.914414 -0.247977 0.31993 0.885606 -0.264575 0.38171 0.747763 -0.641877 0.169837 0.656041 -0.681753 0.323763 0.426669 -0.90439 -0.00561838 0.271483 -0.939835 0.207379 0.65107 -0.715401 0.253593 0.243911 -0.966874 0.0752499 0.936266 -0.0885901 0.339939 0.920386 -0.213156 0.327803 0.907116 -0.277932 0.316061 0.860838 -0.401443 0.312734 0.633291 -0.739091 0.229537 0.374855 -0.916662 -0.138618 0.999992 -0.00402268 -2.38354e-05 0.994747 -0.0312055 -0.0974882 0.985542 -0.168426 0.0184565 0.959395 -0.219262 -0.177439 0.937058 -0.348732 -0.0175707 0.999992 -0.00402976 -2.02039e-05 0.998116 -0.0202175 -0.057927 0.997672 -0.0555522 -0.0395565 0.984101 -0.0861549 -0.155317 0.984405 -0.124987 -0.123792 0.585564 -0.810464 -0.0162015 0.942336 -0.240734 -0.232487 0.941171 -0.162654 -0.296211 0.781332 -0.622651 -0.0427375 0.848384 -0.410502 -0.334265 0.779353 -0.604864 -0.16355 0.833524 -0.539588 0.118674 0.908386 -0.352182 -0.225394 0.957326 -0.269648 0.104009 0.985299 -0.0529262 -0.162432 0.99997 -0.00728503 0.00269517 0.910985 -0.262795 -0.317875 0.886944 -0.252206 -0.386939 0.7226 -0.676151 -0.143766 0.672474 -0.649395 -0.355056 0.371092 -0.925936 0.070235 0.313374 -0.90701 -0.281299 0.904376 -0.277956 -0.323797 0.879329 -0.264804 -0.395804 0.685581 -0.712391 -0.149928 0.634054 -0.678985 -0.370074 0.293503 -0.953254 0.0718558 0.233307 -0.926466 -0.295345 0.87768 -0.378068 -0.29452 0.920386 -0.213156 -0.327803 0.936266 -0.0885898 -0.339939 0.243911 -0.966874 -0.0752499 0.609804 -0.756891 -0.235065 0.656787 -0.715495 -0.238114 0.902804 -0.277959 -0.328151 -0.993228 -0.11618 0 -0.965696 -0.258753 -0.0218693 -0.937455 -0.348079 -0.00427352 -0.793347 -0.608753 0.00455492 -0.448268 -0.893899 0.00062251 -0.572672 -0.819784 -0.000719572 -0.608746 -0.793352 -0.00466331 -0.698993 -0.715125 0.00248118 -0.828736 -0.559593 -0.00727382 -0.25882 -0.965926 0 0.0608396 -0.99562 -0.0709829 -0.179095 -0.983655 -0.0186538 -0.0184516 0.99983 0 -0.0184516 0.99983 0 -0.445728 0.895169 0 -0.445728 0.895169 0 -0.786737 0.617289 0 -0.786737 0.617289 0 -0.975512 0.219946 0 -0.975512 0.219946 0 0.974116 0.225923 0.00753028 0.913165 0.406745 -0.0262308 0.985436 0.170044 -0.000205107 1 0 0 0.349341 0.936891 -0.013979 0.41798 0.908453 -0.00232091 0.216438 0.976296 0 0.494515 0.869163 -0.00338422 0.589092 0.808066 0.000855009 0.775209 0.631696 -0.00333153 0.721915 0.691821 -0.0149182 0.820698 0.571354 -0.00308913 0.216438 0.976296 0 0.41798 0.908454 0.00180516 0.348947 0.937079 0.010926 0.494315 0.869279 0.00265167 0.775194 0.631684 0.00700506 0.716707 0.697373 0.00150003 0.589155 0.80802 -0.000670526 1 0 0 0.985431 0.170076 0.000167814 0.974131 0.225927 0.00502766 0.904595 0.42627 -0.00130132 0.820459 0.5717 0.00247064 -0.975512 0.219946 0 -0.975512 0.219946 0 -0.786737 0.617289 0 -0.786737 0.617289 0 -0.445728 0.895169 0 -0.445728 0.895169 0 -0.0184516 0.99983 0 -0.0184516 0.99983 0 -0.693572 -0.720307 0.01074 -0.572771 -0.819715 0.000541627 -0.425828 -0.904804 -0.000641069 -0.258802 -0.965858 0.0118395 -0.17 -0.985444 0.000241023 -0.00137363 -0.999999 0 -0.608741 -0.793346 -0.0059874 -0.793351 -0.608757 0.00319207 -0.830749 -0.556644 -0.00191774 -0.965927 -0.258815 0 -0.992627 -0.11611 0.0347889 -0.937519 -0.347921 0.00307546 0.404431 0.879006 -0.252555 0.40444 0.878999 -0.252566 0.29941 0.650729 -0.697786 0.299405 0.650737 -0.697781 0.110849 0.240924 -0.964193 0.110847 0.240926 -0.964193 0.75008 0.611218 -0.252572 0.750075 0.611229 -0.25256 0.55529 0.452501 -0.697779 0.555293 0.452478 -0.697791 0.205591 0.167525 -0.964193 0.205591 0.167528 -0.964192 0.942563 0.218606 -0.25256 0.942563 0.218604 -0.252562 0.697782 0.161833 -0.69779 0.69779 0.161859 -0.697776 0.258345 0.0599254 -0.964192 0.25834 0.059902 -0.964195 0.198033 0.960586 -0.195086 0.196268 0.945776 -0.258818 0.181089 0.878397 -0.442295 0.160188 0.777013 -0.608762 0.144424 0.6922 -0.707107 0.122916 0.596223 -0.793353 0.0893049 0.433186 -0.896869 0.0534929 0.253223 -0.965928 0.0393883 0.191058 -0.980788 0.965925 0 -0.258822 0.965925 0 -0.258822 0.707114 0 -0.7071 0.707114 0 -0.7071 0.258805 0 -0.96593 0.258805 0 -0.96593 -0.194885 0.043943 -0.979841 -0.551259 0.124306 -0.825022 -0.817236 0.184266 -0.54605 -0.0181137 0.981522 -0.190491 -0.437556 0.87878 -0.190501 -0.437566 0.878778 -0.190487 -0.77233 0.605988 -0.190488 -0.772332 0.605986 -0.190485 -0.957649 0.215926 -0.190485 -0.957652 0.21592 -0.190475 -0.817222 0.184279 -0.546067 -0.659082 0.517131 -0.546065 -0.6591 0.517125 -0.546048 -0.3734 0.749931 -0.546055 -0.373394 0.74993 -0.54606 -0.0181162 0.981523 -0.190487 -0.0166298 0.900991 -0.433519 -0.0483062 0.834325 -0.549153 -0.0147727 0.800423 -0.599253 -0.0114085 0.618146 -0.785981 -0.551266 0.1243 -0.825018 -0.444595 0.348826 -0.825019 -0.444573 0.348831 -0.825028 -0.251872 0.505863 -0.825023 -0.251877 0.505865 -0.825021 -0.0586501 0.556007 -0.829106 -0.00832479 0.451078 -0.892446 -0.194886 0.043942 -0.979841 -0.157172 0.123324 -0.979841 -0.157174 0.123323 -0.979841 -0.0890462 0.178838 -0.979841 -0.0890557 0.178839 -0.97984 -0.00368639 0.199747 -0.979841 -0.00368817 0.199748 -0.97984 0.588364 -0.766747 -0.256763 0.935114 -0.250558 -0.250566 0.935119 -0.250549 -0.250553 0.694755 -0.186148 -0.694741 0.694737 -0.186162 -0.694754 0.258185 -0.0691833 -0.963615 0.258193 -0.0691746 -0.963614 0.766761 -0.588354 -0.256745 0.66794 -0.667952 -0.32817 0.508581 -0.50859 -0.694753 0.508589 -0.508589 -0.694748 0.189008 -0.189008 -0.963614 0.189008 -0.189008 -0.963614 0.250558 -0.935112 -0.25057 0.250574 -0.935113 -0.250552 0.186165 -0.694744 -0.694747 0.186153 -0.69474 -0.694754 0.069181 -0.258189 -0.963614 0.0691905 -0.258192 -0.963613 -0.258805 0 -0.96593 -0.195073 -0.000586617 -0.980789 -0.608759 0.000442151 -0.793355 -0.555568 0 -0.831471 -0.793373 0 -0.608736 -0.831474 0.000295706 -0.555564 -0.965925 -0.000442262 -0.258822 -0.980788 0 -0.195077 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.7071 -0.707114 0 -0.7071 -0.707114 0 -0.258812 -0.965928 0 -0.258812 -0.965928 -0.935117 -0.250559 -0.250554 -0.766761 -0.588354 -0.256745 -0.250565 -0.935115 -0.250552 -0.250574 -0.93511 -0.250564 -0.186163 -0.694739 -0.694753 -0.186156 -0.694748 -0.694746 -0.0691817 -0.258192 -0.963614 -0.0691888 -0.258185 -0.963615 -0.588346 -0.766766 -0.256748 -0.66794 -0.667952 -0.32817 -0.508584 -0.508593 -0.694749 -0.508585 -0.508585 -0.694753 -0.189008 -0.189008 -0.963614 -0.189008 -0.189008 -0.963614 -0.935116 -0.250548 -0.250566 -0.776033 -0.207925 -0.595432 -0.668326 -0.246253 -0.701926 -0.600818 -0.160995 -0.783006 -0.258188 -0.0691841 -0.963614 -0.258185 -0.0691724 -0.963616 -0.588346 -0.766766 0.256748 -0.0691941 -0.258205 0.963609 -0.0691846 -0.258203 0.96361 -0.186153 -0.69474 0.694754 -0.186165 -0.694744 0.694747 -0.250574 -0.935113 0.250552 -0.250564 -0.935113 0.250564 -0.766761 -0.588354 0.256745 -0.66794 -0.667952 0.32817 -0.508581 -0.50859 0.694753 -0.508589 -0.508589 0.694748 -0.189018 -0.189018 0.96361 -0.189018 -0.189018 0.96361 -0.258206 -0.0691782 0.96361 -0.258198 -0.0691869 0.963611 -0.694737 -0.186162 0.694754 -0.694755 -0.186148 0.694741 -0.935119 -0.250549 0.250553 -0.935114 -0.250558 0.250566 -0.980788 0 0.195077 -0.89685 -0.00175012 0.442331 -0.965925 0 0.258822 -0.793373 0 0.608736 -0.707114 -0.000590453 0.707099 -0.608759 0 0.793355 -0.442286 0 0.896874 -0.258818 -0.000442146 0.965926 -0.195092 0 0.980785 0 -0.258825 0.965924 0 -0.258825 0.965924 0 -0.7071 0.707114 0 -0.7071 0.707114 0 -0.965929 0.258808 0 -0.965929 0.258808 -0.440102 0.0992351 0.892447 -0.00368849 0.199765 0.979837 -0.0890559 0.178858 0.979836 -0.0890612 0.17885 0.979837 -0.157187 0.123336 0.979837 -0.157188 0.123334 0.979837 -0.194903 0.0439472 0.979837 -0.194903 0.043946 0.979838 -0.780973 0.176105 0.599223 -0.603103 0.135997 0.785985 -0.532714 0.169713 0.829104 -0.444586 0.348842 0.825017 -0.444586 0.348819 0.825026 -0.251875 0.505861 0.825023 -0.251873 0.505866 0.825021 -0.957651 0.215926 0.190475 -0.879059 0.198206 0.433556 -0.00368674 0.199766 0.979837 -0.00832479 0.451078 0.892446 -0.0586501 0.556007 0.829106 -0.0114085 0.618146 0.785981 -0.0147727 0.800423 0.599253 -0.807385 0.215764 0.549159 -0.659091 0.517118 0.546067 -0.65909 0.517137 0.54605 -0.373396 0.749934 0.546054 -0.373399 0.749928 0.54606 -0.0483062 0.834325 0.549153 -0.0166298 0.900991 0.433519 -0.957651 0.215919 0.190484 -0.77233 0.605988 0.190485 -0.772331 0.605986 0.190488 -0.437557 0.878783 0.190486 -0.437565 0.878775 0.190501 -0.0181162 0.981522 0.190491 -0.0181137 0.981523 0.190487 0.194945 -0.0387638 0.980048 0.604344 -0.120219 0.787602 0.440584 -0.0876428 0.893423 0.221207 -0.141574 0.964896 0.219131 -0.146412 0.964648 0.219129 -0.146422 0.964647 0.146418 -0.219132 0.964647 0.146421 -0.219128 0.964647 0.0514176 -0.25848 0.964647 0.0514135 -0.258483 0.964647 0.882915 -0.175607 0.435458 0.783676 -0.155869 0.601296 0.672351 -0.222036 0.706148 0.593606 -0.396646 0.700217 0.593606 -0.396649 0.700215 0.396647 -0.593608 0.700215 0.396649 -0.593605 0.700216 0.139276 -0.700212 0.700218 0.139282 -0.700207 0.700222 0.962639 -0.191484 0.191467 0.93625 -0.240211 0.256387 0.804158 -0.537341 0.254155 0.804168 -0.537315 0.25418 0.537337 -0.804153 0.254177 0.537335 -0.804156 0.254174 0.188686 -0.948575 0.254172 0.188673 -0.948581 0.25416 0.039392 0.191076 0.980784 0.0534956 0.253236 0.965924 0.0893049 0.433186 0.896869 0.122916 0.596223 0.793353 0.144424 0.6922 0.707107 0.160188 0.777013 0.608762 0.181089 0.878397 0.442295 0.196268 0.945776 0.258818 0.198033 0.960586 0.195086 0.195092 0 0.980785 0.195092 0 0.980785 0.442286 0 0.896874 0.442286 0 0.896874 0.608759 0 0.793355 0.608759 0 0.793355 0.793373 0 0.608737 0.793373 0 0.608737 0.896852 0 0.442331 0.896852 0 0.442331 0.980788 0 0.195077 0.980788 0 0.195077 0.194892 0.0451902 0.979783 0.221376 0.136236 0.965625 0.110852 0.240937 0.964189 0.110855 0.240937 0.964189 0.299402 0.650732 0.697787 0.299411 0.650733 0.697782 0.404441 0.879002 0.252554 0.2056 0.167535 0.964189 0.205603 0.167534 0.964189 0.555304 0.452487 0.697777 0.555283 0.452495 0.697789 0.439976 0.102056 0.892191 0.602779 0.13982 0.785562 0.670722 0.232144 0.704444 0.780274 0.180965 0.598686 0.878058 0.203644 0.433062 0.40443 0.879003 0.252566 0.750072 0.611227 0.252573 0.750082 0.61122 0.252561 0.930663 0.2625 0.254874 0.956358 0.221805 0.190218 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965926 0.258817 0 0.965926 0.258817 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965926 0.258817 0 0.965926 0.258817 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.974139 -0.225948 0 -0.974139 -0.225948 0 -0.775214 -0.631699 0 -0.775214 -0.631699 0 -0.417984 -0.908455 0 -0.417984 -0.908455 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0.555571 -0.831469 0 0.555571 -0.831469 0 0.195091 -0.980785 0 0.195091 -0.980785 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.831469 0.55557 0 0.831469 0.55557 0 0.980785 0.19509 0 0.980785 0.19509 0 0.980785 -0.19509 0 0.980785 -0.19509 0 0.831469 -0.55557 0 0.831469 -0.55557 0 0.707107 -0.707107 0 0.707107 -0.707107 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.207912 0.978148 -4.03992e-07 0.20791 0.978148 5.69991e-09 0.207912 0.978148 -6.81991e-08 0.207911 0.978148 0 0.207912 0.978148 -4.76262e-08 0.207911 0.978148 1.07742e-07 0.207912 0.978148 -1.36281e-07 0.207911 0.978148 1.04433e-07 0.207912 0.978148 4.55096e-09 0.207912 0.978148 2.6168e-08 0.207912 0.978148 4.07062e-08 0.207912 0.978148 2.55753e-08 0.207912 0.978148 -5.61666e-09 0.207912 0.978148 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.207912 -0.978148 0 0.207912 -0.978148 3.09325e-07 0.207913 -0.978147 0 0.207911 -0.978148 -1.55349e-07 0.207911 -0.978148 0 0.207912 -0.978148 3.64277e-08 0.207912 -0.978148 -9.70054e-09 0.207912 -0.978148 -2.8215e-07 0.20791 -0.978148 8.61282e-09 0.207912 -0.978148 -3.93187e-08 0.207911 -0.978148 -2.50186e-08 0.207912 -0.978148 8.42731e-09 0.207913 -0.978147 -3.35633e-08 0.207912 -0.978148 -0.938604 0.324068 0.118332 -0.939465 0.239921 0.244628 -0.939465 0.269258 0.211909 -0.95576 0.242339 0.16672 -0.939465 0.294165 0.175704 -0.938835 0.323498 0.118061 -0.976058 0.199478 0.0867205 -0.939387 0.328972 0.0965866 -0.96612 0.155649 0.205878 -0.938778 0.224967 0.260932 -0.939465 0.169957 0.297522 -0.95576 0.129224 0.264244 -0.939465 0.13048 0.316828 -0.939465 0.0888563 0.330922 -0.95576 0.057906 0.288393 -0.939465 0.0457713 0.339574 -0.937364 0.290866 -0.191692 -0.93932 0.299172 -0.167853 -0.950218 0.276268 -0.144089 -0.936415 0.292916 -0.193204 -0.936119 0.293235 -0.194149 -0.93641 0.292217 -0.194283 -0.939121 0.325318 -0.11054 -0.938936 0.325837 -0.110585 -0.969223 0.228843 -0.0907562 -0.939466 0.329711 -0.0932417 -0.923944 0.11367 -0.365249 -0.937929 0.0932904 -0.334046 -0.93936 0.0503726 -0.339213 -0.93936 0.0503726 -0.339213 -0.939688 0.0791379 -0.332751 -0.0393773 0.994336 -0.0987155 0 0.995345 -0.0963795 0 0.995345 -0.0963795 -0.0123002 0.995155 -0.0975491 0 0.995345 0.0963795 0 0.995345 0.0963795 -0.0158768 0.995071 0.0978864 -0.0438318 0.994152 0.0986972 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.939692 0.0238582 0.341189 -0.939692 0.0238583 0.341188 -0.939674 0.023861 0.341238 -0.939708 0.0238553 0.341146 -0.939692 0.0238582 -0.341189 -0.939692 0.0238581 -0.341188 -0.939684 0.0238593 -0.341211 -0.939708 0.0238553 -0.341146 -0.348174 0.93743 0 -0.348174 0.93743 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.348173 0.93743 0 -0.348173 0.93743 -4.92713e-06 -0.348174 0.93743 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.925389 0.379019 0.00296682 -0.921412 0.388575 0.000433248 -0.909366 0.415997 0 -0.904994 0.425424 0 -0.826976 0.562238 0 -0.826976 0.562238 0 -0.467848 0.883809 0 -0.467848 0.883809 0 0 1 0 0 1 0 0.467847 0.883809 0 0.467847 0.883809 0 0.826976 0.562237 0 0.826976 0.562237 0 0.826976 -0.562237 0 0.826976 -0.562237 0 0.467847 -0.883809 0 0.467847 -0.883809 0 0 -1 0 0 -1 0 -0.467848 -0.883809 0 -0.467848 -0.883809 0 -0.826976 -0.562238 0 -0.826976 -0.562238 0.0215785 -0.845449 -0.53362 0 -0.789967 -0.61315 0.618928 -0.645578 -0.44739 0.212656 -0.815056 -0.538944 0.0576504 -0.83985 -0.539748 0 -0.925389 -0.379019 0.024825 -0.905802 -0.422974 0.0121087 -0.908484 -0.417744 0.0166947 -0.903121 -0.429062 0.0135689 -0.905612 -0.423891 -0.000883461 -0.877175 -0.480171 0.00105018 -0.851449 -0.524436 -0.417984 -0.908455 0 -0.417984 -0.908455 0 -0.775214 -0.631699 0 -0.775214 -0.631699 0 -0.974139 -0.225948 0 -0.974139 -0.225948 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.0445844 0.910165 0.41184 -0.0333353 0.877828 0.477814 -0.0116666 0.886824 0.461959 -0.00540525 0.896072 0.443875 -0.00114609 0.904208 0.42709 0.00416952 0.945641 0.325185 0 0.947408 0.320029 -0.033335 0.877828 -0.477814 -0.0116666 0.886824 -0.461959 -0.0248236 0.905979 -0.422594 -0.00365632 0.898582 -0.43879 -0.000715752 0.907975 -0.419023 0.00443194 0.947398 -0.320026 0 0.94565 -0.325188 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.5 0.377901 -0.779224 -0.5 0.377904 -0.779223 -0.5 0.377904 -0.779223 -0.5 0.377902 -0.779224 -0.5 0.377901 0.779225 -0.5 0.377902 0.779224 -0.499999 0.377901 0.779225 -0.500001 0.377905 0.779222 -0.5 0.377903 0.779224 0 -0.869008 -0.494798 0 -0.869008 -0.494798 0 -0.985153 -0.171679 0 -0.985153 -0.171679 0 -0.975403 0.22043 -0.182732 -0.861481 0.473773 0 -0.949422 0.314003 -0.0158392 -0.984492 0.17471 -0.0282965 -0.994591 0.0999378 0 -0.195091 0.980785 0.167712 -0.255153 0.952245 -0.113095 -0.552006 0.826135 0 -0.608763 0.793352 0 -0.831469 0.555571 -0.167713 -0.782116 0.60014 0.220164 -0.95672 0.190301 0 -0.965926 0.258818 0 -0.980785 -0.19509 0.167714 -0.952244 -0.255152 -0.113095 -0.826135 -0.552006 0 -0.793352 -0.608763 0 -0.55557 -0.83147 -0.167717 -0.600139 -0.782115 0.220157 -0.190304 -0.956721 0 -0.258819 -0.965926 -0.704917 0.705955 0.0687022 -0.704912 0.705959 0.068704 -0.704917 0.705955 -0.0687022 -0.705452 0.705453 0.0683646 -0.705445 0.705445 -0.068513 -0.704896 0.706004 -0.068418 -0.274248 0.957371 0.0907157 -0.576309 0.813153 0.0815445 -0.553782 0.828779 0.0803161 -0.0550081 0.993838 0.0962336 -0.194142 0.976012 0.0985367 -0.194217 0.976392 -0.0945443 -0.166993 0.981095 -0.0978058 -0.482465 0.872026 -0.0824477 -0.553601 0.828508 -0.084263 -0.66479 0.743547 -0.0720563 -0.980606 0.195066 0.0190159 -0.743842 0.663821 0.0777228 -0.873379 0.484922 0.0453767 -0.985685 0.167538 0.0188913 -0.814349 0.577388 -0.0588066 -0.830258 0.554759 -0.0539881 -0.830258 0.554759 0.0539881 -0.960769 0.276215 -0.0250493 -0.980531 0.195052 -0.0226707 -0.998455 0.0553079 -0.00539164 -0.995903 0.0355543 -0.0831404 -0.984132 0.110233 -0.13904 -0.984558 0.0521739 -0.167102 -0.98472 0.0517485 -0.16628 -0.984718 0.0255818 -0.172269 -0.984718 0.0255817 -0.172269 -0.984807 0.0121131 -0.173227 -0.999637 -0.0257315 -0.00803101 -0.998321 -0.0148996 -0.055981 -0.988638 0.00226911 -0.1503 -0.962749 0.018862 -0.269739 -0.965734 0.249024 0.0731138 -0.996172 0.0838829 0.0246056 -0.984605 0.170203 0.0397965 -0.984746 0.15957 0.0693712 -0.984746 0.15957 0.0693712 -0.984746 0.149379 0.0892238 -0.984746 0.149379 0.0892237 -0.984746 0.136731 0.107609 -0.984746 0.136731 0.107609 -0.984746 0.121834 0.124224 -0.984746 0.121834 0.124224 -0.984746 0.104933 0.138796 -0.984746 0.104933 0.138795 -0.984746 0.0863054 0.151084 -0.984746 0.0863054 0.151084 -0.984746 0.0662586 0.160888 -0.984746 0.0662586 0.160888 -0.984746 0.0451219 0.168045 -0.984746 0.0451219 0.168045 -0.984746 0.023243 0.172438 -0.984746 0.023243 0.172438 -0.962749 0.018862 0.269739 -0.999998 0.000133897 0.0019148 -0.984807 0.0118733 0.173243 -0.998321 -0.0148998 0.0559801 -0.988638 0.00226911 0.1503 -0.996177 0.0840624 -0.0237502 -0.991177 0.110545 -0.0731253 -0.965926 0.254314 -0.0480772 -0.98477 0.167302 -0.0473128 -0.984768 0.161628 -0.0640994 -0.984768 0.161628 -0.0640994 -0.984768 0.154166 -0.080406 -0.984768 0.154166 -0.080406 -0.984658 0.140744 -0.103153 -0.952597 0.254029 -0.167414 0 0.999227 0.039301 0 0.999227 0.039301 0 0.935587 -0.353097 0 0.935587 -0.353097 0 0.724098 -0.689697 0 0.724098 -0.689697 0 0.398182 -0.917306 0 0.398182 -0.917306 0 0.398182 0.917306 0 0.398182 0.917306 0 0.724098 0.689697 0 0.724098 0.689697 0 0.935587 0.353097 0 0.935587 0.353097 0 0.999227 -0.039301 0 0.999227 -0.039301 -0.195093 0.980785 0 -0.290395 0.956898 -0.0041903 -0.146869 0.989155 -0.00104957 -0.0493997 0.998779 0 -0.195698 0.980664 7.88197e-05 -0.555571 0.831469 -7.74182e-05 -0.576489 0.817105 0.000732467 -0.831462 0.555581 -0.000659494 -0.85011 0.526606 0.000354319 -0.980785 0.195093 0 -0.999914 0.0113945 -0.0064262 -0.981897 0.189416 -0.000388098 -0.0493997 0.998779 0 -0.258815 0.965927 0 -0.999982 0.00606662 0 -0.965927 0.258815 0.000225547 -0.981485 0.191517 0.00297604 -0.793331 0.608786 -0.00245086 -0.84967 0.527314 0.000694488 -0.608773 0.793344 -0.000514674 -0.576899 0.816815 -0.00142277 -0.246625 0.969109 0.00194122 -0.2907 0.956807 0.00369877 -0.146945 0.989144 0.000926429 -0.176876 0.984233 0 -0.176876 0.984233 0 -0.176875 0.984233 0 -0.176875 0.984233 0 -0.176876 0.984233 0 -0.176876 0.984233 0 -0.176875 0.984233 0 -0.176875 0.984233 0 0 0.735747 0.677257 0.145262 0.741764 0.65474 -0.982697 0.0808227 -0.166654 -0.985671 0.088106 -0.143843 -0.856946 0.20991 -0.470725 -0.874853 0.226264 -0.428295 -0.638086 0.320875 -0.699918 -0.652029 0.330849 -0.6822 -0.874885 0.225525 0.42862 -0.959582 0.115589 0.256596 -0.985165 0.104564 0.136077 -0.995481 0.0414353 0.0854386 -0.854793 0.21429 0.472661 -0.635965 0.352088 0.686718 -0.65205 0.33084 0.682185 -0.63807 0.33599 -0.692804 -0.649852 0.338175 -0.680684 -0.855614 0.21993 -0.468567 -0.873175 0.219899 -0.434983 -0.98519 0.0658413 -0.15832 -0.979016 0.098586 -0.178352 -0.999805 0.00862111 -0.0177765 -0.979123 0.101135 0.176323 -0.965722 0.116207 0.232113 -0.999805 0.00862087 0.017776 -0.855713 0.220781 0.467986 -0.639776 0.35321 0.68259 -0.708006 0.308163 0.635424 -0.488054 0.864916 -0.117152 -0.640821 0.49822 0.584059 -0.125758 0.943046 -0.307975 -0.366455 0.930373 0.0108234 -0.370311 0.928795 0.0145125 -0.546776 0.771888 0.324384 -0.858887 0.37893 0.344566 -0.85845 0.380377 0.344059 -0.731618 0.670093 0.125343 -0.133078 0.943798 -0.302549 -0.16827 0.924476 -0.342096 -0.175435 0.923943 -0.339931 -0.191417 0.904469 -0.381176 -0.195034 0.903674 -0.381227 -0.441254 0.843417 -0.306501 -0.546592 0.7982 -0.253206 -0.492565 0.862646 -0.114986 -0.729602 0.672547 0.123944 -0.547829 0.770612 0.325637 -0.641191 0.497064 0.584638 -0.967828 0.242045 0.0687203 -0.966472 0.247784 0.0673402 -0.88713 0.459214 -0.0460672 -0.818739 0.565987 -0.0965656 -0.786799 0.603224 -0.130645 -0.606016 0.759204 -0.237391 -0.498844 0.550336 0.669541 -0.498215 0.555214 0.665972 -0.435216 0.81992 0.371911 -0.429784 0.829253 0.357248 -0.299679 0.953954 0.0128058 -0.286029 0.958119 -0.0139775 -0.114697 0.930295 -0.348419 -0.092104 0.91929 -0.382652 -0.494368 0.54694 0.675616 -0.493623 0.551861 0.672151 -0.426019 0.814562 0.393696 -0.420387 0.82425 0.379324 -0.291337 0.955289 0.0504485 -0.277598 0.960401 0.023846 -0.111353 0.947208 -0.300663 -0.0888347 0.937847 -0.335487 -0.98063 0.185225 -0.0636947 -0.965595 0.245256 -0.0864603 -0.896064 0.419797 -0.144359 -0.792134 0.577175 -0.198477 -0.70551 0.669304 -0.232999 -0.194297 0.927628 -0.31899 -0.257744 0.913042 -0.316104 -0.44074 0.848848 -0.2919 -0.607163 0.751391 -0.258387 -0.858066 0.374027 0.351889 -0.895883 0.444217 0.00804567 -0.727633 0.677991 0.1043 -0.120316 0.910185 -0.396342 -0.340308 0.939442 -0.0404882 -0.353122 0.922363 -0.15669 -0.998637 0.049599 -0.0162617 -0.99822 -0.0280018 0.0526527 -0.946925 0.321307 -0.00977709 -0.965668 0.241576 0.0955303 -0.846519 0.411525 0.337716 -0.799491 0.572779 0.18094 -0.704075 0.710036 -0.011265 -0.643614 0.497572 0.581535 -0.633847 0.52257 0.570226 -0.565094 0.774298 0.284836 -0.551631 0.7887 0.271396 -0.448709 0.892569 0.0445041 -0.563071 0.825628 -0.0359176 -0.699969 0.517132 0.492563 -0.980021 0.0791958 0.182446 -0.896801 0.0951852 0.432073 -0.964589 0.105023 0.241945 -0.964589 0.190985 0.181912 -0.964589 0.190985 0.181912 -0.96459 0.246766 0.0931314 -0.96459 0.246766 0.0931315 -0.964589 0.263552 -0.0103658 -0.96459 0.263552 -0.0103659 -0.699969 0.517132 0.492564 -0.699968 0.668172 0.252173 -0.699969 0.668171 0.252173 -0.699969 0.713622 -0.028068 -0.699969 0.713622 -0.0280678 -0.192691 0.354249 0.915084 -0.435103 0.358516 0.825925 -0.699969 0.284372 0.655116 -0.606247 0.25341 0.753822 -0.787398 0.245457 0.565469 -0.25398 0.385125 0.887228 -0.25398 0.700354 0.667082 -0.25398 0.700355 0.667081 -0.25398 0.904908 0.341519 -0.25398 0.904908 0.341519 -0.25398 0.966462 -0.0380124 -0.25398 0.966462 -0.0380123 -0.787091 0.606995 0.109747 -1 0 0 -1 0 0 -0.999663 -0.00345791 0.0257182 -0.982482 0.147137 0.114363 -0.986261 0.164868 -0.0103495 -0.789458 0.612393 0.041597 -0.943567 0.328646 0.0409133 -0.989955 0.103767 0.0960273 -0.993084 0.117405 -0.000771231 -0.995472 0.0947396 -0.00770275 -0.986075 0.166249 -0.00418435 -0.881421 0.46849 -0.0601152 -0.999734 0.0229332 0.00245141 -0.995521 0.0936763 0.0127654 -0.960142 0.279319 0.0104487 -0.960073 0.278424 0.0272132 -0.684699 0.719341 -0.117206 -0.414905 0.901402 -0.12381 -0.562657 0.816939 -0.1266 -0.889916 0.451507 0.0647373 -0.890261 0.455403 -0.00653502 -0.996866 0.0640386 0.0464536 -0.997546 0.0698917 0.00412153 -0.999734 0.0228218 0.00326367 -1 0 0 -0.191251 0.91064 -0.366275 -0.411894 0.829869 -0.376378 -0.547183 0.77837 -0.307786 -0.680298 0.66625 -0.30546 -0.825479 0.526073 -0.204528 -0.879771 0.432263 -0.197868 -0.979718 0.188257 -0.068641 -0.986426 0.150597 -0.0654607 -0.195087 0.203917 0.959353 -0.195087 0.203917 0.959353 -0.442243 0.186475 0.877296 -0.442243 0.186475 0.877296 -0.608781 0.164944 0.776002 -0.608781 0.164944 0.776002 -0.793376 0.126563 0.59543 -0.793376 0.126563 0.59543 -0.896806 0.0919852 0.432756 -0.896806 0.0919852 0.432756 -0.980788 0.0405588 0.190814 -0.980788 0.0405588 0.190814 -0.965683 0.246066 -0.0831197 -0.980648 0.171955 -0.0935977 -0.980648 0.171955 -0.0935978 -0.830516 0.489218 -0.266288 -0.830516 0.489218 -0.266288 -0.554131 0.731136 -0.397968 -0.554132 0.731136 -0.397968 -0.194388 0.861562 -0.468961 -0.194387 0.861562 -0.468961 -0.980596 0.186629 -0.0600065 -0.792185 0.577487 -0.19736 -0.830516 0.527701 -0.178255 -0.607322 0.752674 -0.254249 -0.554188 0.788152 -0.267752 -0.257961 0.916028 -0.307163 -0.194387 0.929336 -0.313925 -0.195076 0.214464 0.957053 -0.247048 0.307701 0.918851 -0.442112 0.210239 0.871973 -0.60843 0.198065 0.768494 -0.692039 0.295167 0.658755 -0.792629 0.16889 0.585847 -0.895694 0.140568 0.421868 -0.95647 0.183521 0.226904 -0.979398 0.0925532 0.17948 -0.928374 0.313332 0.19986 -0.928795 0.31482 0.195522 -0.682644 0.337032 0.648388 -0.683892 0.338427 0.646343 -0.25131 0.270667 0.929292 -0.251861 0.271292 0.92896 -0.7875 0.599631 0.142433 -0.787188 0.600902 0.13875 -0.578351 0.546842 0.605372 -0.578872 0.548342 0.603513 -0.212845 0.347786 0.913095 -0.213103 0.348454 0.91278 -0.787399 0.615967 -0.024227 -0.964597 0.105012 0.24192 -0.964597 0.105012 0.24192 -0.964597 0.190965 0.181893 -0.964597 0.190965 0.181893 -0.964597 0.246741 0.0931217 -0.964597 0.246741 0.0931217 -0.964597 0.263525 -0.0103646 -0.964597 0.263525 -0.0103649 -0.699955 0.284377 0.655129 -0.699954 0.284377 0.655129 -0.699954 0.517142 0.492573 -0.699954 0.517142 0.492573 -0.699954 0.668185 0.252178 -0.699954 0.668184 0.252178 -0.704131 0.709725 0.0221322 -0.601022 0.798615 -0.0314111 -0.253986 0.385125 0.887226 -0.253987 0.385125 0.887226 -0.253987 0.700353 0.66708 -0.253988 0.700353 0.66708 -0.253988 0.904906 0.341519 -0.253987 0.904907 0.341518 -0.253987 0.96646 -0.0380128 -0.253988 0.96646 -0.0380123 -0.681341 0.722005 0.120343 -0.681349 0.722042 0.120074 -0.497252 0.634132 0.592129 -0.497294 0.634193 0.592029 -0.181754 0.378673 0.907509 -0.181783 0.378715 0.907485 -0.681301 0.722012 0.120533 -0.681307 0.722039 0.120336 -0.497166 0.634062 0.592277 -0.49723 0.634154 0.592124 -0.181728 0.37865 0.907524 -0.181748 0.37868 0.907507 -0.195087 0.203917 0.959353 -0.258768 0.219175 0.940745 -0.442288 0.18647 0.877274 -0.608754 0.164949 0.776022 -0.706893 0.171514 0.686211 -0.793376 0.126563 0.59543 -0.896851 0.0919663 0.432666 -0.965754 0.0721899 0.249213 -0.980788 0.0405589 0.190814 -0.643147 0.757258 0.113675 -0.642096 0.758338 0.112413 -0.469445 0.659895 0.586652 -0.468958 0.660791 0.586033 -0.171796 0.388103 0.905462 -0.171633 0.388469 0.905336 -0.467645 0.879663 0.0866054 -0.466915 0.880277 0.0842837 -0.343004 0.751523 0.563526 -0.3428 0.752486 0.562364 -0.126189 0.422928 0.897334 -0.126139 0.423385 0.897125 -0.16197 0.984647 0.0650917 -0.161602 0.984759 0.0642955 -0.118762 0.828278 0.547586 -0.118556 0.828573 0.547185 -0.0436863 0.451124 0.891391 -0.0436144 0.451267 0.891323 -0.195397 0.220594 0.955593 -0.97761 0.124028 0.169986 -0.977248 0.123443 0.172477 -0.195059 0.220445 0.955697 -0.441956 0.224189 0.86857 -0.558278 0.202697 0.804512 -0.607899 0.21654 0.763917 -0.830166 0.186228 0.525494 -0.792746 0.165433 0.586674 -0.894114 0.168049 0.415114 -0.189777 0.253591 0.948513 -0.189486 0.253394 0.948623 -0.539635 0.313991 0.781156 -0.538926 0.313499 0.781843 -0.805809 0.326089 0.494306 -0.805085 0.325441 0.49591 -0.94827 0.288405 0.132693 -0.948109 0.287777 0.135183 0 0.997822 0.0659627 0 0.997822 0.0659627 0 0.834182 0.551489 0 0.834182 0.551489 0 0.451556 0.892243 0 0.451556 0.892243 -0.129167 0.251918 0.95909 -0.178687 0.283475 0.942185 -0.778817 0.405091 0.478899 -0.653798 0.37297 0.658363 -0.518459 0.372898 0.769512 -0.45075 0.342722 0.824237 -0.308117 0.306194 0.900727 -0.922536 0.367952 0.116356 -0.924625 0.380487 -0.0173004 -0.918005 0.378907 0.117034 -0.895302 0.383046 0.227397 -0.826814 0.390469 0.40486 -0.922514 0.367965 0.116489 -0.922527 0.367977 0.11635 -0.783103 0.393676 0.481424 -0.783131 0.393692 0.481366 -0.523651 0.359034 0.772582 -0.523685 0.359053 0.772551 -0.18395 0.269366 0.945307 -0.183967 0.269376 0.9453 -0.316399 0.909347 0.270147 -0.244238 0.958871 0.144617 -0.169867 0.98526 -0.0202159 -0.104947 0.994478 0.000602292 -0.483207 0.801712 0.351809 -0.580494 0.591217 0.559901 -0.812506 0.526952 0.249311 -0.784941 0.53227 0.317105 -0.182738 0.443952 0.877219 -0.0921884 0.995173 0.0336411 -0.0309217 0.998288 0.0496489 -0.050074 0.99657 0.06588 -0.453347 0.842974 0.289607 -0.245738 0.871581 0.424216 -0.304318 0.83966 0.449846 -0.0713043 0.855388 0.513057 -0.128741 0.82724 0.5469 -0.0856722 0.514568 0.853159 -0.349135 0.504284 0.789812 -0.342651 0.506753 0.79107 -0.473811 0.56421 0.676144 -0.64372 0.531679 0.550402 -0.32532 0.930248 0.169725 -0.591117 0.706899 0.388426 -0.240005 0.882194 0.405131 -0.230746 0.79476 0.56135 -0.686426 0.720312 -0.0998492 -0.74459 0.664524 -0.0631879 -0.636702 0.768898 0.0583725 -0.704585 0.6957 0.139864 -0.613096 0.750024 0.248148 -0.834479 0.498905 -0.233965 -0.885041 0.421676 -0.197209 -0.885393 0.420236 -0.198698 -0.903482 0.397164 -0.161184 -0.871522 0.478094 -0.108973 -0.884576 0.461421 -0.067936 -0.881068 0.469664 -0.0559982 -0.910464 0.413474 0.00975108 -0.910061 0.414451 -0.00441188 -0.657388 0.671251 0.342437 -0.655767 0.669751 0.348431 -0.245711 0.766364 0.593559 -0.234886 0.753397 0.614183 -0.258672 0.706621 0.658616 -0.253061 0.705212 0.662296 -0.703885 0.565112 0.430342 -0.691266 0.567701 0.447064 -0.957575 0.274205 0.0886616 -0.950566 0.285994 0.120961 -0.965925 0.183015 0.183015 -0.965925 0.183015 0.183015 -0.707102 0.500004 0.500003 -0.707103 0.500003 0.500003 -0.258823 0.683012 0.683012 -0.258822 0.683012 0.683012 -0.601308 0.664359 -0.44391 -0.254174 0.804163 -0.537325 -0.964647 0.219129 -0.146417 -0.787597 0.512345 -0.342337 -0.254171 0.804164 -0.537324 -0.254173 0.948575 -0.188683 -0.254173 0.948575 -0.188683 -0.254173 0.948575 0.188683 -0.254174 0.948575 0.188683 -0.254175 0.804163 0.537325 -0.254174 0.804163 0.537325 -0.698214 0.584604 -0.413201 -0.700208 0.700221 -0.139283 -0.700208 0.700221 -0.139283 -0.700208 0.700221 0.139282 -0.700208 0.700221 0.139283 -0.700207 0.593619 0.396644 -0.700209 0.593618 0.396642 -0.964647 0.219129 -0.146417 -0.964647 0.25848 -0.0514149 -0.964647 0.25848 -0.0514149 -0.964647 0.25848 0.0514148 -0.964647 0.25848 0.0514148 -0.964647 0.219129 0.146417 -0.964647 0.219129 0.146417 -0.980781 0.137966 -0.137966 -0.965921 0.180963 -0.185065 -0.831475 0.394212 -0.391466 -0.79335 0.430462 -0.430462 -0.555563 0.587941 -0.587941 -0.608746 0.563041 -0.558939 -0.195098 0.690792 -0.696235 -0.258823 0.683012 -0.683012 -0.19148 0.191481 -0.962637 -0.191483 0.19148 -0.962637 -0.435411 0.175626 -0.882934 -0.547205 0.153746 -0.822757 -0.825574 0.101194 -0.555147 -0.787597 0.120213 -0.604351 -0.601317 0.15588 -0.783658 -0.980043 0.0387814 -0.194968 -0.980043 0.0387818 -0.194969 -0.893447 0.0876289 -0.440539 -0.191483 0.545291 -0.816084 -0.191489 0.545289 -0.816083 -0.548118 0.464679 -0.695442 -0.548117 0.46468 -0.695443 -0.826446 0.312795 -0.468131 -0.826446 0.312795 -0.468131 -0.980043 0.11044 -0.165285 -0.980043 0.11044 -0.165285 -0.19509 0 -0.980785 -0.19509 0 -0.980785 -0.442286 0 -0.896874 -0.442286 0 -0.896874 -0.608759 0 -0.793355 -0.608759 0 -0.793355 -0.79335 0 -0.608766 -0.79335 0 -0.608766 -0.896897 0 -0.44224 -0.896897 0 -0.44224 -0.98078 0 -0.195115 -0.98078 0 -0.195115 -0.205417 0.0210897 -0.978447 -0.49483 0.0458928 -0.867777 -0.767492 0.0707924 -0.637138 -0.939041 0.0878791 -0.332383 -0.882035 0.0969553 -0.4611 -0.769942 0.0715368 -0.634092 -0.173717 0.0252975 -0.984471 -0.175066 0.0062838 -0.984537 -0.195089 0.00297505 -0.980781 -0.442215 0.0178394 -0.896732 -0.503104 0.0267123 -0.863813 -0.501783 0.0453924 -0.863801 -0.661457 0.0707769 -0.746636 -0.980476 0.0248927 -0.195055 -0.942238 0.041513 -0.332361 -0.896442 0.0318573 -0.442015 -0.770324 0.0284496 -0.637017 -0.79283 0.0361975 -0.608367 -0.608663 0.0177439 -0.793231 -0.204588 0.0272872 -0.978468 -0.859738 0.0852251 -0.503574 -0.803904 0.0677567 -0.590887 -0.853736 0.0918372 -0.512544 -0.621006 0.0646974 -0.781131 -0.619515 0.0785445 -0.781045 -0.434872 0.050848 -0.899056 -0.492739 0.0621885 -0.867952 -0.309599 0.0385502 -0.950085 -0.195398 0.0159106 -0.980595 -0.880689 0.108153 -0.461182 -0.851798 0.108558 -0.5125 -0.767214 0.0945247 -0.634387 -0.660151 0.0811539 -0.746736 -0.493888 0.551788 -0.672015 -0.494096 0.547007 -0.675761 -0.421189 0.824022 -0.378931 -0.4252 0.814785 -0.394121 -0.278933 0.960031 -0.0231813 -0.289971 0.955667 -0.0511545 -0.0906999 0.937331 0.336429 -0.109436 0.947741 0.299684 -0.498489 0.555131 -0.665836 -0.498562 0.550423 -0.669679 -0.43061 0.828994 -0.356854 -0.434373 0.820172 -0.372341 -0.287406 0.957697 0.0146439 -0.298271 0.954385 -0.0135128 -0.0940285 0.918703 0.383594 -0.112721 0.930902 0.347441 -0.96374 0.253996 -0.0818028 -0.195016 0.905112 0.377812 -0.191163 0.905102 0.379798 -0.441027 0.845977 0.299696 -0.545641 0.801184 0.245722 -0.964682 0.249051 -0.0858073 -0.884953 0.464616 0.031451 -0.816847 0.570682 0.0841681 -0.78532 0.607794 0.117729 -0.605383 0.762681 0.22766 -0.84116 0.393365 -0.371099 -0.841205 0.392565 -0.371842 -0.715357 0.68336 -0.145891 -0.716485 0.681608 -0.148525 -0.479085 0.871612 0.103778 -0.482148 0.870435 0.0993765 -0.166124 0.925748 0.339697 -0.171345 0.926866 0.334008 -0.627419 0.50278 -0.594607 -0.627503 0.503752 -0.593695 -0.535258 0.776878 -0.331601 -0.535531 0.77604 -0.333121 -0.359303 0.933106 -0.014666 -0.360883 0.932411 -0.0193396 -0.125054 0.943256 0.307619 -0.128306 0.945191 0.300251 -0.541521 0.839399 0.0465304 -0.909884 0.394559 -0.128197 -0.929559 0.313195 -0.1945 -0.961239 0.269111 -0.0599911 -0.946925 0.321307 0.00977708 -0.99822 -0.0279986 -0.0526522 -0.998637 0.0495977 0.0162612 -0.686392 0.711811 -0.148969 -0.717603 0.694753 -0.0486206 -0.710275 0.703772 -0.0146421 -0.850096 0.381769 -0.362752 -0.854608 0.403944 -0.326305 -0.642412 0.518692 -0.564149 -0.63514 0.501632 -0.587335 -0.558187 0.78589 -0.266091 -0.558213 0.777769 -0.288917 -0.350343 0.927909 0.127455 -0.340308 0.939442 0.0404883 -0.12032 0.910185 0.39634 -0.965644 0.245746 0.0845064 -0.896325 0.416664 0.151632 -0.98063 0.185225 0.0636947 -0.257789 0.913688 0.314197 -0.194343 0.926748 0.321511 -0.440739 0.848848 0.2919 -0.705636 0.670063 0.23042 -0.607391 0.749484 0.263345 -0.792134 0.577175 0.198477 -0.790167 0.555133 0.259738 -0.986954 0.14657 -0.0666281 -0.987591 0.15686 0.00769745 -0.941197 0.335919 -0.0361383 -0.808339 0.587093 -0.0437132 -0.806959 0.589888 0.0291418 -0.466187 0.879804 0.092814 -0.46199 0.882015 0.0928124 -0.465891 0.856452 0.222342 -0.257735 0.852378 0.455 -0.601828 0.737025 0.307568 -0.78987 0.555399 0.260072 -0.789846 0.612063 0.0390273 -0.928227 0.37044 0.0341927 -0.929556 0.368174 -0.0193552 -0.995645 0.09108 -0.0199105 -0.995629 0.0933259 -0.0035224 -0.999987 -0.000685699 -0.00508507 -1 0 0 -0.99952 0.0306781 -0.00432482 -0.99934 0.0281118 -0.0230037 -0.992067 0.124995 -0.0133612 -0.992006 0.12466 -0.0196186 -0.975836 0.217784 0.0177068 -0.976481 0.207079 0.0600289 -0.964918 0.240789 0.104665 -0.25398 0.966462 0.0380124 -0.699969 0.713622 0.028068 -0.980021 0.0791958 -0.182446 -0.963027 0.0843824 -0.255849 -0.96459 0.190985 -0.181911 -0.96459 0.190985 -0.181911 -0.96459 0.246766 -0.0931315 -0.96459 0.246766 -0.0931315 -0.964589 0.263552 0.010366 -0.96459 0.263552 0.0103658 -0.699969 0.713622 0.0280678 -0.699968 0.668171 -0.252173 -0.699968 0.668172 -0.252173 -0.699968 0.517132 -0.492564 -0.699968 0.517132 -0.492564 -0.893218 0.179033 -0.412443 -0.787399 0.245457 -0.565467 -0.695755 0.25189 -0.672663 -0.601049 0.318233 -0.733122 -0.435103 0.358516 -0.825925 -0.25398 0.966462 0.0380123 -0.25398 0.904908 -0.341519 -0.25398 0.904908 -0.341519 -0.25398 0.700354 -0.667082 -0.25398 0.700355 -0.667082 -0.252362 0.357453 -0.899189 -0.191339 0.390825 -0.900358 -0.965682 0.228121 0.12417 -0.980648 0.185482 0.0626549 -0.965727 0.246594 0.081006 -0.830573 0.527155 0.179599 -0.792278 0.578071 0.195269 -0.554132 0.788649 0.266401 -0.60723 0.75205 0.256306 -0.194337 0.930253 0.311227 -0.257915 0.915355 0.309202 -0.980596 0.17079 0.096238 -0.792187 0.53705 0.289857 -0.830516 0.489218 0.266288 -0.607323 0.697783 0.379813 -0.55419 0.731789 0.396685 -0.257958 0.847562 0.463785 -0.194385 0.861563 0.468961 -0.195087 0.203917 -0.959353 -0.195087 0.203917 -0.959353 -0.442243 0.186475 -0.877296 -0.442243 0.186475 -0.877296 -0.608779 0.164945 -0.776003 -0.608779 0.164945 -0.776003 -0.793377 0.126562 -0.595428 -0.793377 0.126562 -0.595428 -0.896806 0.0919853 -0.432756 -0.896806 0.0919851 -0.432756 -0.980788 0.0405588 -0.190814 -0.980788 0.0405589 -0.190814 -0.601022 0.798615 0.0314111 -0.787399 0.245457 -0.565467 -0.964597 0.263525 0.0103646 -0.964597 0.263525 0.0103648 -0.964597 0.246741 -0.0931222 -0.964597 0.246741 -0.0931218 -0.964597 0.190965 -0.181892 -0.964597 0.190965 -0.181892 -0.964597 0.105012 -0.241919 -0.964597 0.105012 -0.24192 -0.787399 0.615967 0.024227 -0.704131 0.709725 -0.0221322 -0.699955 0.668184 -0.252178 -0.699954 0.668185 -0.252179 -0.699954 0.517143 -0.492573 -0.699953 0.517143 -0.492574 -0.70413 0.327909 -0.629823 -0.601023 0.318241 -0.73314 -0.253988 0.96646 0.0380127 -0.253987 0.96646 0.0380122 -0.253987 0.904906 -0.34152 -0.253988 0.904906 -0.341518 -0.253989 0.700353 -0.66708 -0.253989 0.700353 -0.66708 -0.253989 0.385126 -0.887225 -0.253986 0.385125 -0.887226 -0.524148 0.607092 -0.597251 -0.228046 0.324342 -0.91804 -0.19223 0.368654 -0.909473 -0.191829 0.368831 -0.909486 -0.621676 0.482432 -0.617073 -0.19498 0.236278 -0.951922 -0.247423 0.273307 -0.929562 -0.228863 0.324222 -0.917879 -0.619668 0.483102 -0.618566 -0.525204 0.606499 -0.596926 -0.717573 0.684689 -0.127635 -0.440998 0.259289 -0.859238 -0.605516 0.265195 -0.750347 -0.690486 0.298737 -0.658776 -0.786281 0.255962 -0.562357 -0.886495 0.238825 -0.396344 -0.718929 0.683412 -0.126841 -0.843484 0.512799 -0.159911 -0.845268 0.510863 -0.156655 -0.947064 0.237793 -0.215696 -0.967538 0.200251 -0.154176 -0.195085 0.203917 -0.959354 -0.258768 0.219175 -0.940745 -0.555521 0.16056 -0.815853 -0.608754 0.164949 -0.776022 -0.831476 0.115507 -0.54342 -0.793237 0.108165 -0.599229 -0.980483 0.0649365 -0.185571 -0.965925 0.0538121 -0.253166 -0.681338 0.722009 -0.120342 -0.68127 0.722042 -0.120527 -0.497259 0.634126 -0.59213 -0.497136 0.63409 -0.592271 -0.181753 0.378673 -0.907509 -0.181722 0.378656 -0.907522 -0.681392 0.722001 -0.120083 -0.681299 0.722046 -0.120334 -0.497313 0.634174 -0.592034 -0.497233 0.634151 -0.592125 -0.181792 0.378707 -0.907487 -0.181745 0.378681 -0.907508 -0.189462 0.253521 -0.948594 -0.18982 0.253468 -0.948537 -0.538842 0.313897 -0.78174 -0.539767 0.313599 -0.781222 -0.804911 0.326144 -0.49573 -0.806021 0.325386 -0.494424 -0.947841 0.288763 -0.134955 -0.948543 0.287415 -0.132886 -0.195057 0.22058 -0.955666 -0.195421 0.220461 -0.955619 -0.554907 0.220278 -0.802219 -0.555793 0.219823 -0.80173 -0.829269 0.186431 -0.526837 -0.830247 0.185525 -0.525613 -0.97716 0.124463 -0.172242 -0.977705 0.123004 -0.170185 -0.0533304 0.996408 -0.0657866 -0.053196 0.996409 -0.0658693 -0.0388915 0.833577 -0.551032 -0.0388014 0.833554 -0.551074 -0.0142286 0.451522 -0.892146 -0.0141949 0.45151 -0.892153 -0.266147 0.961482 -0.0686925 -0.265408 0.961596 -0.0699378 -0.195227 0.811648 -0.550558 -0.194662 0.811368 -0.55117 -0.0718211 0.445059 -0.892617 -0.0716049 0.444899 -0.892714 -0.558478 0.82403 -0.0952747 -0.556932 0.824785 -0.0977566 -0.410007 0.71146 -0.570718 -0.408636 0.711307 -0.571891 -0.150875 0.408308 -0.90029 -0.150327 0.408141 -0.900457 -0.938195 0.34576 0.0155136 -0.918334 0.379038 -0.113985 -0.912172 0.376917 -0.160862 -0.855517 0.389391 -0.341271 -0.779458 0.403423 -0.479266 -0.731748 0.383709 -0.563304 -0.520633 0.367185 -0.770789 -0.477573 0.34349 -0.808665 -0.181802 0.275178 -0.944047 -0.165582 0.263602 -0.950314 -0.183946 0.26937 -0.945306 -0.183968 0.269372 -0.945301 -0.523647 0.359045 -0.77258 -0.523689 0.359042 -0.772554 -0.783098 0.393691 -0.48142 -0.783136 0.393677 -0.481369 -0.922502 0.367996 -0.116482 -0.922538 0.367946 -0.116357 0 0.451556 -0.892243 0 0.451556 -0.892243 0 0.834182 -0.551489 0 0.834182 -0.551489 0 0.997822 -0.0659627 0 0.997822 -0.0659627 -0.830817 0.471845 -0.295137 -0.712028 0.517398 -0.474674 -0.715533 0.531625 -0.453196 -0.561748 0.810233 -0.167217 -0.482731 0.8264 -0.289887 -0.539251 0.752466 -0.378157 -0.496248 0.578961 -0.646949 -0.417538 0.51582 -0.748058 -0.336216 0.87035 -0.359792 -0.310282 0.847954 -0.429766 -0.14401 0.988586 -0.0442614 -0.152469 0.98829 -0.00605869 -0.026972 0.990328 0.136096 -0.0425556 0.996918 -0.065903 -0.0569606 0.99762 -0.0388567 -0.0983984 0.830134 -0.548813 -0.155693 0.861002 -0.484184 -0.111065 0.448762 -0.886723 -0.235935 0.530556 -0.814153 -0.965925 0 -0.258823 -0.965925 0 -0.258823 -0.707103 0 -0.70711 -0.707103 0 -0.70711 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.256753 -0.588355 -0.766757 -0.250567 -0.935112 -0.250562 -0.250565 -0.935113 -0.250563 -0.595447 -0.776019 -0.207934 -0.690702 -0.705232 -0.159933 -0.96361 -0.258202 -0.0691852 -0.963611 -0.258202 -0.069185 -0.783 -0.600826 -0.160991 -0.256751 -0.766757 -0.588356 -0.121614 -0.701858 -0.701858 -0.69474 -0.508595 -0.508595 -0.694741 -0.508594 -0.508593 -0.963611 -0.189017 -0.189017 -0.96361 -0.189017 -0.189017 -0.250564 -0.250563 -0.935113 -0.250562 -0.250562 -0.935113 -0.694741 -0.186158 -0.694752 -0.694743 -0.186158 -0.69475 -0.963611 -0.0691851 -0.258202 -0.96361 -0.069185 -0.258203 -0.980781 -0.195114 0 -0.965923 -0.258821 0.00226044 -0.831475 -0.55556 -0.00151329 -0.793349 -0.608767 0 -0.555565 -0.831473 0 -0.608751 -0.793358 -0.00226104 -0.195093 -0.98078 0.00299973 -0.258823 -0.965925 0 -0.221847 -0.973629 0.0532127 -0.194933 -0.979973 0.0406748 -0.613242 -0.77483 0.153535 -0.551719 -0.825719 0.117451 -0.875309 -0.427983 0.225086 -0.81927 -0.547405 0.170719 -0.966133 -0.00461889 0.258005 -0.96225 -0.191427 0.193471 -0.186672 -0.968032 0.167536 -0.172954 -0.973755 0.147949 -0.504847 -0.730577 0.459769 -0.4795 -0.774679 0.412254 -0.694872 -0.330026 0.638933 -0.687721 -0.427612 0.586674 -0.723724 0.137958 0.676159 -0.764499 -0.00461635 0.644608 -0.130883 -0.970188 0.203974 -0.130881 -0.970189 0.203971 -0.361901 -0.742245 0.564003 -0.361901 -0.742246 0.564003 -0.507886 -0.339939 0.791513 -0.507886 -0.339939 0.791513 -0.534555 0.142256 0.833075 -0.534556 0.14224 0.833078 -0.517694 0.153062 0.841763 -0.514708 0.163616 0.841609 -0.47153 -0.309147 0.825886 -0.469353 -0.278588 0.837912 -0.324502 -0.704553 0.631114 -0.329842 -0.665541 0.669522 -0.109003 -0.947979 0.29909 -0.123136 -0.920807 0.370071 -0.528856 0.142237 0.836708 -0.525316 0.15261 0.83711 -0.495134 -0.3399 0.799569 -0.49184 -0.310373 0.813488 -0.346163 -0.742117 0.573963 -0.350543 -0.706145 0.615206 -0.117664 -0.970069 0.212417 -0.131268 -0.949356 0.285467 -0.844637 0.0512233 0.532884 -0.844608 0.0430381 0.533653 -0.723264 -0.336718 0.602917 -0.72797 -0.321952 0.605315 -0.476262 -0.670709 0.568615 -0.497239 -0.640383 0.585374 -0.145822 -0.889546 0.432947 -0.186478 -0.859555 0.475805 -0.640734 0.14634 0.753688 -0.644477 0.120779 0.755024 -0.56841 -0.288142 0.770639 -0.568937 -0.282601 0.7723 -0.384046 -0.669995 0.635307 -0.394142 -0.641116 0.6585 -0.123117 -0.920805 0.370082 -0.1472 -0.890058 0.431427 -0.977085 -0.134508 0.164959 -0.195032 -0.884103 0.424647 -0.196335 -0.883519 0.42526 -0.44176 -0.797452 0.410998 -0.553273 -0.724442 0.411184 -0.976497 -0.138617 0.165039 -0.893346 -0.365639 0.261232 -0.827951 -0.461553 0.318536 -0.790947 -0.521006 0.320868 -0.607592 -0.696044 0.382564 -0.941882 -0.0547797 0.331447 -0.941726 -0.0572569 0.331473 -0.800516 -0.398773 0.447387 -0.799527 -0.401159 0.447021 -0.536769 -0.682863 0.495557 -0.535005 -0.68493 0.494611 -0.189882 -0.863105 0.467969 -0.187625 -0.864481 0.466337 -0.194971 -0.90763 0.371745 -0.2587 -0.895771 0.36148 -0.442023 -0.830077 0.339981 -0.608546 -0.734314 0.300758 -0.707014 -0.656947 0.261826 -0.980765 -0.180629 0.0739816 -0.96591 -0.241431 0.09343 -0.896698 -0.409618 0.16777 -0.793196 -0.56353 0.230809 -0.251668 -0.800359 0.544141 -0.696472 -0.593424 0.403453 -0.963928 -0.220111 0.149647 -0.963928 -0.22011 0.149647 -0.963928 -0.124524 0.235237 -0.963928 -0.124523 0.235237 -0.963928 0 0.266162 -0.963928 0 0.266162 -0.963928 0.124523 0.235237 -0.963928 0.124524 0.235237 -0.963928 0.22011 0.149647 -0.963928 0.220111 0.149647 -0.696472 -0.593425 0.403453 -0.696472 -0.33572 0.634208 -0.69647 -0.335721 0.634209 -0.69647 0 0.717586 -0.69647 0 0.717586 -0.69647 0.33572 0.634209 -0.696471 0.33572 0.634208 -0.696472 0.593425 0.403453 -0.696472 0.593424 0.403452 -0.251668 -0.800358 0.544141 -0.251668 -0.452789 0.855362 -0.251669 -0.452789 0.855362 -0.251669 0 0.967813 -0.251669 0 0.967813 -0.251669 0.452789 0.855362 -0.251668 0.452789 0.855363 -0.251668 0.800359 0.544141 -0.251668 0.800359 0.544141 -0.189543 0.811985 -0.552045 -0.544087 0.693857 -0.471734 -0.823654 0.468971 -0.31884 -0.979639 0.16603 -0.112879 -0.979639 0.16603 -0.112879 -0.979639 0.0939287 -0.17744 -0.979639 0.0939284 -0.17744 -0.979639 0 -0.200767 -0.979639 0 -0.200767 -0.979639 -0.0939285 -0.17744 -0.979639 -0.0939286 -0.17744 -0.979639 -0.16603 -0.112879 -0.979639 -0.16603 -0.112879 -0.823655 0.468971 -0.31884 -0.823655 0.265312 -0.501201 -0.823654 0.265313 -0.501201 -0.823654 0 -0.567092 -0.823654 0 -0.567092 -0.823654 -0.265313 -0.501201 -0.823655 -0.265312 -0.501201 -0.823655 -0.468971 -0.31884 -0.823654 -0.468971 -0.31884 -0.544086 0.693857 -0.471734 -0.544086 0.392538 -0.741542 -0.544086 0.392538 -0.741542 -0.544086 0 -0.83903 -0.544086 0 -0.83903 -0.544086 -0.392538 -0.741542 -0.544086 -0.392538 -0.741542 -0.544086 -0.693857 -0.471734 -0.544087 -0.693857 -0.471733 -0.189544 0.811985 -0.552045 -0.189543 0.459367 -0.867788 -0.189545 0.459366 -0.867788 -0.189544 0 -0.981872 -0.189544 0 -0.981872 -0.189544 -0.459367 -0.867788 -0.189543 -0.459367 -0.867788 -0.189543 -0.811985 -0.552045 -0.189543 -0.811985 -0.552046 -0.194971 -0.90763 -0.371745 -0.194969 -0.90763 -0.371745 -0.555329 -0.769582 -0.315204 -0.555329 -0.769582 -0.315203 -0.831301 -0.514352 -0.210667 -0.8313 -0.514353 -0.210667 -0.980765 -0.180629 -0.0739816 -0.980765 -0.180629 -0.0739817 -0.639078 0.153986 -0.75357 -0.174947 -0.771401 -0.611828 -0.112739 -0.802563 -0.585818 -0.413934 -0.499219 -0.761209 -0.363089 -0.552455 -0.750307 -0.519008 -0.270946 -0.810691 -0.549051 -0.216757 -0.807192 -0.584797 -0.0903809 -0.806129 -0.638701 0.152839 -0.754122 -0.858392 0.0324189 -0.511969 -0.858814 0.0336677 -0.51118 -0.729798 -0.320571 -0.603846 -0.73178 -0.318 -0.602805 -0.489305 -0.628101 -0.605037 -0.493649 -0.625113 -0.604603 -0.170735 -0.841374 -0.512775 -0.177716 -0.839398 -0.513643 -0.967025 -0.106672 -0.231266 -0.968325 -0.102079 -0.227873 -0.822601 -0.44117 -0.358744 -0.82553 -0.43766 -0.356306 -0.552659 -0.711939 -0.433257 -0.556306 -0.709967 -0.431822 -0.194908 -0.875652 -0.441864 -0.198434 -0.875175 -0.441241 -0.137071 -0.733029 -0.666244 -0.486611 0.198256 -0.850826 -0.476767 0.144646 -0.867047 -0.115685 -0.756844 -0.643276 -0.292557 -0.470816 -0.832312 -0.347255 -0.334792 -0.875973 -0.38619 -0.237605 -0.891292 -0.440613 -0.0516182 -0.896212 -0.133636 -0.701018 -0.700511 -0.112232 -0.725806 -0.678683 -0.344096 -0.309908 -0.886315 -0.334034 -0.330937 -0.882554 -0.47504 0.153012 -0.866559 -0.473307 0.145651 -0.868773 -0.165849 -0.700048 -0.694569 -0.153125 -0.706862 -0.690579 -0.449027 -0.321177 -0.833798 -0.432086 -0.336723 -0.836612 -0.622397 0.128691 -0.77205 -0.606374 0.106958 -0.787954 -0.224901 -0.726667 -0.649134 -0.209661 -0.730794 -0.649602 -0.610523 -0.403244 -0.681657 -0.587571 -0.417865 -0.692927 -0.840089 0.0163707 -0.542202 -0.82017 -0.00763862 -0.572069 -0.258672 -0.760022 -0.5962 -0.245733 -0.760985 -0.60043 -0.702998 -0.504709 -0.501061 -0.679408 -0.516054 -0.521625 -0.955114 -0.118909 -0.271328 -0.938112 -0.142969 -0.315445 -0.980764 -0.154201 -0.119686 -0.965923 -0.208017 -0.154017 -0.896815 -0.349485 -0.271261 -0.793216 -0.481043 -0.373372 -0.707036 -0.563404 -0.427406 -0.19501 -0.7748 -0.601378 -0.258752 -0.766626 -0.587649 -0.442122 -0.708565 -0.549968 -0.608583 -0.626831 -0.486528 -0.192302 -0.852789 -0.485563 -0.192306 -0.852789 -0.485561 -0.549826 -0.725865 -0.413294 -0.438269 -0.770934 -0.462148 -0.603021 -0.69323 -0.394713 -0.827606 -0.487783 -0.277734 -0.192306 -0.966765 -0.168475 -0.192304 -0.966765 -0.168475 -0.549823 -0.82288 -0.1434 -0.549824 -0.822879 -0.1434 -0.827607 -0.552974 -0.0963645 -0.827606 -0.552976 -0.0963653 -0.980214 -0.195002 -0.0339823 -0.980214 -0.195001 -0.0339821 -0.789705 -0.528251 -0.311956 -0.894243 -0.388952 -0.221462 -0.980214 -0.172011 -0.0979402 -0.980214 -0.172012 -0.0979405 -0.965925 -0.258823 0 -0.980705 -0.195099 -0.0124061 -0.793315 -0.608739 0.00935721 -0.831477 -0.555559 0 -0.608754 -0.793359 0 -0.555554 -0.831457 0.00625877 -0.258811 -0.965883 -0.00935434 -0.195094 -0.980785 0 -0.963611 -0.069185 0.258202 -0.783002 -0.600825 0.160991 -0.694739 -0.18616 0.694753 -0.250569 -0.250562 0.935112 -0.250563 -0.250565 0.935112 -0.256752 -0.588355 0.766757 -0.121613 -0.701858 0.701858 -0.256752 -0.766757 0.588355 -0.250566 -0.935113 0.250562 -0.250566 -0.935113 0.250562 -0.694741 -0.186158 0.694751 -0.694741 -0.508594 0.508594 -0.694739 -0.508595 0.508594 -0.694739 -0.694753 0.186158 -0.601246 -0.783574 0.156572 -0.963611 -0.0691852 0.258202 -0.963611 -0.189017 0.189017 -0.963611 -0.189017 0.189017 -0.963611 -0.258202 0.0691852 -0.96361 -0.258202 0.0691851 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.258825 0 0.965924 -0.258825 0 0.965924 -0.999998 0.000507164 0.00182653 -0.998688 0.0137016 0.0493456 -0.997654 0.0556383 0.0398789 -0.987754 0.0804805 0.133663 -0.98263 0.127546 0.134796 -0.99997 0.00753572 -0.00177764 -0.998139 0.0236999 0.0561871 -0.985523 0.168671 -0.0171799 -0.974983 0.199451 0.0981255 -0.931598 0.358788 0.0582803 -0.718512 0.618713 0.317701 -0.826979 0.55995 -0.0506183 -0.942194 0.322648 0.0903783 -0.957375 0.270259 -0.101947 -0.994896 0.0343509 0.0948752 -0.99997 0.00755094 -0.00179031 -0.374845 0.916668 0.138607 -0.648473 0.760788 -0.0261703 -0.759889 0.636981 0.129709 -0.902793 0.386832 0.18795 -0.93447 0.243188 0.260048 -0.956396 0.152717 0.248965 -0.908213 0.26307 0.32549 -0.877583 0.277334 0.391067 -0.712932 0.678935 0.175432 -0.615575 0.711228 0.339444 -0.351401 0.936191 -0.00795461 -0.187981 0.956853 0.221575 -0.914483 0.247936 0.319764 -0.885613 0.264575 0.381692 -0.747783 0.641864 0.169798 -0.655997 0.681765 0.323827 -0.426642 0.904403 -0.00557769 -0.271483 0.939835 0.207379 -0.651074 0.715395 0.253599 -0.243919 0.966872 0.0752498 -0.936264 0.0885914 0.339944 -0.920383 0.213159 0.327807 -0.907108 0.277958 0.316061 -0.860838 0.401443 0.312734 -0.633291 0.739091 0.229537 -0.374848 0.916667 -0.138605 -0.99997 0.00753549 0.00177845 -0.994901 0.0344497 -0.0947938 -0.985558 0.168338 0.0183778 -0.959403 0.219175 -0.177506 -0.937075 0.348685 -0.0175974 -0.999998 0.000510611 -0.00182571 -0.998074 0.0167093 -0.0597449 -0.997672 0.0555522 -0.0395565 -0.984101 0.0861549 -0.155317 -0.984404 0.125037 -0.123751 -0.585553 0.810473 -0.0161819 -0.942337 0.240706 -0.232513 -0.941174 0.162703 -0.296174 -0.781339 0.622642 -0.0427342 -0.848392 0.410459 -0.334298 -0.779334 0.604897 -0.163516 -0.833498 0.539618 0.118716 -0.90838 0.35217 -0.225438 -0.95733 0.269628 0.104022 -0.985316 0.0529976 -0.16231 -0.99997 0.00755071 0.00179113 -0.911047 0.262789 -0.317703 -0.886955 0.252177 -0.386934 -0.722602 0.676162 -0.143706 -0.672439 0.649384 -0.355142 -0.371078 0.925945 0.0701894 -0.313368 0.907016 -0.281288 -0.904369 0.277982 -0.323794 -0.879276 0.264805 -0.395919 -0.685559 0.712391 -0.150028 -0.634063 0.679003 -0.370027 -0.2935 0.953257 0.0718293 -0.233307 0.926466 -0.295345 -0.877677 0.378073 -0.294524 -0.920383 0.213159 -0.327808 -0.936264 0.0885916 -0.339944 -0.243919 0.966872 -0.0752498 -0.609799 0.756894 -0.235066 -0.656793 0.715489 -0.238116 -0.902798 0.277984 -0.328148 0.993228 0.116183 0 0.965696 0.258753 -0.0218684 0.937458 0.348072 -0.00427376 0.877104 0.4803 2.33104e-05 0.816697 0.577067 -7.81388e-05 0.706979 0.70699 -0.0185729 0.692069 0.72169 -0.0143 0.00137363 0.999999 0 0.169957 0.985452 -0.000305319 0.258784 0.965812 -0.0154466 0.425976 0.904734 0.000854126 0.572663 0.819791 -0.000715944 0.0184516 -0.99983 0 0.0184516 -0.99983 0 0.445717 -0.895174 0 0.445717 -0.895174 0 0.786737 -0.617289 0 0.786737 -0.617289 0 0.975512 -0.219946 0 0.975512 -0.219946 0 -0.97411 -0.225948 0.00752959 -0.913164 -0.406748 -0.0262276 -0.985436 -0.170047 -0.000201774 -0.999996 -0.00274913 0 -0.349347 -0.936889 -0.0139801 -0.41798 -0.908453 -0.00232318 -0.216309 -0.976325 0 -0.494515 -0.869162 -0.00338626 -0.589128 -0.808039 0.000854266 -0.775209 -0.631696 -0.00333153 -0.721915 -0.691821 -0.0149182 -0.820698 -0.571354 -0.00308913 -0.216309 -0.976325 0 -0.41798 -0.908454 0.00180692 -0.348952 -0.937077 0.0109268 -0.494315 -0.869279 0.00265326 -0.775194 -0.631684 0.00700506 -0.716707 -0.697373 0.00150003 -0.589192 -0.807993 -0.000669944 -0.999996 -0.00274913 0 -0.985431 -0.170078 0.000165087 -0.974126 -0.225952 0.00502691 -0.904595 -0.42627 -0.00130132 -0.820459 -0.5717 0.00247064 0.975512 -0.219946 0 0.975512 -0.219946 0 0.786737 -0.617289 0 0.786737 -0.617289 0 0.445717 -0.895174 0 0.445717 -0.895174 0 0.0184516 -0.99983 0 0.0184516 -0.99983 0 0.00137363 0.999999 0 0.807447 0.588816 0.0363937 0.707101 0.707112 0.00016373 0.877103 0.480301 -1.67975e-05 0.693558 0.720321 0.010737 0.572762 0.819722 0.000538895 0.258814 0.965925 -0.00186074 0.403241 0.914564 0.0311219 0.170011 0.985442 0.000241039 0.965927 0.258815 0 0.992627 0.116113 0.0347882 0.937522 0.347913 0.00307564 -0.404431 -0.879006 -0.252555 -0.404431 -0.879006 -0.252554 -0.299402 -0.650732 -0.697787 -0.299402 -0.650731 -0.697787 -0.11085 -0.240925 -0.964193 -0.11085 -0.240924 -0.964193 -0.750084 -0.611222 -0.252551 -0.750088 -0.611213 -0.252561 -0.555293 -0.452483 -0.697789 -0.55529 -0.452505 -0.697777 -0.205585 -0.167531 -0.964193 -0.205586 -0.167524 -0.964194 -0.942557 -0.218629 -0.252561 -0.942557 -0.218631 -0.25256 -0.697789 -0.161855 -0.697778 -0.697779 -0.161827 -0.697794 -0.258342 -0.0599142 -0.964194 -0.258347 -0.0599335 -0.964191 -0.198032 -0.960584 -0.195093 -0.196268 -0.945776 -0.258818 -0.18109 -0.878403 -0.442284 -0.160187 -0.777009 -0.608766 -0.144424 -0.6922 -0.707107 -0.122918 -0.596232 -0.793347 -0.089302 -0.433172 -0.896877 -0.0534931 -0.253224 -0.965928 -0.0393886 -0.19106 -0.980788 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.7071 0 -0.707114 -0.7071 0 -0.707114 -0.258812 0 -0.965928 -0.258812 0 -0.965928 0.879059 -0.198206 -0.433556 0.0181137 -0.981523 -0.190486 0.43756 -0.878782 -0.19048 0.437556 -0.878783 -0.190486 0.77233 -0.605988 -0.190488 0.772332 -0.605986 -0.190485 0.957649 -0.215926 -0.190485 0.957652 -0.21592 -0.190475 0.603105 -0.135976 -0.785987 0.78095 -0.176073 -0.599262 0.807385 -0.215764 -0.549159 0.659082 -0.517131 -0.546065 0.659075 -0.517133 -0.546072 0.373399 -0.749923 -0.546067 0.373405 -0.749923 -0.546062 0.194892 -0.0439347 -0.97984 0.440103 -0.0992129 -0.892449 0.0181128 -0.981523 -0.190487 0.0166268 -0.900997 -0.433507 0.0483072 -0.834322 -0.549156 0.0147726 -0.80042 -0.599258 0.0114086 -0.618149 -0.785978 0.532723 -0.169692 -0.829103 0.444588 -0.348839 -0.825017 0.444584 -0.34884 -0.825019 0.251883 -0.505866 -0.825018 0.251877 -0.505865 -0.825021 0.0586506 -0.556007 -0.829106 0.0083247 -0.451073 -0.892448 0.194886 -0.043942 -0.979841 0.157172 -0.123324 -0.979841 0.157174 -0.123323 -0.979841 0.0890462 -0.178838 -0.979841 0.0890442 -0.178838 -0.979841 0.00368639 -0.199747 -0.979841 0.00368817 -0.199747 -0.979841 -0.25847 0.0514046 -0.964651 -0.700206 0.139293 -0.700221 -0.948575 0.188686 -0.254173 -0.948568 0.1887 -0.254186 -0.804153 0.537333 -0.254185 -0.804177 0.537311 -0.254157 -0.537327 0.804165 -0.254162 -0.537312 0.804171 -0.254176 -0.188686 0.948575 -0.254172 -0.188685 0.948575 -0.254173 -0.700231 0.139262 -0.700202 -0.593627 0.396632 -0.700207 -0.593614 0.39664 -0.700214 -0.396632 0.59362 -0.700213 -0.396633 0.59362 -0.700212 -0.139283 0.700217 -0.700211 -0.139276 0.700215 -0.700215 -0.258456 0.0514261 -0.964653 -0.219114 0.146407 -0.964652 -0.219119 0.146404 -0.964652 -0.146406 0.219119 -0.964651 -0.146414 0.219117 -0.964651 -0.0514102 0.258466 -0.964651 -0.0514081 0.258466 -0.964652 0.19508 0 -0.980787 0.442285 0.00174973 -0.896873 0.258812 0 -0.965928 0.608759 0 -0.793355 0.793344 0.00117064 -0.608772 0.7071 0 -0.707114 0.896852 0 -0.442331 0.965925 0.000442262 -0.258822 0.980788 0 -0.195077 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258808 -0.965929 0 0.258808 -0.965929 0.250558 0.935114 -0.250566 0.250557 0.935115 -0.250563 0.186152 0.694747 -0.694747 0.186149 0.69475 -0.694745 0.0691782 0.258188 -0.963615 0.0691716 0.258195 -0.963613 0.684546 0.684557 -0.250558 0.684554 0.684542 -0.250577 0.508594 0.508585 -0.694747 0.508592 0.508592 -0.694743 0.189008 0.189008 -0.963614 0.189008 0.189008 -0.963614 0.93511 0.250557 -0.25058 0.935111 0.250571 -0.250565 0.694752 0.186164 -0.694739 0.694742 0.186138 -0.694756 0.258192 0.0691757 -0.963614 0.258192 0.0691743 -0.963614 0.0691735 0.258202 0.963611 0.0691824 0.258204 0.96361 0.160982 0.600819 0.783008 0.246247 0.668336 0.701919 0.250559 0.935114 0.250563 0.250556 0.935114 0.250566 0.207928 0.776019 0.59545 0.189018 0.189018 0.96361 0.189018 0.189018 0.96361 0.508589 0.508589 0.694748 0.508596 0.508587 0.694744 0.684557 0.684546 0.250557 0.684543 0.684553 0.250576 0.258206 0.0691782 0.96361 0.258205 0.0691792 0.96361 0.694761 0.186143 0.694736 0.694739 0.186161 0.694753 0.935107 0.250569 0.250581 0.935114 0.250558 0.250566 0.980788 0 0.195077 0.89685 0.00175012 0.442331 0.965925 0 0.258822 0.793345 0 0.608772 0.707099 0.000590362 0.707114 0.608759 0 0.793355 0.442286 0 0.896874 0.258825 0.000442129 0.965924 0.195099 0 0.980784 0 0.195095 0.980784 -0.00300214 0.258821 0.965921 0.00200867 0.555567 0.831469 0 0.608759 0.793355 0 0.831474 0.555564 0.00300215 0.793355 0.608752 -0.00398281 0.980777 0.195094 0 0.965925 0.258822 0.440103 -0.0992129 0.892449 0.00368849 -0.199765 0.979837 0.0890544 -0.178855 0.979837 0.0890532 -0.178856 0.979837 0.157187 -0.123336 0.979837 0.157188 -0.123334 0.979837 0.194908 -0.0439382 0.979837 0.19491 -0.0439476 0.979836 0.780951 -0.176073 0.599262 0.603105 -0.135976 0.785987 0.532723 -0.169692 0.829103 0.444586 -0.348842 0.825017 0.444586 -0.348838 0.825018 0.251879 -0.505868 0.825018 0.251881 -0.505863 0.82502 0.957651 -0.215926 0.190475 0.879059 -0.198206 0.433556 0.00368674 -0.199766 0.979837 0.0083247 -0.451073 0.892448 0.0586506 -0.556007 0.829106 0.0114086 -0.618149 0.785978 0.0147726 -0.80042 0.599258 0.807385 -0.215764 0.549159 0.659078 -0.517136 0.546064 0.659079 -0.517128 0.546071 0.373403 -0.74992 0.546067 0.3734 -0.749925 0.546062 0.0483072 -0.834322 0.549156 0.0166268 -0.900997 0.433507 0.957651 -0.215919 0.190484 0.77233 -0.605988 0.190485 0.772331 -0.605986 0.190488 0.43756 -0.878781 0.190486 0.437557 -0.878784 0.190481 0.0181128 -0.981523 0.190486 0.0181137 -0.981523 0.190487 -0.766736 0.588377 0.256765 -0.0691807 0.258203 0.963611 -0.258205 0.0691779 0.96361 -0.258206 0.0691793 0.96361 -0.694742 0.186138 0.694756 -0.694752 0.186164 0.694739 -0.935111 0.250571 0.250565 -0.93511 0.250557 0.25058 -0.588364 0.766747 0.256763 -0.66794 0.667952 0.32817 -0.508591 0.5086 0.694738 -0.508592 0.508592 0.694743 -0.189014 0.189014 0.963612 -0.189008 0.189034 0.963609 -0.0691818 0.258202 0.963611 -0.160982 0.600819 0.783008 -0.246251 0.668339 0.701914 -0.207933 0.776018 0.595449 -0.250562 0.935111 0.250571 -0.250558 0.935114 0.250566 -0.0393923 -0.191078 0.980784 -0.0534957 -0.253237 0.965924 -0.089302 -0.433172 0.896877 -0.122918 -0.596232 0.793347 -0.144424 -0.6922 0.707107 -0.160187 -0.777009 0.608766 -0.18109 -0.878403 0.442284 -0.196268 -0.945776 0.258818 -0.198032 -0.960584 0.195093 -0.258825 0 0.965924 -0.258825 0 0.965924 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.110856 -0.240937 0.964189 -0.110855 -0.240937 0.964189 -0.299402 -0.650732 0.697787 -0.299401 -0.650732 0.697787 -0.404431 -0.879006 0.252555 -0.404431 -0.879006 0.252554 -0.2056 -0.167535 0.964189 -0.205594 -0.167538 0.96419 -0.555279 -0.452496 0.697791 -0.5553 -0.452489 0.697779 -0.75009 -0.611214 0.25255 -0.750082 -0.61122 0.252561 -0.258348 -0.0599338 0.964191 -0.25836 -0.0599183 0.964189 -0.697797 -0.161832 0.697775 -0.697776 -0.161853 0.697791 -0.942557 -0.218631 0.252562 -0.942557 -0.218629 0.25256 -0.999995 0 0.00312988 -0.150095 0 0.988672 -0.345417 0.00773456 0.938417 -0.196583 0 0.980487 -0.196583 0 0.980487 -0.150095 0 0.988672 -0.150095 0 0.988672 -0.631108 0.000734556 0.775694 -0.465938 0 0.884817 -0.341553 0 0.939863 -0.176479 -0.000338572 0.984304 -0.150095 0 0.988672 -0.466445 -0.000886994 0.88455 -0.630655 0 0.776064 -0.765253 0 0.64373 -0.876752 0.000653229 0.480942 -0.765805 -0.000932132 0.643072 -0.87643 0 0.481529 -0.980992 -1.82844e-05 0.194049 -0.999998 0.00148025 0.00144332 -0.980988 0 0.194069 -0.980988 0 -0.194069 -0.999998 -0.00148023 -0.00144691 -0.980992 1.82554e-05 -0.194049 -0.999995 0 -0.00313478 -0.765253 0 -0.64373 -0.876752 -0.000653229 -0.480942 -0.765805 0.000932132 -0.643072 -0.87643 0 -0.481529 -0.465938 0 -0.884817 -0.631108 -0.000734556 -0.775694 -0.466445 0.000886994 -0.88455 -0.630655 0 -0.776064 -0.150119 0 -0.988668 -0.34218 -0.0012516 -0.939634 -0.150261 0.000390502 -0.988646 -0.341553 0 -0.939863 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.417984 0.908455 0 -0.417984 0.908455 0 -0.775214 0.631699 0 -0.775214 0.631699 0 -0.974139 0.225948 0 -0.974139 0.225948 0 0 1 0 0 1 0 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.866026 -0.499999 0 -0.866026 -0.499999 0 -1 0 0 -1 0 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.207912 0.978148 -1.21257e-08 -0.207912 0.978148 -3.03565e-08 -0.207911 0.978148 0 -0.207912 0.978148 -2.89159e-08 -0.207911 0.978148 -2.26441e-07 -0.20791 0.978148 9.48858e-08 -0.207912 0.978148 1.01822e-07 -0.207912 0.978148 -4.03992e-07 -0.20791 0.978148 5.69991e-09 -0.207912 0.978148 -5.61666e-09 -0.207912 0.978148 3.55689e-08 -0.207912 0.978148 3.6162e-08 -0.207912 0.978148 2.6168e-08 -0.207912 0.978148 0 -0.207912 -0.978148 0 -0.207912 -0.978148 1.31851e-07 -0.207912 -0.978148 1.71959e-06 -0.207908 -0.978148 -6.56291e-08 -0.207911 -0.978148 -9.23647e-07 -0.207909 -0.978148 -1.40315e-07 -0.207911 -0.978148 1.53084e-08 -0.207912 -0.978148 -1.95056e-06 -0.207912 -0.978148 -4.35915e-09 -0.207912 -0.978148 2.64217e-07 -0.207914 -0.978147 -4.21098e-08 -0.207912 -0.978148 -3.29945e-08 -0.207912 -0.978148 -5.46115e-08 -0.207912 -0.978148 -0.939465 -0.0457713 0.339574 -0.976058 -0.199478 0.0867205 -0.939388 -0.328971 0.0965866 -0.96612 -0.0669305 0.249265 -0.938778 -0.0678224 0.33778 -0.939465 -0.13048 0.316828 -0.95576 -0.129224 0.264244 -0.939465 -0.169957 0.297522 -0.939465 -0.206639 0.273323 -0.95576 -0.192074 0.222781 -0.939465 -0.239921 0.244628 -0.939465 -0.269258 0.211909 -0.95576 -0.242339 0.16672 -0.939465 -0.294165 0.175704 -0.938837 -0.323471 0.118114 -0.93861 -0.324096 0.11821 -0.938931 -0.32581 -0.110707 -0.939466 -0.329711 -0.0932417 -0.936065 -0.293293 -0.194322 -0.936186 -0.293108 -0.194018 -0.937364 -0.290866 -0.191692 -0.969223 -0.228843 -0.0907563 -0.939119 -0.325342 -0.110485 -0.939546 -0.30361 -0.15835 -0.946702 -0.280916 -0.15761 -0.936415 -0.292918 -0.1932 -0.923944 -0.11367 -0.365249 -0.93936 -0.0503726 -0.339213 -0.93936 -0.0503726 -0.339213 -0.939688 -0.0791376 -0.332751 -0.937929 -0.0932905 -0.334046 -0.0438318 -0.994152 0.0986973 0 -0.995345 0.0963795 0 -0.995345 0.0963795 -0.0158781 -0.995071 0.0978865 0 -0.995345 -0.0963795 0 -0.995345 -0.0963795 -0.0123002 -0.995155 -0.0975491 -0.039379 -0.994336 -0.0987156 -0.939692 -0.0238582 0.341188 -0.939692 -0.0238583 0.341189 -0.939674 -0.023861 0.341238 -0.939707 -0.0238554 0.341148 -0.939692 -0.0238582 -0.341188 -0.939692 -0.0238581 -0.341189 -0.939684 -0.0238593 -0.341211 -0.939707 -0.0238554 -0.341148 -0.348174 -0.93743 0 -0.348174 -0.93743 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.348174 -0.93743 0 -0.348174 -0.93743 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.921417 0.388576 0.00384181 0.925382 0.379016 0.000433248 0.909366 0.415997 0 0.904994 0.425424 0.0160203 0.90392 -0.427402 0.0121087 0.908484 -0.417744 0 0.925389 -0.379019 0.0576504 0.83985 -0.539748 0.212656 0.815056 -0.538944 0.618928 0.645578 -0.44739 0 0.789967 -0.61315 0.0215785 0.845449 -0.53362 0.00105018 0.851449 -0.524436 -0.00326149 0.90569 -0.423928 0.0244018 0.896812 -0.441737 0.0175931 0.902398 -0.430545 -0.974139 0.225948 0 -0.974139 0.225948 0 -0.775214 0.631699 0 -0.775214 0.631699 0 -0.417984 0.908455 0 -0.417984 0.908455 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.0330398 -0.877589 0.478274 -0.00302281 -0.900313 0.435234 -0.00522305 -0.895975 0.444075 -0.0114339 -0.886638 0.462323 -0.000666899 -0.907574 0.419892 0.00401059 -0.947234 0.320517 0 -0.94565 0.325188 -0.0333351 -0.877828 -0.477814 -0.0116666 -0.886824 -0.461959 -0.00527874 -0.896255 -0.443508 -0.00291677 -0.900986 -0.433838 -0.000715791 -0.907975 -0.419024 0.00416952 -0.945641 -0.325185 0 -0.947408 -0.320029 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.5 -0.377902 -0.779224 -0.5 -0.377904 -0.779223 -0.5 -0.377904 -0.779223 -0.5 -0.377901 -0.779225 -0.5 -0.377902 0.779224 -0.5 -0.377903 0.779224 -0.499999 -0.377903 0.779224 -0.500002 -0.377899 0.779224 -0.5 -0.377901 0.779225 0 0.985153 -0.17168 0 0.985153 -0.17168 0 0.869008 -0.494798 0 0.869008 -0.494798 0 0.93098 0.36507 0 0.99882 0.0485566 -0.00809196 0.975371 0.220423 -0.0158392 0.984492 0.17471 -0.00680557 0.966928 0.25496 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 -0.704917 -0.705955 -0.0687022 -0.704912 -0.705959 -0.068704 -0.704917 -0.705955 0.0687022 -0.705452 -0.705453 -0.0683646 -0.705445 -0.705445 0.068513 -0.704896 -0.706004 0.068418 -0.66479 -0.743547 -0.0720563 -0.482835 -0.871003 -0.0906901 -0.194274 -0.976677 0.0914261 -0.27448 -0.956484 0.098987 -0.0550083 -0.993838 0.0962336 -0.576173 -0.813517 0.078837 -0.553675 -0.82862 0.0826558 -0.553923 -0.828991 -0.0770997 -0.194172 -0.976166 -0.0969382 -0.166944 -0.981376 -0.095027 -0.998455 -0.0553079 -0.00539164 -0.960973 -0.274723 -0.0325354 -0.743206 -0.665917 0.0648058 -0.830083 -0.554642 0.0577344 -0.873379 -0.484922 0.0453767 -0.985642 -0.168051 0.0163823 -0.980562 -0.195058 0.0212095 -0.980657 -0.195077 -0.0160604 -0.830155 -0.55469 -0.0562367 -0.814219 -0.577828 -0.0562331 -0.995903 -0.0355543 -0.0831403 -0.984132 -0.110233 -0.13904 -0.984558 -0.0521738 -0.167102 -0.98472 -0.0517485 -0.16628 -0.984718 -0.0255817 -0.17227 -0.984718 -0.0255818 -0.172269 -0.962749 -0.018862 -0.269739 -0.999998 -0.000133895 -0.0019148 -0.984807 -0.0118732 -0.173243 -0.998321 0.0148996 -0.055981 -0.988638 -0.00226911 -0.1503 -0.996172 -0.0838829 0.0246056 -0.965937 -0.253016 0.0542965 -0.984753 -0.166912 0.0490055 -0.984746 -0.15957 0.0693712 -0.984746 -0.15957 0.0693712 -0.984746 -0.149379 0.0892238 -0.984746 -0.149379 0.0892237 -0.984746 -0.136731 0.107609 -0.984746 -0.136731 0.107609 -0.984746 -0.121834 0.124224 -0.984746 -0.121834 0.124224 -0.984746 -0.104933 0.138796 -0.984746 -0.104933 0.138795 -0.984746 -0.0863054 0.151084 -0.984746 -0.0863053 0.151084 -0.984746 -0.0662585 0.160887 -0.984746 -0.0662586 0.160888 -0.984746 -0.0451219 0.168045 -0.984746 -0.045122 0.168045 -0.984746 -0.0232431 0.172438 -0.984746 -0.023243 0.172438 -0.984807 -0.0121132 0.173227 -0.999637 0.0257312 0.00803101 -0.998321 0.0148998 0.0559801 -0.988638 -0.00226911 0.1503 -0.962749 -0.018862 0.269739 -0.996177 -0.0840624 -0.0237502 -0.952597 -0.254029 -0.167414 -0.991308 -0.105839 -0.0781473 -0.99122 -0.110312 -0.0728934 -0.984658 -0.140744 -0.103153 -0.984768 -0.154166 -0.080406 -0.984768 -0.154166 -0.080406 -0.984768 -0.161628 -0.0640994 -0.984768 -0.161628 -0.0640994 -0.984601 -0.171021 -0.0362205 -0.965782 -0.249568 -0.0705773 0 -0.398182 -0.917306 0 -0.398182 -0.917306 0 -0.724098 -0.689697 0 -0.724098 -0.689697 0 -0.935586 -0.353098 0 -0.935586 -0.353098 0 -0.999227 0.039301 0 -0.999227 0.039301 0 -0.999227 -0.039301 0 -0.999227 -0.039301 0 -0.935587 0.353098 0 -0.935587 0.353098 0 -0.724098 0.689697 0 -0.724098 0.689697 0 -0.398182 0.917306 0 -0.398182 0.917306 -0.0493997 -0.998779 0 -0.258815 -0.965927 0 -0.999982 -0.00606356 0 -0.965927 -0.258815 -0.00025673 -0.98142 -0.19184 -0.00337092 -0.79333 -0.608785 0.00277959 -0.849632 -0.527375 -0.000785047 -0.608773 -0.793344 0.000581984 -0.577007 -0.816738 0.00160541 -0.246303 -0.969191 -0.00219192 -0.290395 -0.956898 -0.0041903 -0.146869 -0.989155 -0.00104957 -0.258815 -0.965927 0 -0.2907 -0.956807 0.00369877 -0.146945 -0.989144 0.000926429 -0.0493997 -0.998779 0 -0.246625 -0.969109 0.00194122 -0.608773 -0.793343 -0.00178351 -0.576439 -0.81714 -0.000647956 -0.793333 -0.608787 0.000364796 -0.850493 -0.525984 -0.00127247 -0.965927 -0.258815 0 -0.999848 -0.0143279 0.00997984 -0.981484 -0.19152 0.00297601 -0.176876 -0.984233 0 -0.176876 -0.984233 0 -0.176875 -0.984233 0 -0.176875 -0.984233 0 -0.176876 -0.984233 0 -0.176876 -0.984233 0 -0.176875 -0.984233 0 -0.176875 -0.984233 0 0.145262 -0.741764 0.65474 0 -0.735747 0.677257 -0.982697 -0.0808226 -0.166654 -0.985671 -0.088106 -0.143843 -0.901261 -0.181557 -0.393403 -0.908859 -0.182008 -0.375298 -0.81575 -0.252394 -0.520432 -0.826027 -0.253462 -0.503425 -0.638086 -0.320875 -0.699918 -0.652029 -0.330849 -0.6822 -0.995481 -0.0414353 0.0854386 -0.985165 -0.104564 0.136077 -0.959582 -0.115589 0.256596 -0.874885 -0.225525 0.42862 -0.854793 -0.21429 0.472661 -0.652059 -0.344489 0.675386 -0.637446 -0.336215 0.693269 -0.649214 -0.3319 -0.684371 -0.638774 -0.342804 -0.688806 -0.871789 -0.206578 -0.444194 -0.857085 -0.233523 -0.459209 -0.97817 -0.0835158 -0.190286 -0.985904 -0.0807542 -0.146531 -0.999805 -0.00862111 -0.0177765 -0.999805 -0.00862087 0.017776 -0.708006 -0.308163 0.635424 -0.639776 -0.35321 0.68259 -0.81574 -0.252475 0.520408 -0.966293 -0.112136 0.23174 -0.90303 -0.216888 0.370806 -0.978684 -0.0918882 0.183668 -0.730034 -0.672187 0.123351 -0.13165 -0.944514 -0.300935 -0.640978 -0.497153 0.584796 -0.547127 -0.771733 0.32416 -0.547507 -0.770717 0.325932 -0.367507 -0.929964 0.0102572 -0.174753 -0.924718 -0.33817 -0.169524 -0.923727 -0.343496 -0.492047 -0.8631 -0.11379 -0.641033 -0.498146 0.583889 -0.858629 -0.380226 0.34378 -0.858712 -0.379057 0.344861 -0.966716 -0.247161 0.0661262 -0.967608 -0.242565 0.0699842 -0.887129 -0.459217 -0.0460684 -0.818739 -0.565987 -0.0965657 -0.731261 -0.670352 0.126037 -0.488853 -0.864335 -0.118102 -0.369463 -0.929118 0.0154089 -0.127691 -0.942467 -0.308952 -0.195027 -0.904065 -0.380304 -0.191746 -0.904042 -0.382022 -0.441259 -0.843415 -0.306498 -0.546592 -0.7982 -0.253206 -0.606016 -0.759204 -0.237391 -0.786799 -0.603224 -0.130644 -0.11272 -0.930902 -0.347443 -0.0940268 -0.918702 -0.383596 -0.298272 -0.954385 0.0135148 -0.287406 -0.957697 -0.0146437 -0.434372 -0.820174 0.372338 -0.430609 -0.828996 0.356849 -0.498562 -0.550419 0.669683 -0.498489 -0.555126 0.66584 -0.109436 -0.947741 -0.299684 -0.0906991 -0.93733 -0.336431 -0.289971 -0.955667 0.0511544 -0.278934 -0.96003 0.0231832 -0.4252 -0.814785 0.39412 -0.421188 -0.824023 0.378928 -0.494095 -0.547011 0.675758 -0.493888 -0.551783 0.672019 -0.965644 -0.245746 -0.0845064 -0.896324 -0.416666 -0.151633 -0.98063 -0.185225 -0.0636946 -0.25779 -0.913687 -0.314196 -0.194341 -0.926748 -0.321511 -0.440745 -0.848846 -0.291899 -0.705636 -0.670063 -0.23042 -0.607391 -0.749484 -0.263345 -0.792134 -0.577175 -0.198477 -0.563503 -0.825319 -0.0362385 -0.563071 -0.825628 -0.0359176 -0.895883 -0.444217 0.0080457 -0.856019 -0.508893 0.0908863 -0.710275 -0.703772 0.0146422 -0.727633 -0.677991 0.1043 -0.818325 -0.410025 0.402771 -0.85338 -0.318028 0.413039 -0.897526 -0.357613 0.257994 -0.965668 -0.241576 0.0955303 -0.946925 -0.321307 -0.00977708 -0.998239 0.0275003 0.0525675 -0.999241 -0.038348 -0.00690922 -0.642412 -0.518692 0.564149 -0.635138 -0.501628 0.587341 -0.558185 -0.785891 0.266092 -0.558212 -0.777772 0.288914 -0.350342 -0.927909 -0.127456 -0.340308 -0.939442 -0.0404882 -0.120316 -0.910185 -0.396342 -0.25398 -0.966462 -0.0380124 -0.699968 -0.713622 -0.0280677 -0.96459 -0.263552 -0.0103658 -0.96459 -0.263552 -0.0103658 -0.96459 -0.246766 0.0931315 -0.964589 -0.246767 0.0931314 -0.964589 -0.190985 0.181912 -0.964589 -0.190985 0.181912 -0.964589 -0.105023 0.241945 -0.96459 -0.105023 0.241945 -0.699968 -0.713622 -0.0280678 -0.699968 -0.668172 0.252173 -0.699969 -0.668171 0.252173 -0.699969 -0.517132 0.492563 -0.699969 -0.517132 0.492563 -0.699969 -0.284371 0.655116 -0.699968 -0.284372 0.655116 -0.25398 -0.966462 -0.0380123 -0.25398 -0.904908 0.341519 -0.25398 -0.904908 0.341519 -0.25398 -0.700355 0.667081 -0.25398 -0.700355 0.667081 -0.25398 -0.385126 0.887227 -0.253981 -0.385126 0.887227 -0.790164 -0.555136 -0.25974 -0.986954 -0.146566 0.0666289 -0.987573 -0.156941 -0.00830632 -0.915967 -0.40048 0.0248926 -0.808177 -0.58641 0.0545364 -0.806959 -0.589888 -0.0291417 -0.450949 -0.887488 -0.0949166 -0.462259 -0.88139 -0.0973031 -0.465893 -0.856451 -0.222341 -0.257739 -0.852378 -0.454997 -0.601825 -0.737026 -0.307569 -0.789869 -0.5554 -0.260072 -0.789846 -0.612062 -0.0390269 -0.928227 -0.37044 -0.0341924 -0.929556 -0.368174 0.0193552 -0.995644 -0.0910812 0.0199105 -0.995626 -0.0933761 0.00315582 -0.999987 0.000685695 0.00508504 -1 0 0 -0.99952 -0.0306946 0.00420265 -0.99934 -0.0281104 0.0230039 -0.992067 -0.124995 0.0133612 -0.992005 -0.124661 0.0196186 -0.975836 -0.217785 -0.0177069 -0.976481 -0.20708 -0.0600293 -0.964918 -0.240788 -0.104665 -0.965918 -0.0538178 0.253193 -0.965918 -0.0538178 0.253193 -0.707129 -0.147011 0.691633 -0.707129 -0.147011 0.691633 -0.258808 -0.200828 0.944821 -0.258808 -0.200828 0.944821 -0.965683 -0.228121 -0.124169 -0.980648 -0.185482 -0.0626548 -0.980648 -0.185483 -0.062655 -0.896194 -0.420328 -0.141985 -0.830573 -0.527155 -0.179599 -0.792278 -0.578071 -0.195269 -0.607322 -0.752673 -0.254249 -0.554188 -0.788152 -0.267752 -0.440959 -0.850324 -0.287235 -0.194387 -0.929336 -0.313924 -0.194388 -0.929336 -0.313924 -0.980596 -0.17079 -0.0962378 -0.792184 -0.537053 -0.289858 -0.830516 -0.489218 -0.266288 -0.607321 -0.697784 -0.379814 -0.554188 -0.73179 -0.396685 -0.257963 -0.847561 -0.463784 -0.194388 -0.861562 -0.468961 -0.258518 -0.214814 0.941819 -0.258784 -0.214315 0.94186 -0.705938 -0.185777 0.683475 -0.706613 -0.184254 0.68319 -0.964129 -0.107084 0.242874 -0.964607 -0.104682 0.242022 -0.251094 -0.271122 0.929217 -0.251922 -0.270804 0.929086 -0.682154 -0.338315 0.648235 -0.684159 -0.337133 0.646737 -0.927762 -0.315353 0.199524 -0.929359 -0.312828 0.196037 -0.212536 -0.348099 0.913047 -0.213299 -0.348071 0.91288 -0.577569 -0.547769 0.60528 -0.579486 -0.547344 0.60383 -0.786436 -0.601079 0.142206 -0.788215 -0.599466 0.139135 -0.191339 -0.980766 -0.0385749 -0.601022 -0.798615 -0.0314106 -0.893264 -0.449185 -0.0176672 -0.980021 -0.19874 -0.0078166 -0.965912 -0.256298 0.036394 -0.964597 -0.246741 0.0931217 -0.964597 -0.246741 0.0931217 -0.964597 -0.190965 0.181893 -0.964597 -0.190965 0.181893 -0.964597 -0.105012 0.24192 -0.964597 -0.105012 0.24192 -0.787399 -0.615967 -0.024227 -0.70413 -0.709726 0.0221324 -0.699954 -0.668185 0.252178 -0.699954 -0.668185 0.252178 -0.699954 -0.517142 0.492573 -0.699954 -0.517142 0.492573 -0.699954 -0.284377 0.655129 -0.699955 -0.284377 0.655129 -0.435147 -0.899664 -0.035385 -0.255491 -0.966798 -0.00506102 -0.253988 -0.904906 0.341518 -0.253987 -0.904906 0.341519 -0.253987 -0.700353 0.66708 -0.253987 -0.700353 0.66708 -0.253987 -0.385125 0.887226 -0.253986 -0.385125 0.887226 -0.181746 -0.378682 0.907507 -0.181792 -0.378707 0.907487 -0.497233 -0.634151 0.592126 -0.497313 -0.634174 0.592033 -0.6813 -0.722046 0.120333 -0.681392 -0.722001 0.120082 -0.181722 -0.378656 0.907522 -0.181754 -0.378674 0.907509 -0.497136 -0.63409 0.592271 -0.497258 -0.634125 0.592131 -0.68127 -0.722042 0.120527 -0.681338 -0.722009 0.120341 -0.980788 -0.0405589 0.190814 -0.965754 -0.0721899 0.249213 -0.896851 -0.0919663 0.432666 -0.793376 -0.126563 0.59543 -0.706893 -0.171514 0.686211 -0.608754 -0.164949 0.776022 -0.442288 -0.18647 0.877274 -0.258768 -0.219175 0.940745 -0.195087 -0.203917 0.959353 -0.171501 -0.388336 0.905418 -0.171902 -0.388209 0.905397 -0.468658 -0.660552 0.586541 -0.469707 -0.660102 0.586208 -0.641906 -0.758341 0.113469 -0.643328 -0.757255 0.112668 -0.125921 -0.423026 0.897326 -0.126362 -0.423216 0.897174 -0.342316 -0.751837 0.563525 -0.343426 -0.752089 0.562513 -0.466624 -0.880212 0.086541 -0.467921 -0.879726 0.0844523 -0.0435891 -0.451127 0.891395 -0.0437071 -0.451237 0.891333 -0.118497 -0.828305 0.547604 -0.118814 -0.828512 0.547221 -0.161567 -0.984713 0.0650961 -0.162004 -0.984691 0.0643282 -0.977705 -0.123004 0.170186 -0.195421 -0.220461 0.955619 -0.195059 -0.22058 0.955666 -0.97716 -0.124462 0.172242 -0.894114 -0.168049 0.415114 -0.832227 -0.167113 0.528651 -0.791462 -0.19416 0.57956 -0.555793 -0.219823 0.801731 -0.608528 -0.19155 0.770067 -0.441956 -0.224189 0.86857 -0.948543 -0.287415 0.132886 -0.947841 -0.288763 0.134956 -0.80602 -0.325386 0.494425 -0.804912 -0.326144 0.495729 -0.539767 -0.313599 0.781222 -0.538842 -0.313897 0.781741 -0.189822 -0.253468 0.948536 -0.189462 -0.253522 0.948594 0 -0.451556 0.892243 0 -0.451556 0.892243 0 -0.834182 0.551489 0 -0.834182 0.551489 0 -0.997822 0.0659627 0 -0.997822 0.0659627 -0.938195 -0.34576 -0.0155136 -0.918334 -0.379038 0.113986 -0.912172 -0.376917 0.160863 -0.784823 -0.389115 0.482331 -0.821974 -0.412997 0.392163 -0.183967 -0.269376 0.9453 -0.135718 -0.274898 0.951847 -0.308117 -0.306194 0.900727 -0.52379 -0.358771 0.772611 -0.455029 -0.369331 0.810274 -0.653798 -0.37297 0.658363 -0.183948 -0.26937 0.945306 -0.183968 -0.269372 0.945301 -0.523647 -0.359045 0.77258 -0.523689 -0.359042 0.772554 -0.783098 -0.393691 0.481421 -0.783137 -0.393677 0.481369 -0.922503 -0.367996 0.116482 -0.922538 -0.367946 0.116358 -0.780192 -0.543887 0.309011 -0.024167 -0.990399 -0.136106 -0.0725189 -0.831986 0.550037 -0.201734 -0.514778 0.833251 -0.0765209 -0.450232 0.889627 -0.132513 -0.856135 0.499473 -0.257934 -0.846914 0.464981 -0.29389 -0.869872 0.39617 -0.341725 -0.571667 0.745936 -0.466092 -0.453992 0.759374 -0.349135 -0.504284 0.789812 -0.634539 -0.582815 0.507628 -0.596756 -0.543796 0.590058 -0.450832 -0.842252 0.295572 -0.452978 -0.843078 0.289881 -0.0879641 -0.991875 0.0919049 -0.129693 -0.989055 0.0703622 -0.136387 -0.990412 0.0219477 -0.0488345 -0.997793 0.0449927 -0.0329476 -0.99728 0.0659269 -0.872877 -0.434494 -0.222036 -0.230746 -0.79476 0.56135 -0.237774 -0.856157 0.458759 -0.600894 -0.795096 0.0821502 -0.758624 -0.647729 -0.0702611 -0.901252 -0.386039 -0.196773 -0.879399 -0.47238 -0.0592843 0.207522 -0.966221 0.152815 -0.542624 -0.794547 0.272495 -0.639484 -0.740053 0.208284 -0.599107 -0.769415 0.22152 -0.885849 -0.459597 -0.0635794 -0.864114 -0.486242 -0.129908 -0.924425 -0.358839 -0.129128 -0.895634 -0.403324 -0.187534 -0.683537 -0.717707 -0.132945 -0.252361 -0.752902 0.607826 -0.929004 -0.367416 -0.0442341 -0.891363 -0.451951 -0.0348218 -0.22949 -0.766453 0.599903 -0.561122 -0.711692 0.422654 -0.635573 -0.713978 0.29374 -0.737334 -0.622336 0.262748 -0.838991 -0.528005 0.131553 -0.973391 -0.223564 0.0502902 -0.252347 -0.707237 0.660406 -0.194844 -0.728475 0.65678 -0.441556 -0.673657 0.592634 -0.593593 -0.622313 0.510268 -0.606915 -0.614253 0.504329 -0.788902 -0.502826 0.353269 -0.77564 -0.510745 0.370839 -0.890578 -0.394286 0.226735 -0.878608 -0.408268 0.24772 -0.965097 -0.252874 0.0681361 -0.195095 -0.693519 0.693519 -0.25882 -0.680625 0.685392 -0.442282 -0.634187 0.634187 -0.608756 -0.560988 0.560988 -0.707095 -0.496815 0.503181 -0.793351 -0.430461 0.430461 -0.896895 -0.312713 0.312713 -0.965919 -0.180631 0.185397 -0.980781 -0.137967 0.137967 -0.979443 -0.174696 -0.100861 -0.96361 -0.231498 0.133655 -0.783002 -0.538684 -0.311009 -0.694742 -0.622897 0.35963 -0.430047 -0.781854 -0.451403 -0.250565 -0.838399 0.48405 -0.250565 -0.838399 0.48405 -0.250565 -0.9681 0 -0.250565 -0.9681 0 -0.250565 -0.838399 -0.484049 -0.189376 -0.843105 -0.5033 -0.694741 -0.622898 0.35963 -0.694741 -0.71926 0 -0.694741 -0.71926 0 -0.694741 -0.622898 -0.35963 -0.598653 -0.679935 -0.423441 -0.96361 -0.231498 0.133655 -0.96361 -0.267311 0 -0.96361 -0.267311 0 -0.963611 -0.231497 -0.133655 -0.894012 -0.368375 -0.255036 -0.195099 -0.693519 -0.693519 -0.19509 -0.69352 -0.69352 -0.442294 -0.634183 -0.634183 -0.442283 -0.634187 -0.634187 -0.608748 -0.560992 -0.560993 -0.608753 -0.56099 -0.56099 -0.793351 -0.430461 -0.430461 -0.793351 -0.430461 -0.430461 -0.896896 -0.312712 -0.312712 -0.896895 -0.312713 -0.312713 -0.980781 -0.137966 -0.137966 -0.980781 -0.137967 -0.137967 -0.191489 -0.54529 -0.816083 -0.25343 -0.549539 -0.796103 -0.435406 -0.500144 -0.748517 -0.601313 -0.443909 -0.664356 -0.698214 -0.413201 -0.584604 -0.787598 -0.342336 -0.512343 -0.893445 -0.249546 -0.373474 -0.963888 -0.1588 -0.213779 -0.980043 -0.11044 -0.165285 -0.254173 -0.188684 -0.948575 -0.25417 -0.188683 -0.948576 -0.700208 -0.139282 -0.700221 -0.700211 -0.139283 -0.700218 -0.964647 -0.0514151 -0.25848 -0.964647 -0.051415 -0.258481 -0.965925 0 -0.258823 -0.965925 0 -0.258823 -0.707103 0 -0.70711 -0.707103 0 -0.70711 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.231393 -0.0237566 -0.97257 -0.206336 -0.0141472 -0.978379 -0.643363 -0.0738814 -0.761988 -0.582969 -0.0444075 -0.81128 -0.915468 -0.110975 -0.386786 -0.860233 -0.063046 -0.505988 -0.258807 -0.00928956 -0.965884 -0.233007 -0.00047378 -0.972475 -0.706693 -0.03405 -0.7067 -0.647891 -0.00614067 -0.761709 -0.964552 -0.0532888 -0.258456 -0.922266 -0.0052795 -0.386519 -0.847462 -0.0839676 -0.524174 -0.799579 -0.0657279 -0.596954 -0.579697 -0.0711237 -0.811722 -0.204589 -0.027287 -0.978468 -0.202432 -0.0246138 -0.978987 -0.558424 -0.070846 -0.826525 -0.623005 -0.0440535 -0.780977 -0.620957 -0.0650961 -0.781137 -0.853828 -0.0909842 -0.512542 -0.852284 -0.10455 -0.512524 -0.855657 -0.105601 -0.506655 -0.0888336 -0.937846 0.335489 -0.111353 -0.947208 0.300662 -0.277599 -0.960401 -0.0238478 -0.291337 -0.955289 -0.0504483 -0.420388 -0.824248 -0.379327 -0.426018 -0.814564 -0.393694 -0.493622 -0.551865 -0.672147 -0.494369 -0.546934 -0.675621 -0.0921058 -0.919291 0.382649 -0.114695 -0.930294 0.348421 -0.286029 -0.958119 0.0139775 -0.299681 -0.953954 -0.0128077 -0.429784 -0.829252 -0.357249 -0.435217 -0.819919 -0.371914 -0.498215 -0.555218 -0.665969 -0.498844 -0.550341 -0.669537 -0.800528 -0.422231 -0.425295 -0.190779 -0.905555 0.37891 -0.964917 -0.248554 -0.0845902 -0.96348 -0.254603 -0.0829661 -0.884952 -0.464619 0.0314523 -0.816847 -0.57068 0.0841675 -0.195019 -0.904699 0.378797 -0.441032 -0.845975 0.299693 -0.54564 -0.801185 0.245723 -0.605384 -0.76268 0.22766 -0.78532 -0.607794 0.117729 -0.16477 -0.926504 0.338291 -0.172124 -0.926071 0.335805 -0.47825 -0.872179 0.102859 -0.482708 -0.86999 0.100551 -0.714914 -0.683704 -0.146448 -0.716856 -0.681361 -0.147868 -0.802282 -0.527077 -0.280238 -0.883984 -0.359966 -0.298325 -0.123134 -0.943825 0.306648 -0.129784 -0.944496 0.3018 -0.358265 -0.933496 -0.0152224 -0.361744 -0.932094 -0.0184871 -0.534926 -0.777019 -0.331805 -0.535836 -0.775944 -0.332852 -0.627656 -0.502683 -0.594439 -0.627268 -0.503831 -0.593877 -0.858066 -0.374027 -0.351889 -0.79658 -0.600679 0.0681561 -0.909884 -0.394559 -0.128197 -0.340308 -0.939442 0.0404883 -0.12032 -0.910185 0.39634 -0.528772 -0.846546 0.0613249 -0.727632 -0.677992 -0.1043 -0.710275 -0.703772 -0.0146421 -0.846519 -0.411525 -0.337716 -0.965668 -0.241576 -0.0955303 -0.946925 -0.321307 0.00977709 -0.998239 0.0275003 -0.0525675 -0.99924 -0.0383518 0.00691259 -0.643614 -0.497576 -0.581532 -0.633848 -0.52257 -0.570226 -0.565094 -0.774298 -0.284837 -0.551631 -0.7887 -0.271396 -0.350343 -0.927909 0.127455 -0.541521 -0.839399 0.0465304 -0.98063 -0.185225 0.0636946 -0.965595 -0.245256 0.0864603 -0.896063 -0.419799 0.144359 -0.792134 -0.577175 0.198477 -0.70551 -0.669304 0.232998 -0.194295 -0.927629 0.318991 -0.257743 -0.913043 0.316104 -0.440745 -0.848845 0.291899 -0.607163 -0.751391 0.258386 -0.805702 -0.581596 -0.112208 -1 0 0 -0.99979 0.00271498 -0.020324 -0.984571 -0.14115 -0.103423 -0.987573 -0.156941 0.00830615 -0.808339 -0.587093 -0.0437132 -0.953816 -0.298364 -0.0348373 -0.993413 -0.0827279 -0.0792846 -0.995619 -0.0934758 -0.00242228 -0.99952 -0.0306948 -0.00420268 -0.99195 -0.126213 0.0102616 -0.975085 -0.221827 0.00127526 -0.793421 -0.602226 0.0883591 -0.46199 -0.882015 0.0928124 -0.690867 -0.717448 0.0892785 -0.928728 -0.365656 -0.0613228 -0.929462 -0.368883 -0.00504877 -0.992023 -0.124736 -0.0182171 -0.99952 -0.0308193 -0.0032944 -0.252557 -0.906588 0.338103 -0.459247 -0.803089 0.379659 -0.697391 -0.672715 0.247184 -0.789885 -0.555447 0.259925 -0.963678 -0.252941 0.0857089 -0.97592 -0.200047 0.0869559 -0.699968 -0.517132 -0.492564 -0.980021 -0.0791958 -0.182446 -0.896801 -0.0951852 -0.432073 -0.96459 -0.105023 -0.241945 -0.96459 -0.190985 -0.181911 -0.96459 -0.190985 -0.181912 -0.96459 -0.246766 -0.0931316 -0.96459 -0.246766 -0.0931313 -0.96459 -0.263552 0.0103658 -0.96459 -0.263552 0.0103658 -0.699968 -0.517132 -0.492564 -0.699968 -0.668171 -0.252173 -0.699968 -0.668172 -0.252173 -0.699968 -0.713622 0.0280677 -0.699969 -0.713622 0.0280678 -0.192691 -0.354249 -0.915084 -0.435103 -0.358516 -0.825925 -0.699968 -0.284372 -0.655116 -0.606246 -0.25341 -0.753823 -0.787399 -0.245457 -0.565467 -0.25398 -0.385126 -0.887227 -0.25398 -0.700355 -0.667081 -0.25398 -0.700355 -0.667081 -0.25398 -0.904908 -0.34152 -0.25398 -0.904908 -0.34152 -0.25398 -0.966462 0.0380124 -0.25398 -0.966462 0.0380123 -0.19438 -0.929174 0.314406 -0.257949 -0.914499 0.311694 -0.440943 -0.850183 0.287678 -0.607304 -0.752555 0.254643 -0.7059 -0.670018 0.229739 -0.792265 -0.577986 0.195574 -0.96568 -0.246033 0.0832505 -0.96568 -0.246033 0.0832506 -0.257925 -0.848359 0.462344 -0.257924 -0.848359 0.462344 -0.70581 -0.622025 0.338995 -0.70581 -0.622024 0.338995 -0.965685 -0.228047 0.124283 -0.965686 -0.228047 0.124282 -0.980788 -0.0405588 -0.190814 -0.980788 -0.0405589 -0.190814 -0.896806 -0.0919852 -0.432756 -0.896806 -0.0919852 -0.432756 -0.793377 -0.126562 -0.595428 -0.793377 -0.126562 -0.595428 -0.608779 -0.164945 -0.776003 -0.608779 -0.164945 -0.776003 -0.442243 -0.186475 -0.877296 -0.442243 -0.186475 -0.877296 -0.195087 -0.203917 -0.959353 -0.195087 -0.203917 -0.959353 -0.601022 -0.798615 0.0314104 -0.980021 -0.0791961 -0.182446 -0.980021 -0.0791955 -0.182445 -0.980021 -0.144018 -0.137176 -0.980021 -0.144018 -0.137176 -0.980021 -0.186081 -0.0702288 -0.980021 -0.186082 -0.0702287 -0.980021 -0.198739 0.00781655 -0.965912 -0.252648 0.0564115 -0.826248 -0.224298 -0.516724 -0.826248 -0.2243 -0.516725 -0.826248 -0.40789 -0.388511 -0.826249 -0.407888 -0.388511 -0.826248 -0.527022 -0.198902 -0.826248 -0.527022 -0.198902 -0.828595 -0.559811 -0.00652534 -0.787399 -0.615967 0.0242267 -0.547831 -0.333116 -0.767408 -0.54783 -0.333116 -0.767408 -0.54783 -0.605772 -0.576994 -0.547829 -0.605774 -0.576994 -0.547829 -0.782703 -0.295398 -0.54783 -0.782702 -0.295398 -0.549804 -0.835233 0.0100565 -0.435147 -0.899664 0.0353855 -0.191336 -0.390827 -0.900358 -0.191339 -0.390825 -0.900358 -0.191338 -0.71072 -0.676954 -0.191339 -0.71072 -0.676954 -0.191338 -0.918301 -0.346574 -0.191339 -0.918301 -0.346574 -0.191338 -0.980766 0.0385755 -0.191339 -0.980766 0.0385748 -0.524895 -0.606312 -0.597386 -0.844447 -0.511128 -0.160181 -0.71779 -0.684662 -0.126552 -0.718721 -0.683439 -0.127876 -0.62115 -0.483555 -0.616723 -0.967538 -0.200251 -0.154176 -0.947064 -0.237793 -0.215696 -0.844347 -0.512517 -0.156219 -0.620385 -0.482034 -0.618681 -0.524501 -0.607305 -0.596724 -0.192108 -0.368555 -0.909539 -0.886496 -0.238825 -0.396343 -0.786281 -0.255962 -0.562357 -0.690486 -0.298737 -0.658776 -0.605516 -0.265195 -0.750347 -0.440998 -0.259289 -0.859238 -0.191982 -0.368955 -0.909404 -0.22834 -0.323971 -0.918098 -0.228701 -0.324655 -0.917766 -0.247424 -0.273307 -0.929562 -0.19498 -0.236278 -0.951922 -0.980788 -0.0405588 -0.190814 -0.980788 -0.0405588 -0.190814 -0.831476 -0.115507 -0.54342 -0.831476 -0.115507 -0.54342 -0.555565 -0.172873 -0.813303 -0.555565 -0.172873 -0.813303 -0.195085 -0.203917 -0.959354 -0.195085 -0.203917 -0.959354 -0.181747 -0.378679 -0.907508 -0.181728 -0.37865 -0.907524 -0.497229 -0.634154 -0.592125 -0.497165 -0.634062 -0.592277 -0.681307 -0.722039 -0.120334 -0.681301 -0.722012 -0.120533 -0.181783 -0.378715 -0.907485 -0.181754 -0.378672 -0.907509 -0.497294 -0.634192 -0.59203 -0.497252 -0.634132 -0.59213 -0.68135 -0.722042 -0.120074 -0.681342 -0.722005 -0.120342 -0.948109 -0.287777 -0.135183 -0.94827 -0.288405 -0.132693 -0.805085 -0.325441 -0.495909 -0.805809 -0.326089 -0.494305 -0.538926 -0.313499 -0.781843 -0.539635 -0.313991 -0.781156 -0.189486 -0.253394 -0.948623 -0.189776 -0.25359 -0.948513 -0.977248 -0.123443 -0.172477 -0.97761 -0.124029 -0.169986 -0.829312 -0.185735 -0.527014 -0.830166 -0.186228 -0.525493 -0.554918 -0.219869 -0.802324 -0.555731 -0.220234 -0.801661 -0.195057 -0.220445 -0.955697 -0.195397 -0.220595 -0.955593 -0.0141978 -0.451526 -0.892145 -0.0142279 -0.451511 -0.892152 -0.0388036 -0.833584 -0.551028 -0.0388896 -0.833551 -0.551072 -0.0531972 -0.996415 -0.0657831 -0.0533292 -0.996402 -0.0658688 -0.0716749 -0.445123 -0.892596 -0.0717644 -0.444878 -0.892711 -0.19482 -0.811793 -0.550489 -0.195088 -0.811278 -0.551152 -0.265504 -0.961664 -0.0686236 -0.266056 -0.961417 -0.0699457 -0.150634 -0.408535 -0.900227 -0.150629 -0.407991 -0.900474 -0.409323 -0.71201 -0.570523 -0.40941 -0.710847 -0.57191 -0.557349 -0.82482 -0.0950447 -0.558083 -0.823995 -0.0978619 -0.526308 -0.351948 -0.774036 -0.167737 -0.271311 -0.947763 -0.183967 -0.269376 -0.9453 -0.779458 -0.403423 -0.479265 -0.731748 -0.383709 -0.563305 -0.480197 -0.361175 -0.799352 -0.922536 -0.367952 -0.116357 -0.924625 -0.380487 0.0173002 -0.918004 -0.378907 -0.117037 -0.895304 -0.383046 -0.227391 -0.855517 -0.389391 -0.341271 -0.922514 -0.367965 -0.116489 -0.922527 -0.367977 -0.116351 -0.783104 -0.393676 -0.481423 -0.783131 -0.393692 -0.481365 -0.523651 -0.359034 -0.772582 -0.523685 -0.359053 -0.772551 -0.183948 -0.269365 -0.945307 -0.183967 -0.269377 -0.9453 0 -0.997822 -0.0659627 0 -0.997822 -0.0659627 0 -0.834182 -0.551489 0 -0.834182 -0.551489 0 -0.451556 -0.892243 0 -0.451556 -0.892243 -0.494426 -0.502829 -0.709018 -0.529352 -0.766885 -0.362868 -0.464388 -0.84704 -0.258585 -0.078627 -0.996694 0.0204487 -0.135857 -0.990658 -0.011809 -0.190545 -0.9707 -0.146404 -0.194108 -0.968729 -0.154554 -0.311379 -0.847775 -0.429327 -0.336532 -0.869784 -0.360863 -0.412474 -0.58351 -0.699558 -0.68271 -0.542981 -0.488956 -0.69932 -0.565827 -0.436796 -0.826513 -0.4836 -0.28811 -0.213431 -0.441152 -0.871684 -0.121338 -0.529801 -0.839397 -0.152909 -0.824372 -0.545004 -0.0953165 -0.859844 -0.501581 -0.0595421 -0.996052 -0.0658457 -0.0391845 -0.998223 -0.0448971 -0.250562 0.250563 -0.935113 -0.250564 0.250562 -0.935113 -0.694743 0.186157 -0.69475 -0.694741 0.186158 -0.694751 -0.96361 0.0691855 -0.258203 -0.963611 0.0691847 -0.258202 -0.250564 0.684549 -0.684551 -0.250562 0.68455 -0.68455 -0.694741 0.508594 -0.508594 -0.69474 0.508595 -0.508594 -0.963611 0.189017 -0.189017 -0.963611 0.189017 -0.189017 -0.250565 0.935113 -0.250562 -0.250566 0.935112 -0.250563 -0.69474 0.694753 -0.186159 -0.69474 0.694753 -0.186159 -0.963611 0.258202 -0.0691851 -0.963611 0.258202 -0.0691851 -0.195093 0.980785 0 -0.258821 0.965923 0.00226112 -0.442288 0.896873 0 -0.608753 0.79336 0 -0.707097 0.70711 0.00301926 -0.980781 0.195114 0 -0.965923 0.258821 0.00226045 -0.896896 0.442241 0 -0.79335 0.608766 0 -0.619228 0.772885 0.138582 -0.19488 0.979713 0.0467444 -0.22421 0.973334 0.0484883 -0.439779 0.891784 0.106381 -0.602917 0.785754 0.138139 -0.975607 0.00457457 0.219478 -0.95259 0.189506 0.238031 -0.882969 0.425374 0.198549 -0.878966 0.4334 0.198953 -0.778784 0.59759 0.19074 -0.748719 -0.136573 0.648666 -0.737904 0.00457089 0.67489 -0.713026 0.327754 0.619816 -0.669195 0.424753 0.609723 -0.51674 0.728437 0.449844 -0.470055 0.772552 0.426863 -0.190903 0.96769 0.164719 -0.170334 0.973456 0.152872 -0.534554 -0.142256 0.833076 -0.534556 -0.14224 0.833077 -0.507886 0.33994 0.791513 -0.507886 0.33994 0.791513 -0.361901 0.742245 0.564004 -0.361901 0.742245 0.564003 -0.130883 0.970188 0.203973 -0.13088 0.970189 0.20397 -0.0899709 0.946294 0.310538 -0.143062 0.922631 0.358168 -0.31086 0.703466 0.639141 -0.343993 0.666957 0.660937 -0.463398 0.308613 0.830675 -0.477788 0.279529 0.832816 -0.51502 -0.153217 0.843373 -0.517509 -0.163291 0.839953 -0.097616 0.969435 0.225092 -0.152253 0.950063 0.272397 -0.331762 0.741777 0.582839 -0.365455 0.706766 0.605743 -0.48656 0.339832 0.804844 -0.500717 0.310857 0.807868 -0.526034 -0.142233 0.838485 -0.528272 -0.15243 0.835281 -0.133564 0.884835 0.446349 -0.194028 0.867351 0.458318 -0.469586 0.668608 0.576588 -0.501757 0.645296 0.57605 -0.721051 0.33598 0.605973 -0.729822 0.323741 0.602122 -0.845652 -0.0507667 0.531314 -0.843578 -0.043848 0.535214 -0.105449 0.918776 0.380435 -0.162055 0.895331 0.414874 -0.375603 0.669477 0.640877 -0.401649 0.644137 0.650973 -0.567261 0.288051 0.771519 -0.570073 0.283015 0.77131 -0.645531 -0.145564 0.749734 -0.639357 -0.122191 0.759139 -0.19646 0.883785 0.42465 -0.97635 0.13794 0.16647 -0.97724 0.135147 0.163514 -0.893346 0.365638 0.261231 -0.827951 0.461554 0.318536 -0.19503 0.883809 0.425259 -0.44176 0.797452 0.410997 -0.553273 0.724442 0.411184 -0.607591 0.696045 0.382564 -0.790947 0.521006 0.320868 -0.190381 0.863621 0.466813 -0.187362 0.863892 0.467532 -0.537172 0.683289 0.494532 -0.534747 0.684396 0.495629 -0.800829 0.399149 0.44649 -0.799266 0.400703 0.447896 -0.942152 0.055156 0.330617 -0.941461 0.0568575 0.332293 -0.194972 0.90763 0.371745 -0.2587 0.895771 0.36148 -0.442023 0.830077 0.339981 -0.608545 0.734314 0.300759 -0.707013 0.656947 0.261826 -0.793196 0.56353 0.230809 -0.896698 0.409617 0.16777 -0.96591 0.241431 0.09343 -0.980765 0.180629 0.0739817 -0.19497 0.90763 -0.371745 -0.194972 0.90763 -0.371745 -0.555329 0.769582 -0.315204 -0.555328 0.769583 -0.315204 -0.8313 0.514353 -0.210667 -0.831301 0.514352 -0.210667 -0.980765 0.180629 -0.0739817 -0.980765 0.180629 -0.0739817 -0.891599 -0.00236521 -0.452819 -0.127105 0.81139 -0.570518 -0.63891 -0.152769 -0.75396 -0.638873 -0.154074 -0.753726 -0.584797 0.0903802 -0.806129 -0.549051 0.216757 -0.807192 -0.131065 0.806383 -0.576687 -0.293118 0.645803 -0.704997 -0.370274 0.55683 -0.74353 -0.400249 0.496443 -0.770289 -0.519008 0.270946 -0.810691 -0.171387 0.842218 -0.51117 -0.176517 0.838791 -0.515045 -0.4898 0.62871 -0.604003 -0.492894 0.624741 -0.605602 -0.730147 0.320933 -0.603231 -0.731361 0.317758 -0.603441 -0.817452 0.124286 -0.562428 -0.810021 -0.0664716 -0.582621 -0.194917 0.876081 -0.44101 -0.198126 0.874823 -0.442075 -0.552719 0.712464 -0.432316 -0.556009 0.709608 -0.432795 -0.822747 0.441751 -0.357692 -0.825272 0.437244 -0.357412 -0.967243 0.107254 -0.230083 -0.968096 0.101555 -0.229078 -0.0858033 0.795059 -0.600432 -0.132657 0.731787 -0.668499 -0.208033 0.625569 -0.751921 -0.292557 0.470816 -0.832312 -0.347255 0.334792 -0.875973 -0.38619 0.237605 -0.891292 -0.440613 0.0516168 -0.896212 -0.476767 -0.144646 -0.867047 -0.486611 -0.198257 -0.850826 -0.474608 -0.15315 -0.866771 -0.473728 -0.145529 -0.868564 -0.342805 0.309498 -0.886958 -0.335296 0.331307 -0.881937 -0.131484 0.700352 -0.701584 -0.114329 0.726438 -0.677655 -0.613407 -0.133779 -0.778354 -0.615921 -0.103268 -0.78101 -0.443308 0.317177 -0.838378 -0.439088 0.338758 -0.832133 -0.831815 -0.025985 -0.554444 -0.829343 0.0156627 -0.55852 -0.606009 0.39659 -0.689543 -0.594173 0.422461 -0.684459 -0.247355 0.763597 -0.596436 -0.223044 0.72354 -0.653255 -0.213173 0.733134 -0.645811 -0.162753 0.697768 -0.697589 -0.157418 0.708103 -0.688338 -0.951722 0.105418 -0.288291 -0.942398 0.155005 -0.296412 -0.786502 0.410448 -0.461461 -0.688619 0.533834 -0.490739 -0.606141 0.5838 -0.540157 -0.258626 0.757033 -0.600011 -0.965896 0.204547 -0.158764 -0.980689 0.159147 -0.113672 -0.896818 0.349482 -0.271258 -0.793215 0.481043 -0.373372 -0.793216 0.481042 -0.373371 -0.60858 0.626833 -0.48653 -0.608581 0.626832 -0.48653 -0.442131 0.708561 -0.549965 -0.258752 0.766626 -0.587649 -0.19501 0.7748 -0.601378 -0.192306 0.852788 -0.485562 -0.254776 0.835168 -0.487427 -0.436988 0.781645 -0.445054 -0.603017 0.693233 -0.394714 -0.700551 0.613345 -0.364741 -0.788922 0.534 -0.304049 -0.894246 0.388948 -0.22146 -0.964467 0.224619 -0.139101 -0.980214 0.172012 -0.0979405 -0.255234 0.952524 -0.165993 -0.255231 0.952525 -0.165993 -0.701791 0.701807 -0.122301 -0.701791 0.701806 -0.122301 -0.964944 0.258559 -0.0450582 -0.964944 0.25856 -0.0450582 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.7071 0.707114 0 -0.7071 0.707114 0 -0.965925 0.258823 0 -0.965925 0.258823 0 -0.250566 0.935112 0.250564 -0.250566 0.935112 0.250564 -0.694739 0.694753 0.186159 -0.694739 0.694753 0.186159 -0.96361 0.258202 0.0691853 -0.963611 0.258202 0.069185 -0.250563 0.68455 0.68455 -0.250563 0.68455 0.68455 -0.694739 0.508595 0.508595 -0.694741 0.508594 0.508593 -0.963611 0.189017 0.189017 -0.963611 0.189017 0.189017 -0.250563 0.250562 0.935113 -0.250569 0.250565 0.935111 -0.694741 0.18616 0.694751 -0.694739 0.186159 0.694753 -0.963611 0.0691851 0.258202 -0.963611 0.0691851 0.258202 -0.374845 -0.916668 0.138607 -0.99997 -0.00753572 -0.00177764 -0.994901 -0.0344495 0.0947933 -0.98556 -0.168329 -0.0183731 -0.959403 -0.219165 0.177518 -0.937075 -0.348685 0.0175974 -0.999998 -0.000507164 0.00182653 -0.998072 -0.016604 0.0597985 -0.997672 -0.0555521 0.039556 -0.984101 -0.0861549 0.155317 -0.984404 -0.125037 0.123751 -0.585553 -0.810473 0.0161819 -0.942337 -0.240705 0.232511 -0.941175 -0.162703 0.296172 -0.781335 -0.622648 0.0427234 -0.848392 -0.410459 0.334298 -0.779334 -0.604897 0.163516 -0.833497 -0.539621 -0.118709 -0.908378 -0.352187 0.225419 -0.957325 -0.269639 -0.104037 -0.985304 -0.0529172 0.162405 -0.99997 -0.00753862 -0.00178005 -0.233307 -0.926466 0.295345 -0.293508 -0.953249 -0.0718982 -0.634082 -0.679006 0.369988 -0.685565 -0.712384 0.150034 -0.879276 -0.264805 0.395919 -0.904361 -0.277977 0.323821 -0.313373 -0.90702 0.281268 -0.371078 -0.925945 -0.0701894 -0.672435 -0.649392 0.355134 -0.722588 -0.676167 0.143753 -0.886947 -0.252178 0.386951 -0.911039 -0.26279 0.317725 -0.877678 -0.378069 0.294524 -0.920383 -0.213159 0.327807 -0.936264 -0.0885908 0.339944 -0.243904 -0.966875 0.0752501 -0.609792 -0.7569 0.235068 -0.6568 -0.715481 0.238119 -0.902799 -0.27798 0.328149 -0.999998 -0.000510611 -0.00182571 -0.998688 -0.013795 -0.0493246 -0.997654 -0.0556383 -0.0398789 -0.987754 -0.0804805 -0.133663 -0.98263 -0.127546 -0.134796 -0.99997 -0.00753549 0.00177845 -0.998139 -0.0236999 -0.0561871 -0.985524 -0.168662 0.0171753 -0.974984 -0.19944 -0.098131 -0.931597 -0.358789 -0.0582854 -0.718512 -0.618713 -0.317701 -0.826979 -0.55995 0.0506183 -0.942189 -0.322665 -0.0903692 -0.95737 -0.270271 0.101958 -0.994894 -0.0342947 -0.0949213 -0.99997 -0.00753839 0.00178087 -0.374848 -0.916667 -0.138605 -0.648473 -0.760788 0.0261703 -0.759884 -0.636988 -0.129701 -0.902794 -0.386831 -0.187947 -0.934471 -0.243188 -0.260046 -0.956397 -0.152717 -0.248964 -0.271478 -0.939834 -0.207391 -0.426642 -0.904403 0.00557777 -0.655997 -0.681765 -0.323827 -0.747763 -0.641877 -0.169837 -0.885606 -0.264575 -0.38171 -0.914475 -0.247937 -0.319784 -0.187972 -0.956858 -0.22156 -0.35142 -0.936184 0.00801115 -0.615599 -0.711224 -0.33941 -0.712932 -0.678935 -0.175432 -0.877582 -0.27734 -0.391065 -0.908223 -0.263069 -0.325463 -0.651079 -0.715388 -0.253606 -0.243904 -0.966875 -0.0752501 -0.936264 -0.0885915 -0.339944 -0.920383 -0.213159 -0.327808 -0.907107 -0.277962 -0.316061 -0.860836 -0.401447 -0.312733 -0.633291 -0.739091 -0.229537 0.692084 -0.721676 -0.014304 0.572635 -0.81981 -0.000715631 0.425999 -0.904723 0.000853891 0.258784 -0.965812 -0.0154493 0.16994 -0.985454 -0.000305289 0.00137363 -0.999999 0 0.608753 -0.793317 0.00819929 0.793326 -0.608781 -0.00437806 0.830908 -0.556404 0.00265942 0.965927 -0.258815 0 0.992051 -0.116042 -0.0486761 0.937455 -0.348079 -0.00427352 0.975512 0.219946 0 0.975512 0.219946 0 0.786737 0.617289 0 0.786737 0.617289 0 0.445717 0.895174 0 0.445717 0.895174 0 0.0184516 0.99983 0 0.0184516 0.99983 0 -0.494515 0.869162 -0.00338626 -0.417964 0.908418 -0.00909982 -0.34771 0.937601 -0.00150013 -0.216356 0.976315 0 -0.775183 0.631675 -0.00884984 -0.71687 0.697205 -0.00191368 -0.589128 0.808039 0.000854266 -0.999996 0.00274819 0 -0.985436 0.170047 -0.000201844 -0.974119 0.22595 -0.00624593 -0.904488 0.426497 0.00162623 -0.820698 0.571354 -0.00308913 -0.97412 0.22595 -0.0059992 -0.911747 0.410195 0.0214191 -0.985431 0.170078 0.000165144 -0.999996 0.00274819 0 -0.417981 0.908456 0 -0.216273 0.975943 0.0276044 -0.348947 0.937079 0.0109271 -0.494315 0.869279 0.00265326 -0.589192 0.807993 -0.000669944 -0.775211 0.631697 0.00261663 -0.720762 0.69308 0.01191 -0.820459 0.5717 0.00247064 0.0184516 0.99983 0 0.0184516 0.99983 0 0.445717 0.895174 0 0.445717 0.895174 0 0.786737 0.617289 0 0.786737 0.617289 0 0.975512 0.219946 0 0.975512 0.219946 0 0.993228 -0.11618 0 0.980748 -0.195086 0.00861078 0.937824 -0.347098 -0.00308974 0.840444 -0.541873 0.00528907 0.83144 -0.555567 0.00725335 0.773884 -0.633324 0.00209605 0.648613 -0.761107 -0.00419885 0.555566 -0.83144 0.0072879 0.476092 -0.879394 0.00175706 0.195079 -0.980787 0 -0.0242089 -0.999281 0.0291906 0.230885 -0.97297 -0.00456924 -0.942558 0.218629 -0.25256 -0.942557 0.21863 -0.252561 -0.697777 0.161852 -0.697791 -0.697797 0.161831 -0.697775 -0.258347 0.0599149 -0.964192 -0.258335 0.05993 -0.964195 -0.750082 0.61122 -0.252561 -0.75009 0.611215 -0.25255 -0.5553 0.452489 -0.697779 -0.555279 0.452496 -0.697791 -0.205583 0.16753 -0.964194 -0.20559 0.167527 -0.964193 -0.404431 0.879006 -0.252554 -0.404431 0.879006 -0.252555 -0.299402 0.650732 -0.697787 -0.299402 0.650732 -0.697787 -0.11085 0.240925 -0.964193 -0.110846 0.240925 -0.964193 -0.0522567 0.253478 -0.965929 -0.0522568 0.253479 -0.965928 -0.142773 0.692541 -0.707108 -0.142774 0.692544 -0.707105 -0.195032 0.946032 -0.258817 -0.195032 0.94603 -0.258823 -0.258812 0 -0.965928 -0.258812 0 -0.965928 -0.7071 0 -0.707114 -0.7071 0 -0.707114 -0.965925 0 -0.258822 -0.965925 0 -0.258822 0.00488679 0.264811 -0.964288 0.0132077 0.715694 -0.698289 0.0178518 0.96733 -0.252891 0.0178514 0.96733 -0.252891 0.431229 0.866076 -0.252891 0.431234 0.866072 -0.252897 0.761162 0.597222 -0.252901 0.761158 0.597231 -0.252891 0.943803 0.212797 -0.252891 0.943803 0.212794 -0.252894 0.0132073 0.715695 -0.698288 0.319056 0.640778 -0.698288 0.319058 0.640775 -0.69829 0.563152 0.441869 -0.698292 0.563151 0.441877 -0.698288 0.698287 0.157439 -0.69829 0.698283 0.157426 -0.698297 0.00488948 0.264809 -0.964288 0.118053 0.23709 -0.964288 0.11805 0.237094 -0.964288 0.208369 0.163497 -0.964288 0.20837 0.163493 -0.964288 0.258371 0.058249 -0.964288 0.258372 0.0582568 -0.964287 -0.766736 -0.588377 -0.256765 -0.250559 -0.935117 -0.250553 -0.250573 -0.935108 -0.250571 -0.186163 -0.694739 -0.694753 -0.18615 -0.694754 -0.694741 -0.0691791 -0.258192 -0.963614 -0.0691883 -0.258183 -0.963615 -0.588364 -0.766747 -0.256763 -0.66794 -0.667952 -0.32817 -0.508591 -0.5086 -0.694738 -0.508592 -0.508592 -0.694743 -0.189004 -0.189004 -0.963616 -0.188998 -0.189024 -0.963613 -0.93511 -0.250557 -0.25058 -0.935111 -0.250571 -0.250565 -0.694752 -0.186164 -0.694739 -0.694742 -0.186138 -0.694756 -0.258192 -0.0691757 -0.963614 -0.258192 -0.0691743 -0.963614 0.965925 0 -0.258822 0.965925 0 -0.258822 0.7071 0 -0.707114 0.7071 0 -0.707114 0.258812 0 -0.965928 0.258812 0 -0.965928 0 -0.258812 -0.965928 0 -0.258812 -0.965928 0 -0.7071 -0.707114 0 -0.7071 -0.707114 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0.588367 -0.76675 -0.256747 0.935114 -0.250558 -0.250566 0.935107 -0.250569 -0.250581 0.694739 -0.186161 -0.694753 0.694761 -0.186143 -0.694736 0.258192 -0.0691756 -0.963614 0.258193 -0.0691746 -0.963614 0.766736 -0.588377 -0.256765 0.667954 -0.667943 -0.328162 0.508596 -0.508587 -0.694744 0.508589 -0.508589 -0.694748 0.189008 -0.189008 -0.963614 0.189008 -0.189008 -0.963614 0.250559 -0.935114 -0.250563 0.250568 -0.935115 -0.250552 0.18616 -0.694746 -0.694746 0.186147 -0.694741 -0.694755 0.0691788 -0.258191 -0.963614 0.0691837 -0.258192 -0.963613 0.194952 -0.0387652 0.980046 0.194955 -0.0387741 0.980046 0.440584 -0.0876268 0.893424 0.533442 -0.16179 0.830219 0.810288 -0.199131 0.551163 0.783646 -0.155887 0.60133 0.604344 -0.120219 0.787602 0.96264 -0.191484 0.191463 0.96264 -0.191481 0.191467 0.882913 -0.175622 0.435457 0.165266 -0.110447 0.980045 0.165268 -0.110427 0.980047 0.468151 -0.312804 0.826431 0.46815 -0.312791 0.826437 0.695436 -0.46465 0.548151 0.695435 -0.464693 0.548116 0.816077 -0.545307 0.191466 0.816079 -0.545302 0.191473 0.110438 -0.165259 0.980047 0.110433 -0.165268 0.980046 0.312809 -0.468134 0.826439 0.312803 -0.468148 0.826433 0.464676 -0.695444 0.548118 0.46468 -0.695435 0.548126 0.545296 -0.816083 0.191472 0.545301 -0.816077 0.191482 0.038775 -0.19495 0.980046 0.0387773 -0.194948 0.980047 0.109841 -0.552213 0.826436 0.109839 -0.552215 0.826434 0.163168 -0.820326 0.548126 0.163172 -0.820322 0.548131 0.19148 -0.962637 0.191481 0.19147 -0.962642 0.191468 0.195099 0 0.980784 0.258825 0.00044213 0.965924 0.442286 0 0.896874 0.7071 0 0.707114 0.608758 0.00117061 0.793355 0.793345 0 0.608772 0.965925 0 0.258822 0.89685 0.00175012 0.442331 0.980788 0 0.195077 0 -0.980788 0.195077 0 -0.980788 0.195077 0 -0.831465 0.555577 0 -0.831465 0.555577 0 -0.555577 0.831465 0 -0.555577 0.831465 0 -0.195095 0.980784 0 -0.195095 0.980784 0.0178514 0.96733 0.252891 0.0132073 0.715694 0.698289 0.00488983 0.264825 0.964284 0.00488701 0.264824 0.964284 0.118055 0.237104 0.964285 0.11806 0.237104 0.964284 0.208383 0.163503 0.964284 0.208379 0.163505 0.964284 0.258381 0.0582587 0.964285 0.258386 0.0582524 0.964284 0.0132077 0.715695 0.698288 0.319059 0.640777 0.698288 0.319055 0.640777 0.69829 0.563147 0.441874 0.698293 0.563155 0.441871 0.698289 0.698291 0.157428 0.698288 0.698281 0.157438 0.698295 0.0178518 0.96733 0.252891 0.431234 0.866074 0.25289 0.431229 0.866075 0.252896 0.761156 0.597229 0.252901 0.761164 0.597223 0.252891 0.943803 0.212795 0.252891 0.943802 0.212797 0.252894 -0.194833 -0.0521993 0.979447 -0.221444 -0.134086 0.965911 -0.0691941 -0.258205 0.963609 -0.0691819 -0.258202 0.963611 -0.160982 -0.600819 0.783008 -0.246251 -0.668339 0.701914 -0.188998 -0.189024 0.963613 -0.189018 -0.189018 0.96361 -0.508596 -0.508596 0.694737 -0.508589 -0.508597 0.694742 -0.250558 -0.935112 0.25057 -0.250574 -0.935113 0.250552 -0.207939 -0.776004 0.595466 -0.439213 -0.117675 0.890643 -0.60082 -0.160974 0.783009 -0.668343 -0.246247 0.701912 -0.776004 -0.207937 0.595466 -0.872066 -0.233677 0.429996 -0.588364 -0.766747 0.256763 -0.66794 -0.667952 0.32817 -0.766736 -0.588377 0.256765 -0.923555 -0.28821 0.252943 -0.948573 -0.254165 0.188706 -0.195032 0.946032 0.258818 -0.195032 0.94603 0.258823 -0.142773 0.692542 0.707108 -0.142774 0.692544 0.707105 -0.0522593 0.253491 0.965925 -0.0522595 0.253492 0.965925 -0.980781 0 0.195114 -0.980781 0 0.195114 -0.896897 0 0.44224 -0.896897 0 0.44224 -0.793345 0 0.608772 -0.793345 0 0.608772 -0.608759 0 0.793355 -0.608759 0 0.793355 -0.442286 0 0.896874 -0.442286 0 0.896874 -0.195099 0 0.980784 -0.195099 0 0.980784 -0.194899 0.0452138 0.979781 -0.221373 0.136227 0.965627 -0.439977 0.102038 0.892193 -0.602781 0.139795 0.785565 -0.67074 0.232136 0.70443 -0.780244 0.180981 0.59872 -0.878096 0.203678 0.43297 -0.930663 0.2625 0.254874 -0.956346 0.221827 0.190252 -0.205597 0.167533 0.96419 -0.205595 0.167539 0.964189 -0.55529 0.452505 0.697777 -0.555293 0.452483 0.697789 -0.750088 0.611213 0.252561 -0.750084 0.611222 0.252551 -0.110853 0.240939 0.964189 -0.110855 0.240936 0.964189 -0.299402 0.650731 0.697787 -0.299402 0.650732 0.697787 -0.404431 0.879006 0.252554 -0.404431 0.879006 0.252555 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.980785 -0.195092 0 0.980785 -0.195092 0 0.831471 -0.555569 0 0.831471 -0.555569 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.195092 -0.980785 0 0.195092 -0.980785 0 0.980785 -0.195092 0 0.980785 -0.195092 0 0.831471 -0.555569 0 0.831471 -0.555569 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.195092 -0.980785 0 0.195092 -0.980785 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.195092 -0.980785 0 -0.195092 -0.980785 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.831471 -0.555569 0 -0.831471 -0.555569 0 -0.980785 -0.195092 0 -0.980785 -0.195092 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.707114 -0.7071 0 -0.707114 -0.7071 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707114 -0.7071 0 0.707114 -0.7071 0 0.965925 -0.258822 0 0.965925 -0.258822 0 -0.195092 0.980785 0 -0.195092 0.980785 0 -0.555586 0.831459 0 -0.555586 0.831459 0 -0.831456 0.55559 0 -0.831456 0.55559 0 -0.980788 0.195077 0 -0.980788 0.195077 0 0.980788 0.195077 0 0.980788 0.195077 0 0.831474 0.555564 0 0.831474 0.555564 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195092 0.980785 0 0.195092 0.980785 0 -0.980784 -0.195095 0 -0.980784 -0.195095 0 -0.831474 -0.555564 0 -0.831474 -0.555564 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195095 -0.980784 0 -0.195095 -0.980784 0 0.195095 -0.980784 0 0.195095 -0.980784 0 0.555577 -0.831465 0 0.555577 -0.831465 0 0.831465 -0.555577 0 0.831465 -0.555577 0 0.980788 -0.195077 0 0.980788 -0.195077 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965925 0.258822 0 -0.965925 0.258822 0 0.965929 0.258808 0 0.965929 0.258808 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258822 0.965925 0 0.258822 0.965925 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965927 -0.258815 0 0.965927 -0.258815 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965929 0.258808 0 -0.965929 0.258808 0 0.965927 0.258815 0 0.965927 0.258815 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258822 0.965925 0 0.258822 0.965925 0 -0.980786 -0.195086 0 -0.965818 -0.258786 0.0150096 -0.831423 -0.555549 -0.0100437 -0.793345 -0.608772 0 -0.555577 -0.831465 0 -0.608704 -0.793256 -0.0150108 -0.195056 -0.98059 0.0199102 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.258818 0 0.965926 -0.258818 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258815 0 -0.965927 0.258815 0 0.980785 0.195091 0 0.980785 0.195091 0 0.831467 0.555574 0 0.831467 0.555574 0 0.555575 0.831467 0 0.555575 0.831467 0 0.195095 0.980784 0 0.195095 0.980784 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258818 0 -0.965926 0.258818 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -0.831467 -0.555574 0 -0.831467 -0.555574 0 -0.555574 -0.831467 0 -0.555574 -0.831467 0 -0.195096 -0.980784 0 -0.195096 -0.980784 0 0.258823 -0.965925 0 0.258823 -0.965925 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.980785 0.195091 0 0.980785 0.195091 0 0.831467 0.555574 0 0.831467 0.555574 0 0.555572 0.831468 0 0.555572 0.831468 0 0.195096 0.980784 0 0.195096 0.980784 0 -0.195095 0.980784 0 -0.258793 0.965816 0.0150091 -0.555544 0.831426 -0.0100433 -0.608766 0.79335 0 -0.83147 0.55557 0 -0.793262 0.608695 -0.01501 -0.98059 0.195056 0.0199102 -0.965925 0.258822 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.980784 0.195095 0 0.980784 0.195095 0 0.831465 0.555577 0 0.831465 0.555577 0 0.555577 0.831465 0 0.555577 0.831465 0 0.195095 0.980784 0 0.195095 0.980784 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965929 -0.258808 0 0.965929 -0.258808 0 0.965929 0.258808 0 0.965929 0.258808 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258822 0.965925 0 0.258822 0.965925 0 -0.980781 -0.195114 0 -0.980781 -0.195114 0 -0.831474 -0.555564 0 -0.831474 -0.555564 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195099 -0.980784 0 -0.195099 -0.980784 0 0.258825 -0.965924 0 0.258825 -0.965924 0 0.7071 -0.707114 0 0.7071 -0.707114 0 0.965925 -0.258822 0 0.965925 -0.258822 0 -0.258825 0.965924 0 -0.258825 0.965924 0 -0.7071 0.707114 0 -0.7071 0.707114 0 -0.965925 0.258822 0 -0.965925 0.258822 0 0.980781 0.195114 0 0.980781 0.195114 0 0.831474 0.555564 0 0.831474 0.555564 0 0.555568 0.831471 0 0.555568 0.831471 0 0.195099 0.980784 0 0.195099 0.980784 0 0 0.707107 0.707107 0 0.707107 0.707107 -0.139282 0.700214 0.700214 -0.13927 0.700225 0.700206 -0.396653 0.593609 0.700211 -0.396654 0.593607 0.700211 -0.593606 0.396655 0.700212 -0.593608 0.396634 0.700222 -0.700209 0.13927 0.700223 -0.700214 0.139287 0.700214 0.700233 0.139275 0.700198 0.700221 0.139289 0.700207 0.593622 0.396639 0.700207 0.593618 0.396641 0.70021 0.396641 0.593618 0.70021 0.396635 0.593619 0.700213 0.139283 0.700221 0.700208 0.139268 0.700216 0.700216 -0.707107 0 0.707107 -0.707107 0 0.707107 0.707124 0 0.707089 0.707124 0 0.707089 -0.694746 -0.186159 0.694746 -0.694765 -0.186144 0.694732 -0.5086 -0.50859 0.694739 -0.508579 -0.508594 0.694752 -0.186156 -0.694748 0.694746 -0.186171 -0.694753 0.694736 0.186158 -0.694755 0.694738 0.186162 -0.69475 0.694741 0.508602 -0.508591 0.694737 0.508602 -0.508588 0.694739 0.694757 -0.186162 0.694735 0.694762 -0.186173 0.694727 0 -0.707116 0.707098 0 -0.707116 0.707098 0 0.707107 0.707107 0 0.707107 0.707107 -0.186159 0.694746 0.694746 -0.186152 0.694754 0.69474 -0.508596 0.508596 0.694738 -0.508596 0.508596 0.694738 -0.694757 0.186162 0.694735 -0.694755 0.186156 0.694738 0.694756 0.186151 0.694739 0.694751 0.186155 0.694743 0.508591 0.508592 0.694744 0.508592 0.508592 0.694744 0.186159 0.694749 0.694743 0.186154 0.694747 0.694747 -0.707116 0 0.707098 -0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 -0.700223 -0.139287 0.700205 -0.700221 -0.139289 0.700207 -0.593622 -0.396639 0.700207 -0.593629 -0.396635 0.700204 -0.396645 -0.593624 0.700202 -0.396633 -0.593625 0.700208 -0.139286 -0.700222 0.700206 -0.139289 -0.700222 0.700205 0.139287 -0.700223 0.700205 0.139289 -0.700221 0.700207 0.396649 -0.593617 0.700206 0.396645 -0.593624 0.700202 0.593617 -0.396649 0.700206 0.593619 -0.396629 0.700216 0.700217 -0.139272 0.700214 0.700222 -0.139289 0.700205 0 -0.707116 0.707098 0 -0.707116 0.707098 0 0.707107 0.707107 0 0.707107 0.707107 -0.186159 0.694746 0.694746 -0.186155 0.694751 0.694743 -0.508592 0.508591 0.694744 -0.508592 0.508592 0.694744 -0.694753 0.18615 0.694742 -0.694755 0.186156 0.694738 0.694755 0.186156 0.694738 0.694748 0.186162 0.694744 0.508591 0.508592 0.694744 0.508592 0.508592 0.694744 0.186159 0.694749 0.694743 0.186154 0.694747 0.694747 -0.707116 0 0.707098 -0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 -0.694756 -0.186151 0.694739 -0.694751 -0.186155 0.694743 -0.508591 -0.508592 0.694744 -0.508592 -0.508592 0.694744 -0.186159 -0.694749 0.694743 -0.186171 -0.694753 0.694736 0.186161 -0.694755 0.694737 0.186169 -0.694745 0.694745 0.508592 -0.508591 0.694744 0.508592 -0.508592 0.694744 0.694751 -0.186155 0.694743 0.694754 -0.186164 0.694737 0 -0.707116 0.707098 0 -0.707116 0.707098 0 0.707107 0.707107 0 0.707107 0.707107 -0.186159 0.694746 0.694746 -0.186155 0.694751 0.694743 -0.508592 0.508591 0.694744 -0.508592 0.508592 0.694744 -0.694751 0.186155 0.694743 -0.694754 0.186164 0.694737 0.700221 0.139283 0.700208 0.70022 0.139284 0.700208 0.593617 0.396645 0.700208 0.593615 0.396646 0.700209 0.396645 0.593615 0.70021 0.396655 0.593614 0.700205 0.139286 0.700222 0.700206 0.139268 0.700216 0.700216 -0.707116 0 0.707098 -0.707116 0 0.707098 0.707113 0 0.7071 0.707113 0 0.7071 -0.694755 -0.186156 0.694738 -0.694748 -0.186162 0.694744 -0.563387 -0.432314 0.704059 -0.480537 -0.480537 0.733599 -0.432314 -0.563387 0.704059 -0.186159 -0.694749 0.694743 -0.186171 -0.694753 0.694736 0.186161 -0.694755 0.694737 0.186168 -0.694746 0.694744 0.508592 -0.508594 0.694742 0.508593 -0.508593 0.694743 0.694752 -0.186158 0.694741 0.694753 -0.186159 0.69474 0 -0.707116 0.707098 0 -0.707116 0.707098 0 0.707107 0.707107 0 0.707107 0.707107 -0.186159 0.694746 0.694746 -0.186155 0.694752 0.694742 -0.508592 0.508594 0.694742 -0.508593 0.508591 0.694744 -0.694751 0.186157 0.694742 -0.694752 0.186159 0.694741 0.700221 0.139283 0.700208 0.70022 0.139284 0.700208 0.593617 0.396645 0.700208 0.593613 0.396647 0.700211 0.396644 0.593616 0.70021 0.396655 0.593615 0.700204 0.139287 0.700222 0.700206 0.139268 0.700216 0.700216 -0.707112 0 0.707101 -0.707112 0 0.707101 0.707113 0 0.7071 0.707113 0 0.7071 -0.70022 -0.139283 0.700209 -0.700221 -0.139281 0.700208 -0.593617 -0.396645 0.700208 -0.593626 -0.396641 0.700203 -0.396649 -0.593622 0.700202 -0.396639 -0.593623 0.700207 -0.139287 -0.700222 0.700206 -0.139289 -0.700222 0.700205 0.186162 -0.694755 0.694737 0.186168 -0.694747 0.694743 0.508592 -0.508595 0.694741 0.508593 -0.508593 0.694743 0.694752 -0.186158 0.694741 0.694753 -0.186159 0.69474 0 -0.707116 0.707098 0 -0.707116 0.707098 0 0.707107 0.707107 0 0.707107 0.707107 -0.186159 0.694746 0.694746 -0.186154 0.694753 0.694741 -0.432311 0.563393 0.704057 -0.480537 0.480537 0.733599 -0.563394 0.43231 0.704056 -0.694753 0.186161 0.694739 -0.694751 0.186155 0.694743 0.700214 0.139285 0.700214 0.700227 0.13927 0.700205 0.593617 0.396649 0.700206 0.593607 0.396654 0.700211 0.396646 0.593613 0.700211 0.396657 0.593612 0.700205 0.139286 0.700222 0.700206 0.139268 0.700216 0.700216 -0.707111 0 0.707102 -0.707111 0 0.707102 0.707107 0 0.707107 0.707107 0 0.707107 -0.69475 -0.18616 0.694742 -0.694755 -0.186156 0.694738 -0.508594 -0.508594 0.694741 -0.508594 -0.508594 0.694741 -0.18616 -0.69475 0.694742 -0.186169 -0.694754 0.694736 0.186161 -0.694755 0.694737 0.186169 -0.694745 0.694745 0.508592 -0.508591 0.694744 0.508592 -0.508592 0.694744 0.694749 -0.186159 0.694743 0.694747 -0.186154 0.694747 0 -0.707116 0.707098 0 -0.707116 0.707098 0 0.707107 0.707107 0 0.707107 0.707107 -0.186159 0.694746 0.694746 -0.186152 0.694754 0.69474 -0.508596 0.508596 0.694738 -0.508596 0.508596 0.694738 -0.694757 0.186162 0.694735 -0.694755 0.186156 0.694738 0.694756 0.186151 0.694739 0.694751 0.186155 0.694743 0.508591 0.508592 0.694744 0.508592 0.508592 0.694744 0.186159 0.694749 0.694743 0.186154 0.694747 0.694747 -0.707116 0 0.707098 -0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 -0.694755 -0.186161 0.694737 -0.694759 -0.186157 0.694734 -0.508596 -0.508596 0.694738 -0.508596 -0.508596 0.694738 -0.18616 -0.694751 0.694741 -0.186167 -0.694754 0.694737 0.186161 -0.694755 0.694737 0.186169 -0.694745 0.694745 0.508592 -0.508591 0.694744 0.508592 -0.508592 0.694744 0.694753 -0.18615 0.694742 0.694755 -0.186156 0.694738 0 -0.707116 0.707098 0 -0.707116 0.707098 0 0.707107 0.707107 0 0.707107 0.707107 -0.186161 0.694746 0.694746 -0.186156 0.694753 0.69474 -0.50859 0.5086 0.694739 -0.508593 0.508579 0.694752 -0.694741 0.186157 0.694752 -0.694745 0.186168 0.694745 0.700213 0.139298 0.700213 0.700221 0.139289 0.700207 0.593622 0.396639 0.700207 0.593618 0.396641 0.70021 0.396641 0.593618 0.70021 0.39666 0.593617 0.7002 0.139289 0.700223 0.700205 0.139268 0.700216 0.700216 -0.707107 0 0.707107 -0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 -0.700213 -0.139298 0.700213 -0.700221 -0.139289 0.700207 -0.593622 -0.396639 0.700207 -0.593629 -0.396635 0.700204 -0.396645 -0.593624 0.700202 -0.396645 -0.593624 0.700202 -0.139289 -0.700223 0.700205 -0.139289 -0.700222 0.700205 0.186164 -0.694754 0.694737 0.186169 -0.694748 0.694742 0.50859 -0.5086 0.694739 0.508593 -0.508579 0.694752 0.694741 -0.186157 0.694752 0.694745 -0.186168 0.694745 0 -0.707116 0.707098 0 -0.707116 0.707098 0 1 0 0 1 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.195092 -0.980785 0 -0.195092 -0.980785 0 -0.555586 -0.831459 0 -0.555586 -0.831459 0 -0.831456 -0.55559 0 -0.831456 -0.55559 0 -0.980788 -0.195077 0 -0.980788 -0.195077 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.707114 -0.7071 0 0.707114 -0.7071 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.707114 0.7071 0 -0.707114 0.7071 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.195092 0.980785 0 0.195092 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831474 0.555564 0 0.831474 0.555564 0 0.980788 0.195077 0 0.980788 0.195077 0 -0.195095 -0.980784 0 -0.195095 -0.980784 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.831474 -0.555564 0 -0.831474 -0.555564 0 -0.980784 -0.195095 0 -0.980784 -0.195095 0 0.965929 -0.258808 0 0.965929 -0.258808 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965929 0.258808 0 0.965929 0.258808 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0 0.965927 -0.258815 0 0.965927 -0.258815 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965927 0.258815 0 0.965927 0.258815 0 -0.195095 -0.980784 0 -0.195095 -0.980784 0 -0.555577 -0.831465 0 -0.555577 -0.831465 0 -0.831465 -0.555577 0 -0.831465 -0.555577 0 -0.980786 -0.195086 0 -0.980786 -0.195086 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.195095 0.980784 0 0.195095 0.980784 0 0.555575 0.831467 0 0.555575 0.831467 0 0.831467 0.555574 0 0.831467 0.555574 0 0.980785 0.195091 0 0.980785 0.195091 0 -0.965926 0.258818 0 -0.965926 0.258818 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.195096 -0.980784 0 -0.195096 -0.980784 0 -0.555574 -0.831467 0 -0.555574 -0.831467 0 -0.831467 -0.555574 0 -0.831467 -0.555574 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.258823 -0.965925 0 0.258823 -0.965925 0 0.195096 0.980784 0 0.258793 0.965816 -0.015009 0.555544 0.831426 0.0100433 0.608766 0.79335 0 0.831467 0.555574 0 0.793259 0.608699 0.0150104 0.980591 0.195052 -0.0199106 0.965926 0.258818 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.195095 0.980784 0 0.195095 0.980784 0 0.555577 0.831465 0 0.555577 0.831465 0 0.831465 0.555577 0 0.831465 0.555577 0 0.980784 0.195095 0 0.980784 0.195095 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 0.965929 -0.258808 0 0.965929 -0.258808 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965929 0.258808 0 0.965929 0.258808 0 -0.195099 -0.980784 0 -0.195099 -0.980784 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.831474 -0.555564 0 -0.831474 -0.555564 0 -0.980781 -0.195114 0 -0.980781 -0.195114 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.7071 -0.707114 0 0.7071 -0.707114 0 0.258825 -0.965924 0 0.258825 -0.965924 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.7071 0.707114 0 -0.7071 0.707114 0 -0.258825 0.965924 0 -0.258825 0.965924 0 0.195099 0.980784 0 0.195099 0.980784 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831474 0.555564 0 0.831474 0.555564 0 0.980781 0.195114 0 0.980781 0.195114 0 0 0.707107 -0.707107 0 0.707107 -0.707107 -0.694746 0.186159 -0.694746 -0.694765 0.186144 -0.694732 -0.5086 0.50859 -0.694739 -0.508579 0.508594 -0.694752 -0.186156 0.694748 -0.694746 -0.186154 0.694747 -0.694747 0.139282 0.700214 -0.700214 0.13927 0.700225 -0.700206 0.396639 0.593616 -0.700212 0.396637 0.593621 -0.700209 0.593621 0.396638 -0.700209 0.59362 0.396643 -0.700207 0.700226 0.139273 -0.700205 0.700231 0.139291 -0.700196 -0.707107 0 -0.707107 -0.707107 0 -0.707107 0.707124 0 -0.707089 0.707124 0 -0.707089 -0.139284 -0.700223 -0.700206 -0.139288 -0.700219 -0.700208 -0.396653 -0.593609 -0.700211 -0.396645 -0.593624 -0.700202 -0.59361 -0.396658 -0.700207 -0.593613 -0.396625 -0.700223 -0.700209 -0.13927 -0.700223 -0.700214 -0.139287 -0.700214 0.694763 -0.186163 -0.694728 0.694754 -0.186171 -0.694736 0.5086 -0.50859 -0.694739 0.508604 -0.50859 -0.694736 0.186158 -0.694752 -0.694741 0.186163 -0.694754 -0.694737 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707107 -0.707107 0 0.707107 -0.707107 -0.694755 0.186161 -0.694737 -0.694759 0.186157 -0.694734 -0.508596 0.508596 -0.694738 -0.508596 0.508596 -0.694738 -0.18616 0.694751 -0.694741 -0.18615 0.694748 -0.694747 0.186159 0.694746 -0.694746 0.186155 0.694751 -0.694743 0.508592 0.508591 -0.694744 0.508592 0.508592 -0.694744 0.694753 0.18615 -0.694742 0.694755 0.186156 -0.694738 -0.707116 0 -0.707098 -0.707116 0 -0.707098 0.707116 0 -0.707098 0.707116 0 -0.707098 -0.139287 -0.700223 -0.700205 -0.139289 -0.700221 -0.700207 -0.396642 -0.59362 -0.700207 -0.396637 -0.593631 -0.700201 -0.593625 -0.39664 -0.700204 -0.593625 -0.396633 -0.700208 -0.700222 -0.139286 -0.700206 -0.700222 -0.139289 -0.700205 0.694756 -0.186151 -0.694739 0.694751 -0.186155 -0.694743 0.508591 -0.508592 -0.694744 0.508592 -0.508592 -0.694744 0.186159 -0.694749 -0.694743 0.186171 -0.694753 -0.694736 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707107 -0.707107 0 0.707107 -0.707107 -0.694756 0.186151 -0.694739 -0.694751 0.186155 -0.694743 -0.508591 0.508592 -0.694744 -0.508592 0.508592 -0.694744 -0.186159 0.694749 -0.694743 -0.186154 0.694747 -0.694747 0.186159 0.694746 -0.694746 0.186155 0.694751 -0.694743 0.508592 0.508591 -0.694744 0.508592 0.508592 -0.694744 0.694751 0.186155 -0.694743 0.694754 0.186164 -0.694737 -0.707116 0 -0.707098 -0.707116 0 -0.707098 0.707116 0 -0.707098 0.707116 0 -0.707098 -0.186161 -0.694755 -0.694737 -0.186169 -0.694745 -0.694745 -0.508592 -0.508591 -0.694744 -0.508592 -0.508592 -0.694744 -0.694753 -0.18615 -0.694742 -0.694755 -0.186156 -0.694738 0.694755 -0.186156 -0.694738 0.694748 -0.186162 -0.694744 0.508591 -0.508592 -0.694744 0.508592 -0.508592 -0.694744 0.186159 -0.694749 -0.694743 0.186171 -0.694753 -0.694736 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707107 -0.707107 0 0.707107 -0.707107 -0.694755 0.186156 -0.694738 -0.694748 0.186162 -0.694744 -0.508591 0.508592 -0.694744 -0.508592 0.508592 -0.694744 -0.186159 0.694749 -0.694743 -0.186154 0.694747 -0.694747 0.139285 0.700214 -0.700214 0.13927 0.700227 -0.700204 0.396647 0.593618 -0.700206 0.396652 0.59361 -0.700211 0.593616 0.396645 -0.700209 0.593616 0.396647 -0.700208 0.700221 0.139283 -0.700208 0.700221 0.139284 -0.700208 -0.707116 0 -0.707098 -0.707116 0 -0.707098 0.707113 0 -0.7071 0.707113 0 -0.7071 -0.139287 -0.700223 -0.700205 -0.139289 -0.700221 -0.700207 -0.396649 -0.593617 -0.700206 -0.396642 -0.593629 -0.700199 -0.59362 -0.396651 -0.700202 -0.593622 -0.396631 -0.700212 -0.700219 -0.139279 -0.70021 -0.700222 -0.139289 -0.700205 0.694753 -0.186158 -0.69474 0.694751 -0.186159 -0.694741 0.508592 -0.508593 -0.694742 0.508593 -0.508593 -0.694742 0.18616 -0.69475 -0.694743 0.18617 -0.694753 -0.694736 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707107 -0.707107 0 0.707107 -0.707107 -0.694752 0.186158 -0.694741 -0.69475 0.186159 -0.694742 -0.508591 0.508593 -0.694743 -0.508594 0.508592 -0.694742 -0.18616 0.69475 -0.694743 -0.186153 0.694747 -0.694747 0.186159 0.694746 -0.694746 0.186155 0.694752 -0.694742 0.432311 0.563393 -0.704057 0.480537 0.480537 -0.733599 0.563391 0.432312 -0.704058 0.694752 0.186158 -0.694741 0.694753 0.186159 -0.69474 -0.707112 0 -0.707101 -0.707112 0 -0.707101 0.707113 0 -0.7071 0.707113 0 -0.7071 -0.139287 -0.700223 -0.700205 -0.139289 -0.700221 -0.700206 -0.396647 -0.593619 -0.700206 -0.396642 -0.593627 -0.700201 -0.59362 -0.396648 -0.700204 -0.593621 -0.396637 -0.700209 -0.700221 -0.139283 -0.700208 -0.70022 -0.139281 -0.700209 0.694753 -0.186158 -0.69474 0.694751 -0.186159 -0.694741 0.508591 -0.508594 -0.694742 0.508594 -0.508594 -0.694741 0.18616 -0.69475 -0.694742 0.18617 -0.694753 -0.694736 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707107 -0.707107 0 0.707107 -0.707107 -0.69475 0.18616 -0.694742 -0.694755 0.186156 -0.694738 -0.508594 0.508594 -0.694741 -0.508594 0.508594 -0.694741 -0.18616 0.69475 -0.694742 -0.186152 0.694747 -0.694747 0.139285 0.700214 -0.700214 0.13927 0.700227 -0.700205 0.396649 0.593617 -0.700206 0.396654 0.593607 -0.700211 0.593613 0.396646 -0.700211 0.593612 0.396657 -0.700205 0.700222 0.139286 -0.700206 0.700216 0.139268 -0.700216 -0.707111 0 -0.707102 -0.707111 0 -0.707102 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186161 -0.694755 -0.694737 -0.186167 -0.694747 -0.694743 -0.508594 -0.508594 -0.694741 -0.508594 -0.508594 -0.694741 -0.694753 -0.186161 -0.694739 -0.694751 -0.186155 -0.694743 0.694746 -0.186159 -0.694746 0.694751 -0.186155 -0.694743 0.508591 -0.508592 -0.694744 0.508592 -0.508592 -0.694744 0.186159 -0.694749 -0.694743 0.186171 -0.694753 -0.694736 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707107 -0.707107 0 0.707107 -0.707107 -0.694755 0.186161 -0.694737 -0.694759 0.186157 -0.694734 -0.508596 0.508596 -0.694738 -0.508596 0.508596 -0.694738 -0.18616 0.694751 -0.694741 -0.18615 0.694748 -0.694747 0.186159 0.694746 -0.694746 0.186155 0.694751 -0.694743 0.508592 0.508591 -0.694744 0.508592 0.508592 -0.694744 0.694753 0.18615 -0.694742 0.694755 0.186156 -0.694738 -0.707116 0 -0.707098 -0.707116 0 -0.707098 0.707116 0 -0.707098 0.707116 0 -0.707098 -0.186161 -0.694755 -0.694737 -0.186166 -0.694749 -0.694742 -0.508596 -0.508596 -0.694738 -0.508596 -0.508596 -0.694738 -0.694757 -0.186162 -0.694735 -0.694755 -0.186156 -0.694738 0.694756 -0.186151 -0.694739 0.694751 -0.186155 -0.694743 0.508591 -0.508592 -0.694744 0.508592 -0.508592 -0.694744 0.186159 -0.694749 -0.694743 0.186171 -0.694753 -0.694736 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707107 -0.707107 0 0.707107 -0.707107 -0.694746 0.186159 -0.694746 -0.694737 0.186166 -0.694754 -0.508582 0.508593 -0.69475 -0.508604 0.50859 -0.694736 -0.186163 0.69475 -0.694741 -0.186154 0.694747 -0.694747 0.139288 0.700214 -0.700214 0.139271 0.700228 -0.700203 0.396645 0.593625 -0.700202 0.396654 0.593607 -0.700211 0.593621 0.396638 -0.700209 0.59362 0.396643 -0.700207 0.700218 0.139299 -0.700208 0.700214 0.139287 -0.700214 -0.707107 0 -0.707107 -0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.139289 -0.700222 -0.700205 -0.139289 -0.700223 -0.700205 -0.396645 -0.593625 -0.700202 -0.396645 -0.593624 -0.700202 -0.593625 -0.39664 -0.700204 -0.593625 -0.396633 -0.700208 -0.700218 -0.139299 -0.700208 -0.700214 -0.139287 -0.700214 0.694746 -0.186159 -0.694746 0.694737 -0.186166 -0.694754 0.508582 -0.508593 -0.69475 0.508604 -0.50859 -0.694736 0.186163 -0.69475 -0.694741 0.186171 -0.694753 -0.694736 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0.258819 0.965926 0 0.258819 0.965926 0 0.707108 0.707106 0 0.707108 0.707106 0 0.965925 0.258821 0 0.965925 0.258821 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707108 0.707106 0 0.707108 0.707106 0 0.965925 0.258821 0 0.965925 0.258821 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707114 0.7071 0 -0.707114 0.7071 0 -0.965925 0.258822 0 -0.965925 0.258822 0 0.965925 0.258822 0 0.965925 0.258822 0 0.707114 0.7071 0 0.707114 0.7071 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.707114 -0.7071 0 -0.707114 -0.7071 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707114 -0.7071 0 0.707114 -0.7071 0 0.965925 -0.258822 0 0.965925 -0.258822 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965925 0.258822 0 -0.965925 0.258822 0 0.965929 0.258808 0 0.965929 0.258808 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258822 0.965925 0 0.258822 0.965925 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965929 -0.258808 0 0.965929 -0.258808 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965929 0.258808 0 -0.965929 0.258808 0 0.965927 0.258815 0 0.965927 0.258815 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258822 0.965925 0 0.258822 0.965925 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965927 -0.258815 0 0.965927 -0.258815 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258815 0 -0.965927 0.258815 0 0.980785 0.195091 0 0.980785 0.195091 0 0.831467 0.555574 0 0.831467 0.555574 0 0.555575 0.831467 0 0.555575 0.831467 0 0.195095 0.980784 0 0.195095 0.980784 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.258818 0 0.965926 -0.258818 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -0.831473 -0.555565 0 -0.831473 -0.555565 0 -0.55556 -0.831476 0 -0.55556 -0.831476 0 -0.195096 -0.980784 0 -0.195096 -0.980784 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258818 0 -0.965926 0.258818 0 0.980785 0.195091 0 0.980785 0.195091 0 0.831467 0.555574 0 0.831467 0.555574 0 0.555572 0.831468 0 0.555572 0.831468 0 0.195096 0.980784 0 0.195096 0.980784 0 0.258823 -0.965925 0 0.258823 -0.965925 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.965926 -0.258818 0 0.965926 -0.258818 0 -0.980784 -0.195095 0 -0.980784 -0.195095 0 -0.831476 -0.555561 0 -0.831476 -0.555561 0 -0.555559 -0.831477 0 -0.555559 -0.831477 0 -0.195095 -0.980784 0 -0.195095 -0.980784 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965925 0.258822 0 -0.965925 0.258822 0 0.965925 0.258822 0 0.965925 0.258822 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258822 0.965925 0 0.258822 0.965925 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965925 -0.258822 0 0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965925 0.258822 0 -0.965925 0.258822 0 0.965929 0.258808 0 0.965929 0.258808 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258822 0.965925 0 0.258822 0.965925 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965929 -0.258808 0 0.965929 -0.258808 0 -0.258825 0.965924 0 -0.258825 0.965924 0 -0.7071 0.707114 0 -0.7071 0.707114 0 -0.965925 0.258822 0 -0.965925 0.258822 0 0.965925 0.258822 0 0.965925 0.258822 0 0.7071 0.707114 0 0.7071 0.707114 0 0.258825 0.965924 0 0.258825 0.965924 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.7071 -0.707114 0 -0.7071 -0.707114 0 -0.258825 -0.965924 0 -0.258825 -0.965924 0 0.258825 -0.965924 0 0.258825 -0.965924 0 0.7071 -0.707114 0 0.7071 -0.707114 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0 -0.707116 0.707098 0 -0.707116 0.707098 -0.694746 -0.186159 0.694746 -0.694765 -0.186144 0.694732 -0.5086 -0.50859 0.694739 -0.508579 -0.508594 0.694752 -0.186156 -0.694748 0.694746 -0.186171 -0.694753 0.694736 0.186158 -0.694755 0.694738 0.186162 -0.69475 0.694741 0.508602 -0.508591 0.694737 0.508602 -0.508588 0.694739 0.694757 -0.186162 0.694735 0.694762 -0.186173 0.694727 -0.707107 0 0.707107 -0.707107 0 0.707107 0.707124 0 0.707089 0.707124 0 0.707089 -0.186156 0.694747 0.694747 -0.186155 0.694749 0.694745 -0.508593 0.508583 0.69475 -0.50859 0.508604 0.694736 -0.694757 0.186162 0.694735 -0.694749 0.18614 0.694749 0.694763 0.186163 0.694728 0.694754 0.186171 0.694736 0.5086 0.50859 0.694739 0.508604 0.50859 0.694736 0.186158 0.694752 0.694741 0.186147 0.694748 0.694748 0 0.707107 0.707107 0 0.707107 0.707107 0 -0.707116 0.707098 0 -0.707116 0.707098 -0.694755 -0.186161 0.694737 -0.694759 -0.186157 0.694734 -0.508596 -0.508596 0.694738 -0.508596 -0.508596 0.694738 -0.18616 -0.694751 0.694741 -0.186167 -0.694754 0.694737 0.186161 -0.694755 0.694737 0.186169 -0.694745 0.694745 0.508592 -0.508591 0.694744 0.508592 -0.508592 0.694744 0.694753 -0.18615 0.694742 0.694755 -0.186156 0.694738 -0.707116 0 0.707098 -0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 -0.186159 0.694746 0.694746 -0.186152 0.694754 0.69474 -0.508596 0.508596 0.694738 -0.508596 0.508596 0.694738 -0.694757 0.186162 0.694735 -0.694755 0.186156 0.694738 0.694756 0.186151 0.694739 0.694751 0.186155 0.694743 0.508591 0.508592 0.694744 0.508592 0.508592 0.694744 0.186159 0.694749 0.694743 0.186154 0.694747 0.694747 0 0.707107 0.707107 0 0.707107 0.707107 0 -0.707116 0.707098 0 -0.707116 0.707098 -0.694756 -0.186151 0.694739 -0.694751 -0.186155 0.694743 -0.508591 -0.508592 0.694744 -0.508592 -0.508592 0.694744 -0.186159 -0.694749 0.694743 -0.186171 -0.694753 0.694736 0.186161 -0.694755 0.694737 0.186169 -0.694745 0.694745 0.508592 -0.508591 0.694744 0.508592 -0.508592 0.694744 0.694751 -0.186155 0.694743 0.694754 -0.186164 0.694737 -0.707116 0 0.707098 -0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 -0.186159 0.694746 0.694746 -0.186155 0.694751 0.694743 -0.508592 0.508591 0.694744 -0.508592 0.508592 0.694744 -0.694753 0.18615 0.694742 -0.694755 0.186156 0.694738 0.694755 0.186156 0.694738 0.694748 0.186162 0.694744 0.508591 0.508592 0.694744 0.508592 0.508592 0.694744 0.186159 0.694749 0.694743 0.186154 0.694747 0.694747 0 0.707107 0.707107 0 0.707107 0.707107 0 -0.707116 0.707098 0 -0.707116 0.707098 -0.694755 -0.186156 0.694738 -0.694748 -0.186162 0.694744 -0.508591 -0.508592 0.694744 -0.508592 -0.508592 0.694744 -0.186159 -0.694749 0.694743 -0.186171 -0.694753 0.694736 0.186161 -0.694755 0.694737 0.186168 -0.694746 0.694744 0.508592 -0.508594 0.694742 0.508593 -0.508593 0.694743 0.694752 -0.186158 0.694741 0.694753 -0.186159 0.69474 -0.707116 0 0.707098 -0.707116 0 0.707098 0.707113 0 0.7071 0.707113 0 0.7071 -0.186159 0.694746 0.694746 -0.186155 0.694751 0.694743 -0.508592 0.508591 0.694744 -0.508592 0.508592 0.694744 -0.694751 0.186155 0.694743 -0.694754 0.186164 0.694737 0.700221 0.139283 0.700208 0.70022 0.139284 0.700208 0.593617 0.396645 0.700208 0.593615 0.396646 0.700209 0.396645 0.593615 0.70021 0.396655 0.593614 0.700205 0.139286 0.700222 0.700206 0.139268 0.700216 0.700216 0 0.707107 0.707107 0 0.707107 0.707107 0 -0.707116 0.707098 0 -0.707116 0.707098 -0.70022 -0.139283 0.700209 -0.700221 -0.139281 0.700208 -0.59362 -0.396639 0.700209 -0.593622 -0.396638 0.700208 -0.396636 -0.593623 0.700209 -0.396639 -0.593623 0.700207 -0.139287 -0.700222 0.700206 -0.139289 -0.700222 0.700205 0.186162 -0.694755 0.694737 0.186168 -0.694747 0.694743 0.508592 -0.508595 0.694741 0.508593 -0.508593 0.694743 0.694752 -0.186158 0.694741 0.694753 -0.186159 0.69474 -0.707112 0 0.707101 -0.707112 0 0.707101 0.707113 0 0.7071 0.707113 0 0.7071 -0.186159 0.694746 0.694746 -0.186155 0.694752 0.694742 -0.508592 0.508594 0.694742 -0.508593 0.508591 0.694744 -0.694751 0.186157 0.694742 -0.694752 0.186159 0.694741 0.700221 0.139283 0.700208 0.70022 0.139284 0.700208 0.593617 0.396645 0.700208 0.593613 0.396647 0.700211 0.396644 0.593616 0.70021 0.396655 0.593615 0.700204 0.139287 0.700222 0.700206 0.139268 0.700216 0.700216 0 0.707107 0.707107 0 0.707107 0.707107 0 -0.707116 0.707098 0 -0.707116 0.707098 -0.700218 -0.139286 0.70021 -0.700224 -0.139279 0.700206 -0.593623 -0.396637 0.700208 -0.59362 -0.396639 0.70021 -0.396635 -0.593623 0.700209 -0.396638 -0.593623 0.700207 -0.139286 -0.700222 0.700206 -0.139289 -0.700222 0.700205 0.186161 -0.694755 0.694737 0.186169 -0.694745 0.694745 0.508592 -0.508591 0.694744 0.508592 -0.508592 0.694744 0.694749 -0.186159 0.694743 0.694747 -0.186154 0.694747 -0.707111 0 0.707102 -0.707111 0 0.707102 0.707107 0 0.707107 0.707107 0 0.707107 -0.186159 0.694746 0.694746 -0.186154 0.694753 0.694741 -0.508594 0.508594 0.694741 -0.508594 0.508594 0.694741 -0.694753 0.186161 0.694739 -0.694751 0.186155 0.694743 0.694746 0.186159 0.694746 0.694751 0.186155 0.694743 0.508591 0.508592 0.694744 0.508592 0.508592 0.694744 0.186159 0.694749 0.694743 0.186154 0.694747 0.694747 0 0.707107 0.707107 0 0.707107 0.707107 0 -0.707116 0.707098 0 -0.707116 0.707098 -0.694755 -0.186161 0.694737 -0.694759 -0.186157 0.694734 -0.508596 -0.508596 0.694738 -0.508596 -0.508596 0.694738 -0.18616 -0.694751 0.694741 -0.186167 -0.694754 0.694737 0.186161 -0.694755 0.694737 0.186169 -0.694745 0.694745 0.508592 -0.508591 0.694744 0.508592 -0.508592 0.694744 0.694753 -0.18615 0.694742 0.694755 -0.186156 0.694738 -0.707116 0 0.707098 -0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 -0.186159 0.694746 0.694746 -0.186152 0.694754 0.69474 -0.508596 0.508596 0.694738 -0.508596 0.508596 0.694738 -0.694757 0.186162 0.694735 -0.694755 0.186156 0.694738 0.694756 0.186151 0.694739 0.694751 0.186155 0.694743 0.508591 0.508592 0.694744 0.508592 0.508592 0.694744 0.186159 0.694749 0.694743 0.186154 0.694747 0.694747 0 0.707107 0.707107 0 0.707107 0.707107 0 -0.707116 0.707098 0 -0.707116 0.707098 -0.694746 -0.186159 0.694746 -0.694737 -0.186166 0.694754 -0.508582 -0.508593 0.69475 -0.508604 -0.50859 0.694736 -0.186163 -0.69475 0.694741 -0.186171 -0.694753 0.694736 0.186164 -0.694754 0.694737 0.186169 -0.694748 0.694742 0.50859 -0.5086 0.694739 0.508593 -0.508579 0.694752 0.694741 -0.186157 0.694752 0.694745 -0.186168 0.694745 -0.707107 0 0.707107 -0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 -0.186161 0.694746 0.694746 -0.186156 0.694753 0.69474 -0.50859 0.5086 0.694739 -0.508593 0.508579 0.694752 -0.694741 0.186157 0.694752 -0.694745 0.186168 0.694745 0.694746 0.186159 0.694746 0.694737 0.186166 0.694754 0.508582 0.508593 0.69475 0.508604 0.50859 0.694736 0.186163 0.69475 0.694741 0.186154 0.694747 0.694747 0 0.707107 0.707107 0 0.707107 0.707107 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.707114 0.7071 0 -0.707114 0.7071 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707114 0.7071 0 0.707114 0.7071 0 0.965925 0.258822 0 0.965925 0.258822 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707114 -0.7071 0 -0.707114 -0.7071 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.707114 -0.7071 0 0.707114 -0.7071 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965929 0.258808 0 0.965929 0.258808 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 0.965929 -0.258808 0 0.965929 -0.258808 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.965929 0.258808 0 -0.965929 0.258808 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965927 0.258815 0 0.965927 0.258815 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965929 -0.258808 0 -0.965929 -0.258808 0 0.980786 -0.195086 0 0.965818 -0.258786 -0.0150096 0.831429 -0.55554 0.0100429 0.793356 -0.608759 0 0.555564 -0.831474 0 0.608686 -0.793269 0.0150091 0.195056 -0.98059 -0.0199102 0.258822 -0.965925 0 -0.965927 0.258815 0 -0.965927 0.258815 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.195095 0.980784 0 0.258793 0.965816 -0.0150092 0.555547 0.831425 0.0100432 0.608767 0.793349 0 0.831467 0.555574 0 0.793259 0.608699 0.0150104 0.980591 0.195052 -0.0199106 0.965926 0.258818 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965927 -0.258815 0 -0.965927 -0.258815 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.195096 -0.980784 0 -0.195096 -0.980784 0 -0.55556 -0.831476 0 -0.55556 -0.831476 0 -0.831473 -0.555565 0 -0.831473 -0.555565 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -0.965926 0.258818 0 -0.965926 0.258818 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258823 0.965925 0 0.258823 0.965925 0 0.707105 0.707109 0 0.707105 0.707109 0 0.965926 0.258818 0 0.965926 0.258818 0 0.980785 -0.195091 0 0.980785 -0.195091 0 0.831473 -0.555565 0 0.831473 -0.555565 0 0.555559 -0.831477 0 0.555559 -0.831477 0 0.195096 -0.980784 0 0.195096 -0.980784 0 -0.195095 -0.980784 0 -0.195095 -0.980784 0 -0.555559 -0.831477 0 -0.555559 -0.831477 0 -0.831476 -0.555561 0 -0.831476 -0.555561 0 -0.980784 -0.195095 0 -0.980784 -0.195095 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965925 0.258822 0 0.965925 0.258822 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.980784 0.195095 0 -0.980784 0.195095 0 -0.831474 0.555564 0 -0.831474 0.555564 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195095 0.980784 0 -0.195095 0.980784 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965929 0.258808 0 0.965929 0.258808 0 0.965929 -0.258808 0 0.965929 -0.258808 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.7071 0.707114 0 -0.7071 0.707114 0 -0.258825 0.965924 0 -0.258825 0.965924 0 0.258825 0.965924 0 0.258825 0.965924 0 0.7071 0.707114 0 0.7071 0.707114 0 0.965925 0.258822 0 0.965925 0.258822 0 -0.258825 -0.965924 0 -0.258825 -0.965924 0 -0.7071 -0.707114 0 -0.7071 -0.707114 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 0.980781 -0.195114 0 0.980781 -0.195114 0 0.83148 -0.555555 0 0.83148 -0.555555 0 0.555555 -0.83148 0 0.555555 -0.83148 0 0.195099 -0.980784 0 0.195099 -0.980784 0 0 -0.707116 -0.707098 0 -0.707116 -0.707098 -0.186158 -0.694755 -0.694738 -0.186168 -0.694743 -0.694747 -0.508593 -0.508583 -0.69475 -0.50859 -0.508604 -0.694736 -0.694757 -0.186162 -0.694735 -0.694749 -0.18614 -0.694749 0.694763 -0.186163 -0.694728 0.694754 -0.186171 -0.694736 0.5086 -0.50859 -0.694739 0.508604 -0.50859 -0.694736 0.186158 -0.694752 -0.694741 0.186163 -0.694754 -0.694737 -0.707107 0 -0.707107 -0.707107 0 -0.707107 0.707124 0 -0.707089 0.707124 0 -0.707089 -0.694746 0.186159 -0.694746 -0.694765 0.186144 -0.694732 -0.5086 0.50859 -0.694739 -0.508579 0.508594 -0.694752 -0.186156 0.694748 -0.694746 -0.186154 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186149 0.694756 -0.694739 0.508602 0.508591 -0.694737 0.508602 0.508588 -0.694739 0.694757 0.186162 -0.694735 0.694762 0.186173 -0.694727 0 0.707107 -0.707107 0 0.707107 -0.707107 0 -0.707116 -0.707098 0 -0.707116 -0.707098 -0.186161 -0.694755 -0.694737 -0.186166 -0.694749 -0.694742 -0.508596 -0.508596 -0.694738 -0.508596 -0.508596 -0.694738 -0.694757 -0.186162 -0.694735 -0.694755 -0.186156 -0.694738 0.694756 -0.186151 -0.694739 0.694751 -0.186155 -0.694743 0.508591 -0.508592 -0.694744 0.508592 -0.508592 -0.694744 0.186159 -0.694749 -0.694743 0.186171 -0.694753 -0.694736 -0.707116 0 -0.707098 -0.707116 0 -0.707098 0.707116 0 -0.707098 0.707116 0 -0.707098 -0.694755 0.186161 -0.694737 -0.694759 0.186157 -0.694734 -0.508596 0.508596 -0.694738 -0.508596 0.508596 -0.694738 -0.18616 0.694751 -0.694741 -0.18615 0.694748 -0.694747 0.186159 0.694746 -0.694746 0.186155 0.694751 -0.694743 0.508592 0.508591 -0.694744 0.508592 0.508592 -0.694744 0.694753 0.18615 -0.694742 0.694755 0.186156 -0.694738 0 0.707107 -0.707107 0 0.707107 -0.707107 0 -0.707116 -0.707098 0 -0.707116 -0.707098 -0.186161 -0.694755 -0.694737 -0.186169 -0.694745 -0.694745 -0.508592 -0.508591 -0.694744 -0.508592 -0.508592 -0.694744 -0.694753 -0.18615 -0.694742 -0.694755 -0.186156 -0.694738 0.694755 -0.186156 -0.694738 0.694748 -0.186162 -0.694744 0.563394 -0.432304 -0.70406 0.480533 -0.480533 -0.733605 0.432301 -0.563396 -0.70406 0.186159 -0.694749 -0.694743 0.186171 -0.694753 -0.694736 -0.707116 0 -0.707098 -0.707116 0 -0.707098 0.707116 0 -0.707098 0.707116 0 -0.707098 -0.694756 0.186151 -0.694739 -0.694751 0.186155 -0.694743 -0.508591 0.508592 -0.694744 -0.508592 0.508592 -0.694744 -0.186159 0.694749 -0.694743 -0.186154 0.694747 -0.694747 0.186159 0.694746 -0.694746 0.186155 0.694751 -0.694743 0.508592 0.508591 -0.694744 0.508592 0.508592 -0.694744 0.694751 0.186155 -0.694743 0.694754 0.186164 -0.694737 0 0.707107 -0.707107 0 0.707107 -0.707107 0 -0.707116 -0.707098 0 -0.707116 -0.707098 -0.186161 -0.694755 -0.694737 -0.186169 -0.694745 -0.694745 -0.508592 -0.508591 -0.694744 -0.508592 -0.508592 -0.694744 -0.694751 -0.186155 -0.694743 -0.694754 -0.186164 -0.694737 0.694753 -0.186158 -0.69474 0.694751 -0.186159 -0.694741 0.508592 -0.508593 -0.694742 0.508593 -0.508593 -0.694742 0.18616 -0.69475 -0.694743 0.18617 -0.694753 -0.694736 -0.707116 0 -0.707098 -0.707116 0 -0.707098 0.707113 0 -0.7071 0.707113 0 -0.7071 -0.694755 0.186156 -0.694738 -0.694748 0.186162 -0.694744 -0.508591 0.508592 -0.694744 -0.508592 0.508592 -0.694744 -0.186159 0.694749 -0.694743 -0.186154 0.694747 -0.694747 0.186159 0.694746 -0.694746 0.186155 0.694752 -0.694742 0.432312 0.563391 -0.704058 0.480537 0.480537 -0.733599 0.563391 0.432312 -0.704058 0.694752 0.186158 -0.694741 0.694753 0.186159 -0.69474 0 0.707107 -0.707107 0 0.707107 -0.707107 0 -0.707116 -0.707098 0 -0.707116 -0.707098 -0.139287 -0.700223 -0.700205 -0.139289 -0.700221 -0.700206 -0.396637 -0.593624 -0.700207 -0.396638 -0.593621 -0.700209 -0.593621 -0.396639 -0.700209 -0.593621 -0.396637 -0.700209 -0.700221 -0.139283 -0.700208 -0.70022 -0.139281 -0.700209 0.700221 -0.139283 -0.700208 0.70022 -0.139284 -0.700208 0.59362 -0.396639 -0.700209 0.59362 -0.396639 -0.70021 0.396635 -0.593623 -0.700209 0.396641 -0.593622 -0.700206 0.139287 -0.700222 -0.700206 0.139289 -0.700222 -0.700205 -0.707112 0 -0.707101 -0.707112 0 -0.707101 0.707113 0 -0.7071 0.707113 0 -0.7071 -0.694752 0.186158 -0.694741 -0.69475 0.186159 -0.694742 -0.508591 0.508593 -0.694743 -0.508594 0.508592 -0.694742 -0.18616 0.69475 -0.694743 -0.186153 0.694747 -0.694747 0.186159 0.694746 -0.694746 0.186155 0.694752 -0.694742 0.508592 0.508595 -0.694741 0.508593 0.508593 -0.694743 0.694752 0.186158 -0.694741 0.694753 0.186159 -0.69474 0 0.707107 -0.707107 0 0.707107 -0.707107 0 -0.707116 -0.707098 0 -0.707116 -0.707098 -0.139287 -0.700223 -0.700205 -0.139289 -0.700221 -0.700207 -0.396635 -0.593624 -0.700208 -0.396637 -0.593621 -0.700209 -0.593622 -0.396636 -0.700209 -0.593621 -0.39664 -0.700207 -0.700222 -0.139286 -0.700206 -0.700219 -0.139278 -0.70021 0.694746 -0.186159 -0.694746 0.694751 -0.186155 -0.694743 0.508591 -0.508592 -0.694744 0.508592 -0.508592 -0.694744 0.186159 -0.694749 -0.694743 0.186171 -0.694753 -0.694736 -0.707111 0 -0.707102 -0.707111 0 -0.707102 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.69475 0.18616 -0.694742 -0.694755 0.186156 -0.694738 -0.508594 0.508594 -0.694741 -0.508594 0.508594 -0.694741 -0.18616 0.69475 -0.694742 -0.186152 0.694747 -0.694747 0.186159 0.694746 -0.694746 0.186155 0.694751 -0.694743 0.508592 0.508591 -0.694744 0.508592 0.508592 -0.694744 0.694749 0.186159 -0.694743 0.694747 0.186154 -0.694747 0 0.707107 -0.707107 0 0.707107 -0.707107 0 -0.707116 -0.707098 0 -0.707116 -0.707098 -0.186161 -0.694755 -0.694737 -0.186166 -0.694749 -0.694742 -0.508596 -0.508596 -0.694738 -0.508596 -0.508596 -0.694738 -0.694757 -0.186162 -0.694735 -0.694755 -0.186156 -0.694738 0.694756 -0.186151 -0.694739 0.694751 -0.186155 -0.694743 0.508591 -0.508592 -0.694744 0.508592 -0.508592 -0.694744 0.186159 -0.694749 -0.694743 0.186171 -0.694753 -0.694736 -0.707116 0 -0.707098 -0.707116 0 -0.707098 0.707116 0 -0.707098 0.707116 0 -0.707098 -0.700223 0.139287 -0.700205 -0.700221 0.139289 -0.700207 -0.593622 0.396639 -0.700207 -0.593618 0.396641 -0.70021 -0.396641 0.593618 -0.70021 -0.396647 0.593618 -0.700206 -0.139286 0.700222 -0.700206 -0.139268 0.700216 -0.700216 0.186159 0.694746 -0.694746 0.186155 0.694751 -0.694743 0.508592 0.508591 -0.694744 0.508592 0.508592 -0.694744 0.694753 0.18615 -0.694742 0.694755 0.186156 -0.694738 0 0.707107 -0.707107 0 0.707107 -0.707107 0 -0.707116 -0.707098 0 -0.707116 -0.707098 -0.186164 -0.694754 -0.694737 -0.186169 -0.694748 -0.694742 -0.50859 -0.5086 -0.694739 -0.508593 -0.508579 -0.694752 -0.694741 -0.186157 -0.694752 -0.694745 -0.186168 -0.694745 0.700213 -0.139298 -0.700213 0.700221 -0.139289 -0.700207 0.593626 -0.396632 -0.700208 0.593625 -0.396633 -0.700209 0.396632 -0.593625 -0.700209 0.396645 -0.593624 -0.700202 0.139289 -0.700223 -0.700205 0.139289 -0.700222 -0.700205 -0.707107 0 -0.707107 -0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.694746 0.186159 -0.694746 -0.694737 0.186166 -0.694754 -0.508582 0.508593 -0.69475 -0.508604 0.50859 -0.694736 -0.186163 0.69475 -0.694741 -0.186154 0.694747 -0.694747 0.186161 0.694746 -0.694746 0.186156 0.694753 -0.69474 0.50859 0.5086 -0.694739 0.508593 0.508579 -0.694752 0.694741 0.186157 -0.694752 0.694745 0.186168 -0.694745 0 0.707107 -0.707107 0 0.707107 -0.707107 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.195077 -0.980788 0.00795087 -0.152974 -0.988198 -0.00364736 -0.421651 -0.906751 0.00804847 -0.555559 -0.831438 -0.00023756 -0.630491 -0.776197 0.000187261 -0.765387 -0.643571 0.00696764 -0.831451 -0.555555 -0.000265018 -0.876286 -0.481791 0 -0.980787 -0.19508 0.0257926 -0.999279 0.027866 0.000453138 -0.98109 -0.193551 -0.0350352 -0.194957 -0.980186 -0.035035 -0.194955 -0.980186 -0.0792344 -0.440906 -0.894049 -0.103946 -0.552567 -0.826961 -0.108752 -0.605159 -0.788642 -0.141143 -0.785406 -0.602674 -0.152458 -0.821751 -0.549073 -0.159123 -0.885449 -0.436647 -0.17358 -0.965899 -0.192119 -0.17358 -0.965899 -0.19212 -0.0679202 -0.18287 -0.980788 -0.0891579 -0.242968 -0.965928 -0.153993 -0.414615 -0.896873 -0.211958 -0.570679 -0.793347 -0.244928 -0.663344 -0.707096 -0.276223 -0.74371 -0.608766 -0.312268 -0.840757 -0.442286 -0.335356 -0.905838 -0.258832 -0.341485 -0.91942 -0.195078 -0.171028 -0.951692 -0.255012 -0.171029 -0.951691 -0.255016 -0.126062 -0.701473 -0.701459 -0.126062 -0.701475 -0.701457 -0.0464601 -0.258529 -0.964886 -0.0464601 -0.258528 -0.964886 0 -0.965924 -0.258825 -0.000274373 -0.896874 -0.442286 0 -0.980784 -0.195099 0 -0.258808 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.965929 0 -0.258808 -0.965929 0 -0.707114 -0.7071 -0.000183579 -0.608772 -0.793345 0 -0.793356 -0.608759 0 -0.258808 -0.965929 0 -0.258808 -0.965929 -0.0144197 -0.44224 -0.896781 0 -0.195077 -0.980788 0.17358 -0.965895 -0.192138 0.17358 -0.965895 -0.192137 0.159123 -0.885448 -0.436647 0.159123 -0.885447 -0.43665 0.141147 -0.785419 -0.602656 0.141145 -0.785413 -0.602664 0.108752 -0.605159 -0.788642 0.108753 -0.605162 -0.788639 0.0792321 -0.440891 -0.894056 0.0792329 -0.440895 -0.894055 0.0350356 -0.194957 -0.980186 0.0350355 -0.194957 -0.980186 0.0679206 -0.182871 -0.980788 0.0679193 -0.182868 -0.980789 0.153991 -0.41461 -0.896875 0.153999 -0.414629 -0.896865 0.211958 -0.570679 -0.793347 0.211958 -0.570679 -0.793347 0.276228 -0.743722 -0.608749 0.27622 -0.743701 -0.608779 0.312268 -0.840757 -0.442286 0.312273 -0.840771 -0.442256 0.341483 -0.919417 -0.195095 0.341484 -0.919418 -0.195091 0.0993474 -0.552828 -0.827352 0.0350346 -0.194954 -0.980187 0.0350355 -0.194957 -0.980186 0.0792361 -0.440914 -0.894045 0.115268 -0.603206 -0.789212 0.173581 -0.965899 -0.192119 0.17358 -0.965897 -0.192126 0.147782 -0.822342 -0.549468 0.172648 -0.882457 -0.437565 0.141143 -0.785402 -0.60268 0.00386266 -0.98078 -0.195079 -0.000311838 -0.975104 -0.221748 0 -0.999999 -0.0015674 -0.0202813 -0.434713 -0.900341 0.00023756 -0.630491 -0.776197 -0.00043205 -0.831471 -0.555568 -0.0149842 -0.773996 -0.633014 -0.00194828 -0.863263 -0.50475 0.00991605 -0.555549 -0.831424 -0.00620851 -0.195073 -0.980769 0 -0.150099 -0.988671 0.000284716 0.793369 -0.608741 0.00438267 0.767837 -0.640631 -0.00235137 0.875265 -0.483638 0.00900287 0.965885 -0.258815 0.000272205 0.981047 -0.193769 0 0.999999 -0.0015674 0.0413191 0.344255 -0.937966 0.0178558 0.459669 -0.887911 -0.000239362 0.630507 -0.776184 -0.0240733 0.608582 -0.793126 0.0150805 0.258779 -0.965819 0 0.150095 -0.988672 -0.0464599 0.258529 -0.964886 -0.04646 0.258529 -0.964886 -0.108751 0.605148 -0.78865 -0.117074 0.703891 -0.700593 -0.141148 0.785426 -0.602646 -0.171027 0.951693 -0.255012 -0.171027 0.951693 -0.255012 -0.33631 0.905488 -0.25882 -0.336309 0.905487 -0.258823 -0.246199 0.662872 -0.707097 -0.246199 0.662872 -0.707097 -0.09011 0.242614 -0.965929 -0.09011 0.242614 -0.965929 -0.173581 0.965899 -0.192119 -0.178068 0.950319 -0.255314 -0.159124 0.885447 -0.43665 -0.141147 0.785413 -0.602664 -0.135602 0.698839 -0.702308 -0.0350357 0.194957 -0.980186 -0.0537932 0.255896 -0.965206 -0.0792361 0.440917 -0.894043 -0.10875 0.605148 -0.78865 0 0.195077 -0.980788 0 0.195077 -0.980788 0 0.195077 -0.980788 0 0.195077 -0.980788 0 0.195077 -0.980788 0 0.195077 -0.980788 0 0.195077 -0.980788 0 0.195077 -0.980788 0 0.195077 -0.980788 0 0.195077 -0.980788 0 0.442308 -0.896863 0 0.442308 -0.896863 0 0.608759 -0.793356 0 0.608759 -0.793356 0 0.793356 -0.608759 0 0.793356 -0.608759 0 0.896874 -0.442286 0 0.896874 -0.442286 0 0.980787 -0.19508 0 0.980787 -0.19508 0.173581 0.965899 -0.192119 0.178067 0.950321 -0.255309 0.159123 0.885447 -0.43665 0.141146 0.785413 -0.602664 0.135601 0.698839 -0.702308 0.108749 0.605148 -0.78865 0.0792358 0.440918 -0.894043 0.0537929 0.255897 -0.965206 0.0350355 0.194957 -0.980186 0.0901101 0.242614 -0.965929 0.0901101 0.242614 -0.965929 0.2462 0.662873 -0.707097 0.246198 0.662868 -0.707102 0.336311 0.90549 -0.258811 0.336309 0.905487 -0.258823 0.04646 0.258529 -0.964886 0.04646 0.258529 -0.964886 0.171028 0.951692 -0.255012 0.171028 0.951692 -0.255012 0.126061 0.701472 -0.70146 0.123147 0.78733 -0.604107 0.108751 0.605148 -0.78865 0 0.258808 -0.965929 -0.0251028 0.159135 -0.986938 0.00236852 0.422358 -0.906426 -0.00222927 0.608757 -0.793353 0.000239359 0.630507 -0.776184 -0.000184936 0.765363 -0.643599 -0.00294372 0.793366 -0.608738 0.00235136 0.875265 -0.483638 0 0.965924 -0.258825 -0.047588 0.997474 0.0527359 -0.0126909 0.983576 -0.180047 0 0.258808 0.965929 -0.000239362 0.630507 0.776184 0.0178558 0.459669 0.887911 -0.015512 0.608685 0.79326 0.00783623 0.328188 0.94458 0.025103 0.159135 0.986938 0.000184937 0.765363 0.643599 0.00294372 0.793366 0.608738 -0.00235137 0.875265 0.483638 0 0.965924 0.258825 0.047588 0.997474 -0.0527359 0.0126909 0.983576 0.180047 -0.171027 0.951693 0.255012 -0.171027 0.951693 0.255012 -0.126061 0.701475 0.701457 -0.123147 0.787331 0.604107 -0.108751 0.605148 0.78865 -0.04646 0.258529 0.964886 -0.04646 0.258529 0.964886 -0.341483 0.919418 0.195091 -0.337261 0.905133 0.258823 -0.312268 0.840757 0.442286 -0.276228 0.743722 0.608749 -0.24747 0.6624 0.707096 -0.211958 0.570679 0.793347 -0.153991 0.41461 0.896875 -0.091062 0.24226 0.965928 -0.0679205 0.182871 0.980788 -0.0350357 0.194957 0.980186 -0.0350357 0.194957 0.980186 -0.0792326 0.440891 0.894057 -0.0942586 0.553103 0.827763 -0.142969 0.82293 0.549861 -0.141147 0.785419 0.602656 -0.108753 0.605159 0.788642 -0.173581 0.965899 0.192119 -0.173582 0.965897 0.192126 -0.159124 0.885448 0.436647 0 0.195077 0.980788 0 0.195077 0.980788 0 0.195077 0.980788 0 0.258812 0.965928 0 0.258812 0.965928 0 0.258812 0.965928 0 0.258812 0.965928 0 0.258812 0.965928 8.18778e-05 0.223787 0.974638 -6.93256e-05 0.608759 0.793356 0 0.555577 0.831465 0 0.793356 0.608759 -4.63912e-05 0.831471 0.555568 6.93394e-05 0.965928 0.258812 0 0.980787 0.19508 0.0464606 0.258532 0.964885 0.0464593 0.258529 0.964886 0.108749 0.605148 0.78865 0.135601 0.698839 0.702308 0.171029 0.951696 0.254998 0.171029 0.951696 0.254999 0.141146 0.785413 0.602664 0.0679206 0.182871 0.980788 0.0891579 0.242968 0.965928 0.153992 0.41461 0.896875 0.211958 0.570679 0.793347 0.244928 0.663344 0.707096 0.341483 0.919418 0.195091 0.335358 0.905843 0.258811 0.312266 0.840752 0.442297 0.276225 0.743713 0.608761 0.17358 0.965895 0.192137 0.173582 0.965897 0.192126 0.159124 0.885447 0.43665 0.159121 0.885434 0.436677 0.141149 0.785426 0.602646 0.141145 0.785415 0.602662 0.10875 0.605148 0.78865 0.108753 0.605159 0.788642 0.0792329 0.440895 0.894055 0.0792321 0.440891 0.894057 0.0350355 0.194957 0.980186 0.0350356 0.194957 0.980186 0 0.999999 0.0015674 -0.000363969 0.965998 0.258549 0.0116063 0.980718 0.195086 -0.000104331 0.896874 0.442286 0 0.195077 0.980788 -0.00795148 0.15297 0.988199 0.00458746 0.442281 0.896865 9.42077e-05 0.401732 0.915757 -0.000105251 0.608759 0.793355 -0.0108847 0.52864 0.848776 0.0208966 0.793196 0.608608 -0.00807127 0.695828 0.718163 7.47045e-05 0.842363 0.538911 0 -0.258812 0.965928 -0.0251024 -0.159139 0.986937 0.00236852 -0.422358 0.906426 -0.00222927 -0.608757 0.793353 0.000237559 -0.630491 0.776197 -0.00018726 -0.765387 0.643571 -0.00294232 -0.793352 0.608756 0.00235274 -0.875251 0.483663 0 -0.965928 0.258812 -0.0475853 -0.997474 -0.0527337 -0.0126918 -0.98358 0.180027 0.171029 -0.951696 0.254998 0.171029 -0.951696 0.254999 0.12606 -0.701465 0.701467 0.123146 -0.787317 0.604125 0.108751 -0.605148 0.78865 0.04646 -0.258529 0.964886 0.0464601 -0.258532 0.964885 0.336311 -0.90549 0.258811 0.336309 -0.905487 0.258823 0.246195 -0.662861 0.707109 0.246199 -0.662872 0.707097 0.0901101 -0.242614 0.965929 0.0901101 -0.242614 0.965929 0.0464599 -0.258529 0.964886 0.0464599 -0.258529 0.964886 0.126061 -0.701475 0.701457 0.126061 -0.701473 0.701459 0.171028 -0.951692 0.255012 0.171028 -0.951692 0.255012 0 -0.965924 0.258825 0 -0.258808 0.965929 0 -0.258808 0.965929 0 -0.258808 0.965929 0 -0.258808 0.965929 0 -0.965924 0.258825 0 -0.707114 0.7071 0 -0.707114 0.7071 0 -0.258808 0.965929 0 -0.258808 0.965929 0 -0.258808 0.965929 0 -0.258808 0.965929 0 -0.258808 0.965929 -0.0350357 -0.194957 0.980186 -0.0386695 -0.258615 0.965206 -0.0792324 -0.440891 0.894057 -0.108753 -0.605159 0.788642 -0.116201 -0.702324 0.70231 -0.17358 -0.965894 0.192145 -0.163952 -0.952854 0.255323 -0.159124 -0.885448 0.436647 -0.141148 -0.785419 0.602656 -0.0679202 -0.18287 0.980788 -0.0679205 -0.182871 0.980788 -0.153991 -0.41461 0.896875 -0.153993 -0.414615 0.896873 -0.211958 -0.570679 0.793347 -0.211958 -0.57068 0.793347 -0.276228 -0.743722 0.608749 -0.276223 -0.74371 0.608766 -0.312268 -0.840757 0.442286 -0.312268 -0.840757 0.442286 -0.341484 -0.91942 0.195078 -0.341482 -0.919414 0.195108 -0.171028 -0.951696 0.254999 -0.18273 -0.964148 0.192427 -0.159123 -0.885449 0.436647 -0.12606 -0.701466 0.701466 -0.158679 -0.780925 0.604134 -0.108753 -0.605159 0.788642 -0.0464607 -0.258532 0.964885 -0.104057 -0.432503 0.895608 -0.0350348 -0.194955 0.980186 -7.69563e-05 -0.842362 0.538913 0.000413947 -0.965928 0.258812 0.000363969 -0.965998 0.258549 0 -0.999999 0.0015674 0 -0.258812 0.965928 0.0251026 -0.159139 0.986937 -9.42082e-05 -0.401732 0.915757 0.000211732 -0.707107 0.707107 0.0449635 -0.548144 0.835175 0.00806939 -0.695827 0.718164 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.108203 -0.00847693 0.994093 0.657309 0.0383257 0.752646 0.123197 0.00302871 0.992378 0.118294 0.00132503 0.992978 0.110971 -0.00231807 0.993821 0.120419 0.0922938 0.988424 0.123515 0.0571613 0.990695 0.137999 0.0323276 0.989905 0.15005 0.0212412 0.98845 0.162071 0.0151575 0.986663 0.170978 0.0122829 0.985198 0.152142 0.0062995 0.988339 0.654881 0.0715617 0.752337 0.717013 0.0507998 0.695206 0.524301 0.0476792 0.850197 0.569445 0.0352324 0.821274 0.295394 0.028716 0.954944 0.358799 0.0137746 0.933313 0.178295 0.0102136 0.983924 0.182252 0.00959975 0.983205 0.618817 0.0151319 0.785389 0.562127 0.0239002 0.826706 0.498196 0.0240532 0.866731 0.52487 0.0165429 0.851022 0.259406 0.0152419 0.965648 0.295491 0.00628468 0.955325 0.145443 0.00532087 0.989352 0.145649 0.00518353 0.989323 0.618817 -0.0151318 0.785389 0.077409 -0.0028834 0.996995 0.0634637 -0.00352489 0.997978 0.0483006 -0.0049426 0.998821 0.0343505 -0.00685082 0.999386 0.0229097 -0.00924795 0.999695 0.0148661 -0.0114067 0.999824 0.0088997 -0.0134871 0.999869 0.0388332 0 0.999246 0.0247143 0.0277221 0.99931 0.0293061 0.0223388 0.999321 0.0330805 0.0184244 0.999283 0.0435716 0.0103562 0.998997 0.0576657 0.00462474 0.998325 0.0995601 -0.00620499 0.995012 0.112866 -0.00147358 0.993609 0.112723 -0.00151039 0.993625 0.10621 -0.00363356 0.994337 0.0876402 -0.0115673 0.996085 0.0795243 -0.0206134 0.99662 0.0970431 0.00799947 0.995248 0.0229249 -0.00243755 0.999734 0.108207 -0.00190166 0.994127 0.175297 -0.00756413 0.984487 0.259435 -0.00278462 0.965757 0.649135 -0.0394127 0.759652 0.570961 -0.0225695 0.820667 0.551168 -0.0220467 0.834103 0.498303 -0.0121824 0.866917 0.430841 -0.0184094 0.90224 0.300288 -0.0108482 0.953787 0.0691034 0.0010402 0.997609 0.0965853 -0.00494687 0.995312 0.175302 -0.00619184 0.984495 0.186105 -0.00789723 0.982498 0.300254 -0.0208934 0.95363 0.300764 -0.0210247 0.953467 0.430729 -0.0298651 0.901987 0.468935 -0.0382822 0.882403 0.55082 -0.040219 0.833654 0.607431 -0.0510311 0.792732 0.648552 -0.0491285 0.759583 0.722315 -0.0589628 0.689046 0 0.0147784 0.999891 -0.00218255 0.00262459 0.999994 -0.00186383 0.00461198 0.999988 -0.00110859 0.0112479 0.999936 -0.000682494 0.0176868 0.999843 -0.00343983 0.0565127 0.998396 0.000233484 0.0436184 0.999048 0.00187547 0.0382194 0.999268 0.00525224 0.0341519 0.999403 0.00919816 0.0327033 0.999423 -0.000460875 0.0215527 0.999768 0.000293339 0.040015 0.999199 -0.000253539 0.0646175 0.99791 0.00156073 0.136822 0.990594 -0.00507017 0.441256 0.897367 0.00395424 0.247829 0.968796 -0.000625387 0.282428 0.959288 0.000500376 0.127855 0.991793 0.00119742 0.576268 0.81726 -0.000764142 0.488066 0.872806 0.00787467 0.373731 0.927504 0.000788906 0.573403 0.819273 -0.00045073 0.648956 0.760826 -0.00251492 0.670594 0.74182 0.000608521 0.700043 0.714101 -7.25309e-05 0.726776 0.686874 0.000739355 0.770381 0.637583 0.00279504 0.761453 0.648215 -0.00214748 0.823165 0.567798 0.00206202 0.842218 0.539134 -0.000764612 0.87278 0.488114 0.00194409 0.900051 0.435781 0.00289569 0.903422 0.428744 -0.000273321 0.922565 0.385841 -0.00405649 0.983482 0.18096 0.00158456 0.957554 0.288251 0.00306179 0.952256 0.305285 0.00169078 0.948048 0.318124 0.000213372 0.937433 0.348167 1.27552e-08 0.997419 0.0717958 0.00572322 0.998832 0.047969 0.00210299 0.997475 0.0709919 -0.000794416 0.992692 0.12067 0.00363146 0.976654 0.214789 0.12354 -0.00186584 0.992338 0.682376 0.554395 0.476456 0.10549 0.993098 0.051262 0.0518488 0.74093 0.669577 -0.00643699 0.770383 0.637549 0.0504427 0.812974 0.580111 0.00999893 0.842128 0.539185 0.0554395 0.870044 0.489846 0.0174173 0.903138 0.428997 0.0563054 0.917629 0.39343 0.0307724 0.951509 0.306079 0.0526838 0.955995 0.288613 0.0439043 0.982115 0.183089 0.0441286 0.997727 0.0509181 0.0295006 0.996865 0.0734176 0.051534 0.994797 0.0878825 0.0492562 0.982552 0.179349 0.015774 0.998878 0.0446598 0.0335706 0.998315 0.0473262 0.0703216 0.996364 0.0480913 0.0971449 0.993152 0.0649064 0.278982 0.954767 0.102903 0.45827 0.847276 0.268538 0.46944 0.850846 0.235983 0.385526 0.903134 0.188994 0.580265 0.692543 0.428576 0.617764 0.689022 0.378968 0.725991 0.289852 0.623636 0.735301 0.300231 0.607613 0.754173 0.374303 0.539556 0.61263 0.398691 0.682444 0.764214 0.411106 0.49696 0.733207 0.1151 0.670193 0.749969 0.11864 0.650747 0.728358 0.0572332 0.682802 0.717339 0.0357624 0.695806 0.0426157 0.0427632 0.998176 0.0443624 0.0403112 0.998202 0.0169225 0.0326953 0.999322 0.0589013 0.282368 0.957496 0.0577923 0.281956 0.957685 0.0496936 0.572694 0.818261 0.0411437 0.57016 0.820503 0.0507052 0.648081 0.759882 0.78128 0.208791 0.588225 0.731013 0.26003 0.630875 0.681566 0.184149 0.708206 0.688451 0.184501 0.701424 0.628598 0.101147 0.771125 0.599495 0.091286 0.795156 0.569265 -0.000167795 0.822154 0.365927 0.107604 0.924402 0.357241 -0.049068 0.932722 0.120448 0.0690619 0.990314 0.405681 0.243004 0.88112 0.368347 0.242385 0.897535 0.505377 0.372465 0.778373 0.456705 0.374617 0.806897 0.564103 0.478497 0.672925 0.516811 0.484377 0.705894 0.599043 0.562797 0.569567 0.556075 0.571795 0.603185 0.618333 0.629526 0.47049 0.577817 0.641416 0.504692 0.617992 0.677901 0.398166 0.705248 0.554397 0.441892 0.712202 0.486979 0.505588 0.696721 0.498723 0.515612 0.670032 0.461181 0.581695 0.695989 0.455492 0.555091 0.636351 0.374184 0.674569 0.662107 0.371482 0.650857 0.583265 0.270957 0.765757 0.604164 0.270826 0.749426 0.505315 0.155301 0.848845 0.508381 0.15547 0.846982 0.386565 0.0286257 0.921818 0.250817 0.105121 0.96231 0.255748 0.105276 0.960994 0.52311 0.84921 0.0720978 0.290816 0.942744 0.163281 0.28071 0.941209 0.187957 0.360261 0.922538 0.138334 0.29869 0.914007 0.274545 0.382008 0.896892 0.222834 0.297236 0.87688 0.377799 0.380211 0.864167 0.329628 0.276999 0.830083 0.483977 0.363273 0.821483 0.439543 0.243368 0.772241 0.586869 0.336672 0.767172 0.545984 0.197064 0.700537 0.685867 0.302489 0.698469 0.648569 0.13508 0.609053 0.781542 0.258918 0.609631 0.749207 0.0538633 0.48984 0.870147 0.204201 0.491597 0.846543 0.0655832 0.408617 0.910347 -0.00332367 0.441259 0.897374 0.170348 0.982275 0.07822 0.16347 0.983415 0.0785602 0.132191 0.981596 0.137824 0.224445 0.970853 0.0840748 0.137915 0.963089 0.231169 0.245536 0.95439 0.169861 0.126968 0.931288 0.34144 0.242984 0.928306 0.281438 0.108802 0.888043 0.446701 0.229924 0.890571 0.392451 0.0849055 0.835399 0.543047 0.210982 0.842077 0.49638 0.0535164 0.773099 0.632023 0.186219 0.782567 0.594063 0.0100904 0.69792 0.716105 0.157467 0.709118 0.687281 0.0647766 0.666413 0.742764 -0.0198536 0.69988 0.713985 0.57799 0.759433 0.298644 0.491001 0.815045 0.307602 0.451631 0.796691 0.401639 0.510874 0.780574 0.360155 0.439423 0.744691 0.502338 0.499508 0.731984 0.463347 0.409964 0.681066 0.606695 0.475774 0.671069 0.568599 0.363567 0.600291 0.712369 0.439592 0.592924 0.674685 0.297277 0.49542 0.816202 0.385514 0.491262 0.781051 0.203362 0.359251 0.910815 0.304335 0.358419 0.882562 0.0905892 0.199109 0.975781 0.190501 0.199447 0.961213 0.051597 0.0980323 0.993845 -0.00196654 0.127855 0.991791 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.234091 0.0155306 -0.972091 -0.097543 0.00337884 -0.995226 -0.130431 0.00567088 -0.991441 -0.120802 0.0289129 -0.992256 -0.030396 -0.00647566 -0.999517 -0.000333884 0 -1 -0.0043936 -0.000406244 -0.99999 -0.00506996 -0.000236321 -0.999987 -0.0223609 0.000656676 -0.99975 -0.0568105 0.00711955 -0.99836 -0.31169 0.00782283 -0.950152 -0.384607 -0.0922964 -0.918455 -0.259289 0.0143883 -0.965693 -0.324496 -0.105897 -0.939941 -0.23362 0.0235518 -0.972043 -0.250124 0.00773091 -0.968183 -0.282488 0.0270865 -0.958888 -0.311666 0.0078653 -0.950159 -0.311572 0.00793997 -0.950189 -0.679726 0.0512557 -0.731673 -0.708368 0.0716876 -0.702193 -0.709369 0.0726041 -0.701088 -0.236816 -0.00153942 -0.971553 -0.238783 0.000497881 -0.971073 -0.238723 0.00484102 -0.971076 -0.0979607 0.00367964 -0.995184 -0.0611926 -3.9021e-05 -0.998126 -0.24908 0.0392357 -0.967688 -0.627792 0.0346928 -0.777608 -0.657251 0.0485764 -0.752104 -0.550312 0.0480363 -0.833576 -0.614365 0.0352499 -0.788235 -0.430102 0.0510423 -0.901336 -0.531527 0.0235905 -0.846713 -0.447966 0.028455 -0.893597 -0.177684 0.0346616 -0.983477 -0.229474 0.0178504 -0.973151 -0.431114 0.00838994 -0.902258 -0.392038 0.0173576 -0.919785 -0.551077 0.0210826 -0.834188 -0.563449 0.0189193 -0.825934 -0.564044 0.0189708 -0.825527 -0.275565 -0.00802928 -0.961249 -0.306072 -0.0344268 -0.951386 -0.563488 -0.0147285 -0.825993 -0.534735 -0.0350672 -0.844292 -0.546677 -0.034936 -0.836614 -0.720524 -0.035997 -0.692495 -0.336667 -0.0153769 -0.941498 -0.335871 -0.015662 -0.941778 -0.323038 -0.0211858 -0.946149 -0.234116 0.00557719 -0.972193 -0.235811 0.000551956 -0.971799 -0.237924 -0.00254382 -0.97128 -0.239137 -0.00358194 -0.970979 -0.253998 -0.0125891 -0.967123 -0.392068 -0.0122383 -0.919855 -0.424881 -0.0204617 -0.905018 -0.589771 -0.0192313 -0.807342 -0.72919 -0.0657081 -0.68115 -0.682681 -0.0524031 -0.728835 -0.62475 -0.052192 -0.779079 -0.589181 -0.0413678 -0.806941 -0.481027 -0.0407306 -0.875759 -0.424779 -0.0254089 -0.904941 -0.306582 -0.0245337 -0.951528 -0.271396 -0.0131404 -0.962378 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.480573 -0.0623071 -0.874739 -0.18217 -0.0861975 -0.979482 0.0207419 -0.783377 -0.621201 -0.412995 -0.891039 -0.188376 -0.701254 -0.285956 -0.653048 -0.717973 -0.0630513 -0.693209 -0.776053 -0.257067 -0.575898 -0.771036 -0.206866 -0.602255 -0.74968 -0.169806 -0.639645 -0.733872 -0.195556 -0.65053 -0.764217 -0.106596 -0.636089 -0.795534 -0.251712 -0.55115 -0.720227 -0.440197 -0.53619 -0.700815 -0.461578 -0.543878 -0.863868 -0.421948 -0.275122 -0.561688 -0.713692 -0.41851 -0.680582 -0.617473 -0.39438 -0.661569 -0.593248 -0.458675 -0.553495 -0.784654 -0.279215 -0.571912 -0.743668 -0.346229 -0.56621 -0.739263 -0.364549 -0.447637 -0.85907 -0.248233 -0.0514821 -0.986409 -0.156034 -0.0505875 -0.996375 -0.0683969 -0.0334764 -0.996396 -0.0779322 -0.0431533 -0.997995 -0.0463003 -0.0243522 -0.998423 -0.050591 -0.0269018 -0.998605 -0.0454369 -0.0489682 -0.94152 -0.333379 -0.04014 -0.961269 -0.272674 -0.0543611 -0.963896 -0.260672 -0.0473593 -0.98255 -0.179869 -0.0888882 -0.987855 -0.127445 -0.0571396 -0.929547 -0.364249 0.0365821 -0.89119 -0.452152 -0.121855 -0.911924 -0.39185 -0.051676 -0.833994 -0.549348 -0.0362006 -0.847789 -0.529096 -0.0384846 -0.878601 -0.476004 -0.0225967 -0.702828 -0.711001 -0.015023 -0.745899 -0.66589 -0.0776205 -0.795222 -0.601329 -0.0900526 -0.168045 -0.981658 -0.0436991 -0.187072 -0.981374 -0.00369241 -0.2234 -0.97472 -0.71668 -0.373527 -0.588937 -0.740176 -0.28276 -0.610071 -0.704358 -0.224719 -0.673336 -0.70601 -0.214951 -0.674793 -0.644952 -0.123236 -0.754221 -0.644033 -0.128988 -0.754045 -0.604862 -0.07278 -0.792997 -0.619234 0.132969 -0.773866 -0.235972 -0.0565706 -0.970112 -0.23321 -0.0831643 -0.968864 -0.316527 -0.161704 -0.934699 -0.31511 -0.168437 -0.933988 -0.433014 -0.284987 -0.85515 -0.42614 -0.312699 -0.848896 -0.511653 -0.399766 -0.760525 -0.500941 -0.434824 -0.748322 -0.561354 -0.496369 -0.662193 -0.548534 -0.530714 -0.646106 -0.592399 -0.57445 -0.564863 -0.577914 -0.606659 -0.545877 -0.609232 -0.636665 -0.472752 -0.592155 -0.668524 -0.44992 -0.61246 -0.686887 -0.391254 -0.570857 -0.73438 -0.367164 -0.648092 -0.608965 -0.457317 -0.708856 -0.530953 -0.46434 -0.684863 -0.496268 -0.533555 -0.694745 -0.467545 -0.546563 -0.658928 -0.417546 -0.625674 -0.666529 -0.391046 -0.634683 -0.614714 -0.321677 -0.720174 -0.619735 -0.301003 -0.724793 -0.545118 -0.206149 -0.812618 -0.546167 -0.201293 -0.813131 -0.442921 -0.0783476 -0.893131 -0.434832 -0.116066 -0.893 -0.306148 0.00434459 -0.951974 -0.184013 -0.564644 -0.80456 0.00439767 -0.455075 -0.890442 -0.134588 -0.432172 -0.891692 -0.172132 -0.360251 -0.916837 -0.0316847 -0.27291 -0.961518 -0.0140126 -0.365555 -0.930684 0.471327 -0.397945 -0.787077 -0.01694 -0.493308 -0.86969 -0.0472654 -0.610614 -0.790517 -0.0594223 -0.616677 -0.784971 -0.242965 -0.967202 -0.0740792 -0.291212 -0.942255 -0.165381 -0.314896 -0.940977 -0.124111 -0.331813 -0.926864 -0.175563 -0.319795 -0.925345 -0.203635 -0.351924 -0.900953 -0.253835 -0.32572 -0.894354 -0.306655 -0.352017 -0.868423 -0.349177 -0.314033 -0.854438 -0.413906 -0.336046 -0.826617 -0.451418 -0.289829 -0.805373 -0.517081 -0.309121 -0.773704 -0.553017 -0.255686 -0.745659 -0.615318 -0.272831 -0.707172 -0.652281 -0.211061 -0.672023 -0.709815 -0.22579 -0.621957 -0.749792 -0.140807 -0.570881 -0.808869 -0.209193 -0.48757 -0.847652 -0.0495982 -0.383416 -0.922243 -0.0588021 -0.99733 -0.0433131 -0.0988726 -0.992866 -0.0666392 -0.113335 -0.992304 -0.0498816 -0.154203 -0.984812 -0.079788 -0.157072 -0.98482 -0.0738811 -0.185805 -0.974342 -0.127017 -0.172773 -0.973301 -0.151112 -0.202408 -0.956912 -0.208208 -0.172033 -0.950876 -0.257372 -0.198631 -0.929057 -0.312088 -0.160903 -0.917212 -0.364462 -0.184049 -0.889854 -0.417477 -0.143942 -0.873823 -0.46445 -0.162894 -0.840718 -0.516391 -0.121458 -0.821866 -0.556583 -0.135553 -0.781538 -0.608953 -0.0921704 -0.760405 -0.642875 -0.100428 -0.709494 -0.697519 -0.0609248 -0.689734 -0.721495 -0.0566464 -0.660632 -0.74857 -0.445904 -0.860116 -0.24773 -0.484772 -0.823045 -0.295962 -0.468164 -0.815775 -0.339607 -0.492893 -0.785346 -0.37455 -0.463139 -0.769289 -0.440109 -0.483361 -0.739104 -0.469135 -0.442895 -0.713761 -0.542576 -0.460648 -0.681482 -0.568671 -0.408727 -0.645504 -0.645187 -0.42531 -0.607816 -0.670575 -0.35901 -0.558654 -0.747675 -0.37428 -0.513081 -0.772439 -0.287124 -0.446061 -0.847697 -0.300439 -0.390391 -0.870247 -0.189359 -0.304582 -0.933474 -0.200106 -0.240545 -0.949787 -0.102912 -0.167789 -0.980437 -0.125559 -0.110144 -0.985953 -0.00147304 -0.611296 -0.791401 0.00236125 -0.643321 -0.765593 0.000847325 -0.661694 -0.749774 -0.00116741 -0.703336 -0.710856 -0.00112755 -0.703011 -0.711178 -1.28369e-08 -0.725565 -0.688154 -2.03538e-08 -0.736143 -0.676826 -0.000151618 -0.748347 -0.663308 3.30762e-05 -0.745994 -0.665952 -2.84027e-05 -0.767898 -0.640572 -0.00222397 -0.797851 -0.602851 0.00407752 -0.822749 -0.568391 -2.91168e-07 -0.848562 -0.529095 -1.24796e-07 -0.866457 -0.499251 -0.000694242 -0.879547 -0.475812 0.00306748 -0.899253 -0.437419 -0.00263794 -0.919928 -0.392079 0.000387496 -0.93513 -0.354305 6.17687e-08 -0.943146 -0.332378 -2.70884e-07 -0.951126 -0.308802 -0.00242973 -0.962408 -0.271596 0.00407484 -0.975477 -0.220062 -0.000501211 -0.98402 -0.178057 -1.64696e-06 -0.996528 -0.0832607 0.00527097 -0.997841 -0.0654634 0.000369149 -0.992322 -0.123678 6.38554e-07 -0.326143 -0.945321 -0.000671389 -0.390996 -0.920392 -0.0108761 -0.462454 -0.886577 -0.00881348 -0.451189 -0.892385 -2.01326e-06 -0.523325 -0.852133 4.1521e-07 -0.579042 -0.815298 -0.0214788 -0.22335 -0.974502 -0.00636165 -0.231156 -0.972896 -8.15058e-06 -0.238093 -0.971242 0.00534137 -0.210855 -0.977503 0.0124893 -0.180393 -0.983515 -0.0135107 -0.264271 -0.964354 0.00678798 -0.119102 -0.992859 -0.0121071 -0.200209 -0.979679 -0.000777458 -0.142918 -0.989734 0.000279115 -0.0729286 -0.997337 0.00298817 -0.040686 -0.999168 0.00854736 -0.0159851 -0.999836 -0.0748879 -0.0163043 -0.997059 -0.00155325 -0.0436971 -0.999044 9.17115e-05 -0.00245096 -0.999997 0 -0.000879438 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -5.59911e-07 -2.28822e-06 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 8.71126e-06 5.61623e-05 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.156435 -0.987688 0 -0.156435 -0.987688 0 -0.345855 -0.938288 0 -0.453915 -0.890863 0.0180221 -0.488375 -0.872634 0 -0.70711 -0.707104 0 -0.70711 -0.707104 0 -0.891004 -0.453995 0 -0.891004 -0.453995 0 -0.987689 -0.156431 0 -0.987689 -0.156431 0 -1 0 0 -1 0 0 -1 0 0 -0.987689 0.156431 0 -0.987689 0.156431 0 -0.891004 0.453995 0 -0.891004 0.453995 0 -0.70711 0.707104 0 -0.70711 0.707104 0 -0.488375 0.872634 0 -0.453915 0.890863 0.0180221 -0.345855 0.938288 0 -0.156435 0.987688 0 -0.156435 0.987688 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0359973 0.0147689 0.999243 0.0118782 0.0128174 0.999847 0 0.00349661 0.999994 0.0359973 -0.0147689 0.999243 0 -0.0118538 0.99993 -0.934557 0.319836 0.155913 -0.553902 0.723101 0.412696 -0.595531 0.691629 0.408647 -0.966779 0.196877 0.163028 -0.971351 0.166659 0.169418 -0.6308 0.77026 0.0937561 -0.625499 0.779961 -0.0203043 -0.630499 0.77614 0.00885168 -0.659435 0.751388 0.023695 -0.660593 0.750602 0.0146122 -0.695343 0.718538 0.0142094 -0.696124 0.717832 0.0113444 -0.746547 0.6649 0.0239989 -0.717236 0.670882 0.188387 -0.771925 0.635641 0.00957462 -0.801971 0.597017 0.0203386 -0.831632 0.550391 -0.0738819 -0.996107 0.0878223 0.00768482 -0.98365 0.1745 0.044521 -0.9692 0.236969 -0.0670612 -0.969074 0.242796 -0.0441223 -0.9319 0.351797 0.0883246 -0.94187 0.335228 0.0224174 -0.899328 0.436635 0.0236364 -0.90791 0.414857 -0.0599443 -0.851703 0.513025 0.106811 -0.994459 0.0939133 0.047249 -0.998507 0.0133966 0.0529488 -0.998386 0.0130358 0.0552701 -0.609736 0.790885 0.0521806 -0.62048 0.782478 0.0522761 -0.615016 0.78851 0.00276122 -0.720805 0.693113 0.00589261 -0.727286 0.685736 -0.0286456 -0.694163 0.718899 0.0363686 -0.662573 0.748675 0.0219599 -0.664218 0.747371 0.0158427 -0.633975 0.771894 0.0474969 -0.798932 0.600232 -0.0378095 -0.803225 0.591154 -0.0732644 -0.768183 0.63884 0.0421684 -0.882219 0.464308 -0.078155 -0.867203 0.497113 0.0289266 -0.831047 0.555376 0.0302891 -0.989001 0.135538 0.0592081 -0.993253 0.115899 -0.00387573 -0.981986 0.187668 0.022018 -0.970792 0.238896 0.0221652 -0.966068 0.252827 0.0528359 -0.942606 0.333755 0.0100663 -0.938296 0.344453 0.0308687 -0.908642 0.416345 0.0320286 -0.845396 0.451765 0.28498 -0.903592 0.359223 0.233411 -0.742147 0.564629 0.361127 -0.754926 0.535828 0.378122 -0.746314 0.558254 0.362447 -0.795696 0.519442 0.311526 -0.84375 0.456849 0.281736 -0.663724 0.650561 0.369107 -0.645594 0.652885 0.396168 -0.710641 0.606194 0.357097 -0.555844 0.721338 0.41317 -0.548873 0.719523 0.42547 -0.585631 0.711452 0.388423 -0.576467 0.753616 0.31583 -0.583208 0.748796 0.314916 -0.58082 0.750792 0.314578 -0.590261 0.750533 0.297141 -0.622764 0.722114 0.301191 -0.629321 0.719835 0.292905 -0.678895 0.671116 0.297833 -0.685308 0.668381 0.28917 -0.757288 0.583291 0.293745 -0.76807 0.57719 0.277346 -0.830258 0.482228 0.279514 -0.851391 0.458023 0.255634 -0.944462 0.249355 0.214043 -0.937498 0.282712 0.202906 -0.946301 0.295666 0.130752 -0.975146 0.178332 0.131486 -0.968277 0.229982 0.0977154 -0.987547 0.126511 0.0935183 -0.988221 0.133419 0.0749595 -0.575198 0.793833 0.197424 -0.61383 0.768992 0.178505 -0.6046 0.776425 0.177831 -0.61401 0.773827 0.155509 -0.648868 0.744453 0.157355 -0.653058 0.742163 0.1507 -0.70849 0.68905 0.152489 -0.707613 0.689609 0.154024 -0.788505 0.59545 0.153943 -0.782794 0.599875 0.165483 -0.876204 0.454009 0.161686 -0.836866 0.487096 0.249786 -0.900589 0.405369 0.15689 -0.884431 0.389624 0.256855 -0.914968 0.342596 0.213216 -0.908273 0.33342 0.252729 -0.955658 0.256661 0.144369 -0.971352 -0.166663 0.169405 -0.998472 3.10387e-06 0.055266 -0.998572 -0.0143072 0.0514706 -0.998251 -0.0133808 0.0575917 -0.995155 -0.0904578 0.0385316 -0.995426 -0.0940031 0.0170213 -0.983499 -0.175987 0.0419365 -0.964242 -0.249318 -0.0898728 -0.971149 -0.237439 -0.0221986 -0.938335 -0.342322 0.0484019 -0.935331 -0.353048 0.0226462 -0.905903 -0.422834 0.0234823 -0.899453 -0.436699 -0.0166547 -0.845758 -0.527171 0.0823649 -0.83287 -0.551204 -0.0500178 -0.793029 -0.608568 0.0274004 -0.771954 -0.635662 -0.00459806 -0.733422 -0.671092 0.108291 -0.729275 -0.682122 0.0535509 -0.691427 -0.72243 -0.00476212 -0.696101 -0.717803 0.0142282 -0.656384 -0.754284 0.0146827 -0.659492 -0.749344 0.059625 -0.628275 -0.777978 -0.00453051 -0.625499 -0.779961 -0.0203164 -0.599668 -0.79498 0.0916803 -0.657291 -0.645125 0.389593 -0.651313 -0.658669 0.376758 -0.595536 -0.691625 0.408646 -0.585632 -0.711455 0.388416 -0.552961 -0.718742 0.421479 -0.552542 -0.724332 0.412361 -0.584475 -0.694302 0.419921 -0.765224 -0.505914 0.398098 -0.754926 -0.535827 0.378122 -0.72924 -0.591095 0.344698 -0.955649 -0.256673 0.144408 -0.877977 -0.369122 0.304803 -0.913488 -0.340406 0.222852 -0.841791 -0.456723 0.287737 -0.846513 -0.452893 0.279829 -0.754593 -0.565372 0.333083 -0.992386 -0.115718 0.0421879 -0.989783 -0.142467 0.00567702 -0.942706 -0.332213 0.030656 -0.938723 -0.344647 0.00417409 -0.970155 -0.234325 0.0623804 -0.967173 -0.253148 0.022196 -0.981985 -0.187674 0.0220183 -0.798442 -0.599594 -0.0545579 -0.805164 -0.5925 -0.0255778 -0.831048 -0.555375 0.0302891 -0.885883 -0.463057 0.028094 -0.857727 -0.491875 -0.149544 -0.908638 -0.416355 0.0320285 -0.721311 -0.692422 -0.0162215 -0.727581 -0.685936 0.0108789 -0.76818 -0.638843 0.0421738 -0.655063 -0.753747 0.0525116 -0.614214 -0.78741 0.0522118 -0.622884 -0.782036 0.0208707 -0.633977 -0.771891 0.0475058 -0.662828 -0.74857 0.017352 -0.664135 -0.74727 0.0226433 -0.694169 -0.718893 0.0363538 -0.550413 -0.779555 0.298897 -0.562514 -0.765695 0.311911 -0.585573 -0.746809 0.315248 -0.585485 -0.754509 0.296518 -0.627134 -0.718104 0.30171 -0.62499 -0.723793 0.292424 -0.683143 -0.666626 0.298202 -0.681181 -0.672738 0.28882 -0.76434 -0.573882 0.294015 -0.761451 -0.586085 0.276941 -0.84659 -0.452973 0.279466 -0.835841 -0.486328 0.254665 -0.907505 -0.332434 0.256755 -0.892936 -0.397291 0.211721 -0.944461 -0.249365 0.214033 -0.988221 -0.133415 0.0749607 -0.987548 -0.126509 0.0935156 -0.968277 -0.22998 0.0977188 -0.975146 -0.178333 0.131485 -0.937458 -0.322792 0.130298 -0.615668 -0.754453 0.227495 -0.586194 -0.790725 0.17644 -0.610323 -0.771835 0.178258 -0.608214 -0.778459 0.15517 -0.65204 -0.741645 0.157503 -0.649855 -0.744994 0.150574 -0.707837 -0.689724 0.152472 -0.708278 -0.688924 0.154033 -0.784395 -0.600837 0.154009 -0.786934 -0.594448 0.165427 -0.851385 -0.49847 0.163312 -0.869416 -0.449134 0.2059 -0.900591 -0.405367 0.156888 -0.943898 -0.291439 0.155309 -0.937502 -0.282698 0.202908 -0.966781 -0.196869 0.163023 -0.638684 0.575003 -0.511326 -0.743922 0.406066 -0.530745 -0.98703 0.0298545 -0.157738 -0.980395 -0.00485786 -0.196981 -0.982401 0.0375549 -0.182968 -0.978508 0.0125996 -0.205826 -0.999602 0 -0.0282246 -0.999569 0.00206684 -0.029289 -0.997939 0.000756601 -0.0641691 -0.997834 0.00155576 -0.0657616 -0.995899 0.00158672 -0.0904561 -0.995635 0.00530281 -0.0931774 -0.992278 0.00160108 -0.124024 -0.991442 0.00915404 -0.130224 -0.98543 -0.00338018 -0.170047 -0.988219 0.0157351 -0.152233 -0.985446 0.042076 -0.164701 -0.988869 0.0582676 -0.136907 -0.996508 0.0430189 -0.0715573 -0.99449 0.0541378 -0.0897665 -0.99861 0.0307792 -0.042786 -0.998093 0.0358491 -0.05025 -0.997617 0.0363208 -0.058656 -0.625072 0.00833551 -0.780522 -0.624462 0.00774224 -0.781017 -0.697269 0.338832 -0.631672 -0.691672 0.281739 -0.664991 -0.661597 0.28967 -0.69165 -0.680234 0.197245 -0.705958 -0.630695 0.214101 -0.745912 -0.672398 0.1157 -0.731092 -0.606375 0.142313 -0.78234 -0.665525 0.050451 -0.744669 -0.600111 0.0823759 -0.795664 -0.633145 0.0366718 -0.773164 -0.733799 0.404437 -0.545867 -0.764001 0.428856 -0.482063 -0.761175 0.438972 -0.477405 -0.736612 0.56231 -0.375779 -0.80341 0.454952 -0.384124 -0.785011 0.582325 -0.211321 -0.812375 0.530335 -0.242471 -0.86501 0.466868 -0.183825 -0.863732 0.468997 -0.184414 -0.896338 0.4309 -0.10442 -0.921629 0.371834 -0.111087 -0.919876 0.377396 -0.106775 -0.936839 0.3399 -0.0824714 -0.968333 0.201165 -0.147863 -0.962153 0.218105 -0.163379 -0.954735 0.223378 -0.196426 -0.954152 0.270987 -0.127123 -0.944968 0.28316 -0.163876 -0.982868 0.0522921 -0.176736 -0.983173 0.0643805 -0.170958 -0.984589 0.0638609 -0.16281 -0.973437 0.153364 -0.169999 -0.975024 0.14479 -0.168418 -0.975289 0.143372 -0.168096 -0.977505 0.133825 -0.163018 -0.972888 0.17756 -0.148191 -0.971138 0.188041 -0.146736 -0.624918 0.77923 -0.0477247 -0.630109 0.775631 -0.0368797 -0.659485 0.749346 -0.0596664 -0.666287 0.741604 -0.0780058 -0.694222 0.715882 -0.0746301 -0.726286 0.67932 -0.105038 -0.72809 0.676555 -0.110271 -0.768259 0.632628 -0.0977702 -0.80823 0.571596 -0.141573 -0.829389 0.548903 -0.104015 -0.887605 0.430972 -0.162545 -0.88918 0.423621 -0.172929 -0.925404 0.349294 -0.147041 -0.949958 0.253678 -0.182285 -0.960207 0.234778 -0.151268 -0.977559 0.103606 -0.183422 -0.982089 0.0927412 -0.164011 -0.678637 0.597143 -0.427635 -0.728319 0.473618 -0.495214 -0.713781 0.480008 -0.510009 -0.752385 0.333328 -0.568164 -0.743811 0.338491 -0.576341 -0.766618 0.191449 -0.612899 -0.761366 0.19556 -0.618125 -0.770454 0.0767519 -0.632859 -0.767386 0.0795993 -0.636225 -0.98581 0.0132767 -0.167338 -0.983574 0.0192227 -0.179479 -0.892413 0.0111886 -0.45108 -0.665138 0.501608 -0.553155 -0.65466 0.383794 -0.651247 -0.654799 0.383136 -0.651495 -0.638525 0.293748 -0.711335 -0.643598 0.258507 -0.720386 -0.627891 0.200928 -0.751918 -0.632896 0.144953 -0.760547 -0.622052 0.115139 -0.774464 -0.62468 0.0580827 -0.778718 -0.619702 0.0469823 -0.78343 -0.620262 0.0171026 -0.784208 -0.776709 0.00860321 -0.629801 -0.769179 0.0153887 -0.638848 -0.674884 0.00671882 -0.737893 -0.992879 0.115815 0.0279065 -0.995406 0.0632875 -0.0718445 -0.981851 0.187627 0.0276748 -0.987614 0.156901 -0.000868771 -0.96731 0.253227 -0.0136921 -0.938085 0.344363 0.0375595 -0.946089 0.323468 0.0168385 -0.909075 0.41659 0.00587831 -0.867059 0.497024 0.0342854 -0.871361 0.48989 0.0271758 -0.831318 0.555584 0.0153916 -0.950267 0.30062 -0.0813654 -0.961495 0.258222 -0.0940667 -0.970513 0.230412 -0.0708208 -0.986239 0.1383 -0.0905864 -0.986774 0.135765 -0.0885666 -0.99358 0.0474839 -0.102682 -0.991234 0.0584193 -0.118498 -0.72761 0.68599 0.00122554 -0.694525 0.719314 0.0149288 -0.688714 0.724664 0.0231339 -0.664271 0.74747 -0.00571312 -0.82977 0.556292 -0.0449437 -0.831532 0.553506 -0.0467546 -0.875561 0.482977 0.0112612 -0.901086 0.433386 -0.0148674 -0.924756 0.379617 0.026784 -0.959213 0.282371 -0.0133061 -0.966444 0.256823 0.00527169 -0.990245 0.134943 -0.0347188 -0.989985 0.136551 -0.0358199 -0.997309 0.0355299 -0.0641308 -0.997138 0.0376615 -0.0655534 -0.630675 0.77516 -0.0370856 -0.614395 0.78765 0.0461068 -0.634639 0.772796 0.00451204 -0.88534 0.0187629 -0.464566 -0.882336 0.0932392 -0.461292 -0.883475 0.0919971 -0.459357 -0.868079 0.227613 -0.44117 -0.867816 0.227856 -0.441562 -0.830743 0.387825 -0.399322 -0.829804 0.388509 -0.400607 -0.772076 0.536751 -0.340289 -0.774399 0.535423 -0.337089 -0.708202 0.650018 -0.275548 -0.716912 0.645825 -0.262578 -0.656034 0.724073 -0.212928 -0.670947 0.717194 -0.188315 -0.625167 0.764809 -0.155673 -0.644553 0.755026 -0.120365 -0.62823 0.770205 -0.110052 -0.651342 0.75875 -0.00726487 -0.688848 0.724382 -0.0275445 -0.710931 0.70287 0.0234736 -0.736223 0.676676 0.00922378 -0.784931 0.619282 0.0193236 -0.768215 0.638867 0.0411567 -0.80532 0.592551 0.0185017 -0.60919 0.0038505 -0.793015 -0.607017 -0.00393901 -0.794679 -0.606548 0.0346225 -0.794293 -0.611672 0.0463419 -0.789753 -0.610084 0.0841591 -0.787854 -0.62143 0.115007 -0.774983 -0.61899 0.146203 -0.771671 -0.636162 0.20412 -0.744066 -0.634729 0.215924 -0.741954 -0.654575 0.303129 -0.692564 -0.657304 0.28712 -0.696788 -0.675505 0.400246 -0.619271 -0.6585 0.461645 -0.594358 -0.741733 0.551173 -0.382152 -0.736911 0.562687 -0.374626 -0.699744 0.692905 -0.173902 -0.776343 0.569926 -0.269213 -0.726513 0.683935 -0.0664198 -0.768317 0.630723 -0.108985 -0.683602 -0.00474057 -0.72984 -0.682432 0.0679049 -0.727789 -0.686962 0.0638594 -0.723882 -0.680805 0.16741 -0.713077 -0.690903 0.159783 -0.705069 -0.675298 0.29232 -0.677142 -0.692792 0.282176 -0.663639 -0.665595 0.421439 -0.615932 -0.691665 0.410745 -0.594044 -0.623215 0.611711 -0.48725 -0.703323 0.541956 -0.460022 -0.640694 0.669112 -0.376563 -0.682997 0.636361 -0.358553 -0.639835 0.744216 -0.191715 -0.692753 0.678201 -0.245228 -0.649816 0.75152 -0.11383 -0.726556 0.684865 -0.0554619 -0.711064 0.701809 -0.0430472 -0.770201 0.637724 0.00990606 -0.784965 0.619538 -0.00165852 -0.831277 0.553784 0.047966 -0.871372 0.490441 0.0133762 -0.900819 0.430835 0.0539138 -0.945969 0.324248 0.00255427 -0.959594 0.279803 0.0298435 -0.987116 0.158175 -0.0241427 -0.991016 0.133355 -0.0101654 -0.997593 0.0534356 -0.0441984 -0.998951 0.024154 -0.038916 0.105736 -0.645907 0.756058 0.391828 -0.909066 0.141667 0.59057 -0.744043 0.312453 0.656106 -0.632105 0.412271 0.592097 -0.0916325 0.80064 0.31754 -0.0621996 0.946203 0.0419498 -0.0337316 0.99855 0.0355288 -0.0398552 0.998574 0.0305591 -0.0482674 0.998367 0.186479 -0.0547558 0.980932 0.0972404 -0.0210723 0.995038 0.0229259 -0.0489206 0.99854 0.78149 -0.2003 0.590892 0.724778 -0.106607 0.680685 0.752719 -0.112147 0.64872 0.722711 -0.0449176 0.68969 0.714305 -0.482677 0.506747 0.710923 -0.525073 0.467853 0.579147 -0.717252 0.387476 0.452309 -0.849934 0.270238 0.369536 -0.90962 0.189829 0.408515 -0.891691 0.194942 0.456215 -0.855932 0.24341 0.208769 -0.974536 0.0818216 0.0587901 -0.997133 0.0476322 0.033451 -0.998321 0.0472809 0.014516 -0.998901 0.0445771 0.0442808 -0.997718 0.050978 0.0187166 -0.995845 0.0891159 0.0658847 -0.995432 0.0690976 0.0311127 -0.982918 0.181395 0.0598703 -0.984525 0.164698 0.0384901 -0.956097 0.29051 0.0536797 -0.958356 0.280486 0.045345 -0.938163 0.343212 -0.0454926 -0.707797 0.70495 0.223144 -0.76583 0.603085 -0.0592773 -0.762486 0.644283 0.153342 -0.845638 0.511256 -0.0564955 -0.824362 0.563237 0.159218 -0.900131 0.40548 -0.071028 -0.875772 0.477472 0.0473245 -0.917436 0.39506 0.766518 -0.407037 0.49676 0.610908 -0.395765 0.685683 0.752846 -0.373661 0.541849 0.734849 -0.295043 0.610694 0.72618 -0.286568 0.624933 0.729774 -0.257561 0.633318 0.682842 -0.185502 0.706623 0.684136 -0.178086 0.707279 0.615129 -0.083794 0.783961 0.605697 -0.103144 0.788982 0.247332 0.520008 0.817569 0.215889 -0.0731399 0.973675 0.248903 -0.100071 0.963345 0.248365 -0.102473 0.963231 0.387355 -0.225681 0.893882 0.380614 -0.252657 0.889549 0.485371 -0.351908 0.80036 0.473615 -0.389505 0.789921 0.546933 -0.460425 0.699195 0.532366 -0.498032 0.684508 0.585144 -0.548393 0.597388 0.569038 -0.58293 0.57999 0.606835 -0.618 0.499827 0.588815 -0.650668 0.479509 0.610482 -0.670327 0.421869 0.599463 -0.693935 0.398872 0.683152 -0.558252 0.470806 0.696283 -0.497166 0.517703 0.677712 -0.470761 0.564881 0.687603 -0.442356 0.575781 0.644564 -0.38381 0.661231 0.652259 -0.357293 0.668506 0.58965 -0.277789 0.758384 0.594458 -0.258356 0.761493 0.503605 -0.152972 0.850283 0.504047 -0.151042 0.850366 0.430761 -0.0734392 0.899473 0.468705 -0.0067872 0.883329 0.293928 -0.948167 0.120768 0.290822 -0.942489 0.164736 0.300798 -0.943386 0.139798 0.338948 -0.921487 0.189672 0.321661 -0.919043 0.227803 0.356262 -0.893085 0.274731 0.322344 -0.884855 0.336343 0.351666 -0.856797 0.377135 0.30536 -0.841326 0.446011 0.331328 -0.810108 0.48368 0.276396 -0.787469 0.550906 0.299852 -0.751104 0.588159 0.237198 -0.721234 0.650814 0.258185 -0.676165 0.69003 0.185918 -0.637728 0.747487 0.203414 -0.578378 0.790001 0.120249 -0.530082 0.839377 0.133177 -0.447393 0.884366 0.0598572 -0.401874 0.913737 0.0637617 -0.272244 0.960113 0.0387615 -0.262652 0.964112 0.00584098 -0.1112 0.993781 0.0822574 -0.995117 0.0545461 0.100036 -0.992395 0.0717347 0.119191 -0.991542 0.051367 0.162532 -0.983335 0.0814572 0.159859 -0.983336 0.0865807 0.193618 -0.971095 0.139594 0.172315 -0.969232 0.175772 0.205627 -0.950764 0.231873 0.16709 -0.943107 0.287455 0.197378 -0.918593 0.342387 0.15334 -0.905188 0.396386 0.179546 -0.874895 0.449802 0.134113 -0.857468 0.496753 0.15538 -0.8208 0.549677 0.108697 -0.800281 0.589691 0.123948 -0.755512 0.643302 0.0756609 -0.732374 0.676686 0.0841228 -0.67411 0.733825 0.0538484 -0.658902 0.750299 0.0371586 -0.56778 0.822342 0.030963 -0.566046 0.823792 0.0105325 -0.422555 0.906276 0.482714 -0.824865 0.294254 0.490873 -0.814338 0.309674 0.467426 -0.804108 0.36732 0.493774 -0.772554 0.399183 0.457113 -0.754033 0.471681 0.480099 -0.721261 0.499287 0.431073 -0.693333 0.577464 0.452618 -0.656492 0.603453 0.390006 -0.616999 0.683526 0.410722 -0.572833 0.709344 0.330402 -0.51783 0.789105 0.349176 -0.464162 0.814021 0.24419 -0.388117 0.888671 0.259514 -0.323567 0.909921 0.132904 -0.229201 0.964263 0.143388 -0.163044 0.976144 0.0462914 -0.0919934 0.994683 0.04289 -0.0245476 0.998778 -0.000226572 -0.873149 0.487453 0.00263205 -0.856863 0.515537 -0.00263615 -0.82318 0.567775 0.00271955 -0.78624 0.617915 0.000206979 -0.900432 0.434997 0.00454823 -0.922446 0.386099 0.000882398 -0.913448 0.406955 -0.000409843 -0.944108 0.329637 -0.00138747 -0.939653 0.342127 0.00159959 -0.957553 0.288254 0.00242147 -0.9603 0.27896 8.36567e-09 -0.998891 0.0470881 0.00146024 -0.997846 0.0655852 0.00010946 -0.997092 0.0762131 -0.000214463 -0.986785 0.162038 0.00599013 -0.991685 0.128553 -0.00284694 -0.976793 0.214168 0.00183915 -0.262849 0.964835 -0.00154968 -0.37541 0.926858 0.00265528 -0.422577 0.906323 -0.00110384 -0.488083 0.872797 0.00222413 -0.566316 0.824185 0.000862804 -0.576277 0.817254 -0.000515035 -0.649636 0.760245 -0.00251506 -0.670593 0.741822 0.00153201 -0.708532 0.705677 0.000313531 -0.726762 0.686889 -0.000540902 -0.761553 0.648103 0.00493912 -0.026854 0.999627 0.00840811 -0.0245851 0.999662 0.00245227 -0.0294695 0.999563 0.00115198 -0.0332939 0.999445 0.00052495 -0.0356828 0.999363 6.32142e-05 -0.0381244 0.999273 -0.000127481 -0.0645369 0.997915 0.00176635 -0.111202 0.993796 -0.00037719 -0.137751 0.990467 0.000465982 -0.248906 0.968528 -0.000225566 -0.0272771 0.999628 -0.000456822 -0.0215123 0.999768 -0.000980207 -0.0121511 0.999926 0 -9.75499e-05 1 -0.000203392 -0.0147784 0.999891 -0.00206353 -0.00281713 0.999994 -0.00177468 -0.00487196 0.999987 -0.925415 -0.349268 -0.147035 -0.768261 -0.632626 -0.0977659 -0.987643 -0.156702 0.00262937 -0.995406 -0.063279 -0.0718459 -0.992882 -0.115793 0.0278704 -0.998093 -0.0358497 -0.0502594 -0.998605 -0.030826 -0.0428622 -0.99449 -0.0541385 -0.0897662 -0.99651 -0.0430079 -0.0715413 -0.987331 -0.0503906 -0.15046 -0.9891 -0.0595716 -0.134656 -0.991585 -0.0568934 -0.116286 -0.982868 -0.0522921 -0.176736 -0.978863 -0.0146114 -0.203993 -0.98283 -0.0511431 -0.177283 -0.977952 -0.0662864 -0.198029 -0.980151 -0.0222725 -0.196996 -0.983775 -0.00232003 -0.179393 -0.982773 -0.018785 -0.183857 -0.988981 0.0119256 -0.147562 -0.987183 -0.0216363 -0.158121 -0.99997 0 -0.00772332 -0.999542 0.00976557 -0.0286493 -0.999007 -0.0106035 -0.0432623 -0.997939 -0.00105877 -0.0641559 -0.995053 -0.00325322 -0.0992891 -0.995768 -0.0203496 -0.089625 -0.992265 0.000900104 -0.124132 -0.985619 -0.0351565 -0.165285 -0.981742 -0.104276 -0.159089 -0.977282 -0.0643232 -0.201947 -0.965007 -0.212519 -0.153613 -0.955897 -0.223818 -0.190173 -0.969426 -0.196148 -0.14744 -0.971688 -0.18536 -0.146509 -0.978099 -0.13394 -0.15932 -0.974823 -0.14553 -0.168939 -0.975344 -0.143075 -0.168028 -0.840799 -0.463982 -0.278888 -0.842677 -0.45897 -0.281499 -0.815559 -0.533865 -0.223273 -0.882809 -0.43839 -0.168708 -0.893579 -0.389472 -0.223224 -0.731293 -0.269562 -0.626535 -0.679385 -0.304861 -0.667454 -0.729325 -0.400902 -0.554403 -0.694224 -0.715879 -0.0746301 -0.666287 -0.741604 -0.078007 -0.659486 -0.749345 -0.0596721 -0.630011 -0.77501 -0.0494595 -0.725823 -0.678877 -0.110938 -0.713896 -0.641596 -0.280548 -0.678637 -0.597143 -0.427635 -0.679477 -0.59688 -0.426668 -0.666194 -0.502695 -0.550894 -0.633244 -0.469345 -0.615401 -0.667816 -0.310913 -0.67628 -0.624295 -0.285475 -0.727159 -0.641253 -0.153107 -0.7519 -0.655579 -0.15757 -0.738504 -0.629778 -0.108295 -0.769189 -0.887605 -0.430969 -0.162552 -0.889179 -0.423621 -0.172933 -0.830114 -0.387465 -0.400976 -0.830408 -0.388877 -0.398995 -0.750636 -0.342339 -0.56511 -0.745709 -0.329721 -0.578967 -0.690208 -0.300155 -0.658422 -0.678088 -0.275068 -0.681567 -0.62201 -0.248213 -0.742627 -0.634579 -0.117789 -0.763829 -0.608332 -0.112242 -0.785706 -0.611976 -0.0350396 -0.7901 -0.631872 -0.0365734 -0.774209 -0.978197 -0.0923723 -0.186006 -0.981366 -0.10403 -0.161549 -0.883404 -0.0933545 -0.459219 -0.882435 -0.0918854 -0.461374 -0.770356 -0.0799153 -0.632586 -0.767548 -0.0764596 -0.636415 -0.686851 -0.0683488 -0.723578 -0.682607 -0.0634555 -0.728025 -0.61937 -0.0575902 -0.782984 -0.953795 -0.233213 -0.189438 -0.955685 -0.255783 -0.145742 -0.867862 -0.227548 -0.44163 -0.868025 -0.227921 -0.441119 -0.766095 -0.196966 -0.611803 -0.762025 -0.190151 -0.618999 -0.690164 -0.170013 -0.703398 -0.681728 -0.15743 -0.714467 -0.620122 -0.141702 -0.771601 -0.624944 -0.0474006 -0.779229 -0.60624 -0.0459086 -0.793956 -0.823228 -0.54481 -0.159615 -0.812077 -0.576727 -0.0889718 -0.773254 -0.53779 -0.335947 -0.773267 -0.534314 -0.341418 -0.723406 -0.48844 -0.487966 -0.718661 -0.465383 -0.516667 -0.685172 -0.437436 -0.582399 -0.671877 -0.395854 -0.626004 -0.626023 -0.361946 -0.690717 -0.649186 -0.209158 -0.731308 -0.613847 -0.195521 -0.764829 -0.623116 -0.0864953 -0.777332 -0.641496 -0.0898028 -0.761852 -0.624593 -0.0455934 -0.779618 -0.983448 -0.0132369 -0.180709 -0.98571 -0.0195367 -0.167314 -0.885369 -0.0107262 -0.464765 -0.892299 -0.0195184 -0.451022 -0.769182 -0.0079795 -0.63898 -0.776637 -0.016123 -0.629742 -0.683657 -0.00748392 -0.729765 -0.674898 0.00163418 -0.737909 -0.620262 -0.0171026 -0.784208 -0.609195 0.000527387 -0.793021 -0.606998 -0.00329664 -0.794697 -0.625075 -0.00789955 -0.780525 -0.625786 -0.00718728 -0.779962 -0.982197 -0.187788 -0.00495856 -0.967311 -0.253224 -0.0136934 -0.946069 -0.322972 0.0253607 -0.938641 -0.344596 0.0144039 -0.909071 -0.4166 0.00587845 -0.867065 -0.497015 0.0342765 -0.871361 -0.48989 0.0271764 -0.831178 -0.55373 0.050263 -0.924297 -0.379316 -0.0423571 -0.90099 -0.431101 0.0486845 -0.966001 -0.257486 -0.0233165 -0.95966 -0.280848 0.0133175 -0.99005 -0.136494 -0.0342184 -0.990177 -0.13504 -0.0362494 -0.997296 -0.036225 -0.0639387 -0.997336 -0.0365698 -0.0631113 -0.99358 -0.0474856 -0.102681 -0.986468 -0.138231 -0.0881596 -0.986549 -0.135712 -0.091126 -0.963959 -0.258073 -0.064667 -0.968005 -0.228987 -0.102619 -0.954117 -0.28697 -0.0854935 -0.953617 -0.286258 -0.0931168 -0.831319 -0.555583 0.0153905 -0.805323 -0.592548 0.0184994 -0.784756 -0.619014 0.0313105 -0.768747 -0.639356 0.0158721 -0.688818 -0.72473 0.0172132 -0.694311 -0.719051 0.0299707 -0.736228 -0.402242 -0.544216 -0.754832 -0.428012 -0.497026 -0.802265 -0.470443 -0.367498 -0.782604 -0.578675 -0.229491 -0.792049 -0.595264 -0.135348 -0.822417 -0.54216 -0.172317 -0.709843 -0.702331 0.0534193 -0.831714 -0.553653 -0.0414855 -0.78263 -0.61676 0.0842463 -0.901044 -0.433419 -0.0163791 -0.869675 -0.486779 0.0819272 -0.959101 -0.28256 -0.0168913 -0.945658 -0.321485 0.0487602 -0.990264 -0.134915 -0.0342718 -0.987622 -0.156855 -6.05452e-05 -0.997925 -0.0414867 -0.0492433 -0.99855 -0.0470099 -0.0262285 -0.664269 -0.747472 -0.0057123 -0.634642 -0.772793 0.00451104 -0.630391 -0.77616 0.013506 -0.614692 -0.788145 -0.0313182 -0.625244 -0.779639 -0.0351137 -0.659687 -0.729632 -0.180138 -0.641829 -0.74836 -0.167373 -0.628137 -0.770289 -0.109994 -0.649312 -0.750443 -0.123405 -0.630575 -0.77612 0.00354215 -0.711124 -0.701921 -0.0401097 -0.688405 -0.72445 0.0356586 -0.73624 -0.676658 0.00922361 -0.727615 -0.685985 0.00121424 -0.719222 -0.666479 -0.196278 -0.761995 -0.597547 -0.249601 -0.723497 -0.546256 -0.422085 -0.728062 -0.535242 -0.4283 -0.683523 -0.365619 -0.631759 -0.694309 -0.309284 -0.64983 -0.6595 -0.288424 -0.694169 -0.728273 -0.676883 -0.106993 -0.711355 -0.653817 -0.257872 -0.667506 -0.710743 -0.221993 -0.640694 -0.669112 -0.376562 -0.607989 -0.692035 -0.389149 -0.701111 -0.666226 -0.254137 -0.643556 -0.740054 -0.195335 -0.643332 -0.185048 -0.742887 -0.673708 -0.233671 -0.701081 -0.665467 -0.229896 -0.710142 -0.640355 -0.372629 -0.671635 -0.689346 -0.411307 -0.596346 -0.672833 -0.476152 -0.566194 -0.692352 -0.651045 -0.311111 -0.684572 -0.66396 -0.300861 -0.703237 -0.707083 -0.074106 -0.726556 -0.684865 -0.0554622 -0.76927 -0.632299 -0.091774 -0.770175 -0.637742 0.0107825 -0.873436 -0.477796 -0.0939126 -0.873107 -0.477433 -0.0986988 -0.919501 -0.377236 -0.110503 -0.923926 -0.369524 -0.0990552 -0.940132 -0.331286 -0.0800092 0.999833 0.00551865 0.0174372 0.835367 0.0329871 0.548702 0.999687 0.00138379 0.0249905 0.966127 0.0073645 0.257963 0.963953 0.00440278 0.266036 0.87994 0.0115826 0.474944 0.872752 0.00641408 0.488122 0.99974 0.00211535 0.0227149 0.999735 0.00410219 0.0226526 0.966067 0.0192628 0.257574 0.970649 0.0111568 0.240242 0.879838 0.0307457 0.474279 0.894842 0.0160038 0.446097 0.728765 0.00859765 0.684711 0.742971 0.0147585 0.669161 0.742957 0.0259644 0.668835 0.772643 0.0363077 0.633801 0.772261 0.0628316 0.632191 0.894828 0.0345944 0.445069 0.925843 0.0385061 0.375942 0.970612 0.0220941 0.239633 0.980086 0.0250296 0.196988 0.999822 0.00745649 0.0173305 0.999957 0.00826917 0.00422172 0.999728 -0.00575024 0.0226009 0.772542 -0.0483316 0.633121 0.772622 -0.0211797 0.634513 0.835242 -0.0498608 0.547618 0.925948 -0.024671 0.376845 0.894645 -0.0467974 0.44432 0.980154 -0.0170509 0.197502 0.970529 -0.0291324 0.239216 0.999971 -0.00618008 0.00435347 0.999809 -0.00925248 0.0172316 0.999839 -0.00376999 0.0175336 0.970641 -0.0181245 0.239848 0.966117 -0.0126041 0.257797 0.894862 -0.0282975 0.445444 0.879939 -0.0190002 0.474706 0.742803 -0.0402431 0.668299 0.742932 -0.00766292 0.669323 0.728704 -0.0155141 0.684653 0.879908 -0.00584278 0.475108 0.872706 -0.0120437 0.488097 0.966119 -0.00413359 0.258063 0.963935 -0.00757078 0.266031 0.999741 -0.00132579 0.0227396 0.999685 -0.00215294 0.0249905 0.996513 -0.0472536 -0.068765 0.456551 -0.87414 0.165652 0.0508119 -0.997975 0.0382605 0.12113 -0.991504 0.0474136 0.151042 -0.988117 0.0284737 0.15215 -0.987624 0.0380716 0.234204 -0.96314 0.132321 0.360439 -0.932591 0.0188934 0.451609 -0.883929 0.121319 0.42464 -0.897057 0.122349 0.335807 -0.936691 0.0992105 0.545375 -0.817648 0.184436 0.557914 -0.809802 0.181529 0.564434 -0.790179 0.238814 0.647836 -0.713352 0.267279 0.691223 -0.67955 0.24581 0.713499 -0.632155 0.302158 0.756404 -0.572124 0.31706 0.764738 -0.56207 0.315045 0.767096 -0.511407 0.387332 0.816301 -0.442303 0.371512 0.810248 -0.42787 0.400531 0.866931 -0.16441 0.470531 0.836698 -0.249683 0.487438 0.831012 -0.330267 0.447596 0.862581 -0.286513 0.416971 0.814264 -0.37955 0.439223 0.825652 -0.214163 0.52195 0.845829 -0.0914281 0.525562 0.834293 -0.0820799 0.545177 0.991477 -0.0826053 -0.100743 0.991771 -0.0795869 -0.100281 0.991977 -0.078998 -0.0986979 0.194686 -0.980436 0.0290307 0.315268 -0.948618 0.0270254 0.315708 -0.948351 0.0309673 0.376367 -0.925575 0.0407366 0.958759 -0.270453 -0.0873886 0.964673 -0.249318 -0.0851317 0.965213 -0.249026 -0.0796912 0.99205 -0.0771021 -0.0994595 0.992249 -0.0804244 -0.0947337 0.901136 -0.43063 0.0501202 0.876681 -0.478486 0.0498182 0.874167 -0.485147 0.0215525 0.849377 -0.527618 0.013363 0.845225 -0.533605 -0.0293496 0.929557 -0.344125 0.132292 0.943536 -0.308937 0.119576 0.948546 -0.268388 0.168015 0.970746 -0.202468 0.129071 0.973358 -0.167375 0.156717 0.97616 -0.155536 0.151397 0.978973 -0.0985838 0.178587 0.978888 -0.0989515 0.178847 0.980404 -0.0416907 0.192535 0.979646 -0.0448707 0.195654 0.997046 -0.0738992 -0.0209399 0.99774 -0.065636 -0.0143734 0.997987 -0.0628456 -0.00848617 0.998736 -0.0489228 -0.0115295 0.999311 -0.0370907 0.00102172 0.99954 -0.0302056 -0.00271243 0.999868 -0.0154415 0.00505936 0.999893 -0.0140792 0.00385544 0.987945 -0.154804 -0.000421102 0.990178 -0.139736 -0.00459431 0.996094 -0.0496281 -0.0730348 0.995735 -0.060492 -0.0696542 0.750573 -0.659598 -0.0396324 0.796846 -0.602956 -0.0384829 0.798199 -0.60195 -0.0231262 0.907924 -0.414599 -0.0614985 0.910301 -0.412544 -0.03406 0.970328 -0.229282 -0.0767673 0.972059 -0.227076 -0.0594782 0.975586 -0.21253 -0.0553537 0.976924 -0.209522 -0.0414769 0.980717 -0.191393 -0.0395253 0.996961 -0.043714 -0.0644828 0.998434 -0.0528813 -0.0182462 0.992419 -0.121682 0.0172369 0.976267 -0.192266 0.0996848 0.972325 -0.226008 0.0592049 0.965454 -0.251726 0.0673222 0.949586 -0.313435 0.00678416 0.93787 -0.346952 0.00494666 0.935996 -0.351647 -0.0160048 0.924575 -0.380326 -0.0226556 0.921709 -0.384281 -0.0527314 0.816891 -0.57678 0.00369753 0.813417 -0.580413 -0.0383945 0.172956 -0.983619 0.0507908 0.228135 -0.972233 0.0521223 0.257596 -0.963354 0.0747896 0.375971 -0.925883 0.0372479 0.422767 -0.904462 0.0567051 0.487377 -0.871371 0.0563681 0.492294 -0.864725 0.0994857 0.574254 -0.812094 0.103613 0.58094 -0.796747 0.166441 0.661325 -0.734108 0.15406 0.672403 -0.689083 0.270256 0.387177 -0.921954 0.00971328 0.48886 -0.872317 0.00888011 0.489353 -0.87198 0.0135941 0.537134 -0.843204 0.0222305 0.538661 -0.841692 0.0374066 0.623517 -0.780809 0.0395534 0.627207 -0.775308 0.0742293 0.690064 -0.719153 0.0814228 0.695037 -0.707114 0.130055 0.755648 -0.643286 0.123208 0.763124 -0.616496 0.193844 0.84589 -0.50815 0.16203 0.851516 -0.478511 0.214354 0.881905 -0.421922 0.210301 0.88802 -0.373807 0.267748 0.906771 -0.334759 0.256326 0.912636 -0.263632 0.3124 0.920676 -0.245929 0.303108 0.925164 -0.15546 0.34627 0.924897 -0.156046 0.34672 0.927344 -0.0654726 0.368437 0.924918 -0.070488 0.373575 0.878887 -0.472549 -0.0652281 0.901356 -0.428474 -0.0629862 0.902237 -0.427927 -0.0533638 0.96638 -0.243435 -0.0827613 0.967694 -0.242474 -0.0690943 0.992485 -0.0731975 -0.0980551 0.99287 -0.0750256 -0.0926312 0.993656 -0.0686793 -0.0890539 0.993805 -0.0703698 -0.0860207 0.580275 -0.814307 -0.0136045 0.655034 -0.755478 -0.0135769 0.655564 -0.755096 -0.00808313 0.68744 -0.726241 -0.00115105 0.688792 -0.724828 0.013775 0.745823 -0.665923 0.0171783 0.748575 -0.661461 0.0458817 0.791312 -0.608993 0.0543346 0.794831 -0.599887 0.0915382 0.83611 -0.541306 0.0889302 0.84317 -0.510944 0.167337 0.905164 -0.415035 0.0917888 0.924716 -0.371165 0.084479 0.952448 -0.302483 0.03671 0.962031 -0.27094 0.0329775 0.982603 -0.184576 -0.0205579 0.98577 -0.166671 -0.0218537 0.995037 -0.0592077 -0.0799799 0.994611 -0.0670202 -0.0791058 0 -0.999048 0.0436192 3.90824e-07 -0.999048 0.0436196 1.25082e-07 -0.999048 0.0436192 3.10962e-08 -0.999048 0.0436193 -4.23902e-07 -0.999048 0.0436198 1.35654e-06 -0.999048 0.0436186 -1.12208e-07 -0.999048 0.0436194 1.07646e-07 -0.999048 0.0436197 -6.50036e-08 -0.999048 0.0436193 7.33218e-09 -0.999048 0.0436192 -1.77292e-07 -0.999048 0.0436195 -1.83487e-06 -0.999048 0.0436202 1.85543e-07 -0.999048 0.0436194 -1.02039e-06 -0.999048 0.0436191 7.68576e-08 -0.999048 0.0436194 0.956407 0.282839 0.0727144 0.993453 0.0510956 -0.102176 0.993497 0.051454 -0.101566 0.999858 0.0164556 0.00370549 0.834315 0.187454 0.518439 0.843807 0.0880841 0.529368 0.836534 0.254616 0.485162 0.814076 0.382375 0.437115 0.80983 0.431103 0.397901 0.658609 0.752209 -0.020393 0.812228 0.581276 -0.0490302 0.796599 0.603111 -0.0410707 0.798199 0.60195 -0.0231325 0.813405 0.580429 -0.0383904 0.816878 0.576798 0.00368547 0.845211 0.533626 -0.0293603 0.851061 0.523654 0.0384917 0.901706 0.400914 0.161845 0.881778 0.422154 0.210364 0.870775 0.479423 0.109111 0.843129 0.511034 0.167266 0.831717 0.55214 0.0582018 0.0818768 0.996096 0.033013 0.126538 0.990937 0.0450695 0.313804 0.94938 0.0143178 0.315696 0.948355 0.030964 0.376344 0.925584 0.040736 0.375947 0.925893 0.0372356 0.451795 0.889452 0.0689707 0.483823 0.874658 0.0298209 0.496266 0.856261 0.143306 0.567591 0.821377 0.056399 0.5837 0.785907 0.204071 0.655115 0.746896 0.11389 0.672321 0.6892 0.270164 0.730886 0.655599 0.189726 0.746548 0.576154 0.332735 0.79008 0.551951 0.266691 0.851252 0.478885 0.214565 0.820547 0.502371 0.272629 0.806859 0.571397 0.149946 0.76473 0.605541 0.220247 0.750111 0.65556 0.0870304 0.697472 0.697365 0.164968 0.684387 0.728032 0.0397934 0.998257 0.0587994 -0.00497556 0.999885 0.0149957 0.00210694 0.980411 0.0443416 0.191908 0.979726 0.0422576 0.195834 0.927404 0.0695985 0.36753 0.925087 0.0664508 0.373896 0.840027 0.0930003 0.534514 0.835336 0.039989 0.548283 0.998139 0.0591272 -0.0148922 0.973598 0.161386 0.161433 0.975528 0.162698 0.147904 0.912819 0.25462 0.319264 0.919536 0.256447 0.297806 0.846189 0.320088 0.426038 0.833247 0.308347 0.458935 0.853465 0.200824 0.480903 0.924919 0.155807 0.346769 0.925154 0.155992 0.346059 0.978902 0.0987986 0.17886 0.978965 0.0989197 0.178446 0.99934 0.0362865 -0.00139476 0.999345 0.036183 -0.00103543 0.994062 0.0980574 -0.0471739 0.994012 0.106866 -0.0228032 0.992746 0.11101 -0.0461693 0.918665 0.387777 -0.0753955 0.901331 0.428496 -0.0632041 0.902232 0.427936 -0.0533643 0.90792 0.414606 -0.0615009 0.910296 0.412553 -0.0340731 0.921695 0.384315 -0.0527279 0.925747 0.378089 -0.00646468 0.934164 0.35533 -0.032838 0.938997 0.343286 0.0209658 0.949791 0.291113 0.11467 0.946534 0.313813 0.0748002 0.905131 0.415118 0.0917318 0.897987 0.439244 0.0261609 0.796778 0.591886 0.121723 0.786992 0.616638 0.0200142 0.630426 0.767839 0.113959 0.623462 0.780853 0.0395435 0.538633 0.841711 0.0373848 0.537107 0.843221 0.0222296 0.489344 0.871985 0.0135929 0.487996 0.872845 0.000953132 0.270991 0.962078 0.0311273 0.976121 0.195005 -0.0957078 0.964976 0.249155 -0.082122 0.965213 0.249024 -0.0796951 0.966378 0.243442 -0.08276 0.967692 0.242482 -0.0690991 0.970325 0.229292 -0.076771 0.972748 0.226056 -0.0515718 0.974673 0.214343 -0.0637969 0.977631 0.207701 -0.0331379 0.979707 0.194527 -0.0483133 0.146656 0.988679 0.0317239 0.162978 0.985499 0.0472291 0.223136 0.973329 0.0532939 0.224777 0.972652 0.0585138 0.283149 0.956741 0.0668822 0.304293 0.948262 0.0905837 0.345677 0.934142 0.0888083 0.421369 0.896627 0.136047 0.42393 0.895491 0.135571 0.528841 0.825583 0.196825 0.537627 0.820499 0.194266 0.604322 0.746335 0.278888 0.645122 0.717683 0.262201 0.668061 0.651638 0.359252 0.738685 0.592765 0.320895 0.71058 0.551585 0.436841 0.802772 0.463483 0.375154 0.816434 0.442322 0.371196 0.862433 0.40135 0.308427 0.907137 0.331995 0.258616 0.911216 0.328826 0.248109 0.968041 0.22479 0.111206 0.963823 0.226651 0.140269 0.996326 0.0798406 -0.0309985 0.996456 0.0832314 -0.0121506 0.991821 0.0841366 -0.0959838 0.991923 0.0789583 -0.0992658 0.992279 0.0773398 -0.0969618 0.992307 0.0762001 -0.0975701 0.993165 0.0739154 -0.0903367 0.993164 0.0688685 -0.0942449 0.994171 0.0722878 -0.0799939 0.994107 0.0611974 -0.0894728 0.996745 0.0754993 -0.028284 0.982599 0.184594 -0.0205906 0.953375 0.297656 0.049772 0.947592 0.319339 -0.0096009 0.878183 0.472645 0.0734902 0.871196 0.490918 -0.00425743 0.750943 0.6556 0.0792037 0.745792 0.665958 0.0171646 0.688781 0.724839 0.0137536 0.68743 0.72625 -0.00115166 0.655556 0.755104 -0.00808599 0.654515 0.755818 -0.0186779 0.472432 0.88134 0.00689654 0.994522 -2.05286e-06 -0.104531 0.99452 -1.2177e-05 -0.104543 0.994522 2.141e-07 -0.104528 0.994522 0 -0.104528 0.994522 -2.29117e-06 -0.104526 0.994522 2.35891e-06 -0.104531 0.994522 -1.23137e-07 -0.104527 0.994523 -6.79667e-06 -0.104522 0.994522 2.07064e-06 -0.104532 0.994522 3.00272e-07 -0.104529 0.994522 -2.09544e-07 -0.104528 0.994522 -9.72929e-08 -0.104528 0.994522 0 -0.104528 0.994522 -5.75115e-07 -0.104528 0.994522 -3.98872e-06 -0.104532 0.994522 -3.07448e-06 -0.104531 0.994523 9.69082e-06 -0.104516 0.994521 -8.06978e-06 -0.104539 0.994522 -6.25606e-06 -0.104524 0.994522 -3.50093e-06 -0.104526 0.994521 1.08268e-05 -0.104538 0.994522 1.28413e-06 -0.104529 0.994522 2.38024e-07 -0.104528 0.994522 3.76075e-07 -0.104526 0.994522 1.46286e-07 -0.104527 0.994522 1.15146e-06 -0.104525 0.994522 2.91439e-06 -0.104526 0.994522 4.27123e-07 -0.104528 0.994522 -5.19294e-07 -0.104529 0.994522 -1.84681e-07 -0.104529 0.994522 1.7637e-06 -0.104527 0.994521 3.36089e-06 -0.104534 0.994524 -7.22498e-06 -0.10451 0.994518 2.18324e-05 -0.104569 0.994526 -1.36331e-05 -0.104488 0.994519 9.17857e-06 -0.10456 0.994517 1.58399e-05 -0.104576 0.994522 -3.10104e-06 -0.104525 0.994522 -3.56294e-06 -0.104525 0.99452 1.35242e-05 -0.104543 0.994522 4.97103e-07 -0.10453 0.994523 -4.5114e-06 -0.104523 0.994521 4.0219e-06 -0.104533 0.994522 -4.75764e-07 -0.104529 0.994521 -1.49128e-06 -0.104532 0.994521 -1.61557e-06 -0.104533 0.994518 -1.38117e-05 -0.104569 0.994519 7.60098e-06 -0.104553 0.994526 -1.70607e-05 -0.104491 0.994521 7.28659e-06 -0.104537 0.994521 6.9769e-06 -0.104537 0.994519 1.59712e-05 -0.104551 0.994523 -7.56342e-06 -0.104518 0.994525 -1.88036e-05 -0.104499 0.994522 2.0382e-06 -0.104532 0.994521 -8.487e-06 -0.104538 0.994523 5.53583e-06 -0.104519 0.994522 -4.97476e-07 -0.104529 0.994522 2.2072e-06 -0.104526 0.994519 -1.71064e-05 -0.104558 0.994522 3.314e-06 -0.10453 7.04528e-08 0.999048 0.0436194 -3.26485e-07 0.999048 0.0436193 1.50622e-07 0.999048 0.0436194 -3.08359e-08 0.999048 0.0436195 2.80527e-08 0.999048 0.0436195 -7.40443e-07 0.999048 0.0436199 2.88609e-07 0.999048 0.0436192 1.51032e-07 0.999048 0.0436193 7.74944e-09 0.999048 0.0436195 8.13009e-08 0.999048 0.0436194 3.36743e-08 0.999048 0.0436193 2.46557e-08 0.999048 0.0436196 0 0.999048 0.0436195 -6.8081e-07 0.999048 0.0436189 9.02148e-08 0.999048 0.0436194 0.991692 0.0799944 -0.100738 0.993355 0.0511356 -0.103107 0.96293 0.254748 -0.0887126 0.976168 0.194986 -0.0952724 0.893481 0.443076 -0.0733229 0.918124 0.388005 -0.0806246 0.776482 0.627897 -0.0531159 0.811043 0.581817 -0.0608147 0.6167 0.786645 -0.0295141 0.656952 0.753022 -0.0370414 0.43204 0.901839 -0.00520806 0.470572 0.882285 -0.0116432 0.244876 0.969401 0.0172304 0.269189 0.962993 0.0134784 0.0756524 0.996492 0.0357758 0.0820746 0.996016 0.0348642 0.0508092 -0.997976 0.0382332 0.0760882 -0.996488 0.0349735 0.246613 -0.968955 0.0175599 0.193896 -0.980788 0.0214224 0.434929 -0.900449 -0.00532879 0.386054 -0.922475 -0.00122636 0.620398 -0.783712 -0.0300466 0.579005 -0.814905 -0.0261374 0.780236 -0.623155 -0.053947 0.749452 -0.660112 -0.0507371 0.896455 -0.436845 -0.0743973 0.878164 -0.472863 -0.0723057 0.964658 -0.247666 -0.0899788 0.958571 -0.270531 -0.0891896 0.991969 -0.0765122 -0.100717 0.991492 -0.0825993 -0.100603 -0.836053 0.54791 -0.0284688 -0.963148 0.225455 -0.146686 -0.991274 0.105333 -0.0792558 -0.99912 0.01666 -0.0384929 -0.998574 0.0148155 -0.0512888 -0.998463 -0.000695376 -0.0554123 -0.964989 0.24805 0.0852505 -0.975538 0.207243 -0.0733157 -0.995589 0.0910654 0.0225581 -0.905984 0.408722 0.110174 -0.915858 0.397166 0.058846 -0.944757 0.318855 -0.0759354 -0.829276 0.550658 0.095276 -0.838433 0.542138 0.0558277 -0.87532 0.476316 -0.0832955 -0.647526 0.760832 -0.0429606 -0.629645 0.773743 -0.0697744 -0.639838 0.76851 -0.000159159 -0.65352 0.756718 -0.0170281 -0.672875 0.739113 0.030841 -0.678383 0.734583 -0.0135507 -0.707095 0.706987 -0.013636 -0.712596 0.70099 -0.0286401 -0.751364 0.658295 0.0458221 -0.762603 0.643094 -0.0697666 -0.817605 0.575591 0.0147359 -0.615578 0.710917 -0.340089 -0.58674 0.723514 -0.363681 -0.599545 0.727107 -0.334456 -0.620646 0.70914 -0.334542 -0.612665 0.710955 -0.345232 -0.747394 0.545567 -0.379156 -0.730764 0.591033 -0.341563 -0.671869 0.673074 -0.309133 -0.67787 0.63443 -0.371472 -0.644862 0.69129 -0.325992 -0.74053 0.58706 -0.327071 -0.830398 0.47723 -0.287559 -0.817264 0.487588 -0.307144 -0.895577 0.347285 -0.278093 -0.894117 0.335169 -0.297012 -0.890171 0.383706 -0.245693 -0.968269 0.245223 -0.0481776 -0.969065 0.234543 -0.0768232 -0.939365 0.342902 0.00343902 -0.943456 0.329959 -0.0319075 -0.910305 0.412678 -0.032269 -0.785272 0.610034 0.105861 -0.803103 0.590342 -0.0807647 -0.732043 0.681211 0.0080496 -0.721224 0.691192 -0.0457058 -0.676124 0.736723 -0.00982753 -0.678009 0.735049 -0.00250357 -0.636368 0.7702 -0.0427532 -0.63066 0.775998 0.00978159 -0.648907 0.75969 -0.0423229 -0.876988 0.447942 -0.173895 -0.889298 0.45651 -0.0273505 -0.853369 0.481336 0.200192 -0.941187 0.290506 -0.172551 -0.935849 0.320387 -0.14676 -0.972924 0.176008 -0.149803 -0.966921 0.231117 -0.107932 -0.985467 0.132798 -0.105925 -0.988816 0.149004 -0.00640921 -0.991519 0.119452 -0.0511916 -0.636335 0.75084 -0.176965 -0.624823 0.766715 -0.147456 -0.630074 0.76233 -0.147849 -0.627603 0.768567 -0.124177 -0.666091 0.735153 -0.125988 -0.665734 0.735666 -0.124877 -0.716676 0.685907 -0.126125 -0.720334 0.679489 -0.139329 -0.787481 0.600556 -0.138587 -0.79322 0.585507 -0.16728 -0.84954 0.501247 -0.16442 -0.88122 0.395503 -0.258898 -0.606892 0.753662 -0.252341 -0.611814 0.745672 -0.263926 -0.613422 0.744273 -0.264142 -0.612764 0.752154 -0.242454 -0.643485 0.724988 -0.245598 -0.643996 0.723834 -0.247654 -0.686535 0.682472 -0.250804 -0.689819 0.673252 -0.266237 -0.755658 0.59742 -0.26846 -0.758081 0.586962 -0.284232 -0.831006 0.477742 -0.28494 -0.827427 0.488893 -0.276311 -0.895973 0.347692 -0.276302 -0.885434 0.398541 -0.239108 -0.938448 0.245959 -0.242527 -0.933916 0.281975 -0.219751 -0.967923 0.170136 -0.184876 -0.967546 0.167878 -0.188867 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.93227 -0.317642 -0.173137 -0.645997 -0.758553 -0.0853599 -0.714785 -0.693455 -0.0905687 -0.748735 -0.656085 0.0945992 -0.7573 -0.650498 0.0578743 -0.797891 -0.595356 -0.0944486 -0.829267 -0.550762 0.0947484 -0.842097 -0.537468 0.0447185 -0.963686 -0.223531 0.146096 -0.945492 -0.315237 -0.0816689 -0.908416 -0.409919 0.082144 -0.905978 -0.387027 0.171508 -0.877054 -0.47137 -0.0926634 -0.968127 -0.248953 0.0274433 -0.989222 -0.105188 -0.10186 -0.99259 -0.120992 0.0112429 -0.996219 -0.0166267 -0.0852721 -0.998259 -0.0202502 -0.0554009 -0.729159 -0.682335 -0.0524125 -0.677962 -0.735011 -0.0112577 -0.676353 -0.736562 -0.00482039 -0.648894 -0.7597 -0.042348 -0.638555 -0.769481 -0.0120735 -0.630147 -0.775304 -0.0426346 -0.633989 -0.772162 -0.042708 -0.639828 -0.768518 -0.0002657 -0.665876 -0.745352 -0.0325619 -0.672897 -0.739165 0.0290568 -0.706561 -0.706478 -0.040751 -0.870749 -0.490942 -0.0277993 -0.836015 -0.547967 -0.0284685 -0.806232 -0.58889 0.0565546 -0.788341 -0.612243 -0.0606463 -0.721753 -0.691877 0.0194731 -0.97025 -0.237896 -0.0449485 -0.967048 -0.24497 -0.0693417 -0.943394 -0.331635 -0.00518147 -0.938889 -0.342734 -0.0319466 -0.910268 -0.412762 -0.0322384 -0.967531 -0.167917 -0.188913 -0.968037 -0.170972 -0.183503 -0.830914 -0.477803 -0.285108 -0.895939 -0.364099 -0.254411 -0.89502 -0.346919 -0.280332 -0.734087 -0.582645 -0.348771 -0.776511 -0.548348 -0.310396 -0.832606 -0.470714 -0.291884 -0.597849 -0.718839 -0.354751 -0.594062 -0.720457 -0.357815 -0.595379 -0.730548 -0.334401 -0.615185 -0.713879 -0.334549 -0.618486 -0.707546 -0.341838 -0.64486 -0.691289 -0.325998 -0.660689 -0.665444 -0.347382 -0.692966 -0.645731 -0.32067 -0.730752 -0.591027 -0.341598 -0.884064 -0.455899 0.102898 -0.869446 -0.443487 -0.217676 -0.896527 -0.407367 -0.174043 -0.991517 -0.119422 -0.0513111 -0.988809 -0.149048 -0.00637601 -0.985457 -0.132833 -0.105969 -0.966902 -0.231213 -0.107893 -0.97291 -0.176047 -0.149845 -0.94408 -0.294835 -0.147598 -0.933191 -0.281379 -0.223563 -0.610097 -0.772583 -0.175777 -0.636234 -0.757106 -0.148312 -0.624301 -0.767147 -0.147425 -0.633414 -0.763737 -0.124465 -0.665573 -0.735626 -0.125964 -0.666229 -0.735216 -0.124881 -0.722009 -0.680275 -0.126211 -0.714766 -0.685347 -0.139317 -0.797183 -0.587677 -0.138331 -0.783035 -0.598977 -0.167578 -0.849502 -0.501314 -0.164409 -0.613307 -0.740845 -0.273869 -0.625023 -0.734004 -0.265677 -0.60808 -0.748897 -0.263424 -0.618127 -0.747566 -0.24303 -0.644423 -0.724122 -0.245696 -0.643035 -0.724716 -0.247571 -0.693407 -0.675326 -0.25124 -0.682992 -0.680322 -0.265863 -0.762107 -0.589141 -0.268525 -0.751917 -0.594962 -0.283973 -0.825156 -0.4877 -0.285071 -0.832856 -0.479448 -0.276552 -0.87696 -0.39266 -0.277055 -0.903078 -0.355627 -0.24079 -0.937961 -0.247766 -0.242572 -0.962352 -0.229599 -0.145478 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.780798 0.432706 0.450688 -0.705514 0.705416 0.0681055 -0.675922 -0.00345049 0.736966 -0.892282 0.0137803 0.451269 -0.955225 0.28412 0.0825966 -0.994676 0.0416093 0.0942826 -0.99779 0.029803 0.0593804 -0.991929 0.119506 -0.0423693 -0.985748 0.0159536 0.167469 -0.778381 0.416773 0.469493 -0.841625 0.525129 0.126126 -0.906498 0.400357 0.134072 -0.888039 0.458753 0.0305305 -0.932044 0.356715 0.0636252 -0.931477 0.358373 0.0625973 -0.675038 0.349966 0.649497 -0.810417 0.37999 0.445905 -0.767997 0.405375 0.495835 -0.976798 0.0994697 0.189663 -0.995786 0.0464499 0.0790705 -0.977347 0.0718918 0.199058 -0.984982 0.0509818 0.164957 -0.977388 0.0456058 0.206476 -0.977816 0.0457546 0.204409 -0.982491 0.0390999 0.182162 -0.999717 0 0.023811 -0.999559 -0.00765709 0.0286747 -0.998138 0.00390893 0.0608716 -0.996344 -0.00846791 0.0850081 -0.994872 0.0119233 0.100435 -0.99174 -0.00101281 0.128257 -0.989182 0.0145043 0.145972 -0.987061 -0.0007894 0.160344 -0.984006 0.0129329 0.177665 -0.983892 0.0120534 0.178358 -0.980644 0.00205466 0.195791 -0.981841 0.0258216 0.18794 -0.978741 0.0264725 0.203387 -0.978397 0.0264011 0.205041 -0.965412 0.212667 0.150839 -0.956171 0.211347 0.202654 -0.966298 0.208506 0.150976 -0.972244 0.196235 0.127413 -0.989038 0.0484107 0.139499 -0.988528 0.0515692 0.141958 -0.98546 0.105568 0.133132 -0.981167 0.124948 0.147307 -0.97498 0.182848 0.126411 -0.974604 0.185223 0.125858 -0.630536 0.775861 0.0215349 -0.64937 0.760286 -0.016826 -0.647153 0.762035 -0.0222932 -0.646735 0.761922 -0.0347688 -0.668179 0.737284 0.0997418 -0.665074 0.730752 0.153877 -0.888453 0.457347 0.0385325 -0.86607 0.436049 0.244509 -0.84906 0.482916 0.214218 -0.768169 0.518495 0.375607 -0.748744 0.53646 0.38935 -0.678005 0.73504 -0.00503706 -0.686025 0.727478 -0.012051 -0.721838 0.691828 -0.0179923 -0.728699 0.684255 -0.0281678 -0.789504 0.613121 -0.0276712 -0.801131 0.596936 -0.0430848 -0.83602 0.547886 -0.0298509 -0.884584 0.465272 -0.0321392 -0.869489 0.490106 -0.0615191 -0.998946 0.0371673 0.0269405 -0.993581 0.10807 0.0334454 -0.9905 0.137479 0.00311239 -0.969333 0.245562 0.00966795 -0.953967 0.298327 -0.0307814 -0.939266 0.342823 -0.0158669 -0.910605 0.412834 -0.0191695 -0.99622 0.0421001 0.0759893 -0.997929 0.0317969 0.0559231 -0.992328 0.122042 0.0197514 -0.993135 0.115884 0.0159413 -0.970777 0.237062 -0.0373261 -0.965916 0.25778 -0.0235719 -0.931176 0.356819 -0.0747765 -0.912205 0.407949 -0.0381944 -0.884921 0.460274 -0.0711471 -0.846897 0.531512 -0.0161568 -0.84354 0.536692 -0.0200771 -0.787847 0.614296 0.0440328 -0.810851 0.580718 0.0727114 -0.742538 0.655763 0.136423 -0.784756 0.588034 0.195895 -0.992197 0.0544114 0.112184 -0.994813 0.0426387 0.0923482 -0.989651 0.125789 0.0690484 -0.989915 0.124309 0.0679431 -0.975558 0.216544 0.0373547 -0.969014 0.240483 0.0563834 -0.954913 0.294984 0.0335455 -0.942797 0.33134 0.0367102 -0.98593 0.0164409 0.16635 -0.980329 0.102524 0.168652 -0.980734 0.104212 0.16523 -0.955439 0.250787 0.155701 -0.955108 0.245515 0.165804 -0.898908 0.419701 0.125762 -0.900884 0.406422 0.152412 -0.81928 0.565015 0.0976652 -0.825439 0.548107 0.135019 -0.892284 0.0137829 0.451264 -0.889627 0.0916403 0.447399 -0.890154 0.0923938 0.446195 -0.875764 0.226212 0.426456 -0.875195 0.224988 0.42827 -0.83971 0.384608 0.38336 -0.839239 0.382575 0.386412 -0.78499 0.527505 0.324852 -0.785024 0.530837 0.319296 -0.748445 0.655736 0.0992026 -0.741019 0.668252 0.0658058 -0.72559 0.645508 0.238409 -0.728143 0.63309 0.262687 -0.696058 0.592015 0.406229 -0.738603 0.484674 0.468568 -0.733274 0.461231 0.499576 -0.762959 0.339809 0.549931 -0.757727 0.327419 0.564489 -0.776292 0.19574 0.599213 -0.772268 0.189442 0.606394 -0.779627 0.0794592 0.621183 -0.777053 0.0764836 0.624771 -0.778414 0.012303 0.62763 -0.777644 0.011569 0.628598 -0.691361 0.0105058 0.722433 -0.690578 0.063212 0.72049 -0.694902 0.0678901 0.715893 -0.690725 0.156379 0.706007 -0.69973 0.168912 0.694152 -0.68943 0.272674 0.67107 -0.702724 0.298112 0.645994 -0.686644 0.392055 0.612219 -0.701614 0.434787 0.564533 -0.684698 0.497893 0.532252 -0.699507 0.590944 0.40184 -0.623691 0.0187649 0.781446 -0.623316 0.0460569 0.780613 -0.628747 0.0572521 0.775499 -0.626843 0.112809 0.770936 -0.639041 0.14308 0.755748 -0.635222 0.196921 0.746803 -0.653579 0.255516 0.712423 -0.649698 0.288238 0.703428 -0.670015 0.379728 0.637876 -0.670444 0.377345 0.638839 -0.685642 0.498869 0.530118 -0.667215 0.556288 0.495347 -0.697206 0.595938 0.398449 -0.675061 0.685895 0.271735 -0.683767 0.701119 0.202225 -0.675534 0.720338 0.157375 -0.680262 0.729844 0.067612 -0.67252 0.738725 0.0447445 -0.639618 0.76824 0.0263937 -0.645543 0.762519 0.0428884 -0.644759 0.759759 0.0839749 -0.659413 0.737623 0.145213 -0.659257 0.737228 0.147903 -0.700493 0.645826 0.303675 -0.686349 0.622842 0.375491 -0.73443 0.494596 0.464745 -0.679938 0.44096 0.585865 -0.690974 0.393259 0.60655 -0.666889 0.278462 0.691172 -0.664398 0.296645 0.685987 -0.640221 0.208704 0.739296 -0.641132 0.199158 0.741138 -0.621296 0.140937 0.770797 -0.623022 0.112011 0.774143 -0.610364 0.0809843 0.787971 -0.611448 0.045104 0.789998 -0.605887 0.0333323 0.794852 -0.606124 -0.00565923 0.79535 -0.609245 0.00450304 0.79297 -0.624685 0.00692628 0.780846 -0.624702 0.0069089 0.780833 -0.630768 0.0351056 0.775177 -0.624259 0.0437804 0.77999 -0.641371 0.0862468 0.762368 -0.631759 0.10358 0.768213 -0.657456 0.151592 0.738086 -0.648105 0.176571 0.740799 -0.679194 0.225573 0.698435 -0.674278 0.252462 0.693983 -0.706134 0.30085 0.640987 -0.701075 0.345154 0.623989 -0.742968 0.374534 0.554728 -0.712095 0.500662 0.492196 -0.760243 0.558094 0.33251 -0.710238 0.657544 0.251392 -0.720234 0.693214 0.0267746 -0.743968 0.668182 0.0067104 -0.729178 0.684297 -0.00605806 -0.785064 0.61668 -0.0581483 -0.801099 0.596894 -0.0442476 -0.843572 0.52925 -0.0909958 -0.884266 0.464246 -0.0504936 -0.910259 0.404817 -0.0869039 -0.954007 0.298634 -0.0262405 -0.965473 0.255741 -0.049583 -0.9903 0.13817 0.0146593 -0.993368 0.114931 0.00325319 -0.998262 0.0384532 0.0446556 -0.998819 0.0235511 0.0424959 0.0175689 0.0861613 -0.996126 -0.01002 0.0568957 -0.99833 0.0092845 0.0188776 -0.999779 0 0.00711248 -0.999975 -0.708391 -0.66056 0.248682 -0.762146 -0.553389 0.335997 -0.97709 -0.099113 0.188341 -0.999579 0 0.0290096 -0.999566 -0.000754684 0.0294531 -0.997887 -0.0011858 0.0649681 -0.997825 -0.00163908 0.0659034 -0.995719 -0.00162565 0.0924134 -0.995618 -0.00303855 0.0934695 -0.991709 -0.00362566 0.128455 -0.991604 -0.00463145 0.129226 -0.985868 -0.00549504 0.167435 -0.986156 -0.0116249 0.165411 -0.980856 -0.00551566 0.194655 -0.981841 -0.0258216 0.18794 -0.982991 -0.0255643 0.181865 -0.977533 -0.097971 0.186633 -0.978035 -0.0454693 0.203422 -0.977915 -0.0456723 0.203954 -0.985194 -0.0457093 0.16524 -0.994813 -0.0426387 0.0923482 -0.992197 -0.0544114 0.112184 -0.988943 -0.0518606 0.138935 -0.998946 -0.0371675 0.0269421 -0.99873 -0.0376435 0.0334814 -0.998343 -0.0266923 0.0509786 -0.99779 -0.029803 0.0593804 -0.997929 -0.0317969 0.0559231 -0.996219 -0.0421001 0.0759894 -0.994676 -0.0416094 0.0942825 -0.624697 -0.00351505 0.78086 -0.627486 -0.00736967 0.778593 -0.625094 -0.0274969 0.780065 -0.631667 -0.0351699 0.774442 -0.63109 -0.0567416 0.773631 -0.635028 -0.0705993 0.769256 -0.642101 -0.0863711 0.761739 -0.615822 -0.139332 0.775468 -0.668632 -0.113318 0.734909 -0.639856 -0.208547 0.739657 -0.682791 -0.189633 0.705574 -0.671909 -0.2813 0.685134 -0.702945 -0.269448 0.65823 -0.777687 -0.416205 0.471143 -0.843506 -0.528444 0.0961507 -0.882782 -0.453153 0.12389 -0.919294 -0.391335 0.0419122 -0.946077 -0.322254 0.033025 -0.95693 -0.288015 0.0364982 -0.956957 -0.287797 0.0375003 -0.973128 -0.19268 0.126079 -0.967026 -0.209344 0.145036 -0.977758 -0.070872 0.1974 -0.985589 -0.0490953 0.161875 -0.988614 -0.0485022 0.142446 -0.98592 -0.0999281 0.134075 -0.976502 -0.143543 0.160744 -0.649358 -0.760297 -0.0168311 -0.677991 -0.735053 -0.00504286 -0.669089 -0.740161 0.0669516 -0.841462 -0.527868 -0.115313 -0.887925 -0.458492 0.0370672 -0.783123 -0.616279 -0.083175 -0.842315 -0.52625 0.116478 -0.795539 -0.591439 -0.131594 -0.846991 -0.531608 -0.000428593 -0.724156 -0.681426 -0.106099 -0.7878 -0.614115 0.0472626 -0.743968 -0.668182 0.0067104 -0.743436 -0.668781 -0.00583487 -0.86945 -0.490168 -0.0615738 -0.910567 -0.412917 -0.0191974 -0.963605 -0.24405 -0.109112 -0.992583 -0.119638 0.0215725 -0.998624 -0.0445815 0.0276281 -0.884584 -0.465274 -0.0321092 -0.880432 -0.459028 -0.118879 -0.912374 -0.408989 -0.0173819 -0.909389 -0.403836 -0.0996346 -0.933526 -0.358422 -0.00787958 -0.931658 -0.358412 0.0596157 -0.936274 -0.343913 0.0715236 -0.986068 -0.142059 0.086539 -0.990567 -0.136756 -0.00865398 -0.992827 -0.116644 0.0262429 -0.992965 -0.116337 0.0220573 -0.992474 -0.121722 0.0134026 -0.989802 -0.124375 0.0694512 -0.98976 -0.125798 0.0674575 -0.982284 -0.125066 0.139555 -0.974785 -0.184081 0.126127 -0.958917 -0.210663 0.19 -0.974165 -0.215817 0.0665315 -0.970395 -0.239716 0.0295014 -0.971139 -0.238127 -0.0135851 -0.965579 -0.25605 -0.0457846 -0.96582 -0.259176 -0.00429364 -0.952723 -0.295289 -0.0715813 -0.954014 -0.299443 -0.0137907 -0.9374 -0.342116 -0.0650958 -0.889579 -0.0923307 0.447352 -0.690432 -0.0674245 0.720248 -0.696058 -0.592015 0.406229 -0.743292 -0.469809 0.476232 -0.728591 -0.47593 0.492591 -0.764515 -0.331097 0.553075 -0.755996 -0.335899 0.56182 -0.776705 -0.190711 0.600299 -0.771709 -0.194371 0.605546 -0.779686 -0.0767603 0.621448 -0.776926 -0.0791633 0.624595 -0.629444 -0.774411 -0.0639377 -0.647802 -0.761185 0.030829 -0.639609 -0.768247 0.0263956 -0.645543 -0.762518 0.0429018 -0.672508 -0.738739 0.0446968 -0.680263 -0.729844 0.0676048 -0.705498 -0.705431 0.0681105 -0.740102 -0.666045 0.0929166 -0.750116 -0.657297 0.0727076 -0.817157 -0.562147 0.127457 -0.828561 -0.550292 0.103276 -0.896327 -0.417691 0.148769 -0.903903 -0.407883 0.128808 -0.95406 -0.250272 0.16472 -0.956609 -0.245999 0.156151 -0.980903 -0.102593 0.165238 -0.980132 -0.10422 0.168757 -0.890185 -0.0917029 0.446275 -0.875935 -0.225211 0.426636 -0.875054 -0.225987 0.428032 -0.840173 -0.383104 0.383851 -0.838817 -0.38406 0.385855 -0.783883 -0.529836 0.323731 -0.78608 -0.528587 0.32043 -0.722461 -0.641708 0.257412 -0.731099 -0.637391 0.243366 -0.672138 -0.714949 0.192559 -0.686875 -0.707544 0.166085 -0.642404 -0.754801 0.13264 -0.661415 -0.743962 0.0951405 -0.646569 -0.758085 0.0851773 -0.667883 -0.74392 -0.022706 -0.68602 -0.727483 -0.012054 -0.728937 -0.684312 -0.0191763 -0.721643 -0.691689 -0.0282275 -0.801461 -0.597415 -0.0275028 -0.788895 -0.612693 -0.0474579 -0.835983 -0.547943 -0.0298566 -0.698047 -0.597115 0.395201 -0.727461 -0.51791 0.450078 -0.746976 -0.541065 0.386361 -0.748744 -0.53646 0.38935 -0.825598 -0.458059 0.3295 -0.694963 -0.0636357 0.716224 -0.689919 -0.166163 0.704558 -0.700298 -0.158855 0.69595 -0.686925 -0.289828 0.666434 -0.704939 -0.280159 0.651591 -0.680834 -0.417855 0.60155 -0.707573 -0.407766 0.57712 -0.644939 -0.605097 0.466811 -0.721739 -0.537447 0.436169 -0.661141 -0.664584 0.348168 -0.7144 -0.621235 0.322024 -0.650568 -0.719671 0.242559 -0.712899 -0.670472 0.205529 -0.715137 -0.667296 0.208074 -0.720938 -0.684378 0.108969 -0.800213 -0.557762 0.220364 -0.807367 -0.569926 0.152784 -0.867593 -0.431328 0.247463 -0.877283 -0.450746 -0.164929 -0.730977 -0.343908 0.589406 -0.709655 -0.351085 0.610842 -0.700057 -0.344452 0.625518 -0.706378 -0.30099 0.640653 -0.652891 -0.363919 0.664301 -0.672947 -0.222852 0.705323 -0.631688 -0.278001 0.723662 -0.64496 -0.147898 0.749768 -0.617122 -0.190092 0.763561 -0.624207 -0.0833292 0.776802 -0.608959 -0.10908 0.785665 -0.611627 -0.0337405 0.790427 -0.605645 -0.0446384 0.794482 -0.606151 -0.00402185 0.795339 -0.60925 0.0013806 0.792977 -0.98574 -0.0164529 0.167468 -0.985947 -0.0159594 0.166297 -0.892282 -0.0137829 0.451269 -0.892284 -0.0137803 0.451264 -0.777638 -0.0122926 0.628593 -0.778411 -0.0115782 0.627648 -0.67589 -0.010312 0.736931 -0.691143 0.0102181 0.722646 -0.623691 -0.0187649 0.781446 -0.623043 -0.0567034 0.78013 -0.62889 -0.0465048 0.776102 -0.625222 -0.139543 0.76787 -0.640247 -0.11561 0.75942 -0.630213 -0.244429 0.736944 -0.657992 -0.205555 0.724426 -0.638878 -0.356956 0.681482 -0.681005 -0.306206 0.665184 -0.651429 -0.464231 0.600109 -0.707423 -0.406201 0.578405 -0.696639 -0.456926 0.553094 -0.718763 -0.478667 0.504239 -0.738454 -0.398297 0.544101 -0.750216 -0.407629 0.52059 -0.767057 -0.402294 0.499784 0 -0.0115116 -0.999934 0.0343912 -0.0733997 -0.996709 -0.0055448 -0.052837 -0.998588 0.00577579 -0.000941671 -0.999983 0 0.0188784 -0.999822 0.00110492 0.0237141 -0.999718 -0.00113444 0.0963041 -0.995351 5.84661e-05 0.0861746 -0.99628 -5.58593e-05 0.15324 -0.988189 0.0011198 0.141455 -0.989944 -0.00101671 0.207162 -0.978306 0.00372871 0.255923 -0.96669 -0.00162829 0.300789 -0.953689 0.00103094 0.36103 -0.932553 0.0036396 0.39253 -0.919732 -0.00138907 0.423436 -0.905925 0.00166305 0.510565 -0.859837 -0.000278669 0.519391 -0.854537 4.80255e-05 0.574976 -0.81817 0.00457445 0.634979 -0.772516 -0.00643322 0.608145 -0.7938 0.00439666 0.702856 -0.711318 0.000713288 0.691853 -0.722038 -0.000226189 0.734437 -0.678677 0.00321711 0.779642 -0.626218 -0.00367707 0.766742 -0.641945 0.00351953 0.842439 -0.53878 -0.0025681 0.832567 -0.553919 0.00192582 0.89126 -0.453489 -0.000709136 0.895715 -0.444628 0.000313451 0.927633 -0.373492 -3.8798e-06 0.928633 -0.370999 1.60912e-06 0.94769 -0.319193 -0.000470916 0.948739 -0.31606 0.000437325 0.965459 -0.260557 -0.000956499 0.968328 -0.249678 0.000760341 0.979428 -0.201791 -0.00366871 0.987608 -0.156899 0.00417524 0.993606 -0.112823 -0.0034385 0.998928 -0.0461557 0.0040188 0.99999 -0.00204789 -0.0014947 0.999578 0.0290096 0 0.999143 0.041392 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.999587 0.0287344 -0.000492008 -0.999537 0.0304398 0.000831943 -0.9989 -0.0468789 -5.89957e-05 -0.999041 -0.0437838 0.000109763 -0.987527 -0.157449 0.000221647 -0.98746 -0.157866 -0.000113344 -0.968303 -0.249777 0.00439349 -0.960586 -0.277949 -0.000839316 -0.94875 -0.316025 0.000949083 -0.928603 -0.371074 0.00382874 -0.921209 -0.389049 -0.00392338 -0.895804 -0.444433 0.0130277 -0.842124 -0.539127 -0.0119845 -0.872632 -0.488231 0.0117095 -0.779358 -0.62647 -0.010143 -0.811086 -0.584839 0.00439885 -0.734235 -0.678881 0.00386907 -0.736188 -0.676766 -0.00105974 -0.703018 -0.711171 0.00336097 -0.635015 -0.772493 0.00782677 -0.219265 -0.975634 -0.00425613 -0.173361 -0.984849 0.000976208 -0.273237 -0.961946 -0.00180699 -0.321304 -0.946974 0.000409603 -0.342539 -0.939504 -0.000536347 -0.418665 -0.908141 -0.000738474 -0.417559 -0.90865 0.000961204 -0.516559 -0.856251 -0.00883451 -0.478549 -0.878016 0.00742294 -0.574787 -0.818269 0.00226597 -0.553407 -0.832908 -0.00320384 -0.651634 -0.758527 0 -0.0115116 -0.999934 0.000413972 -0.146394 -0.989226 -0.00058152 -0.0734431 -0.997299 0.00238825 -0.0540667 -0.998535 -0.00140125 -0.00361611 -0.999993 0.0785787 0 -0.996908 0.0785787 0 -0.996908 0.245699 0 -0.969346 0.245699 0 -0.969346 0.420648 0 -0.907224 0.420648 0 -0.907224 0.590722 0 -0.806875 0.590722 0 -0.806875 0.740709 0 -0.671826 0.740709 0 -0.671826 0.858286 0 -0.513172 0.858286 0 -0.513172 0.938353 0 -0.34568 0.938353 0 -0.34568 0.983232 0 -0.182358 0.983232 0 -0.182358 0.0785787 0 -0.996908 0.0785787 0 -0.996908 0.245699 0 -0.969346 0.245699 0 -0.969346 0.420648 0 -0.907224 0.420648 0 -0.907224 0.590722 0 -0.806875 0.590722 0 -0.806875 0.740709 0 -0.671826 0.740709 0 -0.671826 0.858286 0 -0.513172 0.858286 0 -0.513172 0.938353 0 -0.345679 0.938353 0 -0.345679 0.983232 0 -0.182358 0.983232 0 -0.182358 0.0748664 -0.996919 0.0233997 0.983228 -0.00285549 -0.182358 0.0785782 -0.00357749 -0.996902 0.949309 -0.21675 -0.227665 0.991751 -0.0766017 -0.102768 0.99137 -0.0795275 -0.104217 0.990502 -0.0793623 -0.112285 0.990954 -0.0768059 -0.110052 0.989443 -0.0798829 -0.120915 0.98988 -0.0782088 -0.118408 0.989062 -0.0763288 -0.126214 0.878195 -0.400293 -0.261798 0.952801 -0.231309 -0.196638 0.957388 -0.224291 -0.181942 0.988604 -0.0750887 -0.130475 0.987314 -0.0809711 -0.136581 0.879419 -0.39911 -0.259486 0.873083 -0.37364 -0.31324 0.949807 -0.215862 -0.226429 0.945923 -0.190355 -0.262668 0.895088 -0.437357 -0.086808 0.893896 -0.439596 -0.0877838 0.889093 -0.438235 -0.132153 0.890309 -0.436333 -0.13024 0.885087 -0.430303 -0.177372 0.88654 -0.428297 -0.174954 0.964043 -0.247913 -0.0957085 0.96246 -0.253085 -0.0980757 0.959858 -0.252354 -0.122432 0.960141 -0.251648 -0.121667 0.957238 -0.248255 -0.14854 0.957603 -0.247464 -0.147507 0.954809 -0.241192 -0.173686 0.881383 -0.416932 -0.22211 0.882771 -0.415299 -0.219643 0.432236 -0.901268 -0.0298079 0.2557 -0.966652 -0.0141617 0.246005 -0.963246 -0.107888 0.255446 -0.961434 -0.101946 0.244512 -0.947176 -0.207538 0.255144 -0.945782 -0.200991 0.244208 -0.919663 -0.307544 0.254156 -0.919032 -0.301305 0.244352 -0.884707 -0.39697 0.253063 -0.884773 -0.391326 0.245031 -0.847868 -0.470192 0.590392 -0.158024 -0.791496 0.587875 -0.156863 -0.793597 0.592828 -0.298396 -0.748007 0.58875 -0.297266 -0.751669 0.596059 -0.410998 -0.689778 0.591714 -0.410279 -0.693935 0.598578 -0.490376 -0.633432 0.594448 -0.490048 -0.637562 0.60072 -0.549431 -0.580742 0.596763 -0.549467 -0.584774 0.60289 -0.597696 -0.528473 0.598861 -0.598092 -0.532589 0.606661 -0.654361 -0.451414 0.245874 -0.201156 -0.948199 0.241892 -0.199436 -0.949586 0.0724615 -0.172195 -0.982394 0.120953 -0.207733 -0.970679 0.0774575 -0.271403 -0.959344 0.0797137 -0.340153 -0.936985 0.244068 -0.75151 -0.612914 0.250986 -0.752802 -0.608519 0.243556 -0.691638 -0.67994 0.250415 -0.693263 -0.67578 0.242877 -0.618039 -0.747689 0.249985 -0.62003 -0.743687 0.241839 -0.518424 -0.820214 0.249339 -0.520748 -0.816487 0.240821 -0.376353 -0.894631 0.247824 -0.378768 -0.891694 0.100456 -0.392616 -0.9142 0.138263 -0.410748 -0.901205 0.420411 -0.183545 -0.888575 0.417031 -0.182101 -0.890463 0.422585 -0.346081 -0.837646 0.41685 -0.344371 -0.841216 0.424991 -0.476376 -0.769707 0.418858 -0.474967 -0.773928 0.426562 -0.567946 -0.703905 0.420742 -0.566924 -0.708219 0.427818 -0.635835 -0.642407 0.422194 -0.635195 -0.646745 0.429137 -0.691229 -0.581416 0.423454 -0.690958 -0.585887 0.43243 -0.755664 -0.491911 0.598989 -0.661701 -0.450959 0.609873 -0.706694 -0.358662 0.604792 -0.708612 -0.36345 0.612893 -0.735876 -0.287835 0.607085 -0.738667 -0.292947 0.616214 -0.759508 -0.208391 0.610012 -0.76309 -0.213492 0.619282 -0.774487 -0.129072 0.613864 -0.778068 -0.133348 0.62227 -0.780847 -0.0553091 0.938313 -0.00920927 -0.345665 0.983185 -0.0029811 -0.182591 0.983357 -0.0167803 -0.180906 0.983389 -0.0168855 -0.180724 0.983811 -0.0320569 -0.17632 0.984044 -0.0325591 -0.174923 0.984437 -0.044062 -0.170126 0.984812 -0.0445938 -0.1678 0.985063 -0.0523756 -0.164037 0.985635 -0.0529846 -0.160362 0.985599 -0.0644792 -0.156324 0.740507 -0.0233398 -0.671643 0.857562 -0.0167504 -0.514108 0.858382 -0.0894202 -0.505159 0.857611 -0.0887823 -0.506578 0.860512 -0.16939 -0.480444 0.85947 -0.16893 -0.482466 0.863625 -0.233041 -0.44704 0.862526 -0.232853 -0.449253 0.866421 -0.277789 -0.414907 0.865382 -0.277825 -0.417047 0.86894 -0.311068 -0.384942 0.881079 -0.308071 -0.358875 0.870577 -0.339367 -0.356267 0.875064 -0.371435 -0.31032 0.858173 -0.0162176 -0.513104 0.938065 -0.00955571 -0.346327 0.938576 -0.0522206 -0.341099 0.938324 -0.0518539 -0.341848 0.939991 -0.0991464 -0.326476 0.939715 -0.0989159 -0.32734 0.942031 -0.136143 -0.306664 0.941738 -0.136035 -0.307611 0.943922 -0.161998 -0.287693 0.943646 -0.161992 -0.288602 0.946285 -0.189044 -0.262311 0.98596 -0.0609013 -0.155479 0.987283 -0.0683754 -0.143516 0.986542 -0.0709304 -0.147322 0.987729 -0.0710643 -0.139074 0.243916 -0.969768 -0.00742727 0.0994389 -0.995037 0.00377687 0.0271112 -0.995846 -0.0869253 0.11322 -0.992218 -0.0518173 0.0437077 -0.980505 -0.191572 0.103707 -0.981032 -0.163772 0.0560271 -0.953362 -0.296585 0.0854185 -0.955604 -0.282002 0.0733874 -0.917485 -0.390942 0.0714142 -0.91715 -0.392091 0.0844849 -0.877057 -0.472898 0.0580812 -0.869064 -0.491279 0.617909 -0.784505 -0.0523536 0.440668 -0.896993 -0.034856 0.431361 -0.89374 -0.123113 0.439122 -0.890658 -0.117901 0.428752 -0.877385 -0.215328 0.43753 -0.874492 -0.209356 0.427254 -0.850319 -0.307266 0.435473 -0.848246 -0.301401 0.426311 -0.816613 -0.389105 0.433497 -0.815392 -0.383687 0.421396 -0.76301 -0.490144 0.303466 -0.807239 -0.506235 0.251428 -0.801966 -0.54188 0.0925539 -0.831224 -0.548179 0.0195643 -0.786917 -0.616748 0.10568 -0.802606 -0.587074 0.0551762 -0.722972 -0.688671 0.0828967 -0.730896 -0.677435 0.0744423 -0.645416 -0.760195 0.0784394 -0.646968 -0.758472 0.0785528 -0.541821 -0.836815 0.0945193 -0.54837 -0.830877 0.07583 -0.475207 -0.8766 0.778094 -0.623885 -0.0730565 0.77908 -0.622715 -0.0725287 0.772146 -0.620625 -0.136436 0.775157 -0.617549 -0.133288 0.767665 -0.608722 -0.200368 0.771173 -0.605545 -0.196487 0.763804 -0.589183 -0.263565 0.767126 -0.586618 -0.25961 0.760601 -0.565131 -0.319553 0.763498 -0.563301 -0.315852 0.754342 -0.526734 -0.391817 0.759065 -0.523316 -0.387249 0.752628 -0.476905 -0.453995 0.754933 -0.476327 -0.450765 0.750003 -0.438163 -0.495489 0.752286 -0.437875 -0.492272 0.747224 -0.390766 -0.537548 0.749606 -0.390772 -0.534217 0.744055 -0.327191 -0.582519 0.746583 -0.32753 -0.579084 0.740652 -0.237098 -0.628664 0.743039 -0.237831 -0.625564 0.738986 -0.124864 -0.662049 0.740564 -0.125761 -0.660113 0.739488 -0.023976 -0.672743 0.589073 -0.0299033 -0.807527 0.590447 -0.0304871 -0.8065 0.418885 -0.035193 -0.907357 0.420379 -0.0357638 -0.906644 0.244112 -0.0389317 -0.968965 0.245507 -0.039446 -0.968592 0.0861002 -0.041073 -0.995439 0.117429 -0.053261 -0.991652 0.983232 0.000538616 -0.182358 0.759065 0.523316 -0.387249 0.0942181 0.915277 -0.391651 0.0811037 0.922605 -0.377124 0.076706 0.943292 -0.32298 0.097134 0.94944 -0.298545 0.0748054 0.961481 -0.264497 0.0867422 0.97712 -0.194196 0.102288 0.972932 -0.207222 0.044451 0.995108 -0.0882268 0.0938802 0.988522 -0.118369 0.0655845 0.997828 0.00611163 0.0973352 0.995205 -0.00962064 0.0754424 0.996578 0.0337778 0.242257 0.970187 -0.0070338 0.255661 0.966656 -0.0146108 0.246744 0.963755 -0.10146 0.25486 0.960879 -0.108432 0.245306 0.948432 -0.200751 0.254539 0.944464 -0.207842 0.244934 0.921516 -0.301357 0.253605 0.917116 -0.307543 0.244982 0.886926 -0.391594 0.252584 0.882498 -0.396736 0.949309 0.21675 -0.227665 0.987202 0.0689066 -0.143823 0.959943 0.252378 -0.121716 0.960073 0.25156 -0.122384 0.957344 0.248368 -0.147665 0.957522 0.24726 -0.148373 0.954809 0.241192 -0.173686 0.959191 0.210799 -0.188457 0.953738 0.236239 -0.185944 0.988219 0.0781814 -0.131569 0.988399 0.074041 -0.132612 0.740599 0.124467 -0.660319 0.739087 0.126124 -0.661697 0.743057 0.235975 -0.626244 0.74084 0.238855 -0.627778 0.746537 0.325579 -0.580241 0.744278 0.329023 -0.581201 0.749513 0.388983 -0.535651 0.752883 0.478282 -0.452121 0.754788 0.474843 -0.452569 0.750242 0.439662 -0.493796 0.889325 0.438307 -0.130335 0.890146 0.436119 -0.13206 0.885359 0.430588 -0.175309 0.886361 0.427826 -0.176998 0.881633 0.417412 -0.220207 0.882607 0.414654 -0.22151 0.878408 0.400895 -0.260158 0.879278 0.398378 -0.261084 0.873083 0.37364 -0.31324 0.949807 0.215862 -0.226429 0.945923 0.190355 -0.262668 0.946285 0.189044 -0.262311 0.943699 0.16243 -0.288182 0.943891 0.161516 -0.288067 0.941788 0.136527 -0.307238 0.942009 0.135601 -0.30697 0.939757 0.0994093 -0.327071 0.939985 0.0986096 -0.326655 0.938353 0.0523499 -0.341691 0.93858 0.051704 -0.341166 0.8584 0.0884944 -0.50529 0.857677 0.0896765 -0.506309 0.860514 0.168201 -0.480858 0.859581 0.170037 -0.48188 0.863588 0.231816 -0.447746 0.862657 0.233982 -0.448415 0.866358 0.276676 -0.415783 0.865518 0.278849 -0.416079 0.869843 0.324215 -0.37183 0.772555 0.620786 -0.133351 0.774892 0.617207 -0.136375 0.768135 0.609242 -0.196957 0.770891 0.604794 -0.199877 0.764235 0.590021 -0.260421 0.766867 0.585574 -0.262712 0.760966 0.566163 -0.316846 0.763273 0.562108 -0.31851 0.754341 0.526734 -0.391817 0.875064 0.371435 -0.31032 0.870577 0.339367 -0.356267 0.888499 0.283775 -0.360613 0.752164 0.436271 -0.49388 0.747455 0.392445 -0.536002 0.245507 0.039446 -0.968592 0.0785122 0.0411233 -0.996065 0.124424 0.0233051 -0.991955 0.076504 0.827482 -0.556256 0.0592916 0.834576 -0.547693 0.102176 0.75902 -0.643 0.034381 0.786028 -0.617235 0.126358 0.682026 -0.720329 0.0210673 0.725249 -0.688164 0.139284 0.597766 -0.789478 0.0237235 0.648921 -0.760486 0.133206 0.502681 -0.854148 0.0512089 0.543672 -0.837734 0.103414 0.38854 -0.91561 0.096018 0.392895 -0.914557 0.0657243 0.254591 -0.964813 0.122131 0.207687 -0.970541 0.0789439 0.152092 -0.985209 0.0782593 0.0955263 -0.992346 0.429423 0.902638 -0.0290117 0.440604 0.896995 -0.0355958 0.432045 0.894151 -0.117608 0.438652 0.890139 -0.123441 0.429504 0.878437 -0.209463 0.437045 0.873303 -0.21525 0.427942 0.851892 -0.301903 0.435028 0.846546 -0.306774 0.426902 0.818507 -0.384448 0.433107 0.813393 -0.388343 0.421396 0.76301 -0.490144 0.43243 0.755664 -0.49191 0.423868 0.693411 -0.582681 0.42888 0.688701 -0.584597 0.422577 0.637847 -0.643879 0.427603 0.633108 -0.645236 0.421104 0.569827 -0.705669 0.426398 0.564963 -0.706401 0.419194 0.478054 -0.771842 0.424904 0.473205 -0.771708 0.417117 0.347227 -0.839909 0.422595 0.343156 -0.838843 0.417157 0.183909 -0.890032 0.42045 0.181715 -0.888933 0.418885 0.035193 -0.907357 0.590447 0.0304871 -0.8065 0.420379 0.0357638 -0.906643 0.244112 0.0389317 -0.968965 0.245893 0.199164 -0.948615 0.242002 0.201413 -0.949141 0.247794 0.375471 -0.893096 0.241076 0.379602 -0.893188 0.249203 0.517143 -0.818817 0.242177 0.521971 -0.817861 0.249768 0.616621 -0.746589 0.243255 0.621395 -0.744779 0.250144 0.690139 -0.67907 0.243962 0.694714 -0.676649 0.250667 0.749903 -0.612219 0.24451 0.754362 -0.609223 0.253973 0.821543 -0.510455 0.345761 0.77362 -0.531001 0.245032 0.847868 -0.470191 0.0804263 0.87749 -0.472804 0.0561088 0.888284 -0.455855 0.779178 0.622731 -0.0713324 0.774119 0.628688 -0.0741026 0.894022 0.439624 -0.0863409 0.891836 0.443683 -0.0881708 0.962615 0.253129 -0.0964222 0.961995 0.255119 -0.0973677 0.991516 0.0800666 -0.102398 0.991505 0.0805674 -0.102112 0.991195 0.0795027 -0.105881 0.990729 0.0793665 -0.110257 0.990714 0.0786237 -0.110927 0.989817 0.0788276 -0.118524 0.989799 0.078015 -0.119215 0.989195 0.0766251 -0.124986 0.986929 0.0723565 -0.144001 0.986791 0.065626 -0.148114 0.986018 0.0606068 -0.15523 0.98508 0.0695364 -0.157422 0.986299 0.047194 -0.158073 0.984738 0.0609272 -0.163033 0.985266 0.0413082 -0.165963 0.98421 0.0501329 -0.169754 0.98441 0.0306853 -0.17319 0.983397 0.0380195 -0.177442 0.983876 0.0161789 -0.17812 0.982805 0.0221808 -0.183311 0.983312 0.0113932 -0.181568 0.614291 0.78742 -0.0511515 0.622181 0.780841 -0.0563752 0.614436 0.778351 -0.128992 0.618915 0.77404 -0.133441 0.610653 0.763882 -0.208774 0.615833 0.758509 -0.213106 0.607671 0.739884 -0.28863 0.612546 0.734473 -0.292126 0.605295 0.710092 -0.359704 0.609567 0.705063 -0.362373 0.598989 0.661702 -0.450958 0.606662 0.65436 -0.451413 0.599213 0.600042 -0.529994 0.602691 0.595645 -0.53101 0.597088 0.551567 -0.58246 0.600555 0.547231 -0.582985 0.594762 0.492382 -0.635467 0.598454 0.487936 -0.63543 0.592011 0.412779 -0.692197 0.596003 0.408386 -0.691377 0.588997 0.299613 -0.750543 0.592855 0.295957 -0.748955 0.588 0.158427 -0.793194 0.590436 0.156431 -0.791779 0.589073 0.0299033 -0.807527 0.739488 0.023976 -0.672743 0.740507 0.0233398 -0.671643 0.857562 0.0167504 -0.514107 0.858173 0.0162177 -0.513104 0.938065 0.00955571 -0.346327 0.938313 0.00920928 -0.345665 0.983185 0.0029811 -0.182591 0.982399 0.00521007 -0.186723 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -7.26013e-05 -0.000447785 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 6.85342e-07 1.42549e-05 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.156435 0.987688 0 -0.156435 0.987688 0 -0.345854 0.938288 0 -0.453915 0.890863 -0.018022 -0.488374 0.872634 0 -0.70711 0.707104 0 -0.70711 0.707104 0 -0.891004 0.453995 0 -0.891004 0.453995 0 -0.987689 0.156431 0 -0.987689 0.156431 0 -1 0 0 -1 0 0 -1 0 0 -0.987689 -0.156431 0 -0.987689 -0.156431 0 -0.891004 -0.453995 0 -0.891004 -0.453995 0 -0.70711 -0.707104 0 -0.70711 -0.707104 0 -0.488374 -0.872634 0 -0.453915 -0.890863 -0.018022 -0.345854 -0.938288 0 -0.156435 -0.987688 0 -0.156435 -0.987688 0 0 -0.0942956 0.995544 0.000446538 -0.0948583 0.995491 -0.000287806 -0.247876 0.968792 0.00694798 -0.26321 0.964714 -0.00194592 -0.340384 0.940284 0.00851351 -0.424961 0.905172 0.00953438 -0.426486 0.904444 -0.00869238 -0.560005 0.828444 0.00570418 -0.582015 0.813158 -0.00232692 -0.661632 0.749825 6.25681e-06 -0.670271 0.742116 -1.39831e-05 -0.730924 0.682459 0.00465719 -0.738603 0.674125 -0.00536771 -0.815998 0.57803 0.00521545 -0.828519 0.559936 -0.00364994 -0.886028 0.463617 2.199e-06 -0.891178 0.453654 -1.72175e-06 -0.926767 0.375637 0.0032645 -0.930972 0.365077 -0.00514254 -0.964323 0.264677 0.00508976 -0.969868 0.24358 -0.00502845 -0.993105 0.117122 0 -0.994333 0.106309 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.0874788 0.996166 0 0.989997 0.141088 2.65897e-05 0.990002 0.141053 -2.03138e-05 0.95106 0.309005 0.00275157 0.952573 0.304297 0.0871091 0.207828 0.974279 -0.0781135 0.111359 0.990706 -0.00351197 0.230297 0.973114 0.00175496 0.341375 0.939926 9.27953e-06 0.33548 0.942047 -1.4545e-05 0.430315 0.902679 -0.00260687 0.425408 0.904998 0.00326919 0.548558 0.836106 -0.00318108 0.53979 0.841794 0.00241148 0.650694 0.759336 1.00947e-05 0.646602 0.762827 -7.16388e-06 0.721836 0.692065 -0.0016717 0.718087 0.695951 0.00309119 0.797188 0.603723 -0.00294303 0.791147 0.611619 0.00381701 0.888576 0.458714 -0.0164628 0.876794 0.480584 -0.000878673 0.918336 0.395801 -4.41801e-08 0.999048 0.0436192 0 0.999048 0.0436192 0 0.999048 0.0436195 1.1808e-07 0.999048 0.0436195 1.48229e-07 0.999048 0.0436196 6.48004e-07 0.999048 0.0436193 6.38423e-07 0.999048 0.0436193 -5.52503e-07 0.999048 0.0436198 -3.6706e-07 0.999048 0.0436195 0 0.999048 0.0436192 1.97092e-07 0.999048 0.0436192 3.46279e-07 0.999048 0.0436194 -5.45957e-07 0.999048 0.0436196 -7.30511e-07 0.999048 0.0436192 -8.73371e-08 0.999048 0.043619 -1.81449e-07 0.999048 0.0436195 3.5336e-08 0.999048 0.0436194 -6.63271e-08 0.999048 0.0436196 0 0.999048 0.0436194 -3.19512e-08 0.999048 0.0436194 5.31028e-07 0.999048 0.0436196 9.50702e-07 0.999048 0.0436189 0 0.999838 0.0179867 -0.00611329 0.900501 -0.43481 0.00455802 0.82261 -0.568587 -0.00454556 0.811731 -0.584014 0.00221174 0.750473 -0.660898 -2.14574e-06 0.743863 -0.668333 3.76083e-06 0.682693 -0.730705 -0.00383748 0.675759 -0.737113 0.0047224 0.577536 -0.816351 -0.00626992 0.559932 -0.828515 0.00489817 0.452345 -0.891829 -2.1492e-05 0.441107 -0.897455 1.22789e-05 0.365029 -0.930996 -0.00256982 0.353388 -0.935473 0.00546953 0.262749 -0.964849 -0.000301889 0.251013 -0.967984 0.000452067 0.0952922 -0.995449 0 0.0947178 -0.995504 -0.00176914 0.999588 0.0286425 0.00601929 0.99629 -0.085848 -0.00603043 0.994577 -0.103826 0.00447278 0.966821 -0.255416 -0.00452905 0.961837 -0.273584 0.000235925 0.940661 -0.339348 -0.00197183 0.903186 -0.429245 0 -0.998527 -0.054257 2.67815e-05 -0.998529 -0.0542218 -2.07351e-05 -0.974402 -0.224813 0.00325214 -0.975695 -0.219107 -0.00156345 -0.94594 -0.324339 2.35943e-08 -0.947925 -0.318494 1.05266e-06 -0.909552 -0.41559 0.00299066 -0.911969 -0.410249 -0.00352298 -0.841465 -0.5403 0.00358567 -0.847669 -0.530514 -0.00290403 -0.762167 -0.647374 -2.24758e-06 -0.766028 -0.642807 2.20461e-06 -0.694774 -0.719229 0.00173867 -0.699259 -0.714866 -0.00359607 -0.609706 -0.792619 0.00363999 -0.61894 -0.78543 -0.0046767 -0.465851 -0.884851 0.00486759 -0.47584 -0.879518 -0.00376216 -0.308774 -0.951128 0.00388665 -0.320329 -0.947298 -0.00499987 -0.144452 -0.989499 0.00521008 -0.15599 -0.987745 -0.00158086 -0.0241086 -0.999708 0 -0.0314049 -0.999507 3.251e-08 -0.999048 0.0436196 -3.59679e-08 -0.999048 0.0436185 7.02311e-07 -0.999048 0.0436195 -1.41898e-08 -0.999048 0.0436193 -3.4686e-08 -0.999048 0.0436192 -8.81503e-07 -0.999048 0.0436192 -8.24927e-07 -0.999048 0.0436193 -6.12955e-07 -0.999048 0.0436191 -2.18957e-07 -0.999048 0.0436195 -4.07482e-07 -0.999048 0.0436196 -5.06819e-07 -0.999048 0.0436196 0 -0.999048 0.0436187 0 -0.999048 0.0436196 0 -0.999048 0.0436195 -1.2713e-07 -0.999048 0.0436195 9.93052e-08 -0.999048 0.0436192 3.02852e-07 -0.999048 0.0436192 3.98366e-07 -0.999048 0.0436191 7.36511e-07 -0.999048 0.0436195 0 -0.999048 0.0436194 -7.54893e-08 -0.999048 0.0436193 -2.18744e-07 -0.999048 0.0436194 -9.33862e-08 -0.999048 0.0436196 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.117692 -0.99305 0 0.194991 -0.980279 -0.0321072 0.309168 -0.951007 0 0.41894 -0.908014 0 0.522826 -0.852285 -0.0162318 0.555282 -0.831042 -0.0321071 0.649565 -0.760306 0 0.773014 -0.634388 0 0.831004 -0.555259 -0.0334674 0.881918 -0.471403 0 0.956941 -0.290283 0 0.980236 -0.194981 -0.033469 0.995185 -0.0980194 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 0 0 1 0 0 0.99058 0.136934 0 0.980397 0.195013 -0.0281268 0.831041 0.555284 -0.0321042 0.891072 0.453861 0 0.94483 0.32756 0 0.41894 0.908014 0 0.572064 0.81985 -0.024273 0.555529 0.831412 -0.0119029 0.693258 0.72069 0 0.785417 0.618967 0 0.309168 0.951007 0 0.194991 0.980279 -0.0321072 0.117692 0.99305 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.271817 0.263279 -0.925635 0.495662 0.482878 -0.721906 0.705231 0.694214 -0.143931 0.851599 -0.00448507 -0.524174 0.660725 0.6502 -0.375078 0.437704 0.320941 -0.839888 0.1506 0.0784613 -0.985476 0.660814 0.644495 -0.384645 0.707079 0.593702 -0.384132 0.704378 0.589411 -0.395533 0.755457 0.521879 -0.396141 0.754587 0.518471 -0.402226 0.771712 0.49252 -0.402349 0.786846 0.429679 -0.443 0.798649 0.430892 -0.420109 0.853716 0.307936 -0.419933 0.843664 0.300145 -0.445134 0.879729 0.16689 -0.445225 0.864353 0.159286 -0.476992 0.877271 0.0501061 -0.477373 0.859554 0.0447035 -0.509086 0.860512 -0.00674157 -0.509386 0.466717 0.450179 -0.761258 0.49708 0.417366 -0.760735 0.493417 0.413081 -0.765443 0.528903 0.365329 -0.766026 0.527197 0.362449 -0.768566 0.561274 0.308734 -0.76789 0.553982 0.302685 -0.775555 0.593876 0.214208 -0.775517 0.58238 0.207477 -0.785994 0.607293 0.115209 -0.78608 0.590994 0.109172 -0.799255 0.599606 0.034255 -0.799562 0.582043 0.0304994 -0.812586 0.582506 -0.00314716 -0.81282 0.574038 -0.00432688 -0.818817 0.167872 0.161639 -0.972467 0.178675 0.150166 -0.972381 0.177087 0.148424 -0.972939 0.189697 0.131202 -0.973037 0.18892 0.130092 -0.973337 0.201276 0.110945 -0.973231 0.198176 0.108544 -0.974138 0.212449 0.0769189 -0.97414 0.20762 0.0742795 -0.975385 0.21648 0.0413885 -0.975409 0.209809 0.0391008 -0.97696 0.212802 0.0124539 -0.977016 0.20569 0.011089 -0.978554 0.205804 -0.000985407 -0.978593 0.2024 -0.00138441 -0.979302 -0.00910862 0.00936464 -0.999915 0 0.00221983 -0.999998 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.115615 -0.0991601 -0.988332 0.851602 0.00364572 -0.524176 0.202403 0.000657632 -0.979302 0.294132 -0.253689 -0.921482 0.536969 -0.467386 -0.702292 0.712834 -0.619274 -0.329191 0.178776 -0.146128 -0.972978 0.197306 -0.120723 -0.972881 0.193551 -0.11907 -0.973838 0.212598 -0.0806369 -0.973807 0.206309 -0.0791572 -0.97528 0.215873 -0.043862 -0.975436 0.210329 -0.0438033 -0.976649 0.214208 -0.016391 -0.976651 0.206761 -0.0168727 -0.978246 0.207173 0.00017515 -0.978304 0.574048 0.00232032 -0.818818 0.585875 0.000912938 -0.810401 0.584492 -0.0469318 -0.810041 0.60294 -0.0451194 -0.79651 0.592033 -0.122466 -0.796555 0.605724 -0.122008 -0.786265 0.578218 -0.221129 -0.785345 0.593611 -0.224206 -0.77289 0.540447 -0.331903 -0.773148 0.54963 -0.335565 -0.765051 0.490111 -0.417341 -0.765256 0.393476 -0.338957 -0.854567 0.864026 0.00134082 -0.503445 0.861527 -0.0693379 -0.502956 0.880157 -0.0653126 -0.470168 0.864215 -0.178916 -0.470236 0.877834 -0.176241 -0.44536 0.836741 -0.320128 -0.444277 0.85157 -0.321087 -0.414405 0.775371 -0.476255 -0.414705 0.784262 -0.478362 -0.3951 0.689194 -0.607536 -0.394856 0.768227 -0.63621 -0.07117 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.000635441 -0.0163502 -0.999866 -0.000294664 -0.00245096 -0.999997 0 -0.00221982 -0.999998 0.984836 0.15392 -0.0800379 0.685652 0.727 -0.0367763 0.975898 -0.0054111 -0.218162 0.97605 0.06322 0.208156 0.986767 0.112419 -0.116848 0.985114 0.160889 -0.0605483 0.874953 0.47677 -0.0845456 0.800511 0.593104 -0.0860792 0.804948 0.585315 -0.0972853 0.723437 0.688231 -0.0545752 0.714676 0.698766 -0.0310465 0.642525 0.761004 -0.0896365 0.633682 0.771866 -0.0516621 0.62123 0.782759 -0.0368953 0.622871 0.781748 -0.0300363 0.612472 0.788819 -0.0514097 0.790309 0.612653 0.00829554 0.742266 0.650844 -0.159507 0.649387 0.736018 0.191242 0.898677 0.406718 0.164194 0.85144 0.523732 -0.0274805 0.82464 0.564962 -0.0280521 0.992692 0.11873 -0.0215628 0.861995 0.467828 -0.195195 0.948872 0.312779 0.0425668 0.967377 0.244047 -0.0679949 0.987384 0.158188 0.00698679 0.992892 0.115043 -0.030516 0.938194 0.260002 -0.228453 0.940208 0.242793 -0.238872 0.945352 0.252614 -0.206145 0.909463 0.348136 -0.227329 0.848293 0.413007 -0.331399 0.847813 0.416622 -0.328084 0.838217 0.457527 -0.29675 0.793884 0.526096 -0.304911 0.734479 0.574209 -0.361698 0.735234 0.572612 -0.362695 0.558598 0.723089 -0.406337 0.592656 0.707476 -0.385015 0.608623 0.665459 -0.432137 0.657105 0.653812 -0.375159 0.710232 0.60685 -0.356796 0.551686 0.720222 -0.420623 0.597894 0.715314 -0.361731 0.601221 0.70492 -0.376326 0.708873 0.697651 -0.103839 0.725925 0.68774 -0.00688158 0.719786 0.604107 -0.341999 0.801047 0.591534 0.0917147 0.816795 0.56208 -0.130046 0.830552 0.528033 -0.177098 0.892567 0.32052 -0.317161 0.956586 0.289184 0.0362778 0.947058 0.311863 -0.076304 0.885151 0.45149 -0.112537 0.889049 0.457603 -0.0138667 0.867457 0.465427 -0.175772 0.937836 0.175516 -0.299429 0.976683 0.102326 -0.188729 0.957379 0.0515687 -0.284193 0.962021 0.00720264 -0.27288 0.939406 -0.00632324 -0.342747 0.942581 0.274231 -0.190626 0.934779 0.277749 -0.221458 0.872986 0.429925 -0.230349 0.845332 0.456822 -0.276997 0.757598 0.590501 -0.278124 0.74959 0.595743 -0.288454 0.654595 0.701057 -0.282885 0.6462 0.702685 -0.297757 0.590864 0.752039 -0.292089 0.580665 0.753146 -0.309191 0.605316 0.732237 -0.312123 0.612168 0.7328 -0.297076 0.784893 0.515303 -0.344102 0.95666 0.281187 -0.0757335 0.94978 0.271833 -0.154997 0.983618 0.10921 -0.143416 0.983941 0.108794 -0.141507 0.99073 0.0226051 -0.133954 0.997222 0.0180295 -0.0722741 0.998978 0.00222065 -0.045147 0.658041 0.728863 -0.18905 0.589908 0.78245 -0.199449 0.625467 0.753634 -0.202056 0.637935 0.749527 -0.176775 0.60317 0.778246 -0.174695 0.614078 0.774437 -0.152168 0.672772 0.723465 -0.154842 0.676434 0.721758 -0.146639 0.780052 0.607754 -0.148843 0.774637 0.61255 -0.157226 0.867599 0.472227 -0.155801 0.867108 0.472814 -0.156753 0.943837 0.294591 -0.149625 0.958337 0.266062 -0.103925 0.985539 0.13866 -0.0973997 0.961733 0.210989 -0.174795 -0.208295 0.485749 -0.848918 0.502566 0.390718 -0.771211 -0.445715 0.110181 -0.888368 -0.0272819 0.998596 -0.0454131 -0.01889 0.710515 -0.703429 -0.0146771 0.751753 -0.659281 -0.0506238 0.76923 -0.636964 -0.0025041 0.804545 -0.593887 -0.0771709 0.846921 -0.526089 -0.0345098 0.8357 -0.548101 -0.0389207 0.877869 -0.477317 -0.0550244 0.8856 -0.461177 -0.0263134 0.918766 -0.393924 -0.0891502 0.938555 -0.333417 -0.0529456 0.929499 -0.365004 -0.040668 0.961133 -0.273075 -0.143748 0.972523 -0.183127 0.019972 0.964963 -0.261624 -0.0894499 0.987795 -0.127517 -0.0511296 0.986333 -0.156631 -0.0508798 0.995679 -0.0776814 -0.0365475 0.997035 -0.0677103 -0.0979396 0.993315 -0.0611066 -0.0661133 0.996564 -0.0498963 -0.0254993 0.998637 -0.0455301 -0.041917 0.997844 -0.0504987 -0.135039 0.989595 -0.0496593 -0.0611332 0.991628 -0.113741 -0.294775 0.947354 -0.125009 -0.284391 0.946671 -0.151448 -0.450554 0.860128 -0.239126 -0.446502 0.859488 -0.248832 -0.500704 0.805862 -0.316043 -0.563961 0.736673 -0.373177 -0.566596 0.738685 -0.36512 -0.603432 0.697606 -0.386285 -0.667757 0.599935 -0.440658 -0.660957 0.593244 -0.459562 -0.704736 0.456801 -0.542844 -0.70466 0.456884 -0.542873 -0.7658 0.363641 -0.530392 -0.728877 0.328386 -0.600751 -0.737826 0.292086 -0.608521 -0.778751 0.193255 -0.596825 -0.73921 0.179462 -0.649124 -0.763919 0.106555 -0.636454 -0.717392 0.0616125 -0.69394 -0.705092 -0.121623 -0.698608 -0.611092 0.113879 -0.783325 -0.43335 0.0818649 -0.8975 -0.208447 0.106731 -0.972193 -0.326506 0.0370582 -0.944468 -0.218403 0.0304178 -0.975385 -0.233266 0.0657845 -0.970185 -0.0990284 0.14782 -0.984044 -0.015421 0.364522 -0.931067 -0.0354386 0.220706 -0.974696 0.0196291 0.237432 -0.971206 -0.765422 0.240965 -0.596712 -0.735815 0.275025 -0.61882 -0.700514 0.21866 -0.679314 -0.70842 0.218932 -0.670977 -0.646324 0.125042 -0.752748 -0.640802 0.124491 -0.757546 -0.615568 0.0879491 -0.783161 -0.531076 0.0517779 -0.84574 -0.120837 0.101043 -0.987516 -0.204931 0.0570975 -0.97711 -0.317897 0.163135 -0.933985 -0.309718 0.162895 -0.936771 -0.445217 0.297017 -0.844726 -0.410769 0.296762 -0.862091 -0.526688 0.414853 -0.741955 -0.483651 0.416829 -0.769633 -0.575195 0.510103 -0.639489 -0.53325 0.515008 -0.671127 -0.604445 0.586015 -0.53966 -0.565014 0.593765 -0.57289 -0.620197 0.646652 -0.444068 -0.580728 0.657581 -0.47994 -0.606083 0.680799 -0.41131 -0.680966 0.616899 -0.394615 -0.840742 0.442942 -0.311377 -0.708939 0.530658 -0.464551 -0.676353 0.484212 -0.555055 -0.702367 0.478544 -0.526951 -0.649646 0.404882 -0.643452 -0.67447 0.402068 -0.619218 -0.606087 0.310362 -0.732348 -0.626452 0.309931 -0.715193 -0.541959 0.202073 -0.81575 -0.546816 0.202284 -0.812449 -0.459414 0.097157 -0.882893 -0.385057 0.0965806 -0.917825 -0.157011 0.549229 -0.820789 -0.132704 0.334645 -0.932954 -0.084954 0.406555 -0.909668 -0.0875393 0.405158 -0.910046 -0.0378682 0.48063 -0.876106 -0.0139357 0.492338 -0.870292 -0.0489711 0.609621 -0.791179 -0.395245 0.901714 -0.175195 -0.330952 0.926646 -0.178318 -0.2965 0.92 -0.256294 -0.376948 0.904214 -0.200768 -0.302065 0.885839 -0.3522 -0.377279 0.874932 -0.303569 -0.289042 0.842721 -0.454177 -0.362532 0.836245 -0.411418 -0.261503 0.789809 -0.554814 -0.338917 0.786793 -0.515841 -0.221404 0.724891 -0.652313 -0.308593 0.724705 -0.616096 -0.16697 0.643622 -0.746908 -0.271512 0.645775 -0.713622 -0.152188 0.577258 -0.802254 -0.0496445 0.618609 -0.784129 -0.144226 0.65364 -0.742936 -0.249575 0.964485 -0.0864951 -0.154752 0.984787 -0.0790296 -0.13071 0.983141 -0.127865 -0.215309 0.973905 -0.0717747 -0.140446 0.967574 -0.209941 -0.238537 0.959786 -0.148023 -0.136307 0.939742 -0.313536 -0.238534 0.937158 -0.254631 -0.121314 0.9006 -0.417376 -0.228337 0.903249 -0.363323 -0.0999107 0.852122 -0.513717 -0.212206 0.858927 -0.466061 -0.0711358 0.794788 -0.602703 -0.191748 0.804543 -0.562088 -0.0320991 0.726532 -0.686383 -0.167076 0.738183 -0.653584 -0.0611021 0.689042 -0.722141 -0.100249 0.674319 -0.731604 -0.57326 0.743921 -0.343443 -0.515037 0.831894 -0.206611 -0.452109 0.807253 -0.379393 -0.509306 0.792559 -0.335347 -0.446343 0.758736 -0.474444 -0.500251 0.748233 -0.435771 -0.423895 0.700403 -0.574237 -0.479381 0.69305 -0.538402 -0.385412 0.627789 -0.676268 -0.447865 0.623009 -0.641308 -0.32964 0.535143 -0.777792 -0.402251 0.532877 -0.744471 -0.250022 0.415617 -0.874501 -0.335356 0.415502 -0.845514 -0.14582 0.269022 -0.952031 -0.240834 0.269426 -0.932421 -0.0963255 0.161743 -0.982121 -0.0554478 0.172016 -0.983532 0 0.00936503 -0.999956 0.000689783 0.00560602 -0.999984 -0.00161781 0.0577463 -0.99833 0.00521789 0.0282889 -0.999586 0.019702 0.154871 -0.987738 0.00121378 0.0550129 -0.998485 0.000173156 0.0807026 -0.996738 -0.000901817 0.142868 -0.989741 0.0278087 0.133409 -0.990671 -0.0261175 0.261607 -0.964821 -0.0120035 0.200243 -0.979673 0.0153759 0.256735 -0.96636 0.00179744 0.240444 -0.970661 -0.00752043 0.230321 -0.973086 -0.0263284 0.220769 -0.974971 -0.0107629 0.462465 -0.886572 0.0128466 0.179548 -0.983665 -8.35679e-06 0.231571 -0.972818 4.48155e-07 0.326527 -0.945188 -0.000616787 0.391004 -0.920389 -0.0218927 0.522369 -0.852438 -4.82055e-06 0.451938 -0.892049 6.51537e-07 0.579923 -0.814671 -0.00141581 0.610353 -0.792129 0.00244732 0.644564 -0.764546 0.000999265 0.660546 -0.750785 0.000125314 0.677733 -0.735308 -0.000364704 0.712502 -0.70167 -0.000120534 0.710647 -0.703549 -0.00169753 0.822663 -0.568527 0.000190648 0.766772 -0.64192 -0.000461088 0.751848 -0.659336 -1.68846e-05 0.745444 -0.666569 -1.68837e-05 0.733918 -0.679238 0.00631561 0.80456 -0.593837 -1.31145e-06 0.849927 -0.5269 -1.17849e-06 0.866505 -0.499169 -0.000646509 0.878832 -0.477132 0.00299833 0.899251 -0.437423 -0.00782557 0.934962 -0.354661 0.00106519 0.919348 -0.393445 -5.81737e-06 0.94321 -0.332198 -6.15219e-06 0.951155 -0.308713 -0.00239315 0.962298 -0.271986 0.00404632 0.975477 -0.220065 -1.82747e-06 0.997834 -0.0657805 0.00381241 0.996562 -0.0827635 0.000361636 0.992316 -0.123729 -0.000536407 0.983876 -0.178849 -0.999766 -0.00209581 -0.0215319 -0.760097 -0.0279472 -0.649208 -0.798959 -0.0526382 -0.599077 -0.801496 -0.0454642 -0.59627 -0.833186 -0.0579253 -0.54995 -0.652977 -0.0100364 -0.757311 -0.715505 -0.0154477 -0.698436 -0.743694 -0.0165392 -0.668315 -0.970734 -0.0178179 -0.239494 -0.999714 -0.00108122 -0.0238821 -0.983304 -0.00550831 -0.181885 -0.96616 -0.0190681 -0.257237 -0.953823 -0.00516329 -0.300326 -0.895613 -0.0109203 -0.444699 -0.999855 -0.00545545 -0.0161185 -0.999763 -0.00344048 -0.0214887 -0.97073 -0.0186534 -0.239448 -0.966213 -0.0113917 -0.257491 -0.879638 -0.0322344 -0.47455 -0.879752 -0.0221685 -0.474916 -0.834948 -0.00886123 -0.550258 -0.99981 -0.00656251 0.0183503 -0.99986 -0.00413049 -0.0161925 -0.996581 -0.0135411 -0.0815014 -0.976844 -0.0271467 -0.212225 -0.979996 -0.0187974 -0.198127 -0.945208 -0.0363525 -0.324437 -0.742178 -0.0156534 -0.67002 -0.741983 -0.0427251 -0.669056 -0.894657 -0.0137596 -0.446541 -0.894694 -0.0276485 -0.445824 -0.910615 -0.0393976 -0.411374 -0.910634 -0.0335347 -0.411851 -0.909821 -0.0329529 -0.41369 -0.894697 0.0276488 -0.445818 -0.999825 0.00925949 -0.0162679 -0.97073 0.0186538 -0.239449 -0.760911 0.0341203 -0.647959 -0.803779 0.0515668 -0.59269 -0.80379 0.0441408 -0.593273 -0.652954 0.0130933 -0.757284 -0.742179 0.0164805 -0.669999 -0.743706 0.0155534 -0.668326 -0.834948 0.00886117 -0.550258 -0.879752 0.0221684 -0.474916 -0.895613 0.0109206 -0.444699 -0.953823 0.00516353 -0.300326 -0.967454 0.0226541 -0.252031 -0.970723 0.019847 -0.239382 -0.986975 0.0215912 -0.159418 -0.999979 0.00549779 -0.00347266 -0.822701 0.0407623 -0.567011 -0.806462 0.0557161 -0.588656 -0.875303 0.0458265 -0.481399 -0.905128 0.0352323 -0.423678 -0.925228 0.0393349 -0.377368 -0.956877 0.0276482 -0.289175 -0.999858 0.00553415 -0.0159077 -0.999763 0.00344035 -0.0214887 -0.999766 0.00223793 -0.0215273 -0.999711 0.00108518 -0.0240238 -0.999715 8.18169e-05 -0.0238821 -0.780345 0.01066 -0.625258 -0.741982 0.0427263 -0.669057 -0.89466 0.0137594 -0.446535 -0.879639 0.0322361 -0.474549 -0.966213 0.0113932 -0.257492 -0.96616 0.019068 -0.257238 -0.983304 0.00550826 -0.181885 -0.992754 0.0751503 0.0937629 -0.992387 0.0756352 0.0971958 -0.815374 0.5787 0.0164989 -0.575872 0.817488 0.00922509 -0.161792 0.986037 -0.0394237 -0.557627 0.809794 -0.182441 -0.999827 0.018416 -0.00265394 -0.924226 0.0721498 -0.374967 -0.956189 0.056871 -0.287173 -0.852177 0.201447 -0.482923 -0.821303 0.0919441 -0.563035 -0.839288 0.102722 -0.533894 -0.838165 0.170091 -0.518216 -0.852889 0.202354 -0.481283 -0.806609 0.448631 -0.384853 -0.811992 0.402044 -0.423119 -0.830764 0.329661 -0.448502 -0.830288 0.329424 -0.449558 -0.835909 0.24878 -0.489248 -0.762289 0.562652 -0.319903 -0.765465 0.545503 -0.341305 -0.772923 0.492126 -0.400502 -0.652477 0.70538 -0.276972 -0.654892 0.694564 -0.297821 -0.659055 0.671465 -0.338792 -0.466722 0.883741 -0.0342397 -0.440137 0.886197 -0.14469 -0.517237 0.83425 -0.191031 -0.367176 0.914001 -0.172581 -0.352714 0.93154 -0.0884689 -0.274653 0.958743 -0.0733335 -0.274558 0.95884 -0.0724176 -0.222357 0.973713 -0.0494015 -0.223685 0.973119 -0.0548195 -0.153262 0.987185 -0.0444616 -0.0652656 0.995869 -0.0631374 -0.159058 0.987108 -0.0178406 -0.151584 0.98803 -0.0286331 -0.36577 0.930594 -0.0143895 -0.451729 0.892096 -0.0103356 -0.796665 0.603151 0.0391694 -0.726674 0.686296 0.0306944 -0.663993 0.747563 0.0161926 -0.959546 0.269042 0.0829957 -0.917811 0.390535 0.0714572 -0.901467 0.428674 0.0599626 -0.877212 0.476442 0.0591822 -0.810902 0.583247 0.0475523 -0.655252 0.755304 0.0127087 -0.657246 0.753618 -0.00934691 -0.797074 0.60287 0.0349224 -0.814432 0.579632 0.0269791 -0.901465 0.428675 0.0599918 -0.977892 0.188142 0.091263 -0.964964 0.249553 0.081039 -0.96483 0.249635 0.0823776 -0.908409 0.41443 0.0551407 -0.909234 0.413698 0.0463447 -0.847358 0.530946 0.00894826 -0.851362 0.522891 -0.0420452 -0.870602 0.491907 0.00893993 -0.878422 0.471665 -0.0768563 -0.897494 0.440468 -0.0221822 -0.906499 0.40678 -0.113088 -0.921772 0.382537 -0.0632528 -0.93044 0.33568 -0.146969 -0.941505 0.319984 -0.10573 -0.948488 0.268896 -0.167527 -0.986606 0.0396376 -0.158234 -0.999907 0.0135176 0.00205205 -0.999344 0.0361843 0.00151201 -0.999259 0.0381656 0.00499544 -0.998106 0.0596008 0.0152474 -0.992167 0.0779044 0.0976477 -0.970862 0.228816 0.0712073 -0.972824 0.225897 0.0508393 -0.974459 0.214837 0.0653764 -0.977749 0.207268 0.0323565 -0.979516 0.195086 0.0499065 -0.983319 0.181436 0.0128155 -0.984761 0.171226 0.0304412 -0.98847 0.15133 -0.0051409 -0.989472 0.144339 0.0105503 -0.992409 0.121866 -0.0165342 -0.991651 0.0816067 0.099845 -0.991844 0.077864 0.10091 -0.991873 0.0794798 0.0993544 -0.966549 0.243618 0.0802073 -0.967104 0.243178 0.074667 -0.9229 0.382918 0.0403724 -0.925967 0.377577 0.00458747 -0.933742 0.356155 0.0357798 -0.93923 0.342525 -0.0228752 -0.947242 0.320284 0.0123027 -0.953566 0.296782 -0.0513117 -0.9601 0.279079 -0.017973 -0.966233 0.245703 -0.0776077 -0.970987 0.234025 -0.0491559 -0.976337 0.191632 -0.100216 -0.971099 0.199659 -0.13078 -0.973706 0.160591 -0.161576 -0.975545 0.163239 -0.147188 -0.979047 0.0987565 -0.178085 -0.978983 0.098582 -0.178534 -0.980333 0.0621776 -0.187299 -0.966874 0.0508149 -0.250144 -0.758599 0.570559 -0.314627 -0.745977 0.582447 -0.322914 -0.735663 0.640739 -0.219667 -0.762769 0.617191 -0.193026 -0.749457 0.65713 -0.0805948 -0.697304 0.695932 -0.171596 -0.683734 0.729039 -0.0317824 -0.630483 0.766641 -0.121462 -0.620245 0.784348 -0.00971449 -0.577516 0.812358 -0.0809292 -0.570422 0.821343 -0.0038771 -0.540201 0.839824 -0.0536414 -0.534808 0.84497 0.00230834 -0.244757 0.968427 -0.0473685 -0.31472 0.949029 -0.017174 -0.318835 0.946028 -0.058094 -0.373585 0.927521 -0.011775 -0.380017 0.9219 -0.0754185 -0.419064 0.907803 -0.0166806 -0.42775 0.897729 -0.105415 -0.483539 0.875057 -0.0215671 -0.496255 0.854719 -0.152272 -0.566913 0.822403 -0.0475652 -0.58353 0.783987 -0.211794 -0.654187 0.748742 -0.106892 -0.670313 0.701667 -0.241547 -0.570473 0.755687 -0.32171 -0.687106 0.708581 -0.160618 -0.998258 0.0583551 0.00872933 -0.997577 0.0672857 0.0176813 -0.998268 0.0579311 0.0102649 -0.996973 0.04024 0.0665199 -0.996054 0.0533826 0.0709027 -0.996072 0.0534838 0.0705645 -0.994971 0.0592021 0.0807948 -0.995152 0.0620853 0.0762737 -0.993868 0.0666805 0.0882008 -0.994012 0.0698172 0.0840604 -0.992953 0.0720963 0.0940544 -0.993065 0.0751376 0.0904251 -0.992794 0.0751062 0.09338 -0.874094 0.083871 -0.478461 -0.927184 0.0651588 -0.368896 -0.924746 0.155829 -0.347222 -0.924991 0.156091 -0.34645 -0.919284 0.257498 -0.297678 -0.912621 0.253892 -0.320409 -0.903225 0.357013 -0.238171 -0.888692 0.355807 -0.289183 -0.87569 0.450157 -0.174719 -0.853227 0.456543 -0.252138 -0.846084 0.507037 -0.164484 -0.84311 0.509812 -0.171048 -0.831137 0.553545 -0.0529056 -0.796849 0.59073 -0.126767 -0.78633 0.617659 -0.0135075 -0.75117 0.654645 -0.0847539 -0.74333 0.668902 0.0055863 -0.726589 0.686494 -0.0281708 -0.687343 0.726327 0.00306945 -0.685613 0.727693 0.0199419 -0.491856 0.869908 -0.0365611 -0.489275 0.872082 -0.00913326 -0.495882 0.868336 -0.00973568 -0.979609 -0.0411111 -0.196664 -0.908854 -0.0716506 -0.410914 -0.275322 -0.960638 -0.0370533 -0.4844 -0.874771 -0.0114944 -0.922834 -0.377467 0.0767878 -0.0831145 -0.995043 -0.0546009 -0.146885 -0.988869 -0.0237403 -0.213373 -0.976509 -0.0300406 -0.246546 -0.965599 -0.0826663 -0.211137 -0.965249 -0.153999 -0.34008 -0.940052 -0.0254705 -0.36723 -0.914006 -0.172438 -0.444375 -0.893332 -0.0670007 -0.654721 -0.694993 -0.297195 -0.65282 -0.704487 -0.278432 -0.661759 -0.707208 -0.248861 -0.566923 -0.778703 -0.268737 -0.557513 -0.809888 -0.182373 -0.527335 -0.828405 -0.188849 -0.455699 -0.875834 -0.158913 -0.728184 -0.569309 -0.381622 -0.722166 -0.603902 -0.337311 -0.758057 -0.571271 -0.314643 -0.658954 -0.671576 -0.338769 -0.737912 -0.512326 -0.439327 -0.806343 -0.450235 -0.383535 -0.812688 -0.392371 -0.430793 -0.838586 -0.32473 -0.437406 -0.831424 -0.318776 -0.455101 -0.836222 -0.229813 -0.497915 -0.850772 -0.202355 -0.485015 -0.843123 -0.177882 -0.507446 -0.838636 -0.158934 -0.520989 -0.839154 -0.0948176 -0.535565 -0.832121 -0.088962 -0.547413 -0.999364 -0.035482 0.00362753 -0.999878 -0.0155518 -0.00112822 -0.999363 -0.0296969 0.0198107 -0.992838 -0.063052 0.101475 -0.812832 -0.580833 0.0440156 -0.855195 -0.515338 0.0553959 -0.582215 -0.812918 0.013775 -0.655342 -0.755241 0.0117192 -0.657239 -0.753624 -0.00933884 -0.397652 -0.917474 -0.0106706 -0.48935 -0.872031 -0.00995945 -0.491847 -0.869914 -0.0365541 -0.685597 -0.727708 0.0199417 -0.687326 -0.726343 0.00307541 -0.709201 -0.704866 -0.0140627 -0.746053 -0.665614 -0.0190438 -0.748292 -0.661972 -0.0430329 -0.791546 -0.608485 -0.0565765 -0.794539 -0.600554 -0.0896776 -0.836335 -0.540709 -0.0904327 -0.841419 -0.521164 -0.142834 -0.874511 -0.466383 -0.133109 -0.880651 -0.432291 -0.193851 -0.904311 -0.388282 -0.177363 -0.911141 -0.328018 -0.249451 -0.171228 -0.982801 -0.0691551 -0.373562 -0.92753 -0.0117759 -0.375961 -0.926019 -0.0337947 -0.42368 -0.903826 -0.0599594 -0.423015 -0.904554 -0.0533011 -0.489856 -0.86844 -0.0765049 -0.491901 -0.865173 -0.097515 -0.574554 -0.811627 -0.105586 -0.580415 -0.79733 -0.165479 -0.661414 -0.733791 -0.155184 -0.670224 -0.701785 -0.241448 -0.735586 -0.640855 -0.219584 -0.745395 -0.588276 -0.313557 -0.793154 -0.537792 -0.285808 -0.80313 -0.451304 -0.388983 -0.193339 -0.980528 -0.034416 -0.315166 -0.948794 -0.0214549 -0.318825 -0.946032 -0.0580864 -0.534787 -0.844984 0.0023071 -0.536874 -0.843484 -0.017327 -0.574269 -0.817623 -0.04134 -0.573636 -0.818376 -0.0346627 -0.625589 -0.778 -0.0579108 -0.626859 -0.775828 -0.0716842 -0.690366 -0.718607 -0.083664 -0.69459 -0.707815 -0.12862 -0.755863 -0.642772 -0.12456 -0.76269 -0.617311 -0.192953 -0.811339 -0.557 -0.177425 -0.819277 -0.513896 -0.254353 -0.854289 -0.465047 -0.232211 -0.862229 -0.401974 -0.308185 -0.907216 -0.330514 -0.260231 -0.912365 -0.26482 -0.312186 -0.920588 -0.245497 -0.303724 -0.924982 -0.155799 -0.346606 -0.924712 -0.156449 -0.347031 -0.927343 -0.0856703 -0.364274 -0.94445 -0.0630963 -0.322542 -0.99805 -0.0610953 0.0127591 -0.99851 -0.0523752 0.0152984 -0.999432 -0.0337016 -0.000683561 -0.992846 -0.0701682 0.0966123 -0.991785 -0.0797693 0.1 -0.991855 -0.0797297 0.0993351 -0.992162 -0.0771414 0.098308 -0.992167 -0.0779212 0.0976403 -0.992628 -0.0753324 0.0949493 -0.992807 -0.0750925 0.0932511 -0.993605 -0.0682982 0.0899153 -0.993767 -0.06962 0.0870684 -0.994473 -0.0645725 0.0827875 -0.99529 -0.061644 0.0748179 -0.876358 -0.478063 0.0587565 -0.901415 -0.428713 0.0604759 -0.901462 -0.428682 0.0599917 -0.908403 -0.414443 0.0551414 -0.909228 -0.413711 0.046354 -0.922891 -0.382939 0.0403788 -0.92437 -0.380686 0.0248719 -0.936103 -0.351419 0.0147131 -0.937752 -0.347292 -0.00304043 -0.949715 -0.313016 -0.00790789 -0.953549 -0.29684 -0.0512815 -0.974539 -0.208623 0.0821622 -0.963834 -0.250184 0.0918307 -0.964833 -0.249623 0.0823801 -0.966547 -0.243624 0.0802155 -0.967102 -0.243183 0.0746699 -0.970861 -0.22882 0.0712083 -0.971908 -0.227352 0.0608802 -0.975636 -0.212451 0.0547605 -0.976817 -0.209734 0.0429024 -0.9808 -0.19109 0.038946 -0.982537 -0.184785 0.0218145 -0.994507 -0.102724 0.0200912 -0.993193 -0.109177 0.0405953 -0.994788 -0.0953616 0.0361118 -0.995931 -0.0864689 0.0253927 -0.996367 -0.08121 0.0256423 -0.997314 -0.0704136 0.0201534 -0.722736 -0.690289 0.033959 -0.796937 -0.602969 0.0363276 -0.79707 -0.602876 0.0349282 -0.814429 -0.579636 0.0269822 -0.81537 -0.578704 0.0165145 -0.84734 -0.530975 0.00895981 -0.849146 -0.528052 -0.0106177 -0.874328 -0.48477 -0.0234462 -0.876508 -0.479011 -0.0477749 -0.901309 -0.430095 -0.051576 -0.905018 -0.415665 -0.0903544 -0.947082 -0.311166 -0.0788198 -0.948134 -0.304853 -0.0900338 -0.959725 -0.26465 -0.0942796 -0.962973 -0.238407 -0.125876 -0.969984 -0.210073 -0.122473 -0.973392 -0.167987 -0.155846 -0.976285 -0.154888 -0.151253 -0.979046 -0.0985763 -0.178191 -0.978963 -0.0989764 -0.178425 -0.980492 -0.0445213 -0.191452 -0.996374 -0.0271793 -0.0806276 0.612168 -0.7328 -0.297076 0.975898 0.00541121 -0.218162 0.688841 -0.720186 0.0826487 0.960986 -0.21249 -0.177073 0.625331 -0.678946 -0.3847 0.838218 -0.457527 -0.296749 0.793885 -0.526096 -0.30491 0.734479 -0.574209 -0.361698 0.735233 -0.572611 -0.362695 0.71023 -0.606852 -0.356796 0.922026 -0.282266 -0.264941 0.942581 -0.274232 -0.190627 0.865705 -0.424727 -0.264882 0.850872 -0.389644 -0.352412 0.847813 -0.416626 -0.32808 0.945069 -0.252383 -0.207719 0.992705 -0.118732 -0.0209907 0.992843 -0.115828 -0.0291073 0.993345 -0.109481 -0.0357831 0.984833 -0.173396 -0.00615448 0.967377 -0.244047 -0.0679953 0.948872 -0.312779 0.0425668 0.906363 -0.410197 -0.10121 0.874597 -0.482778 0.0447792 0.85144 -0.523731 -0.0274805 0.750791 -0.588022 -0.300904 0.751111 -0.6586 0.0455943 0.82464 -0.564962 -0.0280521 0.956979 -0.281943 -0.068554 0.871891 -0.475101 -0.118676 0.887172 -0.453715 -0.0840737 0.805786 -0.585924 -0.0860297 0.799859 -0.592714 -0.0944214 0.714124 -0.698227 -0.0500526 0.725329 -0.68806 -0.0216904 0.631477 -0.76918 -0.0979782 0.646368 -0.761266 -0.0517975 0.612472 -0.788819 -0.0514104 0.621589 -0.78266 -0.0327145 0.622728 -0.781568 -0.0368956 0.661148 -0.749349 -0.0368544 0.985114 -0.160889 -0.0605485 0.986767 -0.112419 -0.116848 0.97605 -0.06322 0.208156 0.939421 0.00285696 -0.342752 0.961144 -0.00791267 -0.275936 0.961577 -0.0733676 -0.264551 0.974127 -0.100163 -0.202594 0.944149 -0.192121 -0.267715 0.956684 -0.281241 -0.0752303 0.861856 -0.328919 -0.386027 0.886558 -0.459223 0.0559464 0.768884 -0.472432 -0.430843 0.801047 -0.591534 0.0917147 0.658506 -0.580977 -0.478368 0.721394 -0.687839 -0.0804271 0.658041 -0.728863 -0.18905 0.55619 -0.719931 -0.415153 0.556195 -0.724123 -0.40779 0.592656 -0.707476 -0.385015 0.621057 -0.624219 -0.47396 0.940207 -0.242802 -0.238867 0.936538 -0.272114 -0.221024 0.855176 -0.463756 -0.231527 0.863187 -0.42298 -0.275673 0.752134 -0.597514 -0.277978 0.75505 -0.58873 -0.288611 0.65004 -0.705436 -0.282504 0.650747 -0.698303 -0.298163 0.585307 -0.756619 -0.291452 0.586205 -0.74856 -0.309873 0.605316 -0.732237 -0.312123 0.597894 -0.715314 -0.361731 0.601221 -0.70492 -0.376326 0.956586 -0.289184 0.0362777 0.932138 -0.325826 -0.157979 0.983703 -0.108518 -0.143359 0.983856 -0.109486 -0.141563 0.991141 -0.0079939 -0.132576 0.99446 -0.0339187 -0.0994889 0.998978 -0.00222065 -0.0451464 0.784893 -0.515303 -0.344102 0.589908 -0.78245 -0.199449 0.63328 -0.746938 -0.202583 0.630127 -0.756205 -0.176332 0.61024 -0.772614 -0.17514 0.607018 -0.780056 -0.151798 0.675211 -0.721169 -0.154936 0.673997 -0.724052 -0.146552 0.77575 -0.613242 -0.148819 0.778942 -0.607058 -0.157256 0.867224 -0.472909 -0.155818 0.867482 -0.472132 -0.156736 0.954062 -0.260672 -0.147704 0.948161 -0.299808 -0.105388 0.985589 -0.138317 -0.0973799 0.984992 -0.151011 -0.0835879 0.625952 -0.0367392 0.778996 0.756656 -0.0466791 0.652145 0.984723 -0.00218896 0.174117 0.680334 -0.396203 0.616579 0.99454 0.00781189 0.104066 0.996285 -0.0149385 0.0848138 0.998552 0.0117654 0.0524851 0.999486 -0.0144361 0.028635 0.999926 0 0.0121953 0.991241 -0.0134369 0.131378 0.986721 -0.0454234 0.155947 0.989838 0.0352748 0.137752 0.982466 -0.032024 0.183671 0.983902 -0.00597281 0.17861 0.979703 -0.0246401 0.198932 0.982761 -0.0508787 0.17774 0.977114 -0.0820685 0.196245 0.957994 -0.231107 0.169813 0.946422 -0.232646 0.223965 0.972657 -0.159161 0.169132 0.977894 -0.144517 0.151124 0.968699 -0.201139 0.145482 0.965254 -0.214942 0.148607 0.84676 -0.45357 0.277978 0.823064 -0.514607 0.240302 0.722978 -0.539654 0.431365 0.708078 -0.546602 0.447048 0.7141 -0.443336 0.54177 0.71494 -0.536409 0.448472 0.741673 -0.555563 0.375862 0.652775 -0.323463 0.685023 0.655356 -0.298132 0.693993 0.630733 -0.242706 0.737068 0.634503 -0.200117 0.746565 0.614544 -0.160906 0.772298 0.619217 -0.112812 0.777074 0.602619 -0.083077 0.793693 0.603416 -0.000631845 0.797426 0.615437 -0.0209756 0.787907 0.608545 -0.0264336 0.793079 0.608198 -0.0232358 0.793445 0.994219 -0.0655351 0.0850496 0.997233 -0.0454928 0.058795 0.990831 -0.0671003 0.117263 0.990505 -0.0670541 0.120017 0.986424 -0.0832487 0.141553 0.975698 -0.0846526 0.202107 0.977306 -0.0814139 0.195561 0.647686 -0.751876 0.123228 0.738293 -0.642069 0.20657 0.973084 -0.158924 0.166886 0.955194 -0.248054 0.161472 0.951684 -0.287702 0.10736 0.893474 -0.414459 0.172999 0.872128 -0.47523 0.116396 0.814386 -0.562554 0.142504 0.803513 -0.584271 0.113995 0.735368 -0.670795 0.0962715 0.714541 -0.698634 0.0366301 0.649438 -0.753587 0.101671 0.634057 -0.772323 0.0385843 0.794745 -0.0475199 0.60508 0.928129 -0.0562031 0.367991 0.980744 -0.0576958 0.186583 0.977724 -0.0633284 0.200112 0.654771 -0.722967 0.220441 0.713262 -0.653267 0.253968 0.718585 -0.631222 0.291882 0.776136 -0.539154 0.326996 0.777054 -0.520898 0.353345 0.834259 -0.39011 0.389647 0.832397 -0.376824 0.406348 0.872111 -0.229599 0.432096 0.869353 -0.221099 0.441974 0.888373 -0.0633412 0.454733 0.86999 -0.0506231 0.490464 0.619606 -0.141775 0.772003 0.636257 -0.115706 0.762751 0.619882 -0.248757 0.744222 0.652445 -0.205475 0.729449 0.6216 -0.363005 0.694147 0.672698 -0.305658 0.673833 0.626595 -0.470663 0.621172 0.695264 -0.40453 0.594108 0.636199 -0.562206 0.528371 0.6295 -0.645414 0.432632 0.677656 -0.557329 0.479757 0.665295 -0.497161 0.556968 0.687499 -0.436606 0.580276 0.670777 -0.389058 0.63142 0.692939 -0.300436 0.655419 0.677178 -0.269419 0.684722 0.692256 -0.170221 0.701289 0.68147 -0.154223 0.715412 0.689115 -0.0324209 0.723926 0.670334 -0.0185945 0.741827 0.992606 -0.11872 0.0252767 0.968806 -0.244407 -0.0409825 0.982874 -0.17628 0.0537113 0.909537 -0.411633 -0.0574507 0.938051 -0.34447 0.0374355 0.851012 -0.523468 -0.0419506 0.86248 -0.505428 -0.0258982 0.825646 -0.56295 -0.0373657 0.919669 -0.390988 0.0365631 0.894129 -0.445591 -0.0445145 0.962345 -0.271174 0.0188891 0.954511 -0.29773 -0.0163218 0.988244 -0.149832 0.0304154 0.988271 -0.149588 0.030712 0.997051 -0.0481889 0.0597212 0.998248 -0.0441989 0.0393426 0.993351 -0.0556079 0.100806 0.984952 -0.15022 0.0854579 0.985191 -0.146277 0.0894588 0.960272 -0.27138 0.065043 0.965844 -0.238885 0.100395 0.942917 -0.323133 0.0805836 0.864521 -0.440392 -0.242193 0.824854 -0.565109 -0.0163491 0.751785 -0.65919 -0.0169769 0.775928 -0.629915 0.0338242 0.706313 -0.707812 -0.0111621 0.661492 -0.749739 0.0178522 0.623137 -0.782082 -0.00691112 0.706126 -0.706881 -0.0413047 0.824633 -0.564515 0.0360954 0.775783 -0.626439 -0.0757284 0.894139 -0.447671 0.0102944 0.860994 -0.502519 -0.0785144 0.954256 -0.298794 0.0108823 0.93874 -0.340915 -0.0504374 0.988315 -0.149546 0.0294868 0.98469 -0.174263 -0.00414883 0.997353 -0.0582432 0.043529 0.99804 -0.0590684 0.0206644 0.676141 -0.667344 0.312227 0.766414 -0.589396 0.255385 0.711257 -0.671878 0.206624 0.794605 -0.58987 0.143724 0.818976 -0.549586 0.165024 0.830089 -0.555746 0.0458135 0.892914 -0.391444 0.222432 0.773846 -0.0528795 0.631162 0.762302 -0.185274 0.620136 0.769725 -0.198805 0.60663 0.74554 -0.320776 0.584185 0.754695 -0.345332 0.557836 0.719088 -0.454589 0.525606 0.7263 -0.490492 0.481565 0.690175 -0.566537 0.450217 0.691686 -0.61034 0.386077 0.653957 -0.667839 0.355431 0.658588 -0.726529 0.196006 0.639754 -0.746482 0.182971 0.646524 -0.752972 0.12264 0.630018 -0.776564 0.00506615 0.612963 -0.789451 0.0323025 0.680348 -0.396085 0.616639 0.708131 -0.484851 0.513293 0.718336 -0.491544 0.492319 0.652114 -0.629416 0.42259 0.694637 -0.666067 0.271724 0.68688 -0.676719 0.265041 0.664577 -0.739444 0.107514 0.727273 -0.68353 0.0621436 0.763313 -0.64013 0.0871 0.767176 -0.641374 0.00899147 0.869062 -0.486993 0.0869958 0.870979 -0.487714 0.0594167 0.914786 -0.389979 0.105275 0.925526 -0.368732 0.0862492 0.936471 -0.341435 0.0802719 -9.30088e-07 -0.999048 -0.0436193 -4.05605e-07 -0.999048 -0.04362 8.82779e-07 -0.999048 -0.0436193 -5.16464e-07 -0.999048 -0.0436195 -7.36382e-07 -0.999048 -0.0436194 -6.93221e-07 -0.999048 -0.0436195 -7.43629e-07 -0.999048 -0.0436194 -5.94561e-07 -0.999048 -0.0436196 2.02872e-07 -0.999048 -0.0436194 0 -0.999048 -0.0436195 -1.64388e-06 -0.999048 -0.0436238 -1.05764e-07 -0.999048 -0.0436196 -2.95581e-07 -0.999048 -0.0436186 -6.82372e-07 -0.999048 -0.0436193 -6.75308e-07 -0.999048 -0.0436195 -0.0810395 -0.996097 -0.0349766 -0.105969 -0.993878 -0.031243 -0.580936 -0.813521 0.0263956 -0.482038 -0.876062 0.0124226 -0.404468 -0.914548 0.00258939 -0.396423 -0.918067 0.00137373 -0.280909 -0.959657 -0.0121747 -0.272917 -0.961946 -0.01331 -0.192121 -0.98111 -0.0226387 -0.526186 -0.850213 0.0163331 -0.643773 -0.764428 0.0347293 -0.721617 -0.69082 0.045126 -0.811031 -0.58169 0.0621734 -0.79095 -0.609169 0.057545 -0.854015 -0.515885 0.067242 -0.875133 -0.478632 0.0710882 -0.904094 -0.420324 0.0770849 -0.922526 -0.377598 0.0797794 -0.950304 -0.298902 0.0870676 -0.978146 -0.185473 0.0939654 -0.973425 -0.209118 0.0933434 -0.99306 -0.0591218 0.10167 -0.992825 -0.0630572 0.101597 -0.994522 0 0.104528 -0.994522 3.60255e-06 0.104531 -0.994522 1.17663e-06 0.104526 -0.994522 -7.67797e-07 0.104529 -0.994522 1.2716e-07 0.104528 -0.994522 0 0.104528 -0.994522 9.62302e-08 0.104528 -0.994511 -3.93186e-05 0.104631 -0.994512 -3.74604e-05 0.104627 -0.994523 9.98949e-06 0.104516 -0.99452 -8.85213e-06 0.104546 -0.994523 6.47298e-06 0.10452 -0.994523 5.69154e-06 0.104521 -0.994522 2.61931e-06 0.104531 -0.994524 8.1339e-06 0.104512 -0.994515 -2.22444e-05 0.104589 -0.994525 6.64044e-06 0.104501 -0.994522 1.32429e-06 0.10453 -0.994522 -2.21394e-06 0.104523 -0.994522 -2.01832e-06 0.104524 -0.994522 -1.177e-07 0.104528 -0.994522 -3.86755e-06 0.104523 -0.994522 5.31054e-07 0.104528 -0.994522 -7.14072e-07 0.104529 -0.994521 -1.04417e-05 0.104536 -0.994522 3.72354e-07 0.104529 -0.994522 5.01406e-06 0.104525 -0.994522 2.81307e-06 0.104531 -0.994522 1.33539e-06 0.104529 -0.994522 -4.6137e-06 0.104523 -0.994522 -2.92233e-06 0.104529 -0.994521 -5.60587e-06 0.104534 -0.994523 7.72459e-06 0.10452 -0.994521 -6.15317e-06 0.104537 -0.994522 1.72841e-06 0.104531 -0.99452 1.33004e-05 0.104551 -0.994524 -1.24605e-05 0.104511 -0.994521 1.87159e-06 0.104535 -0.994524 -1.44589e-05 0.10451 -0.994523 1.96898e-05 0.104516 -0.99452 -2.04908e-05 0.104544 -0.994527 5.26025e-05 0.104482 -0.99452 -2.04415e-05 0.104543 -0.994523 9.6343e-06 0.10452 -0.994521 -6.56913e-06 0.104534 -0.994521 -8.48832e-06 0.104536 -0.994522 2.66468e-07 0.104528 -0.99452 -1.11509e-05 0.104548 -0.994522 1.87003e-06 0.104525 -0.994522 3.59436e-07 0.104528 -0.994522 1.2067e-06 0.104528 -0.99452 3.42922e-05 0.104544 -0.994521 8.98469e-06 0.104533 -0.994522 2.17552e-06 0.104532 -0.994522 1.23296e-06 0.104531 -0.994522 -5.47296e-07 0.104529 -0.994522 -1.58918e-06 0.104527 -0.994521 6.23413e-06 0.104533 -0.994522 3.93206e-06 0.104531 -0.994523 -7.63366e-06 0.104523 -0.994527 -7.59706e-05 0.104481 -0.99452 2.1993e-05 0.104545 -0.994523 -2.9854e-05 0.104516 -0.991566 0.0816416 0.100653 -0.989712 0.101936 0.100392 -0.977555 0.188284 0.0945256 -0.95893 0.269307 0.0890305 -0.956696 0.27726 0.0886587 -0.917034 0.390879 0.0791346 -0.766151 0.640666 0.050591 -0.875888 0.477048 0.0724313 -0.853567 0.516636 0.0671613 -0.913608 0.398925 0.0786112 -0.493504 0.869626 0.0143357 -0.574356 0.818243 0.0243774 -0.619509 0.784364 0.0313326 -0.661992 0.748613 0.0366898 -0.695128 0.71767 0.0417925 -0.725145 0.687048 0.0461441 -0.809588 0.583856 0.0606575 -0.449709 0.893122 0.0097268 -0.500475 0.865624 0.0148159 -0.364536 0.931186 -0.00233426 -0.391643 0.920117 0.000106226 -0.241598 0.970243 -0.016078 -0.268319 0.963231 -0.0138499 -0.160425 0.9867 -0.0262147 -0.0941658 0.995025 -0.0325441 -0.0626152 0.997353 -0.0369655 2.02872e-07 0.999048 -0.0436194 0 0.999048 -0.0436195 -6.01023e-07 0.999048 -0.0436196 -3.92346e-07 0.999048 -0.0436196 -2.45117e-07 0.999048 -0.0436196 -1.90741e-06 0.999048 -0.0436189 -7.6251e-07 0.999048 -0.0436195 -8.27545e-07 0.999048 -0.0436194 -4.81318e-07 0.999048 -0.0436197 -2.86323e-07 0.999048 -0.0436199 -1.82565e-06 0.999048 -0.0436196 -1.22588e-06 0.999048 -0.0436206 -5.64247e-07 0.999048 -0.0436193 -5.55954e-07 0.999048 -0.0436195 0.607777 0.0438726 0.792895 0.709531 0.306173 0.634684 0.63598 0.437261 0.635871 0.724093 0.398657 0.562815 0.688843 0.517591 0.507539 0.755499 0.468319 0.458147 0.718559 0.554362 0.419948 0.791433 0.501255 0.349823 0.918262 0.390812 0.063722 0.925704 0.358535 0.120522 0.908163 0.407475 0.0959416 0.86514 0.485303 0.126544 0.936083 0.313253 0.160068 0.941685 0.264647 0.207823 0.854016 0.447179 -0.26587 0.971497 0.185523 0.147562 0.969016 0.199819 0.14519 0.965849 0.212616 0.148089 0.999926 0 0.0121953 0.99968 0.00976497 0.0233162 0.998549 -0.0120407 0.0524971 0.99714 0.0148321 0.074111 0.994526 -0.008868 0.104111 0.99219 0.0155853 0.123757 0.991265 0.00906065 0.131574 0.986592 -0.0032622 0.163175 0.987451 0.00929422 0.157652 0.981069 0.00832645 0.193481 0.982098 0.0442854 0.183089 0.978671 0.0174558 0.204691 0.982267 0.060936 0.177308 0.990831 0.0671003 0.117263 0.993351 0.0556079 0.100806 0.994219 0.0655351 0.0850496 0.997172 0.0478432 0.0579527 0.992798 0.118743 -0.0159113 0.814386 0.562554 0.142504 0.676258 0.463878 0.57227 0.672963 0.591761 0.443778 0.703361 0.528072 0.47584 0.68345 0.656611 0.318996 0.73588 0.567136 0.369917 0.872128 0.47523 0.116396 0.893474 0.414459 0.172999 0.964356 0.249609 0.0878192 0.984723 0.00218896 0.174117 0.977724 0.0633284 0.200112 0.980744 0.0576958 0.186583 0.973084 0.158924 0.166886 0.94508 0.285705 0.158736 0.756656 0.0466791 0.652145 0.86999 0.0506231 0.490464 0.654782 0.38061 0.652991 0.638109 0.290638 0.712984 0.644306 0.257587 0.720083 0.627539 0.198036 0.752978 0.633708 0.144623 0.759933 0.62202 0.113289 0.774762 0.62619 0.0268551 0.779208 0.648881 0.535951 0.540102 0.698043 0.403388 0.591619 0.660939 0.421353 0.620984 0.697723 0.276779 0.660739 0.672583 0.292499 0.679762 0.693745 0.156677 0.702972 0.679997 0.167563 0.713812 0.689397 0.0104524 0.724309 0.670175 0.0286092 0.741651 0.9393 0.342282 -0.0236182 0.969375 0.244551 0.022492 0.984689 0.174277 -0.00378668 0.996715 0.0577509 0.0567741 0.997748 0.0586427 0.0325699 0.958673 0.231501 0.165387 0.945804 0.23246 0.226752 0.968193 0.2398 0.0713958 0.958019 0.271224 0.0929385 0.977389 0.0811447 0.195258 0.976899 0.0823109 0.197212 0.987737 0.0628179 0.142935 0.975709 0.116215 0.185704 0.989543 0.066921 0.127771 0.976193 0.144144 0.16208 0.985478 0.146356 0.0861047 0.984663 0.150228 0.0887176 0.777022 0.629249 -0.0167969 0.824854 0.565109 -0.0163491 0.86248 0.505428 -0.0258982 0.851011 0.523469 -0.0419515 0.91101 0.4123 0.00837468 0.997764 0.0459939 0.0485006 0.988858 0.14872 0.00644088 0.984359 0.175141 0.0190365 0.954341 0.29703 -0.0317301 0.939313 0.342971 -0.00781541 0.893903 0.445177 -0.0524847 0.862493 0.505804 -0.0163814 0.825526 0.562677 -0.0436185 0.776842 0.629691 0.00237332 0.767362 0.641203 -0.00385793 0.704842 0.707779 0.0473932 0.646524 0.752972 0.12264 0.66649 0.733585 0.132829 0.637352 0.741202 0.210717 0.725639 0.636544 0.261266 0.706629 0.647737 0.284802 0.783835 0.524856 0.331857 0.769535 0.534957 0.348765 0.838121 0.379087 0.392232 0.828554 0.387675 0.403987 0.873564 0.222015 0.433123 0.867869 0.228604 0.44107 0.888373 0.0633412 0.454733 0.928129 0.0562031 0.367991 0.803513 0.584271 0.113995 0.712089 0.696237 0.0904609 0.739485 0.673111 0.00913431 0.629977 0.767353 0.119579 0.652606 0.756407 0.044207 0.612963 0.789451 0.032302 0.630018 0.776564 0.005066 0.623137 0.782082 -0.00691141 0.704836 0.707777 0.0475303 0.661132 0.74933 -0.0375383 0.751778 0.659184 0.0175169 0.603399 0.00765441 0.797403 0.618324 0.0265715 0.785474 0.605043 0.0471875 0.794793 0.613188 0.111788 0.781987 0.613239 0.111708 0.781959 0.624852 0.197233 0.75542 0.628291 0.191869 0.753947 0.642412 0.292509 0.70834 0.602242 0.35247 0.716289 0.654472 0.381751 0.652636 0.664243 0.496444 0.55886 0.695641 0.517724 0.498042 0.664014 0.584613 0.466169 0.665792 0.678477 0.310469 0.694637 0.666067 0.271724 0.68688 0.676719 0.265041 0.699303 0.687239 0.196668 0.774163 0.575901 0.262699 0.771983 0.574381 0.272266 0.801047 0.53862 0.261176 0.853389 0.496464 0.158901 0.87929 0.445382 0.168769 0.997101 0.0465522 0.0601827 0.988236 0.149835 0.0306404 0.988279 0.14958 0.0304933 0.962607 0.270793 -0.00766099 0.954292 0.298734 0.0091701 0.920358 0.390344 -0.0239236 0.894066 0.447742 0.0131434 0.872858 0.487957 -0.0040046 0.823964 0.564472 0.049537 0.829708 0.55558 0.0539951 0.760669 0.638659 0.116179 0.725431 0.682442 0.0895671 0.727273 0.68353 0.0621437 0.664577 0.739444 0.107514 0.639755 0.746482 0.182971 0.685485 0.695598 0.215067 0.630487 0.699312 0.336822 0.709079 0.580298 0.400577 0.673869 0.596193 0.436411 0.736896 0.46463 0.491022 0.70899 0.479917 0.516732 0.759697 0.3262 0.562542 0.740644 0.339531 0.579798 0.771364 0.187201 0.608238 0.760643 0.19673 0.618643 0.773846 0.0528795 0.631162 0.794745 0.0475199 0.60508 0.99058 -0.136934 0 0.980397 -0.195013 0.0281268 0.693258 -0.72069 0 0.785417 -0.618967 0 0.831041 -0.555284 0.0321042 0.891072 -0.453861 0 0.94483 -0.32756 0 0.572201 -0.820046 0.0105576 0.555439 -0.831278 0.0215304 0.41894 -0.908014 0 0.290288 -0.956939 0 0.194982 -0.980236 0.0334702 0.0980171 -0.995185 0 1 0 0 1 0 0 1 0 0 0.117692 0.99305 0 0.194991 0.980279 0.0321072 0.309168 0.951007 0 0.41894 0.908014 0 0.522826 0.852285 0.0162318 0.555282 0.831043 0.032107 0.649565 0.760306 0 0.773015 0.634388 0 0.831004 0.555259 0.0334673 0.881918 0.471403 0 0.956941 0.290283 0 0.980236 0.194981 0.033469 0.995185 0.0980194 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.113939 0.0966768 0.988773 0.386457 0.329316 0.861511 0.289892 0.247487 0.924507 0.787962 0.611494 0.0720484 0.707458 0.609283 0.358157 0.52702 0.452926 0.719102 0.695107 0.606327 0.386255 0.745237 0.543561 0.386217 0.740177 0.542709 0.396994 0.800187 0.449967 0.396523 0.791426 0.448575 0.415241 0.85211 0.318694 0.415143 0.839807 0.318517 0.439627 0.867309 0.231298 0.440769 0.863134 0.234923 0.447001 0.185881 0.140022 0.972544 0.187968 0.137405 0.972516 0.185897 0.136452 0.973048 0.201081 0.113457 0.972982 0.19738 0.112061 0.973901 0.212459 0.0799127 0.973897 0.207281 0.0788343 0.9751 0.213484 0.0573969 0.975259 0.211928 0.0579502 0.975566 0.216979 0.0376792 0.975449 0.210087 0.0375278 0.976962 0.21292 0.0104731 0.977014 0.205763 0.0111045 0.978539 0.205853 -0.00148857 0.978582 0.20206 -0.00098183 0.979373 0.498526 0.413348 0.761981 0.523353 0.381966 0.761711 0.518217 0.379916 0.766234 0.5604 0.315446 0.765798 0.551361 0.31244 0.773552 0.593553 0.222346 0.773471 0.580804 0.220202 0.783695 0.598895 0.160075 0.784666 0.595018 0.161895 0.787238 0.608715 0.10468 0.786453 0.591811 0.104923 0.799219 0.599988 0.0285549 0.7995 0.582256 0.030697 0.812426 0.582675 -0.00469134 0.812692 0.573222 -0.00316413 0.819394 0.876104 0.181217 0.446768 0.821885 0.141766 0.551731 0.870702 0.117259 0.477628 0.877829 0.0412523 0.477195 0.859771 0.0454753 0.508651 0.860728 -0.00719701 0.509014 0.85075 -0.00465039 0.52555 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.0116912 0.999932 -0.0387007 0.0351271 0.998633 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.00492782 -0.0608025 0.998138 0.00273111 -0.0144015 0.999893 0 -0.00955179 0.999954 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.294106 -0.251869 0.921989 0.52702 -0.452926 0.719102 0.748962 -0.651554 0.120555 0.202059 -0.00053039 0.979373 0.850758 -0.00166883 0.525556 0.70275 -0.612226 0.362382 0.698927 -0.601867 0.386337 0.761681 -0.520715 0.385613 0.756047 -0.51408 0.405111 0.837002 -0.368315 0.404687 0.825854 -0.359791 0.434184 0.87417 -0.215343 0.435263 0.862614 -0.208079 0.461085 0.882978 -0.088825 0.460934 0.863511 -0.0824165 0.497551 0.867169 0.00146612 0.498011 0.573221 -0.00106514 0.8194 0.588992 0.000781271 0.808139 0.586791 -0.0562333 0.807784 0.606587 -0.0610309 0.792671 0.592446 -0.143182 0.792784 0.605161 -0.149077 0.782021 0.572364 -0.249627 0.78108 0.585296 -0.257553 0.768827 0.528294 -0.359472 0.769211 0.535449 -0.366051 0.761118 0.494192 -0.418658 0.761905 0.426519 -0.317664 0.84686 0.208422 7.33767e-05 0.978039 0.207718 -0.0202219 0.97798 0.215796 -0.0220184 0.97619 0.210733 -0.0512581 0.976199 0.21598 -0.0535034 0.974931 0.204491 -0.0894732 0.974771 0.209921 -0.0926358 0.97332 0.189406 -0.129113 0.973373 0.192452 -0.131767 0.97242 0.177446 -0.150562 0.972545 0.132065 -0.0848999 0.987599 0.723672 0.575094 0.381531 0.955293 0.0112837 0.295446 0.963636 0.261801 0.0535318 0.82163 0.47973 0.30787 0.7723 0.557107 0.305262 0.725093 0.59743 0.342517 0.897967 0.29474 0.326777 0.934247 0.273438 0.228941 0.856587 0.4537 0.245794 0.830629 0.411307 0.375343 0.829368 0.440422 0.343769 0.978429 0.1492 0.142886 0.97874 0.147099 0.142936 0.9584 0.19794 0.205645 0.924182 0.316806 0.213358 0.9817 0.155299 0.110215 0.948007 0.312856 -0.0583467 0.961446 0.273942 0.0240365 0.986358 0.163035 0.0227506 0.982006 0.187334 -0.0238935 0.992813 0.116551 0.0271635 0.839299 0.515873 -0.171615 0.899594 0.435775 0.0288055 0.93186 0.361719 0.0282105 0.875555 0.471551 0.105086 0.797679 0.602682 -0.0219822 0.793742 0.608255 0.000702303 0.695198 0.716199 0.0613051 0.707404 0.706171 -0.0300316 0.635067 0.770958 0.0481007 0.638672 0.768892 0.0300652 0.659017 0.746551 0.0914216 0.682358 0.729194 0.0516127 0.737653 0.671312 0.0721634 0.735685 0.673141 0.0751633 0.814301 0.576916 0.0638881 0.805265 0.587087 0.0829335 0.994386 0.00748719 0.10555 0.99887 0.0354006 0.0317087 0.992339 0.118955 0.0333586 0.990252 0.104273 0.0923435 0.982312 0.182221 0.0431051 0.939943 -0.00670609 0.341265 0.961922 0.00648425 0.273247 0.956997 0.0470365 0.286259 0.977282 0.0979916 0.187931 0.964271 0.125845 0.233118 0.816423 0.577437 0.00451548 0.827457 0.467909 0.310445 0.896644 0.442556 -0.0131783 0.88725 0.334892 0.31723 0.96002 0.269679 0.075063 0.959818 0.256513 0.113803 0.951285 0.193571 0.239973 0.681601 0.708017 0.18475 0.696092 0.696943 0.172413 0.739901 0.671453 0.0411938 0.742192 0.646014 0.178375 0.802345 0.586033 0.113171 0.711527 0.625277 0.320559 0.652202 0.680741 0.333503 0.630057 0.686918 0.362176 0.611993 0.727511 0.310149 0.595085 0.732124 0.331464 0.596726 0.723262 0.347577 0.637316 0.70231 0.317158 0.635258 0.69164 0.343629 0.663215 0.645065 0.379522 0.992094 0.0109917 0.125013 0.990042 0.00269969 0.140749 0.983432 0.103253 0.149001 0.983754 0.104919 0.145672 0.952687 0.261268 0.15533 0.952889 0.280379 0.11572 0.895875 0.439723 0.0636572 0.909349 0.389517 0.146153 0.867942 0.489723 0.0827524 0.656277 0.73196 0.183125 0.651865 0.744392 0.144752 0.630118 0.76312 0.143522 0.62674 0.770082 0.119039 0.68708 0.716317 0.121698 0.687891 0.714539 0.127436 0.778654 0.613794 0.130213 0.786279 0.598869 0.152058 0.864915 0.478301 0.152149 0.868609 0.466486 0.16706 0.93231 0.32287 0.16295 0.938855 0.2932 0.180511 0.971213 0.209326 0.113703 0.984223 0.138361 0.110276 0.978579 0.149423 0.141621 0.55755 0.803733 0.20773 0.734015 0.605094 0.308357 0.641869 0.705519 0.300412 0.640514 0.722678 0.259767 0.614523 0.745833 0.257089 0.613139 0.754342 0.234584 0.66276 0.70962 0.239141 0.663545 0.703864 0.253541 0.747151 0.611974 0.25933 0.7519 0.597818 0.277956 0.849015 0.44891 0.278663 0.846051 0.465921 0.259069 0.929037 0.272665 0.250088 0.930628 0.250166 0.267112 2.81228e-05 0.100618 0.994925 -0.000212548 0.0469032 0.998899 0.00271858 0.0351533 0.999378 0 0.0019624 0.999998 3.35563e-05 0.137486 0.990504 -0.010648 0.214231 0.976725 0.0209419 0.112131 0.993473 -0.0204767 0.265623 0.96386 0.0192708 0.136933 0.990393 -0.0033976 0.230592 0.973045 -7.04026e-06 0.295315 0.9554 1.73316e-05 0.342304 0.939589 -4.73461e-05 0.342778 0.939416 -5.17649e-05 0.421519 0.90682 -0.00217373 0.431276 0.902217 -6.10051e-05 0.474353 0.880334 0.000165379 0.509117 0.860698 2.30001e-05 0.508116 0.861289 2.54457e-05 0.542188 0.840257 0.00100509 0.558847 0.82927 -0.00134139 0.580559 0.814217 0.00327049 0.632731 0.774365 -0.00169043 0.649445 0.760407 0.00024779 0.687307 0.726367 8.0651e-06 0.84414 0.536124 8.03198e-06 0.82202 0.569459 0.000582706 0.802128 0.597152 0.0044487 0.813423 0.581656 -0.00882542 0.748057 0.663575 -0.00492266 0.754655 0.656103 3.81946e-07 0.706261 0.707951 3.20305e-07 0.695901 0.718138 5.24802e-05 0.691486 0.72239 5.05686e-06 0.929534 0.368736 6.01623e-06 0.911643 0.410983 -0.00051462 0.914801 0.403904 0.00235469 0.886428 0.46286 0.00847806 0.877372 0.479736 -0.00571001 0.829872 0.557925 0.000777356 0.931044 0.364906 -0.00110008 0.958135 0.286314 -0.000534182 0.957529 0.288335 0.000158921 0.974108 0.226085 -1.55034e-05 0.974612 0.223902 -0.000869534 0.996308 0.085842 -1.89571e-05 0.985661 0.168738 -0.0020235 0.984044 0.177913 0.00185393 0.995145 0.0984014 0.000214399 0.999199 0.0400175 -0.00332554 0.999834 -0.0179434 0 0.999934 -0.0115107 -0.0789622 0.686896 0.722454 -0.0753868 0.229215 0.970452 -0.425297 0.472615 0.771853 -0.426436 0.781387 0.455617 -0.991247 0.08003 0.104998 -0.9496 0.215926 0.227234 -0.878233 0.401351 0.260045 -0.882346 0.415089 0.221737 -0.954669 0.241726 0.173712 -0.957352 0.247845 0.148493 -0.961256 0.253387 0.108541 -0.990963 0.101381 0.0878346 -0.991471 0.0816798 0.101556 -0.245507 0.847985 0.469731 -0.252339 0.843077 0.474917 -0.245248 0.80382 0.541966 -0.605524 0.710194 0.359116 -0.433546 0.812963 0.388753 -0.427358 0.818566 0.383816 -0.253151 0.882126 0.397201 -0.245468 0.887038 0.391037 -0.0927632 0.915285 0.39198 -0.0762729 0.925159 0.371839 -0.0780754 0.808365 0.583482 -0.0807018 0.816833 0.571202 -0.0876172 0.831576 0.548456 -0.0760614 0.83941 0.53815 -0.082852 0.876997 0.4733 -0.0732639 0.882009 0.465502 -0.0817433 0.906607 0.413982 -0.621664 0.780611 0.0646592 -0.0804978 0.970382 0.227771 -0.885175 0.431055 0.175091 -0.7707 0.604934 0.200193 -0.768089 0.609454 0.19648 -0.615973 0.758264 0.21357 -0.610916 0.763851 0.20812 -0.437547 0.872903 0.215856 -0.429998 0.878358 0.208782 -0.255178 0.944148 0.208492 -0.24581 0.948427 0.200161 -0.0943706 0.97623 0.195112 -0.0755224 0.982082 0.172661 -0.440103 0.896676 0.0477617 -0.498117 0.866356 0.0361435 -0.61614 0.785294 0.060706 -0.764197 0.590269 0.259974 -0.612683 0.734204 0.292513 -0.607916 0.739937 0.287979 -0.435502 0.846125 0.307262 -0.428415 0.8519 0.301208 -0.25421 0.916769 0.308077 -0.245423 0.921586 0.300745 -0.0839156 0.950733 0.298439 -0.0760712 0.953465 0.291749 -0.596128 0.407939 0.691533 -0.59214 0.412905 0.692011 -0.598569 0.487561 0.63561 -0.0791436 0.135855 0.987563 -0.0789399 0.00193935 0.996877 -0.101063 0.0463568 0.993799 -0.58925 0.0313829 0.807341 -0.420685 0.0360855 0.906489 -0.419249 0.0368486 0.907123 -0.245893 0.0400033 0.968471 -0.24453 0.0406565 0.968789 -0.0925116 0.0422258 0.994816 -0.0788358 0.111208 0.990665 -0.242507 0.522037 0.817721 -0.250267 0.616108 0.746845 -0.421442 0.569976 0.705346 -0.427989 0.632651 0.645428 -0.597252 0.551777 0.582093 -0.602799 0.595319 0.531252 -0.752816 0.478576 0.451921 -0.758773 0.521964 0.389636 -0.873131 0.374713 0.311823 -0.879028 0.398764 0.261336 -0.952431 0.232527 0.196996 -0.954824 0.240602 0.174418 -0.0759494 0.42869 0.900254 -0.0804994 0.505675 0.85896 -0.106067 0.539159 0.835499 -0.108887 0.536356 0.836938 -0.0770357 0.576872 0.813194 -0.0794056 0.691262 0.718228 -0.0840184 0.720105 0.68876 -0.244379 0.694917 0.676291 -0.251167 0.749446 0.612573 -0.42426 0.693535 0.582248 -0.430437 0.734479 0.524656 -0.601386 0.640688 0.47734 -0.607174 0.672186 0.423682 -0.0824765 0.644874 0.759825 -0.0815324 0.64441 0.760321 -0.24364 0.621541 0.744531 -0.250648 0.689703 0.679327 -0.422955 0.638023 0.643456 -0.429276 0.688211 0.584883 -0.599396 0.600201 0.529607 -0.604823 0.635808 0.479517 -0.786025 0.478391 0.391543 -0.758068 0.540134 0.365498 -0.763102 0.562181 0.318791 -0.983418 0.0205151 0.180192 -0.104867 0.208599 0.972363 -0.242327 0.201885 0.948957 -0.246314 0.199328 0.948471 -0.417443 0.18436 0.889805 -0.420778 0.181841 0.888752 -0.588122 0.158836 0.793022 -0.590547 0.156546 0.791674 -0.739038 0.126466 0.661687 -0.740496 0.124602 0.660409 -0.857538 0.0899417 0.506497 -0.858215 0.0886428 0.505579 -0.938224 0.0525361 0.342018 -0.938435 0.0518238 0.341547 -0.98299 0.0172297 0.182849 -0.983263 0.0129314 0.181731 -0.983118 0.00287772 0.182953 -0.983162 0.00300953 0.182712 -0.937917 0.00932569 0.346733 -0.938171 0.00969806 0.346037 -0.857381 0.0165173 0.514418 -0.857983 0.0170784 0.513394 -0.739394 0.0238627 0.67285 -0.740395 0.0245411 0.671724 -0.590553 0.0305698 0.80642 -0.985115 0.0521811 0.163786 -0.985339 0.0474522 0.163876 -0.984315 0.0444812 0.170721 -0.988541 0.0754574 0.130742 -0.987581 0.0710522 0.140129 -0.986814 0.071421 0.145247 -0.986955 0.0675259 0.146149 -0.985958 0.0609355 0.155479 -0.985613 0.0648404 0.156085 -0.985594 0.0568296 0.159297 -0.863373 0.231886 0.448124 -0.862494 0.234231 0.448597 -0.866137 0.276829 0.41614 -0.865351 0.279176 0.416208 -0.868638 0.310314 0.386229 -0.86793 0.31256 0.386011 -0.746412 0.325398 0.580505 -0.744218 0.329207 0.581173 -0.749384 0.388872 0.535912 -0.747392 0.392706 0.535899 -0.752025 0.43623 0.494127 -0.941854 0.135808 0.307357 -0.941655 0.136778 0.307534 -0.943737 0.161777 0.288424 -0.943563 0.162755 0.288443 -0.946124 0.189389 0.262644 -0.950957 0.169192 0.258949 -0.946999 0.19759 0.253279 -0.871101 0.337479 0.356779 -0.248289 0.37492 0.893189 -0.417372 0.347255 0.83977 -0.422981 0.342612 0.838871 -0.589106 0.299681 0.75043 -0.59298 0.295541 0.749019 -0.740777 0.238977 0.627806 -0.742949 0.235767 0.626451 -0.859427 0.170201 0.482096 -0.860317 0.168194 0.481213 -0.939624 0.0995775 0.327401 -0.939831 0.0987341 0.327061 -0.984119 0.0313673 0.174716 -0.983835 0.0339586 0.175828 -0.0750216 0.997168 -0.00531732 -0.092066 0.995671 -0.0127546 -0.25604 0.966494 0.0182347 -0.265173 0.964084 0.0150108 -0.388706 0.920972 0.0267917 -0.692783 0.718421 0.0626315 -0.763544 0.641532 0.0737321 -0.777753 0.622719 0.0855606 -0.852661 0.516981 0.0754908 -0.892204 0.439775 0.102806 -0.912314 0.399409 0.0903079 -0.955889 0.277575 0.0960613 -0.0331455 0.753351 0.656783 -0.0859668 0.781278 0.618235 -0.244952 0.754503 0.608871 -0.251586 0.798892 0.54633 -0.425346 0.739747 0.521397 -0.431942 0.775982 0.459651 -0.603458 0.677289 0.420855 -0.609701 0.704777 0.362704 -0.760913 0.566443 0.31647 -0.766685 0.585683 0.263001 -0.881457 0.417879 0.220025 -0.886083 0.428319 0.177199 -0.957206 0.248915 0.147644 -0.0804925 0.340528 0.936783 -0.118735 0.391036 0.912684 -0.241352 0.379598 0.893115 -0.249707 0.516557 0.819033 -0.41949 0.478143 0.771626 -0.426782 0.564436 0.70659 -0.59492 0.492559 0.635182 -0.600677 0.546902 0.583169 -0.750187 0.43994 0.493631 -0.75465 0.474803 0.452841 -0.870403 0.339762 0.356314 -0.874732 0.37091 0.311882 -0.949251 0.217474 0.227218 -0.952574 0.231489 0.197522 -0.988826 0.0688822 0.132209 -0.988959 0.0766734 0.126812 -0.990227 0.0795994 0.114521 -0.990369 0.0732969 0.117457 -0.990688 0.0798605 0.110273 -0.959905 0.252168 0.122452 -0.959799 0.252946 0.121669 -0.889858 0.436655 0.132233 -0.889116 0.438793 0.130129 -0.774685 0.617392 0.136714 -0.772479 0.620967 0.132949 -0.619062 0.773826 0.133997 -0.614694 0.778235 0.128461 -0.439164 0.889785 0.124172 -0.432575 0.893964 0.117078 -0.255504 0.960619 0.109222 -0.247292 0.963661 0.101019 -0.0839994 0.99223 0.0917837 -0.0828517 0.992429 0.090662 -0.983166 0 0.182713 -0.983166 0 0.182713 -0.938215 0 0.346053 -0.938215 0 0.346053 -0.858108 0 0.513469 -0.858108 0 0.513469 -0.740618 0 0.671926 -0.740618 0 0.671926 -0.590829 0 0.806797 -0.590829 0 0.806797 -0.420959 0 0.90708 -0.420959 0 0.90708 -0.24609 0 0.969247 -0.24609 0 0.969247 -0.0789401 0 0.996879 -0.0789401 0 0.996879 -0.983166 0 0.182713 -0.983166 0 0.182713 -0.938215 0 0.346054 -0.938215 0 0.346054 -0.858108 0 0.513469 -0.858108 0 0.513469 -0.740618 0 0.671926 -0.740618 0 0.671926 -0.590829 0 0.806797 -0.590829 0 0.806797 -0.420959 0 0.90708 -0.420959 0 0.90708 -0.24609 0 0.969247 -0.24609 0 0.969247 -0.0789401 0 0.996879 -0.0789401 0 0.996879 -0.590553 -0.0305698 0.80642 -0.102332 -0.392097 0.914215 -0.401661 -0.915359 0.0280378 -0.0747 -0.877814 0.473141 -0.0808597 -0.905887 0.415729 -0.0927631 -0.915286 0.391979 -0.0762739 -0.925158 0.371839 -0.0803619 -0.939347 0.333421 -0.090208 -0.950081 0.298678 -0.061972 -0.960705 0.270564 -0.102594 -0.979121 0.175489 -0.0755932 -0.978051 0.194171 -0.0829076 -0.993146 0.0823901 -0.0702062 -0.993383 0.0908947 -0.0849811 -0.996357 0.00711551 -0.110781 -0.993707 -0.0165823 -0.105443 -0.994079 -0.0262527 -0.9496 -0.215926 0.227234 -0.771973 -0.620763 0.136786 -0.77501 -0.617823 0.132869 -0.767515 -0.608806 0.200691 -0.771043 -0.605868 0.196004 -0.763669 -0.58923 0.263851 -0.888838 -0.438699 0.132326 -0.890052 -0.43692 0.130034 -0.884852 -0.430706 0.177564 -0.886294 -0.428889 0.174749 -0.881158 -0.417293 0.22232 -0.882541 -0.415872 0.219482 -0.877979 -0.400616 0.26203 -0.959702 -0.252917 0.122497 -0.959983 -0.252272 0.121623 -0.957085 -0.248781 0.14865 -0.957444 -0.248083 0.147498 -0.954554 -0.24149 0.174667 -0.954911 -0.240933 0.173483 -0.952333 -0.232231 0.197812 -0.952649 -0.231858 0.19673 -0.949251 -0.217475 0.227218 -0.986222 -0.0625986 0.153127 -0.986714 -0.0658503 0.148524 -0.986935 -0.0706512 0.144802 -0.987288 -0.0697971 0.142798 -0.988196 -0.0738175 0.13424 -0.988129 -0.0739412 0.134658 -0.988991 -0.076396 0.126729 -0.988925 -0.0765757 0.127138 -0.989836 -0.0786773 0.118464 -0.990092 -0.0778309 0.116874 -0.990632 -0.0804853 0.110323 -0.990831 -0.0799034 0.108945 -0.991487 -0.0801048 0.102649 -0.763377 -0.563668 0.31549 -0.758068 -0.540134 0.365497 -0.774729 -0.504763 0.3808 -0.757399 -0.508852 0.409165 -0.7525 -0.47685 0.454266 -0.754831 -0.476663 0.450581 -0.749895 -0.43809 0.495716 -0.752173 -0.438212 0.492145 -0.747108 -0.39064 0.537801 -0.749496 -0.391079 0.534147 -0.74395 -0.32699 0.582766 -0.746464 -0.327761 0.579106 -0.740553 -0.23688 0.628863 -0.742926 -0.237984 0.625639 -0.738919 -0.124988 0.6621 -0.740454 -0.12612 0.660167 -0.739394 -0.0238627 0.67285 -0.740395 -0.0245411 0.671724 -0.938171 -0.00969806 0.346037 -0.937917 -0.00932569 0.346733 -0.93843 -0.0524165 0.34147 -0.93819 -0.0519668 0.342197 -0.939837 -0.0993389 0.32686 -0.939577 -0.0990211 0.327703 -0.941878 -0.136427 0.307008 -0.941598 -0.136215 0.307959 -0.943774 -0.162349 0.287982 -0.984706 -0.0468118 0.167818 -0.985125 -0.0521386 0.163738 -0.9435 -0.162237 0.28894 -0.945505 -0.181565 0.270287 -0.984021 -0.043145 0.172747 -0.984478 -0.043949 0.169916 -0.983715 -0.0311315 0.177021 -0.983961 -0.0317289 0.175542 -0.98306 -0.0159116 0.182591 -0.983293 -0.0168834 0.181246 -0.983159 -0.00511303 0.182683 -0.982798 -0.00308382 0.184659 -0.983166 -0.000604783 0.182713 -0.857983 -0.0170784 0.513394 -0.857381 -0.0165173 0.514418 -0.858193 -0.0897041 0.505428 -0.857463 -0.0889167 0.506804 -0.860313 -0.169588 0.480729 -0.859299 -0.168902 0.482781 -0.863415 -0.233341 0.447288 -0.862341 -0.232891 0.449589 -0.866212 -0.278169 0.415089 -0.865189 -0.277944 0.417368 -0.868732 -0.311498 0.385063 -0.867764 -0.311476 0.387257 -0.871213 -0.338586 0.355455 -0.0853701 -0.0785564 0.993248 -0.082111 -0.380674 0.921057 -0.077489 -0.272791 0.958948 -0.117346 -0.208161 0.97103 -0.0795592 -0.178119 0.980787 -0.0788357 -0.111204 0.990666 -0.0937864 -0.643298 0.75985 -0.0799744 -0.61324 0.785838 -0.0741321 -0.54165 0.837329 -0.12546 -0.563923 0.816242 -0.0695665 -0.491083 0.868331 -0.0840255 -0.720104 0.688759 -0.0794069 -0.691266 0.718224 -0.0760216 -0.658006 0.749166 -0.0834405 -0.880137 0.467328 -0.0793276 -0.857784 0.507852 -0.0776642 -0.832606 0.548394 -0.0901619 -0.836866 0.539932 -0.0657192 -0.783212 0.618271 -0.0865866 -0.789906 0.607084 -0.0729249 -0.727672 0.682038 -0.52392 -0.850964 0.0369948 -0.440157 -0.89668 0.0471942 -0.43172 -0.89346 0.123888 -0.439762 -0.890419 0.11732 -0.429061 -0.877071 0.215994 -0.438158 -0.874356 0.20861 -0.427556 -0.849969 0.307814 -0.436062 -0.848213 0.300642 -0.426617 -0.816231 0.38957 -0.434037 -0.815427 0.383003 -0.425793 -0.778787 0.460643 -0.43237 -0.778691 0.454639 -0.424778 -0.73695 0.525803 -0.43081 -0.737372 0.520274 -0.423742 -0.690498 0.586222 -0.429598 -0.691341 0.580942 -0.422475 -0.634762 0.646987 -0.428259 -0.636005 0.641943 -0.420992 -0.566424 0.70847 -0.426989 -0.568085 0.703534 -0.419078 -0.474407 0.774152 -0.425407 -0.476453 0.769429 -0.417048 -0.343849 0.841332 -0.422971 -0.3461 0.837443 -0.417292 -0.182229 0.890315 -0.420733 -0.183998 0.888329 -0.419249 -0.0368486 0.907123 -0.245893 -0.0400033 0.968471 -0.277811 -0.960499 0.016208 -0.255637 -0.966512 0.0224344 -0.246383 -0.963054 0.108726 -0.256226 -0.961278 0.101454 -0.244834 -0.946935 0.208255 -0.255921 -0.945712 0.200333 -0.244529 -0.919376 0.308144 -0.254886 -0.919052 0.300626 -0.24469 -0.884378 0.397495 -0.253745 -0.884851 0.390708 -0.244832 -0.845034 0.475368 -0.252854 -0.846087 0.469257 -0.244648 -0.80064 0.546922 -0.252036 -0.802126 0.541361 -0.244407 -0.751071 0.613317 -0.251561 -0.752931 0.608122 -0.24388 -0.691222 0.680246 -0.250983 -0.693454 0.675374 -0.24318 -0.617542 0.748001 -0.250536 -0.620166 0.743388 -0.2421 -0.517853 0.820498 -0.249876 -0.520804 0.816288 -0.241048 -0.375814 0.894796 -0.248329 -0.378756 0.891558 -0.242197 -0.1996 0.949474 -0.246293 -0.201629 0.94799 -0.24453 -0.0406564 0.968789 -0.113151 -0.0420727 0.992687 -0.0789259 -0.0189617 0.9967 -0.789495 -0.60968 0.0706344 -0.780021 -0.623088 0.0576867 -0.901258 -0.421256 0.101377 -0.893597 -0.440168 0.0879552 -0.949418 -0.299245 0.0951706 -0.960903 -0.25328 0.111868 -0.978297 -0.185409 0.0925156 -0.991366 -0.0597721 0.116707 -0.985746 -0.0527882 0.159743 -0.985535 -0.0630793 0.157293 -0.949294 -0.181861 0.256451 -0.946999 -0.19759 0.253279 -0.870224 -0.338758 0.357706 -0.874732 -0.37091 0.311882 -0.873131 -0.374713 0.311822 -0.879198 -0.399653 0.259401 -0.760463 -0.565159 0.31983 -0.767 -0.586977 0.259169 -0.640946 -0.765267 0.0596259 -0.621463 -0.780582 0.0668996 -0.613975 -0.77788 0.13393 -0.619523 -0.774389 0.128504 -0.610115 -0.762867 0.213995 -0.616449 -0.759508 0.207697 -0.607183 -0.73842 0.293368 -0.613119 -0.735956 0.287148 -0.604895 -0.708339 0.363811 -0.610086 -0.706821 0.35805 -0.602916 -0.675216 0.424942 -0.607508 -0.674414 0.419643 -0.600908 -0.638458 0.480917 -0.605112 -0.638174 0.475998 -0.598956 -0.597765 0.53285 -0.60305 -0.597883 0.528078 -0.596844 -0.549151 0.584988 -0.600884 -0.549654 0.580361 -0.594531 -0.489677 0.637769 -0.598723 -0.490574 0.633141 -0.591775 -0.409846 0.694138 -0.596199 -0.411136 0.689575 -0.58881 -0.296859 0.751783 -0.59295 -0.298474 0.74788 -0.587975 -0.156977 0.793501 -0.590494 -0.158441 0.791337 -0.58925 -0.0313829 0.807341 -0.420685 -0.0360855 0.906489 -0.00424539 -0.748232 0.663424 0.00410264 -0.732054 0.681235 -0.00307289 -0.80203 0.597276 7.18159e-06 -0.795639 0.605771 8.42642e-06 -0.830023 0.557729 -0.00154693 -0.842967 0.537963 0.00391833 -0.862902 0.505355 0.00847782 -0.877372 0.479736 0.0029525 -0.88556 0.464516 -0.000753346 -0.914794 0.403919 5.98521e-06 -0.910841 0.412757 4.90518e-06 -0.929534 0.368737 0.000777356 -0.931044 0.364906 -6.26429e-05 -0.943972 0.330027 0.00061454 -0.958185 0.286148 -0.00377149 -0.963472 0.267783 -1.51174e-05 -0.974103 0.226105 -1.88196e-05 -0.984091 0.177666 -0.00128698 -0.985359 0.170485 0.00157521 -0.995142 0.0984392 -0.00313768 -0.996979 0.077605 0.00412407 -0.999948 -0.00933557 0.0083746 -0.999965 0.000127838 0 -0.999343 -0.0362395 -0.000108421 -0.707373 0.70684 4.45719e-07 -0.69826 0.715845 3.07982e-07 -0.695911 0.718129 7.10753e-05 -0.689911 0.723895 -0.00160279 -0.662131 0.749386 -0.00547056 -0.677455 0.735544 0.00645323 -0.617605 0.786462 0.00300723 -0.630357 0.7763 -0.00209987 -0.571583 0.820541 2.72275e-05 -0.55897 0.829188 2.08319e-05 -0.493766 0.869595 -0.00312932 -0.507962 0.861374 -0.000513665 -0.474321 0.880352 0.0024456 -0.383319 0.923613 -0.0262247 -0.263799 0.964221 -0.0107786 -0.420176 0.907379 1.73334e-05 -0.342304 0.939589 -1.79237e-05 -0.274506 0.961586 -0.00269166 -0.294576 0.955624 0.00628413 -0.179394 0.983757 0.0267951 -0.112147 0.99333 0 -0.00955179 0.999954 -0.00158909 -0.0191331 0.999816 -0.0106478 -0.214231 0.976725 3.34835e-05 -0.137486 0.990504 2.47351e-05 -0.0792442 0.996855 -0.00187275 -0.099375 0.995048 0.00158264 -0.0608032 0.998149 0.672635 -0.720911 0.166882 0.982039 -0.187263 0.0230538 0.663669 -0.746672 0.0450051 0.955293 -0.0112838 0.295447 0.994386 -0.00748719 0.10555 0.99887 -0.0354006 0.0317087 0.993956 -0.104672 0.0330922 0.989824 -0.112421 0.0872301 0.98231 -0.182231 0.0431064 0.96363 -0.261821 0.0535344 0.952888 -0.280388 0.115701 0.916282 -0.392505 0.0797943 0.892169 -0.436179 0.1174 0.867942 -0.489723 0.0827524 0.813005 -0.576315 0.0829692 0.806331 -0.587864 0.0651681 0.675566 -0.721962 0.149604 0.637036 -0.770413 0.0254873 0.638318 -0.768466 0.0448201 0.699991 -0.713829 -0.0214659 0.706658 -0.705426 0.0548461 0.797604 -0.603178 -0.00195279 0.793438 -0.608021 -0.0276761 0.850539 -0.522689 0.0581361 0.877088 -0.475957 -0.0646606 0.899629 -0.435705 0.0288049 0.951051 -0.308072 0.0243756 0.953982 -0.271816 -0.126627 0.93186 -0.36172 0.0282105 0.992975 -0.116491 0.0207323 0.981639 -0.155034 0.11113 0.986355 -0.122216 0.110308 0.982047 -0.153138 0.110145 0.985418 -0.170145 -0.0013415 0.993519 -0.108852 0.0327342 0.993106 -0.11382 0.0280149 0.958966 -0.195383 0.205447 0.955842 -0.209108 0.206495 0.923712 -0.316481 0.215864 0.930409 -0.254019 0.264223 0.902864 -0.35814 0.237849 0.8296 -0.436971 0.347592 0.829368 -0.440422 0.343769 0.82163 -0.47973 0.30787 0.7723 -0.557107 0.305262 0.725093 -0.59743 0.342517 0.711527 -0.625277 0.320559 0.638004 -0.692788 0.336149 0.637469 -0.666901 0.385844 0.723672 -0.575094 0.381531 0.663215 -0.645065 0.379522 0.631171 -0.697864 0.33854 0.642966 -0.69914 0.312728 0.588529 -0.727128 0.353438 0.602705 -0.730129 0.32196 0.611994 -0.727511 0.310149 0.896212 -0.440153 0.0553937 0.790702 -0.539709 0.288972 0.811387 -0.57549 0.102286 0.720856 -0.663877 0.199084 0.737417 -0.671268 0.0749432 0.735871 -0.673342 0.0714527 0.94829 -0.230402 0.218314 0.963362 -0.0887397 0.2531 0.966601 -0.0936783 0.238552 0.959438 -0.00832896 0.281796 0.939965 6.84764e-05 0.341272 0.992143 -0.00484262 0.125019 0.989879 -0.0110341 0.141487 0.98329 -0.104467 0.149092 0.983896 -0.103706 0.145584 0.952687 -0.261268 0.15533 0.958927 -0.267951 0.0930657 0.861615 -0.378344 0.338343 0.754753 -0.655769 -0.0177182 0.69097 -0.698729 0.185307 0.645634 -0.741545 0.182393 0.662489 -0.73484 0.14532 0.623167 -0.768884 0.14311 0.633677 -0.764332 0.119375 0.688641 -0.714807 0.121759 0.68633 -0.71605 0.127371 0.789034 -0.600353 0.130392 0.775873 -0.612345 0.15184 0.870615 -0.467889 0.152016 0.8629 -0.476914 0.167204 0.941582 -0.295398 0.161748 0.926458 -0.31841 0.200726 0.971213 -0.209326 0.113703 0.96832 -0.206161 0.140907 0.978422 -0.149352 0.142775 0.717401 -0.644518 0.264449 0.652239 -0.695462 0.301523 0.630699 -0.716046 0.299162 0.651745 -0.71217 0.260849 0.608212 -0.751223 0.256404 0.619464 -0.74896 0.235208 0.666678 -0.70583 0.239466 0.659631 -0.707657 0.253197 0.756202 -0.600574 0.259748 0.742859 -0.609221 0.277508 0.841343 -0.462951 0.278961 0.853721 -0.451874 0.258787 0.927239 -0.278348 0.250498 0.934247 -0.273439 0.228942 0.664228 -0.674633 -0.321981 0.910424 -0.389995 -0.137957 0.798299 -0.0470408 -0.600421 0.789429 -0.600965 0.125074 0.838776 -0.533742 -0.107589 0.953058 -0.300753 -0.0350429 0.627877 -0.413866 -0.659155 0.603307 -0.00726742 -0.797476 0.7571 -0.369594 -0.538702 0.689827 -0.49547 -0.527871 0.781331 -0.44637 -0.436206 0.74334 -0.546477 -0.385757 0.816753 -0.483301 -0.315174 0.793758 -0.561765 -0.23317 0.85897 -0.471095 -0.2006 0.838713 -0.533708 -0.108239 0.90167 -0.416395 -0.116647 0.973854 -0.190575 -0.123652 0.972886 -0.196113 -0.122604 0.969042 -0.210572 -0.128906 0.976584 -0.11842 -0.179611 0.989609 -0.0660991 -0.127692 0.9774 -0.0877505 -0.192327 0.986468 -0.0542927 -0.154703 0.97778 -0.0627312 -0.200029 0.983919 -0.0458167 -0.172641 0.978024 -0.0452166 -0.203532 0.98224 -0.0345573 -0.184417 0.978556 -0.0287528 -0.203966 0.981589 -0.0309108 -0.188486 0.986266 -0.00930667 -0.164903 0.987325 0.00696208 -0.158559 0.981248 -0.0185514 -0.191855 0.991826 -0.00241659 -0.127575 0.994364 -0.060892 -0.0867939 0.99153 0.0576563 -0.116381 0.999591 0 -0.0285964 0.999676 0.0159758 -0.0198183 0.997532 -0.0125112 -0.069094 0.98327 -0.101901 -0.150985 0.994235 -0.0986623 -0.0419894 0.993622 -0.0432266 -0.10415 0.995976 -0.0529523 -0.0722978 0.997898 -0.0389912 -0.051761 0.997748 -0.0361686 -0.0564858 0.998514 -0.0357308 -0.0411381 0.998155 -0.0417089 -0.0441184 0.998469 -0.0494787 -0.0247409 0.996259 -0.0721371 -0.0475795 0.992922 -0.116485 0.0231927 0.961722 -0.274021 0.00178205 0.985916 -0.00742501 -0.167074 0.975522 -0.0570787 -0.212367 0.9303 -0.0555074 -0.362574 0.793106 -0.607766 0.0400541 0.793889 -0.606802 0.0391349 0.707662 -0.706428 0.0132068 0.899774 -0.435775 0.0225332 0.903343 -0.417675 0.0975632 0.906376 -0.421837 0.0231606 0.87245 -0.474246 0.117994 0.876848 -0.480451 0.017439 0.849807 -0.522239 0.0713725 0.966305 -0.251506 -0.0547563 0.96789 -0.250645 0.0191105 0.961097 -0.27148 0.0509045 0.961859 -0.273356 0.010148 0.94655 -0.313566 0.075629 0.948401 -0.316788 0.0134498 0.930468 -0.36118 0.0614742 0.960757 -0.218543 -0.170839 0.974154 -0.222703 -0.0377757 0.988816 -0.134427 -0.0645907 0.990968 -0.133844 -0.00825829 0.99153 -0.129003 -0.015062 0.991389 -0.129211 -0.0212527 0.988204 -0.152469 0.0143403 0.988129 -0.153343 -0.00935946 0.981963 -0.187248 0.0262113 0.966934 -0.0342687 -0.252716 0.981128 -0.103322 -0.163442 0.970755 -0.180087 -0.158759 0.874245 -0.0504687 -0.482854 0.894884 -0.063197 -0.441803 0.875513 -0.226184 -0.426988 0.954337 -0.243856 -0.172553 0.953381 -0.259036 -0.154809 0.685915 -0.0257641 -0.727226 0.78308 -0.0516803 -0.619771 0.770857 -0.195723 -0.606195 0.88063 -0.220395 -0.419426 0.837816 -0.383016 -0.389054 0.899096 -0.408031 -0.158545 0.864772 -0.487934 -0.118701 0.8223 -0.553149 -0.133599 0.781248 -0.528216 -0.332626 0.846706 -0.375101 -0.377343 0.752612 -0.337209 -0.565567 0.781556 -0.186572 -0.595282 0.689019 -0.1666 -0.705335 0.697075 -0.016696 -0.716804 0.61206 -0.042135 -0.789688 0.617601 -0.0259002 -0.786065 0.630012 -0.0263593 -0.776138 0.624676 -0.139989 -0.768234 0.703296 -0.155815 -0.693611 0.683985 -0.290479 -0.669168 0.771782 -0.32417 -0.547053 0.723571 -0.476194 -0.499684 0.794879 -0.518478 -0.315194 0.720822 -0.639672 -0.2669 0.726341 -0.575196 -0.376268 0.667545 -0.532592 -0.520316 0.71397 -0.400424 -0.574376 0.634153 -0.358978 -0.684825 0.661409 -0.201882 -0.722345 0.628519 -0.192308 -0.753645 0.616376 -0.105612 -0.780338 0.638868 -0.769128 -0.0170304 0.66392 -0.741862 -0.0940758 0.681962 -0.728797 -0.061513 0.74644 -0.659967 -0.0852682 0.733398 -0.671079 -0.108538 0.805259 -0.587083 -0.0830142 0.945221 -0.32494 -0.0311594 0.928077 -0.369583 -0.0456165 0.92927 -0.369115 0.0145183 0.837121 -0.537123 0.103571 0.840365 -0.541991 0.00573578 0.72139 -0.68596 0.0951632 0.723474 -0.690148 -0.0167578 0.669105 -0.743087 0.0109793 0.623537 -0.77808 -0.0761143 0.665472 -0.739856 -0.0987909 0.663326 -0.741283 -0.102463 0.687153 -0.695539 -0.209873 0.739204 -0.628431 -0.242181 0.691131 -0.59147 -0.415333 0.751634 -0.460967 -0.471758 0.67585 -0.418387 -0.606778 0.70999 -0.27487 -0.648352 0.627938 -0.245648 -0.738479 0.642046 -0.113551 -0.758211 0.614363 -0.108935 -0.781467 0.606037 -0.0446684 -0.794181 0.744342 -0.667512 -0.0195917 0.797826 -0.56447 -0.211771 0.722117 -0.678439 -0.135157 0.761001 -0.558975 -0.32928 0.708303 -0.652073 -0.270384 0.727236 -0.521478 -0.446306 0.696897 -0.588995 -0.409169 0.696671 -0.457711 -0.552404 0.713559 -0.39912 -0.575792 0.665186 -0.373017 -0.646828 0.665657 -0.248459 -0.703682 0.931792 -0.358612 -0.0562236 0.883539 -0.467124 -0.0339727 0.883699 -0.46715 -0.0291038 0.781872 -0.620256 0.0629104 0.781659 -0.622275 -0.0422251 0.744474 -0.667521 -0.0131729 0.666746 -0.741739 -0.0726166 0.712805 -0.670862 -0.204581 0.659564 -0.734343 -0.160358 0.700865 -0.645852 -0.302761 0.688374 -0.66428 -0.29133 0.685318 -0.579949 -0.440451 0.71511 -0.513974 -0.473759 0.644298 -0.466696 -0.605867 0.686077 -0.300875 -0.662399 0.637768 -0.280528 -0.717326 0.63999 -0.173283 -0.748589 0.997748 0.036221 -0.0564598 0.985916 0.00742501 -0.167074 0.982207 0.00916696 -0.187576 0.999591 0 -0.0285964 0.98539 0.0379692 -0.16603 0.984108 -0.0140101 -0.177017 0.989138 0.00889434 -0.146723 0.991848 -0.0010572 -0.127421 0.992423 0.00386132 -0.122808 0.996436 0.00253239 -0.0843141 0.996372 0.000797834 -0.0850989 0.999567 0.00146747 -0.0294022 0.976668 0.0890739 -0.195409 0.985813 0.0682872 -0.153331 0.977222 0.0631753 -0.202599 0.977731 0.0627799 -0.200251 0.983593 0.0527576 -0.172515 0.977925 0.0452738 -0.203991 0.981859 0.0428848 -0.184697 0.97841 0.0286533 -0.204676 0.979436 0.0293615 -0.19961 0.964142 0.219811 -0.148703 0.971402 0.202834 -0.123439 0.973436 0.193016 -0.123159 0.927534 0.369635 -0.0552264 0.937438 0.34647 -0.0341815 0.950593 0.308796 -0.0319079 0.96629 0.251626 -0.0544736 0.974 0.223414 -0.0375683 0.988802 0.134543 -0.0645701 0.877648 0.465097 -0.115843 0.905147 0.42289 -0.0432743 0.926053 0.373609 -0.0533218 0.837013 0.532832 -0.124498 0.815262 0.575654 -0.0630082 0.824653 0.466602 -0.319735 0.768125 0.564 -0.30313 0.776284 0.46145 -0.429473 0.744318 0.533277 -0.402004 0.734016 0.420098 -0.533608 0.712531 0.467754 -0.522977 0.695265 0.354462 -0.62527 0.682779 0.382489 -0.622507 0.661445 0.276119 -0.697315 0.656136 0.288248 -0.697423 0.63396 0.194653 -0.748468 0.634264 0.193958 -0.748391 0.615245 0.120083 -0.779136 0.619421 0.109766 -0.777348 0.602725 0.0530822 -0.796181 0.617755 0.025903 -0.785944 0.603302 0.00841982 -0.797468 0.981128 0.103312 -0.163443 0.988217 0.153009 0.00400372 0.992911 0.116562 0.0232539 0.996253 0.0722039 -0.0476042 0.998467 0.04954 -0.0246991 0.973948 0.0910677 -0.207684 0.988067 0.0938054 -0.122161 0.984937 0.101664 -0.139868 0.991166 0.10018 -0.0869173 0.997431 0.0679894 -0.022545 0.638868 0.769128 -0.0170333 0.982267 0.187384 -0.00621489 0.961722 0.274021 0.00173709 0.948206 0.316207 0.0303044 0.932098 0.361812 0.016903 0.89974 0.435846 0.0225058 0.876416 0.479286 0.0466939 0.851674 0.523479 0.024929 0.793809 0.606861 0.0398303 0.79314 0.607793 0.0389386 0.723754 0.68983 0.0177497 0.998514 0.035783 -0.0411074 0.998153 0.0417702 -0.0441015 0.991702 0.128547 0.00160897 0.988114 0.153471 -0.00876464 0.960966 0.271518 0.0531336 0.94817 0.316109 0.0323766 0.904014 0.41852 0.0871753 0.876201 0.478883 0.0542536 0.838129 0.538337 0.0879434 0.793725 0.606677 0.0440918 0.782192 0.620794 0.0528266 0.723712 0.690099 0.00200033 0.744452 0.667544 -0.0132355 0.666731 0.741748 -0.0726612 0.712793 0.670857 -0.204638 0.719767 0.661468 -0.210705 0.797931 0.0559776 -0.600144 0.930301 0.0555003 -0.362574 0.972983 0.0570027 -0.223729 0.98076 0.0347587 -0.192099 0.970756 0.180077 -0.15876 0.954343 0.243826 -0.172564 0.953386 0.259016 -0.154812 0.902381 0.40919 -0.135173 0.906169 0.388155 -0.167909 0.864773 0.487934 -0.118695 0.822323 0.553111 -0.133618 0.80526 0.587084 -0.082995 0.74495 0.658841 -0.104775 0.735344 0.67283 -0.0810491 0.670268 0.375731 -0.639974 0.669826 0.377544 -0.63937 0.649259 0.28535 -0.705009 0.654264 0.255033 -0.711967 0.634846 0.194127 -0.747854 0.639909 0.143049 -0.755019 0.626818 0.111 -0.771218 0.629857 0.0370444 -0.775827 0.612402 0.0257048 -0.790129 0.67657 0.723009 -0.139682 0.666044 0.743815 -0.0559075 0.654228 0.731971 -0.190275 0.727318 0.644938 -0.234655 0.73237 0.623272 -0.274165 0.787701 0.532201 -0.310306 0.788314 0.514634 -0.337214 0.843259 0.385259 -0.374821 0.841292 0.372922 -0.391353 0.879399 0.227063 -0.41845 0.876791 0.219532 -0.427835 0.894884 0.0631909 -0.441803 0.874245 0.050462 -0.482855 0.783211 0.0463314 -0.620027 0.772398 0.184583 -0.607726 0.780081 0.197812 -0.593585 0.757289 0.318624 -0.570081 0.767071 0.343075 -0.542127 0.733368 0.450762 -0.508906 0.741399 0.486882 -0.461815 0.707167 0.561404 -0.429815 0.709245 0.605565 -0.36092 0.664235 0.674603 -0.32203 0.704372 0.709303 -0.027389 0.995976 0.0529867 -0.072284 0.997898 0.0390407 -0.0517347 0.990893 0.134026 -0.0129879 0.991595 0.12897 -0.0103318 0.96729 0.25023 0.041664 0.961659 0.272689 0.0292121 0.927129 0.367457 0.0735331 0.906047 0.421167 0.0411908 0.882663 0.46555 0.0645643 0.840349 0.541864 0.0140686 0.844094 0.53609 0.0106226 0.781197 0.62217 -0.0513375 0.814049 0.574946 -0.0822207 0.735231 0.661562 -0.147553 0.789677 0.579019 -0.202848 0.7019 0.661629 -0.263786 0.766068 0.548248 -0.335506 0.67735 0.625834 -0.386689 0.740775 0.485628 -0.464131 0.658512 0.558798 -0.50409 0.684493 0.493606 -0.536491 0.707698 0.706464 -0.00845458 0.647516 0.761753 0.021355 0.665045 0.740269 -0.098576 0.665485 0.73984 -0.0988196 0.645565 0.72036 -0.253626 0.688379 0.66425 -0.291386 0.685319 0.579909 -0.440504 0.697537 0.554438 -0.453918 0.683518 0.492955 -0.53833 0.703892 0.434217 -0.562132 0.685288 0.385569 -0.617833 0.705542 0.298778 -0.642606 0.688331 0.267162 -0.674407 0.701969 0.169388 -0.691771 0.690393 0.15321 -0.707025 0.697018 0.0285588 -0.716485 0.686003 0.0201781 -0.727319 0.479106 0.328895 0.813809 0.522955 0.638676 0.564457 0.443371 0.681946 0.581697 0.605948 0.594483 0.528599 0.369197 0.42043 0.828814 0.130667 0.146988 0.98047 0.0321517 0.106007 0.993845 0.201507 0.209154 0.956896 0.317148 0.39006 0.864448 0.409892 0.449569 0.793648 0.56683 0.614492 0.548729 0.554301 0.610275 0.565964 0.126446 0.153348 0.980049 0.124661 0.152116 0.980469 0.359835 0.435411 0.825189 0.355079 0.432464 0.828791 0.536461 0.648601 0.539933 0.530407 0.646013 0.54894 0.128318 0.152515 0.979936 0.127874 0.152185 0.980045 0.364592 0.43323 0.824248 0.363445 0.432453 0.825162 0.542885 0.645079 0.537726 0.541527 0.644407 0.539896 0.150549 0.160832 0.975432 0.129635 0.15134 0.979944 0.400915 0.419809 0.814265 0.385828 0.414298 0.824314 0.589041 0.613076 0.526468 0.580176 0.611748 0.537737 0.171049 0.192691 0.966236 0.127458 0.185299 0.974381 0.44254 0.413752 0.795593 0.408129 0.412192 0.814572 0.647676 0.571054 0.504395 0.624163 0.576018 0.527848 0.245318 0.621195 0.744269 0.941047 0.232447 0.245764 0.671879 0.485356 0.559471 0.223141 0.632087 0.742074 0.228096 0.53795 0.811531 0.257288 0.547833 0.796042 0.908337 0.287293 0.303952 0.908275 0.288716 0.302786 0.904939 0.322658 0.277447 0.212154 0.506808 0.835546 0.21499 0.478623 0.851293 0.210477 0.489053 0.846479 0.216304 0.437931 0.872599 0.18934 0.451821 0.871784 0.206933 0.378491 0.902177 0.190878 0.388053 0.901654 0.162343 0.204346 0.965343 0.137171 0.241592 0.960634 0.18448 0.238178 0.95354 0.146763 0.302869 0.941664 0.197048 0.292306 0.935804 0.174582 0.34708 0.921443 0.191512 0.325822 0.925831 0.18581 0.340927 0.921544 0.628518 0.529105 0.570099 0.634126 0.435091 0.639203 0.598242 0.469341 0.649481 0.603742 0.420089 0.67751 0.595908 0.443657 0.669374 0.599746 0.411045 0.686547 0.560592 0.445998 0.697727 0.570286 0.405828 0.714197 0.519156 0.441052 0.732086 0.533296 0.404288 0.743065 0.511774 0.43654 0.739946 0.523788 0.407748 0.747922 0.470899 0.430455 0.770041 0.482516 0.410621 0.773672 0.43727 0.420695 0.794865 0.908376 0.277629 0.312691 0.881802 0.280659 0.37902 0.877807 0.313592 0.362098 0.881172 0.281363 0.379962 0.872353 0.32147 0.368317 0.87449 0.305118 0.377056 0.836541 0.370401 0.403736 0.836782 0.369417 0.404138 0.786388 0.433627 0.439956 0.792984 0.416052 0.445058 0.767947 0.46285 0.44275 0.770646 0.456627 0.444518 0.722022 0.49697 0.481358 0.708636 0.519708 0.47722 0.671793 0.539404 0.507679 0.241477 0.676339 0.695884 0.066213 -0.693233 0.717666 0.934845 0.264132 0.237273 0.766972 0.517545 0.379343 0.226894 -0.492701 0.840098 0.252552 0.69341 0.674833 0.252583 0.693365 0.674869 0.700344 0.518606 0.490475 0.664512 0.576751 0.475165 0.934685 0.266478 0.235272 0.940688 0.246091 0.23355 0.98969 0.136468 0.0434857 0.197923 0.97783 0.0683675 0.933192 0.292688 0.208532 0.568686 0.643681 0.512124 0.769336 0.498513 0.399507 0.41943 0.693335 0.585974 0.977851 0.195206 0.0755117 0.977563 0.197907 0.0721313 0.989453 0.138944 0.0409515 0.972311 0.222953 0.070026 0.981091 0.189798 0.0379147 0.983175 0.168613 0.0702663 0.177208 0.742367 0.646133 0.195993 0.745346 0.637218 0.192355 0.79207 0.579331 0.217617 0.796544 0.564058 0.197637 0.818454 0.539511 0.192411 0.866852 0.459941 0.201277 0.917646 0.342657 0.196272 0.902399 0.383606 0.20209 0.864264 0.460661 0.198961 0.917596 0.344139 0.189921 0.947144 0.258552 0.199132 0.944501 0.261273 0.191367 0.960876 0.200238 0.22199 0.964152 0.145364 0.198407 0.966842 0.160784 0.183649 0.980874 0.064491 0.960422 0.205923 -0.187579 0.955945 0.236203 -0.174288 0.960831 0.221284 -0.166843 0.966547 0.219445 -0.132779 0.964364 0.22726 -0.135479 0.9709 0.220921 -0.0924519 0.969323 0.22713 -0.0939415 0.975131 0.216031 -0.0495083 0.974638 0.218161 -0.0498724 0.978809 0.2045 -0.0106031 0.979042 0.203389 -0.0105009 0.981663 0.189505 0.0206224 0.828776 0.459482 0.319386 0.82675 0.479885 0.29359 0.837796 0.462218 0.290607 0.832823 0.508025 0.21981 0.83752 0.500989 0.218108 0.831634 0.538509 0.135616 0.832447 0.537213 0.135771 0.825386 0.560299 0.0693043 0.82799 0.55635 0.0700519 0.818262 0.574831 -0.00410298 0.823298 0.567605 -0.00232903 0.812054 0.57856 -0.07639 0.818185 0.570235 -0.0735202 0.804185 0.574238 -0.153419 0.814174 0.56066 -0.150937 0.554134 0.653893 0.515131 0.550652 0.692304 0.466367 0.562114 0.683193 0.466128 0.555421 0.745394 0.368641 0.563047 0.740059 0.36782 0.555258 0.789796 0.260597 0.558556 0.787235 0.261299 0.549699 0.816253 0.177654 0.555522 0.811988 0.179085 0.543319 0.835107 0.0860339 0.552472 0.828834 0.0883708 0.538082 0.84287 -0.00619566 0.548593 0.836084 -0.00301044 0.530653 0.840947 -0.105901 0.545274 0.831749 -0.104263 0.195152 0.9797 -0.0458693 0.219244 0.97405 -0.0561979 0.188202 0.982079 0.0100207 0.959487 0.205708 -0.192535 0.809133 0.559651 -0.179154 0.538949 0.830737 -0.139324 0.188973 0.978806 -0.0789189 0.961664 0.196483 -0.191304 0.965507 0.1974 -0.16979 0.965889 0.195748 -0.169533 0.971175 0.197331 -0.133715 0.971629 0.19544 -0.133195 0.976083 0.197227 -0.0914513 0.976788 0.194038 -0.0907431 0.979832 0.196384 -0.0369277 0.980406 0.193623 -0.036262 0.813041 0.554079 -0.178775 0.816337 0.554834 -0.160479 0.817062 0.553796 -0.160371 0.821518 0.555157 -0.130033 0.822336 0.554014 -0.129736 0.826156 0.555489 -0.094332 0.827511 0.55354 -0.0939107 0.830098 0.555526 -0.0482436 0.831236 0.553861 -0.0478059 0.542397 0.828484 -0.139354 0.54463 0.828991 -0.127093 0.545267 0.828575 -0.127071 0.548221 0.829484 -0.106815 0.548954 0.829017 -0.106674 0.551545 0.830003 -0.0830184 0.552737 0.82923 -0.0828197 0.554472 0.830558 -0.0522861 0.555505 0.829883 -0.0520462 0.190306 0.978542 -0.0789882 0.191105 0.978728 -0.0746362 0.191363 0.978677 -0.0746394 0.192394 0.978991 -0.0675385 0.192679 0.978937 -0.0675022 0.193597 0.979293 -0.0592022 0.194072 0.979203 -0.0591493 0.194682 0.979671 -0.0484212 0.195087 0.979593 -0.0483505 0.980717 0.195409 0.00321974 0.831426 0.555453 -0.0142676 0.555562 0.830948 -0.0296059 0.19509 0.979951 -0.040458 0.980867 0.194647 0.00362161 0.979636 0.196278 0.0422827 0.979837 0.195213 0.0425602 0.975888 0.197428 0.0930822 0.975999 0.196803 0.0932484 0.97272 0.198054 0.12079 0.972731 0.197928 0.120909 0.969009 0.198999 0.146361 0.969111 0.198396 0.146503 0.96444 0.199583 0.173272 0.963718 0.203843 0.172324 0.964306 0.203702 0.169174 0.959986 0.226781 0.164309 0.83174 0.55499 -0.0139809 0.830764 0.556306 0.0188477 0.831187 0.555667 0.0190533 0.827824 0.557558 0.0619342 0.828059 0.557196 0.0620614 0.825217 0.558317 0.0854376 0.825264 0.558231 0.0855383 0.822154 0.559091 0.107145 0.822364 0.558761 0.107258 0.818381 0.55979 0.129951 0.816746 0.562374 0.129079 0.817283 0.562241 0.126227 0.808305 0.576037 0.12176 0.55584 0.830768 -0.029441 0.555253 0.831648 -0.00748026 0.555628 0.831398 -0.00735892 0.55337 0.832663 0.0213156 0.55359 0.832514 0.0213987 0.551633 0.833264 0.0370328 0.551672 0.833236 0.0370856 0.549639 0.833811 0.0515394 0.549826 0.833683 0.0516128 0.547141 0.834372 0.06679 0.545633 0.835407 0.0661872 0.545996 0.835318 0.0642817 0.537927 0.840766 0.0612097 0.195202 0.979931 -0.0404038 0.195011 0.980256 -0.0326831 0.195161 0.980228 -0.0326437 0.194365 0.98067 -0.0225667 0.194446 0.980654 -0.022541 0.193745 0.980904 -0.0170478 0.193759 0.980901 -0.017032 0.193056 0.981115 -0.011953 0.193127 0.981101 -0.0119289 0.192173 0.981339 -0.0065665 0.191577 0.981454 -0.00677504 0.191684 0.981429 -0.00732949 0.188522 0.982033 -0.00839463 0.969552 0.225779 0.0948282 0.183777 0.813264 -0.552112 0.221486 0.814287 -0.536545 0.422683 0.760955 -0.492226 0.557207 0.707966 -0.43394 0.585226 0.688823 -0.427823 0.769861 0.547181 -0.328491 0.83205 0.488012 -0.263701 0.875773 0.423878 -0.230975 0.98071 0.181043 -0.0737027 0.967599 0.236348 -0.0888372 0.951076 0.282668 0.124711 0.183316 0.981346 -0.0579281 0.195543 0.979265 -0.0529509 0.537663 0.843151 0.00382703 0.546034 0.837725 0.00797292 0.812388 0.579486 0.0649787 0.816486 0.573352 0.067952 0.967403 0.22466 0.116869 0.974674 0.218476 0.0477365 0.975199 0.215716 0.0495338 0.825379 0.562847 -0.0441844 0.824441 0.564141 -0.0451759 0.553423 0.822772 -0.129497 0.548089 0.825794 -0.132899 0.199536 0.960202 -0.19544 0.24002 0.91275 -0.330572 0.196579 0.936594 -0.290084 0.18864 0.961363 -0.20049 0.981444 0.18947 -0.0294823 0.979005 0.199724 -0.0407365 0.835096 0.513747 -0.196667 0.828585 0.520785 -0.2055 0.560156 0.758545 -0.332919 0.55197 0.761819 -0.339059 0.979518 0.201349 0.00190773 0.979371 0.202066 0.00111322 0.832222 0.539175 -0.129217 0.830856 0.54078 -0.131284 0.557849 0.794345 -0.24046 0.554418 0.795834 -0.243454 0.192609 0.929144 -0.315583 0.199349 0.886534 -0.417514 0.191712 0.886507 -0.421132 0.195451 0.853958 -0.482239 0.247427 0.729745 -0.637379 0.968481 0.229007 -0.0979863 0.947607 0.210895 -0.239924 0.879187 0.392285 -0.270451 0.773407 0.517194 -0.36654 0.587346 0.482785 -0.649572 0.67917 0.581242 -0.448203 0.428621 0.709164 -0.559795 0.249619 0.695345 -0.673933 0.189353 0.758806 -0.623185 0.242899 0.719172 -0.650993 0.242375 0.736673 -0.631322 0.670893 0.569628 -0.474791 0.679319 0.579528 -0.450192 0.941084 0.272916 -0.199692 0.945677 0.284973 -0.156481 0.940223 0.284477 -0.187226 0.671634 0.559297 -0.485896 0.24391 0.70453 -0.666443 0.235564 0.699084 -0.675123 0.238876 0.638633 -0.731495 0.223487 0.634037 -0.740304 0.227244 0.571899 -0.788221 0.243087 0.542815 -0.803904 0.211624 0.523164 -0.825539 0.216755 0.484561 -0.847478 0.212746 0.471947 -0.855573 0.219052 0.429937 -0.875883 0.193515 0.410617 -0.891036 0.930095 0.281069 -0.23648 0.930342 0.276612 -0.240728 0.908724 0.287394 -0.302697 0.908534 0.290113 -0.300667 0.88631 0.288275 -0.362427 0.881144 0.327738 -0.340842 0.880054 0.29956 -0.368469 0.871779 0.349785 -0.343004 0.853242 0.328529 -0.405028 0.834858 0.398065 -0.380207 0.817162 0.360919 -0.449426 0.789079 0.435439 -0.433297 0.803223 0.386557 -0.453217 0.769223 0.466466 -0.436698 0.760497 0.423447 -0.492277 0.712336 0.508228 -0.484026 0.708407 0.468441 -0.527942 0.656582 0.553056 -0.512864 0.658538 0.514557 -0.549143 0.630681 0.514425 -0.581041 0.633808 0.464049 -0.618825 0.605344 0.457097 -0.651629 0.606805 0.446611 -0.657516 0.602504 0.426902 -0.674347 0.602302 0.428223 -0.673689 0.573829 0.40705 -0.710655 0.574656 0.403876 -0.711797 0.543279 0.36813 -0.754538 0.533874 0.392347 -0.749028 0.541253 0.353838 -0.762786 0.526972 0.388587 -0.755844 0.503634 0.344497 -0.792259 0.485395 0.376556 -0.789048 0.469972 0.335058 -0.816617 0.207258 0.357531 -0.910613 0.21301 0.342408 -0.915087 0.180753 0.306165 -0.934661 0.18753 0.288694 -0.938876 0.19111 0.258617 -0.946886 0.194743 0.249666 -0.948547 0.166117 0.207144 -0.964104 0.177987 0.186217 -0.966253 0.158213 0.146699 -0.976447 0.155197 0.126846 -0.979706 0.157105 0.148224 -0.976395 0.444791 0.344077 -0.826905 0.444205 0.37065 -0.815659 0.666641 0.506821 -0.546555 0.659815 0.53627 -0.526363 0.147247 0.125339 -0.981126 0.147482 0.136299 -0.979628 0.421427 0.355269 -0.834376 0.419947 0.374504 -0.826675 0.633197 0.531214 -0.562915 0.626445 0.556069 -0.546218 0.0165118 0.0203509 -0.999657 0.271273 0.335046 -0.902306 0.147501 0.155952 -0.976689 0.470388 0.563628 -0.679013 0.386835 0.444515 -0.807939 0.541195 0.634686 -0.551617 -0.00296136 0.23879 -0.971067 0.11361 0.147064 -0.982581 0.113111 0.14614 -0.982776 0.118672 0.141771 -0.98276 0.119714 0.144131 -0.982291 0.132643 0.132342 -0.982289 0.135379 0.138549 -0.981059 0.315024 0.428866 -0.84666 0.325003 0.42094 -0.846866 0.323781 0.418526 -0.848529 0.340248 0.405504 -0.848409 0.342669 0.411721 -0.844431 0.380905 0.376794 -0.844357 0.387047 0.39323 -0.834005 0.505026 0.625859 -0.594348 0.491483 0.636651 -0.594239 0.490268 0.633703 -0.598379 0.515295 0.613719 -0.598181 0.517276 0.621586 -0.588266 0.575735 0.568017 -0.588122 0.58005 0.589295 -0.562383 0.462237 -0.323693 0.825566 0.27719 -0.303047 0.911772 0.116176 -0.141027 0.983166 0.400671 -0.439822 0.803753 0.597477 -0.586883 0.546433 0.130667 -0.146988 0.98047 0.125113 -0.151731 0.980472 0.12599 -0.153718 0.98005 0.127973 -0.152105 0.980044 0.128223 -0.1526 0.979935 0.36849 -0.421039 0.828819 0.356435 -0.431319 0.828805 0.358474 -0.436522 0.825194 0.363736 -0.432214 0.825159 0.364309 -0.433479 0.824242 0.530312 -0.632188 0.564897 0.558758 -0.606071 0.566098 0.562359 -0.618501 0.548825 0.532682 -0.644118 0.548964 0.534196 -0.65046 0.539942 0.541992 -0.644021 0.539891 0.542427 -0.64547 0.537719 0.585351 -0.616788 0.526247 0.583959 -0.608203 0.537662 0.39628 -0.424654 0.814022 0.390745 -0.409826 0.824234 0.145047 -0.166696 0.975281 0.135578 -0.146025 0.979947 0.637248 -0.584063 0.502777 0.63526 -0.563614 0.528 0.431263 -0.428519 0.793967 0.420788 -0.398597 0.814897 0.158941 -0.208874 0.96494 0.14133 -0.170645 0.975144 0.939305 -0.287246 0.187607 0.671204 -0.543725 0.503834 0.93848 -0.259076 0.228329 0.938089 -0.265324 0.222693 0.908644 -0.284698 0.305472 0.243739 -0.626675 0.740182 0.24097 -0.666831 0.705173 0.243087 -0.675072 0.696553 0.877641 -0.314767 0.36148 0.907653 -0.250834 0.336524 0.90842 -0.287304 0.303693 0.908367 -0.288621 0.3026 0.21479 -0.451988 0.865779 0.211726 -0.478729 0.852051 0.213993 -0.488857 0.84571 0.212155 -0.506808 0.835545 0.244317 -0.536213 0.807951 0.227652 -0.551218 0.802704 0.223941 -0.621396 0.750811 0.877809 -0.31358 0.362104 0.877448 -0.31645 0.360478 0.876629 -0.285591 0.387246 0.868797 -0.344494 0.355691 0.846292 -0.326185 0.421181 0.824528 -0.414727 0.384908 0.80416 -0.383837 0.453867 0.775551 -0.460605 0.431698 0.786484 -0.417676 0.454961 0.753673 -0.49407 0.433442 0.743213 -0.458238 0.487497 0.667687 -0.525348 0.52745 0.668973 -0.503764 0.546532 0.630891 -0.505634 0.588482 0.633824 -0.45361 0.626503 0.600772 -0.448982 0.661429 0.601593 -0.441651 0.665605 0.598585 -0.421741 0.681051 0.596815 -0.436592 0.6732 0.567427 -0.418263 0.709284 0.562753 -0.437506 0.701354 0.532106 -0.407503 0.742162 0.520788 -0.436959 0.73338 0.525432 -0.403666 0.748982 0.511153 -0.43798 0.739524 0.48841 -0.400299 0.775382 0.184479 -0.238178 0.95354 0.160639 -0.279437 0.946631 0.187278 -0.31648 0.929929 0.184203 -0.323975 0.92796 0.182749 -0.34894 0.919154 0.185809 -0.340928 0.921544 0.190877 -0.388053 0.901654 0.206933 -0.378491 0.902177 0.193016 -0.437161 0.878428 0.162347 -0.204338 0.965344 0.137171 -0.241592 0.960634 0.454203 -0.398111 0.796999 0.468583 -0.434331 0.769277 0.689457 -0.514702 0.509639 0.693015 -0.544779 0.472171 0.248488 -0.686244 0.68361 0.463166 -0.648059 0.604564 0.97343 -0.208552 0.0945564 0.947315 -0.159048 0.278027 0.891685 -0.353359 0.282906 0.683471 -0.539514 0.491724 0.61453 -0.414688 0.671109 0.794216 -0.468599 0.386828 0.270622 -0.659478 0.701322 0.252406 -0.631185 0.733415 0.0446348 -0.708459 0.70434 0.242778 -0.678757 0.693071 0.24783 -0.690226 0.67983 0.672281 -0.531246 0.515574 0.682241 -0.552324 0.479047 0.942166 -0.253682 0.219017 0.946151 -0.278058 0.165777 0.040764 -0.749104 0.661197 0.45942 -0.683725 0.566968 0.264931 -0.725001 0.635756 0.792175 -0.487442 0.367232 0.614164 -0.609497 0.501315 0.974298 -0.200347 0.10298 0.889985 -0.371707 0.264123 0.195688 -0.750047 0.631772 0.192355 -0.79207 0.579331 0.217615 -0.796543 0.564059 0.978332 -0.190232 0.0817226 0.978502 -0.188293 0.0841384 0.982739 -0.174579 0.0612061 0.197637 -0.818453 0.539514 0.192566 -0.865704 0.462034 0.201948 -0.865412 0.458562 0.196272 -0.902399 0.383606 0.201142 -0.917244 0.34381 0.198852 -0.91804 0.343017 0.190381 -0.945933 0.262615 0.19863 -0.945727 0.257191 0.191362 -0.960877 0.200239 0.215021 -0.963738 0.158034 0.981801 -0.184081 0.0466938 0.976894 -0.208227 0.0481592 0.981663 -0.189505 0.0206224 0.978993 -0.2036 -0.0109769 0.978851 -0.204326 -0.010108 0.974758 -0.217838 -0.0489325 0.975026 -0.216278 -0.0504783 0.969736 -0.226467 -0.0912374 0.970536 -0.221341 -0.0952235 0.964984 -0.226745 -0.131881 0.965991 -0.219655 -0.136431 0.19677 -0.968985 0.1495 0.184628 -0.980275 0.0705278 0.196943 -0.978434 0.062297 0.179496 -0.982978 -0.0391718 0.195152 -0.9797 -0.0458693 0.554132 -0.653914 0.515105 0.551051 -0.688969 0.470813 0.561967 -0.686349 0.461647 0.555622 -0.744281 0.370582 0.562974 -0.7411 0.36583 0.555442 -0.7891 0.262307 0.558415 -0.787907 0.259566 0.55009 -0.81533 0.18066 0.555203 -0.81287 0.176042 0.544018 -0.834179 0.0904934 0.551898 -0.829685 0.083854 0.539 -0.842305 -0.00101027 0.547824 -0.836553 -0.00825308 0.531444 -0.840931 -0.101998 0.544601 -0.831688 -0.108189 0.828689 -0.460608 0.317986 0.827337 -0.474862 0.300031 0.837581 -0.466725 0.283948 0.833021 -0.506917 0.221609 0.837461 -0.501914 0.216199 0.831705 -0.538242 0.136245 0.832398 -0.537451 0.135126 0.825656 -0.559653 0.0712842 0.827789 -0.5569 0.0680241 0.818845 -0.574015 -0.00051362 0.822853 -0.568223 -0.00599362 0.812852 -0.578003 -0.0720068 0.817549 -0.570556 -0.0779708 0.80499 -0.574131 -0.149548 0.813518 -0.560549 -0.154831 0.962691 -0.206444 -0.174949 0.946554 -0.26253 -0.187384 0.960831 -0.221285 -0.166843 0.189005 -0.978813 -0.078752 0.539045 -0.830759 -0.138819 0.809291 -0.559688 -0.178317 0.95971 -0.205759 -0.191361 0.190276 -0.978535 -0.0791541 0.191112 -0.978729 -0.0745998 0.191357 -0.978676 -0.074676 0.192404 -0.978994 -0.0674693 0.192671 -0.978934 -0.0675716 0.193607 -0.979297 -0.0591138 0.194069 -0.979198 -0.0592376 0.194689 -0.979673 -0.048343 0.195087 -0.97959 -0.048429 0.542302 -0.828462 -0.139856 0.544648 -0.828996 -0.126987 0.545249 -0.828571 -0.127177 0.548249 -0.829493 -0.106604 0.548928 -0.829008 -0.106884 0.551571 -0.830013 -0.0827559 0.552718 -0.829216 -0.0830819 0.554482 -0.830567 -0.0520472 0.555501 -0.82987 -0.0522846 0.812885 -0.554039 -0.179606 0.816368 -0.554839 -0.160301 0.817034 -0.553787 -0.160549 0.821564 -0.55517 -0.129688 0.822294 -0.553997 -0.13008 0.826197 -0.555503 -0.0938875 0.827477 -0.553515 -0.0943543 0.830113 -0.555539 -0.0478486 0.831228 -0.553838 -0.0482 0.961442 -0.196431 -0.192469 0.965548 -0.19741 -0.169549 0.965849 -0.195737 -0.169773 0.971238 -0.19735 -0.13323 0.971567 -0.195418 -0.133679 0.976136 -0.197251 -0.0908327 0.976737 -0.194007 -0.0913601 0.979848 -0.196404 -0.036371 0.98039 -0.193596 -0.0368174 0.19509 -0.979953 -0.0404062 0.55556 -0.830955 -0.0294517 0.831424 -0.555462 -0.0140062 0.980712 -0.195424 0.00358518 0.195201 -0.979929 -0.0404546 0.195008 -0.980258 -0.032653 0.195163 -0.980226 -0.0326743 0.194363 -0.98067 -0.0225499 0.19445 -0.980653 -0.022557 0.193745 -0.980904 -0.0170339 0.193763 -0.9809 -0.0170452 0.193056 -0.981115 -0.0119408 0.193129 -0.981101 -0.0119402 0.192189 -0.981335 -0.00665464 0.191562 -0.981458 -0.00668675 0.191772 -0.981409 -0.00777338 0.188446 -0.982051 -0.00794039 0.555845 -0.830759 -0.0295949 0.555251 -0.83165 -0.00738995 0.555634 -0.831393 -0.00744912 0.553365 -0.832665 0.0213686 0.553595 -0.832513 0.0213461 0.551625 -0.833267 0.037078 0.551677 -0.833235 0.03704 0.549632 -0.833814 0.0515763 0.549834 -0.83368 0.0515762 0.547191 -0.83436 0.0665252 0.54558 -0.83542 0.0664523 0.546248 -0.835255 0.0629483 0.537698 -0.840812 0.0625724 0.831744 -0.554977 -0.0142425 0.830757 -0.556311 0.0190026 0.831196 -0.555658 0.0188988 0.827816 -0.557561 0.0620204 0.828068 -0.557191 0.061976 0.825205 -0.558321 0.0855266 0.825276 -0.558227 0.0854494 0.822144 -0.559094 0.107208 0.822374 -0.558758 0.107195 0.818462 -0.559773 0.129513 0.816663 -0.562394 0.129518 0.817697 -0.562134 0.124004 0.807906 -0.576112 0.124027 0.980871 -0.19463 0.00325646 0.979625 -0.196286 0.0425018 0.979849 -0.195202 0.0423414 0.975875 -0.197433 0.093208 0.976012 -0.196797 0.093123 0.972705 -0.198059 0.1209 0.972746 -0.197923 0.120799 0.968993 -0.199003 0.146458 0.969127 -0.198391 0.146406 0.964554 -0.199558 0.172663 0.963603 -0.203871 0.172935 0.964879 -0.20356 0.166049 0.959407 -0.226905 0.16749 0.875771 -0.423881 -0.230976 0.968845 -0.225577 -0.102242 0.585226 -0.688823 -0.427823 0.769863 -0.54718 -0.32849 0.422678 -0.760957 -0.492228 0.183783 -0.813212 -0.552187 0.221726 -0.814247 -0.536507 0.195458 -0.85391 -0.482321 0.191536 -0.88778 -0.418521 0.196017 -0.978997 -0.056064 0.182911 -0.981599 -0.0548298 0.199914 -0.959383 -0.199042 0.188294 -0.962167 -0.196929 0.196586 -0.936564 -0.290176 0.220025 -0.924265 -0.311967 0.194185 -0.921328 -0.336819 0.199493 -0.885272 -0.420114 0.557205 -0.707967 -0.43394 0.551672 -0.763508 -0.335728 0.560271 -0.756972 -0.33629 0.554236 -0.796555 -0.241501 0.557966 -0.79366 -0.242441 0.547837 -0.826292 -0.130831 0.553594 -0.822321 -0.13161 0.537275 -0.843384 0.00632345 0.546379 -0.837521 0.00544832 0.83205 -0.488011 -0.2637 0.828205 -0.522986 -0.2014 0.835227 -0.51189 -0.200909 0.830737 -0.541257 -0.130064 0.832289 -0.53877 -0.130471 0.824367 -0.564294 -0.0446138 0.825421 -0.562739 -0.0447667 0.81208 -0.579707 0.0668294 0.816728 -0.573228 0.0660706 0.96555 -0.225307 0.130195 0.958957 -0.260124 0.112856 0.969552 -0.225779 0.0948282 0.974582 -0.218648 0.0488078 0.975318 -0.215412 0.0485093 0.979549 -0.201203 0.00143205 0.979332 -0.202252 0.00157148 0.981691 -0.187289 -0.0347263 0.978625 -0.202525 -0.0357457 0.980145 -0.189164 -0.0594409 0.945125 -0.293952 -0.142586 0.96556 -0.115398 -0.233188 0.189259 -0.759934 -0.621837 0.250475 -0.688927 -0.680178 0.879137 -0.39296 -0.269631 0.773337 -0.518011 -0.365533 0.681877 -0.495711 -0.53788 0.591296 -0.637195 -0.494319 0.42853 -0.710236 -0.558504 0.939826 -0.299692 -0.164047 0.948358 -0.258062 -0.184448 0.671159 -0.588112 -0.451299 0.6813 -0.565389 -0.464937 0.242354 -0.740233 -0.627152 0.247772 -0.732548 -0.634021 0.243882 -0.721168 -0.648412 0.244225 -0.719463 -0.650175 0.673884 -0.554024 -0.488813 0.942969 -0.261594 -0.205861 0.239909 -0.711327 -0.660649 0.241364 -0.689208 -0.683181 0.235467 -0.696835 -0.677478 0.238937 -0.630872 -0.73818 0.222865 -0.639771 -0.735544 0.227135 -0.57109 -0.788839 0.24255 -0.54235 -0.804379 0.211667 -0.522853 -0.825725 0.21832 -0.471874 -0.854208 0.210694 -0.484753 -0.848895 0.221535 -0.412159 -0.883769 0.188544 -0.428893 -0.88346 0.207338 -0.357211 -0.91072 0.213126 -0.342425 -0.915053 0.180872 -0.305863 -0.934737 0.198241 -0.260491 -0.944905 0.179501 -0.286766 -0.941034 0.205891 -0.221745 -0.95312 0.150526 -0.234195 -0.960466 0.190251 -0.164284 -0.967892 0.142971 -0.167576 -0.975437 0.663931 -0.576643 -0.476108 0.666548 -0.53951 -0.514435 0.655335 -0.562506 -0.504107 0.65839 -0.498441 -0.563986 0.628783 -0.530524 -0.568486 0.634074 -0.445052 -0.632361 0.602212 -0.477541 -0.639762 0.609529 -0.424829 -0.669324 0.598915 -0.449151 -0.662996 0.606156 -0.400995 -0.68686 0.565865 -0.436123 -0.69971 0.583499 -0.36777 -0.724068 0.528382 -0.405935 -0.745674 0.548302 -0.354665 -0.757349 0.525661 -0.391658 -0.755172 0.541148 -0.354103 -0.762738 0.484158 -0.37867 -0.788797 0.500643 -0.349871 -0.7918 0.451406 -0.360892 -0.816082 0.934437 -0.30302 -0.1871 0.937383 -0.262919 -0.228444 0.927797 -0.305484 -0.214179 0.930745 -0.251815 -0.265147 0.905947 -0.316086 -0.281693 0.909819 -0.260625 -0.322961 0.881913 -0.322674 -0.343672 0.885621 -0.294491 -0.359097 0.874727 -0.33388 -0.351251 0.878455 -0.310847 -0.362893 0.842456 -0.371757 -0.389955 0.848452 -0.348758 -0.398118 0.797581 -0.414579 -0.438166 0.808564 -0.385576 -0.444473 0.782671 -0.436944 -0.44329 0.788181 -0.424124 -0.44597 0.737033 -0.466865 -0.488692 0.731606 -0.476303 -0.487738 0.686486 -0.500305 -0.527666 0.648177 -0.530111 -0.546671 0.677365 -0.51293 -0.527333 0.430435 -0.361827 -0.826927 0.457474 -0.352558 -0.816346 0.144723 -0.139668 -0.979565 0.166662 -0.13502 -0.976726 0.616887 -0.549856 -0.563124 0.642112 -0.537507 -0.546606 0.410602 -0.367453 -0.834496 0.430142 -0.362184 -0.826923 0.141636 -0.131597 -0.981133 0.152707 -0.129902 -0.979697 0.325397 -0.420625 -0.846871 0.421021 -0.471183 -0.775066 0.523155 -0.668509 -0.528588 0.108458 -0.133675 -0.985073 0.521836 -0.612026 -0.594232 0.492134 -0.63614 -0.594248 0.489611 -0.634213 -0.598376 0.512453 -0.616042 -0.598234 0.520019 -0.619223 -0.58834 0.566167 -0.577266 -0.588404 0.58897 -0.580064 -0.562708 0.323382 -0.418837 -0.848528 0.338538 -0.406871 -0.848439 0.344285 -0.410284 -0.844473 0.375201 -0.382129 -0.844513 0.392174 -0.387702 -0.834198 0.250891 -0.406135 -0.878697 0.353354 -0.397809 -0.846693 0.105459 -0.15365 -0.982482 0.113742 -0.146957 -0.982581 0.112977 -0.146245 -0.982776 0.118102 -0.14222 -0.982764 0.120244 -0.14365 -0.982296 0.130763 -0.134061 -0.982308 0.13703 -0.136718 -0.981087 0.690919 0.695832 0.196085 0.592316 0.768615 0.241646 0.838498 0.497323 0.222692 0.866243 0.406206 0.290897 0.930159 0.269015 0.249871 0.957178 0.130487 0.258424 0.957756 -0.0421514 0.284476 0.962798 -0.0948442 0.253032 0.851114 -0.481745 0.208633 0.585243 -0.760782 0.280539 0.838939 -0.500103 0.21466 0.166415 0.984941 0.0468701 0.198898 0.970996 0.132688 0.379311 0.919252 0.105348 0.52819 0.836354 0.146723 0.833112 -0.461403 0.305012 0.821976 -0.480968 0.305001 0.938516 -0.0246598 0.344354 0.936947 -0.0420345 0.346936 0.85317 0.417036 0.313341 0.857279 0.405593 0.317124 0.593869 0.774418 0.218164 0.598945 0.76957 0.221418 0.212639 0.974013 0.0779957 0.214828 0.973429 0.0792716 0.794307 -0.441424 0.417399 0.783674 -0.461529 0.415749 0.884905 -0.00707647 0.465717 0.883398 -0.024668 0.467974 0.799383 0.428666 0.420989 0.803231 0.417152 0.42521 0.554356 0.779376 0.292 0.559102 0.774524 0.295834 0.198149 0.974611 0.104258 0.200177 0.974033 0.105773 0.464907 0.773607 0.430575 0.663859 0.421999 0.61742 0.729766 -0.00693441 0.683662 0.652391 -0.433772 0.621473 0.449228 0.801249 0.395214 0.2782 0.802397 0.52798 0.270824 0.8375 0.474603 0.153131 0.840507 0.51971 0.163157 0.854533 0.493106 0.656253 0.486976 0.576357 0.40397 0.488288 0.773552 0.406659 0.573903 0.710819 0.227834 0.578559 0.783174 0.247825 0.614081 0.749324 0.0217905 0.983288 0.18075 0.0586165 0.983435 0.171521 0.0556096 0.981849 0.181327 0.0966744 0.981341 0.166207 0.100694 0.977295 0.186431 0.161094 0.976982 0.139837 0.168106 0.973757 0.153421 0.0245608 0.987391 0.156384 0.0465411 0.912553 0.406302 0.0724097 0.853833 0.515486 0.0717255 0.836505 0.543245 0.0813475 0.611162 0.787314 0.104871 0.703217 0.703199 0.102766 0.541723 0.834251 0.750604 0.0930652 0.654165 0.456448 0.0933827 0.884836 0.486931 0.231402 0.84223 0.26801 0.234171 0.934524 0.302702 0.294022 0.9066 0.10984 0.292474 0.949944 0.132403 0.403166 0.905498 0.721083 -0.31468 0.617265 0.426932 -0.315648 0.847405 0.503513 -0.141311 0.852353 0.266917 -0.143242 0.953015 0.321972 -0.0638193 0.944596 0.0889082 -0.0632551 0.994029 0.157081 0.154491 0.975427 -0.000737517 0.608747 0.793364 0.00110558 0.707115 0.707097 -0.000737125 0.793359 0.608754 0 0.838665 0.544648 0 0.896874 0.442286 0.000460949 0.913543 0.406743 -0.00110292 0.980785 0.19509 0 0.987689 0.156431 0 0.195095 0.980784 -0.00137555 0.156433 0.987688 0.000736732 0.442291 0.896871 0 0.406747 0.913541 0 0.544607 0.838692 0.410902 0.890593 0.194947 0.115461 0.974226 0.193786 0.30762 0.946243 -0.0999722 0.105699 0.89185 0.439808 0.092283 0.828351 0.552557 0.115461 0.974226 0.193786 0.339987 0.920248 0.193785 0.288771 0.781621 0.552883 0.0600973 0.555482 0.829354 0.0719594 0.607169 0.791307 0.093613 0.789875 0.606081 0.327224 0.835944 0.440592 0.275658 0.746128 0.606057 0.19346 0.523641 0.829683 0.0231159 0.195044 0.980522 0.0231156 0.195043 0.980522 0.0523466 0.441685 0.895642 0.219584 0.569993 0.791764 0.154131 0.417189 0.895655 0.0680673 0.184239 0.980522 0.0680675 0.18424 0.980522 0.607677 0.0598496 0.791926 0.512907 0.836116 0.194518 0.415335 0.677045 0.607542 0.469244 0.764923 0.441252 0.231824 0.37791 0.896349 0.318923 0.519896 0.792462 0.10232 0.166796 0.980668 0.493908 0.830423 0.257785 0.627563 0.734554 0.258062 0.627567 0.734554 0.25805 0.746922 0.612975 0.257623 0.746908 0.612975 0.257662 0.852139 0.455486 0.257664 0.852146 0.455485 0.257644 0.924635 0.280483 0.257643 0.924632 0.280484 0.257652 0.961585 0.0947101 0.257652 0.961591 0.0947061 0.257632 0.355796 0.613224 0.705242 0.460009 0.53843 0.706035 0.460014 0.538433 0.706029 0.547909 0.449659 0.70541 0.547917 0.449663 0.7054 0.625112 0.334132 0.705401 0.625111 0.334132 0.705402 0.678286 0.205756 0.705402 0.678284 0.205756 0.705405 0.705392 0.0694733 0.705405 0.792303 0.0508049 0.608008 0.125374 0.228675 0.965396 0.16861 0.197353 0.965724 0.168607 0.197351 0.965725 0.200978 0.164938 0.96561 0.200972 0.164935 0.965612 0.229287 0.122558 0.965612 0.229292 0.122559 0.965611 0.248797 0.075472 0.965611 0.248793 0.0754716 0.965612 0.258736 0.0254827 0.965612 0.258741 0.0254821 0.965611 0.980788 0 0.195077 0.965924 -0.0042524 0.258793 0.831459 0.00284699 0.555579 0.793328 0 0.608795 0.55559 0 0.831456 0.608763 0.00425188 0.793341 0.195088 -0.00564282 0.980769 0.258825 0 0.965924 0.980788 0 0.195077 0.980788 0 0.195077 0.831462 0 0.555581 0.831462 0 0.555581 0.55559 0 0.831456 0.55559 0 0.831456 0.195092 0 0.980785 0.195092 0 0.980785 0.195021 -0.0269592 0.980429 0.255004 -0.365452 0.89522 0.553959 -0.076579 0.829015 0.455587 -0.652919 0.605092 0.826024 -0.114188 0.551947 0.78513 -0.618741 0.0270361 0.758661 -0.622128 0.193366 0.874044 -0.445188 0.194565 0.911977 -0.398651 -0.0968223 0.926742 -0.321289 0.194737 0.971899 -0.134353 0.193293 0.971896 -0.134351 0.193308 0.679946 -0.706852 0.195021 0.561441 -0.804625 0.193294 0.561441 -0.804619 0.193321 0.826031 -0.11419 0.551936 0.764076 -0.333999 0.551935 0.764079 -0.334002 0.55193 0.64481 -0.528767 0.55193 0.644807 -0.528763 0.551936 0.47718 -0.683862 0.551935 0.501738 -0.744904 0.439747 0.55395 -0.0765767 0.829021 0.5124 -0.223985 0.829022 0.512397 -0.223983 0.829024 0.432412 -0.354592 0.829026 0.432404 -0.354583 0.829034 0.319992 -0.458592 0.829035 0.344107 -0.505817 0.791037 0.195013 -0.0269572 0.98043 0.180386 -0.0788521 0.98043 0.180392 -0.0788551 0.980429 0.152235 -0.124837 0.980429 0.152236 -0.124838 0.980428 0.11266 -0.161456 0.980428 0.112664 -0.161463 0.980427 0.280487 -0.92463 0.257655 0.410902 -0.890594 0.194943 0.468156 -0.765567 0.441291 0.326978 -0.941977 0.0759302 0.26108 -0.752135 0.605087 0.242519 -0.668546 0.703015 0.200819 -0.578528 0.790555 0.146144 -0.421016 0.895202 0.0927774 -0.245193 0.965025 0.0645661 -0.186005 0.980425 0.0947077 -0.961584 0.257655 0.0947077 -0.961584 0.257655 0.0694754 -0.705397 0.7054 0.0694755 -0.705396 0.7054 0.0254836 -0.258739 0.965611 0.0254836 -0.258739 0.965611 0.10708 -0.993793 0.0301586 0.187017 -0.967363 0.170979 0.965553 0.0421449 0.256772 0.931705 -0.0818541 0.353871 0.962798 0.0948442 0.253032 0.848811 0.481876 0.217522 0.84387 0.494609 0.207957 0.700933 0.691789 0.173553 0.32344 -0.941981 0.0897653 0.471379 -0.87216 0.130919 0.59825 -0.769485 0.223583 0.64277 -0.742978 0.186628 0.884344 -0.406431 0.229672 0.824608 -0.473594 0.309403 0.928078 -0.274534 0.251599 0.212461 -0.97402 0.0783979 0.21495 -0.973436 0.0788531 0.593374 -0.774464 0.219347 0.599332 -0.769616 0.220208 0.852426 -0.41709 0.315286 0.857968 -0.40565 0.315181 0.937522 0.0246646 0.34705 0.93793 0.0420432 0.344268 0.831786 0.461507 0.308454 0.823179 0.481081 0.301559 0.197943 -0.974617 0.104593 0.200338 -0.974039 0.105418 0.553779 -0.779407 0.293007 0.559596 -0.774562 0.294797 0.798481 -0.42871 0.422654 0.804088 -0.417198 0.423544 0.883685 0.00707754 0.468029 0.884605 0.0246722 0.465688 0.792703 0.441503 0.420354 0.785186 0.461616 0.412788 0 -0.913543 0.406743 -0.00293629 -0.965922 0.258817 0 -0.987689 0.156431 0 -0.838665 0.544648 -0.00195361 -0.707114 0.707097 -0.00195418 -0.707104 0.707107 0 -0.156433 0.987689 -0.00293632 -0.258822 0.965921 0 -0.406747 0.913541 0 -0.544607 0.838692 0.0323741 -0.544321 0.838252 0.013788 -0.913456 0.406704 0.00646399 -0.987668 0.156428 0.0267367 -0.838365 0.544453 0.0208145 -0.706963 0.706945 0.0537497 -0.406159 0.91222 0.0268199 -0.156376 0.987333 0.0117601 -0.986281 0.164657 0.0342819 -0.986072 0.162746 0.0441437 -0.981843 0.184488 0.0665064 -0.982036 0.176586 0.0727766 -0.981466 0.177281 0.0953915 -0.981128 0.168192 0.109079 -0.977404 0.181059 0.132364 -0.977738 0.162815 0.137534 -0.9774 0.160543 0.161315 -0.976862 0.140419 0.173566 -0.974151 0.144584 0.0431874 -0.878779 0.47527 0.0947514 -0.877434 0.470247 0.12006 -0.840529 0.528297 0.184794 -0.842229 0.506459 0.202485 -0.837291 0.507881 0.267363 -0.835213 0.480558 0.302491 -0.802981 0.513537 0.369685 -0.805555 0.463048 0.38381 -0.802715 0.456441 0.450558 -0.799493 0.397251 0.481465 -0.776136 0.407192 0.0427408 -0.675408 0.736205 0.146085 -0.673055 0.725022 0.178221 -0.579688 0.795109 0.276865 -0.582493 0.76423 0.303409 -0.570147 0.763463 0.400109 -0.566999 0.720018 0.441709 -0.488094 0.752767 0.541705 -0.491563 0.681852 0.562766 -0.484504 0.669738 0.657542 -0.480375 0.580412 0.690791 -0.424954 0.584997 0.050022 -0.398491 0.915807 0.182063 -0.396355 0.899864 0.211007 -0.238172 0.948024 0.328431 -0.239856 0.913566 0.361767 -0.219218 0.906128 0.47374 -0.217525 0.853377 0.504236 -0.0901289 0.85885 0.617475 -0.0909594 0.781314 0.643039 -0.0797781 0.761667 0.746596 -0.0789152 0.660581 0.764022 0.00700107 0.645152 0.0586233 -0.0782663 0.995207 0.198591 -0.0777534 0.976993 0.214309 0.135915 0.967264 0.331376 0.136932 0.933509 0.369874 0.163897 0.914511 0.477739 0.162637 0.863316 0.48079 0.322993 0.815179 0.582199 0.325606 0.745 0.611541 0.339246 0.714794 0.703399 0.336112 0.626306 0.689358 0.43799 0.577018 0.931619 -0.220317 -0.289045 0.87153 -0.388662 -0.298961 0.951653 -0.0768852 -0.297397 0.947606 0.0693349 -0.311827 0.946056 0.157025 -0.283408 0.82626 0.511815 -0.235245 0.581134 0.771089 -0.260202 0.796478 0.554349 -0.241495 0.166117 -0.984621 -0.0541055 0.211977 -0.972442 -0.0970701 0.852177 -0.446763 -0.272392 0.703284 -0.675556 -0.221392 0.60565 -0.76288 -0.226278 0.529095 -0.831397 -0.169817 0.381157 -0.916397 -0.12221 0.795967 0.494761 -0.348782 0.785825 0.511234 -0.348022 0.914308 0.0542819 -0.401365 0.912417 0.0691256 -0.403382 0.840069 -0.397599 -0.369051 0.843205 -0.387616 -0.372504 0.588345 -0.766167 -0.258529 0.592465 -0.761938 -0.261602 0.211274 -0.973019 -0.0927277 0.213082 -0.972506 -0.0939544 0.745106 0.479113 -0.46397 0.736052 0.494912 -0.461834 0.847889 0.040211 -0.528647 0.846105 0.0543013 -0.530244 0.774966 -0.40708 -0.48344 0.777573 -0.397727 -0.487024 0.541051 -0.770267 -0.33757 0.544559 -0.766293 -0.340955 0.193991 -0.973521 -0.120931 0.19553 -0.973042 -0.122297 0.0156524 -0.872388 -0.488563 0.0416813 -0.15632 -0.986827 0.0346103 -0.453713 -0.890475 0.0265174 -0.706855 -0.706861 0.0046095 -0.938185 -0.346103 0.00760385 -0.98766 -0.15643 -0.00404508 -0.120216 -0.99274 0.186405 -0.118865 -0.975256 0.113844 0.11545 -0.986768 0.315864 0.116653 -0.941606 0.263662 0.159146 -0.951396 0.462607 0.15713 -0.872528 0.379512 0.337539 -0.861417 0.561161 0.341763 -0.753855 0.5153 0.362451 -0.776592 0.679828 0.357337 -0.640425 0.603037 0.47302 -0.642338 -0.000302483 -0.42835 -0.903613 0.162637 -0.424738 -0.890588 0.119773 -0.252599 -0.960129 0.301976 -0.254829 -0.918625 0.265872 -0.222541 -0.93797 0.448009 -0.220091 -0.866515 0.411748 -0.0763524 -0.908094 0.588549 -0.0773108 -0.804757 0.557886 -0.0602897 -0.827725 0.719187 -0.0594233 -0.692271 0.691206 0.0396197 -0.721571 0.00172787 -0.692463 -0.721451 0.126894 -0.688928 -0.713636 0.104886 -0.587866 -0.80213 0.249897 -0.591221 -0.766817 0.226504 -0.571946 -0.788399 0.374404 -0.567713 -0.73316 0.367121 -0.478408 -0.797714 0.514672 -0.48279 -0.708538 0.495294 -0.472091 -0.729256 0.634285 -0.46696 -0.616142 0.636169 -0.402377 -0.658317 0.0414997 -0.885118 -0.463513 0.0813178 -0.88349 -0.461338 0.0723194 -0.843659 -0.531986 0.16558 -0.845598 -0.507492 0.152387 -0.837975 -0.524 0.249443 -0.835231 -0.490068 0.253836 -0.79866 -0.545628 0.351174 -0.801875 -0.483398 0.340387 -0.797571 -0.498013 0.436106 -0.793507 -0.424451 0.447855 -0.766037 -0.4611 0.00264987 -0.987043 -0.160435 0.0295311 -0.986756 -0.1595 0.0275533 -0.982208 -0.185766 0.0596848 -0.982412 -0.176931 0.0553997 -0.981554 -0.182983 0.0892529 -0.981096 -0.17171 0.0922933 -0.976875 -0.192866 0.126207 -0.977279 -0.170284 0.122606 -0.976801 -0.175578 0.156861 -0.976098 -0.150425 0.162459 -0.972906 -0.164504 0 -0.987688 -0.156435 -0.00124328 -0.980785 -0.19509 0 -0.938195 -0.346107 0 -0.872495 -0.488623 -0.00186688 -0.831466 -0.555573 0.00124616 -0.707103 -0.707109 -0.0018667 -0.555574 -0.831465 0.000934582 -0.453985 -0.891009 -0.00124276 -0.195095 -0.980784 0 -0.156456 -0.987685 0.410902 -0.890594 -0.194943 0.28877 -0.781616 -0.552892 0.339988 -0.920248 -0.193785 0.307619 -0.946243 0.0999767 0.327226 -0.835944 -0.440592 0.275654 -0.746115 -0.606075 0.193465 -0.523653 -0.829674 0.115461 -0.974226 -0.193786 0.115461 -0.974226 -0.193786 0.0980672 -0.82746 -0.552896 0.0980675 -0.82746 -0.552894 0.0657023 -0.554374 -0.82967 0.0657017 -0.554372 -0.829672 0.0231156 -0.195043 -0.980522 0.023116 -0.195044 -0.980522 0.219591 -0.570009 -0.791751 0.154131 -0.417189 -0.895655 0.0680673 -0.184239 -0.980522 0.0680675 -0.18424 -0.980522 0.512908 -0.836116 -0.194514 0.415328 -0.677034 -0.607559 0.469244 -0.764923 -0.441252 0.231824 -0.37791 -0.896349 0.318933 -0.519912 -0.792448 0.10232 -0.166796 -0.980668 0.493908 -0.830423 -0.257782 0.627563 -0.734554 -0.25806 0.627567 -0.734554 -0.258051 0.746921 -0.612975 -0.257624 0.746908 -0.612975 -0.257662 0.852139 -0.455486 -0.257664 0.852146 -0.455485 -0.257644 0.924635 -0.280483 -0.257643 0.924632 -0.280484 -0.257652 0.961585 -0.0947101 -0.257652 0.961591 -0.0947061 -0.257632 0.355797 -0.613221 -0.705243 0.460007 -0.538429 -0.706036 0.460015 -0.538434 -0.706028 0.547909 -0.44966 -0.705409 0.547917 -0.449663 -0.7054 0.625112 -0.334132 -0.705401 0.625111 -0.334132 -0.705402 0.678286 -0.205756 -0.705402 0.678283 -0.205756 -0.705405 0.705391 -0.0694733 -0.705405 0.705391 -0.0694734 -0.705405 0.125374 -0.228675 -0.965396 0.16861 -0.197353 -0.965724 0.168607 -0.197351 -0.965725 0.200978 -0.164938 -0.965611 0.200972 -0.164935 -0.965612 0.229287 -0.122558 -0.965612 0.229292 -0.122559 -0.965611 0.248797 -0.075472 -0.965611 0.248793 -0.0754716 -0.965612 0.258736 -0.0254827 -0.965612 0.258741 -0.0254821 -0.965611 0.965932 0 -0.258795 0.965932 0 -0.258795 0.7071 0 -0.707114 0.7071 0 -0.707114 0.258825 0 -0.965924 0.258825 0 -0.965924 0.980788 0 -0.195077 0.965924 0.0042524 -0.258793 0.896897 0 -0.44224 0.793317 0 -0.608808 0.707088 0.005677 -0.707103 0.195092 0 -0.980785 0.258823 0.00425357 -0.965915 0.442331 0 -0.896852 0.608786 0 -0.793334 0.679946 0.706852 -0.195021 0.78513 0.61874 -0.0270358 0.971896 0.134351 -0.193308 0.971899 0.134353 -0.193293 0.890082 0.123043 -0.438879 0.826912 0.109242 -0.551618 0.555087 0.0717959 -0.828688 0.606642 0.0838619 -0.79054 0.788589 0.109014 -0.60518 0.195013 0.0269572 -0.98043 0.195021 0.0269592 -0.980429 0.441506 0.0610327 -0.89518 0.926742 0.321289 -0.194737 0.911977 0.398651 0.0968223 0.76407 0.333997 -0.551944 0.764074 0.333999 -0.551939 0.512412 0.22399 -0.829013 0.512409 0.223989 -0.829015 0.180386 0.0788521 -0.98043 0.180392 0.0788551 -0.980429 0.874044 0.445188 -0.194565 0.758661 0.622128 -0.193366 0.644805 0.528763 -0.551939 0.644803 0.52876 -0.551944 0.432423 0.354601 -0.829017 0.432414 0.354592 -0.829025 0.152235 0.124837 -0.980429 0.152236 0.124838 -0.980428 0.561441 0.804625 -0.193294 0.56144 0.804618 -0.193325 0.477177 0.683858 -0.551942 0.47718 0.683865 -0.551932 0.32 0.458603 -0.829026 0.319991 0.458587 -0.829038 0.11266 0.161456 -0.980428 0.112664 0.161463 -0.980427 0.303263 0.932843 -0.194514 0.410902 0.890593 -0.194947 0.346556 0.938029 2.11274e-05 0.28877 0.781617 -0.55289 0.288769 0.781616 -0.552892 0.193463 0.523648 -0.829678 0.193464 0.523653 -0.829674 0.0680675 0.18424 -0.980522 0.0680673 0.184239 -0.980522 0.115461 0.974226 -0.193786 0.115461 0.974226 -0.193786 0.0980673 0.82746 -0.552894 0.0980674 0.82746 -0.552896 0.0657021 0.554372 -0.829672 0.065702 0.554374 -0.82967 0.0231158 0.195044 -0.980522 0.0231158 0.195043 -0.980522 0.877448 0.388557 -0.281263 0.672864 0.709001 -0.21112 0.606957 0.762915 -0.222629 0.491763 0.856309 -0.157807 0.347775 0.930928 -0.111468 0.208985 0.972215 -0.105471 0.130504 0.990536 -0.042506 0.82207 -0.512131 -0.248843 0.805756 -0.545611 -0.230359 0.659861 -0.727086 -0.189553 0.846866 0.43904 -0.300103 0.931619 0.220317 -0.289045 0.951581 -0.0693126 -0.299482 0.937069 0.0489185 -0.345701 0.946056 -0.157025 -0.283408 0.21109 0.973025 -0.0930758 0.213213 0.972513 -0.0935863 0.58784 0.766209 -0.259552 0.592873 0.761982 -0.260547 0.839299 0.39765 -0.370745 0.843929 0.387668 -0.370807 0.913284 -0.0542922 -0.403689 0.913431 -0.0691392 -0.401078 0.79459 -0.494866 -0.351759 0.787073 -0.511347 -0.345024 0.193795 0.973525 -0.121212 0.195691 0.973048 -0.121998 0.540485 0.770301 -0.338397 0.545051 0.766327 -0.340091 0.774088 0.407118 -0.484812 0.778414 0.397768 -0.485645 0.8467 -0.040217 -0.530548 0.847283 -0.0543098 -0.528358 0.743537 -0.479192 -0.466399 0.737529 -0.494997 -0.459379 0 0.987688 -0.156435 -0.00124328 0.980785 -0.19509 0 0.938195 -0.346107 0 0.872495 -0.488623 -0.00186688 0.831466 -0.555573 0.00124616 0.707103 -0.707109 -0.00370782 0.453982 -0.891003 0.00185585 0.555574 -0.831465 -0.00154985 0.156456 -0.987684 0 0.195095 -0.980784 0.637887 -0.476557 -0.604974 0.651296 -0.369252 -0.662922 0.721343 -0.0398975 -0.691427 0.702552 0.0522499 -0.709712 0.659157 0.404374 -0.634029 0.624004 0.464266 -0.628552 0.462052 0.767794 -0.443847 0.167235 0.973177 -0.157983 0.456748 -0.368956 -0.809477 0.458235 -0.192304 -0.867779 0.48898 0.0522065 -0.870731 0.459135 0.194646 -0.86678 0.433556 0.464069 -0.772444 0.390217 0.553144 -0.736045 0.300212 -0.193499 -0.93404 0.273463 -0.0772467 -0.958776 0.297925 0.195862 -0.93428 0.264713 0.28447 -0.921414 0.252304 0.55564 -0.792217 0.219926 0.608675 -0.76233 0.117225 -0.0768985 -0.990124 0.102793 0.155627 -0.982453 0.114529 0.283359 -0.952151 0.091395 0.452085 -0.88728 0.096544 0.607155 -0.788696 0.0717778 0.70528 -0.705286 0.0640868 0.870701 -0.487619 0.429472 0.793074 -0.431957 0.29909 0.793021 -0.530719 0.261685 0.829675 -0.493113 0.169586 0.831386 -0.529186 0.145659 0.852459 -0.502093 0.0602704 0.851386 -0.521065 0.0378176 0.937524 -0.345859 0.154258 0.976121 -0.152944 0.108345 0.976219 -0.18777 0.0936268 0.980474 -0.172928 0.0615399 0.980784 -0.185138 0.0525598 0.983206 -0.174765 0.0249389 0.983147 -0.18111 0.0172657 0.987541 -0.156411 -0.841664 0.104005 -0.529891 -0.0691046 0.705417 -0.705416 -0.0608672 0.708256 -0.703327 -0.190667 0.683547 -0.704564 -0.841675 0.0819965 -0.533723 -0.798517 0.210984 -0.563788 -0.775838 0.246961 -0.580591 -0.759037 0.280358 -0.58759 -0.68814 0.381913 -0.616932 -0.701438 0.347878 -0.622066 -0.598433 0.48951 -0.634239 -0.634956 0.431671 -0.640696 -0.549835 0.522484 -0.651684 -0.569236 0.500964 -0.651925 -0.468044 0.574419 -0.671548 -0.498565 0.541739 -0.676722 -0.382506 0.633492 -0.67259 -0.431975 0.590259 -0.681903 -0.311502 0.655542 -0.687918 -0.318451 0.651012 -0.689037 -0.218452 0.677771 -0.702072 -0.145163 0.703883 -0.695325 -0.866026 0 -0.499999 -0.866026 0 -0.499999 -0.866026 0 -0.499999 -0.866026 0 -0.499999 0.866027 -1.34366e-05 -0.499998 0.866024 -1.32575e-06 -0.500002 0.866024 -8.19555e-06 -0.500002 0.866027 1.38733e-05 -0.499998 0.866027 1.30157e-05 -0.499998 0.866027 -1.1752e-05 -0.499998 0.217166 0.682269 -0.698103 0.107071 0.698391 -0.707663 0.0861103 0.696951 -0.71193 0.0334116 0.706712 -0.706712 0.223612 0.681925 -0.696402 0.31382 0.647201 -0.694729 0.338813 0.633955 -0.695203 0.378619 0.622688 -0.684768 0.475109 0.569048 -0.67116 0.487694 0.564178 -0.666226 0.54372 0.520596 -0.658293 0.599261 0.476744 -0.643119 0.846578 0.0862532 -0.525229 0.835566 0.104555 -0.539349 0.787647 0.235315 -0.56942 0.77775 0.248564 -0.577339 0.699734 0.367337 -0.612728 0.684885 0.379051 -0.622296 0.591786 0.486745 -0.642549 0.367943 -0.62909 -0.684736 0.365995 -0.630585 -0.684405 0.46258 -0.575476 -0.674424 0.430882 -0.60131 -0.67288 0.508697 -0.539911 -0.670615 0.485577 -0.562666 -0.669045 0.57219 -0.498497 -0.651229 0.549363 -0.524976 -0.650078 0.630943 -0.43387 -0.64317 0.626122 -0.441715 -0.642541 0.712808 -0.356025 -0.604277 0.718806 -0.344766 -0.6037 0.787292 -0.222875 -0.574889 0.787206 -0.223349 -0.574823 0.850826 -0.0769591 -0.519781 0.848522 -0.104752 -0.518688 0.85752 -0.0417865 -0.51275 0.0725329 -0.705245 -0.705244 0.0461246 -0.715215 -0.697381 0.109584 -0.700565 -0.705124 0.222368 -0.676868 -0.701713 0.200067 -0.690471 -0.695143 0.288831 -0.657721 -0.695687 -0.2168 -0.678661 -0.701724 -0.107353 -0.702577 -0.703464 -0.0869774 -0.69925 -0.709567 -0.0161661 -0.707015 -0.707014 -0.858289 -0.0383303 -0.511733 -0.848419 -0.100716 -0.519656 -0.850271 -0.0826572 -0.519814 -0.787322 -0.220338 -0.575826 -0.786991 -0.221766 -0.57573 -0.721408 -0.343053 -0.601569 -0.716826 -0.351971 -0.601895 -0.626873 -0.440957 -0.642329 -0.626103 -0.442158 -0.642255 -0.547391 -0.523022 -0.653308 -0.565011 -0.504295 -0.653031 -0.517032 -0.540662 -0.663598 -0.504476 -0.550588 -0.665099 -0.46959 -0.570923 -0.673448 -0.440685 -0.591407 -0.675303 -0.349771 -0.630531 -0.692886 -0.331778 -0.644106 -0.689239 -0.2209 -0.678216 -0.700876 0.866026 1.67589e-06 -0.499999 0.866028 6.33219e-07 -0.499996 0.866028 -3.23362e-08 -0.499996 0.866029 -5.01444e-07 -0.499995 0.866026 -1.26136e-05 -0.499999 0.866025 -8.07381e-06 -0.5 0.866025 5.75243e-06 -0.5 0.860015 -0.0303604 -0.509365 0.543191 -0.521268 -0.658197 0.569323 -0.497791 -0.654274 0.834941 -0.0969179 -0.541739 0.835387 -0.0882013 -0.54254 0.803655 -0.221486 -0.552343 0.809596 -0.181558 -0.558203 0.761484 -0.27651 -0.586246 0.76246 -0.274292 -0.586019 0.708226 -0.355926 -0.609698 0.724976 -0.31365 -0.613216 0.654112 -0.445891 -0.610998 0.675319 -0.392321 -0.624522 0.592557 -0.482684 -0.644897 0.064646 -0.705628 -0.705627 0.078786 -0.700202 -0.709585 0.188748 -0.689057 -0.699697 0.193455 -0.686978 -0.700454 0.258091 -0.667415 -0.698531 0.250057 -0.670511 -0.698489 0.322449 -0.646377 -0.691537 0.300276 -0.661152 -0.68754 0.404402 -0.602796 -0.68782 0.37002 -0.632264 -0.680682 0.483131 -0.558137 -0.674587 0.44838 -0.597734 -0.664583 0.503481 -0.550313 -0.66608 0.866027 1.94165e-05 -0.499997 0.866028 -6.39736e-06 -0.499996 0.866029 -1.19569e-06 -0.499995 -0.86603 0 -0.499993 -0.86603 0 -0.499993 -0.86603 0 -0.499993 -0.86603 0 -0.499993 -0.0101662 -0.707071 -0.70707 -0.0523896 -0.707682 -0.704586 -0.0965285 -0.69521 -0.712296 -0.154361 -0.695367 -0.701882 -0.213319 -0.67877 -0.702685 -0.237362 -0.675033 -0.698563 -0.261022 -0.667139 -0.697706 -0.304456 -0.652795 -0.69366 -0.338305 -0.633738 -0.695648 -0.388099 -0.619913 -0.681973 -0.442908 -0.586932 -0.677748 -0.485288 -0.566481 -0.666028 -0.503471 -0.550364 -0.666045 -0.542597 -0.521767 -0.658292 -0.571111 -0.496389 -0.653782 -0.60034 -0.477535 -0.641523 -0.641079 -0.43172 -0.634535 -0.695234 -0.380103 -0.610059 -0.708811 -0.352818 -0.610825 -0.860903 -0.0261719 -0.508095 -0.837136 -0.094596 -0.538753 -0.838237 -0.0765973 -0.539899 -0.807325 -0.217106 -0.548718 -0.813466 -0.176058 -0.554325 -0.76267 -0.273676 -0.586034 -0.761754 -0.275682 -0.586285 -0.741249 -0.30819 -0.596296 -0.86603 0 -0.499993 -0.86603 0 -0.499993 -0.850527 0.07112 -0.521101 -0.842092 0.180894 -0.508093 -0.564641 0.504612 -0.653106 -0.581422 0.484963 -0.653268 -0.836178 0.0759588 -0.543172 -0.808531 0.185679 -0.558392 -0.771173 0.258377 -0.581836 -0.769614 0.26256 -0.582028 -0.719993 0.339614 -0.605204 -0.725004 0.329479 -0.604825 -0.66703 0.409969 -0.62209 -0.685464 0.376795 -0.623029 -0.637621 0.441474 -0.6313 -0.0685077 0.705446 -0.705446 -0.0792962 0.70077 -0.708966 -0.204409 0.685696 -0.698598 -0.196784 0.689757 -0.696786 -0.252055 0.669897 -0.69836 -0.337216 0.640606 -0.689862 -0.332661 0.644305 -0.688627 -0.443871 0.587105 -0.676968 -0.435415 0.594774 -0.675765 -0.508042 0.546038 -0.666135 -0.489822 0.562494 -0.666089 -0.516339 0.541188 -0.663709 0.0105159 0.707068 -0.707068 0.0614607 0.707901 -0.703632 0.0981764 0.694917 -0.712357 0.186813 0.691632 -0.697672 0.222233 0.676645 -0.701972 0.259773 0.66746 -0.697865 0.297522 0.655122 -0.694475 0.301714 0.654205 -0.693531 0.357223 0.631092 -0.68856 0.379879 0.624122 -0.682762 0.443474 0.584043 -0.679871 0.481936 0.569399 -0.665975 0.515959 0.541531 -0.663725 0.564404 0.504333 -0.653526 0.57852 0.487632 -0.653857 0.649753 0.431697 -0.625667 0.659677 0.415532 -0.626226 0.718495 0.339947 -0.606795 0.7168 0.343671 -0.606703 0.770279 0.261183 -0.581768 0.792556 0.232877 -0.563581 0.8076 0.185293 -0.559865 0.848336 0.0810608 -0.523216 0.848296 0.0797757 -0.523479 -0.0144419 -0.195075 -0.980682 -0.121225 -0.544085 -0.830226 -0.0409942 -0.556007 -0.830166 -0.0411729 -0.555103 -0.830762 -0.304527 -0.48438 -0.820146 -0.239999 -0.518835 -0.820494 -0.240144 -0.582821 -0.776306 -0.184741 -0.529813 -0.827749 -0.120885 -0.548611 -0.827293 -0.014386 -0.195447 -0.980609 -0.0424687 -0.191264 -0.98062 -0.0424224 -0.193055 -0.98027 -0.0751277 -0.183248 -0.980192 -0.0759842 -0.187423 -0.979336 -0.107048 -0.170992 -0.97944 -0.108369 -0.175188 -0.978553 -0.137263 -0.154046 -0.978483 -0.141156 -0.160627 -0.97687 -0.166932 -0.132789 -0.976986 -0.17141 -0.138794 -0.975374 -0.193747 -0.105944 -0.975314 -0.202425 -0.113382 -0.972712 -0.544138 -0.295006 -0.78542 -0.481464 -0.38787 -0.78597 -0.471368 -0.372588 -0.799368 -0.429958 -0.418223 -0.800141 -0.423857 -0.472874 -0.772487 -0.376631 -0.444438 -0.812788 -0.307291 -0.495056 -0.812706 -0.611445 -0.227436 -0.757897 -0.591614 -0.252049 -0.76581 -0.563801 -0.313581 -0.764065 -0.24448 -0.0560185 -0.968035 -0.232204 -0.0502814 -0.971367 -0.216507 -0.0804846 -0.972958 -0.221108 -0.08515 -0.971525 -0.616847 -0.226205 -0.753877 -0.644256 -0.136519 -0.752527 -0.671476 -0.15135 -0.725405 -0.693508 -0.0697908 -0.71706 -0.684163 -0.0588166 -0.726954 -0.252986 -0.0263491 -0.967111 -0.248613 -0.0225709 -0.96834 -0.70681 -0.0285964 -0.706825 -0.696723 -0.0177421 -0.717121 -0.258809 -0.0113752 -0.965862 -0.254123 -0.00772438 -0.967141 0.146431 -0.538945 -0.829515 0.149768 -0.54462 -0.825202 0.0513419 -0.189522 -0.980533 0.0525594 -0.19185 -0.980016 0.0505859 -0.554863 -0.830402 0.0511128 -0.556491 -0.82928 0.0177535 -0.195064 -0.98063 0.0179369 -0.195718 -0.980496 -0.165034 0.0195582 -0.986094 -0.258825 0 -0.965924 -0.771589 0 -0.636122 -0.707045 0.0124696 -0.707059 -0.580749 0 -0.814083 -0.414678 0 -0.909968 0.016866 -0.038177 -0.999129 0.706229 -0.161603 -0.689293 0.508679 -0.424718 -0.748906 0.560034 -0.344999 -0.753218 0.589998 -0.351103 -0.727069 0.618939 -0.284008 -0.732294 0.66187 -0.259901 -0.703121 0.652621 -0.25023 -0.715172 0.675753 -0.166187 -0.71815 0.471618 -0.547089 -0.691571 0.460756 -0.458028 -0.760207 0.492596 -0.420106 -0.762142 0.420595 -0.475175 -0.772858 0.352668 -0.529422 -0.771581 0.345595 -0.524331 -0.778229 0.27923 -0.564523 -0.776753 0.0218091 -0.0381953 -0.999032 0.0162977 -0.0576572 -0.998203 0.0250269 -0.0583057 -0.997985 0.0189072 -0.0732585 -0.997134 0.0379704 -0.0799558 -0.996075 0.0319285 -0.0891969 -0.995502 0.0448441 -0.0950257 -0.994464 0.0421487 -0.0981985 -0.994274 0.0566633 -0.109666 -0.992352 0.054379 -0.11146 -0.99228 0.0591308 -0.115706 -0.991522 0.0528196 -0.119577 -0.991419 0.0910378 -0.177661 -0.979872 0.201728 -0.526165 -0.826109 0.27322 -0.542872 -0.794129 0.164759 -0.36022 -0.918203 0.21036 -0.332488 -0.919348 0.211955 -0.333811 -0.918502 0.247343 -0.305888 -0.919377 0.249743 -0.307645 -0.918141 0.281959 -0.269901 -0.92068 0.284956 -0.271071 -0.919413 0.315688 -0.223822 -0.922087 0.324591 -0.226466 -0.918343 0.34843 -0.168739 -0.922022 0.357669 -0.168887 -0.91845 0.374451 -0.109243 -0.920789 0.391622 -0.10848 -0.913709 -0.165065 0 -0.986283 -0.165065 0 -0.986283 -0.414678 0 -0.909968 -0.414678 0 -0.909968 -0.580749 0 -0.814083 -0.580749 0 -0.814083 -0.771589 0 -0.636122 -0.771589 0 -0.636122 0.732989 -0.0339416 -0.679393 0.746084 -0.0239093 -0.665422 0.409381 -0.0231039 -0.912071 0.419327 -0.0177738 -0.907661 0.020531 -0.009396 -0.999745 0.0231425 -0.0081974 -0.999699 0.716838 -0.0852445 -0.692009 0.730285 -0.0765017 -0.678846 0.398369 -0.0566621 -0.915474 0.407518 -0.0525745 -0.911683 0.0191191 -0.0201672 -0.999614 0.0198725 -0.0198856 -0.999605 -0.766029 0 -0.642806 -0.165065 0 -0.986283 -0.173667 -0.00113603 -0.984804 -0.414678 0.000599404 -0.909968 -0.499983 -0.00599174 -0.866014 -0.580749 0.000603178 -0.814083 -0.771588 -0.00119064 -0.636121 0.746097 -0.000775898 -0.665837 0.745989 -0.00083225 -0.665957 0.418972 -0.00210495 -0.907997 0.418338 -0.00234871 -0.908289 0.0223722 -0.00309578 -0.999745 0.0212722 -0.00347809 -0.999768 0.746265 -0.000530963 -0.665649 0.746096 -0.000619289 -0.665838 0.419367 -0.0015111 -0.907816 0.418971 -0.00166277 -0.907998 0.0231365 -0.00219713 -0.99973 0.0223712 -0.00246265 -0.999747 -0.499522 0.0433535 -0.865216 -0.474444 0.0460595 -0.87908 -0.463976 0.105116 -0.879589 -0.451848 0.106755 -0.885684 -0.681122 0.236213 -0.693019 -0.701232 0.165724 -0.693404 -0.717373 0.16169 -0.677667 -0.732776 0.0713294 -0.676721 -0.764392 0.0653382 -0.641432 -0.150026 0.0581554 -0.98697 -0.155891 0.0372236 -0.987073 -0.16042 0.0368449 -0.986361 -0.164145 0.0163246 -0.986301 -0.173645 0.0156374 -0.984684 -0.627881 0.289431 -0.722492 -0.733972 0.279861 -0.61884 -0.475793 0.186024 -0.85966 -0.432468 0.174148 -0.884672 -0.348841 0.134655 -0.927458 -0.141856 0.0563336 -0.988283 0.743293 -0.00285711 -0.668959 0.738762 -0.00323927 -0.673959 0.407289 -0.00780125 -0.913266 0.388872 -0.00886226 -0.921249 0.00101742 -0.0113657 -0.999935 -0.0324988 -0.012945 -0.999388 0.745991 -0.00173048 -0.665954 0.743288 -0.00193561 -0.668969 0.418342 -0.00473487 -0.908277 0.407274 -0.00532306 -0.913291 0.0212797 -0.00693188 -0.99975 0.000996688 -0.0078445 -0.999969 -0.133746 0.0724335 -0.988365 -0.628333 0.288495 -0.722473 -0.447056 0.244128 -0.860548 -0.326369 0.179675 -0.928009 -0.545086 0.305004 -0.780931 -0.516815 0.351546 -0.780588 -0.497619 0.347015 -0.794957 -0.209774 0.081629 -0.974337 -0.187104 0.119781 -0.97501 -0.172868 0.115153 -0.978191 -0.164943 0.124815 -0.978374 -0.141753 0.110072 -0.983763 -0.135073 0.115476 -0.984084 -0.117694 0.102098 -0.987788 -0.105346 0.109475 -0.988391 -0.0881198 0.0873364 -0.992274 -0.0634528 0.096222 -0.993335 -0.0547006 0.0793799 -0.995342 -0.0209734 0.0851414 -0.996148 -0.0190187 0.0785941 -0.996725 -0.453252 0.401119 -0.796031 -0.467295 0.43611 -0.769054 -0.400788 0.420419 -0.814012 -0.360687 0.452531 -0.815549 -0.349573 0.444808 -0.824587 -0.275252 0.488765 -0.827856 -0.266084 0.477525 -0.837358 -0.16624 0.513499 -0.841833 -0.161951 0.505749 -0.847343 -0.0555996 0.523881 -0.849975 -0.0548841 0.521747 -0.851333 0.738173 -0.00351594 -0.674602 0.73751 -0.00390835 -0.675325 0.38626 -0.00955392 -0.92234 0.383678 -0.0106563 -0.923405 -0.0371495 -0.0137416 -0.999215 -0.0418859 -0.0155755 -0.999001 0.738764 -0.00345879 -0.673956 0.738176 -0.00380523 -0.674598 0.388876 -0.00935051 -0.921243 0.386268 -0.0104603 -0.922327 -0.0324945 -0.0134902 -0.999381 -0.037137 -0.0152793 -0.999193 0.162782 0.577535 -0.799972 0.161141 0.50607 -0.847305 0.121578 0.383134 -0.915657 0.0887863 0.2418 -0.966256 0.0631452 0.0770098 -0.995029 0.0393364 0.0193303 -0.999039 0.0492772 0.523522 -0.850586 0.0496139 0.521891 -0.851568 0.0174907 0.083975 -0.996314 0.0183092 0.0785952 -0.996738 0.586447 0.305431 -0.750195 0.332858 0.161829 -0.928987 -0.0401408 0.0517559 -0.997853 -0.059846 0.0479055 -0.997057 0.674211 0.21598 -0.706252 0.787172 0.271122 -0.553943 0.307653 0.158211 -0.938253 0.73441 0.0776118 -0.674254 0.700092 0.0657104 -0.711023 0.382607 0.0462072 -0.922755 0.354623 0.038098 -0.934233 -0.0420583 0.00660306 -0.999093 -0.0522757 0.00371302 -0.998626 0.183483 0.290089 -0.939246 0.225059 0.558029 -0.798719 0.126737 0.229384 -0.96505 -0.0444006 0.0609751 -0.997151 0.268277 0.571815 -0.775277 0.185445 0.296023 -0.937006 0.214649 0.275202 -0.937118 0.217918 0.280424 -0.934812 0.239443 0.257207 -0.936222 0.241889 0.26072 -0.93462 0.163741 0.369564 -0.914665 0.155092 0.304078 -0.939938 0.254047 0.554007 -0.792803 0.32057 0.521093 -0.79101 0.323184 0.53045 -0.783693 0.398237 0.47663 -0.783728 0.407236 0.491725 -0.769653 0.465682 0.429366 -0.773812 0.473335 0.441276 -0.762384 0.547817 0.387039 -0.741685 0.525093 0.368743 -0.767011 0.270912 0.239215 -0.932407 0.262387 0.232311 -0.936581 -0.0298553 0.0665714 -0.997335 -0.0178113 0.0499315 -0.998594 -0.0125784 0.0574481 -0.998269 0.00479018 0.0386485 -0.999241 0.00976029 0.0465729 -0.998867 0.0294082 0.0325836 -0.999036 0.0290345 0.0315202 -0.999081 0.0429903 0.0246455 -0.998771 0.0419563 0.0184657 -0.998949 -0.501581 0.347433 -0.79228 -0.258744 0.0251025 -0.96562 -0.611885 0.233279 -0.755763 -0.631245 0.175056 -0.75557 -0.653531 0.168808 -0.737836 -0.671587 0.074134 -0.737208 -0.705644 0.064129 -0.705658 -0.641546 0.321276 -0.696564 -0.571508 0.258707 -0.778748 -0.519057 0.349333 -0.780094 -0.243377 0.0277192 -0.969536 -0.236541 0.0625328 -0.969607 -0.227078 0.0638413 -0.971782 -0.215334 0.098663 -0.971544 -0.20233 0.0962378 -0.974577 -0.184947 0.125622 -0.974687 -0.178075 0.124107 -0.976159 -0.157569 0.150557 -0.975964 -0.149514 0.14574 -0.97796 -0.123108 0.168159 -0.978042 -0.119057 0.165206 -0.979047 -0.0897735 0.183541 -0.978904 -0.0864749 0.179345 -0.979978 -0.053404 0.19138 -0.980062 -0.0521284 0.189321 -0.980531 -0.0192003 0.195872 -0.980442 -0.0189517 0.195061 -0.980608 -0.455529 0.406582 -0.79195 -0.474232 0.449446 -0.757035 -0.39546 0.435092 -0.808892 -0.348979 0.474039 -0.808394 -0.338206 0.46743 -0.816778 -0.255077 0.518861 -0.815916 -0.246253 0.508846 -0.824885 -0.152335 0.54343 -0.825517 -0.148746 0.538395 -0.829461 -0.0547205 0.556753 -0.828874 -0.0540118 0.554763 -0.830254 -0.258805 -0.0124735 -0.965849 -0.165065 0 -0.986283 -0.7071 0 -0.707114 -0.771441 -0.0195515 -0.636 -0.500002 0.00724747 -0.865994 0.00922131 0.195087 -0.980743 0.02629 0.555381 -0.83118 0.00918468 0.195188 -0.980723 0.0296411 0.193249 -0.980702 0.0294737 0.194169 -0.980525 0.0614211 0.187284 -0.980384 0.0618571 0.191119 -0.979616 0.0261882 0.555607 -0.831033 0.0846395 0.549978 -0.83088 0.0840598 0.552283 -0.829408 0.175266 0.532013 -0.828399 0.175954 0.541683 -0.821961 -0.173667 0 -0.984805 -0.771589 0 -0.636122 -0.766029 0.00113168 -0.642805 -0.499992 -0.00125781 -0.866029 -0.500015 -0.00125398 -0.866016 -0.165065 0.00119522 -0.986282 0.280808 0.494755 -0.822414 0.0661561 0.116817 -0.990948 0.0656645 0.115395 -0.991147 0.0722915 0.110656 -0.991226 0.0660962 0.101125 -0.992676 0.0677284 0.0993119 -0.992749 0.0565235 0.0870441 -0.9946 0.0594523 0.0822797 -0.994834 0.0432081 0.0706242 -0.996567 0.048188 0.0568117 -0.997221 0.0380254 0.051481 -0.99795 0.0426788 0.0262084 -0.998745 0.040075 0.0254755 -0.998872 0.086809 0.179923 -0.979843 0.105328 0.096224 -0.989771 0.155443 0.362695 -0.918852 0.203072 0.337928 -0.919003 0.204716 0.342956 -0.916773 0.252776 0.308451 -0.91704 0.256262 0.313841 -0.914239 0.299409 0.26603 -0.916287 0.303236 0.270193 -0.913807 0.340055 0.210136 -0.916627 0.348587 0.216121 -0.912019 0.37654 0.138882 -0.915931 0.388849 0.145289 -0.909774 0.405497 0.0541333 -0.912492 0.428097 0.0605479 -0.901702 0.271246 0.562872 -0.780769 0.325126 0.534305 -0.780264 0.327893 0.544085 -0.772306 0.413357 0.482163 -0.772434 0.423628 0.498686 -0.756209 0.50451 0.409429 -0.760156 0.519063 0.425809 -0.741121 0.585595 0.316798 -0.746135 0.611009 0.334945 -0.717272 0.65876 0.204196 -0.724113 0.684749 0.218757 -0.695172 0.710785 0.0745036 -0.699453 0.74616 0.0860456 -0.660183 -0.157745 -0.0459984 -0.986408 -0.151199 -0.0425596 -0.987587 -0.705138 -0.20304 -0.679379 -0.683136 -0.18926 -0.705341 -0.456267 -0.131558 -0.880064 -0.499752 -0.155813 -0.852039 -0.369928 -0.103391 -0.923289 -0.763629 -0.0790987 -0.640792 -0.731168 -0.0681543 -0.678785 -0.499318 -0.051933 -0.864861 -0.47332 -0.0445227 -0.879764 -0.173637 -0.0186235 -0.984634 -0.163685 -0.0159526 -0.986384 0.747929 0.00167403 -0.663777 0.748486 0.00194633 -0.663148 0.426432 0.00452217 -0.904508 0.428539 0.00528483 -0.903508 0.0361043 0.00658173 -0.999326 0.0400095 0.0078751 -0.999168 0.747438 0.00175405 -0.664329 0.74793 0.00199519 -0.663774 0.424257 0.00466819 -0.90553 0.426436 0.00545895 -0.904501 0.0320658 0.00679242 -0.999463 0.0361109 0.00813719 -0.999315 -0.136125 -0.101768 -0.985451 -0.00487839 -0.0786068 -0.996894 -0.0130624 -0.52249 -0.852545 -0.0130428 -0.522506 -0.852536 -0.0867987 -0.518671 -0.850557 -0.0861824 -0.522976 -0.847979 -0.178389 -0.502212 -0.846144 -0.176932 -0.507265 -0.843432 -0.265522 -0.476447 -0.838151 -0.267357 -0.490913 -0.829171 -0.125771 -0.0993898 -0.987068 -0.00459743 -0.0788849 -0.996873 -0.031728 -0.0777998 -0.996464 -0.0308621 -0.0880766 -0.995636 -0.0648685 -0.0801338 -0.994671 -0.0630757 -0.0901626 -0.993928 -0.0928126 -0.0800963 -0.992457 -0.0982922 -0.106267 -0.989468 -0.118114 -0.0945167 -0.988492 -0.351618 -0.441704 -0.825386 -0.503318 -0.444918 -0.740755 -0.397282 -0.419016 -0.816452 -0.352653 -0.453135 -0.818721 -0.18318 -0.114129 -0.976432 -0.175431 -0.101423 -0.979254 -0.142898 -0.0649619 -0.987603 -0.203038 -0.082868 -0.975658 -0.345999 -0.167747 -0.923117 -0.472454 -0.228169 -0.851308 -0.145936 -0.0941901 -0.9848 -0.160717 -0.119047 -0.979795 -0.441604 -0.411097 -0.797487 -0.500041 -0.341767 -0.795709 -0.507447 -0.357382 -0.784076 -0.567079 -0.261558 -0.781031 -0.635654 -0.315327 -0.704636 0.746886 0.00176184 -0.66495 0.74744 0.00203595 -0.664327 0.42205 0.00472822 -0.90656 0.424261 0.00553793 -0.905523 0.0280591 0.00686942 -0.999583 0.032072 0.00821727 -0.999452 0.746341 0.0017293 -0.665562 0.746887 0.00200065 -0.664948 0.419899 0.0046559 -0.907559 0.422053 0.00544729 -0.906555 0.024083 0.00675407 -0.999687 0.0280644 0.00809678 -0.999573 0.176882 -0.502322 -0.846396 0.215207 -0.565379 -0.796262 0.14629 -0.381025 -0.912918 0.0596026 -0.0780699 -0.995165 0.143316 -0.227335 -0.963213 0.0475849 -0.0220259 -0.998624 0.0580903 -0.521652 -0.851178 0.0589124 -0.523862 -0.849763 0.0201447 -0.0785918 -0.996703 0.0222047 -0.0848639 -0.996145 0.6876 -0.207756 -0.695733 0.658114 -0.192294 -0.727948 0.377957 -0.134624 -0.915983 0.361811 -0.126755 -0.923594 0.0106537 -0.0412314 -0.999093 0.0176394 -0.0446732 -0.998846 0.71066 -0.0742304 -0.699609 0.744435 -0.0643156 -0.66459 0.392932 -0.0458737 -0.918422 0.419262 -0.0411709 -0.906931 0.0156063 -0.011581 -0.999811 0.0240071 -0.0104477 -0.999657 0.616193 -0.313217 -0.722635 0.0146349 -0.0532178 -0.998476 0.337494 -0.19642 -0.920607 0.585838 -0.31074 -0.748488 0.546837 -0.378805 -0.746643 0.53197 -0.377985 -0.757717 0.0211743 -0.0547822 -0.998274 0.0241215 -0.0497322 -0.998471 0.0282947 -0.0507015 -0.998313 0.0342698 -0.0425228 -0.998508 0.0376553 -0.0447059 -0.99829 0.0460744 -0.0373125 -0.998241 0.0448269 -0.0364883 -0.998328 0.0554356 -0.0290907 -0.998038 0.0493402 -0.0213125 -0.998555 0.158054 -0.221295 -0.962314 0.322438 -0.193633 -0.926574 0.302799 -0.227455 -0.925514 0.296237 -0.226319 -0.927914 0.27299 -0.257927 -0.926795 0.263055 -0.251943 -0.931304 0.234177 -0.277423 -0.931771 0.229115 -0.27432 -0.933946 0.191694 -0.300186 -0.93442 0.224364 -0.349574 -0.909648 0.490177 -0.434346 -0.755691 0.513279 -0.472169 -0.71666 0.431959 -0.461979 -0.774588 0.399469 -0.490279 -0.77463 0.391435 -0.486189 -0.78128 0.321539 -0.533922 -0.78201 0.313956 -0.524997 -0.791082 -0.0126855 0.990808 0.134679 -0.0126605 0.990795 0.134775 -0.0165961 0.99065 0.135418 -0.0165848 0.990644 0.135461 -0.0205281 0.990459 0.136271 -0.0204922 0.990441 0.136407 -0.0244425 0.990215 0.137394 -0.0244066 0.990197 0.137529 -0.0283154 0.989938 0.138643 -0.0282671 0.989914 0.138824 -0.0321568 0.989615 0.140103 -0.0321096 0.989591 0.140278 -0.0170568 0.990461 0.136736 -0.0100864 0.989162 0.146483 -0.0081452 0.988982 0.147812 -0.00881735 0.988536 0.150725 -0.00278665 0.971857 0.235555 -0.00997832 0.973377 0.228994 -0.14033 0.966804 0.213536 -0.00792761 0.925438 0.378815 -0.00538474 0.927355 0.374144 -0.00561951 0.930441 0.366397 -0.007035 0.883303 0.468749 -0.00621739 0.883568 0.468261 -0.00783975 0.887961 0.459852 -0.00689682 0.888646 0.458541 -0.00686706 0.884813 0.465896 -0.00908608 0.882441 0.470335 -0.00947543 0.88687 0.461923 -0.00937317 0.886992 0.461689 -0.00932845 0.882761 0.469731 -0.0114751 0.88109 0.472809 -0.0119665 0.885649 0.464202 -0.0118577 0.885815 0.463887 -0.0117999 0.881493 0.47205 -0.0141674 0.875453 0.483096 -0.0140775 0.879349 0.47597 -0.0135495 0.879517 0.475674 -0.0180953 0.878399 0.477586 0.00626483 0.88439 0.466707 -0.0162707 0.879847 0.474978 -0.0144055 0.884145 0.466991 -0.0168255 0.882352 0.470289 -0.0158445 0.877727 0.478899 -0.0210779 0.876917 0.480179 0.00189507 0.882671 0.469987 -0.0175712 0.878254 0.477871 -0.0116969 0.876908 0.480515 -0.0164976 0.877493 0.479306 -0.0180555 0.924986 0.379572 -0.0216814 0.924087 0.381568 -0.0234199 0.928824 0.36978 -0.0226031 0.876017 0.48175 -0.0226878 0.875273 0.483098 -0.020831 0.874618 0.484365 -0.0209672 0.880338 0.473883 -0.0199798 0.881752 0.47129 -0.0228673 0.965591 0.259057 -0.0298858 0.963559 0.265821 -0.0188611 0.871186 0.490591 -0.0181037 0.875574 0.482745 -0.0234722 0.875002 0.48355 -0.0192383 0.876297 0.481387 -0.0178923 0.875908 0.482146 0.866025 0.47276 0.162784 0.866025 0.47276 0.162784 0.866025 0.47276 0.162785 0.866027 0.472758 0.162781 0.866025 0.47276 0.162785 0.866025 0.47276 0.162784 -0.0174773 0.754595 -0.655958 -0.077426 0.755404 -0.650669 -0.150728 0.761401 -0.630515 -0.863149 0.492378 0.111972 -0.86455 0.49095 0.107337 -0.846569 0.531147 0.034696 -0.843134 0.537089 0.0256929 -0.839642 0.542919 -0.0155023 -0.829687 0.551961 -0.0834139 -0.825617 0.557521 -0.0867598 -0.768837 0.601856 -0.216009 -0.719563 0.64132 -0.26634 -0.685623 0.648633 -0.33045 -0.622496 0.667363 -0.40881 -0.345888 0.78239 -0.517907 -0.468326 0.706609 -0.530447 -0.305724 0.736573 -0.603319 -0.213008 0.744032 -0.63328 -0.399604 0.722238 -0.564525 -0.44186 0.717053 -0.539068 -0.467896 0.724147 -0.506641 -0.483583 0.717868 -0.500813 -0.545336 0.693575 -0.470704 0.860031 0.507725 0.050608 0.797537 0.588941 -0.130704 0.811937 0.583006 -0.029349 0.785697 0.616093 -0.0557594 0.84869 0.528223 0.0265775 0.294062 0.790956 -0.536578 0.282501 0.730246 -0.62204 0.0399012 0.755451 -0.653989 0.0427897 0.754019 -0.655457 0.135579 0.764345 -0.630393 0.215669 0.784766 -0.581059 0.293819 0.744355 -0.599672 0.789898 0.586311 -0.179722 0.754159 0.619367 -0.21824 0.772937 0.599626 -0.207405 0.710291 0.633196 -0.307489 0.599377 0.696796 -0.393983 0.588943 0.693859 -0.414373 0.455082 0.70807 -0.539941 -0.499997 0 -0.866027 0.499999 0 -0.866026 0.500003 0 0.866024 -0.499999 0 0.866026 -0.500156 -5.22376e-05 0.865935 0.500003 0 0.866024 0.499996 0 -0.866028 -1 0 0 -1 0 0 -0.5 0 -0.866026 -0.5 0 -0.866026 -1 0 0 1 0 0 0.500001 0 0.866025 0.500001 0 0.866025 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 0.500006 0 0.866022 0.499999 5.09842e-07 0.866026 0.499999 0 0.866026 -0.500001 0 -0.866025 -0.499995 0 0.866028 -0.499995 0 0.866028 -0.5 0 0.866026 0.0159416 -0.881798 -0.471358 -0.000161106 -0.193752 -0.981051 0.0033049 -0.129972 -0.991512 5.0514e-07 -0.119588 -0.992824 0.00020811 -0.25028 -0.968173 0.000161106 -0.193752 -0.981051 0.00216598 -0.13606 -0.990698 4.27017e-06 -0.119602 -0.992822 0.00908205 -0.0993737 -0.995009 0.013519 -0.0773486 -0.996912 0.0163134 -0.0648344 -0.997763 0.0175404 -0.0595813 -0.998069 0.0175609 -0.0594973 -0.998074 0.0134411 -0.0754022 -0.997063 0.00481275 -0.487057 -0.873357 0.00327652 -0.467951 -0.883749 0.00248265 -0.454037 -0.89098 0.00229915 -0.299254 -0.954171 0.0043514 -0.328358 -0.944543 0.000952384 -0.37329 -0.927714 0.00128089 -0.431127 -0.90229 0.000842453 -0.437264 -0.899333 0.000402329 -0.441658 -0.897184 -0.00163045 -0.453984 -0.891008 -0.00402061 -0.465584 -0.884995 -0.0102743 -0.4847 -0.87462 -0.0189667 -0.499044 -0.866369 -0.00516107 -0.478786 -0.877916 0.00206329 -0.538665 -0.842517 -0.00935397 -0.572969 -0.819524 -0.00888086 -0.572319 -0.819983 0.00443159 -0.617301 -0.786714 -0.01326 -0.659265 -0.751794 -0.0148994 -0.657564 -0.753252 0.0138603 -0.716229 -0.697727 -0.0138398 -0.74233 -0.669892 -0.00486146 -0.75945 -0.650548 0.0160874 -0.811405 -0.584263 -0.0154388 -0.795874 -0.605265 0.0125838 -0.862803 -0.505384 -0.00320494 -0.854878 -0.518819 -0.00850983 -0.987725 -0.155973 0.0112292 -0.99138 -0.130539 -0.025403 -0.97817 -0.206247 0.0120511 -0.983122 -0.182553 -0.00412023 -0.96523 -0.261369 -0.000345289 -0.968023 -0.250863 -0.000338163 -0.948046 -0.318134 0.0170042 -0.953568 -0.300697 -0.0264089 -0.906817 -0.420697 0.0272753 -0.921972 -0.386296 0.000782039 -0.890983 -0.454035 -0.00343716 -0.989905 -0.141693 4.56279e-05 -0.991557 -0.129671 -0.0014889 -0.996255 -0.0864525 -0.0165657 -0.994415 -0.104231 0.0588342 -0.998243 -0.00696768 -0.0419909 -0.997229 -0.0614148 -0.0290646 -0.998233 -0.0518348 -0.0192897 -0.998836 -0.0442114 -0.0108032 -0.999312 -0.0354736 -0.004135 -0.99959 -0.0283452 0.00996087 -0.999433 -0.032172 0.0194009 -0.998884 -0.0430617 0.0263857 -0.998456 -0.0488903 0.0345284 -0.997874 -0.0552656 0.0453626 -0.997139 -0.0604725 0.0388571 -0.997583 -0.0576051 0.0499163 -0.996389 0.0686828 0.0375281 -0.99738 0.0618411 0.0289577 -0.997974 0.0566585 0.022198 -0.998495 0.0501597 0.0173081 -0.99883 0.0451664 0.00995979 -0.999311 0.0357477 0.00468288 -0.999838 -0.0173896 0.00398955 -0.999815 -0.0187965 0.00804138 -0.999354 0.0350266 0.00468248 -0.999733 0.0226123 -0.00103783 -0.997893 0.0648771 -0.00368562 -0.997427 0.0715928 -0.00673446 -0.996859 0.0789143 -0.000833648 -0.99266 0.120938 -0.0108969 -0.996275 0.0855376 -0.017084 -0.995357 0.0947194 0.012835 -0.997717 0.0663084 -0.0019123 -0.99364 0.112584 0.000424319 -0.990866 0.134851 -0.00266592 -0.989077 0.147377 -0.00282962 -0.988997 0.147908 0.000109414 -0.987157 0.159756 -0.00253961 -0.979344 0.202187 0.00268224 -0.978301 0.207173 -0.00128812 -0.963941 0.266113 -0.000339954 -0.962985 0.269553 -0.000334138 -0.946511 0.32267 0.00164967 -0.945668 0.325131 -0.000919842 -0.926638 0.375953 0.0107164 -0.907221 0.420519 -0.00433707 -0.899663 0.436564 -0.000248825 -0.878644 0.477477 -0.000247109 -0.872585 0.488462 0.00637758 -0.849143 0.528124 -0.0105115 -0.838441 0.544891 0.0101139 -0.784815 0.619647 -0.00520891 -0.773539 0.633728 0.00693115 -0.69887 0.715215 -0.014791 -0.711736 0.702291 0.0159541 -0.610746 0.791666 -0.0306221 -0.503076 0.863699 0.0381251 -0.442444 0.895985 -0.0279911 -0.554308 0.831841 0.0145902 -0.5201 0.853981 -0.007866 -0.603636 0.797221 -0.0430124 -0.645506 0.762543 -0.0134268 -0.476401 0.879126 -0.00627383 -0.459231 0.888295 -0.00236054 -0.445192 0.895432 0.000396077 -0.433989 0.900918 0.000830322 -0.431089 0.902309 0.00117873 -0.427839 0.903854 0.00302739 -0.454464 0.89076 0.00411938 -0.468566 0.883419 0.00632716 -0.49047 0.871435 0.00887755 -0.50771 0.861482 0.0131705 -0.534251 0.845223 0.0083853 -0.514703 0.857327 0.000132072 -0.18138 0.983413 0.000169085 -0.232212 0.972665 0.00323345 -0.313876 0.949458 0.00318741 -0.314306 0.949316 0.00107324 -0.389547 0.921006 0.0126183 -0.068447 0.997575 0.0183203 -0.0428422 0.998914 0.0170552 -0.0479176 0.998706 0.0144785 -0.0593159 0.998134 0.0102149 -0.0807176 0.996685 0.00599387 -0.104532 0.994503 0.00177509 -0.129615 0.991563 4.28705e-06 -0.114513 0.993422 5.0633e-07 -0.114497 0.993424 2.98503e-08 -0.110039 0.993927 0.0102942 -0.0730016 0.997279 0.0169944 -0.048051 0.9987 -5.05979e-07 -0.114497 0.993424 -4.28705e-06 -0.114513 0.993422 -0.00177509 -0.129615 0.991563 -0.00290451 -0.122908 0.992414 -0.00770626 -0.0946756 0.995478 -0.0114009 -0.0744163 0.997162 -0.0144785 -0.0593159 0.998134 -0.0170552 -0.0479174 0.998706 -0.0177985 -0.0449361 0.998831 -0.0135623 -0.0609609 0.998048 -0.00456997 -0.0936174 0.995598 -0.00107324 -0.389547 0.921006 -0.00318741 -0.314306 0.949316 -0.00323345 -0.313876 0.949458 -0.000169085 -0.232212 0.972665 -0.000132072 -0.18138 0.983413 -0.00586626 -0.486123 0.873871 -0.00395891 -0.466792 0.884358 -0.00283671 -0.451734 0.892148 -0.00117874 -0.427839 0.903854 -0.000830323 -0.431089 0.902309 -0.000396077 -0.433989 0.900918 0.00295453 -0.447597 0.89423 0.0069686 -0.461118 0.887312 0.0153414 -0.480518 0.876851 0.0257851 -0.494803 0.868623 -0.01585 -0.442709 0.896525 0.0118483 -0.532402 0.846409 0.00131174 -0.520154 0.854072 -0.000366563 -0.575831 0.817568 0.0110047 -0.610785 0.79172 0.00713513 -0.61537 0.788206 -0.00192181 -0.658418 0.75265 0.0106404 -0.698846 0.715193 -0.0103984 -0.716259 0.697757 0.00919519 -0.773516 0.63371 -0.0133471 -0.792645 0.609537 0.0137594 -0.838408 0.544869 -0.00545894 -0.852507 0.522688 0.000247108 -0.872585 0.488462 0.000248789 -0.878515 0.477715 0.00412865 -0.899664 0.436564 -0.0107302 -0.907081 0.42082 0.000930803 -0.926638 0.375953 -0.00182538 -0.94651 0.322669 0.000333834 -0.945649 0.325189 0.000340292 -0.963942 0.266114 0.00117699 -0.963265 0.26855 -0.00197513 -0.979345 0.202187 0.00279816 -0.978482 0.206312 -0.000845706 -0.989001 0.147909 0.00465188 -0.987663 0.156523 0.0014754 -0.98982 0.142314 -0.00329682 -0.993637 0.112583 0.00614877 -0.991948 0.126497 -0.0117217 -0.99773 0.0663093 0.0224873 -0.994756 0.0997727 0.0141863 -0.995747 0.091034 0.00891156 -0.996566 0.0823176 0.00534512 -0.997095 0.0759838 0.00255515 -0.997635 0.0686812 0.000345928 -0.998038 0.0626044 -0.00804138 -0.999354 0.0350266 -0.00468247 -0.999733 0.0226123 -0.0099598 -0.999311 0.0357476 -0.0188029 -0.998714 0.0470819 -0.0250763 -0.998286 0.0528722 -0.0324294 -0.997717 0.059231 -0.0401239 -0.997516 -0.057891 -0.0306915 -0.99814 -0.0526836 -0.0231807 -0.998665 -0.0461607 -0.0177477 -0.998995 -0.0411549 -0.00353949 -0.999687 -0.0247621 -0.0099649 -0.999928 -0.006669 -0.00468287 -0.999838 -0.0173896 0.00609349 -0.999508 -0.0307779 0.0143553 -0.999133 -0.0390883 0.000494948 -0.99393 -0.110009 0.0232598 -0.998591 -0.0476937 0.0340297 -0.997881 -0.0554666 -0.0363683 -0.999314 -0.00697521 0.00538483 -0.996242 -0.0864515 0.000295439 -0.992617 -0.121287 0.000613397 -0.990927 -0.134401 -0.00084547 -0.991442 -0.130547 0.00879243 -0.480553 -0.876921 0.000859869 -0.989013 -0.147828 0.00269292 -0.987203 -0.159443 0.0138788 -0.983099 -0.18255 -0.0079787 -0.978273 -0.207167 0.00186818 -0.968021 -0.250863 0.000344199 -0.964966 -0.262375 0.000340182 -0.953706 -0.300741 -0.0108071 -0.94801 -0.318058 0.0137387 -0.922226 -0.386406 -0.0137394 -0.907187 -0.420503 0.0141415 -0.870939 -0.491187 -0.0136864 -0.851611 -0.523996 0.0117469 -0.811453 -0.5843 -0.0151558 -0.784765 -0.619608 0.0155006 -0.742312 -0.669876 -0.0115818 -0.711766 -0.702321 0.0141027 -0.659257 -0.751785 0.00412632 -0.648921 -0.760845 -0.00592138 -0.572332 -0.820001 0.0280463 -0.599384 -0.79997 -0.0510526 -0.47817 -0.876782 0.0598878 -0.542717 -0.837778 0.0228999 -0.507456 -0.861373 0.00356392 -0.463876 -0.885893 0.00130753 -0.452031 -0.892001 -0.000402333 -0.441658 -0.897184 -0.00261222 -0.456491 -0.889724 -0.00340005 -0.469659 -0.882841 -0.00519291 -0.491401 -0.870918 -0.00740913 -0.508612 -0.860964 -0.0111839 -0.535158 -0.844678 -0.00952396 -0.527796 -0.849317 -0.000842449 -0.437264 -0.899333 -0.00128089 -0.431127 -0.90229 -0.000952384 -0.37329 -0.927714 -0.0043514 -0.328358 -0.944543 -0.00229915 -0.299254 -0.954171 -0.00020811 -0.25028 -0.968173 -0.0149382 -0.0709959 -0.997365 -0.018068 -0.0574213 -0.998187 -0.0175404 -0.0595814 -0.998069 -0.0163134 -0.0648342 -0.997763 -0.0121192 -0.0840958 -0.996384 -0.00698696 -0.11025 -0.993879 -0.00216598 -0.13606 -0.990698 -4.27069e-06 -0.119602 -0.992822 -5.0514e-07 -0.119588 -0.992824 -2.17246e-07 -0.125031 -0.992153 -0.0102321 -0.0874689 -0.996115 -0.0167779 -0.0625927 -0.997898 -0.00179825 -0.974999 -0.222203 0.0177871 -0.982701 -0.184343 0.0208315 -0.967929 -0.250359 0.00779097 -0.979762 -0.200012 0.0144691 -0.982982 -0.18313 0.0185946 -0.985529 -0.168484 0.0217777 -0.987529 -0.155926 0.0239074 -0.989406 -0.14319 0.0255791 -0.99092 -0.131997 0.0274856 -0.993302 -0.112229 0.0276325 -0.993202 -0.113081 0.028478 -0.994364 -0.102122 0.0269291 -0.992589 -0.118498 0.0163606 -0.890638 -0.454418 0.0155123 -0.898679 -0.438332 0.0141432 -0.908031 -0.418664 0.00997835 -0.9186 -0.395064 0.0040235 -0.929928 -0.36772 0.00397367 -0.929987 -0.367572 0.0162451 -0.947361 -0.319755 0.020677 -0.960731 -0.27671 0.00300082 -0.840418 -0.541931 0.010881 -0.827746 -0.560997 0.0175787 -0.829479 -0.558261 0.0109311 -0.832122 -0.554485 0.00644167 -0.838709 -0.544541 0.0176018 -0.848243 -0.529314 0.0292104 -0.931614 -0.362274 0.015542 -0.923288 -0.383794 0.00888176 -0.914712 -0.404009 0.0442647 -0.93896 -0.341166 0.0410455 -0.937862 -0.344573 0.012153 -0.954607 -0.29762 0.00477681 -0.907554 -0.419908 0.00392789 -0.900122 -0.43562 0.00225052 -0.843786 -0.536676 0.0382011 -0.86174 -0.505911 0.0273744 -0.854903 -0.518065 0.0102899 -0.990076 -0.140155 0.00967571 -0.990593 -0.136497 0.00971121 -0.990566 -0.136693 0.0104439 -0.990194 -0.139306 0.012359 -0.989291 -0.145429 0.0157606 -0.988255 -0.151999 0.021083 -0.986655 -0.161457 0.0309757 -0.984477 -0.172761 0.0251922 -0.98567 -0.166793 0.0103112 -0.979653 -0.200434 0.0017232 -0.969212 -0.246222 -0.00771357 -0.997837 -0.0652878 0.00574985 -0.998539 -0.0537272 0.0293142 -0.998848 -0.0380043 -0.00730383 -0.99831 -0.0576452 -0.0205063 -0.999786 -0.00278208 -0.0310241 -0.996774 -0.0740187 -0.0358624 -0.99792 -0.0535694 -0.039831 -0.998458 -0.0386607 -0.0448415 -0.998744 -0.0223446 -0.0338219 -0.998002 -0.0533636 -0.0318122 -0.999482 -0.00487286 -0.0317048 -0.999493 0.00292967 -0.0318476 -0.997609 0.0613403 -0.0487574 -0.998639 0.0185122 -0.0426959 -0.998437 0.0360547 -0.0451492 -0.992493 0.113659 -0.0211037 -0.996193 0.0845807 -0.00875435 -0.99738 0.0718148 0.00501554 -0.998163 0.0603813 -0.00397804 -0.997797 0.0662212 -0.0186212 -0.999596 0.0214666 -0.0204755 -0.999748 0.00915461 0.040954 -0.998555 -0.0347881 0.0368235 -0.998081 -0.0497766 0.0277048 -0.9958 -0.0872642 0.0446764 -0.992713 -0.111911 0.0214057 -0.996515 -0.0806159 0.0104282 -0.99763 -0.0680175 -0.00173687 -0.998379 -0.056883 -0.000660373 -0.998337 -0.0576463 0.0149788 -0.999615 -0.023375 0.00567322 -0.9976 0.0690137 0.0190744 -0.999773 -0.00945207 0.0209147 -0.999777 0.00275583 0.014896 -0.997694 0.0662151 -0.0360948 -0.998513 0.0408487 -0.00953863 -0.998321 0.0571356 0.0314495 -0.996584 0.0763659 0.0369311 -0.997779 0.0554392 0.0414321 -0.998339 0.0400457 0.0470511 -0.998623 0.0232201 0.0324589 -0.997589 0.061339 0.031678 -0.999486 0.00485873 0.0324359 -0.998048 -0.0533662 0.0513532 -0.998672 -0.00416244 0.0463681 -0.998766 -0.0177919 0.0070861 -0.651017 -0.75903 0.00524913 -0.606808 -0.794831 0.00742993 -0.527805 -0.849333 0.0165935 -0.560969 -0.827671 0.00845991 -0.518276 -0.855171 -0.00469954 -0.851905 -0.523676 0.0125834 -0.829988 -0.55764 0.23081 -0.807609 -0.542674 0.0237639 -0.853279 -0.520913 -0.000424304 -0.908667 -0.417521 0.237969 -0.903258 -0.357065 0.014761 -0.948935 -0.315125 0.0175833 -0.994006 -0.107899 0.0170332 -0.992684 -0.119536 0.0178817 -0.991048 -0.132304 0.0320202 -0.989324 -0.142174 0.0518478 -0.98679 -0.153486 0.154172 -0.971102 -0.182189 0.0464459 -0.97779 -0.204377 0.0150206 -0.965621 -0.259518 0.0314857 -0.987756 0.152797 0.02054 -0.990013 0.139471 -0.020201 -0.997601 0.0662066 0.10189 -0.991311 0.083186 0.0697463 -0.994769 0.0746296 0.170205 -0.964782 0.200566 0.105949 -0.975332 0.193657 0.0148257 -0.964024 0.265402 0.0145579 -0.946616 0.322036 0.231016 -0.899398 0.3711 0.0342968 -0.908057 0.417439 0.231844 -0.799213 0.554534 0.0105967 -0.854316 0.519646 0.0109166 -0.880106 0.474651 0.00524527 -0.576589 0.817017 0.00521791 -0.617962 0.786191 0.00843851 -0.649327 0.760462 0.00772092 -0.660102 0.751136 0.00786014 -0.716703 0.697334 -0.00324605 -0.718432 0.695589 0.0175493 -0.794683 0.606771 -0.042327 -0.997025 0.0644242 -0.0569882 -0.995814 0.0714569 -0.0363299 -0.997146 0.0661801 -0.0186085 -0.992778 0.118511 -0.0148401 -0.990921 0.133626 -0.0245557 -0.989265 0.144055 -0.0380164 -0.987165 0.155116 -0.14659 -0.970255 0.192656 -0.0883844 -0.975014 0.203804 -0.0196215 -0.649231 0.760338 -0.00769041 -0.649331 0.760467 -0.00797191 -0.650948 0.759081 -0.00512468 -0.606834 0.794812 -0.0056911 -0.514712 0.857345 -0.0191152 -0.560095 0.828208 -0.010111 -0.517362 0.855707 0.0113081 -0.786905 0.616971 -0.234794 -0.79863 0.554131 -0.0105551 -0.850953 0.525136 -0.0148205 -0.963673 0.266673 -0.0145575 -0.946572 0.322165 -0.231218 -0.899354 0.371082 -0.0358236 -0.90808 0.417261 -0.0109186 -0.880257 0.474371 -0.00859594 -0.660056 -0.751167 -0.00852086 -0.660881 -0.750442 -0.00509294 -0.617983 -0.786175 -0.00603617 -0.576355 -0.817177 -0.0259411 -0.990128 -0.137742 -0.0160935 -0.991641 -0.128021 -0.0228202 -0.998077 -0.0576327 -0.074969 -0.994681 -0.0706425 -0.0536217 -0.996462 -0.0647107 -0.0433802 -0.987576 -0.151039 -0.154176 -0.971101 -0.182189 -0.0523038 -0.977732 -0.203237 -0.237924 -0.903268 -0.357069 -0.0147619 -0.948978 -0.314996 -0.0150261 -0.965963 -0.258243 -0.00705337 -0.761544 -0.648075 -0.00739108 -0.798007 -0.602603 -0.23496 -0.806783 -0.54212 -0.0238087 -0.856454 -0.515674 0.00184991 -0.908594 -0.417676 0.00131262 -0.531983 -0.846754 0.000650054 -0.527816 -0.849359 0.000406929 -0.330409 -0.943838 0.000114695 -0.32836 -0.944553 0.012105 -0.825536 -0.564219 0.0108398 -0.739251 -0.673343 0.00567801 -0.73928 -0.673374 7.52788e-05 -0.843784 -0.536683 0.00010263 -0.843839 -0.536596 0.000114157 -0.938614 -0.344969 0.000140294 -0.938647 -0.344878 0.000147367 -0.985975 -0.166893 0.000166635 -0.985987 -0.166822 0.000168782 -0.99869 -0.0511755 0.000175782 -0.998691 -0.0511498 0.000175707 -0.998267 0.0588402 0.000167711 -0.998269 0.0588108 0.000165358 -0.984268 0.176685 0.000145635 -0.98428 0.176613 0.000138116 -0.933464 0.358672 0.000111426 -0.933499 0.358579 9.97407e-05 -0.835604 0.549332 7.28735e-05 -0.835659 0.549248 6.06496e-05 -0.695485 0.718541 0.00625274 -0.835598 0.549305 0.00854307 -0.830784 0.55653 0.0095986 -0.93343 0.358631 0.0118548 -0.930339 0.36651 0.012541 -0.984194 0.176647 0.0142556 -0.983032 0.182882 0.014475 -0.998164 0.0588229 0.0151705 -0.998 0.0613671 0.0151792 -0.998575 -0.0511594 0.0145661 -0.998467 -0.0533912 0.01438 -0.985712 -0.167826 0.0166437 -0.989468 -0.143795 0.0176822 -0.996572 0.0808131 0.0275278 -0.995346 0.0923481 0.0271171 -0.980494 0.194669 0.0238913 -0.982852 0.182844 0.0224653 -0.924189 0.381275 0.0182554 -0.93025 0.366471 0.0161217 -0.821525 0.569944 0.0118684 -0.830757 0.556509 0.0104137 -0.728932 0.684507 0.00545476 -0.728958 0.684537 0.0196215 -0.649231 0.760338 0.00166146 -0.699809 0.714329 0.00122202 -0.514717 0.857359 0.000600213 -0.518757 0.854921 0.000363162 -0.313877 0.949464 9.65793e-05 -0.315776 0.948834 3.3755e-05 -0.110365 0.993891 -0.0117373 -0.821576 0.569978 -0.0163019 -0.830707 0.556472 -0.018138 -0.92427 0.381308 -0.0226106 -0.930168 0.366436 -0.023836 -0.980576 0.194684 -0.02718 -0.982769 0.182828 -0.0275324 -0.995512 0.0905466 -0.0380263 -0.997948 0.0515184 -0.0183285 -0.996874 -0.0768513 -0.0277004 -0.995641 -0.0890629 -0.0273345 -0.982489 -0.184304 -0.0242135 -0.98465 -0.172854 -0.0228634 -0.929749 -0.367483 -0.0186894 -0.935538 -0.352733 -0.0165799 -0.829939 -0.557608 -0.0123027 -0.839018 -0.543965 -0.0110749 -0.755287 -0.655301 -0.0257515 -0.713722 0.699956 -0.00786014 -0.716703 0.697334 -0.0104137 -0.728932 0.684507 -0.00545475 -0.728958 0.684537 -0.00621681 -0.830797 0.55654 -0.00859247 -0.835588 0.54929 -0.00956703 -0.930361 0.36652 -0.0118939 -0.933409 0.358616 -0.0125265 -0.983054 0.182887 -0.0142721 -0.984172 0.176639 -0.0144728 -0.99801 0.0613679 -0.0151728 -0.998153 0.0588218 -0.0151774 -0.998458 -0.0533906 -0.0145678 -0.998584 -0.0511602 -0.0143672 -0.984836 -0.17289 -0.0127094 -0.985899 -0.166856 -0.0120614 -0.935632 -0.352772 -0.00982573 -0.938578 -0.344928 -0.00878377 -0.839048 -0.543987 -0.0064806 -0.843777 -0.536654 0.00458132 -0.108237 -0.994115 2.87636e-07 -0.125031 -0.992153 4.37708e-05 -0.125312 -0.992117 -4.38213e-05 -0.125456 -0.992099 -0.000115411 -0.330409 -0.943838 -0.000404405 -0.32836 -0.944553 -0.000655187 -0.531983 -0.846755 -0.00130234 -0.527816 -0.849358 -0.00175424 -0.710963 -0.703227 -0.0198304 -0.660781 -0.750317 -0.00567801 -0.73928 -0.673374 -0.00677868 -0.739276 -0.673369 -0.0112518 -0.718388 -0.695551 -3.91317e-08 -0.110039 0.993927 -3.37224e-05 -0.110259 0.993903 -9.59986e-05 -0.313877 0.949464 -0.000365358 -0.315776 0.948834 -0.000595538 -0.514717 0.85736 -0.00123162 -0.518757 0.854921 -0.00166146 -0.699809 0.714329 -6.06496e-05 -0.695485 0.718541 -7.28687e-05 -0.835604 0.549333 -9.97473e-05 -0.835659 0.549248 -0.000111422 -0.933464 0.358672 -0.000138121 -0.933499 0.358579 -0.000145633 -0.984268 0.176685 -0.000165361 -0.98428 0.176613 -0.00016771 -0.998267 0.0588402 -0.000175707 -0.998269 0.0588108 -0.000175781 -0.99869 -0.0511755 -0.000168782 -0.998691 -0.0511498 -0.000166633 -0.985975 -0.166893 -0.000147369 -0.985987 -0.166822 -0.000140289 -0.938614 -0.344969 -0.000114161 -0.938647 -0.344878 -0.000102624 -0.843784 -0.536683 -7.52837e-05 -0.843839 -0.536596 -6.30279e-05 -0.706466 -0.707747 6.30418e-05 -0.706466 -0.707747 0.00175424 -0.710963 -0.703227 0.0198304 -0.660781 -0.750317 0.00857845 -0.660881 -0.750442 0.0071996 -0.722049 -0.691805 0.0667137 -0.712361 -0.698635 -0.0364016 -0.786437 -0.616597 -0.0324715 0.986112 0.162874 -0.0294794 0.986302 0.162292 2.55727e-07 0.754709 -0.65606 -4.57693e-07 0.754712 -0.656057 -1.17891e-06 0.754708 -0.656061 0 0.754711 -0.656058 2.38473e-07 0.754709 -0.656059 5.01649e-06 0.754687 -0.656085 1.98651e-05 0.75471 -0.656058 -1.72784e-07 0.754707 -0.656062 1.68777e-06 0.754713 -0.656055 -1.31047e-07 0.754708 -0.656061 6.81369e-08 0.754716 -0.656052 -1.46152e-07 0.754708 -0.656061 2.24783e-06 0.754707 -0.656062 5.82924e-07 0.75471 -0.656058 -2.84653e-06 0.754708 -0.656061 5.04846e-08 0.754711 -0.656058 -2.93092e-07 0.754722 -0.656044 8.4182e-07 0.754709 -0.65606 7.97258e-07 0.754709 -0.65606 -5.25446e-06 0.754727 -0.656039 2.50103e-08 0.754708 -0.656061 4.87872e-06 0.754727 -0.656039 -9.54173e-07 0.754709 -0.65606 -5.61067e-07 0.754717 -0.656051 1.33815e-05 0.754717 -0.65605 2.59085e-08 0.75471 -0.656059 -2.74188e-06 0.754712 -0.656056 -8.78098e-07 0.754711 -0.656057 7.51795e-07 0.754707 -0.656062 9.45166e-07 0.754708 -0.656061 -3.01779e-07 0.754704 -0.656066 6.653e-07 0.754716 -0.656051 -0.866026 0.472759 0.162785 -0.866 0.472781 0.162859 -0.866025 0.472759 0.162784 -0.866025 0.472763 0.162778 -0.866026 0.472758 0.162784 -0.866026 0.472758 0.162785 0 0.190809 0.981627 -2.11909e-06 0.190809 0.981627 -2.80426e-06 0.190841 0.981621 2.95208e-07 0.190812 0.981627 -2.03692e-09 0.19081 0.981627 7.65228e-08 0.190808 0.981628 2.29641e-06 0.190778 0.981633 1.82554e-07 0.190807 0.981628 1.62861e-08 0.190812 0.981627 -6.05818e-07 0.190808 0.981627 -1.2339e-06 0.190815 0.981626 -4.05556e-07 0.190809 0.981627 4.48503e-08 0.190812 0.981627 1.26636e-07 0.190808 0.981627 -4.34697e-07 0.190813 0.981627 2.30283e-07 0.190807 0.981628 1.36537e-07 0.190811 0.981627 -3.00205e-07 0.190808 0.981627 -8.98117e-07 0.19081 0.981627 -9.87103e-07 0.190809 0.981627 2.05593e-06 0.190806 0.981628 -6.77544e-08 0.190809 0.981627 -7.69835e-08 0.19081 0.981627 2.84658e-07 0.190812 0.981627 -0.715529 0.325944 0.617883 -0.169762 0.188039 0.967379 -0.490409 0.205369 0.846949 -0.57416 0.391393 0.719133 -0.47163 0.244767 0.847145 -0.507436 0.27879 0.815343 -0.346766 0.192437 0.917998 -0.128803 0.223653 0.966121 -0.188502 0.324143 0.927038 -0.0875521 0.190077 0.977857 -0.659902 0.28473 0.695311 -0.735339 0.397598 0.54881 -0.749447 0.310667 0.58465 -0.82346 0.389334 0.412715 -0.841992 0.430366 0.325322 -0.859705 0.430048 0.275619 0.579849 0.260991 0.771789 0.852804 0.476143 0.214507 0.865401 0.460057 0.198568 0.849943 0.439298 0.290886 0.842996 0.43928 0.31047 0.813824 0.348784 0.464801 0.511735 0.268072 0.816251 0.448443 0.296798 0.843095 0.392364 0.222784 0.892423 0.561779 0.266206 0.783287 0.58661 0.266296 0.764837 0.737461 0.302993 0.603611 0.628848 0.366615 0.68567 0.714324 0.350725 0.605586 0.380737 0.213585 0.899678 0.152321 0.194332 0.969037 0.146264 0.188757 0.97107 -0.863012 -0.49825 -0.083407 -0.833772 -0.551969 0.0124444 -0.822276 -0.567852 0.0374976 -0.801833 -0.577751 0.152538 -0.73288 -0.622841 0.27378 -0.609702 -0.677392 0.411588 -0.631903 -0.683333 0.365726 -0.226045 -0.735175 0.639079 -0.121983 -0.785162 0.607158 -0.265225 -0.754188 0.600713 -0.402797 -0.71393 0.572763 -0.529193 -0.700696 0.478518 -0.866025 -0.472759 -0.162784 -0.866025 -0.472759 -0.162784 -0.866026 -0.472759 -0.162783 -0.0744175 -0.19028 -0.978905 -0.175771 -0.222857 -0.958874 -0.21838 -0.242145 -0.945345 -0.331139 -0.204409 -0.921175 -0.602206 -0.299501 -0.740032 -0.588561 -0.280459 -0.758247 -0.469334 -0.236442 -0.850777 -0.860229 -0.431991 -0.270905 -0.808233 -0.426217 -0.406322 -0.821885 -0.425044 -0.379267 -0.772542 -0.328634 -0.543303 -0.687907 -0.310158 -0.656191 -2.31548e-07 -0.754709 0.65606 0 -0.75471 0.656059 1.6412e-07 -0.754709 0.656059 -6.21884e-08 -0.190809 -0.981627 0 -0.190809 -0.981627 6.87552e-08 -0.190809 -0.981627 0.86323 -0.445091 -0.238175 0.836907 -0.425881 -0.343819 0.823974 -0.421531 -0.378654 0.802075 -0.361594 -0.475317 0.733501 -0.32257 -0.598268 0.685074 -0.305706 -0.661224 0.6452 -0.27243 -0.713792 0.529815 -0.255955 -0.808568 0.525016 -0.255828 -0.811733 0.40171 -0.209615 -0.891454 0.266871 -0.224496 -0.93722 0.219863 -0.231726 -0.947609 0.126626 -0.189273 -0.973725 0.105492 -0.750498 0.652399 0.220406 -0.763463 0.607079 0.525778 -0.699647 0.483789 0.381628 -0.719177 0.580642 0.236899 -0.75906 0.606389 0.775092 -0.594474 0.214085 0.701394 -0.639991 0.313779 0.68452 -0.648983 0.332045 0.616496 -0.664207 0.422803 0.503698 -0.708083 0.49488 0.820524 -0.567643 0.0672438 0.824892 -0.563902 0.0396029 0.860958 -0.505162 -0.0596915 0.866026 -0.472759 -0.162784 0.866026 -0.472759 -0.162784 0.866026 -0.472758 -0.162785 -0.500007 0 0.866022 -0.500001 -1.09091e-06 0.866025 0.500003 0 -0.866024 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -1 0 0 1 0 0 -0.499993 -7.5233e-07 -0.866029 -0.49999 0 -0.866031 0.499996 0 0.866028 0.500002 1.76504e-06 0.866024 -1 0 0 1 0 0 -0.500004 0 -0.866023 -0.50001 -6.05644e-07 -0.86602 -0.500019 0 -0.866015 -0.499999 0 0.866026 -0.499999 9.19736e-07 0.866026 -0.500004 0 0.866023 0.500022 0 0.866013 0.500001 2.0642e-07 0.866025 0.500001 0 0.866025 -0.500001 0 0.866025 -0.5 -1.15697e-06 0.866025 -0.499964 0 0.866046 0.499957 0 0.86605 0.499999 -2.29249e-06 0.866026 0.5 0 0.866025 -0.500001 0 0.866025 -0.5 -1.35897e-06 0.866025 -0.499981 0 0.866037 0.499989 0 0.866032 0.499999 -7.78647e-07 0.866026 0.5 0 0.866026 -0.500001 0 0.866025 -0.5 -9.7009e-07 0.866025 -0.499988 0 0.866032 0.500016 0 0.866016 0.500001 1.05298e-06 0.866025 0.5 0 0.866025 -0.499999 0 0.866026 -0.5 1.09656e-06 0.866025 -0.500018 0 0.866015 0.500025 0 -0.866011 0.500013 -7.94774e-07 -0.866018 0.500006 0 -0.866022 -0.500002 0 -0.866024 -0.499989 4.16739e-06 -0.866032 -0.499858 0 -0.866107 0.5 0 0.866025 0.500018 4.94342e-05 0.866015 -0.500158 0.000424224 0.865934 -0.500001 0 0.866025 0.50007 0 -0.865985 0.500007 -1.85019e-06 -0.866021 0.500001 0 -0.866025 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.561617 0.0953523 -0.821885 0.415476 0.104818 -0.903545 0.981989 0.0909959 -0.165584 0.931472 0.0424552 -0.361327 0.855483 0.060421 -0.514294 0.998502 0.0065538 -0.0543279 0.98279 0.0825565 0.165254 0.743309 0.0891919 0.662976 0.85529 0.0637347 0.514215 0.931368 0.0447878 0.361313 0.166685 0.119371 0.978758 0.258617 0.808386 -0.528799 0.258738 0.745992 -0.613637 0.258693 0.745988 -0.613662 0.258567 0.674435 -0.691578 0.258513 0.67443 -0.691604 0.258518 0.587771 -0.766612 0.258474 0.587764 -0.766632 0.258595 0.500824 -0.826017 0.258564 0.500815 -0.826032 0.258438 0.407503 -0.875872 0.258412 0.407496 -0.875882 0.258417 0.300887 -0.91798 0.258404 0.300883 -0.917985 0.258525 0.199169 -0.94525 0.258519 0.199166 -0.945252 0.258813 0.144032 -0.955128 0.166819 0.113131 -0.979476 0.312713 0.78242 -0.538544 0.259038 0.826613 -0.499611 0.258676 0.86532 -0.429311 0.31396 0.840186 -0.442173 0.259094 0.879965 -0.39816 0.25914 0.894275 -0.364855 0.259154 0.894281 -0.36483 0.25912 0.906619 -0.333014 0.291561 0.909853 -0.29523 0.259051 0.924952 -0.278131 0.258937 0.945702 -0.196468 0.2591 0.945672 -0.196394 0.259253 0.954212 -0.149221 0.279032 0.952026 -0.12565 0.259229 0.958969 -0.114795 0.259209 0.963588 -0.0656474 0.259221 0.963585 -0.0656409 0.259271 0.965558 -0.0218211 0.292359 0.9563 0.00393722 0.259224 0.965577 0.0215531 0.259091 0.961801 0.0883843 0.265657 0.959823 0.090364 0.259286 0.956821 0.131393 0.259051 0.949773 0.175566 0.258909 0.949819 0.175528 0.258935 0.927017 0.27128 0.258897 0.927032 0.271265 0.258774 0.892005 0.370625 0.258712 0.89203 0.370607 0.258706 0.84184 0.473684 0.258645 0.841866 0.47367 0.258774 0.784982 0.562885 0.258725 0.785007 0.562873 0.258602 0.719072 0.645027 0.258545 0.719099 0.64502 0.258539 0.637623 0.725668 0.258487 0.637648 0.725665 0.258616 0.554439 0.791022 0.258583 0.554457 0.79102 0.258461 0.465055 0.846712 0.258432 0.465069 0.846713 0.258426 0.3615 0.895842 0.258405 0.361511 0.895844 0.258797 0.291143 0.92101 0.258792 0.291149 0.92101 0.25841 0.219733 0.940714 0.258401 0.219737 0.940715 0.258778 0.145821 0.954867 0.415193 0.110588 0.902987 0.561299 0.100612 0.821475 0.707088 0.11236 0.698142 0.706492 0.160978 0.68917 0.706495 0.160979 0.689166 0.707055 0.213144 0.674272 0.707057 0.213147 0.674269 0.706483 0.264842 0.656308 0.706495 0.264844 0.656294 0.706504 0.3407 0.620303 0.706517 0.3407 0.620288 0.706697 0.406089 0.579371 0.706712 0.406089 0.579353 0.706524 0.467122 0.531621 0.706544 0.467117 0.531598 0.706553 0.526778 0.472533 0.706578 0.526769 0.472506 0.706757 0.574923 0.412258 0.70678 0.574914 0.412233 0.706591 0.6167 0.347002 0.706621 0.616682 0.346973 0.706629 0.653426 0.271494 0.706652 0.653411 0.271473 0.706831 0.67891 0.198675 0.70685 0.678895 0.198657 0.706812 0.695621 0.128562 0.706968 0.69548 0.128465 0.706954 0.704145 0.0662983 0.706966 0.704134 0.0662923 0.706965 0.707243 0.00291247 0.706965 0.707243 0.0029125 0.70719 0.705388 -0.0480567 0.707185 0.705394 -0.0480536 0.707087 0.701046 -0.0925331 0.707075 0.701059 -0.0925281 0.707054 0.692384 -0.143803 0.706862 0.692594 -0.143737 0.706655 0.67301 -0.218394 0.706626 0.673042 -0.218388 0.70723 0.6546 -0.267067 0.707226 0.654608 -0.26706 0.70663 0.633852 -0.314492 0.706603 0.633884 -0.314491 0.70661 0.592153 -0.387373 0.706588 0.592178 -0.387374 0.706765 0.546345 -0.449433 0.706742 0.546373 -0.449436 0.706556 0.49406 -0.506639 0.706533 0.494085 -0.506647 0.70654 0.430577 -0.561609 0.706521 0.430597 -0.561617 0.706699 0.366809 -0.605003 0.706684 0.366825 -0.60501 0.706498 0.298531 -0.641669 0.70649 0.298539 -0.641675 0.706497 0.220426 -0.672513 0.706492 0.22043 -0.672517 0.70667 0.145878 -0.692342 0.706667 0.14588 -0.692344 0.707109 0.111884 -0.698197 0.743534 0.0860205 -0.663143 0.965767 0.0585207 -0.252724 0.965844 0.0534238 -0.253556 0.965846 0.053425 -0.253551 0.965813 0.080743 -0.246345 0.965813 0.0807431 -0.246344 0.965812 0.109354 -0.235052 0.965814 0.109353 -0.235044 0.965848 0.134335 -0.221567 0.965849 0.134335 -0.221562 0.965816 0.157723 -0.205723 0.965819 0.157721 -0.205715 0.965817 0.180979 -0.18559 0.96582 0.180975 -0.185579 0.965854 0.200086 -0.164595 0.965856 0.200082 -0.164586 0.965824 0.216907 -0.141899 0.965828 0.216899 -0.141887 0.965826 0.232182 -0.1152 0.965829 0.232175 -0.115192 0.965938 0.239597 -0.0977601 0.965939 0.239595 -0.0977493 0.965829 0.246525 -0.0799975 0.965831 0.246519 -0.0799922 0.965869 0.253626 -0.0526412 0.965905 0.253505 -0.0525579 0.965908 0.256659 -0.0338783 0.96591 0.256653 -0.0338747 0.965928 0.258213 -0.0175919 0.965929 0.25821 -0.0175899 0.965887 0.25896 0.00106738 0.965887 0.258964 0.0010663 0.965887 0.257825 0.0242754 0.965885 0.257829 0.0242744 0.965888 0.254652 0.0470419 0.96586 0.254761 0.0470265 0.965867 0.24861 0.0727543 0.965865 0.248619 0.0727525 0.965832 0.239331 0.0994423 0.965829 0.239343 0.0994421 0.965828 0.225882 0.1271 0.965824 0.225897 0.127101 0.965859 0.210536 0.150969 0.965856 0.210546 0.150971 0.965823 0.192947 0.17308 0.965821 0.192958 0.173083 0.965819 0.171099 0.194727 0.965815 0.171112 0.194734 0.96585 0.148715 0.212174 0.965849 0.14872 0.212177 0.965816 0.124796 0.227214 0.965814 0.124802 0.227219 0.965812 0.0970132 0.240406 0.965812 0.0970145 0.240408 0.965917 0.0780176 0.246815 0.965916 0.078023 0.246817 0.965813 0.0589656 0.252443 0.965812 0.0589679 0.252446 0.96585 0.0562083 0.252932 0.998496 0.00691174 0.0543789 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.258728 -0.890902 -0.3733 -0.258746 -0.175202 0.949923 -0.998691 -0.00612559 0.0507783 -0.930861 -0.0379856 0.363393 -0.980774 -0.120612 0.15341 -0.569045 -0.0945869 0.816848 -0.422992 -0.104222 0.90012 -0.25882 -0.152987 0.953733 -0.174814 -0.112733 0.978127 -0.568826 -0.0987923 -0.816503 -0.422794 -0.108848 -0.899665 -0.93078 -0.0403857 -0.363342 -0.755899 -0.0841765 -0.649254 -0.998688 -0.00639301 -0.050803 -0.295917 -0.221809 0.929104 -0.258501 -0.201053 0.944857 -0.258418 -0.303635 0.917075 -0.296408 -0.422858 0.856349 -0.258782 -0.376272 0.889636 -0.258433 -0.303626 0.917073 -0.258452 -0.408377 0.87546 -0.25854 -0.502477 0.82503 -0.258572 -0.502455 0.825033 -0.258489 -0.590071 0.764853 -0.258532 -0.590045 0.764858 -0.258527 -0.675135 0.69091 -0.258579 -0.675105 0.69092 -0.258667 -0.747232 0.612157 -0.258719 -0.7472 0.612173 -0.258637 -0.809965 0.526369 -0.259135 -0.89499 0.3631 -0.258853 -0.868999 0.421705 -0.270477 -0.862849 0.427006 -0.259096 -0.842777 0.471802 -0.258694 -0.809935 0.526387 -0.258956 -0.945954 0.195224 -0.259194 -0.930995 0.257036 -0.280763 -0.913846 0.293355 -0.258973 -0.914215 0.311679 -0.259149 -0.894975 0.363126 -0.259069 -0.965835 -0.00674233 -0.259207 -0.963696 0.0640523 -0.259196 -0.963699 0.0640452 -0.259259 -0.959666 0.108742 -0.275264 -0.953148 0.125455 -0.259231 -0.955191 0.142863 -0.259104 -0.945899 0.195295 -0.259197 -0.934936 -0.242306 -0.258924 -0.949662 -0.176352 -0.259054 -0.949638 -0.176289 -0.259272 -0.957538 -0.126091 -0.275551 -0.956878 -0.0919524 -0.259159 -0.962218 -0.0835049 -0.259069 -0.965835 -0.0067423 -0.287534 -0.913426 -0.288059 -0.258866 -0.926499 -0.273108 -0.258782 -0.8909 -0.373267 -0.259104 -0.860547 -0.438548 -0.279234 -0.836387 -0.471684 -0.25886 -0.833449 -0.488215 -0.258751 -0.783881 -0.564428 -0.258699 -0.783873 -0.564463 -0.258615 -0.717154 -0.647155 -0.258559 -0.717144 -0.647188 -0.258553 -0.636913 -0.726287 -0.258504 -0.636901 -0.726314 -0.258594 -0.552881 -0.792119 -0.258559 -0.552869 -0.792139 -0.258476 -0.462528 -0.848091 -0.258445 -0.462517 -0.848106 -0.25844 -0.360613 -0.896196 -0.258419 -0.360605 -0.896205 -0.258785 -0.289065 -0.921668 -0.25878 -0.289057 -0.921672 -0.965575 -0.0672403 0.251285 -0.965838 -0.0539361 0.253472 -0.965839 -0.0539334 0.253469 -0.965817 -0.081476 0.246089 -0.965817 -0.0814741 0.246087 -0.965816 -0.109585 0.234927 -0.965817 -0.109581 0.234925 -0.965841 -0.134792 0.221321 -0.965843 -0.134784 0.221317 -0.965821 -0.158331 0.205235 -0.965822 -0.158325 0.205233 -0.965821 -0.181158 0.185396 -0.965824 -0.181145 0.185392 -0.965848 -0.200436 0.164207 -0.96585 -0.200424 0.164206 -0.965828 -0.217322 0.141235 -0.965831 -0.217307 0.141235 -0.96583 -0.232286 0.114958 -0.965833 -0.232274 0.114959 -0.965936 -0.239795 0.0972901 -0.965937 -0.239789 0.0972957 -0.965831 -0.246768 0.0792179 -0.965834 -0.246755 0.0792209 -0.965872 -0.253696 0.0522406 -0.965906 -0.253557 0.0522874 -0.965909 -0.256667 0.0337845 -0.96591 -0.256662 0.0337865 -0.965925 -0.258254 0.0171637 -0.965925 -0.25825 0.0171658 -0.965889 -0.258952 -0.00180779 -0.965888 -0.258954 -0.00180864 -0.965888 -0.257772 -0.0247717 -0.965887 -0.257776 -0.0247743 -0.965891 -0.254614 -0.0471931 -0.965864 -0.254704 -0.0472578 -0.965861 -0.248487 -0.0732513 -0.965859 -0.248495 -0.0732604 -0.965836 -0.23902 -0.100148 -0.965834 -0.239027 -0.100158 -0.965832 -0.225744 -0.127312 -0.965828 -0.225752 -0.127326 -0.965852 -0.210257 -0.151398 -0.96585 -0.21026 -0.151408 -0.965827 -0.19242 -0.173644 -0.965825 -0.192423 -0.173655 -0.965823 -0.170899 -0.194883 -0.96582 -0.170902 -0.194895 -0.965844 -0.148307 -0.212486 -0.965842 -0.148307 -0.212496 -0.965819 -0.12411 -0.227573 -0.965819 -0.12411 -0.227577 -0.965817 -0.0967672 -0.240486 -0.965815 -0.096766 -0.240494 -0.965914 -0.0774663 -0.247001 -0.965913 -0.0774636 -0.247004 -0.965817 -0.0580785 -0.252634 -0.965816 -0.0580774 -0.252637 -0.965706 -0.0642645 -0.251558 -0.982 -0.110282 -0.153344 -0.707097 -0.123636 -0.696224 -0.706512 -0.158553 -0.689711 -0.706518 -0.158556 -0.689705 -0.707042 -0.211622 -0.674765 -0.707043 -0.211625 -0.674763 -0.706505 -0.264177 -0.656552 -0.706514 -0.26418 -0.656542 -0.706522 -0.338831 -0.621305 -0.706536 -0.338834 -0.621287 -0.706659 -0.404955 -0.580211 -0.706674 -0.404957 -0.580192 -0.706542 -0.466576 -0.532076 -0.706565 -0.466574 -0.532047 -0.706573 -0.525345 -0.474096 -0.706597 -0.525339 -0.474066 -0.70672 -0.574129 -0.413427 -0.706744 -0.574122 -0.413396 -0.706613 -0.616333 -0.34761 -0.70664 -0.61632 -0.347578 -0.706648 -0.652592 -0.273445 -0.706671 -0.652578 -0.273419 -0.706794 -0.678547 -0.200039 -0.706813 -0.678534 -0.200019 -0.706826 -0.695502 -0.129125 -0.706979 -0.69537 -0.129005 -0.706962 -0.704008 -0.0676599 -0.706974 -0.703997 -0.0676516 -0.706972 -0.707224 -0.00493771 -0.706974 -0.707223 -0.00493692 -0.707176 -0.705481 0.0468899 -0.70717 -0.705487 0.0468853 -0.707093 -0.701072 0.0922867 -0.707081 -0.701085 0.0922795 -0.707063 -0.692553 0.142943 -0.706878 -0.692762 0.142841 -0.706667 -0.67368 0.216279 -0.706644 -0.673708 0.216269 -0.707222 -0.655122 0.265807 -0.707217 -0.655132 0.265795 -0.706652 -0.634145 0.313851 -0.706626 -0.634177 0.313844 -0.706633 -0.593289 0.385587 -0.706608 -0.593321 0.385584 -0.706729 -0.547267 0.448368 -0.706705 -0.547298 0.448367 -0.706577 -0.494549 0.506133 -0.706555 -0.494577 0.506137 -0.706562 -0.432241 0.560302 -0.706542 -0.432265 0.560308 -0.706663 -0.368029 0.604302 -0.70665 -0.368047 0.604308 -0.706521 -0.299161 0.641351 -0.706511 -0.299173 0.641357 -0.706518 -0.222431 0.671831 -0.706513 -0.222437 0.671834 -0.706634 -0.147263 0.692085 -0.70663 -0.147267 0.692088 -0.70704 -0.124742 0.696084 -0.756064 -0.0813959 0.649417 -0.258713 -0.241756 -0.935212 -0.283231 -0.21487 -0.934672 -0.258734 -0.187153 -0.947645 -0.258814 -0.153369 -0.953674 -0.174718 -0.117748 -0.977553 -0.416504 0.104764 -0.903078 -0.998502 0.0065538 -0.0543279 -0.562772 0.10049 0.820481 -0.416214 0.110532 0.902523 -0.93137 0.0447865 0.361309 -0.856629 0.063462 0.512016 -0.998496 0.00691174 0.0543789 -0.981986 0.0909886 -0.165604 -0.746524 0.0844669 -0.659975 -0.856829 0.0601599 -0.512078 -0.931473 0.0424534 -0.361324 -0.167927 0.113109 -0.979289 -0.258814 0.143859 -0.955154 -0.25852 0.199169 -0.945251 -0.258525 0.199167 -0.94525 -0.258404 0.300888 -0.917984 -0.258417 0.300881 -0.917982 -0.258412 0.407506 -0.875878 -0.258437 0.407494 -0.875876 -0.258564 0.500828 -0.826024 -0.258595 0.500811 -0.826025 -0.258474 0.587779 -0.766621 -0.258516 0.587758 -0.766623 -0.258511 0.674446 -0.691588 -0.258566 0.67442 -0.691593 -0.258693 0.746001 -0.613645 -0.258738 0.745978 -0.613654 -0.258887 0.795651 -0.547647 -0.291787 0.800439 -0.523602 -0.259038 0.826613 -0.499611 -0.258951 0.854748 -0.449833 -0.292388 0.856662 -0.425017 -0.259094 0.879965 -0.39816 -0.25914 0.894284 -0.364831 -0.259154 0.894271 -0.364853 -0.294412 0.938519 -0.180287 -0.259176 0.93975 -0.22293 -0.258795 0.918775 -0.298124 -0.309337 0.910671 -0.273839 -0.25912 0.906619 -0.333014 -0.259099 0.945673 -0.196395 -0.259113 0.957543 -0.126378 -0.259142 0.957534 -0.126388 -0.259209 0.963588 -0.0656406 -0.259222 0.963584 -0.0656472 -0.259272 0.965558 -0.0218203 -0.31422 0.949114 0.0211859 -0.259065 0.965852 0.00397615 -0.259089 0.961801 0.0883843 -0.265656 0.959824 0.090364 -0.259285 0.956822 0.131393 -0.259051 0.949782 0.175521 -0.25891 0.949811 0.175573 -0.258935 0.927022 0.271262 -0.258897 0.927027 0.271282 -0.2589 0.89549 0.362034 -0.27764 0.887164 0.368586 -0.259124 0.872455 0.41434 -0.965767 0.0585207 -0.252724 -0.965844 0.0534259 -0.253555 -0.965846 0.053423 -0.253552 -0.965813 0.0807433 -0.246345 -0.965813 0.0807427 -0.246344 -0.965812 0.109356 -0.23505 -0.965813 0.109354 -0.235048 -0.965847 0.134339 -0.22157 -0.965849 0.134331 -0.221565 -0.965816 0.157726 -0.205721 -0.965818 0.157719 -0.205717 -0.965817 0.180983 -0.185587 -0.96582 0.180972 -0.185582 -0.965854 0.200089 -0.164591 -0.965856 0.20008 -0.164589 -0.965824 0.21691 -0.141894 -0.965828 0.216896 -0.141892 -0.965826 0.232184 -0.115196 -0.965829 0.232173 -0.115196 -0.965938 0.2396 -0.0977513 -0.965938 0.239599 -0.0977527 -0.965828 0.24653 -0.0799958 -0.965831 0.246518 -0.079997 -0.965868 0.25364 -0.0525859 -0.965905 0.253496 -0.0526142 -0.965908 0.256659 -0.0338756 -0.965909 0.256657 -0.0338763 -0.965927 0.258217 -0.0175904 -0.965928 0.258214 -0.0175919 -0.965886 0.258964 0.00106631 -0.965886 0.258964 0.00106609 -0.965887 0.257825 0.024274 -0.965886 0.257829 0.0242759 -0.965888 0.254657 0.0470072 -0.96586 0.254753 0.0470607 -0.965868 0.248611 0.07275 -0.965865 0.248618 0.0727566 -0.965832 0.239333 0.099438 -0.965829 0.239341 0.0994462 -0.965828 0.225884 0.127094 -0.965824 0.225893 0.127106 -0.965859 0.210539 0.150966 -0.965856 0.210543 0.150974 -0.965823 0.19295 0.173076 -0.96582 0.192956 0.173091 -0.965818 0.171106 0.194726 -0.965816 0.171109 0.194736 -0.96585 0.148717 0.212172 -0.965849 0.148718 0.212178 -0.965816 0.124798 0.227213 -0.965814 0.124799 0.22722 -0.965812 0.0970139 0.240406 -0.965811 0.0970137 0.240412 -0.965916 0.0780232 0.246818 -0.965916 0.0780241 0.246817 -0.965813 0.0589671 0.252443 -0.965812 0.0589664 0.252447 -0.96585 0.0562083 0.252931 -0.982787 0.0825507 0.165274 -0.746292 0.0877766 0.659805 -0.70709 0.112744 0.698078 -0.706492 0.16098 0.68917 -0.706495 0.160977 0.689167 -0.707055 0.213151 0.67427 -0.707057 0.213148 0.674269 -0.706483 0.264847 0.656306 -0.706495 0.264836 0.656298 -0.706504 0.340707 0.6203 -0.706515 0.340696 0.620293 -0.706694 0.406099 0.579367 -0.70671 0.406082 0.579361 -0.706521 0.467133 0.531615 -0.706546 0.467106 0.531605 -0.706555 0.526786 0.472522 -0.706575 0.526763 0.472517 -0.706755 0.574934 0.412247 -0.706777 0.574907 0.412247 -0.706589 0.61671 0.346988 -0.70662 0.616674 0.346989 -0.706629 0.653432 0.271482 -0.706651 0.653406 0.271485 -0.706831 0.678913 0.198663 -0.706849 0.678892 0.19867 -0.70681 0.695635 0.128494 -0.706967 0.695469 0.128534 -0.706954 0.704146 0.0662934 -0.706966 0.704134 0.0662972 -0.706965 0.707243 0.00291154 -0.706965 0.707243 0.00291153 -0.70719 0.705388 -0.0480532 -0.707187 0.705391 -0.0480554 -0.70709 0.701045 -0.0925249 -0.707075 0.701058 -0.0925348 -0.707056 0.692404 -0.143698 -0.706862 0.692571 -0.143843 -0.706653 0.673016 -0.218381 -0.706629 0.673035 -0.218401 -0.707232 0.654604 -0.267052 -0.707226 0.654604 -0.267069 -0.706631 0.633858 -0.314478 -0.706603 0.633876 -0.314504 -0.706611 0.592159 -0.387362 -0.706588 0.592171 -0.387384 -0.706765 0.546355 -0.44942 -0.70674 0.546364 -0.44945 -0.706554 0.49407 -0.506631 -0.706533 0.494076 -0.506655 -0.706541 0.430585 -0.561602 -0.706522 0.430588 -0.561624 -0.706699 0.366816 -0.604998 -0.706686 0.366815 -0.605013 -0.706501 0.298536 -0.641664 -0.70649 0.298535 -0.641677 -0.706497 0.220429 -0.672512 -0.70649 0.220427 -0.67252 -0.706668 0.14588 -0.692344 -0.706665 0.145879 -0.692347 -0.707107 0.112328 -0.698128 -0.563084 0.0952377 -0.820893 -0.258838 0.846501 0.465229 -0.278373 0.837073 0.470975 -0.259063 0.817214 0.514827 -0.258775 0.784996 0.562865 -0.258726 0.784993 0.562892 -0.258604 0.719088 0.645009 -0.258544 0.719084 0.645038 -0.258539 0.637638 0.725655 -0.258487 0.637632 0.725679 -0.258616 0.554452 0.791013 -0.258584 0.554444 0.791028 -0.258462 0.465066 0.846706 -0.258432 0.465059 0.846719 -0.258426 0.361508 0.895839 -0.258406 0.361502 0.895847 -0.258798 0.29115 0.921008 -0.258792 0.291144 0.921011 -0.25841 0.219736 0.940713 -0.2584 0.219733 0.940716 -0.258777 0.14567 0.95489 -0.167794 0.119349 0.978571 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0.166941 -0.11289 0.979483 0.981998 -0.110274 -0.15336 0.743565 -0.0909491 -0.66245 0.855528 -0.0629771 -0.513913 0.934001 -0.0434603 -0.354617 0.56168 -0.0993799 -0.821364 0.415532 -0.109251 -0.902994 0.258817 -0.15497 -0.953414 0.166849 -0.117911 -0.978907 0.415732 -0.104607 0.903452 0.743706 -0.0887401 0.662591 0.980773 -0.120604 0.153425 0.934069 -0.0416216 0.354658 0.855653 -0.0603175 0.514023 0.998691 -0.00612559 0.0507783 0.258818 -0.15478 0.953444 0.258745 -0.175201 0.949924 0.278498 -0.199893 0.939405 0.258737 -0.224302 0.939544 0.258419 -0.303627 0.917077 0.258433 -0.303633 0.917071 0.258782 -0.376272 0.889636 0.282392 -0.405534 0.869366 0.258707 -0.427683 0.866116 0.25854 -0.50246 0.82504 0.258571 -0.502472 0.825023 0.258489 -0.590052 0.764867 0.258531 -0.590064 0.764844 0.258526 -0.675114 0.69093 0.25858 -0.675126 0.690899 0.258668 -0.747211 0.612182 0.258719 -0.747221 0.612149 0.258637 -0.809947 0.526396 0.258694 -0.809952 0.526361 0.259096 -0.842778 0.471799 0.270476 -0.862849 0.427006 0.258853 -0.868999 0.421706 0.259136 -0.894979 0.363127 0.25915 -0.894986 0.3631 0.258973 -0.914215 0.311679 0.280764 -0.913846 0.293354 0.259194 -0.930995 0.257034 0.258957 -0.945938 0.195304 0.290579 -0.946325 0.141537 0.259117 -0.957587 0.126039 0.259105 -0.945915 0.195215 0.259259 -0.959666 0.108742 0.259196 -0.963699 0.064053 0.259207 -0.963696 0.0640455 0.259069 -0.965835 -0.0067423 0.259069 -0.965835 -0.00674233 0.259159 -0.962218 -0.0835049 0.275552 -0.956878 -0.0919527 0.259272 -0.957538 -0.126093 0.259054 -0.949628 -0.176346 0.258923 -0.949673 -0.176295 0.259197 -0.934936 -0.242304 0.277413 -0.921547 -0.271649 0.259059 -0.921142 -0.290491 0.258782 -0.890889 -0.373295 0.258727 -0.890914 -0.373273 0.258721 -0.841361 -0.474527 0.258661 -0.841391 -0.474506 0.258751 -0.783861 -0.564455 0.258698 -0.783892 -0.564437 0.258614 -0.717133 -0.647177 0.258559 -0.717165 -0.647164 0.258554 -0.636892 -0.726305 0.258504 -0.636921 -0.726297 0.258594 -0.552864 -0.792131 0.258559 -0.552887 -0.792126 0.258475 -0.462514 -0.848099 0.258445 -0.462532 -0.848098 0.25844 -0.360603 -0.8962 0.258419 -0.360615 -0.896201 0.258786 -0.289057 -0.92167 0.258781 -0.289065 -0.921669 0.258424 -0.216434 -0.941474 0.303944 -0.238436 -0.92237 0.258734 -0.187153 -0.947645 0.707105 -0.121198 -0.696645 0.706512 -0.158557 -0.68971 0.706516 -0.158553 -0.689707 0.70704 -0.211626 -0.674766 0.707042 -0.211623 -0.674765 0.706504 -0.264185 -0.656551 0.706515 -0.264172 -0.656543 0.706523 -0.338839 -0.621299 0.706536 -0.338825 -0.621293 0.706659 -0.404966 -0.580203 0.706673 -0.404947 -0.580198 0.706542 -0.46659 -0.532065 0.706564 -0.466561 -0.532059 0.706573 -0.525357 -0.474083 0.706597 -0.525327 -0.474081 0.70672 -0.574141 -0.413411 0.706742 -0.574112 -0.413414 0.70661 -0.616345 -0.347592 0.706639 -0.616309 -0.347598 0.706648 -0.6526 -0.273428 0.706671 -0.652571 -0.273436 0.706794 -0.678552 -0.200022 0.706812 -0.67853 -0.200033 0.706824 -0.695522 -0.129034 0.706975 -0.695356 -0.129098 0.70696 -0.70401 -0.0676529 0.706974 -0.703996 -0.0676597 0.706972 -0.707224 -0.00493596 0.706975 -0.707221 -0.00493768 0.707177 -0.70548 0.0468834 0.707169 -0.705488 0.0468918 0.707092 -0.701075 0.0922793 0.707081 -0.701084 0.0922882 0.707066 -0.692579 0.142803 0.706882 -0.69273 0.142979 0.706668 -0.673685 0.216261 0.706644 -0.673702 0.216285 0.707222 -0.655127 0.265793 0.707215 -0.655126 0.265813 0.706651 -0.634155 0.313833 0.706627 -0.634169 0.313861 0.706634 -0.5933 0.38557 0.706609 -0.59331 0.3856 0.706729 -0.547279 0.448352 0.706704 -0.547285 0.448384 0.706576 -0.494562 0.506122 0.706555 -0.494565 0.506148 0.706562 -0.432253 0.560292 0.706543 -0.432253 0.560317 0.706664 -0.368039 0.604296 0.706649 -0.368036 0.604316 0.70652 -0.299169 0.641349 0.706511 -0.299166 0.64136 0.706518 -0.222435 0.671829 0.706511 -0.222432 0.671838 0.706632 -0.147267 0.692086 0.70663 -0.147266 0.692088 0.707065 -0.122005 0.696544 0.561895 -0.0951492 0.821718 0.965575 -0.0672403 0.251285 0.965838 -0.053934 0.253472 0.965839 -0.0539355 0.253468 0.965817 -0.0814747 0.246089 0.965817 -0.0814753 0.246087 0.965816 -0.109582 0.234928 0.965817 -0.109583 0.234923 0.965841 -0.134788 0.221323 0.965843 -0.134788 0.221313 0.965821 -0.158328 0.205238 0.965822 -0.158327 0.205231 0.965821 -0.181153 0.1854 0.965824 -0.18115 0.185387 0.965848 -0.200431 0.164212 0.96585 -0.200428 0.164201 0.965828 -0.217317 0.141241 0.965832 -0.217311 0.141228 0.96583 -0.232283 0.114963 0.965833 -0.232276 0.114953 0.965936 -0.239792 0.0972969 0.965937 -0.239792 0.0972888 0.965832 -0.246766 0.0792227 0.965834 -0.246759 0.0792152 0.965873 -0.25368 0.0523129 0.965906 -0.253572 0.0522152 0.965908 -0.256669 0.0337891 0.96591 -0.256662 0.0337839 0.965925 -0.258254 0.017164 0.965925 -0.258254 0.0171637 0.965888 -0.258955 -0.00180734 0.965888 -0.258954 -0.00180781 0.965888 -0.257772 -0.0247738 0.965887 -0.257776 -0.0247722 0.96589 -0.254607 -0.0472412 0.965862 -0.254718 -0.0472124 0.965861 -0.248489 -0.0732566 0.965859 -0.248497 -0.0732541 0.965836 -0.239018 -0.100154 0.965833 -0.23903 -0.100152 0.965832 -0.22574 -0.12732 0.965828 -0.225756 -0.127319 0.965852 -0.210252 -0.151405 0.965849 -0.210266 -0.151405 0.965826 -0.192418 -0.173651 0.965824 -0.19243 -0.173653 0.965822 -0.170897 -0.19489 0.965819 -0.170909 -0.194894 0.965843 -0.148306 -0.21249 0.965842 -0.148312 -0.212493 0.965819 -0.124107 -0.227575 0.965818 -0.124113 -0.227579 0.965816 -0.0967664 -0.24049 0.965815 -0.0967697 -0.240492 0.965914 -0.077463 -0.247002 0.965913 -0.0774669 -0.247003 0.965817 -0.0580767 -0.252634 0.965816 -0.0580792 -0.252637 0.965706 -0.0642645 -0.251558 0.998688 -0.00639301 -0.050803 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.707112 0.707101 0 0.707102 0.707112 -2.10513e-05 0.707096 0.707117 -2.10511e-05 0.707107 0.707107 0 0 1 0 0 1 0 0 1 0 0 1 0 0.707107 0.707107 0 0.70711 0.707104 1.05291e-05 0.707107 0.707107 1.0529e-05 0.707104 0.707109 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707112 0.707101 0 -0.707112 0.707101 0 -0.707107 0.707107 0 -0.707109 0.707104 -1.0529e-05 -0.707107 0.707107 -1.0529e-05 -0.707104 0.707109 0 -0.500196 0 -0.865912 -0.500196 0 -0.865912 0.500002 0 -0.866024 0.500002 0 -0.866024 -0.993488 0 -0.113939 -0.145086 0 -0.989419 -0.165998 -0.040874 -0.985279 -0.561868 -0.0145188 -0.8271 -0.544302 6.5767e-06 -0.83889 -0.416811 -1.5646e-05 -0.908993 -0.416878 -0.000107982 -0.908963 -0.308663 2.70669e-05 -0.951171 -0.740993 -0.0404457 -0.670294 -0.729538 -0.000399124 -0.68394 -0.605066 6.26292e-05 -0.796175 -0.993511 -0.000412911 -0.113735 -0.968906 7.43387e-05 -0.24743 -0.92776 -0.0355634 -0.371479 -0.921875 6.94384e-06 -0.387487 -0.855825 5.69513e-06 -0.517266 -0.856005 -8.69253e-05 -0.516968 -0.833495 8.07454e-05 -0.552527 0 0 -1 0 0 -1 0 0 -1 0.108188 0 -0.99413 0.989454 0 -0.144848 0.983564 -0.0440613 -0.175101 0.823594 -0.0166744 -0.566935 0.838673 -1.81123e-05 -0.544636 0.908588 1.61847e-05 -0.417693 0.908674 0.000225305 -0.417507 0.950984 -5.30487e-05 -0.30924 0.658321 -0.0437599 -0.751465 0.679721 0.000674331 -0.733471 0.794074 -0.000115998 -0.607821 0.108789 0.000811818 -0.994065 0.238417 -0.000176755 -0.971163 0.360338 -0.0378118 -0.932055 0.38347 -1.07955e-06 -0.923554 0.512879 -1.00347e-06 -0.858461 0.513356 0.000101898 -0.858176 0.546555 -0.000167291 -0.837423 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.0840512 0 0.996461 0.36798 -0.000777834 0.929833 0.260474 0.00452506 0.96547 0.259049 -0.00209421 0.965862 0.0822571 0.00184998 0.996609 0.995731 0 0.0923042 0.995253 0.00208067 0.0972951 0.959331 -0.00229179 0.282275 0.92343 0.0434214 0.381302 0.905108 -0.00346486 0.425168 0.842618 0.00611503 0.538477 0.842693 0.00265096 0.538388 0.711997 -0.00515489 0.702164 0.714604 -0.0114916 0.699435 0.580084 0.00140163 0.814555 0.509127 -0.0232582 0.860377 0.475212 0.000567987 0.879871 0.370369 -8.90028e-05 0.928885 0 0 1 0 0 1 0 0 1 -0.989144 0 0.14695 -0.990114 -0.0149521 0.139463 -0.917669 0.00933604 0.397235 -0.918924 -0.00617363 0.394385 -0.80246 0.00848799 0.596645 -0.814162 -0.0302809 0.579847 -0.60233 0.0271091 0.797787 -0.0161053 0 0.99987 -0.0619818 0.0111409 0.998015 -0.592635 0.0576717 0.803404 -0.548085 -0.00440646 0.836411 -0.425042 0.00929435 0.905126 -0.425636 0.0436673 0.90384 -0.277492 -0.0893591 0.956563 -0.268487 0.064385 0.961129 -0.11741 -0.0241869 0.992789 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.993488 0 0.113933 0.145087 0 0.989419 0.165999 -0.0408738 0.985279 0.480332 -0.0404977 0.876151 0.463456 -0.000167909 0.88612 0.308663 2.70669e-05 0.951171 0.740991 -0.0404397 0.670296 0.729538 -0.000399124 0.68394 0.605082 6.25737e-05 0.796163 0.993511 -0.000403271 0.113734 0.968906 8.37414e-05 0.247429 0.951303 -0.0170919 0.307783 0.94526 1.30076e-05 0.326319 0.887861 -1.15613e-05 0.460111 0.887978 -0.000338194 0.459885 0.833497 8.93286e-05 0.552525 0 0 1 0 0 1 0 0 1 -0.108188 0 0.99413 -0.989454 0 0.144848 -0.983564 -0.0440613 0.175101 -0.823593 -0.0166739 0.566936 -0.83868 -9.54609e-06 0.544625 -0.908592 2.52604e-05 0.417685 -0.90867 0.000216663 0.417515 -0.950993 -6.21832e-05 0.309212 -0.658321 -0.0437542 0.751465 -0.679718 0.000674777 0.733473 -0.794074 -0.000115641 0.607821 -0.10879 0.00081284 0.994064 -0.238417 -0.000174526 0.971163 -0.360339 -0.037809 0.932055 -0.38347 -1.07955e-06 0.923554 -0.512857 -1.00348e-06 0.858474 -0.513335 0.000102068 0.858188 -0.546568 -0.000167398 0.837415 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0.987547 0 -0.157325 0.991808 -0.0161013 -0.126719 0.0160822 0 -0.999871 0.0619761 0.0111451 -0.998015 0.917666 0.00933673 -0.397243 0.918921 -0.00617171 -0.394393 0.80246 0.00849021 -0.596646 0.814162 -0.0302809 -0.579847 0.602328 0.0271096 -0.797788 0.592632 0.0576753 -0.803406 0.489689 -0.0787556 -0.868333 0.448881 0.065948 -0.891155 0.277494 -0.0893648 -0.956562 0.268489 0.0643863 -0.961129 0.117411 -0.0241864 -0.992789 -0.084052 0 -0.996461 -0.367968 -0.000785678 -0.929838 -0.260472 0.00451762 -0.965471 -0.25905 -0.00208898 -0.965862 -0.0822525 0.00185551 -0.99661 -0.995732 0 -0.0922965 -0.995254 0.00208051 -0.0972871 -0.959332 -0.00229275 -0.282273 -0.923426 0.0434262 -0.381312 -0.905101 -0.00346377 -0.425182 -0.842621 0.0061146 -0.538472 -0.842696 0.0026535 -0.538383 -0.711991 -0.00515212 -0.702169 -0.7146 -0.0114912 -0.699439 -0.580111 0.0013992 -0.814536 -0.509135 -0.0232668 -0.860372 -0.475216 0.000563087 -0.879869 -0.370372 -9.28252e-05 -0.928884 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.0840997 0 -0.996457 -0.0822994 0.00186545 -0.996606 -0.264096 -0.00220478 -0.964494 -0.255889 0.004775 -0.966694 -0.434187 -0.00416815 -0.900813 -0.429361 -0.000962747 -0.903132 -0.532633 0.000375561 -0.846346 -0.554455 -0.00762748 -0.832179 -0.580188 0.00139457 -0.814482 -0.717551 -0.0118581 -0.696405 -0.709585 -0.00530687 -0.704599 -0.834982 0.002148 -0.550273 -0.834669 2.64149e-05 -0.550752 -0.873095 -5.19588e-06 -0.48755 -0.995678 0 -0.0928679 -0.995189 0.00213814 -0.0979508 -0.943987 -0.00347631 -0.329965 -0.949561 -0.0124712 -0.313335 -0.876178 0.00116016 -0.481986 0.989147 0 -0.146933 0.990118 -0.0148497 -0.139451 0.91739 0.00934228 -0.39788 0.918717 -0.00620745 -0.394867 0.801915 0.0084463 -0.597378 0.813722 -0.0304284 -0.580457 0.600094 0.0276177 -0.799453 0.0158896 0 -0.999874 0.0607179 0.0107437 -0.998097 0.589487 0.0600126 -0.805545 0.547066 -0.00353029 -0.837082 0.423505 0.00736483 -0.905864 0.423619 0.0456437 -0.90469 0.276434 -0.0932791 -0.956495 0.266525 0.0664031 -0.961538 0.116995 -0.0243325 -0.992834 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.993384 0 0.114839 0.145085 0 0.989419 0.166455 -0.040463 0.985218 0.480493 -0.0401429 0.876079 0.463168 -0.00019339 0.886271 0.308523 2.86794e-05 0.951217 0.740859 -0.0397945 0.670481 0.729178 -0.000441443 0.684325 0.604758 6.39104e-05 0.796409 0.993412 -0.000487577 0.114597 0.968539 8.29102e-05 0.248863 0.951082 -0.0164908 0.308499 0.945074 1.28293e-05 0.326856 0.887659 -1.56596e-05 0.4605 0.887792 -0.000380633 0.460244 0.833096 9.85629e-05 0.553129 0 0 1 0 0 1 0 0 1 -0.106733 0 0.994288 -0.989429 0 0.145018 -0.983426 -0.0450031 0.175637 -0.869171 -0.0463157 0.492337 -0.885061 0.000306713 0.465475 -0.950817 -5.73536e-05 0.309754 -0.656618 -0.0445934 0.752904 -0.678659 0.000602944 0.734453 -0.793314 -9.98013e-05 0.608813 -0.107298 0.000738697 0.994227 -0.235842 -0.000163222 0.971791 -0.297857 -0.0195355 0.954411 -0.321185 -6.12099e-06 0.947017 -0.454719 4.27623e-06 0.890635 -0.455174 0.000486375 0.890402 -0.544981 -0.000155302 0.838448 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0.0840997 0 0.996457 0.0823056 0.00185898 0.996605 0.264101 -0.00221303 0.964493 0.255893 0.00476734 0.966693 0.434198 -0.00417767 0.900808 0.429352 -0.000958603 0.903137 0.532627 0.000380768 0.84635 0.554469 -0.00762963 0.83217 0.580192 0.00138912 0.814478 0.717558 -0.0118651 0.696398 0.709588 -0.0053098 0.704597 0.834984 0.00214573 0.550271 0.834671 2.42261e-05 0.550749 0.873074 -7.10013e-06 0.487588 0.995679 0 0.0928675 0.995191 0.00213168 0.0979351 0.94399 -0.00348169 0.329955 0.949561 -0.0124712 0.313335 0.876166 0.00116194 0.482007 -0.987552 0 0.157294 -0.99181 -0.0159906 0.126716 -0.015913 0 0.999873 -0.0607251 0.0107398 0.998097 -0.917391 0.00934213 0.397879 -0.918718 -0.00620898 0.394866 -0.801914 0.00844429 0.59738 -0.813721 -0.0304299 0.580459 -0.600098 0.027614 0.79945 -0.589488 0.0600216 0.805544 -0.489301 -0.0822409 0.868229 -0.446014 0.0682573 0.892419 -0.276431 -0.0932778 0.956496 -0.266522 0.0664051 0.961538 -0.116994 -0.0243311 0.992835 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.993385 0 -0.114833 -0.145086 0 -0.989419 -0.166456 -0.0404628 -0.985218 -0.561837 -0.0143518 -0.827123 -0.544129 1.09221e-05 -0.839001 -0.416663 -1.08019e-05 -0.909061 -0.416746 -0.000124776 -0.909023 -0.308525 2.92325e-05 -0.951216 -0.740861 -0.0397933 -0.670479 -0.72918 -0.000441855 -0.684322 -0.604758 6.34445e-05 -0.796409 -0.993412 -0.000478034 -0.114596 -0.968547 9.20687e-05 -0.248829 -0.927572 -0.0344791 -0.372051 -0.921652 5.49767e-06 -0.388017 -0.855598 3.80271e-06 -0.517641 -0.855795 -9.84046e-05 -0.517316 -0.833078 9.0516e-05 -0.553155 0 0 -1 0 0 -1 0 0 -1 0.106733 0 -0.994288 0.98943 0 -0.145013 0.983425 -0.0450125 -0.175638 0.869172 -0.0463155 -0.492337 0.885061 0.000306713 -0.465475 0.950807 -5.72897e-05 -0.309783 0.656621 -0.0445877 -0.752902 0.678656 0.000597395 -0.734456 0.793327 -0.000106693 -0.608796 0.107298 0.000738697 -0.994227 0.235842 -0.000163222 -0.971791 0.297857 -0.0195356 -0.95441 0.321188 -3.66086e-06 -0.947015 0.454719 8.02284e-06 -0.890635 0.455174 0.000490657 -0.890402 0.544983 -0.000150185 -0.838447 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.340477 -0.940253 0 0.340477 -0.940253 0 0.461043 -0.887378 0 0.461043 -0.887378 0 0.542388 -0.840128 0 0.542388 -0.840128 0 0.648053 -0.761595 0 0.648053 -0.761595 0 0.71675 -0.69733 0 0.71675 -0.69733 0 0.790764 -0.612121 0 0.790764 -0.612121 0 0.854707 -0.51911 0 0.854707 -0.51911 0 0.899703 -0.436502 0 0.899703 -0.436502 0 0.949248 -0.314528 0 0.949248 -0.314528 0 0.974604 -0.223936 0 0.974604 -0.223936 0 0.995575 -0.0939673 0 0.995575 -0.0939673 0 0.995575 0.0939673 0 0.995575 0.0939673 0 0.974604 0.223936 0 0.974604 0.223936 0 0.949248 0.314528 0 0.949248 0.314528 0 0.899703 0.436502 0 0.899703 0.436502 0 0.854707 0.519111 0 0.854707 0.519111 0 0.790764 0.612121 0 0.790764 0.612121 0 0.71675 0.69733 0 0.71675 0.69733 0 0.648053 0.761595 0 0.648053 0.761595 0 0.542388 0.840128 0 0.542388 0.840128 0 0.461043 0.887378 0 0.461043 0.887378 0 0.340477 0.940253 0 0.340477 0.940253 0 0.340477 -0.940253 0 0.340477 -0.940253 0 0.461043 -0.887378 0 0.461043 -0.887378 0 0.542388 -0.840128 0 0.542388 -0.840128 0 0.648053 -0.761595 0 0.648053 -0.761595 0 0.71675 -0.69733 0 0.71675 -0.69733 0 0.790764 -0.612121 0 0.790764 -0.612121 0 0.854707 -0.51911 0 0.854707 -0.51911 0 0.899703 -0.436502 0 0.899703 -0.436502 0 0.949248 -0.314528 0 0.949248 -0.314528 0 0.974604 -0.223936 0 0.974604 -0.223936 0 0.995575 -0.0939673 0 0.995575 -0.0939673 0 0.995575 0.0939673 0 0.995575 0.0939673 0 0.974604 0.223936 0 0.974604 0.223936 0 0.949248 0.314528 0 0.949248 0.314528 0 0.899703 0.436502 0 0.899703 0.436502 0 0.854707 0.519111 0 0.854707 0.519111 0 0.790764 0.612121 0 0.790764 0.612121 0 0.71675 0.69733 0 0.71675 0.69733 0 0.648053 0.761595 0 0.648053 0.761595 0 0.542388 0.840128 0 0.542388 0.840128 0 0.461043 0.887378 0 0.461043 0.887378 0 0.340477 0.940253 0 0.340477 0.940253 -0.578444 0.815722 0 -0.0555016 0.998459 0 -0.0554886 0.998459 1.15665e-05 -0.249212 0.968449 -4.23004e-07 -0.275835 0.959183 -0.0623093 -0.408191 0.912897 1.43847e-06 -0.578446 0.815721 -5.08134e-06 -0.0553433 0.998467 0 -0.0553433 0.998467 0 -0.275832 0.961206 0 -0.275832 0.961206 0 -0.578407 0.815748 0 -0.578407 0.815748 0 0.167818 0.985818 0 0.66681 0.745228 0 0.6668 0.745236 -1.10976e-05 0.484523 0.874779 -1.30267e-05 0.484531 0.874774 1.44339e-05 0.167816 0.985818 4.99914e-06 0.666483 0.74552 0 0.666464 0.745537 -2.38623e-05 0.483975 0.875082 7.49189e-06 0.167625 0.985851 0 0.167627 0.985851 4.68792e-06 0.356722 0.934211 -7.3242e-06 0.50429 0.86034 0.0742109 0.578399 0.815754 0 0.0553955 0.998465 0 0.0553974 0.998464 1.65084e-06 0.249123 0.968472 7.42388e-06 0.275507 0.959284 0.0622054 0.408136 0.912921 0 0.578399 0.815754 0 0.0553451 0.998467 0 0.0553433 0.998467 -1.64509e-06 0.275831 0.961206 -8.19914e-06 0.275831 0.961206 -8.2767e-06 0.578411 0.815745 -1.72011e-05 0.578407 0.815748 0 -0.167862 0.985811 0 -0.666885 0.74516 0 -0.666885 0.74516 0 -0.484669 0.874697 0 -0.484669 0.874697 0 -0.167862 0.985811 0 -0.666467 0.745535 0 -0.666463 0.745538 4.03295e-06 -0.48398 0.875079 -2.18914e-05 -0.167624 0.985851 0 -0.167625 0.985851 -4.6881e-06 -0.356744 0.934202 7.32576e-06 -0.504285 0.860344 -0.0741942 0 0.999309 0.0371609 -4.09161e-05 0.999309 0.0371782 5.56534e-05 0.993741 0.111706 0 0.993738 0.111734 0 0.956989 0.290123 -0.326259 0.889834 0.318984 0.501068 0.642848 0.579377 -0.278157 0.759557 0.587964 0.252159 0.419143 0.872202 0 0.455468 0.890252 0.278149 0.759559 -0.587966 -0.252172 0.41914 -0.872199 0 0.455468 -0.890252 0 0.999308 -0.037184 -4.09464e-05 0.99931 -0.0371548 5.56932e-05 0.993738 -0.111736 0 0.993742 -0.111703 0 0.956989 -0.290123 0.326256 0.889835 -0.318984 -0.501075 0.642845 -0.579374 -0.278149 0.759559 0.587965 0.252152 0.419143 0.872203 0 0.455468 0.890252 0 0.999308 0.037184 4.09452e-05 0.99931 0.0371548 -5.56916e-05 0.993738 0.111736 0 0.993742 0.111703 0 0.956989 0.290123 -0.326251 0.889837 0.318985 0.501057 0.642853 0.579381 0 0.999309 -0.0371609 4.09149e-05 0.999309 -0.0371782 -5.56517e-05 0.993741 -0.111706 0 0.993738 -0.111734 0 0.956989 -0.290123 0.326247 0.889838 -0.318985 -0.501064 0.64285 -0.579378 0.278141 0.759561 -0.587967 -0.252165 0.419141 -0.872201 0 0.455468 -0.890252 -0.392632 0.883981 0.253806 -0.0139627 0.280982 0.959611 -0.0142991 0.280725 0.959682 -0.0386119 0.716321 0.696702 -0.0388599 0.716163 0.69685 -0.0531813 0.965774 0.253874 -0.0533912 0.965716 0.254051 -0.0707549 0.278061 0.957954 -0.0713915 0.27434 0.958979 -0.193505 0.696994 0.690474 -0.194152 0.694475 0.692828 -0.260004 0.916195 0.304933 -0.239811 0.937415 0.252477 -0.149554 0.247683 0.957229 -0.148383 0.240749 0.959178 -0.406493 0.600251 0.688812 -0.406 0.594874 0.69375 -0.555355 0.794278 0.246379 -0.55644 0.791404 0.253088 -0.677763 0.690218 0.253447 -0.677507 0.690754 0.252671 -0.491359 0.524732 0.695142 -0.491302 0.527054 0.693423 -0.178677 0.224148 0.958036 -0.179249 0.22879 0.956831 -0.678433 0.689272 0.25423 -0.678176 0.689805 0.253466 -0.492459 0.521342 0.696912 -0.492395 0.523697 0.69519 -0.179178 0.218422 0.959264 -0.179743 0.223083 0.958085 -6.75918e-08 0.967096 0.254411 -7.53297e-08 0.967095 0.254414 -1.33072e-07 0.716734 0.697346 -2.42617e-07 0.716705 0.697377 -1.73229e-07 0.280814 0.959762 -3.3578e-07 0.280753 0.95978 9.06419e-08 0.967095 0.254414 1.01017e-07 0.967096 0.254411 1.78455e-07 0.716705 0.697377 3.25355e-07 0.716734 0.697346 2.32286e-07 0.280753 0.95978 4.5031e-07 0.280814 0.959762 -0.0524056 0.967726 0.246496 -0.0527294 0.967634 0.246789 -0.0377449 0.731752 0.680525 -0.0377741 0.731731 0.680546 -0.0138019 0.316325 0.948551 -0.0135617 0.316597 0.948463 -0.262163 0.93437 0.241294 -0.263242 0.933012 0.24534 -0.190039 0.710534 0.677515 -0.190063 0.71039 0.677659 -0.0693275 0.306026 0.949496 -0.0692119 0.309911 0.948243 -0.552532 0.797228 0.24318 -0.553466 0.794306 0.250506 -0.402053 0.608852 0.683852 -0.401997 0.608551 0.684152 -0.146066 0.261536 0.954077 -0.148149 0.268109 0.951929 0.167728 0.226373 0.959491 0.171738 0.225829 0.95891 0.463539 0.54686 0.697191 0.467081 0.546047 0.695463 0.638762 0.72591 0.255027 0.641641 0.724265 0.252463 0.122037 0.255019 0.959204 0.127083 0.258595 0.95759 0.338171 0.636071 0.69358 0.342141 0.638356 0.689523 0.4643 0.848895 0.252593 0.466877 0.84904 0.2473 0.0425117 0.2805 0.958912 0.0438581 0.2824 0.958294 0.117326 0.711755 0.69256 0.118359 0.712968 0.691135 0.160887 0.954497 0.2511 0.161633 0.954815 0.249404 -1.33581e-07 0.968976 0.247154 -1.33581e-07 0.968976 0.247154 -3.68094e-07 0.732231 0.681057 -3.81923e-07 0.73223 0.681057 -3.41889e-07 0.316576 0.948567 -5.98226e-07 0.316562 0.948572 -1.06855e-06 0.968982 0.247133 -1.45877e-06 0.968976 0.247154 -2.97233e-06 0.732253 0.681033 -3.56604e-06 0.732231 0.681057 -4.01649e-06 0.316626 0.948551 -4.95692e-06 0.316576 0.948567 0.678576 0.689405 0.253485 0.678027 0.689685 0.254195 0.493635 0.522455 0.695245 0.491219 0.522579 0.696861 0.1818 0.221022 0.958174 0.177117 0.220473 0.959177 0.677922 0.690339 0.252693 0.67735 0.690631 0.253428 0.492528 0.525827 0.693486 0.490135 0.525954 0.695083 0.181298 0.226738 0.956933 0.176631 0.226191 0.957935 0.159818 0.312493 0.936379 0.653103 0.707788 0.269245 0.892028 0.268859 0.363319 0.91127 0.208055 0.355388 0.240068 0.965676 0.0991846 0.818784 0.291149 0.494798 0.713741 0.28733 0.63876 0.712696 0.301079 0.633573 0.536414 0.304256 0.787203 0.481961 0.127265 0.866901 0.396041 0.312459 0.863436 0.159312 0.309623 0.937419 0.646276 0.716072 0.263758 0.520118 0.716215 0.46531 0.516649 0.72232 0.459703 0.334532 0.722301 0.605285 0.333636 0.726057 0.601272 0.115234 0.726057 0.677911 0.115399 0.727338 0.676507 0.236726 0.966729 0.0969314 0.190526 0.966736 0.17065 0.188744 0.967508 0.168239 0.122256 0.967491 0.221393 0.121704 0.967965 0.219616 0.0420517 0.967958 0.247565 0.042074 0.968118 0.246935 0.484478 0.840036 0.244173 0.6361 0.728971 0.25294 0.638973 0.727352 0.250343 0.461645 0.555668 0.691461 0.461888 0.55563 0.691329 0.169776 0.241635 0.9554 0.166521 0.241455 0.956018 0.338441 0.907497 0.248809 0.470923 0.861911 0.187994 0.335105 0.650433 0.681647 0.335333 0.65058 0.681394 0.12491 0.284938 0.950373 0.120342 0.280722 0.952215 0.159001 0.956656 0.243984 0.160058 0.95711 0.241499 0.115281 0.727371 0.676492 0.115333 0.727441 0.676408 0.0425852 0.316338 0.94769 0.0414599 0.314194 0.948453 0.950581 0.26001 0.16968 0.948611 0.272164 0.161443 0.695312 0.704116 0.14409 0.68793 0.713015 0.13551 0.256517 0.963096 0.0815138 0.246104 0.966499 0.0728935 0.964776 0.248361 0.0867471 0.960662 0.266955 0.0765746 0.707027 0.696733 0.121149 0.698591 0.706388 0.113959 0.258764 0.957888 0.124467 0.252312 0.960136 0.120323 1.06864e-06 0.968976 0.247154 1.4587e-06 0.968982 0.247133 2.97241e-06 0.732231 0.681057 3.56598e-06 0.732253 0.681033 4.01649e-06 0.316576 0.948567 4.95699e-06 0.316626 0.948551 1.33581e-07 0.968976 0.247154 1.33581e-07 0.968976 0.247154 3.68094e-07 0.73223 0.681057 3.81923e-07 0.732231 0.681057 3.41887e-07 0.316562 0.948572 5.98227e-07 0.316576 0.948567 0.964318 0.120584 0.235693 0.964318 0.120584 0.235692 0.698469 0.325951 0.637101 0.698468 0.325952 0.637102 0.253007 0.440649 0.861288 0.253001 0.44065 0.861289 0.964318 0.209354 0.162058 0.964318 0.209354 0.162058 0.698469 0.565904 0.438058 0.698475 0.565898 0.438055 0.252999 0.765038 0.592206 0.253002 0.765037 0.592206 0.965238 0.250132 0.0758303 0.965238 0.250131 0.0758303 0.70339 0.680232 0.206221 0.703388 0.680234 0.206221 0.256281 0.925028 0.280433 0.256284 0.925028 0.280433 -0.563903 0.793532 0.228736 -0.160208 0.312473 0.936319 -0.0422305 0.968112 0.246934 -0.115776 0.727306 0.676478 -0.161045 0.309566 0.937141 -0.464019 0.309539 0.829983 -0.419003 -0.0420118 0.907012 -0.896947 0.269464 0.350535 -0.903312 0.225552 0.364901 -0.820115 0.290918 0.492725 -0.718705 0.287206 0.633226 -0.713262 0.301101 0.632926 -0.537842 0.304112 0.786283 -0.116403 0.726013 0.677757 -0.334321 0.72611 0.600828 -0.337317 0.722301 0.603738 -0.517329 0.722376 0.458851 -0.523401 0.716216 0.461612 -0.64574 0.716329 0.264373 -0.742174 0.613288 0.270287 -0.0424636 0.96795 0.247529 -0.121996 0.967972 0.219424 -0.123224 0.967494 0.22084 -0.189027 0.96752 0.167851 -0.19167 0.966738 0.169351 -0.236494 0.966776 0.0970244 -0.240416 0.965739 0.0977191 0.965637 0.0884881 0.244367 0.792052 0.207845 -0.573981 0.705543 0.241284 0.666326 0.257749 0.328973 0.908484 -0.122978 0.657244 0.743577 0.257755 0.328972 0.908482 0.258652 0.445354 0.857181 -0.304257 0.48619 0.819175 0.258429 0.523964 0.811589 0.25813 0.62609 0.735785 -0.304255 0.91488 0.265375 0.258771 0.692337 0.673578 0.257745 0.764047 0.591439 0.257737 0.764049 0.59144 0.258763 0.825596 0.501431 -0.122976 0.884564 0.449916 0.258121 0.869215 0.42171 0.25842 0.917005 0.303844 -0.122973 0.884564 -0.449916 0.258667 0.941435 0.216315 0.25777 0.961931 0.0907918 0.257749 0.961937 0.0907915 0.257749 0.961937 -0.0907923 0.25777 0.961931 -0.0907909 0.258667 0.941435 -0.216315 -0.304254 0.91488 -0.265375 0.25842 0.917005 -0.303844 0.258121 0.869215 -0.42171 0.258646 0.445355 -0.857182 -0.304254 0.48619 -0.819176 0.258763 0.825597 -0.50143 0.257737 0.764048 -0.59144 0.257746 0.764047 -0.591439 0.258771 0.692337 -0.673578 -0.122978 0.657244 -0.743577 0.25813 0.62609 -0.735785 0.258429 0.523963 -0.811589 0.257748 0.328973 -0.908484 0.194294 0.331547 -0.923216 0.4407 0.30563 -0.844022 0.705546 0.241283 0.666323 0.705546 0.361693 0.609412 0.705546 0.361693 0.609412 0.705546 0.469328 0.530976 0.705548 0.469327 0.530976 0.705549 0.560384 0.433786 0.705548 0.560385 0.433787 0.705547 0.631652 0.321277 0.705549 0.631651 0.321277 0.705549 0.680607 0.19742 0.705534 0.680621 0.197424 0.705534 0.70554 0.0665917 0.705537 0.705537 0.0665916 0.705537 0.705537 -0.0665914 0.705534 0.70554 -0.0665919 0.705534 0.680621 -0.197425 0.705549 0.680607 -0.19742 0.705549 0.631651 -0.321276 0.705546 0.631653 -0.321278 0.705545 0.560387 -0.433788 0.705549 0.560384 -0.433786 0.705548 0.469327 -0.530975 0.705546 0.469327 -0.530976 0.705546 0.361693 -0.609412 0.705546 0.361693 -0.609412 0.705546 0.241283 -0.666323 0.607305 0.26564 -0.748743 0.965637 0.0884882 0.244367 0.965637 0.132647 0.223496 0.965637 0.132647 0.223495 0.965637 0.172121 0.19473 0.965637 0.172122 0.194731 0.965637 0.205517 0.159088 0.965637 0.205517 0.159088 0.965636 0.231653 0.117826 0.965637 0.231653 0.117826 0.965637 0.249607 0.0724021 0.965637 0.249606 0.0724017 0.965637 0.258744 0.0244214 0.965638 0.258741 0.0244212 0.965638 0.258741 -0.0244211 0.965637 0.258744 -0.0244215 0.965637 0.249606 -0.0724016 0.965637 0.249607 -0.0724022 0.965637 0.231653 -0.117826 0.965637 0.231653 -0.117826 0.965637 0.205517 -0.159088 0.965636 0.205517 -0.159088 0.965637 0.172122 -0.194731 0.965637 0.172121 -0.19473 0.965637 0.132647 -0.223495 0.965636 0.132648 -0.223497 0.965636 0.0884888 -0.244369 0.965637 0.0884883 -0.244367 -0.97567 0.203727 0.0810129 -0.979986 0.186713 0.0690393 -0.822782 0.557383 0.111148 -0.831303 0.546222 0.102846 -0.546687 0.827888 0.12544 -0.555561 0.822719 0.120356 -0.188826 0.974457 0.121567 -0.195026 0.97355 0.119016 -0.947114 0.27229 0.169803 -0.972437 0.201137 0.11794 -0.765034 0.616528 0.186053 -0.818372 0.554338 0.151582 -0.589309 0.797662 0.128262 -0.545111 0.826726 0.139204 -0.251341 0.966637 0.0494081 -0.19486 0.978631 0.0656504 0.980063 0.187031 -0.0670458 0.980063 0.187033 -0.0670469 0.826514 0.529898 -0.189956 0.826516 0.529895 -0.189954 0.548265 0.78725 -0.28221 0.548266 0.78725 -0.28221 0.191543 0.923914 -0.331201 0.191541 0.923915 -0.331201 0.980063 0.14759 -0.133018 0.980063 0.147589 -0.133017 0.826517 0.418146 -0.376861 0.826514 0.418148 -0.376863 0.548265 0.621229 -0.559893 0.54827 0.621227 -0.559891 0.191542 0.729073 -0.657088 0.191543 0.729073 -0.657088 0.191532 0.425119 -0.884641 0.191544 0.425119 -0.884638 0.435521 0.389902 -0.811356 0.548596 0.36545 -0.75199 0.601464 0.346035 -0.72007 0.826516 0.24382 -0.507368 0.787142 0.272317 -0.553399 0.979742 0.0798262 -0.183667 0.96467 0.114115 -0.237465 -0.191555 0.425118 0.884636 -0.191534 0.425118 0.884641 -0.435521 0.389901 0.811356 -0.548578 0.365453 0.752002 -0.826878 0.247022 0.505226 -0.787724 0.266826 0.555243 -0.601436 0.346043 0.720089 -0.980063 0.0860585 0.179081 -0.980064 0.0860577 0.179079 -0.893454 0.194546 0.404835 -0.191538 0.729073 0.657088 -0.191549 0.729072 0.657086 -0.548252 0.621236 0.559898 -0.548247 0.621238 0.5599 -0.826533 0.418129 0.376845 -0.82653 0.418131 0.376847 -0.980063 0.147589 0.133017 -0.980063 0.147588 0.133016 -0.191548 0.923913 0.331201 -0.19155 0.923913 0.331201 -0.548248 0.78726 0.282214 -0.548248 0.787261 0.282214 -0.826532 0.529873 0.189947 -0.826532 0.529873 0.189947 -0.980063 0.187032 0.0670465 -0.980064 0.18703 0.0670454 0.195019 0.973552 -0.119016 0.555579 0.822708 -0.120347 0.975662 0.203764 -0.0810168 0.979986 0.186718 -0.0690205 0.822802 0.557358 -0.111129 0.188824 0.974457 -0.121565 0.194859 0.978632 -0.0656502 0.182279 0.980808 -0.0692086 0.42577 0.899025 -0.102342 0.545095 0.826736 -0.139207 0.546671 0.827897 -0.12545 0.831285 0.546246 -0.102863 0.963107 0.209462 -0.168967 0.966724 0.197669 -0.162395 0.876842 0.452804 -0.161605 0.814919 0.551926 -0.176873 0.773419 0.616449 -0.147696 0.589305 0.797664 -0.128263 -0.258436 0.523962 -0.811588 -0.705546 0.361693 0.609412 -0.980622 0.0667024 0.184204 -0.965637 0.172121 0.19473 -0.965637 0.132647 0.223495 -0.965637 0.132647 0.223496 -0.965637 0.0884882 0.244367 -0.896327 0.143727 0.419453 -0.965637 0.231653 -0.117826 -0.965637 0.249607 -0.0724021 -0.965637 0.249606 -0.0724017 -0.965637 0.258744 -0.0244214 -0.965638 0.258741 -0.0244212 -0.965638 0.258741 0.0244211 -0.965637 0.258744 0.0244215 -0.965637 0.249606 0.0724016 -0.965637 0.249607 0.0724022 -0.705548 0.469327 0.530975 -0.965637 0.205517 0.159088 -0.965637 0.205517 0.159088 -0.705549 0.560384 0.433786 -0.705547 0.560386 0.433787 -0.705534 0.680621 -0.197424 -0.705534 0.70554 -0.0665917 -0.705537 0.705537 -0.0665916 -0.705537 0.705537 0.0665914 -0.705534 0.70554 0.0665919 -0.705534 0.680621 0.197425 -0.705549 0.680607 0.19742 -0.705546 0.631653 -0.321278 -0.965637 0.205517 -0.159088 -0.965636 0.205517 -0.159088 -0.705545 0.560387 -0.433788 -0.705548 0.560385 -0.433786 -0.257762 0.328971 0.90848 -0.194318 0.331545 0.923211 -0.440702 0.30563 0.844021 -0.705546 0.241283 0.666323 -0.607277 0.265646 0.748763 -0.79207 0.207837 0.573959 -0.965637 0.172122 0.194731 -0.705546 0.469328 0.530976 -0.705546 0.361693 0.609412 0.304265 0.486188 0.819173 -0.258659 0.445353 0.857179 -0.25877 0.825595 0.50143 -0.257744 0.764047 0.591439 -0.257753 0.764045 0.591438 -0.258779 0.692335 0.673577 0.122981 0.657244 0.743577 -0.258137 0.626089 0.735784 -0.258437 0.523962 0.811587 -0.965636 0.231653 0.117826 -0.965637 0.231653 0.117826 -0.705547 0.631652 0.321277 -0.705548 0.631651 0.321277 0.12298 0.884563 0.449915 -0.258129 0.869213 0.421709 -0.258427 0.917003 0.303844 0.304263 0.914877 0.265374 -0.258674 0.941433 0.216315 -0.257777 0.961929 0.0907907 -0.257756 0.961935 0.0907921 -0.257756 0.961935 -0.0907913 -0.257777 0.961929 -0.0907916 -0.965636 0.231653 -0.117826 -0.705549 0.631651 -0.321277 -0.705549 0.680607 -0.19742 0.304262 0.914878 -0.265374 -0.258675 0.941433 -0.216315 -0.258779 0.692335 -0.673577 -0.257752 0.764045 -0.591438 -0.257744 0.764047 -0.591439 -0.25877 0.825595 -0.501429 0.122977 0.884564 -0.449916 -0.258128 0.869213 -0.42171 -0.258427 0.917003 -0.303844 -0.965637 0.172122 -0.194731 -0.965637 0.172121 -0.19473 -0.705548 0.469326 -0.530975 -0.705546 0.469328 -0.530977 0.122981 0.657244 -0.743577 -0.258138 0.626089 -0.735784 -0.258653 0.445354 -0.85718 0.304263 0.486188 -0.819173 -0.705546 0.361693 -0.609412 -0.705546 0.361693 -0.609412 -0.965636 0.132648 -0.223497 -0.965637 0.132647 -0.223495 -0.965636 0.0884889 -0.244369 -0.965637 0.0884882 -0.244367 -0.705546 0.241283 -0.666323 -0.70555 0.241282 -0.66632 -0.257756 0.328972 -0.908482 -0.257744 0.328973 -0.908485 0.236286 0.966764 -0.0976504 0.419348 0.898454 -0.130108 0.18115 0.980654 -0.0741749 0.818784 0.291149 -0.494798 0.91127 0.208055 -0.355388 0.911489 0.20728 -0.355278 0.827652 0.447781 -0.338356 0.64509 0.716293 -0.26605 0.741448 0.613122 -0.272646 0.563462 0.793407 -0.230252 0.190862 0.966762 -0.170127 0.188254 0.967534 -0.168636 0.521256 0.716376 -0.463785 0.515246 0.722478 -0.461028 0.715869 0.287482 -0.636306 0.418091 -0.0322323 -0.907833 0.536414 0.304256 -0.787203 0.710469 0.30124 -0.635994 0.115001 0.727372 -0.676539 0.115621 0.726098 -0.677801 0.0419443 0.968123 -0.246937 0.0421755 0.967963 -0.247527 0.122556 0.967508 -0.221154 0.121343 0.96798 -0.21975 0.335509 0.722394 -0.604632 0.332549 0.726164 -0.601745 0.461587 0.309604 -0.831314 0.159981 0.309643 -0.937298 0.159147 0.312528 -0.936482 -0.256291 0.925026 -0.280433 -0.256288 0.925026 -0.280433 -0.703388 0.680234 -0.206221 -0.703388 0.680234 -0.206221 -0.965238 0.250132 -0.0758304 -0.965238 0.25013 -0.0758302 -0.253009 0.765036 -0.592205 -0.253006 0.765036 -0.592205 -0.698471 0.565901 -0.438057 -0.698469 0.565903 -0.438058 -0.964318 0.209352 -0.162057 -0.964317 0.209356 -0.162059 -0.253008 0.440649 -0.861287 -0.253002 0.44065 -0.861288 -0.698468 0.325952 -0.637101 -0.698475 0.325948 -0.637095 -0.964317 0.120585 -0.235695 -0.964318 0.120584 -0.235693 -5.98226e-07 0.316562 -0.948572 -5.98226e-07 0.316562 -0.948572 -5.65968e-07 0.732238 -0.681049 -3.68095e-07 0.73223 -0.681057 -1.33581e-07 0.968976 -0.247154 -1.33581e-07 0.968976 -0.247154 -4.95698e-06 0.316626 -0.948551 -3.76015e-06 0.316562 -0.948572 -3.38194e-06 0.732253 -0.681033 -2.97239e-06 0.732238 -0.681049 -1.45871e-06 0.968981 -0.247137 -1.13543e-06 0.968976 -0.247154 -0.950578 0.260009 -0.169699 -0.948603 0.27219 -0.161443 -0.695313 0.704115 -0.14409 -0.68793 0.713015 -0.135509 -0.256523 0.963095 -0.0815139 -0.24611 0.966497 -0.0728944 -0.964775 0.248362 -0.0867464 -0.960662 0.266955 -0.0765746 -0.707027 0.696733 -0.121149 -0.698592 0.706387 -0.11396 -0.258771 0.957886 -0.124468 -0.252317 0.960135 -0.120323 -0.484474 0.840042 -0.244159 -0.636107 0.728971 -0.252922 -0.638957 0.727365 -0.250346 -0.461627 0.555671 -0.69147 -0.461888 0.55563 -0.691329 -0.16978 0.241639 -0.955398 -0.166518 0.241458 -0.956018 -0.338464 0.907492 -0.248799 -0.470923 0.861911 -0.187994 -0.335102 0.650427 -0.681654 -0.33533 0.650574 -0.681401 -0.124918 0.284953 -0.950367 -0.12034 0.280728 -0.952213 -0.158997 0.956654 -0.243993 -0.16006 0.957111 -0.241494 -0.115282 0.727371 -0.676492 -0.115332 0.727438 -0.676411 -0.0425852 0.316338 -0.94769 -0.0414668 0.314207 -0.948448 -0.0423612 0.968106 -0.246932 -0.116177 0.727272 -0.676446 -0.160377 0.309518 -0.937272 -0.160886 0.312439 -0.936215 -0.397021 0.312432 -0.862995 -0.484625 0.125083 -0.865732 -0.537837 0.304112 -0.786287 -0.715491 0.300939 -0.630483 -0.716577 0.287052 -0.635703 -0.0423402 0.967944 -0.247571 -0.122359 0.967956 -0.219291 -0.122921 0.967479 -0.221075 -0.189514 0.967495 -0.167447 -0.191333 0.966713 -0.169879 -0.23693 0.966742 -0.0963019 -0.240228 0.965703 -0.0985282 -0.116016 0.725986 -0.677853 -0.335411 0.726014 -0.600335 -0.336338 0.722193 -0.604412 -0.51874 0.722207 -0.457522 -0.522268 0.716049 -0.463153 -0.64692 0.716108 -0.262076 -0.653648 0.707946 -0.267501 -0.892929 0.268993 -0.360999 -0.908738 0.220216 -0.354543 -0.820124 0.290918 -0.49271 -0.679846 0.687821 -0.254387 -0.679109 0.687958 -0.255981 -0.496209 0.517251 -0.697301 -0.492467 0.516075 -0.700816 -0.184175 0.212632 -0.959618 -0.176478 0.209076 -0.961843 -0.67839 0.689869 -0.252721 -0.67765 0.690016 -0.254302 -0.493829 0.524519 -0.69355 -0.490084 0.523374 -0.697064 -0.183091 0.22494 -0.957016 -0.175404 0.221402 -0.959278 4.95691e-06 0.316562 -0.948572 3.76016e-06 0.316626 -0.948551 3.38198e-06 0.732238 -0.681049 2.97233e-06 0.732253 -0.681033 1.45877e-06 0.968976 -0.247154 1.13535e-06 0.968981 -0.247137 5.98226e-07 0.316562 -0.948572 5.98226e-07 0.316562 -0.948572 5.6597e-07 0.73223 -0.681057 3.6809e-07 0.732238 -0.681049 1.33581e-07 0.968976 -0.247154 1.33581e-07 0.968976 -0.247154 -0.168983 0.213356 -0.962249 -0.172691 0.212844 -0.961704 -0.466455 0.539248 -0.701165 -0.469256 0.538607 -0.699787 -0.640839 0.723573 -0.256452 -0.64271 0.722506 -0.254772 -0.123146 0.2426 -0.962279 -0.127886 0.245957 -0.960807 -0.340765 0.62983 -0.697992 -0.343895 0.63165 -0.694805 -0.466123 0.847465 -0.254034 -0.467768 0.847569 -0.250639 -0.0429098 0.268465 -0.962333 -0.044186 0.270261 -0.961773 -0.118271 0.706444 -0.697817 -0.119093 0.707413 -0.696695 -0.161553 0.953761 -0.253459 -0.162004 0.953955 -0.252438 0.0524056 0.967726 -0.246496 0.0527317 0.967633 -0.246791 0.0377543 0.731745 -0.680532 0.0377741 0.731731 -0.680546 0.0138018 0.316324 -0.948551 0.0135613 0.316597 -0.948463 0.262163 0.934371 -0.24129 0.263243 0.933012 -0.24534 0.190036 0.710531 -0.677519 0.19006 0.710387 -0.677663 0.0693307 0.306039 -0.949491 0.0692155 0.309909 -0.948243 0.552536 0.797224 -0.243184 0.553468 0.794309 -0.250494 0.402053 0.608852 -0.683852 0.401996 0.608542 -0.68416 0.146067 0.261535 -0.954078 0.148154 0.268121 -0.951925 0 0.966456 -0.256833 0 0.966456 -0.256833 0 0.711452 -0.702735 5.4603e-08 0.711437 -0.702749 2.06247e-08 0.268725 -0.963217 5.75874e-08 0.268712 -0.963221 0 0.966456 -0.256833 0 0.966456 -0.256833 0 0.711438 -0.702749 -7.24444e-08 0.711452 -0.702735 -2.73619e-08 0.268712 -0.963221 -7.64036e-08 0.268725 -0.963217 0.678053 0.689606 -0.254337 0.677976 0.690284 -0.2527 0.491317 0.522161 -0.697105 0.492598 0.525757 -0.693489 0.17745 0.219354 -0.959372 0.181033 0.227004 -0.95692 0.679521 0.687546 -0.255991 0.679433 0.688227 -0.25439 0.493709 0.51484 -0.70085 0.494976 0.518503 -0.697247 0.178541 0.207019 -0.961908 0.182102 0.214703 -0.959553 0.393386 0.882965 -0.256163 0.0140493 0.268924 -0.963059 0.0143651 0.268684 -0.963121 0.0388329 0.711029 -0.70209 0.0390446 0.710895 -0.702214 0.0532985 0.965108 -0.256371 0.0534136 0.965076 -0.256466 0.0712953 0.265739 -0.961405 0.0719019 0.262253 -0.962317 0.194754 0.691098 -0.696028 0.195275 0.689092 -0.697868 0.260978 0.915066 -0.307482 0.240266 0.936716 -0.254629 0.15049 0.234716 -0.960344 0.149413 0.228203 -0.962081 0.408689 0.592791 -0.693954 0.408322 0.588521 -0.697794 0.556832 0.79216 -0.249842 0.557568 0.790253 -0.254201 -0.0546127 0.978619 -0.198299 -0.0547641 0.978644 -0.198136 -0.0465938 0.824761 -0.563559 -0.046802 0.824871 -0.56338 -0.0312468 0.540954 -0.840472 -0.0314542 0.541108 -0.840365 -0.0108964 0.171506 -0.985123 -0.0111738 0.171724 -0.985082 -0.271696 0.941793 -0.198008 -0.272662 0.942105 -0.195175 -0.232548 0.794901 -0.560404 -0.233924 0.7963 -0.55784 -0.15649 0.522111 -0.838398 -0.15832 0.524506 -0.836557 -0.0545824 0.163291 -0.985067 -0.0567984 0.166292 -0.984439 -0.569217 0.79743 -0.200244 -0.57158 0.797409 -0.193483 -0.486923 0.668589 -0.562045 -0.490747 0.67052 -0.55639 -0.327496 0.434063 -0.839247 -0.33246 0.437357 -0.835577 -0.114032 0.128106 -0.985183 -0.119693 0.131963 -0.984002 -5.29915e-08 0.980113 -0.198441 -6.76696e-08 0.980114 -0.198434 -1.17568e-07 0.825759 -0.564023 -1.80569e-07 0.825776 -0.563998 -1.90255e-07 0.541342 -0.840803 -2.72867e-07 0.541376 -0.84078 -1.96171e-07 0.171671 -0.985154 -3.28586e-07 0.171735 -0.985143 7.02179e-08 0.980114 -0.198434 8.96722e-08 0.980113 -0.198441 1.55788e-07 0.825776 -0.563998 2.39279e-07 0.825759 -0.564023 2.52113e-07 0.541376 -0.84078 3.61575e-07 0.541342 -0.840803 2.59972e-07 0.171735 -0.985143 4.3539e-07 0.171671 -0.985154 -0.697171 0.688748 -0.198945 -0.697466 0.688608 -0.198395 -0.594867 0.57142 -0.565342 -0.596246 0.571423 -0.563885 -0.398274 0.363575 -0.842135 -0.401155 0.364125 -0.840528 -0.138487 0.0981938 -0.985484 -0.142963 0.0993398 -0.98473 -0.697758 0.688002 -0.199464 -0.698057 0.687862 -0.198904 -0.596055 0.568845 -0.566687 -0.597434 0.568852 -0.565225 -0.399363 0.359097 -0.84354 -0.402204 0.359644 -0.841955 -0.138904 0.0921767 -0.986007 -0.143364 0.0933166 -0.985261 0.65649 0.728157 -0.197 0.657986 0.726099 -0.199589 0.560841 0.607468 -0.56253 0.561699 0.604735 -0.564615 0.376552 0.391059 -0.839811 0.37702 0.38788 -0.841074 0.132439 0.112863 -0.984745 0.132832 0.109459 -0.985076 0.47733 0.857001 -0.19418 0.478285 0.855246 -0.199493 0.409433 0.722515 -0.557078 0.409466 0.718938 -0.561663 0.27662 0.473694 -0.836119 0.275969 0.468611 -0.839193 0.0981577 0.146898 -0.984269 0.097227 0.140898 -0.985238 0.165258 0.966638 -0.195705 0.165712 0.966218 -0.197387 0.141599 0.817456 -0.558315 0.141997 0.816324 -0.559868 0.0954873 0.538902 -0.836939 0.0958633 0.537114 -0.838045 0.0336101 0.171638 -0.984587 0.0340319 0.169388 -0.984962 -0.0114823 0.133273 -0.991013 -0.0112263 0.132977 -0.991055 -0.0321594 0.517433 -0.855119 -0.032082 0.517361 -0.855166 -0.0474836 0.815186 -0.577249 -0.0476008 0.815254 -0.577144 -0.0549045 0.977449 -0.203907 -0.0551931 0.977497 -0.203599 -0.0581543 0.132173 -0.989519 -0.0558914 0.128266 -0.990164 -0.16119 0.501924 -0.849759 -0.16055 0.500942 -0.850459 -0.236724 0.78559 -0.571673 -0.237413 0.786369 -0.570315 -0.273322 0.940018 -0.204112 -0.274809 0.940558 -0.199577 -0.120811 0.110175 -0.986543 -0.114773 0.104965 -0.987831 -0.334425 0.420811 -0.843254 -0.332802 0.419532 -0.844533 -0.492379 0.661046 -0.566198 -0.494006 0.662001 -0.56366 -0.571393 0.795226 -0.202794 -0.574064 0.795338 -0.194648 0.697813 0.688106 -0.198915 0.697988 0.687766 -0.199478 0.596725 0.569582 -0.56524 0.596781 0.568138 -0.566632 0.401028 0.360823 -0.842011 0.400536 0.357908 -0.843489 0.141701 0.0949737 -0.985343 0.140562 0.0905197 -0.985925 0.69724 0.688841 -0.198378 0.69741 0.688509 -0.198934 0.59554 0.572131 -0.563914 0.595591 0.570716 -0.565292 0.399956 0.365309 -0.840586 0.399457 0.362394 -0.842083 0.141296 0.101008 -0.984801 0.140145 0.0965297 -0.985414 8.81621e-07 0.978992 -0.2039 1.03602e-06 0.97899 -0.20391 2.40646e-06 0.8162 -0.577769 2.9121e-06 0.81618 -0.577797 3.56532e-06 0.517657 -0.855588 4.07633e-06 0.517628 -0.855606 3.96541e-06 0.133047 -0.99111 4.87667e-06 0.132986 -0.991118 1.10203e-07 0.978992 -0.2039 1.10203e-07 0.978992 -0.2039 3.12274e-07 0.816194 -0.577778 1.56135e-07 0.8162 -0.577769 2.31208e-07 0.517679 -0.855575 6.02314e-07 0.517657 -0.855588 5.71624e-07 0.133047 -0.99111 5.71624e-07 0.133047 -0.99111 0.133721 0.0936605 -0.986583 0.134016 0.0970537 -0.986215 0.379684 0.37751 -0.844587 0.379647 0.37845 -0.844182 0.564265 0.600304 -0.566781 0.56459 0.599133 -0.567696 0.657934 0.726521 -0.198217 0.659658 0.724149 -0.201143 0.0983273 0.113416 -0.98867 0.100175 0.12034 -0.987666 0.280197 0.45211 -0.846809 0.280538 0.453949 -0.845712 0.413925 0.712762 -0.566248 0.413924 0.711027 -0.568425 0.479149 0.855476 -0.196409 0.480585 0.852995 -0.203562 0.034877 0.132905 -0.990515 0.0346579 0.135706 -0.990143 0.0980225 0.515135 -0.851486 0.0979144 0.515872 -0.851052 0.144182 0.807652 -0.57176 0.144388 0.807019 -0.572602 0.166276 0.965361 -0.201071 0.16706 0.964645 -0.203839 -0.564686 0.145613 -0.812359 -0.0363165 0.97845 -0.203263 -0.0363343 0.978346 -0.203764 -0.102534 0.812762 -0.573503 -0.102551 0.811891 -0.574732 -0.15101 0.513864 -0.844476 -0.150917 0.51175 -0.845776 -0.174471 0.134418 -0.975444 -0.174117 0.131015 -0.975971 -0.102269 0.978796 -0.177484 -0.10277 0.978512 -0.178751 -0.289076 0.815565 -0.501287 -0.29027 0.81315 -0.50451 -0.426691 0.520274 -0.739764 -0.42767 0.51439 -0.743304 -0.45348 0.417381 -0.787495 -0.420686 0.136024 -0.896951 -0.153705 0.97925 -0.132075 -0.155122 0.978806 -0.133704 -0.43494 0.819422 -0.373329 -0.43847 0.815597 -0.377552 -0.643706 0.52966 -0.552361 -0.647147 0.520301 -0.557215 -0.749325 0.159185 -0.642784 -0.749808 0.144109 -0.645771 -0.186072 0.979846 -0.0726559 -0.188555 0.979266 -0.0740609 -0.527359 0.824417 -0.205497 -0.533582 0.819474 -0.20917 -0.783178 0.541851 -0.30501 -0.789677 0.529722 -0.309524 -0.916861 0.178932 -0.35686 -0.919104 0.159211 -0.360416 -1.10203e-07 0.978992 -0.2039 -1.10203e-07 0.978992 -0.2039 -3.1227e-07 0.8162 -0.577769 -1.56137e-07 0.816194 -0.577778 -2.31212e-07 0.517657 -0.855588 -6.02313e-07 0.517679 -0.855575 -5.71624e-07 0.133047 -0.99111 -5.71624e-07 0.133047 -0.99111 -8.81665e-07 0.97899 -0.20391 -1.03598e-06 0.978992 -0.2039 -2.40656e-06 0.81618 -0.577797 -2.91203e-06 0.8162 -0.577769 -3.56535e-06 0.517628 -0.855606 -4.07631e-06 0.517657 -0.855588 -3.96535e-06 0.132986 -0.991118 -4.87678e-06 0.133047 -0.99111 -0.191426 0.98146 0.00963064 -0.201669 0.979448 0.00321537 -0.550994 0.832945 -0.051074 -0.559611 0.826772 -0.0573003 -0.824964 0.555643 -0.103418 -0.830471 0.546236 -0.109289 -0.971389 0.192302 -0.139371 -0.97275 0.181113 -0.144763 -0.194887 0.975639 0.100731 -0.200334 0.974818 0.0979581 -0.554668 0.829372 0.0669757 -0.562426 0.824511 0.062115 -0.829958 0.55734 0.0232875 -0.837127 0.546766 0.0163071 -0.979399 0.200553 -0.0235897 -0.982318 0.184368 -0.032559 0.413499 0.13562 -0.900347 0.845353 0.160392 -0.509562 0.891738 0.297123 -0.341352 0.188486 0.979157 -0.0756612 0.185585 0.979767 -0.0749371 0.533075 0.818676 -0.213544 0.525656 0.823892 -0.211866 0.788214 0.528344 -0.31555 0.780012 0.541063 -0.314377 0.913492 0.178612 -0.365555 0.152966 0.978781 -0.136344 0.151197 0.979217 -0.135183 0.432354 0.8154 -0.384959 0.427796 0.819131 -0.382118 0.638097 0.519862 -0.567957 0.632905 0.528999 -0.565324 0.739365 0.143457 -0.657845 0.736314 0.158182 -0.657891 0.0999701 0.9785 -0.180399 0.0991696 0.978773 -0.179355 0.28236 0.813057 -0.509129 0.280277 0.815389 -0.506542 0.416053 0.514175 -0.750016 0.413583 0.51986 -0.747459 0.441323 0.412622 -0.796854 0.557663 0.145084 -0.81729 0.0347207 0.978402 -0.203777 0.0345793 0.978496 -0.203346 0.0980359 0.812262 -0.574995 0.097662 0.813053 -0.57394 0.144376 0.512255 -0.846611 0.143878 0.514179 -0.845529 0.166693 0.131185 -0.977243 0.1662 0.134298 -0.976904 -0.191548 0.425119 0.884637 -0.191527 0.425119 0.884642 -0.435521 0.389901 0.811356 -0.548596 0.365448 0.751991 -0.82686 0.247034 0.505249 -0.787696 0.266841 0.555276 -0.601464 0.346034 0.72007 -0.980063 0.0860585 0.179081 -0.980064 0.0860577 0.179079 -0.893454 0.194546 0.404835 -0.191531 0.729074 0.657089 -0.191542 0.729073 0.657087 -0.548269 0.621228 0.55989 -0.548265 0.62123 0.559892 -0.826515 0.418149 0.376863 -0.826512 0.418151 0.376865 -0.980063 0.147589 0.133017 -0.980063 0.147588 0.133016 -0.191541 0.923914 0.331201 -0.191543 0.923914 0.331201 -0.548266 0.78725 0.28221 -0.548265 0.78725 0.28221 -0.826514 0.529898 0.189956 -0.826514 0.529898 0.189956 -0.980063 0.187032 0.0670465 -0.980064 0.18703 0.0670454 0.200562 0.974529 0.100345 0.978984 0.201597 -0.030818 0.982645 0.183757 -0.0253489 0.89514 0.445767 0.00395618 0.836209 0.54841 0.000354735 0.194872 0.97589 0.0983078 0.441596 0.893745 0.0788245 0.561286 0.826298 0.0467952 0.607597 0.792206 0.056887 0.791876 0.609929 0.0303241 0.202607 0.979228 0.00797363 0.190904 0.981597 0.00481159 0.560399 0.82655 -0.0526152 0.550344 0.833072 -0.0557802 0.831184 0.546071 -0.104591 0.824237 0.555827 -0.108115 0.973467 0.181026 -0.139971 0.970627 0.192609 -0.14417 -0.258429 0.523963 -0.811589 -0.705546 0.361693 0.609412 -0.980622 0.0667024 0.184204 -0.965637 0.172121 0.19473 -0.965637 0.132647 0.223495 -0.965637 0.132647 0.223496 -0.965637 0.0884882 0.244367 -0.896327 0.143727 0.419453 -0.965637 0.231653 -0.117826 -0.965637 0.249607 -0.0724021 -0.965637 0.249606 -0.0724017 -0.965637 0.258744 -0.0244214 -0.965638 0.258741 -0.0244212 -0.965638 0.258741 0.0244211 -0.965637 0.258744 0.0244215 -0.965637 0.249606 0.0724016 -0.965637 0.249607 0.0724022 -0.705548 0.469327 0.530975 -0.965637 0.205517 0.159088 -0.965637 0.205517 0.159088 -0.705549 0.560384 0.433786 -0.705547 0.560386 0.433787 -0.705534 0.680621 -0.197424 -0.705534 0.70554 -0.0665917 -0.705537 0.705537 -0.0665916 -0.705537 0.705537 0.0665914 -0.705534 0.70554 0.0665919 -0.705534 0.680621 0.197425 -0.705549 0.680607 0.19742 -0.705546 0.631653 -0.321278 -0.965637 0.205517 -0.159088 -0.965636 0.205517 -0.159088 -0.705545 0.560387 -0.433788 -0.705548 0.560385 -0.433786 -0.257755 0.328972 0.908482 -0.194311 0.331546 0.923212 -0.440702 0.30563 0.844021 -0.705546 0.241283 0.666323 -0.607305 0.26564 0.748743 -0.792042 0.207849 0.573993 -0.965637 0.172122 0.194731 -0.705546 0.469328 0.530976 -0.705546 0.361693 0.609412 0.304257 0.48619 0.819175 -0.258652 0.445354 0.857181 -0.258763 0.825596 0.501431 -0.257737 0.764048 0.59144 -0.257746 0.764047 0.591439 -0.258771 0.692337 0.673578 0.122978 0.657244 0.743577 -0.25813 0.62609 0.735785 -0.258429 0.523964 0.811589 -0.965636 0.231653 0.117826 -0.965637 0.231653 0.117826 -0.705547 0.631652 0.321277 -0.705548 0.631651 0.321277 0.122976 0.884564 0.449916 -0.258121 0.869214 0.42171 -0.25842 0.917005 0.303844 0.304255 0.91488 0.265375 -0.258667 0.941435 0.216315 -0.25777 0.961931 0.0907909 -0.257749 0.961937 0.0907923 -0.257749 0.961937 -0.0907914 -0.25777 0.961931 -0.0907918 -0.965636 0.231653 -0.117826 -0.705549 0.631651 -0.321277 -0.705549 0.680607 -0.19742 0.304254 0.91488 -0.265375 -0.258667 0.941435 -0.216315 -0.258771 0.692337 -0.673578 -0.257745 0.764047 -0.591439 -0.257737 0.764049 -0.59144 -0.258763 0.825597 -0.50143 0.122973 0.884564 -0.449916 -0.258121 0.869215 -0.42171 -0.25842 0.917005 -0.303844 -0.965637 0.172122 -0.194731 -0.965637 0.172121 -0.19473 -0.705548 0.469326 -0.530975 -0.705546 0.469328 -0.530977 0.122978 0.657244 -0.743577 -0.25813 0.62609 -0.735785 -0.258646 0.445355 -0.857182 0.304254 0.48619 -0.819176 -0.705546 0.361693 -0.609412 -0.705546 0.361693 -0.609412 -0.965636 0.132648 -0.223497 -0.965637 0.132647 -0.223495 -0.965636 0.0884889 -0.244369 -0.965637 0.0884882 -0.244367 -0.705546 0.241283 -0.666323 -0.70555 0.241282 -0.66632 -0.257748 0.328972 -0.908484 -0.257737 0.328974 -0.908487 0.964318 0.209354 0.162058 0.964318 0.120584 0.235693 0.964318 0.120584 0.235692 0.698454 0.325957 0.637113 0.698461 0.565909 0.438063 0.980384 0.188619 0.057182 0.965494 0.246862 0.0829508 0.964318 0.209354 0.162058 0.698454 0.565915 0.438067 0.698453 0.325958 0.637114 0.253014 0.440648 0.861286 0.895035 0.426814 0.129394 0.790241 0.586439 0.177786 0.704072 0.676604 0.215614 0.604726 0.762178 0.231063 0.438537 0.860059 0.260737 0.253008 0.440649 0.861287 0.253006 0.765036 0.592205 0.253009 0.765036 0.592205 0.256547 0.922802 0.287438 0.193133 0.938972 0.284661 -0.193126 0.938973 -0.284661 -0.25654 0.922803 -0.287439 -0.438537 0.860059 -0.260737 -0.604754 0.762158 -0.231057 -0.704084 0.676594 -0.215609 -0.790241 0.586439 -0.177786 -0.894989 0.426902 -0.12942 -0.965494 0.24686 -0.0829544 -0.980391 0.188584 -0.0571717 -0.253002 0.765037 -0.592206 -0.252999 0.765038 -0.592206 -0.698471 0.565901 -0.438057 -0.698469 0.565903 -0.438058 -0.964318 0.209352 -0.162057 -0.964317 0.209356 -0.162059 -0.253001 0.44065 -0.861289 -0.252995 0.440651 -0.86129 -0.698468 0.325952 -0.637101 -0.698475 0.325948 -0.637095 -0.964317 0.120585 -0.235695 -0.964318 0.120584 -0.235693 0.965637 0.0884881 0.244367 0.792052 0.207845 -0.573981 0.705529 0.241289 0.66634 0.257757 0.328972 0.908482 -0.122981 0.657244 0.743577 0.257762 0.328971 0.90848 0.258659 0.445353 0.857179 -0.304265 0.486188 0.819173 0.258437 0.523962 0.811587 0.258137 0.626089 0.735784 -0.304263 0.914877 0.265374 0.258779 0.692335 0.673577 0.257752 0.764045 0.591438 0.257744 0.764047 0.591439 0.25877 0.825595 0.50143 -0.12298 0.884563 0.449915 0.258128 0.869213 0.421709 0.258427 0.917003 0.303844 -0.122977 0.884564 -0.449916 0.258674 0.941433 0.216315 0.257777 0.961929 0.0907916 0.257756 0.961935 0.0907913 0.257756 0.961935 -0.0907921 0.257777 0.961929 -0.0907907 0.258675 0.941433 -0.216315 -0.304262 0.914878 -0.265374 0.258427 0.917003 -0.303844 0.258128 0.869213 -0.42171 0.258653 0.445354 -0.85718 -0.304263 0.486188 -0.819173 0.25877 0.825595 -0.501429 0.257744 0.764047 -0.591439 0.257753 0.764045 -0.591438 0.258779 0.692335 -0.673577 -0.122981 0.657244 -0.743577 0.258137 0.626089 -0.735784 0.258436 0.523962 -0.811588 0.257756 0.328972 -0.908482 0.194301 0.331546 -0.923214 0.4407 0.30563 -0.844022 0.705532 0.241288 0.666337 0.705532 0.3617 0.609424 0.705531 0.3617 0.609424 0.705532 0.469337 0.530987 0.705533 0.469336 0.530986 0.705534 0.560396 0.433795 0.705533 0.560396 0.433796 0.705533 0.631665 0.321284 0.705534 0.631663 0.321283 0.705534 0.680621 0.197425 0.70552 0.680635 0.197428 0.70552 0.705555 0.0665931 0.705523 0.705552 0.066593 0.705523 0.705552 -0.0665928 0.70552 0.705555 -0.0665933 0.70552 0.680635 -0.197428 0.705534 0.680621 -0.197424 0.705534 0.631663 -0.321283 0.705532 0.631666 -0.321284 0.705531 0.560398 -0.433797 0.705534 0.560396 -0.433795 0.705534 0.469336 -0.530986 0.705532 0.469337 -0.530987 0.705532 0.3617 -0.609425 0.705532 0.3617 -0.609424 0.705532 0.241288 -0.666337 0.607277 0.265647 -0.748763 0.965637 0.0884882 0.244367 0.965637 0.132647 0.223496 0.965637 0.132647 0.223495 0.965637 0.172121 0.19473 0.965637 0.172122 0.194731 0.965637 0.205517 0.159088 0.965637 0.205517 0.159088 0.965636 0.231653 0.117826 0.965637 0.231653 0.117826 0.965637 0.249607 0.0724021 0.965637 0.249606 0.0724017 0.965637 0.258744 0.0244214 0.965638 0.258741 0.0244212 0.965638 0.258741 -0.0244211 0.965637 0.258744 -0.0244215 0.965637 0.249606 -0.0724016 0.965637 0.249607 -0.0724022 0.965637 0.231653 -0.117826 0.965637 0.231653 -0.117826 0.965637 0.205517 -0.159088 0.965636 0.205517 -0.159088 0.965637 0.172122 -0.194731 0.965637 0.172121 -0.19473 0.965637 0.132647 -0.223495 0.965636 0.132648 -0.223497 0.965636 0.0884888 -0.244369 0.965637 0.0884883 -0.244367 -0.200554 0.97453 -0.100346 -0.978991 0.20156 0.0308215 -0.982644 0.183758 0.0253643 -0.895094 0.445859 -0.00395306 -0.836209 0.54841 -0.000354735 -0.194865 0.975891 -0.0983083 -0.441596 0.893745 -0.0788245 -0.561303 0.826286 -0.0467903 -0.607625 0.792185 -0.0568837 -0.791876 0.609929 -0.0303241 -0.202607 0.979228 -0.00797692 -0.190897 0.981598 -0.00481263 -0.560416 0.826538 0.052618 -0.550361 0.833061 0.055783 -0.831185 0.546069 0.104591 -0.824237 0.555827 0.108116 -0.97346 0.181065 0.13997 -0.97063 0.192608 0.144155 0.980056 0.187066 -0.0670585 0.980055 0.187068 -0.0670595 0.826532 0.529873 -0.189947 0.826534 0.52987 -0.189946 0.548248 0.787261 -0.282214 0.548248 0.787261 -0.282214 0.19155 0.923913 -0.3312 0.191548 0.923913 -0.3312 0.980055 0.147618 -0.133043 0.980056 0.147617 -0.133042 0.826535 0.418127 -0.376843 0.826532 0.418129 -0.376845 0.548247 0.621238 -0.559901 0.548252 0.621236 -0.559898 0.191549 0.729072 -0.657087 0.19155 0.729072 -0.657087 0.191539 0.425118 -0.88464 0.191551 0.425118 -0.884637 0.435521 0.389902 -0.811356 0.548578 0.365454 -0.752001 0.601436 0.346044 -0.720089 0.826534 0.243808 -0.507344 0.787142 0.27232 -0.553398 0.979735 0.079846 -0.183698 0.96467 0.114115 -0.237465 -0.420685 0.136041 0.896949 -0.174033 0.134425 0.975522 -0.174554 0.131022 0.975892 -0.150697 0.513825 0.844556 -0.151238 0.511711 0.845742 -0.102341 0.812745 0.573561 -0.102752 0.811874 0.57472 -0.036249 0.978448 0.203287 -0.0364059 0.978343 0.203763 -0.564684 0.145628 0.812357 -0.453477 0.417394 0.78749 -0.425904 0.520191 0.740275 -0.428502 0.514308 0.742881 -0.288604 0.815519 0.501634 -0.290804 0.813103 0.504278 -0.102112 0.978789 0.177612 -0.102959 0.978505 0.17868 -0.748004 0.15913 0.644335 -0.751126 0.144072 0.644247 -0.64279 0.529546 0.553535 -0.648162 0.52018 0.556147 -0.434419 0.819348 0.374096 -0.439143 0.815524 0.376928 -0.153539 0.979239 0.132347 -0.155364 0.978795 0.133501 -0.915911 0.178859 0.359329 -0.920065 0.159141 0.357988 -0.782571 0.541697 0.306835 -0.790452 0.529577 0.30779 -0.527054 0.824322 0.206656 -0.534135 0.81938 0.208124 -0.185985 0.979832 0.0730635 -0.188764 0.979252 0.073707 0.191433 0.981459 -0.00962646 0.201669 0.979448 -0.00321537 0.550977 0.832956 0.0510712 0.559594 0.826784 0.0572974 0.824964 0.555643 0.103418 0.830472 0.546234 0.10929 0.971388 0.192302 0.139372 0.972753 0.181079 0.14478 0.194895 0.975638 -0.100731 0.200342 0.974817 -0.0979577 0.554651 0.829383 -0.0669777 0.562409 0.824523 -0.062117 0.829976 0.557313 -0.023284 0.837127 0.546765 -0.0163201 0.979392 0.200587 0.0235707 0.982318 0.184368 0.0325587 4.87678e-06 0.133047 0.99111 3.96535e-06 0.132986 0.991118 4.0763e-06 0.517671 0.85558 3.56533e-06 0.517641 0.855598 2.91205e-06 0.816194 0.577778 2.40659e-06 0.816174 0.577806 1.03598e-06 0.978992 0.2039 8.81665e-07 0.97899 0.20391 5.71627e-07 0.133065 0.991107 3.03789e-07 0.133047 0.99111 3.71103e-07 0.517665 0.855583 4.62419e-07 0.517671 0.85558 3.12274e-07 0.816194 0.577778 3.12274e-07 0.816194 0.577778 1.10203e-07 0.978992 0.2039 1.10203e-07 0.978992 0.2039 0.919163 0.179093 0.350806 0.845348 0.160383 0.509572 0.889457 0.285863 0.35658 0.787424 0.528496 0.317262 0.780633 0.541214 0.31257 0.532504 0.818777 0.214578 0.525964 0.823992 0.21071 0.188271 0.979171 0.0760093 0.185672 0.979781 0.0745317 0.151365 0.979227 0.134918 0.152722 0.978792 0.136538 0.428316 0.819208 0.381371 0.431683 0.815472 0.385559 0.633823 0.529111 0.56419 0.637086 0.519971 0.568991 0.737641 0.158223 0.656393 0.340051 0.575467 0.743776 0.557659 0.145084 0.817292 0.738042 0.143505 0.659318 0.14407 0.512265 0.846657 0.144179 0.514202 0.845464 0.0978444 0.812278 0.575006 0.0978466 0.813069 0.573886 0.0346529 0.978404 0.203777 0.0346436 0.978499 0.203324 0.099323 0.978781 0.17923 0.0997861 0.978507 0.180465 0.28074 0.815435 0.506213 0.281839 0.813102 0.509345 0.414358 0.519929 0.746982 0.415243 0.514242 0.750419 0.480796 0.134289 0.866488 0.166617 0.134308 0.976832 0.166273 0.131213 0.977311 -0.133733 0.093674 0.98658 -0.134028 0.0970673 0.986212 -0.379683 0.377509 0.844587 -0.379646 0.378449 0.844183 -0.564261 0.600299 0.566789 -0.564589 0.599117 0.567713 -0.657937 0.726519 0.198217 -0.659647 0.724166 0.201119 -0.0983379 0.113435 0.988667 -0.100185 0.120356 0.987663 -0.280194 0.452097 0.846817 -0.280536 0.453945 0.845714 -0.413921 0.712754 0.566261 -0.413921 0.711027 0.568429 -0.47915 0.855481 0.196389 -0.48059 0.852992 0.203562 -0.0348773 0.132905 0.990515 -0.0346566 0.135727 0.99014 -0.0980206 0.515148 0.851478 -0.0979165 0.515858 0.85106 -0.144183 0.807643 0.571773 -0.144388 0.807016 0.572606 -0.166276 0.965361 0.201071 -0.167057 0.964648 0.203829 -5.71624e-07 0.133047 0.99111 -3.03793e-07 0.133065 0.991107 -3.71104e-07 0.517671 0.85558 -4.62421e-07 0.517665 0.855583 -3.12274e-07 0.816194 0.577778 -3.12274e-07 0.816194 0.577778 -1.10203e-07 0.978992 0.2039 -1.10203e-07 0.978992 0.2039 -4.87667e-06 0.132986 0.991118 -3.96541e-06 0.133047 0.99111 -4.07632e-06 0.517641 0.855598 -3.5653e-06 0.517671 0.85558 -2.91213e-06 0.816174 0.577806 -2.40649e-06 0.816194 0.577778 -1.03602e-06 0.97899 0.20391 -8.81621e-07 0.978992 0.2039 -0.697526 0.688576 0.198295 -0.697616 0.688145 0.199472 -0.596414 0.571459 0.563671 -0.595705 0.569193 0.566704 -0.401373 0.364394 0.840307 -0.398948 0.359491 0.843568 -0.143088 0.100059 0.984639 -0.138723 0.0923825 0.986013 -0.696291 0.690157 0.197135 -0.696373 0.689729 0.198339 -0.593901 0.576911 0.560764 -0.59318 0.574694 0.563795 -0.399119 0.373985 0.837161 -0.396667 0.369102 0.840488 -0.142189 0.112952 0.983374 -0.137826 0.105322 0.984841 0.0114823 0.133274 0.991013 0.0112259 0.132977 0.991055 0.0321584 0.517432 0.85512 0.0320962 0.517374 0.855157 0.0474927 0.815186 0.577249 0.0476021 0.815249 0.577151 0.0549063 0.977449 0.203907 0.055195 0.977497 0.203599 0.0581549 0.132175 0.989519 0.0558919 0.128268 0.990163 0.161192 0.501932 0.849754 0.160545 0.500937 0.850463 0.236722 0.785591 0.571673 0.23741 0.786369 0.570315 0.273321 0.940018 0.204112 0.274808 0.940558 0.199577 0.120821 0.110191 0.98654 0.114771 0.10497 0.98783 0.334409 0.420794 0.84327 0.332807 0.419532 0.844531 0.492387 0.661053 0.566183 0.494004 0.662002 0.563661 0.571387 0.795225 0.202815 0.574065 0.795337 0.194648 -0.655589 0.729208 0.196108 -0.656535 0.727903 0.197784 -0.558422 0.612536 0.559432 -0.559047 0.61053 0.560999 -0.374302 0.400667 0.83628 -0.374682 0.39806 0.837354 -0.131587 0.126408 0.983212 -0.131955 0.123174 0.983573 -0.476626 0.857598 0.193271 -0.4772 0.856525 0.196585 -0.407404 0.726384 0.553523 -0.407411 0.723809 0.556881 -0.274684 0.482171 0.831902 -0.274123 0.477932 0.834529 -0.097411 0.159995 0.9823 -0.0965173 0.154338 0.983293 -0.164998 0.967049 0.193888 -0.165257 0.966808 0.194864 -0.140849 0.820646 0.553807 -0.14113 0.819842 0.554925 -0.0947739 0.546745 0.831918 -0.0950929 0.545214 0.832886 -0.0333409 0.184485 0.98227 -0.0337391 0.182331 0.982658 0.696142 0.68996 0.198348 0.696534 0.689914 0.197129 0.592487 0.575402 0.563801 0.594609 0.576199 0.560745 0.395477 0.370268 0.840535 0.400304 0.372795 0.837127 0.136185 0.106959 0.984893 0.143839 0.111299 0.983322 0.697374 0.688379 0.199509 0.69776 0.688341 0.198286 0.594999 0.569915 0.566722 0.597139 0.570748 0.563623 0.397758 0.360658 0.843632 0.402548 0.363196 0.840264 0.137068 0.094035 0.986088 0.14475 0.0983941 0.984564 0 0.980487 0.196586 7.58292e-09 0.980487 0.196583 2.15773e-08 0.828912 0.559379 1.03966e-08 0.828909 0.559384 -1.10513e-08 0.549196 0.835694 4.23708e-08 0.549218 0.835679 1.4239e-08 0.184569 0.98282 5.21513e-08 0.184587 0.982816 0 0.980487 0.196583 -9.9409e-09 0.980487 0.196586 -2.82867e-08 0.828909 0.559384 -1.36296e-08 0.828912 0.559379 1.44857e-08 0.549218 0.835679 -5.5543e-08 0.549196 0.835694 -1.86683e-08 0.184587 0.982816 -6.83653e-08 0.184569 0.98282 0.0544176 0.979016 0.196382 0.0545023 0.97903 0.19629 0.0462668 0.827947 0.558895 0.0463976 0.828016 0.558781 0.0309374 0.548799 0.835382 0.0311412 0.548951 0.835274 0.0107941 0.184365 0.982799 0.0110602 0.184576 0.982756 0.271108 0.942521 0.195332 0.271679 0.942702 0.193658 0.231263 0.798734 0.555465 0.232259 0.799739 0.5536 0.155325 0.530521 0.83332 0.156848 0.532509 0.831765 0.0541323 0.176347 0.982838 0.0562369 0.179207 0.982203 0.568444 0.798728 0.197245 0.569953 0.798697 0.192971 0.48496 0.673815 0.557482 0.487766 0.675204 0.553338 0.325656 0.44375 0.834886 0.329826 0.446498 0.831778 0.113321 0.141648 0.983409 0.118673 0.1453 0.982245 1.23875e-05 0.754745 -0.656018 -7.08107e-06 0.754712 -0.656057 0.434225 -0.859454 -0.26979 0.101602 -0.866408 0.488891 0.0779458 -0.991468 0.104483 0.0414908 -0.953391 -0.298873 0.0989865 -0.870167 0.482712 0.222483 -0.858408 0.46221 0.21858 -0.860518 0.460143 0.35239 -0.834055 0.424468 0.344944 -0.843489 0.411753 0.461948 -0.813468 0.353376 0.456398 -0.816952 0.35255 0.561053 -0.776569 0.286636 0.549914 -0.788849 0.274429 0.633194 -0.749939 0.191462 0.628434 -0.753674 0.192473 0.697892 -0.708101 0.107421 0.687064 -0.719641 0.100299 0.739951 -0.67256 -0.0116251 0.735999 -0.67689 -0.0112124 0.769543 -0.626409 -0.124158 0.764191 -0.632689 -0.125371 0.07667 -0.991903 0.101246 0.15877 -0.983525 0.0864396 0.157481 -0.983801 0.0856461 0.245022 -0.967403 0.0639926 0.242664 -0.96823 0.0603747 0.31623 -0.948427 0.022007 0.314991 -0.948846 0.0217525 0.379828 -0.924893 -0.0174088 0.377208 -0.925918 -0.0197753 0.425853 -0.902077 -0.0700512 0.42494 -0.902518 -0.0699181 0.465719 -0.877037 -0.117947 0.463413 -0.878103 -0.119095 0.492207 -0.851156 -0.18239 0.491329 -0.85168 -0.18231 0.510661 -0.824426 -0.244022 0.580569 -0.779424 -0.235451 0.0417467 -0.95357 -0.298263 0.0697347 -0.950291 -0.303453 0.0711394 -0.950453 -0.302619 0.0977926 -0.946006 -0.309045 0.103146 -0.947691 -0.302064 0.123586 -0.941713 -0.312896 0.127157 -0.941454 -0.312243 0.141291 -0.936598 -0.320657 0.152142 -0.937551 -0.31281 0.161338 -0.932733 -0.322457 0.165054 -0.931883 -0.323034 0.16993 -0.929025 -0.32869 0.181186 -0.928317 -0.324651 0.184069 -0.925466 -0.331105 0.187606 -0.924581 -0.331594 0.18866 -0.923183 -0.334874 0.192874 -0.922316 -0.334863 0.00940827 -0.957461 -0.288408 0.00957257 -0.959495 -0.281563 0.00632568 -0.99386 0.11046 0.00641122 -0.993378 0.114716 0.00221511 -0.870804 0.491625 0.00224121 -0.870107 0.492859 0.0152256 -0.954014 -0.299376 0.0154499 -0.957403 -0.288341 0.0102651 -0.994565 0.103614 0.0103654 -0.993822 0.110505 0.00359908 -0.871921 0.489633 0.00362655 -0.87079 0.491641 0.768492 -0.605391 -0.207177 0.434739 -0.852795 -0.289384 0.58137 -0.770253 -0.262142 0.71168 -0.669277 -0.213495 0.711708 -0.669831 -0.211656 0.711644 -0.669901 -0.211649 0.19255 -0.929516 -0.314524 0.276845 -0.914599 -0.294729 0.277264 -0.921105 -0.273296 0.296558 -0.917525 -0.264956 0.277903 -0.927005 -0.251857 -0.763643 -0.629838 -0.141961 -0.497277 -0.832682 -0.243634 -0.169143 -0.933677 -0.315653 -0.764534 -0.628975 -0.140988 -0.746627 -0.663032 -0.0541924 -0.747146 -0.662596 -0.0523405 -0.710532 -0.701455 0.0557282 -0.714384 -0.696992 0.0621172 -0.651858 -0.741519 0.158842 -0.651736 -0.740696 0.163127 -0.573245 -0.778409 0.255872 -0.576014 -0.772747 0.266589 -0.476374 -0.810822 0.340051 -0.474777 -0.809967 0.344297 -0.360525 -0.837964 0.40968 -0.360459 -0.833618 0.41851 -0.241068 -0.856227 0.456905 -0.239465 -0.855901 0.458356 -0.112023 -0.866123 0.487116 -0.111594 -0.8651 0.489029 -0.497046 -0.832773 -0.243791 -0.486298 -0.851831 -0.194677 -0.486183 -0.851843 -0.19491 -0.465995 -0.874923 -0.131756 -0.465243 -0.875201 -0.132558 -0.426832 -0.901185 -0.0753638 -0.426766 -0.901178 -0.0758164 -0.378775 -0.92533 -0.0171665 -0.378169 -0.925552 -0.0184721 -0.313529 -0.949181 0.0274692 -0.31363 -0.949161 0.027001 -0.238724 -0.968447 0.0715696 -0.238544 -0.968593 0.0701772 -0.157901 -0.982934 0.0943779 -0.158161 -0.98292 0.0940936 -0.0720443 -0.990714 0.115306 -0.072245 -0.99086 0.11392 -0.16716 -0.93372 -0.316582 -0.165985 -0.935683 -0.311363 -0.164701 -0.935283 -0.313241 -0.161737 -0.938944 -0.303686 -0.153084 -0.938183 -0.310447 -0.145958 -0.942707 -0.299998 -0.144674 -0.941417 -0.304638 -0.132443 -0.947979 -0.289473 -0.124294 -0.945103 -0.302212 -0.105911 -0.951356 -0.289316 -0.106526 -0.949762 -0.294287 -0.0812861 -0.95683 -0.27905 -0.0786051 -0.953468 -0.291067 -0.0504928 -0.957838 -0.282837 -0.0522313 -0.957141 -0.284873 -0.0205684 -0.960695 -0.276843 -0.0211032 -0.959289 -0.281636 0.276201 -0.919306 -0.280337 0.752434 -0.563333 -0.341321 0.75492 -0.556081 -0.347663 0.71369 -0.532706 -0.45483 0.725408 -0.507235 -0.465291 0.66128 -0.493817 -0.564671 0.660271 -0.48583 -0.572724 0.581209 -0.469242 -0.664837 0.586223 -0.442374 -0.678711 0.48712 -0.436133 -0.756638 0.482843 -0.429291 -0.763264 0.37063 -0.419928 -0.828429 0.368964 -0.398182 -0.839831 0.252964 -0.399352 -0.881208 0.248022 -0.396694 -0.883809 0.124358 -0.393826 -0.910734 0.120995 -0.382019 -0.9162 0.708194 -0.657698 -0.256701 0.763928 -0.572381 -0.297983 0.519549 -0.815928 -0.253635 0.503942 -0.804158 -0.315235 0.505897 -0.801697 -0.318356 0.481764 -0.787566 -0.384244 0.490709 -0.778563 -0.391208 0.449395 -0.770095 -0.452768 0.449836 -0.767336 -0.456993 0.399955 -0.756652 -0.517217 0.404958 -0.747709 -0.526252 0.339053 -0.743763 -0.576072 0.33784 -0.741485 -0.57971 0.263606 -0.735029 -0.624695 0.264447 -0.727692 -0.632876 0.185499 -0.728836 -0.659081 0.183454 -0.727912 -0.660673 0.0992782 -0.725563 -0.680957 0.0980436 -0.721232 -0.68572 0.195818 -0.949051 -0.246897 0.19481 -0.948261 -0.250701 0.194375 -0.948505 -0.250115 0.18913 -0.945537 -0.264935 0.188314 -0.945875 -0.264306 0.17766 -0.943493 -0.279747 0.177471 -0.943779 -0.278902 0.163021 -0.940917 -0.296815 0.161374 -0.942043 -0.294133 0.140865 -0.940518 -0.309164 0.141066 -0.940852 -0.308054 0.11609 -0.939011 -0.323701 0.115625 -0.939917 -0.321227 0.0882962 -0.939932 -0.329744 0.0886022 -0.940011 -0.329438 0.0579857 -0.939568 -0.337417 0.0580394 -0.939696 -0.337049 -0.169591 -0.953191 -0.250332 -0.167161 -0.953516 -0.250729 -0.49802 -0.834327 -0.236378 -0.496741 -0.834986 -0.236744 -0.76567 -0.613437 -0.193504 -0.765343 -0.613793 -0.193669 -0.169121 -0.940047 -0.296157 -0.168042 -0.940173 -0.296372 -0.497573 -0.825543 -0.26627 -0.497008 -0.825821 -0.266464 -0.765448 -0.61034 -0.203896 -0.765318 -0.610478 -0.203973 0.0248727 -0.942133 -0.334316 0.0247463 -0.941192 -0.336964 0.0168425 -0.727338 -0.686073 0.0167527 -0.726194 -0.687286 0.00595681 -0.388961 -0.921235 0.00592342 -0.388436 -0.921456 0.0152331 -0.942936 -0.332626 0.0151643 -0.942354 -0.334273 0.0103199 -0.72822 -0.685266 0.010272 -0.727488 -0.686044 0.00365001 -0.389326 -0.921093 0.00363378 -0.389014 -0.921225 -0.0655262 -0.389242 -0.918802 -0.0391654 -0.728031 -0.684425 -0.00608391 -0.943071 -0.332537 -0.0651579 -0.389813 -0.918586 -0.160457 -0.393591 -0.905174 -0.158427 -0.394848 -0.904984 -0.301721 -0.397971 -0.866362 -0.295504 -0.410003 -0.862888 -0.426727 -0.423749 -0.798962 -0.420485 -0.427215 -0.800425 -0.540664 -0.436446 -0.719165 -0.526845 -0.457528 -0.716312 -0.622622 -0.477099 -0.620256 -0.615462 -0.48025 -0.624953 -0.697107 -0.494485 -0.51916 -0.678488 -0.518306 -0.520589 -0.739112 -0.544614 -0.39637 -0.731655 -0.549822 -0.402959 -0.773036 -0.570777 -0.27682 -0.755698 -0.590163 -0.283953 -0.0391729 -0.728022 -0.684434 -0.103438 -0.73071 -0.674806 -0.102782 -0.73101 -0.674582 -0.199387 -0.732653 -0.650742 -0.196529 -0.736047 -0.647774 -0.282388 -0.745477 -0.603756 -0.279757 -0.746446 -0.603784 -0.358655 -0.752144 -0.552852 -0.351096 -0.758496 -0.549013 -0.410771 -0.771057 -0.486559 -0.407321 -0.771949 -0.488042 -0.45963 -0.780775 -0.423238 -0.448099 -0.788432 -0.421405 -0.484018 -0.804488 -0.344276 -0.479538 -0.806084 -0.346803 -0.505166 -0.818622 -0.27325 -0.493514 -0.824979 -0.275415 -0.00644019 -0.942864 -0.333114 -0.0289808 -0.943689 -0.329562 -0.0296294 -0.94355 -0.329902 -0.0625295 -0.944536 -0.3224 -0.0645466 -0.943491 -0.325053 -0.0924935 -0.946184 -0.310131 -0.0938597 -0.945988 -0.310318 -0.117576 -0.948058 -0.295571 -0.121127 -0.946868 -0.297941 -0.137899 -0.950099 -0.279815 -0.138981 -0.950033 -0.279501 -0.152434 -0.952575 -0.263374 -0.154892 -0.951985 -0.264069 -0.163466 -0.955632 -0.245044 -0.16366 -0.955618 -0.244968 -0.168086 -0.957907 -0.232724 -0.168375 -0.957861 -0.232705 -0.0556225 0.991009 0.121687 -0.166276 0.926614 -0.337252 -0.246942 0.0169109 -0.968883 -0.935112 -0.15534 -0.318487 -0.935112 -0.15534 -0.318488 -0.954817 0.22628 -0.192669 -0.937656 0.314955 -0.146983 -0.887339 0.450976 -0.0961788 -0.790654 0.612119 -0.0132943 -0.68455 -0.0140468 -0.728831 -0.684551 -0.0140427 -0.72883 -0.68455 0.459779 -0.56568 -0.68455 0.459784 -0.565676 -0.244499 0.068483 -0.967228 -0.258488 0.266288 -0.928587 -0.250563 0.54136 -0.802588 -0.240889 0.455658 -0.856941 -0.237766 0.662425 -0.710395 -0.698256 0.7135 0.057925 -0.508582 0.822485 -0.254682 -0.508585 0.822482 -0.254687 -0.186155 0.883089 -0.430697 -0.189928 0.804243 -0.563134 -0.258202 0.933635 0.248308 -0.258198 0.933636 0.24831 -0.620577 0.778698 0.0922658 -0.206988 0.96448 0.164117 -0.126539 0.971453 0.200668 -0.158834 0.98016 0.118568 -0.0691877 0.995175 0.0695711 -0.0923395 0.98603 -0.138634 -0.207918 0.924855 0.318453 -0.258817 0.912412 0.317045 -0.58779 0.765602 0.261452 -0.629337 0.734793 0.253009 -0.809018 0.555761 0.191364 -0.866016 0.473656 0.160204 -0.913537 0.384595 0.132426 -0.994524 0.0988185 0.0340259 -0.987685 0.148795 0.0483564 -0.951051 -0.293281 -0.0974037 -0.965924 -0.244723 -0.0842649 0 0.992545 0.121876 0 0.992545 0.121876 0 0.99026 -0.139229 0 0.99026 -0.139229 0 0.939695 -0.342013 0 0.939695 -0.342013 0 0.819154 -0.573574 0 0.819154 -0.573574 0 0.681983 -0.731368 0 0.681983 -0.731368 0 0.469483 -0.882942 0 0.469483 -0.882942 0 0.275656 -0.961256 0 0.275656 -0.961256 0 0.0174513 -0.999848 0 0.0174513 -0.999848 -0.246943 -0.583183 0.773897 -0.246942 -0.583168 0.773909 -0.220113 0.18454 0.95786 -0.237764 0.0846569 0.967627 -0.257495 -0.217362 0.941515 -0.24973 -0.168142 0.953605 -0.258487 -0.361855 0.895682 -0.151432 0.565424 0.81078 -0.166279 0.522545 0.836241 -0.211855 0.285739 0.934596 -0.0556285 0.855836 0.514248 -0.0556221 0.855845 0.514233 -0.12076 0.689566 0.714084 -0.674661 -0.502778 0.540414 -0.67466 -0.502782 0.540411 -0.70349 -0.13353 0.698048 -0.70349 -0.133531 0.698048 -0.617565 0.259464 0.742491 -0.617563 0.259467 0.742491 -0.425044 0.617248 0.662074 -0.425049 0.617243 0.662076 -0.151972 0.873945 0.461653 -0.151966 0.873948 0.46165 -0.921602 -0.363531 0.135998 -0.921602 -0.36353 0.135998 -0.960986 0.0116652 0.27635 -0.960988 0.011656 0.276346 -0.843606 0.386937 0.372301 -0.843605 0.386939 0.372302 -0.580629 0.704974 0.407286 -0.580634 0.70497 0.407285 -0.207591 0.905316 0.370553 -0.207596 0.905314 0.370554 0.766762 -0.0512071 -0.639886 0.246943 0.0169108 -0.968883 0.228633 0.268355 -0.935795 0.402158 -0.539185 -0.739965 0.255842 0.453858 -0.853556 0.241517 0.541597 -0.805197 0.935115 -0.155327 -0.318488 0.935112 -0.155339 -0.318489 0.935115 0.318478 -0.155342 0.120768 0.983012 -0.13821 0.166276 0.926614 -0.337252 0.177523 0.883036 -0.434434 0.211855 0.80056 -0.560555 0.237767 0.662425 -0.710394 0.958608 0.221958 -0.178343 0.887326 0.451004 -0.0961699 0.69473 0.717518 0.0501779 0.794309 0.607458 0.00828952 0.620577 0.778698 0.0922658 0.0556226 0.991009 0.121687 0.0638147 0.995736 0.0666227 0.158834 0.98016 0.118565 0.109116 0.963792 0.243308 0.250563 0.0675364 -0.965742 0.684553 -0.014033 -0.728828 0.684551 0.459776 -0.565682 0.684553 0.459771 -0.565684 0.508582 0.822485 -0.254681 0.508578 0.822489 -0.254677 0.189016 0.97265 0.135003 0.258202 0.933635 0.248308 0.258194 0.933637 0.24831 0 0.857172 0.515031 0 0.857172 0.515031 0 0.694649 0.719349 0 0.694649 0.719349 0 0.529922 0.848046 0 0.529922 0.848046 0 0.292376 0.956303 0 0.292376 0.956303 0 0.0871563 0.996195 0 0.0871563 0.996195 0 -0.173644 0.984809 0 -0.173644 0.984809 0 -0.374585 0.927192 0 -0.374585 0.927192 0 -0.601822 0.79863 0 -0.601822 0.79863 0.258815 0.913302 0.314475 0.207913 0.923749 0.321653 0.629335 0.735676 0.250436 0.587791 0.764937 0.263389 0.809035 0.555739 0.191356 0.866016 0.473656 0.160205 0.913524 0.384623 0.132436 0.987692 0.147888 0.0509218 0.99452 0.099501 0.0320973 0.965921 -0.245608 -0.0816911 0.951046 -0.292211 -0.100616 0.246945 -0.583161 0.773913 0.57944 -0.535746 0.614187 0.24694 -0.583184 0.773898 0.258487 -0.361855 0.895682 0.252919 -0.217888 0.942633 0.255842 -0.167865 0.952033 0.226044 0.185872 0.956219 0.921591 -0.36356 0.135989 0.921613 -0.3635 0.136007 0.960987 0.0116735 0.276348 0.960987 0.0116662 0.276347 0.843606 0.38694 0.3723 0.843613 0.386924 0.372299 0.580634 0.70497 0.407286 0.580637 0.704967 0.407286 0.207592 0.905315 0.370554 0.225821 0.084905 0.970462 0.211854 0.28574 0.934596 0.155578 0.566598 0.809174 0.160339 0.523066 0.837074 0.12076 0.689566 0.714084 0.0595973 0.915687 0.397449 0.166308 0.882965 0.438993 0.207587 0.905317 0.370553 0.755148 -0.478542 0.448051 0.530689 -0.797634 0.286617 0.70349 -0.133531 0.698048 0.70349 -0.133542 0.698046 0.617567 0.259456 0.742492 0.617562 0.259474 0.74249 0.425053 0.617237 0.662078 0.425046 0.617249 0.662072 0.151976 0.873943 0.461657 0.0556272 0.855834 0.51425 0.0556242 0.855845 0.514233 0.186162 0.883074 -0.430726 0.0691749 0.995173 0.069612 0.0691909 0.995175 0.0695717 0.18903 0.972649 0.134991 0.189016 0.97265 0.135003 0.2582 0.933637 0.248305 0.258196 0.933638 0.248306 0.186152 0.883091 -0.430696 0.508581 0.822485 -0.254682 0.508596 0.822472 -0.254697 0.694752 0.717498 0.0501681 0.694757 0.717493 0.0501658 0 0.997562 0.0697791 0 0.997562 0.0697791 0 0.898785 -0.438389 0 0.898785 -0.438389 0.258818 0.913301 0.314475 0.258816 0.913302 0.314475 0.707116 0.668573 0.230208 0.707118 0.668572 0.230208 -0.2582 0.933637 0.248304 -0.70154 0.704098 0.109944 -0.158792 0.942369 0.294493 -0.322449 0.940679 0.105594 -0.20698 0.96448 0.164125 -0.158823 0.980159 0.118593 -0.206425 0.978454 -0.00413852 -0.0473241 0.987081 0.153074 -0.0461663 0.996499 0.0697047 -0.701549 0.70409 0.109937 -0.602507 0.786234 -0.137194 -0.602503 0.786238 -0.137188 -0.385688 0.856826 -0.34219 -0.385688 0.856826 -0.342191 -0.12528 0.891706 -0.434931 -0.12528 0.891704 -0.434935 0.258198 0.888588 0.379138 0.701545 0.622519 0.34685 0.158791 0.923905 0.348117 0.322447 0.806277 0.495928 0.206975 0.861069 0.464458 0.158819 0.845391 0.50999 0.206421 0.768488 0.605654 0.0473266 0.872072 0.487083 0.0473646 0.873643 0.484258 0.0752557 0.717301 0.692687 0.101896 0.584719 0.804811 0.701542 0.622522 0.34685 0.6025 0.535107 0.592161 0.602504 0.5351 0.592163 0.385687 0.464514 0.797165 0.385683 0.46453 0.797158 0.135519 0.436693 0.889345 0.135535 0.355057 0.924968 -0.258819 0.913301 0.314474 -0.258822 0.9133 0.314474 -0.707111 0.668579 0.23021 -0.707109 0.66858 0.23021 0 0.874624 0.484802 0 0.874624 0.484802 0 0.719341 0.694657 0 0.719341 0.694657 0 0.587778 0.809022 0 0.587778 0.809022 0 0.358363 0.933582 0 0.358363 0.933582 -0.113359 0.58399 0.803807 -0.0464757 0.873679 0.484278 -0.150637 0.354274 0.922929 -0.0837707 0.716813 0.692215 -0.0511656 0.867017 0.495644 -0.192222 0.793459 0.577472 -0.15882 0.84539 0.509992 -0.206978 0.861068 0.464459 -0.287663 0.824552 0.487201 -0.185221 0.911813 0.366455 -0.25848 0.895353 0.362672 -0.148423 0.43588 0.887682 -0.396636 0.468811 0.789238 -0.396647 0.468793 0.789243 -0.593623 0.53292 0.602999 -0.593613 0.532932 0.602999 -0.700215 0.616719 0.359662 -0.700216 0.616718 0.359661 -0.412671 2.018e-06 0.91088 -0.610722 -3.31965e-06 0.791845 0.176764 -0.0331204 -0.983696 0.261202 0.0329754 -0.964721 0.421617 -0.0119822 -0.906695 0.460019 -1.86354e-06 -0.887909 0.567954 -3.17229e-06 -0.82306 0.602452 0.0210921 -0.797877 0.752884 -0.0329737 -0.657327 -0.561035 -0.050112 0.826274 -0.738238 0.039776 0.673367 -0.79504 -0.0143517 0.606387 -0.854402 -1.28135e-06 0.519612 -0.885496 -1.14581e-06 0.464648 -0.928817 0.0252275 0.36968 -0.962089 -0.039376 0.269877 -0.993031 0.0198128 0.116177 -0.998613 -1.12872e-06 0.0526425 -0.998643 1.11694e-06 -0.0520873 -0.993122 -0.0195881 -0.11543 -0.977758 0.0160234 -0.209123 -0.92942 -0.0259694 -0.368108 -0.913035 8.06467e-06 -0.407882 -0.854617 1.16054e-06 -0.519259 -0.831382 0.00574226 -0.555672 -0.740868 -0.0321199 -0.670882 -0.678495 0.0326418 -0.73388 -0.560297 -0.00723633 -0.82826 -0.52378 -9.82525e-07 -0.851853 -0.413033 4.24982e-07 -0.910716 -0.372239 0.0256517 -0.927782 -0.159349 -0.0330589 -0.986669 -0.120743 -0.00373817 -0.992677 0.0476302 0.00127495 -0.998864 -0.467588 0.0375735 0.883148 -0.281536 -0.0404667 0.958697 -0.156032 0.0407539 0.986911 -0.0577874 0.00204447 0.998327 0.178172 -0.00560994 0.983983 0.111623 0.0672347 0.991473 0.420921 -0.05876 0.905192 0.363949 -1.78283e-06 0.931419 0.568256 -1.57502e-06 0.822852 0.78852 0.00981723 -0.61493 0.880638 -0.00334804 -0.473778 0.928022 -0.0328606 -0.371074 0.95626 0.0327945 -0.290673 0.994265 -0.0164683 -0.105668 0.998007 0 -0.0631059 0.985806 0 0.167891 0.99237 -0.0646148 0.10501 0.907087 0.0598971 0.416659 0.928666 0.0118421 0.370727 0.8258 -0.00480293 0.563943 0.753037 0.04074 0.656716 0.664281 -0.0409529 0.746361 0.515047 0.0313582 0.856588 0.412671 2.30009e-06 -0.91088 0.610716 -3.07102e-06 -0.79185 -0.176766 -0.033119 0.983696 -0.2612 0.0329734 0.964721 -0.42161 -0.0119845 0.906698 -0.460033 2.54931e-06 0.887902 -0.567954 2.36314e-06 0.823061 -0.602445 0.0210942 0.797881 -0.752884 -0.0329737 0.657327 0.561035 -0.0501064 -0.826274 0.738237 0.0397834 -0.673367 0.79504 -0.0143439 -0.606387 0.85437 -1.28148e-06 -0.519665 0.885512 -1.14573e-06 -0.464616 0.928821 0.0252209 -0.36967 0.962089 -0.0393759 -0.269877 0.993031 0.0198128 -0.116177 0.998613 -1.12872e-06 -0.0526425 0.998643 1.11694e-06 0.0520873 0.993124 -0.0195837 0.115416 0.977761 0.0160272 0.209108 0.929417 -0.025972 0.368117 0.913035 -9.72813e-07 0.407882 0.854617 -7.30929e-06 0.519258 0.83137 0.00573686 0.555689 0.740873 -0.032118 0.670877 0.678495 0.0326486 0.73388 0.560286 -0.00723406 0.828268 0.52378 -7.15226e-07 0.851854 0.413032 7.10743e-07 0.910716 0.372243 0.0256492 0.927781 0.159349 -0.0330603 0.986669 0.120742 -0.00373829 0.992677 -0.0476324 0.00127486 0.998864 0.467587 0.0375731 -0.883148 0.281536 -0.0404668 -0.958697 0.156032 0.0407537 -0.986911 0.057787 0.00204413 -0.998327 -0.178172 -0.00561026 -0.983983 -0.111623 0.0672346 -0.991474 -0.420921 -0.0587603 -0.905192 -0.363949 -1.78283e-06 -0.931419 -0.568256 -1.57502e-06 -0.822852 -0.515046 0.0313589 -0.856589 -0.664281 -0.0409528 -0.746361 -0.753037 0.04074 -0.656716 -0.82581 -0.00480994 -0.563928 -0.92867 0.0118334 -0.370719 -0.788526 0.00982452 0.614923 -0.880615 -0.00333527 0.473821 -0.928022 -0.0328605 0.371074 -0.95626 0.0327945 0.290673 -0.994267 -0.0164724 0.105653 -0.998008 0 0.0630797 -0.998049 0 -0.0624366 -0.994298 0.0164269 -0.105362 -0.97327 -0.016591 -0.229066 -0.90708 0.0599123 -0.416673 -0.911153 -0.195792 -0.362583 -0.739438 -0.197322 -0.643658 -0.0766053 -0.986767 -0.142908 -0.12362 -0.986812 -0.104498 -0.128579 -0.985891 -0.107173 -0.158026 -0.985671 -0.058989 -0.161726 -0.985035 -0.0595859 -0.420419 0.110541 -0.900571 -0.556449 -0.199585 -0.806554 -0.73941 -0.197409 -0.643664 -0.483471 -0.199627 -0.852294 -0.17213 -0.196196 -0.965339 -0.170433 -0.201457 -0.964556 0.159571 -0.193494 -0.968038 0.841956 -0.193404 -0.503692 0.731353 -0.196704 -0.653016 0.730803 -0.18747 -0.65634 0.5564 -0.198557 -0.806842 0.475173 -0.039213 -0.879018 0.412852 -0.194233 -0.889847 0.1618 -0.201766 -0.965977 0.925891 -0.0980781 -0.364839 0.905044 -0.192494 -0.379264 0.975388 -0.189815 -0.112204 0.996774 -0.048416 -0.0640152 0.980133 -0.191851 0.0503343 0.960186 -0.1921 0.20283 0.960786 -0.189882 0.202075 0.898086 -0.193909 0.394767 0.88382 -0.0336249 0.466617 0.82018 -0.192068 0.538901 0.671305 -0.197672 0.714335 0.674158 -0.187844 0.714301 -0.449416 -0.200763 0.870471 -0.252481 -0.196629 0.947413 -0.253328 -0.201097 0.946248 -0.0411345 -0.199215 0.979092 0.0735043 -0.0680988 0.994967 0.125251 -0.201649 0.971416 0.397118 -0.191003 0.897672 0.375664 -0.0961576 0.921754 0.521365 -0.197937 0.83006 -0.602331 -0.0264243 0.797809 -0.554341 -0.197565 0.808501 -0.773562 -0.197845 0.602046 -0.802559 -0.104832 0.58729 -0.863519 -0.199111 0.463345 -0.93855 -0.195579 0.284381 -0.938494 -0.196072 0.284225 -0.171001 -0.985133 -0.0164841 -0.148602 -0.98888 -0.00576386 -0.171446 -0.985144 0.00983949 -0.166645 -0.984886 0.0472019 -0.164029 -0.985395 0.0457303 -0.138318 -0.985613 0.0971376 -0.134768 -0.986494 0.0931011 -0.0902319 -0.986556 0.136258 -0.0881561 -0.987439 0.131118 -0.0282341 -0.986912 0.15877 -0.0280628 -0.9875 0.155104 0.0391031 -0.986095 0.161518 0.038982 -0.986166 0.161112 0.102771 -0.984023 0.145387 0.104297 -0.983547 0.147504 0.1557 -0.981214 0.113915 0.159082 -0.980393 0.116287 0.193376 -0.978509 0.0715931 0.196857 -0.977742 0.0725751 0.210271 -0.977126 0.0317882 0.21143 -0.976881 0.0316474 0.215731 -0.976403 -0.0098816 0.215213 -0.976519 -0.00973378 0.203048 -0.977262 -0.0610721 0.200443 -0.977914 -0.0592186 0.169907 -0.979643 -0.106919 0.1675 -0.980425 -0.103492 0.11895 -0.982763 -0.141521 0.118089 -0.983305 -0.138444 0.0558949 -0.985607 -0.159548 0.0559217 -0.98567 -0.159144 -0.0109274 -0.987308 -0.158443 -0.0120737 -0.986861 -0.161121 -0.411023 -0.84001 -0.354181 -0.506241 -0.839252 -0.198435 -0.508196 -0.83802 -0.198644 -0.545919 -0.837531 -0.022684 -0.546145 -0.837385 -0.022631 -0.523437 -0.837662 0.156001 -0.522122 -0.838639 0.155158 -0.440243 -0.839388 0.318768 -0.438422 -0.84122 0.31644 -0.30378 -0.841463 0.44683 -0.302595 -0.843721 0.443364 -0.128803 -0.842224 0.523516 -0.12881 -0.844332 0.520108 0.0630906 -0.840308 0.538426 0.0622626 -0.841907 0.536018 0.247489 -0.835638 0.490365 0.24657 -0.836601 0.489185 0.402358 -0.829467 0.387418 0.401871 -0.82985 0.387103 0.511776 -0.823765 0.24392 0.5117 -0.823817 0.243902 0.557698 -0.823005 0.107868 0.557707 -0.822999 0.107866 0.571166 -0.820159 -0.0332906 0.57117 -0.820156 -0.0332922 0.530813 -0.822677 -0.203569 0.530835 -0.822658 -0.203588 0.434499 -0.828177 -0.354024 0.434707 -0.827919 -0.354373 0.289758 -0.834947 -0.467872 0.29 -0.834185 -0.469079 0.110965 -0.84083 -0.529803 0.110645 -0.839403 -0.532127 -0.0806797 -0.844062 -0.530141 -0.0821523 -0.842083 -0.533055 -0.260969 -0.844173 -0.468259 -0.770829 -0.559348 -0.304881 -0.828724 -0.558573 -0.0348279 -0.828779 -0.558493 -0.0348059 -0.793972 -0.558966 0.239092 -0.793671 -0.559507 0.238828 -0.669192 -0.560746 0.487591 -0.66871 -0.562065 0.486734 -0.466418 -0.562538 0.682646 -0.466101 -0.564869 0.680935 -0.207502 -0.562713 0.800186 -0.207862 -0.566224 0.797611 0.076768 -0.560271 0.824744 0.0753201 -0.564766 0.821807 0.351395 -0.555364 0.753719 0.34892 -0.560289 0.75122 0.583827 -0.549433 0.597721 0.581005 -0.553908 0.596338 0.749078 -0.544513 0.377344 0.74691 -0.54764 0.377115 0.820568 -0.546442 0.167539 0.819895 -0.547367 0.167814 0.838227 -0.542881 -0.0515269 0.838488 -0.542465 -0.0516662 0.776302 -0.54642 -0.314293 0.77757 -0.543772 -0.315749 0.630772 -0.552288 -0.545073 0.631861 -0.548192 -0.547939 0.414091 -0.558843 -0.718486 0.414175 -0.554044 -0.722146 0.148008 -0.563949 -0.812438 0.146945 -0.559347 -0.815805 -0.136658 -0.566219 -0.812847 -0.138338 -0.562471 -0.815162 -0.404782 -0.565485 -0.718594 -0.406395 -0.562851 -0.719751 -0.624108 -0.562841 -0.541941 -0.0730442 -0.987593 -0.139015 -0.263589 -0.841936 -0.470813 -0.408109 -0.842008 -0.352804 -0.625201 -0.561304 -0.542274 -0.770303 -0.560062 -0.304901 -0.910997 -0.196346 -0.362676 -0.979846 -0.195407 -0.0414583 -0.993256 0.0485115 -0.10531 -0.978268 -0.197979 0.0616134 0.911149 -0.195793 0.362591 0.739438 -0.197322 0.643658 0.0766072 -0.986767 0.14291 0.123624 -0.986811 0.1045 0.128575 -0.985892 0.107171 0.15802 -0.985672 0.058988 0.161732 -0.985034 0.0595868 0.420419 0.110541 0.900571 0.556449 -0.199586 0.806554 0.73941 -0.19741 0.643664 0.483473 -0.199645 0.852288 0.17213 -0.196203 0.965337 0.170433 -0.201463 0.964554 -0.159569 -0.193489 0.968039 -0.841992 -0.193371 0.503644 -0.731357 -0.196677 0.65302 -0.730808 -0.187469 0.656335 -0.5564 -0.198557 0.806842 -0.475173 -0.0392122 0.879018 -0.412851 -0.194234 0.889847 -0.1618 -0.201766 0.965977 -0.925886 -0.0980844 0.364848 -0.905041 -0.192494 0.379273 -0.975388 -0.189815 0.112204 -0.996774 -0.048416 0.0640152 -0.980133 -0.191851 -0.0503343 -0.960186 -0.1921 -0.20283 -0.960776 -0.189919 -0.202088 -0.89808 -0.193943 -0.394764 -0.883816 -0.0336387 -0.466624 -0.820196 -0.192036 -0.538888 -0.671313 -0.197647 -0.714335 -0.674158 -0.187844 -0.714301 0.4494 -0.20078 -0.870475 0.252482 -0.196638 -0.94741 0.253327 -0.201088 -0.94625 0.0411326 -0.199214 -0.979092 -0.0735042 -0.0680995 -0.994967 -0.125252 -0.201654 -0.971415 -0.397117 -0.191018 -0.897669 -0.37566 -0.0961542 -0.921756 -0.521366 -0.197937 -0.83006 0.602337 -0.0264164 -0.797805 0.554345 -0.197564 -0.808498 0.773556 -0.197845 -0.602053 0.802561 -0.104801 -0.587292 0.863542 -0.199112 -0.463303 0.93855 -0.195579 -0.284381 0.938494 -0.196072 -0.284225 0.171008 -0.985132 0.0164847 0.148606 -0.98888 0.00576406 0.171452 -0.985143 -0.00983989 0.166651 -0.984885 -0.0472037 0.164035 -0.985394 -0.0457321 0.138322 -0.985612 -0.0971407 0.134772 -0.986493 -0.093104 0.0902332 -0.986555 -0.136261 0.0881561 -0.987439 -0.131118 0.0282341 -0.986912 -0.15877 0.0280627 -0.9875 -0.155103 -0.0391035 -0.986094 -0.16152 -0.0389816 -0.986166 -0.16111 -0.102769 -0.984023 -0.145383 -0.104297 -0.983547 -0.147504 -0.155698 -0.981214 -0.113916 -0.159086 -0.980392 -0.116292 -0.193383 -0.978508 -0.0715952 -0.196857 -0.977742 -0.0725751 -0.21027 -0.977126 -0.0317909 -0.211438 -0.976879 -0.0316491 -0.215739 -0.976401 0.00988214 -0.215214 -0.976518 0.00973208 -0.203048 -0.977262 0.0610721 -0.200449 -0.977912 0.0592229 -0.169911 -0.979641 0.106925 -0.1675 -0.980425 0.103492 -0.118951 -0.982763 0.141521 -0.118091 -0.983304 0.138448 -0.0558948 -0.985606 0.15955 -0.0559218 -0.985671 0.159142 0.0109276 -0.987308 0.158443 0.0120735 -0.986861 0.16112 0.411025 -0.84001 0.354178 0.506239 -0.839252 0.198439 0.508195 -0.838019 0.198648 0.545919 -0.837531 0.022684 0.546145 -0.837385 0.022631 0.523436 -0.837662 -0.156006 0.522106 -0.83865 -0.155153 0.440232 -0.839397 -0.31876 0.438411 -0.841229 -0.316432 0.303774 -0.84147 -0.446822 0.302592 -0.843721 -0.443365 0.128805 -0.842224 -0.523515 0.128811 -0.844329 -0.520112 -0.0630906 -0.840309 -0.538424 -0.062263 -0.841908 -0.536018 -0.247489 -0.835638 -0.490365 -0.24657 -0.836601 -0.489185 -0.402355 -0.829467 -0.38742 -0.401869 -0.82985 -0.387106 -0.511776 -0.823765 -0.24392 -0.511716 -0.823806 -0.243906 -0.557715 -0.822993 -0.107872 -0.557706 -0.822999 -0.107874 -0.571166 -0.820159 0.0332959 -0.571152 -0.820169 0.0332909 -0.530798 -0.822689 0.203557 -0.530835 -0.822658 0.203588 -0.434497 -0.828177 0.354027 -0.434704 -0.827919 0.354375 -0.289758 -0.834947 0.467872 -0.289998 -0.834191 0.46907 -0.110965 -0.840833 0.529799 -0.110645 -0.839402 0.53213 0.0806791 -0.844064 0.530138 0.0821529 -0.842084 0.533054 0.260969 -0.844174 0.468259 0.770812 -0.559372 0.304882 0.828706 -0.558599 0.0348272 0.828761 -0.558519 0.0348052 0.793956 -0.558991 -0.239087 0.793668 -0.559508 -0.238835 0.669192 -0.560746 -0.487592 0.66871 -0.562065 -0.486734 0.466421 -0.562539 -0.682643 0.466107 -0.564855 -0.680943 0.207501 -0.562706 -0.800191 0.207863 -0.566231 -0.797606 -0.0767679 -0.560269 -0.824746 -0.0753203 -0.564763 -0.821809 -0.351398 -0.555353 -0.753726 -0.348922 -0.560278 -0.751227 -0.583839 -0.549414 -0.597727 -0.580994 -0.553927 -0.596332 -0.749061 -0.544537 -0.377342 -0.74691 -0.54764 -0.377115 -0.820568 -0.546442 -0.167539 -0.819895 -0.547367 -0.167814 -0.838227 -0.542881 0.0515269 -0.838505 -0.542438 0.0516751 -0.776315 -0.546394 0.314307 -0.777558 -0.543796 0.315735 -0.630767 -0.552309 0.545058 -0.631866 -0.548173 0.547953 -0.414095 -0.55883 0.718494 -0.414179 -0.554031 0.722154 -0.148007 -0.563945 0.812441 -0.146946 -0.559352 0.815802 0.136659 -0.566215 0.81285 0.138339 -0.562466 0.815165 0.40479 -0.565472 0.7186 0.406395 -0.562851 0.719752 0.624109 -0.56284 0.541941 0.0730423 -0.987593 0.139013 0.263583 -0.841941 0.470807 0.408099 -0.842016 0.352796 0.625201 -0.561304 0.542274 0.770303 -0.560062 0.304901 0.911003 -0.196312 0.362678 0.979853 -0.195371 0.0414587 0.993254 0.0485496 0.10531 0.978266 -0.197979 -0.061639 -0.0301633 -0.644442 -0.764058 -0.0832839 -0.907333 -0.412081 -0.119928 -0.99263 0.01738 -0.133244 -0.887481 0.441162 -0.120816 -0.613043 0.780757 -0.084758 -0.219253 0.97198 -0.0299976 -0.645116 -0.763496 -0.0994609 -0.628098 -0.771752 -0.100787 -0.631287 -0.768973 -0.142071 -0.604004 -0.784216 -0.145658 -0.607791 -0.780624 -0.156341 -0.596739 -0.787058 -0.162339 -0.599989 -0.783364 -0.157214 -0.608345 -0.777946 -0.159496 -0.609046 -0.776933 -0.152017 -0.628022 -0.763203 -0.149389 -0.627551 -0.764109 -0.143238 -0.652836 -0.743833 -0.130457 -0.65248 -0.746493 -0.0838376 -0.906347 -0.414133 -0.28149 -0.854361 -0.436842 -0.278487 -0.848391 -0.450196 -0.41055 -0.763154 -0.499045 -0.403066 -0.757708 -0.513241 -0.466756 -0.691491 -0.551343 -0.447418 -0.686239 -0.573492 -0.472577 -0.645501 -0.6 -0.446083 -0.643514 -0.622013 -0.452569 -0.627164 -0.633914 -0.426589 -0.627921 -0.650951 -0.428955 -0.618088 -0.65876 -0.382655 -0.625658 -0.679799 -0.121527 -0.992512 0.0123163 -0.406892 -0.91317 -0.0236469 -0.40565 -0.912368 -0.0550644 -0.604745 -0.786276 -0.126706 -0.595918 -0.785889 -0.165105 -0.701117 -0.675538 -0.228216 -0.67311 -0.680967 -0.288456 -0.724934 -0.597542 -0.342658 -0.684859 -0.608514 -0.400848 -0.704505 -0.55947 -0.436653 -0.665626 -0.571667 -0.479728 -0.675883 -0.528045 -0.514151 -0.608517 -0.555477 -0.566702 -0.136167 -0.890424 0.434285 -0.454424 -0.801648 0.388406 -0.461428 -0.816953 0.345936 -0.691342 -0.671663 0.266299 -0.694342 -0.689001 0.207768 -0.822875 -0.553195 0.129817 -0.810002 -0.585489 0.0331536 -0.88093 -0.47151 -0.040499 -0.850345 -0.507924 -0.137578 -0.880844 -0.432457 -0.1926 -0.845026 -0.46383 -0.266068 -0.861634 -0.391222 -0.323314 -0.792358 -0.446866 -0.415307 -0.125263 -0.620382 0.774232 -0.417066 -0.543051 0.728802 -0.437789 -0.580622 0.686454 -0.656179 -0.440481 0.612703 -0.683811 -0.482932 0.546973 -0.814219 -0.345008 0.466923 -0.841213 -0.412811 0.349212 -0.920741 -0.284609 0.266896 -0.925316 -0.352692 0.139277 -0.962899 -0.260065 0.0720556 -0.948945 -0.314078 -0.0292844 -0.969912 -0.220326 -0.103569 -0.921768 -0.307402 -0.236321 -0.0908259 -0.231178 0.968663 -0.29964 -0.179678 0.93698 -0.338626 -0.241176 0.909487 -0.504647 -0.132129 0.853155 -0.566181 -0.199381 0.799804 -0.676523 -0.0833462 0.73169 -0.763335 -0.185279 0.618863 -0.839575 -0.0615915 0.53974 -0.902372 -0.159189 0.400479 -0.942206 -0.0607665 0.329477 -0.968377 -0.135734 0.209339 -0.991611 -0.0308869 0.125515 -0.988277 -0.146706 -0.0422618 -0.923723 -0.271893 -0.269835 -0.382234 -0.656995 -0.649812 -0.608237 -0.565007 -0.557508 -0.79295 -0.433699 -0.427943 -0.99142 -0.0930464 -0.0918115 -0.194753 -0.889901 -0.41249 -0.194756 -0.835383 -0.51401 -0.194749 -0.835384 -0.514011 -0.194756 -0.769826 -0.607814 -0.194784 -0.769823 -0.607809 -0.194865 -0.699703 -0.687345 -0.130313 -0.705744 -0.696379 -0.335362 -0.893162 -0.299656 -0.194748 -0.932049 -0.305544 -0.194739 -0.889903 -0.412492 -0.195024 -0.946437 -0.257337 -0.194795 -0.959564 -0.203205 -0.194935 -0.959538 -0.203193 -0.555071 -0.593626 -0.58267 -0.554893 -0.652938 -0.515525 -0.554916 -0.652926 -0.515514 -0.554905 -0.708533 -0.43596 -0.554896 -0.708539 -0.435964 -0.55489 -0.754782 -0.34986 -0.554892 -0.75478 -0.349859 -0.554908 -0.790519 -0.259147 -0.554901 -0.790523 -0.259149 -0.555074 -0.813755 -0.172322 -0.55525 -0.813643 -0.172288 -0.831178 -0.397317 -0.38895 -0.831041 -0.436546 -0.344671 -0.831031 -0.436558 -0.344682 -0.831023 -0.473742 -0.291493 -0.831024 -0.473741 -0.291493 -0.83102 -0.504664 -0.233924 -0.831018 -0.504666 -0.233925 -0.831029 -0.528553 -0.17327 -0.831024 -0.52856 -0.173273 -0.83114 -0.544002 -0.115192 -0.83128 -0.543799 -0.115138 -0.98075 -0.140538 -0.135569 -0.980718 -0.153384 -0.121104 -0.980717 -0.153386 -0.121106 -0.980716 -0.166454 -0.102419 -0.980717 -0.166449 -0.102416 -0.980716 -0.177315 -0.0821897 -0.980716 -0.177314 -0.0821892 -0.980718 -0.185704 -0.0608776 -0.980719 -0.1857 -0.060876 -0.980736 -0.191102 -0.0404618 -0.980754 -0.191013 -0.0404385 -0.000423175 -0.220053 0.975488 -0.000421567 -0.220012 0.975497 -0.00118932 -0.61756 0.786523 -0.0011838 -0.617445 0.786613 -0.00172491 -0.895429 0.445202 -0.00171643 -0.895327 0.445405 -0.00192714 -0.999842 0.0176561 -0.00191589 -0.999837 0.0179646 -0.00175756 -0.910575 -0.41334 -0.00174275 -0.910747 -0.412962 -0.00124807 -0.644938 -0.764234 -0.00123146 -0.645301 -0.763928 -0.000200429 -0.220084 0.975481 -0.000199269 -0.220053 0.975488 -0.000562874 -0.617599 0.786493 -0.000561057 -0.617561 0.786523 -0.000817401 -0.895477 0.445107 -0.000813496 -0.89543 0.445202 -0.000913382 -0.999846 0.0175023 -0.000907779 -0.999844 0.0176561 -0.000832487 -0.910503 -0.413502 -0.000826085 -0.910576 -0.41334 -0.000591603 -0.644743 -0.764399 -0.000582463 -0.644939 -0.764234 -0.554722 -0.809106 -0.193989 -0.82831 -0.530678 -0.179675 -0.975199 -0.173117 -0.137904 -0.967933 -0.203171 -0.147739 -0.945146 -0.186092 -0.268458 -0.942704 -0.190873 -0.273635 -0.898796 -0.169936 -0.404089 -0.909857 -0.0630434 -0.410105 -0.828889 -0.18773 -0.526973 -0.80927 -0.183881 -0.557916 -0.806452 -0.187614 -0.560747 -0.709994 -0.170446 -0.683269 -0.703865 -0.191774 -0.683957 -0.586414 -0.183559 -0.788939 -0.584283 -0.185989 -0.789951 -0.541929 -0.81717 -0.196331 -0.528761 -0.809243 -0.256004 -0.525748 -0.81058 -0.257971 -0.503739 -0.797738 -0.331455 -0.487982 -0.808626 -0.32863 -0.447918 -0.802363 -0.39444 -0.444718 -0.803775 -0.395186 -0.397708 -0.79381 -0.460103 -0.386083 -0.803496 -0.453137 -0.32345 -0.80034 -0.504813 -0.320982 -0.801524 -0.50451 -0.251511 -0.794424 -0.55284 -0.245995 -0.800971 -0.545831 -0.165587 -0.800764 -0.575638 -0.164459 -0.801408 -0.575063 -0.0294677 -0.962745 -0.2688 -0.0580118 -0.963773 -0.26034 -0.0591749 -0.963494 -0.261108 -0.0847058 -0.963983 -0.252113 -0.0905142 -0.961274 -0.260307 -0.111772 -0.963061 -0.244992 -0.114139 -0.962634 -0.245576 -0.131448 -0.963854 -0.231747 -0.142476 -0.960405 -0.239422 -0.154831 -0.962729 -0.221768 -0.157429 -0.962369 -0.221502 -0.166946 -0.964121 -0.206397 -0.178881 -0.961278 -0.209635 -0.183744 -0.963958 -0.192414 -0.185511 -0.963788 -0.191569 -0.188467 -0.965655 -0.17886 -0.195058 -0.964435 -0.178377 -0.0285681 -0.963674 -0.265549 -0.063243 -0.867606 -0.493214 -0.0745965 -0.796566 -0.599932 -0.0863004 -0.760064 -0.644093 -0.112662 -0.577135 -0.80884 -0.814666 -0.549537 -0.18528 -0.794859 -0.536761 -0.282996 -0.791593 -0.539786 -0.286378 -0.75332 -0.518883 -0.404066 -0.738268 -0.540088 -0.40406 -0.675807 -0.530162 -0.512067 -0.672523 -0.53279 -0.513661 -0.595692 -0.516888 -0.614799 -0.585657 -0.533024 -0.610648 -0.488416 -0.528173 -0.69461 -0.48604 -0.530054 -0.694844 -0.376845 -0.519034 -0.767197 -0.372353 -0.52881 -0.762701 -0.249426 -0.528556 -0.811428 -0.248333 -0.529505 -0.811144 -0.113159 -0.522358 -0.845185 -0.127519 -0.416788 -0.900015 -0.526276 -0.181679 -0.830678 -0.466281 0.0859514 -0.880451 -0.402504 -0.186552 -0.896208 -0.299191 -0.184178 -0.936249 -0.298211 -0.18527 -0.936347 -0.141073 -0.179697 -0.973554 -0.140565 -0.18276 -0.973057 0.99821 -0.0442489 0.0402265 0.989443 -0.134528 -0.0539025 0.957832 -0.229017 -0.173518 0.922138 -0.298076 -0.246603 0.839243 -0.395265 -0.373413 0.791522 -0.441403 -0.422677 0.651909 -0.52931 -0.542997 0.606394 -0.554525 -0.569902 0.410979 -0.6201 -0.668261 0.379372 -0.629531 -0.678061 0.136264 -0.660082 -0.738731 0.126156 -0.661115 -0.739602 0.140171 -0.635891 -0.758943 0.146789 -0.636074 -0.757538 0.409067 -0.631834 -0.65837 0.449861 -0.624328 -0.638623 0.644172 -0.575565 -0.503753 0.704976 -0.546506 -0.45204 0.825982 -0.472008 -0.30816 0.885085 -0.411179 -0.218075 0.939887 -0.32998 -0.0879023 0.971712 -0.233062 0.0381743 0.977078 -0.161346 0.138871 0.884571 -0.0790298 0.459662 0.931412 -0.10788 0.347611 0.956561 -0.0310191 0.289877 0.160664 -0.603182 -0.781255 0.155166 -0.601738 -0.783476 0.447319 -0.668704 -0.593919 0.473742 -0.668841 -0.572905 0.679381 -0.652834 -0.335036 0.720466 -0.63565 -0.277268 0.828864 -0.558248 -0.0366726 0.859269 -0.508209 0.0581495 0.878634 -0.397092 0.265179 0.871181 -0.306333 0.383672 0.157248 -0.59915 -0.785043 0.155595 -0.599121 -0.785394 0.44616 -0.704162 -0.552356 0.450957 -0.702996 -0.549941 0.668685 -0.70456 -0.237604 0.677271 -0.698757 -0.230312 0.791669 -0.600493 0.112553 0.799975 -0.587011 0.124329 0.796742 -0.407696 0.446078 0.800496 -0.384772 0.459518 0.15468 -0.615554 -0.772766 0.154362 -0.615525 -0.772853 0.443238 -0.641735 -0.625872 0.462713 -0.639011 -0.61446 0.684983 -0.60015 -0.413061 0.715139 -0.585338 -0.382041 0.854392 -0.495385 -0.156872 0.881244 -0.46109 -0.10395 0.933753 -0.338727 0.115623 0.941368 -0.281332 0.186219 0.883918 -0.0781235 0.461071 0.823503 -0.188903 0.534937 0.755297 -0.0593736 0.652688 0.683109 -0.154817 0.713718 0.473966 -0.058192 0.878618 0.651241 -0.15479 0.742916 0.678879 -0.122909 0.72389 0.10826 -0.627433 -0.771108 0.105168 -0.62473 -0.773726 0.298496 -0.837356 -0.457968 0.305747 -0.840449 -0.447396 0.434947 -0.897983 -0.0666977 0.44642 -0.893925 -0.0400984 0.494727 -0.802589 0.33331 0.503048 -0.78089 0.370342 0.468589 -0.569643 0.675227 0.46729 -0.524299 0.711864 0.165742 -0.609159 0.775535 0.162394 -0.623172 0.765039 0.180156 -0.880767 0.437942 0.17654 -0.887053 0.426581 0.16075 -0.986836 0.0177256 0.157639 -0.987455 0.00903481 0.110467 -0.905221 -0.410331 0.108836 -0.903749 -0.413996 0.0381824 -0.644887 -0.763324 0.0387995 -0.645956 -0.762388 0.148982 -0.606668 -0.780871 0.142899 -0.603552 -0.784414 0.410382 -0.747718 -0.52202 0.424848 -0.750453 -0.506285 0.607574 -0.772679 -0.183905 0.630032 -0.763681 -0.140894 0.710976 -0.67963 0.180597 0.72442 -0.643942 0.246079 0.706072 -0.484132 0.516796 0.694045 -0.41344 0.589381 0.531925 -0.119527 0.838313 0.360573 -0.23751 0.901985 0.344924 -0.167766 0.923516 0.117407 -0.241039 0.963388 0.119939 -0.218702 0.968393 -0.0040722 -0.869375 -0.494137 -0.00357587 -0.762986 -0.646405 -0.00570263 -0.677242 -0.735738 -0.00272167 -0.581005 -0.813896 -0.0019705 -0.420466 -0.907306 -0.00304581 -0.245469 -0.9694 -0.000866379 -0.184917 -0.982754 -0.00943668 -0.94577 -0.3247 -0.00632398 -0.945796 -0.324701 -0.00451948 -0.964061 -0.265641 -0.0024477 -0.245543 -0.969383 -0.0024499 -0.245474 -0.9694 -0.00579217 -0.581205 -0.813736 -0.00422189 -0.677253 -0.735738 -0.00761167 -0.7632 -0.646117 -0.00942396 -0.945881 -0.324378 0.180937 -0.96292 -0.200119 0.546808 -0.819742 -0.170364 0.827877 -0.549177 -0.114126 0.980356 -0.193112 -0.0401252 0.182106 -0.962697 -0.200128 0.182304 -0.949894 -0.253905 0.327929 -0.899 -0.290277 0.183707 -0.932943 -0.309627 0.18363 -0.893164 -0.410534 0.185499 -0.89281 -0.410464 0.185571 -0.841844 -0.506816 0.187226 -0.841531 -0.506727 0.187162 -0.780741 -0.596166 0.298277 -0.761747 -0.575128 0.189282 -0.747827 -0.636339 0.547361 -0.819382 -0.17032 0.547132 -0.796564 -0.257161 0.548131 -0.795926 -0.257011 0.548134 -0.759954 -0.349311 0.549264 -0.759256 -0.349056 0.549421 -0.715831 -0.430957 0.550451 -0.715217 -0.43066 0.550317 -0.663651 -0.506674 0.551434 -0.663029 -0.506275 0.12595 -0.712734 -0.690034 0.188991 -0.706846 -0.681653 0.378838 -0.664199 -0.644454 0.551472 -0.600689 -0.578836 0.605891 -0.571539 -0.553389 0.791622 -0.438981 -0.425005 0.828043 -0.548933 -0.11409 0.827889 -0.533766 -0.17232 0.828293 -0.533188 -0.172167 0.828295 -0.509089 -0.234001 0.828756 -0.508454 -0.23375 0.828861 -0.479296 -0.288555 0.829273 -0.478754 -0.288273 0.829183 -0.444294 -0.339203 0.829619 -0.443758 -0.338838 0.829663 -0.402449 -0.386902 0.923209 -0.2754 -0.268028 0.980372 -0.193032 -0.0401125 0.98035 -0.187729 -0.0606019 0.9804 -0.187486 -0.0605356 0.980401 -0.179012 -0.0822784 0.980454 -0.178764 -0.082178 0.98047 -0.168493 -0.101436 0.980513 -0.1683 -0.101333 0.9805 -0.156201 -0.119249 0.980554 -0.15598 -0.119096 0.980574 -0.1423 -0.135004 0.99136 -0.0942355 -0.09124 0.0141947 -0.945859 -0.324268 0.0428915 -0.762787 -0.645225 0.0748251 -0.580261 -0.810986 0.109301 -0.2454 -0.963241 0.101143 -0.180996 -0.978269 0.226214 -0.185934 -0.956167 0.225207 -0.184475 -0.956687 0.0203794 -0.964228 -0.264291 0.0307601 -0.96457 -0.262027 0.0303015 -0.964297 -0.263085 0.059014 -0.965053 -0.255325 0.0616678 -0.962596 -0.263831 0.0870825 -0.964771 -0.248262 0.086981 -0.964183 -0.250569 0.10886 -0.965755 -0.235515 0.116723 -0.96226 -0.24583 0.133258 -0.965097 -0.225454 0.134132 -0.964358 -0.228086 0.14734 -0.966559 -0.20989 0.158131 -0.963317 -0.21683 0.165464 -0.966515 -0.196141 0.166812 -0.965914 -0.197947 0.17235 -0.968567 -0.17937 0.181029 -0.9666 -0.181421 0.0466358 -0.799428 -0.59895 0.114769 -0.802856 -0.585022 0.114186 -0.802174 -0.58607 0.199673 -0.803048 -0.561467 0.202185 -0.796616 -0.56967 0.279107 -0.804525 -0.524251 0.278789 -0.803079 -0.526631 0.349614 -0.806826 -0.476236 0.357803 -0.796924 -0.486712 0.413675 -0.807731 -0.420052 0.414453 -0.805706 -0.423163 0.462914 -0.812549 -0.354224 0.476506 -0.801021 -0.362364 0.505661 -0.814643 -0.284013 0.507526 -0.812479 -0.286873 0.529814 -0.822261 -0.207809 0.545646 -0.811092 -0.210712 0.0726783 -0.525122 -0.847918 0.183046 -0.530868 -0.82745 0.182256 -0.529732 -0.828352 0.31185 -0.531016 -0.787891 0.31349 -0.520686 -0.79411 0.432474 -0.53279 -0.727393 0.431707 -0.530437 -0.729566 0.540049 -0.53613 -0.648777 0.546371 -0.519458 -0.656995 0.635698 -0.536384 -0.555139 0.635852 -0.53282 -0.558387 0.710513 -0.543492 -0.446976 0.722505 -0.521655 -0.453721 0.771771 -0.543509 -0.330101 0.773251 -0.539193 -0.333698 0.806363 -0.554727 -0.205076 0.822508 -0.52972 -0.207067 0.307423 -0.187191 -0.93298 0.400005 0.103515 -0.910649 0.437931 -0.180365 -0.88073 0.525967 -0.187263 -0.829633 0.524541 -0.184219 -0.831216 0.654802 -0.193542 -0.7306 0.656972 -0.171226 -0.734213 0.768057 -0.189404 -0.611731 0.766951 -0.184479 -0.614617 0.85641 -0.199945 -0.476008 0.86165 -0.168489 -0.478717 0.924906 -0.192873 -0.327642 0.924822 -0.186434 -0.331582 0.962864 -0.207981 -0.172152 0.970563 -0.168766 -0.171829 -0.0846967 -0.578791 0.811066 -0.0478257 -0.868363 0.493618 -0.0222859 -0.963829 0.265588 -0.0554147 -0.761768 0.645476 -0.0758104 -0.419106 0.904767 -0.23124 -0.185166 0.955113 -0.105542 -0.18204 0.977611 -0.10577 -0.183641 0.977286 -0.0221936 -0.96331 0.267473 -0.045991 -0.963902 0.262253 -0.0455551 -0.963654 0.263239 -0.0742981 -0.963977 0.255399 -0.0769329 -0.961484 0.263875 -0.102326 -0.963277 0.248246 -0.102213 -0.962701 0.250519 -0.123913 -0.963934 0.235537 -0.131793 -0.960299 0.245878 -0.148168 -0.962875 0.22565 -0.149041 -0.962121 0.228276 -0.0595928 -0.799002 0.598368 -0.128183 -0.801459 0.584152 -0.127698 -0.800917 0.585 -0.212779 -0.800497 0.560295 -0.21494 -0.794779 0.567562 -0.291393 -0.801497 0.522201 -0.291077 -0.800178 0.524394 -0.361279 -0.802839 0.474265 -0.368943 -0.793374 0.484189 -0.424313 -0.803289 0.417954 -0.425057 -0.801315 0.420976 -0.0886642 -0.525753 0.846004 -0.192871 -0.529474 0.82611 -0.192327 -0.528727 0.826716 -0.321169 -0.528047 0.786141 -0.322394 -0.519664 0.791209 -0.440629 -0.529942 0.724574 -0.439941 -0.527951 0.726443 -0.547425 -0.531959 0.646023 -0.553028 -0.516752 0.65355 -0.641678 -0.532313 0.552171 -0.641801 -0.528996 0.555208 -0.811432 -0.190043 0.552686 -0.769083 -0.183142 0.612348 -0.770122 -0.187656 0.60967 -0.659593 -0.171042 0.731903 -0.657853 -0.190732 0.728595 -0.528377 -0.183474 0.828948 -0.529579 -0.185932 0.827632 -0.496155 -0.183992 0.848515 -0.395356 -0.0705512 0.915814 -0.370424 -0.185996 0.91005 -0.230622 -0.184312 0.955428 -0.161981 -0.964101 0.210405 -0.172734 -0.960701 0.217294 -0.472946 -0.807426 0.352682 -0.486064 -0.796075 0.360566 -0.715797 -0.53853 0.444545 -0.727174 -0.51747 0.451046 -0.888867 0.0748018 0.452018 -0.884569 -0.174878 0.432383 -0.925652 -0.184648 0.330263 -0.925747 -0.190843 0.326453 -0.777303 -0.534424 0.331949 -0.775895 -0.538603 0.328471 -0.51663 -0.807046 0.285953 -0.514808 -0.8092 0.283141 -0.181184 -0.963143 0.198816 -0.179884 -0.963744 0.197075 -0.971041 -0.166529 0.171309 -0.963448 -0.205649 0.171689 -0.825996 -0.524497 0.206478 -0.810064 -0.549499 0.204566 -0.554124 -0.805311 0.210763 -0.538583 -0.816505 0.207959 -0.195045 -0.963613 0.182775 -0.186548 -0.965667 0.180796 -0.194942 -0.959714 0.202355 -0.555263 -0.813783 0.171581 -0.831288 -0.543885 0.114669 -0.980756 -0.191041 0.0402739 -0.194817 -0.959739 0.202354 -0.195017 -0.944771 0.263394 -0.420329 -0.862502 0.281807 -0.194892 -0.927516 0.318954 -0.194743 -0.889765 0.412787 -0.194758 -0.889762 0.412786 -0.195083 -0.861636 0.468536 -0.272038 -0.822642 0.499255 -0.194859 -0.836178 0.512676 -0.194753 -0.777537 0.597919 -0.194785 -0.777531 0.597916 -0.194778 -0.702579 0.68443 -0.194756 -0.702583 0.684432 -0.555103 -0.81389 0.171594 -0.554881 -0.79079 0.258376 -0.554873 -0.790795 0.258377 -0.554877 -0.754673 0.350114 -0.554879 -0.754672 0.350114 -0.555032 -0.711116 0.43157 -0.555035 -0.711115 0.43157 -0.554906 -0.65947 0.507128 -0.554911 -0.659467 0.507126 -0.5549 -0.595902 0.580506 -0.5549 -0.595902 0.580506 -0.83116 -0.544076 0.114698 -0.831012 -0.528747 0.172758 -0.831013 -0.528745 0.172758 -0.831016 -0.504591 0.234094 -0.831013 -0.504596 0.234096 -0.831116 -0.4754 0.288516 -0.83112 -0.475394 0.288513 -0.831033 -0.440926 0.33907 -0.83102 -0.440942 0.33908 -0.831013 -0.398444 0.388149 -0.831032 -0.398423 0.388131 -0.980737 -0.191132 0.0402888 -0.980716 -0.185775 0.0606986 -0.980714 -0.185782 0.0607003 -0.980715 -0.177294 0.0822517 -0.980715 -0.177292 0.0822508 -0.98073 -0.167016 0.101361 -0.980731 -0.167014 0.10136 -0.980718 -0.154919 0.119131 -0.980719 -0.154917 0.11913 -0.980717 -0.139987 0.136371 -0.980717 -0.139987 0.136371 -0.00407221 -0.869376 0.494134 -0.00943774 -0.94588 0.324378 -0.00419372 -0.420623 0.907226 -0.000553092 -0.245487 0.9694 -0.00184408 -0.18499 0.982739 -0.00451948 -0.964061 0.265641 -0.00632396 -0.945796 0.3247 -0.00942287 -0.94577 0.324699 -0.00761167 -0.7632 0.646117 -0.00357587 -0.762986 0.646405 -0.00570263 -0.677242 0.735738 -0.00422189 -0.677253 0.735738 -0.00579221 -0.581203 0.813738 -0.00086639 -0.184919 0.982753 -0.00304574 -0.245469 0.9694 -0.00197047 -0.42046 0.907309 -0.00272167 -0.581005 0.813896 -0.61541 -0.193498 -0.764087 -0.19507 -0.654707 0.730278 -0.139026 -0.66355 0.735101 -0.413859 -0.616317 0.669981 -0.55541 -0.577563 0.598282 -0.653565 -0.52661 0.543631 -0.830672 -0.406605 0.380336 -0.998246 -0.0440404 -0.0395639 -0.97883 -0.177858 0.101286 -0.957917 -0.229058 0.172998 -0.839615 -0.396844 0.370892 -0.956855 -0.0305847 -0.288953 -0.977426 -0.160644 -0.137228 -0.972117 -0.231542 -0.0371063 -0.940368 -0.328212 0.0893598 -0.885912 -0.408816 0.219158 -0.826996 -0.469452 0.309343 -0.706499 -0.543682 0.453066 -0.645949 -0.572677 0.504769 -0.452175 -0.621572 0.639677 -0.41181 -0.62907 0.659305 -0.149797 -0.633916 0.758756 -0.143813 -0.633767 0.760037 -0.888787 -0.0668813 -0.453415 -0.915611 -0.146452 -0.374445 -0.941998 -0.279569 -0.18569 -0.934461 -0.337274 -0.114143 -0.882429 -0.458646 0.104706 -0.855459 -0.4931 0.158249 -0.716923 -0.582578 0.382915 -0.686642 -0.597443 0.414229 -0.465028 -0.636394 0.615429 -0.445558 -0.639126 0.626894 -0.156997 -0.613498 0.773933 -0.157557 -0.613548 0.773779 -0.755315 -0.0589181 -0.652708 -0.824041 -0.188323 -0.534313 -0.871831 -0.304875 -0.383357 -0.879577 -0.395587 -0.264301 -0.860565 -0.506089 -0.0574644 -0.830269 -0.556087 0.0376871 -0.722324 -0.633172 0.278103 -0.68126 -0.650363 0.336026 -0.47596 -0.666467 0.573832 -0.449597 -0.666358 0.594836 -0.157458 -0.599901 0.784427 -0.163142 -0.601381 0.782129 -0.679038 -0.122347 -0.723836 -0.683511 -0.154468 -0.713409 -0.801395 -0.383372 -0.459121 -0.797757 -0.406386 -0.445459 -0.801557 -0.58499 -0.123665 -0.793238 -0.598587 -0.111655 -0.67929 -0.696511 0.231165 -0.670699 -0.702322 0.238551 -0.453189 -0.700858 0.550834 -0.448381 -0.702021 0.553282 -0.157721 -0.597486 0.786215 -0.159363 -0.597517 0.785861 -0.474356 -0.161637 -0.865367 -0.49611 -0.0686518 -0.865542 -0.695011 -0.412162 -0.589137 -0.707335 -0.482978 -0.516149 -0.726189 -0.642173 -0.245488 -0.712838 -0.67791 -0.179722 -0.632294 -0.761668 0.141659 -0.609775 -0.770704 0.184906 -0.427206 -0.748561 0.507101 -0.412641 -0.745823 0.522948 -0.14495 -0.602128 0.785132 -0.150994 -0.605209 0.781616 -0.345266 -0.167258 -0.923481 -0.361273 -0.237389 -0.901736 -0.468834 -0.523322 -0.711568 -0.470311 -0.56892 -0.674639 -0.505475 -0.779569 -0.369821 -0.497164 -0.801451 -0.332422 -0.449245 -0.892477 0.0407907 -0.437678 -0.896582 0.0676725 -0.308432 -0.839082 0.448119 -0.301044 -0.835943 0.458881 -0.10719 -0.623671 0.774303 -0.110178 -0.626271 0.771781 -0.120609 -0.218421 -0.968373 -0.118101 -0.241216 -0.963259 -0.167653 -0.608824 -0.775388 -0.164276 -0.623157 -0.764649 -0.182921 -0.880352 -0.43763 -0.179233 -0.886804 -0.425975 -0.16384 -0.986336 -0.0172713 -0.160626 -0.986981 -0.00828477 -0.113276 -0.90463 0.410868 -0.111547 -0.903075 0.414743 -0.0401571 -0.644223 0.763783 -0.0407068 -0.645169 0.762954 0.181042 -0.967457 0.176782 0.546266 -0.815021 0.193223 0.82491 -0.536088 0.179257 0.974855 -0.175496 0.137325 0.967569 -0.205309 0.147171 0.944985 -0.188035 0.267668 0.942499 -0.192881 0.272933 0.174369 -0.968591 0.177276 0.171368 -0.966658 0.190275 0.169508 -0.966812 0.191158 0.164541 -0.96401 0.208833 0.152535 -0.966678 0.205588 0.142816 -0.964751 0.221042 0.140214 -0.965071 0.221312 0.127727 -0.962537 0.239183 0.116716 -0.965794 0.231559 0.0992927 -0.964301 0.245487 0.0969634 -0.964682 0.24492 0.0757144 -0.96257 0.260243 0.069802 -0.965215 0.251969 0.0443681 -0.964336 0.260936 0.0431522 -0.964608 0.260134 0.533372 -0.822958 0.195589 0.520204 -0.814866 0.255699 0.517102 -0.816205 0.25771 0.494916 -0.802966 0.332121 0.478673 -0.813917 0.329258 0.438288 -0.807042 0.395711 0.434941 -0.808465 0.396497 0.387682 -0.797742 0.461856 0.375359 -0.807749 0.454586 0.312531 -0.803632 0.506459 0.309846 -0.80487 0.506141 0.240335 -0.796691 0.554547 0.234117 -0.80386 0.546808 0.153721 -0.802418 0.576625 0.152374 -0.803164 0.575943 0.0148163 -0.963156 0.268534 0.0305574 -0.945534 0.324086 0.0626417 -0.796956 0.600781 0.0746249 -0.761529 0.64382 0.103935 -0.578983 0.808688 0.811235 -0.554725 0.184873 0.79152 -0.541738 0.282872 0.788126 -0.544841 0.286367 0.749676 -0.523388 0.405033 0.733944 -0.545171 0.405111 0.671244 -0.534296 0.51377 0.667726 -0.537045 0.515486 0.59069 -0.519989 0.617006 0.579594 -0.537401 0.612593 0.482245 -0.531045 0.696729 0.4795 -0.533154 0.697013 0.370372 -0.520474 0.769371 0.364827 -0.532106 0.764045 0.241969 -0.529951 0.812775 0.240502 -0.531192 0.8124 0.105349 -0.521986 0.846423 0.121075 -0.418829 0.899957 0.920196 -0.181375 0.346903 0.916873 0.0877434 0.389416 0.858373 -0.195845 0.474173 0.808591 -0.185408 0.558395 0.805543 -0.189364 0.561464 0.709169 -0.1709 0.684012 0.70211 -0.194612 0.684958 0.584886 -0.184546 0.789842 0.582357 -0.187347 0.791051 0.448534 -0.174413 0.876583 0.444655 -0.189497 0.875427 0.296935 -0.184505 0.936903 0.295435 -0.186132 0.937055 0.138691 -0.178216 0.974168 0.137464 -0.184938 0.973089 -0.000200416 -0.220069 -0.975484 -0.000199898 -0.220084 -0.975481 -0.000563323 -0.617561 -0.786523 -0.000561102 -0.61761 -0.786485 -0.000817357 -0.89543 -0.445202 -0.00081354 -0.895477 -0.445107 -0.000913377 -0.999844 -0.0176564 -0.000907773 -0.999846 -0.0175023 -0.000832809 -0.910579 0.413334 -0.000825764 -0.9105 0.413508 -0.000591297 -0.644929 0.764242 -0.000582769 -0.644753 0.764391 -0.000423127 -0.220028 -0.975493 -0.000421677 -0.220069 -0.975484 -0.0011891 -0.617445 -0.786613 -0.00118403 -0.61756 -0.786523 -0.00172471 -0.895327 -0.445405 -0.00171663 -0.895429 -0.445202 -0.00192713 -0.999837 -0.0179647 -0.00191592 -0.999842 -0.0176564 -0.00175762 -0.910747 0.412962 -0.00174244 -0.910578 0.413334 -0.00124875 -0.645301 0.763928 -0.00123029 -0.644928 0.764242 0.180929 -0.962688 0.201237 0.946493 -0.230415 0.225962 0.552569 -0.595087 0.583558 0.83011 -0.398119 0.390407 0.991366 -0.0936178 0.0918115 0.189187 -0.77277 0.605834 0.189247 -0.701037 0.687555 0.190729 -0.700886 0.6873 0.285472 -0.815627 0.503248 0.187369 -0.838387 0.51186 0.187374 -0.772992 0.606114 0.185802 -0.865004 0.466096 0.185494 -0.892917 0.410234 0.18365 -0.893196 0.410455 0.183786 -0.930561 0.316669 0.393446 -0.874463 0.283751 0.182306 -0.947638 0.262195 0.182107 -0.962486 0.20114 0.551647 -0.595484 0.584025 0.55152 -0.656467 0.514661 0.550425 -0.657 0.515155 0.550413 -0.712619 0.434994 0.54927 -0.713229 0.435439 0.549266 -0.75934 0.34887 0.548154 -0.759978 0.349229 0.548168 -0.795544 0.258112 0.54719 -0.796136 0.25836 0.547365 -0.819197 0.171195 0.546792 -0.819557 0.171302 0.829765 -0.398465 0.39079 0.82968 -0.439322 0.344423 0.829231 -0.439824 0.344863 0.829224 -0.47706 0.291205 0.828744 -0.477649 0.291609 0.828741 -0.508529 0.233638 0.828293 -0.509117 0.233948 0.828301 -0.532935 0.172909 0.827929 -0.533448 0.173107 0.828047 -0.548804 0.114682 0.827866 -0.549063 0.114751 0.980589 -0.141546 0.135684 0.980556 -0.154437 0.121073 0.980509 -0.154615 0.121227 0.980508 -0.167706 0.102367 0.980456 -0.167921 0.102512 0.980456 -0.178777 0.0821328 0.980402 -0.179014 0.0822551 0.980403 -0.187386 0.0607918 0.980351 -0.187631 0.0608839 0.980368 -0.193008 0.0403267 0.980354 -0.193075 0.0403437 0.0288495 -0.645075 0.763574 0.119354 -0.992692 -0.0178322 0.133267 -0.887408 -0.441302 0.121457 -0.613061 -0.780644 0.0859215 -0.219414 -0.971841 0.120902 -0.992582 -0.0127798 0.407647 -0.912821 0.0241185 0.406309 -0.91205 0.0554873 0.604402 -0.786418 0.127455 0.595456 -0.786086 0.165833 0.699398 -0.67716 0.228684 0.671671 -0.682516 0.28815 0.723234 -0.599881 0.342162 0.682944 -0.610924 0.400449 0.702582 -0.562126 0.436341 0.663744 -0.574269 0.479227 0.136126 -0.890373 -0.434402 0.456098 -0.801073 -0.38763 0.462986 -0.816424 -0.345102 0.692005 -0.671499 -0.264987 0.694818 -0.688949 -0.206342 0.82208 -0.554653 -0.128628 0.809219 -0.586566 -0.0332534 0.879928 -0.473392 0.040344 0.849088 -0.510036 0.137522 0.879662 -0.434758 0.19282 0.843973 -0.465964 0.265682 0.125848 -0.620479 -0.77406 0.419408 -0.542478 -0.727883 0.440086 -0.580187 -0.685352 0.657899 -0.440227 -0.61104 0.685338 -0.48283 -0.545149 0.814669 -0.346182 -0.465266 0.841082 -0.413231 -0.34903 0.92046 -0.285772 -0.266621 0.924776 -0.354168 -0.139124 0.962515 -0.26164 -0.0714846 0.948507 -0.315425 0.0290274 0.091944 -0.231487 -0.968483 0.302306 -0.179333 -0.93619 0.341369 -0.24104 -0.908497 0.507291 -0.131934 -0.851616 0.568719 -0.199404 -0.797995 0.678365 -0.0841539 -0.72989 0.763757 -0.184899 -0.618456 0.839953 -0.0618167 -0.539127 0.90248 -0.159911 -0.399949 0.942517 -0.0615064 -0.328448 0.968292 -0.136035 -0.209535 0.0286652 -0.645853 0.762924 0.0982818 -0.628709 0.771405 0.0997085 -0.632106 0.76844 0.14045 -0.605148 0.783626 0.14411 -0.608992 0.779975 0.15428 -0.598469 0.78615 0.16009 -0.601629 0.782569 0.154652 -0.610444 0.776814 0.156629 -0.611054 0.775938 0.148995 -0.630345 0.761883 0.145955 -0.629792 0.762928 0.139722 -0.655241 0.742386 0.19097 -0.655667 0.7305 0.988196 -0.147348 0.0419095 0.99163 -0.0313092 -0.12526 0.94398 -0.272446 0.18621 0.970261 -0.216883 0.107494 0.828905 -0.421177 0.368138 0.860652 -0.393472 0.323199 0.552982 -0.578336 0.599783 0.67278 -0.536701 0.509234 0.426805 -0.618472 0.659796 0.423891 -0.630558 0.650163 0.449977 -0.629841 0.633104 0.443581 -0.645897 0.621332 0.470344 -0.647917 0.59915 0.445475 -0.687979 0.57292 0.464596 -0.693188 0.551037 0.401902 -0.758343 0.513216 0.409402 -0.763745 0.499083 0.278214 -0.848528 0.450108 0.281237 -0.85443 0.436869 0.0827576 -0.906752 0.413464 0.0822422 -0.907698 0.411486 -0.0748258 -0.580258 0.810988 -0.0340263 -0.869184 0.493317 -0.00735308 -0.964205 0.265055 -0.0428912 -0.762787 0.645225 -0.0680242 -0.420407 0.904782 -0.101698 -0.185298 0.977406 -0.101143 -0.181003 0.978268 -0.226215 -0.185945 0.956165 -0.225207 -0.184484 0.956686 -0.00725301 -0.963638 0.267111 -0.0307612 -0.96457 0.262028 -0.030302 -0.964296 0.263087 -0.0590149 -0.965052 0.255328 -0.0616676 -0.962596 0.26383 -0.0870846 -0.964771 0.24826 -0.0869831 -0.964184 0.250568 -0.10886 -0.965755 0.235516 -0.116725 -0.962259 0.245832 -0.13326 -0.965096 0.225459 -0.13413 -0.964359 0.22808 -0.147335 -0.966561 0.209888 -0.158131 -0.963317 0.21683 -0.165464 -0.966515 0.196141 -0.166812 -0.965914 0.197947 -0.172351 -0.968567 0.17937 -0.181029 -0.9666 0.18142 -0.0466358 -0.79943 0.598947 -0.114768 -0.802859 0.585017 -0.114182 -0.802175 0.58607 -0.199673 -0.803049 0.561466 -0.202185 -0.796616 0.56967 -0.279114 -0.804525 0.524247 -0.278794 -0.803073 0.526638 -0.349622 -0.806818 0.476245 -0.357797 -0.796933 0.486703 -0.413671 -0.807741 0.420037 -0.414453 -0.805705 0.423164 -0.462914 -0.812548 0.354227 -0.476505 -0.801021 0.362366 -0.505661 -0.814643 0.284013 -0.507514 -0.812492 0.286855 -0.529797 -0.822272 0.207806 -0.545664 -0.81108 0.210715 -0.0794033 -0.525655 0.846984 -0.183042 -0.53086 0.827456 -0.182258 -0.529732 0.828351 -0.31185 -0.531016 0.787891 -0.313489 -0.520695 0.794104 -0.432469 -0.532803 0.727387 -0.431702 -0.530452 0.729558 -0.540042 -0.536148 0.648768 -0.54637 -0.51946 0.656994 -0.635697 -0.536385 0.55514 -0.635851 -0.532798 0.558408 -0.710526 -0.543469 0.446984 -0.722505 -0.521655 0.453721 -0.771779 -0.543512 0.330079 -0.773258 -0.539196 0.333676 -0.806363 -0.554726 0.20508 -0.822508 -0.529719 0.207071 -0.307418 -0.187203 0.932979 -0.400007 0.103521 0.910647 -0.437933 -0.180349 0.880732 -0.525972 -0.187244 0.829634 -0.524543 -0.184196 0.83122 -0.654808 -0.193514 0.730602 -0.656975 -0.171223 0.734211 -0.768043 -0.189399 0.61175 -0.766938 -0.184477 0.614634 -0.85641 -0.199945 0.476008 -0.86165 -0.168489 0.478717 -0.924914 -0.192877 0.327616 -0.924831 -0.186438 0.331556 -0.962864 -0.207981 0.172156 -0.970563 -0.168765 0.171833 -0.180937 -0.96292 0.200119 -0.546826 -0.819731 0.170363 -0.827877 -0.549177 0.114125 -0.980356 -0.193112 0.0401235 -0.182113 -0.962696 0.200128 -0.182295 -0.947985 0.260946 -0.410006 -0.867963 0.280241 -0.183771 -0.930607 0.316543 -0.18363 -0.893164 0.410534 -0.185502 -0.892809 0.410464 -0.185813 -0.864854 0.466371 -0.262045 -0.826751 0.497811 -0.18727 -0.839275 0.510439 -0.187169 -0.78079 0.596099 -0.188975 -0.780465 0.595955 -0.18897 -0.705521 0.683031 -0.190664 -0.705232 0.682858 -0.547343 -0.819394 0.170321 -0.547115 -0.796575 0.257165 -0.548114 -0.795937 0.257014 -0.548117 -0.759965 0.349316 -0.549264 -0.759255 0.349057 -0.549421 -0.71583 0.430957 -0.550433 -0.715227 0.430666 -0.5503 -0.66366 0.506681 -0.551438 -0.663026 0.506274 -0.551425 -0.599358 0.580259 -0.552415 -0.59885 0.579841 -0.828043 -0.548934 0.114088 -0.827889 -0.533766 0.17232 -0.828312 -0.533162 0.17216 -0.828314 -0.509063 0.233991 -0.828757 -0.508452 0.233749 -0.828863 -0.479295 0.288553 -0.829271 -0.478757 0.288272 -0.829181 -0.444295 0.339205 -0.829619 -0.443757 0.338839 -0.829612 -0.401147 0.388362 -0.830037 -0.400669 0.387947 -0.980379 -0.192996 0.040105 -0.980357 -0.187694 0.0605922 -0.9804 -0.187486 0.0605356 -0.980401 -0.179012 0.0822784 -0.980454 -0.178765 0.0821782 -0.98047 -0.168495 0.101435 -0.980521 -0.168269 0.101315 -0.980508 -0.156171 0.119228 -0.980554 -0.15598 0.119096 -0.980553 -0.141004 0.136505 -0.980604 -0.140813 0.136337 0.00866715 -0.869523 0.493816 0.00443474 -0.945753 0.324857 0.00197047 -0.42046 0.907309 0.00304574 -0.245469 0.9694 0.00086639 -0.184919 0.982753 0.00961787 -0.964172 0.265105 0.00752999 -0.945787 0.3247 0.00442822 -0.945807 0.324699 0.00357587 -0.762986 0.646406 0.00761166 -0.7632 0.646117 0.00422189 -0.677253 0.735738 0.00570263 -0.677242 0.735738 0.00272167 -0.581005 0.813896 0.00184409 -0.18499 0.982739 0.000553093 -0.245487 0.9694 0.00419372 -0.420622 0.907226 0.00579221 -0.581203 0.813738 -0.190975 -0.657255 0.729071 -0.135293 -0.665867 0.733701 -0.411136 -0.619107 0.669084 -0.552928 -0.580514 0.597724 -0.651883 -0.529324 0.543014 -0.829667 -0.409009 0.379954 -0.99821 -0.0442852 -0.040189 -0.97868 -0.178962 0.100788 -0.957707 -0.230377 0.172408 -0.838827 -0.399022 0.370337 -0.140171 -0.635891 0.758943 -0.146789 -0.636074 0.757538 -0.409067 -0.631834 0.65837 -0.449856 -0.624329 0.638626 -0.644147 -0.575575 0.503773 -0.704992 -0.546497 0.452027 -0.826005 -0.471988 0.308129 -0.885085 -0.411179 0.218075 -0.939887 -0.32998 0.0879023 -0.971707 -0.23309 -0.0381388 -0.977079 -0.161379 -0.138832 -0.884557 -0.0790052 -0.459692 -0.931415 -0.107863 -0.347608 -0.95656 -0.031015 -0.289882 -0.16067 -0.603184 0.781252 -0.15518 -0.601742 0.78347 -0.447304 -0.668703 0.593932 -0.473748 -0.668841 0.572901 -0.679382 -0.652833 0.335038 -0.72047 -0.635647 0.277265 -0.828865 -0.558245 0.0366734 -0.859263 -0.508222 -0.0581198 -0.878633 -0.397069 -0.265217 -0.871174 -0.306309 -0.383706 -0.15726 -0.599156 0.785036 -0.155597 -0.599127 0.785389 -0.446167 -0.70416 0.552353 -0.450967 -0.702993 0.549936 -0.668689 -0.704557 0.237601 -0.677248 -0.698773 0.230332 -0.791655 -0.600516 -0.112531 -0.799976 -0.58701 -0.124329 -0.796739 -0.40767 -0.446108 -0.80049 -0.384754 -0.459543 -0.15468 -0.615555 0.772765 -0.154369 -0.615526 0.77285 -0.443233 -0.641735 0.625876 -0.462696 -0.639013 0.614471 -0.684996 -0.600145 0.413044 -0.715138 -0.585341 0.382038 -0.85439 -0.495388 0.156869 -0.881243 -0.461093 0.103945 -0.933748 -0.338755 -0.115587 -0.94137 -0.281304 -0.186253 -0.883923 -0.0781249 -0.461061 -0.823507 -0.18891 -0.534929 -0.75531 -0.0593929 -0.652671 -0.683121 -0.154835 -0.713703 -0.473968 -0.0581996 -0.878617 -0.651256 -0.154805 -0.742901 -0.678891 -0.122927 -0.723876 -0.108258 -0.627431 0.77111 -0.105177 -0.624738 0.773719 -0.298502 -0.837359 0.45796 -0.305743 -0.840448 0.447403 -0.434941 -0.897985 0.0667118 -0.446426 -0.893922 0.0400839 -0.494731 -0.802583 -0.33332 -0.50305 -0.780889 -0.370342 -0.468589 -0.569633 -0.675235 -0.467291 -0.524309 -0.711856 -0.165745 -0.609155 -0.775538 -0.162393 -0.623182 -0.765031 -0.180155 -0.880767 -0.437942 -0.176538 -0.887053 -0.426581 -0.160748 -0.986836 -0.0177256 -0.157639 -0.987455 -0.00904022 -0.110466 -0.90522 0.410335 -0.108834 -0.903746 0.414003 -0.0381794 -0.644887 0.763324 -0.0388021 -0.645966 0.762379 -0.148986 -0.60667 0.780868 -0.142895 -0.603549 0.784417 -0.410386 -0.747721 0.522012 -0.424856 -0.750457 0.506273 -0.607563 -0.772682 0.183929 -0.630024 -0.763684 0.140914 -0.710976 -0.67963 -0.180597 -0.724423 -0.643931 -0.246098 -0.706069 -0.484115 -0.516816 -0.694042 -0.413433 -0.589389 -0.531943 -0.119552 -0.838298 -0.360581 -0.237536 -0.901975 -0.344928 -0.167776 -0.923513 -0.117412 -0.241042 -0.963386 -0.119942 -0.218722 -0.968388 0.195051 -0.964436 0.178378 0.554739 -0.809094 0.193989 0.828292 -0.530703 0.179682 0.975207 -0.173082 0.137893 0.967933 -0.203171 0.147739 0.945138 -0.186087 0.268487 0.942696 -0.19087 0.273665 0.188467 -0.965655 0.17886 0.185511 -0.963788 0.191569 0.183744 -0.963958 0.192414 0.178881 -0.961278 0.209634 0.16694 -0.964123 0.206395 0.157421 -0.962369 0.221503 0.154838 -0.962727 0.221767 0.14248 -0.960403 0.239426 0.131452 -0.963853 0.23175 0.114141 -0.962633 0.245579 0.111776 -0.963059 0.244995 0.0905162 -0.961273 0.26031 0.0847051 -0.963984 0.252112 0.0591743 -0.963494 0.261108 0.0580118 -0.963773 0.26034 0.541928 -0.81717 0.196334 0.528761 -0.809243 0.256004 0.525769 -0.810571 0.257957 0.503754 -0.797726 0.331459 0.487981 -0.808626 0.328632 0.447925 -0.802364 0.394429 0.444705 -0.803785 0.39518 0.397698 -0.793819 0.460095 0.386074 -0.803506 0.453129 0.323444 -0.800348 0.504804 0.32099 -0.801525 0.504503 0.25151 -0.794425 0.55284 0.245999 -0.800965 0.545838 0.165589 -0.80076 0.575643 0.164454 -0.801408 0.575065 0.0294678 -0.962745 0.2688 0.0449846 -0.944795 0.324561 0.0745965 -0.796566 0.599932 0.0863015 -0.76006 0.644097 0.112663 -0.577135 0.80884 0.814685 -0.549511 0.185272 0.794883 -0.536739 0.282972 0.79157 -0.539807 0.286402 0.753304 -0.518906 0.404067 0.738268 -0.540089 0.404061 0.675806 -0.530163 0.512068 0.672523 -0.53279 0.513661 0.595692 -0.516888 0.614799 0.585657 -0.533024 0.610648 0.488428 -0.528174 0.6946 0.486033 -0.530071 0.694836 0.376841 -0.519047 0.76719 0.372349 -0.528823 0.762694 0.249417 -0.528564 0.811426 0.248345 -0.529495 0.811147 0.113159 -0.522352 0.845188 0.127517 -0.416796 0.900012 0.920628 -0.179726 0.346617 0.916099 0.0920922 0.390233 0.859348 -0.19363 0.473318 0.80927 -0.183882 0.557916 0.806475 -0.187583 0.560723 0.71 -0.170417 0.68327 0.703862 -0.191774 0.68396 0.586414 -0.183559 0.788939 0.584283 -0.185989 0.789951 0.45011 -0.17501 0.875655 0.44724 -0.186853 0.874678 0.299204 -0.184164 0.936248 0.298209 -0.185272 0.936347 0.141072 -0.179699 0.973554 0.140565 -0.182762 0.973057 0.000423206 -0.220069 -0.975484 0.000421597 -0.220028 -0.975493 0.00118932 -0.61756 -0.786523 0.0011838 -0.617445 -0.786613 0.00172491 -0.895429 -0.445202 0.00171643 -0.895327 -0.445405 0.00192715 -0.999842 -0.0176563 0.0019159 -0.999837 -0.0179646 0.00175731 -0.910578 0.413334 0.00174275 -0.910747 0.412962 0.00124805 -0.644928 0.764242 0.00123099 -0.645301 0.763928 0.000200429 -0.220084 -0.975481 0.000199885 -0.220069 -0.975484 0.000563368 -0.61761 -0.786484 0.000561058 -0.617561 -0.786523 0.000817402 -0.895477 -0.445107 0.000813496 -0.89543 -0.445202 0.000913382 -0.999846 -0.0175023 0.000907768 -0.999844 -0.0176563 0.000832739 -0.9105 0.413508 0.000825834 -0.910579 0.413334 0.000591142 -0.644753 0.764391 0.000582925 -0.644929 0.764242 0.194928 -0.959539 0.203193 0.946791 -0.229097 0.226056 0.555036 -0.592106 0.584247 0.831105 -0.395851 0.390597 0.991427 -0.0930064 0.0917719 0.194782 -0.769823 0.60781 0.194843 -0.698173 0.688906 0.194829 -0.698174 0.688908 0.294905 -0.811396 0.504647 0.194745 -0.835385 0.514011 0.19475 -0.769827 0.607815 0.195076 -0.861764 0.468304 0.194753 -0.889901 0.41249 0.194746 -0.889902 0.412491 0.194893 -0.927535 0.318897 0.406549 -0.86817 0.284604 0.195009 -0.944497 0.264378 0.194795 -0.959564 0.203205 0.555038 -0.592106 0.584247 0.554911 -0.652928 0.515518 0.554917 -0.652926 0.515515 0.554905 -0.708534 0.435959 0.554878 -0.708548 0.435969 0.554872 -0.754793 0.349865 0.554872 -0.754793 0.349865 0.554888 -0.790531 0.259152 0.554901 -0.790523 0.259149 0.555074 -0.813755 0.172322 0.555268 -0.813631 0.172285 0.831107 -0.39585 0.390595 0.831022 -0.436568 0.344691 0.831033 -0.436556 0.34468 0.831025 -0.47374 0.291492 0.831023 -0.473743 0.291494 0.831019 -0.504665 0.233925 0.831019 -0.504665 0.233924 0.83103 -0.528551 0.173269 0.831024 -0.52856 0.173273 0.83114 -0.544002 0.115191 0.831262 -0.543824 0.115143 0.980757 -0.140511 0.135542 0.980725 -0.153355 0.12108 0.980724 -0.153358 0.121083 0.980723 -0.166422 0.1024 0.980724 -0.166418 0.102397 0.980724 -0.177281 0.0821742 0.980724 -0.177281 0.0821741 0.980725 -0.18567 0.0608663 0.980726 -0.185665 0.0608646 0.980743 -0.191066 0.0404542 0.980762 -0.190977 0.0404309 0.030161 -0.644451 0.76405 0.119928 -0.992631 -0.0173759 0.133242 -0.887481 -0.441162 0.120822 -0.61305 -0.780751 0.0847594 -0.219255 -0.971979 0.121525 -0.992512 -0.0123167 0.406894 -0.913169 0.0236476 0.405652 -0.912367 0.0550654 0.604745 -0.786276 0.126706 0.595918 -0.785889 0.165105 0.701116 -0.67554 0.228215 0.673099 -0.68097 0.288475 0.724922 -0.597545 0.342677 0.684877 -0.60851 0.400823 0.704525 -0.559464 0.436629 0.665594 -0.571677 0.47976 0.13617 -0.890429 -0.434274 0.454427 -0.801656 -0.388386 0.461424 -0.816949 -0.345952 0.691344 -0.671652 -0.266322 0.694345 -0.688998 -0.207766 0.822875 -0.553195 -0.129817 0.810008 -0.585479 -0.0331861 0.880939 -0.471497 0.0404671 0.850332 -0.507936 0.137613 0.880829 -0.432473 0.192635 0.845026 -0.46383 0.266068 0.125264 -0.620382 -0.774232 0.417061 -0.543052 -0.728803 0.437789 -0.580631 -0.686446 0.656185 -0.440486 -0.612694 0.683805 -0.482917 -0.546994 0.814211 -0.344992 -0.466948 0.841217 -0.412827 -0.349181 0.920745 -0.284627 -0.266863 0.925318 -0.352674 -0.139312 0.962903 -0.260042 -0.0720905 0.948947 -0.314075 0.0292863 0.090817 -0.231161 -0.968668 0.299628 -0.179655 -0.936988 0.338627 -0.241172 -0.909488 0.504647 -0.132133 -0.853155 0.56619 -0.199397 -0.799793 0.676537 -0.0833615 -0.731675 0.763327 -0.185268 -0.618876 0.839565 -0.0615786 -0.539758 0.902383 -0.159211 -0.400445 0.942217 -0.0607893 -0.329442 0.968376 -0.135731 -0.209344 0.0300003 -0.645105 0.763505 0.0994569 -0.628088 0.77176 0.100787 -0.631287 0.768973 0.142071 -0.604004 0.784216 0.145658 -0.607791 0.780624 0.156341 -0.596739 0.787058 0.162339 -0.599989 0.783364 0.157214 -0.608345 0.777946 0.159496 -0.609046 0.776933 0.152017 -0.628022 0.763203 0.149407 -0.627554 0.764103 0.143256 -0.652836 0.74383 0.195074 -0.653135 0.731683 0.988284 -0.146674 0.0422149 0.991611 -0.0308852 -0.125518 0.9443 -0.271082 0.186577 0.9706 -0.215444 0.107324 0.829908 -0.418926 0.368447 0.861634 -0.391224 0.323312 0.555444 -0.57549 0.600245 0.674616 -0.533929 0.509719 0.429534 -0.615696 0.66062 0.426607 -0.627922 0.650939 0.452568 -0.627165 0.633913 0.446084 -0.643513 0.622013 0.472592 -0.6455 0.599988 0.44743 -0.686243 0.573478 0.466756 -0.691491 0.551343 0.403066 -0.757708 0.513241 0.41055 -0.763154 0.499045 0.27849 -0.84839 0.450197 0.281496 -0.854367 0.436826 0.083836 -0.906352 0.414123 0.0832859 -0.907331 0.412085 -0.0288495 -0.645075 -0.763574 -0.0822419 -0.907697 -0.411488 -0.119354 -0.992692 0.0178322 -0.133262 -0.887408 0.441302 -0.121455 -0.613058 0.780646 -0.0859211 -0.219401 0.971844 -0.0286652 -0.645853 -0.762924 -0.0982823 -0.628709 -0.771405 -0.0997046 -0.632095 -0.768449 -0.14044 -0.605142 -0.783633 -0.144109 -0.608994 -0.779974 -0.154281 -0.598469 -0.78615 -0.160095 -0.601631 -0.782566 -0.154658 -0.610446 -0.776812 -0.156614 -0.611049 -0.775945 -0.148978 -0.630343 -0.761888 -0.145962 -0.629794 -0.762925 -0.139729 -0.655241 -0.742385 -0.126138 -0.654826 -0.745179 -0.0827573 -0.906751 -0.413466 -0.281236 -0.854426 -0.436878 -0.278217 -0.848531 -0.450101 -0.409404 -0.763749 -0.499075 -0.401896 -0.758341 -0.513223 -0.464589 -0.693187 -0.551044 -0.445474 -0.68798 -0.572919 -0.470345 -0.647916 -0.59915 -0.443577 -0.645895 -0.621336 -0.449971 -0.629843 -0.633107 -0.423873 -0.63056 -0.650174 -0.426215 -0.620889 -0.657904 -0.379375 -0.628464 -0.679049 -0.120901 -0.992582 0.0127844 -0.40765 -0.91282 -0.0241053 -0.406311 -0.912049 -0.0554741 -0.604406 -0.786418 -0.127436 -0.595456 -0.786087 -0.16583 -0.6994 -0.67716 -0.22868 -0.671668 -0.682517 -0.288155 -0.723231 -0.599881 -0.342169 -0.682963 -0.610919 -0.400425 -0.702603 -0.562117 -0.436319 -0.663767 -0.574261 -0.479205 -0.674054 -0.530782 -0.513733 -0.606285 -0.558303 -0.566318 -0.136125 -0.890377 0.434396 -0.456098 -0.801076 0.387625 -0.462986 -0.816427 0.345097 -0.692006 -0.6715 0.264983 -0.694818 -0.688949 0.206342 -0.82208 -0.554653 0.128628 -0.809218 -0.586566 0.0332527 -0.879928 -0.473391 -0.0403432 -0.849088 -0.510036 -0.137522 -0.879662 -0.434758 -0.19282 -0.84397 -0.465967 -0.265687 -0.860649 -0.393474 -0.323206 -0.791134 -0.449268 -0.415049 -0.12585 -0.620482 0.774057 -0.419411 -0.542489 0.727874 -0.440085 -0.58019 0.68535 -0.657902 -0.440235 0.611031 -0.685333 -0.482827 0.545158 -0.814668 -0.346176 0.465273 -0.841081 -0.413227 0.349036 -0.92046 -0.285769 0.266626 -0.924776 -0.354167 0.139124 -0.962515 -0.26164 0.0714847 -0.948507 -0.315424 -0.0290268 -0.969567 -0.221783 -0.103695 -0.921308 -0.309016 -0.236012 -0.0919482 -0.231483 0.968484 -0.3023 -0.179324 0.936193 -0.34137 -0.241044 0.908496 -0.507287 -0.131933 0.851618 -0.568717 -0.199406 0.797996 -0.678365 -0.0841539 0.72989 -0.763762 -0.184907 0.618447 -0.839957 -0.0618229 0.539119 -0.902477 -0.159906 0.399957 -0.942515 -0.0615019 0.328454 -0.968297 -0.136057 0.209498 -0.991633 -0.0313383 0.125224 -0.988196 -0.14735 -0.0419064 -0.378953 -0.659937 -0.648751 -0.791728 -0.436151 -0.427715 -0.606001 -0.56792 -0.556983 -0.923278 -0.273474 -0.269758 -0.991338 -0.0960743 -0.0895477 -0.185483 -0.892918 -0.410235 -0.185484 -0.838692 -0.512047 -0.18737 -0.838432 -0.511786 -0.187375 -0.772992 -0.606114 -0.189187 -0.77277 -0.605834 -0.189268 -0.702593 -0.685959 -0.125994 -0.708292 -0.694584 -0.321268 -0.898752 -0.298383 -0.183651 -0.934989 -0.303427 -0.183643 -0.893197 -0.410456 -0.182321 -0.949554 -0.255159 -0.182108 -0.962486 -0.20114 -0.180929 -0.962688 -0.201237 -0.551695 -0.59703 -0.582398 -0.551516 -0.65647 -0.514662 -0.550425 -0.657 -0.515154 -0.550413 -0.712618 -0.434995 -0.54927 -0.713228 -0.43544 -0.549266 -0.75934 -0.34887 -0.548156 -0.759976 -0.349228 -0.54817 -0.795543 -0.258111 -0.54719 -0.796136 -0.258359 -0.547365 -0.819197 -0.171196 -0.546809 -0.819546 -0.171299 -0.829817 -0.399968 -0.389141 -0.82968 -0.439323 -0.344422 -0.829233 -0.439823 -0.34486 -0.829226 -0.477058 -0.291205 -0.828761 -0.477626 -0.291596 -0.828759 -0.508506 -0.233627 -0.828309 -0.509095 -0.233938 -0.828318 -0.532912 -0.1729 -0.827911 -0.533473 -0.173117 -0.828029 -0.54883 -0.114687 -0.827866 -0.549064 -0.114749 -0.980576 -0.140036 -0.137334 -0.980564 -0.154409 -0.121049 -0.980509 -0.154615 -0.121227 -0.980508 -0.167706 -0.102367 -0.980456 -0.16792 -0.102512 -0.980456 -0.178776 -0.0821325 -0.980402 -0.179014 -0.0822551 -0.980403 -0.187386 -0.0607934 -0.980358 -0.187596 -0.0608727 -0.980375 -0.192973 -0.0403177 -0.980354 -0.193075 -0.0403437 0.000200401 -0.220053 0.975488 0.000199297 -0.220084 0.975481 0.000562839 -0.617561 0.786523 0.000561093 -0.617599 0.786493 0.000817358 -0.89543 0.445202 0.00081354 -0.895477 0.445107 0.000913377 -0.999844 0.0176561 0.000907783 -0.999846 0.0175023 0.000832552 -0.910576 -0.41334 0.000826022 -0.910503 -0.413502 0.000591778 -0.644939 -0.764234 0.00058229 -0.644743 -0.764399 0.000423096 -0.220012 0.975497 0.000421645 -0.220053 0.975488 0.0011891 -0.617445 0.786613 0.00118403 -0.61756 0.786523 0.00172471 -0.895327 0.445405 0.00171663 -0.895429 0.445202 0.00192713 -0.999837 0.0179647 0.00191591 -0.999842 0.017656 0.00175788 -0.910747 -0.412962 0.00174244 -0.910575 -0.41334 0.00124875 -0.645301 -0.763928 0.00123078 -0.644938 -0.764234 -0.546283 -0.815009 -0.193223 -0.82491 -0.536087 -0.179262 -0.974855 -0.175495 -0.137331 -0.967577 -0.205272 -0.147166 -0.945001 -0.188003 -0.267634 -0.942499 -0.192881 -0.272933 -0.898343 -0.171387 -0.404483 -0.90946 -0.0692544 -0.409984 -0.827902 -0.189473 -0.5279 -0.808592 -0.185406 -0.558394 -0.805541 -0.189367 -0.561466 -0.709168 -0.170903 -0.684012 -0.702111 -0.19461 -0.684958 -0.584888 -0.184544 -0.789841 -0.582338 -0.187368 -0.79106 -0.533372 -0.822957 -0.195592 -0.520204 -0.814866 -0.255699 -0.517123 -0.816196 -0.257697 -0.494931 -0.802955 -0.332124 -0.478674 -0.813917 -0.329258 -0.438289 -0.807041 -0.395711 -0.434941 -0.808465 -0.396497 -0.387682 -0.797742 -0.461856 -0.375359 -0.807749 -0.454586 -0.312531 -0.803632 -0.506459 -0.309846 -0.80487 -0.506141 -0.240334 -0.796691 -0.554547 -0.23412 -0.803855 -0.546814 -0.153726 -0.802415 -0.576627 -0.152375 -0.803163 -0.575944 -0.0148162 -0.963156 -0.268534 -0.0431528 -0.964608 -0.260133 -0.0443694 -0.964336 -0.260936 -0.0698017 -0.965215 -0.251969 -0.0757142 -0.96257 -0.260243 -0.0969634 -0.964682 -0.24492 -0.0992927 -0.964301 -0.245487 -0.116716 -0.965794 -0.231559 -0.127726 -0.962537 -0.239182 -0.140213 -0.965071 -0.221312 -0.142823 -0.96475 -0.221041 -0.152541 -0.966677 -0.205589 -0.164535 -0.964011 -0.208832 -0.169502 -0.966813 -0.191157 -0.171369 -0.966659 -0.19027 -0.174369 -0.968591 -0.177276 -0.181041 -0.967457 -0.176782 -0.0138269 -0.964145 -0.265016 -0.0500457 -0.868647 -0.492897 -0.062642 -0.796955 -0.600782 -0.0746249 -0.761529 -0.64382 -0.103934 -0.578986 -0.808686 -0.811234 -0.554725 -0.184878 -0.791525 -0.541743 -0.282848 -0.788133 -0.544844 -0.286342 -0.749676 -0.523388 -0.405033 -0.733943 -0.545172 -0.405111 -0.671242 -0.534297 -0.513771 -0.667727 -0.537044 -0.515485 -0.590691 -0.519988 -0.617007 -0.579593 -0.537403 -0.612593 -0.482245 -0.531046 -0.696728 -0.479501 -0.533154 -0.697012 -0.370372 -0.520474 -0.769371 -0.364828 -0.532104 -0.764046 -0.241971 -0.52995 -0.812775 -0.240502 -0.531192 -0.8124 -0.105349 -0.521986 -0.846423 -0.121074 -0.418836 -0.899954 -0.524196 -0.18216 -0.831887 -0.467957 0.0839564 -0.879754 -0.399775 -0.188462 -0.89703 -0.296935 -0.184505 -0.936903 -0.295435 -0.186132 -0.937055 -0.13869 -0.178215 -0.974168 -0.137463 -0.184938 -0.973089 0.61541 -0.193498 0.764087 0.998246 -0.0440441 0.0395671 0.98954 -0.133624 -0.0543533 0.95804 -0.227705 -0.174097 0.922605 -0.296271 -0.247029 0.840031 -0.393077 -0.37395 0.792751 -0.438845 -0.423038 0.65358 -0.526603 -0.54362 0.6086 -0.551598 -0.57039 0.413683 -0.617329 -0.669157 0.382673 -0.626654 -0.678871 0.139989 -0.657747 -0.740116 0.130477 -0.658749 -0.740963 0.956847 -0.0305599 0.28898 0.977426 -0.160643 0.137228 0.972117 -0.231541 0.037107 0.940368 -0.328212 -0.0893598 0.885912 -0.408816 -0.219158 0.826977 -0.469468 -0.309368 0.706499 -0.543683 -0.453066 0.645964 -0.572671 -0.504756 0.452175 -0.621572 -0.639677 0.411791 -0.629074 -0.659314 0.149797 -0.633917 -0.758756 0.143813 -0.633768 -0.760037 0.888783 -0.0668783 0.453424 0.915603 -0.146433 0.374471 0.941998 -0.279592 0.185656 0.934463 -0.337268 0.114143 0.882443 -0.458626 -0.104677 0.855459 -0.4931 -0.158249 0.716923 -0.582578 -0.382915 0.686642 -0.597443 -0.414229 0.465011 -0.636394 -0.61544 0.445558 -0.639125 -0.626895 0.157004 -0.613498 -0.773931 0.157557 -0.613548 -0.773779 0.755296 -0.0588898 0.652733 0.824038 -0.188315 0.534321 0.871831 -0.304875 0.383357 0.879576 -0.395609 0.264271 0.860563 -0.506091 0.0574657 0.83028 -0.556074 -0.0376552 0.722324 -0.633172 -0.278103 0.68126 -0.650363 -0.336026 0.475955 -0.666467 -0.573837 0.449582 -0.666357 -0.594848 0.157463 -0.599903 -0.784424 0.163148 -0.601384 -0.782125 0.679026 -0.122362 0.723845 0.683492 -0.154441 0.713433 0.801395 -0.383372 0.459121 0.797757 -0.406386 0.445459 0.801553 -0.585001 0.123637 0.793248 -0.598575 0.111648 0.6793 -0.6965 -0.231167 0.670706 -0.702314 -0.238556 0.453203 -0.700857 -0.550823 0.448371 -0.702027 -0.553283 0.157707 -0.597482 -0.786221 0.159372 -0.597513 -0.785861 0.474356 -0.161637 0.865367 0.49611 -0.0686518 0.865542 0.69502 -0.412184 0.589111 0.707338 -0.482975 0.516147 0.726193 -0.642159 0.24551 0.712833 -0.677922 0.179698 0.63229 -0.76167 -0.14166 0.609775 -0.770705 -0.184901 0.427205 -0.748562 -0.507101 0.412652 -0.745826 -0.522936 0.144962 -0.602133 -0.785125 0.150982 -0.605203 -0.781623 0.345271 -0.167257 0.923479 0.361277 -0.237386 0.901735 0.468836 -0.523308 0.711577 0.470314 -0.568941 0.674619 0.505472 -0.779568 0.369827 0.497164 -0.801445 0.332438 0.449245 -0.892477 -0.0407907 0.437677 -0.896582 -0.0676737 0.308435 -0.839085 -0.448112 0.301043 -0.835944 -0.45888 0.107179 -0.623661 -0.774312 0.110187 -0.626278 -0.771774 0.120608 -0.218425 0.968372 0.118101 -0.241216 0.963259 0.167651 -0.608809 0.7754 0.164272 -0.623154 0.764653 0.182919 -0.880353 0.43763 0.179233 -0.8868 0.425982 0.16384 -0.986336 0.0172658 0.160627 -0.98698 0.00828456 0.113279 -0.904635 -0.410858 0.111548 -0.903078 -0.414737 0.0401546 -0.644212 -0.763792 0.0407042 -0.645159 -0.762964 0.00866715 -0.869523 -0.493816 0.00761166 -0.7632 -0.646117 0.00422189 -0.677253 -0.735738 0.00579217 -0.581205 -0.813736 0.00419358 -0.420616 -0.907229 0.000553093 -0.245487 -0.9694 0.00184409 -0.18499 -0.982739 0.00443499 -0.945807 -0.3247 0.00752999 -0.945787 -0.324701 0.00961789 -0.964172 -0.265105 0.00114998 -0.245448 -0.969409 0.00115163 -0.245483 -0.9694 0.00272167 -0.581005 -0.813896 0.00570263 -0.677242 -0.735738 0.00357587 -0.762986 -0.646406 0.00442797 -0.945753 -0.324858 0.194934 -0.959715 -0.202355 0.55528 -0.813772 -0.171578 0.831271 -0.543911 -0.114673 0.980763 -0.191005 -0.0402663 0.194818 -0.959739 -0.202354 0.195035 -0.946702 -0.256352 0.337449 -0.894793 -0.292358 0.194836 -0.929877 -0.312037 0.194754 -0.889763 -0.412786 0.194762 -0.889762 -0.412786 0.194836 -0.8385 -0.508879 0.194816 -0.838503 -0.50888 0.194753 -0.777536 -0.59792 0.304937 -0.758059 -0.576507 0.195085 -0.744867 -0.638056 0.555103 -0.81389 -0.171593 0.554881 -0.79079 -0.258377 0.554855 -0.790806 -0.258381 0.55486 -0.754684 -0.350119 0.554861 -0.754683 -0.350119 0.555015 -0.711127 -0.431575 0.555038 -0.711113 -0.431569 0.55491 -0.659468 -0.507126 0.554911 -0.659468 -0.507126 0.130266 -0.710195 -0.691848 0.194786 -0.703936 -0.683032 0.382138 -0.661254 -0.645533 0.554952 -0.597236 -0.579084 0.608102 -0.56864 -0.55395 0.792845 -0.436529 -0.425251 0.83116 -0.544076 -0.114698 0.831012 -0.528747 -0.172758 0.831012 -0.528747 -0.172758 0.831015 -0.504593 -0.234095 0.831012 -0.504597 -0.234097 0.831114 -0.475402 -0.288517 0.83112 -0.475394 -0.288513 0.831033 -0.440926 -0.339069 0.83102 -0.440942 -0.33908 0.831065 -0.399753 -0.386689 0.923654 -0.273817 -0.268118 0.980744 -0.191097 -0.0402812 0.980723 -0.185741 -0.0606872 0.980722 -0.185747 -0.0606889 0.980722 -0.177261 -0.0822362 0.980723 -0.177259 -0.0822353 0.980738 -0.166984 -0.101342 0.980738 -0.166983 -0.101341 0.980725 -0.154891 -0.11911 0.980726 -0.154887 -0.119107 0.980745 -0.141254 -0.134856 0.991421 -0.0936249 -0.0912063 0.0289428 -0.94536 -0.324743 0.0554145 -0.761766 -0.645478 0.0846967 -0.578791 -0.811066 0.231241 -0.185157 -0.955115 0.105541 -0.182036 -0.977611 0.114166 -0.243594 -0.963135 0.0351368 -0.963703 -0.264654 0.0459923 -0.963903 -0.262253 0.0455556 -0.963654 -0.263241 0.0742993 -0.963976 -0.255402 0.0769332 -0.961484 -0.263875 0.102323 -0.963277 -0.248248 0.102211 -0.962702 -0.250515 0.123909 -0.963935 -0.235534 0.13179 -0.960301 -0.245875 0.148166 -0.962877 -0.225644 0.149041 -0.962121 -0.228275 0.0595928 -0.799002 -0.598368 0.128183 -0.801459 -0.584152 0.127701 -0.80092 -0.584995 0.212777 -0.800502 -0.560288 0.214942 -0.794774 -0.567569 0.291398 -0.80149 -0.522208 0.291082 -0.800171 -0.524402 0.361287 -0.80283 -0.474273 0.368944 -0.793374 -0.484188 0.424314 -0.803289 -0.417952 0.425058 -0.801315 -0.420974 0.0819264 -0.525313 -0.846956 0.192876 -0.52948 -0.826105 0.192327 -0.528727 -0.826716 0.321167 -0.528047 -0.786141 0.32239 -0.519675 -0.791203 0.440623 -0.529957 -0.724566 0.439935 -0.527966 -0.726436 0.547418 -0.531978 -0.646014 0.553027 -0.516754 -0.653549 0.641679 -0.532314 -0.552169 0.641801 -0.528994 -0.555208 0.811426 -0.190042 -0.552695 0.769083 -0.183142 -0.612348 0.770122 -0.187656 -0.60967 0.659595 -0.171043 -0.731901 0.657858 -0.190708 -0.728597 0.528368 -0.183454 -0.828958 0.529579 -0.185932 -0.827632 0.496175 -0.183993 -0.848503 0.395357 -0.0705349 -0.915815 0.370426 -0.185981 -0.910053 0.230623 -0.184302 -0.95543 0.16198 -0.964102 -0.210406 0.172728 -0.960703 -0.217291 0.472946 -0.807426 -0.352682 0.486077 -0.796063 -0.360574 0.715795 -0.538529 -0.444549 0.727173 -0.517469 -0.451049 0.888865 0.0748258 -0.452018 0.884565 -0.174913 -0.432378 0.925643 -0.184644 -0.33029 0.925739 -0.190878 -0.326456 0.77732 -0.534399 -0.331951 0.775903 -0.538606 -0.328449 0.516635 -0.807049 -0.285938 0.514825 -0.809188 -0.283144 0.181184 -0.963143 -0.198816 0.179879 -0.963747 -0.197068 0.971049 -0.166493 -0.171303 0.963448 -0.20565 -0.171684 0.82598 -0.524524 -0.206476 0.810082 -0.549472 -0.204568 0.554141 -0.805298 -0.210766 0.538583 -0.816505 -0.207959 0.195038 -0.963615 -0.182774 0.186548 -0.965667 -0.180797 0.997598 0 0.0692758 0.997598 0 0.0692758 0.971715 -0.236053 0.00707663 0.987099 0.136612 0.0834987 0.756994 -0.635673 -0.151261 0.949662 0.293327 0.110006 0.765298 -0.544764 -0.342857 0.947263 0 -0.320458 0.934787 0.0078545 -0.355123 0.932592 0.0112907 -0.360755 0.3516 0.936096 -0.0100548 0.915757 0 -0.401733 0.791502 -0.316694 -0.522713 0.884521 0.00025021 -0.466499 0.855843 -1.45257e-05 -0.517235 0.856625 0.0685198 -0.511369 0.670859 -0.359028 -0.648881 0.680325 0.684964 -0.260735 0.754674 0.0843844 -0.650651 0.603521 -0.191769 -0.773943 0.568471 0.00350755 -0.822696 0.501051 -0.00420376 -0.865408 0.255669 0.966113 -0.0354816 0.0451852 -0.841255 -0.538747 0.0356564 -0.853834 -0.519323 0.204223 0 -0.978924 0.102512 0.0397471 -0.993937 0.127422 0 -0.991849 0.00255381 -3.32279e-05 0.999997 0.00256149 -2.70742e-05 0.999997 0.0033512 0 0.999994 0.0033512 0 0.999994 0.00414591 0 0.999991 0.00414591 0 0.999991 0.00493748 0 0.999988 0.00493748 0 0.999988 0.00572603 0 0.999984 0.00572603 0 0.999984 -0.406789 0.0246186 -0.91319 -0.35885 0.900649 -0.245068 -0.432578 0.750438 -0.49972 -0.238609 -0.58249 -0.777027 -0.0731488 -0.808812 -0.583501 -0.353591 0.934578 -0.0392172 -0.360005 -0.0463694 -0.931797 -0.36944 0 -0.929255 -0.238601 0.0499924 -0.96983 -0.273694 -0.0997654 -0.956629 -0.161224 0 -0.986918 -0.571095 -0.00278581 -0.82088 -0.63256 0.00974142 -0.77445 -0.676834 0.414758 -0.608171 -0.593797 -0.302251 -0.745687 -0.646096 0.718579 -0.257302 -0.973627 0 -0.228145 -0.0182542 -0.927278 -0.373928 -0.243585 0.921404 0.302788 -0.143271 0.926787 0.347188 -0.163937 -0.848152 -0.503748 -0.830036 -0.0046846 -0.55769 -0.932892 0.00298011 -0.360144 0.0349997 -0.927974 -0.370998 -0.973627 0 -0.228145 -0.998977 0 0.0452309 -0.998977 0 0.0452309 0.0116223 0 -0.999933 0.0116223 0 -0.999932 0.0116195 -6.24307e-05 -0.999933 0.011619 0 -0.999933 0.011619 0 -0.999933 0.0116197 0 -0.999933 0.0116197 0 -0.999933 0.0116201 0 -0.999933 0.0116201 0 -0.999933 0.0116194 0 -0.999933 0.0116194 0 -0.999933 0.0116186 0 -0.999933 0.0116186 0 -0.999933 0.0116201 0 -0.999932 0.0116201 0 -0.999933 0.0116194 0 -0.999933 0.0116194 0 -0.999933 0.00651231 -2.70421e-05 0.999979 0.00650476 -3.3187e-05 0.999979 0.548537 0 0.836127 0.612011 0.0709948 0.787656 0.57639 0 0.817175 0.0116194 0 -0.999933 0.0116194 0 -0.999933 -0.606792 0 0.794861 -0.645225 0.00589571 0.76397 -0.651836 0 0.75836 -0.00569532 0.980422 0.196826 -5.69216e-07 0.121066 0.992644 5.11561e-05 0.0454248 -0.998968 -0.000311527 0.116058 -0.993242 0.00703702 0.0690445 -0.997589 0.00478926 0.0856088 -0.996317 0.00198399 0.108123 -0.994136 5.67912e-07 0.114739 -0.993396 4.60535e-06 0.114757 -0.993394 0.00280385 0.0243385 -0.9997 0.000353598 0.0191732 -0.999816 0.00908671 0.0405365 -0.999137 0.000504351 0.0261794 -0.999657 4.09964e-08 0.0344496 -0.999406 -2.38562e-06 0.0549391 -0.99849 -5.11561e-05 0.0454248 -0.998968 -0.000374048 0.0317147 -0.999497 -0.000720432 0.0235937 -0.999721 -5.67912e-07 0.114739 -0.993396 -4.60523e-06 0.114757 -0.993394 -1.3672e-05 0.0630399 -0.998011 -0.000816891 0.116058 -0.993242 -0.00382934 0.0931208 -0.995647 0.00709174 0.427999 -0.903751 0.00131293 0.413364 -0.910565 -0.00390854 0.458778 -0.888542 -0.00290917 0.445418 -0.895318 -0.000559579 0.119685 -0.992812 0.000633382 0.234535 -0.972107 -0.00179763 0.206177 -0.978513 0.00134859 0.350418 -0.936593 -0.00253293 0.311463 -0.950255 -0.000454893 0.409118 -0.912481 -0.00055741 0.408512 -0.912753 0.0153401 0.445887 -0.894958 0.0248379 0.460494 -0.887315 -0.00463805 0.421825 -0.906665 0.00094797 0.492825 -0.870128 0.00381519 0.508785 -0.860885 0.00741234 0.518438 -0.855083 -0.00177948 0.546702 -0.837325 0.00191088 0.701492 -0.712674 -0.00169026 0.608448 -0.793592 0.0238122 0.628964 -0.77707 0.00219322 0.586812 -0.80972 -0.0121231 0.90543 -0.424322 0.00483712 0.88493 -0.465699 -0.00448338 0.862242 -0.506476 0.000197735 0.855832 -0.517253 0.00019145 0.830481 -0.557047 0.00468541 0.823733 -0.566958 -0.00883545 0.7816 -0.623718 0.00227152 0.772283 -0.635274 -0.00270119 0.698169 -0.715928 -0.00127865 0.938684 -0.344777 0.000861005 0.925909 -0.377746 -0.00497835 0.911072 -0.412218 -0.0133386 0.948447 -0.316655 0.0456656 0.976672 -0.209825 -0.0737504 0.955039 -0.287161 0.00245466 0.986747 -0.162246 -0.000725325 0.987993 -0.154496 0.00286527 0.979093 -0.203394 0.000210753 0.989114 -0.147154 0.000446459 0.990892 -0.134657 0.00302501 0.992907 -0.118851 0.0021433 0.993169 -0.116662 -0.00455808 0.997677 -0.0679663 -0.0347923 0.99914 -0.022578 0.0158624 0.997263 -0.0722137 0.00450308 0.998383 -0.0566668 -0.00697609 0.999303 -0.0366835 -0.00729433 0.99926 -0.0377587 -0.0176117 0.998603 -0.0498276 -0.0256348 0.998017 -0.0574932 -0.0332189 0.997442 -0.0633007 -0.0491209 0.996125 -0.0729533 -0.0473633 0.996254 -0.0723547 -0.0330318 0.997775 0.057914 -0.0208992 0.998591 0.0487726 -0.00697701 0.999398 0.0339733 -0.0072956 0.999434 0.032831 0.0027802 0.998806 0.0487765 0.00287458 0.994078 0.108628 0.0126216 0.997976 0.0623203 0.0193428 0.997403 0.0693714 -0.0267838 0.999392 0.0223066 0.00759747 0.995776 0.0915017 0.000455801 0.992021 0.126075 0.000140587 0.990394 0.138272 -0.000192147 0.990704 0.136038 0.00395166 0.983335 0.181761 0.0344966 0.987696 0.152534 -0.0121692 0.976428 0.215501 0.00989658 0.959706 0.280833 -0.0140591 0.943966 0.329743 0.0141402 0.923373 0.383643 -0.0140742 0.897559 0.440669 0.0142565 0.871428 0.490316 -0.00959582 0.843738 0.536669 0.00994465 0.812632 0.582693 -0.0136785 0.780279 0.625283 0.0139866 0.74433 0.667666 -0.0383885 0.659589 0.750646 0.0386115 0.700246 0.712857 0.00352895 0.641846 0.766825 -0.00716231 0.573959 0.818853 0.0274325 0.604683 0.795994 0.0111224 0.579458 0.814926 0.00299542 0.560093 0.828424 -0.00214443 0.52599 0.850488 0.0082158 0.481403 0.876461 0.00785417 0.480696 0.876852 0.00401078 0.466067 0.88474 0.00222054 0.458374 0.888756 0.000860842 0.448548 0.893758 -0.000593679 0.435088 0.900388 -0.00178636 0.433709 0.901051 -0.0026169 0.449694 0.893179 -0.00348381 0.464177 0.885735 -0.00482951 0.479529 0.877513 -0.00612292 0.49175 0.870715 -0.00404755 0.475246 0.879843 -0.00119544 0.42217 0.906516 -0.000378686 0.364828 0.931075 -0.00124954 0.374217 0.927341 -0.00236464 0.115029 0.993359 -5.72352e-05 0.131143 0.991364 -0.000367895 0.301415 0.953493 -0.000954184 0.249409 0.968398 0.000459765 0.22746 0.973787 -0.000724216 0.126637 0.991949 -4.61947e-06 0.121081 0.992643 -0.00031267 0.0494421 0.998777 -7.72703e-05 0.0591245 0.998251 -8.13384e-06 0.068824 0.997629 -0.00279787 0.0393478 0.999222 -0.000376841 0.0342496 0.999413 -0.00647444 0.0491531 0.99877 -0.000691671 0.0379407 0.99928 -2.48123e-07 0.0495261 0.998773 8.66818e-05 0.131143 0.991364 8.56752e-06 0.0704975 0.997512 3.42146e-05 0.0630682 0.998009 0.000174317 0.0551335 0.998479 0.00031267 0.0494421 0.998777 0.000520709 0.0431298 0.999069 0.000708632 0.0386287 0.999253 0.000902081 0.0344137 0.999407 0.0010917 0.0349615 0.999388 5.70157e-07 0.121066 0.992644 -0.00103472 0.449975 0.89304 0.00401415 0.475246 0.879844 0.00619183 0.492366 0.870366 -0.000192291 0.442374 0.896831 0.00448451 0.476296 0.879273 0.00321166 0.459856 0.887988 0.00249641 0.447488 0.894286 4.6192e-06 0.121081 0.992643 0.000724216 0.126637 0.991949 -0.000459765 0.22746 0.973787 0.000954184 0.249409 0.968398 0.000367895 0.301415 0.953493 0.00113473 0.364828 0.931074 0.000511144 0.374217 0.927341 0.00119544 0.42217 0.906516 0.000593679 0.435088 0.900388 -0.00283881 0.462202 0.88677 -0.00834969 0.481457 0.87643 -0.00832261 0.481403 0.87646 -0.00270296 0.586705 0.809796 -0.00864939 0.573952 0.818844 0.00173759 0.546687 0.837335 -0.00153109 0.509991 0.860178 0.00257244 0.6312 0.775616 -0.0390583 0.700958 0.712132 0.0402574 0.65954 0.750591 -0.0403418 0.780994 0.623235 0.0400446 0.743807 0.667193 0.00999746 0.903269 0.428957 -0.00976677 0.876333 0.481607 0.0139261 0.849965 0.526655 0.010256 0.846064 0.532982 -0.00983609 0.812633 0.582694 0.0124849 0.905426 0.42432 -0.0357003 0.947927 0.316481 0.0480929 0.926034 0.374364 -0.0497509 0.976481 0.209784 0.0612049 0.957954 0.280317 -0.0129612 0.98326 0.181747 -0.00369761 0.986767 0.162105 0.00169355 0.990702 0.136038 -3.05644e-05 0.989796 0.142495 -0.000356117 0.99152 0.129951 -0.00261897 0.995801 0.0915039 -0.015354 0.994361 0.104934 0.0331706 0.999201 0.0223023 -0.0221291 0.997138 0.072293 -0.0148292 0.997799 0.0646372 -0.00519609 0.998602 0.0525974 0.00697716 0.99942 0.0333352 0.00729524 0.999385 0.0343117 0.0180538 0.99879 0.0457488 0.0269081 0.998208 0.0534516 0.0352701 0.997617 0.0593057 0.0432254 0.99703 0.0637444 0.0202009 0.998398 -0.0528552 0.00697591 0.999277 -0.0373861 0.00729477 0.999321 -0.0361284 -0.0023311 0.998598 -0.0528877 -0.0111198 0.997747 -0.0661682 -0.0171355 0.997182 -0.0730418 0.0283071 0.999344 -0.0225828 -0.0138425 0.995254 -0.0963229 0.0116604 0.99762 -0.0679623 -0.00465331 0.992366 -0.123241 -0.00947618 0.990929 -0.134055 -0.00736346 0.991375 -0.130848 0.000436142 0.987367 -0.158449 0.0138906 0.897562 -0.44067 0.00073947 0.911083 -0.412223 -0.000688194 0.925909 -0.377746 0.00360191 0.934734 -0.355329 -0.000283121 0.938685 -0.344777 -0.000288266 0.9544 -0.29853 -0.00507207 0.957634 -0.287945 0.00806027 0.976468 -0.21551 0.0218763 0.972767 -0.23075 -0.00177859 0.982045 -0.188639 0.0104769 0.772243 -0.635241 -0.0044785 0.823734 -0.566959 0.00972055 0.843737 -0.536669 0.000518022 0.855832 -0.517253 -0.0011929 0.88494 -0.465704 -0.00191324 0.78035 -0.62534 0.00155728 0.700767 -0.713388 -0.00177532 0.69817 -0.715929 0.000434277 0.64203 -0.76668 -0.0116186 0.608408 -0.79354 -0.0107073 0.607287 -0.794411 -0.00199856 0.581547 -0.813511 0.00621571 0.518443 -0.85509 -0.0131717 0.441431 -0.897199 -0.0269327 0.552816 -0.832868 -0.00643171 0.522125 -0.852845 0.0120989 0.421799 -0.906609 -0.0277192 0.465434 -0.884648 -0.0185111 0.450631 -0.892518 -0.00570424 0.424703 -0.905315 0.00055741 0.408512 -0.912753 0.00328151 0.39234 -0.919814 0.00317351 0.487719 -0.872995 0.00409476 0.461586 -0.887086 0.00426102 0.46317 -0.886259 0.000559579 0.119685 -0.992812 -0.000336528 0.206177 -0.978515 0.0011902 0.234536 -0.972107 -0.000484703 0.311464 -0.950258 0.00171598 0.35042 -0.936591 0.000452456 0.40923 -0.912431 0.00309159 0.447968 -0.894044 -0.0424334 0.985302 0.165466 -0.0308125 0.986841 0.15873 -0.0161446 0.989919 0.140714 -0.0170173 0.991633 0.127963 -0.0262505 0.997618 0.0637835 -0.0647447 0.995175 0.0737263 -0.0429939 0.997042 0.0637091 0.116894 0.815328 0.567077 -0.13309 0.898813 0.41764 0.10025 0.878259 0.467559 -0.124674 0.942053 0.311437 0.0982905 0.927464 0.360762 -0.0508795 0.746651 0.663267 0.0366854 0.783191 0.620699 -0.132627 0.844345 0.519126 -0.00998604 0.681053 0.732166 -0.00531517 0.683167 0.730243 -0.00567435 0.72631 0.687344 -0.00333046 0.511493 0.859281 -0.0037664 0.547304 0.836925 -0.00667974 0.578688 0.815522 -0.00599829 0.588503 0.808473 -0.00549886 0.632778 0.774314 0.0230218 0.986908 -0.159634 0.0858621 0.974616 -0.206765 0.0165032 0.989261 -0.145227 0.0172037 0.991015 -0.132636 0.0410735 0.996531 -0.0723755 0.0603246 0.995151 -0.0776892 0.0349267 0.997273 -0.0650077 -0.0620086 0.982815 -0.173867 0.0584619 0.962686 -0.26423 -0.0297499 0.949041 -0.313747 0.0565884 0.924978 -0.375783 -0.0275054 0.906537 -0.421229 0.053065 0.874352 -0.482383 -0.0335557 0.851391 -0.523458 0.0510725 0.81126 -0.58245 -0.0350537 0.783237 -0.620735 0.04894 0.736642 -0.67451 -0.0398673 0.703039 -0.710033 0.00314303 0.511592 -0.859223 0.00426298 0.547128 -0.837038 0.00639339 0.566034 -0.824357 -0.00564407 0.559041 -0.829121 -0.00315698 0.525926 -0.850524 -0.00315169 0.461587 -0.887089 -0.00749027 0.491501 -0.870845 -0.00548804 0.475404 -0.87975 -0.0105613 0.674427 -0.738266 -0.00699901 0.643725 -0.765225 -0.00298819 0.566039 -0.824373 -0.0104993 0.600582 -0.799494 -0.00695947 0.571059 -0.82088 0.138449 0.955031 -0.262199 -0.166244 0.886585 -0.431659 0.147243 0.916334 -0.372359 -0.15352 0.835538 -0.527549 0.0945364 0.871634 -0.480954 -0.112297 0.777455 -0.618832 0.0963756 0.808505 -0.580544 -0.0158897 0.991185 -0.131533 -0.0181004 0.987606 -0.155905 -0.0420831 0.983842 -0.174025 0.0274759 0.976728 -0.212715 -0.161568 0.932734 -0.32234 0.00598422 0.571318 0.820707 0.0049109 0.559267 0.828973 0.00307112 0.525965 0.850501 0.00891251 0.600861 0.799304 0.00453631 0.578692 0.815533 0.00649983 0.643752 0.765207 0.0540838 0.966675 0.250228 -0.0267572 0.944813 0.326515 0.051433 0.930765 0.361982 -0.0277243 0.898751 0.437582 0.047944 0.88172 0.469331 -0.019224 0.845406 0.533779 0.0527271 0.819853 0.570141 -0.0365501 0.781882 0.622355 0.0506498 0.74666 0.663275 0.0246333 0.99462 0.100622 0.0146895 0.991115 0.132193 0.0286511 0.985785 0.16555 0.0673688 0.986789 0.147337 -0.0238266 0.97682 0.212734 0.0116331 0.998437 0.0546705 -0.0207036 0.999784 -0.00193106 -0.0203019 0.999785 0.00428529 -0.00935333 0.997919 0.0638042 0.0390497 0.998542 0.0372686 0.0240901 0.99862 0.0466713 5.96988e-05 0.997976 0.0635993 -0.00666594 0.997581 0.0692002 -0.0170283 0.99675 0.0787307 -0.0392852 0.998073 0.0480212 -0.036915 0.997749 0.0559789 -0.0427368 0.998404 0.0369196 -0.0481195 0.998615 0.0212917 -0.0336172 0.997686 0.0591039 -0.0316896 0.999489 0.0041551 -0.0316018 0.999498 -0.00245495 -0.0315451 0.997244 -0.0671449 -0.053748 0.998453 -0.0142537 -0.0495389 0.998461 -0.0249399 -0.0464537 0.998368 -0.0332075 -0.0425522 0.998119 -0.044129 -0.0396596 0.997806 -0.053016 -0.0317877 0.994703 -0.0977477 -0.0213129 0.995926 -0.0876238 -0.0108439 0.996901 -0.0779188 -0.00221394 0.99747 -0.0710559 0.00566878 0.997869 -0.0650047 0.0211235 0.998279 -0.054704 -0.00933327 0.997329 -0.0724367 -0.019527 0.999648 -0.0179858 -0.0207748 0.999735 -0.00988558 0.0323667 0.997727 0.0591068 0.0523136 0.99858 0.0100882 0.047242 0.998598 0.0238846 0.0444741 0.998502 0.031857 0.0409892 0.998261 0.0423727 0.0384151 0.997963 0.0509422 0.0313646 0.995091 0.0938679 0.0215589 0.996271 0.0835363 0.0120262 0.997193 0.0739069 0.00426937 0.99773 0.067205 -0.00280784 0.998115 0.0613094 -0.0166798 0.998543 0.0513219 0.00325203 0.997957 0.0638073 0.0169396 0.999669 0.0193432 0.0194568 0.999758 0.0102565 0.0204533 0.999789 0.00194427 0.0208514 0.999774 -0.00422098 0.0169899 0.997229 -0.0724286 -0.046145 0.998131 -0.0400737 -0.0293853 0.998323 -0.0498792 -0.0154998 0.998186 -0.0581685 -0.00260913 0.997726 -0.0673543 0.00488494 0.997312 -0.0731047 0.0325014 0.996592 -0.0758204 0.0379687 0.99758 -0.0582465 0.0406381 0.997923 -0.0499831 0.0445114 0.998268 -0.0384691 0.033849 0.997169 -0.0671389 0.0316764 0.99939 -0.0147171 0.0315791 0.999493 -0.00414389 -0.0153997 0.878924 0.476713 -0.0145757 0.871622 0.489962 -0.0139924 0.872533 0.488355 -0.0140837 0.87239 0.488608 -0.0139843 0.881018 0.472876 -0.0129947 0.881038 0.472866 -0.0129598 0.882021 0.471033 -0.0130578 0.874403 0.485024 -0.0118416 0.877996 0.478521 -0.00916218 0.894095 0.447783 -0.00709907 0.885935 0.463756 -0.00775228 0.888109 0.459567 -0.0085286 0.891334 0.453267 -0.00865753 0.884467 0.466523 -0.00832922 0.889445 0.456967 -0.0112118 0.894133 0.447662 -0.0131521 0.896769 0.442304 -0.0086238 0.894072 0.447841 -0.0106323 0.888717 0.458333 -0.0117457 0.885033 0.46538 -0.0128949 0.880863 0.473196 -0.0136986 0.876906 0.480466 -0.0139026 0.875838 0.482405 -0.0141919 0.874237 0.485291 -0.0177554 0.876614 0.480867 -0.0203343 0.87795 0.478321 -0.0205463 0.878692 0.476946 -0.0204112 0.874638 0.484347 -0.0169622 0.870788 0.491366 -0.0192881 0.874661 0.484352 -0.0198681 0.876348 0.481268 -0.0198728 0.875364 0.483055 -0.0177209 0.877756 0.478779 -0.0177654 0.871512 0.490053 -0.0185524 0.872933 0.487488 -0.0189273 0.873784 0.485947 -0.0189122 0.876374 0.48126 -0.0189229 0.876236 0.481511 -0.0165731 0.878859 0.476793 -0.0165597 0.878899 0.47672 -0.0166293 0.87065 0.491622 -0.0163075 0.870545 0.491819 -0.0154506 0.870661 0.491641 -0.0153582 0.880035 0.47466 -0.015498 0.929517 0.368454 -0.0168801 0.918783 0.394402 -0.019148 0.882568 0.469796 0.00235694 0.913099 0.407732 -0.00376048 0.904598 0.426249 -0.00419313 0.952536 0.304398 -0.027631 0.931639 0.362332 -0.0173362 0.96717 0.25354 -0.0225083 0.980666 0.194391 -0.021786 0.975741 0.217843 -0.116537 0.971563 0.206117 0.077249 0.965189 0.249887 -0.0169111 0.967951 0.25057 -0.0182253 0.970046 0.242236 -0.0284069 0.990532 0.134314 -0.0265199 0.991533 0.127115 -0.0319555 0.986477 0.160752 -0.0302505 0.989297 0.142745 -0.0323277 0.987409 0.154849 -0.0272215 0.993612 0.10952 -0.0284179 0.995978 0.0849726 -0.0274153 0.993665 0.108987 -0.0274757 0.995583 0.0897809 -0.032015 0.996811 0.0730982 -0.0262334 0.991399 0.128219 -0.0253223 0.990114 0.137958 -0.0220489 0.98595 0.16558 -0.0184459 0.989974 0.140043 -0.0193377 0.989023 0.146488 -0.0228919 0.984092 0.176181 -0.0207633 0.987319 0.157383 -0.0226202 0.983835 0.177642 -0.0015774 0.988815 0.149142 -0.0201656 0.985012 0.171302 -0.0138573 0.987173 0.159049 -0.0111771 0.988182 0.152876 -0.00963056 0.988978 0.147749 -0.00889372 0.989408 0.144889 -0.0117183 0.983235 0.181965 -0.00877146 0.989286 0.145727 -0.00828704 0.989854 0.141847 -0.00842534 0.989897 0.141539 -0.0204643 0.988695 0.148537 -0.0225407 0.990695 0.134221 -0.0245289 0.991211 0.129994 -0.0142206 0.976658 0.214327 -0.0163029 0.981882 0.188791 -0.0184081 0.986301 0.163928 -0.0127032 0.973525 0.228229 -0.0136043 0.973119 0.229902 -0.00298051 0.962135 0.272556 -0.017014 0.901251 0.432963 -0.0219809 0.905422 0.423942 -0.00790033 0.894363 0.447272 -0.00355774 0.916972 0.398936 -0.00378914 0.921086 0.38934 -0.00416873 0.924964 0.380031 -0.00588783 0.929227 0.369463 -0.0119372 0.94043 0.339778 -0.0159383 0.93783 0.346729 -0.00529479 0.951074 0.308918 -0.00145914 0.578695 0.815543 -0.00106693 0.58333 0.812235 -0.000857181 0.475247 0.879852 -0.000568854 0.478897 0.877871 -0.000425424 0.364828 0.931075 -0.000240886 0.367276 0.930112 -0.000159306 0.249409 0.968398 -6.59692e-05 0.250683 0.968069 -3.29494e-05 0.131143 0.991364 -5.21128e-06 0.131526 0.991313 -1.84674e-06 0.0495979 0.998769 -0.0105548 0.882812 0.469608 -0.0105316 0.883708 0.467921 -0.0105469 0.882756 0.469714 -0.00862839 0.891413 0.453111 -0.00799212 0.830171 0.557451 -0.00679452 0.835002 0.550206 -0.00612055 0.757535 0.652766 -0.00501295 0.762786 0.646632 -0.0152441 0.867699 0.496857 -0.0158721 0.861 0.508357 -0.0150805 0.820893 0.570883 -0.0128971 0.830133 0.557416 -0.0115279 0.747561 0.664093 -0.00950741 0.757518 0.652745 -0.00838222 0.673306 0.739317 -0.00438618 0.673319 0.739339 -0.00175384 0.687369 0.726307 -5.58421e-05 0.752736 -0.658323 -6.9063e-05 0.752797 -0.658252 -7.63333e-05 0.826555 -0.562856 -9.06628e-05 0.826612 -0.562773 -9.78567e-05 0.887584 -0.460647 -0.000112702 0.887632 -0.460554 -0.000119252 0.935373 -0.353662 -0.000133396 0.935408 -0.353569 -0.000138742 0.969858 -0.243671 -0.000151489 0.96988 -0.243585 -0.000154535 0.987587 -0.157074 -0.000164556 0.987598 -0.157006 -0.000166489 0.997922 -0.0644352 -0.000175869 0.997924 -0.0644033 -0.000175962 0.998391 0.0567041 -0.000167843 0.998393 0.0566764 -0.000166034 0.988815 0.149145 -0.000156005 0.988826 0.149077 -0.000153292 0.973201 0.229955 -0.000140752 0.973221 0.229871 -0.00013561 0.940485 0.339835 -0.000121854 0.940518 0.339744 -0.000115415 0.89438 0.447308 -0.000100692 0.894426 0.447216 -9.35352e-05 0.835008 0.550237 -7.90317e-05 0.835065 0.550152 -7.1728e-05 0.762784 0.646653 -5.82898e-05 0.762846 0.64658 -5.1426e-05 0.678541 0.734562 -2.92768e-06 0.116058 -0.993243 -2.48712e-05 0.11636 -0.993207 -5.27318e-05 0.234535 -0.972108 -0.000137063 0.235676 -0.971832 -0.000209413 0.350419 -0.936593 -0.000385569 0.352712 -0.935732 -0.000513877 0.461587 -0.887095 -0.000799285 0.46509 -0.885263 -0.000985891 0.56604 -0.824378 -0.00138552 0.570569 -0.821249 -0.00476279 0.747474 -0.664275 -0.00593482 0.752736 -0.658296 -0.00651942 0.821645 -0.569962 -0.00780084 0.826545 -0.562817 -0.00838022 0.883456 -0.46844 -0.00969337 0.887556 -0.460597 -0.0102229 0.932305 -0.36153 -0.0114816 0.935324 -0.353607 -0.0119191 0.967935 -0.250917 -0.0130342 0.969784 -0.243619 -0.0132834 0.986544 -0.162954 -0.0141816 0.987492 -0.157031 -0.0143466 0.997638 -0.0671788 -0.0151673 0.997808 -0.0644145 -0.0151732 0.998135 0.0591375 -0.0144502 0.998287 0.0566869 -0.0140987 0.976223 0.216309 -0.012426 0.981351 0.191821 -0.0368903 0.99742 -0.0615808 -0.0272909 0.995282 -0.0931098 -0.0270153 0.986273 -0.162897 -0.025283 0.984399 -0.174128 -0.0248112 0.96771 -0.250841 -0.022648 0.964085 -0.264627 -0.0218323 0.932137 -0.361446 -0.01938 0.926283 -0.376329 -0.0184122 0.883345 -0.468362 -0.015848 0.875468 -0.483016 -0.0148027 0.821581 -0.5699 -0.0123016 0.81225 -0.58318 -0.0112537 0.747442 -0.664232 0.00529926 0.588653 -0.808369 0.00575309 0.632756 -0.77433 0.00908817 0.661849 -0.749582 0.00817189 0.675846 -0.736997 0.0091003 0.747456 -0.664249 0.0110932 0.737472 -0.675287 0.0124537 0.821605 -0.569922 0.0146223 0.812225 -0.583161 0.0160026 0.883379 -0.468385 0.0182353 0.875433 -0.482996 0.0195144 0.932181 -0.361467 0.0216836 0.92624 -0.37631 0.0227434 0.967757 -0.250856 0.0247091 0.964038 -0.264613 0.0253385 0.986316 -0.162905 0.0269581 0.984355 -0.17412 0.02729 0.995254 -0.0934099 0.0163644 0.996431 -0.0828081 0.0359579 0.997599 0.0591887 0.0274765 0.995608 0.0894994 0.0272295 0.987579 0.154749 0.0255656 0.985868 0.165565 0.0251459 0.971185 0.236995 0.0230285 0.967833 0.250538 0.0222399 0.937386 0.347581 0.0198143 0.931811 0.362402 0.0188615 0.890257 0.455069 0.0163016 0.882612 0.46982 0.0152618 0.830108 0.557394 0.0127435 0.820919 0.570902 0.011692 0.757503 0.652727 0.00937409 0.747577 0.664109 -0.0392394 0.702294 0.710805 0.00998604 0.681053 0.732166 0.00838221 0.673306 0.739317 0.00438618 0.673319 0.739339 0.00497603 0.757538 0.652772 0.00616598 0.762784 0.646625 0.0067523 0.830178 0.557458 0.00804194 0.834996 0.550197 0.00861752 0.890374 0.455148 0.00992871 0.89435 0.447258 0.0104489 0.937561 0.347664 0.0116945 0.940432 0.33978 0.0121161 0.971417 0.237069 0.0132085 0.973124 0.229904 0.01343 0.987854 0.154805 0.0142931 0.988718 0.149103 0.0144477 0.998145 0.0591384 0.0151753 0.998277 0.0566857 0.0151645 0.997626 -0.0671776 0.0143498 0.99782 -0.064416 0.0141666 0.986532 -0.162952 0.013298 0.987504 -0.157035 0.013007 0.967923 -0.250912 0.0119445 0.969796 -0.243625 0.0114415 0.932293 -0.361523 0.0102592 0.935335 -0.353615 0.00964516 0.883446 -0.468433 0.00842238 0.887565 -0.460606 0.00775121 0.821639 -0.569955 0.00656126 0.82655 -0.562826 0.00589036 0.74747 -0.664269 0.0047987 0.752738 -0.658303 0.00418136 0.661866 -0.749611 0.0016595 0.675516 -0.737344 0.00137373 0.56604 -0.824377 0.000994284 0.570569 -0.821249 0.000792824 0.461587 -0.887095 0.000518013 0.46509 -0.885263 0.000382871 0.350419 -0.936593 0.00021086 0.352712 -0.935732 0.000136345 0.234535 -0.972108 5.30009e-05 0.235676 -0.971832 2.48e-05 0.116058 -0.993243 2.93547e-06 0.11636 -0.993207 8.25431e-07 0.0344845 -0.999405 -8.25164e-07 0.0344721 -0.999406 -5.43907e-08 0.0344494 -0.999406 -0.00091488 0.0194453 -0.999811 -0.00108084 0.0199249 -0.999801 -0.110537 0.698529 -0.706993 0.100654 0.733746 -0.671927 -0.00897067 0.737487 -0.675302 -0.00799116 0.661855 -0.74959 -0.00418136 0.661866 -0.749611 -0.0016595 0.675516 -0.737344 -4.90772e-05 0.667041 -0.745021 4.90772e-05 0.667041 -0.745021 5.58469e-05 0.752797 -0.658252 6.9057e-05 0.752736 -0.658323 7.63389e-05 0.826612 -0.562773 9.06561e-05 0.826555 -0.562856 9.78624e-05 0.887632 -0.460554 0.000112695 0.887584 -0.460647 0.000119257 0.935408 -0.353569 0.000133391 0.935373 -0.353662 0.000138746 0.96988 -0.243585 0.000151485 0.969858 -0.243671 0.000154537 0.987598 -0.157006 0.000164554 0.987587 -0.157074 0.000166489 0.997924 -0.0644033 0.000175869 0.997922 -0.0644352 0.000175962 0.998393 0.0566764 0.000167842 0.998391 0.0567041 0.000166036 0.988826 0.149077 0.000156004 0.988815 0.149145 0.000153295 0.973221 0.229871 0.000140749 0.973201 0.229955 0.000135615 0.940518 0.339744 0.00012185 0.940485 0.339835 0.000115422 0.894426 0.447216 0.000100687 0.89438 0.447308 9.35419e-05 0.835065 0.550152 7.9026e-05 0.835008 0.550237 7.17342e-05 0.762846 0.64658 5.82847e-05 0.762784 0.646653 5.1426e-05 0.678541 0.734562 0.00175384 0.687369 0.726307 0.00147166 0.583329 0.812234 0.00105791 0.578694 0.815544 0.000864247 0.478897 0.877871 0.000564256 0.475247 0.879852 0.000428497 0.367276 0.930112 0.00023919 0.364828 0.931075 0.000160186 0.250683 0.968069 6.5617e-05 0.249409 0.968398 3.30553e-05 0.131526 0.991313 5.19553e-06 0.131143 0.991364 1.84556e-06 0.0495689 0.998771 3.32733e-07 0.0495247 0.998773 -0.997429 -0.00133279 0.0716512 -0.711841 -0.0236242 0.701944 -0.993953 -0.0100004 0.109353 -0.946334 -0.0683112 0.315888 -0.986265 -0.0231427 0.163542 -0.995743 0.00129122 0.0921608 -0.999675 -0.00411909 0.025175 -0.97315 -0.203519 0.107514 -0.970596 -0.105816 0.216208 -0.977475 -0.0615989 0.201863 -0.977809 -0.0599648 0.200731 -0.97734 -0.0610117 0.202691 -0.972065 -0.204073 0.11595 -0.954798 -0.265306 0.134065 -0.960749 -0.237364 0.143597 -0.968002 -0.210222 0.137035 -0.928415 -0.334034 0.162689 -0.941152 -0.29675 0.161778 -0.954243 -0.26842 0.131796 -0.945974 -0.262876 0.189816 -0.961088 -0.185082 0.205072 -0.971156 -0.163272 0.173776 -0.975907 -0.124819 0.178956 -0.977237 -0.120224 0.174799 -0.840668 -0.323897 0.434014 -0.759951 -0.35254 0.546067 -0.884853 -0.307157 0.350273 -0.828334 -0.37047 0.420255 -0.849565 -0.386061 0.359439 -0.835906 -0.407804 0.367363 -0.747648 -0.393915 0.534652 -0.851236 -0.423542 0.309855 -0.897839 -0.372448 0.234876 -0.887609 -0.364319 0.28182 -0.915796 -0.254415 0.310789 -0.925048 -0.259565 0.277332 -0.942972 -0.165157 0.28901 -0.952477 -0.169071 0.253382 -0.978986 -0.0422405 0.199507 -0.971889 -0.0673643 0.225599 -0.976074 -0.0602788 0.208917 -0.964973 -0.0935573 0.245099 -0.971567 -0.0952856 0.216746 -0.952885 -0.166539 0.253525 -0.957312 -0.157126 0.24262 -0.947859 -0.213344 0.236744 -0.943705 -0.211209 0.254582 -0.919012 -0.320651 0.229347 -0.929863 -0.329045 0.164571 -0.897208 -0.374961 0.233287 -0.872627 -0.234145 0.428601 -0.921016 -0.197614 0.335677 -0.900794 -0.190253 0.390351 -0.93764 -0.154213 0.311528 -0.92698 -0.151382 0.343209 -0.953324 -0.118852 0.277575 -0.960827 -0.120399 0.249631 -0.981286 -0.0423531 0.187839 -0.978945 -0.024578 0.202639 -0.978092 -0.0468267 0.202837 -0.988026 -0.0479287 0.146656 -0.980655 -0.0142226 0.195227 -0.989623 -0.0184722 0.142494 -0.9889 -0.0176287 0.147536 -0.992885 -0.00519492 0.118966 -0.997175 -0.0114195 0.074245 -0.822209 -0.243426 0.514506 -0.87805 -0.206596 0.431679 -0.861832 -0.200785 0.465759 -0.905125 -0.163482 0.392457 -0.898041 -0.161585 0.40916 -0.930085 -0.127244 0.344602 -0.92474 -0.126153 0.359085 -0.950518 -0.0917405 0.296816 -0.956152 -0.092643 0.277831 -0.970655 -0.0254038 0.239132 -0.95862 -0.0376192 0.282192 -0.977259 -0.00675017 0.21194 -0.98218 -0.00129764 0.18794 -0.98446 -0.00223174 0.175593 -0.992524 -0.00241981 0.122023 -0.989388 0.0045549 0.145223 -0.994858 -0.00134123 0.101275 -0.664821 -0.0207019 0.746716 -0.660933 -0.0272599 0.74995 -0.591372 -0.0229509 0.806073 -0.983048 -0.0094359 0.183103 -0.982093 -0.0122967 0.187993 -0.971847 -0.0254994 0.234227 -0.972185 -0.00300579 0.234193 -0.959281 -0.00966474 0.282288 -0.961379 -0.00645428 0.275152 -0.937053 -0.0109754 0.349014 -0.94072 -0.00338049 0.339167 -0.917258 -0.00415225 0.398272 -0.915206 -0.00725816 0.402921 -0.889958 -0.0036599 0.456028 -0.885011 -0.00954917 0.465473 -0.856006 -0.00437009 0.516947 -0.850496 -0.0102128 0.525882 -0.813561 -0.00637486 0.581444 -0.809741 -0.0105525 0.586693 -0.763641 -0.00871004 0.645582 -0.763499 -0.00886136 0.645749 -0.706869 -0.0131301 0.707222 -0.715407 0.00501944 0.69869 -0.661179 -0.0106792 0.750153 -0.663951 -0.00509241 0.747759 -0.681999 -0.00595377 0.731329 -0.715806 -0.100983 0.690959 -0.615275 -0.103107 0.78154 -0.66872 -0.115436 0.734499 -0.684319 -0.0924019 0.723305 -0.714605 -0.0983953 0.692574 -0.726649 -0.0787448 0.682481 -0.765175 -0.0850916 0.638174 -0.774187 -0.0684019 0.629251 -0.821005 -0.074208 0.566078 -0.988529 -0.0312959 0.147752 -0.973752 -0.0296992 0.225666 -0.978521 -0.0657814 0.195372 -0.971669 -0.0647756 0.227296 -0.971074 -0.0734862 0.227188 -0.964303 -0.0856815 0.250555 -0.970411 -0.0865452 0.225417 -0.954098 -0.111845 0.277825 -0.962938 -0.113691 0.244589 -0.939185 -0.143279 0.312094 -0.949833 -0.146596 0.276273 -0.920319 -0.201351 0.335367 -0.919059 -0.200812 0.339125 -0.909107 -0.251468 0.332098 -0.849863 -0.286972 0.442019 -0.856189 -0.259171 0.446957 -0.787297 -0.293082 0.542463 -0.789428 -0.28381 0.544294 -0.776379 -0.277022 0.566122 -0.73125 -0.3234 0.600572 -0.761166 -0.342416 0.550797 -0.723225 -0.344514 0.598544 -0.703452 -0.224795 0.674257 -0.687433 -0.224658 0.690626 -0.690861 -0.226184 0.686697 -0.722271 -0.188035 0.665558 -0.730968 -0.191232 0.655069 -0.756181 -0.156658 0.635334 -0.777101 -0.162913 0.607926 -0.796825 -0.131689 0.589685 -0.837132 -0.140993 0.528518 -0.933422 -0.0441079 0.356058 -0.921345 -0.0613968 0.383868 -0.910578 -0.0604427 0.408893 -0.894401 -0.0803503 0.43999 -0.88052 -0.0788268 0.467409 -0.860168 -0.100622 0.499987 -0.82423 -0.0953688 0.558166 -0.818561 -0.106148 0.564527 -0.783814 -0.100011 0.61289 -0.769797 -0.124024 0.626123 -0.739453 -0.116996 0.662964 -0.721146 -0.144448 0.677557 -0.701079 -0.138782 0.699448 -0.677712 -0.170195 0.71536 -0.650094 -0.160884 0.742626 -0.709896 -0.160827 0.685698 -0.787923 -0.0482069 0.613884 -0.586933 -0.0560402 0.807694 -0.663393 -0.0664425 0.745316 -0.67227 -0.0522605 0.738459 -0.710721 -0.0569662 0.701163 -0.717597 -0.0448871 0.695011 -0.762537 -0.0496002 0.645041 -0.767584 -0.0395469 0.639728 -0.812716 -0.0429844 0.581072 -0.811311 -0.0460271 0.582799 -0.85492 -0.0487718 0.516463 -0.863945 -0.0382864 0.502129 -0.889242 -0.0393224 0.455744 -0.8969 -0.0294754 0.44125 -0.916832 -0.0301197 0.398135 -0.922873 -0.0213216 0.384515 -0.943027 -0.0220134 0.331986 -0.942298 -0.0448174 0.331762 -0.947273 -0.0366285 0.318328 -0.999533 0 0.0305728 -0.999426 0.00144767 0.0338334 -0.999339 0 0.0363471 -0.999339 0 0.0363471 -0.999499 0 0.0316425 -0.999334 -0.00274238 0.0363957 -0.995731 -0.00269927 0.0922618 -0.993921 -0.0124734 0.109387 -0.986398 -0.0119937 0.163938 -0.982473 -0.0342109 0.183237 -0.97364 -0.0332473 0.225655 -0.969785 -0.0489032 0.23901 -0.958607 -0.0699791 0.276 -0.958998 -0.0638754 0.27612 -0.946692 -0.0623803 0.316042 -0.930966 -0.0854328 0.35497 -0.928677 -0.0851205 0.36099 -0.906583 -0.112297 0.406813 -0.904102 -0.111875 0.412412 -0.874395 -0.142428 0.46384 -0.870707 -0.141607 0.470974 -0.832622 -0.174547 0.525618 -0.834334 -0.17506 0.522724 -0.786187 -0.208283 0.581832 -0.770415 -0.202245 0.604614 -0.744857 -0.234272 0.624743 -0.747584 -0.23549 0.621017 -0.708592 -0.278619 0.648281 -0.724145 -0.287135 0.627031 -0.707671 -0.28727 0.645506 -0.864398 0.184438 0.467759 -0.813287 0.0105428 0.581768 -0.763499 0.00885594 0.645749 -0.915222 0.00428527 0.402928 -0.94072 0.00331012 0.339168 -0.588788 0.0228304 0.807965 -0.733828 0.0381212 0.678265 -0.580154 0.0551994 0.812634 -0.733603 0.0917584 0.673356 -0.605463 0.100995 0.78944 -0.71885 0.15299 0.678121 -0.639229 0.157442 0.752728 -0.713092 0.21879 0.666056 -0.677371 0.220471 0.701827 -0.715157 0.282571 0.6393 -0.700933 0.271049 0.659717 -0.728976 0.322422 0.603853 -0.75448 0.348396 0.556219 -0.754425 0.349313 0.55572 -0.816682 0.425739 0.389586 -0.912737 0.317058 0.257652 -0.880504 0.429275 0.201087 -0.865046 0.348987 0.360421 -0.950957 0.274206 0.143152 -0.932352 0.320288 0.167735 -0.913787 0.379282 0.145393 -0.96408 0.222287 0.145392 -0.971432 0.204107 0.121077 -0.977292 0.12067 0.174179 -0.976821 0.121631 0.176144 -0.97784 0.0600048 0.200569 -0.977752 0.0604054 0.200879 -0.964892 0.0938427 0.24531 -0.973544 0.0345168 0.225878 -0.978417 0.0561655 0.19886 -0.976045 0.0604362 0.209008 -0.977124 0.0610864 0.20371 -0.977563 0.060865 0.20166 -0.986608 0.0273059 0.160806 -0.972645 0.0463852 0.227618 -0.979575 0.0470788 0.195491 -0.985619 0.0164601 0.168177 -0.988877 0.0180952 0.147628 -0.991946 0.0070885 0.126465 -0.855299 0.342516 0.388775 -0.901122 0.318078 0.294628 -0.903014 0.310837 0.296557 -0.974906 0.131845 0.179374 -0.971701 0.164035 0.16997 -0.957238 0.157568 0.242625 -0.955308 0.170741 0.241317 -0.940926 0.164774 0.295817 -0.896276 0.213651 0.388642 -0.868876 0.15422 0.470394 -0.924247 0.168987 0.34236 -0.931357 0.114786 0.345541 -0.948128 0.157386 0.276193 -0.907332 0.146635 0.394013 -0.92954 0.201248 0.308959 -0.956565 0.0848152 0.278909 -0.967518 0.11496 0.22515 -0.943072 0.109909 0.313902 -0.958236 0.149749 0.243636 -0.955521 0.148822 0.254621 -0.961897 0.0930954 0.257074 -0.967508 0.133511 0.214717 -0.97194 0.0907331 0.217025 -0.977017 0.120572 0.175787 -0.994004 0.00268492 0.109309 -0.999622 0.00274927 0.0273437 -0.9997 0.00486291 0.0240229 -0.998511 0.00160196 0.0545183 -0.982453 0.0342471 0.183339 -0.970401 0.0329608 0.239241 -0.970194 0.0387498 0.239212 -0.982096 0.0107268 0.188078 -0.972157 0.0030003 0.234313 -0.961363 0.00868394 0.275147 -0.977281 -0.000502362 0.211945 -0.98446 0.00223653 0.175593 -0.989396 0.00232831 0.145224 -0.663926 0.0101289 0.74773 -0.715406 -0.00538574 0.698689 -0.706658 0.0133142 0.70743 -0.763356 0.00870857 0.645919 -0.762654 0.0391948 0.645618 -0.812482 0.0429918 0.581399 -0.885047 0.00310484 0.465492 -0.917146 0.00747835 0.398481 -0.916958 0.0211413 0.398424 -0.931633 0.021635 0.362757 -0.943151 0.00996371 0.332216 -0.959264 0.00687039 0.282428 -0.958981 0.0245488 0.282407 -0.971818 0.0255189 0.234347 -0.983012 0.0109123 0.183216 -0.98211 0.00940197 0.188072 -0.993946 0.0100068 0.109412 -0.991462 -0.00255313 0.130373 -0.994858 0.00134471 0.101275 -0.716774 0.0577767 0.694908 -0.715756 0.0770454 0.694087 -0.724897 0.100558 0.681478 -0.723855 0.113537 0.680547 -0.736072 0.148868 0.66033 -0.735856 0.150816 0.660129 -0.958583 0.248145 0.139792 -0.95395 0.268858 0.133021 -0.934921 0.257302 0.244375 -0.933224 0.265022 0.242603 -0.909069 0.251397 0.332254 -0.893379 0.313044 0.322299 -0.861923 0.229798 0.451976 -0.840105 0.324049 0.43499 -0.799408 0.233604 0.553513 -0.789192 0.284063 0.544504 -0.770167 0.202399 0.604878 -0.744595 0.234445 0.624991 -0.750422 0.19867 0.630394 -0.849301 0.44934 0.277096 -0.805125 0.354996 0.475133 -0.828136 0.370981 0.420196 -0.820403 0.396379 0.412096 -0.774481 0.286439 0.564031 -0.762084 0.343484 0.548859 -0.743427 0.260576 0.615967 -0.737154 0.294707 0.608072 -0.717634 0.2225 0.659921 -0.715415 0.23749 0.657099 -0.696855 0.178987 0.694519 -0.69708 0.176996 0.694803 -0.681126 0.133356 0.71992 -0.68231 0.118747 0.721355 -0.670228 0.0897394 0.73671 -0.671392 0.06762 0.738011 -0.663751 0.0512875 0.746194 -0.664426 0.0275159 0.746848 -0.925788 0.115746 0.359889 -0.878026 0.107652 0.466349 -0.878412 0.103435 0.466576 -0.982775 0.0219156 0.183503 -0.978376 0.0401508 0.202898 -0.977274 0.060979 0.20302 -0.964239 0.0858622 0.250742 -0.963529 0.0939974 0.250552 -0.933573 0.115202 0.339368 -0.924622 0.126292 0.359339 -0.902907 0.121985 0.412163 -0.899733 0.148348 0.410455 -0.837656 0.13453 0.529371 -0.841252 0.0979305 0.5317 -0.803338 0.133304 0.580413 -0.818321 0.106201 0.564865 -0.809771 0.00614309 0.586714 -0.85578 0.0106707 0.51723 -0.855165 0.0379501 0.516965 -0.89646 0.0396427 0.441347 -0.895597 0.0591965 0.44091 -0.932448 0.0624584 0.355864 -0.932541 0.0608173 0.355906 -0.772761 0.0864385 0.628784 -0.771884 0.0980167 0.628163 -0.781085 0.126793 0.611416 -0.780938 0.128216 0.611307 -0.792194 0.167659 0.586788 -0.792816 0.163043 0.587247 -0.825852 0.224118 0.517435 -0.831731 0.190625 0.521427 -0.865729 0.264153 0.42513 -0.881798 0.18402 0.434245 -0.909386 0.252077 0.330869 -0.920167 0.201716 0.335563 -0.935812 0.20872 0.284064 -0.935955 0.207949 0.284159 -0.955493 0.218107 0.198651 -0.959157 0.197366 0.202646 -0.973018 0.204276 0.107271 -0.850535 0.0035706 0.525906 -0.889784 0.0103627 0.456264 -0.889433 0.0292571 0.456128 -0.922569 0.0303278 0.384638 -0.92213 0.0432745 0.384451 -0.942232 0.0448551 0.331944 -0.93183 0.0607377 0.357776 -0.960217 0.0377997 0.276685 -0.958552 0.0700637 0.27617 -0.973307 0.0413551 0.225751 -0.997429 0.00133249 0.0716512 -0.999531 -0.00169351 0.0305728 -0.999339 0 0.0363648 -0.999339 0 0.0363648 -0.999339 0 0.0363648 -0.999339 0 0.0363648 -0.68058 0.00542414 0.732653 -0.660945 0.00471231 0.750419 -0.660778 0.0204785 0.750302 -0.711544 0.023629 0.702245 -0.710945 0.0442455 0.701854 -0.766893 0.0501156 0.639816 -0.766023 0.0674588 0.639264 -0.798865 0.0715007 0.597246 -0.822193 0.0467411 0.567286 -0.863348 0.0493428 0.502191 -0.861833 0.0768716 0.501333 -0.909094 0.0820594 0.408429 -0.909055 0.0825967 0.408408 -0.944881 0.087467 0.315514 -0.944592 0.090943 0.315397 -0.968272 0.0714766 0.239457 -0.971628 0.0648672 0.227445 -0.972064 0.0649289 0.225558 -0.980245 0.0303892 0.195441 -0.983138 0.030701 0.18027 -0.988983 0.0121577 0.147526 -0.995628 0.0126292 0.0925526 -0.995689 0.00776997 0.0924338 -0.996416 0.00317884 0.0845267 -0.997442 0.000549896 -0.0714722 -0.925419 0.131083 -0.355551 -0.999689 0 -0.0249495 -0.999347 0.0029521 -0.0360151 -0.996035 0.000940048 -0.0889631 -0.98614 0.0239164 -0.164182 -0.978757 0.0304087 -0.202757 -0.981464 0.0479311 -0.185555 -0.977492 0.047612 -0.205528 -0.977853 0.0682303 -0.197858 -0.977566 0.0685986 -0.199146 -0.978305 0.0695172 -0.19516 -0.973421 0.137511 -0.183143 -0.975022 0.131742 -0.178819 -0.967691 0.137927 -0.21107 -0.976312 0.0777466 -0.201916 -0.977743 0.0686562 -0.198253 -0.950606 0.255683 -0.175995 -0.935961 0.318721 -0.149644 -0.940027 0.28644 -0.185205 -0.910913 0.360213 -0.201209 -0.913916 0.348508 -0.208086 -0.870835 0.411461 -0.268974 -0.874673 0.387367 -0.291364 -0.851785 0.420706 -0.3122 -0.798145 0.440504 -0.410999 -0.796766 0.448946 -0.404489 -0.74986 0.370179 -0.548341 -0.734396 0.396367 -0.550959 -0.749573 0.336666 -0.569908 -0.615776 0.308714 -0.724924 -0.651049 0.0377667 -0.758096 -0.614173 0.0251617 -0.78877 -0.72666 0.119542 -0.676517 -0.727761 0.105901 -0.677606 -0.671246 0.0942096 -0.735223 -0.672642 0.070567 -0.736596 -0.699 0.074487 -0.711232 -0.619998 0.0752431 -0.780987 -0.765388 0.0555473 -0.641167 -0.766946 0.0522553 -0.63958 -0.715104 0.046988 -0.697438 -0.666589 0.0287645 -0.744871 -0.665772 0.0540126 -0.744198 -0.720452 0.0609854 -0.690819 -0.719375 0.081415 -0.689835 -0.777351 0.0909759 -0.622454 -0.774062 0.130676 -0.619477 -0.780785 0.118412 -0.613476 -0.907479 0.115917 -0.403789 -0.929198 0.0873244 -0.359117 -0.931463 0.0876745 -0.353115 -0.933658 0.0448017 -0.355352 -0.921972 0.0626402 -0.382156 -0.911208 0.0615274 -0.407326 -0.895281 0.0824843 -0.4378 -0.889901 0.0401376 -0.454384 -0.897537 0.0296605 -0.439941 -0.917473 0.0305443 -0.396624 -0.923289 0.0214973 -0.383504 -0.943477 0.0223065 -0.330685 -0.942858 0.0456071 -0.33006 -0.982349 0.0121371 -0.186663 -0.961585 0.00670921 -0.274424 -0.972248 0.025936 -0.232509 -0.970777 0.0258287 -0.238588 -0.970093 0.0495469 -0.237621 -0.973618 0.0341098 -0.225621 -0.98271 0.0350376 -0.181808 -0.983144 0.00962026 -0.182582 -0.992527 0.00995209 -0.121616 -0.992543 -0.0051681 -0.121783 -0.994884 0.000594052 -0.101019 -0.968136 0.103553 -0.228011 -0.96246 0.102177 -0.251456 -0.962495 0.175697 -0.206723 -0.967408 0.178187 -0.179922 -0.969799 0.156942 -0.186704 -0.920698 0.280128 -0.271742 -0.872315 0.303986 -0.38296 -0.880569 0.269458 -0.389861 -0.839894 0.322755 -0.436357 -0.852098 0.272199 -0.447031 -0.783355 0.310264 -0.538602 -0.800635 0.224692 -0.555425 -0.741853 0.26005 -0.618084 -0.750674 0.208658 -0.626858 -0.69422 0.186837 -0.69509 -0.694581 0.183957 -0.695498 -0.752198 0.205094 -0.626206 -0.583299 0.185553 -0.79078 -0.594065 0.247196 -0.765494 -0.771223 0.276254 -0.573497 -0.710206 0.246525 -0.659418 -0.698986 0.304918 -0.646872 -0.769589 0.274151 -0.576692 -0.74771 0.368611 -0.552319 -0.828231 0.337822 -0.447112 -0.813319 0.389483 -0.432222 -0.861585 0.336646 -0.379921 -0.851891 0.369898 -0.370752 -0.894208 0.317723 -0.315349 -0.890465 0.331284 -0.311967 -0.923934 0.282182 -0.258302 -0.925182 0.277033 -0.259403 -0.933823 0.202839 -0.294671 -0.92911 0.160446 -0.333184 -0.901928 0.213569 -0.375385 -0.908628 0.171829 -0.380618 -0.865603 0.212196 -0.453546 -0.874804 0.147862 -0.461362 -0.836504 0.183362 -0.516371 -0.845434 0.101563 -0.524334 -0.820495 0.126683 -0.55744 -0.825707 0.0481081 -0.562045 -0.814794 0.0604376 -0.576592 -0.928159 0.160173 -0.335955 -0.931481 0.132484 -0.33881 -0.899787 0.169231 -0.402174 -0.905849 0.115604 -0.407522 -0.876336 0.148235 -0.458325 -0.882288 0.0808298 -0.463718 -0.86183 0.10422 -0.496374 -0.865395 0.0387979 -0.499587 -0.856043 0.050313 -0.514451 -0.958857 0.072077 -0.274586 -0.9602 0.072283 -0.269797 -0.957913 0.104293 -0.267444 -0.961195 0.102652 -0.256059 -0.966351 0.103653 -0.23542 -0.968909 0.0669951 -0.238175 -0.978733 0.0685656 -0.193339 -0.97369 0.0308388 -0.225781 -0.988687 0.0323346 -0.146466 -0.986432 0.0123718 -0.163704 -0.994008 0.0127359 -0.108567 -0.994061 0.00217538 -0.108806 -0.963058 0.222813 -0.151243 -0.950592 0.224883 -0.214014 -0.948701 0.234236 -0.212366 -0.943941 0.231446 -0.235389 -0.946424 0.13812 -0.291899 -0.963865 0.143357 -0.224528 -0.962798 0.0808431 -0.257847 -0.976384 0.0828801 -0.199512 -0.975154 0.0494205 -0.215946 -0.988499 0.0511046 -0.142334 -0.980436 0.0171096 -0.196095 -0.989612 0.0190102 -0.142502 -0.988964 0.0182732 -0.147022 -0.992912 0.00526982 -0.118739 -0.997242 0.0114245 -0.0733318 -0.999346 0 -0.0361659 -0.999346 0 -0.0361659 -0.999208 0.00213644 -0.0397406 -0.999209 0 -0.0397642 -0.999515 -0.00539481 -0.0306779 -0.937671 0.0110082 -0.347349 -0.94108 0.00361647 -0.338164 -0.917819 0.00398049 -0.396979 -0.915614 0.00751261 -0.401988 -0.890509 0.00334758 -0.454954 -0.884945 0.0103607 -0.465581 -0.857017 0.00383655 -0.515274 -0.849434 0.0120081 -0.527557 -0.816227 0.00508021 -0.577709 -0.808511 0.0130264 -0.588336 -0.768018 0.00703339 -0.640389 -0.760616 0.0146418 -0.649037 -0.715974 0.0087243 -0.698073 -0.710018 0.014426 -0.704036 -0.658611 0.0117396 -0.752392 -0.661159 0.00697861 -0.750214 -0.675859 0.00901277 -0.736976 -0.590775 0.127855 -0.796641 -0.729618 0.135612 -0.670274 -0.682001 0.123674 -0.720819 -0.680573 0.139522 -0.719273 -0.737788 0.15646 -0.65665 -0.737559 0.158504 -0.656416 -0.796356 0.176578 -0.578478 -0.789741 0.220301 -0.572518 -0.837636 0.183717 -0.514407 -0.824628 0.258871 -0.502965 -0.880355 0.217767 -0.421371 -0.870983 0.264633 -0.413954 -0.902989 0.213983 -0.372589 -0.888576 0.281741 -0.362016 -0.921348 0.198062 -0.3345 -0.925719 0.168631 -0.338539 -0.938731 0.172926 -0.298129 -0.952489 0.14077 -0.270088 -0.95425 0.125125 -0.271569 -0.945836 0.123196 -0.300362 -0.947988 0.0992792 -0.302428 -0.944565 0.0986445 -0.313155 -0.946794 0.0637635 -0.31546 -0.95923 0.0654035 -0.274956 -0.947576 0.0373353 -0.317342 -0.959154 0.0383454 -0.280272 -0.959699 0.00969447 -0.280862 -0.972503 0.00313256 -0.232869 -0.977304 0.00695855 -0.21173 -0.982397 0.00129899 -0.186801 -0.98458 0.00230907 -0.174918 -0.989482 0.00237374 -0.144635 -0.970881 -0.149857 -0.186906 -0.651489 -0.00537993 -0.758639 -0.944695 -0.28745 -0.157874 -0.942223 -0.291908 -0.164334 -0.931095 -0.311612 -0.189632 -0.911034 -0.359921 -0.201182 -0.891358 -0.423195 -0.162442 -0.961927 -0.227518 -0.151435 -0.971168 -0.103509 -0.214754 -0.975838 -0.131782 -0.174278 -0.974884 -0.131441 -0.17979 -0.9783 -0.0679955 -0.195717 -0.977799 -0.0686129 -0.197995 -0.977868 -0.068388 -0.197729 -0.982607 -0.0250435 -0.183999 -0.988935 -0.0188794 -0.147144 -0.991849 -0.0073997 -0.127205 -0.999178 -0.00230124 -0.040461 -0.997945 -0.00231464 -0.0640379 -0.999927 0 -0.0120962 -0.999927 0 -0.0120962 -0.746883 -0.394075 -0.535604 -0.714177 -0.33279 -0.615794 -0.750518 -0.357343 -0.555904 -0.731628 -0.255772 -0.631903 -0.721084 -0.317158 -0.615994 -0.691439 -0.284807 -0.663926 -0.701564 -0.29066 -0.650634 -0.717228 -0.196276 -0.668625 -0.731362 -0.201759 -0.651463 -0.740462 -0.123104 -0.660728 -0.773441 -0.130903 -0.620204 -0.695551 -0.155821 -0.701376 -0.623286 -0.109624 -0.774272 -0.668611 -0.120762 -0.733741 -0.672737 -0.0550641 -0.73783 -0.713862 -0.0603214 -0.697683 -0.697399 -0.226064 -0.680095 -0.644724 -0.166667 -0.746025 -0.675821 -0.177793 -0.715301 -0.683431 -0.0970168 -0.72354 -0.717158 -0.104015 -0.689105 -0.72032 -0.0476352 -0.692005 -0.766313 -0.0523301 -0.640333 -0.661161 -0.00643517 -0.750216 -0.649781 -0.0276966 -0.759616 -0.623478 -0.025892 -0.781412 -0.677368 -0.0365922 -0.734734 -0.828537 -0.236913 -0.507345 -0.796469 -0.171574 -0.579828 -0.868205 -0.194063 -0.456684 -0.841474 -0.140322 -0.521759 -0.901398 -0.154929 -0.404325 -0.879789 -0.111043 -0.462213 -0.926362 -0.119969 -0.357016 -0.909715 -0.0846383 -0.406516 -0.945091 -0.0900915 -0.314143 -0.932808 -0.0621974 -0.354965 -0.932606 -0.062173 -0.355499 -0.689016 -0.263165 -0.675278 -0.674047 -0.230169 -0.701914 -0.686593 -0.236094 -0.687641 -0.698321 -0.145184 -0.700906 -0.722791 -0.152451 -0.674042 -0.728645 -0.083163 -0.679824 -0.77674 -0.0911391 -0.623192 -0.764757 -0.0556171 -0.641914 -0.824679 -0.061587 -0.562238 -0.814848 -0.0474437 -0.57773 -0.864639 -0.051073 -0.499791 -0.856087 -0.0383931 -0.515404 -0.897003 -0.0406344 -0.440152 -0.889919 -0.0294073 -0.455169 -0.922934 -0.0308716 -0.383719 -0.917463 -0.0213325 -0.397249 -0.93236 -0.0219158 -0.360867 -0.961569 -0.00884155 -0.27442 -0.959616 -0.00704815 -0.281226 -0.943462 -0.0101138 -0.331327 -0.942718 -0.0457237 -0.330442 -0.922571 -0.043989 -0.383312 -0.932723 -0.0639562 -0.354876 -0.896268 -0.0601898 -0.439409 -0.909718 -0.084587 -0.40652 -0.863296 -0.0786701 -0.498528 -0.880083 -0.107517 -0.462487 -0.822485 -0.0981654 -0.560252 -0.842364 -0.131707 -0.522567 -0.78018 -0.118613 -0.614207 -0.79577 -0.176927 -0.579178 -0.755963 -0.164584 -0.633586 -0.750601 -0.20549 -0.62799 -0.788748 -0.285033 -0.544641 -0.992548 -0.0023681 -0.121829 -0.992549 -0.00218837 -0.121831 -0.994019 -0.0100379 -0.108748 -0.973341 -0.0421412 -0.225457 -0.970542 -0.0339103 -0.238534 -0.982671 -0.0351252 -0.182002 -0.9831 -0.0109234 -0.182743 -0.982333 -0.00961496 -0.186895 -0.99598 -0.0044049 -0.0894725 -0.994947 -0.00760184 -0.100117 -0.993994 -0.0127673 -0.108685 -0.989 -0.0125153 -0.147386 -0.983264 -0.0318317 -0.179384 -0.980184 -0.0315251 -0.195566 -0.972217 -0.0677027 -0.224075 -0.951921 -0.251397 -0.17506 -0.943233 -0.289899 -0.162081 -0.936788 -0.285292 -0.202574 -0.978265 -0.0470566 -0.20195 -0.977596 -0.0467526 -0.205232 -0.968038 -0.104006 -0.228222 -0.971061 -0.104779 -0.214623 -0.954432 -0.172742 -0.243349 -0.9673 -0.178896 -0.179797 -0.952205 -0.216921 -0.215059 -0.967005 -0.222877 -0.123396 -0.965708 -0.223107 -0.132785 -0.872828 -0.387301 -0.296933 -0.881959 -0.206703 -0.423581 -0.88994 -0.27529 -0.363624 -0.854885 -0.257682 -0.450301 -0.862645 -0.338585 -0.375771 -0.832746 -0.319495 -0.45217 -0.93985 -0.164151 -0.299562 -0.901557 -0.214164 -0.375937 -0.911863 -0.19527 -0.361076 -0.906257 -0.193258 -0.375965 -0.912238 -0.246078 -0.327518 -0.871934 -0.304895 -0.383105 -0.869973 -0.303717 -0.388461 -0.838284 -0.410695 -0.358622 -0.948896 -0.166951 -0.267814 -0.932488 -0.120666 -0.34045 -0.945671 -0.123554 -0.300734 -0.905355 -0.272072 -0.326051 -0.90626 -0.272588 -0.323092 -0.941714 -0.174592 -0.287563 -0.938497 -0.173483 -0.298541 -0.95917 -0.123185 -0.254594 -0.9563 -0.102078 -0.27399 -0.966258 -0.103986 -0.235654 -0.967615 -0.0869724 -0.236976 -0.960445 -0.065954 -0.270548 -0.986799 -0.0181419 -0.160931 -0.984139 -0.0262021 -0.175453 -0.979607 -0.050104 -0.194577 -0.978158 -0.0499312 -0.201776 -0.970197 -0.0822332 -0.227936 -0.969722 -0.0821616 -0.229975 -0.957055 -0.141797 -0.252863 -0.958501 -0.142241 -0.247068 -0.932822 -0.226375 -0.280352 -0.935726 -0.227885 -0.26923 -0.906683 -0.344065 -0.244019 -0.876029 -0.323179 -0.35795 -0.872953 -0.387403 -0.296434 -0.827926 -0.453453 -0.330029 -0.823197 -0.398542 -0.404365 -0.98942 0.0114882 -0.144625 -0.994884 -0.000604766 -0.101019 -0.997442 -0.000543174 -0.0714722 -0.999342 -0.0030488 -0.0361404 -0.999344 -0.00214115 -0.0361586 -0.999207 0 -0.0398071 -0.999197 0.00408569 -0.0398516 -0.999529 0 -0.0306784 -0.692632 -0.0906061 -0.715577 -0.614317 -0.0622391 -0.786601 -0.664419 -0.069579 -0.744115 -0.666252 -0.0124593 -0.745623 -0.715221 -0.0143235 -0.698752 -0.710066 -0.00841943 -0.704084 -0.767311 -0.0151745 -0.641096 -0.760682 -0.00644423 -0.649093 -0.81566 -0.0137978 -0.578368 -0.808574 -0.00395023 -0.588382 -0.856587 -0.0133146 -0.515831 -0.849493 -0.00250329 -0.527594 -0.890195 -0.0114447 -0.455437 -0.884989 -0.00274571 -0.465604 -0.917606 -0.00768701 -0.397417 -0.915632 -0.00418347 -0.401996 -0.941081 -0.00344567 -0.338164 -0.796392 -0.453029 -0.400655 -0.765864 -0.38332 -0.516254 -0.805212 -0.413824 -0.424717 -0.764157 -0.300008 -0.571016 -0.834107 -0.342791 -0.432158 -0.796445 -0.24654 -0.552171 -0.866992 -0.280667 -0.411766 -0.834582 -0.201551 -0.512689 -0.89935 -0.225947 -0.374323 -0.872718 -0.162065 -0.460541 -0.925515 -0.177524 -0.334526 -0.904532 -0.126815 -0.407111 -0.944331 -0.135964 -0.299589 -0.9284 -0.0960407 -0.358956 -0.958063 -0.101506 -0.267977 -0.946329 -0.0704321 -0.315437 -0.958757 -0.0722659 -0.274886 -0.960202 -0.0385421 -0.276635 -0.970386 -0.0395097 -0.238307 -0.95941 -0.0251104 -0.280894 -0.972184 -0.0259949 -0.232771 -0.97244 -0.00312096 -0.233133 -0.982318 -0.0113963 -0.186871 -0.977327 0.000772814 -0.211735 -0.98458 -0.00232074 -0.174918 0 0.0798601 -0.996806 -0.000342292 0.0803969 -0.996763 0.000322794 0.233825 -0.972279 0.00158643 0.231743 -0.972776 -0.000115669 0.308924 -0.951087 0.00266144 0.383395 -0.923581 0.0158037 0.711854 -0.70215 -0.0492703 0.762967 -0.644557 0.0400212 0.643887 -0.764073 -0.0020802 0.691295 -0.72257 0.000853796 0.599282 -0.800538 -0.00289162 0.611227 -0.79145 0.00511614 0.532892 -0.846168 0.0076164 0.528348 -0.848994 -0.00767119 0.413657 -0.910401 0.0305823 0.338606 -0.940431 0 0.994333 -0.106309 0.00502845 0.993105 -0.117122 -0.0062776 0.966064 -0.258228 0.00633915 0.960346 -0.27874 -0.00572761 0.907049 -0.420986 0.00569842 0.897758 -0.440452 -0.00640816 0.819945 -0.572406 -0.037279 0.847474 -0.529526 -0.0105476 0.819858 -0.572469 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.991991 -0.126308 -2.24785e-05 -0.991985 -0.126353 2.24389e-05 -0.957171 -0.289523 -0.00309477 -0.95535 -0.295461 0.00326102 -0.891044 -0.453904 -0.00326741 -0.895353 -0.445346 0.0020436 -0.822912 -0.568165 0.0123004 -0.808161 -0.588833 -0.00129504 -0.768657 -0.639659 0.00297614 -0.694493 -0.719493 -0.00305199 -0.684813 -0.728713 0.00122755 -0.603465 -0.797389 -0.0168176 -0.526308 -0.850128 -0.00337233 -0.550633 -0.834741 0.00308046 -0.415063 -0.909787 -0.00330703 -0.401169 -0.915998 0.00408913 -0.244635 -0.969607 -0.0046554 -0.255625 -0.966765 0.0043787 -0.0813772 -0.996674 0 -0.0874788 -0.996166 8.37274e-07 -0.999048 -0.043619 1.72072e-07 -0.999048 -0.0436203 3.6827e-08 -0.999048 -0.0436192 -4.96092e-07 -0.999048 -0.0436195 -5.16116e-07 -0.999048 -0.0436192 -8.09013e-07 -0.999048 -0.0436198 6.74887e-07 -0.999048 -0.0436172 3.60666e-07 -0.999048 -0.0436194 -2.76089e-07 -0.999048 -0.0436197 -2.60856e-07 -0.999048 -0.0436196 -1.65519e-07 -0.999048 -0.0436195 -1.94122e-07 -0.999048 -0.0436192 2.126e-07 -0.999048 -0.0436189 0 -0.999048 -0.0436195 0 -0.999048 -0.0436189 0 -0.999048 -0.0436202 -5.48998e-07 -0.999048 -0.0436195 -1.34372e-07 -0.999048 -0.0436191 1.16175e-07 -0.999048 -0.0436195 1.22394e-07 -0.999048 -0.0436195 2.75522e-07 -0.999048 -0.0436194 2.82209e-07 -0.999048 -0.0436195 2.51026e-07 -0.999048 -0.0436195 2.51234e-07 -0.999048 -0.0436195 1.89197e-08 -0.999048 -0.0436196 3.19935e-08 -0.999048 -0.0436194 0 -0.999048 -0.0436194 3.01494e-07 -0.999048 -0.0436193 3.90899e-07 -0.999048 -0.0436197 1.14115e-06 -0.999048 -0.0436192 0 -0.0802339 0.996776 -0.000341844 -0.0807698 0.996733 0.000331828 -0.236924 0.971528 -0.00176602 -0.240279 0.970702 0.0017758 -0.38919 0.921156 0.0351327 -0.337503 0.940669 -0.00623143 -0.411825 0.911242 0.0061999 -0.534982 0.844841 -0.00640096 -0.555624 0.831409 9.70428e-05 -0.613106 0.790001 -0.000580991 -0.687318 0.726357 0 -0.999911 -0.013369 0.00208577 -0.999992 -0.00352134 -0.0049891 -0.994926 0.100481 0.00500338 -0.992899 0.118852 -0.00263953 -0.973355 0.229287 -2.4846e-07 -0.971076 0.238772 -3.28006e-07 -0.94902 0.315217 0.00289984 -0.945873 0.324524 -0.00508055 -0.902063 0.431575 0.00507524 -0.893835 0.448367 -0.00185731 -0.84428 0.5359 6.31278e-07 -0.838856 0.544354 -1.58432e-06 -0.792642 0.609688 0.00372963 -0.786748 0.617263 -0.00505418 -0.701515 0.712637 0.0404988 -0.638915 0.768211 0 0.999225 0.0393568 -2.40372e-05 0.999223 0.039405 2.39216e-05 0.978995 0.203886 -0.00361418 0.977468 0.211054 0.00333673 0.93209 0.362212 -0.00333621 0.926758 0.375644 0.00359867 0.85628 0.5165 -0.00366328 0.848589 0.52904 0.00338651 0.755135 0.65556 -0.00339578 0.745354 0.66666 0.00365512 0.631906 0.775036 0.0140635 0.648336 0.761225 -6.18386e-06 0.284453 0.95869 9.24128e-06 0.367309 0.930099 0.00248567 0.36143 0.932396 -0.00414861 0.488865 0.872349 0.00401734 0.478666 0.877988 -0.00115995 0.575229 0.817992 -0.00165275 0.276873 0.960905 0.0042988 0.15862 0.98733 -0.0044343 0.170585 0.985333 0.00228712 0.0389419 0.999239 0 0.0458797 0.998947 0 0.999048 -0.0436195 -4.94084e-07 0.999048 -0.0436191 -3.29168e-07 0.999048 -0.0436191 -2.67204e-08 0.999048 -0.0436196 -7.53073e-08 0.999048 -0.0436194 4.06278e-07 0.999048 -0.0436197 -4.3684e-08 0.999048 -0.0436189 1.02343e-07 0.999048 -0.0436193 1.75539e-07 0.999048 -0.0436194 1.66559e-07 0.999048 -0.0436195 4.31835e-07 0.999048 -0.0436197 4.43147e-07 0.999048 -0.0436195 0 0.999048 -0.0436192 0 0.999048 -0.043619 6.18435e-07 0.999048 -0.0436196 6.13622e-07 0.999048 -0.0436199 -7.66981e-08 0.999048 -0.0436194 -2.63726e-08 0.999048 -0.0436193 0 0.999048 -0.0436196 -4.63642e-07 0.999048 -0.0436195 -2.67348e-08 0.999048 -0.0436194 -2.35418e-07 0.999048 -0.0436193 -3.19797e-07 0.999048 -0.0436195 -7.66989e-07 0.999048 -0.0436194 -7.90824e-07 0.999048 -0.0436195 4.56748e-09 0.999048 -0.0436198 3.02422e-08 0.999048 -0.0436193 6.20666e-07 0.999048 -0.0436195 -4.29751e-07 0.999048 -0.0436187 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.829889 0.347646 0.43638 0.988436 0.0328115 0.148048 0.94702 0.0143045 0.320857 0.723203 0.0137005 0.6905 0.720417 0.107487 0.685161 0.744161 0.21193 0.633491 0.667342 0.098057 0.738268 0.791554 0.475827 0.383446 0.713445 0.453858 0.533862 0.772606 0.408974 0.485613 0.663265 0.280039 0.694015 0.685667 0.235194 0.688872 0.713588 0.202149 0.670767 0.640399 0.0887619 0.762896 0.644188 0.0373736 0.763954 0.638029 0.013507 0.769894 0.640504 0.00590372 0.767932 0.99992 0 0.0126555 0.99992 0 0.0126555 0.998778 0.00469861 0.0491924 0.979211 0.0514181 0.196221 0.973817 0.139895 0.17919 0.974625 0.138332 0.175986 0.975035 0.137794 0.174124 0.971996 0.148511 0.182121 0.966145 0.183267 0.181594 0.967913 0.179599 0.175749 0.96249 0.233975 0.137362 0.956034 0.242832 0.164413 0.941154 0.29727 0.160808 0.941404 0.295812 0.162028 0.919232 0.34415 0.19124 0.903012 0.11911 0.412775 0.871713 0.152334 0.465738 0.870774 0.152176 0.467542 0.830128 0.188069 0.524897 0.833194 0.188794 0.519754 0.782066 0.226012 0.580768 0.796861 0.230717 0.558374 0.733439 0.267467 0.624923 0.726608 0.264717 0.634008 0.69474 0.298451 0.654418 0.726391 0.313005 0.611869 0.668219 0.351957 0.655446 0.878702 0.0834357 0.470023 0.857157 0.106574 0.503909 0.840504 0.104598 0.531612 0.814243 0.129208 0.565963 0.796633 0.126256 0.59113 0.764471 0.152524 0.626355 0.723448 0.143318 0.675339 0.715512 0.155012 0.681186 0.678581 0.145824 0.719905 0.650642 0.214162 0.72856 0.993925 0.00229413 0.110033 0.992349 0.0100391 0.123054 0.982764 0.0100141 0.184592 0.976847 0.0267784 0.212255 0.977511 0.00490937 0.210826 0.977143 0.00606071 0.212497 0.990673 0.000189785 0.136261 0.992371 -0.0047552 0.123194 0.995184 0.000612106 0.0980214 0.978233 0.0698198 0.195413 0.973168 0.0322635 0.227824 0.971178 0.0752425 0.226169 0.950724 0.00711638 0.309958 0.949351 0.0565845 0.309081 0.965122 0.0264152 0.260465 0.964912 0.0350208 0.260228 0.982275 0.0356916 0.184019 0.98614 0.0129016 0.165414 0.993866 0.0129109 0.109833 0.94874 0.239832 0.205848 0.948452 0.241104 0.205689 0.92387 0.288595 0.251352 0.923439 0.290174 0.251117 0.887473 0.345588 0.304896 0.97639 0.0915434 0.195659 0.971211 0.0494194 0.23304 0.962576 0.147319 0.227473 0.962131 0.0843138 0.259222 0.960263 0.106302 0.258058 0.950772 0.145784 0.27346 0.936315 0.178847 0.302206 0.925141 0.176527 0.336084 0.917413 0.287749 0.274869 0.946437 0.144492 0.288753 0.941758 0.238634 0.236952 0.963342 0.101089 0.248502 0.970828 0.184902 0.152656 0.974194 0.119268 0.191629 0.97456 0.134472 0.179305 0.834231 0.41973 0.35761 0.851034 0.429026 0.302783 0.843905 0.4426 0.303198 0.895956 0.219625 0.386042 0.897698 0.220073 0.381714 0.89869 0.400959 0.177732 0.90859 0.355318 0.219578 0.884569 0.404665 0.231915 0.86926 0.39669 0.294998 0.869576 0.316404 0.379112 0.890095 0.325165 0.319373 0.899673 0.200087 0.388013 0.931116 0.207538 0.299917 0.926581 0.166156 0.337402 0.947286 0.169683 0.271766 0.930652 0.125957 0.343542 0.944016 0.127553 0.304245 0.946611 0.10215 0.305767 0.683066 0.416584 0.599899 0.776899 0.379895 0.502103 0.746179 0.363872 0.557507 0.760361 0.313693 0.568725 0.77575 0.320679 0.543486 0.82036 0.268431 0.504929 0.817541 0.267422 0.510012 0.999982 0 0.00600697 0.983123 0.026716 0.180983 0.98602 0.0275115 0.164343 0.98508 0.0198964 0.170943 0.990824 0.0187988 0.133843 0.988812 0.0113191 0.148737 0.995482 0.00600671 0.0947604 0.995291 0.00515343 0.0967906 0.999331 -0.000144043 0.0365736 0.999329 0.00210825 0.0365766 0.999077 -0.00156759 0.0429226 0.998891 0.000492769 0.0470876 0.746967 0.474275 0.465945 0.844483 0.32661 0.42447 0.827296 0.346435 0.442226 0.831345 0.332938 0.444992 0.834111 0.334181 0.438841 0.85677 0.306463 0.41476 0.877059 0.223493 0.425228 0.895943 0.228532 0.380866 0.868319 0.169557 0.466126 0.923188 0.179888 0.339654 0.901534 0.132532 0.411913 0.922733 0.135363 0.360888 0.924301 0.12162 0.361769 0.899433 0.0753526 0.430515 0.891869 0.0845235 0.444327 0.894196 0.0412968 0.445767 0.861275 0.0401328 0.506551 0.851511 0.0513103 0.52182 0.820159 0.049574 0.569985 0.80876 0.0614671 0.584919 0.772518 0.0584406 0.632298 0.758604 0.0716993 0.647595 0.704079 0.0654237 0.707101 0.980775 0.0496112 0.18873 0.978288 0.0391531 0.203518 0.97583 0.0851453 0.201262 0.974759 0.0512205 0.217306 0.965375 0.106753 0.238024 0.968296 0.0691735 0.240039 0.95658 0.107805 0.2708 0.959263 0.0743848 0.272546 0.942815 0.101788 0.317393 0.945928 0.0563975 0.319437 0.918817 0.0767646 0.387147 0.921268 0.0129635 0.388711 0.889333 0.0341558 0.455983 0.900872 0.00438284 0.434063 0.852596 0.00864095 0.5225 0.858972 0.000214129 0.512022 0.810189 0.0199263 0.585829 0.807379 0.0241289 0.58954 0.760788 0.00412884 0.648988 0.707414 0.0391976 0.705712 0.706501 0.0611715 0.705064 0.653694 0.05529 0.754736 0.643327 0.152289 0.750292 0.999982 0 0.00600697 0.775765 -0.320649 0.543482 0.973231 -0.140288 0.182047 0.760373 -0.313662 0.568725 0.974186 -0.1203 0.191025 0.974616 -0.134938 0.178649 0.975032 -0.137743 0.174182 0.978397 -0.0354555 0.203673 0.994589 -0.00747356 0.103616 0.993867 -0.0129109 0.109829 0.995974 -0.0009047 0.0896339 0.997267 -0.0120947 0.0728788 0.640511 -0.0036709 0.76794 0.638011 -0.0134863 0.769909 0.644638 -0.033689 0.763745 0.651539 -0.0952649 0.75261 0.659062 -0.157211 0.735474 0.679328 -0.292128 0.673183 0.666753 -0.256345 0.699805 0.781982 -0.4987 0.373903 0.797624 -0.39979 0.451623 0.813327 -0.497433 0.301762 0.865467 -0.3947 0.30851 0.858027 -0.452261 0.243414 0.899415 -0.398126 0.18041 0.956608 -0.243929 0.159372 0.944585 -0.282432 0.167308 0.981 -0.0496073 0.187559 0.978945 -0.0495718 0.198013 0.968121 -0.0978686 0.230571 0.973966 -0.0935115 0.206509 0.953434 -0.179251 0.242555 0.966087 -0.183229 0.18194 0.968039 -0.179236 0.175431 0.672589 -0.2214 0.706121 0.660725 -0.141387 0.737192 0.715536 -0.154999 0.681163 0.720441 -0.107484 0.685137 0.704101 -0.0654182 0.70708 0.651486 -0.0956304 0.752609 0.643213 -0.0541333 0.763772 0.706519 -0.0611735 0.705045 0.708061 -0.0136865 0.706019 0.722959 -0.0293519 0.690267 0.701126 -0.363603 0.613364 0.679453 -0.291418 0.673364 0.694753 -0.298432 0.654413 0.713599 -0.202131 0.67076 0.744179 -0.211914 0.633475 0.723468 -0.143311 0.675319 0.792798 -0.15892 0.5884 0.859154 -0.0817978 0.505138 0.876632 -0.108871 0.468682 0.81689 -0.101781 0.567742 0.837655 -0.133138 0.529724 0.851972 -0.0397926 0.522073 0.860841 -0.0518171 0.506229 0.80935 -0.0489661 0.585282 0.819577 -0.0623691 0.569565 0.767921 -0.121452 0.628926 0.771734 -0.0732178 0.631717 0.759382 -0.0573436 0.648113 0.76081 -0.0041256 0.648961 0.810095 -0.0253678 0.58575 0.807437 -0.020952 0.589582 0.852638 -0.00295465 0.522494 0.992388 -0.00232392 0.123131 0.993894 -0.0100394 0.109884 0.977121 -0.00998984 0.21245 0.982516 -0.0269579 0.184218 0.950479 -0.0259706 0.309701 0.964034 -0.0573745 0.259514 0.971559 -0.0693781 0.226408 0.979869 -0.032502 0.196976 0.980099 -0.0208839 0.197408 0.991173 -0.0085323 0.132301 0.988727 -0.0192234 0.148489 0.9888 -0.0129087 0.148685 0.982849 -0.0326089 0.181508 0.982277 -0.0356828 0.18401 0.973088 -0.0353262 0.227708 0.963021 -0.0746521 0.258878 0.962038 -0.199745 0.185971 0.942446 -0.266046 0.202524 0.93516 -0.293121 0.198885 0.942065 -0.296075 0.157652 0.92269 -0.335021 0.190798 0.834123 -0.334153 0.438841 0.885239 -0.267525 0.380502 0.871622 -0.317242 0.373675 0.920198 -0.204921 0.333532 0.952929 -0.128591 0.274574 0.925395 -0.165936 0.340747 0.928135 -0.0774259 0.364104 0.926393 -0.100198 0.362982 0.829391 -0.210841 0.517355 0.859836 -0.218898 0.461266 0.905621 -0.176578 0.385579 0.895795 -0.174729 0.408683 0.929452 -0.136239 0.342868 0.942773 -0.137983 0.303546 0.944021 -0.127545 0.304231 0.938055 -0.168098 0.302977 0.908009 -0.202036 0.367018 0.897711 -0.220052 0.381697 0.878722 -0.215173 0.426084 0.863008 -0.283797 0.417944 0.849481 -0.278884 0.447891 0.774496 -0.32203 0.544475 0.908594 -0.355291 0.219603 0.903985 -0.353121 0.241076 0.936509 -0.236745 0.258654 0.930633 -0.234702 0.280781 0.958324 -0.14654 0.245238 0.95568 -0.146075 0.255614 0.969185 -0.0847534 0.231294 0.969513 -0.0847733 0.229907 0.977841 -0.0513532 0.202955 0.988351 -0.0518031 0.143106 0.98543 -0.0228299 0.168542 0.999691 0 0.0248553 0.999331 -0.00299428 0.0364544 0.999331 0 0.0365749 0.99933 -0.00210592 0.0365343 0.999191 0 0.040214 0.999191 -0.000478073 0.0402088 0.998885 0.00346811 0.0470873 0.725252 -0.426392 0.540554 0.705736 -0.342879 0.619976 0.746193 -0.363838 0.55751 0.726622 -0.264695 0.634001 0.784282 -0.288042 0.549484 0.743838 -0.213908 0.633205 0.823807 -0.239311 0.513879 0.790051 -0.178595 0.58645 0.864045 -0.196087 0.463655 0.836096 -0.146303 0.528714 0.89844 -0.156812 0.410141 0.875958 -0.115866 0.468266 0.864862 -0.114528 0.488771 0.891876 -0.0845159 0.444313 0.894511 -0.0309583 0.445974 0.886481 -0.0410245 0.460944 0.900872 -0.00439477 0.434063 0.858944 -0.00812139 0.512005 0.717423 -0.451072 0.530884 0.772621 -0.408935 0.485623 0.776195 -0.398715 0.488414 0.827303 -0.346406 0.442236 0.807411 -0.405078 0.428951 0.860623 -0.346178 0.373482 0.847295 -0.385494 0.365356 0.893463 -0.326601 0.308311 0.905696 -0.283116 0.315532 0.902669 -0.281947 0.325106 0.94122 -0.179855 0.285933 0.936323 -0.178832 0.30219 0.958094 -0.126838 0.256844 0.955335 -0.105843 0.275921 0.965379 -0.106736 0.238015 0.966921 -0.0891112 0.239004 0.959618 -0.0685917 0.272816 0.957022 -0.103122 0.271063 0.944998 -0.073341 0.318746 0.944654 -0.0785944 0.318515 0.920085 -0.0549667 0.387844 0.921275 -0.0129617 0.388695 0.950671 -0.0145158 0.309862 0.947091 -0.00735499 0.320881 0.977149 -0.00494841 0.2125 0.977506 -0.00592803 0.210825 0.992387 0.000812947 0.12316 0.990645 0.0075464 0.136257 0.995184 -0.00061256 0.0980214 0.746626 -0.199231 -0.63471 0.999859 -0.0135398 -0.0099724 0.644488 -0.0353493 -0.763797 0.923159 -0.351211 -0.156299 0.875279 -0.442736 -0.194607 0.88789 -0.411864 -0.204988 0.772534 -0.45836 -0.439428 0.829251 -0.404649 -0.38549 0.817888 -0.398763 -0.414785 0.711305 -0.388441 -0.585798 0.764554 -0.348802 -0.542028 0.759052 -0.346159 -0.551375 0.675814 -0.246315 -0.694697 0.679176 -0.236589 -0.6948 0.719777 -0.19119 -0.667358 0.646064 -0.143717 -0.749631 0.999076 0.000128762 -0.042988 0.995641 -0.00516108 -0.0931262 0.995974 -0.00703789 -0.0893632 0.988859 -0.00866772 -0.148602 0.991283 -0.0192316 -0.130338 0.985335 -0.0175835 -0.169721 0.98631 -0.0274263 -0.162606 0.983382 -0.0238049 -0.179983 0.978389 -0.033022 -0.204119 0.98062 -0.0440166 -0.19091 0.960877 -0.132841 -0.243042 0.976584 -0.113717 -0.182626 0.975745 -0.114129 -0.186806 0.975913 -0.155403 -0.153117 0.975939 -0.155376 -0.152973 0.975124 -0.155665 -0.157803 0.957823 -0.249934 -0.141804 0.967814 -0.215617 -0.129786 0.97084 -0.212178 -0.111582 0.942355 -0.298503 -0.151204 0.952989 -0.275209 -0.126776 0.943998 -0.271614 -0.187334 0.956116 -0.218155 -0.195578 0.974025 -0.159694 -0.160537 0.897873 -0.389292 -0.205613 0.927471 -0.334544 -0.166968 0.900227 -0.322918 -0.292088 0.944679 -0.247258 -0.215512 0.9123 -0.236017 -0.33467 0.950931 -0.196261 -0.239191 0.921757 -0.188095 -0.339094 0.812359 -0.458686 -0.36011 0.880854 -0.391501 -0.266128 0.828821 -0.366475 -0.422791 0.900886 -0.320673 -0.292529 0.84535 -0.297998 -0.443375 0.907885 -0.25481 -0.332893 0.86854 -0.241863 -0.432597 0.919238 -0.200877 -0.3386 0.897135 -0.195544 -0.396121 0.737266 -0.432368 -0.51913 0.781442 -0.378379 -0.496164 0.753794 -0.364318 -0.54687 0.806881 -0.312157 -0.501498 0.781599 -0.301425 -0.546119 0.854698 -0.262108 -0.448097 0.817059 -0.249138 -0.519947 0.875745 -0.209497 -0.43495 0.857292 -0.204743 -0.472367 0.902462 -0.166167 -0.39743 0.894837 -0.164855 -0.414837 0.977792 -0.0587189 -0.201186 0.972779 -0.0440918 -0.2275 0.969561 -0.0890454 -0.228085 0.974673 -0.0892637 -0.205047 0.969344 -0.0480272 -0.240967 0.979174 -0.048358 -0.197181 0.97806 -0.0665372 -0.197412 0.954685 -0.0652376 -0.290381 0.962767 -0.122208 -0.241132 0.951957 -0.121229 -0.281215 0.952602 -0.115953 -0.281254 0.961644 -0.116866 -0.24816 0.965182 -0.0830157 -0.248055 0.975531 -0.0829128 -0.20363 0.974303 -0.113754 -0.194405 0.962023 -0.0911835 -0.257288 0.954454 -0.15211 -0.256671 0.936929 -0.148753 -0.316287 0.9356 -0.157196 -0.316137 0.924501 -0.155497 -0.348022 0.928247 -0.129414 -0.348725 0.948021 -0.13158 -0.28973 0.937146 -0.0700351 -0.341837 0.978663 -0.0726613 -0.192195 0.641381 -0.0837197 -0.762641 0.654345 -0.0517772 -0.754421 0.705582 -0.0571389 -0.706321 0.64012 -0.00561403 -0.768254 0.637856 -0.0121076 -0.77006 0.703384 -0.0130452 -0.71069 0.707064 -0.00989297 -0.70708 0.771258 -0.0131412 -0.636387 0.982761 -0.00969954 -0.184628 0.976691 -0.0260389 -0.213064 0.955861 -0.0252449 -0.292733 0.94967 -0.0456498 -0.309907 0.921301 -0.0445541 -0.386289 0.905492 -0.0820728 -0.416352 0.877901 -0.0802003 -0.472077 0.856904 -0.101451 -0.505394 0.837917 -0.099395 -0.536671 0.812773 -0.121874 -0.56969 0.794614 -0.118873 -0.595364 0.762809 -0.14283 -0.630652 0.724183 -0.134407 -0.676383 0.716055 -0.14542 -0.682729 0.67318 -0.135425 -0.726972 0.657237 -0.192595 -0.728661 0.908626 -0.0216162 -0.417051 0.901271 -0.0399019 -0.431414 0.861098 -0.0389701 -0.506943 0.851846 -0.0490219 -0.521493 0.818569 -0.0474145 -0.572448 0.807916 -0.058144 -0.586423 0.770516 -0.0549384 -0.635048 0.999328 0 -0.0366462 0.999328 0 -0.0366462 0.669004 -0.0921186 -0.737528 0.720554 -0.100718 -0.686046 0.703193 -0.0609402 -0.708382 0.756702 -0.0671108 -0.650306 0.758216 -0.0337314 -0.651131 0.809563 -0.00236461 -0.587028 0.846936 -0.0213127 -0.531267 0.852936 -0.0129587 -0.521855 0.904364 0.00215308 -0.426756 0.902072 -0.00398685 -0.431567 0.929283 -0.00386162 -0.369348 0.874425 -0.0210662 -0.484703 0.951146 -0.00867486 -0.308619 0.950734 -0.00951589 -0.309861 0.977042 -0.00225592 -0.213035 0.977071 -0.00217726 -0.212901 0.987397 -0.00231092 -0.158243 0.979319 -0.00964461 -0.202091 0.99352 -0.00240063 -0.113631 0.993915 -0.0013973 -0.110145 0.99799 -0.00132856 -0.0633532 0.9995 0.00291853 -0.031483 0.999757 0 -0.0220383 0.99949 0 -0.0319189 0.999323 -0.00270972 -0.0366991 0.995657 -0.0028082 -0.0930576 0.993813 -0.0125578 -0.110356 0.988804 -0.0124684 -0.148699 0.982194 -0.0329005 -0.184968 0.965063 -0.0321302 -0.260039 0.963407 -0.0644933 -0.260167 0.937626 -0.0630336 -0.341883 0.915675 -0.115165 -0.385067 0.901832 -0.113765 -0.416841 0.870975 -0.144398 -0.46963 0.86754 -0.143866 -0.476107 0.827982 -0.176712 -0.532182 0.831435 -0.177507 -0.526504 0.780913 -0.211301 -0.587815 0.800761 -0.217369 -0.558152 0.736912 -0.251191 -0.627586 0.735431 -0.250635 -0.629542 0.703438 -0.283503 -0.651767 0.711233 -0.28682 -0.641781 0.688959 -0.316704 -0.651947 0.931167 0.129735 -0.34073 0.650574 0.118682 -0.750112 0.649146 0.0620051 -0.758133 0.644571 0.0507668 -0.762857 0.706545 0.284844 -0.64781 0.713142 0.376515 -0.591325 0.927496 0.334468 -0.16698 0.956729 0.266333 -0.117203 0.948433 0.285432 -0.137852 0.934147 0.31963 -0.158761 0.919865 0.363009 -0.148569 0.97114 0.210663 -0.111839 0.9851 0.0189984 -0.17093 0.994563 0.00742106 -0.103871 0.991181 0.00827424 -0.132254 0.997301 0.000223637 -0.0734244 0.999689 0 -0.0249262 0.752712 0.365329 -0.547685 0.90027 0.322852 -0.292028 0.934051 0.267816 -0.236272 0.95194 0.274648 -0.135566 0.965285 0.222202 -0.137297 0.900367 0.126217 -0.416423 0.922226 0.169539 -0.347499 0.865218 0.159725 -0.475275 0.893366 0.214057 -0.395066 0.827965 0.197229 -0.524953 0.862804 0.264922 -0.430564 0.795863 0.241905 -0.555053 0.837414 0.325235 -0.439272 0.84076 0.32668 -0.431744 0.973566 0.0325009 -0.226083 0.978064 0.0665306 -0.197392 0.968253 0.0659991 -0.241102 0.966399 0.0888653 -0.241196 0.955552 0.0883114 -0.281285 0.966526 0.117307 -0.22818 0.941587 0.114776 -0.316607 0.956704 0.152498 -0.247915 0.928757 0.14717 -0.340224 0.94691 0.195017 -0.255596 0.921961 0.188085 -0.338542 0.940354 0.24559 -0.235414 0.949511 0.249006 -0.190852 0.964692 0.168309 -0.202584 0.971641 0.21176 -0.105221 0.995604 0.00898734 -0.0932305 0.995555 0.0125879 -0.0933332 0.993909 0.00283615 -0.110163 0.877885 0.389976 -0.277915 0.848052 0.299026 -0.437484 0.890831 0.316408 -0.326047 0.860055 0.239092 -0.45071 0.906908 0.254443 -0.335823 0.879381 0.191279 -0.436007 0.927219 0.202793 -0.314865 0.904693 0.152405 -0.397875 0.946572 0.15883 -0.280667 0.929571 0.119042 -0.348893 0.949385 0.120968 -0.289888 0.954274 0.0711451 -0.290342 0.962905 0.0716936 -0.260144 0.965279 0.0255962 -0.259965 0.977042 0.00217771 -0.213035 0.987397 0.00231257 -0.158243 0.982411 0.0262764 -0.184872 0.982724 0.0123637 -0.184663 0.988253 0.0331927 -0.14918 0.988691 0.0183802 -0.148834 0.980274 0.019642 -0.196665 0.98798 0.0485989 -0.146741 0.977692 0.0482928 -0.204418 0.978326 0.0347215 -0.204139 0.973752 0.0178758 -0.226909 0.978669 0.0567597 -0.197447 0.965195 0.0829906 -0.248013 0.975908 0.0828748 -0.201828 0.961117 0.100499 -0.257206 0.975311 0.114376 -0.188908 0.962345 0.120598 -0.243613 0.974166 0.154281 -0.164918 0.975695 0.155689 -0.15421 0.705593 0.057144 -0.706309 0.681521 0.09421 -0.725709 0.657994 0.090307 -0.747589 0.661641 0.179831 -0.727937 0.63985 0.0117675 -0.76841 0.640083 0.0121372 -0.76821 0.707025 0.0131052 -0.707067 0.703411 0.00971289 -0.710717 0.75875 0.0124965 -0.651262 0.771059 0.0262306 -0.636223 0.809567 0.00236605 -0.587022 0.852718 0.0244398 -0.5218 0.84704 0.0145072 -0.531332 0.902096 -0.00140776 -0.431534 0.696657 0.18431 -0.693324 0.687943 0.18172 -0.702647 0.688344 0.313952 -0.653924 0.690053 0.339794 -0.639035 0.703457 0.28353 -0.651735 0.678353 0.307611 -0.667243 0.739468 0.336776 -0.582897 0.741112 0.426888 -0.51819 0.907859 0.044021 -0.416959 0.918826 0.082953 -0.385846 0.858817 0.0788718 -0.506174 0.875825 0.103496 -0.471402 0.815237 0.0969337 -0.570957 0.835147 0.125603 -0.535494 0.766003 0.11418 -0.632616 0.790944 0.149036 -0.593461 0.754914 0.141112 -0.640462 0.901831 0.0215157 -0.431554 0.908029 0.0400513 -0.416988 0.852278 0.0387563 -0.521652 0.860637 0.0494444 -0.506812 0.808454 0.0469236 -0.586686 0.817978 0.0590227 -0.572214 0.757419 0.0538332 -0.650707 0.769727 0.0686421 -0.634672 0.723203 0.0632413 -0.687734 0.716067 0.145436 -0.682713 0.67466 0.13578 -0.725533 0.675166 0.248865 -0.694418 0.95114 0.00942212 -0.308617 0.977072 0.00224909 -0.212897 0.977014 0.00960992 -0.21296 0.979318 0.00964574 -0.202097 0.993913 0.00211884 -0.110149 0.993522 0.00140177 -0.113631 0.99799 0.0013282 -0.0633532 0.999465 0.00359608 -0.0325011 0.999473 0.00270151 -0.0323564 0.999328 0 -0.0366466 0.999331 -0.00224924 -0.0365083 0.999757 0 -0.0220383 0.904359 0.00397297 -0.426753 0.929283 0.00386067 -0.369348 0.874372 0.0210705 -0.484799 0.950746 0.00876445 -0.309848 0.949673 0.0456535 -0.3099 0.943704 0.0633854 -0.32466 0.920349 0.0620254 -0.386148 0.932747 0.116853 -0.341068 0.87505 0.110994 -0.471134 0.897362 0.148474 -0.415569 0.833547 0.138586 -0.534784 0.861121 0.184375 -0.473789 0.788296 0.167625 -0.592023 0.822637 0.224112 -0.522535 0.74638 0.200829 -0.634496 0.789315 0.270998 -0.550947 0.77837 0.266842 -0.568275 0.753824 0.364321 -0.546826 0.776755 0.375977 -0.505265 0.776757 0.377602 -0.504048 0.805208 0.475924 -0.353747 0.852454 0.377669 -0.361509 0.866721 0.471817 -0.161813 0.886946 0.407095 -0.218176 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.12108 -0.992643 0 -0.12108 -0.992643 0 0.0949378 -0.995483 0 0.0949378 -0.995483 0 -0.210411 -0.977613 0 -0.190857 -0.977137 0.0936836 -0.174387 -0.984677 0 -0.141213 -0.989979 0 -0.118705 -0.988868 0.0897191 -0.104781 -0.994495 0 -0.0713168 -0.997454 0 -0.0458797 -0.995708 0.0803764 -0.0346581 -0.999399 0 -0.00106845 -0.999999 0 0.0273173 -0.997471 0.0656193 0.105755 -0.994392 0 0.10053 -0.993897 0.0454074 0.0691851 -0.997604 0 0.0356364 -0.999365 0 0.0304038 -0.999538 0 0.0845763 -0.990676 -0.106804 0.0686634 -0.997045 -0.0344604 0.129398 -0.991593 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0.0990044 0.995087 0 0.0685105 0.994824 -0.0750387 0.0304038 0.999538 0 0.100634 0.994924 0 0.105607 0.993006 0.0527916 0.0691851 0.997604 0 0.0273764 0.999625 0 0.0355088 0.995786 0.0845528 -0.00106832 0.999999 0 -0.0346581 0.999399 0 -0.0458797 0.995708 0.0803761 -0.210411 0.977613 0 -0.190857 0.977137 0.0936836 -0.0713167 0.997454 0 -0.104781 0.994495 0 -0.118705 0.988868 0.089719 -0.141213 0.989979 0 -0.174387 0.984677 0 0.0949378 0.995483 0 0.0949378 0.995483 0 -0.12108 0.992643 0 -0.12108 0.992643 0 0.201912 0.979404 0 0.201912 0.979404 9.63978e-08 0.201912 0.979404 0 0.365571 0.930784 0 0.365571 0.930784 0 0.656461 0.75436 0 0.656461 0.75436 0 0.871371 0.490624 0 0.871371 0.490624 0 0.985426 0.170106 0 0.985426 0.170106 0 1 0 0 1 0 0 0.985426 -0.170106 0 0.985426 -0.170106 0 0.871371 -0.490624 0 0.871371 -0.490624 0 0.656461 -0.75436 0 0.656461 -0.75436 0 0.365571 -0.930784 0 0.365571 -0.930784 0 0.201912 -0.979404 0 0.201912 -0.979404 9.56438e-08 0.201912 -0.979404 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.0422458 -0.999107 0 -0.195039 -0.980527 -0.0229654 -0.236349 -0.971668 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.831469 -0.555571 0 -0.831469 -0.555571 0 -0.980785 -0.195091 0 -0.980785 -0.195091 0 -0.0422458 0.999107 0 -0.195039 0.980527 -0.0229654 -0.236349 0.971668 0 -0.555571 0.831469 0 -0.555571 0.831469 0 -0.831469 0.555571 0 -0.831469 0.555571 0 -0.980785 0.195091 0 -0.980785 0.195091 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.25882 -0.965925 0 -0.25882 -0.965925 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.25882 0.965925 0 -0.25882 0.965925 0 0.508589 0.50859 -0.694747 0.508589 0.50859 -0.694747 0.694746 0.186157 -0.694747 0.694748 0.186155 -0.694746 0.694747 -0.186158 -0.694746 0.694747 -0.186155 -0.694747 0.508589 -0.508591 -0.694747 0.508589 -0.50859 -0.694747 0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 -0.186158 -0.694747 -0.694746 -0.186157 -0.694746 -0.694747 -0.508589 -0.50859 -0.694747 -0.508589 -0.50859 -0.694747 -0.694746 -0.186157 -0.694747 -0.694748 -0.186155 -0.694746 -0.694747 0.186158 -0.694746 -0.694747 0.186155 -0.694747 -0.508589 0.508591 -0.694747 -0.508589 0.50859 -0.694747 -0.186158 0.694746 -0.694747 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.258818 0.965926 0 0.258818 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.25882 -0.965925 0 -0.25882 -0.965925 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.25882 0.965925 0 -0.25882 0.965925 0 0.508589 0.50859 -0.694747 0.508589 0.50859 -0.694747 0.694746 0.186157 -0.694747 0.694748 0.186155 -0.694746 0.694747 -0.186158 -0.694746 0.694747 -0.186155 -0.694747 0.508589 -0.508591 -0.694747 0.508589 -0.50859 -0.694747 0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 -0.186158 -0.694747 -0.694746 -0.186157 -0.694746 -0.694747 -0.508589 -0.50859 -0.694747 -0.508589 -0.50859 -0.694747 -0.694746 -0.186157 -0.694747 -0.694748 -0.186155 -0.694746 -0.694747 0.186158 -0.694746 -0.694747 0.186155 -0.694747 -0.508589 0.508591 -0.694747 -0.508589 0.50859 -0.694747 -0.186158 0.694746 -0.694747 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.258818 0.965926 0 0.258818 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707114 -0.707099 0 -0.707114 -0.707099 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707114 0.707099 0 -0.707114 0.707099 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.508589 0.508591 -0.694746 0.508588 0.508592 -0.694747 0.694746 0.186157 -0.694747 0.694746 0.186158 -0.694747 0.694746 -0.186157 -0.694747 0.694746 -0.186158 -0.694747 0.508589 -0.508591 -0.694747 0.508588 -0.508592 -0.694746 0.186156 -0.694747 -0.694746 0.186157 -0.694747 -0.694746 -0.186156 -0.694747 -0.694747 -0.186157 -0.694747 -0.694746 -0.508597 -0.508586 -0.694745 -0.508591 -0.508588 -0.694747 -0.694746 -0.186157 -0.694747 -0.694746 -0.186158 -0.694747 -0.694746 0.186157 -0.694747 -0.694746 0.186158 -0.694747 -0.508594 0.508584 -0.694748 -0.508592 0.508589 -0.694745 -0.186156 0.694747 -0.694746 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186157 0.694747 -0.694746 0.258818 0.965926 0 0.258818 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707114 -0.707099 0 -0.707114 -0.707099 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707114 0.707099 0 -0.707114 0.707099 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.508589 0.508591 -0.694746 0.508588 0.508592 -0.694747 0.694746 0.186157 -0.694747 0.694746 0.186158 -0.694747 0.694746 -0.186157 -0.694747 0.694746 -0.186158 -0.694747 0.508589 -0.508591 -0.694747 0.508588 -0.508592 -0.694746 0.186156 -0.694747 -0.694746 0.186157 -0.694747 -0.694746 -0.186156 -0.694747 -0.694747 -0.186157 -0.694747 -0.694746 -0.508597 -0.508586 -0.694745 -0.508591 -0.508588 -0.694747 -0.694746 -0.186157 -0.694747 -0.694746 -0.186158 -0.694747 -0.694746 0.186157 -0.694747 -0.694746 0.186158 -0.694747 -0.508594 0.508584 -0.694748 -0.508592 0.508589 -0.694745 -0.186156 0.694747 -0.694746 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186157 0.694747 -0.694746 0.0711828 -0.703754 -0.706868 0.0711828 -0.703755 -0.706868 0.0193645 -0.707081 -0.706868 0.0193645 -0.70708 -0.706868 -0.0325581 -0.706596 -0.706868 -0.0325582 -0.706596 -0.706868 -0.0843053 -0.702303 -0.706868 -0.0843055 -0.702304 -0.706867 -0.135598 -0.694228 -0.706867 -0.135599 -0.694228 -0.706867 0.0486387 -0.70627 -0.70627 0.0486387 -0.706271 -0.706269 0.0673279 -0.705976 -0.705028 0.0673278 -0.705976 -0.705028 -0.0858672 -0.703961 -0.705029 -0.0858667 -0.703962 -0.705028 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0.142774 -0.692544 -0.707106 0.142774 -0.692544 -0.707106 -0.139281 -0.700215 -0.700214 -0.139282 -0.700215 -0.700214 -0.39664 -0.593612 -0.700215 -0.396641 -0.593617 -0.70021 -0.593617 -0.396644 -0.700209 -0.593616 -0.396641 -0.700212 -0.700218 -0.139283 -0.700211 -0.70021 -0.139277 -0.70022 0.701897 -0.121163 -0.701897 0.701899 -0.121162 -0.701896 0.62066 -0.349462 -0.701896 0.620658 -0.349462 -0.701898 0.467582 -0.537314 -0.701898 0.467583 -0.537314 -0.701897 0.260388 -0.662977 -0.701897 0.260389 -0.662978 -0.701896 -0.707102 0 -0.707112 -0.707102 0 -0.707112 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.700209 0.139281 -0.70022 -0.700219 0.139279 -0.700211 -0.593615 0.396642 -0.700211 -0.593618 0.396643 -0.700209 -0.396643 0.593616 -0.70021 -0.396638 0.593613 -0.700216 -0.139281 0.700215 -0.700214 -0.139282 0.700215 -0.700214 0.260388 0.662978 -0.701897 0.260388 0.662977 -0.701897 0.467583 0.537315 -0.701897 0.467582 0.537314 -0.701898 0.620658 0.349461 -0.701898 0.62066 0.349463 -0.701896 0.701899 0.121163 -0.701896 0.701897 0.121162 -0.701897 0 0.707107 -0.707106 0 0.707107 -0.707106 0.142774 0.692544 -0.707106 0.142774 0.692544 -0.707106 0.0486387 0.706271 -0.706269 0.0486387 0.70627 -0.70627 -0.0858674 0.703962 -0.705028 -0.0858665 0.703961 -0.705029 0.0673279 0.705976 -0.705028 0.0673278 0.705976 -0.705028 -0.135598 0.694228 -0.706867 -0.135598 0.694228 -0.706867 -0.0843054 0.702304 -0.706867 -0.0843054 0.702303 -0.706868 -0.0325581 0.706596 -0.706868 -0.0325581 0.706596 -0.706868 0.0193645 0.707081 -0.706868 0.0193645 0.70708 -0.706868 0.0711828 0.703755 -0.706868 0.0711828 0.703754 -0.706868 -0.163286 0.708258 0.686811 -0.162521 0.706539 0.68876 0.11558 0.7062 0.698515 0.126905 0.724701 0.677276 0.130024 0.740644 0.659197 0.103895 0.698195 0.708329 0.0767454 0.707935 0.702096 0.0747985 0.703317 0.706931 -0.16438 0.709339 0.685432 -0.148795 0.691331 0.707052 -0.113237 0.698184 0.706907 -0.129834 0.733112 0.6676 -0.0998577 0.700058 0.707069 -0.0661032 0.704211 0.706907 -0.0771584 0.732322 0.676573 -0.0504301 0.705329 0.707084 -0.0186713 0.70706 0.706907 -0.0252418 0.72787 0.68525 -0.000755388 0.707118 0.707095 0.0288448 0.706718 0.706907 0.0256696 0.719862 0.693642 0.0489217 0.705417 0.707102 0.130024 -0.740644 0.659197 0.126905 -0.724701 0.677276 0.11558 -0.7062 0.698515 -0.16438 -0.709339 0.685432 -0.162521 -0.706539 0.68876 -0.163286 -0.708258 0.686811 0.105379 -0.699222 0.707096 0.0983583 -0.700233 0.707106 0.0767454 -0.707935 0.702096 0.0747985 -0.703317 0.706931 0.0489217 -0.705417 0.707102 0.0292913 -0.717657 0.69578 0.0252039 -0.706801 0.706964 -0.000755481 -0.707118 0.707095 -0.0190857 -0.722753 0.690843 -0.0245109 -0.706795 0.706993 -0.0504302 -0.705329 0.707084 -0.0678788 -0.723127 0.687372 -0.0741007 -0.703301 0.707019 -0.0998577 -0.700058 0.707069 -0.116572 -0.718746 0.68543 -0.123321 -0.696336 0.707042 -0.148795 -0.691331 0.707052 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.508591 0.508592 -0.694744 0.508589 0.508592 -0.694745 0.694748 0.186156 -0.694746 0.694747 0.186157 -0.694747 0.694747 -0.186156 -0.694747 0.694747 -0.186157 -0.694746 0.50859 -0.508591 -0.694746 0.50859 -0.508593 -0.694745 0.186157 -0.694748 -0.694745 0.186158 -0.694746 -0.694746 -0.186157 -0.694747 -0.694747 -0.186157 -0.694746 -0.694747 -0.508588 -0.508589 -0.694748 -0.508591 -0.508589 -0.694746 -0.694747 -0.186156 -0.694746 -0.694747 -0.186157 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.50859 0.508591 -0.694746 -0.50859 0.508588 -0.694748 -0.186156 0.694747 -0.694747 -0.186156 0.694747 -0.694746 0.186157 0.694747 -0.694746 0.186157 0.694748 -0.694745 0.508591 0.508592 -0.694744 0.508589 0.508592 -0.694746 0.694748 0.186156 -0.694746 0.694747 0.186156 -0.694747 0.694747 -0.186156 -0.694747 0.694747 -0.186157 -0.694746 0.50859 -0.508591 -0.694746 0.50859 -0.508593 -0.694745 0.186157 -0.694748 -0.694745 0.186157 -0.694747 -0.694746 -0.186157 -0.694747 -0.694746 -0.186156 -0.694747 -0.694747 -0.508588 -0.508589 -0.694748 -0.508591 -0.508589 -0.694746 -0.694748 -0.186156 -0.694746 -0.694747 -0.186157 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.50859 0.508591 -0.694746 -0.508589 0.508588 -0.694748 -0.186157 0.694746 -0.694747 -0.186156 0.694748 -0.694745 0.186157 0.694748 -0.694745 0.186157 0.694748 -0.694745 0.508588 0.508589 -0.694748 0.508591 0.508589 -0.694746 0.694748 0.186156 -0.694746 0.694747 0.186157 -0.694747 0.694747 -0.186156 -0.694747 0.694747 -0.186157 -0.694746 0.50859 -0.508591 -0.694746 0.508589 -0.508588 -0.694748 0.186157 -0.694746 -0.694747 0.186157 -0.694747 -0.694747 -0.186159 -0.694746 -0.694746 -0.186158 -0.694746 -0.694747 -0.508588 -0.508589 -0.694748 -0.508591 -0.508589 -0.694746 -0.694747 -0.186156 -0.694746 -0.694747 -0.186157 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.50859 0.508591 -0.694746 -0.50859 0.508588 -0.694748 -0.186158 0.694746 -0.694747 -0.186157 0.694747 -0.694746 0.186157 0.694747 -0.694746 0.186156 0.694747 -0.694747 0.508588 0.508589 -0.694748 0.508591 0.508589 -0.694746 0.694748 0.186156 -0.694746 0.694747 0.186156 -0.694747 0.694747 -0.186156 -0.694747 0.694747 -0.186157 -0.694746 0.50859 -0.508591 -0.694746 0.50859 -0.508588 -0.694748 0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694746 -0.186158 -0.694747 -0.694746 -0.186157 -0.694746 -0.694747 -0.508588 -0.508589 -0.694748 -0.508591 -0.508589 -0.694746 -0.694748 -0.186156 -0.694746 -0.694747 -0.186157 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.50859 0.508591 -0.694746 -0.508589 0.508588 -0.694748 -0.186158 0.694746 -0.694747 -0.186157 0.694748 -0.694745 0.186157 0.694748 -0.694745 0.186156 0.694747 -0.694747 0.508593 0.50859 -0.694744 0.50859 0.50859 -0.694746 0.694745 0.186161 -0.694747 0.694752 0.186158 -0.694741 0.694751 -0.186163 -0.694741 0.694747 -0.186157 -0.694746 0.508593 -0.508587 -0.694747 0.508593 -0.508593 -0.694742 0.186157 -0.694751 -0.694743 0.186159 -0.694746 -0.694746 -0.186156 -0.694747 -0.694747 -0.186159 -0.694748 -0.694744 -0.50859 -0.50859 -0.694746 -0.50859 -0.50859 -0.694746 -0.694748 -0.186156 -0.694746 -0.694747 -0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.508589 0.508592 -0.694746 -0.508589 0.508589 -0.694748 -0.186158 0.694746 -0.694747 -0.186156 0.694749 -0.694744 0.186159 0.694749 -0.694744 0.186157 0.694748 -0.694745 0.508593 0.50859 -0.694744 0.50859 0.50859 -0.694746 0.694745 0.186161 -0.694747 0.694752 0.186158 -0.694741 0.694751 -0.186163 -0.694741 0.694747 -0.186157 -0.694746 0.508593 -0.508587 -0.694747 0.508593 -0.508593 -0.694742 0.186157 -0.694751 -0.694743 0.186159 -0.694746 -0.694746 -0.186156 -0.694747 -0.694747 -0.186159 -0.694748 -0.694744 -0.50859 -0.50859 -0.694746 -0.50859 -0.50859 -0.694746 -0.694748 -0.186156 -0.694746 -0.694747 -0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.508589 0.508592 -0.694746 -0.508589 0.508589 -0.694748 -0.186158 0.694746 -0.694747 -0.186156 0.694749 -0.694744 0.186159 0.694749 -0.694744 0.186157 0.694748 -0.694745 0.508595 0.508589 -0.694744 0.508591 0.508589 -0.694746 0.694745 0.186161 -0.694747 0.694752 0.186158 -0.694741 0.694751 -0.186163 -0.694741 0.694748 -0.186157 -0.694745 0.508593 -0.50859 -0.694745 0.508593 -0.50859 -0.694744 0.186156 -0.694748 -0.694745 0.186157 -0.694747 -0.694747 -0.186156 -0.694747 -0.694747 -0.186156 -0.694747 -0.694747 -0.508587 -0.50859 -0.694748 -0.508592 -0.50859 -0.694745 -0.694748 -0.186156 -0.694745 -0.694747 -0.186157 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.50859 0.50859 -0.694746 -0.50859 0.508588 -0.694748 -0.186156 0.694747 -0.694747 -0.186156 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186157 0.694748 -0.694745 0.508595 0.508589 -0.694744 0.508591 0.508589 -0.694746 0.694745 0.186161 -0.694747 0.694752 0.186158 -0.694741 0.694751 -0.186163 -0.694741 0.694748 -0.186157 -0.694745 0.508593 -0.50859 -0.694745 0.508593 -0.50859 -0.694744 0.186156 -0.694748 -0.694745 0.186157 -0.694747 -0.694747 -0.186156 -0.694747 -0.694747 -0.186156 -0.694747 -0.694747 -0.508587 -0.50859 -0.694748 -0.508592 -0.50859 -0.694745 -0.694748 -0.186156 -0.694745 -0.694747 -0.186157 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.50859 0.50859 -0.694746 -0.50859 0.508588 -0.694748 -0.186156 0.694747 -0.694747 -0.186156 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186157 0.694748 -0.694745 0.508587 0.50859 -0.694748 0.50859 0.50859 -0.694746 0.694748 0.186156 -0.694746 0.694747 0.186156 -0.694747 0.694747 -0.186156 -0.694747 0.694747 -0.186157 -0.694746 0.50859 -0.50859 -0.694746 0.50859 -0.50859 -0.694746 0.186156 -0.694749 -0.694744 0.186158 -0.694746 -0.694746 -0.186156 -0.694747 -0.694747 -0.18616 -0.694749 -0.694744 -0.508591 -0.508591 -0.694744 -0.508589 -0.508591 -0.694746 -0.694748 -0.186156 -0.694746 -0.694747 -0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.508589 0.508592 -0.694746 -0.508589 0.508591 -0.694746 -0.186159 0.694746 -0.694746 -0.186158 0.694749 -0.694744 0.186159 0.694749 -0.694744 0.186156 0.694747 -0.694747 0.508589 0.508591 -0.694746 0.50859 0.508591 -0.694746 0.694747 0.186157 -0.694746 0.694746 0.186157 -0.694746 0.694747 -0.186157 -0.694747 0.694747 -0.186158 -0.694746 0.508591 -0.508589 -0.694746 0.508591 -0.508592 -0.694744 0.186157 -0.69475 -0.694743 0.186159 -0.694746 -0.694746 -0.186156 -0.694747 -0.694747 -0.18616 -0.694749 -0.694744 -0.508592 -0.508591 -0.694744 -0.50859 -0.508591 -0.694746 -0.694747 -0.186157 -0.694746 -0.694746 -0.186157 -0.694746 -0.694747 0.186157 -0.694747 -0.694747 0.186158 -0.694746 -0.508589 0.508591 -0.694746 -0.508589 0.508591 -0.694746 -0.186159 0.694746 -0.694746 -0.186157 0.694749 -0.694744 0.186159 0.694749 -0.694744 0.186157 0.694747 -0.694746 0.508589 0.508591 -0.694746 0.50859 0.508591 -0.694746 0.694747 0.186157 -0.694746 0.694748 0.186157 -0.694745 0.694748 -0.186157 -0.694745 0.694747 -0.186157 -0.694746 0.508591 -0.508589 -0.694746 0.508591 -0.508592 -0.694744 0.186157 -0.69475 -0.694743 0.186159 -0.694746 -0.694746 -0.186156 -0.694747 -0.694747 -0.186159 -0.694749 -0.694744 -0.508592 -0.508591 -0.694744 -0.50859 -0.508591 -0.694746 -0.694747 -0.186157 -0.694746 -0.694748 -0.186157 -0.694745 -0.694748 0.186157 -0.694745 -0.694747 0.186157 -0.694746 -0.508589 0.508591 -0.694746 -0.508589 0.508591 -0.694746 -0.186159 0.694746 -0.694746 -0.186157 0.694749 -0.694744 0.186159 0.694749 -0.694744 0.186157 0.694747 -0.694746 0.508588 0.508591 -0.694746 0.508589 0.508591 -0.694746 0.694748 0.186156 -0.694746 0.694747 0.186156 -0.694747 0.694747 -0.186156 -0.694747 0.694747 -0.186157 -0.694746 0.50859 -0.50859 -0.694746 0.50859 -0.508592 -0.694745 0.186157 -0.69475 -0.694743 0.186159 -0.694746 -0.694746 -0.186156 -0.694747 -0.694747 -0.18616 -0.694749 -0.694743 -0.508593 -0.508593 -0.694742 -0.508588 -0.508593 -0.694746 -0.694748 -0.186156 -0.694746 -0.694747 -0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.508589 0.508592 -0.694746 -0.508589 0.508593 -0.694745 -0.186159 0.694747 -0.694746 -0.186158 0.694749 -0.694744 0.186159 0.694749 -0.694744 0.186157 0.694747 -0.694746 0.50859 0.50859 -0.694746 0.50859 0.50859 -0.694746 0.694748 0.186156 -0.694746 0.694747 0.186156 -0.694747 0.694747 -0.186156 -0.694747 0.694748 -0.186157 -0.694745 0.50859 -0.508593 -0.694744 0.50859 -0.50859 -0.694746 0.186156 -0.694748 -0.694746 0.186156 -0.694747 -0.694747 -0.186156 -0.694747 -0.694747 -0.186157 -0.694748 -0.694745 -0.50859 -0.508593 -0.694745 -0.50859 -0.508593 -0.694744 -0.694748 -0.186156 -0.694745 -0.694747 -0.186157 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.50859 0.50859 -0.694746 -0.50859 0.508592 -0.694745 -0.186156 0.694748 -0.694745 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186157 0.694747 -0.694746 0.508591 0.50859 -0.694746 0.508591 0.508589 -0.694746 0.694747 0.186157 -0.694746 0.694748 0.186157 -0.694745 0.694748 -0.186157 -0.694745 0.694748 -0.186157 -0.694745 0.508591 -0.508592 -0.694744 0.508591 -0.50859 -0.694746 0.186156 -0.694748 -0.694746 0.186156 -0.694747 -0.694747 -0.186156 -0.694747 -0.694747 -0.186157 -0.694747 -0.694746 -0.508589 -0.508591 -0.694746 -0.508592 -0.508591 -0.694744 -0.694748 -0.186157 -0.694745 -0.694748 -0.186157 -0.694745 -0.694748 0.186157 -0.694745 -0.694747 0.186157 -0.694746 -0.508591 0.508589 -0.694746 -0.508591 0.50859 -0.694746 -0.186156 0.694748 -0.694746 -0.186156 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186157 0.694747 -0.694746 0.508591 0.50859 -0.694746 0.508591 0.508589 -0.694746 0.694747 0.186157 -0.694746 0.694746 0.186157 -0.694746 0.694747 -0.186157 -0.694747 0.694747 -0.186158 -0.694746 0.508591 -0.508592 -0.694744 0.508591 -0.50859 -0.694746 0.186156 -0.694748 -0.694746 0.186156 -0.694747 -0.694747 -0.186156 -0.694747 -0.694747 -0.186157 -0.694747 -0.694746 -0.508589 -0.508591 -0.694746 -0.508592 -0.508591 -0.694744 -0.694748 -0.186157 -0.694745 -0.694746 -0.186158 -0.694746 -0.694747 0.186157 -0.694747 -0.694747 0.186158 -0.694746 -0.508591 0.508589 -0.694746 -0.508591 0.50859 -0.694746 -0.186156 0.694747 -0.694746 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186157 0.694747 -0.694746 0.508589 0.508589 -0.694748 0.508591 0.508589 -0.694746 0.694748 0.186156 -0.694746 0.694747 0.186156 -0.694747 0.694747 -0.186156 -0.694747 0.694748 -0.186157 -0.694745 0.50859 -0.508593 -0.694744 0.50859 -0.508588 -0.694748 0.186156 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 -0.186156 -0.694747 -0.694747 -0.186157 -0.694747 -0.694746 -0.508588 -0.508591 -0.694746 -0.508591 -0.508591 -0.694744 -0.694748 -0.186156 -0.694745 -0.694747 -0.186157 -0.694747 -0.694747 0.186156 -0.694747 -0.694747 0.186157 -0.694746 -0.50859 0.50859 -0.694746 -0.50859 0.50859 -0.694746 -0.186157 0.694747 -0.694746 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186156 0.694747 -0.694747 -1 0 0 -1 0 0 0 1 0 0 1 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965925 0.258821 0 0.965925 0.258821 0 0.965925 -0.258821 0 0.965925 -0.258821 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965925 0.258821 0 0.965925 0.258821 0 0.965925 -0.258821 0 0.965925 -0.258821 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965928 0.258813 0 0.965928 0.258813 0 0.965928 -0.258813 0 0.965928 -0.258813 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965928 0.258813 0 0.965928 0.258813 0 0.965928 -0.258813 0 0.965928 -0.258813 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965925 0.258821 0 0.965925 0.258821 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258816 -0.965927 0 0.258816 -0.965927 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258816 0.965927 0 0.258816 0.965927 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965925 0.258821 0 0.965925 0.258821 0 0.965925 -0.258821 0 0.965925 -0.258821 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965928 0.258813 0 0.965928 0.258813 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258816 -0.965927 0 0.258816 -0.965927 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258816 0.965927 0 0.258816 0.965927 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965928 0.258813 0 0.965928 0.258813 0 0.965928 -0.258813 0 0.965928 -0.258813 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258816 0.965927 0 -0.258816 0.965927 0 0.707108 -0.707105 0 0.707108 -0.707105 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.707105 0.707108 0 -0.707105 0.707108 0 0.707108 0.707105 0 0.707108 0.707105 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555571 0.831469 0 0.555571 0.831469 0 -0.195088 0.980786 0 -0.195088 0.980786 0 -0.555571 0.831469 0 -0.555571 0.831469 0 -0.555571 -0.831469 0 -0.555571 -0.831469 0 -0.195088 -0.980786 0 -0.195088 -0.980786 0 0.555571 -0.831469 0 0.555571 -0.831469 0 0.195088 -0.980786 0 0.195088 -0.980786 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 -0.831472 -0.555568 0 -0.831472 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.83147 0.555569 0 0.83147 0.555569 0 0.980787 0.195084 0 0.980787 0.195084 0 0.195093 -0.980785 0 0.195093 -0.980785 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980786 -0.195084 0 0.980786 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.83147 0.555569 0 0.83147 0.555569 0 0.980787 0.195084 0 0.980787 0.195084 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 -0.965926 0.25882 0 -0.9789 0.194726 0.0619398 -0.792481 0.608103 -0.046741 -0.83147 0.555569 0 -0.608765 0.793351 0 -0.555296 0.831064 -0.0312894 -0.258536 0.964871 0.0467318 -0.195093 0.980785 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980786 0.195084 0 0.980786 0.195084 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 -0.965926 0.25882 0 -0.9789 0.194727 0.0619389 -0.792481 0.608103 -0.0467429 -0.831472 0.555567 0 -0.608765 0.793351 0 -0.555296 0.831064 -0.0312894 -0.258536 0.964871 0.0467318 -0.195093 0.980785 0 -0.980783 -0.1951 0 -0.980783 -0.1951 0 -0.83147 -0.555569 0 -0.83147 -0.555569 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 -0.965926 0.25882 0 -0.9789 0.194727 0.0619389 -0.792481 0.608103 -0.0467429 -0.831472 0.555567 0 -0.608765 0.793351 0 -0.555296 0.831064 -0.0312894 -0.258536 0.964871 0.0467318 -0.195093 0.980785 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980786 0.195084 0 0.980786 0.195084 0 0.195093 -0.980785 0 0.195093 -0.980785 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980786 -0.195084 0 0.980786 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.980783 -0.1951 0 -0.980783 -0.1951 0 -0.83147 -0.555569 0 -0.83147 -0.555569 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.980783 -0.1951 0 -0.980783 -0.1951 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -0.965926 0.25882 0 -0.9789 0.194726 0.0619393 -0.792482 0.608102 -0.0467415 -0.831472 0.555567 0 -0.608763 0.793352 0 -0.555295 0.831065 -0.031289 -0.258536 0.964871 0.0467318 -0.195093 0.980785 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.980783 0.195101 0 -0.980783 0.195101 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195091 0.980785 0 -0.195091 0.980785 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -0.965926 0.25882 0 -0.9789 0.194726 0.0619396 -0.792482 0.608102 -0.046741 -0.831471 0.555568 0 -0.608764 0.793352 0 -0.555296 0.831064 -0.031289 -0.258535 0.964871 0.0467324 -0.195091 0.980785 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -0.965926 0.25882 0 -0.9789 0.194726 0.0619395 -0.792483 0.608101 -0.0467408 -0.831472 0.555567 0 -0.608763 0.793352 0 -0.555295 0.831064 -0.0312886 -0.258535 0.964871 0.0467328 -0.195091 0.980785 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.980783 -0.1951 0 -0.980783 -0.1951 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555567 -0.831472 0 -0.555567 -0.831472 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -0.965926 0.25882 0 -0.9789 0.194726 0.0619398 -0.792482 0.608102 -0.0467405 -0.831471 0.555568 0 -0.608765 0.793351 0 -0.555296 0.831064 -0.0312894 -0.258535 0.964871 0.0467322 -0.195091 0.980785 0 -0.980783 -0.195101 0 -0.964871 -0.258537 -0.0467268 -0.896885 -0.442264 0 -0.793349 -0.608767 0 -0.70573 -0.705733 -0.0623459 -0.608763 -0.793352 0 -0.442283 -0.896876 0 -0.258536 -0.964871 -0.0467333 -0.195091 -0.980785 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -0.965926 0.25882 0 -0.9789 0.194726 0.0619396 -0.792483 0.6081 -0.0467401 -0.831472 0.555567 0 -0.608765 0.793351 0 -0.555296 0.831064 -0.0312894 -0.258533 0.964871 0.0467326 -0.195089 0.980786 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.980783 0.1951 0 -0.980783 0.1951 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195089 0.980786 0 -0.195089 0.980786 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.195089 -0.980786 0 0.195089 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980787 -0.195084 0 0.980787 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.980783 0.1951 0 -0.980783 0.1951 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195089 0.980786 0 -0.195089 0.980786 0 -0.980783 0.1951 0 -0.964871 0.258537 -0.0467273 -0.896884 0.442267 0 -0.79335 0.608766 0 -0.705729 0.705733 -0.062347 -0.195089 0.980786 0 -0.258536 0.96487 -0.0467348 -0.442288 0.896873 0 -0.608761 0.793354 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.195089 -0.980786 0 0.195089 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980787 -0.195084 0 0.980787 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.195089 -0.980786 0 0.195089 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980787 -0.195084 0 0.980787 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 -0.980783 0.1951 0 -0.964871 0.258537 -0.0467273 -0.896884 0.442267 0 -0.79335 0.608766 0 -0.705729 0.705733 -0.062347 -0.195089 0.980786 0 -0.258536 0.96487 -0.0467348 -0.442288 0.896873 0 -0.608761 0.793354 0 -0.980783 0.1951 0 -0.980783 0.1951 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195089 0.980786 0 -0.195089 0.980786 0 0.195089 -0.980786 0 0.195089 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980787 -0.195084 0 0.980787 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258816 0.965927 0 0.258816 0.965927 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258816 0.965927 0 0.258816 0.965927 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831463 0.55558 0 0.831463 0.55558 0 0.980787 0.195084 0 0.980787 0.195084 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555575 0.831466 0 0.555575 0.831466 0 0.831463 0.55558 0 0.831463 0.55558 0 0.980787 0.195084 0 0.980787 0.195084 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831463 0.55558 0 0.831463 0.55558 0 0.980787 0.195084 0 0.980787 0.195084 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831463 0.55558 0 0.831463 0.55558 0 0.980787 0.195084 0 0.980787 0.195084 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831463 0.55558 0 0.831463 0.55558 0 0.980787 0.195084 0 0.980787 0.195084 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831464 0.555579 0 0.831464 0.555579 0 0.980787 0.195084 0 0.980787 0.195084 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831464 0.555579 0 0.831464 0.555579 0 0.980787 0.195084 0 0.980787 0.195084 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.201912 0.979404 0 0.201912 0.979404 -2.38512e-07 0.201912 0.979404 0 0.201912 0.979404 0 -1 0 0 -1 0 0 -0.97414 0.225945 0 -0.97414 0.225945 0 -0.775212 0.631701 0 -0.775212 0.631701 0 -0.417985 0.908454 0 -0.417985 0.908454 0 -0.201912 0.979404 0 -0.201912 0.979404 0 -0.201912 0.979404 0 -0.201912 0.979404 6.36032e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.201912 -0.979404 0 0.201912 -0.979404 0 0.201912 -0.979404 0 0.201912 -0.979404 2.38512e-07 -0.201912 -0.979404 0 -0.201912 -0.979404 1.11306e-06 -0.201912 -0.979404 0 -0.201912 -0.979404 0 -0.417986 -0.908454 0 -0.417986 -0.908454 0 -0.775212 -0.631701 0 -0.775212 -0.631701 0 -0.97414 -0.225945 0 -0.97414 -0.225945 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0.97414 0.225946 0 0.97414 0.225946 0 0.775214 0.631699 0 0.775214 0.631699 0 0.417983 0.908455 0 0.417983 0.908455 0 0.41798 0.908456 0 0.41798 0.908456 0 0.775212 0.631701 0 0.775212 0.631701 0 0.97414 0.225945 0 0.97414 0.225945 0 1 0 0 1 0 0 -0.417984 0.908455 0 -0.417984 0.908455 0 -0.775214 0.631699 0 -0.775214 0.631699 0 -0.974139 0.225948 0 -0.974139 0.225948 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0.97414 -0.225945 0 0.97414 -0.225945 0 0.775212 -0.631701 0 0.775212 -0.631701 0 0.417982 -0.908455 0 0.417982 -0.908455 0 0.417983 -0.908455 0 0.417983 -0.908455 0 0.775214 -0.631699 0 0.775214 -0.631699 0 0.97414 -0.225946 0 0.97414 -0.225946 0 -0.974139 -0.225948 0 -0.974139 -0.225948 0 -0.775214 -0.631699 0 -0.775214 -0.631699 0 -0.417984 -0.908455 0 -0.417984 -0.908455 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.258821 0.965925 0 0.258821 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965924 0.258825 0 0.965924 0.258825 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707105 0.707109 0 0.707105 0.707109 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707104 -0.707109 0 0.707104 -0.707109 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258821 0.965925 0 0.258821 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965924 0.258825 0 0.965924 0.258825 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707104 0.707109 0 0.707104 0.707109 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965927 0.258813 0 0.965927 0.258813 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707108 0.707106 0 0.707108 0.707106 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965927 0.258813 0 0.965927 0.258813 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707108 0.707106 0 0.707108 0.707106 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258821 0.965925 0 0.258821 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965924 0.258825 0 0.965924 0.258825 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258821 0.965925 0 0.258821 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965924 0.258825 0 0.965924 0.258825 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258821 0.965925 0 0.258821 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965924 0.258825 0 0.965924 0.258825 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707108 0.707105 0 0.707108 0.707105 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258821 0.965925 0 0.258821 0.965925 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965924 0.258825 0 0.965924 0.258825 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965927 -0.258813 0 -0.965927 -0.258813 0 -0.965927 0.258813 0 -0.965927 0.258813 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707108 0.707105 0 0.707108 0.707105 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965927 0.258813 0 0.965927 0.258813 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965924 -0.258825 0 -0.965924 -0.258825 0 -0.965924 0.258825 0 -0.965924 0.258825 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707104 -0.70711 0 -0.707104 -0.70711 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707104 0.70711 0 -0.707104 0.70711 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965924 -0.258825 0 -0.965924 -0.258825 0 -0.965924 0.258825 0 -0.965924 0.258825 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707108 0.707106 0 0.707108 0.707106 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707108 0.707106 0 0.707108 0.707106 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965925 -0.258821 0 0.965925 -0.258821 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965927 0.258813 0 0.965927 0.258813 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707108 0.707105 0 0.707108 0.707105 0 0.965926 0.258819 0 0.965926 0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.258818 -0.965926 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965925 0.258822 0 0.965925 0.258822 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.258818 -0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.186156 -0.694745 0.694748 -0.508586 -0.508586 0.694752 -0.508591 -0.508588 0.694747 -0.694747 -0.186157 0.694746 -0.694741 -0.186158 0.694752 -0.694742 0.186156 0.694752 -0.694746 0.186159 0.694746 -0.50859 0.50859 0.694746 -0.508588 0.508585 0.694752 -0.186156 0.694745 0.694748 -0.186156 0.694747 0.694747 0.186157 0.694747 0.694747 0.186158 0.694748 0.694745 0.508594 0.508589 0.694744 0.508591 0.508588 0.694747 0.694747 0.186157 0.694746 0.694741 0.186158 0.694752 0.694742 -0.186156 0.694752 0.694746 -0.186159 0.694746 0.508592 -0.508588 0.694747 0.508593 -0.50859 0.694744 0.186157 -0.694748 0.694745 0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 0.258817 0.965926 0 0.258817 0.965926 0 0.707111 0.707102 0 0.707111 0.707102 0 0.965923 0.258828 0 0.965923 0.258828 0 0.965924 -0.258827 0 0.965924 -0.258827 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965927 -0.258816 0 -0.965927 -0.258816 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.50859 0.50859 -0.694747 0.50859 0.50859 -0.694747 0.694746 0.186158 -0.694747 0.694751 0.186156 -0.694742 0.694751 -0.18616 -0.694742 0.694747 -0.186155 -0.694747 0.50859 -0.50859 -0.694747 0.50859 -0.50859 -0.694747 0.186157 -0.694748 -0.694745 0.186156 -0.694749 -0.694744 -0.186159 -0.694749 -0.694744 -0.186158 -0.694748 -0.694746 -0.50859 -0.50859 -0.694747 -0.50859 -0.50859 -0.694747 -0.694746 -0.186158 -0.694747 -0.694751 -0.186156 -0.694742 -0.694751 0.18616 -0.694742 -0.694747 0.186155 -0.694747 -0.50859 0.50859 -0.694747 -0.50859 0.50859 -0.694747 -0.186158 0.694747 -0.694746 -0.186158 0.694749 -0.694744 0.186157 0.694749 -0.694744 0.186156 0.694748 -0.694745 0.50859 0.50859 -0.694747 0.50859 0.50859 -0.694747 0.694746 0.186158 -0.694747 0.694751 0.186156 -0.694742 0.694751 -0.18616 -0.694742 0.694747 -0.186155 -0.694747 0.50859 -0.50859 -0.694747 0.50859 -0.50859 -0.694747 0.186157 -0.694748 -0.694745 0.186156 -0.694749 -0.694744 -0.186159 -0.694749 -0.694744 -0.186158 -0.694748 -0.694746 -0.50859 -0.50859 -0.694747 -0.50859 -0.50859 -0.694747 -0.694746 -0.186158 -0.694747 -0.694751 -0.186156 -0.694742 -0.694751 0.18616 -0.694742 -0.694747 0.186155 -0.694747 -0.50859 0.50859 -0.694747 -0.50859 0.50859 -0.694747 -0.186158 0.694747 -0.694746 -0.186159 0.694746 -0.694746 0.186156 0.694747 -0.694747 0.186157 0.694748 -0.694745 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.25882 -0.965926 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707106 0.707107 0 0.707106 0.707107 0 0.965926 0.258817 0 0.965926 0.258817 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.186158 -0.694748 0.694745 -0.508591 -0.508591 0.694744 -0.50859 -0.508591 0.694746 -0.694747 -0.186157 0.694746 -0.694752 -0.186157 0.694741 -0.694752 0.186158 0.694741 -0.694748 0.186155 0.694746 -0.50859 0.50859 0.694746 -0.508591 0.508592 0.694744 -0.186157 0.694748 0.694745 -0.186157 0.694747 0.694747 0.186157 0.694747 0.694747 0.186158 0.694748 0.694745 0.508591 0.508591 0.694744 0.50859 0.508591 0.694746 0.694747 0.186157 0.694746 0.694752 0.186156 0.694741 0.694752 -0.186158 0.694741 0.694748 -0.186156 0.694746 0.50859 -0.50859 0.694746 0.508591 -0.508592 0.694744 0.186157 -0.694748 0.694745 0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 -0.965926 0.258817 0 -0.796366 0.604815 0 -0.707086 0.707089 -0.00739691 -0.612682 0.790329 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.258817 0 0.965926 0.258817 0 0.965927 -0.258816 0 0.965927 -0.258816 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.965927 -0.258816 0 -0.965927 -0.258816 0 -0.965926 0.258817 0 -0.694751 -0.186156 -0.694742 -0.706315 0.047452 -0.706306 -0.641455 0.171879 -0.747659 -0.675566 0.230541 -0.700329 -0.50859 0.50859 -0.694747 -0.508591 0.508596 -0.694741 -0.186157 0.69475 -0.694743 -0.186158 0.694749 -0.694744 0.186157 0.694749 -0.694744 0.186158 0.69475 -0.694743 0.508594 0.508594 -0.69474 0.508594 0.508594 -0.69474 0.694756 0.186154 -0.694738 0.694742 0.186159 -0.694751 0.694743 -0.186151 -0.694752 0.694753 -0.186162 -0.694739 0.508594 -0.508594 -0.69474 0.508594 -0.508594 -0.69474 0.186157 -0.69475 -0.694743 0.186158 -0.694749 -0.694744 -0.186157 -0.694749 -0.694744 -0.186158 -0.69475 -0.694743 -0.508594 -0.508594 -0.69474 -0.508587 -0.508593 -0.694746 -0.694746 -0.186158 -0.694747 -0.186158 -0.69475 -0.694743 -0.412668 -0.57629 -0.705405 -0.461112 -0.461112 -0.758123 -0.550126 -0.451788 -0.702317 -0.694746 -0.186158 -0.694747 -0.694751 -0.186156 -0.694742 -0.694751 0.18616 -0.694742 -0.694747 0.186155 -0.694747 -0.50859 0.50859 -0.694747 -0.508591 0.508596 -0.694741 -0.186157 0.69475 -0.694743 -0.186159 0.694746 -0.694746 0.186156 0.694747 -0.694747 0.186159 0.694749 -0.694743 0.508594 0.508594 -0.69474 0.508594 0.508594 -0.69474 0.694756 0.186154 -0.694738 0.694742 0.186159 -0.694751 0.694743 -0.186151 -0.694752 0.694753 -0.186162 -0.694739 0.508594 -0.508594 -0.69474 0.508594 -0.508594 -0.69474 0.186157 -0.69475 -0.694743 0.186158 -0.694749 -0.694744 -0.186157 -0.694749 -0.694744 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.258817 -0.965926 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965925 0.258822 0 0.965925 0.258822 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258817 -0.965926 0 -0.186155 -0.694746 0.694748 -0.508586 -0.508586 0.694752 -0.508591 -0.508588 0.694747 -0.694747 -0.186157 0.694746 -0.694741 -0.186158 0.694752 -0.694742 0.186156 0.694752 -0.694746 0.186159 0.694746 -0.50859 0.50859 0.694746 -0.508588 0.508585 0.694752 -0.186156 0.694745 0.694748 -0.186156 0.694749 0.694744 0.186158 0.694749 0.694744 0.186157 0.694748 0.694745 0.508594 0.508589 0.694744 0.508591 0.508588 0.694747 0.694747 0.186157 0.694746 0.694741 0.186158 0.694752 0.694742 -0.186156 0.694752 0.694746 -0.186159 0.694746 0.508592 -0.508588 0.694747 0.508593 -0.50859 0.694744 0.186157 -0.694748 0.694745 0.186157 -0.694749 0.694744 -0.186158 -0.694749 0.694744 0.258817 0.965926 0 0.258817 0.965926 0 0.707113 0.707101 0 0.707113 0.707101 0 0.965923 0.258828 0 0.965923 0.258828 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.50859 0.50859 -0.694747 0.508591 0.50859 -0.694745 0.694746 0.186158 -0.694747 0.694751 0.186157 -0.694742 0.694751 -0.18616 -0.694742 0.694747 -0.186155 -0.694747 0.50859 -0.50859 -0.694747 0.508589 -0.508588 -0.694748 0.186156 -0.694746 -0.694748 0.186156 -0.694747 -0.694747 -0.186158 -0.694746 -0.694746 -0.186157 -0.694745 -0.694748 -0.508588 -0.508588 -0.694749 -0.50859 -0.508589 -0.694747 -0.694746 -0.186158 -0.694747 -0.694751 -0.186156 -0.694742 -0.694751 0.18616 -0.694742 -0.694747 0.186156 -0.694746 -0.508591 0.508591 -0.694745 -0.50859 0.508589 -0.694747 -0.186157 0.694748 -0.694745 -0.186157 0.694747 -0.694747 0.186155 0.694747 -0.694747 0.186156 0.694748 -0.694745 0.508588 0.508588 -0.694749 0.50859 0.508589 -0.694747 0.694746 0.186158 -0.694747 0.694751 0.186156 -0.694742 0.69475 -0.18616 -0.694742 0.694747 -0.186156 -0.694747 0.50859 -0.508589 -0.694747 0.50859 -0.508589 -0.694747 0.186155 -0.694748 -0.694745 0.186156 -0.694747 -0.694747 -0.186157 -0.694747 -0.694747 -0.186158 -0.694748 -0.694746 -0.508591 -0.508589 -0.694747 -0.50859 -0.508589 -0.694747 -0.694745 -0.186159 -0.694747 -0.694751 -0.186157 -0.694742 -0.694751 0.18616 -0.694742 -0.694747 0.186155 -0.694747 -0.50859 0.50859 -0.694747 -0.508589 0.508588 -0.694748 -0.186158 0.694745 -0.694748 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186156 0.694746 -0.694748 -0.258818 -0.965926 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707106 0.707107 0 0.707106 0.707107 0 0.965926 0.258817 0 0.965926 0.258817 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258818 -0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.186157 -0.694748 0.694745 -0.508591 -0.508591 0.694744 -0.50859 -0.508591 0.694746 -0.694747 -0.186157 0.694746 -0.694752 -0.186156 0.694741 -0.694752 0.186158 0.694741 -0.694748 0.186155 0.694746 -0.50859 0.50859 0.694746 -0.508591 0.508592 0.694744 -0.186157 0.694748 0.694745 -0.186157 0.694749 0.694744 0.186158 0.694749 0.694744 0.186157 0.694748 0.694745 0.508591 0.508591 0.694744 0.50859 0.508591 0.694746 0.694747 0.186157 0.694746 0.694752 0.186156 0.694741 0.694752 -0.186158 0.694741 0.694748 -0.186155 0.694746 0.50859 -0.50859 0.694746 0.508591 -0.508592 0.694744 0.186157 -0.694748 0.694745 0.186157 -0.694749 0.694744 -0.186158 -0.694749 0.694744 -0.25882 -0.965926 0 -0.612682 -0.790329 0 -0.707087 -0.707087 -0.00739703 -0.796368 -0.604812 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258817 0 0.965926 0.258817 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.508588 -0.508592 -0.694747 -0.675566 -0.230542 -0.700329 -0.641454 -0.171879 -0.747659 -0.706315 -0.0474517 -0.706306 -0.694751 0.18616 -0.694742 -0.694747 0.186156 -0.694746 -0.508591 0.508591 -0.694745 -0.508592 0.508596 -0.694741 -0.186156 0.694751 -0.694743 -0.186157 0.694747 -0.694747 0.186155 0.694747 -0.694747 0.186158 0.69475 -0.694743 0.508594 0.508594 -0.69474 0.508596 0.508594 -0.694739 0.694757 0.186155 -0.694737 0.694742 0.18616 -0.69475 0.694743 -0.186151 -0.694752 0.694753 -0.186162 -0.694739 0.508594 -0.508594 -0.69474 0.508594 -0.508592 -0.694742 0.186157 -0.694748 -0.694745 0.186157 -0.694747 -0.694747 -0.186156 -0.694747 -0.694747 -0.186158 -0.694748 -0.694745 -0.508593 -0.508593 -0.694742 -0.694747 0.186155 -0.694747 -0.550126 0.451788 -0.702317 -0.461112 0.461112 -0.758123 -0.412669 0.576286 -0.705406 -0.186157 0.694748 -0.694745 -0.186157 0.694747 -0.694747 0.186156 0.694747 -0.694747 0.186158 0.694748 -0.694745 0.508593 0.508593 -0.694742 0.508595 0.508593 -0.694741 0.694756 0.186154 -0.694738 0.694742 0.186159 -0.694751 0.694743 -0.186151 -0.694752 0.694753 -0.186163 -0.694739 0.508595 -0.508593 -0.694741 0.508595 -0.508593 -0.69474 0.186156 -0.694751 -0.694743 0.186157 -0.694747 -0.694747 -0.186155 -0.694747 -0.694747 -0.186158 -0.69475 -0.694743 -0.508595 -0.508593 -0.69474 -0.508588 -0.508592 -0.694747 -0.694745 -0.186159 -0.694747 -0.694751 -0.186157 -0.694742 -0.694751 0.18616 -0.694742 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.707114 -0.7071 0 -0.707114 -0.7071 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707114 0.7071 0 -0.707114 0.7071 0 -0.965925 0.258822 0 -0.965925 0.258822 0 0.258825 0.965924 0 0.258825 0.965924 0 0.7071 0.707114 0 0.7071 0.707114 0 0.965925 0.258822 0 0.965925 0.258822 0 0.980781 -0.195114 0 0.965838 -0.258798 -0.0134257 0.896897 -0.44224 0 0.793355 -0.608759 0 0.706986 -0.707 -0.0179331 0.195099 -0.980784 0 0.258802 -0.965837 -0.0134292 0.442286 -0.896874 0 0.608741 -0.793369 0 0.965925 0.258822 0 0.130537 0.991443 0 0.258801 0.965862 0.0114874 0.382681 0.923881 0 0.612725 0.790296 0 0.796132 0.604566 0.0259675 0.707114 0.7071 0 0.965925 0.258822 0 0.965925 -0.258822 0 0.980711 -0.195061 0.0125412 0.793348 -0.608696 -0.00944676 0.834243 -0.551396 0.000721589 0.608741 -0.793369 -0.000502841 0.562579 -0.82672 -0.00621475 0.288237 -0.957531 0.00738117 0.258803 -0.965871 0.0107131 0.0980135 -0.995185 0 -0.098021 -0.995184 0 -0.25881 -0.965869 0.0107123 -0.288237 -0.957531 0.00738118 -0.608718 -0.793339 -0.00872649 -0.560046 -0.828462 -0.000722074 -0.793355 -0.608759 0.000464067 -0.834228 -0.551386 -0.00608513 -0.965882 -0.25881 0.00944814 -0.980781 -0.195114 0 -0.965925 0.258822 0 -0.965925 0.258822 0 -0.796372 0.604807 0 -0.707043 0.707058 0.0125991 -0.612725 0.790296 0 -0.382681 0.923881 0 -0.258808 0.96586 0.0114868 -0.130545 0.991442 0 0.555568 -0.831471 0 0.620208 -0.782673 -0.052582 0.0980209 -0.995184 0 0.195082 -0.980747 -0.00880998 0.290279 -0.956942 0 0.456227 -0.889863 0 0.456227 -0.889863 0 -0.621083 -0.783745 0 -0.555309 -0.831065 -0.0310366 -0.458325 -0.888785 0 -0.456808 -0.889565 -0.000176263 -0.292615 -0.95623 0.00021948 -0.195078 -0.980748 -0.00881031 -0.0980172 -0.995185 0 -0.55557 0.83147 0 -0.620214 0.782669 -0.0525839 -0.0980172 0.995185 0 -0.195088 0.980746 -0.00881115 -0.290296 0.956937 0 -0.456227 0.889863 0 -0.456227 0.889863 0 0.621057 0.783765 0 0.555294 0.831075 -0.0310317 0.458344 0.888775 0 0.456813 0.889563 -0.000177838 0.292614 0.956231 0.000217802 0.195091 0.980746 -0.00881082 0.0980209 0.995184 0 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.707113 -0.707101 -0.694763 0.186162 -0.694729 -0.694759 0.186159 -0.694733 -0.508597 0.508599 -0.694735 -0.508596 0.508597 -0.694736 -0.186158 0.694754 -0.694739 -0.186158 0.694752 -0.69474 0.139281 0.700221 -0.700209 0.139282 0.700222 -0.700207 0.39665 0.593619 -0.700204 0.396644 0.593617 -0.700209 0.593612 0.396649 -0.70021 0.593617 0.396649 -0.700206 0.700224 0.139278 -0.700205 0.700214 0.139282 -0.700214 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.139283 -0.70022 -0.700208 -0.139281 -0.700219 -0.700211 -0.396638 -0.593614 -0.700214 -0.396643 -0.593617 -0.70021 -0.593619 -0.396641 -0.700209 -0.593605 -0.396641 -0.700221 -0.700204 -0.139287 -0.700224 -0.700233 -0.139275 -0.700198 0.694747 -0.186157 -0.694747 0.694757 -0.186166 -0.694734 0.508597 -0.508599 -0.694735 0.508592 -0.508585 -0.694748 0.186157 -0.69475 -0.694743 0.186156 -0.694753 -0.694741 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.707113 -0.707101 -0.694763 0.186162 -0.694729 -0.694759 0.186158 -0.694733 -0.508597 0.508598 -0.694735 -0.508596 0.508597 -0.694736 -0.186158 0.694754 -0.694739 -0.186158 0.694752 -0.69474 0.13928 0.700221 -0.700209 0.139282 0.700222 -0.700207 0.39665 0.593619 -0.700204 0.396644 0.593617 -0.700209 0.593612 0.396649 -0.70021 0.593617 0.396649 -0.700206 0.700224 0.139278 -0.700205 0.700214 0.139282 -0.700214 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186158 -0.694752 -0.694741 -0.186159 -0.694754 -0.694739 -0.508596 -0.508598 -0.694736 -0.508597 -0.508598 -0.694735 -0.694759 -0.186161 -0.694734 -0.694764 -0.18616 -0.694729 0.694747 -0.186157 -0.694747 0.694756 -0.186166 -0.694734 0.508597 -0.508599 -0.694735 0.508592 -0.508585 -0.694749 0.186157 -0.69475 -0.694744 0.186156 -0.694753 -0.694741 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 -0.186158 0.694751 -0.694742 -0.694763 0.186162 -0.694729 -0.69476 0.186159 -0.694733 -0.563397 0.432317 -0.70405 -0.57492 0.57492 -0.58218 -0.432312 0.563395 -0.704054 -0.186158 0.694752 -0.694741 0.139284 0.700219 -0.70021 0.139285 0.700219 -0.700209 0.396643 0.593621 -0.700206 0.396649 0.593624 -0.7002 0.59363 0.39665 -0.700195 0.593619 0.39665 -0.700204 0.700225 0.139278 -0.700205 0.700214 0.139283 -0.700214 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.139285 -0.700223 -0.700205 -0.139279 -0.700217 -0.700212 -0.396637 -0.593613 -0.700216 -0.396644 -0.593616 -0.70021 -0.593619 -0.39664 -0.70021 -0.593605 -0.39664 -0.700221 -0.700203 -0.139287 -0.700225 -0.700233 -0.139275 -0.700198 0.694747 -0.186157 -0.694747 0.694743 -0.186154 -0.694751 0.508588 -0.508591 -0.694747 0.508587 -0.508587 -0.694751 0.186159 -0.694747 -0.694746 0.186158 -0.694755 -0.694738 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 -0.694763 0.186162 -0.694729 -0.69476 0.186159 -0.694733 -0.508597 0.5086 -0.694734 -0.508596 0.508596 -0.694738 -0.186158 0.694752 -0.694741 -0.186158 0.694755 -0.694738 0.139285 0.700223 -0.700205 0.139282 0.70022 -0.700209 0.396643 0.593621 -0.700206 0.396649 0.593624 -0.7002 0.59363 0.39665 -0.700195 0.593619 0.39665 -0.700204 0.700225 0.139278 -0.700205 0.700214 0.139283 -0.700214 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186159 -0.694755 -0.694738 -0.18616 -0.694756 -0.694736 -0.508597 -0.508599 -0.694735 -0.508597 -0.508599 -0.694734 -0.694759 -0.186161 -0.694733 -0.694763 -0.18616 -0.694729 0.700215 -0.139277 -0.700215 0.700222 -0.139284 -0.700206 0.593621 -0.396642 -0.700207 0.593626 -0.396654 -0.700195 0.396646 -0.593626 -0.7002 0.396646 -0.59362 -0.700205 0.139284 -0.70022 -0.700209 0.139283 -0.700223 -0.700206 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 -0.186158 0.694755 -0.694738 -0.186158 0.694752 -0.694741 -0.508596 0.508596 -0.694738 -0.694763 0.186162 -0.694729 -0.69476 0.186159 -0.694733 -0.563397 0.432317 -0.70405 -0.559577 0.729249 -0.393788 0.139285 0.700223 -0.700205 0.139282 0.70022 -0.700209 0.396643 0.593621 -0.700206 0.396649 0.593624 -0.7002 0.593631 0.396648 -0.700195 0.593617 0.396648 -0.700206 0.700224 0.139279 -0.700206 0.700214 0.139283 -0.700214 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.139285 -0.700223 -0.700205 -0.139279 -0.700217 -0.700212 -0.396637 -0.593613 -0.700216 -0.396644 -0.593616 -0.70021 -0.593619 -0.39664 -0.70021 -0.593605 -0.39664 -0.700221 -0.700203 -0.139287 -0.700225 -0.700233 -0.139275 -0.700198 0.694747 -0.186157 -0.694747 0.694743 -0.186154 -0.694751 0.508588 -0.508591 -0.694747 0.508588 -0.50859 -0.694748 0.18616 -0.694751 -0.694741 0.18616 -0.694755 -0.694738 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 -0.694763 0.186162 -0.694729 -0.69476 0.186159 -0.694733 -0.508597 0.5086 -0.694734 -0.508597 0.508599 -0.694735 -0.186159 0.694756 -0.694736 -0.18616 0.694755 -0.694738 0.139285 0.700223 -0.700205 0.139282 0.70022 -0.700209 0.396643 0.593621 -0.700206 0.396649 0.593624 -0.7002 0.593631 0.396648 -0.700195 0.593617 0.396648 -0.700206 0.700224 0.139279 -0.700206 0.700214 0.139283 -0.700214 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186159 -0.694755 -0.694738 -0.186157 -0.694753 -0.694741 -0.508595 -0.508597 -0.694738 -0.508598 -0.508598 -0.694734 -0.694759 -0.186161 -0.694733 -0.694763 -0.18616 -0.694729 0.700215 -0.139277 -0.700215 0.700222 -0.139284 -0.700206 0.593621 -0.396642 -0.700207 0.593626 -0.396654 -0.700195 0.396646 -0.593626 -0.7002 0.396646 -0.59362 -0.700205 0.139284 -0.70022 -0.700209 0.139283 -0.700223 -0.700206 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 -0.18616 0.694755 -0.694738 -0.186159 0.694756 -0.694736 -0.508597 0.508599 -0.694735 -0.694763 0.186162 -0.694729 -0.69476 0.186159 -0.694733 -0.563397 0.432317 -0.70405 -0.559577 0.729249 -0.393788 0.186159 0.694755 -0.694738 0.186157 0.694752 -0.694741 0.508588 0.50859 -0.694748 0.508601 0.508595 -0.694735 0.694759 0.186161 -0.694733 0.694746 0.186163 -0.694746 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.139285 -0.700223 -0.700205 -0.139279 -0.700217 -0.700212 -0.396637 -0.593613 -0.700216 -0.396644 -0.593616 -0.70021 -0.593617 -0.396641 -0.70021 -0.593607 -0.396641 -0.700219 -0.700204 -0.139287 -0.700224 -0.700233 -0.139275 -0.700198 0.694747 -0.186157 -0.694747 0.694757 -0.186166 -0.694734 0.508597 -0.5086 -0.694734 0.508592 -0.508583 -0.69475 0.186157 -0.694748 -0.694746 0.186155 -0.694755 -0.694738 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 -0.694763 0.186162 -0.694729 -0.694759 0.186158 -0.694733 -0.508596 0.508598 -0.694736 -0.508595 0.508596 -0.694738 -0.186158 0.694752 -0.694741 -0.186158 0.694753 -0.69474 0.13928 0.700221 -0.700208 0.139282 0.700223 -0.700206 0.39665 0.59362 -0.700203 0.396643 0.593616 -0.70021 0.593612 0.396648 -0.700211 0.593617 0.396648 -0.700206 0.700224 0.139279 -0.700206 0.700214 0.139282 -0.700214 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.139284 -0.700219 -0.70021 -0.139282 -0.700217 -0.700212 -0.396637 -0.593613 -0.700216 -0.396644 -0.593616 -0.70021 -0.593617 -0.396641 -0.70021 -0.593607 -0.396641 -0.700219 -0.700204 -0.139287 -0.700224 -0.700233 -0.139275 -0.700198 0.694747 -0.186157 -0.694747 0.694757 -0.186166 -0.694734 0.508597 -0.5086 -0.694734 0.508592 -0.508583 -0.69475 0.186157 -0.694748 -0.694746 0.186156 -0.694751 -0.694742 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 -0.694763 0.186162 -0.694729 -0.69476 0.186159 -0.694733 -0.508597 0.5086 -0.694734 -0.508596 0.508598 -0.694736 -0.186159 0.694754 -0.694739 -0.186159 0.694753 -0.69474 0.13928 0.700221 -0.700208 0.139282 0.700223 -0.700206 0.39665 0.59362 -0.700203 0.396645 0.593617 -0.700208 0.593613 0.396649 -0.700209 0.593617 0.396649 -0.700206 0.700224 0.139279 -0.700206 0.700214 0.139282 -0.700214 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186158 -0.694753 -0.69474 -0.186158 -0.694752 -0.694741 -0.508595 -0.508597 -0.694738 -0.508597 -0.508598 -0.694736 -0.694758 -0.186161 -0.694734 -0.694763 -0.186159 -0.694729 0.694747 -0.186157 -0.694747 0.694756 -0.186166 -0.694735 0.508596 -0.508598 -0.694736 0.508591 -0.508584 -0.69475 0.186157 -0.694748 -0.694746 0.186156 -0.694753 -0.69474 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 -0.186159 0.694753 -0.69474 -0.186159 0.694754 -0.694739 -0.508596 0.508598 -0.694736 -0.694763 0.186162 -0.694729 -0.69476 0.186159 -0.694733 -0.563397 0.432316 -0.70405 -0.559577 0.729253 -0.39378 0.186158 0.694753 -0.69474 0.186156 0.69475 -0.694743 0.508587 0.508589 -0.694749 0.508601 0.508594 -0.694735 0.694759 0.186161 -0.694733 0.694746 0.186163 -0.694746 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.139283 -0.700221 -0.700208 -0.139281 -0.700219 -0.70021 -0.396639 -0.593615 -0.700214 -0.396643 -0.593616 -0.70021 -0.593618 -0.396641 -0.70021 -0.593606 -0.396641 -0.70022 -0.700204 -0.139287 -0.700224 -0.700233 -0.139275 -0.700198 0.694747 -0.186157 -0.694747 0.694756 -0.186166 -0.694735 0.508597 -0.508598 -0.694736 0.508592 -0.508585 -0.694748 0.186156 -0.69475 -0.694743 0.186156 -0.694753 -0.69474 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 -0.700231 0.139292 -0.700196 -0.700209 0.13927 -0.700223 -0.593609 0.396634 -0.700221 -0.593614 0.396647 -0.70021 -0.396641 0.593619 -0.700209 -0.396641 0.593613 -0.700214 -0.139282 0.700219 -0.70021 -0.139282 0.700221 -0.700208 0.13928 0.700221 -0.700208 0.139282 0.700223 -0.700206 0.39665 0.59362 -0.700203 0.396644 0.593617 -0.700209 0.593612 0.396649 -0.70021 0.593617 0.396649 -0.700206 0.700224 0.139278 -0.700205 0.700214 0.139282 -0.700214 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186157 -0.694751 -0.694742 -0.186159 -0.694754 -0.694739 -0.508596 -0.508598 -0.694736 -0.508597 -0.508598 -0.694735 -0.694759 -0.186161 -0.694733 -0.694763 -0.18616 -0.694729 0.694747 -0.186157 -0.694747 0.694757 -0.186166 -0.694734 0.508597 -0.508599 -0.694735 0.508592 -0.508585 -0.694748 0.186156 -0.69475 -0.694743 0.186156 -0.694751 -0.694742 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.707113 -0.707101 -0.186159 0.694752 -0.69474 -0.186158 0.694754 -0.694739 -0.508596 0.508598 -0.694736 -0.694763 0.186162 -0.694729 -0.69476 0.186159 -0.694733 -0.563397 0.432316 -0.70405 -0.559577 0.729251 -0.393784 0.186158 0.694752 -0.694741 0.186156 0.69475 -0.694743 0.508587 0.508589 -0.694749 0.508601 0.508594 -0.694736 0.694759 0.186161 -0.694734 0.694746 0.186163 -0.694746 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.139283 -0.70022 -0.700209 -0.139282 -0.700219 -0.70021 -0.396639 -0.593615 -0.700214 -0.396644 -0.593617 -0.700209 -0.593619 -0.396641 -0.700209 -0.593605 -0.396641 -0.700221 -0.700204 -0.139287 -0.700224 -0.700233 -0.139275 -0.700198 0.694747 -0.186157 -0.694747 0.694757 -0.186166 -0.694734 0.508597 -0.508599 -0.694735 0.508592 -0.508585 -0.694748 0.186157 -0.69475 -0.694743 0.186157 -0.694752 -0.694741 0 -0.707112 -0.707101 0 -0.707112 -0.707101 0 -0.707112 -0.707101 0 -0.707112 -0.707101 0 0.707112 -0.707101 0 0.707112 -0.707101 0 0.707112 -0.707101 0 0.707112 -0.707101 -0.186159 0.694752 -0.694741 -0.694763 0.186162 -0.694729 -0.694759 0.186158 -0.694733 -0.563397 0.432315 -0.704051 -0.574921 0.574922 -0.582177 -0.432311 0.563397 -0.704053 -0.186158 0.694754 -0.694739 0.186158 0.694752 -0.694741 0.186156 0.69475 -0.694743 0.508587 0.508589 -0.694749 0.5086 0.508593 -0.694737 0.694758 0.186161 -0.694734 0.694746 0.186163 -0.694746 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.139283 -0.70022 -0.700208 -0.139281 -0.700219 -0.70021 -0.396638 -0.593614 -0.700214 -0.396644 -0.593617 -0.700209 -0.593619 -0.396641 -0.700209 -0.593605 -0.396641 -0.700221 -0.700204 -0.139287 -0.700224 -0.700233 -0.139275 -0.700198 0.694747 -0.186157 -0.694747 0.694756 -0.186166 -0.694734 0.508597 -0.508598 -0.694735 0.508592 -0.508585 -0.694749 0.186157 -0.694749 -0.694744 0.186156 -0.694753 -0.694741 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 -0.694763 0.186162 -0.694729 -0.69476 0.186159 -0.694733 -0.508597 0.508599 -0.694735 -0.508596 0.508598 -0.694736 -0.186158 0.694755 -0.694738 -0.186158 0.694751 -0.694742 0.13928 0.700219 -0.70021 0.139281 0.70022 -0.700209 0.396649 0.593618 -0.700205 0.396644 0.593616 -0.700209 0.593612 0.396649 -0.70021 0.593617 0.396649 -0.700206 0.700224 0.139278 -0.700205 0.700214 0.139282 -0.700214 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186158 -0.694753 -0.69474 -0.186159 -0.694753 -0.69474 -0.508595 -0.508598 -0.694737 -0.508597 -0.508598 -0.694735 -0.694759 -0.186161 -0.694733 -0.694763 -0.18616 -0.694729 0.694747 -0.186157 -0.694747 0.694757 -0.186166 -0.694734 0.508597 -0.508599 -0.694735 0.508592 -0.508584 -0.694749 0.186157 -0.694749 -0.694744 0.186156 -0.694753 -0.69474 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 -0.186158 0.694751 -0.694742 -0.186158 0.694755 -0.694738 -0.508596 0.508598 -0.694736 -0.694763 0.186162 -0.694729 -0.694759 0.186158 -0.694733 -0.563396 0.432315 -0.704051 -0.559577 0.729249 -0.393788 0.186157 0.694751 -0.694742 0.186156 0.69475 -0.694743 0.508588 0.508589 -0.694749 0.5086 0.508593 -0.694737 0.694758 0.186161 -0.694734 0.694746 0.186163 -0.694746 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.139282 -0.700219 -0.70021 -0.139281 -0.700217 -0.700212 -0.396636 -0.593614 -0.700216 -0.396645 -0.593617 -0.700208 -0.59362 -0.396641 -0.700208 -0.593606 -0.396641 -0.70022 -0.700204 -0.139287 -0.700224 -0.700233 -0.139275 -0.700198 0.694747 -0.186157 -0.694747 0.694756 -0.186166 -0.694735 0.508597 -0.508598 -0.694736 0.508592 -0.508585 -0.694748 0.186156 -0.69475 -0.694743 0.186156 -0.694751 -0.694742 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 0 0.707113 -0.7071 -0.694763 0.186162 -0.694729 -0.694759 0.186158 -0.694733 -0.508597 0.508598 -0.694736 -0.508596 0.508598 -0.694736 -0.186158 0.694755 -0.694738 -0.186158 0.694753 -0.69474 0.13928 0.700221 -0.700208 0.139282 0.700223 -0.700206 0.39665 0.59362 -0.700203 0.396643 0.593616 -0.70021 0.593611 0.396649 -0.700211 0.593618 0.396649 -0.700205 0.700225 0.139278 -0.700205 0.700214 0.139282 -0.700214 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.700233 -0.139275 -0.700198 -0.700203 -0.139287 -0.700225 -0.634865 -0.313059 -0.706357 -0.631787 -0.422154 -0.650101 -0.563392 -0.432312 -0.704057 -0.396645 -0.593617 -0.700208 -0.139283 -0.700221 -0.700208 -0.139281 -0.700219 -0.70021 -0.313077 -0.634868 -0.706347 -0.480295 -0.625931 -0.614432 0.694747 -0.186157 -0.694747 0.694757 -0.186166 -0.694734 0.508597 -0.5086 -0.694734 0.508592 -0.508585 -0.694748 0.186158 -0.69475 -0.694743 0.186157 -0.694753 -0.69474 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 -0.186158 0.694751 -0.694742 -0.186157 0.694757 -0.694736 -0.508597 0.508599 -0.694735 -0.694763 0.186162 -0.694729 -0.694759 0.186158 -0.694734 -0.563396 0.432314 -0.704053 -0.559577 0.729249 -0.393788 0.186156 0.694751 -0.694742 0.186157 0.694752 -0.694741 0.508589 0.508589 -0.694747 0.508599 0.508592 -0.694738 0.694758 0.186161 -0.694734 0.694746 0.186163 -0.694746 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.139283 -0.700221 -0.700208 -0.139281 -0.700219 -0.70021 -0.396639 -0.593615 -0.700214 -0.396645 -0.593617 -0.700208 -0.59362 -0.396641 -0.700208 -0.593605 -0.396641 -0.700221 -0.700203 -0.139287 -0.700225 -0.700233 -0.139275 -0.700198 0.694747 -0.186157 -0.694747 0.694757 -0.186166 -0.694734 0.508597 -0.5086 -0.694734 0.508592 -0.508585 -0.694748 0.186158 -0.69475 -0.694743 0.186157 -0.694753 -0.69474 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 -0.707113 -0.7071 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 -0.700231 0.139292 -0.700196 -0.700209 0.13927 -0.700223 -0.593608 0.396633 -0.700222 -0.593614 0.396646 -0.70021 -0.396641 0.593618 -0.70021 -0.396641 0.593616 -0.700212 -0.139281 0.700221 -0.700208 -0.139282 0.700219 -0.70021 0.186156 0.694751 -0.694742 0.186157 0.694752 -0.694741 0.508589 0.508589 -0.694747 0.508599 0.508592 -0.694738 0.694758 0.18616 -0.694734 0.694746 0.186163 -0.694746 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186158 -0.694751 -0.694742 -0.186159 -0.694752 -0.694741 -0.508595 -0.508597 -0.694738 -0.508598 -0.508598 -0.694734 -0.694759 -0.186161 -0.694733 -0.694763 -0.18616 -0.694729 0.694747 -0.186157 -0.694747 0.694757 -0.186166 -0.694734 0.508597 -0.5086 -0.694734 0.508592 -0.508583 -0.69475 0.186157 -0.694748 -0.694746 0.186156 -0.694751 -0.694742 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 -0.139282 0.700219 -0.70021 -0.139281 0.700221 -0.700208 -0.313081 0.634868 -0.706345 -0.422148 0.63179 -0.650102 -0.432307 0.563394 -0.704058 -0.593614 0.396646 -0.70021 -0.700231 0.139292 -0.700196 -0.700209 0.13927 -0.700223 -0.634864 0.313061 -0.706357 -0.625928 0.480297 -0.614434 0.18616 0.69475 -0.694742 0.186158 0.694747 -0.694746 0.508586 0.508588 -0.694751 0.508586 0.508588 -0.69475 0.694741 0.186156 -0.694752 0.694747 0.186155 -0.694747 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186158 -0.694751 -0.694742 -0.186159 -0.694752 -0.694741 -0.508595 -0.508597 -0.694738 -0.508598 -0.508598 -0.694734 -0.694759 -0.186161 -0.694733 -0.694763 -0.18616 -0.694729 0.700215 -0.139276 -0.700215 0.700222 -0.139284 -0.700206 0.593621 -0.396642 -0.700207 0.593627 -0.396657 -0.700193 0.396648 -0.593629 -0.700196 0.396648 -0.593623 -0.700202 0.139282 -0.700225 -0.700204 0.139285 -0.700219 -0.70021 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 -0.700231 0.139292 -0.700196 -0.700209 0.13927 -0.700223 -0.593608 0.396633 -0.700222 -0.593615 0.396648 -0.700208 -0.396643 0.593621 -0.700206 -0.396643 0.593615 -0.700212 -0.139281 0.700221 -0.700208 -0.139282 0.700219 -0.70021 0.18616 0.69475 -0.694742 0.186158 0.694747 -0.694746 0.508586 0.508588 -0.694751 0.508589 0.508589 -0.694747 0.694742 0.186156 -0.694751 0.694747 0.186155 -0.694747 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186158 -0.694751 -0.694742 -0.186159 -0.694752 -0.694741 -0.508595 -0.508597 -0.694738 -0.508595 -0.508597 -0.694737 -0.694758 -0.18616 -0.694734 -0.694764 -0.186159 -0.694729 0.700215 -0.139276 -0.700215 0.700222 -0.139284 -0.700206 0.593621 -0.396642 -0.700207 0.593626 -0.396654 -0.700195 0.396646 -0.593626 -0.7002 0.396646 -0.593624 -0.700202 0.139282 -0.700225 -0.700204 0.139285 -0.700219 -0.70021 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 -0.139282 0.700219 -0.70021 -0.139281 0.700221 -0.700208 -0.313081 0.634868 -0.706345 -0.422151 0.63179 -0.650101 -0.432309 0.563397 -0.704055 -0.593615 0.396648 -0.700208 -0.700231 0.139292 -0.700196 -0.700209 0.13927 -0.700223 -0.634864 0.313061 -0.706357 -0.625928 0.480297 -0.614434 0.18616 0.69475 -0.694742 0.186158 0.694747 -0.694746 0.508586 0.508588 -0.694751 0.508589 0.508589 -0.694747 0.694742 0.186156 -0.694751 0.694747 0.186155 -0.694747 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186156 -0.694751 -0.694742 -0.18616 -0.694756 -0.694736 -0.508598 -0.508598 -0.694734 -0.508595 -0.508597 -0.694737 -0.694758 -0.18616 -0.694734 -0.694764 -0.186159 -0.694729 0.700215 -0.139276 -0.700215 0.700222 -0.139284 -0.700206 0.593621 -0.396642 -0.700207 0.593626 -0.396654 -0.700195 0.396646 -0.593626 -0.7002 0.396646 -0.593624 -0.700202 0.139282 -0.700225 -0.700204 0.139285 -0.700219 -0.70021 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.707111 -0.707102 -0.700231 0.139292 -0.700196 -0.700209 0.13927 -0.700223 -0.593608 0.396633 -0.700222 -0.593614 0.396646 -0.70021 -0.396641 0.593618 -0.70021 -0.396641 0.593616 -0.700212 -0.139281 0.700221 -0.700208 -0.139282 0.700219 -0.70021 0.18616 0.69475 -0.694742 0.186158 0.694747 -0.694746 0.508586 0.508588 -0.694751 0.508586 0.508588 -0.69475 0.694741 0.186156 -0.694752 0.694747 0.186155 -0.694747 -0.707124 0 -0.707089 -0.707124 0 -0.707089 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.186156 -0.694751 -0.694742 -0.18616 -0.694756 -0.694736 -0.508598 -0.508598 -0.694734 -0.508595 -0.508597 -0.694737 -0.694758 -0.18616 -0.694734 -0.694764 -0.186159 -0.694729 0.700215 -0.139276 -0.700215 0.700222 -0.139284 -0.700206 0.593621 -0.396642 -0.700207 0.593626 -0.396654 -0.700195 0.396646 -0.593626 -0.7002 0.396646 -0.593624 -0.700202 0.139282 -0.700225 -0.700204 0.139285 -0.700219 -0.70021 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.707111 -0.707102 -0.310827 -0.950467 0 -0.417833 -0.908137 0.0265202 -0.515318 -0.856999 0.000613218 -0.610373 -0.792114 0 -0.775213 -0.6317 0 -0.775213 -0.6317 0 -0.97414 -0.225945 0 -0.97414 -0.225945 0 -0.610373 0.792114 0 -0.775213 0.6317 0 -0.775213 0.6317 0 -0.97414 0.225945 0 -0.97414 0.225945 0 -0.515318 0.856999 0.000613213 -0.417833 0.908137 0.0265202 -0.310827 0.950467 0 0.610873 -0.791729 0 0.775213 -0.6317 0 0.775213 -0.6317 0 0.97414 -0.225945 0 0.97414 -0.225945 0 0.515317 -0.856999 0.000616062 0.417838 -0.908135 0.0265213 0.310827 -0.950467 0 0.310827 0.950467 0 0.417838 0.908135 0.0265213 0.515317 0.856999 0.000616068 0.610873 0.791729 0 0.775213 0.6317 0 0.775213 0.6317 0 0.97414 0.225945 0 0.97414 0.225945 0 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.186161 0.694746 0.694746 -0.186156 0.694753 0.69474 -0.50859 0.5086 0.694739 -0.508593 0.508579 0.694752 -0.694741 0.186157 0.694752 -0.694745 0.186168 0.694745 -0.697784 -0.161846 0.697784 -0.697773 -0.161849 0.697795 -0.555286 -0.452488 0.697791 -0.555298 -0.452491 0.697779 -0.299405 -0.650738 0.69778 -0.299406 -0.650739 0.697778 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 -0.142775 -0.692549 0.707101 -0.142775 -0.692551 0.707099 -0.142775 -0.692549 0.707101 0.694763 0.186163 0.694728 0.694754 0.186171 0.694736 0.5086 0.50859 0.694739 0.508604 0.50859 0.694736 0.186158 0.694752 0.694741 0.186147 0.694748 0.694748 -0.697801 -0.161852 0.697766 -0.697791 -0.161849 0.697777 -0.555297 -0.452495 0.697778 -0.555296 -0.452495 0.697778 -0.299408 -0.650739 0.697778 -0.299408 -0.650739 0.697778 0.707124 0 0.707089 0.707124 0 0.707089 0.707124 0 0.707089 0.707124 0 0.707089 -0.707124 0 0.707089 -0.707124 0 0.707089 -0.707124 0 0.707089 0.299408 -0.650739 0.697778 0.299408 -0.650736 0.69778 0.555294 -0.452495 0.69778 0.555296 -0.452498 0.697777 0.697791 -0.161848 0.697777 0.697801 -0.161855 0.697766 -0.299408 0.650739 0.697778 -0.299408 0.650739 0.697778 -0.555296 0.452495 0.697778 -0.555297 0.452495 0.697778 -0.69779 0.16185 0.697778 -0.697801 0.161851 0.697766 0.142775 -0.692549 0.707101 0.142775 -0.692548 0.707102 0.142775 -0.692549 0.707101 -0.142775 0.692549 0.707101 -0.142775 0.692551 0.707099 -0.142775 0.692549 0.707101 0.299407 -0.650739 0.697778 0.299407 -0.650739 0.697778 0.555296 -0.452495 0.697778 0.555297 -0.452495 0.697778 0.697791 -0.161848 0.697777 0.697784 -0.161847 0.697784 -0.299405 0.65074 0.697778 -0.299405 0.650738 0.69778 -0.555294 0.452495 0.69778 -0.555289 0.452483 0.697792 -0.697774 0.161844 0.697795 -0.697784 0.161851 0.697784 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 0.697784 0.161847 0.697784 0.697791 0.161849 0.697777 0.555297 0.452495 0.697778 0.555296 0.452495 0.697778 0.299407 0.650739 0.697778 0.299407 0.650739 0.697778 -0.694746 -0.186159 0.694746 -0.694737 -0.186166 0.694754 -0.563388 -0.4323 0.704067 -0.480538 -0.480524 0.733608 -0.432294 -0.563407 0.704056 -0.186163 -0.69475 0.694741 -0.186171 -0.694753 0.694736 0.142775 0.692549 0.707101 0.142775 0.692548 0.707102 0.142775 0.692549 0.707101 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0 -0.707116 0.707098 0.697801 0.16185 0.697767 0.697789 0.161853 0.697778 0.555296 0.452496 0.697777 0.555293 0.452496 0.69778 0.299407 0.650737 0.69778 0.299409 0.650738 0.697778 0.186158 -0.694755 0.694738 0.186162 -0.69475 0.694741 0.432294 -0.563407 0.704056 0.480538 -0.480524 0.733608 0.563417 -0.432282 0.704055 0.694757 -0.186162 0.694735 0.694762 -0.186173 0.694727 0.707124 0 0.707089 0.707124 0 0.707089 0.707124 0 0.707089 0.707124 0 0.707089 0.707124 0 0.707089 0.142774 0.692544 0.707106 0.142775 0.692549 0.707101 0.142779 0.692571 0.707078 0.697784 0.161846 0.697784 0.697773 0.161849 0.697795 0.555286 0.452488 0.697791 0.555299 0.452492 0.697778 0.299405 0.65074 0.697778 0.299405 0.65074 0.697778 0.707107 0 0.707107 0.707107 0 0.707107 0.139289 -0.700222 0.700205 0.139289 -0.700223 0.700205 0.313083 -0.634876 0.706337 0.385519 -0.576973 0.720053 0.432293 -0.563406 0.704057 0.563396 -0.432305 0.704058 0.57697 -0.385505 0.720064 0.634887 -0.313049 0.706342 0.700218 -0.139299 0.700208 0.700214 -0.139287 0.700214 0 -0.707116 0.707098 -7.93963e-08 -0.707118 0.707095 0 -0.707107 0.707107 0 -0.707107 0.707107 0.142775 -0.692549 0.707101 0.142774 -0.692544 0.707106 0.142779 -0.692572 0.707078 0.299406 -0.650739 0.697778 0.299406 -0.65074 0.697778 0.555295 -0.452496 0.697778 0.555289 -0.452483 0.697792 0.697774 -0.161844 0.697795 0.697784 -0.161851 0.697784 0.707107 0 0.707107 0.707107 0 0.707107 0.694746 0.186159 0.694746 0.694737 0.186166 0.694754 0.508582 0.508593 0.69475 0.508604 0.50859 0.694736 0.186163 0.69475 0.694741 0.186154 0.694747 0.694747 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 -0.707119 0.707095 2.45083e-07 -0.707106 0.707107 1.50901e-08 -0.707116 0.707098 0 -0.707107 0.707107 -0.694746 -0.186159 0.694746 -0.694765 -0.186144 0.694732 -0.5086 -0.50859 0.694739 -0.508579 -0.508594 0.694752 -0.186156 -0.694748 0.694746 -0.186171 -0.694753 0.694736 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.299408 0.650739 0.697778 -0.299408 0.650738 0.697778 -0.555295 0.452496 0.697778 -0.555296 0.452498 0.697777 -0.697791 0.161848 0.697777 -0.697785 0.161843 0.697785 -0.142775 0.692549 0.707101 -0.142774 0.692544 0.707106 -0.142779 0.692572 0.707077 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 -0.186156 0.694747 0.694747 -0.186155 0.694749 0.694745 -0.508593 0.508583 0.69475 -0.50859 0.508604 0.694736 -0.694757 0.186162 0.694735 -0.694749 0.18614 0.694749 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.697784 -0.161846 0.697784 -0.697792 -0.161844 0.697777 -0.555296 -0.452497 0.697777 -0.555294 -0.452497 0.697779 -0.299409 -0.650738 0.697778 -0.299409 -0.650738 0.697778 -0.142774 -0.692544 0.707106 -0.142775 -0.692549 0.707101 -0.142779 -0.692571 0.707078 0 0.707107 -0.707107 0 0.707107 -0.707107 -0.396642 0.593617 -0.70021 -0.39664 0.593616 -0.700212 -0.139286 0.70022 -0.700208 -0.13928 0.700215 -0.700215 0.186161 0.694746 -0.694746 0.186156 0.694753 -0.69474 0.50859 0.5086 -0.694739 0.508593 0.508579 -0.694752 0.694741 0.186157 -0.694752 0.694745 0.186168 -0.694745 -0.500002 0.500004 -0.707102 -0.500002 0.500004 -0.707102 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.396643 0.593616 -0.70021 -0.396642 0.593615 -0.700212 -0.139281 0.700221 -0.700208 -0.139282 0.700214 -0.700214 0.697784 -0.161846 -0.697784 0.697773 -0.161849 -0.697795 0.555286 -0.452488 -0.697791 0.555299 -0.452492 -0.697778 0.299406 -0.65074 -0.697778 0.299406 -0.650739 -0.697778 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0.142775 -0.692549 -0.707101 0.142775 -0.692549 -0.707101 0.13928 0.700215 -0.700215 0.139286 0.700224 -0.700204 0.396647 0.593623 -0.700202 0.39664 0.593619 -0.70021 0.697784 -0.161847 -0.697784 0.697791 -0.161849 -0.697777 0.555297 -0.452495 -0.697778 0.555296 -0.452495 -0.697778 0.299407 -0.650739 -0.697778 0.299407 -0.650739 -0.697778 0.500004 0.500002 -0.707102 0.500004 0.500002 -0.707102 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.139288 0.700214 -0.700214 0.139282 0.700225 -0.700204 0.39664 0.593627 -0.700203 0.396641 0.593618 -0.70021 0.299407 0.650739 -0.697778 0.299407 0.650739 -0.697778 0.555296 0.452495 -0.697778 0.555297 0.452495 -0.697778 0.697791 0.161848 -0.697777 0.697784 0.161847 -0.697784 0 0.707107 -0.707107 0 0.707107 -0.707107 0.142775 0.692549 -0.707101 0.142775 0.692549 -0.707101 -0.694746 0.186159 -0.694746 -0.694765 0.186144 -0.694732 -0.5086 0.50859 -0.694739 -0.508579 0.508594 -0.694752 -0.186156 0.694748 -0.694746 -0.186154 0.694747 -0.694747 0.299405 0.65074 -0.697778 0.299405 0.65074 -0.697778 0.555295 0.452496 -0.697778 0.555289 0.452483 -0.697792 0.697774 0.161844 -0.697795 0.697784 0.161851 -0.697784 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 -0.299409 -0.650738 -0.697778 -0.299409 -0.650738 -0.697778 -0.555295 -0.452496 -0.697778 -0.555296 -0.452498 -0.697777 -0.697791 -0.161848 -0.697777 -0.697785 -0.161843 -0.697785 0.694746 -0.186159 -0.694746 0.694737 -0.186166 -0.694754 0.508582 -0.508593 -0.69475 0.508604 -0.50859 -0.694736 0.186163 -0.69475 -0.694741 0.186171 -0.694753 -0.694736 -0.142775 -0.692549 -0.707101 -0.142775 -0.692549 -0.707101 0 -0.707116 -0.707098 0 -0.707116 -0.707098 -0.299408 -0.650739 -0.697778 -0.299408 -0.650739 -0.697778 -0.555296 -0.452495 -0.697778 -0.555297 -0.452495 -0.697778 -0.69779 -0.16185 -0.697778 -0.697801 -0.161851 -0.697766 -0.13928 -0.700223 -0.700206 -0.139287 -0.700211 -0.700217 -0.396642 -0.593607 -0.700219 -0.396641 -0.593618 -0.70021 -0.707124 0 -0.707089 -0.707124 0 -0.707089 -0.707124 0 -0.707089 -0.500003 -0.500003 -0.707102 -0.499999 -0.500001 -0.707107 -0.5 -0.500006 -0.707102 -0.697801 0.161852 -0.697766 -0.697791 0.161849 -0.697777 -0.555297 0.452495 -0.697778 -0.555296 0.452495 -0.697778 -0.299408 0.650739 -0.697778 -0.299408 0.650739 -0.697778 -0.139281 -0.700223 -0.700206 -0.13928 -0.700222 -0.700208 -0.396642 -0.593615 -0.700212 -0.396643 -0.593616 -0.70021 -0.142775 0.692549 -0.707101 -0.142775 0.692549 -0.707101 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707116 -0.707098 -0.697784 0.161846 -0.697784 -0.697792 0.161844 -0.697777 -0.555296 0.452497 -0.697777 -0.555294 0.452497 -0.697779 -0.299408 0.650738 -0.697778 -0.299409 0.650739 -0.697778 0.396643 -0.593616 -0.70021 0.396644 -0.593625 -0.700202 0.139282 -0.700225 -0.700204 0.139282 -0.700223 -0.700206 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 0.500004 -0.500002 -0.707102 0.500008 -0.500008 -0.707096 0.500006 -0.5 -0.707102 -0.186158 -0.694755 -0.694738 -0.186168 -0.694743 -0.694747 -0.508593 -0.508583 -0.69475 -0.50859 -0.508604 -0.694736 -0.694757 -0.186162 -0.694735 -0.694749 -0.18614 -0.694749 0.396641 -0.593618 -0.70021 0.396641 -0.593618 -0.700209 0.139281 -0.700216 -0.700213 0.139289 -0.700222 -0.700205 0 -0.707116 -0.707098 0 -0.707116 -0.707098 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 -0.707107 1.21399e-08 -0.707125 -0.707089 1.9407e-08 -0.70713 -0.707084 0 -0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980787 0.195084 0 -0.980787 0.195084 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195089 0.980786 0 -0.195089 0.980786 0 0 1 0 0 1 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0 -1 0 0 -1 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.83147 -0.555569 0 -0.83147 -0.555569 0 -0.980787 -0.195084 0 -0.980787 -0.195084 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.694755 0.186159 0.694738 0.694751 0.186158 0.694742 0.508591 0.508593 0.694743 0.508591 0.508593 0.694743 0.186158 0.694747 0.694745 0.186156 0.694742 0.694751 0 0.707102 0.707111 0 0.707102 0.707111 0 0.707102 0.707111 0 0.707102 0.707111 0 0.707102 0.707111 0 0.707102 0.707111 0 0.707102 0.707111 0 0.707102 0.707111 -0.186156 0.694742 0.694751 -0.186156 0.694748 0.694745 -0.508593 0.508591 0.694743 -0.508593 0.508591 0.694743 -0.69475 0.186161 0.694742 -0.694738 0.186155 0.694755 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.707098 0 0.707116 -0.694738 -0.186158 0.694755 -0.69475 -0.186158 0.694743 -0.508591 -0.508589 0.694747 -0.508591 -0.508589 0.694746 -0.186155 -0.694744 0.69475 -0.186157 -0.694747 0.694747 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0.186157 -0.694747 0.694747 0.186157 -0.694743 0.69475 0.508589 -0.508591 0.694747 0.508589 -0.508591 0.694746 0.69475 -0.186157 0.694743 0.694755 -0.18616 0.694738 0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 0.707115 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 0.707116 0 0.707098 0.965926 0.258818 0 0.965926 0.258818 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258821 0.965925 0 0.258821 0.965925 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965925 0.258823 0 -0.965925 0.258823 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.965925 -0.258823 0 -0.965925 -0.258823 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.258818 0 0.965926 -0.258818 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 -1 0 0 -0.977819 -0.20945 0 -0.977819 -0.20945 0 -0.806226 -0.591608 0 -0.806226 -0.591608 0 -0.493153 -0.869943 0 -0.493153 -0.869943 0 -0.511477 -0.859297 0 -0.511477 -0.859297 0 -0.84219 -0.53918 0 -0.84219 -0.53918 0 -0.994489 -0.104845 0 -0.994489 -0.104845 0 -0.93611 0.351707 0 -0.93611 0.351707 0 -0.774771 0.632242 0 -0.677834 0.732014 -0.0685277 -0.608478 0.793571 0 -0.27881 0.960346 0 -0.27881 0.960346 0 -0.698162 0.71594 0 -0.664869 0.745239 0.0506832 -0.519943 0.854201 0 -0.272879 0.962048 0 -0.272879 0.962048 0 -0.65628 0.754517 0 -0.65628 0.754517 0 -0.236367 0.971664 0 -0.236367 0.971664 0 0 1 0 0 1 0 0.236367 0.971664 0 0.236367 0.971664 0 0.65628 0.754517 0 0.65628 0.754517 0 0.698162 0.71594 0 0.664869 0.745239 0.0506832 0.519943 0.854201 0 0.272877 0.962049 0 0.272877 0.962049 0 0.278813 0.960345 0 0.278813 0.960345 0 0.679427 0.733744 0 0.679427 0.733744 0 0.936114 0.351698 0 0.936114 0.351698 0 0.994489 -0.104845 0 0.994489 -0.104845 0 0.84219 -0.53918 0 0.84219 -0.53918 0 0.511477 -0.859297 0 0.511477 -0.859297 0 0.493153 -0.869943 0 0.493153 -0.869943 0 0.806226 -0.591608 0 0.806226 -0.591608 0 0.977819 -0.20945 0 0.977819 -0.20945 0 1 0 0 1 0 0 1 0 0 0.975822 0.218566 0 0.975822 0.218566 0 0.78935 0.613944 0 0.78935 0.613944 0 0.452048 0.891994 0 0.452048 0.891994 0 0.452045 0.891995 0 0.452045 0.891995 0 0.789355 0.613938 0 0.789355 0.613938 0 0.975822 0.218568 0 0.975822 0.218568 0 0.975822 -0.218568 0 0.975822 -0.218568 0 0.789355 -0.613938 0 0.789355 -0.613938 0 0.452045 -0.891995 0 0.452045 -0.891995 0 0.452048 -0.891994 0 0.452048 -0.891994 0 0.78935 -0.613944 0 0.78935 -0.613944 0 0.975822 -0.218566 0 0.975822 -0.218566 0 1 0 0 1 0 0 1 0 0 0.977819 0.20945 0 0.977819 0.20945 0 0.806226 0.591608 0 0.806226 0.591608 0 0.493153 0.869943 0 0.493153 0.869943 0 0.511477 0.859297 0 0.511477 0.859297 0 0.84219 0.53918 0 0.84219 0.53918 0 0.994489 0.104845 0 0.994489 0.104845 0 0.936114 -0.351697 0 0.936114 -0.351697 0 0.679427 -0.733744 0 0.679427 -0.733744 0 0.278813 -0.960345 0 0.278813 -0.960345 0 0.698162 -0.71594 0 0.664867 -0.74524 0.0506851 0.519935 -0.854206 0 0.272877 -0.962049 0 0.272877 -0.962049 0 0.65628 -0.754517 0 0.65628 -0.754517 0 0.236368 -0.971664 0 0.236368 -0.971664 0 0 -1 0 0 -1 0 -0.236368 -0.971664 0 -0.236368 -0.971664 0 -0.65628 -0.754517 0 -0.65628 -0.754517 0 -0.698162 -0.71594 0 -0.664867 -0.74524 0.0506851 -0.519935 -0.854206 0 -0.272879 -0.962048 0 -0.272879 -0.962048 0 -0.27881 -0.960346 0 -0.27881 -0.960346 0 -0.679432 -0.733739 0 -0.679432 -0.733739 0 -0.93611 -0.351706 0 -0.93611 -0.351706 0 -0.994489 0.104845 0 -0.994489 0.104845 0 -0.84219 0.53918 0 -0.84219 0.53918 0 -0.511477 0.859297 0 -0.511477 0.859297 0 -0.493153 0.869943 0 -0.493153 0.869943 0 -0.806226 0.591608 0 -0.806226 0.591608 0 -0.977819 0.20945 0 -0.977819 0.20945 0 -1 0 0 -1 0 0 -1 0 0 -0.975822 -0.218566 0 -0.975822 -0.218566 0 -0.789355 -0.613937 0 -0.789355 -0.613937 0 -0.452044 -0.891996 0 -0.452044 -0.891996 0 -0.452049 -0.891993 0 -0.452049 -0.891993 0 -0.67309 -0.73956 0 -0.788568 -0.613336 -0.0444835 -0.81846 -0.574563 0 -0.975822 -0.218568 0 -0.975822 -0.218568 0 -0.975822 0.218568 0 -0.975822 0.218568 0 -0.81846 0.574563 0 -0.788568 0.613336 -0.0444835 -0.67309 0.73956 0 -0.452049 0.891993 0 -0.452049 0.891993 0 -0.452044 0.891996 0 -0.452044 0.891996 0 -0.789355 0.613937 0 -0.789355 0.613937 0 -0.975822 0.218566 0 -0.975822 0.218566 0 0 1 0 0 1 0 -0.19509 0.980785 0 -0.19509 0.980785 0 -0.555574 0.831467 0 -0.555574 0.831467 0 -0.831467 0.555574 0 -0.831467 0.555574 0 -0.980786 0.195087 0 -0.980786 0.195087 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9807 -0.19552 0 -0.965714 -0.258759 -0.0209632 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.89668 -0.44268 0 0 -1 0 0 -1 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.651247 -0.758866 0 0.706915 -0.706918 -0.0231785 0.965927 -0.258816 0 0.965927 -0.258816 0 0.825462 -0.564458 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.980786 0.195087 0 0.980786 0.195087 0 0.864061 0.503387 0 0.831393 0.555517 -0.0136426 0.19509 0.980785 0 0.19509 0.980785 0 0.55557 0.83147 0 0.55557 0.83147 0 0.749259 0.662277 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.965923 0.258828 0 0.965923 0.258828 0 0.707113 0.707101 0 0.707113 0.707101 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707101 0.707113 0 -0.707101 0.707113 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.7071 -0.707114 0 -0.7071 -0.707114 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.7071 -0.707114 0 0.7071 -0.707114 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258806 0 0.965929 0.258806 0 0.707101 0.707113 0 0.707101 0.707113 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707113 0.707101 0 -0.707113 0.707101 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707112 -0.707102 0 0.707112 -0.707102 0 0.965924 -0.258828 0 0.965924 -0.258828 0 0.965924 0.258828 0 0.965924 0.258828 0 0.707112 0.707102 0 0.707112 0.707102 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.7071 0.707113 0 -0.7071 0.707113 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.7071 -0.707113 0 -0.7071 -0.707113 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.7071 -0.707113 0 0.7071 -0.707113 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258806 0 0.965929 0.258806 0 0.7071 0.707113 0 0.7071 0.707113 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707112 0.707102 0 -0.707112 0.707102 0 -0.965924 0.258828 0 -0.965924 0.258828 0 -0.965924 -0.258828 0 -0.965924 -0.258828 0 -0.707112 -0.707102 0 -0.707112 -0.707102 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.965923 0.258828 0 0.965923 0.258828 0 0.707113 0.707101 0 0.707113 0.707101 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707101 0.707113 0 -0.707101 0.707113 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.707101 -0.707113 0 -0.707101 -0.707113 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707101 -0.707113 0 0.707101 -0.707113 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258806 0 0.965929 0.258806 0 0.707101 0.707113 0 0.707101 0.707113 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707113 0.707101 0 -0.707113 0.707101 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.195093 -0.980785 0 0.195093 -0.980785 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980786 -0.195084 0 0.980786 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0 -1 0 0 -1 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.83147 0.555569 0 0.83147 0.555569 0 0.980787 0.195084 0 0.980787 0.195084 0 0 1 0 0 1 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.195093 -0.980785 0 -0.195093 -0.980785 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0 -1 0 0 -1 0 -0.980783 0.1951 0 -0.980783 0.1951 0 -0.83147 0.555569 0 -0.83147 0.555569 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195093 0.980785 0 -0.195093 0.980785 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.83147 0.555569 0 0.83147 0.555569 0 0.980787 0.195084 0 0.980787 0.195084 0 0 1 0 0 1 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 0 -1 0 0 -1 0 -0.980783 0.195101 0 -0.980783 0.195101 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195093 0.980785 0 -0.195093 0.980785 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980786 0.195084 0 0.980786 0.195084 0 0 1 0 0 1 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.195093 -0.980785 0 0.195093 -0.980785 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980786 -0.195084 0 0.980786 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0 -1 0 0 -1 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831472 0.555567 0 0.831472 0.555567 0 0.980786 0.195084 0 0.980786 0.195084 0 0 1 0 0 1 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.195089 -0.980786 0 0.195089 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980787 -0.195084 0 0.980787 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0 -1 0 0 -1 0 -0.980783 0.1951 0 -0.980783 0.1951 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195089 0.980786 0 -0.195089 0.980786 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0 1 0 0 1 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.195089 -0.980786 0 0.195089 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980787 -0.195084 0 0.980787 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0 -1 0 0 -1 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0 1 0 0 1 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.195089 -0.980786 0 0.195089 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980787 -0.195084 0 0.980787 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 0 -1 0 0 -1 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 0 1 0 0 1 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.195089 -0.980786 0 0.195089 -0.980786 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.831472 -0.555567 0 0.831472 -0.555567 0 0.980787 -0.195084 0 0.980787 -0.195084 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 0 -1 0 0 -1 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 -0.980783 0.1951 0 -0.980783 0.1951 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195089 0.980786 0 -0.195089 0.980786 0 0 1 0 0 1 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980783 0.1951 0 -0.980783 0.1951 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195089 0.980786 0 -0.195089 0.980786 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258816 0.965927 0 0.258816 0.965927 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 0 1 0 0 1 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 -0.980783 0.195101 0 -0.980783 0.195101 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555567 0.831472 0 -0.555567 0.831472 0 -0.195091 0.980785 0 -0.195091 0.980785 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 -0.831472 -0.555568 0 -0.831472 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980783 0.195101 0 -0.980783 0.195101 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195089 0.980786 0 -0.195089 0.980786 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -1 0 0 -1 0 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258816 0.965927 0 0.258816 0.965927 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -1 0 0 -1 0 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831463 0.55558 0 0.831463 0.55558 0 0.980787 0.195084 0 0.980787 0.195084 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980783 0.1951 0 -0.980783 0.1951 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195091 0.980785 0 -0.195091 0.980785 0 -0.980783 -0.1951 0 -0.980783 -0.1951 0 -0.831472 -0.555567 0 -0.831472 -0.555567 0 -0.555567 -0.831472 0 -0.555567 -0.831472 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -1 0 0 -1 0 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -1 0 0 -1 0 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555575 0.831466 0 0.555575 0.831466 0 0.831463 0.55558 0 0.831463 0.55558 0 0.980787 0.195084 0 0.980787 0.195084 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -1 0 0 -1 0 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831463 0.55558 0 0.831463 0.55558 0 0.980787 0.195084 0 0.980787 0.195084 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -1 0 0 -1 0 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195088 0.980786 0 0.195088 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831463 0.55558 0 0.831463 0.55558 0 0.980787 0.195084 0 0.980787 0.195084 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980783 0.1951 0 -0.980783 0.1951 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195091 0.980785 0 -0.195091 0.980785 0 -0.980783 -0.195101 0 -0.980783 -0.195101 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -1 0 0 -1 0 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980783 0.195101 0 -0.980783 0.195101 0 -0.831471 0.555568 0 -0.831471 0.555568 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195091 0.980785 0 -0.195091 0.980785 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -1 0 0 -1 0 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831463 0.55558 0 0.831463 0.55558 0 0.980787 0.195084 0 0.980787 0.195084 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980783 0.195101 0 -0.980783 0.195101 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555567 0.831472 0 -0.555567 0.831472 0 -0.195093 0.980785 0 -0.195093 0.980785 0 -0.980783 -0.1951 0 -0.980783 -0.1951 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 -1 0 0 -1 0 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707105 -0.707108 0 -0.707105 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -1 0 0 -1 0 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831464 0.555579 0 0.831464 0.555579 0 0.980787 0.195084 0 0.980787 0.195084 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707105 0.707108 0 -0.707105 0.707108 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.980783 -0.1951 0 -0.980783 -0.1951 0 -0.83147 -0.555569 0 -0.83147 -0.555569 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 -1 0 0 -1 0 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.195087 0.980786 0 0.195087 0.980786 0 0.555576 0.831466 0 0.555576 0.831466 0 0.831464 0.555579 0 0.831464 0.555579 0 0.980787 0.195084 0 0.980787 0.195084 0 1 0 0 1 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.980783 0.195101 0 -0.980783 0.195101 0 -0.831472 0.555567 0 -0.831472 0.555567 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195093 0.980785 0 -0.195093 0.980785 0 0.980787 -0.195084 0 0.980787 -0.195084 0 0.831462 -0.555581 0 0.831462 -0.555581 0 0.555576 -0.831466 0 0.555576 -0.831466 0 0.19509 -0.980785 0 0.19509 -0.980785 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707105 0.707108 0 0.707105 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 0 1 0 0 1 0 0 -0.980783 -0.1951 0 -0.980783 -0.1951 0 -0.83147 -0.555569 0 -0.83147 -0.555569 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.195093 -0.980785 0 -0.195093 -0.980785 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.373495 -0.373491 0.849121 0.13671 -0.5102 0.849121 0.373496 0.37349 0.849121 0.5102 0.136713 0.84912 0.5102 -0.136713 0.84912 -0.373489 0.373495 0.849122 -0.136708 0.5102 0.849121 0.136708 0.5102 0.849121 -0.373488 -0.373496 0.849122 -0.510201 -0.136701 0.849122 -0.510201 0.136701 0.849122 -0.13671 -0.5102 0.849121 0.258822 -0.965925 0 0.258822 -0.965925 0 0.707111 -0.707102 0 0.707111 -0.707102 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.965923 0.258828 0 0.965923 0.258828 0 0.707113 0.707101 0 0.707113 0.707101 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707101 0.707113 0 -0.707101 0.707113 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.7071 -0.707114 0 -0.7071 -0.707114 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.373488 -0.373496 0.849122 0.13671 -0.5102 0.849121 0.373489 0.373495 0.849122 0.510201 0.136701 0.849122 0.510201 -0.136701 0.849122 -0.373496 0.37349 0.849121 -0.136708 0.5102 0.849121 0.136708 0.5102 0.849121 -0.373495 -0.373491 0.849121 -0.5102 -0.136713 0.84912 -0.5102 0.136713 0.84912 -0.13671 -0.5102 0.849121 0.258822 -0.965925 0 0.258822 -0.965925 0 0.7071 -0.707114 0 0.7071 -0.707114 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258806 0 0.965929 0.258806 0 0.707101 0.707113 0 0.707101 0.707113 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707113 0.707101 0 -0.707113 0.707101 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.707111 -0.707102 0 -0.707111 -0.707102 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.373496 -0.37349 0.849121 0.136708 -0.5102 0.849121 0.373496 0.37349 0.849121 0.5102 0.136713 0.84912 0.5102 -0.136713 0.84912 -0.373488 0.373495 0.849122 -0.136708 0.5102 0.849121 0.136708 0.5102 0.849121 -0.373488 -0.373495 0.849122 -0.510201 -0.136701 0.849122 -0.510201 0.136701 0.849122 -0.136708 -0.5102 0.849121 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707112 -0.707102 0 0.707112 -0.707102 0 0.965924 -0.258828 0 0.965924 -0.258828 0 0.965924 0.258828 0 0.965924 0.258828 0 0.707112 0.707102 0 0.707112 0.707102 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.7071 0.707113 0 -0.7071 0.707113 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.7071 -0.707113 0 -0.7071 -0.707113 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.373488 -0.373495 0.849122 0.136708 -0.5102 0.849121 0.373488 0.373495 0.849122 0.510201 0.136701 0.849122 0.510201 -0.136701 0.849122 -0.373496 0.37349 0.849121 -0.136708 0.5102 0.849121 0.136708 0.5102 0.849121 -0.373496 -0.37349 0.849121 -0.5102 -0.136713 0.84912 -0.5102 0.136713 0.84912 -0.136708 -0.5102 0.849121 0.258819 -0.965926 0 0.258819 -0.965926 0 0.7071 -0.707113 0 0.7071 -0.707113 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258806 0 0.965929 0.258806 0 0.7071 0.707113 0 0.7071 0.707113 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707112 0.707102 0 -0.707112 0.707102 0 -0.965924 0.258828 0 -0.965924 0.258828 0 -0.965924 -0.258828 0 -0.965924 -0.258828 0 -0.707112 -0.707102 0 -0.707112 -0.707102 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.373496 -0.37349 0.849121 0.136708 -0.5102 0.849121 0.373496 0.37349 0.849121 0.5102 0.136713 0.84912 0.5102 -0.136713 0.84912 -0.373489 0.373495 0.849122 -0.136707 0.510201 0.849121 0.136707 0.510201 0.849121 -0.373489 -0.373495 0.849122 -0.510201 -0.136701 0.849122 -0.510201 0.136701 0.849122 -0.136708 -0.5102 0.849121 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.965923 0.258828 0 0.965923 0.258828 0 0.707113 0.707101 0 0.707113 0.707101 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707101 0.707113 0 -0.707101 0.707113 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.707101 -0.707113 0 -0.707101 -0.707113 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.373489 -0.373495 0.849122 0.136708 -0.5102 0.849121 0.373489 0.373495 0.849122 0.510201 0.136701 0.849122 0.510201 -0.136701 0.849122 -0.373496 0.37349 0.849121 -0.136707 0.510201 0.849121 0.136707 0.510201 0.849121 -0.373496 -0.37349 0.849121 -0.5102 -0.136713 0.84912 -0.5102 0.136713 0.84912 -0.136708 -0.5102 0.849121 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707101 -0.707113 0 0.707101 -0.707113 0 0.965929 -0.258806 0 0.965929 -0.258806 0 0.965929 0.258806 0 0.965929 0.258806 0 0.707101 0.707113 0 0.707101 0.707113 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707113 0.707101 0 -0.707113 0.707101 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.707113 -0.707101 0 -0.707113 -0.707101 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0 -0.425779 0.904827 0 -0.217851 0.975982 -0.0173266 -0.187353 0.98214 0 -0.0938103 0.99559 0 0.0627905 0.998027 0 0.0627905 0.998027 0 0.309017 0.951057 0 0.309017 0.951057 0 0.535827 0.844328 0 0.535827 0.844328 0 0.728969 0.684547 0 0.728969 0.684547 0 0.821588 0.570081 -0.0132912 0.876229 0.481711 0 0.88656 0.462613 0 0.968583 0.24869 0 0.968583 0.24869 0 1 0 0 1 0 0 0.968583 -0.24869 0 0.968583 -0.24869 0 0.876307 -0.481754 0 0.876307 -0.481754 0 0.767698 -0.640812 -0.0231409 0.728773 -0.684364 0 0.681329 -0.731977 0 0.535827 -0.844328 0 0.535827 -0.844328 0 0.309017 -0.951057 0 0.309017 -0.951057 0 0.0627905 -0.998027 0 0.0627905 -0.998027 0 -0.187381 -0.982287 0 -0.187381 -0.982287 0 -0.425779 -0.904827 0 -0.425779 -0.904827 0 -0.615367 -0.788241 -0.0162264 -0.63734 -0.770412 0 -0.709308 -0.704899 0 -0.809017 -0.587786 0 -0.809017 -0.587786 0 -0.929777 -0.368124 0 -0.929777 -0.368124 0 -0.992115 -0.125334 0 -0.992115 -0.125334 0 -0.992115 0.125334 0 -0.992115 0.125334 0 -0.929777 0.368124 0 -0.929777 0.368124 0 -0.809017 0.587785 0 -0.809017 0.587785 0 -0.709308 0.704899 -0.0162264 -0.63734 0.770412 0 -0.615367 0.788241 0 -0.425779 0.904827 -0.849119 0.13671 -0.510203 -0.849119 0.373493 -0.373496 -0.849119 0.510204 -0.136707 -0.84912 -0.510202 -0.136712 -0.849119 -0.373493 -0.373496 -0.849119 -0.13671 -0.510203 0 0.965927 -0.258816 0 0.965927 -0.258816 0 0.707104 -0.70711 0 0.707104 -0.70711 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707104 -0.70711 0 -0.707104 -0.70711 0 -0.965924 -0.258826 0 -0.965924 -0.258826 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258817 0 -0.965926 -0.258817 -0.849119 0.136708 -0.510204 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136708 -0.849119 -0.510204 -0.136708 -0.849119 -0.373495 -0.373495 -0.849119 -0.136708 -0.510204 0 0.965927 -0.258816 0 0.965927 -0.258816 0 0.707104 -0.70711 0 0.707104 -0.70711 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707104 -0.70711 0 -0.707104 -0.70711 0 -0.965927 -0.258816 0 -0.965927 -0.258816 -0.849119 0.13671 -0.510203 -0.849119 0.373493 -0.373496 -0.849119 0.510204 -0.136707 -0.849119 -0.510204 -0.136707 -0.849119 -0.373493 -0.373496 -0.849119 -0.13671 -0.510203 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.258819 0 -0.965926 -0.258819 -0.849119 0.136709 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136709 -0.849119 -0.510204 -0.136709 -0.849119 -0.373495 -0.373495 -0.849119 -0.136709 -0.510203 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965926 -0.258819 0 -0.965926 -0.258819 -0.849119 0.136709 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136709 -0.849119 -0.510204 -0.136709 -0.849119 -0.373495 -0.373495 -0.849119 -0.136709 -0.510203 0 0.974929 -0.222518 0 0.974929 -0.222518 0 0.78183 -0.623491 0 0.78183 -0.623491 0 0.433884 -0.900969 0 0.433884 -0.900969 0 0 -1 0 0 -1 0 -0.433884 -0.900969 0 -0.433884 -0.900969 0 -0.78183 -0.623491 0 -0.78183 -0.623491 0 -0.974929 -0.222518 0 -0.974929 -0.222518 -0.851305 0.511518 -0.116749 -0.851305 0 -0.524671 -0.851305 0.227646 -0.472712 -0.851305 0.410204 -0.327128 -0.851305 -0.511518 -0.116749 -0.851305 -0.410204 -0.327128 -0.851305 -0.227646 -0.472712 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.258817 0 -0.965926 -0.258817 -0.849119 0.13671 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136708 -0.849119 -0.510204 -0.136708 -0.849119 -0.373495 -0.373495 -0.849119 -0.13671 -0.510203 0 0.965927 -0.258816 0 0.965927 -0.258816 0 0.707104 -0.70711 0 0.707104 -0.70711 0 0.258822 -0.965925 0 0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707104 -0.70711 0 -0.707104 -0.70711 0 -0.965924 -0.258826 0 -0.965924 -0.258826 -0.849119 0.13671 -0.510203 -0.849119 0.373493 -0.373496 -0.849119 0.510204 -0.136707 -0.84912 -0.510202 -0.136712 -0.849119 -0.373493 -0.373496 -0.849119 -0.13671 -0.510203 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965924 -0.258827 0 -0.965924 -0.258827 -0.849119 0.136709 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136707 -0.84912 -0.510202 -0.136713 -0.849119 -0.373495 -0.373495 -0.849119 -0.136709 -0.510203 0 0.965926 -0.258817 0 0.965926 -0.258817 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.965924 -0.258827 0 -0.965924 -0.258827 -0.849119 0.136709 -0.510203 -0.849119 0.373495 -0.373495 -0.849119 0.510204 -0.136707 -0.84912 -0.510202 -0.136713 -0.849119 -0.373495 -0.373495 -0.849119 -0.136709 -0.510203 0.939848 0.337905 -0.0500604 0.939677 0.337956 -0.0528403 0.939715 0.337878 -0.0526762 0.939823 0.337573 -0.0526978 0.939762 0.337887 -0.0517753 0.939691 0.337679 -0.0543523 0.94079 0.334607 -0.0543267 0.940495 0.335427 -0.054389 0.939737 0.337746 -0.0531191 0.940046 0.337704 -0.0476423 0.940591 0.336735 -0.0435708 0.940962 0.335914 -0.0418716 0.939576 0.341979 -0.0157344 0.938802 0.344162 -0.0142347 0.93981 0.340166 -0.0323053 0.940119 0.33889 -0.0364679 0.940386 0.322178 -0.108973 0.940247 0.32256 -0.109046 0.939698 0.324569 -0.107809 0.939684 0.324671 -0.107625 0.939727 0.324594 -0.107481 0.939662 0.32494 -0.107001 0.939729 0.324326 -0.10827 0.939822 0.324682 -0.10638 0.939969 0.324733 -0.104909 0.940225 0.324739 -0.102576 0.940754 0.323997 -0.100036 0.941064 0.323524 -0.0986479 0.942088 0.321707 -0.0947389 0.941623 0.322674 -0.0960641 0.944165 0.320929 -0.074544 0.939063 0.336428 -0.0705416 0.939772 0.330577 -0.0868813 0.940189 0.328534 -0.0900526 0.941649 0.329073 -0.0707748 0.940555 0.33282 -0.0677222 0.939668 0.336152 -0.0634491 0.940374 0.334783 -0.0601473 0.939672 0.336289 -0.0626617 0.939728 0.334845 -0.0692155 0.939651 0.335036 -0.0693306 0.939553 0.336555 -0.0630188 0.941745 0.330663 -0.061462 0.941626 0.33099 -0.0615359 0.93961 0.335167 -0.0692483 0.940018 0.334182 -0.0684777 0.939883 0.234521 -0.248234 0.939789 0.233788 -0.249278 0.940267 0.23606 -0.245303 0.941321 0.237054 -0.24025 0.94208 0.237156 -0.237156 0.941395 0.239941 -0.237072 0.940149 0.24579 -0.236024 0.937959 0.264597 -0.224103 0.943048 0.249054 -0.22053 0.940656 0.262036 -0.215646 0.939634 0.263025 -0.218872 0.939731 0.255373 -0.227355 0.939652 0.255484 -0.227557 0.939425 0.263271 -0.219475 0.943051 0.255787 -0.212669 0.942939 0.256027 -0.212878 0.939611 0.255639 -0.227551 0.94001 0.255181 -0.226415 0.9397 0.227176 -0.255646 0.94602 0.198321 -0.25635 0.939663 0.227897 -0.25514 0.940301 0.20821 -0.269225 0.942693 0.207302 -0.26145 0.927055 0.217861 -0.305133 0.941557 0.22066 -0.254518 0.93998 0.220536 -0.260386 0.939694 0.230917 -0.252293 0.939686 0.232692 -0.250688 0.944499 0.107729 -0.310348 0.932708 0.131093 -0.335962 0.941868 0.0952985 -0.322185 0.941584 0.0960952 -0.322778 0.940161 0.0898601 -0.328669 0.940932 0.123086 -0.315432 0.939576 0.122822 -0.319548 0.939736 0.107483 -0.324567 0.939645 0.107477 -0.324833 0.939276 0.12283 -0.320428 0.944297 0.118194 -0.307136 0.944185 0.118305 -0.30744 0.939604 0.107616 -0.324906 0.940038 0.107802 -0.323584 0.939692 0.0689303 -0.335003 0.94538 0.0462871 -0.322668 0.939664 0.0697661 -0.33491 0.940224 0.050353 -0.336813 0.939493 0.0487771 -0.339077 0.939105 0.0492324 -0.340086 0.945482 0.0462415 -0.322376 0.93972 0.0692541 -0.334858 0.939677 0.0691666 -0.334998 0.941269 0.0699002 -0.330343 0.932885 0.0445509 -0.357408 0.943348 0.0547723 -0.327253 0.942112 0.0534226 -0.331015 0.942216 0.071573 -0.327272 0.942759 0.0724578 -0.325509 0.940603 0.0696724 -0.332284 0.939643 0.0827901 -0.33199 0.939752 0.086705 -0.330679 0.931685 -0.0449335 -0.360478 0.94119 -0.0464638 -0.334669 0.939497 -0.0487722 -0.339067 0.93972 -0.0692472 -0.334859 0.939649 -0.0693551 -0.335038 0.939105 -0.0492324 -0.340086 0.94548 -0.0462421 -0.32238 0.945381 -0.0462866 -0.322665 0.939605 -0.069266 -0.335179 0.940012 -0.0684956 -0.334194 0.944298 -0.118194 -0.307136 0.944185 -0.118305 -0.30744 0.939696 -0.107821 -0.324572 0.939682 -0.10764 -0.324671 0.939732 -0.107473 -0.324583 0.93966 -0.106944 -0.324964 0.940126 -0.120553 -0.318794 0.941515 -0.115736 -0.316472 0.942454 -0.113101 -0.314625 0.9428 -0.112155 -0.313927 0.936862 -0.127119 -0.325777 0.940303 -0.102202 -0.32463 0.940754 -0.100038 -0.323998 0.941064 -0.0986476 -0.323523 0.942087 -0.0947392 -0.321708 0.941623 -0.0960641 -0.322674 0.940189 -0.0900524 -0.328534 0.939772 -0.0868808 -0.330577 0.939691 -0.0846355 -0.331387 0.939623 -0.0702271 -0.334929 0.943785 -0.0739664 -0.322179 0.941649 -0.0707745 -0.329073 0.946022 -0.198317 -0.256345 0.939618 -0.227534 -0.255629 0.940004 -0.226434 -0.255185 0.941427 -0.203509 -0.268885 0.939398 -0.208206 -0.272364 0.964078 -0.146646 -0.221468 0.939001 -0.21079 -0.271744 0.946109 -0.19816 -0.256147 0.939734 -0.227328 -0.255385 0.939652 -0.227538 -0.255501 0.943053 -0.255783 -0.212665 0.942937 -0.256031 -0.212881 0.939703 -0.255654 -0.227153 0.939688 -0.255532 -0.227355 0.939731 -0.25537 -0.227361 0.939665 -0.255125 -0.227904 0.940008 -0.261091 -0.219581 0.94091 -0.257005 -0.220538 0.941559 -0.25451 -0.22066 0.942471 -0.251052 -0.22073 0.938637 -0.263193 -0.222913 0.939789 -0.249276 -0.23379 0.939883 -0.248235 -0.23452 0.939929 -0.234704 -0.247888 0.939663 -0.233158 -0.25034 0.939761 -0.220926 -0.260846 0.942022 -0.220659 -0.252794 0.924377 -0.22167 -0.310468 0.940267 -0.245303 -0.236059 0.941321 -0.24025 -0.237054 0.94208 -0.237155 -0.237156 0.941395 -0.237071 -0.239943 0.940295 -0.236146 -0.245114 0.939903 -0.324801 -0.105295 0.940421 -0.32455 -0.101366 0.939678 -0.335031 -0.0689855 0.941624 -0.330996 -0.0615354 0.939658 -0.334903 -0.069876 0.939672 -0.335029 -0.0690889 0.939731 -0.334835 -0.06921 0.941749 -0.330654 -0.0614583 0.939552 -0.336556 -0.0630175 0.939673 -0.336287 -0.0626573 0.939873 -0.335439 -0.0641809 0.940321 -0.333685 -0.0667177 0.940697 -0.332355 -0.0680353 0.940851 -0.331816 -0.0685353 0.941411 -0.329887 -0.0701491 0.939642 -0.331991 -0.0827906 0.940602 -0.332284 -0.0696726 0.94276 -0.325506 -0.0724594 0.942217 -0.327267 -0.0715761 0.939752 -0.330678 -0.0867089 0.94016 -0.328672 -0.0898589 0.941583 -0.322779 -0.0960964 0.942158 -0.321577 -0.094483 0.941183 -0.323315 -0.098194 0.939687 -0.324079 -0.109367 0.93975 -0.324516 -0.107512 0.939635 -0.324852 -0.107506 0.939659 -0.324235 -0.109144 0.940393 -0.32216 -0.108968 0.94025 -0.322553 -0.109043 0.939607 -0.324901 -0.107598 0.940066 -0.323505 -0.107795 0.939598 -0.341987 -0.0141448 0.938903 -0.343817 -0.0158192 0.940223 -0.337945 -0.0421243 0.942586 -0.332124 -0.0350037 0.940989 -0.335883 -0.0414942 0.940251 -0.337373 -0.0458999 0.940522 -0.335352 -0.054384 0.939678 -0.337934 -0.0529697 0.939805 -0.33757 -0.053038 0.939974 -0.337778 -0.0485265 0.939848 -0.337905 -0.0500624 0.939688 -0.337871 -0.0531955 0.940103 -0.336531 -0.054345 0.940782 -0.33463 -0.0543291 0.939838 -0.337525 -0.0527388 0.939735 -0.337814 -0.0527184 0.939753 -0.324455 -0.107676 0.939691 -0.324052 -0.10941 0.939599 -0.318863 -0.12442 0.938046 -0.320037 -0.132839 0.940362 -0.305611 -0.149404 0.939671 -0.304036 -0.156782 0.939599 -0.294035 -0.175207 0.939163 -0.293973 -0.177631 0.939988 -0.277692 -0.198268 0.939625 -0.277275 -0.20056 0.939634 -0.263026 -0.218873 0.939425 -0.263271 -0.219475 0.94363 -0.20671 -0.258524 0.939371 -0.208891 -0.27193 0.939599 -0.175207 -0.294036 0.938156 -0.171258 -0.30089 0.940362 -0.149404 -0.305611 0.939667 -0.144089 -0.310264 0.939574 -0.122822 -0.319555 0.939276 -0.12283 -0.320428 0.942918 -0.0544555 -0.328542 0.939477 -0.0495778 -0.339005 0.939599 -0.0141448 -0.341986 0.941836 -0.025199 -0.335128 0.934773 0.0146807 -0.354943 0.940342 0 -0.340232 0.93969 0.0256455 -0.341066 0.942123 0.113882 -0.315333 0.939562 0.122085 -0.319873 0.939599 0.150328 -0.3075 0.940951 0.142595 -0.307048 0.937335 0.178356 -0.29932 0.939486 0.169464 -0.297739 0.939391 0.208221 -0.272376 0.964079 0.146644 -0.221466 0.939001 0.21079 -0.271744 0.946111 0.198156 -0.256141 0.939727 0.227368 -0.255377 0.939686 0.227363 -0.255533 0.941325 0.255304 -0.220743 0.939625 0.262531 -0.219504 0.939599 0.278563 -0.19889 0.940026 0.276381 -0.199913 0.939068 0.295285 -0.175952 0.939569 0.293022 -0.177057 0.939599 0.3075 -0.150327 0.941047 0.300655 -0.155039 0.937104 0.325173 -0.126883 0.939476 0.316439 -0.131345 0.939691 0.324054 -0.109404 0.939659 0.324234 -0.109147 0 -0.995734 -0.0922685 0 -0.995734 -0.0922685 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.18375 -0.982973 0 -0.18375 -0.982973 0 0 -1 0 0 -1 0 0.18375 -0.982973 0 0.18375 -0.982973 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.798017 -0.602634 0 0.798017 -0.602634 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.961825 -0.273664 0 0.961825 -0.273664 0 0.995734 -0.0922682 0 0.995734 -0.0922682 0 -0.995734 -0.0922685 0 -0.995734 -0.0922685 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.18375 -0.982973 0 -0.18375 -0.982973 0 0 -1 0 0 -1 0 0.18375 -0.982973 0 0.18375 -0.982973 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.961825 -0.273664 0 0.961825 -0.273664 0 0.995734 -0.0922682 0 0.995734 -0.0922682 0 -0.995185 -0.0980171 0 -0.995185 -0.0980171 0 -0.95694 -0.290285 0 -0.95694 -0.290285 0 -0.881921 -0.471397 0 -0.881921 -0.471397 0 -0.77301 -0.634393 0 -0.77301 -0.634393 0 -0.634393 -0.77301 0 -0.634393 -0.77301 0 -0.471397 -0.881921 0 -0.471397 -0.881921 0 -0.290285 -0.95694 0 -0.290285 -0.95694 0 -0.0980173 -0.995185 0 -0.0980173 -0.995185 0 0.0980173 -0.995185 0 0.0980173 -0.995185 0 0.290285 -0.95694 0 0.290285 -0.95694 0 0.471396 -0.881921 0 0.471396 -0.881921 0 0.634393 -0.77301 0 0.634393 -0.77301 0 0.773011 -0.634393 0 0.773011 -0.634393 0 0.881921 -0.471397 0 0.881921 -0.471397 0 0.95694 -0.290284 0 0.95694 -0.290284 0 0.995185 -0.0980173 0 0.995185 -0.0980173 0 0.977764 -0.209708 0 0.985595 -0.169124 0.0112203 0.996132 -0.0871503 0.100448 0.987302 -0.123067 0 0.999146 -0.041325 0.0844684 0.955002 -0.284316 0.0211928 0.965709 -0.258761 0 0.942794 -0.333375 0 0.851919 -0.523673 0 0.872832 -0.48802 0.0299153 0.905902 -0.422429 0.0696542 0.896209 -0.43813 0 0.928213 -0.37205 0.0560286 0.81257 -0.580164 0.0373876 0.818579 -0.573175 0 0.777724 -0.628606 0 0.628606 -0.777724 0 0.660209 -0.751082 0.0436108 0.706434 -0.706434 0.0436116 0.706434 -0.706434 0 0.751083 -0.660208 0.0324142 0.580772 -0.813421 0.0485864 0.572899 -0.818185 0 0.523673 -0.851919 0 0.37205 -0.928213 0.0523166 0.422039 -0.905067 0.0224494 0.439086 -0.898165 0 0.48802 -0.872833 0 0.209708 -0.977764 0.0548026 0.25843 -0.964474 0.0137223 0.28531 -0.958337 0 0.333373 -0.942795 0 -0.0413255 -0.999146 0 0.0413255 -0.999146 0.056044 0.087019 -0.994629 0.00623854 0.12369 -0.992301 0 0.169123 -0.985595 0.100448 -0.123067 -0.987302 0.0112201 -0.0871505 -0.996132 0 -0.169124 -0.985595 0 -0.333373 -0.942795 0.0211923 -0.258761 -0.965709 0.0844702 -0.284317 -0.955002 0 -0.209708 -0.977764 0 -0.523673 -0.851919 0 -0.488019 -0.872833 0.0299147 -0.422429 -0.905902 0.0696542 -0.43813 -0.896209 0 -0.37205 -0.928213 0.0560288 -0.580164 -0.81257 0.0373872 -0.573176 -0.818579 0 -0.628606 -0.777724 0 -0.777722 -0.628608 0 -0.751083 -0.660208 0.0436112 -0.706434 -0.706434 0.0436107 -0.706434 -0.706434 0 -0.660209 -0.751082 0.032416 -0.813421 -0.580771 0.048587 -0.818185 -0.572899 0 -0.85192 -0.523673 0 -0.928214 -0.372047 0.0523191 -0.905067 -0.422039 0.0224495 -0.898164 -0.439087 0 -0.872832 -0.488021 0 -0.985593 -0.169136 0 -0.977764 -0.209709 0.0548011 -0.964474 -0.25843 0.0137258 -0.958338 -0.285307 0 -0.942792 -0.333382 0.00624038 -0.992301 -0.12369 0.0560453 -0.994629 -0.0870193 0 -0.999146 -0.0413248 0 -0.996195 -0.0871558 0 -0.996195 -0.0871558 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.906308 -0.422618 0 -0.906308 -0.422618 0 -0.819152 -0.573576 0 -0.819152 -0.573576 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.573576 -0.819152 0 -0.573576 -0.819152 0 -0.422618 -0.906308 0 -0.422618 -0.906308 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.0871559 -0.996195 0 -0.0871559 -0.996195 0 0.0871559 -0.996195 0 0.0871559 -0.996195 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.422618 -0.906308 0 0.422618 -0.906308 0 0.573576 -0.819152 0 0.573576 -0.819152 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.819152 -0.573576 0 0.819152 -0.573576 0 0.906308 -0.422618 0 0.906308 -0.422618 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.996195 -0.0871555 0 0.996195 -0.0871555 0 0.995734 -0.0922684 0 0.995734 -0.0922684 0 0.961826 -0.273663 0 0.961826 -0.273663 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.18375 -0.982973 0 0.18375 -0.982973 0 0 -1 0 0 -1 0 -0.18375 -0.982973 0 -0.18375 -0.982973 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.895164 -0.445738 0 -0.895164 -0.445738 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.995734 -0.0922682 0 -0.995734 -0.0922682 0 0.995185 -0.0980172 0 0.995185 -0.0980172 0 0.95694 -0.290285 0 0.95694 -0.290285 0 0.881921 -0.471397 0 0.881921 -0.471397 0 0.77301 -0.634393 0 0.77301 -0.634393 0 0.634393 -0.77301 0 0.634393 -0.77301 0 0.471397 -0.881921 0 0.471397 -0.881921 0 0.290285 -0.95694 0 0.290285 -0.95694 0 0.0980172 -0.995185 0 0.0980172 -0.995185 0 -0.0980172 -0.995185 0 -0.0980172 -0.995185 0 -0.290285 -0.95694 0 -0.290285 -0.95694 0 -0.471397 -0.881921 0 -0.471397 -0.881921 0 -0.634393 -0.77301 0 -0.634393 -0.77301 0 -0.77301 -0.634393 0 -0.77301 -0.634393 0 -0.881921 -0.471397 0 -0.881921 -0.471397 0 -0.95694 -0.290285 0 -0.95694 -0.290285 0 -0.995185 -0.0980168 0 -0.995185 -0.0980168 0 -0.995185 -0.0980172 0 -0.995185 -0.0980172 0 -0.95694 -0.290285 0 -0.95694 -0.290285 0 -0.881921 -0.471397 0 -0.881921 -0.471397 0 -0.77301 -0.634393 0 -0.77301 -0.634393 0 -0.634393 -0.77301 0 -0.634393 -0.77301 0 -0.471397 -0.881921 0 -0.471397 -0.881921 0 -0.290285 -0.95694 0 -0.290285 -0.95694 0 -0.0980172 -0.995185 0 -0.0980172 -0.995185 0 0.0980172 -0.995185 0 0.0980172 -0.995185 0 0.290285 -0.95694 0 0.290285 -0.95694 0 0.471397 -0.881921 0 0.471397 -0.881921 0 0.634393 -0.77301 0 0.634393 -0.77301 0 0.773011 -0.634393 0 0.773011 -0.634393 0 0.881921 -0.471397 0 0.881921 -0.471397 0 0.95694 -0.290284 0 0.95694 -0.290284 0 0.995185 -0.0980172 0 0.995185 -0.0980172 0.202048 0.978539 0.0404727 0.202048 0.978539 0.0404727 0.202048 0.971855 0.121141 0.202048 0.971855 0.121142 0.202211 0.965234 0.165631 0.148207 0.966966 0.207392 0.202046 0.958532 0.200983 0.202046 0.938661 0.279451 0.202047 0.938661 0.279451 0.202204 0.923319 0.326488 0.0930114 0.924189 0.370437 0.202046 0.912378 0.356011 0.202046 0.879863 0.430139 0.202047 0.879862 0.430139 0.202195 0.854804 0.47794 0.0930804 0.855325 0.509663 0.202143 0.834332 0.512862 0.202051 0.797063 0.569092 0.202046 0.797064 0.569093 0.202179 0.761663 0.615625 0.0806841 0.760596 0.644192 0.202161 0.735574 0.646576 0.202047 0.692523 0.692524 0.20205 0.692523 0.692523 0.202164 0.646577 0.735573 0.0806826 0.644192 0.760596 0.202183 0.615624 0.761662 0.20205 0.569092 0.797063 0.202051 0.569092 0.797063 0.202143 0.512863 0.834332 0.0930814 0.509663 0.855324 0.202198 0.47794 0.854804 0.202051 0.430138 0.879862 0.202044 0.430138 0.879863 0.202109 0.364372 0.909057 0.117737 0.36098 0.925112 0.202211 0.326486 0.923319 0.202054 0.279451 0.938659 0.202048 0.279451 0.938661 0.202083 0.205382 0.957591 0.1543 0.202758 0.966996 0.202217 0.165629 0.965233 0.202054 0.121141 0.971853 0.202049 0.121141 0.971854 0.20205 0.0404732 0.978539 0.202042 0.0404726 0.97854 0.202042 -0.0404733 0.97854 0.20205 -0.0404725 0.978539 0.202049 -0.121141 0.971854 0.202053 -0.121141 0.971854 0.202216 -0.16563 0.965233 0.14821 -0.207392 0.966965 0.202046 -0.200984 0.958532 0.202045 -0.279452 0.938661 0.202054 -0.27945 0.93866 0.202211 -0.326486 0.923319 0.093014 -0.370437 0.924189 0.202041 -0.356012 0.912379 0.20204 -0.430139 0.879864 0.202047 -0.430138 0.879863 0.202194 -0.477939 0.854805 0.0930751 -0.509662 0.855325 0.202143 -0.512863 0.834332 0.202051 -0.569093 0.797063 0.20205 -0.569093 0.797063 0.202183 -0.615624 0.761662 0.0806799 -0.644193 0.760596 0.202158 -0.646578 0.735574 0.202044 -0.692524 0.692524 0.20205 -0.692523 0.692523 0.202164 -0.735574 0.646576 0.0806897 -0.760596 0.644192 0.202176 -0.761662 0.615627 0.202043 -0.797065 0.569093 0.202044 -0.797065 0.569093 0.202135 -0.834334 0.512863 0.0930844 -0.855324 0.509663 0.202198 -0.854803 0.477941 0.202051 -0.879861 0.430139 0.202042 -0.879863 0.43014 0.202108 -0.909059 0.364369 0.117757 -0.92511 0.360979 0.202204 -0.923317 0.326496 0.850924 0.52484 0.0217075 0.850924 0.524841 0.0217076 0.850924 0.521255 0.0649745 0.850924 0.521255 0.0649743 0.850924 0.514109 0.107797 0.850924 0.514109 0.107797 0.850924 0.503451 0.149884 0.850925 0.50345 0.149884 0.850925 0.489353 0.190946 0.850924 0.489355 0.190947 0.850924 0.471915 0.230705 0.850924 0.471915 0.230705 0.850924 0.451252 0.268887 0.850924 0.451251 0.268887 0.850924 0.427506 0.305233 0.850924 0.427506 0.305233 0.850924 0.40084 0.339494 0.850924 0.400839 0.339494 0.850924 0.371435 0.371435 0.850925 0.371434 0.371434 0.850925 0.339493 0.400838 0.850923 0.339495 0.400841 0.850923 0.305234 0.427507 0.850926 0.305231 0.427503 0.850926 0.268886 0.451248 0.850923 0.268888 0.451253 0.850923 0.230706 0.471916 0.850923 0.230706 0.471917 0.850923 0.190948 0.489357 0.850923 0.190947 0.489356 0.850923 0.149884 0.503453 0.850924 0.149884 0.50345 0.850924 0.107797 0.514108 0.850924 0.107797 0.51411 0.850924 0.0649747 0.521255 0.850922 0.0649748 0.521258 0.850922 0.0217073 0.524843 0.850926 0.0217076 0.524837 0.850926 -0.0217071 0.524837 0.850922 -0.0217079 0.524843 0.850922 -0.064975 0.521258 0.850924 -0.0649745 0.521255 0.850924 -0.107797 0.51411 0.850925 -0.107797 0.514107 0.850925 -0.149883 0.503449 0.850922 -0.149885 0.503454 0.850922 -0.190948 0.489358 0.850923 -0.190947 0.489355 0.850924 -0.230705 0.471915 0.850923 -0.230706 0.471916 0.850923 -0.268889 0.451253 0.850925 -0.268887 0.45125 0.850925 -0.305232 0.427505 0.850923 -0.305234 0.427507 0.850923 -0.339495 0.400841 0.850922 -0.339496 0.400842 0.850921 -0.371438 0.371438 0.850925 -0.371434 0.371434 0.850925 -0.400838 0.339493 0.850925 -0.400838 0.339493 0.850925 -0.427504 0.305232 0.850922 -0.427509 0.305235 0.850922 -0.451255 0.268889 0.850927 -0.451247 0.268885 0.850927 -0.47191 0.230703 0.850927 -0.47191 0.230703 0.850927 -0.489349 0.190945 0.850918 -0.489364 0.190949 0.850917 -0.503462 0.149886 0.850929 -0.503443 0.149883 0.850929 -0.5141 0.107795 0.850932 -0.514097 0.107795 0.573242 0.818686 0.0338611 0.573243 0.818685 0.033861 0.573243 0.813093 0.101352 0.573242 0.813093 0.101352 0.573242 0.801947 0.168151 0.573244 0.801946 0.16815 0.573244 0.785321 0.2338 0.573242 0.785322 0.233801 0.573242 0.763333 0.297853 0.573245 0.763331 0.297852 0.573245 0.736127 0.359871 0.573243 0.736129 0.359872 0.573242 0.703897 0.419431 0.573242 0.703897 0.419432 0.573241 0.666856 0.476127 0.573247 0.666854 0.476124 0.573247 0.625258 0.529566 0.573243 0.62526 0.529568 0.573243 0.579393 0.579393 0.573243 0.579393 0.579393 0.573243 0.529568 0.62526 0.573247 0.529567 0.625258 0.573247 0.476124 0.666853 0.573239 0.476127 0.666859 0.573239 0.419433 0.703899 0.573242 0.419432 0.703896 0.573243 0.359871 0.736129 0.573245 0.359871 0.736127 0.573246 0.297853 0.76333 0.573242 0.297853 0.763333 0.573242 0.2338 0.785322 0.573246 0.2338 0.78532 0.573246 0.168151 0.801944 0.573239 0.168151 0.801949 0.573238 0.101352 0.813096 0.573246 0.101352 0.813091 0.573246 0.0338609 0.818683 0.573242 0.0338606 0.818686 0.573242 -0.033861 0.818686 0.573246 -0.0338604 0.818683 0.573246 -0.101351 0.813091 0.573238 -0.101353 0.813096 0.573239 -0.168152 0.801949 0.573244 -0.16815 0.801945 0.573244 -0.2338 0.785321 0.573244 -0.2338 0.785321 0.573244 -0.297853 0.763331 0.573248 -0.297852 0.763329 0.573248 -0.359869 0.736126 0.573245 -0.35987 0.736127 0.573246 -0.41943 0.703895 0.573239 -0.419433 0.703899 0.573239 -0.476128 0.666858 0.573247 -0.476124 0.666854 0.573247 -0.529567 0.625258 0.573251 -0.529564 0.625256 0.573252 -0.579388 0.579389 0.573243 -0.579393 0.579393 0.573243 -0.62526 0.529568 0.573247 -0.625258 0.529567 0.573247 -0.666854 0.476124 0.573249 -0.666853 0.476123 0.57325 -0.703892 0.419429 0.573237 -0.7039 0.419433 0.573237 -0.736132 0.359874 0.573237 -0.736132 0.359874 0.573236 -0.763337 0.297855 0.573242 -0.763333 0.297854 0.573242 -0.785322 0.2338 0.573239 -0.785324 0.2338 0.573239 -0.801949 0.16815 0.573238 -0.80195 0.16815 0.202047 -0.938661 0.279449 0.202065 -0.938657 0.27945 0.202101 -0.957587 0.205382 0.154293 -0.966997 0.202757 0.202192 -0.965236 0.165643 0.85092 -0.521262 0.0649745 0.850932 -0.521242 0.064974 0.573259 -0.813082 0.101352 0.573238 -0.813097 0.101352 0.202024 -0.97186 0.121142 0.202028 -0.971859 0.121142 0.850921 -0.524845 0.021708 0.85092 -0.524847 0.0217079 0.573255 -0.818677 0.0338608 0.573259 -0.818674 0.0338611 0.202033 -0.978542 0.0404734 0.202024 -0.978544 0.0404727 0 0.999048 -0.0436192 0 0.999048 -0.0436192 0 0.991445 -0.130526 0 0.991445 -0.130526 0 0.976296 -0.21644 0 0.976296 -0.21644 0 0.953717 -0.300707 0 0.953717 -0.300707 0 0.92388 -0.382683 0 0.92388 -0.382683 0 0.887011 -0.461749 0 0.887011 -0.461749 0 0.843392 -0.537299 0 0.843392 -0.537299 0 0.793353 -0.608762 0 0.793353 -0.608762 0 0.737277 -0.67559 0 0.737277 -0.67559 0 0.675591 -0.737277 0 0.675591 -0.737277 0 0.608761 -0.793353 0 0.608761 -0.793353 0 0.537299 -0.843392 0 0.537299 -0.843392 0 0.461749 -0.887011 0 0.461749 -0.887011 0 0.382683 -0.92388 0 0.382683 -0.92388 0 0.300706 -0.953717 0 0.300706 -0.953717 0 0.216439 -0.976296 0 0.216439 -0.976296 0 0.130527 -0.991445 0 0.130527 -0.991445 0 0.0436192 -0.999048 0 0.0436192 -0.999048 0 -0.0436192 -0.999048 0 -0.0436192 -0.999048 0 -0.130527 -0.991445 0 -0.130527 -0.991445 0 -0.216439 -0.976296 0 -0.216439 -0.976296 0 -0.300706 -0.953717 0 -0.300706 -0.953717 0 -0.382683 -0.92388 0 -0.382683 -0.92388 0 -0.461749 -0.887011 0 -0.461749 -0.887011 0 -0.537299 -0.843392 0 -0.537299 -0.843392 0 -0.608761 -0.793353 0 -0.608761 -0.793353 0 -0.675591 -0.737277 0 -0.675591 -0.737277 0 -0.737277 -0.67559 0 -0.737277 -0.67559 0 -0.793353 -0.608762 0 -0.793353 -0.608762 0 -0.843391 -0.5373 0 -0.843391 -0.5373 0 -0.887011 -0.461749 0 -0.887011 -0.461749 0 -0.92388 -0.382683 0 -0.92388 -0.382683 0 -0.953717 -0.300706 0 -0.953717 -0.300706 0 -0.976296 -0.21644 0 -0.976296 -0.21644 0 -0.991445 -0.130526 0 -0.991445 -0.130526 0 -0.999048 -0.0436194 0 -0.999048 -0.0436194 -0.793116 -0.608491 -0.0265672 -0.896677 0.442264 -0.01931 -0.608426 0.792855 -0.0346173 -0.19486 0.979898 -0.0427831 -0.442008 0.896157 -0.0391276 -0.258613 0.964994 -0.0436567 -0.258597 0.957721 -0.126085 -0.258572 0.957728 -0.126087 -0.258572 0.943094 -0.209079 -0.258566 0.943096 -0.20908 -0.258567 0.921284 -0.29048 -0.258545 0.92129 -0.290482 -0.258547 0.892466 -0.369673 -0.258591 0.892456 -0.369667 -0.258591 0.856841 -0.446043 -0.258605 0.856838 -0.446041 -0.258604 0.814703 -0.519022 -0.258607 0.814702 -0.519021 -0.258608 0.766365 -0.588053 -0.25858 0.766371 -0.588058 -0.258581 0.712202 -0.652613 -0.25858 0.712202 -0.652613 -0.258581 0.652613 -0.712202 -0.258613 0.652608 -0.712195 -0.258612 0.588053 -0.766364 -0.258594 0.588055 -0.766368 -0.258595 0.519024 -0.814704 -0.258579 0.519026 -0.814708 -0.25858 0.446044 -0.856844 -0.258616 0.44604 -0.856835 -0.258616 0.369665 -0.892449 -0.258588 0.369667 -0.892456 -0.258588 0.290478 -0.921279 -0.258606 0.290477 -0.921274 -0.258608 0.209077 -0.943085 -0.258596 0.209077 -0.943088 -0.258595 0.126087 -0.957722 -0.258596 0.126087 -0.957721 -0.258597 0.0421356 -0.965066 -0.258596 0.0421355 -0.965066 -0.258596 -0.0421356 -0.965066 -0.258597 -0.0421355 -0.965066 -0.258596 -0.126087 -0.957721 -0.258592 -0.126087 -0.957722 -0.258591 -0.209078 -0.943089 -0.258608 -0.209077 -0.943085 -0.258606 -0.290476 -0.921274 -0.258588 -0.290478 -0.921279 -0.258588 -0.369668 -0.892456 -0.258616 -0.369664 -0.892449 -0.258616 -0.44604 -0.856835 -0.25859 -0.446044 -0.856841 -0.258591 -0.519024 -0.814705 -0.258607 -0.519022 -0.814702 -0.258608 -0.588052 -0.766366 -0.258598 -0.588054 -0.766368 -0.258598 -0.652611 -0.712198 -0.258604 -0.652609 -0.712197 -0.258605 -0.712197 -0.652609 -0.258598 -0.712199 -0.65261 -0.258598 -0.766368 -0.588054 -0.258608 -0.766365 -0.588053 -0.258607 -0.814701 -0.519022 -0.258604 -0.814702 -0.519022 -0.258605 -0.856838 -0.446041 -0.258601 -0.856839 -0.446042 -0.258602 -0.892453 -0.369666 -0.258599 -0.892454 -0.369666 -0.258599 -0.921276 -0.290477 -0.258588 -0.921279 -0.290478 -0.258588 -0.94309 -0.209078 -0.258594 -0.943088 -0.209078 -0.258594 -0.957722 -0.126086 -0.258597 -0.957721 -0.126086 -0.258597 -0.965066 -0.0421358 -0.258596 -0.965066 -0.0421357 -0.608366 -0.792901 -0.0346189 -0.706815 -0.706633 -0.0328898 -0.706772 -0.701389 -0.0923396 -0.706774 -0.701387 -0.0923394 -0.706774 -0.690671 -0.153118 -0.706775 -0.69067 -0.153118 -0.706774 -0.674697 -0.212731 -0.706772 -0.674699 -0.212732 -0.706772 -0.653591 -0.270726 -0.706774 -0.653589 -0.270726 -0.706774 -0.627506 -0.326659 -0.70677 -0.62751 -0.326661 -0.70677 -0.596651 -0.380109 -0.706774 -0.596649 -0.380107 -0.706774 -0.56125 -0.430662 -0.706772 -0.561251 -0.430663 -0.706772 -0.52158 -0.477941 -0.706767 -0.521584 -0.477944 -0.706767 -0.477945 -0.521584 -0.706772 -0.477941 -0.52158 -0.706772 -0.430663 -0.561251 -0.706778 -0.430659 -0.561246 -0.706779 -0.380105 -0.596645 -0.70677 -0.380109 -0.596651 -0.70677 -0.326661 -0.62751 -0.706766 -0.326663 -0.627514 -0.706766 -0.270729 -0.653596 -0.70678 -0.270723 -0.653584 -0.706779 -0.212729 -0.674692 -0.706774 -0.212731 -0.674697 -0.706775 -0.153118 -0.69067 -0.706769 -0.153119 -0.690675 -0.706769 -0.0923403 -0.701392 -0.706774 -0.0923395 -0.701388 -0.706773 -0.030858 -0.706768 -0.70677 -0.0308583 -0.70677 -0.70677 0.0308582 -0.70677 -0.706773 0.0308582 -0.706768 -0.706774 0.0923398 -0.701388 -0.706767 0.0923403 -0.701394 -0.706767 0.153119 -0.690678 -0.706777 0.153118 -0.690667 -0.706778 0.21273 -0.674693 -0.706779 0.212729 -0.674692 -0.70678 0.270724 -0.653583 -0.706761 0.27073 -0.653601 -0.706761 0.326665 -0.627519 -0.70677 0.326661 -0.62751 -0.70677 0.380109 -0.596651 -0.706785 0.380102 -0.596639 -0.706786 0.430655 -0.56124 -0.706765 0.430667 -0.561257 -0.706764 0.477946 -0.521586 -0.706775 0.477939 -0.521578 -0.706776 0.521577 -0.477938 -0.706772 0.52158 -0.477941 -0.706772 0.561251 -0.430663 -0.706778 0.561246 -0.430659 -0.706779 0.596645 -0.380104 -0.70676 0.59666 -0.380114 -0.70676 0.627519 -0.326666 -0.706769 0.627511 -0.326661 -0.706768 0.653594 -0.270728 -0.706789 0.653575 -0.27072 -0.706789 0.674683 -0.212727 -0.706775 0.674696 -0.212732 -0.706775 0.69067 -0.153118 -0.706815 0.690631 -0.153107 -0.706815 0.701346 -0.0923331 -0.706772 0.701389 -0.0923407 -0.706815 0.706634 -0.0328892 -0.793072 0.608548 -0.0265702 -0.980765 0.195007 -0.00851395 -0.965886 0.25865 -0.0128224 -0.96587 0.25681 -0.0338098 -0.965868 0.256819 -0.0338112 -0.965868 0.252895 -0.0560656 -0.965875 0.25287 -0.0560593 -0.965875 0.247022 -0.0778854 -0.965869 0.247042 -0.0778925 -0.965869 0.239314 -0.0991269 -0.965869 0.239313 -0.0991266 -0.965869 0.229763 -0.119607 -0.965873 0.229752 -0.119601 -0.965872 0.218454 -0.13917 -0.965871 0.218458 -0.139173 -0.965871 0.205497 -0.157683 -0.965872 0.205495 -0.157682 -0.965872 0.19097 -0.174992 -0.965871 0.190973 -0.174994 -0.965871 0.174994 -0.190973 -0.96587 0.174995 -0.190974 -0.96587 0.157685 -0.205499 -0.965869 0.157688 -0.205504 -0.965869 0.139177 -0.218465 -0.965872 0.139172 -0.218455 -0.965872 0.119602 -0.229754 -0.965872 0.119603 -0.229754 -0.965872 0.0991232 -0.239305 -0.965871 0.0991243 -0.239307 -0.965871 0.0778902 -0.247036 -0.96587 0.0778906 -0.247038 -0.96587 0.0560636 -0.252886 -0.965871 0.056063 -0.252883 -0.965871 0.0338094 -0.256807 -0.96587 0.0338098 -0.256811 -0.96587 0.0112984 -0.25878 -0.965872 0.0112984 -0.258775 -0.965872 -0.0112982 -0.258775 -0.96587 -0.0112986 -0.258779 -0.96587 -0.0338097 -0.256809 -0.965871 -0.0338093 -0.256807 -0.965871 -0.0560628 -0.252883 -0.96587 -0.0560637 -0.252886 -0.96587 -0.0778906 -0.247038 -0.96587 -0.0778907 -0.247038 -0.96587 -0.0991253 -0.239309 -0.965871 -0.0991241 -0.239307 -0.965871 -0.119604 -0.229757 -0.96587 -0.119605 -0.229759 -0.96587 -0.139175 -0.218461 -0.96587 -0.139176 -0.218462 -0.96587 -0.157686 -0.205501 -0.965872 -0.157682 -0.205496 -0.965872 -0.174992 -0.190971 -0.96587 -0.174997 -0.190976 -0.96587 -0.190976 -0.174997 -0.96587 -0.190974 -0.174995 -0.96587 -0.205499 -0.157685 -0.96587 -0.205499 -0.157685 -0.96587 -0.21846 -0.139174 -0.965871 -0.218458 -0.139173 -0.965871 -0.229756 -0.119604 -0.96587 -0.22976 -0.119606 -0.96587 -0.23931 -0.0991256 -0.96587 -0.239308 -0.0991249 -0.96587 -0.247037 -0.0778905 -0.965871 -0.247036 -0.0778901 -0.965871 -0.252884 -0.0560631 -0.965871 -0.252885 -0.0560631 -0.965871 -0.256808 -0.0338095 -0.965871 -0.256808 -0.0338095 -0.965871 -0.258778 -0.0112985 -0.96587 -0.258779 -0.0112985 0.79298 0.608668 -0.0265755 0.896818 -0.441978 -0.0192971 0.608458 -0.792831 -0.0346158 0.194897 -0.97989 -0.042783 0.441932 -0.896195 -0.0391288 0.258589 -0.965 -0.0436559 0.258573 -0.957727 -0.126087 0.25857 -0.957728 -0.126087 0.25857 -0.943095 -0.209079 0.258564 -0.943096 -0.20908 0.258565 -0.921285 -0.29048 0.258575 -0.921282 -0.290479 0.258575 -0.89246 -0.369669 0.258578 -0.892459 -0.369669 0.258577 -0.856844 -0.446045 0.258581 -0.856843 -0.446044 0.25858 -0.814708 -0.519026 0.258583 -0.814707 -0.519026 0.258584 -0.766371 -0.588057 0.258574 -0.766372 -0.588058 0.258574 -0.712203 -0.652615 0.258581 -0.712202 -0.652613 0.25858 -0.652614 -0.712202 0.258574 -0.652615 -0.712203 0.258574 -0.588058 -0.766373 0.258584 -0.588057 -0.766371 0.258583 -0.519026 -0.814707 0.258567 -0.519027 -0.814711 0.258566 -0.446046 -0.856847 0.258592 -0.446043 -0.85684 0.258592 -0.369668 -0.892455 0.258564 -0.36967 -0.892462 0.258564 -0.290479 -0.921285 0.258582 -0.290478 -0.92128 0.258584 -0.209078 -0.943091 0.258567 -0.209079 -0.943095 0.258568 -0.126088 -0.957729 0.258572 -0.126088 -0.957728 0.258573 -0.0421358 -0.965072 0.258572 -0.0421358 -0.965073 0.258572 0.0421358 -0.965073 0.258573 0.0421358 -0.965072 0.258572 0.126088 -0.957728 0.258571 0.126088 -0.957728 0.258572 0.209079 -0.943094 0.258584 0.209078 -0.943091 0.258582 0.290478 -0.92128 0.258564 0.29048 -0.921285 0.258564 0.369671 -0.892462 0.258592 0.369667 -0.892455 0.258592 0.446042 -0.856841 0.258556 0.446048 -0.856849 0.258555 0.51903 -0.814713 0.258571 0.519027 -0.81471 0.25857 0.588059 -0.766373 0.258588 0.588056 -0.76637 0.258589 0.652611 -0.712201 0.258557 0.652618 -0.712206 0.258556 0.712207 -0.652618 0.258557 0.712207 -0.652618 0.258556 0.766376 -0.588061 0.258584 0.76637 -0.588057 0.258583 0.814707 -0.519025 0.25858 0.814708 -0.519025 0.258581 0.856843 -0.446045 0.258567 0.856847 -0.446046 0.258567 0.892461 -0.369671 0.258523 0.892473 -0.369674 0.258521 0.921296 -0.290484 0.258543 0.92129 -0.290483 0.258542 0.943102 -0.209081 0.258548 0.9431 -0.209081 0.258548 0.957734 -0.126087 0.258573 0.957728 -0.126087 0.258573 0.965072 -0.0421366 0.258549 0.965079 -0.0421361 0.608518 0.792785 -0.0346142 0.706815 0.706634 -0.0328871 0.706772 0.701389 -0.0923388 0.706815 0.701346 -0.092335 0.706815 0.69063 -0.153109 0.706775 0.69067 -0.153116 0.706774 0.674697 -0.212731 0.706789 0.674682 -0.212727 0.706789 0.653575 -0.270721 0.706768 0.653594 -0.270727 0.706769 0.627511 -0.326662 0.70676 0.627519 -0.326666 0.70676 0.59666 -0.380114 0.706779 0.596644 -0.380105 0.706778 0.561246 -0.430659 0.706772 0.561251 -0.430663 0.706772 0.52158 -0.47794 0.706776 0.521577 -0.477938 0.706775 0.477939 -0.521579 0.706764 0.477946 -0.521586 0.706765 0.430668 -0.561257 0.706786 0.430654 -0.561241 0.706785 0.380101 -0.596639 0.70677 0.380109 -0.596651 0.70677 0.32666 -0.62751 0.70676 0.326665 -0.627518 0.706761 0.270731 -0.6536 0.70678 0.270723 -0.653584 0.706779 0.212729 -0.674692 0.706778 0.21273 -0.674693 0.706777 0.153117 -0.690667 0.706767 0.15312 -0.690677 0.706767 0.0923406 -0.701394 0.706774 0.0923395 -0.701388 0.706773 0.030858 -0.706768 0.70677 0.0308583 -0.70677 0.70677 -0.0308582 -0.70677 0.706773 -0.0308582 -0.706768 0.706774 -0.0923397 -0.701388 0.706769 -0.0923401 -0.701393 0.706769 -0.153119 -0.690675 0.706774 -0.153118 -0.69067 0.706774 -0.212731 -0.674697 0.706779 -0.212729 -0.674692 0.70678 -0.270724 -0.653583 0.706766 -0.270728 -0.653596 0.706766 -0.326663 -0.627514 0.70677 -0.326661 -0.62751 0.70677 -0.380109 -0.596651 0.706779 -0.380105 -0.596644 0.706778 -0.430659 -0.561246 0.706772 -0.430662 -0.561251 0.706772 -0.477941 -0.52158 0.706767 -0.477944 -0.521584 0.706767 -0.521584 -0.477944 0.706772 -0.52158 -0.47794 0.706772 -0.561251 -0.430663 0.706774 -0.56125 -0.430662 0.706774 -0.596649 -0.380107 0.70677 -0.596651 -0.380109 0.70677 -0.62751 -0.326661 0.706774 -0.627506 -0.326659 0.706774 -0.653589 -0.270726 0.706772 -0.653591 -0.270726 0.706772 -0.674699 -0.212732 0.706775 -0.674697 -0.212731 0.706775 -0.69067 -0.153118 0.706774 -0.690671 -0.153118 0.706774 -0.701387 -0.0923394 0.706772 -0.701389 -0.0923397 0.706815 -0.706634 -0.0328877 0.793024 -0.60861 -0.0265724 0.980738 -0.195143 -0.00852015 0.965886 -0.258649 -0.0128194 0.965871 -0.256808 -0.0338095 0.965871 -0.256808 -0.0338095 0.965871 -0.252885 -0.0560632 0.965871 -0.252884 -0.0560631 0.965871 -0.247036 -0.07789 0.96587 -0.247037 -0.0778905 0.96587 -0.239308 -0.0991248 0.96587 -0.23931 -0.0991257 0.96587 -0.22976 -0.119606 0.965871 -0.229756 -0.119604 0.965871 -0.218458 -0.139173 0.96587 -0.21846 -0.139174 0.96587 -0.205499 -0.157685 0.96587 -0.205499 -0.157685 0.96587 -0.190974 -0.174995 0.96587 -0.190976 -0.174997 0.96587 -0.174997 -0.190976 0.965872 -0.174993 -0.190971 0.965871 -0.157683 -0.205496 0.96587 -0.157686 -0.205501 0.96587 -0.139176 -0.218462 0.96587 -0.139175 -0.218461 0.96587 -0.119605 -0.229759 0.965871 -0.119604 -0.229757 0.965871 -0.0991242 -0.239307 0.96587 -0.0991252 -0.23931 0.96587 -0.0778907 -0.247038 0.96587 -0.0778906 -0.247038 0.96587 -0.0560636 -0.252886 0.965871 -0.056063 -0.252883 0.965871 -0.0338094 -0.256807 0.965871 -0.0338096 -0.256809 0.96587 -0.0112984 -0.258779 0.965872 -0.0112984 -0.258775 0.965872 0.0112982 -0.258775 0.96587 0.0112986 -0.25878 0.96587 0.0338099 -0.256811 0.965871 0.0338093 -0.256807 0.965871 0.0560628 -0.252883 0.96587 0.0560637 -0.252886 0.96587 0.0778906 -0.247038 0.965871 0.0778901 -0.247036 0.965871 0.0991244 -0.239307 0.965872 0.0991231 -0.239305 0.965872 0.119603 -0.229754 0.965872 0.119602 -0.229754 0.965872 0.139171 -0.218455 0.965869 0.139178 -0.218465 0.965869 0.157689 -0.205504 0.96587 0.157685 -0.205499 0.96587 0.174995 -0.190974 0.965871 0.174994 -0.190973 0.965871 0.190973 -0.174994 0.965872 0.19097 -0.174992 0.965872 0.205495 -0.157682 0.965871 0.205497 -0.157683 0.965871 0.218458 -0.139173 0.965872 0.218454 -0.13917 0.965873 0.229752 -0.119601 0.965869 0.229763 -0.119607 0.965869 0.239313 -0.0991267 0.965869 0.239314 -0.0991269 0.965869 0.247043 -0.0778918 0.965875 0.247022 -0.077886 0.965875 0.25287 -0.0560601 0.965868 0.252895 -0.0560648 0.965868 0.256819 -0.0338109 0.96587 0.25681 -0.0338101 0.96587 0.258779 -0.0112982 0.965875 0.258763 -0.011298 -0.705594 0.705594 -0.0653828 -0.705581 0.705606 -0.0653844 -0.705582 0.681577 -0.193926 -0.70559 0.68157 -0.193923 -0.705589 0.634332 -0.31586 -0.705591 0.63433 -0.315859 -0.705591 0.565491 -0.427038 -0.705582 0.565497 -0.427044 -0.705583 0.477399 -0.523682 -0.705588 0.477396 -0.523678 -0.705588 0.373042 -0.602483 -0.705589 0.373041 -0.602482 -0.705587 0.255984 -0.660771 -0.70559 0.255983 -0.660769 -0.70559 0.130209 -0.696555 -0.705588 0.130209 -0.696557 -0.705587 0 -0.708623 -0.705587 0 -0.708623 -0.705588 -0.130209 -0.696557 -0.70559 -0.130209 -0.696555 -0.70559 -0.255983 -0.660769 -0.705582 -0.255986 -0.660776 -0.705582 -0.373045 -0.602488 -0.705588 -0.373042 -0.602483 -0.705588 -0.477396 -0.523678 -0.705588 -0.477396 -0.523678 -0.705587 -0.565493 -0.427041 -0.705588 -0.565493 -0.42704 -0.705588 -0.634333 -0.31586 -0.705589 -0.634331 -0.31586 -0.705589 -0.68157 -0.193923 -0.705588 -0.681571 -0.193924 -0.705588 -0.705599 -0.0653835 -0.705587 -0.7056 -0.0653836 0.705587 -0.7056 -0.0653836 0.705588 -0.705599 -0.0653835 0.705588 -0.681571 -0.193924 0.705589 -0.68157 -0.193923 0.705589 -0.634332 -0.31586 0.705588 -0.634333 -0.31586 0.705588 -0.565493 -0.42704 0.705587 -0.565493 -0.427041 0.705588 -0.477396 -0.523678 0.705588 -0.477396 -0.523678 0.705588 -0.373042 -0.602483 0.705582 -0.373045 -0.602488 0.705582 -0.255986 -0.660776 0.70559 -0.255983 -0.660769 0.70559 -0.130209 -0.696555 0.705588 -0.130209 -0.696557 0.705587 0 -0.708623 0.705587 0 -0.708623 0.705588 0.130209 -0.696557 0.70559 0.130209 -0.696555 0.70559 0.255983 -0.660769 0.705587 0.255984 -0.660771 0.705589 0.373041 -0.602482 0.705588 0.373042 -0.602483 0.705588 0.477396 -0.523678 0.705583 0.477399 -0.523681 0.705582 0.565498 -0.427044 0.705591 0.56549 -0.427039 0.705591 0.63433 -0.315859 0.705589 0.634331 -0.315859 0.70559 0.68157 -0.193924 0.705582 0.681577 -0.193926 0.705581 0.705606 -0.0653839 0.705594 0.705594 -0.0653832 0 -0.991445 0.130526 0 -0.991445 0.130526 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258814 -0.965927 0 0.258814 -0.965927 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.991442 0.130545 0 -0.991442 0.130545 0 -0.995793 0.0916275 0.0230728 -0.971083 0.237625 0.0179389 -0.751719 0.659239 0.00299063 -0.792407 0.609985 -0.00272114 -0.941899 0.335884 0.00102426 -0.206938 0.978354 0.0151659 -0.355761 0.934454 0.0168071 -0.362387 0.931876 -0.00290407 -0.537061 0.843539 0.00305551 -0.655781 0.754945 -0.00245922 0.0178274 0.999838 0.0182313 0.10885 0.993891 -0.000101903 0.266284 0.963894 0.000132009 0.43885 0.89856 0.0217744 0.555439 0.831272 -0.000127303 0.639693 0.76863 5.1018e-05 0.772826 0.634618 0.0174318 0.876594 0.480915 0 0.901294 0.433207 0 -0.990006 0.141022 0.019092 -0.972193 0.2334 0.00602296 -0.945172 0.326516 0.00266333 -0.66842 0.743779 0.0195372 -0.775122 0.631509 0.0137661 -0.760334 0.649387 -3.08793e-05 -0.864787 0.502139 2.54046e-05 -0.91102 0.412363 -0.00491871 -0.484184 0.874952 0.018559 -0.382617 0.923721 -0.000114274 -0.242875 0.970058 0.000122704 -0.0605025 0.998168 0.0205993 0.0784427 0.996706 -0.000124298 0.173939 0.984757 4.39848e-05 0.35604 0.934471 0.0160163 0.522431 0.852531 0 0.563935 0.825819 0 -0.999578 0.0290656 0.00524497 -0.987321 0.158651 0.017693 -0.973725 0.227038 0.00601012 -0.950772 0.309832 -0.00774086 -0.856578 0.515959 0.0184393 -0.772876 0.634289 -0.000128148 -0.685913 0.727684 0.00010509 -0.540522 0.84133 0.0186161 -0.412635 0.910706 -0.0106292 -0.291364 0.956553 0.0138944 0.0327155 0.999368 0 0.0754716 0.997148 0 -0.995575 0.0939692 0.0162628 -0.97673 0.213858 -0.000138262 -0.952186 0.305519 7.34888e-05 -0.879835 0.47528 0.0152279 -0.795648 0.605568 -0.00884511 -0.731102 0.682211 0.0107828 -0.462884 0.886353 0 -0.433209 0.901293 0 -0.999576 0.0291325 0.00755186 -0.980757 0.195084 -0.0029259 -0.972087 0.234601 0.00327959 -0.831466 0.555566 0 -0.825815 0.563942 0 -0.965927 -0.258816 0 -0.965927 -0.258816 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965927 -0.258816 0 0.965927 -0.258816 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.258818 0 0.965926 -0.258818 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707106 -0.707107 0 0.707106 -0.707107 0 0.965926 -0.258818 0 0.965926 -0.258818 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258816 -0.965927 0 -0.258816 -0.965927 0 0.258816 -0.965927 0 0.258816 -0.965927 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.965926 -0.258817 0 0.965926 -0.258817 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965925 -0.258821 0 0.965925 -0.258821 0 -0.965928 -0.258813 0 -0.965928 -0.258813 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965925 -0.258821 0 0.965925 -0.258821 0 -0.965923 -0.258829 0 -0.965923 -0.258829 0 -0.707103 -0.70711 0 -0.707103 -0.70711 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707112 -0.707101 0 0.707112 -0.707101 0 0.965923 -0.258829 0 0.965923 -0.258829 0 -0.965923 -0.258829 0 -0.965923 -0.258829 0 -0.707105 -0.707109 0 -0.707105 -0.707109 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707114 -0.7071 0 0.707114 -0.7071 0 0.965923 -0.258829 0 0.965923 -0.258829 0 -0.965928 -0.258811 0 -0.965928 -0.258811 0 -0.707102 -0.707111 0 -0.707102 -0.707111 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258821 -0.965925 0 0.258821 -0.965925 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.25882 0 0.965926 -0.25882 -2.53246e-06 -0.739338 0.673334 -1.02012e-06 -0.572154 0.820147 -0.00260712 -0.522521 0.852622 0.00577499 -0.370626 0.928764 0 -0.314076 0.949398 0 -0.997732 0.0673089 -0.0102392 -0.972286 0.233569 -0.00864712 -0.974678 0.223447 -2.36564e-06 -0.923294 0.384094 -9.66615e-07 -0.873116 0.487512 0.00289974 -0.845418 0.534097 -0.00842598 -0.702063 0.712065 0 -0.999756 0.0220745 0.00295976 -0.98579 0.167957 -0.00516232 -0.973848 0.227142 0.00508045 -0.864915 0.501893 0.012822 -0.830148 0.557395 0 -0.740669 0.67187 0 -0.987119 0.159987 0 -0.987119 0.159987 0.000261806 -0.89287 0.450314 -0.00198988 -0.780888 0.624668 -0.00249278 -0.782763 0.622315 0.00297531 -0.476342 0.879255 0 -0.462913 0.886404 1.60541e-06 -0.898101 0.43979 4.41753e-06 -0.976859 0.213883 0 -0.976854 0.213908 0 -0.744978 0.66709 -0.0109776 -0.874099 0.485623 0.00530935 -0.832117 0.554574 -0.00402195 -0.981007 0.193933 0 -0.985781 0.168036 0.705411 -0.705385 -0.0694741 0.705422 -0.705375 -0.0694735 0.705422 -0.678268 -0.20575 0.705428 -0.678261 -0.205749 0.705427 -0.62509 -0.334118 0.705412 -0.625104 -0.334125 0.705413 -0.547907 -0.449656 0.705418 -0.547903 -0.449653 0.705419 -0.449652 -0.547903 0.705422 -0.44965 -0.5479 0.705421 -0.334121 -0.625096 0.705412 -0.334125 -0.625103 0.705414 -0.205753 -0.678275 0.705416 -0.205752 -0.678273 0.705415 -0.069474 -0.705381 0.705418 -0.0694736 -0.705378 0.705418 0.0694737 -0.705379 0.705415 0.0694739 -0.705381 0.705416 0.205752 -0.678273 0.705416 0.205752 -0.678274 0.705416 0.334123 -0.6251 0.705418 0.334122 -0.625098 0.705418 0.449653 -0.547903 0.705419 0.449652 -0.547902 0.705418 0.547903 -0.449653 0.705418 0.547903 -0.449653 0.705418 0.625099 -0.334122 0.705419 0.625098 -0.334122 0.705419 0.67827 -0.205751 0.705419 0.678271 -0.205751 0.705419 0.705378 -0.0694737 0.705418 0.705378 -0.0694738 0.705587 -0.7056 -0.0653836 0.705588 -0.705599 -0.0653835 0.705588 -0.681571 -0.193924 0.705589 -0.68157 -0.193923 0.705589 -0.634332 -0.31586 0.705588 -0.634333 -0.31586 0.705588 -0.565493 -0.42704 0.705587 -0.565493 -0.427041 0.705588 -0.477396 -0.523678 0.705588 -0.477396 -0.523678 0.705588 -0.373042 -0.602483 0.705582 -0.373045 -0.602488 0.705582 -0.255986 -0.660776 0.70559 -0.255983 -0.660769 0.70559 -0.130209 -0.696555 0.705588 -0.130209 -0.696557 0.705587 0 -0.708623 0.705587 0 -0.708623 0.705588 0.130209 -0.696557 0.70559 0.130209 -0.696555 0.70559 0.255983 -0.660769 0.705587 0.255984 -0.660771 0.705589 0.373041 -0.602482 0.705588 0.373042 -0.602483 0.705588 0.477396 -0.523678 0.705583 0.477399 -0.523681 0.705582 0.565498 -0.427044 0.705591 0.56549 -0.427039 0.705591 0.63433 -0.315859 0.705589 0.634331 -0.315859 0.70559 0.68157 -0.193924 0.705582 0.681577 -0.193926 0.705581 0.705606 -0.0653839 0.705594 0.705594 -0.0653832 0.705751 -0.705764 -0.0617464 0.705752 -0.705763 -0.0617463 0.705752 -0.684319 -0.183363 0.705752 -0.684319 -0.183363 0.705752 -0.642082 -0.299408 0.705749 -0.642084 -0.299409 0.705749 -0.580338 -0.406357 0.705752 -0.580336 -0.406355 0.705751 -0.500957 -0.500957 0.705746 -0.50096 -0.50096 0.705746 -0.406359 -0.58034 0.705753 -0.406355 -0.580335 0.705754 -0.299407 -0.64208 0.705749 -0.299409 -0.642084 0.705749 -0.183363 -0.684322 0.705756 -0.183362 -0.684315 0.705755 -0.0617461 -0.70576 0.705751 -0.0617463 -0.705764 0.705751 0.0617465 -0.705764 0.705756 0.0617458 -0.705759 0.705757 0.183361 -0.684314 0.705749 0.183364 -0.684322 0.705749 0.299409 -0.642084 0.705757 0.299406 -0.642078 0.705757 0.406353 -0.580332 0.70575 0.406357 -0.580337 0.705751 0.500957 -0.500957 0.705756 0.500953 -0.500953 0.705757 0.580331 -0.406352 0.705749 0.580338 -0.406357 0.705749 0.642085 -0.299409 0.705767 0.642068 -0.299402 0.705768 0.684303 -0.183359 0.705755 0.684316 -0.183362 0.705755 0.70576 -0.0617458 0.705758 0.705758 -0.0617457 0.705758 -0.705758 -0.0617462 0.705755 -0.70576 -0.0617463 0.705755 -0.684316 -0.183362 0.705743 -0.684328 -0.183365 0.705743 -0.64209 -0.299411 0.705749 -0.642085 -0.299409 0.705749 -0.580338 -0.406357 0.705747 -0.58034 -0.406358 0.705746 -0.50096 -0.50096 0.705756 -0.500953 -0.500953 0.705755 -0.406354 -0.580333 0.705757 -0.406353 -0.580332 0.705757 -0.299406 -0.642078 0.705749 -0.299409 -0.642085 0.705749 -0.183363 -0.684322 0.705748 -0.183364 -0.684323 0.705748 -0.0617468 -0.705767 0.705751 -0.0617464 -0.705764 0.705751 0.0617465 -0.705764 0.705748 0.0617467 -0.705767 0.705747 0.183364 -0.684323 0.705749 0.183363 -0.684322 0.705749 0.299409 -0.642084 0.705753 0.299407 -0.642081 0.705753 0.406355 -0.580335 0.705752 0.406356 -0.580336 0.705751 0.500957 -0.500957 0.705749 0.500958 -0.500958 0.705749 0.580338 -0.406357 0.705752 0.580335 -0.406355 0.705752 0.642082 -0.299408 0.705752 0.642082 -0.299408 0.705752 0.684319 -0.183363 0.705751 0.684319 -0.183363 0.705752 0.705763 -0.0617463 0.705751 0.705764 -0.0617464 -0.705398 0.705398 -0.0694758 -0.705395 0.705401 -0.0694762 -0.705395 0.678293 -0.205758 -0.705389 0.678299 -0.20576 -0.705389 0.625124 -0.334136 -0.705397 0.625117 -0.334132 -0.705397 0.54792 -0.449666 -0.705387 0.547927 -0.449672 -0.705387 0.449672 -0.547927 -0.705387 0.449672 -0.547927 -0.705388 0.334136 -0.625125 -0.705398 0.334131 -0.625116 -0.705398 0.205757 -0.678291 -0.705396 0.205758 -0.678293 -0.705396 0.069476 -0.705401 -0.705392 0.0694762 -0.705405 -0.705392 -0.0694764 -0.705405 -0.705394 -0.069476 -0.705402 -0.705392 -0.205759 -0.678296 -0.705396 -0.205758 -0.678293 -0.705395 -0.334133 -0.625118 -0.705391 -0.334135 -0.625122 -0.705391 -0.449669 -0.547924 -0.705387 -0.449672 -0.547927 -0.705387 -0.547927 -0.449672 -0.705391 -0.547924 -0.44967 -0.705391 -0.625122 -0.334135 -0.705392 -0.625121 -0.334134 -0.705392 -0.678296 -0.205759 -0.705392 -0.678296 -0.205759 -0.705392 -0.705404 -0.0694762 -0.705392 -0.705405 -0.0694763 0.705392 -0.705405 -0.0694763 0.705392 -0.705404 -0.0694762 0.705392 -0.678296 -0.205759 0.705392 -0.678296 -0.205759 0.705392 -0.625121 -0.334134 0.705391 -0.625122 -0.334135 0.705391 -0.547924 -0.449669 0.705387 -0.547927 -0.449672 0.705387 -0.449672 -0.547927 0.705391 -0.449669 -0.547924 0.705391 -0.334134 -0.625122 0.705395 -0.334133 -0.625118 0.705396 -0.205758 -0.678293 0.705392 -0.205759 -0.678296 0.705394 -0.0694762 -0.705402 0.705392 -0.0694763 -0.705405 0.705392 0.0694764 -0.705405 0.705396 0.0694759 -0.705401 0.705396 0.205758 -0.678293 0.705398 0.205757 -0.678291 0.705398 0.334131 -0.625116 0.705388 0.334136 -0.625125 0.705387 0.449672 -0.547927 0.705387 0.449672 -0.547927 0.705387 0.547927 -0.449672 0.705397 0.54792 -0.449666 0.705397 0.625117 -0.334132 0.705389 0.625124 -0.334135 0.705389 0.678299 -0.205759 0.705395 0.678293 -0.205758 0.705395 0.705401 -0.0694761 0.705398 0.705398 -0.0694759 0.705409 -0.705387 -0.0694746 0.705411 -0.705386 -0.0694744 0.70541 -0.678278 -0.205754 0.705409 -0.67828 -0.205754 0.705409 -0.625106 -0.334126 0.705411 -0.625105 -0.334125 0.705411 -0.547909 -0.449657 0.705411 -0.547908 -0.449657 0.705411 -0.449657 -0.547908 0.705409 -0.449658 -0.54791 0.70541 -0.334126 -0.625106 0.705412 -0.334125 -0.625104 0.705412 -0.205753 -0.678277 0.705408 -0.205754 -0.678281 0.705408 -0.0694747 -0.705388 0.705407 -0.0694748 -0.705389 0.705407 0.0694748 -0.705389 0.705408 0.0694746 -0.705388 0.705408 0.205754 -0.678281 0.705412 0.205753 -0.678277 0.705412 0.334125 -0.625104 0.70541 0.334126 -0.625106 0.705409 0.449658 -0.54791 0.705411 0.449657 -0.547909 0.705411 0.547909 -0.449657 0.705414 0.547906 -0.449655 0.705415 0.625101 -0.334124 0.705407 0.625108 -0.334127 0.705407 0.678282 -0.205754 0.705413 0.678276 -0.205753 0.705413 0.705384 -0.0694743 0.705407 0.705389 -0.0694745 0.705585 -0.705603 -0.0653836 0.70559 -0.705597 -0.0653834 0.70559 -0.681569 -0.193923 0.705585 -0.681574 -0.193924 0.705585 -0.634335 -0.315861 0.705586 -0.634335 -0.315861 0.705586 -0.565494 -0.427042 0.705584 -0.565496 -0.427043 0.705585 -0.477398 -0.523681 0.705593 -0.477392 -0.523675 0.705592 -0.37304 -0.60248 0.705589 -0.373042 -0.602482 0.705588 -0.255984 -0.660771 0.705589 -0.255984 -0.66077 0.705587 -0.130209 -0.696557 0.705589 -0.130209 -0.696556 0.705587 0 -0.708623 0.705587 0 -0.708623 0.705587 0.130209 -0.696558 0.705586 0.130209 -0.696559 0.705586 0.255985 -0.660773 0.705588 0.255984 -0.66077 0.705588 0.373041 -0.602482 0.705587 0.373042 -0.602484 0.705587 0.477397 -0.523679 0.705588 0.477396 -0.523679 0.705588 0.565493 -0.42704 0.705588 0.565493 -0.42704 0.705588 0.634333 -0.31586 0.705587 0.634333 -0.31586 0.705587 0.681572 -0.193924 0.705588 0.681571 -0.193924 0.705588 0.705599 -0.0653834 0.705587 0.7056 -0.0653836 0 0.998943 0.0459622 0 0.998943 0.0459622 0 0.556599 0.830781 0.00906492 0.654425 0.756073 0 0.989667 0.143385 -0.00119319 0.988416 0.151767 0.000911101 0.918833 0.394644 -4.86555e-05 0.915336 0.402691 3.19927e-05 0.827847 0.560954 0.00245039 0.845871 0.533382 -0.00422355 0.725109 0.688621 0 -0.998943 0.0459615 0 -0.998943 0.0459615 0 -0.996957 0.0779478 0 -0.996957 0.0779478 0 -0.965925 0.258822 -0.0131381 -0.985725 0.167848 -2.32408e-06 -0.908889 0.417038 -3.94054e-06 -0.707115 0.707099 -0.0259914 -0.825243 0.56418 0 -0.652189 0.758056 -0.694728 -0.694763 0.186164 -0.694735 -0.694755 0.18617 -0.694736 -0.508603 0.508591 -0.694735 -0.508605 0.508591 -0.694737 -0.508598 0.508596 -0.703426 -0.703426 0.101907 -0.558622 -0.80116 0.214674 -0.704627 -0.651983 0.280034 -0.694736 -0.508598 0.508596 -0.706733 -0.706733 0.0325169 -0.706716 -0.706749 0.0325159 -0.706733 -0.706733 0.0325091 -0.706717 -0.706747 0.0325478 -0.706011 -0.706046 0.0552027 -0.706028 -0.706023 0.0552782 0.422252 0.90552 0.0416631 0.422252 0.905521 0.041663 -0.50474 -0.862359 0.0396772 -0.504736 -0.862362 0.039677 0.706022 0.706033 0.0552376 0.706021 0.706034 0.0552337 0.706727 0.706738 0.0325176 0.706727 0.706738 0.0325177 0.706727 0.706738 0.0325171 0.706727 0.706738 0.0325171 0.701799 0.70181 0.122233 0.732051 0.674211 0.0976817 0.681424 0.663963 0.30792 0.64114 0.681542 0.35276 0.775459 0.446466 0.446466 0.700662 0.466947 0.539475 0.701668 0.457989 0.54581 0.710638 0.46611 0.527006 0.69508 0.622614 0.359466 0.717903 0.62819 0.299988 0.690696 0.712159 0.125573 0.704438 0.704449 0.0867151 0 -0.996957 0.0779478 0 -0.996957 0.0779478 0.00111218 -0.90239 0.430919 -0.000519789 -0.748428 0.663216 0.00596542 -0.662486 0.749051 0 -0.593492 0.80484 0 -0.995561 0.0941222 0.00190336 -0.99251 0.122148 -0.00124449 -0.961572 0.27455 0.00849915 -0.872999 0.487649 0 -0.998943 0.0459615 0 -0.998943 0.0459615 2.66303e-09 0.999643 0.0267095 -0.0015888 0.996811 0.0797867 -0.00710583 0.985144 0.171581 0.00285648 0.969612 0.244633 -0.00284993 0.885005 0.465572 0.00419271 0.907183 0.420716 -0.00395699 0.786406 0.617697 -0.0204608 0.706959 0.706959 0 0.62233 0.782755 -4.00213e-07 0.999729 0.0232987 -0.000589921 0.998943 0.0459621 0 0.997602 0.0692112 0 -0.97493 -0.222511 0 -0.97493 -0.222511 0 -0.781824 -0.623499 0 -0.781824 -0.623499 0 -0.433889 -0.900966 0 -0.433889 -0.900966 0 0 -1 0 0 -1 0 0.433889 -0.900966 0 0.433889 -0.900966 0 0.781831 -0.623491 0 0.781831 -0.623491 0 0.974927 -0.222524 0 0.974927 -0.222524 0 -0.97493 -0.222513 0 -0.97493 -0.222513 0 -0.78184 -0.623479 0 -0.78184 -0.623479 0 -0.433881 -0.90097 0 -0.433881 -0.90097 0 0 -1 0 0 -1 0 0.433881 -0.90097 0 0.433881 -0.90097 0 0.78184 -0.623479 0 0.78184 -0.623479 0 0.974924 -0.222538 0 0.974924 -0.222538 0 -0.97493 -0.222512 0 -0.97493 -0.222512 0 -0.781839 -0.623481 0 -0.781839 -0.623481 0 -0.433881 -0.90097 0 -0.433881 -0.90097 0 0 -1 0 0 -1 0 0.433881 -0.90097 0 0.433881 -0.90097 0 0.781839 -0.623481 0 0.781839 -0.623481 0 0.974924 -0.222538 0 0.974924 -0.222538 0 0.608664 -0.793428 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 -0.0184938 0.379584 -0.924972 0 0.129784 -0.991542 -0.019076 0.793672 -0.608047 0 0.707107 -0.707107 0 0.924209 -0.381888 -0.00946966 0.965883 -0.258805 0 0.991555 -0.129684 0 -0.974927 -0.222527 0 -0.974927 -0.222527 0 -0.781834 -0.623487 0 -0.781834 -0.623487 0 -0.433878 -0.900971 0 -0.433878 -0.900971 0 0 -1 0 0 -1 0 0.433878 -0.900971 0 0.433878 -0.900971 0 0.781834 -0.623487 0 0.781834 -0.623487 0 0.974927 -0.222527 0 0.974927 -0.222527 0 -0.382816 -0.923825 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 -0.70711 -0.707104 -0.0184929 -0.611264 -0.791211 0 -0.79381 -0.608165 -0.0190695 -0.12979 -0.991358 0 -0.258816 -0.965927 0 0.131448 -0.991323 -0.00946863 0.258805 -0.965883 0 0.383509 -0.923537 0 0.70711 -0.707104 0 0.70711 -0.707104 0 0.965925 -0.258822 0 0.965925 -0.258822 0 -0.991573 -0.129546 -0.0184583 -0.925066 -0.379359 0 -0.965926 -0.25882 0 -0.793334 -0.608786 -0.00959864 -0.707074 -0.707074 0 -0.608747 -0.793365 0 -0.381807 -0.924242 -0.00946948 -0.258805 -0.965883 0 -0.129598 -0.991567 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.974928 -0.22252 0 -0.974928 -0.22252 0 -0.78183 -0.623492 0 -0.78183 -0.623492 0 -0.433884 -0.900969 0 -0.433884 -0.900969 0 0 -1 0 0 -1 0 0.433884 -0.900969 0 0.433884 -0.900969 0 0.781831 -0.623491 0 0.781831 -0.623491 0 0.974928 -0.222522 0 0.974928 -0.222522 0 -0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.781831 -0.62349 0 -0.781831 -0.62349 0 -0.433884 -0.900969 0 -0.433884 -0.900969 0 0 -1 0 0 -1 0 0.433884 -0.900969 0 0.433884 -0.900969 0 0.781832 -0.623489 0 0.781832 -0.623489 0 0.974928 -0.222522 0 0.974928 -0.222522 0 -0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.781829 -0.623493 0 -0.781829 -0.623493 0 -0.433886 -0.900968 0 -0.433887 -0.900968 0 0 -1 0 0 -1 0 0.433886 -0.900968 0 0.433886 -0.900968 0 0.781829 -0.623493 0 0.781829 -0.623493 0 0.974928 -0.222521 0 0.974928 -0.222521 0 -0.974927 -0.222524 0 -0.974927 -0.222524 0 -0.781833 -0.623487 0 -0.781833 -0.623487 0 -0.433881 -0.90097 0 -0.433881 -0.90097 0 0 -1 0 0 -1 0 0.433881 -0.90097 0 0.433881 -0.90097 0 0.781834 -0.623487 0 0.781834 -0.623487 0 0.974927 -0.222524 0 0.974927 -0.222524 0 -0.974927 -0.222524 0 -0.974927 -0.222524 0 -0.781834 -0.623487 0 -0.781834 -0.623487 0 -0.433878 -0.900971 0 -0.433878 -0.900971 0 0 -1 0 0 -1 0 0.433878 -0.900971 0 0.433878 -0.900971 0 0.781833 -0.623487 0 0.781833 -0.623487 0 0.974927 -0.222524 0 0.974927 -0.222524 -0.705167 0.705157 -0.0741151 -0.705165 0.705159 -0.0741157 -0.705165 0.674341 -0.219107 -0.705167 0.674339 -0.219106 -0.705167 0.614048 -0.354521 -0.705171 0.614045 -0.354518 -0.70517 0.526918 -0.474439 -0.705168 0.52692 -0.474441 -0.705167 0.416764 -0.573626 -0.705168 0.416763 -0.573625 -0.705168 0.288393 -0.647741 -0.705168 0.288393 -0.647741 -0.705168 0.147418 -0.693546 -0.705166 0.147418 -0.693548 -0.705165 0 -0.709043 -0.705165 0 -0.709043 -0.705166 -0.147418 -0.693548 -0.705167 -0.147418 -0.693547 -0.705167 -0.288393 -0.647742 -0.705167 -0.288393 -0.647742 -0.705167 -0.416764 -0.573626 -0.705166 -0.416765 -0.573627 -0.705166 -0.526921 -0.474442 -0.705166 -0.526921 -0.474442 -0.705166 -0.614049 -0.354521 -0.705167 -0.614048 -0.354521 -0.705167 -0.674339 -0.219106 -0.705166 -0.674339 -0.219106 -0.705166 -0.705158 -0.0741151 -0.705166 -0.705158 -0.0741151 -0.705757 0.705758 -0.0617458 -0.705757 0.705758 -0.0617458 -0.705757 0.684314 -0.183361 -0.705757 0.684314 -0.183361 -0.705757 0.642078 -0.299406 -0.705757 0.642078 -0.299406 -0.705757 0.580332 -0.406353 -0.705757 0.580332 -0.406353 -0.705757 0.500953 -0.500953 -0.705757 0.500953 -0.500953 -0.705757 0.406353 -0.580332 -0.705757 0.406353 -0.580332 -0.705757 0.299406 -0.642078 -0.705757 0.299406 -0.642078 -0.705756 0.183362 -0.684314 -0.705757 0.183361 -0.684314 -0.705757 0.0617458 -0.705758 -0.705757 0.0617459 -0.705758 -0.705757 -0.0617458 -0.705758 -0.705757 -0.0617459 -0.705758 -0.705757 -0.183361 -0.684314 -0.705757 -0.183361 -0.684314 -0.705757 -0.299406 -0.642078 -0.705757 -0.299406 -0.642077 -0.705757 -0.406353 -0.580331 -0.705757 -0.406353 -0.580332 -0.705757 -0.500952 -0.500953 -0.705757 -0.500952 -0.500953 -0.705757 -0.580332 -0.406352 -0.705756 -0.580333 -0.406353 -0.705756 -0.642079 -0.299406 -0.705756 -0.642078 -0.299406 -0.705756 -0.684315 -0.183362 -0.705758 -0.684313 -0.183361 -0.705758 -0.705757 -0.061746 -0.705758 -0.705758 -0.0617461 -0.202057 0.971869 0.121007 -0.837542 0.544504 0.0451545 -0.83973 0.540913 0.0476117 -0.839515 0.542861 0.0227146 -0.203243 0.978272 0.0409331 -0.202045 0.978516 0.0410381 -0.576236 0.816573 0.0340729 -0.202057 0.97187 0.121007 -0.202211 0.965337 0.165031 -0.146825 0.968582 0.200726 -0.202094 0.957941 0.203734 -0.202056 0.939918 0.275186 -0.202056 0.939918 0.275186 -0.202199 0.924238 0.323883 -0.0983727 0.92949 0.355487 -0.202138 0.910473 0.360803 -0.202058 0.883671 0.422253 -0.202056 0.883672 0.422253 -0.202179 0.857196 0.473644 -0.0782996 0.86205 0.500739 -0.202166 0.837453 0.507742 -0.202053 0.804585 0.558406 -0.202054 0.804585 0.558406 -0.202147 0.766094 0.610112 -0.0871576 0.770096 0.631946 -0.202193 0.740924 0.640429 -0.202056 0.704702 0.680124 -0.202061 0.704701 0.680124 -0.202061 0.647748 0.734571 -0.105536 0.663531 0.740668 -0.202209 0.623601 0.755138 -0.202058 0.586603 0.784264 -0.202055 0.586604 0.784264 -0.202056 0.521662 0.82888 -0.189369 0.523886 0.830471 -0.202218 0.488776 0.84865 -0.202061 0.453342 0.868131 -0.202055 0.453343 0.868132 -0.202055 0.382091 0.901765 -0.202055 0.382091 0.901765 -0.202209 0.340232 0.918343 -0.142082 0.311665 0.939509 -0.202097 0.303022 0.931308 -0.202055 0.232644 0.951341 -0.202058 0.232644 0.951341 -0.2022 0.182137 0.962259 -0.0957812 0.15796 0.982789 -0.202139 0.143282 0.968819 -0.202056 0.0771837 0.976328 -0.202063 0.0771831 0.976327 -0.202184 0.0189289 0.979165 -0.0779401 -0.00157694 0.996957 -0.202167 -0.0204761 0.979137 -0.202052 -0.0802714 0.97608 -0.202059 -0.0802718 0.976078 -0.20215 -0.144814 0.968589 -0.0890494 -0.16117 0.982901 -0.202193 -0.18366 0.96197 -0.202055 -0.235651 0.950601 -0.202058 -0.235652 0.9506 -0.202059 -0.311304 0.928581 -0.112148 -0.308949 0.944443 -0.202204 -0.341682 0.917805 -0.202052 -0.384942 0.900552 -0.202054 -0.384942 0.900552 -0.202054 -0.456088 0.866694 -0.195713 -0.456229 0.868073 -0.202211 -0.490156 0.847855 -0.202053 -0.524281 0.827227 -0.202058 -0.524281 0.827226 -0.202057 -0.589081 0.782404 -0.202058 -0.589081 0.782404 -0.202211 -0.624798 0.754148 -0.137511 -0.657454 0.74084 -0.202105 -0.65464 0.728423 -0.202061 -0.706849 0.677891 -0.202049 -0.70685 0.677893 -0.202189 -0.741937 0.639257 -0.0933614 -0.771655 0.629152 -0.202146 -0.767059 0.608899 -0.202061 -0.806346 0.555857 -0.202073 -0.806345 0.555855 -0.202193 -0.838249 0.506415 -0.0777844 -0.863665 0.498029 -0.202174 -0.857945 0.472289 -0.202057 -0.885003 0.419456 -0.202053 -0.885003 0.419457 -0.202141 -0.911043 0.359361 -0.0911297 -0.931255 0.352789 -0.202177 -0.924752 0.322426 -0.202038 -0.940788 0.272212 -0.202048 -0.940786 0.272211 -0.202048 -0.959623 0.195707 -0.118743 -0.971528 0.205019 -0.202227 -0.965595 0.163495 -0.202074 -0.972244 0.117932 -0.202068 -0.972245 0.117933 -0.202069 -0.978579 0.0393945 -0.202042 -0.978584 0.0393969 -0.840836 0.540824 0.0224624 -0.573239 0.818664 0.034445 -0.573261 0.813095 0.101238 -0.573262 0.813094 0.101238 -0.573262 0.802325 0.166271 -0.573261 0.802325 0.166271 -0.573261 0.786363 0.230229 -0.57326 0.786363 0.230229 -0.57326 0.765312 0.292696 -0.57326 0.765312 0.292696 -0.57326 0.739306 0.353269 -0.57326 0.739306 0.353269 -0.57326 0.708516 0.411556 -0.573261 0.708515 0.411556 -0.573261 0.673139 0.467178 -0.573262 0.673139 0.467178 -0.573262 0.633406 0.519777 -0.573259 0.633407 0.519778 -0.573259 0.589575 0.569013 -0.573256 0.589577 0.569014 -0.573256 0.541928 0.614566 -0.573261 0.541925 0.614564 -0.573261 0.49077 0.656138 -0.573261 0.490769 0.656138 -0.573262 0.436437 0.693465 -0.573259 0.436438 0.693466 -0.573259 0.379281 0.726306 -0.573261 0.37928 0.726304 -0.573261 0.319668 0.754443 -0.573261 0.319668 0.754443 -0.573262 0.257987 0.777698 -0.573261 0.257987 0.777698 -0.573261 0.194637 0.79592 -0.57326 0.194637 0.79592 -0.573261 0.130026 0.80899 -0.573267 0.130025 0.808986 -0.573267 0.0645734 0.81682 -0.573263 0.064574 0.816823 -0.573263 -0.00129609 0.819371 -0.573262 -0.00129605 0.819371 -0.573262 -0.0671575 0.816616 -0.57326 -0.0671574 0.816617 -0.57326 -0.132584 0.808576 -0.573264 -0.132584 0.808573 -0.573264 -0.197153 0.795298 -0.57326 -0.197153 0.795301 -0.57326 -0.260446 0.776879 -0.573262 -0.260446 0.776877 -0.573262 -0.322053 0.753427 -0.573261 -0.322053 0.753428 -0.573261 -0.381576 0.725101 -0.573263 -0.381576 0.7251 -0.573262 -0.438628 0.692081 -0.573263 -0.438628 0.69208 -0.573264 -0.492841 0.654581 -0.573264 -0.492841 0.654581 -0.573264 -0.543866 0.612844 -0.573261 -0.543867 0.612846 -0.573261 -0.591371 0.567144 -0.573262 -0.591371 0.567143 -0.573262 -0.635047 0.51777 -0.573252 -0.635052 0.517775 -0.573252 -0.674619 0.465051 -0.573254 -0.674618 0.465049 -0.573254 -0.709818 0.409315 -0.573263 -0.709813 0.409311 -0.573263 -0.740418 0.350928 -0.573254 -0.740424 0.350931 -0.573254 -0.766238 0.290276 -0.573261 -0.766233 0.290273 -0.573261 -0.787087 0.227739 -0.573259 -0.787089 0.22774 -0.573259 -0.802849 0.163734 -0.573252 -0.802853 0.163735 -0.573252 -0.813417 0.0986672 -0.573257 -0.813414 0.0986664 -0.573257 -0.818713 0.0329603 -0.573272 -0.818702 0.0329584 -0.850931 -0.524852 0.0211298 -0.850929 -0.524856 0.0211304 -0.850929 -0.521459 0.0632528 -0.850937 -0.521446 0.06325 -0.850937 -0.514674 0.104963 -0.850941 -0.514668 0.104961 -0.850941 -0.504565 0.145993 -0.850936 -0.504572 0.145996 -0.850936 -0.491203 0.186084 -0.850939 -0.491198 0.186081 -0.850939 -0.474651 0.224965 -0.85093 -0.474664 0.224973 -0.85093 -0.455044 0.2624 -0.850933 -0.455039 0.262397 -0.850933 -0.432473 0.298127 -0.850937 -0.432469 0.298123 -0.850937 -0.407105 0.331923 -0.850935 -0.407107 0.331925 -0.850935 -0.379107 0.363576 -0.850933 -0.379109 0.363578 -0.850933 -0.348656 0.392876 -0.850933 -0.348656 0.392876 -0.850933 -0.315946 0.419632 -0.850934 -0.315945 0.419632 -0.850933 -0.28119 0.443671 -0.850936 -0.281189 0.443668 -0.850936 -0.244614 0.464836 -0.850934 -0.244615 0.464838 -0.850934 -0.206457 0.482997 -0.850934 -0.206457 0.482997 -0.850934 -0.166963 0.49803 -0.850935 -0.166963 0.498029 -0.850935 -0.126388 0.509839 -0.850934 -0.126388 0.50984 -0.850934 -0.0849953 0.51835 -0.850937 -0.084995 0.518346 -0.850937 -0.0430521 0.523501 -0.850934 -0.043052 0.523506 -0.850933 -0.000830883 0.525273 -0.850934 -0.000830975 0.525272 -0.850934 0.0413961 0.523639 -0.850934 0.0413961 0.523639 -0.850934 0.0833556 0.518617 -0.850933 0.0833561 0.518618 -0.850933 0.124776 0.510239 -0.850935 0.124774 0.510236 -0.850935 0.165387 0.498555 -0.850934 0.165387 0.498556 -0.850934 0.204928 0.483648 -0.850934 0.204929 0.483648 -0.850934 0.243144 0.46561 -0.850935 0.243143 0.465609 -0.850935 0.279785 0.444557 -0.850935 0.279785 0.444557 -0.850935 0.314615 0.420627 -0.850935 0.314616 0.420627 -0.850935 0.34741 0.393976 -0.850936 0.347408 0.393974 -0.850936 0.377954 0.364772 -0.850936 0.377953 0.364772 -0.850936 0.406053 0.333209 -0.850935 0.406054 0.33321 -0.850935 0.431525 0.299491 -0.850935 0.431527 0.299492 -0.850934 0.454205 0.263834 -0.850935 0.454204 0.263834 -0.850935 0.473943 0.226468 -0.850935 0.473943 0.226469 -0.850935 0.490614 0.187637 -0.850934 0.490615 0.187638 -0.850934 0.50411 0.147592 -0.850934 0.50411 0.147592 -0.850934 0.514343 0.106591 -0.850935 0.514343 0.106591 -0.850935 0.521247 0.0649002 -0.878472 0.473574 0.0633551 -0.817789 0.574613 0.0322739 0 0.998176 -0.0603785 -0.00671583 0.996172 -0.0871538 0 0.956696 -0.291088 -0.00746244 0.965899 -0.258812 0 0.978426 -0.206598 0 0.989115 -0.147145 0 0.937376 -0.34832 -0.00186549 0.911898 -0.410412 -0.00559606 0.906294 -0.422612 0 0.795392 -0.606095 -0.00783584 0.819127 -0.573559 0 0.84519 -0.534465 0 0.875918 -0.48246 0 0.757346 -0.653014 -0.00410332 0.707101 -0.707101 -0.00410332 0.707101 -0.707101 0 0.653014 -0.757346 0 0.606095 -0.795392 -0.00783579 0.573559 -0.819127 -0.0018655 0.410412 -0.911898 -0.005596 0.422612 -0.906294 0 0.482459 -0.875919 0 0.534466 -0.84519 0 0.34832 -0.937376 0 0.291088 -0.956696 -0.00746241 0.258812 -0.965899 0 0.206599 -0.978426 0 0.147145 -0.989115 -0.00671582 0.0871538 -0.996172 0 0.0603785 -0.998176 0 -0.0603785 -0.998176 -0.00671581 -0.0871537 -0.996172 0 -0.147145 -0.989115 0 -0.206599 -0.978426 -0.00746234 -0.258812 -0.965899 -0.00671293 -0.410404 -0.911879 -0.00223785 -0.422617 -0.906306 0 -0.34832 -0.937376 0 -0.291087 -0.956697 0 -0.606096 -0.795392 -0.00783586 -0.573559 -0.819127 0 -0.534466 -0.84519 0 -0.482459 -0.875919 0 -0.653012 -0.757347 -0.00410346 -0.707101 -0.707101 -0.00410321 -0.707101 -0.707101 0 -0.845191 -0.534465 -0.00783587 -0.819127 -0.573558 0 -0.795392 -0.606095 0 -0.757344 -0.653016 0 -0.875919 -0.482459 -0.00671288 -0.911879 -0.410405 -0.002238 -0.906305 -0.422617 0 -0.937377 -0.348316 0 -0.956696 -0.291088 -0.00746252 -0.965899 -0.258812 0 -0.998176 -0.0603785 -0.00671591 -0.996172 -0.0871541 0 -0.989115 -0.147146 0 -0.978426 -0.206598 -0.947053 0.318243 0.0425748 -0.939632 0.331553 0.0846396 -0.939476 0.331635 0.0860351 -0.938491 0.333008 0.0913275 -0.937019 0.337515 0.0898818 -0.938857 0.331614 0.0926244 -0.944805 0.307977 0.111772 -0.933765 0.338457 0.116315 -0.937604 0.327999 0.115391 -0.941152 0.323273 0.0986297 -0.943474 0.317589 0.0948376 -0.94673 0.309054 0.0904838 -0.942969 0.320946 0.0883372 -0.940726 0.32795 0.0865081 -0.940037 0.330209 0.0853998 -0.939777 0.331205 0.0843936 -0.942647 0.330687 0.0454108 -0.941685 0.330522 0.0631256 -0.939453 0.33628 0.0659005 -0.941472 0.330957 0.0640099 -0.941855 0.329982 0.0634087 -0.9397 0.3317 0.0833001 -0.939394 0.336124 0.0675222 -0.942829 0.327492 0.0618193 -0.93968 0.331769 0.0832506 -0.939887 0.335367 0.0643603 -0.933321 0.351573 0.072859 -0.940456 0.336453 0.0483904 -0.941314 0.334243 0.0470069 -0.939599 -0.342001 0.0137687 -0.862599 -0.505353 0.0232511 -0.964234 -0.263123 0.0319162 -0.953232 -0.299926 0.0373289 -0.943325 -0.329013 0.0434643 -0.940996 -0.335251 0.0461974 -0.940283 -0.337002 0.0479424 -0.94017 -0.336633 0.0525238 -0.940081 -0.336884 0.0525145 -0.940163 -0.336655 0.0525013 -0.937222 -0.341032 0.0728779 -0.939599 -0.335306 0.0687262 -0.939687 -0.338167 0.0513024 -0.940015 -0.337609 0.0489043 -0.939512 -0.335561 0.0686685 -0.941858 -0.328771 0.0693822 -0.937296 -0.341506 0.0696466 -0.93989 -0.330979 0.0840266 -0.940264 -0.329671 0.0849744 -0.941169 -0.326809 0.0860067 -0.946864 -0.308962 0.089397 -0.949312 -0.30229 0.0861803 -0.943204 -0.318462 0.0945938 -0.939472 -0.329461 0.094058 -0.940498 -0.324081 0.102152 -0.939128 -0.32853 0.100537 -0.940118 -0.325104 0.102396 -0.938986 -0.331324 0.0923611 -0.937388 -0.336547 0.0896721 -0.93002 -0.358257 0.0819503 -0.930514 -0.357097 0.0814051 -0.93443 -0.347794 0.0766857 -0.941038 -0.323725 0.0982328 -0.939668 -0.326739 0.10132 -0.939604 -0.320068 0.121252 -0.936316 -0.325399 0.132016 -0.940945 -0.305937 0.145002 -0.939677 -0.305608 0.15366 -0.939604 -0.2965 0.170976 -0.936377 -0.299974 0.182248 -0.940953 -0.278728 0.192142 -0.939676 -0.277118 0.200536 -0.940343 -0.249151 0.231687 -0.926825 -0.291024 0.237279 -0.938536 -0.263285 0.223231 -0.939482 -0.260793 0.222173 -0.941586 -0.245554 0.230474 -0.944865 -0.237095 0.225867 -0.946999 -0.231847 0.222349 -0.941036 -0.238366 0.240068 -0.939913 -0.238657 0.244146 -0.939691 -0.237294 0.246316 -0.939683 -0.237959 0.245706 -0.938555 -0.243122 0.244962 -0.938823 -0.243147 0.243907 -0.93938 -0.240432 0.244455 -0.939581 -0.239085 0.245004 -0.939207 -0.243515 0.242053 -0.939518 -0.244073 0.240281 -0.941678 -0.25597 0.218454 -0.931 -0.274135 0.241016 -0.935375 -0.267125 0.231769 -0.939702 -0.237849 0.245739 -0.939692 -0.237163 0.246439 -0.939603 -0.227182 0.255996 -0.936497 -0.226922 0.267356 -0.940966 -0.203604 0.270423 -0.939674 -0.199673 0.277746 -0.939603 -0.183222 0.289093 -0.936558 -0.181185 0.300053 -0.940971 -0.157631 0.299544 -0.939673 -0.15271 0.306094 -0.939603 -0.134527 0.314719 -0.936618 -0.130832 0.325008 -0.940974 -0.107589 0.320924 -0.939673 -0.101819 0.326571 -0.939513 -0.0926452 0.329747 -0.93966 -0.094103 0.328912 -0.93969 -0.0950178 0.328565 -0.939692 -0.0951297 0.328525 -0.939735 -0.0940422 0.328715 -0.939933 -0.0927846 0.328506 -0.94034 -0.0913013 0.327758 -0.941332 -0.0888645 0.325573 -0.947084 -0.0772338 0.311555 -0.949061 -0.076803 0.305588 -0.944007 -0.0774222 0.320714 -0.939611 -0.0620667 0.336569 -0.952735 -0.0429039 0.300759 -0.937775 -0.0719964 0.339697 -0.934979 -0.0760795 0.346448 -0.931666 -0.0800548 0.354386 -0.936765 -0.0866694 0.339058 -0.938952 -0.0906043 0.331903 -0.942053 -0.077289 0.32644 -0.940714 -0.0768241 0.330386 -0.925884 -0.0611342 0.37283 -0.939491 -0.0622562 0.336869 -0.939603 -0.0280525 0.341114 -0.936738 -0.0215592 0.349367 -0.940978 -0.000535451 0.338467 -0.939671 0.00644429 0.342019 -0.939603 0.0269735 0.341201 -0.936798 0.0345472 0.348162 -0.940978 0.0537114 0.334178 -0.93967 0.0610335 0.336594 -0.937288 0.080991 0.339016 -0.938548 0.0783539 0.336137 -0.939666 0.0751527 0.333736 -0.93962 0.0750745 0.333885 -0.940707 0.0761682 0.330558 -0.939365 0.107706 0.325565 -0.942344 0.0767883 0.325717 -0.947868 0.0764678 0.309354 -0.946195 0.0768681 0.314334 -0.940352 0.0901996 0.328028 -0.935174 0.11152 0.336175 -0.943938 0.100925 0.314317 -0.944519 0.109508 0.309663 -0.938699 0.0993726 0.330105 -0.937603 0.0984573 0.333476 -0.936142 0.0976902 0.33778 -0.932858 0.0966667 0.347032 -0.927831 0.0956895 0.360519 -0.931713 0.0901424 0.35183 -0.93561 0.0840074 0.342894 -0.941272 0.104893 0.320943 -0.939605 0.107865 0.32482 -0.939604 0.13353 0.315143 -0.936917 0.142526 0.319176 -0.940976 0.156677 0.300029 -0.939668 0.16414 0.300137 -0.939603 0.182307 0.289672 -0.936976 0.191625 0.292156 -0.940972 0.202737 0.271051 -0.939667 0.210007 0.270042 -0.937147 0.233499 0.259294 -0.941992 0.244068 0.230394 -0.939594 0.226911 0.25627 -0.939506 0.226992 0.256523 -0.938802 0.227821 0.258357 -0.939755 0.237538 0.245839 -0.939977 0.237929 0.244607 -0.940428 0.237953 0.242843 -0.941498 0.237146 0.239467 -0.94729 0.230526 0.222486 -0.948828 0.226666 0.219883 -0.943888 0.239177 0.22775 -0.939631 0.250958 0.232623 -0.938684 0.251197 0.236163 -0.939755 0.250296 0.232837 -0.939682 0.244621 0.239077 -0.939587 0.243882 0.240205 -0.939335 0.243232 0.241844 -0.9388 0.242722 0.244418 -0.933952 0.241266 0.263675 -0.930213 0.249312 0.269348 -0.934256 0.240358 0.263426 -0.940684 0.247653 0.231907 -0.939671 0.250969 0.232449 -0.939603 0.264584 0.217119 -0.937095 0.273782 0.216555 -0.940963 0.278096 0.193007 -0.939665 0.284501 0.189971 -0.939603 0.295958 0.171913 -0.937154 0.304739 0.16993 -0.940956 0.305447 0.145955 -0.939664 0.311211 0.142052 -0.939603 0.319683 0.122264 -0.93463 0.336333 0.11553 -0.940047 0.325741 0.10102 0 -0.994522 -0.104528 0 -0.994522 -0.104528 0 -0.951057 -0.309017 0 -0.951057 -0.309017 0 -0.866026 -0.5 0 -0.866026 -0.5 0 -0.743145 -0.669131 0 -0.743145 -0.669131 0 -0.587785 -0.809017 0 -0.587785 -0.809017 0 -0.406736 -0.913546 0 -0.406736 -0.913546 0 -0.207912 -0.978148 0 -0.207912 -0.978148 0 0 -1 0 0 -1 0 0.207912 -0.978148 0 0.207912 -0.978148 0 0.406737 -0.913546 0 0.406737 -0.913546 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.743145 -0.66913 0 0.743145 -0.66913 0 0.866026 -0.5 0 0.866026 -0.5 0 0.951056 -0.309017 0 0.951056 -0.309017 0 0.994522 -0.104529 0 0.994522 -0.104529 0.849121 -0.136709 -0.5102 0.849121 -0.373493 -0.373493 0.849121 -0.5102 -0.136711 0.849122 0.5102 -0.136706 0.849122 0.373492 -0.373492 0.849121 0.136707 -0.5102 0.849121 -0.136705 -0.510201 0.849121 -0.373495 -0.37349 0.84912 -0.510202 -0.136706 0.84912 0.510202 -0.136706 0.849121 0.373495 -0.37349 0.849121 0.136705 -0.510201 0.849121 -0.136706 -0.510201 0.849121 -0.373493 -0.373493 0.849121 -0.5102 -0.136711 0.849122 0.5102 -0.136706 0.849122 0.373492 -0.373492 0.849121 0.136705 -0.510201 0.849121 -0.136707 -0.5102 0.849121 -0.373495 -0.37349 0.84912 -0.510202 -0.136706 0.84912 0.510202 -0.136706 0.849121 0.373495 -0.37349 0.849121 0.136707 -0.5102 0.705505 -0.705531 -0.0670039 0.705516 -0.705519 -0.0670033 0.705516 -0.680294 -0.198614 0.70551 -0.6803 -0.198615 0.70551 -0.63075 -0.323125 0.705513 -0.630748 -0.323124 0.705513 -0.558646 -0.436081 0.705515 -0.558644 -0.43608 0.705514 -0.466569 -0.533445 0.705509 -0.466573 -0.533448 0.705392 0.705405 0.0694763 0.705392 0.705404 0.0694763 0.705392 0.678296 0.205759 0.705393 0.678295 0.205758 0.705394 0.62512 0.334133 0.705397 0.625117 0.334132 0.705397 0.54792 0.449666 0.705387 0.547927 0.449672 0.705387 0.449672 0.547927 0.705392 0.449669 0.547924 0.705391 0.334135 0.625122 0.70539 0.334135 0.625123 0.705389 0.20576 0.678299 0.70539 0.20576 0.678298 0.705389 0.0694766 0.705407 0.705392 0.0694762 0.705405 0.705392 -0.0694763 0.705405 0.705389 -0.0694764 0.705407 0.705389 -0.20576 0.678299 0.705388 -0.20576 0.6783 0.705386 -0.334137 0.625126 0.705395 -0.334133 0.625119 0.705396 -0.449667 0.54792 0.705387 -0.449672 0.547927 0.705387 -0.547927 0.449672 0.705386 -0.547928 0.449673 0.705385 -0.625127 0.334137 0.705391 -0.625122 0.334135 0.70539 -0.678298 0.20576 0.705395 -0.678293 0.205758 0.705395 -0.705401 0.0694757 0.705385 -0.705411 0.0694771 -0.706946 -0.548759 0.446196 -0.756777 -0.533063 0.378328 -0.746956 -0.539695 0.388312 -0.707007 -0.599844 0.374604 -0.707061 -0.614197 0.350467 -0.669691 -0.670155 0.320008 -0.706162 -0.643762 0.294798 -0.706923 -0.670431 0.225348 -0.647188 -0.735259 0.201352 -0.706532 -0.688203 0.16489 -0.7057 -0.7057 0.0630444 -0.572955 -0.812672 0.106242 -0.70681 -0.706812 0.0289213 -0.705517 0.705518 -0.067003 -0.705517 0.705519 -0.067003 -0.705517 0.680293 -0.198613 -0.705517 0.680293 -0.198613 -0.705517 0.630744 -0.323122 -0.705517 0.630744 -0.323122 -0.705517 0.558643 -0.436078 -0.705518 0.558642 -0.436078 -0.705518 0.466567 -0.533442 -0.705516 0.466568 -0.533442 -0.705397 -0.625116 0.334132 -0.705398 -0.678291 0.205757 -0.705398 -0.67829 0.205757 -0.705398 -0.705398 0.0694754 -0.705398 -0.705398 0.0694754 -0.705397 -0.334132 0.625117 -0.705397 -0.449666 0.547919 -0.705397 -0.449666 0.54792 -0.707074 -0.50665 0.493308 -0.664007 -0.578 0.474352 -0.705831 -0.553531 0.442047 -0.705398 -0.625116 0.334132 -0.705397 0.205757 0.678291 -0.705397 0.0694758 0.705399 -0.705397 0.0694758 0.705399 -0.705397 -0.0694758 0.705399 -0.705397 -0.0694758 0.705399 -0.706784 -0.167458 0.687324 -0.610536 -0.229902 0.757886 -0.706559 -0.234095 0.667812 -0.705396 -0.334132 0.625117 -0.705397 0.54792 0.449666 -0.705396 0.449666 0.54792 -0.705398 0.449666 0.547919 -0.707029 0.380539 0.59607 -0.644288 0.360516 0.674478 -0.706048 0.320726 0.631373 -0.705398 0.205757 0.678291 -0.641875 0.682251 0.350043 -0.707056 0.594506 0.382928 -0.705398 0.547919 0.449665 -0.705398 0.625116 0.334132 -0.705397 0.678291 0.205757 -0.705397 0.678291 0.205757 -0.705397 0.705399 0.0694758 -0.705397 0.705399 0.0694757 -0.891954 -0.450867 0.0337364 -0.706866 -0.706866 0.0260917 -0.186159 -0.694746 -0.694746 -0.186155 -0.694744 -0.69475 -0.508581 -0.50859 -0.694753 -0.508592 -0.508589 -0.694746 -0.694751 -0.186148 -0.694744 -0.694747 -0.186151 -0.694747 -0.694748 0.186147 -0.694748 -0.69475 0.186152 -0.694745 -0.508587 0.508595 -0.694745 -0.508587 0.508587 -0.69475 -0.186155 0.694747 -0.694747 -0.186155 0.694747 -0.694747 -0.258822 -0.965925 0 -0.258822 -0.965925 0 -0.707101 -0.707113 0 -0.707101 -0.707113 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.707101 0.707113 0 -0.707101 0.707113 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.510203 -0.136701 -0.84912 -0.373491 -0.373497 -0.84912 -0.13671 -0.510202 -0.84912 -0.136707 0.510203 -0.84912 -0.373491 0.373497 -0.84912 -0.510203 0.136701 -0.84912 -0.159333 -0.698073 -0.698073 -0.15933 -0.698072 -0.698076 -0.446431 -0.559811 -0.698076 -0.446427 -0.559811 -0.698079 -0.645112 -0.310669 -0.69808 -0.64512 -0.310665 -0.698074 -0.716024 0 -0.698076 -0.716024 0 -0.698076 -0.645115 0.310671 -0.698076 -0.645114 0.310665 -0.69808 -0.446435 0.559804 -0.69808 -0.446432 0.559816 -0.698072 -0.159325 0.69808 -0.698069 -0.15933 0.698074 -0.698074 -0.222524 -0.974927 0 -0.222524 -0.974927 0 -0.623487 -0.781834 0 -0.623487 -0.781834 0 -0.900969 -0.433884 0 -0.900969 -0.433884 0 -1 0 0 -1 0 0 -0.900969 0.433884 0 -0.900969 0.433884 0 -0.623495 0.781827 0 -0.623495 0.781827 0 -0.222511 0.97493 0 -0.222511 0.97493 0 -0.116752 -0.511516 -0.851305 -0.52467 0 -0.851306 -0.472711 -0.227646 -0.851306 -0.327125 -0.410205 -0.851305 -0.116745 0.511517 -0.851306 -0.327129 0.410201 -0.851306 -0.472711 0.227646 -0.851306 -0.15933 0.698074 -0.698074 -0.159325 0.69808 -0.698069 -0.330557 0.625369 -0.706856 -0.455123 0.570716 -0.683481 -0.46527 0.540656 -0.700867 -0.585042 0.398895 -0.706123 -0.665351 0.320411 -0.674273 -0.661914 0.259772 -0.703127 -0.704873 0.0794122 -0.704875 -0.741339 0 -0.671131 -0.704873 -0.0794122 -0.704875 -0.645117 -0.310666 -0.698076 -0.704667 -0.276551 -0.653425 -0.585042 -0.398895 -0.706123 -0.446427 -0.559811 -0.698079 -0.159333 -0.698073 -0.698073 -0.15933 -0.698072 -0.698076 -0.33051 -0.625387 -0.706862 -0.480107 -0.557897 -0.67694 -0.222524 -0.974927 0 -0.258816 -0.965924 -0.00229812 -0.46725 -0.884125 0 -0.652286 -0.757973 0 -0.707096 -0.707107 -0.00383759 -0.826226 -0.563339 0 -0.930879 -0.365329 0 -0.965919 -0.258804 -0.00460969 -0.993713 -0.111953 0 -0.993713 0.111953 0 -0.965919 0.258804 -0.00460969 -0.930879 0.365329 0 -0.826226 0.563339 0 -0.707096 0.707107 -0.0038376 -0.222511 0.97493 0 -0.258816 0.965924 -0.00229891 -0.467313 0.884092 0 -0.652286 0.757973 0 -0.510203 -0.136701 -0.84912 -0.373491 -0.373497 -0.84912 -0.136707 -0.510203 -0.84912 -0.136707 0.510203 -0.84912 -0.373491 0.373497 -0.84912 -0.510203 0.136701 -0.84912 0.258771 -0.876452 0.406041 0.258123 -0.836678 0.483056 0.258803 -0.0865865 0.962042 0.258153 0 0.966104 0.706097 -0.659165 0.258703 0.706091 -0.10554 0.700212 0.706095 0.553629 0.441504 0.965752 -0.258743 0.0193901 0.965751 -0.252964 0.0577375 0.96575 -0.0764814 0.247947 0.965751 0.176485 0.190206 0.96575 0.258749 0.0193906 0.965749 0.202869 0.161782 0.965752 0.202859 0.161775 0.965752 0.224704 0.129733 0.965751 0.146166 0.214385 0.965752 0.146162 0.21438 0.965753 0.112578 0.23377 0.965751 0.112581 0.233776 0.965751 0.0764806 0.247944 0.965752 0.076479 0.247939 0.965752 0.0386717 0.256569 0.965752 -0.0386715 0.256569 0.965749 -0.0386731 0.256578 0.965749 0 0.259477 0.96575 -0.112583 0.23378 0.965753 -0.112577 0.23377 0.965753 -0.146162 0.21438 0.965749 -0.146168 0.21439 0.965749 -0.176489 0.19021 0.965751 -0.176486 0.190206 0.965751 -0.202863 0.161778 0.965749 -0.241543 0.0947985 0.965748 -0.241545 0.0947995 0.965748 -0.224718 0.129741 0.706097 0.659166 0.258703 0.965751 0.252966 0.0577379 0.965751 0.241535 0.0947954 0.706101 0.659162 0.258702 0.706101 0.613242 0.354055 0.258145 0.836673 0.483053 0.258795 0.789862 0.556007 0.706085 0.398902 0.585082 0.706089 0.3989 0.585079 0.70609 0.307243 0.637996 0.706086 0.307245 0.638 0.706086 0.208724 0.676666 0.706089 0.208723 0.676664 0.706091 0.10554 0.700212 0.706096 0.10554 0.700207 0.706097 0 0.708115 0.706094 -0.307241 0.637993 0.706098 -0.30724 0.637989 0.706099 -0.398894 0.585071 0.706085 -0.398902 0.585083 0.706085 -0.481649 0.519093 0.706082 -0.481651 0.519096 0.70608 -0.55364 0.441513 0.706089 -0.553633 0.441508 0.706089 -0.613253 0.354062 0.965752 0.258743 0.01939 0.706098 0.706134 0.0529174 0.706089 0.706143 0.0529182 0.258127 0.96341 0.0721977 0.258149 0.963404 0.0721969 0.96575 0.252968 0.0577385 0.706097 0.690361 0.15757 0.706098 0.690361 0.15757 -0.642618 0.746977 0.170493 0.258695 0.950436 0.172479 0.258123 0.836677 0.483056 0.258771 0.876453 0.406038 -0.425345 0.84247 0.330645 0.25838 0.904444 0.339443 0.258568 0.934922 0.243031 0.96575 0.241537 0.0947964 0.96575 0.224711 0.129737 0.706089 0.613253 0.354062 0.706089 0.553633 0.441507 -0.425334 0.707586 0.564281 0.258397 0.746185 0.613546 0.965749 0.17649 0.190211 0.706086 0.481648 0.519093 0.706095 0.481642 0.519087 -0.642613 0.521142 0.561658 0.258586 0.677929 0.688147 -0.64261 0.225839 0.732154 0.258725 0.325844 0.909333 0.258158 0.419177 0.870428 0.258147 0.419178 0.870431 0.25815 0.544226 0.798233 0.258143 0.544227 0.798235 0.258708 0.624587 0.73686 0.258153 0 0.966104 0.258803 0.0865865 0.962042 -0.425318 0.13489 0.894935 0.258368 0.158255 0.952996 0.258555 0.256991 0.931185 0.965749 0.038673 0.256579 0.965749 0 0.259477 0.706097 0 0.708115 0.706096 -0.10554 0.700207 -0.425318 -0.13489 0.894935 0.258367 -0.158255 0.952996 0.965752 -0.0764788 0.247939 0.706091 -0.208722 0.676661 0.706089 -0.208723 0.676664 -0.64261 -0.225839 0.732154 0.258555 -0.256991 0.931185 -0.642617 -0.52114 0.561655 0.258751 -0.624578 0.736852 0.258181 -0.544221 0.798227 0.258131 -0.544229 0.798237 0.258132 -0.41918 0.870434 0.258158 -0.419176 0.870429 0.258725 -0.325844 0.909333 0.258118 -0.836679 0.483057 0.258767 -0.789866 0.556013 -0.425334 -0.707586 0.564281 0.258371 -0.746191 0.61355 0.258562 -0.677933 0.688151 0.965752 -0.202859 0.161775 0.965752 -0.224704 0.129733 0.706116 -0.613229 0.354049 0.706118 -0.659147 0.258696 -0.425366 -0.842461 0.330642 0.258412 -0.904436 0.33944 0.258761 -0.950419 0.172473 0.965748 -0.252975 0.0577396 0.706071 -0.690387 0.157576 0.706098 -0.69036 0.15757 -0.642617 -0.746977 0.170493 0.258601 -0.934913 0.24303 0.965751 -0.258744 0.0193902 0.70608 -0.706152 0.0529189 0.706071 -0.706161 0.0529194 0.258183 -0.963395 0.0721963 0.258194 -0.963392 0.0721963 0.705162 -0.705162 -0.0741154 0.705157 -0.705167 -0.0741157 0.705157 -0.674348 -0.219109 0.705158 -0.674346 -0.219109 0.705158 -0.614055 -0.354525 0.705158 -0.614055 -0.354525 0.705157 -0.526928 -0.474448 0.705156 -0.526929 -0.474448 0.705156 -0.416771 -0.573636 0.705156 -0.416771 -0.573636 0.705155 -0.288398 -0.647752 0.705159 -0.288396 -0.647749 0.705159 -0.14742 -0.693555 0.705156 -0.14742 -0.693557 0.705156 0 -0.709052 0.705156 0 -0.709052 0.705156 0.14742 -0.693557 0.705159 0.14742 -0.693555 0.705159 0.288397 -0.647749 0.705155 0.288398 -0.647752 0.705156 0.416771 -0.573636 0.705155 0.416771 -0.573636 0.705156 0.526928 -0.474448 0.705157 0.526928 -0.474448 0.705157 0.614056 -0.354525 0.705153 0.61406 -0.354528 0.705152 0.674352 -0.219111 0.70516 0.674345 -0.219108 0.70516 0.705164 -0.0741156 0.705155 0.705168 -0.0741163 0 0.997212 0.074617 0 0.997212 0.074617 -0.694746 0.694746 -0.186158 -0.694751 0.694742 -0.186156 -0.694748 0.50859 -0.508587 -0.694743 0.508592 -0.508592 -0.694742 0.186158 -0.694751 -0.694743 0.186158 -0.69475 -0.694744 -0.186156 -0.69475 -0.694735 -0.18616 -0.694757 -0.694723 -0.508607 -0.508604 -0.694748 -0.508586 -0.508592 -0.694751 -0.694742 -0.186157 -0.694747 -0.694747 -0.186157 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258817 -0.965927 0 -0.258817 -0.965927 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0.694746 -0.694746 -0.186158 0.694751 -0.694742 -0.186156 0.694748 -0.50859 -0.508587 0.694724 -0.508602 -0.508608 0.694735 -0.186158 -0.694758 0.694743 -0.186158 -0.69475 0.694743 0.186157 -0.69475 0.694742 0.186158 -0.694751 0.694743 0.508593 -0.508591 0.694748 0.508589 -0.508588 0.694751 0.694742 -0.186157 0.694747 0.694747 -0.186157 -0.694746 0.694746 -0.186158 -0.694751 0.694742 -0.186156 -0.694748 0.50859 -0.508587 -0.694741 0.508594 -0.508594 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186157 -0.694753 -0.694732 -0.186161 -0.694761 -0.694721 -0.508609 -0.508606 -0.694748 -0.508586 -0.508592 -0.694751 -0.694742 -0.186157 -0.694747 -0.694747 -0.186157 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.258817 -0.965927 0 -0.258817 -0.965927 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0.694746 -0.694746 -0.186158 0.694751 -0.694742 -0.186156 0.694748 -0.50859 -0.508587 0.694722 -0.508604 -0.50861 0.694731 -0.186159 -0.694761 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694741 0.508595 -0.508593 0.694748 0.508589 -0.508589 0.694751 0.694742 -0.186157 0.694747 0.694747 -0.186157 -0.694747 0.694747 -0.186157 -0.694752 0.694742 -0.186155 -0.694751 0.508588 -0.508585 -0.694741 0.508594 -0.508594 -0.694739 0.186157 -0.694755 -0.694747 0.186157 -0.694747 -0.694747 -0.186153 -0.694747 -0.694732 -0.186161 -0.694761 -0.694721 -0.508609 -0.508606 -0.69475 -0.508584 -0.50859 -0.694752 -0.694741 -0.186156 -0.694747 -0.694747 -0.186156 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0.694747 -0.694747 -0.186157 0.694752 -0.694742 -0.186155 0.694751 -0.508588 -0.508585 0.694722 -0.508604 -0.50861 0.694731 -0.186157 -0.694762 0.694747 -0.186157 -0.694747 0.694747 0.186155 -0.694747 0.694739 0.186159 -0.694754 0.694741 0.508596 -0.508592 0.694751 0.508587 -0.508587 0.694752 0.694741 -0.186156 0.694747 0.694747 -0.186156 -0.694747 0.694747 -0.186151 -0.694722 0.69477 -0.186163 -0.694721 0.508604 -0.508611 -0.69475 0.508589 -0.508586 -0.694752 0.186157 -0.694741 -0.694747 0.186157 -0.694747 -0.694746 -0.186158 -0.694746 -0.694752 -0.186155 -0.694741 -0.694751 -0.508587 -0.508587 -0.694741 -0.508595 -0.508592 -0.694749 -0.694745 -0.186157 -0.694747 -0.694747 -0.186157 0 0.965928 -0.258811 0 0.965928 -0.258811 0 0.707102 -0.707111 0 0.707102 -0.707111 0 0.258821 -0.965925 0 0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0.694747 -0.694747 -0.186157 0.694749 -0.694745 -0.186156 0.694741 -0.508594 -0.508594 0.69475 -0.508589 -0.508586 0.694752 -0.186157 -0.694741 0.694747 -0.186157 -0.694747 0.694746 0.186158 -0.694746 0.694752 0.186155 -0.694741 0.694751 0.508583 -0.50859 0.694722 0.508608 -0.508605 0.694721 0.694772 -0.186158 0.694747 0.694747 -0.186157 -0.69806 0.698086 -0.159335 -0.698065 0.698082 -0.159333 -0.698066 0.559819 -0.446438 -0.698059 0.559823 -0.446443 -0.698062 0.310676 -0.645128 -0.69806 0.310676 -0.64513 -0.698061 0 -0.716039 -0.69806 0 -0.716039 -0.69806 -0.310677 -0.64513 -0.698068 -0.310672 -0.645124 -0.69807 -0.559816 -0.446435 -0.698066 -0.55982 -0.446437 -0.698065 -0.698081 -0.159334 -0.69806 -0.698086 -0.159334 0 0.974927 -0.222523 0 0.974927 -0.222523 0 0.781834 -0.623487 0 0.781834 -0.623487 0 0.433882 -0.90097 0 0.433882 -0.90097 0 0 -1 0 0 -1 0 -0.433882 -0.90097 0 -0.433882 -0.90097 0 -0.781834 -0.623487 0 -0.781834 -0.623487 0 -0.974927 -0.222523 0 -0.974927 -0.222523 0.69806 -0.698086 -0.159335 0.698065 -0.698082 -0.159333 0.698066 -0.559819 -0.446438 0.69807 -0.559817 -0.446435 0.698068 -0.310673 -0.645123 0.69806 -0.310675 -0.64513 0.698061 0 -0.716039 0.69806 0 -0.716039 0.69806 0.310677 -0.64513 0.698062 0.310675 -0.645128 0.698059 0.559824 -0.446442 0.698066 0.559818 -0.446439 0.698065 0.698081 -0.159334 0.69806 0.698086 -0.159334 -0.69474 0.694753 -0.186158 -0.694744 0.694749 -0.186156 -0.694743 0.508592 -0.508592 -0.694736 0.508596 -0.508598 -0.694737 0.186159 -0.694756 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694737 -0.186159 -0.694756 -0.694736 -0.508598 -0.508597 -0.694743 -0.508591 -0.508593 -0.694744 -0.694749 -0.186157 -0.694747 -0.694747 -0.186157 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0.694747 -0.694747 -0.186156 0.694745 -0.694749 -0.186157 0.694743 -0.508592 -0.508592 0.694736 -0.508596 -0.508598 0.694737 -0.186159 -0.694756 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694737 0.186159 -0.694756 0.694736 0.508598 -0.508597 0.694743 0.508591 -0.508593 0.694744 0.694749 -0.186157 0.69474 0.694753 -0.186157 -0.69474 0.694753 -0.186158 -0.694744 0.694749 -0.186156 -0.694743 0.508592 -0.508592 -0.694739 0.508595 -0.508596 -0.69474 0.186158 -0.694753 -0.694743 0.186158 -0.69475 -0.694743 -0.186157 -0.69475 -0.69474 -0.186158 -0.694752 -0.694738 -0.508596 -0.508595 -0.694743 -0.508592 -0.508593 -0.694744 -0.694749 -0.186157 -0.694747 -0.694747 -0.186157 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.258818 -0.965926 0 0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0.694747 -0.694747 -0.186156 0.694745 -0.694749 -0.186157 0.694743 -0.508592 -0.508592 0.694739 -0.508595 -0.508596 0.69474 -0.186158 -0.694753 0.694743 -0.186158 -0.69475 0.694743 0.186157 -0.69475 0.69474 0.186158 -0.694752 0.694738 0.508596 -0.508595 0.694743 0.508592 -0.508593 0.694744 0.694749 -0.186157 0.69474 0.694753 -0.186157 -0.694733 0.694759 -0.186161 -0.694739 0.694754 -0.186158 -0.694741 0.508594 -0.508594 -0.694741 0.508594 -0.508594 -0.694739 0.186157 -0.694755 -0.694747 0.186157 -0.694747 -0.694747 -0.186155 -0.694747 -0.694739 -0.186159 -0.694754 -0.694741 -0.508594 -0.508594 -0.694741 -0.508594 -0.508594 -0.694739 -0.694754 -0.186159 -0.694733 -0.694759 -0.186159 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0.694733 -0.694759 -0.186161 0.694739 -0.694754 -0.186158 0.694741 -0.508594 -0.508594 0.694741 -0.508594 -0.508594 0.694739 -0.186157 -0.694755 0.694747 -0.186157 -0.694747 0.694747 0.186155 -0.694747 0.694739 0.186159 -0.694754 0.694741 0.508594 -0.508594 0.694741 0.508594 -0.508594 0.694739 0.694754 -0.186159 0.694733 0.694759 -0.186159 -0.694747 0.694747 -0.186152 -0.694725 0.694766 -0.186162 -0.694731 0.508599 -0.508602 -0.694741 0.508594 -0.508594 -0.694739 0.186157 -0.694755 -0.694747 0.186157 -0.694747 -0.694747 -0.186155 -0.694747 -0.694739 -0.186159 -0.694754 -0.694741 -0.508596 -0.508592 -0.694751 -0.508587 -0.508587 -0.694752 -0.694741 -0.186157 -0.694747 -0.694747 -0.186157 0 0.965928 -0.258813 0 0.965928 -0.258813 0 0.707105 -0.707109 0 0.707105 -0.707109 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0.694746 -0.694746 -0.186158 0.694752 -0.694741 -0.186155 0.694751 -0.508588 -0.508585 0.694741 -0.508594 -0.508594 0.694739 -0.186157 -0.694755 0.694747 -0.186157 -0.694747 0.694747 0.186155 -0.694747 0.694739 0.186159 -0.694754 0.694741 0.508592 -0.508595 0.694731 0.5086 -0.5086 0.694725 0.694768 -0.186158 0.694747 0.694747 -0.186157 -0.694747 0.694747 -0.186157 -0.694752 0.694742 -0.186155 -0.694751 0.508588 -0.508585 -0.694741 0.508594 -0.508594 -0.694739 0.186157 -0.694755 -0.694747 0.186157 -0.694747 -0.694747 -0.186153 -0.694747 -0.694732 -0.186161 -0.694761 -0.694721 -0.508609 -0.508606 -0.69475 -0.508584 -0.50859 -0.694752 -0.694741 -0.186156 -0.694747 -0.694747 -0.186156 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258817 -0.965926 0 0.258817 -0.965926 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0.694747 -0.694747 -0.186157 0.694752 -0.694742 -0.186155 0.694751 -0.508588 -0.508585 0.694722 -0.508604 -0.50861 0.694731 -0.186157 -0.694762 0.694747 -0.186157 -0.694747 0.694747 0.186155 -0.694747 0.694739 0.186159 -0.694754 0.694741 0.508596 -0.508592 0.694751 0.508587 -0.508587 0.694752 0.694741 -0.186156 0.694747 0.694747 -0.186156 -3.68258e-05 0.103912 -0.994587 0.320225 0.385319 -0.865439 0 0.394582 -0.918861 0 0.477896 -0.878417 0.000480464 0.47958 -0.877498 0.00615317 0.487006 -0.873377 5.39745e-05 0.106377 -0.994326 0 0.106037 -0.994362 0.0432958 0.207717 -0.97723 0.166635 0.200787 -0.965359 0 0.303415 -0.952859 0.0414711 -0.203459 -0.978205 0.159786 -0.20524 -0.96558 0 -0.303417 -0.952858 0.0129382 0 -0.999916 0.0129382 0 -0.999916 -3.68258e-05 -0.103912 -0.994587 4.53952e-05 -0.106144 -0.994351 0 -0.106324 -0.994332 0.00884903 -0.490534 -0.871377 0.000480445 -0.479595 -0.87749 0 -0.477911 -0.878408 0 -0.394582 -0.918861 0.32023 -0.385318 -0.865438 0 -0.488468 -0.872582 0 -0.587785 -0.809017 0 -0.587785 -0.809017 0 -0.743145 -0.66913 0 -0.743145 -0.66913 0 -0.866025 -0.5 0 -0.866025 -0.5 0 -0.951057 -0.309017 0 -0.951057 -0.309017 0 -0.994522 -0.104528 0 -0.994522 -0.104528 0 0.490555 -0.87141 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.743145 -0.669131 0 0.743145 -0.669131 0 0.866025 -0.5 0 0.866025 -0.5 0 0.951056 -0.309017 0 0.951056 -0.309017 0 0.994522 -0.104528 0 0.994522 -0.104528 0 0.999164 0.0408838 -0.179823 0.975399 0.127515 0 0.996033 0.0889816 0 0.972476 0.233001 -0.0915341 0.960439 0.263018 0 0.947887 0.318608 0 0.902397 0.430906 -0.0716563 0.906866 0.415281 0.0844542 0.808825 0.581953 0 0.821005 0.570921 0 0.995521 -0.0945445 0 0.995521 -0.0945445 0 0.959926 -0.280253 0 0.959926 -0.280253 0 0.89001 -0.455941 0 0.89001 -0.455941 0 0.788272 -0.615327 0 0.788272 -0.615327 0 0.658349 -0.752713 0 0.658349 -0.752713 0 -0.995185 0.0980168 0 -0.995185 0.0980168 0 -0.95694 0.290285 0 -0.95694 0.290285 0 -0.881921 0.471397 0 -0.881921 0.471397 0 -0.77301 0.634393 0 -0.77301 0.634393 0 -0.634394 0.77301 0 -0.634394 0.77301 0 -0.471397 0.881921 0 -0.471397 0.881921 0 -0.290285 0.95694 0 -0.290285 0.95694 0 -0.0980171 0.995185 0 -0.0980171 0.995185 0 0.0980171 0.995185 0 0.0980171 0.995185 0 0.290285 0.95694 0 0.290285 0.95694 0 0.471397 0.881921 0 0.471397 0.881921 0 0.634394 0.77301 0 0.634394 0.77301 0 0.77301 0.634394 0 0.77301 0.634394 0 0.881921 0.471397 0 0.881921 0.471397 0 0.95694 0.290285 0 0.95694 0.290285 0 0.995185 0.0980172 0 0.995185 0.0980172 0 0.997204 -0.0747298 0.293504 0.950721 -0.0999248 0 0.907359 -0.420356 0 0.936235 -0.351375 0.345756 0.8924 -0.289958 0 0.967835 -0.251587 0 0.983929 -0.178558 0.181116 0.851703 -0.491731 0.181113 0.851703 -0.491731 0 0.81772 -0.575617 0 0.772417 -0.635116 0.345757 0.697311 -0.627861 0 0.701798 -0.712376 0 0.6466 -0.762829 0.293502 0.561898 -0.773387 0 0.56332 -0.826239 0 0.433884 -0.900969 0.293502 0.388823 -0.873311 0 0.33733 -0.941387 0 0.266037 -0.963963 0.345759 0.195088 -0.917819 0 0.163817 -0.986491 0.181116 0 -0.983462 0.181116 0 -0.983462 0 0.0896406 -0.995974 0.345759 -0.195088 -0.917819 0 -0.163817 -0.986491 0 -0.0896406 -0.995974 0.293502 -0.388823 -0.873312 0 -0.33733 -0.941387 0 -0.266037 -0.963963 0.293497 -0.561899 -0.773388 0 -0.56332 -0.826239 0 -0.433884 -0.900969 0 -0.817718 -0.575619 0 -0.772417 -0.635115 0.345758 -0.697311 -0.627861 0 -0.701798 -0.712376 0 -0.646598 -0.762831 0.181118 -0.851703 -0.491731 0.181111 -0.851703 -0.491732 0 -0.907358 -0.420359 0 -0.936235 -0.351374 0.345751 -0.892401 -0.289959 0 -0.967834 -0.251588 0 -0.98393 -0.178555 0.293495 -0.950724 -0.0999245 0 -0.997204 -0.0747301 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.997204 0.0747301 0.293495 -0.950724 0.0999245 0 -0.98393 0.178555 0 -0.967834 0.251588 0.34575 -0.892402 0.289959 0 -0.936235 0.351374 0.181117 -0.851703 0.491731 0.18111 -0.851704 0.491731 0 -0.907358 0.420359 0.345758 -0.697311 0.627861 0 -0.772417 0.635115 0 -0.817718 0.575619 0.293497 -0.561899 0.773388 0 -0.646598 0.762831 0 -0.701798 0.712376 0.293502 -0.388823 0.873311 0 -0.433884 0.900969 0 -0.56332 0.826239 0 -0.0896406 0.995974 0 -0.163817 0.986491 0.345759 -0.195088 0.917819 0 -0.266037 0.963963 0 -0.33733 0.941387 0.181116 0 0.983462 0.181115 0 0.983462 0 0.0896406 0.995974 0 0.163817 0.986491 0.345759 0.195088 0.917819 0 0.266037 0.963963 0 0.33733 0.941387 0.293502 0.388823 0.873311 0 0.433884 0.900969 0 0.56332 0.826239 0.293502 0.561898 0.773387 0 0.6466 0.762829 0 0.701798 0.712376 0.345757 0.697311 0.627861 0 0.772417 0.635116 0 0.907359 0.420356 0.181115 0.851703 0.491731 0.181112 0.851703 0.491731 0 0.81772 0.575617 0 0.936235 0.351375 0.345755 0.8924 0.289958 0 0.967835 0.251587 0 0.983929 0.178558 0.293504 0.950721 0.0999248 0 0.997204 0.0747298 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.658349 -0.752713 0 -0.658349 -0.752713 0 -0.788272 -0.615327 0 -0.788272 -0.615327 0 -0.89001 -0.455941 0 -0.89001 -0.455941 0 -0.959926 -0.280253 0 -0.959926 -0.280253 0 -0.995521 -0.0945441 0 -0.995521 -0.0945441 0 -0.844282 -0.5359 0 -0.811726 0.584039 -0.0716581 -0.818894 0.569454 0 -0.868549 0.495603 0 -0.909204 0.416352 -0.117001 -0.915779 0.384265 0 -0.947887 0.318608 0 -0.972477 0.233 -0.136561 -0.973369 0.184129 0 -0.991563 0.129628 0 -0.999727 -0.0233756 -0.210812 -0.975508 -0.062785 0 -0.999164 0.0408838 0 -0.90302 -0.429598 -0.128346 -0.884829 -0.447889 0 -0.934687 -0.355472 0 -0.972813 -0.231591 -0.170032 -0.95067 -0.259454 0 -0.987026 -0.160563 -0.0859646 -0.780461 -0.619266 0 -0.793423 -0.60867 0 -0.719488 -0.694505 -0.0397668 -0.648341 -0.760311 0 -0.642609 -0.766194 0 0.642609 -0.766194 0.0397681 0.648341 -0.760311 -0.0364267 0.777735 -0.627536 0 0.783361 -0.621567 0 0.884702 -0.466158 -0.0793435 0.889395 -0.450201 0 0.844282 -0.5359 0 0.9953 -0.0968369 -0.157188 0.98553 -0.0634307 0 0.987026 -0.160563 0 0.957967 -0.286878 -0.118548 0.957915 -0.261431 0 0.934686 -0.355473 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 -1 0 0 -1 0 -0.994522 0.104528 0 -0.994522 0.104528 0 -0.951057 0.309017 0 -0.951057 0.309017 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.743145 0.66913 0 -0.743145 0.66913 0 -0.587785 0.809017 0 -0.587785 0.809017 0 -0.406737 0.913545 0 -0.406737 0.913545 0 -0.207912 0.978148 0 -0.207912 0.978148 0 0 1 0 0 1 0 0.207912 0.978148 0 0.207912 0.978148 0 0.406737 0.913545 0 0.406737 0.913545 0 0.587785 0.809017 0 0.587785 0.809017 0 0.743145 0.669131 0 0.743145 0.669131 0 0.866025 0.5 0 0.866025 0.5 0 0.951056 0.309017 0 0.951056 0.309017 0 0.994522 0.104528 0 0.994522 0.104528 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.262694 0.964879 0 -0.262694 0.964879 0 -0.0884883 0.996077 0 -0.0884883 0.996077 0 0.0884883 0.996077 0 0.0884883 0.996077 0 0.262694 0.964879 0 0.262694 0.964879 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.988864 0.14882 0 -0.988864 0.14882 9.84879e-07 -0.988865 0.148817 0 -0.988865 0.148818 1.40669e-07 -0.988865 0.148819 -6.77464e-07 -0.988864 0.148821 1.24122e-06 -0.988865 0.148817 -1.012e-06 -0.988864 0.14882 0 0.988865 0.148819 -1.17006e-06 0.988864 0.14882 0 0.988864 0.148819 0 0.988864 0.148819 2.21301e-07 0.988865 0.148818 6.22695e-07 0.988865 0.148818 0 0.258819 0.965926 0 0.258819 0.965926 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -0.707107 -0.707107 0 -0.707107 -0.707107 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.707107 -0.707107 0 0.707107 -0.707107 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.379309 -0.92527 0 0.379309 -0.92527 0 -0.0806427 -0.996743 0 -0.0806427 -0.996743 0 -0.523121 -0.852259 0 -0.523121 -0.852259 0 0.523121 -0.852259 0 0.523121 -0.852259 0 0.0806425 -0.996743 0 0.0806425 -0.996743 0 -0.37931 -0.92527 0 -0.37931 -0.92527 0 -0.285317 -0.958433 0 -0.285317 -0.958433 0 -0.718693 -0.695327 0 -0.718693 -0.695327 0 -0.967336 -0.253496 0 -0.967336 -0.253496 0 0.967336 -0.253496 0 0.967336 -0.253496 0 0.718693 -0.695327 0 0.718693 -0.695327 0 0.285317 -0.958433 0 0.285317 -0.958433 0 -0.955811 0.293983 -0.160372 -0.9853 0.0588645 -0.0135698 -0.965836 0.258798 0 -0.999833 0.0182595 0 -0.955811 0.293983 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.955813 0.293975 -0.0251219 0.96562 0.25874 -0.00206602 0.998487 0.0549517 0 0.999833 0.0182595 -0.0364892 0.972345 0.230679 0.0318829 0.792951 0.608451 0 0.831471 0.555568 0 0.608761 0.793354 0.0213376 0.555443 0.831281 -0.0318822 0.258687 0.965435 0 0.195091 0.980785 0 0.423825 0.905744 0 0.423825 0.905744 0 0.293523 0.955952 0 0.293523 0.955952 0 -0.293522 0.955952 0 -0.293522 0.955952 0 -0.423825 0.905744 0 -0.423825 0.905744 0 -0.941871 0.335975 0 -0.941871 0.335975 0 -0.745717 0.666263 0 -0.745717 0.666263 0 -0.439525 0.89823 0 -0.439525 0.89823 0 0.439525 0.89823 0 0.439525 0.89823 0 0.745718 0.666262 0 0.745718 0.666262 0 0.941869 0.33598 0 0.941869 0.33598 0 -0.976296 0.216441 0 -0.976296 0.216441 0 -0.793354 0.608761 0 -0.793354 0.608761 0 -0.461748 0.887011 0 -0.461748 0.887011 0 0.461749 0.887011 0 0.461749 0.887011 0 0.793354 0.608761 0 0.793354 0.608761 0 0.976296 0.216441 0 0.976296 0.216441 0 0.507473 0.861668 0 0.507473 0.861668 0 0.77576 0.631028 0 0.77576 0.631028 0 0.946944 0.321398 0 0.946944 0.321398 0 -0.946943 0.3214 0 -0.946943 0.3214 0 -0.775762 0.631026 0 -0.775762 0.631026 0 -0.507473 0.861668 0 -0.507473 0.861668 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.965925 -0.258822 0 -0.965925 -0.258822 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.258819 -0.965926 0 0.258819 -0.965926 0 -0.980785 -0.195092 0 -0.83147 -0.555569 -0.120403 -0.776863 -0.61805 0 -0.856694 -0.515825 -0.006668 -0.870119 -0.492797 -0.0159654 -0.876814 -0.480564 0 -0.903758 -0.428044 0 -0.980785 -0.195092 -0.055189 0.902376 -0.427402 -0.00668096 0.870128 -0.49278 0 0.856677 -0.515853 0 0.782559 -0.622576 -0.0701495 0.829422 -0.554201 0 0.888978 -0.457949 0 0.980786 -0.195089 0 0.980786 -0.195089 0 -0.925996 0.377534 -0.167276 -0.969438 0.179468 -0.0317188 -0.96544 0.258689 0 -0.999836 0.0181021 0 -0.925996 0.377534 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.925996 0.377534 -0.104083 0.96068 0.257413 -0.0169565 0.989017 0.146828 0 0.999837 0.0180763 -0.0444435 0.947767 0.315851 0.0636692 0.791743 0.607528 0 0.831469 0.555571 0 0.608764 0.793351 0.0426469 0.555066 0.830712 -0.0636674 0.258293 0.963966 0 0.195091 0.980785 0 -0.652354 0.757914 0.00524758 -0.653269 0.757108 -0.00521557 -0.898769 0.438391 0 -0.899315 0.437301 0 0.898781 0.438397 -0.00523535 0.899302 0.437297 0.00528676 0.652344 0.757905 0 0.653278 0.757118 0 0.0123247 0.999924 0.00591057 0.0110302 0.999922 -0.00586855 -0.406921 0.913445 0.0117555 -0.410443 0.91181 -0.0116756 -0.751559 0.659562 0.0175217 -0.755747 0.654629 -0.0174105 -0.95842 0.28483 0 -0.959664 0.28115 0 0.958564 0.284878 -0.0177242 0.959512 0.281111 0.018045 0.751488 0.6595 -0.0120245 0.755809 0.654682 0.0119648 0.406899 0.913395 -0.00597319 0.410464 0.911857 0.00594546 -0.0123246 0.999906 0 -0.0110305 0.999939 0 -1 0 0 -1 0 0.195093 0.980785 0 0.195093 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831468 0.555573 0 0.831468 0.555573 0 0.980787 0.195082 0 0.980787 0.195082 0 0 1 0 0 1 0 -0.980785 0.195091 0 -0.980785 0.195091 0 -0.831468 0.555573 0 -0.831468 0.555573 0 -0.555573 0.831468 0 -0.555573 0.831468 0 -0.195091 0.980785 0 -0.195091 0.980785 0 -1 0 0 -1 0 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.258819 -0.965926 0 0.258819 -0.965926 0 1 0 0 1 0 0 0 1 0 0 1 0 0.195089 0.980786 0 0.195089 0.980786 0 0.555568 0.831471 0 0.555568 0.831471 0 0.83147 0.55557 0 0.83147 0.55557 0 0.980787 0.195083 0 0.980787 0.195083 0 -0.980785 0.195092 0 -0.980785 0.195092 0 -0.83147 0.55557 0 -0.83147 0.55557 0 -0.555573 0.831468 0 -0.555573 0.831468 0 -0.195087 0.980786 0 -0.195087 0.980786 0 -1 0 0 -1 0 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 0 -1 0 0 -1 0 0.965926 -0.258818 0 0.965926 -0.258818 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.258821 -0.965925 0 0.258821 -0.965925 0 1 0 0 1 0 0 -0.707112 -0.707102 0 -0.707112 -0.707102 0 -0.698581 -0.69857 0.15487 -0.698579 -0.698572 0.15487 -0.698579 -0.567671 0.435588 -0.698582 -0.567668 0.435588 -0.698581 -0.330395 0.634684 -0.69858 -0.330396 0.634684 -0.694751 -0.186156 -0.694742 -0.69475 -0.186153 -0.694744 -0.694749 -0.508588 -0.508588 -0.694752 -0.508592 -0.50858 -0.694752 -0.694741 -0.186158 -0.694752 -0.694741 -0.186158 -0.707112 -0.183012 0.683008 -0.707112 -0.183012 0.683008 -0.707111 0 -0.707102 -0.707111 0 -0.707102 -0.707111 0 -0.707102 -0.700439 -0.672225 0.23979 -0.700434 -0.672228 0.239794 -0.700435 -0.53223 0.475523 -0.700437 -0.53223 0.475521 -0.700436 -0.313696 0.64108 -0.700436 -0.313696 0.64108 -0.694752 0.694741 -0.186158 -0.694752 0.694741 -0.186158 -0.694751 0.508587 -0.508586 -0.694751 0.508587 -0.508586 -0.694751 0.186156 -0.694742 -0.694751 0.186155 -0.694742 -0.707114 -0.699226 0.10523 -0.707114 -0.699226 0.10523 -0.707112 0.707102 0 -0.707112 0.707102 0 -0.701471 -0.674885 0.229061 -0.701472 -0.674884 0.229062 -0.701472 -0.552883 0.449731 -0.701472 -0.552883 0.449731 -0.701471 -0.361675 0.614109 -0.70147 -0.361676 0.61411 -0.698581 0.330395 0.634683 -0.698581 0.330395 0.634684 -0.698581 0.567669 0.435587 -0.698579 0.56767 0.43559 -0.698579 0.698572 0.154871 -0.698581 0.69857 0.154869 -0.705721 -0.186116 0.683607 -0.705721 -0.186116 0.683608 -0.705721 -0.0626931 0.705711 -0.705721 -0.062693 0.705711 -0.705721 0.0626931 0.705711 -0.705721 0.0626931 0.70571 -0.705722 0.186116 0.683606 -0.70572 0.186116 0.683608 -0.707112 0.183012 0.683008 -0.707112 0.183011 0.683007 -0.701469 0.361676 0.614111 -0.701468 0.361676 0.614112 -0.701468 0.552885 0.449734 -0.70147 0.552885 0.449732 -0.701469 0.674887 0.22906 -0.701469 0.674887 0.229061 -0.700436 0.313696 0.64108 -0.700435 0.313697 0.641081 -0.700435 0.532231 0.475522 -0.700437 0.532229 0.475522 -0.700437 0.672225 0.239794 -0.700436 0.672227 0.239793 -0.707111 0.699229 0.10523 -0.707111 0.699229 0.10523 0.698073 0.698073 0.159333 0.698078 0.698069 0.159331 0.698077 0.559811 0.446431 0.69806 0.559821 0.446445 0.698062 0.310677 0.645127 0.698054 0.310679 0.645135 0.698061 0 0.716039 0.698061 0 0.716039 0.698066 -0.310673 0.645125 0.698062 -0.310675 0.645128 0.698059 -0.559824 0.446442 0.698076 -0.559808 0.446435 0.698079 -0.698069 0.159332 0.698074 -0.698074 0.159332 0 -0.974927 0.222524 0 -0.974927 0.222524 0 -0.781834 0.623487 0 -0.781834 0.623487 0 -0.43388 0.900971 0 -0.43388 0.900971 0 0 1 0 0 1 0 0.433884 0.900969 0 0.433884 0.900969 0 0.781834 0.623487 0 0.781834 0.623487 0 0.974927 0.222524 0 0.974927 0.222524 -0.698073 -0.698073 0.159333 -0.698078 -0.698069 0.159331 -0.698077 -0.559811 0.446431 -0.69806 -0.559821 0.446445 -0.698062 -0.310674 0.645129 -0.698066 -0.310674 0.645125 -0.698061 0 0.716039 -0.698061 0 0.716039 -0.698054 0.310681 0.645134 -0.698062 0.310675 0.645128 -0.698059 0.559824 0.446442 -0.698076 0.559808 0.446435 -0.698079 0.698069 0.159332 -0.698074 0.698074 0.159332 0.694747 0.694747 0.186151 0.694725 0.694767 0.186161 0.69473 0.508598 0.508604 0.694751 0.508587 0.508587 0.694752 0.186157 0.694741 0.694747 0.186157 0.694747 0.694746 -0.186158 0.694746 0.694752 -0.186155 0.694741 0.694751 -0.508587 0.508587 0.694751 -0.508587 0.508587 0.694752 -0.694741 0.186156 0.694747 -0.694747 0.186156 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258821 0.965925 0 -0.258821 0.965925 0 0.258821 0.965925 0 0.258821 0.965925 0 0.707102 0.707111 0 0.707102 0.707111 0 0.965928 0.258811 0 0.965928 0.258811 -0.694747 -0.694747 0.186157 -0.694752 -0.694742 0.186155 -0.694751 -0.508587 0.508587 -0.694751 -0.508587 0.508587 -0.694752 -0.186157 0.694741 -0.694747 -0.186157 0.694747 -0.694746 0.186158 0.694746 -0.694752 0.186155 0.694741 -0.694751 0.508583 0.50859 -0.694731 0.5086 0.5086 -0.694725 0.694769 0.186157 -0.694747 0.694747 0.186156 0.69806 0.698086 0.159336 0.698065 0.698082 0.159333 0.698066 0.559819 0.446438 0.698059 0.559823 0.446443 0.698062 0.310676 0.645128 0.69806 0.310676 0.64513 0.698061 0 0.716039 0.69806 0 0.716039 0.69806 -0.310677 0.64513 0.698068 -0.310672 0.645124 0.69807 -0.559816 0.446435 0.698066 -0.55982 0.446437 0.698065 -0.698081 0.159335 0.69806 -0.698086 0.159335 0 -0.974927 0.222524 0 -0.974927 0.222524 0 -0.781834 0.623487 0 -0.781834 0.623487 0 -0.433882 0.90097 0 -0.433882 0.90097 0 0 1 0 0 1 0 0.433882 0.90097 0 0.433882 0.90097 0 0.781834 0.623487 0 0.781834 0.623487 0 0.974927 0.222524 0 0.974927 0.222524 -0.69806 -0.698086 0.159336 -0.698065 -0.698082 0.159333 -0.698066 -0.559819 0.446438 -0.69807 -0.559817 0.446435 -0.698068 -0.310673 0.645123 -0.69806 -0.310675 0.64513 -0.698061 0 0.716039 -0.69806 0 0.716039 -0.69806 0.310677 0.64513 -0.698062 0.310675 0.645128 -0.698059 0.559824 0.446442 -0.698066 0.559818 0.446439 -0.698065 0.698081 0.159335 -0.69806 0.698086 0.159335 0.69474 0.694753 0.186158 0.694744 0.694749 0.186156 0.694743 0.508592 0.508592 0.694739 0.508595 0.508596 0.69474 0.186158 0.694753 0.694743 0.186158 0.69475 0.694743 -0.186157 0.69475 0.69474 -0.186158 0.694752 0.694738 -0.508596 0.508595 0.694743 -0.508592 0.508593 0.694745 -0.694749 0.186157 0.694747 -0.694747 0.186157 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965926 0.258819 0 0.965926 0.258819 -0.694747 -0.694747 0.186156 -0.694745 -0.694749 0.186157 -0.694743 -0.508592 0.508592 -0.694739 -0.508595 0.508596 -0.69474 -0.186158 0.694753 -0.694743 -0.186158 0.69475 -0.694743 0.186157 0.69475 -0.69474 0.186158 0.694752 -0.694738 0.508596 0.508595 -0.694743 0.508592 0.508593 -0.694745 0.694749 0.186157 -0.69474 0.694753 0.186157 0.69474 0.694753 0.186158 0.694744 0.694749 0.186156 0.694743 0.508592 0.508592 0.694739 0.508595 0.508596 0.69474 0.186159 0.694752 0.69474 0.186159 0.694753 0.69474 -0.186159 0.694753 0.69474 -0.186158 0.694752 0.694738 -0.508596 0.508595 0.694743 -0.508592 0.508593 0.694745 -0.694749 0.186157 0.694747 -0.694747 0.186157 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.258819 0.965926 0 -0.258819 0.965926 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707107 0.707106 0 0.707107 0.707106 0 0.965926 0.258819 0 0.965926 0.258819 -0.694747 -0.694747 0.186156 -0.694745 -0.694749 0.186157 -0.694743 -0.508592 0.508592 -0.694739 -0.508595 0.508596 -0.69474 -0.186159 0.694752 -0.69474 -0.186159 0.694753 -0.69474 0.186159 0.694753 -0.69474 0.186158 0.694752 -0.694738 0.508596 0.508595 -0.694743 0.508592 0.508593 -0.694745 0.694749 0.186157 -0.69474 0.694753 0.186157 0.694733 0.694759 0.186162 0.694739 0.694754 0.186159 0.694741 0.508594 0.508594 0.694741 0.508594 0.508594 0.694739 0.186157 0.694755 0.694747 0.186157 0.694747 0.694747 -0.186155 0.694747 0.694739 -0.186159 0.694754 0.694741 -0.508594 0.508594 0.694741 -0.508594 0.508594 0.694739 -0.694753 0.18616 0.694733 -0.694759 0.18616 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965925 0.258821 0 0.965925 0.258821 -0.694733 -0.694759 0.186162 -0.694739 -0.694754 0.186159 -0.694741 -0.508594 0.508594 -0.694741 -0.508594 0.508594 -0.694739 -0.186157 0.694755 -0.694747 -0.186157 0.694747 -0.694747 0.186155 0.694747 -0.694739 0.186159 0.694754 -0.694741 0.508594 0.508594 -0.694741 0.508594 0.508594 -0.694739 0.694753 0.18616 -0.694733 0.694759 0.18616 0.694747 0.694747 0.186152 0.694725 0.694766 0.186162 0.694731 0.508599 0.508602 0.694741 0.508594 0.508594 0.694739 0.186157 0.694755 0.694747 0.186157 0.694747 0.694747 -0.186155 0.694747 0.694739 -0.186159 0.694754 0.694741 -0.508596 0.508592 0.694751 -0.508587 0.508587 0.694752 -0.694741 0.186157 0.694747 -0.694747 0.186157 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707105 0.707109 0 0.707105 0.707109 0 0.965928 0.258813 0 0.965928 0.258813 -0.694746 -0.694746 0.186158 -0.694752 -0.694741 0.186155 -0.694751 -0.508588 0.508585 -0.694741 -0.508594 0.508594 -0.694739 -0.186157 0.694755 -0.694747 -0.186157 0.694747 -0.694747 0.186155 0.694747 -0.694739 0.186159 0.694754 -0.694741 0.508592 0.508595 -0.694731 0.5086 0.5086 -0.694725 0.694768 0.186158 -0.694747 0.694747 0.186157 0.694746 0.694746 0.186158 0.694752 0.694741 0.186155 0.694751 0.508588 0.508585 0.694741 0.508594 0.508594 0.694739 0.186157 0.694755 0.694747 0.186157 0.694747 0.694747 -0.186153 0.694747 0.694732 -0.186161 0.694761 0.694721 -0.508609 0.508606 0.69475 -0.508584 0.50859 0.694752 -0.694741 0.186157 0.694747 -0.694747 0.186157 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.258814 0.965927 0 -0.258814 0.965927 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707109 0.707105 0 0.707109 0.707105 0 0.965925 0.258821 0 0.965925 0.258821 -0.694746 -0.694746 0.186158 -0.694752 -0.694741 0.186155 -0.694751 -0.508588 0.508585 -0.694722 -0.508604 0.50861 -0.694731 -0.186157 0.694762 -0.694747 -0.186157 0.694747 -0.694747 0.186155 0.694747 -0.694739 0.186159 0.694754 -0.694741 0.508596 0.508592 -0.694751 0.508587 0.508587 -0.694752 0.694741 0.186157 -0.694747 0.694747 0.186157 0.694746 0.694746 0.186158 0.694751 0.694742 0.186156 0.694748 0.50859 0.508587 0.694743 0.508592 0.508592 0.694742 0.186158 0.694751 0.69474 0.186159 0.694753 0.69474 -0.186157 0.694753 0.694735 -0.18616 0.694757 0.694723 -0.508607 0.508604 0.694748 -0.508586 0.508592 0.694751 -0.694742 0.186157 0.694747 -0.694747 0.186157 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.258818 0.965926 0 -0.258818 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707108 0.707105 0 0.707108 0.707105 0 0.965925 0.258821 0 0.965925 0.258821 -0.694746 -0.694746 0.186158 -0.694751 -0.694742 0.186156 -0.694748 -0.50859 0.508587 -0.694724 -0.508602 0.508608 -0.694735 -0.186159 0.694758 -0.69474 -0.186159 0.694753 -0.69474 0.186159 0.694753 -0.694742 0.186158 0.694751 -0.694743 0.508593 0.508591 -0.694748 0.508589 0.508588 -0.694751 0.694742 0.186157 -0.694747 0.694747 0.186157 0.694746 0.694746 0.186158 0.694751 0.694742 0.186156 0.694748 0.50859 0.508587 0.694743 0.508592 0.508592 0.694742 0.186158 0.694751 0.694743 0.186158 0.69475 0.694744 -0.186156 0.69475 0.694735 -0.18616 0.694757 0.694723 -0.508607 0.508604 0.694748 -0.508586 0.508592 0.694751 -0.694742 0.186157 0.694747 -0.694747 0.186157 0 -0.965925 0.258821 0 -0.965925 0.258821 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.258817 0.965927 0 -0.258817 0.965927 0 0.258819 0.965926 0 0.258819 0.965926 0 0.707108 0.707105 0 0.707108 0.707105 0 0.965925 0.258821 0 0.965925 0.258821 -0.694746 -0.694746 0.186158 -0.694751 -0.694742 0.186156 -0.694748 -0.50859 0.508587 -0.694724 -0.508602 0.508608 -0.694735 -0.186158 0.694758 -0.694743 -0.186158 0.69475 -0.694743 0.186157 0.69475 -0.694742 0.186158 0.694751 -0.694743 0.508593 0.508591 -0.694748 0.508589 0.508588 -0.694751 0.694742 0.186157 -0.694747 0.694747 0.186157 -0.939694 0 -0.342018 -0.939694 0 -0.342018 -0.923696 0.183736 -0.336195 -0.923695 0.183727 -0.336202 -0.783068 0.523233 -0.336202 -0.783067 0.523236 -0.336199 -0.523233 0.783069 -0.336199 -0.523233 0.783069 -0.336199 -0.183735 0.923694 -0.336199 -0.183735 0.923695 -0.336199 -0.244167 -0.911251 -0.33167 -0.244168 -0.911251 -0.331668 -0.667084 -0.667081 -0.331666 -0.66708 -0.667083 -0.331671 -0.91125 -0.244169 -0.33167 -0.911252 -0.244166 -0.331666 0 0.939692 -0.342021 0 0.939692 -0.342021 0 -0.939692 -0.342021 0 -0.939692 -0.342021 0.183737 0.923694 -0.336199 0.183736 0.923694 -0.336199 0.523229 0.783072 -0.336199 0.52323 0.783072 -0.336199 0.783069 0.523233 -0.336199 0.783072 0.523231 -0.336196 0.923698 0.183727 -0.336195 0.923693 0.183735 -0.336203 0.911249 -0.244169 -0.331673 0.911249 -0.244171 -0.33167 0.667083 -0.667079 -0.331671 0.667083 -0.66708 -0.331671 0.244169 -0.91125 -0.33167 0.244168 -0.91125 -0.33167 0.939691 0 -0.342025 0.939691 0 -0.342025 -0.939694 0 -0.342018 -0.939694 0 -0.342018 -0.923696 0.183736 -0.336195 -0.923695 0.183728 -0.336203 -0.783069 0.52323 -0.336202 -0.783068 0.523234 -0.336199 -0.523233 0.783069 -0.336199 -0.523231 0.783072 -0.336196 -0.183731 0.923697 -0.336195 -0.183735 0.923695 -0.336199 -0.244169 -0.911251 -0.331668 -0.24417 -0.911251 -0.331667 -0.667084 -0.667082 -0.331664 -0.66708 -0.667083 -0.331668 -0.91125 -0.244168 -0.331669 -0.911252 -0.244166 -0.331666 0 0.939692 -0.342021 0 0.939692 -0.342021 0 -0.939693 -0.34202 0 -0.939693 -0.34202 0.183733 0.923695 -0.336199 0.183737 0.923696 -0.336196 0.52323 0.783073 -0.336196 0.523227 0.783073 -0.336199 0.783071 0.523231 -0.336199 0.783073 0.523229 -0.336196 0.923697 0.183728 -0.336195 0.923693 0.183735 -0.336203 0.911249 -0.244168 -0.331673 0.91125 -0.244171 -0.33167 0.667083 -0.667081 -0.331668 0.667083 -0.66708 -0.33167 0.244171 -0.91125 -0.331669 0.24417 -0.911251 -0.331668 0.939691 0 -0.342025 0.939691 0 -0.342025 0 -0.212859 0.977083 0 -0.212859 0.977083 0 -0.6 0.8 0 -0.6 0.8 0 0.6 0.8 0 0.6 0.8 0 0.21286 0.977083 0 0.21286 0.977083 0 -0.374391 -0.927271 0.0153905 -0.359157 -0.93315 -0.0142515 0.0505737 -0.998619 0.0284882 0.0993864 -0.994641 -0.0262023 0.465999 -0.884397 0.0392759 0.536348 -0.843083 -0.0358392 0.794657 -0.606 0 0.823909 -0.566723 0 0.932682 -0.360701 -0.0431569 0.975601 -0.215268 0 0.988492 -0.15127 0 -0.997212 0.074617 -0.0511113 -0.995277 -0.0825319 0 -0.987635 -0.156771 0 -0.930655 -0.365899 -0.0447596 -0.853259 -0.519564 0 -0.821535 -0.570158 0 -0.679372 -0.733794 -0.036466 -0.530518 -0.846889 0.0243262 -0.466022 -0.884439 -0.0262402 -0.0952369 -0.995109 0.0131257 -0.0505743 -0.998634 -0.014079 0.360463 -0.932667 0 0.374391 -0.927271 0.705155 0.705169 0.0741161 0.70516 0.705164 0.0741158 0.705159 0.674345 0.219108 0.705152 0.674352 0.21911 0.705153 0.61406 0.354528 0.705158 0.614055 0.354525 0.705157 0.526928 0.474448 0.705157 0.526928 0.474448 0.705156 0.416771 0.573636 0.705156 0.416771 0.573635 0.705155 0.288398 0.647752 0.705159 0.288396 0.647749 0.705159 0.14742 0.693555 0.705156 0.14742 0.693557 0.705156 0 0.709052 0.705156 0 0.709052 0.705156 -0.14742 0.693557 0.705159 -0.14742 0.693555 0.705159 -0.288397 0.647749 0.705155 -0.288398 0.647752 0.705156 -0.416771 0.573636 0.705156 -0.416771 0.573636 0.705156 -0.526928 0.474448 0.705157 -0.526928 0.474447 0.705157 -0.614056 0.354526 0.705159 -0.614055 0.354525 0.705159 -0.674346 0.219108 0.705156 -0.674349 0.219109 0.705157 -0.705167 0.074116 0.705162 -0.705162 0.0741151 0.258771 0.876453 -0.406038 0.258123 0.836678 -0.483056 0.258803 0.0865865 -0.962042 0.258153 0 -0.966104 0.706099 0.659164 -0.258703 0.706109 0.105537 -0.700195 0.70608 -0.55364 -0.441513 0.965752 0.258743 -0.0193901 0.96575 0.252968 -0.0577384 0.965751 0.0764807 -0.247944 0.965749 -0.176489 -0.19021 0.965751 -0.258744 -0.0193903 0.965751 -0.202863 -0.161778 0.965752 -0.202859 -0.161775 0.965752 -0.224704 -0.129733 0.965749 -0.146168 -0.21439 0.965751 -0.146166 -0.214386 0.96575 -0.112581 -0.233777 0.96575 -0.112582 -0.23378 0.96575 -0.0764815 -0.247947 0.96575 -0.0764815 -0.247947 0.96575 -0.0386729 -0.256578 0.96575 0.0386729 -0.256578 0.965749 0.038673 -0.256578 0.965749 0 -0.259477 0.965751 0.112581 -0.233776 0.96575 0.112581 -0.233777 0.965751 0.146166 -0.214386 0.965751 0.146166 -0.214385 0.965751 0.176485 -0.190206 0.965749 0.17649 -0.190211 0.965749 0.202869 -0.161782 0.965751 0.241536 -0.0947957 0.96575 0.241537 -0.0947964 0.96575 0.224711 -0.129737 0.706099 -0.659164 -0.258703 0.965748 -0.252975 -0.0577399 0.965748 -0.241543 -0.0947988 0.706117 -0.659147 -0.258696 0.706117 -0.613228 -0.354048 0.258115 -0.836679 -0.483057 0.258767 -0.789866 -0.556013 0.706085 -0.398902 -0.585083 0.706114 -0.398886 -0.585058 0.706114 -0.307233 -0.637974 0.706094 -0.307241 -0.637993 0.706091 -0.208722 -0.676661 0.706106 -0.208718 -0.676647 0.706108 -0.105538 -0.700195 0.706096 -0.105539 -0.700207 0.706097 0 -0.708115 0.706086 0.307245 -0.638 0.706106 0.307235 -0.637982 0.706104 0.398892 -0.585066 0.706085 0.398903 -0.585082 0.706085 0.481648 -0.519094 0.706095 0.481642 -0.519087 0.706094 0.553629 -0.441504 0.706089 0.553633 -0.441507 0.706089 0.613253 -0.354062 0.965752 -0.258743 -0.0193901 0.706071 -0.706161 -0.0529196 0.70608 -0.706152 -0.0529187 0.258194 -0.963392 -0.0721961 0.258183 -0.963395 -0.0721965 0.965751 -0.252964 -0.0577372 0.706099 -0.690359 -0.15757 0.706071 -0.690386 -0.157576 -0.642617 -0.746977 -0.170493 0.258761 -0.950419 -0.172473 0.258123 -0.836678 -0.483056 0.258771 -0.876452 -0.406041 -0.425366 -0.842461 -0.330642 0.258408 -0.904437 -0.33944 0.258599 -0.934913 -0.24303 0.965748 -0.241545 -0.0947995 0.965748 -0.224717 -0.129741 0.706089 -0.613253 -0.354062 0.706089 -0.553633 -0.441507 -0.425334 -0.707586 -0.564281 0.25837 -0.746191 -0.61355 0.965751 -0.176486 -0.190206 0.706085 -0.481649 -0.519094 0.706082 -0.481651 -0.519096 -0.642617 -0.52114 -0.561655 0.258562 -0.677933 -0.688151 -0.64261 -0.225839 -0.732154 0.258725 -0.325844 -0.909333 0.258158 -0.419177 -0.870428 0.258132 -0.419179 -0.870435 0.258131 -0.544228 -0.798238 0.258181 -0.544222 -0.798226 0.258751 -0.624578 -0.736852 0.258153 0 -0.966104 0.258803 -0.0865865 -0.962042 -0.425318 -0.13489 -0.894935 0.258368 -0.158255 -0.952996 0.258555 -0.256991 -0.931185 0.965749 -0.038673 -0.256579 0.965749 0 -0.259477 0.706097 0 -0.708115 0.706096 0.10554 -0.700207 -0.425318 0.13489 -0.894935 0.258367 0.158255 -0.952996 0.96575 0.0764816 -0.247947 0.706086 0.208724 -0.676666 0.706106 0.208718 -0.676647 -0.64261 0.225839 -0.732154 0.258555 0.256991 -0.931185 -0.642613 0.521142 -0.561658 0.258708 0.624587 -0.73686 0.258143 0.544227 -0.798235 0.25815 0.544226 -0.798233 0.258147 0.419178 -0.870431 0.258158 0.419176 -0.870429 0.258725 0.325844 -0.909333 0.258147 0.836672 -0.483053 0.258795 0.789862 -0.556007 -0.425334 0.707586 -0.564281 0.258397 0.746185 -0.613546 0.258586 0.677929 -0.688147 0.965752 0.202859 -0.161775 0.965752 0.224704 -0.129733 0.7061 0.613243 -0.354056 0.706101 0.659162 -0.258702 -0.425345 0.84247 -0.330645 0.258377 0.904444 -0.339444 0.258695 0.950436 -0.172479 0.965751 0.252966 -0.057738 0.706097 0.690361 -0.15757 0.706099 0.690359 -0.15757 -0.642617 0.746978 -0.170493 0.258566 0.934922 -0.243031 0.96575 0.258749 -0.0193905 0.706089 0.706143 -0.052918 0.706098 0.706134 -0.0529176 0.258149 0.963404 -0.0721972 0.258127 0.963409 -0.0721973 0.510203 0.136713 -0.849119 0.373498 0.373492 -0.849119 0.136707 0.510203 -0.84912 0.136707 -0.510203 -0.84912 0.373498 -0.373492 -0.849119 0.510203 -0.136713 -0.849119 0.258817 0.965926 0 0.258817 0.965926 0 0.707113 0.707101 0 0.707113 0.707101 0 0.965923 0.258828 0 0.965923 0.258828 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.186155 0.694747 -0.694747 0.186159 0.694749 -0.694744 0.508598 0.50859 -0.694741 0.50859 0.50859 -0.694746 0.694745 0.186163 -0.694746 0.694746 0.186163 -0.694746 0.694746 -0.186163 -0.694746 0.694745 -0.186163 -0.694746 0.508594 -0.508586 -0.694747 0.508593 -0.508593 -0.694741 0.186156 -0.69475 -0.694744 0.186158 -0.694746 -0.694746 0.510203 0.136713 -0.849119 0.373498 0.373492 -0.849119 0.136707 0.510203 -0.84912 0.136707 -0.510203 -0.84912 0.373498 -0.373492 -0.849119 0.510203 -0.136713 -0.849119 0.258817 0.965926 0 0.258817 0.965926 0 0.707113 0.707101 0 0.707113 0.707101 0 0.965923 0.258828 0 0.965923 0.258828 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.186155 0.694747 -0.694747 0.186159 0.694749 -0.694744 0.508598 0.50859 -0.694741 0.50859 0.50859 -0.694746 0.694745 0.186163 -0.694746 0.694746 0.186163 -0.694746 0.694746 -0.186163 -0.694746 0.694745 -0.186163 -0.694746 0.508594 -0.508586 -0.694747 0.508593 -0.508593 -0.694741 0.186156 -0.69475 -0.694744 0.186158 -0.694746 -0.694746 0.510203 0.136713 -0.849119 0.373498 0.373492 -0.849119 0.136707 0.510203 -0.84912 0.13671 -0.510202 -0.84912 0.373498 -0.373492 -0.849119 0.510203 -0.136713 -0.849119 0.258817 0.965926 0 0.258817 0.965926 0 0.707113 0.707101 0 0.707113 0.707101 0 0.965923 0.258828 0 0.965923 0.258828 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.707113 -0.707101 0 0.707113 -0.707101 0 0.258822 -0.965925 0 0.258822 -0.965925 0 0.186155 0.694747 -0.694747 0.186159 0.694749 -0.694744 0.508598 0.50859 -0.694741 0.50859 0.50859 -0.694746 0.694745 0.186163 -0.694746 0.694746 0.186163 -0.694746 0.694746 -0.186163 -0.694746 0.694745 -0.186163 -0.694746 0.508594 -0.508586 -0.694747 0.508594 -0.508591 -0.694743 0.186159 -0.694745 -0.694747 0.186158 -0.694746 -0.694746 -0.707105 0 0.707108 -0.707105 0 0.707108 -0.694746 -0.694746 0.186159 -0.694746 -0.694746 0.186159 -0.694746 -0.50859 0.50859 -0.694746 -0.50859 0.50859 -0.694746 -0.186156 0.694747 -0.694745 -0.186159 0.694748 -0.694745 0.186157 0.694748 -0.694746 0.186159 0.694746 -0.704062 0.432305 0.563391 -0.718851 0.491555 0.491555 -0.704062 0.563391 0.432304 -0.694746 0.694746 0.186159 -0.694746 0.694746 0.186159 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.69527 -0.205071 -0.688873 -0.69527 -0.205071 -0.688872 -0.69527 -0.51656 -0.499765 -0.69527 -0.51656 -0.499765 -0.69527 -0.695272 -0.1822 -0.695271 -0.695271 -0.182198 -0.695271 0.695271 -0.1822 -0.69527 0.695272 -0.182198 -0.69527 0.51656 -0.499765 -0.69527 0.51656 -0.499765 -0.69527 0.205071 -0.688872 -0.69527 0.205072 -0.688873 -0.706913 0 -0.7073 -0.706913 0 -0.7073 -0.698654 -0.698654 -0.154161 -0.639676 -0.75914 -0.120501 -0.706473 -0.658662 -0.258961 -0.701807 -0.585234 -0.406162 -0.698653 0.267862 -0.663426 -0.698653 0.267861 -0.663426 -0.698653 -0.036187 -0.714545 -0.698653 -0.0361872 -0.714545 -0.698653 -0.333519 -0.632968 -0.698655 -0.333517 -0.632968 -0.706753 -0.480629 -0.51913 -0.687533 -0.55563 -0.467518 -0.736834 -0.576102 -0.353812 -0.705145 0.460079 -0.539535 -0.705144 0.460079 -0.539536 -0.706614 0.538058 -0.459554 -0.755389 0.513319 -0.407298 -0.707033 0.576293 -0.409866 -0.706989 0.59704 -0.379091 -0.707059 0.597037 -0.378964 -0.705145 0.640298 -0.304613 -0.617247 0.701962 -0.355324 -0.706999 0.661024 -0.251396 -0.705144 0.689787 -0.164213 -0.581323 0.784965 -0.21423 -0.706918 0.698118 -0.113565 -0.706378 0.706371 -0.0455057 -0.706488 0.706263 -0.0454566 -0.706736 0.706888 0.0288799 -0.70681 0.706812 0.0289213 -0.706695 0.701549 0.0917144 -0.612033 0.777052 0.146992 -0.70695 0.548619 0.446362 -0.762726 0.530962 0.369227 -0.706533 0.688202 0.16489 -0.706925 0.67043 0.225348 -0.62753 0.717949 0.301255 -0.706163 0.643761 0.294798 -0.706849 0.606481 0.364068 -0.776007 0.514796 0.364414 -0.698863 0.152249 0.698864 -0.698863 0.152249 0.698864 -0.698862 0.429154 0.572205 -0.698864 0.429152 0.572205 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.694746 0.186156 0.694747 -0.694746 0.186156 0.694747 -0.704062 0.432307 0.563389 -0.740614 0.475127 0.475126 -0.704062 0.56339 0.432306 -0.694746 0.694747 0.186157 -0.694744 0.694749 0.18616 -0.707104 0.707109 0 -0.707104 0.707109 0 -0.700212 0.700217 -0.139281 -0.700214 0.700214 -0.139285 -0.700214 0.593614 -0.396639 -0.700213 0.593615 -0.396639 -0.707106 0.500001 -0.500001 -0.707106 0.500001 -0.500001 -0.697195 0.375016 -0.610968 -0.697195 0.375016 -0.610968 -0.697195 0.0578111 -0.714547 -0.697195 0.0578115 -0.714547 -0.697195 -0.27192 -0.663309 -0.697195 -0.271921 -0.663308 -0.705518 -0.466567 -0.533442 -0.705518 -0.466567 -0.533442 -0.705518 -0.558642 -0.436078 -0.705518 -0.558642 -0.436077 -0.705519 -0.630743 -0.323122 -0.705518 -0.630743 -0.323122 -0.705518 -0.680292 -0.198613 -0.705519 -0.680291 -0.198613 -0.705519 -0.705517 -0.0670026 -0.705518 -0.705518 -0.0670029 -0.697195 0.27192 -0.663309 -0.697195 0.27192 -0.663309 -0.697195 -0.0578113 -0.714547 -0.697195 -0.0578114 -0.714547 -0.697194 -0.375016 -0.610969 -0.697196 -0.375017 -0.610967 -0.707107 -0.5 -0.5 -0.707107 -0.5 -0.5 -0.700215 -0.593614 -0.396639 -0.700214 -0.593613 -0.396641 -0.700214 -0.700215 -0.139283 -0.700215 -0.700215 -0.139282 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.694747 -0.694747 0.186157 -0.694746 -0.694748 0.186156 -0.694746 -0.50859 0.50859 -0.694746 -0.50859 0.50859 -0.694746 -0.186157 0.694747 -0.694746 -0.186157 0.694747 -0.707106 0 0.707107 -0.707106 0 0.707107 -0.698863 -0.429153 0.572204 -0.698863 -0.429153 0.572204 -0.698863 -0.152249 0.698864 -0.698863 -0.152249 0.698864 -0.705439 -0.70544 -0.0686348 -0.593245 -0.80336 -0.0517053 -0.706917 -0.69812 -0.113565 -0.705439 -0.67898 -0.203331 -0.625459 -0.752728 -0.205432 -0.707 -0.661023 -0.251394 -0.705439 -0.62705 -0.330399 -0.654741 -0.674379 -0.341361 -0.707058 -0.597038 -0.378964 -0.787161 -0.46584 -0.404192 -0.708917 -0.574162 -0.409603 -0.707105 -0.589951 -0.389822 -0.705439 -0.455463 -0.543056 -0.705439 -0.455463 -0.543056 -0.707094 -0.508764 -0.491098 -0.681324 -0.573406 -0.454976 -0.307997 0.948735 0.0709897 -0.697313 -0.257462 -0.66893 -0.697313 -0.257462 -0.66893 -0.697313 0.0712656 -0.713215 -0.697313 0.0712658 -0.713215 -0.697313 0.384732 -0.604761 -0.697315 0.384732 -0.604759 -0.704542 0.564735 -0.429761 -0.720049 0.571729 -0.393262 -0.693538 0.66429 -0.27879 -0.706362 0.660199 -0.255323 -0.703013 0.702993 -0.10758 -0.699627 0.466772 0.540967 -0.699629 0.466771 0.540966 -0.699808 0.642408 0.31238 -0.874975 0.405213 0.264992 -0.70624 0.207806 0.676788 -0.706239 0.207806 0.676789 -0.70624 0.300057 0.641242 -0.706235 0.300059 0.641246 -0.813711 -0.529147 0.240576 -0.950187 -0.298408 0.089984 -0.99153 -0.12464 0.0365154 -0.856071 -0.493326 0.154183 -0.70423 -0.661992 0.256567 -0.698659 -0.540786 0.46843 -0.698663 -0.540784 0.468426 -0.698666 -0.293671 0.652398 -0.698666 -0.293671 0.652398 -0.698666 0.00789168 0.715404 -0.698666 0.0078917 0.715404 -0.705058 0.275937 -0.653262 -0.701661 0.145091 -0.697581 -0.705429 0.144512 -0.693892 -0.707093 0.214551 -0.673786 -0.775051 0.247547 -0.581391 -0.704116 0.280187 -0.652469 -0.704121 -0.280185 -0.652465 -0.705276 -0.279705 -0.651423 -0.773343 -0.246691 -0.584024 -0.701642 -0.145276 -0.697562 -0.705423 -0.144333 -0.693935 -0.707097 -0.214551 -0.673781 -0.759296 0.610799 0.224488 -0.856071 0.493326 0.154183 -0.950187 0.298408 0.089984 -0.991523 0.124689 0.0365306 -0.698666 -0.00789172 0.715404 -0.698666 -0.00789169 0.715404 -0.698666 0.293671 0.652398 -0.698671 0.293668 0.652394 -0.698674 0.540775 0.46842 -0.698659 0.540788 0.468426 -0.706228 0.6445 0.293022 -0.706235 -0.300058 0.641246 -0.70624 -0.300057 0.641242 -0.706239 -0.207806 0.676789 -0.706244 -0.207805 0.676784 -0.793259 -0.547579 0.266266 -0.706096 -0.592642 0.387562 -0.699629 -0.466771 0.540966 -0.699627 -0.466772 0.540967 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.695267 0.205072 -0.688876 0.695268 0.205072 -0.688875 0.69527 0.51656 -0.499766 0.69527 0.51656 -0.499766 0.69527 0.695271 -0.1822 0.695271 0.695271 -0.182199 0.706909 0 -0.707304 0.706909 0 -0.707304 0.695271 -0.695271 -0.1822 0.69527 -0.695272 -0.1822 0.69527 -0.51656 -0.499766 0.69527 -0.51656 -0.499766 0.695268 -0.205072 -0.688875 0.695267 -0.205072 -0.688876 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.707077 0.505806 -0.494169 0.703085 0.560652 -0.437425 0.692048 0.566793 -0.447007 0.702387 0.557022 -0.443147 0.707101 0.500004 -0.500004 0.707101 0.500004 -0.500004 0.697186 -0.271923 -0.663317 0.697194 -0.271919 -0.66331 0.697193 0.0578113 -0.714548 0.697195 0.0578114 -0.714547 0.697192 0.375017 -0.610971 0.697191 0.375018 -0.610972 0.705509 0.466572 -0.533448 0.705514 0.466569 -0.533444 0.705515 0.558644 -0.436079 0.705513 0.558646 -0.436081 0.705513 0.630747 -0.323124 0.70551 0.63075 -0.323126 0.70551 0.6803 -0.198615 0.705509 0.6803 -0.198615 0.70551 0.705526 -0.0670037 0.705511 0.705524 -0.0670035 0.697194 -0.375016 -0.610969 0.697192 -0.375018 -0.610971 0.697195 -0.0578113 -0.714547 0.697193 -0.0578116 -0.714548 0.697194 0.27192 -0.66331 0.697186 0.271922 -0.663318 0.707105 -0.500001 -0.500001 0.707105 -0.500001 -0.500001 0.707082 -0.505782 -0.494186 0.691174 -0.569787 -0.444547 0.702525 -0.556889 -0.443094 0.702397 -0.557012 -0.443143 0.849121 0.136707 0.5102 0.849121 0.373495 0.37349 0.84912 0.510202 0.136706 0.84912 -0.510202 0.136706 0.849121 -0.373495 0.37349 0.849121 -0.136707 0.5102 0.849121 0.136707 0.5102 0.849122 0.373492 0.373492 0.849122 0.5102 0.136706 0.849121 -0.5102 0.136711 0.849121 -0.373493 0.373493 0.849121 -0.136709 0.5102 0.849121 0.136707 0.5102 0.849121 0.373495 0.37349 0.84912 0.510202 0.136706 0.84912 -0.510202 0.136706 0.849121 -0.373495 0.37349 0.849121 -0.136707 0.5102 0.849121 0.136707 0.5102 0.849122 0.373492 0.373492 0.849122 0.5102 0.136706 0.849121 -0.5102 0.136711 0.849121 -0.373493 0.373493 0.849121 -0.136709 0.5102 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.994522 0.104529 0 0.994522 0.104529 0 0.951056 0.309017 0 0.951056 0.309017 0 0.866025 0.5 0 0.866025 0.5 0 0.743145 0.66913 0 0.743145 0.66913 0 0.587785 0.809017 0 0.587785 0.809017 0 0.406737 0.913546 0 0.406737 0.913546 0 0.207912 0.978148 0 0.207912 0.978148 0 0 1 0 0 1 0 -0.207912 0.978148 0 -0.207912 0.978148 0 -0.406736 0.913546 0 -0.406736 0.913546 0 -0.587785 0.809017 0 -0.587785 0.809017 0 -0.743145 0.669131 0 -0.743145 0.669131 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.951057 0.309017 0 -0.951057 0.309017 0 -0.994522 0.104528 0 -0.994522 0.104528 -0.939695 0.331646 -0.0835764 -0.939756 0.331486 -0.083516 -0.940168 0.329925 -0.0850449 -0.94237 0.323024 -0.0871405 -0.951832 0.292738 -0.0912207 -0.948237 0.302791 -0.0957303 -0.939561 0.331515 -0.085571 -0.939511 0.329141 -0.094796 -0.941633 0.316445 -0.114845 -0.939351 0.323031 -0.115203 -0.939228 0.330262 -0.0936946 -0.938798 0.331784 -0.0926153 -0.938165 0.333862 -0.0915617 -0.938414 0.333385 -0.0907362 -0.939135 0.332117 -0.0878888 -0.943811 0.324012 -0.0650892 -0.939538 0.335768 -0.0672882 -0.941894 0.329809 -0.0637379 -0.938576 0.338193 -0.0685578 -0.940246 0.338388 -0.0378369 -0.934407 0.350372 -0.064208 -0.947252 0.315563 -0.0559764 -0.944885 0.322242 -0.0579004 -0.938499 0.339297 -0.0640074 -0.943042 0.326839 -0.0620274 -0.940991 0.332385 -0.0636898 -0.941704 0.330437 -0.0632862 -0.941424 0.331174 -0.0636016 -0.939849 -0.337894 -0.0501267 -0.93969 -0.337978 -0.0524739 -0.940057 -0.33695 -0.052512 -0.940187 -0.336591 -0.0524913 -0.939549 -0.340012 -0.0404851 -0.940215 -0.337207 -0.0478253 -0.940417 -0.336696 -0.0474577 -0.940015 -0.337609 -0.0489043 -0.939571 -0.341991 -0.0157349 -0.985127 -0.171515 -0.0103748 -0.948581 -0.31487 -0.032405 -0.940592 -0.337518 -0.0370059 -0.944552 0.312597 -0.10052 -0.941853 0.319435 -0.104276 -0.905057 0.394316 -0.159331 -0.939477 0.32266 -0.115213 -0.939609 0.309003 -0.147146 -0.941652 0.306198 -0.139764 -0.93623 0.304083 -0.176089 -0.939508 0.299158 -0.166818 -0.939673 0.285133 -0.188982 -0.939456 0.284978 -0.190289 -0.940163 0.268214 -0.210132 -0.939281 0.269136 -0.21288 -0.949923 0.217765 -0.224108 -0.957628 0.203652 -0.203652 -0.944779 0.237201 -0.226115 -0.941551 0.245547 -0.230626 -0.940036 0.225595 -0.255813 -0.938054 0.23113 -0.258135 -0.935464 0.237595 -0.26164 -0.933474 0.242108 -0.264596 -0.938021 0.242313 -0.247791 -0.93934 0.243106 -0.241951 -0.940778 0.248227 -0.230913 -0.937153 0.252462 -0.240848 -0.938606 0.251262 -0.236402 -0.939753 0.250869 -0.232227 -0.939327 0.252451 -0.232235 -0.940331 0.249091 -0.231799 -0.942683 0.229176 -0.242544 -0.940845 0.231377 -0.247537 -0.92937 0.238859 -0.281458 -0.939594 0.226939 -0.256247 -0.939608 0.205295 -0.273845 -0.941844 0.206299 -0.265275 -0.935831 0.188059 -0.298086 -0.939501 0.187871 -0.286432 -0.939672 0.164722 -0.299804 -0.939547 0.164299 -0.300427 -0.939886 0.140151 -0.311404 -0.939313 0.139879 -0.313249 -0.939622 0.0752792 -0.333831 -0.938548 0.0783539 -0.336137 -0.93728 0.0810077 -0.339034 -0.935624 0.0839858 -0.342863 -0.931717 0.0901361 -0.351822 -0.927831 0.0956893 -0.360519 -0.932858 0.0966663 -0.347032 -0.936148 0.097692 -0.337761 -0.937599 0.0984538 -0.333488 -0.947246 0.106859 -0.30217 -0.937299 0.107 -0.331696 -0.939734 0.107833 -0.324458 -0.939335 0.108649 -0.325339 -0.941311 0.105169 -0.320739 -0.944041 0.101134 -0.313941 -0.951607 0.0912792 -0.29345 -0.951129 0.0918674 -0.294813 -0.940805 0.0859276 -0.327876 -0.935853 0.077119 -0.343849 -0.942344 0.0767886 -0.325718 -0.93966 -0.094103 -0.328912 -0.939686 -0.0949103 -0.328606 -0.939513 -0.0926452 -0.329747 -0.938952 -0.0906043 -0.331903 -0.932624 -0.0795116 -0.351982 -0.926768 -0.0857445 -0.365718 -0.934979 -0.0760796 -0.346448 -0.956713 -0.0411001 -0.288115 -0.936657 -0.0660512 -0.343964 -0.939638 -0.0620305 -0.336502 -0.939348 -0.0211241 -0.342315 -0.939592 -0.020667 -0.341671 -0.93964 0.00644585 -0.342103 -0.939672 0.0066107 -0.342013 -0.939493 0.0338261 -0.340895 -0.935414 0.0281633 -0.352432 -0.942037 0.0598607 -0.330127 -0.939607 0.0546003 -0.337872 -0.939666 0.0751216 -0.333743 -0.940707 0.0761686 -0.330558 -0.93961 -0.0620225 -0.336579 -0.942617 -0.0622588 -0.328019 -0.936933 -0.063001 -0.343785 -0.939877 -0.084233 -0.330962 -0.940805 -0.0859273 -0.327876 -0.942378 -0.0867974 -0.323095 -0.94067 -0.0902308 -0.327105 -0.939873 -0.0929442 -0.328633 -0.93972 -0.0943719 -0.328665 -0.939692 -0.0951912 -0.328507 -0.939606 -0.108593 -0.324574 -0.942231 -0.0997024 -0.319783 -0.934979 -0.139216 -0.32624 -0.939484 -0.127934 -0.317809 -0.939671 -0.153014 -0.305948 -0.939736 -0.152634 -0.305941 -0.939282 -0.177523 -0.293659 -0.939207 -0.243516 -0.242053 -0.938769 -0.243251 -0.244011 -0.938968 -0.242447 -0.244048 -0.939388 -0.240394 -0.244462 -0.939578 -0.239119 -0.244982 -0.939683 -0.23796 -0.245705 -0.939691 -0.237301 -0.24631 -0.939384 -0.177231 -0.293506 -0.939704 -0.199626 -0.277681 -0.942105 -0.206797 -0.263957 -0.936601 -0.226742 -0.267145 -0.939669 -0.232056 -0.25134 -0.939693 -0.237167 -0.246434 -0.939702 -0.237849 -0.245739 -0.939913 -0.238657 -0.244146 -0.941036 -0.238366 -0.240068 -0.946918 -0.23194 -0.222601 -0.938629 -0.262129 -0.224196 -0.935375 -0.267125 -0.231769 -0.94028 -0.258927 -0.220978 -0.939652 -0.244731 -0.239084 -0.939519 -0.244076 -0.240274 -0.944778 -0.237203 -0.226117 -0.941552 -0.245545 -0.230625 -0.917995 -0.307283 -0.250723 -0.941583 -0.255585 -0.219314 -0.939486 -0.260908 -0.222022 -0.939671 -0.277621 -0.199863 -0.939833 -0.27677 -0.200283 -0.938953 -0.294427 -0.177987 -0.939423 -0.292934 -0.177971 -0.93969 -0.305576 -0.153643 -0.941987 -0.306078 -0.137755 -0.936524 -0.324885 -0.131808 -0.93967 -0.322249 -0.114786 -0.936492 -0.339286 -0.0887046 -0.93002 -0.358257 -0.0819503 -0.932283 -0.3529 -0.0794341 -0.938199 -0.333925 -0.0909762 -0.938933 -0.331476 -0.0923542 -0.94186 -0.320464 -0.101012 -0.937431 -0.333811 -0.0989584 -0.938616 -0.330201 -0.0998349 -0.939669 -0.326701 -0.101437 -0.939624 -0.326785 -0.101578 -0.940744 -0.324405 -0.0988013 -0.94212 -0.321122 -0.0963867 -0.9441 -0.316154 -0.0933913 -0.947182 -0.308049 -0.0891733 -0.942369 -0.323029 -0.0871383 -0.940167 -0.329931 -0.0850427 -0.936024 -0.344829 -0.0703681 -0.942931 -0.325674 -0.0694112 -0.940652 -0.332263 -0.0690952 -0.939601 -0.335327 -0.0686013 -0.938731 -0.337401 -0.0703233 -0.936611 -0.342518 -0.0737718 0 -0.975353 0.220651 0.0572596 -0.969894 0.236699 0 -0.953638 0.300957 0 -0.926513 0.376262 0.0646928 -0.916864 0.393923 0 -0.892032 0.451972 0 -0.853027 0.521866 0.0711007 -0.838571 0.540132 0 -0.806701 0.59096 0 -0.756851 0.653588 0.0764967 -0.73721 0.67132 0 -0.699908 0.714233 0 -0.640542 0.767923 0.0808803 -0.615598 0.783899 0 -0.574497 0.818507 0 -0.507195 0.861831 0.0842497 -0.477097 0.874803 0 -0.433805 0.901007 0 -0.360356 0.932815 0.0866114 -0.325517 0.941561 0 -0.281574 0.95954 0 -0.203931 0.978985 0.0879642 -0.16502 0.98236 0 -0.121854 0.992548 0 0 1 0.172489 0.0404922 0.984179 0 -0.0420809 0.999114 0 0.326745 0.945113 0.146688 0.35556 0.923071 0 0.28064 0.959813 0 0.165662 0.986183 0.159629 0.200375 0.966627 0 0.120888 0.992666 0 0.617621 0.786476 0.12057 0.635127 0.762939 0 0.573701 0.819065 0 0.478799 0.877925 0.133664 0.501812 0.854587 0 0.432928 0.901428 0 0.840699 0.541503 0.0941999 0.848728 0.520371 0 0.806123 0.591748 0 0.739376 0.673292 0.107413 0.75184 0.650538 0 0.699212 0.714914 0 0.971488 0.237087 0.0676236 0.972906 0.221093 0 0.953344 0.301885 0 0.918789 0.39475 0.0809336 0.923108 0.375927 0 0.891592 0.452839 0 0.975138 -0.2216 0.0547574 0.970031 -0.236732 0 0.953344 -0.301885 0 0.926146 -0.377164 0.0625045 0.916992 -0.393978 0 0.891593 -0.452839 0 0.852519 -0.522696 0.0692314 0.838681 -0.540204 0 0.806123 -0.591747 0 0.756215 -0.654324 0.0749399 0.737297 -0.671399 0 0.699212 -0.714914 0 0.639794 -0.768546 0.0796334 0.61566 -0.783978 0 0.573701 -0.819065 0 0.506356 -0.862325 0.0833169 0.477134 -0.874872 0 0.432928 -0.901429 0 0.359447 -0.933165 0.0859891 0.325535 -0.941612 0 0.28064 -0.959813 0 0.202979 -0.979183 0.0876549 0.165024 -0.982387 0 0.120887 -0.992666 0 0.0411083 -0.999155 0.0883108 0 -0.996093 0 -0.0420809 -0.999114 0 -0.326745 -0.945113 0.150696 -0.356241 -0.922162 0 -0.281574 -0.95954 0 -0.165662 -0.986183 0.163613 -0.201183 -0.965793 0 -0.121854 -0.992548 0 -0.617621 -0.786476 0.124622 -0.635549 -0.761937 0 -0.574497 -0.818506 0 -0.478799 -0.877925 0.137694 -0.502364 -0.853622 0 -0.433805 -0.901007 0 -0.840699 -0.541503 0.0982815 -0.848897 -0.51934 0 -0.806701 -0.59096 0 -0.739376 -0.673293 0.111485 -0.752133 -0.649513 0 -0.699907 -0.714234 0 -0.971488 -0.237087 0.0717383 -0.97284 -0.220082 0 -0.953638 -0.300956 0 -0.918789 -0.39475 0.0850364 -0.923157 -0.3749 0 -0.892033 -0.451971 -0.422646 0.896235 0.134661 -0.427363 0.893097 0.140495 -0.422555 0.895716 0.138352 -0.444701 0.873411 0.198482 -0.421794 -0.896487 0.135652 -0.427229 -0.893169 0.140446 -0.424207 -0.894784 0.139324 -0.423068 -0.895836 0.135984 -0.422431 -0.896614 0.132801 -0.227019 0.657435 0.718499 -0.422538 0.556399 0.715459 -0.422477 0.519987 0.742379 -0.503855 0.473746 0.722284 -0.354686 0.473435 0.806261 -0.422542 0.434881 0.795197 -0.422444 0.392402 0.817045 -0.504656 0.352009 0.788297 -0.362299 0.335028 0.869768 -0.422547 0.302177 0.854484 -0.42241 0.254373 0.869979 -0.503953 0.221581 0.834825 -0.369597 0.188606 0.909849 -0.422544 0.161707 0.8918 -0.422365 0.109576 0.899778 -0.501737 0.0854141 0.860793 -0.376586 0.0380821 0.925599 -0.422553 0.0170741 0.906178 -0.422327 -0.0381439 0.90564 -0.497986 -0.0534118 0.865539 -0.383265 -0.112549 0.916756 -0.422553 -0.127995 0.897255 -0.422279 -0.184857 0.887417 -0.492663 -0.191748 0.848832 -0.38965 -0.259319 0.883701 -0.422557 -0.269772 0.865257 -0.422229 -0.326659 0.845587 -0.485727 -0.326419 0.810876 -0.395739 -0.398391 0.827451 -0.422559 -0.404611 0.811008 -0.422174 -0.459779 0.781263 -0.477112 -0.454284 0.752323 -0.401543 -0.526147 0.749621 -0.422563 -0.529045 0.735902 -0.422119 -0.580678 0.696153 -0.466744 -0.572291 0.674265 -0.407067 -0.639295 0.652379 -0.422562 -0.639874 0.641874 -0.422055 -0.686138 0.592523 -0.454527 -0.677535 0.578232 -0.412312 -0.734939 0.53839 -0.422565 -0.734248 0.531336 -0.421992 -0.773354 0.473124 -0.440357 -0.76731 0.466176 -0.417289 -0.810655 0.41074 -0.422575 -0.809735 0.407135 -0.421932 -0.840002 0.34113 -0.424113 -0.839176 0.340458 -0.421993 -0.864567 0.272847 -0.422572 -0.864405 0.272465 -0.421856 -0.884316 0.200056 -0.405673 -0.891004 0.203815 -0.423539 -0.895059 0.139584 -0.594072 0.514658 0.618227 -0.422508 0.633737 0.647969 -0.422536 0.66361 0.617321 -0.222929 0.764573 0.604757 -0.575948 0.618195 0.5349 -0.422535 0.730627 0.536328 -0.422534 0.753755 0.503307 -0.21883 0.852221 0.475219 -0.55693 0.708068 0.43413 -0.422556 0.808083 0.410425 -0.42253 0.824517 0.376351 -0.320931 0.877156 0.357213 -0.485211 0.82194 0.298302 -0.422575 0.864043 0.273607 -0.422527 0.874075 0.239715 -0.256066 0.946742 0.19522 -0.406312 0.895838 0.17996 -0.397675 0.895812 -0.198433 -0.466179 0.863043 -0.194509 -0.531464 0.826021 -0.187713 -0.427374 0.89309 -0.140504 -0.420201 -0.896594 -0.139824 -0.423914 -0.895052 -0.138487 -0.423041 -0.895857 -0.135928 -0.422465 -0.896611 -0.132713 -0.40606 0.895947 -0.179982 -0.264933 0.943783 -0.1977 -0.422526 0.874076 -0.239716 -0.422575 0.864043 -0.273607 -0.485211 0.82194 -0.298302 -0.32093 0.877156 -0.357213 -0.42253 0.824517 -0.376351 -0.422556 0.808083 -0.410424 -0.492258 0.760241 -0.423929 -0.329877 0.804799 -0.493438 -0.422533 0.753756 -0.503308 -0.422533 0.730628 -0.536329 -0.497682 0.680279 -0.538083 -0.338479 0.711578 -0.615701 -0.422536 0.66361 -0.617321 -0.422508 0.633737 -0.647969 -0.501538 0.584019 -0.638264 -0.346748 0.6001 -0.720864 -0.422538 0.5564 -0.715458 -0.422477 0.519987 -0.742379 -0.503856 0.473746 -0.722284 -0.354688 0.473435 -0.80626 -0.422542 0.434881 -0.795196 -0.422444 0.392401 -0.817045 -0.504656 0.352009 -0.788297 -0.362298 0.335027 -0.869768 -0.422542 0.302179 -0.854486 -0.422549 0.161706 -0.891798 -0.421994 0.232578 -0.876259 -0.55508 0.233436 -0.79837 -0.369599 0.188606 -0.909848 -0.422553 0.0170741 -0.906178 -0.42199 0.0895199 -0.90217 -0.54289 0.101521 -0.833645 -0.376586 0.038082 -0.925599 -0.421982 -0.0558398 -0.904883 -0.530156 -0.0356804 -0.847149 -0.34136 -0.132739 -0.930513 -0.422355 -0.110452 -0.899676 -0.421971 -0.199767 -0.884327 -0.516858 -0.17458 -0.838081 -0.359133 -0.277793 -0.890985 -0.422397 -0.255221 -0.869737 -0.421964 -0.338556 -0.841027 -0.502979 -0.311455 -0.806231 -0.374659 -0.413909 -0.829644 -0.422434 -0.393199 -0.816667 -0.421954 -0.468641 -0.7761 -0.488499 -0.44256 -0.752004 -0.388053 -0.537977 -0.748328 -0.422467 -0.520712 -0.741876 -0.421944 -0.586675 -0.691213 -0.473392 -0.564223 -0.676427 -0.3994 -0.647248 -0.649269 -0.422502 -0.634369 -0.647354 -0.42194 -0.689621 -0.588548 -0.457639 -0.672945 -0.581129 -0.408794 -0.739348 -0.535026 -0.422524 -0.731155 -0.535617 -0.421926 -0.774837 -0.47075 -0.441224 -0.765504 -0.468322 -0.416303 -0.812325 -0.408437 -0.422555 -0.808482 -0.409638 -0.421924 -0.840123 -0.340842 -0.424118 -0.839057 -0.340746 -0.42198 -0.864668 -0.272548 -0.42257 -0.864311 -0.272766 -0.42191 -0.88381 -0.202169 -0.40632 -0.89121 -0.201616 -0.423778 -0.895088 -0.138671 -0.425003 -0.894215 -0.140539 -0.424504 -0.894589 -0.139667 0.705874 0.688142 0.167938 0.705874 0.688141 0.167938 0.705874 0.650812 0.279616 0.705873 0.650813 0.279616 0.705873 0.595499 0.383568 0.705874 0.595499 0.383567 0.705874 0.523728 0.476918 0.705874 0.523728 0.476918 0.705873 0.437485 0.557091 0.705873 0.437485 0.557091 0.705873 0.339152 0.621868 0.705874 0.339151 0.621867 0.705874 0.231446 0.669459 0.705874 0.231446 0.669459 0.705873 0.117345 0.698551 0.705875 0.117344 0.69855 0.705874 0 0.708337 0.705874 0 0.708337 0.705875 -0.117344 0.698549 0.705873 -0.117345 0.698551 0.705874 -0.231446 0.669459 0.705874 -0.231446 0.669459 0.705874 -0.339151 0.621867 0.705871 -0.339152 0.62187 0.70587 -0.437487 0.557093 0.705875 -0.437484 0.557089 0.705875 -0.523727 0.476918 0.705877 -0.523726 0.476916 0.705877 -0.595496 0.383565 0.705872 -0.5955 0.383568 0.705872 -0.650814 0.279617 0.705871 -0.650815 0.279617 0.70587 -0.688145 0.167939 0.705879 -0.688137 0.167936 0.705879 -0.688136 -0.167937 0.70587 -0.688145 -0.167938 0.705871 -0.650816 -0.279617 0.705874 -0.650813 -0.279616 0.705874 -0.595498 -0.383567 0.705878 -0.595495 -0.383565 0.705877 -0.523726 -0.476916 0.705875 -0.523727 -0.476917 0.705875 -0.437484 -0.55709 0.70587 -0.437487 -0.557093 0.705871 -0.339153 -0.62187 0.705874 -0.339151 -0.621867 0.705874 -0.231446 -0.669459 0.705874 -0.231446 -0.669459 0.705873 -0.117345 -0.698551 0.705875 -0.117344 -0.69855 0.705874 0 -0.708337 0.705874 0 -0.708337 0.705875 0.117344 -0.698549 0.705873 0.117345 -0.698551 0.705874 0.231446 -0.669459 0.705874 0.231446 -0.669459 0.705874 0.339151 -0.621867 0.705873 0.339152 -0.621868 0.705873 0.437485 -0.557091 0.705874 0.437485 -0.55709 0.705873 0.523729 -0.476919 0.705875 0.523728 -0.476918 0.705874 0.595499 -0.383567 0.705875 0.595497 -0.383566 0.705875 0.650812 -0.279616 0.705874 0.650812 -0.279616 0.705874 0.688141 -0.167938 0.705874 0.688142 -0.167938 0 -0.500495 0.865739 0 -0.985966 0.166945 -0.00226235 -0.996192 0.0871558 -0.0133954 -0.992634 0.120406 0 -0.999191 0.0402265 0 -0.978451 0.20648 -0.0101963 -0.960548 0.277929 -0.00414402 -0.965918 0.258817 0 -0.944252 0.329225 0 -0.930246 0.366936 -0.00668766 -0.906287 0.422609 -0.00511516 -0.903629 0.428285 0 -0.876035 0.482247 0 -0.855928 0.517095 -0.00493948 -0.82332 0.567557 -0.00676047 -0.819134 0.573563 -0.0104312 -0.721696 0.692131 -0.00401146 -0.707101 0.707101 0 -0.757584 0.652738 0 -0.783228 0.621734 0 -0.668434 0.743772 0 -0.637977 0.770055 -0.00210075 -0.573575 0.81915 -0.0136593 -0.601431 0.798808 -8.89116e-05 -0.535322 0.844648 0 -0.465226 0.885192 -0.0131336 -0.393015 0.919438 -0.00242228 -0.422617 0.906305 0 -0.348889 0.937164 0 -0.31091 0.950439 -0.00740653 -0.258812 0.965899 -0.00317657 -0.240613 0.970616 0 -0.187533 0.982258 0 -0.0209078 0.999781 -0.00574351 -0.0871543 0.996178 -0.00717484 -0.0819603 0.99661 0 -0.147866 0.989007 0 0.0193281 0.999813 -0.00476609 0.0788079 0.996878 -0.00683113 0.0871537 0.996171 0 0.146302 0.98924 0 0.185978 0.982554 -0.00387681 0.258817 0.965919 -0.0106682 0.23753 0.971322 0 0.309407 0.95093 -0.000180319 0.462891 0.886415 -0.00785975 0.422605 0.90628 -0.00109284 0.390137 0.920756 0 0.347408 0.937714 -0.00156283 0.598957 0.80078 -0.00780035 0.573559 0.819127 0 0.53354 0.845775 0 0.499087 0.866552 0 0.636755 0.771067 0 0.667257 0.744828 -0.00735858 0.707088 0.707088 -0.00332722 0.719539 0.694444 0 0.75655 0.653935 0 0.782243 0.622973 -0.00697442 0.82151 0.570152 -0.00584171 0.819138 0.573567 0 0.85511 0.518447 0 0.875271 0.483632 -0.00532828 0.906295 0.422612 -0.00800002 0.902254 0.431132 0 0.929664 0.368408 0 0.978123 0.208026 -0.00757541 0.965898 0.258812 -0.00259741 0.95971 0.280981 0 0.943731 0.330714 0 0.999126 0.0418056 -0.0078688 0.996164 0.087153 -0.000981087 0.992337 0.123555 0 0.9857 0.168512 -0.201846 -0.977634 -0.0590697 -0.203414 0.341038 -0.917778 -0.575868 -0.643556 -0.504194 -0.575869 0.504193 -0.643555 -0.575868 0.804151 -0.147366 -0.852353 0.251827 -0.458342 -0.852353 -0.233927 -0.467731 -0.851971 -0.322907 -0.41216 -0.851975 -0.448073 -0.270869 -0.850689 -0.524702 -0.031866 -0.904323 -0.419858 -0.0769422 -0.852345 -0.517798 -0.0734381 -0.851966 -0.522643 -0.0316141 -0.851975 -0.477455 -0.214885 -0.852353 -0.492647 -0.175482 -0.904555 -0.407051 -0.126842 -0.85221 -0.502566 -0.145482 -0.852208 -0.512638 -0.104612 -0.852209 -0.377481 -0.362282 -0.852202 -0.405391 -0.330772 -0.904087 -0.336402 -0.263554 -0.852351 -0.424425 -0.30555 -0.852214 -0.166001 -0.496161 -0.852203 -0.205354 -0.481228 -0.852347 -0.135683 -0.505068 -0.851972 -0.0943795 -0.515011 -0.851976 -0.094378 -0.515005 -0.851976 -0.0316126 -0.522626 -0.851969 -0.031614 -0.522637 -0.852351 0.0101065 -0.522872 -0.903596 0.0258655 -0.427604 -0.852205 0.0416774 -0.521546 -0.852221 0.0834638 -0.516482 -0.905208 0.0766024 -0.418007 -0.852346 0.114451 -0.510301 -0.851972 0.155769 -0.49988 -0.851969 0.15577 -0.499884 -0.851969 0.214889 -0.477463 -0.851971 0.370234 -0.370234 -0.852344 0.338396 -0.398746 -0.905413 0.261817 -0.334184 -0.852218 0.313825 -0.418615 -0.852197 0.279177 -0.442516 -0.852221 0.47236 -0.224936 -0.852196 0.452785 -0.262199 -0.851971 0.499881 -0.155769 -0.852343 0.484894 -0.19593 -0.868565 0.493771 -0.0422554 -0.851971 0.515013 -0.0943797 -0.851971 0.515012 -0.0943794 -0.852387 0.519673 -0.0581072 -0.880405 0.473006 -0.0339607 -0.575867 0.816052 -0.0493621 -0.575868 0.643556 -0.504194 -0.852355 0.435912 -0.288917 -0.85197 0.412162 -0.322908 -0.575868 0.643556 -0.504194 -0.575868 0.57809 -0.57809 -0.203056 0.692376 -0.692376 -0.203393 0.639364 -0.741515 -0.575865 -0.147366 -0.804154 -0.575862 -0.147367 -0.804155 -0.575862 -0.0493626 -0.816055 -0.575867 -0.0493621 -0.816052 -0.575867 0.0493624 -0.816052 -0.575862 0.0493623 -0.816055 -0.575862 0.147367 -0.804155 -0.575866 0.147366 -0.804153 -0.575866 0.243222 -0.780527 -0.575866 0.243222 -0.780527 -0.575877 -0.50419 -0.643551 -0.851969 -0.270874 -0.448081 -0.851969 -0.32291 -0.412163 -0.575868 -0.504194 -0.643556 -0.575868 -0.57809 -0.57809 -0.203062 -0.692375 -0.692375 -0.2034 -0.741512 -0.639365 -0.572884 -0.818149 -0.0493568 -0.575876 -0.816042 -0.0494262 -0.575874 -0.804147 -0.147366 -0.575866 -0.804153 -0.147367 -0.575866 -0.780527 -0.243222 -0.575878 -0.780518 -0.24322 -0.203058 0.97738 -0.0591206 -0.203058 0.97738 -0.0591207 -0.203343 0.96845 -0.144071 -0.840787 0.540793 -0.024882 -0.89323 0.448779 -0.0271461 -0.575868 0.816051 -0.049362 -0.575868 0.804151 -0.147366 0.0764896 0.980738 -0.179727 -0.203304 0.957992 -0.202284 -0.203409 0.917779 -0.341038 -0.851971 0.499882 -0.155769 -0.575868 0.780525 -0.243222 -0.575868 0.780525 -0.243221 -0.0933522 0.950552 -0.296204 -0.203133 0.936751 -0.285019 -0.905611 0.386745 -0.17406 -0.575868 0.745517 -0.33553 -0.575867 0.745517 -0.33553 -0.20306 0.892902 -0.401862 -0.203057 0.892902 -0.401863 -0.903077 0.367541 -0.222186 -0.575868 0.699638 -0.422946 -0.575868 0.699638 -0.422946 0.048236 0.854785 -0.516735 -0.203376 0.857612 -0.472376 -0.203058 0.692375 -0.692375 -0.203397 0.741515 -0.639364 -0.00853256 0.787155 -0.616696 -0.203198 0.778798 -0.593451 -0.203255 0.827548 -0.523309 -0.85197 0.412162 -0.322908 -0.85197 0.370235 -0.370235 -0.575868 0.57809 -0.57809 -0.575868 0.504194 -0.643556 -0.00852941 0.616696 -0.787155 -0.203197 0.593451 -0.778799 -0.203378 0.472375 -0.857612 -0.903339 0.2219 -0.367068 -0.57587 0.422945 -0.699636 -0.57587 0.422945 -0.699636 0.0482408 0.516736 -0.854785 -0.203252 0.52331 -0.827548 -0.85197 0.214889 -0.477463 -0.575866 0.335531 -0.745518 -0.57587 0.33553 -0.745516 -0.203063 0.401862 -0.892901 -0.203062 0.401862 -0.892901 -0.079243 0.290172 -0.953688 -0.20306 0.291305 -0.934831 -0.203306 0.202284 -0.957992 0.0764923 0.179727 -0.980738 -0.203342 0.144071 -0.96845 -0.203056 0.0591207 -0.977381 -0.203056 0.0591207 -0.977381 -0.203056 -0.0591207 -0.977381 -0.203056 -0.0591207 -0.977381 -0.203341 -0.144071 -0.96845 0.0764933 -0.179727 -0.980738 -0.203309 -0.202284 -0.957991 -0.203408 -0.341038 -0.917779 -0.904997 -0.126563 -0.406155 -0.575866 -0.243222 -0.780526 -0.575864 -0.243222 -0.780528 -0.0933525 -0.296204 -0.950552 -0.203139 -0.285018 -0.936749 -0.903847 -0.175598 -0.390163 -0.575865 -0.335531 -0.745519 -0.575866 -0.33553 -0.745518 -0.203062 -0.401862 -0.892901 -0.203056 -0.401863 -0.892902 -0.851972 -0.270871 -0.448076 -0.575876 -0.422942 -0.699633 -0.575864 -0.422948 -0.69964 0.0482444 -0.516736 -0.854784 -0.203378 -0.472375 -0.857612 -0.20305 -0.692377 -0.692376 -0.203388 -0.639363 -0.741517 -0.00853166 -0.616696 -0.787155 -0.203186 -0.593453 -0.7788 -0.203243 -0.523311 -0.82755 -0.852348 -0.354764 -0.384245 -0.904778 -0.301145 -0.301145 -0.575872 -0.578088 -0.578088 -0.575873 -0.643553 -0.504192 -0.00852594 -0.787155 -0.616697 -0.203198 -0.778798 -0.59345 -0.203392 -0.85761 -0.472374 -0.851971 -0.448078 -0.270872 -0.57586 -0.699643 -0.422948 -0.575868 -0.699638 -0.422946 0.0482246 -0.854786 -0.516736 -0.203255 -0.827548 -0.523308 -0.851975 -0.477455 -0.214885 -0.575877 -0.745511 -0.335528 -0.575859 -0.745523 -0.335532 -0.203036 -0.892907 -0.401863 -0.203076 -0.892898 -0.401862 -0.203055 -0.977381 -0.0591207 -0.203341 -0.96845 -0.144072 0.0764869 -0.980738 -0.179727 -0.203298 -0.957993 -0.202284 -0.203052 -0.934832 -0.291306 -0.0792249 -0.953689 -0.290173 -0.203386 -0.917785 -0.341035 -0.705758 -0.705758 0.061746 -0.705758 -0.705757 0.0617461 -0.705758 -0.684313 0.183361 -0.705756 -0.684315 0.183361 -0.705756 -0.642078 0.299406 -0.705756 -0.642079 0.299406 -0.705756 -0.580333 0.406353 -0.705757 -0.580331 0.406352 -0.705757 -0.500952 0.500953 -0.705757 -0.500953 0.500953 -0.705757 -0.406353 0.580332 -0.705757 -0.406353 0.580331 -0.705757 -0.299406 0.642077 -0.705757 -0.299405 0.642077 -0.705757 -0.183361 0.684314 -0.705757 -0.183361 0.684314 -0.705757 -0.0617458 0.705758 -0.705757 -0.0617459 0.705758 -0.705757 0.0617458 0.705758 -0.705757 0.0617459 0.705758 -0.705757 0.183361 0.684314 -0.705757 0.183361 0.684314 -0.705757 0.299406 0.642077 -0.705757 0.299406 0.642078 -0.705757 0.406353 0.580332 -0.705757 0.406353 0.580332 -0.705757 0.500953 0.500953 -0.705757 0.500953 0.500953 -0.705757 0.580332 0.406353 -0.705756 0.580332 0.406353 -0.705756 0.642078 0.299406 -0.705757 0.642077 0.299406 -0.705757 0.684314 0.183361 -0.705757 0.684314 0.183361 -0.705757 0.705758 0.0617458 -0.705757 0.705758 0.0617458 -0.705167 0.705157 0.0741154 -0.705165 0.705159 0.0741153 -0.705165 0.67434 0.219107 -0.705166 0.674339 0.219106 -0.705166 0.614049 0.354521 -0.705171 0.614045 0.354519 -0.70517 0.526918 0.474439 -0.705168 0.52692 0.474441 -0.705167 0.416764 0.573626 -0.705168 0.416763 0.573625 -0.707096 0.347526 0.615826 -0.759505 0.258734 0.596832 -0.705168 0.288393 0.647741 -0.705168 0.147418 0.693546 -0.705166 0.147418 0.693548 -0.70711 0.0728234 0.703344 -0.714713 0 0.699418 -0.714713 0 0.699418 -0.755272 -0.266579 0.598748 -0.705516 -0.28188 0.650224 -0.705167 -0.147418 0.693547 -0.705166 -0.147418 0.693548 -0.70711 -0.0728232 0.703344 -0.705166 -0.705158 0.0741151 -0.705166 -0.705158 0.0741151 -0.705166 -0.674339 0.219106 -0.705166 -0.674339 0.219106 -0.705166 -0.614048 0.354521 -0.705166 -0.614049 0.354521 -0.705166 -0.526921 0.474442 -0.705166 -0.526921 0.474442 -0.705166 -0.416765 0.573627 -0.705167 -0.416764 0.573626 -0.707095 -0.347527 0.615827 0 0.974927 0.222527 0 0.974927 0.222527 0 0.781833 0.623487 0 0.781833 0.623487 0 0.433878 0.900971 0 0.433878 0.900971 0 0 1 0 0 1 0 -0.433878 0.900971 0 -0.433878 0.900971 0 -0.781833 0.623487 0 -0.781833 0.623487 0 -0.974927 0.222527 0 -0.974927 0.222527 0 0.383643 0.923482 0 0.70711 0.707104 0 0.70711 0.707104 0 0.965925 0.258822 0 0.965925 0.258822 -0.0184524 0.134038 0.990804 0 0.258817 0.965926 0 -0.130588 0.991437 -0.00959865 -0.258804 0.965882 0 -0.382729 0.923861 0 -0.609425 0.792844 -0.00946948 -0.707078 0.707072 0 -0.793851 0.608112 0 -0.965925 0.258822 0 -0.965925 0.258822 0 0.974928 0.222522 0 0.974928 0.222522 0 0.781832 0.623489 0 0.781832 0.623489 0 0.433881 0.90097 0 0.433881 0.90097 0 0 1 0 0 1 0 -0.433881 0.90097 0 -0.433881 0.90097 0 -0.781832 0.623489 0 -0.781832 0.623489 0 -0.974928 0.222522 0 -0.974928 0.222522 0 0.991339 0.131325 -0.00805947 0.965894 0.258811 0 0.923571 0.383428 0 0.707106 0.707107 0 0.707106 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.965926 0.258819 -0.0190817 -0.991369 0.129709 0 -0.923846 0.382764 0 -0.707106 0.707107 -0.0184373 -0.790977 0.611568 0 -0.607856 0.794047 0 0.991457 0.130432 -0.00796558 0.965895 0.258812 0 0.923917 0.382594 0 0.792772 0.609518 -0.00805931 0.707085 0.707083 0 0.608008 0.793931 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.965926 0.25882 -0.0184316 -0.990785 0.134184 0 -0.923426 0.383776 0 0.991579 0.129502 -0.00805921 0.965895 0.25881 0 0.924277 0.381722 0 0.793338 0.608781 -0.00796577 0.707081 0.707087 0 0.608739 0.793371 0 0.381766 0.924259 -0.00805927 0.258814 0.965894 0 0.129547 0.991573 0 -0.258822 0.965925 0 -0.258822 0.965925 0 -0.707104 0.70711 0 -0.707104 0.70711 0 -0.965926 0.258818 0 -0.965926 0.258818 0 0.974927 0.222524 0 0.974927 0.222524 0 0.781834 0.623487 0 0.781834 0.623487 0 0.433881 0.90097 0 0.433881 0.90097 0 0 1 0 0 1 0 -0.433881 0.90097 0 -0.433881 0.90097 0 -0.781833 0.623487 0 -0.781833 0.623487 0 -0.974927 0.222524 0 -0.974927 0.222524 0 0.965924 0.258826 0 0.965924 0.258826 0 0.707107 0.707107 0 0.707107 0.707107 0 0.383693 0.923461 -0.00805967 0.258809 0.965895 0 0.131601 0.991303 0 -0.130583 0.991437 -0.00796533 -0.258809 0.965896 0 -0.382727 0.923862 0 -0.609459 0.792818 -0.00805917 -0.707084 0.707084 0 -0.793883 0.608071 0 -0.965927 0.258816 0 -0.965927 0.258816 0 0.974927 0.222524 0 0.974927 0.222524 0 0.781831 0.623491 0 0.781831 0.623491 0 0.433889 0.900966 0 0.433889 0.900966 0 0 1 0 0 1 0 -0.433889 0.900966 0 -0.433889 0.900966 0 -0.781824 0.623499 0 -0.781824 0.623499 0 -0.97493 0.222511 0 -0.97493 0.222511 0 0.991342 0.131305 -0.00946907 0.96588 0.258816 0 0.923591 0.383379 0 0.707113 0.707101 0 0.707113 0.707101 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.607816 0.794078 -0.00805891 -0.707078 0.70709 0 -0.792617 0.60972 0 -0.923848 0.382759 -0.00796579 -0.965899 0.258798 0 -0.991435 0.130602 0 0.991458 0.130425 -0.0190818 0.923401 0.383361 0 0.965924 0.258827 0 0.792796 0.609488 -0.00946895 0.707079 0.707071 0 0.608055 0.793895 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.7071 0.707114 0 -0.7071 0.707114 0 -0.923418 0.383796 -0.00805951 -0.965898 0.258797 0 -0.991288 0.131715 0 0.991573 0.129546 -0.0184579 0.925068 0.379354 0 0.965926 0.258817 0 0.793337 0.608783 -0.00959894 0.707074 0.707074 0 0.608744 0.793367 0 0.381809 0.924241 -0.00946959 0.258805 0.965883 0 0.129597 0.991567 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258817 0 -0.965926 0.258817 0 0.998943 0.0459615 0 0.998943 0.0459615 0 0.998943 -0.0459615 0 0.998943 -0.0459615 0 0.633751 -0.773537 -0.0194622 0.706973 -0.706973 -4.00186e-07 0.999661 -0.0260501 -0.00154883 0.996864 -0.0791175 -0.012227 0.966501 -0.25637 -0.0128254 0.965846 -0.258798 3.1901e-05 0.891442 -0.453135 -5.87519e-05 0.812077 -0.58355 0 0.998943 -0.0459621 -4.59251e-09 0.998943 -0.0459622 0 0.5 -0.866025 1.15678e-07 0.5 -0.866025 0 0.5 -0.866026 0 0.5 0.866025 -6.93399e-08 0.5 0.866025 0 -0.998626 0.0524129 -0.00635279 -0.995192 -0.0977402 0.00301874 -0.987817 -0.155593 -0.00344129 -0.888081 -0.459673 0.00235877 -0.873368 -0.487056 -0.00245514 -0.654455 -0.756097 0 -0.645277 -0.763949 0 -0.998943 -0.0459615 0 -0.998943 -0.0459615 0 -0.588483 0.808509 -0.0104739 -0.654421 0.756058 0.00699333 -0.776704 0.629827 -0.00949533 -0.888047 0.459655 0.00446813 -0.931943 0.362577 -0.00584107 -0.995195 0.0977405 0 -0.998018 0.0629367 0 -0.499998 -0.866026 2.34406e-07 -0.499999 -0.866026 0 -0.499999 -0.866026 0 -0.499999 0.866026 2.34406e-07 -0.499999 0.866026 0 -0.499998 0.866026 0 -0.993221 -0.116243 0.00113956 -0.996957 -0.0779483 0 -0.999259 -0.0385019 -0.0153544 -0.878654 -0.477212 0.0124601 -0.580003 -0.814519 0 -0.662496 -0.749065 0 -0.992512 -0.122148 0.00244061 -0.995432 -0.0954456 -0.0016144 -0.956201 -0.292707 0 -0.96405 -0.26572 0 -0.825165 -0.564891 0.221354 -0.692592 -0.686527 0.0051928 0.98796 -0.154626 0.0031384 0.984803 -0.173649 -0.00170152 0.998797 0.0490022 0 0.996953 0.0779983 -0.00187985 0.93999 -0.341196 0.00422051 0.866018 -0.499994 0.0020494 0.852039 -0.523474 -0.000272748 0.772364 -0.63518 0.0016535 0.642786 -0.766044 0 0.630357 -0.776305 -0.00302301 0.642785 0.766041 0.0175177 0.756811 0.653399 8.02379e-08 0.615126 0.788429 0 0.996953 -0.0779987 -0.00174492 0.998833 -0.048262 0.00320131 0.984803 0.173648 0.00504504 0.987667 0.156486 -0.00801773 0.865997 0.499984 0.0164545 0.932835 0.359927 0.00185831 0.850783 0.525514 0.706028 -0.706023 0.0552782 0.706011 -0.706046 0.0552028 0.694727 -0.694762 -0.186172 0.757477 -0.647974 -0.079746 0.699903 -0.47318 -0.535011 0.723221 -0.488347 -0.488333 0.694065 -0.632629 -0.343591 0.725801 -0.657776 -0.201355 0.707098 -0.353557 -0.612381 0.707098 -0.353557 -0.612381 0.694736 -0.508598 -0.508596 0.528389 -0.555636 -0.64193 0.753327 -0.584047 -0.302304 0.558621 -0.80116 -0.214674 0.742789 -0.666319 -0.0654408 0.706717 -0.706747 0.0325478 0.706716 -0.706749 0.0325176 0.706733 -0.706733 0.0325152 0.706733 -0.706733 -0.0325169 0.706716 -0.706749 -0.0325159 0.706717 -0.706747 -0.0325478 0.770115 -0.616168 0.165104 0.700658 -0.466954 0.539475 0.59003 -0.570906 0.570904 0.753327 -0.584047 0.302304 0.281138 -0.955072 0.0938 0.707098 -0.353557 0.612381 0.707099 -0.353556 0.61238 0.694735 -0.508605 0.508591 0.725406 -0.456011 0.515597 0.685024 -0.65741 0.313933 0.733452 -0.656577 0.17594 0.704427 -0.704462 0.0866977 0.706008 -0.706043 -0.0552802 0.706025 -0.706032 -0.0552019 0.706021 0.706033 -0.055238 0.706022 0.706033 -0.0552341 0.707102 0.353556 0.612377 0.707101 0.353556 0.612378 0.706727 0.706738 -0.0325176 0.706727 0.706738 -0.0325177 0.706727 0.706738 -0.0325171 0.706727 0.706738 -0.0325171 0.69474 0.508594 -0.508594 0.703419 0.70343 -0.101915 0.790807 0.59121 -0.158414 0.64114 0.681542 -0.35276 0.793634 0.398165 -0.46001 0.707101 0.353557 -0.612378 0.707101 0.353557 -0.612378 0.701668 0.701679 -0.123726 0.681899 0.725967 -0.0893639 0.720611 0.600451 -0.346669 0.685284 0.657185 -0.313836 0.710262 0.452482 -0.539248 0.699906 0.473183 -0.535004 -0.543894 0.740864 0.394081 -0.597441 0.650951 0.468324 -0.552714 0.62755 0.54835 -0.590579 0.556098 0.584784 -0.540003 0.726667 0.424679 -0.543786 0.719941 0.431255 -0.579549 0.565155 0.587131 -0.576719 0.566285 0.588826 -0.57747 0.565814 0.588542 -0.529115 0.671105 0.519284 -0.567897 0.641388 0.515863 -0.524187 0.759039 0.38612 -0.544125 0.738852 0.397524 -0.510375 0.812323 0.28222 -0.540791 0.785275 0.301477 -0.478729 0.86644 0.141779 -0.512775 0.843708 0.158805 -0.483222 0.873359 -0.0611619 -0.5055 0.862394 0.0273115 -0.491961 0.87035 -0.021583 -0.490321 0.871521 -0.00602718 -0.486858 0.871939 -0.0518784 -0.483308 0.872078 0.0767612 -0.455051 0.889687 0.0372266 -0.48292 0.874739 0.0402468 -0.48292 0.874739 -0.0402468 -0.48292 0.874739 -0.0402468 -0.500454 0.865477 0.0222464 -0.485679 0.873642 -0.0294145 -0.490025 0.871685 0.00645435 -0.486149 0.871712 0.0614664 -0.478536 0.877257 0.037732 -0.483263 0.872962 0.0662874 -0.512316 0.847134 -0.141051 -0.520807 0.843834 -0.129248 -0.513354 0.814115 -0.271448 -0.50599 0.811782 -0.291521 -0.539592 0.766009 -0.349387 -0.532838 0.750731 -0.390497 -0.555595 0.67248 -0.488964 -0.535401 0.659166 -0.528058 -0.577726 0.565158 -0.588922 -0.578433 0.565704 -0.587703 -0.578522 0.565475 -0.587835 -0.579218 0.565999 -0.586644 -0.576983 0.571654 -0.583354 -0.57461 0.623164 -0.530557 -0.544784 0.724995 -0.421418 -0.542149 0.73 -0.416142 -0.577997 0.670005 -0.465847 -0.543509 0.741894 -0.392671 -0.551715 -0.672624 -0.49314 -0.562781 -0.604538 -0.563748 -0.584667 -0.567159 -0.580082 -0.554676 -0.677348 -0.483254 -0.55234 -0.679945 -0.482281 -0.579084 -0.565231 -0.587517 -0.577994 -0.565717 -0.588121 -0.578314 -0.564899 -0.588593 -0.577201 -0.565401 -0.589204 -0.555239 -0.617483 -0.557158 -0.594968 -0.658905 -0.46028 -0.493119 -0.744734 -0.449673 -0.593447 -0.779444 -0.200717 -0.432598 -0.833226 -0.344374 -0.541902 -0.837213 -0.073604 -0.466257 -0.884131 -0.0302715 -0.50497 -0.861455 0.0538647 -0.504736 -0.862362 -0.0396774 -0.50474 -0.862359 -0.0396769 -0.504493 -0.862927 -0.029036 -0.544095 -0.838859 0.0166039 -0.449616 -0.880733 0.148847 -0.548566 -0.811297 0.202169 -0.482827 -0.794391 0.368539 -0.562966 -0.734726 0.378479 -0.522104 -0.654913 0.546349 -0.544994 -0.639244 0.54254 -0.577353 -0.565009 0.58943 -0.57816 -0.565291 0.588368 -0.578144 -0.565333 0.588344 -0.578949 -0.565608 0.587287 -0.57422 -0.577484 0.58033 -0.575271 -0.602462 0.553266 -0.559627 -0.670452 0.487147 -0.55146 -0.6869 0.47335 -0.55218 -0.68604 0.473759 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.422367 -0.900095 -0.106934 0.424936 -0.904844 -0.026208 0.425223 -0.904278 -0.0383053 0.422918 -0.8831 0.203163 0.428215 -0.892215 0.143472 0.460507 -0.81297 0.356389 0.471327 -0.787118 0.397864 0.485239 -0.733288 0.476268 0.509043 -0.652579 0.561263 0.520139 -0.576669 0.630006 0.522625 -0.57038 0.633664 0.521077 -0.571549 0.633885 0.521661 -0.570061 0.634745 0.520072 -0.571274 0.634957 0.422487 -0.904514 -0.0579611 0.405002 -0.913621 0.0356311 0.438952 -0.894794 0.0816424 0.423131 -0.865906 0.266771 0.46525 -0.830026 0.30757 0.451225 -0.755687 0.474692 0.501722 -0.698993 0.509592 0.497 -0.625826 0.60111 0.422256 -0.905519 0.041663 0.422254 -0.90552 0.0416636 0.422254 -0.90552 -0.0416631 0.422256 -0.905519 -0.0416635 0.474056 -0.672819 -0.567966 0.475612 -0.67133 -0.568427 0.474167 -0.754722 -0.453388 0.431556 -0.826154 -0.362255 0.419319 -0.820673 -0.388158 0.452533 -0.864718 -0.217893 0.398856 -0.909334 -0.118425 0.438711 -0.898413 -0.0196536 0.422346 -0.90521 0.0471017 0.520521 -0.570123 -0.635623 0.52121 -0.57121 -0.634081 0.521512 -0.570442 -0.634525 0.52219 -0.571486 -0.633025 0.484537 -0.656298 -0.578357 0.529385 -0.562133 -0.63542 0.456698 -0.791817 -0.405527 0.491243 -0.722155 -0.487003 0.414048 -0.886692 -0.205772 0.448746 -0.84196 -0.29955 0.427254 -0.900666 -0.0790889 0.425703 -0.904482 0.0262491 0.421614 -0.903864 0.0726083 0.419803 0.907238 0.0261574 0.416592 0.909067 -0.00700644 0.441295 0.87529 -0.197802 0.443494 0.84652 -0.294477 0.471452 0.787083 -0.397785 0.492271 0.687275 -0.534156 0.506441 0.653026 -0.563093 0.544079 0.510812 -0.66562 0.522624 0.570378 -0.633666 0.521075 0.571549 -0.633887 0.521656 0.570066 -0.634744 0.520077 0.571272 -0.634955 0.422405 0.904942 0.0515235 0.402502 0.914717 -0.0358548 0.438662 0.894329 -0.0880426 0.423132 0.865905 -0.266772 0.465248 0.830029 -0.307566 0.451227 0.755677 -0.474706 0.501721 0.698987 -0.509601 0.497003 0.625829 -0.601104 0.422252 0.905521 -0.0416631 0.422252 0.90552 -0.041663 0.487108 0.646873 0.586755 0.46625 0.672727 0.574499 0.422405 0.904943 -0.0514973 0.421495 0.905604 -0.0471565 0.426426 0.900488 0.0853375 0.408423 0.9053 0.116716 0.44856 0.856036 0.256896 0.423609 0.828756 0.365676 0.426112 0.826441 0.368 0.48776 0.745307 0.454541 0.520524 0.570128 0.635617 0.521209 0.571209 0.634084 0.52151 0.57044 0.634528 0.52219 0.571486 0.633026 0.484524 0.656321 0.578342 0.529365 0.562179 0.635396 0.456721 0.791818 0.4055 0.471094 0.765429 0.438394 0.435816 0.877658 0.199454 0.429054 0.886529 0.173146 0.424658 0.904968 -0.0264195 0.421133 0.905163 -0.0576771 -0.699906 0.473184 0.535003 -0.699906 0.473184 0.535004 -0.699906 0.644515 0.307786 -0.699907 0.644515 0.307784 -0.704437 0.704449 0.0867151 -0.683152 0.729557 0.0324176 -0.706021 0.706034 -0.0552342 -0.707101 0.353557 0.612378 -0.707102 0.353556 0.612377 -0.706727 0.706738 -0.0325177 -0.706727 0.706738 -0.0325176 -0.703419 0.70343 0.101915 -0.703419 0.703431 0.101915 -0.700661 0.633648 0.32797 -0.700662 0.466947 0.539475 -0.700661 0.466948 0.539475 -0.706184 0.586139 0.397171 -0.590028 0.741851 0.318629 -0.706727 0.706738 0.0325171 -0.706727 0.706738 0.0325171 -0.706727 0.706738 -0.0325171 -0.706727 0.706738 -0.0325171 -0.706727 0.706738 0.0325176 -0.706727 0.706738 0.0325177 -0.70342 0.70343 -0.101915 -0.703419 0.703431 -0.101915 -0.700661 0.633648 -0.32797 -0.700661 0.633648 -0.32797 -0.700661 0.466947 -0.539476 -0.700661 0.466947 -0.539476 -0.707101 0.353557 -0.612378 -0.707101 0.353557 -0.612378 -0.706021 0.706034 0.0552337 -0.664371 0.741804 -0.0913133 -0.699906 0.713531 -0.0317055 -0.699906 0.644515 -0.307785 -0.699907 0.644515 -0.307785 -0.699907 0.473183 -0.535004 -0.699906 0.473183 -0.535004 -0.694735 -0.508603 -0.508593 -0.694737 -0.508604 -0.508589 -0.694734 -0.694758 -0.186162 -0.694727 -0.694762 -0.186172 -0.707098 -0.353557 -0.612381 -0.707098 -0.353557 -0.612381 -0.694746 -0.694746 -0.18616 -0.694736 -0.508598 -0.508596 -0.694735 -0.508599 -0.508597 -0.704626 -0.651984 -0.280034 -0.372135 -0.918589 -0.133078 -0.706716 -0.706749 -0.0325176 -0.706733 -0.706733 -0.0325152 -0.706716 -0.70675 -0.0325098 -0.706732 -0.706732 -0.0325471 -0.707099 -0.353557 0.61238 -0.707098 -0.353557 0.612381 -0.706025 -0.706032 -0.055202 -0.706008 -0.706043 -0.0552802 0 -0.996957 -0.0779483 -0.00167027 -0.993131 -0.116995 0 -0.999239 -0.0390165 0 -0.995533 -0.0944164 -0.00857584 -0.965889 -0.258813 -2.67052e-07 -0.937151 -0.348924 -3.43233e-06 -0.815808 -0.578323 -0.00846967 -0.707089 -0.707074 0 -0.638377 -0.769724 0 0.998137 -0.0610096 -0.00545518 0.998999 0.0443902 0.00362831 0.979518 0.201322 -0.00471377 0.902375 0.430926 0.00235535 0.857502 0.514475 -0.00289089 0.662502 0.749054 0 0.638437 0.769674 0 0.581122 -0.813816 -0.0136394 0.773489 -0.633664 0.009164 0.662476 -0.749027 -0.00475127 0.902375 -0.430925 0.00237949 0.939739 -0.341883 -0.00293917 0.99901 -0.0443906 0 0.999925 -0.0122494 0 -0.499996 0.866028 -1.05894e-06 -0.499999 0.866026 0 -0.500002 0.866024 0 -0.500002 -0.866024 -1.05894e-06 -0.499999 -0.866026 0 -0.499996 -0.866028 0 -0.99847 -0.0552884 0.000336292 -0.998944 -0.0459505 -0.00145598 -0.988692 0.149956 -0.00251531 -0.989665 0.143375 0.00161067 -0.918831 0.394648 -0.00860298 -0.874753 0.484493 0.0154573 -0.707024 0.707021 0 -0.646888 0.762585 0 -0.998943 -0.0459615 0 -0.998943 -0.0459615 0 -0.5979 -0.80157 0.018241 -0.70699 -0.706988 0 -0.998944 0.0459505 -0.00474443 -0.998221 -0.0594308 0.00403544 -0.98966 -0.143374 -0.00424229 -0.936103 -0.3517 0.000942297 -0.918832 -0.394648 -0.00062905 -0.832085 -0.554648 0.0106902 -0.740618 -0.671841 0 0.5 0.866025 4.96379e-08 0.5 0.866025 0 0.5 0.866025 0 0.5 -0.866025 4.96379e-08 0.5 -0.866025 0 0.5 -0.866025 0 0.998943 -0.0459622 0 0.998943 -0.0459622 0 0.989667 -0.143385 -0.00226257 0.987232 -0.15927 0.00273824 0.888088 -0.459666 -0.00181836 0.87571 -0.482833 0.00188392 0.654451 -0.756102 0 0.646881 -0.762591 0 0.998943 0.0459615 0 0.998943 0.0459615 0 0.998943 -0.0459615 0 0.998943 -0.0459615 0.705587 0.7056 0.0653835 0.705588 0.705599 0.0653835 0.705588 0.681571 0.193924 0.705587 0.681572 0.193924 0.705587 0.634333 0.31586 0.705588 0.634333 0.31586 0.705588 0.565493 0.42704 0.705588 0.565493 0.42704 0.705588 0.477396 0.523679 0.705587 0.477396 0.523679 0.705587 0.373042 0.602484 0.705588 0.373041 0.602483 0.705588 0.255984 0.660771 0.705586 0.255985 0.660773 0.705586 0.130209 0.696559 0.705587 0.130209 0.696558 0.705587 0 0.708623 0.705587 0 0.708623 0.705589 -0.130209 0.696556 0.705587 -0.130209 0.696557 0.705589 -0.255984 0.66077 0.705588 -0.255984 0.660771 0.705588 -0.373041 0.602482 0.705592 -0.37304 0.60248 0.705593 -0.477393 0.523675 0.705585 -0.477397 0.523681 0.705584 -0.565496 0.427043 0.705586 -0.565494 0.427041 0.705586 -0.634335 0.315861 0.705585 -0.634335 0.315861 0.705585 -0.681574 0.193925 0.70559 -0.681569 0.193923 0.70559 -0.705597 0.0653831 0.705585 -0.705602 0.0653839 0.705407 0.705389 0.0694749 0.705413 0.705384 0.0694739 0.705413 0.678276 0.205753 0.705408 0.678281 0.205754 0.705408 0.625107 0.334127 0.705415 0.625101 0.334123 0.705414 0.547906 0.449655 0.705408 0.547911 0.449659 0.705408 0.449659 0.547911 0.705409 0.449658 0.54791 0.70541 0.334126 0.625106 0.705412 0.334125 0.625104 0.705412 0.205753 0.678277 0.705408 0.205754 0.678281 0.705408 0.0694747 0.705388 0.705411 0.0694746 0.705385 0.705411 -0.0694744 0.705385 0.705408 -0.0694749 0.705388 0.705408 -0.205754 0.678281 0.705412 -0.205753 0.678277 0.705412 -0.334125 0.625104 0.70541 -0.334126 0.625106 0.705409 -0.449658 0.54791 0.705408 -0.449659 0.547911 0.705408 -0.547911 0.449659 0.705411 -0.547909 0.449657 0.705411 -0.625105 0.334125 0.70541 -0.625105 0.334126 0.70541 -0.678279 0.205754 0.705411 -0.678278 0.205754 0.705411 -0.705386 0.0694745 0.705409 -0.705387 0.0694745 0.705398 0.705398 0.0694758 0.705395 0.705401 0.0694762 0.705395 0.678293 0.205758 0.705389 0.678299 0.20576 0.705389 0.625124 0.334136 0.705397 0.625117 0.334132 0.705397 0.54792 0.449666 0.705387 0.547927 0.449672 0.705387 0.449672 0.547927 0.705387 0.449672 0.547927 0.705388 0.334136 0.625125 0.705392 0.334134 0.625121 0.705391 0.205759 0.678297 0.705389 0.20576 0.678299 0.705389 0.0694764 0.705407 0.705392 0.0694762 0.705405 0.705392 -0.0694761 0.705405 0.705388 -0.0694767 0.705409 0.705385 -0.205761 0.678302 0.705389 -0.20576 0.678299 0.705389 -0.334136 0.625124 0.705391 -0.334135 0.625122 0.705391 -0.449669 0.547924 0.705387 -0.449672 0.547927 0.705387 -0.547927 0.449672 0.705391 -0.547924 0.44967 0.705391 -0.625122 0.334135 0.705392 -0.625121 0.334134 0.705392 -0.678296 0.205759 0.705392 -0.678296 0.205759 0.705392 -0.705404 0.0694762 0.705392 -0.705405 0.0694763 -0.705392 -0.705405 0.0694763 -0.705392 -0.705404 0.0694762 -0.705392 -0.678296 0.205759 -0.705392 -0.678296 0.205759 -0.705392 -0.625121 0.334134 -0.705391 -0.625122 0.334135 -0.705391 -0.547924 0.449669 -0.705387 -0.547927 0.449672 -0.705387 -0.449672 0.547927 -0.705391 -0.449669 0.547924 -0.705391 -0.334135 0.625122 -0.705389 -0.334136 0.625124 -0.705389 -0.20576 0.678299 -0.705385 -0.205761 0.678302 -0.705388 -0.0694765 0.705409 -0.705392 -0.0694763 0.705405 -0.705392 0.0694761 0.705405 -0.705389 0.0694765 0.705407 -0.705389 0.20576 0.678299 -0.705391 0.205759 0.678297 -0.705392 0.334134 0.625121 -0.705388 0.334136 0.625125 -0.705387 0.449672 0.547927 -0.705387 0.449672 0.547927 -0.705387 0.547927 0.449672 -0.705397 0.54792 0.449666 -0.705397 0.625117 0.334132 -0.705389 0.625124 0.334135 -0.705389 0.678299 0.205759 -0.705395 0.678293 0.205758 -0.705395 0.705401 0.0694761 -0.705398 0.705398 0.0694759 0.705751 0.705764 0.0617464 0.705752 0.705763 0.0617463 0.705752 0.684319 0.183363 0.705752 0.684319 0.183363 0.705752 0.642082 0.299408 0.705754 0.64208 0.299407 0.705754 0.580334 0.406354 0.705749 0.580338 0.406357 0.705749 0.500959 0.500958 0.705752 0.500956 0.500956 0.705752 0.406356 0.580336 0.705753 0.406355 0.580335 0.705754 0.299407 0.64208 0.705749 0.299409 0.642085 0.705749 0.183363 0.684322 0.705748 0.183364 0.684323 0.705748 0.0617468 0.705767 0.705758 0.0617456 0.705758 0.705758 -0.0617459 0.705758 0.705748 -0.0617464 0.705767 0.705747 -0.183364 0.684323 0.705749 -0.183363 0.684322 0.705749 -0.299409 0.642084 0.705757 -0.299406 0.642078 0.705757 -0.406353 0.580332 0.705756 -0.406353 0.580333 0.705756 -0.500954 0.500953 0.705747 -0.50096 0.50096 0.705746 -0.58034 0.406359 0.705752 -0.580336 0.406356 0.705751 -0.642083 0.299408 0.705743 -0.64209 0.299412 0.705743 -0.684328 0.183365 0.705755 -0.684316 0.183362 0.705755 -0.70576 0.0617464 0.705758 -0.705758 0.0617461 0.705758 0.705758 0.0617456 0.705755 0.70576 0.0617459 0.705755 0.684316 0.183362 0.705769 0.684302 0.183358 0.705769 0.642067 0.299401 0.705749 0.642084 0.299409 0.705749 0.580338 0.406357 0.705757 0.580332 0.406352 0.705756 0.500954 0.500953 0.705751 0.500957 0.500957 0.70575 0.406356 0.580337 0.705757 0.406353 0.580332 0.705756 0.299406 0.642078 0.705749 0.299409 0.642084 0.705749 0.183363 0.684322 0.705757 0.183361 0.684314 0.705756 0.061746 0.705759 0.705751 0.0617463 0.705764 0.705751 -0.0617465 0.705764 0.705755 -0.0617459 0.70576 0.705756 -0.183362 0.684315 0.705749 -0.183364 0.684322 0.705749 -0.299409 0.642084 0.705754 -0.299407 0.64208 0.705753 -0.406355 0.580335 0.705746 -0.406359 0.58034 0.705746 -0.50096 0.50096 0.705751 -0.500957 0.500957 0.705752 -0.580336 0.406356 0.705749 -0.580338 0.406357 0.705749 -0.642084 0.299409 0.705754 -0.64208 0.299407 0.705753 -0.684318 0.183362 0.705751 -0.684319 0.183363 0.705752 -0.705763 0.0617463 0.705751 -0.705764 0.0617464 0.705594 0.705594 0.0653828 0.705581 0.705606 0.0653844 0.705582 0.681577 0.193926 0.70559 0.68157 0.193923 0.705589 0.634332 0.31586 0.705591 0.63433 0.315859 0.705591 0.565491 0.427038 0.705582 0.565497 0.427044 0.705583 0.477399 0.523682 0.705588 0.477396 0.523678 0.705588 0.373042 0.602483 0.705589 0.373041 0.602482 0.705587 0.255984 0.660771 0.70559 0.255983 0.660769 0.70559 0.130209 0.696555 0.705588 0.130209 0.696557 0.705587 0 0.708623 0.705587 0 0.708623 0.705588 -0.130209 0.696557 0.70559 -0.130209 0.696555 0.70559 -0.255983 0.660769 0.705582 -0.255986 0.660776 0.705582 -0.373045 0.602488 0.705588 -0.373042 0.602483 0.705588 -0.477396 0.523678 0.705588 -0.477396 0.523678 0.705587 -0.565493 0.427041 0.705588 -0.565493 0.42704 0.705588 -0.634333 0.31586 0.705589 -0.634331 0.31586 0.705589 -0.68157 0.193923 0.705588 -0.681571 0.193924 0.705588 -0.705599 0.0653835 0.705587 -0.7056 0.0653836 0.705418 0.705379 0.0694737 0.705419 0.705378 0.0694737 0.705418 0.678271 0.205751 0.70542 0.678269 0.205751 0.70542 0.625096 0.334121 0.705418 0.625099 0.334122 0.705418 0.547903 0.449653 0.705414 0.547906 0.449655 0.705414 0.449655 0.547906 0.705418 0.449653 0.547903 0.705418 0.334122 0.625099 0.705416 0.334123 0.6251 0.705416 0.205752 0.678273 0.705416 0.205752 0.678273 0.705415 0.069474 0.705381 0.705418 0.0694736 0.705378 0.705418 -0.0694737 0.705379 0.705415 -0.0694739 0.705381 0.705416 -0.205752 0.678273 0.705414 -0.205752 0.678275 0.705413 -0.334125 0.625103 0.705421 -0.334121 0.625096 0.705422 -0.44965 0.5479 0.705414 -0.449655 0.547907 0.705414 -0.547906 0.449655 0.705413 -0.547907 0.449656 0.705412 -0.625104 0.334125 0.705429 -0.625089 0.334116 0.705429 -0.67826 0.205748 0.705422 -0.678268 0.205751 0.705422 -0.705375 0.0694731 0.705411 -0.705385 0.0694745 0.421828 0.554791 0.717125 0.422232 0.326696 0.845571 0.415756 0.326624 0.848801 0.42544 0.38229 0.820277 0.42254 0.381753 0.822025 0.421927 0.449964 0.78709 0.409793 0.451217 0.792763 0.423782 0.501493 0.754263 0.422613 0.500366 0.755667 0.42183 0.55479 0.717124 0.451876 -0.156109 0.878316 0.494357 -0.370339 0.786423 0.401271 -0.190369 0.895958 0.551328 -0.578737 0.600917 0.460544 -0.461496 0.758236 0.610542 -0.703801 0.363185 0.529857 -0.655222 0.538458 0.435644 -0.0109679 0.900052 0.425238 0.133045 0.895249 0.419428 0.16762 0.892179 0.417337 0.711947 0.564766 0.418481 0.705583 0.571863 0.444962 0.839989 0.310526 0.451369 0.844433 0.288442 0.483924 0.868514 0.107239 0.51234 0.858105 -0.0341145 0.5023 0.864689 -0.0026975 0.5523 0.797008 -0.244424 0.563962 0.77914 -0.273655 0.609443 0.655004 -0.44671 0.587417 -0.69892 0.407986 0.587081 -0.699095 0.408169 0.587417 0.702786 -0.40129 0.587062 0.703046 -0.401353 0.509149 0.777691 0.368732 0.529669 0.822025 0.209105 0.549761 0.812724 0.192985 0.571963 0.819127 0.0434686 0.44309 0.755977 0.481841 0.4924 0.749095 0.443169 0.448899 0.629073 0.634632 0.445293 0.628275 0.637954 0.44195 0.532624 0.721797 0.46784 -0.20526 0.859648 0.4381 0.520844 0.73266 0.433944 0.445455 0.78311 0.450788 0.406194 0.794856 0.432121 0.365611 0.824378 0.411968 0.272107 0.869621 0.421844 0.289811 0.859103 0.42162 0.164677 0.891694 0.426459 0.173693 0.887673 0.421748 0.0234963 0.906408 0.422551 0.0250717 0.905992 0.439973 -0.0775835 0.894653 0.438138 -0.0991256 0.893425 0.44898 -0.149861 0.880885 0.450535 -0.256825 0.85502 0.48155 -0.352773 0.802285 0.493578 -0.373905 0.785223 0.49264 -0.382979 0.78143 0.490116 -0.481183 0.726808 0.48424 -0.508606 0.711921 0.550307 -0.557846 0.621265 0.530415 -0.667751 0.522272 0.554089 -0.674033 0.488534 0.554092 -0.339467 0.760095 0.530415 -0.317154 0.786177 0.550307 -0.172475 0.816955 0.484239 -0.0845036 0.870845 0.505526 0.0463656 0.861565 0.497146 0.0606353 0.865546 0.440765 0.179814 0.879428 0.44292 0.18532 0.877199 0.456013 0.31103 0.833854 0.452387 0.293329 0.842202 0.43814 0.360863 0.823293 0.439975 0.380135 0.813584 0.422552 0.474709 0.772076 0.421751 0.473555 0.773222 0.426462 0.59426 0.681899 0.421618 0.588457 0.689897 0.421842 0.680534 0.599101 0.411967 0.670462 0.617061 0.427724 0.715555 0.552298 0.412571 0.787853 0.457245 0.415591 0.788246 0.453819 0.466924 0.85074 0.241294 0.384955 0.872525 0.300848 0.460759 0.867947 0.185387 0.492676 0.870183 0.00719045 0.493911 0.869457 0.0098599 0.529671 0.816447 -0.229922 0.549761 0.800332 -0.239231 0.571964 0.73112 -0.371916 0.587415 0.809277 0.00386615 0.587063 0.809532 0.00394013 0.587417 -0.401289 0.702786 0.58708 -0.40135 0.703033 0.417341 0.334166 0.84508 0.418482 0.325125 0.848037 0.444962 0.572183 0.688923 0.451382 0.587106 0.671983 0.483933 0.698554 0.527097 0.512339 0.760196 0.399513 0.502298 0.750188 0.430018 0.5523 0.812441 0.186828 0.563962 0.811582 0.15258 0.609443 0.790604 -0.0593587 0.451876 0.30396 0.838699 0.494356 0.0724888 0.866232 0.401253 0.283147 0.871105 0.551327 -0.200743 0.809778 0.460571 -0.0205998 0.887384 0.610544 -0.42792 0.666424 0.529844 -0.298192 0.793944 0.435642 0.440541 0.784946 0.425239 0.562833 0.708795 0.419424 0.591265 0.688832 0.421999 0.128735 0.89741 0.423623 0.128869 0.896625 0.422394 0.0679632 0.903861 0.422606 0.0681968 0.903744 0.421827 0 0.906676 0.422004 -0.128977 0.897373 0.423621 -0.128627 0.896661 0.422402 -0.068204 0.903839 0.422607 -0.0679558 0.903762 0.421827 0 0.906676 0.422615 0.858574 0.290254 0.424519 0.858898 0.286493 0.394028 0.848878 0.352346 0.421844 0.838801 0.344181 0.42255 0.805543 0.415395 0.429552 0.804062 0.41106 0.403886 0.782973 0.473106 0.422168 0.77752 0.466088 0.422405 0.734422 0.531224 0.432836 0.731992 0.526157 0.411785 0.700708 0.582615 0.422402 0.698682 0.577425 0.612012 -0.787993 -0.067146 0.562607 -0.812616 0.152078 0.583172 -0.807568 0.0879983 0.548325 -0.805615 0.224331 0.522359 -0.777094 0.351092 0.50703 -0.746951 0.430098 0.491556 -0.724834 0.482688 0.458298 -0.613219 0.643371 0.456413 -0.584682 0.670697 0.442005 -0.504675 0.741576 0.41783 -0.334355 0.844763 0.417437 -0.332785 0.845577 0.417341 0.898941 0.133158 0.41848 0.896985 0.142452 0.444961 0.882716 -0.151069 0.451375 0.875513 -0.172443 0.483926 0.805771 -0.341392 0.512339 0.726086 -0.458593 0.502301 0.747493 -0.434682 0.5523 0.568017 -0.610181 0.563957 0.537945 -0.626552 0.609444 0.343891 -0.714365 0.587418 -0.809275 0.00386434 0.587078 -0.809521 0.00393576 0.587417 0.407985 -0.69892 0.587062 0.408178 -0.699106 0.529669 0.607343 0.592103 0.549764 0.607348 0.573488 0.571965 0.687644 0.447215 0.357337 0.162049 0.91981 0.455989 0.254458 0.852834 0.4924 0.42715 0.758343 0.458595 0.418105 0.784143 0.511643 0.500641 0.698269 0.450537 -0.649926 0.612055 0.467842 -0.607586 0.641844 0.466923 0.216402 0.857411 0.438096 0.0847267 0.894926 0.431208 -0.0428224 0.901236 0.442035 -0.031878 0.896431 0.411968 -0.199159 0.889167 0.421844 -0.178569 0.88891 0.42162 -0.303234 0.854568 0.42646 -0.293414 0.855594 0.421749 -0.432855 0.796721 0.42255 -0.431285 0.797148 0.439972 -0.514517 0.736001 0.438137 -0.53256 0.724166 0.448975 -0.570213 0.687953 0.538125 -0.834032 0.121702 0.481552 -0.706653 0.51841 0.49715 -0.719266 0.485281 0.505526 -0.722952 0.470939 0.484239 -0.796428 0.362238 0.521412 -0.796438 0.306295 0.545555 -0.825113 0.146827 0.554089 0.0860633 0.827996 0.530414 0.118425 0.839426 0.550306 0.259108 0.793742 0.484239 0.362238 0.796427 0.490115 0.388846 0.780119 0.492639 0.485249 0.722385 0.493578 0.493072 0.716422 0.440766 0.595438 0.671699 0.467842 0.641847 0.607583 0.448977 0.687949 0.570215 0.438139 0.724164 0.532561 0.439974 0.736 0.514517 0.422552 0.797148 0.431284 0.42175 0.796721 0.432855 0.42646 0.855593 0.293414 0.421619 0.854567 0.303236 0.421844 0.88891 0.178568 0.411967 0.889167 0.199159 0.445433 0.895289 0.00677353 0.403705 0.914064 0.03886 0.441951 0.891406 -0.100371 0.445293 0.866621 -0.225126 0.4489 0.864143 -0.227478 0.4924 0.758344 -0.42715 0.44309 0.795275 -0.413774 0.509151 0.708175 -0.489136 0.52967 0.592103 -0.607341 0.54976 0.573493 -0.607347 0.571963 0.447212 -0.687648 0.58742 0.698918 0.407985 0.58706 0.699105 0.408181 0.587416 0.00386593 0.809276 0.58708 0.00393657 0.809519 0.417348 -0.133213 0.89893 0.418481 -0.142451 0.896984 0.444961 0.15107 0.882716 0.451381 0.172465 0.875506 0.484833 0.347561 0.802582 0.514405 0.463629 0.721413 0.502289 0.434655 0.747516 0.552297 0.610179 0.568023 0.563979 0.626586 0.537883 0.609446 0.714367 0.343883 0.451877 0.682588 0.574353 0.494358 0.49589 0.713936 0.40125 0.680772 0.61282 0.551327 0.231039 0.80166 0.460552 0.425885 0.77879 0.610542 -0.0373743 0.791102 0.529852 0.138713 0.836669 0.435644 0.773991 0.459514 0.425242 0.841818 0.332432 0.419425 0.856465 0.300916 0.422255 -0.325547 0.846002 0.415964 -0.327738 0.84827 0.425267 -0.381216 0.820867 0.422551 -0.382862 0.821503 0.421969 -0.448463 0.787923 0.4102 -0.452627 0.791748 0.423425 -0.500159 0.755349 0.422616 -0.501795 0.754717 0.42183 -0.55479 0.717124 0.421828 -0.554791 0.717125 0.529829 -0.793963 -0.298166 0.610558 -0.666397 -0.427942 0.541552 -0.815771 -0.203075 0.505762 -0.862671 -0.00163148 0.51179 -0.858797 -0.0232115 0.426697 -0.858068 0.285742 0.472736 -0.865582 0.165194 0.390401 -0.722981 0.569987 0.411991 -0.753143 0.512873 0.417341 0.845085 -0.334153 0.41848 0.848038 -0.325125 0.444961 0.68892 -0.572187 0.451375 0.671995 -0.587097 0.484832 0.521274 -0.70229 0.514401 0.392964 -0.762215 0.502304 0.43 -0.750194 0.552301 0.186825 -0.812441 0.563958 0.152595 -0.811583 0.609443 -0.0593604 -0.790604 0.587416 -0.702786 -0.401291 0.587081 -0.703032 -0.401351 0.587417 0.00386616 -0.809275 0.587062 0.00394069 -0.809532 0.512131 0.0874311 0.854446 0.52967 0.229924 0.816446 0.54976 0.239233 0.800332 0.571961 0.371913 0.731123 0.46162 -0.028151 0.886631 0.492399 -0.00925028 0.87032 0.457351 -0.200248 0.866447 0.429776 -0.236164 0.871504 0.449925 -0.325106 0.83179 0.438098 -0.374085 0.817393 0.43121 -0.487704 0.75908 0.442037 -0.475824 0.760392 0.41197 -0.61706 0.670461 0.421846 -0.599098 0.680534 0.421622 -0.689887 0.588465 0.426456 -0.681906 0.594256 0.423575 -0.755089 0.500424 0.413513 -0.77624 0.475877 0.429786 -0.789006 0.439038 0.46591 -0.84627 0.258369 0.439974 -0.813583 0.38014 0.438137 -0.823298 0.360855 0.448974 -0.837799 0.31067 0.538126 -0.783142 -0.311623 0.45491 -0.861699 0.224794 0.475421 -0.872437 0.113262 0.483339 -0.869932 0.0979923 0.485118 -0.872626 0.056428 0.497849 -0.866093 -0.0450425 0.487491 -0.869181 -0.0829241 0.52903 -0.833187 -0.16102 0.542099 -0.785771 -0.297812 0.554083 0.488546 0.674029 0.531249 0.521123 0.667987 0.550312 0.621269 0.557837 0.484735 0.71018 0.510565 0.490949 0.726693 0.480507 0.492516 0.780266 0.385503 0.493629 0.785212 0.373862 0.440821 0.850613 0.28659 0.468293 0.859458 0.205022 0.449653 0.880136 0.152229 0.43802 0.893336 0.100449 0.439974 0.894653 0.0775851 0.422786 0.905916 -0.023855 0.422686 0.905968 -0.0236549 0.425832 0.888201 -0.172527 0.42162 0.891693 -0.164682 0.421874 0.859464 -0.288693 0.412768 0.86928 -0.271982 0.444043 0.780362 -0.440296 0.405214 0.81055 -0.422859 0.442027 0.721767 -0.532602 0.444212 0.639806 -0.627155 0.449884 0.634539 -0.628462 0.491042 0.445243 -0.748757 0.444558 0.482056 -0.754977 0.509441 0.368813 -0.777462 0.528414 0.21134 -0.822261 0.550514 0.19337 -0.812122 0.571485 0.0446554 -0.819397 0.587416 0.40129 0.702786 0.587062 0.401354 0.703046 0.587416 0.407986 0.69892 0.587081 0.408168 0.699095 0.417339 -0.564766 0.711946 0.418482 -0.571857 0.705586 0.444962 -0.310531 0.839988 0.451376 -0.28842 0.844437 0.484834 -0.100288 0.868837 0.514402 0.040792 0.856579 0.502294 0.0026748 0.864693 0.552301 0.244423 0.797008 0.563959 0.273642 0.779147 0.609444 0.446713 0.655 0.451877 0.878315 0.156109 0.494358 0.786421 0.370342 0.40125 0.895975 0.190333 0.551327 0.600917 0.578738 0.46056 0.758212 0.461518 0.610542 0.363184 0.703801 0.52985 0.53847 0.655217 0.435644 0.900053 0.010955 0.425242 0.895252 -0.133016 0.419425 0.892178 -0.167632 0.422439 -0.696949 0.579489 0.41273 -0.702109 0.580257 0.432001 -0.730747 0.528568 0.422437 -0.735987 0.529027 0.422226 -0.775853 0.468804 0.40522 -0.784125 0.470047 0.428342 -0.803123 0.414147 0.422565 -0.806992 0.412555 0.421928 -0.837362 0.347566 0.395841 -0.849579 0.348605 0.422874 -0.85846 0.290214 0.422617 -0.859749 0.286752 0.422437 0.696949 -0.57949 0.412723 0.702111 -0.580258 0.431995 0.73075 -0.528568 0.422439 0.735986 -0.529027 0.422228 0.775852 -0.468804 0.405224 0.784123 -0.470047 0.428346 0.803121 -0.414146 0.422573 0.806988 -0.412556 0.421936 0.837358 -0.347565 0.395842 0.849579 -0.348604 0.422874 0.858459 -0.290215 0.422619 0.859743 -0.286768 0.529858 -0.538458 -0.65522 0.610561 -0.363136 -0.703809 0.460568 -0.758191 -0.461545 0.55135 -0.600867 -0.578768 0.501554 -0.755589 -0.421341 0.441582 -0.87972 -0.176346 0.482413 -0.824302 -0.296316 0.442468 -0.888705 -0.120105 0.4216 -0.896981 0.13296 0.418373 -0.895935 0.149216 0.417338 0.564778 -0.711937 0.41848 0.57186 -0.705585 0.444961 0.310533 -0.839988 0.451367 0.288449 -0.844432 0.484832 0.100288 -0.868839 0.514399 -0.0407926 -0.85658 0.502306 -0.00271979 -0.864685 0.5523 -0.244422 -0.797009 0.563961 -0.273648 -0.779144 0.609445 -0.446715 -0.654999 0.587416 -0.407986 -0.698921 0.587083 -0.408167 -0.699095 0.587417 -0.401289 -0.702786 0.587061 -0.401354 -0.703046 0.49391 -0.443267 0.748042 0.52967 -0.209106 0.822024 0.549761 -0.192986 0.812723 0.571963 -0.0434713 0.819126 0.432868 -0.901074 0.0262872 0.405888 -0.913744 -0.0180799 0.424445 -0.902376 0.0745905 0.426467 -0.88767 0.173692 0.421629 -0.89169 0.164677 0.421852 -0.859092 0.28983 0.411965 -0.869623 0.272106 0.442031 -0.792279 0.420598 0.431216 -0.801901 0.41353 0.438104 -0.732661 0.520839 0.451815 -0.691276 0.563916 0.42884 -0.640405 0.637163 0.459352 -0.599587 0.655356 0.492675 -0.441318 0.750006 0.438536 -0.893242 -0.0990211 0.455265 -0.87801 -0.147761 0.473419 -0.861157 -0.185157 0.44045 -0.85163 -0.284132 0.47831 -0.806989 -0.346392 0.484119 -0.78423 -0.388088 0.498622 -0.745636 -0.442045 0.484355 -0.711902 -0.508523 0.511232 -0.676357 -0.530267 0.56307 -0.522503 -0.640268 0.521207 -0.555691 -0.647727 0.554084 0.760107 0.339454 0.531249 0.785298 0.317933 0.550312 0.816953 0.172465 0.484736 0.870316 0.0870713 0.49095 0.869587 0.0527853 0.492517 0.868481 -0.0562883 0.493629 0.866945 -0.0688317 0.473809 0.873558 -0.111366 0.458293 0.860126 -0.223945 0.468294 0.846823 -0.252175 0.449653 0.838334 -0.308233 0.438021 0.823875 -0.359678 0.439974 0.813587 -0.38013 0.422785 0.772619 -0.473616 0.422687 0.772761 -0.473473 0.425834 0.682941 -0.593512 0.421622 0.689887 -0.588465 0.421876 0.599971 -0.679747 0.412769 0.616829 -0.670181 0.444045 0.455664 -0.771489 0.405215 0.490526 -0.771482 0.442027 0.358771 -0.822129 0.444212 0.240511 -0.863035 0.449884 0.235296 -0.861534 0.491042 0.0112137 -0.871064 0.444558 0.0399855 -0.894857 0.509441 -0.069329 -0.857708 0.528414 -0.228105 -0.817769 0.550513 -0.238598 -0.800004 0.571484 -0.371024 -0.731948 0.587416 -0.00386593 0.809276 0.587062 -0.00394047 0.809533 0.587417 0.702786 0.40129 0.58708 0.703032 0.40135 0.417333 -0.845044 0.334266 0.418488 -0.848035 0.325121 0.444968 -0.688908 0.572197 0.451378 -0.671994 0.587096 0.484831 -0.521293 0.702277 0.514407 -0.392945 0.76222 0.502304 -0.43 0.750193 0.552302 -0.186823 0.812441 0.563951 -0.152616 0.811584 0.609444 0.0593639 0.790604 0.451878 0.8387 -0.303957 0.494357 0.866232 -0.0724843 0.401257 0.871105 -0.28314 0.551327 0.809779 0.200743 0.460547 0.887397 0.0205582 0.610541 0.666429 0.427916 0.529857 0.793927 0.298213 0.435643 0.784945 -0.440541 0.425242 0.708806 -0.562817 0.419424 0.688832 -0.591265 0.422254 0.325548 -0.846002 0.415964 0.327738 -0.84827 0.425267 0.381215 -0.820867 0.42255 0.382862 -0.821504 0.421968 0.448463 -0.787924 0.410201 0.452626 -0.791748 0.423426 0.500156 -0.75535 0.422616 0.501795 -0.754717 0.42183 0.554791 -0.717124 0.421828 0.554791 -0.717125 0.451878 -0.682584 -0.574357 0.494355 -0.495905 -0.713927 0.401198 -0.680863 -0.612753 0.551327 -0.231039 -0.801661 0.460565 -0.42586 -0.778796 0.610541 0.0373716 -0.791102 0.529852 -0.138715 -0.836669 0.435648 -0.773973 -0.459539 0.425257 -0.841773 -0.332529 0.419425 -0.85646 -0.30093 0.417348 0.133213 -0.89893 0.418481 0.142451 -0.896985 0.444961 -0.151072 -0.882715 0.451381 -0.172465 -0.875506 0.484833 -0.347561 -0.802582 0.514405 -0.463629 -0.721413 0.502296 -0.434672 -0.747502 0.552298 -0.610178 -0.568022 0.563969 -0.62657 -0.537911 0.609445 -0.714364 -0.343892 0.587417 -0.00386616 -0.809276 0.587081 -0.00393681 -0.809519 0.587417 -0.69892 -0.407986 0.587063 -0.699105 -0.408179 0.494406 -0.758978 0.423693 0.528415 -0.594157 0.606428 0.550511 -0.573528 0.606633 0.571483 -0.448374 0.68729 0.425616 -0.800353 -0.42224 0.423184 -0.856604 -0.295202 0.408904 -0.852572 -0.325451 0.422504 -0.868139 -0.260432 0.421879 -0.888663 -0.179714 0.437222 -0.887443 -0.145884 0.412547 -0.910451 -0.0297156 0.434927 -0.90041 0.0100299 0.438066 -0.895047 0.083605 0.454038 -0.877367 0.155166 0.429406 -0.873593 0.22901 0.462683 -0.841441 0.27911 0.491624 -0.757424 0.429667 0.420484 -0.797269 -0.433076 0.44509 -0.721505 -0.530401 0.456215 -0.704311 -0.543888 0.452238 -0.685501 -0.570586 0.447533 -0.603805 -0.659647 0.451714 -0.610924 -0.650174 0.481245 -0.517296 -0.707678 0.477906 -0.52415 -0.704892 0.4846 -0.482863 -0.729387 0.497487 -0.433778 -0.751228 0.484916 -0.359785 -0.797127 0.500308 -0.33885 -0.796789 0.576052 -0.13656 -0.805925 0.515472 -0.169042 -0.840068 0.554079 0.828001 -0.0860836 0.53125 0.839054 -0.11731 0.550314 0.793735 -0.259114 0.484735 0.797251 -0.359753 0.49095 0.779473 -0.389089 0.492517 0.723983 -0.482986 0.493629 0.716382 -0.49308 0.44082 0.673502 -0.593357 0.468293 0.607282 -0.641802 0.449653 0.571902 -0.686105 0.438021 0.533659 -0.723427 0.439975 0.514515 -0.736 0.422786 0.432298 -0.796474 0.422685 0.432499 -0.796418 0.425832 0.294688 -0.855468 0.42162 0.303227 -0.85457 0.421874 0.179719 -0.888664 0.412769 0.199098 -0.888809 0.444044 0.00887267 -0.895961 0.405216 0.0390672 -0.913386 0.442028 -0.100361 -0.891369 0.444213 -0.223228 -0.867666 0.449884 -0.226993 -0.863759 0.491042 -0.425821 -0.75997 0.444561 -0.412802 -0.794959 0.509439 -0.488891 -0.708136 0.528414 -0.60643 -0.594155 0.550514 -0.606635 -0.573523 0.571484 -0.68729 -0.448374 0.587416 -0.407986 0.69892 0.587065 -0.408177 0.699104 0.587415 0.809277 -0.00386615 0.587082 0.809518 -0.00393624 0.417343 -0.898932 -0.133213 0.419275 -0.895522 -0.149158 0.443252 -0.87843 0.178573 0.442251 -0.879487 0.175832 0.492295 -0.786309 0.373315 0.50688 -0.746206 0.431566 0.518064 -0.685329 0.511795 0.567038 -0.537762 0.623923 0.584009 -0.416222 0.696916 0.451878 0.574361 -0.68258 0.494355 0.713931 -0.495899 0.401272 0.612843 -0.680738 0.55133 0.801659 -0.231036 0.460531 0.778779 -0.425929 0.61054 0.791103 0.0373703 0.529863 0.836666 -0.138695 0.435648 0.459536 -0.773975 0.425246 0.332438 -0.841814 0.419427 0.300909 -0.856466 0.422614 -0.858575 -0.290253 0.424531 -0.858902 -0.286463 0.394028 -0.848878 -0.352346 0.421838 -0.838803 -0.344183 0.422544 -0.805545 -0.415396 0.429552 -0.804063 -0.411057 0.403885 -0.782973 -0.473107 0.422165 -0.777521 -0.466088 0.422402 -0.734422 -0.531226 0.432843 -0.73199 -0.526154 0.411792 -0.700707 -0.582613 0.422404 -0.698681 -0.577424 0.421998 -0.128734 -0.89741 0.423623 -0.128869 -0.896625 0.422394 -0.0679632 -0.903861 0.422606 -0.0681968 -0.903744 0.421827 0 -0.906676 0.422005 0.128977 -0.897372 0.423621 0.128627 -0.896661 0.422402 0.068204 -0.903839 0.422607 0.0679558 -0.903762 0.421827 0 -0.906676 0.451875 -0.303962 -0.838699 0.494356 -0.0724884 -0.866232 0.401256 -0.28314 -0.871106 0.551327 0.200743 -0.809778 0.460571 0.0205998 -0.887384 0.610544 0.427918 -0.666425 0.529841 0.298186 -0.793948 0.435643 -0.44053 -0.784952 0.425236 -0.562858 -0.708778 0.419426 -0.591265 -0.688831 0.417338 -0.334183 -0.845074 0.418476 -0.325167 -0.848024 0.440736 -0.498524 -0.746475 0.456383 -0.584395 -0.670967 0.459184 -0.63255 -0.623723 0.504366 -0.751643 -0.425027 0.502706 -0.749939 -0.429975 0.545137 -0.804777 -0.23486 0.583164 -0.80757 -0.0880347 0.562597 -0.812617 -0.152115 0.612028 -0.787972 0.067248 0.587416 0.40129 -0.702786 0.587081 0.401351 -0.703032 0.587418 -0.809275 -0.00386434 0.587059 -0.809534 -0.00393965 0.571487 -0.731941 0.371032 0.550515 -0.800003 0.238596 0.528416 -0.817768 0.228104 0.496843 -0.86784 -0.000496135 0.490141 -0.871628 -0.00511503 0.470379 -0.871211 -0.140481 0.47553 -0.87088 -0.12425 0.440992 -0.864807 -0.240073 0.45964 -0.844641 -0.274433 0.438047 -0.816931 -0.37515 0.436068 -0.793374 -0.424738 0.412034 -0.77385 -0.481024 0.44112 -0.713017 -0.544996 0.417821 -0.681245 -0.601108 0.427125 -0.608635 -0.668676 0.418811 -0.595447 -0.685595 0.428385 -0.520355 -0.738727 0.414102 -0.474727 -0.77663 0.433695 -0.435812 -0.788655 0.439439 -0.359674 -0.823121 0.451611 -0.328294 -0.829621 0.449802 -0.308233 -0.838254 0.450759 -0.200429 -0.869853 0.441651 -0.177284 -0.879497 0.478875 -0.0986226 -0.872326 0.484561 -0.0534633 -0.873122 0.496465 -0.0011413 -0.868056 0.485239 0.0868249 -0.87006 0.501515 0.104895 -0.858767 0.571957 0.28784 -0.768124 0.517421 0.276844 -0.809712 0.536077 0.576517 -0.616644 0.536671 0.663552 -0.521232 0.540893 0.663646 -0.516729 0.514442 0.539512 -0.666541 0.492091 0.513707 -0.702817 0.485633 0.509957 -0.710003 0.495749 0.431591 -0.753633 0.484554 0.390241 -0.782892 0.479199 0.351213 -0.804374 0.480968 0.354364 -0.801933 0.468465 0.310401 -0.827159 0.45047 0.258154 -0.854654 0.453367 0.249547 -0.855678 0.448249 0.152682 -0.880773 0.449083 0.135088 -0.883219 0.438018 0.100452 -0.893336 0.438082 0.0343606 -0.898278 0.414022 -0.0228025 -0.909981 0.431002 -0.0794464 -0.898847 0.416975 -0.172962 -0.89231 0.429339 -0.206507 -0.879217 0.416465 -0.289669 -0.861771 0.428563 -0.323534 -0.843599 0.424557 -0.366636 -0.827846 0.436128 -0.465989 -0.769835 0.401478 -0.443032 -0.801584 0.446014 -0.528968 -0.721987 0.436029 -0.631592 -0.641069 0.447908 -0.635424 -0.628979 0.496717 -0.744799 -0.445586 0.530399 -0.836401 -0.138244 0.619598 -0.781771 -0.0702313 0.465302 -0.845926 -0.260582 0.530672 -0.820611 -0.212093 0.500752 -0.764272 -0.40637 0.398414 -0.757307 -0.517448 0.587416 -0.702786 0.401291 0.587062 -0.703045 0.401354 0.58742 0.698918 -0.407985 0.587079 0.699096 -0.408171 0.417337 -0.711947 -0.564766 0.418476 -0.705611 -0.571831 0.445571 -0.851911 -0.275162 0.441289 -0.850064 -0.287498 0.494411 -0.867262 -0.0584255 0.507328 -0.861753 0.000526613 0.521601 -0.845077 0.117378 0.587407 -0.723598 0.362435 0.547243 -0.786647 0.285852 0.629022 -0.60329 0.490278 0.451875 0.156107 -0.878316 0.494357 0.370339 -0.786423 0.401225 0.190287 -0.895996 0.551326 0.578743 -0.600913 0.460567 0.461534 -0.758198 0.610539 0.703803 -0.363185 0.52987 0.655235 -0.538428 0.435644 0.0109682 -0.900052 0.425238 -0.133045 -0.895249 0.419428 -0.167618 -0.892179 0.421828 -0.554791 -0.717125 0.422233 -0.326696 -0.84557 0.415756 -0.326624 -0.848801 0.42544 -0.38229 -0.820277 0.422541 -0.381753 -0.822024 0.421928 -0.449963 -0.787089 0.409792 -0.451217 -0.792763 0.423781 -0.501494 -0.754264 0.422613 -0.500368 -0.755665 0.42183 -0.55479 -0.717124 0.671574 -0.498183 -0.548453 0.69817 -0.481982 -0.529388 0.70418 -0.478653 -0.524426 0.678256 -0.5196 -0.5196 0.751442 -0.4697 -0.463375 0.650413 -0.54271 -0.531441 0.478902 -0.627858 -0.613553 0.539123 -0.813529 -0.217985 0.687893 -0.70108 -0.187854 0.678323 -0.709751 -0.190084 0.673028 -0.714372 -0.191589 0.635365 -0.745925 -0.199766 0.385899 -0.890763 -0.24005 0.539124 -0.813528 0.217985 0.678248 -0.709794 0.190189 0.386817 -0.890393 0.239943 0.635459 -0.745851 0.199747 0.673276 -0.714153 0.191533 0.687596 -0.701493 0.187399 0.479341 -0.627687 0.613385 0.650513 -0.542647 0.531382 0.683878 -0.520742 0.511017 0.745945 -0.470938 0.470938 0.70419 -0.478651 0.524414 0.698225 -0.481947 0.529347 0.671822 -0.498033 0.548287 0.553907 -0.234467 0.798882 0.667174 -0.209032 0.714972 0.690894 -0.202125 0.694126 0.781953 -0.161331 0.602097 0.698239 -0.162031 0.697287 0.686391 -0.163786 0.708549 0.629478 -0.174089 0.757265 0.616816 0.176349 0.767098 0.682917 0.164419 0.711752 0.697658 0.162027 0.697868 0.781954 0.161331 0.602097 0.690895 0.202124 0.694125 0.667115 0.209048 0.715022 0.55355 0.234534 0.79911 0.669888 0.499209 0.549582 0.697631 0.482311 0.5298 0.704122 0.478662 0.524496 0.678256 0.5196 0.5196 0.751441 0.469701 0.463377 0.65041 0.542711 0.531443 0.478769 0.62791 0.613604 0.678256 0.709787 0.190187 0.678256 0.709787 0.190187 0.635218 0.746017 0.199895 0.371956 0.89742 0.237247 0.633572 0.747115 0.201013 0.396907 0.886584 0.237559 0.678256 0.709787 -0.190187 0.678256 0.709787 -0.190187 0.635221 0.746014 -0.199894 0.371946 0.895816 -0.243249 0.633573 0.747526 -0.199475 0.396899 0.886587 -0.23756 0.479252 0.627721 -0.613419 0.650503 0.542653 -0.531389 0.683878 0.520742 -0.511017 0.745944 0.47094 -0.47094 0.704121 0.478662 -0.524495 0.6976 0.482328 -0.529825 0.669875 0.499217 -0.549591 0.553684 0.234509 -0.799024 0.667221 0.209019 -0.714932 0.690895 0.202124 -0.694125 0.781954 0.161331 -0.602097 0.697658 0.162027 -0.697868 0.682866 0.164427 -0.711799 0.616691 0.176371 -0.767194 0.0532485 -0.998338 -0.0220432 -0.00989704 -0.956257 -0.29236 0 -0.999075 -0.0429934 0 -0.740382 -0.672186 0.00533824 -0.779733 -0.62609 -0.00215785 -0.865185 -0.501448 0.00810184 -0.971793 -0.235696 0.00486295 -0.0368492 -0.999309 -0.00850018 0.173141 -0.98486 0.00422875 0.274587 -0.961553 -0.0053044 0.549365 -0.835566 0 0.578115 -0.815955 0.00647257 -0.0598593 -0.998186 -0.0164932 -0.326336 -0.94511 -1.54293e-06 -0.238457 -0.971153 2.65639e-07 -0.480939 -0.876754 -0.00190205 -0.511538 -0.859259 0.00302655 -0.648458 -0.761244 0 -0.675256 -0.737583 0 -0.987119 -0.159987 0 -0.987119 -0.159987 0.00486613 -0.531613 -0.846974 -0.00850001 -0.342485 -0.939485 0.00422899 -0.242975 -0.970023 -0.00530435 0.0579764 -0.998304 0 0.0926792 -0.995696 0.00647309 -0.550946 -0.834516 -0.0164892 -0.755166 -0.655326 -4.64789e-07 -0.692092 -0.721809 1.89486e-06 -0.854871 -0.518841 -0.00189966 -0.872617 -0.488401 0.00302979 -0.942196 -0.335047 0 -0.953586 -0.30112 0 -0.953523 0.301319 0.0054716 -0.932092 0.362181 -0.0187191 -0.431921 0.901717 -0.00145965 -0.342495 0.939519 0.000530866 -0.577842 0.816148 0.0041444 -0.531614 0.846977 -0.0134106 -0.759742 0.650086 0.00670947 -0.69479 0.719181 -0.0019003 -0.872519 0.488577 0.00600255 -0.188818 0.981994 -0.011457 0.120768 0.992615 0 0.0579772 0.998318 0 -0.989129 -0.147048 -0.00911721 -0.975241 -0.220957 2.68074e-06 -0.933839 -0.357694 1.5773e-06 -0.896983 -0.442064 0.00151502 -0.860442 -0.509546 -0.00838407 -0.780033 -0.625682 0.00533836 -0.695419 -0.718585 -0.00750021 -0.461747 -0.88698 0 -0.41755 -0.908654 0 -0.675114 0.737714 0.00547192 -0.62612 0.779707 -0.0187219 0.0767832 0.996872 -0.00145932 0.173147 0.984895 0.000531521 -0.0923219 0.995729 0.00414661 -0.0368493 0.999312 -0.0134135 -0.332931 0.942856 0.0067119 -0.24211 0.970226 -0.0018985 -0.511352 0.859369 0.00600213 0.327471 0.944842 -0.0114559 0.600895 0.799246 0 0.549373 0.835577 0 -0.998501 -0.0547403 -0.00705598 -0.98076 -0.19509 0.00350845 -0.961519 -0.274714 -0.0041759 -0.83147 -0.555554 0 -0.815943 -0.578132 0 -0.215777 0.976443 0.0054689 -0.152384 0.988306 -0.0187191 0.564948 0.824914 -0.00145996 0.642397 0.766371 0.000530648 0.417905 0.908491 0.00414263 0.467695 0.88388 -0.013413 0.183105 0.983002 0.00671265 0.275445 0.961293 -0.00189934 -0.0132024 0.999911 0.00600284 0.756015 0.654526 -0.0114558 0.920017 0.39171 0 0.893564 0.448936 0 -0.991442 -0.130545 0 -0.991442 -0.130545 0 0.301319 0.953523 0.00547185 0.362184 0.932091 -0.0194947 0.898144 0.439269 -2.90755e-06 0.939518 0.342499 4.45369e-07 0.811439 0.584438 0.0041521 0.847063 0.531476 -0.0134145 0.650069 0.759757 0.00671183 0.719186 0.694785 -0.00189835 0.488554 0.872532 0.00600221 0.981993 0.188824 -0.0114562 0.992615 -0.120762 0 0.998318 -0.0579737 0.0048595 -0.467799 0.883821 -0.00849914 -0.642375 0.766344 0.00422981 -0.718576 0.695436 -0.00530367 -0.893548 0.448937 0 -0.908639 0.417583 0.00647362 -0.447254 0.894384 -0.0164914 -0.189938 0.981658 8.19088e-07 -0.279069 0.960271 2.94923e-06 -0.0218741 0.999761 -0.00190064 0.0133978 0.999908 0.00302704 0.180943 0.983489 0 0.215988 0.976396 0 0.73771 0.675118 0.00547169 0.779703 0.626126 -0.019495 0.99745 -0.0686596 -2.90999e-06 0.984895 -0.173152 3.51253e-07 0.994941 0.100459 0.00413972 0.999308 0.0369684 -0.0134127 0.942858 0.332926 0.0067124 0.970227 0.242106 -0.00189822 0.85936 0.511367 0.00600204 0.944842 -0.327472 -0.0114556 0.799249 -0.600891 0 0.83558 -0.54937 0.00486231 0.0368397 0.999309 -0.00850008 -0.173142 0.98486 0.00422875 -0.274587 0.961553 -0.00530448 -0.549367 0.835564 0 -0.578118 0.815953 0.00647264 0.0598596 0.998186 -0.0164924 0.326333 0.945111 -1.35626e-06 0.238457 0.971153 6.40954e-07 0.480951 0.876747 -0.00190087 0.511538 0.859258 0.00302803 0.648458 0.761244 0 0.67527 0.737571 0 0.976435 0.215811 0.00547179 0.988306 0.152385 -0.0194958 0.82949 -0.558182 -1.9434e-06 0.766365 -0.642405 1.01062e-06 0.91187 -0.410478 0.00413679 0.883932 -0.467596 -0.013413 0.983002 -0.183104 0.00671166 0.961295 -0.27544 -0.00189848 0.999912 0.0131678 0.00600134 0.654522 -0.75602 -0.0114567 0.39172 -0.920013 0 0.448949 -0.893557 0.00487018 0.531656 0.846946 -0.00849991 0.342478 0.939487 0.00422829 0.242975 0.970023 -0.00530474 -0.0579775 0.998304 0 -0.0926834 0.995696 0.00647217 0.550929 0.834527 -0.0164933 0.75517 0.655321 -1.68389e-06 0.692086 0.721815 3.94532e-07 0.854888 0.518812 -0.00190107 0.872633 0.488373 0.00302784 0.942202 0.335031 0 0.953585 0.301125 0 0.953523 -0.301319 0.00547181 0.932091 -0.362183 -0.0187227 0.43194 -0.901708 -0.00145908 0.342492 -0.939519 0.000531661 0.577822 -0.816163 0.00414028 0.531658 -0.846949 -0.0134132 0.759753 -0.650073 0.00671168 0.694786 -0.719186 -0.00189854 0.872532 -0.488553 0.00600196 0.188819 -0.981993 -0.0114556 -0.120763 -0.992615 0 -0.0579783 -0.998318 0.00487008 0.883901 0.467648 -0.00850013 0.76634 0.642379 0.00422814 0.695435 0.718577 -0.00530486 0.448943 0.893545 0 0.417582 0.908639 0.00647202 0.894382 0.447257 -0.0164935 0.981658 0.189938 -1.61532e-06 0.960272 0.279067 4.14436e-07 0.999761 0.02186 -0.001901 0.999909 -0.0133721 0.00302795 0.983487 -0.180956 0 0.976391 -0.216012 0 0.675123 -0.737705 0.00547258 0.626123 -0.779705 -0.0187218 -0.076784 -0.996872 -0.00145918 -0.173148 -0.984895 0.000531442 0.0923219 -0.995729 0.00414718 0.0368398 -0.999313 -0.0134134 0.332933 -0.942855 0.00671227 0.24211 -0.970226 -0.00189785 0.511356 -0.859367 0.00600223 -0.327469 -0.944843 -0.0114561 -0.600898 -0.799243 0 -0.549375 -0.835576 0.00487135 0.999305 -0.0369683 -0.00849963 0.98486 0.173146 0.00422875 0.961553 0.274587 -0.00530428 0.835568 0.549362 0 0.815958 0.578111 0.00647233 0.998186 -0.0598544 -0.0164924 0.945112 -0.32633 -1.16958e-06 0.971154 -0.238453 1.01617e-06 0.876747 -0.480951 -0.00190048 0.859258 -0.511538 0.00302852 0.761244 -0.648458 0 0.737567 -0.675274 0 0.215815 -0.976434 0.00547214 0.152384 -0.988306 -0.0187191 -0.564948 -0.824914 -0.00145996 -0.642397 -0.766371 0.000530648 -0.417905 -0.908491 0.00415045 -0.467801 -0.883824 -0.0134126 -0.183107 -0.983001 0.00671215 -0.275443 -0.961294 -0.00189822 0.0131655 -0.999912 0.00600284 -0.756015 -0.654526 -0.0114551 -0.920013 -0.391721 0 -0.89356 -0.448943 0.00485469 0.847061 -0.531474 -0.00850108 0.939484 -0.342487 0.0042285 0.970024 -0.242972 -0.00530466 0.998304 0.0579729 0 0.995696 0.0926785 0.00647256 0.83452 -0.550939 -0.0164908 0.655331 -0.755162 -1.31815e-06 0.721815 -0.692086 1.28773e-06 0.518838 -0.854873 -0.00190152 0.488377 -0.87263 0.00302763 0.335024 -0.942205 0 0.301121 -0.953586 0 0.965925 0.258821 0 0.965925 0.258821 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707105 0.707109 0 -0.707105 0.707109 0 -0.965928 0.258813 0 -0.965928 0.258813 0 0.965923 0.258829 0 0.965923 0.258829 0 0.707112 0.707101 0 0.707112 0.707101 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707103 0.70711 0 -0.707103 0.70711 0 -0.965923 0.258829 0 -0.965923 0.258829 0 0.965923 0.258829 0 0.965923 0.258829 0 0.707112 0.707101 0 0.707112 0.707101 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707103 0.70711 0 -0.707103 0.70711 0 -0.965923 0.258829 0 -0.965923 0.258829 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707102 0.707111 0 -0.707102 0.707111 0 -0.965928 0.258811 0 -0.965928 0.258811 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965926 0.25882 0 -0.965926 0.25882 0 0.965927 0.258816 0 0.965927 0.258816 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965927 0.258816 0 -0.965927 0.258816 0 0.965926 0.258818 0 0.965926 0.258818 0 0.707106 0.707108 0 0.707106 0.707108 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.25882 0 -0.965926 0.25882 0 0.965926 0.258818 0 0.965926 0.258818 0 0.707106 0.707107 0 0.707106 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.965926 0.258818 0 0.965926 0.258818 0 0.707106 0.707107 0 0.707106 0.707107 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.974928 0.222521 0 0.974928 0.222521 0 0.781834 0.623487 0 0.781834 0.623487 0 0.433882 0.90097 0 0.433882 0.90097 0 0 1 0 0 1 0 -0.433882 0.90097 0 -0.433882 0.90097 0 -0.781834 0.623487 0 -0.781834 0.623487 0 -0.974927 0.222524 0 -0.974927 0.222524 0 0.965926 0.258817 0 0.965926 0.258817 0 0.707105 0.707109 0 0.707105 0.707109 0 0.258821 0.965925 0 0.258821 0.965925 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707105 0.707109 0 -0.707105 0.707109 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 0.965926 0.25882 0 0.965926 0.25882 0 0.977737 0.209832 0.0207829 0.999784 0 0.0135978 0.999756 -0.0174295 2.45935e-05 0.975394 -0.220471 -7.82666e-05 0.927791 -0.3731 0.0260761 0.865731 -0.499831 -0.00215452 0.793326 -0.608793 0.000903078 0.656126 -0.75465 0.0168388 0.49993 -0.865902 0.0278904 0.533004 -0.845653 0.0165775 -0.0152572 -0.999746 -6.73655e-05 0.206904 -0.978361 0.000126059 0.356508 -0.934292 0.0769743 -0.205754 -0.975572 -0.00021821 0 -1 0.000123807 -0.398995 -0.916953 0.0258754 -0.499833 -0.865735 -0.000128126 -0.622874 -0.782322 8.52841e-05 -0.758878 -0.651233 0.0244951 -0.865765 -0.499851 0 -0.901296 -0.433204 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.707106 0.707108 0 -0.707106 0.707108 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.575166 -0.818036 0.0191628 0.522402 -0.852484 3.75668e-05 0.368624 -0.929579 -4.84834e-05 0.232448 -0.972609 0.0198222 0.0784439 -0.996721 0.0210647 0.0834494 -0.996289 1.75784e-05 -0.532667 -0.846325 0.012919 -0.40987 -0.912052 0.0188788 -0.382614 -0.923715 -0.00012201 -0.247324 -0.968933 0.000120578 -0.0633974 -0.997988 -2.61938e-05 -0.662477 -0.749083 0.01841 -0.760277 -0.649338 -0.000103388 -0.819456 -0.573142 4.99917e-05 -0.920171 -0.391517 0.0162576 -0.972242 -0.233411 0 -0.986059 -0.166394 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.0829871 -0.996551 0.0162067 0.0313416 -0.999377 2.8032e-05 -0.14653 -0.989206 -4.87399e-05 -0.282877 -0.959156 0.0199415 -0.416375 -0.908974 0.016917 -0.428527 -0.903371 -2.31094e-05 -0.92346 -0.383694 4.48022e-05 -0.851574 -0.524235 0.0184597 -0.777221 -0.628956 -0.000196787 -0.708773 -0.705436 0.000122807 -0.546424 -0.837509 0.00725638 -0.955254 -0.295698 0.0168691 -0.974667 -0.223026 0 -0.991327 -0.131417 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 -0.409942 -0.912112 0.0164579 -0.461687 -0.88689 3.78932e-05 -0.597341 -0.801988 -6.49407e-05 -0.714682 -0.69945 0.0187798 -0.793217 -0.608649 0.00926083 -0.822732 -0.568354 -0.00946002 -0.932535 -0.360956 0.016719 -0.976159 -0.216412 0 -0.995343 -0.0963979 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.707108 0.707106 0 0.707108 0.707106 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.785876 -0.618384 0.0170078 -0.83135 -0.555489 0.000723742 -0.88912 -0.457674 -0.000947188 -0.956215 -0.292665 0.015539 -0.980667 -0.195066 0 -0.995502 -0.0947361 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.965925 0.258822 0 0.965925 0.258822 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.991445 -0.130526 0 -0.991445 -0.130526 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.951664 0.30714 0.0207809 -0.865838 0.499893 0.0136012 -0.857106 0.514961 2.54426e-05 -0.734493 0.678616 -7.74304e-05 -0.616946 0.787006 0.0260763 -0.499831 0.865731 -0.0021531 -0.382658 0.923888 0.000902479 -0.190907 0.981608 0.016839 0 0.999858 0.027892 -0.038773 0.998859 0.016574 0.513071 0.858186 -6.7477e-05 0.309992 0.950739 0.000125844 0.158396 0.987376 0.0769691 0.665963 0.742004 -0.000217589 0.500001 0.866025 0.00012448 0.804011 0.594614 0.0258759 0.865735 0.499833 -0.000128098 0.930582 0.366084 8.52083e-05 0.982823 0.18455 0.0244926 0.9997 0 0 0.997148 -0.0754724 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.707107 -0.707107 0 0.707107 -0.707107 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.670603 0.741816 0.0171479 -0.531955 0.846599 0.000513873 -0.490033 0.871704 -0.000469133 -0.179194 0.983814 0.0160238 -0.111949 0.993585 5.66211e-05 0.0455945 0.99896 -7.22829e-05 0.19574 0.980656 0.0170235 0.33023 0.943747 0.017331 0.328768 0.944252 -3.31567e-05 0.814749 0.579814 0.0090535 0.743639 0.66852 0.0172984 0.707002 0.707 0.00159909 0.630914 0.775851 -0.0013069 0.462208 0.88677 6.51517e-05 0.90141 0.432967 0.0179053 0.943732 0.330225 -0.000135603 0.975253 0.221091 8.97037e-05 0.999273 0.0381294 0.0170369 0.993568 -0.111948 -0.0098007 0.974166 -0.225621 0.0123788 0.84666 -0.531991 0 0.825819 -0.563935 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.258818 -0.965926 0 0.258819 -0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.209847 0.977734 0.0207813 0 0.999784 0.0136008 0.0174174 0.999756 2.505e-05 0.220454 0.975397 -7.78816e-05 0.373096 0.927793 0.0260757 0.49983 0.865731 -0.00215335 0.608781 0.793336 0.00090217 0.754643 0.656134 0.0168388 0.865903 0.499929 0.0278918 0.845651 0.533008 0.0165744 0.999747 -0.0152405 -6.71491e-05 0.97836 0.206909 0.00012627 0.934289 0.356517 0.0769704 0.975574 -0.205743 -0.000217986 1 0 0.000124186 0.916956 -0.398988 0.0258755 0.865736 -0.499832 -0.000128139 0.782329 -0.622865 8.5281e-05 0.651235 -0.758876 0.0244924 0.499851 -0.865765 0 0.433214 -0.901291 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258818 0.965926 0 0.258818 0.965926 0 0.307145 0.951663 0.0207837 0.499893 0.865838 0.0135979 0.514974 0.857098 2.54651e-05 0.678622 0.734488 -7.75247e-05 0.787012 0.616937 0.0260758 0.865731 0.49983 -0.00215475 0.923893 0.382645 0.000902825 0.981609 0.190899 0.0168388 0.999858 0 0.0278901 0.998859 0.0387673 0.0165774 0.858178 -0.513085 -6.72114e-05 0.950737 -0.309998 0.000126194 0.987375 -0.1584 0.0769752 0.741992 -0.665975 -0.000218203 0.866026 -0.5 0.00012386 0.594606 -0.804017 0.0258749 0.499832 -0.865736 -0.000128034 0.366077 -0.930585 8.53798e-05 0.184538 -0.982825 0.0244945 0 -0.9997 0 -0.0754811 -0.997147 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.707106 -0.707107 0 -0.707106 -0.707107 0 0.707107 0.707107 0 0.707107 0.707107 0 0.741825 0.670594 0.0207839 0.865839 0.499892 0.0135976 0.87453 0.484781 2.52896e-05 0.954948 0.296774 -7.76264e-05 0.990041 0.140778 0.0260759 0.99966 0 -0.00215468 0.991437 -0.130566 0.000902699 0.94555 -0.325476 0.0168391 0.865903 -0.499929 0.0278892 0.884419 -0.46586 0.016577 0.48666 -0.873434 -6.77197e-05 0.668365 -0.743833 0.000125722 0.775892 -0.630866 0.0769736 0.309599 -0.947746 -0.000218694 0.500001 -0.866025 0.000123301 0.112935 -0.993602 0.0258742 0 -0.999665 -0.000128631 -0.148259 -0.988949 8.47822e-05 -0.331598 -0.943421 0.024494 -0.499851 -0.865765 0 -0.563942 -0.825815 0.629836 -0.174024 -0.756983 0.686336 -0.163796 -0.7086 0.69825 -0.162031 -0.697275 0.781953 -0.161331 -0.602097 0.690894 -0.202125 -0.694127 0.667122 -0.209047 -0.715016 0.553549 -0.234534 -0.79911 0 -0.314339 -0.949311 0.00489604 -0.362235 -0.932074 -0.00258009 -0.522738 -0.85249 2.45927e-06 -0.564763 -0.825253 -6.23317e-07 -0.739347 -0.673324 -0.00345856 -0.72431 -0.689466 0.00164489 -0.873115 -0.487511 0.00321505 -0.883262 -0.468869 -0.00719403 -0.974689 -0.22345 -0.0110163 -0.969208 -0.245997 0 -0.997726 -0.0673997 0.00486713 0.467693 -0.883878 -0.00849914 0.642375 -0.766344 0.00423078 0.718581 -0.69543 -0.00530241 0.893552 -0.448929 0 0.908639 -0.417583 0.00647286 0.447254 -0.894384 -0.016492 0.189935 -0.981658 1.25722e-06 0.279071 -0.96027 2.98336e-06 0.0218748 -0.999761 -0.00190063 -0.0133976 -0.999908 0.00302725 -0.18094 -0.983489 0 -0.215988 -0.976396 0 0.974927 0.222525 0 0.974927 0.222525 0 0.781836 0.623485 0 0.781836 0.623485 0 0.43388 0.900971 0 0.43388 0.900971 0 0 1 0 0 1 0 -0.433884 0.900969 0 -0.433884 0.900969 0 -0.781836 0.623485 0 -0.781836 0.623485 0 -0.974927 0.222525 0 -0.974927 0.222525 0 -0.965926 0.258818 0 -0.965926 0.258818 0 0.965925 -0.258822 0 0.965925 -0.258822 -0.000516954 -0.219335 -0.97565 0 0.936672 -0.350208 0.0259649 0.876432 -0.480826 0.017422 0.860934 -0.508419 0.00595219 0.812038 -0.583575 0.0141146 0.51488 -0.857146 0.0243239 0.570189 -0.821153 0.0196148 0.555464 -0.831309 -4.68079e-05 0.68538 -0.728185 3.24496e-05 0.769726 -0.638374 0.000503244 -0.0351993 -0.99938 0.0211311 0.125564 -0.99186 0.0170876 0.108853 -0.993911 -7.7543e-05 0.275258 -0.96137 0.000103441 0.430705 -0.902493 0.0206998 -0.751679 -0.659204 0.00409254 -0.678381 -0.734699 -0.010015 -0.36242 -0.931961 0.0608844 -0.531456 -0.844895 0.0221597 -0.386163 -0.922164 0 -0.971342 -0.237688 0.0650629 -0.993864 -0.0894532 0.0155071 -0.968623 -0.248052 -0.00126029 -0.905724 -0.423867 0.00292815 -0.810102 -0.586282 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.705594 0.705594 0.0653828 0.705581 0.705606 0.0653844 0.705582 0.681577 0.193926 0.70559 0.68157 0.193923 0.705589 0.634332 0.31586 0.705591 0.63433 0.315859 0.705591 0.565491 0.427038 0.705582 0.565497 0.427044 0.705583 0.477399 0.523682 0.705588 0.477396 0.523678 0.705588 0.373042 0.602483 0.705589 0.373041 0.602482 0.705587 0.255984 0.660771 0.70559 0.255983 0.660769 0.70559 0.130209 0.696555 0.705588 0.130209 0.696557 0.705587 0 0.708623 0.705587 0 0.708623 0.705588 -0.130209 0.696557 0.70559 -0.130209 0.696555 0.70559 -0.255983 0.660769 0.705582 -0.255986 0.660776 0.705582 -0.373045 0.602488 0.705588 -0.373042 0.602483 0.705588 -0.477396 0.523678 0.705588 -0.477396 0.523678 0.705587 -0.565493 0.427041 0.705588 -0.565493 0.42704 0.705588 -0.634333 0.31586 0.705589 -0.634331 0.31586 0.705589 -0.68157 0.193923 0.705588 -0.681571 0.193924 0.705588 -0.705599 0.0653835 0.705587 -0.7056 0.0653836 -0.705587 -0.7056 0.0653836 -0.705588 -0.705599 0.0653835 -0.705588 -0.681571 0.193924 -0.705589 -0.68157 0.193923 -0.705589 -0.634332 0.31586 -0.705588 -0.634333 0.31586 -0.705588 -0.565493 0.42704 -0.705587 -0.565493 0.427041 -0.705588 -0.477396 0.523678 -0.705588 -0.477396 0.523678 -0.705588 -0.373042 0.602483 -0.705582 -0.373045 0.602488 -0.705582 -0.255986 0.660776 -0.70559 -0.255983 0.660769 -0.70559 -0.130209 0.696555 -0.705588 -0.130209 0.696557 -0.705587 0 0.708623 -0.705587 0 0.708623 -0.705588 0.130209 0.696557 -0.70559 0.130209 0.696555 -0.70559 0.255983 0.660769 -0.705587 0.255984 0.660771 -0.705589 0.373041 0.602482 -0.705588 0.373042 0.602483 -0.705588 0.477396 0.523678 -0.705583 0.477399 0.523681 -0.705582 0.565498 0.427044 -0.705591 0.56549 0.427039 -0.705591 0.63433 0.315859 -0.705589 0.634331 0.315859 -0.70559 0.68157 0.193924 -0.705582 0.681577 0.193926 -0.705581 0.705606 0.0653839 -0.705594 0.705594 0.0653832 0.195049 0.733436 0.651173 0.83098 0.503357 0.236862 0.830973 -0.138349 0.538835 0.830977 -0.503362 0.236864 0.965809 0.258745 0.0162788 0.980701 0.192051 0.0366354 0.980699 -0.195136 0.0122769 0.980699 -0.195136 0.0122769 0.9807 -0.176912 0.0832487 0.9807 -0.176911 0.083248 0.9807 -0.18595 0.0604187 0.980699 -0.0486243 0.189379 0.980699 -0.048625 0.189382 0.980699 -0.0719775 0.181794 0.980698 0.176921 0.0832529 0.9807 0.176912 0.0832488 0.9807 0.165084 0.104765 0.896639 -0.441889 0.0278013 0.830995 -0.555137 0.0356377 0.792723 -0.608379 0.0382759 0.554833 -0.702448 0.445787 0.830976 -0.469707 0.298085 0.830974 -0.469709 0.298086 0.9807 -0.165084 0.104765 0.9807 -0.165083 0.104765 0.554832 -0.104273 0.825402 0.830973 -0.0697246 0.551927 0.830982 -0.0697226 0.551913 0.980699 -0.0245053 0.19398 0.980699 -0.0245054 0.19398 0.554834 0.791242 0.257089 0.83098 0.529075 0.171906 0.830963 0.529099 0.171915 0.980698 0.185961 0.0604223 0.980698 0.185961 0.0604224 0.554843 -0.791236 0.257088 0.195056 -0.85448 0.481474 0.194696 -0.887512 0.417631 0.554843 -0.752775 0.354229 0.554843 -0.791236 0.257088 0.830977 -0.529079 0.171908 0.55484 -0.569514 0.60647 0.195005 -0.508082 0.838943 0.194676 -0.57654 0.793538 0.554836 -0.489014 0.67307 0.554838 -0.569515 0.606471 0.830971 -0.380825 0.405537 0.980699 -0.133845 0.142531 0.980699 -0.114926 0.158182 0.830975 -0.326991 0.450065 0.830975 -0.268004 0.487498 0.554836 -0.4008 0.729052 0.554834 -0.306265 0.773538 0.980699 -0.114925 0.158181 0.980699 -0.094194 0.171338 0.830979 -0.268001 0.487493 0.830979 -0.204789 0.517238 0.554857 -0.306259 0.773523 0.554856 -0.206896 0.805809 0.194724 -0.243929 0.950043 0.19509 -0.177048 0.964673 0.554832 0.104273 0.825402 0.195045 0.319316 0.927359 0.194704 0.24393 0.950047 0.554822 0.206902 0.805832 0.554824 0.104273 0.825407 0.830982 0.0697228 0.551913 0.9807 0.0245051 0.193978 0.9807 0.0486236 0.189376 0.830973 0.138349 0.538835 0.830974 0.204792 0.517245 0.554826 0.306267 0.773543 0.554825 0.400803 0.729058 0.980699 0.0486246 0.18938 0.980699 0.0719766 0.181792 0.83098 0.204789 0.517237 0.830979 0.268002 0.487492 0.554856 0.400794 0.72904 0.554856 0.489006 0.673059 0.194736 0.576533 0.793529 0.195104 0.627807 0.753521 0.980699 0.114926 0.158182 0.980699 0.133845 0.142531 0.830977 0.380818 0.40553 0.830979 0.42864 0.354602 0.554813 0.641048 0.530321 0.554814 0.702459 0.445794 0.9807 0.133842 0.142527 0.9807 0.15065 0.124628 0.830975 0.428644 0.354605 0.830974 0.469709 0.298087 0.554814 0.702459 0.445794 0.554811 0.752794 0.354239 0.194606 0.887528 0.41764 0.194955 0.916888 0.348295 0.608066 -0.79232 0.0498485 0.554857 -0.830259 0.0529443 0.441568 -0.895457 0.0563375 0.194708 -0.978926 0.0615889 0.194705 -0.978926 0.0615889 0.980699 -0.192058 0.0366371 0.830977 -0.546453 0.104242 0.830975 -0.546457 0.104242 0.554844 -0.817218 0.155893 0.554837 -0.817223 0.155893 0.751867 -0.647636 0.123543 0.195022 -0.969771 0.146664 0.194703 -0.887511 0.417631 0.195055 -0.91687 0.348287 0.662082 -0.712751 0.231587 0.194854 -0.936968 0.29004 0.19494 -0.958664 0.20727 0.980699 -0.192059 0.0366372 0.980699 -0.185953 0.0604196 0.830971 -0.529088 0.171911 0.830971 -0.50337 0.236868 0.554841 -0.752777 0.35423 0.554842 -0.702444 0.445785 0.599427 -0.675825 0.428892 0.194839 -0.822598 0.534201 0.9807 -0.150651 0.12463 0.830971 -0.428649 0.354609 0.830975 -0.428644 0.354605 0.554841 -0.641033 0.530309 0.554831 -0.641039 0.530313 0.76211 -0.498867 0.412699 0.194983 -0.772886 0.603845 0.194715 -0.576535 0.793533 0.195084 -0.627809 0.753524 0.37651 -0.634173 0.675326 0.19476 -0.673931 0.712661 0.195015 -0.733441 0.651179 0.9807 -0.150651 0.12463 0.980699 -0.133843 0.142529 0.830977 -0.380819 0.405531 0.830977 -0.326989 0.450062 0.554856 -0.489006 0.673059 0.554856 -0.400793 0.72904 0.733503 -0.327441 0.595613 0.194704 -0.24393 0.950046 0.195045 -0.319316 0.927359 0.704815 -0.261144 0.659575 0.194894 -0.376926 0.905507 0.194922 -0.45441 0.869205 0.980699 -0.0941933 0.171337 0.980699 -0.0719763 0.181791 0.830971 -0.204794 0.51725 0.830971 -0.13835 0.538839 0.554828 -0.206902 0.805828 0.554827 -0.104273 0.825405 0.508059 -0.107952 0.85453 0.194783 -0.116136 0.973947 0.980699 0 0.195521 0.83098 0 0.556302 0.83098 0 0.556302 0.554833 0 0.831962 0.554832 0 0.831962 0.765398 0 0.643557 0.194985 -0.0308079 0.980322 0.194718 0.24393 0.950044 0.195085 0.177049 0.964674 0.508059 0.107952 0.85453 0.194783 0.116136 0.973947 0.194985 0.0308079 0.980322 0.980699 0 0.195521 0.980699 0.0245053 0.19398 0.830973 0.0697242 0.551926 0.830973 0.138349 0.538835 0.554851 0.206898 0.805813 0.554849 0.306262 0.773529 0.704815 0.261144 0.659575 0.194676 0.576539 0.793539 0.195006 0.508082 0.838943 0.733503 0.327441 0.595613 0.194922 0.45441 0.869205 0.194894 0.376926 0.905507 0.9807 0.0719755 0.181789 0.9807 0.094192 0.171335 0.830971 0.268008 0.487504 0.830969 0.326995 0.450071 0.55481 0.489024 0.673084 0.554808 0.569528 0.606486 0.376527 0.634168 0.675321 0.194791 0.673926 0.712657 0.9807 0.0941927 0.171336 0.9807 0.114923 0.158179 0.830983 0.326984 0.450055 0.830983 0.380812 0.405524 0.554819 0.569524 0.606481 0.554815 0.641047 0.53032 0.76211 0.498867 0.412699 0.194709 0.88751 0.41763 0.19507 0.854477 0.481473 0.599427 0.675825 0.428892 0.194852 0.822596 0.534199 0.194995 0.772884 0.603844 0.980699 0.150653 0.124631 0.980699 0.165085 0.104766 0.830989 0.469691 0.298075 0.83099 0.503344 0.236856 0.554865 0.752762 0.354223 0.554864 0.791223 0.257083 0.662053 0.712776 0.231594 0.194928 0.936953 0.290037 0.194969 0.969782 0.146664 0.980698 0.192068 0.0366389 0.830975 0.546457 0.104242 0.830963 0.546474 0.104246 0.554858 0.817209 0.155892 0.554833 0.817225 0.155895 0.751872 0.64763 0.123543 0.195015 0.95865 0.207267 0.980683 0.195301 0.01088 0.792646 0.608411 0.0393425 0.830975 0.555213 0.0349306 0.608126 0.792274 0.0498451 0.554879 0.830244 0.0529434 0.258319 0.964219 0.0596053 0.194654 0.978936 0.0615898 -0.19504 -0.733437 0.651176 -0.19501 0.0308078 0.980317 -0.830971 -0.50337 0.236868 -0.83099 0.503344 0.236856 -0.965804 -0.258761 0.0162799 -0.980724 -0.191938 0.0366141 -0.980725 0.195006 0.0122687 -0.980727 0.195 0.0122684 -0.980724 0.176801 0.0831967 -0.980722 0.17681 0.0832005 -0.980722 0.185844 0.0603844 -0.980724 -0.1768 0.0831957 -0.980724 -0.176801 0.0831965 -0.980724 -0.16498 0.1047 -0.896497 0.442176 0.0278195 -0.830995 0.555137 0.0356364 -0.792771 0.608317 0.0382716 -0.554756 0.702492 0.445815 -0.830989 0.46969 0.298074 -0.830974 0.469709 0.298086 -0.980724 0.16498 0.1047 -0.980724 0.164982 0.104701 -0.554785 -0.791273 0.2571 -0.830971 -0.529088 0.171911 -0.830977 -0.529079 0.171908 -0.980724 -0.185833 0.0603808 -0.980724 -0.185836 0.0603818 -0.554775 0.79128 0.257101 -0.195094 0.854473 0.481471 -0.194734 0.887505 0.417629 -0.554805 0.752798 0.354241 -0.554806 0.79126 0.257095 -0.830963 0.529099 0.171914 -0.554761 0.56955 0.606509 -0.19503 0.50808 0.838939 -0.1947 0.576537 0.793534 -0.55475 0.489048 0.673116 -0.554749 0.569555 0.606515 -0.830977 0.380818 0.40553 -0.980723 0.133762 0.142441 -0.980723 0.114854 0.158083 -0.830969 0.326996 0.450071 -0.83097 0.268008 0.487504 -0.554766 0.400823 0.729093 -0.554768 0.306282 0.773579 -0.980724 0.114851 0.158079 -0.980724 0.0941335 0.171228 -0.830979 0.268001 0.487493 -0.830979 0.204789 0.517238 -0.554791 0.306276 0.773565 -0.554792 0.206907 0.805851 -0.194742 0.243928 0.950039 -0.195109 0.177048 0.964669 -0.980724 0.048593 0.189257 -0.980724 0.0244897 0.193857 -0.830982 0.0697226 0.551913 -0.83098 0 0.556302 -0.554774 0 0.832001 -0.554773 -0.104278 0.825441 -0.980724 0.02449 0.193859 -0.980724 0 0.195399 -0.83098 0 0.556302 -0.830982 -0.0697229 0.551913 -0.554769 -0.104278 0.825444 -0.554768 -0.206911 0.805866 -0.194728 -0.243929 0.950042 -0.195069 -0.319314 0.927355 -0.980724 -0.0244899 0.193858 -0.980724 -0.0485939 0.189261 -0.830971 -0.13835 0.538838 -0.83097 -0.204794 0.51725 -0.554776 -0.306279 0.773574 -0.554777 -0.400819 0.729087 -0.980723 -0.0485944 0.189263 -0.980723 -0.0719323 0.18168 -0.830979 -0.204789 0.517238 -0.830979 -0.268001 0.487493 -0.554797 -0.400812 0.729075 -0.554797 -0.489029 0.673091 -0.194741 -0.576532 0.793528 -0.195109 -0.627806 0.75352 -0.980723 -0.114854 0.158083 -0.980724 -0.133761 0.142441 -0.830971 -0.380825 0.405537 -0.830971 -0.428648 0.354609 -0.554773 -0.641068 0.530338 -0.554774 -0.702482 0.445809 -0.980724 -0.13376 0.142439 -0.980724 -0.150557 0.124552 -0.830975 -0.428644 0.354605 -0.830974 -0.469709 0.298086 -0.554782 -0.702477 0.445806 -0.554782 -0.752812 0.354246 -0.194727 -0.887506 0.417629 -0.19508 -0.916865 0.348285 -0.608034 0.792344 0.0498495 -0.55482 0.830284 0.0529455 -0.441644 0.89542 0.0563355 -0.194679 0.978932 0.0615896 -0.194669 0.978934 0.0615896 -0.980725 0.191931 0.0366127 -0.830963 0.546474 0.104245 -0.830975 0.546456 0.104243 -0.554775 0.817264 0.155902 -0.5548 0.817247 0.155899 -0.751915 0.647583 0.123534 -0.194993 0.969777 0.146663 -0.19463 0.887524 0.417636 -0.19498 0.916883 0.348293 -0.662102 0.712735 0.231581 -0.194952 0.936949 0.290036 -0.195039 0.958645 0.207266 -0.980722 0.191947 0.0366156 -0.980722 0.185844 0.0603844 -0.83098 0.529074 0.171907 -0.83098 0.503358 0.236862 -0.554752 0.75283 0.354255 -0.554755 0.702492 0.445815 -0.599477 0.675794 0.428872 -0.194876 0.822592 0.534197 -0.980724 0.150558 0.124553 -0.830979 0.428639 0.354601 -0.830975 0.428644 0.354605 -0.554756 0.641077 0.530345 -0.554755 0.641078 0.530345 -0.762151 0.49883 0.412668 -0.19502 0.77288 0.603841 -0.194758 0.57653 0.793526 -0.195128 0.627804 0.753517 -0.376569 0.634157 0.675308 -0.194816 0.673923 0.712654 -0.195074 0.733433 0.65117 -0.980724 0.150555 0.12455 -0.980724 0.133758 0.142438 -0.830983 0.380812 0.405523 -0.830983 0.326984 0.450055 -0.554797 0.489029 0.673091 -0.554798 0.400812 0.729074 -0.733547 0.327418 0.595572 -0.194728 0.243929 0.950042 -0.195069 0.319314 0.927355 -0.704861 0.261128 0.659533 -0.194918 0.376924 0.905503 -0.194946 0.454408 0.869201 -0.980724 0.0941328 0.171227 -0.980724 0.0719303 0.181675 -0.830974 0.204792 0.517245 -0.830973 0.138349 0.538835 -0.554763 0.206912 0.805869 -0.554766 0.104278 0.825446 -0.508108 0.107949 0.854502 -0.194807 0.116136 0.973942 -0.980724 0.0719314 0.181678 -0.980724 0.0485941 0.189261 -0.830973 0.138349 0.538835 -0.830973 0.0697245 0.551926 -0.554774 0.104277 0.825441 -0.554774 0 0.832001 -0.765439 0 0.643508 -0.19475 -0.243928 0.950038 -0.195115 -0.177047 0.964668 -0.508108 -0.107949 0.854502 -0.194807 -0.116136 0.973942 -0.195009 -0.0308077 0.980317 -0.980724 0 0.195399 -0.980724 -0.02449 0.193859 -0.830973 -0.0697243 0.551927 -0.830973 -0.138349 0.538835 -0.554798 -0.206907 0.805847 -0.554798 -0.306274 0.77356 -0.704861 -0.261128 0.659533 -0.1947 -0.576536 0.793535 -0.19503 -0.50808 0.838939 -0.733547 -0.327418 0.595572 -0.194946 -0.454408 0.869201 -0.194918 -0.376924 0.905503 -0.980724 -0.0719313 0.181677 -0.980724 -0.0941343 0.17123 -0.830975 -0.268004 0.487498 -0.830975 -0.32699 0.450064 -0.554776 -0.489037 0.673102 -0.55478 -0.569541 0.6065 -0.376552 -0.634161 0.675313 -0.194785 -0.673927 0.712658 -0.980724 -0.094135 0.171231 -0.980724 -0.114853 0.158082 -0.830977 -0.326989 0.450062 -0.830976 -0.380819 0.405531 -0.554782 -0.56954 0.606499 -0.554782 -0.641064 0.530334 -0.762151 -0.49883 0.412668 -0.194721 -0.887507 0.417629 -0.195081 -0.854476 0.481471 -0.599477 -0.675794 0.428872 -0.194863 -0.822594 0.534198 -0.195008 -0.772882 0.603842 -0.980724 -0.150557 0.124552 -0.980724 -0.16498 0.104699 -0.830977 -0.469706 0.298084 -0.830976 -0.503362 0.236864 -0.554785 -0.75281 0.354246 -0.554785 -0.791273 0.2571 -0.662131 -0.712711 0.231574 -0.194879 -0.936963 0.290039 -0.195046 -0.969766 0.146663 -0.980724 -0.191938 0.0366142 -0.830975 -0.546457 0.104242 -0.830977 -0.546453 0.104241 -0.554778 -0.817261 0.155901 -0.554785 -0.817257 0.1559 -0.75191 -0.647589 0.123534 -0.194964 -0.95866 0.207269 -0.980706 -0.195187 0.0108701 -0.792782 -0.608235 0.0393282 -0.830975 -0.555213 0.034931 -0.607974 -0.79239 0.0498529 -0.554799 -0.830298 0.0529464 -0.258365 -0.964207 0.0596049 -0.194732 -0.978921 0.0615885 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.998027 0.0627908 0 0.998027 0.0627908 0 0.988757 0.149534 0 0.988757 0.149534 0 0.977416 0.211324 0 0.977416 0.211324 0 0.955278 0.295709 0 0.955278 0.295709 0 0.934825 0.355108 0 0.934825 0.355108 0 0.904827 0.425779 0 0.904827 0.425779 0 0.871214 0.490904 0 0.871214 0.490904 0 0.838671 0.544639 0 0.838671 0.544639 0 0.78801 0.615662 0 0.78801 0.615662 0 0.747799 0.663925 0 0.747799 0.663925 0 0.687087 0.726575 0 0.687087 0.726575 0 0.640108 0.768285 0 0.640108 0.768285 0 0.587785 0.809017 0 0.587785 0.809017 0 0.518027 0.855364 0 0.518027 0.855364 0 0.463296 0.886203 0 0.463296 0.886203 0 0.384295 0.92321 0 0.384295 0.92321 0 0.325568 0.945518 0 0.325568 0.945518 0 0.24869 0.968583 0 0.24869 0.968583 0 0.180517 0.983572 0 0.180517 0.983572 0 0.118404 0.992966 0 0.118404 0.992966 0 0.0314108 0.999507 0 0.0314108 0.999507 0 -0.0314108 0.999507 0 -0.0314108 0.999507 0 -0.118404 0.992966 0 -0.118404 0.992966 0 -0.180516 0.983572 0 -0.180516 0.983572 0 -0.24869 0.968583 0 -0.24869 0.968583 0 -0.325568 0.945518 0 -0.325568 0.945518 0 -0.384295 0.92321 0 -0.384295 0.92321 0 -0.463296 0.886203 0 -0.463296 0.886203 0 -0.518027 0.855364 0 -0.518027 0.855364 0 -0.587785 0.809017 0 -0.587785 0.809017 0 -0.640108 0.768285 0 -0.640108 0.768285 0 -0.687088 0.726575 0 -0.687088 0.726575 0 -0.747798 0.663926 0 -0.747798 0.663926 0 -0.788011 0.615662 0 -0.788011 0.615662 0 -0.838671 0.544639 0 -0.838671 0.544639 0 -0.871214 0.490903 0 -0.871214 0.490903 0 -0.904827 0.425779 0 -0.904827 0.425779 0 -0.934826 0.355107 0 -0.934826 0.355107 0 -0.955278 0.295708 0 -0.955278 0.295708 0 -0.977416 0.211325 0 -0.977416 0.211325 0 -0.988756 0.149535 0 -0.988756 0.149535 0 -0.998027 0.0627906 0 -0.998027 0.0627906 0.202033 -0.978542 -0.0404726 0.202024 -0.978544 -0.0404735 0.202024 -0.971859 -0.121142 0.202028 -0.971859 -0.121142 0.202192 -0.965236 -0.165643 0.148201 -0.966967 -0.207394 0.202066 -0.958528 -0.200981 0.202065 -0.938658 -0.279448 0.202047 -0.938661 -0.279451 0.202204 -0.923317 -0.326496 0.0930404 -0.924188 -0.370433 0.202042 -0.912379 -0.356011 0.202042 -0.879863 -0.43014 0.202051 -0.879861 -0.430139 0.202198 -0.854803 -0.477941 0.0930844 -0.855324 -0.509663 0.202136 -0.834334 -0.512863 0.202044 -0.797065 -0.569093 0.202048 -0.797064 -0.569092 0.202181 -0.761661 -0.615626 0.080693 -0.760595 -0.644192 0.202164 -0.735574 -0.646576 0.20205 -0.692523 -0.692523 0.202044 -0.692523 -0.692524 0.202159 -0.646578 -0.735574 0.0806799 -0.644193 -0.760596 0.202183 -0.615624 -0.761662 0.20205 -0.569093 -0.797063 0.202051 -0.569093 -0.797063 0.202143 -0.512863 -0.834332 0.0930751 -0.509662 -0.855325 0.202194 -0.477939 -0.854805 0.202047 -0.430139 -0.879862 0.202048 -0.430139 -0.879862 0.202114 -0.364371 -0.909056 0.117738 -0.36098 -0.925112 0.202211 -0.326486 -0.923319 0.202054 -0.279452 -0.938659 0.202037 -0.279451 -0.938663 0.202072 -0.205381 -0.957593 0.1543 -0.202758 -0.966996 0.202216 -0.16563 -0.965233 0.202053 -0.121141 -0.971854 0.202049 -0.121141 -0.971854 0.20205 -0.0404732 -0.978539 0.202042 -0.0404726 -0.97854 0.202042 0.0404733 -0.97854 0.20205 0.0404725 -0.978539 0.202049 0.121142 -0.971854 0.202054 0.121141 -0.971853 0.202217 0.165629 -0.965233 0.148211 0.207392 -0.966965 0.202039 0.200984 -0.958533 0.202039 0.279453 -0.938662 0.202054 0.27945 -0.93866 0.202211 0.326486 -0.923319 0.093014 0.370437 -0.924189 0.202052 0.35601 -0.912377 0.202052 0.430138 -0.879861 0.202051 0.430138 -0.879862 0.202198 0.47794 -0.854804 0.0930814 0.509663 -0.855324 0.202143 0.512863 -0.834332 0.202051 0.569092 -0.797063 0.20205 0.569092 -0.797063 0.202183 0.615624 -0.761662 0.0806826 0.644192 -0.760596 0.202164 0.646577 -0.735573 0.20205 0.692523 -0.692523 0.202047 0.692523 -0.692523 0.202161 0.735574 -0.646576 0.0806875 0.760596 -0.644192 0.202185 0.761662 -0.615624 0.202052 0.797063 -0.569092 0.202051 0.797063 -0.569092 0.202143 0.834332 -0.512862 0.0930804 0.855325 -0.509663 0.202195 0.854804 -0.47794 0.202047 0.879862 -0.430139 0.202046 0.879862 -0.430139 0.202112 0.909057 -0.364372 0.117735 0.925112 -0.36098 0.202204 0.923319 -0.326488 0.850921 -0.524845 -0.0217078 0.85092 -0.524847 -0.021708 0.85092 -0.521261 -0.0649763 0.850932 -0.521243 -0.0649721 0.850932 -0.514097 -0.107794 0.85093 -0.5141 -0.107795 0.85093 -0.503443 -0.149881 0.850918 -0.503461 -0.149888 0.850918 -0.489364 -0.190951 0.850927 -0.48935 -0.190944 0.850927 -0.47191 -0.230703 0.850928 -0.471909 -0.230702 0.850928 -0.451246 -0.268884 0.850922 -0.451254 -0.26889 0.850922 -0.427508 -0.305235 0.850925 -0.427505 -0.305232 0.850925 -0.400838 -0.339493 0.850925 -0.400838 -0.339493 0.850925 -0.371434 -0.371434 0.850922 -0.371438 -0.371438 0.850922 -0.339496 -0.400842 0.850923 -0.339495 -0.400841 0.850923 -0.305234 -0.427507 0.850925 -0.305233 -0.427505 0.850925 -0.268887 -0.45125 0.850923 -0.268888 -0.451253 0.850923 -0.230706 -0.471916 0.850926 -0.230704 -0.471912 0.850926 -0.190946 -0.489352 0.850924 -0.190946 -0.489354 0.850924 -0.149883 -0.503451 0.850925 -0.149883 -0.503449 0.850925 -0.107797 -0.514107 0.850924 -0.107797 -0.51411 0.850924 -0.0649747 -0.521255 0.850922 -0.0649748 -0.521258 0.850922 -0.0217073 -0.524843 0.850926 -0.0217076 -0.524837 0.850926 0.0217071 -0.524837 0.850922 0.0217079 -0.524843 0.850922 0.064975 -0.521258 0.850924 0.0649745 -0.521255 0.850924 0.107797 -0.51411 0.850925 0.107797 -0.514108 0.850924 0.149884 -0.503451 0.850925 0.149883 -0.50345 0.850925 0.190946 -0.489353 0.850925 0.190946 -0.489353 0.850925 0.230704 -0.471914 0.850923 0.230706 -0.471916 0.850923 0.268889 -0.451253 0.850926 0.268886 -0.451248 0.850926 0.305231 -0.427503 0.850923 0.305234 -0.427507 0.850923 0.339495 -0.400841 0.850925 0.339493 -0.400838 0.850925 0.371434 -0.371434 0.850924 0.371435 -0.371435 0.850924 0.400839 -0.339494 0.850924 0.40084 -0.339494 0.850924 0.427506 -0.305233 0.850924 0.427506 -0.305233 0.850924 0.451251 -0.268887 0.850925 0.451251 -0.268887 0.850925 0.471914 -0.230705 0.850924 0.471915 -0.230705 0.850924 0.489355 -0.190947 0.850925 0.489353 -0.190946 0.850925 0.50345 -0.149884 0.850924 0.503451 -0.149884 0.850924 0.514109 -0.107797 0.850924 0.514109 -0.107797 0.573255 -0.818677 -0.0338612 0.573259 -0.818674 -0.0338607 0.573259 -0.813082 -0.10135 0.573238 -0.813096 -0.101354 0.573238 -0.80195 -0.168151 0.573239 -0.801949 -0.16815 0.573239 -0.785324 -0.233801 0.573242 -0.785322 -0.2338 0.573242 -0.763333 -0.297853 0.573236 -0.763336 -0.297855 0.573237 -0.736132 -0.359874 0.573237 -0.736132 -0.359874 0.573237 -0.7039 -0.419434 0.57325 -0.703893 -0.419428 0.573249 -0.666853 -0.476123 0.573243 -0.666856 -0.476126 0.573243 -0.62526 -0.529568 0.573243 -0.62526 -0.529568 0.573243 -0.579393 -0.579393 0.573252 -0.579389 -0.579388 0.573251 -0.529565 -0.625255 0.573247 -0.529566 -0.625258 0.573247 -0.476125 -0.666853 0.573239 -0.476127 -0.666858 0.573239 -0.419432 -0.703899 0.573246 -0.41943 -0.703895 0.573245 -0.359871 -0.736127 0.573242 -0.359871 -0.736129 0.573242 -0.297853 -0.763333 0.573244 -0.297853 -0.763331 0.573244 -0.2338 -0.785321 0.573244 -0.2338 -0.785321 0.573244 -0.168151 -0.801945 0.573239 -0.168151 -0.801949 0.573238 -0.101352 -0.813096 0.573246 -0.101352 -0.813091 0.573246 -0.0338609 -0.818683 0.573242 -0.0338606 -0.818686 0.573242 0.033861 -0.818686 0.573246 0.0338604 -0.818683 0.573246 0.101351 -0.813091 0.573238 0.101353 -0.813096 0.573239 0.168152 -0.801949 0.573246 0.16815 -0.801944 0.573246 0.233799 -0.78532 0.573242 0.2338 -0.785322 0.573242 0.297853 -0.763333 0.57324 0.297854 -0.763334 0.57324 0.359872 -0.736131 0.573243 0.359871 -0.736129 0.573242 0.419431 -0.703897 0.573239 0.419433 -0.703899 0.573239 0.476128 -0.666858 0.573247 0.476124 -0.666854 0.573247 0.529566 -0.625258 0.573243 0.529568 -0.62526 0.573243 0.579393 -0.579393 0.573243 0.579393 -0.579393 0.573243 0.62526 -0.529568 0.573243 0.62526 -0.529568 0.573243 0.666856 -0.476126 0.573241 0.666857 -0.476126 0.573242 0.703897 -0.419432 0.573242 0.703897 -0.419431 0.573243 0.736129 -0.359871 0.573245 0.736127 -0.359871 0.573245 0.763331 -0.297853 0.573242 0.763333 -0.297853 0.573242 0.785322 -0.2338 0.573244 0.785321 -0.2338 0.573244 0.801946 -0.16815 0.573242 0.801947 -0.168151 0.202047 0.938661 -0.279451 0.202046 0.938661 -0.279451 0.202081 0.957592 -0.205382 0.154296 0.966996 -0.202758 0.202211 0.965234 -0.165631 0.850924 0.521255 -0.0649744 0.850924 0.521255 -0.0649744 0.573243 0.813093 -0.101352 0.573242 0.813093 -0.101352 0.202048 0.971855 -0.121142 0.202048 0.971855 -0.121141 0.850924 0.52484 -0.0217075 0.850924 0.524841 -0.0217075 0.573242 0.818686 -0.033861 0.573243 0.818685 -0.0338611 0.202048 0.978539 -0.0404727 0.202048 0.978539 -0.0404727 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.995185 0.0980172 0 0.995185 0.0980172 0 0.95694 0.290284 0 0.95694 0.290284 0 0.881921 0.471397 0 0.881921 0.471397 0 0.773011 0.634393 0 0.773011 0.634393 0 0.634393 0.773011 0 0.634393 0.773011 0 0.471397 0.881921 0 0.471397 0.881921 0 0.290285 0.95694 0 0.290285 0.95694 0 0.0980172 0.995185 0 0.0980172 0.995185 0 -0.0980172 0.995185 0 -0.0980172 0.995185 0 -0.290285 0.95694 0 -0.290285 0.95694 0 -0.471397 0.881921 0 -0.471397 0.881921 0 -0.634393 0.773011 0 -0.634393 0.773011 0 -0.77301 0.634393 0 -0.77301 0.634393 0 -0.881921 0.471397 0 -0.881921 0.471397 0 -0.95694 0.290285 0 -0.95694 0.290285 0 -0.995185 0.0980172 0 -0.995185 0.0980172 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.995185 0.0980168 0 -0.995185 0.0980168 0 -0.95694 0.290285 0 -0.95694 0.290285 0 -0.881921 0.471397 0 -0.881921 0.471397 0 -0.77301 0.634393 0 -0.77301 0.634393 0 -0.634393 0.77301 0 -0.634393 0.77301 0 -0.471397 0.881921 0 -0.471397 0.881921 0 -0.290285 0.95694 0 -0.290285 0.95694 0 -0.0980172 0.995185 0 -0.0980172 0.995185 0 0.0980172 0.995185 0 0.0980172 0.995185 0 0.290285 0.95694 0 0.290285 0.95694 0 0.471397 0.881921 0 0.471397 0.881921 0 0.634393 0.77301 0 0.634393 0.77301 0 0.77301 0.634393 0 0.77301 0.634393 0 0.881921 0.471397 0 0.881921 0.471397 0 0.95694 0.290285 0 0.95694 0.290285 0 0.995185 0.0980172 0 0.995185 0.0980172 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.995734 0.0922682 0 -0.995734 0.0922682 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.895164 0.445738 0 -0.895164 0.445738 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.18375 0.982973 0 -0.18375 0.982973 0 0 1 0 0 1 0 0.18375 0.982973 0 0.18375 0.982973 0 0.361242 0.932472 0 0.361242 0.932472 0 0.526432 0.850217 0 0.526432 0.850217 0 0.673696 0.739009 0 0.673696 0.739009 0 0.798017 0.602635 0 0.798017 0.602635 0 0.895163 0.445738 0 0.895163 0.445738 0 0.961826 0.273663 0 0.961826 0.273663 0 0.995734 0.0922684 0 0.995734 0.0922684 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.996195 0.0871555 0 0.996195 0.0871555 0 0.965926 0.25882 0 0.965926 0.25882 0 0.906308 0.422618 0 0.906308 0.422618 0 0.819152 0.573576 0 0.819152 0.573576 0 0.707107 0.707107 0 0.707107 0.707107 0 0.573576 0.819152 0 0.573576 0.819152 0 0.422618 0.906308 0 0.422618 0.906308 0 0.258819 0.965926 0 0.258819 0.965926 0 0.0871559 0.996195 0 0.0871559 0.996195 0 -0.0871559 0.996195 0 -0.0871559 0.996195 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.422618 0.906308 0 -0.422618 0.906308 0 -0.573576 0.819152 0 -0.573576 0.819152 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.819152 0.573576 0 -0.819152 0.573576 0 -0.906308 0.422618 0 -0.906308 0.422618 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.996195 0.0871558 0 -0.996195 0.0871558 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.985593 0.169136 0.0112218 -0.996132 0.0871508 0.100449 -0.987302 0.123067 0 -0.999146 0.0413248 0 -0.928214 0.372047 0 -0.942792 0.333382 0.0211949 -0.965709 0.258761 0.0844647 -0.955003 0.284314 0 -0.977764 0.209709 0.069658 -0.896208 0.438131 0.0299157 -0.905902 0.422429 0 -0.872832 0.488021 0 -0.751083 0.660208 0 -0.777722 0.628608 0.0373887 -0.818579 0.573175 0.0560285 -0.812571 0.580164 0 -0.85192 0.523673 0.0436114 -0.706434 0.706434 0.0436109 -0.706434 0.706434 0 -0.660209 0.751082 0 -0.523673 0.851919 0.0485866 -0.572899 0.818184 0.032414 -0.580772 0.813421 0 -0.628606 0.777724 0 -0.333373 0.942795 0 -0.37205 0.928213 0.0523165 -0.422039 0.905067 0.022449 -0.439086 0.898165 0 -0.488019 0.872833 0.0137225 -0.285309 0.958337 0.0548019 -0.25843 0.964474 0 -0.209708 0.977764 0 -0.0413255 0.999146 0.056044 -0.087019 0.994629 0.00623867 -0.12369 0.992301 0 -0.169124 0.985595 0 0.169123 0.985595 0.01122 0.0871505 0.996132 0.100448 0.123067 0.987302 0 0.0413255 0.999146 0 0.37205 0.928213 0 0.333373 0.942795 0.0211923 0.258761 0.965709 0.0844681 0.284316 0.955002 0 0.209709 0.977764 0.0696542 0.43813 0.896209 0.0299151 0.422429 0.905902 0 0.48802 0.872833 0 0.660209 0.751082 0 0.628606 0.777724 0.0373873 0.573175 0.818579 0.0560285 0.580164 0.81257 0 0.523673 0.851919 0.0436105 0.706434 0.706434 0.0436113 0.706434 0.706434 0 0.751083 0.660208 0 0.872832 0.48802 0 0.851919 0.523673 0.0485866 0.818185 0.572899 0.0324146 0.813421 0.580772 0 0.777724 0.628606 0.0224496 0.898165 0.439086 0.0523167 0.905067 0.42204 0 0.928213 0.37205 0 0.977764 0.209708 0.0548021 0.964474 0.25843 0.013723 0.958337 0.285309 0 0.942794 0.333375 0 0.999146 0.041325 0.0560444 0.994629 0.0870188 0.00623875 0.992301 0.12369 0 0.985595 0.169124 0 0.995185 0.0980173 0 0.995185 0.0980173 0 0.95694 0.290284 0 0.95694 0.290284 0 0.881921 0.471397 0 0.881921 0.471397 0 0.773011 0.634393 0 0.773011 0.634393 0 0.634393 0.77301 0 0.634393 0.77301 0 0.471397 0.881921 0 0.471397 0.881921 0 0.290285 0.95694 0 0.290285 0.95694 0 0.0980169 0.995185 0 0.0980169 0.995185 0 -0.0980169 0.995185 0 -0.0980169 0.995185 0 -0.290285 0.95694 0 -0.290285 0.95694 0 -0.471397 0.881921 0 -0.471397 0.881921 0 -0.634393 0.77301 0 -0.634393 0.77301 0 -0.77301 0.634393 0 -0.77301 0.634393 0 -0.881921 0.471397 0 -0.881921 0.471397 0 -0.95694 0.290285 0 -0.95694 0.290285 0 -0.995185 0.0980171 0 -0.995185 0.0980171 0 0.995734 0.0922682 0 0.995734 0.0922682 0 0.961825 0.273664 0 0.961825 0.273664 0 0.895163 0.445738 0 0.895163 0.445738 0 0.798017 0.602635 0 0.798017 0.602635 0 0.673696 0.739009 0 0.673696 0.739009 0 0.526432 0.850217 0 0.526432 0.850217 0 0.361242 0.932472 0 0.361242 0.932472 0 0.18375 0.982973 0 0.18375 0.982973 0 0 1 0 0 1 0 -0.18375 0.982973 0 -0.18375 0.982973 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.995734 0.0922685 0 -0.995734 0.0922685 0 0.995734 0.0922682 0 0.995734 0.0922682 0 0.961825 0.273664 0 0.961825 0.273664 0 0.895163 0.445738 0 0.895163 0.445738 0 0.798017 0.602634 0 0.798017 0.602634 0 0.673696 0.739009 0 0.673696 0.739009 0 0.526432 0.850217 0 0.526432 0.850217 0 0.361242 0.932472 0 0.361242 0.932472 0 0.18375 0.982973 0 0.18375 0.982973 0 0 1 0 0 1 0 -0.18375 0.982973 0 -0.18375 0.982973 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.995734 0.0922685 0 -0.995734 0.0922685 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.705874 0.688142 -0.167938 -0.705874 0.688141 -0.167938 -0.705874 0.650812 -0.279616 -0.705875 0.650812 -0.279616 -0.705875 0.595497 -0.383566 -0.705874 0.595499 -0.383567 -0.705874 0.523728 -0.476918 -0.705874 0.523728 -0.476918 -0.705873 0.437485 -0.557091 -0.705873 0.437485 -0.557091 -0.705873 0.339152 -0.621868 -0.705874 0.339151 -0.621867 -0.705874 0.231446 -0.669459 -0.705874 0.231446 -0.669459 -0.705873 0.117345 -0.698551 -0.705875 0.117344 -0.69855 -0.705874 0 -0.708337 -0.705874 0 -0.708337 -0.705875 -0.117344 -0.698549 -0.705873 -0.117345 -0.698551 -0.705874 -0.231446 -0.669459 -0.705874 -0.231446 -0.669459 -0.705874 -0.339151 -0.621867 -0.705871 -0.339152 -0.62187 -0.70587 -0.437487 -0.557093 -0.705875 -0.437484 -0.557089 -0.705875 -0.523727 -0.476918 -0.705877 -0.523726 -0.476916 -0.705877 -0.595496 -0.383565 -0.705874 -0.595498 -0.383567 -0.705874 -0.650813 -0.279616 -0.705871 -0.650815 -0.279617 -0.70587 -0.688145 -0.167939 -0.705879 -0.688136 -0.167936 -0.705879 -0.688136 0.167937 -0.70587 -0.688145 0.167938 -0.705871 -0.650815 0.279617 -0.705872 -0.650814 0.279617 -0.705872 -0.5955 0.383568 -0.705878 -0.595495 0.383565 -0.705877 -0.523726 0.476916 -0.705875 -0.523727 0.476917 -0.705875 -0.437484 0.55709 -0.70587 -0.437487 0.557093 -0.705871 -0.339153 0.62187 -0.705874 -0.339151 0.621867 -0.705874 -0.231446 0.669459 -0.705874 -0.231446 0.669459 -0.705873 -0.117345 0.698551 -0.705875 -0.117344 0.69855 -0.705874 0 0.708337 -0.705874 0 0.708337 -0.705875 0.117344 0.698549 -0.705873 0.117345 0.698551 -0.705874 0.231446 0.669459 -0.705874 0.231446 0.669459 -0.705874 0.339151 0.621867 -0.705873 0.339152 0.621868 -0.705873 0.437485 0.557091 -0.705874 0.437485 0.55709 -0.705873 0.523729 0.476919 -0.705875 0.523728 0.476918 -0.705874 0.595499 0.383567 -0.705873 0.595499 0.383568 -0.705873 0.650813 0.279616 -0.705874 0.650812 0.279616 -0.705874 0.688141 0.167938 -0.705874 0.688142 0.167938 0.42256 0.891066 -0.165662 0.413966 0.895712 -0.162269 0.422615 0.894625 -0.145062 0.422527 0.891834 0.161567 0.411777 0.895932 0.166567 0.422615 0.894625 0.145062 0.422527 -0.891834 -0.161566 0.411787 -0.895929 -0.166562 0.422613 -0.894623 -0.145081 0.42256 -0.891067 0.165658 0.413974 -0.895709 0.162268 0.422613 -0.894623 0.145081 0.939848 -0.337905 0.0500624 0.939691 -0.337908 0.0529149 0.939735 -0.337814 0.0527184 0.939838 -0.337525 0.0527388 0.939761 -0.337887 0.0517758 0.939691 -0.337679 0.0543546 0.940782 -0.33463 0.0543291 0.940522 -0.335352 0.054384 0.939716 -0.337819 0.0530328 0.940046 -0.337704 0.0476417 0.940591 -0.336735 0.043568 0.940961 -0.335914 0.0418712 0.939576 -0.341979 0.0157347 0.938802 -0.344163 0.0142348 0.939809 -0.340173 0.0322781 0.94012 -0.338885 0.0364789 0.940394 -0.322158 0.108967 0.94025 -0.322553 0.109043 0.939705 -0.324547 0.107816 0.939689 -0.32466 0.107611 0.939732 -0.324584 0.107468 0.939663 -0.32495 0.106962 0.939728 -0.324322 0.108286 0.939825 -0.324688 0.106334 0.93997 -0.324734 0.1049 0.940231 -0.324734 0.102533 0.940762 -0.323985 0.100005 0.941077 -0.323501 0.0986009 0.942099 -0.321687 0.0946968 0.941615 -0.322693 0.0960709 0.940183 -0.328564 0.0900088 0.939768 -0.330591 0.0868617 0.93909 -0.336356 0.0705263 0.944607 -0.319546 0.074889 0.942944 -0.324918 0.0727028 0.941633 -0.329124 0.0707419 0.940548 -0.332847 0.0676941 0.939668 -0.336155 0.0634354 0.940357 -0.334818 0.0602166 0.939671 -0.336291 0.0626624 0.939708 -0.334884 0.0692998 0.939638 -0.335058 0.069405 0.939552 -0.336556 0.0630175 0.941749 -0.330654 0.0614582 0.941624 -0.330996 0.0615354 0.939592 -0.335207 0.0693114 0.939991 -0.334242 0.0685568 0.939889 -0.234544 0.24819 0.939793 -0.233811 0.249243 0.941383 -0.239991 0.237071 0.94208 -0.237156 0.237156 0.941339 -0.237056 0.240179 0.94027 -0.236072 0.245279 0.943023 -0.249137 0.22054 0.937986 -0.26454 0.224054 0.939926 -0.247903 0.234697 0.94029 -0.245147 0.236129 0.940636 -0.26205 0.215715 0.939629 -0.263032 0.218889 0.939733 -0.25537 0.227349 0.939646 -0.255493 0.227572 0.939425 -0.263271 0.219475 0.943053 -0.255783 0.212665 0.942937 -0.256031 0.212881 0.939607 -0.255642 0.227566 0.940004 -0.255185 0.226434 0.939702 -0.227177 0.255639 0.946022 -0.198316 0.256345 0.939653 -0.227972 0.255109 0.940313 -0.20821 0.269184 0.942724 -0.207284 0.26135 0.92698 -0.217968 0.305284 0.941563 -0.220662 0.254494 0.939972 -0.220551 0.260403 0.939695 -0.230924 0.252287 0.939686 -0.23271 0.250671 0.940165 -0.0898903 0.328649 0.941592 -0.0960887 0.322756 0.944467 -0.107805 0.310419 0.932765 -0.131039 0.335825 0.941174 -0.0982285 0.323331 0.942147 -0.0945267 0.321597 0.940908 -0.123075 0.315508 0.939568 -0.122823 0.319573 0.939734 -0.107477 0.324576 0.939646 -0.107472 0.32483 0.939276 -0.12283 0.320428 0.944297 -0.118194 0.307136 0.944185 -0.118305 0.30744 0.939604 -0.107616 0.324906 0.940038 -0.107802 0.323584 0.939693 -0.068933 0.335 0.945381 -0.0462866 0.322665 0.939662 -0.0697758 0.334913 0.940233 -0.0503713 0.336787 0.939493 -0.0487772 0.339078 0.939105 -0.0492324 0.340086 0.94548 -0.0462421 0.322379 0.93972 -0.0692478 0.334859 0.939678 -0.0691629 0.334995 0.942139 -0.0534589 0.330934 0.943365 -0.0547909 0.327202 0.932838 -0.0445662 0.35753 0.940851 -0.0685342 0.331816 0.941418 -0.0701701 0.32986 0.942236 -0.0716056 0.327207 0.942779 -0.0724836 0.325445 0.940603 -0.0696724 0.332283 0.93964 -0.082821 0.331989 0.939757 -0.086744 0.330654 0.941633 0.0707404 0.329126 0.931736 0.0449173 0.360347 0.941161 0.0465106 0.334744 0.939487 0.0487841 0.339093 0.939723 0.0692431 0.334852 0.939645 0.0693606 0.335047 0.939105 0.0492324 0.340086 0.945482 0.0462415 0.322376 0.94538 0.0462871 0.322668 0.939601 0.0692722 0.335187 0.940017 0.0684854 0.334181 0.944298 0.118194 0.307136 0.944185 0.118305 0.30744 0.939696 0.107821 0.324572 0.939678 0.107594 0.324697 0.939721 0.107449 0.324621 0.939668 0.107055 0.324906 0.940132 0.120529 0.318786 0.941535 0.115672 0.316435 0.942464 0.113072 0.314604 0.942808 0.112134 0.31391 0.936862 0.127119 0.325777 0.940306 0.102178 0.324629 0.940766 0.0999847 0.323979 0.941076 0.0986011 0.323502 0.942097 0.0947014 0.32169 0.941616 0.0960698 0.322692 0.940184 0.0900087 0.328562 0.939768 0.0868541 0.330594 0.939692 0.0846086 0.331393 0.939622 0.0702272 0.334929 0.944196 0.0743435 0.320886 0.942944 0.0727025 0.324917 0.94602 0.198321 0.25635 0.939615 0.227541 0.255636 0.94 0.226445 0.255193 0.941393 0.203593 0.268939 0.939384 0.208237 0.272389 0.964079 0.146644 0.221466 0.939001 0.21079 0.271744 0.946111 0.198156 0.256142 0.939728 0.227362 0.255377 0.939656 0.227547 0.255479 0.943051 0.255787 0.212669 0.942939 0.256027 0.212878 0.9397 0.25565 0.227171 0.939686 0.255539 0.227355 0.93973 0.255373 0.227361 0.939662 0.255121 0.227922 0.940012 0.261073 0.219587 0.940925 0.256942 0.220547 0.941563 0.254496 0.220662 0.942491 0.25098 0.220724 0.938613 0.263243 0.222956 0.939793 0.249241 0.233813 0.939889 0.248192 0.234543 0.941383 0.23707 0.239992 0.94208 0.237156 0.237156 0.941338 0.240183 0.237056 0.94027 0.245278 0.236073 0.939698 0.334989 0.0689185 0.941626 0.33099 0.0615359 0.939663 0.334905 0.0698037 0.941282 0.3303 0.0699323 0.940699 0.33235 0.0680414 0.939684 0.334985 0.0691266 0.939728 0.334845 0.0692143 0.941745 0.330663 0.061462 0.939553 0.336555 0.0630187 0.939673 0.336286 0.0626585 0.939874 0.335438 0.0641829 0.94033 0.333649 0.0667608 0.942235 0.327209 0.0716048 0.942779 0.325445 0.0724841 0.940603 0.332283 0.0696725 0.944499 0.316571 0.0877699 0.940986 0.324375 0.0965706 0.939757 0.330654 0.0867441 0.93964 0.331989 0.0828206 0.941846 0.322227 0.0953751 0.940413 0.32456 0.101414 0.9399 0.324799 0.105329 0.939688 0.324075 0.109374 0.939727 0.324594 0.107479 0.939651 0.324817 0.107475 0.939659 0.324234 0.109147 0.940387 0.322176 0.108973 0.940247 0.32256 0.109046 0.93961 0.32489 0.107612 0.940018 0.323647 0.107787 0.939598 0.341987 0.0141447 0.938904 0.343817 0.015819 0.940223 0.337944 0.0421247 0.942584 0.33213 0.035012 0.940989 0.335884 0.041494 0.940252 0.337371 0.0458933 0.940495 0.335426 0.054389 0.939648 0.338018 0.05297 0.939941 0.337177 0.0531276 0.939974 0.337778 0.0485303 0.939848 0.337905 0.0500605 0.939688 0.337871 0.0531942 0.940103 0.336532 0.0543429 0.94079 0.334607 0.0543268 0.939823 0.337573 0.0526978 0.939715 0.337878 0.0526762 0.939752 0.324452 0.10769 0.939691 0.324052 0.109411 0.939599 0.318863 0.124421 0.938046 0.320037 0.132839 0.940362 0.305611 0.149404 0.939671 0.304036 0.156783 0.939599 0.294035 0.175207 0.939163 0.293973 0.177631 0.939988 0.277692 0.198268 0.939625 0.277275 0.200559 0.939634 0.263026 0.218873 0.939425 0.263271 0.219475 0.94014 0.236001 0.245848 0.939662 0.233125 0.250375 0.939771 0.220908 0.260825 0.941312 0.220739 0.255354 0.93036 0.213051 0.298396 0.939372 0.20888 0.271937 0.939599 0.175207 0.294036 0.938156 0.171258 0.30089 0.940362 0.149404 0.305611 0.939668 0.144088 0.310264 0.939574 0.122822 0.319555 0.939276 0.12283 0.320428 0.942895 0.0544279 0.328615 0.939478 0.0495644 0.339007 0.939599 0.0141448 0.341986 0.941836 0.025199 0.335128 0.934773 -0.0146807 0.354943 0.940342 0 0.340232 0.93969 -0.0256455 0.341066 0.942105 -0.113935 0.315368 0.939562 -0.122098 0.319868 0.939599 -0.150327 0.3075 0.940951 -0.142595 0.307048 0.937335 -0.178356 0.29932 0.939486 -0.169464 0.297739 0.939391 -0.208221 0.272376 0.964078 -0.146646 0.221467 0.939001 -0.21079 0.271744 0.946108 -0.19816 0.256147 0.939727 -0.22736 0.255384 0.939688 -0.227355 0.255532 0.941312 -0.255353 0.22074 0.939625 -0.262539 0.219494 0.939599 -0.278563 0.19889 0.940026 -0.276381 0.199913 0.939068 -0.295284 0.175952 0.939569 -0.293022 0.177057 0.939599 -0.307499 0.150328 0.941047 -0.300655 0.155039 0.937104 -0.325173 0.126882 0.939476 -0.316439 0.131345 0.939691 -0.324055 0.109401 0.939659 -0.324235 0.109143 0 0.948621 -0.316414 0 -0.770825 -0.637047 0 -0.983983 -0.17826 0 -0.983983 -0.17826 -0.211517 -0.944071 -0.252964 -0.00594197 -0.971471 -0.237083 -0.188715 -0.726091 -0.661195 0 -0.611896 -0.790938 0 -0.553669 -0.832737 -0.0109146 -0.609544 -0.792677 -0.0934737 -0.614917 -0.783032 0 -0.672369 -0.740216 0 -0.715208 -0.698912 -0.189525 -0.320823 -0.927983 0 -0.281615 -0.959527 0 -0.224047 -0.974578 -0.158233 -0.163575 -0.973758 0 -0.142265 -0.989829 0 0.142265 -0.989829 0 0.142265 -0.989829 -0.158234 0.163575 -0.973758 0 0.360397 -0.932799 0 0.360397 -0.932799 -0.189524 0.320823 -0.927984 0 0.281616 -0.959527 0 0.224047 -0.974578 -0.0934733 0.614917 -0.783032 0 0.611896 -0.790938 0 0.770825 -0.637047 0 0.770825 -0.637047 -0.188716 0.726091 -0.661194 0 0.715208 -0.698912 0 0.672369 -0.740216 0 0.983983 -0.178261 0 0.983983 -0.178261 -0.155782 0.959628 -0.234193 -0.00433166 0.965917 -0.258817 0 0.948621 -0.316414 0 0.918789 -0.39475 -0.0507838 0.923953 -0.379121 0 0.890392 -0.455194 0 0.840699 -0.541503 -0.0992323 0.853466 -0.511614 0 0.811996 -0.583663 -0.0109146 0.609545 -0.792677 0 0.553669 -0.832737 0 0.478799 -0.877925 -0.0619702 0.495349 -0.866481 0 0.422426 -0.906397 0 0.0752464 -0.997165 -0.0221241 0 -0.999755 -0.0221241 0 -0.999755 0 -0.0752464 -0.997165 0 -0.142265 -0.989829 0 -0.496303 -0.868149 -0.0471006 -0.478267 -0.87695 0 -0.422426 -0.906397 0 -0.360397 -0.932799 0 -0.360397 -0.932799 0 -0.770825 -0.637047 0 -0.811996 -0.583663 -0.0610585 -0.83913 -0.540493 0 -0.948629 -0.316389 0 -0.948629 -0.316389 0 -0.925146 -0.379612 -0.0407971 -0.918024 -0.394421 0 -0.890394 -0.455192 0 -0.857699 -0.514152 0 0.0752464 0.997165 0 -0.948627 0.316396 0 0.770825 0.637047 0 0.983983 0.178261 0 0.983983 0.178261 -0.211514 0.944072 0.252963 -0.00594423 0.971471 0.237083 -0.188717 0.726091 0.661194 0 0.611896 0.790938 0 0.553669 0.832737 -0.0109147 0.609545 0.792677 -0.0934732 0.614917 0.783032 0 0.672369 0.740216 0 0.715208 0.698912 -0.189524 0.320823 0.927984 0 0.142265 0.989829 0 0.142265 0.989829 -0.158234 0.163575 0.973758 0 0.224047 0.974578 0 0.281616 0.959527 -0.158233 -0.163575 0.973758 0 -0.360397 0.932799 0 -0.360397 0.932799 -0.189525 -0.320823 0.927983 0 -0.281615 0.959527 0 -0.224047 0.974578 -0.0934736 -0.614917 0.783032 0 -0.611896 0.790938 0 -0.770825 0.637047 0 -0.770825 0.637047 -0.188715 -0.726091 0.661195 0 -0.715208 0.698912 0 -0.672369 0.740216 0 -0.983983 0.17826 0 -0.983983 0.17826 -0.155784 -0.959628 0.234193 -0.00433017 -0.965917 0.258817 0 -0.948627 0.316396 0 -0.918789 0.39475 -0.050782 -0.923952 0.379122 0 -0.890393 0.455192 0 -0.840699 0.541503 -0.0992319 -0.853466 0.511614 0 -0.811996 0.583663 -0.0109146 -0.609544 0.792677 0 -0.553669 0.832737 0 -0.478799 0.877925 -0.0619702 -0.495349 0.866481 0 -0.422426 0.906397 -0.0221241 0 0.999755 -0.0221241 0 0.999755 0 -0.0752464 0.997165 0 -0.142265 0.989829 0 -0.142265 0.989829 0 0.496303 0.868149 -0.0471006 0.478267 0.87695 0 0.422426 0.906397 0 0.360397 0.932799 0 0.360397 0.932799 0 0.770825 0.637047 0 0.811996 0.583663 -0.0610592 0.83913 0.540493 0 0.948619 0.31642 0 0.948619 0.31642 0 0.925146 0.379611 -0.0407988 0.918024 0.394421 0 0.890392 0.455194 0 0.857699 0.514152 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 -0.136709 0.510204 -0.849119 -0.373495 0.373496 -0.84912 -0.510202 0.136713 -0.849119 0.510204 0.136708 -0.849119 0.373495 0.373496 -0.849119 0.136709 0.510204 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.258817 0 0.965926 0.258817 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 -0.136709 0.510204 -0.849119 -0.373495 0.373496 -0.84912 -0.510202 0.136713 -0.849119 0.510204 0.136708 -0.849119 0.373495 0.373496 -0.849119 0.136709 0.510204 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.258817 0 0.965926 0.258817 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849118 -0.136711 0.510204 -0.849119 -0.373494 0.373497 -0.84912 -0.510202 0.136713 -0.849119 0.510204 0.136708 -0.849119 0.373494 0.373497 -0.849118 0.136711 0.510204 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.707104 0.70711 0 -0.707104 0.70711 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707104 0.70711 0 0.707104 0.70711 0 0.965926 0.258817 0 0.965926 0.258817 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 -0.136708 0.510204 -0.849119 -0.373495 0.373495 -0.849119 -0.510204 0.136708 -0.849119 0.510204 0.136708 -0.849119 0.373495 0.373495 -0.849119 0.136708 0.510204 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.258817 0.965926 0 -0.258817 0.965926 0 0.258817 0.965926 0 0.258817 0.965926 0 0.707107 0.707107 0 0.707107 0.707107 0 0.965926 0.258817 0 0.965926 0.258817 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849118 -0.136711 0.510204 -0.849119 -0.373494 0.373497 -0.849119 -0.510204 0.136708 -0.849119 0.510204 0.136708 -0.849119 0.373494 0.373497 -0.849118 0.136711 0.510204 0 -0.965926 0.258817 0 -0.965926 0.258817 0 -0.707104 0.70711 0 -0.707104 0.70711 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707104 0.70711 0 0.707104 0.70711 0 0.965926 0.258817 0 0.965926 0.258817 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 -0.136709 0.510204 -0.849119 -0.373495 0.373496 -0.849119 -0.510203 0.136709 -0.849119 0.510203 0.136709 -0.849119 0.373495 0.373496 -0.849119 0.136709 0.510204 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 -0.136709 0.510204 -0.849119 -0.373495 0.373496 -0.849119 -0.510203 0.136709 -0.849119 0.510203 0.136709 -0.849119 0.373495 0.373496 -0.849119 0.136709 0.510204 0 -0.965926 0.25882 0 -0.965926 0.25882 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707106 0.707108 0 0.707106 0.707108 0 0.965926 0.25882 0 0.965926 0.25882 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.851305 -0.511517 0.11675 -0.851304 0 0.524672 -0.851304 -0.227647 0.472713 -0.851305 -0.410204 0.327128 -0.851305 0.511517 0.11675 -0.851305 0.410204 0.327128 -0.851304 0.227647 0.472713 0 -0.974928 0.222519 0 -0.974928 0.222519 0 -0.78183 0.623491 0 -0.78183 0.623491 0 -0.433884 0.900969 0 -0.433884 0.900969 0 0 1 0 0 1 0 0.433884 0.900969 0 0.433884 0.900969 0 0.78183 0.623491 0 0.78183 0.623491 0 0.974928 0.222519 0 0.974928 0.222519 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.849119 -0.13671 0.510203 -0.849119 -0.373493 0.373496 -0.849119 -0.510204 0.136707 -0.849119 0.510204 0.136707 -0.849119 0.373493 0.373496 -0.849119 0.13671 0.510203 0 -0.965927 0.258816 0 -0.965927 0.258816 0 -0.707104 0.70711 0 -0.707104 0.70711 0 -0.258822 0.965925 0 -0.258822 0.965925 0 0.258822 0.965925 0 0.258822 0.965925 0 0.707104 0.70711 0 0.707104 0.70711 0 0.965927 0.258816 0 0.965927 0.258816 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.974927 0.222526 0 -0.974927 0.222526 0 -0.781834 0.623487 0 -0.781834 0.623487 0 -0.433878 0.900971 0 -0.433878 0.900971 0 0 1 0 0 1 0 0.433878 0.900971 0 0.433878 0.900971 0 0.781834 0.623487 0 0.781834 0.623487 0 0.974927 0.222526 0 0.974927 0.222526 -0.851306 -0.511515 0.116752 -0.851304 0 0.524672 -0.851305 -0.227644 0.472714 -0.851305 -0.410205 0.327125 -0.851304 0.511517 0.116753 -0.851304 0.410206 0.327127 -0.851304 0.227644 0.472715 -0.705587 -0.7056 0.0653835 -0.705588 -0.705599 0.0653834 -0.705588 -0.681571 0.193924 -0.70559 -0.68157 0.193923 -0.705589 -0.634331 0.31586 -0.705589 -0.634332 0.31586 -0.705589 -0.565492 0.42704 -0.70559 -0.565491 0.427039 -0.70559 -0.477394 0.523677 -0.705588 -0.477396 0.523678 -0.705588 -0.373042 0.602483 -0.705582 -0.373045 0.602488 -0.705582 -0.255986 0.660776 -0.705584 -0.255986 0.660775 -0.705584 -0.13021 0.696561 -0.705588 -0.130209 0.696557 -0.705587 0 0.708623 -0.705587 0 0.708623 -0.705588 0.130209 0.696557 -0.705586 0.130209 0.696559 -0.705588 0.255984 0.66077 -0.705582 0.255986 0.660776 -0.705582 0.373045 0.602488 -0.705588 0.373042 0.602483 -0.705588 0.477396 0.523678 -0.705592 0.477393 0.523675 -0.705593 0.565489 0.427038 -0.705589 0.565492 0.42704 -0.705589 0.634332 0.31586 -0.705589 0.634331 0.31586 -0.70559 0.68157 0.193923 -0.705582 0.681577 0.193925 -0.705581 0.705606 0.0653837 -0.705594 0.705594 0.065383 -0.705614 -0.705574 0.0653812 -0.705614 -0.705573 0.0653811 -0.705614 -0.681546 0.193916 -0.705613 -0.681548 0.193917 -0.705613 -0.634311 0.315849 -0.705616 -0.634308 0.315848 -0.705615 -0.565471 0.427024 -0.705616 -0.56547 0.427023 -0.705616 -0.477377 0.523657 -0.705619 -0.477375 0.523655 -0.70562 -0.373025 0.602456 -0.705614 -0.373028 0.602461 -0.705615 -0.255974 0.660746 -0.70561 -0.255976 0.66075 -0.70561 -0.130205 0.696535 -0.705614 -0.130204 0.696531 -0.705614 0 0.708597 -0.705614 0 0.708597 -0.705614 0.130204 0.696531 -0.705612 0.130205 0.696533 -0.705615 0.255974 0.660746 -0.705615 0.255974 0.660746 -0.705614 0.373028 0.602461 -0.705613 0.373029 0.602462 -0.70561 0.477381 0.523662 -0.705619 0.477375 0.523656 -0.705619 0.565468 0.427022 -0.705615 0.565471 0.427024 -0.705616 0.634308 0.315848 -0.705616 0.634308 0.315848 -0.705616 0.681544 0.193916 -0.705608 0.681552 0.193918 -0.705608 0.70558 0.0653819 -0.705594 0.705594 0.0653827 -0.705784 -0.705731 0.0617432 -0.705782 -0.705734 0.0617433 -0.705782 -0.68429 0.183355 -0.705769 -0.684302 0.183358 -0.70577 -0.642066 0.2994 -0.705775 -0.642061 0.299398 -0.705776 -0.580316 0.406342 -0.705773 -0.580319 0.406343 -0.705773 -0.500941 0.500941 -0.705773 -0.500941 0.500941 -0.705774 -0.406343 0.580317 -0.70577 -0.406345 0.580321 -0.705771 -0.2994 0.642064 -0.705782 -0.299395 0.642055 -0.705782 -0.183355 0.68429 -0.70578 -0.183355 0.684292 -0.705781 -0.0617437 0.705734 -0.705777 -0.0617442 0.705738 -0.705777 0.0617441 0.705738 -0.705782 0.0617438 0.705734 -0.705782 0.183355 0.68429 -0.705784 0.183355 0.684288 -0.705784 0.299394 0.642053 -0.705774 0.299398 0.642062 -0.705774 0.406343 0.580318 -0.705778 0.406341 0.580314 -0.705778 0.500938 0.500938 -0.705777 0.500938 0.500938 -0.705778 0.580314 0.406341 -0.705778 0.580314 0.406341 -0.705779 0.642058 0.299397 -0.705779 0.642058 0.299396 -0.705779 0.684293 0.183356 -0.705778 0.684294 0.183356 -0.705778 0.705737 0.061744 -0.705777 0.705738 0.0617441 -0.705594 -0.705594 0.0653829 -0.705595 -0.705593 0.0653828 -0.705594 -0.681565 0.193922 -0.705589 -0.68157 0.193923 -0.705589 -0.634331 0.31586 -0.705589 -0.634331 0.31586 -0.705589 -0.565492 0.42704 -0.705582 -0.565498 0.427044 -0.705583 -0.477399 0.523681 -0.705593 -0.477392 0.523675 -0.705593 -0.373039 0.602479 -0.705588 -0.373042 0.602483 -0.705589 -0.255984 0.66077 -0.705595 -0.255981 0.660765 -0.705593 -0.130208 0.696552 -0.705588 -0.130209 0.696557 -0.705587 0 0.708623 -0.705587 0 0.708623 -0.705588 0.130209 0.696557 -0.70559 0.130209 0.696555 -0.70559 0.255983 0.660769 -0.705591 0.255983 0.660768 -0.705591 0.37304 0.60248 -0.705593 0.373039 0.602478 -0.705593 0.477393 0.523675 -0.705593 0.477393 0.523675 -0.705593 0.565489 0.427037 -0.705586 0.565494 0.427042 -0.705586 0.634334 0.315861 -0.705589 0.634332 0.315859 -0.70559 0.68157 0.193923 -0.705588 0.681571 0.193924 -0.705588 0.7056 0.0653834 -0.705587 0.7056 0.0653835 -0.705587 -0.7056 0.0653835 -0.705588 -0.705599 0.0653834 -0.705588 -0.681571 0.193924 -0.705587 -0.681572 0.193924 -0.705588 -0.634333 0.31586 -0.705586 -0.634334 0.315861 -0.705586 -0.565494 0.427041 -0.705587 -0.565493 0.427041 -0.705588 -0.477396 0.523678 -0.705588 -0.477396 0.523678 -0.705588 -0.373042 0.602483 -0.705588 -0.373042 0.602483 -0.705589 -0.255984 0.66077 -0.70559 -0.255983 0.660769 -0.70559 -0.130209 0.696555 -0.705585 -0.13021 0.696559 -0.705587 0 0.708623 -0.705587 0 0.708623 -0.705585 0.13021 0.696559 -0.70559 0.130209 0.696555 -0.70559 0.255983 0.660769 -0.705589 0.255984 0.66077 -0.705588 0.373042 0.602483 -0.705588 0.373042 0.602483 -0.705588 0.477396 0.523678 -0.705592 0.477393 0.523675 -0.705593 0.565489 0.427038 -0.705589 0.565492 0.42704 -0.705589 0.634331 0.31586 -0.705591 0.63433 0.315859 -0.70559 0.681569 0.193923 -0.705582 0.681577 0.193925 -0.705581 0.705606 0.0653839 -0.705581 0.705607 0.0653839 -0.705784 -0.705731 0.0617439 -0.705781 -0.705734 0.061744 -0.705781 -0.684291 0.183355 -0.705769 -0.684302 0.183358 -0.70577 -0.642066 0.2994 -0.705777 -0.64206 0.299397 -0.705778 -0.580315 0.406341 -0.705773 -0.580319 0.406343 -0.705773 -0.500942 0.500941 -0.705782 -0.500935 0.500935 -0.705782 -0.406338 0.580311 -0.705783 -0.406338 0.58031 -0.705783 -0.299395 0.642054 -0.705775 -0.299398 0.642061 -0.705775 -0.183357 0.684296 -0.705774 -0.183357 0.684298 -0.705774 -0.0617445 0.705741 -0.705784 -0.0617433 0.705731 -0.705784 0.0617437 0.705731 -0.705775 0.0617441 0.705741 -0.705774 0.183357 0.684298 -0.705776 0.183357 0.684296 -0.705776 0.299398 0.642061 -0.70578 0.299396 0.642057 -0.705779 0.40634 0.580313 -0.705778 0.40634 0.580314 -0.705778 0.500938 0.500938 -0.705776 0.50094 0.50094 -0.705775 0.580317 0.406342 -0.705781 0.580312 0.406339 -0.70578 0.642057 0.299396 -0.705779 0.642058 0.299397 -0.705779 0.684293 0.183356 -0.705778 0.684294 0.183356 -0.705778 0.705737 0.061744 -0.705777 0.705738 0.0617441 -0.694733 -0.694759 0.186161 -0.694737 -0.694756 0.186159 -0.694736 -0.508598 0.508596 -0.694731 -0.5086 0.5086 -0.694735 -0.186159 0.694758 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694739 0.186159 0.694754 -0.694741 0.508593 0.508594 -0.694736 0.508597 0.508597 -0.694737 0.694756 0.186157 -0.694747 0.694747 0.186157 -0.694747 -0.694747 0.186155 -0.694738 -0.694755 0.186159 -0.694738 -0.508595 0.508596 -0.694743 -0.508592 0.508592 -0.694742 -0.186158 0.694751 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694739 0.186159 0.694754 -0.694733 0.5086 0.508598 -0.694738 0.508595 0.508595 -0.694738 0.694754 0.18616 -0.694733 0.694759 0.18616 -0.694747 -0.694747 0.186155 -0.694738 -0.694755 0.186159 -0.694738 -0.508595 0.508596 -0.694743 -0.508593 0.508592 -0.694741 -0.186158 0.694752 -0.69474 -0.186158 0.694753 -0.69474 0.186159 0.694753 -0.694741 0.186158 0.694752 -0.694743 0.508592 0.508593 -0.694738 0.508596 0.508595 -0.694738 0.694755 0.186157 -0.694747 0.694747 0.186157 -0.694747 -0.694747 0.186155 -0.694738 -0.694755 0.186159 -0.694738 -0.508595 0.508596 -0.694743 -0.508592 0.508592 -0.694742 -0.186158 0.694751 -0.694742 -0.186158 0.694751 -0.694742 0.186158 0.694751 -0.694742 0.186158 0.694751 -0.694743 0.508591 0.508592 -0.694738 0.508596 0.508595 -0.694738 0.694755 0.186157 -0.694747 0.694747 0.186157 -0.694747 -0.694747 0.186155 -0.694738 -0.694755 0.186159 -0.694738 -0.508595 0.508596 -0.694741 -0.508594 0.508594 -0.694739 -0.186159 0.694754 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694735 0.18616 0.694757 -0.694731 0.508602 0.5086 -0.694738 0.508595 0.508595 -0.694738 0.694754 0.18616 -0.694733 0.694759 0.18616 -0.694733 -0.694759 0.186161 -0.694739 -0.694754 0.186159 -0.694741 -0.508595 0.508592 -0.694731 -0.5086 0.5086 -0.694735 -0.186159 0.694758 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694739 0.186159 0.694754 -0.694741 0.508594 0.508594 -0.694741 0.508594 0.508594 -0.694739 0.694754 0.186157 -0.694747 0.694747 0.186157 -0.69474 -0.694753 0.186158 -0.694739 -0.694754 0.186159 -0.694741 -0.508594 0.508593 -0.694736 -0.508597 0.508597 -0.694737 -0.186159 0.694756 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694735 0.18616 0.694757 -0.694731 0.508602 0.508599 -0.694741 0.508594 0.508594 -0.694739 0.694753 0.18616 -0.694733 0.694759 0.18616 -0.694747 -0.694747 0.186156 -0.694745 -0.694748 0.186157 -0.694743 -0.508592 0.508592 -0.694741 -0.508594 0.508594 -0.694739 -0.186158 0.694754 -0.69474 -0.186158 0.694753 -0.69474 0.186158 0.694753 -0.694739 0.186159 0.694754 -0.694741 0.508594 0.508593 -0.694743 0.508592 0.508592 -0.694745 0.694749 0.186157 -0.694747 0.694747 0.186157 -0.69474 -0.694753 0.186159 -0.694745 -0.694748 0.186157 -0.694743 -0.508592 0.508592 -0.694743 -0.508592 0.508592 -0.694742 -0.186158 0.694751 -0.694742 -0.186158 0.694751 -0.694742 0.186158 0.694751 -0.69474 0.186158 0.694752 -0.694738 0.508596 0.508595 -0.694738 0.508596 0.508595 -0.694738 0.694755 0.186159 -0.69474 0.694753 0.186159 -0.69474 -0.694753 0.186159 -0.694745 -0.694748 0.186157 -0.694743 -0.508592 0.508592 -0.694743 -0.508593 0.508592 -0.694741 -0.186158 0.694752 -0.69474 -0.186158 0.694753 -0.69474 0.186158 0.694753 -0.694739 0.186159 0.694753 -0.694738 0.508596 0.508596 -0.694738 0.508596 0.508595 -0.694738 0.694755 0.186159 -0.69474 0.694753 0.186159 -0.694747 -0.694747 0.186156 -0.694745 -0.694748 0.186157 -0.694743 -0.508592 0.508592 -0.694743 -0.508592 0.508592 -0.694742 -0.186158 0.694751 -0.69474 -0.186158 0.694753 -0.69474 0.186159 0.694753 -0.694742 0.186158 0.694751 -0.694743 0.508592 0.508592 -0.694743 0.508592 0.508592 -0.694745 0.694749 0.186157 -0.694747 0.694747 0.186157 -0.69474 -0.694753 0.186158 -0.694737 -0.694756 0.186159 -0.694736 -0.508597 0.508597 -0.694736 -0.508597 0.508597 -0.694737 -0.186159 0.694756 -0.69474 -0.186159 0.694753 -0.69474 0.186158 0.694753 -0.694735 0.18616 0.694757 -0.694731 0.508601 0.5086 -0.694736 0.508597 0.508597 -0.694737 0.694755 0.18616 -0.694733 0.694759 0.18616 0.694747 0.694747 0.186155 0.694739 0.694754 0.186159 0.694741 0.508594 0.508594 0.694741 0.508594 0.508594 0.694739 0.186159 0.694754 0.69474 0.186159 0.694753 0.69474 -0.186158 0.694753 0.694735 -0.18616 0.694757 0.694731 -0.508602 0.508599 0.694741 -0.508594 0.508594 0.694739 -0.694753 0.18616 0.694733 -0.694759 0.18616 0.694733 0.694759 0.186161 0.694738 0.694755 0.186159 0.694739 0.508596 0.508594 0.694731 0.5086 0.5086 0.694735 0.186159 0.694758 0.69474 0.186159 0.694753 0.69474 -0.186158 0.694753 0.694739 -0.186159 0.694754 0.694741 -0.508593 0.508594 0.694738 -0.508595 0.508595 0.694738 -0.694755 0.186157 0.694747 -0.694747 0.186157 0.694747 0.694747 0.186155 0.694738 0.694755 0.186159 0.694738 0.508595 0.508596 0.694743 0.508592 0.508592 0.694742 0.186158 0.694751 0.694742 0.186158 0.694751 0.694742 -0.186158 0.694751 0.694742 -0.186158 0.694751 0.694743 -0.508591 0.508592 0.694738 -0.508596 0.508595 0.694738 -0.694755 0.186157 0.694747 -0.694747 0.186157 0.694747 0.694747 0.186155 0.694738 0.694755 0.186159 0.694738 0.508595 0.508596 0.694743 0.508593 0.508592 0.694741 0.186158 0.694752 0.69474 0.186158 0.694753 0.69474 -0.186159 0.694753 0.694741 -0.186158 0.694752 0.694743 -0.508592 0.508593 0.694738 -0.508596 0.508595 0.694738 -0.694755 0.186157 0.694747 -0.694747 0.186157 0.694733 0.694759 0.186161 0.694738 0.694755 0.186159 0.694739 0.508596 0.508595 0.694734 0.508599 0.508599 0.694739 0.186159 0.694754 0.69474 0.186159 0.694753 0.69474 -0.186159 0.694753 0.694742 -0.186158 0.694751 0.694743 -0.508591 0.508593 0.694738 -0.508595 0.508595 0.694738 -0.694755 0.186157 0.694747 -0.694747 0.186157 0.694747 0.694747 0.186155 0.694737 0.694756 0.186159 0.694736 0.508597 0.508598 0.694741 0.508594 0.508594 0.694739 0.186159 0.694754 0.69474 0.186159 0.694753 0.69474 -0.186158 0.694753 0.694735 -0.18616 0.694757 0.694731 -0.508601 0.5086 0.694736 -0.508597 0.508597 0.694737 -0.694755 0.18616 0.694733 -0.694759 0.18616 0.694733 0.694759 0.186161 0.694737 0.694756 0.186159 0.694736 0.508598 0.508596 0.694731 0.5086 0.5086 0.694735 0.186159 0.694758 0.69474 0.186159 0.694753 0.69474 -0.186158 0.694753 0.694737 -0.18616 0.694755 0.694736 -0.508597 0.508597 0.694736 -0.508597 0.508597 0.694737 -0.694756 0.186159 0.69474 -0.694753 0.186159 0.694747 0.694747 0.186156 0.694745 0.694748 0.186157 0.694743 0.508592 0.508592 0.694743 0.508592 0.508592 0.694742 0.186158 0.694751 0.69474 0.186159 0.694753 0.69474 -0.186159 0.694753 0.694742 -0.186158 0.694751 0.694743 -0.508592 0.508592 0.694743 -0.508592 0.508592 0.694745 -0.694749 0.186157 0.694747 -0.694747 0.186157 0.69474 0.694753 0.186158 0.694738 0.694755 0.186159 0.694738 0.508596 0.508595 0.694738 0.508596 0.508596 0.694739 0.186158 0.694753 0.69474 0.186158 0.694753 0.69474 -0.186159 0.694753 0.694741 -0.186158 0.694752 0.694743 -0.508593 0.508592 0.694743 -0.508592 0.508592 0.694745 -0.694748 0.186158 0.69474 -0.694753 0.186159 0.69474 0.694753 0.186158 0.694738 0.694755 0.186159 0.694738 0.508596 0.508595 0.694738 0.508596 0.508595 0.69474 0.186158 0.694753 0.694742 0.186158 0.694751 0.694742 -0.186158 0.694751 0.694742 -0.186158 0.694751 0.694743 -0.508592 0.508592 0.694743 -0.508592 0.508592 0.694745 -0.694748 0.186158 0.69474 -0.694753 0.186159 0.694747 0.694747 0.186156 0.694745 0.694748 0.186157 0.694743 0.508592 0.508592 0.694741 0.508594 0.508594 0.694739 0.186159 0.694754 0.69474 0.186159 0.694753 0.69474 -0.186158 0.694753 0.694739 -0.186159 0.694754 0.694741 -0.508594 0.508593 0.694743 -0.508592 0.508592 0.694745 -0.694749 0.186157 0.694747 -0.694747 0.186157 0.694733 0.694759 0.186161 0.694739 0.694754 0.186159 0.694741 0.508595 0.508592 0.694731 0.5086 0.5086 0.694735 0.186159 0.694758 0.69474 0.186159 0.694753 0.69474 -0.186158 0.694753 0.694737 -0.18616 0.694755 0.694736 -0.508598 0.508597 0.694741 -0.508594 0.508594 0.694739 -0.694754 0.186159 0.69474 -0.694753 0.186159 0.707101 0.691437 0.148064 0.705157 0.705167 0.0741161 0.705155 0.705169 0.0741161 0.688909 0.689032 0.225032 0.705159 0.674346 0.219108 0.706822 0.634237 0.313283 0.266132 0.834793 0.481969 0.706356 0.598409 0.378111 0.705155 0.526929 0.474449 0.705158 0.526927 0.474448 0.705158 0.416769 0.573634 0.705157 0.41677 0.573635 0.705157 0.288397 0.64775 0.705155 0.288398 0.647752 0.705155 0.14742 0.693559 0.705154 0.147421 0.69356 0.705154 0 0.709054 0.705154 0 0.709054 0.705154 -0.14742 0.69356 0.705156 -0.14742 0.693558 0.705156 -0.288397 0.647751 0.705155 -0.288398 0.647752 0.705154 -0.416772 0.573637 0.705157 -0.41677 0.573634 0.705158 -0.526927 0.474447 0.705161 -0.526925 0.474445 0.705162 -0.614052 0.354523 0.705155 -0.614058 0.354527 0.705155 -0.67435 0.219109 0.705152 -0.674352 0.21911 0.705152 -0.705172 0.074117 0.705162 -0.705162 0.0741154 -0.705162 -0.705162 0.074116 -0.705155 -0.614058 0.354527 -0.706881 -0.655895 0.264804 -0.300701 -0.90704 0.294715 -0.706241 -0.680596 0.194971 -0.705152 -0.705172 0.0741164 -0.705157 -0.41677 0.573634 -0.707023 -0.484246 0.515388 -0.633281 -0.54694 0.547551 -0.587887 -0.577781 0.566179 -0.329727 -0.701585 0.631711 -0.706168 -0.541029 0.456743 -0.705162 -0.614052 0.354524 -0.26807 -0.39185 0.880109 -0.672238 -0.33907 0.658124 -0.707088 -0.348498 0.615286 -0.705154 -0.416772 0.573637 -0.707023 0.484247 0.515387 -0.705158 0.41677 0.573634 -0.705157 0.41677 0.573635 -0.705157 0.288397 0.64775 -0.705155 0.288398 0.647753 -0.705155 0.14742 0.693559 -0.705154 0.147421 0.69356 -0.705154 0 0.709054 -0.705154 0 0.709054 -0.705154 -0.147421 0.69356 -0.705156 -0.14742 0.693558 -0.70705 -0.229954 0.668732 -0.567026 -0.317963 0.759856 -0.511607 0.644892 0.567778 -0.342801 0.698116 0.628587 -0.632101 0.547784 0.54807 -0.65733 0.527718 0.537988 -0.707033 0.563935 0.426711 -0.705154 0.614059 0.354527 -0.705159 0.614055 0.354524 -0.706885 0.655891 0.264804 -0.300694 0.907042 0.294716 -0.706245 0.680592 0.194969 -0.705157 0.705167 0.074116 -0.705155 0.705169 0.0741162 0 0.965926 0.258817 0 0.965926 0.258817 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258817 0 -0.965926 0.258817 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258817 0 -0.965926 0.258817 0 0.965927 0.258817 0 0.965927 0.258817 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.25882 0 -0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258818 0 -0.965926 0.258818 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965925 0.25882 0 -0.965925 0.25882 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965925 0.25882 0 -0.965925 0.25882 0 0.965926 0.258819 0 0.965926 0.258819 0 0.707107 0.707106 0 0.707107 0.707106 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707107 0.707106 0 -0.707107 0.707106 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.965925 0.258821 0 0.965925 0.258821 0 0.707109 0.707105 0 0.707109 0.707105 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.258819 0 -0.965926 0.258819 0 0.965926 0.258817 0 0.965926 0.258817 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965925 0.258821 0 -0.965925 0.258821 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707105 0 0.707108 0.707105 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707106 0.707107 0 -0.707106 0.707107 0 -0.965926 0.258817 0 -0.965926 0.258817 0 0.965926 0.258817 0 0.965926 0.258817 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258817 0 -0.965926 0.258817 0.698073 -0.698075 0.15933 0.698073 -0.698075 0.15933 0.698073 -0.559813 0.446435 0.698072 -0.559815 0.446433 0.698072 -0.310672 0.645119 0.698072 -0.310672 0.645119 0.698073 0 0.716027 0.698073 0 0.716027 0.698073 0.310673 0.645118 0.698072 0.310672 0.645119 0.698072 0.559813 0.446435 0.698072 0.559812 0.446437 0.702556 0.68212 0.202798 0.711357 0.68521 0.156393 0.706368 0.70637 0.0456791 0 0.974928 0.222519 0 0.974928 0.222519 0 0.78183 0.623491 0 0.78183 0.623491 0 0.433883 0.900969 0 0.433883 0.900969 0 0 1 0 0 1 0 -0.433883 0.900969 0 -0.433883 0.900969 0 -0.781834 0.623486 0 -0.781834 0.623486 0 -0.974928 0.222519 0 -0.974928 0.222519 0.694746 0.694748 0.186153 0.694745 0.694748 0.186156 0.694745 0.508589 0.508593 0.694746 0.50859 0.50859 0.694746 0.186157 0.694748 0.694746 0.186157 0.694748 0.694746 -0.186157 0.694748 0.694745 -0.186157 0.694748 0.694745 -0.508591 0.50859 0.694745 -0.508591 0.508591 0.694745 -0.694748 0.186158 0.694745 -0.694747 0.186158 0 0.965927 0.258814 0 0.965927 0.258814 0 0.707104 0.707109 0 0.707104 0.707109 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.25882 0 -0.965926 0.25882 0.694745 0.694747 0.186158 0.694746 0.694747 0.186156 0.694746 0.508591 0.508589 0.694746 0.508591 0.50859 0.694745 0.186156 0.694748 0.694746 0.186157 0.694747 0.694746 -0.186156 0.694747 0.694745 -0.186157 0.694748 0.694745 -0.508592 0.50859 0.694746 -0.508589 0.508591 0.694746 -0.694747 0.186158 0.694746 -0.694748 0.186156 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707105 0 0.707108 0.707105 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.965925 0.25882 0 -0.965925 0.25882 0.694745 0.694747 0.186158 0.694746 0.694747 0.186157 0.694746 0.508591 0.50859 0.694746 0.508591 0.50859 0.694746 0.186157 0.694747 0.694746 0.186157 0.694748 0.694746 -0.186157 0.694748 0.694746 -0.186157 0.694747 0.694746 -0.50859 0.508591 0.694745 -0.508591 0.508591 0.694745 -0.694748 0.186156 0.694746 -0.694748 0.186157 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.25882 0.965926 0 -0.25882 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258817 0 -0.965926 0.258817 0.694746 0.694748 0.186156 0.694745 0.694748 0.186157 0.694745 0.50859 0.508591 0.694746 0.508591 0.50859 0.694746 0.186157 0.694748 0.694746 0.186157 0.694748 0.694746 -0.186157 0.694748 0.694746 -0.186157 0.694748 0.694745 -0.508591 0.50859 0.694746 -0.508591 0.50859 0.694746 -0.694747 0.186158 0.694746 -0.694748 0.186157 0 0.965926 0.258817 0 0.965926 0.258817 0 0.707106 0.707108 0 0.707106 0.707108 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965926 0.25882 0 -0.965926 0.25882 0.694745 0.694747 0.186158 0.694746 0.694747 0.186157 0.694746 0.508591 0.50859 0.694746 0.508591 0.508591 0.694745 0.186157 0.694748 0.694746 0.186157 0.694748 0.694746 -0.186157 0.694748 0.694746 -0.186157 0.694748 0.694746 -0.50859 0.508591 0.694745 -0.508591 0.508591 0.694745 -0.694748 0.186156 0.694746 -0.694748 0.186157 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707106 0.707108 0 -0.707106 0.707108 0 -0.965926 0.258817 0 -0.965926 0.258817 0.694745 0.694747 0.186158 0.694746 0.694747 0.186156 0.694746 0.508591 0.508589 0.694746 0.50859 0.50859 0.694745 0.186156 0.694748 0.694746 0.186157 0.694748 0.694746 -0.186156 0.694748 0.694745 -0.186157 0.694748 0.694745 -0.508592 0.50859 0.694746 -0.508589 0.508591 0.694746 -0.694747 0.186158 0.694746 -0.694748 0.186156 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707105 0 0.707108 0.707105 0 0.258817 0.965926 0 0.258817 0.965926 0 -0.258817 0.965926 0 -0.258817 0.965926 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.965925 0.25882 0 -0.965925 0.25882 0.694746 0.694748 0.186154 0.694745 0.694748 0.186156 0.694745 0.50859 0.508592 0.694746 0.508591 0.50859 0.694746 0.186158 0.694747 0.694746 0.186157 0.694748 0.694745 -0.186158 0.694747 0.694746 -0.186157 0.694747 0.694745 -0.508592 0.50859 0.694745 -0.508591 0.50859 0.694745 -0.694747 0.186158 0.694745 -0.694747 0.186158 0 0.965927 0.258815 0 0.965927 0.258815 0 0.707105 0.707108 0 0.707105 0.707108 0 0.25882 0.965925 0 0.25882 0.965925 0 -0.25882 0.965925 0 -0.25882 0.965925 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.965925 0.258821 0 -0.965925 0.258821 0.694745 0.694747 0.186158 0.694745 0.694747 0.186158 0.694745 0.508591 0.50859 0.694745 0.508591 0.508591 0.694745 0.186157 0.694748 0.694746 0.186157 0.694748 0.694746 -0.186157 0.694748 0.694746 -0.186157 0.694748 0.694746 -0.508588 0.508592 0.694745 -0.508591 0.508591 0.694745 -0.694749 0.186154 0.694746 -0.694748 0.186156 0 0.965925 0.25882 0 0.965925 0.25882 0 0.707108 0.707106 0 0.707108 0.707106 0 0.258819 0.965926 0 0.258819 0.965926 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707104 0.707109 0 -0.707104 0.707109 0 -0.965927 0.258814 0 -0.965927 0.258814 -0.980541 -0.0294405 0.194094 -0.980398 -0.196079 0.0193121 -0.980398 -0.196079 0.0193122 -0.980398 -0.173763 0.0928784 -0.979269 -0.17738 0.0978182 -0.980578 -0.180204 0.0774222 -0.980398 -0.188544 0.0571942 -0.979846 -0.190769 0.0592352 -0.98058 -0.192097 0.0395192 -0.980398 -0.124993 0.152305 -0.978034 -0.127975 0.164538 -0.980568 -0.135042 0.142304 -0.980398 -0.152305 0.124993 -0.978665 -0.156233 0.133436 -0.980573 -0.160924 0.112157 -0.980398 -0.0571942 0.188544 -0.976678 -0.0542127 0.207754 -0.980552 -0.0679294 0.184131 -0.980398 -0.0928784 0.173763 -0.977372 -0.0935573 0.189715 -0.98056 -0.103616 0.166628 -0.97595 -0.0114091 0.217697 -0.980398 -0.0193121 0.196079 -0.980529 0.0102775 0.196105 -0.978323 0.0202979 0.206088 -0.980541 0.0294405 0.194094 -0.980515 0.0496003 0.190078 -0.978403 0.0600043 0.197808 -0.980552 0.0679293 0.184131 -0.9805 0.0869188 0.176254 -0.978561 0.0970885 0.18164 -0.980561 0.103616 0.166628 -0.980483 0.120704 0.155191 -0.978794 0.129952 0.158347 -0.980568 0.135042 0.142304 -0.980464 0.149571 0.127746 -0.9791 0.157213 0.129022 -0.980573 0.160923 0.112158 -0.980444 0.172333 0.095035 -0.979473 0.177772 0.0950213 -0.980578 0.180204 0.0774217 -0.980422 0.188053 0.058392 -0.979908 0.190862 0.0578973 -0.98058 0.192097 0.0395186 -0.980398 0.196079 0.0193121 -0.980398 0.196079 0.0193121 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.995734 0.0922682 0 0.995734 0.0922682 0 0.961826 0.273663 0 0.961826 0.273663 0 0.895163 0.445738 0 0.895163 0.445738 0 0.798017 0.602635 0 0.798017 0.602635 0 0.673696 0.739009 0 0.673696 0.739009 0 0.526432 0.850217 0 0.526432 0.850217 0 0.361241 0.932472 0 0.361241 0.932472 0 0.18375 0.982973 0 0.18375 0.982973 0 0 1 0 0 1 0 -0.18375 0.982973 0 -0.18375 0.982973 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.995734 0.0922684 0 -0.995734 0.0922684 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.995734 0.0922684 0 -0.995734 0.0922684 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.183749 0.982973 0 -0.183749 0.982973 0 0 1 0 0 1 0 0.183749 0.982973 0 0.183749 0.982973 0 0.361242 0.932472 0 0.361242 0.932472 0 0.526432 0.850217 0 0.526432 0.850217 0 0.673696 0.739009 0 0.673696 0.739009 0 0.798017 0.602634 0 0.798017 0.602634 0 0.895163 0.445738 0 0.895163 0.445738 0 0.961826 0.273663 0 0.961826 0.273663 0 0.995734 0.0922684 0 0.995734 0.0922684 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.995734 0.0922679 0 0.995734 0.0922679 0 0.961826 0.273663 0 0.961826 0.273663 0 0.895163 0.445738 0 0.895163 0.445738 0 0.798017 0.602635 0 0.798017 0.602635 0 0.673696 0.739009 0 0.673696 0.739009 0 0.526432 0.850217 0 0.526432 0.850217 0 0.361242 0.932472 0 0.361242 0.932472 0 0.183749 0.982973 0 0.183749 0.982973 0 0 1 0 0 1 0 -0.183749 0.982973 0 -0.183749 0.982973 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.995734 0.0922684 0 -0.995734 0.0922684 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.995734 0.0922688 0 0.995734 0.0922688 0 0.961826 0.273663 0 0.961826 0.273663 0 0.895163 0.445738 0 0.895163 0.445738 0 0.798017 0.602635 0 0.798017 0.602635 0 0.673696 0.739009 0 0.673696 0.739009 0 0.526432 0.850217 0 0.526432 0.850217 0 0.361242 0.932472 0 0.361242 0.932472 0 0.18375 0.982973 0 0.18375 0.982973 0 0 1 0 0 1 0 -0.18375 0.982973 0 -0.18375 0.982973 0 -0.361242 0.932472 0 -0.361242 0.932472 0 -0.526432 0.850217 0 -0.526432 0.850217 0 -0.673696 0.739009 0 -0.673696 0.739009 0 -0.798017 0.602635 0 -0.798017 0.602635 0 -0.895163 0.445738 0 -0.895163 0.445738 0 -0.961826 0.273663 0 -0.961826 0.273663 0 -0.995734 0.0922685 0 -0.995734 0.0922685 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.996195 0.0871554 0 -0.996195 0.0871554 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.906308 0.422618 0 -0.906308 0.422618 0 -0.819152 0.573576 0 -0.819152 0.573576 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.573576 0.819152 0 -0.573576 0.819152 0 -0.422619 0.906308 0 -0.422619 0.906308 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.0871557 0.996195 0 -0.0871557 0.996195 0 0.0871557 0.996195 0 0.0871557 0.996195 0 0.258819 0.965926 0 0.258819 0.965926 0 0.422619 0.906308 0 0.422619 0.906308 0 0.573576 0.819152 0 0.573576 0.819152 0 0.707107 0.707107 0 0.707107 0.707107 0 0.819152 0.573576 0 0.819152 0.573576 0 0.906308 0.422618 0 0.906308 0.422618 0 0.965926 0.258819 0 0.965926 0.258819 0 0.996195 0.0871557 0 0.996195 0.0871557 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -0.996195 0.0871563 0 -0.996195 0.0871563 0 -0.965926 0.258819 0 -0.965926 0.258819 0 -0.906308 0.422618 0 -0.906308 0.422618 0 -0.819152 0.573577 0 -0.819152 0.573577 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.573577 0.819152 0 -0.573577 0.819152 0 -0.422618 0.906308 0 -0.422618 0.906308 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.087156 0.996195 0 -0.087156 0.996195 0 0.087156 0.996195 0 0.087156 0.996195 0 0.258819 0.965926 0 0.258819 0.965926 0 0.422618 0.906308 0 0.422618 0.906308 0 0.573576 0.819152 0 0.573576 0.819152 0 0.707107 0.707107 0 0.707107 0.707107 0 0.819152 0.573577 0 0.819152 0.573577 0 0.906308 0.422618 0 0.906308 0.422618 0 0.965926 0.258819 0 0.965926 0.258819 0 0.996195 0.0871558 0 0.996195 0.0871558 0.80997 0.584239 0.0511143 0.80997 0.584239 0.0511143 0.80997 0.566487 0.15179 0.80997 0.566487 0.15179 0.80997 0.531523 0.247853 0.80997 0.531523 0.247853 0.80997 0.480409 0.336386 0.80997 0.480409 0.336386 0.80997 0.414698 0.414697 0.80997 0.414698 0.414697 0.80997 0.336386 0.480409 0.809971 0.336385 0.480409 0.809971 0.247853 0.531523 0.809971 0.247853 0.531523 0.809971 0.15179 0.566487 0.80997 0.15179 0.566487 0.80997 0.0511144 0.584239 0.809971 0.0511142 0.584239 0.809971 -0.0511144 0.584239 0.80997 -0.0511143 0.584239 0.80997 -0.15179 0.566487 0.809971 -0.15179 0.566487 0.809971 -0.247853 0.531523 0.809971 -0.247853 0.531523 0.809971 -0.336386 0.480408 0.80997 -0.336386 0.480409 0.80997 -0.414698 0.414697 0.80997 -0.414698 0.414697 0.80997 -0.480409 0.336386 0.80997 -0.480409 0.336386 0.80997 -0.531523 0.247853 0.80997 -0.531523 0.247853 0.80997 -0.566487 0.15179 0.80997 -0.566488 0.15179 0.80997 -0.58424 0.0511147 0.80997 -0.584239 0.0511143 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.994522 0.104529 0 -0.994522 0.104529 0 -0.951057 0.309017 0 -0.951057 0.309017 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.743145 0.669131 0 -0.743145 0.669131 0 -0.587785 0.809017 0 -0.587785 0.809017 0 -0.406737 0.913545 0 -0.406737 0.913545 0 -0.207911 0.978148 0 -0.207911 0.978148 0 0 1 0 0 1 0 0.207912 0.978148 0 0.207912 0.978148 0 0.406737 0.913545 0 0.406737 0.913545 0 0.587785 0.809017 0 0.587785 0.809017 0 0.743145 0.669131 0 0.743145 0.669131 0 0.866025 0.5 0 0.866025 0.5 0 0.951057 0.309017 0 0.951057 0.309017 0 0.994522 0.104528 0 0.994522 0.104528 0 -0.994522 0.104529 -0.14221 -0.98507 0.0970217 0 -0.979487 0.201506 0 -0.951057 0.309017 -0.276168 -0.917879 0.285008 0 -0.91879 0.394746 0 -0.875675 0.482901 -0.330673 -0.817307 0.471873 -0.443096 -0.526934 0.725263 0 -0.820403 0.571786 0 -0.760406 0.649448 -0.396042 -0.682379 0.614417 0 -0.688355 0.725374 0 -0.613941 0.789352 -0.492718 -0.180922 0.851174 0 -0.528067 0.849203 0 -0.442289 0.896873 -0.474625 -0.358005 0.804092 0 -0.346117 0.938191 0 -0.252491 0.967599 0 -0.149966 0.988691 0 -0.0523362 0.99863 -0.498611 0 0.866826 0 0.0523362 0.99863 0 0.149966 0.988691 -0.492718 0.180922 0.851173 0 0.252492 0.967599 0 0.346117 0.938191 -0.474626 0.358004 0.804091 0 0.442289 0.896873 0 0.528068 0.849202 -0.443092 0.526935 0.725264 0 0.613941 0.789352 0 0.688355 0.725374 -0.396043 0.682379 0.614417 0 0.760406 0.649448 0 0.820401 0.571789 -0.330686 0.817303 0.471871 0 0.875675 0.4829 0 0.918792 0.394743 -0.243925 0.922329 0.299683 0 0.995185 0.0980172 -0.133511 0.985618 0.103593 0 0.979488 0.201502 0 0.95502 0.296542 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0.994522 -0.104528 -0.142206 0.985071 -0.0970211 0 0.979488 -0.201502 0 0.951057 -0.309017 -0.276158 0.917881 -0.28501 0 0.918792 -0.394743 0 0.875675 -0.4829 -0.330686 0.817303 -0.471871 -0.443092 0.526935 -0.725264 0 0.820401 -0.571789 0 0.760406 -0.649448 -0.396043 0.682379 -0.614417 0 0.688355 -0.725374 0 0.613941 -0.789352 -0.492718 0.180922 -0.851173 0 0.528068 -0.849202 0 0.442289 -0.896873 -0.474626 0.358004 -0.804091 0 0.346117 -0.938191 0 0.252492 -0.967599 0 0.149966 -0.988691 0 0.0523362 -0.99863 -0.498611 0 -0.866826 0 -0.0523362 -0.99863 0 -0.149966 -0.988691 -0.492718 -0.180922 -0.851174 0 -0.252491 -0.967599 0 -0.346117 -0.938191 -0.474625 -0.358005 -0.804092 0 -0.442289 -0.896873 0 -0.528067 -0.849203 -0.443096 -0.526934 -0.725263 0 -0.613941 -0.789352 0 -0.688355 -0.725374 -0.396042 -0.68238 -0.614418 0 -0.760406 -0.649448 0 -0.820403 -0.571786 -0.330674 -0.817307 -0.471873 0 -0.875675 -0.482901 0 -0.91879 -0.394746 -0.243935 -0.922327 -0.299682 0 -0.995185 -0.0980179 -0.133514 -0.985618 -0.103593 0 -0.979487 -0.201506 0 -0.95502 -0.296541 0 0.994522 -0.104528 0 0.994522 -0.104528 0 0.951057 -0.309017 0 0.951057 -0.309017 0 0.866025 -0.5 0 0.866025 -0.5 0 0.743145 -0.669131 0 0.743145 -0.669131 0 0.587785 -0.809017 0 0.587785 -0.809017 0 0.406737 -0.913545 0 0.406737 -0.913545 0 0.207912 -0.978148 0 0.207912 -0.978148 0 0 -1 0 0 -1 0 -0.207911 -0.978148 0 -0.207911 -0.978148 0 -0.406737 -0.913545 0 -0.406737 -0.913545 0 -0.587785 -0.809017 0 -0.587785 -0.809017 0 -0.743145 -0.669131 0 -0.743145 -0.669131 0 -0.866025 -0.5 0 -0.866025 -0.5 0 -0.951057 -0.309017 0 -0.951057 -0.309017 0 -0.994522 -0.104529 0 -0.994522 -0.104529 0.80997 -0.584239 -0.0511146 0.80997 -0.58424 -0.0511143 0.80997 -0.566488 -0.15179 0.80997 -0.566487 -0.15179 0.80997 -0.531523 -0.247853 0.80997 -0.531524 -0.247853 0.80997 -0.480409 -0.336386 0.80997 -0.480409 -0.336386 0.80997 -0.414698 -0.414697 0.80997 -0.414698 -0.414697 0.80997 -0.336386 -0.480409 0.809971 -0.336386 -0.480409 0.809971 -0.247853 -0.531523 0.809971 -0.247853 -0.531523 0.809971 -0.15179 -0.566487 0.80997 -0.15179 -0.566487 0.80997 -0.0511144 -0.584239 0.809971 -0.0511142 -0.584239 0.809971 0.0511144 -0.584239 0.80997 0.0511143 -0.584239 0.80997 0.15179 -0.566487 0.809971 0.15179 -0.566487 0.809971 0.247853 -0.531523 0.809971 0.247853 -0.531523 0.809971 0.336386 -0.480409 0.80997 0.336386 -0.480409 0.80997 0.414698 -0.414697 0.80997 0.414698 -0.414697 0.80997 0.480409 -0.336386 0.80997 0.480409 -0.336386 0.80997 0.531523 -0.247853 0.80997 0.531523 -0.247853 0.80997 0.566487 -0.15179 0.80997 0.566487 -0.15179 0.80997 0.584239 -0.0511143 0.80997 0.584239 -0.0511143 0 0.996195 -0.0871558 0 0.996195 -0.0871558 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.906308 -0.422618 0 0.906308 -0.422618 0 0.819152 -0.573577 0 0.819152 -0.573577 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.573576 -0.819152 0 0.573576 -0.819152 0 0.422618 -0.906308 0 0.422618 -0.906308 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.087156 -0.996195 0 0.087156 -0.996195 0 -0.087156 -0.996195 0 -0.087156 -0.996195 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.422618 -0.906308 0 -0.422618 -0.906308 0 -0.573577 -0.819152 0 -0.573577 -0.819152 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.819152 -0.573577 0 -0.819152 -0.573577 0 -0.906308 -0.422618 0 -0.906308 -0.422618 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.996195 -0.0871563 0 -0.996195 -0.0871563 0 0.996195 -0.0871557 0 0.996195 -0.0871557 0 0.965926 -0.258819 0 0.965926 -0.258819 0 0.906308 -0.422618 0 0.906308 -0.422618 0 0.819152 -0.573576 0 0.819152 -0.573576 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.573576 -0.819152 0 0.573576 -0.819152 0 0.422619 -0.906308 0 0.422619 -0.906308 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.0871557 -0.996195 0 0.0871557 -0.996195 0 -0.0871557 -0.996195 0 -0.0871557 -0.996195 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 -0.422619 -0.906308 0 -0.422619 -0.906308 0 -0.573576 -0.819152 0 -0.573576 -0.819152 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.819152 -0.573576 0 -0.819152 -0.573576 0 -0.906308 -0.422618 0 -0.906308 -0.422618 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.996195 -0.0871554 0 -0.996195 -0.0871554 0 -0.995734 -0.0922685 0 -0.995734 -0.0922685 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.18375 -0.982973 0 -0.18375 -0.982973 0 0 -1 0 0 -1 0 0.18375 -0.982973 0 0.18375 -0.982973 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.961826 -0.273663 0 0.961826 -0.273663 0 0.995734 -0.0922688 0 0.995734 -0.0922688 0 -0.995734 -0.0922684 0 -0.995734 -0.0922684 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.183749 -0.982973 0 -0.183749 -0.982973 0 0 -1 0 0 -1 0 0.183749 -0.982973 0 0.183749 -0.982973 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.961826 -0.273663 0 0.961826 -0.273663 0 0.995734 -0.0922679 0 0.995734 -0.0922679 0 0.995734 -0.0922684 0 0.995734 -0.0922684 0 0.961826 -0.273663 0 0.961826 -0.273663 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.361242 -0.932472 0 0.361242 -0.932472 0 0.183749 -0.982973 0 0.183749 -0.982973 0 0 -1 0 0 -1 0 -0.183749 -0.982973 0 -0.183749 -0.982973 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.995734 -0.0922684 0 -0.995734 -0.0922684 0 -0.995734 -0.0922684 0 -0.995734 -0.0922684 0 -0.961826 -0.273663 0 -0.961826 -0.273663 0 -0.895163 -0.445738 0 -0.895163 -0.445738 0 -0.798017 -0.602635 0 -0.798017 -0.602635 0 -0.673696 -0.739009 0 -0.673696 -0.739009 0 -0.526432 -0.850217 0 -0.526432 -0.850217 0 -0.361242 -0.932472 0 -0.361242 -0.932472 0 -0.18375 -0.982973 0 -0.18375 -0.982973 0 0 -1 0 0 -1 0 0.18375 -0.982973 0 0.18375 -0.982973 0 0.361241 -0.932472 0 0.361241 -0.932472 0 0.526432 -0.850217 0 0.526432 -0.850217 0 0.673696 -0.739009 0 0.673696 -0.739009 0 0.798017 -0.602635 0 0.798017 -0.602635 0 0.895163 -0.445738 0 0.895163 -0.445738 0 0.961826 -0.273663 0 0.961826 -0.273663 0 0.995734 -0.0922682 0 0.995734 -0.0922682 -0.980541 0.0294405 -0.194094 -0.980398 0.196079 -0.0193121 -0.980398 0.196079 -0.0193121 -0.980398 0.173763 -0.0928784 -0.979269 0.17738 -0.0978182 -0.980578 0.180204 -0.0774217 -0.980398 0.188544 -0.0571942 -0.979846 0.190769 -0.0592355 -0.98058 0.192097 -0.0395186 -0.980398 0.124993 -0.152305 -0.978034 0.127975 -0.164539 -0.980568 0.135042 -0.142304 -0.980398 0.152305 -0.124993 -0.978665 0.156233 -0.133436 -0.980573 0.160923 -0.112158 -0.980398 0.0571942 -0.188544 -0.976678 0.0542127 -0.207754 -0.980552 0.0679293 -0.184131 -0.980398 0.0928783 -0.173763 -0.977372 0.0935572 -0.189715 -0.980561 0.103616 -0.166628 -0.97595 0.0114091 -0.217697 -0.980398 0.0193121 -0.196079 -0.980529 -0.0102775 -0.196105 -0.978323 -0.0202979 -0.206088 -0.980541 -0.0294405 -0.194094 -0.980515 -0.0496003 -0.190078 -0.978403 -0.0600043 -0.197808 -0.980552 -0.0679294 -0.184131 -0.9805 -0.0869188 -0.176254 -0.978561 -0.0970884 -0.18164 -0.980561 -0.103616 -0.166628 -0.980483 -0.120704 -0.155191 -0.978794 -0.129952 -0.158347 -0.980568 -0.135042 -0.142304 -0.980464 -0.149571 -0.127746 -0.9791 -0.157214 -0.129022 -0.980573 -0.160924 -0.112157 -0.980444 -0.172333 -0.095035 -0.979473 -0.177772 -0.0950213 -0.980578 -0.180204 -0.0774222 -0.980422 -0.188053 -0.0583919 -0.979908 -0.190861 -0.0578972 -0.98058 -0.192097 -0.0395192 -0.980398 -0.196079 -0.0193121 -0.980398 -0.196079 -0.0193123 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -0.707104 -0.707109 0 -0.707104 -0.707109 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965925 -0.25882 0 0.965925 -0.25882 0.694746 -0.694748 -0.186153 0.694745 -0.694748 -0.186156 0.694745 -0.508589 -0.508593 0.694746 -0.50859 -0.50859 0.694746 -0.186157 -0.694747 0.694746 -0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694745 0.508591 -0.50859 0.694745 0.508591 -0.508591 0.694745 0.694747 -0.186158 0.694745 0.694747 -0.186158 0 -0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965927 -0.258814 0 0.965927 -0.258814 0.704846 0.704848 -0.0798916 0.71628 0.674036 -0.180604 0.694745 -0.694747 -0.186158 0.694745 -0.694747 -0.186158 0.694746 -0.508592 -0.508589 0.694745 -0.508591 -0.508591 0.694745 -0.186157 -0.694748 0.694746 -0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694746 0.508589 -0.508591 0.694745 0.508591 -0.50859 0.703159 0.661708 -0.26021 0 -0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.965925 -0.25882 0 0.965925 -0.25882 0.694745 -0.694747 -0.186158 0.694746 -0.694747 -0.186156 0.694746 -0.508591 -0.508589 0.694745 -0.50859 -0.508592 0.694745 -0.186156 -0.694748 0.694746 -0.186157 -0.694748 0.694746 0.186156 -0.694748 0.694745 0.186157 -0.694748 0.694746 0.508592 -0.508589 0.694746 0.50859 -0.50859 0.694746 0.694747 -0.186158 0.694746 0.694748 -0.186156 0 -0.974928 -0.222519 0.101691 -0.960919 -0.257476 0 -0.884116 -0.467267 0 -0.707106 -0.707108 0.231196 -0.737437 -0.634614 0 -0.563314 -0.826243 0 -0.25882 -0.965926 0.335403 -0.34418 -0.876952 0 -0.111964 -0.993712 0 0.111964 -0.993712 0.200842 0.253546 -0.946244 0 0.365342 -0.930873 0 0.56332 -0.826239 0.168256 0.697027 -0.697025 0 0.974928 -0.222519 0.1017 0.960917 -0.257478 0 0.884107 -0.467285 0 0.757973 -0.652286 0.698073 0.698075 -0.159331 0.698072 0.698075 -0.15933 0.706858 0.625378 -0.330536 0.693897 0.562977 -0.448959 0.700861 0.540661 -0.465275 0.706115 0.398885 -0.585058 0.691347 0.313491 -0.65097 0.703124 0.259783 -0.661914 0.704872 0.0794201 -0.704874 0.69049 0 -0.723342 0.704872 -0.0794201 -0.704874 0.698073 -0.310672 -0.645118 0.680458 -0.267718 -0.682132 0.706115 -0.398882 -0.58506 0.698073 -0.559812 -0.446435 0.698073 -0.698075 -0.15933 0.698073 -0.698075 -0.15933 0.706859 -0.625384 -0.330524 0.689671 -0.548865 -0.472335 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.258817 0 0.965926 -0.258817 0.694745 -0.694747 -0.186158 0.694746 -0.694747 -0.186157 0.694746 -0.508591 -0.50859 0.694746 -0.508591 -0.50859 0.694746 -0.186157 -0.694748 0.694746 -0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694746 0.50859 -0.508591 0.694745 0.508591 -0.508591 0.694745 0.694748 -0.186156 0.694746 0.694748 -0.186157 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965925 -0.25882 0 0.965925 -0.25882 0.694746 -0.694748 -0.186156 0.694745 -0.694748 -0.186157 0.694745 -0.50859 -0.508591 0.694746 -0.508591 -0.508591 0.694745 -0.186157 -0.694748 0.694746 -0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694745 0.508591 -0.50859 0.694746 0.50859 -0.50859 0.694746 0.694747 -0.186158 0.694746 0.694748 -0.186157 0 -0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.258817 -0.965926 0 -0.258817 -0.965926 0 0.258817 -0.965926 0 0.258817 -0.965926 0 0.707108 -0.707105 0 0.707108 -0.707105 0 0.965925 -0.25882 0 0.965925 -0.25882 0.694745 -0.694747 -0.186158 0.694746 -0.694747 -0.186156 0.694746 -0.508591 -0.508589 0.694745 -0.50859 -0.508592 0.694745 -0.186156 -0.694748 0.694746 -0.186157 -0.694748 0.694746 0.186156 -0.694748 0.694745 0.186157 -0.694748 0.694746 0.508592 -0.508589 0.694746 0.50859 -0.50859 0.694746 0.694747 -0.186158 0.694746 0.694748 -0.186156 0 -0.965925 -0.258821 0 -0.965925 -0.258821 0 -0.707108 -0.707105 0 -0.707108 -0.707105 0 -0.25882 -0.965925 0 -0.25882 -0.965925 0 0.25882 -0.965925 0 0.25882 -0.965925 0 0.707105 -0.707108 0 0.707105 -0.707108 0 0.965927 -0.258815 0 0.965927 -0.258815 0.694745 -0.694747 -0.186158 0.694745 -0.694747 -0.186158 0.694746 -0.508592 -0.508589 0.694745 -0.508591 -0.50859 0.694746 -0.186158 -0.694747 0.694746 -0.186157 -0.694748 0.694745 0.186158 -0.694747 0.694746 0.186157 -0.694747 0.694746 0.508589 -0.508591 0.694745 0.508591 -0.50859 0.694745 0.694749 -0.186154 0.694746 0.694748 -0.186156 0 -0.965927 -0.258814 0 -0.965927 -0.258814 0 -0.707104 -0.707109 0 -0.707104 -0.707109 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965925 -0.25882 0 0.965925 -0.25882 0.694746 -0.694748 -0.186153 0.694745 -0.694748 -0.186156 0.694745 -0.508589 -0.508593 0.694746 -0.50859 -0.50859 0.694746 -0.186157 -0.694748 0.694746 -0.186157 -0.694748 0.694746 0.186157 -0.694748 0.694745 0.186157 -0.694748 0.694745 0.508591 -0.50859 0.694745 0.508591 -0.508591 0.694745 0.694747 -0.186158 0.694745 0.694747 -0.186158 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.258817 0 0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965925 -0.25882 0 0.965925 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965927 -0.258817 0 0.965927 -0.258817 0 -0.965926 -0.258818 0 -0.965926 -0.258818 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707108 -0.707106 0 0.707108 -0.707106 0 0.965926 -0.25882 0 0.965926 -0.25882 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.781831 -0.62349 0 -0.781831 -0.62349 0 -0.433884 -0.900969 0 -0.433884 -0.900969 0 0 -1 0 0 -1 0 0.433883 -0.900969 0 0.433883 -0.900969 0 0.781832 -0.623489 0 0.781832 -0.623489 0 0.974928 -0.222521 0 0.974928 -0.222521 0 -0.965925 -0.25882 0 -0.965925 -0.25882 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707107 -0.707106 0 -0.707107 -0.707106 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707107 -0.707106 0 0.707107 -0.707106 0 0.965926 -0.258819 0 0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.965926 -0.258819 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707109 -0.707105 0 0.707109 -0.707105 0 0.965925 -0.258821 0 0.965925 -0.258821 0 -0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.78183 -0.623491 0 -0.78183 -0.623491 0 -0.433884 -0.900969 0 -0.433884 -0.900969 0 0 -1 0 0 -1 0 0.433884 -0.900969 0 0.433884 -0.900969 0 0.78183 -0.623491 0 0.78183 -0.623491 0 0.974928 -0.222521 0 0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.974928 -0.222521 0 -0.781831 -0.62349 0 -0.781831 -0.62349 0 -0.433884 -0.900969 0 -0.433884 -0.900969 0 0 -1 0 0 -1 0 0.433884 -0.900969 0 0.433884 -0.900969 0 0.781831 -0.62349 0 0.781831 -0.62349 0 0.974928 -0.222521 0 0.974928 -0.222521 0 -0.965926 -0.258817 0 -0.965926 -0.258817 0 -0.707106 -0.707108 0 -0.707106 -0.707108 0 -0.258819 -0.965926 0 -0.258819 -0.965926 0 0.258819 -0.965926 0 0.258819 -0.965926 0 0.707106 -0.707108 0 0.707106 -0.707108 0 0.965926 -0.258817 0 0.965926 -0.258817 -0.705157 0.674348 -0.219109 -0.705157 0.705167 -0.0741161 -0.705155 0.705169 -0.0741161 -0.707033 0.563935 -0.426711 -0.705687 0.608058 -0.363692 -0.521928 0.738711 -0.426495 -0.707061 0.641499 -0.297563 -0.705158 0.674347 -0.219109 -0.511607 0.644892 -0.567778 -0.342801 0.698116 -0.628586 -0.632101 0.547784 -0.54807 -0.705154 -0.14742 -0.69356 -0.705154 0 -0.709054 -0.705154 0 -0.709054 -0.705154 0.147421 -0.69356 -0.705155 0.14742 -0.693559 -0.705155 0.288398 -0.647753 -0.705157 0.288397 -0.64775 -0.705157 0.41677 -0.573635 -0.705156 0.416771 -0.573636 -0.707021 0.484248 -0.515388 -0.65733 0.527718 -0.537988 -0.705154 -0.416771 -0.573637 -0.705738 -0.299149 -0.642218 -0.501516 -0.351888 -0.790353 -0.70705 -0.229954 -0.668732 -0.705156 -0.14742 -0.693558 -0.633281 -0.54694 -0.547551 -0.707021 -0.484247 -0.515389 -0.705156 -0.416771 -0.573635 -0.587888 -0.577781 -0.566177 -0.329727 -0.701585 -0.63171 -0.706168 -0.54103 -0.456743 -0.705162 -0.614052 -0.354523 -0.705154 -0.614059 -0.354528 -0.70688 -0.655896 -0.264804 -0.300701 -0.90704 -0.294715 -0.706241 -0.680596 -0.194971 -0.705152 -0.705172 -0.074117 -0.705162 -0.705162 -0.0741154 0.705162 -0.705162 -0.074116 0.705152 -0.705172 -0.0741164 0.705152 -0.674352 -0.21911 0.705154 -0.674351 -0.21911 0.705154 -0.614059 -0.354527 0.705162 -0.614052 -0.354524 0.706056 -0.539182 -0.459095 0.373125 -0.689476 -0.620807 0.628604 -0.54997 -0.5499 0.705155 -0.288398 -0.647752 0.705154 -0.416772 -0.573637 0.705156 -0.416771 -0.573636 0.707058 -0.481299 -0.518093 0.665769 -0.521202 -0.533948 0.705157 0.41677 -0.573635 0.705157 0.288397 -0.64775 0.705155 0.288398 -0.647753 0.705155 0.14742 -0.693559 0.705154 0.147421 -0.69356 0.705154 0 -0.709054 0.705154 0 -0.709054 0.707089 -0.0790704 -0.70269 0.622904 -0.162649 -0.765203 0.705419 -0.152447 -0.692202 0.705156 -0.288397 -0.647751 0.665753 0.521215 -0.533954 0.707058 0.481298 -0.518094 0.705156 0.41677 -0.573636 0.628642 0.549942 -0.549884 0.373123 0.689476 -0.620807 0.706049 0.539187 -0.4591 0.705154 0.614059 -0.354527 0.705158 0.614056 -0.354525 0.706656 0.691429 -0.15021 0.673293 0.703188 -0.22848 0.697827 0.680711 -0.222867 0.707103 0.646177 -0.287161 0.707101 0.691437 -0.148064 0.705157 0.705167 -0.074116 0.705155 0.705169 -0.0741162 0.69474 -0.694753 -0.186158 0.694737 -0.694756 -0.186159 0.694736 -0.508597 -0.508597 0.694736 -0.508597 -0.508597 0.694737 -0.186159 -0.694756 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694735 0.18616 -0.694757 0.694731 0.508601 -0.5086 0.694736 0.508597 -0.508597 0.694737 0.694755 -0.18616 0.694733 0.694759 -0.18616 0.694747 -0.694747 -0.186156 0.694745 -0.694748 -0.186157 0.694743 -0.508592 -0.508592 0.694743 -0.508592 -0.508592 0.694742 -0.186158 -0.694751 0.69474 -0.186158 -0.694753 0.69474 0.186159 -0.694753 0.694742 0.186158 -0.694751 0.694743 0.508592 -0.508592 0.694743 0.508592 -0.508592 0.694745 0.694749 -0.186157 0.694747 0.694747 -0.186157 0.698067 -0.69808 -0.159332 0.698065 -0.698082 -0.159333 0.698065 -0.559818 -0.446441 0.698071 -0.559814 -0.446436 0.69807 -0.310674 -0.645121 0.698066 -0.310675 -0.645124 0.698067 0 -0.716032 0.698067 0 -0.716032 0.698069 0.310674 -0.645121 0.698067 0.310675 -0.645123 0.698066 0.559818 -0.446439 0.69807 0.559814 -0.446437 0.698072 0.698076 -0.159331 0.698067 0.69808 -0.159331 0.69474 -0.694753 -0.186159 0.694745 -0.694748 -0.186157 0.694743 -0.508592 -0.508592 0.694742 -0.508593 -0.508593 0.69474 -0.186158 -0.694752 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694737 0.508596 -0.508596 0.694738 0.508595 -0.508595 0.694738 0.694755 -0.186159 0.69474 0.694753 -0.186159 0.694747 -0.694747 -0.186156 0.694745 -0.694748 -0.186157 0.694743 -0.508592 -0.508592 0.694741 -0.508594 -0.508594 0.694739 -0.186158 -0.694754 0.69474 -0.186158 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694741 0.508594 -0.508593 0.694743 0.508592 -0.508592 0.694745 0.694749 -0.186157 0.694747 0.694747 -0.186157 0.69474 -0.694753 -0.186158 0.694739 -0.694754 -0.186159 0.694741 -0.508594 -0.508593 0.694736 -0.508597 -0.508597 0.694737 -0.186159 -0.694756 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694735 0.18616 -0.694757 0.694731 0.508602 -0.508599 0.694741 0.508594 -0.508594 0.694739 0.694753 -0.18616 0.694733 0.694759 -0.18616 0.69806 -0.698086 -0.159334 0.698063 -0.698084 -0.159332 0.698061 -0.55982 -0.446443 0.69807 -0.559815 -0.446437 0.698068 -0.310674 -0.645122 0.698066 -0.310675 -0.645124 0.698067 0 -0.716032 0.698067 0 -0.716032 0.698066 0.310675 -0.645124 0.698068 0.310674 -0.645122 0.69807 0.559814 -0.446438 0.698062 0.559821 -0.446442 0.698063 0.698083 -0.159333 0.698073 0.698073 -0.159333 0.698074 -0.698074 -0.159331 0.698065 -0.698081 -0.159335 0.698066 -0.559818 -0.44644 0.69807 -0.559815 -0.446437 0.698068 -0.310674 -0.645122 0.698066 -0.310675 -0.645124 0.698067 0 -0.716032 0.698067 0 -0.716032 0.698066 0.310675 -0.645124 0.698068 0.310674 -0.645122 0.69807 0.559814 -0.446437 0.698066 0.559818 -0.446439 0.698065 0.698082 -0.159333 0.698061 0.698087 -0.159333 0.694747 -0.694747 -0.186155 0.694738 -0.694755 -0.186159 0.694738 -0.508595 -0.508596 0.694742 -0.508593 -0.508593 0.69474 -0.186158 -0.694752 0.69474 -0.186159 -0.694753 0.69474 0.186159 -0.694753 0.69474 0.186158 -0.694752 0.694742 0.508592 -0.508593 0.694738 0.508595 -0.508595 0.694738 0.694755 -0.186157 0.694747 0.694747 -0.186157 0.694747 -0.694747 -0.186155 0.694738 -0.694755 -0.186159 0.694739 -0.508595 -0.508596 0.694743 -0.508592 -0.508592 0.694741 -0.186158 -0.694752 0.694741 -0.186158 -0.694752 0.694741 0.186158 -0.694752 0.694741 0.186158 -0.694752 0.694743 0.508592 -0.508593 0.694739 0.508595 -0.508595 0.694738 0.694755 -0.186157 0.694747 0.694747 -0.186157 0.694747 -0.694747 -0.186155 0.694738 -0.694755 -0.186159 0.694738 -0.508595 -0.508596 0.694743 -0.508592 -0.508592 0.694742 -0.186158 -0.694751 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694733 0.5086 -0.508598 0.694738 0.508595 -0.508595 0.694738 0.694754 -0.18616 0.694733 0.694759 -0.18616 0.694733 -0.694759 -0.186161 0.694737 -0.694756 -0.186159 0.694736 -0.508598 -0.508596 0.694731 -0.5086 -0.5086 0.694735 -0.186159 -0.694758 0.69474 -0.186159 -0.694753 0.69474 0.186158 -0.694753 0.694739 0.186159 -0.694754 0.694741 0.508593 -0.508594 0.694736 0.508597 -0.508597 0.694737 0.694756 -0.186157 0.694747 0.694747 -0.186157 -0.694733 0.694759 -0.186161 -0.694739 0.694754 -0.186159 -0.694741 0.508595 -0.508592 -0.694731 0.5086 -0.5086 -0.694735 0.186159 -0.694758 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694737 -0.18616 -0.694755 -0.694736 -0.508598 -0.508597 -0.694741 -0.508594 -0.508594 -0.694739 -0.694754 -0.186159 -0.69474 -0.694753 -0.186159 -0.694747 0.694747 -0.186156 -0.694745 0.694748 -0.186157 -0.694743 0.508592 -0.508592 -0.694741 0.508594 -0.508594 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694739 -0.186159 -0.694754 -0.694741 -0.508594 -0.508593 -0.694743 -0.508592 -0.508592 -0.694745 -0.694749 -0.186157 -0.694747 -0.694747 -0.186157 -0.69474 0.694753 -0.186158 -0.694738 0.694755 -0.186159 -0.694738 0.508596 -0.508595 -0.694737 0.508596 -0.508596 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186159 -0.694753 -0.69474 -0.186158 -0.694752 -0.694742 -0.508593 -0.508593 -0.694743 -0.508592 -0.508592 -0.694745 -0.694748 -0.186158 -0.69474 -0.694753 -0.186159 -0.698067 0.69808 -0.159332 -0.698071 0.698076 -0.15933 -0.698071 0.559814 -0.446436 -0.698066 0.559817 -0.44644 -0.698066 0.310675 -0.645124 -0.698069 0.310674 -0.645121 -0.698067 0 -0.716032 -0.698067 0 -0.716032 -0.698066 -0.310676 -0.645124 -0.698069 -0.310673 -0.645121 -0.698071 -0.559813 -0.446437 -0.698065 -0.559819 -0.446439 -0.698065 -0.698082 -0.159333 -0.698067 -0.69808 -0.159333 -0.694747 0.694747 -0.186156 -0.694745 0.694748 -0.186157 -0.694743 0.508592 -0.508592 -0.694743 0.508592 -0.508592 -0.694742 0.186158 -0.694751 -0.69474 0.186159 -0.694753 -0.69474 -0.186159 -0.694753 -0.694742 -0.186158 -0.694751 -0.694743 -0.508592 -0.508592 -0.694743 -0.508592 -0.508592 -0.694745 -0.694749 -0.186157 -0.694747 -0.694747 -0.186157 -0.694733 0.694759 -0.186161 -0.694737 0.694756 -0.186159 -0.694736 0.508598 -0.508596 -0.694731 0.5086 -0.5086 -0.694735 0.186159 -0.694758 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694737 -0.18616 -0.694755 -0.694736 -0.508597 -0.508597 -0.694736 -0.508597 -0.508597 -0.694737 -0.694756 -0.186159 -0.69474 -0.694753 -0.186159 -0.694747 0.694747 -0.186155 -0.694737 0.694756 -0.186159 -0.694736 0.508597 -0.508598 -0.694741 0.508594 -0.508594 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186158 -0.694753 -0.694735 -0.18616 -0.694757 -0.694731 -0.508601 -0.5086 -0.694736 -0.508597 -0.508597 -0.694737 -0.694755 -0.18616 -0.694733 -0.694759 -0.18616 -0.694733 0.694759 -0.186161 -0.694738 0.694755 -0.186159 -0.694739 0.508596 -0.508595 -0.694734 0.508599 -0.508599 -0.694739 0.186159 -0.694754 -0.69474 0.186159 -0.694753 -0.69474 -0.186159 -0.694753 -0.694742 -0.186158 -0.694751 -0.694743 -0.508591 -0.508593 -0.694738 -0.508595 -0.508595 -0.694738 -0.694755 -0.186157 -0.694747 -0.694747 -0.186157 -0.694747 0.694747 -0.186155 -0.694738 0.694755 -0.186159 -0.694739 0.508595 -0.508596 -0.694743 0.508592 -0.508592 -0.694741 0.186158 -0.694752 -0.694741 0.186158 -0.694752 -0.694741 -0.186158 -0.694752 -0.694741 -0.186158 -0.694752 -0.694743 -0.508592 -0.508593 -0.694739 -0.508595 -0.508595 -0.694738 -0.694755 -0.186157 -0.694747 -0.694747 -0.186157 -0.694747 0.694747 -0.186155 -0.694738 0.694755 -0.186159 -0.694738 0.508595 -0.508596 -0.694742 0.508593 -0.508593 -0.69474 0.186158 -0.694752 -0.69474 0.186159 -0.694753 -0.69474 -0.186159 -0.694753 -0.69474 -0.186158 -0.694752 -0.694742 -0.508592 -0.508593 -0.694738 -0.508595 -0.508595 -0.694738 -0.694755 -0.186157 -0.694747 -0.694747 -0.186157 -0.69806 0.698086 -0.159334 -0.698065 0.698082 -0.159332 -0.698066 0.559818 -0.44644 -0.69807 0.559815 -0.446437 -0.698068 0.310674 -0.645122 -0.698066 0.310675 -0.645124 -0.698067 0 -0.716032 -0.698067 0 -0.716032 -0.698066 -0.310675 -0.645124 -0.698068 -0.310674 -0.645122 -0.69807 -0.559814 -0.446437 -0.698066 -0.559818 -0.446439 -0.698065 -0.698082 -0.159333 -0.698073 -0.698073 -0.159333 -0.698074 0.698074 -0.159331 -0.698064 0.698083 -0.159335 -0.698061 0.55982 -0.446443 -0.69807 0.559815 -0.446437 -0.698068 0.310674 -0.645122 -0.698066 0.310675 -0.645124 -0.698067 0 -0.716032 -0.698067 0 -0.716032 -0.698066 -0.310675 -0.645124 -0.698068 -0.310674 -0.645122 -0.69807 -0.559814 -0.446438 -0.698062 -0.559821 -0.446442 -0.698063 -0.698083 -0.159333 -0.69806 -0.698086 -0.159333 -0.705777 0.705738 -0.0617441 -0.705778 0.705737 -0.0617441 -0.705778 0.684294 -0.183356 -0.705779 0.684293 -0.183356 -0.705779 0.642058 -0.299397 -0.705779 0.642058 -0.299396 -0.705778 0.580314 -0.40634 -0.705775 0.580317 -0.406342 -0.705775 0.50094 -0.50094 -0.705778 0.500938 -0.500938 -0.705778 0.40634 -0.580314 -0.705779 0.40634 -0.580313 -0.70578 0.299396 -0.642057 -0.705775 0.299398 -0.642061 -0.705775 0.183357 -0.684296 -0.705774 0.183357 -0.684298 -0.705774 0.0617445 -0.705741 -0.705777 0.0617441 -0.705738 -0.705777 -0.0617442 -0.705738 -0.705775 -0.0617444 -0.705741 -0.705774 -0.183357 -0.684298 -0.705776 -0.183357 -0.684296 -0.705776 -0.299398 -0.642061 -0.705783 -0.299395 -0.642054 -0.705783 -0.406338 -0.58031 -0.705782 -0.406338 -0.580311 -0.705782 -0.500935 -0.500935 -0.705773 -0.500941 -0.500942 -0.705773 -0.580319 -0.406344 -0.705776 -0.580316 -0.406342 -0.705776 -0.642061 -0.299398 -0.70577 -0.642066 -0.2994 -0.705769 -0.684302 -0.183359 -0.705781 -0.684291 -0.183355 -0.705781 -0.705734 -0.0617441 -0.705784 -0.705731 -0.0617438 -0.705581 0.705607 -0.065384 -0.705581 0.705606 -0.0653839 -0.705582 0.681577 -0.193926 -0.705589 0.68157 -0.193923 -0.705589 0.634331 -0.31586 -0.705589 0.634332 -0.31586 -0.705589 0.565492 -0.42704 -0.705593 0.565489 -0.427037 -0.705592 0.477393 -0.523675 -0.705588 0.477396 -0.523678 -0.705588 0.373042 -0.602483 -0.705588 0.373042 -0.602483 -0.705589 0.255984 -0.66077 -0.70559 0.255983 -0.660769 -0.70559 0.130209 -0.696555 -0.705585 0.13021 -0.696559 -0.705587 0 -0.708623 -0.705587 0 -0.708623 -0.705585 -0.13021 -0.696559 -0.70559 -0.130209 -0.696555 -0.70559 -0.255983 -0.660769 -0.705589 -0.255984 -0.66077 -0.705588 -0.373042 -0.602483 -0.705588 -0.373042 -0.602483 -0.705588 -0.477396 -0.523678 -0.705588 -0.477396 -0.523678 -0.705588 -0.565493 -0.427041 -0.705586 -0.565494 -0.427041 -0.705586 -0.634334 -0.315861 -0.705586 -0.634334 -0.315861 -0.705586 -0.681573 -0.193924 -0.705588 -0.681571 -0.193924 -0.705588 -0.705599 -0.0653834 -0.705587 -0.7056 -0.0653835 -0.705587 0.7056 -0.0653835 -0.705588 0.7056 -0.0653835 -0.705588 0.681571 -0.193924 -0.705589 0.68157 -0.193923 -0.705589 0.634331 -0.31586 -0.705588 0.634333 -0.31586 -0.705588 0.565493 -0.42704 -0.705593 0.565489 -0.427038 -0.705592 0.477393 -0.523675 -0.705593 0.477393 -0.523675 -0.705593 0.373039 -0.602479 -0.705591 0.37304 -0.60248 -0.705591 0.255983 -0.660768 -0.705589 0.255983 -0.660769 -0.70559 0.130209 -0.696555 -0.705588 0.130209 -0.696557 -0.705587 0 -0.708623 -0.705587 0 -0.708623 -0.705588 -0.130209 -0.696557 -0.705593 -0.130208 -0.696552 -0.705594 -0.255982 -0.660765 -0.705589 -0.255983 -0.66077 -0.705588 -0.373042 -0.602483 -0.705593 -0.373039 -0.602479 -0.705593 -0.477393 -0.523674 -0.705583 -0.477399 -0.523682 -0.705582 -0.565497 -0.427044 -0.705591 -0.565491 -0.427039 -0.705591 -0.63433 -0.315859 -0.705589 -0.634331 -0.31586 -0.705589 -0.68157 -0.193923 -0.705594 -0.681565 -0.193922 -0.705595 -0.705593 -0.0653828 -0.705594 -0.705594 -0.0653829 -0.705777 0.705738 -0.0617441 -0.705778 0.705737 -0.061744 -0.705778 0.684294 -0.183356 -0.705779 0.684293 -0.183356 -0.705779 0.642058 -0.299396 -0.705779 0.642058 -0.299396 -0.705778 0.580314 -0.40634 -0.705778 0.580314 -0.406341 -0.705778 0.500938 -0.500938 -0.705777 0.500938 -0.500938 -0.705778 0.40634 -0.580314 -0.705773 0.406343 -0.580318 -0.705774 0.299399 -0.642062 -0.705784 0.299394 -0.642053 -0.705784 0.183354 -0.684288 -0.705776 0.183357 -0.684296 -0.705775 0.0617443 -0.70574 -0.705777 0.061744 -0.705738 -0.705777 -0.0617441 -0.705738 -0.705775 -0.0617442 -0.705741 -0.705774 -0.183357 -0.684298 -0.705782 -0.183355 -0.68429 -0.705782 -0.299395 -0.642055 -0.705772 -0.299399 -0.642064 -0.70577 -0.406345 -0.580321 -0.705775 -0.406343 -0.580317 -0.705773 -0.500941 -0.500941 -0.705773 -0.500941 -0.500941 -0.705773 -0.580319 -0.406344 -0.705775 -0.580317 -0.406342 -0.705775 -0.642061 -0.299398 -0.70577 -0.642065 -0.2994 -0.705769 -0.684302 -0.183358 -0.705782 -0.68429 -0.183355 -0.705782 -0.705734 -0.0617434 -0.705784 -0.705731 -0.0617431 -0.705594 0.705594 -0.0653832 -0.705608 0.70558 -0.0653814 -0.705608 0.681552 -0.193918 -0.705616 0.681544 -0.193916 -0.705616 0.634308 -0.315848 -0.705616 0.634308 -0.315848 -0.705615 0.565471 -0.427024 -0.705619 0.565468 -0.427022 -0.705619 0.477375 -0.523655 -0.705606 0.477384 -0.523666 -0.705607 0.373032 -0.602467 -0.705614 0.373028 -0.60246 -0.705615 0.255974 -0.660746 -0.705615 0.255974 -0.660746 -0.705612 0.130205 -0.696533 -0.705614 0.130204 -0.696531 -0.705614 0 -0.708597 -0.705614 0 -0.708597 -0.705614 -0.130204 -0.696531 -0.70561 -0.130205 -0.696535 -0.70561 -0.255976 -0.66075 -0.705615 -0.255974 -0.660746 -0.705614 -0.373028 -0.602461 -0.705614 -0.373028 -0.602461 -0.705614 -0.477378 -0.523659 -0.705616 -0.477377 -0.523657 -0.705617 -0.56547 -0.427023 -0.705615 -0.565471 -0.427024 -0.705616 -0.634308 -0.315848 -0.705613 -0.634311 -0.315849 -0.705613 -0.681547 -0.193917 -0.705614 -0.681546 -0.193917 -0.705614 -0.705573 -0.0653811 -0.705614 -0.705574 -0.0653811 -0.705594 0.705594 -0.0653825 -0.705581 0.705606 -0.0653842 -0.705582 0.681577 -0.193925 -0.70559 0.68157 -0.193923 -0.705589 0.634331 -0.31586 -0.705589 0.634332 -0.31586 -0.705589 0.565492 -0.42704 -0.705593 0.565489 -0.427037 -0.705592 0.477393 -0.523675 -0.705588 0.477396 -0.523678 -0.705588 0.373042 -0.602483 -0.705588 0.373042 -0.602483 -0.705589 0.255984 -0.66077 -0.705588 0.255984 -0.66077 -0.705586 0.130209 -0.696559 -0.705588 0.130209 -0.696557 -0.705587 0 -0.708623 -0.705587 0 -0.708623 -0.705588 -0.130209 -0.696557 -0.705584 -0.13021 -0.696561 -0.705583 -0.255986 -0.660775 -0.705589 -0.255984 -0.66077 -0.705588 -0.373042 -0.602483 -0.705588 -0.373042 -0.602483 -0.705588 -0.477396 -0.523678 -0.70559 -0.477394 -0.523677 -0.70559 -0.565491 -0.427039 -0.705589 -0.565492 -0.42704 -0.705589 -0.634332 -0.31586 -0.705589 -0.634331 -0.31586 -0.70559 -0.68157 -0.193923 -0.705588 -0.681571 -0.193924 -0.705588 -0.705599 -0.0653834 -0.705587 -0.7056 -0.0653835 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.939621 -0.0370023 0.34021 -0.939566 0.0329192 0.340783 -0.938389 0.0498414 0.341967 -0.939692 0.0508149 0.338226 -0.93943 0.0518273 0.338801 -0.939408 0.0518971 0.338849 -0.939889 0.0514323 0.337585 -0.939983 0.0516756 0.337285 -0.939936 0.0515869 0.337432 -0.939771 0.0515727 0.337892 -0.939571 0.0516513 0.338434 -0.939633 -0.0516251 0.338267 -0.939832 -0.0515465 0.337727 -0.94095 -0.048826 0.335005 -0.939692 -0.0507739 0.338232 -0.939956 -0.0515979 0.337372 -0.939978 -0.0516527 0.337304 -0.939693 -0.0502959 0.338302 -0.939472 -0.0517289 0.3387 -0.93945 -0.0517848 0.33875 -0.939566 -0.0329192 0.340783 -0.94337 -0.0336276 0.330033 -0.936007 -0.008472 0.351879 -0.939622 -0.0123554 0.341991 -0.939661 0.0082366 0.342009 -0.937285 0.0125847 0.348336 -0.94337 0.0336276 0.330033 -0.939621 0.0370023 0.34021 -0.939692 0.0502915 0.338303 -0.149348 -0.106913 0.982988 -0.488786 -0.0943295 0.867289 -0.346056 0.101445 0.932713 -0.655058 0.081697 0.751149 -0.850962 0.0567903 0.522148 -0.850961 0.0567906 0.522149 -0.850961 0.0189633 0.524886 -0.850962 0.0189631 0.524885 -0.850962 -0.0189632 0.524885 -0.850961 -0.0189631 0.524886 -0.850961 -0.0567904 0.522149 -0.850962 -0.0567904 0.522148 -0.655066 -0.0816962 0.751142 -0.573444 -0.0811231 0.815218 -0.573333 -0.0295815 0.818788 -0.573333 -0.0295814 0.818788 -0.573333 0.0295815 0.818788 -0.573333 0.0295814 0.818788 -0.573444 0.0811235 0.815218 -0.488788 0.0943293 0.867288 -0.346081 -0.101444 0.932704 -0.202124 -0.100133 0.974227 -0.202086 -0.0353598 0.978729 -0.202085 -0.0353597 0.978729 -0.202085 0.0353598 0.978729 -0.202087 0.0353596 0.978729 -0.202125 0.100134 0.974227 -0.149352 0.106913 0.982987 0.707099 -0.124149 -0.696131 0.671184 -0.0864091 -0.736237 0.706473 -0.0842522 -0.702708 0.706474 0 -0.707739 0.706474 0 -0.707739 0.706524 0.0824922 -0.702864 0.672817 0.0880698 -0.734548 0.707097 0.124148 -0.696133 0.706463 0.084253 0.702717 0.706474 0.0842522 0.702706 0.706474 0 0.707739 0.706474 0 0.707739 0.706474 -0.0842516 0.702706 0.706462 -0.0842537 0.702719 0.694738 -0.059492 -0.716798 0.487523 -0.789654 -0.372516 0.694743 -0.0594929 -0.716794 0.702917 -0.339721 -0.624898 0.494621 -0.495323 -0.714146 0.705015 -0.488448 -0.514172 0.703698 -0.60038 -0.379938 0.7044 -0.677594 -0.211395 0.7044 -0.708707 -0.0394278 0.487516 -0.870122 0.0722198 0.694731 -0.306881 0.650517 0.694739 -0.306876 0.650511 0.702917 -0.537139 0.466251 0.494624 -0.714146 0.495322 0.705019 -0.637638 0.310429 0.7037 -0.695441 0.145492 0.698522 0.0284259 -0.715024 0.698526 0.0284244 -0.71502 0.698526 0.328651 -0.635649 0.698529 0.328649 -0.635647 0.698529 0.56698 -0.436567 0.698521 0.566988 -0.436569 0.698525 0.698536 -0.155274 0.698518 0.698544 -0.155273 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.0827142 -0.996573 0 -0.320169 0.947361 -0.0478499 -0.426168 0.903378 -0.0190432 -0.505304 0.862731 0.0231315 -0.703674 0.710147 -0.00911297 -0.978769 0.204766 0.0343651 -0.933534 0.356838 0.00482461 -0.899099 0.437719 -0.00546098 -0.755169 0.655508 -0.00780455 -0.954593 -0.297812 -1.73839e-05 -0.964852 -0.262796 2.42211e-05 -0.998456 -0.0555475 -1.13849e-05 -0.99845 -0.0556624 -7.57253e-06 -0.994906 0.100809 -0.0167062 -0.638863 -0.769139 0.0109692 -0.767161 -0.641361 -0.0114743 -0.844956 -0.534712 2.39323e-05 -0.880809 -0.473471 1.71224e-05 -0.925106 -0.379708 -0.02653 -0.0368935 -0.998967 0.0157215 -0.438153 -0.898763 1.77919e-05 -0.477625 -0.878564 -6.52248e-06 -0.688738 -0.72501 0 0.0157905 -0.999875 -0.0104434 0.0397216 -0.999156 0.00978841 0.40498 -0.914273 -0.0153998 0.459222 -0.888188 0.00079543 0.619772 -0.784781 -0.00343899 0.759076 -0.650993 -0.0232002 0.792122 -0.609922 -0.000125847 0.877492 -0.479592 0.000222364 0.952566 -0.304333 -0.0289657 0.975765 -0.216898 0 0.995968 -0.0897057 0 0.119043 0.992889 0 0.119043 0.992889 0 0 1 0 0 1 0 -0.119043 0.992889 0 -0.119043 0.992889 0 0.119044 -0.992889 0 0.119044 -0.992889 0 0 -1 0 0 -1 0 -0.119044 -0.992889 0 -0.119044 -0.992889 0.87924 -0.121055 0.460741 0.887081 -0.185211 0.422828 0.954993 -0.213682 0.205741 0.960101 -0.209238 0.18554 0.978435 -0.149538 0.142487 0.978976 -0.14808 0.140276 0.991397 -0.0621429 0.115198 0.990797 -0.0665725 0.117852 0.965171 -0.0742781 -0.250854 0.793208 -0.568248 -0.218894 0.859468 -0.349968 -0.372609 0.839107 -0.377553 -0.391605 0.884192 -0.0696557 -0.461901 0.876484 -0.0783763 -0.475008 0.859291 -0.489209 0.149312 0.938544 -0.241642 0.246463 0.933188 -0.238332 0.268995 0.821645 -0.569779 0.015836 0.847485 -0.528506 -0.0495142 0.891281 -0.452011 -0.0360981 0.947044 -0.277997 -0.160702 0.938318 -0.29897 -0.173711 0.97091 -0.0893294 -0.222156 0.989049 -0.0760298 -0.1265 0.807334 -0.433418 0.400451 0.693243 -0.678476 0.243074 0.770719 -0.636664 0.0255316 0.902134 -0.235403 0.361581 0.887847 -0.179406 0.423723 0.749546 -0.338765 0.5687 0.710136 -0.348521 0.611752 0.275998 -0.862457 0.424255 0.145858 -0.495219 0.856437 0.19781 -0.347225 0.916682 0.147949 -0.314642 0.937609 0.111227 -0.440403 -0.890883 0.0953825 -0.0393399 -0.994663 0.105769 -0.0356721 -0.993751 0.0780537 -0.881572 -0.465552 0.143581 -0.766533 -0.625948 0.177636 -0.754392 -0.631932 0.0973017 -0.642556 -0.760035 0.110867 -0.440522 -0.89087 0.0290627 -0.703331 0.710268 0.134962 -0.922478 0.361691 -0.130543 -0.907299 0.399709 0.156273 -0.981084 0.114252 0.216098 -0.973433 0.075699 0.0506077 -0.997433 -0.0506532 0.143392 -0.942358 -0.302324 0.273417 -0.934787 -0.226753 0.14237 -0.920817 -0.363078 0.354226 -0.819428 0.450623 0.457112 -0.87777 0.143417 0.363182 -0.916296 0.168819 0.490839 -0.853062 -0.177093 0.397291 -0.90236 -0.16705 0.522587 -0.703955 -0.480989 0.442841 -0.751479 -0.489051 0.546612 -0.428534 -0.719426 0.493389 -0.460224 -0.738079 0.553361 -0.0599241 -0.830783 0.546233 -0.063119 -0.835252 0.176404 -0.874052 0.452675 0.302655 -0.949312 0.0848906 0.186317 -0.976233 0.110699 0.325661 -0.907139 -0.26654 0.208487 -0.945147 -0.251456 0.343278 -0.732024 -0.588474 0.241857 -0.771844 -0.588015 0.351508 -0.431632 -0.830745 0.282647 -0.460904 -0.841236 0.345025 -0.0404253 -0.937723 0.33367 -0.0450128 -0.941615 0.879548 -0.119854 0.460469 0.763482 -0.186665 0.618264 0.693959 -0.254637 0.673484 0.651407 -0.241371 0.719312 0.484446 -0.288978 0.825714 0.918295 -0.245878 0.310287 0.901025 -0.259507 0.347578 0.758732 -0.525233 0.385301 0.805306 -0.471418 0.359508 0.700512 -0.607174 0.374998 0.633805 -0.450407 0.628828 0.461121 -0.542724 0.70201 0.425671 -0.332706 0.841493 0.341458 -0.328832 0.880498 0.172202 -0.654674 0.736035 0.179199 -0.655012 0.734062 0.42409 -0.586828 0.689769 0.486868 -0.720618 0.493628 0.502667 -0.715008 0.485891 0.601391 -0.773971 0.198239 0.531872 -0.816939 0.222987 0.642848 -0.762017 -0.0779477 0.575092 -0.815071 -0.0701934 0.685235 -0.640526 -0.346669 0.629206 -0.689858 -0.358046 0.721672 -0.401419 -0.563961 0.685625 -0.432693 -0.585401 0.73994 -0.0647172 -0.669552 0.725679 -0.0744774 -0.68399 0.146154 0.378315 0.914066 0.826272 0.560144 0.0592799 0.651438 0.241323 0.719299 0.880896 0.17383 0.440233 0.992268 0.0783359 0.0962662 0.992327 0.0396653 0.117107 0.976265 0.16555 0.139644 0.978908 0.147595 0.141265 0.963202 0.200355 0.179163 0.942932 0.258264 0.210185 0.902135 0.21952 0.371433 0.895798 0.222182 0.384943 0.919327 0.240404 0.311518 0.851016 0.078534 0.519233 0.740543 0.603853 0.294886 0.783617 0.56866 0.250141 0.707952 0.523632 0.473934 0.912305 0.248564 0.325446 0.939734 0.234481 0.248833 0.785904 0.611841 0.0894745 0.847487 0.528505 -0.0494837 0.79326 0.568166 -0.218919 0.856964 0.366096 -0.362748 0.84421 0.360291 -0.396863 0.884163 0.0782945 -0.460572 0.877674 0.0700827 -0.474106 0.923013 0.269006 0.275104 0.960832 0.19278 0.199095 0.891329 0.451918 -0.036083 0.944823 0.289803 -0.152721 0.941841 0.285624 -0.177073 0.97092 0.0893763 -0.222097 0.965173 0.0743162 -0.250836 0.0802676 0.878253 -0.471411 0.171971 0.938989 -0.297869 0.146967 0.759143 -0.634115 0.158083 0.75545 -0.635849 0.0929163 0.622453 -0.777122 0.146474 0.440916 -0.885516 0.0592899 0.406809 -0.911587 0.10617 0.0177461 -0.99419 0.150244 0.0367853 -0.987964 0.33401 0.0403271 -0.941707 0.138209 0.947446 -0.28852 0.0626534 0.994544 -0.0834074 0.205196 0.975909 0.074142 0.11931 0.98658 0.111467 0.0122604 0.909159 0.416268 0.365935 0.872493 0.323803 0.179963 0.874432 0.450535 0.094129 0.852396 0.514354 0.0328706 0.713087 0.700305 0.190232 0.65539 0.730942 0.0915775 0.35563 0.930129 0.341493 0.328769 0.880508 0.693996 0.254604 0.673459 0.714754 0.392982 0.578526 0.412194 0.563071 0.716273 0.486908 0.720649 0.493543 0.354175 0.819489 0.450553 0.447642 0.875906 0.180017 0.378524 0.915785 0.134378 0.48014 0.865893 -0.140337 0.413095 0.888246 -0.200925 0.514055 0.727613 -0.454232 0.45519 0.727767 -0.512988 0.542696 0.451685 -0.70814 0.499642 0.43769 -0.747519 0.553287 0.0633262 -0.83058 0.546658 0.0595624 -0.835235 0.34468 0.0458793 -0.937599 0.288263 0.436761 -0.852141 0.346231 0.457015 -0.819306 0.253706 0.746933 -0.614592 0.33285 0.758354 -0.560456 0.224047 0.930951 -0.28833 0.313038 0.922054 -0.22765 0.201525 0.976704 0.0737403 0.291648 0.948459 0.123959 0.187833 0.885527 0.424924 0.269281 0.849601 0.453505 0.179191 0.654927 0.73414 0.463848 0.5709 0.677435 0.425697 0.332649 0.841502 0.484439 0.288931 0.825735 0.875354 0.113817 0.469894 0.889584 0.176743 0.421191 0.689713 0.389162 0.610614 0.745686 0.510385 0.428322 0.502634 0.715061 0.485847 0.59326 0.771102 0.23118 0.546278 0.815292 0.192038 0.633758 0.772244 -0.0446111 0.590004 0.801195 -0.099912 0.678251 0.660531 -0.321986 0.640939 0.667856 -0.378372 0.718695 0.42141 -0.553075 0.691731 0.412409 -0.592813 0.739911 0.074387 -0.66858 0.727069 0.0648234 -0.683497 0.572898 0 0.819627 0.850725 0.0636532 0.521743 0.879516 -0.057632 0.472367 0.654678 -0.089986 0.750532 0.764993 -0.0766686 0.639458 0.845143 -0.0602367 0.531135 0.851114 -0.0323968 0.52398 0.850696 0 0.525657 0.850696 0 0.525657 0.851114 0.0323833 0.523981 0.345767 -0.111701 0.931648 0.488418 -0.103879 0.866405 0.149219 -0.117711 0.981773 0.201908 -0.113124 0.972849 0.201869 0 0.979413 0.844346 0.0637834 0.531988 0.654705 0.0899832 0.750509 0.573019 0.0930682 0.81424 0.488411 0.10388 0.866408 0.345795 0.1117 0.931638 0.573019 -0.0930691 0.81424 0.572898 0 0.819627 0.201869 0 0.979413 0.201908 0.113123 0.97285 0.149214 0.117711 0.981774 0.340892 -0.111913 -0.933417 0.994035 0 0.109062 0.994036 0.0132062 0.108246 0.994251 0.0127471 0.106317 0.991754 -0.0155211 0.127214 0.996676 -0.00502731 0.0813173 0.65868 0 -0.752423 0.931791 0 -0.362996 0.994046 -0.0110552 0.108403 0.993745 0.0132937 -0.110876 0.971837 0.0280534 -0.233979 0.994056 0.00671749 0.108663 0.994035 0 0.109062 0.931791 0 -0.362996 0.931639 0.0497305 -0.359966 0.558445 -0.112612 -0.821862 0.739311 -0.0801601 -0.668576 0.931791 -0.0432126 -0.360415 0.888072 -0.0662196 -0.45491 0.971843 -0.0280504 -0.233955 0.237284 0 -0.97144 0.237285 -0.115644 -0.964532 0.108126 -0.132819 -0.985225 0.887837 0.0547792 -0.456887 0.739296 0.080162 -0.668592 0.658468 0.0962 -0.746436 0.558106 0.0987789 -0.823869 0.34089 0.111913 -0.933418 0.65868 -0.0895714 -0.747073 0.65868 0 -0.752423 0.237284 0 -0.97144 0.237188 0.12225 -0.963741 0.108039 0.118347 -0.987077 0.939515 -0.0414811 0.339987 0.939602 -0.0626284 0.33649 0.939492 -0.0628018 0.336766 0.939578 -0.0625079 0.336581 0.939697 -0.0614292 0.336445 0.939842 -0.0625223 0.335839 0.939863 -0.0625588 0.335774 0.939744 -0.0625591 0.336106 0.939508 0.0414811 0.340006 0.939901 0.0626166 0.335658 0.939805 0.0623805 0.335968 0.93969 0.0614388 0.336463 0.939697 0.0616385 0.336407 0.939544 0.0626372 0.336649 0.939484 0.0628419 0.336779 0.939529 0.0627211 0.336677 0.939646 0.0626077 0.336373 0.939778 0.062543 0.336016 0.939515 0.0414789 0.339987 0.939511 0.0414792 0.339998 0.939694 0.0211031 0.341366 0.939693 0.0210973 0.341367 0.939497 0 0.342556 0.939497 0 0.342556 0.939693 -0.0211045 0.341367 0.939693 -0.0211061 0.341367 0.939511 -0.0414814 0.339999 0.939508 -0.041483 0.340006 0.93969 -0.0616668 0.336421 -0.0420618 0.715806 0.697032 -0.00151248 0.859844 0.510554 0.000294159 0.895427 0.445209 -0.00686617 0.973193 0.229888 -0.056786 0.948759 0.310858 0 0.994888 0.10098 0.0106883 0.76743 0.641043 -0.00938825 0.399469 0.916699 0 0.385284 0.922798 0.697431 0.697457 0.164753 0.697437 0.697452 0.16475 0.697439 0.550006 0.459426 0.69744 0.550005 0.459425 0.697438 0.28629 0.656976 0.697435 0.28629 0.65698 -0.000652311 -0.880809 0.473471 0 -0.999557 0.0297563 0.00490114 -0.971865 0.235489 0.0463859 -0.942036 0.33229 0.00614534 -0.989147 0.146803 0 -0.372939 0.927856 0.0140691 -0.34399 0.938868 0.00071517 -0.545215 0.838296 -0.00557459 -0.756278 0.654227 0.0339606 -0.69829 0.715009 0.00403645 -0.836914 0.547319 -0.696944 -0.696957 0.168877 -0.69695 -0.696952 0.168874 -0.696954 -0.542347 0.469164 -0.696947 -0.542351 0.46917 -0.696946 -0.267443 0.665387 -0.696947 -0.267443 0.665386 -0.698865 -0.572324 -0.428992 -0.698861 -0.572327 -0.428993 -0.698862 -0.69888 -0.152181 -0.698864 -0.698877 -0.152181 -0.698865 -0.0499934 -0.713504 -0.698864 -0.049994 -0.713505 -0.698862 -0.342139 -0.628118 -0.819612 -0.233964 -0.52297 -0.70602 -0.420126 -0.570113 -0.458483 0.816371 -0.351187 -0.69474 0.0842102 -0.714315 -0.694739 0.0842102 -0.714315 -0.705701 0.319651 -0.632305 -0.754938 0.332934 -0.564999 -0.624884 0.520558 -0.581841 -0.705015 0.505915 -0.496995 -0.703697 0.613141 -0.358982 -0.704396 0.684494 -0.187867 -0.704397 0.70965 -0.0149301 -0.458493 0.882586 0.104045 -0.69474 0.284228 0.66072 -0.694738 0.28423 0.660721 -0.702912 0.520721 0.484526 -0.466761 0.708857 0.528825 -0.705015 0.626539 0.33227 -0.703696 0.690007 0.169415 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 0.0510933 -0.706189 -0.706177 0.0510934 -0.70619 -0.706177 -0.0510933 -0.70619 -0.706178 -0.0510932 -0.706188 0 -0.0961511 -0.995367 -0.0420201 -0.0720983 -0.996512 0 -0.0240723 -0.99971 0 0.0721621 -0.997393 -0.0629305 0.0959606 -0.993394 0 0.0240723 -0.99971 -0.706178 -0.0510935 0.706188 -0.706183 -0.0510933 0.706183 -0.706183 0.0510931 0.706183 -0.706177 0.0510937 0.706189 0 0.117079 -0.993123 0 0.286297 0.958141 0.032319 0.394961 0.918129 0.0129608 0.474312 0.880261 -0.0156222 0.679006 0.733967 0.00369083 0.732088 0.681201 -0.00326066 0.883449 0.468516 -0.0251512 0.924097 0.38133 3.44646e-05 0.964338 -0.264674 -3.98677e-05 0.999992 0.00394165 -0.00662213 0.999757 -0.0210336 0.00506819 0.971144 0.238442 0.00404005 0.713362 -0.700784 -0.00868958 0.782894 -0.622095 0.00792534 0.862944 -0.505237 -0.00305018 0.908261 -0.418393 0.00554929 0.97088 -0.239503 0.0225875 0.0612255 -0.997868 -0.0121227 0.446876 -0.894514 0.00323321 0.507676 -0.861542 -4.50728e-06 0.622117 -0.782925 -5.91902e-07 0.658931 -0.752203 0 -0.0408904 -0.999164 0.00839486 -0.0698937 -0.997519 -0.00845319 -0.427836 -0.903817 0.00838051 -0.478327 -0.878142 -0.000413223 -0.63968 -0.768641 0.0024586 -0.775541 -0.631293 0.0133769 -0.800097 -0.599722 -0.000426876 -0.890393 -0.455193 0.00125649 -0.960534 -0.278161 0.0176834 -0.976951 -0.21273 0 -0.997364 -0.0725658 -0.994042 -0.0104801 0.10849 -0.971841 0.022657 -0.234546 -0.658919 0 -0.752214 -0.108084 -0.0955878 -0.989536 -0.558296 -0.0797713 -0.825798 -0.341054 -0.0903866 -0.935688 -0.237327 -0.101702 -0.966091 -0.237623 -0.0233828 -0.971076 -0.153992 0 -0.988072 -0.237623 0.0233828 -0.971076 -0.237428 0.0934018 -0.966904 -0.887885 -0.0442361 -0.457934 -0.739466 -0.0647288 -0.670075 -0.108163 0.113779 -0.987601 -0.341054 0.0903866 -0.935688 -0.65892 0.0723265 -0.748728 -0.558603 0.0971742 -0.823723 -0.739471 0.0647283 -0.670069 -0.971845 -0.0226554 -0.23453 -0.931696 -0.0430565 -0.360677 -0.931861 0 -0.362816 -0.658697 -0.0806447 -0.748074 -0.658919 0 -0.752214 -0.931861 0 -0.362816 -0.931861 0.0348854 -0.361135 -0.888089 0.0586507 -0.455914 -0.994042 0.01048 0.10849 -0.994042 0.0104801 0.108491 -0.994053 0.00262192 0.10887 -0.994978 0 0.100096 -0.994053 -0.00262121 0.10887 -0.994042 -0.01048 0.108491 0 -0.108126 0.994137 0.0635019 -0.0720167 0.99538 0 -0.0361046 0.999348 0 0.0361046 0.999348 0.063502 0.0720167 0.99538 0 0.108126 0.994137 -0.738155 0.475134 0.47893 -0.933086 0.230114 0.276402 -0.885798 0.161986 0.434883 -0.902767 0.202842 0.379298 -0.900881 0.227544 0.369645 -0.893729 0.187211 0.407676 -0.982603 0.133126 0.129496 -0.968984 0.17737 0.172075 -0.959181 0.205788 0.193969 -0.978164 0.142367 0.151415 -0.993506 0.0428537 0.105404 -0.993503 0.0486698 0.102875 -0.955077 0.207183 0.211905 -0.937213 0.235986 0.256793 -0.812787 0.568684 0.126394 -0.759742 0.590401 0.272431 -0.532645 0.809175 0.248042 -0.600333 0.766828 0.227101 -0.364135 0.910244 0.197133 -0.456016 0.872351 0.176218 -0.187401 0.972117 0.140957 -0.145509 0.463474 0.874082 -0.172302 0.630416 0.756893 -0.88495 0.167832 0.434391 -0.71267 0.352001 0.606793 -0.697723 0.384248 0.604596 -0.461109 0.520025 0.718994 -0.423352 0.561772 0.710764 -0.179688 0.630605 0.755016 -0.275273 0.846459 0.455777 -0.918223 0.236236 0.317898 -0.916087 0.238126 0.322616 -0.77136 0.552386 0.316028 -0.722808 0.518468 0.45688 -0.503335 0.699094 0.50786 -0.487235 0.705169 0.515111 -0.353651 0.803343 0.479136 -0.177298 0.859163 0.480005 -0.30151 0.945813 0.120543 -0.175108 0.78184 -0.598384 -0.0983751 0.662725 -0.742373 -0.10052 0.626087 -0.773247 -0.274906 0.941154 -0.196609 -0.876428 0.0946336 -0.472142 -0.884046 0.0865017 -0.459325 -0.725698 0.0976597 -0.681047 -0.73982 0.0884963 -0.666959 -0.546207 0.0917364 -0.832612 -0.55329 0.0887387 -0.828249 -0.333632 0.0777084 -0.939495 -0.344985 0.0734669 -0.935729 -0.10576 0.0695627 -0.991956 -0.121708 0.0644777 -0.99047 -0.0684751 0.909363 -0.410329 -0.148738 0.777067 -0.611592 -0.342311 0.753962 -0.560682 -0.242339 0.790196 -0.562905 -0.521628 0.722079 -0.45443 -0.443216 0.766668 -0.464521 -0.684278 0.653987 -0.32259 -0.629471 0.700834 -0.335556 -0.792137 0.577208 -0.198368 -0.839076 0.39042 -0.378847 -0.858959 0.364388 -0.359736 -0.685631 0.451989 -0.570628 -0.721165 0.422443 -0.549056 -0.493427 0.484563 -0.722308 -0.546158 0.454933 -0.703382 -0.282718 0.488573 -0.82545 -0.351093 0.461927 -0.814468 -0.0853922 0.469146 -0.878983 -0.151904 0.450626 -0.879694 -0.147949 0.280634 0.948344 -0.205597 0.315105 0.92652 -0.341411 0.298095 0.891391 -0.425002 0.300899 0.853717 -0.484352 0.260926 0.835057 -0.687666 0.203979 0.696784 -0.647367 0.260966 0.71611 -0.87021 0.0461699 0.490513 -0.85001 0.125874 0.511506 -0.029029 0.678119 0.734378 -0.135882 0.911277 0.388729 0.182428 0.890742 0.416291 -0.290351 0.956118 0.0391852 -0.0131399 0.996437 0.0833128 -0.14355 0.951985 -0.270404 -0.324402 0.917016 -0.232044 -0.209393 0.952354 -0.221759 -0.489625 0.859819 -0.144841 -0.39806 0.906821 -0.138653 -0.641641 0.765424 -0.049219 -0.575725 0.816424 -0.0446459 -0.805194 0.588818 0.0703992 -0.849343 0.526436 -0.0385009 -0.891409 0.452681 -0.0216764 -0.946586 0.285121 -0.150603 -0.938296 0.304601 -0.163763 -0.97139 0.0819946 -0.222887 -0.963017 0.0999702 -0.250208 -0.484353 -0.260873 0.835073 -0.146449 -0.336548 0.930209 -0.546586 -0.0885399 -0.832709 -0.824706 -0.559534 0.0823546 -0.942265 -0.255155 0.216871 -0.971801 -0.164043 0.16939 -0.978816 -0.147886 0.141594 -0.989309 -0.072105 0.126759 -0.993672 -0.0431599 0.103696 -0.851107 -0.0711761 0.520145 -0.873464 -0.155216 0.461485 -0.889399 -0.177383 0.421312 -0.901406 -0.20621 0.380717 -0.895308 -0.209764 0.392968 -0.91823 -0.230254 0.322238 -0.651394 -0.216095 0.727316 -0.692768 -0.226543 0.684653 -0.714403 -0.371576 0.592925 -0.741728 -0.593928 0.31159 -0.782193 -0.559875 0.273338 -0.708892 -0.508747 0.488518 -0.911959 -0.238507 0.333834 -0.938588 -0.227486 0.259427 -0.786963 -0.607646 0.107031 -0.849347 -0.526428 -0.0385155 -0.792187 -0.577123 -0.198415 -0.856723 -0.378361 -0.350525 -0.843569 -0.375408 -0.384004 -0.884012 -0.0941063 -0.457895 -0.877483 -0.0872927 -0.471597 -0.921889 -0.264423 0.2832 -0.959989 -0.184344 0.210804 -0.891441 -0.452617 -0.0217047 -0.944652 -0.295065 -0.143418 -0.941309 -0.293308 -0.167058 -0.970892 -0.0954306 -0.219686 -0.965065 -0.0835444 -0.248336 -0.139221 -0.955829 -0.258859 -0.171159 -0.948762 -0.265621 -0.0818058 -0.891721 -0.445131 -0.148642 -0.777018 -0.611677 -0.148778 -0.77698 -0.611692 -0.0946757 -0.643504 -0.759565 -0.146664 -0.470704 -0.870016 -0.032215 -0.429114 -0.902676 -0.106328 -0.0431121 -0.993396 -0.17455 -0.0711845 -0.982072 -0.333938 -0.0734569 -0.939728 -0.183627 -0.857153 0.481217 -0.234217 -0.85853 0.456146 -0.0680631 -0.995624 -0.0640341 -0.154498 -0.98682 0.0481401 -0.22623 -0.96771 0.111165 -0.114439 -0.98048 0.159881 -0.0516845 -0.9382 0.342214 -0.091361 -0.828601 0.552335 -0.0352487 -0.6947 0.718436 -0.511635 -0.446285 0.734207 -0.553196 -0.0918056 -0.827977 -0.499058 -0.464534 -0.731538 -0.542568 -0.47552 -0.69246 -0.454271 -0.746177 -0.48668 -0.513926 -0.742488 -0.429642 -0.412114 -0.895285 -0.169192 -0.480013 -0.870127 -0.111654 -0.377657 -0.910829 0.166631 -0.447575 -0.869548 0.208718 -0.353594 -0.803412 0.479062 -0.48727 -0.705208 0.515024 -0.412918 -0.540098 0.733344 -0.463501 -0.545681 0.69814 -0.425024 -0.300841 0.853727 -0.344666 -0.0784363 -0.935443 -0.287818 -0.467046 -0.83608 -0.346266 -0.484578 -0.803296 -0.253009 -0.768586 -0.58759 -0.332869 -0.776783 -0.534609 -0.223308 -0.94075 -0.255192 -0.313065 -0.929137 -0.196709 -0.200954 -0.973627 0.108021 -0.291661 -0.943806 0.155445 -0.187464 -0.870198 0.455646 -0.269264 -0.834036 0.48154 -0.179506 -0.630086 0.755493 -0.178556 -0.630731 0.75518 -0.112027 -0.322935 0.939767 -0.341441 -0.298029 0.891402 -0.87091 -0.0935875 0.48245 -0.89297 -0.155792 0.422296 -0.690171 -0.369813 0.622015 -0.744778 -0.49429 0.448311 -0.503285 -0.699162 0.507816 -0.593144 -0.763301 0.256031 -0.545227 -0.808655 0.220919 -0.633578 -0.773435 -0.0194148 -0.588806 -0.805131 -0.0712152 -0.677989 -0.671067 -0.3 -0.639889 -0.681954 -0.354232 -0.718477 -0.440042 -0.53866 -0.691091 -0.434098 -0.577886 -0.739778 -0.0971357 -0.665802 -0.726934 -0.0890133 -0.680914 0 -0.393349 -0.919389 0 -0.393349 -0.919389 0 -0.5 -0.866025 0 -0.5 -0.866025 0 -0.599539 -0.800345 0 -0.599539 -0.800345 0 -0.538797 -0.842435 0 0.196409 0.980522 -0.0323327 0.119854 0.992265 -0.00477477 -0.00576553 0.999972 0.0109494 -0.255035 0.96687 -0.00691322 -0.290661 0.956801 0.00189162 -0.496297 0.868151 0.023351 -0.630966 0.775459 -0.0207659 -0.701267 0.712596 -0.00129376 -0.811262 0.584682 0.00323856 -0.892369 0.451295 -0.0314886 -0.940742 0.337658 -0.00693383 -0.967135 0.254171 0.000741183 -0.93843 -0.34547 -0.00314447 -0.984906 -0.173062 -0.0274194 -0.994203 -0.103966 -0.0021294 -0.999543 0.0301679 0.000708695 -0.991009 0.133793 -0.00398586 -0.532024 -0.84672 0.0033929 -0.828527 -0.559939 2.18481e-05 -0.8328 -0.553574 9.57502e-07 -0.935107 -0.354366 0 0.59954 0.800345 0 0.59954 0.800345 0 0.5 0.866026 0 0.5 0.866026 0 0.393349 0.919389 0 0.393349 0.919389 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.999446 0.0332947 -0.0196824 0.968776 0.247155 0.000313942 0.976538 0.215347 -0.00031759 0.795383 0.606107 0 0.795066 0.606523 0.698664 0.698664 0.15407 0.698648 0.698677 0.154079 0.698651 0.569067 0.433647 0.698658 0.569063 0.433641 9.6556e-06 -0.765336 0.643631 0.0232831 -0.885756 0.463568 -0.0284632 -0.81123 0.584034 0.0225715 -0.971146 0.237417 0.0214617 -0.970217 0.241283 0 -0.99706 0.0766229 -2.27628e-05 -0.613025 0.790064 -0.0119868 -0.646516 0.762806 0.0084705 -0.431556 0.902046 1.06947e-05 -0.469369 0.883002 -2.48671e-05 -0.242395 0.970178 -0.00966416 -0.20545 0.97862 0.0146149 0.134979 0.990741 0 0.171891 0.985116 -0.696414 0.0968757 0.711071 -0.696412 0.0968768 0.711074 -0.703789 -0.172199 0.689223 -0.504592 -0.297729 0.810398 -0.696408 -0.696434 0.173196 -0.696421 -0.696422 0.173189 -0.703796 -0.576533 0.415067 -0.504597 -0.642641 0.576536 -0.705066 -0.458505 0.540976 -0.705064 -0.33285 0.626175 0 -0.580953 -0.813937 -0.0420209 -0.560695 -0.826956 0 -0.520701 -0.853739 0 -0.436202 -0.899849 -0.0629317 -0.413592 -0.908285 0 -0.479009 -0.87781 -0.706178 0.308846 0.637124 -0.706176 0.308847 0.637125 -0.706177 0.397343 0.586031 -0.706174 0.397345 0.586034 0 -0.395167 -0.918609 0 0.727016 0.686621 0.0323169 0.801111 0.597643 0.0129613 0.850891 0.525183 -0.0156229 0.955019 0.296131 0.0036916 0.974608 0.223888 -0.00325972 0.999347 -0.0359859 -0.0251489 0.990956 -0.13181 3.42307e-05 0.702806 -0.711382 -4.01632e-05 0.867989 -0.496584 -0.00662204 0.855298 -0.518094 0.00506805 0.960259 -0.279065 0.0225878 -0.445911 -0.894792 -0.0133913 -0.0455452 -0.998873 -1.39755e-05 0.00889083 -0.999961 1.42271e-06 0.194579 -0.980887 0.00404021 0.267394 -0.963579 -0.00869013 0.36696 -0.930196 0.00792445 0.494713 -0.86902 -0.00305094 0.577378 -0.816471 0.00554851 0.721054 -0.692856 0 -0.497962 -0.867199 0.0125113 -0.546102 -0.837625 -0.000323747 -0.662137 -0.749382 0.00111473 -0.827686 -0.561191 0.00391774 -0.822473 -0.568791 -0.00423714 -0.980333 -0.197306 0 -0.977774 -0.209662 -0.994042 0.0451692 0.0991953 -0.971841 -0.097652 -0.214452 -0.658921 -0.376106 -0.651435 -0.108084 -0.57755 -0.809169 -0.558292 -0.481985 -0.675279 -0.341051 -0.546122 -0.765137 -0.237322 -0.571123 -0.785809 -0.237618 -0.505788 -0.829287 -0.153991 -0.494036 -0.855696 -0.237617 -0.46529 -0.852669 -0.237423 -0.402564 -0.884066 -0.887884 -0.267278 -0.374467 -0.73947 -0.391091 -0.547934 -0.108169 -0.395266 -0.912176 -0.341048 -0.389568 -0.855525 -0.658921 -0.311727 -0.68458 -0.558605 -0.327706 -0.761951 -0.739472 -0.278978 -0.61266 -0.971845 -0.136884 -0.19178 -0.931696 -0.217627 -0.290828 -0.931861 -0.181408 -0.314208 -0.658697 -0.443878 -0.607529 -0.658919 -0.376107 -0.651436 -0.931861 -0.181408 -0.314208 -0.931861 -0.150356 -0.330195 -0.888089 -0.177165 -0.424159 -0.994042 0.0633215 0.0887157 -0.994042 0.0633207 0.0887149 -0.994053 0.0567053 0.0929729 -0.994978 0.0500477 0.0866851 -0.994053 0.052165 0.095595 -0.994042 0.0451692 0.0991955 0 0.403429 0.915011 0.0635019 0.435322 0.898033 0 0.468406 0.883513 0 0.530942 0.847408 0.0635014 0.560058 0.826016 0 0.590708 0.806885 -0.0684606 0.582364 -0.81004 -0.0983939 0.202782 -0.974268 -0.738156 0.650944 0.177193 -0.933087 0.337481 0.124316 -0.885799 0.357725 0.295624 -0.902766 0.36532 0.227056 -0.90088 0.381882 0.20635 -0.893726 0.365962 0.259472 -0.982604 0.180034 0.045582 -0.968982 0.239653 0.0603374 -0.95918 0.275205 0.0650882 -0.978164 0.199001 0.0599466 -0.993506 0.0898146 0.0698561 -0.993503 0.093587 0.0647585 -0.955075 0.285383 0.0799276 -0.937215 0.332761 0.104396 -0.812787 0.55569 -0.174889 -0.759741 0.647518 -0.0592756 -0.532648 0.824784 -0.189784 -0.60033 0.777644 -0.186746 -0.364134 0.886859 -0.284406 -0.455997 0.843596 -0.283572 -0.187411 0.912356 -0.363983 -0.145511 0.838414 0.52525 -0.172306 0.924401 0.340284 -0.884951 0.362539 0.292278 -0.712671 0.608235 0.3495 -0.697722 0.635067 0.331472 -0.461104 0.809855 0.362655 -0.423346 0.841894 0.334654 -0.179707 0.923624 0.338561 -0.275289 0.960939 -0.0285123 -0.91823 0.363522 0.157179 -0.916085 0.367535 0.160334 -0.771362 0.636391 -0.00249475 -0.722813 0.67744 0.136441 -0.503329 0.859366 0.0902773 -0.487228 0.868253 0.0935193 -0.353626 0.935293 0.0132675 -0.17732 0.984055 -0.0138826 -0.301522 0.879366 -0.36851 -0.274898 0.71676 -0.640848 -0.876427 -0.154116 -0.456206 -0.884046 -0.15475 -0.441039 -0.725702 -0.255946 -0.63863 -0.73982 -0.256838 -0.621853 -0.546201 -0.336859 -0.766936 -0.553286 -0.337274 -0.761657 -0.333631 -0.402449 -0.852482 -0.344991 -0.40424 -0.847096 -0.105758 -0.435736 -0.89384 -0.121701 -0.439395 -0.890012 -0.145528 0.376723 -0.914823 -0.171014 0.368528 -0.913751 -0.342321 0.372605 -0.862544 -0.242332 0.402878 -0.88259 -0.521629 0.398124 -0.754587 -0.443216 0.431695 -0.78562 -0.684279 0.405075 -0.606364 -0.629468 0.439165 -0.641018 -0.792141 0.400693 -0.460388 -0.839076 0.148693 -0.523299 -0.858962 0.135703 -0.493729 -0.685627 0.10612 -0.720176 -0.721167 0.0913166 -0.686717 -0.493424 0.0584876 -0.86782 -0.546158 0.0422897 -0.836614 -0.282729 0.0103903 -0.959144 -0.351084 -0.00718979 -0.936316 -0.0853842 -0.0331951 -0.995795 -0.106832 -0.0384882 -0.993532 -0.147952 0.717212 0.680968 -0.205593 0.736152 0.644835 -0.341435 0.703848 0.622912 -0.424997 0.687445 0.588895 -0.484347 0.643497 0.592722 -0.687666 0.525041 0.501445 -0.647362 0.584063 0.489686 -0.870212 0.285236 0.401711 -0.850011 0.364763 0.380039 -0.0290216 0.954458 0.29693 -0.135884 0.983553 -0.118991 0.182442 0.979548 -0.0848528 -0.29035 0.847614 -0.444125 -0.0131315 0.904596 -0.426068 -0.143542 0.689241 -0.710171 -0.324412 0.678136 -0.65946 -0.209401 0.713884 -0.668223 -0.489618 0.672207 -0.555349 -0.398054 0.716004 -0.57349 -0.641641 0.638268 -0.425337 -0.57573 0.684718 -0.446874 -0.805194 0.545131 -0.233443 -0.849343 0.436655 -0.296563 -0.891407 0.381197 -0.245118 -0.946585 0.171622 -0.27299 -0.938297 0.18191 -0.294123 -0.97139 -0.0404329 -0.234022 -0.963018 -0.0385255 -0.26667 -0.146447 0.173643 0.973859 -0.82471 -0.443387 0.351086 -0.651396 0.176514 0.737921 -0.942264 -0.112534 0.315395 -0.9718 -0.0573704 0.22872 -0.978816 -0.0572761 0.196567 -0.989309 0.000934825 0.145829 -0.993672 0.0144705 0.111383 -0.851106 0.198433 0.486048 -0.873462 0.0963221 0.477269 -0.889404 0.0570223 0.453552 -0.901407 0.011774 0.432813 -0.895306 0.0148227 0.445204 -0.91823 -0.0382902 0.394192 -0.741736 -0.358559 0.5668 -0.782192 -0.348196 0.516657 -0.708894 -0.196331 0.677439 -0.911959 -0.0396392 0.408362 -0.938587 -0.0672969 0.338418 -0.786958 -0.472722 0.396523 -0.849347 -0.475159 0.229857 -0.792185 -0.599014 0.116726 -0.856721 -0.502936 -0.114389 -0.84357 -0.517115 -0.144852 -0.884011 -0.310445 -0.349497 -0.877483 -0.311395 -0.36477 -0.921892 -0.0873926 0.377462 -0.959989 -0.0542427 0.274734 -0.891441 -0.40283 0.207511 -0.944653 -0.327241 0.0233272 -0.941309 -0.337539 0.0019762 -0.970892 -0.192488 -0.142536 -0.965064 -0.196519 -0.173294 -0.333935 -0.533479 -0.777102 -0.105763 -0.556286 -0.824233 -0.307203 -0.478602 -0.822537 -0.0132432 -0.553147 0.832978 -0.283643 -0.56385 0.775641 -0.1157 -0.661343 -0.741106 -0.0793929 -0.82315 -0.562247 -0.182733 -0.839229 -0.512155 -0.0109239 -0.977952 -0.208545 -0.144765 -0.979244 -0.141857 -0.0752895 -0.993507 0.0852953 -0.207745 -0.946237 0.247947 -0.181752 -0.948963 0.257752 0.0831626 -0.826494 0.556769 -0.375206 -0.79755 0.472371 -0.105892 -0.753015 0.649427 -0.068894 -0.424264 0.902914 -0.100125 -0.19843 0.974987 -0.178502 -0.16832 0.969436 -0.112021 0.190214 0.975331 -0.341454 0.1876 0.920986 -0.692767 0.146136 0.7062 -0.7144 -0.0253315 0.699278 -0.412916 -0.101065 0.905144 -0.487265 -0.353213 0.798632 -0.353583 -0.456244 0.816591 -0.447567 -0.6487 0.615526 -0.377659 -0.705485 0.59972 -0.480016 -0.809376 0.338371 -0.41212 -0.859932 0.301122 -0.513933 -0.85783 -0.000829674 -0.45426 -0.889554 -0.0483964 -0.542561 -0.758045 -0.361933 -0.499054 -0.768069 -0.401267 -0.553198 -0.493494 -0.671145 -0.546586 -0.493032 -0.676878 -0.344663 -0.535649 -0.7709 -0.287818 -0.822512 -0.490544 -0.346266 -0.821304 -0.453386 -0.253009 -0.95941 -0.124577 -0.332861 -0.940021 -0.074601 -0.223298 -0.942311 0.249377 -0.313053 -0.903014 0.294217 -0.200947 -0.789179 0.580359 -0.29166 -0.739639 0.606522 -0.187458 -0.525792 0.8297 -0.269272 -0.481521 0.834045 -0.179694 -0.168497 0.969185 -0.463506 -0.123506 0.877444 -0.42503 0.166328 0.889767 -0.484354 0.191613 0.853631 -0.870906 0.160183 0.464612 -0.892969 0.0762284 0.443617 -0.690168 -0.00925971 0.72359 -0.744776 -0.203914 0.635395 -0.503297 -0.351579 0.789357 -0.593151 -0.533015 0.60338 -0.54522 -0.589865 0.595646 -0.633569 -0.67953 0.369903 -0.588802 -0.732874 0.340893 -0.677986 -0.731164 0.0757219 -0.639896 -0.767699 0.0342098 -0.718484 -0.650412 -0.246466 -0.691094 -0.66488 -0.283415 -0.739777 -0.417022 -0.528036 -0.726936 -0.417544 -0.54518 -0.939622 0.13806 0.313131 -0.939566 0.1989 0.278666 -0.938391 0.214142 0.271229 -0.939692 0.213116 0.267507 -0.939424 0.214307 0.267499 -0.939407 0.214372 0.267504 -0.939889 0.213334 0.266642 -0.939981 0.213394 0.266268 -0.939935 0.21339 0.266432 -0.939773 0.213605 0.266831 -0.939573 0.213946 0.267264 -0.939633 0.124426 0.318762 -0.939833 0.124222 0.31825 -0.940952 0.125221 0.314529 -0.939692 0.125147 0.318303 -0.939959 0.123991 0.317966 -0.939978 0.12392 0.317939 -0.939692 0.125595 0.318126 -0.939471 0.124553 0.319187 -0.939449 0.124529 0.319262 -0.939565 0.141883 0.311587 -0.94337 0.135894 0.302631 -0.936007 0.168602 0.308972 -0.939622 0.160295 0.30235 -0.939661 0.178137 0.292071 -0.937285 0.185067 0.295376 -0.94337 0.194139 0.269004 -0.939621 0.20215 0.276129 -0.939692 0.212706 0.267833 -0.149345 0.398904 0.904749 -0.488788 0.351953 0.798258 -0.346077 0.554206 0.757024 -0.655056 0.446327 0.609667 -0.850962 0.310256 0.423798 -0.850962 0.310257 0.423799 -0.850962 0.278865 0.445083 -0.850962 0.278865 0.445082 -0.850963 0.246019 0.464045 -0.850961 0.246021 0.464046 -0.850961 0.211893 0.48059 -0.850962 0.211892 0.480589 -0.655066 0.304819 0.691356 -0.573439 0.337356 0.746564 -0.573328 0.383777 0.723885 -0.573331 0.383776 0.723884 -0.573331 0.435013 0.694302 -0.57333 0.435014 0.694303 -0.573441 0.477866 0.66544 -0.488785 0.515337 0.70393 -0.346096 0.378497 0.858462 -0.202131 0.400396 0.893771 -0.202093 0.458741 0.865283 -0.202088 0.458742 0.865284 -0.202087 0.519987 0.829924 -0.20209 0.519987 0.829924 -0.202128 0.573831 0.793639 -0.149353 0.584083 0.797835 0.707104 -0.455582 -0.540785 0.671185 -0.44295 -0.594395 0.70647 -0.42432 -0.566439 0.70647 -0.353871 -0.612923 0.70647 -0.353871 -0.612923 0.706523 -0.279992 -0.649946 0.672815 -0.291004 -0.680174 0.707099 -0.240545 -0.664943 0.698066 -0.385794 -0.603214 0.698075 -0.385792 -0.603205 0.698074 -0.609309 -0.376079 0.618521 -0.654388 -0.434981 0.706908 -0.661406 -0.250645 0.698076 -0.712141 -0.0744681 0.69807 -0.712147 -0.074471 0.698069 -0.673932 0.241898 0.698054 -0.673948 0.241898 0.698057 -0.502249 0.510356 0.698063 0.0858649 0.710869 0.698068 0.0858659 0.710865 0.700602 -0.207406 0.682744 0.6349 -0.249322 0.73126 0.706898 -0.351039 0.614058 0.698069 -0.502237 0.510351 0.697828 -0.327737 -0.636886 0.697828 -0.327737 -0.636887 0.697828 -0.0147344 -0.716114 0.697829 -0.0147347 -0.716113 0.697829 0.301259 -0.649829 0.697828 0.30126 -0.64983 0.697829 0.556037 -0.451506 0.697823 0.556043 -0.451508 0.697821 0.697843 -0.161434 0.697832 0.697832 -0.161435 0.706472 0.424319 0.566437 0.70647 0.42432 0.566438 0.70647 0.353871 0.612923 0.706471 0.353871 0.612922 0.706471 0.27839 0.650691 0.706469 0.27839 0.650692 0.879243 0.125534 0.459535 0.887083 0.051025 0.458781 0.954993 -0.0821847 0.285016 0.960102 -0.0884359 0.2653 0.978436 -0.0582606 0.198163 0.978976 -0.0581034 0.195526 0.991396 0.00378022 0.13084 0.990797 0.00127329 0.135349 0.965171 -0.189754 -0.18011 0.793208 -0.601566 0.0945519 0.859466 -0.489388 -0.147706 0.839106 -0.522773 -0.150364 0.884192 -0.291275 -0.36519 0.876487 -0.305376 -0.372179 0.859292 -0.349008 0.373913 0.938544 -0.0860376 0.334265 0.933186 -0.0719028 0.352127 0.821647 -0.485524 0.298603 0.847486 -0.482455 0.221373 0.891282 -0.409502 0.194744 0.947044 -0.321104 -0.00017447 0.93832 -0.345768 -0.000953166 0.970911 -0.188439 -0.147724 0.989049 -0.129094 -0.0715353 0.807334 -0.175125 0.56351 0.693243 -0.466038 0.549748 0.77072 -0.5386 0.340442 0.902132 -0.0230724 0.430844 0.887847 0.0564834 0.456659 0.749555 -0.00903608 0.661881 0.710137 0.00404305 0.704052 0.275999 -0.534785 0.798642 0.145864 -0.00065614 0.989304 0.197815 0.157627 0.967483 0.14794 0.19632 0.969315 0.111221 -0.826844 -0.551324 0.0953788 -0.5314 -0.841735 0.105771 -0.527766 -0.842779 0.0780519 -0.99624 0.03761 0.143584 -0.976811 -0.158821 0.177637 -0.969289 -0.170073 0.0973013 -0.936487 -0.336935 0.110863 -0.82694 -0.551253 0.0290463 -0.253972 0.966775 0.134949 -0.618046 0.774472 -0.130549 -0.585892 0.799805 0.156235 -0.792507 0.589512 0.2161 -0.805167 0.552274 0.0506026 -0.889132 0.454844 0.143384 -0.96727 0.209357 0.273403 -0.922931 0.271016 0.14237 -0.978989 0.145984 0.354231 -0.484335 0.799963 0.457118 -0.688462 0.563083 0.36317 -0.709129 0.604353 0.490829 -0.827324 0.27317 0.397302 -0.864988 0.306509 0.522597 -0.850131 -0.0645683 0.442841 -0.895326 -0.0477862 0.546614 -0.730833 -0.408773 0.493388 -0.767607 -0.409082 0.553357 -0.467288 -0.68952 0.546228 -0.472289 -0.691793 0.176403 -0.530617 0.829053 0.302663 -0.77968 0.548173 0.186337 -0.790091 0.583982 0.325676 -0.91887 0.22274 0.208484 -0.944248 0.254812 0.343273 -0.92819 -0.143623 0.24185 -0.962446 -0.123315 0.351501 -0.789179 -0.503629 0.282647 -0.819773 -0.49808 0.345029 -0.503868 -0.791879 0.33367 -0.509789 -0.792957 0.87955 0.126436 0.458701 0.763479 0.147475 0.628769 0.69396 0.116221 0.710572 0.651405 0.150627 0.743629 0.484447 0.162599 0.859577 0.918302 -0.0577993 0.391639 0.901023 -0.0509532 0.430769 0.758733 -0.262211 0.596296 0.805309 -0.228502 0.54705 0.700509 -0.338331 0.628347 0.633804 -0.0756572 0.769785 0.46111 -0.119018 0.879325 0.425658 0.132611 0.895115 0.341461 0.155464 0.92695 0.172207 -0.198942 0.964763 0.179197 -0.20022 0.963224 0.424093 -0.163317 0.890771 0.486873 -0.377259 0.787801 0.502662 -0.37627 0.778301 0.601382 -0.571163 0.55867 0.531863 -0.596 0.601586 0.642841 -0.698907 0.313502 0.575083 -0.740977 0.346745 0.685223 -0.728057 0.0200388 0.629211 -0.776453 0.0348479 0.721675 -0.629618 -0.287692 0.685628 -0.667423 -0.290623 0.739943 -0.390821 -0.547489 0.725679 -0.406495 -0.555114 0.340894 -0.563628 -0.752406 0.994035 0.054531 0.0944505 0.994036 0.0655603 0.0871413 0.994251 0.064198 0.0857001 0.991754 0.0501653 0.117931 0.996676 0.0363047 0.0729359 0.658677 -0.376213 -0.65162 0.93179 -0.181499 -0.314365 0.994046 0.0446274 0.0994072 0.993745 -0.043925 -0.102668 0.971837 -0.0926952 -0.21666 0.994056 0.0601492 0.0907459 0.994035 0.0545309 0.0944503 0.931791 -0.181498 -0.314364 0.931639 -0.136915 -0.336605 0.558439 -0.508459 -0.655451 0.739316 -0.403705 -0.538919 0.93179 -0.217631 -0.290523 0.888072 -0.284802 -0.360854 0.971842 -0.14127 -0.188587 0.237286 -0.48572 -0.841291 0.237286 -0.582416 -0.777487 0.108123 -0.607637 -0.78682 0.887838 -0.181002 -0.423062 0.739296 -0.264874 -0.619099 0.658465 -0.289907 -0.694534 0.558103 -0.32639 -0.762883 0.340887 -0.369789 -0.864322 0.658679 -0.451108 -0.602199 0.65868 -0.376212 -0.651618 0.237287 -0.48572 -0.841291 0.237189 -0.375999 -0.895749 0.108041 -0.391047 -0.914007 0.572895 0.409814 0.70982 0.850727 0.315995 0.420013 0.879519 0.18627 0.437893 0.654674 0.297338 0.694976 0.764993 0.253333 0.592122 0.845143 0.213402 0.490096 0.851114 0.233936 0.469977 0.850696 0.262829 0.455233 0.850697 0.262828 0.455231 0.851115 0.290041 0.437583 0.345772 0.369087 0.86268 0.488422 0.34324 0.802266 0.149207 0.388946 0.909097 0.201909 0.388457 0.899074 0.201868 0.489706 0.848196 0.844349 0.32123 0.42882 0.654697 0.453187 0.604974 0.573015 0.487722 0.65862 0.488423 0.523162 0.698387 0.345778 0.562558 0.750977 0.57302 0.32652 0.751687 0.5729 0.409813 0.709816 0.201873 0.489706 0.848195 0.201913 0.584392 0.78595 0.149213 0.592828 0.791385 0.146154 0.784665 0.602445 0.826272 0.514738 -0.228735 0.651429 0.568646 0.502276 0.880893 0.370658 0.294347 0.992268 0.115974 0.0442011 0.992327 0.0929056 0.0815843 0.976265 0.213192 0.0381595 0.978908 0.198452 0.0485421 0.963204 0.263087 0.0549821 0.942932 0.328758 0.0528935 0.902136 0.375827 0.211906 0.8958 0.384886 0.222273 0.919327 0.363957 0.149579 0.851019 0.327627 0.4104 0.740543 0.670395 -0.0465453 0.783615 0.617547 -0.0676983 0.707955 0.690445 0.148615 0.912307 0.377984 0.15756 0.939733 0.327486 0.0982584 0.785901 0.574611 -0.228434 0.847487 0.432956 -0.307109 0.793259 0.382584 -0.473677 0.856961 0.135677 -0.497201 0.844206 0.113591 -0.523844 0.884162 -0.162484 -0.438014 0.877675 -0.17636 -0.445628 0.923008 0.37053 0.103749 0.960832 0.266499 0.0760318 0.891325 0.373336 -0.257215 0.944822 0.174615 -0.277166 0.941841 0.158824 -0.29616 0.97092 -0.0336483 -0.23703 0.965173 -0.0610597 -0.254388 0.131205 0.334836 -0.933097 0.0963161 0.137765 -0.985771 0.14647 -0.0609131 -0.987338 0.0518746 -0.107049 -0.9929 0.106231 -0.484463 -0.868338 0.157101 -0.461455 -0.873143 0.334012 -0.435928 -0.835705 0.0122633 0.995489 -0.0940835 0.240083 0.961273 -0.135331 0.150956 0.328257 -0.932448 0.0723452 0.544679 -0.835518 0.202045 0.66322 -0.720636 0.130337 0.693438 -0.70863 0.0119039 0.890795 -0.454249 0.320264 0.815029 -0.482865 0.105143 0.928127 -0.357107 0.0889433 0.995249 0.0396113 0.0328623 0.967701 0.249949 0.190214 0.933056 0.305327 0.0915604 0.773047 0.627706 0.341474 0.724978 0.598166 0.693995 0.557225 0.455929 0.714752 0.629597 0.304527 0.412204 0.845766 0.338775 0.486918 0.870867 0.0670954 0.35418 0.934973 -0.0195592 0.447643 0.848565 -0.282051 0.378512 0.860284 -0.341527 0.48013 0.679719 -0.554488 0.413103 0.668787 -0.618118 0.514063 0.403018 -0.757177 0.455181 0.373765 -0.808152 0.542686 0.0370951 -0.839116 0.499644 0.00529515 -0.866215 0.553285 -0.360448 -0.750968 0.546652 -0.366038 -0.753119 0.34468 -0.429068 -0.834923 0.288263 -0.0478238 -0.956356 0.346237 -0.013862 -0.938045 0.253715 0.339572 -0.905715 0.332833 0.376519 -0.864555 0.224024 0.66206 -0.715185 0.313046 0.684703 -0.658167 0.20154 0.882716 -0.424493 0.291663 0.883364 -0.366879 0.187843 0.979349 -0.0747702 0.269283 0.962527 -0.0320591 0.179195 0.934252 0.308322 0.463857 0.833126 0.301227 0.425707 0.708831 0.562434 0.484453 0.663081 0.570639 0.875353 0.333512 0.350039 0.889584 0.363658 0.276395 0.689705 0.642336 0.334233 0.745683 0.656171 0.115743 0.502645 0.862178 0.0632239 0.593265 0.783382 -0.185336 0.546281 0.802082 -0.241333 0.633761 0.646475 -0.424754 0.590007 0.643898 -0.487122 0.678252 0.411039 -0.609115 0.64095 0.389195 -0.661597 0.718704 0.088419 -0.689671 0.691734 0.0607471 -0.719593 0.739913 -0.269869 -0.616198 0.727074 -0.285607 -0.624333 0.939514 0.134071 0.315179 0.939603 0.114005 0.322722 0.93949 0.113993 0.323054 0.939578 0.114159 0.322738 0.939697 0.115016 0.322089 0.939843 0.113771 0.322105 0.939864 0.113706 0.322066 0.939744 0.113874 0.322357 0.939507 0.205928 0.273715 0.939903 0.222055 0.259372 0.939805 0.222004 0.259772 0.93969 0.221436 0.260671 0.939697 0.221585 0.260518 0.939545 0.222566 0.26023 0.939484 0.222812 0.26024 0.939528 0.222658 0.260212 0.939644 0.222409 0.260006 0.939777 0.222173 0.259728 0.939515 0.205916 0.273699 0.939511 0.205921 0.273707 0.939694 0.18896 0.285079 0.939693 0.188959 0.28508 0.939498 0.171278 0.296662 0.939498 0.171278 0.296662 0.939694 0.152407 0.306184 0.939693 0.152406 0.306184 0.939511 0.134075 0.315187 0.939507 0.134078 0.315197 0.93969 0.114815 0.322182 0 -0.488987 -0.872291 -0.0153079 -0.45751 -0.889073 0.0139157 -0.10928 -0.993914 -0.0215401 -0.0205663 -0.999556 -0.00264738 0.131163 -0.991357 0.00676894 0.320352 -0.947275 -0.0292771 0.420417 -0.906859 -0.000611811 0.540304 -0.841469 0 0.974271 -0.22538 -0.0389797 0.985845 -0.163064 -0.00187354 0.929653 -0.368431 0.00681368 0.776283 -0.630347 -0.0595017 0.838441 -0.541734 0.000715404 0.690177 -0.72364 -0.700053 -0.700053 -0.140896 -0.70004 -0.700066 -0.140894 -0.700049 -0.389999 -0.598191 -0.700048 -0.39 -0.598191 -0.700047 -0.591048 -0.400744 -0.776295 -0.50474 -0.37763 -0.706724 -0.638977 -0.303727 -0.458487 0.531405 -0.712319 -0.694743 -0.284226 -0.660717 -0.69474 -0.284228 -0.660719 -0.7057 -0.0393294 -0.707418 -0.754941 0.00583053 -0.655767 -0.624894 0.159893 -0.764161 -0.70502 0.189634 -0.683363 -0.703704 0.351501 -0.617452 -0.704397 0.498856 -0.504943 -0.704397 0.607109 -0.367755 -0.45848 0.816373 -0.351187 -0.694736 0.576512 0.430088 -0.694742 0.576506 0.430086 -0.702915 0.693218 0.159247 -0.46676 0.878302 0.103541 -0.705015 0.708734 -0.0255211 -0.703697 0.682273 -0.198278 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 -0.308846 -0.637124 -0.706171 -0.308849 -0.63713 -0.706169 -0.397347 -0.586038 -0.706182 -0.39734 -0.586027 0.694737 0.306877 -0.650513 0.487519 -0.497605 -0.717436 0.694737 0.306877 -0.650513 0.702913 0.0182442 -0.711042 0.494614 -0.0718864 -0.866135 0.705016 -0.165924 -0.689508 0.703698 -0.329975 -0.629226 0.704394 -0.481119 -0.521874 0.704395 -0.59405 -0.3885 0.487515 -0.789657 -0.372518 0.694743 -0.591014 0.409919 0.694739 -0.591018 0.409921 0.702914 -0.698304 0.135215 0.494621 -0.866131 0.0718883 0.705015 -0.707429 -0.0499779 0.703699 -0.675016 -0.221723 0.699629 0.372838 -0.609517 0.699631 0.372836 -0.609516 0.699633 0.584371 -0.411126 0.699627 0.584377 -0.411127 0.699629 0.699638 -0.145007 0.699627 0.69964 -0.145006 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.426654 -0.904415 0 -0.750949 0.66036 -0.0478512 -0.820759 0.569267 -0.0190426 -0.868973 0.494494 0.0231323 -0.964474 0.263164 -0.00911222 -0.950021 -0.312054 0.0343669 -0.986883 -0.157736 0.00482574 -0.997502 -0.0704707 -0.00545943 -0.98175 0.1901 -0.00780288 -0.677795 -0.73521 -1.8058e-05 -0.70418 -0.710021 2.3653e-05 -0.836916 -0.547331 -1.20488e-05 -0.836853 -0.547427 -7.88057e-06 -0.912021 -0.410144 -0.0167067 -0.1687 -0.985526 0.0109693 -0.343702 -0.939015 -0.0114737 -0.464397 -0.885553 2.41673e-05 -0.526065 -0.850444 1.76467e-05 -0.611322 -0.791382 -0.0265313 0.467535 -0.883577 0.0157205 0.069928 -0.997428 1.85691e-05 0.02565 -0.999671 -5.93692e-06 -0.233962 -0.972246 0 0.473875 -0.880592 -0.018437 0.521723 -0.852916 -0.000259055 0.641249 -0.767333 0.000964894 0.817871 -0.575401 -0.00804123 0.806481 -0.591206 0.00859144 0.979154 -0.202939 0 0.97561 -0.219509 0 -0.393349 0.919389 0 -0.393349 0.919389 0 -0.5 0.866025 0 -0.5 0.866025 0 -0.59954 0.800345 0 -0.59954 0.800345 0 0.599539 -0.800345 0 0.599539 -0.800345 0 0.5 -0.866025 0 0.5 -0.866025 0 0.393349 -0.919389 0 0.393349 -0.919389 0.879242 -0.335204 0.338484 0.887083 -0.371803 0.273581 0.954993 -0.287924 0.0713347 0.960101 -0.273975 0.0560634 0.978435 -0.200748 0.0486277 0.978976 -0.198381 0.0474432 0.991397 -0.111419 0.0686937 0.990797 -0.116579 0.0687771 0.965171 0.0611028 -0.254384 0.793208 -0.382669 -0.473694 0.859467 -0.116778 -0.497674 0.839103 -0.131171 -0.527921 0.88419 0.17063 -0.434848 0.876485 0.169632 -0.450555 0.859292 -0.498322 -0.115292 0.938544 -0.3325 0.0926221 0.933187 -0.3409 0.113793 0.821646 -0.501359 -0.271176 0.847485 -0.432942 -0.307133 0.891282 -0.373403 -0.257266 0.947044 -0.160403 -0.27817 0.938319 -0.172062 -0.299921 0.970911 0.0337145 -0.237054 0.989049 -0.00259425 -0.147566 0.807334 -0.575575 0.130095 0.693241 -0.709116 -0.128731 0.770718 -0.564133 -0.296223 0.902132 -0.384657 0.195439 0.887847 -0.367235 0.277249 0.749549 -0.577728 0.323121 0.710136 -0.607706 0.355529 0.275999 -0.959037 -0.0638151 0.145867 -0.85709 0.494085 0.197818 -0.759049 0.620251 0.14794 -0.741289 0.654679 0.111229 0.0640401 -0.991729 0.0953847 0.463264 -0.881072 0.105767 0.465983 -0.878449 0.0780604 -0.530685 -0.843967 0.143589 -0.350865 -0.925352 0.177641 -0.33736 -0.924463 0.0973035 -0.17645 -0.979488 0.110866 0.0639296 -0.991777 0.0290507 -0.964238 0.26344 0.134951 -0.979736 -0.148007 -0.130548 -0.985597 -0.107494 0.156261 -0.906773 -0.391593 0.216095 -0.880867 -0.42116 0.0506097 -0.838478 -0.542581 0.143396 -0.664941 -0.733002 0.273406 -0.696167 -0.663778 0.142384 -0.615922 -0.774834 0.354226 -0.934957 -0.0194649 0.457112 -0.831879 -0.314684 0.363178 -0.877947 -0.311948 0.490835 -0.650231 -0.579897 0.397297 -0.697941 -0.595847 0.522597 -0.369144 -0.768521 0.442832 -0.406278 -0.799273 0.546608 -0.0114084 -0.837311 0.493396 -0.0295227 -0.869304 0.553364 0.363497 -0.749439 0.546229 0.362964 -0.754911 0.176404 -0.983289 -0.0450001 0.30266 -0.864573 -0.401138 0.186326 -0.900791 -0.392248 0.325672 -0.652331 -0.684399 0.208474 -0.692797 -0.690341 0.343261 -0.339717 -0.875651 0.241859 -0.374425 -0.895159 0.351507 0.0415674 -0.935262 0.282646 0.0214628 -0.958984 0.345024 0.433852 -0.832304 0.333676 0.431827 -0.837966 0.87955 -0.334027 0.338849 0.763484 -0.470787 0.442101 0.693959 -0.557264 0.455936 0.651408 -0.568688 0.502256 0.484444 -0.66312 0.570601 0.918302 -0.368069 0.145765 0.901023 -0.398532 0.171259 0.758732 -0.647515 0.0710662 0.805309 -0.58801 0.0756362 0.700506 -0.713332 0.0211688 0.633802 -0.704482 0.319374 0.461116 -0.821023 0.336591 0.425664 -0.708883 0.562401 0.341462 -0.725028 0.598112 0.172209 -0.93498 0.31009 0.179193 -0.934287 0.308216 0.424096 -0.853088 0.303948 0.486875 -0.870884 0.0671881 0.502667 -0.86216 0.0632941 0.601391 -0.769397 -0.215305 0.531871 -0.818984 -0.215357 0.642846 -0.620954 -0.448515 0.575092 -0.670775 -0.468326 0.685232 -0.38138 -0.620489 0.629214 -0.418408 -0.655 0.721678 -0.0656556 -0.689109 0.685622 -0.0820237 -0.723322 0.739939 0.27873 -0.612209 0.725683 0.277497 -0.629588 0.146162 -0.129402 0.980761 0.826271 0.455459 0.331411 0.651433 -0.150658 0.743597 0.880894 -0.0695808 0.468171 0.992268 0.0197096 0.122537 0.992327 -0.0242031 0.12125 0.976264 0.0735495 0.203712 0.978908 0.0571873 0.196137 0.963207 0.0839233 0.255323 0.942931 0.118574 0.311162 0.902137 0.00439737 0.431428 0.895798 -5.25607e-05 0.444461 0.919326 0.0524393 0.389986 0.851019 -0.191601 0.488934 0.740544 0.375509 0.557304 0.783615 0.367404 0.50096 0.707954 0.216517 0.672251 0.912306 0.0525416 0.406125 0.939733 0.07865 0.33274 0.7859 0.485135 0.383413 0.847486 0.482442 0.221397 0.793259 0.601507 0.0944913 0.856962 0.498425 -0.131104 0.844209 0.510454 -0.163547 0.884163 0.298089 -0.35972 0.877676 0.297744 -0.375543 0.923015 0.0954111 0.372748 0.960832 0.0674034 0.268811 0.891326 0.409421 0.194711 0.944822 0.327339 0.012639 0.94184 0.335895 -0.0105378 0.970919 0.188451 -0.147654 0.965172 0.189778 -0.180075 0.262977 0.952698 0.152348 0.07924 0.976049 0.202606 0.103107 0.978206 -0.180226 0.0255658 0.975759 -0.217351 0.165121 0.822953 -0.543584 0.0785323 0.806853 -0.58551 0.114866 0.640029 -0.759716 0.334006 0.505779 -0.795379 0.105773 0.527834 -0.842736 0.273499 0.459361 -0.845095 0.300419 0.593828 0.746403 0.0368643 0.576853 0.816016 0.116748 0.826172 0.551189 0.0237857 0.855354 0.517498 0.108099 0.945342 0.307642 0.0615922 0.460924 0.8853 0.111886 0.235634 0.96538 0.190218 0.202111 0.960712 0.0915646 -0.15709 0.98333 0.341456 -0.155542 0.926938 0.693998 -0.116232 0.710533 0.714755 0.051074 0.697508 0.41221 0.129499 0.901839 0.486922 0.377327 0.787738 0.354181 0.484427 0.799929 0.447644 0.668545 0.593853 0.378521 0.725906 0.574267 0.48014 0.820054 0.311411 0.413105 0.8697 0.270123 0.514064 0.857242 -0.029564 0.455184 0.886761 -0.0803843 0.542691 0.745242 -0.387428 0.499644 0.752811 -0.428522 0.553288 0.470132 -0.68764 0.546658 0.4692 -0.693553 0.344676 0.508533 -0.789045 0.288257 0.804318 -0.519597 0.346232 0.805441 -0.481029 0.253712 0.954158 -0.158783 0.33284 0.936984 -0.1062 0.224032 0.950396 0.215773 0.313036 0.912346 0.263882 0.201527 0.808981 0.552211 0.291651 0.75941 0.581581 0.187834 0.554432 0.810755 0.269275 0.509032 0.817543 0.179186 0.200112 0.963248 0.463854 0.155693 0.872123 0.425703 -0.132668 0.895084 0.484446 -0.162646 0.859569 0.875353 -0.136383 0.46385 0.889583 -0.0575362 0.453135 0.689703 0.0317139 0.723397 0.745681 0.227848 0.626135 0.502638 0.376336 0.778285 0.593262 0.552201 0.585759 0.546283 0.61004 0.573957 0.633762 0.691084 0.347489 0.590005 0.74381 0.314071 0.678251 0.73303 0.0514149 0.640945 0.767561 0.00625309 0.718701 0.641485 -0.268266 0.691734 0.653561 -0.307186 0.739911 0.39871 -0.541814 0.727071 0.397887 -0.559512 0.572896 -0.409814 0.709819 0.850727 -0.205745 0.483666 0.879518 -0.286092 0.380263 0.65468 -0.453196 0.604986 0.764995 -0.386125 0.515451 0.845143 -0.317734 0.429858 0.851115 -0.290042 0.437583 0.850697 -0.262828 0.455231 0.850697 -0.262828 0.455232 0.851115 -0.233939 0.469975 0.345772 -0.562559 0.750979 0.488417 -0.523165 0.69839 0.149209 -0.592828 0.791386 0.20191 -0.584392 0.78595 0.20187 -0.489706 0.848196 0.844348 -0.210755 0.492604 0.654702 -0.297328 0.694955 0.573018 -0.326521 0.751688 0.488416 -0.343241 0.802269 0.345766 -0.369088 0.862682 0.573018 -0.487721 0.658619 0.572897 -0.409814 0.709818 0.201871 -0.489706 0.848196 0.201911 -0.388456 0.899074 0.149219 -0.388945 0.909096 0.340888 0.369789 -0.864321 0.994035 -0.054531 0.0944506 0.994036 -0.0426862 0.100347 0.994251 -0.0421194 0.098447 0.991754 -0.0770488 0.10241 0.996676 -0.0450111 0.0679078 0.658679 0.376212 -0.651618 0.931791 0.181498 -0.314364 0.994046 -0.0637756 0.0883521 0.993745 0.0669509 -0.0893749 0.971837 0.141285 -0.188606 0.994056 -0.0485145 0.0974635 0.994035 -0.054531 0.0944505 0.93179 0.181498 -0.314365 0.931639 0.223051 -0.286875 0.558447 0.313406 -0.768059 0.739312 0.264867 -0.619083 0.931791 0.142784 -0.333735 0.888074 0.170106 -0.42707 0.971842 0.0926862 -0.216639 0.237285 0.48572 -0.841292 0.237285 0.382115 -0.893131 0.108128 0.377588 -0.919639 0.887837 0.275883 -0.368285 0.739298 0.403717 -0.538936 0.658468 0.456529 -0.598332 0.558104 0.49748 -0.664103 0.340894 0.563628 -0.752406 0.658679 0.295966 -0.691771 0.658679 0.376212 -0.651618 0.237289 0.485719 -0.841291 0.237192 0.587742 -0.773498 0.108037 0.59603 -0.795661 0.939515 -0.205917 0.273697 0.939603 -0.222483 0.260092 0.93949 -0.222776 0.260247 0.939578 -0.222422 0.260234 0.939697 -0.221425 0.260653 0.939843 -0.222065 0.259582 0.939865 -0.222064 0.259504 0.939743 -0.222234 0.259798 0.939507 -0.13408 0.315197 0.939902 -0.113596 0.321993 0.939804 -0.113966 0.322148 0.93969 -0.115027 0.322106 0.939697 -0.114818 0.322159 0.939545 -0.114079 0.322864 0.939488 -0.113972 0.323068 0.939529 -0.114021 0.322932 0.939644 -0.113968 0.322616 0.939777 -0.113844 0.322272 0.939515 -0.134072 0.315178 0.939511 -0.134077 0.315186 0.939694 -0.152409 0.306183 0.939694 -0.152408 0.306183 0.939498 -0.171278 0.296662 0.939497 -0.171278 0.296662 0.939693 -0.188959 0.285081 0.939693 -0.188959 0.285081 0.939511 -0.205923 0.273706 0.939507 -0.20593 0.273713 0.93969 -0.22161 0.260523 0 0.991268 0.131864 -0.0350619 0.970878 0.236997 -0.0184756 0.954556 0.29746 0.0223816 0.855451 0.517399 -0.001263 0.817965 0.575266 0.00124556 0.643174 0.765719 0.00815521 0.65819 0.752808 -0.00662228 0.466161 0.884675 -7.18923e-06 0.486201 0.873847 3.16475e-05 0.265116 0.964216 0.00862941 0.242604 0.970087 -0.013922 -0.104978 0.994377 0 -0.127733 0.991809 0.696792 -0.0753067 0.713309 0.696796 -0.0753046 0.713305 0.696795 0.261827 0.667775 0.324184 0.250798 0.912143 0.696796 0.696809 0.170095 0.696793 0.696812 0.170097 0.703903 0.580998 0.408609 0.535514 0.635878 0.555773 0.705129 0.466725 0.533818 0.705127 0.344756 0.619628 0 -0.998721 0.0505561 0.0226864 -0.956855 0.289679 -0.00893472 -0.974602 0.223765 0.00755008 -0.779396 0.626486 0 -0.767191 0.641419 -0.697965 -0.697972 0.160252 -0.697961 -0.697975 0.160254 -0.697963 -0.558168 0.448661 -0.69796 -0.558169 0.448663 -0.698113 -0.312314 -0.644281 -0.698108 -0.312318 -0.644285 -0.698107 -0.560476 -0.445548 -0.698114 -0.560469 -0.445546 -0.698112 -0.698119 -0.158963 -0.698112 -0.698119 -0.158963 -0.69811 0.307665 -0.646518 -0.698108 0.307665 -0.646519 -0.698111 -0.00258181 -0.715985 -0.842205 0.0503109 -0.536805 -0.705433 -0.0921892 -0.702756 -0.698066 0.406397 -0.58953 -0.698072 0.406395 -0.589524 -0.70427 0.579224 -0.410491 -0.771601 0.541593 -0.333628 -0.684045 0.674073 -0.278761 -0.706895 0.669672 -0.22768 -0.698063 0.714301 -0.0498318 -0.698064 0.714299 -0.0498312 -0.698064 0.665182 0.265026 -0.698067 0.665179 0.265025 -0.698067 0.484316 0.52739 -0.698066 -0.110365 0.707477 -0.698061 -0.110364 0.707482 -0.700596 0.183712 0.689504 -0.627461 0.225676 0.745227 -0.706901 0.329627 0.625809 -0.698069 0.484314 0.527389 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 0.397343 -0.586031 -0.706177 0.397343 -0.586032 -0.706176 0.308847 -0.637125 -0.706175 0.308847 -0.637127 0 0.414414 -0.910089 -0.0420203 0.435817 -0.899054 0 0.479008 -0.877811 0 0.561191 -0.827686 -0.0629304 0.579801 -0.812324 0 0.520703 -0.853738 -0.706176 -0.397344 0.586032 -0.706173 -0.397345 0.586035 -0.706173 -0.308848 0.637128 -0.706175 -0.308847 0.637126 0 0.567569 -0.823326 0 -0.231128 0.972923 0.0219207 -0.154097 0.987813 0.00326146 -0.0297842 0.999551 -0.007386 0.221635 0.975102 0.00467379 0.257456 0.966279 -0.00127697 0.466028 0.884769 -0.0165309 0.610458 0.791876 0.012111 0.676338 0.736492 -0.00719721 0.863586 0.50415 0.0216187 0.928763 0.370044 0.00294502 0.96048 0.278335 3.93744e-06 0.946756 -0.321951 -6.98482e-05 0.988955 -0.148219 0.0189451 0.997396 -0.0695807 0.00146907 0.997909 0.0646231 -0.00030248 0.987394 0.158282 0.00632609 0.552437 -0.833531 -0.00539725 0.842026 -0.539409 -1.78155e-05 0.85142 -0.524485 5.78989e-07 0.946776 -0.321893 -0.00101359 -0.269989 -0.962863 0 0.576675 -0.816974 0.0140745 0.429662 -0.90288 0.000859313 -0.168169 -0.985758 0.0120156 -0.0208778 -0.99971 0.0163228 -0.00360546 -0.99986 -0.00344533 0.187071 -0.98234 0.00894433 0.412085 -0.911102 0.0133877 -0.416171 -0.909188 0.0187233 -0.436124 -0.899692 -0.00146475 -0.57223 -0.820092 0.00147511 -0.692052 -0.721846 0.0193581 -0.782648 -0.622163 0.00546752 -0.816306 -0.577594 0 -0.975042 -0.222019 0.0315526 -0.988752 -0.1462 -0.00301666 -0.925574 -0.378554 -0.994042 -0.0633211 0.0887153 -0.971841 0.136894 -0.191794 -0.658919 0.376107 -0.651436 -0.108088 0.411986 -0.904757 -0.558297 0.343815 -0.755047 -0.341052 0.389567 -0.855524 -0.237325 0.394969 -0.887511 -0.237621 0.465288 -0.852668 -0.15399 0.494036 -0.855696 -0.237621 0.505789 -0.829286 -0.237426 0.564341 -0.790663 -0.887884 0.190658 -0.418703 -0.739467 0.27898 -0.612665 -0.108166 0.592335 -0.798398 -0.341055 0.546121 -0.765136 -0.658919 0.437 -0.612255 -0.558599 0.496019 -0.66478 -0.739471 0.391091 -0.547933 -0.971845 0.0976447 -0.214436 -0.931696 0.143051 -0.333885 -0.931861 0.181408 -0.314208 -0.658697 0.304196 -0.688173 -0.658919 0.376107 -0.651436 -0.931861 0.181408 -0.314208 -0.931861 0.210779 -0.295309 -0.888089 0.27875 -0.365508 -0.994042 -0.0451691 0.0991952 -0.994042 -0.0451692 0.0991955 -0.994053 -0.0521644 0.0955954 -0.994978 -0.0500476 0.086685 -0.994053 -0.0567051 0.0929736 -0.994042 -0.0633211 0.0887153 0 -0.590708 0.806885 0.0635012 -0.560058 0.826016 0 -0.530942 0.847408 0 -0.436202 0.899849 0.126162 -0.400205 0.9077 0 -0.468406 0.883513 -0.0983857 0.945126 -0.31154 -0.738156 0.172013 0.652332 -0.933087 0.0610859 0.354426 -0.885799 -0.0771629 0.457608 -0.902766 -0.0139798 0.429904 -0.90088 0.0122354 0.433896 -0.893727 -0.0417165 0.446666 -0.982603 0.0505423 0.178708 -0.968983 0.0675713 0.237711 -0.95918 0.0812338 0.270877 -0.978164 0.0475856 0.202314 -0.993506 -0.0155904 0.112709 -0.993503 -0.00928725 0.113428 -0.955076 0.0734739 0.287108 -0.937213 0.0759735 0.340382 -0.812789 0.429295 0.393802 -0.759744 0.375084 0.531132 -0.532642 0.576747 0.619399 -0.600326 0.550546 0.580093 -0.364118 0.689734 0.625848 -0.456017 0.667371 0.588782 -0.187426 0.771396 0.608128 -0.14551 -0.0356735 0.988713 -0.172306 0.167508 0.970697 -0.884951 -0.0718474 0.460109 -0.712673 0.00144548 0.701495 -0.697725 0.0304737 0.715717 -0.461102 0.0908648 0.882683 -0.423352 0.131126 0.896426 -0.179694 0.16861 0.969165 -0.275275 0.505165 0.817944 -0.918224 0.0456409 0.393423 -0.916086 0.0449177 0.398458 -0.771361 0.320365 0.54988 -0.72281 0.220563 0.654903 -0.503327 0.351504 0.789371 -0.487236 0.353139 0.798683 -0.353649 0.456151 0.816615 -0.177313 0.504053 0.845275 -0.301518 0.758823 0.5773 -0.274906 0.913368 0.300309 -0.144651 0.974093 0.173836 -0.0773284 0.994277 0.0737088 -0.876426 0.318029 -0.361572 -0.884047 0.304573 -0.354536 -0.725701 0.425096 -0.540973 -0.739821 0.410119 -0.533355 -0.546207 0.495751 -0.675195 -0.553285 0.490976 -0.672917 -0.33363 0.537046 -0.774773 -0.344979 0.531491 -0.773632 -0.105762 0.556223 -0.824276 -0.121709 0.551076 -0.825531 -0.145527 0.980622 -0.131156 -0.171018 0.975595 -0.137719 -0.342315 0.93329 -0.108586 -0.242324 0.965786 -0.0923921 -0.521636 0.852549 -0.0325041 -0.443218 0.896213 -0.0189463 -0.684274 0.727668 0.0476258 -0.629468 0.77472 0.0598201 -0.792142 0.599053 0.116818 -0.839076 0.527537 -0.132877 -0.858964 0.495431 -0.129341 -0.685631 0.676748 -0.268184 -0.721165 0.640375 -0.264275 -0.493422 0.7808 -0.383257 -0.546159 0.745674 -0.381682 -0.282715 0.835841 -0.470576 -0.351086 0.807276 -0.474388 -0.0853928 0.845783 -0.526649 -0.106822 0.841181 -0.530098 -0.147947 -0.231134 0.961607 -0.205594 -0.19037 0.959943 -0.341424 -0.187536 0.92101 -0.424996 -0.166276 0.889793 -0.484351 -0.191566 0.853643 -0.687667 -0.171746 0.70542 -0.647367 -0.132055 0.750652 -0.870212 -0.205275 0.447876 -0.85001 -0.146741 0.505914 -0.0290116 0.220085 0.975049 -0.135872 0.594826 0.792288 0.182442 0.563259 0.805888 -0.290348 0.80843 0.511994 -0.0131303 0.821283 0.57037 -0.143543 0.959647 0.241813 -0.324423 0.910174 0.257551 -0.20939 0.935641 0.284133 -0.489609 0.817053 0.304478 -0.398068 0.854654 0.333329 -0.64164 0.687489 0.340084 -0.575728 0.729367 0.369542 -0.805194 0.474735 0.355373 -0.849342 0.475159 0.229872 -0.891408 0.402876 0.207566 -0.946585 0.322227 0.0121348 -0.938297 0.345671 0.0104781 -0.97139 0.182452 -0.152026 -0.963017 0.211683 -0.166699 -0.146451 -0.756566 0.637307 -0.824707 -0.525747 -0.208444 -0.651392 -0.550804 0.521827 -0.942263 -0.32941 0.0602383 -0.971801 -0.226759 0.064675 -0.978816 -0.19887 0.0486818 -0.989309 -0.125825 0.0737241 -0.993672 -0.0892249 0.0682232 -0.851107 -0.321712 0.414873 -0.873462 -0.365167 0.322051 -0.889404 -0.364277 0.276159 -0.901406 -0.368942 0.226604 -0.895307 -0.378147 0.235439 -0.918229 -0.360526 0.163938 -0.741732 -0.670148 -0.0271188 -0.782194 -0.621534 -0.0432183 -0.708894 -0.684844 0.168694 -0.91196 -0.37347 0.169853 -0.938587 -0.326725 0.110929 -0.786961 -0.579756 -0.211129 -0.849347 -0.436642 -0.29657 -0.792188 -0.400597 -0.460392 -0.856724 -0.152406 -0.492745 -0.843571 -0.133111 -0.520259 -0.884012 0.147448 -0.443602 -0.877483 0.1602 -0.452062 -0.921891 -0.37059 0.113048 -0.959989 -0.265048 0.0903921 -0.891441 -0.381125 -0.245105 -0.944653 -0.183824 -0.271735 -0.941309 -0.170482 -0.29133 -0.970892 0.0271966 -0.237968 -0.965065 0.0518161 -0.256837 -0.0703907 -0.577507 -0.813346 -0.218116 -0.687382 -0.692771 -0.128122 -0.426973 -0.895142 -0.235909 -0.371324 -0.898034 -0.122752 -0.279738 -0.952197 -0.154 0.402697 -0.902286 -0.0814458 0.182024 -0.979915 -0.241039 0.0182409 -0.970344 -0.132202 -0.0321555 -0.990701 -0.0950346 -0.176154 -0.979764 -0.108057 0.572706 -0.812608 -0.222496 0.423725 -0.878039 -0.33394 0.406249 -0.850556 -0.307507 -0.945889 -0.103605 -0.0132373 -0.997954 -0.0625532 -0.11846 -0.924147 -0.363209 -0.217946 -0.894877 -0.38948 -0.0214622 -0.818044 -0.574755 -0.197995 -0.695798 -0.690408 -0.092663 -0.993956 0.0588643 -0.0301034 -0.955594 0.293144 -0.178502 -0.923715 0.338951 -0.112026 -0.749555 0.652394 -0.341451 -0.7038 0.622958 -0.692764 -0.538522 0.479659 -0.714398 -0.618259 0.327705 -0.412913 -0.83441 0.365051 -0.487267 -0.868242 0.0934206 -0.353595 -0.935306 0.0131776 -0.447578 -0.857409 -0.254017 -0.377656 -0.872117 -0.311109 -0.480013 -0.697726 -0.531757 -0.412113 -0.690744 -0.594168 -0.513927 -0.428194 -0.743323 -0.454267 -0.402868 -0.794568 -0.542567 -0.0655809 -0.837449 -0.499061 -0.0365302 -0.865797 -0.553203 0.334479 -0.762948 -0.546581 0.339682 -0.765418 -0.344659 0.399799 -0.849336 -0.287811 0.0135699 -0.957591 -0.346267 -0.0180099 -0.937963 -0.25301 -0.371821 -0.89316 -0.332865 -0.405408 -0.851378 -0.223305 -0.68712 -0.691376 -0.313055 -0.706303 -0.634927 -0.200948 -0.897196 -0.393268 -0.291658 -0.895083 -0.337286 -0.187456 -0.981438 -0.040501 -0.269273 -0.963064 1.23572e-05 -0.179696 -0.923586 0.338671 -0.463508 -0.82164 0.331764 -0.425031 -0.687398 0.588926 -0.484358 -0.643458 0.592755 -0.870905 -0.322273 0.371031 -0.892969 -0.346069 0.287822 -0.690173 -0.631274 0.353772 -0.744779 -0.652222 0.141104 -0.503287 -0.859398 0.090201 -0.593142 -0.789055 -0.159922 -0.545226 -0.810776 -0.213006 -0.633577 -0.660108 -0.403531 -0.588806 -0.661657 -0.464239 -0.677988 -0.431162 -0.595341 -0.639889 -0.413475 -0.64775 -0.718478 -0.111758 -0.686513 -0.691091 -0.0869961 -0.717513 -0.739778 0.248778 -0.62517 -0.726933 0.263368 -0.634196 -0.939621 -0.20215 0.276129 -0.939565 -0.141883 0.311586 -0.938393 -0.127812 0.321064 -0.939692 -0.125107 0.31832 -0.939427 -0.124511 0.319335 -0.939408 -0.124479 0.319401 -0.939888 -0.124255 0.318075 -0.939983 -0.123892 0.317936 -0.939935 -0.124042 0.318018 -0.93977 -0.124285 0.31841 -0.939574 -0.124485 0.318912 -0.939635 -0.21384 0.267132 -0.939832 -0.213503 0.266705 -0.940955 -0.209773 0.265705 -0.939692 -0.213086 0.267533 -0.93996 -0.213373 0.266359 -0.939978 -0.213384 0.266288 -0.939693 -0.212709 0.26783 -0.939472 -0.214147 0.267458 -0.939449 -0.214225 0.267475 -0.939566 -0.1989 0.278667 -0.94337 -0.194139 0.269003 -0.936007 -0.183277 0.3005 -0.939622 -0.181696 0.289995 -0.93966 -0.163871 0.300307 -0.937285 -0.163269 0.30796 -0.94337 -0.135894 0.302631 -0.939621 -0.13806 0.313132 -0.939692 -0.125596 0.318126 -0.149349 -0.584083 0.797836 -0.488792 -0.515334 0.703927 -0.34607 -0.378501 0.858471 -0.655059 -0.304822 0.691362 -0.850962 -0.211892 0.480588 -0.850962 -0.211892 0.480589 -0.850962 -0.24602 0.464046 -0.850963 -0.246019 0.464043 -0.850963 -0.278864 0.44508 -0.850961 -0.278866 0.445084 -0.850961 -0.310257 0.4238 -0.850962 -0.310256 0.423798 -0.655064 -0.446323 0.609661 -0.573443 -0.477865 0.665439 -0.573332 -0.435014 0.694301 -0.573327 -0.435015 0.694304 -0.573327 -0.383777 0.723886 -0.573328 -0.383777 0.723885 -0.573439 -0.337355 0.746565 -0.488788 -0.351953 0.798258 -0.346093 -0.554203 0.75702 -0.202128 -0.573831 0.793639 -0.20209 -0.519987 0.829924 -0.202093 -0.519987 0.829923 -0.202092 -0.458741 0.865283 -0.202095 -0.458741 0.865283 -0.202133 -0.400395 0.893771 -0.149349 -0.398904 0.904749 0.707102 0.240541 -0.664942 0.671181 0.293288 -0.680807 0.706474 0.278389 -0.650688 0.706474 0.35387 -0.61292 0.70647 0.353871 -0.612923 0.706522 0.422874 -0.567455 0.672814 0.443546 -0.592105 0.707096 0.455584 -0.540795 0.706467 -0.278392 0.650694 0.706471 -0.27839 0.650691 0.706471 -0.353871 0.612922 0.70647 -0.353871 0.612923 0.70647 -0.42432 0.566438 0.706474 -0.424317 0.566435 0 0.997954 0.0639373 -0.0265339 0.970062 0.241405 -0.0347816 0.97444 0.221938 2.48024e-05 0.682407 0.730972 2.62157e-05 0.771883 0.635765 -0.0119367 0.807926 0.589163 0.000128994 0.854834 0.518901 -0.0001796 0.918868 0.394566 -0.0156797 0.580416 0.814169 0.010704 0.641745 0.766844 -0.00974445 0.428389 0.903542 -7.59231e-06 0.455774 0.890096 2.6777e-05 0.199215 0.979956 0.0117741 0.227326 0.973748 -0.007876 -0.0223591 0.999719 -1.3764e-05 0.00576813 0.999983 2.53792e-05 -0.235887 0.971781 0.0109336 -0.262885 0.964765 -0.01664 -0.584454 0.811256 0 -0.606524 0.795065 0.696399 -0.419495 0.582282 0.6964 -0.419494 0.582281 0.6964 -0.097661 0.710978 0.3328 -0.22244 0.916387 0.705271 0.00408925 0.708926 0.704462 0.161354 0.691158 0.524011 0.293085 0.799696 0.6964 0.696413 0.173306 0.696402 0.696412 0.173305 0.703501 0.574229 0.418745 0.530088 0.630903 0.56654 0.705271 0.454984 0.543676 0.704461 0.323482 0.631739 0 -0.982085 0.188441 0.0342205 -0.959408 0.279937 0 -0.995518 0.0945682 -0.700682 -0.700692 0.134447 -0.700681 -0.700693 0.134448 -0.994042 -0.0991952 0.0451691 -0.971841 0.214451 -0.0976515 -0.65892 0.651436 -0.376106 -0.108089 0.809169 -0.577549 -0.558293 0.675278 -0.481984 -0.341056 0.765136 -0.546121 -0.237326 0.785809 -0.571123 -0.237622 0.829285 -0.505789 -0.153989 0.855696 -0.494036 -0.23762 0.852669 -0.465288 -0.237425 0.884065 -0.402564 -0.887884 0.374466 -0.267278 -0.739468 0.547936 -0.391093 -0.108169 0.912176 -0.395266 -0.34105 0.855524 -0.389568 -0.65892 0.68458 -0.311728 -0.558602 0.761953 -0.327707 -0.739472 0.61266 -0.278978 -0.971845 0.191781 -0.136885 -0.931696 0.290828 -0.217627 -0.931861 0.314208 -0.181408 -0.658697 0.607529 -0.443877 -0.658919 0.651436 -0.376107 -0.931861 0.314208 -0.181408 -0.931861 0.330195 -0.150356 -0.888088 0.42416 -0.177165 -0.994042 -0.088715 0.0633208 -0.994042 -0.0887153 0.0633211 -0.994053 -0.0929732 0.0567057 -0.994978 -0.0866851 0.0500477 -0.994053 -0.0955948 0.052165 -0.994042 -0.0991953 0.0451691 0 -0.915011 0.403429 0.0635016 -0.898033 0.435322 0 -0.883513 0.468406 0 -0.847408 0.530942 0.0635018 -0.826016 0.560058 0 -0.806885 0.590708 -0.068467 0.81004 0.582364 -0.0983868 0.974273 0.202761 -0.738157 -0.177198 0.650941 -0.933087 -0.124312 0.337484 -0.8858 -0.295631 0.357716 -0.902766 -0.227059 0.365318 -0.90088 -0.206353 0.381882 -0.893729 -0.259451 0.365969 -0.982603 -0.0455829 0.180037 -0.968982 -0.0603372 0.239652 -0.95918 -0.065088 0.275203 -0.978164 -0.0599457 0.199002 -0.993506 -0.0698559 0.0898138 -0.993503 -0.0647569 0.0935872 -0.955076 -0.0799241 0.285379 -0.937214 -0.104396 0.332764 -0.812789 0.174883 0.555689 -0.759743 0.0592678 0.647517 -0.532636 0.189782 0.824792 -0.60033 0.186743 0.777645 -0.364134 0.284403 0.88686 -0.456006 0.283569 0.843592 -0.187413 0.363983 0.912356 -0.145505 -0.525242 0.838421 -0.172299 -0.340281 0.924403 -0.88495 -0.292275 0.362544 -0.712672 -0.349494 0.608237 -0.697726 -0.331468 0.635064 -0.461105 -0.362651 0.809856 -0.423351 -0.334653 0.841892 -0.179693 -0.33856 0.923627 -0.275278 0.0285174 0.960942 -0.918225 -0.157185 0.363532 -0.916086 -0.160331 0.367534 -0.771361 0.00250019 0.636393 -0.722811 -0.136438 0.677443 -0.50333 -0.0902736 0.859366 -0.487233 -0.0935147 0.86825 -0.353638 -0.0132656 0.935288 -0.177309 0.0138881 0.984057 -0.301513 0.368509 0.879369 -0.274908 0.640844 0.71676 -0.876426 0.456207 -0.154115 -0.884047 0.441036 -0.154749 -0.7257 0.638631 -0.255947 -0.739822 0.62185 -0.256839 -0.546204 0.766933 -0.336861 -0.553286 0.761656 -0.337275 -0.333634 0.852481 -0.402449 -0.344987 0.847098 -0.404239 -0.105762 0.89384 -0.435734 -0.121706 0.890012 -0.439394 -0.145532 0.914822 0.376723 -0.171018 0.91375 0.368528 -0.342317 0.862545 0.372605 -0.242324 0.882591 0.402879 -0.521635 0.754582 0.398125 -0.443214 0.785619 0.431699 -0.684278 0.606362 0.405079 -0.629473 0.641013 0.439165 -0.79214 0.460389 0.400694 -0.839077 0.523298 0.148693 -0.858963 0.493728 0.135703 -0.68563 0.720174 0.10612 -0.721168 0.686716 0.0913164 -0.493424 0.86782 0.0584874 -0.546158 0.836614 0.0422896 -0.282721 0.959146 0.0103892 -0.351084 0.936316 -0.00719298 -0.0853895 0.995794 -0.0331981 -0.106821 0.993533 -0.0384872 -0.147949 -0.680971 0.717209 -0.205593 -0.644838 0.736149 -0.341428 -0.622917 0.703848 -0.424998 -0.588897 0.687443 -0.484351 -0.592723 0.643494 -0.687666 -0.501447 0.525039 -0.647365 -0.489689 0.584058 -0.870213 -0.401711 0.285233 -0.85001 -0.380037 0.364766 -0.0290115 -0.296926 0.95446 -0.135869 0.118987 0.983556 0.182414 0.0848534 0.979554 -0.290372 0.444121 0.847609 -0.0131359 0.426065 0.904597 -0.143542 0.710172 0.68924 -0.324416 0.65946 0.678135 -0.209392 0.668223 0.713886 -0.48962 0.555345 0.672208 -0.398067 0.573486 0.716001 -0.641635 0.425343 0.63827 -0.575733 0.446878 0.684713 -0.805194 0.233447 0.545128 -0.849342 0.296564 0.436656 -0.891409 0.245115 0.381194 -0.946585 0.272989 0.171622 -0.938296 0.294123 0.181911 -0.97139 0.234023 -0.0404328 -0.963017 0.266672 -0.0385254 -0.14881 -0.948689 0.279006 -0.824708 -0.351087 -0.44339 -0.651395 -0.737922 0.176512 -0.942264 -0.315395 -0.112535 -0.971801 -0.228718 -0.0573696 -0.978816 -0.196567 -0.0572755 -0.989309 -0.145829 0.000934777 -0.993672 -0.111383 0.0144705 -0.851107 -0.486047 0.198433 -0.873463 -0.477268 0.0963214 -0.889401 -0.453557 0.0570303 -0.901406 -0.432815 0.0117727 -0.895308 -0.445202 0.0148205 -0.918229 -0.394194 -0.0382888 -0.741732 -0.566805 -0.358559 -0.782194 -0.516656 -0.348195 -0.708895 -0.677438 -0.196329 -0.91196 -0.408361 -0.0396374 -0.938587 -0.338416 -0.0672952 -0.786962 -0.396518 -0.47272 -0.849348 -0.229858 -0.475157 -0.792189 -0.11673 -0.599008 -0.856724 0.114383 -0.502932 -0.843571 0.144852 -0.517114 -0.884012 0.349495 -0.310446 -0.877482 0.36477 -0.311396 -0.921889 -0.377468 -0.0873944 -0.959989 -0.274735 -0.0542427 -0.891439 -0.207512 -0.402833 -0.944652 -0.023328 -0.327243 -0.941309 -0.00197655 -0.337542 -0.970892 0.142537 -0.192488 -0.965065 0.173293 -0.19652 -0.0661931 -0.105544 -0.992209 -0.226437 -0.249655 -0.941487 -0.146317 0.133942 -0.980128 -0.165352 0.138726 -0.976429 -0.0926704 0.329021 -0.939765 -0.146664 0.518104 -0.84265 -0.0760683 0.54947 -0.832043 -0.105984 0.829663 -0.548112 -0.133558 0.820953 -0.555156 -0.333936 0.777102 -0.533479 -0.306115 -0.94668 0.100451 -0.276825 -0.756814 -0.592115 0.207911 -0.799855 -0.563032 -0.216184 -0.580267 -0.78521 -0.0427212 -0.503084 -0.863181 -0.123733 -0.297235 -0.946753 -0.0880362 -0.898611 -0.429823 -0.0256589 -0.977819 -0.207876 -0.152042 -0.974618 -0.164329 -0.14545 -0.970854 0.19049 -0.341456 -0.920986 0.187599 -0.692765 -0.706202 0.146135 -0.7144 -0.699279 -0.0253294 -0.412913 -0.905146 -0.101063 -0.487267 -0.79863 -0.353216 -0.353593 -0.816588 -0.456241 -0.447577 -0.615528 -0.648691 -0.37766 -0.599721 -0.705484 -0.480017 -0.338371 -0.809376 -0.412111 -0.301116 -0.859938 -0.513924 0.000837236 -0.857836 -0.454269 0.0483894 -0.88955 -0.542568 0.361929 -0.758042 -0.49906 0.401263 -0.768067 -0.553199 0.671144 -0.493494 -0.546583 0.67688 -0.493032 -0.344664 0.7709 -0.535648 -0.287817 0.490544 -0.822513 -0.346265 0.453386 -0.821305 -0.253008 0.124575 -0.95941 -0.332868 0.0745942 -0.940018 -0.22331 -0.249375 -0.942308 -0.313058 -0.294212 -0.903014 -0.200949 -0.580361 -0.789177 -0.291658 -0.606523 -0.739639 -0.187457 -0.829699 -0.525794 -0.269275 -0.834044 -0.481521 -0.179697 -0.969184 -0.168497 -0.463508 -0.877444 -0.123505 -0.425031 -0.889766 0.166328 -0.484351 -0.853633 0.191611 -0.870905 -0.464612 0.160185 -0.892969 -0.443616 0.076228 -0.690171 -0.723587 -0.00925996 -0.744779 -0.635393 -0.203912 -0.503287 -0.789362 -0.351582 -0.593143 -0.603381 -0.533022 -0.545222 -0.595649 -0.58986 -0.633573 -0.369904 -0.679526 -0.588804 -0.340893 -0.732872 -0.677988 -0.0757255 -0.731162 -0.639888 -0.0342026 -0.767707 -0.718476 0.246472 -0.650418 -0.691089 0.283416 -0.664884 -0.739777 0.528036 -0.417023 -0.726935 0.54518 -0.417545 -0.939621 -0.313131 0.13806 -0.939565 -0.278668 0.198901 -0.938391 -0.271227 0.214146 -0.939692 -0.267506 0.21312 -0.939425 -0.267498 0.214301 -0.939408 -0.267503 0.21437 -0.939888 -0.266646 0.213332 -0.939985 -0.266255 0.213395 -0.939935 -0.266432 0.213391 -0.939771 -0.266838 0.213609 -0.939573 -0.267264 0.213944 -0.939633 -0.318759 0.124424 -0.939832 -0.318252 0.124222 -0.940954 -0.314524 0.12522 -0.939692 -0.318304 0.125147 -0.939957 -0.317969 0.123999 -0.939978 -0.317939 0.123919 -0.939692 -0.318126 0.125594 -0.939471 -0.319187 0.124552 -0.939449 -0.319261 0.124528 -0.939565 -0.311587 0.141883 -0.94337 -0.302631 0.135894 -0.936007 -0.308973 0.168603 -0.939622 -0.30235 0.160295 -0.939661 -0.29207 0.178138 -0.937285 -0.295376 0.185067 -0.94337 -0.269003 0.194139 -0.939621 -0.276129 0.20215 -0.939693 -0.267831 0.212707 -0.149348 -0.904749 0.398904 -0.488784 -0.79826 0.351953 -0.346074 -0.757026 0.554207 -0.655057 -0.609666 0.446327 -0.850962 -0.423798 0.310256 -0.850963 -0.423797 0.310255 -0.850963 -0.445081 0.278864 -0.850962 -0.445082 0.278865 -0.850962 -0.464045 0.24602 -0.850962 -0.464045 0.24602 -0.850962 -0.480589 0.211892 -0.850962 -0.480588 0.211892 -0.655066 -0.691356 0.304819 -0.57344 -0.746564 0.337355 -0.573329 -0.723885 0.383777 -0.573327 -0.723886 0.383778 -0.573327 -0.694304 0.435014 -0.573327 -0.694305 0.435015 -0.573438 -0.665441 0.477867 -0.488787 -0.703929 0.515336 -0.346097 -0.858462 0.378497 -0.202129 -0.893771 0.400396 -0.20209 -0.865283 0.458742 -0.202092 -0.865283 0.458741 -0.202093 -0.829923 0.519986 -0.202093 -0.829923 0.519986 -0.202131 -0.793638 0.573831 -0.149351 -0.797835 0.584083 0.707098 0.540791 -0.455585 0.671181 0.594398 -0.442953 0.70647 0.566439 -0.42432 0.70647 0.612923 -0.353871 0.706469 0.612924 -0.353872 0.706521 0.649948 -0.279993 0.672813 0.680175 -0.291005 0.7071 0.664943 -0.240542 0.70647 -0.566439 0.42432 0.70647 -0.566439 0.42432 0.70647 -0.612923 0.353871 0.706471 -0.612923 0.353871 0.706471 -0.65069 0.27839 0.706471 -0.65069 0.27839 0.694741 0.591017 -0.409921 0.487517 -0.0722197 -0.870122 0.69474 0.591017 -0.409921 0.702915 0.371318 -0.606657 0.494621 0.370809 -0.786035 0.705015 0.201062 -0.680094 0.703698 0.0288466 -0.709914 0.704395 -0.155725 -0.692516 0.704395 -0.320214 -0.633476 0.487515 -0.497605 -0.717439 0.694741 -0.716796 0.0594936 0.69474 -0.716797 0.0594933 0.702914 -0.672357 -0.232051 0.494619 -0.786036 -0.370809 0.705013 -0.587665 -0.396998 0.703695 -0.473721 -0.52953 0.701597 0.615913 -0.358349 0.701594 0.615915 -0.358349 0.701595 0.701612 -0.124518 0.701597 0.70161 -0.124519 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.821701 -0.569919 0 -0.980521 0.196415 -0.0478519 -0.995432 0.0826202 -0.0190429 -0.999799 -0.00624285 0.0231321 -0.966841 -0.25433 -0.00911224 -0.666714 -0.745258 0.0343673 -0.775797 -0.630045 0.00482579 -0.828627 -0.55978 -0.0054592 -0.94527 -0.326242 -0.00780371 -0.219383 -0.975608 -1.74782e-05 -0.254834 -0.966985 2.41978e-05 -0.451127 -0.89246 -1.24801e-05 -0.451021 -0.892513 -8.17829e-06 -0.584763 -0.811204 -0.0167062 0.346661 -0.937842 0.0109689 0.171857 -0.985061 -0.0114746 0.0405977 -0.99911 2.36786e-05 -0.0303645 -0.999539 1.71009e-05 -0.133727 -0.991018 -0.0265309 0.846685 -0.531433 0.0157208 0.559274 -0.828834 1.73986e-05 0.522046 -0.852917 -7.05464e-06 0.283509 -0.95897 0 0.865062 -0.501666 0.000562933 0.864348 -0.502893 -0.000568737 0.984614 -0.174744 0 0.984868 -0.173308 0 -0.800345 0.59954 0 -0.800345 0.59954 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.919389 0.393349 0 -0.919389 0.393349 0 0.919389 -0.393349 0 0.919389 -0.393349 0 0.866025 -0.5 0 0.866025 -0.5 0 0.800345 -0.599539 0 0.800345 -0.599539 0.879241 -0.459539 0.125533 0.887082 -0.458782 0.0510247 0.954993 -0.285017 -0.0821845 0.960101 -0.265301 -0.0884358 0.978436 -0.198165 -0.058261 0.978976 -0.195525 -0.0581036 0.991397 -0.130838 0.00378118 0.990797 -0.135349 0.00127317 0.965171 0.180108 -0.189752 0.793206 -0.0945543 -0.601567 0.859467 0.147705 -0.489388 0.839105 0.150363 -0.522775 0.884191 0.365193 -0.291274 0.876485 0.372182 -0.305376 0.859292 -0.373911 -0.349009 0.938544 -0.334264 -0.0860372 0.933187 -0.352126 -0.0719026 0.821647 -0.298601 -0.485525 0.847484 -0.221375 -0.482456 0.891282 -0.194745 -0.409501 0.947044 0.0001729 -0.321104 0.938319 0.00095155 -0.34577 0.970911 0.147725 -0.188438 0.989048 0.0715403 -0.129096 0.807335 -0.563509 -0.175122 0.693242 -0.549747 -0.46604 0.77072 -0.34044 -0.538601 0.902132 -0.430842 -0.0230746 0.887847 -0.456659 0.0564862 0.749551 -0.661885 -0.00903366 0.710135 -0.704054 0.00404469 0.275997 -0.798645 -0.534783 0.145868 -0.989304 -0.000656022 0.197819 -0.967482 0.157628 0.147939 -0.969314 0.196326 0.111225 0.551324 -0.826844 0.0953814 0.841734 -0.5314 0.105771 0.842778 -0.527766 0.0780649 -0.0376054 -0.996239 0.143595 0.158821 -0.976809 0.177642 0.17007 -0.969288 0.0973067 0.33693 -0.936488 0.110869 0.551254 -0.826939 0.0290551 -0.966775 -0.253973 0.134958 -0.774472 -0.618045 -0.130549 -0.799806 -0.58589 0.15626 -0.589494 -0.792515 0.216095 -0.552274 -0.805168 0.0506064 -0.454851 -0.889129 0.143392 -0.209354 -0.967269 0.273418 -0.271016 -0.922926 0.142387 -0.145985 -0.978986 0.354228 -0.799964 -0.484335 0.457114 -0.563086 -0.688463 0.363177 -0.604352 -0.709127 0.490835 -0.273167 -0.827322 0.397296 -0.30651 -0.86499 0.522595 0.0645725 -0.850132 0.442839 0.0477907 -0.895327 0.546613 0.408774 -0.730834 0.493391 0.409083 -0.767604 0.553361 0.689518 -0.467287 0.546233 0.69179 -0.472288 0.176406 -0.829053 -0.530615 0.30266 -0.548174 -0.779681 0.186327 -0.583984 -0.790092 0.325671 -0.222736 -0.918873 0.208476 -0.254809 -0.944251 0.343263 0.143623 -0.928193 0.241856 0.123318 -0.962444 0.351504 0.503629 -0.789179 0.282648 0.498079 -0.819772 0.345027 0.791879 -0.503868 0.333669 0.792957 -0.509789 0.879549 -0.458701 0.126439 0.763483 -0.628764 0.147478 0.693958 -0.710573 0.116222 0.651408 -0.743627 0.150623 0.484443 -0.85958 0.162596 0.918301 -0.391642 -0.0577977 0.901023 -0.430768 -0.0509522 0.758732 -0.596297 -0.262212 0.805309 -0.54705 -0.228503 0.700506 -0.628348 -0.338333 0.633801 -0.769788 -0.0756557 0.461116 -0.879322 -0.119014 0.425664 -0.895111 0.132613 0.341471 -0.926946 0.155465 0.17221 -0.964761 -0.198945 0.179192 -0.963225 -0.200221 0.424095 -0.89077 -0.163318 0.486873 -0.787802 -0.377257 0.502663 -0.778301 -0.376267 0.601388 -0.558667 -0.57116 0.531867 -0.601584 -0.595998 0.642844 -0.313504 -0.698904 0.575096 -0.346743 -0.740969 0.685234 -0.0200388 -0.728048 0.62921 -0.0348513 -0.776454 0.721675 0.287694 -0.629617 0.685623 0.290625 -0.667426 0.73994 0.547492 -0.390823 0.725681 0.555114 -0.406492 0.14616 -0.602446 0.784663 0.106528 0.861075 -0.497194 0.826272 0.228733 0.514739 0.651431 -0.502274 0.568646 0.880895 -0.29434 0.370658 0.992268 -0.0442004 0.115974 0.992327 -0.0815851 0.0929047 0.976265 -0.0381605 0.213193 0.978908 -0.0485424 0.198453 0.963204 -0.0549822 0.263087 0.942932 -0.0528936 0.328758 0.902137 -0.211905 0.375827 0.8958 -0.222273 0.384886 0.919326 -0.14958 0.363957 0.851017 -0.410402 0.327628 0.740543 0.0465455 0.670395 0.783615 0.0676985 0.617547 0.707955 -0.148614 0.690444 0.912307 -0.15756 0.377983 0.939733 -0.0982583 0.327485 0.785901 0.228432 0.574612 0.847487 0.307107 0.432956 0.79326 0.473675 0.382584 0.856963 0.497199 0.135675 0.844209 0.52384 0.113591 0.884164 0.438012 -0.162481 0.877675 0.445627 -0.17636 0.923008 -0.103749 0.37053 0.960832 -0.0760319 0.266499 0.891327 0.257212 0.373334 0.944822 0.277164 0.174616 0.94184 0.296162 0.158822 0.970919 0.23703 -0.0336482 0.965173 0.254388 -0.0610589 0.244537 0.733117 0.634619 0.169573 0.727972 0.664306 0.0807678 0.848094 0.523654 0.126157 0.907052 0.401674 0.22558 0.913361 0.338948 0.0935057 0.968446 0.231017 0.334009 0.835706 -0.435929 0.185737 0.869116 -0.45841 -0.00744022 0.997275 -0.0733926 0.309748 0.938996 -0.149475 0.10402 0.992056 0.070738 0.333005 0.159697 0.929303 -0.0466977 0.099898 0.993901 0.150511 0.409734 0.899702 0.201354 0.424527 0.882742 0.0641965 0.572892 0.817113 0.110742 0.670195 0.733877 0.0768452 -0.0284997 0.996636 0.0754003 -0.2656 0.96113 0.190221 -0.305326 0.933055 0.0915652 -0.627708 0.773045 0.341461 -0.598171 0.72498 0.693992 -0.455932 0.557226 0.714749 -0.304528 0.6296 0.412198 -0.338776 0.845768 0.486913 -0.0670923 0.87087 0.354189 0.0195536 0.934969 0.447651 0.282044 0.848563 0.378512 0.341527 0.860284 0.48013 0.554489 0.679718 0.413098 0.618123 0.668785 0.514059 0.757179 0.403018 0.455184 0.80815 0.373768 0.542691 0.839113 0.0370994 0.499641 0.866216 0.00529308 0.553285 0.750967 -0.360449 0.546658 0.753116 -0.366035 0.34468 0.834924 -0.429066 0.28826 0.956357 -0.0478258 0.346233 0.938046 -0.0138643 0.253711 0.905717 0.339571 0.332839 0.864551 0.376522 0.224037 0.715182 0.662059 0.313051 0.658168 0.6847 0.201546 0.424489 0.882717 0.291661 0.366879 0.883365 0.187843 0.0747703 0.979349 0.269294 0.0320532 0.962525 0.179208 -0.308319 0.93425 0.463856 -0.301224 0.833128 0.425706 -0.562434 0.708832 0.484451 -0.570638 0.663083 0.875353 -0.350036 0.333514 0.889584 -0.276392 0.363659 0.689707 -0.334228 0.642336 0.745684 -0.115742 0.656171 0.502636 -0.0632218 0.862183 0.593259 0.185339 0.783386 0.54628 0.241329 0.802084 0.633762 0.424751 0.646477 0.590002 0.487126 0.643899 0.678249 0.609117 0.41104 0.640945 0.661601 0.389196 0.7187 0.689675 0.0884178 0.691734 0.719593 0.0607501 0.739911 0.616199 -0.26987 0.727071 0.624336 -0.285609 0.572894 -0.70982 0.409815 0.850725 -0.420015 0.315996 0.879517 -0.437896 0.186272 0.654679 -0.694973 0.297336 0.764994 -0.592121 0.253332 0.845143 -0.490095 0.213401 0.851115 -0.469976 0.233936 0.850697 -0.455232 0.262828 0.850697 -0.455232 0.262828 0.851114 -0.437583 0.290044 0.345783 -0.862676 0.369085 0.488416 -0.802269 0.343241 0.149207 -0.909097 0.388946 0.201912 -0.899073 0.388457 0.201872 -0.848196 0.489706 0.844349 -0.42882 0.32123 0.654699 -0.604972 0.453186 0.573015 -0.658621 0.487722 0.488419 -0.698388 0.523164 0.345769 -0.75098 0.56256 0.573015 -0.75169 0.326521 0.572894 -0.70982 0.409815 0.201872 -0.848196 0.489706 0.201912 -0.78595 0.584392 0.149217 -0.791385 0.592827 0.340892 0.752407 -0.563629 0.994035 -0.0944505 0.054531 0.994036 -0.0871409 0.06556 0.994251 -0.0857001 0.0641981 0.991754 -0.117931 0.0501654 0.996676 -0.0729359 0.0363047 0.658679 0.651618 -0.376212 0.931791 0.314364 -0.181498 0.994046 -0.0994072 0.0446273 0.993745 0.102671 -0.0439265 0.971837 0.216659 -0.0926949 0.994056 -0.0907463 0.060149 0.994035 -0.0944505 0.054531 0.93179 0.314365 -0.181498 0.931639 0.336606 -0.136916 0.558446 0.655448 -0.508455 0.739313 0.538922 -0.403707 0.931791 0.290522 -0.21763 0.888072 0.360854 -0.284803 0.971842 0.188586 -0.14127 0.237289 0.841291 -0.48572 0.237289 0.777487 -0.582416 0.108129 0.78682 -0.607637 0.887837 0.423064 -0.181003 0.739297 0.619098 -0.264874 0.658467 0.694532 -0.289906 0.558107 0.762881 -0.326389 0.340888 0.864321 -0.369789 0.658679 0.602199 -0.451108 0.658678 0.651619 -0.376212 0.237287 0.841291 -0.48572 0.23719 0.895749 -0.375999 0.108041 0.914007 -0.391047 0.939515 -0.315178 0.13407 0.939603 -0.322721 0.114005 0.93949 -0.323054 0.113992 0.939578 -0.32274 0.114158 0.939697 -0.322086 0.11502 0.939842 -0.322105 0.113773 0.939864 -0.322065 0.113706 0.939744 -0.322357 0.113874 0.939508 -0.273714 0.205927 0.939902 -0.259373 0.222056 0.939805 -0.259768 0.222006 0.93969 -0.260669 0.221437 0.939697 -0.260515 0.221587 0.939546 -0.260228 0.222566 0.939485 -0.260238 0.222812 0.939529 -0.26021 0.222657 0.939643 -0.260008 0.222413 0.939777 -0.259725 0.222174 0.939515 -0.273698 0.205915 0.939511 -0.273707 0.205921 0.939693 -0.28508 0.188959 0.939694 -0.285079 0.18896 0.939498 -0.296661 0.171277 0.939498 -0.296661 0.171278 0.939694 -0.306183 0.152406 0.939694 -0.306184 0.152406 0.939511 -0.315187 0.134075 0.939508 -0.315196 0.134078 0.93969 -0.322182 0.114812 -0.697588 -0.697598 -0.163488 -0.697587 -0.697599 -0.163488 -0.697588 -0.552319 -0.456416 -0.638172 -0.60461 -0.476638 -0.707007 -0.440824 -0.553005 -0.697587 -0.292015 -0.654293 -0.697588 -0.292015 -0.654292 -0.697589 0.029103 -0.715907 -0.69759 0.0291033 -0.715906 -0.707009 0.204831 -0.676892 -0.685363 0.270461 -0.676113 -0.825857 0.323366 -0.461947 -0.701045 0.602934 -0.380797 -0.600135 0.655933 -0.457811 -0.706726 0.496193 -0.504313 -0.699418 0.357641 -0.618796 -0.458499 0.712315 0.5314 -0.694741 0.66072 -0.284227 -0.694737 0.660722 -0.284229 -0.705697 0.707421 -0.0393293 -0.754938 0.65577 0.00583053 -0.624889 0.764164 0.159894 -0.705015 0.683368 0.189634 -0.703698 0.617455 0.351509 -0.704397 0.504947 0.498852 -0.704397 0.367753 0.607111 -0.458491 0.351185 0.816367 -0.694736 -0.430088 0.576512 -0.694738 -0.430087 0.57651 -0.702914 -0.15925 0.693218 -0.46676 -0.103545 0.878301 -0.705014 0.0255164 0.708734 -0.703698 0.198281 0.682271 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706177 0.637125 -0.308847 -0.706174 0.637127 -0.308848 -0.706175 0.586033 -0.397344 -0.706178 0.58603 -0.397343 0 0.813937 -0.580953 -0.04202 0.826955 -0.560695 0 0.853738 -0.520703 0 0.899849 -0.436202 -0.0629303 0.908285 -0.413593 0 0.877811 -0.479008 -0.706177 -0.637125 0.308847 -0.706175 -0.637127 0.308847 -0.706174 -0.586033 0.397344 -0.706174 -0.586034 0.397345 0 0.918609 -0.395167 0 -0.686624 0.727012 0.0323185 -0.597643 0.801111 0.0129609 -0.525174 0.850896 -0.0156222 -0.296128 0.955021 0.0036903 -0.223893 0.974607 -0.00326083 0.0359793 0.999347 -0.02515 0.131804 0.990957 3.37981e-05 0.711387 0.7028 -4.04636e-05 0.496586 0.867987 -0.00662082 0.518092 0.8553 0.00506907 0.279069 0.960258 0.0225872 0.894793 -0.445909 -0.013392 0.998873 -0.0455433 -1.5106e-05 0.999961 0.00889079 3.11858e-07 0.980891 0.194559 0.00404012 0.963579 0.267392 -0.00869061 0.930196 0.366961 0.00792479 0.869017 0.494719 -0.00304958 0.816471 0.577378 0.00555033 0.692854 0.721056 0 0.835836 -0.548979 -0.00561605 0.845478 -0.533981 0.000789755 0.701345 -0.712822 -0.00753284 0.55511 -0.831743 0.0100101 0.500372 -0.865752 -0.000486295 0.338593 -0.940933 0.000207064 0.289634 -0.957137 -0.00316903 0.150776 -0.988563 0.0212952 0.0406096 -0.998948 -0.000796771 -0.0980041 -0.995186 0.00077801 -0.284746 -0.958603 0.0220046 -0.407459 -0.912958 -0.0019994 -0.499237 -0.866463 0.000195932 -0.623331 -0.781958 -0.00580835 -0.785303 -0.619085 0.0051454 -0.767681 -0.640812 0 -0.97362 -0.228176 0.00804787 -0.977629 -0.210181 -0.000448907 -0.898647 -0.438673 0 0.88161 0.471979 -0.0376688 0.821118 0.569515 -0.0154258 0.768961 0.639109 0.0283308 0.521837 0.852575 1.24653e-05 -0.451127 0.89246 -0.0268651 -0.524559 0.85095 7.16991e-05 -0.417823 0.908528 -0.000100443 -0.21939 0.975637 -1.1858e-05 -0.21911 0.9757 -5.62156e-06 0.0406004 0.999175 -0.0342169 -0.0612146 0.997538 0.0537476 0.283099 0.957584 0.00712739 0.194984 0.980781 -0.00709946 0.584004 0.81172 0 -0.996573 -0.0827149 -0.0330451 -0.991356 -0.126974 0.0252543 -0.944983 0.326143 -0.00777989 -0.9629 0.269747 5.33774e-06 -0.890922 0.454156 -8.04367e-06 -0.828637 0.559787 -0.0189329 -0.86251 0.505686 0.0359315 -0.666311 0.744808 -0.035276 -0.757031 0.652426 2.57615e-05 -0.611951 0.790896 0 -0.919389 -0.393349 0 -0.919389 -0.393349 0 -0.866025 -0.5 0 -0.866025 -0.5 0 -0.800345 -0.59954 0 -0.800345 -0.59954 0 0.800345 0.599539 0 0.800345 0.599539 0 0.866025 0.5 0 0.866025 0.5 0 0.919389 0.393349 0 0.919389 0.393349 0.87924 -0.338485 -0.335209 0.887083 -0.273581 -0.371803 0.954993 -0.0713332 -0.287922 0.960101 -0.0560632 -0.273975 0.978436 -0.0486274 -0.200746 0.978976 -0.0474433 -0.198381 0.991396 -0.0686935 -0.111419 0.990797 -0.0687769 -0.116579 0.965171 0.254385 0.0611022 0.793206 0.473696 -0.38267 0.859466 0.497676 -0.116778 0.839107 0.527916 -0.131169 0.884192 0.434846 0.170629 0.876485 0.450554 0.169631 0.859293 0.115291 -0.498321 0.938544 -0.0926215 -0.3325 0.933186 -0.113794 -0.340902 0.821647 0.271178 -0.501358 0.847484 0.307133 -0.432944 0.891282 0.257266 -0.373404 0.947044 0.278171 -0.160401 0.938319 0.299922 -0.17206 0.970911 0.237055 0.033715 0.989048 0.14757 -0.00259267 0.807335 -0.130097 -0.575574 0.693241 0.128731 -0.709116 0.770718 0.296225 -0.564131 0.902132 -0.195436 -0.384658 0.887846 -0.277248 -0.367236 0.74955 -0.323119 -0.577728 0.710135 -0.355529 -0.607707 0.048096 0.251966 -0.96654 0.183342 0.457831 -0.869929 0.0890387 0.443843 -0.89167 0.275998 0.0638111 -0.959038 0.162588 -0.384726 -0.908598 0.243777 0.0159821 -0.9697 0.0759189 0.0873325 -0.993282 0.076241 -0.211139 -0.974478 0.129212 -0.584998 -0.800676 0.196021 -0.620435 -0.759365 0.149367 -0.730714 -0.666143 0.105771 0.878448 0.465985 0.0427788 0.94358 -0.328369 0.117379 0.991456 -0.0569046 0.222639 0.973394 0.0541923 0.040514 0.984376 0.171357 0.201097 0.849125 0.488412 0.0855579 0.618202 -0.781349 0.1107 0.669771 -0.73427 0.21036 0.718352 -0.663113 0.00586343 0.823987 -0.566578 0.242001 0.931063 -0.273051 0.354226 0.0194649 -0.934957 0.457112 0.314684 -0.831879 0.363173 0.311947 -0.877949 0.490831 0.579898 -0.650233 0.397301 0.595846 -0.697939 0.522597 0.768521 -0.369145 0.44284 0.79927 -0.406276 0.546614 0.837307 -0.0114076 0.493392 0.869306 -0.0295257 0.553361 0.749441 0.363497 0.546232 0.754909 0.362964 0.176415 0.0449985 -0.983287 0.30267 0.401135 -0.86457 0.186333 0.392246 -0.900791 0.325675 0.684399 -0.65233 0.20847 0.690341 -0.692799 0.343262 0.875651 -0.339716 0.241854 0.89516 -0.374426 0.351502 0.935264 0.0415662 0.28265 0.958983 0.0214642 0.345026 0.832303 0.433854 0.333669 0.837968 0.431827 0.879549 -0.338851 -0.334026 0.763486 -0.442101 -0.470781 0.693958 -0.455938 -0.557264 0.651408 -0.502256 -0.568688 0.484444 -0.570601 -0.66312 0.918301 -0.145767 -0.368071 0.901023 -0.171258 -0.398532 0.758735 -0.0710666 -0.647511 0.805308 -0.0756361 -0.588013 0.700506 -0.0211698 -0.713333 0.633799 -0.319373 -0.704485 0.461115 -0.33659 -0.821024 0.425664 -0.5624 -0.708884 0.341474 -0.598107 -0.725026 0.233128 -0.293099 -0.927224 0.179195 -0.308215 -0.934287 0.424095 -0.303947 -0.853088 0.486873 -0.0671868 -0.870885 0.502657 -0.0632947 -0.862166 0.601384 0.215307 -0.769403 0.531868 0.215359 -0.818985 0.642845 0.448517 -0.620953 0.575096 0.468327 -0.670772 0.685234 0.620488 -0.381378 0.629211 0.655002 -0.418409 0.721675 0.689111 -0.065658 0.685622 0.723322 -0.0820253 0.739939 0.612209 0.278731 0.72568 0.62959 0.277497 0.146157 -0.980762 -0.1294 0.826271 -0.33141 0.455459 0.651432 -0.743598 -0.150659 0.880894 -0.468172 -0.0695796 0.992268 -0.122537 0.0197084 0.992327 -0.12125 -0.024202 0.976264 -0.203712 0.0735515 0.978908 -0.196136 0.0571865 0.963206 -0.255324 0.0839231 0.942932 -0.31116 0.118572 0.902136 -0.431429 0.00439823 0.8958 -0.444458 -5.01744e-05 0.919326 -0.389987 0.0524382 0.851017 -0.488935 -0.191603 0.740542 -0.557307 0.375507 0.783616 -0.500961 0.367402 0.707955 -0.67225 0.216518 0.912305 -0.406126 0.0525404 0.939733 -0.332739 0.0786496 0.785901 -0.383411 0.485135 0.847486 -0.221398 0.482442 0.793259 -0.094491 0.601508 0.856962 0.131102 0.498425 0.844208 0.163548 0.510455 0.884163 0.35972 0.298089 0.877675 0.375545 0.297744 0.923011 -0.372756 0.0954146 0.960831 -0.268811 0.0674045 0.891326 -0.194711 0.40942 0.944822 -0.012639 0.327339 0.941841 0.0105364 0.335895 0.97092 0.147655 0.18845 0.965173 0.180073 0.189776 0.11517 0.761084 0.638347 0.0771108 0.578423 0.812085 0.146472 0.546422 0.824602 0.0440322 0.191725 0.98046 0.0571086 0.185864 0.980914 0.0998392 -0.0736365 0.992275 0.181856 -0.212377 0.960117 0.334009 0.795378 0.505779 0.105774 0.842735 0.527835 0.278923 0.844697 0.456825 0.0122564 -0.815076 0.579224 0.315352 -0.737905 0.596698 0.112604 -0.862125 0.494024 0.136034 -0.230056 0.963623 0.0636135 -0.422633 0.904066 0.20285 -0.552195 0.808661 0.247985 -0.530595 0.810538 0.108767 -0.616331 0.77994 0.0842295 -0.890467 0.447185 0.0328513 -0.963027 0.267395 0.190216 -0.960713 0.202109 0.0915608 -0.983331 -0.157088 0.341472 -0.926933 -0.15554 0.693994 -0.710536 -0.116234 0.714751 -0.697512 0.0510703 0.4122 -0.901844 0.129495 0.486915 -0.787741 0.37733 0.354184 -0.79993 0.484422 0.447647 -0.593854 0.668543 0.378518 -0.574265 0.725908 0.480136 -0.311411 0.820057 0.4131 -0.270123 0.869702 0.51406 0.0295648 0.857244 0.455184 0.0803828 0.886762 0.54269 0.387428 0.745243 0.499642 0.428524 0.752812 0.553286 0.687642 0.470132 0.546659 0.693553 0.4692 0.344677 0.789045 0.508532 0.288259 0.519597 0.804317 0.346234 0.481029 0.80544 0.253712 0.158781 0.954159 0.332839 0.106198 0.936985 0.224035 -0.215769 0.950396 0.313048 -0.263883 0.912341 0.201541 -0.552212 0.808977 0.291659 -0.581579 0.759408 0.187842 -0.810756 0.554428 0.269287 -0.817544 0.509025 0.179201 -0.963246 0.200113 0.463857 -0.872121 0.155696 0.425706 -0.895083 -0.132668 0.484448 -0.859568 -0.162646 0.875354 -0.463849 -0.136381 0.889584 -0.453134 -0.0575338 0.689708 -0.723393 0.0317166 0.745684 -0.626131 0.227849 0.50264 -0.778282 0.376339 0.593261 -0.585761 0.552201 0.546279 -0.573959 0.610042 0.63376 -0.347488 0.691086 0.590005 -0.314071 0.74381 0.678251 -0.0514149 0.73303 0.640945 -0.00625309 0.767561 0.7187 0.268266 0.641485 0.691734 0.307186 0.653561 0.739911 0.541814 0.398709 0.727071 0.559513 0.397886 0.572894 -0.70982 -0.409815 0.850726 -0.483668 -0.205746 0.879516 -0.380266 -0.286094 0.654679 -0.604987 -0.453196 0.764998 -0.515449 -0.386123 0.845143 -0.429858 -0.317735 0.851115 -0.437584 -0.290041 0.850697 -0.455231 -0.262828 0.850697 -0.455232 -0.262828 0.851115 -0.469975 -0.233939 0.345784 -0.750975 -0.562556 0.488417 -0.698389 -0.523164 0.149205 -0.791386 -0.592829 0.201912 -0.78595 -0.584392 0.201872 -0.848196 -0.489706 0.844348 -0.492604 -0.210755 0.6547 -0.694956 -0.297328 0.573015 -0.75169 -0.326521 0.488417 -0.802268 -0.343241 0.345778 -0.862678 -0.369086 0.573015 -0.658621 -0.487722 0.572894 -0.70982 -0.409815 0.201872 -0.848196 -0.489706 0.201912 -0.899074 -0.388456 0.149215 -0.909096 -0.388946 0.340892 0.86432 0.369789 0.994035 -0.0944506 -0.054531 0.994036 -0.100347 -0.0426863 0.994251 -0.098447 -0.0421194 0.991754 -0.10241 -0.0770486 0.996675 -0.0679106 -0.0450137 0.658678 0.651619 0.376212 0.93179 0.314364 0.181498 0.994046 -0.088352 -0.0637755 0.993745 0.0893768 0.0669523 0.971837 0.188606 0.141285 0.994056 -0.0974635 -0.0485145 0.994035 -0.0944505 -0.054531 0.931791 0.314364 0.181498 0.931639 0.286875 0.223051 0.558446 0.768059 0.313406 0.739312 0.619083 0.264867 0.93179 0.333735 0.142785 0.888072 0.427073 0.170107 0.971843 0.216637 0.0926854 0.237287 0.841291 0.48572 0.237287 0.893131 0.382115 0.108128 0.919639 0.377588 0.887838 0.368284 0.275882 0.739295 0.538938 0.403719 0.658467 0.598333 0.45653 0.558107 0.664102 0.49748 0.340888 0.752408 0.56363 0.658679 0.69177 0.295966 0.658679 0.651618 0.376212 0.237289 0.841291 0.485719 0.237192 0.773499 0.587742 0.108041 0.79566 0.59603 0.939515 -0.273697 -0.205917 0.939604 -0.260091 -0.222482 0.93949 -0.260247 -0.222777 0.939579 -0.260233 -0.22242 0.939697 -0.260651 -0.221426 0.939842 -0.259585 -0.222065 0.939865 -0.259504 -0.222064 0.939743 -0.259798 -0.222234 0.939508 -0.315195 -0.13408 0.939902 -0.321993 -0.113596 0.939805 -0.322147 -0.113965 0.93969 -0.322105 -0.115026 0.939697 -0.322158 -0.11482 0.939545 -0.322864 -0.11408 0.939486 -0.323073 -0.11397 0.939528 -0.322933 -0.114021 0.939644 -0.322615 -0.113967 0.939777 -0.322271 -0.113844 0.939515 -0.315178 -0.134072 0.939511 -0.315186 -0.134077 0.939694 -0.306182 -0.152409 0.939694 -0.306183 -0.152408 0.939498 -0.296661 -0.171277 0.939498 -0.296662 -0.171278 0.939693 -0.285079 -0.188961 0.939694 -0.28508 -0.188958 0.939511 -0.273705 -0.205922 0.939508 -0.273713 -0.205929 0.93969 -0.26052 -0.221613 0 0.984834 0.173499 -0.00049346 0.984614 0.174744 0.000540489 0.864348 0.502893 0 0.865034 0.501714 0.701597 0.70161 0.124518 0.701595 0.701612 0.124519 0.701594 0.615915 0.35835 0.701596 0.615913 0.358348 -0.000353936 -0.221074 0.975257 0.00621434 -0.316783 0.948478 0.0220233 -0.407459 0.912958 -0.00551235 -0.512456 0.858696 8.28103e-06 -0.623331 0.781958 6.71917e-06 -0.660686 0.750663 0.00828479 -0.785289 0.619074 -0.0205009 -0.837015 0.546796 0.0193287 -0.973438 0.228133 0 -0.985784 0.168016 0.000876404 -0.0877223 0.996145 0.021286 0.0406081 0.998948 -0.0033061 0.151212 0.988496 0.000182361 0.289648 0.957133 -0.000469835 0.338883 0.940828 0.010016 0.500371 0.865753 -0.00637853 0.551607 0.83408 0.00768569 0.819995 0.572319 0 0.833458 0.552583 -0.697586 0.587544 0.410079 -0.697585 0.587546 0.41008 -0.70452 0.406979 0.581394 -0.786896 0.308787 0.534271 -0.685363 0.270461 0.676113 -0.707006 0.204842 0.676892 -0.697586 0.0291031 0.71591 -0.697589 0.0291022 0.715907 -0.697588 -0.292015 0.654292 -0.697588 -0.697598 0.163488 -0.697587 -0.697599 0.163488 -0.699418 -0.561276 0.442475 -0.646819 -0.587889 0.485811 -0.707007 -0.440824 0.553006 -0.697587 -0.292015 0.654293 -0.694736 -0.430089 -0.576512 -0.458503 0.351182 -0.816362 -0.694738 -0.430087 -0.57651 -0.702914 -0.15925 -0.693218 -0.46676 -0.103545 -0.878301 -0.705014 0.0255164 -0.708734 -0.703698 0.198284 -0.682271 -0.694741 0.660719 0.284228 -0.694737 0.660723 0.284228 -0.702913 0.711248 -0.00632381 -0.782475 0.621722 0.0345648 -0.561453 0.797377 -0.221271 -0.701772 0.6973 -0.145903 -0.703698 0.617455 -0.351509 -0.458499 0.712315 -0.5314 -0.704397 0.504947 -0.498852 -0.704396 0.36775 -0.607113 -0.700681 -0.700693 -0.134448 -0.700682 -0.700692 -0.134448 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 0.586031 0.397343 -0.706175 0.586033 0.397344 -0.706175 0.637127 0.308848 -0.706177 0.637125 0.308847 0 0.910089 0.414414 -0.04202 0.899054 0.435817 0 0.877811 0.479008 0 0.827686 0.561191 -0.0629303 0.812324 0.579801 0 0.853738 0.520703 -0.706174 -0.586034 -0.397345 -0.706174 -0.586033 -0.397344 -0.706175 -0.637127 -0.308847 -0.706177 -0.637125 -0.308847 0 -0.959822 -0.280609 0.0173645 -0.981937 -0.188412 0 -0.995631 -0.0933765 0 0.86671 0.498812 0.0262992 0.918292 0.39503 0.0108382 0.949093 0.31481 -0.0197306 0.999766 -0.00888905 0.00457738 0.518093 -0.855312 -6.76604e-05 0.541341 -0.840803 8.61019e-05 0.711387 -0.7028 -0.00521408 0.728755 -0.684755 0.00478476 0.869034 -0.494729 0.0130121 0.846554 -0.532144 -0.0208406 0.963378 -0.267336 -0.00416534 0.946938 -0.32139 0.00493713 0.997842 0.0654749 0 -0.597955 -0.80153 0.0272972 -0.640656 -0.767342 -0.0219137 -0.22384 -0.974379 0.00552666 -0.290895 -0.956739 -4.17609e-06 -0.0865246 -0.99625 7.27486e-06 0.0359795 -0.999353 0.0147481 -0.0374017 -0.999192 -0.0292798 0.278958 -0.959857 0.0251986 0.142828 -0.989427 -0.00320754 0.371539 -0.928412 -0.994042 -0.0887149 -0.0633209 -0.971841 0.191795 0.136895 -0.658919 0.651436 0.376107 -0.108088 0.904757 0.411986 -0.558295 0.755048 0.343815 -0.341052 0.855524 0.389568 -0.237324 0.887511 0.394969 -0.23762 0.852669 0.465288 -0.153989 0.855696 0.494036 -0.237622 0.829285 0.505789 -0.237427 0.790663 0.564341 -0.887884 0.418702 0.190658 -0.739467 0.612665 0.27898 -0.108166 0.798398 0.592335 -0.341056 0.765136 0.546121 -0.658919 0.612255 0.437001 -0.558599 0.66478 0.496019 -0.739474 0.547931 0.391089 -0.971845 0.214436 0.0976447 -0.931697 0.333884 0.14305 -0.931861 0.314207 0.181408 -0.658697 0.688173 0.304197 -0.65892 0.651436 0.376107 -0.931861 0.314208 0.181408 -0.931861 0.29531 0.210779 -0.888089 0.365509 0.278751 -0.994042 -0.0991952 -0.0451691 -0.994042 -0.0991953 -0.0451691 -0.994053 -0.0955951 -0.0521644 -0.994978 -0.086685 -0.0500477 -0.994053 -0.0929736 -0.0567051 -0.994042 -0.0887153 -0.0633211 0 -0.806885 -0.590708 0.063501 -0.826016 -0.560058 0 -0.847408 -0.530942 0 -0.883513 -0.468406 0.0635016 -0.898033 -0.435322 0 -0.915011 -0.403429 -0.891408 -0.207567 0.402874 -0.893729 -0.446664 -0.0417103 -0.90088 -0.433895 0.0122357 -0.982603 -0.178708 0.0505426 -0.968982 -0.237714 0.0675726 -0.95918 -0.270878 0.0812338 -0.955076 -0.287109 0.0734736 -0.937214 -0.340379 0.075973 -0.963017 0.1667 0.211681 -0.97139 0.152028 0.182454 -0.876427 0.361571 0.318029 -0.884047 0.354535 0.304575 -0.858963 0.129343 0.495432 -0.839076 0.132878 0.527537 -0.946585 -0.0121349 0.322226 -0.938296 -0.0104779 0.345675 -0.978164 -0.202313 0.047586 -0.993506 -0.112709 -0.01559 -0.993503 -0.113427 -0.00928809 -0.712672 -0.701496 0.00144576 -0.88495 -0.46011 -0.0718472 -0.885799 -0.457609 -0.0771627 -0.792141 -0.116816 0.599055 -0.849343 -0.229873 0.475158 -0.805195 -0.355373 0.474733 -0.812789 -0.393798 0.429299 -0.759743 -0.531131 0.375087 -0.771361 -0.549882 0.320362 -0.722811 -0.654903 0.220562 -0.102743 -0.666082 0.738768 -0.199232 -0.580665 0.789389 0.044061 -0.832814 0.551797 0.0141892 -0.831187 0.555812 -0.275285 -0.81794 0.505166 -0.149108 -0.984009 -0.0974348 -0.151986 -0.975911 0.15652 -0.933087 -0.354424 0.0610849 -0.918224 -0.393422 0.0456393 -0.916086 -0.398458 0.044916 -0.902767 -0.429904 -0.0139796 -0.738156 -0.652332 0.172014 -0.697724 -0.715718 0.0304729 -0.461103 -0.882682 0.0908635 -0.105761 0.824278 0.55622 -0.1217 0.825532 0.551076 -0.0853843 0.526647 0.845785 -0.15191 0.536526 0.830098 -0.0927366 0.329307 0.939658 -0.164211 0.13877 0.976615 -0.146557 0.134361 0.980035 -0.0375601 -0.51545 0.856096 -0.112379 -0.32864 0.937746 -0.225437 -0.24995 0.941649 -0.211861 -0.241211 0.947065 -0.0696656 -0.0958598 0.992954 -0.353638 -0.816617 0.456155 -0.456007 -0.588787 0.667374 -0.364127 -0.625844 0.689732 -0.489615 -0.304476 0.81705 -0.398065 -0.333331 0.854655 -0.521633 0.0325064 0.852551 -0.443215 0.0189489 0.896215 -0.546157 0.381682 0.745675 -0.493425 0.383257 0.780798 -0.553287 0.672916 0.490976 -0.546205 0.675195 0.495753 -0.177313 -0.845275 0.504055 -0.301515 -0.577302 0.758822 -0.187419 -0.608131 0.771395 -0.324421 -0.257552 0.910175 -0.209396 -0.284132 0.93564 -0.342319 0.108587 0.933288 -0.242329 0.0923929 0.965785 -0.351087 0.474386 0.807277 -0.282722 0.470574 0.83584 -0.344988 0.77363 0.531487 -0.333631 0.774772 0.537046 -0.148812 -0.948653 -0.279129 -0.230475 -0.954321 -0.190139 -0.341437 -0.921006 -0.187535 -0.424997 -0.889792 -0.166278 -0.484349 -0.853644 -0.191566 -0.687666 -0.705421 -0.171746 -0.647365 -0.750653 -0.132054 -0.870212 -0.447877 -0.205275 -0.850011 -0.505914 -0.146742 -0.174047 -0.970341 0.167767 -0.1797 -0.969164 0.16861 -0.423352 -0.896426 0.131126 -0.487235 -0.798684 0.353137 -0.503328 -0.789371 0.351502 -0.600328 -0.580091 0.550546 -0.532643 -0.619397 0.576748 -0.641639 -0.340085 0.687489 -0.57573 -0.369542 0.729365 -0.684277 -0.0476252 0.727665 -0.629471 -0.0598194 0.774718 -0.721166 0.264276 0.640373 -0.685631 0.268185 0.676748 -0.739821 0.533354 0.41012 -0.7257 0.540972 0.425098 -0.146451 -0.637307 -0.756566 -0.824708 0.208445 -0.525745 -0.651392 -0.521827 -0.550804 -0.942263 -0.0602382 -0.32941 -0.971801 -0.0646748 -0.22676 -0.978816 -0.0486815 -0.19887 -0.989309 -0.0737238 -0.125825 -0.993672 -0.0682229 -0.0892248 -0.851107 -0.414872 -0.321712 -0.873463 -0.322051 -0.365165 -0.8894 -0.276172 -0.364276 -0.901406 -0.226603 -0.368942 -0.895308 -0.235435 -0.378145 -0.91823 -0.163938 -0.360525 -0.741733 0.027118 -0.670147 -0.782194 0.043217 -0.621535 -0.708895 -0.168693 -0.684843 -0.911959 -0.169855 -0.373471 -0.938587 -0.110928 -0.326724 -0.786962 0.21113 -0.579754 -0.849347 0.296569 -0.436642 -0.792189 0.460391 -0.400596 -0.856724 0.492743 -0.152408 -0.843571 0.520259 -0.133112 -0.884012 0.443602 0.147449 -0.877482 0.452062 0.160202 -0.92189 -0.113048 -0.370592 -0.959989 -0.0903916 -0.265048 -0.89144 0.245107 -0.381127 -0.944652 0.271737 -0.183824 -0.941309 0.291331 -0.170483 -0.970892 0.237968 0.0271966 -0.965064 0.256838 0.0518165 -0.115181 0.944512 0.30762 -0.0768016 0.995269 0.0595002 -0.146663 0.988808 0.0273673 -0.0529673 0.943966 -0.325764 -0.148665 0.918252 -0.367032 -0.0857136 0.837307 -0.539973 -0.146643 0.709804 -0.688966 -0.33394 0.850556 0.406249 -0.105761 0.893875 0.435663 -0.296937 0.830305 0.471617 -0.143079 0.709594 -0.689931 -0.0595382 0.534222 -0.843245 -0.223399 0.388236 -0.894073 -0.116141 0.356612 -0.927005 -0.0132373 0.0625532 -0.997954 -0.298407 0.102422 -0.948927 -0.108507 -0.0486522 -0.992904 -0.0837929 -0.0936524 -0.992073 -0.0301117 -0.293145 -0.955594 -0.178503 -0.338949 -0.923715 -0.112024 -0.652394 -0.749555 -0.341451 -0.622959 -0.703799 -0.692764 -0.479659 -0.538522 -0.714398 -0.327703 -0.61826 -0.412914 -0.365048 -0.834411 -0.487267 -0.0934222 -0.868242 -0.353599 -0.0131819 -0.935304 -0.447582 0.254016 -0.857407 -0.37766 0.311108 -0.872115 -0.480017 0.531756 -0.697725 -0.412111 0.594171 -0.690742 -0.513924 0.743325 -0.428194 -0.454267 0.794568 -0.402869 -0.542567 0.837449 -0.0655809 -0.499061 0.865796 -0.0365304 -0.553201 0.76295 0.334478 -0.546581 0.765419 0.33968 -0.344666 0.849335 0.399795 -0.287815 0.95759 0.0135679 -0.346267 0.937963 -0.01801 -0.25301 0.89316 -0.371821 -0.332867 0.851377 -0.405409 -0.223309 0.691376 -0.687119 -0.313055 0.634929 -0.706301 -0.200946 0.393268 -0.897196 -0.291653 0.337288 -0.895084 -0.18745 0.0405017 -0.981439 -0.269278 -1.69862e-05 -0.963063 -0.1797 -0.338669 -0.923586 -0.463506 -0.331762 -0.821642 -0.42503 -0.588927 -0.687397 -0.484356 -0.592756 -0.643459 -0.870908 -0.371024 -0.322273 -0.892971 -0.287822 -0.346067 -0.690171 -0.353772 -0.631276 -0.744778 -0.141105 -0.652224 -0.503286 -0.0902028 -0.859399 -0.593143 0.15992 -0.789055 -0.545223 0.213008 -0.810777 -0.633575 0.403534 -0.660108 -0.588806 0.464239 -0.661657 -0.677988 0.595341 -0.431162 -0.639889 0.64775 -0.413475 -0.718478 0.686513 -0.111759 -0.691089 0.717515 -0.0869958 -0.739776 0.625171 0.248781 -0.726937 0.634193 0.263365 -0.939621 -0.276129 -0.20215 -0.939565 -0.311587 -0.141883 -0.93839 -0.32107 -0.127818 -0.939692 -0.31832 -0.125108 -0.939424 -0.319344 -0.124507 -0.939408 -0.319401 -0.124479 -0.939888 -0.318074 -0.124255 -0.939984 -0.317934 -0.123888 -0.939936 -0.318017 -0.124041 -0.93977 -0.31841 -0.124284 -0.939573 -0.318913 -0.124485 -0.939633 -0.267135 -0.213842 -0.939832 -0.266706 -0.213504 -0.940953 -0.265708 -0.20978 -0.939692 -0.267532 -0.213086 -0.939957 -0.266372 -0.21337 -0.939979 -0.266285 -0.213384 -0.939692 -0.267831 -0.21271 -0.939472 -0.267459 -0.214147 -0.939449 -0.267476 -0.214225 -0.939565 -0.278668 -0.198901 -0.94337 -0.269003 -0.194139 -0.936007 -0.3005 -0.183277 -0.939622 -0.289995 -0.181695 -0.939661 -0.300307 -0.163872 -0.937285 -0.307961 -0.163269 -0.94337 -0.302631 -0.135894 -0.939621 -0.313131 -0.13806 -0.939692 -0.318125 -0.125597 -0.149349 -0.797836 -0.584083 -0.488788 -0.703929 -0.515335 -0.346082 -0.858467 -0.378499 -0.655057 -0.691363 -0.304823 -0.850962 -0.480588 -0.211892 -0.850962 -0.480588 -0.211892 -0.850962 -0.464045 -0.246019 -0.850962 -0.464045 -0.24602 -0.850962 -0.445082 -0.278865 -0.850963 -0.445081 -0.278864 -0.850963 -0.423797 -0.310255 -0.850962 -0.423798 -0.310256 -0.655064 -0.609661 -0.446324 -0.573438 -0.665442 -0.477867 -0.573327 -0.694305 -0.435015 -0.573327 -0.694304 -0.435015 -0.573327 -0.723886 -0.383778 -0.573328 -0.723885 -0.383777 -0.573439 -0.746565 -0.337355 -0.488786 -0.798259 -0.351953 -0.346093 -0.75702 -0.554203 -0.202128 -0.793639 -0.573831 -0.20209 -0.829924 -0.519987 -0.202093 -0.829923 -0.519987 -0.202092 -0.865283 -0.458741 -0.202092 -0.865283 -0.458741 -0.20213 -0.893771 -0.400396 -0.149348 -0.904749 -0.398904 0.7071 0.664943 0.240542 0.671179 0.680809 0.293288 0.70647 0.650692 0.278391 0.70647 0.612924 0.353872 0.70647 0.612923 0.353871 0.706522 0.567455 0.422874 0.672814 0.592105 0.443546 0.707098 0.540791 0.455585 0.706471 -0.65069 -0.27839 0.706471 -0.65069 -0.27839 0.706471 -0.612923 -0.353871 0.70647 -0.612923 -0.353871 0.70647 -0.566438 -0.42432 0.70647 -0.566439 -0.42432 0.696401 0.696413 -0.173306 0.43046 0.890704 -0.146119 0.70593 0.650564 -0.280053 0.696401 0.533963 -0.479489 0.332811 0.761921 -0.555619 0.70527 0.454987 -0.543673 0.704461 0.323482 -0.631739 0.524011 0.293085 -0.799696 0.696399 -0.419495 -0.582282 0.6964 -0.419494 -0.582281 0.7035 -0.167643 -0.69064 0.53009 -0.115391 -0.840053 0.705271 0.00408925 -0.708926 0.704462 0.161354 -0.691158 0.694741 -0.716796 -0.0594932 0.487518 -0.497604 0.717438 0.69474 -0.716797 -0.0594936 0.702914 -0.672357 0.232051 0.49462 -0.786036 0.370808 0.705015 -0.587663 0.396997 0.703698 -0.47372 0.529528 0.704395 -0.320214 0.633475 0.704395 -0.155725 0.692516 0.487517 -0.0722197 0.870122 0.694741 0.591017 0.40992 0.69474 0.591017 0.409921 0.702915 0.371318 0.606657 0.494621 0.370809 0.786035 0.705015 0.201062 0.680094 0.703698 0.0288466 0.709914 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.00863848 0.627737 -0.778378 -0.00531469 0.641777 -0.766873 0.00902109 0.480778 -0.876796 -1.83404e-05 0.455774 -0.890096 4.86793e-06 0.256387 -0.966574 -0.00737056 0.227335 -0.973789 0.00820073 0.0351936 -0.999347 -2.46845e-05 0.00576813 -0.999983 1.82208e-05 -0.207275 -0.978283 -0.00928982 -0.235876 -0.971739 0.00337769 -0.383265 -0.923632 -0.0236759 -0.584372 -0.811141 -0.021888 -0.586943 -0.809332 0 -0.738637 -0.674104 -1.58969e-05 0.681979 -0.731372 -7.07628e-06 0.807982 -0.589208 0.00962882 0.82376 -0.566857 -0.00358749 0.918504 -0.395395 0.014151 0.964717 -0.262908 -0.0128892 0.986728 -0.161872 0 0.998784 -0.0492953 -0.939621 -0.13806 -0.313132 -0.939566 -0.1989 -0.278667 -0.938393 -0.214143 -0.271221 -0.939692 -0.213119 -0.267506 -0.939424 -0.214307 -0.267498 -0.939409 -0.214369 -0.267503 -0.939888 -0.213333 -0.266645 -0.939984 -0.213395 -0.266258 -0.939935 -0.213391 -0.266432 -0.939772 -0.213608 -0.266835 -0.939572 -0.213946 -0.267265 -0.939634 -0.124424 -0.318759 -0.939831 -0.124223 -0.318255 -0.940955 -0.125221 -0.314521 -0.939692 -0.125147 -0.318304 -0.939959 -0.123991 -0.317967 -0.939978 -0.123917 -0.317939 -0.939692 -0.125595 -0.318126 -0.939471 -0.12455 -0.319189 -0.93945 -0.124528 -0.319259 -0.939565 -0.141883 -0.311586 -0.94337 -0.135894 -0.302631 -0.936007 -0.168602 -0.308972 -0.939622 -0.160295 -0.30235 -0.939661 -0.178138 -0.29207 -0.937285 -0.185067 -0.295376 -0.94337 -0.194139 -0.269003 -0.939621 -0.20215 -0.276129 -0.939692 -0.212707 -0.267832 -0.149348 -0.398904 -0.904749 -0.488788 -0.351953 -0.798258 -0.346086 -0.554205 -0.757022 -0.655058 -0.446326 -0.609665 -0.850962 -0.310256 -0.423798 -0.850961 -0.310258 -0.4238 -0.850961 -0.278866 -0.445084 -0.850962 -0.278865 -0.445082 -0.850962 -0.24602 -0.464045 -0.850962 -0.24602 -0.464046 -0.850962 -0.211892 -0.480589 -0.850962 -0.211892 -0.480588 -0.655066 -0.304819 -0.691356 -0.573439 -0.337356 -0.746564 -0.573328 -0.383778 -0.723885 -0.57333 -0.383777 -0.723884 -0.57333 -0.435014 -0.694302 -0.573332 -0.435013 -0.694302 -0.573443 -0.477865 -0.665439 -0.488784 -0.515337 -0.70393 -0.346089 -0.378498 -0.858465 -0.202128 -0.400396 -0.893771 -0.202091 -0.458741 -0.865284 -0.202088 -0.458742 -0.865284 -0.202088 -0.519987 -0.829924 -0.20209 -0.519986 -0.829924 -0.202128 -0.573831 -0.793639 -0.149351 -0.584083 -0.797835 0.707101 0.455585 0.540787 0.671181 0.442953 0.594398 0.70647 0.42432 0.566439 0.70647 0.353872 0.612923 0.706473 0.35387 0.612921 0.706526 0.279991 0.649943 0.672815 0.291004 0.680174 0.707102 0.240541 0.664942 0.706474 -0.424318 -0.566435 0.70647 -0.42432 -0.566439 0.70647 -0.353871 -0.612923 0.706477 -0.353868 -0.612917 0.706477 -0.278388 -0.650685 0.706467 -0.278391 -0.650694 0.696796 0.696809 -0.170096 0.457729 0.877334 -0.144113 0.706058 0.651637 -0.277221 0.696794 0.540063 -0.472028 0.324164 0.773796 -0.544203 0.696792 -0.0753051 -0.71331 0.696796 -0.0753062 -0.713305 0.703905 0.188311 -0.684878 0.535524 0.308278 -0.786244 0.705127 0.344756 -0.619628 0.705129 0.466725 -0.533818 0.698071 -0.572692 -0.429793 0.69807 -0.572692 -0.429794 0.698068 -0.70246 -0.138749 0.618523 -0.765312 -0.178117 0.706901 -0.707306 -0.00302583 0.698067 -0.693096 0.179778 0.698066 -0.693098 0.179778 0.698068 -0.546455 0.462696 0.698069 -0.546454 0.462696 0.698069 -0.291582 0.653972 0.69807 0.329498 0.635712 0.698066 0.329498 0.635716 0.700598 0.0449612 0.712138 0.634902 0.0227045 0.772259 0.706904 -0.113643 0.69812 0.698072 -0.29158 0.65397 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.112721 -0.993627 -0.00504595 -0.104987 -0.994461 0.00308027 0.265115 -0.964212 -0.00404595 0.669148 -0.743118 0.000126143 0.584336 -0.811512 -0.000956026 0.486201 -0.873847 -3.65671e-05 0.483282 -0.875465 1.04933e-05 0.257696 -0.966226 1.83583e-05 0.658212 -0.752833 -1.11478e-05 0.817966 -0.575267 0.00763878 0.830219 -0.557386 -0.00305016 0.920186 -0.391469 -0.00128754 0.925117 -0.379681 0.0040552 0.986768 -0.162089 0 0.985206 -0.171374 0 0.527507 0.849551 -0.0254453 0.460024 0.887542 -0.00386064 0.346055 0.938206 0.0105377 0.0630066 0.997958 -0.00709837 0.0999018 0.994972 0.00161549 -0.160669 0.987007 0.0201075 -0.322515 0.946351 -0.0192707 -0.407143 0.913161 -0.00122747 -0.554721 0.832035 0.00305292 -0.677823 0.735219 -0.0539155 -0.811848 0.581374 -0.0129093 -0.763108 0.646142 0.000749981 -0.881337 0.472487 0 -0.799816 -0.600246 -0.00495428 -0.79512 -0.606432 0.00438748 -0.97396 -0.226677 -0.00778114 -0.968769 -0.247843 4.59624e-06 -0.99864 -0.0521452 -5.99663e-07 -0.999991 -0.0042779 0.000873198 -0.999986 0.00520371 -0.00543577 -0.967953 0.251071 -0.0432676 -0.981385 0.187112 -0.00224184 -0.925329 0.379159 0 -0.59954 -0.800345 0 -0.59954 -0.800345 0 -0.5 -0.866026 0 -0.5 -0.866026 0 -0.39335 -0.919389 0 -0.39335 -0.919389 0 0.393349 0.919389 0 0.393349 0.919389 0 0.5 0.866025 0 0.5 0.866025 0 0.599539 0.800345 0 0.599539 0.800345 0.87924 -0.125536 -0.459541 0.887083 -0.0510251 -0.458781 0.954993 0.0821843 -0.285017 0.960102 0.0884359 -0.2653 0.978436 0.0582609 -0.198164 0.978976 0.0581036 -0.195524 0.991396 -0.00377989 -0.130839 0.990797 -0.00127244 -0.135349 0.965171 0.189752 0.180108 0.793207 0.601567 -0.0945545 0.859466 0.489389 0.147704 0.839104 0.522777 0.150362 0.88419 0.291274 0.365194 0.876485 0.305376 0.372183 0.859292 0.349008 -0.373913 0.938544 0.0860371 -0.334265 0.933187 0.0719031 -0.352126 0.821646 0.485526 -0.298602 0.847484 0.482457 -0.221374 0.891282 0.409502 -0.194744 0.947044 0.321105 0.000172948 0.938319 0.34577 0.000951549 0.970911 0.188437 0.147726 0.989049 0.129092 0.0715358 0.807334 0.175125 -0.56351 0.69324 0.466044 -0.549747 0.770718 0.538603 -0.340441 0.902132 0.0230724 -0.430844 0.887847 -0.056483 -0.456659 0.749555 0.00903598 -0.661881 0.710137 -0.00404301 -0.704052 0.105523 0.820364 -0.56202 0.138594 0.822139 -0.552159 0.275999 0.534785 -0.798642 0.109156 0.250286 -0.961999 0.0572733 0.478795 -0.876057 0.220799 0.547616 -0.807072 0.206457 0.558151 -0.803644 0.0678208 0.662987 -0.745553 0.146985 -0.157558 -0.97651 0.0751921 -0.114077 -0.990622 0.106178 0.511929 0.852441 0.15143 0.525703 0.837081 0.10508 0.684607 0.721298 0.111229 0.826844 0.551323 0.0784781 0.919255 -0.385761 0.152095 0.9711 -0.183934 0.0787843 0.976014 -0.202952 0.101821 0.984257 0.144468 0.178216 0.969197 0.16999 0.0897973 0.932038 0.351058 0.149989 0.815794 0.558554 0.35423 0.484333 -0.799964 0.457118 0.688462 -0.563083 0.36317 0.709129 -0.604353 0.49083 0.827325 -0.273166 0.397294 0.864991 -0.306508 0.52259 0.850135 0.06457 0.442842 0.895325 0.0477898 0.546615 0.730832 0.408776 0.493389 0.767605 0.409084 0.553357 0.46729 0.689518 0.546231 0.47229 0.69179 0.176396 0.530616 -0.829054 0.302654 0.779683 -0.548174 0.186328 0.790093 -0.583982 0.325667 0.918873 -0.222739 0.208486 0.944249 -0.254809 0.343273 0.92819 0.143623 0.24185 0.962446 0.123315 0.351501 0.789179 0.503629 0.282655 0.81977 0.498081 0.345033 0.503867 0.791878 0.333666 0.509792 0.792956 0.879549 -0.126445 -0.4587 0.763495 -0.147485 -0.628747 0.693959 -0.116223 -0.710572 0.651406 -0.150627 -0.743628 0.484446 -0.162599 -0.859578 0.918302 0.0577993 -0.391639 0.901023 0.0509532 -0.430769 0.758733 0.262211 -0.596296 0.805311 0.228501 -0.547048 0.700506 0.338334 -0.628348 0.633803 0.0756574 -0.769786 0.46111 0.119018 -0.879325 0.425657 -0.132612 -0.895114 0.341461 -0.155465 -0.926949 0.206314 0.205093 -0.95675 0.179197 0.20022 -0.963224 0.424093 0.163317 -0.890771 0.486872 0.377258 -0.787802 0.502666 0.376268 -0.778299 0.601388 0.571159 -0.558668 0.531875 0.595995 -0.601581 0.642849 0.6989 -0.313502 0.575095 0.740968 -0.346744 0.685234 0.728048 -0.0200388 0.62921 0.776454 -0.0348513 0.721675 0.629617 0.287694 0.685619 0.66743 0.290626 0.739938 0.390825 0.547492 0.725682 0.406491 0.555113 0.146157 -0.784665 -0.602444 0.826271 -0.51474 0.228734 0.651429 -0.568646 -0.502276 0.880893 -0.370659 -0.294345 0.992268 -0.115974 -0.0442004 0.992327 -0.0929046 -0.0815849 0.976264 -0.213196 -0.0381586 0.978908 -0.198453 -0.048543 0.963206 -0.263079 -0.0549823 0.942932 -0.328758 -0.0528935 0.902136 -0.375828 -0.211907 0.8958 -0.384886 -0.222273 0.919327 -0.363957 -0.149579 0.851018 -0.327627 -0.410401 0.740542 -0.670396 0.0465462 0.783616 -0.617546 0.0676998 0.707954 -0.690445 -0.148617 0.912305 -0.377986 -0.157561 0.939733 -0.327486 -0.0982571 0.7859 -0.574612 0.228433 0.847486 -0.432956 0.307109 0.793261 -0.382585 0.473673 0.856964 -0.135677 0.497198 0.844209 -0.113591 0.52384 0.884164 0.162482 0.438012 0.877675 0.176362 0.445627 0.923011 -0.370524 -0.103747 0.960832 -0.266499 -0.0760316 0.891327 -0.373334 0.257213 0.944822 -0.174616 0.277165 0.94184 -0.158823 0.296162 0.97092 0.0336478 0.237029 0.965173 0.0610596 0.254388 0.115168 0.339946 0.933366 0.0771075 0.0948856 0.992497 0.14647 0.060913 0.987338 0.0440315 -0.32419 0.944967 0.0571111 -0.329494 0.942429 0.0998417 -0.559913 0.822514 0.181855 -0.663983 0.725297 0.334012 0.435929 0.835704 0.105774 0.465914 0.878485 0.278921 0.503117 0.817971 0.012257 -0.995489 0.0940841 0.315348 -0.937395 0.147802 0.112611 -0.993634 -0.00321791 0.136031 -0.681046 0.719494 0.0636135 -0.818042 0.57163 0.202853 -0.882545 0.424224 0.247966 -0.864786 0.436644 0.108768 -0.923726 0.367286 0.0842358 -0.994759 -0.0579552 0.032857 -0.967703 -0.249944 0.190216 -0.933057 -0.305325 0.0915582 -0.773046 -0.627708 0.341467 -0.724979 -0.598169 0.693993 -0.557226 -0.45593 0.714751 -0.629599 -0.304527 0.412201 -0.845767 -0.338775 0.486916 -0.870868 -0.067094 0.354184 -0.934971 0.0195564 0.447647 -0.848563 0.282049 0.378516 -0.860282 0.341525 0.480132 -0.67972 0.554485 0.413098 -0.668786 0.618123 0.514059 -0.403019 0.757178 0.455179 -0.373766 0.808153 0.542686 -0.0370951 0.839116 0.499644 -0.00529513 0.866215 0.553288 0.360448 0.750966 0.546655 0.366038 0.753117 0.34468 0.429068 0.834923 0.288263 0.0478237 0.956356 0.346237 0.013862 0.938045 0.253715 -0.339571 0.905715 0.332838 -0.376521 0.864553 0.224034 -0.662059 0.715183 0.31305 -0.684701 0.658167 0.201543 -0.882717 0.424489 0.291658 -0.883365 0.36688 0.187837 -0.97935 0.0747709 0.269282 -0.962528 0.0320571 0.179196 -0.934252 -0.30832 0.463857 -0.833127 -0.301225 0.425707 -0.708831 -0.562434 0.484453 -0.663081 -0.570639 0.875353 -0.333512 -0.350039 0.889584 -0.363659 -0.276392 0.689708 -0.642335 -0.334228 0.745685 -0.656169 -0.115743 0.502641 -0.862181 -0.063223 0.593262 -0.783383 0.185339 0.546281 -0.802082 0.241333 0.633761 -0.646478 0.424752 0.590004 -0.6439 0.487123 0.67825 -0.411041 0.609115 0.640945 -0.389196 0.661601 0.7187 -0.0884178 0.689675 0.69173 -0.0607465 0.719597 0.739908 0.269874 0.616202 0.727072 0.285608 0.624335 0.572897 -0.409814 -0.709818 0.850726 -0.315995 -0.420014 0.879516 -0.186273 -0.437898 0.654676 -0.297337 -0.694975 0.765007 -0.253326 -0.592107 0.845143 -0.213401 -0.490095 0.851115 -0.233936 -0.469976 0.850697 -0.262828 -0.455232 0.850697 -0.262828 -0.455231 0.851115 -0.290038 -0.437585 0.345772 -0.369087 -0.86268 0.488418 -0.343241 -0.802268 0.14921 -0.388946 -0.909097 0.201911 -0.388457 -0.899074 0.201871 -0.489706 -0.848196 0.844348 -0.32123 -0.428821 0.654697 -0.453187 -0.604974 0.573018 -0.487721 -0.658619 0.488423 -0.523162 -0.698387 0.345774 -0.562559 -0.750978 0.573014 -0.326521 -0.75169 0.572893 -0.409815 -0.709821 0.20187 -0.489706 -0.848196 0.20191 -0.584393 -0.78595 0.149215 -0.592828 -0.791385 0.340894 0.563628 0.752406 0.994035 -0.054531 -0.0944505 0.994036 -0.06556 -0.087141 0.99425 -0.0641982 -0.0857003 0.991754 -0.0501654 -0.117931 0.996676 -0.0363047 -0.0729359 0.658679 0.376212 0.651618 0.931791 0.181498 0.314363 0.994046 -0.0446274 -0.0994072 0.993745 0.043925 0.102668 0.971837 0.0926948 0.216659 0.994056 -0.0601494 -0.0907461 0.994035 -0.054531 -0.0944506 0.931791 0.181498 0.314364 0.931639 0.136916 0.336605 0.558443 0.508456 0.655449 0.739313 0.403707 0.538922 0.931791 0.21763 0.290522 0.888072 0.284803 0.360855 0.971843 0.14127 0.188586 0.237288 0.48572 0.841291 0.237289 0.582416 0.777487 0.108129 0.607637 0.78682 0.887837 0.181003 0.423064 0.739297 0.264873 0.619097 0.658467 0.289906 0.694532 0.558105 0.32639 0.762882 0.340884 0.36979 0.864322 0.658677 0.451109 0.6022 0.658677 0.376213 0.65162 0.237285 0.48572 0.841292 0.237188 0.375999 0.895749 0.108041 0.391047 0.914007 0.939514 -0.134071 -0.31518 0.939603 -0.114006 -0.32272 0.93949 -0.113994 -0.323055 0.939578 -0.114161 -0.322738 0.939696 -0.115016 -0.32209 0.939843 -0.113773 -0.322104 0.939864 -0.113707 -0.322065 0.939744 -0.113875 -0.322357 0.939507 -0.205928 -0.273715 0.939903 -0.222055 -0.259373 0.939805 -0.222005 -0.259771 0.93969 -0.221436 -0.260671 0.939697 -0.221586 -0.260517 0.939544 -0.222572 -0.260227 0.939488 -0.222797 -0.260236 0.939528 -0.222658 -0.260211 0.939645 -0.222407 -0.260004 0.939777 -0.222173 -0.259728 0.939515 -0.205915 -0.273699 0.939511 -0.205921 -0.273707 0.939694 -0.18896 -0.285079 0.939693 -0.188957 -0.285082 0.939498 -0.171278 -0.296662 0.939498 -0.171278 -0.296662 0.939694 -0.152407 -0.306184 0.939693 -0.152406 -0.306184 0.939511 -0.134075 -0.315187 0.939508 -0.134078 -0.315196 0.93969 -0.114815 -0.32218 0 0.988067 0.154024 -0.0178826 0.979033 0.202914 0.000937607 0.933434 0.358747 -0.00366202 0.817866 0.575397 -0.00533031 0.819982 0.572364 0.000278114 0.685372 0.728193 -0.00443676 0.521807 0.853052 0 0.513081 0.85834 0.699627 0.69964 0.145007 0.699629 0.699638 0.145006 0.699627 0.584376 0.411129 0.699633 0.584373 0.411124 0.699631 0.372837 0.609515 0.699629 0.372837 0.609518 0 -0.981951 0.189136 0.0113026 -0.97498 0.222004 -0.00651747 -0.865939 0.500107 0.0215154 -0.782612 0.622138 0.00270887 -0.719231 0.694766 -0.00184638 -0.574824 0.818275 0.0187063 -0.436124 0.899692 -0.000344453 -0.364097 0.931361 9.88191e-05 -0.178038 0.984024 0.0133097 -0.00360562 0.999905 -0.00486026 0.0607715 0.99814 0.00565346 0.429698 0.902955 0 0.445505 0.895279 -0.69811 0.307664 0.646518 -0.698108 0.307665 0.646519 -0.704245 0.0662488 0.70686 -0.798049 -0.00217292 0.602589 -0.698112 -0.698119 0.158962 -0.69811 -0.698121 0.158963 -0.69811 -0.560473 0.445548 -0.698108 -0.560474 0.44555 -0.698107 -0.312317 0.644286 -0.698113 -0.312316 0.64428 -0.705433 -0.0921892 0.702756 -0.694739 -0.0842123 -0.714315 -0.458492 0.712318 -0.531402 -0.694741 -0.0842115 -0.714313 -0.702915 0.208695 -0.679968 -0.466761 0.34948 -0.812402 -0.705011 0.376466 -0.601026 -0.703693 0.512858 -0.491725 -0.694739 0.430087 0.57651 -0.694736 0.430088 0.576512 -0.702913 0.619121 0.350147 -0.782477 0.521143 0.340794 -0.561462 0.801178 0.207063 -0.701771 0.676833 0.222295 -0.703697 0.710487 0.00431195 -0.458494 0.882585 -0.10405 -0.704394 0.686725 -0.179547 -0.704394 0.62204 -0.3419 -0.69796 -0.55817 -0.448662 -0.697963 -0.558167 -0.448661 -0.697961 -0.697975 -0.160253 -0.697965 -0.697971 -0.160253 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706175 0.308847 0.637126 -0.706176 0.308847 0.637125 -0.706177 0.397343 0.586031 -0.706178 0.397342 0.58603 0 0.580953 0.813937 -0.0420201 0.560695 0.826955 0 0.520703 0.853738 0 0.436202 0.899849 -0.0629308 0.413592 0.908285 0 0.479008 0.877811 -0.706175 -0.308847 -0.637126 -0.706179 -0.308845 -0.637123 -0.706179 -0.397342 -0.58603 -0.706176 -0.397344 -0.586032 0 -0.764564 -0.644548 0.00897396 -0.779387 -0.626479 -0.000625036 -0.895719 -0.444619 0.00476585 -0.965983 -0.25856 0.0163914 -0.97451 -0.223744 0 -0.998724 -0.0505053 0 0.501184 0.865341 0.0262995 0.597748 0.801252 0.0108376 0.664537 0.747177 -0.0197306 0.870268 0.492184 0.00457643 0.876339 -0.481673 -6.76947e-05 0.889215 -0.457489 8.60205e-05 0.967479 -0.252951 -0.0052139 0.973497 -0.22864 0.00478509 0.99997 0.00606883 0.0130123 0.999209 -0.0375725 -0.0208409 0.967977 0.250172 -0.00416468 0.980767 0.195138 0.0049375 0.831419 0.555624 0 -0.117081 -0.993122 0.0272974 -0.171155 -0.984866 -0.0219145 0.29334 -0.955757 0.00552704 0.226446 -0.974008 -4.22751e-06 0.423206 -0.906034 7.15124e-06 0.530835 -0.847475 0.0147469 0.46721 -0.884023 -0.0292806 0.721512 -0.691782 0.0251994 0.618403 -0.785457 -0.00320819 0.785972 -0.618254 -0.994042 -0.0451691 -0.0991952 -0.971841 0.0976519 0.214452 -0.658919 0.376107 0.651436 -0.108089 0.577549 0.809169 -0.558288 0.481986 0.675281 -0.341055 0.546121 0.765136 -0.237324 0.571123 0.785809 -0.237621 0.505789 0.829286 -0.15399 0.494036 0.855696 -0.237621 0.465288 0.852668 -0.237426 0.402564 0.884065 -0.887884 0.267277 0.374465 -0.739468 0.391093 0.547936 -0.108173 0.395266 0.912175 -0.341045 0.389568 0.855526 -0.658919 0.311727 0.684581 -0.558605 0.327706 0.761951 -0.739472 0.278978 0.61266 -0.971845 0.136885 0.191781 -0.931696 0.217627 0.290827 -0.931861 0.181408 0.314208 -0.658697 0.443878 0.607529 -0.658919 0.376107 0.651436 -0.931861 0.181408 0.314208 -0.931861 0.150356 0.330195 -0.888089 0.177164 0.424159 -0.994042 -0.0633211 -0.0887152 -0.994042 -0.0633211 -0.0887153 -0.994053 -0.0567056 -0.0929733 -0.994978 -0.0500477 -0.0866852 -0.994053 -0.052165 -0.095595 -0.994042 -0.0451692 -0.0991955 0 -0.403429 -0.915011 0.0635016 -0.435322 -0.898033 0 -0.468406 -0.883513 0 -0.530941 -0.847409 0.0635018 -0.560058 -0.826016 0 -0.590708 -0.806885 -0.0694567 -0.579996 0.811653 -0.0924188 -0.185778 0.978236 -0.812788 -0.555689 0.174885 -0.893728 -0.365967 -0.259456 -0.90088 -0.381882 -0.206352 -0.982603 -0.180037 -0.0455828 -0.968982 -0.239653 -0.0603374 -0.95918 -0.275204 -0.0650882 -0.955076 -0.28538 -0.079923 -0.937214 -0.332764 -0.104394 -0.978164 -0.199002 -0.0599456 -0.993506 -0.0898139 -0.0698557 -0.993503 -0.0935865 -0.0647578 -0.712671 -0.608238 -0.349495 -0.884951 -0.362543 -0.292275 -0.8858 -0.357718 -0.295629 -0.759743 -0.647517 0.0592698 -0.771361 -0.636393 0.00250013 -0.722811 -0.677443 -0.136439 -0.187417 -0.912355 0.363984 -0.301517 -0.879368 0.36851 -0.0389394 -0.964431 -0.261451 -0.491278 -0.768428 -0.410078 -0.14694 -0.745388 -0.650234 -0.123004 -0.756812 -0.641955 -0.09266 -0.993959 -0.0588162 -0.219668 -0.974906 0.0361117 -0.275277 -0.960942 0.0285157 -0.177315 -0.984056 0.0138872 -0.353638 -0.935288 -0.0132656 -0.456006 -0.843591 0.283571 -0.364123 -0.886864 0.284405 -0.172303 -0.924402 -0.340283 -0.179695 -0.923626 -0.338562 -0.423353 -0.84189 -0.334655 -0.487236 -0.868249 -0.093516 -0.503329 -0.859366 -0.0902754 -0.600329 -0.777646 0.186741 -0.532645 -0.824787 0.18978 -0.267889 -0.715679 0.645011 -0.876427 0.154115 0.456205 -0.884046 0.154749 0.441038 -0.7257 0.255946 0.638632 -0.73982 0.256838 0.621853 -0.546198 0.33686 0.766937 -0.553286 0.337275 0.761656 -0.333634 0.402449 0.852481 -0.344994 0.40424 0.847094 -0.105763 0.435737 0.893839 -0.121701 0.439395 0.890012 -0.146199 -0.374728 0.915535 -0.16662 -0.368274 0.914665 -0.342317 -0.372607 0.862545 -0.242337 -0.402877 0.882589 -0.521635 -0.398122 0.754583 -0.443216 -0.431696 0.78562 -0.684279 -0.405076 0.606363 -0.629466 -0.439167 0.641019 -0.792141 -0.400695 0.460387 -0.839075 -0.148694 0.5233 -0.858964 -0.135702 0.493726 -0.685628 -0.106118 0.720176 -0.721163 -0.0913161 0.686721 -0.493424 -0.0584876 0.86782 -0.546158 -0.0422897 0.836614 -0.282729 -0.0103902 0.959144 -0.351093 0.00719211 0.936313 -0.0853846 0.0331986 0.995795 -0.1519 0.0495942 0.987151 -0.484348 -0.643495 -0.592724 -0.687665 -0.52504 -0.501447 -0.647365 -0.584057 -0.48969 -0.870212 -0.285232 -0.401712 -0.85001 -0.364765 -0.380038 -0.933086 -0.337484 -0.124315 -0.918226 -0.36353 -0.157184 -0.916086 -0.367534 -0.160332 -0.902766 -0.365319 -0.227058 -0.738156 -0.650943 -0.177197 -0.697725 -0.635066 -0.331469 -0.461104 -0.809856 -0.362651 -0.424996 -0.687443 -0.588897 -0.34144 -0.703846 -0.622912 0.0665028 -0.978379 0.195835 -0.306027 -0.842108 0.444073 -0.0131362 -0.904597 0.426066 -0.143546 -0.689241 0.71017 -0.324416 -0.678136 0.659459 -0.209392 -0.713887 0.668222 -0.489611 -0.672211 0.555349 -0.398069 -0.715999 0.573487 -0.641642 -0.638265 0.42534 -0.575732 -0.684714 0.446877 -0.805194 -0.545129 0.233446 -0.849342 -0.436656 0.296563 -0.891408 -0.381195 0.245115 -0.946585 -0.171623 0.272989 -0.938297 -0.181911 0.294122 -0.97139 0.0404329 0.234022 -0.963018 0.0385255 0.26667 -0.146448 -0.173643 -0.973859 -0.824707 0.443391 -0.351089 -0.651396 -0.176513 -0.737921 -0.942264 0.112535 -0.315395 -0.971801 0.0573704 -0.228719 -0.978816 0.0572762 -0.196567 -0.989309 -0.000934823 -0.145829 -0.993672 -0.0144704 -0.111383 -0.851107 -0.198433 -0.486047 -0.873463 -0.0963216 -0.477267 -0.889404 -0.0570227 -0.453551 -0.901407 -0.011774 -0.432813 -0.895309 -0.0148216 -0.445199 -0.918231 0.0382882 -0.394191 -0.741733 0.358561 -0.566804 -0.782193 0.348197 -0.516656 -0.708893 0.19633 -0.67744 -0.911958 0.0396375 -0.408366 -0.938587 0.0672968 -0.338417 -0.786962 0.47272 -0.396518 -0.849348 0.475157 -0.229857 -0.792191 0.599006 -0.116731 -0.856724 0.502932 0.11438 -0.84357 0.517115 0.144852 -0.884011 0.310445 0.349497 -0.877483 0.311395 0.36477 -0.921891 0.0873943 -0.377465 -0.959989 0.0542434 -0.274734 -0.891439 0.402835 -0.207512 -0.944652 0.327244 -0.0233273 -0.941309 0.337542 -0.00197849 -0.970892 0.192488 0.142536 -0.965064 0.196519 0.173294 -0.115181 0.664165 0.73866 -0.0768019 0.832178 0.549163 -0.146663 0.842649 0.518105 -0.0529683 0.980381 0.189863 -0.148668 0.978745 0.141266 -0.0857167 0.995115 -0.0489769 -0.146647 0.959191 -0.24176 -0.333931 0.533479 0.777104 -0.105769 0.556285 0.824233 -0.296945 0.483253 0.823584 -0.143076 0.959492 -0.242703 -0.0595358 0.884271 -0.463163 -0.223391 0.783261 -0.580171 -0.116143 0.772342 -0.624499 -0.0132362 0.553148 -0.832978 -0.298398 0.563163 -0.770588 -0.108508 0.454323 -0.884204 -0.0837996 0.414944 -0.90598 -0.0301139 0.223925 -0.974141 -0.178501 0.16832 -0.969436 -0.112023 -0.190214 -0.975331 -0.34145 -0.1876 -0.920988 -0.692766 -0.146136 -0.706201 -0.714401 0.0253316 -0.699278 -0.412917 0.101065 -0.905144 -0.487268 0.353214 -0.79863 -0.353593 0.456241 -0.816588 -0.447578 0.64869 -0.615528 -0.377659 0.705485 -0.59972 -0.480016 0.809376 -0.338371 -0.412107 0.85994 -0.301115 -0.513921 0.857837 0.000839771 -0.454272 0.889548 0.048387 -0.542572 0.758041 0.361925 -0.499056 0.768068 0.401266 -0.553196 0.493494 0.671146 -0.546586 0.493032 0.676878 -0.344663 0.535649 0.7709 -0.287818 0.822512 0.490544 -0.346266 0.821304 0.453386 -0.253008 0.95941 0.124573 -0.332868 0.940019 0.0745925 -0.223309 0.942309 -0.249374 -0.313055 0.903016 -0.29421 -0.200947 0.789179 -0.580359 -0.29166 0.739639 -0.606522 -0.187458 0.525792 -0.8297 -0.269272 0.481521 -0.834045 -0.179694 0.168497 -0.969185 -0.463506 0.123506 -0.877444 -0.42503 -0.166327 -0.889767 -0.484354 -0.191612 -0.853631 -0.870905 -0.160186 -0.464612 -0.892969 -0.0762289 -0.443617 -0.690168 0.00925975 -0.72359 -0.744777 0.203913 -0.635395 -0.503293 0.35158 -0.789359 -0.593147 0.53302 -0.603379 -0.545228 0.589856 -0.595648 -0.633579 0.67952 -0.369906 -0.588807 0.73287 -0.340893 -0.67799 0.73116 -0.0757265 -0.639888 0.767707 -0.0342013 -0.718476 0.650418 0.246471 -0.69109 0.664884 0.283414 -0.739778 0.417022 0.528035 -0.726936 0.417543 0.545181 0.146159 -0.378317 -0.914064 0.826272 -0.560144 -0.0592799 0.651436 -0.241324 -0.719301 0.880896 -0.17383 -0.440233 0.992268 -0.0783359 -0.0962658 0.992327 -0.039665 -0.117107 0.976264 -0.165553 -0.139644 0.978908 -0.147593 -0.141266 0.963207 -0.200341 -0.179155 0.942932 -0.258264 -0.210185 0.902136 -0.219521 -0.371432 0.895796 -0.222184 -0.384946 0.919326 -0.240407 -0.311518 0.851016 -0.0785343 -0.519234 0.740543 -0.603853 -0.294886 0.783617 -0.56866 -0.250141 0.707954 -0.523633 -0.47393 0.912307 -0.248565 -0.325442 0.939734 -0.234483 -0.248834 0.7859 -0.611845 -0.089477 0.847486 -0.528506 0.0494866 0.79326 -0.568166 0.218919 0.856964 -0.366099 0.362746 0.844207 -0.360293 0.396868 0.884162 -0.0782937 0.460573 0.877675 -0.0700832 0.474105 0.923009 -0.269015 -0.27511 0.960831 -0.192782 -0.199095 0.891325 -0.451926 0.0360866 0.944822 -0.289804 0.152727 0.941841 -0.285626 0.17707 0.97092 -0.0893757 0.222096 0.965173 -0.0743154 0.250835 0.11516 -0.172288 0.978292 0.0771003 -0.414072 0.906973 0.146473 -0.440917 0.885515 0.0440365 -0.753242 0.656268 0.0571071 -0.756564 0.651421 0.0998372 -0.896154 0.432366 0.181855 -0.937674 0.296135 0.334009 -0.0403269 0.941707 0.105773 -0.0357493 0.993747 0.278919 0.0267258 0.959943 0.0122488 -0.90916 -0.416267 0.315357 -0.885707 -0.340695 0.112605 -0.858898 -0.499615 0.136031 -0.94955 0.282577 0.0636146 -0.99426 0.0860234 0.20285 -0.976419 -0.0738812 0.24796 -0.96725 -0.0542477 0.108766 -0.983614 -0.14378 0.084219 -0.832492 -0.547599 0.0328511 -0.713088 -0.700305 0.190226 -0.655388 -0.730945 0.0915745 -0.355629 -0.93013 0.341481 -0.328769 -0.880512 0.693995 -0.254605 -0.673459 0.714752 -0.392987 -0.578524 0.412207 -0.563069 -0.716267 0.486918 -0.720645 -0.493539 0.354185 -0.819487 -0.450549 0.44765 -0.875901 -0.180022 0.378517 -0.915789 -0.134373 0.480133 -0.865896 0.140344 0.413102 -0.888244 0.20092 0.51406 -0.727614 0.454225 0.455181 -0.727768 0.512995 0.542687 -0.451684 0.708147 0.499644 -0.437693 0.747516 0.553288 -0.0633264 0.83058 0.546658 -0.0595624 0.835235 0.34468 -0.0458793 0.937599 0.288262 -0.436762 0.852141 0.346235 -0.457018 0.819303 0.253712 -0.746935 0.614588 0.332843 -0.758353 0.560461 0.224039 -0.930951 0.288336 0.313047 -0.922052 0.227644 0.201538 -0.976701 -0.0737375 0.29166 -0.948456 -0.123957 0.187843 -0.885525 -0.424924 0.269281 -0.849602 -0.453502 0.179191 -0.654925 -0.734142 0.463852 -0.570896 -0.677436 0.4257 -0.332651 -0.841501 0.484444 -0.28893 -0.825732 0.875355 -0.113818 -0.469893 0.889584 -0.176743 -0.421191 0.689708 -0.389166 -0.610617 0.745682 -0.510387 -0.428325 0.502633 -0.715061 -0.485848 0.59326 -0.771102 -0.23118 0.546284 -0.815287 -0.192043 0.633764 -0.772239 0.0446084 0.590006 -0.801193 0.0999151 0.678251 -0.660531 0.321986 0.640944 -0.667855 0.378365 0.718701 -0.421408 0.553069 0.691735 -0.412406 0.592811 0.739911 -0.0743876 0.668579 0.727069 -0.0648237 0.683497 0.572898 0 -0.819627 0.850725 -0.0636531 -0.521743 0.879516 0.0576319 -0.472366 0.654678 0.089986 -0.750532 0.764993 0.0766687 -0.639459 0.845143 0.0602367 -0.531135 0.851114 0.0323968 -0.52398 0.850696 0 -0.525657 0.850696 0 -0.525657 0.851114 -0.0323833 -0.523981 0.345769 0.111701 -0.931647 0.488417 0.103879 -0.866405 0.149218 0.117711 -0.981773 0.201908 0.113124 -0.972849 0.201869 0 -0.979413 0.844346 -0.0637834 -0.531988 0.654705 -0.0899833 -0.75051 0.573019 -0.0930682 -0.81424 0.488413 -0.103879 -0.866407 0.345791 -0.1117 -0.931639 0.573019 0.0930691 -0.81424 0.572898 0 -0.819627 0.201869 0 -0.979413 0.201908 -0.113124 -0.97285 0.149216 -0.117711 -0.981773 0.340893 0.111913 0.933417 0.994035 0 -0.109062 0.994036 -0.0132062 -0.108246 0.994251 -0.0127471 -0.106317 0.991754 0.0155211 -0.127214 0.996676 0.00502731 -0.0813173 0.65868 0 0.752423 0.931791 0 0.362996 0.994046 0.0110552 -0.108403 0.993745 -0.0132938 0.110877 0.971837 -0.0280534 0.233979 0.994056 -0.00671749 -0.108663 0.994035 0 -0.109062 0.931791 0 0.362996 0.931639 -0.0497305 0.359967 0.558445 0.112612 0.821862 0.739311 0.08016 0.668576 0.931791 0.0432125 0.360415 0.888071 0.0662198 0.454911 0.971843 0.0280505 0.233955 0.237284 0 0.97144 0.237285 0.115644 0.964532 0.108127 0.132819 0.985225 0.887837 -0.0547791 0.456886 0.739295 -0.0801622 0.668593 0.658468 -0.0961999 0.746435 0.558108 -0.0987788 0.823868 0.340889 -0.111914 0.933418 0.658679 0.0895714 0.747073 0.65868 0 0.752423 0.237284 0 0.97144 0.237188 -0.12225 0.963741 0.108038 -0.118347 0.987077 0.939515 0.0414811 -0.339987 0.939606 0.0626261 -0.336479 0.93949 0.0628092 -0.336771 0.939578 0.0625079 -0.336581 0.939697 0.0614292 -0.336445 0.939842 0.0625217 -0.33584 0.939863 0.0625585 -0.335774 0.939744 0.0625588 -0.336106 0.939508 -0.041481 -0.340006 0.939901 -0.062617 -0.335657 0.939805 -0.0623805 -0.335968 0.939691 -0.0614397 -0.336462 0.939697 -0.0616385 -0.336407 0.939544 -0.0626382 -0.33665 0.939486 -0.0628379 -0.336776 0.939529 -0.0627208 -0.336677 0.939645 -0.062608 -0.336375 0.939777 -0.0625432 -0.336017 0.939515 -0.0414789 -0.339987 0.939511 -0.0414792 -0.339998 0.939694 -0.0211031 -0.341366 0.939693 -0.0210973 -0.341367 0.939497 0 -0.342556 0.939497 0 -0.342556 0.939693 0.0211045 -0.341367 0.939693 0.0211061 -0.341367 0.939511 0.0414814 -0.339999 0.939508 0.041483 -0.340006 0.93969 0.0616661 -0.336422 0 0.99599 0.0894671 -0.0289412 0.975765 0.216898 -0.00936842 0.961193 0.275717 0.00448699 0.892054 0.451907 -0.023165 0.792122 0.609923 -0.0032528 0.75885 0.651257 0.000781361 0.6196 0.784917 -0.0154083 0.459222 0.888188 0.000914068 0.424273 0.905534 -0.00109236 0.0397238 0.99921 0 0.0374734 0.999298 0.698517 0.698543 0.155276 0.698525 0.698537 0.155271 0.698521 0.566987 0.436571 0.698529 0.566982 0.436565 0.698529 0.32865 0.635646 0.698526 0.32865 0.635649 0.698526 0.0284257 0.71502 0.698522 0.0284245 0.715024 0 -0.997382 0.0723176 0.017655 -0.976951 0.21273 0.00801459 -0.967895 0.251226 -0.00277123 -0.90327 0.429063 0.0133473 -0.800097 0.599722 0.00231983 -0.775314 0.631572 -0.000405386 -0.639533 0.768764 0.00838806 -0.478327 0.878142 -0.00235482 -0.446283 0.894889 0.00260422 -0.0698959 0.997551 0 -0.0618195 0.998087 -0.698865 -0.0499939 0.713504 -0.698864 -0.0499935 0.713505 -0.703796 -0.290108 0.648466 -0.787843 -0.294601 0.540845 -0.698864 -0.698878 0.15218 -0.698862 -0.69888 0.152181 -0.698861 -0.572327 0.428994 -0.698865 -0.572325 0.428991 -0.70602 -0.420126 0.570113 0 0.0961512 0.995367 -0.0420201 0.0720984 0.996512 0 0.0240723 0.99971 0 -0.072162 0.997393 -0.0629304 -0.0959605 0.993394 0 -0.0240723 0.99971 -0.706177 0.0510935 -0.706189 -0.706183 0.0510933 -0.706183 -0.706183 -0.0510931 -0.706183 -0.706178 -0.0510937 -0.706188 -0.0015364 -0.570579 -0.821242 0.0135943 -0.372905 -0.92777 0.0104866 -0.365393 -0.930794 0 -0.170048 -0.985436 0.00718324 -0.722034 -0.69182 0.0225389 -0.756097 -0.654071 -0.00163199 -0.858582 -0.512674 0 -0.992988 -0.118213 0.0252484 -0.971566 -0.235417 0.00609792 -0.946776 -0.321837 0.000614211 -0.906658 -0.421866 0 0.00136859 0.999999 0.0262993 0.117038 0.992779 0.0108371 0.201918 0.979342 -0.0197309 0.50758 0.861379 0.00457574 0.999768 0.0210338 -6.57329e-05 0.998828 0.0483999 8.76747e-05 0.964338 0.264674 -0.00521357 0.957393 0.288742 0.00478563 0.862962 0.505247 0.0130117 0.884121 0.467077 -0.0208392 0.713213 0.700638 -0.00416522 0.751801 0.659377 0.00493708 0.442216 0.896895 0 0.395167 -0.918609 0.0272988 0.344206 -0.938497 -0.0219129 0.731917 -0.681042 0.00552731 0.683113 -0.730292 -4.23207e-06 0.819525 -0.573043 7.13062e-06 0.883454 -0.468518 0.0147455 0.846631 -0.531977 -0.0292812 0.97074 -0.238343 0.0251996 0.928281 -0.371025 -0.00320885 0.9898 -0.14243 -0.994042 0.0104801 -0.10849 -0.971841 -0.022657 0.234546 -0.658919 0 0.752214 -0.108086 0.0955879 0.989535 -0.558296 0.0797713 0.825798 -0.341054 0.0903866 0.935688 -0.237327 0.101702 0.966091 -0.237623 0.0233828 0.971076 -0.153992 0 0.988072 -0.237623 -0.0233828 0.971076 -0.237428 -0.0934017 0.966905 -0.887883 0.0442364 0.457937 -0.739466 0.0647288 0.670075 -0.108161 -0.113779 0.987601 -0.341054 -0.0903866 0.935688 -0.65892 -0.0723265 0.748728 -0.558603 -0.0971742 0.823723 -0.739471 -0.0647283 0.670069 -0.971845 0.0226552 0.234528 -0.931696 0.0430568 0.360677 -0.931861 0 0.362816 -0.658697 0.0806447 0.748074 -0.658919 0 0.752214 -0.931861 0 0.362816 -0.931861 -0.0348854 0.361135 -0.888089 -0.0586507 0.455914 -0.994042 -0.01048 -0.10849 -0.994042 -0.0104801 -0.108491 -0.994053 -0.00262192 -0.10887 -0.994978 0 -0.100096 -0.994053 0.00262121 -0.10887 -0.994042 0.01048 -0.108491 0 0.108126 -0.994137 0.063502 0.0720167 -0.99538 0 0.0361046 -0.999348 0 -0.0361046 -0.999348 0.0635019 -0.0720167 -0.99538 0 -0.108126 -0.994137 -0.127368 -0.35888 -0.924653 -0.0569859 -0.943012 -0.327843 -0.89141 -0.452679 0.0216781 -0.893727 -0.187204 -0.407684 -0.90088 -0.227545 -0.369646 -0.982603 -0.133126 -0.129495 -0.968986 -0.177365 -0.172069 -0.959181 -0.205789 -0.193967 -0.955076 -0.207184 -0.211906 -0.937214 -0.235985 -0.256792 -0.963018 -0.0999704 0.250206 -0.97139 -0.0819955 0.222887 -0.876426 -0.0946359 0.472146 -0.884046 -0.0865017 0.459325 -0.858961 -0.364387 0.359733 -0.839075 -0.390421 0.378846 -0.946586 -0.285122 0.150602 -0.938297 -0.3046 0.163761 -0.978164 -0.142368 -0.151414 -0.993506 -0.0428539 -0.105404 -0.993503 -0.0486698 -0.102875 -0.712673 -0.351996 -0.606792 -0.88495 -0.167831 -0.434391 -0.885797 -0.161989 -0.434882 -0.792139 -0.577207 0.198363 -0.849342 -0.526437 0.0385036 -0.805193 -0.58882 -0.070396 -0.812787 -0.568685 -0.12639 -0.759742 -0.590403 -0.272428 -0.771361 -0.552383 -0.316031 -0.722809 -0.518465 -0.456881 -0.133807 -0.985972 -0.0997711 -0.275273 -0.846459 -0.455777 -0.446693 -0.49036 -0.74834 -0.0444206 -0.718652 -0.693949 -0.119368 -0.883408 -0.453146 -0.332066 -0.793306 -0.510292 -0.192657 -0.88112 -0.431869 -0.933085 -0.230112 -0.276406 -0.918228 -0.236232 -0.317887 -0.916086 -0.238126 -0.322617 -0.902767 -0.202843 -0.379298 -0.738155 -0.475134 -0.47893 -0.697723 -0.384249 -0.604595 -0.461106 -0.520029 -0.718994 -0.105759 -0.0695627 0.991956 -0.121708 -0.0644773 0.99047 -0.085392 -0.469147 0.878982 -0.151913 -0.450624 0.879693 -0.0947171 -0.643356 0.759685 -0.147683 -0.777104 0.6118 -0.14887 -0.776775 0.61193 -0.223938 -0.96426 -0.141611 -0.0681437 -0.995635 0.0637765 -0.14354 -0.951985 0.270409 -0.246983 -0.945326 0.212977 -0.0723699 -0.904416 0.420469 -0.353643 -0.803348 -0.479133 -0.456007 -0.872356 -0.176217 -0.364126 -0.910248 -0.197131 -0.489617 -0.859824 0.14484 -0.398069 -0.906816 0.138654 -0.521633 -0.722078 0.454425 -0.443221 -0.766669 0.464516 -0.546162 -0.454931 0.703381 -0.493427 -0.484563 0.722308 -0.55329 -0.0887387 0.828249 -0.546207 -0.0917364 0.832612 -0.177309 -0.859162 -0.480002 -0.30152 -0.945809 -0.120547 -0.187422 -0.972113 -0.14096 -0.324422 -0.91701 0.232042 -0.209391 -0.952355 0.221755 -0.342312 -0.75396 0.560684 -0.242323 -0.790199 0.562907 -0.351084 -0.461929 0.81447 -0.282718 -0.488572 0.82545 -0.344985 -0.0734669 0.935729 -0.333632 -0.0777084 0.939495 -0.149398 -0.167664 -0.974458 -0.188635 -0.316759 -0.929559 -0.341412 -0.298094 -0.891391 -0.425 -0.300897 -0.853719 -0.48435 -0.260925 -0.835059 -0.687668 -0.203977 -0.696783 -0.647364 -0.260971 -0.71611 -0.87021 -0.0461706 -0.490513 -0.850011 -0.125874 -0.511506 -0.172302 -0.630416 -0.756893 -0.179688 -0.630605 -0.755016 -0.423352 -0.561772 -0.710764 -0.487235 -0.705169 -0.515111 -0.503327 -0.699097 -0.507864 -0.600326 -0.766834 -0.2271 -0.532647 -0.809175 -0.248038 -0.641642 -0.765424 0.0492219 -0.575726 -0.816422 0.0446491 -0.684278 -0.653989 0.322588 -0.62947 -0.700836 0.335554 -0.721165 -0.422443 0.549056 -0.685631 -0.451989 0.570628 -0.73982 -0.0884963 0.666959 -0.725698 -0.0976597 0.681046 -0.146449 0.336548 -0.930209 -0.824707 0.559531 -0.0823555 -0.651397 0.216102 -0.727312 -0.942264 0.255158 -0.216872 -0.971801 0.164042 -0.169389 -0.978816 0.147886 -0.141594 -0.989309 0.072105 -0.126759 -0.993672 0.0431599 -0.103696 -0.851107 0.0711759 -0.520146 -0.873465 0.155217 -0.461484 -0.889399 0.177383 -0.421312 -0.901406 0.20621 -0.380717 -0.895308 0.209764 -0.392968 -0.91823 0.230254 -0.322238 -0.74173 0.593926 -0.31159 -0.782193 0.559875 -0.273341 -0.708892 0.508747 -0.488518 -0.911959 0.238507 -0.333834 -0.938588 0.227486 -0.259427 -0.786965 0.607643 -0.107032 -0.849349 0.526424 0.038517 -0.792191 0.577118 0.198413 -0.856725 0.378362 0.350521 -0.843571 0.375409 0.384001 -0.884012 0.0941062 0.457894 -0.877483 0.0872924 0.471597 -0.921889 0.264423 -0.2832 -0.959989 0.184344 -0.210804 -0.891439 0.45262 0.0217074 -0.944652 0.295066 0.143421 -0.941308 0.293309 0.167058 -0.970892 0.0954306 0.219686 -0.965065 0.0835444 0.248336 -0.115176 0.205855 0.971781 -0.0767942 0.446104 0.89168 -0.146668 0.470706 0.870014 -0.0529747 0.754104 0.654615 -0.148666 0.776984 0.611714 -0.0857202 0.886277 0.455153 -0.146653 0.951562 0.270225 -0.333938 0.0734567 0.939728 -0.105758 0.0696426 0.99195 -0.296941 0.00671772 0.954872 -0.143081 0.952295 0.26956 -0.0595372 0.997383 0.0410138 -0.223388 0.96841 -0.110818 -0.116168 0.981115 -0.154656 -0.0132552 0.895531 -0.444802 -0.298393 0.873009 -0.385768 -0.10851 0.83556 -0.538576 -0.0837992 0.812343 -0.577128 -0.0301159 0.680996 -0.731668 -0.178506 0.630486 -0.755396 -0.112027 0.322935 -0.939767 -0.341441 0.298029 -0.891402 -0.692761 0.226547 -0.684659 -0.714395 0.371574 -0.592935 -0.412911 0.540091 -0.733353 -0.487266 0.705209 -0.515025 -0.353585 0.803416 -0.479063 -0.447568 0.869553 -0.208713 -0.377665 0.910825 -0.166636 -0.48002 0.870124 0.111648 -0.412114 0.895285 0.169192 -0.513927 0.742486 0.429644 -0.454271 0.746176 0.486682 -0.542569 0.47552 0.69246 -0.499063 0.464536 0.731534 -0.553202 0.0918056 0.827973 -0.546586 0.0885371 0.832709 -0.344659 0.0784327 0.935446 -0.287814 0.467047 0.83608 -0.346265 0.484581 0.803294 -0.253009 0.768586 0.58759 -0.332862 0.776782 0.534614 -0.223299 0.940752 0.255194 -0.313056 0.92914 0.196711 -0.200942 0.973629 -0.108023 -0.29165 0.94381 -0.155447 -0.187456 0.870202 -0.45564 -0.269275 0.834033 -0.48154 -0.179692 0.630514 -0.755091 -0.463515 0.545676 -0.698134 -0.425039 0.300841 -0.853719 -0.484353 0.260883 -0.83507 -0.870909 0.0935865 -0.482452 -0.89297 0.155792 -0.422296 -0.690173 0.369812 -0.622014 -0.744781 0.494289 -0.448308 -0.503293 0.699158 -0.507813 -0.593149 0.763295 -0.256035 -0.545221 0.80866 -0.220914 -0.633572 0.77344 0.0194174 -0.588805 0.805132 0.0712124 -0.67799 0.671066 0.300002 -0.63989 0.681953 0.354234 -0.718477 0.440043 0.538659 -0.691088 0.434099 0.577888 -0.739778 0.0971353 0.665803 -0.726934 0.0890133 0.680914 -0.939621 0.0370023 -0.34021 -0.939566 -0.0329192 -0.340783 -0.938389 -0.0498414 -0.341967 -0.939692 -0.0508149 -0.338226 -0.93943 -0.0518251 -0.3388 -0.939408 -0.0518973 -0.338849 -0.939889 -0.0514328 -0.337585 -0.939982 -0.0516739 -0.337288 -0.939936 -0.0515867 -0.337431 -0.939772 -0.0515726 -0.337889 -0.939571 -0.0516516 -0.338435 -0.939633 0.0516251 -0.338267 -0.939832 0.0515465 -0.337727 -0.940951 0.0488244 -0.335003 -0.939692 0.0507739 -0.338232 -0.939956 0.0515979 -0.337372 -0.939978 0.0516527 -0.337304 -0.939693 0.0502959 -0.338302 -0.939472 0.0517285 -0.338699 -0.93945 0.0517849 -0.33875 -0.939566 0.0329192 -0.340783 -0.94337 0.0336276 -0.330033 -0.936007 0.008472 -0.351879 -0.939622 0.0123554 -0.341991 -0.939661 -0.0082366 -0.342009 -0.937285 -0.0125847 -0.348336 -0.94337 -0.0336276 -0.330033 -0.939621 -0.0370023 -0.34021 -0.939692 -0.0502915 -0.338303 -0.149348 0.106913 -0.982988 -0.488786 0.0943294 -0.867289 -0.346056 -0.101445 -0.932714 -0.655057 -0.081697 -0.751149 -0.850962 -0.0567902 -0.522148 -0.850961 -0.0567906 -0.522149 -0.850961 -0.0189633 -0.524886 -0.850962 -0.0189631 -0.524885 -0.850962 0.0189632 -0.524885 -0.850961 0.0189631 -0.524886 -0.850961 0.0567904 -0.522149 -0.850962 0.0567905 -0.522148 -0.655067 0.0816962 -0.751141 -0.573444 0.081123 -0.815218 -0.573333 0.0295815 -0.818788 -0.573333 0.0295814 -0.818788 -0.573333 -0.0295815 -0.818788 -0.573333 -0.0295814 -0.818788 -0.573444 -0.0811235 -0.815218 -0.488787 -0.0943295 -0.867288 -0.346081 0.101444 -0.932704 -0.202125 0.100133 -0.974227 -0.202087 0.0353598 -0.978729 -0.202085 0.0353597 -0.978729 -0.202085 -0.0353598 -0.978729 -0.202086 -0.0353597 -0.978729 -0.202124 -0.100134 -0.974227 -0.149352 -0.106913 -0.982987 0.707097 0.124148 0.696133 0.671183 0.0864092 0.736238 0.706473 0.0842522 0.702708 0.706474 0 0.707739 0.706474 0 0.707739 0.706524 -0.0824922 0.702864 0.672818 -0.0880697 0.734548 0.707099 -0.124149 0.696131 0.706462 -0.0842531 -0.702719 0.706474 -0.0842522 -0.702706 0.706474 0 -0.707739 0.706474 0 -0.707739 0.706474 0.0842516 -0.702706 0.706463 0.0842535 -0.702717 0.697435 0.286292 -0.65698 0.697438 0.286289 -0.656977 0.69744 0.550005 -0.459426 0.697431 0.550014 -0.459429 0.697434 0.697454 -0.164753 0.697431 0.697457 -0.164752 0.694731 -0.306879 -0.650518 0.487516 -0.870122 -0.0722198 0.69474 -0.306878 -0.65051 0.702917 -0.537139 -0.466251 0.494624 -0.714146 -0.495322 0.705019 -0.637638 -0.310429 0.7037 -0.695441 -0.145492 0.7044 -0.708707 0.0394278 0.7044 -0.677594 0.211395 0.487523 -0.789654 0.372516 0.694738 -0.0594932 0.716798 0.694742 -0.0594916 0.716794 0.702917 -0.339721 0.624898 0.494621 -0.495323 0.714146 0.705015 -0.488448 0.514172 0.703698 -0.60038 0.379938 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.372128 -0.928181 -0.016886 0.39943 -0.916608 0.000228779 0.577753 -0.816211 -0.00142353 0.727618 -0.685981 -0.0291342 0.767148 -0.640808 0.0021586 0.870481 -0.492198 -0.00448284 0.949166 -0.314743 -0.0346899 0.97263 -0.229755 0 0.994873 -0.10113 0 0.0320584 0.999486 -0.0376686 -0.0826555 0.995866 -0.015424 -0.16901 0.985494 0.028332 -0.477433 0.878211 1.42751e-05 -0.998456 0.0555475 -0.0268683 -0.999224 -0.0288175 7.10296e-05 -0.99572 0.09242 -0.000100841 -0.954622 0.297821 -1.24279e-05 -0.954536 0.298095 -5.87399e-06 -0.845012 0.534748 -0.0342171 -0.894501 0.445755 0.0537473 -0.687743 0.723962 0.00712701 -0.75189 0.65925 -0.00709964 -0.410965 0.911623 0 -0.426657 -0.904414 -0.0330478 -0.385716 -0.922026 0.0252517 -0.754939 -0.655308 -0.0077793 -0.715062 -0.699018 4.57626e-06 -0.838756 -0.544508 -8.76008e-06 -0.899109 -0.437725 -0.0189361 -0.869189 -0.494117 0.0359293 -0.978177 -0.204642 -0.035276 -0.943533 -0.329394 2.71366e-05 -0.990912 -0.13451 0 -0.119043 -0.992889 0 -0.119043 -0.992889 0 0 -1 0 0 -1 0 0.119043 -0.992889 0 0.119043 -0.992889 0 -0.119044 0.992889 0 -0.119044 0.992889 0 0 1 0 0 1 0 0.119044 0.992889 0 0.119044 0.992889 0.879241 0.121053 -0.46074 0.887082 0.185208 -0.422829 0.954993 0.213682 -0.205741 0.960101 0.209238 -0.18554 0.978435 0.149538 -0.142487 0.978976 0.148081 -0.140277 0.991397 0.0621429 -0.115199 0.990797 0.0665721 -0.117852 0.965171 0.0742756 0.250854 0.793206 0.568249 0.218899 0.859466 0.349971 0.37261 0.839101 0.377561 0.391608 0.884189 0.0696553 0.461908 0.876484 0.0783715 0.475009 0.859294 0.489201 -0.14932 0.938543 0.241643 -0.246465 0.933189 0.238334 -0.26899 0.821646 0.569778 -0.0158331 0.847485 0.528506 0.0495142 0.891281 0.452011 0.0360981 0.947044 0.278 0.160701 0.938319 0.298971 0.173707 0.970911 0.0893289 0.222152 0.989049 0.0760291 0.126496 0.807332 0.43342 -0.400452 0.693235 0.678485 -0.243071 0.770714 0.636669 -0.0255294 0.902133 0.235404 -0.361581 0.887847 0.179408 -0.423722 0.749547 0.338767 -0.568698 0.710134 0.348524 -0.611752 0.133692 0.988785 -0.0665599 0.276009 0.862454 -0.424255 0.220913 0.877755 -0.425139 0.0485668 0.946608 -0.318706 0.47103 0.493643 -0.731059 0.0377209 0.72554 -0.687146 0.0993556 0.862548 -0.496125 0.146991 0.351798 -0.924463 0.123064 0.367057 -0.922022 0.10577 0.035672 0.993751 0.0953825 0.0393399 0.994663 0.111228 0.440406 0.890882 0.149993 0.42722 0.89162 0.0929529 0.622283 0.777254 0.157218 0.755571 0.63592 0.147157 0.758902 0.63436 0.245719 0.961748 -0.121095 0.0627153 0.994561 0.0831633 0.143381 0.942359 0.302326 0.246753 0.938125 0.24297 0.0700695 0.892661 0.445249 0.354235 0.819424 -0.450623 0.457121 0.877765 -0.143417 0.36318 0.916296 -0.168823 0.490839 0.853062 0.177093 0.397291 0.90236 0.16705 0.522587 0.703956 0.480987 0.442838 0.751482 0.48905 0.546615 0.428531 0.719426 0.49339 0.460222 0.73808 0.553361 0.0599239 0.830783 0.546232 0.0631192 0.835253 0.176414 0.87405 -0.452675 0.302666 0.949309 -0.0848917 0.186328 0.976231 -0.110701 0.32567 0.907136 0.266538 0.208497 0.945146 0.251454 0.343287 0.732018 0.588476 0.241844 0.771847 0.588017 0.351496 0.431636 0.830747 0.282651 0.460901 0.841236 0.345025 0.0404251 0.937723 0.33367 0.0450126 0.941615 0.879548 0.119854 -0.460468 0.76348 0.186666 -0.618267 0.693958 0.254637 -0.673486 0.651407 0.241371 -0.719312 0.484443 0.288979 -0.825716 0.918294 0.245881 -0.310287 0.901024 0.25951 -0.347578 0.75874 0.525223 -0.385298 0.805306 0.471418 -0.35951 0.700511 0.607173 -0.375 0.633805 0.450407 -0.628828 0.461121 0.542724 -0.70201 0.425671 0.332705 -0.841494 0.341464 0.328831 -0.880496 0.172206 0.654673 -0.736036 0.179207 0.65501 -0.734061 0.42409 0.586828 -0.689769 0.486869 0.72062 -0.493625 0.50266 0.715012 -0.485892 0.601383 0.773976 -0.198242 0.531877 0.816936 -0.222985 0.642847 0.762018 0.0779482 0.575093 0.815071 0.070194 0.685235 0.640527 0.346667 0.629216 0.68985 0.358041 0.721677 0.401415 0.563957 0.685622 0.432697 0.585402 0.73994 0.0647174 0.669553 0.72568 0.0744768 0.683989 -0.69474 0.284229 -0.660719 -0.458493 0.882586 -0.104045 -0.694738 0.284229 -0.660722 -0.702912 0.520721 -0.484526 -0.466761 0.708857 -0.528825 -0.705015 0.626539 -0.33227 -0.703696 0.690007 -0.169415 -0.69474 0.0842102 0.714315 -0.694739 0.0842102 0.714315 -0.702917 0.361098 0.612794 -0.782473 0.28093 0.55571 -0.561442 0.590323 0.579915 -0.701772 0.475007 0.530928 -0.703697 0.613141 0.358982 -0.458483 0.816371 0.351187 -0.704396 0.684494 0.187867 -0.704397 0.70965 0.0149301 -0.696947 -0.267443 -0.665386 -0.696946 -0.267444 -0.665387 -0.696947 -0.542352 -0.469168 -0.696945 -0.542354 -0.469169 -0.696947 -0.696954 -0.168877 -0.696944 -0.696957 -0.168877 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 -0.0510932 0.706188 -0.706177 -0.0510934 0.70619 -0.706177 0.0510933 0.70619 -0.706177 0.0510933 0.706189 0.698658 0.569061 -0.433643 0.698651 0.569068 -0.433645 0.698648 0.698679 -0.154074 0.698663 0.698663 -0.154076 0.694737 0.059496 -0.716799 0.487522 -0.717434 -0.497605 0.694745 0.0594929 -0.716792 0.702919 -0.232047 -0.672353 0.494616 -0.37081 -0.786038 0.70501 -0.396999 -0.587667 0.703693 -0.529532 -0.473722 0.704404 -0.633468 -0.320209 0.704404 -0.692506 -0.155722 0.48753 -0.870115 -0.0722165 0.694738 -0.409921 0.591019 0.694737 -0.409923 0.59102 0.702911 -0.606661 0.371318 0.494622 -0.786034 0.370809 0.70502 -0.68009 0.201058 0.703701 -0.70991 0.0288465 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.796801 -0.604241 0.00144315 0.795382 -0.606107 -0.0012211 0.969426 -0.245379 -0.0167207 0.976401 -0.215317 0 0.999446 -0.0332923 0 -0.471978 0.88161 -0.0376687 -0.569514 0.821118 -0.0154232 -0.639116 0.768956 0.0283328 -0.852576 0.521835 1.38157e-05 -0.892461 -0.451126 -0.0268685 -0.850942 -0.524571 7.19003e-05 -0.90853 -0.417821 -0.000100337 -0.975637 -0.219389 -1.27816e-05 -0.9757 -0.219112 -6.56739e-06 -0.999175 0.0406006 -0.0342142 -0.997539 -0.0612039 0.0537465 -0.957585 0.283095 0.00712827 -0.980781 0.194984 -0.00709875 -0.811719 0.584005 0 0.0827144 -0.996573 -0.0330468 0.126975 -0.991355 0.0252519 -0.326139 -0.944984 -0.00778128 -0.269745 -0.9629 6.76092e-06 -0.454221 -0.890889 -6.56642e-06 -0.559786 -0.828637 -0.0189338 -0.505678 -0.862515 0.0359317 -0.744809 -0.66631 -0.0352778 -0.652425 -0.757032 2.71713e-05 -0.790905 -0.611939 0 0.39335 -0.919389 0 0.39335 -0.919389 0 0.5 -0.866026 0 0.5 -0.866026 0 0.59954 -0.800345 0 0.59954 -0.800345 0 -0.599539 0.800345 0 -0.599539 0.800345 0 -0.5 0.866025 0 -0.5 0.866025 0 -0.393349 0.919389 0 -0.393349 0.919389 0.879244 0.335201 -0.338482 0.887082 0.371801 -0.273585 0.954991 0.287928 -0.0713393 0.960102 0.273974 -0.0560618 0.978436 0.200746 -0.0486265 0.978976 0.198381 -0.0474424 0.991397 0.111416 -0.0686937 0.990797 0.11658 -0.0687771 0.965171 -0.0611024 0.254384 0.793205 0.382671 0.473697 0.859465 0.116777 0.497677 0.839105 0.131168 0.527918 0.884189 -0.170631 0.43485 0.876484 -0.169633 0.450556 0.859289 0.498326 0.115299 0.938544 0.332498 -0.0926245 0.933188 0.340898 -0.113792 0.821644 0.501363 0.271175 0.847484 0.432945 0.307132 0.891285 0.373399 0.257261 0.947045 0.160401 0.278167 0.938319 0.172061 0.299921 0.970911 -0.0337148 0.237054 0.989049 0.00259427 0.147566 0.807334 0.575576 -0.130093 0.693244 0.709114 0.128725 0.770721 0.564131 0.296219 0.902133 0.384658 -0.195436 0.887846 0.367234 -0.277252 0.74955 0.577725 -0.323124 0.71014 0.6077 -0.355531 0.011953 0.890972 0.453901 0.275999 0.959037 0.0638151 0.0335803 0.968393 -0.247158 0.0888937 0.995253 -0.0396058 0.18827 0.979278 0.0746286 -0.0536539 0.978013 0.201526 0.268371 0.834578 0.481099 0.146987 0.7669 -0.624708 0.0953329 0.791946 -0.603103 0.0937627 0.14727 0.984642 0.149996 -0.0758295 0.985774 0.111228 -0.06404 0.991729 0.0953823 -0.463266 0.881072 0.105767 -0.465985 0.878448 0.110833 0.20268 0.972953 0.174146 0.337204 0.925185 0.144248 0.348875 0.926001 0.143409 0.664943 0.732997 0.26628 0.69483 0.668061 0.067017 0.557912 0.82719 0.354236 0.934953 0.0194633 0.45712 0.831876 0.314681 0.363167 0.877952 0.311944 0.490827 0.650232 0.579903 0.3973 0.697935 0.595852 0.522597 0.369145 0.768521 0.442828 0.406281 0.799274 0.546608 0.0114084 0.837311 0.493396 0.0295227 0.869304 0.553364 -0.363496 0.749439 0.546226 -0.362963 0.754914 0.176404 0.983289 0.0450001 0.302661 0.864571 0.401141 0.186316 0.900792 0.39225 0.325664 0.652334 0.6844 0.208482 0.692795 0.690341 0.343264 0.339716 0.87565 0.241859 0.374426 0.895159 0.351507 -0.0415673 0.935262 0.282646 -0.0214629 0.958984 0.34503 -0.433853 0.832301 0.333672 -0.431826 0.837967 0.87955 0.334029 -0.338845 0.763477 0.470796 -0.442101 0.693963 0.557261 -0.455934 0.651406 0.568687 -0.502261 0.484448 0.663115 -0.570604 0.918302 0.368068 -0.145766 0.901024 0.398531 -0.171259 0.758725 0.647523 -0.0710634 0.805312 0.588007 -0.0756345 0.7005 0.713338 -0.0211624 0.633796 0.704489 -0.319371 0.461114 0.821025 -0.336587 0.425662 0.708883 -0.562403 0.341456 0.725028 -0.598116 0.193423 0.93272 -0.304338 0.179193 0.934287 -0.308216 0.424099 0.853086 -0.303947 0.486878 0.870882 -0.0671854 0.502668 0.86216 -0.063292 0.601389 0.7694 0.2153 0.531874 0.818983 0.215351 0.642853 0.620947 0.448515 0.575087 0.670777 0.46833 0.685228 0.381383 0.620491 0.629213 0.418409 0.655 0.721678 0.0656556 0.689109 0.685622 0.0820237 0.723322 0.739939 -0.278728 0.61221 0.725685 -0.277495 0.629586 0.146163 0.129402 -0.980761 0.82627 -0.455461 -0.331411 0.651432 0.150659 -0.743598 0.880894 0.0695808 -0.468171 0.992268 -0.0197093 -0.122537 0.992327 0.0242021 -0.12125 0.976264 -0.0735513 -0.203712 0.978908 -0.0571869 -0.196136 0.963204 -0.0839274 -0.255332 0.942933 -0.118569 -0.311157 0.902137 -0.00439737 -0.431428 0.895801 5.05888e-05 -0.444455 0.919327 -0.052437 -0.389985 0.851019 0.1916 -0.488934 0.740541 -0.37551 -0.557307 0.783615 -0.367404 -0.50096 0.707954 -0.216517 -0.672251 0.912306 -0.0525393 -0.406124 0.939734 -0.0786479 -0.332739 0.785901 -0.485135 -0.38341 0.847486 -0.482442 -0.221397 0.793257 -0.601511 -0.0944874 0.85696 -0.498428 0.131106 0.844208 -0.510456 0.163545 0.884163 -0.29809 0.359719 0.877676 -0.297745 0.375543 0.923009 -0.0954146 -0.372761 0.960832 -0.0674032 -0.26881 0.891329 -0.409416 -0.194709 0.944823 -0.327338 -0.0126426 0.94184 -0.335895 0.0105379 0.970919 -0.188451 0.147656 0.965173 -0.189778 0.180073 0.115156 -0.638353 0.761081 0.0770959 -0.812085 0.578424 0.146476 -0.824606 0.546416 0.0440378 -0.98046 0.191725 0.0570955 -0.980914 0.185872 0.099827 -0.992277 -0.0736247 0.181851 -0.960118 -0.212377 0.33401 -0.505776 0.795379 0.105773 -0.527832 0.842737 0.27892 -0.456825 0.844698 0.0122822 -0.579226 -0.815075 0.315353 -0.596696 -0.737906 0.112596 -0.494018 -0.86213 0.136023 -0.963624 -0.230058 0.0636064 -0.904068 -0.42263 0.202853 -0.808657 -0.5522 0.247973 -0.810534 -0.530608 0.108797 -0.779946 -0.616318 0.0842628 -0.447246 -0.890433 0.0328657 -0.267392 -0.963027 0.19022 -0.20211 -0.960712 0.0915631 0.157091 -0.98333 0.341451 0.155544 -0.92694 0.693998 0.116231 -0.710533 0.714755 -0.051074 -0.697508 0.412209 -0.129499 -0.901839 0.48692 -0.377328 -0.787739 0.354181 -0.484427 -0.799929 0.447644 -0.668545 -0.593854 0.378526 -0.725902 -0.574269 0.480143 -0.820053 -0.311409 0.413106 -0.8697 -0.270119 0.514063 -0.857243 0.0295604 0.455177 -0.886765 0.080386 0.542685 -0.745245 0.387431 0.499643 -0.752813 0.42852 0.553288 -0.470131 0.687641 0.546659 -0.469199 0.693554 0.344681 -0.508531 0.789045 0.288262 -0.80432 0.51959 0.346231 -0.805442 0.481027 0.253713 -0.954157 0.158787 0.332849 -0.936981 0.106198 0.224043 -0.950394 -0.21577 0.313047 -0.912343 -0.263879 0.201534 -0.808975 -0.552217 0.29165 -0.759408 -0.581583 0.187835 -0.554433 -0.810754 0.269281 -0.509031 -0.817542 0.179189 -0.200112 -0.963248 0.463853 -0.155694 -0.872124 0.425704 0.132667 -0.895084 0.484447 0.162646 -0.859568 0.875353 0.136381 -0.46385 0.889583 0.0575362 -0.453135 0.689703 -0.0317139 -0.723397 0.745681 -0.227848 -0.626135 0.502634 -0.376337 -0.778286 0.593257 -0.552205 -0.585761 0.546278 -0.610043 -0.573958 0.633759 -0.691087 -0.347489 0.59 -0.743815 -0.314069 0.678247 -0.733034 -0.0514098 0.640949 -0.767558 -0.00625771 0.718704 -0.641483 0.268261 0.691734 -0.653561 0.307186 0.739911 -0.398712 0.541813 0.727066 -0.397888 0.559517 0.572897 0.409813 -0.709818 0.850727 0.205745 -0.483666 0.879519 0.286091 -0.38026 0.654678 0.453197 -0.604987 0.764991 0.386128 -0.515455 0.845143 0.317734 -0.429858 0.851115 0.290042 -0.437583 0.850697 0.262828 -0.455231 0.850696 0.262829 -0.455233 0.851114 0.233939 -0.469976 0.345767 0.56256 -0.75098 0.488419 0.523164 -0.698389 0.149212 0.592828 -0.791385 0.201913 0.584392 -0.78595 0.201873 0.489705 -0.848196 0.844347 0.210755 -0.492605 0.654699 0.297329 -0.694956 0.573017 0.326521 -0.751688 0.488419 0.343241 -0.802267 0.345752 0.36909 -0.862686 0.573015 0.487722 -0.65862 0.572895 0.409814 -0.70982 0.201868 0.489706 -0.848196 0.201909 0.388456 -0.899074 0.149221 0.388946 -0.909095 0.340891 -0.369789 0.86432 0.994035 0.0545309 -0.0944503 0.994036 0.0426861 -0.100347 0.994251 0.0421194 -0.098447 0.991754 0.0770491 -0.102411 0.996676 0.0450112 -0.0679079 0.658677 -0.376213 0.65162 0.931791 -0.181498 0.314364 0.994046 0.0637753 -0.0883519 0.993745 -0.0669509 0.089375 0.971837 -0.141284 0.188605 0.994056 0.0485145 -0.0974635 0.994035 0.054531 -0.0944505 0.931791 -0.181498 0.314364 0.931639 -0.223051 0.286875 0.558447 -0.313407 0.768058 0.739309 -0.264868 0.619086 0.931791 -0.142784 0.333734 0.888074 -0.170106 0.427071 0.971842 -0.0926858 0.216638 0.237287 -0.48572 0.841291 0.237286 -0.382115 0.893131 0.108128 -0.377588 0.919639 0.887836 -0.275884 0.368287 0.739301 -0.403715 0.538933 0.658466 -0.456531 0.598333 0.5581 -0.497482 0.664105 0.34089 -0.563629 0.752407 0.658677 -0.295966 0.691772 0.658677 -0.376213 0.65162 0.237287 -0.48572 0.841291 0.237189 -0.587742 0.773499 0.108037 -0.59603 0.795661 0.939515 0.205917 -0.273697 0.939602 0.222485 -0.260095 0.93949 0.222776 -0.260249 0.939578 0.222421 -0.260235 0.939697 0.221422 -0.260656 0.939842 0.222064 -0.259584 0.939865 0.222063 -0.259503 0.939743 0.222233 -0.259798 0.939508 0.134079 -0.315195 0.939903 0.113597 -0.321992 0.939805 0.113966 -0.322147 0.93969 0.115025 -0.322104 0.939696 0.114818 -0.322161 0.939545 0.114082 -0.322863 0.939487 0.113974 -0.323069 0.939528 0.114022 -0.322935 0.939641 0.11397 -0.322623 0.939778 0.113842 -0.322268 0.939514 0.134073 -0.31518 0.939511 0.134077 -0.315186 0.939694 0.152409 -0.306183 0.939694 0.152408 -0.306183 0.939498 0.171278 -0.296662 0.939498 0.171278 -0.296662 0.939694 0.188959 -0.28508 0.939693 0.188959 -0.28508 0.939511 0.205922 -0.273706 0.939507 0.20593 -0.273713 0.93969 0.22161 -0.260523 0 0.980345 0.197293 -0.0147988 0.974164 0.225356 0.00919313 0.852938 0.521932 -0.0320484 0.775903 0.630038 4.6537e-05 0.195435 0.980717 -0.000408726 0.340778 0.940144 -0.0292571 0.420417 0.906859 0.00281937 0.554091 0.832452 -0.00332507 0.701544 0.712618 -0.00141608 0.140908 0.990022 -0.0215486 -0.0205663 0.999556 0.00423099 -0.0851483 0.996359 -0.00527105 -0.457557 0.889165 0 -0.467199 0.884152 0.697832 0.697832 0.161431 0.697822 0.697842 0.161437 0.697823 0.556042 0.45151 0.697829 0.556039 0.451504 0.697828 0.301259 0.64983 0.697829 0.301259 0.649828 0.697829 -0.0147343 0.716113 0.697828 -0.0147347 0.716114 0.697828 -0.327737 0.636887 0.697834 -0.327732 0.636882 0 -0.989139 0.14698 0.0121337 -0.980269 0.197294 0.000276862 -0.941878 0.335956 -0.00108225 -0.827686 0.561191 0.00242649 -0.833749 0.552138 -0.000121997 -0.698928 0.715192 0.00291238 -0.546143 0.837687 0 -0.537826 0.843056 -0.70004 -0.700066 0.140899 -0.700049 -0.39 0.59819 -0.700048 -0.39 0.598192 -0.702984 -0.569466 0.426055 -0.763184 -0.534836 0.362631 -0.706724 -0.638977 0.303727 -0.700053 -0.700054 0.140892 -0.694736 0.576511 -0.43009 -0.45848 0.816372 0.351187 -0.694743 0.576507 -0.430084 -0.702915 0.693218 -0.159247 -0.46676 0.878302 -0.103541 -0.705015 0.708733 0.0255211 -0.703697 0.682273 0.198278 -0.694743 -0.284227 0.660717 -0.69474 -0.284227 0.66072 -0.702916 0.00632053 0.711245 -0.782473 -0.0345652 0.621724 -0.561446 0.221274 0.797381 -0.70177 0.145904 0.697302 -0.703698 0.351507 0.617456 -0.458487 0.531405 0.712319 -0.704397 0.498856 0.504943 -0.704397 0.607109 0.367755 -0.696408 -0.696434 -0.173192 -0.696421 -0.696421 -0.173192 -0.703796 -0.576533 -0.415067 -0.504597 -0.642641 -0.576536 -0.696414 0.0968764 -0.711071 -0.696412 0.0968761 -0.711074 -0.703789 -0.172199 -0.689223 -0.504592 -0.297729 -0.810398 -0.70507 -0.332851 -0.626168 -0.705071 -0.458499 -0.540975 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706181 -0.39734 0.586028 -0.706169 -0.397347 0.586037 -0.70617 -0.30885 0.63713 -0.706178 -0.308846 0.637124 0 -0.414414 0.910089 -0.042021 -0.435817 0.899054 0 -0.479009 0.87781 0 -0.56119 0.827687 -0.0629317 -0.579801 0.812324 0 -0.520701 0.853739 -0.706174 0.397344 -0.586034 -0.706182 0.39734 -0.586027 -0.706182 0.308844 -0.63712 -0.706178 0.308846 -0.637124 0 0.175912 -0.984406 0.0159011 0.134976 -0.990721 2.47348e-05 -0.0665395 -0.997784 4.55873e-06 -0.242395 -0.970178 -2.4214e-05 -0.242502 -0.970151 2.89053e-05 -0.469374 -0.882999 -0.00193267 -0.47802 -0.878347 0.00175657 -0.646558 -0.762863 8.89215e-06 -0.654017 -0.75648 -1.38105e-05 -0.810302 -0.586012 0.000488303 -0.811559 -0.584271 -0.000221922 -0.906652 -0.421879 0.0176318 -0.97029 -0.241301 0 -0.982114 -0.18829 0 -0.498818 0.866707 0.0263006 -0.39503 0.918292 0.0108378 -0.314801 0.949096 -0.0197296 0.0088845 0.999766 0.00457598 0.855308 0.5181 -6.6972e-05 0.840805 0.541337 8.65171e-05 0.702806 0.711382 -0.00521532 0.684755 0.728755 0.00478379 0.494727 0.869035 0.0130117 0.532144 0.846554 -0.0208412 0.267338 0.963377 -0.00416642 0.32139 0.946938 0.00493597 -0.0654732 0.997842 0 0.801529 -0.597955 0.0272957 0.767344 -0.640654 -0.0219165 0.97438 -0.223836 0.00552559 0.956739 -0.290895 -2.82757e-06 0.996241 -0.0866214 8.55707e-06 0.999352 0.0359861 0.0147424 0.999193 -0.0373602 -0.0292786 0.959859 0.278949 0.0251997 0.989428 0.142819 -0.00320902 0.928407 0.37155 -0.994042 0.0633214 -0.0887158 -0.971841 -0.136893 0.191793 -0.658919 -0.376107 0.651436 -0.108084 -0.411986 0.904757 -0.558294 -0.343816 0.755049 -0.341055 -0.389567 0.855523 -0.237322 -0.394969 0.887512 -0.237617 -0.46529 0.852669 -0.153991 -0.494036 0.855696 -0.237618 -0.505788 0.829287 -0.237423 -0.564341 0.790664 -0.887883 -0.190659 0.418704 -0.739469 -0.27898 0.612663 -0.10816 -0.592336 0.798398 -0.341051 -0.546122 0.765137 -0.658919 -0.437001 0.612255 -0.558603 -0.496017 0.664778 -0.739473 -0.391089 0.547931 -0.971845 -0.0976444 0.214435 -0.931696 -0.143051 0.333885 -0.931861 -0.181408 0.314208 -0.658698 -0.304196 0.688172 -0.658921 -0.376106 0.651435 -0.931861 -0.181408 0.314208 -0.931861 -0.210779 0.29531 -0.888088 -0.278752 0.36551 -0.994042 0.0451692 -0.0991954 -0.994042 0.0451692 -0.0991955 -0.994053 0.0521643 -0.0955954 -0.994978 0.0500475 -0.0866847 -0.994053 0.0567048 -0.0929732 -0.994042 0.0633209 -0.0887148 0 0.590708 -0.806885 0.063502 0.560058 -0.826016 0 0.530941 -0.847409 0 0.468406 -0.883513 0.0635013 0.435322 -0.898033 0 0.403429 -0.915011 -0.891408 -0.402875 -0.207566 -0.893727 0.0417178 -0.446667 -0.90088 -0.0122353 -0.433896 -0.982603 -0.0505423 -0.178708 -0.968982 -0.0675722 -0.237714 -0.95918 -0.0812334 -0.270877 -0.955076 -0.0734721 -0.287111 -0.937213 -0.0759712 -0.340381 -0.963018 -0.211679 0.166699 -0.97139 -0.182454 0.152028 -0.876425 -0.318032 0.361573 -0.884047 -0.304573 0.354536 -0.858962 -0.495434 0.129344 -0.839077 -0.527536 0.132879 -0.946585 -0.322227 -0.0121334 -0.938296 -0.345673 -0.0104764 -0.978164 -0.0475858 -0.202312 -0.993506 0.0155897 -0.11271 -0.993503 0.00928727 -0.113428 -0.712673 -0.00144544 -0.701495 -0.884951 0.0718471 -0.460109 -0.8858 0.077161 -0.457608 -0.792139 -0.599057 -0.116817 -0.849341 -0.475161 -0.229873 -0.805193 -0.474737 -0.355372 -0.812788 -0.429297 -0.393802 -0.759744 -0.375088 -0.531129 -0.771362 -0.320364 -0.549879 -0.72281 -0.220562 -0.654903 -0.18212 -0.783809 -0.593696 -0.13379 -0.803996 -0.579389 -0.0550051 -0.648478 -0.759243 -0.275275 -0.505165 -0.817944 -0.32966 -0.423918 -0.843575 -0.0482174 -0.548966 -0.834453 -0.0957221 -0.234753 -0.967331 -0.146939 0.190427 -0.970642 -0.122997 0.177542 -0.976397 -0.158568 -0.0573581 -0.985681 -0.106258 -0.536885 0.836937 -0.16672 -0.553163 0.81622 -0.107832 -0.698555 0.707385 -0.0853867 -0.845787 0.526643 -0.0736528 -0.900333 -0.428924 -0.15625 -0.966291 -0.204618 -0.028261 -0.973326 -0.227681 -0.141868 -0.981262 0.130376 -0.170652 -0.975651 0.137779 -0.091916 -0.940755 0.326393 -0.15192 -0.830099 0.536522 -0.353636 -0.456158 -0.816616 -0.456004 -0.667376 -0.588787 -0.364119 -0.689735 -0.625845 -0.489609 -0.817053 -0.304478 -0.398059 -0.854657 -0.333332 -0.52163 -0.852552 0.0325087 -0.443212 -0.896216 0.0189514 -0.546156 -0.745676 0.381682 -0.493422 -0.7808 0.383257 -0.553285 -0.490975 0.672918 -0.546203 -0.495752 0.675198 -0.177325 -0.504054 -0.845273 -0.301525 -0.75882 -0.5773 -0.187427 -0.771394 -0.60813 -0.32443 -0.910172 -0.257549 -0.20939 -0.935641 -0.284133 -0.342315 -0.933289 0.108589 -0.242325 -0.965786 0.0923953 -0.35108 -0.807281 0.474384 -0.282726 -0.83584 0.470572 -0.344991 -0.531486 0.773631 -0.333634 -0.537044 0.774772 -0.48435 0.191566 -0.853644 -0.687667 0.171746 -0.70542 -0.647368 0.132056 -0.75065 -0.870212 0.205276 -0.447876 -0.85001 0.146741 -0.505915 -0.933087 -0.0610847 -0.354424 -0.918227 -0.045642 -0.393415 -0.916086 -0.0449177 -0.398458 -0.902766 0.0139798 -0.429904 -0.738156 -0.172013 -0.652332 -0.697725 -0.0304735 -0.715718 -0.461102 -0.0908644 -0.882683 -0.424995 0.166277 -0.889793 -0.341424 0.187537 -0.92101 -0.222903 -0.174888 -0.959025 -0.179694 -0.16861 -0.969165 -0.423352 -0.131125 -0.896426 -0.487236 -0.353137 -0.798683 -0.503326 -0.351503 -0.789372 -0.600327 -0.550547 -0.580092 -0.53265 -0.576746 -0.619394 -0.641642 -0.687486 -0.340087 -0.57574 -0.729358 -0.369541 -0.684285 -0.727658 -0.047626 -0.629473 -0.774716 -0.0598217 -0.721169 -0.640371 0.264273 -0.685635 -0.676745 0.268182 -0.739823 -0.410117 0.533353 -0.725703 -0.425095 0.540971 -0.146451 0.756567 -0.637305 -0.824705 0.525749 0.208447 -0.651388 0.550808 -0.521829 -0.942265 0.329406 -0.0602401 -0.971801 0.226761 -0.064676 -0.978816 0.198869 -0.048681 -0.98931 0.125823 -0.0737239 -0.993672 0.0892259 -0.0682234 -0.851107 0.321713 -0.41487 -0.873463 0.365167 -0.32205 -0.889404 0.364277 -0.276159 -0.901406 0.368942 -0.226604 -0.895307 0.378146 -0.235438 -0.918229 0.360527 -0.16394 -0.741726 0.670154 0.0271181 -0.782197 0.62153 0.0432207 -0.708897 0.684841 -0.168695 -0.91196 0.373468 -0.169854 -0.938588 0.326722 -0.110928 -0.786963 0.579752 0.211132 -0.849347 0.436643 0.296569 -0.792187 0.400597 0.460392 -0.856723 0.152408 0.492744 -0.843569 0.133111 0.520262 -0.88401 -0.147452 0.443604 -0.877482 -0.160201 0.452062 -0.921887 0.370602 -0.113048 -0.959988 0.265051 -0.0903907 -0.891439 0.381129 0.245108 -0.944652 0.183825 0.271736 -0.941309 0.170483 0.291331 -0.970892 -0.0271979 0.237968 -0.965065 -0.0518168 0.256836 -0.115184 -0.307611 0.944515 -0.0768063 -0.0594983 0.995269 -0.146659 -0.0273696 0.988809 -0.0529624 0.325764 0.943967 -0.148657 0.36703 0.918254 -0.085703 0.539972 0.837308 -0.146632 0.688967 0.709805 -0.333937 -0.406248 0.850558 -0.105756 -0.435662 0.893876 -0.296955 -0.47162 0.830297 -0.143071 0.689931 0.709596 -0.0595304 0.843247 0.53422 -0.223384 0.894074 0.388241 -0.116145 0.927001 0.356623 -0.0132361 0.997954 0.0625499 -0.298385 0.948935 0.102417 -0.108542 0.992902 -0.0486136 -0.0837558 0.992067 -0.0937459 -0.0301008 0.955594 -0.293144 -0.178499 0.923716 -0.33895 -0.112024 0.749556 -0.652393 -0.341476 0.703793 -0.622952 -0.692765 0.538524 -0.479655 -0.714398 0.618259 -0.327705 -0.412918 0.834408 -0.365051 -0.487271 0.868239 -0.093425 -0.353581 0.935311 -0.0131717 -0.447566 0.857412 0.254025 -0.377651 0.872118 0.31111 -0.48001 0.697728 0.531758 -0.412112 0.690746 0.594167 -0.513927 0.428192 0.743324 -0.454273 0.402868 0.794565 -0.542568 0.065581 0.837448 -0.499061 0.0365301 0.865796 -0.553201 -0.334481 0.762949 -0.546584 -0.33968 0.765417 -0.344655 -0.399799 0.849337 -0.287811 -0.01357 0.957591 -0.346267 0.0180098 0.937963 -0.253007 0.37182 0.893161 -0.332867 0.405409 0.851377 -0.223309 0.68712 0.691375 -0.313064 0.706304 0.634922 -0.200958 0.897194 0.393267 -0.291673 0.89508 0.337281 -0.187473 0.981435 0.0404953 -0.269268 0.963065 -7.72812e-06 -0.179685 0.923588 -0.338673 -0.46351 0.821639 -0.331766 -0.425032 0.687395 -0.588928 -0.48435 0.643463 -0.592757 -0.870904 0.322274 -0.371033 -0.892968 0.346071 -0.287824 -0.690171 0.631275 -0.353775 -0.744777 0.652223 -0.141108 -0.503285 0.859399 -0.0902067 -0.593144 0.789053 0.159927 -0.545231 0.810772 0.213007 -0.63358 0.660107 0.403529 -0.588811 0.661656 0.464235 -0.677991 0.431163 0.595338 -0.639887 0.413473 0.647753 -0.718477 0.111757 0.686514 -0.69109 0.086996 0.717514 -0.739779 -0.248778 0.625169 -0.726935 -0.263368 0.634194 -0.939621 0.20215 -0.276129 -0.939565 0.141883 -0.311587 -0.938393 0.127812 -0.321064 -0.939692 0.125107 -0.31832 -0.939428 0.124515 -0.31933 -0.939407 0.124479 -0.319404 -0.939889 0.124252 -0.318074 -0.939982 0.123895 -0.317937 -0.939935 0.124042 -0.318018 -0.939774 0.12428 -0.318401 -0.939573 0.124485 -0.318915 -0.939633 0.213843 -0.267136 -0.939832 0.213504 -0.266707 -0.940956 0.209771 -0.265703 -0.939692 0.213086 -0.267532 -0.93996 0.213373 -0.266359 -0.939978 0.213384 -0.266287 -0.939693 0.212706 -0.267831 -0.939471 0.214149 -0.267458 -0.93945 0.214223 -0.267474 -0.939566 0.1989 -0.278666 -0.94337 0.194139 -0.269004 -0.936007 0.183277 -0.300501 -0.939622 0.181696 -0.289995 -0.93966 0.163871 -0.300308 -0.937285 0.163269 -0.30796 -0.94337 0.135894 -0.302631 -0.939622 0.13806 -0.313131 -0.939693 0.125596 -0.318125 -0.149349 0.584083 -0.797836 -0.488783 0.515338 -0.70393 -0.34607 0.378501 -0.858471 -0.655061 0.304821 -0.69136 -0.850962 0.211892 -0.480589 -0.850961 0.211892 -0.48059 -0.850961 0.246021 -0.464047 -0.850961 0.246021 -0.464046 -0.850961 0.278866 -0.445083 -0.850962 0.278865 -0.445083 -0.850962 0.310256 -0.423799 -0.850962 0.310256 -0.423798 -0.65506 0.446325 -0.609664 -0.573441 0.477866 -0.66544 -0.57333 0.435013 -0.694303 -0.573334 0.435012 -0.6943 -0.573334 0.383776 -0.723882 -0.573328 0.383777 -0.723885 -0.573439 0.337356 -0.746564 -0.488784 0.351954 -0.79826 -0.346117 0.554198 -0.757012 -0.202128 0.573831 -0.793639 -0.20209 0.519987 -0.829924 -0.202083 0.519987 -0.829925 -0.202083 0.458742 -0.865285 -0.202088 0.458742 -0.865284 -0.202126 0.400396 -0.893772 -0.149349 0.398905 -0.904749 0.707099 -0.240545 0.664943 0.671181 -0.293287 0.680807 0.706471 -0.27839 0.65069 0.70647 -0.353871 0.612923 0.70647 -0.353871 0.612923 0.706522 -0.422874 0.567454 0.672819 -0.443544 0.592101 0.707109 -0.455584 0.540777 0.706469 0.278391 -0.650692 0.706477 0.278388 -0.650685 0.706477 0.353868 -0.612918 0.70647 0.353871 -0.612923 0.70647 0.42432 -0.566438 0.706472 0.424319 -0.566437 -0.0339768 0.972399 0.230839 -0.0130007 0.983125 0.182473 0 0.99955 0.0300103 -1.24012e-06 0.255524 0.966803 -0.0270586 0.374482 0.926839 -0.0339714 0.394145 0.91842 0.00634568 0.529106 0.848532 -6.10343e-06 0.614563 0.788868 6.72096e-07 0.691232 0.722633 -0.0273487 0.779822 0.625403 0.0167737 0.852426 0.522579 -0.0102626 0.942725 0.333413 2.73092e-06 0.0883674 0.996088 -0.0300307 -0.0607141 0.997703 0.00810605 -0.166419 0.986022 -2.09808e-07 -0.311874 0.950124 1.96204e-06 -0.356623 0.934249 -0.0103612 -0.522873 0.852348 0.00710172 -0.557217 0.830337 -0.0082311 -0.837703 0.546064 0 -0.846894 0.531762 0.697351 -0.600422 0.391401 0.697325 -0.600448 0.391408 0.697334 -0.360448 0.619519 0.642329 -0.400767 0.653299 0.707002 -0.220561 0.671939 0.697345 -0.0435351 0.715412 0.697343 -0.0435357 0.715414 0.697341 0.282662 0.658648 0.69735 0.69735 0.165545 0.697326 0.697371 0.165558 0.699205 0.55772 0.447281 0.650511 0.581267 0.48884 0.707004 0.434625 0.557895 0.697343 0.282662 0.658647 0 -0.991323 0.131447 0.00725968 -0.98606 0.166233 4.28663e-05 -0.955906 0.293673 -0.000319819 -0.877086 0.480333 0 -0.877672 0.479262 -0.702122 -0.702149 0.11837 -0.702131 -0.702141 0.118365 -0.702133 -0.624525 0.342019 -0.70213 -0.624528 0.342022 -0.994042 0.0991949 -0.0451687 -0.97184 -0.214456 0.0976531 -0.658926 -0.651432 0.376103 -0.108097 -0.809168 0.577549 -0.558293 -0.675278 0.481984 -0.341049 -0.765138 0.546123 -0.237331 -0.785808 0.571122 -0.237628 -0.829284 0.505787 -0.153992 -0.855696 0.494035 -0.237609 -0.85267 0.465292 -0.237414 -0.884068 0.402565 -0.887885 -0.374465 0.267277 -0.739468 -0.547936 0.391093 -0.10816 -0.912177 0.395266 -0.341053 -0.855523 0.389568 -0.658926 -0.684575 0.311726 -0.558595 -0.761958 0.327707 -0.739482 -0.61265 0.278974 -0.971845 -0.191781 0.136884 -0.931695 -0.29083 0.217629 -0.931859 -0.314211 0.18141 -0.658697 -0.607528 0.443878 -0.658919 -0.651436 0.376107 -0.931861 -0.314208 0.181408 -0.931861 -0.330195 0.150356 -0.888087 -0.424162 0.177165 -0.994042 0.0887153 -0.0633211 -0.994042 0.088715 -0.0633208 -0.994053 0.0929727 -0.0567057 -0.994978 0.0866843 -0.0500474 -0.994053 0.0955945 -0.0521648 -0.994042 0.099195 -0.0451688 0 0.915011 -0.403429 0.126159 0.876454 -0.464663 0 0.899849 -0.436202 0 0.847408 -0.530942 0.0635016 0.826016 -0.560058 0 0.806885 -0.590709 -0.891407 -0.245117 -0.381196 -0.893729 0.259451 -0.365969 -0.90088 0.20635 -0.381882 -0.982603 0.045583 -0.180037 -0.968983 0.060337 -0.23965 -0.95918 0.065088 -0.275203 -0.955076 0.0799249 -0.28538 -0.937213 0.104397 -0.332765 -0.963018 -0.26667 0.0385255 -0.97139 -0.234024 0.0404327 -0.876427 -0.456207 0.154114 -0.884048 -0.441035 0.154748 -0.858966 -0.493722 -0.135702 -0.839078 -0.523296 -0.148694 -0.946584 -0.272991 -0.171623 -0.938296 -0.294124 -0.181911 -0.978164 0.0599459 -0.199002 -0.993506 0.0698561 -0.0898141 -0.993503 0.0647572 -0.0935874 -0.712673 0.349493 -0.608237 -0.88495 0.292274 -0.362544 -0.8858 0.295628 -0.357719 -0.792143 -0.460384 -0.400696 -0.849342 -0.296564 -0.436656 -0.805193 -0.233446 -0.54513 -0.812787 -0.174888 -0.55569 -0.759742 -0.059272 -0.647518 -0.771361 -0.0025001 -0.636393 -0.72281 0.13644 -0.677443 -0.116197 -0.435008 -0.892898 -0.185753 -0.396198 -0.899179 -0.0296786 -0.219127 -0.975245 -0.275278 -0.0285173 -0.960942 -0.127916 0.618671 -0.775167 -0.161199 0.425 -0.890724 -0.286331 0.0297297 -0.957669 -0.0901178 -0.0529802 -0.994521 -0.0666523 0.248135 -0.96643 -0.933088 0.12431 -0.337483 -0.918221 0.157192 -0.363539 -0.916086 0.160331 -0.367532 -0.902767 0.22706 -0.365316 -0.738155 0.177198 -0.650943 -0.697726 0.331466 -0.635066 -0.4611 0.362648 -0.80986 -0.106671 -0.873735 0.474562 -0.207975 -0.880675 0.425627 -0.0433279 -0.932636 -0.358207 -0.121173 -0.989707 -0.0761322 -0.245827 -0.969149 0.0178747 -0.0874125 -0.988247 0.125404 -0.11214 -0.951356 0.286961 -0.0815491 -0.582449 -0.808766 -0.113662 -0.650397 -0.751043 -0.227277 -0.690013 -0.687188 -0.0280906 -0.802347 -0.596196 -0.212762 -0.923402 -0.319471 -0.353638 0.0132656 -0.935288 -0.456003 -0.28357 -0.843593 -0.36413 -0.284404 -0.886862 -0.489613 -0.55535 -0.67221 -0.398063 -0.573489 -0.716001 -0.521628 -0.754585 -0.398129 -0.443214 -0.785618 -0.431701 -0.546158 -0.836614 -0.0422896 -0.493424 -0.86782 -0.0584874 -0.553286 -0.761656 0.337275 -0.546205 -0.766933 0.336861 -0.17731 -0.013888 -0.984057 -0.30152 -0.368509 -0.879367 -0.187415 -0.363982 -0.912355 -0.324419 -0.659458 -0.678135 -0.209399 -0.668221 -0.713886 -0.342325 -0.862541 -0.372607 -0.242322 -0.88259 -0.402883 -0.351084 -0.936316 0.00719298 -0.282721 -0.959146 -0.0103892 -0.344987 -0.847097 0.404242 -0.333627 -0.852483 0.402451 -0.149386 0.757937 -0.634993 -0.192868 0.646209 -0.738387 -0.341422 0.622917 -0.703851 -0.424992 0.588897 -0.687446 -0.484353 0.592724 -0.64349 -0.687667 0.501448 -0.525037 -0.647368 0.489691 -0.584053 -0.870211 0.401714 -0.285233 -0.850009 0.380039 -0.364768 -0.238111 0.324172 -0.915541 -0.17969 0.338564 -0.923627 -0.423354 0.334656 -0.841888 -0.487238 0.093517 -0.868248 -0.503328 0.0902771 -0.859367 -0.600331 -0.186742 -0.777644 -0.532648 -0.18978 -0.824785 -0.641645 -0.425336 -0.638264 -0.575735 -0.446874 -0.684714 -0.684282 -0.606358 -0.405079 -0.629472 -0.641012 -0.439169 -0.721168 -0.686716 -0.0913165 -0.685632 -0.720172 -0.106119 -0.739823 -0.621849 0.256838 -0.7257 -0.638632 0.255946 -0.146448 0.97386 -0.173637 -0.824705 0.35109 0.443393 -0.65139 0.737925 -0.176517 -0.942264 0.315397 0.112536 -0.971801 0.228718 0.0573694 -0.978816 0.196568 0.0572753 -0.989309 0.145828 -0.000936212 -0.993672 0.111382 -0.0144718 -0.85111 0.486043 -0.198432 -0.873463 0.477269 -0.0963175 -0.889403 0.453553 -0.0570202 -0.901406 0.432814 -0.0117698 -0.895305 0.445208 -0.0148192 -0.918227 0.3942 0.0382889 -0.741725 0.566814 0.35856 -0.782199 0.51665 0.348193 -0.708903 0.677431 0.196327 -0.911962 0.408356 0.0396365 -0.938587 0.338416 0.0672929 -0.78696 0.396519 0.472723 -0.849347 0.229856 0.475159 -0.792189 0.116731 0.599007 -0.856723 -0.114382 0.502934 -0.843569 -0.144852 0.517116 -0.884011 -0.349498 0.310444 -0.877482 -0.364773 0.311394 -0.921887 0.377474 0.0873951 -0.959989 0.274735 0.0542418 -0.891439 0.207511 0.402834 -0.944652 0.023328 0.327243 -0.941309 0.00197789 0.337541 -0.970893 -0.142533 0.192488 -0.965064 -0.173297 0.19652 -0.115196 -0.738662 0.66416 -0.0768128 -0.549162 0.832178 -0.14667 -0.518105 0.842648 -0.0529668 -0.189862 0.980381 -0.14866 -0.141268 0.978746 -0.0857148 0.0489692 0.995116 -0.146649 0.241758 0.959191 -0.333938 -0.777098 0.533483 -0.105755 -0.82423 0.556291 -0.296956 -0.823581 0.48325 -0.143067 0.242703 0.959493 -0.0595206 0.463159 0.884274 -0.22339 0.580179 0.783256 -0.116173 0.624496 0.77234 -0.0132749 0.832974 0.553153 -0.298416 0.770582 0.563163 -0.108502 0.884213 0.454307 -0.0837217 0.906047 0.414814 -0.0300737 0.974141 0.223932 -0.1785 0.969437 0.168313 -0.112024 0.975332 -0.190206 -0.341486 0.920976 -0.187591 -0.69277 0.706198 -0.146134 -0.714404 0.699275 0.0253273 -0.4129 0.905152 0.101065 -0.487256 0.798634 0.353221 -0.353592 0.81659 0.456238 -0.447578 0.615529 0.648689 -0.377663 0.599722 0.705481 -0.48002 0.338369 0.809375 -0.412114 0.301114 0.859937 -0.513923 -0.000835632 0.857836 -0.454265 -0.0483901 0.889552 -0.542564 -0.361934 0.758042 -0.499062 -0.401263 0.768066 -0.553206 -0.671136 0.493498 -0.546577 -0.676883 0.493035 -0.344655 -0.770903 0.53565 -0.287811 -0.490547 0.822513 -0.346262 -0.453388 0.821305 -0.253011 -0.124574 0.95941 -0.332869 -0.0745938 0.940018 -0.223308 0.249371 0.94231 -0.313059 0.29421 0.903014 -0.200948 0.580368 0.789173 -0.291642 0.606525 0.739643 -0.187439 0.829696 0.525805 -0.269292 0.834043 0.481512 -0.179718 0.969181 0.168494 -0.463496 0.877449 0.123508 -0.425019 0.889772 -0.16633 -0.484347 0.853634 -0.191616 -0.870899 0.464619 -0.160202 -0.892968 0.443618 -0.0762253 -0.690179 0.723579 0.00926062 -0.744785 0.635387 0.20391 -0.503287 0.78936 0.351586 -0.593143 0.603378 0.533027 -0.545233 0.595647 0.589852 -0.633579 0.369906 0.67952 -0.588803 0.340891 0.732874 -0.677987 0.0757258 0.731163 -0.639889 0.0342044 0.767706 -0.718482 -0.246465 0.650414 -0.691087 -0.283421 0.664885 -0.739769 -0.528046 0.417024 -0.726943 -0.54517 0.417545 -0.93962 0.313134 -0.138061 -0.939565 0.278667 -0.1989 -0.938391 0.271227 -0.214146 -0.939692 0.267505 -0.21312 -0.939427 0.267497 -0.214295 -0.939408 0.267503 -0.214371 -0.939888 0.266643 -0.213333 -0.939984 0.266255 -0.213395 -0.939935 0.266432 -0.213391 -0.939768 0.266845 -0.213613 -0.939575 0.267261 -0.213941 -0.939631 0.318767 -0.124425 -0.939834 0.318249 -0.124219 -0.940965 0.31449 -0.125223 -0.939691 0.318306 -0.125149 -0.93996 0.317967 -0.123988 -0.939977 0.317941 -0.12392 -0.939693 0.318123 -0.125596 -0.939472 0.319187 -0.124552 -0.939449 0.319262 -0.124527 -0.939566 0.311585 -0.141881 -0.943369 0.302633 -0.135895 -0.936006 0.308974 -0.168604 -0.939622 0.302351 -0.160295 -0.93966 0.29207 -0.178139 -0.937285 0.295375 -0.185067 -0.94337 0.269004 -0.194139 -0.939622 0.276129 -0.202149 -0.939693 0.267831 -0.212706 -0.149346 0.904749 -0.398905 -0.48878 0.798262 -0.351954 -0.346067 0.757028 -0.554208 -0.65506 0.609664 -0.446326 -0.85096 0.4238 -0.310258 -0.850964 0.423796 -0.310254 -0.850964 0.44508 -0.278863 -0.850959 0.445085 -0.278868 -0.850959 0.464049 -0.246022 -0.850963 0.464044 -0.246018 -0.850963 0.480587 -0.211892 -0.850965 0.480584 -0.21189 -0.655061 0.69136 -0.304822 -0.573443 0.746562 -0.337355 -0.573331 0.723883 -0.383777 -0.573337 0.72388 -0.383774 -0.573336 0.694299 -0.435011 -0.57333 0.694302 -0.435014 -0.573441 0.66544 -0.477866 -0.48879 0.703928 -0.515335 -0.346125 0.858453 -0.378492 -0.202132 0.89377 -0.400396 -0.202094 0.865283 -0.458741 -0.202092 0.865283 -0.458741 -0.202093 0.829923 -0.519987 -0.202094 0.829923 -0.519987 -0.202132 0.793638 -0.573831 -0.149354 0.797835 -0.584083 0.707106 -0.540779 0.455587 0.67118 -0.594399 0.442953 0.706475 -0.566435 0.424317 0.706476 -0.612918 0.353868 0.706469 -0.612924 0.353872 0.706521 -0.649948 0.279993 0.67284 -0.680153 0.290996 0.707108 -0.664928 0.24056 0.706467 0.566441 -0.424322 0.706475 0.566434 -0.424317 0.706476 0.612918 -0.353869 0.70647 0.612924 -0.353872 0.706469 0.650692 -0.27839 0.706454 0.650706 -0.278396 0.701789 0.701837 -0.122139 0.701812 0.701812 -0.122145 0.694737 0.409924 -0.591018 0.487529 -0.372514 -0.789651 0.694746 0.409917 -0.591013 0.702919 0.135215 -0.698299 0.494627 0.0718882 -0.866127 0.705018 -0.0499777 -0.707426 0.7037 -0.221725 -0.675014 0.704397 -0.388495 -0.59405 0.704397 -0.521874 -0.481117 0.487521 -0.717436 -0.497602 0.694749 -0.650502 0.306873 0.694746 -0.650504 0.306873 0.70292 -0.711035 0.0182441 0.494613 -0.866135 -0.0718911 0.70501 -0.689515 -0.165925 0.703692 -0.62923 -0.32998 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0.985193 -0.17145 0 0.985193 -0.17145 0 -0.84955 0.527509 -0.0376688 -0.903772 0.426353 -0.0154282 -0.937961 0.346396 0.0283298 -0.99927 0.0256398 1.17771e-05 -0.547326 -0.83692 -0.0268622 -0.474671 -0.879753 7.00305e-05 -0.577885 -0.816118 -0.000102164 -0.735234 -0.677814 -1.11076e-05 -0.735434 -0.677597 -4.72388e-06 -0.88561 -0.46443 -0.0342247 -0.833269 -0.551807 0.0537467 -0.970841 -0.233623 0.00712798 -0.946873 -0.321529 -0.00709827 -0.994972 0.0999015 0 0.569919 -0.821701 -0.0330462 0.60564 -0.795052 0.0252545 0.190043 -0.981451 -0.00778061 0.247843 -0.968769 5.54548e-06 0.052124 -0.998641 -7.49748e-06 -0.0704715 -0.997514 -0.0189356 -0.0066716 -0.999798 0.0359308 -0.311869 -0.949445 -0.0352766 -0.186504 -0.981821 2.48546e-05 -0.378959 -0.925413 0 0.800345 -0.59954 0 0.800345 -0.59954 0 0.866025 -0.500001 0 0.866025 -0.500001 0 0.919389 -0.393349 0 0.919389 -0.393349 0 -0.919389 0.39335 0 -0.919389 0.39335 0 -0.866025 0.5 0 -0.866025 0.5 0 -0.800345 0.599539 0 -0.800345 0.599539 0.879247 0.459529 -0.125534 0.105414 0.939882 0.324822 0.0900142 0.0966503 0.99124 0.0969642 -0.158105 0.98265 0.150378 -0.173868 0.97322 0.275078 0.271857 0.922185 0.143292 0.209347 0.967286 0.0794607 0.38307 0.920295 0.132843 0.552012 0.823187 0.188167 0.534393 0.824025 -0.0290522 0.812433 0.58233 0.204973 0.841866 0.499248 0.0559354 0.693771 0.71802 0.214342 0.962346 0.167175 0.147367 0.974011 -0.172007 0.169267 0.972881 -0.15764 0.887085 0.458775 -0.0510398 0.954996 0.285005 0.0821865 0.960102 0.2653 0.0884346 0.978434 0.198173 0.058264 0.978975 0.195527 0.0581063 0.991397 0.130836 -0.00378307 0.990797 0.135348 -0.00127413 0.965173 -0.180103 0.189749 0.793206 0.0945528 0.601568 0.859468 -0.147704 0.489386 0.839104 -0.150362 0.522777 0.884189 -0.365198 0.291274 0.87648 -0.37219 0.305381 0.859295 0.373912 0.349 0.938543 0.334266 0.0860407 0.933185 0.352131 0.0719034 0.821649 0.2986 0.485522 0.847485 0.221375 0.482454 0.891284 0.194745 0.409496 0.947044 -0.0001729 0.321104 0.938319 -0.000951548 0.34577 0.970912 -0.147723 0.188435 0.989047 -0.0715481 0.129102 0.807326 0.563517 0.175138 0.693231 0.549752 0.466051 0.770713 0.340447 0.538607 0.90213 0.430847 0.0230775 0.887846 0.456663 -0.0564752 0.749569 0.661864 0.00904097 0.71013 0.704059 -0.00404524 0.0994224 -0.347858 0.932261 0.101533 -0.549734 0.829147 0.110145 -0.551462 0.826897 0.0964061 -0.841846 0.531039 0.105746 -0.84278 0.527769 0.354224 0.799969 0.484329 0.457115 0.563083 0.688465 0.363183 0.604347 0.709129 0.490836 0.273166 0.827321 0.397288 0.306512 0.864993 0.522596 -0.0645726 0.850131 0.442833 -0.0477894 0.895329 0.546603 -0.408778 0.730839 0.493397 -0.409087 0.767598 0.553367 -0.689514 0.467285 0.546221 -0.691792 0.472298 0.190645 0.952662 0.236834 0.276005 0.798644 0.53478 0.176393 0.829059 0.53061 0.302654 0.548173 0.779684 0.186326 0.583981 0.790094 0.32567 0.222737 0.918873 0.208484 0.254808 0.94425 0.343259 -0.143623 0.928195 0.241857 -0.123318 0.962444 0.35151 -0.503629 0.789176 0.28265 -0.498079 0.819772 0.345031 -0.791877 0.50387 0.333678 -0.792954 0.509788 0.879553 0.458694 -0.126436 0.763463 0.628788 -0.147478 0.693952 0.710578 -0.116229 0.651407 0.743627 -0.150627 0.48446 0.85957 -0.162598 0.918306 0.391628 0.0578056 0.90102 0.430773 0.0509574 0.758741 0.596291 0.262202 0.805319 0.547041 0.228491 0.700508 0.628347 0.338332 0.6338 0.769789 0.0756494 0.46112 0.879322 0.119006 0.425669 0.89511 -0.132609 0.341461 0.926949 -0.155465 0.149323 0.98849 0.0243138 0.172455 0.964284 0.201036 0.424084 0.890773 0.163327 0.486862 0.787808 0.377258 0.502687 0.778286 0.376266 0.601401 0.558659 0.571154 0.531872 0.601583 0.595996 0.642845 0.313506 0.698902 0.57509 0.346749 0.74097 0.685233 0.02004 0.728048 0.629212 0.0348517 0.776452 0.721679 -0.287696 0.629611 0.68562 -0.290628 0.667428 0.739934 -0.547493 0.390831 0.725691 -0.555107 0.406483 0.14616 0.602444 -0.784664 0.826272 -0.228735 -0.514738 0.651429 0.502276 -0.568646 0.880894 0.294346 -0.370656 0.992268 0.0442003 -0.115975 0.992327 0.0815855 -0.0929049 0.976265 0.0381608 -0.213192 0.978908 0.0485423 -0.198453 0.963204 0.0549821 -0.263087 0.942932 0.0528935 -0.328758 0.902137 0.211904 -0.375826 0.895801 0.22227 -0.384884 0.919327 0.149581 -0.363956 0.851019 0.410401 -0.327625 0.740543 -0.0465456 -0.670395 0.783615 -0.0676987 -0.617546 0.707955 0.148614 -0.690444 0.912306 0.157562 -0.377984 0.939734 0.0982577 -0.327485 0.785898 -0.228434 -0.574615 0.847485 -0.307111 -0.432956 0.79326 -0.473673 -0.382587 0.856963 -0.497197 -0.135677 0.844207 -0.523844 -0.113589 0.884162 -0.438014 0.162485 0.877676 -0.445625 0.176358 0.923008 0.103748 -0.37053 0.960832 0.0760316 -0.266499 0.891326 -0.257215 -0.373334 0.944822 -0.277166 -0.174614 0.941841 -0.296159 -0.158824 0.97092 -0.237028 0.0336471 0.965173 -0.254387 0.0610604 0.115177 -0.933362 0.339956 0.0771168 -0.992497 0.0948848 0.146471 -0.987338 0.0609166 0.0440332 -0.944966 -0.32419 0.0571109 -0.942429 -0.329494 0.0998456 -0.822499 -0.559934 0.181845 -0.725297 -0.663985 0.334 -0.835708 0.435932 0.105774 -0.878484 0.465915 0.278922 -0.81797 0.503118 0.0122508 -0.0940851 -0.995489 0.315352 -0.147805 -0.937394 0.112589 0.00323411 -0.993636 0.136052 -0.719498 -0.681038 0.0636208 -0.571615 -0.818052 0.202843 -0.424226 -0.882546 0.24799 -0.436655 -0.864774 0.10876 -0.367282 -0.923729 0.0842334 0.0579345 -0.99476 0.032847 0.249944 -0.967703 0.190216 0.305327 -0.933056 0.0915646 0.627707 -0.773046 0.34146 0.59817 -0.724981 0.693992 0.455932 -0.557226 0.714749 0.304528 -0.6296 0.412199 0.338775 -0.845768 0.486914 0.0670922 -0.87087 0.354189 -0.0195536 -0.93497 0.447651 -0.282046 -0.848562 0.37852 -0.341523 -0.860282 0.480137 -0.554486 -0.679716 0.413105 -0.618122 -0.668783 0.514065 -0.757174 -0.403019 0.455184 -0.80815 -0.373766 0.542691 -0.839113 -0.0371028 0.499638 -0.866218 -0.00529427 0.553285 -0.750965 0.360453 0.546667 -0.753111 0.366031 0.344673 -0.834926 0.429068 0.288255 -0.956358 0.0478281 0.346237 -0.938045 0.013862 0.253715 -0.905715 -0.339571 0.33284 -0.864552 -0.376521 0.224036 -0.71518 -0.662062 0.313041 -0.658173 -0.6847 0.201539 -0.42449 -0.882718 0.291659 -0.366879 -0.883366 0.187842 -0.0747707 -0.979349 0.269294 -0.0320531 -0.962524 0.179204 0.308321 -0.934251 0.463853 0.301226 -0.833128 0.425701 0.562435 -0.708834 0.484448 0.57064 -0.663083 0.875356 0.35003 -0.333511 0.889586 0.276391 -0.363655 0.689707 0.334228 -0.642337 0.745683 0.115742 -0.656171 0.502636 0.0632218 -0.862183 0.593259 -0.18534 -0.783386 0.546278 -0.241333 -0.802084 0.633763 -0.424753 -0.646475 0.590008 -0.487123 -0.643896 0.678251 -0.609113 -0.411044 0.640943 -0.661602 -0.389197 0.718697 -0.689679 -0.0884144 0.691737 -0.719589 -0.0607536 0.739915 -0.616197 0.269867 0.727068 -0.624337 0.285614 0.572894 0.70982 -0.409816 0.850727 0.420013 -0.315994 0.879522 0.437888 -0.186268 0.654678 0.694974 -0.297335 0.764977 0.59214 -0.253339 0.845145 0.490093 -0.2134 0.851117 0.46997 -0.23394 0.8507 0.455228 -0.262827 0.850697 0.455231 -0.262828 0.851115 0.437582 -0.290043 0.345772 0.86268 -0.369088 0.488431 0.802261 -0.343238 0.14921 0.909097 -0.388946 0.201921 0.899072 -0.388456 0.201881 0.848194 -0.489706 0.844349 0.42882 -0.321229 0.654697 0.604974 -0.453186 0.573015 0.658621 -0.487722 0.488417 0.69839 -0.523164 0.345769 0.75098 -0.56256 0.573008 0.751695 -0.326523 0.572887 0.709824 -0.409817 0.201875 0.848195 -0.489706 0.201914 0.785949 -0.584392 0.149217 0.791385 -0.592827 0.340883 -0.752409 0.563631 0.994035 0.0944506 -0.0545311 0.994036 0.0871411 -0.06556 0.99425 0.0857003 -0.0641982 0.991754 0.117931 -0.0501653 0.996676 0.0729344 -0.0363043 0.658679 -0.651619 0.376213 0.93179 -0.314364 0.181499 0.994046 0.0994073 -0.0446274 0.993744 -0.10268 0.0439306 0.971838 -0.216653 0.0926924 0.994056 0.0907454 -0.0601499 0.994035 0.0944503 -0.054531 0.93179 -0.314365 0.181499 0.931638 -0.336607 0.136916 0.558454 -0.655444 0.508451 0.739309 -0.538926 0.40371 0.93179 -0.290523 0.217631 0.888074 -0.360852 0.284801 0.971842 -0.188587 0.14127 0.237285 -0.841292 0.48572 0.237285 -0.777487 0.582417 0.10813 -0.78682 0.607636 0.887832 -0.423073 0.181007 0.739307 -0.619087 0.264869 0.658467 -0.694533 0.289906 0.558095 -0.762888 0.326392 0.340898 -0.864318 0.369788 0.658678 -0.6022 0.451109 0.658677 -0.65162 0.376213 0.237289 -0.841291 0.48572 0.237192 -0.895749 0.375998 0.108014 -0.91401 0.391049 0.939514 0.31518 -0.134071 0.939602 0.322725 -0.114008 0.939493 0.323044 -0.113996 0.939575 0.322751 -0.11415 0.939696 0.322086 -0.115028 0.939842 0.322106 -0.113779 0.939865 0.322064 -0.113709 0.939748 0.322347 -0.113872 0.939507 0.273715 -0.205928 0.939904 0.259368 -0.222056 0.939804 0.259772 -0.222005 0.93969 0.260668 -0.221439 0.939697 0.260516 -0.221588 0.939545 0.260228 -0.222566 0.939484 0.260238 -0.222812 0.939528 0.260211 -0.222658 0.939644 0.260006 -0.22241 0.939775 0.25973 -0.222177 0.939515 0.273699 -0.205916 0.939511 0.273707 -0.20592 0.939694 0.285078 -0.188962 0.939693 0.28508 -0.18896 0.939498 0.296662 -0.171278 0.939498 0.296661 -0.171278 0.939694 0.306183 -0.152407 0.939694 0.306181 -0.15241 0.939511 0.315186 -0.134074 0.939507 0.315197 -0.134078 0.93969 0.322182 -0.114815 -0.694726 0.714328 -0.0842174 -0.458483 0.531402 0.712324 -0.694741 0.714314 -0.0842117 -0.702916 0.679966 0.208697 -0.466774 0.812396 0.349477 -0.705026 0.601011 0.376463 -0.703707 0.491721 0.512842 -0.69475 -0.576503 0.430078 -0.694736 -0.576511 0.430089 -0.702912 -0.350144 0.619123 -0.782483 -0.34079 0.521136 -0.561457 -0.20706 0.801182 -0.701771 -0.222292 0.676834 -0.703697 -0.00431383 0.710487 -0.458497 0.104048 0.882584 -0.704392 0.179544 0.686728 -0.704387 0.341903 0.622046 -0.380722 -0.912146 -0.151793 -0.734314 -0.655284 -0.177159 -0.707044 -0.707071 -0.0117969 -0.705893 -0.648975 -0.283807 -0.703394 -0.570551 -0.42392 -0.500126 -0.638272 -0.58522 -0.70522 -0.448252 -0.549303 -0.704388 -0.313661 -0.636753 -0.492751 -0.285283 -0.822077 -0.696086 0.437574 -0.569205 -0.69609 0.437572 -0.569201 -0.703396 0.185307 -0.686218 -0.500113 0.138549 -0.854805 -0.70522 0.0116202 -0.708893 -0.704386 -0.148209 -0.694172 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706187 -0.637115 0.308842 -0.706163 -0.637137 0.308852 -0.706164 -0.586042 0.39735 -0.706178 -0.58603 0.397343 0 -0.813937 0.580953 -0.0420203 -0.826955 0.560695 0 -0.853738 0.520702 0 -0.899849 0.436203 -0.0629333 -0.908285 0.413592 0 -0.877809 0.47901 -0.706163 0.637137 -0.308852 -0.706161 0.637139 -0.308853 -0.706162 0.586043 -0.397351 -0.706174 0.586034 -0.397344 0.00948995 -0.593479 -0.804794 0.00154623 -0.632242 -0.77477 -0.0020772 -0.45041 -0.892819 2.06109e-05 -0.441891 -0.897069 -8.69274e-06 -0.222436 -0.974947 0.00278569 -0.208798 -0.977955 -0.00262462 0.00257855 -0.999993 2.27786e-05 0.0163898 -0.999866 -2.57231e-05 0.243859 -0.969811 0.00416474 0.2607 -0.965411 -0.00144332 0.422591 -0.906319 0.0172871 0.609378 -0.792691 0.0118256 0.620651 -0.783998 0 0.766188 -0.642617 1.21715e-05 -0.665256 -0.746615 1.92687e-06 -0.802688 -0.596399 -0.000788686 -0.804609 -0.593805 0.000436339 -0.916219 -0.400677 -0.0126632 -0.95168 -0.30683 0.0104826 -0.98638 -0.164146 0 -0.997786 -0.0665001 0 -0.865341 0.501183 0.0262991 -0.801254 0.597746 0.0108377 -0.747181 0.664533 -0.0197315 -0.492179 0.87027 0.00457579 0.481673 0.876339 -6.88018e-05 0.457487 0.889216 8.54102e-05 0.252946 0.96748 -0.0052134 0.228641 0.973497 0.00478519 -0.00607147 0.99997 0.0130114 0.0375649 0.99921 -0.0208403 -0.250168 0.967978 -0.00416516 -0.195136 0.980767 0.00493844 -0.555624 0.831419 0 0.993122 -0.117081 0.027294 0.984867 -0.171149 -0.0219172 0.955756 0.293343 0.00552425 0.974007 0.226449 -2.78217e-06 0.906098 0.423067 8.60528e-06 0.847471 0.530841 0.0147534 0.884032 0.467194 -0.0292755 0.69179 0.721505 0.0251982 0.785454 0.618407 -0.00320902 0.61825 0.785975 0 -0.850115 -0.526597 0.0110653 -0.862214 -0.506423 -0.00122191 -0.721978 -0.691915 0.00872231 -0.576997 -0.8167 -0.016278 -0.522832 -0.85228 0.00109784 -0.362978 -0.931797 -0.000329443 -0.311874 -0.950123 0.00359063 -0.176519 -0.984291 -0.0321404 -0.0607085 -0.997638 0.00116071 0.0718864 -0.997412 -0.000938212 0.259475 -0.965749 -0.0315937 0.394174 -0.918493 0.00434534 0.482049 -0.876134 -0.000331378 0.614563 -0.788868 0.00692233 0.780096 -0.625621 0.0105252 0.783977 -0.6207 -0.0096575 0.96982 -0.24363 -0.017112 0.972818 -0.230939 0 0.999553 -0.0298823 0 0.919389 0.393349 0 0.919389 0.393349 0 0.866025 0.500001 0 0.866025 0.500001 0 0.800345 0.59954 0 0.800345 0.59954 0 -0.800345 -0.599539 0 -0.800345 -0.599539 0 -0.866025 -0.5 0 -0.866025 -0.5 0 -0.919389 -0.39335 0 -0.919389 -0.39335 0.879241 0.338489 0.335204 0.887083 0.273578 0.371805 0.954994 0.0713328 0.287921 0.960101 0.0560633 0.273975 0.978436 0.0486275 0.200746 0.978976 0.0474435 0.198381 0.991396 0.0686937 0.11142 0.990797 0.0687771 0.116579 0.965172 -0.254382 -0.0611012 0.793205 -0.473697 0.382671 0.859465 -0.497677 0.116779 0.839106 -0.527917 0.131169 0.884192 -0.434844 -0.170631 0.876484 -0.450556 -0.169632 0.859293 -0.115293 0.498321 0.938544 0.092622 0.332501 0.933186 0.113796 0.340904 0.821647 -0.271176 0.501358 0.847484 -0.307131 0.432945 0.891283 -0.257263 0.373404 0.947045 -0.278168 0.160402 0.938321 -0.299916 0.17206 0.970912 -0.237052 -0.0337139 0.989048 -0.147574 0.00259107 0.807335 0.130098 0.575573 0.693241 -0.128731 0.709116 0.770718 -0.296224 0.564132 0.902132 0.195439 0.384657 0.887847 0.277247 0.367235 0.749547 0.323119 0.577731 0.710133 0.355527 0.60771 0.275998 -0.0638109 0.959038 0.145863 0.494084 0.857091 0.197816 0.620252 0.75905 0.147933 0.654683 0.741287 0.111209 -0.991732 -0.064038 0.0953695 -0.881073 -0.463265 0.105758 -0.878449 -0.465986 0.0780724 -0.84396 0.530694 0.143606 -0.925352 0.350859 0.17764 -0.924463 0.337361 0.0972952 -0.979492 0.176436 0.110856 -0.991778 -0.0639302 0.0290603 0.263441 0.964238 0.134966 -0.148006 0.979734 -0.130553 -0.10749 0.985597 0.15624 -0.391579 0.906783 0.216102 -0.42116 0.880866 0.0506093 -0.542588 0.838473 0.143396 -0.733001 0.664941 0.273432 -0.663762 0.696172 0.142381 -0.774845 0.615909 0.354226 -0.0194649 0.934957 0.457108 -0.314683 0.831882 0.363172 -0.311946 0.877949 0.490832 -0.5799 0.650231 0.397293 -0.59585 0.69794 0.522587 -0.768527 0.369147 0.442833 -0.799274 0.406276 0.546608 -0.837311 0.0114052 0.493382 -0.869312 0.0295242 0.553353 -0.749447 -0.363496 0.546235 -0.754906 -0.362965 0.176416 -0.0449984 0.983287 0.302675 -0.401135 0.864568 0.186326 -0.392245 0.900792 0.325664 -0.684401 0.652332 0.208475 -0.690343 0.692795 0.343265 -0.875649 0.339717 0.241858 -0.895158 0.374428 0.351506 -0.935263 -0.041564 0.282663 -0.958979 -0.0214645 0.345037 -0.832299 -0.433852 0.333669 -0.83797 -0.431823 0.879549 0.338854 0.334024 0.763495 0.442099 0.47077 0.693955 0.455938 0.557267 0.651402 0.50226 0.568691 0.484447 0.570601 0.663118 0.918303 0.145761 0.368066 0.901023 0.171257 0.398533 0.758736 0.0710668 0.64751 0.805307 0.0756362 0.588013 0.700506 0.0211699 0.713333 0.633799 0.319372 0.704485 0.461121 0.336589 0.821021 0.425669 0.562401 0.70888 0.34148 0.598108 0.725023 0.172207 0.310087 0.934982 0.179194 0.308212 0.934289 0.424098 0.303944 0.853088 0.486873 0.0671868 0.870885 0.502657 0.0632951 0.862166 0.601385 -0.215305 0.769402 0.531871 -0.215357 0.818984 0.64285 -0.448513 0.620951 0.575097 -0.468324 0.670773 0.685236 -0.620486 0.381378 0.629213 -0.655 0.418409 0.721677 -0.689109 0.0656584 0.685621 -0.723322 0.0820268 0.739939 -0.612208 -0.278732 0.725684 -0.629585 -0.277499 0.148967 0.955701 0.253858 0.826271 0.331412 -0.455458 0.651446 0.743587 0.150658 0.880893 0.468173 0.0695795 0.992268 0.122537 -0.0197062 0.992327 0.12125 0.0242011 0.976263 0.203717 -0.073559 0.978907 0.196138 -0.0571879 0.963213 0.255303 -0.0839143 0.942929 0.311165 -0.11858 0.902136 0.43143 -0.00439907 0.895803 0.444451 4.67704e-05 0.919329 0.389981 -0.0524412 0.851018 0.488934 0.191602 0.740547 0.557299 -0.37551 0.783617 0.500958 -0.367405 0.707955 0.67225 -0.216518 0.912306 0.406125 -0.0525436 0.939733 0.33274 -0.0786516 0.785902 0.383412 -0.485132 0.847487 0.221397 -0.48244 0.793261 0.0944913 -0.601506 0.856963 -0.1311 -0.498424 0.844208 -0.163549 -0.510455 0.884163 -0.359721 -0.298088 0.877675 -0.375546 -0.297744 0.923014 0.372748 -0.095413 0.960832 0.26881 -0.0674045 0.891328 0.19471 -0.409417 0.944822 0.0126402 -0.32734 0.94184 -0.0105358 -0.335895 0.97092 -0.147656 -0.188449 0.965173 -0.180073 -0.189776 0.0641058 0.0777131 -0.994913 0.216841 0.215219 -0.952187 0.144765 -0.162716 -0.975995 0.171056 -0.171124 -0.970287 0.0910107 -0.355191 -0.930353 0.146474 -0.54642 -0.824604 0.0953847 -0.570347 -0.815847 0.105805 -0.844185 -0.525506 0.113082 -0.841943 -0.527584 0.334022 -0.795371 -0.50578 0.149348 0.988488 -0.024203 0.172223 0.964783 -0.198831 0.0697312 0.968548 -0.238857 0.0815765 0.816447 -0.57163 -0.0806669 0.776729 -0.624648 0.191572 0.552306 -0.811331 0.0379752 0.484567 -0.87393 0.122139 0.269201 -0.955308 0.34142 0.926951 0.155544 0.169169 0.972886 0.15772 0.269492 0.958837 0.089474 0.694004 0.710527 0.116235 0.714761 0.697501 -0.0510718 0.412199 0.901843 -0.129501 0.486913 0.78774 -0.377334 0.354181 0.799929 -0.484427 0.447642 0.593859 -0.668541 0.378501 0.574267 -0.725916 0.480128 0.31141 -0.820062 0.413099 0.270126 -0.869702 0.51406 -0.0295645 -0.857244 0.455182 -0.0803831 -0.886763 0.542683 -0.387436 -0.745244 0.499642 -0.428524 -0.752812 0.553286 -0.687643 -0.47013 0.546666 -0.693548 -0.469199 0.344685 -0.789042 -0.508533 0.288264 -0.519593 -0.804317 0.346232 -0.48103 -0.80544 0.253711 -0.158781 -0.954159 0.332839 -0.106198 -0.936984 0.224033 0.215771 -0.950396 0.313048 0.263886 -0.91234 0.20155 0.552211 -0.808975 0.291669 0.581578 -0.759405 0.187857 0.810753 -0.554427 0.269298 0.81754 -0.509026 0.179212 0.963244 -0.200109 0.463844 0.872128 -0.155695 0.425693 0.89509 0.132663 0.484446 0.859569 0.162646 0.875343 0.463862 0.136409 0.889578 0.453144 0.0575405 0.6897 0.723401 -0.0317036 0.745681 0.626135 -0.227848 0.50262 0.778292 -0.376344 0.59325 0.58576 -0.552213 0.546285 0.573961 -0.610034 0.633764 0.347491 -0.691082 0.590005 0.314071 -0.74381 0.678251 0.0514147 -0.733029 0.640945 0.00625299 -0.767561 0.718704 -0.268264 -0.641482 0.691735 -0.307189 -0.653558 0.739911 -0.541815 -0.398709 0.72707 -0.559515 -0.397885 0.572887 0.709824 0.409818 0.850727 0.483667 0.205744 0.879516 0.380265 0.286095 0.654672 0.604992 0.4532 0.765007 0.51544 0.386116 0.845141 0.429861 0.317736 0.851114 0.437587 0.290037 0.850697 0.455232 0.262829 0.8507 0.455228 0.262826 0.851117 0.469965 0.23395 0.345791 0.750973 0.562555 0.48842 0.698388 0.523163 0.149202 0.791387 0.592829 0.201914 0.78595 0.584391 0.201875 0.848195 0.489706 0.844348 0.492605 0.210754 0.654713 0.694946 0.297323 0.573008 0.751694 0.326524 0.488415 0.802269 0.343242 0.34573 0.862694 0.369094 0.573015 0.658621 0.487722 0.572894 0.70982 0.409815 0.201881 0.848194 0.489705 0.201921 0.899072 0.388455 0.149233 0.909094 0.388945 0.340907 -0.864315 -0.369787 0.994035 0.0944503 0.0545309 0.994036 0.100348 0.0426866 0.99425 0.0984474 0.0421196 0.991754 0.10241 0.0770485 0.996675 0.0679152 0.0450179 0.658677 -0.651619 -0.376213 0.93179 -0.314365 -0.181499 0.994046 0.0883519 0.0637753 0.993745 -0.089379 -0.0669539 0.971837 -0.188604 -0.141284 0.994056 0.097464 0.0485136 0.994035 0.0944506 0.0545311 0.93179 -0.314364 -0.181498 0.931639 -0.286875 -0.223051 0.558454 -0.768054 -0.313405 0.739311 -0.619084 -0.264868 0.93179 -0.333736 -0.142785 0.888072 -0.427073 -0.170108 0.971843 -0.216636 -0.0926854 0.237289 -0.841291 -0.48572 0.237289 -0.89313 -0.382116 0.108094 -0.919644 -0.377586 0.887836 -0.368287 -0.275884 0.739299 -0.538935 -0.403716 0.658466 -0.598334 -0.45653 0.558109 -0.6641 -0.497479 0.340888 -0.752407 -0.56363 0.658679 -0.691771 -0.295966 0.658678 -0.651619 -0.376212 0.237285 -0.841292 -0.48572 0.237188 -0.773499 -0.587742 0.10803 -0.795661 -0.596031 0.939515 0.273698 0.205917 0.939601 0.260094 0.222486 0.939491 0.260246 0.222773 0.939579 0.260233 0.22242 0.939697 0.260651 0.221428 0.939843 0.259582 0.222065 0.939864 0.259505 0.222064 0.939746 0.259791 0.222229 0.939507 0.315197 0.13408 0.939905 0.321986 0.113592 0.939806 0.322143 0.113966 0.93969 0.3221 0.115043 0.939697 0.322157 0.114827 0.939541 0.322877 0.114072 0.939494 0.323047 0.113983 0.939526 0.32294 0.114021 0.939649 0.322603 0.113965 0.939776 0.322272 0.113846 0.939514 0.315179 0.134073 0.939512 0.315184 0.134076 0.939694 0.306182 0.152405 0.939694 0.306178 0.152416 0.939498 0.296661 0.171278 0.939498 0.296661 0.171278 0.939694 0.285076 0.188964 0.939694 0.285081 0.188954 0.939512 0.273704 0.205921 0.939507 0.273713 0.20593 0.93969 0.260523 0.22161 0 0.985193 0.17145 -0.0420369 0.966045 0.254932 0 0.996299 0.0859556 0.701813 0.701813 0.122135 0.70179 0.701834 0.122149 -1.29444e-05 -0.665617 0.746293 -0.00383563 -0.904342 0.426792 0.0244189 -0.973558 0.227131 0.0191984 -0.969385 0.244793 0.0040926 -0.994493 0.10472 0 -0.999251 0.038699 -1.48822e-05 -0.802688 0.596399 0.0167977 -0.759743 0.650006 0.00328821 -0.82925 0.558868 0.0172011 -0.530393 0.847577 -0.0204511 -0.63211 0.774609 0.0145992 -0.381455 0.924272 2.71196e-06 -0.441891 0.897069 -2.44724e-05 -0.208799 0.977959 -0.0146656 -0.143407 0.989555 0.00457724 0.0163896 0.999855 0.000652659 0.0719366 0.997409 -0.0031422 0.291476 0.956573 -0.0144036 0.260676 0.965319 0.0160276 0.609391 0.792708 0 0.641419 0.767191 -0.696086 0.437575 0.569204 -0.69609 0.437571 0.569201 -0.703396 0.185307 0.686218 -0.500113 0.138549 0.854805 -0.70522 0.0116202 0.708893 -0.704386 -0.148209 0.694172 -0.492751 -0.285283 0.822077 -0.704388 -0.313661 0.636753 -0.70522 -0.448252 0.549303 -0.500126 -0.638272 0.58522 -0.703394 -0.570551 0.42392 -0.697545 -0.691708 0.187006 -0.733219 -0.659296 0.166488 -0.707044 -0.707071 0.011797 -0.70213 -0.624528 -0.34202 -0.702133 -0.624525 -0.34202 -0.702132 -0.70214 -0.118369 -0.702123 -0.702149 -0.118366 -0.458493 0.10405 -0.882586 -0.694749 -0.576501 -0.430082 -0.694738 -0.576512 -0.430086 -0.7057 -0.38777 -0.592978 -0.754944 -0.32283 -0.570824 -0.624892 -0.243606 -0.741731 -0.705014 -0.177456 -0.686633 -0.703697 -0.00431383 -0.710487 -0.704389 0.179545 -0.686731 -0.704384 0.341904 -0.622048 -0.458477 0.531404 -0.712326 -0.694725 0.714329 0.0842134 -0.69474 0.714313 0.0842158 -0.702915 0.679967 -0.208697 -0.466772 0.812397 -0.349477 -0.705024 0.601013 -0.376464 -0.703705 0.491722 -0.512844 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.706178 -0.586031 -0.397342 -0.706164 -0.586042 -0.397351 -0.706163 -0.637137 -0.308853 -0.706187 -0.637116 -0.308842 0 -0.910089 -0.414413 -0.0420221 -0.899054 -0.435817 0 -0.877809 -0.47901 0 -0.827687 -0.561191 -0.0629307 -0.812324 -0.579801 0 -0.853738 -0.520702 -0.706174 0.586034 0.397345 -0.706162 0.586044 0.397351 -0.706161 0.637139 0.308853 -0.706163 0.637137 0.308852 0 -0.801531 -0.597953 0 0.972926 0.231119 0.0323153 0.992604 0.11702 0.0129599 0.999484 0.0293773 -0.0156235 0.975138 -0.221047 0.0036927 0.955979 -0.293412 -0.00325878 0.847467 -0.530838 -0.0251483 0.792287 -0.60963 3.29292e-05 0.252946 -0.96748 -4.19181e-05 0.503406 -0.86405 -0.0066215 0.481668 -0.876329 0.005068 0.692078 -0.721805 0.0225851 -0.833564 -0.551961 -0.0133929 -0.538879 -0.842277 -1.4717e-05 -0.492277 -0.870439 4.03469e-07 -0.321942 -0.94676 0.00403966 -0.25022 -0.968181 -0.00869067 -0.147301 -0.989054 0.00792414 -0.00607134 -0.99995 -0.00304989 0.0917828 -0.995774 0.00555119 0.278031 -0.960556 0 -0.877689 -0.479231 -0.00032932 -0.877086 -0.480333 7.8225e-05 -0.956116 -0.29299 0.00727114 -0.98606 -0.166233 0 -0.991333 -0.131372 -0.994042 0.0887153 0.063321 -0.971841 -0.191795 -0.136895 -0.658919 -0.651437 -0.376106 -0.108084 -0.904757 -0.411986 -0.558303 -0.755043 -0.343814 -0.341055 -0.855522 -0.389568 -0.237313 -0.887514 -0.39497 -0.237609 -0.85267 -0.465292 -0.153992 -0.855696 -0.494035 -0.237628 -0.829284 -0.505787 -0.237433 -0.790662 -0.56434 -0.887881 -0.418707 -0.190661 -0.739467 -0.612666 -0.278981 -0.108179 -0.798397 -0.592333 -0.341045 -0.765139 -0.546124 -0.658919 -0.612254 -0.437001 -0.558599 -0.66478 -0.496019 -0.739474 -0.54793 -0.39109 -0.971844 -0.214438 -0.0976452 -0.931696 -0.333885 -0.14305 -0.931861 -0.314208 -0.181409 -0.658705 -0.688167 -0.304194 -0.658927 -0.65143 -0.376104 -0.931859 -0.314211 -0.18141 -0.931859 -0.295312 -0.210781 -0.88809 -0.365507 -0.278749 -0.994042 0.0991948 0.0451687 -0.994042 0.099195 0.0451688 -0.994053 0.0955946 0.0521645 -0.994978 0.0866854 0.050048 -0.994053 0.0929733 0.0567048 -0.994042 0.088715 0.0633208 0 0.806885 0.590709 0.0635023 0.826016 0.560058 0 0.847408 0.530942 0 0.883514 0.468406 0.0635007 0.898033 0.435321 0 0.915011 0.403429 -0.0684609 0.0993161 -0.992698 -0.0983885 -0.31153 -0.945129 -0.73816 0.652326 -0.172019 -0.933087 0.354426 -0.0610858 -0.885799 0.457608 0.0771743 -0.902765 0.429908 0.0139709 -0.90088 0.433896 -0.0122245 -0.893733 0.446658 0.0416916 -0.982604 0.178704 -0.050544 -0.968983 0.237708 -0.0675742 -0.95918 0.270875 -0.0812376 -0.978164 0.202316 -0.0475869 -0.993506 0.112708 0.0155911 -0.993503 0.113427 0.00928868 -0.955075 0.287114 -0.0734742 -0.937213 0.340381 -0.0759735 -0.812788 0.3938 -0.429299 -0.759744 0.531128 -0.375089 -0.53265 0.619392 -0.576747 -0.600327 0.580091 -0.550548 -0.364129 0.625844 -0.689732 -0.456007 0.588787 -0.667374 -0.187431 0.608132 -0.771392 -0.14551 0.988713 0.0356737 -0.172304 0.970699 -0.167497 -0.884948 0.460113 0.0718494 -0.712669 0.701499 -0.00144209 -0.697725 0.715718 -0.0304633 -0.461106 0.882682 -0.0908513 -0.423349 0.896428 -0.131119 -0.179707 0.969164 -0.168601 -0.275294 0.817935 -0.50517 -0.918231 0.393405 -0.0456478 -0.916084 0.398463 -0.0449214 -0.771364 0.549881 -0.320357 -0.722816 0.654897 -0.220561 -0.503328 0.78937 -0.351506 -0.487236 0.798682 -0.353141 -0.353639 0.816614 -0.456158 -0.177312 0.845272 -0.504058 -0.301512 0.577306 -0.75882 -0.274914 0.300316 -0.913363 -0.876424 -0.361574 -0.318034 -0.884046 -0.354537 -0.304576 -0.725699 -0.540972 -0.425099 -0.739821 -0.533354 -0.41012 -0.546212 -0.675191 -0.495751 -0.553287 -0.672914 -0.490979 -0.333634 -0.774769 -0.537049 -0.344988 -0.773628 -0.531492 -0.105757 -0.824275 -0.556225 -0.121706 -0.825531 -0.551078 -0.145534 -0.131159 -0.980621 -0.171015 -0.137719 -0.975596 -0.342311 -0.108587 -0.933291 -0.242328 -0.0923936 -0.965785 -0.521633 -0.0325065 -0.85255 -0.443215 -0.0189488 -0.896215 -0.68428 0.0476259 -0.727662 -0.62947 0.0598212 -0.774718 -0.792141 0.116818 -0.599054 -0.839076 -0.13288 -0.527536 -0.858963 -0.129344 -0.495432 -0.685632 -0.268187 -0.676746 -0.721167 -0.264278 -0.640371 -0.493426 -0.38326 -0.780796 -0.546153 -0.381686 -0.745676 -0.282723 -0.470576 -0.835839 -0.35108 -0.474387 -0.807279 -0.0853882 -0.526646 -0.845785 -0.106827 -0.530097 -0.841181 -0.147947 0.96161 0.231125 -0.20559 0.959945 0.190363 -0.341458 0.920999 0.187528 -0.425001 0.88979 0.166275 -0.484359 0.853639 0.191566 -0.687664 0.705423 0.171746 -0.647346 0.750672 0.132039 -0.870213 0.447877 0.20527 -0.850013 0.50591 0.14674 -0.0290074 0.975052 -0.220075 -0.135869 0.792286 -0.594829 0.182413 0.805888 -0.563268 -0.290368 0.51199 -0.808426 -0.0131113 0.570374 -0.821281 -0.143529 0.241811 -0.959649 -0.324426 0.257551 -0.910173 -0.209399 0.284132 -0.935639 -0.489616 0.304475 -0.81705 -0.39806 0.333332 -0.854657 -0.641642 0.340087 -0.687486 -0.57574 0.369541 -0.729358 -0.805193 0.355372 -0.474736 -0.849342 0.229872 -0.47516 -0.891409 0.207566 -0.402873 -0.946585 0.012135 -0.322226 -0.938297 0.0104781 -0.345673 -0.97139 -0.152027 -0.182454 -0.963016 -0.1667 -0.211685 -0.146451 0.637307 0.756566 -0.112064 -0.951573 -0.286269 -0.824708 -0.208442 0.525746 -0.651392 0.521828 0.550803 -0.942263 0.060238 0.32941 -0.971801 0.0646746 0.22676 -0.978816 0.0486812 0.19887 -0.989309 0.0737237 0.125824 -0.993672 0.0682229 0.0892252 -0.851105 0.414874 0.321714 -0.873463 0.32205 0.365167 -0.889404 0.276159 0.364277 -0.901406 0.226604 0.368942 -0.895306 0.23544 0.378148 -0.918229 0.163937 0.360527 -0.741733 -0.027118 0.670147 -0.782194 -0.0432169 0.621535 -0.708895 0.168694 0.684843 -0.911961 0.169851 0.373466 -0.938587 0.11093 0.326725 -0.78696 -0.211128 0.579758 -0.849348 -0.296571 0.436639 -0.792191 -0.460389 0.400593 -0.856725 -0.492741 0.152409 -0.843571 -0.520259 0.133111 -0.884012 -0.443602 -0.147449 -0.877484 -0.45206 -0.160199 -0.92189 0.113049 0.370592 -0.959989 0.0903922 0.265047 -0.89144 -0.245109 0.381125 -0.944652 -0.271739 0.183824 -0.941308 -0.291333 0.170483 -0.970892 -0.23797 -0.0271985 -0.965064 -0.256838 -0.0518165 -0.177514 -0.702944 0.688737 -0.111452 -0.9872 0.114084 -0.078584 -0.968504 0.236271 -0.233482 -0.898701 0.371244 -0.102335 -0.894865 0.434448 -0.0894766 -0.819749 0.56569 -0.0726561 -0.996769 -0.0342575 -0.351222 -0.930859 -0.100717 -0.155347 -0.986552 0.0508272 -0.33393 -0.850559 -0.406252 -0.105774 -0.893873 -0.435663 -0.233608 -0.855742 -0.461664 0.0904608 -0.0747344 0.993092 -0.24995 -0.114002 0.961524 -0.28099 -0.70523 0.650919 -0.113653 -0.650764 0.750725 -0.0130972 -0.426417 0.904432 -0.402976 -0.441198 0.801845 -0.15141 -0.358874 0.921024 -0.0873964 0.0795947 0.992989 -0.0301099 0.293144 0.955594 -0.178503 0.338949 0.923715 -0.112024 0.652394 0.749555 -0.341451 0.622959 0.703799 -0.692764 0.47966 0.538521 -0.714399 0.327701 0.618261 -0.412919 0.365046 0.83441 -0.487268 0.0934222 0.868241 -0.353599 0.0131819 0.935304 -0.44758 -0.254018 0.857407 -0.37766 -0.311109 0.872115 -0.480016 -0.531755 0.697726 -0.412108 -0.594172 0.690743 -0.513921 -0.743328 0.428193 -0.454267 -0.794568 0.402869 -0.542567 -0.837449 0.0655839 -0.499061 -0.865797 0.0365333 -0.553201 -0.762951 -0.334477 -0.546581 -0.76542 -0.339679 -0.344662 -0.849336 -0.399795 -0.287811 -0.957591 -0.0135666 -0.346266 -0.937963 0.0180132 -0.25301 -0.89316 0.371821 -0.332867 -0.851377 0.405409 -0.223311 -0.691378 0.687116 -0.313065 -0.634925 0.7063 -0.200952 -0.393267 0.897195 -0.291657 -0.337287 0.895083 -0.187451 -0.0405015 0.981439 -0.269278 1.69861e-05 0.963063 -0.179698 0.338669 0.923586 -0.463507 0.331763 0.821641 -0.425032 0.588926 0.687397 -0.484361 0.592755 0.643456 -0.870907 0.371025 0.322275 -0.89297 0.287821 0.34607 -0.69017 0.353771 0.631277 -0.744777 0.141106 0.652224 -0.503285 0.0902033 0.8594 -0.593144 -0.159918 0.789054 -0.545221 -0.21301 0.810778 -0.633571 -0.403534 0.660112 -0.588797 -0.464244 0.661661 -0.677982 -0.595349 0.431161 -0.639885 -0.647754 0.413474 -0.718474 -0.686517 0.111757 -0.69109 -0.717514 0.0869986 -0.739778 -0.62517 -0.248778 -0.726937 -0.634194 -0.263364 -0.939622 0.276129 0.202149 -0.939566 0.311585 0.141881 -0.938392 0.321066 0.127819 -0.939692 0.318317 0.125109 -0.939426 0.319337 0.12451 -0.939407 0.319406 0.124477 -0.939886 0.318077 0.124262 -0.939987 0.317929 0.123875 -0.939934 0.318022 0.124044 -0.939775 0.318398 0.124277 -0.939573 0.318914 0.124483 -0.939632 0.267136 0.213845 -0.939834 0.266702 0.213501 -0.940952 0.265707 0.209781 -0.939692 0.267531 0.213086 -0.93996 0.266359 0.213373 -0.939977 0.266289 0.213384 -0.939692 0.267831 0.212707 -0.939471 0.267459 0.214149 -0.939449 0.267475 0.214225 -0.939565 0.278667 0.1989 -0.94337 0.269004 0.194139 -0.936007 0.300501 0.183277 -0.939623 0.289993 0.181695 -0.939661 0.300305 0.163872 -0.937285 0.307962 0.16327 -0.943369 0.302633 0.135895 -0.93962 0.313134 0.138061 -0.939692 0.318128 0.125597 -0.149349 0.797835 0.584084 -0.488794 0.703926 0.515333 -0.346102 0.858461 0.378495 -0.655042 0.691375 0.304829 -0.850965 0.480584 0.211891 -0.850963 0.480588 0.211892 -0.850963 0.464044 0.246019 -0.850959 0.464049 0.246021 -0.850959 0.445086 0.278867 -0.850964 0.445079 0.278864 -0.850964 0.423796 0.310254 -0.85096 0.423801 0.310257 -0.655064 0.609661 0.446324 -0.573441 0.66544 0.477866 -0.57333 0.694303 0.435013 -0.573336 0.694299 0.435012 -0.573337 0.72388 0.383775 -0.573332 0.723883 0.383776 -0.573443 0.746562 0.337353 -0.488795 0.798255 0.351951 -0.346093 0.75702 0.554203 -0.202135 0.793638 0.57383 -0.202097 0.829922 0.519986 -0.202093 0.829923 0.519986 -0.202092 0.865284 0.458741 -0.202093 0.865283 0.458741 -0.202131 0.893771 0.400396 -0.149349 0.904749 0.398904 0.707108 -0.664928 -0.24056 0.671208 -0.680785 -0.293277 0.706469 -0.650691 -0.278391 0.70647 -0.612924 -0.353872 0.706476 -0.612918 -0.353869 0.706527 -0.56745 -0.422871 0.672814 -0.592105 -0.443546 0.707106 -0.540779 -0.455587 0.706454 0.650706 0.278396 0.706469 0.650692 0.27839 0.706469 0.612924 0.353872 0.706476 0.612918 0.353869 0.706475 0.566434 0.424317 0.706467 0.566441 0.424322 0.698076 -0.635707 -0.329495 0.69807 -0.635711 -0.329499 0.698071 -0.715719 -0.0210376 0.618504 -0.78422 -0.0495122 0.706891 -0.698135 0.113629 0.69806 -0.65398 0.291585 0.698068 -0.653972 0.291585 0.698066 -0.462697 0.546457 0.698062 -0.462701 0.546459 0.698066 -0.179779 0.693098 0.698064 0.429797 0.572697 0.698065 0.429797 0.572695 0.7006 0.161748 0.69498 0.634905 0.149708 0.757947 0.706901 0.00301766 0.707306 0.698069 -0.179777 0.693095 0.697349 0.697349 -0.165553 0.697326 0.697373 -0.16555 0.697331 0.54855 -0.461326 0.64236 0.597883 -0.47949 0.707004 0.434625 -0.557895 0.697343 0.282661 -0.658647 0.697344 0.28266 -0.658646 0.697347 -0.0435349 -0.715411 0.697345 -0.0435344 -0.715412 0.707002 -0.220561 -0.671939 0.650486 -0.381957 -0.656488 0.7009 -0.61502 -0.361233 0.607893 -0.665169 -0.433608 0.706702 -0.510808 -0.489539 0.699211 -0.37383 -0.60939 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -0.887828 -0.460176 0 0.660362 0.750947 -0.0323346 0.599932 0.799398 -0.00477534 0.494993 0.868884 0.0109496 0.262567 0.964852 -0.00691561 0.226674 0.973946 0.00188909 0.00426636 0.999989 0.0233486 -0.158703 0.98705 -0.0207693 -0.25102 0.967759 -0.00129664 -0.410237 0.911978 0.0032357 -0.547166 0.837018 -0.0314911 -0.645877 0.762792 -0.00693778 -0.710474 0.703689 0.000743163 -0.985441 0.170016 -0.00314279 -0.939486 0.342573 -0.0274217 -0.912985 0.40707 -0.00213219 -0.850544 0.5259 0.000705618 -0.791351 0.611361 -0.00398413 -0.884106 -0.467269 0.00339432 -0.997495 -0.0706576 2.38586e-05 -0.998013 -0.0630101 2.72921e-06 -0.987012 0.160647 0 1 0 0 1 0 0 -1 0 0 -1 0 0.996917 0.0784674 0 0.987513 0.15641 -0.0188186 0.890848 0.453912 -0.018821 0.923881 0.38268 0 0.97237 0.233444 0 0.706982 0.706982 -0.0188199 0.760406 0.649448 0 0.852637 0.522505 0 0.319174 0.947696 0.000187838 0.353945 0.935265 -0.00166504 0.39744 0.917603 -0.00681032 0.430598 0.902447 -0.0132271 0.437827 0.898939 -0.0147052 0.4406 0.897573 -0.0152988 0.439545 0.898094 -0.0150692 0.435582 0.900037 -0.014191 0.431425 0.902051 -0.0132611 0.429163 0.903137 -0.0127521 0.427165 0.90409 -0.0122965 0.453916 0.890853 -0.0184825 0.513512 0.858082 0 0.649448 0.760406 0 0.22804 0.973651 -0.00104428 0.156397 0.987458 -0.0216111 0.0766138 0.997061 0 -0.0766138 0.997061 0 -0.156397 0.987458 -0.0216111 -0.39744 0.917603 -0.00681033 -0.43043 0.902527 -0.0131943 -0.439545 0.898094 -0.0150692 -0.441047 0.897352 -0.0153958 -0.437829 0.898938 -0.0147072 -0.432415 0.901658 -0.00553812 -0.433647 0.900978 -0.0137625 -0.429163 0.903137 -0.0127521 -0.427163 0.904091 -0.0122968 -0.353967 0.935256 -0.00166764 -0.319155 0.947703 0.000187576 -0.22804 0.973651 -0.00104428 -0.513235 0.857632 -0.0324981 -0.45399 0.891007 0 -0.649448 0.760406 0 -0.706982 0.706982 -0.0188199 -0.760406 0.649448 0 -0.852643 0.522494 0 -0.890851 0.453906 -0.0188194 -0.923881 0.38268 0 -0.97237 0.233444 0 -0.987513 0.15641 -0.0188186 -0.996917 0.0784674 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.996917 -0.0784671 0 -0.987513 -0.15641 -0.0188187 -0.890851 -0.453905 -0.0188196 -0.923881 -0.382679 0 -0.97237 -0.233445 0 -0.706982 -0.706982 -0.0188199 -0.760406 -0.649448 0 -0.852643 -0.522494 0 -0.319155 -0.947703 0.000187576 -0.353967 -0.935256 -0.00166764 -0.397451 -0.917598 -0.00681168 -0.430341 -0.90257 -0.0131761 -0.437829 -0.898938 -0.0147072 -0.441047 -0.897352 -0.0153958 -0.439729 -0.898003 -0.0151093 -0.434598 -0.900516 -0.0139722 -0.432166 -0.901694 -0.0134281 -0.429163 -0.903137 -0.0127521 -0.427519 -0.903921 -0.0123777 -0.453913 -0.890855 -0.018481 -0.513504 -0.858087 0 -0.649448 -0.760406 0 -0.22804 -0.973651 -0.00104428 -0.156397 -0.987458 -0.0216111 -0.0766138 -0.997061 0 0.0766138 -0.997061 0 0.156397 -0.987458 -0.0216111 0.397451 -0.917598 -0.00681168 0.430509 -0.90249 -0.0132089 0.439729 -0.898003 -0.0151093 0.4406 -0.897573 -0.0152988 0.437827 -0.898939 -0.0147052 0.431761 -0.901985 -0.0023846 0.433467 -0.901065 -0.013722 0.429163 -0.903137 -0.0127521 0.427519 -0.903922 -0.0123778 0.353945 -0.935265 -0.00166504 0.319174 -0.947696 0.000187838 0.22804 -0.973651 -0.00104428 0.513239 -0.85763 -0.0324982 0.453993 -0.891005 0 0.649448 -0.760406 0 0.706982 -0.706982 -0.0188199 0.760406 -0.649448 0 0.852637 -0.522505 0 0.890848 -0.453911 -0.0188212 0.923881 -0.382679 0 0.97237 -0.233445 0 0.987513 -0.15641 -0.0188187 0.996917 -0.0784671 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.980785 -0.195094 0 0.980785 -0.195094 0 0.831469 -0.555572 0 0.831469 -0.555572 0 0.555573 -0.831468 0 0.555573 -0.831468 0 0.19509 -0.980785 0 0.19509 -0.980785 0 0 -1 0 0 -1 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555573 -0.831468 0 -0.555573 -0.831468 0 -0.831469 -0.555572 0 -0.831469 -0.555572 0 -0.980785 -0.195094 0 -0.980785 -0.195094 0 -1 0 0 -1 0 0 -0.980785 0.195094 0 -0.980785 0.195094 0 -0.831469 0.555572 0 -0.831469 0.555572 0 -0.555573 0.831468 0 -0.555573 0.831468 0 -0.19509 0.980785 0 -0.19509 0.980785 0 0 1 0 0 1 0 0.19509 0.980785 0 0.19509 0.980785 0 0.555573 0.831468 0 0.555573 0.831468 0 0.831469 0.555572 0 0.831469 0.555572 0 0.980785 0.195094 0 0.980785 0.195094 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.980785 -0.195094 0 0.980785 -0.195094 0 0.831468 -0.555572 0 0.831468 -0.555572 0 0.555573 -0.831468 0 0.555573 -0.831468 0 0.19509 -0.980785 0 0.19509 -0.980785 0 0 -1 0 0 -1 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555568 -0.831471 0 -0.555568 -0.831471 0 -0.831473 -0.555565 0 -0.831473 -0.555565 0 -0.980785 -0.195094 0 -0.980785 -0.195094 0 -1 0 0 -1 0 0 -0.980785 0.195094 0 -0.980785 0.195094 0 -0.831473 0.555565 0 -0.831473 0.555565 0 -0.555568 0.831471 0 -0.555568 0.831471 0 -0.195089 0.980785 0 -0.195089 0.980785 0 0 1 0 0 1 0 0.195089 0.980785 0 0.195089 0.980785 0 0.555573 0.831468 0 0.555573 0.831468 0 0.831469 0.555572 0 0.831469 0.555572 0 0.980785 0.195094 0 0.980785 0.195094 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.980786 -0.195085 0 0.980786 -0.195085 0 0.831469 -0.555572 0 0.831469 -0.555572 0 0.555568 -0.831471 0 0.555568 -0.831471 0 0.195092 -0.980785 0 0.195092 -0.980785 0 0 -1 0 0 -1 0 -0.19509 -0.980785 0 -0.19509 -0.980785 0 -0.555573 -0.831468 0 -0.555573 -0.831468 0 -0.831469 -0.555572 0 -0.831469 -0.555572 0 -0.980785 -0.195094 0 -0.980785 -0.195094 0 -1 0 0 -1 0 0 -0.980785 0.195094 0 -0.980785 0.195094 0 -0.831468 0.555572 0 -0.831468 0.555572 0 -0.555573 0.831468 0 -0.555573 0.831468 0 -0.19509 0.980785 0 -0.19509 0.980785 0 0 1 0 0 1 0 0.195092 0.980785 0 0.195092 0.980785 0 0.555568 0.831471 0 0.555568 0.831471 0 0.831468 0.555572 0 0.831468 0.555572 0 0.980786 0.195085 0 0.980786 0.195085 0 1 0 0 1 0 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.707107 0 0.707107 0.707107 0 0.707107 0.441785 0.587619 0.677887 0.369011 0.61893 0.693366 0.420299 0.492108 0.762351 0.426615 0.584772 0.689958 0.530266 0.452888 0.716736 0.706223 0.0499882 0.706223 0.707785 0.0557013 0.704229 0.690257 0.148564 0.708148 0.691701 0.166063 0.702832 0.661104 0.243797 0.70958 0.658124 0.272602 0.701827 0.619324 0.334051 0.710527 0.607876 0.372513 0.701228 0.565727 0.417661 0.710994 0.516725 0.508415 0.688847 0.369013 -0.618929 0.693365 0.420299 -0.492111 0.762349 0.426869 -0.591945 0.683655 0.542271 -0.463142 0.701029 0.501257 -0.493192 0.710987 0.43365 -0.576799 0.692279 0.706015 -0.055562 0.706015 0.708628 -0.0501585 0.703797 0.686522 -0.164819 0.708182 0.697337 -0.150087 0.700853 0.649928 -0.269208 0.710719 0.672448 -0.247982 0.697365 0.597313 -0.366038 0.713606 0.634243 -0.342097 0.69333 0.565725 -0.417663 0.710994 -0.369009 0.618926 0.693371 -0.420298 0.492097 0.762358 -0.426869 0.591945 0.683655 -0.542265 0.463148 0.70103 -0.501256 0.493194 0.710987 -0.43365 0.576799 0.692279 -0.706015 0.055562 0.706015 -0.708628 0.0501585 0.703797 -0.686522 0.164819 0.708182 -0.697337 0.150088 0.700853 -0.649928 0.269208 0.710719 -0.672449 0.247981 0.697365 -0.597317 0.366032 0.713606 -0.63425 0.342088 0.693327 -0.565718 0.41767 0.710996 -0.441785 -0.587619 0.677887 -0.369011 -0.618925 0.69337 -0.420298 -0.4921 0.762356 -0.426615 -0.584772 0.689958 -0.530261 -0.452895 0.716735 -0.706223 -0.0499882 0.706223 -0.707785 -0.0557013 0.704229 -0.690257 -0.148563 0.708148 -0.691701 -0.166062 0.702832 -0.661104 -0.243798 0.70958 -0.658123 -0.272603 0.701827 -0.619332 -0.334039 0.710525 -0.607883 -0.372505 0.701226 -0.565717 -0.417671 0.710996 -0.516723 -0.50841 0.688852 -0.707107 0 0.707107 -0.707107 0 0.707107 -0.555145 0.0392974 0.830825 -0.195069 0.0138069 0.980692 -0.195074 0.0138088 0.980691 -0.191184 0.041148 0.980691 -0.191175 0.041143 0.980693 -0.183474 0.0676608 0.980693 -0.183485 0.0676694 0.980691 -0.172124 0.0928388 0.980691 -0.172117 0.0928314 0.980693 -0.157326 0.116149 0.980693 -0.15733 0.116155 0.980691 -0.139398 0.137159 0.980691 -0.139398 0.137159 0.980691 -0.117583 0.156396 0.980671 -0.117584 0.156398 0.98067 -0.234822 0.312338 0.920491 -0.555138 0.0392941 0.83083 -0.54407 0.11709 0.83083 -0.544093 0.117105 0.830812 -0.522173 0.192578 0.830812 -0.522145 0.192553 0.830836 -0.489816 0.264182 0.830836 -0.489822 0.26419 0.83083 -0.447726 0.330551 0.830829 -0.447731 0.330559 0.830824 -0.396704 0.390331 0.830824 -0.396698 0.390318 0.830832 -0.336285 0.443554 0.830766 -0.338448 0.45017 0.826317 -0.555574 0 0.831467 -0.555574 0 0.831467 -0.195088 0 0.980786 -0.195088 0 0.980786 -0.234892 -0.31243 0.920442 -0.117585 -0.156398 0.98067 -0.338444 -0.450165 0.826322 -0.117581 -0.156395 0.980671 -0.139396 -0.137157 0.980692 -0.139399 -0.137159 0.980691 -0.157331 -0.116153 0.980691 -0.157323 -0.116151 0.980693 -0.172114 -0.0928335 0.980693 -0.172126 -0.0928354 0.980691 -0.183487 -0.0676653 0.980691 -0.183472 -0.067665 0.980693 -0.191174 -0.0411459 0.980693 -0.191184 -0.0411446 0.980691 -0.195074 -0.0138073 0.980691 -0.195069 -0.0138085 0.980692 -0.336284 -0.443555 0.830766 -0.396696 -0.39032 0.830832 -0.396708 -0.390326 0.830824 -0.447732 -0.330558 0.830823 -0.447723 -0.330556 0.830829 -0.489825 -0.264185 0.83083 -0.489815 -0.264184 0.830836 -0.522139 -0.192566 0.830837 -0.522177 -0.192566 0.830813 -0.544096 -0.117095 0.830812 -0.544068 -0.117099 0.83083 -0.555137 -0.0392969 0.83083 -0.555145 -0.0392946 0.830825 0.234823 0.312338 0.920491 0.117584 0.156398 0.98067 0.338448 0.45017 0.826317 0.117582 0.156396 0.980671 0.1394 0.137157 0.980691 0.139392 0.137153 0.980693 0.157321 0.11615 0.980693 0.157325 0.116151 0.980693 0.172116 0.0928342 0.980693 0.172126 0.0928358 0.980691 0.183487 0.0676653 0.980691 0.183473 0.067665 0.980693 0.191174 0.041146 0.980693 0.191184 0.0411449 0.980691 0.195074 0.0138073 0.980691 0.195069 0.0138085 0.980692 0.336285 0.443554 0.830766 0.396694 0.390322 0.830833 0.396707 0.390327 0.830824 0.447733 0.330557 0.830823 0.447748 0.330561 0.830814 0.489847 0.264199 0.830812 0.48981 0.264194 0.830835 0.522139 0.192565 0.830837 0.522177 0.192565 0.830813 0.544096 0.117095 0.830812 0.544068 0.1171 0.83083 0.555137 0.0392969 0.83083 0.555145 0.0392946 0.830825 0.555574 0 0.831467 0.555574 0 0.831467 0.195088 0 0.980786 0.195088 0 0.980786 0.555145 -0.0392974 0.830825 0.195069 -0.0138069 0.980692 0.195074 -0.0138088 0.980691 0.191184 -0.041148 0.980691 0.191175 -0.0411426 0.980693 0.183473 -0.0676604 0.980693 0.183485 -0.0676697 0.980691 0.172124 -0.0928388 0.980691 0.172116 -0.0928303 0.980693 0.157323 -0.116151 0.980693 0.157321 -0.11615 0.980693 0.139394 -0.137151 0.980693 0.139397 -0.137157 0.980692 0.117582 -0.156393 0.980671 0.117584 -0.156398 0.98067 0.234892 -0.31243 0.920442 0.555138 -0.0392941 0.83083 0.54407 -0.117089 0.83083 0.544093 -0.117104 0.830812 0.522173 -0.192579 0.830812 0.522144 -0.192554 0.830836 0.489816 -0.264181 0.830836 0.489841 -0.264209 0.830813 0.447744 -0.330567 0.830814 0.447735 -0.330554 0.830823 0.396705 -0.390329 0.830824 0.396699 -0.390317 0.830832 0.336284 -0.443555 0.830766 0.338444 -0.450165 0.826322 -0.424672 -0.712283 0.558844 -0.503778 -0.835223 0.220479 -0.528894 -0.843195 0.0964028 -0.54218 -0.839815 0.0274149 -0.539377 -0.840973 0.0428594 -0.537285 -0.841669 0.054018 -0.534009 -0.842486 0.0710789 -0.472264 -0.79211 0.386689 -0.499755 -0.83822 0.218248 -0.562391 -0.796852 0.220779 -0.427299 -0.71447 0.554029 -0.540518 -0.632858 0.554374 -0.540508 -0.632853 0.554389 -0.632848 -0.540514 0.55439 -0.632861 -0.540518 0.554372 -0.709631 -0.434855 0.554369 -0.70962 -0.434853 0.554385 -0.768909 -0.318492 0.554384 -0.768915 -0.318492 0.554376 -0.809271 -0.194288 0.554375 -0.809263 -0.194289 0.554387 -0.829694 -0.0652953 0.554387 -0.829678 -0.0653006 0.55441 -0.503711 -0.841723 0.194364 -0.637042 -0.745879 0.194532 -0.63704 -0.745879 0.194536 -0.745876 -0.637043 0.194541 -0.745881 -0.637042 0.194524 -0.836354 -0.512516 0.194526 -0.836357 -0.512514 0.194513 -0.906235 -0.375371 0.194513 -0.906236 -0.37537 0.194507 -0.953798 -0.228989 0.194508 -0.953801 -0.228987 0.194494 -0.97788 -0.076965 0.194493 -0.977876 -0.0769685 0.194509 -0.980786 0 0.195088 -0.980786 0 0.195088 -0.831453 0 0.555596 -0.831453 0 0.555596 -0.829678 0.0652941 0.55441 -0.516438 0.842546 0.152997 -0.499503 0.837803 0.220416 -0.50417 0.834985 0.220484 -0.512226 0.854627 0.0850711 -0.512839 0.856303 0.0611627 -0.513105 0.857091 0.0460246 -0.513273 0.857556 0.0338961 -0.513384 0.857882 0.0218082 -0.506145 0.840254 0.194398 -0.637042 0.745881 0.19452 -0.637043 0.745876 0.194536 -0.745878 0.63704 0.194541 -0.745878 0.637045 0.194523 -0.836355 0.512513 0.194526 -0.836356 0.512517 0.194513 -0.906235 0.375371 0.194513 -0.906235 0.375371 0.194513 -0.953798 0.228985 0.194512 -0.953801 0.22899 0.194494 -0.977879 0.076969 0.194493 -0.977877 0.076965 0.194509 -0.424677 0.712297 0.558823 -0.829694 0.0653021 0.554386 -0.809265 0.194287 0.554385 -0.809271 0.194291 0.554375 -0.768915 0.318493 0.554376 -0.768913 0.318491 0.554379 -0.709624 0.434853 0.554379 -0.709628 0.434859 0.55437 -0.632857 0.540522 0.554371 -0.632851 0.54051 0.55439 -0.540513 0.632849 0.55439 -0.540517 0.63286 0.554374 -0.427293 0.714474 0.554028 -0.47227 0.792125 0.386651 0.829678 -0.0652941 0.55441 0.514401 -0.842168 0.161696 0.49951 -0.837808 0.220381 0.504712 -0.834665 0.220456 0.512124 -0.854355 0.0883583 0.512896 -0.856461 0.0584092 0.513091 -0.857044 0.0470424 0.51326 -0.857504 0.0353683 0.513393 -0.857888 0.0213441 0.506222 -0.840212 0.194381 0.637046 -0.745886 0.194492 0.637046 -0.745884 0.194496 0.745885 -0.637046 0.194495 0.745885 -0.637051 0.194477 0.836358 -0.512529 0.194474 0.836356 -0.512517 0.194513 0.906235 -0.37537 0.194513 0.906236 -0.375372 0.194507 0.953799 -0.228986 0.194508 0.953801 -0.22899 0.194494 0.977879 -0.0769687 0.194493 0.977877 -0.0769648 0.194509 0.424675 -0.712288 0.558836 0.829693 -0.0653018 0.554387 0.809264 -0.194286 0.554387 0.809271 -0.194291 0.554375 0.768914 -0.318494 0.554376 0.76891 -0.31849 0.554383 0.709617 -0.434859 0.554385 0.709607 -0.434845 0.554407 0.632846 -0.5405 0.554405 0.632851 -0.54051 0.55439 0.540505 -0.632856 0.554389 0.540503 -0.632846 0.554403 0.427285 -0.714461 0.554051 0.472189 -0.791984 0.38704 0.980786 0 0.195088 0.980786 0 0.195088 0.831453 0 0.555596 0.831453 0 0.555596 0.42467 0.712284 0.558845 0.505104 0.834426 0.220461 0.528981 0.843189 0.0959791 0.5421 0.839852 0.0278539 0.53963 0.84088 0.0414809 0.536827 0.841804 0.0564249 0.534521 0.84238 0.0684322 0.472064 0.791779 0.387611 0.499751 0.838219 0.218262 0.560888 0.79792 0.220746 0.427285 0.714461 0.554051 0.540501 0.632847 0.554403 0.54051 0.632852 0.554389 0.632854 0.540507 0.554389 0.632843 0.540504 0.554405 0.709603 0.434852 0.554407 0.709623 0.434855 0.554379 0.768912 0.318492 0.554379 0.768915 0.318492 0.554376 0.809271 0.194289 0.554375 0.809265 0.19429 0.554385 0.829695 0.0652953 0.554386 0.829678 0.0653009 0.55441 0.503724 0.841726 0.194319 0.63705 0.745885 0.19448 0.637045 0.745885 0.194497 0.745883 0.637049 0.194495 0.745888 0.637048 0.194477 0.836362 0.512521 0.194474 0.836351 0.512525 0.194513 0.906235 0.375371 0.194513 0.906235 0.375371 0.194513 0.953797 0.228989 0.194512 0.953802 0.228986 0.194494 0.97788 0.0769653 0.194493 0.977876 0.0769687 0.194509 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.995185 0.0980186 0 0.995185 0.0980186 0 0.956938 0.290293 0 0.956938 0.290293 0 0.881922 0.471396 0 0.881922 0.471396 0 0.773015 0.634388 0 0.773015 0.634388 0 0.634391 0.773012 0 0.634391 0.773012 0 0.471397 0.881921 0 0.471397 0.881921 0 0.290282 0.956941 0 0.290282 0.956941 0 0.0980167 0.995185 0 0.0980167 0.995185 0 -0.0980167 0.995185 0 -0.0980167 0.995185 0 -0.290282 0.956941 0 -0.290282 0.956941 0 -0.471397 0.881921 0 -0.471397 0.881921 0 -0.6344 0.773005 0 -0.6344 0.773005 0 -0.773006 0.634399 0 -0.773006 0.634399 0 -0.881922 0.471396 0 -0.881922 0.471396 0 -0.956943 0.290276 0 -0.956943 0.290276 0 -0.995185 0.0980186 0 -0.995185 0.0980186 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -0.995185 -0.0980189 0 -0.995185 -0.0980189 0 -0.956943 -0.290276 0 -0.956943 -0.290276 0 -0.881922 -0.471396 0 -0.881922 -0.471396 0 -0.773006 -0.634399 0 -0.773006 -0.634399 0 -0.6344 -0.773005 0 -0.6344 -0.773005 0 -0.471397 -0.881921 0 -0.471397 -0.881921 0 -0.290282 -0.956941 0 -0.290282 -0.956941 0 -0.0980167 -0.995185 0 -0.0980167 -0.995185 0 0.0980167 -0.995185 0 0.0980167 -0.995185 0 0.290282 -0.956941 0 0.290282 -0.956941 0 0.471397 -0.881921 0 0.471397 -0.881921 0 0.634391 -0.773012 0 0.634391 -0.773012 0 0.773015 -0.634388 0 0.773015 -0.634388 0 0.881922 -0.471396 0 0.881922 -0.471396 0 0.956938 -0.290293 0 0.956938 -0.290293 0 0.995185 -0.0980189 0 0.995185 -0.0980189 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 0.984807 0 -0.173652 0.984807 0 -0.173652 0.984807 0 -0.173652 -0.984807 0 -0.173652 -0.984807 0 -0.173652 -0.984807 0 -0.173652 -0.967212 -0.175706 -0.183383 -0.816275 -0.554337 -0.1625 -0.96608 -0.123576 -0.226758 -0.896046 -0.416308 -0.154235 -0.911325 -0.366526 -0.187471 -0.800918 -0.570169 -0.182858 -0.794262 -0.585612 -0.161885 -0.816271 0.554342 -0.162501 -0.794262 0.585612 -0.161886 -0.800917 0.570172 -0.182855 -0.898234 0.397551 -0.187425 -0.913991 0.367598 -0.171732 -0.966293 0.1571 -0.203955 -0.975511 0.124782 -0.181127 0.816266 -0.554346 -0.162511 0.794262 -0.585612 -0.161885 0.800918 -0.570169 -0.182858 0.890824 -0.413938 -0.187315 0.914585 -0.367827 -0.16804 0.960737 -0.174195 -0.215967 0.975511 -0.124782 -0.181127 0.970398 0.158005 -0.182652 0.81627 0.554341 -0.16251 0.970216 0.124105 -0.208036 0.901775 0.399092 -0.165915 0.911328 0.366517 -0.187476 0.800919 0.570168 -0.18286 0.794262 0.585612 -0.161886 -0.802073 -0.575393 -0.160004 -0.847633 -0.519226 -0.109187 -0.998708 -0.0491551 -0.0129062 -0.991837 -0.125739 -0.0211858 -0.98236 -0.185656 -0.0223837 -0.954814 -0.28424 -0.0868179 -0.892779 -0.437294 -0.108258 -0.999979 -0.00617022 -0.00170067 -0.98269 -0.176677 -0.0557268 -0.989475 -0.104986 -0.099588 -0.964273 -0.254399 -0.073883 -0.905249 -0.409976 -0.111549 -0.847569 -0.502574 -0.170428 -0.816398 -0.554165 -0.162466 -0.883761 0.451063 -0.124536 -0.990244 0.134775 -0.0353866 -0.954286 0.298792 -0.00786204 -0.796718 0.597862 -0.0883327 -0.740704 0.649081 -0.173352 -0.847885 0.516207 -0.120918 -0.847569 0.502571 -0.170439 -0.816365 0.554211 -0.162475 -0.982681 0.180922 -0.0400706 -0.982718 0.178456 -0.049187 -0.989386 0.0354414 -0.140923 -0.989024 0.110925 -0.0976102 -0.962843 0.259691 -0.0741272 -0.903829 0.412643 -0.113217 0.883761 -0.451063 -0.124536 0.990244 -0.134775 -0.0353866 0.954286 -0.298792 -0.00786204 0.796718 -0.597862 -0.0883327 0.740664 -0.649125 -0.173359 0.847876 -0.516224 -0.120912 0.84756 -0.502587 -0.170435 0.816389 -0.554176 -0.162477 0.982681 -0.180922 -0.0400706 0.982718 -0.178456 -0.049187 0.989398 -0.035662 -0.140785 0.989057 -0.11027 -0.0980159 0.963272 -0.258119 -0.0740409 0.904261 -0.411838 -0.112701 0.80206 0.57541 -0.160008 0.847624 0.519241 -0.109188 0.998712 0.0490774 -0.0128858 0.99186 0.125562 -0.0211874 0.98236 0.185651 -0.022402 0.954865 0.284085 -0.0867627 0.892808 0.437234 -0.108257 0.999946 0.00999168 -0.00275396 0.982654 0.175651 -0.0594824 0.989024 0.110925 -0.0976102 0.962834 0.259726 -0.0741214 0.903832 0.412642 -0.113202 0.84756 0.502586 -0.170437 0.816382 0.554185 -0.162479 0.802034 -0.399052 -0.444408 0.882078 -0.383907 -0.273047 0.889362 -0.322086 -0.324494 0.987991 -0.111783 -0.106669 0.979399 -0.170075 -0.108869 0.936332 -0.277847 -0.214671 0.881058 -0.421382 -0.21488 0.999754 -0.0130382 -0.0179203 0.999849 -0.0124871 -0.0120982 0.998692 -0.0492959 -0.0135879 0.772345 -0.554546 -0.309778 0.806867 -0.523493 -0.273717 0.705824 -0.493869 -0.507844 0.758014 -0.471631 -0.450533 0.625812 -0.475413 -0.618339 0.911487 -0.163557 -0.377412 0.749051 -0.430152 -0.503877 0.356239 -0.109096 -0.928004 0.298781 -0.0113384 -0.954254 0.684504 -0.393704 -0.613557 0.666133 -0.379908 -0.641824 0.601477 -0.29317 -0.743154 0.585241 -0.288198 -0.757914 0.37858 -0.184775 -0.906937 0.669996 -0.120242 -0.732562 0.662181 -0.122099 -0.739329 0.496861 -0.0903024 -0.863119 0.370534 -0.066746 -0.926418 0.343381 -0.0548248 -0.937595 0.810037 -0.147244 -0.56759 0.905929 -0.166514 -0.389315 0.806675 -0.442959 -0.391231 0.722408 -0.33665 -0.603981 0.785904 -0.535448 -0.309274 0.2988 0 -0.954316 0.2988 0 -0.954316 0.4989 0 -0.86666 0.4989 0 -0.86666 0.674893 0 -0.737916 0.674893 0 -0.737916 0.818964 0 -0.573845 0.818964 0 -0.573845 0.923929 0 -0.382563 0.923929 0 -0.382563 0.700604 0.36866 -0.610937 0.358241 0.0487773 -0.932354 0.343268 0.0989795 -0.934008 0.397335 0.185223 -0.898787 0.538447 0.25241 -0.803968 0.606733 0.284394 -0.74229 0.298781 0.0113384 -0.954254 0.343795 0.0552345 -0.937419 0.49726 0.0810129 -0.863811 0.663251 0.109976 -0.740272 0.670971 0.107653 -0.733628 0.811768 0.13227 -0.568803 0.908463 0.150032 -0.39011 0.913946 0.146604 -0.37843 0.608255 0.287042 -0.740022 0.684924 0.37745 -0.623225 0.807339 0.44372 -0.388993 0.77691 0.383592 -0.499268 0.711493 0.31548 -0.627894 0.785907 0.535444 -0.309274 0.802074 0.399043 -0.444344 0.999769 0.0126914 -0.0173626 0.999851 0.0122061 -0.0121816 0.995239 0.0962206 -0.0155413 0.988391 0.107445 -0.107414 0.957477 0.265626 -0.112605 0.948605 0.232539 -0.21465 0.735584 0.504399 -0.452214 0.719132 0.475206 -0.506979 0.625822 0.4754 -0.618338 0.940461 0.262915 -0.215427 0.874051 0.423623 -0.237862 0.882075 0.383907 -0.273055 0.785332 0.555708 -0.272841 0.795507 0.521355 -0.3088 -0.802074 0.399043 -0.444344 -0.882086 0.383903 -0.273025 -0.889359 0.322232 -0.324357 -0.987775 0.112689 -0.10771 -0.979068 0.171303 -0.109916 -0.935603 0.279481 -0.215726 -0.880432 0.422176 -0.215887 -0.999674 0.0134923 -0.0216988 -0.999846 0.0126026 -0.0121976 -0.998671 0.0496866 -0.0136907 -0.772321 0.554578 -0.309778 -0.806863 0.523508 -0.273698 -0.705814 0.493883 -0.507845 -0.758061 0.471616 -0.450468 -0.625822 0.4754 -0.618338 -0.757384 0.416739 -0.50269 -0.913946 0.146604 -0.37843 -0.34326 0.0989677 -0.934012 -0.298788 0.0113448 -0.954252 -0.397335 0.185223 -0.898787 -0.692436 0.381529 -0.612347 -0.682721 0.374664 -0.627311 -0.606469 0.285064 -0.742249 -0.611484 0.286619 -0.73752 -0.538447 0.25241 -0.803968 -0.670971 0.107653 -0.733628 -0.663251 0.109976 -0.740272 -0.496447 0.0808717 -0.864291 -0.355777 0.0572413 -0.932816 -0.336272 0.0478144 -0.94055 -0.811768 0.13227 -0.568803 -0.908463 0.150032 -0.39011 -0.814267 0.430015 -0.389944 -0.711493 0.31548 -0.627894 -0.785907 0.535444 -0.309274 -0.923929 0 -0.382563 -0.923929 0 -0.382563 -0.818964 0 -0.573845 -0.818964 0 -0.573845 -0.674893 0 -0.737916 -0.674893 0 -0.737916 -0.498079 0 -0.867132 -0.498079 0 -0.867132 -0.298807 0 -0.954314 -0.298807 0 -0.954314 -0.373989 -0.0561895 -0.925729 -0.356252 -0.109097 -0.927999 -0.378594 -0.184776 -0.906932 -0.585257 -0.288196 -0.757903 -0.60148 -0.293163 -0.743154 -0.78591 -0.535439 -0.309274 -0.72243 -0.336673 -0.603942 -0.771192 -0.393565 -0.500369 -0.911487 -0.163557 -0.377412 -0.90592 -0.166519 -0.389335 -0.798661 -0.458038 -0.39031 -0.669998 -0.385492 -0.634427 -0.700603 -0.36866 -0.610937 -0.298788 -0.0113448 -0.954252 -0.35191 -0.063277 -0.933893 -0.496051 -0.0901511 -0.863601 -0.66218 -0.122104 -0.73933 -0.669996 -0.120247 -0.732562 -0.810037 -0.14725 -0.56759 -0.802092 -0.399021 -0.444332 -0.999875 -0.00833457 -0.0134039 -0.999938 -0.0082492 -0.00745355 -0.995984 -0.0889347 -0.0103017 -0.989278 -0.102557 -0.103978 -0.95944 -0.259874 -0.10927 -0.950372 -0.228594 -0.211042 -0.735595 -0.50438 -0.452218 -0.719134 -0.475204 -0.506979 -0.625816 -0.475407 -0.618338 -0.942009 -0.260251 -0.211867 -0.874589 -0.421374 -0.239873 -0.882094 -0.383871 -0.273043 -0.785349 -0.555691 -0.272828 -0.79552 -0.521336 -0.308799 -0.991768 0.0917397 -0.0893367 -0.925767 0.2947 -0.236869 -0.926422 0.281823 -0.249635 -0.93137 0.257229 -0.257649 -0.989187 0.104585 -0.102815 -0.997035 -0.0335759 0.0692405 -0.99999 0.0030274 0.00321834 -1 0 0 -0.991745 0.0830861 -0.0976642 -0.971629 0.164431 -0.169999 -0.846913 0.32686 -0.419406 -0.851408 0.320774 -0.41498 -0.704356 0.45107 -0.548105 -0.702022 0.340124 -0.625684 -0.328886 0.011847 -0.944295 -0.96961 0.00344232 -0.244633 -0.737509 0.00831219 -0.675286 -0.349855 0.00455368 -0.936793 -0.349757 0.0436051 -0.935825 -0.376101 0.0495464 -0.925253 -0.473961 0.104822 -0.874284 -0.472578 0.186249 -0.861384 -0.578 0.150905 -0.801963 -0.579713 0.249663 -0.775629 -0.57891 0.258899 -0.773198 -0.635119 0.283332 -0.718573 -0.632487 0.389657 -0.669423 -0.746472 0.00382862 -0.665405 -0.746013 0.0480099 -0.664199 -0.797658 0.0322999 -0.602245 -0.797265 0.128796 -0.589729 -0.840019 0.101347 -0.533008 -0.840386 0.192693 -0.506577 -0.862498 0.164604 -0.478543 -0.861407 0.25659 -0.438338 -0.850594 0.269915 -0.451259 -0.970697 0.00191178 -0.240299 -0.970595 0.0190163 -0.239965 -0.976791 0.0129327 -0.213803 -0.976665 0.0479881 -0.209337 -0.981785 0.0373373 -0.18629 -0.981775 0.0693848 -0.176929 -0.9844 0.0590739 -0.165734 -0.984432 0.0622489 -0.164377 -0.971801 0.115288 -0.205697 -0.328909 0 -0.944362 -0.328909 0 -0.944362 -0.737535 0 -0.675309 -0.737535 0 -0.675309 -0.969615 0 -0.244635 -0.969615 0 -0.244635 -0.969613 -0.00194628 -0.244634 -0.737529 -0.00382689 -0.675304 -0.349878 -0.0121933 -0.936716 -0.328906 -0.00434406 -0.944353 -0.9707 -0.00343473 -0.240272 -0.97065 -0.0145209 -0.24006 -0.976848 -0.0179726 -0.213178 -0.976772 -0.0421104 -0.210104 -0.981871 -0.0438125 -0.184416 -0.981857 -0.0636654 -0.178616 -0.98445 -0.0650129 -0.163193 -0.984291 -0.0863194 -0.154011 -0.987513 -0.0821253 -0.134438 -0.922336 -0.187004 -0.338122 -0.746492 -0.00839544 -0.665341 -0.74631 -0.0343875 -0.66471 -0.7981 -0.0476478 -0.600638 -0.79791 -0.110936 -0.59248 -0.840747 -0.121341 -0.527657 -0.84091 -0.175082 -0.512071 -0.862976 -0.183201 -0.47086 -0.861234 -0.259396 -0.437023 -0.850302 -0.264244 -0.455151 -0.349626 -0.0551026 -0.935268 -0.3979 -0.0445971 -0.916344 -0.473966 -0.114133 -0.873115 -0.473473 -0.155877 -0.866906 -0.579278 -0.185315 -0.793785 -0.579563 -0.258796 -0.772743 -0.635093 -0.28174 -0.719222 -0.633925 -0.364334 -0.682202 -0.70377 -0.367557 -0.607955 -0.926439 -0.281396 -0.250055 -0.993129 0.0591185 0.100992 -0.991166 -0.0953264 -0.0922077 -0.932725 -0.254265 -0.255684 -0.851407 -0.320798 -0.414963 -0.704356 -0.451076 -0.5481 -0.923043 -0.24668 -0.295196 -0.926536 -0.242009 -0.288032 -0.769758 -0.417082 -0.483234 -1 0 0 -0.999858 -0.0115438 0.0122719 -0.991768 -0.0917397 -0.0893367 -0.991772 -0.08675 -0.0941415 -0.987516 -0.102066 -0.119974 0.99998 0.00457561 -0.00430992 0.999977 0.0062267 -0.00255467 0.997035 -0.0335759 0.0692405 0.989146 0.104757 -0.103031 0.931376 0.2572 -0.257658 0.926422 0.281823 -0.249635 0.926536 0.242021 -0.288022 0.769754 0.417096 -0.483229 0.851493 0.320678 -0.414881 0.704356 0.45107 -0.548105 0.991768 0.0917397 -0.0893367 0.991573 0.103315 -0.078157 0.971993 0.152281 -0.179 0.349688 0.0484046 -0.935615 0.349858 0.0121857 -0.936724 0.328906 0.00434406 -0.944353 0.746493 0.00839544 -0.665341 0.737529 0.0038269 -0.675304 0.9707 0.00343473 -0.240272 0.969613 0.00194627 -0.244634 0.47399 0.104839 -0.874267 0.365941 0.0439452 -0.9296 0.798066 0.0476388 -0.600684 0.74631 0.0343875 -0.66471 0.976848 0.0179726 -0.213178 0.97065 0.0145209 -0.240059 0.976772 0.0421104 -0.210104 0.981871 0.0438125 -0.184416 0.797876 0.110943 -0.592524 0.840747 0.121357 -0.527652 0.473502 0.155885 -0.866888 0.575686 0.290972 -0.764148 0.579713 0.249663 -0.775629 0.579278 0.185315 -0.793785 0.850387 0.264187 -0.455024 0.861236 0.259374 -0.437033 0.971092 0.0996474 -0.216911 0.984291 0.0863194 -0.154011 0.981857 0.0636654 -0.178616 0.98445 0.0650129 -0.163193 0.84091 0.175082 -0.512071 0.862976 0.183201 -0.47086 0.634157 0.249377 -0.731885 0.633925 0.364334 -0.682202 0.70377 0.367557 -0.607955 0.969615 0 -0.244635 0.969615 0 -0.244635 0.737535 0 -0.675309 0.737535 0 -0.675309 0.328909 0 -0.944362 0.328909 0 -0.944362 0.922267 -0.187078 -0.338267 0.328886 -0.0118401 -0.944295 0.96961 -0.00344232 -0.244633 0.737509 -0.00831219 -0.675286 0.349835 -0.00455348 -0.9368 0.349737 -0.0436006 -0.935833 0.41278 -0.0578691 -0.908991 0.473995 -0.114134 -0.873099 0.472607 -0.186249 -0.861368 0.578 -0.150916 -0.80196 0.578684 -0.288942 -0.762652 0.634157 -0.249377 -0.731885 0.632487 -0.389657 -0.669423 0.702022 -0.340124 -0.625684 0.746472 -0.00382862 -0.665405 0.746013 -0.0480012 -0.664199 0.797624 -0.0323014 -0.60229 0.797231 -0.128816 -0.58977 0.840019 -0.101347 -0.533008 0.840386 -0.192693 -0.506577 0.862498 -0.164604 -0.478543 0.861407 -0.25659 -0.438338 0.850678 -0.269814 -0.451162 0.970697 -0.00191178 -0.240299 0.970595 -0.0190163 -0.239965 0.976791 -0.0129327 -0.213803 0.976665 -0.0479881 -0.209337 0.981785 -0.0373373 -0.18629 0.981775 -0.0693848 -0.176929 0.9844 -0.0590739 -0.165734 0.984182 -0.091152 -0.151914 0.987422 -0.0773007 -0.13792 0.925768 -0.294684 -0.236885 0.926428 -0.28167 -0.249785 0.931766 -0.256351 -0.257093 0.989511 -0.1032 -0.10108 0.994229 0.0529855 0.0932816 0.99998 -0.00457561 -0.00430992 0.99998 -0.00450401 -0.00438604 0.991766 -0.0919523 -0.0891318 0.991745 -0.0830861 -0.0976642 0.987458 -0.105406 -0.117541 0.922976 -0.24678 -0.295323 0.846965 -0.326826 -0.419327 0.851492 -0.320695 -0.414868 0.704355 -0.451081 -0.548096 -0.951828 0.292055 0.093424 -0.956031 0.280882 0.0843253 -0.842881 0.518191 0.145015 -0.692279 0.694931 0.194476 -0.686798 0.703931 0.181081 -0.271748 0.93165 0.241208 -0.268475 0.9337 0.236908 0.186028 0.906626 0.378712 -0.0297961 0.968855 0.245828 0.179379 0.952727 0.245224 0.203149 0.955127 0.215552 0.133433 0.828159 0.544379 0.182653 0.788604 0.587147 -0.0948773 0.798479 0.594499 -0.273975 0.805019 0.526195 -0.867888 0.398449 0.296662 -0.727199 0.550581 0.40993 -0.695372 0.611943 0.376808 -0.538918 0.675651 0.503054 -0.330387 0.757053 0.563662 -0.0967313 0.662517 0.742774 -0.336161 0.61101 0.716702 0.148104 0.640686 0.753383 -0.971429 0.157723 0.177339 -0.971428 0.154925 0.179794 -0.970136 0.157006 0.184891 -0.752659 0.431102 0.497649 -0.741802 0.435149 0.510271 0.137814 0.655232 0.742751 0.105981 0.65162 0.751105 0.105982 0.653703 0.749293 -0.0957648 0.650119 0.753774 -0.336158 0.623645 0.705737 -0.364365 0.610598 0.703142 -0.364366 0.611073 0.702729 -0.553952 0.543622 0.630565 -0.954053 0.0748375 0.290141 -0.972292 0.154379 0.175541 -0.872014 0.325653 0.365433 -0.752655 0.430169 0.498463 -0.733837 0.449919 0.508975 -0.546388 0.557319 0.625184 0.0501445 0.198836 0.978749 0.0612647 0.416071 0.907266 0.0590694 0.603061 0.795505 -0.329508 0.206897 0.921205 -0.298711 0.166373 0.93973 -0.0452328 0.174154 0.983679 0.145885 0.496411 0.855742 -0.094293 0.499543 0.861142 -0.327777 0.468827 0.820222 -0.968874 0.0431501 0.243763 -0.870203 0.0858798 0.48515 -0.736575 0.157182 0.657839 -0.723142 0.12041 0.680123 -0.520414 0.148864 0.840838 -0.331588 0.473402 0.816051 -0.547898 0.419771 0.723602 -0.734056 0.336532 0.589838 -0.737004 0.342845 0.582479 -0.96905 0.120088 0.215687 -0.969778 0 0.24399 -0.873257 -0.0199127 0.486853 -0.96592 0 0.258842 -0.728442 0 0.685108 -0.707105 -0.00221149 0.707105 -0.526278 0 0.850313 -0.302933 0 0.953012 -0.258812 -0.00310062 0.965923 -0.0459347 0 0.998944 -0.25873 0.0254837 0.965614 -0.705398 0.0694813 0.705398 -0.961578 0.0947086 0.257679 -0.961581 0.0947152 0.257663 -0.924632 0.280475 0.257663 -0.924632 0.280475 0.257662 -0.852144 0.455479 0.257661 -0.852145 0.455488 0.257644 -0.746908 0.612982 0.257646 -0.74691 0.612968 0.257674 -0.612978 0.746902 0.257672 -0.612976 0.74691 0.257656 -0.455481 0.852145 0.257656 -0.455479 0.852148 0.257648 -0.280482 0.924633 0.257652 -0.280482 0.924632 0.257652 -0.0947074 0.961584 0.257656 -0.0947076 0.961584 0.257656 0.0947074 0.961584 0.257656 0.0947057 0.961583 0.25766 0.280481 0.924629 0.257665 0.280487 0.924631 0.257652 0.455482 0.852147 0.257648 0.455478 0.852146 0.257656 0.612972 0.746913 0.257656 0.612978 0.746912 0.257643 0.746919 0.612972 0.25764 0.746915 0.612973 0.257647 0.852148 0.455482 0.257644 0.852141 0.455485 0.257661 0.924627 0.280491 0.257662 0.924627 0.280491 0.257662 0.961582 0.094709 0.257663 0.961591 0.0946981 0.257634 -0.705393 0.0694782 0.705403 -0.678288 0.20575 0.705403 -0.678294 0.205756 0.705395 -0.625116 0.334137 0.705395 -0.625104 0.334118 0.705415 -0.547909 0.449653 0.705413 -0.547917 0.449675 0.705393 -0.449669 0.547921 0.705394 -0.449668 0.547915 0.705399 -0.334129 0.625116 0.705399 -0.334129 0.625114 0.705401 -0.205755 0.678288 0.705401 -0.205756 0.678284 0.705405 -0.0694752 0.705395 0.705401 -0.0694751 0.705395 0.705401 0.0694739 0.705395 0.705401 0.0694753 0.705397 0.705399 0.205759 0.67829 0.705398 0.205757 0.678287 0.705401 0.334128 0.625115 0.705401 0.33413 0.625116 0.705399 0.449666 0.547917 0.705399 0.449656 0.547912 0.705409 0.547911 0.449655 0.705411 0.547908 0.449654 0.705413 0.625098 0.334127 0.705416 0.625121 0.334127 0.705396 0.678291 0.205764 0.705395 0.678308 0.20576 0.70538 0.705419 0.0694701 0.705378 0.705398 0.0694787 0.705398 -0.258731 0.0254845 0.965613 -0.248789 0.0754684 0.965613 -0.248792 0.0754709 0.965612 -0.229289 0.122555 0.965612 -0.229293 0.12256 0.965611 -0.200975 0.16494 0.965611 -0.200971 0.164933 0.965613 -0.164934 0.20097 0.965613 -0.164934 0.200971 0.965612 -0.122556 0.229287 0.965613 -0.122555 0.229284 0.965613 -0.0754696 0.248789 0.965613 -0.0754694 0.248793 0.965612 -0.025483 0.258734 0.965612 -0.0254833 0.258733 0.965613 0.0254828 0.258733 0.965613 0.0254829 0.258733 0.965613 0.0754696 0.248789 0.965613 0.0754696 0.248789 0.965613 0.122554 0.229284 0.965613 0.122557 0.229287 0.965613 0.164932 0.200972 0.965612 0.164931 0.200972 0.965613 0.200971 0.164932 0.965613 0.200978 0.164935 0.965611 0.229295 0.122558 0.965611 0.229288 0.122557 0.965612 0.248792 0.0754695 0.965612 0.248788 0.0754698 0.965613 0.258731 0.0254839 0.965613 0.25873 0.0254843 0.965614 0.969778 0 0.24399 0.965931 -0.00117581 0.258797 0.873775 0 0.486331 0.728442 0 0.685108 0.707105 -0.00221149 0.707105 0.0459347 0 0.998944 0.258812 -0.00310062 0.965923 0.302933 0 0.953012 0.526278 0 0.850313 0.0444053 0.25589 0.965686 -0.0612647 0.416071 0.907266 -0.0487507 0.174125 0.983516 0.298711 0.166373 0.93973 0.329508 0.206897 0.921205 0.96905 0.120088 0.215687 0.73703 0.342831 0.582455 0.734081 0.336518 0.589814 0.334578 0.476989 0.812736 0.327777 0.468827 0.820222 0.094293 0.499543 0.861142 -0.0606591 0.500855 0.863403 -0.147426 0.561786 0.814041 0.520414 0.148864 0.840838 0.723142 0.12041 0.680123 0.736606 0.157272 0.657782 0.870555 0.0857715 0.484539 0.968874 0.0431502 0.243763 0.971441 0.157691 0.177302 -0.137804 0.655231 0.742754 -0.105981 0.65162 0.751105 0.0967313 0.662517 0.742774 0.336158 0.623645 0.705737 0.364364 0.610598 0.703142 0.546388 0.557319 0.625184 0.733837 0.449919 0.508975 0.752655 0.430169 0.498463 0.872014 0.325653 0.365433 0.972304 0.154346 0.175504 0.954027 0.0746898 0.290265 0.970134 0.158344 0.183761 0.971435 0.153534 0.180948 0.741803 0.439151 0.506828 0.752631 0.427022 0.501198 0.338892 0.616973 0.710279 0.364333 0.603641 0.70914 0.0957648 0.650119 0.753774 -0.105982 0.653703 0.749293 -0.148104 0.640686 0.753383 -0.135198 0.794748 0.59169 -0.184077 0.814191 0.550644 0.0297956 0.968863 0.245799 -0.186011 0.906909 0.378042 -0.179403 0.95273 0.245194 -0.203149 0.955127 0.215552 0.84597 0.513507 0.143688 0.684744 0.701826 0.196383 0.690886 0.700176 0.180083 0.0948768 0.798494 0.594479 0.273986 0.805028 0.526177 0.271521 0.932879 0.23667 0.268165 0.932624 0.241453 0.330385 0.757079 0.563629 0.538915 0.675674 0.503026 0.695364 0.611959 0.376795 0.727198 0.550592 0.409918 0.999574 0.0234056 0.0174255 0.857063 0.459133 0.233751 0.951818 0.292102 0.0933778 0.951817 -0.292106 0.0933742 0.95607 -0.280797 0.0841648 0.845968 -0.513506 0.143704 0.692279 -0.694931 0.194476 0.686798 -0.703931 0.181081 0.271748 -0.93165 0.241208 0.268475 -0.9337 0.236908 -0.186001 -0.906787 0.378341 0.0297961 -0.968855 0.245828 -0.179366 -0.952729 0.245224 -0.203149 -0.955131 0.215535 -0.133423 -0.828161 0.544378 -0.182633 -0.788615 0.587139 0.094877 -0.798487 0.594489 0.273976 -0.805027 0.526184 0.867873 -0.398471 0.296678 0.727205 -0.550575 0.409926 0.695372 -0.611949 0.376797 0.538917 -0.675659 0.503044 0.330386 -0.757062 0.563651 0.0967313 -0.662517 0.742774 0.336161 -0.611009 0.716704 -0.148096 -0.640687 0.753384 0.97144 -0.157693 0.177303 0.971439 -0.154894 0.179759 0.970136 -0.156993 0.184902 0.752663 -0.431091 0.497653 0.741827 -0.43513 0.51025 -0.137804 -0.655231 0.742754 -0.105981 -0.65162 0.751105 -0.105982 -0.653701 0.749295 0.0957648 -0.650117 0.753776 0.336158 -0.623645 0.705737 0.364365 -0.610598 0.703142 0.364366 -0.611071 0.702731 0.553473 -0.543836 0.630801 0.954027 -0.074687 0.290267 0.972305 -0.154344 0.175503 0.872002 -0.325666 0.365449 0.752658 -0.430167 0.49846 0.733842 -0.449916 0.508971 0.546388 -0.557319 0.625184 -0.0501445 -0.198836 0.978749 -0.0612725 -0.41624 0.907188 -0.059082 -0.603046 0.795515 0.331022 -0.251389 0.909521 0.236493 -0.169387 0.956755 0.0452328 -0.174154 0.983679 -0.145879 -0.496419 0.855738 0.0942928 -0.499551 0.861137 0.327777 -0.468834 0.820218 0.968874 -0.0431518 0.243763 0.798163 -0.105014 0.593219 0.738865 -0.232135 0.632608 0.626945 -0.135815 0.767134 0.463907 -0.154437 0.872319 0.331589 -0.473411 0.816046 0.547525 -0.419901 0.723809 0.734084 -0.336516 0.589811 0.737029 -0.34282 0.582462 0.96905 -0.120085 0.21569 0.965932 0 0.258797 0.969777 0.00124727 0.24399 0.793341 -0.000705137 0.608777 0.8026 0 0.596517 0.632809 0 0.774308 0.608777 0.000966462 0.793341 0.46954 -0.000631236 0.882911 0.239958 0.00441199 0.970773 0.258812 0.00310062 0.965923 0.0459347 0 0.998945 0.790931 -0.0778916 0.606928 0.96159 -0.09471 0.257634 0.25873 -0.0254838 0.965614 0.607686 -0.0598545 0.791919 0.961583 -0.0946976 0.257663 0.924627 -0.280491 0.257662 0.924627 -0.280491 0.257662 0.852144 -0.455479 0.257661 0.852145 -0.455488 0.257644 0.746917 -0.612971 0.257647 0.746917 -0.612974 0.25764 0.612974 -0.746916 0.257643 0.612976 -0.74691 0.257656 0.455481 -0.852145 0.257656 0.455479 -0.852148 0.257648 0.280482 -0.924633 0.257652 0.280486 -0.924628 0.257665 0.0947073 -0.961583 0.25766 0.0947058 -0.961584 0.257656 -0.0947074 -0.961584 0.257656 -0.0947076 -0.961584 0.257656 -0.280482 -0.924633 0.257652 -0.280482 -0.924633 0.257652 -0.455482 -0.852147 0.257648 -0.455478 -0.852146 0.257656 -0.612981 -0.746906 0.257656 -0.612974 -0.746906 0.257671 -0.746902 -0.612977 0.257675 -0.746915 -0.612973 0.257647 -0.852148 -0.455482 0.257644 -0.852141 -0.455485 0.257661 -0.924632 -0.280475 0.257662 -0.924632 -0.280475 0.257663 -0.961582 -0.0947092 0.257663 -0.961577 -0.0947151 0.257678 0.708848 -0.0448331 0.703935 0.678306 -0.205769 0.705379 0.678294 -0.205756 0.705395 0.625116 -0.334137 0.705395 0.625104 -0.334118 0.705415 0.547909 -0.449653 0.705413 0.54791 -0.449656 0.705411 0.44966 -0.547909 0.705409 0.449662 -0.54792 0.705399 0.334129 -0.625116 0.705399 0.334129 -0.625114 0.705401 0.205758 -0.678287 0.705401 0.205758 -0.67829 0.705398 0.0694742 -0.705397 0.705399 0.0694751 -0.705395 0.705401 -0.0694752 -0.705395 0.705401 -0.0694751 -0.705395 0.705401 -0.205754 -0.678284 0.705405 -0.205757 -0.678287 0.705401 -0.334128 -0.625115 0.705401 -0.33413 -0.625116 0.705399 -0.449666 -0.547917 0.705399 -0.449671 -0.547919 0.705394 -0.547925 -0.449667 0.705392 -0.547902 -0.449662 0.705413 -0.625098 -0.334127 0.705416 -0.625121 -0.334127 0.705396 -0.678295 -0.205752 0.705395 -0.678286 -0.205754 0.705403 -0.705393 -0.069481 0.705403 -0.705398 -0.0694788 0.705398 0.258731 -0.0254845 0.965613 0.248789 -0.0754684 0.965613 0.248792 -0.0754709 0.965612 0.229289 -0.122555 0.965612 0.229293 -0.12256 0.965611 0.200977 -0.164937 0.965611 0.200973 -0.16493 0.965613 0.164932 -0.200972 0.965613 0.164932 -0.200973 0.965612 0.122556 -0.229287 0.965613 0.122555 -0.229284 0.965613 0.0754696 -0.248789 0.965613 0.0754696 -0.248789 0.965613 0.0254828 -0.258733 0.965613 0.0254829 -0.258733 0.965613 -0.0254828 -0.258733 0.965613 -0.0254834 -0.258734 0.965613 -0.0754706 -0.248792 0.965612 -0.0754684 -0.248789 0.965613 -0.122554 -0.229284 0.965613 -0.122557 -0.229287 0.965613 -0.164935 -0.200971 0.965612 -0.164933 -0.20097 0.965613 -0.200969 -0.164935 0.965613 -0.200976 -0.164937 0.965611 -0.229295 -0.122558 0.965611 -0.229288 -0.122557 0.965612 -0.248792 -0.0754695 0.965612 -0.248788 -0.0754698 0.965613 -0.258731 -0.025484 0.965613 -0.25873 -0.0254844 0.965614 -0.969778 0 0.24399 -0.965919 0.00117937 0.258842 -0.87343 0 0.486949 -0.728442 0 0.685108 -0.707105 0.00221148 0.707105 -0.0459347 0 0.998945 -0.258812 0.00310062 0.965923 -0.302933 0 0.953012 -0.526278 0 0.850313 -0.0444053 -0.25589 0.965686 0.0612725 -0.41624 0.907188 0.0487507 -0.174125 0.983516 -0.298711 -0.166373 0.93973 -0.329508 -0.206897 0.921205 -0.96905 -0.120085 0.21569 -0.737003 -0.342835 0.582486 -0.734058 -0.336531 0.589835 -0.334572 -0.47699 0.812738 -0.327777 -0.468834 0.820218 -0.0942928 -0.499551 0.861137 0.0606692 -0.500863 0.863398 0.147419 -0.561781 0.814045 -0.520414 -0.148864 0.840838 -0.723142 -0.12041 0.680123 -0.736576 -0.157187 0.657836 -0.870203 -0.0858831 0.48515 -0.968874 -0.0431518 0.243763 -0.971428 -0.157725 0.17734 0.137814 -0.655232 0.742751 0.105981 -0.65162 0.751105 -0.0967313 -0.662517 0.742774 -0.336158 -0.623645 0.705737 -0.364364 -0.610598 0.703142 -0.546388 -0.557319 0.625184 -0.733842 -0.449916 0.508972 -0.752658 -0.430167 0.49846 -0.872002 -0.325666 0.365449 -0.972293 -0.154378 0.175541 -0.954053 -0.0748346 0.290144 -0.970134 -0.158344 0.183761 -0.971422 -0.153581 0.180975 -0.741777 -0.43918 0.50684 -0.752635 -0.427019 0.501195 -0.338885 -0.616975 0.710281 -0.364333 -0.603639 0.709142 -0.0957648 -0.650117 0.753776 0.105982 -0.653701 0.749295 0.148096 -0.640687 0.753384 0.135207 -0.794754 0.591679 0.184077 -0.814192 0.550643 -0.0297956 -0.968863 0.245799 0.186015 -0.90672 0.378494 0.17939 -0.952732 0.245195 0.203149 -0.955131 0.215535 -0.842883 -0.518193 0.144999 -0.684744 -0.701826 0.196383 -0.690891 -0.700175 0.180069 -0.0948766 -0.798502 0.594469 -0.273976 -0.805035 0.526171 -0.271509 -0.932883 0.23667 -0.268167 -0.932628 0.241436 -0.330385 -0.757079 0.563629 -0.538915 -0.675674 0.503026 -0.69537 -0.611956 0.37679 -0.727204 -0.550587 0.409914 -0.999563 -0.0237054 0.0176488 -0.857054 -0.459121 0.233809 -0.951827 -0.292058 0.0934205 -0.195098 -0.0047347 0.980772 -0.188015 -0.0131971 0.982078 -0.442181 -0.00763825 0.896893 -0.427911 -0.0147114 0.903701 -0.608718 -0.00651041 0.79336 -0.590243 -0.0271497 0.806769 -0.793409 -0.00585386 0.608661 -0.772874 -0.0370962 0.633474 -0.89675 -0.0113038 0.442394 -0.878623 -0.0334337 0.476344 -0.980774 0.00704376 0.195022 -0.968279 -0.0655586 0.24112 -0.980798 0 0.195027 -0.965929 -0.00151212 0.258803 -0.896807 0 0.442422 -0.793423 0 0.608671 -0.707129 -0.0020188 0.707081 -0.608731 0 0.793377 -0.442194 0 0.896919 -0.258803 -0.00151032 0.965929 -0.1951 0 0.980783 0.15315 -0.925904 0.345322 0.161294 -0.847283 0.506059 0.151422 -0.721306 0.675862 0.143843 -0.676297 0.722449 0.405039 -0.90911 0.0972787 0.432378 -0.900224 0.0514383 -0.254252 -0.884236 0.391768 -0.0336721 -0.978876 0.201663 -0.0301073 -0.978972 0.201758 0.0502665 -0.978521 0.199924 0.105344 -0.967904 0.228177 -0.202543 -0.14816 0.968 -0.122463 -0.164049 0.978821 -0.266987 -0.239074 0.933574 -0.289812 -0.703883 0.648505 -0.339967 -0.891853 0.298363 -0.668876 -0.683012 0.293427 -0.668346 -0.685019 0.289934 -0.812134 -0.49929 0.301907 -0.913934 -0.280431 0.293398 -0.937195 -0.257102 0.23572 -0.846408 -0.259762 0.464884 -0.668299 -0.205101 0.71506 -0.512228 -0.469255 0.719321 -0.453593 -0.463179 0.761393 -0.282521 -0.707415 0.647878 -0.757971 -0.17991 0.626987 -0.576379 -0.17688 0.79781 -0.24621 -0.0755575 0.966267 -0.425132 -0.0637292 0.902885 -0.185665 -0.0569759 0.98096 -0.961588 -0.0947068 0.25764 -0.961592 -0.0947102 0.257625 -0.924638 -0.280486 0.257627 -0.92463 -0.280474 0.257669 -0.85214 -0.455481 0.25767 -0.852138 -0.455476 0.257687 -0.746906 -0.612969 0.257684 -0.746908 -0.612982 0.257646 -0.612975 -0.746913 0.257649 -0.612974 -0.746898 0.257695 -0.455474 -0.852138 0.257688 -0.455475 -0.852134 0.257702 -0.280484 -0.924622 0.257689 -0.280481 -0.92463 0.257664 -0.0947081 -0.961581 0.257667 -0.0947072 -0.961582 0.257662 0.0947082 -0.961582 0.257662 0.0947071 -0.961581 0.257667 0.280481 -0.92463 0.257663 0.280481 -0.92463 0.257663 0.455486 -0.852141 0.257659 0.455477 -0.852137 0.257688 0.612967 -0.746903 0.257695 0.612964 -0.746903 0.257706 0.746899 -0.612964 0.257715 0.74691 -0.612964 0.257684 0.852136 -0.455479 0.257687 0.852142 -0.455478 0.25767 0.924628 -0.280482 0.257669 0.924614 -0.280488 0.257713 0.961569 -0.0947048 0.257714 0.961564 -0.0947075 0.257729 -0.705422 -0.0694713 0.705374 -0.705442 -0.0694789 0.705355 -0.67833 -0.205774 0.705355 -0.678316 -0.205765 0.705371 -0.625139 -0.334145 0.705371 -0.62514 -0.334146 0.70537 -0.547937 -0.449687 0.70537 -0.547926 -0.449671 0.705389 -0.449674 -0.547925 0.705387 -0.449679 -0.547936 0.705375 -0.33414 -0.625137 0.705375 -0.33414 -0.625135 0.705377 -0.205763 -0.67831 0.705377 -0.205763 -0.678303 0.705384 -0.069478 -0.705416 0.70538 -0.0694779 -0.705416 0.70538 0.069478 -0.705416 0.70538 0.0694779 -0.705416 0.70538 0.205757 -0.678305 0.705384 0.205762 -0.678311 0.705377 0.334145 -0.625133 0.705376 0.334146 -0.625134 0.705375 0.449675 -0.54794 0.705375 0.449691 -0.547951 0.705357 0.547958 -0.44969 0.705351 0.54794 -0.449682 0.705371 0.62514 -0.334146 0.70537 0.625139 -0.334146 0.705371 0.678315 -0.205769 0.705371 0.678331 -0.205769 0.705355 0.705442 -0.0694732 0.705354 0.705422 -0.069477 0.705374 -0.258719 -0.0254813 0.965616 -0.25871 -0.0254782 0.965619 -0.248767 -0.0754634 0.965619 -0.24877 -0.0754652 0.965618 -0.229268 -0.122548 0.965618 -0.229264 -0.122545 0.965619 -0.200952 -0.164919 0.965619 -0.200952 -0.16492 0.965619 -0.16492 -0.200951 0.965619 -0.164925 -0.20096 0.965616 -0.122547 -0.229273 0.965617 -0.122546 -0.229269 0.965618 -0.0754634 -0.24877 0.965618 -0.0754633 -0.248769 0.965619 -0.0254814 -0.258712 0.965618 -0.0254812 -0.258713 0.965618 0.0254811 -0.258713 0.965618 0.0254813 -0.258714 0.965618 0.0754667 -0.248775 0.965617 0.0754601 -0.248763 0.96562 0.122539 -0.229259 0.965621 0.12255 -0.229271 0.965617 0.164924 -0.20096 0.965616 0.164917 -0.200955 0.965619 0.200955 -0.164917 0.965619 0.200954 -0.164916 0.965619 0.229264 -0.122546 0.965619 0.229268 -0.122547 0.965618 0.24877 -0.0754645 0.965618 0.248767 -0.0754642 0.965619 0.258709 -0.0254803 0.965619 0.258719 -0.0254791 0.965617 0.225659 -0.868249 0.441839 0.443526 -0.894327 0.058853 0.433338 -0.89943 0.0569573 0.442866 -0.896184 0.0269261 0.445503 -0.894316 0.0415534 0.443156 -0.896305 0.0158073 0.446616 -0.89442 0.0234057 0.441197 -0.897035 0.0259316 0.438439 -0.898741 0.00598958 -0.164239 -0.824418 0.541628 0.0474764 -0.975009 0.217034 0.046825 -0.976794 0.209001 0.118835 -0.944654 0.305789 0.145111 -0.981898 0.121736 0.223489 -0.947277 0.229608 0.260822 -0.963903 0.0535043 0.32227 -0.937503 0.131264 0.326942 -0.943112 0.0603963 0.369049 -0.923248 0.106846 0.373532 -0.926412 0.0472814 0.411449 -0.908761 0.0697407 0.409617 -0.91052 0.0562759 0.432192 -0.899792 0.0598788 -0.294924 -0.685732 0.665426 -0.148635 -0.624422 0.766814 -0.324474 -0.40945 0.852683 -0.26057 -0.442354 0.858153 -0.120008 -0.394337 0.911096 -0.0238304 -0.211425 0.977104 0.00578935 -0.458103 0.88888 0.445527 -0.894305 0.0415262 0.433486 -0.900072 0.0442796 0.432341 -0.900769 0.0411777 0.415666 -0.908701 0.0385355 0.417465 -0.907249 0.0512097 0.390062 -0.920129 0.0348561 0.385292 -0.919784 0.0744782 0.357169 -0.933024 0.0435511 0.351487 -0.931672 0.0918964 0.312234 -0.949069 0.0421691 0.278006 -0.94726 0.15941 0.229165 -0.969005 0.0922699 0.202847 -0.955204 0.215496 0.106818 -0.990465 0.0869942 -0.0738543 -0.835915 0.543867 -0.0706721 -0.834673 0.546193 -0.0544099 -0.694236 0.717688 0.0901013 -0.639962 0.763106 0.0994963 -0.604598 0.790293 0.441224 -0.897112 0.0226354 0.432341 -0.901372 0.0247004 0.433451 -0.900767 0.0271919 0.421918 -0.90628 0.0253227 0.422598 -0.905823 0.0299256 0.406078 -0.913617 0.020091 0.401644 -0.9147 0.0447864 0.385463 -0.92233 0.0269392 0.380577 -0.92318 0.0538408 0.359391 -0.932798 0.0269535 0.333941 -0.938061 0.0923347 0.307966 -0.949709 0.0566642 0.287545 -0.949334 0.126816 0.238534 -0.969181 0.0615618 0.101823 -0.935728 0.337705 0.115638 -0.930417 0.347781 0.111899 -0.876302 0.468586 0.171701 -0.85534 0.488786 0.216139 -0.763494 0.608573 0.437333 -0.899244 0.00996427 0.437431 -0.899198 0.00990227 0.436662 -0.89958 0.00907675 0.433248 -0.901221 0.00985761 0.432027 -0.901829 0.00763712 0.42771 -0.903889 0.00695592 0.428122 -0.90367 0.00963765 0.421496 -0.906812 0.00569806 0.419167 -0.90779 0.0146765 0.41267 -0.91085 0.00751753 0.410133 -0.911864 0.0171954 0.402196 -0.915526 0.00710279 0.390699 -0.920044 0.0295619 0.380861 -0.924493 0.016056 0.371424 -0.92756 0.0409564 0.349527 -0.936852 0.0118028 0.288307 -0.950306 0.117461 0.279575 -0.95367 0.111136 0.275414 -0.947043 0.165096 0.277016 -0.946482 0.165632 0.285327 -0.938362 0.1951 0.980774 0 0.195149 0.965905 -0.00151142 0.258892 0.896807 0 0.442422 0.793423 0 0.608671 0.707129 -0.0020188 0.707081 0.1951 0 0.980783 0.258803 -0.00151032 0.965929 0.442194 0 0.896919 0.608731 0 0.793377 0.0339726 -0.442129 0.896308 0.139081 -0.593824 0.792484 0.0446134 -0.190486 0.980676 0.204638 -0.873725 0.44128 0.212803 -0.942344 0.258268 0.223683 -0.955046 0.19456 0.0149891 -0.195066 0.980676 0.0277324 -0.257606 0.965852 0.05135 -0.253955 0.965852 0.101122 -0.431754 0.896305 0.0467247 -0.608089 0.792493 0.0645841 -0.704833 0.706428 0.151266 -0.691431 0.706429 0.181116 -0.773295 0.607628 0.07515 -0.97801 0.194548 0.0816873 -0.962613 0.25827 0.0687551 -0.894759 0.441224 0.060849 -0.791871 0.607649 0.188435 -0.00457299 0.982075 0.195083 -0.0130589 0.9807 0.428212 -0.00797803 0.903643 0.44215 -0.0141188 0.89683 0.590977 -0.00738741 0.806655 0.608531 -0.0256054 0.793117 0.774039 -0.00837234 0.633083 0.792976 -0.0335466 0.608329 0.879203 -0.0156872 0.47619 0.896447 -0.0283456 0.442244 0.970554 0.000659673 0.240884 0.979203 -0.0565772 0.194836 0 -0.195088 0.980786 0 -0.195088 0.980786 0 -0.442385 0.896825 0 -0.442385 0.896825 0 -0.608754 0.793359 0 -0.608754 0.793359 0 -0.793341 0.608777 0 -0.793341 0.608777 0 -0.896882 0.442271 0 -0.896882 0.442271 0 -0.980783 0.1951 0 -0.980783 0.1951 0.289799 -0.703838 0.648559 0.537378 -0.548735 0.640402 0.322313 -0.442415 0.836889 0.512228 -0.469255 0.719321 0.266987 -0.239074 0.933574 0.175289 -0.191805 0.965653 0.121785 -0.0890856 0.988551 -0.431912 -0.900402 0.0522388 -0.405039 -0.90911 0.0972787 -0.143843 -0.676297 0.722449 -0.151399 -0.721169 0.676013 -0.161282 -0.847271 0.506083 -0.15314 -0.925896 0.345346 0.846408 -0.259762 0.464884 -0.105326 -0.967908 0.228168 -0.0502665 -0.978521 0.199924 0.0301073 -0.978972 0.201758 0.0336721 -0.978876 0.201663 0.254252 -0.884236 0.391768 0.339967 -0.891853 0.298363 0.667575 -0.684229 0.293554 0.669589 -0.68374 0.290087 0.81493 -0.494665 0.301987 0.920692 -0.259165 0.29182 0.929422 -0.285233 0.23413 0.748983 -0.229863 0.62144 0.679482 -0.17988 0.7113 0.57629 -0.176853 0.79788 0.419834 -0.128839 0.89841 0.255732 -0.0592992 0.964927 0.185665 -0.0569824 0.98096 -0.101123 -0.431754 0.896305 -0.046724 -0.608089 0.792493 -0.0149889 -0.195066 0.980676 -0.0687551 -0.894759 0.441224 -0.0816873 -0.962613 0.25827 -0.07515 -0.97801 0.194548 -0.0446146 -0.190491 0.980675 -0.0513508 -0.253955 0.965852 -0.027732 -0.257607 0.965852 -0.0339721 -0.442129 0.896308 -0.139083 -0.593823 0.792484 -0.15127 -0.691441 0.706418 -0.064584 -0.704837 0.706423 -0.060849 -0.791871 0.607649 -0.223683 -0.955046 0.19456 -0.212803 -0.942344 0.258268 -0.204643 -0.873759 0.44121 -0.181109 -0.773275 0.607656 -0.00578935 -0.458103 0.888881 -0.43283 -0.901104 0.0258693 -0.438439 -0.898741 0.00598958 -0.444336 -0.894975 0.0398159 -0.437027 -0.899391 0.0101587 -0.445735 -0.893287 0.0579591 -0.433355 -0.899501 0.0556918 -0.431744 -0.900011 0.0598074 -0.41358 -0.908687 0.056908 -0.408273 -0.910249 0.0689906 -0.384326 -0.921575 0.0547117 -0.362567 -0.926702 0.0988332 -0.343814 -0.935782 0.0781219 -0.310758 -0.943389 0.115955 -0.290721 -0.952519 0.0904974 -0.207559 -0.955993 0.207356 -0.186588 -0.966095 0.178452 -0.0900414 -0.95938 0.267362 0.294876 -0.685819 0.665358 0.0521388 -0.905636 0.420838 -0.031432 -0.999173 0.0258002 -0.046825 -0.976794 0.209001 -0.4374 -0.899235 0.00760696 -0.432799 -0.901449 0.00867345 -0.432625 -0.901529 0.00902759 -0.42794 -0.903769 0.00827393 -0.42724 -0.904092 0.00911257 -0.42428 -0.905501 0.00735128 -0.41778 -0.908453 0.0131436 -0.41609 -0.909254 0.0112798 -0.40773 -0.912983 0.0147812 -0.407275 -0.913195 0.0142004 -0.387682 -0.921433 0.0257686 -0.387874 -0.921345 0.0260331 -0.366281 -0.929881 0.0340502 -0.364662 -0.930594 0.0318849 -0.280177 -0.953443 0.111572 -0.296284 -0.947114 0.123249 -0.259824 -0.952325 0.159902 -0.290356 -0.941673 0.170133 -0.272769 -0.942099 0.195054 -0.225678 -0.868283 0.441762 -0.432859 -0.901092 0.0258002 -0.423857 -0.905401 0.0243679 -0.420911 -0.906641 0.0289167 -0.412389 -0.910696 0.0238364 -0.398609 -0.916223 0.0405836 -0.393689 -0.918571 0.0351569 -0.375082 -0.925809 0.0468138 -0.373071 -0.926747 0.0442519 -0.326588 -0.941589 0.0821598 -0.326409 -0.941673 0.0819123 -0.274522 -0.955349 0.1093 -0.278227 -0.953694 0.114269 -0.0820706 -0.942788 0.323134 -0.159297 -0.91157 0.379031 -0.0727468 -0.887859 0.454329 -0.223226 -0.833993 0.504605 -0.148982 -0.781319 0.606089 -0.436227 -0.899729 0.0139121 -0.439762 -0.898075 0.00841969 -0.445796 -0.894874 0.0215986 -0.441215 -0.897087 0.0237569 -0.441173 -0.896968 0.0285566 -0.442271 -0.896568 0.0237016 -0.445499 -0.894319 0.0415325 -0.432842 -0.900375 0.0444261 -0.433499 -0.900144 0.042661 -0.41897 -0.907105 0.040314 -0.414725 -0.908659 0.0484037 -0.399155 -0.916048 0.0391424 -0.380071 -0.922343 0.0694897 -0.369421 -0.927468 0.0577201 -0.342783 -0.935939 0.0807364 -0.334123 -0.939948 0.0697106 -0.266244 -0.953226 0.143089 -0.258981 -0.956673 0.13306 -0.181991 -0.965266 0.187457 -0.173368 -0.969024 0.175886 0.104597 -0.84721 0.52086 -0.00706296 -0.800058 0.599881 0.120247 -0.713147 0.690625 -0.106998 -0.632453 0.767173 -0.075638 -0.610579 0.788335 0.288157 -0.68353 0.670635 0.186579 -0.476835 0.858962 0.26057 -0.442354 0.858153 0.00764313 -0.349809 0.93679 0.122457 -0.239731 0.963085 0.195098 0.00473488 0.980772 0.188015 0.0131976 0.982078 0.442181 0.00763856 0.896893 0.427912 0.0147114 0.903701 0.608718 0.00651041 0.79336 0.590142 0.02726 0.806839 0.793408 0.0059891 0.60866 0.772973 0.0370793 0.633355 0.89675 0.0113038 0.442394 0.878623 0.0334337 0.476344 0.980749 -0.00702681 0.195144 0.968289 0.0653885 0.241123 0.980774 0 0.195149 0.965905 0.00151142 0.258892 0.896807 0 0.442422 0.793423 0 0.608671 0.707129 0.0020188 0.707081 0.608731 0 0.793377 0.442194 0 0.896919 0.258803 0.00151032 0.965929 0.1951 0 0.980783 -0.15314 0.925896 0.345346 -0.161282 0.847271 0.506083 -0.151399 0.721169 0.676013 -0.143843 0.676297 0.722449 -0.405039 0.90911 0.0972787 -0.432154 0.900309 0.0518221 0.254254 0.884245 0.391747 0.0337005 0.978875 0.201662 0.0301073 0.978972 0.201758 -0.0502665 0.978521 0.199924 -0.105326 0.967908 0.228168 0.202557 0.148174 0.967995 0.122476 0.164059 0.978818 0.266997 0.239084 0.933569 0.289786 0.703844 0.648558 0.339951 0.891859 0.298363 0.668876 0.683012 0.293427 0.668346 0.685019 0.289934 0.814929 0.494666 0.301987 0.913895 0.280464 0.293489 0.937193 0.257102 0.235728 0.846408 0.259762 0.464884 0.668299 0.205101 0.71506 0.512228 0.469255 0.719321 0.453593 0.463179 0.761393 0.28268 0.707236 0.648004 0.758077 0.179876 0.626868 0.576284 0.176851 0.797885 0.246233 0.0755646 0.96626 0.425137 0.0637434 0.902882 0.185665 0.0569819 0.98096 0.961565 0.0947042 0.257729 0.961568 0.0947077 0.257714 0.924617 0.280479 0.257713 0.924625 0.280491 0.25767 0.85214 0.455481 0.25767 0.852138 0.455476 0.257687 0.746906 0.612969 0.257684 0.746903 0.612959 0.257715 0.612965 0.746901 0.257706 0.612965 0.746905 0.257695 0.455482 0.852134 0.257688 0.45548 0.852144 0.257659 0.280481 0.92463 0.257663 0.280481 0.92463 0.257664 0.0947081 0.961581 0.257667 0.0947072 0.961582 0.257662 -0.0947082 0.961582 0.257662 -0.0947071 0.961581 0.257667 -0.280486 0.924628 0.257663 -0.280479 0.924623 0.257689 -0.455473 0.852135 0.257702 -0.455477 0.852137 0.257688 -0.612967 0.746903 0.257695 -0.612982 0.746907 0.257649 -0.746913 0.612976 0.257646 -0.746901 0.612975 0.257683 -0.852136 0.455479 0.257687 -0.852142 0.455478 0.25767 -0.924628 0.280482 0.257669 -0.924641 0.280477 0.257627 -0.961592 0.0947069 0.257625 -0.961588 0.0947096 0.25764 0.705422 0.0694711 0.705374 0.705442 0.0694787 0.705355 0.67833 0.205774 0.705355 0.678316 0.205765 0.705371 0.625139 0.334145 0.705371 0.62514 0.334146 0.70537 0.547943 0.449678 0.705371 0.547954 0.449694 0.705352 0.449687 0.547954 0.705356 0.449679 0.547936 0.705375 0.334146 0.625134 0.705375 0.334145 0.625133 0.705376 0.205761 0.678311 0.705377 0.205761 0.67831 0.705378 0.0694768 0.705422 0.705374 0.0694779 0.705416 0.70538 -0.0694762 0.705416 0.70538 -0.0694784 0.705422 0.705374 -0.205765 0.678309 0.705378 -0.205765 0.67831 0.705377 -0.334139 0.625136 0.705377 -0.33414 0.625137 0.705375 -0.449682 0.547934 0.705375 -0.449672 0.547927 0.705387 -0.547922 0.449675 0.705389 -0.54794 0.449682 0.705371 -0.62514 0.334146 0.70537 -0.625139 0.334146 0.705371 -0.678315 0.205769 0.705371 -0.678331 0.205769 0.705355 -0.705442 0.0694731 0.705354 -0.705422 0.0694768 0.705374 0.258719 0.0254812 0.965616 0.258709 0.0254781 0.965619 0.248767 0.0754634 0.965619 0.24877 0.0754652 0.965618 0.229268 0.122548 0.965618 0.229264 0.122545 0.965619 0.200954 0.164916 0.965619 0.200955 0.164917 0.965619 0.164918 0.200954 0.965619 0.164922 0.200962 0.965616 0.122547 0.229273 0.965617 0.122542 0.229258 0.965621 0.0754628 0.248762 0.96562 0.0754636 0.248773 0.965618 0.0254808 0.258711 0.965619 0.0254806 0.258713 0.965618 -0.0254816 0.258713 0.965618 -0.0254802 0.258709 0.965619 -0.0754623 0.248766 0.965619 -0.0754641 0.248769 0.965618 -0.122545 0.229269 0.965618 -0.122548 0.229273 0.965617 -0.164927 0.200959 0.965616 -0.164919 0.200953 0.965619 -0.200952 0.164919 0.965619 -0.200952 0.164919 0.965619 -0.229264 0.122546 0.965619 -0.229268 0.122547 0.965618 -0.24877 0.0754645 0.965618 -0.248767 0.0754642 0.965619 -0.258709 0.0254802 0.965619 -0.258719 0.0254791 0.965617 -0.22568 0.868321 0.441688 -0.445805 0.893251 0.0579721 -0.433355 0.899501 0.0556918 -0.443341 0.895867 0.0295243 -0.445316 0.894457 0.0404984 -0.441045 0.897381 0.0136849 -0.444862 0.895328 0.0220394 -0.441455 0.896972 0.0236443 -0.438311 0.8988 0.00645102 0.164269 0.824403 0.541642 -0.0474752 0.975012 0.217019 -0.046825 0.976794 0.209001 -0.118865 0.944638 0.305829 -0.145184 0.981922 0.121454 -0.223625 0.947309 0.229341 -0.26101 0.963884 0.05292 -0.322444 0.937542 0.13056 -0.327091 0.943095 0.0598667 -0.369186 0.923267 0.106207 -0.373586 0.926368 0.0477102 -0.411699 0.908596 0.0704087 -0.409686 0.91053 0.055605 -0.431993 0.899934 0.0591731 0.29486 0.685839 0.665344 0.148132 0.626058 0.765577 0.32463 0.409366 0.852664 0.260589 0.442345 0.858152 0.12002 0.394328 0.911099 0.0238357 0.211424 0.977104 -0.00577365 0.458066 0.888899 -0.444543 0.894784 0.0417521 -0.433486 0.900072 0.0442796 -0.433115 0.900299 0.0432735 -0.415764 0.908571 0.0404779 -0.417089 0.907499 0.0498165 -0.390261 0.920081 0.0338858 -0.385279 0.919724 0.0752811 -0.356885 0.933112 0.04399 -0.351244 0.931756 0.0919666 -0.312126 0.949093 0.0424178 -0.277978 0.947275 0.15937 -0.229196 0.968993 0.0923129 -0.202877 0.955188 0.215537 -0.106815 0.990466 0.0869893 0.0738626 0.835919 0.543861 0.0706539 0.834665 0.546207 0.0543983 0.694259 0.717667 -0.0901048 0.639969 0.7631 -0.0995005 0.604596 0.790293 -0.441447 0.896951 0.0245557 -0.433129 0.900943 0.026468 -0.432505 0.901283 0.0250695 -0.421622 0.906472 0.0233348 -0.422699 0.905753 0.0306168 -0.406141 0.913574 0.020763 -0.401995 0.914591 0.0438519 -0.385738 0.922243 0.0259553 -0.380717 0.923134 0.0536441 -0.359487 0.932768 0.0266989 -0.333882 0.938067 0.0924802 -0.30792 0.949714 0.0568286 -0.287545 0.949334 0.126816 -0.238534 0.969181 0.0615617 -0.101828 0.935734 0.337687 -0.115646 0.930423 0.347762 -0.111905 0.876293 0.468603 -0.171704 0.855336 0.488792 -0.216151 0.763464 0.608606 -0.437333 0.899244 0.00996427 -0.438113 0.89887 0.00946875 -0.436044 0.899896 0.00725259 -0.432293 0.901697 0.00812032 -0.432808 0.901441 0.0090571 -0.42769 0.903888 0.00823379 -0.427883 0.903784 0.00949527 -0.421395 0.90686 0.0056382 -0.419077 0.907834 0.0145765 -0.41267 0.91085 0.00751753 -0.410003 0.911913 0.0176854 -0.401976 0.91562 0.007464 -0.390633 0.92007 0.0296224 -0.380808 0.924514 0.0161228 -0.371406 0.927568 0.0409325 -0.349522 0.936854 0.0117957 -0.288301 0.950309 0.117457 -0.279587 0.953665 0.111145 -0.275426 0.947038 0.165105 -0.276999 0.946487 0.165632 -0.28531 0.938368 0.1951 -0.980798 0 0.195027 -0.965929 0.00151212 0.258803 -0.896807 0 0.442422 -0.793423 0 0.608671 -0.707129 0.0020188 0.707081 -0.1951 0 0.980783 -0.258803 0.00151032 0.965929 -0.442194 0 0.896919 -0.608731 0 0.793377 -0.0198852 0.258786 0.96573 -0.0446153 0.190491 0.980675 -0.0513518 0.253955 0.965852 -0.101115 0.431718 0.896323 -0.139083 0.593823 0.792484 -0.15127 0.691441 0.706418 -0.181109 0.773275 0.607656 -0.204651 0.873795 0.441136 -0.212807 0.942349 0.258246 -0.223683 0.955046 0.19456 -0.0198848 0.258791 0.965729 -0.0467258 0.608112 0.792475 -0.0645813 0.704837 0.706423 -0.0608461 0.791871 0.607649 -0.0740165 0.963277 0.258107 -0.0740177 0.963274 0.258116 -0.188435 0.00457317 0.982075 -0.195083 0.0130594 0.9807 -0.428212 0.00797834 0.903643 -0.44215 0.0141188 0.89683 -0.591071 0.00738282 0.806586 -0.608533 0.025503 0.793119 -0.773945 0.00825236 0.633199 -0.792976 0.0335466 0.608329 -0.879203 0.0156872 0.47619 -0.896447 0.0283456 0.442244 -0.970554 -0.000659676 0.240884 -0.979218 0.0567316 0.194713 0 0.195094 0.980785 -0.00186777 0.258842 0.965918 0.00124906 0.555595 0.831452 0 0.608777 0.793341 0 0.831467 0.555574 0.00186769 0.79334 0.608776 -0.00247701 0.98078 0.195099 0 0.965924 0.258826 -0.289805 0.703907 0.648481 -0.536234 0.547567 0.642358 -0.322152 0.442384 0.836968 -0.512228 0.469255 0.719321 -0.266997 0.239084 0.933569 -0.175272 0.1918 0.965657 -0.121773 0.0890792 0.988553 0.43262 0.900131 0.0510213 0.405039 0.90911 0.0972787 0.143843 0.676297 0.722449 0.151422 0.721306 0.675861 0.161294 0.847283 0.506059 0.15315 0.925904 0.345322 -0.846408 0.259762 0.464884 0.105344 0.967904 0.228177 0.0502665 0.978521 0.199924 -0.0301073 0.978972 0.201758 -0.0337005 0.978875 0.201662 -0.254254 0.884245 0.391747 -0.339951 0.891859 0.298362 -0.667575 0.684229 0.293554 -0.669589 0.68374 0.290087 -0.812135 0.499289 0.301908 -0.920721 0.259163 0.291731 -0.929434 0.285184 0.234142 -0.748901 0.229838 0.621548 -0.679471 0.179906 0.711304 -0.576372 0.176878 0.797816 -0.419845 0.128843 0.898404 -0.255709 0.0592891 0.964934 -0.185665 0.0569754 0.98096 0.0149896 0.195072 0.980674 0.0149883 0.195066 0.980676 0.0426516 0.55509 0.830696 0.0426534 0.555099 0.83069 0.0637595 0.829775 0.554443 0.0637594 0.829775 0.554444 0.0751497 0.97801 0.194548 0.07515 0.97801 0.194546 0.0446133 0.190482 0.980676 0.0446145 0.190485 0.980676 0.126961 0.542073 0.830685 0.126954 0.542054 0.830699 0.189778 0.810292 0.554447 0.189785 0.810307 0.554423 0.223685 0.955049 0.194544 0.223683 0.955046 0.19456 -0.288062 0.683316 0.670894 0.433117 0.900986 0.0251878 0.438311 0.8988 0.00645102 0.443724 0.895318 0.0389129 0.437027 0.899391 0.0101587 0.445286 0.89343 0.0591807 0.433338 0.89943 0.0569573 0.432441 0.899714 0.0592448 0.413332 0.908845 0.0561877 0.408454 0.910293 0.0673138 0.384971 0.921384 0.0533715 0.362316 0.926747 0.0993297 0.34353 0.935852 0.0785403 0.310731 0.943387 0.116045 0.290696 0.952521 0.0905524 0.207566 0.955996 0.207336 0.186635 0.966084 0.178463 0.090053 0.959375 0.267378 0.437305 0.899275 0.00826094 0.43207 0.90179 0.00945642 0.432897 0.90141 0.00777466 0.429185 0.903188 0.00718843 0.427469 0.903983 0.00924841 0.424167 0.905555 0.00728416 0.417695 0.908494 0.0130504 0.415923 0.909332 0.0110959 0.407967 0.912882 0.014433 0.407569 0.913068 0.0139254 0.38793 0.921335 0.0255283 0.388206 0.921208 0.0259089 0.366281 0.929881 0.0340502 0.364658 0.930596 0.0318784 0.28017 0.953445 0.111567 0.432614 0.901193 0.0263816 0.423978 0.905328 0.0249786 0.420985 0.906585 0.0295921 0.412041 0.910842 0.0242627 0.398455 0.916281 0.0407689 0.393554 0.918622 0.0353511 0.37533 0.925711 0.0467549 0.373249 0.926682 0.0441038 0.326484 0.941618 0.0822432 0.32632 0.941694 0.0820168 0.274553 0.955335 0.109341 0.278222 0.953696 0.114262 0.0820536 0.942788 0.323139 0.436631 0.899554 0.0124746 0.438879 0.898501 0.00898149 0.445681 0.894875 0.0238424 0.441437 0.896921 0.0258202 0.441432 0.896909 0.0262947 0.442156 0.896641 0.0230821 0.445499 0.894319 0.0415325 0.432595 0.900491 0.0444823 0.433504 0.90017 0.042037 0.419248 0.907 0.0397819 0.41426 0.908823 0.0492849 0.398742 0.91619 0.0400112 0.380447 0.922218 0.0691014 0.369815 0.927332 0.0573752 0.342603 0.935991 0.0808903 0.333962 0.939992 0.0698902 0.266244 0.953226 0.143089 0.259011 0.956659 0.133102 0.182022 0.965252 0.187499 0.173358 0.969028 0.175872 -0.104601 0.847211 0.520857 -0.294924 0.685732 0.665426 -0.0521631 0.905619 0.420872 0.0314264 0.999175 0.0257356 0.046825 0.976794 0.209001 -0.260589 0.442345 0.858152 -0.186585 0.476833 0.858963 -0.120241 0.713151 0.690621 0.00706296 0.800058 0.599881 0.072732 0.887842 0.454364 0.159296 0.911557 0.379064 0.259865 0.952324 0.159841 0.29627 0.94712 0.123239 -0.122445 0.239743 0.963084 -0.00765266 0.3498 0.936793 0.0204288 0.569506 0.821733 0.107027 0.632472 0.767153 0.159931 0.81764 0.55307 0.210884 0.839361 0.501 0.272753 0.942104 0.195054 0.290387 0.941676 0.170065 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965924 0.258825 0 -0.965924 0.258825 0 -0.965924 -0.258826 0 -0.965924 -0.258826 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965927 -0.258814 0 0.965927 -0.258814 0 0.965927 0.258813 0 0.965927 0.258813 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.258821 0.965925 0 -0.258821 0.965925 0 -0.707107 0.707107 0 -0.707107 0.707107 0 -0.965924 0.258825 0 -0.965924 0.258825 0 -0.965924 -0.258825 0 -0.965924 -0.258825 0 -0.707107 -0.707107 0 -0.707107 -0.707107 0 -0.258821 -0.965925 0 -0.258821 -0.965925 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.707107 -0.707107 0 0.707107 -0.707107 0 0.965927 -0.258813 0 0.965927 -0.258813 0 0.965927 0.258813 0 0.965927 0.258813 0 0.707107 0.707107 0 0.707107 0.707107 0 0.258818 0.965926 0 0.258818 0.965926 0 -0.939693 0 -0.34202 -0.939693 0 -0.34202 -0.183734 -0.923695 -0.336197 -0.183734 -0.923695 -0.336197 -0.523229 -0.783072 -0.336197 -0.523232 -0.78307 -0.336199 -0.783073 -0.523226 -0.3362 -0.783071 -0.523233 -0.336196 -0.923695 -0.183738 -0.336196 -0.923695 -0.183735 -0.336197 -0.923695 0.183738 -0.336197 -0.923696 0.183736 -0.336196 -0.783075 0.523227 -0.336196 -0.783069 0.523232 -0.3362 -0.523229 0.783072 -0.336199 -0.523233 0.78307 -0.336197 -0.183734 0.923695 -0.336198 -0.183734 0.923695 -0.336198 0 -0.939693 -0.34202 0 -0.939693 -0.34202 0 0.939693 -0.34202 0 0.939693 -0.34202 0.923695 -0.183738 -0.336197 0.923696 -0.183736 -0.336195 0.78307 -0.523234 -0.336196 0.783071 -0.523233 -0.336195 0.523234 -0.78307 -0.336196 0.523233 -0.78307 -0.336197 0.183734 -0.923695 -0.336197 0.183734 -0.923695 -0.336197 0.183734 0.923695 -0.336198 0.183734 0.923695 -0.336198 0.523234 0.78307 -0.336197 0.523233 0.783071 -0.336196 0.783071 0.523233 -0.336196 0.783071 0.523233 -0.336196 0.923695 0.183738 -0.336196 0.923695 0.183735 -0.336197 0.939693 0 -0.34202 0.939693 0 -0.34202 -0.939693 0 -0.34202 -0.939693 0 -0.34202 -0.183734 -0.923695 -0.336198 -0.183733 -0.923696 -0.336197 -0.523234 -0.78307 -0.336197 -0.523233 -0.783071 -0.336196 -0.783071 -0.523233 -0.336195 -0.783071 -0.523233 -0.336196 -0.923695 -0.183738 -0.336196 -0.923695 -0.183735 -0.336197 -0.923695 0.183738 -0.336197 -0.923696 0.183736 -0.336195 -0.783071 0.523233 -0.336196 -0.783071 0.523233 -0.336195 -0.523234 0.78307 -0.336196 -0.523232 0.78307 -0.336197 -0.183734 0.923695 -0.336198 -0.183734 0.923695 -0.336198 0 -0.939693 -0.34202 0 -0.939693 -0.34202 0 0.939693 -0.34202 0 0.939693 -0.34202 0.923693 -0.183738 -0.336203 0.923698 -0.183724 -0.336195 0.783071 -0.523233 -0.336196 0.783071 -0.523233 -0.336195 0.523234 -0.78307 -0.336196 0.523226 -0.783073 -0.336201 0.183734 -0.923695 -0.336199 0.183735 -0.923695 -0.336198 0.183734 0.923695 -0.336198 0.183736 0.923695 -0.336199 0.523233 0.783069 -0.3362 0.523227 0.783074 -0.336196 0.783071 0.523233 -0.336195 0.783071 0.523233 -0.336196 0.923695 0.183738 -0.336196 0.923695 0.183724 -0.336203 0.939691 0 -0.342025 0.939691 0 -0.342025 -0.939691 0 -0.342025 -0.939691 0 -0.342025 -0.183734 -0.923695 -0.336198 -0.183736 -0.923695 -0.336199 -0.523233 -0.783069 -0.3362 -0.523228 -0.783074 -0.336196 -0.783071 -0.523233 -0.336195 -0.783071 -0.523233 -0.336196 -0.923695 -0.183738 -0.336196 -0.923695 -0.183724 -0.336203 -0.923693 0.183738 -0.336203 -0.923698 0.183724 -0.336195 -0.78307 0.523234 -0.336196 -0.783071 0.523233 -0.336195 -0.523234 0.78307 -0.336196 -0.523227 0.783073 -0.336201 -0.183734 0.923695 -0.336198 -0.183735 0.923695 -0.336198 0 -0.939693 -0.34202 0 -0.939693 -0.34202 0 0.939692 -0.34202 0 0.939692 -0.34202 0.923696 -0.183729 -0.336198 0.923694 -0.183735 -0.336201 0.783069 -0.523232 -0.3362 0.783069 -0.523232 -0.3362 0.523229 -0.783072 -0.336199 0.523233 -0.78307 -0.336197 0.183736 -0.923695 -0.336197 0.183736 -0.923695 -0.336197 0.183736 0.923695 -0.336198 0.183735 0.923695 -0.336197 0.523229 0.783072 -0.336197 0.523232 0.78307 -0.336199 0.783069 0.523233 -0.3362 0.783069 0.523232 -0.3362 0.923695 0.183729 -0.336201 0.923695 0.183735 -0.336197 0.939693 0 -0.34202 0.939693 0 -0.34202 0.995774 0.0918419 6.07815e-08 0.981727 0.190275 -0.00279452 0.97696 0.213413 -0.00208312 0.957794 0.287454 -0.000370524 0.920169 0.39152 0.000178481 0.817517 0.575899 -0.00228075 0.837932 0.545757 -0.00445794 0.511094 0.859523 -0.00193499 0.600418 0.799659 -0.00660746 0.504763 0.863257 -0.00126504 0.659337 0.751847 0.000174005 0.73804 0.674757 -0.000556323 0.379887 0.925033 -7.83742e-05 0.166908 0.985972 0.000236706 0.17204 0.98509 0 -0.0720111 0.997404 0 -0.0481235 0.998841 -0.000427588 -0.195131 0.980777 0.000448118 -0.214031 0.976827 0.000810997 -0.36613 0.930564 -0.000836344 -0.404839 0.914388 4.55345e-07 0.707045 -0.707168 9.57906e-05 0.806999 -0.590552 -0.00010995 0.983711 -0.17976 -9.76861e-05 0.818557 0.574426 0 0.999845 0.0149309 -0.00932726 0.986728 -0.160071 0.0272806 0.999996 -0.000469981 0.00262777 0.959366 0.282157 -0.00220312 0.956654 0.291207 -0.00334363 0.867183 0.497984 0.00234309 0.882493 0.4703 0.00490214 0.85213 0.523328 0.00163663 0.880809 -0.473258 0.0141978 0.934773 -0.355223 0.00403914 0.95891 -0.283711 0.000116387 0.81256 -0.581379 0.0417662 0.925675 -0.377497 -0.0249239 0.862711 -0.505621 -0.00875731 0.460615 -0.886722 0.0394879 0.537908 -0.842731 0.0214282 0.618475 -0.785764 0.00796922 0.647711 -0.761442 -0.0260126 0.471446 -0.881895 0.000443285 0.307987 -0.95139 -0.000194847 0.134897 -0.990809 0.0100337 0.0858671 -0.996307 -1.25666e-06 0.283155 -0.958837 -0.0213002 0.199358 -0.979875 -0.0100719 -0.246833 0.969058 1.93266e-05 -0.0588704 0.998167 -0.0140412 -0.18949 0.981868 -0.00540454 -0.450636 0.892706 0.00163962 -0.619839 0.784727 -0.00167712 -0.629067 0.77735 -0.00137999 -0.825891 0.563824 0.00274001 -0.766434 0.64232 -0.00207974 -0.910672 0.413128 0.000865881 -0.888139 0.459576 -0.000109575 -0.952677 0.303984 0.00012224 -0.954647 0.297741 0.000257536 -0.99069 0.136139 -0.000222578 -0.992329 0.123623 0 0.935987 -0.35193 -0.00858441 0.995694 -0.0927029 0 0.982953 -0.183819 0.00372331 0.987855 -0.149798 -0.0412724 0.880093 -0.472691 0.0447198 0.942408 -0.334072 0.0162197 0.503045 -0.864058 0.0187204 0.41511 -0.908959 0.0384375 0.619137 -0.785277 0.00305091 0.815016 -0.579419 -0.00472965 0.746665 -0.665042 0.0144818 0.815002 -0.579438 0.00479442 0.194907 -0.980822 6.36261e-06 0.0976689 -0.994981 0.0217607 0.578106 -0.815869 -0.0123033 0.406453 -0.91367 -0.00155549 0.305542 -0.952178 0.00143545 0.219827 -0.975521 0.00593279 0 1 0 -0.235871 0.971784 0 -0.146142 0.989244 -0.00620721 -0.328064 0.944655 -0.000986345 -0.586152 0.810199 0.00176284 -0.470212 0.88254 -0.00491475 -0.750097 0.661309 0.00495822 -0.67669 0.736268 0.000148208 -0.832408 0.554163 -4.79724e-05 -0.91618 0.400761 0.00230549 -0.870564 0.492052 -0.00184944 -0.966364 0.257178 0.000909929 -0.953304 0.302012 0 0.768247 -0.638949 -0.0392462 0.595525 -0.803214 0.0140686 0.736972 -0.675923 0.000932421 0.847134 -0.531378 -0.0013293 0.843179 -0.537632 -0.000601806 0.941485 -0.337055 0.000649388 0.92299 -0.384779 0.00590751 0.960988 -0.276589 0 0.658755 -0.752321 -0.00740195 0.473858 -0.880601 0.00124095 0.348803 -0.937192 -0.00270534 0.285225 -0.958272 -0.0190118 0.13703 -0.990427 0.0166536 0.161815 -0.986801 -0.00626254 0.0683477 -0.997662 -1.26844e-06 0.980349 0.197273 0 0.984561 0.175039 0.00115864 0.847655 0.530547 -0.00107457 0.837544 0.54637 -9.70704e-05 0.716638 0.697445 2.80107e-06 0.719542 0.694449 -8.80381e-06 0.598874 0.800843 4.69995e-05 0.60805 0.793898 -0.000409239 0.36567 0.930745 0.000356462 0.427485 0.904021 -0.00184304 0.262073 0.965048 0.000707478 0.127276 0.991867 -0.000922764 0.0794801 0.996836 0 -0.764811 -0.644254 -0.000863949 -0.0971955 -0.995263 0.00195364 -0.0326058 -0.999468 2.4198e-05 -0.596963 -0.802265 0.00264897 -0.689693 -0.723686 0.0245309 -0.605216 -0.796037 0.00619151 -0.339837 -0.940465 -0.00594323 -0.43676 -0.899526 0.00972313 -0.119157 -0.992796 -0.0125443 -0.282266 -0.959177 0.017467 -0.167144 -0.985913 0.00614875 -0.994265 -0.104335 0.0234604 -0.972457 -0.232949 -0.00788738 -0.999151 -0.0412034 0 -0.971038 -0.238864 0.00534915 -0.946387 -0.323033 0.00134058 -0.843691 -0.5368 -0.00561276 -0.907329 -0.419691 0.0247469 -0.849302 -0.527862 0.00698159 0.183662 -0.37962 0.906729 0.414866 -0.184826 -0.890913 0.152755 -0.589341 -0.793311 0.0415324 -0.986665 0.157378 0.0478972 -0.983084 0.176784 0.0934959 -0.990941 0.0964041 0.180669 -0.964528 0.192468 0.120744 -0.991991 0.0370901 0.160636 -0.985574 0.0532882 0.185455 -0.942294 -0.278725 0.109225 -0.988121 -0.108109 0.153961 -0.977266 -0.145761 0.174114 -0.9799 -0.0973691 0.128439 -0.989312 -0.069033 0.183519 -0.981019 -0.0626231 0.183435 -0.983009 -0.00665961 0.108306 -0.993612 -0.0317031 0.177497 -0.98404 0.0126803 0.0870192 -0.981014 -0.173317 0.0526905 -0.966739 -0.250279 0.0556426 -0.954398 -0.293305 0.156217 -0.420236 -0.893867 0.844845 0.0793086 -0.5291 0.8228 0.178781 -0.539478 0.750943 -0.187224 -0.633271 0.54377 -0.175959 -0.820581 0.588032 0.298547 -0.751723 0.481493 -0.0699315 -0.873656 0.463392 0.516847 0.719817 0.637953 -0.0960512 0.764061 0.792468 -0.0887984 0.603415 0.720822 0.473859 0.505838 0.165652 -0.561233 0.810911 0.165556 -0.559224 0.812318 0.473424 -0.553784 0.684977 0.472416 -0.55877 0.681615 0.705781 -0.548593 0.448239 0.702575 -0.555978 0.444159 0.827876 -0.542746 0.141593 0.822553 -0.551558 0.138532 0.822501 -0.537335 -0.186448 0.816429 -0.546246 -0.18724 0.692786 -0.533161 -0.485579 0.687893 -0.540688 -0.48421 0.460401 -0.530695 -0.711614 0.45783 -0.535703 -0.709517 0.16079 -0.530265 -0.832446 0.190665 -0.177701 -0.965437 0.190159 -0.180532 -0.965012 0.254668 -0.0953354 0.962318 0.442562 -0.09264 0.89194 0.485167 0.377173 0.788894 0.863727 0.135641 0.485363 0.767939 -0.620217 0.160001 0.976731 -0.0986596 0.190431 0.993836 -0.0890481 -0.0660398 0.0610551 -0.192983 0.979301 0.221908 0.179594 0.958386 0.189423 -0.282316 0.940434 0.539795 -0.275943 0.795284 0.538276 -0.283472 0.793664 0.805847 -0.271769 0.526072 0.80295 -0.282969 0.524594 0.94724 -0.267739 0.176219 0.943435 -0.281105 0.175815 0.960337 -0.276886 -0.0329563 0.974327 0.126871 -0.185984 0.946925 -0.190336 -0.259048 0.877791 -0.183635 -0.44245 0.110738 -0.841105 0.529415 0.110431 -0.849864 0.515303 0.312808 -0.846164 0.431459 0.311648 -0.847955 0.428774 0.465719 -0.841214 0.27471 0.46255 -0.843972 0.271587 0.545113 -0.835247 0.072211 0.54037 -0.838489 0.0702629 0.540349 -0.829126 -0.143434 0.535284 -0.832407 -0.143419 0.454166 -0.823825 -0.339182 0.450198 -0.826689 -0.337503 0.301248 -0.820158 -0.486405 0.299243 -0.822116 -0.484334 0.0992095 -0.817899 -0.566743 0.117008 -0.773906 -0.622398 -0.183679 0.379438 0.906801 -0.414868 0.184822 -0.890913 -0.152756 0.589355 -0.793301 -0.0415298 0.986668 0.15736 -0.0478994 0.983084 0.17678 -0.0934945 0.990941 0.0964065 -0.180672 0.964527 0.192474 -0.120742 0.991991 0.037086 -0.160637 0.985574 0.0532853 -0.185458 0.942292 -0.278732 -0.109225 0.988121 -0.108109 -0.153961 0.977266 -0.145761 -0.174116 0.9799 -0.0973644 -0.128453 0.98931 -0.0690357 -0.183519 0.981019 -0.0626274 -0.183435 0.983009 -0.00665711 -0.108294 0.993613 -0.0317044 -0.177495 0.98404 0.0126851 -0.087029 0.981011 -0.173331 -0.0526934 0.966731 -0.250308 -0.0556436 0.954398 -0.293305 -0.156219 0.420235 -0.893867 -0.844845 -0.0793102 -0.529099 -0.8228 -0.178785 -0.539478 -0.750942 0.187228 -0.63327 -0.543769 0.175962 -0.820581 -0.588032 -0.298547 -0.751723 -0.481493 0.0699315 -0.873656 -0.463387 -0.516861 0.71981 -0.637953 0.0960513 0.764062 -0.792468 0.0887983 0.603415 -0.720819 -0.473864 0.505838 -0.165655 0.561242 0.810905 -0.165558 0.559224 0.812317 -0.473424 0.553784 0.684977 -0.472414 0.558778 0.68161 -0.705777 0.548601 0.448236 -0.70257 0.555986 0.444155 -0.827871 0.542754 0.14159 -0.822558 0.551549 0.138535 -0.822507 0.537326 -0.186449 -0.816435 0.546237 -0.18724 -0.69279 0.533153 -0.485582 -0.687898 0.54068 -0.484213 -0.460405 0.530686 -0.711617 -0.457825 0.535711 -0.709514 -0.160792 0.530274 -0.832439 -0.190669 0.177697 -0.965437 -0.190163 0.180532 -0.965011 -0.254668 0.0953354 0.962318 -0.442563 0.09264 0.89194 -0.485164 -0.377186 0.78889 -0.863732 -0.135622 0.48536 -0.767951 0.620201 0.160005 -0.97673 0.0986596 0.190431 -0.993836 0.0890481 -0.0660406 -0.0610593 0.192983 0.9793 -0.221912 -0.179567 0.95839 -0.189427 0.282316 0.940433 -0.539795 0.275943 0.795284 -0.538278 0.283462 0.793666 -0.80585 0.271759 0.526073 -0.80295 0.282969 0.524594 -0.947239 0.267739 0.17622 -0.943435 0.281105 0.175815 -0.960337 0.276886 -0.0329586 -0.974327 -0.126873 -0.185983 -0.946925 0.190336 -0.259047 -0.87779 0.183635 -0.442451 -0.110743 0.841096 0.529428 -0.110435 0.849856 0.515315 -0.312813 0.846157 0.431471 -0.311648 0.847955 0.428774 -0.46572 0.841213 0.274709 -0.462561 0.843963 0.271594 -0.545125 0.835239 0.0722158 -0.540357 0.838497 0.0702578 -0.540336 0.829134 -0.143432 -0.535271 0.832416 -0.143417 -0.454156 0.823834 -0.339176 -0.450187 0.826697 -0.337496 -0.301241 0.820167 -0.486395 -0.299245 0.822116 -0.484333 -0.0992094 0.817899 -0.566744 -0.117014 0.77389 -0.622416 -0.93023 -0.352801 -0.101015 -0.931013 -0.310823 0.19132 -0.979059 -0.0592033 0.194776 -0.972487 0.118096 -0.200805 -0.965319 0.176908 0.191996 -0.88621 0.420494 0.194466 -0.792692 0.547146 -0.268833 -0.760091 0.620596 0.192672 -0.573404 0.795936 0.19415 -0.442148 0.842452 -0.307863 0.442148 0.842452 -0.307863 -0.366327 0.91021 0.193192 -0.118252 0.973906 0.193709 0 0.947237 -0.320534 0.118256 0.973906 0.193709 0.366327 0.91021 0.193192 0.573404 0.795936 0.19415 0.760091 0.620596 0.192672 0.792692 0.547146 -0.268833 0.88621 0.420494 0.194466 0.974699 0.118365 0.189611 0.931648 0.170737 -0.32075 0.979059 -0.0592033 0.194776 0.918043 -0.348179 0.189654 0.936403 -0.312622 -0.159428 0.828969 -0.524227 0.194929 0.651091 -0.734932 0.189618 0.67798 -0.734911 0.0157679 0.473189 -0.859105 0.195014 0.234976 -0.953328 0.189608 0.234977 -0.953326 0.18962 -0.234972 -0.953327 0.18962 -0.234974 -0.953329 0.189608 -0.473189 -0.859105 0.195014 -0.662799 -0.748148 0.0311978 -0.665649 -0.721544 0.190489 -0.828969 -0.524227 0.194929 0.200768 -0.814535 0.544266 0.556303 -0.627939 0.54426 0.556302 -0.627937 0.544264 0.784397 -0.297488 0.544264 0.784412 -0.297498 0.544236 0.832816 0.101123 0.544235 0.832757 0.101128 0.544325 0.690389 0.476535 0.544314 0.690399 0.47654 0.544297 0.389855 0.742811 0.544284 0.389848 0.742803 0.5443 0 0.838913 0.544266 0 0.838913 0.544266 -0.38985 0.742802 0.5443 -0.389853 0.742812 0.544284 -0.690398 0.476541 0.544297 -0.69039 0.476533 0.544314 -0.832759 0.101116 0.544323 -0.832815 0.101135 0.544234 -0.784413 -0.297494 0.544237 -0.784395 -0.297492 0.544264 -0.556302 -0.627938 0.544264 -0.556304 -0.627939 0.54426 -0.200765 -0.814536 0.544266 -0.200763 -0.814531 0.544274 0.200767 -0.81453 0.544273 0.135673 -0.550437 0.823779 0.37592 -0.424328 0.82379 0.375921 -0.424329 0.823789 0.530048 -0.201017 0.823797 0.530097 -0.201043 0.823759 0.562807 0.0683374 0.823759 0.562805 0.0683374 0.82376 0.466579 0.322054 0.823763 0.466586 0.322057 0.823758 0.263464 0.501995 0.823764 0.26347 0.502004 0.823757 0 0.566924 0.82377 0 0.566924 0.82377 -0.263469 0.502004 0.823757 -0.263465 0.501994 0.823765 -0.466585 0.322058 0.823758 -0.46658 0.322053 0.823763 -0.562805 0.0683372 0.82376 -0.562807 0.0683376 0.823759 -0.530098 -0.201036 0.82376 -0.530045 -0.201023 0.823798 -0.375921 -0.424328 0.823789 -0.37592 -0.424328 0.82379 -0.135669 -0.550439 0.823779 -0.135675 -0.550453 0.823768 0.135675 -0.550453 0.823768 0.0480264 -0.19485 0.979657 0.133074 -0.150209 0.979657 0.133075 -0.150212 0.979657 0.187639 -0.0711616 0.979657 0.187631 -0.0711576 0.979659 0.199207 0.02419 0.979659 0.199225 0.0241904 0.979655 0.165162 0.114004 0.979655 0.16517 0.114008 0.979653 0.0932663 0.177703 0.979655 0.0932577 0.17769 0.979658 0 0.200683 0.979656 0 0.200683 0.979656 -0.0932593 0.17769 0.979658 -0.093265 0.177704 0.979655 -0.16517 0.114009 0.979654 -0.165163 0.114003 0.979655 -0.199224 0.0241921 0.979655 -0.199207 0.0241882 0.979659 -0.18763 -0.0711585 0.979659 -0.187639 -0.0711608 0.979657 -0.133076 -0.150212 0.979657 -0.133073 -0.150209 0.979657 -0.0480256 -0.194851 0.979657 -0.048026 -0.194852 0.979656 0.0480266 -0.194852 0.979656 -0.93023 -0.352801 -0.101011 -0.931013 -0.310823 0.19132 -0.979059 -0.0592031 0.194776 -0.972487 0.118096 -0.200806 -0.965319 0.176908 0.191996 -0.88621 0.420494 0.194466 -0.792692 0.547146 -0.268833 -0.760091 0.620596 0.192672 -0.573404 0.795936 0.19415 -0.442148 0.842452 -0.307863 0.442148 0.842452 -0.307863 -0.366327 0.91021 0.193192 -0.118252 0.973906 0.193709 0 0.947237 -0.320534 0.118256 0.973906 0.193709 0.366327 0.91021 0.193192 0.573404 0.795936 0.19415 0.760091 0.620596 0.192672 0.792692 0.547146 -0.268833 0.88621 0.420494 0.194466 0.974699 0.118365 0.189611 0.931648 0.170737 -0.320752 0.979059 -0.0592031 0.194776 0.918043 -0.348179 0.189654 0.936403 -0.312623 -0.159424 0.828968 -0.524226 0.194934 0.65109 -0.734931 0.189625 0.677981 -0.73491 0.0157673 0.473189 -0.859105 0.195014 0.234976 -0.953328 0.189608 0.234977 -0.953326 0.18962 -0.234972 -0.953327 0.18962 -0.234974 -0.953329 0.189608 -0.473189 -0.859105 0.195014 -0.662799 -0.748148 0.0311978 -0.665649 -0.721543 0.190495 -0.828968 -0.524226 0.194934 0.200768 -0.814535 0.544266 0.556303 -0.627939 0.54426 0.556302 -0.627937 0.544264 0.784397 -0.297488 0.544264 0.784412 -0.297498 0.544236 0.832816 0.101123 0.544235 0.832757 0.101128 0.544325 0.690389 0.476535 0.544314 0.690399 0.47654 0.544297 0.389855 0.742811 0.544284 0.389848 0.742803 0.5443 0 0.838913 0.544266 0 0.838913 0.544266 -0.38985 0.742802 0.5443 -0.389853 0.742812 0.544284 -0.690398 0.476541 0.544297 -0.69039 0.476533 0.544314 -0.832759 0.101116 0.544323 -0.832815 0.101135 0.544234 -0.784413 -0.297494 0.544237 -0.784395 -0.297492 0.544264 -0.556302 -0.627938 0.544264 -0.556304 -0.627939 0.54426 -0.200765 -0.814536 0.544266 -0.200763 -0.814531 0.544274 0.200767 -0.81453 0.544273 0.135673 -0.550437 0.823779 0.37592 -0.424328 0.82379 0.375921 -0.424329 0.823789 0.530048 -0.201017 0.823797 0.530097 -0.201043 0.823759 0.562807 0.0683374 0.823759 0.562805 0.0683374 0.82376 0.466579 0.322054 0.823763 0.466586 0.322057 0.823758 0.263464 0.501995 0.823765 0.263468 0.502 0.82376 0 0.56692 0.823773 0 0.56692 0.823773 -0.263468 0.502001 0.82376 -0.263465 0.501994 0.823765 -0.466585 0.322058 0.823758 -0.46658 0.322053 0.823763 -0.562805 0.0683372 0.82376 -0.562807 0.0683376 0.823759 -0.530098 -0.201036 0.82376 -0.530045 -0.201023 0.823798 -0.375921 -0.424328 0.823789 -0.37592 -0.424328 0.82379 -0.135669 -0.550439 0.823779 -0.135675 -0.550453 0.823768 0.135675 -0.550453 0.823768 0.0480264 -0.19485 0.979657 0.133074 -0.150209 0.979657 0.133075 -0.150212 0.979657 0.187639 -0.0711616 0.979657 0.187631 -0.0711576 0.979659 0.199207 0.02419 0.979659 0.199225 0.0241904 0.979655 0.165162 0.114004 0.979655 0.16517 0.114008 0.979653 0.0932663 0.177703 0.979655 0.0932587 0.177691 0.979657 0 0.200685 0.979656 0 0.200685 0.979656 -0.0932601 0.177691 0.979657 -0.0932652 0.177704 0.979655 -0.16517 0.114009 0.979654 -0.165163 0.114003 0.979655 -0.199224 0.0241921 0.979655 -0.199207 0.0241882 0.979659 -0.18763 -0.0711585 0.979659 -0.187639 -0.0711608 0.979657 -0.133076 -0.150212 0.979657 -0.133073 -0.150209 0.979657 -0.0480256 -0.194851 0.979657 -0.048026 -0.194852 0.979656 0.0480266 -0.194852 0.979656 -0.930233 0.352785 0.101043 -0.931038 0.310831 -0.191188 -0.979087 0.059205 -0.194637 -0.972465 -0.118076 0.200922 -0.965318 -0.176907 -0.192003 -0.886208 -0.420494 -0.194473 -0.792689 -0.547145 0.268842 -0.76009 -0.620595 -0.192679 -0.573404 -0.795934 -0.194157 -0.442146 -0.842449 0.307873 0.442157 -0.842453 0.307847 -0.366326 -0.910208 -0.193199 -0.118251 -0.973905 -0.193717 0 -0.947233 0.320545 0.118255 -0.973901 -0.193734 0.366322 -0.910198 -0.193254 0.573404 -0.795934 -0.194157 0.76009 -0.620595 -0.192679 0.792699 -0.547168 0.268766 0.886189 -0.420536 -0.194472 0.9747 -0.118348 -0.189617 0.931663 -0.170717 0.320718 0.979058 0.0592032 -0.194784 0.918041 0.348179 -0.189662 0.936402 0.312622 0.159434 0.828968 0.524226 -0.194936 0.651099 0.734924 -0.189626 0.677979 0.73491 -0.0158741 0.473182 0.859091 -0.195092 0.234974 0.953321 -0.18965 0.234973 0.953325 -0.189628 -0.234971 0.953326 -0.189628 -0.234973 0.953328 -0.189615 -0.473189 0.859104 -0.195021 -0.662799 0.748147 -0.031199 -0.665648 0.721543 -0.190496 -0.828968 0.524226 -0.194936 0.200767 0.814547 -0.544248 0.556318 0.627942 -0.544242 0.556314 0.627936 -0.544252 0.784406 0.297491 -0.544248 0.784422 0.297502 -0.544219 0.832827 -0.101124 -0.544218 0.83284 -0.101123 -0.544198 0.690446 -0.476575 -0.544207 0.690401 -0.476556 -0.544281 0.38986 -0.742821 -0.544266 0.389875 -0.742839 -0.544231 0 -0.838924 -0.544249 0 -0.838924 -0.544249 -0.389862 -0.742809 -0.544281 -0.389874 -0.742851 -0.544216 -0.690447 -0.47659 -0.544192 -0.690399 -0.47654 -0.544297 -0.832771 -0.101117 -0.544306 -0.832758 -0.101113 -0.544325 -0.784362 0.297475 -0.544321 -0.78441 0.297483 -0.544247 -0.556307 0.627944 -0.544251 -0.556311 0.627948 -0.544243 -0.200768 0.814547 -0.544248 -0.200766 0.814542 -0.544256 0.200767 0.814542 -0.544256 0.135669 0.550429 -0.823785 0.375934 0.424344 -0.823775 0.375909 0.424307 -0.823806 0.530025 0.201008 -0.823814 0.530072 0.201034 -0.823777 0.56278 -0.0683342 -0.823777 0.562779 -0.0683342 -0.823778 0.466557 -0.322039 -0.823781 0.466564 -0.322042 -0.823776 0.263455 -0.501969 -0.823783 0.263442 -0.501951 -0.823798 0 -0.566898 -0.823788 0 -0.566898 -0.823788 -0.263457 -0.501981 -0.823775 -0.263441 -0.501938 -0.823807 -0.466514 -0.322009 -0.823817 -0.466554 -0.322045 -0.82378 -0.562779 -0.068334 -0.823778 -0.56278 -0.0683344 -0.823777 -0.530072 0.201035 -0.823777 -0.530085 0.201039 -0.823768 -0.375941 0.424343 -0.823773 -0.375902 0.424308 -0.823808 -0.135663 0.550413 -0.823797 -0.135668 0.550427 -0.823786 0.135669 0.550427 -0.823786 0.0480354 0.194887 -0.979649 0.133099 0.150238 -0.97965 0.1331 0.15024 -0.979649 0.187674 0.071175 -0.979649 0.187666 0.071171 -0.979651 0.199244 -0.0241946 -0.979651 0.199262 -0.0241949 -0.979648 0.165194 -0.114023 -0.979648 0.165181 -0.114015 -0.979651 0.093276 -0.177724 -0.97965 0.0932835 -0.177736 -0.979647 0 -0.200721 -0.979648 0 -0.200721 -0.979649 -0.0932769 -0.177723 -0.97965 -0.0932826 -0.177737 -0.979647 -0.165201 -0.11403 -0.979646 -0.165194 -0.114024 -0.979648 -0.199263 -0.0241937 -0.979647 -0.199275 -0.0241964 -0.979645 -0.187693 0.0711821 -0.979645 -0.187673 0.0711768 -0.979649 -0.133101 0.15024 -0.979649 -0.133114 0.150252 -0.979645 -0.0480371 0.194894 -0.979647 -0.048035 0.194888 -0.979649 0.0480357 0.194888 -0.979648 -0.930233 0.352785 0.101043 -0.931038 0.310831 -0.191188 -0.979087 0.059205 -0.194637 -0.972465 -0.118076 0.200922 -0.965318 -0.176907 -0.192003 -0.886208 -0.420494 -0.194473 -0.792689 -0.547145 0.268842 -0.76009 -0.620595 -0.192679 -0.573404 -0.795934 -0.194157 -0.442146 -0.842449 0.307873 0.442157 -0.842453 0.307847 -0.366326 -0.910208 -0.193199 -0.118251 -0.973905 -0.193717 0 -0.947233 0.320545 0.118255 -0.973901 -0.193734 0.366322 -0.910198 -0.193254 0.573404 -0.795934 -0.194157 0.76009 -0.620595 -0.192679 0.792699 -0.547168 0.268766 0.886189 -0.420536 -0.194472 0.9747 -0.118348 -0.189617 0.931663 -0.170717 0.320718 0.979058 0.0592032 -0.194784 0.918041 0.348179 -0.189662 0.936402 0.312622 0.159434 0.828968 0.524226 -0.194936 0.651099 0.734924 -0.189626 0.677979 0.73491 -0.0158741 0.473182 0.859091 -0.195092 0.234974 0.953321 -0.18965 0.234973 0.953325 -0.189628 -0.234971 0.953326 -0.189628 -0.234973 0.953328 -0.189615 -0.473189 0.859104 -0.195021 -0.662799 0.748147 -0.031199 -0.665648 0.721543 -0.190496 -0.828968 0.524226 -0.194936 0.200767 0.814547 -0.544248 0.556318 0.627942 -0.544242 0.556316 0.627939 -0.544247 0.784407 0.297492 -0.544246 0.784422 0.297502 -0.544219 0.832827 -0.101124 -0.544218 0.83284 -0.101123 -0.544198 0.690446 -0.476575 -0.544207 0.690401 -0.476556 -0.544281 0.38986 -0.742821 -0.544266 0.389875 -0.742839 -0.544231 0 -0.838924 -0.544249 0 -0.838924 -0.544249 -0.389862 -0.742809 -0.544281 -0.389874 -0.742851 -0.544216 -0.690447 -0.47659 -0.544192 -0.690399 -0.47654 -0.544297 -0.832771 -0.101117 -0.544306 -0.832758 -0.101113 -0.544325 -0.784362 0.297475 -0.544321 -0.784412 0.297483 -0.544245 -0.556309 0.627946 -0.544246 -0.556311 0.627948 -0.544243 -0.200768 0.814547 -0.544248 -0.200766 0.814542 -0.544256 0.200767 0.814542 -0.544256 0.135669 0.550429 -0.823785 0.375934 0.424344 -0.823775 0.375907 0.424304 -0.823808 0.530024 0.201008 -0.823815 0.530072 0.201034 -0.823777 0.56278 -0.0683342 -0.823777 0.562779 -0.0683342 -0.823778 0.466557 -0.322039 -0.823781 0.466564 -0.322042 -0.823776 0.263455 -0.501969 -0.823783 0.263442 -0.501951 -0.823798 0 -0.566898 -0.823788 0 -0.566898 -0.823788 -0.263457 -0.501981 -0.823775 -0.263441 -0.501938 -0.823807 -0.466514 -0.322009 -0.823817 -0.466554 -0.322045 -0.82378 -0.562779 -0.068334 -0.823778 -0.56278 -0.0683344 -0.823777 -0.530072 0.201035 -0.823777 -0.530084 0.201038 -0.823769 -0.375939 0.42434 -0.823775 -0.375902 0.424308 -0.823808 -0.135663 0.550413 -0.823797 -0.135668 0.550427 -0.823786 0.135669 0.550427 -0.823786 0.0480354 0.194887 -0.979649 0.133099 0.150238 -0.97965 0.1331 0.15024 -0.979649 0.187674 0.071175 -0.979649 0.187666 0.071171 -0.979651 0.199244 -0.0241946 -0.979651 0.199262 -0.0241949 -0.979648 0.165194 -0.114023 -0.979648 0.165181 -0.114015 -0.979651 0.093276 -0.177724 -0.97965 0.0932835 -0.177736 -0.979647 0 -0.200721 -0.979648 0 -0.200721 -0.979649 -0.0932769 -0.177723 -0.97965 -0.0932826 -0.177737 -0.979647 -0.165201 -0.11403 -0.979646 -0.165194 -0.114024 -0.979648 -0.199263 -0.0241937 -0.979647 -0.199275 -0.0241964 -0.979645 -0.187693 0.0711821 -0.979645 -0.187673 0.0711768 -0.979649 -0.133101 0.15024 -0.979649 -0.133114 0.150252 -0.979645 -0.0480371 0.194894 -0.979647 -0.048035 0.194888 -0.979649 0.0480357 0.194888 -0.979648 0.0691864 -0.258204 -0.96361 0.189021 -0.189022 -0.963609 0.189012 -0.189015 -0.963612 0.258196 -0.0691808 -0.963612 0.258191 -0.0691803 -0.963614 0.258191 0.0691795 -0.963614 0.258196 0.0691817 -0.963612 0.189013 0.189013 -0.963612 0.189019 0.189023 -0.963609 0.0691862 0.258204 -0.96361 0.0691862 0.258203 -0.96361 -0.0691846 0.258203 -0.96361 -0.0691852 0.258205 -0.96361 -0.189025 0.18902 -0.963608 -0.189014 0.189012 -0.963612 -0.258193 0.0691857 -0.963613 -0.258191 0.0691855 -0.963614 -0.258191 -0.069185 -0.963614 -0.258193 -0.069186 -0.963613 -0.189015 -0.18901 -0.963612 -0.189023 -0.189021 -0.963609 -0.0691846 -0.258205 -0.96361 -0.0691843 -0.258202 -0.963611 0.0691853 -0.258202 -0.963611 0.186157 -0.694744 -0.694749 0.508598 -0.508596 -0.694736 0.508588 -0.50859 -0.694747 0.694747 -0.186161 -0.694745 0.694789 -0.186161 -0.694704 0.694787 0.186172 -0.694702 0.694751 0.186151 -0.694744 0.50859 0.508588 -0.694748 0.508595 0.508597 -0.694737 0.186156 0.694744 -0.694749 0.186156 0.694736 -0.694757 -0.186154 0.694736 -0.694758 -0.18615 0.694731 -0.694764 -0.508569 0.508566 -0.694779 -0.508595 0.508582 -0.694749 -0.694747 0.186161 -0.694745 -0.694732 0.186161 -0.69476 -0.694732 -0.186157 -0.694761 -0.694745 -0.186164 -0.694746 -0.50859 -0.508588 -0.694748 -0.508575 -0.508562 -0.694778 -0.186152 -0.69473 -0.694765 -0.186152 -0.69474 -0.694754 0.186155 -0.69474 -0.694754 0.250563 -0.935114 -0.250561 0.684554 -0.684545 -0.250567 0.684546 -0.684544 -0.250592 0.935101 -0.250568 -0.250603 0.935106 -0.250566 -0.250588 0.935105 0.25057 -0.250587 0.935102 0.250565 -0.250603 0.68455 0.68454 -0.250592 0.684551 0.684548 -0.250568 0.250564 0.935114 -0.250561 0.250563 0.935115 -0.250555 -0.250564 0.935115 -0.250555 -0.250563 0.935114 -0.250561 -0.684543 0.684556 -0.250569 -0.68456 0.684558 -0.250515 -0.935133 0.250555 -0.250497 -0.935106 0.250567 -0.250588 -0.93511 -0.250548 -0.250589 -0.935128 -0.250572 -0.250499 -0.684553 -0.684565 -0.250515 -0.684551 -0.684548 -0.250568 -0.250564 -0.935114 -0.250561 -0.250563 -0.935115 -0.250555 0.250564 -0.935115 -0.250555 0.0691864 -0.258204 -0.96361 0.189021 -0.189022 -0.963609 0.189012 -0.189015 -0.963612 0.258196 -0.0691808 -0.963612 0.258191 -0.0691803 -0.963614 0.258191 0.0691795 -0.963614 0.258196 0.0691817 -0.963612 0.189013 0.189013 -0.963612 0.189019 0.189023 -0.963609 0.0691862 0.258204 -0.96361 0.0691862 0.258203 -0.96361 -0.0691846 0.258203 -0.96361 -0.0691852 0.258205 -0.96361 -0.189025 0.18902 -0.963608 -0.189014 0.189012 -0.963612 -0.258193 0.0691857 -0.963613 -0.258191 0.0691855 -0.963614 -0.258191 -0.069185 -0.963614 -0.258193 -0.069186 -0.963613 -0.189015 -0.18901 -0.963612 -0.189023 -0.189021 -0.963609 -0.0691846 -0.258205 -0.96361 -0.0691843 -0.258202 -0.963611 0.0691853 -0.258202 -0.963611 0.186157 -0.694744 -0.694749 0.508598 -0.508596 -0.694736 0.508588 -0.50859 -0.694747 0.694747 -0.186161 -0.694745 0.694789 -0.186161 -0.694704 0.694787 0.186172 -0.694702 0.694751 0.186151 -0.694744 0.508591 0.508588 -0.694748 0.508597 0.508599 -0.694734 0.186156 0.694748 -0.694745 0.186156 0.694736 -0.694757 -0.186153 0.694737 -0.694758 -0.186151 0.694734 -0.694761 -0.508571 0.508568 -0.694776 -0.508595 0.508582 -0.694749 -0.694747 0.186161 -0.694745 -0.694732 0.186161 -0.69476 -0.694732 -0.186157 -0.694761 -0.694745 -0.186164 -0.694746 -0.50859 -0.508588 -0.694748 -0.508575 -0.508562 -0.694778 -0.186152 -0.69473 -0.694765 -0.186152 -0.69474 -0.694754 0.186155 -0.69474 -0.694754 0.250563 -0.935114 -0.250561 0.684554 -0.684545 -0.250567 0.684546 -0.684544 -0.250592 0.935101 -0.250568 -0.250603 0.935106 -0.250566 -0.250588 0.935105 0.25057 -0.250587 0.935102 0.250565 -0.250603 0.68455 0.68454 -0.250592 0.684551 0.684547 -0.250573 0.250563 0.935112 -0.250567 0.250562 0.935115 -0.250555 -0.250564 0.935115 -0.250555 -0.250561 0.935113 -0.250567 -0.684542 0.684555 -0.250573 -0.684561 0.684557 -0.250515 -0.935133 0.250555 -0.250497 -0.935106 0.250567 -0.250588 -0.93511 -0.250548 -0.250589 -0.935128 -0.250572 -0.250499 -0.684553 -0.684565 -0.250515 -0.684551 -0.684548 -0.250568 -0.250564 -0.935114 -0.250561 -0.250563 -0.935115 -0.250555 0.250564 -0.935115 -0.250555 0.0691864 0.258204 0.96361 0.189021 0.189022 0.963609 0.189029 0.189027 0.963606 0.258225 0.0691885 0.963604 0.258191 0.0691855 0.963614 0.258191 -0.0691794 0.963614 0.258222 -0.0691937 0.963605 0.189028 -0.189029 0.963606 0.189023 -0.189021 0.963609 0.0691859 -0.258204 0.96361 0.0691857 -0.258202 0.963611 -0.0691838 -0.258202 0.963611 -0.0691852 -0.258205 0.96361 -0.189021 -0.189022 0.963609 -0.189029 -0.189027 0.963606 -0.258225 -0.0691884 0.963604 -0.258191 -0.0691854 0.963614 -0.258191 0.0691795 0.963614 -0.258222 0.0691938 0.963605 -0.189028 0.189029 0.963606 -0.189023 0.189021 0.963609 -0.069185 0.258205 0.96361 -0.0691848 0.258203 0.96361 0.0691861 0.258203 0.96361 0.186159 0.694746 0.694747 0.508572 0.508585 0.694763 0.508599 0.5086 0.694732 0.694766 0.18615 0.694729 0.694748 0.18615 0.694747 0.694748 -0.186145 0.694748 0.694764 -0.186154 0.694729 0.508593 -0.508607 0.694731 0.508576 -0.508578 0.694765 0.18616 -0.694742 0.694751 0.18616 -0.694753 0.694739 -0.186158 -0.694753 0.694739 -0.186153 -0.694744 0.69475 -0.508569 -0.508583 0.694766 -0.508599 -0.5086 0.694732 -0.694766 -0.18615 0.694729 -0.694748 -0.18615 0.694747 -0.694748 0.186145 0.694748 -0.694764 0.186155 0.694729 -0.508594 0.508607 0.694731 -0.508578 0.50858 0.694762 -0.186156 0.694747 0.694746 -0.186156 0.69475 0.694743 0.186161 0.69475 0.694743 0.250568 0.935116 0.250546 0.684566 0.684556 0.250503 0.684535 0.684553 0.250598 0.935099 0.250568 0.25061 0.935135 0.250553 0.250492 0.935129 -0.250576 0.25049 0.935106 -0.250545 0.250609 0.684549 -0.684539 0.250599 0.684552 -0.684571 0.250499 0.250565 -0.935119 0.25054 0.250568 -0.935112 0.250562 -0.250558 -0.935115 0.250563 -0.250564 -0.935119 0.25054 -0.684567 -0.684557 0.250498 -0.684534 -0.684553 0.250598 -0.935099 -0.250568 0.25061 -0.935135 -0.250552 0.250491 -0.935129 0.250576 0.25049 -0.935106 0.250545 0.250609 -0.684549 0.684539 0.250599 -0.684552 0.68457 0.250504 -0.250559 0.935119 0.250546 -0.250561 0.935114 0.250562 0.250564 0.935113 0.250562 0.0691864 0.258204 0.96361 0.189021 0.189022 0.963609 0.189029 0.189027 0.963606 0.258225 0.0691884 0.963604 0.258191 0.0691854 0.963614 0.258191 -0.0691795 0.963614 0.258222 -0.0691938 0.963605 0.189028 -0.189029 0.963606 0.189023 -0.189021 0.963609 0.0691862 -0.258204 0.96361 0.0691862 -0.258203 0.96361 -0.0691846 -0.258203 0.96361 -0.0691852 -0.258205 0.96361 -0.189021 -0.189022 0.963609 -0.189029 -0.189027 0.963606 -0.258225 -0.0691885 0.963604 -0.258191 -0.0691855 0.963614 -0.258191 0.0691794 0.963614 -0.258222 0.0691937 0.963605 -0.189028 0.189029 0.963606 -0.189023 0.189021 0.963609 -0.0691846 0.258205 0.96361 -0.0691843 0.258202 0.963611 0.0691853 0.258202 0.963611 0.186157 0.694743 0.69475 0.508569 0.508583 0.694766 0.508599 0.5086 0.694732 0.694766 0.18615 0.694729 0.694748 0.18615 0.694747 0.694748 -0.186145 0.694748 0.694764 -0.186155 0.694729 0.508593 -0.508607 0.694731 0.508576 -0.508578 0.694765 0.18616 -0.694742 0.694751 0.18616 -0.69475 0.694743 -0.186157 -0.69475 0.694743 -0.186154 -0.694744 0.69475 -0.508569 -0.508583 0.694766 -0.508599 -0.5086 0.694732 -0.694766 -0.18615 0.694729 -0.694748 -0.18615 0.694747 -0.694748 0.186145 0.694748 -0.694764 0.186154 0.694729 -0.508593 0.508607 0.694731 -0.508576 0.508578 0.694765 -0.186156 0.694744 0.69475 -0.186156 0.694754 0.69474 0.186163 0.694753 0.694739 0.250569 0.935117 0.25054 0.684567 0.684557 0.250498 0.684534 0.684553 0.250598 0.935099 0.250568 0.25061 0.935135 0.250552 0.250491 0.935129 -0.250576 0.25049 0.935106 -0.250545 0.250609 0.684549 -0.684539 0.250599 0.684552 -0.684571 0.250499 0.250565 -0.935119 0.25054 0.250568 -0.935112 0.250562 -0.250558 -0.935115 0.250563 -0.250564 -0.935119 0.25054 -0.684567 -0.684557 0.250498 -0.684534 -0.684553 0.250598 -0.935099 -0.250568 0.25061 -0.935135 -0.250553 0.250492 -0.935129 0.250576 0.25049 -0.935106 0.250545 0.250609 -0.684549 0.684539 0.250599 -0.684552 0.684571 0.250499 -0.25056 0.93512 0.250539 -0.250562 0.935113 0.250562 0.250564 0.935113 0.250562 0.935101 0.250603 -0.250568 0.684538 0.250585 -0.684554 0.684566 0.250499 -0.684558 0.250564 0.250543 -0.935118 0.250558 0.250566 -0.935114 -0.250568 0.250565 -0.935111 -0.250565 0.250543 -0.935118 -0.684554 0.250501 -0.68457 -0.68455 0.250586 -0.684542 -0.935107 0.250602 -0.250545 -0.93513 0.250487 -0.250576 -0.935136 0.250488 0.250553 -0.9351 0.250607 0.250568 -0.684535 0.250594 0.684554 -0.684569 0.25049 0.684558 -0.25057 0.25053 0.93512 -0.250561 0.250565 0.935113 0.250562 0.250565 0.935113 0.250558 0.250529 0.935124 0.684554 0.250491 0.684573 0.68455 0.250596 0.684539 0.935107 0.250605 0.250545 0.93513 0.250487 0.250576 0.935136 0.250488 -0.250553 0.694758 0.694737 -0.186148 0.508592 0.694743 -0.508593 0.508567 0.694771 -0.50858 0.186153 0.694753 -0.694741 0.186157 0.694747 -0.694747 -0.186159 0.694746 -0.694746 -0.186159 0.694754 -0.694738 -0.508573 0.69477 -0.508575 -0.508587 0.694742 -0.508599 -0.694757 0.694738 -0.186152 -0.694741 0.694755 -0.186144 -0.694741 0.694755 0.186148 -0.694758 0.694737 0.186148 -0.508592 0.694743 0.508593 -0.508563 0.694776 0.508577 -0.186153 0.694761 0.694733 -0.186161 0.694746 0.694746 0.186153 0.694747 0.694747 0.186153 0.694761 0.694733 0.508569 0.694775 0.508571 0.508586 0.694741 0.508601 0.694757 0.694738 0.186152 0.694741 0.694755 0.186144 0.694741 0.694755 -0.186148 0.258225 0.963604 -0.0691886 0.18903 0.963606 -0.189028 0.189021 0.963609 -0.189022 0.0691854 0.96361 -0.258204 0.0691841 0.963611 -0.258202 -0.069186 0.963611 -0.258202 -0.0691863 0.96361 -0.258204 -0.189023 0.963609 -0.189021 -0.189029 0.963606 -0.18903 -0.258222 0.963604 -0.0691939 -0.258191 0.963614 -0.0691794 -0.258191 0.963614 0.0691855 -0.258225 0.963604 0.0691886 -0.18903 0.963606 0.189028 -0.189021 0.963609 0.189022 -0.0691861 0.96361 0.258204 -0.0691849 0.963611 0.258202 0.069184 0.963611 0.258202 0.0691843 0.96361 0.258205 0.189023 0.963609 0.189021 0.189029 0.963606 0.18903 0.258222 0.963604 0.0691939 0.258191 0.963614 0.0691794 0.258191 0.963614 -0.0691855 0.935099 0.25061 -0.250567 0.684545 0.250599 -0.684542 0.684551 0.250579 -0.684543 0.250562 0.250574 -0.93511 0.250563 0.250569 -0.935111 -0.250562 0.250569 -0.935112 -0.250563 0.250574 -0.93511 -0.684549 0.25058 -0.684546 -0.684551 0.250522 -0.684565 -0.935126 0.250506 -0.250571 -0.935108 0.250596 -0.250548 -0.935104 0.250595 0.250566 -0.935131 0.250504 0.250554 -0.684559 0.250522 0.684556 -0.68454 0.25058 0.684554 -0.250562 0.250574 0.93511 -0.250563 0.250569 0.935111 0.250562 0.250569 0.935112 0.250563 0.250574 0.93511 0.684549 0.25058 0.684546 0.684548 0.250599 0.684539 0.9351 0.25061 0.250565 0.935103 0.250594 0.250569 0.935104 0.250595 -0.250565 0.694761 0.69473 -0.186164 0.5086 0.69473 -0.508602 0.50861 0.694719 -0.508608 0.186162 0.694731 -0.694761 0.186158 0.694739 -0.694753 -0.18616 0.694739 -0.694753 -0.186161 0.694731 -0.694762 -0.508607 0.694719 -0.508609 -0.508602 0.69473 -0.5086 -0.69476 0.69473 -0.186168 -0.694746 0.694746 -0.18616 -0.694746 0.694746 0.186165 -0.694761 0.69473 0.186165 -0.5086 0.69473 0.508602 -0.50861 0.694719 0.508608 -0.186162 0.694731 0.694761 -0.186158 0.694739 0.694753 0.18616 0.694739 0.694753 0.186161 0.694731 0.694762 0.508607 0.694719 0.508609 0.508602 0.69473 0.5086 0.69476 0.69473 0.186169 0.694746 0.694746 0.186161 0.694746 0.694746 -0.186164 0.258179 0.963617 -0.0691819 0.189003 0.963616 -0.189001 0.188996 0.963619 -0.188997 0.0691798 0.963616 -0.258183 0.069182 0.963614 -0.258188 -0.0691811 0.963615 -0.258188 -0.0691806 0.963616 -0.258183 -0.188997 0.963618 -0.188996 -0.189002 0.963616 -0.189003 -0.258182 0.963616 -0.0691778 -0.258206 0.963609 -0.069189 -0.258206 0.963609 0.0691845 -0.258179 0.963617 0.0691821 -0.189003 0.963616 0.189001 -0.188996 0.963619 0.188997 -0.0691798 0.963616 0.258183 -0.069182 0.963614 0.258188 0.0691811 0.963615 0.258188 0.0691806 0.963616 0.258183 0.188997 0.963618 0.188996 0.189002 0.963616 0.189003 0.258182 0.963616 0.069178 0.258206 0.963609 0.0691892 0.258206 0.963609 -0.0691843 -0.935132 -0.250501 -0.250554 -0.68456 -0.250519 -0.684557 -0.684541 -0.250577 -0.684555 -0.250562 -0.250571 -0.935111 -0.250563 -0.250565 -0.935112 0.250562 -0.250565 -0.935113 0.250563 -0.250571 -0.935111 0.684549 -0.250576 -0.684547 0.684548 -0.250596 -0.68454 0.935101 -0.250607 -0.250565 0.935104 -0.250591 -0.250569 0.935105 -0.250591 0.250566 0.9351 -0.250607 0.250568 0.684546 -0.250595 0.684543 0.684552 -0.250576 0.684544 0.250562 -0.250571 0.935111 0.250563 -0.250565 0.935112 -0.250562 -0.250565 0.935113 -0.250563 -0.250571 0.935111 -0.684549 -0.250576 0.684547 -0.684551 -0.250518 0.684565 -0.935127 -0.250502 0.250572 -0.935109 -0.250592 0.250548 -0.935105 -0.250591 -0.250566 -0.694755 -0.694737 -0.186163 -0.508595 -0.694737 -0.508597 -0.508605 -0.694726 -0.508603 -0.186161 -0.694738 -0.694754 -0.186157 -0.694747 -0.694747 0.186159 -0.694746 -0.694746 0.186159 -0.694738 -0.694755 0.508602 -0.694727 -0.508604 0.508597 -0.694737 -0.508595 0.694753 -0.694738 -0.186166 0.694739 -0.694753 -0.186159 0.694739 -0.694753 0.186163 0.694754 -0.694737 0.186163 0.508595 -0.694737 0.508597 0.508605 -0.694726 0.508603 0.186161 -0.694738 0.694754 0.186157 -0.694747 0.694747 -0.186159 -0.694746 0.694746 -0.186159 -0.694738 0.694755 -0.508602 -0.694727 0.508604 -0.508597 -0.694737 0.508595 -0.694753 -0.694738 0.186167 -0.694739 -0.694753 0.186159 -0.694739 -0.694753 -0.186163 -0.258193 -0.963613 -0.0691855 -0.189013 -0.963612 -0.189011 -0.189006 -0.963615 -0.189007 -0.0691834 -0.963612 -0.258197 -0.0691856 -0.963611 -0.258202 0.0691847 -0.963611 -0.258202 0.0691842 -0.963612 -0.258196 0.189007 -0.963615 -0.189006 0.189012 -0.963612 -0.189013 0.258195 -0.963613 -0.0691814 0.258219 -0.963605 -0.0691926 0.258219 -0.963606 0.0691881 0.258193 -0.963613 0.0691857 0.189013 -0.963612 0.189011 0.189006 -0.963615 0.189007 0.0691834 -0.963612 0.258197 0.0691856 -0.963611 0.258202 -0.0691847 -0.963611 0.258202 -0.0691842 -0.963612 0.258196 -0.189007 -0.963615 0.189006 -0.189012 -0.963612 0.189013 -0.258195 -0.963613 0.0691815 -0.258219 -0.963605 0.0691928 -0.258219 -0.963606 -0.0691879 -0.935101 -0.250603 -0.250568 -0.684538 -0.250585 -0.684554 -0.684566 -0.250499 -0.684558 -0.250569 -0.250543 -0.935117 -0.250563 -0.250565 -0.935112 0.250562 -0.250565 -0.935113 0.250559 -0.250542 -0.93512 0.684554 -0.250501 -0.68457 0.68455 -0.250586 -0.684542 0.935107 -0.250602 -0.250545 0.93513 -0.250487 -0.250576 0.935136 -0.250488 0.250553 0.9351 -0.250607 0.250568 0.684535 -0.250594 0.684554 0.684569 -0.25049 0.684558 0.250565 -0.25053 0.935122 0.250555 -0.250566 0.935114 -0.250568 -0.250565 0.935111 -0.250563 -0.250529 0.935122 -0.684554 -0.250491 0.684573 -0.68455 -0.250596 0.684539 -0.935107 -0.250605 0.250545 -0.93513 -0.250487 0.250576 -0.935136 -0.250488 -0.250553 -0.694758 -0.694737 -0.186148 -0.508592 -0.694743 -0.508593 -0.508567 -0.694771 -0.50858 -0.186157 -0.694754 -0.694739 -0.186161 -0.694746 -0.694746 0.186155 -0.694747 -0.694747 0.186155 -0.694754 -0.69474 0.508573 -0.69477 -0.508575 0.508587 -0.694742 -0.508599 0.694757 -0.694738 -0.186152 0.694741 -0.694755 -0.186144 0.694741 -0.694755 0.186148 0.694758 -0.694737 0.186148 0.508592 -0.694743 0.508593 0.508563 -0.694776 0.508577 0.18615 -0.694761 0.694735 0.186157 -0.694747 0.694747 -0.186157 -0.694747 0.694747 -0.186157 -0.694762 0.694732 -0.508569 -0.694775 0.508571 -0.508586 -0.694741 0.508601 -0.694757 -0.694738 0.186152 -0.694741 -0.694755 0.186144 -0.694741 -0.694755 -0.186148 -0.258225 -0.963604 -0.0691886 -0.18903 -0.963606 -0.189028 -0.189021 -0.963609 -0.189022 -0.0691866 -0.96361 -0.258204 -0.0691856 -0.963611 -0.258202 0.0691847 -0.963611 -0.258202 0.069185 -0.96361 -0.258205 0.189023 -0.963609 -0.189021 0.189029 -0.963606 -0.18903 0.258222 -0.963604 -0.0691939 0.258191 -0.963614 -0.0691794 0.258191 -0.963614 0.0691855 0.258225 -0.963604 0.0691886 0.18903 -0.963606 0.189028 0.189021 -0.963609 0.189022 0.0691849 -0.96361 0.258205 0.0691834 -0.963611 0.258202 -0.0691854 -0.963611 0.258202 -0.0691856 -0.96361 0.258204 -0.189023 -0.963609 0.189021 -0.189029 -0.963606 0.18903 -0.258222 -0.963604 0.0691939 -0.258191 -0.963614 0.0691794 -0.258191 -0.963614 -0.0691855 -0.958213 -0.256737 0.12615 -0.892911 -0.256738 0.369858 -0.892918 -0.256694 0.369872 -0.766766 -0.256702 0.588366 -0.766764 -0.256718 0.58836 -0.588364 -0.256726 0.766759 -0.588363 -0.256698 0.766769 -0.36986 -0.25672 0.892916 -0.36986 -0.256719 0.892916 -0.126148 -0.25674 0.958213 -0.126151 -0.256754 0.958208 0.126148 -0.256754 0.958209 0.126152 -0.25674 0.958212 0.36986 -0.256719 0.892916 0.369847 -0.25676 0.892909 0.588358 -0.256763 0.766751 0.588348 -0.256791 0.766749 0.766744 -0.256804 0.58835 0.76675 -0.256787 0.588349 0.892898 -0.256793 0.369853 0.892916 -0.256738 0.369846 0.958214 -0.256736 0.12614 0.958202 -0.256781 0.126149 0.958203 -0.256781 -0.126139 0.958213 -0.256739 -0.12615 0.89291 -0.256743 -0.369858 0.892902 -0.256793 -0.369842 0.766748 -0.256787 -0.588352 0.766746 -0.256804 -0.588347 0.588355 -0.256792 -0.766744 0.588354 -0.256753 -0.766758 0.369854 -0.256748 -0.89291 0.369851 -0.256719 -0.892919 0.126148 -0.25674 -0.958213 0.126151 -0.256754 -0.958208 -0.126148 -0.256754 -0.958209 -0.126152 -0.25674 -0.958212 -0.369857 -0.256719 -0.892917 -0.369861 -0.256707 -0.892919 -0.588372 -0.256687 -0.766766 -0.588359 -0.256726 -0.766763 -0.766762 -0.256718 -0.588363 -0.766768 -0.256702 -0.588363 -0.892922 -0.256694 -0.369863 -0.892906 -0.256742 -0.369868 -0.958214 -0.256738 -0.126141 -0.958202 -0.256781 -0.126149 -0.958203 -0.256781 0.126139 -0.704043 -0.704083 0.092681 -0.656066 -0.704083 0.271743 -0.65609 -0.704053 0.271763 -0.563396 -0.704053 0.432313 -0.563397 -0.704051 0.432314 -0.432307 -0.704053 0.5634 -0.432298 -0.704081 0.563373 -0.271754 -0.704074 0.656072 -0.271754 -0.704076 0.656069 -0.0926903 -0.704067 0.704058 -0.0926895 -0.704063 0.704063 0.0926909 -0.704063 0.704063 0.092689 -0.704067 0.704059 0.271754 -0.704076 0.656069 0.271755 -0.704074 0.656071 0.43229 -0.704082 0.563378 0.432314 -0.704054 0.563394 0.563398 -0.704051 0.432314 0.563396 -0.704053 0.432313 0.656094 -0.704052 0.271754 0.656063 -0.704082 0.271752 0.704042 -0.704084 0.0926852 0.704056 -0.70407 0.0926827 0.704056 -0.70407 -0.0926873 0.704043 -0.704084 -0.0926813 0.656066 -0.704083 -0.271743 0.65609 -0.704053 -0.271763 0.563396 -0.704053 -0.432313 0.563397 -0.704051 -0.432314 0.432307 -0.704053 -0.5634 0.432296 -0.704087 -0.563367 0.271752 -0.70408 -0.656065 0.271752 -0.704076 -0.65607 0.0926903 -0.704067 -0.704058 0.0926895 -0.704063 -0.704063 -0.0926909 -0.704063 -0.704063 -0.092689 -0.704067 -0.704059 -0.271754 -0.704076 -0.656069 -0.271751 -0.70408 -0.656066 -0.432287 -0.704087 -0.563373 -0.432315 -0.704054 -0.563393 -0.563398 -0.704051 -0.432314 -0.563396 -0.704053 -0.432313 -0.656094 -0.704052 -0.271754 -0.656063 -0.704082 -0.271752 -0.704042 -0.704084 -0.0926855 -0.704056 -0.70407 -0.092683 -0.704056 -0.70407 0.092687 -0.258653 -0.96537 0.0340509 -0.241027 -0.96537 0.0998335 -0.241026 -0.96537 0.099833 -0.206972 -0.96537 0.158817 -0.206971 -0.965371 0.158816 -0.158817 -0.96537 0.206973 -0.158822 -0.965367 0.206983 -0.099839 -0.965367 0.241035 -0.0998383 -0.965369 0.24103 -0.034053 -0.965369 0.258656 -0.0340527 -0.965369 0.258658 0.0340532 -0.965369 0.258658 0.0340525 -0.965369 0.258656 0.0998372 -0.965369 0.241031 0.09984 -0.965367 0.241034 0.158825 -0.965367 0.206982 0.158815 -0.96537 0.206975 0.206971 -0.965371 0.158816 0.206972 -0.96537 0.158817 0.241026 -0.96537 0.0998332 0.241027 -0.96537 0.0998333 0.258651 -0.96537 0.0340568 0.258676 -0.965364 0.034054 0.258676 -0.965364 -0.0340602 0.258652 -0.96537 -0.034051 0.241027 -0.96537 -0.0998335 0.241026 -0.96537 -0.099833 0.206972 -0.96537 -0.158817 0.206971 -0.965371 -0.158816 0.158817 -0.96537 -0.206973 0.158822 -0.965367 -0.206983 0.0998398 -0.965367 -0.241035 0.0998396 -0.965368 -0.241033 0.0340525 -0.965368 -0.25866 0.0340527 -0.965369 -0.258658 -0.0340523 -0.965369 -0.258658 -0.034053 -0.965368 -0.25866 -0.0998393 -0.965368 -0.241033 -0.09984 -0.965367 -0.241034 -0.158825 -0.965367 -0.206982 -0.158815 -0.96537 -0.206975 -0.206971 -0.965371 -0.158816 -0.206972 -0.96537 -0.158817 -0.241026 -0.96537 -0.0998332 -0.241027 -0.96537 -0.0998333 -0.258651 -0.96537 -0.0340569 -0.258676 -0.965364 -0.0340541 -0.258676 -0.965364 0.0340601 0.958213 0.256737 0.12615 0.892911 0.256738 0.369858 0.892903 0.256792 0.369841 0.76676 0.256788 0.588337 0.766764 0.256718 0.58836 0.588352 0.256726 0.766769 0.588353 0.256764 0.766755 0.369853 0.256761 0.892907 0.369855 0.256773 0.892903 0.126154 0.256767 0.958205 0.126151 0.256754 0.958208 -0.126151 0.256754 0.958208 -0.126147 0.256767 0.958205 -0.369852 0.256773 0.892904 -0.369856 0.256761 0.892906 -0.588346 0.256764 0.766761 -0.588359 0.256726 0.766763 -0.766774 0.256718 0.588348 -0.76675 0.256787 0.588349 -0.892898 0.256793 0.369853 -0.892916 0.256738 0.369846 -0.958211 0.256737 0.126165 -0.95823 0.256674 0.126153 -0.958228 0.256674 -0.126167 -0.958213 0.256737 -0.12615 -0.892911 0.256738 -0.369858 -0.892903 0.256792 -0.369841 -0.766758 0.256788 -0.588338 -0.766763 0.256719 -0.588362 -0.588354 0.256726 -0.766767 -0.588354 0.256753 -0.766758 -0.369854 0.256748 -0.89291 -0.369856 0.25676 -0.892906 -0.126151 0.256754 -0.958209 -0.126148 0.256741 -0.958212 0.126154 0.256741 -0.958212 0.126151 0.256754 -0.958208 0.369853 0.25676 -0.892907 0.369857 0.256748 -0.892909 0.588349 0.256753 -0.766761 0.588359 0.256726 -0.766763 0.766773 0.256718 -0.588349 0.766749 0.256787 -0.588351 0.892898 0.256793 -0.369853 0.892916 0.256738 -0.369846 0.958211 0.256737 -0.126165 0.95823 0.256674 -0.126153 0.958228 0.256674 0.126167 0.704096 0.704027 0.0927063 0.65611 0.704028 0.27178 0.65609 0.704053 0.271763 0.563395 0.704053 0.432314 0.563367 0.704101 0.432273 0.432293 0.704095 0.563359 0.43231 0.704046 0.563407 0.271761 0.704051 0.656093 0.271761 0.704054 0.65609 0.0926936 0.70406 0.704065 0.0926942 0.704062 0.704062 -0.0926908 0.704063 0.704063 -0.0926922 0.704059 0.704066 -0.27176 0.704054 0.65609 -0.271762 0.704051 0.656093 -0.432323 0.704045 0.563398 -0.432281 0.704094 0.563369 -0.563357 0.704102 0.432284 -0.563404 0.704054 0.432301 -0.656087 0.704054 0.27177 -0.656112 0.704029 0.271772 -0.704099 0.704026 0.0926927 -0.704055 0.704069 0.0927008 -0.704056 0.70407 -0.092687 -0.704096 0.704027 -0.0927063 -0.65611 0.704028 -0.271781 -0.656088 0.704056 -0.271762 -0.563393 0.704058 -0.43231 -0.56337 0.704096 -0.432277 -0.432295 0.704089 -0.563365 -0.432308 0.704052 -0.563401 -0.27176 0.704058 -0.656086 -0.271761 0.704054 -0.65609 -0.0926889 0.704059 -0.704066 -0.0926908 0.70407 -0.704055 0.09269 0.70407 -0.704056 0.0926945 0.70406 -0.704065 0.271762 0.704054 -0.65609 0.271759 0.704058 -0.656086 0.432318 0.704051 -0.563395 0.432286 0.704089 -0.563372 0.563361 0.704097 -0.432286 0.5634 0.704058 -0.4323 0.656084 0.704056 -0.27177 0.656112 0.704029 -0.271772 0.704099 0.704026 -0.0926927 0.704055 0.704069 -0.0927008 0.704056 0.70407 0.092687 0.258666 0.965366 0.0340526 0.241037 0.965366 0.0998454 0.241035 0.965367 0.0998438 0.206986 0.965367 0.158821 0.207 0.965361 0.158839 0.158834 0.965361 0.207 0.158824 0.965368 0.206978 0.0998424 0.965367 0.241036 0.099844 0.965364 0.241046 0.0340552 0.965364 0.258673 0.0340554 0.965365 0.258672 -0.034054 0.965365 0.258672 -0.0340547 0.965364 0.258673 -0.0998464 0.965364 0.241045 -0.0998402 0.965367 0.241037 -0.158819 0.965368 0.206981 -0.158838 0.965362 0.206996 -0.207004 0.965361 0.158835 -0.206983 0.965367 0.158825 -0.241035 0.965367 0.0998444 -0.241037 0.965366 0.0998448 -0.258666 0.965366 0.0340514 -0.258661 0.965368 0.034052 -0.258661 0.965368 -0.0340507 -0.258666 0.965366 -0.0340526 -0.241037 0.965366 -0.0998454 -0.241036 0.965367 -0.0998447 -0.206987 0.965366 -0.158822 -0.207 0.965361 -0.158838 -0.158833 0.965361 -0.207001 -0.158823 0.965368 -0.206978 -0.0998432 0.965367 -0.241035 -0.0998447 0.965364 -0.241046 -0.0340542 0.965364 -0.258673 -0.0340541 0.965364 -0.258675 0.0340555 0.965364 -0.258675 0.0340547 0.965364 -0.258673 0.0998472 0.965364 -0.241045 0.0998409 0.965367 -0.241037 0.158818 0.965368 -0.206981 0.158838 0.965362 -0.206997 0.207004 0.965361 -0.158835 0.206985 0.965366 -0.158826 0.241036 0.965367 -0.0998449 0.241037 0.965366 -0.0998451 0.258666 0.965366 -0.0340514 0.258661 0.965368 -0.034052 0.258661 0.965368 0.0340507 0.958213 0.256737 0.12615 0.892911 0.256738 0.369858 0.892903 0.256792 0.369841 0.766748 0.256787 0.588352 0.766746 0.256804 0.588347 0.588353 0.256792 0.766745 0.588353 0.256764 0.766755 0.369856 0.256761 0.892906 0.369851 0.256719 0.892919 0.126148 0.25674 0.958213 0.126151 0.256754 0.958208 -0.126148 0.256754 0.958209 -0.126152 0.25674 0.958212 -0.36986 0.256719 0.892916 -0.36986 0.25672 0.892916 -0.588368 0.256698 0.766765 -0.588359 0.256726 0.766763 -0.766762 0.256718 0.588363 -0.766768 0.256702 0.588363 -0.892922 0.256694 0.369863 -0.892908 0.256737 0.369868 -0.958214 0.256736 0.12614 -0.958202 0.256781 0.126149 -0.958203 0.256781 -0.126139 -0.958213 0.256739 -0.12615 -0.89291 0.256743 -0.369858 -0.892918 0.256694 -0.369873 -0.766766 0.256702 -0.588366 -0.766764 0.256718 -0.58836 -0.588366 0.256726 -0.766758 -0.588365 0.256687 -0.766771 -0.369859 0.256707 -0.89292 -0.36986 0.256719 -0.892916 -0.126148 0.25674 -0.958213 -0.126151 0.256754 -0.958208 0.126148 0.256754 -0.958209 0.126152 0.25674 -0.958212 0.369857 0.256719 -0.892917 0.369848 0.256748 -0.892912 0.588362 0.256753 -0.766752 0.588348 0.256791 -0.766749 0.766744 0.256804 -0.58835 0.76675 0.256787 -0.588349 0.892898 0.256793 -0.369853 0.892914 0.256743 -0.369847 0.958214 0.256738 -0.126141 0.958202 0.256781 -0.126149 0.958203 0.256781 0.126139 0.704043 0.704083 0.092681 0.656066 0.704083 0.271743 0.65609 0.704053 0.271763 0.563396 0.704053 0.432313 0.563397 0.704051 0.432314 0.432307 0.704053 0.5634 0.432298 0.704081 0.563373 0.271754 0.704074 0.656072 0.271754 0.704076 0.656069 0.0926903 0.704067 0.704058 0.0926895 0.704063 0.704063 -0.0926909 0.704063 0.704063 -0.092689 0.704067 0.704059 -0.271754 0.704076 0.656069 -0.271755 0.704074 0.656071 -0.43229 0.704082 0.563378 -0.432314 0.704054 0.563394 -0.563398 0.704051 0.432314 -0.563396 0.704053 0.432313 -0.656094 0.704052 0.271754 -0.656063 0.704082 0.271752 -0.704042 0.704084 0.0926852 -0.704056 0.70407 0.0926827 -0.704056 0.70407 -0.0926873 -0.704043 0.704084 -0.0926813 -0.656066 0.704083 -0.271743 -0.65609 0.704053 -0.271763 -0.563396 0.704053 -0.432313 -0.563397 0.704051 -0.432314 -0.432307 0.704053 -0.5634 -0.432296 0.704087 -0.563367 -0.271752 0.70408 -0.656065 -0.271752 0.704076 -0.65607 -0.0926903 0.704067 -0.704058 -0.0926895 0.704063 -0.704063 0.0926909 0.704063 -0.704063 0.092689 0.704067 -0.704059 0.271754 0.704076 -0.656069 0.271751 0.70408 -0.656066 0.432287 0.704087 -0.563373 0.432315 0.704054 -0.563393 0.563398 0.704051 -0.432314 0.563396 0.704053 -0.432313 0.656094 0.704052 -0.271754 0.656063 0.704082 -0.271752 0.704042 0.704084 -0.0926855 0.704056 0.70407 -0.092683 0.704056 0.70407 0.092687 0.258666 0.965366 0.0340526 0.241039 0.965366 0.0998387 0.241038 0.965367 0.0998382 0.206983 0.965367 0.158825 0.206982 0.965367 0.158824 0.158826 0.965366 0.206983 0.15883 0.965363 0.206994 0.0998442 0.965364 0.241048 0.0998434 0.965365 0.241043 0.0340547 0.965365 0.25867 0.0340545 0.965365 0.258672 -0.034055 0.965365 0.258672 -0.0340543 0.965365 0.25867 -0.0998423 0.965365 0.241043 -0.0998452 0.965364 0.241047 -0.158833 0.965363 0.206993 -0.158824 0.965366 0.206985 -0.206982 0.965367 0.158824 -0.206983 0.965367 0.158825 -0.241038 0.965367 0.0998383 -0.241039 0.965366 0.0998385 -0.258664 0.965367 0.0340586 -0.25869 0.96536 0.0340558 -0.25869 0.96536 -0.034062 -0.258666 0.965366 -0.0340528 -0.241039 0.965366 -0.0998387 -0.241038 0.965367 -0.0998382 -0.206983 0.965367 -0.158825 -0.206982 0.965367 -0.158824 -0.158826 0.965366 -0.206983 -0.15883 0.965363 -0.206994 -0.0998449 0.965364 -0.241047 -0.0998447 0.965364 -0.241046 -0.0340543 0.965364 -0.258673 -0.0340545 0.965365 -0.258672 0.0340541 0.965365 -0.258672 0.0340547 0.965364 -0.258673 0.0998444 0.965364 -0.241046 0.0998452 0.965364 -0.241047 0.158833 0.965363 -0.206993 0.158824 0.965366 -0.206985 0.206982 0.965367 -0.158824 0.206983 0.965367 -0.158825 0.241038 0.965367 -0.0998383 0.241039 0.965366 -0.0998385 0.258664 0.965367 -0.0340587 0.25869 0.96536 -0.0340559 0.258689 0.96536 0.0340619 -0.958213 -0.256737 0.12615 -0.892911 -0.256738 0.369858 -0.892903 -0.256792 0.369841 -0.76676 -0.256788 0.588337 -0.766764 -0.256718 0.58836 -0.588352 -0.256726 0.766769 -0.588353 -0.256764 0.766755 -0.369853 -0.256761 0.892907 -0.369855 -0.256773 0.892903 -0.12615 -0.256767 0.958205 -0.126148 -0.256754 0.958209 0.126154 -0.256754 0.958208 0.126151 -0.256767 0.958205 0.369852 -0.256773 0.892904 0.369856 -0.256761 0.892906 0.588346 -0.256764 0.766761 0.588359 -0.256726 0.766763 0.766774 -0.256718 0.588348 0.76675 -0.256787 0.588349 0.892898 -0.256793 0.369853 0.892916 -0.256738 0.369846 0.958211 -0.256737 0.126165 0.95823 -0.256674 0.126153 0.958228 -0.256674 -0.126167 0.958213 -0.256737 -0.12615 0.892911 -0.256738 -0.369858 0.892903 -0.256792 -0.369841 0.766758 -0.256788 -0.588338 0.766763 -0.256719 -0.588362 0.588354 -0.256726 -0.766767 0.588354 -0.256753 -0.766758 0.369854 -0.256748 -0.89291 0.369856 -0.25676 -0.892906 0.126154 -0.256754 -0.958208 0.126152 -0.256741 -0.958212 -0.126151 -0.256741 -0.958212 -0.126148 -0.256754 -0.958209 -0.369853 -0.25676 -0.892907 -0.369857 -0.256748 -0.892909 -0.588349 -0.256753 -0.766761 -0.588359 -0.256726 -0.766763 -0.766773 -0.256718 -0.588349 -0.766749 -0.256787 -0.588351 -0.892898 -0.256793 -0.369853 -0.892916 -0.256738 -0.369846 -0.958211 -0.256737 -0.126165 -0.95823 -0.256674 -0.126153 -0.958228 -0.256674 0.126167 -0.704096 -0.704027 0.0927063 -0.65611 -0.704028 0.27178 -0.65609 -0.704053 0.271763 -0.563395 -0.704053 0.432314 -0.563367 -0.704101 0.432273 -0.432293 -0.704095 0.563359 -0.43231 -0.704046 0.563407 -0.271761 -0.704051 0.656093 -0.271761 -0.704054 0.65609 -0.0926912 -0.704059 0.704066 -0.0926918 -0.704063 0.704063 0.0926933 -0.704063 0.704063 0.0926945 -0.70406 0.704065 0.27176 -0.704054 0.65609 0.271762 -0.704051 0.656093 0.432323 -0.704045 0.563398 0.432281 -0.704094 0.563369 0.563357 -0.704102 0.432284 0.563404 -0.704054 0.432301 0.656087 -0.704054 0.27177 0.656112 -0.704029 0.271772 0.704099 -0.704026 0.0926927 0.704055 -0.704069 0.0927008 0.704056 -0.70407 -0.092687 0.704096 -0.704027 -0.0927063 0.65611 -0.704028 -0.271781 0.656088 -0.704056 -0.271762 0.563393 -0.704058 -0.43231 0.56337 -0.704096 -0.432277 0.432295 -0.704089 -0.563365 0.432308 -0.704052 -0.563401 0.27176 -0.704058 -0.656086 0.271761 -0.704054 -0.65609 0.0926913 -0.704059 -0.704066 0.0926932 -0.70407 -0.704055 -0.0926875 -0.70407 -0.704056 -0.0926922 -0.704059 -0.704066 -0.271762 -0.704054 -0.65609 -0.271759 -0.704058 -0.656086 -0.432318 -0.704051 -0.563395 -0.432286 -0.704089 -0.563372 -0.563361 -0.704097 -0.432286 -0.5634 -0.704058 -0.4323 -0.656084 -0.704056 -0.27177 -0.656112 -0.704029 -0.271772 -0.704099 -0.704026 -0.0926927 -0.704055 -0.704069 -0.0927008 -0.704056 -0.70407 0.092687 -0.258666 -0.965366 0.0340526 -0.241037 -0.965366 0.0998454 -0.241035 -0.965367 0.0998438 -0.206986 -0.965367 0.158821 -0.207 -0.965361 0.158839 -0.158834 -0.965361 0.207 -0.158824 -0.965368 0.206978 -0.0998424 -0.965367 0.241036 -0.099844 -0.965364 0.241046 -0.0340542 -0.965364 0.258673 -0.0340545 -0.965365 0.258672 0.034055 -0.965365 0.258672 0.0340556 -0.965364 0.258673 0.0998464 -0.965364 0.241045 0.0998402 -0.965367 0.241037 0.158819 -0.965368 0.206981 0.158838 -0.965362 0.206996 0.207004 -0.965361 0.158835 0.206983 -0.965367 0.158825 0.241035 -0.965367 0.0998444 0.241037 -0.965366 0.0998448 0.258666 -0.965366 0.0340514 0.258661 -0.965368 0.034052 0.258661 -0.965368 -0.0340507 0.258666 -0.965366 -0.0340526 0.241037 -0.965366 -0.0998454 0.241036 -0.965367 -0.0998447 0.206987 -0.965366 -0.158822 0.207 -0.965361 -0.158838 0.158833 -0.965361 -0.207001 0.158823 -0.965368 -0.206978 0.0998432 -0.965367 -0.241035 0.0998447 -0.965364 -0.241046 0.0340552 -0.965364 -0.258673 0.034055 -0.965364 -0.258675 -0.0340545 -0.965364 -0.258675 -0.0340538 -0.965364 -0.258674 -0.0998472 -0.965364 -0.241045 -0.0998409 -0.965367 -0.241037 -0.158818 -0.965368 -0.206981 -0.158838 -0.965362 -0.206997 -0.207004 -0.965361 -0.158835 -0.206985 -0.965366 -0.158826 -0.241036 -0.965367 -0.0998449 -0.241037 -0.965366 -0.0998451 -0.258666 -0.965366 -0.0340514 -0.258661 -0.965368 -0.034052 -0.258661 -0.965368 0.0340507 -0.0340546 -0.258669 -0.965366 -0.0998435 -0.241043 -0.965365 -0.0998433 -0.241041 -0.965366 -0.158829 -0.206987 -0.965365 -0.158827 -0.206984 -0.965366 -0.206985 -0.158826 -0.965366 -0.206994 -0.158838 -0.965362 -0.241053 -0.0998501 -0.965362 -0.241047 -0.0998451 -0.965364 -0.258675 -0.0340574 -0.965364 -0.258652 -0.0340467 -0.965371 -0.258652 0.0340544 -0.96537 -0.258677 0.0340501 -0.965364 -0.241046 0.0998473 -0.965364 -0.241054 0.0998481 -0.965362 -0.206996 0.158834 -0.965362 -0.206982 0.158829 -0.965366 -0.158827 0.206985 -0.965366 -0.158829 0.206986 -0.965365 -0.0998427 0.241041 -0.965365 -0.0998441 0.241043 -0.965365 -0.0340549 0.258669 -0.965366 -0.0340545 0.258668 -0.965366 0.0340538 0.258668 -0.965366 0.0340536 0.258669 -0.965366 0.0998435 0.241043 -0.965365 0.0998433 0.241041 -0.965366 0.158829 0.206987 -0.965365 0.158827 0.206984 -0.965366 0.206985 0.158826 -0.965366 0.206994 0.158838 -0.965362 0.241053 0.0998501 -0.965362 0.241047 0.0998451 -0.965364 0.258675 0.0340575 -0.965364 0.258652 0.0340467 -0.965371 0.258652 -0.0340544 -0.96537 0.258677 -0.03405 -0.965364 0.241046 -0.0998473 -0.965364 0.241054 -0.0998481 -0.965362 0.206996 -0.158834 -0.965362 0.206982 -0.158829 -0.965366 0.158827 -0.206985 -0.965366 0.158829 -0.206986 -0.965365 0.0998427 -0.241041 -0.965365 0.0998441 -0.241043 -0.965365 0.034054 -0.258669 -0.965366 0.0340534 -0.258668 -0.965366 -0.0340548 -0.258668 -0.965366 -0.0926925 -0.704059 -0.704066 -0.271754 -0.656084 -0.704063 -0.271754 -0.65607 -0.704075 -0.432299 -0.563373 -0.70408 -0.4323 -0.563377 -0.704076 -0.563379 -0.432295 -0.704078 -0.563382 -0.4323 -0.704073 -0.65607 -0.271757 -0.704074 -0.656076 -0.271763 -0.704067 -0.704057 -0.0926949 -0.704067 -0.704062 -0.0926976 -0.704062 -0.704062 0.0926957 -0.704062 -0.704057 0.0926971 -0.704068 -0.656077 0.27176 -0.704067 -0.656068 0.27176 -0.704075 -0.563383 0.432298 -0.704073 -0.563378 0.432296 -0.704078 -0.432301 0.563376 -0.704076 -0.432297 0.563374 -0.70408 -0.271749 0.656073 -0.704075 -0.271758 0.656082 -0.704062 -0.0926925 0.704059 -0.704066 -0.0926926 0.70406 -0.704066 0.0926901 0.70406 -0.704066 0.09269 0.70406 -0.704066 0.271754 0.656084 -0.704063 0.271754 0.65607 -0.704075 0.432299 0.563373 -0.70408 0.4323 0.563377 -0.704076 0.563379 0.432295 -0.704078 0.563382 0.4323 -0.704073 0.65607 0.271757 -0.704074 0.656076 0.271763 -0.704067 0.704057 0.092695 -0.704067 0.704062 0.0926978 -0.704062 0.704062 -0.0926955 -0.704062 0.704057 -0.0926969 -0.704068 0.656077 -0.27176 -0.704067 0.656068 -0.27176 -0.704075 0.563383 -0.432298 -0.704073 0.563378 -0.432296 -0.704078 0.432301 -0.563376 -0.704076 0.432297 -0.563374 -0.70408 0.271749 -0.656073 -0.704075 0.271758 -0.656082 -0.704062 0.0926901 -0.70406 -0.704066 0.09269 -0.70406 -0.704066 -0.0926925 -0.70406 -0.704066 -0.126153 -0.95821 -0.256748 -0.369854 -0.892911 -0.256746 -0.369851 -0.892917 -0.256729 -0.588361 -0.766765 -0.256717 -0.588362 -0.766756 -0.256739 -0.766758 -0.588362 -0.256735 -0.766757 -0.588352 -0.25676 -0.892909 -0.369849 -0.256761 -0.892914 -0.369862 -0.256724 -0.958216 -0.126159 -0.256722 -0.958214 -0.126157 -0.25673 -0.958214 0.126159 -0.256729 -0.958216 0.126157 -0.256722 -0.892918 0.369852 -0.256725 -0.892904 0.369858 -0.256764 -0.766751 0.588358 -0.256763 -0.766762 0.588356 -0.256735 -0.588357 0.76676 -0.256739 -0.588366 0.766761 -0.256717 -0.369856 0.892915 -0.256729 -0.36985 0.892912 -0.256746 -0.126155 0.958209 -0.256748 -0.126152 0.958207 -0.256757 0.126152 0.958207 -0.256757 0.126149 0.95821 -0.256748 0.369854 0.892911 -0.256746 0.369851 0.892917 -0.256729 0.588361 0.766765 -0.256717 0.588362 0.766756 -0.256739 0.766757 0.588362 -0.256735 0.766756 0.588351 -0.256763 0.892908 0.369848 -0.256763 0.892914 0.369862 -0.256724 0.958216 0.126159 -0.256722 0.958214 0.126157 -0.25673 0.958214 -0.126159 -0.256729 0.958216 -0.126157 -0.256722 0.892918 -0.369853 -0.256725 0.892904 -0.369858 -0.256761 0.766753 -0.588358 -0.25676 0.766762 -0.588356 -0.256735 0.588357 -0.76676 -0.256739 0.588366 -0.766761 -0.256717 0.369856 -0.892915 -0.256729 0.36985 -0.892912 -0.256746 0.12615 -0.95821 -0.256748 0.126149 -0.958209 -0.256752 -0.126153 -0.958209 -0.256752 -0.0340546 -0.258669 -0.965366 -0.0998435 -0.241043 -0.965365 -0.0998433 -0.241041 -0.965366 -0.158829 -0.206987 -0.965365 -0.158827 -0.206984 -0.965366 -0.206985 -0.158826 -0.965366 -0.206994 -0.158838 -0.965362 -0.241053 -0.0998502 -0.965362 -0.241046 -0.0998449 -0.965364 -0.258675 -0.0340574 -0.965364 -0.258652 -0.0340467 -0.965371 -0.258652 0.0340544 -0.96537 -0.258677 0.03405 -0.965364 -0.241046 0.0998473 -0.965364 -0.241054 0.0998481 -0.965362 -0.206996 0.158834 -0.965362 -0.206982 0.158829 -0.965366 -0.158827 0.206985 -0.965366 -0.158829 0.206986 -0.965365 -0.0998427 0.241041 -0.965365 -0.0998441 0.241043 -0.965365 -0.0340549 0.258669 -0.965366 -0.0340545 0.258668 -0.965366 0.0340538 0.258668 -0.965366 0.0340536 0.258669 -0.965366 0.0998435 0.241043 -0.965365 0.0998433 0.241041 -0.965366 0.158829 0.206987 -0.965365 0.158827 0.206984 -0.965366 0.206985 0.158826 -0.965366 0.206994 0.158838 -0.965362 0.241053 0.0998501 -0.965362 0.241047 0.0998451 -0.965364 0.258675 0.0340574 -0.965364 0.258652 0.0340467 -0.965371 0.258652 -0.0340544 -0.96537 0.258677 -0.03405 -0.965364 0.241046 -0.0998473 -0.965364 0.241054 -0.0998481 -0.965362 0.206996 -0.158834 -0.965362 0.206982 -0.158829 -0.965366 0.158827 -0.206985 -0.965366 0.158829 -0.206986 -0.965365 0.0998427 -0.241041 -0.965365 0.0998441 -0.241043 -0.965365 0.034054 -0.258669 -0.965366 0.0340534 -0.258668 -0.965366 -0.0340548 -0.258668 -0.965366 -0.0926925 -0.704059 -0.704066 -0.271754 -0.656084 -0.704063 -0.271754 -0.65607 -0.704075 -0.432299 -0.563373 -0.70408 -0.4323 -0.563377 -0.704076 -0.563379 -0.432295 -0.704078 -0.563382 -0.4323 -0.704073 -0.656069 -0.271757 -0.704075 -0.656076 -0.271763 -0.704067 -0.704057 -0.0926949 -0.704067 -0.704062 -0.0926976 -0.704062 -0.704062 0.0926955 -0.704062 -0.704057 0.0926969 -0.704068 -0.656077 0.27176 -0.704067 -0.656068 0.27176 -0.704075 -0.563383 0.432298 -0.704073 -0.563378 0.432296 -0.704078 -0.432301 0.563376 -0.704076 -0.432297 0.563374 -0.70408 -0.271749 0.656073 -0.704075 -0.271758 0.656082 -0.704062 -0.0926925 0.704059 -0.704066 -0.0926926 0.70406 -0.704066 0.0926901 0.70406 -0.704066 0.09269 0.70406 -0.704066 0.271754 0.656084 -0.704063 0.271754 0.65607 -0.704075 0.432299 0.563373 -0.70408 0.4323 0.563377 -0.704076 0.563379 0.432295 -0.704078 0.563382 0.4323 -0.704073 0.65607 0.271757 -0.704074 0.656076 0.271763 -0.704067 0.704057 0.0926949 -0.704067 0.704062 0.0926976 -0.704062 0.704062 -0.0926955 -0.704062 0.704057 -0.0926969 -0.704068 0.656077 -0.27176 -0.704067 0.656068 -0.27176 -0.704075 0.563383 -0.432298 -0.704073 0.563378 -0.432296 -0.704078 0.432301 -0.563376 -0.704076 0.432297 -0.563374 -0.70408 0.271749 -0.656073 -0.704075 0.271758 -0.656082 -0.704062 0.0926901 -0.70406 -0.704066 0.09269 -0.70406 -0.704066 -0.0926925 -0.70406 -0.704066 -0.126152 -0.958208 -0.256754 -0.369853 -0.892909 -0.256751 -0.369851 -0.892915 -0.256734 -0.588361 -0.766763 -0.256721 -0.588362 -0.766756 -0.256739 -0.766757 -0.588362 -0.256735 -0.766756 -0.588351 -0.256763 -0.892908 -0.369848 -0.256763 -0.892914 -0.369863 -0.256722 -0.958216 -0.126159 -0.256721 -0.958214 -0.126157 -0.25673 -0.958214 0.126159 -0.256729 -0.958216 0.126157 -0.256722 -0.892918 0.369853 -0.256725 -0.892904 0.369858 -0.256761 -0.766753 0.588358 -0.25676 -0.766762 0.588356 -0.256735 -0.588357 0.76676 -0.256739 -0.588366 0.766761 -0.256717 -0.369856 0.892915 -0.256729 -0.36985 0.892912 -0.256746 -0.126154 0.95821 -0.256748 -0.126152 0.958209 -0.256752 0.12615 0.958209 -0.256752 0.126149 0.95821 -0.256748 0.369854 0.892911 -0.256746 0.369851 0.892917 -0.256729 0.588361 0.766765 -0.256717 0.588362 0.766756 -0.256739 0.766758 0.588362 -0.256735 0.766757 0.588352 -0.25676 0.892909 0.369849 -0.256761 0.892914 0.369862 -0.256724 0.958216 0.126159 -0.256722 0.958214 0.126157 -0.25673 0.958214 -0.126159 -0.256729 0.958216 -0.126157 -0.256721 0.892918 -0.369852 -0.256722 0.892904 -0.369859 -0.256764 0.766751 -0.588358 -0.256763 0.766762 -0.588356 -0.256735 0.588358 -0.766759 -0.256739 0.588365 -0.76676 -0.256721 0.369855 -0.892913 -0.256735 0.369849 -0.892911 -0.256751 0.12615 -0.958209 -0.256754 0.126149 -0.958208 -0.256758 -0.126153 -0.958207 -0.256757 -0.0340546 0.258669 0.965366 -0.0998435 0.241043 0.965365 -0.0998433 0.241041 0.965366 -0.158825 0.206989 0.965365 -0.158824 0.206987 0.965366 -0.206985 0.158826 0.965366 -0.206981 0.158821 0.965368 -0.241035 0.0998356 0.965368 -0.241047 0.0998451 0.965364 -0.258675 0.0340574 0.965364 -0.258675 0.0340576 0.965364 -0.258675 -0.0340576 0.965364 -0.258675 -0.0340576 0.965364 -0.241048 -0.0998408 0.965364 -0.241033 -0.0998395 0.965368 -0.20698 -0.158822 0.965368 -0.206987 -0.158825 0.965366 -0.158824 -0.206988 0.965366 -0.158825 -0.206989 0.965365 -0.0998427 -0.241041 0.965365 -0.0998441 -0.241043 0.965365 -0.0340549 -0.258669 0.965366 -0.0340545 -0.258668 0.965366 0.0340538 -0.258668 0.965366 0.0340542 -0.258666 0.965366 0.0998399 -0.241035 0.965367 0.0998407 -0.241043 0.965365 0.158829 -0.206987 0.965365 0.158827 -0.206984 0.965366 0.206985 -0.158826 0.965366 0.206981 -0.158821 0.965368 0.241032 -0.0998414 0.965368 0.241026 -0.0998365 0.96537 0.258653 -0.0340473 0.96537 0.258675 -0.0340577 0.965364 0.258676 0.0340502 0.965364 0.258651 0.0340544 0.96537 0.241026 0.0998387 0.96537 0.241033 0.0998395 0.965368 0.20698 0.158822 0.965368 0.206987 0.158825 0.965366 0.158827 0.206985 0.965366 0.158829 0.206986 0.965365 0.0998427 0.241041 0.965365 0.0998376 0.241035 0.965367 0.0340536 0.258666 0.965366 0.0340545 0.258668 0.965366 -0.0340548 0.258668 0.965366 -0.0926933 0.704065 0.70406 -0.271758 0.656075 0.704069 -0.271758 0.656081 0.704063 -0.432306 0.563383 0.704068 -0.432316 0.563418 0.704033 -0.563419 0.432325 0.704027 -0.563422 0.43233 0.704022 -0.656122 0.271778 0.704018 -0.656093 0.27175 0.704056 -0.704069 0.0926965 0.704055 -0.704074 0.0926992 0.70405 -0.704074 -0.0926971 0.70405 -0.704068 -0.0926986 0.704056 -0.656087 -0.271764 0.704056 -0.656129 -0.271765 0.704017 -0.563423 -0.432328 0.704022 -0.563417 -0.432327 0.704027 -0.432326 -0.563409 0.704034 -0.432295 -0.56339 0.704069 -0.27176 -0.65608 0.704063 -0.271756 -0.656076 0.704069 -0.0926908 -0.704066 0.70406 -0.0926941 -0.704071 0.704053 0.0926916 -0.704072 0.704054 0.0926916 -0.704072 0.704053 0.271765 -0.656092 0.70405 0.271765 -0.656098 0.704044 0.432314 -0.563412 0.704039 0.432307 -0.563387 0.704064 0.563388 -0.432302 0.704066 0.563391 -0.432307 0.70406 0.65608 -0.271762 0.704062 0.656086 -0.271767 0.704056 0.704069 -0.0926964 0.704056 0.704028 -0.0926735 0.7041 0.704027 0.0926909 0.704098 0.704073 0.0926792 0.704054 0.656088 0.271764 0.704055 0.656079 0.271764 0.704063 0.563392 0.432305 0.704061 0.563387 0.432304 0.704066 0.4323 0.563393 0.704063 0.432322 0.563407 0.704038 0.271767 0.656097 0.704045 0.271763 0.656093 0.70405 0.0926917 0.704072 0.704053 0.0926915 0.704072 0.704054 -0.0926916 0.704072 0.704054 -0.126149 0.95821 0.256748 -0.369863 0.892907 0.256746 -0.36986 0.892913 0.25673 -0.588349 0.766774 0.256717 -0.588353 0.766744 0.256794 -0.766755 0.588334 0.256806 -0.766757 0.588352 0.25676 -0.892899 0.36987 0.256762 -0.892893 0.369854 0.256807 -0.958196 0.126131 0.25681 -0.958214 0.126157 0.25673 -0.958217 -0.126134 0.25673 -0.958193 -0.126154 0.25681 -0.892889 -0.369865 0.256805 -0.892904 -0.369859 0.256764 -0.766763 -0.588342 0.256764 -0.766747 -0.588345 0.256806 -0.588336 -0.766758 0.256793 -0.588366 -0.766761 0.256717 -0.369865 -0.892911 0.25673 -0.369859 -0.892909 0.256746 -0.126152 -0.95821 0.256748 -0.126149 -0.958208 0.256758 0.126152 -0.958207 0.256757 0.126149 -0.95821 0.256748 0.369854 -0.892911 0.256746 0.369857 -0.892904 0.256764 0.588352 -0.766753 0.256772 0.58835 -0.766766 0.256739 0.766757 -0.588362 0.256735 0.766756 -0.588351 0.256763 0.892908 -0.369848 0.256763 0.892914 -0.369863 0.256722 0.958216 -0.126159 0.256721 0.958214 -0.126157 0.25673 0.958214 0.126159 0.256729 0.958216 0.126157 0.256722 0.892918 0.369853 0.256725 0.892904 0.369858 0.256761 0.766753 0.588358 0.25676 0.766762 0.588356 0.256735 0.588357 0.76676 0.256739 0.588345 0.766759 0.256772 0.369852 0.892906 0.256764 0.369859 0.892909 0.256746 0.12615 0.95821 0.256748 0.126149 0.958209 0.256752 -0.12615 0.958209 0.256752 -0.0340546 0.258669 0.965366 -0.0998435 0.241043 0.965365 -0.0998433 0.241041 0.965366 -0.158825 0.206989 0.965365 -0.158824 0.206987 0.965366 -0.206985 0.158826 0.965366 -0.206981 0.158821 0.965368 -0.241035 0.0998356 0.965368 -0.241047 0.0998451 0.965364 -0.258675 0.0340574 0.965364 -0.258675 0.0340576 0.965364 -0.258675 -0.0340576 0.965364 -0.258675 -0.0340576 0.965364 -0.241048 -0.0998408 0.965364 -0.241033 -0.0998395 0.965368 -0.20698 -0.158822 0.965368 -0.206987 -0.158825 0.965366 -0.158824 -0.206988 0.965366 -0.158825 -0.206989 0.965365 -0.0998427 -0.241041 0.965365 -0.0998441 -0.241043 0.965365 -0.0340549 -0.258669 0.965366 -0.0340545 -0.258668 0.965366 0.0340538 -0.258668 0.965366 0.0340542 -0.258666 0.965366 0.0998399 -0.241035 0.965367 0.0998407 -0.241043 0.965365 0.158829 -0.206987 0.965365 0.158827 -0.206984 0.965366 0.206985 -0.158826 0.965366 0.206981 -0.158821 0.965368 0.241032 -0.0998414 0.965368 0.241026 -0.0998365 0.96537 0.258653 -0.0340473 0.96537 0.258675 -0.0340577 0.965364 0.258676 0.0340502 0.965364 0.258651 0.0340544 0.96537 0.241026 0.0998387 0.96537 0.241033 0.0998395 0.965368 0.20698 0.158822 0.965368 0.206987 0.158825 0.965366 0.158827 0.206985 0.965366 0.158829 0.206986 0.965365 0.0998427 0.241041 0.965365 0.0998376 0.241035 0.965367 0.0340536 0.258666 0.965366 0.0340545 0.258668 0.965366 -0.0340548 0.258668 0.965366 -0.0926933 0.704065 0.70406 -0.271758 0.656075 0.704069 -0.271758 0.656081 0.704063 -0.432306 0.563383 0.704068 -0.432316 0.563418 0.704033 -0.563419 0.432325 0.704027 -0.563422 0.43233 0.704022 -0.656122 0.271778 0.704018 -0.656093 0.27175 0.704056 -0.704069 0.0926965 0.704055 -0.704074 0.0926992 0.70405 -0.704074 -0.0926973 0.70405 -0.704069 -0.0926986 0.704055 -0.656088 -0.271764 0.704055 -0.656129 -0.271765 0.704017 -0.563423 -0.432328 0.704022 -0.563417 -0.432327 0.704027 -0.432326 -0.563409 0.704034 -0.432295 -0.56339 0.704069 -0.27176 -0.65608 0.704063 -0.271756 -0.656076 0.704069 -0.0926908 -0.704066 0.70406 -0.0926941 -0.704071 0.704053 0.0926916 -0.704072 0.704054 0.0926916 -0.704072 0.704053 0.271765 -0.656092 0.70405 0.271765 -0.656098 0.704044 0.432314 -0.563412 0.704039 0.432307 -0.563387 0.704064 0.563388 -0.432302 0.704066 0.563391 -0.432307 0.70406 0.656081 -0.271761 0.704062 0.656087 -0.271767 0.704054 0.704069 -0.0926966 0.704055 0.704028 -0.0926735 0.7041 0.704027 0.0926909 0.704098 0.704073 0.0926792 0.704054 0.656088 0.271764 0.704055 0.656079 0.271764 0.704063 0.563392 0.432305 0.704061 0.563387 0.432304 0.704066 0.4323 0.563393 0.704063 0.432322 0.563407 0.704038 0.271767 0.656097 0.704045 0.271763 0.656093 0.70405 0.0926917 0.704072 0.704053 0.0926915 0.704072 0.704054 -0.0926916 0.704072 0.704054 -0.126149 0.95821 0.256748 -0.369863 0.892907 0.256746 -0.36986 0.892913 0.25673 -0.588349 0.766774 0.256717 -0.588353 0.766744 0.256794 -0.766755 0.588334 0.256806 -0.766757 0.588352 0.25676 -0.892899 0.36987 0.256762 -0.892893 0.369854 0.256807 -0.958196 0.126131 0.25681 -0.958214 0.126157 0.25673 -0.958217 -0.126134 0.25673 -0.958193 -0.126154 0.256811 -0.892889 -0.369865 0.256807 -0.892904 -0.369858 0.256764 -0.766763 -0.588342 0.256764 -0.766747 -0.588345 0.256806 -0.588336 -0.766758 0.256793 -0.588366 -0.766761 0.256717 -0.369865 -0.892911 0.25673 -0.369859 -0.892909 0.256746 -0.126152 -0.95821 0.256748 -0.126149 -0.958208 0.256758 0.126152 -0.958207 0.256757 0.126149 -0.95821 0.256748 0.369854 -0.892911 0.256746 0.369857 -0.892904 0.256764 0.588352 -0.766753 0.256772 0.58835 -0.766766 0.256739 0.766757 -0.588362 0.256735 0.766756 -0.588351 0.256763 0.892908 -0.369848 0.256763 0.892914 -0.369862 0.256724 0.958216 -0.126159 0.256722 0.958214 -0.126157 0.25673 0.958214 0.126159 0.256729 0.958216 0.126157 0.256722 0.892918 0.369853 0.256725 0.892904 0.369858 0.256761 0.766753 0.588358 0.25676 0.766762 0.588356 0.256735 0.588357 0.76676 0.256739 0.588345 0.766759 0.256772 0.369852 0.892906 0.256764 0.369859 0.892909 0.256746 0.12615 0.95821 0.256748 0.126149 0.958209 0.256752 -0.12615 0.958209 0.256752 -0.0508683 0.222868 -0.973521 -0.132601 0.208377 -0.969018 -0.0794722 0.0996545 -0.991843 -0.208292 0.194976 -0.958436 -0.169068 0.0925253 -0.981252 -0.120742 0.0581468 -0.990979 -0.312075 0.079368 -0.946736 -0.148575 0 -0.988901 -0.151568 -0.000394627 -0.988447 -0.0382502 -0.167584 -0.985115 -0.104556 -0.151647 -0.982889 -0.0793425 -0.0994917 -0.99187 -0.203733 -0.192725 -0.95987 -0.167983 -0.0808974 -0.982465 -0.0996029 -0.0551881 -0.993496 -0.309632 -0.08048 -0.947445 -0.0286275 0.082524 -0.996178 -0.017026 0.175754 -0.984287 0.0400879 0.175638 -0.983638 0.0400886 0.17564 -0.983638 0.112329 0.140856 -0.983637 0.112325 0.140851 -0.983638 0.162314 0.078167 -0.983638 0.162325 0.0781712 -0.983636 0.180169 0 -0.983636 0.180169 0 -0.983636 0.162325 -0.0781724 -0.983636 0.162315 -0.0781661 -0.983638 0.112325 -0.140851 -0.983638 0.112329 -0.140856 -0.983637 0.0400884 -0.175641 -0.983638 0.0400881 -0.175638 -0.983638 -0.039239 -0.175644 -0.983671 0.86349 0.415836 0.285421 0.813446 0.554584 -0.175334 0.614247 0.770245 -0.171532 0.94177 0 0.336257 0.978405 0.110251 -0.174837 0.916677 0.359762 -0.173997 0.863491 -0.415836 0.285417 0.916677 -0.359763 -0.173997 0.978405 -0.110251 -0.174837 0.619016 -0.776225 0.119558 0.642466 -0.746569 -0.172836 0.813447 -0.554583 -0.175334 -0.219224 -0.96048 -0.171521 -0.219224 -0.96048 -0.17152 0.219221 -0.960481 -0.171521 0.219221 -0.960481 -0.171521 0.460017 -0.870357 -0.175681 -0.863491 -0.415836 0.285417 -0.813447 -0.554583 -0.175334 -0.614247 -0.770245 -0.171532 -0.641963 -0.745984 0.177177 -0.460017 -0.870357 -0.175681 -0.94177 0 0.336257 -0.978405 -0.110251 -0.174837 -0.916677 -0.359763 -0.173997 -0.86349 0.415836 0.28542 -0.916677 0.359762 -0.173997 -0.978405 0.110251 -0.174837 -0.619016 0.776225 0.119558 -0.642466 0.746569 -0.172836 -0.813446 0.554584 -0.175334 0.641962 0.745984 0.177177 0.460017 0.870357 -0.175681 0.219221 0.960481 -0.171521 0.219222 0.960482 -0.171512 -0.219224 0.960481 -0.171512 -0.219225 0.96048 -0.171521 -0.460017 0.870357 -0.175681 -0.342206 0.429111 -0.835918 -0.34222 0.429133 -0.835901 -0.494524 0.238153 -0.835901 -0.494498 0.238135 -0.835921 -0.548847 0 -0.835923 -0.548847 0 -0.835923 -0.494497 -0.23814 -0.83592 -0.494526 -0.238149 -0.8359 -0.342222 -0.429131 -0.835901 -0.342203 -0.429113 -0.835918 -0.122135 -0.535107 -0.835909 -0.122138 -0.535114 -0.835904 0.122135 -0.535114 -0.835904 0.122135 -0.535108 -0.835908 0.342206 -0.429111 -0.835918 0.34222 -0.429133 -0.835901 0.494524 -0.238153 -0.835901 0.494498 -0.238135 -0.835921 0.548847 0 -0.835923 0.548847 0 -0.835923 0.494497 0.23814 -0.83592 0.494526 0.238149 -0.8359 0.342222 0.429131 -0.835901 0.342203 0.429113 -0.835918 0.122134 0.535108 -0.835908 0.122136 0.535114 -0.835904 -0.122137 0.535114 -0.835904 -0.122136 0.535107 -0.835909 -0.528944 0.663281 -0.529412 -0.528941 0.663274 -0.529423 -0.76435 0.368088 -0.529414 -0.764363 0.368099 -0.529388 -0.848383 0 -0.529382 -0.848383 0 -0.529382 -0.764365 -0.368095 -0.529389 -0.764349 -0.368091 -0.529415 -0.52894 -0.663275 -0.529422 -0.528946 -0.66328 -0.529412 -0.188779 -0.827082 -0.529431 -0.188775 -0.827075 -0.529444 0.188774 -0.827075 -0.529444 0.188774 -0.827084 -0.529431 0.528944 -0.663281 -0.529412 0.528941 -0.663274 -0.529423 0.76435 -0.368088 -0.529414 0.764363 -0.368099 -0.529388 0.848383 0 -0.529382 0.848383 0 -0.529382 0.764365 0.368095 -0.529389 0.764349 0.368091 -0.529415 0.52894 0.663275 -0.529422 0.528946 0.66328 -0.529412 0.188776 0.827083 -0.529431 0.188772 0.827076 -0.529444 -0.188777 0.827075 -0.529444 -0.188777 0.827083 -0.529431 -0.234196 0.293671 -0.926774 -0.172857 0.0957766 -0.980279 -0.11984 0.0577125 -0.991114 -0.309632 0.08048 -0.947445 -0.150777 0 -0.988568 -0.147769 0.000384737 -0.989022 -0.163701 -0.078835 -0.983355 -0.102359 -0.0560174 -0.993169 -0.312075 -0.079368 -0.946736 -0.0251962 -0.110392 -0.993569 -0.0822638 -0.217494 -0.972589 -0.161746 -0.202821 -0.965765 -0.0489353 -0.0769 -0.995837 -0.208292 -0.194976 -0.958436 -0.0574157 0.0543136 -0.996872 -0.104556 0.151647 -0.982889 -0.0382502 0.167584 -0.985115 -0.039239 0.175644 -0.983671 0.0400879 0.175638 -0.983638 0.0400886 0.17564 -0.983638 0.112329 0.140856 -0.983637 0.112325 0.140851 -0.983638 0.162314 0.078167 -0.983638 0.162326 0.0781715 -0.983636 0.180169 0 -0.983636 0.180169 0 -0.983636 0.162325 -0.0781724 -0.983636 0.162315 -0.0781661 -0.983638 0.112325 -0.140851 -0.983638 0.11233 -0.140857 -0.983637 0.0400886 -0.175642 -0.983638 0.0400881 -0.175638 -0.983638 -0.017026 -0.175754 -0.984287 0.863491 0.415836 0.285417 0.813447 0.554583 -0.175334 0.614247 0.770245 -0.171532 0.94177 0 0.336257 0.978405 0.110251 -0.174838 0.916676 0.359762 -0.174 0.86349 -0.415836 0.28542 0.916677 -0.359762 -0.173997 0.978405 -0.110251 -0.174837 0.619015 -0.776224 0.119565 0.642466 -0.746569 -0.172836 0.813446 -0.554584 -0.175334 -0.219225 -0.96048 -0.171521 -0.219225 -0.96048 -0.17152 0.219222 -0.96048 -0.171521 0.219222 -0.96048 -0.171521 0.460012 -0.870359 -0.175681 -0.86349 -0.415836 0.285421 -0.813446 -0.554584 -0.175334 -0.614247 -0.770245 -0.171532 -0.641962 -0.745983 0.177185 -0.460012 -0.870359 -0.175681 -0.94177 0 0.336257 -0.978405 -0.110251 -0.174837 -0.916677 -0.359762 -0.173997 -0.863491 0.415836 0.285417 -0.916676 0.359762 -0.174 -0.978405 0.110251 -0.174838 -0.619016 0.776225 0.119558 -0.642466 0.746569 -0.172836 -0.813447 0.554583 -0.175334 0.641962 0.745984 0.177177 0.460017 0.870357 -0.175681 0.219221 0.960481 -0.171521 0.219221 0.960481 -0.171521 -0.219224 0.96048 -0.17152 -0.219224 0.96048 -0.171521 -0.460017 0.870357 -0.175681 -0.342206 0.429111 -0.835918 -0.34222 0.429133 -0.835901 -0.494524 0.238153 -0.835901 -0.494498 0.238135 -0.835921 -0.548847 0 -0.835923 -0.548847 0 -0.835923 -0.494497 -0.23814 -0.83592 -0.494526 -0.238149 -0.8359 -0.342222 -0.42913 -0.835901 -0.342201 -0.42911 -0.83592 -0.122134 -0.535104 -0.835911 -0.122138 -0.535114 -0.835904 0.122135 -0.535114 -0.835904 0.122134 -0.535104 -0.835911 0.342205 -0.429108 -0.83592 0.34222 -0.429133 -0.835901 0.494524 -0.238153 -0.835901 0.494498 -0.238135 -0.835921 0.548847 0 -0.835923 0.548847 0 -0.835923 0.494497 0.23814 -0.83592 0.494526 0.238149 -0.8359 0.342222 0.429131 -0.835901 0.342203 0.429113 -0.835918 0.122134 0.535108 -0.835908 0.122136 0.535114 -0.835904 -0.122137 0.535114 -0.835904 -0.122136 0.535107 -0.835909 -0.528944 0.663281 -0.529412 -0.528941 0.663274 -0.529423 -0.76435 0.368088 -0.529414 -0.764363 0.368099 -0.529388 -0.848383 0 -0.529382 -0.848383 0 -0.529382 -0.764365 -0.368095 -0.529389 -0.764349 -0.368091 -0.529415 -0.52894 -0.663275 -0.529422 -0.528946 -0.66328 -0.529412 -0.188779 -0.827082 -0.529431 -0.188777 -0.827078 -0.529438 0.188775 -0.827078 -0.529439 0.188775 -0.827083 -0.529431 0.528944 -0.663281 -0.529412 0.528941 -0.663274 -0.529423 0.76435 -0.368088 -0.529414 0.764363 -0.368099 -0.529388 0.848383 0 -0.529382 0.848383 0 -0.529382 0.764365 0.368095 -0.529389 0.764349 0.368091 -0.529415 0.52894 0.663275 -0.529422 0.528946 0.66328 -0.529412 0.188776 0.827083 -0.529431 0.188772 0.827076 -0.529444 -0.188777 0.827075 -0.529444 -0.188777 0.827083 -0.529431 -0.104034 -0.0424221 0.993669 -0.174974 -0.0842637 0.980961 -0.272154 -0.0353219 0.961605 -0.127042 0 0.991897 -0.272154 0.0353219 0.961605 -0.189287 0.0771863 0.978883 -0.119672 0.0576318 0.991139 -0.261242 0.196668 0.945026 -0.0926461 0.116174 0.988899 -0.0962392 0.12214 0.987836 -0.261242 -0.196668 0.945026 -0.0908524 -0.115303 0.989167 -0.0958756 -0.120223 0.988106 -0.117223 -0.235301 0.964828 -0.0259153 -0.113542 0.993195 -0.0258722 -0.175755 0.984094 0.0400961 -0.175672 0.983632 0.0400955 -0.175671 0.983632 0.112341 -0.140872 0.983633 0.112347 -0.140879 0.983632 0.162347 -0.0781804 0.983632 0.162336 -0.0781764 0.983634 0.180178 0 0.983634 0.180178 0 0.983634 0.162336 0.0781753 0.983634 0.162346 0.0781813 0.983632 0.112346 0.140879 0.983632 0.112341 0.140871 0.983634 0.0400955 0.175669 0.983632 0.0400959 0.175673 0.983632 -0.0400963 0.175672 0.983632 -0.0144422 0.0981092 0.995071 -0.117221 0.235298 0.964828 0.86346 -0.415821 -0.285534 0.813425 -0.554614 0.175334 0.614254 -0.770239 0.171532 0.941727 0 -0.336377 0.978429 -0.110254 0.174701 0.916698 -0.35977 0.173869 0.863461 0.415822 -0.285531 0.916698 0.359771 0.173869 0.978429 0.110253 0.174701 0.619022 0.776218 -0.119572 0.642475 0.746561 0.172836 0.813426 0.554613 0.175334 -0.219224 0.96048 0.171521 -0.219224 0.96048 0.17152 0.219221 0.960481 0.171521 0.219221 0.960481 0.171521 0.460017 0.870357 0.175681 -0.863491 0.415836 -0.285417 -0.813447 0.554583 0.175334 -0.614247 0.770245 0.171532 -0.641963 0.745984 -0.177177 -0.460017 0.870357 0.175681 -0.94177 0 -0.336257 -0.978433 0.110224 0.174701 -0.91669 0.35979 0.173869 -0.86349 -0.415836 -0.28542 -0.91669 -0.35979 0.173869 -0.978433 -0.110224 0.174701 -0.619016 -0.776225 -0.119558 -0.642466 -0.746569 0.172836 -0.813446 -0.554584 0.175334 0.641969 -0.745974 -0.177195 0.460017 -0.870357 0.175681 0.219222 -0.96048 0.171521 0.219222 -0.96048 0.171521 -0.219225 -0.96048 0.17152 -0.219225 -0.96048 0.171521 -0.460017 -0.870357 0.175681 -0.342213 -0.429119 0.835911 -0.34221 -0.429114 0.835915 -0.494505 -0.238144 0.835914 -0.494479 -0.238126 0.835934 -0.548827 0 0.835936 -0.548827 0 0.835936 -0.494478 0.238131 0.835934 -0.494508 0.23814 0.835914 -0.342209 0.429114 0.835915 -0.342216 0.42912 0.835909 -0.122133 0.535099 0.835914 -0.122132 0.535094 0.835918 0.122132 0.535094 0.835917 0.122133 0.535099 0.835914 0.34221 0.429123 0.83591 0.342207 0.429117 0.835914 0.494509 0.238138 0.835913 0.494523 0.238147 0.835902 0.548881 0 0.835901 0.548881 0 0.835901 0.494524 -0.238145 0.835903 0.494508 -0.23814 0.835914 0.342206 -0.429118 0.835914 0.34221 -0.429121 0.835912 0.122132 -0.535096 0.835916 0.122132 -0.535094 0.835918 -0.122132 -0.535094 0.835918 -0.122132 -0.535096 0.835916 -0.52893 -0.663251 0.529463 -0.528941 -0.663274 0.529423 -0.76435 -0.368088 0.529414 -0.764363 -0.368099 0.529388 -0.848383 0 0.529382 -0.848383 0 0.529382 -0.764365 0.368095 0.529389 -0.764349 0.368091 0.529415 -0.528946 0.66327 0.529423 -0.528925 0.663254 0.529464 -0.188773 0.827072 0.52945 -0.188775 0.827075 0.529444 0.188774 0.827075 0.529444 0.188774 0.827084 0.529431 0.528944 0.663281 0.529412 0.528927 0.663243 0.529476 0.764308 0.368068 0.52949 0.764321 0.368078 0.529464 0.848331 0 0.529466 0.848331 0 0.529466 0.764322 -0.368075 0.529464 0.764306 -0.368071 0.52949 0.52892 -0.66325 0.529475 0.528952 -0.663275 0.529411 0.188776 -0.827083 0.529431 0.188774 -0.827079 0.529439 -0.188775 -0.827078 0.529439 -0.188775 -0.827071 0.52945 -0.104034 -0.0424221 0.993669 -0.174974 -0.0842637 0.980961 -0.272154 -0.0353219 0.961605 -0.127042 0 0.991897 -0.272154 0.0353219 0.961605 -0.189287 0.0771863 0.978883 -0.119672 0.0576318 0.991139 -0.261242 0.196668 0.945026 -0.0926461 0.116174 0.988899 -0.0962392 0.12214 0.987836 -0.261242 -0.196668 0.945026 -0.0908524 -0.115303 0.989167 -0.095875 -0.120223 0.988107 -0.117221 -0.235298 0.964828 -0.0259153 -0.113542 0.993195 -0.0258722 -0.175755 0.984094 0.0400963 -0.175672 0.983632 0.0400951 -0.175669 0.983632 0.11234 -0.140871 0.983634 0.112347 -0.140879 0.983632 0.162347 -0.0781804 0.983632 0.162336 -0.0781764 0.983634 0.180178 0 0.983634 0.180178 0 0.983634 0.162336 0.0781753 0.983634 0.162346 0.0781813 0.983632 0.112346 0.140879 0.983632 0.112341 0.140871 0.983634 0.0400955 0.175669 0.983632 0.0400959 0.175673 0.983632 -0.0400963 0.175672 0.983632 -0.0144422 0.0981092 0.995071 -0.117221 0.235298 0.964828 0.86346 -0.415821 -0.285534 0.813425 -0.554614 0.175334 0.614254 -0.770239 0.171532 0.941727 0 -0.336377 0.978429 -0.110254 0.174701 0.916698 -0.35977 0.173869 0.863461 0.415822 -0.285531 0.916698 0.359771 0.173869 0.978429 0.110253 0.174701 0.619022 0.776218 -0.119572 0.642475 0.746561 0.172836 0.813426 0.554613 0.175334 -0.219224 0.96048 0.171521 -0.219224 0.96048 0.17152 0.219221 0.960481 0.171521 0.219221 0.960481 0.171521 0.460017 0.870357 0.175681 -0.863491 0.415836 -0.285417 -0.813447 0.554583 0.175334 -0.614247 0.770245 0.171532 -0.641963 0.745984 -0.177177 -0.460017 0.870357 0.175681 -0.94177 0 -0.336257 -0.978433 0.110224 0.174701 -0.91669 0.35979 0.173869 -0.86349 -0.415836 -0.28542 -0.91669 -0.35979 0.173869 -0.978433 -0.110224 0.174701 -0.619016 -0.776225 -0.119558 -0.642466 -0.746569 0.172836 -0.813446 -0.554584 0.175334 0.641969 -0.745974 -0.177195 0.460017 -0.870357 0.175681 0.219221 -0.960481 0.171521 0.219222 -0.960482 0.171512 -0.219224 -0.960481 0.171512 -0.219225 -0.96048 0.171521 -0.460017 -0.870357 0.175681 -0.342214 -0.429121 0.835909 -0.34221 -0.429114 0.835915 -0.494505 -0.238144 0.835914 -0.494479 -0.238126 0.835934 -0.548827 0 0.835936 -0.548827 0 0.835936 -0.494478 0.238131 0.835934 -0.494508 0.23814 0.835914 -0.342209 0.429114 0.835915 -0.342216 0.42912 0.835909 -0.122133 0.535099 0.835914 -0.122132 0.535094 0.835918 0.122132 0.535094 0.835917 0.122133 0.535099 0.835914 0.34221 0.429123 0.83591 0.342207 0.429117 0.835914 0.494509 0.238138 0.835913 0.494523 0.238147 0.835902 0.548881 0 0.835901 0.548881 0 0.835901 0.494524 -0.238145 0.835903 0.494508 -0.23814 0.835914 0.342206 -0.429118 0.835914 0.342211 -0.429123 0.83591 0.122133 -0.535099 0.835914 0.122132 -0.535094 0.835918 -0.122132 -0.535094 0.835917 -0.122133 -0.535099 0.835914 -0.52893 -0.663251 0.529463 -0.528941 -0.663274 0.529423 -0.76435 -0.368088 0.529414 -0.764363 -0.368099 0.529388 -0.848383 0 0.529382 -0.848383 0 0.529382 -0.764365 0.368095 0.529389 -0.764349 0.368091 0.529415 -0.528946 0.66327 0.529423 -0.528925 0.663254 0.529464 -0.188773 0.827072 0.52945 -0.188775 0.827075 0.529444 0.188774 0.827075 0.529444 0.188774 0.827084 0.529431 0.528944 0.663281 0.529412 0.528927 0.663243 0.529476 0.764308 0.368068 0.52949 0.764321 0.368078 0.529464 0.848331 0 0.529466 0.848331 0 0.529466 0.764322 -0.368075 0.529464 0.764306 -0.368071 0.52949 0.52892 -0.66325 0.529475 0.528952 -0.663275 0.529411 0.188776 -0.827083 0.529431 0.188772 -0.827076 0.529444 -0.188774 -0.827075 0.529444 -0.188774 -0.827071 0.52945 0.258784 0.965788 -0.016864 0.482452 0.875922 0 0.678064 0.735002 0 0.70677 0.706767 -0.0309476 0.845182 0.534479 0 0.948535 0.316672 0 0.965064 0.258587 -0.0422363 0.998177 0.0603593 0 0.983623 -0.180238 0 0.964683 -0.258485 -0.0507103 0.903437 -0.428721 0 0.774605 -0.632446 0 0.705985 -0.705982 -0.0563456 0.584527 -0.811374 0 0.37336 -0.927686 0 0.258367 -0.964233 -0.0591699 0.120539 -0.992709 0 -0.120535 -0.992709 0 -0.258363 -0.964234 -0.059172 -0.37336 -0.927686 0 -0.584527 -0.811374 0 -0.705985 -0.705982 -0.0563456 -0.774605 -0.632446 0 -0.903457 -0.428678 0 -0.964684 -0.258485 -0.0506959 -0.983619 -0.180261 0 -0.998177 0.0603593 0 -0.965064 0.258587 -0.0422363 -0.948535 0.316672 0 -0.845182 0.534479 0 -0.70677 0.706767 -0.0309476 -0.678064 0.735002 0 -0.482452 0.875922 0 -0.258779 0.965789 -0.0168643 -0.239313 0.970942 0 0.239317 0.970941 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707112 0.707102 0 0.707112 0.707102 0 0.965923 0.258828 0 0.965923 0.258828 0 0.965924 -0.258827 0 0.965924 -0.258827 0 0.707112 -0.707102 0 0.707112 -0.707102 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.7071 -0.707113 0 -0.7071 -0.707113 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.7071 0.707113 0 -0.7071 0.707113 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.258784 0.965788 -0.016864 0.482452 0.875922 0 0.678064 0.735002 0 0.70677 0.706767 -0.0309476 0.845182 0.534479 0 0.948535 0.316672 0 0.965064 0.258587 -0.0422363 0.998177 0.0603593 0 0.983623 -0.180238 0 0.964683 -0.258485 -0.0507103 0.903437 -0.428721 0 0.774605 -0.632446 0 0.705985 -0.705982 -0.0563456 0.584527 -0.811374 0 0.37336 -0.927686 0 0.258367 -0.964233 -0.0591699 0.120539 -0.992709 0 -0.120535 -0.992709 0 -0.258363 -0.964234 -0.059172 -0.37336 -0.927686 0 -0.584527 -0.811374 0 -0.705985 -0.705982 -0.0563456 -0.774605 -0.632446 0 -0.903457 -0.428678 0 -0.964684 -0.258485 -0.0506959 -0.983619 -0.180261 0 -0.998177 0.0603593 0 -0.965064 0.258587 -0.0422363 -0.948535 0.316672 0 -0.845182 0.534479 0 -0.70677 0.706767 -0.0309476 -0.678064 0.735002 0 -0.482452 0.875922 0 -0.258779 0.965789 -0.0168643 -0.239313 0.970942 0 0.239317 0.970941 0 0.25882 0.965926 0 0.25882 0.965926 0 0.707112 0.707102 0 0.707112 0.707102 0 0.965923 0.258828 0 0.965923 0.258828 0 0.965924 -0.258827 0 0.965924 -0.258827 0 0.707112 -0.707102 0 0.707112 -0.707102 0 0.25882 -0.965926 0 0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.25882 -0.965926 0 -0.7071 -0.707113 0 -0.7071 -0.707113 0 -0.965929 -0.258806 0 -0.965929 -0.258806 0 -0.965929 0.258806 0 -0.965929 0.258806 0 -0.7071 0.707113 0 -0.7071 0.707113 0 -0.25882 0.965926 0 -0.25882 0.965926 0 0.382645 0.92379 0.0139651 0.222255 0.973772 -0.0486868 0.130526 0.991445 0 -0.130526 0.991445 0 -0.222258 0.973771 -0.0486885 -0.382654 0.923786 0.0139636 -0.467284 0.884107 0 -0.60875 0.793362 0 -0.652003 0.757651 -0.0292666 -0.793251 0.608664 0.0167579 -0.826247 0.563309 0 -0.923873 0.3827 0 -0.930824 0.365338 -0.00976404 -0.991412 0.130504 0.00837468 -0.993714 0.111945 0 -0.991447 -0.130509 0 -0.993667 -0.11194 0.00976291 -0.923815 -0.382676 -0.0111489 -0.930869 -0.365355 0 -0.793362 -0.608751 0 -0.825892 -0.563069 0.0292611 -0.608221 -0.792673 -0.0416664 -0.652282 -0.757976 0 -0.382691 -0.923876 0 -0.46673 -0.883058 0.0486918 -0.130079 -0.988039 -0.082816 -0.222523 -0.974928 0 0.130527 -0.991445 0 0.222255 -0.973772 -0.0486864 0.382645 -0.92379 0.0139651 0.467284 -0.884107 0 0.608763 -0.793353 0 0.652012 -0.757644 -0.029264 0.793238 -0.608682 0.0167531 0.826225 -0.563341 0 0.923882 -0.382678 0 0.930832 -0.365317 -0.00976244 0.991409 -0.13053 0.00837276 0.993711 -0.111976 0 0.991444 0.130534 0 0.993664 0.11197 0.00976069 0.923824 0.382654 -0.0111472 0.930876 0.365335 0 0.79335 0.608766 0 0.825872 0.563099 0.0292532 0.608234 0.792664 -0.0416629 0.652291 0.757968 0 0.467284 0.884107 0 0.382645 0.92379 0.0139651 0.222255 0.973772 -0.0486868 0.130526 0.991445 0 -0.130526 0.991445 0 -0.222258 0.973771 -0.0486885 -0.382654 0.923786 0.0139636 -0.467284 0.884107 0 -0.60875 0.793362 0 -0.652003 0.757651 -0.0292666 -0.793251 0.608664 0.0167579 -0.826247 0.563309 0 -0.923873 0.3827 0 -0.930824 0.365338 -0.00976404 -0.991412 0.130504 0.00837468 -0.993714 0.111945 0 -0.991447 -0.130509 0 -0.993667 -0.11194 0.00976291 -0.923815 -0.382676 -0.0111489 -0.930869 -0.365355 0 -0.793362 -0.608751 0 -0.825892 -0.563069 0.0292611 -0.608221 -0.792673 -0.0416664 -0.652282 -0.757976 0 -0.382691 -0.923876 0 -0.46673 -0.883058 0.0486918 -0.130079 -0.988039 -0.082816 -0.222523 -0.974928 0 0.130527 -0.991445 0 0.222255 -0.973772 -0.0486864 0.382645 -0.92379 0.0139651 0.467284 -0.884107 0 0.608763 -0.793353 0 0.652012 -0.757644 -0.029264 0.793238 -0.608682 0.0167531 0.826225 -0.563341 0 0.923882 -0.382678 0 0.930832 -0.365317 -0.00976244 0.991409 -0.13053 0.00837276 0.993711 -0.111976 0 0.991444 0.130534 0 0.993664 0.11197 0.00976069 0.923824 0.382654 -0.0111472 0.930876 0.365335 0 0.79335 0.608766 0 0.825872 0.563099 0.0292532 0.608234 0.792664 -0.0416629 0.652291 0.757968 0 0.467284 0.884107 0 0.258755 -0.965681 0.022483 0.482452 -0.875922 0 0.678065 -0.735002 0 0.706507 -0.706503 0.0412482 0.845182 -0.534479 0 0.948535 -0.316673 0 0.964395 -0.258408 0.0562766 0.998177 -0.0603591 0 0.983619 0.180261 0 0.963721 0.258228 0.0675273 0.903457 0.428678 0 0.774605 0.632446 0 0.705115 0.705112 0.0750353 0.584527 0.811374 0 0.37336 0.927686 0 0.258016 0.962923 0.0787864 0.120539 0.992709 0 -0.120535 0.992709 0 -0.258012 0.962924 0.0787892 -0.37336 0.927686 0 -0.584527 0.811374 0 -0.705115 0.705112 0.0750353 -0.774605 0.632446 0 -0.903457 0.428678 0 -0.963721 0.258228 0.0675273 -0.983619 0.180261 0 -0.998177 -0.0603591 0 -0.964395 -0.258408 0.0562767 -0.948535 -0.316673 0 -0.845182 -0.534479 0 -0.706507 -0.706503 0.0412482 -0.678065 -0.735002 0 -0.482452 -0.875922 0 -0.258751 -0.965682 0.0224834 -0.239313 -0.970942 0 0.239317 -0.970941 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707112 -0.707102 0 0.707112 -0.707102 0 0.965924 -0.258827 0 0.965924 -0.258827 0 0.965923 0.258828 0 0.965923 0.258828 0 0.707112 0.707102 0 0.707112 0.707102 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258814 0.965927 0 -0.258814 0.965927 0 -0.707112 0.707102 0 -0.707112 0.707102 0 -0.965923 0.258828 0 -0.965923 0.258828 0 -0.965924 -0.258827 0 -0.965924 -0.258827 0 -0.707112 -0.707102 0 -0.707112 -0.707102 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 0.258755 -0.965681 0.022483 0.482452 -0.875922 0 0.678065 -0.735002 0 0.706507 -0.706503 0.0412483 0.845182 -0.534479 0 0.948535 -0.316672 0 0.964395 -0.258408 0.0562763 0.998177 -0.0603593 0 0.983619 0.180261 0 0.963721 0.258227 0.0675274 0.903457 0.428678 0 0.774605 0.632446 0 0.705115 0.705112 0.0750353 0.584527 0.811374 0 0.37336 0.927686 0 0.258016 0.962923 0.0787864 0.120539 0.992709 0 -0.120535 0.992709 0 -0.258012 0.962924 0.0787892 -0.37336 0.927686 0 -0.584527 0.811374 0 -0.705115 0.705112 0.0750353 -0.774605 0.632446 0 -0.903457 0.428678 0 -0.963721 0.258227 0.0675274 -0.983619 0.180261 0 -0.998177 -0.0603593 0 -0.964395 -0.258408 0.0562763 -0.948535 -0.316672 0 -0.845182 -0.534479 0 -0.706507 -0.706503 0.0412483 -0.678065 -0.735002 0 -0.482452 -0.875922 0 -0.258751 -0.965682 0.0224834 -0.239313 -0.970942 0 0.239317 -0.970941 0 0.25882 -0.965926 0 0.25882 -0.965926 0 0.707112 -0.707102 0 0.707112 -0.707102 0 0.965923 -0.258828 0 0.965923 -0.258828 0 0.965924 0.258827 0 0.965924 0.258827 0 0.707112 0.707102 0 0.707112 0.707102 0 0.25882 0.965926 0 0.25882 0.965926 0 -0.258814 0.965927 0 -0.258814 0.965927 0 -0.707112 0.707102 0 -0.707112 0.707102 0 -0.965924 0.258827 0 -0.965924 0.258827 0 -0.965923 -0.258828 0 -0.965923 -0.258828 0 -0.707112 -0.707102 0 -0.707112 -0.707102 0 -0.258814 -0.965927 0 -0.258814 -0.965927 0 0.38262 -0.923729 -0.0180712 0.222077 -0.972995 0.0629561 0.130526 -0.991445 0 -0.130529 -0.991444 0 -0.22208 -0.972994 0.0629545 -0.38262 -0.923729 -0.0180712 -0.467284 -0.884107 0 -0.608763 -0.793352 0 -0.651815 -0.757433 0.0378521 -0.793163 -0.608623 -0.0216926 -0.826247 -0.563309 0 -0.923882 -0.382678 0 -0.930802 -0.365306 0.0126334 -0.991386 -0.130526 -0.0108351 -0.993711 -0.111975 0 -0.991444 0.130534 0 -0.993632 0.111967 -0.0126311 -0.923786 0.382638 0.0144251 -0.930876 0.365335 0 -0.793349 0.608767 0 -0.825653 0.562906 -0.0378709 -0.607878 0.7922 0.0538745 -0.652282 0.757976 0 -0.382682 0.92388 0 -0.466357 0.882352 -0.0629707 -0.129782 0.985761 0.106923 -0.222523 0.974928 0 0.130527 0.991445 0 0.222078 0.972994 0.0629557 0.38262 0.923729 -0.0180712 0.467284 0.884107 0 0.608763 0.793352 0 0.651815 0.757433 0.0378521 0.793162 0.608624 -0.0216923 0.826246 0.56331 0 0.923882 0.382678 0 0.930802 0.365306 0.0126333 0.991386 0.130526 -0.0108351 0.993711 0.111976 0 0.991444 -0.130534 0 0.993632 -0.111966 -0.0126311 0.923786 -0.382638 0.0144252 0.930876 -0.365335 0 0.79335 -0.608766 0 0.825654 -0.562905 -0.0378713 0.607878 -0.7922 0.0538745 0.652282 -0.757976 0 0.467284 -0.884107 0 0.38262 -0.923729 -0.0180702 0.222078 -0.972994 0.0629568 0.130526 -0.991445 0 -0.130529 -0.991444 0 -0.222081 -0.972994 0.0629551 -0.38262 -0.923729 -0.0180702 -0.46728 -0.884109 0 -0.608764 -0.793352 0 -0.651816 -0.757432 0.0378518 -0.793162 -0.608624 -0.0216923 -0.826246 -0.56331 0 -0.923882 -0.382678 0 -0.930802 -0.365306 0.0126333 -0.991386 -0.130526 -0.0108351 -0.993711 -0.111976 0 -0.991444 0.130534 0 -0.993632 0.111967 -0.0126309 -0.923786 0.382638 0.0144256 -0.930876 0.365335 0 -0.79335 0.608766 0 -0.825654 0.562905 -0.0378713 -0.607878 0.7922 0.0538745 -0.652282 0.757976 0 -0.382682 0.92388 0 -0.466357 0.882352 -0.0629707 -0.129781 0.985761 0.106924 -0.222522 0.974928 0 0.130526 0.991445 0 0.222077 0.972995 0.0629561 0.38262 0.923729 -0.0180712 0.467284 0.884107 0 0.608763 0.793352 0 0.651815 0.757433 0.0378521 0.793163 0.608623 -0.0216926 0.826247 0.563309 0 0.923882 0.382678 0 0.930802 0.365306 0.0126337 0.991386 0.130526 -0.010835 0.993711 0.111976 0 0.991444 -0.130534 0 0.993632 -0.111967 -0.0126311 0.923786 -0.382638 0.0144251 0.930876 -0.365335 0 0.793349 -0.608767 0 0.825653 -0.562906 -0.0378709 0.607879 -0.7922 0.0538742 0.652283 -0.757976 0 0.46728 -0.884109 0 0.965924 0 -0.258827 0.965924 0 -0.258827 0.707111 0 -0.707102 0.707111 0 -0.707102 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.7071 0 -0.707114 -0.7071 0 -0.707114 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.965929 0 0.258806 -0.965929 0 0.258806 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.707111 0 0.707102 0.707111 0 0.707102 0.965923 0 0.258828 0.965923 0 0.258828 0.965924 0 -0.258827 0.965924 0 -0.258827 0.707111 0 -0.707102 0.707111 0 -0.707102 0.258814 0 -0.965927 0.258814 0 -0.965927 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707111 0 -0.707102 -0.707111 0 -0.707102 -0.965924 0 -0.258827 -0.965924 0 -0.258827 -0.965923 0 0.258828 -0.965923 0 0.258828 -0.707113 0 0.707101 -0.707113 0 0.707101 -0.258817 0 0.965926 -0.258817 0 0.965926 0.258811 0 0.965928 0.258811 0 0.965928 0.707113 0 0.707101 0.707113 0 0.707101 0.965923 0 0.258828 0.965923 0 0.258828 0.965924 0 -0.258827 0.965924 0 -0.258827 0.707111 0 -0.707102 0.707111 0 -0.707102 0.25882 0 -0.965926 0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.7071 0 -0.707114 -0.7071 0 -0.707114 -0.965929 0 -0.258806 -0.965929 0 -0.258806 -0.965929 0 0.258806 -0.965929 0 0.258806 -0.7071 0 0.707114 -0.7071 0 0.707114 -0.25882 0 0.965926 -0.25882 0 0.965926 0.25882 0 0.965926 0.25882 0 0.965926 0.707111 0 0.707102 0.707111 0 0.707102 0.965923 0 0.258828 0.965923 0 0.258828 0.965924 0 -0.258827 0.965924 0 -0.258827 0.707111 0 -0.707102 0.707111 0 -0.707102 0.258814 0 -0.965927 0.258814 0 -0.965927 -0.25882 0 -0.965926 -0.25882 0 -0.965926 -0.707111 0 -0.707102 -0.707111 0 -0.707102 -0.965924 0 -0.258827 -0.965924 0 -0.258827 -0.965923 0 0.258828 -0.965923 0 0.258828 -0.707113 0 0.707101 -0.707113 0 0.707101 -0.258817 0 0.965926 -0.258817 0 0.965926 0.258811 0 0.965928 0.258811 0 0.965928 0.707113 0 0.707101 0.707113 0 0.707101 0.965923 0 0.258828 0.965923 0 0.258828 0.725902 -0.0114049 0.687703 0.785061 -0.144202 0.6024 0.512508 0.0796966 0.854976 0.608762 5.52598e-06 0.793353 0.301148 -1.00209e-06 0.953577 0.380828 -0.09841 0.919394 0.0438896 0.0597041 0.997251 0.130527 -2.28158e-06 0.991445 -0.131233 2.29393e-06 0.991352 -0.130523 -0.00049574 0.991445 -0.383342 0.000493644 0.923606 -0.382685 -4.22121e-06 0.923879 -0.582026 9.3443e-06 0.81317 -0.608667 0.017625 0.79323 -0.772939 -0.0237498 0.634036 -0.793353 -1.62098e-06 0.608762 -0.900716 1.12555e-05 0.434408 -0.923619 0.0239172 0.382564 -0.981896 -0.0426809 0.184548 -0.991445 0 0.130525 -0.968078 0 -0.250649 -0.515702 6.7141e-06 -0.856768 -0.973118 -0.191387 -0.128113 -0.923864 0.00656994 -0.382665 -0.725356 -0.0129841 -0.688252 -0.780547 -0.17894 -0.598938 -0.608704 0.0137368 -0.793278 -0.044083 0 -0.999028 -0.301147 1.39738e-06 -0.953578 -0.37957 -0.12733 -0.916359 -0.130479 0.0261913 -0.991105 0.131233 0 -0.991352 0.130527 -0.000638349 -0.991445 0.38336 0.000635757 -0.923599 0.382685 -5.29455e-06 -0.923879 0.582027 1.17203e-05 -0.81317 0.608622 0.0214543 -0.79317 0.771722 -0.0285229 -0.63532 0.793351 -1.84694e-06 -0.608764 0.900718 1.28238e-05 -0.434405 0.923564 0.0263125 -0.382541 0.981062 -0.0456204 -0.188245 0.991445 0 -0.130525 0.968078 0 0.250649 0.977129 -0.169325 0.128641 0.923868 0.00578878 0.382667 0.130489 0.0239421 -0.991161 0.608728 0.0106129 -0.793308 0.513858 -4.93578e-06 -0.857875 0.382676 -1.18199e-05 -0.923882 0.362741 -0.0161041 -0.931751 0.175418 0.00780509 -0.984463 0.991445 4.02327e-07 -0.130525 0.985593 -0.0345158 -0.165572 0.923618 0.023981 -0.382564 0.908601 -6.64533e-07 -0.417666 0.793353 -1.22963e-05 -0.608762 0.822634 0.0428748 -0.566952 0.664692 -0.0378428 -0.746158 0.793103 0.0250707 0.608571 0.811485 -1.35501e-05 0.584373 0.923884 1.6924e-06 0.382673 0.896935 0.0646073 0.437417 0.986837 -0.0963009 0.129919 0.975807 0.0365789 0.215554 0.999678 -7.82278e-08 0.0253791 -0.382551 0.0265226 0.923554 -0.300103 -0.0362522 0.953218 -0.130458 0.0324654 0.990922 -0.0821396 6.7375e-06 0.996621 0.130527 -1.07064e-05 0.991445 0.0854227 0.0487089 0.995153 0.381869 -0.0649148 0.921934 0.33404 0.0106221 0.942499 0.60874 -0.0083899 0.793325 0.579071 0.0333661 0.814594 0.707786 -0.00736152 0.706389 -0.608597 0.0233058 -0.793138 -0.696072 -0.02249 -0.717619 -0.793145 0.0229059 -0.608603 -0.826841 5.04839e-06 -0.562436 -0.923874 3.43506e-06 -0.382696 -0.908834 0.0260733 -0.416343 -0.990894 -0.0333213 -0.130453 -0.985968 0 -0.166937 -0.991445 0 0.130525 -0.97545 -0.0600727 0.211869 -0.923588 0.0249062 0.382576 -0.890957 5.778e-06 0.454087 -0.793353 3.26931e-05 0.608762 -0.775817 -0.0228109 0.630546 -0.608655 0.0187321 0.793214 -0.588281 3.097e-05 0.808656 -0.467597 -5.2307e-06 0.883942 0.0673257 0 -0.997731 -0.0616154 0 -0.9981 -0.130489 0.0238886 -0.991162 -0.249855 -0.0232646 -0.968004 -0.382578 0.0236659 -0.92362 -0.437631 5.96168e-06 -0.899155 -0.550086 8.16975e-06 -0.835108 -0.725902 0.0114049 0.687703 -0.785061 0.144202 0.6024 -0.512508 -0.0796966 0.854976 -0.608762 -5.52598e-06 0.793353 -0.301148 1.00209e-06 0.953577 -0.380828 0.0984098 0.919394 -0.0438896 -0.059704 0.997251 -0.130523 0 0.991445 0.131233 0 0.991352 0.130527 0.000495726 0.991445 0.383342 -0.000493643 0.923606 0.382685 4.22121e-06 0.923879 0.582026 -9.3443e-06 0.81317 0.608667 -0.017625 0.79323 0.772939 0.0237498 0.634036 0.793353 1.62098e-06 0.608762 0.900716 -1.12555e-05 0.434408 0.923619 -0.0239172 0.382564 0.981896 0.0426808 0.184548 0.991445 0 0.130525 0.968078 0 -0.250649 0.515702 -6.7141e-06 -0.856768 0.973118 0.191387 -0.128113 0.923864 -0.00656994 -0.382665 0.725356 0.0129841 -0.688252 0.780547 0.178939 -0.598938 0.608704 -0.0137367 -0.793278 0.044083 1.00135e-06 -0.999028 0.301147 -1.39738e-06 -0.953578 0.37957 0.12733 -0.916359 0.130482 -0.0261894 -0.991105 -0.131233 -2.98097e-06 -0.991352 -0.130523 0.000638363 -0.991445 -0.38336 -0.000635756 -0.923599 -0.382685 5.29454e-06 -0.923879 -0.582027 -1.17203e-05 -0.81317 -0.608622 -0.0214543 -0.79317 -0.771722 0.0285229 -0.63532 -0.793351 1.84694e-06 -0.608764 -0.900718 -1.28238e-05 -0.434405 -0.923564 -0.0263124 -0.382541 -0.981062 0.0456203 -0.188245 -0.991445 0 -0.130525 -0.968078 0 0.250649 -0.977129 0.169325 0.128641 -0.923868 -0.00578878 0.382667 -0.991349 -0.0139445 -0.130513 -0.97946 0.0276672 -0.199731 -0.923662 -0.02142 -0.382608 -0.904718 -4.7798e-06 -0.426011 -0.793353 -6.83025e-06 -0.608762 -0.820099 -0.0325617 -0.571295 -0.608181 0.0436728 -0.792596 -0.650534 -0.00776924 -0.759438 -0.382678 0.00610489 -0.923862 -0.362171 0.0229448 -0.931829 -0.130508 -0.0167884 -0.991305 -0.101034 0 -0.994883 0.130527 0 -0.991445 -0.923744 -0.0168238 0.382641 -0.949362 0.0312262 0.312627 -0.991178 -0.0232252 0.13049 -0.996816 0 0.0797395 -0.999721 0 -0.0236221 -0.13045 -0.0343383 0.99086 -0.139297 -0.0289578 0.989827 -0.381734 0.0704471 0.921583 -0.3167 -0.0313649 0.948007 -0.4796 -1.64898e-06 0.877487 -0.608762 -3.18366e-05 0.793353 -0.609792 0.00123595 0.792561 -0.793352 -0.00124827 0.608762 -0.794201 -1.81792e-05 0.607655 -0.878801 -8.98682e-06 0.477189 0.382676 0 0.923882 0.364923 0.0206459 0.930809 0.130506 -0.0176738 0.99129 0.111632 6.10442e-06 0.99375 -0.0567406 -3.10276e-06 0.998389 0.923574 -0.025868 -0.382546 0.965825 0.0493537 -0.254452 0.991045 -0.0284195 -0.130473 0.998932 -1.42419e-07 -0.0462046 0.991445 4.02326e-07 0.130525 0.984844 0.038112 0.169204 0.923529 -0.0277041 0.382526 0.908984 9.19337e-06 0.416832 0.793353 2.78061e-05 0.608762 0.825328 -0.0605008 0.561403 0.606538 0.085401 0.790455 0.666294 -0.0288968 0.745129 0.516195 0 0.856471 0.0673875 -0.0463316 -0.996651 0.298204 0.0371631 -0.953778 0.382628 -0.0159528 -0.923765 0.476545 4.14826e-06 -0.87915 0.608762 -1.66846e-05 -0.793353 0.616563 0.00741013 -0.78727 0.793334 -0.00689929 -0.608748 0.799058 2.62449e-05 -0.601254 0.888291 1.41187e-05 -0.459282 -0.829625 1.56524e-05 0.558321 -0.346236 -0.133638 -0.928581 -0.258813 0.00801361 -0.965894 -0.646143 -0.00525073 -0.763198 -0.704526 -0.0852541 -0.704539 -0.814197 -0.00375307 -0.580577 -0.963522 -0.0705012 -0.258174 -0.96906 -0.106591 -0.222625 -0.908544 0.00427026 -0.417768 -0.876429 1.0253e-05 0.481531 -0.931447 -0.0131049 0.363641 -0.962468 -0.084545 0.257892 -0.99149 0 0.130182 -0.997588 0 -0.0694097 -0.68405 -0.0700722 0.726061 -0.706484 -0.0417237 0.706498 -0.531678 0.00134584 0.846946 -0.313031 -0.00605864 0.949724 -0.258445 -0.0538905 0.964522 -0.0636933 0 0.99797 0.550176 0.00158403 0.835047 0.377969 -0.0031778 0.925813 0.25813 -0.0730201 0.963347 0.199237 -0.0389557 0.979177 0.068937 0 0.997621 0.692316 -0.0484808 0.719964 0.705707 -0.0629213 0.705705 0.819313 -0.000753356 0.573346 0.912682 0.000925608 0.40867 0.963628 -0.0689384 0.258203 0.973252 -0.0462801 0.22503 0.904982 -4.23943e-06 -0.42545 0.954235 -0.0535048 -0.294231 0.963145 -0.0758326 -0.258073 0.992097 0 -0.12547 0.997625 0 0.06888 -0.089157 2.16243e-06 -0.996018 0.0752891 -1.82534e-06 -0.997162 0.258022 -0.0785422 -0.962941 0.330993 0.000216876 -0.943633 0.707109 -0.000317327 -0.707105 0.642375 -0.113151 -0.757992 0.815785 -2.24229e-05 -0.578355 -0.484132 0.000130038 0.874995 -0.253741 -0.0492999 -0.966015 -0.258451 -0.0533037 -0.964553 -0.442634 0.000108361 -0.896702 -0.874699 0.000109237 -0.484667 -0.79347 0.000114444 -0.608609 -0.705236 -0.0727268 -0.705232 -0.637901 -0.0209074 -0.769834 -0.533056 0.000104315 -0.84608 -0.904519 -0.00510615 -0.426403 -0.964384 -0.0564805 -0.258405 -0.980784 0 -0.195098 -0.845725 0.000128937 0.533619 -0.896706 0.000127369 0.442626 -0.964087 -0.0616855 0.258325 -0.96618 -0.0553113 0.251865 -0.998085 0 0.0618608 -0.707109 0.000125844 0.707105 -0.604253 -0.16492 0.779538 -0.769528 -0.0248705 0.638129 0.442629 0.000132455 0.896705 0.258251 -0.065992 0.963821 0.254926 -0.0624738 0.96494 0.0616212 0 0.9981 -0.258819 0 0.965926 -0.195183 -0.0871277 0.976889 -0.425878 -0.00616851 0.904759 0.793464 0.000128474 0.608617 0.704515 -0.0855773 0.704511 0.638972 -0.0255986 0.768804 0.533051 0.000127505 0.846083 0.965926 0 0.258818 0.970461 -0.0230062 0.240159 0.874694 0.000122631 0.484676 0.845731 0.000114856 -0.53361 0.896709 0.00011346 -0.44262 0.964384 -0.0564805 -0.258405 0.964825 -0.0552343 -0.257024 0.998085 0 -0.0618602 0.768425 -0.0221226 -0.639557 0.705236 -0.0727268 -0.705232 0.608623 0.000105592 -0.793459 -0.0616254 0 -0.998099 0.195088 0 -0.980786 0.258447 -0.0533048 -0.964554 0.425656 -0.00504685 -0.904871 0.484159 0.000106388 -0.87498 -0.874872 1.82098e-05 0.484354 0.42702 -6.16878e-06 0.904242 0.258802 -0.0120975 -0.965855 0.342674 0.115398 -0.93234 0.875298 3.09487e-05 -0.483583 0.835063 3.19789e-05 -0.550155 0.705942 0.0574168 -0.705938 0.708246 0.0607849 -0.703344 0.555244 0.00255807 -0.831684 0.932897 0.0120108 -0.359944 0.963142 0.0758727 -0.258072 0.992038 0 -0.125935 0.963483 0.0710721 0.258164 0.982271 0.0340435 0.184349 0.997662 0 0.0683355 0.555218 -5.66701e-06 0.831705 0.680655 0.0442315 0.731267 0.705461 0.0682017 0.705459 0.809968 0.000685092 0.586474 0.928945 -0.000968685 0.370216 -0.258445 0.0538904 0.964522 -0.0644174 0.000199009 0.997923 0.258821 0.000204411 0.965925 0.130912 0.142372 0.981118 0.306312 0.0455159 0.950842 -0.829412 1.37496e-05 0.558638 -0.685804 0.0695338 0.724457 -0.706423 0.0437384 0.706437 -0.533244 -0.00146205 0.84596 -0.312799 0.00626556 0.949799 -0.965926 4.48309e-06 -0.258818 -0.913636 0.171787 -0.368453 -0.980183 0.0456937 -0.192752 -0.997641 0 -0.0686461 -0.965926 0 0.258818 -0.977316 0.158781 0.14015 -0.93006 0.0109546 0.367245 -0.706696 0.0338215 -0.706708 -0.683613 0.0737674 -0.726107 -0.836306 -1.91296e-05 -0.548263 0.0752934 3.65054e-06 -0.997161 -0.0980213 -4.75292e-06 -0.995184 -0.257748 0.0909585 -0.961921 -0.352263 0 -0.935901 -0.521755 0 -0.853095 0.484132 -0.000130038 0.874995 0.25374 0.0493042 -0.966015 0.258447 0.0533048 -0.964554 0.442634 -0.000108361 -0.896702 0.874699 -0.000109237 -0.484667 0.79347 -0.000114444 -0.608609 0.705236 0.0727266 -0.705232 0.637901 0.0209074 -0.769834 0.533056 -0.000104315 -0.84608 0.904519 0.00510614 -0.426403 0.964384 0.0564805 -0.258405 0.980784 0 -0.195098 0.845725 -0.000128937 0.533619 0.896706 -0.000127369 0.442626 0.964087 0.0616853 0.258326 0.96618 0.0553111 0.251865 0.998085 0 0.0618608 0.707109 -0.000125844 0.707105 0.604253 0.16492 0.779538 0.769528 0.0248705 0.638129 -0.442629 -0.000132455 0.896705 -0.258255 0.0659906 0.96382 -0.254926 0.0624681 0.964941 -0.0616254 0 0.998099 0.258815 0 0.965927 0.195178 0.0871291 0.97689 0.425878 0.00616851 0.904759 -0.793464 -0.000128474 0.608617 -0.704515 0.0855773 0.704511 -0.638972 0.0255984 0.768804 -0.533051 -0.000127505 0.846083 -0.965926 0 0.258818 -0.970461 0.0230062 0.240159 -0.874694 -0.000122631 0.484676 -0.845731 -0.000114856 -0.53361 -0.896709 -0.00011346 -0.44262 -0.964384 0.0564805 -0.258405 -0.964825 0.0552341 -0.257024 -0.998085 0 -0.0618602 -0.768425 0.0221226 -0.639557 -0.705236 0.0727266 -0.705232 -0.608623 -0.000105592 -0.793459 0.0616212 0 -0.9981 -0.195093 0 -0.980785 -0.258451 0.0533037 -0.964553 -0.425656 0.00504683 -0.904871 -0.484159 -0.000106388 -0.87498 -0.749589 0.598826 -0.282 -0.689548 0.512745 -0.511484 -0.704793 0.515311 -0.487568 -0.750097 -0.600053 -0.278011 -0.684728 -0.50707 -0.523476 -0.701785 -0.522052 -0.484726 -0.509089 -0.858597 -0.0603278 -0.371706 -0.120616 0.920482 -0.334695 -0.941595 0.0371255 -0.0514525 -0.997653 0.0451883 -0.0404269 -0.998233 0.0435382 -0.789953 -0.441973 0.425011 -0.785838 -0.524135 0.32824 -0.746643 -0.635162 0.197724 -0.883852 -0.467311 -0.0206483 -0.364596 -0.752338 -0.548686 -0.0685705 -0.997175 0.0306475 -0.0174336 -0.999025 0.0405647 0.0439757 -0.710162 0.702664 -0.0213372 -0.498405 0.866682 -0.161574 0.076527 0.983889 -0.0703302 -0.308555 -0.948603 0.031337 -0.224882 -0.973882 -0.0315037 -0.182665 -0.98267 -0.029239 -0.157153 -0.987141 -0.251066 -0.166528 -0.953538 -0.322915 -0.254662 -0.911522 -0.323188 -0.25465 -0.911429 -0.319499 -0.254142 -0.912871 -0.404039 -0.194887 -0.89374 -0.602248 -0.296921 -0.741037 -0.61691 -0.308414 -0.724088 -0.688748 -0.297394 -0.661198 -0.703455 -0.303286 -0.642782 -0.651987 -0.319587 -0.687588 -0.628493 -0.314754 -0.711285 -0.720895 -0.336739 -0.605737 -0.718192 -0.318371 -0.618741 -0.838071 -0.149108 -0.524789 -0.828182 -0.186052 -0.528678 -0.808412 -0.263461 -0.526362 -0.82819 -0.264827 -0.493931 -0.785098 -0.264653 -0.559982 -0.764944 -0.273045 -0.583359 -0.737189 -0.289202 -0.610667 -0.698135 -0.301191 -0.649532 -0.717488 -0.302839 -0.627295 -0.683881 -0.343745 -0.643542 -0.701765 -0.324646 -0.634138 -0.857304 -0.116901 -0.501363 -0.851097 -0.00548347 -0.52498 -0.912281 -0.100304 -0.397092 -0.911189 -0.119602 -0.394246 -0.926702 -0.0852919 -0.365991 -0.97445 -0.153628 -0.163845 -0.984703 -0.110972 -0.13433 -0.976093 -0.171462 -0.13358 -0.975528 -0.133678 -0.174574 -0.975807 -0.139785 -0.168107 -0.965667 -0.242705 -0.0926356 -0.972851 -0.225981 -0.0499435 -0.973452 -0.218513 -0.0681382 -0.970975 -0.214965 -0.104865 -0.97289 -0.201557 -0.113398 -0.974404 -0.184986 -0.127736 -0.98453 -0.175113 -0.00609989 -0.98235 -0.185917 -0.0205676 -0.980731 -0.193276 -0.028497 -0.978168 -0.204469 -0.0371339 -0.983775 -0.164268 0.0721305 -0.983481 -0.176276 0.041135 -0.979815 -0.177663 0.0916418 -0.983584 -0.161737 0.0800275 -0.983697 -0.154718 0.0916649 -0.981368 -0.143439 0.127833 -0.990489 -0.0577261 0.124897 -0.973628 -0.0868747 0.210954 -0.979482 -0.106751 0.170935 -0.980745 -0.0890335 0.173817 -0.979666 -0.150519 0.132663 -0.932937 -0.0541675 0.355941 -0.91186 -0.0848047 0.401647 -0.907551 -0.095704 0.408891 -0.886384 -0.1447 0.439756 -0.888908 -0.147197 0.433793 -0.878626 -0.148824 0.453727 -0.856004 -0.0921787 0.508684 -0.614934 -0.0386295 0.787632 -0.647822 -0.105466 0.754456 -0.649889 -0.0846356 0.755302 -0.481861 -0.0726342 0.873232 -0.478468 -0.07954 0.874495 -0.323234 0.0038842 0.946311 -0.295321 -0.0517859 0.953993 -0.20134 -0.0525807 0.978109 -0.0353058 -0.0637359 0.997342 -0.00968219 -0.0460067 0.998894 0.0521176 -0.199952 0.978419 -0.0598465 -0.21818 0.974072 -0.00512782 -0.337186 0.941424 -0.135278 -0.766808 0.62746 -0.0680726 -0.763527 0.642178 -0.029229 -0.810337 0.585235 -0.0682124 -0.862792 0.500936 -0.0995325 -0.868543 0.485517 -0.0325545 -0.841416 0.539407 -0.0741776 -0.950834 0.300686 0.0379567 -0.920758 0.388283 -0.511006 -0.765122 0.391741 -0.0257239 -0.909546 0.414806 -0.139474 -0.944405 0.297736 -0.0201315 -0.937441 0.347562 7.35158e-05 -0.999048 0.0436229 -0.000636383 -0.999049 0.0435968 -0.000282102 -0.999049 0.043608 -0.0432212 -0.998246 0.0404653 -0.0177783 -0.998981 0.0414859 -0.0184972 -0.999029 0.0399956 -0.0305219 -0.998953 0.0340707 -0.0325583 -0.998824 0.0359184 -0.133774 -0.991012 0.000306608 -0.0963101 -0.995121 0.0214 -0.0880965 -0.995668 0.029746 -0.083016 -0.996313 0.0216414 -0.0321709 -0.998684 0.0399365 -0.0352484 -0.998766 0.0349825 -0.0148271 -0.999053 0.0409123 -0.0142273 -0.999046 0.0412941 -0.111313 -0.957733 -0.265249 -0.14692 -0.973481 -0.175354 -0.191987 -0.969888 -0.149859 -0.234909 -0.962229 -0.137599 -0.40521 -0.9068 -0.116269 -0.332878 -0.93538 -0.119404 -0.190078 -0.979953 -0.0596901 -0.123661 -0.99227 -0.0104086 -0.21861 -0.97552 -0.0238685 -0.164727 -0.986292 -0.00969265 0.00236386 -0.975277 -0.220974 -0.0404799 -0.972345 -0.230013 -0.00599834 -0.96774 -0.251881 -0.0349563 -0.970634 -0.238007 -0.0878149 -0.969461 -0.228983 -0.0440756 -0.875198 -0.481753 -0.00933051 -0.903203 -0.429113 -0.0291743 -0.925495 -0.377634 -0.0575867 -0.933016 -0.355198 -0.0290026 -0.945928 -0.323078 -0.0250855 -0.960835 -0.275983 -0.0467065 -0.8741 -0.483496 0.0279844 -0.834508 -0.550284 -0.00212021 -0.836364 -0.54817 -0.198905 -0.826497 -0.52663 -0.117966 -0.829656 -0.545669 -0.0703488 -0.83977 -0.538365 -0.401354 -0.764097 -0.505045 -0.370764 -0.77575 -0.510633 -0.385765 -0.765268 -0.515316 -0.567377 -0.637487 -0.521242 -0.510139 -0.680877 -0.525514 -0.478103 -0.71069 -0.516078 -0.467867 -0.71528 -0.519111 -0.417602 -0.743463 -0.522371 -0.640704 -0.557274 -0.528152 -0.661485 -0.54768 -0.512332 -0.577243 -0.620394 -0.530945 -0.724732 -0.359209 -0.58799 -0.733432 -0.37897 -0.564322 -0.749761 -0.409271 -0.519958 -0.754263 -0.394248 -0.525029 -0.741404 -0.450172 -0.49766 -0.748072 -0.443556 -0.493606 -0.704517 -0.48914 -0.514197 -0.057534 -0.262879 -0.963112 -0.110348 -0.289776 -0.950712 -0.137129 -0.276497 -0.951181 -0.224615 -0.42159 -0.878527 -0.664797 -0.238046 -0.708082 -0.59549 -0.267892 -0.75738 -0.587439 -0.276857 -0.760438 -0.511401 -0.28751 -0.809819 -0.542429 -0.260779 -0.798602 -0.462326 -0.271161 -0.844231 -0.419847 -0.309203 -0.853301 -0.352653 -0.283461 -0.891788 -0.322681 -0.38028 -0.866755 -0.298072 -0.271158 -0.91522 -0.245152 -0.294582 -0.923646 -0.172376 -0.245499 -0.953948 -0.184198 -0.246008 -0.951604 -0.120295 -0.15654 -0.980318 -0.0227494 -0.23731 -0.971168 -0.0906387 -0.250318 -0.963912 -0.0407724 -0.279751 -0.959206 -0.0153152 -0.283771 -0.95877 -0.822592 -0.20814 -0.52917 -0.811939 -0.262138 -0.521573 -0.826671 -0.300841 -0.47551 -0.827894 -0.290401 -0.479854 -0.820785 -0.101282 -0.562187 -0.825175 -0.0861151 -0.558275 -0.848431 -0.139252 -0.510661 -0.850043 -0.130291 -0.510345 -0.876858 -0.206477 -0.434151 -0.879599 -0.188584 -0.436741 -0.893307 0.0143885 -0.449217 -0.887399 -0.0839199 -0.4533 -0.905351 -0.139905 -0.400956 -0.906772 -0.120932 -0.403906 -0.924775 -0.176504 -0.337102 -0.863213 -0.465268 -0.195932 -0.775343 -0.623298 -0.101703 -0.681039 -0.725815 -0.0968457 -0.68501 -0.726919 -0.0484873 -0.866531 -0.455652 -0.203728 -0.922016 -0.336694 -0.191112 -0.922536 -0.33483 -0.191878 -0.948795 -0.25764 -0.182783 -0.948831 -0.25745 -0.182864 -0.972662 -0.156912 -0.171193 -0.965973 -0.14039 -0.217223 -0.865979 -0.474774 -0.157068 -0.925366 -0.348225 -0.149793 -0.925074 -0.349193 -0.149339 -0.952307 -0.268993 -0.144062 -0.95197 -0.270607 -0.143266 -0.974029 -0.17977 -0.137658 -0.975859 -0.158404 -0.150359 -0.975766 -0.214677 -0.0423543 -0.972574 -0.227557 -0.0481459 -0.960941 -0.272676 -0.0473315 -0.958278 -0.281383 -0.050266 -0.936966 -0.345905 -0.0494493 -0.932225 -0.357956 -0.0531407 -0.870624 -0.489292 -0.0510642 -0.877071 -0.476827 -0.0581627 -0.878217 -0.478051 -0.0142339 -0.937542 -0.347404 -0.0180182 -0.941425 -0.33689 -0.0149794 -0.961451 -0.27447 -0.0166953 -0.963837 -0.266123 -0.0140061 -0.983583 -0.179691 -0.0166074 -0.887136 -0.461278 0.0145436 -0.747896 -0.645138 0.156361 -0.798229 -0.582815 0.152174 -0.798877 -0.59241 0.104143 -0.88868 -0.450962 0.0829578 -0.865754 -0.490871 0.0975437 -0.865102 -0.478145 0.151576 -0.821648 -0.547487 0.158598 -0.820632 -0.533623 0.204474 -0.770857 -0.600558 0.21239 -0.768471 -0.587975 0.252464 -0.805629 -0.485969 0.338816 -0.843777 -0.428543 0.323098 -0.849497 -0.455628 0.266001 -0.725287 -0.19505 0.660238 -0.715069 -0.197916 0.670452 -0.784714 -0.319762 0.531014 -0.76699 -0.328891 0.55096 -0.804465 -0.409126 0.43064 -0.843278 -0.350759 0.407248 -0.856612 -0.396026 0.330726 -0.915467 -0.276436 0.292409 -0.904041 -0.280543 0.3225 -0.914279 -0.328582 0.236911 -0.903685 -0.335877 0.265596 -0.907083 -0.352824 0.2296 -0.919498 -0.33357 0.207978 -0.922216 -0.356294 0.150243 -0.792322 -0.54875 0.266645 -0.834064 -0.488806 0.255747 -0.836293 -0.504305 0.215152 -0.877979 -0.433116 0.203871 -0.879304 -0.450007 0.155941 -0.913547 -0.379284 0.146884 -0.914618 -0.393124 0.0944843 -0.884476 -0.466253 0.0176502 -0.944002 -0.329719 0.012102 -0.941673 -0.336218 0.0144778 -0.966031 -0.258178 0.0113341 -0.963986 -0.265569 0.0143164 -0.983478 -0.180705 0.0108407 -0.979352 -0.200314 -0.0272859 -0.950169 -0.148985 0.273829 -0.943619 -0.157435 0.291199 -0.953754 -0.197212 0.226847 -0.947858 -0.207041 0.24228 -0.953771 -0.235418 0.186816 -0.948806 -0.245112 0.199218 -0.952686 -0.271028 0.137599 -0.946313 -0.288027 0.146736 -0.948346 -0.305243 0.0864125 -0.945228 -0.313702 0.0901959 -0.967187 -0.238513 0.0875306 -0.970483 -0.226888 0.0817624 -0.967594 -0.208781 0.142028 -0.972801 -0.190826 0.131313 -0.967617 -0.164164 0.191749 -0.971649 -0.155187 0.178369 -0.965561 -0.130252 0.225224 -0.967337 -0.128515 0.2185 -0.965482 -0.104247 0.238698 -0.957302 -0.103553 0.269906 -0.957534 -0.0250852 0.287227 -0.93922 -0.111213 0.324804 -0.934738 -0.10941 0.338075 -0.897119 -0.210695 0.388311 -0.908691 -0.210392 0.360578 -0.852506 -0.32283 0.411114 -0.821535 -0.245152 0.514763 -0.833197 -0.238928 0.498694 -0.768036 -0.112238 0.630495 -0.786595 -0.121212 0.605456 -0.790717 -0.156619 0.591809 -0.719626 -0.0393311 0.693247 -0.334163 -0.940806 0.0567324 -0.238041 -0.969631 0.0561398 -0.237045 -0.969401 0.0638061 -0.163262 -0.984682 0.0612132 -0.163702 -0.984712 0.0595363 -0.0997194 -0.99338 0.0570357 -0.0966164 -0.99326 0.064037 -0.134658 -0.989644 0.0497136 -0.108735 -0.988972 0.100549 -0.206878 -0.976261 0.06415 -0.111189 -0.967323 0.227867 -0.256214 -0.951269 0.171587 -0.089452 -0.913796 0.3962 -0.249043 -0.905512 0.343549 -0.0562849 -0.835925 0.545951 -0.221896 -0.832685 0.507344 -0.0451683 -0.758125 0.650543 -0.0740477 -0.762097 0.643215 -0.0708233 -0.68236 0.727578 -0.0554196 -0.674639 0.736064 -0.0216151 -0.610865 0.79144 -0.142952 -0.646958 0.749006 -0.0269816 -0.594612 0.80356 0.144807 -0.481777 0.864246 -0.0765711 -0.397767 0.914286 -0.137666 -0.433924 0.89037 0.00612035 -0.427376 0.904053 -0.182446 -0.540524 0.821308 -0.0579043 -0.533766 0.843647 -0.223196 -0.626436 0.746835 -0.115017 -0.621389 0.775014 -0.257784 -0.695574 0.670615 -0.162166 -0.692828 0.702632 -0.326169 -0.766881 0.552727 -0.194012 -0.783668 0.590105 -0.363646 -0.847487 0.386688 -0.242881 -0.86887 0.431362 -0.374082 -0.901097 0.219288 -0.255586 -0.929132 0.267187 -0.330683 -0.937884 0.104991 -0.229109 -0.962863 0.142842 -0.258125 -0.963589 0.0697747 -0.20116 -0.975377 0.0904105 -0.207284 -0.975526 0.0733615 -0.26624 -0.960883 0.0762861 -0.26698 -0.960954 0.072726 -0.347605 -0.934587 0.0756174 -0.349089 -0.935137 0.0604681 -0.0524799 -0.120016 0.991384 -0.0491632 -0.120644 0.991478 -0.124331 -0.173769 0.976907 -0.016851 -0.170263 0.985255 -0.206886 -0.306008 0.929278 -0.0996441 -0.301713 0.948177 -0.277597 -0.425411 0.861374 -0.180993 -0.422866 0.887933 -0.334633 -0.524298 0.783027 -0.250436 -0.524422 0.813796 -0.378165 -0.60372 0.701793 -0.304023 -0.606406 0.734739 -0.444933 -0.68488 0.577039 -0.344695 -0.709013 0.615212 -0.479961 -0.77402 0.412953 -0.39024 -0.801553 0.453018 -0.483467 -0.836364 0.25837 -0.39055 -0.870246 0.300236 -0.443774 -0.883804 0.148173 -0.354171 -0.91687 0.184156 -0.379063 -0.920069 0.0989156 -0.315016 -0.941124 0.122682 -0.322883 -0.941808 0.0935124 -0.377704 -0.920906 0.0962913 -0.379486 -0.921333 0.0844736 -0.600913 -0.317725 0.733454 -0.54789 -0.317126 0.774111 -0.455167 -0.219871 0.862832 -0.474361 -0.221418 0.85203 -0.370991 -0.120545 0.920779 -0.481937 -0.0559773 0.874416 -0.564429 -0.148396 0.812033 -0.56237 -0.148136 0.813509 -0.658396 -0.270141 0.702523 -0.635514 -0.276605 0.720841 -0.724443 -0.405517 0.557439 -0.695834 -0.419173 0.583188 -0.74842 -0.507476 0.427007 -0.716949 -0.527901 0.455308 -0.745714 -0.585231 0.318457 -0.709587 -0.612579 0.348185 -0.724128 -0.647888 0.236387 -0.684822 -0.679088 0.264306 -0.691836 -0.698956 0.181173 -0.654551 -0.728014 0.203861 -0.658177 -0.738151 0.148109 -0.711774 -0.686906 0.146761 -0.712848 -0.693395 0.105123 -0.789312 -0.605564 0.101386 -0.789544 -0.610758 0.0599561 -0.888599 -0.455727 0.0520099 -0.88738 -0.457928 0.05347 -0.945745 -0.321714 0.0454512 -0.944052 -0.326385 0.0473048 -0.968073 -0.247044 0.0424684 -0.965915 -0.254764 0.0458594 -0.98347 -0.176342 0.0411046 -0.981619 -0.190756 0.00606649 -0.868588 -0.484185 -0.105451 -0.769317 -0.630417 -0.103562 -0.772272 -0.633077 -0.0530024 -0.733584 -0.67855 -0.0377431 -0.734713 -0.678273 -0.0119309 -0.738844 -0.673714 -0.0148024 -0.739885 -0.67231 0.0238694 -0.742504 -0.669477 0.0220999 -0.74277 -0.667899 0.0469502 -0.697293 -0.714108 0.0619098 -0.696666 -0.710266 0.100897 -0.610027 -0.785789 0.101995 -0.60827 -0.782226 0.134644 -0.554615 -0.821275 0.13383 -0.548958 -0.815519 0.183234 -0.598566 -0.785114 0.159105 -0.587074 -0.770981 0.246846 -0.641961 -0.735706 0.215922 -0.619524 -0.706893 0.341311 -0.670894 -0.674708 0.307686 -0.629109 -0.623847 0.463721 -0.675067 -0.598696 0.4311 -0.603572 -0.515893 0.60791 -0.649717 -0.496479 0.575652 -0.578793 -0.415059 0.701944 -0.137841 -0.961543 -0.23756 -0.179911 -0.952493 -0.245742 -0.0681213 -0.931861 -0.356363 -0.122543 -0.899562 -0.419251 -0.0406961 -0.874994 -0.48242 -0.078871 -0.837376 -0.540908 -0.0264069 -0.820964 -0.570368 -0.037841 -0.998389 0.0422771 -0.0376021 -0.998542 0.0387193 -0.0438041 -0.998222 0.0404357 -0.0692729 -0.997144 0.0300842 -0.0701443 -0.996992 0.0329781 -0.110829 -0.993691 0.0172017 -0.111884 -0.993525 0.0197438 -0.186653 -0.982394 -0.00796856 -0.182847 -0.983023 -0.0152276 -0.243303 -0.967962 -0.0620691 -0.213342 -0.970393 -0.113241 -0.279921 -0.94535 -0.167206 -0.205435 -0.94062 -0.270243 -0.26287 -0.910952 -0.31791 -0.165554 -0.890954 -0.42284 -0.217077 -0.855811 -0.469536 -0.0683102 -0.805412 -0.588766 -0.407989 -0.8866 -0.217913 -0.461522 -0.849212 -0.256585 -0.497659 -0.828231 -0.257622 -0.542081 -0.789363 -0.288191 -0.581678 -0.760754 -0.287932 -0.616578 -0.723214 -0.311116 -0.658542 -0.686238 -0.30887 -0.684292 -0.652424 -0.32571 -0.759188 -0.568959 -0.3161 -0.770965 -0.53966 -0.338202 -0.859 -0.404691 -0.313598 -0.862171 -0.390985 -0.322168 -0.911106 -0.285087 -0.297677 -0.911822 -0.28184 -0.298574 -0.936677 -0.209878 -0.280335 -0.936851 -0.208628 -0.280687 -0.925382 -0.170858 -0.338342 -0.899063 -0.246866 -0.361584 -0.899824 -0.242785 -0.362453 -0.850645 -0.349124 -0.393084 -0.849617 -0.355092 -0.389949 -0.763183 -0.488037 -0.423523 -0.755683 -0.511992 -0.40842 -0.679354 -0.597731 -0.425672 -0.659547 -0.627226 -0.414228 -0.612518 -0.669236 -0.420648 -0.584873 -0.703269 -0.404148 -0.537336 -0.738144 -0.407938 -0.50152 -0.774598 -0.385325 -0.454057 -0.80257 -0.386929 -0.410393 -0.839032 -0.357215 -0.0510874 -0.99758 0.0471614 -0.124956 -0.991036 0.0472643 -0.125223 -0.991248 0.0417808 -0.220594 -0.97458 0.0391399 -0.219792 -0.975217 0.0253462 -0.230267 -0.972883 0.0218079 -0.228479 -0.973499 0.00989762 -0.254701 -0.96702 0.000399871 -0.252541 -0.967545 -0.00897561 -0.301288 -0.953149 -0.0270585 -0.296524 -0.95405 -0.0431533 -0.328833 -0.942773 -0.0552114 -0.382815 -0.919134 -0.0929771 -0.652397 -0.73998 -0.163732 -0.536643 -0.838295 -0.0963095 -0.525092 -0.836664 -0.155796 -0.571451 -0.809149 -0.136827 -0.500226 -0.85887 -0.110071 -0.627237 -0.769417 -0.120715 -0.6185 -0.764797 -0.180398 -0.757035 -0.620184 -0.205596 -0.743221 -0.643539 -0.182975 -0.747052 -0.649789 -0.140312 -0.600431 -0.788597 -0.132655 -0.607412 -0.79043 -0.0791896 -0.467161 -0.881684 -0.0662874 -0.473402 -0.880492 -0.0249869 -0.477578 -0.869102 -0.128762 -0.432883 -0.896091 -0.0981458 -0.435886 -0.895861 -0.0862365 -0.40108 -0.913876 -0.0629757 -0.404172 -0.913332 -0.0496911 -0.357833 -0.933206 -0.0328968 -0.361233 -0.932355 -0.0150293 -0.337901 -0.941156 -0.00695151 -0.340391 -0.9402 0.0125724 -0.331213 -0.943429 0.0154855 -0.332307 -0.94246 0.0366112 -0.22331 -0.973935 0.039792 -0.222841 -0.973469 0.0519667 -0.138659 -0.989003 0.0514407 -0.138375 -0.988949 0.0532201 -0.0692417 -0.996277 0.0513509 -0.0704829 -0.996388 0.0473664 -0.938352 -0.0983749 -0.331389 -0.940334 -0.117747 -0.319231 -0.95421 -0.102275 -0.281111 -0.956515 -0.131273 -0.260474 -0.968455 -0.134512 -0.209766 -0.944214 -0.236494 -0.229194 -0.943866 -0.238598 -0.228449 -0.918727 -0.312001 -0.242064 -0.917659 -0.316243 -0.240606 -0.8662 -0.427217 -0.259195 -0.862172 -0.441095 -0.249187 -0.767107 -0.583779 -0.265987 -0.752806 -0.612529 -0.241022 -0.672063 -0.69894 -0.24457 -0.6426 -0.7326 -0.224415 -0.598516 -0.769254 -0.223668 -0.558973 -0.805555 -0.196548 -0.518336 -0.832809 -0.194313 -0.468995 -0.868629 -0.159775 -0.432564 -0.887861 -0.156819 -0.375033 -0.919816 -0.115276 -0.264058 -0.716677 -0.645482 -0.266001 -0.786646 -0.557164 -0.317278 -0.801775 -0.506449 -0.270875 -0.839075 -0.471783 -0.362678 -0.86077 -0.357128 -0.311805 -0.894897 -0.319275 -0.374756 -0.901569 -0.216174 -0.31341 -0.9344 -0.169327 -0.341364 -0.933226 -0.112071 -0.279127 -0.958017 -0.0655103 -0.28907 -0.95637 -0.0423763 -0.201071 -0.979533 -0.00927774 -0.202888 -0.979193 -0.00418136 -0.156375 -0.987606 0.0134952 -0.156994 -0.987473 0.0158075 -0.131213 -0.991022 0.025679 -0.132037 -0.990775 0.0305307 -0.121952 -0.991945 0.0342343 -0.12238 -0.991636 0.0410027 -0.0394621 -0.998282 0.0433162 -0.0404808 -0.998272 0.0426058 -0.00107945 -0.999047 0.0436286 -0.000844021 -0.999035 0.0439028 -0.00582622 -0.999024 0.043789 -0.00409107 -0.998994 0.0446589 -0.0126449 -0.998935 0.0443802 -0.0187266 -0.99875 0.0463423 -0.0254165 -0.998651 0.0452844 -0.0376606 -0.998105 0.0486654 -0.0422588 -0.997642 0.0540762 -0.0638129 -0.995837 0.0650867 -0.0423883 -0.994433 0.0964687 -0.07648 -0.980584 0.18057 -0.100738 -0.980815 0.166892 -0.0566427 -0.973027 0.223628 -0.0749654 -0.0325413 0.996655 -0.0948742 -0.0403153 0.994673 -0.157025 -0.0869415 0.98376 -0.139173 -0.0858204 0.986542 -0.280573 -0.198435 0.939097 -0.23802 -0.195591 0.951362 -0.379189 -0.312802 0.870845 -0.326245 -0.310657 0.89278 -0.450056 -0.4151 0.790659 -0.396167 -0.415435 0.818819 -0.497965 -0.500387 0.708268 -0.447693 -0.503452 0.73899 -0.557242 -0.591211 0.583053 -0.486124 -0.61558 0.620278 -0.58564 -0.689059 0.426876 -0.52019 -0.717361 0.463461 -0.583064 -0.759733 0.287824 -0.512694 -0.794575 0.325263 -0.547921 -0.815546 0.186193 -0.475523 -0.851825 0.21971 -0.493483 -0.859895 0.130593 -0.433685 -0.887611 0.155124 -0.441135 -0.890068 0.114796 -0.494124 -0.861495 0.116908 -0.49691 -0.863362 0.0876734 -0.527211 -0.845859 0.0810577 -0.528194 -0.846989 0.0601664 -0.516751 -0.853613 0.0656752 -0.517125 -0.855353 0.0308728 -0.514873 -0.856667 0.0320471 -0.513615 -0.85802 0.00122327 -0.517546 -0.855655 -0.00100321 -0.516011 -0.856384 -0.0184295 -0.583152 -0.811336 -0.0408363 -0.578196 -0.811539 -0.0842277 -0.697342 -0.710659 -0.0931562 -0.683536 -0.698674 -0.211266 -0.771563 -0.616611 -0.156465 -0.864281 -0.479108 -0.153214 -0.866661 -0.488063 -0.103408 -0.927673 -0.359247 -0.101805 -0.930717 -0.351996 -0.0993236 -0.954757 -0.280771 -0.0980143 -0.956757 -0.274677 -0.0957512 -0.967703 -0.233406 -0.0952516 -0.971949 -0.222007 -0.0776431 -0.00248041 -0.903442 -0.428703 0.00019286 -0.99316 -0.116764 0.0153776 -0.980543 -0.195702 0.0522943 -0.993187 -0.104141 0.022791 -0.992144 -0.123007 -0.104697 -0.969715 -0.220662 0.0526834 -0.984372 -0.168038 0.0243438 -0.982279 -0.185837 3.09474e-08 -0.999131 0.0416789 0.00312259 -0.999043 0.0436217 0.000128449 -0.999153 0.041161 0.00029519 -0.999169 0.0407473 0.00132591 -0.999263 0.0383616 0.00658031 -0.999422 0.0333432 0.023755 -0.999295 0.029075 0.0567944 -0.998039 0.0263218 0.0550428 -0.998137 0.0263136 -0.0152848 -0.999516 -0.027089 0.0271826 -0.998737 -0.0422602 0.0242153 -0.998757 -0.0435712 0.000139911 -0.998365 -0.0571582 0.0223676 -0.927284 -0.37369 0.0150887 -0.923917 -0.382296 -0.00404547 -0.947095 -0.320927 0.00321627 -0.958067 -0.286526 -2.61735e-05 -0.961878 -0.273477 -2.42396e-05 -0.976795 -0.214178 0.0145586 -0.9755 -0.219518 0.00045501 -0.836422 -0.548086 0.594111 -0.720771 -0.3571 0.00798657 -0.85052 -0.525883 0.0151748 -0.848275 -0.529339 -0.0404309 -0.860827 -0.507289 0.00770911 -0.805574 -0.592445 0.0203045 -0.797139 -0.603455 0.0471933 -0.786497 -0.615789 0.0450137 -0.785435 -0.617305 -0.014607 -0.742098 -0.670132 0.0596405 -0.689759 -0.721579 -0.0553679 -0.668179 -0.741938 -5.25361e-05 -0.309274 -0.950973 0.205976 -0.220358 -0.953423 0.0132198 -0.245363 -0.969341 0.000396812 -0.249101 -0.968477 0.0312809 -0.276996 -0.960362 -0.149332 -0.14993 -0.977354 0.0394101 -0.315388 -0.948144 -0.0237158 -0.27924 -0.959929 0.00624473 -0.379959 -0.924982 0 -0.373124 -0.927781 0 -0.429575 -0.903031 0.0207162 -0.441162 -0.897188 -0.0471179 -0.538551 -0.841274 -0.000142857 -0.549152 -0.835723 -0.000142288 -0.620971 -0.783833 0.000220026 -0.1573 -0.987551 0.00217571 -0.159851 -0.987139 -4.41891e-05 -0.153491 -0.98815 0.000914057 -0.145972 -0.989288 0 -0.0075328 -0.999972 0.0020127 -0.137799 -0.990458 0.00837929 -0.119222 -0.992832 0.000622461 -0.128799 -0.99167 -0.000217482 -0.0889775 -0.996034 0.00270493 -0.0751135 -0.997171 0.00828562 -0.060296 -0.998146 0.00827094 -0.0602668 -0.998148 -0.0061851 -0.016913 -0.999838 -0.982817 -0.0737421 -0.169211 -0.98458 -0.0190579 -0.173893 -0.743764 -0.00411439 -0.66843 -0.0113136 0 -0.999936 -0.00859582 0.00251831 -0.99996 -0.0392839 -0.00220532 -0.999226 -0.0790991 0.0041059 -0.996858 -0.0970566 -0.00858661 -0.995242 -0.172197 -0.00939412 -0.985018 -0.187916 -0.00313035 -0.98218 -0.266617 -0.0360724 -0.963127 -0.291159 -0.0262094 -0.956316 -0.340112 -0.0319079 -0.939844 -0.356446 -0.0323043 -0.933757 -0.406449 -0.0475552 -0.912435 -0.444338 -0.0304968 -0.89534 -0.498258 -0.0511265 -0.86552 -0.534544 -0.0476863 -0.843795 -0.586976 -0.0641549 -0.807058 -0.618254 -0.0445681 -0.784714 -0.70655 -0.0779918 -0.703352 -0.685585 -0.0481939 -0.726396 -0.730132 -0.059472 -0.680713 -0.736309 -0.0603913 -0.673945 -0.745254 -0.0610035 -0.663985 -0.760391 -0.0589587 -0.646784 -0.763736 -0.0605327 -0.642684 -0.836155 -0.0636219 -0.544791 -0.883315 -0.065532 -0.464177 -0.823845 -0.0569746 -0.563944 -0.815562 -0.0744148 -0.573865 -0.869521 -0.0240104 -0.493313 -0.855095 -0.0391559 -0.516991 -0.852282 -0.0563014 -0.520044 -0.852581 -0.0532856 -0.519871 -0.822648 -0.0481574 -0.566508 -0.82882 -0.0627121 -0.555991 -0.821337 -0.0622804 -0.567033 -0.817282 -0.0627004 -0.572816 -0.801277 -0.0610392 -0.595172 -0.805303 -0.0599686 -0.589822 -0.783868 -0.0634431 -0.617677 -0.790958 -0.0611308 -0.608809 -0.778008 -0.0614753 -0.625239 -0.847983 0.00494748 -0.530001 -0.853501 -0.00664811 -0.521048 -0.822348 -0.00728005 -0.568938 -0.804213 0.00070244 -0.59434 -0.789609 -0.0047272 -0.613592 -0.770569 0.0536032 -0.635098 -0.791108 0.0202213 -0.611342 -0.70034 0.00356302 -0.713801 -0.693575 0.0186766 -0.720143 -0.601139 -0.0219239 -0.798844 -0.556582 0.0396635 -0.829845 -0.512857 -0.000797186 -0.858474 -0.386944 -0.0110398 -0.922037 -0.412941 0.0457296 -0.909609 -0.274823 -0.0261291 -0.96114 -0.215829 0.0374116 -0.975714 -0.183515 0.00702002 -0.982992 -0.0835092 -0.0172815 -0.996357 -0.101034 0.0235292 -0.994605 -0.0122558 -0.0139476 -0.999828 -0.0175523 0 -0.999846 -0.984804 -0.110054 -0.134345 -0.982822 -0.0822941 -0.165191 -0.981036 -0.110588 -0.159183 -0.981254 -0.103329 -0.162675 -0.981259 -0.0788715 -0.175812 -0.971747 -0.0741472 -0.224074 -0.973193 -0.0712116 -0.218686 -0.956709 -0.0729943 -0.281743 -0.950826 -0.0632779 -0.303194 -0.940737 -0.0687479 -0.332095 -0.929505 -0.065939 -0.362868 -0.848957 -0.0677181 -0.524105 -0.851786 -0.0664137 -0.519664 -0.891012 -0.0696934 -0.448599 -0.909515 -0.0577291 -0.411643 -0.915206 -0.0622612 -0.398148 -0.927906 -0.0689619 -0.36638 -0.856571 -0.00928552 -0.515946 -0.867454 -0.0256141 -0.496858 -0.910877 -0.0234527 -0.412012 -0.91101 -0.0236324 -0.411707 -0.952115 -0.0211592 -0.305008 -0.952666 -0.0221917 -0.303209 -0.973487 -0.0206957 -0.227805 -0.974296 -0.0227894 -0.224114 -0.98359 -0.0220697 -0.179065 -0.984563 -0.0445663 -0.169263 -0.012257 0 -0.999925 -0.0991453 0.00952798 -0.995027 -0.0113695 -0.00257199 -0.999932 -0.0138843 0 -0.999904 -0.289185 0.0128577 -0.957187 -0.27631 0.017213 -0.960914 -0.193407 0.0250423 -0.980799 -0.194182 0.0246533 -0.980656 -0.0813886 -0.0108701 -0.996623 -0.745614 0.0635226 -0.663344 -0.716297 0.0559133 -0.695552 -0.702656 0.0483105 -0.709888 -0.658789 0.0713345 -0.748939 -0.607454 0.0426581 -0.793208 -0.579231 0.054225 -0.813358 -0.520388 0.0487958 -0.852534 -0.5292 0.0455351 -0.847275 -0.422397 0.0516211 -0.90494 -0.468546 0.0102316 -0.88338 -0.361215 0.0476224 -0.931266 -0.823659 0.0570127 -0.564211 -0.815213 0.0744222 -0.57436 -0.678599 0.078149 -0.73034 -0.864487 0.0649648 -0.498439 -0.832716 0.063363 -0.550063 -0.797986 0.064718 -0.599191 -0.789493 0.0596703 -0.610853 -0.771016 0.0548772 -0.634446 -0.760921 0.0599106 -0.646072 -0.78151 0.0618324 -0.620821 -0.936265 0.0656479 -0.345107 -0.851699 0.0677177 -0.519638 -0.852611 0.0682406 -0.518071 -0.895012 0.067896 -0.440845 -0.909477 0.0578101 -0.411715 -0.926297 0.070723 -0.370097 -0.950618 0.0661088 -0.30324 -0.950426 0.065715 -0.303928 -0.967748 0.0755333 -0.24033 -0.972052 0.0697725 -0.224158 -0.977683 0.0780072 -0.195064 -0.983503 0.0630566 -0.169548 -0.983385 0.112593 -0.142394 -0.983002 0.116058 -0.142258 -0.983415 0.0191023 -0.180361 -0.984559 0.0445733 -0.169283 -0.982498 0.0778805 -0.169213 -0.981408 0.0739533 -0.177113 -0.981955 0.107489 -0.155599 -0.0100272 -0.00493361 -0.999938 -0.0835167 0.0108592 -0.996447 -0.0669871 -0.0270687 -0.997387 -0.215979 0.00315931 -0.976393 -0.252329 -0.0716122 -0.964988 -0.158123 0.0160278 -0.987289 -0.557011 0.00591244 -0.830484 -0.579339 -0.0478418 -0.813682 -0.497486 0.00493434 -0.867458 -0.386968 -0.000686022 -0.922093 -0.404019 -0.0356054 -0.914057 -0.317934 0.00240184 -0.94811 -0.805202 0.000454654 -0.593001 -0.789326 -0.0227273 -0.613553 -0.789417 -0.0225578 -0.613443 -0.760486 0.00721409 -0.649314 -0.693688 -0.00469543 -0.720261 -0.694897 -0.00782587 -0.719066 -0.637292 0.00404866 -0.770612 -0.852284 0.0561376 -0.520059 -0.852616 0.0526557 -0.519877 -0.822131 0.0481288 -0.567261 -0.828833 0.0627933 -0.555962 -0.81893 0.0620814 -0.570526 -0.815903 0.0624597 -0.574805 -0.80537 0.0617815 -0.589544 -0.870235 0.0299502 -0.491726 -0.856717 0.00950106 -0.5157 -0.853513 0.0040566 -0.521055 -0.836037 0.0069421 -0.548629 -0.823283 0.00710515 -0.567586 -0.854262 0.0442511 -0.517956 -0.863939 0.0257569 -0.502938 -0.910981 0.0234685 -0.41178 -0.910873 0.0236157 -0.41201 -0.952671 0.0211364 -0.303269 -0.952093 0.022205 -0.305001 -0.974334 0.0206367 -0.224161 -0.973442 0.0228266 -0.227794 -0.984521 0.0219928 -0.173883 -0.468447 0.881405 0.0606844 -0.503326 0.859089 -0.0928991 -0.739943 0.672296 0.022415 -0.697403 0.713983 0.0621036 -0.913287 0.377214 0.153676 -0.713102 0.693784 0.100745 -0.748344 0.647127 0.145629 -0.771826 0.604922 0.195841 -0.429042 0.204901 -0.879738 -0.889516 0.0895545 -0.448042 -0.896694 -0.0380022 -0.441018 -0.986679 0.0988362 0.129209 -0.972141 0.0953113 0.214144 -0.0344431 0.613808 0.788704 -0.0347907 0.841131 0.539712 -0.0175239 0.999026 0.0404971 -0.0489319 0.821288 -0.568412 -0.363397 0.750978 -0.551338 -0.506385 0.685026 -0.52375 -0.0665189 0.306888 -0.949418 0.0353265 0.216298 -0.975688 -0.0215548 0.184242 -0.982645 -0.243585 0.283005 -0.927672 -0.118328 0.370633 -0.921211 -0.116766 0.289484 -0.950034 -0.0669112 0.267721 -0.96117 -0.0604604 0.26437 -0.962524 -0.661857 0.321201 -0.677329 -0.613114 0.311933 -0.725802 -0.583686 0.271485 -0.76525 -0.698567 0.395676 -0.596192 -0.701287 0.318167 -0.637939 -0.790208 0.240127 -0.563836 -0.71402 0.294491 -0.635178 -0.735982 0.4764 -0.481013 -0.742763 0.446666 -0.498791 -0.74808 0.422215 -0.511968 -0.745063 0.433477 -0.506931 -0.708972 0.417418 -0.568437 -0.701653 0.406579 -0.58513 -0.644335 0.561055 -0.519664 -0.649891 0.548279 -0.526339 -0.471733 0.715955 -0.514661 -0.370576 0.775768 -0.510743 -0.276963 0.729566 -0.62532 -0.272298 0.788805 -0.551036 -0.22932 0.792072 -0.565716 -0.0135007 0.858732 -0.512248 -0.00807349 0.825915 -0.563736 0.00280238 0.828659 -0.559746 -0.00203396 0.829038 -0.559188 -0.0314515 0.926624 -0.374672 -0.172291 0.803118 -0.570366 -0.131216 0.83055 -0.541267 -0.117986 0.831397 -0.543009 0.0270674 0.847441 -0.5302 -0.125219 0.859444 -0.495657 0.0106395 0.881381 -0.472285 -0.08602 0.887917 -0.451889 -0.0258656 0.96823 -0.248719 -0.00683405 0.980358 -0.197106 -0.0395472 0.971048 -0.23559 -0.030353 0.970283 -0.240061 -0.164942 0.985077 -0.049163 -0.210773 0.975171 -0.0679417 -0.227433 0.963765 -0.139398 -0.185557 0.9709 -0.151401 -0.159407 0.972395 -0.170404 -0.13543 0.970405 -0.199933 -0.103864 0.994477 0.0150915 -0.141925 0.989875 -0.00227007 -0.0219356 0.999031 0.0381541 -0.0102838 0.999021 0.0430253 -0.0442254 0.998516 0.0317801 -0.0770351 0.996568 0.0302842 -0.0880861 0.99566 0.0300489 -0.0899906 0.995393 0.0330915 -0.0160651 0.999533 0.0259895 -0.0304268 0.998914 0.0352741 0.000557291 0.999047 0.0436348 0.000556391 0.999047 0.0436484 -0.00906132 0.999032 0.0430447 -0.00430834 0.999055 0.0432404 -0.000974672 0.999127 0.0417751 -0.0155034 0.99902 0.0414693 -0.0142416 0.999052 0.0411304 -0.00566415 0.999018 0.0439379 -0.0177605 0.998802 0.0456002 -0.0255521 0.998647 0.0452946 -0.0377249 0.998101 0.0486885 -0.0516306 0.996493 0.0658507 -0.0712108 0.995884 0.056076 -0.0831367 0.977756 0.192565 -0.0945614 0.978683 0.182312 -0.0546943 0.987978 0.144598 -0.0476236 0.99475 0.0905776 -0.0917117 0.931962 0.350764 -0.0647508 0.974237 0.216033 -0.0223552 0.955267 0.2949 -0.230129 0.930166 0.286062 -0.0796499 0.85997 0.504091 -0.0565439 0.872474 0.485377 -0.029282 0.910052 0.413458 -0.0473325 0.90879 0.414562 0.00551514 0.934325 0.356381 -0.0856718 0.400129 0.912446 0.0101551 0.426379 0.904488 -0.0661829 0.498251 0.864503 -0.0558144 0.122782 0.990863 0.0284468 0.137787 0.990053 -0.061488 0.212126 0.975306 -0.110803 -0.102664 0.988526 -0.0785765 0.0489104 0.995708 -0.0672367 0.0196629 0.997543 -0.0218179 0.0389372 0.999003 -0.0151334 0.0646824 0.997791 -0.326025 0.0281396 0.944942 -0.234848 0.15358 0.959823 -0.276859 0.0357913 0.960244 -0.583275 0.0181937 0.812071 -0.645066 0.110615 0.756078 -0.69705 0.0377956 0.716026 -0.849913 0.041169 0.525312 -0.840104 0.0899939 0.534908 -0.871198 0.160668 0.463896 -0.933595 0.137426 0.330931 -0.927328 0.0567258 0.369926 -0.910754 0.0867061 0.403744 -0.978459 0.182512 0.0964705 -0.987199 0.142627 0.0713791 -0.984177 0.158136 0.0799322 -0.981194 0.142456 0.130252 -0.980402 0.145954 0.132322 -0.983242 0.165396 0.0766817 -0.984317 0.171582 0.0409914 -0.98319 0.177037 0.0446735 -0.982268 0.187146 0.0112379 -0.982898 0.183952 0.00860422 -0.973362 0.217892 -0.0713481 -0.973234 0.222579 -0.0572214 -0.978066 0.204912 -0.0374006 -0.98059 0.193905 -0.029049 -0.983356 0.181001 -0.0157735 -0.985191 0.171449 0.00206333 -0.985583 0.169038 0.00725796 -0.985779 0.167742 0.0101375 -0.974303 0.178232 -0.137718 -0.973834 0.191685 -0.122083 -0.972939 0.201456 -0.113162 -0.970852 0.21569 -0.104516 -0.968192 0.23022 -0.0980001 -0.973116 0.158591 -0.167018 -0.976258 0.164181 -0.1413 -0.94495 0.125298 -0.302274 -0.824258 0.089651 -0.559072 -0.820471 0.102654 -0.562396 -0.854815 -0.00922197 -0.518851 -0.859778 0.110705 -0.498523 -0.849122 0.137878 -0.509885 -0.850245 0.130604 -0.509927 -0.837264 0.152633 -0.525063 -0.825114 0.196874 -0.529553 -0.752043 0.280187 -0.596596 -0.721163 0.305826 -0.621606 -0.735478 0.293531 -0.610665 -0.77078 0.270368 -0.576888 -0.793049 0.263023 -0.549447 -0.812702 0.263796 -0.519545 -0.813404 0.259629 -0.520544 -0.817771 0.233132 -0.526214 -0.310273 0.245996 -0.918269 -0.327884 0.251539 -0.910615 -0.304957 0.194765 -0.932238 -0.20241 0.207567 -0.957051 -0.508267 0.296694 -0.808478 -0.572435 0.249764 -0.780984 -0.472554 0.287546 -0.833073 -0.487126 0.266554 -0.831659 -0.375771 0.303955 -0.875447 -0.327294 0.506001 -0.798024 -0.299958 0.270146 -0.914902 -0.242232 0.292656 -0.925028 -0.172518 0.245608 -0.953894 -0.186613 0.244569 -0.951505 -0.0962155 0.150013 -0.983991 -0.0290556 0.244331 -0.969256 -0.100782 0.23894 -0.96579 -0.0296996 0.28881 -0.956926 0.00029806 0.276536 -0.961004 -0.647993 0.0819578 0.757224 -0.723968 0.192813 0.662339 -0.713964 0.195588 0.67231 -0.784148 0.317979 0.532918 -0.766491 0.327011 0.552771 -0.780395 0.119287 0.613803 -0.781168 0.12433 0.611816 -0.774383 0.122123 0.62082 -0.832691 0.237274 0.500326 -0.821091 0.243416 0.516293 -0.793904 0.554925 0.248546 -0.767099 0.580507 0.273076 -0.850641 0.461703 0.251475 -0.807569 0.416586 0.417479 -0.786275 0.432212 0.441548 -0.854894 0.329868 0.40043 -0.840298 0.341609 0.420954 -0.90209 0.224214 0.368729 -0.912224 0.260175 0.316475 -0.745998 0.629863 0.216241 -0.836929 0.508697 0.201933 -0.83294 0.481616 0.2725 -0.948081 0.140129 0.285494 -0.945759 0.163736 0.280589 -0.952467 0.190084 0.238064 -0.979715 0.0933224 0.177342 -0.981356 0.0836376 0.173046 -0.970574 0.149354 0.188892 -0.965577 0.129816 0.225407 -0.967216 0.128281 0.219174 -0.965053 0.0996346 0.242374 -0.956264 0.106923 0.272261 -0.955432 0.0163422 0.294758 -0.939414 0.111241 0.324232 -0.933603 0.111434 0.340542 -0.90394 0.193222 0.381521 -0.886139 0.143496 0.440643 -0.891576 0.149203 0.427588 -0.892133 0.108534 0.438542 -0.876197 0.0705067 0.476768 -0.711439 0.684519 0.159025 -0.821862 0.54957 0.150052 -0.820137 0.528407 0.219458 -0.909158 0.368758 0.193518 -0.906211 0.346639 0.242121 -0.92239 0.358219 0.144485 -0.864887 0.47593 0.159562 -0.865854 0.490644 0.0978003 -0.789311 0.60492 0.105171 -0.789628 0.610628 0.0601661 -0.808022 0.493298 0.322115 -0.783367 0.515093 0.347873 -0.858415 0.403135 0.317183 -0.841765 0.419919 0.339264 -0.907861 0.293564 0.299346 -0.912455 0.315154 0.260966 -0.949321 0.212064 0.231989 -0.953085 0.230258 0.196494 -0.968788 0.168241 0.182058 -0.972828 0.190454 0.131657 -0.967605 0.208466 0.142417 -0.970515 0.226662 0.0820095 -0.967208 0.238326 0.0878004 -0.968102 0.2469 0.0426455 -0.96594 0.254637 0.0460447 -0.966058 0.25807 0.0114663 -0.964013 0.265463 0.0144494 -0.963866 0.266026 -0.0138894 -0.980907 0.193811 -0.016078 -0.982653 0.183646 -0.0258351 -0.914685 0.392901 0.0947616 -0.888727 0.450816 0.0832386 -0.888669 0.455412 0.0535366 -0.887442 0.457937 0.0523381 -0.887251 0.460952 0.0175881 -0.878232 0.477811 -0.0201272 -0.739033 0.673562 -0.0120098 -0.734703 0.678237 -0.0143673 -0.866219 0.475698 -0.152893 -0.694898 0.500282 -0.51656 -0.740653 0.448936 -0.499889 -0.767724 0.49685 -0.404648 -0.742843 0.667802 0.0471615 -0.742611 0.669296 0.0239027 -0.884535 0.466235 0.0149248 -0.8841 0.467075 -0.0144403 -0.937586 0.347292 -0.0178924 -0.696619 0.709573 0.105958 -0.79899 0.592798 0.101024 -0.798004 0.580434 0.16213 -0.879457 0.452001 0.149167 -0.870494 0.400844 0.285595 -0.919564 0.333038 0.208535 -0.949703 0.248649 0.190365 -0.952741 0.270653 0.137953 -0.946342 0.287727 0.147141 -0.948391 0.305029 0.0866692 -0.94526 0.313526 0.0904715 -0.945783 0.321578 0.0456359 -0.944086 0.326261 0.0474943 -0.944037 0.329612 0.0122432 -0.941713 0.3361 0.0146151 -0.941466 0.336781 -0.0148566 -0.961482 0.274368 -0.0165754 -0.864042 0.478308 -0.157012 -0.925088 0.349022 -0.14965 -0.925447 0.348314 -0.149083 -0.951952 0.270298 -0.14397 -0.952411 0.269193 -0.142997 -0.976204 0.168336 -0.136707 -0.970469 0.162581 -0.178204 -0.744061 0.64489 -0.174611 -0.771594 0.616627 -0.15625 -0.775269 0.623082 -0.103571 -0.866652 0.487679 -0.105282 -0.86878 0.484324 -0.103207 -0.927713 0.359192 -0.101636 -0.930767 0.351913 -0.0991478 -0.954789 0.28072 -0.097849 -0.956791 0.274618 -0.0955849 -0.966599 0.237973 -0.0951549 -0.969811 0.227982 -0.0865551 -0.965912 0.148132 -0.212297 -0.943768 0.23818 -0.229284 -0.94438 0.23705 -0.227936 -0.917445 0.315462 -0.242443 -0.918984 0.312999 -0.239794 -0.860782 0.437271 -0.260476 -0.867342 0.431727 -0.247648 -0.74888 0.606198 -0.267773 -0.770378 0.590922 -0.239434 -0.750847 0.504126 -0.426716 -0.851534 0.351808 -0.388744 -0.84874 0.352898 -0.393833 -0.898795 0.245636 -0.363084 -0.900295 0.243949 -0.360497 -0.924328 0.174603 -0.339309 -0.926024 0.172541 -0.335723 -0.945585 0.094025 -0.311494 -0.959796 0.147058 -0.239095 -0.961018 0.108878 -0.254147 -0.936623 0.209605 -0.28072 -0.936995 0.209038 -0.279899 -0.910901 0.284393 -0.298966 -0.912096 0.28276 -0.296863 -0.857287 0.400201 -0.32388 -0.863659 0.396239 -0.311589 -0.754338 0.560881 -0.341154 -0.775251 0.548644 -0.313011 -0.5973 0.252423 -0.761259 -0.687403 0.249589 -0.682043 -0.705019 0.313745 -0.636012 -0.71629 0.310696 -0.624818 -0.762169 0.392786 -0.514604 -0.824986 0.295801 -0.48156 -0.829999 0.294969 -0.473387 -0.875059 0.200048 -0.440741 -0.881832 0.194116 -0.429756 -0.903344 0.132461 -0.40795 -0.909167 0.127125 -0.396554 -0.911287 0.119556 -0.394032 -0.926251 0.0713978 -0.370083 -0.362112 0.919948 -0.150237 -0.382631 0.919232 -0.0927732 -0.313873 0.948405 -0.0448467 -0.340385 0.940201 0.0126719 -0.337897 0.941158 -0.00687462 -0.361182 0.932376 -0.014931 -0.357782 0.933228 -0.0328159 -0.681554 0.725976 -0.0918839 -0.606525 0.790368 -0.0862872 -0.602377 0.789352 -0.118599 -0.533496 0.838241 -0.112844 -0.529587 0.837739 -0.133159 -0.507372 0.858885 -0.0699246 -0.579165 0.811611 -0.0765176 -0.583171 0.811329 -0.0407059 -0.685052 0.726887 -0.0483552 -0.733667 0.678468 -0.0376074 -0.265838 0.963772 -0.0217888 -0.181059 0.98336 -0.0148871 -0.195138 0.980773 -0.00248792 -0.398501 0.900625 -0.173414 -0.184918 0.969684 -0.159745 -0.312934 0.942412 -0.118032 -0.365675 0.922927 -0.120362 -0.343471 0.931293 -0.12133 -0.000893406 0.999047 0.0436295 -0.00313785 0.999047 0.0435443 -0.0378565 0.99838 0.0424803 -0.037806 0.998414 0.0417212 -0.0462904 0.998194 0.0382921 -0.0464861 0.998144 0.0393422 -0.0691857 0.997149 0.0301174 -0.0700532 0.996997 0.0330018 -0.110701 0.993704 0.0172438 -0.111757 0.993539 0.0197898 -0.18643 0.982437 -0.00787582 -0.162131 0.9853 -0.0538208 -0.359318 0.930374 -0.0727649 -0.292094 0.932975 -0.210329 -0.477965 0.85031 -0.220279 -0.400409 0.764787 -0.504751 -0.2423 0.82911 -0.503853 -0.349533 0.809343 -0.472008 -0.125686 0.877866 -0.46212 -0.262603 0.864974 -0.427621 -0.0135136 0.913625 -0.406334 -0.185621 0.911799 -0.366289 -0.0269345 0.935891 -0.351258 -0.0990142 0.941159 -0.323135 -0.0798355 0.970375 -0.228034 -0.181567 0.952708 -0.243683 -0.115517 0.957288 -0.265057 -0.301459 0.913757 -0.272343 -0.172431 0.934028 -0.312826 -0.389862 0.863768 -0.319238 -0.288204 0.889462 -0.354677 -0.472686 0.806397 -0.355376 -0.393649 0.833883 -0.386885 -0.684376 0.603166 -0.40966 -0.654513 0.622245 -0.429446 -0.688765 0.657136 -0.306228 -0.653812 0.681893 -0.32795 -0.675597 0.702351 -0.224214 -0.638635 0.729554 -0.244738 -0.649738 0.738229 -0.181269 -0.759192 0.624705 -0.182678 -0.740519 0.639651 -0.206102 -0.867145 0.458234 -0.195145 -0.862464 0.463104 -0.204181 -0.922646 0.335185 -0.190722 -0.921973 0.336402 -0.191832 -0.948877 0.257492 -0.182565 -0.948826 0.257603 -0.182676 -0.974661 0.145807 -0.169633 -0.96728 0.165005 -0.192727 -0.567634 0.634228 -0.524925 -0.564529 0.635452 -0.52679 -0.620533 0.674569 -0.399869 -0.577103 0.698049 -0.423886 -0.623694 0.727268 -0.286509 -0.57447 0.756724 -0.312015 -0.604241 0.771741 -0.198266 -0.552843 0.803195 -0.221905 -0.56703 0.808298 -0.158528 -0.621378 0.766606 -0.161881 -0.625404 0.7687 -0.134048 -0.693298 0.70735 -0.137819 -0.696995 0.710406 -0.0975825 -0.769548 0.630506 -0.101281 -0.772335 0.633012 -0.0528543 -0.870575 0.48864 -0.057714 -0.877436 0.476959 -0.0511584 -0.932271 0.357857 -0.0529941 -0.937011 0.345802 -0.049304 -0.958308 0.281306 -0.0501248 -0.960974 0.272585 -0.0471873 -0.972358 0.228512 -0.047987 -0.97416 0.221226 -0.0455025 -0.00568342 0.999022 0.0438444 -0.0052597 0.999023 0.0438692 -0.0404759 0.998231 0.0435456 -0.0404897 0.998241 0.0433092 -0.12239 0.991633 0.0410329 -0.121965 0.991943 0.0342615 -0.131997 0.990778 0.0305802 -0.131171 0.991026 0.0257117 -0.156909 0.987486 0.0158616 -0.156287 0.987619 0.0135349 -0.202751 0.979222 -0.0041172 -0.200943 0.97956 -0.0091932 -0.288845 0.956444 -0.042241 -0.261954 0.95948 -0.103817 -0.445604 0.886965 -0.121364 -0.392614 0.884196 -0.253085 -0.212999 0.672967 0.70834 -0.20309 0.713111 0.67099 -0.28886 0.751795 0.59276 -0.226151 0.79867 0.557658 -0.332878 0.839062 0.43031 -0.268243 0.878103 0.396208 -0.348282 0.898319 0.267811 -0.276771 0.933785 0.22681 -0.313808 0.938043 0.146971 -0.245349 0.963741 0.104919 -0.249911 0.963757 0.0933661 -0.209548 0.975405 0.0683792 -0.207731 0.975423 0.0734709 -0.163922 0.984672 0.0595846 -0.163477 0.984642 0.0612754 -0.138502 0.988929 0.0532566 -0.138784 0.988983 0.0514914 -0.181256 0.0582479 0.981709 -0.144825 0.0776961 0.986402 -0.143857 0.0887503 0.985611 -0.0702351 0.133013 0.988623 -0.0688727 0.205801 0.976167 -0.059864 0.211948 0.975446 -0.00646792 0.3324 0.943116 -0.0160479 0.496794 0.86772 -0.065294 0.470573 0.879942 -0.062255 0.38586 0.920454 -0.149663 0.335439 0.930098 -0.153797 0.266451 0.951499 -0.254595 0.208056 0.944401 -0.257858 0.179357 0.94939 -0.367868 0.117231 0.922459 -0.36786 0.117281 0.922455 -0.0227569 0.787354 0.616082 -0.0976211 0.754178 0.649373 0.0446442 0.709413 0.703378 -0.0557491 0.673066 0.737479 -0.0186801 0.608736 0.793153 -0.117345 0.567754 0.814792 -0.119075 0.502721 0.856208 -0.223782 0.450502 0.864274 -0.231491 0.392292 0.890235 -0.347367 0.32703 0.878856 -0.353609 0.290189 0.889242 -0.461007 0.224938 0.858414 -0.46345 0.210024 0.860874 -0.346198 0.583451 0.734665 -0.333202 0.622978 0.707725 -0.419909 0.671251 0.610818 -0.366629 0.720659 0.588417 -0.460351 0.765847 0.448948 -0.406915 0.808937 0.424312 -0.467394 0.831889 0.299172 -0.405037 0.874908 0.265481 -0.432537 0.881967 0.187203 -0.366055 0.918712 0.148229 -0.372451 0.919434 0.12618 -0.322621 0.941558 0.0968709 -0.323461 0.941591 0.0937022 -0.266502 0.960803 0.0763883 -0.267243 0.960873 0.0728293 -0.23719 0.969361 0.0638757 -0.238187 0.96959 0.0562247 -0.222915 0.973448 0.0520314 -0.223389 0.973914 0.0398675 -0.466722 0.880102 0.0871269 -0.496567 0.862788 0.0949624 -0.494409 0.861298 0.117159 -0.555177 0.820842 0.134153 -0.552494 0.818184 0.159139 -0.59655 0.781221 0.183908 -0.591968 0.775578 0.219209 -0.638486 0.729541 0.245163 -0.625729 0.713161 0.316013 -0.665471 0.666434 0.336176 -0.636427 0.631133 0.443433 -0.667726 0.588539 0.455811 -0.612679 0.524823 0.590919 -0.639806 0.48347 0.597415 -0.577586 0.412506 0.704438 -0.477345 0.481866 0.734811 -0.466196 0.517237 0.717724 -0.541365 0.577513 0.611067 -0.500627 0.625829 0.598088 -0.573634 0.679818 0.456938 -0.531269 0.724502 0.439148 -0.5736 0.753175 0.32204 -0.522261 0.799972 0.295448 -0.541343 0.811376 0.220493 -0.483381 0.85506 0.187654 -0.489379 0.8577 0.157667 -0.439242 0.88904 0.129132 -0.441754 0.889727 0.115062 -0.377999 0.920766 0.096468 -0.379788 0.921195 0.0846237 -0.347763 0.934519 0.0757277 -0.349251 0.935068 0.0605893 -0.334246 0.940771 0.0568334 -0.334785 0.941559 0.0372332 -0.332337 0.942446 0.0367059 -0.33125 0.943415 0.0155689 -0.293922 0.954451 -0.0513065 -0.301154 0.953194 -0.0269705 -0.252465 0.967565 -0.00891605 -0.254626 0.967039 0.000476896 -0.228455 0.973504 0.00995117 -0.230242 0.972887 0.0218831 -0.219816 0.975211 0.025402 -0.220612 0.974573 0.0392007 -0.125287 0.991239 0.0418257 -0.125017 0.991027 0.0472957 -0.051177 0.997574 0.0471817 -0.0504997 0.99743 0.0508254 -0.0675578 0.996638 0.0463644 -0.100004 0.993348 0.0570856 -0.103391 0.993411 0.0494395 -0.12738 0.989695 0.0654135 -0.127307 0.989694 0.0655566 -0.186064 0.977047 0.103727 -0.141265 0.973395 0.180405 -0.218366 0.948668 0.228793 -0.127599 0.927832 0.350494 -0.203073 0.894342 0.39864 -0.100606 0.856889 0.505588 -0.168897 0.81362 0.556323 -0.0583625 0.763903 0.642687 -0.0728337 0.750142 0.657254 -0.0697687 0.680094 0.729798 -0.163985 0.647565 0.744156 -0.170213 0.597285 0.783759 -0.285553 0.545817 0.787746 -0.296287 0.498331 0.814788 -0.417005 0.431478 0.799959 -0.42616 0.393501 0.814583 -0.607911 0.266613 0.747905 -0.568306 0.338649 0.749897 -0.413431 0.745788 -0.522374 -0.476765 0.710075 -0.51816 -0.549726 0.742881 -0.382007 -0.489934 0.769401 -0.409862 -0.553087 0.792178 -0.257971 -0.486959 0.824895 -0.287088 -0.527215 0.833802 -0.163763 -0.459863 0.867395 -0.190136 -0.484076 0.868934 -0.103073 -0.426025 0.896217 -0.123683 -0.440395 0.895298 -0.0670364 -0.396381 0.914418 -0.0819915 -0.404056 0.91339 -0.0495792 -0.468741 0.881549 -0.0561506 -0.473385 0.880504 -0.0248838 -0.516052 0.856361 -0.0183196 -0.517745 0.855534 0.00105517 -0.513586 0.858038 -0.0006439 -0.514899 0.856686 0.0311005 -0.517213 0.855254 0.0321187 -0.517099 0.854531 0.0488318 -0.587546 0.806588 0.0648555 -0.586378 0.804314 0.0961204 -0.610281 0.785562 0.102223 -0.608519 0.781979 0.134956 -0.658644 0.737661 0.148474 -0.656657 0.731667 0.182938 -0.691081 0.6938 0.202605 -0.68786 0.684591 0.241213 -0.722388 0.640463 0.260695 -0.713677 0.619375 0.327168 -0.742528 0.575996 0.341879 -0.721904 0.535136 0.438729 -0.743699 0.497037 0.447065 -0.701501 0.426488 0.570968 -0.718038 0.394013 0.573738 -0.640295 0.281878 0.71454 -0.651181 0.259792 0.713072 -0.560982 0.146107 0.814832 -0.561181 0.144665 0.814952 -0.478926 0.0528578 0.876263 -0.470701 0.105798 0.875927 -0.444883 0.0289874 0.895119 9.46142e-06 -0.999212 -0.0396869 -0.0007909 -0.999291 -0.03763 -0.00401365 -0.999451 -0.0328908 -0.00968961 -0.999551 -0.0283509 -0.020379 -0.999533 -0.0227923 -0.0152574 -0.999587 -0.0243698 0.00128737 -0.999955 0.00940858 -0.00442195 -0.998875 0.0472061 -0.015902 -0.999081 0.0398016 -0.000114559 -0.997411 0.0719062 -0.00104018 -0.993832 0.110892 -0.0118135 -0.994812 0.101042 0.0463537 -0.975662 0.214323 -0.0417381 -0.983847 0.17408 -0.0156601 -0.980223 0.197274 -0.0419966 -0.985226 0.166028 -0.00348972 -0.973382 0.22916 0.000705954 -0.959448 0.281884 -0.00723793 -0.939904 0.341362 -0.000871378 -0.937235 0.348697 0.000586106 -0.905224 0.424934 2.92705e-05 -0.905803 0.423698 2.95561e-05 -0.884669 0.466219 -0.00541434 -0.877331 0.479855 0.00904471 -0.849014 0.528294 -0.0118896 -0.82971 0.558068 3.75594e-05 -0.809893 0.586578 3.79444e-05 -0.793893 0.608057 0.00197084 -0.781612 0.623762 -0.0140883 -0.750345 0.660897 0.00341264 -0.733296 0.679901 -0.00154813 -0.686587 0.727046 0.000137985 -0.682951 0.730464 0.000137992 -0.632941 0.7742 -0.00613201 -0.64081 0.767675 -0.000324467 -0.60789 0.794021 0.00195571 -0.549297 0.835625 0 -0.55136 0.834268 0 -0.483717 0.875225 0.00607904 -0.453311 0.891332 -0.0195401 -0.394493 0.918691 -0.0233347 -0.400864 0.915841 0.00407367 -0.346225 0.938143 -0.00502728 -0.253632 0.967288 0.00499772 -0.235744 0.971802 -0.00422022 -0.139733 0.99018 -0.00205589 -0.13478 0.990873 0.00200526 -0.0501697 0.998739 0.00859481 -0.0340398 0.999384 1.76773e-05 -0.00713922 0.999975 0.330119 -0.859997 -0.389136 0.0239807 -0.689387 0.723996 0.164302 -0.949099 0.268732 0.31547 -0.948787 0.0167878 0.156175 -0.987721 0.00410349 0.619006 -0.329682 0.71284 0.689181 -0.722404 -0.0562387 0.706121 -0.694443 -0.138356 0.874605 -0.445174 -0.192058 0.00858127 -0.959203 0.282589 0.0154172 -0.984849 0.172726 -0.0247748 -0.967033 0.253442 0.163633 -0.983408 0.078313 0.133952 -0.989721 -0.0500947 0.0323395 -0.552233 -0.833062 0.32718 -0.109813 -0.93856 0.438274 0.47185 -0.765032 0.97845 -0.129409 0.1609 0.611203 -0.125006 0.78154 0.131621 -0.133608 0.982255 0.10322 -0.398831 0.911197 0.027978 -0.682646 0.730214 0.0106003 -0.685013 0.728454 0.00550794 -0.640809 0.767681 0.0770618 -0.606083 0.79166 0.17745 -0.0221573 0.98388 0.205051 -0.0502106 0.977462 0.244773 -0.0348282 0.968955 0.625765 -0.118029 0.77103 0.881824 -0.081685 0.464449 0.859863 -0.0879735 0.502888 0.827946 -0.117378 0.548386 0.773 -0.0450433 0.632805 0.811615 -0.122029 0.571306 0.832539 -0.103145 0.544279 0.861578 -0.180573 0.474423 0.894782 -0.153663 0.419229 0.933628 -0.106422 0.342073 0.939462 -0.0926478 0.32989 0.951651 -0.123915 0.281079 0.951723 -0.125158 0.280283 0.959455 -0.127356 0.251449 0.96302 -0.14259 0.228607 0.968004 -0.137177 0.21012 0.970145 -0.156702 0.185105 0.97379 -0.155615 0.165885 0.968216 -0.235755 0.0835326 0.961782 -0.250769 0.109952 0.954498 -0.278706 0.106095 0.967596 -0.223964 0.11661 0.969768 -0.210511 0.12343 0.971919 -0.193835 0.133425 0.979573 -0.201087 0.00120605 0.977467 -0.209311 0.0273491 0.973984 -0.222978 0.0404448 0.968204 -0.245457 0.0482986 0.955505 -0.289951 0.0542083 0.96149 -0.268112 0.0604455 0.968153 -0.239146 0.0740867 0.977721 -0.199826 -0.064274 0.981312 -0.191275 0.0209985 0.981532 -0.190229 0.0201897 0.981741 -0.190218 0.000912487 0.981196 -0.192894 -0.00675084 0.982609 -0.185183 -0.0136389 0.976041 -0.194731 -0.0970744 0.978266 -0.186427 -0.0907732 0.982994 -0.16857 -0.0728508 0.983956 -0.1748 -0.0357275 0.979297 -0.195891 -0.0510397 0.982472 -0.183259 -0.0341286 0.981508 -0.151723 -0.116717 0.980504 -0.153999 -0.122048 0.97429 -0.0926003 -0.205388 0.97828 -0.104024 -0.179297 0.977922 -0.121462 -0.170045 0.978284 -0.120652 -0.168535 0.979955 -0.118123 -0.160419 0.911374 -0.0843998 -0.402832 0.873409 -0.0706079 -0.481842 0.828199 -0.107511 -0.550025 0.827038 -0.108766 -0.551523 0.768719 -0.0720236 -0.635518 0.787684 -0.0527261 -0.613819 0.797309 -0.0581875 -0.60076 0.225231 -0.0552485 -0.972738 0.17872 0.0128748 -0.983816 0.155924 -0.0934216 -0.983341 0.169447 -0.0992091 -0.980533 0.0722833 -0.0950072 -0.992849 0.0705407 -0.174792 -0.982075 0.0470602 -0.169905 -0.984336 0.0343194 -0.633279 -0.773162 0.0903641 -0.719012 -0.689098 0.00184369 -0.71755 -0.696504 0.0233545 -0.760673 -0.648715 0.106122 -0.80312 -0.58629 -0.051183 -0.78587 -0.616271 0.0345452 -0.823035 -0.566939 0.0319046 -0.856074 -0.515867 0.0468874 -0.865751 -0.498275 0.0343713 -0.883161 -0.467809 0.0241492 -0.956716 -0.29002 -0.00590501 -0.944861 -0.327418 0.171227 -0.917592 -0.358756 -0.465662 -0.819309 -0.334503 0.0491156 -0.982662 -0.178781 0.0462599 -0.96373 -0.262841 0.102574 -0.98655 -0.127268 0.0854874 -0.986581 -0.139103 0.0369193 -0.996395 -0.0763822 0.0182767 -0.998478 -0.0520357 0.0552285 -0.997363 -0.047091 0.0536944 -0.997382 -0.0484469 0.00352992 -0.999035 -0.0437833 0.00542901 -0.999031 -0.0436684 0.0822296 -0.996065 -0.0330699 0.0477524 -0.997932 -0.0430231 0.047361 -0.997841 -0.0455025 0.0176231 -0.998819 -0.0452775 0.0215558 -0.998751 -0.0450765 0.00409137 -0.999065 -0.0430508 0.00515457 -0.999055 -0.0431519 0.0897238 -0.995206 -0.0389211 0.0168814 -0.999172 -0.0370267 0.0229057 -0.999004 -0.038306 0.196437 -0.979731 0.0392385 0.194018 -0.980246 0.038409 0.137647 -0.990421 0.0109013 0.101267 -0.994578 -0.0236397 0.109061 -0.993718 -0.0250973 0.0524217 -0.998261 -0.0269518 0.122324 -0.978287 0.167307 0.1825 -0.970417 0.158065 0.252206 -0.95509 0.155548 0.074982 -0.968729 0.236518 0.00661641 -0.937004 0.349256 0.0429339 -0.882776 0.467828 -0.0130932 -0.906079 0.422905 0.000920016 -0.809879 0.586596 0.0650278 -0.77925 0.62333 -0.00809772 -0.795407 0.606022 0.0616625 -0.731584 0.678957 0.672889 -0.123771 -0.729316 0.675814 -0.124254 -0.726523 0.722257 -0.197068 -0.662954 0.759709 -0.201196 -0.618355 0.784166 -0.459515 -0.417048 0.809334 -0.440784 -0.388185 0.771679 -0.360162 -0.524209 0.792294 -0.348684 -0.500689 0.751836 -0.270744 -0.601199 0.839685 -0.367413 -0.399922 0.857255 -0.352857 -0.374975 0.826117 -0.274109 -0.492336 0.840372 -0.26569 -0.472424 0.789185 -0.159622 -0.593049 0.79618 -0.157283 -0.58426 0.761648 -0.0924512 -0.641362 0.727351 -0.0762025 -0.682022 0.678775 0.156986 -0.717371 0.638815 -0.0732064 -0.76587 0.570056 -0.0740285 -0.818264 0.896315 -0.324426 -0.302269 0.885337 -0.287216 -0.365632 0.892348 -0.258765 -0.369805 0.870864 -0.200434 -0.448801 0.8753 -0.178625 -0.449381 0.846324 -0.112175 -0.520723 0.855284 -0.0977342 -0.508859 0.927601 -0.288509 -0.237317 0.922021 -0.265494 -0.281763 0.9275 -0.238312 -0.288012 0.916905 -0.202789 -0.343747 0.92092 -0.176728 -0.347382 0.901619 -0.123855 -0.414418 0.902659 -0.115247 -0.414637 0.889149 -0.0854721 -0.449564 0.930886 -0.0864527 -0.354934 0.945864 -0.129638 -0.297547 0.94696 -0.0957011 -0.306772 0.956585 -0.165274 -0.240061 0.956739 -0.144639 -0.252447 0.961439 -0.16053 -0.223305 0.963722 -0.17258 -0.203607 0.956082 -0.175087 -0.235058 0.960298 -0.189412 -0.204822 0.967538 -0.174599 -0.182715 0.972024 -0.195055 -0.130858 0.983712 -0.133228 -0.120672 0.975583 -0.169551 -0.139606 0.876272 -0.458635 -0.147652 0.9119 -0.386454 -0.138177 0.913148 -0.398072 -0.0877467 0.707667 -0.699568 -0.0990578 0.78668 -0.610064 -0.0946429 0.787116 -0.614434 -0.0540202 0.686474 -0.726901 -0.0192129 0.689041 -0.724448 -0.0199425 0.781316 -0.62396 -0.0148048 0.831923 -0.521928 -0.188401 0.814134 -0.542067 -0.208204 0.816742 -0.557035 -0.150482 0.862412 -0.485673 -0.142713 0.86347 -0.495698 -0.0932911 0.909946 -0.405704 -0.0860356 0.910257 -0.411586 -0.0450582 0.986951 -0.118152 -0.109396 0.990018 -0.130054 -0.0543096 0.98379 -0.163681 -0.073248 0.969776 -0.230554 -0.0798695 0.967685 -0.218159 -0.126461 0.951552 -0.275952 -0.135647 0.948879 -0.25965 -0.179471 0.924311 -0.32839 -0.194446 0.921386 -0.313468 -0.22975 0.892364 -0.377979 -0.246614 0.887045 -0.355278 -0.294838 0.83761 -0.441419 -0.321804 0.857104 -0.421979 -0.295476 0.776592 -0.537843 -0.328069 0.805267 -0.513042 -0.297208 0.764192 -0.618942 -0.18144 0.737174 -0.643891 -0.204887 0.740497 -0.65542 -0.148622 0.79413 -0.590596 -0.143364 0.795291 -0.598321 -0.0975973 0.858634 -0.504393 -0.0913019 0.858908 -0.509807 -0.0487215 0.885497 -0.463579 -0.0314557 0.885468 -0.463973 -0.0259798 0.905661 -0.42386 -0.0109648 0.905252 -0.424351 0.0210987 0.78 -0.43307 0.451719 0.773825 -0.447522 0.44824 0.794761 -0.487007 0.362188 0.784175 -0.509073 0.354843 0.796349 -0.532438 0.286945 0.783275 -0.55664 0.276827 0.79048 -0.570087 0.223925 0.77767 -0.591359 0.213365 0.707566 -0.677344 0.201385 0.728317 -0.649913 0.217183 0.720044 -0.639853 0.268562 0.74062 -0.609192 0.283492 0.726094 -0.589571 0.353827 0.743044 -0.560949 0.364995 0.717715 -0.525386 0.457006 0.729297 -0.503454 0.463314 0.685685 -0.442217 0.578169 0.393306 -0.0966702 0.914311 0.402065 -0.0636517 0.913396 0.472581 -0.163262 0.866033 0.477015 -0.143776 0.867056 0.61866 -0.330402 0.712807 0.682935 -0.261262 0.68216 0.675588 -0.280061 0.682017 0.579337 -0.0578226 0.813035 0.488288 -0.0399386 0.871768 0.562585 -0.174193 0.80818 0.625575 -0.0224625 0.779841 0.609854 -0.166063 0.77492 0.540509 -0.232153 0.808675 0.542398 -0.222805 0.810038 0.691568 -0.430114 0.58029 0.743714 -0.367612 0.558346 0.744191 -0.366394 0.558511 0.788453 -0.303329 0.535102 0.738121 -0.200028 0.644334 0.728059 -0.2332 0.644631 0.67018 -0.112941 0.733555 0.686617 -0.178018 0.704888 0.722521 -0.0585914 0.688862 0.776264 -0.187009 0.602032 0.785636 -0.144186 0.601653 0.829273 -0.248382 0.500612 0.82151 -0.279827 0.496809 0.842649 -0.332257 0.423731 0.842178 -0.335481 0.422124 0.858307 -0.376631 0.348509 0.85546 -0.390785 0.339817 0.8646 -0.415568 0.282437 0.860304 -0.432168 0.270383 0.865788 -0.447672 0.223608 0.861682 -0.460717 0.212708 0.865624 -0.472402 0.165925 0.782073 -0.598885 0.172332 0.771949 -0.614256 0.163661 0.712398 -0.682178 0.164686 0.694993 -0.702955 0.151128 0.953751 -0.28056 0.107912 0.928837 -0.353788 0.10998 0.93077 -0.360578 0.0604178 0.898615 -0.434703 0.0593762 0.899493 -0.436245 0.0245508 0.853368 -0.520864 0.0215439 0.853978 -0.520187 -0.0112926 0.784479 -0.619951 -0.0158918 0.784698 -0.617593 -0.0531776 0.693864 -0.717795 -0.0576424 0.693087 -0.714625 -0.0945579 0.954233 -0.279649 0.106002 0.955413 -0.275623 0.105919 0.957394 -0.28363 0.0543166 0.949162 -0.311665 0.0442349 0.949491 -0.313323 0.0172115 0.952675 -0.30299 0.0246593 0.953014 -0.302713 -0.0113539 0.955343 -0.295443 -0.00568714 0.955311 -0.292475 -0.0428823 0.957375 -0.286378 -0.0377009 0.95716 -0.281801 -0.0665847 0.947404 -0.309939 -0.0797659 0.945756 -0.296844 -0.132019 0.920456 -0.364146 -0.141983 0.918374 -0.348709 -0.187063 0.884509 -0.42089 -0.201232 0.881967 -0.407178 -0.237362 0.827116 -0.499114 -0.258388 0.846893 -0.477519 -0.233985 0.75818 -0.598897 -0.257846 0.787942 -0.571596 -0.228968 0.915152 -0.0592089 0.398737 0.890437 -0.152067 0.42895 0.906264 -0.199872 0.372474 0.906464 -0.190017 0.377116 0.921016 -0.233632 0.311683 0.920869 -0.236043 0.310295 0.929776 -0.264486 0.256054 0.929206 -0.270137 0.252196 0.934982 -0.289819 0.204485 0.934538 -0.29301 0.201948 0.0695298 -0.997425 -0.0175544 0.217635 -0.975999 -0.00782828 0.197961 -0.979122 0.0461669 0.304252 -0.951064 0.0539308 0.0723881 -0.925883 0.370811 0.119273 -0.91898 0.375831 0.00375061 -0.890072 0.455805 0.274508 -0.936226 0.219379 0.213202 -0.962541 0.167509 0.259675 -0.961252 0.0925448 0.19418 -0.980185 0.0391359 0.22112 -0.975177 -0.0116659 0.0972832 -0.995109 -0.0171774 0.0391235 -0.998489 -0.0385973 0.0221447 -0.998966 -0.0397082 0.371862 -0.889637 0.265074 0.315352 -0.922889 0.220972 0.355961 -0.923317 0.144147 0.291524 -0.951911 0.0942302 0.322918 -0.946132 0.0236096 0.108177 -0.99408 0.0101661 0.124942 -0.991716 -0.0298161 0.0343873 -0.998837 -0.0337968 0.0600091 -0.971252 0.230368 0.123541 -0.963404 0.237887 -0.0512381 -0.91991 0.388767 0.020366 -0.916125 0.400374 0.127245 -0.881981 0.453782 -0.109263 -0.776836 0.620152 -0.00932582 -0.756063 0.654433 0.00246245 -0.748508 0.663121 0.0127697 -0.453283 0.891275 0.0207339 -0.551241 0.834088 0.00925954 -0.547249 0.836918 0.0427264 -0.620291 0.783208 0.034808 -0.617406 0.785874 0.0609675 -0.676219 0.734173 0.0652345 -0.67783 0.732319 0.0823262 -0.725612 0.683161 0.0960234 -0.730832 0.675769 -0.0150553 -0.23572 0.971704 0.0636871 -0.345525 0.936246 0.0210635 -0.329584 0.943891 0.0450676 -0.430163 0.901626 0.0558574 -0.434484 0.898946 0.0774388 -0.513804 0.854405 0.0982727 -0.522577 0.84691 0.111288 -0.584735 0.803555 0.141207 -0.597688 0.789195 0.14747 -0.646663 0.748385 0.181937 -0.661609 0.727442 0.183243 -0.700739 0.689483 0.46038 -0.834788 0.301959 0.410764 -0.872143 0.26578 0.444875 -0.875461 0.188823 0.386676 -0.910651 0.145593 0.399253 -0.909948 0.112213 0.336837 -0.939246 0.0660169 0.169164 -0.973561 0.153505 0.205665 -0.964239 0.167167 0.0771839 -0.944276 0.319978 0.191514 -0.924658 0.329135 0.242686 -0.894597 0.375232 0.298541 -0.876542 0.377555 0.343412 -0.843562 0.412881 0.399132 -0.818614 0.412994 0.43803 -0.783787 0.440236 0.0576816 -0.985242 0.161153 0.130087 -0.977956 0.163337 0.0183006 -0.957402 0.288177 0.203303 -0.931102 0.302846 0.0377329 -0.887303 0.459641 0.146988 -0.868079 0.474165 0.19342 -0.831053 0.521479 0.248566 -0.813585 0.525637 0.290618 -0.775515 0.560461 0.35126 -0.749203 0.561525 0.388166 -0.710759 0.586642 0.560286 -0.567895 0.602972 0.538323 -0.599192 0.592603 0.601978 -0.647363 0.467487 0.576719 -0.68003 0.452719 0.616311 -0.705649 0.3496 0.583423 -0.743085 0.327786 0.605821 -0.754232 0.25321 0.566385 -0.792727 0.225371 0.577582 -0.796243 0.179989 0.53805 -0.82919 0.151481 0.54314 -0.829873 0.127713 0.509893 -0.853969 0.103664 0.516892 -0.853502 0.0660098 0.357692 -0.932353 0.052676 0.365657 -0.930667 0.012421 0.227715 -0.973727 0.0011612 0.231525 -0.972566 -0.0226043 0.0776448 -0.996481 -0.0315626 0.479583 -0.63985 0.600492 0.449188 -0.67668 0.583382 0.524541 -0.717562 0.458215 0.492122 -0.752495 0.437685 0.541746 -0.773032 0.330049 0.500271 -0.811704 0.301439 0.528163 -0.818701 0.225329 0.478806 -0.857152 0.18983 0.4912 -0.858128 0.149463 0.443582 -0.888839 0.114888 0.447773 -0.888602 0.0994316 0.409414 -0.909535 0.0716026 0.416491 -0.908164 0.0421206 0.252551 -0.967176 0.0280985 0.260529 -0.965451 -0.00539837 0.160899 -0.986886 -0.0129412 0.0902184 -0.995057 -0.041511 0.0758172 -0.996405 -0.0377985 0.0149035 -0.999065 -0.0405963 0.0159317 -0.999041 -0.0407836 0.273079 -0.620903 0.734784 0.277605 -0.5825 0.763957 0.228323 -0.556409 0.798923 0.2303 -0.508566 0.829652 0.178729 -0.481226 0.858183 0.17701 -0.421422 0.889422 0.12583 -0.395016 0.910016 0.119318 -0.319423 0.94007 0.0734418 -0.297034 0.952039 0.0616893 -0.202306 0.977377 0.00618119 -0.177097 0.984174 0.0360146 -0.0755591 0.996491 -0.0625344 -0.0339744 0.997464 0.366311 -0.533637 0.762265 0.373547 -0.49821 0.782463 0.317131 -0.459324 0.829729 0.323661 -0.416736 0.849456 0.259638 -0.372264 0.891071 0.264794 -0.32337 0.908469 0.191896 -0.273719 0.942472 0.195289 -0.221086 0.955501 0.113455 -0.16804 0.97923 0.115416 -0.116856 0.98642 0.0409533 -0.0721135 0.996555 0.0420488 -0.0332812 0.998561 0.0187892 -0.00958815 0.999777 0.115346 0.030394 0.99286 0.103083 -0.0175247 0.994518 0.171717 -0.0735437 0.982397 0.170838 -0.0787881 0.982144 0.262581 -0.157482 0.951972 0.259028 -0.178165 0.949295 0.339512 -0.249541 0.906896 0.334291 -0.277568 0.90067 0.403526 -0.339681 0.849579 0.397572 -0.368513 0.840318 0.489241 -0.44999 0.747096 0.522685 -0.394325 0.755849 0.495605 -0.514062 0.700083 0.416153 -0.566933 0.710918 0.40869 -0.595876 0.691306 0.319302 -0.644696 0.69456 0.313163 -0.675742 0.66731 0.219681 -0.71615 0.662472 0.217445 -0.747953 0.627124 0.109124 -0.782218 0.613373 0.096091 -0.796652 0.596752 0.101899 -0.795167 0.597767 0.00300391 -0.841205 0.540709 0.119255 -0.833489 0.539513 0.0345625 -0.850779 0.524385 0.0135735 -0.848876 0.528418 0.532201 -0.0860768 0.842231 0.475986 -0.0567515 0.87762 0.421067 -0.0749395 0.903929 0.352984 0.349397 0.867943 0.352642 -0.036801 0.935034 0.254095 -0.0400388 0.96635 0.325791 -0.120405 0.937744 0.327941 -0.111423 0.938104 0.405935 -0.199176 0.891934 0.405146 -0.202684 0.891502 0.47369 -0.27982 0.835056 0.471522 -0.289726 0.832902 0.557013 -0.386346 0.735169 0.546073 -0.405609 0.732998 0.630587 -0.497543 0.595661 0.617309 -0.520085 0.590289 0.670154 -0.575369 0.468875 0.652061 -0.603553 0.458848 0.683546 -0.634361 0.361042 0.659028 -0.66829 0.345067 0.67694 -0.683747 0.272474 0.647377 -0.719445 0.251597 0.657053 -0.72609 0.20267 0.626995 -0.757774 0.180708 0.632163 -0.760216 0.149807 0.606506 -0.784237 0.130853 0.612737 -0.785555 0.086348 0.468054 -0.880465 0.0755472 0.475336 -0.879313 0.0293908 0.33678 -0.941413 0.0179082 0.340791 -0.940067 -0.011662 0.217841 -0.975791 -0.0194247 0.219106 -0.974997 -0.0370567 0.0777271 -0.996106 -0.0416139 0.0790872 -0.996039 -0.0406472 0.0811519 -0.969725 -0.230319 0.0641025 -0.965709 -0.251589 0.012073 -0.938396 -0.345352 0.106971 -0.952036 -0.286677 -0.0177542 -0.907094 -0.420554 0.114064 -0.92594 -0.360035 0.0490489 -0.904572 -0.42349 0.369065 -0.830458 -0.41729 0.218688 -0.778254 -0.588639 0.290984 -0.779556 -0.554636 0.184774 -0.723976 -0.664618 0.265267 -0.727389 -0.632881 0.141985 -0.659052 -0.738574 0.235395 -0.664415 -0.709325 0.0878028 -0.579619 -0.810144 0.200814 -0.586569 -0.784609 0.0228847 -0.482404 -0.87565 0.16248 -0.489614 -0.856667 0.0444424 -0.423471 -0.904819 -0.197623 -0.478403 -0.855614 0.177938 -0.936381 -0.302538 0.249718 -0.950535 -0.184725 0.163687 -0.973044 -0.162455 0.201935 -0.975592 -0.0862672 0.118867 -0.957894 -0.261361 0.184439 -0.969448 -0.161719 0.0971574 -0.985562 -0.138665 0.136491 -0.988381 -0.066886 0.114573 -0.992096 -0.0511771 0.0894711 -0.994032 -0.0624108 0.0928635 -0.994226 -0.0537609 0.148529 -0.987381 -0.0549363 0.132699 -0.989386 -0.059218 0.362538 -0.914589 -0.179146 0.246748 -0.941142 -0.231012 0.309743 -0.947016 -0.0849736 0.217048 -0.967974 -0.126163 0.239892 -0.968635 -0.0647976 0.191737 -0.97767 -0.0860128 0.196543 -0.977896 -0.0713441 0.363293 -0.70213 -0.612399 0.416473 -0.699094 -0.581222 0.327232 -0.641549 -0.693782 0.387452 -0.640428 -0.663124 0.280468 -0.567603 -0.774057 0.349922 -0.568399 -0.744632 0.218642 -0.476075 -0.851791 0.301089 -0.478654 -0.824764 0.140904 -0.364537 -0.920467 0.240251 -0.368177 -0.898179 0.498476 -0.608869 -0.61709 0.538153 -0.604485 -0.587358 0.466556 -0.542511 -0.698575 0.509803 -0.540107 -0.669616 0.422805 -0.462378 -0.779386 0.469159 -0.462013 -0.752618 0.362999 -0.365799 -0.856985 0.40938 -0.367167 -0.835222 0.284399 -0.254594 -0.924283 0.323863 -0.256573 -0.91065 0.264983 -0.863739 -0.428649 0.455275 -0.787584 -0.415255 0.467478 -0.785224 -0.406063 0.415707 -0.170356 -0.893402 0.41556 -0.170344 -0.893472 0.506882 -0.270946 -0.818327 0.488781 -0.26993 -0.829597 0.569742 -0.36216 -0.737722 0.543479 -0.361974 -0.757367 0.611148 -0.440495 -0.657619 0.583199 -0.442076 -0.681503 0.638639 -0.506924 -0.578937 0.663945 -0.502875 -0.553439 0.584143 -0.712633 -0.388498 0.51813 -0.74067 -0.427725 0.575656 -0.777516 -0.253159 0.499592 -0.813648 -0.297295 0.533922 -0.829825 -0.162227 0.459294 -0.864965 -0.202198 0.477294 -0.870803 -0.117868 0.420107 -0.895601 -0.146315 0.430101 -0.897956 -0.0932086 0.367273 -0.923791 -0.108267 0.372476 -0.925185 -0.0727671 0.341654 -0.936371 -0.0805063 0.343716 -0.937335 -0.0571103 0.888809 -0.443591 0.115087 0.837056 -0.534619 0.116275 0.839747 -0.539219 0.0637846 0.770259 -0.634882 0.0602095 0.773083 -0.631314 0.061532 0.683785 -0.727538 0.0559175 0.680572 -0.730645 0.0545784 0.571414 -0.819336 0.0466289 0.574586 -0.818393 0.00916107 0.449753 -0.893152 0.000958287 0.451349 -0.891868 -0.0292496 0.452255 -0.891418 -0.0289531 0.452022 -0.89003 -0.0593471 0.463185 -0.884486 -0.0560828 0.461071 -0.882771 -0.0901653 0.489104 -0.8683 -0.0826617 0.484475 -0.865485 -0.127354 0.543799 -0.831811 -0.111237 0.535815 -0.826361 -0.173289 0.58521 -0.797823 -0.144945 0.572379 -0.78701 -0.230214 0.630989 -0.751373 -0.193107 0.607777 -0.728119 -0.316938 0.665096 -0.69356 -0.276805 0.625336 -0.649471 -0.4326 0.675049 -0.622586 -0.395847 0.637459 -0.578351 -0.509074 0.519952 -0.663937 -0.537435 0.557507 -0.657583 -0.506726 0.389534 -0.752444 -0.531123 0.439147 -0.747377 -0.498575 0.245366 -0.824411 -0.510041 0.31272 -0.823367 -0.473575 -0.0101304 -0.680288 -0.732875 0.0625237 -0.651498 -0.75607 0.124241 -0.679357 -0.723214 -0.00960413 -0.665492 -0.746343 0.145724 -0.743239 -0.652962 0.0296206 -0.730287 -0.682498 0.165915 -0.796716 -0.581133 0.0602773 -0.785267 -0.616216 0.183579 -0.842579 -0.506318 0.0840348 -0.833045 -0.546786 0.197785 -0.881957 -0.427823 0.10299 -0.875005 -0.473032 0.209482 -0.915205 -0.344262 0.117836 -0.911511 -0.394034 0.180437 -0.933638 -0.309454 0.341851 -0.889909 -0.301993 0.276058 -0.896837 -0.345653 0.428268 -0.838773 -0.336224 0.474377 -0.852308 -0.220313 0.378107 -0.88605 -0.268238 0.42657 -0.895823 -0.12466 0.338431 -0.926144 -0.1665 0.360781 -0.928359 -0.0893677 0.302925 -0.945964 -0.115705 0.313378 -0.946668 -0.074929 0.255908 -0.962679 -0.0880931 0.260905 -0.963366 -0.0620919 0.231017 -0.970453 -0.0696608 0.233272 -0.971139 -0.0497346 0.274071 -0.960978 -0.0374968 0.273802 -0.960389 -0.0518141 0.330534 -0.943197 -0.0335597 0.328999 -0.944286 -0.00910712 0.457558 -0.889179 -0.000720714 0.453792 -0.890474 0.033597 0.583679 -0.810794 0.0439509 0.577577 -0.810857 0.094426 0.679861 -0.726417 0.100536 0.699553 -0.706292 0.108525 0.766971 -0.632024 0.11091 0.775922 -0.620285 0.114851 0.83905 -0.531696 0.115299 0.827572 -0.509311 0.236065 0.885506 -0.43224 0.170433 0.938307 -0.306674 0.159785 0.971226 -0.172362 0.164349 0.972907 -0.176605 0.149209 0.950666 -0.267628 0.156873 0.917101 -0.332384 0.220108 0.926475 -0.359286 0.11206 0.890395 -0.44067 0.114051 0.89256 -0.446502 0.063029 0.845656 -0.530214 0.0611513 0.84687 -0.53124 0.0244089 0.774954 -0.631705 0.0198611 0.780353 -0.624938 0.0224218 0.682952 -0.730284 0.0161797 0.685259 -0.728098 0.0171228 0.572038 -0.820169 0.00974942 0.5735 -0.818836 -0.0246145 0.575167 -0.817683 -0.0240363 0.575127 -0.815885 -0.0596721 0.583089 -0.810398 -0.0571203 0.581518 -0.807736 -0.0969483 0.603595 -0.792178 -0.090156 0.600061 -0.787182 -0.142376 0.648931 -0.750304 -0.126223 0.643345 -0.740761 -0.193341 0.681601 -0.712456 -0.166816 0.672966 -0.696561 -0.248835 0.715967 -0.664034 -0.215525 0.700265 -0.634616 -0.326943 0.741553 -0.604348 -0.291313 0.713499 -0.554331 -0.428529 0.749366 -0.531099 -0.395456 0.701094 -0.451756 -0.55171 0.731922 -0.436241 -0.523435 0.675611 -0.348744 -0.64956 0.692039 -0.348357 -0.632242 0.640162 -0.273784 -0.717799 0.652515 -0.274402 -0.706348 0.591719 -0.191431 -0.783085 0.594244 -0.191689 -0.781108 0.527132 -0.105277 -0.843237 0.512687 -0.103447 -0.852321 0.458156 -0.0369556 -0.888103 0.321704 -0.0717436 -0.944118 0.305131 -0.0657945 -0.950035 0.189822 -0.139171 -0.971905 0.211682 -0.140224 -0.967227 0.054824 -0.237056 -0.969948 0.166474 -0.239717 -0.956464 0.0492773 -0.31135 -0.949017 -0.0982548 -0.252395 -0.962623 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1.43949e-07 0.72131 -0.692612 1.17851e-07 0.760596 -0.649226 -0.0035195 0.7789 -0.627138 0.00252963 0.812358 -0.583154 -0.00172157 0.838596 -0.544751 1.64975e-07 0.850724 -0.525612 -9.06858e-05 0.974194 -0.225712 -0.00187314 0.966323 -0.257326 -0.00375877 0.962602 -0.270892 -0.000832262 0.955002 -0.296598 -2.59124e-05 0.946584 -0.322458 0.000212885 0.921645 -0.388033 -0.00120648 0.923847 -0.38276 0.000824429 0.878935 -0.47694 -0.00727275 0.900332 -0.435143 -7.93301e-08 0.881097 -0.472936 0.000202705 0.983392 -0.181497 -3.25301e-05 0.983734 -0.179629 -2.99889e-05 0.991792 -0.127861 -0.000470584 0.992364 -0.123344 0.000649137 0.997308 -0.0733168 -0.00120911 0.998031 -0.0627185 2.20662e-06 0.998975 -0.0452574 -0.000275586 0.723425 -0.690403 0.000247294 0.688925 -0.724833 -0.00455371 0.642998 -0.765854 0 0.624147 -0.781307 0 0.506347 -0.86233 0.0103036 0.465522 -0.884976 0 0.387271 -0.921966 -0.00253765 0.138018 -0.990426 0.0210061 0.244412 -0.969444 0.00616337 0.252141 -0.967671 0 0.25886 -0.965915 -0.00793593 0.230671 -0.972999 0.0311133 0.323769 -0.945624 0.00519315 0.247434 -0.968891 -0.00269579 0.138972 -0.990293 0.0019329 0.0681159 -0.997676 -0.00266211 0.0536027 -0.998559 0.00204245 0.0117923 -0.999928 0 0.00760191 -0.999971 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.9981 -0.0590343 0.0176328 0.269272 -0.013603 -0.962968 0.303313 -0.00795017 -0.952858 0.0901635 -0.0200249 -0.995726 0.126121 -0.0121673 -0.99194 0.153514 -0.00886126 -0.988107 0.187059 -0.00738707 -0.982321 0.000387093 0 -1 0.0099578 0.00126683 -0.99995 0.0114133 0.000598326 -0.999935 0.0394047 -0.00110683 -0.999223 0.0483503 -0.0258304 -0.998496 0.0483434 -0.0258332 -0.998497 0.171486 -0.00600359 -0.985168 0.225469 -0.0152321 -0.974131 0.232779 -0.0106595 -0.972471 0.236722 -0.0091648 -0.971534 0.156361 0.00078315 -0.9877 0.132915 0.0177804 -0.990968 0.132695 0.000778949 -0.991157 0.0548377 -0.0012213 -0.998495 0.0372871 -0.000809635 -0.999304 0.994324 -0.1061 0.00790733 0.997302 -0.073412 -0.000153921 0.990732 -0.13448 0.0190855 0.989153 -0.145532 0.01993 0.999585 -0.0264939 0.0112982 0.982238 -0.0803136 -0.169584 0.980431 -0.0799218 -0.179911 0.976497 -0.0749912 -0.202066 0.975633 -0.0760158 -0.205822 0.971196 -0.0744188 -0.226363 0.964742 -0.0711775 -0.25339 0.9675 -0.067485 -0.2437 0.944562 -0.0768089 -0.319222 0.864459 -0.0646893 -0.498524 0.830341 -0.0584279 -0.554184 0.815528 -0.0655475 -0.574993 0.857588 -0.0622742 -0.510553 0.873971 -0.0601017 -0.482247 0.237479 -0.00900094 -0.971351 0.207803 -0.0134675 -0.978078 0.328868 -0.0142664 -0.944268 0.303153 -0.0178051 -0.952776 0.49894 -0.0397441 -0.865725 0.482879 -0.0438046 -0.874591 0.687485 -0.0462362 -0.724725 0.6332 -0.0708986 -0.770734 0.769689 -0.0491031 -0.636527 0.742687 -0.0568999 -0.667217 0.787387 -0.060113 -0.613521 0.797229 -0.0600632 -0.600682 0.951754 -0.0645584 -0.299994 0.932206 -0.0673229 -0.355611 0.910333 -0.0633681 -0.408997 0.912857 -0.060973 -0.4037 0.890488 -0.0643549 -0.450433 0.94706 -0.0286225 -0.319779 0.955204 -0.0228267 -0.295067 0.966927 -0.0257108 -0.253754 0.963748 -0.0302285 -0.265098 0.979192 -0.0144687 -0.202419 0.270046 -0.0163578 -0.962709 0.405081 -0.0146492 -0.914164 0.483393 -0.0246049 -0.875057 0.52439 -0.0189763 -0.851267 0.634927 -0.0267863 -0.772108 0.637357 -0.0262385 -0.770122 0.743876 -0.0243691 -0.667873 0.720086 -0.0328064 -0.693109 0.817351 -0.0198129 -0.575799 0.813068 -0.0221243 -0.581748 0.866074 -0.0281002 -0.499125 0.871187 -0.026375 -0.490243 0.912002 -0.0244914 -0.409454 0.903421 -0.0339353 -0.427411 0.935741 -0.0207492 -0.352076 0.996254 -0.03159 -0.080494 0.996285 -0.0313574 -0.0802041 0.998085 -0.0314374 -0.0532748 0.998655 -0.0325096 -0.0403915 0.998893 -0.0378351 -0.0279483 0.999334 -0.0325008 -0.01661 0.999287 -0.0324845 0.0192438 0.991731 -0.104788 -0.0740872 0.989585 -0.110275 -0.0925297 0.988939 -0.110318 -0.0991418 0.949617 -0.0744075 -0.304453 0.988102 -0.0899041 -0.124788 0.99402 -0.07433 -0.0799947 0.993725 -0.0823184 -0.0757302 0.991419 -0.106737 -0.0754692 0.997036 -0.0748709 0.0176911 0.994447 -0.105001 0.00702749 0.994091 -0.10498 -0.0276226 0.995645 -0.0920666 -0.0146819 0.996608 -0.0818899 0.00811852 0.991954 -0.121654 -0.0350296 0.991183 -0.12172 -0.0523497 0.974891 -0.0276679 -0.220958 0.982081 -0.0253827 -0.186742 0.986705 -0.0249381 -0.160596 0.983776 -0.0324403 -0.176445 0.991974 -0.0176569 -0.125201 0.989711 -0.0287563 -0.140161 0.993549 -0.0284167 -0.109786 0.990388 -0.0837332 -0.110091 0.988587 -0.0860249 -0.123678 0.983309 -0.0862895 -0.160178 0.986845 -0.0771568 -0.142069 0.983628 -0.0802349 -0.161366 0.332971 0.0167834 -0.942788 0.264867 0.0154957 -0.96416 0.331825 0.017082 -0.943186 0.318688 0.0212732 -0.947621 0.35423 -0.00633689 -0.935137 0.312457 0.00993457 -0.94988 0.269295 -0.00386784 -0.96305 0.98997 0.139862 0.0199323 0.998331 0.0577518 0.000668452 0.994325 0.106147 0.0071304 0.997019 0.0748183 0.0188733 0.998081 0.0589928 0.0188154 0.956904 0.0684924 -0.282211 0.956896 0.068477 -0.282244 0.967068 0.0735735 -0.24365 0.97145 0.071287 -0.226282 0.971167 0.0714803 -0.227432 0.975505 0.0780469 -0.205669 0.980652 0.0767295 -0.180095 0.256464 0.0115336 -0.966485 0.304816 0.0229319 -0.952135 0.401684 0.0236374 -0.915473 0.442185 0.0339128 -0.896282 0.512377 0.0384852 -0.857898 0.532591 0.0391111 -0.845469 0.562071 0.0388559 -0.826176 0.610997 0.0519949 -0.789923 0.680618 0.0500555 -0.730926 0.686908 0.0495076 -0.725056 0.721764 0.0574579 -0.68975 0.774569 0.057349 -0.629884 0.785801 0.0614046 -0.615424 0.834379 0.0610652 -0.547798 0.840446 0.0635606 -0.538155 0.890401 0.062878 -0.450812 0.880741 0.0530958 -0.470613 0.912738 0.0685816 -0.402749 0.933317 0.0627784 -0.353522 0.932153 0.0615815 -0.356789 0.943259 0.0689262 -0.324826 0.982619 0.0274373 -0.183597 0.982047 0.0267031 -0.186736 0.973527 0.019105 -0.227774 0.272475 0.00324028 -0.962157 0.278458 0.00813061 -0.960414 0.405042 0.0201557 -0.914076 0.401769 0.0193828 -0.915536 0.524393 0.0186505 -0.851272 0.562414 0.0264284 -0.826434 0.637425 0.0217696 -0.770205 0.687602 0.0293297 -0.725495 0.720259 0.0243993 -0.693276 0.775691 0.0286581 -0.630462 0.813131 0.0183052 -0.581793 0.835798 0.0267045 -0.548388 0.871195 0.025999 -0.490248 0.891811 0.0320461 -0.451273 0.974999 0.0233418 -0.220982 0.963905 0.0242459 -0.265141 0.958852 0.0271428 -0.282605 0.955186 0.0236434 -0.295061 0.934954 0.024926 -0.353894 0.935633 0.0257379 -0.352035 0.903676 0.0242136 -0.427532 0.998077 0.0316893 -0.0532744 0.996747 0.0335798 -0.0732645 0.998684 0.0316183 -0.0403926 0.999017 0.0370745 -0.0243165 0.999314 0.0331144 -0.0166097 0.999406 0.0318143 0.0132158 0.999467 0.0263698 0.0192473 0.988364 0.105486 -0.10959 0.988006 0.0903198 -0.125249 0.985658 0.10033 -0.135691 0.989145 0.112228 -0.0948506 0.990913 0.112389 -0.0738977 0.994957 0.0866563 -0.0505091 0.996358 0.0280947 -0.0805024 0.993529 0.029129 -0.109784 0.990902 0.0321897 -0.130678 0.9898 0.0254332 -0.140174 0.983961 0.0260136 -0.176478 0.98382 0.0729681 -0.163628 0.972892 0.0937313 -0.211413 0.980725 0.0675192 -0.183358 0.989829 0.0669553 -0.125525 0.988539 0.0760319 -0.13042 0.996143 0.0754131 -0.0448466 0.992111 0.102015 -0.0728617 0.994241 0.101923 -0.0331193 0.994819 0.098785 -0.0240285 0.994383 0.104966 -0.0136119 0.994441 0.10497 0.00821311 0.991516 0.129174 0.014517 0.519804 0.112977 -0.846782 0.195408 0.978138 -0.0711511 0.135383 0.824529 -0.549384 0.466842 0.855422 0.224305 0.0741585 0.910325 0.407198 0.177285 0.927888 0.328016 0.92339 0.347249 0.163615 0.835351 0.523099 0.168983 0.785654 0.565475 -0.250971 0.106109 0.581738 0.806425 -0.0416726 0.485038 0.8735 -0.107421 0.0468348 0.99311 0.474239 0.10326 0.874319 0.893322 0.14163 0.426516 0.979641 0.199434 -0.0230259 0.982606 0.185268 -0.0127151 0.98695 0.118233 -0.109317 0.974302 0.0927064 -0.205282 0.0312391 0.418635 -0.907617 -0.174931 0.458369 -0.871377 0.00988733 0.760546 -0.649209 0.0314078 0.850112 -0.525664 0.0365254 0.996502 -0.07517 0.0211078 0.998765 -0.0449668 0.0156664 0.999041 -0.0408809 0.0144309 0.999067 -0.0406948 0.00374682 0.999064 -0.0431005 0.0774548 0.996158 -0.0408772 0.078277 0.996064 -0.0415747 0.0800385 0.988114 -0.131242 0.0565296 0.964224 -0.258993 0.0440261 0.954078 -0.296304 0.0183816 0.95465 -0.297162 -0.00235776 0.946605 -0.322388 0.0385892 0.811627 -0.5829 -0.00499265 0.829168 -0.558977 0.0383383 0.772005 -0.634459 0.0226271 0.723225 -0.690242 0.0600062 0.702841 -0.708812 -0.0366604 0.688469 -0.724338 0.0849582 0.260062 -0.961847 0.264478 0.0632952 -0.962312 0.353679 0.0661087 -0.933028 0.311339 0.0930611 -0.945731 0.572476 0.0747352 -0.816508 0.53275 0.0274432 -0.845828 0.479249 0.0626938 -0.875437 0.510707 0.0940072 -0.8546 0.442107 0.0400083 -0.89607 0.680697 0.0472958 -0.731036 0.743147 0.0619244 -0.666257 0.703361 0.23592 -0.670541 0.787006 -0.00215668 -0.616942 0.911377 0.0883873 -0.401969 0.902575 0.117932 -0.414067 0.955345 0.150648 -0.254206 0.951857 0.124289 -0.280215 0.940295 0.120128 -0.318456 0.939847 0.11037 -0.323275 0.930561 0.08572 -0.355961 0.978254 0.104082 -0.179406 0.977964 0.121547 -0.169741 0.979691 0.117421 -0.162537 0.982556 0.127892 -0.135013 0.980073 0.155103 -0.124095 0.981492 0.151879 -0.116648 0.983757 0.172644 -0.0491561 0.982984 0.168654 -0.0727908 0.968065 0.240345 0.071309 0.971744 0.231797 0.0445491 0.975839 0.215702 0.0348067 0.978629 0.204875 0.0176386 0.967307 0.225699 0.115659 0.960721 0.255031 0.109424 0.953439 0.282491 0.105611 0.965142 0.131785 0.226126 0.971933 0.168274 0.164407 0.973859 0.136025 0.181922 0.974191 0.14158 0.175803 0.972438 0.178913 0.149512 0.971844 0.176702 0.155869 0.971484 0.198482 0.129708 0.912406 0.0661145 0.403912 0.936561 0.103081 0.335005 0.936703 0.0929608 0.33756 0.951388 0.120048 0.283636 0.951694 0.125132 0.280393 0.958401 0.127099 0.255567 0.964988 0.145222 0.218425 0.82887 0.116081 0.547265 0.859957 0.0878519 0.502748 0.880442 0.0822079 0.466973 0.120689 -0.0363552 0.992024 0.105012 0.0197022 0.994276 -0.0102042 0.0419788 0.999066 0.0207334 0.00926297 0.999742 0.064444 0.0562332 0.996336 0.0238118 0.0846146 0.996129 0.0276844 0.187989 0.981781 -0.0889041 0.236964 0.967442 -0.0424319 0.951865 0.303567 0.00433779 0.974194 0.225672 0.177884 0.963 0.202456 0.0628186 0.968385 0.241421 0.302245 0.940622 0.154525 0.098256 0.994948 -0.0205829 0.0915632 0.994954 -0.0410227 0.119751 0.992798 -0.00354038 0.147987 0.988862 0.0158751 0.195649 0.979902 0.0389073 0.880212 0.064101 -0.470231 0.836174 0.121236 -0.534896 0.841822 0.104064 -0.529629 0.818659 0.122646 -0.56103 0.794534 0.154606 -0.587207 0.743127 0.0624333 -0.666232 0.674752 0.127327 -0.726978 0.642154 0.0786736 -0.762528 0.610984 0.0524662 -0.789902 0.84291 0.377106 -0.383787 0.779487 0.547124 -0.30505 0.802154 0.505159 -0.318377 0.788127 0.469755 -0.397726 0.805452 0.432203 -0.405521 0.776314 0.37016 -0.510215 0.854789 0.414189 -0.312704 0.839901 0.450325 -0.302942 0.845287 0.471352 -0.251629 0.828481 0.506302 -0.239326 0.830858 0.517791 -0.203883 0.858676 0.510207 -0.0486231 0.858335 0.504444 -0.0937961 0.863223 0.496628 -0.0905902 0.861791 0.484387 -0.150617 0.876118 0.461417 -0.139681 0.873518 0.441642 -0.204739 0.884836 0.426145 -0.188323 0.880274 0.401934 -0.252123 0.893258 0.38531 -0.231572 0.884633 0.348595 -0.309689 0.89799 0.333532 -0.287003 0.738071 0.649079 -0.184251 0.740305 0.658367 -0.136022 0.704796 0.693141 -0.151059 0.707211 0.700736 -0.0939215 0.692357 0.714657 -0.0995348 0.693329 0.718445 -0.0559602 0.688619 0.722821 -0.0577323 0.688477 0.725009 -0.0190079 0.685951 0.727373 -0.0199978 0.759959 0.60631 -0.234203 0.762532 0.615003 -0.20079 0.814767 0.54721 -0.191614 0.816488 0.560029 -0.140409 0.793239 0.589249 -0.153484 0.794915 0.59941 -0.0938992 0.786196 0.610132 -0.0981622 0.786729 0.615024 -0.0529366 0.78431 0.618008 -0.0540715 0.784072 0.6205 -0.0145299 0.780947 0.624392 -0.0160003 0.967525 0.17495 -0.182449 0.972393 0.198301 -0.123 0.967089 0.216285 -0.134018 0.969738 0.230763 -0.0797281 0.983774 0.163838 -0.0731122 0.981217 0.175641 -0.079769 0.988073 0.121449 -0.0946635 0.982491 0.183544 -0.0319807 0.981881 0.185986 -0.0363229 0.957344 0.285824 -0.04238 0.957111 0.282005 -0.0664212 0.947327 0.310208 -0.0796354 0.945284 0.295433 -0.138412 0.951691 0.278642 -0.129009 0.938042 0.227603 -0.261292 0.96393 0.207052 -0.167236 0.956034 0.175447 -0.234983 0.963774 0.172741 -0.203223 0.961444 0.160732 -0.223138 0.958725 0.151131 -0.240843 0.838808 0.531845 0.116367 0.890178 0.440825 0.115134 0.89248 0.447178 0.0592595 0.692862 0.701983 0.164809 0.71357 0.684039 0.151356 0.704605 0.675097 0.218578 0.730261 0.653091 0.200476 0.716317 0.636188 0.286625 0.743302 0.613818 0.265949 0.721981 0.585036 0.369427 0.746147 0.566465 0.349831 0.713864 0.521073 0.467846 0.732214 0.508727 0.452836 0.682967 0.439437 0.583482 0.770685 0.613297 0.172947 0.782597 0.600705 0.163386 0.775817 0.589213 0.225689 0.791534 0.573153 0.21206 0.78084 0.553274 0.290132 0.797949 0.536762 0.274161 0.781501 0.505161 0.366153 0.796635 0.491862 0.351347 0.771618 0.444468 0.455032 0.781497 0.43695 0.445351 0.743216 0.367484 0.559093 0.744102 0.366939 0.558273 0.686263 0.267042 0.676559 0.769988 0.169938 0.615012 0.792349 0.158445 0.589134 0.829107 0.248491 0.500833 0.926457 0.359897 0.110236 0.95525 0.275438 0.107846 0.957353 0.283752 0.0544045 0.954398 0.293568 0.0542356 0.962865 0.264965 0.0518225 0.527927 0.0540357 0.847569 0.574145 0.048378 0.817323 0.610927 0.124993 0.781758 0.662445 0.0995927 0.742461 0.722594 0.220934 0.655016 0.743642 0.210524 0.634568 0.788238 0.303458 0.535345 0.821335 0.279965 0.497019 0.842997 0.333884 0.421755 0.841429 0.334342 0.424515 0.859966 0.3825 0.337864 0.853137 0.385973 0.350972 0.866148 0.421494 0.268571 0.858039 0.427385 0.284802 0.8667 0.451653 0.211756 0.86016 0.45772 0.224984 0.863013 0.464829 0.197843 0.885365 0.432471 0.17058 0.888706 0.444019 0.114228 0.928628 0.353705 0.111997 0.930685 0.360782 0.060513 0.949104 0.311833 0.0443009 0.620581 0.159641 0.76772 0.696437 0.0850197 0.712564 0.741187 0.0989477 0.663966 0.775368 0.0459067 0.629839 0.811072 0.122837 0.571904 0.832796 0.104101 0.543703 0.861454 0.18064 0.474622 0.891884 0.156201 0.424434 0.904696 0.194744 0.378947 0.908078 0.194435 0.370929 0.921249 0.234843 0.31008 0.920444 0.235154 0.312228 0.930299 0.266917 0.251592 0.928439 0.268256 0.256983 0.935186 0.291069 0.201759 0.934149 0.292176 0.204936 0.936069 0.298205 0.186675 0.95062 0.267723 0.156989 0.953778 0.281146 0.106137 0.954861 0.277472 0.106061 0.968235 0.235938 0.0827916 0.030387 0.998957 -0.0340834 0.0733564 0.996784 -0.0322471 0.0751181 0.996453 -0.0379198 0.0895127 0.995115 -0.0416389 0.0278229 0.99899 -0.0352953 0.0248279 0.999112 -0.0340431 0.0216319 0.998975 -0.0397603 0.105413 0.993908 -0.0321852 -0.000306634 0.99977 -0.0214659 0.118552 0.992811 -0.0164613 0.117754 0.992936 -0.0145572 0.159832 0.987074 -0.0118051 0.160173 0.987003 -0.0130416 0.228399 0.973536 -0.00790834 0.230119 0.972984 -0.0186585 0.328391 0.94446 -0.0124487 0.329709 0.943487 -0.0335259 0.499702 0.858145 0.117838 0.434005 0.888928 0.146447 0.453609 0.888059 0.0747647 0.402562 0.910336 0.0960829 0.412242 0.909271 0.0572933 0.469603 0.880691 0.0620944 0.473801 0.879927 0.0352262 0.571102 0.819753 0.0429883 0.573879 0.81888 0.0099442 0.682389 0.730791 0.0170149 0.684751 0.728593 0.0163802 0.774513 0.63217 0.0221245 0.780055 0.625383 0.0202658 0.853009 0.521302 0.0249173 0.853733 0.520591 -0.0112095 0.885291 0.464314 -0.0259302 0.885319 0.463927 -0.0313273 0.224256 0.974318 0.0203389 0.172696 0.983077 0.0611297 0.140955 0.976396 0.163655 0.218066 0.964352 0.14991 0.0973667 0.950407 0.295374 0.0993224 0.92245 0.373124 -0.015851 0.933397 0.358494 0.132303 0.964481 0.228632 -0.00671439 0.966951 0.254874 0.0381766 0.983552 0.176546 0.080699 0.984434 0.156133 0.105392 0.876876 0.469021 0.0729114 0.901196 0.427234 0.0195636 0.916416 0.399748 0.132373 0.945309 0.298108 0.0430835 0.964765 0.259562 0.132436 0.978357 0.158992 0.199961 0.960772 0.192181 0.0556677 0.856936 0.512408 -0.029294 0.801826 0.596839 -0.00494022 0.797233 0.603652 0.0496643 0.740253 0.670492 0.000401441 0.754102 0.656757 0.0235804 0.690097 0.723332 0.129112 0.649546 0.74928 0.0497097 0.433161 0.899945 0.154929 0.472435 0.867642 0.000301452 0.552105 0.833775 0.0462048 0.622489 0.781263 -0.0299379 0.656171 0.754018 0.0272166 0.691259 0.722094 -0.0112597 0.706981 0.707143 0.106404 0.739809 0.66435 0.952989 0.302946 -0.00590852 0.905522 0.424161 -0.0108896 0.904999 0.424676 0.0250278 0.846674 0.531688 0.0212264 0.84526 0.530492 0.0641483 0.772773 0.631798 0.0604384 0.769856 0.635255 0.0614198 0.679956 0.73113 0.0557567 0.683397 0.727983 0.05485 0.582715 0.811286 0.0475195 0.578382 0.81144 0.0839063 0.513971 0.854152 0.0791128 0.504879 0.854014 0.125528 0.546992 0.830405 0.105957 0.531251 0.828145 0.178743 0.583147 0.797832 0.15298 0.558063 0.789916 0.254161 0.612869 0.757558 0.224717 0.574431 0.738575 0.352897 0.30881 0.949585 0.054088 0.26959 0.952859 0.139216 0.460724 0.875062 0.148326 0.392907 0.868771 0.30143 0.55347 0.77709 0.29967 0.479113 0.746677 0.461437 0.60983 0.653672 0.44813 0.528312 0.59215 0.608478 0.635263 0.503639 0.585482 0.540245 0.400374 0.74016 0.618127 0.330347 0.713295 0.54535 0.227509 0.806742 0.37799 0.920596 0.0981174 0.291287 0.92002 0.262134 0.477549 0.837439 0.265788 0.381095 0.812519 0.441111 0.536437 0.723664 0.43422 0.433842 0.668145 0.604453 0.569001 0.575796 0.587108 0.0597083 0.922138 0.382225 -0.0328748 0.902722 0.428967 0.0123858 0.893376 0.44914 0.012362 0.854581 0.519171 0.0289141 0.852062 0.522642 0.0571176 0.817736 0.572753 0.101233 0.795629 0.597266 -0.0169578 0.753665 0.65704 0.142736 0.705087 0.694606 -0.0263477 0.640744 0.767302 0.176221 0.553899 0.813721 -0.0158249 0.472344 0.881272 0.192977 0.354834 0.914797 0.483797 0.153626 0.861591 0.53679 0.227486 0.812469 0.466593 0.28519 0.837233 0.561636 0.392525 0.728346 0.515146 0.4302 0.741318 0.494991 0.51446 0.700225 0.388574 0.583493 0.713125 0.493779 0.648756 0.579049 0.329577 0.739373 0.587118 0.455459 0.789462 0.411469 0.273921 0.869666 0.410669 0.39612 0.890753 0.222819 0.321807 0.785707 0.528304 0.178525 0.73142 0.658144 0.347302 0.658919 0.667239 0.237507 0.602266 0.762146 0.397167 0.514887 0.759703 0.286934 0.43895 0.851465 0.418503 0.353953 0.836405 0.318112 0.264024 0.910547 0.407064 0.201162 0.890973 0.331461 0.116073 0.936302 0.381209 0.0792909 0.921082 0.230799 0.681739 0.694236 0.0888353 0.619808 0.779709 0.275064 0.531897 0.80089 0.123141 0.45115 0.883912 0.299149 0.347231 0.888786 0.153486 0.248207 0.95647 0.273912 0.167912 0.946983 0.259216 0.731992 0.630075 0.135883 0.679566 0.72092 0.312886 0.600893 0.735547 0.183956 0.532464 0.826221 0.352759 0.437366 0.827208 0.224547 0.348417 0.910046 0.354493 0.263642 0.897122 0.246733 0.168205 0.954374 0.321405 0.116015 0.939808 0.368501 0.849069 0.378536 0.218826 0.801772 0.556126 0.409534 0.720099 0.560125 0.284454 0.661526 0.69388 0.434956 0.579881 0.688877 0.341431 0.517415 0.78467 0.470155 0.433886 0.768568 0.381273 0.354944 0.853607 0.477523 0.284987 0.831116 0.403004 0.20115 0.892819 0.465179 0.153108 0.871875 0.413791 0.0804018 0.906814 0.987784 0.154536 0.0200234 0.981587 0.19027 0.0168307 0.980272 0.196545 0.0209124 0.952787 0.303129 0.0176166 0.949414 0.313074 0.0244676 0.899371 0.436692 0.0207899 0.898295 0.434804 0.0633373 0.839595 0.539778 0.0609938 0.836891 0.535067 0.1154 0.766286 0.632164 0.114777 0.775855 0.621028 0.11123 0.678629 0.726541 0.107702 0.699792 0.70708 0.101638 0.610936 0.785767 0.0965777 0.603118 0.783626 0.148925 0.634426 0.761626 0.132022 0.622418 0.755896 0.20302 0.660449 0.728782 0.180788 0.641756 0.71596 0.274865 0.681349 0.688063 0.249666 0.652876 0.66357 0.365279 0.688524 0.639953 0.341167 0.645994 0.598415 0.473911 0.107497 0.811577 -0.574271 0.112635 0.775307 -0.62146 0.0843681 0.761578 -0.642559 0.0847454 0.717751 -0.691123 0.0567532 0.703836 -0.708092 0.0514015 0.648315 -0.759635 0.0652216 0.654992 -0.752816 -0.586756 0.753681 -0.296114 0.162824 0.919901 -0.35675 0.03965 0.932968 -0.357769 0.0521428 0.937403 -0.34432 0.153006 0.926423 -0.343989 0.291186 0.948399 -0.125497 0.266691 0.946358 -0.182434 0.149426 0.971151 -0.185844 0.263676 0.951828 -0.15652 0.0813808 0.983265 -0.162997 0.200656 0.970701 -0.132199 0.0885473 0.986563 -0.137303 0.0491855 0.981815 -0.183357 0.316622 0.884596 -0.342406 0.287789 0.874754 -0.389849 0.168601 0.904029 -0.392816 0.141195 0.893661 -0.42595 0.0467732 0.904924 -0.422995 0.0521895 0.907009 -0.417865 0.392728 0.824434 -0.407521 0.337364 0.913592 -0.227014 0.297719 0.905268 -0.303074 0.172254 0.935735 -0.30778 0.181799 0.935119 -0.304141 0.117708 0.958572 -0.259394 0.0550861 0.963826 -0.260776 0.0470134 0.972695 -0.227275 0.144433 0.558766 -0.816652 0.141012 0.614881 -0.775911 0.190592 0.64314 -0.741651 0.183586 0.686179 -0.703886 0.228285 0.710796 -0.665323 0.218553 0.745328 -0.629858 0.259153 0.766468 -0.587678 0.24724 0.7954 -0.553364 0.284329 0.813129 -0.507915 0.0210754 0.998763 -0.0450356 0.0175556 0.998823 -0.0452152 0.0948934 0.994438 -0.0456998 0.0454522 0.997584 -0.0525468 0.147686 0.987514 -0.0548175 0.131864 0.989504 -0.0591071 0.0527098 0.997446 -0.0482056 0.0489758 0.997469 -0.0515402 0.143144 0.98841 -0.0505462 0.0901478 0.994249 -0.0578208 0.2054 0.97581 -0.0748741 0.194204 0.978102 -0.0748357 0.232985 0.968606 -0.0867178 0.187822 0.402044 -0.896149 0.0906117 0.453361 -0.886709 0.091691 0.528157 -0.844182 0.0458368 0.54916 -0.834459 0.0192857 0.624031 -0.781162 0.203166 0.134209 -0.969903 0.228346 0.155385 -0.9611 0.0752733 0.0866117 -0.993394 0.263667 0.45585 -0.850106 0.2557 0.505893 -0.823826 0.319664 0.550665 -0.771093 0.309811 0.591 -0.744806 0.362321 0.62657 -0.690024 0.351043 0.660032 -0.664174 0.39522 0.688374 -0.608229 0.382906 0.716734 -0.582817 0.420224 0.738898 -0.526727 0.406573 0.764322 -0.500511 0.458692 0.790673 -0.40551 0.554385 0.376272 -0.742345 0.0567905 0.168099 -0.984133 0.112711 0.206291 -0.971977 0.201191 0.150991 -0.967845 0.307384 0.243909 -0.919796 0.416661 0.173053 -0.892438 0.500151 0.264727 -0.824481 0.593441 0.195003 -0.780898 0.670602 0.302628 -0.677281 0.732905 0.241126 -0.636167 0.788123 0.340875 -0.51251 0.829822 0.283128 -0.480869 0.854241 0.344534 -0.389319 0.894875 0.268678 -0.356387 0.882269 0.279991 -0.378426 0.981732 0.190261 0.00186134 0.981265 0.192549 -0.00665947 0.955369 0.295211 -0.0109583 0.95534 0.293057 -0.0379959 0.910125 0.411886 -0.0449604 0.909752 0.405665 -0.0882431 0.913004 0.398931 -0.0853115 0.91141 0.385205 -0.144738 0.92043 0.366762 -0.135253 0.917418 0.345368 -0.197651 0.924785 0.333284 -0.183561 0.919851 0.308445 -0.242353 0.928631 0.29544 -0.224411 0.919761 0.258985 -0.2949 0.929296 0.247079 -0.274518 0.913964 0.195516 -0.355589 0.923542 0.186512 -0.335089 0.901732 0.124843 -0.413877 0.867646 0.194153 -0.457706 0.878326 0.18772 -0.439664 0.837165 0.258539 -0.481988 0.791608 0.164875 -0.588365 0.738522 0.226484 -0.635051 0.675077 0.124154 -0.727225 0.593881 0.192127 -0.781276 0.521745 0.0997218 -0.847253 0.416762 0.172432 -0.892511 0.327635 0.0788122 -0.941512 0.290776 0.0785377 -0.953562 0.212035 0.00105323 -0.977262 0.169671 0.0864128 -0.981705 0.600905 0.43015 -0.673709 0.593843 0.456229 -0.662726 0.647067 0.519122 -0.558406 0.00310837 0.999037 -0.0437715 0.00476037 0.999035 -0.0436734 0.046936 0.997966 -0.0431492 0.0812989 0.996145 -0.0329556 0.133109 0.989838 -0.0500369 0.232387 0.971354 -0.0496673 0.231071 0.970997 -0.0614068 0.258366 0.963489 -0.0702583 0.257806 0.963421 -0.0731853 0.30841 0.947012 -0.0897267 0.308781 0.947029 -0.0882673 0.351759 0.928841 -0.116274 0.349218 0.928651 -0.125117 0.412374 0.895949 -0.164996 0.392344 0.892024 -0.224411 0.456953 0.849808 -0.262718 0.427314 0.839889 -0.334648 0.470331 0.780583 -0.411679 0.303885 0.852279 -0.425764 0.27041 0.838247 -0.47352 0.153756 0.867281 -0.473479 0.126233 0.855443 -0.502278 0.0190143 0.869402 -0.493739 0.0565237 0.879242 -0.47301 0.670663 0.480379 -0.565196 0.637056 0.579883 -0.507833 0.666966 0.614734 -0.42102 0.632839 0.659755 -0.405264 0.657803 0.687318 -0.30804 0.614016 0.736553 -0.28368 0.624956 0.747449 -0.225278 0.576943 0.792857 -0.19625 0.580617 0.795905 -0.171517 0.538639 0.829889 -0.145441 0.54092 0.831386 -0.12729 0.485442 0.86726 -0.110481 0.487499 0.868451 -0.0902048 0.460765 0.883701 -0.0822683 0.462176 0.884815 -0.0591251 0.451248 0.890632 -0.0561318 0.451434 0.891828 -0.0291668 0.450543 0.892285 -0.0289491 0.449086 0.893488 -0.00124822 0.339574 0.940542 -0.00840306 0.337081 0.941422 0.0100366 0.257671 0.966226 0.00355363 0.255688 0.966686 0.0118983 0.211034 0.977443 0.00834739 0.208164 0.977959 0.0162439 0.205531 0.978519 0.0160792 0.167129 0.982093 0.0869555 0.288111 0.956633 0.0429626 0.181776 0.959711 0.21427 0.307641 0.936054 0.170762 0.157637 0.915855 0.369271 0.279079 0.900692 0.33297 0.106222 0.852771 0.51137 0.238722 0.843268 0.481572 0.0788272 0.790068 0.60793 0.111271 0.793 0.598974 0.0952131 0.731324 0.675351 0.0101587 0.695927 0.718041 0.20256 0.622969 0.755565 0.0376064 0.551036 0.833633 0.234076 0.45037 0.861612 0.05518 0.357791 0.93217 0.233659 0.246446 0.940568 0.00506138 0.999055 -0.0431739 0.0889384 0.995287 -0.0386376 0.0770445 0.996527 -0.0316036 0.217323 0.975818 -0.0234713 0.218295 0.975179 -0.0370478 0.272948 0.960632 -0.0518152 0.273217 0.961225 -0.0373975 0.342828 0.937666 -0.0570234 0.341522 0.937105 -0.0720901 0.370342 0.925362 -0.080946 0.368806 0.924989 -0.0915312 0.426002 0.898076 -0.109464 0.424562 0.897779 -0.117219 0.470382 0.870303 -0.145992 0.466617 0.869157 -0.163813 0.524323 0.827924 -0.199065 0.509179 0.820866 -0.258682 0.564196 0.773061 -0.289931 0.528863 0.750412 -0.396467 0.572038 0.705872 -0.417752 0.532023 0.675605 -0.510401 0.544454 0.649104 -0.531257 0.512399 0.622746 -0.591299 0.523609 0.594259 -0.610484 0.483009 0.559228 -0.673771 0.493202 0.527682 -0.691595 0.441813 0.481886 -0.756695 0.45064 0.447605 -0.772381 0.38343 0.386807 -0.838667 -0.0706395 0.243854 -0.967236 0.0592049 0.309629 -0.949012 0.109293 0.279669 -0.953855 0.193528 0.33909 -0.920633 0.302999 0.273631 -0.912862 0.39026 0.352124 -0.850709 0.497097 0.280977 -0.820943 0.559802 0.352231 -0.750037 0.702903 0.229345 -0.673297 0.682146 0.359739 -0.636604 0.725941 0.427588 -0.538682 0.707453 0.462942 -0.534037 0.743911 0.522598 -0.416519 0.718809 0.564822 -0.405327 0.736913 0.596919 -0.317248 0.704364 0.643791 -0.299005 0.712306 0.658631 -0.242541 0.675726 0.703553 -0.220017 0.678819 0.709261 -0.190144 0.644929 0.745404 -0.168642 0.647164 0.74925 -0.140722 0.600527 0.789476 -0.126869 0.602502 0.792261 -0.096511 0.581126 0.808801 -0.0901869 0.582303 0.8108 -0.0593876 0.574448 0.816539 -0.0572065 0.574465 0.818163 -0.0244817 0.572787 0.819351 -0.0240562 0.571378 0.820638 0.00900983 0.456592 0.889675 0.0014515 0.453738 0.890708 0.0275969 0.363455 0.931395 0.0201093 0.360082 0.932177 0.0372476 0.309917 0.950192 0.0329581 0.300681 0.951639 0.0630368 0.321365 0.945358 0.0549761 0.398632 0.910239 0.112059 0.370096 0.910253 0.185657 0.538977 0.820412 0.190861 0.487422 0.807708 0.331703 0.62407 0.710733 0.324646 0.567654 0.674441 0.472121 0.675095 0.581449 0.454054 0.611489 0.514977 0.600732 0.693408 0.433708 0.575398 0.618713 0.330104 0.7129 0.671866 0.273654 0.688266 0.609473 0.166187 0.775193 0.616014 0.119603 0.778602 0.53017 0.113495 0.840261 0.494326 0.0508178 0.86779 0.420889 0.074795 0.904023 0.356975 -0.329206 0.874181 0.353512 0.0388044 0.934625 0.246903 0.0368561 0.968339 0.248214 0.0342983 0.968098 0.203782 0.0509421 0.97769 0.167225 0.076502 0.982946 0.174483 0.0763105 0.981699 0.0752029 0.143984 0.986718 0.154437 0.140744 0.977927 -0.0160643 0.252518 0.967459 0.155401 0.244286 0.95717 0.0130336 0.335313 0.942017 0.136747 0.374646 0.917028 -0.112843 0.0346628 0.993008 -0.990917 0.133113 0.0190841 -0.997458 0.0657574 -0.0274662 -0.99148 0.128739 -0.0198273 -0.992304 0.12178 -0.0224112 -0.989445 0.142595 -0.0257843 -0.988783 0.112191 0.0985963 -0.990618 0.11214 0.0781054 -0.992248 0.103495 0.0687888 -0.990329 0.131006 0.0456817 -0.993971 0.109233 0.00951029 -0.98712 0.0941518 0.129345 -0.987156 0.0925587 0.130218 -0.978957 0.101466 0.177056 -0.97614 0.0759764 0.203416 -0.97368 0.0762332 0.214792 -0.967297 0.0714721 0.24337 -0.966932 0.0706893 0.245042 -0.953316 0.0719472 0.293279 -0.948459 0.0651962 0.310122 -0.940064 0.0674742 0.334256 -0.926743 0.0677258 0.369541 -0.915296 0.0594619 0.398368 -0.912372 0.0608472 0.404814 -0.849365 0.0566876 0.524753 -0.876589 0.0631348 0.47708 -0.895207 0.0667415 0.440624 -0.583306 0.0291639 0.811729 -0.13341 -0.00111423 0.99106 -0.137204 0.000703042 0.990543 -0.444921 0.0351479 0.89488 -0.313417 0.0170383 0.949463 -0.325891 0.0162257 0.945268 -0.17127 0.0124902 0.985145 -0.198576 0.00359519 0.980079 -0.198426 0.00364997 0.980109 -0.198328 0.00369011 0.980129 -0.234789 -0.016674 0.971903 -0.134625 0.00714627 0.990871 -0.11776 0.0163558 0.992907 -0.0161321 -0.015078 0.999756 -0.0278903 -0.00528912 0.999597 -0.040409 -0.000984209 0.999183 -0.0609087 0.00246585 0.99814 -0.00130142 0 0.999999 -0.0208066 0.00181639 0.999782 -0.0110469 0.00425021 0.99993 -0.0319574 0.000979207 0.999489 -0.0683151 0.00144033 0.997663 -0.137183 0.00641504 0.990525 -0.119443 0.00914374 0.992799 -0.647444 0.059561 0.759782 -0.784338 0.0531747 0.61805 -0.753353 0.0657071 0.654326 -0.849228 0.0565847 0.524986 -0.850173 0.0350379 0.525336 -0.497289 0.0245845 0.867237 -0.496815 0.0511145 0.86635 -0.696938 0.0444337 0.715754 -0.444101 0.0161782 0.895831 -0.356762 0.0156313 0.934065 -0.313417 0.0167508 0.949468 -0.2413 0.00455365 0.97044 -0.129451 0.00824922 0.991552 -0.831441 0.0257343 0.555018 -0.770139 0.0272764 0.637293 -0.754838 0.0298472 0.655231 -0.723998 0.0255168 0.68933 -0.648485 0.0263848 0.76077 -0.652286 0.0273228 0.75748 -0.55923 0.0210446 0.828745 -0.969033 0.0272261 0.245425 -0.963757 0.0238888 0.265711 -0.950258 0.0247923 0.310477 -0.949114 0.0231807 0.314078 -0.916705 0.0262593 0.3987 -0.915149 0.0246461 0.402362 -0.877673 0.0263782 0.478533 -0.996136 0.048473 0.0732321 -0.998619 0.0482945 0.0206891 -0.998555 0.0493536 0.0212537 -0.998503 0.0493645 -0.0235678 -0.999125 0.024936 -0.0335841 -0.990174 0.0282183 0.136964 -0.990305 0.0292804 0.135788 -0.994385 0.0289563 0.101783 -0.996096 0.0315679 0.0824387 -0.997248 0.0160612 0.0723769 -0.999648 0.0157629 0.0213303 -0.998519 0.0413364 0.0353674 -0.999897 -0.00436597 -0.0137 -0.994646 0.100004 -0.026063 -0.996103 0.085504 -0.0216329 -0.996148 0.085496 0.0194841 -0.996296 0.0835115 0.0205107 -0.994106 0.0835903 0.0690327 -0.994434 0.0759481 0.0730312 -0.988522 0.0761718 0.130472 -0.988533 0.0666095 0.135517 -0.978622 0.0670426 0.194433 -0.980554 0.0241816 0.194753 -0.977711 0.0164531 0.20931 -0.727312 -0.0283085 0.685723 -0.129455 0.00247703 0.991582 -0.134847 -0.000454905 0.990866 -0.165417 -0.00829512 0.986189 -0.178408 -0.00500917 0.983944 -0.163499 -0.0289799 0.986118 -0.187867 -0.0125645 0.982114 -0.201255 -0.0107697 0.97948 -0.20718 -0.0105559 0.978246 -0.200413 -0.0107835 0.979652 -0.191228 -0.0101993 0.981493 -0.1884 -0.0100054 0.982041 -0.453367 -0.0302929 0.890809 -0.482094 -0.0377372 0.875307 -0.614833 -0.0475413 0.787223 -0.726262 -0.0573122 0.685025 -0.719273 -0.0546178 0.692577 -0.804442 -0.062463 0.590739 -0.798401 -0.0597151 0.599158 -0.913097 -0.0655048 0.402446 -0.909623 -0.0655898 0.410225 -0.875323 -0.0658962 0.479027 -0.897206 -0.0458163 0.439229 -0.857711 -0.064312 0.510094 -0.968072 -0.0728732 0.239846 -0.95562 -0.0708296 0.285961 -0.987646 -0.0959439 0.123894 -0.987623 -0.096075 0.12398 -0.995591 -0.0833872 0.0429623 -0.990858 -0.113143 0.0734758 -0.989154 -0.113192 0.0936029 -0.987328 -0.14485 0.0648177 -0.993138 -0.115627 0.017529 -0.9913 -0.131448 0.00674125 -0.997676 -0.0662069 -0.0160945 -0.994632 -0.0999719 -0.0267052 -0.992409 -0.120997 -0.0220133 -0.991533 -0.127507 -0.0245805 -0.989541 -0.141662 -0.0272245 -0.972359 -0.0253094 0.232114 -0.977408 -0.0166688 0.210705 -0.932567 -0.061625 0.355697 -0.926812 -0.0682827 0.369265 -0.954302 -0.0684551 0.290899 -0.956248 -0.0272811 0.291281 -0.96376 -0.0237338 0.265712 -0.611025 -0.0463555 0.790253 -0.611493 -0.0277559 0.790763 -0.652353 -0.0233134 0.757557 -0.323666 -0.0238282 0.945871 -0.271645 -0.0124585 0.962317 -0.271641 -0.00639407 0.962378 -0.164697 -0.00557938 0.986328 -0.14162 -0.00208248 0.989919 -0.241286 -0.0118962 0.970381 -0.356769 -0.014283 0.934084 -0.453466 -0.0194947 0.891061 -0.444063 -0.0208833 0.895752 -0.55923 -0.0210695 0.828745 -0.723929 -0.0290325 0.689264 -0.770166 -0.0259459 0.637316 -0.805862 -0.0288361 0.5914 -0.831514 -0.022008 0.555067 -0.876889 -0.0331527 0.479548 -0.877507 -0.0327823 0.478442 -0.929027 -0.0143392 0.369734 -0.914867 -0.0349677 0.402238 -0.949178 -0.0200608 0.3141 -0.979995 -0.101639 0.171111 -0.976722 -0.0680083 0.203441 -0.989934 -0.0674907 0.124403 -0.988636 -0.0768416 0.12921 -0.994893 -0.0766088 0.0657153 -0.994056 -0.0838478 0.0694461 -0.996326 -0.0837751 0.017785 -0.996169 -0.0854405 0.018646 -0.995799 -0.0854303 -0.0329661 -0.998443 -0.043141 0.0353647 -0.999724 -0.013302 0.0193734 -0.997208 -0.0184004 0.0723739 -0.997216 -0.0182746 0.0722968 -0.994702 -0.0142163 0.101815 -0.990977 -0.0188272 0.132705 -0.990499 -0.0118762 0.137009 -0.977743 -0.0143328 0.209316 -0.975058 -0.0670148 0.211592 -0.969798 -0.0763436 0.231652 -0.979725 -0.0775592 0.184726 -0.981923 -0.0395688 0.185097 -0.990812 -0.0389062 0.129531 -0.990166 -0.0445633 0.13261 -0.996589 -0.0441168 0.0697366 -0.996204 -0.0486254 0.0721986 -0.998648 -0.0484575 0.0188301 -0.998597 -0.0493046 0.0192938 -0.998492 -0.0493185 -0.024127 -0.995775 0.0595741 -0.0698838 -0.999588 -0.0252426 -0.0136958 1.61336e-07 -0.181329 0.983423 0.0139425 -0.0420255 0.999019 -0.0249564 -0.114947 0.993058 0.0122754 -0.0167665 0.999784 -0.0133632 -0.0521044 0.998552 0 -0.00805396 0.999968 0.00693735 -0.0618995 0.998058 0.00343522 -0.0803778 0.996759 -5.71315e-05 -0.10177 0.994808 0.00263011 -0.108994 0.994039 -0.00386464 -0.0950689 0.995463 0.0267202 -0.12017 0.992394 -0.00568535 -0.0637586 0.997949 -0.00802579 -0.283449 0.958954 0.0105239 -0.200106 0.979718 -0.00792758 -0.375959 0.926602 -0.00147083 -0.337191 0.941435 0.00152559 -0.483581 0.875299 0.000848911 -0.486897 0.873459 -0.000642795 -0.598555 0.801081 -6.13477e-06 -0.594838 0.803846 -6.11878e-06 -0.653341 0.757064 0.00139042 -0.67037 0.742026 -0.00231866 -0.710894 0.703295 0.0043865 -0.7534 0.657548 -9.67642e-07 -0.774309 0.632807 -8.73654e-07 -0.810838 0.585271 0.00392732 -0.840896 0.541183 0.00349717 -0.842084 0.539336 -0.000568517 -0.873694 0.486475 0.000695379 -0.892372 0.4513 -3.5518e-05 -0.896333 0.443383 -3.53435e-05 -0.920646 0.3904 -0.000156921 -0.921002 0.389558 0.000247728 -0.956504 0.291719 0.00205576 -0.954298 0.298849 -0.000429983 -0.975175 0.221436 0.0022953 -0.986984 0.160805 0.00263512 -0.986709 0.162475 -0.00265106 -0.99795 0.0639413 0.00666652 -0.995554 0.0939555 0 -0.998667 0.0516131 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0.982821 -0.0686047 0.171339 0.98066 -0.11115 0.161096 0.980946 -0.106704 0.162357 0.980667 -0.0754713 0.180543 0.97436 -0.0782272 0.21096 0.969093 -0.0675479 0.237267 0.96502 -0.0709598 0.252392 0.956739 -0.0712041 0.2821 0.941907 -0.0601039 0.330453 0.945643 -0.0680568 0.318005 0.914577 -0.0684963 0.39857 0.90162 -0.0570175 0.428754 0.882801 -0.0677482 0.464837 0.681321 -0.0583076 0.729659 0.696841 -0.0643256 0.714335 0.775209 -0.0662189 0.628225 0.772083 -0.06459 0.632231 0.840166 -0.07002 0.53779 0.832185 -0.0646811 0.550713 0.861294 -0.0679488 0.503543 0.552428 -0.0465388 0.832261 0.579479 -0.0539451 0.8132 0.62928 -0.0603126 0.774835 0.395298 -0.032626 0.917973 0.476245 -0.0477534 0.878015 0.533713 -0.0483634 0.844282 0.0986391 -0.00230918 0.995121 0.014669 -0.00120239 0.999892 0.0187917 -1.15948e-05 0.999823 0.115357 -0.00765 0.993295 0.177496 -0.0122051 0.984046 0.234413 -0.0159144 0.972007 0.244905 -0.019911 0.969343 0.375206 -0.0355907 0.926258 0.0117617 0 0.999931 0.0146741 -0.0008785 0.999892 0.0794715 -0.000853616 0.996837 0.0985713 -0.00660042 0.995108 0.205303 -0.00649469 0.978677 0.234423 -0.0153683 0.972013 0.3693 -0.0149482 0.92919 0.395535 -0.0232771 0.918156 0.536184 -0.0221578 0.84381 0.55305 -0.0279452 0.832679 0.674394 -0.0260721 0.737911 0.682515 -0.0291889 0.730289 0.773991 -0.0269566 0.632623 0.776959 -0.0282594 0.628916 0.841542 -0.0260756 0.539563 0.84228 -0.0264503 0.538391 0.90292 -0.0237112 0.429154 0.90303 -0.0238578 0.428915 0.947322 -0.021292 0.319575 0.947795 -0.0221446 0.318109 0.970409 -0.0205247 0.240595 0.971191 -0.0224232 0.237244 0.982691 -0.0214803 0.184003 0.981937 -0.0194863 0.1882 0.979838 0.112329 0.165228 0.020736 1.15902e-05 0.999785 0.014659 0.00184695 0.999891 0.0986464 0.00183984 0.995121 0.120719 0.00859797 0.992649 0.234416 0.0157636 0.972009 0.247054 0.020551 0.968784 0.394879 0.0465956 0.917551 0.477006 0.0200697 0.878671 0.376575 0.0354015 0.925709 0.968457 0.0762883 0.237215 0.973416 0.0651036 0.219599 0.98272 0.0762113 0.168681 0.980293 0.0689575 0.185123 0.980205 0.107178 0.166469 0.0146877 0 0.999892 0.0117617 0.000879531 0.999931 0.0986618 0.000845529 0.995121 0.0794698 0.00661116 0.996815 0.234581 0.0064518 0.972075 0.205283 0.0154177 0.978581 0.39572 0.0148267 0.918252 0.36924 0.0234157 0.929039 0.553209 0.0219741 0.832752 0.536103 0.0281425 0.843683 0.682613 0.0259114 0.730321 0.674333 0.0293515 0.737844 0.777002 0.0268679 0.628924 0.773961 0.0283459 0.632598 0.842292 0.026046 0.538392 0.841533 0.0264784 0.539557 0.903034 0.023705 0.428915 0.902917 0.0238632 0.429153 0.947817 0.0212562 0.318105 0.947304 0.0221741 0.319569 0.971238 0.0204521 0.237231 0.970368 0.0224805 0.240585 0.982027 0.0215439 0.187505 0.982732 0.0194564 0.184011 0.963927 0.0709957 0.256522 0.956007 0.0712195 0.284567 0.946016 0.0624071 0.318054 0.939415 0.0692179 0.335721 0.901035 0.0664754 0.428622 0.913288 0.0505748 0.404162 0.881456 0.0677725 0.467379 0.861378 0.0679554 0.503398 0.840452 0.0656229 0.537897 0.832717 0.0690396 0.549377 0.775269 0.0652187 0.628255 0.774429 0.0655632 0.629255 0.680976 0.0647911 0.729434 0.697916 0.0579614 0.71383 0.627903 0.0601641 0.775963 0.552273 0.0504325 0.832136 0.574248 0.0451127 0.817438 0.528108 0.0483216 0.847801 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.76709e-05 -3.89376e-06 1 1.45287e-05 -1.00284e-05 1 2.04986e-05 -2.48919e-06 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 1.76709e-05 8.57139e-07 1 1.23041e-05 1.38884e-05 1 1.70664e-05 6.47239e-06 1 1.21975e-05 1.16346e-05 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -3.6712e-05 -1.16347e-05 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 3.50091e-05 4.058e-06 1 2.6426e-05 1.9492e-06 1 2.48214e-05 1.53738e-06 1 0 0 1 0.0290086 -0.253515 -0.966896 0 -0.00753571 -0.999972 0.0145615 -0.0459846 -0.998836 -0.0119254 -0.0188851 -0.999751 0.0117166 -0.102777 -0.994635 -0.0026478 -0.0718241 -0.997414 0.000886395 -0.129651 -0.991559 -0.0011783 -0.156525 -0.987673 0.0069008 -0.247032 -0.968983 0.00550317 -0.253207 -0.967396 -0.016541 -0.286447 -0.957953 0.00832836 -0.262892 -0.964789 0 -0.612616 -0.790381 0 -0.51789 -0.855447 0.00890128 -0.488009 -0.872793 0 -0.398577 -0.917135 0 -0.335691 -0.941972 0.00178776 -0.633651 -0.773617 -0.0033782 -0.680319 -0.732909 -0.00598847 -0.694808 -0.71917 1.34835e-05 -0.722005 -0.691888 1.34739e-05 -0.760907 -0.648861 -0.00202202 -0.784709 -0.619861 0.0034893 -0.808037 -0.589122 -0.00269975 -0.844372 -0.535751 -1.30629e-06 -0.856725 -0.515773 -1.48885e-06 -0.883945 -0.467591 2.9127e-06 -0.883963 -0.467556 2.02864e-05 -0.897008 -0.442015 -0.000395817 -0.921848 -0.38755 -0.000997838 -0.920881 -0.389843 0.000111818 -0.944817 -0.327598 -0.00137679 -0.962992 -0.269527 -0.00590229 -0.957275 -0.28912 -0.00158445 -0.968321 -0.249703 -0.000213491 -0.973677 -0.227933 0.00074642 -0.985033 -0.172363 -1.52268e-05 -0.984234 -0.176874 -1.23712e-05 -0.993141 -0.116924 -0.000596061 -0.992407 -0.122994 0.00121188 -0.998037 -0.0626153 -0.00208372 -0.997227 -0.0743899 1.98717e-06 -0.998968 -0.0454198 9.19564e-07 -0.999048 -0.0436195 -1.32497e-07 -0.999048 -0.0436194 1.98468e-06 -0.999048 -0.0436214 2.23413e-06 -0.999048 -0.0436212 4.65814e-07 -0.999048 -0.0436195 -4.50944e-06 -0.999048 -0.0436263 9.45986e-06 -0.999048 -0.0436231 1.95932e-05 -0.999048 -0.0436174 1.18318e-05 -0.999049 -0.0436064 -3.65114e-06 -0.999048 -0.0436194 -6.19342e-06 -0.999048 -0.0436251 2.07658e-06 -0.999048 -0.0436189 3.58437e-06 -0.999048 -0.0436149 -1.84805e-06 -0.999048 -0.0436194 -1.94558e-06 -0.999048 -0.0436201 -1.76956e-06 -0.999048 -0.0436234 3.47105e-06 -0.999048 -0.0436168 2.62017e-06 -0.999048 -0.0436209 9.34408e-06 -0.999048 -0.0436177 7.85495e-06 -0.999048 -0.043623 -2.16278e-07 -0.999048 -0.0436193 4.43843e-07 -0.999048 -0.0436197 -7.37923e-07 -0.999048 -0.0436192 -8.61997e-07 -0.999048 -0.0436184 3.95435e-07 -0.999048 -0.0436204 1.35121e-06 -0.999048 -0.0436213 -5.60777e-06 -0.999048 -0.0436167 -5.47046e-07 -0.999048 -0.0436194 -4.97201e-06 -0.999048 -0.0436189 3.8457e-07 -0.999048 -0.0436195 -1.37122e-05 -0.999049 -0.043613 -1.07516e-06 -0.999048 -0.0436194 -3.29467e-07 -0.999048 -0.0436194 -3.58369e-06 -0.999048 -0.0436192 -1.33529e-07 -0.999048 -0.0436194 5.48783e-06 -0.999048 -0.04362 1.97167e-06 -0.999048 -0.0436196 -8.09916e-06 -0.999048 -0.0436225 -7.66825e-06 -0.999048 -0.0436229 1.90973e-06 -0.999048 -0.0436302 1.15727e-05 -0.999048 -0.0436161 8.10908e-06 -0.999048 -0.0436223 -2.18606e-06 0.999048 -0.0436192 -3.45484e-07 0.999048 -0.0436193 7.91728e-08 0.999048 -0.0436192 -1.91311e-06 0.999048 -0.0436194 1.91319e-06 0.999048 -0.0436195 1.5686e-07 0.999048 -0.0436193 1.3522e-06 0.999048 -0.0436199 1.69237e-07 0.999048 -0.0436192 2.20664e-06 0.999048 -0.0436208 7.2378e-08 0.999048 -0.0436196 -6.04214e-08 0.999048 -0.0436193 -5.04907e-07 0.999048 -0.0436203 1.27551e-06 0.999048 -0.04362 2.06863e-07 0.999048 -0.0436196 -8.02575e-08 0.999048 -0.0436193 5.26807e-09 0.999048 -0.0436194 -8.9752e-07 0.999048 -0.0436191 1.8631e-07 0.999048 -0.0436149 -9.92408e-07 0.999048 -0.043624 3.04194e-06 0.999048 -0.0436208 -5.5278e-07 0.999048 -0.0436229 -3.73574e-07 0.999048 -0.0436213 9.45987e-06 0.999048 -0.0436189 2.98306e-06 0.999048 -0.0436162 4.09421e-07 0.999048 -0.043619 5.23052e-07 0.999048 -0.0436191 -5.23617e-09 0.999048 -0.0436201 -4.44652e-08 0.999048 -0.0436191 1.20898e-07 0.999048 -0.0436194 -9.50274e-08 0.999048 -0.0436193 3.00774e-07 0.999048 -0.0436191 -3.91326e-07 0.999048 -0.0436198 3.1694e-06 0.999048 -0.0436233 -1.98368e-08 0.999048 -0.043615 -3.9933e-07 0.999048 -0.0436204 1.13371e-06 0.999048 -0.0436218 8.67821e-07 0.999048 -0.0436214 1.27024e-06 0.999048 -0.0436154 -1.09287e-06 0.999048 -0.0436213 3.43484e-08 0.999048 -0.0436193 2.92171e-06 0.999048 -0.0436213 -3.66895e-06 0.999048 -0.0436161 1.76772e-05 0.00706021 0.999975 0.0035977 0.585037 0.810999 -0.00870332 0.655034 0.75555 0 0.576548 0.817063 0 0.513685 0.857979 0.019292 0.485369 0.874096 -0.0129548 0.409854 0.912059 0 0.378199 0.925724 0 0.329724 0.944078 0.0174236 0.23787 0.971141 0.0301062 0.249738 0.967845 -0.000135681 0.160753 0.986995 0.000341109 0.0471074 0.99889 0.0510663 0.0897717 0.994652 0.0118601 0.0444648 0.998941 -0.00706981 0.656425 0.754358 0.00099071 0.70699 0.707222 -0.00735083 0.75088 0.660398 -0.0156657 0.744705 0.667209 0.0132625 0.80877 0.587975 0.00369821 0.801694 0.597723 -0.00204245 0.843327 0.537397 0.0115617 0.859189 0.511527 -0.0151367 0.889272 0.457128 0.00176213 0.902286 0.431134 -0.00109639 0.925496 0.378757 -0.0147428 0.94011 0.340553 0.0087585 0.951284 0.30819 -0.00319558 0.96856 0.24876 -6.96451e-07 0.971864 0.235544 -5.4885e-07 0.982621 0.185625 -0.00982534 0.986352 0.164359 0.00520079 0.98345 0.181107 -0.00180139 0.992701 0.120592 -0.0100617 0.994499 0.104265 -0.0245771 0.995811 0.0880722 -0.0232871 0.995764 0.0889472 0.00121913 0.998559 0.0536563 -0.00172467 0.999569 0.0293175 0.00407401 0.999739 0.0224791 -0.0112972 0.999649 -0.0239495 -0.0169213 0.999602 -0.0225768 9.46271e-06 0.999348 -0.0361002 -0.00801422 0.998938 -0.0453779 -0.000108786 0.999211 -0.0397055 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.999999 0 -0.0013742 -0.999999 -0.000268579 -0.00141482 -0.99993 0.000593058 -0.0118276 -0.999926 -0.00115197 -0.0121006 -0.999553 0.00125968 -0.029866 -0.999539 -0.00150895 -0.0303323 -0.998698 0.00193417 -0.0509843 -0.99892 -0.00208261 -0.0464127 -0.997643 0.00193653 -0.0685876 -0.997873 -0.00180853 -0.0651632 -0.996414 0.00159888 -0.0845944 -0.996583 -0.00117539 -0.0825912 -0.995169 0.000985063 -0.09817 -0.995255 -0.000543656 -0.0972995 -0.994085 0.000408734 -0.108603 -0.994111 -9.29458e-05 -0.108367 -0.99324 7.21569e-05 -0.116077 -0.9932 -0.000830234 -0.116419 -0.993154 6.2743e-05 -0.116814 -0.994806 -0.000538629 -0.101791 -0.994775 0.00136912 -0.102085 -0.998755 -0.00226454 -0.0498235 -0.998834 0.00493911 -0.0480277 -0.999807 -0.00338606 0.0193695 -0.999851 0.00480878 0.0166019 -0.996917 -0.00536466 0.0782804 -0.997181 0.00457992 0.0748952 -0.993856 -0.000329757 0.11068 -0.990262 -0.00599972 0.139089 -0.990784 0.00549127 0.135338 -0.98311 -0.00426398 0.182964 -0.983574 0.00342822 0.180474 -0.976705 -0.00322616 0.214563 -0.976847 0.00104213 0.213936 -0.978259 0.00213366 0.207377 -0.978109 -0.00258854 0.208076 -0.987605 0.00373961 0.156917 -0.999987 0 0.00510409 -0.999987 -0.000165276 0.0051498 -0.999478 0.000253569 0.0323089 -0.999472 -0.000222142 0.0324837 -0.997844 0.000225212 0.0656353 -0.997848 0.000383399 0.0655633 -0.995179 -0.000394864 0.0980718 -0.995253 0.00106619 0.0973175 -0.993109 -0.000274869 0.117193 -0.993177 -5.20266e-07 0.116615 -0.987766 -6.95735e-07 0.155945 -0.999999 0 -0.00135575 -0.999987 0 0.00519913 -0.995155 -0.000998854 0.0983165 -0.99528 0.000870717 0.0970461 -0.997804 -0.000900266 0.0662358 -0.997885 0.000666954 0.0649968 -0.999459 -0.000670615 0.0328924 -0.999485 0.000158697 0.0321015 -0.999987 -9.68245e-05 0.0051729 -0.978213 0.000866071 0.207603 -0.988279 -0.00146808 0.152655 -0.987633 0.018601 0.155678 -0.993109 0.00027487 0.117193 -0.97816 -0.000178302 0.207852 -0.976759 -8.7441e-05 0.214341 -0.97677 -0.000412553 0.214291 -0.980304 1.17361e-05 0.197493 -0.983383 -0.00175433 0.181537 -0.983448 -0.000985187 0.181188 -0.990632 0.00128543 0.13655 -0.990437 -0.00195929 0.137955 -0.997099 0.00223039 0.0760817 -0.99696 -0.00190564 0.0778866 -0.999848 0.001682 0.0173348 -0.999828 -0.00105492 0.0185384 -0.998805 0.001613 -0.0488406 -0.998826 -0.00171343 -0.0484112 -0.998787 0.00170384 -0.0492023 -0.997785 -0.00169927 -0.0664961 -0.997725 0.00150137 -0.0673926 -0.996541 -0.00140596 -0.0830859 -0.996462 0.00118016 -0.0840345 -0.995254 -0.00105834 -0.0973037 -0.99518 0.000564535 -0.0980638 -0.994117 -0.000477983 -0.108309 -0.994084 8.76455e-05 -0.108615 -0.99324 -7.21617e-05 -0.116077 -0.993237 -5.19067e-07 -0.116104 -0.993155 -5.22195e-07 -0.116804 -0.993156 -1.02004e-05 -0.116799 -0.994792 1.55334e-05 -0.101927 -0.994785 0.000290672 -0.101994 -0.99879 -0.000496746 -0.0491758 -0.999964 0.00802905 -0.00267674 -0.999916 -0.00761052 -0.0105092 -0.999733 0.0176466 -0.014893 -0.999512 -0.0157166 -0.0270135 -0.999537 0.00168613 -0.0303667 -1 0 0 -1 0 0 -1 0 0 8.73013e-07 -0.999048 0.0436192 1.78623e-05 -0.999048 0.043626 1.29291e-06 -0.999048 0.0436198 -9.21399e-07 -0.999048 0.0436188 7.23284e-07 -0.999048 0.0436193 -1.33998e-05 -0.999048 0.043622 -4.55344e-06 -0.999048 0.0436204 7.6483e-07 -0.999048 0.0436194 -9.13387e-06 -0.999048 0.0436207 1.0094e-05 -0.999048 0.0436269 2.09626e-08 -0.999048 0.0436192 0 -0.999048 0.0436192 1.34587e-07 -0.999048 0.0436192 -1.17361e-06 -0.999048 0.0436201 -4.47625e-07 -0.999048 0.0436197 3.1276e-06 -0.999048 0.0436179 -7.53373e-07 -0.999048 0.0436195 -1.01451e-06 -0.999048 0.0436185 -2.30502e-06 -0.999048 0.043623 -6.10783e-07 -0.999048 0.0436193 -6.60029e-07 -0.999048 0.0436193 -6.86666e-06 -0.999048 0.0436221 -9.20534e-07 -0.999048 0.0436195 -1.92863e-07 -0.999048 0.0436191 1.74719e-05 -0.999049 0.0436108 1.88005e-05 -0.999048 0.0436272 1.88568e-05 -0.999048 0.0436226 -1.44596e-05 -0.999048 0.0436246 8.21324e-06 -0.999048 0.043619 -1.26521e-06 -0.999048 0.0436194 -2.84895e-05 -0.999048 0.0436214 1.11962e-07 -0.999048 0.0436194 8.41931e-06 -0.999048 0.0436187 1.97475e-06 -0.999048 0.0436191 -1.17316e-05 -0.999048 0.043621 3.23829e-08 -0.999049 0.0436122 1.41943e-05 -0.999048 0.0436209 -2.44653e-06 -0.999048 0.0436326 -1.01264e-05 -0.999048 0.0436185 -7.93655e-06 -0.999048 0.0436137 -2.51864e-06 -0.999048 0.0436194 -3.51675e-07 -0.999049 0.0436088 7.9904e-06 -0.999048 0.0436191 7.67254e-06 -0.999048 0.04362 8.98503e-05 0.999129 0.041732 -5.35527e-06 0.829081 -0.559129 0 0.00762074 -0.999971 -0.00617893 0.0169129 -0.999838 0.00824227 0.0605526 -0.998131 -0.0203209 0.101675 -0.99461 0.0149834 0.0713002 -0.997342 -0.000112651 0.104701 -0.994504 0.000259578 0.167966 -0.985793 0.0128259 0.154897 -0.987847 -0.0535779 0.276803 -0.959432 0.000216262 0.240178 -0.970729 0.240636 0.210323 -0.947554 -5.25593e-05 0.307543 -0.951534 0.0170162 0.240144 -0.970588 0.0248433 0.241867 -0.969991 0.00318104 0.243248 -0.969959 -0.0003117 0.356181 -0.934417 0.00486992 0.377708 -0.925912 0.0394334 0.417542 -0.907801 0.0344428 0.420464 -0.906655 -0.0387772 0.527013 -0.848972 -6.39344e-05 0.517043 -0.855959 -6.41018e-05 0.602328 -0.798249 -0.234047 0.663979 -0.710179 0.0367647 0.651483 -0.757772 -0.000111516 0.726217 -0.687465 -0.000111987 0.736522 -0.676414 -0.00618349 0.742363 -0.66997 0.0340349 0.787734 -0.615074 0.0615608 0.782338 -0.619805 -0.106322 0.832675 -0.543459 0.0406528 0.808025 -0.587744 0.0177796 0.81791 -0.575072 0.00905397 0.830054 -0.557609 0.00572089 0.980674 -0.195563 -0.000196394 0.827972 -0.560769 -0.000197824 0.859136 -0.511747 0.00780329 0.874005 -0.485854 -0.0130231 0.89327 -0.449331 0.0115248 0.917749 -0.396995 -2.76782e-05 0.928074 -0.372396 -1.98367e-05 0.948946 -0.315438 -0.000131191 0.9875 -0.157617 0.00116053 0.970391 -0.241537 -0.145299 0.93012 -0.33729 0.0376228 0.970564 -0.237885 0.0390756 0.970735 -0.236954 0.0520268 0.969425 -0.239809 0.00515346 0.99077 -0.135455 0.0244836 0.992494 -0.11982 0.0790871 0.99279 -0.0900718 0.0832707 0.996434 -0.013585 -0.0916549 0.995722 -0.0117506 0.159814 0.984352 -0.0742316 0.00822265 0.999963 0.00238043 3.23218e-05 0.99993 0.0118127 1.60622e-05 0.999404 0.0345097 0.00898743 0.99943 0.0325352 0.00352742 0.999338 0.0362185 0.00187506 0.999281 0.0378792 3.02417e-08 0.99917 0.0407285 0.00170928 0.99906 0.0433184 0.000227901 0.999125 0.0418179 4.31002e-06 0.999048 0.0436179 1.25993e-06 0.999048 0.0436195 -3.04678e-06 0.999048 0.0436198 9.21381e-06 0.999048 0.0436151 -1.70204e-07 0.999048 0.0436194 1.29023e-06 0.999048 0.043619 -7.90955e-07 0.999048 0.04362 8.33612e-08 0.999048 0.0436193 6.08596e-07 0.999048 0.0436199 -5.50726e-07 0.999048 0.0436196 -5.12312e-07 0.999048 0.0436196 -2.52312e-07 0.999048 0.0436194 8.31511e-06 0.999048 0.0436154 2.73076e-07 0.999048 0.0436193 1.25744e-07 0.999048 0.0436193 -3.43388e-07 0.999048 0.0436195 1.58288e-06 0.999048 0.0436189 1.00103e-06 0.999048 0.0436195 -1.23933e-06 0.999048 0.0436195 -1.094e-07 0.999048 0.0436194 -3.74781e-08 0.999048 0.0436194 -8.31842e-07 0.999048 0.0436196 1.08365e-06 0.999048 0.0436193 -2.3675e-07 0.999048 0.0436195 -5.99345e-07 0.999048 0.0436195 4.54024e-06 0.999048 0.043616 -1.10034e-07 0.999048 0.0436202 -6.57562e-06 0.999048 0.0436225 -2.50869e-06 0.999048 0.0436199 1.99033e-06 0.999048 0.043619 -5.1141e-07 0.999048 0.0436197 8.40815e-08 0.999048 0.0436196 -1.25476e-07 0.999048 0.0436197 0 0.999048 0.0436196 -1.69504e-06 0.999048 0.0436178 4.07294e-07 0.999048 0.0436198 -1.02514e-07 0.999048 0.0436195 -1.67124e-06 0.999048 0.0436187 -9.09149e-08 0.999048 0.0436194 6.03353e-07 0.999048 0.043619 -9.08467e-07 0.999048 0.0436199 3.23883e-08 0.999048 0.0436195 3.1235e-08 0.999048 0.0436195 -3.02729e-08 0.999048 0.0436193 1.27997e-07 0.999048 0.0436192 -7.83757e-07 0.999048 0.0436178 6.89381e-08 0.999048 0.0436194 0.000433084 0.502015 0.864859 -0.000522156 0.614176 0.789169 0.000229953 0.617307 0.786722 -0.000206109 0.710134 0.704066 0.00769468 0.742666 0.669618 -0.0028159 0.787613 0.616164 -2.34606e-05 0.813198 0.581987 4.32207e-05 0.84186 0.539696 0.00234557 0.851904 0.523693 -0.000833322 0.874347 0.485301 -3.56961e-07 0.981921 0.189292 0.00124618 0.976938 0.213521 0.000150422 0.979478 0.20155 -0.000372246 0.958496 0.285105 0.00260504 0.910331 0.413873 -1.87589e-06 0.905435 0.424484 -1.49786e-06 0.934276 0.35655 -0.000325037 0.931757 0.363084 0.00153547 0.955964 0.293481 -2.81799e-06 0.989868 0.141988 0.000538965 0.990445 0.137906 -0.000312984 0.996118 0.0880289 0.00190762 0.997956 0.0638769 0 0.998643 0.0520802 0.0172556 0.0483628 0.998681 0.00913052 0.0716273 0.99739 -0.00922234 0.064688 0.997863 0.0440575 0.137711 0.989492 -0.00663546 0.104675 0.994484 -0.00113124 0.113409 0.993548 0 0.499354 0.866398 0 0.426399 0.904535 0.00120511 0.397475 0.917612 -0.00333197 0.332406 0.943131 0.00188645 0.283913 0.958848 -0.000822093 0.212538 0.977152 1.72974e-05 0.194648 0.980873 -3.50377e-05 0.115259 0.993335 0.00378077 0.0944747 0.99552 0 0.00798919 0.999968 0.000869936 0.00473419 0.999988 -0.00264212 0.0566308 0.998392 -0.0275099 0.127487 0.991459 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.499997 2.69847e-07 -0.866027 0.500001 -2.77923e-07 -0.866025 0.500001 6.33127e-08 -0.866025 0.500001 8.50277e-08 -0.866025 0.500001 -6.1635e-08 -0.866025 0.500001 -8.51532e-08 -0.866025 0.500001 -5.3465e-07 -0.866025 0.499998 5.36498e-07 -0.866027 0.499998 -1.10523e-06 0.866026 0.500003 5.01722e-07 0.866024 0.500003 1.39034e-06 0.866024 0.5 3.06904e-08 0.866026 0.5 -7.2061e-07 0.866026 0.499999 -8.18844e-07 0.866026 0.499999 -3.20779e-07 0.866026 0.500003 9.57262e-07 0.866024 0.500003 3.1541e-07 0.866024 0.500003 3.09243e-07 0.866024 0.500003 2.09303e-06 0.866024 0.499999 -1.03581e-06 0.866026 0.506318 0.0203038 0.862108 0.533297 0.0785194 0.842276 0.528205 0.12389 0.84003 0.581066 0.232638 0.779899 0.577755 0.262232 0.772938 0.61385 0.371629 0.696477 0.603341 0.36286 0.71015 0.626816 0.417813 0.657673 0.638175 0.469323 0.610302 0.631359 0.463958 0.621393 0.65339 0.505024 0.563944 0.6615 0.577981 0.477866 0.677897 0.53494 0.504277 0.67536 0.616328 0.405003 0.694688 0.631832 0.343797 0.688607 0.664381 0.290548 0.701073 0.671043 0.241242 0.698882 0.694439 0.171227 0.701247 0.693781 0.164075 0.709322 0.701796 0.0659155 0.705996 0.705993 0.0560711 0.704565 0.704561 -0.084748 0.726902 0.685646 -0.0387793 0.698664 0.699903 -0.148336 0.704756 0.673396 -0.223285 0.687598 0.66895 -0.282338 0.691698 0.651834 -0.310913 0.680724 0.601442 -0.41819 0.702258 0.603578 -0.377528 0.649406 0.557955 -0.516679 0.653862 0.539786 -0.530186 0.650237 0.486674 -0.583388 0.643277 0.472811 -0.602199 0.628915 0.420209 -0.654133 0.586592 0.377107 -0.716729 0.594983 0.337393 -0.729493 0.570705 0.195906 -0.797444 0.555141 0.249482 -0.793459 0.543346 0.0638363 -0.837078 0.506402 0.156346 -0.848005 0.515923 0.0527297 -0.85501 0.610366 -0.295319 -0.73501 0.553937 -0.19971 -0.808251 0.551105 -0.147405 -0.821313 0.514881 -0.0679258 -0.854567 0.515923 -0.0527297 -0.85501 0.559002 -0.248448 -0.791069 0.60718 -0.333013 -0.721412 0.614774 -0.407046 -0.675549 0.625536 -0.417788 -0.658906 0.651402 -0.498076 -0.57236 0.697412 -0.648606 -0.30484 0.678343 -0.643287 -0.35501 0.684104 -0.600171 -0.414482 0.664788 -0.572386 -0.480033 0.667045 -0.554531 -0.49754 0.648862 -0.496114 -0.57693 0.70424 -0.704237 -0.089983 0.718776 -0.692459 -0.0621376 0.691214 -0.690028 -0.214672 0.708873 -0.685016 -0.168085 0.697225 -0.674466 -0.242844 0.686364 -0.691373 0.225628 0.715765 -0.696012 0.0569893 0.70498 -0.704976 0.0775366 0.661576 -0.535566 0.524868 0.678977 -0.611825 0.405784 0.693756 -0.615989 0.373175 0.688355 -0.664035 0.291933 0.719405 -0.673213 0.170995 0.63761 -0.353275 0.684581 0.63431 -0.469123 0.614471 0.671746 -0.538323 0.508888 0.608119 -0.433767 0.664859 0.601217 -0.326772 0.729217 0.575912 -0.260648 0.774847 0.57862 -0.222442 0.784677 0.555798 -0.177024 0.812251 0.522497 -0.0769243 0.849164 0.522778 -0.0772016 0.848966 -0.866024 -2.21443e-06 -0.500003 -0.866021 -8.92984e-06 -0.500008 -0.866027 5.45984e-06 -0.499997 -0.866027 1.77377e-06 -0.499997 -0.866025 3.08115e-07 -0.500001 -0.866028 -1.92816e-06 -0.499995 -0.866028 1.48481e-05 -0.499995 0.866025 0 -0.500001 0.866025 0 -0.500001 0.139196 -0.699703 -0.700743 0.096436 -0.714214 -0.693253 0.0657926 -0.705575 -0.705575 0.650294 -0.447118 -0.614169 0.656927 -0.427182 -0.621258 0.556676 -0.50979 -0.655917 0.491417 -0.57294 -0.655934 0.500386 -0.570895 -0.650917 0.28793 -0.638284 -0.713925 0.390451 -0.660568 -0.641248 0.214019 -0.674867 -0.706222 0.723423 -0.326853 -0.608133 0.820899 -0.206297 -0.532509 0.765378 -0.255312 -0.590773 0.857023 -0.0716586 -0.510271 0.846094 -0.0880561 -0.525711 0.848437 0.0792311 -0.523333 0.848814 0.0933464 -0.520385 0.782668 0.229663 -0.57852 0.779766 0.243563 -0.576751 0.6984 0.37239 -0.611198 0.699251 0.369868 -0.611756 0.646547 0.428811 -0.630951 0.590815 0.483839 -0.64563 0.578944 0.504685 -0.640404 0.466946 0.568793 -0.67708 0.451362 0.584168 -0.674552 0.340241 0.640858 -0.68814 0.332898 0.647444 -0.685562 0.199643 0.68137 -0.704186 0.133474 0.716725 -0.684463 0.191642 0.685473 -0.702425 0.0658247 0.705635 -0.705512 0.0659818 0.705565 -0.705566 -0.864039 -0.010542 -0.503315 -0.846513 -0.0742463 -0.527165 -0.846051 -0.113421 -0.520897 -0.79204 -0.207269 -0.574206 -0.767236 -0.284482 -0.574821 -0.717545 -0.334806 -0.610765 -0.685023 -0.387549 -0.616887 -0.628325 -0.443023 -0.639483 -0.630189 -0.4398 -0.639873 -0.545754 -0.528763 -0.650048 -0.513528 -0.539594 -0.667179 -0.423904 -0.602353 -0.67637 -0.36814 -0.618377 -0.694322 -0.313972 -0.656391 -0.685983 -0.214621 -0.673228 -0.707603 -0.18196 -0.691192 -0.699389 -0.0706989 -0.700925 -0.709723 -0.0593209 -0.705862 -0.705862 -0.438987 0.551689 -0.709175 -0.358715 0.635234 -0.68396 -0.260651 0.66678 -0.698188 -0.216487 0.673504 -0.706771 -0.179539 0.691944 -0.699271 -0.0578002 0.700792 -0.71102 -0.0730271 0.705218 -0.705219 -0.381817 0.640949 -0.665883 -0.493047 0.553335 -0.671361 -0.552837 0.520851 -0.65045 -0.560404 0.512272 -0.650788 -0.640617 0.427103 -0.638117 -0.649917 0.401984 -0.644994 -0.715732 0.34458 -0.607447 -0.760275 0.279653 -0.586324 -0.810131 0.209716 -0.547454 -0.808307 0.235665 -0.539539 -0.821575 0.156007 -0.54834 -0.85318 0.0557931 -0.518624 -0.855348 0.0512712 -0.51551 -0.866021 -9.12059e-06 -0.500008 -0.866027 3.98686e-06 -0.499998 -0.866027 1.46825e-05 -0.499998 -0.866022 -3.47882e-06 -0.500006 0.0647758 -0.705621 -0.705622 0.0667861 -0.70487 -0.706185 0.2007 -0.684334 -0.701004 0.198053 -0.685818 -0.700306 0.339995 -0.639977 -0.689081 0.294297 -0.675283 -0.676301 0.45581 -0.55504 -0.695822 0.425107 -0.60272 -0.675287 0.592367 -0.482193 -0.645439 0.548748 -0.547659 -0.631621 0.569914 -0.517206 -0.638511 0.68249 -0.365393 -0.633004 0.671903 -0.40111 -0.622621 0.78783 -0.234214 -0.56962 0.841464 -0.104715 -0.530069 0.84001 -0.0772849 -0.537038 0.783619 -0.253525 -0.567156 0.866029 0 -0.499994 0.866029 0 -0.499994 -0.852656 0.0625281 -0.518718 -0.0698934 0.705377 -0.705378 -0.0926775 0.695199 -0.712818 -0.205727 0.687232 -0.696699 -0.230533 0.675859 -0.70005 -0.280498 0.661353 -0.695653 -0.296927 0.655132 -0.69472 -0.704353 0.353542 -0.615544 -0.622934 0.458604 -0.633748 -0.583004 0.483515 -0.652932 -0.549 0.517135 -0.656636 -0.451182 0.586823 -0.672364 -0.473538 0.557112 -0.682194 -0.347815 0.646328 -0.67918 -0.379691 0.621001 -0.685706 -0.31065 0.651084 -0.692521 -0.842134 0.177786 -0.509119 -0.69013 0.391671 -0.608535 -0.733808 0.319943 -0.599302 -0.755498 0.286349 -0.58926 -0.766764 0.264682 -0.584821 -0.803674 0.205931 -0.558301 -0.830644 0.0699831 -0.552388 0.851928 0.0655187 -0.519544 0.824488 0.116478 -0.553762 0.807679 0.194493 -0.556621 0.767542 0.263581 -0.584299 0.759938 0.279312 -0.586924 0.0826436 0.704687 -0.704688 0.105553 0.711151 -0.69507 0.213841 0.677409 -0.703838 0.240871 0.673518 -0.698824 0.303108 0.653536 -0.693554 0.354468 0.642363 -0.679501 0.41763 0.594103 -0.687479 0.483019 0.568334 -0.6661 0.515844 0.542109 -0.663342 0.577473 0.49486 -0.649338 0.587189 0.481815 -0.650433 0.692013 0.386545 -0.609673 0.691209 0.388449 -0.609375 0.735297 0.317854 -0.598588 -0.854473 -0.0549884 -0.516577 -0.843885 -0.154737 -0.513726 -0.842218 -0.114669 -0.526802 -0.774725 -0.249614 -0.580942 -0.767045 -0.269495 -0.58225 -0.748078 -0.298552 -0.59266 -0.730612 -0.323932 -0.601062 -0.702162 -0.370426 -0.608073 -0.645184 -0.419377 -0.638639 -0.601894 -0.480815 -0.637605 -0.557828 -0.510144 -0.654661 -0.509677 -0.547046 -0.664056 -0.447317 -0.578826 -0.681812 -0.393706 -0.628648 -0.670669 -0.317074 -0.646991 -0.693445 -0.0890733 -0.704296 -0.704296 -0.0680126 -0.698396 -0.712473 -0.223615 -0.684217 -0.694149 -0.204192 -0.683928 -0.700391 -0.27806 -0.662085 -0.695936 -0.997291 0.0735549 0 -0.994643 0.100591 0.0238111 -0.975598 0.219049 -0.0150271 -0.969401 0.245481 0 -0.933006 0.359861 0 -0.939639 0.341751 -0.0169076 -0.869919 0.492733 0.0213409 -0.87566 0.48285 0.00870505 -0.788379 0.615159 -0.00615521 -0.761002 0.648169 0.0274274 -0.689518 0.724089 -0.016099 -0.678038 0.734974 -0.00882717 -0.649282 0.760548 0 -1 0 0 -1 0 0 -0.994925 -0.100619 0 -0.996762 -0.0735159 0.0325624 -0.969127 -0.245412 -0.0237958 -0.975708 -0.219074 0 -0.939773 -0.3418 0 -0.932933 -0.359833 -0.0124821 -0.875539 -0.482784 0.0187234 -0.870091 -0.492831 0.00763756 -0.761249 -0.64838 -0.0101613 -0.787587 -0.614541 0.0452295 -0.677777 -0.734915 -0.0227558 -0.689554 -0.724127 -0.0124523 -0.649282 -0.760548 0 -0.726455 -0.687214 0 -0.775486 -0.629853 0.0436691 -0.874577 -0.484571 -0.0175177 -0.908774 -0.417289 0 -0.967841 -0.251564 0 -0.973761 -0.227106 0.0145791 -0.999928 -0.00262007 -0.0116764 -0.999746 0.0225475 0 -0.969146 0.246488 0 -0.974938 0.222 -0.0145783 -0.877093 0.480002 0.0174768 -0.889032 0.457845 0 -0.779537 0.626356 0 -0.729938 0.683289 -0.0175251 -0.598405 0.800004 0.0436607 -0.536873 0.843663 0 -0.726455 0.687214 0 -0.726455 0.687214 0 -0.874711 0.484645 0 -0.874711 0.484645 0 -0.967841 0.251564 0 -0.967841 0.251564 0 -0.999997 0.00262025 0 -0.999997 0.00262025 0 -0.969146 -0.246488 0 -0.969146 -0.246488 0 -0.877227 -0.480075 0 -0.877227 -0.480075 0 -0.73005 -0.683394 0 -0.73005 -0.683394 0 -0.536873 -0.843663 0 -0.536873 -0.843663 0 -0.995455 -0.0952292 0 -0.995131 -0.0984262 -0.00517463 -0.975335 -0.220724 0.00145661 -0.974359 -0.224999 -2.71926e-05 -0.948936 -0.315468 5.08605e-05 -0.946388 -0.322956 -0.00700263 -0.883222 -0.468861 0.00941584 -0.884211 -0.466937 0.0118916 -0.831744 -0.555157 -0.00167313 -0.772983 -0.634289 0.0131987 -0.754173 -0.656448 -0.0172654 -0.657266 -0.753594 0.00983142 -0.661422 -0.749899 0.0131307 -0.551595 -0.833786 -0.0233245 -0.537505 -0.842281 -0.0406272 -0.47825 -0.878179 -0.00883036 -0.444111 -0.895971 0 -0.994916 0.100707 0 -0.995515 0.0944463 -0.0054635 -0.974119 0.226029 0.00163789 -0.975219 0.221241 -2.30971e-05 -0.946014 0.324125 6.34023e-05 -0.949152 0.314717 -0.00799434 -0.884167 0.467082 0.00918324 -0.882746 0.469693 0.0121342 -0.831409 0.555658 -0.00175222 -0.772641 0.634708 0.0131219 -0.753814 0.656864 -0.0171567 -0.657266 0.753594 0.00983198 -0.623309 0.781804 -0.016369 -0.551701 0.833944 0.0127503 -0.495309 0.868534 -0.0178389 -0.478242 0.878184 -0.00882712 -0.444117 0.895969 0 -0.996301 0.0859314 0 -0.996301 0.0859314 0 -0.966867 0.255279 0 -0.966867 0.255279 0 -0.908879 0.417061 0 -0.908879 0.417061 0 -0.82404 0.566531 0 -0.530025 0.847982 0 -0.563893 0.825797 0.00918565 -0.584436 0.811177 0.0206474 -0.681723 0.730308 -0.0436491 -0.714853 0.699275 0 -0.82404 0.566531 0 -0.618905 0.785466 0 -0.618905 0.785466 0 -0.798913 0.601447 0 -0.798913 0.601447 0 -0.925972 0.377593 0 -0.925972 0.377593 0 -0.991684 0.128693 0 -0.991684 0.128693 0 -0.991684 -0.128693 0 -0.991684 -0.128693 0 -0.925972 -0.377593 0 -0.925972 -0.377593 0 -0.798913 -0.601447 0 -0.798913 -0.601447 0 -0.618905 -0.785466 0 -0.618905 -0.785466 0 -0.618905 -0.785466 0 -0.618905 -0.785466 0 -0.798913 -0.601447 0 -0.798913 -0.601447 0 -0.925972 -0.377593 0 -0.925972 -0.377593 0 -0.991684 -0.128693 0 -0.991684 -0.128693 0 -0.991684 0.128693 0 -0.991684 0.128693 0 -0.925972 0.377593 0 -0.925972 0.377593 0 -0.798913 0.601447 0 -0.798913 0.601447 0 -0.618905 0.785466 0 -0.618905 0.785466 0 -0.991683 -0.128703 0 -0.992833 -0.118613 0.014638 -0.954975 -0.296626 -0.0060503 -0.957958 -0.28691 0 -0.908879 -0.417061 0 -0.91699 -0.398431 0.0195532 -0.8238 -0.566366 -0.0241397 -0.828321 -0.560055 -0.0149164 -0.744261 -0.667876 0.00428395 -0.67284 -0.739175 -0.030122 -0.618413 -0.784828 0.0401435 -0.563893 -0.825797 0.00918565 -0.530025 -0.847982 0 -0.996961 0.0778995 0 -0.996725 0.0808051 0.00325104 -0.972023 0.234862 -0.00319253 -0.969754 0.244008 0.00606293 -0.921533 0.388258 -0.0058216 -0.915068 0.403213 0.00837019 -0.846356 0.532557 -0.00806959 -0.833885 0.551837 0.0105185 -0.530025 0.847982 0 -0.563893 0.825797 0.00918565 -0.588198 0.808396 0.022772 -0.641454 0.767014 -0.0150483 -0.724462 0.689047 0.0191868 -0.730633 0.68265 0.012836 -0.780992 0.624536 -0.00262729 -0.996629 -0.0820405 0 -0.997012 -0.0771737 0.00344873 -0.96933 -0.245735 -0.00365697 -0.972312 -0.233582 0.00693557 -0.914603 -0.404289 -0.00719937 -0.921732 -0.387688 0.0103918 -0.833605 -0.552258 -0.0106548 -0.846211 -0.532668 0.01384 -0.780993 -0.624535 -0.00262709 -0.718284 -0.695556 0.0164194 -0.675582 -0.736328 -0.0375589 -0.58096 -0.813717 0.0186916 -0.563893 -0.825797 0.00918565 -0.530025 -0.847982 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.607894 0.0524393 -0.792285 -0.151815 0.210717 -0.965687 -0.41412 0.574788 -0.705778 -0.564785 0.783902 -0.257908 -0.564777 0.783897 -0.257939 -0.690662 0.675612 -0.257943 -0.690664 0.675613 -0.257934 -0.796156 0.547361 -0.257935 -0.796153 0.547361 -0.257947 -0.878121 0.402947 -0.257949 -0.878124 0.402947 -0.257938 -0.93415 0.246641 -0.257938 -0.934168 0.246638 -0.257874 -0.962605 0.0830251 -0.257872 -0.962581 0.0830326 -0.257958 -0.414103 0.574771 -0.705802 -0.506406 0.49537 -0.705805 -0.50644 0.495395 -0.705763 -0.583792 0.401361 -0.705759 -0.583748 0.401339 -0.705808 -0.643851 0.295445 -0.705811 -0.643859 0.295448 -0.705802 -0.684939 0.180837 -0.705802 -0.684962 0.180839 -0.705779 -0.705812 0.0608836 -0.705778 -0.792204 0.0545091 -0.607818 -0.151824 0.210728 -0.965683 -0.185667 0.181618 -0.965682 -0.185655 0.181608 -0.965687 -0.214008 0.147135 -0.965687 -0.214025 0.147144 -0.965682 -0.236061 0.108322 -0.965682 -0.236044 0.108316 -0.965687 -0.251105 0.0662952 -0.965687 -0.251106 0.0662954 -0.965687 -0.258749 0.0223207 -0.965687 -0.258775 0.0223201 -0.96568 -0.980787 0 -0.19508 -0.965916 -0.00106399 -0.258852 -0.831462 0.000710718 -0.555581 -0.793383 0 -0.608723 -0.555555 0 -0.83148 -0.608731 0.00106298 -0.793376 -0.195124 -0.00141025 -0.980778 -0.25884 0 -0.96592 -0.598157 0.759122 -0.256791 -0.439474 0.557731 -0.70413 -0.161433 0.204879 -0.965383 -0.161448 0.204892 -0.965378 -0.208407 0.156892 -0.965376 -0.20838 0.156878 -0.965384 -0.24152 0.0984858 -0.965385 -0.24153 0.0984876 -0.965383 -0.258667 0.0335722 -0.965383 -0.258665 0.0335723 -0.965384 -0.258665 -0.0335719 -0.965384 -0.258667 -0.0335727 -0.965383 -0.241529 -0.0984893 -0.965383 -0.241521 -0.0984839 -0.965385 -0.208382 -0.156873 -0.965385 -0.208403 -0.156896 -0.965377 -0.161446 -0.204895 -0.965377 -0.161436 -0.204877 -0.965383 -0.439461 0.557721 -0.704146 -0.567266 0.427066 -0.704148 -0.567297 0.427079 -0.704116 -0.657527 0.268117 -0.70411 -0.657465 0.268108 -0.704172 -0.704121 0.0913884 -0.704174 -0.704148 0.0913852 -0.704148 -0.704148 -0.091392 -0.704148 -0.704122 -0.091382 -0.704174 -0.65747 -0.268094 -0.704173 -0.657522 -0.268132 -0.70411 -0.567294 -0.427087 -0.704113 -0.567271 -0.42706 -0.704147 -0.439464 -0.557718 -0.704146 -0.439471 -0.557733 -0.704131 -0.598145 0.759118 -0.256829 -0.772114 0.581272 -0.256832 -0.772114 0.581272 -0.256833 -0.894907 0.364935 -0.256835 -0.894922 0.364932 -0.256786 -0.958431 0.124386 -0.256785 -0.958445 0.124379 -0.256736 -0.958444 -0.124388 -0.256735 -0.958432 -0.124378 -0.256784 -0.894919 -0.36494 -0.256785 -0.89491 -0.364927 -0.256835 -0.772114 -0.581272 -0.256833 -0.772114 -0.581272 -0.256832 -0.598151 -0.759114 -0.256829 -0.598152 -0.759127 -0.256791 -0.195062 -0.0253171 -0.980464 -0.275549 -0.349704 -0.895422 -0.554116 -0.0719157 -0.829327 -0.492529 -0.625073 -0.605557 -0.826663 -0.107291 -0.552374 -0.972937 -0.12627 -0.193519 -0.755556 -0.568811 0.324945 -0.972956 -0.126278 -0.193418 -0.936695 -0.290948 -0.19481 -0.87573 -0.357094 0.324933 -0.891531 -0.4091 -0.194446 -0.808313 -0.555719 -0.194442 -0.72999 -0.65507 -0.19493 -0.607209 -0.770609 -0.193541 -0.607215 -0.770623 -0.193467 -0.826629 -0.107284 -0.552426 -0.771861 -0.31474 -0.552422 -0.771891 -0.314756 -0.55237 -0.665972 -0.501369 -0.552368 -0.66597 -0.501367 -0.552372 -0.515922 -0.654762 -0.552368 -0.550379 -0.709717 -0.439756 -0.554163 -0.0719247 -0.829295 -0.517442 -0.210999 -0.829297 -0.51744 -0.210998 -0.829298 -0.446432 -0.336091 -0.829302 -0.446402 -0.336065 -0.829328 -0.345823 -0.438887 -0.829328 -0.375874 -0.482611 -0.791078 -0.195041 -0.0253133 -0.980468 -0.182119 -0.074263 -0.980468 -0.182118 -0.0742626 -0.980468 -0.157129 -0.118291 -0.980468 -0.157147 -0.118307 -0.980463 -0.121739 -0.1545 -0.980464 -0.121727 -0.154483 -0.980468 -0.694138 -0.672174 -0.257595 -0.694135 -0.672168 -0.257616 -0.570951 -0.552883 -0.606906 -0.513651 -0.489005 -0.705008 -0.186791 -0.180879 -0.965604 -0.186801 -0.180891 -0.9656 -0.438715 -0.424835 -0.791861 -0.561389 -0.786304 -0.25801 -0.561389 -0.786308 -0.257996 -0.411569 -0.576463 -0.705905 -0.411568 -0.576461 -0.705907 -0.150856 -0.211296 -0.96571 -0.150857 -0.211297 -0.96571 -0.37877 0.480692 -0.790865 -0.555959 0.705569 -0.439411 -0.492531 0.625072 -0.605556 -0.607212 0.770626 -0.193467 -0.448133 0.54987 -0.704855 -0.567266 0.427066 -0.704148 -0.567297 0.427079 -0.704116 -0.657527 0.268117 -0.70411 -0.657465 0.268108 -0.704172 -0.704121 0.0913884 -0.704174 -0.704148 0.0913852 -0.704148 -0.704148 -0.0913918 -0.704148 -0.704123 -0.0913821 -0.704173 -0.657471 -0.268094 -0.704171 -0.657522 -0.268132 -0.70411 -0.567294 -0.427087 -0.704113 -0.567271 -0.42706 -0.704147 -0.121725 -0.154484 -0.980468 -0.167852 -0.198444 -0.965632 -0.208403 -0.156896 -0.965377 -0.208382 -0.156873 -0.965385 -0.241521 -0.098484 -0.965385 -0.241528 -0.098489 -0.965383 -0.258667 -0.0335726 -0.965383 -0.258665 -0.0335719 -0.965384 -0.258665 0.0335723 -0.965384 -0.258667 0.0335722 -0.965383 -0.24153 0.0984876 -0.965383 -0.241521 0.0984858 -0.965385 -0.20838 0.156878 -0.965384 -0.208407 0.156892 -0.965376 -0.161448 0.204892 -0.965378 -0.161433 0.204879 -0.965383 -0.275553 -0.349701 -0.895421 -0.37877 -0.480692 -0.790865 -0.448133 -0.54987 -0.704855 -0.492531 -0.625072 -0.605556 -0.555959 -0.705569 -0.439411 -0.604798 0.753738 -0.257095 -0.772114 0.581272 -0.256832 -0.772114 0.581272 -0.256833 -0.894907 0.364935 -0.256835 -0.894922 0.364932 -0.256786 -0.958431 0.124386 -0.256785 -0.958445 0.124379 -0.256736 -0.958444 -0.124388 -0.256735 -0.958432 -0.124378 -0.256784 -0.894919 -0.36494 -0.256785 -0.89491 -0.364927 -0.256835 -0.772114 -0.581272 -0.256833 -0.772114 -0.581272 -0.256832 -0.604798 -0.753738 -0.257096 -0.607212 -0.770626 -0.193467 -0.185349 -0.192084 -0.963717 -0.17446 -0.256896 -0.950562 -0.187214 -0.258202 -0.947778 -0.531742 -0.249887 -0.809202 -0.54898 -0.249987 -0.797576 -0.819152 -0.203451 -0.536282 -0.835319 -0.200847 -0.511765 -0.972788 -0.128149 -0.193031 -0.979997 -0.122231 -0.157054 -0.171162 -0.15566 -0.972869 -0.250664 -0.195205 -0.948189 -0.513229 -0.242806 -0.82319 -0.532128 -0.247593 -0.809653 -0.794437 -0.274932 -0.541555 -0.806698 -0.277193 -0.521922 -0.945629 -0.264501 -0.189272 -0.94994 -0.264209 -0.166754 -0.158347 -0.120242 -0.980035 -0.179556 -0.131203 -0.974959 -0.490296 -0.259096 -0.832153 -0.504931 -0.266664 -0.820936 -0.755814 -0.361533 -0.54593 -0.762975 -0.365346 -0.533285 -0.895162 -0.404558 -0.18713 -0.896808 -0.405617 -0.176666 -0.21314 -0.147702 -0.965793 -0.165026 -0.108049 -0.980353 -0.502395 -0.34539 -0.792657 -0.461147 -0.311967 -0.830675 -0.660179 -0.441584 -0.607591 -0.695916 -0.469794 -0.543134 -0.80785 -0.53 -0.257835 -0.818795 -0.543796 -0.184013 -0.577143 0.793202 -0.19426 -0.577128 0.793193 -0.194339 -0.528071 0.725769 -0.440908 -0.487153 0.675205 -0.553877 -0.467478 0.642494 -0.607178 -0.327813 0.450541 -0.830393 -0.354963 0.496209 -0.792324 -0.120202 0.154062 -0.980722 -0.152859 0.210086 -0.965659 -0.710781 0.676034 -0.194342 -0.710792 0.676039 -0.194284 -0.603226 0.573732 -0.55403 -0.60323 0.573735 -0.554023 -0.403738 0.383997 -0.830387 -0.403728 0.383989 -0.830395 -0.141928 0.134989 -0.98063 -0.14194 0.134999 -0.980627 -0.157247 -0.872948 -0.461774 -0.455519 -0.434206 -0.777153 -0.988222 -0.108474 -0.107941 -0.988195 -0.102355 -0.113987 -0.988194 -0.102361 -0.113994 -0.988188 -0.0897017 -0.124254 -0.98881 -0.0875051 -0.120823 -0.987453 -0.0767964 -0.137982 -0.988176 -0.0747871 -0.133851 -0.98817 -0.0567723 -0.142467 -0.982231 -0.0676597 -0.175057 -0.982066 -0.141798 -0.124254 -0.921721 -0.296083 -0.250528 -0.988216 -0.122623 -0.0916115 -0.98815 -0.131734 -0.0787749 -0.987625 -0.134652 -0.0804074 -0.988222 -0.137101 -0.0679701 -0.83534 -0.200141 -0.512007 -0.157084 -0.774969 -0.612167 -0.66301 -0.571472 -0.483567 0.439579 -0.624091 -0.645973 -0.153102 -0.660241 -0.735284 -0.153278 -0.605376 -0.781041 -0.364892 -0.546105 -0.754071 0.420323 -0.46992 -0.776211 -0.156985 -0.481701 -0.86216 -0.157193 -0.393621 -0.905733 -0.45556 -0.434198 -0.777134 -0.455672 -0.522114 -0.720944 -0.45573 -0.5221 -0.720917 -0.455804 -0.594678 -0.662269 -0.455825 -0.594672 -0.66226 -0.454828 -0.679848 -0.575272 -0.454973 -0.679794 -0.575221 -0.157071 -0.833894 -0.529103 -0.617014 -0.675652 -0.40347 -0.455121 -0.764495 -0.456523 -0.455121 -0.764495 -0.456522 -0.649538 -0.652795 -0.38982 -0.18731 -0.32975 -0.9253 -0.410725 -0.3383 -0.846675 -0.548023 -0.312005 -0.776095 -0.455248 -0.323594 -0.82948 -0.709352 -0.263007 -0.653947 -0.709361 -0.343789 -0.615318 -0.709423 -0.343763 -0.615261 -0.70953 -0.413328 -0.570725 -0.709584 -0.4133 -0.570678 -0.709653 -0.470724 -0.524225 -0.709653 -0.470724 -0.524225 -0.708681 -0.538587 -0.455736 -0.708816 -0.538487 -0.455644 -0.709004 -0.60488 -0.362537 -0.761037 -0.556961 -0.332591 -0.893312 -0.167817 -0.416931 -0.893314 -0.219214 -0.392346 -0.893332 -0.219198 -0.392313 -0.893388 -0.263532 -0.363881 -0.893425 -0.263493 -0.363819 -0.89346 -0.300081 -0.334187 -0.893466 -0.300073 -0.334177 -0.892967 -0.343617 -0.290754 -0.893028 -0.343527 -0.290672 -0.893102 -0.386231 -0.230639 -0.893118 -0.386204 -0.230622 -0.161901 0.114029 -0.980197 -0.159579 0.112748 -0.980725 -0.461306 0.31187 -0.830623 -0.461167 0.311797 -0.830727 -0.698368 0.465935 -0.543311 -0.691636 0.462919 -0.554387 -0.819463 0.542782 -0.184031 -0.817282 0.542457 -0.194395 -0.180147 0.12952 -0.975075 -0.157567 0.121937 -0.979951 -0.505561 0.265026 -0.821078 -0.489636 0.260454 -0.832118 -0.763539 0.363942 -0.533437 -0.7554 0.362418 -0.545916 -0.897282 0.404518 -0.176776 -0.894969 0.404974 -0.187156 -0.187281 0.18025 -0.965627 -0.163751 0.176964 -0.970499 -0.532536 0.245729 -0.809952 -0.512655 0.244633 -0.823006 -0.807157 0.275154 -0.52229 -0.793947 0.276573 -0.541438 -0.950465 0.262148 -0.167018 -0.945268 0.265865 -0.189168 -0.187213 0.257468 -0.947978 -0.174378 0.258038 -0.950268 -0.548969 0.248414 -0.798074 -0.531559 0.25156 -0.808803 -0.835392 0.198408 -0.512595 -0.818856 0.205707 -0.535873 -0.980205 0.119231 -0.158061 -0.972555 0.130686 -0.192506 -0.189251 -0.976734 -0.100871 -0.983124 -0.170469 -0.0663899 -0.157003 -0.910703 -0.38206 -0.188463 -0.906131 -0.378693 -0.455524 -0.821141 -0.343839 -0.550489 -0.771518 -0.318937 -0.988101 -0.144067 -0.0538533 -0.893246 -0.415721 -0.171135 -0.837522 -0.506144 -0.205851 -0.761306 -0.599123 -0.24792 -0.64989 -0.701854 -0.291623 -0.983766 -0.178578 -0.0177474 -0.982246 -0.186488 -0.0203991 -0.839767 -0.529374 -0.120646 -0.835921 -0.534962 -0.122688 -0.553331 -0.806669 -0.207629 -0.548558 -0.809599 -0.20889 -0.190969 -0.946885 -0.258727 -0.186547 -0.947614 -0.259282 -0.982099 -0.184816 0.0364035 -0.981167 -0.189901 0.0353274 -0.838591 -0.544052 -0.0277801 -0.835341 -0.548965 -0.0290373 -0.553121 -0.828241 -0.0898544 -0.547707 -0.831701 -0.091056 -0.475147 -0.873952 -0.102194 -0.186296 -0.969585 -0.158739 -0.978782 -0.186897 0.0839914 -0.978321 -0.189441 0.0836695 -0.834593 -0.548836 0.0472542 -0.832834 -0.551545 0.0467533 -0.549528 -0.835474 0.00146652 -0.546113 -0.837711 0.000791511 -0.189056 -0.98103 -0.0428636 -0.184477 -0.98187 -0.0435745 -0.982938 0.0733691 -0.168669 -0.982893 0.0898347 -0.160783 -0.991978 0.0650726 -0.108376 -0.973355 0.134501 -0.185714 -0.982952 0.112124 -0.145716 -0.98292 0.122955 -0.13693 -0.993552 0.0792945 -0.0810339 -0.885502 0.354699 -0.300126 -0.953899 0.23192 -0.190501 -0.982951 0.147248 -0.110119 -0.982271 0.0629964 -0.176565 -0.969498 0.0905759 -0.22775 -0.835226 0.203812 -0.510743 -0.548094 0.309792 -0.776931 -0.838554 0.201506 -0.506185 -0.838618 0.265693 -0.475529 -0.83865 0.265665 -0.475488 -0.838726 0.319415 -0.441036 -0.838772 0.319369 -0.440983 -0.838821 0.36373 -0.405069 -0.838822 0.363728 -0.405067 -0.838135 0.416401 -0.352335 -0.838231 0.416284 -0.352244 -0.551236 0.308768 -0.775113 -0.55133 0.406926 -0.728318 -0.55137 0.40691 -0.728296 -0.551488 0.489293 -0.675613 -0.55156 0.48926 -0.675578 -0.551636 0.557268 -0.620604 -0.551665 0.557254 -0.620592 -0.550603 0.637247 -0.539215 -0.550735 0.637177 -0.539163 -0.18836 0.823586 -0.535001 -0.188189 0.764988 -0.615937 -0.579506 0.622129 -0.52643 -0.18847 0.708383 -0.6802 -0.188319 0.656163 -0.730743 0.287973 0.615766 -0.733419 -0.354754 0.548398 -0.757238 0.12804 0.502179 -0.855232 -0.188166 0.479036 -0.85739 -0.188318 0.380342 -0.90547 -0.366301 0.344444 -0.864397 -0.187373 0.318189 -0.929326 -0.18842 0.863193 -0.468398 -0.611308 0.679465 -0.405746 -0.550899 0.716537 -0.427884 -0.550887 0.716544 -0.427888 -0.838346 0.468039 -0.279492 -0.838333 0.468057 -0.279501 -0.982857 0.158294 -0.0945255 -0.982855 0.158303 -0.0945309 -0.834451 -0.551028 -0.00774656 -0.544604 -0.838292 -0.0259591 -0.183793 -0.982429 -0.0324674 -0.143105 -0.98802 -0.0577795 -0.21028 -0.975356 -0.0667992 -0.182105 -0.981183 -0.0641781 -0.184117 -0.982119 -0.0392929 -0.345205 -0.937713 -0.0390858 -0.119724 -0.991593 -0.0490829 -0.183197 -0.981607 -0.0537279 -0.182674 -0.981336 -0.0600848 -0.18653 -0.982415 -0.00814782 -0.176962 -0.984049 -0.0182459 -0.182647 -0.983028 -0.0172264 -0.185966 -0.982438 -0.0152282 -0.544355 -0.837515 0.0473859 -0.259464 -0.96575 -0.00220435 -0.144421 -0.989436 -0.0125947 -0.150197 -0.98859 -0.0114319 -0.166112 -0.986085 -0.00653995 -0.180568 -0.983556 -0.00356565 -0.181717 -0.983308 -0.00922444 -0.827966 -0.551131 0.103573 -0.540229 -0.84023 0.0465478 -0.534598 -0.841634 0.0765295 -0.534946 -0.841405 0.0766204 -0.534048 -0.841599 0.0806521 -0.533863 -0.84172 0.0806024 -0.537359 -0.840968 0.0633972 -0.536897 -0.841271 0.063279 -0.540844 -0.840198 0.0394284 -0.54022 -0.840606 0.0392976 -0.827002 -0.552621 0.10333 -0.818516 -0.554769 0.149209 -0.819056 -0.553926 0.149378 -0.817704 -0.554222 0.155558 -0.81735 -0.554775 0.155445 -0.822698 -0.553624 0.129107 -0.822192 -0.554412 0.128947 -0.828194 -0.552768 0.0924256 -0.827435 -0.553937 0.092221 -0.976399 -0.187908 0.10647 -0.914 -0.386301 0.123998 -0.971433 -0.187715 0.145195 -0.962117 -0.189961 0.195564 -0.962311 -0.188865 0.19567 -0.96074 -0.189195 0.202938 -0.960617 -0.189892 0.20287 -0.966901 -0.188539 0.171918 -0.966662 -0.189893 0.171772 -0.973683 -0.187995 0.128836 -0.984262 -0.162084 0.0704061 -0.976872 -0.188727 0.100519 -0.973342 -0.189886 0.128645 -0.5439 -0.838746 -0.0260201 -0.543566 -0.837015 -0.0627898 -0.542456 -0.837735 -0.0627893 -0.54013 -0.836563 -0.0917763 -0.539666 -0.836864 -0.0917511 -0.538765 -0.836541 -0.099656 -0.538796 -0.836521 -0.0996581 -0.833586 -0.552334 -0.00787196 -0.832904 -0.54968 -0.0642141 -0.831729 -0.551449 -0.0642695 -0.828288 -0.549653 -0.108725 -0.82771 -0.550524 -0.108721 -0.826357 -0.550028 -0.120846 -0.826387 -0.549982 -0.120847 -0.183699 -0.982623 -0.0265994 -0.150692 -0.98809 -0.0311636 -0.543864 -0.839147 0.0066364 -0.543035 -0.839685 0.00651441 -0.832972 -0.551703 0.0421981 -0.832015 -0.553162 0.0420003 -0.979348 -0.189804 0.069654 -0.982248 -0.187263 0.0110283 -0.981846 -0.189369 0.0108632 -0.980909 -0.18638 -0.055495 -0.980338 -0.189319 -0.0556414 -0.976381 -0.187101 -0.108045 -0.976159 -0.188232 -0.108089 -0.974586 -0.187624 -0.122393 -0.974598 -0.187561 -0.122391 -0.186632 0.968254 -0.166291 -0.978344 0.189359 0.0835809 -0.978812 0.186885 0.0836683 -0.832746 0.551692 0.046587 -0.834637 0.548809 0.0467838 -0.546091 0.837726 0.000623649 -0.549597 0.835429 0.000904152 -0.184446 0.98187 -0.0437253 -0.189118 0.980993 -0.0434308 -0.981175 0.189945 0.0348849 -0.98217 0.184611 0.0355178 -0.83533 0.548936 -0.0298855 -0.838576 0.544001 -0.0292113 -0.5477 0.831584 -0.0921573 -0.55319 0.828006 -0.0915773 -0.493063 0.864111 -0.101001 -0.189716 0.975931 -0.107552 -0.982247 0.186447 -0.0206824 -0.98378 0.178392 -0.0187708 -0.835912 0.534794 -0.123475 -0.839763 0.529047 -0.122098 -0.548561 0.809299 -0.210037 -0.553322 0.806239 -0.209316 -0.186554 0.947259 -0.260572 -0.190935 0.946431 -0.260409 -0.982834 0.171835 -0.0671567 -0.983121 0.170394 -0.066624 -0.838537 0.503663 -0.207796 -0.837453 0.505232 -0.208358 -0.5513 0.769934 -0.321357 -0.550426 0.770483 -0.321538 -0.188197 0.905521 -0.380281 -0.188436 0.905475 -0.380272 -0.184536 -0.981913 -0.04235 -0.541125 -0.8373 -0.0781901 -0.828316 -0.550702 -0.103053 -0.975875 -0.188058 -0.110915 -0.182432 -0.982312 -0.0422118 -0.189792 -0.98143 0.0278135 -0.531842 -0.846752 0.0125106 -0.185115 -0.97841 0.091902 -0.193918 -0.962168 0.191384 -0.183534 -0.964034 0.192236 -0.193643 -0.926089 0.323824 -0.185675 -0.927473 0.324528 -0.190946 -0.892564 0.408496 -0.526815 -0.765884 0.36863 -0.188043 -0.865187 0.464857 -0.191241 -0.813923 0.548595 -0.332043 -0.787389 0.51939 -0.187203 -0.621799 0.760474 -0.549629 -0.547581 0.630923 -0.18778 -0.674682 0.713823 -0.187122 -0.738337 0.647954 -0.18947 -0.737953 0.647708 -0.188653 -0.781676 0.594468 -0.542615 -0.836328 -0.0782566 -0.551331 -0.83423 0.00965541 -0.544303 -0.838825 0.0103379 -0.55522 -0.82141 0.130449 -0.548178 -0.825935 0.131652 -0.557332 -0.791695 0.2502 -0.551059 -0.7956 0.251704 -0.557447 -0.748887 0.358358 -0.552062 -0.752096 0.359971 -0.555994 -0.694803 0.456201 -0.551132 -0.69754 0.45792 -0.553057 -0.628671 0.546718 -0.548983 -0.630798 0.548371 -0.549335 -0.547707 0.631069 -0.547929 -0.548363 0.631722 -0.829004 -0.549667 -0.103053 -0.835215 -0.548448 -0.0402529 -0.832415 -0.552716 -0.0398692 -0.840175 -0.540387 0.0456879 -0.836759 -0.545566 0.0468198 -0.843349 -0.520848 0.132211 -0.839732 -0.526184 0.134092 -0.844381 -0.492161 0.211656 -0.840407 -0.497751 0.214381 -0.843283 -0.456001 0.284493 -0.838974 -0.461664 0.288078 -0.840385 -0.412011 0.352138 -0.83632 -0.416881 0.356059 -0.836625 -0.359436 0.413357 -0.835109 -0.361034 0.415028 -0.97594 -0.18773 -0.110902 -0.978873 -0.187263 -0.0821 -0.978428 -0.189628 -0.0819702 -0.981961 -0.184075 -0.0432246 -0.981254 -0.18798 -0.0424842 -0.984308 -0.176439 -0.002668 -0.983255 -0.182235 -0.000749672 -0.985467 -0.165922 0.0363968 -0.984079 -0.173204 0.039854 -0.985466 -0.153087 0.0736276 -0.98377 -0.161227 0.0787596 -0.984446 -0.137918 0.108834 -0.982639 -0.145549 0.11505 -0.982808 -0.121718 0.138829 -0.982178 -0.12399 0.141252 -0.185853 0.982474 -0.0142469 -0.182664 0.983065 -0.0147165 -0.181309 0.983397 -0.00757946 -0.219647 0.975571 0.00403197 -0.151911 0.988345 -0.00987057 -0.153568 0.988093 -0.00945535 -0.298872 0.954202 0.0131836 -0.322897 0.946258 0.0182654 -0.149558 0.988496 -0.0225445 -0.428579 0.903504 0.000926089 -0.183622 0.982573 -0.0288786 -0.183969 0.982254 -0.0364999 -0.152426 0.987486 -0.0404691 -0.183864 0.982077 -0.0414713 -0.183793 0.981712 -0.049617 -0.118791 0.991702 -0.0491562 -0.183012 0.981504 -0.05618 -0.182565 0.981265 -0.0615605 -0.209637 0.975649 -0.0645021 -0.182102 0.981182 -0.0641965 -0.181132 0.981369 -0.0640733 -0.53882 0.836504 -0.0996643 -0.826375 0.549999 -0.120852 -0.538788 0.836526 -0.0996608 -0.539677 0.836846 -0.091859 -0.540064 0.836592 -0.0918953 -0.542374 0.83775 -0.063283 -0.543484 0.837027 -0.0633278 -0.543871 0.83873 -0.0271415 -0.544612 0.838249 -0.0271367 -0.543152 0.839621 0.00485167 -0.543998 0.839072 0.004907 -0.540431 0.840537 0.0378311 -0.541089 0.84011 0.0379144 -0.537095 0.841212 0.0623822 -0.537477 0.840963 0.0624483 -0.53386 0.841746 0.0803608 -0.534094 0.841592 0.080414 -0.534899 0.841418 0.0768036 -0.534599 0.841615 0.0767375 -0.540238 0.840211 0.0467836 -0.544359 0.837509 0.0474574 -0.826355 0.550029 -0.120851 -0.827692 0.55052 -0.108879 -0.82826 0.549657 -0.108917 -0.831682 0.551432 -0.065027 -0.832837 0.549683 -0.065042 -0.833594 0.552295 -0.00958264 -0.834414 0.551055 -0.00956316 -0.832143 0.553155 0.0394512 -0.833163 0.551612 0.0395355 -0.827736 0.553856 0.0899784 -0.82852 0.552664 0.0900914 -0.822447 0.554352 0.127572 -0.823011 0.55349 0.12768 -0.817472 0.55469 0.155112 -0.81778 0.554213 0.155191 -0.818992 0.553947 0.149652 -0.818497 0.554711 0.149529 -0.827012 0.552556 0.103596 -0.827938 0.551136 0.103773 -0.97463 0.187574 -0.122116 -0.972397 0.198515 -0.122618 -0.974507 0.187764 -0.122806 -0.976108 0.188383 -0.108282 -0.976356 0.187101 -0.108272 -0.980292 0.189292 -0.0565301 -0.980858 0.186353 -0.056475 -0.98188 0.189296 0.0088565 -0.982259 0.187317 0.00888829 -0.979559 0.189817 0.0665845 -0.980017 0.187415 0.06665 -0.973661 0.190025 0.125997 -0.974049 0.187971 0.126077 -0.966943 0.189919 0.170152 -0.967194 0.18858 0.170215 -0.960686 0.189988 0.202455 -0.960834 0.189175 0.20251 -0.962242 0.18888 0.195996 -0.962011 0.190139 0.195912 -0.971924 0.187712 0.14187 -0.971628 0.189311 0.141779 -0.187065 -0.539601 0.820876 -0.547864 -0.447561 0.706777 -0.450719 -0.482863 0.750797 -0.672795 -0.397254 0.624129 -0.835171 -0.296326 0.463336 -0.845095 -0.287443 0.450767 -0.982192 -0.100796 0.158554 -0.97806 -0.11254 0.175311 -0.999877 -0.00842717 0.0132316 -0.447147 -0.479592 0.755017 -0.138396 -0.479062 0.866802 -0.137887 -0.390799 0.91009 -0.999861 -0.00657482 0.0153104 -0.999877 -0.00619023 0.0144238 -0.978042 -0.0821919 0.191514 -0.978048 -0.08218 0.191489 -0.844943 -0.210936 0.491505 -0.844972 -0.210916 0.491464 -0.672496 -0.291877 0.680115 -0.672583 -0.291844 0.680044 -0.48844 -0.344128 0.801874 -0.450689 -0.353224 0.819825 -0.326698 -0.37273 0.868528 -0.144463 -0.390233 0.909312 -0.184526 0.981911 -0.0424402 -0.186893 0.643668 0.742134 -0.547926 0.548427 0.631669 -0.835106 0.36103 0.415037 -0.98218 0.123915 0.141308 -0.18758 0.643603 0.742017 -0.18714 0.738798 0.647423 -0.189497 0.738534 0.647038 -0.188163 0.796905 0.574054 -0.533809 0.70693 0.464003 -0.190501 0.83091 0.522779 -0.186983 0.877125 0.442367 -0.192612 0.87637 0.441448 -0.185661 0.92749 0.324487 -0.193631 0.926313 0.323188 -0.186852 0.954907 0.230735 -0.563031 0.816398 0.128413 -0.191441 0.968167 0.161253 -0.18316 0.980426 0.0722305 -0.453053 0.891174 0.0234759 -0.187989 0.982122 0.00980913 -0.182439 0.982314 -0.0421396 -0.549342 0.547872 0.630919 -0.548983 0.63113 0.54799 -0.553114 0.629242 0.546004 -0.551193 0.697888 0.457318 -0.556005 0.695442 0.455214 -0.552096 0.752175 0.359754 -0.557498 0.749192 0.357642 -0.551138 0.795556 0.25167 -0.557308 0.791903 0.249595 -0.548203 0.825911 0.131699 -0.555198 0.821526 0.129808 -0.544359 0.838786 0.010582 -0.551298 0.834258 0.0092053 -0.542606 0.836326 -0.0783376 -0.541157 0.837285 -0.0781272 -0.836563 0.35966 0.413289 -0.836256 0.417082 0.355976 -0.840402 0.412523 0.351497 -0.839002 0.461812 0.287759 -0.843223 0.456609 0.283698 -0.840372 0.497822 0.214356 -0.84431 0.492527 0.211087 -0.839686 0.526239 0.134165 -0.843337 0.520995 0.131709 -0.836788 0.545518 0.0468571 -0.840146 0.540472 0.0452208 -0.832437 0.552694 -0.0397294 -0.835195 0.548458 -0.0405383 -0.828997 0.549665 -0.10311 -0.82831 0.55072 -0.103006 -0.982838 0.121742 0.138595 -0.982672 0.145323 0.115051 -0.984476 0.138171 0.108235 -0.98381 0.161019 0.078685 -0.985484 0.1533 0.072937 -0.984122 0.172954 0.0398811 -0.985477 0.165978 0.0358689 -0.983294 0.182023 -0.000697818 -0.984292 0.176521 -0.00301167 -0.981265 0.187929 -0.0424357 -0.981945 0.184103 -0.0434752 -0.978438 0.189604 -0.0819116 -0.978862 0.187264 -0.0822255 -0.975938 0.187728 -0.110917 -0.975876 0.188058 -0.110904 -0.740327 -0.645897 0.186368 -0.597466 -0.524213 0.606824 -0.457598 -0.404182 0.791986 -0.19543 -0.171531 0.9656 -0.951607 -0.252418 0.175301 -0.943859 -0.264568 -0.197823 -0.740884 -0.646115 0.183373 -0.814795 -0.548984 0.186349 -0.869045 -0.476785 -0.13205 -0.866242 -0.467379 0.176585 -0.92159 -0.339637 0.187933 -0.416419 -0.37222 0.829486 -0.46545 -0.303117 0.831551 -0.483811 -0.310837 0.818112 -0.500577 -0.272235 0.821773 -0.525001 -0.275479 0.805286 -0.96933 -0.149911 0.194748 -0.996416 -0.0839542 -0.0103051 -0.97501 -0.141526 0.171246 -0.814381 -0.223035 0.535761 -0.794477 -0.319276 0.516594 -0.778249 -0.319607 0.540537 -0.72895 -0.433057 0.530183 -0.719673 -0.430009 0.545126 -0.62996 -0.556297 0.541927 -0.678124 -0.593479 0.433509 -0.844954 -0.21067 0.4916 -0.673746 -0.250214 0.695313 -0.527792 -0.261845 0.808006 -0.489818 -0.265936 0.830275 -0.327671 -0.269928 0.905412 -0.147273 -0.134668 0.979885 -0.147904 -0.133773 0.979913 -0.174015 -0.145938 0.973869 -0.156896 -0.185613 0.970016 -0.186184 -0.191881 0.963596 -0.171504 -0.264006 0.949151 -0.144824 -0.263812 0.95364 -0.169081 0.403987 0.899003 -0.18732 0.566343 0.8026 -0.982194 0.100923 0.15846 -0.169259 0.506274 0.8456 -0.527164 0.456168 0.716944 -0.502679 0.46414 0.729307 -0.547994 0.450731 0.704659 -0.760617 0.34794 0.548087 -0.835211 0.297411 0.462568 -0.933111 0.191754 0.304195 -0.995537 0.0540105 0.0773938 -0.995569 0.0371057 0.0864059 -0.174824 0.324646 0.929538 -0.467635 0.348592 0.812282 -0.502429 0.34098 0.794543 -0.50246 0.340974 0.794525 -0.760359 0.256146 0.596861 -0.760402 0.256128 0.596815 -0.895169 0.175783 0.4096 -0.93305 0.143483 0.329895 -0.959816 0.110676 0.257885 -0.995474 0.0374792 0.0873302 -0.381913 -0.598469 0.704257 -0.519901 -0.814695 0.256857 -0.140285 -0.219832 0.965398 -0.519895 -0.814689 0.256886 -0.638952 -0.724423 0.258749 -0.666772 -0.721334 0.187328 -0.595564 -0.675224 0.435174 -0.467826 -0.5304 0.706976 -0.381923 -0.59848 0.704242 -0.140295 -0.219846 0.965394 -0.554385 -0.56763 0.608649 -0.40277 -0.456645 0.793254 -0.171263 -0.194171 0.965902 -0.171266 -0.194173 0.965901 -0.81447 0.549451 0.186393 -0.183633 0.204126 0.961567 -0.921454 0.339951 0.188031 -0.991304 0.116735 0.0607445 -0.96969 0.14652 0.195535 -0.814786 0.219742 0.536504 -0.894224 0.195991 0.402432 -0.957364 0.159036 0.241168 -0.171065 0.264788 0.949012 -0.174667 0.265162 0.948251 -0.527059 0.264394 0.807654 -0.503823 0.264134 0.822433 -0.761104 0.235885 0.604218 -0.164799 0.1673 0.972035 -0.254803 0.211685 0.943539 -0.501102 0.270614 0.821988 -0.524364 0.277352 0.805058 -0.778707 0.318512 0.540523 -0.793654 0.321613 0.51641 -0.945286 0.268105 -0.185886 -0.951396 0.253065 0.175512 -0.148773 0.132239 0.979989 -0.173336 0.147442 0.973764 -0.466141 0.302094 0.831536 -0.482926 0.312405 0.818038 -0.719937 0.429525 0.545159 -0.728178 0.434614 0.529969 -0.867949 0.476832 -0.138909 -0.866087 0.467611 0.176729 -0.144282 0.132147 0.980673 -0.146973 0.134788 0.979914 -0.417155 0.369595 0.83029 -0.417799 0.370243 0.829677 -0.626029 0.549165 0.553629 -0.631162 0.554676 0.542189 -0.739254 0.644849 0.194094 -0.740406 0.646643 0.183445 -0.518855 -0.815349 0.256896 -0.381117 -0.598908 0.704314 -0.139994 -0.219991 0.965404 -0.139988 -0.219984 0.965407 -0.190361 -0.178194 0.965407 -0.190359 -0.178194 0.965407 -0.228737 -0.125178 0.965407 -0.228734 -0.125177 0.965407 -0.2527 -0.0642706 0.965408 -0.2527 -0.0642706 0.965408 -0.260745 0.000683423 0.965408 -0.260758 0.000686139 0.965404 -0.252373 0.0656 0.965404 -0.252355 0.0655912 0.965409 -0.228072 0.126366 0.965409 -0.228083 0.126375 0.965405 -0.189428 0.17919 0.965406 -0.189428 0.17919 0.965406 -0.381128 -0.598919 0.7043 -0.518265 -0.485142 0.7043 -0.51824 -0.485129 0.704328 -0.622718 -0.340789 0.704334 -0.622768 -0.340801 0.704283 -0.688018 -0.174987 0.704281 -0.688014 -0.174987 0.704284 -0.709917 0.00186802 0.704283 -0.709857 0.00185234 0.704343 -0.687032 0.178571 0.704343 -0.687045 0.178578 0.704329 -0.620934 0.344044 0.704326 -0.620931 0.344042 0.704329 -0.515702 0.48783 0.704325 -0.515719 0.487858 0.704293 -0.518856 -0.815349 0.256893 -0.705544 -0.660466 0.256889 -0.70556 -0.660468 0.256841 -0.847812 -0.463954 0.25683 -0.847776 -0.463958 0.256941 -0.936607 -0.238214 0.256945 -0.93661 -0.238213 0.256937 -0.966424 0.00252184 0.256939 -0.966439 0.00253232 0.256882 -0.935363 0.243121 0.256883 -0.935364 0.243123 0.256876 -0.845355 0.468389 0.256879 -0.845349 0.468377 0.256919 -0.702073 0.664144 0.256917 -0.702074 0.664151 0.256896 -0.611485 0.766972 0.194526 -0.611487 0.766983 0.194474 -0.51881 0.650739 0.554414 -0.518795 0.650712 0.55446 -0.347066 0.435316 0.83069 -0.347063 0.435312 0.830693 -0.121957 0.152967 0.980677 -0.121964 0.152977 0.980675 -0.485929 0.852085 0.194484 -0.485928 0.852075 0.19453 -0.412272 0.72292 0.554454 -0.412277 0.722934 0.554431 -0.275799 0.483617 0.830692 -0.275798 0.483614 0.830694 -0.0969204 0.169951 0.980675 -0.096924 0.169959 0.980673 -0.258793 0.019088 0.965744 -0.706133 0.0520871 0.706161 -0.963477 0.071061 0.258191 -0.963496 0.0710712 0.258118 -0.942645 0.21165 0.258119 -0.942634 0.211642 0.258165 -0.901378 0.347662 0.258165 -0.901378 0.347662 0.258164 -0.840621 0.476139 0.258163 -0.840621 0.476139 0.258162 -0.761669 0.594317 0.258162 -0.761676 0.594331 0.25811 -0.66624 0.699644 0.258116 -0.666236 0.699633 0.258153 -0.706107 0.0520808 0.706188 -0.690827 0.155106 0.706187 -0.690884 0.155129 0.706126 -0.660647 0.254812 0.706127 -0.660644 0.25481 0.706132 -0.616111 0.348974 0.706133 -0.616102 0.348966 0.706145 -0.558233 0.435585 0.706146 -0.558208 0.435558 0.706182 -0.488268 0.512744 0.706179 -0.488286 0.512771 0.706146 -0.258799 0.0190892 0.965743 -0.253197 0.0568522 0.965743 -0.253161 0.0568394 0.965753 -0.242082 0.0933707 0.965753 -0.242079 0.0933694 0.965753 -0.225763 0.127874 0.965753 -0.225779 0.127886 0.965748 -0.204574 0.159625 0.965748 -0.204573 0.159623 0.965749 -0.178938 0.187911 0.965749 -0.178942 0.187915 0.965747 -0.872312 0.449235 0.193026 -0.980702 0.022118 0.194254 -0.154435 -0.125431 0.980009 -0.154433 -0.12543 0.980009 -0.348985 -0.283445 0.893235 -0.439336 -0.351902 0.826528 -0.651539 -0.524452 0.548131 -0.620474 -0.503942 0.600878 -0.478578 -0.388696 0.787324 -0.191236 -0.0548794 0.980009 -0.191245 -0.0548811 0.980007 -0.541561 -0.15541 0.826172 -0.541527 -0.155404 0.826195 -0.804151 -0.230771 0.547801 -0.804234 -0.230781 0.547675 -0.761897 -0.618817 0.191256 -0.761896 -0.618817 0.19126 -0.698897 -0.567648 0.435107 -0.943436 -0.270726 0.191404 -0.759516 -0.177138 0.625905 -0.891363 -0.409295 0.194808 -0.197457 0.0244565 0.980007 -0.197409 0.0244461 0.980016 -0.55911 0.0692373 0.826198 -0.559211 0.0692607 0.826127 -0.830351 0.102843 0.547669 -0.830297 0.102827 0.547754 -0.77219 0.095631 0.628154 -0.956475 0.217796 0.19422 -0.764596 0.614352 0.194846 -0.723942 0.42018 0.547135 -0.723582 0.419971 0.547772 -0.723591 0.419978 0.547754 -0.487295 0.282831 0.826166 -0.487337 0.282861 0.826131 -0.172062 0.0998685 0.980011 -0.172041 0.0998537 0.980016 -0.119164 0.159308 0.980011 -0.11917 0.159318 0.980008 -0.337479 0.451174 0.826166 -0.337474 0.451166 0.826172 -0.501123 0.669946 0.547766 -0.501127 0.669955 0.547751 -0.587915 0.78598 0.191289 -0.587914 0.785979 0.191296 -0.965919 0 0.258845 -0.965919 0 0.258845 -0.707092 0 0.707121 -0.707092 0 0.707121 -0.25884 0 0.96592 -0.25884 0 0.96592 -0.676431 -0.710346 0.19455 -0.547679 -0.575134 0.607675 -0.618807 -0.649827 0.441365 -0.30568 -0.321009 0.896389 -0.420503 -0.441589 0.792576 -0.134885 -0.14165 0.980684 -0.662057 -0.703644 0.258006 -0.76168 -0.594326 0.25811 -0.761666 -0.594322 0.25816 -0.840622 -0.476139 0.25816 -0.84062 -0.476139 0.258165 -0.901378 -0.347662 0.258165 -0.901378 -0.347662 0.258165 -0.942632 -0.211648 0.258165 -0.942646 -0.211645 0.258119 -0.963496 -0.0710624 0.258118 -0.963476 -0.0710698 0.25819 -0.48288 -0.518235 0.705874 -0.558204 -0.435563 0.706182 -0.558235 -0.43558 0.706147 -0.6161 -0.348968 0.706146 -0.616112 -0.348972 0.706133 -0.660643 -0.25481 0.706132 -0.660648 -0.254811 0.706127 -0.690887 -0.15512 0.706125 -0.690825 -0.155116 0.706186 -0.706106 -0.0520852 0.706188 -0.706133 -0.0520828 0.706161 -0.175077 -0.192124 0.965627 -0.204572 -0.159624 0.965749 -0.204575 -0.159625 0.965748 -0.22578 -0.127884 0.965748 -0.225762 -0.127877 0.965753 -0.242079 -0.0933697 0.965754 -0.242082 -0.0933704 0.965753 -0.25316 -0.0568438 0.965753 -0.253198 -0.0568477 0.965743 -0.258799 -0.0190884 0.965743 -0.258792 -0.0190887 0.965744 -0.0872188 -0.177283 0.980288 -0.530375 -0.83047 0.170358 -0.523753 -0.840797 0.136903 -0.551391 -0.811128 0.195036 -0.16176 -0.248699 0.954978 -0.268154 -0.440636 0.856699 -0.283402 -0.479501 0.830519 -0.362506 -0.559912 0.745042 -0.442178 -0.704663 0.554913 -0.435699 -0.700985 0.564612 -0.499295 -0.768352 0.400424 -0.939605 -0.281414 0.194804 -0.195035 -0.0233 0.98052 -0.195029 -0.0233 0.980521 -0.554348 -0.0662275 0.829646 -0.554335 -0.0662277 0.829655 -0.827384 -0.0988496 0.552869 -0.827394 -0.0988487 0.552854 -0.974123 -0.116378 0.193751 -0.974125 -0.116378 0.193743 -0.184051 -0.0685885 0.980521 -0.184053 -0.0685891 0.98052 -0.523133 -0.19495 0.829654 -0.523138 -0.194951 0.829651 -0.780822 -0.29098 0.552854 -0.780835 -0.290982 0.552834 -0.935484 -0.348612 -0.0577955 -0.899612 -0.39088 0.194706 -0.162715 -0.110017 0.98052 -0.16271 -0.110014 0.980521 -0.462489 -0.312706 0.82965 -0.4625 -0.312711 0.829642 -0.690308 -0.46674 0.552837 -0.690292 -0.466733 0.552863 -0.812708 -0.549503 0.193783 -0.812716 -0.549504 0.193749 -0.132214 -0.145249 0.980521 -0.132214 -0.145249 0.980521 -0.375815 -0.412865 0.829642 -0.375817 -0.412867 0.82964 -0.560915 -0.616214 0.552861 -0.560911 -0.616211 0.552867 -0.66039 -0.725497 0.193752 -0.660389 -0.725496 0.193757 -0.51215 0.649969 0.561464 -0.567816 0.720615 0.397868 -0.321196 0.407632 0.854792 -0.414584 0.526151 0.742486 -0.184893 0.234653 0.954333 -0.480889 0.577764 0.659496 -0.601358 0.452727 0.658337 -0.601367 0.452745 0.658316 -0.697021 0.284222 0.658316 -0.697028 0.284229 0.658306 -0.746492 0.0968821 0.658304 -0.746488 0.0968793 0.658309 -0.746487 -0.0968816 0.658309 -0.746492 -0.09688 0.658304 -0.697029 -0.284225 0.658306 -0.697019 -0.284226 0.658316 -0.601371 -0.452737 0.658317 -0.601352 -0.452734 0.658337 -0.609998 -0.774161 0.169051 -0.613701 -0.753076 0.237168 -0.776202 -0.584357 0.236723 -0.776209 -0.584355 0.236704 -0.899662 -0.366852 0.236701 -0.89965 -0.36686 0.236738 -0.963492 -0.125045 0.23674 -0.963502 -0.125036 0.236708 -0.9635 0.125046 0.236708 -0.963494 0.125035 0.23674 -0.899654 0.366848 0.236738 -0.899658 0.366863 0.236702 -0.776206 0.58436 0.236704 -0.776206 0.584352 0.236723 -0.613701 0.753076 0.237167 -0.609998 0.774161 0.169051 -0.567816 -0.720615 0.397868 -0.51215 -0.649969 0.561464 -0.480889 -0.577764 0.659496 -0.414584 -0.526151 0.742486 -0.321196 -0.407632 0.854792 -0.235268 0.271393 0.933271 -0.288189 0.216966 0.93267 -0.288174 0.216942 0.93268 -0.334002 0.136197 0.93268 -0.334002 0.136197 0.93268 -0.357703 0.0464228 0.932681 -0.357709 0.0464257 0.932678 -0.357709 -0.0464236 0.932679 -0.357703 -0.046425 0.932681 -0.334002 -0.136197 0.93268 -0.334002 -0.136197 0.93268 -0.288169 -0.216951 0.932679 -0.288196 -0.216959 0.932669 -0.235268 -0.271393 0.933271 -0.184893 -0.234653 0.954333 -0.965932 0 0.258795 -0.980784 -0.00282075 0.195076 -0.793316 0.00212774 0.608807 -0.831456 0 0.55559 -0.608786 0 0.793334 -0.555567 0.0014235 0.83147 -0.258811 -0.0021263 0.965926 -0.195088 0 0.980786 -0.551391 0.811128 0.195036 -0.133007 0.265807 0.954807 -0.112006 0.159728 0.980786 -0.268153 0.440637 0.856699 -0.322962 0.583567 0.745081 -0.307602 0.462901 0.831327 -0.439083 0.698901 0.564575 -0.44017 0.705972 0.554846 -0.499295 0.768352 0.400424 -0.531475 0.833203 0.152667 -0.520678 0.836574 0.170406 -0.616408 0.660341 0.428941 -0.419004 0.448865 0.789275 -0.129722 0.138967 0.981764 -0.279768 0.336058 0.89933 -0.530244 0.594475 0.604517 -0.663075 0.725951 0.182554 -0.178038 0.190726 0.965363 -0.214007 0.147133 0.965688 -0.214004 0.14713 0.965689 -0.236038 0.108311 0.965689 -0.236044 0.108316 0.965687 -0.251106 0.0662951 0.965687 -0.251107 0.0662955 0.965686 -0.25875 0.0223186 0.965686 -0.258747 0.0223177 0.965687 -0.607949 0.0524374 0.792243 -0.484598 0.519137 0.704032 -0.583766 0.401345 0.70579 -0.583764 0.401343 0.705792 -0.643866 0.295456 0.705792 -0.643853 0.295445 0.705808 -0.684933 0.180831 0.705809 -0.684954 0.180844 0.705785 -0.707518 0.0471443 0.705121 -0.791467 0.0682605 0.607388 -0.6595 0.706502 0.256739 -0.796156 0.547364 0.257932 -0.796155 0.54736 0.257944 -0.878123 0.402945 0.257946 -0.878124 0.402948 0.257934 -0.934152 0.246638 0.257935 -0.934154 0.246642 0.257922 -0.962592 0.0830193 0.257922 -0.962597 0.0830244 0.257901 -0.716684 0.669617 0.194877 -0.125505 0.150073 0.980677 -0.125501 0.150066 0.980678 -0.357148 0.427053 0.830705 -0.357155 0.427066 0.830696 -0.533889 0.638395 0.55445 -0.533887 0.63839 0.554457 -0.629273 0.752446 0.194527 -0.629273 0.752447 0.194522 -0.766005 0.612552 0.19498 -0.748203 0.656813 0.0937488 -0.625428 0.549034 0.554439 -0.62542 0.54902 0.554461 -0.418393 0.367283 0.830693 -0.418392 0.367282 0.830694 -0.147019 0.129059 0.980678 -0.147018 0.129058 0.980678 -0.133007 0.265807 0.954807 -0.487874 0.758763 0.431576 -0.555487 0.810954 0.183815 -0.55178 0.811634 0.191803 -0.512492 0.824895 0.238537 -0.434008 0.666224 0.606451 -0.439748 0.698489 0.564566 -0.334499 0.511348 0.791602 -0.348301 0.568599 0.745239 -0.276004 0.435901 0.856629 -0.229438 0.372013 0.899424 -0.110578 0.152692 0.982068 -0.181572 -0.140303 0.973317 -0.831796 0.52168 0.189647 -0.831451 0.520478 0.194403 -0.707065 0.441735 0.552204 -0.706183 0.440685 0.554168 -0.463323 0.284144 0.839401 -0.473264 0.293867 0.83046 -0.154869 0.0869983 0.984097 -0.169015 0.0996903 0.980559 -0.907894 0.369864 0.197304 -0.908937 0.373126 0.186038 -0.773912 0.291882 0.562019 -0.780876 0.298977 0.548494 -0.505506 0.161819 0.847513 -0.520533 0.173253 0.83608 -0.165035 0.0100197 0.986237 -0.18722 0.0245772 0.982011 -0.958897 0.196458 0.204744 -0.961766 0.205639 0.180881 -0.818582 0.105553 0.564608 -0.830762 0.116984 0.544196 -0.536044 -0.00675914 0.844163 -0.556214 0.00555944 0.831021 -0.0971231 -0.135818 0.985962 -0.189291 -0.0633696 0.979874 -0.978946 0.0118004 0.203778 -0.985324 0.0306967 0.167914 -0.831873 -0.100578 0.545777 -0.848612 -0.0856274 0.52204 -0.546456 -0.200988 0.813013 -0.564888 -0.19188 0.802548 -0.186761 -0.267119 0.945393 -0.200499 -0.262993 0.943735 -0.51215 0.649969 0.561464 -0.321196 0.407632 0.854792 -0.414584 0.526151 0.742486 -0.184893 0.234653 0.954333 -0.601315 -0.763141 0.236721 -0.776202 -0.584357 0.236723 -0.776209 -0.584355 0.236704 -0.899662 -0.366852 0.236701 -0.89965 -0.36686 0.236738 -0.963492 -0.125045 0.23674 -0.963502 -0.125036 0.236708 -0.9635 0.125046 0.236708 -0.963494 0.125035 0.23674 -0.899654 0.366848 0.236738 -0.899658 0.366863 0.236702 -0.776206 0.58436 0.236704 -0.776206 0.584352 0.236723 -0.601321 0.763136 0.236721 -0.601318 0.763145 0.236697 -0.480889 0.577764 0.659496 -0.601358 0.452727 0.658337 -0.601367 0.452745 0.658316 -0.697021 0.284222 0.658316 -0.697028 0.284229 0.658306 -0.746492 0.0968821 0.658304 -0.746488 0.0968793 0.658309 -0.746487 -0.0968816 0.658309 -0.746492 -0.09688 0.658304 -0.697029 -0.284225 0.658306 -0.697019 -0.284226 0.658316 -0.601371 -0.452737 0.658317 -0.601352 -0.452734 0.658337 -0.601325 -0.76314 0.236697 -0.51215 -0.649969 0.561464 -0.480889 -0.577764 0.659496 -0.414584 -0.526151 0.742486 -0.321196 -0.407632 0.854792 -0.235268 0.271393 0.933271 -0.288189 0.216966 0.93267 -0.288174 0.216942 0.93268 -0.334002 0.136197 0.93268 -0.334002 0.136197 0.93268 -0.357703 0.0464228 0.932681 -0.357709 0.0464257 0.932678 -0.357709 -0.0464236 0.932679 -0.357703 -0.046425 0.932681 -0.334002 -0.136197 0.93268 -0.334002 -0.136197 0.93268 -0.288169 -0.216951 0.932679 -0.288196 -0.216959 0.932669 -0.235268 -0.271393 0.933271 -0.184893 -0.234653 0.954333 -0.761249 -0.546568 0.348946 -0.454589 -0.565901 0.687826 -0.988205 -0.0873174 0.1258 -0.988058 -0.070934 0.13678 -0.981978 -0.0891964 0.166624 -0.991753 -0.082812 0.0978196 -0.988114 -0.0976539 0.118718 -0.9882 -0.110289 0.106287 -0.992301 -0.0936172 0.0810888 -0.988179 -0.118331 0.0974714 -0.988184 -0.127136 0.0856141 -0.992124 -0.105577 0.0674042 -0.988201 -0.132697 0.0764837 -0.833698 -0.258417 0.488025 -0.156826 -0.477598 0.864469 -0.157212 -0.591112 0.79112 0.153007 -0.627862 0.763137 -0.157143 -0.662042 0.732808 -0.156853 -0.744081 0.649415 -0.109085 -0.751392 0.650777 -0.204339 -0.82316 0.529768 -0.156911 -0.832434 0.531444 -0.454825 -0.565809 0.687746 -0.455147 -0.673068 0.582941 -0.455276 -0.673012 0.582906 -0.455397 -0.750402 0.479073 -0.455416 -0.750393 0.479069 -0.187307 -0.369316 0.910232 0.0553289 -0.464882 0.883642 -0.546404 -0.382704 0.74497 -0.454342 -0.417674 0.786843 -0.707643 -0.322771 0.628539 -0.708414 -0.448411 0.545048 -0.70866 -0.448234 0.544873 -0.708975 -0.533082 0.461711 -0.709069 -0.533005 0.461656 -0.709191 -0.59424 0.379377 -0.650009 -0.643691 0.403919 -0.892461 -0.205953 0.401369 -0.892865 -0.28609 0.34777 -0.892985 -0.285924 0.347599 -0.893148 -0.33997 0.294461 -0.893202 -0.339884 0.294398 -0.893263 -0.378899 0.241901 -0.893279 -0.378871 0.241886 -0.542435 -0.799261 0.25874 -0.515489 -0.829222 0.216013 -0.0841816 -0.171408 0.981597 -0.162579 -0.248206 0.954967 -0.229438 -0.372013 0.899424 -0.276004 -0.435901 0.856629 -0.321947 -0.51993 0.791216 -0.3623 -0.560039 0.745047 -0.425222 -0.67209 0.606203 -0.449444 -0.692422 0.564404 -0.521237 -0.819413 0.238482 -0.981197 -0.17341 0.0847418 -0.186122 -0.903957 0.384994 -0.157207 -0.881212 0.445815 0.0300095 -0.905536 0.423206 -0.455485 -0.808307 0.37306 -0.5456 -0.757992 0.357446 -0.988206 -0.13551 0.071322 -0.893363 -0.407183 0.190014 -0.832758 -0.499063 0.239688 -0.76142 -0.587155 0.274754 -0.649975 -0.688867 0.320928 -0.979409 -0.182121 0.0871161 -0.981186 -0.173187 0.0853247 -0.829496 -0.526214 0.187175 -0.833841 -0.519675 0.186136 -0.54206 -0.798786 0.260982 -0.547337 -0.79526 0.260737 -0.182475 -0.938838 0.292038 -0.187299 -0.937789 0.292353 -0.977971 -0.185937 0.0948735 -0.979037 -0.180402 0.0945569 -0.828348 -0.541671 0.142941 -0.831732 -0.536462 0.142936 -0.540863 -0.823782 0.169854 -0.54664 -0.819866 0.170306 -0.181004 -0.968744 0.169627 -0.188538 -0.967134 0.1706 -0.976348 -0.187142 0.108271 -0.976828 -0.184552 0.108389 -0.828915 -0.54707 0.116683 -0.830624 -0.544405 0.116991 -0.543038 -0.83291 0.106638 -0.546361 -0.830658 0.107221 -0.183711 -0.979682 0.0804574 -0.188493 -0.978702 0.0813211 -0.202221 -0.161702 0.965898 -0.75441 -0.603277 0.258694 -0.664144 -0.435032 0.607997 -0.552374 -0.441712 0.706947 -0.703202 -0.562323 0.435087 -0.793448 -0.579099 0.187308 -0.128385 -0.13993 0.981803 -0.171211 -0.197808 0.965173 -0.202221 -0.161702 0.965898 -0.475613 -0.380313 0.793192 -0.296762 -0.323447 0.898507 -0.414841 -0.452142 0.789604 -0.473089 -0.529948 0.703805 -0.538864 -0.587318 0.60389 -0.653352 -0.712101 0.25699 -0.653354 -0.712101 0.256982 -0.823438 -0.550217 0.138608 -0.536752 -0.836378 0.111212 -0.974709 -0.186505 0.123118 -0.178787 -0.980491 0.0816896 -0.161547 -0.986508 0.0265257 -0.183423 -0.982702 0.0255345 -0.183948 -0.982418 0.0318982 -0.145486 -0.988702 0.0360784 -0.240152 -0.969764 0.043412 -0.183677 -0.981897 0.046283 -0.183364 -0.981613 0.0530444 -0.164931 -0.984721 0.0558849 -0.182695 -0.981409 0.0588058 -0.181663 -0.980998 0.0681316 -0.178399 -0.98164 0.0675052 -0.945471 -0.282523 0.162069 -0.812319 -0.549091 0.196562 -0.812832 -0.548293 0.196668 -0.529302 -0.835261 0.148927 -0.52977 -0.834945 0.149032 -0.160372 -0.984046 0.0770371 -0.162376 -0.98369 0.077387 -0.170315 -0.982116 0.0802555 -0.528521 -0.835123 0.152432 -0.528856 -0.834897 0.152509 -0.81114 -0.54888 0.201948 -0.811484 -0.548344 0.202021 -0.184864 -0.980227 0.07057 -0.211338 -0.974511 0.075261 -0.541334 -0.832127 0.120507 -0.535341 -0.836139 0.119509 -0.824413 -0.545223 0.151903 -0.82124 -0.550121 0.151431 -0.969101 -0.188779 0.158763 -0.959304 -0.186526 0.212 -0.959056 -0.187835 0.211964 -0.95768 -0.18757 0.218326 -0.967101 -0.173798 0.185767 -0.961313 -0.187403 0.201885 -0.957852 -0.186659 0.218352 -0.537493 -0.835884 0.111352 -0.541077 -0.837277 0.0787655 -0.54186 -0.83676 0.0788655 -0.543377 -0.838193 0.0466307 -0.544065 -0.837744 0.0466772 -0.543703 -0.839217 0.0100894 -0.544602 -0.838635 0.0100551 -0.54227 -0.839992 -0.0188884 -0.542623 -0.839763 -0.0189207 -0.824263 -0.54894 0.138767 -0.82972 -0.551076 0.0887672 -0.83067 -0.549624 0.0888913 -0.833029 -0.551821 0.0394615 -0.833878 -0.550532 0.0395215 -0.833157 -0.552789 -0.016565 -0.834217 -0.551186 -0.0166239 -0.83077 -0.553266 -0.0609762 -0.831258 -0.552527 -0.0610293 -0.17994 -0.980739 0.0759834 -0.182575 -0.980203 0.0766036 -0.532391 -0.83566 0.135028 -0.532826 -0.835366 0.135131 -0.81691 -0.549516 0.175187 -0.817455 -0.548663 0.175318 -0.964531 -0.186649 0.186661 -0.971542 -0.188512 0.143419 -0.971905 -0.186567 0.143505 -0.978308 -0.18912 0.0845373 -0.978772 -0.186668 0.0846168 -0.981579 -0.18923 0.0263631 -0.981967 -0.187198 0.026406 -0.980985 -0.18999 -0.0396399 -0.981512 -0.187236 -0.0397013 -0.977555 -0.189582 -0.0919007 -0.977796 -0.188311 -0.0919416 -0.976186 -0.188964 -0.106553 -0.195708 -0.980453 0.020258 -0.183126 -0.982855 0.0214555 -0.541726 -0.840128 -0.0267921 -0.541719 -0.840133 -0.0267913 -0.829912 -0.553087 -0.073089 -0.829852 -0.553177 -0.0730816 -0.975184 -0.194499 -0.105767 -0.976247 -0.189048 -0.105846 -0.189195 -0.0209689 0.981716 -0.186718 0.264455 0.94615 -0.546203 0.196516 0.814275 -0.831336 0.0944844 0.547679 -0.978338 -0.0185532 0.206179 -0.200917 0.264834 0.94313 -0.184278 0.156317 0.970364 -0.0980958 0.135249 0.985944 -0.19411 0.0782705 0.977852 -0.163629 -0.0142416 0.986419 -0.565349 0.195305 0.801397 -0.535032 0.00160188 0.84483 -0.557325 -0.00133513 0.830293 -0.504008 -0.16569 0.847658 -0.522161 -0.170016 0.835729 -0.153435 -0.0898736 0.984063 -0.230711 -0.123388 0.965167 -0.45878 -0.29229 0.839099 -0.519487 -0.320444 0.792117 -0.674181 -0.420244 0.60735 -0.849028 0.0907234 0.520501 -0.817428 -0.110607 0.565313 -0.831788 -0.11284 0.543504 -0.772676 -0.294949 0.562118 -0.781963 -0.296548 0.548263 -0.703118 -0.448233 0.552007 -0.763962 -0.477509 0.433991 -0.985757 -0.0246312 0.166361 -0.957817 -0.200925 0.205467 -0.962641 -0.201894 0.180448 -0.907004 -0.37195 0.197476 -0.909558 -0.371648 0.185964 -0.83136 -0.522381 0.189628 -0.832083 -0.522285 0.186699 -0.180649 -0.983548 -1.46551e-05 -0.539876 -0.84068 -0.0423151 -0.82909 -0.553434 -0.0795007 -0.976603 -0.188914 -0.102755 0.0549192 -0.969854 -0.237416 -0.190336 -0.981719 -0.000387544 -0.1839 -0.980887 -0.0635677 0.0233562 -0.995677 -0.089902 -0.189105 -0.972904 -0.133028 -0.180814 -0.957488 -0.224772 -0.186826 -0.539407 -0.821058 -0.0173276 -0.562447 -0.826652 -0.186959 -0.609702 -0.770266 -0.186679 -0.67757 -0.711372 -0.184478 -0.677745 -0.71178 -0.186505 -0.770406 -0.609665 -0.182536 -0.770859 -0.610292 -0.186595 -0.843479 -0.503711 -0.180748 -0.844316 -0.50444 -0.187391 -0.902984 -0.386658 -0.179014 -0.904379 -0.387366 -0.186302 -0.937001 -0.2955 -0.548549 -0.835035 -0.0425488 -0.538863 -0.832164 -0.130881 -0.546605 -0.827171 -0.130423 -0.535967 -0.807266 -0.247107 -0.543757 -0.802447 -0.245778 -0.535768 -0.766681 -0.353769 -0.542601 -0.762734 -0.351883 -0.537329 -0.715803 -0.445986 -0.543239 -0.712699 -0.443792 -0.539957 -0.654443 -0.529292 -0.54505 -0.652089 -0.526973 -0.543307 -0.57672 -0.610091 -0.547166 -0.575239 -0.608038 -0.546458 -0.470708 -0.692689 -0.547358 -0.470451 -0.692153 -0.832357 -0.548512 -0.0794814 -0.826587 -0.547063 -0.132196 -0.829747 -0.5424 -0.13161 -0.823377 -0.530495 -0.201555 -0.827324 -0.524947 -0.199914 -0.822612 -0.503812 -0.263597 -0.826943 -0.498112 -0.260865 -0.823859 -0.4707 -0.315749 -0.828394 -0.465207 -0.312003 -0.826453 -0.430972 -0.36227 -0.831199 -0.4258 -0.357496 -0.830124 -0.380304 -0.407754 -0.834169 -0.376518 -0.402984 -0.833665 -0.310056 -0.45702 -0.834735 -0.309277 -0.455594 -0.976967 -0.187055 -0.102691 -0.975883 -0.186807 -0.112938 -0.976402 -0.184306 -0.112562 -0.975117 -0.181897 -0.126728 -0.976127 -0.177402 -0.12532 -0.975285 -0.173641 -0.136633 -0.976797 -0.167396 -0.133586 -0.976298 -0.162999 -0.142384 -0.978209 -0.15565 -0.137402 -0.977876 -0.149777 -0.14603 -0.980039 -0.142065 -0.139072 -0.979814 -0.13232 -0.149855 -0.981736 -0.126167 -0.142394 -0.981612 -0.106665 -0.158305 -0.982149 -0.105276 -0.155888 -0.988152 0.129336 0.0826345 -0.992718 0.0909893 0.0789472 -0.988191 0.119356 0.0960863 -0.98815 0.129345 0.0826411 -0.988134 0.0750577 0.134007 -0.988207 0.0862847 0.1265 -0.990203 0.0885751 0.107942 -0.98813 0.0983663 0.118 -0.988191 0.111564 0.105036 -0.157069 0.841332 0.517194 0.0196309 0.842533 0.538288 -0.455415 0.750234 0.479318 -0.761242 0.546459 0.349133 -0.893277 0.378795 0.242013 -0.158128 0.802967 0.574665 -0.157476 0.733421 0.661283 -0.433796 0.680578 0.590453 0.0660124 0.633044 0.771296 -0.893259 0.378824 0.242035 -0.893199 0.339644 0.294683 -0.893149 0.339714 0.294754 -0.892987 0.285525 0.347923 -0.892863 0.285665 0.348124 -0.156971 0.609654 0.77697 -0.157087 0.495782 0.854122 0.160279 0.460258 0.873197 -0.187142 0.390453 0.901401 -0.45537 0.750251 0.479334 -0.45525 0.672536 0.583475 -0.455146 0.67257 0.583517 -0.454824 0.56501 0.688404 -0.45458 0.565073 0.688513 -0.453914 0.408125 0.792084 -0.545993 0.389384 0.741803 -0.982269 0.071687 0.173231 -0.99014 0.0672854 0.12286 -0.834198 0.250139 0.491472 -0.892946 0.215068 0.395466 -0.707672 0.322275 0.62876 -0.708414 0.447745 0.545594 -0.708651 0.447614 0.545395 -0.708966 0.532693 0.462176 -0.70908 0.532614 0.462091 -0.709089 0.59575 0.377194 -0.649796 0.640538 0.409239 -0.15639 -0.368533 -0.916365 -0.453262 -0.3627 -0.81425 -0.548144 -0.353433 -0.758039 0.00250042 -0.41211 -0.911131 -0.187167 -0.433459 -0.881522 -0.648349 -0.318129 -0.691692 -0.759452 -0.271839 -0.591047 -0.834941 -0.224737 -0.502362 -0.987624 -0.0655307 -0.142494 -0.982155 -0.0760003 -0.172032 -0.940523 -0.14195 -0.308652 -0.875754 -0.201713 -0.438596 -0.893369 0.407102 0.190157 -0.649975 0.688711 0.321265 -0.183627 0.979632 0.0812485 -0.542964 0.832878 0.107261 -0.828872 0.547054 0.117063 -0.976333 0.187138 0.108413 -0.188572 0.978694 0.0812317 -0.183006 0.971761 0.14896 -0.0193682 0.986371 0.163393 -0.157003 0.893943 0.419781 -0.127641 0.898879 0.419195 -0.186664 0.914453 0.359072 -0.187287 0.9374 0.293608 -0.182522 0.938169 0.294152 -0.187067 0.960014 0.208277 -0.546412 0.830645 0.107065 -0.540743 0.823455 0.171812 -0.546677 0.819718 0.170899 -0.542121 0.79814 0.262825 -0.547329 0.795044 0.26141 -0.545977 0.760958 0.350502 -0.455756 0.803639 0.38269 -0.830676 0.544375 0.116761 -0.828279 0.541456 0.144152 -0.831784 0.53638 0.14294 -0.829516 0.525702 0.188521 -0.833893 0.519637 0.186011 -0.833022 0.500578 0.235576 -0.761724 0.581723 0.285265 -0.976845 0.184645 0.108079 -0.977926 0.185971 0.0952681 -0.979099 0.180406 0.0939122 -0.979401 0.181834 0.0878057 -0.981209 0.17348 0.0844655 -0.981148 0.172308 0.0875181 -0.988191 0.137228 0.068163 -0.191618 -0.058694 -0.979713 -0.568972 -0.182611 -0.801825 -0.155887 -0.263549 -0.951967 -0.204599 -0.261406 -0.943295 -0.451353 -0.207653 -0.867848 -0.64626 -0.171127 -0.743683 -0.982629 0.0406223 -0.18108 -0.93506 -0.0135973 -0.35423 -0.85139 -0.0732136 -0.519399 -0.871324 -0.0666778 -0.486156 -0.755215 -0.115695 -0.645186 -0.948121 0.31759 0.0142524 -0.964735 0.178009 -0.193904 -0.985529 0.0439343 -0.163714 -0.15532 0.0295937 -0.987421 -0.184296 0.0412546 -0.982005 -0.483058 0.21143 -0.849678 -0.503445 0.219297 -0.835735 -0.741104 0.364049 -0.564122 -0.751426 0.367533 -0.547976 -0.645062 0.526756 -0.553555 -0.645955 0.527197 -0.552092 -0.434397 0.350035 -0.829924 -0.42197 0.342548 -0.839406 -0.156615 0.119252 -0.980434 -0.139694 0.108387 -0.984245 -0.18169 -0.141136 -0.973175 -0.0685947 -0.136289 -0.988292 -0.528136 0.0286773 -0.848676 -0.554582 0.0348697 -0.831398 -0.807103 0.155301 -0.569619 -0.823819 0.160003 -0.543803 -0.949152 0.25817 -0.180163 -0.869541 0.45201 -0.198961 -0.872307 0.45233 -0.185682 -0.759883 0.621801 -0.189581 -0.758825 0.621686 -0.194143 -0.179571 0.980648 0.0780008 -0.196329 0.976896 0.084438 -0.171504 0.981914 0.0802008 -0.178744 0.980477 0.081949 -0.179489 0.980643 0.0782499 -0.170865 0.982494 0.0742311 -0.259547 0.962225 0.0822056 -0.181754 0.981016 0.0676282 -0.182393 0.981288 0.0616949 -0.17248 0.983465 0.0552019 -0.183649 0.98136 0.056622 -0.18408 0.981794 0.0468434 -0.172269 0.983985 0.045801 -0.183881 0.982049 0.0420428 -0.183799 0.982384 0.0337543 -0.184102 0.982328 0.0337275 -0.168636 0.985343 0.0257112 -0.177274 0.983841 0.0251321 -0.183574 0.982626 0.0273344 -0.541718 0.840133 -0.0267943 -0.183116 0.982857 0.0214556 -0.187059 0.982122 0.0210814 -0.829855 0.553173 -0.0730834 -0.541725 0.840129 -0.0267954 -0.542608 0.83977 -0.0190516 -0.542255 0.839999 -0.0189912 -0.544564 0.838665 0.00950179 -0.543698 0.839226 0.00960375 -0.544109 0.837781 0.0454807 -0.543417 0.838226 0.0455433 -0.542015 0.836823 0.0771202 -0.54124 0.837322 0.0771448 -0.537755 0.83592 0.109801 -0.537003 0.836407 0.109778 -0.533053 0.835374 0.134184 -0.53257 0.835688 0.134147 -0.528928 0.834896 0.152261 -0.528593 0.835118 0.15221 -0.529279 0.835239 0.149132 -0.529756 0.834924 0.149201 -0.829909 0.553089 -0.0730968 -0.831234 0.552539 -0.0612369 -0.830747 0.553284 -0.0611246 -0.834163 0.55124 -0.0174817 -0.83313 0.552807 -0.0172991 -0.833923 0.550594 0.0376704 -0.833117 0.551803 0.0378067 -0.830935 0.549652 0.0861946 -0.829972 0.551089 0.0863 -0.824662 0.54894 0.136372 -0.823795 0.55023 0.136413 -0.81778 0.548646 0.173849 -0.817166 0.54956 0.173849 -0.811579 0.548346 0.201635 -0.811207 0.548909 0.201601 -0.812242 0.549094 0.196872 -0.812752 0.548323 0.196917 -0.976247 0.189048 -0.105846 -0.975162 0.194611 -0.105765 -0.976171 0.18904 -0.106561 -0.977757 0.188397 -0.0921856 -0.97755 0.189519 -0.0920802 -0.981475 0.187212 -0.0407267 -0.980958 0.18995 -0.0404952 -0.982021 0.187213 0.024213 -0.981619 0.189281 0.0244269 -0.979023 0.186774 0.0814218 -0.978547 0.18916 0.0816406 -0.972313 0.186601 0.14067 -0.9719 0.188619 0.140829 -0.964838 0.186715 0.185001 -0.964544 0.18813 0.185097 -0.957949 0.186698 0.217892 -0.957769 0.187591 0.217919 -0.958976 0.187824 0.212335 -0.959237 0.186534 0.212295 -0.968597 0.188678 0.161927 -0.974709 0.186507 0.123119 -0.947789 0.276144 0.159498 -0.824408 0.54522 0.151942 -0.82115 0.550144 0.151839 -0.541344 0.832133 0.120423 -0.535302 0.836109 0.119888 -0.184775 0.980182 0.0714197 -0.180913 0.980935 0.0709681 -0.128505 0.147339 -0.980703 -0.128506 0.147339 -0.980702 -0.365745 0.419348 -0.83089 -0.365736 0.419341 -0.830897 -0.546892 0.627048 -0.554726 -0.546887 0.627045 -0.554733 -0.644717 0.739215 -0.194681 -0.644726 0.739215 -0.194652 -0.10787 0.163055 -0.980702 -0.107871 0.163056 -0.980702 -0.307005 0.464066 -0.830898 -0.307013 0.464073 -0.83089 -0.459072 0.69392 -0.554732 -0.459075 0.693923 -0.554727 -0.541197 0.818056 -0.194655 -0.541189 0.818054 -0.194682 -0.547339 0.470898 -0.691864 -0.834724 0.309487 -0.45547 -0.98215 0.105202 -0.155931 -0.0505558 0.683054 -0.728616 -0.186677 0.678603 -0.710387 -0.186767 0.591507 -0.784371 0.109194 0.559885 -0.821344 -0.187121 0.518069 -0.83462 -0.0156017 0.923744 -0.382693 -0.185803 0.72197 -0.666511 -0.186496 0.771184 -0.608682 -0.182525 0.77202 -0.608827 -0.185565 0.821309 -0.53946 0.00649353 0.863515 -0.504281 -0.18201 0.855209 -0.485274 -0.186737 0.89685 -0.400985 -0.182217 0.983165 0.0135755 -0.0763534 0.996996 0.0129982 -0.188104 0.981899 -0.0221756 -0.178926 0.978046 -0.106822 -0.190872 0.975572 -0.108753 -0.177854 0.951434 -0.251278 -0.189025 0.948949 -0.252518 -0.18317 0.923252 -0.337721 -0.546411 0.471316 -0.692312 -0.547157 0.575816 -0.607499 -0.543264 0.577871 -0.60904 -0.545014 0.652584 -0.526397 -0.539917 0.655565 -0.527943 -0.543195 0.713026 -0.443321 -0.537352 0.716699 -0.444517 -0.542567 0.762757 -0.351884 -0.535871 0.767173 -0.352544 -0.543764 0.802525 -0.245509 -0.535972 0.807793 -0.245364 -0.546567 0.827284 -0.129869 -0.539036 0.832374 -0.12882 -0.548445 0.835075 -0.0431053 -0.540013 0.840648 -0.0412017 -0.833642 0.310543 -0.456732 -0.834175 0.376599 -0.402896 -0.830104 0.381294 -0.406868 -0.831173 0.425863 -0.35748 -0.826453 0.43189 -0.361173 -0.828366 0.46525 -0.312014 -0.823898 0.471385 -0.314623 -0.826917 0.498041 -0.261083 -0.822688 0.504175 -0.262664 -0.827318 0.524973 -0.199869 -0.823445 0.530825 -0.200409 -0.829773 0.54244 -0.131284 -0.826738 0.547135 -0.130949 -0.832342 0.548488 -0.0798014 -0.82917 0.553406 -0.0788606 -0.981596 0.106998 -0.158178 -0.981725 0.125779 -0.142813 -0.979824 0.132968 -0.149213 -0.980027 0.141645 -0.139583 -0.977878 0.150423 -0.145356 -0.978165 0.155447 -0.137948 -0.976325 0.163409 -0.141726 -0.976763 0.167246 -0.134025 -0.975323 0.173856 -0.136088 -0.976105 0.17735 -0.12556 -0.975154 0.182019 -0.126272 -0.976398 0.184313 -0.112591 -0.975904 0.186915 -0.112581 -0.976939 0.187142 -0.102801 -0.976621 0.188907 -0.102593 -0.467288 0.862321 -0.195052 -0.0693189 0.18494 -0.980302 -0.428959 0.871256 -0.238555 -0.466915 0.86269 -0.194309 -0.364134 0.740696 -0.564602 -0.370155 0.744994 -0.55495 -0.305128 0.593082 -0.745084 -0.234574 0.505109 -0.830566 -0.22321 0.465014 -0.856702 -0.136278 0.26353 -0.954976 -0.982197 0.0784884 -0.17067 -0.980669 0.0825306 -0.177418 -0.835116 0.229033 -0.500125 -0.830729 0.232609 -0.50575 -0.548006 0.349522 -0.759949 -0.554505 0.346884 -0.756437 -0.186894 0.411325 -0.892123 -0.194561 0.409882 -0.891147 -0.601086 -0.5686 -0.561595 -0.666469 -0.63045 -0.397935 -0.376923 -0.35656 -0.854865 -0.486492 -0.46021 -0.742652 -0.21695 -0.205228 -0.954366 -0.521603 0.819667 -0.236804 -0.709283 0.66396 -0.236802 -0.709288 0.663959 -0.236788 -0.852287 0.466412 -0.236785 -0.852273 0.466419 -0.236821 -0.941575 0.239482 -0.236822 -0.941581 0.239477 -0.236803 -0.971555 -0.00255612 -0.236801 -0.971547 -0.0025457 -0.236832 -0.94031 -0.244393 -0.236832 -0.940317 -0.24441 -0.236787 -0.849829 -0.470873 -0.236789 -0.849827 -0.470858 -0.236825 -0.716859 -0.655605 -0.237267 -0.715988 -0.677313 -0.169141 -0.559993 -0.501295 -0.65963 -0.658304 -0.364753 -0.658476 -0.658294 -0.364738 -0.658495 -0.728384 -0.189312 -0.658496 -0.728402 -0.189328 -0.658472 -0.752602 -0.00198007 -0.658473 -0.75257 -0.00196324 -0.658509 -0.729353 0.185505 -0.658507 -0.729378 0.185499 -0.658481 -0.660203 0.361295 -0.658482 -0.660197 0.361295 -0.658488 -0.549428 0.51432 -0.658486 -0.549436 0.514322 -0.658478 -0.521603 0.819667 -0.236804 -0.444213 0.698053 -0.561601 -0.420781 0.622759 -0.659632 -0.359532 0.564993 -0.742643 -0.278533 0.437705 -0.854888 -0.272401 -0.233928 -0.933314 -0.315419 -0.174763 -0.932721 -0.315427 -0.174772 -0.932717 -0.349013 -0.0907162 -0.932717 -0.349014 -0.0907162 -0.932717 -0.360609 -0.000940723 -0.932716 -0.360605 -0.000938881 -0.932718 -0.349481 0.0888819 -0.932718 -0.349483 0.0888816 -0.932717 -0.316336 0.173116 -0.932718 -0.316327 0.173115 -0.932721 -0.263256 0.246432 -0.932721 -0.263266 0.246436 -0.932717 -0.207107 0.293322 -0.933311 -0.160339 0.251966 -0.954361 -0.940488 -0.286126 -0.183342 -0.176546 0.116487 -0.977375 -0.759839 -0.621849 -0.1896 -0.759544 -0.620814 -0.194121 -0.646114 -0.526976 -0.552117 -0.64554 -0.526207 -0.55352 -0.423418 -0.340425 -0.83954 -0.433063 -0.351456 -0.830021 -0.141151 -0.106082 -0.984288 -0.154997 -0.12088 -0.980492 -0.870741 -0.449737 -0.198865 -0.87189 -0.453116 -0.185728 -0.742683 -0.360936 -0.564045 -0.75048 -0.369139 -0.548193 -0.484765 -0.207621 -0.849645 -0.501823 -0.221663 -0.836085 -0.156916 -0.0256098 -0.98728 -0.182247 -0.0441016 -0.982263 -0.964883 -0.177009 -0.194083 -0.958272 -0.283788 -0.0343424 -0.80856 -0.149698 -0.569052 -0.822938 -0.16282 -0.544301 -0.529365 -0.0230453 -0.848081 -0.553443 -0.0378298 -0.832027 -0.104839 0.125642 -0.986521 -0.182454 0.0363138 -0.982544 -0.975949 -0.0254126 -0.216511 -0.984939 -0.0501911 -0.165454 -0.826434 0.089352 -0.555898 -0.850849 0.0692124 -0.520832 -0.552434 0.188497 -0.811964 -0.568448 0.181216 -0.802513 -0.194378 0.259987 -0.945846 -0.203503 0.257444 -0.944621 -0.638367 -0.750628 -0.170427 -0.663546 -0.722263 -0.195047 -0.647778 -0.746121 -0.153905 -0.606484 -0.686926 -0.400387 -0.538943 -0.633744 -0.554896 -0.536822 -0.626968 -0.564564 -0.372032 -0.412868 -0.831344 -0.170723 -0.24335 -0.954796 -0.134162 -0.141651 -0.980783 -0.329922 -0.396544 -0.856682 -0.405278 -0.529706 -0.745092 -0.107871 -0.163057 -0.980702 -0.10787 -0.163055 -0.980702 -0.307011 -0.464075 -0.83089 -0.307007 -0.464064 -0.830898 -0.459074 -0.693923 -0.554727 -0.459073 -0.69392 -0.554732 -0.541193 -0.818051 -0.194686 -0.541192 -0.818059 -0.194655 -0.128506 -0.14734 -0.980702 -0.128505 -0.147338 -0.980703 -0.365738 -0.41934 -0.830897 -0.365743 -0.419349 -0.83089 -0.546888 -0.627044 -0.554733 -0.54689 -0.627049 -0.554726 -0.644721 -0.739219 -0.194652 -0.644722 -0.739211 -0.194681 -0.92176 -0.335248 -0.194853 -0.195068 -0.019727 -0.980591 -0.195068 -0.0197269 -0.980591 -0.441799 -0.0446784 -0.896001 -0.555605 -0.0506584 -0.829901 -0.149254 -0.127124 -0.980593 -0.149258 -0.127128 -0.980592 -0.424439 -0.361509 -0.830158 -0.424428 -0.361497 -0.830169 -0.633974 -0.539973 -0.55363 -0.633992 -0.539996 -0.553587 -0.746801 -0.636081 -0.194138 -0.746798 -0.636071 -0.194179 -0.171688 -0.0946722 -0.980592 -0.171685 -0.09467 -0.980593 -0.488206 -0.269205 -0.830171 -0.4882 -0.2692 -0.830176 -0.729272 -0.40213 -0.553582 -0.729267 -0.402126 -0.553593 -0.859025 -0.473676 -0.194186 -0.859026 -0.473678 -0.194175 -0.950806 -0.240772 -0.194925 -0.954636 -0.297771 -0.00150981 -0.795006 -0.247979 -0.553599 -0.795011 -0.247982 -0.55359 -0.532219 -0.166011 -0.830171 -0.53221 -0.166007 -0.830178 -0.187169 -0.0583817 -0.980591 -0.187164 -0.0583793 -0.980592 -0.607636 -0.0614516 -0.791835 -0.790776 -0.0799731 -0.606858 -0.829284 -0.0782106 -0.553327 -0.89323 -0.0903281 -0.440432 -0.975989 -0.0986971 -0.194176 -0.975999 -0.098705 -0.194124 -0.46679 -0.86259 -0.195053 -0.467439 -0.862549 -0.193675 -0.428953 -0.871258 -0.238555 -0.0955537 -0.170096 -0.980784 -0.106203 -0.277658 -0.954792 -0.368057 -0.746079 -0.554887 -0.367653 -0.738981 -0.564569 -0.260079 -0.491164 -0.831334 -0.263816 -0.612578 -0.745084 -0.22321 -0.465014 -0.856702 -0.195106 0 -0.980782 -0.195106 0 -0.980782 -0.44224 0 -0.896897 -0.44224 0 -0.896897 -0.608786 0 -0.793334 -0.608786 0 -0.793334 -0.793317 0 -0.608808 -0.793317 0 -0.608808 -0.896897 0 -0.44224 -0.896897 0 -0.44224 -0.980788 0 -0.195077 -0.980788 0 -0.195077 -0.444213 -0.698053 -0.561601 -0.278533 -0.437706 -0.854888 -0.359532 -0.564993 -0.742643 -0.160339 -0.251966 -0.954361 -0.420781 -0.622759 -0.659632 -0.549433 -0.514325 -0.658478 -0.54943 -0.514317 -0.658487 -0.660198 -0.361293 -0.658487 -0.660202 -0.361297 -0.658482 -0.729374 -0.185511 -0.658482 -0.729355 -0.185494 -0.658509 -0.752571 0.00197998 -0.658508 -0.752603 0.00196333 -0.658471 -0.728404 0.189317 -0.658473 -0.728381 0.189322 -0.658497 -0.65829 0.364745 -0.658494 -0.658309 0.364746 -0.658475 -0.715988 0.677313 -0.169141 -0.716859 0.655605 -0.237267 -0.849821 0.470869 -0.236825 -0.849835 0.470863 -0.23679 -0.940321 0.244395 -0.236786 -0.940306 0.244407 -0.236831 -0.971547 0.0025561 -0.236832 -0.971555 0.00254572 -0.236802 -0.94158 -0.239484 -0.236801 -0.941577 -0.239476 -0.236822 -0.852279 -0.466408 -0.236821 -0.852281 -0.466423 -0.236785 -0.709285 -0.663962 -0.236788 -0.709286 -0.663956 -0.236802 -0.521603 -0.819667 -0.236804 -0.521603 -0.819667 -0.236804 -0.666469 0.63045 -0.397935 -0.601086 0.5686 -0.561595 -0.559992 0.501295 -0.65963 -0.486492 0.46021 -0.742652 -0.376923 0.35656 -0.854865 -0.207107 -0.293322 -0.933311 -0.263263 -0.246438 -0.932717 -0.263259 -0.246428 -0.932721 -0.316329 -0.173112 -0.932721 -0.316335 -0.173119 -0.932718 -0.349483 -0.0888824 -0.932717 -0.349481 -0.0888811 -0.932718 -0.360605 0.000940722 -0.932718 -0.36061 0.000938894 -0.932716 -0.349014 0.0907162 -0.932716 -0.349013 0.0907162 -0.932717 -0.315429 0.174768 -0.932717 -0.315417 0.174766 -0.932721 -0.272401 0.233928 -0.933314 -0.21695 0.205228 -0.954366 -0.950806 0.240772 -0.194926 -0.554679 0.056096 -0.830172 -0.195068 0.019727 -0.980591 -0.195068 0.019727 -0.980591 -0.441799 0.0446784 -0.896001 -0.607922 0.0532713 -0.792208 -0.975988 0.0987039 -0.194177 -0.975999 0.0986981 -0.194124 -0.828559 0.0837881 -0.553598 -0.894454 0.0737506 -0.441035 -0.790776 0.0799731 -0.606858 -0.187169 0.058381 -0.980591 -0.187163 0.05838 -0.980593 -0.532219 0.16601 -0.830171 -0.532209 0.166008 -0.830177 -0.795006 0.24798 -0.553598 -0.795011 0.247981 -0.553591 -0.954636 0.297771 -0.0015103 -0.92176 0.335248 -0.194853 -0.171685 0.0946705 -0.980593 -0.171689 0.0946718 -0.980592 -0.4882 0.269201 -0.830176 -0.488207 0.269204 -0.830171 -0.729266 0.402127 -0.553594 -0.729273 0.402129 -0.553582 -0.859027 0.473676 -0.194175 -0.859024 0.473677 -0.194187 -0.149258 0.127127 -0.980592 -0.149254 0.127125 -0.980593 -0.424427 0.361499 -0.830169 -0.42444 0.361507 -0.830158 -0.633996 0.539991 -0.553587 -0.633969 0.539978 -0.55363 -0.746794 0.636075 -0.19418 -0.746804 0.636077 -0.194138 -0.112343 0.162444 -0.980301 -0.646381 0.743748 -0.170386 -0.641801 0.754126 -0.139233 -0.663546 0.722263 -0.195047 -0.196437 0.222314 -0.954981 -0.329922 0.396544 -0.856682 -0.3507 0.432615 -0.830574 -0.440587 0.50072 -0.745092 -0.540709 0.632181 -0.554959 -0.533832 0.629486 -0.564597 -0.606484 0.686926 -0.400387 0.763109 0.0878604 -0.64027 0.665218 0.061271 -0.744131 0.0181153 0.195064 -0.980623 0.0218071 0.208543 -0.97777 0.0523463 0.178709 -0.982508 0.0590102 0.190903 -0.979834 0.0933091 0.176821 -0.97981 0.0891613 0.171614 -0.981121 0.138627 0.170002 -0.975644 0.177387 0.203991 -0.962768 0.148082 0.123002 -0.981296 0.176661 0.133039 -0.975239 0.195004 0.105184 -0.975146 0.225669 0.113799 -0.967535 0.210974 0.0646792 -0.975349 0.237021 0.064822 -0.969339 0.246928 0.0112597 -0.968968 0.17363 0.0159581 -0.984682 0.0516158 0.554833 -0.830359 0.0522114 0.556726 -0.829054 0.149334 0.538411 -0.829345 0.171556 0.575983 -0.799257 0.240108 0.472324 -0.848091 0.274358 0.51163 -0.814225 0.352099 0.460164 -0.815031 0.414449 0.499222 -0.760926 0.39535 0.351704 -0.84853 0.487777 0.393662 -0.779169 0.540256 0.291896 -0.789253 0.574694 0.298927 -0.761819 0.615708 0.19882 -0.762479 0.679653 0.194175 -0.707367 0.589801 -0.0145983 -0.807416 0.578684 0.0661515 -0.812864 0.499562 0.041484 -0.865284 -0.139181 0.540706 -0.829618 -0.142355 0.546539 -0.825245 -0.0488065 0.190143 -0.980542 -0.0499608 0.192518 -0.980021 -0.0455636 0.554996 -0.830604 -0.0460098 0.556343 -0.829678 -0.0159887 0.195071 -0.980659 -0.0161436 0.195613 -0.980548 0.766072 0 -0.642755 0.766072 0 -0.642755 0.499992 0 -0.86603 0.499992 0 -0.86603 0.173652 0 -0.984807 0.173652 0 -0.984807 0.0307897 0.0381939 -0.998796 -0.644544 0.322564 -0.693192 -0.203455 0.525374 -0.826189 0.0452961 0.0212859 -0.998747 0.0646377 0.0238667 -0.997623 -0.233885 0.0927091 -0.967834 -0.204473 0.171906 -0.963659 -0.431773 0.284649 -0.85589 -0.407694 0.275876 -0.870447 -0.792628 0.441137 -0.420879 -0.561335 0.389505 -0.730198 -0.0852094 0.179903 -0.979987 -0.083667 0.175863 -0.980853 -0.0949034 0.167385 -0.981313 -0.0899791 0.133447 -0.986963 0.000971006 0.0636781 -0.99797 0.00412775 0.0680538 -0.997673 -0.689775 0.193278 -0.69775 -0.739221 0.194155 -0.644869 -0.481987 0.14953 -0.863325 -0.51891 0.152489 -0.841118 -0.244775 0.0962026 -0.964795 -0.30712 0.583997 -0.751415 -0.281506 0.509295 -0.813249 -0.350868 0.457994 -0.816782 0.0345661 0.0483356 -0.998233 0.0214641 0.0523077 -0.9984 -0.208164 0.174217 -0.962453 -0.171931 0.224518 -0.959183 -0.334894 0.37685 -0.863614 -0.547127 0.533151 -0.645292 -0.496302 0.479315 -0.723838 -0.757637 0.0523786 -0.650571 -0.779972 0.0449603 -0.624198 -0.532196 0.0412985 -0.845613 -0.552229 0.0365537 -0.832891 -0.252521 0.0262226 -0.967236 -0.264129 0.0240965 -0.964186 0.044022 0.00937034 -0.998987 0.0430462 0.00922377 -0.999031 -0.780705 0.000513682 -0.624899 -0.780524 0.000549164 -0.625126 -0.552545 0.00148755 -0.833482 -0.551814 0.00159923 -0.833966 -0.264175 0.00232724 -0.964472 -0.262686 0.00252252 -0.964878 0.0430537 0.00292198 -0.999068 0.0451924 0.00317768 -0.998973 0.173624 -0.0180817 -0.984646 0.756068 -0.0827955 -0.649235 0.763483 -0.0821345 -0.640584 0.245163 -0.0156391 -0.969356 0.232112 -0.0773001 -0.969613 0.217359 -0.0754299 -0.973173 0.606095 -0.208473 -0.767586 0.729532 -0.212451 -0.650113 0.550915 -0.181726 -0.814536 0.577178 -0.0582675 -0.814537 0.499154 -0.0578944 -0.864577 -0.780526 0.00182182 -0.62512 -0.775783 0.00203029 -0.630996 -0.55182 0.00526085 -0.833946 -0.531601 0.00589653 -0.846975 -0.262696 0.00824534 -0.964843 -0.22212 0.00921419 -0.974976 0.0451744 0.0103682 -0.998925 0.103334 0.0114361 -0.994581 0.198206 -0.116729 -0.973185 0.541626 -0.345224 -0.76646 0.169806 -0.103446 -0.980033 0.154996 -0.119599 -0.980649 0.119646 -0.0863654 -0.989053 0.0953149 -0.100175 -0.990394 0.0754582 -0.0657535 -0.994979 0.029899 -0.0767576 -0.996601 0.0262563 -0.0633587 -0.997645 0.505689 -0.330375 -0.796951 0.401363 -0.443975 -0.80112 0.378743 -0.423229 -0.823062 0.242686 -0.500354 -0.831113 0.233283 -0.484173 -0.8433 0.0780206 -0.521801 -0.849492 0.0765281 -0.516682 -0.85275 0.103289 0.0167525 -0.99451 -0.77579 0.00279458 -0.630985 -0.77491 0.00300045 -0.632065 -0.53162 0.00803478 -0.846945 -0.52778 0.00872268 -0.849336 -0.22215 0.0124795 -0.974933 -0.214399 0.0136463 -0.976651 0.108232 0.0154729 -0.994005 0.114263 0.0170812 -0.993304 -0.148264 -0.511688 -0.846282 -0.017865 -0.0633704 -0.99783 -0.144751 -0.505027 -0.850879 -0.0478232 -0.519117 -0.853364 -0.0481531 -0.517601 -0.854266 -0.0170127 -0.0686287 -0.997497 -0.0529212 -0.063423 -0.996583 -0.0528668 -0.0795384 -0.995429 -0.690687 -0.105078 -0.715479 0.107161 -0.0377239 -0.993526 0.129272 -0.0278288 -0.991219 -0.166241 -0.119824 -0.978778 -0.161766 -0.11906 -0.979621 -0.45591 -0.19985 -0.867298 -0.425007 -0.196214 -0.883668 -0.724908 -0.263918 -0.636283 -0.645621 -0.261968 -0.717318 -0.774699 -0.011624 -0.632223 -0.809259 -0.0877334 -0.580863 -0.525458 -0.0700416 -0.847932 -0.484127 -0.060666 -0.872892 -0.213664 -0.0378063 -0.976175 -0.184258 -0.031305 -0.982379 0.114415 -0.00219713 -0.993431 0.123626 -0.000160193 -0.992329 -0.313825 -0.452748 -0.834585 -0.548453 -0.401326 -0.733579 -0.489233 -0.484764 -0.72502 -0.604893 -0.361057 -0.709748 -0.664843 -0.412396 -0.622827 -0.372291 -0.282094 -0.884207 -0.387243 -0.286735 -0.876257 0.104039 -0.0304488 -0.994107 0.0897412 -0.0365285 -0.995295 0.0583559 -0.0124752 -0.998218 -0.0567737 -0.0910782 -0.994224 -0.244618 -0.493032 -0.834914 -0.242961 -0.48183 -0.841909 -0.0687783 -0.0858388 -0.993932 -0.0665348 -0.0752301 -0.994944 -0.142922 -0.16385 -0.976077 -0.147073 -0.165381 -0.975202 -0.138258 -0.178296 -0.974215 -0.334134 -0.337955 -0.879853 -0.320923 -0.330147 -0.8877 -0.396583 -0.38928 -0.831374 -0.365393 -0.285698 -0.885926 -0.353765 -0.47904 -0.80335 -0.057198 -0.0906781 -0.994236 -0.0579359 -0.092306 -0.994044 0.560806 -0.160801 -0.812182 0.170736 -0.14175 -0.975067 0.743073 -0.175698 -0.645734 0.19877 -0.0993252 -0.975 0.230978 -0.124206 -0.964998 0.207982 -0.0557784 -0.976541 0.235709 -0.0719377 -0.969157 0.244955 -0.0223999 -0.969276 0.149789 -0.115039 -0.982003 0.154541 -0.147968 -0.976843 0.128262 -0.158523 -0.978989 0.128745 -0.159541 -0.97876 0.0953605 -0.181813 -0.978698 0.0945199 -0.178873 -0.979321 0.055026 -0.189909 -0.980258 0.0549505 -0.188874 -0.980463 0.0178341 -0.195831 -0.980475 0.0179213 -0.195064 -0.980627 0.760768 -0.0742856 -0.644759 0.792815 -0.0688963 -0.605556 0.580357 -0.0565593 -0.812396 0.60972 -0.0534904 -0.79081 0.258728 -0.0274136 -0.965561 0.0511058 -0.554847 -0.830381 0.0508024 -0.556765 -0.829115 0.158198 -0.53651 -0.828934 0.158533 -0.54542 -0.823034 0.267147 -0.500218 -0.823659 0.270409 -0.513787 -0.814188 0.370009 -0.447336 -0.814238 0.377698 -0.464128 -0.801205 0.465343 -0.376034 -0.801283 0.479046 -0.395403 -0.783691 0.550899 -0.286812 -0.78374 0.580361 -0.315608 -0.750715 0.606921 -0.188915 -0.771983 0.794703 0 -0.606998 0.794703 0 -0.606998 0.610594 0 -0.791943 0.610594 0 -0.791943 0.258825 0 -0.965924 0.258825 0 -0.965924 -0.0190181 -0.19506 -0.980607 -0.0539169 -0.556995 -0.828764 -0.0542276 -0.554756 -0.830244 -0.0189302 -0.195969 -0.980427 -0.0587472 -0.188026 -0.980406 -0.0591493 -0.191767 -0.979657 -0.158572 -0.536293 -0.829003 -0.177753 -0.566083 -0.804956 -0.217636 -0.523312 -0.82388 0.0163961 -0.045594 -0.998825 -0.778435 -0.105644 -0.618772 -0.238135 -0.149256 -0.959695 0.0117112 -0.0270946 -0.999564 0.0251742 -0.0240397 -0.999394 -0.261342 -0.0573864 -0.963539 -0.276339 -0.0606741 -0.959143 -0.00265209 -0.0573429 -0.998351 -0.727808 -0.11155 -0.676647 -0.694285 -0.255255 -0.672914 -0.838475 -0.356055 -0.412535 -0.610043 -0.337347 -0.716969 -0.545276 -0.445431 -0.710117 -0.0842416 -0.180907 -0.979886 -0.102631 -0.169831 -0.980114 -0.116305 -0.157746 -0.980607 -0.106621 -0.13469 -0.985135 -0.221491 -0.178755 -0.958639 -0.238554 -0.14947 -0.959558 -0.00456668 -0.053729 -0.998545 0.0163985 -0.0455939 -0.998825 -0.0897759 -0.156674 -0.983562 -0.312665 -0.501475 -0.806699 -0.298167 -0.486361 -0.821309 -0.557127 -0.0870692 -0.82585 -0.516986 -0.0889602 -0.851359 -0.478665 -0.239937 -0.844577 -0.448912 -0.232845 -0.862706 -0.379205 -0.350903 -0.856196 -0.563014 -0.461692 -0.68546 -0.389635 -0.435754 -0.811359 0.609984 0.044695 -0.791152 0.720799 0.178055 -0.669885 0.258774 0.0199106 -0.965733 0.246474 0.0229541 -0.968877 0.240984 0.0580919 -0.968789 0.793058 0.0643191 -0.605742 0.974166 0.139677 -0.177456 0.407917 0.0720404 -0.910173 0.548344 0.130501 -0.826007 0.228977 0.0589151 -0.971647 -0.781411 -0.00143852 -0.624016 -0.782216 -0.00157478 -0.623005 -0.555366 -0.00411112 -0.831596 -0.558673 -0.00456095 -0.829375 -0.269902 -0.00640502 -0.962867 -0.276498 -0.00719894 -0.960988 0.0347942 -0.00801782 -0.999362 0.0252466 -0.0091025 -0.99964 0.0310643 0.0633499 -0.997508 0.0846176 0.522406 -0.848488 0.0850772 0.516323 -0.852157 0.0306605 0.077811 -0.996497 0.0889945 0.0621634 -0.99409 0.0997076 0.101243 -0.989853 0.137417 0.0770398 -0.987513 0.164449 0.116739 -0.979453 0.534696 0.300639 -0.789758 0.466432 0.390148 -0.793868 0.518078 0.51016 -0.686537 0.378982 0.423887 -0.822613 0.267983 0.493215 -0.827601 0.331695 0.589369 -0.736629 0.192291 0.495546 -0.847029 0.188339 0.0857897 -0.97835 0.213731 0.104485 -0.971289 0.650091 0.329201 -0.684842 0.554827 0.108527 -0.824857 0.695074 0.258631 -0.670807 -0.780626 -0.00147705 -0.624996 -0.781411 -0.0016117 -0.624014 -0.552109 -0.0042017 -0.833761 -0.555368 -0.0046513 -0.831591 -0.263257 -0.0065296 -0.964704 -0.269907 -0.00734206 -0.962859 0.0444014 -0.0081601 -0.99898 0.034788 -0.00927073 -0.999352 -0.224214 0.490584 -0.842054 -0.173377 0.543954 -0.821009 -0.0195393 0.0633684 -0.997799 -0.0215558 0.0694778 -0.997351 -0.0677154 0.0802396 -0.994473 -0.0583238 0.0631413 -0.996299 -0.174967 0.498834 -0.848853 -0.0569282 0.519388 -0.85264 -0.0561802 0.517384 -0.853908 -0.778334 0.0693519 -0.624008 -0.697075 0.19229 -0.690732 -0.948661 0.138533 -0.284342 -0.332076 0.0803547 -0.939824 -0.511818 0.154201 -0.845142 -0.235647 0.0850509 -0.96811 -0.293156 0.111814 -0.949504 0.0417458 0.0192821 -0.998942 0.00558027 0.0334013 -0.999426 -0.551157 0.046553 -0.833102 -0.26291 0.0298729 -0.964358 -0.244739 0.0251515 -0.969263 0.0444582 0.00465644 -0.999 0.0682513 -0.00132119 -0.997667 -0.433661 0.224072 -0.872771 -0.275416 0.167622 -0.946599 -0.184148 0.157979 -0.97012 -0.0815756 0.074898 -0.993849 -0.165697 0.178241 -0.969935 -0.0888818 0.0832376 -0.992558 -0.0969705 0.0762987 -0.992358 -0.00594535 -0.00536635 -0.999968 0.0134274 0.0150559 -0.999797 0.0221909 0.010161 -0.999702 -0.24587 0.482212 -0.840845 -0.468388 0.361142 -0.806343 0.0086575 0.0431128 -0.999033 0.0376725 0.0357846 -0.998649 -0.205896 0.129574 -0.969957 -0.187804 0.161418 -0.968852 -0.389156 0.302587 -0.870057 -0.578956 0.389976 -0.71605 -0.616326 0.323305 -0.718064 -0.61361 0.321081 -0.72138 -0.537395 0.0558488 -0.841479 -0.674261 0.268087 -0.688115 -0.301357 0.501127 -0.811206 -0.298072 0.470437 -0.830568 -0.375302 0.417103 -0.827752 -0.397946 0.46811 -0.788994 -0.412827 0.397661 -0.819414 0.959883 0.074197 0.270405 0.953677 0.0955143 0.285266 0.652406 -0.141811 0.744484 0.963095 0.0814753 0.256536 0.803123 -0.00985286 0.595732 0.788392 -0.0179734 0.614911 0.412781 -0.126799 0.901961 0.610589 -0.0560486 0.789962 0.699652 0.0076873 0.714442 0.956299 0.0601574 0.286134 0.944874 0.053292 0.323068 0.956465 0.0473307 0.287983 0.957671 0.021109 0.287089 0.957119 0.0211366 0.288921 0.95408 0.0846516 0.287343 0.954948 0.0846982 0.284432 0.782318 0.045458 0.621219 0.700108 0.00768283 0.713995 0.699437 0.0202463 0.714407 0.700025 0.0202502 0.713831 0.699526 0.0260619 0.714132 0.603145 0.0152999 0.797485 0.991394 -0.0425853 0.123789 0.994761 -0.0055914 0.102073 0.991709 -0.00114625 0.128503 0.984734 -0.0315279 0.171186 0.9882 -0.00500617 0.153087 0.982414 5.55277e-05 0.186714 0.98238 -0.000113846 0.186894 0.977872 0.0147014 0.208689 0.974435 0.00451291 0.224623 0.973661 0.0331567 0.225577 0.965571 0.0220685 0.259201 0.963845 0.0500086 0.261729 0.968453 0.050028 0.244122 0.821477 -0.117566 0.557992 0.659222 -0.185399 0.728734 0.995991 -0.0382437 0.0808637 0.996817 -0.021965 0.0766362 0.915271 -0.396588 0.0706936 0.758644 -0.165189 0.630216 0.774385 -0.251559 0.580557 0.781251 -0.248183 0.572758 0.797515 -0.324319 0.508711 0.801746 -0.321208 0.504012 0.817495 -0.384505 0.428788 0.819356 -0.382693 0.426851 0.833984 -0.432092 0.343174 0.83389 -0.432203 0.343261 0.846937 -0.467889 0.252542 0.845528 -0.469829 0.25366 0.856607 -0.491166 0.158054 0.853983 -0.495187 0.159696 0.862996 -0.502691 0.0503953 0.785417 -0.615793 0.0626013 0.699652 -0.00766377 0.714442 0.957669 -0.0211791 0.287092 0.957121 -0.0210662 0.288922 0.603143 -0.0152996 0.797486 0.700107 -0.00770625 0.713996 0.699441 -0.0201858 0.714405 0.70002 -0.0203104 0.713834 0.699526 -0.0260625 0.714132 0.782322 -0.0454606 0.621213 0.956465 -0.0473307 0.287983 0.944874 -0.053292 0.323068 0.956299 -0.0601574 0.286134 0.954102 -0.0844349 0.287333 0.9549 -0.0849122 0.284528 0.920507 -0.389118 -0.0354222 0.792117 -0.608645 -0.0458492 0.998132 0.0601889 0.0104402 0.997388 0.0665256 0.028147 0.997699 0.0656522 0.0169005 0.99672 0.0763796 0.0267442 0.998678 -0.00984829 -0.0504503 0.999787 -0.0203335 0.00361714 0.999007 -0.0196146 0.0400125 0.998561 0.0140761 0.051745 0.999465 -0.0257697 0.0201265 0.99889 -0.00682421 -0.0466015 0.974609 -0.0535769 -0.21741 0.977362 -0.0815483 -0.195225 0.974146 -0.0876726 -0.208213 0.972418 -0.0561117 -0.226393 0.968854 -0.06009 -0.240231 0.784227 -0.603845 -0.14269 0.688192 -0.277643 -0.670303 0.625374 -0.290168 -0.724369 0.782907 -0.321246 -0.532783 0.729677 -0.347336 -0.589007 0.735459 -0.441523 -0.513962 0.367394 -0.672136 -0.642849 0.764709 -0.491388 -0.416843 0.7662 -0.562565 -0.310578 0.496881 -0.855706 -0.144486 0.913742 -0.404569 -0.0374164 0.916473 -0.358053 -0.178535 0.999987 0.00446085 0.00256224 0.999111 -0.0307112 -0.0288863 0.86125 -0.177066 -0.476336 0.872106 -0.172089 -0.458057 0.875713 -0.237797 -0.420214 0.88527 -0.230386 -0.404004 0.888058 -0.316906 -0.333052 0.903118 -0.296349 -0.310733 0.905781 -0.380103 -0.187304 0.509944 -0.770052 -0.383375 0.785762 -0.583123 -0.206266 0.730471 0.0597653 0.680324 0.961561 -0.0620756 0.267483 0.605284 0.00240926 0.796006 0.507031 0.0725189 0.858871 0.788259 0.0160324 0.615134 0.964258 -0.0828602 0.251677 0.955096 -0.0831497 0.284389 0.682007 -0.166715 -0.71209 0.826325 -0.00463796 -0.563175 0.837976 0.00205769 -0.545703 0.955907 0.0434192 -0.290444 0.958903 0.0468745 -0.279837 0.996247 0.0864989 0.00301479 0.996201 0.0869621 0.00463594 0.997723 0.0669886 0.00785582 0.997688 0.0673933 0.00874271 0.965982 -0.0121018 -0.258327 0.963675 -0.0161423 -0.266589 0.856218 -0.0914653 -0.508454 0.8457 -0.0999302 -0.524218 0.658709 -0.168808 -0.733216 0.648872 -0.0419774 -0.759739 0.625282 -0.0510684 -0.778726 0.964695 -0.0415837 0.260067 0.964649 -0.0414128 0.260264 0.972523 -0.028015 0.231116 0.970406 -0.0141788 0.241064 0.978752 -0.0183325 0.204228 0.97666 0.008471 0.214624 0.983857 -0.0108299 0.178631 0.981404 0.058077 0.182955 0.987004 -0.0143468 0.160053 0.989704 0.0360217 0.13852 0.990664 0.0112011 0.135863 0.994387 0.0197566 0.10394 0.994129 0.035671 0.102152 0.997126 0.0232789 0.072095 0.996995 0.0114165 0.0766247 0.914663 0.39801 0.0705668 0.788662 0.614237 0.0269265 0.861433 0.503212 0.0686333 0.853406 0.496718 0.15802 0.855761 0.492343 0.158968 0.844952 0.471638 0.252216 0.846236 0.469238 0.252388 0.833325 0.434135 0.342195 0.833411 0.433977 0.342183 0.818717 0.384604 0.426359 0.817189 0.387196 0.426944 0.801088 0.322884 0.503988 0.79751 0.328332 0.506139 0.780554 0.249516 0.573129 0.774626 0.257234 0.577742 0.757427 0.164103 0.631962 0.748772 0.173288 0.639775 0.999775 0.0179439 0.011328 0.999744 0.0180216 0.0136899 0.957497 0.0141061 -0.288098 0.957982 0.0141718 -0.286477 0.823697 0.00884886 -0.566961 0.824278 0.00889234 -0.566115 0.619588 0.0029657 -0.784922 0.619822 0.00297839 -0.784737 0.997982 0.0633495 0.00429436 0.997915 0.0637057 0.0103463 0.955465 0.0498884 -0.290856 0.956068 0.0500505 -0.288839 0.823883 0.0315222 -0.565883 0.822831 0.0313554 -0.567421 0.62076 0.0107015 -0.783927 0.619305 0.0105258 -0.78508 0.995393 -0.0882915 0.0373864 0.998776 0.0215099 0.0445314 0.999046 -0.000444945 0.0436611 0.999521 0.025064 0.0181732 0.999812 0.019373 0.000895528 0.995348 -0.0895353 0.0355661 0.995611 -0.0867135 0.0352003 0.996178 -0.0822041 0.0295402 0.99694 -0.0742579 0.0244095 0.996813 -0.0750877 0.0269519 0.998857 -0.0474527 0.00574508 0.985701 0.15073 -0.0753302 0.985127 0.115298 -0.127399 0.994326 0.0535479 -0.0919171 0.978736 0.108712 -0.173945 0.977076 0.0788493 -0.197749 0.997757 -0.0649978 0.0160006 0.552658 0.596084 -0.582455 0.860039 0.22298 -0.458925 0.688107 0.276128 -0.671015 0.861285 0.179271 -0.475447 0.734337 0.415275 -0.536931 0.729995 0.353864 -0.584711 0.875297 0.238658 -0.420591 0.871462 0.168112 -0.460751 0.968933 0.0617212 -0.2395 0.791598 0.610489 -0.0260052 0.485359 0.861994 -0.146263 0.78301 0.60983 -0.122486 0.785182 0.571454 -0.238599 0.440152 0.803239 -0.401338 0.766825 0.543698 -0.341134 0.762191 0.471823 -0.443225 0.998164 -0.0596354 0.0105782 0.997896 -0.0620478 0.0187893 0.972111 0.0537901 -0.228269 0.974017 0.0888552 -0.208318 0.88463 0.225901 -0.407921 0.887708 0.316143 -0.334705 0.902918 0.295473 -0.312144 0.905734 0.379031 -0.189689 0.916548 0.358555 -0.177139 0.913841 0.404239 -0.0385379 0.9199 0.39064 -0.034427 0.621713 -0.00302759 -0.783239 0.619822 -0.00303258 -0.784737 0.826311 -0.0088933 -0.563144 0.824278 -0.00891232 -0.566115 0.958302 -0.0141441 -0.285406 0.957983 -0.0141538 -0.286477 0.999764 -0.0179865 0.0122118 0.999745 -0.0179682 0.01369 0.620764 -0.0106606 -0.783925 0.621426 -0.0107029 -0.7834 0.823881 -0.0315429 -0.565884 0.825435 -0.0316605 -0.563609 0.955459 -0.049981 -0.290862 0.956873 -0.0501297 -0.286148 0.997972 -0.0635045 0.0042858 0.997912 -0.0636032 0.0112333 0.997725 -0.0669607 0.00780085 0.64952 0.0469878 -0.758892 0.625011 0.046159 -0.77925 0.838356 0.00152852 -0.545122 0.826136 0.00112947 -0.56347 0.959098 -0.045035 -0.27947 0.955788 -0.0452184 -0.29056 0.682003 0.166729 -0.712091 0.658762 0.168818 -0.733166 0.856533 0.0946317 -0.507343 0.845556 0.0968429 -0.52503 0.966127 0.0134779 -0.257714 0.963611 0.0147328 -0.266901 0.997685 -0.0674354 0.00884096 0.996221 -0.0867199 0.00479353 0.996225 -0.0867559 0.00300053 0.0100499 0.551172 0.834331 0.415598 0.52692 0.741373 -0.937412 0.313086 0.15243 -0.913155 0.403361 -0.0587179 0.0739623 0.769564 0.634272 0.527018 0.610341 0.591384 0.516872 0.533575 0.669433 0.280011 0.495889 0.822003 0.399059 0.446194 0.801039 0.506847 0.411105 0.757693 -0.929386 0.35198 0.111141 -0.951962 0.303196 0.0428982 -0.714695 0.627845 0.308256 -0.70813 0.63273 0.313377 -0.483463 0.757498 0.438702 -0.476408 0.759948 0.44217 -0.205187 0.821494 0.53202 -0.198458 0.8219 0.533943 0.621956 0.588928 0.516076 0.100335 0.849811 0.51745 0.23285 0.820658 0.521825 0.363169 0.766445 0.529784 0.577199 0.642222 0.504372 0.601257 0.712086 0.362525 0.533792 0.843943 0.0531626 -0.664813 0.746898 -0.0129009 -0.661955 0.749443 -0.0122709 -0.421547 0.906708 0.0133653 -0.391344 0.920067 0.0180439 -0.137934 0.989458 0.0441236 -0.187314 0.981616 0.0366544 0.15075 0.985975 0.0716136 0.130766 0.989031 0.0686849 0.411297 0.907485 0.0854722 0.824497 0.55275 0.121129 0.618003 0.768482 0.165854 -0.950726 0.309948 -0.00722019 -0.905058 0.425289 -0.000381246 -0.899026 0.434705 -0.0527555 -0.949318 0.265269 0.168608 -0.961549 0.2577 0.0949395 -0.753022 0.48923 0.440014 -0.743561 0.494437 0.450166 -0.534053 0.582491 0.612774 -0.520757 0.585527 0.621265 -0.264426 0.625633 0.733936 -0.247903 0.625736 0.739594 0.599065 0.420996 0.68109 0.0518493 0.669161 0.741306 0.42934 0.561729 0.707197 0.445466 0.632695 0.633448 -0.918921 0.385867 0.0818009 -0.909444 0.41523 0.0222539 -0.683685 0.714215 0.149906 -0.681525 0.716057 0.150954 -0.444669 0.865503 0.230597 -0.444078 0.865754 0.230794 -0.162057 0.942522 0.292214 -0.163854 0.942335 0.291816 0.127731 0.93631 0.327122 0.123553 0.937053 0.326598 0.390171 0.857816 0.334543 0.384516 0.860433 0.334369 0.884201 0.397521 0.245288 0.608951 0.752741 0.25012 0.145938 0.928262 -0.3421 -0.898127 0.416058 -0.142348 -0.902183 0.379861 -0.204379 -0.888721 0.351987 -0.293733 0.528699 0.802756 -0.275791 0.73161 0.67719 -0.07849 0.544242 0.829126 -0.127868 0.563545 0.531122 -0.632713 0.56538 0.58976 -0.576653 0.848915 0.408149 -0.335795 0.231928 0.798825 -0.555057 0.619857 0.685059 -0.382715 0.313331 0.562958 -0.764789 0.0869841 0.592818 -0.800625 0.0597098 0.59559 -0.801067 -0.192025 0.589678 -0.784478 -0.196214 0.589463 -0.783603 -0.46166 0.538303 -0.705053 -0.533203 0.518988 -0.668092 -0.689935 0.44391 -0.571781 -0.748585 0.410276 -0.52086 -0.971464 0.14194 -0.19003 -0.87861 0.30237 -0.369616 -0.932859 0.227148 -0.279602 -0.977583 0.14464 -0.153006 -0.93577 0.338158 -0.099916 0.0924384 0.775545 -0.624488 0.123351 0.773883 -0.6212 -0.186566 0.767316 -0.61353 -0.159463 0.7719 -0.61542 -0.456806 0.696937 -0.552817 -0.435527 0.70596 -0.558513 -0.686246 0.572171 -0.449096 -0.671432 0.583464 -0.45689 -0.934858 0.283116 -0.214208 -0.902352 0.361882 -0.234098 0.500501 0.779264 -0.377155 0.497938 0.820758 -0.280026 0.405377 0.860378 -0.308901 0.397923 0.906141 -0.143407 0.139585 0.974912 -0.173386 0.1471 0.974001 -0.172289 -0.146084 0.972216 -0.182908 -0.172603 0.967535 -0.184616 -0.425679 0.886122 -0.183263 -0.378365 0.907658 -0.181653 -0.665064 0.72731 -0.169441 -0.651716 0.739248 -0.16964 -0.909341 0.399526 -0.116091 0.535214 0.45927 -0.708955 0.811722 0.335559 -0.478025 0.344566 0.554476 -0.757516 0.349457 0.727763 -0.59012 0.38121 0.719029 -0.581099 0.38336 0.819709 -0.425574 0.124123 0.878972 -0.460436 0.610671 0.728359 -0.310764 -0.159525 0.900491 -0.404559 -0.138334 0.904085 -0.404344 -0.4357 0.819158 -0.373022 -0.418656 0.8271 -0.375009 -0.67167 0.672168 -0.311527 -0.659477 0.682577 -0.314926 -0.931737 0.325034 -0.161925 -0.897046 0.406965 -0.1723 -0.950942 0.255959 0.173766 -0.951694 0.253098 0.173842 -0.956997 0.222819 0.185763 -0.960658 0.219433 0.170253 -0.780556 0.339127 0.525096 -0.785846 0.336643 0.518766 -0.569349 0.388914 0.724284 -0.57934 0.386637 0.71755 -0.303398 0.404956 0.862531 -0.318602 0.403865 0.857547 -0.0172587 0.385445 0.922569 -0.0367426 0.38642 0.921591 0.253081 0.336967 0.906865 0.231384 0.340432 0.911355 0.482287 0.270787 0.833111 0.460823 0.276597 0.843289 -0.966456 0.164112 0.197563 -0.96537 0.164254 0.202686 -0.810814 0.205712 0.547962 -0.804834 0.205744 0.556697 -0.615929 0.217055 0.75731 -0.604102 0.216118 0.767042 -0.365882 0.210386 0.906569 -0.347033 0.207841 0.914533 -0.0912705 0.186608 0.978186 -0.0662989 0.182102 0.981042 0.174448 0.150327 0.973124 0.203042 0.143944 0.968532 0.406463 0.107672 0.907301 0.435405 0.0999067 0.894674 -0.00468784 0.224637 -0.974431 0.00304207 0.336189 -0.94179 -0.972277 0.132291 -0.192815 -0.910273 0.203098 -0.360769 -0.892158 0.213903 -0.397868 -0.716631 0.300807 -0.62925 -0.773822 0.283438 -0.566447 -0.507557 0.347808 -0.788299 -0.576491 0.341266 -0.742425 -0.256602 0.386104 -0.886047 -0.252629 0.386109 -0.887186 0.468373 0.325159 -0.821522 0.0153613 0.44444 -0.895677 0.272326 0.416436 -0.867421 0.510115 0.364579 -0.779015 0.388201 0.407727 -0.826474 0.381987 0.287959 -0.87816 0.355866 0.298009 -0.885748 0.3546 0.181896 -0.917155 0.329632 0.190822 -0.924624 0.32026 0.0777161 -0.944137 -0.928368 0.134614 -0.346428 -0.922738 0.137932 -0.359901 -0.725233 0.174867 -0.665927 -0.732592 0.173516 -0.658181 -0.518245 0.187257 -0.83448 -0.533305 0.185797 -0.825267 -0.270493 0.185936 -0.944596 -0.296272 0.185033 -0.937009 0.448105 0.120404 -0.885836 -0.047869 0.117635 -0.991903 0.301373 0.0838718 -0.94981 0.272944 0.00718913 0.962003 0.272705 0.00720092 0.962071 -0.111581 0.017438 0.993602 -0.112246 0.0174611 0.993527 -0.389558 0.0234394 0.920704 -0.390575 0.0234715 0.920272 -0.639978 0.0275654 0.767899 -0.641085 0.0275964 0.766974 -0.831964 0.0293063 0.554055 -0.833075 0.0293317 0.552383 -0.979827 0.0278261 0.197902 -0.980282 0.027848 0.195631 0.273844 0.018845 0.961589 0.273558 0.0188787 0.96167 -0.109258 0.0457122 0.992962 -0.110117 0.0457849 0.992864 -0.386425 0.0614613 0.920271 -0.387652 0.0615536 0.919748 -0.636363 0.0723068 0.767993 -0.637826 0.0724007 0.76677 -0.828433 0.0769215 0.554781 -0.82975 0.0769847 0.5528 -0.977152 0.0731189 0.19957 -0.977751 0.0731586 0.196596 -0.973925 0.111153 0.197773 -0.973191 0.111151 0.201358 -0.825047 0.116844 0.552852 -0.823368 0.116755 0.555368 -0.633202 0.109826 0.766155 -0.631381 0.109676 0.767678 -0.383763 0.0933462 0.918701 -0.38215 0.0931821 0.91939 -0.107297 0.0694231 0.9918 -0.106251 0.0693003 0.991921 0.274647 0.028625 0.961119 0.162491 0.0459213 0.985641 0.39664 0.0136064 0.917873 -0.927614 0.046959 -0.370578 0.295452 0.0157575 -0.955228 0.296222 0.0157158 -0.95499 0.296092 0.00448625 -0.955149 0.29581 0.00448688 -0.955236 -0.180386 0.0131503 -0.983508 -0.928391 0.0200485 -0.371063 -0.927488 0.0200992 -0.373313 -0.645338 0.0190598 -0.76366 -0.0554055 0.0388995 -0.997706 -0.180085 0.0473682 -0.98251 -0.181352 0.0131454 -0.98333 -0.643973 0.0190839 -0.76481 -0.310404 0.0528476 -0.949135 -0.546802 0.0633837 -0.834859 -0.643423 0.0680797 -0.762478 -0.743654 0.0694142 -0.664951 -0.994258 0.0643958 -0.0854698 -0.928471 0.0776115 -0.363205 -0.979495 -0.0278861 0.199527 -0.980284 -0.0277727 0.195632 -0.829575 -0.0293382 0.557624 -0.833076 -0.0292798 0.552383 -0.635184 -0.0275485 0.771869 -0.641086 -0.027537 0.766975 -0.382278 -0.0233527 0.923752 -0.390575 -0.023407 0.920273 -0.102373 -0.0172745 0.994596 -0.112247 -0.0173979 0.993528 0.277638 -0.00714761 0.960659 0.272705 -0.00719673 0.962071 -0.976797 -0.0732689 0.201245 -0.977428 -0.0730757 0.198227 -0.826021 -0.0769434 0.558362 -0.827366 -0.0769033 0.556374 -0.631624 -0.072178 0.771908 -0.63304 -0.0721856 0.770746 -0.379047 -0.0611128 0.923357 -0.380387 -0.0611478 0.922804 -0.100091 -0.0451512 0.993953 -0.10093 -0.0451855 0.993867 0.278472 -0.0184936 0.960266 0.278244 -0.0185025 0.960332 -0.972839 -0.111355 0.202937 -0.973597 -0.111086 0.19942 -0.820934 -0.116792 0.558952 -0.82266 -0.11675 0.556417 -0.626643 -0.109482 0.771578 -0.628486 -0.109526 0.770071 -0.37494 -0.0926678 0.922406 -0.376406 -0.0927452 0.921801 -0.0971087 -0.068453 0.992917 -0.0981496 -0.0685298 0.992809 0.279721 -0.0280224 0.959672 0.279264 -0.0280591 0.959804 -0.181338 -0.013165 -0.983333 0.296092 -0.00448076 -0.955149 0.295795 -0.00449241 -0.955241 0.296205 -0.015703 -0.954995 0.295454 -0.0157716 -0.955227 -0.643973 -0.0190473 -0.764811 -0.927614 -0.0469529 -0.370578 -0.928391 -0.0200924 -0.371062 -0.927489 -0.0200552 -0.373313 -0.180386 -0.0131302 -0.983508 -0.645337 -0.0190963 -0.763659 -0.643499 -0.0666819 -0.762537 -0.994263 -0.0643939 -0.0854057 -0.928471 -0.0776128 -0.363205 -0.74346 -0.0722711 -0.664864 -0.546802 -0.0633837 -0.834859 -0.180126 -0.0459927 -0.982568 -0.310168 -0.0555884 -0.949055 -0.0554058 -0.0388998 -0.997706 0.290192 -0.122799 0.949057 -0.957237 -0.221525 0.186076 -0.956143 -0.222492 0.190496 -0.782191 -0.330496 0.528158 -0.787489 -0.328064 0.521762 -0.571801 -0.377677 0.728288 -0.581792 -0.375446 0.721497 -0.306506 -0.39215 0.867337 -0.321532 -0.391076 0.862367 -0.0206984 -0.372281 0.927889 -0.039889 -0.373176 0.926903 0.249581 -0.324537 0.912351 0.228283 -0.327786 0.916757 0.478875 -0.259913 0.838525 -0.96562 -0.163277 0.202285 -0.966382 -0.162454 0.199284 -0.805551 -0.203127 0.556622 -0.808991 -0.202323 0.551905 -0.605322 -0.212878 0.766986 -0.612032 -0.212196 0.761833 -0.348496 -0.204362 0.91476 -0.359623 -0.204126 0.910496 -0.0678312 -0.178709 0.981561 -0.0830414 -0.179288 0.980286 0.201567 -0.140892 0.969289 0.437254 -0.11474 0.891989 0.458076 -0.265305 0.848398 -0.0478707 -0.117635 -0.991902 -0.905911 -0.154923 -0.394113 -0.947696 -0.179027 -0.264238 0.0464138 -0.443422 -0.895111 0.409369 -0.394783 -0.822535 0.387848 -0.395107 -0.832745 -0.255974 -0.392214 -0.883542 -0.50651 -0.356745 -0.784972 -0.437695 -0.373942 -0.817674 -0.716236 -0.30404 -0.628145 -0.753204 -0.286673 -0.592032 -0.933829 -0.186993 -0.304955 -0.94965 -0.166284 -0.265547 -0.949919 -0.164777 -0.265522 -0.188729 -0.392893 -0.900009 0.49701 -0.321569 -0.805962 0.00304207 -0.336189 -0.94179 0.382391 -0.293245 -0.876233 0.301065 -0.0798813 -0.950252 0.320648 -0.0815719 -0.94368 0.329286 -0.185516 -0.925826 0.355923 -0.292569 -0.887537 0.354766 -0.187163 -0.91603 -0.00468778 -0.224637 -0.974431 0.448105 -0.120404 -0.885836 -0.27055 -0.184473 -0.944867 -0.296073 -0.186582 -0.936765 -0.518266 -0.186257 -0.834691 -0.533157 -0.186812 -0.825133 -0.725241 -0.174309 -0.666064 -0.732505 -0.174108 -0.658121 -0.938675 -0.132055 -0.318514 -0.925416 -0.114099 -0.361368 0.514916 -0.486039 0.706136 0.131251 -0.955167 0.265387 0.537164 -0.798255 0.272476 -0.929913 -0.349966 0.113072 -0.946092 -0.28208 0.159185 -0.962297 -0.271916 0.00684925 -0.934179 -0.356788 -0.00346259 0.347335 -0.936199 0.0537531 0.535818 -0.843675 0.0333612 0.135407 -0.990732 0.0107374 -0.89104 -0.452427 -0.0368576 -0.917884 -0.396483 0.0170417 -0.681933 -0.714776 0.155123 -0.684344 -0.712653 0.15427 -0.444559 -0.864003 0.23636 -0.445326 -0.863654 0.236191 -0.164494 -0.940194 0.298289 -0.162866 -0.940417 0.29848 0.660084 -0.681214 0.316603 0.118196 -0.909195 0.399241 0.433969 -0.80693 0.400669 0.382034 -0.827581 0.41129 0.235021 -0.875571 0.422068 -0.935081 -0.326818 0.137165 -0.964348 -0.248985 0.0896638 -0.745562 -0.485971 0.456036 -0.754907 -0.479926 0.446974 -0.523167 -0.574857 0.629155 -0.536725 -0.570561 0.6216 -0.250689 -0.613732 0.748658 -0.267766 -0.612164 0.744014 0.0368644 -0.59845 0.800312 0.0174946 -0.600235 0.799632 0.304307 -0.53744 0.786483 0.284367 -0.542735 0.7903 0.820034 -0.240057 0.519535 0.499941 -0.373964 0.78116 -0.912139 -0.402142 -0.0792751 -0.934815 -0.349359 -0.0637873 -0.661959 -0.749457 -0.0111105 -0.664851 -0.746891 -0.011268 -0.391376 -0.920052 0.0181429 -0.421672 -0.9066 0.0164316 -0.187494 -0.981394 0.0413713 -0.137692 -0.989484 0.0442951 0.583589 -0.804902 0.107503 0.145396 -0.98047 0.132432 0.577421 -0.801948 0.153178 0.357919 -0.903846 0.234429 -0.914814 -0.400192 0.0544162 -0.921226 -0.375271 0.102538 -0.709284 -0.628543 0.319138 -0.716312 -0.622877 0.314517 -0.477744 -0.754573 0.449868 -0.48534 -0.751477 0.446908 -0.200062 -0.815696 0.542786 -0.20736 -0.814814 0.541369 0.0882151 -0.805011 0.586665 0.0818672 -0.805796 0.586507 0.352509 -0.732493 0.582402 0.347302 -0.734384 0.583148 0.813901 -0.395706 0.425419 0.585307 -0.592306 0.553705 -0.896765 -0.40683 -0.174072 0.0505117 -0.552747 -0.831817 -0.901405 -0.35134 -0.25304 0.0948562 -0.746522 -0.658564 0.492276 -0.650239 -0.578665 0.412874 -0.493626 -0.765421 0.43451 -0.491495 -0.754741 0.437746 -0.590412 -0.67808 -0.890795 -0.30946 -0.332745 -0.922617 -0.310393 -0.228985 -0.684974 -0.581153 -0.4394 -0.670652 -0.590908 -0.44839 -0.454815 -0.707992 -0.540268 -0.434317 -0.715168 -0.547634 -0.183926 -0.779424 -0.59889 -0.158021 -0.781962 -0.602964 0.576374 -0.645131 -0.501597 0.125738 -0.821054 -0.556831 0.452098 -0.738384 -0.500397 0.385261 -0.77123 -0.506733 0.597602 -0.65979 -0.455576 0.596934 -0.724868 -0.343856 -0.898324 -0.422321 -0.121078 -0.909432 -0.399603 -0.115113 -0.665024 -0.728122 -0.166078 -0.651829 -0.739386 -0.168604 -0.425589 -0.88714 -0.178484 -0.378369 -0.907614 -0.18186 -0.145825 -0.972609 -0.181015 -0.172971 -0.968329 -0.180055 0.139938 -0.975514 -0.169673 0.146947 -0.97449 -0.169635 0.398462 -0.906397 -0.140259 0.54423 -0.829552 -0.125127 0.609769 -0.784951 -0.109694 -0.94716 -0.193097 -0.256129 -0.960988 -0.180634 -0.209461 -0.74684 -0.425448 -0.511101 -0.688301 -0.457319 -0.563118 -0.429736 -0.559487 -0.708732 -0.459165 -0.552986 -0.695251 -0.180475 -0.60259 -0.777377 -0.188916 -0.602154 -0.775707 0.564895 -0.4945 -0.660578 0.0922336 -0.655811 -0.749269 0.418995 -0.593854 -0.686863 0.489527 -0.650973 -0.580171 -0.902018 -0.379883 -0.205064 -0.930382 -0.329362 -0.160968 -0.671144 -0.67584 -0.304642 -0.659422 -0.685171 -0.309359 -0.434819 -0.823632 -0.364091 -0.418531 -0.830397 -0.367794 -0.158466 -0.905271 -0.394175 -0.138054 -0.907766 -0.396109 0.124698 -0.911648 -0.391598 0.147515 -0.90845 -0.391098 0.382585 -0.850724 -0.360413 0.405678 -0.841325 -0.357209 0.859084 -0.476311 -0.187356 0.616716 -0.750371 -0.237919 0.994525 0 0.104498 0.95105 0 -0.309037 0.95105 0 -0.309037 0.806985 0.00100137 0.590571 0.912142 0 0.409874 0.994525 0 0.104498 0.866038 0 0.499978 0.587799 0 0.809007 0.587799 0 0.809007 0.207879 0 0.978154 0.207879 0 0.978154 0.948318 -0.0757398 -0.30815 0.207863 -0.0125093 0.978078 0.240076 -0.0201093 0.970546 0.233791 -0.0582331 0.970541 0.237946 -0.0599834 0.969425 0.2239 -0.100442 0.969423 0.227255 -0.102631 0.968412 0.208013 -0.143125 0.967598 0.205655 -0.140889 0.96843 0.506248 -0.348712 0.788742 0.680625 -0.469073 0.562779 0.705029 -0.483162 -0.519123 0.687521 -0.474907 -0.549344 0.790683 -0.542052 -0.284607 0.780952 -0.539141 -0.315342 0.824696 -0.565565 -0.00364929 0.822697 -0.567634 -0.031019 0.787493 -0.540264 0.296598 0.791274 -0.545637 0.27598 0.799425 -0.35887 -0.481801 0.778203 -0.353481 -0.519087 0.883904 -0.396999 -0.247196 0.872949 -0.396198 -0.284583 0.911744 -0.409721 0.0291835 0.910728 -0.41299 -0.00365373 0.863751 -0.388375 0.321091 0.869892 -0.394124 0.296571 0.918016 -0.23261 0.321152 0.909567 -0.227466 0.347774 0.968872 -0.245838 0.0291813 0.968125 -0.241856 0.0651182 0.939116 -0.238597 -0.247248 0.949352 -0.236976 -0.206333 0.849183 -0.216044 -0.481885 0.5007 -0.343821 0.79441 0.553446 -0.250359 0.794367 0.545671 -0.245683 0.801176 0.580106 -0.146633 0.801234 0.570451 -0.142986 0.80879 0.585482 -0.0526075 0.808976 0.586975 -0.0529342 0.807873 0.674389 -0.46288 0.575275 0.745195 -0.337362 0.575214 0.736152 -0.331211 0.590237 0.782505 -0.198013 0.590319 0.771268 -0.193096 0.606514 0.792511 -0.0640099 0.606489 0.932411 -0.0966325 0.348242 0.864276 -0.0637677 0.49896 0.993821 -0.0898561 0.065159 0.990942 -0.0848089 0.104122 0.975142 -0.0807585 -0.206341 0.892683 -0.0921647 -0.441161 0.870994 -0.217269 -0.44064 0.537374 -0.612826 -0.579373 0.0773211 -0.846759 -0.526327 0.0935743 -0.715798 -0.692009 0.152611 -0.775187 -0.613021 0.247909 -0.752938 -0.60961 0.208804 -0.656982 -0.724414 0.192028 -0.64033 0.743708 0.189316 -0.627914 0.754907 0.254751 -0.82654 0.50193 0.253401 -0.818582 0.515472 0.293242 -0.933835 0.204844 0.293282 -0.930594 0.219045 0.30218 -0.947473 -0.1048 0.303442 -0.948474 -0.0912182 0.184932 -0.195901 0.963028 0.175194 -0.182789 0.967417 0.439733 -0.459157 0.771887 0.42728 -0.443361 0.787948 0.583983 -0.607618 0.538297 0.574915 -0.594831 0.561826 0.672481 -0.69817 0.245616 0.668791 -0.690578 0.275356 0.69293 -0.718175 -0.0638135 0.695953 -0.717421 -0.0309481 0.651746 -0.674417 -0.346971 0.661465 -0.680758 -0.314695 0.440422 -0.457305 -0.772593 0.616538 -0.563093 -0.550279 0.0198061 -0.288691 0.957217 0.114555 -0.367886 0.922788 0.082855 -0.300618 0.950139 0.0394344 -0.309512 0.950077 0.0106709 -0.249176 0.9684 0.0670531 -0.681138 0.729078 0.0674273 -0.666004 0.742894 0.0828042 -0.886009 0.456215 0.0841025 -0.861681 0.500432 0.0958025 -0.965378 0.242625 0.0946109 -0.974648 0.202754 0.104441 -0.989794 -0.0969577 0.103466 -0.988843 -0.107161 0.0931756 -0.917294 -0.387156 0.28434 -0.87815 -0.384711 0.286509 -0.882484 -0.373008 0.112542 -0.196785 0.973966 0.130316 -0.237845 0.962521 0.326511 -0.566172 0.756862 0.319479 -0.551372 0.770664 0.432286 -0.738009 0.518143 0.427795 -0.727288 0.536696 0.496642 -0.839023 0.222231 0.495407 -0.833725 0.243876 0.510669 -0.855283 -0.0877898 0.512902 -0.855949 -0.0654425 0.479224 -0.795967 -0.369839 0.484708 -0.80229 -0.348411 0.479749 -0.793694 -0.37402 0.41449 -0.702905 -0.578033 -0.0740977 -0.278878 0.957464 -0.0740472 -0.278775 0.957498 -0.185385 -0.642574 0.743459 -0.194427 -0.688254 0.698931 -0.250431 -0.828117 0.501505 -0.274917 -0.939465 0.204515 -0.277692 -0.917045 0.28621 -0.293124 -0.951374 -0.0946918 -0.293696 -0.950099 -0.105144 -0.281619 -0.903763 -0.322339 -0.278076 -0.879993 -0.38508 -0.241949 -0.776385 -0.581969 -0.249141 -0.791986 -0.557393 -0.0298161 -0.335462 0.941582 -0.0188375 -0.288697 0.957235 -0.0632124 -0.666748 0.742598 -0.066506 -0.681163 0.729105 -0.0783913 -0.862408 0.500107 -0.0838124 -0.885934 0.456177 -0.0936624 -0.97478 0.202563 -0.0892245 -0.965971 0.242774 -0.101414 -0.989026 -0.107437 -0.100414 -0.990206 -0.0969981 -0.0899359 -0.917465 -0.387516 -0.0921743 -0.845686 -0.525661 -0.0766498 -0.767457 -0.636502 0.993612 0.095566 0.060015 0.0807664 0.845429 0.527945 0.0366135 0.380986 0.923856 0.0117887 0.124135 0.992195 0.0155405 0.259531 0.96561 0.0727366 0.248832 0.965812 0.0725057 0.248321 0.96596 0.121007 0.227926 0.96613 0.120184 0.226793 0.966499 0.163201 0.198102 0.966499 0.157825 0.193148 0.968393 0.207839 0.0197746 0.977963 0.0608269 0.635463 0.769731 0.0793893 0.840244 0.536365 0.236621 0.810293 0.53613 0.235579 0.808132 0.539838 0.394441 0.743666 0.539794 0.391643 0.739975 0.546857 0.531941 0.646484 0.546897 0.527019 0.64209 0.556751 0.0591198 0.627084 0.776705 0.176605 0.60485 0.77651 0.175827 0.602969 0.778148 0.294256 0.554919 0.778125 0.292024 0.551614 0.78131 0.396478 0.48198 0.781345 0.39247 0.47802 0.785789 0.908662 0.0872685 0.40831 0.804671 0.0756956 0.588876 0.793745 0.0734756 0.603796 0.586773 0.0590436 0.807596 0.586658 0.0590187 0.807682 0.241374 0.0191835 0.970243 0.232496 0.0664626 0.970324 0.861188 0.250195 -0.442444 0.744989 0.395391 -0.537269 0.958105 0.280067 0.0599703 0.912089 0.263939 0.313734 0.839255 0.444124 0.313695 0.717484 0.377566 0.585373 0.726619 0.384392 0.569445 0.532205 0.28022 0.798896 0.540218 0.285591 0.791582 0.222293 0.116706 0.96797 0.195322 0.157284 0.968045 0.946653 0.0960508 -0.307609 0.973008 0.0919271 -0.211671 0.938077 0.274331 -0.21155 0.960431 0.277823 0.0196622 0.883618 0.467795 0.0196674 0.84767 0.44609 0.287158 0.740736 0.607295 0.287235 0.636607 0.519954 0.569542 0.642421 0.526544 0.556819 0.473116 0.386569 0.79166 0.478397 0.391934 0.785827 0.186893 0.152359 0.970494 0.180319 0.178054 0.967358 0.0735187 0.787302 -0.612168 0.0737057 0.777043 -0.625118 0.145034 0.777861 -0.611472 0.223276 0.760635 -0.609575 0.225996 0.775832 -0.589077 0.371388 0.698315 -0.611905 0.378181 0.715261 -0.587691 0.516575 0.627719 -0.58234 0.524292 0.639429 -0.56236 0.640414 0.523052 -0.562394 0.653257 0.536046 -0.534705 0.705522 0.466146 -0.533804 0.747791 0.397292 -0.531947 0.0938806 0.991071 -0.0946855 0.0945007 0.991597 -0.0883448 0.2786 0.956339 -0.0883075 0.279529 0.956809 -0.0798785 0.466047 0.881148 -0.0798642 0.467793 0.881467 -0.0646926 0.632807 0.771603 -0.0646836 0.635034 0.771257 -0.0435279 0.773852 0.631868 -0.043537 0.844904 0.444459 -0.297647 0.738083 0.605472 -0.297719 0.731556 0.597252 -0.328811 0.598861 0.730235 -0.328819 0.5948 0.722489 -0.352453 0.437516 0.827274 -0.352416 0.435665 0.820949 -0.369106 0.259914 0.892301 -0.369112 0.259604 0.888543 -0.378283 0.0873752 0.921458 -0.378525 0.0875599 0.919728 -0.382667 0.989645 0.0989449 0.103985 0.935073 0.0861837 0.343817 0.901408 0.263318 0.343696 0.765789 0.221531 0.603731 0.77823 0.227271 0.585411 0.56669 0.164109 0.807422 0.577358 0.168435 0.798929 0.22923 0.0660018 0.971132 0.226956 0.118414 0.966679 0.0917874 0.970192 0.22428 0.092388 0.968227 0.232381 0.27212 0.933815 0.23225 0.272276 0.932181 0.238545 0.45416 0.858389 0.238551 0.4538 0.8553 0.250057 0.614124 0.748534 0.250097 0.612605 0.744196 0.266247 0.746566 0.609731 0.266211 0.773125 0.634065 -0.0154716 0.884879 0.465564 -0.0154588 0.853862 0.452201 -0.257747 0.928169 0.268426 -0.257778 0.871196 0.254386 -0.419888 0.879769 0.0811369 -0.468427 -0.144473 -0.247707 0.958003 -0.233465 -0.189937 0.953634 -0.226377 -0.184321 0.956441 -0.473075 -0.439615 0.763504 -0.504367 -0.480096 0.71772 -0.657987 -0.666651 -0.350185 -0.697336 -0.705573 -0.126054 -0.705619 -0.705284 -0.0683829 -0.692843 -0.680042 0.239818 -0.692925 -0.680262 0.238952 -0.607329 -0.622645 -0.493421 -0.559223 -0.592761 -0.579572 -0.417441 -0.700291 -0.579082 -0.427926 -0.714136 -0.553976 -0.477009 -0.807093 -0.347942 -0.483475 -0.815194 -0.318921 -0.509637 -0.857858 -0.0659529 -0.506894 -0.857159 -0.0913122 -0.495496 -0.834331 0.24161 -0.492458 -0.821057 0.288704 -0.144691 -0.247988 0.957897 -0.362319 -0.614599 0.700709 -0.335849 -0.547391 0.76653 -0.427984 -0.730311 0.532424 -0.614243 -0.58498 0.529626 -0.635766 -0.613195 0.468822 -0.081732 0.78839 -0.609722 -0.0814029 0.786819 -0.611792 -0.0953763 0.919974 -0.380198 -0.0951108 0.919089 -0.382401 -0.102679 0.990405 -0.0924935 -0.102489 0.990225 -0.0946047 -0.100448 0.968978 0.225814 -0.100341 0.969388 0.224095 -0.0875003 0.84424 0.528775 -0.0874621 0.84495 0.527646 -0.0657556 0.634608 0.770032 -0.0657569 0.635264 0.76949 -0.0394131 0.380462 0.923957 -0.0394265 0.380945 0.923757 -0.012842 0.124007 0.992198 -0.0128474 0.124134 0.992182 -0.245565 0.762338 -0.598781 -0.242261 0.754945 -0.609399 -0.284953 0.884788 -0.368717 -0.282695 0.88075 -0.379951 -0.305458 0.94865 -0.082213 -0.304379 0.948058 -0.0924125 -0.297982 0.925615 0.23333 -0.297888 0.927547 0.225652 -0.259213 0.805333 0.533148 -0.259663 0.80827 0.528464 -0.194758 0.605198 0.771884 -0.195295 0.607731 0.769755 -0.116808 0.363031 0.924426 -0.117136 0.364399 0.923847 -0.0380941 0.118382 0.992237 -0.0381973 0.118786 0.992185 -0.952544 -0.0773492 -0.29441 -0.393234 -0.168471 0.903872 -0.402749 -0.014232 0.9152 -0.716165 -0.484222 -0.502629 -0.286989 -0.121657 0.950177 -0.617586 -0.336379 0.710941 -0.604188 -0.322912 0.728481 -0.761347 -0.45595 0.460934 -0.74319 -0.435402 0.508029 -0.829592 -0.508756 0.230098 -0.828246 -0.505682 0.241444 -0.831291 -0.538698 -0.136965 -0.849079 -0.526752 -0.0399658 -0.794648 -0.52728 -0.300851 -0.789533 -0.063668 0.610397 -0.389514 -0.0252512 0.920674 -0.463994 -0.0462737 0.884629 -0.37539 -0.0555137 0.925203 -0.691411 -0.137693 0.709219 -0.772026 -0.170785 0.612216 -0.849663 -0.182152 0.494867 -0.940389 -0.213436 0.26479 -0.946852 -0.213904 0.240242 -0.972975 -0.230728 0.00919752 -0.972935 -0.22946 -0.0273088 -0.892179 -0.228363 -0.3897 -0.913882 -0.222834 -0.339358 -0.935805 -0.0840443 -0.342353 -0.996628 -0.0818344 0.00600965 -0.995351 -0.0840972 0.046955 -0.961971 -0.0775242 0.261919 -0.952225 -0.0789072 0.295028 -0.773486 -0.0579133 0.631162 -0.456085 -0.106471 0.883545 -0.339689 -0.0853136 0.936661 -0.661503 -0.23018 0.713745 -0.653605 -0.227484 0.721839 -0.809779 -0.305413 0.50098 -0.810744 -0.305733 0.499222 -0.899894 -0.35906 0.24752 -0.903739 -0.36017 0.231372 -0.922544 -0.385404 -0.0194112 -0.921785 -0.384492 -0.0497769 -0.848761 -0.377874 -0.369886 -0.866577 -0.390549 -0.31067 -0.771232 -0.35043 -0.531414 -0.704261 -0.480503 -0.522621 -0.544293 0.605234 -0.580893 -0.458308 0.443222 0.770395 -0.461599 0.447391 0.766008 -0.599834 0.593892 0.536183 -0.598874 0.592495 0.538795 -0.683834 0.687963 0.243058 -0.682416 0.684539 0.25635 -0.698701 0.712307 -0.0666004 -0.7013 0.711563 -0.0430936 -0.651699 0.67294 -0.349915 -0.661287 0.678403 -0.320109 -0.454011 0.48622 -0.746635 -0.603698 0.546534 -0.580387 -0.849821 0.243478 -0.467464 -0.68055 0.257918 -0.685806 -0.616421 0.250119 -0.746636 -0.912872 0.329339 -0.241249 -0.897619 0.329963 -0.292242 -0.313622 0.0781879 0.946323 -0.343799 0.0935037 0.934377 -0.629558 0.196802 0.751616 -0.643017 0.203242 0.738392 -0.803847 0.267513 0.531288 -0.797843 0.264029 0.541973 -0.912247 0.315563 0.261199 -0.90615 0.310246 0.28747 -0.941495 0.336108 -0.0248583 -0.94342 0.329758 0.0349057 -0.936868 0.334981 -0.100328 -0.289425 0.248276 0.924442 -0.202983 0.180306 0.962438 -0.157512 0.215825 0.963644 -0.0722768 0.143413 0.98702 -0.058791 0.109103 0.99229 -0.418731 0.70044 -0.577969 -0.409497 0.688481 -0.598587 -0.48203 0.804272 -0.347553 -0.476396 0.798277 -0.36851 -0.513869 0.855468 -0.0641312 -0.511884 0.855119 -0.0821371 -0.500013 0.830508 0.245444 -0.500632 0.833689 0.233088 -0.435543 0.72144 0.538356 -0.436902 0.724801 0.532711 -0.329439 0.543345 0.77217 -0.32983 0.544174 0.771418 -0.199424 0.325837 0.924154 -0.222437 0.0927643 0.970524 -0.282537 0.142364 0.948633 -0.561109 0.323795 0.761783 -0.566019 0.32777 0.756432 -0.72466 0.436353 0.533352 -0.722696 0.434509 0.537505 -0.822959 0.510064 0.250147 -0.819921 0.505638 0.268439 -0.843259 0.535225 -0.0494797 -0.846121 0.532712 -0.0172511 -0.792918 0.514748 -0.32606 -0.806614 0.517862 -0.284945 -0.752221 0.49184 -0.438471 -0.810408 0.441064 0.385619 -0.686159 -0.0106652 0.727373 -0.402767 -0.0112735 0.915233 -0.399543 -0.0101931 0.916658 -0.396895 -0.0110576 0.917797 -0.846735 0.012233 0.531875 -0.774632 -0.00968815 0.632338 -0.983601 -0.0072463 0.180211 -0.955639 -0.00239303 -0.294532 -0.955849 -0.00251202 -0.293847 -0.998839 -0.00573096 0.04784 -0.954693 -0.0289574 0.29618 -0.346393 0.012338 0.938008 -0.944612 0.0559366 -0.323387 -0.984394 0.173238 0.0309284 -0.979016 0.17468 -0.104953 -0.953317 0.174851 -0.246201 -0.929404 0.181451 -0.321379 -0.868354 0.161101 -0.46905 -0.35606 0.0427092 0.933487 -0.297554 0.0186737 0.954522 -0.674645 0.0699713 0.734819 -0.65279 0.0654342 0.754708 -0.838465 0.0915409 0.537213 -0.824641 0.0880079 0.558768 -0.95317 0.109292 0.281998 -0.941307 0.10466 0.320916 -0.88355 0.116765 -0.453548 -0.996162 0.0574007 0.0660755 -0.95552 0.0628019 -0.288163 -0.396904 -0.00929477 0.917813 -0.955852 -0.00197774 -0.293842 -0.347737 -0.00545788 0.937576 -0.29897 -0.00656536 0.95424 -0.65505 -0.00705229 0.755553 -0.686176 -0.00675575 0.727404 -0.828433 -0.00647344 0.560052 -0.84683 -0.00616947 0.531828 -0.94667 -0.00539459 0.32216 -0.983615 -0.0037429 0.180242 -0.997833 -0.00389034 0.0656817 -0.951789 -0.00154643 -0.306751 -0.957283 -0.00120385 -0.28915 -0.957284 -0.000493155 -0.289148 -0.957378 -0.000543369 -0.288839 -0.997839 -0.00123706 0.0656881 -0.997812 -0.00127313 0.0660976 -0.94668 -0.0016643 0.322171 -0.946544 -0.00170235 0.322569 -0.828445 -0.0019619 0.560067 -0.827891 -0.00205077 0.560885 -0.655062 -0.00214621 0.755572 -0.654207 -0.00224371 0.756312 -0.347743 -0.00210541 0.937587 -0.346414 -0.0023213 0.938079 0.82833 -0.26628 -0.492914 0.0351541 -0.370835 0.928033 0.12144 -0.22808 0.966039 0.072249 -0.24802 0.966057 0.0662519 -0.194348 0.978693 0.0382348 -0.386469 0.92151 0.0162125 -0.118569 0.992813 0.240511 -0.0225473 0.970385 0.258688 -0.027273 0.965576 0.587152 -0.0535402 0.807704 0.594568 -0.0550095 0.802161 0.793019 -0.0754356 0.604508 0.781075 -0.072181 0.620252 0.924013 -0.0877101 0.372165 0.0797602 -0.840784 0.535462 0.0795659 -0.840156 0.536476 0.235816 -0.810501 0.53617 0.234689 -0.808369 0.53987 0.395251 -0.743217 0.53982 0.392266 -0.739572 0.546956 0.533021 -0.645476 0.547036 0.527883 -0.641226 0.556928 0.0595086 -0.627566 0.776286 0.0593662 -0.626952 0.776793 0.175989 -0.60497 0.776556 0.175167 -0.603108 0.778188 0.294832 -0.554562 0.778161 0.292478 -0.551257 0.781391 0.397219 -0.481193 0.781454 0.39313 -0.477355 0.785864 0.601775 -0.727889 -0.328702 0.612395 -0.554267 -0.563702 0.585079 -0.58262 -0.564125 0.520512 -0.633254 -0.572762 0.549471 -0.765615 0.334538 0.323655 -0.61367 -0.720179 0.320348 -0.733608 -0.599331 0.219958 -0.758746 -0.613126 0.22035 -0.761396 -0.60969 0.0748465 -0.788914 -0.609928 0.0745698 -0.787747 -0.611469 0.594294 -0.722962 -0.352336 0.439769 -0.826151 -0.352247 0.435072 -0.821288 -0.369052 0.259827 -0.892345 -0.369067 0.257818 -0.889043 -0.378328 0.0874317 -0.921431 -0.378578 0.087187 -0.920754 -0.380278 0.371362 -0.25794 0.89194 0.19803 -0.103046 0.974764 0.540686 -0.284262 0.791741 0.532786 -0.278703 0.799039 0.727285 -0.382693 0.569739 0.718276 -0.375459 0.585756 0.840151 -0.442254 0.313939 0.913002 -0.260526 0.313933 0.958913 -0.277108 0.0608033 0.994037 -0.0904875 0.0608431 0.972733 -0.0961616 -0.211053 0.985389 -0.089409 -0.144964 0.914397 -0.0874759 -0.395255 0.273623 -0.0855438 0.958026 0.232492 -0.0659527 0.97036 0.577751 -0.166551 0.79904 0.567056 -0.161969 0.807598 0.778693 -0.224771 0.58576 0.766239 -0.218564 0.604241 0.902023 -0.260464 0.344257 0.934837 -0.0860885 0.344482 0.98828 -0.0941283 0.120179 0.854358 -0.496742 0.152706 0.543309 -0.447959 -0.710034 0.741263 -0.601789 -0.297286 0.73102 -0.597971 -0.328694 0.775337 -0.630065 -0.0432513 0.636471 -0.770087 -0.0432593 0.633878 -0.77074 -0.0644858 0.468826 -0.880934 -0.0644837 0.466765 -0.880769 -0.0798461 0.278606 -0.95708 -0.0798584 0.27751 -0.956661 -0.0882536 0.0940997 -0.991638 -0.0883125 0.0939027 -0.991505 -0.0900019 0.770276 -0.405943 -0.491818 0.85679 -0.446951 -0.257189 0.844444 -0.44559 -0.297262 0.886174 -0.463105 -0.015138 0.774291 -0.632649 -0.015128 0.747951 -0.607961 0.26637 0.613923 -0.74304 0.26644 0.615162 -0.747633 0.250242 0.454759 -0.854749 0.250195 0.454891 -0.858017 0.238497 0.271369 -0.932451 0.238526 0.271074 -0.934115 0.232266 0.0918741 -0.968264 0.232429 0.0917412 -0.968616 0.231014 0.990426 -0.114219 -0.0775231 0.73868 -0.218012 -0.637827 0.940259 -0.267297 -0.210866 0.928122 -0.26915 -0.257193 0.961451 -0.274227 0.0202836 0.884596 -0.465917 0.0202797 0.848766 -0.443714 0.287601 0.741773 -0.605829 0.287651 0.637672 -0.518363 0.569801 0.643337 -0.525244 0.556988 0.473862 -0.385385 0.791791 0.479109 -0.390953 0.785882 0.197363 -0.160144 0.967162 0.161924 -0.195781 0.967187 0.12922 -0.138595 0.981883 0.207495 -0.338253 0.917895 0.999857 0 -0.0168966 0.989351 0.000716731 -0.145547 0.961178 -0.0046664 -0.27589 0.917915 0 -0.396776 0.992685 0 0.120737 0.992687 -8.51196e-07 0.120715 0.92761 -2.63401e-06 0.37355 0.927588 0 0.373605 0.783157 0 0.621824 0.783117 2.97764e-06 0.621874 0.595471 -6.6385e-08 0.803376 0.59547 0 0.803378 0.258784 0 0.965935 0.258784 0 0.965935 -0.355709 -0.723823 -0.591228 -0.246956 -0.754051 -0.608621 -0.214529 -0.528452 -0.821411 -0.352825 -0.857465 -0.374524 -0.354305 -0.864487 -0.356553 -0.379064 -0.921372 -0.0859361 -0.378395 -0.923031 -0.0695063 -0.369963 -0.89944 0.232668 -0.367845 -0.897004 0.245101 -0.321283 -0.781278 0.535147 -0.318774 -0.777076 0.542712 -0.240114 -0.584044 0.775395 -0.238118 -0.580274 0.778834 -0.142032 -0.345554 0.927588 -0.14095 -0.343385 0.928558 -0.0454551 -0.110593 0.992826 -0.0451604 -0.109977 0.992908 -0.0995649 -0.786021 -0.610129 -0.0996362 -0.788877 -0.606421 -0.116274 -0.918004 -0.379142 -0.116174 -0.919642 -0.375182 -0.125136 -0.988077 -0.0896907 -0.124891 -0.98843 -0.0860705 -0.122251 -0.965422 0.230252 -0.121927 -0.964788 0.233062 -0.106184 -0.838703 0.534137 -0.105876 -0.837629 0.535881 -0.0793245 -0.626699 0.775214 -0.0791133 -0.625777 0.77598 -0.0469103 -0.370656 0.927585 -0.0467883 -0.370054 0.927831 -0.0150045 -0.118571 0.992832 -0.0149729 -0.118401 0.992853 -0.216126 -0.15925 0.963291 -0.99543 -0.0556034 0.0776378 -0.285894 -0.0756135 0.955273 -0.863989 -0.331843 -0.378686 -0.881434 -0.281375 -0.379345 -0.957198 -0.288394 0.024508 -0.957256 -0.0538345 -0.284189 -0.945333 -0.0631679 -0.319929 -0.933805 -0.162758 -0.318618 -0.850413 -0.363494 -0.380355 -0.766371 -0.403137 -0.500155 -0.833649 -0.517908 -0.191835 -0.49553 -0.638455 -0.588918 -0.491349 -0.631949 -0.599347 -0.576355 -0.735217 -0.356752 -0.581147 -0.744273 -0.329127 -0.616126 -0.78457 -0.0695565 -0.6157 -0.786514 -0.0480477 -0.599374 -0.761993 0.245189 -0.59679 -0.760205 0.256768 -0.519859 -0.659641 0.54279 -0.519002 -0.658826 0.544597 -0.388957 -0.492064 0.778836 -0.39261 -0.495876 0.774573 -0.231237 -0.290539 0.928502 -0.162013 -0.214754 0.963137 -0.0764212 -0.0916963 0.99285 -0.279461 -0.0145935 0.960046 -0.389214 -0.125236 0.912594 -0.608815 -0.211329 0.764647 -0.606896 -0.210761 0.766327 -0.78159 -0.282547 0.556133 -0.788958 -0.284559 0.544584 -0.894241 -0.332203 0.299958 -0.903055 -0.334004 0.27006 -0.847002 -0.337114 -0.411025 -0.909793 -0.41458 -0.0199967 -0.865513 -0.405649 -0.293831 -0.896203 -0.275536 -0.347708 -0.921206 -0.169994 -0.349973 -0.985366 -0.169022 0.0220146 -0.931459 -0.119177 -0.343773 -0.949518 -0.104684 0.295731 -0.935429 -0.105182 0.337505 -0.828658 -0.0876953 0.552844 -0.811339 -0.0873014 0.57802 -0.644089 -0.0640374 0.762266 -0.630558 -0.0634382 0.773545 -0.318232 -0.0240012 0.947709 -0.255413 -0.132439 0.957718 -0.180223 -0.113465 0.977059 -0.521897 -0.366989 0.770028 -0.519041 -0.365245 0.772783 -0.678708 -0.487175 0.54956 -0.682826 -0.489514 0.542332 -0.777118 -0.565653 0.275906 -0.782693 -0.5681 0.254271 -0.805234 -0.592761 -0.015233 -0.805378 -0.590605 -0.0505286 -0.768469 -0.5716 -0.287626 -0.75814 -0.561567 -0.33146 -0.510344 -0.396899 -0.762902 -0.618132 -0.560447 -0.551192 0.966233 0.122049 0.22693 0.95798 0.081634 -0.274972 0.977048 0.0726277 -0.200257 0.997328 0.0710864 -0.0168539 0.990509 0.0661621 0.120472 0.793308 0.340766 -0.50452 0.748307 0.283936 -0.599514 0.903059 0.335017 -0.268791 0.909961 0.341563 -0.23517 0.936939 0.347191 0.0400524 0.258613 0.0363917 0.965295 0.242653 0.0359945 0.969445 0.593439 0.0825586 0.800634 0.59206 0.0824642 0.801664 0.778374 0.110354 0.618026 0.797739 0.111159 0.592669 0.919692 0.130385 0.370361 0.936002 0.130085 0.327077 0.899886 0.134398 -0.414901 0.978105 0.20422 0.0400498 0.95832 0.203838 -0.200181 0.951437 0.19859 -0.235224 0.863126 0.184453 -0.470097 0.835317 0.284228 -0.470596 0.2231 0.103617 0.969273 0.234377 0.107436 0.966191 0.542523 0.252759 0.801113 0.564161 0.260922 0.783353 0.730565 0.340445 0.591922 0.752183 0.347848 0.559663 0.856682 0.399341 0.326531 0.871619 0.403038 0.278999 0.786829 0.374259 -0.490745 0.872417 0.488346 -0.020174 0.838688 0.473649 -0.268811 0.832181 0.46581 -0.300827 0.752302 0.424877 -0.50351 0.738051 0.413093 -0.533512 -0.318302 0.00388379 0.947981 -0.958591 0.000843134 -0.284784 -0.95844 0.000921491 -0.285293 -0.996983 0.00204216 0.0775882 -0.997057 0.00212137 0.0766333 -0.940728 0.0027222 0.33915 -0.941428 0.0029017 0.337201 -0.814524 0.00324323 0.580122 -0.815875 0.00344787 0.578218 -0.631857 0.00348427 0.775077 -0.634445 0.00377058 0.772959 -0.320079 0.00333475 0.947385 -0.322044 0.00395043 0.946716 0.335361 0.728386 -0.597484 0.655088 0.535634 -0.532876 0.565881 0.594441 -0.571331 0.524718 0.45719 -0.718087 0.712929 0.614901 -0.337091 0.720708 0.625213 -0.29948 0.755491 0.652833 -0.0551573 0.754718 0.655742 -0.0200816 0.731639 0.633497 0.251764 0.724168 0.630221 0.280004 0.634755 0.550957 0.541787 0.623832 0.544037 0.561122 0.477944 0.416323 0.773462 0.466743 0.408435 0.784431 0.201551 0.17721 0.963314 0.192024 0.171008 0.966376 0.462284 0.659748 -0.592474 0.469972 0.674489 -0.569377 0.530891 0.764916 -0.364771 0.534521 0.774195 -0.338982 0.564915 0.820914 -0.083492 0.563991 0.823799 -0.0571826 0.549043 0.804826 0.225403 0.543714 0.801256 0.249728 0.477962 0.707947 0.519965 0.469079 0.698861 0.539961 0.361356 0.543391 0.757725 0.350175 0.530418 0.772032 0.155072 0.245801 0.956836 0.141452 0.230897 0.962641 0.0838211 0.282149 0.955702 0.0921341 0.297914 0.950136 0.208768 0.621366 0.755195 0.214684 0.633312 0.743523 0.279724 0.80929 0.516531 0.284187 0.816894 0.501918 0.324018 0.919791 0.221353 0.326744 0.922547 0.205291 0.335619 0.937905 -0.0877201 0.336546 0.935956 -0.103551 0.317394 0.873674 -0.368719 0.316705 0.867731 -0.383068 0.211717 0.561072 -0.800234 0.236386 0.755933 -0.610481 0.0909884 0.784855 -0.612963 0.0909798 0.786462 -0.610901 0.103961 0.91526 -0.389218 0.103842 0.916492 -0.386341 0.110164 0.987768 -0.110355 0.109872 0.988216 -0.106573 0.106657 0.974302 0.198395 0.106128 0.973428 0.202916 0.0924729 0.86368 0.495484 0.0916733 0.861016 0.500248 0.0695668 0.67106 0.738132 0.0685231 0.666473 0.742373 0.029423 0.318813 0.947361 0.0277454 0.312312 0.949574 -0.95844 0.000884187 -0.285293 -0.958356 0.000927753 -0.285575 -0.997057 0.00206813 0.0766335 -0.997164 0.00218492 0.0752252 -0.941428 0.00279524 0.337201 -0.941983 0.00293809 0.335648 -0.815875 0.00328835 0.578219 -0.817539 0.00354129 0.575862 -0.634445 0.00357409 0.77296 -0.636961 0.00385328 0.770886 -0.322045 0.00340768 0.946718 -0.325834 0.00400677 0.945419 -0.0392112 0.329839 0.943222 -0.247704 0.730902 -0.635944 -0.25584 0.834888 -0.487349 -0.379734 0.709277 -0.593909 -0.27915 0.613204 -0.738956 -0.438236 0.821218 -0.365445 -0.383265 0.78558 -0.48577 -0.432538 0.897809 -0.0827652 -0.285268 0.877943 -0.384498 -0.304001 0.947029 -0.103535 -0.329104 0.818764 -0.470442 -0.357675 0.910718 0.206547 -0.354486 0.90752 0.225272 -0.311422 0.806369 0.502778 -0.306097 0.79772 0.519565 -0.235609 0.625059 0.744171 -0.22858 0.611737 0.757317 -0.0928215 0.27137 0.957989 -0.0942708 0.27383 0.957147 -0.00410734 0.318948 0.947763 -0.0295251 0.296236 0.954658 -0.0755537 0.670767 0.73781 -0.0754212 0.665218 0.74283 -0.100567 0.863 0.495094 -0.100663 0.859722 0.500745 -0.116075 0.973267 0.198184 -0.116358 0.972091 0.203713 -0.119961 0.98664 -0.110229 -0.120359 0.987111 -0.105476 -0.113266 0.914325 -0.38882 -0.113714 0.915858 -0.385062 -0.0991744 0.784239 -0.612482 -0.107888 0.823985 -0.556246 -0.83782 0.463454 -0.288563 -0.347954 0.102521 0.931889 -0.265671 0.123288 0.956148 -0.229169 0.0750929 0.970486 -0.609325 0.248212 0.75307 -0.668115 0.269884 0.693387 -0.91164 0.403829 0.0763876 -0.87369 0.377718 0.306585 -0.881563 0.379417 0.280875 -0.773937 0.330728 0.540037 -0.874819 0.326514 -0.357882 -0.748108 0.417859 -0.515489 -0.797018 0.458417 -0.393214 -0.846081 0.355213 -0.397455 -0.818412 0.277266 -0.503315 -0.877458 0.474767 -0.0682884 -0.748133 0.363934 -0.554842 -0.942256 0.334873 0.00375543 -0.980391 0.197062 0.000549905 -0.908976 0.19478 -0.368542 -0.92555 0.187581 -0.328893 -0.301165 0.0272353 0.953183 -0.325636 0.0333348 0.944907 -0.656128 0.0821412 0.750166 -0.635097 0.0772381 0.768561 -0.837011 0.109662 0.536084 -0.813297 0.102878 0.572681 -0.95261 0.128886 0.275542 -0.935128 0.121296 0.332902 -0.8789 0.133993 -0.4578 -0.994951 0.0668539 0.0748595 -0.941053 0.0736191 -0.330152 -0.956341 0.0637623 -0.285212 -0.546783 0.710158 -0.443512 -0.665141 0.544524 -0.510961 -0.579578 0.500703 -0.642951 -0.723277 0.602323 -0.337752 -0.735414 0.615744 -0.282888 -0.768093 0.63722 -0.0631157 -0.76868 0.637032 -0.0576332 -0.767419 0.635691 0.0834591 -0.748103 0.615959 0.246853 -0.729298 0.607708 0.314349 -0.65668 0.531692 0.53486 -0.490306 0.41324 0.767354 -0.554921 0.449006 0.700326 -0.224419 0.171205 0.959336 -0.231646 0.175533 0.956833 -0.483597 0.64703 -0.589479 -0.558647 0.746633 -0.361182 -0.562298 0.75505 -0.337225 -0.595739 0.799233 -0.0795147 -0.594998 0.801698 -0.0570748 -0.580185 0.781467 0.229551 -0.576128 0.779015 0.247413 -0.506301 0.685213 0.523586 -0.500731 0.680023 0.535571 -0.384292 0.52371 0.760294 -0.378877 0.51799 0.766902 -0.166609 0.23254 0.95821 -0.163243 0.229233 0.959585 -0.378537 -0.41364 -0.828017 -0.339861 0.272888 -0.900015 -0.0982858 -0.0458711 -0.9941 -0.676712 -0.387658 -0.625926 -0.637954 0.378947 -0.670384 -0.521618 -0.0117862 -0.853098 -0.84797 -0.425445 -0.316139 -0.925103 0.0251599 -0.378882 -0.831461 0.124651 -0.541419 -0.9242 0.0888261 0.371435 -0.984987 0.104593 0.137334 -0.884222 -0.466463 0.0237551 -0.993459 0.095362 -0.0628082 -0.976678 0.10139 -0.18926 -0.246565 0.548914 0.798686 -0.242392 0.590325 0.769911 -0.187364 0.767142 0.613505 -0.146796 0.842749 0.517905 -0.130096 0.885552 0.445952 -0.057855 0.970896 0.232408 -0.0224706 0.988831 0.147339 0.0011677 0.998683 0.0512964 -0.0751424 0.98835 0.132359 -0.0264827 0.996206 0.0829022 -0.0575451 0.992976 0.103382 -0.0645543 0.994913 0.077332 -0.0332683 0.99765 0.0598986 -0.0975013 0.994188 0.0456552 -0.0338274 0.999104 0.0254191 -0.0568642 0.99832 0.0111484 -0.0432256 0.998928 -0.0165645 -0.0378016 0.999233 -0.0102085 -0.0364993 0.997209 -0.0651366 -0.0186137 0.999689 -0.0165999 0.000972939 0.995249 -0.0973587 0.0168455 0.999836 -0.00664231 -0.0119943 0.997331 -0.0720272 -0.0156073 0.715838 -0.698092 -0.0283189 0.539917 -0.841242 -0.0300285 0.344212 -0.938412 -0.0633556 -0.30939 -0.948822 0.0774469 0.151515 -0.985416 -0.424009 0.86226 0.276991 -0.423956 0.862297 0.276956 -0.476474 0.875462 0.080863 -0.478785 0.874158 0.0813213 -0.450209 0.884017 -0.125805 -0.456431 0.880647 -0.127013 -0.352395 0.885818 -0.3019 -0.358441 0.882014 -0.305893 -0.199847 0.884227 -0.422142 -0.201573 0.882608 -0.424701 -0.0040195 0.882079 -0.471084 -0.526829 0.0952146 0.844622 -0.323435 0.0853895 0.94239 -0.30392 0.184449 0.934672 -0.82111 0.0990581 0.562109 -0.278441 0.409126 0.868957 -0.296433 0.27149 0.915653 -0.612003 0.284836 0.737781 -0.600498 -0.456433 0.65656 -0.684285 0.0846096 0.724289 -0.0368686 0.492422 -0.869575 -0.367015 0.491527 -0.789748 -0.366674 0.493815 -0.788478 -0.649958 0.490029 -0.580884 -0.647741 0.496427 -0.57792 -0.828971 0.487941 -0.273351 -0.824324 0.497353 -0.270426 -0.87303 0.480699 0.0821464 -0.86615 0.492749 0.0835647 -0.616222 0.270344 0.739719 -0.51892 0.553069 0.651795 -0.516419 0.56032 0.647574 -0.306762 0.850229 0.427794 -0.307177 0.84976 0.428428 -0.037305 0.991556 0.124199 -0.0529483 0.986936 0.152162 -0.0353564 0.294581 -0.954972 -0.401504 0.294473 -0.867225 -0.401396 0.296576 -0.866559 -0.710398 0.292465 -0.640156 -0.709298 0.299198 -0.638261 -0.906155 0.290102 -0.307772 -0.903136 0.301974 -0.305216 -0.95583 0.283993 0.0757398 -0.950562 0.300629 0.0778039 -0.83976 -0.323375 0.436155 -0.778326 -0.526829 0.341554 -0.845959 0.29441 0.444608 -0.852284 0.275635 0.444563 -0.714435 0.573541 0.400791 -0.782312 0.472245 0.406169 -0.659393 0.650181 0.377446 -0.737489 0.66991 0.0856131 -0.743916 0.662867 0.084831 -0.701727 0.677356 -0.220835 -0.707284 0.670556 -0.223841 -0.551289 0.678018 -0.486181 -0.554659 0.672338 -0.49022 -0.312245 0.675588 -0.667896 -0.312849 0.673428 -0.669791 -0.0225999 0.673625 -0.738728 -0.011092 0.861509 -0.507621 0.00134762 0.998681 0.0513194 -0.0636986 0.188229 0.980057 0.125474 -0.269066 0.954913 0.547738 0.18728 0.81542 0.437122 -0.131213 0.889779 0.425961 -0.0474344 0.903497 0.30262 0.187547 0.934477 0.671008 0.184774 0.718057 0.737512 -0.178138 0.651416 0.796854 0.184353 0.575359 0.912576 0.182981 0.36568 0.94227 -0.0908015 0.322308 0.965458 0.182935 0.185543 0.931268 0.0953721 -0.35163 0.98953 0.0793516 -0.120556 0.70866 0.102127 -0.69812 0.836547 0.0855237 -0.541179 0.132519 0.990727 0.0299756 0.160607 0.987018 0.000165264 0.142514 0.989501 -0.0240453 0.175949 0.984398 0.00182593 0.185157 0.981994 0.0374661 0.160015 0.986454 0.0361166 0.225836 0.9713 0.0746688 0.14868 0.986731 0.0652363 0.219081 0.961601 0.165308 0.136751 0.984566 0.109217 0.0856833 0.985224 0.1483 0.126561 0.955619 0.266034 0.00982442 0.993409 0.114199 -0.00921729 0.971066 0.238633 0.0215634 0.885136 0.464833 0.0383108 0.843177 0.53627 0.247744 0.841602 0.479926 0.249495 0.83968 0.48238 0.415172 0.837303 0.355746 0.420293 0.833373 0.358948 0.51861 0.833527 0.190462 0.525544 0.828923 0.191546 0.550766 0.834605 0.00951194 0.555217 0.831664 0.0083473 0.509301 0.84378 -0.169256 0.509641 0.843522 -0.169521 0.831141 -0.266627 -0.487969 0.735684 -0.541077 -0.407436 0.88018 0.258297 -0.398205 0.559177 0.0896407 -0.824188 0.587253 -0.395634 -0.706122 0.662866 0.26864 -0.698886 0.658871 0.290082 -0.694076 0.622187 0.464706 -0.630026 0.342914 0.14281 -0.928448 0.346471 0.104878 -0.932179 0.331587 0.335108 -0.881903 0.337062 0.295435 -0.893928 0.312378 0.530872 -0.787778 0.324061 0.489606 -0.809488 0.267959 0.707762 -0.65366 0.0884045 0.992536 -0.0840065 0.208909 0.855547 -0.473704 0.20356 0.876145 -0.436959 0.282724 0.668684 -0.687699 0.549852 0.647205 -0.528005 0.617086 0.478908 -0.624382 0.820386 0.44999 -0.352813 0.874754 0.28024 -0.395311 0.965643 0.256118 -0.0440087 0.964482 -0.242046 -0.105771 0.979686 0.186048 0.0748438 0.0391776 0.410846 0.910863 0.0560419 0.589731 0.805653 0.0452386 0.765824 0.641457 0.0670057 0.186186 0.980227 0.0578623 0.549489 0.833495 0.376395 0.546913 0.747805 0.376453 0.546781 0.747873 0.633683 0.542726 0.551266 0.634986 0.540529 0.551926 0.793125 0.540374 0.280979 0.797057 0.534464 0.281155 0.839007 0.543718 -0.0209529 0.845001 0.534249 -0.0234715 0.765522 0.554355 -0.326599 0.721172 0.628873 -0.290567 0.546127 0.653542 -0.524049 0.391638 0.86001 -0.327112 0.390495 0.861285 -0.325119 0.107429 0.994211 0.00178442 0.115276 0.983875 -0.136752 -0.29897 -0.260196 0.918104 0.0121705 -0.999924 0.00174917 -0.0264799 -0.999648 -0.00132987 -0.0424513 -0.999069 -0.00770654 -0.0464819 -0.998184 -0.0383097 -0.0112524 -0.999748 -0.0194022 -0.0316791 -0.997996 -0.0547795 0.0152299 -0.999349 -0.0327167 0.00231206 -0.978654 -0.205501 -0.0499759 -0.998739 0.00487601 -0.0275533 -0.999242 0.0275056 -0.0886861 -0.995784 0.0234476 -0.0339397 -0.997633 0.0598103 -0.0618868 -0.9958 0.0674695 -0.0552787 -0.993229 0.10218 -0.0469764 -0.994196 0.0967877 -0.0576978 -0.976468 0.207799 -0.0225172 -0.99075 0.133819 -0.0436263 -0.98611 0.160263 -0.227197 -0.64827 0.726724 -0.167717 -0.813886 0.556292 -0.310064 -0.0730292 0.947907 -0.993376 -0.0957422 -0.0635492 -0.884392 0.4662 0.0225666 -0.969382 -0.103092 -0.222869 -0.811644 0.496601 -0.307606 -0.905708 -0.0964977 -0.412773 -0.811316 -0.101185 -0.575785 -0.637415 0.490947 -0.593863 -0.579583 -0.457267 -0.67453 0.0769126 -0.100473 -0.991962 -0.0158681 -0.792387 -0.609813 -0.0246391 -0.624698 -0.780478 -0.00635934 -0.908209 -0.418468 -0.00234316 -0.885156 -0.465289 -0.198324 -0.885834 -0.419484 -0.19752 -0.887429 -0.416479 -0.352735 -0.885342 -0.302899 -0.348277 -0.889067 -0.29709 -0.450019 -0.884009 -0.126532 -0.444599 -0.88719 -0.12339 -0.47295 -0.877447 0.0800287 -0.470604 -0.878679 0.0803479 -0.418917 -0.865627 0.274223 -0.985007 -0.105159 0.136755 -0.925599 -0.0896429 0.367738 -0.777942 0.528167 0.340361 -0.839144 0.330912 0.431665 -0.821243 -0.0996856 0.561802 -0.682543 -0.085011 0.725885 -0.606381 0.43683 0.664441 -0.525245 -0.0956414 0.845559 -0.310337 -0.0851455 0.946806 -0.514193 -0.563537 0.646554 -0.251051 -0.552712 0.794659 -0.254047 -0.476758 0.841524 -0.326835 -0.359259 -0.874135 -0.38411 0.381413 -0.840823 -0.400953 -0.296241 -0.866878 -0.146182 -0.846267 0.512312 -0.303824 -0.853073 0.424213 -0.518561 -0.556553 0.64911 -0.717371 -0.57651 0.391172 -0.774235 -0.472403 0.421184 -0.864805 -0.495484 0.0812884 -0.871417 -0.483641 0.0819987 -0.822049 -0.50036 -0.271802 -0.827434 -0.490645 -0.273167 -0.645647 -0.499187 -0.577886 -0.648585 -0.492938 -0.579957 -0.365363 -0.496706 -0.787269 -0.366069 -0.494463 -0.788352 -0.400514 -0.298473 -0.866315 -0.709711 -0.294412 -0.640025 -0.707857 -0.301241 -0.638899 -0.905436 -0.292168 -0.307933 -0.901865 -0.303784 -0.307173 -0.95532 -0.285706 0.0757366 -0.950125 -0.302671 0.0751797 -0.851512 -0.277452 0.444914 -0.846564 -0.295953 0.442426 -0.615456 -0.271794 0.739825 -0.612836 -0.286545 0.736427 -0.296642 -0.273206 0.915075 -0.0362734 -0.99233 0.118173 -0.0616097 -0.986437 0.152141 -0.303186 -0.853551 0.423708 -0.419224 -0.865452 0.274305 -0.656976 -0.653622 0.375713 -0.734639 -0.673263 0.0838011 -0.740865 -0.66632 0.084481 -0.698187 -0.680811 -0.221432 -0.704229 -0.674019 -0.223068 -0.548061 -0.681492 -0.484973 -0.55226 -0.675827 -0.488125 -0.310319 -0.679103 -0.665223 -0.311339 -0.676964 -0.666924 -0.0316243 -0.678101 -0.734288 -0.0273765 -0.494562 -0.868711 -0.0374415 -0.337904 -0.940435 -0.0350173 -0.29643 -0.954412 -0.041661 0.443059 -0.895524 -0.0895459 0.113333 -0.989514 0.549075 -0.648244 -0.527538 0.0531453 -0.647375 0.760317 0.0432541 -0.999043 0.00647263 0.172977 -0.982172 0.0735979 0.0239318 -0.975652 0.218014 0.0348764 -0.961164 0.273764 0.0659796 -0.991901 0.108531 0.0943694 -0.984978 0.144614 0.146874 -0.982056 0.118296 0.097304 -0.993278 0.0626913 0.127173 -0.984648 0.11956 0.142798 -0.989646 0.0144694 0.192146 -0.981248 0.0152168 0.170786 -0.984554 0.0385316 0.237932 -0.970172 0.0464307 0.148368 -0.98656 0.0684523 0.167894 -0.985788 0.00586399 0.138794 -0.989767 -0.0331219 0.192913 -0.974772 -0.112267 0.0548498 -0.998457 -0.00868441 0.0750704 -0.977994 -0.19466 0.669614 -0.199667 -0.715367 0.330572 0.00808175 -0.943746 0.95226 -0.0950944 -0.2901 0.808987 0.40947 -0.421752 0.780234 0.463098 -0.420446 0.806061 -0.234055 -0.543585 0.567254 0.367995 -0.736751 0.979222 -0.188258 0.0753849 0.956983 -0.183526 0.224725 0.931377 0.176586 0.318361 0.896253 -0.186173 0.40258 0.805573 -0.186849 0.562263 0.738982 0.163268 0.653643 0.682248 -0.186684 0.706885 0.0682108 0.112587 0.991298 0.19678 -0.190647 0.961734 0.436372 -0.185475 0.880442 0.356201 0.306862 0.882585 0.542597 -0.189726 0.818287 0.065995 -0.261164 0.963036 0.0126185 0.354316 0.935041 -0.0636809 -0.0752097 0.995132 0.178564 -0.903291 -0.390102 0.204628 -0.874915 -0.43892 0.391741 -0.860035 -0.326924 0.393409 -0.858722 -0.328368 0.511711 -0.842139 -0.170157 0.511263 -0.842442 -0.170003 0.55743 -0.830171 0.00939992 0.552894 -0.833202 0.00907032 0.527062 -0.827428 0.193824 0.520897 -0.832074 0.190578 0.420943 -0.831954 0.361468 0.417158 -0.835871 0.356789 0.249736 -0.838323 0.48461 0.248877 -0.840258 0.481691 0.0379526 -0.841845 0.538384 0.0336544 -0.813207 0.581 0.937737 0.318365 -0.1389 0.994607 -0.078703 -0.0675427 0.964202 -0.261715 -0.0426501 0.874448 -0.285741 -0.392037 0.87848 -0.264603 -0.397816 0.65952 -0.295961 -0.690971 0.338121 -0.328579 -0.881879 0.607447 -0.470839 -0.63978 0.315974 -0.492818 -0.810735 0.291386 -0.669944 -0.682839 0.295668 -0.615949 -0.730197 0.24612 -0.7847 -0.56892 0.341285 -0.0927122 -0.935377 0.337726 -0.301221 -0.891744 0.661148 -0.274662 -0.698172 0.585345 -0.572278 -0.574342 0.77451 -0.545115 -0.320911 0.767311 -0.55652 -0.31862 0.84391 -0.53608 -0.0208525 0.837797 -0.545554 -0.0216164 0.795296 -0.536335 0.282574 0.791986 -0.542315 0.28045 0.633308 -0.542545 0.551875 0.632498 -0.544753 0.550627 0.375522 -0.548824 0.746843 0.375507 -0.548948 0.74676 0.0574907 -0.551489 0.832199 0.0475734 -0.47671 0.877772 0.248258 0.180436 -0.951741 0.165651 0.561242 0.810905 0.0461349 0.966153 -0.253811 0.0885921 0.98046 -0.175643 0.178199 0.945466 -0.272652 0.115833 0.985905 -0.120721 0.157579 0.977931 -0.137184 0.187679 0.961978 0.198431 0.114454 0.993121 0.0247169 0.157097 0.985653 0.0617067 0.177496 0.98404 0.0126852 0.130319 0.991315 -0.0176517 0.1835 0.982748 -0.023119 0.183412 0.979818 -0.0794839 0.105354 0.992928 -0.0547171 0.174117 0.9799 -0.0973649 0.0918767 0.991327 0.0939645 0.0473841 0.980942 0.188435 0.0443168 0.986549 0.157341 0.154077 0.381396 0.911481 0.539325 0.275954 0.795599 0.538749 0.283475 0.793342 0.943597 0.264793 -0.19877 0.943614 0.281114 0.174837 0.947035 0.26783 0.177177 0.805379 0.271829 0.526759 0.803408 0.28298 0.523887 0.696025 -0.523268 0.491671 0.773472 -0.380376 0.507006 0.76822 0.0903909 0.633773 0.608092 0.0968202 0.787941 0.479494 -0.469173 0.741595 0.476884 -0.134577 0.868603 0.425708 0.0930868 0.90006 0.458553 0.535663 -0.70908 0.459733 0.530598 -0.712117 0.688675 0.540613 -0.483181 0.692145 0.532997 -0.486671 0.816824 0.54617 -0.185735 0.822297 0.537121 -0.187959 0.822345 0.551476 0.140082 0.82826 0.542543 0.140113 0.701904 0.555909 0.445304 0.706567 0.548431 0.447198 0.471698 0.558713 0.682159 0.474193 0.553687 0.684523 0.166584 0.559311 0.812048 0.189425 0.282282 0.940444 0.19976 0.189447 0.961356 0.195109 0.0954334 0.976128 0.431329 0.184944 -0.883035 0.533245 -0.0746924 -0.842657 0.550896 -0.184632 -0.813895 0.623469 0.181628 -0.760459 0.813284 0.187701 -0.550761 0.763847 -0.301077 -0.570868 0.871395 0.065935 -0.486131 0.0600108 0.183556 -0.981176 0.194836 -0.136701 -0.971263 0.173571 0.419001 -0.891241 0.154721 0.529624 -0.834002 0.152751 0.589355 -0.793302 0.11701 0.773891 -0.622416 0.885509 0.184537 -0.426402 0.960876 0.190923 -0.200664 0.979502 0.082586 -0.183725 0.993906 0.0944199 0.0568907 0.861812 -0.468112 0.195326 0.964399 0.0867171 0.249829 0.8945 0.095398 0.436771 0.0591191 0.954207 -0.293247 0.0992125 0.817884 -0.566765 0.299679 0.822069 -0.484144 0.300905 0.820098 -0.486719 0.45067 0.826645 -0.336979 0.453848 0.823748 -0.339797 0.535544 0.832377 -0.142625 0.540301 0.829016 -0.144251 0.54032 0.838449 0.0711108 0.545385 0.835137 0.0714245 0.462225 0.843936 0.272249 0.466192 0.841131 0.274159 0.311276 0.847933 0.429088 0.313243 0.846111 0.431249 0.108289 0.849687 0.516048 0.113093 0.840872 0.529287 -0.248259 -0.180436 -0.951741 -0.165654 -0.561233 0.810911 -0.0461421 -0.966148 -0.25383 -0.0886021 -0.980456 -0.175658 -0.178201 -0.945464 -0.272658 -0.115831 -0.985906 -0.120716 -0.15758 -0.977931 -0.137181 -0.187664 -0.961984 0.198414 -0.114442 -0.993123 0.0247097 -0.157081 -0.985657 0.0616955 -0.177479 -0.984043 0.0126744 -0.130324 -0.991314 -0.017648 -0.183519 -0.982744 -0.0231167 -0.183431 -0.979813 -0.0794901 -0.105334 -0.992931 -0.0547107 -0.174115 -0.979899 -0.0973697 -0.0918874 -0.991325 0.0939762 -0.0473893 -0.980937 0.188457 -0.0443216 -0.986546 0.157359 -0.154094 -0.381577 0.911402 -0.539325 -0.275954 0.795599 -0.538747 -0.283485 0.79334 -0.943597 -0.264793 -0.198769 -0.943614 -0.281114 0.174837 -0.947038 -0.26782 0.177178 -0.805377 -0.271838 0.526756 -0.80341 -0.28297 0.52389 -0.696022 0.523275 0.491668 -0.773468 0.380389 0.507003 -0.76822 -0.0903909 0.633773 -0.608092 -0.0968202 0.787941 -0.479494 0.469173 0.741595 -0.476884 0.134577 0.868603 -0.425708 -0.0930868 0.90006 -0.458553 -0.535663 -0.70908 -0.459733 -0.530598 -0.712117 -0.688675 -0.540613 -0.483181 -0.692149 -0.532989 -0.486675 -0.816829 -0.546161 -0.185736 -0.822297 -0.537121 -0.187957 -0.822345 -0.551476 0.14008 -0.828255 -0.542551 0.140111 -0.7019 -0.555917 0.4453 -0.706568 -0.548431 0.447197 -0.471698 -0.558713 0.682159 -0.474189 -0.553695 0.684519 -0.166586 -0.559319 0.812041 -0.189429 -0.282283 0.940443 -0.199764 -0.189447 0.961355 -0.195113 -0.0954333 0.976127 -0.431329 -0.184944 -0.883035 -0.533245 0.0746924 -0.842657 -0.550896 0.184632 -0.813895 -0.623468 -0.181624 -0.76046 -0.813284 -0.187698 -0.550761 -0.763844 0.301086 -0.570867 -0.871395 -0.0659314 -0.486132 -0.060015 -0.183556 -0.981176 -0.19484 0.136678 -0.971265 -0.173576 -0.419001 -0.891241 -0.154725 -0.529625 -0.834001 -0.152757 -0.589341 -0.793311 -0.117009 -0.773905 -0.622398 -0.88551 -0.184541 -0.4264 -0.960875 -0.190927 -0.200664 -0.979502 -0.082586 -0.183724 -0.993906 -0.0944198 0.0568899 -0.861817 0.468102 0.195328 -0.964399 -0.0867171 0.249829 -0.8945 -0.095398 0.436771 -0.0591203 -0.954207 -0.293247 -0.0992126 -0.817893 -0.566752 -0.299671 -0.822078 -0.484134 -0.300898 -0.820107 -0.486709 -0.450661 -0.826654 -0.33697 -0.453848 -0.823748 -0.339797 -0.535543 -0.832377 -0.142627 -0.540288 -0.829024 -0.144249 -0.540307 -0.838458 0.07111 -0.545398 -0.835128 0.0714253 -0.462235 -0.843928 0.272257 -0.466202 -0.841123 0.274167 -0.311285 -0.847925 0.429098 -0.313243 -0.846111 0.431249 -0.108292 -0.849687 0.516047 -0.11309 -0.840881 0.529274 -0.000494135 0.455468 -0.890252 -0.00103002 0.455247 -0.890365 -0.00177886 0.455246 -0.890364 -0.00421192 0.454388 -0.890794 0.00221748 0.470969 -0.882147 0.00434567 0.473014 -0.881044 -0.00123557 0.494234 -0.869328 0.00457162 0.521306 -0.853357 -0.000335952 0.871337 -0.490685 -6.54894e-06 0.871411 -0.490554 0.00387831 0.87104 -0.491197 -0.010962 0.871228 -0.490756 0.011433 0.865891 -0.500102 -0.00509442 0.867044 -0.498205 0.00347878 0.849182 -0.528089 0.000171923 0.850134 -0.526567 -0.000221473 0.827457 -0.561529 0 0.82741 -0.561599 0 0.804414 -0.594069 0 0.804414 -0.594069 0 0.752782 -0.65827 0 0.752782 -0.65827 0 0.675694 -0.737182 0 0.675694 -0.737182 0 0.598335 -0.801246 0 0.598335 -0.801246 0 0.539158 -0.842205 0.0141947 0.512543 -0.858544 -0.487433 0.447964 -0.749491 -0.274345 0.517519 -0.810499 -0.427242 0.384697 -0.818213 -0.691178 0.419629 -0.588375 -0.693567 0.432664 -0.575992 -0.67017 0.6032 -0.432459 -0.0542391 0.459362 -0.886592 -0.02647 0.455347 -0.889921 -0.0252051 0.452246 -0.891537 -0.196248 0.530924 -0.824382 -0.268588 0.52683 -0.806419 -0.248863 0.614712 -0.748463 -0.181318 0.845862 -0.501638 -0.253787 0.813114 -0.523868 -0.251763 0.794537 -0.552563 -0.307305 0.727214 -0.613778 -0.123003 0.852581 -0.507913 -0.00122735 0.87131 -0.490732 -0.0352945 0.873832 -0.484945 -0.017267 0.854513 -0.519143 -0.110386 0.880207 -0.461575 -0.0784013 0.846313 -0.526885 -0.147481 0.864563 -0.480395 -0.298759 0.851857 -0.430212 -0.419391 0.846635 -0.327599 -0.268762 0.835757 -0.478829 -0.257914 0.835247 -0.485636 -0.140541 0.613781 -0.776866 -0.312002 0.690573 -0.652506 0.0375334 0.794397 -0.606238 -0.24646 0.773839 -0.583464 -0.344688 0.790707 -0.505937 -0.231119 0.83275 -0.503102 -0.334552 0.804016 -0.491562 -0.38022 0.795104 -0.472485 -0.387151 0.79444 -0.467953 -0.40738 0.782086 -0.471574 -0.473498 0.742385 -0.473988 -0.446798 0.739997 -0.502768 -0.552195 0.709357 -0.438056 -0.563487 0.685186 -0.461522 -0.60586 0.645591 -0.464915 -0.703868 0.53586 -0.466288 -0.692758 0.553073 -0.462814 -0.63592 0.604296 -0.480034 -0.720221 0.513228 -0.466775 -0.718132 0.51738 -0.465407 -0.711007 0.528806 -0.463501 -0.70531 0.429351 -0.564088 -0.71299 0.435379 -0.549628 -0.712195 0.45242 -0.536744 -0.721602 0.446721 -0.528896 -0.73825 0.461671 -0.491779 -0.730329 0.464663 -0.500707 -0.732287 0.491313 -0.471559 -0.730021 0.487809 -0.478656 -0.724682 0.506238 -0.467504 -0.647916 0.442323 -0.620125 -0.598663 0.508056 -0.619259 -0.59445 0.388147 -0.704252 -0.537239 0.440038 -0.719542 -0.510461 0.431092 -0.744036 -0.508797 0.432103 -0.744588 -0.492265 0.420136 -0.762339 -0.470796 0.43329 -0.768512 -0.432029 0.41009 -0.803229 -0.338091 0.459975 -0.821047 -0.363951 0.438292 -0.821852 -0.317201 0.449411 -0.835113 -0.042033 0.453716 -0.890154 -0.058252 0.436201 -0.897962 -0.0838706 0.457133 -0.885435 -0.088064 0.457658 -0.884756 -0.105177 0.487461 -0.866787 -0.137121 0.455924 -0.879393 -0.191598 0.44627 -0.874147 -0.229993 0.419127 -0.878314 -0.250945 0.454468 -0.854684 -0.310408 0.482551 -0.819019 -0.305101 0.476631 -0.824461 -0.24082 0.43898 -0.865622 -0.263376 0.47244 -0.841091 0.956693 -0.291099 -0.000503768 0.906453 -0.42226 -0.00632078 0.929007 -0.370058 0.00162691 0.828691 -0.559706 -0.000651917 0.851863 -0.523762 0.00162556 0.818318 -0.574766 0 0.982875 0.183578 0.0160125 0.987871 -0.153437 -0.0238179 0.99995 0.000870782 0.00999617 0.981045 -0.193778 0.000590922 0.722584 0.691283 0.000171782 0.862458 0.506129 -0.000644553 0.852368 0.522932 0.00335344 0.960483 0.278333 -0.00160949 0.952602 0.30422 0.000698982 0.986363 0.164584 -0.000433205 0.999593 0.0274734 -0.00761936 0.680229 0.732994 0.00290376 0.585476 0.810617 0.0108642 0.706123 0.70777 -0.0212797 0.446113 0.894695 0.0224535 0.536502 0.843899 -0.000236519 0.0814975 0.996674 0 0.194344 0.980899 0.00823491 0.21677 0.976206 0.00570162 0.31224 0.950003 9.28584e-05 0.791333 -0.611385 0 0.315029 -0.948996 -0.0128019 0.245088 -0.969496 0.00291516 0.157311 -0.987545 -0.00294249 0.158098 -0.987418 -0.00312033 0.0402093 -0.999175 0.00571295 0.0597445 -0.998194 -0.00632778 0.00412708 -0.999991 0 0.5015 -0.865153 -0.00278259 0.463348 -0.886176 -5.53016e-07 0.429865 -0.902893 -1.53442e-06 0.399039 -0.916917 0.0055881 0.320684 -0.947123 -0.0109813 0.607126 -0.794566 -0.00794182 0.559657 -0.828724 0.00112062 0.503773 -0.863834 -0.00204901 0.773251 -0.634093 0.00304452 0.759218 -0.650791 0.00762754 0.715962 -0.698084 -0.00883334 0.665168 -0.746652 0.00788373 0.598744 -0.800857 -0.0115335 -0.000108074 -1 2.34485e-05 9.88583e-05 -1 7.73161e-06 7.18327e-06 -1 4.36682e-06 0.000104037 -1 -4.88011e-10 0.000104015 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.198439 0.980113 0 -0.227974 0.973637 0.00763832 -0.573944 0.818865 -0.00700416 -0.565965 0.824378 -0.00917386 -0.869176 0.494331 0.0130516 -0.768338 0.638849 -0.0390935 -0.990774 0.129025 0.0414598 -0.963776 0.266713 0 0.99604 -0.0889107 0 0.98307 -0.183199 -0.00353102 0.963457 -0.267862 -0.000196131 0.897882 -0.440236 0.000185716 0.725198 -0.688541 2.52115e-05 0.845283 -0.534319 -0.000501884 0.786117 -0.618014 -0.00887856 0.840118 -0.542387 -0.00427259 0.587414 -0.809286 -0.000733885 0.432227 -0.90164 -0.0150017 0.576815 -0.816875 -0.000367465 0.0460354 -0.99894 0 0.206031 -0.97854 -0.00319434 0.221496 -0.975159 -0.00205213 0.379012 -0.925392 5.67519e-05 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -9.78244e-05 1 0 -9.78244e-05 1 0 -0.00010846 1 5.46385e-07 -9.56493e-05 1 0 -8.88793e-05 1 2.48905e-07 -0.000107779 1 6.2233e-07 -9.67398e-05 1 8.67337e-07 -0.0257629 0.999668 0 -0.0259361 0.999664 5.80152e-05 -0.136696 0.990613 -0.000101151 -0.137003 0.990571 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 -1.95896e-05 -1 8.24886e-06 1.93449e-08 -1 8.25404e-06 8.32655e-05 -1 0 1 0 0 1 0 0 1 0 0 1 0 0 -0.537461 0.843288 4.19663e-07 -0.54333 0.839516 -0.00239428 -0.626938 0.779068 0.00140271 -0.609576 0.792706 0.00587976 -0.68164 0.731635 -0.00877903 -0.667898 0.744247 -0.00313008 -0.753318 0.657646 0.00366272 -0.759973 0.649955 0 -0.963731 0.266876 -0.000764387 -0.986088 0.166223 0.000288099 -0.254455 -0.967085 -1.34597e-06 -0.150756 -0.988526 -0.00939837 -0.332813 -0.942991 -0.00201013 -0.634302 -0.773077 0.0037166 -0.464951 -0.885267 -0.0110848 -0.590191 -0.807258 -0.00303301 -0.721681 -0.692226 4.69634e-05 -0.804981 -0.593301 -5.66521e-05 -0.932986 -0.359881 0.00471626 -0.818098 -0.57491 -0.0139475 -0.918874 -0.394548 -0.00159211 -0.999982 -0.00579143 0.0013519 -0.98622 -0.165325 -0.00621439 -0.999777 -0.021073 -0.00101263 -0.819284 0.573387 0 -0.870198 0.492689 0.00352974 -0.947289 0.320335 -0.00545917 -0.882316 0.470656 -0.000875871 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.339915 0.632283 -0.696187 -0.310114 0.633833 -0.70858 -0.313964 0.633057 -0.707577 -0.319514 0.632084 -0.705961 -0.325237 0.631476 -0.703889 -0.330743 0.631379 -0.701405 -0.464445 0.532163 -0.70788 -0.413417 0.568204 -0.711499 -0.393521 0.579629 -0.713563 -0.363168 0.61809 -0.69719 -0.303664 0.635242 -0.710109 -0.561664 0.471316 -0.679997 -0.562185 0.471393 -0.679513 -0.610504 0.431599 -0.664084 -0.616828 0.438128 -0.653886 -0.561237 0.471187 -0.680438 -0.529556 0.459236 -0.713213 -0.548918 0.469996 -0.691226 -0.609397 0.448442 -0.653861 -0.599436 0.447204 -0.663841 -0.394804 0.456242 -0.797479 -0.45393 0.477784 -0.75211 -0.48291 0.493504 -0.723361 -0.474537 0.49863 -0.725385 -0.532594 0.4723 -0.702336 -0.285263 0.445099 -0.84883 -0.373591 0.489084 -0.788179 -0.368724 0.491269 -0.789112 -0.250535 0.611648 -0.750412 -0.308863 0.444462 -0.840867 -0.27938 0.433319 -0.856844 -0.293984 0.423644 -0.856796 -0.399227 0.479297 -0.781596 -0.320315 0.502604 -0.802987 -0.280781 0.512333 -0.811589 -0.308354 0.495486 -0.812041 -0.315593 0.491389 -0.81175 -0.000297347 0.72391 -0.689895 -0.00686895 0.724622 -0.689112 -0.0178675 0.726464 -0.686973 -0.0251141 0.72811 -0.685 -0.0270564 0.728732 -0.684265 0.00933383 0.669509 -0.742746 0.0643986 0.656377 -0.75168 -0.0204606 0.725519 -0.687898 -0.0262981 0.728485 -0.684557 -0.000386453 0.431816 -0.901961 -0.00227709 0.432126 -0.90181 -0.00341856 0.434279 -0.900772 0.00176327 0.439414 -0.898283 -0.00402808 0.454109 -0.890937 -0.0268439 0.472004 -0.881188 -0.0865299 0.537546 -0.838783 0.179431 0.477641 -0.860037 -0.0048585 0.580406 -0.814313 -0.00178485 0.485638 -0.874158 -0.0176551 0.478053 -0.878154 -0.0390243 0.47815 -0.877411 -0.0871115 0.196527 -0.976621 -0.0215837 0.72365 -0.68983 -0.00356531 0.716842 -0.697227 -0.0193584 0.720633 -0.693047 -0.0254738 0.771593 -0.635607 -0.155172 0.66838 -0.727454 -0.102369 0.637871 -0.76331 -0.33065 0.553779 -0.764199 -0.111671 0.711529 -0.693726 -0.112822 0.710761 -0.694327 -0.115069 0.709554 -0.695193 -0.117089 0.708561 -0.695867 -0.120689 0.706934 -0.696907 -0.124007 0.70565 -0.697625 -0.116481 0.473595 -0.873006 -0.112964 0.472309 -0.874164 -0.106964 0.469744 -0.876299 -0.098492 0.464998 -0.879816 -0.103868 0.638517 -0.762567 -0.112961 0.583446 -0.804258 -0.13582 0.573118 -0.808139 -0.145667 0.495345 -0.856396 -0.0648882 0.579224 -0.812582 -0.0284194 0.58283 -0.812097 -0.0259375 0.58193 -0.812825 -0.146444 0.520173 -0.841412 0.00883167 0.529436 -0.848304 -0.100856 0.473325 -0.875095 -0.125857 0.476525 -0.870106 -0.136601 0.45404 -0.880448 -0.085986 0.719223 -0.689438 -0.0716184 0.715153 -0.695289 0.0115024 0.680528 -0.732632 -0.128326 0.681761 -0.720232 -0.03216 0.648158 -0.760827 -3.22972e-06 0.661441 -0.749997 0.0655387 0.656329 -0.751623 -0.419333 0.0467056 -0.906631 -0.881306 0.136754 -0.452326 -0.897127 0.15436 -0.413928 -0.879685 0.0933637 -0.466303 -0.874376 0.0694109 -0.48026 -0.870068 0.0244207 -0.492327 -0.868832 -0.0532515 -0.492235 -0.824368 0.233989 -0.515429 -0.844913 0.222109 -0.48661 -0.843348 0.227198 -0.486975 -0.856261 0.204322 -0.474415 -0.855159 0.209174 -0.474288 -0.860023 0.195176 -0.471451 -0.828122 0.224923 -0.513443 -0.781504 0.250455 -0.571423 -0.784169 0.123347 -0.608166 -0.589303 0.187316 -0.785898 -0.608496 0.481011 -0.631159 -0.619234 -0.0469278 -0.783803 -0.695313 0.280792 -0.661586 -0.426769 0.151335 -0.891609 -0.481753 0.237134 -0.843612 -0.479975 0.23912 -0.844065 -0.525306 0.209475 -0.824727 -0.427623 0.0873009 -0.899732 -0.391078 0.0354846 -0.919673 -0.42693 0.0322443 -0.90371 -0.41524 0.00853424 -0.909672 -0.368233 0.0271045 -0.929338 -0.389288 0.0365675 -0.92039 -0.388787 0.0430432 -0.920321 -0.408038 0.056885 -0.911191 -0.406961 0.0952907 -0.908462 -0.35831 0.176267 -0.916812 -0.391748 0.192655 -0.899677 -0.38957 0.190515 -0.901077 -0.434451 0.175101 -0.883511 -0.45126 0.185473 -0.872905 -0.388132 0.171833 -0.905443 -0.395698 0.157233 -0.904821 -0.43144 0.156343 -0.888491 -0.429372 0.153102 -0.890056 -0.42575 0.130401 -0.895395 -0.313633 0.193304 -0.92966 -0.197603 -0.03477 -0.979665 -0.258849 0.408305 -0.875377 -0.00422502 0.130989 -0.991375 -0.0291772 0.117641 -0.992627 -0.0511522 0.195868 -0.979295 -0.0872189 0.1458 -0.985462 -0.167151 0.149997 -0.974455 -0.425501 -0.0261158 -0.904581 -0.346032 0.032515 -0.937659 -0.368018 0.017782 -0.929649 -0.336915 0.0254586 -0.941191 -0.310135 0.021069 -0.950459 -0.311659 0.0200941 -0.949982 -0.259229 0.0202446 -0.965604 -0.390328 0.00146246 -0.920675 -0.347563 0.0416 -0.936733 -0.358409 0.0356465 -0.932884 -0.365077 0.0332384 -0.930384 -0.366159 0.0330634 -0.929965 -0.353459 0.0349109 -0.934799 -0.349854 0.0343518 -0.936174 -0.353658 0.0351736 -0.934713 -0.332804 0.0245167 -0.942677 -0.321845 0.0129943 -0.946703 -0.316823 0.00609339 -0.948465 -0.284501 0.025942 -0.958325 -0.260637 0.0241654 -0.965135 -0.192401 0.0023958 -0.981313 -0.155244 0.12605 -0.979801 -0.0922902 -0.00296326 -0.995728 -0.0205336 0.0108027 -0.999731 -0.0184905 0 -0.999829 -0.262464 0.0149756 -0.964825 -0.154671 0.0114196 -0.9879 -0.151935 0.000967666 -0.98839 -0.076756 0.00263475 -0.997046 -0.0210595 -0.0177941 -0.99962 -0.0243117 0 -0.999704 -0.498723 -0.00993262 -0.866704 -0.443953 0.0462752 -0.894854 -0.396408 0.0427326 -0.91708 -0.404107 0.0354302 -0.914025 -0.387879 0.039337 -0.92087 -0.370534 0.0401665 -0.92795 -0.418874 0.0381866 -0.907241 -0.443065 0.0403358 -0.895582 -0.43553 0.0393982 -0.899312 -0.421482 0.0366533 -0.906096 -0.433271 0.040825 -0.900339 -0.4326 0.0402449 -0.900688 -0.469617 0.0346027 -0.882192 -0.486082 0.043932 -0.872809 -0.493145 0.0408016 -0.86899 -0.563627 0.0390176 -0.825108 -0.518283 0.181282 -0.835775 -0.586943 0.0444096 -0.808409 -0.665077 0.058911 -0.744448 -0.864215 0.086332 -0.49566 -0.670314 0.0396319 -0.741019 -0.749683 0.0727544 -0.657786 -0.758881 0.203138 -0.618736 -0.810952 0.038923 -0.583817 -0.831508 0.0640814 -0.551804 -0.844798 0.057815 -0.531953 -0.843872 0.0555324 -0.533664 -0.867265 0.0773558 -0.491801 -0.869018 0.0783291 -0.488542 -0.869695 0.0775 -0.487468 -0.870965 0.0761241 -0.485412 -0.876705 0.082748 -0.473857 -0.877142 0.0892983 -0.471855 -0.872825 0.0816157 -0.481161 -0.870548 0.0750334 -0.486329 -0.870771 0.0780251 -0.485458 -0.858627 0.0801273 -0.5063 -0.852555 0.067301 -0.518287 -0.849046 0.0468204 -0.52624 -0.83736 0.0737078 -0.54166 -0.799167 0.0809658 -0.595632 -0.802585 0.0655227 -0.592928 -0.730246 0.0858372 -0.67777 -0.739568 0.0435523 -0.671672 -0.678659 0.0783704 -0.73026 -0.685667 0.0697576 -0.724565 -0.62304 0.0677374 -0.779251 -0.637123 0.0156609 -0.770603 -0.531149 0.102789 -0.841021 0.0230822 0.0731092 -0.997057 -0.0145003 0.104428 -0.994427 0.0272048 0.11387 -0.993123 -0.00556304 0.120186 -0.992736 0.000303244 0.131028 -0.991379 0.000198256 0.130974 -0.991386 0.00112795 0.130974 -0.991385 0.0102865 0.133118 -0.991047 -0.00762355 0.0817938 -0.99662 0 0.0607017 -0.998156 0 0.049427 -0.998778 0 0.049427 -0.998778 0 0.0195231 -0.999809 0.015189 0.0140935 -0.999785 0.00082443 0.00187388 -0.999998 0 0.00021933 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.978879 0.203976 0.0137913 0.997298 -0.0727887 -0.00992915 0.996701 0.0809342 0.0060092 0.999405 -0.0344789 -9.80386e-09 0.94501 0.32704 -2.18319e-05 0.965704 0.259628 0.00291211 0.99874 0.0491436 -0.0101893 0.906718 0.421737 1.96561e-05 0.86091 0.508734 0.00479689 0.872064 0.489385 0.00262997 0.783516 0.62137 -0.00135886 0.776352 0.630299 -0.000799313 0.724921 0.688832 0.000400374 0.660248 0.751044 0.00249481 0.57532 0.817806 0.0141706 0.627846 0.778327 0.00410324 0.444878 0.895589 -0.00171346 0.424267 0.905537 -0.000337431 0.18514 0.982712 0.00109269 0.190131 0.981759 -3.57786e-06 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.258818 0.965926 0 -0.258818 0.965926 0 -0.707109 0.707105 0 -0.707109 0.707105 0 -0.965925 0.258823 0 -0.965925 0.258823 0 -0.976331 -0.216282 0 -0.994265 -0.0997302 0.0386234 -0.953545 -0.301244 0.00181965 -0.826471 -0.562974 -0.00260402 -0.793355 -0.608649 0.0115605 -0.666627 -0.745391 -0.00104119 -0.501425 -0.865193 0.00369441 -0.0865154 -0.996251 0 -0.174305 -0.984625 0.0114525 -0.260311 -0.965525 -0.000325009 -0.490053 -0.871692 0.000539827 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.996352 -0.0853432 -2.40848e-08 0.996352 -0.0853446 5.06956e-07 0.996351 -0.085346 0 0.982949 -0.183877 0 0.982325 -0.187181 -0.00116573 0.997618 -0.0689821 0 0.993227 -0.116181 0.00112368 0.993901 -0.110269 -0.000820419 0.997355 -0.0726909 4.43962e-05 0.99756 -0.0698183 -2.8435e-06 0.99749 -0.0708145 1.17207e-05 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.707125 -0.707089 0 0.707125 -0.707089 0 0.25881 -0.965928 0 0.25881 -0.965928 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 0.195764 0.980651 0 0.167558 0.985859 0.00255179 0.422784 0.90623 -0.00092519 0.589944 0.807413 -0.00709022 0.483915 0.875096 0.00574663 0.710553 0.703642 -0.00156386 0.668115 0.744058 2.29383e-06 0.768334 0.640049 -3.87482e-06 0.876801 0.480795 -0.00754913 0.783547 0.621289 0.00743872 0.932504 0.361137 -0.00413532 0.898958 0.438036 -3.57063e-06 0.972064 0.234716 1.813e-06 0.959769 0.280781 0.00239643 0.997918 0.0644568 -0.002428 0.993772 0.111432 -1.06576e-07 0 1 0 0 1 0 0 1 0 0 1 0 1.10887e-06 1 -9.36936e-07 5.44295e-09 1 -9.37549e-07 -9.44243e-06 1 -8.93969e-07 0 1 0 0 1 0 0.0907229 -0.995876 0 0 -0.999956 0.00935321 -0.0225703 -0.999701 0.00935341 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.996352 0.085337 -2.04162e-08 -0.996352 0.0853334 -7.32593e-07 -0.996352 0.0853435 -5.07534e-07 -0.996351 0.0853464 0 -0.964473 -0.264181 -0.00019035 -0.916438 -0.400176 6.26451e-05 -0.228595 -0.973522 1.17308e-05 -0.105938 -0.994334 -0.00877503 -0.257149 -0.966369 -0.00228047 -0.615271 -0.788305 0.0042095 -0.442225 -0.896833 -0.0113313 -0.561596 -0.827398 -0.00477535 -0.669977 -0.742382 -0.000820118 -0.856968 -0.515369 0.00139691 -0.762783 -0.646624 -0.00629356 -0.846128 -0.532978 -0.00120758 -0.996263 0.0863687 -2.0663e-08 -0.999633 -0.0264179 0.00598603 -0.972558 -0.232593 -0.00558762 -0.9998 -0.0200011 -0.000353298 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 6.97834e-07 -1 -2.9884e-07 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.988921 0.148442 0 -0.985036 0.172295 0.00439062 -0.980613 0.195952 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.000914868 0.00697897 -0.999975 9.3887e-05 0.0460871 -0.998937 -0.00490874 0.0469701 -0.998884 -0.0128423 0.0494912 -0.998692 -0.0162616 0.051103 -0.998561 -0.0176577 0.0518409 -0.998499 -0.0181188 0.0521374 -0.998476 -0.0176272 0.0517616 -0.998504 -0.000777992 0.00700233 -0.999975 -0.00124869 0.0018477 -0.999998 -0.0165362 0.0508465 -0.99857 0.012367 0.0223803 -0.999673 -0.00758326 0.00386715 -0.999964 -0.00559669 0.0053261 -0.99997 -0.0030365 0.00635783 -0.999975 -0.00198478 0.0066893 -0.999976 -0.109552 0.0835832 -0.990461 -0.0338366 0.0309161 -0.998949 -0.201816 0.0818186 -0.976 -0.27674 0.0352698 -0.960297 -0.275346 0.0375268 -0.960613 -0.194046 0.123016 -0.973249 -0.253199 0.0278721 -0.967013 -0.267027 0.0223407 -0.96343 -0.276711 0.0275674 -0.960558 -0.279031 0.11084 -0.953864 -0.288796 0.115488 -0.9504 -0.298695 0.107809 -0.94824 -0.297345 0.11148 -0.948239 -0.295164 0.113799 -0.948645 -0.050815 0.00335634 -0.998702 -0.134231 0.0267784 -0.990588 -0.163482 0.0501214 -0.985272 -0.15612 0.0499255 -0.986476 -0.226239 0.0522875 -0.972667 -0.213347 0.0589031 -0.975199 -0.234221 0.0640923 -0.970068 -0.265608 0.0683239 -0.961657 -0.297129 0.103062 -0.949259 -0.0248097 0.046033 -0.998632 -0.050873 0.00717271 -0.998679 -0.00153438 0.0429132 -0.999078 -0.576429 0.0566953 -0.815178 -0.62285 0.12471 -0.772338 -0.689595 0.0529964 -0.722253 -0.75955 0.0798666 -0.645527 -0.734863 0.0938364 -0.671693 -0.739852 0.101259 -0.665105 -0.740079 0.101751 -0.664778 -0.439573 0.0992809 -0.892703 -0.556424 0.0386511 -0.829999 -0.349993 0.0359533 -0.936062 -0.355366 0.0378945 -0.933959 -0.3501 0.0354495 -0.936041 -0.357584 0.0364899 -0.933168 -0.365728 0.0380573 -0.929944 -0.378258 0.0303612 -0.925202 -0.377489 0.0417911 -0.925071 -0.452704 0.0762067 -0.888398 -0.453535 0.0328635 -0.890632 -0.43467 -0.0382358 -0.899778 -0.376242 0.032244 -0.92596 -0.378418 0.0289034 -0.925184 -0.520284 0.0550249 -0.852219 -0.449649 -0.00609528 -0.893185 -0.442546 -0.0188132 -0.896549 -0.4022 0.0299256 -0.915063 -0.385661 0.0365155 -0.921918 -0.62536 0.12102 -0.770895 -0.629994 0.013839 -0.776477 -0.627448 0.0180245 -0.77845 -0.736117 0.0905654 -0.670768 -0.732942 0.0773745 -0.675876 -0.733361 0.0740657 -0.675793 -0.745763 0.0473218 -0.664528 -0.740906 0.0528591 -0.669525 -0.694236 0.091139 -0.713954 -0.737787 0.063567 -0.672033 -0.743046 0.0524907 -0.667178 -0.746096 0.046814 -0.66419 -0.522612 0.0582381 -0.850579 -0.408231 0.124439 -0.904357 -0.417293 0.133848 -0.898861 -0.410646 0.113937 -0.904648 -0.412388 0.111602 -0.904147 -0.495088 0.00883779 -0.868798 -0.480367 0.0754656 -0.873815 -0.491026 0.0631847 -0.868851 -0.466713 0.0887432 -0.879945 -0.452119 0.102367 -0.886064 -0.444146 0.109314 -0.889261 -0.433925 0.117728 -0.893224 -0.420951 0.127157 -0.898126 -0.433676 0.126961 -0.89208 -0.489239 0.0573944 -0.870259 -0.436491 0.498509 -0.748976 -0.553298 0.104557 -0.826395 -0.570622 0.122863 -0.81197 -0.730704 0.128486 -0.670494 -0.718391 0.11139 -0.686663 -0.727446 0.0999905 -0.67884 -0.66565 0.150304 -0.730972 -0.712832 0.0166591 -0.701137 -0.633481 0.154988 -0.758077 -0.748888 0.0833698 -0.657432 -0.719898 0.149676 -0.677749 -0.718341 0.134988 -0.682469 -0.717673 0.120494 -0.685877 -0.717476 0.0965474 -0.68986 -0.717569 0.0951968 -0.689951 -0.706245 0.127374 -0.696415 -0.698405 0.138877 -0.7021 -0.70644 0.127362 -0.69622 -0.713828 0.117374 -0.690415 -0.444177 0.198606 -0.873649 -0.544134 0.0793247 -0.83524 -0.629878 0.078517 -0.772715 -0.618583 0.106286 -0.778498 -0.689447 0.0237945 -0.723945 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.00874963 0 -0.999962 -0.0220763 0.0176768 -0.9996 -0.100028 -0.0347554 -0.994377 -0.089951 -0.0496789 -0.994706 -0.226633 0.0238595 -0.973688 -0.226636 0.0232953 -0.973701 -0.232197 0.0150262 -0.972553 -0.241052 0.00437777 -0.970502 -0.245408 0.00016132 -0.96942 -0.24688 -0.00113246 -0.969045 -0.246532 -0.00086446 -0.969134 -0.242436 0.00157271 -0.970166 -0.173903 0.0339209 -0.984178 -0.152561 0.0974108 -0.983482 -0.244757 0.0271403 -0.969204 -0.24613 0.0249095 -0.968917 -0.148845 0.125108 -0.980914 -0.222305 0.0251097 -0.974654 -0.236423 0.0195107 -0.971454 -0.244715 0.0238692 -0.969301 -0.18391 -0.0392023 -0.982161 -0.100168 0.049493 -0.993739 -0.0769108 0.0237316 -0.996755 -0.00887232 -0.0211083 -0.999738 -0.0194997 0 -0.99981 -0.220839 -0.0641801 -0.973196 -0.137865 0.184269 -0.973159 -0.0129157 -0.111857 -0.99364 -0.0273788 0 -0.999625 -0.282082 0.0265764 -0.959022 -0.282794 0.0251016 -0.958852 -0.28084 0.0161958 -0.959618 -0.280844 0.014621 -0.959642 -0.273454 0.0123413 -0.961806 -0.273458 0.0102299 -0.96183 -0.271854 0.00266892 -0.962335 -0.273469 -0.000569366 -0.961881 -0.224893 0.00266747 -0.97438 -0.199787 0.0076895 -0.979809 -0.181181 -0.00271456 -0.983446 -0.0989139 -0.0686734 -0.992724 -0.283299 0.06299 -0.956961 -0.300362 0.115044 -0.946862 -0.285154 0.0513053 -0.957108 -0.313712 0.0594387 -0.947656 -0.310766 0.0351778 -0.949835 -0.310609 0.0355091 -0.949874 -0.30838 0.024992 -0.950935 -0.308375 0.0260034 -0.95091 -0.295528 0.0220113 -0.95508 -0.295526 0.022603 -0.955067 -0.293508 0.0128837 -0.95587 -0.293892 0.0121043 -0.955762 -0.291255 -0.0110728 -0.956581 -0.297197 -0.0550816 -0.953226 -0.29759 -0.0570154 -0.95299 -0.221598 0.00621935 -0.975118 -0.197666 0.0121321 -0.980194 -0.183368 0.0121355 -0.98297 -0.102767 -0.0313811 -0.99421 -0.108898 0.00141537 -0.994052 -0.0145378 0.00141665 -0.999893 -0.0142793 0 -0.999898 -0.328883 0.123772 -0.936225 -0.354893 0.211039 -0.910776 -0.239804 0.0436211 -0.969841 -0.152695 -0.0244721 -0.98797 -0.127467 -0.100126 -0.986776 -0.0369751 0.110887 -0.993145 -0.0168309 0 -0.999858 -0.307434 0.0384878 -0.950791 -0.358745 0.0301237 -0.932949 -0.391913 0.0375572 -0.919236 -0.390611 0.0385075 -0.91975 -0.418952 0.0363004 -0.907283 -0.501094 0.0585859 -0.863407 -0.507561 0.034042 -0.860943 -0.633984 0.0583814 -0.771139 -0.641387 0.0964003 -0.761137 -0.691219 0.0519014 -0.720779 -0.745489 0.0539788 -0.664329 -0.745177 0.0554314 -0.664559 -0.813552 0.04978 -0.579358 -0.81264 0.0544062 -0.580221 -0.850016 0.049173 -0.524456 -0.854653 0.0640231 -0.515238 -0.87346 0.0352999 -0.485615 -0.870603 0.0652788 -0.487636 -0.881071 0.0350218 -0.471685 -0.878037 0.0542883 -0.475505 -0.883859 0.0367267 -0.466309 -0.853238 0.0321846 -0.520528 -0.87053 0.0340209 -0.490938 -0.88128 0.0241022 -0.47198 -0.867845 0.0339842 -0.495672 -0.878929 0.0326786 -0.475832 -0.896595 0.0333378 -0.441594 -0.891506 0.0300365 -0.452012 -0.893934 0.0314437 -0.447095 -0.88393 0.0419725 -0.465732 -0.882745 0.0487896 -0.467312 -0.898912 0.0363601 -0.436617 -0.888184 0.0218664 -0.458968 -0.888151 0.0209641 -0.459074 -0.886984 0.0123071 -0.461636 -0.887294 0.0235929 -0.460601 -0.883576 0.0112133 -0.468154 -0.877587 0.0132102 -0.479236 -0.870777 0.0114942 -0.491544 -0.861866 -0.012141 -0.506991 -0.868199 -0.0334454 -0.495087 -0.849947 0.0111015 -0.526751 -0.814563 0.0122227 -0.579946 -0.815131 0.00858854 -0.579213 -0.742755 0.0166356 -0.669356 -0.740928 0.00584216 -0.671559 -0.627744 0.021642 -0.778119 -0.632356 -0.00111567 -0.774677 -0.54104 0.0147606 -0.840867 -0.466935 -0.0482446 -0.882975 -0.271138 -0.020601 -0.96232 -0.270037 -0.0127842 -0.962765 -0.285977 -0.0347203 -0.957607 -0.287101 -0.0377361 -0.957157 -0.362021 0.0122058 -0.93209 -0.454313 -0.00281842 -0.890838 -0.864359 0.0026715 -0.502868 -0.846416 0.0374117 -0.531207 -0.814932 0.0245395 -0.579037 -0.812903 0.0355409 -0.581313 -0.781958 0.0364019 -0.622268 -0.743701 0.0270931 -0.667964 -0.740597 0.0420298 -0.670634 -0.635281 0.0303827 -0.771683 -0.221655 0.0803173 -0.971812 -0.281206 0.0104956 -0.95959 -0.343732 0.0245309 -0.938747 -0.364782 0.0215325 -0.930844 -0.380353 0.0300279 -0.924354 -0.390963 0.0266083 -0.920022 -0.487102 0.0255031 -0.872973 -0.485911 0.0303335 -0.873482 -0.636577 0.0375652 -0.770298 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.794543 0.607207 -0.00124893 0.857267 0.514861 0.0033723 0.896089 0.443867 -0.00239203 0.954643 0.297745 0.00227868 0.977426 0.211247 -0.00368633 0.996174 0.0873674 0.00229824 0.99848 0.0551069 0.000975266 0.999972 0.00750727 0 0.734454 0.678657 0.00114898 0.664554 0.747222 0.0051151 0.652027 0.758161 0.00726218 0.469601 0.882868 -0.00427143 0.42965 0.902995 -0.000996714 0.103084 0.994673 0 0.19971 0.979822 0.00809146 0.261021 0.96533 0.00265722 0.328092 0.944646 0.000470164 -1 0 0 -1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707108 0.707105 0 -0.707108 0.707105 0 -0.965925 0.258823 0 -0.965925 0.258823 0 -0.965925 -0.258823 0 -0.965925 -0.258823 0 -0.707109 -0.707105 0 -0.707109 -0.707105 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.999627 -0.027295 0 0.999051 -0.0414261 -0.0134367 0.999494 -0.0318042 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.707126 -0.707088 0 0.707126 -0.707088 0 0.258811 -0.965928 0 0.258811 -0.965928 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0.25881 0.965928 0 0.25881 0.965928 0 0.707126 0.707088 0 0.707126 0.707088 0 0.965924 0.258825 0 0.965924 0.258825 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.999846 0.0175554 -1.02769e-09 -0.999776 0.021184 0.000309353 -0.999749 0.0223963 -1.32175e-09 -1 -0.000976622 5.71714e-11 -0.659705 -0.751525 -6.45325e-05 -0.185596 -0.982626 1.7204e-06 -0.0935785 -0.995599 -0.00510987 -0.241759 -0.970336 -0.000696564 -0.5482 -0.836346 0.00155512 -0.412699 -0.910828 -0.0084353 -0.54673 -0.837306 -0.00239494 -0.79572 -0.60559 -0.00952815 -0.937686 -0.347318 0.0107192 -0.812058 -0.583577 0.000151231 -0.864544 -0.502531 -0.00500797 -0.890838 -0.454311 -0.00317129 -0.993956 -0.109662 0.00506356 -0.954834 -0.297099 -0.00489976 -0.994965 -0.10022 -0.000380827 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 -0.999197 0.0400544 0 -0.99912 0.0419319 0.000323203 -0.99904 0.043816 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 3.24927e-07 1 -1.04975e-07 3.13132e-07 1 -8.44908e-08 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.0949139 0.0720986 -0.992871 -0.10892 0.0080862 -0.994018 -0.0926506 0.0922566 -0.991416 -0.175964 0.00805175 -0.984364 -0.174827 0.00994152 -0.984549 -0.156888 0.00891902 -0.987576 -0.168091 0.00454293 -0.985761 -0.174713 0.00771917 -0.984589 -0.187006 0.00979576 -0.98231 -0.18207 0.00804305 -0.983253 -0.185835 0.00966306 -0.982533 -0.179574 0.00880538 -0.983705 -0.0134595 0 -0.999909 -0.0125409 0.000904231 -0.999921 -0.0471013 0.000876738 -0.99889 -0.0428532 0.00145716 -0.99908 -0.102848 0.000386567 -0.994697 -0.119097 -0.0136499 -0.992789 -0.164393 0.00486413 -0.986383 -0.172147 0.00732173 -0.985044 -0.321761 0.0286376 -0.946388 -0.293289 0.0222179 -0.955766 -0.299493 0.0244565 -0.953785 -0.294845 0.0223588 -0.955284 -0.301928 0.0233497 -0.953045 -0.310663 0.0250794 -0.950189 -0.313475 0.0235097 -0.949306 -0.339227 0.0362989 -0.940004 -0.395696 0.0768414 -0.915161 -0.396452 0.0230467 -0.917766 -0.375992 -0.0495556 -0.925297 -0.312007 0.0235317 -0.949788 -0.313607 0.0209965 -0.949321 -0.484775 0.0387074 -0.873782 -0.409988 0.0142473 -0.91198 -0.384102 -0.0305481 -0.922785 -0.337547 0.0226613 -0.941036 -0.321467 0.0289681 -0.946478 -0.55551 0.0452386 -0.830278 -0.592152 -0.00984528 -0.805766 -0.62322 0.0238777 -0.781682 -0.762863 0.0475403 -0.64481 -0.68242 0.0699656 -0.727604 -0.723246 0.0209479 -0.690273 -0.734058 0.0330825 -0.67828 -0.750195 0.0460391 -0.659612 -0.742336 0.00237112 -0.670023 -0.766528 0.0480678 -0.640409 -0.764798 0.0472747 -0.642533 -0.763943 0.0468071 -0.643584 -0.767591 0.0472734 -0.639194 -0.767255 0.0436202 -0.639857 -0.723433 0.0127359 -0.690277 -0.694096 0.0844424 -0.714913 -0.74516 0.0480398 -0.665153 -0.767038 0.0422563 -0.640209 -0.765324 0.0431531 -0.642197 -0.763516 0.0430251 -0.644354 -0.757036 0.0437062 -0.651909 -0.418548 0.0429375 -0.907179 -0.493396 0.0353007 -0.869088 -0.591045 0.0465753 -0.805293 -0.559977 0.114531 -0.820554 -0.63335 0.0538037 -0.771993 -0.764415 0.0209431 -0.644384 -0.768746 0.0203474 -0.639231 -0.763263 0.023569 -0.645658 -0.763261 0.0236059 -0.645659 -0.759278 0.0142742 -0.65061 -0.74655 0.0240714 -0.664894 -0.735924 0.0468402 -0.675442 -0.69567 0.0941427 -0.712166 -0.72095 0.00439249 -0.692973 -0.636476 0.0259298 -0.77086 -0.277335 0.0115021 -0.960704 -0.283766 0.0138353 -0.958794 -0.279885 0.0120888 -0.959957 -0.286684 0.012971 -0.957937 -0.295361 0.014577 -0.955275 -0.306092 0.0177841 -0.951836 -0.327421 0.026407 -0.944509 -0.379427 0.0647018 -0.922957 -0.412168 0.0191846 -0.910906 -0.491855 0.0178265 -0.870495 -0.335438 -0.0101509 -0.942008 -0.314153 0.0134967 -0.949277 -0.298394 0.0196294 -0.954241 -0.290505 0.0145736 -0.956763 -0.637129 0.0239804 -0.770384 -0.579821 -0.0165096 -0.814576 -0.578283 0.064 -0.813322 -0.565892 0.0392241 -0.823546 -0.290576 0.0121453 -0.956775 -0.289024 0.0146474 -0.95721 -0.352155 -0.0561984 -0.934253 -0.315298 0.0144126 -0.948883 -0.416569 -0.0710436 -0.906324 -0.378463 0.0221105 -0.925352 -0.494636 0.0251746 -0.868736 -0.566837 0.00762672 -0.823795 -0.746541 0.0254433 -0.664853 -0.762719 0.0243032 -0.646273 -0.762748 0.0262472 -0.646163 -0.758275 0.035202 -0.650983 -0.698875 0.0397232 -0.71414 -0.720701 0.00216333 -0.693242 -0.743308 0.0177225 -0.668715 -0.762722 0.025941 -0.646206 -0.763399 0.0276324 -0.645335 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.107388 0.0813061 -0.990887 -0.122445 0.0151815 -0.992359 -0.104748 0.103766 -0.989071 -0.191886 0.0154429 -0.981296 -0.190716 0.0173753 -0.981491 -0.171453 0.0157978 -0.985066 -0.183309 0.0111459 -0.982992 -0.190603 0.0147018 -0.981557 -0.209471 0.0159643 -0.977684 -0.204507 0.0142012 -0.978762 -0.208805 0.0160495 -0.977826 -0.202221 0.0151586 -0.979223 -0.0153937 0 -0.999882 -0.0140441 0.0013199 -0.999901 -0.0968458 0.00189281 -0.995298 -0.0497992 0.0394317 -0.997981 -0.166793 -0.0372649 -0.985288 -0.134592 -0.0101277 -0.990849 -0.185838 0.0109088 -0.98252 -0.194316 0.0135896 -0.980845 -0.143195 0.0413087 -0.988832 -0.150241 0.154103 -0.976565 -0.0166713 -0.154678 -0.987824 -0.0369012 0 -0.999319 -0.2743 -0.00463154 -0.961633 -0.27346 -0.00830743 -0.961847 -0.273448 -0.0146403 -0.961775 -0.284656 -0.0111339 -0.958565 -0.280846 -0.0135129 -0.959658 -0.253015 -0.0205777 -0.967243 -0.235635 -0.0159322 -0.971711 -0.214142 -0.0129855 -0.976716 -0.20903 -0.0156141 -0.977785 -0.295835 -0.0173878 -0.955081 -0.29554 -0.0186835 -0.955148 -0.29551 -0.0260744 -0.954984 -0.308393 -0.0219573 -0.951006 -0.308356 -0.0293072 -0.95082 -0.308262 -0.0297922 -0.950835 -0.313135 -0.0395919 -0.948883 -0.264946 -0.0239334 -0.963966 -0.241982 -0.017965 -0.970115 -0.22108 -0.0283677 -0.974843 -0.223075 -0.0304113 -0.974327 -0.128111 0.0433595 -0.990812 -0.329632 -0.023393 -0.94382 -0.285484 -0.0336914 -0.957791 -0.288138 0.0204908 -0.95737 -0.299021 0.0528795 -0.95278 -0.29136 -0.00785005 -0.956581 -0.280822 -0.0213893 -0.959522 -0.289463 -0.0341941 -0.956578 -0.268264 -0.0197318 -0.963143 -0.282722 -0.0303907 -0.95872 -0.269239 0.0334966 -0.962491 -0.27803 0.0595662 -0.958724 -0.270896 0.00245966 -0.962606 -0.0142793 0 -0.999898 -0.0145378 -0.00141665 -0.999893 -0.0457899 -0.00141764 -0.99895 -0.110871 -0.00965665 -0.993788 -0.11041 -0.0121128 -0.993812 -0.194613 -0.0121331 -0.980805 -0.0988301 -0.0911294 -0.990923 -0.0278493 0.0816843 -0.996269 -0.013006 0 -0.999915 -0.19228 -0.00443665 -0.98133 -0.267375 -0.00886881 -0.963552 -0.270183 -0.00295073 -0.962805 -0.350039 -0.0102198 -0.936679 -0.357715 -0.00444309 -0.93382 -0.37654 -0.0096447 -0.92635 -0.474313 -0.00660967 -0.880331 -0.475377 -0.0113042 -0.87971 -0.633515 -0.0128612 -0.773623 -0.633858 -0.0112263 -0.773368 -0.74411 -0.0141243 -0.667908 -0.745079 -0.00880331 -0.666918 -0.816063 -0.0150727 -0.577767 -0.815654 -0.0122009 -0.578411 -0.847248 -0.0111621 -0.53108 -0.861206 -0.0381814 -0.50682 -0.857398 0.0232837 -0.514127 -0.876313 -0.02725 -0.480971 -0.873958 -0.00338079 -0.485989 -0.885084 -0.0227828 -0.464874 -0.885092 -0.00362195 -0.465403 -0.887439 -0.0225212 -0.460375 -0.87747 -0.0328096 -0.478508 -0.892582 -0.0327394 -0.449696 -0.890148 -0.0340548 -0.454397 -0.895389 -0.0314922 -0.444169 -0.888188 -0.0218723 -0.458959 -0.887821 -0.0128189 -0.460009 -0.895521 -0.0297216 -0.444025 -0.883952 -0.0419501 -0.465692 -0.884489 -0.0387778 -0.464947 -0.878788 -0.048067 -0.474785 -0.878192 -0.0495069 -0.475739 -0.872078 -0.0475179 -0.487054 -0.865601 -0.049303 -0.498301 -0.855981 -0.0684542 -0.512455 -0.859262 -0.0797528 -0.50528 -0.845087 -0.0499192 -0.532294 -0.812281 -0.0544281 -0.580721 -0.812541 -0.0568154 -0.580129 -0.745502 -0.0472256 -0.664828 -0.742141 -0.0623824 -0.667334 -0.691254 -0.0505063 -0.720844 -0.632332 -0.0931909 -0.769072 -0.31178 -0.0519722 -0.948732 -0.310242 -0.0416433 -0.949745 -0.331099 -0.0713609 -0.940894 -0.307178 -0.00563313 -0.951635 -0.401645 -0.0447492 -0.914702 -0.390173 -0.0263763 -0.920364 -0.506739 -0.0680704 -0.859408 -0.498398 -0.0246891 -0.866596 -0.639545 -0.0661426 -0.765903 -0.877257 -0.032764 -0.478901 -0.869417 -0.0333711 -0.492951 -0.868549 -0.0340619 -0.494432 -0.8604 -0.0330575 -0.508546 -0.850103 -0.0417536 -0.524958 -0.84893 -0.0384882 -0.527101 -0.811781 -0.0233068 -0.583497 -0.814379 -0.0456419 -0.578536 -0.74405 -0.0262533 -0.667608 -0.740085 -0.0451188 -0.670999 -0.687873 -0.0355786 -0.724958 -0.624823 -0.0777787 -0.776883 -0.347979 -0.0232145 -0.937215 -0.367958 -0.0257804 -0.929485 -0.376479 -0.021092 -0.926185 -0.393836 -0.0265803 -0.918796 -0.4861 -0.0255165 -0.873531 -0.487068 -0.0299196 -0.872851 -0.634367 -0.0393218 -0.772031 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.327347 -0.944902 0.00228856 0.0262063 -0.999657 8.49806e-08 0.235043 -0.971972 -0.00505711 0.111873 -0.993381 0.0260594 0.243405 -0.969899 0.0071518 0.445843 -0.894106 0.0423993 0.615779 -0.787728 -0.0173146 0.447104 -0.894478 -0.00291052 0.545524 -0.837882 0.0189068 0.65359 -0.756838 0.00405732 0.845697 -0.53362 -0.00682307 0.733493 -0.679121 0.0279643 0.999972 -0.00750496 5.14867e-10 0.799376 -0.600744 0.0102642 0.900904 -0.434014 -0.00170705 0.957077 -0.289828 0.00207073 0.958753 -0.284235 0.00163845 0.99654 -0.0830827 -0.00239697 0.988431 -0.151591 0.00493795 0.998481 -0.0550899 0.000975265 0.995691 0.0927338 0 0.982942 0.183879 0.00373212 0.990154 0.13998 0.000132032 0.92278 0.385327 -0.000229229 0.940944 0.338473 -0.00779984 0.822002 0.569463 0.00499573 0.837819 0.545944 0.0022202 0.737269 0.675598 -0.00118735 0.679498 0.733671 0.00302324 0.618574 0.78569 0.00760122 0.547928 0.836292 0.019772 0.634565 0.772867 0.00180508 0.420219 0.907422 -0.000960497 0.428973 0.903316 -0.00178078 0.171564 0.985165 0.00387306 0.18937 0.981906 0 -1 0 0 -1 0 0 -0.258819 0.965926 0 -0.258819 0.965926 0 -0.707108 0.707106 0 -0.707108 0.707106 0 -0.965925 0.258823 0 -0.965925 0.258823 0 -0.980786 -0.195087 0 -0.980786 -0.195087 0 -0.831466 -0.555576 0 -0.831466 -0.555576 0 -0.555569 -0.83147 0 -0.555569 -0.83147 0 -0.195091 -0.980785 0 -0.195091 -0.980785 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.999768 0.0215255 -1.47673e-09 0.999485 0.0317841 -0.00443085 0.999333 0.0365095 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 5.91461e-08 -1 -3.60918e-08 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 0.965924 -0.258826 0 0.965924 -0.258826 0 0.707127 -0.707087 0 0.707127 -0.707087 0 0.25881 -0.965928 0 0.25881 -0.965928 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0.258811 0.965928 0 0.258811 0.965928 0 0.707126 0.707088 0 0.707126 0.707088 0 0.965924 0.258825 0 0.965924 0.258825 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.999039 -0.0438297 0 -0.999039 -0.0438297 5.31805e-09 -0.999198 -0.040045 4.72598e-09 -0.999198 -0.040045 0 -0.917576 -0.397559 -0.000707418 -0.166997 -0.985957 0 -0.0838878 -0.996467 -0.00411488 -0.223983 -0.974593 -0.000416607 -0.453799 -0.891104 0.00067739 -0.51409 -0.857734 -0.00182628 -0.77814 -0.628086 0.00240449 -0.738835 -0.673886 -0.000687227 -0.893396 -0.449271 0.000251475 -0.985545 -0.169405 0.00160201 -0.963443 -0.267905 -0.00227961 -0.994294 -0.106678 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 -0.250023 0.96824 -1.15859e-05 -0.0709346 0.997387 -0.0136965 -0.205827 0.978575 -0.0051002 -0.629158 0.777249 0.00666176 -0.519507 0.854459 -0.00358544 -0.845694 0.533661 0.00265448 -0.789738 0.613441 -0.00213497 -0.927668 0.373405 0.000935806 -0.908107 0.418738 -4.9178e-05 -0.965614 0.25998 4.57997e-05 -0.970605 0.240678 0.000432422 -0.996631 0.0820198 -0.000394674 -0.998237 0.059352 3.4491e-09 -0.9998 -0.0199946 -1.17049e-09 -0.999693 -0.024759 0.00122106 -0.999775 -0.0211903 -6.60997e-10 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.0576916 -0.00268579 -0.998331 -0.0498379 -0.00155158 -0.998756 -0.0156738 -0.00160522 -0.999876 -0.0140441 0 -0.999901 -0.205121 -0.0157311 -0.97861 -0.198412 -0.0161801 -0.979985 -0.203628 -0.0135541 -0.978954 -0.203642 -0.0132481 -0.978956 -0.169552 -0.0202957 -0.985312 -0.107631 -0.0457636 -0.993137 -0.121912 -0.0162889 -0.992407 -0.133993 -0.000559804 -0.990982 -0.119352 0.0719737 -0.99024 -0.121239 0.0559527 -0.991045 -0.187224 -0.0118437 -0.982246 -0.193522 -0.0156692 -0.980971 -0.187033 -0.0180085 -0.982189 -0.19393 -0.0150062 -0.980901 -0.184908 -0.0162877 -0.982621 -0.176855 -0.0179391 -0.984074 -0.722543 -0.0280796 -0.690756 -0.316417 -0.00801109 -0.948586 -0.286612 -0.0143296 -0.95794 -0.294118 -0.0115341 -0.9557 -0.288251 -0.0142111 -0.95745 -0.296828 -0.0130335 -0.954842 -0.306004 -0.0112443 -0.951964 -0.378666 -0.0483534 -0.924269 -0.282593 -0.0128742 -0.959153 -0.335469 -0.000103614 -0.942051 -0.379545 0.0312687 -0.924645 -0.378215 -0.0113221 -0.925649 -0.354287 -0.0934313 -0.930458 -0.281107 -0.0115555 -0.959607 -0.282597 -0.0140396 -0.959136 -0.361096 -0.0779216 -0.929267 -0.304202 -0.0143576 -0.952499 -0.289405 -0.00866718 -0.957167 -0.724075 -0.0556427 -0.687473 -0.659788 0.00255446 -0.751447 -0.577883 -0.0730602 -0.812843 -0.587357 -0.0899007 -0.80432 -0.512375 -1.8819e-05 -0.858762 -0.723183 -0.0232208 -0.690266 -0.724643 -0.0302751 -0.688459 -0.728535 -0.0473111 -0.683372 -0.741614 -0.0687434 -0.667295 -0.738003 -0.0826073 -0.669722 -0.73354 -0.0674555 -0.676291 -0.730772 -0.0564168 -0.680286 -0.698876 -0.0397299 -0.714138 -0.741158 0.0359822 -0.670365 -0.738883 0.0301763 -0.673158 -0.734749 0.0175209 -0.678113 -0.729809 0.000288223 -0.683651 -0.72472 -0.0191495 -0.688778 -0.41751 -0.0231656 -0.908377 -0.494611 -0.0251854 -0.86875 -0.579793 -0.00437059 -0.814752 -0.566675 0.025409 -0.82355 -0.637117 -0.0239764 -0.770394 -0.765021 -0.0474868 -0.642252 -0.748137 -0.0219074 -0.663182 -0.756885 -0.0475999 -0.651812 -0.559116 0.0367563 -0.828274 -0.635533 -0.0350598 -0.771277 -0.720731 -0.075936 -0.689043 -0.698237 -0.00573247 -0.715844 -0.744185 -0.0411764 -0.666703 -0.30958 -0.0231981 -0.95059 -0.317623 -0.0201493 -0.948003 -0.309688 -0.0238697 -0.950538 -0.319894 -0.0222695 -0.947192 -0.329348 -0.0202181 -0.943992 -0.428441 -0.0317626 -0.903011 -0.396278 0.0183161 -0.917948 -0.353367 -0.0104176 -0.935427 -0.339882 -0.0166057 -0.940322 -0.33906 -0.0475104 -0.939564 -0.299633 -0.0250968 -0.953725 -0.298027 -0.0223958 -0.954295 -0.353586 -0.0848376 -0.931547 -0.319183 -0.0221751 -0.947434 -0.417136 -0.0925386 -0.904121 -0.396296 -0.045129 -0.917013 -0.493364 -0.0352978 -0.869107 -0.320169 -0.0264221 -0.946992 -0.305743 -0.0208674 -0.951886 -0.299631 -0.0247465 -0.953734 -0.590901 -0.0513191 -0.80511 -0.588849 -0.0914489 -0.803053 -0.563148 -0.0432833 -0.825222 -0.762635 -0.0430127 -0.645397 -0.754702 -0.0442151 -0.654576 -0.743499 -0.0492683 -0.66692 -0.721381 -0.0654202 -0.689441 -0.696353 -0.0256913 -0.71724 -0.633358 -0.05382 -0.771985 -0.764958 -0.0474469 -0.64233 -0.767543 -0.0468836 -0.639281 -0.767194 -0.0432394 -0.639956 -0.764557 -0.0435702 -0.643082 -0.766442 -0.0424972 -0.640906 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.0805947 -0.0585183 -0.995028 -0.0123941 0 -0.999923 -0.0134595 -0.0010419 -0.999909 -0.0471013 -0.000822846 -0.99889 -0.183551 -0.00966536 -0.982963 -0.176732 -0.011005 -0.984198 -0.182188 -0.00834701 -0.983228 -0.182234 -0.00745891 -0.983227 -0.101261 -0.00978382 -0.994812 -0.113651 0.00866858 -0.993483 -0.100821 0.0742941 -0.992127 -0.102676 0.057852 -0.993031 -0.165915 -0.00680172 -0.986117 -0.177907 -0.00816743 -0.984014 -0.172244 -0.0101936 -0.985002 -0.177349 -0.00800565 -0.984116 -0.169769 -0.00905431 -0.985442 -0.163796 -0.0102678 -0.986441 -0.159146 -0.0115646 -0.987187 -0.155134 -0.0128489 -0.98781 -0.142179 -0.0181723 -0.989674 -0.844991 -0.0519529 -0.53225 -0.865197 -0.0948801 -0.492375 -0.86856 -0.055642 -0.492451 -0.873117 -0.0955178 -0.478062 -0.876826 -0.0691681 -0.475806 -0.876572 -0.0808746 -0.474427 -0.876255 -0.0765787 -0.475723 -0.865379 -0.0821096 -0.494346 -0.869702 -0.0774883 -0.487457 -0.868065 -0.0796607 -0.490019 -0.863234 -0.0891365 -0.496872 -0.867272 -0.0772959 -0.491798 -0.850277 -0.0613228 -0.522751 -0.842456 -0.0633257 -0.535031 -0.839903 -0.0601635 -0.539392 -0.831509 -0.0640935 -0.551801 -0.426643 -0.0316555 -0.903866 -0.473425 -0.0384446 -0.879995 -0.481031 -0.0339949 -0.876044 -0.496978 -0.0407139 -0.866808 -0.526396 -0.0400058 -0.849298 -0.561402 -0.0986956 -0.821637 -0.587432 -0.0431488 -0.808123 -0.665049 -0.0595192 -0.744424 -0.67113 -0.0371958 -0.740406 -0.772058 -0.0869253 -0.629579 -0.719561 -0.29203 -0.63004 -0.811196 -0.0392143 -0.583458 -0.438749 -0.0443776 -0.897513 -0.42271 -0.0369995 -0.905509 -0.423459 -0.0371636 -0.905153 -0.434946 -0.0394076 -0.899594 -0.442488 -0.0403455 -0.895867 -0.417984 -0.0381692 -0.907652 -0.384568 -0.0395519 -0.922249 -0.398665 -0.0373188 -0.916337 -0.396586 -0.0387505 -0.917179 -0.289162 0.0394861 -0.956465 -0.321691 -0.0154358 -0.946719 -0.342117 -0.0307107 -0.939156 -0.352098 -0.0345733 -0.935324 -0.34252 -0.0278054 -0.939099 -0.319395 -0.0206367 -0.947397 -0.311005 -0.0238194 -0.95011 -0.297792 -0.02014 -0.954418 -0.262455 -0.0202372 -0.964732 -0.336917 -0.0254837 -0.94119 -0.368648 -0.0262023 -0.9292 -0.35542 -0.0311704 -0.934187 -0.391134 -0.0261942 -0.919961 -0.366469 -0.0331446 -0.92984 -0.353963 -0.0349636 -0.934606 -0.350011 -0.0343503 -0.936116 -0.353814 -0.0351721 -0.934654 -0.259237 -0.0148703 -0.965699 -0.151948 -0.0113288 -0.988324 -0.154656 -0.000916076 -0.987968 -0.0243128 -0.00379236 -0.999697 -0.025 0 -0.999687 -0.317716 -0.0453256 -0.947102 -0.234009 -0.0141335 -0.972132 -0.155509 -0.109077 -0.981794 -0.163029 -0.14305 -0.976196 -0.0925917 0.00302127 -0.9957 -0.0184931 -0.0111931 -0.999766 -0.0205306 0 -0.999789 -0.432581 -0.0477301 -0.900331 -0.455761 -0.0348704 -0.889419 -0.499326 0.00956405 -0.866362 -0.531185 -0.101962 -0.841099 -0.624459 -0.028018 -0.780555 -0.666005 -0.208028 -0.716353 -0.648917 -0.0941861 -0.755007 -0.732036 -0.0478871 -0.679581 -0.736925 -0.0787867 -0.671367 -0.772484 -0.0743965 -0.630661 -0.800018 -0.0662445 -0.596307 -0.801689 -0.0804293 -0.592306 -0.839352 -0.0732965 -0.538624 -0.844952 -0.125901 -0.519812 -0.388806 -0.043058 -0.920313 -0.390917 -0.166459 -0.905249 -0.0386495 -0.130592 -0.990683 -0.0444594 -0.102999 -0.993687 -0.164863 -0.189917 -0.967859 -0.230392 -0.00417005 -0.973089 -0.309896 -0.237549 -0.920617 -0.346844 -0.198754 -0.916622 -0.397267 -0.154022 -0.904686 -0.391305 -0.0078038 -0.920228 -0.426644 -0.03168 -0.903865 -0.391282 -0.0348634 -0.91961 -0.369011 -0.0482685 -0.928171 -0.427623 -0.087301 -0.899732 -0.406961 -0.0952907 -0.908462 -0.408038 -0.0568776 -0.911191 -0.418849 -0.0471317 -0.906832 -0.416321 -0.0107196 -0.909154 -0.425155 -0.141167 -0.894044 -0.436232 -0.161506 -0.885222 -0.42814 -0.152808 -0.8907 -0.44186 -0.204124 -0.873552 -0.495872 -0.237843 -0.835189 -0.446564 -0.165915 -0.879234 -0.41269 -0.188714 -0.891108 -0.390471 -0.18049 -0.902749 -0.373849 -0.17974 -0.909907 -0.481688 -0.176458 -0.858393 -0.576052 -0.232724 -0.783584 -0.587199 -0.205224 -0.782995 -0.681909 -0.223977 -0.6963 -0.6711 -0.25288 -0.696905 -0.776781 -0.183925 -0.602314 -0.777532 -0.112355 -0.618724 -0.804818 -0.23821 -0.543621 -0.869856 -0.0160356 -0.493044 -0.873797 -0.0660168 -0.481789 -0.878983 -0.0910058 -0.468089 -0.883946 -0.106588 -0.455278 -0.893165 -0.138609 -0.427835 -0.876667 -0.150455 -0.456965 -0.857518 -0.201374 -0.473403 -0.858372 -0.200069 -0.472408 -0.85425 -0.208841 -0.47607 -0.849103 -0.215803 -0.482134 -0.847651 -0.219224 -0.483144 -0.839821 -0.22466 -0.494195 -0.82922 -0.239906 -0.504816 -0.828374 -0.237082 -0.507533 -0.818015 -0.230847 -0.526841 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.00021892 -1 0.000222665 -0.131013 -0.991381 0.00029954 -0.130975 -0.991386 -0.00128371 -0.130975 -0.991385 -0.00283148 -0.131622 -0.991296 0.00148096 -0.114876 -0.993379 0.006547 -0.108568 -0.994067 0.000764162 -0.110781 -0.993845 -0.000155974 -0.0896654 -0.995972 0.00306843 -0.0742534 -0.997235 0.00357296 -0.0748982 -0.997185 0 -0.0591579 -0.998249 0 -0.0494266 -0.998778 0 -0.0494266 -0.998778 0 -0.0140952 -0.999901 0.0215665 -0.0195185 -0.999577 0.000827614 -0.00187659 -0.999998 0.76893 -0.639333 -0.000122476 0.503581 -0.863926 -0.00609269 0.341609 -0.939825 0.00564844 0.175314 -0.98449 -0.00675799 0.0931169 -0.995653 -0.00192023 0.0352218 -0.99938 0 0.336062 -0.941425 -0.0279631 0.12574 -0.991326 0.0382309 0.253589 -0.96721 0.0140565 0.664279 -0.747485 0.000211842 0.623357 -0.781669 -0.0204893 0.446143 -0.894293 0.0345766 0.541618 -0.840503 0.014326 0.879364 -0.476036 -0.010415 0.797182 -0.603335 0.022086 0.860575 -0.50925 0.00863555 0.905524 -0.424292 0.00158276 0.943571 -0.331171 -0.000445007 0.97557 -0.21968 0.00180446 0.976915 -0.213625 0.00128675 0.999972 -0.00725848 -0.00163683 0.996702 -0.0809309 0.00600937 0.999406 0.0344774 9.73025e-09 0.960963 0.276678 0 0.832162 0.554532 -0.000115597 0.912393 0.409201 -0.00969106 0.806012 0.591436 0.0234348 0.963484 0.265996 -0.0307471 0.859147 0.511324 0.0203299 0.923073 0.384579 0.00590086 0.745444 0.666569 0.000143394 0.595608 0.803144 0.0145067 0.741405 0.670387 -0.0299847 0.457452 0.888904 0.0242436 0.595936 0.803 -0.00715766 0.335893 0.941889 0.00457731 0.414322 0.910113 -0.0055534 0.140024 0.990113 0.00836861 0.181318 0.983424 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.871941 0.48954 -0.00832128 -0.742291 0.670016 0.00906829 -0.677854 0.735164 -0.00690722 -0.488916 0.872302 0.00705584 -0.480749 0.876842 0.00539167 -0.337582 0.941294 -0.00182103 -0.300912 0.953643 -0.00413673 -0.166438 0.985999 0.0101939 -0.0980812 0.995178 0 -0.996074 0.0885282 0 -0.993548 0.113369 0.00323731 -0.965338 0.260991 -0.00245726 -0.958202 0.286094 -1.54804e-05 -0.896283 0.443483 -1.49846e-05 -0.965925 -0.258823 0 -0.965925 -0.258823 0 -0.707108 -0.707106 0 -0.707108 -0.707106 0 -0.258818 -0.965926 0 -0.258818 -0.965926 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0.983104 0.183046 0 0.989016 0.14724 -0.012967 0.993725 0.11185 -0.000861661 0.99747 0.0710863 8.15316e-05 0.997345 0.0728279 2.74778e-05 0.997591 0.0693653 0 0.996353 0.0853314 0 0.996352 0.0853358 -1.69583e-06 0.996352 0.0853404 2.43808e-08 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 0.980812 -0.194955 0 0.994974 -0.0997598 -0.00868117 0.962438 -0.271501 -0.000871183 0.912997 -0.407966 0.000425813 0.831635 -0.555314 -0.00318241 0.804687 -0.593699 1.96787e-05 0.637515 -0.770438 -1.13168e-05 0.55619 -0.831044 -0.00435175 0.0624115 -0.998051 0 0.195623 -0.980672 -0.00376643 0.255596 -0.966784 -2.16267e-05 0.475173 -0.879893 1.49472e-05 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0.0529476 0.998583 0.00543021 -0.0131896 0.999898 0.00545912 0 1 0 0 1 0 0 1 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 0.258813 0.965927 0 0.258813 0.965927 0 0.707125 0.707089 0 0.707125 0.707089 0 0.965924 0.258825 0 0.965924 0.258825 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.980591 -0.196065 0 -0.98059 -0.196069 6.52284e-07 -0.988913 -0.148495 -7.06251e-06 -0.988907 -0.148534 0 -0.0612152 -0.998125 0 -0.321182 -0.947007 0.00446934 -0.153114 -0.988168 -0.00893163 -0.334629 -0.942348 -0.00219925 -0.641167 -0.767392 0.00366945 -0.510352 -0.859947 -0.00567755 -0.698372 -0.715734 0.000646331 -0.920634 -0.202309 -0.333923 -0.929091 -0.369851 0 -0.830262 -0.557319 -0.00775762 -0.939301 -0.343061 0.0047957 -0.828223 -0.560398 -0.000547585 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 0 1 0 2.02223e-06 1 1.49418e-06 1.7652e-06 1 1.60424e-06 3.04059e-06 1 -9.41224e-07 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.999743 -0.022651 -5.41903e-09 -0.999792 0.0203704 -0.000773541 -0.986472 0.163927 0.000664556 -0.965258 0.261297 -0.000880879 -0.888457 0.458956 0.0019423 -0.860947 0.508694 -8.85777e-05 -0.764246 0.644924 1.76164e-05 -0.697878 0.716217 -0.00056565 -0.64266 0.766148 -0.00239927 -0.103449 0.994635 4.96898e-07 -0.252015 0.967714 -0.0041664 -0.27797 0.960585 -0.00303369 -0.492653 0.870223 0.00206849 -0.996353 -0.0853293 0 -0.996353 -0.0853251 8.19509e-07 -0.996353 -0.0853299 7.12336e-07 -0.996352 -0.0853341 -2.04153e-08 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 0 0 1 0 0 9.43319e-05 -0.0460885 -0.998937 2.85434e-05 -0.00128762 -0.999999 -0.000254178 -0.0020792 -0.999998 -0.000761959 -0.00295067 -0.999995 -0.000207952 -0.000578688 -1 -0.00015502 -0.000601906 -1 -2.4607e-05 -0.000734407 -1 0.012006 -0.0223804 -0.999677 -0.0044089 -0.00736762 -0.999963 -0.00257135 -0.0047722 -0.999985 -0.000358059 -0.00079974 -1 -9.10242e-05 -0.000534476 -1 -0.00120124 -0.0694686 -0.997583 -0.0101746 -0.0479147 -0.9988 -0.0178086 -0.0519763 -0.99849 -0.0169658 -0.0513474 -0.998537 -0.00198866 -0.0380169 -0.999275 -0.0512206 -0.007571 -0.998659 -0.0211945 -0.0460409 -0.998715 -0.0507652 -0.00346336 -0.998705 -0.134274 -0.0267323 -0.990584 -0.194273 -0.0937001 -0.976462 -0.207763 -0.0411649 -0.977313 -0.256881 0.0405884 -0.96559 -0.232859 -0.00403259 -0.972502 -0.216467 -0.0379386 -0.975553 -0.203521 -0.0684703 -0.976673 -0.25141 -0.029779 -0.967423 -0.262562 -0.0231355 -0.964638 -0.277308 -0.032806 -0.960221 -0.275548 -0.0279766 -0.96088 -0.272272 -0.024511 -0.961908 -0.201131 -0.0802638 -0.97627 -0.19964 -0.0773542 -0.976811 -0.208462 -0.0749331 -0.975156 -0.24622 -0.0686877 -0.966777 -0.275734 -0.0371077 -0.960518 -0.0348206 -0.0293765 -0.998962 -0.0474323 -0.0407223 -0.998044 -0.0942622 -0.0703847 -0.993056 -0.544135 -0.0792787 -0.835244 -0.443782 -0.089688 -0.891635 -0.467015 -0.0738998 -0.881156 -0.492812 -0.0539071 -0.868465 -0.470158 -0.0721904 -0.879625 -0.442299 -0.0820632 -0.893106 -0.423128 -0.109775 -0.899395 -0.428099 -0.107557 -0.897308 -0.485424 -0.0752257 -0.871036 -0.448978 -0.0806142 -0.889899 -0.444802 -0.0813785 -0.891924 -0.540186 -0.0843739 -0.837305 -0.450562 -0.107772 -0.886216 -0.421707 -0.126642 -0.897845 -0.703238 -0.131739 -0.698642 -0.706213 -0.127343 -0.696453 -0.717543 -0.0952207 -0.689975 -0.718044 -0.087634 -0.690459 -0.717589 -0.104175 -0.688632 -0.717601 -0.119502 -0.686126 -0.620181 -0.0786375 -0.780508 -0.634988 -0.0882153 -0.767469 -0.689451 -0.0237131 -0.723944 -0.718556 -0.143045 -0.680599 -0.727311 -0.115263 -0.67656 -0.731275 -0.0966114 -0.675206 -0.728793 -0.0989295 -0.67755 -0.722354 -0.106262 -0.683311 -0.714019 -0.116966 -0.690287 -0.687329 -0.133296 -0.714011 -0.649326 -0.116347 -0.751558 -0.623883 -0.135194 -0.769736 -0.572292 -0.134624 -0.808924 -0.444683 -0.603353 -0.661983 -0.513539 -0.0560446 -0.856234 -0.428752 -0.098375 -0.89805 -0.679736 -0.178734 -0.711346 -0.449652 0.00617613 -0.893183 -0.372837 -0.0316677 -0.927356 -0.381023 -0.0284317 -0.924128 -0.369188 -0.034269 -0.928723 -0.382555 -0.0320114 -0.923378 -0.392596 -0.0297253 -0.91923 -0.445859 -0.0884211 -0.890725 -0.35769 -0.040177 -0.932976 -0.404157 -0.0255755 -0.914332 -0.453638 -0.00104326 -0.891186 -0.453567 -0.0337279 -0.890584 -0.428282 -0.121965 -0.895377 -0.355822 -0.0361478 -0.933854 -0.357659 -0.0392521 -0.933027 -0.433487 -0.109889 -0.894435 -0.376506 -0.0418331 -0.925469 -0.362724 -0.0365028 -0.931181 -0.519955 -0.0608237 -0.852026 -0.629291 -0.0508008 -0.775507 -0.582577 -0.163454 -0.79617 -0.728414 -0.127703 -0.673131 -0.747011 -0.0613982 -0.661971 -0.75262 -0.0847085 -0.652984 -0.752573 -0.0850494 -0.652993 -0.753906 -0.0809749 -0.651973 -0.669643 -0.221759 -0.708803 -0.707477 -0.0760001 -0.702638 -0.734025 -6.90222e-05 -0.679123 -0.733139 -0.0746353 -0.675971 -0.696586 0.0397838 -0.716369 -0.743657 -0.0691074 -0.664981 -0.753791 -0.0697678 -0.6534 -0.52032 -0.0550357 -0.852196 -0.576475 -0.0567068 -0.815145 -0.630044 -0.0161023 -0.776393 -0.627506 -0.0109501 -0.778535 -0.713975 -0.117284 -0.690278 -0.69243 0.0757804 -0.717494 -0.756484 -0.0715298 -0.650089 -0.755086 -0.0654921 -0.652346 -0.757911 -0.0689304 -0.648706 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.00874593 0 -0.999962 -0.0189718 0.0134286 -0.99973 -0.100163 -0.0381049 -0.994241 -0.115692 -0.0145083 -0.993179 -0.226622 -0.02329 -0.973704 -0.226619 -0.023865 -0.973691 -0.229738 -0.0285446 -0.972834 -0.233724 -0.033331 -0.971731 -0.234115 -0.0337051 -0.971625 -0.23284 -0.032587 -0.971969 -0.228296 -0.0291659 -0.973155 -0.220755 -0.024815 -0.975013 -0.196287 -0.0134014 -0.980455 -0.173694 0.0595984 -0.982995 -0.263782 -0.0182217 -0.96441 -0.2657 -0.0214464 -0.963817 -0.171322 0.0776115 -0.982153 -0.24557 -0.0155139 -0.969255 -0.258515 -0.0205096 -0.96579 -0.263795 -0.0175573 -0.964419 -0.200846 -0.0611788 -0.977711 -0.0999698 0.0397615 -0.994196 -0.0900268 0.0280253 -0.995545 -0.00858499 -0.0267289 -0.999606 -0.0220798 0 -0.999756 -0.00103005 -0.455469 -0.890251 -0.000498294 -0.455249 -0.890364 -0.00033803 -0.86949 -0.49395 -9.77561e-07 -0.881394 -0.472382 0.00516943 -0.870914 -0.491409 -0.00927496 -0.872234 -0.489001 0.00507522 -0.868597 -0.495494 -0.0114314 -0.870366 -0.492273 0.00954745 -0.86002 -0.51017 -0.0165895 -0.864356 -0.502607 0.00710315 -0.858237 -0.513204 -0.000868898 -0.846051 -0.533102 0.00216317 -0.83726 -0.546801 0.0150985 -0.830031 -0.557512 0 -0.822758 -0.568392 0 -0.78904 -0.614341 0 -0.78904 -0.614341 0 -0.735229 -0.677818 -0.142423 -0.696833 -0.70295 0.0794584 -0.649756 -0.755978 0 -0.613754 -0.789497 0 -0.569774 -0.821801 0 -0.569774 -0.821801 0 -0.535254 -0.844691 -0.000537624 -0.534667 -0.845063 0.000965108 -0.501684 -0.86505 0.0205922 -0.508555 -0.860783 -0.0192021 -0.482265 -0.875815 0.0310137 -0.473086 -0.88047 -0.00661572 -0.464574 -0.885509 0.0109307 -0.45379 -0.891042 0.00104978 -0.455249 -0.890364 -0.172901 -0.859683 -0.480678 -0.65275 -0.409316 -0.637477 -0.0583417 -0.437045 -0.897545 -0.0866537 -0.456127 -0.885686 -0.238894 -0.46038 -0.854973 -0.012366 -0.881016 -0.472925 -0.00124701 -0.869462 -0.493999 -0.019575 -0.871349 -0.490274 -0.0217376 -0.864994 -0.50131 -0.127947 -0.867844 -0.480079 -0.0159167 -0.866157 -0.499518 -0.0433152 -0.874009 -0.483976 -0.0720625 -0.869847 -0.48803 -0.102939 -0.853396 -0.510997 -0.103487 -0.863596 -0.49345 -0.0518544 -0.860221 -0.507279 -0.24244 -0.804657 -0.541986 -0.280247 -0.761639 -0.584267 0.48816 -0.666908 -0.562969 -0.193717 -0.84614 -0.496509 -0.171283 -0.84723 -0.502855 -0.106182 -0.853931 -0.509438 -0.1907 -0.445818 -0.874574 -0.168821 -0.420821 -0.891296 -0.113143 -0.479726 -0.870093 -0.0856728 -0.446211 -0.890818 -0.0654357 -0.458454 -0.886306 -0.0267459 -0.465782 -0.884495 -0.0278811 -0.455332 -0.889885 -0.0295756 -0.461538 -0.886627 -0.231544 -0.438892 -0.868194 -0.250125 -0.443471 -0.860681 -0.276087 -0.514662 -0.811726 -0.519626 -0.425028 -0.741175 -0.515874 -0.42872 -0.741669 -0.538512 -0.181507 -0.822836 -0.590944 -0.411143 -0.694079 -0.594566 -0.422613 -0.684025 -0.584076 -0.396164 -0.708456 -0.586469 -0.405778 -0.700998 -0.557126 -0.430125 -0.710354 -0.535051 -0.435541 -0.723896 -0.532004 0.804793 -0.263212 -0.991431 -0.11656 -0.0589861 -0.99143 -0.116543 -0.0590239 -0.991432 -0.116556 -0.0589736 -0.991426 -0.116558 -0.0590697 -0.991427 -0.116556 -0.0590557 -0.711514 -0.435749 -0.551245 -0.725075 -0.439749 -0.529988 -0.725649 -0.439464 -0.529438 -0.728958 -0.466323 -0.501162 -0.743229 -0.440357 -0.503683 -0.733881 -0.4671 -0.49319 -0.730594 -0.48179 -0.48385 -0.730556 -0.481892 -0.483806 -0.730152 -0.494482 -0.471557 -0.717761 -0.514681 -0.46896 -0.76198 -0.459268 -0.456572 -0.717796 -0.534043 -0.44673 -0.68138 -0.569599 -0.45965 -0.692381 -0.55352 -0.462844 -0.655113 -0.58708 -0.475567 -0.648448 -0.618648 -0.44361 -0.606047 -0.645485 -0.464817 -0.545698 -0.700343 -0.460145 -0.575102 -0.700559 -0.422462 -0.468574 -0.73482 -0.490386 -0.455299 -0.753927 -0.4736 -0.386448 -0.793416 -0.470265 -0.399517 -0.792666 -0.460506 -0.36052 -0.798423 -0.482231 -0.305232 -0.812124 -0.497281 -0.332917 -0.839222 -0.429968 -0.421171 -0.846526 -0.325591 -0.26028 -0.834086 -0.486368 -0.259888 -0.835654 -0.48388 -0.300654 -0.82023 -0.486652 -0.307011 -0.772402 -0.556004 -0.206186 -0.786567 -0.582064 -0.251009 -0.759981 -0.599519 -0.269955 -0.708797 -0.651714 -0.311492 -0.690695 -0.65262 -0.165853 -0.625756 -0.762182 -0.252561 -0.599689 -0.759333 -0.268899 -0.525284 -0.807323 -0.26624 -0.530581 -0.804737 -0.22294 -0.516439 -0.826794 -0.3024 -0.474707 -0.826564 -0.283626 -0.450665 -0.846438 -0.601268 -0.429802 -0.673608 -0.630743 -0.436028 -0.641906 -0.652855 -0.408954 -0.637602 -0.377195 -0.036415 -0.925418 -0.799848 0.282978 -0.529308 -0.991428 -0.116598 -0.0589555 -0.991431 -0.116472 -0.0591592 -0.330851 -0.448027 -0.830548 -0.369073 -0.434543 -0.821558 -0.401571 -0.406544 -0.820648 -0.421551 -0.448554 -0.788095 -0.467546 -0.430796 -0.771891 -0.466762 -0.429975 -0.772823 -0.486191 -0.443921 -0.752696 0.791214 0.611539 0 0.772808 0.634632 0.00314811 0.765263 0.643693 0.00566651 0.715434 0.698631 -0.00829346 0.607019 0.794654 -0.00730044 0.603403 0.797386 -0.00893001 0.678544 0.734522 0.00744957 0.443736 0.896156 -0.00179295 0.473743 0.880663 -1.05413e-06 0.514384 0.85756 -2.96842e-07 0.507985 0.861364 -0.00184945 0.557222 0.830363 0.00100385 0.269531 0.96266 -0.0252901 0.392339 0.919782 0.00848184 0.463951 0.885837 -0.00650553 0.325945 0.945373 0.00552698 0.227098 0.973872 -9.50964e-05 0.158673 0.987331 0.000492711 0.134805 0.990851 -0.00654116 0.0874021 0.996173 -0.000378587 0.026039 0.999661 0.000880132 0.0280741 0.999606 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.0323648 0.999476 0 -0.0967064 0.995311 0.00191405 -0.114656 0.993401 0.00298484 -0.26865 0.963229 -0.00419939 -0.376066 0.926577 0.00551211 -0.480007 0.877263 -0.00131204 -0.620655 0.784081 0.00202968 -0.65463 0.755947 -0.00189175 -0.775653 0.631158 0.00132915 -0.797361 0.60349 0.00386777 -0.89042 0.455112 -0.00500735 -0.981951 0.187826 0.0222013 -0.967149 0.254212 0 0.000150972 1 0 0.000154483 1 3.95267e-07 0.00015586 1 4.45834e-07 0.000150404 1 1.22446e-07 0.000155828 1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.996086 -0.0883892 0 -0.966114 -0.25728 0.0207693 -0.968333 -0.248972 0.0185495 -0.901993 -0.43175 -0.0006172 -0.791631 -0.610999 0.000996927 -0.795275 -0.606249 -7.57959e-05 -0.0779859 -0.996954 0 -0.134709 -0.990868 0.00581814 -0.253651 -0.967291 -0.00303532 -0.392547 -0.919718 0.00501686 -0.380435 -0.924784 0.00658115 -0.612235 -0.790564 -0.0132738 -0.497295 -0.867325 0.0210937 -0.643526 -0.765424 4.7917e-05 0.97051 -0.241061 0 0.994358 -0.105547 -0.0105373 0.968145 -0.250367 -0.00349262 0.788547 -0.614947 0.00580113 0.906892 -0.421204 -0.011587 0.309951 -0.950751 0.00152578 0.547435 -0.836848 -0.000996114 0.654784 -0.755812 0.00245288 0.832452 -0.554082 -0.00410141 0.0258192 -0.999667 0 0.097137 -0.995219 0.0102162 0.357377 -0.933934 -0.00699987 0.140157 -0.990129 -0.000695688 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0.182271 0.983248 0 0.548366 0.836224 0.00489849 0.449342 0.893358 -0.00150572 0.155506 0.987833 0.00216574 0.88439 0.466709 0.00610183 0.755535 0.655109 -0.000165241 0.646284 0.763097 0.000238318 0.764013 0.645016 -0.0154209 0.8749 0.484301 -0.00134752 0.987029 0.160535 0.00148029 0.979465 0.201606 -0.00174762 0.999716 0.023821 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.0255765 -0.999673 0 -0.0251194 -0.999684 0.000152258 -0.136725 -0.990609 -0.000270999 -0.135928 -0.990719 0 -0.000151138 -1 0 -0.000157446 -1 3.56455e-07 -0.000145334 -1 1.7445e-07 -0.00015303 -1 -2.91131e-08 -0.000153586 -1 0 -0.000153586 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.724828 -0.665308 -0.178858 -0.724821 -0.665302 -0.178908 -0.724823 -0.665302 -0.1789 -0.724832 -0.6653 -0.178868 -0.7248 -0.665311 -0.178959 -0.724815 -0.665307 -0.178914 -0.724829 -0.6653 -0.178883 -0.725189 -0.665085 -0.17822 -0.724817 -0.665308 -0.178904 -0.540409 -0.841403 4.18724e-07 -0.542589 -0.839998 0.00092308 -0.60111 -0.799166 -3.99008e-05 -0.631676 -0.775233 0.000552291 -0.685041 -0.728386 -0.0131326 -0.846207 -0.52658 0.0815265 -0.987696 -0.114325 -0.106703 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0.107001 0.985403 0.132404 -0.126664 0.9877 0.0916764 0 1 0 0 1 0 0 1 0 0 1 0 -0.292009 -0.425532 -0.856536 -0.288326 -0.428888 -0.85611 -0.284953 -0.434267 -0.854526 -0.484502 -0.497656 -0.719442 -0.46162 -0.479701 -0.746186 -0.431891 -0.470498 -0.769482 -0.366396 -0.461551 -0.807914 -0.356174 -0.467802 -0.808889 -0.309429 -0.425835 -0.850246 -0.300159 -0.423043 -0.85495 -0.986708 -0.139811 -0.0828212 -0.557956 -0.460513 -0.690372 -0.521157 -0.476957 -0.707749 -0.471348 -0.512982 -0.717413 -0.499031 -0.512334 -0.698915 -0.405877 -0.572842 -0.71212 -0.393259 -0.579628 -0.713708 -0.286273 -0.442788 -0.849698 -0.290101 -0.447259 -0.84605 -0.334961 -0.484284 -0.808251 -0.318894 -0.500051 -0.805143 -0.32493 -0.539918 -0.776472 -0.249001 -0.611156 -0.751323 -0.347117 -0.634059 -0.690998 -0.347649 -0.628668 -0.695641 -0.346916 -0.620883 -0.70296 -0.293664 -0.678089 -0.673763 -0.287745 -0.669348 -0.684964 -0.345765 -0.616376 -0.70748 -0.329797 -0.566081 -0.755504 -0.343763 -0.595994 -0.725684 -0.310265 -0.671115 -0.673306 -0.309303 -0.653277 -0.691058 -0.000305162 -0.727401 -0.686213 -0.0201756 -0.731279 -0.68178 -0.0193863 -0.730998 -0.682104 -0.0131113 -0.729436 -0.683923 -0.00450329 -0.727922 -0.685645 -0.000340224 -0.483081 -0.875576 -0.0115448 -0.481834 -0.876186 -0.0322406 -0.477762 -0.877898 -0.0455957 -0.473965 -0.879363 -0.0529153 -0.471519 -0.880267 -0.0621846 -0.468036 -0.881519 -0.0737407 -0.462632 -0.883478 0.153412 -0.570555 -0.806803 -0.0109793 -0.539535 -0.841891 0.00803824 -0.661677 -0.749746 0.0392823 -0.669016 -0.742209 -0.0130478 -0.727363 -0.686129 -0.0321737 -0.648176 -0.760811 -0.118636 -0.644786 -0.755101 -0.0303475 -0.72687 -0.686105 0.00884661 -0.664965 -0.746822 0.0722232 -0.65997 -0.747812 -0.069297 -0.576212 -0.814357 -0.102315 -0.516128 -0.850378 -0.03985 -0.32709 -0.944152 -0.0275643 -0.473238 -0.880503 -0.00721335 -0.483071 -0.875552 -0.176625 -0.514385 -0.839173 -0.101298 -0.466875 -0.878502 -0.111764 -0.471952 -0.874511 -0.116906 -0.711755 -0.692631 -0.112216 -0.711074 -0.694105 -0.124856 -0.69893 -0.704207 -0.131452 -0.676504 -0.724612 -0.0250785 -0.768639 -0.639191 -0.0832373 -0.704738 -0.704567 -0.0842049 -0.719853 -0.689 -0.121599 -0.706581 -0.697106 -0.116691 -0.708757 -0.695735 -0.489517 -0.546199 -0.679735 -0.0947841 -0.591435 -0.800763 -0.0451252 -0.611776 -0.789743 -0.17544 -0.607005 -0.775091 0.0114682 -0.680566 -0.732597 -0.128383 -0.681795 -0.72019 -0.0194272 -0.720659 -0.693017 -0.00355954 -0.716845 -0.697224 -0.0223876 -0.580629 -0.81386 -0.0259715 -0.581936 -0.81282 -0.146502 -0.520169 -0.841404 0.00879445 -0.52944 -0.848302 -0.100868 -0.473346 -0.875083 -0.124608 -0.476375 -0.870367 -0.13647 -0.454464 -0.880249 -0.170627 -0.985336 0 -0.0976159 -0.995209 -0.00545016 -0.356667 -0.934226 0.00319323 -0.617421 -0.786582 -0.00899864 -0.493649 -0.869652 0.00397567 -0.777509 -0.628866 -0.00280672 -0.759238 -0.650812 -0.00104701 -0.894778 -0.44651 0.000634892 -0.966253 -0.257505 -0.00684973 -0.930972 -0.365088 0.00159615 -0.99646 -0.0840637 -0.000875811 -0.994522 -0.10453 8.78934e-08 0.980476 -0.19664 0 0.986982 -0.160803 0.0030624 0.886374 -0.462966 -0.00187906 0.915525 -0.402223 -0.00546984 0.757659 -0.652597 0.00838226 0.63215 -0.774617 -0.0188499 0.862324 -0.506319 -0.00629018 0.748636 -0.662981 0.000560216 0.640217 -0.768194 -0.000468076 0.426141 -0.904631 0.00685522 0.487543 -0.873089 -0.00414082 0.186615 -0.982429 0.00276962 0.131325 -0.991339 0 0.176833 0.984241 0 0.167888 0.985806 0.000741184 0.484731 0.874663 -0.000668916 0.542001 0.840367 0.00422554 0.668558 0.74366 0 0.74513 0.666919 0 0.784012 0.620744 -0.001409 0.873393 0.487007 0.00306929 0.899446 0.437032 0.000228789 0.959974 0.28009 -2.04367e-05 0.98546 0.169882 0.00306305 0.993893 0.110345 0 0.258813 -0.965927 0 0.258813 -0.965927 0 0.707125 -0.707089 0 0.707125 -0.707089 0 0.965924 -0.258825 0 0.965924 -0.258825 0 -0.999097 -0.0424852 0 -0.999999 0.00134345 -0.000836013 -0.987802 0.155713 0.000743256 -0.970375 0.241604 -0.000760097 -0.920973 0.389625 0.000876313 -0.870294 0.49253 -0.00142492 -0.460267 0.88778 0.00062242 -0.645358 0.763878 -0.00165243 -0.664824 0.746999 -0.000544693 -0.818316 0.574769 0.000244818 -0.0723984 0.997376 0 -0.25087 0.968014 -0.00360673 -0.227343 0.973803 -0.00486764 -0.330977 0.943637 -0.00167165 -0.936192 -0.351487 0.00137483 -0.244696 -0.9696 0 -0.101434 -0.994785 -0.010685 -0.233648 -0.972312 -0.00421534 -0.439184 -0.898396 0.00151265 -0.613079 -0.79002 -0.00156538 -0.816845 -0.576825 0.00611827 -0.720144 -0.693818 -0.00323373 -0.842306 -0.538999 -0.000508881 -0.994255 -0.107042 0 -0.986373 -0.164312 0.00841717 -0.91439 -0.404797 -0.00545751 -0.977621 -0.210371 -0.000516504 -0.999344 0.0362112 0 -0.996124 0.0879597 -0.000866954 -0.976602 0.215052 0.000682988 -0.946039 0.32405 -0.000775199 -0.9149 0.40368 0.000406678 -0.82282 0.568302 -0.000882493 -0.792459 0.609925 0.000647167 -0.552358 0.833607 -0.00101808 -0.56214 0.827042 -0.000364335 -0.367512 0.930019 2.64988e-05 -0.178164 0.984001 -0.0008091 -0.19194 0.981407 0 -0.945714 -0.325 0.000412899 -0.872125 -0.489283 -0.00015786 -0.248366 -0.968666 0 -0.105515 -0.994359 -0.0107908 -0.242525 -0.970137 -0.0040962 -0.61908 -0.785301 0.00655621 -0.471645 -0.881766 -0.00638183 -0.644594 -0.764524 -0.00107136 -0.831979 -0.554804 0.00179663 -0.774452 -0.632627 -0.0025292 -0.848787 -0.528734 -0.000693422 -0.998853 -0.0478857 -2.80947e-09 -0.992711 -0.120329 0.00677565 -0.939713 -0.341926 -0.00513154 -0.988693 -0.149954 -0.000482079 0.195084 0.980787 0 0.195084 0.980787 0 0.555582 0.831462 0 0.555582 0.831462 0 0.831443 0.555611 0 0.831443 0.555611 0 0.980798 0.195028 0 0.980798 0.195028 0 0.25881 -0.965928 0 0.25881 -0.965928 0 0.707126 -0.707088 0 0.707126 -0.707088 0 0.965924 -0.258825 0 0.965924 -0.258825 0 0.258811 0.965928 0 0.258811 0.965928 0 0.707126 0.707088 0 0.707126 0.707088 0 0.965924 0.258825 0 0.965924 0.258825 0 0.258811 -0.965928 0 0.258811 -0.965928 0 0.707126 -0.707088 0 0.707126 -0.707088 0 0.965924 -0.258825 0 0.965924 -0.258825 0 -0.995028 0.0995968 -5.84339e-09 -0.988773 0.149423 -0.000829992 -0.962529 0.271179 0.000620415 -0.925315 0.379199 -0.000751755 -0.894711 0.446645 0.00031057 -0.791608 0.611029 -0.0006548 -0.772651 0.634832 0.000261814 -0.637484 0.770463 -0.00012391 -0.529564 0.848268 -0.00209074 -0.476344 0.879259 -1.2546e-06 -0.17551 0.984478 -2.93655e-06 -0.175566 0.984468 0 -0.959028 -0.283313 0.000120651 -0.249518 -0.96837 0 -0.109938 -0.99388 -0.0108209 -0.254564 -0.967049 -0.00376461 -0.632595 -0.774457 0.00629954 -0.42865 -0.903387 -0.0122615 -0.560159 -0.828372 -0.00467417 -0.668391 -0.743809 -0.00109156 -0.851588 -0.524209 0.00185666 -0.796395 -0.604771 -0.00265504 -0.889482 -0.456971 -6.87733e-05 -0.999794 0.0202887 0 -0.997848 -0.0652469 0.00656671 -0.959852 -0.28046 -0.00505655 -0.996781 -0.0801748 -0.000391844 -0.987182 0.159599 0 -0.978025 0.208487 -0.000851973 -0.944615 0.32818 0.000607523 -0.874313 0.48536 -0.00144408 -0.900391 0.435082 0.000228626 -0.751718 0.659484 -0.000268385 -0.751802 0.659389 -0.000263699 -0.616179 0.787606 6.71852e-05 -0.485758 0.874092 -0.00146802 -0.47012 0.882602 -0.000823979 -0.175417 0.984494 0.000857325 -0.157055 0.98759 0 -0.965668 -0.259777 -0.000637591 -0.246594 -0.969119 0 -0.100306 -0.994891 -0.011459 -0.226667 -0.97396 -0.00484988 -0.331817 -0.943342 -0.00161947 -0.635921 -0.771744 0.00389742 -0.482614 -0.875783 -0.00937657 -0.639279 -0.768973 -0.00162921 -0.859127 -0.511759 0.00204119 -0.801746 -0.597657 -0.00301916 -0.935739 -0.352691 0.00155094 -0.999975 -0.00697433 0.00105487 -0.995708 -0.0925219 -0.00215325 -0.997959 0.0638638 0 0.258813 0.965927 0 0.258813 0.965927 0 0.707125 0.707089 0 0.707125 0.707089 0 0.965924 0.258825 0 0.965924 0.258825 0 0.98548 -0.169789 0 0.985812 -0.167854 0.000153447 0.873092 -0.487555 -7.14528e-05 0.874668 -0.484722 0.000183256 0.6649 -0.746932 -0.000182079 0.619795 -0.784752 0.00431428 0.441399 -0.89731 -0.00117419 0.284452 -0.958687 0.00232775 0.220984 -0.975261 0.00570619 0.110425 -0.993884 0 0.973739 -0.227669 0 0.991311 -0.131316 -0.00767827 0.954058 -0.299619 -0.00157069 0.807083 -0.590429 0.00311668 0.906004 -0.423136 -0.0106178 0.83921 -0.543798 -0.00317968 0.705371 -0.708838 0.000827333 0.646778 -0.762678 -0.000145073 0.450847 -0.892601 0.000595936 0.518822 -0.854875 -0.00355796 0.362731 -0.931894 -0.000266834 0.142496 -0.989795 0.000465526 0.236045 -0.971736 -0.00346483 -0.429317 -0.903154 4.49455e-07 -0.368733 -0.929535 -0.000886827 -0.282914 -0.959145 0.000579741 -0.128616 -0.991694 -0.000764348 -0.0180594 -0.999836 0.00165682 0.158841 -0.987303 -0.00165103 -0.304849 -0.952401 0 -0.348225 -0.93741 -0.000974492 -0.50607 -0.862492 0.000991215 -0.573883 -0.818937 -0.000766296 -0.740709 -0.671825 0.00118287 -0.782669 -0.622437 -0.00109058 -0.989787 -0.142556 0 -0.967184 -0.254041 -0.00418578 -0.940453 -0.33992 -0.0014802 -0.884041 -0.46741 0.00041645 -0.995754 0.0920557 0 -0.975135 0.221562 -0.00476574 -0.965877 0.258986 -0.00285545 -0.937547 0.347858 -0.000889851 -0.89424 0.447586 0.000843458 -0.803393 0.595443 -0.0028307 -0.799379 0.600819 -0.00321473 -0.720753 0.693192 -0.000386429 -0.560662 0.828044 0.00101903 -0.511514 0.85927 -0.00281186 -0.352813 0.935694 0.000451726 -0.146671 0.989184 -0.0017696 -0.169789 0.98548 0 0.997828 0.0658658 0 0.194578 0.980887 0 0.148078 0.988968 0.00395016 0.433173 0.901308 -0.00213338 0.386216 0.922398 -0.00438878 0.639047 0.769128 0.00784612 0.528543 0.848901 -0.00304214 0.742943 0.669353 0.00141797 0.689063 0.7247 -0.0015124 0.855963 0.517029 0.00300474 0.792289 0.610121 -0.00561838 0.896155 0.443741 0.000630996 0.970574 0.240756 -0.00473351 0.998021 0.0622099 0.00920648 0.966657 0.256074 -0.0010228 -0.0921647 0.995744 6.79643e-07 -0.122431 0.992476 -0.00121469 -0.271438 0.962456 0.000845083 -0.403569 0.914945 -0.00283849 -0.441875 0.897077 -0.000811134 -0.63417 0.773193 0.000939979 -0.598464 0.801149 -0.00143253 -0.752494 0.658599 0.00107497 -0.742278 0.670092 0.000478365 -0.881021 0.473076 -0.000789107 -0.872777 0.488115 -0.00188429 -0.986395 0.164377 0.00244466 -0.981021 0.193902 0 0.245751 0.969333 -0.000573211 0.177115 0.984184 -0.00336596 0.0820126 0.996631 0 0.406575 0.913617 0.000436038 0.553969 0.832523 -0.00492782 0.51733 0.855784 -0.00185904 0.663326 0.74833 0.000259627 0.81016 0.586206 -0.00194892 0.788597 0.614909 0.00118311 0.941685 0.336495 -0.000790015 0.949851 0.312694 -0.00223394 0.98735 0.158555 0.000526353 0.99711 0.0759688 -0.000633613 0.999003 0.0446482 -4.15278e-08 -0.0958726 -0.995394 0 -0.172981 -0.98492 -0.00324111 -0.997091 -0.0762219 0 -0.995448 -0.0953022 -0.000607219 -0.967668 -0.252225 0.000683127 -0.935897 -0.352261 -0.00297768 -0.894837 -0.446393 0.000685308 -0.763115 -0.646262 -0.00123063 -0.777783 -0.628527 -0.00270379 -0.496332 -0.868125 0.00375146 -0.616386 -0.787391 -0.00911801 -0.358025 -0.933706 0.00328364 0.987107 -0.160061 0 0.99433 -0.106266 -0.00395628 0.954101 -0.299482 0.0010197 0.887234 -0.461314 -0.00209541 0.872139 -0.489258 -0.000403041 0.757376 -0.652979 0.000331568 0.759069 -0.65101 0.000234876 0.644421 -0.764671 -0.000218851 0.438406 -0.89874 0.00816907 0.658271 -0.752492 -0.0208555 0.50437 -0.86348 -0.0036084 0.143301 -0.989674 0.00327971 0.23306 -0.972454 -0.00408162 0.0546533 -0.998505 0 -0.977197 0.212336 0 -0.0770252 0.997029 0 -0.121708 0.992565 -0.00151792 -0.25046 0.968126 0.00114237 -0.401847 0.915703 -0.00280099 -0.482898 0.875675 0.00176785 -0.633704 0.773575 -0.0010336 -0.659313 0.751869 -3.50807e-05 -0.752288 0.658834 3.0357e-05 -0.82153 0.570156 0.00308972 -0.880622 0.473813 -0.00236901 -0.986353 0.164583 0.00441499 0.0911518 0.995837 0 0.174732 0.98461 -0.0033582 0.274183 0.961677 0.000306558 0.448693 0.893686 -0.000373553 0.693914 0.720058 -0.000263954 0.510888 0.859646 0.00174459 0.620875 0.783839 -0.0104976 0.54302 0.839702 -0.00540605 0.998433 0.0559558 0 0.996532 0.0832075 -0.000694956 0.973444 0.228923 0.0011373 0.944777 0.327699 -0.00313004 0.928195 0.37209 -0.00151163 0.780006 0.625757 0.00437817 0.893825 0.448096 -0.0169147 0.795636 0.60577 -0.00236539 -0.170326 -0.985388 0 -0.0990984 -0.995062 -0.00560128 -0.99815 -0.0607974 0 -0.994813 -0.101719 -0.00106851 -0.971605 -0.236604 0.00137017 -0.931365 -0.364074 -0.00304607 -0.897263 -0.441497 0.000314353 -0.756119 -0.654434 -0.000547357 -0.781227 -0.624238 -0.00329581 -0.491089 -0.871098 0.0043605 -0.605553 -0.795761 -0.00837451 -0.347057 -0.93784 0.00287328 0.986725 -0.162398 0 0.994602 -0.103665 -0.00445344 0.951019 -0.309128 0.00139231 0.883379 -0.468652 -0.00251817 0.868416 -0.495836 -0.000928398 0.752206 -0.658927 0.00080929 0.759406 -0.650617 0.000355225 0.636001 -0.771688 -0.000317781 0.658596 -0.752495 -0.0014167 0.420101 -0.90747 0.00361759 0.500486 -0.865731 -0.00490848 0.13414 -0.990952 0.00451041 0.245272 -0.969441 -0.00502782 0.0641688 -0.997939 0 0.278687 0.960382 0.000496106 0.172535 0.984998 -0.00332048 0.0931594 0.995651 0 0.69615 0.717897 -0.000486841 0.503294 0.86411 0.00283738 0.612043 0.790765 -0.00975763 0.451738 0.89215 -0.000656101 0.766231 0.642561 -0.00217923 0.874242 0.485294 -0.0137962 0.770562 0.637338 0.00581749 0.927655 0.373432 -0.00202715 0.965108 0.261774 -0.00634676 0.939541 0.342436 0.00042524 0.996334 0.0855458 -0.000219496 0.995872 0.0907735 0 0.98662 -0.163037 -1.94396e-08 0.994702 -0.102701 -0.00460725 0.950019 -0.312188 0.00151552 0.882379 -0.470532 -0.00263926 0.867426 -0.497566 -0.00107998 0.752812 -0.658235 0.000932997 0.761498 -0.648167 0.000385409 0.636142 -0.771572 -0.000362899 0.657857 -0.753142 -0.00147818 0.415969 -0.909372 0.00359762 0.499156 -0.866496 -0.0052362 0.131995 -0.991238 0.00485495 0.283934 -0.958807 -0.00842274 0.105006 -0.994472 0 -0.975072 0.221888 0 -0.0717625 0.997422 0 -0.11761 0.993059 -0.00147191 -0.240965 0.970533 0.00117762 -0.393958 0.919124 -0.00281743 -0.472682 0.881231 0.00166913 -0.626626 0.77932 -0.00100344 -0.650615 0.759408 -2.24113e-05 -0.747057 0.66476 1.66712e-05 -0.813631 0.581374 0.00302433 -0.878463 0.477803 -0.0026968 -0.986132 0.165871 0.00555267 -0.16985 -0.98547 0 -0.0991597 -0.995056 -0.00556457 -0.34397 -0.938977 0.00275782 -0.602555 -0.798036 -0.00815687 -0.4897 -0.871879 0.00455696 -0.778642 -0.627459 -0.00336305 -0.754277 -0.656556 -0.000730519 -0.998147 -0.060852 -6.84625e-09 -0.994656 -0.103234 -0.0011169 -0.971631 -0.236497 0.00141124 -0.930178 -0.367096 -0.00306449 -0.930116 -0.367252 -0.00305764 -0.885991 -0.463703 0.000342164 0.279863 0.96004 0.00053344 0.17227 0.985044 -0.00331694 0.0936632 0.995604 0 0.700271 0.713877 -0.000608504 0.502142 0.86478 0.00305337 0.611038 0.791543 -0.00965202 0.450237 0.892909 -0.000693856 0.771941 0.635689 -0.00264252 0.876482 0.481217 -0.014485 0.769082 0.639121 0.00606669 0.929687 0.368344 -0.00226327 0.968074 0.250561 -0.00716217 0.938881 0.344241 0.00108962 0.996894 0.0787537 -0.000535756 0.995817 0.0913755 0 -0.974571 0.224079 0 -0.986094 0.166084 0.00583757 -0.878018 0.47862 -0.00276853 -0.813842 0.58108 0.00284942 -0.748248 0.66342 1.55536e-05 -0.6518 0.758391 -1.95441e-05 -0.627752 0.778413 -0.001053 -0.472897 0.881116 0.00164931 -0.444001 0.896026 3.57664e-06 -0.24303 0.970019 5.64318e-06 -0.286696 0.958019 0.00211743 -0.0731607 0.997317 -0.0023519 -0.116795 0.993156 0 -0.169803 -0.985478 0 -0.0993232 -0.99504 -0.00556835 -0.342514 -0.939509 0.00270567 -0.601256 -0.799016 -0.00804144 -0.489396 -0.872049 0.00463065 -0.754128 -0.656722 -0.00260985 -0.778442 -0.627717 -0.000541324 -0.998342 -0.0575615 0 -0.994692 -0.10289 -0.00113574 -0.97232 -0.233648 0.00151556 -0.930232 -0.366958 -0.00309786 -0.930093 -0.36731 -0.00308233 -0.88625 -0.463207 0.000329926 0.986691 -0.162607 0 0.994771 -0.102023 -0.00461004 0.950179 -0.3117 0.0015412 0.882738 -0.469858 -0.00265953 0.867869 -0.496792 -0.00110858 0.751443 -0.659797 0.00100305 0.762719 -0.64673 0.000263269 0.634906 -0.77259 -0.000241243 0.661417 -0.750017 -0.00161398 0.418487 -0.908214 0.00396209 0.503257 -0.864121 -0.00519163 0.133865 -0.990988 0.00476824 0.292008 -0.956372 -0.00919358 0.113111 -0.993582 0 -0.975156 0.221519 0 -0.986197 0.165486 0.00553866 -0.878678 0.477408 -0.00269947 -0.813992 0.580868 0.003037 -0.747246 0.664548 1.43237e-05 -0.0840035 0.996465 0 -0.119269 0.992861 -0.00132319 -0.25262 0.967565 0.000880927 -0.39617 0.918173 -0.00273513 -0.360765 0.932645 -0.00470666 -0.626209 0.779614 0.00799736 -0.499201 0.866469 -0.0055009 -0.65505 0.755585 -2.06206e-05 -0.170255 -0.9854 0 -0.0994182 -0.99503 -0.00560841 -0.344334 -0.938843 0.00276524 -0.603446 -0.797362 -0.00816917 -0.490497 -0.871431 0.00456059 -0.755675 -0.654942 -0.00259663 -0.781647 -0.623721 -0.000367173 -0.998508 -0.0546083 0 -0.994885 -0.10101 -0.00109419 -0.972972 -0.230917 0.00158158 -0.931449 -0.363858 -0.00310974 -0.930011 -0.36752 -0.00295233 -0.888187 -0.459482 0.00021591 0.0934119 0.995628 0 0.173616 0.984808 -0.00335003 0.279521 0.960139 0.000473436 0.455647 0.89016 -0.000634659 0.540743 0.84117 -0.00548289 0.616008 0.787676 -0.010058 0.505602 0.862763 0.0026735 0.697731 0.716359 -0.000468809 0.795989 0.605305 -0.00290274 0.772888 0.634542 0.000167799 0.897071 0.441886 -4.10544e-05 0.970108 0.242621 -0.00512006 0.942405 0.334445 0.00443791 0.999165 0.0408256 -0.00177437 0.996336 0.0855276 0 0.986843 -0.161682 0 0.994757 -0.102171 -0.00448469 0.951247 -0.308426 0.00142923 0.884029 -0.467424 -0.0025557 0.869329 -0.494232 -0.000991594 0.752681 -0.658384 0.000883739 0.761703 -0.647927 0.000298167 0.637095 -0.770785 -0.000263682 0.665679 -0.746236 -0.00167815 0.424777 -0.905288 0.00433291 0.508182 -0.861236 -0.00480567 0.137647 -0.990472 0.00433958 0.300654 -0.953681 -0.00997107 0.123397 -0.992357 0 -0.976167 0.217019 0 -0.986319 0.164773 0.00500488 -0.879766 0.4754 -0.00256398 -0.817854 0.575417 0.00306208 -0.749852 0.661606 2.23526e-05 -0.093302 0.995638 0 -0.121999 0.992529 -0.00118768 -0.262453 0.964945 0.000694064 -0.400887 0.916124 -0.00265716 -0.36145 0.932379 -0.00486875 -0.629728 0.776772 0.00831007 -0.504372 0.863471 -0.00517443 -0.661758 0.749718 -1.81416e-05 0.0926966 0.995694 0 0.175056 0.984553 -0.00338244 0.278064 0.960563 0.000383305 0.453258 0.89138 -0.000486909 0.544275 0.838889 -0.00549875 0.622015 0.782934 -0.0105634 0.509834 0.86027 0.0021439 0.697612 0.716476 -0.000359129 0.804553 0.593874 -0.00290205 0.778371 0.627804 0.000794916 0.901903 0.43194 -0.00018343 0.971744 0.235993 -0.00452102 0.946054 0.323976 0.004716 0.999476 0.03232 -0.00175243 0.996804 0.0798823 0 0.987327 -0.158701 0 0.994595 -0.103757 -0.00400204 0.954849 -0.297089 0.00105458 0.88845 -0.458968 -0.00214193 0.874027 -0.485878 -0.000508223 0.756644 -0.653827 0.000439962 0.761566 -0.648088 0.000136054 0.644789 -0.76436 -0.000118622 0.675265 -0.737573 -0.00149895 0.445123 -0.89546 0.00411431 0.51363 -0.858006 -0.00323908 0.149672 -0.988731 0.00291612 0.270799 -0.962608 -0.00734 0.0943793 -0.995536 0 -0.171989 -0.985099 0 -0.0995873 -0.995012 -0.00575404 -0.935896 -0.352276 0.000577884 -0.761685 -0.647948 -0.000524281 -0.786409 -0.617698 -0.00324586 -0.495131 -0.868808 0.00423034 -0.613117 -0.789943 -0.00877056 -0.352665 -0.935745 0.00306702 -0.998428 -0.0560428 0 -0.99526 -0.0950434 0.02059 -0.892786 -0.449924 -0.0223862 -0.967463 -0.252968 -0.00469365 0.090595 0.995888 0 0.1793 0.983788 -0.00346064 0.273003 0.962013 9.05443e-05 0.445823 0.895121 -0.000101658 0.692766 0.721162 -7.30322e-05 0.522502 0.852638 0.000636652 0.637265 0.770557 -0.0116099 0.562639 0.826682 -0.00583355 0.799317 0.600907 -0.00162372 0.894563 0.446674 -0.0154742 0.79462 0.607102 0.00244607 0.926568 0.376126 -0.000701877 0.974907 0.222556 -0.00499922 0.955607 0.294642 0.00139743 0.998933 0.0461905 -0.000505691 0.99797 0.0636809 0 0.987802 -0.155717 -1.44834e-07 0.993482 -0.113948 -0.00295169 0.956402 -0.292053 0.000490965 0.892785 -0.450481 -0.0014934 0.851054 -0.525066 0.00346395 0.760631 -0.649184 -0.000642397 0.652343 -0.757923 0.00097169 0.682491 -0.730893 -0.000708374 0.463433 -0.886131 0.00134048 0.552922 -0.833205 -0.00690924 0.406163 -0.9138 -0.000188794 0.16022 -0.987081 0.000338087 0.241447 -0.970398 -0.00565792 0.082025 -0.99663 0 0.0910276 0.995848 0 0.185239 0.982687 -0.00350667 0.2728 0.962071 -0.000166208 0.445021 0.89552 0.000157527 0.587911 0.808903 -0.0060677 0.657673 0.753199 -0.012518 0.536744 0.843745 -0.000509034 0.710814 0.70338 0.00010972 0.834684 0.55072 -0.00317598 0.812562 0.582875 0.000183934 0.938461 0.345384 -6.861e-05 0.968343 0.2496 -0.00345907 0.990404 0.138195 0.00163195 0.99935 0.0360459 0 -0.979328 0.202277 1.70083e-07 -0.9871 0.16007 0.00350022 -0.885542 0.464555 -0.00204104 -0.822793 0.568329 0.00373944 -0.756457 0.654043 0.000295695 -0.643139 0.765749 -0.000317384 -0.534377 0.845236 0.00413614 -0.431299 0.902207 -0.0019583 -0.17793 0.98404 0.00226378 -0.14138 0.989955 0 -0.979189 0.202953 0 -0.986712 0.162441 0.00351071 -0.883141 0.469103 -0.00207597 -0.822832 0.568272 0.00374633 -0.751432 0.65981 0.000109721 -0.634671 0.772783 -0.000138983 -0.518826 0.854864 0.00517453 -0.415272 0.909696 -0.00182526 -0.159999 0.987116 0.0017726 -0.130041 0.991509 0 -0.173274 -0.984874 1.27833e-06 -0.0954243 -0.995418 -0.00618215 -0.263113 -0.964765 3.76281e-05 -0.499404 -0.866369 4.13875e-05 -0.356253 -0.93431 -0.0121582 -0.443898 -0.896062 -0.00521506 -0.977639 -0.210292 0 -0.59744 -0.801914 0.0005734 -0.742853 -0.669454 -0.000930201 -0.766476 -0.642267 -0.00273522 -0.863391 -0.504533 0.00114366 -0.939198 -0.343367 -0.00252452 -0.995905 -0.0897661 0.0107712 0.800674 -0.59906 -0.00699669 0.94763 -0.319362 0.00218051 0.986577 -0.163274 -0.00276316 0.996113 -0.0880852 0 0.105513 -0.994418 0 0.140471 -0.990084 -0.00156826 0.299148 -0.954206 0.000866852 0.309076 -0.951037 0.000615736 0.415158 -0.909749 -0.000613783 0.441128 -0.897443 -0.00130831 0.568802 -0.822472 0.00206777 0.665552 -0.746347 -0.00264184 0.873339 -0.487062 0.00703691 -0.193817 -0.981038 0 -0.160737 -0.986993 0.00272834 -0.406522 -0.913522 -0.0147446 -0.648847 -0.76085 0.0102561 -0.46194 -0.886909 -0.00171973 -0.507753 -0.861483 -0.00584664 -0.652794 -0.757536 0.000134343 -0.766477 -0.642272 -0.000135691 -0.905461 -0.42434 0.00871945 -0.740168 -0.671974 -0.024558 -0.781621 -0.623494 -0.0179742 -0.877836 -0.478943 -0.00424415 -0.936385 -0.350972 -0.00102469 -0.984596 -0.174833 0.00223098 -0.991792 -0.127862 0 -0.973541 0.228512 0 -0.988901 0.148469 -0.00560223 -0.942022 0.335551 -0.000637769 -0.814226 0.580547 0.00119837 -0.664868 0.74686 0.0122837 -0.872472 0.488545 -0.0107932 -0.724213 0.689576 0.000794605 -0.551143 0.834411 -0.000211364 -0.387379 0.921918 0.00199454 -0.247515 0.96885 0.00813717 -0.472385 0.881385 -0.00358758 -0.295587 0.955316 0 0.760054 -0.544312 -0.355024 0.484665 -0.867248 -0.113932 0.363357 -0.93165 -0.000613123 0.5826 -0.755485 -0.2997 0.020932 -0.997547 -0.0667927 0.13965 -0.990199 -0.00200295 0.565095 -0.420416 0.709872 0.156499 -0.967768 -0.197315 0.15639 -0.818322 -0.553075 0.201724 -0.820078 -0.535518 0.117265 -0.851376 -0.511281 0.122346 -0.852625 -0.507999 0.520097 -0.835964 -0.175108 0.140383 -0.895981 -0.421319 0.134775 -0.917315 -0.374659 0.106406 -0.872824 -0.476295 0.344516 -0.857966 -0.381056 0.365262 -0.829364 -0.422775 0.443567 -0.817043 -0.368359 0.466778 -0.750105 -0.468466 0.585309 -0.714214 -0.383812 0.453943 -0.723378 -0.52025 0.648966 -0.641087 -0.409695 0.889181 -0.405913 -0.211167 0.787 -0.509888 -0.347341 0.775063 -0.584005 -0.24128 0.726341 -0.611948 -0.312965 0.705386 -0.673028 -0.222405 0.778992 -0.618974 -0.100211 0.985453 -0.165992 -0.0364632 0.953229 -0.258025 -0.157411 0.940154 -0.338083 -0.0425444 0.90454 -0.40177 -0.142789 0.880136 -0.473269 -0.0371158 0.834773 -0.533944 -0.134376 0.798132 -0.601662 -0.0314371 0.743539 -0.656436 -0.12744 0.685559 -0.727876 -0.0143707 0.365984 -0.896817 -0.248547 0.220803 -0.96848 -0.115295 0.0388088 -0.907014 -0.419309 0.0336596 -0.919375 -0.391939 0.0197736 -0.975204 -0.220422 -0.000289621 -0.997798 -0.0663325 -0.000163568 -0.997765 -0.0668151 0.0261184 -0.979497 -0.199756 -0.00844689 -0.919861 -0.392155 -0.000329821 -0.879964 -0.475041 0.987647 -0.105165 -0.116162 0.453578 -0.598133 -0.660684 0.338108 -0.557273 -0.758373 0.453449 -0.526268 -0.719324 0.481155 -0.51909 -0.706424 0.706567 -0.419025 -0.570247 0.614731 -0.555279 -0.560153 0.162207 -0.662254 -0.731511 0.162308 -0.605616 -0.779029 -0.0252201 -0.591958 -0.805574 0.1564 -0.562762 -0.811688 0.890849 -0.3049 -0.336784 0.987647 -0.105166 -0.116163 0.987614 -0.0906474 -0.128069 0.995808 -0.0541609 -0.0737134 0.890766 -0.269101 -0.366225 0.706635 -0.418979 -0.570197 0.706722 -0.474829 -0.524482 0.453546 -0.598146 -0.660694 0.452612 -0.679958 -0.576888 -0.380238 -0.70526 -0.598354 0.156324 -0.77934 -0.606789 0.452729 -0.67991 -0.576853 0.70582 -0.54017 -0.458294 0.70674 -0.474816 -0.52447 0.890856 -0.304891 -0.336775 0.89081 -0.269044 -0.36616 0.969107 -0.146041 -0.198756 0.987591 -0.119753 -0.101607 0.987584 -0.119786 -0.101633 0.890425 -0.347046 -0.294452 0.890372 -0.347128 -0.294516 0.759276 -0.496229 -0.421019 0.648341 -0.582406 -0.490364 -3.11294e-05 -0.975329 -0.220756 -0.000767139 -0.975445 -0.220241 -0.00119659 -0.879965 -0.475037 0.012283 -0.92001 -0.391702 -0.0616887 -0.989241 -0.132652 0.184207 -0.401824 -0.896998 0.468313 0.168974 -0.867255 0.17792 0.403641 -0.897451 0.540193 -0.123581 -0.832418 0.521061 0.117993 -0.845325 0.45578 -0.159781 -0.875634 0.356516 -0.0529891 -0.932785 0.368277 -0.00399664 -0.929707 0.153598 0.0931216 -0.983736 0.156901 0.0766248 -0.984637 0.5336 0.657862 -0.531497 0.514745 0.434476 -0.7391 0.636496 0.345877 -0.689378 0.9958 -0.0553047 -0.0729659 0.984971 0.144273 -0.0949636 0.193774 0.978255 -0.0739499 0.516218 0.84688 -0.127723 0.640325 0.719305 -0.269416 0.67889 0.725036 -0.115895 0.794143 0.601382 -0.0876172 0.820516 0.571624 0.000944363 0.91666 0.377249 -0.131979 0.982206 0.187113 -0.0160979 0.716398 0.457616 -0.526652 0.849882 0.299971 -0.433264 0.848146 0.174486 -0.500204 0.884769 -0.147127 -0.442195 0.924256 -0.0213939 -0.381173 0.705712 -0.333126 -0.625298 0.81774 -0.121518 -0.562614 0.481714 -0.473893 -0.737141 0.600778 -0.335339 -0.725681 0.337894 -0.460808 -0.820661 0.21648 -0.508775 -0.833237 0.156342 -0.506915 -0.8477 0.572936 0.744342 -0.343073 0.69716 0.654494 -0.292584 0.737341 0.591017 -0.327149 0.867858 0.436096 -0.237998 0.896168 0.300018 -0.326912 0.978645 0.0774596 -0.190405 0.962686 -0.0368086 -0.268106 0.203186 -0.318202 -0.925993 0.148606 -0.337274 -0.929604 0.0882054 -0.24821 -0.964682 0.00875393 -0.318278 -0.947957 0.00871275 -0.31825 -0.947967 0.338383 0.881583 -0.329102 0.362683 0.751173 -0.551544 0.341288 0.741896 -0.577159 0.335014 0.549047 -0.765711 0.496038 0.476468 -0.725896 0.641461 0.362914 -0.675885 0.437353 0.247938 -0.864436 0.191299 0.354371 -0.915328 0.220277 0.696437 -0.682974 0.0900824 0.604859 -0.791221 0.140814 0.802438 -0.579884 0.195441 0.824029 -0.53177 0.0939875 0.929734 -0.356034 0.154607 0.973475 -0.168649 0.376889 0.819186 -0.432306 0.366172 0.861097 -0.352748 0.533586 0.7863 -0.311477 0.563217 0.613037 -0.554051 0.690139 0.5209 -0.502366 0.649263 0.289836 -0.703173 0.794361 0.117231 -0.596026 0.598627 -0.0441529 -0.799811 0.76911 0.00471608 -0.639099 0.592736 -0.211973 -0.777002 0.552138 -0.20355 -0.808524 0.20772 -0.438679 -0.874307 0.188821 -0.435347 -0.880239 -0.0555958 -0.917951 -0.392779 -0.022187 -0.901626 -0.431946 -0.0253533 -0.919846 -0.391459 -0.0258867 -0.99065 -0.133951 -0.025946 -0.990773 -0.133026 -0.132525 -0.982686 -0.129481 -0.132633 -0.982059 -0.134048 -0.117161 -0.914372 -0.387553 -0.117105 -0.912347 -0.392312 -0.000484041 0.972278 -0.233826 -0.00104371 -0.257695 -0.966226 0.0429856 -0.317968 -0.947127 -0.0340355 0.0775408 -0.996408 -0.0158557 0.114702 -0.993273 0.00730968 0.384798 -0.922972 -0.00210515 0.410185 -0.912 -0.0018954 0.607815 -0.794076 -0.00168588 0.607328 -0.79445 -0.00167532 0.714647 -0.699483 -0.0179287 0.840097 -0.54214 -0.0400193 0.818951 -0.572466 0.0447068 0.984338 -0.17053 -6.90648e-05 0.972348 -0.233537 -0.33258 -0.791366 -0.512962 -0.26289 -0.955171 -0.13615 -0.914264 -0.403678 -0.0341419 -0.197747 -0.89829 -0.392393 -0.492718 -0.870018 -0.0172535 -0.519391 -0.851885 0.0672663 -0.389277 -0.911624 -0.131925 -0.22545 -0.881458 -0.414974 -0.258184 -0.884362 -0.388903 -0.665362 -0.641264 -0.382196 -0.878169 -0.413338 -0.240771 -0.797067 -0.542338 -0.265619 -0.986128 -0.153477 -0.0632149 -0.924236 -0.36796 -0.101952 -0.384152 -0.7832 -0.488902 -0.769431 -0.573479 -0.281245 -0.512738 -0.768809 -0.382143 -0.783931 -0.5858 -0.205647 -0.677996 -0.692003 -0.247896 -0.909589 -0.412404 -0.0506983 -0.796537 -0.599099 -0.0812922 -0.747331 -0.664406 0.00782074 -0.654892 -0.745125 -0.126115 -0.627379 -0.763932 -0.151008 -0.539262 -0.801258 -0.259197 -0.47611 -0.822934 -0.309997 -0.384798 -0.829614 -0.404564 -0.302889 -0.838261 -0.453406 -0.0713015 -0.254272 -0.964501 -0.12219 -0.322794 -0.938549 -0.0137445 0.993522 -0.11281 -0.0346138 0.972065 -0.232144 -0.0414838 0.93931 -0.340554 -0.0692339 0.819573 -0.568776 -0.0692139 0.819885 -0.568329 -0.0938443 0.629538 -0.771282 -0.0938335 0.63031 -0.770652 -0.111401 0.385559 -0.915934 -0.111433 0.387117 -0.915272 -0.119888 0.116178 -0.985966 -0.120003 0.118507 -0.985675 -0.116763 -0.250781 -0.960976 -0.0323447 -0.254139 -0.966627 -0.0319336 -0.257558 -0.965735 -0.0329826 0.116278 -0.992669 -0.0328859 0.114654 -0.992861 -0.0306326 0.385837 -0.922058 -0.0305626 0.38461 -0.922573 -0.0257836 0.629863 -0.776278 -0.00779663 0.972247 -0.233827 -0.0077843 0.972208 -0.23399 -0.0189854 0.819471 -0.572807 -0.0190062 0.819808 -0.572322 -0.0231899 0.714443 -0.69931 -0.0245204 0.607622 -0.793848 -0.986766 -0.123886 -0.104622 -0.986731 -0.124042 -0.104765 -0.878593 -0.364876 -0.308124 -0.878305 -0.365264 -0.308484 -0.666006 -0.569928 -0.481267 -0.665296 -0.570386 -0.481706 -0.385035 -0.705138 -0.595423 -0.383616 -0.70555 -0.595851 -0.98694 -0.102193 -0.124522 -0.986741 -0.102926 -0.125491 -0.880266 -0.30106 -0.366734 -0.878407 -0.303113 -0.369491 -0.670935 -0.470539 -0.573096 -0.66566 -0.473319 -0.576945 -0.393918 -0.583289 -0.710354 -0.384732 -0.585452 -0.713602 -0.814933 0.579152 -0.0216138 -0.863454 0.334019 -0.377992 -0.88942 0.0387817 -0.455443 -0.986886 -0.0719741 -0.144482 -0.881644 0.138526 -0.451125 -0.817717 0.235804 -0.525106 -0.779431 0.230033 -0.582728 -0.695498 0.312015 -0.647247 -0.695585 0.50099 -0.514947 -0.162309 0.93479 -0.315948 -0.215403 0.911666 -0.349953 -0.384462 0.874966 -0.294319 -0.44774 0.830904 -0.330345 -0.670486 0.710761 -0.212762 -0.404035 -0.272516 -0.873207 -0.341657 -0.29865 -0.891111 -0.495458 0.0133958 -0.868529 -0.456793 0.294135 -0.839539 -0.590864 0.231943 -0.772711 -0.483148 0.135383 -0.865008 -0.621273 0.038411 -0.782652 -0.387213 -0.323869 -0.863235 -0.388525 -0.409413 -0.825488 -0.463637 -0.394007 -0.793599 -0.990845 0.0581853 -0.12182 -0.881116 -0.242341 -0.406087 -0.906245 -0.15376 -0.3938 -0.672774 -0.390964 -0.628109 -0.736237 -0.27702 -0.617426 -0.395524 -0.480729 -0.782598 -0.364761 -0.502726 -0.78372 -0.112547 0.989232 -0.0935569 -0.225711 0.957702 -0.178499 -0.313517 0.94683 -0.0722518 -0.421526 0.899653 -0.113752 -0.567118 0.822656 -0.0401826 -0.622466 0.777378 -0.0906636 -0.773714 0.627947 -0.083958 -0.211569 0.815722 -0.538365 -0.259706 0.784556 -0.563049 -0.432477 0.746343 -0.505901 -0.481368 0.697822 -0.530406 -0.706641 0.578377 -0.407601 -0.687236 0.637499 -0.348285 -0.836939 0.496977 -0.22923 -0.832012 0.50704 -0.225092 -0.903189 0.404172 -0.144553 -0.948654 0.272384 -0.160818 -0.969135 0.215681 -0.11941 -0.282143 0.385337 -0.878585 -0.35731 0.479521 -0.801492 -0.341179 0.117184 -0.932665 -0.327972 0.088026 -0.940577 -0.258264 -0.250494 -0.933034 -0.249672 -0.261258 -0.93242 -0.249451 0.6275 -0.737575 -0.281968 0.597723 -0.750481 -0.453086 0.55978 -0.693801 -0.485153 0.514642 -0.706944 -0.613025 0.456217 -0.645033 -0.703525 0.196211 -0.683047 -0.63086 -0.0123105 -0.775799 -0.692143 -0.0805221 -0.717255 -0.713654 -0.0772133 -0.69623 -0.691753 -0.209116 -0.691193 -0.71669 -0.276507 -0.640234 -0.907029 -0.00798119 -0.420992 -0.897438 -0.103997 -0.428708 -0.963179 0.231804 -0.136209 -0.984722 0.0938617 -0.146669 -0.075444 -0.61825 -0.782352 -0.0663454 -0.618148 -0.783257 0.261683 -0.598265 -0.757365 0.386005 -0.56785 -0.727013 0.488977 -0.540504 -0.684658 0.689763 -0.448787 -0.56817 0.947239 -0.198665 -0.251535 0.97594 -0.132079 -0.173482 0.994407 -0.0654507 -0.0828936 -0.0663793 -0.725366 -0.685155 -0.0628096 -0.725361 -0.685497 0.386303 -0.670533 -0.633368 0.272021 -0.706073 -0.653808 0.496475 -0.630931 -0.596187 0.775028 -0.459381 -0.433936 0.774683 -0.388038 -0.499293 0.845866 -0.330519 -0.41865 0.6948 -0.529166 -0.48707 0.848164 -0.385032 -0.363824 0.976033 -0.158202 -0.149439 0.948156 -0.235937 -0.21292 0.994477 -0.0762871 -0.0720825 0.700683 0.702836 -0.122736 0.284266 0.953632 -0.0988883 0.0559241 0.968996 -0.240663 -0.228042 -0.25243 -0.940359 -0.364198 -0.231768 -0.902022 -0.360922 -0.238617 -0.901553 -0.291546 0.138109 -0.946534 0.203982 0.554421 -0.806851 0.221201 0.556007 -0.801203 0.433113 0.409478 -0.802957 0.422372 0.41 -0.808395 0.603634 0.219044 -0.766581 0.62039 0.696708 -0.36016 0.408521 0.840218 -0.356574 0.417635 0.828314 -0.373467 0.173279 0.92932 -0.326095 0.318893 0.728441 -0.606367 0.338855 0.727622 -0.596442 0.556862 0.576092 -0.59835 0.544641 0.578164 -0.607529 0.73422 0.377994 -0.563952 0.704518 0.384054 -0.596789 0.839188 0.168359 -0.517125 0.965385 0.0748146 -0.24987 0.940593 -0.0752096 -0.331102 0.270607 -0.403741 -0.873936 0.287325 -0.383322 -0.877786 -0.0381195 -0.485039 -0.873661 -0.0214418 -0.489676 -0.871641 -0.075682 -0.540083 -0.838202 0.285014 -0.483766 -0.827488 0.262285 -0.50259 -0.823778 0.688359 -0.327477 -0.647241 0.652547 -0.324493 -0.684753 0.727932 -0.136767 -0.67187 0.664775 0.0230169 -0.746689 0.669935 0.0287547 -0.741863 0.0162749 0.0452055 -0.998845 -0.221763 -0.302317 -0.927052 0.0155258 0.0418817 -0.999002 -0.294246 0.170959 -0.940315 -0.17253 0.513166 -0.84077 -0.326775 0.402296 -0.855205 -0.215437 0.661983 -0.71789 -0.258245 0.638789 -0.724747 -0.113473 0.842664 -0.526347 -0.171272 0.822447 -0.542444 -0.0397268 0.934395 -0.354016 0.809928 0.578583 -0.0962217 0.795054 0.588159 -0.148184 0.913704 0.399826 -0.0726918 0.903273 0.402633 -0.148273 0.978288 0.20096 -0.0506741 0.978293 0.201703 -0.0475248 0.9942 -0.0399636 -0.0998511 0.882279 0.302316 -0.360817 0.907416 0.29843 -0.295863 0.776235 0.508113 -0.373203 0.800379 0.500066 -0.330647 0.627775 0.684397 -0.370809 0.645348 0.758729 -0.0886354 0.441923 0.8631 -0.244463 0.514992 0.846746 -0.133431 0.35387 0.928315 -0.114047 -0.0940507 -0.351729 -0.931365 -0.119848 -0.414805 -0.901983 0.243511 -0.192851 -0.950532 0.22419 -0.219998 -0.949389 0.43573 -0.0517226 -0.89859 0.525998 -0.272415 -0.805677 0.503942 -0.31213 -0.805368 0.521067 -0.407606 -0.749898 0.489681 -0.445062 -0.749755 0.0511445 0.987615 -0.148328 -0.0499657 0.955324 -0.291307 0.189225 0.908359 -0.372933 0.0600205 0.808517 -0.585404 0.112373 0.815798 -0.567314 -0.0420605 0.628057 -0.77703 -0.000414989 0.640232 -0.768182 -0.132147 0.411481 -0.901787 0.069244 0.32812 -0.942095 0.238993 0.364084 -0.90018 0.264259 0.198333 -0.943839 0.416667 0.0379288 -0.908268 0.574579 0.22227 -0.787689 0.701424 0.0189996 -0.712491 0.804298 0.17298 -0.568492 0.890294 -0.0649308 -0.450734 0.840135 -0.189819 -0.508077 0.271392 -0.794499 -0.543248 -0.349511 -0.917658 -0.189063 0.760997 -0.636648 -0.124751 0.870773 -0.470206 -0.143736 0.954361 -0.28711 -0.0822412 0.993884 -0.103131 -0.0394908 0.881071 -0.427436 -0.202513 0.77792 -0.602716 -0.177692 0.930347 -0.363099 -0.0511273 0.942422 -0.333962 -0.017583 0.947334 -0.272518 -0.168205 0.765823 -0.557144 -0.321101 0.74904 -0.62054 -0.232097 0.592337 -0.718969 -0.363623 0.553593 -0.796859 -0.241973 0.471327 -0.818537 -0.328402 0.420245 -0.881476 -0.215391 0.335845 -0.893041 -0.299476 0.244165 -0.958615 -0.14643 0.0562391 -0.954703 -0.292197 -0.0969689 -0.984163 -0.148395 0.10912 -0.987804 0.111072 0.123859 -0.991993 -0.0246775 0.162961 -0.985479 -0.0477028 0.388018 -0.921029 0.0338927 0.352126 -0.935932 -0.00630919 0.416231 -0.904809 -0.0898409 0.543958 -0.839046 0.0105748 0.589715 -0.80499 -0.0650173 0.164065 -0.817002 -0.552803 0.622186 -0.665587 -0.412162 0.496056 -0.712274 -0.496582 0.694353 -0.586843 -0.416521 -0.0628392 -0.805819 -0.588818 -0.118064 -0.790503 -0.60097 -0.11439 -0.847498 -0.518326 0.135049 -0.908581 -0.395275 -0.328507 -0.796526 -0.507572 -0.435206 -0.898076 -0.0636808 -0.223258 -0.956712 0.186702 -0.344887 -0.928485 -0.137726 -0.156572 -0.957674 -0.241549 -0.213256 -0.929766 -0.300095 -0.121859 -0.914234 -0.386429 -0.251675 -0.965862 0.0614006 -0.14582 -0.976245 -0.160256 0.0108638 -0.998739 -0.0490197 0.106986 -0.98439 -0.139749 0.707392 -0.684883 0.174737 0.445848 -0.892069 -0.0737082 0.505139 -0.845399 -0.173594 0.662605 -0.747867 -0.0406041 0.708807 -0.690802 -0.142774 0.844502 -0.535552 0.00101887 0.86242 -0.503706 -0.0501243 -0.399647 -0.834849 -0.378561 -0.393958 -0.830875 -0.392993 -0.294488 -0.882005 -0.367891 -0.303176 -0.834499 -0.460104 -0.190386 -0.872134 -0.450705 0.0175198 -0.943257 -0.331602 0.0929219 -0.883675 -0.458785 0.393602 -0.878492 -0.270792 0.142881 -0.862222 -0.485961 0.314762 -0.864107 -0.39274 0.336381 -0.821463 -0.460486 0.599033 -0.714092 -0.362261 0.610664 -0.665766 -0.428771 0.84762 -0.439251 -0.297656 -0.382732 0.403306 -0.831181 -0.503057 -0.375005 -0.778656 -0.417732 0.139522 -0.897794 -0.456255 -0.470124 -0.755523 -0.45906 -0.231899 -0.857605 -0.316726 0.704776 -0.634804 -0.407775 0.814394 -0.412895 -0.0777202 0.938121 -0.337473 -0.44637 0.617468 -0.647678 -0.213353 0.848424 -0.484415 -0.0528921 0.993614 -0.0996653 -0.000642121 -0.999996 -0.00268315 -0.58927 -0.465647 -0.660253 -0.607245 -0.325474 -0.72479 -0.189051 0.82354 -0.534829 -0.575907 -0.359669 -0.734145 -0.308686 0.640556 -0.703137 -0.5359 -0.432586 -0.725038 -0.541635 -0.331766 -0.772375 -0.586752 -0.716188 -0.377884 -0.541359 -0.838198 -0.0659954 -0.633731 -0.551441 -0.542492 -0.711532 -0.691663 -0.123794 -0.557518 -0.490922 -0.669454 -0.634664 -0.679993 -0.367165 -0.497775 -0.779534 -0.380193 -0.329746 -0.461011 -0.823854 -0.565592 -0.80148 -0.194255 -0.570542 -0.811148 -0.128536 -0.235314 -0.31484 0.919513 -0.996028 -0.00658062 -0.0887975 -0.996026 -0.00658444 -0.0888203 -0.919181 -0.366444 -0.14431 -0.919181 -0.366442 -0.144316 -0.842733 -0.389857 -0.371232 -0.863139 -0.479329 -0.158852 -0.958251 -0.0250708 -0.284827 -0.493111 0.869822 -0.0158314 -0.975889 0.212846 -0.048348 -0.975822 0.212995 -0.0490353 -0.927305 0.104927 -0.3593 -0.995525 0.0525095 -0.0785727 -0.995533 0.0525563 -0.0784407 -0.991408 0.071891 -0.109281 -0.99141 0.0718174 -0.109305 -0.208612 -0.947214 -0.243448 -0.746974 -0.656144 0.107264 -0.927117 0.102877 0.360375 -0.996018 -0.00660192 -0.0889066 -0.996032 -0.00653831 -0.0887561 -0.899074 0.395662 -0.187394 -0.899083 0.395639 -0.187401 -0.912119 -0.313615 -0.263979 -0.991306 0.0446128 -0.12378 -0.99298 -0.0652435 -0.0986578 -0.925816 -0.149471 -0.347166 -0.951281 0.130574 -0.279313 -0.835653 -0.360244 -0.414618 -0.884245 -0.232131 -0.405248 -0.151569 0.18598 -0.970793 -0.0347888 0.982565 -0.182635 -0.034941 0.982355 -0.183734 -0.102509 0.837282 -0.537076 -0.103159 0.833773 -0.542384 -0.156783 0.548687 -0.821195 -0.157308 0.539361 -0.827251 -0.182008 -0.256905 -0.949143 -0.258077 0.17159 -0.950764 -0.00648918 0.965905 -0.258814 -0.00998233 0.982935 -0.183684 -0.0110329 0.79482 -0.606744 -0.013631 0.838232 -0.545144 -0.0198646 0.610624 -0.791671 -0.0182759 0.55007 -0.834919 -0.0278856 0.258717 -0.96555 -0.024502 0.186117 -0.982222 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.794869 -0.606781 -0.051028 0.706195 -0.706177 0 0.610745 -0.791828 0 0.258818 -0.965926 0 0.258818 -0.965926 -0.417646 0.481617 -0.770465 -0.418842 0.129608 -0.898762 -0.362513 0.913941 -0.182474 -0.289554 0.944368 -0.155973 -0.190361 0.963376 -0.188862 -0.107169 0.981106 -0.161079 -0.338232 0.160245 -0.927319 -0.344285 0.171428 -0.923082 -0.345788 0.562684 -0.750878 -0.319441 0.540313 -0.778473 -0.423513 0.190417 -0.885651 -0.551302 0.426241 -0.717206 -0.549661 0.445146 -0.706907 -0.569523 0.707344 -0.418699 -0.696569 0.514172 -0.500418 -0.536308 0.826656 -0.170333 -0.670472 0.708346 -0.220713 -0.218373 0.833961 -0.506777 -0.281122 0.80457 -0.523104 -0.373341 0.786527 -0.491927 -0.41877 0.75365 -0.5066 -0.540402 0.703664 -0.461328 -0.455431 0.877622 -0.149539 -0.51873 0.836492 -0.176637 0.193079 0.172832 -0.965841 0.0464508 0.258539 -0.964883 0.0464506 0.258539 -0.964883 0.126031 0.701477 -0.70146 0.12603 0.701479 -0.701458 0.170985 0.951701 -0.255008 0.14343 0.222378 -0.964353 0.14343 0.222381 -0.964352 0.387804 0.601268 -0.698631 0.387804 0.601266 -0.698632 0.193088 0.172804 -0.965845 0.454027 0.406329 -0.792942 0.643967 0.330439 -0.690012 0.591431 0.52936 -0.608266 0.670988 0.600566 -0.434852 0.170987 0.9517 -0.25501 0.524366 0.812997 -0.253132 0.524356 0.813009 -0.253114 0.822462 0.509633 -0.252648 0.731975 0.655145 -0.187076 -0.864202 0.46595 -0.189856 -0.887078 0.446593 -0.116819 -0.826783 0.341607 -0.446918 -0.768032 0.564744 -0.301978 -0.786512 0.595334 -0.164246 -0.782253 0.59857 -0.172608 -0.478919 0.0687536 -0.875163 -0.53218 0.0926417 -0.841547 -0.654271 0.270238 -0.70633 -0.704302 0.302779 -0.642093 -0.776392 0.430411 -0.460393 -0.981563 0.179155 -0.0666085 -0.969387 0.195106 -0.149075 -0.908298 0.13427 -0.396191 -0.895825 0.13847 -0.422283 -0.747083 0.0660082 -0.661446 -0.737956 0.0671788 -0.671497 -0.512798 -0.00859871 -0.858466 -0.514455 -0.00867382 -0.857474 0.484338 0.269838 -0.832228 0.512241 0.332806 -0.791739 0.184857 0.038449 -0.982013 0.229195 0.127728 -0.964964 0.858365 0.478559 -0.184907 0.858319 0.478734 -0.184668 0.733154 0.408726 -0.543533 0.740503 0.512828 -0.434352 0.696665 0.388437 -0.603137 0.968488 0.166319 -0.185388 0.968533 0.166882 -0.184648 0.827206 0.141346 -0.543831 0.827464 0.141843 -0.543308 0.546527 0.0924405 -0.832324 0.546874 0.0928 -0.832056 0.187248 0.0302088 -0.981848 0.187625 0.0304785 -0.981768 -0.990396 -0.0161404 -0.137314 -0.990066 -0.0106959 -0.140197 -0.992796 -0.0117187 -0.119239 -0.907765 -0.0402944 -0.417539 -0.910762 -0.0401501 -0.410976 -0.741853 -0.0643044 -0.667472 -0.750248 -0.0642698 -0.658025 -0.514595 -0.0821397 -0.85349 -0.529675 -0.0824475 -0.844184 0.135093 -0.0489735 -0.989622 0.982277 -0.0021146 -0.187421 0.988048 -0.00738489 -0.153969 0.999908 -0.000510262 -0.0135822 0.0559283 -0.0194925 -0.998245 0.187301 -0.0271335 -0.981928 0.318153 -0.02309 -0.947758 0.548948 -0.0203577 -0.835609 0.480904 -0.0285691 -0.876308 0.668501 -0.0171861 -0.743513 0.835752 -0.0154857 -0.548889 0.84941 -0.0129612 -0.527574 0.97956 -0.00481677 -0.201093 -0.652759 -0.740486 -0.15996 -0.788486 -0.604848 -0.111579 -0.818807 -0.573553 -0.0243333 -0.889626 -0.428303 -0.158499 -0.529458 -0.162525 -0.832622 -0.45884 -0.169299 -0.872241 -0.40231 -0.26399 -0.876616 -0.461935 -0.26594 -0.846104 -0.494577 -0.233872 -0.837077 -0.346876 -0.330531 -0.877739 -0.95953 -0.261291 -0.10502 -0.981326 -0.191914 -0.0129478 -0.986654 -0.105147 -0.124329 -0.900884 -0.203003 -0.383663 -0.892096 -0.21024 -0.399956 -0.775303 -0.482445 -0.407618 -0.787543 -0.482446 -0.383435 -0.592409 -0.677089 -0.43658 -0.529643 -0.847079 -0.0439984 -0.369499 -0.870837 -0.324213 -0.400388 -0.911676 -0.0923986 -0.135786 -0.972932 -0.186992 -0.162192 -0.979866 -0.116435 -0.39621 -0.254824 -0.88209 -0.435548 -0.828487 -0.352006 -0.370689 -0.630966 -0.681521 -0.260828 -0.865646 -0.427348 -0.146678 -0.761695 -0.631116 -0.34145 -0.906634 -0.247844 -0.312532 -0.821643 -0.476684 -0.571185 -0.720414 -0.393385 -0.539701 -0.50283 -0.675193 -0.672603 -0.372409 -0.639466 -0.91853 -0.38697 -0.0809773 -0.746615 -0.192164 -0.636898 0.846045 -0.119756 -0.519486 0.614012 -0.770271 -0.172253 0.941206 -0.286245 -0.17943 0.450216 -0.370899 -0.812244 0.975252 -0.104978 -0.194584 0.97638 -0.100514 -0.191258 0.994987 -0.0996865 -0.00794645 0.777228 -0.60073 -0.187191 0.825001 -0.552784 -0.11749 0.678739 -0.506712 -0.531561 0.690129 -0.50298 -0.52032 0.451776 -0.374022 -0.809942 0.0596984 -0.985224 -0.16053 0.10246 -0.604729 -0.789813 0.159481 -0.85378 -0.495607 0.165035 -0.84661 -0.505979 0.183875 -0.979075 -0.0871876 0.244194 -0.954838 -0.169272 0.340132 -0.129105 -0.931473 0.317376 -0.129041 -0.939479 0.0872971 -0.106649 -0.990457 0.135086 -0.067312 -0.988545 0.134457 -0.172419 -0.975804 0.140652 -0.206155 -0.968358 0.105003 -0.241697 -0.964654 0.887329 -0.420803 -0.188603 0.940342 -0.291524 -0.175418 0.790089 -0.284965 -0.542729 0.866716 -0.179255 -0.46548 0.532673 -0.182504 -0.826409 0.667152 -0.109494 -0.73683 0.478442 -0.151818 -0.864896 0.0404173 -0.270941 -0.961747 0.0344146 -0.43506 -0.899744 0.0477426 -0.214885 -0.975472 0.297303 -0.781301 -0.548799 0.295456 -0.525773 -0.797664 0.451811 -0.72625 -0.518101 0.450433 -0.733335 -0.509244 0.541289 -0.82111 -0.181065 0.475089 -0.879937 -0.00112651 -0.0228786 -0.863063 -0.504578 -0.0228035 -0.860143 -0.509544 -0.00780839 -0.985121 -0.171683 -0.00780806 -0.985082 -0.17191 -0.0425702 -0.286213 -0.95722 -0.0431231 -0.300494 -0.952808 -0.221206 -0.299263 -0.928175 -0.217668 -0.328587 -0.919049 -0.18248 -0.616888 -0.765604 -0.0355575 -0.618602 -0.7849 -0.0352898 -0.610205 -0.791457 -0.0387372 -0.98593 -0.162611 -0.0390975 -0.985707 -0.163868 -0.114396 -0.868401 -0.482487 -0.11751 -0.862066 -0.492985 -0.149678 -0.761875 -0.630192 -0.178674 -0.632513 -0.75366 -0.0061091 -0.864833 -0.502023 1.20988e-05 -0.986984 -0.160817 0.00570805 -0.986011 -0.166581 9.05208e-05 -0.985112 -0.171912 -0.000128373 -0.607929 -0.793991 0.00174836 -0.610565 -0.791964 -0.000980604 -0.860357 -0.509691 0.000607235 -0.435318 -0.900277 0.00883013 -0.271152 -0.962496 0.000290993 -0.286519 -0.958075 0.549485 -0.147237 -0.822428 0.194834 -0.0522044 -0.979446 0.194829 -0.0522046 -0.979447 0.439197 -0.117684 -0.890649 0.602934 -0.137683 -0.785821 0.948557 -0.254171 -0.188778 0.948568 -0.254155 -0.188741 0.811604 -0.217458 -0.542228 0.882089 -0.180537 -0.435115 0.776061 -0.207949 -0.595388 0.142622 -0.142625 -0.979447 0.142622 -0.142625 -0.979447 0.402255 -0.402263 -0.82242 0.402268 -0.402268 -0.822412 0.594128 -0.594128 -0.542239 0.5941 -0.594125 -0.542274 0.694382 -0.694412 -0.188751 0.694427 -0.694391 -0.188658 0.0522033 -0.194826 -0.979448 0.0522016 -0.194823 -0.979448 0.147239 -0.549516 -0.822407 0.147241 -0.549518 -0.822405 0.217457 -0.811572 -0.542276 0.217459 -0.811573 -0.542273 0.254169 -0.948578 -0.188673 0.254165 -0.948578 -0.188681 0.1951 0 -0.980783 0.1951 0 -0.980783 0.442271 0 -0.896882 0.442271 0 -0.896882 0.608731 0 -0.793377 0.608731 0 -0.793377 0.793405 0 -0.608694 0.793405 0 -0.608694 0.896825 0 -0.442385 0.896825 0 -0.442385 0.980774 0 -0.195149 0.980774 0 -0.195149 0 -0.980786 -0.195088 0 -0.980786 -0.195088 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555574 -0.831467 0 -0.555574 -0.831467 0 -0.195089 -0.980785 0 -0.195089 -0.980785 0.19483 0.0522032 -0.979447 0.207932 0.776024 -0.595441 0.160988 0.600825 -0.783002 0.132267 0.556499 -0.820252 0.0930477 0.257695 -0.961736 0.0522025 0.194825 -0.979448 0.194834 0.052206 -0.979446 0.439197 0.117684 -0.890649 0.556468 0.132264 -0.820274 0.142622 0.142624 -0.979447 0.142622 0.142625 -0.979447 0.402263 0.402271 -0.822412 0.402258 0.402258 -0.822421 0.594114 0.594114 -0.542271 0.594116 0.594142 -0.542237 0.872004 0.233641 -0.430141 0.818006 0.198895 -0.53973 0.776061 0.207949 -0.595388 0.600791 0.160985 -0.783028 0.254165 0.948578 -0.188681 0.180495 0.882133 -0.435044 0.217458 0.811571 -0.542277 0.254169 0.948578 -0.188673 0.694394 0.694424 -0.188661 0.694414 0.694379 -0.188753 0.948562 0.254153 -0.188777 0.948564 0.254173 -0.18874 -0.254258 -0.206749 -0.944779 -0.033975 -0.982833 -0.181341 -0.0335642 -0.983163 -0.179623 -0.00450509 -0.982946 -0.183837 -0.00535096 -0.980772 -0.195085 -0.0126703 -0.839217 -0.543649 -0.0137034 -0.831393 -0.555516 -0.0201314 -0.552858 -0.833033 -0.0199178 -0.555464 -0.831302 -0.0241804 -0.190502 -0.981389 -0.0239142 -0.195034 -0.980505 -0.149588 -0.190318 -0.970259 -0.177368 0.232915 -0.956186 -0.153513 -0.551405 -0.819992 -0.151756 -0.560798 -0.813927 -0.100341 -0.838289 -0.535913 -0.0997906 -0.839733 -0.533751 -0.0666139 -0.931877 -0.356607 0 0.980786 -0.195088 0.0382549 0.965219 -0.25863 0 0.896863 -0.442308 0 0.793365 -0.608747 0 0.793365 -0.608747 0 0.608765 -0.79335 0 0.608765 -0.79335 0 0.258818 -0.965926 0 0.258818 -0.965926 -0.496251 -0.0666929 -0.865614 -0.79854 -0.44111 -0.409581 -0.543166 -0.707132 -0.452698 -0.185989 -0.92911 -0.31963 -0.410088 -0.90513 -0.112105 -0.189691 -0.96403 -0.186179 -0.110064 -0.981613 -0.155956 -0.797636 -0.590991 -0.120444 -0.818501 -0.571823 -0.0554498 -0.899282 -0.403832 -0.167964 -0.965367 -0.240119 -0.102025 -0.39307 -0.240723 -0.887439 -0.308627 -0.793663 -0.52426 -0.3607 -0.55868 -0.746841 -0.345203 -0.528736 -0.775418 -0.336958 -0.206557 -0.918582 -0.30357 -0.143456 -0.941948 -0.986767 -0.0767119 -0.142849 -0.978474 -0.2032 -0.0360185 -0.896858 -0.162091 -0.411549 -0.779095 -0.4385 -0.448027 -0.668446 -0.29554 -0.682521 -0.256124 -0.836755 -0.483986 -0.359232 -0.879947 -0.310877 -0.366842 -0.868456 -0.333483 -0.481584 -0.86011 -0.168189 -0.656306 -0.740618 -0.14404 -0.464247 -0.121401 -0.877346 -0.43675 -0.0687341 -0.896953 -0.902524 -0.350432 -0.250295 -0.727246 -0.116671 -0.676388 -0.892238 -0.164794 -0.420422 -0.639453 -0.747371 -0.18038 -0.65219 -0.709248 -0.267609 -0.580112 -0.654863 -0.48438 -0.54323 -0.448306 -0.709876 -0.526902 -0.433722 -0.73093 -0.402957 -0.146949 -0.903345 -0.433489 -0.151649 -0.888307 -0.153496 0.165997 -0.974107 -0.153902 0.184187 -0.970767 -0.131573 0.534391 -0.834934 -0.131157 0.545955 -0.827484 -0.099868 0.768218 -0.632351 -0.0890048 0.834118 -0.544358 -0.0731716 0.883813 -0.462082 -0.043892 0.959634 -0.277806 -0.0318669 0.98205 -0.185912 -0.014536 0.995667 -0.0918437 -0.00534579 0.965912 -0.258816 -0.009003 0.982227 -0.18748 -0.00852964 0.793336 -0.608724 -0.0112784 0.834988 -0.550153 -0.0163422 0.608684 -0.793244 -0.0145661 0.547032 -0.836985 -0.0236231 0.258746 -0.965657 -0.0201066 0.18473 -0.982584 -0.481012 -0.0336103 -0.876069 -0.98897 -0.00550345 -0.148017 -0.989303 -0.00556911 -0.14577 -0.89912 -0.0160943 -0.437406 -0.902399 -0.0163693 -0.43059 -0.721611 -0.0253685 -0.691834 -0.73037 -0.0259302 -0.682559 -0.491534 -0.0318631 -0.870275 -0.496566 -0.0325316 -0.867389 -0.418607 0.00215747 -0.908165 -0.899855 0.13028 -0.416278 -0.888717 0.135358 -0.438019 -0.718558 0.0659817 -0.69233 -0.599668 0.710796 -0.367651 -0.571034 0.645033 -0.507791 -0.445241 0.143168 -0.883891 -0.378659 0.101424 -0.919962 -0.514742 0.400992 -0.75779 -0.534 0.417004 -0.735494 -0.577061 0.61748 -0.534527 -0.445161 0.891179 0.0873559 -0.558157 0.825437 -0.0843516 -0.287637 0.954201 -0.0822569 -0.140165 0.988474 0.0572069 -0.10714 0.991983 -0.0670088 -0.687097 0.720495 -0.0937294 -0.825147 0.564735 -0.0144061 -0.821568 0.548404 -0.155817 -0.972607 0.184054 -0.141982 -0.970487 0.186845 -0.152462 -0.293266 0.87002 -0.396309 -0.291438 0.837018 -0.463104 -0.319476 0.759442 -0.56673 -0.313532 0.72372 -0.614757 -0.340443 0.531785 -0.775437 -0.32386 0.503424 -0.801049 -0.306225 0.166576 -0.937272 -0.318453 0.188811 -0.928945 -0.480992 -0.0236588 -0.876406 -0.436782 0.0183768 -0.899379 -0.891222 0.316136 -0.325242 -0.663778 0.254164 -0.70342 -0.780402 0.413212 -0.469286 -0.803793 0.417298 -0.424004 -0.828736 0.525618 -0.192152 -0.587364 0.759877 -0.278551 -0.590098 0.782711 -0.197862 -0.260368 0.917703 -0.30005 -0.255862 0.942166 -0.216467 -0.972663 -0.19367 -0.128136 -0.914061 -0.157597 -0.373705 -0.91356 -0.157425 -0.375 -0.980549 -0.172118 0.0943299 -0.980913 -0.14642 -0.127947 -0.871299 -0.34018 -0.353717 -0.960105 -0.248389 -0.128461 -0.84339 -0.536386 -0.0313706 -0.846655 -0.4907 -0.205886 -0.885652 -0.458056 0.0761948 -0.895187 -0.445563 -0.0107163 -0.88677 -0.238509 -0.39592 -0.896516 -0.23692 -0.374338 -0.656509 -0.660564 -0.364213 -0.524943 -0.800042 -0.290461 -0.441452 -0.874712 -0.200001 -0.180842 -0.983302 -0.0203194 -0.322758 -0.935528 -0.143581 -0.398667 -0.916532 -0.032158 -0.297449 -0.948694 0.107257 -0.783714 -0.376147 -0.494273 -0.819549 -0.300133 -0.488119 -0.593218 -0.755259 -0.278705 -0.779904 -0.507423 -0.366431 -0.588014 -0.784102 -0.198552 -0.696694 -0.676879 -0.237599 -0.647987 -0.734027 -0.203267 -0.81824 -0.319901 -0.477647 -0.840582 -0.306111 -0.446898 -0.780434 -0.507115 -0.365727 -0.857608 -0.332254 -0.392576 -0.749898 -0.641567 -0.161381 -0.823894 -0.517544 -0.23097 -0.609528 -0.792643 0.013902 -0.791117 -0.604431 -0.0937905 -0.924591 -0.0664648 -0.375119 -0.780439 0.604456 -0.159836 -0.899461 0.169958 -0.402598 -0.882796 0.367918 -0.292075 -0.920142 0.170431 -0.35255 -0.728425 0.679437 -0.0881062 -0.919363 0.322098 -0.225885 -0.884039 0.0446524 -0.465276 -0.88142 0.0256999 -0.471633 -0.900582 -0.0190198 -0.43427 -0.920398 -0.110531 -0.375035 -0.99176 0.0779178 -0.101688 -0.922487 -0.0701869 -0.379593 -0.997609 0.067341 -0.0155541 -0.98939 -0.0701364 -0.127236 -0.924175 0.0578452 -0.377565 -0.948065 0.119852 -0.294633 -0.950095 0.269518 -0.157097 -0.949777 0.266978 -0.163237 -0.923874 0.38267 -0.00465081 -0.863309 0.488864 -0.125337 -0.780917 0.623702 0.0341265 -0.803648 0.566938 -0.18092 -0.677193 0.73576 -0.00819481 -0.596947 -0.655196 -0.463004 -0.593528 -0.660405 -0.45999 -0.735192 -0.366505 -0.570234 -0.732685 -0.375167 -0.567822 -0.129196 -0.986551 -0.100129 -0.132488 -0.98583 -0.102891 -0.112647 -0.986697 -0.117213 -0.647356 -0.359823 -0.671906 -0.644884 -0.367325 -0.670222 -0.526191 -0.65179 -0.546161 -0.523243 -0.656148 -0.543771 -0.337785 -0.873483 -0.350613 -0.0490713 -0.996649 -0.0654405 -0.0968381 -0.986186 -0.134389 -0.114731 -0.986235 -0.119069 -0.335595 -0.875082 -0.348722 -0.38318 -0.874556 -0.297196 -0.380455 -0.87653 -0.294871 -0.562261 -0.35038 -0.749064 -0.559531 -0.359715 -0.74668 -0.458242 -0.646024 -0.610465 -0.454894 -0.65164 -0.60699 -0.339362 -0.824748 -0.452354 -0.289408 -0.873299 -0.391907 -0.246364 -0.911761 -0.328628 -0.148091 -0.969072 -0.197403 -0.835811 0.110511 -0.537781 -0.441674 0.895804 -0.0495855 -0.858568 0.0606205 -0.509104 -0.865317 0.103346 -0.490455 -0.860706 0.195399 -0.470111 -0.815832 0.427923 -0.388973 -0.82532 0.406643 -0.391777 -0.676425 0.704826 -0.213706 -0.735544 0.634751 -0.236783 -0.44727 0.891873 -0.067174 -0.634152 0.768488 -0.0853105 -0.732381 0.520125 -0.439418 -0.470312 0.82769 -0.306164 -0.564047 0.774381 -0.286678 -0.156486 0.981793 -0.107681 -0.297146 0.950452 -0.0913532 -0.838145 0.137386 -0.527862 -0.732874 0.515583 -0.443926 -0.793811 0.435005 -0.425012 -0.567082 0.773887 -0.281987 -0.643028 0.716899 -0.26939 -0.293476 0.951035 -0.096974 -0.418901 0.904048 -0.0849619 0.406354 -0.241862 -0.881124 0.600954 -0.797031 -0.059962 0.640663 -0.212223 -0.73791 0.842125 -0.421952 -0.335832 0.249531 -0.550437 -0.796714 0.47125 -0.579518 -0.664893 0.532767 -0.443448 -0.720773 0.75517 -0.40432 -0.515988 0.793455 -0.229036 -0.563889 0.936468 -0.148794 -0.317629 0.722602 -0.614585 -0.316436 0.781035 -0.558141 -0.280113 0.589685 -0.627578 -0.508347 0.923152 -0.294048 -0.247642 0.936976 -0.329489 -0.116247 0.886743 -0.451677 -0.0983607 0.861271 -0.502296 -0.07688 0.811708 -0.571192 -0.121938 0.571299 -0.815194 0.0952709 -0.00795759 -0.733492 -0.679651 -0.0888491 -0.701889 -0.706724 0.157238 -0.825794 -0.541609 0.0466818 -0.805967 -0.590117 0.312857 -0.871385 -0.377901 0.177781 -0.875343 -0.449632 0.447837 -0.870883 -0.202495 0.297593 -0.907743 -0.295703 0.436095 -0.884949 -0.16336 0.145576 -0.284933 -0.947429 -0.222377 -0.21951 -0.949928 -0.225153 -0.217355 -0.94977 0.822042 -0.185152 -0.538484 0.610543 -0.245188 -0.753074 0.57348 -0.414331 -0.706719 0.609926 -0.411557 -0.677208 0.351722 -0.31145 -0.882774 0.102534 -0.292196 -0.950846 0.00966714 -0.497881 -0.867191 -0.30775 -0.309512 -0.899718 -0.277714 -0.362729 -0.889552 0.675314 -0.728519 -0.11494 0.746349 -0.661883 -0.0698176 0.575946 -0.761835 -0.296468 0.65193 -0.712235 -0.260211 0.44314 -0.759911 -0.475565 0.516308 -0.72866 -0.449979 0.281827 -0.717487 -0.637014 0.045014 -0.991006 -0.12602 0.221457 -0.97505 -0.0153354 -0.0442177 -0.963711 -0.26326 0.111321 -0.979489 -0.167956 -0.135537 -0.907231 -0.398197 -0.00767517 -0.946582 -0.322373 -0.225343 -0.821483 -0.523818 -0.128885 -0.873503 -0.469448 -0.360716 -0.645553 -0.673161 -0.208209 -0.750309 -0.627444 -0.347742 -0.618534 -0.704621 -0.221157 -0.56963 -0.791588 0.989096 -0.111529 -0.0961734 0.916986 -0.192909 -0.349175 0.879372 -0.368524 -0.301488 0.713082 -0.446752 -0.540303 0.649886 -0.586929 -0.48287 0.416796 -0.603888 -0.679412 0.3449 -0.702842 -0.622139 0.390598 -0.709393 -0.586681 0.162931 -0.572464 -0.803579 -0.0453949 -0.485802 -0.872889 -0.169833 -0.60112 -0.780904 -0.409591 -0.33235 -0.849576 -0.405982 -0.517541 -0.753213 -0.45272 -0.350298 -0.819961 -0.134255 0.981907 -0.133548 -0.557619 0.14707 -0.816965 -0.557522 0.1544 -0.815677 -0.479464 0.525943 -0.702494 -0.478275 0.530542 -0.699841 -0.315036 0.829275 -0.461579 -0.313847 0.830974 -0.459328 -0.106668 0.981932 -0.156304 -0.106228 0.982104 -0.155523 -0.659278 0.142138 -0.738342 -0.659122 0.147165 -0.737496 -0.567636 0.523164 -0.635679 -0.566677 0.526101 -0.63411 -0.373112 0.828374 -0.417832 -0.372255 0.82937 -0.416619 -0.125818 0.981994 -0.140914 -0.12597 0.981946 -0.141118 -0.7676 0.136948 -0.626127 -0.767216 0.141693 -0.625542 -0.662241 0.519258 -0.540193 -0.66106 0.52196 -0.539034 -0.435951 0.826729 -0.35562 -0.435061 0.827547 -0.354805 -0.147734 0.981656 -0.120526 -0.147434 0.981734 -0.12026 0.99369 -0.0140761 -0.111274 0.996885 -0.00658326 -0.0785941 0.941196 -0.0466508 -0.334624 0.973571 -0.0236863 -0.227153 0.826229 -0.0589796 -0.560239 0.829099 -0.0582301 -0.556061 0.643579 -0.0801755 -0.761169 0.649663 -0.0791322 -0.756093 0.40846 -0.0956711 -0.907749 0.418508 -0.0944861 -0.903285 0.146927 -0.103734 -0.983693 0.16058 -0.102645 -0.981671 -0.222837 -0.102679 -0.969433 -0.206182 -0.101204 -0.973266 0.251522 0.947669 -0.19662 0.518652 0.852576 -0.0641416 0.509095 0.805193 -0.304116 0.305167 0.831427 -0.46433 0.301902 0.802381 -0.514819 0.164727 0.747967 -0.64297 -0.356631 0.197827 -0.91306 -0.283405 -0.155291 -0.946344 -0.476275 0.154725 -0.865576 0.0880694 0.808036 -0.582514 0.48688 0.839428 -0.241472 0.367947 0.911988 -0.181365 0.148231 0.887137 -0.437054 0.123761 0.733451 -0.668381 0.158432 0.711933 -0.684142 -0.02354 0.520473 -0.853554 -0.11602 0.525129 -0.843077 -0.162964 0.550726 -0.818623 -0.214978 0.542389 -0.812157 -0.299453 0.570385 -0.764846 -0.0317155 0.852904 -0.521103 -0.125419 0.84385 -0.521715 0.205675 0.963447 -0.171661 0.082057 0.979513 -0.183907 -0.364086 0.215495 -0.906092 -0.394019 0.18842 -0.899581 -0.472104 0.146179 -0.869339 -0.306682 0.584803 -0.750967 -0.407596 0.531339 -0.742661 -0.181624 0.85262 -0.48995 -0.259623 0.83137 -0.491345 0.0359237 0.986763 -0.15814 -0.0811437 0.982066 -0.170183 0.958204 0.161276 -0.236295 0.610269 0.784848 -0.107638 0.877026 0.428863 -0.216568 0.869771 0.346887 -0.350953 0.757419 0.347339 -0.552876 0.751554 0.332083 -0.569989 0.584239 0.30824 -0.750768 0.57651 0.294161 -0.762303 0.364805 0.245424 -0.898156 0.356854 0.234127 -0.904345 0.121617 0.165791 -0.978633 0.114952 0.157877 -0.980745 -0.205889 0.00322716 -0.97857 0.737911 0.641946 -0.208309 0.705134 0.705102 -0.0749437 0.594914 0.753065 -0.281015 0.5891 0.731979 -0.342297 0.474128 0.730437 -0.491594 0.46469 0.701235 -0.540678 0.317622 0.659257 -0.68154 0.307881 0.631897 -0.711277 0.138722 0.539555 -0.830443 0.0966719 0.418972 -0.902838 -0.0494707 0.387353 -0.920603 -0.286949 0.141879 -0.947381 0.972737 0.0276983 -0.230251 0.97174 0.103128 -0.212336 0.822283 0.0941968 -0.561229 0.818515 0.0872385 -0.567822 0.645208 0.0722982 -0.760579 0.640906 0.0666309 -0.764722 0.416572 0.0447597 -0.908 0.412682 0.0408624 -0.909958 0.160221 0.0144365 -0.986976 0.15749 0.0122591 -0.987445 -0.115649 -0.0175294 -0.993135 -0.231088 0.0388315 -0.972158 -0.261365 0.124899 -0.957125 0.925844 0.356127 -0.126442 0.838538 0.536979 -0.0922386 0.755343 0.579188 -0.306591 0.751903 0.558189 -0.350808 0.637792 0.562871 -0.525735 0.629682 0.537553 -0.560837 0.471617 0.507156 -0.721367 0.460738 0.481866 -0.745336 0.268459 0.413935 -0.869821 0.257258 0.392366 -0.883101 0.0486111 0.293024 -0.954869 0.0393011 0.277135 -0.960027 -0.185445 0.146522 -0.971669 -0.586471 0.099375 -0.803851 0.210892 -0.977079 -0.0290014 0.417258 -0.126985 -0.899873 0.163457 -0.167527 -0.972223 0.622526 -0.777794 -0.0865904 0.0507705 -0.770075 -0.63593 0.38241 -0.629813 -0.67609 0.64395 -0.133848 -0.753269 0.330971 -0.641989 -0.691598 0.544996 -0.679313 -0.491439 0.634015 -0.554468 -0.539063 0.820974 -0.513823 -0.248973 0.809504 -0.553552 -0.19566 0.466859 -0.511569 -0.721346 0.675725 -0.52668 -0.515755 0.747648 -0.363438 -0.55582 0.916969 -0.319043 -0.239538 0.912589 -0.351491 -0.208891 0.407073 -0.90306 -0.137016 0.570844 -0.821044 -0.00497207 0.330539 -0.886422 -0.324036 0.451997 -0.860287 -0.235806 0.215052 -0.840913 -0.496606 -0.383247 -0.233959 -0.893524 -0.303117 -0.20204 -0.93129 0.0038886 -0.371223 -0.928536 0.820697 -0.132946 -0.555682 0.637988 -0.139641 -0.757279 0.599253 -0.323528 -0.732274 0.606158 -0.324013 -0.726352 0.392644 -0.204581 -0.896648 0.146944 -0.169863 -0.974451 0.0530465 -0.38211 -0.922593 -0.192207 -0.0569625 -0.9797 0.709998 -0.695122 -0.112731 0.649456 -0.743729 -0.158349 0.636861 -0.694675 -0.334418 0.487847 -0.703601 -0.516673 0.327975 -0.841737 -0.428849 0.159429 -0.789297 -0.592953 0.0062216 -0.600059 -0.799931 -0.0647957 -0.54912 -0.833228 -0.15504 -0.603876 -0.781854 -0.146722 -0.56588 -0.811328 -0.0284638 -0.995836 -0.0866105 0.211327 -0.977019 -0.027836 -0.0294771 -0.956993 -0.288609 0.103888 -0.974452 -0.199124 -0.120327 -0.888861 -0.442095 -0.00906779 -0.927746 -0.373103 -0.211766 -0.784347 -0.583057 -0.127608 -0.83532 -0.53475 -0.344387 -0.572909 -0.743756 -0.286284 -0.61842 -0.731845 -0.45508 -0.225414 -0.861447 -0.399927 -0.302545 -0.865173 -0.219138 -0.0917078 -0.971374 -0.180394 -0.139792 -0.97361 -0.28412 -0.17299 -0.943054 -0.249745 -0.320509 -0.913729 -0.100208 -0.470176 -0.876865 0.164205 -0.528064 -0.833178 0.216606 -0.472694 -0.854191 0.409992 -0.637493 -0.652311 0.292243 -0.442653 -0.847734 0.506557 -0.493818 -0.706784 0.57414 -0.340919 -0.744404 0.772163 -0.339644 -0.537034 0.813422 -0.142823 -0.563867 0.963539 -0.114416 -0.241869 0.964914 -0.13623 -0.224459 -0.19223 -0.041806 -0.980459 -0.174083 -0.0429774 -0.983793 -0.180485 -0.0442479 -0.982582 0.0552171 -0.044049 -0.997502 0.164774 -0.0428919 -0.985398 0.183949 -0.0437598 -0.981961 0.429766 -0.039449 -0.902078 0.418909 -0.0404208 -0.907128 0.653887 -0.0330955 -0.755868 0.64731 -0.0338783 -0.761473 0.828762 -0.0245063 -0.559064 0.82564 -0.0250368 -0.563642 0.942131 -0.0146928 -0.334922 0.972725 -0.00421841 -0.231925 0.993958 -0.00484727 -0.109657 -0.57192 -0.23442 -0.786101 -0.0504859 -0.995989 -0.0738777 -0.0981406 -0.98386 -0.149629 -0.513659 -0.225476 -0.827838 -0.56365 -0.00824865 -0.825972 -0.46255 -0.573421 -0.676193 -0.459857 -0.579 -0.673269 -0.347325 -0.788206 -0.508033 -0.295138 -0.848494 -0.439262 -0.252146 -0.894554 -0.369047 -0.150762 -0.963659 -0.220529 -0.65313 -0.234148 -0.720136 -0.651881 -0.239739 -0.719428 -0.547647 -0.579191 -0.603838 -0.545762 -0.582582 -0.60228 -0.355247 -0.848744 -0.391706 -0.353725 -0.850014 -0.390327 -0.119982 -0.983923 -0.132289 -0.104712 -0.987497 -0.117832 -0.730367 -0.239837 -0.639564 -0.729575 -0.24313 -0.639224 -0.611376 -0.582754 -0.535366 -0.610135 -0.584791 -0.53456 -0.396167 -0.850116 -0.34692 -0.395129 -0.850902 -0.346178 -0.153865 -0.978861 -0.134749 -0.132419 -0.984139 -0.118049 -0.143696 -0.98421 -0.103353 -0.143918 -0.984164 -0.103488 -0.425728 -0.851456 -0.306233 -0.426413 -0.85097 -0.30663 -0.657663 -0.586233 -0.473085 -0.658531 -0.584891 -0.473539 -0.786966 -0.245364 -0.566111 -0.787521 -0.243156 -0.566292 0.655199 0.748856 -0.0996448 -0.17591 0.82566 -0.536043 0.0164701 0.844187 -0.535796 -0.0745263 0.836567 -0.542772 -0.200771 0.855491 -0.477311 0.154881 0.78674 -0.597539 0.189645 0.707497 -0.680796 0.212442 0.865855 -0.45295 0.415587 0.890765 -0.183917 0.311172 0.927479 -0.207255 0.238825 0.955387 -0.173774 0.121675 0.973164 -0.195311 0.0511557 0.985717 -0.160455 -0.0632133 0.981574 -0.180324 0.650407 0.0693212 -0.756416 0.445688 0.224734 -0.86652 0.274801 0.183403 -0.943847 0.223478 0.300758 -0.927147 0.762889 0.635819 -0.117199 0.388861 0.56904 -0.724556 0.367287 0.494799 -0.787575 0.604369 0.56354 -0.56317 0.628706 0.590258 -0.506284 0.719518 0.592274 -0.362637 0.736585 0.610015 -0.292103 0.833066 0.553166 -0.0030512 -0.137031 0.0206762 -0.990351 0.0146522 0.325099 -0.945566 -0.113786 0.444454 -0.888546 -0.134368 0.400888 -0.90622 -0.312484 0.470561 -0.825183 0.970101 0.234115 -0.0639904 0.914286 0.389538 -0.111092 0.879906 0.464455 -0.10023 0.241217 0.671555 -0.700591 0.246988 0.70275 -0.667188 0.383765 0.758184 -0.527145 0.387535 0.786534 -0.480813 0.554278 0.795784 -0.243936 0.576166 0.757677 -0.306527 0.569403 0.820614 0.0487125 0.591544 0.802804 -0.0747018 -0.174049 -0.0240787 -0.984443 0.0551522 0.00484733 -0.998466 0.183592 0.0183062 -0.982832 -0.425112 0.1444 -0.893548 -0.440021 0.122188 -0.889636 -0.266591 0.232038 -0.935461 -0.356194 0.141174 -0.923686 -0.242258 0.125185 -0.962102 -0.205298 0.133984 -0.969485 -0.213525 0.0799152 -0.973664 -0.179708 0.0359214 -0.983064 0.2867 0.173869 -0.942111 0.331743 -0.0577491 -0.9416 0.428355 0.0407099 -0.902693 -0.28013 0.6888 -0.668642 -0.372249 0.522699 -0.766953 -0.213218 0.606026 -0.766336 -0.164273 0.63849 -0.751894 -0.0718509 0.602657 -0.794759 0.106008 0.650805 -0.751808 0.0884501 0.572777 -0.814925 0.110211 0.553675 -0.825408 0.115001 0.429137 -0.895888 0.197378 0.31414 -0.928632 0.530745 0.433845 -0.728071 0.635661 0.168131 -0.753437 0.803755 0.191575 -0.563273 0.808294 0.196279 -0.5551 0.914221 0.204665 -0.349732 0.917925 0.210416 -0.336362 0.979922 0.199288 -0.00609818 0.992363 0.0516715 -0.112007 -0.636131 -0.765205 -0.0989885 -0.854417 -0.189109 -0.483952 -0.828503 -0.550712 -0.101487 -0.954171 -0.233323 -0.187399 -0.8243 -0.245476 -0.510168 -0.992606 -0.103432 -0.0635287 -0.978402 -0.206386 -0.0115701 -0.323896 -0.599471 0.731933 -0.894558 -0.445078 0.0408835 -0.875311 -0.481015 -0.0495407 -0.3178 -0.947354 -0.0390279 -0.381753 -0.914896 -0.13126 -0.43703 -0.898293 -0.0455383 -0.75484 -0.60795 -0.246197 -0.804474 -0.570529 -0.165283 -0.892878 -0.2099 -0.398385 -0.911546 -0.204052 -0.356997 -0.68848 -0.725122 -0.0139073 -0.874061 -0.425494 -0.234461 -0.949046 -0.296225 -0.107525 -0.909365 -0.116304 -0.399412 -0.920604 -0.112195 -0.374032 -0.850192 -0.147389 -0.505421 -0.641342 -0.710957 -0.28848 -0.711599 -0.585285 -0.388675 -0.875375 -0.174247 -0.450952 -0.84331 -0.400776 -0.358059 -0.83043 -0.409541 -0.377708 -0.645858 -0.73451 -0.208237 -0.577282 -0.75417 -0.313006 -0.425647 -0.891886 -0.152856 -0.470516 -0.850084 -0.236585 -0.251537 -0.957497 -0.141169 -0.182937 -0.982184 -0.0430049 -0.386995 0.688761 -0.61306 -0.526368 0.756096 -0.388916 -0.142214 0.981366 -0.129212 -0.0766797 0.995445 -0.0566569 -0.142428 0.981305 -0.12944 -0.12448 0.981576 -0.144957 -0.124525 0.981562 -0.145018 -0.105517 0.981597 -0.159168 -0.0845704 0.987334 -0.134237 -0.0917789 0.981947 -0.165396 -0.798483 0.119616 -0.590015 -0.692079 0.509419 -0.511388 -0.156964 0.981337 -0.111083 -0.229122 0.958563 -0.169294 -0.383534 0.87898 -0.283365 -0.798421 0.120932 -0.58983 -0.768867 0.121063 -0.627843 -0.736404 0.103265 -0.668615 -0.733368 0.124347 -0.668363 -0.64646 0.124282 -0.752757 -0.646299 0.132192 -0.751547 -0.528683 0.132072 -0.838482 -0.528629 0.144062 -0.836539 -0.691763 0.510185 -0.511053 -0.636641 0.510045 -0.578396 -0.63587 0.512137 -0.577396 -0.559688 0.511952 -0.651655 -0.558257 0.516568 -0.649235 -0.456727 0.516348 -0.72442 -0.455469 0.521694 -0.721376 -0.4591 0.823599 -0.333035 -0.419769 0.823621 -0.381369 -0.419022 0.824392 -0.380524 -0.368919 0.824262 -0.429524 -0.367667 0.825771 -0.427695 -0.300903 0.825632 -0.477273 -0.299052 0.828477 -0.473492 -0.879448 -0.031035 -0.474983 -0.931056 -0.0596435 -0.359968 -0.988023 -0.0870953 -0.127378 -0.923359 -0.0851171 -0.374384 -0.971833 -0.0961278 -0.215176 -0.977242 -0.0934022 -0.19046 -0.994263 -0.0859675 -0.0636524 -0.876244 -0.080986 -0.475013 -0.930586 -0.0666152 -0.359961 -0.959507 0.251298 -0.127262 -0.990075 0.0707046 -0.121457 -0.392781 0.918227 -0.0508166 -0.438976 0.898104 0.0266469 -0.641157 0.759995 -0.106421 -0.70109 0.713068 -0.00263066 -0.666189 0.730273 -0.151304 -0.599592 0.756128 -0.262221 -0.269227 0.956906 -0.108844 -0.577805 0.754798 -0.310518 -0.84448 0.11963 -0.522056 -0.742795 0.509036 -0.434899 -0.799305 0.411163 -0.438242 -0.839727 0.396265 -0.371258 -0.872958 0.293063 -0.389947 -0.918036 0.25298 -0.305306 -0.840658 0.302971 -0.448891 -0.871326 0.0469188 -0.488457 -0.894438 0.0279954 -0.446316 -0.905382 0.116023 -0.40844 -0.929468 0.0114039 -0.368726 -0.929856 0.0131258 -0.367689 -0.923794 -0.0605901 -0.378065 -0.997497 0.0463766 -0.0533845 -0.990545 -0.0507419 -0.127459 -0.112333 0.993664 -0.00352345 -0.137789 0.990234 -0.0212283 -0.49054 0.853873 -0.173986 -0.558649 0.827155 -0.0610453 -0.711075 0.679495 -0.18072 -0.767051 0.635964 -0.0847482 -0.769688 0.631873 -0.0911902 -0.835286 0.54656 -0.0597544 -0.872497 0.488067 0.0232403 -0.944849 0.18859 -0.267757 -0.953091 0.24005 -0.184375 -0.936613 0.273853 -0.218543 -0.837851 0.531914 -0.122771 -0.856612 0.483313 -0.180621 -0.791871 0.535652 -0.293286 -0.756905 0.608699 -0.237867 -0.691562 0.633617 -0.346801 -0.430907 0.877292 -0.211372 0.0691837 -0.258199 -0.963611 0.258205 -0.0691843 -0.96361 0.258188 -0.0691872 -0.963614 0.694756 -0.186176 -0.694732 0.694734 -0.186185 -0.694751 0.935087 -0.250598 -0.250626 0.935109 -0.250568 -0.250574 0.189009 -0.189012 -0.963613 0.189017 -0.189015 -0.963611 0.508593 -0.508589 -0.694745 0.50858 -0.508587 -0.694755 0.684544 -0.684553 -0.250572 0.684577 -0.684539 -0.250521 0.0691828 -0.258198 -0.963612 0.160988 -0.600825 -0.783002 0.152649 -0.708028 -0.689489 0.207937 -0.776024 -0.595441 0.250567 -0.935116 -0.250548 0.250553 -0.935115 -0.250567 0.965908 0 -0.258887 0.965908 0 -0.258887 0.707119 0 -0.707095 0.707119 0 -0.707095 0.258826 0 -0.965924 0.258826 0 -0.965924 0 -0.965925 -0.258822 -0.0507216 -0.979523 -0.194841 0.038243 -0.792784 -0.608301 0 -0.831471 -0.555568 0 -0.608765 -0.79335 0.025604 -0.555392 -0.831195 -0.0382528 -0.258629 -0.965219 0 -0.195089 -0.980785 0.18868 0.948576 -0.254171 0.139281 0.700223 -0.700206 0.0514143 0.258475 -0.964649 0.0514136 0.258477 -0.964648 0.146415 0.219128 -0.964648 0.146415 0.219124 -0.964649 0.219121 0.146418 -0.964649 0.219123 0.146423 -0.964648 0.258479 0.051411 -0.964648 0.258483 0.0514153 -0.964647 0.139281 0.700224 -0.700205 0.396646 0.593621 -0.700205 0.396648 0.593609 -0.700213 0.593598 0.396656 -0.700219 0.593604 0.396688 -0.700195 0.70023 0.139284 -0.700199 0.700227 0.139279 -0.700203 0.188677 0.948578 -0.254167 0.537337 0.804159 -0.254161 0.537337 0.804158 -0.254162 0.804132 0.537378 -0.254157 0.804137 0.537363 -0.254175 0.948575 0.188677 -0.254177 0.94857 0.18862 -0.25424 -0.00310887 -0.982964 -0.183771 -0.00387649 -0.980778 -0.19509 -0.00856413 -0.839347 -0.543529 -0.00952139 -0.831433 -0.555543 -0.0138799 -0.552879 -0.833146 -0.0136761 -0.555522 -0.831389 -0.0168414 -0.190191 -0.981603 -0.0165617 -0.195063 -0.980651 -0.0234895 -0.98316 -0.18123 -0.0237276 -0.982911 -0.182545 -0.069319 -0.841455 -0.535863 -0.0701082 -0.838817 -0.539881 -0.106198 -0.55967 -0.821883 -0.107349 -0.552054 -0.826869 -0.125392 -0.202856 -0.971147 -0.126391 -0.189786 -0.973656 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.793362 -0.60875 -0.0510492 0.706194 -0.706176 0 0.608768 -0.793348 0 0.258817 -0.965926 0 0.258817 -0.965926 -0.625839 -0.295737 -0.72171 -0.640466 -0.746813 -0.179091 -0.301992 -0.556745 -0.773845 -0.431081 -0.0612968 -0.900229 -0.152767 -0.976628 -0.151193 -0.795544 -0.589878 -0.138398 -0.822925 -0.563746 -0.0705964 -0.896863 -0.406491 -0.174362 -0.318014 -0.237339 -0.917898 -0.287572 -0.534166 -0.794965 -0.263895 -0.203382 -0.942865 -0.228461 -0.142044 -0.963135 -0.96727 -0.226328 -0.114737 -0.977726 -0.198889 -0.0670479 -0.986203 -0.0617028 -0.153613 -0.392103 -0.91005 -0.134405 -0.333762 -0.894976 -0.29601 -0.544032 -0.834977 -0.0827215 -0.575317 -0.649328 -0.497377 -0.780014 -0.442508 -0.442454 -0.76337 -0.44264 -0.470464 -0.882373 -0.160386 -0.442374 -0.39572 -0.118758 -0.91066 -0.367879 -0.0636981 -0.927689 -0.869325 -0.328169 -0.369566 -0.690253 -0.113037 -0.714684 -0.87858 -0.162785 -0.448998 -0.119826 -0.972418 -0.200111 -0.219343 -0.83778 -0.500013 -0.342593 -0.877733 -0.334984 -0.271653 -0.801856 -0.532196 -0.558999 -0.68719 -0.463995 -0.492918 -0.449992 -0.744674 -0.479379 -0.440209 -0.759218 -0.331406 -0.145142 -0.932258 -0.363109 -0.151108 -0.919412 -0.108867 0.175783 -0.978391 -0.109173 0.185682 -0.976526 -0.0930235 0.540918 -0.835915 -0.0929818 0.54742 -0.831676 -0.0704706 0.771706 -0.632063 -0.0639123 0.834893 -0.546689 -0.0515794 0.885609 -0.461559 -0.0309473 0.960255 -0.277405 -0.0232828 0.982153 -0.186638 -0.0102507 0.995731 -0.0917354 -0.00377636 0.965919 -0.258818 -0.00788861 0.98226 -0.18736 -0.0048344 0.793353 -0.608743 -0.00797831 0.835406 -0.549576 -0.0115586 0.608728 -0.793295 -0.00954095 0.548019 -0.836411 -0.0178166 0.258776 -0.965773 -0.0142467 0.185984 -0.98245 -0.987621 -0.00360691 -0.156821 -0.98786 -0.00367887 -0.155304 -0.886651 -0.0105206 -0.462319 -0.888863 -0.0107787 -0.458047 -0.687309 -0.0164506 -0.726179 -0.693415 -0.016949 -0.720339 -0.420826 -0.0204898 -0.90691 -0.43141 -0.0212166 -0.901906 -0.359694 0.0204562 -0.932846 -0.964663 0.194745 -0.17748 -0.969382 0.187985 -0.15799 -0.884314 0.138756 -0.445799 -0.876208 0.143296 -0.460136 -0.684208 0.0795214 -0.724938 -0.541784 0.663347 -0.516179 -0.579789 0.716211 -0.388441 -0.57408 0.770449 -0.2772 -0.581906 0.784264 -0.21521 -0.425506 0.894588 0.136588 -0.564672 0.816958 -0.117153 -0.263698 0.962278 -0.0669677 -0.380407 0.154914 -0.911752 -0.316096 0.11734 -0.941443 -0.470364 0.41861 -0.776868 -0.485566 0.42916 -0.761608 -0.547647 0.624797 -0.556517 -0.0965962 0.992534 -0.0744684 -0.153727 0.986367 0.0587139 -0.243367 0.942193 -0.230314 -0.240159 0.924967 -0.294552 -0.267746 0.871257 -0.411367 -0.261272 0.847349 -0.462316 -0.281816 0.762313 -0.582631 -0.273847 0.736187 -0.6189 -0.286488 0.537768 -0.792925 -0.272462 0.517201 -0.811337 -0.242375 0.176129 -0.954061 -0.255161 0.197856 -0.946438 -0.670725 0.736042 -0.091491 -0.821172 0.568467 -0.0502116 -0.798435 0.56032 -0.220326 -0.826153 0.54638 -0.137626 -0.78331 0.426641 -0.45211 -0.763762 0.426333 -0.484673 -0.622034 0.26823 -0.735613 -0.86077 0.305233 -0.407319 -0.375746 0.0342879 -0.926088 -0.420805 -0.00920281 -0.907104 -0.883219 -0.153009 -0.443298 -0.993445 -0.0959837 -0.0620863 -0.958224 -0.220275 -0.182446 -0.8623 -0.168366 -0.477589 -0.856524 -0.12437 -0.500898 -0.83223 -0.231918 -0.503594 -0.926456 -0.078483 -0.368129 -0.914581 -0.0832173 -0.395747 -0.920142 -0.172714 -0.351439 -0.900635 -0.184055 -0.393675 -0.857204 -0.380092 -0.347464 -0.840037 -0.392254 -0.374801 -0.643553 -0.711847 -0.281271 -0.431569 -0.888896 -0.153662 -0.184171 -0.981934 -0.0434243 -0.90348 -0.428193 -0.0193422 -0.850809 -0.514742 -0.105666 -0.694875 -0.7191 -0.00661347 -0.655927 -0.747927 -0.101812 -0.441898 -0.895992 -0.0438575 -0.419479 -0.904197 -0.0804114 -0.288211 -0.953777 -0.0851111 -0.252084 -0.957395 -0.140884 -0.475811 -0.847123 -0.236617 -0.674222 -0.535631 0.508452 -0.511107 -0.587101 0.62776 -0.960966 -0.260194 -0.0940349 -0.886059 -0.400756 -0.233009 -0.815823 -0.555459 -0.16093 -0.766146 -0.594127 -0.245018 -0.653522 -0.72848 -0.205489 -0.585072 -0.748359 -0.312491 -0.71937 -0.577027 -0.386712 -0.0456592 -0.99595 -0.0774474 -0.0885766 -0.98371 -0.156427 -0.111085 -0.983858 -0.140298 -0.130527 -0.987214 -0.091491 -0.145449 -0.983899 -0.103866 -0.430435 -0.848696 -0.307314 -0.430771 -0.848419 -0.307605 -0.663749 -0.578691 -0.473872 -0.664148 -0.577924 -0.474248 -0.79147 -0.233042 -0.565038 -0.791658 -0.23179 -0.565289 -0.14098 -0.983958 -0.109325 -0.133363 -0.983904 -0.118942 -0.394866 -0.848562 -0.352169 -0.394995 -0.848463 -0.352264 -0.608773 -0.578475 -0.542919 -0.608868 -0.578315 -0.542984 -0.725803 -0.232919 -0.64727 -0.634753 -0.0305833 -0.772109 -0.673101 -0.233244 -0.701807 -0.725829 -0.232806 -0.647282 -0.417586 -0.570005 -0.707614 -0.415306 -0.575228 -0.704722 -0.313903 -0.786295 -0.532171 -0.266598 -0.847072 -0.459776 -0.227944 -0.893598 -0.386684 -0.136324 -0.963325 -0.231129 -0.216065 -0.954836 -0.203972 -0.0910707 -0.990031 -0.107451 -0.342254 -0.848278 -0.404087 -0.343241 -0.847417 -0.405057 -0.527399 -0.578016 -0.622694 -0.52874 -0.575481 -0.623903 -0.629258 -0.228244 -0.742926 -0.494261 -0.228192 -0.838829 -0.495756 -0.219904 -0.84016 -0.997044 -0.044403 -0.0627074 -0.928568 -0.0427484 -0.368691 -0.929338 -0.0428762 -0.366731 -0.98138 -0.0431269 -0.187173 -0.981596 -0.0431562 -0.18603 -0.99871 -0.0421981 -0.0282519 -0.997235 -0.0406169 -0.0622313 0.219827 -0.974693 -0.0406267 0.46746 -0.109338 -0.877227 0.231687 -0.145388 -0.961865 0.624233 -0.777067 -0.0806223 0.113447 -0.753002 -0.648164 0.431025 -0.597406 -0.676257 0.675293 -0.114542 -0.728601 0.391195 -0.60682 -0.691908 0.577752 -0.651685 -0.491436 0.670287 -0.519127 -0.530305 0.834197 -0.497747 -0.237409 0.819744 -0.542188 -0.184529 0.517321 -0.473964 -0.712557 0.701136 -0.498842 -0.509475 0.772512 -0.333467 -0.540393 0.91895 -0.310031 -0.243743 0.91479 -0.348051 -0.204989 0.426052 -0.895063 -0.131691 0.577533 -0.816315 0.00925911 0.375277 -0.867738 -0.325881 0.468917 -0.848702 -0.244585 0.273428 -0.819982 -0.502858 -0.304081 -0.21817 -0.927328 -0.21318 -0.199506 -0.956426 0.0835992 -0.343689 -0.935355 0.836067 -0.117825 -0.535826 0.667535 -0.121945 -0.734525 0.631491 -0.296035 -0.716647 0.652325 -0.298254 -0.69679 0.443703 -0.180112 -0.877888 0.212037 -0.148257 -0.96595 0.123627 -0.352363 -0.927662 -0.112844 -0.0410644 -0.992764 0.717045 -0.686618 -0.120012 0.66448 -0.728433 -0.166887 0.664443 -0.671786 -0.327443 0.534067 -0.67021 -0.515355 0.361847 -0.82211 -0.439547 0.212703 -0.763828 -0.609364 0.0855568 -0.576337 -0.812721 0.0162982 -0.524358 -0.851342 -0.0795728 -0.584075 -0.80779 -0.0701389 -0.550239 -0.832056 -0.00940716 -0.995482 -0.0944817 0.227258 -0.973822 -0.00492799 0.00904621 -0.954818 -0.297053 0.116163 -0.97048 -0.211365 -0.0699609 -0.886564 -0.457286 0.0201586 -0.920197 -0.390937 -0.151279 -0.781784 -0.604921 -0.082387 -0.825707 -0.558051 -0.271927 -0.569594 -0.775641 -0.222102 -0.60847 -0.761863 -0.377531 -0.220618 -0.899332 -0.330854 -0.284289 -0.899842 -0.136534 -0.0791605 -0.987467 -0.100302 -0.117998 -0.987935 -0.201413 -0.155991 -0.967005 -0.160158 -0.310282 -0.937056 -0.0227439 -0.447019 -0.894235 0.230922 -0.50038 -0.834443 0.285029 -0.442046 -0.850502 0.461919 -0.607762 -0.645954 0.350579 -0.406197 -0.84386 0.547264 -0.460821 -0.698675 0.613237 -0.308307 -0.727246 0.790161 -0.316729 -0.524717 0.829324 -0.126805 -0.544189 0.967148 -0.107137 -0.230533 0.968183 -0.124364 -0.217152 -0.885648 0.454527 -0.0950432 -0.298787 0.947632 0.112787 -0.997809 0.0209706 -0.0627525 -0.954845 0.257709 -0.14784 -0.921949 0.386603 -0.0234198 -0.93676 0.347008 -0.0454561 -0.984808 0.156375 -0.0754952 -0.580371 0.763977 -0.281975 -0.28131 0.956076 -0.0823589 -0.571102 0.772621 -0.277305 -0.776793 0.562367 -0.283436 -0.865217 0.328914 -0.378438 -0.829748 0.426035 -0.360573 -0.874683 0.0892427 -0.47641 -0.838812 0.320063 -0.440403 -0.930167 -0.0127371 -0.366915 -0.977198 0.171821 0.124748 -0.981306 0.04846 -0.186253 -0.10512 0.550417 0.828246 -0.917618 -0.0028898 -0.397454 -0.930313 0.0576899 -0.3622 -0.10502 0.994429 -0.00907692 -0.398423 0.912941 -0.0883021 -0.39426 0.918931 -0.0111936 -0.847401 0.155819 -0.507575 -0.737715 0.528999 -0.419448 -0.792257 0.43928 -0.423511 -0.668104 0.654987 -0.35303 -0.741642 0.629635 -0.23136 -0.649818 0.745666 -0.147373 -0.69192 0.700732 -0.173843 -0.437987 0.879972 -0.183894 -0.461176 0.865722 -0.194532 -0.542544 0.837862 -0.0602704 -0.792172 0.574494 -0.205962 -0.735598 0.669864 -0.100884 -0.700311 0.713729 0.0124864 -0.854935 0.498653 -0.142938 -0.895338 0.362358 -0.258973 -0.908038 0.2931 -0.299265 -0.903086 0.164032 -0.396898 -0.896636 0.0715794 -0.436944 -0.100771 -0.0265649 -0.994555 -0.112852 -0.0277581 -0.993224 0.233291 -0.0263498 -0.97205 0.364092 -0.0324446 -0.930798 0.4691 -0.0243843 -0.882809 0.682372 -0.0198233 -0.730737 0.67824 -0.0202552 -0.734561 0.842532 -0.0146147 -0.538447 0.840455 -0.0149176 -0.541675 0.946237 -0.00878734 -0.323356 0.974971 -0.000544511 -0.222333 0.994323 -0.00291433 -0.106367 -0.80213 0.155746 -0.576481 -0.80227 0.154046 -0.576743 -0.68899 0.529235 -0.495179 -0.689467 0.528174 -0.495649 -0.521937 0.766055 -0.375156 -0.45797 0.82785 -0.323925 -0.381268 0.882902 -0.274078 -0.229044 0.959393 -0.164635 -0.157871 0.981419 -0.109058 -0.0757077 0.995644 -0.0544235 -0.142134 0.981421 -0.128884 -0.142064 0.981441 -0.12881 -0.415798 0.827626 -0.377024 -0.415608 0.827817 -0.376815 -0.629331 0.527575 -0.57062 -0.629179 0.527961 -0.570431 -0.732046 0.153509 -0.663734 -0.732017 0.153965 -0.663661 -0.121871 0.981394 -0.148372 -0.121888 0.981388 -0.148397 -0.356265 0.82769 -0.433595 -0.356513 0.827389 -0.433965 -0.538953 0.528634 -0.655802 -0.539402 0.527227 -0.656565 -0.62714 0.15636 -0.763051 -0.627259 0.153379 -0.763558 -0.0931539 0.98156 -0.166922 -0.0935669 0.981368 -0.167815 -0.272442 0.829173 -0.488106 -0.273436 0.827497 -0.49039 -0.41258 0.532443 -0.739109 -0.413489 0.528316 -0.741559 -0.480975 0.162657 -0.861514 -0.481051 0.15617 -0.862671 0.587188 0.806149 -0.0730366 0.276061 0.297876 -0.913816 0.324216 0.186093 -0.927498 0.336354 0.918554 -0.207666 -0.0419797 0.981036 -0.189225 0.224061 0.794491 -0.56443 0.431477 0.555824 -0.710554 0.410057 0.478174 -0.776661 0.923854 0.208157 -0.321192 0.915376 0.388077 -0.107157 0.861177 0.499786 -0.0926773 0.838039 0.545152 0.0223599 0.735961 0.667504 -0.113141 0.66405 0.741218 -0.0981526 0.363364 0.701758 -0.612782 0.398226 0.591202 -0.701353 0.421181 0.770185 -0.47898 0.632952 0.54951 -0.545354 0.652042 0.572641 -0.496914 0.817262 0.190389 -0.543907 0.823723 0.196735 -0.531767 -0.067059 0.038437 -0.997008 -0.100741 -0.000775072 -0.994912 0.363241 0.0453847 -0.930589 0.0797297 0.324966 -0.942359 -0.0462248 0.443723 -0.894971 -0.375264 0.163342 -0.912412 0.0639019 0.984305 -0.164502 -0.189141 0.829792 -0.525044 -0.112533 0.850534 -0.51374 -0.309207 0.533943 -0.786954 -0.194957 0.594221 -0.780316 -0.361767 0.145079 -0.920911 -0.267491 0.216663 -0.938885 0.96017 0.268356 -0.0778348 0.980621 0.194525 0.0233016 0.990431 0.0856749 -0.108193 0.919883 0.202203 -0.336049 0.750099 0.595335 -0.28797 0.737503 0.578797 -0.34797 0.59246 0.74714 -0.301285 0.568586 0.787083 -0.239188 0.427126 0.885558 -0.182621 0.150136 0.803281 -0.576366 0.362293 0.0464743 -0.930905 0.335239 0.177413 -0.925278 -0.107941 0.0506945 -0.992864 -0.145662 0.0903761 -0.985198 -0.139872 0.14899 -0.978896 -0.161936 0.142918 -0.976397 -0.263203 0.146374 -0.953571 -0.0640486 0.405522 -0.911838 -0.111007 0.425804 -0.89798 0.679338 0.0757624 -0.729904 0.576276 0.159833 -0.801473 0.63362 0.256015 -0.730056 0.562449 0.422984 -0.710447 0.253521 0.309334 -0.916537 0.175404 0.420182 -0.890326 0.170841 0.542188 -0.822706 0.147249 0.563267 -0.813049 0.163784 0.645834 -0.745703 -0.00620772 0.60038 -0.799691 -0.123387 0.645866 -0.753414 0.0558526 0.839993 -0.539715 -0.0225293 0.834122 -0.551119 0.248962 0.952753 -0.174011 0.148594 0.968602 -0.199322 -0.655847 -0.748455 -0.098385 -0.727095 -0.568298 -0.385189 -0.888271 -0.136601 -0.438538 -0.694559 -0.718699 -0.0325731 -0.297678 -0.950848 -0.0853028 -0.153089 -0.983602 -0.0953422 -0.891809 -0.388904 -0.231152 -0.961854 -0.256341 -0.0955299 -0.965619 -0.185918 -0.181701 -0.61891 -0.777082 0.114431 -0.810001 -0.574943 -0.115496 -0.887194 -0.458212 -0.0541169 -0.866254 -0.365115 -0.341021 -0.757416 -0.486622 -0.43534 -0.839297 -0.217349 -0.498337 -0.839386 -0.213849 -0.4997 -0.997115 -0.044575 -0.0614322 -0.989171 -0.14641 -0.0102589 -0.0831275 -0.583116 0.808125 -0.883576 -0.45193 0.122687 -0.895975 -0.442466 -0.0381052 -0.326804 -0.944332 -0.0378915 -0.396322 -0.908665 -0.131364 -0.450411 -0.891734 -0.0440585 -0.774398 -0.584081 -0.243224 -0.821973 -0.546444 -0.160496 -0.905173 -0.169834 -0.389639 -0.944821 -0.127932 -0.301572 -0.896294 -0.0721113 -0.437558 -0.929417 -0.0587988 -0.364317 -0.31782 -0.9335 -0.166037 -0.483796 -0.842079 -0.238422 -0.432023 -0.88957 -0.148393 -0.594895 -0.74049 -0.312689 -0.662864 -0.720202 -0.204745 -0.816992 -0.467131 -0.338101 -0.835179 -0.386952 -0.390825 -0.868657 -0.155647 -0.470329 -0.868134 -0.1517 -0.472579 -0.302466 -0.783092 -0.543397 -0.0440223 -0.995893 -0.0791146 -0.291696 -0.933793 -0.207231 -0.147164 -0.983569 -0.104567 -0.109336 -0.983569 -0.143658 -0.0885163 -0.990316 -0.106958 -0.249974 -0.937968 -0.240267 -0.134327 -0.983578 -0.120545 -0.141579 -0.983639 -0.111402 -0.141955 -0.98478 -0.100288 -0.475669 -0.209892 -0.854216 -0.085469 -0.983395 -0.16009 -0.131417 -0.9628 -0.236107 -0.219765 -0.892008 -0.395 -0.401821 -0.563769 -0.721599 -0.474558 -0.216397 -0.85321 -0.622297 -0.216567 -0.752227 -0.626453 -0.0280538 -0.778954 -0.671534 -0.21957 -0.707694 -0.726204 -0.219112 -0.651627 -0.726313 -0.218612 -0.651674 -0.795453 -0.218724 -0.565167 -0.795787 -0.21724 -0.565269 -0.400133 -0.567825 -0.719353 -0.524657 -0.568153 -0.633986 -0.523902 -0.569621 -0.633292 -0.611541 -0.570002 -0.54874 -0.611617 -0.56987 -0.548792 -0.669746 -0.570086 -0.47586 -0.670294 -0.569202 -0.476147 -0.257242 -0.844175 -0.470313 -0.341387 -0.844549 -0.412543 -0.340692 -0.845171 -0.411843 -0.397532 -0.84541 -0.356723 -0.397532 -0.84541 -0.356723 -0.435226 -0.845548 -0.309236 -0.438221 -0.843359 -0.310979 -0.997849 -0.0215623 -0.0619108 -0.997867 -0.0215688 -0.0616201 -0.982294 -0.0220587 -0.186041 -0.982426 -0.0220767 -0.185342 -0.931087 -0.0221515 -0.364124 -0.93083 -0.0221118 -0.364783 -0.140013 -0.28654 -0.947782 0.00534562 -0.433046 -0.901356 0.718024 -0.317422 -0.619423 0.626759 -0.460813 -0.628351 0.91612 -0.344622 -0.204839 0.920183 -0.30587 -0.244349 0.82374 -0.536803 -0.18247 0.115891 -0.564378 -0.817341 0.0231602 -0.953533 -0.300398 0.120179 -0.968618 -0.217568 -0.0517182 -0.884418 -0.46382 0.0304111 -0.916198 -0.39957 -0.257308 -0.169659 -0.951319 -0.305312 -0.270089 -0.913146 -0.349101 -0.210672 -0.913097 -0.0868653 -0.0307173 -0.995746 -0.110628 -0.0661655 -0.991657 0.252007 -0.131729 -0.958718 0.235633 -0.134029 -0.962556 0.128399 -0.979948 -0.152364 0.236524 -0.952434 0.19216 0.252718 -0.965833 -0.0574437 0.459756 -0.687227 -0.562444 0.551496 -0.656151 -0.515091 0.674487 -0.662901 -0.325007 0.714753 -0.291329 -0.635811 0.625097 -0.4972 -0.601703 0.83897 -0.491703 -0.233148 0.669716 -0.722636 -0.171108 0.724085 -0.679378 -0.118934 0.626387 -0.775186 -0.0820075 -0.20091 -0.150561 -0.96797 -0.259605 -0.23079 -0.937732 -0.0423409 -0.539727 -0.840775 -0.198937 -0.600042 -0.774838 -0.245734 -0.563403 -0.788792 -0.0716574 -0.108702 -0.991488 -0.172844 -0.141967 -0.974664 0.148706 -0.336139 -0.929999 0.11248 -0.328196 -0.937889 0.309993 -0.426881 -0.849516 0.255564 -0.485907 -0.835812 0.0460024 -0.510323 -0.858751 -0.0521782 -0.571988 -0.818601 0.136161 -0.744294 -0.653824 -0.0662962 -0.819742 -0.568884 -0.129476 -0.778315 -0.614379 0.432963 -0.892022 -0.129766 0.577998 -0.815927 0.0134326 0.391974 -0.860102 -0.326467 0.474749 -0.844061 -0.249349 0.295168 -0.810728 -0.505565 0.374168 -0.813568 -0.44509 0.232083 -0.751713 -0.617305 0.428159 -0.57478 -0.697358 0.479613 -0.594206 -0.64567 0.371378 -0.388459 -0.843314 0.461919 -0.166957 -0.871066 0.664681 -0.285545 -0.690408 0.482358 -0.096628 -0.870628 0.762517 -0.106286 -0.638178 0.76624 -0.118235 -0.631582 0.968496 -0.104607 -0.225994 0.969273 -0.118171 -0.215745 -0.360397 0.930449 -0.0661655 -0.423169 0.905136 0.0406972 -0.790214 0.576372 -0.208222 -0.418823 0.885558 -0.200935 -0.675345 0.660208 -0.328687 -0.563525 0.771768 -0.294642 -0.84712 0.177191 -0.50099 -0.835915 0.333438 -0.435965 -0.874452 0.107949 -0.472949 -0.896273 0.0908127 -0.434107 -0.90089 0.178646 -0.395578 -0.92999 0.0788688 -0.359025 -0.931304 0.00867763 -0.36414 -0.91866 0.0183414 -0.394624 -0.112871 0.545721 0.83033 -0.980367 0.0661029 -0.185769 -0.978124 0.177035 0.109233 -0.997092 0.044209 -0.0620693 -0.848172 0.510462 -0.141538 -0.769765 0.572987 -0.281332 -0.733786 0.639408 -0.229599 -0.641099 0.753371 -0.146374 -0.581596 0.775005 -0.247211 -0.259869 0.959982 -0.104412 -0.0955304 0.99516 -0.02304 -0.080902 0.996722 -0.00102797 -0.47138 0.86665 -0.16346 -0.532881 0.844083 -0.0596916 -0.683643 0.709078 -0.172747 -0.728462 0.677998 -0.0982963 -0.690625 0.723063 0.0147639 -0.880272 0.464882 -0.094899 -0.918941 0.393853 -0.020676 -0.729724 0.544676 -0.413318 -0.789726 0.450047 -0.416882 -0.82456 0.438048 -0.358071 -0.861037 0.342391 -0.37601 -0.903853 0.307386 -0.297598 -0.890359 0.375416 -0.257534 -0.951582 0.270161 -0.146645 -0.920178 0.390543 -0.0273701 -0.980972 0.175542 -0.0829374 -0.0799575 -0.0148367 -0.996688 -0.086872 -0.0155144 -0.996099 0.253667 -0.0146045 -0.967181 0.378111 -0.0209009 -0.925524 0.483939 -0.0134696 -0.874998 0.689551 -0.0109464 -0.724154 0.770614 -0.00290391 -0.637296 0.845904 -0.00819163 -0.533272 0.947304 -0.00485708 -0.320299 0.975641 0.00205552 -0.219363 0.99444 -0.00160769 -0.105297 -0.13816 0.982615 -0.124018 -0.0758602 0.995666 -0.0537928 -0.0883441 0.982573 -0.163542 -0.0625964 0.990422 -0.123071 -0.100199 0.982678 -0.155898 -0.117831 0.982549 -0.143922 -0.15398 0.971146 -0.182115 -0.118094 0.987622 -0.103235 -0.802794 0.177126 -0.569341 -0.517842 0.77265 -0.367221 -0.683997 0.544828 -0.485089 -0.153435 0.9826 -0.104664 -0.224956 0.961221 -0.159529 -0.376998 0.886786 -0.267363 -0.802987 0.17611 -0.569383 -0.732583 0.175998 -0.657532 -0.732617 0.175582 -0.657604 -0.623725 0.175388 -0.761712 -0.623703 0.175803 -0.761635 -0.467916 0.175665 -0.866139 -0.467865 0.178319 -0.865624 -0.68434 0.544241 -0.485263 -0.624461 0.543979 -0.560479 -0.624674 0.543468 -0.560736 -0.531976 0.543052 -0.649689 -0.531912 0.54324 -0.649584 -0.399168 0.542882 -0.73888 -0.398821 0.544432 -0.737927 -0.449977 0.836037 -0.313948 -0.408393 0.83597 -0.366566 -0.40864 0.835731 -0.366834 -0.348153 0.835455 -0.425211 -0.348134 0.835477 -0.425183 -0.26136 0.835243 -0.483797 -0.261028 0.8358 -0.483014 0.587168 0.80624 -0.072184 0.290013 0.304077 -0.90743 0.336997 0.194715 -0.921151 0.340166 0.917626 -0.205549 -0.0329177 0.981917 -0.186428 0.233907 0.794422 -0.560518 0.441154 0.556724 -0.703876 0.419362 0.479555 -0.770819 0.925265 0.210593 -0.315491 0.917451 0.383283 -0.106663 0.863785 0.495411 -0.0918852 0.838954 0.543592 0.0257695 0.744702 0.658763 -0.107006 0.669236 0.736519 -0.0983038 0.373008 0.701633 -0.607105 0.407259 0.592865 -0.694731 0.429153 0.768005 -0.47539 0.638476 0.54915 -0.539242 0.657278 0.571653 -0.49112 0.819894 0.194212 -0.538568 0.827449 0.201333 -0.524208 -0.0462914 0.0510489 -0.997623 -0.0799336 0.0123872 -0.996723 0.377274 0.0558146 -0.924418 0.0966049 0.332036 -0.938307 -0.0282739 0.450121 -0.89252 -0.35777 0.17918 -0.916458 0.0610425 0.984947 -0.161721 -0.167669 0.836232 -0.522114 -0.105225 0.853094 -0.511036 -0.286499 0.546036 -0.78725 -0.178248 0.603003 -0.77757 -0.34186 0.159202 -0.926168 -0.249485 0.231836 -0.940217 0.964116 0.256573 -0.0681923 0.980986 0.192692 0.0231691 0.991111 0.0804622 -0.105952 0.920619 0.203964 -0.332956 0.75293 0.593554 -0.284236 0.740604 0.577481 -0.343542 0.591043 0.750107 -0.296659 0.570208 0.785615 -0.240149 0.429907 0.884621 -0.180628 0.163552 0.802878 -0.57327 0.375017 0.0583975 -0.925177 0.348819 0.185449 -0.918659 -0.0877563 0.0629356 -0.994152 -0.126503 0.10173 -0.986736 -0.121232 0.161396 -0.979415 -0.13946 0.156216 -0.977828 -0.24427 0.157238 -0.956874 -0.045536 0.41343 -0.909397 -0.0937382 0.434396 -0.895831 0.686612 0.0833888 -0.722226 0.583308 0.167945 -0.794699 0.640047 0.260531 -0.722816 0.570092 0.425186 -0.703002 0.267432 0.315508 -0.910459 0.190733 0.424696 -0.885017 0.186916 0.543809 -0.818128 0.162221 0.565967 -0.808311 0.179117 0.649537 -0.738931 0.0108993 0.604584 -0.796467 -0.106733 0.65048 -0.751987 0.0662991 0.840935 -0.53706 -0.00825708 0.835447 -0.54951 0.251473 0.952311 -0.172815 0.155748 0.967571 -0.198868 0.069184 -0.258199 -0.963611 0.258205 -0.0691843 -0.96361 0.258188 -0.0691872 -0.963614 0.935109 -0.250568 -0.250574 0.935087 -0.250598 -0.250626 0.694734 -0.186185 -0.694751 0.785192 -0.143509 -0.602394 0.60079 -0.160995 -0.783027 0.189009 -0.189012 -0.963613 0.189017 -0.189015 -0.963611 0.508593 -0.508589 -0.694745 0.508582 -0.508587 -0.694754 0.684545 -0.684553 -0.25057 0.684576 -0.684539 -0.250523 0.0691826 -0.258197 -0.963612 0.160988 -0.600825 -0.783002 0.152649 -0.70803 -0.689487 0.207936 -0.776024 -0.595441 0.250565 -0.935116 -0.250551 0.250553 -0.935115 -0.250567 0.980774 0 -0.195149 0.965892 0.0056718 -0.258883 0.831476 -0.00379037 -0.555548 0.793405 0 -0.608694 0.555544 0 -0.831487 0.608721 -0.00567049 -0.793364 0.195094 0.00752257 -0.980756 0.258826 0 -0.965924 0 -0.965925 -0.258822 -0.0507216 -0.979523 -0.194841 0.038243 -0.792784 -0.608301 0 -0.831471 -0.555568 0 -0.608765 -0.79335 0.0256049 -0.55539 -0.831196 -0.0382523 -0.258628 -0.965219 0 -0.195089 -0.980785 0.132267 0.556499 -0.820252 0.0930477 0.257695 -0.961736 0.0522028 0.194825 -0.979448 0.180497 0.88213 -0.435048 0.207933 0.776024 -0.595442 0.160989 0.600826 -0.783001 0.217457 0.811574 -0.542274 0.254167 0.948579 -0.188673 0.254163 0.948578 -0.188681 0.142622 0.142624 -0.979447 0.142622 0.142626 -0.979447 0.402262 0.402272 -0.822413 0.402258 0.402259 -0.822421 0.594113 0.594115 -0.54227 0.594116 0.59414 -0.54224 0.694395 0.694423 -0.188661 0.694415 0.694378 -0.188753 0.19483 0.0522032 -0.979447 0.194834 0.0522059 -0.979446 0.549486 0.147235 -0.822427 0.54949 0.147238 -0.822425 0.811599 0.217471 -0.54223 0.811585 0.217453 -0.542258 0.948562 0.254153 -0.188777 0.948564 0.254173 -0.18874 -0.108498 -0.198163 -0.974146 -0.00263558 -0.982959 -0.183807 -0.00337242 -0.980779 -0.195091 -0.00717321 -0.839273 -0.543663 -0.00809077 -0.831444 -0.55555 -0.0117588 -0.552615 -0.833354 -0.0115382 -0.555535 -0.831413 -0.0143504 -0.189647 -0.981747 -0.0140414 -0.19507 -0.980689 -0.0199885 -0.983073 -0.182123 -0.020118 -0.982921 -0.182926 -0.0589971 -0.840555 -0.538504 -0.0594494 -0.838877 -0.541065 -0.0903493 -0.557001 -0.825583 -0.0910444 -0.551984 -0.828869 -0.107236 -0.162032 -0.980941 -0.0450847 -0.189733 -0.9808 0 0.980786 -0.195088 0.0382557 0.965218 -0.258632 0 0.896861 -0.442313 0 0.793364 -0.608747 0 0.793364 -0.608747 0 0.608767 -0.793349 0 0.608767 -0.793349 0 0.258818 -0.965926 0 0.258818 -0.965926 -0.61097 -0.292417 -0.735668 -0.633579 -0.752131 -0.181319 -0.280614 -0.553836 -0.783914 -0.405587 -0.0534159 -0.912494 -0.147465 -0.97665 -0.15623 -0.79161 -0.593522 -0.145211 -0.823839 -0.562009 -0.0737206 -0.887057 -0.430968 -0.165517 -0.290982 -0.231507 -0.928296 -0.266719 -0.533467 -0.802667 -0.237295 -0.198509 -0.950939 -0.201107 -0.13763 -0.969853 -0.985569 -0.0598025 -0.15836 -0.977207 -0.198638 -0.0749 -0.966834 -0.22539 -0.120133 -0.926097 -0.342882 -0.157404 -0.38553 -0.911691 -0.142079 -0.32494 -0.901572 -0.285626 -0.546287 -0.832917 -0.0884312 -0.565239 -0.652466 -0.50477 -0.77392 -0.441468 -0.454042 -0.758055 -0.442123 -0.479459 -0.877956 -0.15665 -0.452386 -0.371135 -0.112669 -0.921718 -0.342619 -0.0554923 -0.937834 -0.852919 -0.319642 -0.412744 -0.673631 -0.105713 -0.731469 -0.872186 -0.160284 -0.462169 -0.115794 -0.973081 -0.199259 -0.204739 -0.836787 -0.507809 -0.336215 -0.876203 -0.345295 -0.258727 -0.803691 -0.535855 -0.551145 -0.686388 -0.474458 -0.474964 -0.447868 -0.757511 -0.462421 -0.439393 -0.77013 -0.305501 -0.139868 -0.941863 -0.337573 -0.146054 -0.929899 -0.0974135 0.182568 -0.978355 -0.0975461 0.186528 -0.977595 -0.0830664 0.545227 -0.834163 -0.0830704 0.548035 -0.83232 -0.0546856 0.834085 -0.548918 -0.0546264 0.835266 -0.547126 -0.0275776 0.960627 -0.276469 -0.0210675 0.982189 -0.186712 -0.00912931 0.99577 -0.0914228 -0.0033769 0.96592 -0.25882 -0.00760782 0.982279 -0.187273 -0.00388894 0.793358 -0.608743 -0.00714351 0.835615 -0.54927 -0.0103337 0.608734 -0.793307 -0.00826221 0.548526 -0.836093 -0.0163254 0.258783 -0.965798 -0.0127626 0.186785 -0.982318 -0.399853 -0.0108317 -0.916515 -0.987058 -0.00205267 -0.16035 -0.987195 -0.00210298 -0.159502 -0.881346 -0.00598078 -0.472434 -0.882608 -0.00615319 -0.47007 -0.673034 -0.00931714 -0.739552 -0.676662 -0.00964874 -0.736231 -0.39524 -0.0115465 -0.918506 -0.405904 -0.0131123 -0.913822 -0.342381 0.0316219 -0.939029 -0.565043 0.646312 -0.512842 -0.878976 0.14425 -0.454526 -0.87085 0.149061 -0.468403 -0.670046 0.0865575 -0.737256 -0.282104 0.793337 -0.539476 -0.550569 0.681292 -0.482405 -0.470618 0.436244 -0.766948 -0.457195 0.427377 -0.77995 -0.298238 0.126937 -0.946013 -0.362106 0.163493 -0.917687 -0.426789 0.892494 0.145961 -0.563678 0.817401 -0.118841 -0.263039 0.962496 -0.066415 -0.157149 0.985721 0.0604867 -0.0953715 0.99256 -0.0756896 -0.669691 0.736722 -0.093564 -0.820104 0.570166 -0.0483894 -0.810785 0.571141 -0.128165 -0.961819 0.199937 -0.186892 -0.968867 0.189472 -0.159366 -0.238167 0.205387 -0.949259 -0.224715 0.182867 -0.957112 -0.258263 0.523995 -0.811622 -0.270982 0.54198 -0.795504 -0.250956 0.824425 -0.507291 -0.399832 0.000737811 -0.916588 -0.355806 0.0430432 -0.933568 -0.847937 0.306424 -0.43256 -0.608807 0.276889 -0.743429 -0.758266 0.432801 -0.487562 -0.77582 0.43229 -0.459597 -0.822974 0.52569 -0.215322 -0.569831 0.774274 -0.275306 -0.578389 0.785594 -0.21979 -0.234593 0.927294 -0.291704 -0.239156 0.942536 -0.233304 0.0691837 -0.258199 -0.963611 0.258205 -0.0691843 -0.96361 0.258187 -0.0691871 -0.963614 0.694756 -0.186176 -0.694732 0.694734 -0.186185 -0.694751 0.935087 -0.250598 -0.250626 0.935109 -0.250568 -0.250574 0.189008 -0.189012 -0.963613 0.189017 -0.189015 -0.963611 0.508593 -0.508588 -0.694745 0.508581 -0.508587 -0.694755 0.684545 -0.684553 -0.25057 0.684576 -0.684539 -0.250522 0.0691827 -0.258198 -0.963612 0.160988 -0.600826 -0.783001 0.15265 -0.708028 -0.689488 0.207936 -0.776022 -0.595444 0.250566 -0.935116 -0.250549 0.250554 -0.935115 -0.250565 0.965908 0 -0.258887 0.965908 0 -0.258887 0.707119 0 -0.707095 0.707119 0 -0.707095 0.258826 0 -0.965924 0.258826 0 -0.965924 0 -0.965925 -0.258821 -0.050722 -0.979523 -0.194839 0.0382437 -0.792782 -0.608304 0 -0.83147 -0.55557 0 -0.608767 -0.793349 0.0256047 -0.555392 -0.831195 -0.0382525 -0.258628 -0.965219 0 -0.195089 -0.980785 0.0691832 0.258197 -0.963612 0.069183 0.258199 -0.963612 0.186156 0.694756 -0.694738 0.186159 0.69475 -0.694743 0.250564 0.935113 -0.250563 0.250556 0.935118 -0.25055 0.189014 0.189017 -0.963611 0.189011 0.189009 -0.963613 0.508587 0.508583 -0.694753 0.508589 0.508594 -0.694744 0.684554 0.684561 -0.250525 0.684567 0.68453 -0.250572 0.258191 0.0691805 -0.963614 0.258205 0.0691919 -0.963609 0.69474 0.186171 -0.69475 0.694754 0.18619 -0.69473 0.935099 0.250601 -0.250576 0.935095 0.250564 -0.250628 -0.0182654 -0.982894 -0.183263 -0.0183756 -0.982756 -0.18399 -0.00240182 -0.982925 -0.183989 -0.00311328 -0.980781 -0.195089 -0.00649446 -0.838914 -0.544226 -0.00735641 -0.831447 -0.555555 -0.010729 -0.551635 -0.834017 -0.0104362 -0.555544 -0.831422 -0.0131459 -0.187966 -0.982088 -0.012741 -0.195074 -0.980706 -0.0973144 -0.187711 -0.977392 -0.0976019 -0.183732 -0.978119 -0.0826829 -0.551114 -0.830323 -0.083052 -0.548338 -0.832122 -0.0540046 -0.838582 -0.542092 -0.0547961 -0.835468 -0.546801 -0.0364073 -0.930368 -0.364816 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.793362 -0.60875 -0.0510492 0.706194 -0.706176 0 0.608768 -0.793348 0 0.258817 -0.965926 0 0.258817 -0.965926 -0.608559 -0.277202 -0.743515 -0.402259 -0.0314227 -0.914987 -0.633499 -0.750694 -0.187452 -0.474708 -0.865395 -0.160449 -0.501043 -0.708437 -0.497065 -0.195188 -0.831979 -0.519339 -0.153187 -0.927024 -0.342287 -0.383635 -0.911754 -0.146724 -0.155191 -0.968725 -0.193617 -0.104804 -0.980194 -0.168038 -0.775545 -0.432832 -0.459551 -0.757959 -0.433334 -0.487566 -0.878881 -0.144969 -0.45448 -0.189722 -0.184253 -0.964394 -0.322373 -0.903399 -0.282747 -0.335122 -0.872788 -0.354872 -0.253682 -0.800767 -0.542603 -0.272137 -0.544962 -0.793069 -0.257516 -0.524207 -0.811722 -0.221441 -0.156088 -0.962601 -0.2789 -0.215074 -0.935926 -0.968579 -0.218528 -0.118743 -0.976916 -0.197766 -0.0807702 -0.9859 -0.0501489 -0.159643 -0.927646 -0.338081 -0.158667 -0.889026 -0.425723 -0.168502 -0.824054 -0.560983 -0.0789534 -0.793313 -0.590757 -0.147176 -0.362283 -0.091987 -0.927518 -0.333626 -0.0337025 -0.942103 -0.851279 -0.306999 -0.425529 -0.673628 -0.0887385 -0.733724 -0.872244 -0.148928 -0.465845 -0.635801 -0.749594 -0.184026 -0.640322 -0.694964 -0.327128 -0.545628 -0.661095 -0.515019 -0.470296 -0.436491 -0.767006 -0.456853 -0.427591 -0.780033 -0.29453 -0.120889 -0.947965 -0.327038 -0.127102 -0.936425 -0.107044 0.196977 -0.974547 -0.10676 0.18819 -0.976313 -0.0909056 0.553981 -0.827551 -0.0909284 0.548943 -0.830899 -0.0597193 0.837283 -0.543499 -0.0598312 0.835561 -0.54613 -0.0300521 0.961334 -0.273742 -0.0228684 0.982215 -0.18636 -0.00993551 0.995843 -0.0905397 -0.00370903 0.965919 -0.258818 -0.00785809 0.982319 -0.187051 -0.00465352 0.793353 -0.608744 -0.00786327 0.835968 -0.548722 -0.0113285 0.608729 -0.793297 -0.00933554 0.549524 -0.835426 -0.0175316 0.258778 -0.965778 -0.0140586 0.188475 -0.981977 -0.987365 0.00202834 -0.158449 -0.987225 0.00210158 -0.159319 -0.883988 0.00592197 -0.467471 -0.882734 0.00615036 -0.469833 -0.68033 0.00923944 -0.732848 -0.676771 0.0096381 -0.736131 -0.408629 0.011483 -0.912628 -0.402593 0.0119743 -0.915301 -0.873656 0.159471 -0.459667 -0.877907 0.156756 -0.452447 -0.758425 0.441612 -0.479344 -0.774173 0.440952 -0.454112 -0.565698 0.652055 -0.504788 -0.564987 0.795567 -0.218776 -0.509321 0.856262 -0.086065 -0.46824 0.451079 -0.759789 -0.319403 0.16375 -0.933364 -0.31466 0.136343 -0.939361 -0.408608 0.0245111 -0.912381 -0.36624 0.0670662 -0.928101 -0.351155 0.054368 -0.934738 -0.362961 0.120931 -0.923924 -0.273812 0.959508 -0.0661131 -0.384937 0.918826 -0.0870774 -0.512884 0.856502 -0.0579221 -0.682007 0.710865 -0.171866 -0.824164 0.54994 -0.135349 -0.825291 0.549108 -0.131813 -0.961355 0.204682 -0.184124 -0.969506 0.191683 -0.152693 -0.255329 0.827898 -0.499392 -0.279566 0.529158 -0.801146 -0.26815 0.551702 -0.789759 -0.241626 0.235195 -0.941435 -0.246479 0.197247 -0.948864 -0.677171 0.107374 -0.727949 -0.855716 0.319149 -0.407302 -0.61124 0.292089 -0.735574 -0.469417 0.433407 -0.769289 -0.551622 0.685998 -0.474467 -0.28746 0.796145 -0.532465 -0.236878 0.927641 -0.28874 -0.240389 0.943563 -0.227821 -0.152894 0.985959 0.0671499 -0.107221 0.991674 -0.0713161 0.0691835 -0.258198 -0.963612 0.258205 -0.0691843 -0.96361 0.258188 -0.0691872 -0.963614 0.694756 -0.186176 -0.694732 0.694734 -0.186185 -0.694751 0.935087 -0.250598 -0.250626 0.935109 -0.250568 -0.250574 0.189009 -0.189012 -0.963613 0.189017 -0.189015 -0.963611 0.508593 -0.508589 -0.694745 0.508582 -0.508587 -0.694754 0.684545 -0.684553 -0.25057 0.684576 -0.684539 -0.250523 0.0691826 -0.258197 -0.963612 0.160989 -0.600828 -0.783 0.15265 -0.708029 -0.689487 0.207935 -0.776021 -0.595445 0.250565 -0.935116 -0.250551 0.250555 -0.935115 -0.250564 0.965908 0 -0.258887 0.965908 0 -0.258887 0.707119 0 -0.707095 0.707119 0 -0.707095 0.258826 0 -0.965924 0.258826 0 -0.965924 0 -0.965926 -0.25882 -0.0507223 -0.979523 -0.194837 0.0382439 -0.792781 -0.608305 0 -0.831469 -0.555571 0 -0.608768 -0.793348 0.0256053 -0.555392 -0.831195 -0.0382523 -0.258628 -0.965219 0 -0.195089 -0.980785 0.0691835 0.258197 -0.963612 0.0691832 0.258199 -0.963611 0.186156 0.694756 -0.694738 0.186159 0.69475 -0.694743 0.250564 0.935112 -0.250566 0.250555 0.935119 -0.25055 0.189014 0.189017 -0.963611 0.189011 0.189009 -0.963613 0.508587 0.508583 -0.694753 0.508589 0.508594 -0.694744 0.684554 0.684561 -0.250525 0.684567 0.68453 -0.250572 0.258191 0.0691805 -0.963614 0.258205 0.0691919 -0.963609 0.69474 0.186171 -0.69475 0.694754 0.18619 -0.69473 0.935099 0.250601 -0.250576 0.935095 0.250564 -0.250628 -0.180066 -0.177534 -0.967501 -0.00268763 -0.982904 -0.184099 -0.00340894 -0.98078 -0.195087 -0.00734116 -0.838714 -0.544523 -0.00819803 -0.831441 -0.555552 -0.0120267 -0.551111 -0.834345 -0.0116905 -0.555536 -0.83141 -0.102797 -0.0245429 -0.9944 -0.020636 -0.982588 -0.184647 -0.0203972 -0.982866 -0.183191 -0.0609966 -0.835832 -0.545587 -0.0603202 -0.838311 -0.541845 -0.0932302 -0.544055 -0.833854 -0.0923242 -0.550484 -0.829725 -0.109151 -0.186865 -0.976303 -0.0146726 -0.187169 -0.982218 -0.0142192 -0.19507 -0.980686 0 0.965925 -0.258822 0 0.965925 -0.258822 0 0.793365 -0.608747 -0.0510509 0.706194 -0.706176 0 0.608765 -0.79335 0 0.258817 -0.965926 0 0.258817 -0.965926 -0.242968 -0.177281 -0.953697 -0.341521 -0.774184 -0.532918 -0.366841 -0.780488 -0.506227 -0.389079 -0.910091 -0.142662 -0.32859 -0.898795 -0.290165 -0.476105 -0.864354 -0.161912 -0.511298 -0.703825 -0.493158 -0.645332 -0.692999 -0.321401 -0.553493 -0.654801 -0.514666 -0.783054 -0.427092 -0.452126 -0.763453 -0.426773 -0.484773 -0.420487 -0.0209137 -0.907058 -0.351194 -0.0227713 -0.936026 -0.204304 -0.112568 -0.972414 -0.296747 -0.207683 -0.932099 -0.312275 -0.110998 -0.943485 -0.344678 -0.117159 -0.931381 -0.380291 -0.08171 -0.92125 -0.986499 -0.0443176 -0.15766 -0.929463 -0.334482 -0.155629 -0.893168 -0.417667 -0.16675 -0.823495 -0.561607 -0.0803287 -0.799003 -0.584519 -0.141178 -0.637582 -0.747639 -0.185807 -0.639764 -0.746632 -0.182329 -0.684195 -0.0797216 -0.724929 -0.876166 -0.143605 -0.46012 -0.884262 -0.139089 -0.445797 -0.976799 -0.198386 -0.0806628 -0.970419 -0.213894 -0.111965 -0.860985 -0.305687 -0.406521 -0.621838 -0.268528 -0.73567 -0.470018 -0.418869 -0.776937 -0.485301 -0.429497 -0.761587 -0.271739 -0.517472 -0.811407 -0.346314 -0.62587 -0.698823 -0.232428 -0.543935 -0.806295 -0.179071 -0.817995 -0.546643 -0.209725 -0.831927 -0.513725 -0.1167 -0.972237 -0.20282 -0.149682 -0.976024 -0.158024 -0.126111 0.201709 -0.971293 -0.125736 0.188628 -0.973966 -0.106966 0.55669 -0.823805 -0.107099 0.549012 -0.828924 -0.0702335 0.838208 -0.54081 -0.0704897 0.83551 -0.544935 -0.0353309 0.96153 -0.272418 -0.0265196 0.982197 -0.18597 -0.011679 0.995862 -0.0901216 -0.00437611 0.965916 -0.25882 -0.00833867 0.98233 -0.186972 -0.00621435 0.793349 -0.608735 -0.00927498 0.836047 -0.548579 -0.0133534 0.608711 -0.793279 -0.0114744 0.549777 -0.835233 -0.0199892 0.258766 -0.965733 -0.01658 0.18902 -0.981833 -0.98786 0.00357208 -0.155307 -0.987621 0.00371267 -0.156818 -0.888863 0.0104258 -0.458055 -0.886651 0.0108697 -0.462311 -0.693415 0.0163289 -0.720354 -0.687308 0.0170641 -0.726165 -0.43141 0.0204014 -0.901925 -0.420825 0.0212972 -0.906892 -0.498008 0.83554 -0.23208 -0.550035 0.827909 -0.109675 -0.575785 0.648959 -0.497317 -0.780293 0.442044 -0.442426 -0.763698 0.442187 -0.470358 -0.882428 0.160072 -0.442378 -0.87862 0.162489 -0.449026 -0.485558 0.453482 -0.747388 -0.344785 0.168804 -0.923379 -0.340092 0.140811 -0.92979 -0.431387 0.0327337 -0.901573 -0.390216 0.0739876 -0.917746 -0.375143 0.0612322 -0.924942 -0.387787 0.126674 -0.913003 -0.288149 0.954948 -0.071024 -0.388319 0.917567 -0.0853183 -0.518109 0.853741 -0.0518578 -0.691545 0.702334 -0.168796 -0.828792 0.545776 -0.123423 -0.825072 0.548348 -0.136272 -0.96411 0.202523 -0.171684 -0.97003 0.192837 -0.147836 -0.26616 0.829346 -0.491268 -0.301751 0.529389 -0.792902 -0.288568 0.554748 -0.780374 -0.268098 0.242852 -0.93228 -0.273389 0.202105 -0.940432 -0.690266 0.112852 -0.714701 -0.869081 0.327707 -0.370548 -0.626066 0.295452 -0.72163 -0.487104 0.433604 -0.758101 -0.55949 0.686829 -0.463937 -0.303355 0.793527 -0.527533 -0.244101 0.925619 -0.289212 -0.245058 0.944078 -0.220596 -0.147103 0.986868 0.0667296 -0.117962 0.990824 -0.0659791 -0.133911 -0.247545 -0.959578 0.0197087 -0.406453 -0.913459 0.724386 -0.292597 -0.624222 0.637042 -0.443255 -0.630636 0.919029 -0.333812 -0.209655 0.922874 -0.299962 -0.241508 0.828244 -0.52796 -0.187804 0.137652 -0.546563 -0.826027 0.0297806 -0.951419 -0.306457 0.121067 -0.966536 -0.226165 -0.0437601 -0.879224 -0.474395 0.0342116 -0.910463 -0.412174 -0.293825 -0.237016 -0.926008 -0.336479 -0.179054 -0.924512 -0.07995 -0.00168653 -0.996797 -0.102657 -0.03362 -0.994149 0.257486 -0.101793 -0.960905 0.247367 -0.103093 -0.963422 0.132875 -0.979246 -0.15304 0.221302 -0.960706 0.167538 0.259854 -0.963538 -0.0638075 0.468236 -0.672202 -0.573498 0.564892 -0.640254 -0.52055 0.68256 -0.654116 -0.325951 0.72221 -0.273163 -0.635449 0.635068 -0.474375 -0.609637 0.842921 -0.485965 -0.230915 0.672095 -0.718693 -0.178235 0.730245 -0.672824 -0.118534 0.632214 -0.769991 -0.0861379 -0.169753 -0.163121 -0.971893 -0.260619 -0.174553 -0.949531 -0.0278811 -0.51819 -0.854811 -0.189108 -0.580446 -0.792036 -0.235298 -0.544108 -0.805346 -0.0612093 -0.080515 -0.994872 -0.159565 -0.110106 -0.981028 0.160256 -0.306604 -0.938249 0.12871 -0.299423 -0.945399 0.325575 -0.402534 -0.855551 0.272051 -0.460731 -0.844817 0.0626972 -0.486001 -0.871706 -0.0385533 -0.549889 -0.834347 0.149108 -0.731119 -0.665756 -0.0599876 -0.809103 -0.584598 -0.120545 -0.768317 -0.628616 0.442597 -0.887061 -0.131268 0.574122 -0.818729 0.00821233 0.403809 -0.853163 -0.33023 0.477687 -0.839866 -0.257762 0.309502 -0.800336 -0.513489 0.381064 -0.80405 -0.456393 0.24276 -0.736171 -0.631759 0.442079 -0.555786 -0.704037 0.485821 -0.574473 -0.658756 0.38267 -0.360364 -0.850706 0.472088 -0.140653 -0.870258 0.66649 -0.26381 -0.697277 0.486257 -0.0676603 -0.871193 0.76698 -0.08888 -0.635485 0.768434 -0.0937179 -0.633029 0.969696 -0.10095 -0.222481 0.969982 -0.106513 -0.21861 -0.0868718 0.0148396 -0.996109 -0.0799574 0.015514 -0.996678 0.373478 0.0138289 -0.927536 0.259149 0.00140854 -0.965836 0.487754 0.0134335 -0.872878 0.687136 0.0109842 -0.726445 0.772393 0.0164684 -0.634932 0.844719 0.00822101 -0.535146 0.946989 0.00487161 -0.321229 0.975799 0.00870803 -0.218498 0.994401 0.00161321 -0.105658 -0.532536 -0.176513 -0.827797 -0.0438597 -0.995725 -0.0812866 -0.0856358 -0.982449 -0.165712 -0.110786 -0.982648 -0.148761 -0.802431 -0.176184 -0.570143 -0.802263 -0.177069 -0.570105 -0.683944 -0.544122 -0.485955 -0.683529 -0.544832 -0.485743 -0.447204 -0.836084 -0.31776 -0.446855 -0.836348 -0.317558 -0.151145 -0.98266 -0.107398 -0.151183 -0.982652 -0.107421 -0.731336 -0.175551 -0.659037 -0.73124 -0.176077 -0.659004 -0.623621 -0.543399 -0.561974 -0.623355 -0.543887 -0.561797 -0.407935 -0.835728 -0.367625 -0.407688 -0.835929 -0.367442 -0.138022 -0.982587 -0.124389 -0.138027 -0.982586 -0.124392 -0.622482 -0.175854 -0.762622 -0.622567 -0.175359 -0.762666 -0.530894 -0.543221 -0.650432 -0.531003 -0.542997 -0.650531 -0.347494 -0.835453 -0.425754 -0.34749 -0.835456 -0.425751 -0.0901076 -0.989792 -0.110416 -0.123326 -0.98264 -0.138595 -0.130942 -0.961224 -0.242699 -0.219097 -0.88721 -0.406024 -0.257606 -0.835027 -0.486178 -0.301071 -0.773284 -0.558022 -0.398855 -0.542884 -0.739048 -0.398239 -0.544453 -0.738226 -0.474156 0.0613078 -0.878304 -0.446899 -0.1787 -0.876555 0.957551 0.259536 -0.125448 0.279136 0.331912 -0.901065 0.324656 0.226554 -0.918298 0.663263 0.742226 -0.0958286 -0.0385907 0.982102 -0.184353 0.337602 0.919101 -0.203169 0.427222 0.886644 -0.177043 0.150272 0.814086 -0.560966 0.224498 0.805395 -0.54858 0.360133 0.714962 -0.599277 0.764007 0.634551 -0.116782 0.881336 0.462976 -0.0943417 0.83811 0.545427 0.00902071 0.74833 0.603378 -0.275566 0.731564 0.587728 -0.345528 0.65001 0.588057 -0.481328 0.626128 0.564239 -0.538144 0.403839 0.504832 -0.762928 -0.05481 0.0810292 -0.995204 -0.086842 0.0444729 -0.995229 0.372659 0.0830588 -0.924244 0.0814343 0.359615 -0.929541 -0.0421087 0.475977 -0.878449 -0.370562 0.209669 -0.904833 0.0649844 0.985218 -0.158504 -0.180621 0.840239 -0.511249 -0.107223 0.860197 -0.498561 -0.298928 0.562355 -0.770973 -0.187218 0.62163 -0.760609 -0.355666 0.189488 -0.915203 -0.26225 0.263052 -0.928455 0.993437 0.0459446 -0.10475 0.98112 0.192996 -0.0125053 0.924289 0.223306 -0.309555 0.916304 0.213919 -0.338565 0.825668 0.220661 -0.519212 0.813208 0.210379 -0.542617 0.590933 0.803719 -0.0695243 0.573808 0.81595 0.0704926 0.590831 0.751243 -0.294199 0.568215 0.789646 -0.231496 0.419193 0.779891 -0.46481 0.388064 0.617157 -0.684488 0.427259 0.57571 -0.697142 0.366644 0.0900029 -0.925998 0.340946 0.213749 -0.91546 -0.100733 0.0944501 -0.99042 -0.138844 0.133768 -0.981238 -0.132319 0.192956 -0.972245 -0.154689 0.186609 -0.97018 -0.258895 0.187846 -0.947464 -0.06101 0.438152 -0.896828 -0.112771 0.460619 -0.880405 0.684255 0.104638 -0.721696 0.575077 0.197032 -0.794018 0.631128 0.282757 -0.722306 0.561436 0.446468 -0.696747 0.252079 0.345562 -0.903904 0.176182 0.452932 -0.873964 0.17501 0.564306 -0.806803 0.14813 0.588349 -0.794923 0.167857 0.668513 -0.72451 -0.00344254 0.62341 -0.781887 -0.116959 0.667585 -0.73529 0.0588189 0.849719 -0.523944 -0.0178953 0.84388 -0.536233 0.24989 0.953591 -0.167987 0.149748 0.969525 -0.193899 -0.909863 -0.413458 -0.034659 -0.931529 -0.0143784 -0.363382 -0.899345 -0.0277459 -0.436359 -0.769151 -0.574632 -0.279651 -0.594485 -0.77254 -0.22309 -0.628347 -0.721135 -0.291795 -0.680474 -0.703459 -0.205186 -0.619667 -0.779234 -0.0938468 -0.998075 0.00292734 -0.0619456 -0.875998 -0.451105 0.170681 -0.336622 -0.940861 -0.0382957 -0.409035 -0.90264 -0.133912 -0.469815 -0.882138 -0.0332508 -0.538938 -0.832868 -0.126 -0.596608 -0.802057 -0.0276477 -0.659991 -0.741684 -0.119655 -0.710443 -0.703039 -0.0317406 -0.635448 -0.764289 0.109856 -0.99551 -0.0915061 -0.0242053 -0.0366085 -0.592857 0.804475 -0.972309 -0.145085 -0.183208 -0.970392 -0.223462 -0.0916775 -0.947779 -0.0809494 -0.308485 -0.846964 -0.177151 -0.501269 -0.84698 -0.179857 -0.500276 -0.874786 -0.111084 -0.471603 -0.848576 -0.354138 -0.393072 -0.832138 -0.437798 -0.340411 -0.771623 -0.458267 -0.441122 -0.70853 -0.618025 -0.340631 -0.730355 -0.544663 -0.412219 -0.535887 -0.782303 -0.317532 -0.495211 -0.834869 -0.240334 -0.269908 -0.951823 -0.145546 -0.192063 -0.980445 -0.0428959 -0.874626 -0.110172 -0.472114 -0.89434 -0.0947756 -0.437234 -0.880968 -0.33036 -0.338759 -0.912183 -0.13056 -0.388427 -0.837453 -0.522309 -0.160828 -0.905261 -0.356205 -0.231563 -0.822662 -0.557321 -0.112339 -0.899922 -0.432608 -0.0546866 -0.795863 0.216175 -0.565572 -0.795657 0.217658 -0.565293 -0.67188 0.566212 -0.477473 -0.671412 0.567136 -0.477035 -0.439699 0.842036 -0.312475 -0.439343 0.842335 -0.31217 -0.221278 0.96245 -0.157245 -0.151841 0.982928 -0.103909 -0.073207 0.995959 -0.0520212 -0.136826 0.98294 -0.122913 -0.136811 0.982944 -0.122896 -0.401073 0.842233 -0.360256 -0.401112 0.842196 -0.360299 -0.612791 0.56705 -0.550401 -0.612852 0.566914 -0.550473 -0.726092 0.217967 -0.652136 -0.726142 0.217538 -0.652223 -0.117485 0.982842 -0.142192 -0.117278 0.982909 -0.141901 -0.344238 0.841376 -0.416638 -0.343685 0.842002 -0.415829 -0.525474 0.56517 -0.635972 -0.524918 0.566695 -0.635073 -0.621995 0.215526 -0.752776 -0.621807 0.217773 -0.752284 -0.0901548 0.982651 -0.16208 -0.0897866 0.982814 -0.161289 -0.263959 0.839657 -0.474659 -0.263007 0.841174 -0.472497 -0.402351 0.560814 -0.723603 -0.401353 0.564851 -0.721012 -0.475228 0.208758 -0.854739 -0.474972 0.215349 -0.853245 -0.997867 0.0215565 -0.0616202 -0.997853 0.021564 -0.0618496 -0.982426 0.0220711 -0.185342 -0.98254 0.0220526 -0.184742 -0.930829 0.0221891 -0.364782 -0.931386 0.0221073 -0.363362 -0.994377 0.0865612 -0.0610046 -0.434767 0.878724 -0.197034 -0.446861 0.893619 -0.0419643 -0.774544 0.583894 -0.243205 -0.831856 0.536735 -0.141179 -0.875262 0.411109 -0.254766 -0.824905 0.361092 -0.434907 -0.839344 0.216288 -0.49872 -0.717159 0.566069 -0.406509 -0.929779 0.0518896 -0.364442 -0.916553 0.0630113 -0.394918 -0.961866 0.20512 -0.180939 -0.9644 0.249112 -0.0887496 -0.354192 0.604345 0.713663 -0.568894 0.592982 0.569852 -0.659681 0.745794 -0.0927968 -0.69351 0.71959 -0.0351178 -0.674442 0.738179 0.0148034 -0.864318 0.494335 -0.092667 -0.905678 0.42349 -0.0200804 -0.891082 0.134272 -0.433525 -0.868803 0.151134 -0.47153 -0.808528 0.470508 -0.353419 -0.773117 0.482374 -0.411831 -0.479777 0.841284 -0.24911 -0.925146 0.119059 -0.360458 -0.89221 0.222375 -0.393078 -0.890944 0.344537 -0.295827 -0.847358 0.37882 -0.372129 -0.662987 0.720111 -0.204667 -0.623199 0.733836 -0.270385 -0.441621 0.877535 -0.186824 -0.269952 0.959558 -0.0798339 -0.418777 0.896803 -0.142723 -0.119972 0.992546 0.0214461 -0.151996 -0.238833 -0.959091 0.00229295 -0.399708 -0.91664 0.719445 -0.28841 -0.631838 0.631126 -0.441954 -0.637461 0.919972 -0.328738 -0.213502 0.923567 -0.299746 -0.239115 0.828054 -0.525925 -0.194238 0.123665 -0.5446 -0.829529 0.0202149 -0.951108 -0.308195 0.117366 -0.966916 -0.226491 -0.0567272 -0.877339 -0.476506 0.0263028 -0.9102 -0.413332 -0.311727 -0.225091 -0.923125 -0.356076 -0.164373 -0.919887 -0.100761 0.0107475 -0.994853 -0.122949 -0.0208493 -0.992194 0.241166 -0.091354 -0.966175 0.232788 -0.0924113 -0.968127 0.127858 -0.979517 -0.15556 0.216665 -0.966461 0.137875 0.266087 -0.961648 -0.0665592 0.458723 -0.674614 -0.578333 0.558156 -0.641812 -0.52587 0.679105 -0.65582 -0.329723 0.717487 -0.26985 -0.642178 0.62894 -0.473571 -0.616576 0.841635 -0.486847 -0.233733 0.668459 -0.721695 -0.179775 0.728146 -0.674869 -0.119813 0.635216 -0.767279 -0.0882249 -0.189751 -0.149393 -0.9704 -0.280057 -0.162902 -0.946061 -0.0452658 -0.511976 -0.857806 -0.205748 -0.573741 -0.792773 -0.254686 -0.535256 -0.805379 -0.0817858 -0.0681203 -0.994319 -0.178676 -0.0988982 -0.978925 0.14395 -0.299397 -0.943207 0.112327 -0.292137 -0.949757 0.312827 -0.398223 -0.862298 0.260191 -0.455254 -0.851495 0.0452433 -0.481209 -0.875437 -0.0564373 -0.54508 -0.836482 0.135838 -0.729637 -0.670208 -0.0720789 -0.806983 -0.586159 -0.136445 -0.764045 -0.630569 0.443575 -0.886009 -0.13502 0.570376 -0.821383 -0.00126933 0.395974 -0.855548 -0.33353 0.473899 -0.841441 -0.259607 0.298543 -0.801713 -0.517812 0.373859 -0.80545 -0.459869 0.230948 -0.736562 -0.635719 0.432475 -0.554873 -0.710691 0.472872 -0.572247 -0.670019 0.370724 -0.355607 -0.857967 0.461879 -0.132423 -0.877001 0.655392 -0.258634 -0.709627 0.474485 -0.056974 -0.878418 0.762546 -0.0829616 -0.641593 0.763243 -0.0853344 -0.640452 0.969395 -0.100116 -0.224167 0.969534 -0.102935 -0.22228 -0.112852 0.0265651 -0.993257 -0.100771 0.0277653 -0.994522 0.355952 0.02501 -0.93417 0.242783 0.0130956 -0.969992 0.475978 0.0242716 -0.879122 0.67824 0.0199367 -0.73457 0.767179 0.0245169 -0.640964 0.840455 0.0149176 -0.541675 0.945592 0.00883999 -0.325234 0.975277 0.0115315 -0.220685 0.994261 0.00293013 -0.106944 -0.311449 -0.768929 -0.558344 -0.0453806 -0.995653 -0.0813354 -0.152543 -0.9822 -0.10961 -0.113839 -0.982212 -0.149335 -0.093672 -0.989073 -0.11384 -0.232684 -0.94628 -0.224526 -0.139465 -0.98214 -0.126297 -0.147382 -0.982204 -0.116421 -0.142488 -0.984611 -0.101184 -0.411225 -0.535678 -0.737525 -0.0889032 -0.982031 -0.166468 -0.135526 -0.960522 -0.242959 -0.226812 -0.885084 -0.406426 -0.803375 -0.156959 -0.574414 -0.805463 -0.126907 -0.5789 -0.772989 -0.155522 -0.615062 -0.732252 -0.155237 -0.663105 -0.732335 -0.15474 -0.663129 -0.628002 -0.154598 -0.762701 -0.627606 -0.157061 -0.762524 -0.481437 -0.15693 -0.862318 -0.480415 -0.16379 -0.861611 -0.412905 -0.531421 -0.739663 -0.538219 -0.531704 -0.653919 -0.538831 -0.530416 -0.654462 -0.628229 -0.530769 -0.56887 -0.628032 -0.531141 -0.56874 -0.687979 -0.531344 -0.494326 -0.687357 -0.532442 -0.49401 -0.267305 -0.830889 -0.488029 -0.353224 -0.831289 -0.429175 -0.353671 -0.830869 -0.42962 -0.412212 -0.831112 -0.373274 -0.411992 -0.831294 -0.373112 -0.451222 -0.831432 -0.324223 -0.450703 -0.83183 -0.323922 0.957454 0.257122 -0.131033 0.256758 0.347946 -0.90167 0.30218 0.243624 -0.921594 0.659308 0.745776 -0.0955557 -0.123559 0.8642 -0.487741 -0.191272 0.845604 -0.498366 0.0578397 0.98649 -0.153274 -0.0455553 0.9831 -0.177309 0.324843 0.924324 -0.200255 0.42262 0.889271 -0.174899 0.127276 0.822976 -0.553635 0.207547 0.813998 -0.542523 0.341052 0.725201 -0.598137 0.770806 0.626705 -0.114452 0.88459 0.456434 -0.0957538 0.83541 0.549589 -0.00646527 0.742038 0.612722 -0.27194 0.720968 0.597636 -0.350766 0.639071 0.601889 -0.478871 0.610456 0.576883 -0.542724 0.382424 0.523374 -0.761467 -0.0820124 0.0921152 -0.992365 -0.11281 0.0566713 -0.991999 0.355146 0.0946198 -0.93001 -0.319237 0.571342 -0.75608 -0.210834 0.629497 -0.747852 -0.143694 0.472352 -0.869618 -0.0908389 0.44957 -0.888614 -0.0701174 0.489497 -0.869181 0.0530324 0.37429 -0.925794 0.993615 0.0391689 -0.105811 0.980564 0.194429 -0.0263107 0.921995 0.231218 -0.310585 0.912022 0.220693 -0.345703 0.820509 0.231992 -0.522441 0.805033 0.220025 -0.550918 0.594854 0.80085 -0.0691969 0.576932 0.814393 0.0625568 0.578434 0.761806 -0.291659 0.560259 0.794535 -0.234144 0.404363 0.790528 -0.459952 0.364939 0.633636 -0.682147 0.406683 0.589854 -0.697625 -0.377618 0.220612 -0.899297 -0.402257 0.185075 -0.896625 -0.173739 0.352376 -0.91959 -0.323003 0.20166 -0.924663 -0.188406 0.19709 -0.962112 -0.159157 0.20517 -0.965699 -0.167109 0.147713 -0.974811 -0.130621 0.107117 -0.985629 0.321262 0.22857 -0.918992 0.34742 0.103626 -0.931966 0.67531 0.114279 -0.728627 0.561378 0.21263 -0.799777 0.617506 0.296374 -0.728594 0.546883 0.461392 -0.698596 0.226165 0.363342 -0.903788 0.149833 0.470447 -0.869614 0.150132 0.578633 -0.801651 0.123151 0.602611 -0.788476 0.144793 0.680001 -0.718773 -0.0308517 0.633869 -0.772825 -0.140396 0.67617 -0.723245 0.0431734 0.855462 -0.516062 -0.0384974 0.848943 -0.527081 0.246172 0.955002 -0.165441 0.138594 0.971912 -0.190208 -0.917038 -0.396225 -0.0452552 -0.477652 -0.877899 -0.0337799 -0.635395 -0.712907 -0.296709 -0.601799 -0.765765 -0.22681 -0.415568 -0.899291 -0.136306 -0.342435 -0.938735 -0.0389299 -0.831344 -0.54393 -0.11405 -0.911092 -0.339421 -0.233893 -0.954702 -0.258226 -0.147861 -0.104006 -0.550673 0.828217 -0.981291 -0.0487665 -0.186251 -0.847428 -0.157012 -0.507162 -0.84759 -0.163641 -0.50479 -0.874659 -0.0882024 -0.476647 -0.874852 -0.0891436 -0.476117 -0.884096 -0.435891 0.168443 -0.959361 -0.189749 -0.208858 -0.967578 -0.153403 0.200651 -0.992395 -0.123029 -0.00391095 -0.997746 0.0246788 -0.0623952 -0.645658 -0.755693 0.109792 -0.719256 -0.693955 -0.0331353 -0.66907 -0.733241 -0.121256 -0.605585 -0.795291 -0.0279327 -0.547105 -0.827229 -0.127936 -0.688796 -0.694407 -0.208228 -0.627975 -0.772459 -0.0946263 -0.776784 -0.562378 -0.283439 -0.845533 -0.50848 -0.162854 -0.91339 -0.110441 -0.391818 -0.948071 -0.0589616 -0.312546 -0.898052 -0.00635274 -0.439844 -0.930226 0.00736749 -0.366913 -0.8944 -0.0734948 -0.441188 -0.886117 -0.312683 -0.342092 -0.853226 -0.337418 -0.397687 -0.838302 -0.42231 -0.344823 -0.776137 -0.443784 -0.447959 -0.713968 -0.60909 -0.345338 -0.735391 -0.532236 -0.419435 -0.541145 -0.776086 -0.323809 -0.50059 -0.830244 -0.245162 -0.273642 -0.950275 -0.148651 -0.194781 -0.97987 -0.0437519 -0.495213 0.21991 -0.840478 -0.608735 0.578557 -0.542876 -0.773764 0.298467 -0.558754 -0.635448 0.629501 -0.447141 -0.272365 0.941652 -0.197757 -0.483883 0.807104 -0.338291 -0.0726752 0.996005 -0.051894 -0.147328 0.983892 -0.101252 -0.13335 0.983907 -0.118934 -0.135485 0.983348 -0.121126 -0.113456 0.984481 -0.133887 -0.115693 0.983797 -0.13696 -0.0972254 0.983859 -0.150232 -0.0692444 0.990685 -0.117251 -0.083669 0.983653 -0.159455 -0.791402 0.233054 -0.565127 -0.725797 0.232933 -0.647273 -0.725802 0.232893 -0.647281 -0.6731 0.233324 -0.70178 -0.644631 0.0704602 -0.76124 -0.618389 0.228502 -0.751919 -0.494798 0.228224 -0.838504 -0.608839 0.578334 -0.542997 -0.527564 0.578048 -0.622525 -0.52854 0.575498 -0.624057 -0.415728 0.575258 -0.70445 -0.41714 0.570037 -0.70785 -0.570219 0.723875 -0.3884 -0.663699 0.578774 -0.473839 -0.430399 0.848704 -0.307341 -0.394861 0.84857 -0.352157 -0.394964 0.848476 -0.352267 -0.342327 0.848296 -0.403988 -0.3431 0.847458 -0.40509 -0.269955 0.847277 -0.457435 -0.271338 0.845242 -0.460371 -0.929342 0.0427818 -0.366732 -0.928427 0.0429054 -0.369029 -0.981598 0.0431014 -0.186031 -0.981126 0.0431785 -0.188487 -0.997158 0.0424881 -0.0622179 -0.997117 0.0425109 -0.0628571 -0.840327 0.297947 -0.452855 -0.84957 0.171707 -0.498747 -0.886512 0.149873 -0.437762 -0.887082 0.232774 -0.398624 -0.921463 0.135465 -0.364082 -0.913676 0.0817564 -0.398136 -0.926911 0.0699381 -0.368707 -0.901639 0.431747 -0.0253334 -0.723831 0.549759 0.416934 -0.419606 0.593756 0.686574 -0.992 0.109852 -0.062204 -0.688069 0.724625 -0.0384702 -0.620273 0.770754 -0.1456 -0.520899 0.85203 -0.0520573 -0.402373 0.915165 0.0238421 -0.0893495 0.995666 -0.0258166 -0.53504 0.804967 -0.256438 -0.320196 0.939404 -0.12245 -0.454265 0.876234 -0.1608 -0.080251 0.996773 -0.00171538 -0.345638 0.935881 -0.0682669 -0.962135 0.200183 -0.184992 -0.958584 0.265578 -0.10288 -0.869934 0.42103 -0.256805 -0.88616 0.353108 -0.300058 -0.841647 0.387742 -0.375882 -0.549403 0.801315 -0.236752 -0.685298 0.628505 -0.367897 -0.609744 0.72273 -0.325382 -0.589094 0.744531 -0.314074 -0.657872 0.724231 -0.206628 -0.768705 0.590547 -0.245656 -0.82777 0.542451 -0.143331 -0.673704 0.738875 0.0136693 -0.858601 0.503486 -0.096465 0.069184 -0.258199 -0.963611 0.258187 -0.0691872 -0.963614 0.441956 -0.0377009 -0.896244 0.194834 -0.0522044 -0.979446 0.935109 -0.250568 -0.250574 0.957586 -0.216161 -0.190535 0.871994 -0.233689 -0.430136 0.694735 -0.186185 -0.694751 0.785192 -0.143509 -0.602394 0.60079 -0.160996 -0.783027 0.189008 -0.189012 -0.963613 0.189017 -0.189015 -0.963611 0.508594 -0.508589 -0.694744 0.508583 -0.508588 -0.694753 0.684545 -0.684553 -0.25057 0.684575 -0.68454 -0.250525 0.0691832 -0.258198 -0.963612 0.160989 -0.600825 -0.783002 0.15265 -0.708031 -0.689486 0.207936 -0.776024 -0.595441 0.250565 -0.935115 -0.250553 0.250553 -0.935114 -0.250569 0.980774 0 -0.195149 0.980774 0 -0.195149 0.896825 0 -0.442385 0.896825 0 -0.442385 0.793405 0 -0.608694 0.793405 0 -0.608694 0.608731 0 -0.793377 0.608731 0 -0.793377 0.442271 0 -0.896882 0.442271 0 -0.896882 0.1951 0 -0.980783 0.1951 0 -0.980783 0 -0.965924 -0.258825 -0.0507208 -0.979522 -0.194844 0.038243 -0.792784 -0.608301 0 -0.831471 -0.555568 0 -0.608765 -0.79335 0.025604 -0.555392 -0.831195 -0.0382528 -0.258629 -0.965219 0 -0.195089 -0.980785 0.194834 0.0522044 -0.979446 0.269684 0.0482678 -0.961738 0.0691831 0.258198 -0.963612 0.0691831 0.258198 -0.963612 0.186157 0.694755 -0.694738 0.186159 0.694751 -0.694741 0.250564 0.935113 -0.250563 0.189013 0.189016 -0.963611 0.18901 0.189009 -0.963614 0.508588 0.508584 -0.694752 0.50859 0.508595 -0.694743 0.439197 0.117693 -0.890648 0.60079 0.160996 -0.783027 0.708021 0.152656 -0.689494 0.776056 0.207978 -0.595384 0.871994 0.233689 -0.430136 0.250558 0.935117 -0.250553 0.684553 0.68456 -0.250527 0.684566 0.684531 -0.250572 0.942941 0.221598 -0.24851 0.948564 0.254173 -0.18874 -0.0038093 -0.982854 -0.184346 -0.00457904 -0.980774 -0.195093 -0.0106478 -0.838302 -0.545101 -0.0115216 -0.831416 -0.555532 -0.0170738 -0.550188 -0.834866 -0.0166488 -0.555497 -0.831352 -0.020599 -0.185896 -0.982354 -0.0200617 -0.19505 -0.980588 -0.0292757 -0.982312 -0.184949 -0.0287677 -0.982776 -0.182546 -0.0865235 -0.833261 -0.546067 -0.0850482 -0.837593 -0.539634 -0.132018 -0.537589 -0.832808 -0.130065 -0.549068 -0.825595 -0.154419 -0.167183 -0.973758 -0.152901 -0.185376 -0.970699 0 0.965926 -0.25882 0 0.965926 -0.25882 0 0.793365 -0.608747 -0.0510509 0.706194 -0.706176 0 0.608765 -0.79335 0 0.258818 -0.965926 0 0.258818 -0.965926 -0.306761 -0.167736 -0.93689 -0.372569 -0.764083 -0.526658 -0.406617 -0.904951 -0.125405 -0.78009 -0.413591 -0.46947 -0.803579 -0.417705 -0.424008 -0.578707 -0.639481 -0.506125 -0.657802 -0.692792 -0.295528 -0.542373 -0.693965 -0.473545 -0.900505 -0.404443 -0.15974 -0.480666 -0.00509846 -0.876889 -0.41188 -0.00572188 -0.91122 -0.26633 -0.0960973 -0.95908 -0.36081 -0.201935 -0.910516 -0.375258 -0.0952439 -0.922014 -0.406721 -0.101023 -0.90795 -0.442247 -0.0658479 -0.894473 -0.987899 -0.0409336 -0.149599 -0.821198 -0.565275 -0.0780975 -0.808494 -0.575894 -0.121175 -0.643093 -0.741855 -0.189954 -0.658039 -0.735963 -0.159195 -0.481684 -0.860025 -0.168335 -0.355225 -0.87844 -0.319621 -0.401988 -0.773612 -0.489827 -0.71855 -0.0661119 -0.692326 -0.888687 -0.135575 -0.438013 -0.899774 -0.130544 -0.416372 -0.97713 -0.202243 -0.0656875 -0.965981 -0.226079 -0.125571 -0.891414 -0.316654 -0.324209 -0.663589 -0.254467 -0.703489 -0.514475 -0.401203 -0.75786 -0.533726 -0.417244 -0.735558 -0.323159 -0.503633 -0.8012 -0.390934 -0.620769 -0.67957 -0.28775 -0.538017 -0.792299 -0.212548 -0.81141 -0.54446 -0.246718 -0.829475 -0.5011 -0.127281 -0.969852 -0.207816 -0.163071 -0.97542 -0.148204 -0.149618 0.18919 -0.970475 -0.254316 0.20563 -0.945008 -0.177207 -0.236447 -0.955348 -0.15275 0.557813 -0.815789 -0.153265 0.548339 -0.822091 -0.100317 0.838403 -0.53574 -0.100932 0.834988 -0.540933 -0.0504934 0.961532 -0.270013 -0.0369353 0.982109 -0.184657 -0.0166899 0.995863 -0.0893247 -0.00634068 0.965906 -0.258814 -0.00973811 0.982329 -0.186911 -0.0108179 0.793318 -0.608711 -0.0134083 0.835928 -0.548675 -0.0193088 0.608652 -0.793202 -0.0177463 0.549704 -0.835171 -0.02721 0.258722 -0.965568 -0.0239392 0.189364 -0.981615 -0.496566 0.0325316 -0.867389 -0.989303 0.00542011 -0.145776 -0.988969 0.00565012 -0.148012 -0.902399 0.0158494 -0.430609 -0.89912 0.0166052 -0.437386 -0.730371 0.0250531 -0.682591 -0.721611 0.0262305 -0.691801 -0.491534 0.0318631 -0.870275 -0.481012 0.0336103 -0.876069 -0.973057 0.191846 -0.127888 -0.971308 0.194868 -0.136338 -0.896969 0.161791 -0.411425 -0.892271 0.16455 -0.420446 -0.727256 0.116526 -0.676403 -0.585325 0.789186 -0.185955 -0.256283 0.945188 -0.202333 -0.584313 0.766714 -0.265948 -0.605607 0.635616 -0.478782 -0.581355 0.686422 -0.436864 -0.536973 0.425068 -0.728682 -0.533786 0.452895 -0.714114 -0.410096 0.139873 -0.901253 -0.414511 0.169781 -0.894066 -0.456743 0.128868 -0.880215 -0.441477 0.0648201 -0.894928 -0.265855 0.918942 -0.291319 -0.348403 0.78312 -0.51511 -0.295332 0.831104 -0.471216 -0.363413 0.522709 -0.771172 -0.344399 0.556883 -0.755825 -0.340426 0.253737 -0.905388 -0.347034 0.205312 -0.915103 -0.496542 0.0409491 -0.867046 -0.45786 0.079138 -0.885495 -0.902353 0.349908 -0.251643 -0.668579 0.295222 -0.682529 -0.779414 0.438154 -0.447811 -0.798802 0.440743 -0.409465 -0.825281 0.541323 -0.160873 -0.818475 0.542936 -0.187932 -0.828322 0.559494 -0.0291365 -0.566645 0.815419 -0.118348 -0.567268 0.813762 -0.126487 -0.180168 0.98294 -0.0369862 -0.180323 0.982869 -0.0381146 0 -0.980784 -0.195095 0 -0.980784 -0.195095 0 -0.831471 -0.555568 0 -0.831471 -0.555568 0 -0.555574 -0.831467 0 -0.555574 -0.831467 0 -0.195089 -0.980785 0 -0.195089 -0.980785 0.123866 -0.15683 -0.979827 0.123861 -0.156827 -0.979828 0.350309 -0.443545 -0.824955 0.350328 -0.443554 -0.824943 0.519284 -0.657471 -0.545963 0.519295 -0.657472 -0.545951 0.608477 -0.770384 -0.190432 0.608454 -0.770392 -0.190473 0.0441642 -0.1949 -0.979828 0.0441638 -0.194899 -0.979829 0.124908 -0.55123 -0.824951 0.124902 -0.551223 -0.824956 0.185147 -0.817097 -0.54596 0.185144 -0.817096 -0.545963 0.216941 -0.957426 -0.190452 0.216943 -0.957426 -0.190449 -0.258077 -0.171589 -0.950765 -0.0349965 -0.982354 -0.183726 -0.0347329 -0.982565 -0.182646 -0.103506 -0.833792 -0.542289 -0.102145 -0.837307 -0.537107 -0.157922 -0.539396 -0.827111 -0.156156 -0.548697 -0.821308 -0.182008 0.256902 -0.949144 -0.151572 -0.18596 -0.970796 -0.0203791 -0.555458 -0.831295 -0.0208204 -0.550119 -0.834826 -0.0140226 -0.831389 -0.555514 -0.0131137 -0.838218 -0.545177 -0.00545942 -0.98077 -0.195093 -0.004611 -0.982933 -0.183905 -0.0249206 -0.195029 -0.980481 -0.0209077 -0.110976 -0.993603 -0.0751974 -0.186416 -0.979589 0.968638 -0.166264 -0.18465 0.968415 -0.166762 -0.185374 0.827567 -0.141319 -0.543288 0.827163 -0.141693 -0.543805 0.546996 -0.0924605 -0.832014 0.546513 -0.0926983 -0.832304 0.187679 -0.0302729 -0.981764 0.187246 -0.030396 -0.981843 0.856817 -0.478396 -0.192358 0.860722 -0.474229 -0.185106 0.726036 -0.412174 -0.55044 0.732821 -0.40927 -0.543572 0.490055 -0.273448 -0.827691 0.482453 -0.274246 -0.831883 0.175488 -0.093007 -0.980078 0.165691 -0.0924148 -0.981838 -0.584307 -0.772096 -0.249907 -0.440889 -0.175684 -0.8802 -0.40982 -0.776979 -0.477861 -0.696573 -0.514135 -0.500451 -0.569433 -0.707381 -0.418758 -0.549611 -0.445208 -0.706907 -0.339511 -0.171473 -0.92484 -0.343187 -0.158421 -0.925811 -0.379464 -0.766169 -0.518644 -0.540309 -0.703703 -0.461377 -0.470488 -0.861013 -0.193128 -0.6443 -0.754042 -0.127664 -0.334118 -0.93204 -0.140236 -0.30386 -0.933523 -0.190272 -0.426703 -0.890112 -0.160079 -0.500863 -0.855386 -0.132103 -0.392175 -0.140002 -0.909175 -0.551255 -0.426311 -0.717201 -0.349962 -0.504162 -0.789524 -0.408703 -0.613785 -0.675448 -0.319429 -0.540316 -0.778475 -0.230129 -0.811041 -0.537823 -0.265379 -0.830469 -0.489792 -0.129797 -0.96957 -0.207573 -0.166237 -0.975848 -0.141722 0.187331 0.0191775 -0.98211 0.999908 0.00051026 -0.0135821 0.982277 0.0021146 -0.187421 0.135094 0.0489739 -0.989622 0.0839213 0.0299161 -0.996023 0.433676 0.0189861 -0.900869 0.5489 0.0247918 -0.83552 0.648642 0.0185476 -0.760868 0.988048 0.00738487 -0.15397 0.97956 0.00481677 -0.201093 0.835773 0.0134944 -0.548909 0.84944 0.0152599 -0.527464 0.725175 0.0167801 -0.68836 -0.712304 -0.499048 -0.493532 -0.782768 -0.598013 -0.172205 -0.786387 -0.595265 -0.165094 -0.880004 -0.459109 -0.121701 -0.897482 -0.126943 -0.422387 -0.905471 -0.144562 -0.399029 -0.738317 -0.0624718 -0.671554 -0.745642 -0.0702318 -0.662636 -0.514442 0.00804787 -0.857488 -0.512986 0.00904832 -0.858349 -0.518721 -0.105562 -0.848402 -0.491378 -0.0412732 -0.869968 -0.684514 -0.323844 -0.653119 -0.665941 -0.248917 -0.703252 -0.796637 -0.486146 -0.359209 -0.82657 -0.342081 -0.446948 -0.863786 -0.474883 -0.168404 -0.973071 -0.204042 -0.10724 -0.973247 -0.175332 -0.148488 0.171646 0.238419 -0.955873 0.187214 0.968345 -0.165102 0.158994 0.855431 -0.492909 0.104219 0.606331 -0.788354 0.135087 0.0677883 -0.988512 0.45098 0.73299 -0.509257 0.954237 0.0320113 0.297332 0.642808 0.177968 -0.745067 0.717328 0.186308 -0.671364 0.819789 0.182833 -0.542695 0.83634 0.204352 -0.508701 0.938513 0.202721 -0.279459 0.956062 0.228467 -0.183707 0.986215 0.165416 -0.00413655 0.96965 0.23962 -0.0485843 0.924958 0.369016 -0.090995 0.869677 0.486871 -0.0813564 0.759125 0.591372 0.272046 0.654808 0.569586 0.496789 0.817527 0.514766 -0.258197 0.0102475 0.274397 -0.961562 0.0499089 0.235029 -0.970706 0.0667442 0.437602 -0.896688 0.0525081 0.226108 -0.972686 0.297754 0.781617 -0.548104 0.183202 0.970433 -0.15715 0.166031 0.846393 -0.506017 0.452358 0.725882 -0.518139 0.295801 0.525524 -0.7977 0.45047 0.370501 -0.812285 0.139733 0.175642 -0.974487 0.210602 0.117455 -0.97049 0.431246 0.160264 -0.887886 0.547901 0.13754 -0.825159 0.452064 0.373684 -0.809937 0.690489 0.502452 -0.520353 0.679131 0.506181 -0.531566 0.812081 0.551996 -0.189273 0.544716 0.822395 -0.164167 0.577488 0.808337 -0.114447 0.403905 0.897372 -0.177722 -0.990066 0.0106959 -0.140197 -0.990396 0.0161403 -0.137314 -0.992796 0.0117187 -0.119239 -0.910754 0.039672 -0.411039 -0.907758 0.0407669 -0.417509 -0.750231 0.063427 -0.658126 -0.741837 0.0651355 -0.667409 -0.529651 0.081311 -0.844309 -0.514576 0.0832596 -0.853393 0.00099748 0.985129 -0.171816 0.000299074 0.286502 -0.95808 0.00702156 0.274405 -0.961589 0.00057769 0.43858 -0.898692 -0.000171664 0.610625 -0.79192 0 0.98714 -0.159856 0.000535306 0.60965 -0.79267 0.00024193 0.866452 -0.49926 -0.00700373 0.860397 -0.509577 0.00614504 0.986195 -0.165474 0 0.985112 -0.171913 -0.22892 0.969268 -0.0900815 -0.967427 0.212984 -0.136832 -0.973881 0.198968 -0.109397 -0.892032 0.209985 -0.400232 -0.900936 0.202632 -0.383739 -0.746636 0.191929 -0.636944 -0.562183 0.809423 -0.16966 -0.466692 0.167595 -0.868395 -0.485122 0.243234 -0.839937 -0.450598 0.276679 -0.84877 -0.370739 0.630994 -0.681469 -0.33682 0.759909 -0.555958 -0.312029 0.821764 -0.476803 -0.323972 0.857646 -0.399356 -0.265782 0.926567 -0.266145 -0.229018 0.969682 -0.0852493 -0.554594 0.830289 -0.0551886 -0.561647 0.809093 -0.172978 -0.592719 0.676869 -0.4365 -0.571539 0.720193 -0.393276 -0.539912 0.502658 -0.675151 -0.435619 0.829013 -0.350677 -0.392561 0.239984 -0.887864 -0.380901 0.329999 -0.863722 -0.829438 0.548919 -0.103538 -0.821925 0.553679 -0.133717 -0.787916 0.481893 -0.383364 -0.775589 0.481906 -0.407712 -0.672791 0.372073 -0.639464 -0.918545 0.386529 -0.0828883 -0.479448 0.178351 -0.859256 -0.52995 0.131757 -0.837731 -0.0284493 0.286394 -0.957689 -0.161984 0.300945 -0.939784 -0.218771 -0.294038 -0.93042 -0.267265 0.330032 -0.905344 -0.0395747 0.985289 -0.166254 -0.0388588 0.985946 -0.162482 -0.117115 0.862197 -0.492849 -0.115227 0.868493 -0.482122 -0.181773 0.617105 -0.765597 -0.159464 0.764166 -0.624997 -0.180038 0.632625 -0.753241 -0.00778609 0.985101 -0.171803 -0.007789 0.985413 -0.170004 -0.0229625 0.860198 -0.509442 -0.0230352 0.863136 -0.504446 -0.0355393 0.610254 -0.791408 -0.035805 0.618728 -0.784789 -0.0442611 0.0592314 -0.997263 -0.0847767 0.30124 -0.949772 0.64491 0.758441 -0.0941175 0.644015 0.132849 -0.75339 0.506373 0.493862 -0.706885 -0.246844 0.843858 -0.476416 -0.159192 0.868781 -0.468911 0.124907 0.814278 -0.566878 0.142809 0.755671 -0.639192 0.192889 0.886722 -0.42014 0.408919 0.896247 -0.171835 0.291555 0.936944 -0.192694 -0.0720685 0.982909 -0.169398 0.0538223 0.987277 -0.149627 0.109069 0.977438 -0.180882 0.755427 0.644832 -0.116285 0.349895 0.621818 -0.700654 0.324121 0.563789 -0.759663 0.567981 0.607487 -0.5553 0.609022 0.63447 -0.475963 0.691886 0.623413 -0.364211 0.724764 0.635628 -0.265884 0.835081 0.550103 -0.00512081 0.164441 0.10531 -0.980749 0.164823 0.105613 -0.980652 -0.192171 0.0663393 -0.979117 -0.160068 0.104605 -0.981548 -0.389796 0.571441 -0.72216 -0.275893 0.634744 -0.721792 -0.225331 0.487508 -0.843541 -0.172732 0.46536 -0.868104 -0.147194 0.511508 -0.846577 -0.0256725 0.40005 -0.916134 -0.01426 0.424018 -0.905542 0.0591123 0.321647 -0.945013 0.0720319 0.340975 -0.937309 -0.455922 0.224271 -0.8613 -0.47252 0.199417 -0.858463 -0.294965 0.318499 -0.900863 -0.391329 0.220635 -0.89341 -0.280968 0.207059 -0.937114 -0.233863 0.219202 -0.947237 -0.244615 0.168055 -0.954946 -0.213387 0.123792 -0.969093 0.1249 0.222127 -0.966985 0.13698 0.235263 -0.962231 0.968959 0.23702 -0.0702898 0.905698 0.40942 -0.10994 0.876053 0.47298 -0.0939208 0.992504 0.0571796 -0.108014 0.981532 0.191126 -0.00813372 0.914818 0.248502 -0.318362 0.900835 0.236252 -0.364255 0.803164 0.254802 -0.53852 0.783344 0.240739 -0.573076 0.521508 0.240341 -0.818697 0.580061 0.324621 -0.747094 0.203778 0.714086 -0.669743 0.215723 0.746861 -0.629017 0.351308 0.787932 -0.505714 0.362787 0.816237 -0.449602 0.535816 0.809301 -0.240693 0.545539 0.787764 -0.286033 0.577679 0.816041 0.0190823 0.603103 0.794373 -0.0723765 0.234495 0.958653 -0.161231 -0.094513 0.857428 -0.50585 -0.000467796 0.866168 -0.499753 -0.205284 0.688436 -0.69564 -0.105669 0.650907 -0.751767 0.0781364 0.700296 -0.709563 0.0533149 0.631067 -0.773894 0.165763 0.526242 -0.834021 0.179235 0.555356 -0.812068 0.277331 0.418575 -0.864802 0.292031 0.442653 -0.847807 0.363189 0.282908 -0.887726 0.376701 0.299838 -0.876467 0.414686 0.123644 -0.901525 0.417289 0.12614 -0.899977 -0.513682 0.224321 -0.828137 -0.787031 0.244359 -0.566455 -0.787374 0.242166 -0.56692 -0.659231 0.583344 -0.474472 -0.659967 0.581935 -0.47518 -0.429638 0.848402 -0.309233 -0.430277 0.847873 -0.309795 -0.216164 0.963877 -0.155607 -0.148774 0.983511 -0.102825 -0.0715461 0.996107 -0.0515078 -0.136181 0.98345 -0.119498 -0.135858 0.983535 -0.119167 -0.399522 0.847025 -0.350615 -0.398665 0.847807 -0.349699 -0.61237 0.579804 -0.53743 -0.611422 0.58183 -0.536318 -0.729853 0.238741 -0.64056 -0.729407 0.242101 -0.639806 -0.122031 0.983315 -0.13491 -0.121619 0.983439 -0.134376 -0.35798 0.845661 -0.395864 -0.35677 0.846937 -0.394223 -0.548177 0.57617 -0.606243 -0.546789 0.579665 -0.60416 -0.652273 0.232653 -0.721397 -0.651666 0.238655 -0.719983 -0.103302 0.983068 -0.151349 -0.102683 0.983298 -0.150268 -0.302781 0.843457 -0.443739 -0.301196 0.84555 -0.440825 -0.462837 0.570566 -0.678408 -0.461164 0.576012 -0.674936 -0.563207 0.00771701 -0.82628 -0.571677 0.232961 -0.786711 -0.174083 0.0429774 -0.983793 -0.19223 0.041806 -0.980459 -0.180485 0.0442479 -0.982582 0.164775 0.0431116 -0.985389 0.179512 0.0438095 -0.98278 0.418909 0.0397094 -0.907159 0.429766 0.0401689 -0.902046 0.647311 0.0333639 -0.761496 0.653887 0.0336161 -0.755845 0.82564 0.0247179 -0.563655 0.828762 0.0248288 -0.55905 0.941123 0.01482 -0.337739 0.973195 0.016086 -0.229419 0.993877 0.0048795 -0.110386 -0.987267 0.146001 -0.0631438 -0.442465 0.881865 -0.162907 -0.434466 0.899628 -0.0436863 -0.755198 0.607511 -0.246182 -0.814981 0.56064 -0.146591 -0.856539 0.44756 -0.256965 -0.921718 0.102035 -0.374199 -0.908699 0.114942 -0.401316 -0.949632 0.251672 -0.18671 -0.951966 0.289137 -0.100801 -0.508942 0.596054 0.621045 -0.722413 0.560238 0.405282 -0.642048 0.76123 -0.0911203 -0.675357 0.736524 -0.0377587 -0.660385 0.750843 0.0112295 -0.844437 0.527276 -0.0943714 -0.888241 0.45861 -0.0265434 -0.642019 0.710408 -0.288326 -0.713085 0.582421 -0.390251 -0.467626 0.847657 -0.250607 -0.879396 0.170991 -0.444326 -0.842599 0.196741 -0.501318 -0.840153 0.244168 -0.484279 -0.914587 0.161454 -0.37076 -0.878092 0.263531 -0.399382 -0.875396 0.375745 -0.304135 -0.830571 0.409334 -0.377622 -0.646187 0.734265 -0.208079 -0.606133 0.747555 -0.271594 -0.426415 0.885103 -0.186446 -0.264063 0.961068 -0.0813542 -0.440171 0.883873 -0.158173 -0.120117 0.992495 0.0229268 0.428348 -0.0408984 -0.902688 0.178119 -0.0805932 -0.980703 0.637115 -0.764894 -0.094983 -0.228894 -0.761786 -0.606044 0.0823655 -0.736232 -0.671699 0.41198 -0.577125 -0.705123 0.650389 -0.0695883 -0.756407 0.373043 -0.58618 -0.719189 0.567408 -0.642804 -0.514637 0.66725 -0.500642 -0.551484 0.833974 -0.494907 -0.244038 0.823593 -0.526198 -0.211682 0.505508 -0.444209 -0.739689 0.693848 -0.483493 -0.533676 0.771839 -0.303402 -0.55876 0.923664 -0.303403 -0.234075 0.921263 -0.31922 -0.2222 0.431408 -0.890734 -0.143105 0.561416 -0.827305 -0.019465 0.360576 -0.869039 -0.338758 0.458804 -0.850274 -0.257939 0.251055 -0.814727 -0.522677 -0.0147183 -0.951829 -0.306276 0.10459 -0.969755 -0.220538 -0.103236 -0.875716 -0.471661 -0.00192234 -0.913868 -0.406006 -0.227524 -0.7193 -0.656384 -0.0501893 -0.789462 -0.611745 -0.350175 -0.151847 -0.924294 -0.262054 -0.127905 -0.95654 -0.376242 -0.217977 -0.900515 -0.376056 -0.212087 -0.901998 -0.445857 -0.144506 -0.883363 0.0479169 -0.292353 -0.955109 0.82355 -0.0870247 -0.560528 0.655334 -0.0651781 -0.752521 0.615363 -0.258736 -0.74457 0.610732 -0.257841 -0.748682 0.421814 -0.127352 -0.897694 0.179523 -0.0804263 -0.980461 0.0836747 -0.300648 -0.950058 -0.174064 0.0289332 -0.984309 0.107785 -0.981039 -0.161073 0.248567 -0.950408 0.18692 0.236711 -0.970139 -0.0528931 -0.339867 -0.524123 -0.780888 -0.356291 -0.550445 -0.755027 -0.229298 -0.527158 -0.818246 -0.245104 -0.561573 -0.790291 -0.11203 -0.510253 -0.852697 -0.12391 -0.547686 -0.827458 -0.0234215 -0.485904 -0.873699 0.0614278 -0.5529 -0.83098 0.184259 -0.750609 -0.634535 0.344572 -0.818029 -0.460542 0.524802 -0.660557 -0.536887 0.660741 -0.669219 -0.339951 0.654517 -0.734746 -0.178203 0.724256 -0.679779 -0.115558 -0.194308 -0.0014783 -0.98094 -0.152816 -0.0505382 -0.986962 -0.247411 -0.0886559 -0.964846 -0.21098 -0.245259 -0.946222 -0.064317 -0.400073 -0.914223 0.208196 -0.459863 -0.863238 0.259861 -0.404778 -0.876714 0.426435 -0.582826 -0.691713 0.323708 -0.363417 -0.873579 0.531319 -0.433038 -0.728133 0.603715 -0.266377 -0.75138 0.78302 -0.293147 -0.548585 0.826052 -0.0839447 -0.557307 0.967299 -0.102794 -0.231876 0.967201 -0.100649 -0.23322 -0.994261 0.0859881 -0.0636523 -0.977239 0.0934211 -0.190462 -0.996114 0.0857073 -0.0202738 -0.923358 0.0851217 -0.374386 -0.971846 0.0961391 -0.215113 -0.925593 0.0577776 -0.374085 -0.985394 0.0849426 -0.147589 -0.681787 -0.124597 -0.720862 -0.0502534 -0.995559 -0.0796014 -0.0989306 -0.981493 -0.163961 -0.167192 -0.973512 -0.155951 -0.798375 -0.120939 -0.58989 -0.79856 -0.119696 -0.589894 -0.691705 -0.510239 -0.511079 -0.692109 -0.50949 -0.511277 -0.45592 -0.823806 -0.336868 -0.456263 -0.823535 -0.337067 -0.734422 -0.124414 -0.667192 -0.734947 -0.120898 -0.667261 -0.635729 -0.512159 -0.57753 -0.636784 -0.5101 -0.57819 -0.418885 -0.824452 -0.380544 -0.419766 -0.823709 -0.381182 -0.142172 -0.981378 -0.129168 -0.154434 -0.981391 -0.114111 -0.154788 -0.98131 -0.11433 -0.103702 -0.986792 -0.124452 -0.124491 -0.981574 -0.144963 -0.369052 -0.824325 -0.429288 -0.367448 -0.825817 -0.427795 -0.560066 -0.51199 -0.6513 -0.557855 -0.516659 -0.649509 -0.651847 0.0331015 -0.757628 -0.63137 -0.132351 -0.764104 -0.527765 -0.144086 -0.83708 -0.529551 -0.132096 -0.83793 -0.454239 -0.523967 -0.720504 -0.45738 -0.516447 -0.723938 -0.344787 -0.763196 -0.546493 -0.29713 -0.825499 -0.47986 -0.251252 -0.882363 -0.397878 -0.150033 -0.959661 -0.237781 -0.844531 -0.119699 -0.521957 -0.845941 -0.144738 -0.513259 -0.870661 -0.0386554 -0.490363 -0.872833 -0.0461453 -0.485832 -0.60418 -0.793873 -0.0687874 -0.595842 -0.798787 -0.0831351 -0.715791 -0.697769 0.0275964 -0.745652 -0.664508 -0.0493315 -0.698079 -0.711708 -0.0784662 -0.802312 -0.584163 -0.122673 -0.845548 -0.532181 -0.0427994 -0.912766 -0.399427 -0.0855298 -0.93553 -0.351302 -0.0370156 -0.996007 0.0869497 -0.0202668 -0.967052 -0.253997 0.0172099 -0.960837 -0.156923 -0.228403 -0.999809 -0.0165298 -0.0104005 -0.993783 -0.0295595 -0.107338 -0.967169 0.208247 -0.14566 -0.319137 -0.943347 -0.0908239 -0.612464 -0.754514 -0.235791 -0.646432 -0.697408 -0.309431 -0.925648 0.0569022 -0.374083 -0.927179 0.0577499 -0.370141 -0.925008 -0.0197341 -0.379435 -0.935622 -0.0307162 -0.351664 -0.913786 -0.0640347 -0.401117 -0.892303 -0.0295399 -0.45047 -0.896567 -0.273447 -0.348418 -0.860642 -0.302222 -0.409825 -0.84865 -0.392218 -0.354905 -0.781541 -0.41637 -0.464574 -0.723657 -0.589369 -0.359115 -0.74154 -0.50917 -0.43688 -0.546533 -0.765977 -0.3385 -0.508832 -0.821695 -0.256726 -0.276597 -0.948328 -0.155461 -0.199975 -0.978705 -0.046336 -0.920178 -0.303219 -0.247652 -0.936671 -0.274073 -0.218016 -0.837099 -0.533324 -0.121777 -0.856455 -0.483366 -0.181226 -0.792043 -0.535419 -0.293247 -0.639768 -0.763098 -0.0915394 -0.704152 -0.676607 -0.215342 -0.466075 -0.881134 -0.0798575 -0.461186 -0.882944 -0.0878502 0.691983 -0.704896 -0.155824 0.322718 -0.808196 -0.492618 -0.470025 -0.154693 -0.868992 -0.351971 -0.142764 -0.92506 -0.356168 -0.166856 -0.919404 -0.0744497 -0.501164 -0.862144 -0.082584 -0.531443 -0.843059 -0.335712 -0.528604 -0.779664 -0.341103 -0.653693 -0.675525 -0.299429 -0.570363 -0.764871 0.156216 -0.743667 -0.650043 0.153428 -0.71515 -0.681924 0.0420789 -0.778139 -0.626681 -0.193661 -0.56662 -0.800898 -0.179727 -0.529306 -0.829176 -0.398815 -0.178902 -0.899411 -0.410803 -0.237031 -0.880373 0.568894 -0.822129 0.0215151 0.429465 -0.877734 -0.212469 0.295091 -0.944464 -0.144601 0.325556 -0.915455 -0.236548 0.131156 -0.982707 -0.130713 0.159736 -0.960849 -0.226393 -0.0320239 -0.992324 -0.119449 -0.00877826 -0.977346 -0.211463 0.438094 -0.851072 -0.289395 0.285002 -0.813555 -0.506855 0.148308 -0.887132 -0.437036 0.132415 -0.787099 -0.602447 -0.0888166 -0.868324 -0.48798 -0.0624234 -0.829924 -0.554373 -0.23023 -0.857329 -0.460413 -0.206279 -0.828624 -0.520415 0.878134 -0.426638 -0.216472 0.95168 -0.300623 -0.0627029 0.810664 -0.558037 -0.177255 0.789507 -0.577568 -0.207592 0.588124 -0.723554 -0.361357 0.471895 -0.73272 -0.490344 0.454146 -0.69743 -0.554386 0.318968 -0.657989 -0.682136 0.305943 -0.621653 -0.721073 0.136311 -0.542529 -0.828904 0.0328458 -0.285616 -0.957781 0.0335629 -0.437881 -0.898406 -0.221017 -0.225966 -0.948731 -0.284305 -0.109273 -0.952486 0.613748 -0.561964 -0.554535 0.651725 -0.540756 -0.531824 0.447101 -0.501661 -0.740565 0.482197 -0.489244 -0.726723 0.247137 -0.406259 -0.879703 0.275448 -0.401208 -0.873591 0.032845 -0.285617 -0.957781 0.0527057 -0.285122 -0.957041 -0.258231 -0.100771 -0.960813 -0.211186 -0.00507775 -0.977433 0.965215 -0.109333 -0.237501 0.966721 -0.104029 -0.23373 0.817536 -0.0950738 -0.567975 0.82286 -0.0887563 -0.56127 0.639924 -0.0730287 -0.76496 0.645528 -0.0681632 -0.760689 0.411871 -0.045318 -0.910115 0.416681 -0.0421992 -0.908073 0.157005 -0.0148715 -0.987486 0.160236 -0.0132845 -0.986989 -0.206205 0.0269221 -0.978138 -0.113932 -0.0797301 -0.990284 0.123586 -0.158763 -0.979551 0.113266 -0.161315 -0.980382 0.367965 -0.234697 -0.899733 0.354084 -0.240224 -0.903835 0.588865 -0.293887 -0.752907 0.572771 -0.303359 -0.761516 0.763332 -0.330375 -0.555137 0.747365 -0.343695 -0.568611 0.870783 -0.34417 -0.351119 0.770906 -0.555023 -0.312497 0.735186 -0.584363 -0.343542 0.596258 -0.751722 -0.281762 0.710175 -0.700867 -0.06661 0.621584 -0.774095 -0.120042 0.670033 -0.741741 -0.0295994 -0.125596 -0.98195 -0.141423 -0.106733 -0.981932 -0.156263 -0.106165 -0.982103 -0.155569 -0.315243 -0.829313 -0.46137 -0.313602 -0.830983 -0.459478 -0.479916 -0.525894 -0.702223 -0.477837 -0.530559 -0.700128 -0.55816 -0.147077 -0.816594 -0.556974 -0.154407 -0.81605 -0.658788 -0.147169 -0.737793 -0.659619 -0.142142 -0.738037 -0.566459 -0.526037 -0.634358 -0.567878 -0.523173 -0.635456 -0.372091 -0.829407 -0.416693 -0.373237 -0.828379 -0.417712 -0.122382 -0.982973 -0.137068 -0.133832 -0.981908 -0.133959 -0.147735 -0.981658 -0.120504 -0.147414 -0.981736 -0.120265 -0.435992 -0.826732 -0.355563 -0.435014 -0.827551 -0.354856 -0.662335 -0.519264 -0.540071 -0.660961 -0.521967 -0.539149 -0.767738 -0.136931 -0.625962 -0.767081 -0.141696 -0.625707 0.99369 0.014076 -0.111274 -0.222821 0.100892 -0.969624 -0.206166 0.103005 -0.97308 0.146924 0.102914 -0.983779 0.160573 0.103473 -0.981585 0.408449 0.0949939 -0.907825 0.418497 0.0951718 -0.903218 0.643567 0.0796886 -0.76123 0.649653 0.0796265 -0.756049 0.826223 0.0586804 -0.560279 0.829093 0.0585341 -0.556038 0.941097 0.0352451 -0.336295 0.9735 0.0297192 -0.22675 0.996885 0.00658323 -0.0785939 -0.822197 -0.413568 -0.391093 -0.858262 -0.0567938 -0.510059 -0.614343 -0.724904 -0.311604 -0.590571 -0.769381 -0.243471 -0.865414 -0.102592 -0.490443 -0.840402 -0.109939 -0.530696 -0.834166 -0.1374 -0.534123 -0.676374 -0.705361 -0.212095 -0.731413 -0.640315 -0.234589 -0.593615 -0.790756 -0.149417 -0.414023 -0.909998 0.0220969 -0.44016 -0.896608 -0.0485158 -0.382063 -0.913387 -0.140546 -0.325509 -0.944437 -0.0456256 -0.860882 -0.191076 -0.471564 -0.815398 -0.428673 -0.389057 -0.764679 -0.443179 -0.467824 -0.723441 -0.576656 -0.379606 -0.732297 -0.520129 -0.439554 -0.529186 -0.778556 -0.337361 -0.500433 -0.82592 -0.259659 -0.255545 -0.954722 -0.152325 -0.195171 -0.9795 -0.0498804 -0.0720477 0.986385 -0.147834 0.273672 0.946763 -0.16954 0.403217 0.902348 -0.152265 0.0402889 0.877658 -0.477591 0.139932 0.869714 -0.473303 0.245731 0.800439 -0.54673 0.0997031 0.982256 -0.15885 0.640662 0.212191 -0.737921 0.572521 0.416665 -0.706124 0.517542 0.672195 -0.529437 0.585146 0.689334 -0.427111 0.65111 0.670597 -0.355465 0.712702 0.66364 -0.227239 0.819664 0.570961 -0.0464164 0.809074 0.584634 -0.0600151 0.646523 0.75701 -0.0945747 0.146574 0.226569 -0.962903 0.129245 0.214248 -0.968191 -0.222839 0.185492 -0.957045 -0.195149 0.218421 -0.956143 0.032308 0.449693 -0.892599 -0.0722695 0.511768 -0.856078 -0.179121 0.608319 -0.773216 -0.392003 0.410848 -0.823127 0.0976622 0.357573 -0.928765 0.0812764 0.341647 -0.936307 -0.257135 0.242537 -0.935445 -0.28339 0.294046 -0.912813 -0.263323 0.351605 -0.898351 -0.316799 0.335585 -0.887142 -0.403198 0.341859 -0.848861 -0.210025 0.564581 -0.798209 -0.26727 0.588647 -0.76293 0.0519651 0.990547 -0.12695 -0.242318 0.874101 -0.420987 -0.162108 0.897 -0.411232 -0.394122 0.649153 -0.650591 -0.284197 0.71071 -0.643524 -0.480501 0.351881 -0.803305 -0.50245 0.320331 -0.803076 0.531648 0.445697 -0.720212 0.754309 0.406709 -0.51537 0.711731 0.449378 -0.539906 0.878511 0.371062 -0.300885 0.840906 0.424686 -0.335437 0.947521 0.311434 -0.0721971 0.906802 0.404698 -0.118022 0.610336 0.245181 -0.753244 0.822044 0.185163 -0.538478 0.793349 0.228987 -0.564059 0.936471 0.148755 -0.31764 0.9169 0.192881 -0.349416 0.989106 0.111432 -0.096186 0.96483 0.200215 -0.170345 0.614595 0.785626 -0.0711642 0.576973 0.816522 -0.0198536 0.510643 0.822884 -0.249209 0.510061 0.829173 -0.228712 0.337544 0.85299 -0.398087 0.244475 0.75299 -0.610932 0.329552 0.665351 -0.669853 0.20846 0.672838 -0.709812 0.470315 0.580599 -0.664612 0.231983 0.962451 -0.140972 -0.10713 0.887441 -0.448299 -0.0115417 0.897043 -0.441792 -0.217644 0.753046 -0.620929 -0.134257 0.721758 -0.679 0.0535318 0.770562 -0.635113 0.017352 0.712161 -0.701801 0.0468943 0.686754 -0.725375 0.0329359 0.608292 -0.79303 0.155987 0.435638 -0.886503 0.248608 0.551311 -0.796398 0.320659 0.393052 -0.861794 0.34183 0.414515 -0.843404 0.383875 0.223796 -0.895855 0.406357 0.241803 -0.881139 -0.777236 -0.609524 -0.15616 -0.924198 0.0748977 -0.374498 -0.920112 0.0724683 -0.384893 -0.928591 -0.0266464 -0.370147 -0.893405 -0.000544536 -0.449251 -0.959245 -0.20286 -0.196714 -0.951118 -0.263406 -0.161222 -0.948191 -0.118407 -0.29481 -0.996597 -0.0607496 -0.0557197 -0.997618 -0.0594778 -0.0349403 -0.988342 0.0833392 -0.127415 -0.670735 -0.741418 -0.0203494 -0.744868 -0.654656 -0.128831 -0.8101 -0.586197 -0.0105795 -0.93111 -0.364554 0.0115846 -0.864695 -0.486451 -0.125171 -0.920033 -0.320384 -0.225596 -0.719621 -0.689583 -0.0813718 -0.921598 -0.167158 -0.350306 -0.881869 -0.373296 -0.288023 -0.889607 -0.0612801 -0.452597 -0.89606 -0.167627 -0.411069 -0.881725 -0.0186513 -0.471396 -0.868516 -0.0507 -0.493062 -0.735096 0.367478 -0.569732 -0.711663 0.430871 -0.554876 -0.596453 0.657504 -0.46036 -0.559249 0.706477 -0.433741 -0.379677 0.877065 -0.294282 -0.422118 0.846617 -0.324124 -0.298575 0.925874 -0.231541 -0.129644 0.986451 -0.100535 -0.127555 0.986875 -0.0990351 -0.645062 0.368315 -0.669506 -0.646634 0.36081 -0.672072 -0.522126 0.658553 -0.541934 -0.524413 0.654181 -0.545012 -0.33261 0.877597 -0.345244 -0.334374 0.876051 -0.347461 -0.110932 0.987137 -0.115128 -0.112409 0.986759 -0.116922 -0.0981511 0.986525 -0.130901 -0.0974231 0.986748 -0.129759 -0.291506 0.873938 -0.388918 -0.289579 0.875972 -0.385767 -0.456499 0.648495 -0.60915 -0.454136 0.654042 -0.604971 -0.561404 0.351406 -0.749226 -0.559921 0.360704 -0.74591 -0.913549 0.157506 -0.374992 -0.914444 0.157548 -0.372788 -0.977074 0.170116 -0.128013 -0.977229 0.170087 -0.126861 -0.1341 0.986956 -0.0890776 -0.15158 0.986529 -0.0615224 -0.348093 0.924567 -0.154944 -0.477007 0.845707 -0.239257 -0.803406 0.540954 -0.248812 -0.826597 0.478504 -0.296262 -0.779027 0.509871 -0.364895 -0.518356 0.819757 -0.243525 -0.782699 0.431445 -0.448595 -0.823338 0.318103 -0.470027 -0.848 0.301687 -0.435754 -0.837969 0.380284 -0.391397 -0.887497 0.276726 -0.368471 -0.886042 0.23657 -0.398704 -0.901552 0.218082 -0.373691 -0.355808 0.929926 -0.0929488 -0.395995 0.917666 -0.0328109 -0.408696 0.911199 -0.0517988 -0.593166 0.801588 -0.0749062 -0.655577 0.754918 0.0178372 -0.954886 0.268052 -0.127835 -0.882262 0.468846 0.0424035 -0.888254 0.456678 -0.0495058 -0.5732 0.703518 -0.420125 -0.773019 0.614311 -0.158313 -0.759295 0.63524 -0.141211 -0.694898 0.679552 -0.235215 -0.584859 0.787078 -0.196084 -0.521575 0.803025 -0.288289 -0.618947 0.706651 -0.342855 0.940768 0.200758 -0.273224 0.759859 0.384937 -0.523868 0.481167 0.519087 -0.706419 0.969001 0.188388 -0.159836 0.15643 0.794511 -0.586755 -0.174024 0.750904 -0.63707 0.452729 0.679917 -0.576844 0.705913 0.540104 -0.45823 0.890425 0.347051 -0.294446 0.995792 0.06988 -0.0592902 0.156132 0.74355 -0.650197 0.156389 0.66738 -0.728111 0.0859602 0.668662 -0.738581 0.254769 0.578591 -0.774806 0.156225 0.584877 -0.795935 0.452632 0.679952 -0.576879 0.45357 0.59814 -0.660684 0.453578 0.598137 -0.66068 0.45349 0.527758 -0.718205 0.338207 0.549769 -0.763787 0.705815 0.540175 -0.458297 0.706732 0.474824 -0.524473 0.706722 0.47483 -0.524481 0.706635 0.418985 -0.570192 0.64907 0.44581 -0.61641 0.890372 0.347127 -0.294517 0.890849 0.304901 -0.336783 0.890855 0.304894 -0.336774 0.89081 0.26905 -0.366155 0.876092 0.283642 -0.389886 0.987565 0.120778 -0.10064 0.987647 0.105164 -0.11616 0.987647 0.105165 -0.116161 0.987641 0.092804 -0.126303 0.987636 0.0928221 -0.126332 0.758587 0.297227 -0.579829 0.156416 0.519844 -0.83982 0.0569747 -0.956838 -0.284983 0.920398 0.00607821 -0.390936 0.479705 0.400255 -0.780819 0.436732 -0.248497 -0.864589 0.324067 -0.0169997 -0.945881 0.41141 -0.234191 -0.88085 0.552439 -0.13167 -0.823088 0.521374 -0.117945 -0.845138 0.628396 -0.00139899 -0.777893 0.694443 -0.0252312 -0.719106 0.304638 -0.00496198 -0.952455 0.409607 0.0712589 -0.909475 0.384737 0.0823623 -0.919344 0.496332 0.205529 -0.843453 0.4472 0.231824 -0.863869 0.64178 0.159547 -0.750109 0.677031 0.254964 -0.690379 0.466675 0.279154 -0.839218 0.692336 0.349923 -0.631051 0.647945 0.356617 -0.673047 0.819121 -0.572231 0.0399061 0.810296 -0.58235 -0.0654867 0.796256 -0.319219 -0.513883 0.980097 -0.088262 -0.177818 0.96088 -0.223705 -0.163295 0.943622 -0.269932 -0.19161 0.994092 0.0244943 -0.10574 0.984494 0.018155 -0.174475 0.938519 0.124633 -0.321946 0.234921 -0.9692 -0.0739164 0.412742 -0.903736 -0.113605 0.460459 -0.881834 -0.101712 0.566396 -0.823312 -0.0367866 0.635818 -0.762102 -0.122212 0.765915 -0.635833 -0.0953462 0.151307 -0.827617 -0.540514 0.214772 -0.790271 -0.573886 0.33754 -0.759334 -0.556308 0.826578 -0.333228 -0.453573 0.614952 -0.544 -0.570875 0.644337 -0.588019 -0.488941 0.360711 -0.735368 -0.573691 0.33542 -0.882497 -0.329686 0.125633 -0.926802 -0.353912 0.108564 -0.987656 -0.112909 0.159098 -0.0906843 -0.983089 0.152878 -0.0820434 -0.984834 0.174664 -0.360435 -0.916286 0.196418 -0.403401 -0.893693 0.213948 -0.592225 -0.77685 0.0477097 -0.997994 -0.0416157 0.342403 -0.91006 -0.233561 0.362941 -0.862314 -0.353112 0.645659 -0.71296 -0.273518 0.632755 -0.676804 -0.37624 0.798936 -0.527074 -0.289645 0.817876 -0.519411 -0.24757 0.900516 -0.398016 -0.17508 0.892504 -0.162308 -0.420824 0.862227 -0.147126 -0.484684 0.337846 0.460614 -0.820789 0.171843 0.523749 -0.83436 0.244435 0.388324 -0.888514 0.196465 0.435359 -0.878558 0.172377 0.347472 -0.92171 0.184318 0.292398 -0.938366 0.138464 0.303714 -0.942648 0.0574851 0.259221 -0.964106 0.0117672 0.31435 -0.949234 0.136773 -0.777889 -0.613337 0.332124 -0.550241 -0.766113 0.495314 -0.477033 -0.726019 0.567687 -0.288701 -0.770963 0.625041 -0.313444 -0.714897 0.752854 -0.174282 -0.634694 0.717442 -0.160709 -0.677827 0.805 -0.0177698 -0.593008 0.769048 -0.00563539 -0.639166 0.796293 0.0587982 -0.602047 0.839382 0.073784 -0.538511 0.869001 0.241654 -0.431787 0.876144 0.244968 -0.415165 0.391254 0.8792 -0.271897 0.0645438 0.995689 -0.0666101 0.396603 0.917485 -0.0304372 0.486293 0.796286 0.359788 0.314894 0.892778 -0.322164 0.200586 0.8849 -0.420378 0.102466 0.877688 -0.468151 0.679774 0.725197 -0.109529 0.710967 0.703196 -0.0064719 0.990868 0.131882 0.0280574 0.84853 0.493563 -0.190767 0.965821 0.248095 -0.0750845 0.872369 0.447082 -0.197712 0.887102 0.422123 -0.186713 0.784512 0.546139 -0.293722 0.704579 0.621987 -0.341615 0.0214326 0.919617 -0.392231 0.547494 0.57381 0.609092 0.15667 0.967706 -0.197483 0.221287 0.968382 -0.115189 0.0373144 0.906028 -0.421569 0.0849721 0.916963 -0.38982 0.35012 0.811752 -0.467412 0.123271 0.85149 -0.509676 0.447734 0.807392 -0.384255 0.356346 0.842479 -0.404039 0.583099 0.755085 -0.299737 0.50993 0.846031 -0.155572 0.718571 0.695263 0.0162985 0.470396 0.876957 -0.0983512 0.946057 0.299263 0.124168 0.593734 0.774041 -0.219864 0.84138 0.536513 -0.0650673 0.71477 0.674828 -0.183604 0.753496 0.638216 -0.157873 0.642998 0.72475 -0.24757 0.671104 0.642996 -0.369019 0.467484 0.74776 -0.471502 0.453268 0.755098 -0.473683 0.156391 0.818284 -0.55313 -0.000266198 -0.993529 -0.113581 0.04029 -0.971685 -0.23282 0.0207361 -0.958188 -0.285386 -0.0307979 -0.83686 -0.54655 -0.0169372 -0.821446 -0.570035 0.00849246 -0.633466 -0.773724 -0.00291167 -0.60626 -0.795261 -0.00102654 -0.414703 -0.909956 -0.0022425 -0.411414 -0.911446 -0.00222815 -0.281776 -0.959478 -0.0173171 -0.0830068 -0.996399 -0.041342 -0.123103 -0.991533 0.0441724 0.314065 -0.948373 -0.00104341 0.253205 -0.967412 -8.44788e-05 0.997765 -0.0668214 -0.000281542 0.920211 -0.391423 -2.79243e-05 0.919827 -0.392325 -7.85197e-05 0.990919 -0.13446 0.0170734 0.979652 -0.199974 -0.000767435 0.998081 -0.0619118 -9.63424e-05 0.997768 -0.0667811 -0.0327495 -0.124752 -0.991647 -0.00773897 -0.972387 -0.233246 -0.0317782 0.25304 -0.966934 -0.0271164 0.290607 -0.956458 -0.0592469 0.24983 -0.966475 -0.0283863 -0.41452 -0.909597 -0.0316257 -0.281635 -0.959 -0.0326539 -0.123144 -0.991852 -0.00770496 -0.972445 -0.233007 -0.0187805 -0.821418 -0.570018 -0.0188009 -0.821749 -0.56954 -0.0254785 -0.633269 -0.773512 -0.0255201 -0.633997 -0.772914 -0.0302742 -0.392402 -0.919295 -0.116846 0.249488 -0.961303 -0.116591 0.246344 -0.962144 -0.119595 -0.124632 -0.984969 -0.119412 -0.127001 -0.984689 -0.110881 -0.392106 -0.913213 -0.110691 -0.393677 -0.91256 -0.0932527 -0.633662 -0.767969 -0.0931159 -0.634417 -0.767362 -0.0687475 -0.821512 -0.566031 -0.0686592 -0.821826 -0.565586 -0.0280499 -0.972616 -0.23072 -0.0530832 -0.939905 -0.337286 -0.0137416 -0.993525 -0.112783 -0.000957506 0.919791 -0.392406 -0.00140841 0.920214 -0.391413 -0.000602471 0.99092 -0.134455 -0.000301059 0.991015 -0.133753 -0.000526953 0.990979 -0.134016 -0.669965 0.328152 -0.66593 -0.412044 0.281372 -0.866631 -0.214216 -0.911953 -0.349933 -0.445765 -0.831888 -0.330538 -0.382613 -0.875684 -0.294594 -0.46544 -0.735759 -0.491959 -0.442998 -0.711691 -0.545205 -0.478712 -0.55239 -0.682422 -0.454426 -0.526526 -0.718517 -0.612132 -0.45707 -0.645276 -0.637708 -0.399256 -0.658728 -0.609579 -0.639825 -0.468014 -0.653647 -0.574495 -0.492647 -0.569743 -0.775896 -0.270885 -0.632692 -0.710921 -0.307069 -0.84247 -0.154496 -0.516116 -0.823846 -0.0402665 -0.565382 -0.879914 -0.312046 -0.358301 -0.886141 -0.170729 -0.430821 -0.872709 -0.449746 -0.190019 -0.913623 -0.291095 -0.283827 -0.394959 0.453787 -0.798802 -0.563376 0.397088 -0.72452 -0.381389 0.414398 -0.826327 -0.63616 0.175005 -0.751448 -0.338223 -0.0837695 -0.93733 -0.331321 -0.125827 -0.93509 -0.261465 0.246013 -0.933335 -0.974592 -0.21987 0.0427528 -0.955122 -0.2908 -0.056372 -0.888362 -0.430281 -0.160221 -0.794818 -0.594277 0.122878 -0.801519 -0.595817 -0.0506826 -0.686192 -0.725804 -0.0484603 -0.581445 -0.804864 -0.118809 -0.50299 -0.861198 -0.0730665 -0.457139 -0.884216 -0.0958401 -0.334596 -0.93556 -0.113016 -0.308634 -0.92028 -0.240478 -0.11158 -0.989326 -0.0937238 -0.254588 0.254656 -0.932917 -0.361857 0.314684 -0.877515 -0.540888 0.00805893 -0.841056 -0.529359 0.0600377 -0.846271 -0.61049 -0.14537 -0.778569 -0.729722 -0.0236039 -0.683337 -0.676461 0.17225 -0.716053 -0.727512 0.309307 -0.612418 -0.886495 0.121817 -0.446417 -0.834768 0.222279 -0.503741 -0.952455 0.00134585 -0.304676 -0.913934 0.13372 -0.383202 -0.980716 -0.117102 -0.15647 -0.966142 0.043946 -0.254242 -0.986017 -0.0801531 -0.146103 -0.159804 -0.935416 -0.315372 -0.245368 -0.813977 -0.526532 -0.220532 -0.789488 -0.572777 -0.274951 -0.629475 -0.726749 -0.251216 -0.602437 -0.757601 -0.283004 -0.391819 -0.875435 -0.446631 -0.600303 -0.663443 -0.355395 -0.333308 -0.87327 -0.590151 -0.232757 -0.773011 -0.733644 -0.382228 -0.561844 -0.728691 -0.332994 -0.598435 -0.743602 -0.267972 -0.612574 -0.745384 -0.507748 -0.431965 -0.778516 -0.430286 -0.45691 -0.720259 -0.647354 -0.249317 -0.773717 -0.565845 -0.284924 -0.689766 -0.7154 -0.111468 -0.773048 -0.629571 -0.0777033 -0.132616 0.982058 -0.134068 -0.133101 0.982596 -0.129577 -0.102788 0.835066 -0.540462 -0.136211 0.911117 -0.38899 -0.0262678 0.990658 -0.133814 -0.0262601 0.990642 -0.133934 -0.0255245 0.919548 -0.392149 -0.0390324 0.978603 -0.202022 -0.393933 0.583187 -0.71043 -0.384694 0.585985 -0.713184 -0.670933 0.470481 -0.573146 -0.665666 0.47372 -0.57661 -0.837008 0.347238 -0.4229 -0.878331 0.302001 -0.370581 -0.917736 0.252098 -0.306932 -0.971064 0.151546 -0.184578 -0.986715 0.101854 -0.126564 -0.996877 0.0501201 -0.0610338 -0.986731 0.124076 -0.104725 -0.986767 0.123904 -0.104591 -0.878319 0.365345 -0.308349 -0.878599 0.364935 -0.308036 -0.665293 0.570546 -0.48152 -0.666016 0.570027 -0.481136 -0.383646 0.705743 -0.595603 -0.385003 0.705273 -0.595284 -0.665363 0.641111 -0.38245 -0.477034 0.82243 -0.309916 -0.638607 0.750751 -0.168979 -0.878193 0.413081 -0.241124 -0.797737 0.541414 -0.265496 -0.986145 0.153213 -0.063595 -0.256885 0.956842 -0.135882 -0.450145 0.892955 0.00120254 -0.42874 0.888439 -0.163883 -0.518013 0.820985 -0.240097 -0.938143 0.338179 0.074319 -0.913656 0.404885 -0.0360794 -0.928208 0.358309 -0.100226 -0.22792 0.890612 -0.393526 -0.228439 0.88273 -0.410614 -0.360842 0.85689 -0.368147 -0.309658 0.824799 -0.473094 -0.396284 0.795729 -0.458012 -0.217847 0.799956 -0.559118 -0.508937 0.859178 0.0528879 -0.573123 0.808992 -0.130618 -0.762611 0.64668 -0.0151271 -0.824786 0.547364 -0.141848 -0.678967 0.691003 -0.248031 -0.784787 0.584543 -0.205955 -0.513574 0.768179 -0.382287 -0.767808 0.574765 -0.283049 -0.384173 0.783088 -0.489065 -0.0779339 -0.993686 -0.0807157 -0.239718 -0.941414 -0.237225 -0.162206 -0.972407 -0.167674 -0.392937 -0.824859 -0.406457 -0.391352 -0.826502 -0.404646 -0.53322 -0.64145 -0.55156 -0.531372 -0.644851 -0.549373 -0.635243 -0.405837 -0.657086 -0.633791 -0.411086 -0.655223 -0.687758 -0.144481 -0.711417 -0.687251 -0.151413 -0.710465 -0.678947 0.216222 -0.701626 -0.677226 0.224349 -0.700737 -0.583118 0.225235 -0.78054 -0.489025 0.442112 -0.751926 -0.460986 0.231875 -0.856578 -0.449096 0.533186 -0.716956 -0.526348 -0.138582 -0.8389 -0.525721 -0.144238 -0.838339 -0.486859 -0.401017 -0.775986 -0.485695 -0.405277 -0.774501 -0.40918 -0.638121 -0.652206 -0.407868 -0.640808 -0.650392 -0.301753 -0.823152 -0.481006 -0.300696 -0.824421 -0.479491 -0.181321 -0.939985 -0.289051 -0.11829 -0.97336 -0.196412 -0.0602029 -0.993544 -0.0961535 0.826282 -0.540775 -0.157548 0.261017 0.444366 -0.856977 0.174938 -0.928945 -0.326277 0.968079 0.0839938 -0.236154 0.943178 0.0964793 -0.317974 0.879148 0.211428 -0.427079 0.846822 0.0321125 -0.530906 0.737392 0.168353 -0.654148 0.679714 0.010133 -0.733407 0.686985 -0.0456553 -0.725236 0.59184 -0.198065 -0.781342 0.588874 -0.236629 -0.77281 0.431452 -0.401583 -0.807825 0.777885 -0.505731 -0.373002 0.908122 -0.296589 -0.295548 0.883018 -0.300582 -0.360458 0.959469 -0.100245 -0.263382 0.0963716 -0.798027 -0.594866 0.935483 -0.0956564 -0.340178 0.882249 0.0322676 -0.469675 0.823535 -0.132392 -0.5516 0.821465 -0.203352 -0.532769 0.726486 -0.354815 -0.588493 0.715874 -0.401732 -0.571082 0.555942 -0.568393 -0.606512 0.550319 -0.581776 -0.598904 0.327401 -0.733831 -0.595231 -0.212974 0.291237 -0.932643 -0.344554 0.210091 -0.914956 -0.359741 0.231701 -0.903826 0.17946 -0.274792 -0.944607 -0.130843 -0.411308 -0.902056 -0.0119055 -0.620188 -0.784363 -0.0258169 -0.64889 -0.760444 0.218206 -0.547324 -0.807975 0.206285 -0.530205 -0.822392 -0.283463 -0.166992 -0.944332 0.0161107 -0.0413419 -0.999015 0.0187652 -0.0430774 -0.998896 0.251218 0.201882 -0.946643 0.688401 0.328093 -0.646884 0.489704 0.445578 -0.749433 0.600168 0.300942 -0.741102 0.308274 0.441644 -0.842566 0.220412 0.210596 -0.952401 -0.0756327 0.517787 -0.85216 -0.0521164 0.504116 -0.862062 -0.107284 0.408968 -0.90622 -0.0974818 0.392565 -0.914544 -0.198815 0.285648 -0.937485 0.566395 -0.820925 -0.0726476 0.63683 -0.699015 -0.325308 0.411125 -0.911404 -0.0178691 0.469641 -0.872399 -0.135491 0.259303 -0.96109 -0.095229 0.270834 -0.953536 -0.131979 0.0488388 -0.995212 -0.0846656 0.419951 -0.82717 -0.373405 0.410949 -0.838952 -0.356763 0.622472 -0.695011 -0.359846 0.630126 -0.682192 -0.370885 0.802011 -0.497687 -0.330282 0.803813 -0.535444 -0.259202 0.893963 -0.439654 -0.0867992 0.968311 -0.208452 -0.137555 0.967489 -0.207625 -0.144421 0.998118 -0.0394611 -0.0469486 0.990251 -0.0181945 -0.138103 -0.0385387 -0.934253 -0.354523 -0.147507 -0.846215 -0.512018 -0.13321 -0.819094 -0.557979 -0.241737 -0.665479 -0.706188 -0.227362 -0.636775 -0.736766 -0.223608 -0.644046 -0.731576 -0.219054 -0.396421 -0.891553 -0.302603 -0.13833 -0.943025 0.842873 0.215341 -0.493145 0.728045 0.330629 -0.600529 0.698353 0.165099 -0.696452 0.532876 0.293639 -0.793612 0.48097 0.154426 -0.86303 0.530145 -0.0323041 -0.847292 0.41808 -0.0359033 -0.9077 0.26629 -0.196455 -0.94366 0.428295 -0.413188 -0.803641 0.212369 -0.561193 -0.799976 0.335485 -0.719573 -0.608 0.0799544 -0.825687 -0.558435 0.190768 -0.908103 -0.372769 -0.0485875 -0.955361 -0.291418 0.0521545 -0.987497 -0.148763 -0.873673 -0.0060145 -0.486477 -0.898299 0.330829 -0.289156 -0.713533 -0.69733 -0.0678386 -0.740566 -0.671896 -0.0108505 -0.781612 0.216418 -0.585018 -0.752918 0.28351 -0.593916 -0.826031 0.253265 -0.503517 -0.909154 -0.138491 -0.392759 -0.814395 -0.151027 -0.560314 -0.825458 -0.0314773 -0.563585 -0.695442 -0.580314 -0.423788 -0.927594 -0.366614 -0.0718558 -0.889572 -0.422811 -0.172893 -0.930975 -0.282894 -0.230775 -0.918497 -0.328233 -0.220513 -0.931999 -0.156704 -0.326835 -0.912981 0.0687389 -0.402169 -0.764287 -0.523188 -0.377016 -0.820917 -0.416577 -0.390588 -0.655616 -0.705879 -0.268147 -0.752646 -0.58985 -0.292577 -0.515478 -0.843617 -0.150311 -0.853473 -0.222481 -0.47126 -0.896993 -0.197746 -0.395349 -0.859142 -0.395219 -0.325079 -0.866437 -0.375852 -0.328669 -0.801538 -0.561102 -0.206641 -0.688724 -0.713791 -0.127127 -0.654895 -0.732719 -0.185027 -0.400783 -0.91462 -0.0533285 -0.369206 -0.929162 -0.0185719 -0.81565 0.575205 -0.0620828 -0.889702 0.454436 0.0438103 -0.89976 -0.417502 0.126982 -0.982309 -0.152502 -0.108685 -0.870225 -0.49256 -0.00964472 -0.857932 -0.511911 -0.0435804 -0.79053 -0.611377 -0.0357971 -0.81812 -0.562382 -0.120024 -0.797365 -0.581126 -0.162796 -0.565987 -0.824 -0.0261339 -0.55109 -0.832821 -0.0520413 -0.941606 0.335809 -0.0246933 -0.962849 0.259091 -0.0761137 -0.902493 0.220145 0.370194 -0.881456 0.457024 -0.119012 -0.865364 0.466579 -0.182893 -0.95557 0.224807 -0.19065 -0.929083 0.285636 -0.234983 -0.98079 0.162266 -0.108265 -0.999815 0.017852 0.00710188 -0.995821 0.0667231 -0.0623502 -0.770739 0.520214 -0.367885 -0.766671 0.512031 -0.387349 -0.828416 0.436894 -0.3505 -0.794169 0.423795 -0.435539 -0.865342 0.317615 -0.38769 -0.318363 -0.943592 -0.0909908 -0.112949 -0.992785 -0.040254 -0.466518 -0.856822 -0.219587 -0.289584 -0.940226 -0.179208 -0.60219 -0.720454 -0.343966 -0.465311 -0.825742 -0.318804 -0.707949 -0.538511 -0.456962 -0.620355 -0.644689 -0.446693 -0.744751 -0.410611 -0.526065 -0.861279 0.178606 -0.475708 -0.773766 0.416536 -0.477268 -0.938945 0.110343 -0.325895 -0.892175 0.252513 -0.374514 -0.974562 -0.0893664 -0.205531 -0.946578 0.127071 -0.296384 -0.967508 -0.221601 -0.121742 -0.971131 0.0465346 -0.233963 -0.755124 -0.640177 0.141284 -0.990646 -0.00143981 -0.136449 -0.977186 -0.210495 -0.0282818 -0.998489 0.0402008 -0.0374566 -0.0628196 0.725535 -0.685312 -0.0663804 0.725191 -0.68534 0.388746 0.669787 -0.632662 0.386308 0.670387 -0.63352 0.694547 0.522972 -0.494071 0.948033 0.231278 -0.218505 0.975969 0.161003 -0.146845 0.994476 0.0762902 -0.0720854 -0.0663489 0.618664 -0.782849 -0.0754568 0.617738 -0.782755 0.386151 0.571927 -0.723731 0.261883 0.589987 -0.763762 0.488988 0.540501 -0.684652 0.77489 0.391892 -0.49595 0.774863 0.462801 -0.430583 0.848164 0.385032 -0.363824 0.690127 0.4408 -0.573951 0.845862 0.330523 -0.418656 0.97601 0.134985 -0.170831 0.947397 0.1925 -0.255701 0.994407 0.065452 -0.0828951 -0.634497 0.680136 -0.36719 -0.558871 0.492977 -0.666811 -0.623744 0.771221 -0.127125 -0.678444 0.723832 -0.125625 -0.737794 0.565095 -0.369226 -0.561961 0.496501 -0.661579 -0.725164 0.662211 -0.188715 -0.641723 0.592023 0.487546 -0.752819 0.655109 -0.0639943 -0.483155 0.757186 -0.439581 -0.532489 0.836314 -0.130516 -0.500956 0.71569 0.486652 -0.546917 0.773938 -0.319221 -0.531123 0.753184 -0.3881 -0.0411425 0.0240097 -0.998865 -0.152272 0.871356 -0.466424 -0.379184 0.86947 -0.316611 0.289017 0.886109 -0.362326 -0.423436 0.896813 -0.128169 -0.299277 0.954076 -0.0131585 -0.284419 0.952983 -0.104539 -0.190687 0.97288 -0.130931 0.00789443 0.994365 -0.105715 0.00825682 0.994431 -0.105065 0.467767 0.843593 -0.263712 0.506097 0.775102 -0.378262 0.754352 0.604336 -0.25638 0.777372 0.603373 -0.177858 0.751811 0.651584 -0.101082 0.81934 0.572836 -0.02326 0.936182 0.34878 -0.0437623 0.862988 0.50236 -0.0537214 0.853738 0.520063 -0.0258254 0.745974 0.662513 -0.0678141 0.315116 0.811538 -0.492045 -0.204137 0.818749 -0.536636 0.187431 0.840041 -0.509117 0.0701008 0.831244 -0.55147 -0.412035 0.798454 -0.438974 -0.394701 0.789567 -0.469889 -0.368261 0.883821 -0.28852 -0.260386 0.900452 -0.348404 -0.0814074 0.983226 -0.163217 -0.00615623 0.972045 -0.234714 0.306351 0.951112 -0.03918 -0.248545 0.880319 -0.40406 -0.29871 0.81052 -0.503815 0.017404 0.943234 -0.331674 0.0926954 0.883777 -0.458634 0.214056 0.895323 -0.39061 0.243937 0.840666 -0.483503 0.598895 0.714288 -0.362102 0.968011 0.240548 -0.0713464 0.948849 0.311996 -0.0484135 0.943167 0.331656 -0.0209806 0.577933 0.814804 -0.0456906 0.566022 0.823987 -0.0257766 0.720357 0.693503 -0.0117704 0.708931 0.704757 -0.0271205 0.491102 0.858198 -0.149382 0.568725 0.767298 -0.29632 0.510195 0.858119 -0.0577339 0.343165 0.935001 -0.0895004 0.305717 0.951225 -0.041324 0.947322 0.272662 -0.168037 0.765705 0.557368 -0.320992 0.84761 0.439389 -0.29748 0.610552 0.665944 -0.428655 0.694371 0.586942 -0.416351 0.323081 0.779056 -0.5373 0.389097 0.737464 -0.552042 -0.0629172 0.791229 -0.608274 -0.366292 0.831079 -0.418494 -0.341803 0.815156 -0.467644 -0.204204 0.928935 -0.308838 -0.121782 0.914262 -0.386385 0.356076 0.928932 -0.101464 0.219331 0.944521 -0.244489 0.335844 0.928477 -0.158552 0.412463 0.863877 -0.289122 0.614578 0.771812 -0.163097 0.655609 0.700493 -0.281934 0.870689 0.470394 -0.143629 0.881008 0.427618 -0.202406 0.993877 0.103247 -0.0393528 -0.0122517 -0.87158 -0.4901 -0.0239626 -0.928319 -0.371011 -0.00923248 -0.819332 -0.573246 -0.000579895 -0.848112 -0.529817 -0.147226 -0.987951 -0.0477256 -0.070746 -0.854261 -0.515008 -0.0421472 -0.849625 -0.5257 -1.89024e-05 -0.848114 -0.529813 -6.21456e-06 -0.871967 -0.489564 -0.000975144 -0.861539 -0.50769 0.000794883 -0.841533 -0.540206 -0.808347 -0.0561994 -0.586018 -0.810373 -0.0708795 -0.581612 -0.822928 -0.0707969 -0.563717 -0.86073 -0.0402957 -0.507464 -0.802587 -0.118611 -0.584625 -0.746042 -0.115554 -0.655797 -0.830895 -0.227914 -0.507611 -0.873184 -0.0662302 -0.48287 -0.832059 -0.0291142 -0.553922 -0.854626 -0.0301302 -0.518369 -0.854645 0.0301307 -0.518338 -0.83208 0.0291147 -0.553891 -0.876742 0.0697235 -0.47588 -0.803946 0.105126 -0.585337 -0.664364 0.102791 -0.740307 -0.784831 0.1628 -0.597943 -0.829162 0.225612 -0.511458 -0.865611 0.0360701 -0.499416 -0.821588 0.0718306 -0.565538 -0.821472 0.0718429 -0.565705 -0.810088 0.0682554 -0.582322 -0.808331 0.0560449 -0.586054 -5.56359e-06 0.873145 -0.487462 0.000115135 0.871882 -0.489716 -5.60181e-05 0.848049 -0.529918 -1.29864e-05 0.847706 -0.530466 -0.0175763 0.871287 -0.490459 -0.000566928 0.847704 -0.53047 -0.0138964 0.802947 -0.595888 -0.0236271 0.895544 -0.444345 -0.0741578 0.801578 -0.593274 -0.148877 0.851338 0.50305 -0.358843 0.108101 -0.927117 -0.235222 -0.561108 -0.793617 -0.09293 -0.822911 -0.560518 -0.101431 -0.828652 -0.550497 -0.0745413 -0.793005 -0.604637 -0.0797419 -0.834695 -0.544909 -0.28664 -0.678005 -0.676865 -0.405985 -0.750835 -0.520983 -0.239238 -0.764919 -0.59805 -0.208083 -0.788555 -0.578691 -0.225084 -0.786353 -0.575314 -0.156443 -0.807029 -0.569412 -0.365499 0.408143 -0.836558 -0.386796 0.356142 -0.850618 -0.559411 0.31166 -0.768067 -0.561709 0.575078 -0.594785 -0.540052 0.613743 -0.575902 -0.383215 0.654118 -0.652132 -0.302551 0.948139 -0.0974429 -0.301772 0.94895 -0.0917981 -0.397052 0.812141 -0.427525 -0.392907 0.875665 -0.280776 -0.28242 0.94896 0.140404 -0.330927 0.831967 -0.445329 -0.356913 0.700879 -0.617561 -0.913046 0.123038 -0.388855 -0.733887 -0.311719 -0.603524 -0.827165 -0.0932363 -0.55417 -0.676226 0.735877 -0.0346981 -0.673066 0.73909 -0.0269683 -0.804334 0.509044 -0.306466 -0.79016 0.577686 -0.204757 -0.841681 0.358198 -0.404064 -0.564313 0.810784 -0.155497 -0.552607 0.826074 -0.110577 -0.656707 0.663014 -0.359373 -0.643126 0.722556 -0.253579 -0.716424 0.436267 -0.544433 -0.72644 0.504 -0.467192 -0.453349 -0.691978 -0.56182 -0.323886 -0.372438 -0.869705 -0.32479 -0.366084 -0.872063 -0.486738 -0.431634 -0.759459 -0.57462 -0.625996 -0.5272 -0.521702 -0.552998 -0.649631 -0.566737 -0.515118 -0.643011 -0.476782 -0.45536 -0.751881 -0.290375 -0.672559 -0.680696 -0.202912 -0.637141 -0.743558 -0.085357 -0.766711 -0.636293 -0.6739 -0.0380614 -0.737841 -0.837964 0.534516 -0.110042 -0.83627 0.538706 -0.102216 -0.892553 0.360536 -0.270856 -0.883855 0.433377 -0.176025 -0.910667 0.213844 -0.353492 -0.855765 0.266395 -0.443508 -0.827315 0.0723393 -0.557061 -0.708769 0.148127 -0.689713 -0.734704 0.208264 -0.645628 -0.570321 0.276729 -0.773405 -0.522216 0.0228414 -0.852507 -0.364977 -0.230149 -0.902121 -0.408402 -0.0890655 -0.908447 -0.989135 -0.00640262 -0.146873 -0.973825 0.213832 0.0770694 -0.964475 -0.140986 -0.223407 -0.995061 -0.00711898 -0.099008 -0.887825 -0.318864 -0.331801 -0.955594 -0.201198 -0.215311 -0.70515 -0.530016 -0.471006 -0.861015 -0.393494 -0.322204 -0.488122 -0.673132 -0.555545 -0.949297 0.245471 -0.196418 -0.892982 0.449355 0.0257616 -0.957001 0.10586 -0.27008 -0.957215 0.265334 -0.115484 -0.920512 -0.0928099 -0.37953 -0.964048 0.046277 -0.261669 -0.830302 -0.294977 -0.472851 -0.898419 -0.189927 -0.395943 -0.755452 -0.411574 -0.509803 -0.696966 -0.333165 -0.635011 -0.757169 -0.254318 -0.601679 -0.636324 -0.172596 -0.751866 -0.616063 -0.206789 -0.760069 -0.403225 -0.122527 -0.906861 -0.37763 -0.206889 -0.902548 -0.0371024 0.990675 -0.131096 -0.125225 0.964974 -0.230529 -0.0968785 0.0967204 -0.990586 -0.112922 0.139571 -0.983752 -0.127112 0.280139 -0.951507 -0.0404249 -0.552624 -0.83245 -0.048269 -0.538075 -0.841514 -0.094393 -0.345306 -0.933731 -0.0729 -0.25669 -0.963741 -0.0946147 -0.171472 -0.980635 -0.113716 -0.0511408 -0.992196 -0.0885236 0.910679 -0.403519 -0.0975386 0.928228 -0.358997 -0.0832553 0.985669 -0.146716 -0.050145 -0.759313 -0.648791 -0.019222 -0.712399 -0.701512 -0.0705262 -0.765018 -0.640136 -0.143383 0.449846 -0.881522 -0.134891 0.436424 -0.889572 -0.118109 0.730184 -0.672964 -0.117678 0.729455 -0.67383 -0.11338 0.859623 -0.498191 -0.1564 -0.562762 -0.811688 -0.890746 -0.269125 -0.366257 -0.98766 -0.0927303 -0.126207 -0.987666 -0.0927132 -0.126179 -0.940768 -0.200758 -0.273224 -0.876008 -0.28373 -0.39001 -0.987671 -0.105062 -0.116048 -0.987672 -0.105061 -0.116047 -0.890791 -0.304977 -0.336868 -0.890785 -0.304984 -0.336878 -0.706722 -0.474827 -0.524483 -0.70674 -0.474817 -0.524469 -0.453643 -0.598113 -0.660658 -0.45361 -0.598122 -0.660672 -0.156377 -0.662886 -0.732208 -0.156388 -0.726183 -0.669478 -0.45325 -0.581019 -0.676004 0.0252201 -0.591958 -0.805574 -0.453554 -0.527738 -0.718179 -0.453449 -0.527763 -0.718227 -0.706635 -0.418985 -0.570192 -0.649083 -0.445804 -0.616401 -0.759859 -0.384937 -0.523868 -0.156324 -0.77934 -0.606789 0.380238 -0.70526 -0.598354 -0.452793 -0.679888 -0.576828 -0.452676 -0.67993 -0.57687 -0.705913 -0.5401 -0.458235 -0.70582 -0.540167 -0.458298 -0.890361 -0.347145 -0.294531 -0.890308 -0.347221 -0.294601 -0.96909 -0.188121 -0.159612 -0.987589 -0.120658 -0.100544 -0.995792 -0.0698778 -0.0592892 8.26822e-05 -0.760598 -0.649223 -1.85435e-05 -0.760282 -0.649593 0.000162882 -0.553081 -0.833127 5.28577e-05 -0.553439 -0.832889 0.000241479 -0.257395 -0.966306 0.000130005 -0.257768 -0.966207 0.000290554 0.0971644 -0.995268 0.000200008 0.0968723 -0.995297 0.000259671 0.28243 -0.959288 0.00165375 0.450399 -0.892826 0.000254945 0.454542 -0.890725 0.000279404 0.611267 -0.791424 -0.00122295 0.735342 -0.677695 0.000257626 0.738908 -0.673806 0.000252952 0.844357 -0.535781 -0.0012126 0.914274 -0.405096 0.000231059 0.916624 -0.39975 0.000208974 0.967054 -0.25457 -0.00106216 0.991358 -0.131179 0.000178487 0.992117 -0.125315 -0.0332317 -0.558808 -0.828631 -0.938483 -0.244992 -0.243369 -0.875027 -0.307566 -0.373807 -0.647139 -0.496667 -0.578388 -0.757316 -0.44437 -0.478547 -0.713514 -0.570358 -0.406928 -0.357804 -0.92432 -0.1327 -0.460815 -0.873766 -0.155508 -0.0941583 -0.55355 -0.827476 -0.0903058 -0.547678 -0.831802 -0.289087 -0.729684 -0.61967 -0.174712 -0.541 -0.822676 -0.755749 -0.444895 -0.480533 -0.647325 -0.482896 -0.589731 -0.485612 -0.52794 -0.69675 -0.453451 -0.527674 -0.718291 -0.156458 -0.543337 -0.824806 -0.0715938 -0.981971 -0.174948 -0.104949 -0.782766 -0.613403 -0.14303 -0.88831 -0.436402 -0.16164 -0.913314 -0.373805 -0.160418 -0.909488 -0.383532 -0.223622 -0.944722 -0.239776 -0.985843 -0.136609 -0.0972214 -0.959048 -0.218702 -0.179988 -0.940876 -0.317323 -0.118568 -0.911487 -0.371533 -0.176508 -0.873881 -0.471786 -0.11726 -0.83238 -0.522877 -0.183697 -0.771993 -0.630681 -0.0791714 -0.0352837 -0.585373 -0.809996 -0.103416 -0.771699 -0.627523 -0.265423 -0.699116 -0.663918 -0.412653 -0.802668 -0.43063 -0.457582 -0.812242 -0.361776 -0.452214 -0.809826 -0.373745 -0.600986 -0.782412 -0.163239 -0.754053 -0.646816 -0.114158 -0.502941 -0.657601 -0.560902 -0.616064 -0.64324 -0.454651 -0.447998 -0.626616 -0.637692 -0.386716 -0.625481 -0.677661 -0.147946 -0.548741 -0.822797 -0.14087 -0.547401 -0.824929 -0.000943972 -0.756212 -0.654326 0.00276254 -0.760596 -0.64922 -0.00474413 -0.553432 -0.832881 0.00297178 -0.542937 -0.839768 -0.00527791 -0.257764 -0.966193 0.00304246 -0.246256 -0.9692 -0.0051682 0.0968718 -0.995283 0.00260586 0.107136 -0.994241 -0.00446024 0.457566 -0.889164 0.00190336 0.450399 -0.892825 -0.000665589 0.611267 -0.791424 0.000944461 0.73889 -0.673825 0.000926204 0.738908 -0.673806 -0.000404963 0.844357 -0.535781 0.00217251 0.915416 -0.402502 0.000301442 0.916624 -0.39975 -0.000117911 0.967054 -0.254571 0.00280185 0.992114 -0.125308 0.000188326 0.991508 -0.130042 -0.000123048 0.991472 -0.130323 -0.0212906 -0.990598 -0.13514 -0.000334899 -0.984546 -0.175124 -4.51565e-05 -0.984498 -0.175399 0.0120656 -0.914721 -0.403906 -0.000505199 -0.897538 -0.440936 -0.000624717 -0.78735 -0.616506 -0.000743009 -0.787112 -0.616809 -0.000738841 -0.690267 -0.723555 -0.0170765 -0.585653 -0.810382 -0.000504787 -0.551656 -0.834072 -0.0218135 -0.742125 -0.669907 -0.020734 -0.756102 -0.654126 -0.0168136 -0.526509 -0.850004 -0.0157397 -0.542924 -0.839635 -0.00947546 -0.229984 -0.973148 -0.00848744 -0.246268 -0.969165 -0.000332006 0.120307 -0.992737 0.000480165 0.107136 -0.994244 0.00914851 0.465668 -0.884912 0.0097143 0.457529 -0.889142 0.017167 0.742427 -0.669707 0.0174965 0.738744 -0.673759 0.022613 0.916179 -0.40013 0.0227595 0.915149 -0.402473 0.0254166 0.991224 -0.129725 0.0254533 0.991134 -0.130402 -0.0986436 -0.811474 -0.576002 -0.0911934 -0.737037 -0.669672 -0.067831 -0.613796 -0.786545 -0.0598065 -0.52352 -0.849912 -0.0250844 -0.320473 -0.946925 -0.0179966 -0.229416 -0.973162 0.0252012 0.0446595 -0.998684 0.0299495 0.11828 -0.992529 0.0734466 0.415349 -0.906692 0.0755146 0.460985 -0.884189 0.109795 0.714679 -0.690782 0.11005 0.735385 -0.668654 0.129962 0.901379 -0.413068 0.129576 0.907663 -0.399197 0.135898 0.981435 -0.135342 0.135556 0.982307 -0.129219 -0.0408697 -0.689655 -0.722984 -0.0205567 -0.990788 -0.133855 -0.0210214 -0.993569 -0.111255 -0.0516159 -0.97941 -0.195173 -0.0357875 -0.993609 -0.107054 -0.0836025 -0.979791 -0.181715 -0.0990391 -0.988113 -0.117576 -0.0681636 -0.992047 -0.105816 -0.0752163 -0.990516 -0.11498 -0.0603842 -0.990513 -0.123438 -0.448477 -0.749905 -0.486324 -0.604766 -0.534039 -0.590813 -0.67365 0.117991 -0.729571 -0.540677 -0.53832 -0.646437 -0.461475 -0.538256 -0.70521 -0.461073 -0.539196 -0.704755 -0.370218 -0.539147 -0.756478 -0.369755 -0.540417 -0.755798 -0.267633 -0.54034 -0.79775 -0.265876 -0.546291 -0.794277 -0.156031 -0.54641 -0.822855 -0.155102 -0.550728 -0.820147 -0.0251984 -0.551526 -0.833777 -0.0554259 -0.197996 -0.978635 -0.0619101 -0.299957 -0.951942 -0.081208 -0.5512 -0.830412 -0.00767519 -0.990746 -0.135511 -0.0076425 -0.990793 -0.135169 -0.0228674 -0.914531 -0.403868 -0.0997008 -0.990412 -0.0956261 -0.0582956 -0.996293 -0.0632609 -0.279352 -0.911181 -0.302841 -0.224878 -0.911768 -0.34367 -0.224644 -0.911937 -0.343375 -0.180383 -0.911916 -0.368606 -0.180075 -0.912183 -0.368097 -0.130307 -0.912147 -0.388597 -0.129253 -0.913319 -0.38619 -0.0758431 -0.913372 -0.4 -0.0752818 -0.914281 -0.398024 -0.0228774 -0.914152 -0.404726 -0.034868 -0.786851 -0.616157 -0.0354697 -0.759987 -0.648969 -0.120706 -0.76031 -0.638246 -0.121548 -0.757854 -0.641002 -0.207125 -0.757745 -0.618807 -0.20873 -0.754455 -0.622278 -0.288395 -0.754527 -0.589505 -0.288829 -0.753824 -0.590192 -0.359697 -0.753874 -0.549812 -0.36013 -0.753283 -0.550338 -0.446938 -0.752028 -0.484459 -0.280447 -0.910411 -0.304141 -0.358012 -0.740291 -0.569031 0.509534 0.850111 -0.132992 0.327689 0.935116 -0.134821 -0.169662 -0.605533 -0.777525 -0.165672 -0.591487 -0.789111 -0.0709617 -0.327152 -0.942304 -0.0666464 -0.311197 -0.948006 0.0474379 0.0238783 -0.998589 0.0512682 0.0389475 -0.997925 0.162965 0.383772 -0.908934 0.165611 0.395226 -0.903532 0.251175 0.676141 -0.692636 0.252508 0.6831 -0.685284 0.300851 0.85935 -0.413529 0.301204 0.862687 -0.406259 0.307524 0.889464 -0.338059 0.229729 0.964214 -0.13235 -0.240225 -0.789885 -0.564247 -0.244358 -0.797963 -0.550949 -0.155687 -0.800302 -0.579032 -0.42823 -0.70873 -0.560644 -0.469923 -0.862317 -0.18863 -0.297793 -0.557576 -0.774873 -0.294551 -0.550497 -0.781148 -0.155414 -0.298781 -0.941582 -0.151987 -0.291327 -0.944473 0.0226655 0.0271008 -0.999376 0.0255949 0.033527 -0.99911 0.203738 0.360627 -0.910186 0.205688 0.365015 -0.907996 0.349189 0.630653 -0.693068 0.350177 0.633003 -0.690422 0.43849 0.798554 -0.412356 0.438827 0.799487 -0.410185 0.429445 0.781719 -0.452208 0.441595 0.887447 -0.132028 -0.511257 -0.652253 -0.559627 -0.511566 -0.652775 -0.558736 -0.394847 -0.493451 -0.774985 -0.3954 -0.494335 -0.774139 -0.217693 -0.256627 -0.941675 -0.218457 -0.257811 -0.941175 0.00716718 0.0393689 -0.999199 0.00617775 0.037858 -0.999264 0.238844 0.339883 -0.909634 0.237825 0.338332 -0.910478 0.428032 0.580977 -0.692283 0.427181 0.579664 -0.693907 0.547336 0.728718 -0.411573 0.54684 0.72791 -0.413659 0.599931 0.789182 -0.131431 0.599798 0.788884 -0.133806 -0.601237 -0.568564 -0.561471 -0.603158 -0.570986 -0.556934 -0.463497 -0.427163 -0.776339 -0.46618 -0.430348 -0.772966 -0.254353 -0.217654 -0.942301 -0.257546 -0.221324 -0.940577 0.0105173 0.0426977 -0.999033 0.00739177 0.0391695 -0.999205 0.282991 0.305728 -0.909091 0.280463 0.302893 -0.910822 0.505326 0.515718 -0.691868 0.503623 0.513795 -0.694534 0.645477 0.643462 -0.411481 0.644566 0.642395 -0.414563 0.707188 0.694665 -0.131627 0.706948 0.694314 -0.134736 0.443925 -0.821528 -0.357804 -0.58029 -0.528151 -0.619935 0.427123 -0.900373 -0.0830334 0.083655 -0.995589 -0.042476 0.889498 -0.44832 -0.0883316 0.866977 -0.498249 -0.00996231 0.774837 -0.622636 -0.109326 0.749923 -0.660282 -0.0405412 0.854576 -0.478247 -0.202436 0.879081 -0.450366 -0.156162 0.968316 -0.242876 -0.0580971 0.974317 -0.151943 -0.16619 0.998589 -0.0352591 -0.0397154 0.961234 0.271929 -0.0456513 0.782528 -0.0119745 -0.6225 0.886701 0.459563 -0.0506219 -0.303872 -0.813264 -0.496249 -0.630842 -0.53439 -0.562553 -0.610383 -0.572001 -0.547949 -0.612296 -0.573023 -0.544738 -0.0593834 -0.98834 -0.140205 -0.259565 -0.908886 -0.326424 -0.186992 -0.95532 -0.228904 -0.46694 -0.750904 -0.467022 -0.480212 -0.730913 -0.484935 -0.434355 -0.779133 -0.451982 -0.397543 -0.759777 -0.514488 -0.604135 -0.579707 -0.546773 -0.584583 -0.604271 -0.541405 0.280429 -0.909345 -0.307328 0.403186 -0.880364 -0.2498 0.466834 -0.860447 -0.2042 0.118228 -0.950543 -0.287212 0.240803 -0.943939 -0.225816 0.287492 -0.938249 -0.19245 0.421315 -0.900142 -0.110621 0.378316 -0.914107 -0.145896 0.583746 -0.811473 -0.0274338 0.925545 0.346065 -0.15364 0.887127 0.401181 0.228166 0.976489 0.0997949 -0.191074 0.99635 -0.0691916 -0.049991 0.791918 0.0894516 -0.60404 0.0151069 -0.374456 -0.927122 0.218879 -0.289955 -0.931675 0.19278 -0.293036 -0.936464 0.386687 -0.196929 -0.90094 0.512103 -0.124963 -0.849785 0.53882 -0.0933176 -0.837237 0.688809 0.00996363 -0.724875 0.596348 -0.370408 -0.712157 0.225045 -0.515826 -0.826606 0.268336 -0.51694 -0.812877 -0.114552 -0.586096 -0.802103 -0.378086 -0.507488 -0.774278 0.835473 -0.156208 -0.526862 0.862938 -0.358929 -0.355678 0.76828 -0.455063 -0.45018 0.75153 -0.595957 -0.282912 0.587181 -0.705168 -0.397437 0.551418 -0.791133 -0.264664 0.212523 -0.865008 -0.454528 0.178091 -0.914104 -0.364276 0.072657 -0.913868 -0.399457 0.0407157 -0.941789 -0.333731 -0.0606529 -0.925456 -0.373968 0.544358 -0.378367 -0.748674 0.574269 -0.593092 -0.564319 0.250717 -0.686567 -0.682471 0.161974 -0.708994 -0.686361 -0.09573 -0.708797 -0.698887 -0.152993 -0.709908 -0.687477 -0.406281 -0.652965 -0.639197 -0.434368 -0.647046 -0.626623 0.919798 0.256673 -0.296802 0.877961 0.237289 -0.415786 0.957968 0.0111151 -0.28666 0.928517 -0.0136729 -0.371037 0.95511 -0.223515 -0.194437 0.885503 -0.311717 -0.344554 0.866748 -0.476209 -0.148233 0.779027 -0.560302 -0.281388 0.73805 -0.66314 -0.124613 0.637546 -0.730574 -0.244534 0.593076 -0.795337 -0.125301 0.592818 -0.795493 -0.125532 0.616067 -0.781937 -0.0950583 -0.655648 -0.543802 -0.523836 -0.653256 -0.542316 -0.528346 -0.655434 -0.541308 -0.526681 -0.57518 -0.530098 -0.623029 -0.420353 -0.55191 -0.720208 -0.315369 -0.539602 -0.780623 -0.102533 -0.509384 -0.854409 0.467283 -0.618401 -0.631844 0.448351 -0.769626 -0.454596 0.148228 -0.809904 -0.567524 -0.169303 -0.800935 -0.574316 -0.166062 -0.801896 -0.573922 -0.273498 -0.77102 -0.575089 -0.440653 -0.69137 -0.572567 -0.584734 -0.60448 -0.541008 -0.661851 -0.534464 -0.525644 0.39306 -0.91916 -0.0254735 0.101479 -0.977151 -0.186757 0.230634 -0.968192 -0.0970187 0.153986 -0.978179 -0.13948 0.0698504 -0.976081 -0.205879 -0.123969 -0.940434 -0.316569 -0.10448 -0.948202 -0.299995 -0.265476 -0.8763 -0.40202 -0.233162 -0.858843 -0.456097 -0.301475 -0.814604 -0.495514 -0.0630043 -0.887717 -0.456058 -0.0371558 -0.851357 -0.523269 0.310392 -0.865967 -0.39212 0.344562 -0.781522 -0.520097 0.643584 -0.679633 -0.351993 0.662221 -0.534112 -0.525535 0.767274 -0.455835 -0.451115 0.741503 -0.260181 -0.61845 0.8297 -0.160113 -0.534754 0.744001 0.0742366 -0.664041 0.874557 0.208137 -0.437984 0.776998 0.604222 -0.176606 -0.271464 -0.19756 -0.941954 -0.490591 -0.370547 -0.788679 -0.504698 -0.379198 -0.775557 -0.619482 -0.483104 -0.618751 -0.655946 -0.505616 -0.560436 0.0134381 0.0392486 -0.999139 -0.117297 -0.0705448 -0.990588 -0.287356 -0.206255 -0.935353 0.310785 0.273172 -0.910379 0.198919 0.181386 -0.963084 0.0546532 0.0633812 -0.996492 0.706189 0.574255 -0.414159 0.597489 0.489415 -0.635201 0.55081 0.463373 -0.694186 0.498245 0.415977 -0.760733 0.343003 0.290923 -0.893148 0.76421 0.630947 -0.133748 0.7638 0.609085 -0.213601 0.692946 0.569311 -0.442392 -0.618143 -0.484819 -0.618748 0.808127 0.561698 -0.177277 0.840469 0.483915 -0.2438 0.803535 0.589623 -0.0817107 -0.576962 -0.533511 -0.61845 -0.592536 -0.492981 -0.63708 -0.433123 -0.341897 -0.833973 -0.468321 -0.399085 -0.788294 -0.255622 -0.254682 -0.932628 -0.253343 -0.250537 -0.934371 -0.102078 -0.171436 -0.979893 -0.0613716 -0.14426 -0.987635 0.0889262 -0.0620552 -0.994103 0.115388 -0.0183704 -0.993151 0.242606 0.0575423 -0.968417 0.274395 0.077425 -0.958495 0.400516 0.155403 -0.903016 0.416722 0.187796 -0.889424 0.544277 0.273016 -0.793237 0.578964 0.301037 -0.757745 0.656722 0.343814 -0.671199 0.674047 0.379841 -0.633547 0.74999 0.438527 -0.495186 0.766099 0.46605 -0.442593 0.802232 0.481898 -0.352416 0.820188 0.536447 -0.198791 -0.778958 0.308337 -0.546034 -0.158562 0.977999 -0.135561 -0.0844475 0.994664 -0.0592622 -0.161893 0.976978 -0.138943 -0.136786 0.979292 -0.149256 -0.139672 0.978299 -0.153042 -0.116255 0.978268 -0.171685 -0.102802 0.983671 -0.147727 -0.104956 0.968742 -0.224773 -0.088861 0.978885 -0.184086 -0.0626572 0.979011 -0.193939 -0.0454357 0.986307 -0.15854 -0.0506293 0.946576 -0.318483 -0.0250072 0.979766 -0.198579 -0.009314 0.979847 -0.199531 -0.00526471 0.982716 -0.185043 -0.00373373 0.979959 -0.199165 -0.0289366 0.0557849 -0.998023 -0.0378805 0.168308 -0.985006 -0.125677 -0.128251 -0.983746 -0.162805 0.205642 -0.96499 -0.274629 -0.152917 -0.949313 -0.310968 0.198235 -0.929517 -0.414911 -0.157338 -0.896155 -0.416682 -0.19237 -0.888465 -0.487072 0.0797044 -0.869717 -0.552991 -0.176943 -0.814182 -0.586596 0.129472 -0.799464 -0.668679 -0.150466 -0.728168 -0.693566 0.126842 -0.709138 -0.752474 -0.144837 -0.642499 -0.774796 0.138398 -0.616877 -0.810656 -0.131912 -0.570469 -0.828446 -0.0192538 -0.559738 -0.579935 0.705593 -0.407203 -0.702151 0.514277 -0.492446 -0.173509 0.977966 -0.116095 -0.265412 0.945786 -0.187206 -0.435655 0.847004 -0.304611 -0.74787 0.416065 -0.517282 -0.691198 0.416022 -0.590907 -0.690184 0.419641 -0.589532 -0.613364 0.419443 -0.669217 -0.612052 0.424992 -0.666914 -0.507601 0.424794 -0.749594 -0.506228 0.432465 -0.746128 -0.381276 0.432447 -0.817079 -0.380128 0.44278 -0.812064 -0.247368 0.442788 -0.861828 -0.246902 0.454489 -0.85585 -0.111252 0.454549 -0.883747 -0.111649 0.465088 -0.878196 -0.0252139 0.465725 -0.88457 -0.0255493 0.469548 -0.882537 -0.50587 0.789511 -0.347516 -0.466491 0.789524 -0.398796 -0.465367 0.790805 -0.39757 -0.413712 0.790636 -0.451372 -0.41219 0.792638 -0.449247 -0.34199 0.792473 -0.505005 -0.340286 0.795297 -0.501705 -0.256386 0.795274 -0.549368 -0.254803 0.799062 -0.544587 -0.165907 0.799058 -0.577911 -0.164954 0.803346 -0.572211 -0.0744101 0.803398 -0.590775 -0.0743434 0.807375 -0.585337 -0.0168023 0.807864 -0.589129 -0.0169624 0.809256 -0.587211 0 0.981083 -0.193587 0.000246828 0.0558153 -0.998441 0.00328353 0.979961 -0.199161 -0.0036046 0.809372 -0.587286 -0.00362658 0.809353 -0.587311 0.00402354 0.469706 -0.882814 -0.0104667 0.450035 -0.89295 0.0104282 0.0391351 -0.99918 -0.556282 0.635776 -0.535107 -0.0351772 0.990242 -0.134848 0.753098 0.6489 -0.108501 0.179628 0.61373 -0.768811 0.357689 0.663375 -0.657261 0.416062 0.67665 -0.607484 0.500423 0.665358 -0.553963 0.640971 0.661084 -0.390031 0.643729 0.661094 -0.385445 0.734486 0.622421 -0.270413 0.789503 0.593522 -0.156257 0.829819 0.551183 -0.0871624 0.212798 0.937488 -0.275377 0.268119 0.943768 -0.193425 -0.180155 0.833784 -0.52187 0.317113 0.814047 -0.486588 0.480315 0.812982 -0.329179 0.555234 0.784629 -0.275812 0.656306 0.742651 -0.13316 0.703378 0.705943 -0.0830847 -0.434776 0.765869 -0.473724 -0.492933 0.780102 -0.385302 -0.417547 0.845993 -0.331587 0.206562 0.971995 -0.112066 -0.227135 0.942616 -0.244713 -0.102456 0.98795 -0.116009 -0.295866 0.917207 -0.266823 -0.227992 0.900515 -0.37026 -0.340414 0.830356 -0.441165 -0.814406 -0.088701 -0.573476 -0.823962 -0.124731 -0.552746 -0.654643 0.16843 -0.736935 -0.626379 0.20367 -0.752442 -0.486523 0.270251 -0.830819 -0.190875 0.461082 -0.866586 -0.0432588 0.740306 -0.670877 -0.287356 0.591659 -0.753237 -0.330498 0.573757 -0.749382 -0.568353 0.34238 -0.748165 -0.835266 -0.120721 -0.53643 -0.840107 -0.116056 -0.52986 -0.829307 0.00509763 -0.558769 0.371942 0.926083 -0.0634753 0.441934 0.880665 -0.170656 0.673171 0.699994 0.238432 0.583429 0.811171 -0.0401464 0.347112 0.88628 -0.306628 0.399575 0.889935 -0.219899 0.169573 0.889925 -0.423413 0.240804 0.819697 -0.519722 0.0209326 0.751651 -0.659228 0.123651 0.610318 -0.782446 -0.180552 0.463188 -0.867674 -0.835668 0.00849003 -0.549169 -0.835322 -0.0192582 -0.549424 -0.737813 0.398305 -0.544963 -0.767872 0.308057 -0.561671 -0.737557 0.390378 -0.551012 -0.695861 0.514053 -0.501525 -0.571657 0.705217 -0.419378 0.164092 0.984257 0.0656632 0.145724 0.977762 -0.150821 -0.00218008 0.963091 -0.269166 0.121639 0.982543 -0.140761 -0.0991785 0.945819 -0.309176 -0.00380779 0.893514 -0.449019 -0.240436 0.774856 -0.584628 -0.152989 0.841801 -0.517653 -0.475784 0.592452 -0.6501 -0.422002 0.66088 -0.620607 -0.663249 0.359121 -0.656607 -0.63886 0.410558 -0.650615 -0.775802 0.135403 -0.616277 -0.722533 0.0849877 -0.686093 -0.740361 0.0519425 -0.6702 -0.950455 0.245528 -0.190661 -0.778787 0.110527 -0.617474 -0.257921 0.767558 -0.586798 -0.258911 0.765341 -0.589253 -0.415383 0.700631 -0.580149 -0.474836 0.855962 -0.204594 -0.479394 0.850061 -0.218122 -0.294416 0.93878 -0.178919 -0.301365 0.932645 -0.198377 -0.124933 -0.00238192 -0.992162 -0.178084 0.0170484 -0.983868 -0.0129624 0.0391339 -0.99915 -0.0497805 0.0868296 -0.994979 -0.991608 0.0831953 -0.0989523 -0.858409 0.141389 -0.493096 -0.91824 0.160326 -0.36212 -0.95405 0.152166 -0.258135 -0.830441 0.139028 -0.53948 -0.713055 0.417928 -0.562929 -0.416283 0.696988 -0.58388 -0.553222 0.605714 -0.571888 -0.636173 0.747728 -0.190229 -0.59002 0.750845 -0.296832 -0.657701 0.73132 0.180556 -0.170663 -0.0319861 -0.98481 -0.174771 -0.032105 -0.984086 -0.502015 0.0357853 -0.864118 -0.0588404 0.00902342 -0.998227 -0.133688 0.0691364 -0.988609 -0.327929 0.379692 -0.865042 -0.476054 0.232157 -0.848219 -0.475702 0.232026 -0.848453 -0.548343 0.0585899 -0.834199 -0.672815 0.0819908 -0.735253 -0.869499 0.492088 0.0426713 -0.765233 0.47142 -0.438385 -0.808079 0.512445 -0.290532 -0.814243 0.515442 -0.267074 -0.717422 0.425968 -0.551232 -0.553491 0.600798 -0.576792 -0.28367 0.230329 -0.930849 -0.277835 0.400272 -0.873264 -0.113338 0.465493 -0.877765 -0.130927 0.294344 -0.946689 -0.0587768 0.449282 -0.891455 -0.0865359 0.801464 -0.59175 -0.0829931 0.806566 -0.585289 -0.103357 0.973388 -0.204533 -0.0984883 0.976313 -0.192646 -0.686607 -0.133737 -0.714622 -0.422687 -0.0699795 -0.90357 -0.193397 0.0266172 -0.98076 -0.142904 0.0177746 -0.989577 0.132054 0.118785 -0.9841 0.173665 0.110103 -0.978631 0.450113 0.199629 -0.870372 0.478614 0.19153 -0.856881 0.706924 0.255807 -0.65941 0.7229 0.248887 -0.644571 0.872546 0.282777 -0.398372 0.879883 0.27729 -0.385897 0.951495 0.280907 -0.125495 -0.506193 0.0323958 -0.861812 -0.474684 -0.0611495 -0.87803 -0.638664 -0.142687 -0.756141 0.26254 0.451209 -0.852926 0.00614939 0.311467 -0.950237 -0.119934 0.339227 -0.933028 -0.383148 0.062334 -0.921581 0.949199 0.284708 -0.134024 0.900801 0.418406 -0.116162 0.899404 0.409326 -0.153377 -0.719924 -0.00673296 -0.69402 -0.767969 -0.228839 -0.598211 -0.676709 -0.0797643 -0.731917 -0.552748 -0.0392684 -0.832423 -0.365998 0.139111 -0.92016 -0.214869 0.0871553 -0.972746 0.037173 0.237691 -0.970629 0.099444 0.212317 -0.972128 0.448881 0.372292 -0.812345 0.384641 0.380885 -0.84082 0.47857 0.416007 -0.773246 0.635733 0.448613 -0.628164 0.614861 0.426616 -0.663283 0.808085 0.457274 -0.371347 0.764295 0.395411 -0.509415 0.825613 0.436716 -0.35727 -0.258802 -0.0136149 -0.965835 -0.995522 -0.0030651 -0.0944831 -0.981219 -0.0124357 -0.192497 -0.965931 -0.00113358 -0.258797 -0.933459 -0.00603318 -0.358633 -0.786896 -0.0117661 -0.616974 -0.706996 -0.0186131 -0.706972 -0.174814 -0.0486655 -0.983398 -0.12963 -0.0268048 -0.9912 -0.50349 -0.013255 -0.863899 -0.677776 -0.017385 -0.735063 0.981208 0.146386 -0.125706 0.981443 0.146482 -0.123745 0.91211 0.136783 -0.386453 0.914192 0.137293 -0.381319 0.754714 0.113977 -0.646077 0.761745 0.115487 -0.6375 0.505608 0.0773363 -0.85929 0.520777 0.0804193 -0.849897 0.191926 0.0307913 -0.980926 0.216489 0.0356685 -0.975633 -0.135004 -0.0180199 -0.990681 -0.103263 -0.0117485 -0.994585 -0.424499 -0.0614626 -0.90334 -0.390468 -0.0546774 -0.918991 -0.648561 -0.0952532 -0.755179 -0.617321 -0.0888786 -0.781675 -0.258826 0 -0.965924 -0.258826 0 -0.965924 -0.707119 0 -0.707095 -0.707119 0 -0.707095 -0.965932 0 -0.258797 -0.965932 0 -0.258797 0.485579 0.109177 -0.867348 0.97215 0.0680151 -0.224275 0.989673 0.0709962 -0.124525 0.776876 -0.549424 -0.307565 0.95211 0.184454 -0.243851 0.770466 -0.040729 -0.636179 0.810719 0.19427 -0.552263 0.674395 0.020952 -0.738074 0.261524 0.125479 -0.957006 0.217828 0.0174328 -0.975831 0.524114 0.039554 -0.850729 0.10933 0.00876455 -0.993967 -0.128942 -0.00893508 -0.991612 -0.0995862 -0.0603198 -0.993199 -0.526094 -0.0332831 -0.849775 -0.57055 -0.340882 -0.747177 -0.395046 0.00903287 -0.918617 -0.250562 -0.935113 -0.250563 -0.25056 -0.935118 -0.250547 -0.207931 -0.776025 -0.595441 -0.199453 -0.689195 -0.696584 -0.0691835 -0.258199 -0.963611 -0.0691834 -0.258198 -0.963612 -0.160989 -0.600825 -0.783002 -0.684559 -0.684556 -0.250523 -0.684557 -0.684539 -0.250575 -0.508592 -0.508578 -0.694754 -0.508614 -0.50862 -0.694707 -0.189015 -0.189017 -0.963611 -0.18901 -0.189009 -0.963613 -0.935109 -0.250566 -0.250575 -0.935116 -0.250575 -0.250541 -0.694788 -0.186177 -0.694699 -0.694758 -0.186158 -0.694735 -0.258191 -0.0691811 -0.963614 -0.258205 -0.0691892 -0.963609 -0.547699 -0.0606473 -0.834474 -0.392067 -0.0378155 -0.919159 -0.18257 -0.0268083 -0.982827 -0.208608 -0.0276915 -0.977607 0.0394893 -0.00258806 -0.999217 0.0507707 -0.00243075 -0.998707 0.344297 0.0201026 -0.938646 0.272544 0.019348 -0.961949 0.516323 0.0340249 -0.855718 0.618688 0.050354 -0.784021 0.707369 0.0545218 -0.704739 0.857857 0.0697249 -0.509136 0.888632 0.0674084 -0.45364 0.9709 0.0844304 -0.224109 0.618139 0.0566084 -0.784028 0.826521 0.0743325 -0.557977 0.857576 0.0730159 -0.509149 0.980221 0.0902904 -0.17611 0.980622 0.085855 -0.176098 0.989481 0.0837392 -0.117961 -0.704232 -0.061391 -0.707311 -0.526075 -0.033523 -0.849777 -0.392609 -0.0314229 -0.919169 -0.129442 -0.002608 -0.991584 -0.184539 -0.00361243 -0.982818 0.109426 0.00752256 -0.993967 0.0386872 0.00676575 -0.999228 0.270226 0.0295312 -0.962344 0.343228 0.0325565 -0.938688 0.491222 0.0487164 -0.869671 0.672274 0.0549537 -0.73826 0 -0.195089 -0.980785 -0.0382528 -0.258629 -0.965219 0.025604 -0.555392 -0.831195 0 -0.608765 -0.79335 0 -0.831471 -0.555568 0.038243 -0.792784 -0.608301 -0.0507223 -0.979523 -0.194837 0 -0.965926 -0.25882 -0.811941 -0.100107 -0.575092 -0.163064 -0.070696 -0.984079 0.511685 -0.264246 -0.817528 0.74733 -0.219005 -0.627324 0.336245 -0.356767 -0.871583 0.089035 -0.308602 -0.947015 0.106554 -0.324781 -0.939768 -0.101969 -0.318392 -0.942459 -0.344293 -0.220542 -0.912592 -0.24306 -0.393728 -0.88651 -0.620549 -0.107389 -0.776779 -0.577943 -0.203902 -0.790193 -0.682765 -0.129165 -0.719131 -0.680157 -0.085843 -0.728023 0.987543 -0.106135 -0.116164 0.980545 -0.128681 -0.148235 0.912704 -0.168409 -0.372304 0.901132 -0.183387 -0.392849 0.773312 -0.225588 -0.592536 0.992669 0.0278004 -0.117627 0.990724 0.0197873 -0.134442 0.891789 0.0089485 -0.452362 0.913755 0.0540534 -0.402654 0.712556 -0.0596864 -0.699072 0.753697 -0.026172 -0.656701 0.521125 -0.0356201 -0.852736 0.495399 -0.0524629 -0.86708 0.278535 -0.0531118 -0.958957 0.171384 -0.0871985 -0.981338 0.0558089 -0.057012 -0.996812 -0.201698 -0.0950676 -0.974823 0.631546 -0.25968 -0.730559 0.519549 -0.257181 -0.814817 0.491294 -0.219425 -0.842902 0.119114 -0.172673 -0.97775 0.167334 -0.234361 -0.95764 -0.22494 -0.143297 -0.963778 -0.166617 -0.225677 -0.959848 -0.458609 -0.122966 -0.880089 -0.457276 -0.0806798 -0.885658 -0.551002 -0.0230385 -0.834186 -0.0911783 -0.195583 -0.976439 -0.229525 -0.209892 -0.950402 -0.139915 -0.984459 -0.106132 -0.162502 -0.979246 -0.12112 -0.418259 -0.853144 -0.311777 -0.41802 -0.85334 -0.311561 -0.647313 -0.590053 -0.482519 -0.647005 -0.590637 -0.482216 -0.775984 -0.251543 -0.578424 -0.775858 -0.252328 -0.578252 -0.112292 -0.987974 -0.106287 -0.129252 -0.984329 -0.119958 -0.382451 -0.853012 -0.355108 -0.383489 -0.852211 -0.355912 -0.591764 -0.589838 -0.549461 -0.592957 -0.587846 -0.550308 -0.709269 -0.251402 -0.658586 -0.621548 -0.102152 -0.776687 -0.659599 -0.248409 -0.709382 -0.710097 -0.247943 -0.659004 -0.100327 -0.980139 -0.171064 -0.0896748 -0.983791 -0.155287 -0.262883 -0.850162 -0.456198 -0.265705 -0.847122 -0.460201 -0.405744 -0.582536 -0.704289 -0.409366 -0.574237 -0.708993 -0.112595 -0.984324 -0.135755 -0.103263 -0.986626 -0.126117 -0.33137 -0.852059 -0.405203 -0.333379 -0.850297 -0.407251 -0.512211 -0.587584 -0.626406 -0.514773 -0.582757 -0.628811 -0.61449 -0.239953 -0.751548 -0.484564 -0.239816 -0.841241 -0.487062 -0.226195 -0.843568 -0.387211 -0.226927 -0.893629 -0.0676378 -0.983875 -0.165575 -0.0482886 -0.990156 -0.131379 -0.182493 -0.847161 -0.499013 -0.184997 -0.843486 -0.504288 -0.281043 -0.574294 -0.768896 -0.284363 -0.56415 -0.77516 -0.342398 0.0256682 -0.939204 -0.311602 -0.209674 -0.926791 -0.0762388 -0.940237 -0.331877 -0.0367993 -0.981921 -0.185681 -0.103896 -0.843664 -0.526722 -0.105255 -0.840619 -0.531301 -0.15962 -0.564421 -0.809908 -0.161534 -0.555898 -0.815404 -0.192634 0.0270673 -0.980897 -0.161703 -0.195555 -0.967269 -0.00690318 -0.984419 -0.175701 -0.00840478 -0.980751 -0.195081 -0.0215625 -0.84024 -0.541785 -0.0227346 -0.831256 -0.555425 -0.0335438 -0.555344 -0.830944 -0.0335499 -0.555261 -0.830999 -0.0399695 0.210977 -0.976674 -0.0182006 -0.195057 -0.980623 0.585521 -0.554928 -0.590948 0.729473 -0.504264 -0.462154 -0.106779 -0.982234 -0.154317 0.54669 -0.827847 -0.125694 0.495609 -0.868018 -0.0302723 -0.488758 -0.728962 -0.479303 -0.785632 -0.295897 -0.543348 -0.658939 -0.344273 -0.668787 -0.78126 -0.221878 -0.583441 -0.82138 -0.164657 -0.546097 -0.795595 -0.276379 -0.539114 -0.787821 -0.286873 -0.545015 -0.63696 -0.558886 -0.530969 -0.591836 -0.610248 -0.526618 -0.518363 -0.691324 -0.503359 -0.383219 -0.780781 -0.493482 0.197355 -0.964963 -0.17291 0.345267 -0.938471 -0.00795738 0.393885 -0.914566 -0.0917791 0.243675 -0.966868 -0.0760874 0.210574 -0.977336 -0.0217446 0.0128445 -0.991187 -0.131844 -0.0370654 -0.997864 -0.0537979 -0.402449 -0.852486 -0.33362 0.947201 -0.314494 -0.0624725 0.771161 -0.403742 -0.492243 0.903677 -0.406616 -0.134282 0.855785 -0.516476 -0.0297413 0.681055 -0.630998 -0.371492 0.661793 -0.731615 -0.163612 0.642214 -0.766414 0.0130147 0.35923 -0.89921 -0.249751 0.310474 -0.937079 -0.159652 0.20883 -0.955444 -0.208608 0.172476 -0.974208 -0.145504 0.0712551 -0.978432 -0.193891 0.0254925 -0.992625 -0.118515 0.855755 -0.440392 -0.271548 0.792091 -0.460572 -0.400582 0.718439 -0.66002 -0.21959 0.649008 -0.685568 -0.329825 0.578843 -0.795186 -0.180609 -0.376762 -0.448567 -0.810456 -0.13223 -0.537321 -0.832948 -0.0596845 -0.561604 -0.825251 0.0514068 -0.56901 -0.820722 0.198098 -0.590043 -0.782692 0.29859 -0.586236 -0.753108 0.464569 -0.579173 -0.669877 0.509255 -0.574901 -0.640428 0.433685 -0.774021 -0.461311 0.638572 -0.543502 -0.544822 0.569439 -0.730235 -0.377488 0.412825 -0.774695 -0.478982 0.358324 -0.859606 -0.364254 0.0171681 -0.879152 -0.476232 -0.655871 -0.346453 -0.670674 -0.591536 -0.39713 -0.701693 -0.454925 -0.553911 -0.697299 -0.124752 -0.7249 -0.677464 -0.172128 -0.695385 -0.697719 0.12413 -0.780609 -0.612569 -0.238542 -0.794798 -0.558027 -0.338574 -0.746746 -0.572484 -0.50153 -0.624005 -0.599237 -0.553666 -0.582042 -0.595551 -0.702355 -0.407815 -0.583425 -0.784102 -0.29477 -0.546163 -0.833406 -0.175169 -0.524167 0.792239 -0.598413 -0.119415 0.742822 -0.669217 -0.0191093 0.50245 -0.817437 -0.281675 0.438761 -0.884791 -0.156953 0.135424 -0.917517 -0.37393 0.0894693 -0.952875 -0.289871 -0.00148198 -0.946379 -0.323055 -0.0343758 -0.963362 -0.265992 -0.121691 -0.946193 -0.29985 -0.153364 -0.956616 -0.247719 -0.329594 -0.887515 -0.322001 -0.362091 -0.892017 -0.270548 0.361239 -0.590167 -0.721948 0.288622 -0.782174 -0.552179 0.126962 -0.781339 -0.611056 0.0541882 -0.887404 -0.457796 -0.0942527 -0.857235 -0.506225 -0.150237 -0.90139 -0.40611 -0.221286 -0.878514 -0.423373 -0.248954 -0.892798 -0.37541 -0.315755 -0.862873 -0.394649 -0.348479 -0.87332 -0.340405 -0.513773 -0.737373 -0.438541 -0.640754 -0.609356 -0.467033 -0.668812 -0.569281 -0.478131 -0.652475 -0.590814 -0.474569 -0.799705 -0.252574 -0.544682 0 0.258817 -0.965927 0 0.258817 -0.965927 0 0.611029 -0.791609 -0.0510182 0.706195 -0.706177 0 0.795073 -0.606514 0 0.965926 -0.25882 0 0.965926 -0.25882 -0.0383356 0.258626 -0.965216 -0.735312 0.427778 -0.525664 -0.140743 0.981923 -0.126567 -0.0765411 0.995563 -0.0547267 -0.14538 0.980612 -0.131395 -0.116912 0.983213 -0.140089 -0.120707 0.981976 -0.145443 -0.10267 0.982062 -0.158154 -0.0716852 0.989582 -0.124857 -0.0871779 0.982261 -0.166021 -0.0623337 0.982172 -0.17735 -0.0605412 0.983447 -0.170781 -0.0341335 0.981643 -0.187646 -0.0334327 0.982833 -0.181445 -0.0139654 0.982881 -0.183711 -0.0101024 0.986882 -0.161125 -0.00344116 0.96592 -0.258818 -0.805165 0.14296 -0.575562 -0.525348 0.763512 -0.375577 -0.645219 0.608998 -0.461317 -0.156043 0.981903 -0.107321 -0.228182 0.959854 -0.163135 -0.38227 0.882704 -0.273319 -0.805263 0.14161 -0.575759 -0.736095 0.141535 -0.661915 -0.736079 0.141833 -0.66187 -0.634334 0.141714 -0.759959 -0.634197 0.145701 -0.759319 -0.492907 0.145587 -0.857815 -0.492798 0.155569 -0.856124 -0.385011 0.156173 -0.909602 -0.331971 -0.0842991 -0.939515 -0.30217 0.170043 -0.937965 -0.217348 0.170249 -0.961132 -0.180062 -0.0501426 -0.982376 -0.149432 0.18248 -0.971788 -0.0361624 0.182062 -0.982622 -0.695825 0.523156 -0.492073 -0.633751 0.523061 -0.569883 -0.633741 0.523085 -0.569872 -0.546257 0.522781 -0.654449 -0.545484 0.525193 -0.653161 -0.424065 0.524892 -0.738009 -0.422677 0.530993 -0.734432 -0.28097 0.531108 -0.799363 -0.279906 0.53987 -0.793847 -0.150574 0.540251 -0.827923 -0.150384 0.548002 -0.822848 -0.0290188 0.547574 -0.836254 -0.0293179 0.610766 -0.791268 -0.457847 0.828677 -0.321978 -0.416222 0.828653 -0.37429 -0.41621 0.828666 -0.374276 -0.358881 0.828452 -0.429968 -0.358205 0.829258 -0.428975 -0.278592 0.829049 -0.484835 -0.277231 0.831253 -0.481832 -0.184315 0.831331 -0.524325 -0.183128 0.83459 -0.519542 -0.0985253 0.834833 -0.541615 -0.0981425 0.837706 -0.53723 -0.0201373 0.837465 -0.546119 -0.0194991 0.794922 -0.606398 -0.935117 0.250568 -0.250541 -0.935107 0.250573 -0.250574 -0.694757 0.186168 -0.694733 -0.694792 0.186167 -0.694698 -0.258205 0.0691851 -0.96361 -0.258189 0.0691847 -0.963614 -0.68455 0.684548 -0.250571 -0.684566 0.684549 -0.250522 -0.508621 0.508608 -0.69471 -0.508581 0.508587 -0.694755 -0.189009 0.189011 -0.963613 -0.189016 0.189016 -0.963611 -0.250564 0.935117 -0.250548 -0.25056 0.935114 -0.250564 -0.186155 0.69475 -0.694744 -0.186159 0.694755 -0.694738 -0.0691841 0.258199 -0.963611 -0.0691827 0.258197 -0.963612 -0.240731 0.650298 -0.720528 0.463921 0.883557 -0.0640623 0.705678 0.706869 -0.0485199 0.202346 0.644368 -0.737459 0.241038 0.635221 -0.733754 0.50491 0.651009 -0.566792 0.548437 0.630033 -0.549796 0.927508 0.372955 0.0251886 0.915518 0.394774 -0.077334 0.759298 0.502938 -0.41294 0.830113 0.495058 -0.256573 0.917785 0.383158 0.104212 0.605469 0.790924 -0.0885781 0.613071 0.780064 -0.12508 0.447207 0.844933 -0.293417 0.517369 0.83313 -0.195508 0.289086 0.875196 -0.387895 -0.822072 0.184887 -0.53853 -0.828875 0.143109 -0.540819 -0.672266 0.539987 -0.506432 0.788661 0.450224 -0.418703 0.654336 0.473934 -0.589263 0.593901 0.504253 -0.626906 0.351189 0.475826 -0.806385 0.291535 0.4955 -0.818222 -0.0376164 0.4253 -0.904271 -0.321878 0.454027 -0.830815 -0.508968 0.467275 -0.722915 -0.718455 0.202544 -0.665431 -0.693265 0.232554 -0.68213 -0.609289 0.305003 -0.731943 -0.632306 0.284347 -0.720649 -0.422088 0.355471 -0.833956 -0.264566 0.426772 -0.864795 0.750367 0.64858 -0.127646 0.735513 0.655384 -0.171736 0.600481 0.722082 -0.34354 0.662959 0.709375 -0.239317 0.364287 0.772107 -0.520717 0.43285 0.784801 -0.443541 0.0732382 0.748108 -0.659523 0.132697 0.777735 -0.614426 -0.189622 0.66452 -0.722812 -0.103563 0.490797 -0.865097 -0.2342 0.439963 -0.866939 -0.0170054 0.989214 -0.145488 0.31053 0.936921 0.16047 -0.185678 0.956059 -0.22688 -0.729341 0.427567 -0.534087 -0.705034 0.476092 -0.525607 -0.468311 0.736015 -0.488842 -0.35857 0.824486 -0.437779 -0.240515 0.886898 -0.394416 -0.155071 0.925759 -0.344852 0.00143954 0.962994 -0.269518 0.218383 0.969242 -0.113484 -0.64046 0.608788 -0.468175 -0.515469 0.762989 -0.39005 -0.41718 0.841873 -0.342361 -0.361464 0.881366 -0.3042 -0.225419 0.946675 -0.2302 -0.038904 0.994796 -0.0941656 0.0609876 0.964458 -0.257102 0.158264 0.96971 -0.186054 0.337504 0.938405 -0.074075 0.497061 0.859023 -0.122514 0.564872 0.824938 -0.019919 0.30395 0.916776 -0.259107 0.376421 0.910812 -0.169493 0.0721951 0.9176 -0.390894 -0.03419 0.870146 -0.491606 -0.149725 0.824155 -0.546215 -0.0325221 0.881204 -0.471616 -0.396389 0.68768 -0.608253 -0.320977 0.752357 -0.575268 -0.606292 0.496849 -0.620928 -0.570075 0.546148 -0.61379 -0.80732 0.175276 -0.563482 -0.760271 0.318109 -0.566388 -0.852655 0.0520922 -0.519872 -0.813644 0.0832749 -0.575368 -0.837151 0.0401771 -0.545495 -0.1951 0 -0.980783 -0.258825 0.00166411 -0.965923 -0.442271 0 -0.896882 -0.608823 0 -0.793306 -0.707117 0.00222101 -0.707093 -0.980798 0 -0.195027 -0.96593 0.00166535 -0.258797 -0.896825 0 -0.442385 -0.793313 0 -0.608814 -0.827594 -0.00222475 -0.561322 -0.713712 -0.00786729 -0.700395 -0.710698 -0.00373156 -0.703487 -0.494649 0.106766 -0.86251 -0.199674 0.033308 -0.979296 0.122824 0.0790216 -0.989277 0.141952 0.0682514 -0.987518 0.466323 0.101162 -0.878811 0.475516 0.0951353 -0.874548 0.740708 0.110787 -0.66263 0.742687 0.109072 -0.660696 0.912066 0.108588 -0.395404 0.966895 0.208441 -0.147199 0.912587 0.114055 -0.392654 -0.556155 0.0600586 -0.828905 -0.379074 0.163358 -0.910833 -0.656003 -0.0476637 -0.753252 -0.636596 -0.0335655 -0.770466 -0.226934 0.0479721 -0.972728 -0.241441 0.152515 -0.958356 -0.205433 0.17243 -0.963361 -0.175039 0.185359 -0.966956 0.00297585 0.253215 -0.967405 0.101987 0.226048 -0.968763 0.39123 0.304728 -0.868378 0.439978 0.279884 -0.853279 0.697258 0.288032 -0.656406 0.717133 0.273955 -0.640835 0.831338 0.27275 -0.484237 0.94951 0.193069 -0.247297 0.940887 0.189711 -0.280609 0.986844 0.098011 -0.128584 -0.0387765 -0.194943 -0.980048 -0.10984 -0.552212 -0.826437 -0.163171 -0.820326 -0.548124 -0.962635 -0.191477 -0.191497 -0.816088 -0.54528 -0.191495 -0.816092 -0.545303 -0.191413 -0.545292 -0.816094 -0.191435 -0.545293 -0.81609 -0.191447 -0.191479 -0.96264 -0.191468 -0.191481 -0.962637 -0.191479 -0.163171 -0.820328 -0.548122 -0.464677 -0.695443 -0.548119 -0.464676 -0.695438 -0.548126 -0.695443 -0.464669 -0.548126 -0.695443 -0.46467 -0.548125 -0.962647 -0.191496 -0.191417 -0.882886 -0.17563 -0.435508 -0.817956 -0.172087 -0.54894 -0.783617 -0.155865 -0.601373 -0.604407 -0.12022 -0.787553 -0.109841 -0.552206 -0.82644 -0.312793 -0.468129 -0.826448 -0.312793 -0.468129 -0.826448 -0.468125 -0.312784 -0.826454 -0.468154 -0.312817 -0.826425 -0.548902 -0.119431 -0.827311 -0.440569 -0.0876336 -0.893431 -0.0387764 -0.194945 -0.980047 -0.110429 -0.165269 -0.980047 -0.110426 -0.165262 -0.980048 -0.16526 -0.110426 -0.980049 -0.165263 -0.110428 -0.980048 -0.194942 -0.0387759 -0.980048 -0.194953 -0.0387812 -0.980046 -0.795759 -0.0287254 -0.604932 -0.713152 -0.0254406 -0.700548 -0.493203 -0.0214359 -0.86965 -0.590851 -0.0210933 -0.806505 -0.197805 -0.0124457 -0.980163 -0.294303 -0.0125618 -0.955629 0.145451 -0.00128346 -0.989365 0.0684986 -0.0015589 -0.99765 0.48083 0.0103171 -0.876753 0.433746 0.0101362 -0.900978 0.749003 0.0202445 -0.662257 0.728346 0.0202206 -0.684912 0.917888 0.0271408 -0.39591 0.91221 0.0271899 -0.408819 0.991238 0.0308787 -0.128428 0.990753 0.0309095 -0.132112 0 -0.195089 -0.980785 0 -0.195089 -0.980785 0 -0.555573 -0.831468 0 -0.555573 -0.831468 0 -0.83147 -0.55557 0 -0.83147 -0.55557 0 -0.980786 -0.195089 0 -0.980786 -0.195089 0.991184 -0.0121141 -0.131935 -0.829193 -0.0418319 -0.557396 -0.796005 -0.0181541 -0.605017 -0.630282 -0.0688594 -0.773307 -0.59018 -0.0445707 -0.806041 -0.332322 -0.0927443 -0.938595 -0.292785 -0.0702442 -0.953595 0.0394228 -0.10669 -0.99351 0.0696751 -0.0887092 -0.993618 0.41649 -0.105982 -0.902942 0.433364 -0.094219 -0.89628 0.652635 -0.0932119 -0.751917 0.727942 -0.0596924 -0.683035 0.778068 -0.0821947 -0.62278 0.873023 -0.0732302 -0.48215 0.911948 -0.0439456 -0.407945 0.938848 -0.0611861 -0.338851 0.986073 -0.0456753 -0.159919 0.988927 -0.0693069 -0.131225 -0.0491219 -0.983 -0.176914 -0.172698 -0.977006 -0.125039 -0.149274 -0.98313 -0.105699 -0.441601 -0.84097 -0.312662 -0.441764 -0.840832 -0.312803 -0.800121 -0.197142 -0.566517 -0.114093 -0.98793 -0.104773 -0.136363 -0.983109 -0.122077 -0.403368 -0.84078 -0.361087 -0.40338 -0.84077 -0.361096 -0.6188 -0.557027 -0.553902 -0.618741 -0.557132 -0.553863 -0.118373 -0.983115 -0.139543 -0.0969895 -0.988224 -0.118348 -0.343415 -0.840503 -0.419072 -0.343708 -0.840235 -0.419369 -0.526548 -0.556721 -0.642502 -0.526793 -0.556229 -0.642727 -0.123386 -0.967898 -0.218972 -0.0872156 -0.982955 -0.161842 -0.257344 -0.839989 -0.477695 -0.257774 -0.839489 -0.478342 -0.394254 -0.555844 -0.731848 -0.394779 -0.55453 -0.732561 -0.35092 -0.195736 -0.91572 -0.465315 -0.194794 -0.863445 -0.46498 -0.196883 -0.863151 -0.621484 -0.197057 -0.758239 -0.621368 -0.19768 -0.758171 -0.730362 -0.197879 -0.65377 -0.730428 -0.197549 -0.653796 -0.800055 -0.197694 -0.566418 -0.677631 -0.557321 -0.479802 -0.726572 -0.467068 -0.503926 -0.629484 -0.636487 -0.445684 -0.0649335 -0.983117 -0.171066 -0.0424081 -0.989476 -0.138342 -0.15901 -0.839704 -0.519243 -0.159318 -0.839181 -0.519994 -0.243542 -0.554857 -0.795501 -0.244013 -0.553205 -0.796506 -0.292265 0.0455657 -0.955251 -0.265275 -0.19228 -0.944806 -0.140856 -0.189587 -0.971708 -0.140592 -0.192217 -0.971229 -0.119594 -0.552346 -0.824992 -0.119329 -0.553762 -0.82408 -0.0780549 -0.839099 -0.53835 -0.0778953 -0.83954 -0.537684 -0.0236184 -0.986377 -0.162796 -0.0281336 -0.983005 -0.181412 -0.0274462 -0.195016 -0.980416 -0.0276804 -0.18957 -0.981477 -0.0230237 -0.555426 -0.831247 -0.0232259 -0.552282 -0.833334 -0.015663 -0.831367 -0.555502 -0.014829 -0.839051 -0.54385 -0.00587674 -0.980769 -0.195085 -0.00720819 -0.976351 -0.216072 0.584269 -0.698784 -0.412711 0.784276 -0.587372 -0.199762 0.781376 -0.623302 0.0307646 -0.326343 -0.843122 -0.427372 0.021741 -0.326503 -0.944946 0.205793 -0.978327 -0.0229449 -0.138138 -0.982754 -0.12293 -0.825848 -0.19733 -0.528238 -0.343784 -0.248692 -0.905519 -0.49854 -0.274691 -0.822194 -0.637713 -0.20534 -0.742399 -0.648777 -0.202362 -0.733579 -0.689715 -0.310365 -0.654192 -0.698486 -0.303911 -0.647886 -0.0014936 -0.311467 -0.950256 -0.0477267 -0.518366 -0.853826 -0.402314 -0.387998 -0.829218 -0.446084 -0.50887 -0.736248 -0.475108 -0.496077 -0.72676 -0.532056 -0.584668 -0.612437 -0.71923 -0.466836 -0.51456 -0.642562 -0.584399 -0.495572 -0.433015 -0.81984 -0.374647 -0.370333 -0.858654 -0.354355 -0.259053 -0.923025 -0.28446 -0.174445 -0.952376 -0.250098 0.790362 -0.564127 -0.238932 0.866756 -0.497256 -0.0383466 0.924578 -0.349806 -0.150968 0.689468 -0.708241 -0.15175 0.652767 -0.753734 -0.0760376 0.581427 -0.811724 -0.0551952 0.539845 -0.833553 -0.117288 0.493439 -0.869221 -0.0311919 0.445896 -0.739342 -0.504529 0.425957 -0.739136 -0.521765 0.347472 -0.863405 -0.365781 0.268133 -0.854229 -0.445418 0.198771 -0.92867 -0.31315 0.121519 -0.914148 -0.386738 0.0721541 -0.952305 -0.296494 0.197368 -0.956984 -0.212669 0.160722 -0.975843 -0.147984 0.126231 -0.736634 -0.664406 0.196107 -0.550703 -0.811337 0.399697 -0.567191 -0.720094 0.448906 -0.339429 -0.826602 0.629867 -0.335685 -0.700416 0.691041 -0.65837 -0.298348 0.658916 -0.669864 -0.342217 0.583505 -0.789192 -0.191566 0.505629 -0.809934 -0.297233 0.435467 -0.88542 -0.162482 0.353362 -0.899059 -0.258512 0.301932 -0.939222 -0.163397 0.389071 -0.91646 -0.0934079 0.340652 -0.940151 -0.00852924 0.212782 -0.965627 -0.149296 0.234987 -0.969306 -0.0722985 -0.81919 -0.215302 -0.531577 -0.813114 -0.240735 -0.529993 -0.805459 -0.235102 -0.544026 -0.583015 -0.540674 -0.606437 -0.782103 -0.264595 -0.564184 -0.744946 -0.378512 -0.54935 -0.855443 -0.0914674 -0.509755 -0.847727 -0.101114 -0.520706 -0.819756 -0.0817947 -0.566841 -0.831457 -0.0764829 -0.550299 -0.289995 -0.927958 -0.234087 -0.446707 -0.840986 -0.30528 -0.464103 -0.824531 -0.323662 -0.634496 -0.636662 -0.438266 -0.696752 -0.499393 -0.51492 -0.698022 -0.496548 -0.515951 -0.430423 -0.768521 -0.473404 -0.365084 -0.719544 -0.590737 -0.26394 -0.771792 -0.578509 -0.18578 -0.651312 -0.735717 -0.128074 -0.663037 -0.737549 -0.0688776 -0.501559 -0.862377 0.226685 -0.561962 -0.795496 0.274292 -0.346012 -0.89724 0.398033 -0.325282 -0.857765 0.977404 -0.181102 -0.109007 0.856666 -0.348325 -0.380516 0.903464 -0.322528 -0.282362 0.85875 -0.356309 -0.36823 0.832163 -0.368168 -0.414676 0.777544 -0.394737 -0.489497 0.734047 -0.405636 -0.544642 0.671993 -0.425871 -0.605854 0.872852 -0.360817 -0.328544 0.517503 -0.556397 -0.650087 0.366006 -0.55813 -0.744668 0.296414 -0.742674 -0.600479 0.130826 -0.737971 -0.66203 0.0641094 -0.844752 -0.531305 -0.246866 -0.781181 -0.573423 -0.133381 -0.859695 -0.493086 -0.195042 -0.904451 -0.379377 -0.204381 -0.900252 -0.384416 -0.133297 -0.938196 -0.319407 0.0575391 -0.979049 -0.195327 0.0129926 -0.992723 -0.119716 0.00180252 -0.991359 -0.131165 -0.0271048 -0.996088 -0.0841112 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.610781 -0.7918 -0.0510305 0.706194 -0.706177 0 0.794906 -0.606732 0 0.965925 -0.258821 0 0.965925 -0.258821 -0.720375 0.466878 -0.512919 -0.0740836 0.995856 -0.0527518 -0.135584 0.983113 -0.122907 -0.113 0.988615 -0.0993514 -0.158689 0.968961 -0.189556 -0.11515 0.983038 -0.142748 -0.0952077 0.983152 -0.156034 -0.0639198 0.990614 -0.12082 -0.0791902 0.983067 -0.165252 -0.0528209 0.982986 -0.175923 -0.0483116 0.986594 -0.155876 -0.0289128 0.978545 -0.203992 -0.027074 0.982932 -0.181968 -0.0103514 0.982982 -0.183409 -0.00869806 0.984975 -0.17248 -0.00258653 0.965922 -0.25882 -0.79863 0.197076 -0.56864 -0.509761 0.780003 -0.36296 -0.628336 0.636441 -0.447366 -0.15096 0.983098 -0.103579 -0.221226 0.962417 -0.157523 -0.370342 0.890682 -0.26369 -0.798566 0.197601 -0.568547 -0.726336 0.197487 -0.658357 -0.726296 0.197898 -0.658279 -0.615516 0.197687 -0.762928 -0.615558 0.197072 -0.763054 -0.45843 0.196916 -0.866641 -0.458487 0.194729 -0.867104 -0.281955 0.194886 -0.939426 -0.281907 0.191831 -0.940069 -0.137659 0.192115 -0.97167 -0.13754 0.18958 -0.972184 -0.0269094 0.189549 -0.981503 -0.0290396 0.258709 -0.965519 -0.678695 0.557269 -0.478355 -0.61529 0.557122 -0.557703 -0.615295 0.55711 -0.55771 -0.521616 0.556679 -0.646548 -0.521791 0.556176 -0.64684 -0.388684 0.55587 -0.734802 -0.38899 0.554524 -0.735657 -0.23917 0.554823 -0.79685 -0.239334 0.553178 -0.797943 -0.116811 0.55374 -0.824456 -0.116809 0.552334 -0.825399 -0.0210194 0.552225 -0.83343 -0.0217025 0.610637 -0.791613 -0.443268 0.840795 -0.310768 -0.401153 0.840744 -0.363629 -0.401135 0.840761 -0.363609 -0.340215 0.840481 -0.421718 -0.340464 0.840191 -0.422093 -0.253699 0.839997 -0.479627 -0.25399 0.839509 -0.480328 -0.156127 0.839702 -0.52012 -0.156287 0.839182 -0.520911 -0.0762237 0.839552 -0.537906 -0.0762561 0.839114 -0.538585 -0.0149297 0.839073 -0.543815 -0.0136701 0.794832 -0.606675 -0.935117 0.250568 -0.250541 -0.935107 0.250573 -0.250574 -0.694757 0.186168 -0.694733 -0.694792 0.186167 -0.694699 -0.258205 0.0691851 -0.96361 -0.258189 0.0691847 -0.963614 -0.68455 0.684547 -0.250571 -0.684566 0.684549 -0.250524 -0.508621 0.508608 -0.694711 -0.508581 0.508587 -0.694755 -0.189009 0.189011 -0.963613 -0.189016 0.189016 -0.963611 -0.250563 0.935116 -0.25055 -0.250559 0.935114 -0.250565 -0.186155 0.69475 -0.694743 -0.186158 0.694755 -0.694738 -0.0691838 0.258199 -0.963611 -0.0691831 0.258198 -0.963612 -0.852538 0.109504 -0.511065 -0.813834 0.131975 -0.565913 0.213306 0.976338 -0.035554 0.91868 0.367685 -0.144345 0.833992 0.438147 -0.335386 0.798987 0.473261 -0.371004 0.625128 0.52558 -0.577045 0.583033 0.549499 -0.598434 0.317124 0.555124 -0.768941 0.278336 0.567207 -0.775116 0.208562 0.748839 -0.62908 0.138922 0.722834 -0.676913 0.511101 0.729774 -0.4541 0.433352 0.723338 -0.537577 0.733444 0.634438 -0.244024 0.353408 0.899053 -0.25847 -0.13339 0.859699 -0.493076 0.110687 0.923565 -0.367118 0.208507 0.920057 -0.331692 0.43552 0.885403 -0.162432 0.505684 0.809927 -0.297156 0.235945 0.968949 -0.073952 0.193939 0.963535 -0.184356 0.0932796 0.962314 -0.255443 0.268113 0.957824 -0.10339 -0.110411 0.927778 -0.356422 0.0418687 0.969825 -0.240181 -0.316872 0.839087 -0.442183 -0.201819 0.908463 -0.366012 -0.0370432 0.993232 -0.110078 -0.0985092 0.980576 -0.169606 -0.175768 0.958101 -0.226159 -0.0090081 0.996583 -0.0821061 -0.33666 0.887882 -0.31357 -0.202391 0.958479 -0.200888 -0.489494 0.778652 -0.392552 -0.392716 0.864313 -0.314225 -0.714447 0.466646 -0.521352 -0.637716 0.205346 -0.742396 -0.648693 0.202392 -0.733645 -0.68964 0.310432 -0.654239 -0.21666 0.637815 -0.739087 -0.126633 0.390694 -0.911769 -0.0859192 0.405493 -0.910051 -0.346292 0.327825 -0.878984 -0.376695 0.323982 -0.867834 -0.446121 0.508853 -0.736237 -0.475108 0.496075 -0.726762 -0.534564 0.588721 -0.606341 -0.813889 0.241327 -0.528531 -0.799245 0.230619 -0.554997 -0.740418 0.370535 -0.560789 -0.698492 0.303918 -0.647875 -0.859511 0.0793305 -0.504923 -0.80611 0.0976376 -0.583656 -0.830548 0.0605966 -0.55364 0.474933 0.880022 0.000613388 0.543778 0.829817 -0.125335 0.619073 0.785192 -0.0149121 0.66166 0.74397 -0.0933558 0.655762 0.741077 -0.14416 0.765082 0.642001 -0.0498465 0.822521 0.542008 -0.172298 0.872121 0.488672 -0.0245753 0.665441 0.65513 -0.357762 0.583502 0.789195 -0.191564 0.357301 0.851077 -0.384712 0.257545 0.867681 -0.425206 0.0641132 0.844755 -0.5313 -0.246909 0.781161 -0.573431 -0.357557 0.71343 -0.602636 -0.430367 0.768565 -0.473384 -0.698025 0.496547 -0.515947 -0.622718 0.636174 -0.455527 -0.82388 0.1973 -0.531313 -0.645072 0.586053 -0.49033 -0.578784 0.537369 -0.613387 -0.268414 0.778203 -0.567762 -0.187502 0.654184 -0.732726 -0.0441672 0.693253 -0.719339 0.0493441 0.429108 -0.901905 -0.492427 0.323555 -0.807978 0.113576 0.328984 -0.937481 0.361259 0.351439 -0.863703 0.396328 0.337627 -0.853775 0.666026 0.332638 -0.667653 0.700779 0.311269 -0.641888 0.867967 0.277472 -0.411877 0.893704 0.25001 -0.372544 0.986315 0.149855 0.0687509 0.965376 0.242573 -0.0959604 -0.258826 0 -0.965924 -0.258826 0 -0.965924 -0.707119 0 -0.707095 -0.707119 0 -0.707095 -0.965932 0 -0.258797 -0.965932 0 -0.258797 0.991185 0.0121178 -0.131932 -0.829193 0.0418389 -0.557394 -0.796029 0.0181841 -0.604985 -0.630288 0.0689144 -0.773297 -0.590063 0.0445503 -0.806127 -0.332323 0.0927409 -0.938595 -0.29277 0.0702284 -0.953601 -0.0627008 0.0967523 -0.993332 0.0694436 0.0653446 -0.995443 0.13274 0.0926696 -0.986809 0.416489 0.105996 -0.902941 0.433362 0.0942289 -0.89628 0.720676 0.0912977 -0.687234 0.726726 0.0856367 -0.681569 0.910014 0.0682364 -0.408923 0.910939 0.0668233 -0.407094 0.989741 0.0435453 -0.136077 0.9801 0.0747181 -0.183907 -0.250562 -0.935113 -0.250563 -0.25056 -0.935116 -0.250553 -0.186157 -0.694755 -0.694738 -0.186157 -0.694749 -0.694744 -0.0691834 -0.258197 -0.963612 -0.0691835 -0.258199 -0.963611 -0.684559 -0.684555 -0.250527 -0.684557 -0.68454 -0.250571 -0.508591 -0.508579 -0.694754 -0.508613 -0.508619 -0.694708 -0.189014 -0.189017 -0.963611 -0.18901 -0.18901 -0.963613 -0.935109 -0.250566 -0.250574 -0.935116 -0.250575 -0.250541 -0.694788 -0.186177 -0.6947 -0.694758 -0.186158 -0.694735 -0.258191 -0.0691812 -0.963614 -0.258205 -0.0691892 -0.963609 -0.713055 0.0275986 -0.700565 -0.795843 0.0266257 -0.604918 -0.590678 0.0233281 -0.80657 -0.526789 0.0205512 -0.849748 -0.294245 0.0141655 -0.955625 -0.278181 0.0133268 -0.960436 0.0685557 0.0025166 -0.997644 0.102035 0.000619509 -0.994781 0.433769 -0.00892279 -0.90098 0.480774 -0.0116064 -0.876768 0.728273 -0.0195554 -0.685008 0.678852 -0.0163462 -0.734093 0.794872 -0.0226446 -0.606355 0.912272 -0.0268275 -0.408706 0.91573 -0.0271287 -0.400877 0.990748 -0.0310424 -0.13212 0.989743 -0.0308419 -0.139489 -1.20529e-06 -0.258818 -0.965926 -0.0988722 -0.607833 -0.787885 0 -0.707116 -0.707098 0 -0.258817 -0.965927 0 -0.794947 -0.606679 0 -0.965926 -0.25882 0 -0.965926 -0.25882 0.966907 -0.208368 -0.147221 0.782771 -0.156134 -0.602405 0.741066 -0.105507 -0.663091 0.672487 -0.108026 -0.732183 0.466786 -0.0949006 -0.879264 0.474886 -0.102455 -0.874063 0.12427 -0.0666226 -0.990009 0.0998497 -0.0446276 -0.994001 -0.228491 -0.0563153 -0.971916 -0.279427 -0.0172273 -0.960012 0.985312 -0.0983543 -0.139597 0.952881 -0.17105 -0.250521 0.899178 -0.183041 -0.397461 0.909909 -0.175204 -0.37599 0.994488 -0.104586 -0.00741807 -0.828533 -0.00161543 -0.559938 0.0920965 -0.287617 -0.953307 -0.205522 -0.172778 -0.96328 -0.241816 -0.152669 -0.958237 -0.379156 -0.163664 -0.910744 -0.622644 -0.0158418 -0.782344 -0.550297 -0.0408893 -0.833967 -0.528459 -0.0524667 -0.847336 -0.676621 -0.0159349 -0.736159 -0.716654 0.00726911 -0.697391 -0.713814 0.00355201 -0.700327 0.831463 -0.273043 -0.483856 0.699246 -0.273647 -0.660433 0.714113 -0.287788 -0.638138 0.480654 -0.283382 -0.829859 0.443284 -0.261405 -0.857418 0.281257 -0.277646 -0.91859 0.0121403 -0.198068 -0.980113 -0.217754 -0.170051 -0.961075 -0.0573205 -0.982508 -0.17718 -0.101992 -0.987852 -0.117245 -0.45615 -0.828509 -0.324808 -0.531263 -0.763515 -0.367157 -0.382958 -0.882585 -0.272738 -0.806237 -0.142893 -0.574077 -0.418223 -0.828352 -0.372722 -0.418268 -0.828315 -0.372754 -0.636425 -0.522777 -0.567158 -0.636439 -0.522749 -0.567167 -0.548378 -0.524798 -0.651052 -0.549491 -0.522427 -0.652019 -0.360384 -0.828888 -0.427865 -0.361232 -0.828091 -0.428693 -0.122269 -0.981822 -0.145177 -0.141576 -0.981853 -0.126176 -0.128451 -0.984897 -0.116097 -0.169037 -0.978232 -0.120369 -0.153627 -0.981899 -0.110786 -0.111882 -0.982012 -0.152103 -0.0950642 -0.98187 -0.163997 -0.28099 -0.828707 -0.484034 -0.279077 -0.830898 -0.481378 -0.427525 -0.524532 -0.736267 -0.425133 -0.530562 -0.733325 -0.386867 -0.155784 -0.908881 -0.495466 -0.155186 -0.854653 -0.496887 -0.145346 -0.855557 -0.637372 -0.145443 -0.756705 -0.637973 -0.141493 -0.756948 -0.739048 -0.141612 -0.6586 -0.739068 -0.141484 -0.658605 -0.80633 -0.141571 -0.574273 -0.694303 -0.523006 -0.494376 -0.74165 -0.427639 -0.516798 -0.646126 -0.608913 -0.460158 -0.148977 -0.949841 -0.27497 -0.049239 -0.989035 -0.139231 -0.186157 -0.830942 -0.524291 -0.184046 -0.834241 -0.519777 -0.283697 -0.53064 -0.79871 -0.280995 -0.53953 -0.793693 -0.333666 0.10011 -0.937361 -0.302553 -0.169858 -0.937875 -0.0335649 -0.982476 -0.183343 -0.0333051 -0.982672 -0.182338 -0.0994339 -0.834518 -0.541934 -0.0982292 -0.837397 -0.537696 -0.15197 -0.53994 -0.827871 -0.150321 -0.547696 -0.823063 -0.180809 0.0515454 -0.982167 -0.149784 -0.182334 -0.971761 -0.035691 -0.258653 -0.965311 -0.0402935 -0.181959 -0.98248 -0.0264497 -0.610612 -0.791488 -0.0312028 -0.5473 -0.836354 -0.0225346 -0.794745 -0.606525 -0.0184895 -0.837075 -0.546775 -0.0123421 -0.965852 -0.2588 -0.00686223 -0.982868 -0.184181 -0.165737 -0.929965 -0.328172 -0.124276 -0.97995 -0.155737 -0.422091 -0.355472 -0.833953 -0.421719 -0.355573 -0.834099 -0.599771 -0.24396 -0.762075 -0.829662 -0.0780854 -0.552779 -0.512774 -0.471947 -0.717168 -0.487647 -0.485252 -0.725763 -0.2407 -0.650317 -0.720522 -0.845822 -0.0546518 -0.530659 -0.69325 -0.232579 -0.682138 -0.751785 -0.159574 -0.639809 -0.719633 -0.210718 -0.661608 -0.835771 -0.033535 -0.548053 0.169061 -0.971289 -0.16738 0.301983 -0.953223 -0.0131579 0.349235 -0.932526 -0.0918206 0.208305 -0.974877 -0.0788966 0.177468 -0.983711 -0.0285988 -0.0199635 -0.991246 -0.130508 -0.0630942 -0.996097 -0.0617172 -0.371022 -0.881979 -0.290614 0.669214 -0.660123 -0.341159 0.498821 -0.857503 -0.125962 0.446799 -0.893931 -0.035467 0.603895 -0.551701 -0.575271 0.762502 -0.518686 -0.386724 0.830017 -0.495111 -0.256783 0.406556 -0.57022 -0.713836 0.317813 -0.573022 -0.755408 0.211008 -0.556788 -0.803407 0.153286 -0.552364 -0.819389 -0.0580249 -0.49454 -0.867216 0.354911 -0.787469 -0.503915 0.508109 -0.760558 -0.4042 0.662886 -0.709414 -0.239402 0.759215 -0.502971 -0.413052 0.915518 -0.394775 -0.0773285 -0.264566 -0.426775 -0.864793 -0.103303 -0.490242 -0.865443 -0.189629 -0.664527 -0.722803 0.053004 -0.758701 -0.64928 0.0633954 -0.762821 -0.643494 0.219741 -0.779258 -0.586916 0.367259 -0.788714 -0.493002 0.468795 -0.575199 -0.670357 0.62575 -0.55249 -0.550628 0.746296 -0.654738 -0.119833 0.69129 -0.722122 -0.0256518 0.447145 -0.844948 -0.293469 0.376366 -0.910828 -0.169531 0.0722053 -0.917606 -0.390878 -0.831745 -0.143031 -0.536416 -0.819244 -0.187544 -0.54191 -0.734387 -0.427434 -0.527235 -0.66958 -0.538131 -0.511936 -0.705032 -0.476101 -0.525603 -0.46823 -0.736084 -0.488816 -0.358567 -0.824485 -0.437784 -0.240572 -0.886872 -0.394441 -0.220149 -0.897192 -0.382858 0.0229405 -0.951436 -0.306992 0.620582 -0.7682 -0.15731 0.581611 -0.813466 -0.00160296 0.303931 -0.916784 -0.2591 0.252644 -0.952357 -0.170843 0.15592 -0.964042 -0.215204 0.120843 -0.98026 -0.156484 0.0251975 -0.979591 -0.199418 -0.0181449 -0.991542 -0.128508 -0.206109 -0.942582 -0.26279 -0.413262 -0.844884 -0.339685 -0.417182 -0.841873 -0.342358 -0.515681 -0.762797 -0.390146 -0.64053 -0.608669 -0.468234 0.891527 -0.413189 -0.185618 0.810626 -0.584253 -0.0391623 0.600408 -0.72211 -0.343609 0.517306 -0.833155 -0.195567 0.289085 -0.875197 -0.387893 -0.0341957 -0.870147 -0.491605 -0.0246939 -0.873206 -0.486725 -0.160499 -0.832838 -0.529737 -0.315784 -0.746246 -0.586001 -0.404182 -0.69346 -0.596448 -0.567217 -0.542211 -0.619897 -0.610882 -0.499778 -0.61404 -0.747524 -0.300486 -0.592382 -0.817102 -0.180668 -0.547452 -0.850751 -0.0609856 -0.522018 -0.0444687 0.983427 -0.175768 -0.0702595 0.996153 -0.0523686 -0.124788 0.980386 -0.15255 -0.120529 0.986529 -0.110608 -0.129297 0.984321 -0.119977 -0.06244 0.983318 -0.170842 -0.126724 0.940891 -0.314111 -0.0694291 0.990306 -0.120309 -0.0938214 0.984084 -0.150915 -0.113624 0.984012 -0.137147 -0.0257492 0.989173 -0.144481 -0.0354262 0.98304 -0.179939 -0.0124918 0.983059 -0.182866 -0.0111454 0.984863 -0.172978 -0.00184148 0.965924 -0.258819 -0.775886 0.252093 -0.578317 -0.484359 0.796918 -0.360997 -0.647259 0.59017 -0.482447 -0.143401 0.984306 -0.102852 -0.209865 0.965137 -0.156418 -0.351424 0.898826 -0.261939 -0.776092 0.251287 -0.578391 -0.709545 0.251157 -0.658382 -0.709997 0.247863 -0.659142 -0.659594 0.248317 -0.709419 -0.627915 0.121601 -0.768724 -0.606504 0.239876 -0.758032 -0.484916 0.239598 -0.8411 -0.485607 0.225941 -0.844474 -0.387108 0.226662 -0.89374 -0.341104 -0.0289212 -0.939581 -0.0179472 0.258776 -0.965771 -0.047652 -0.150931 -0.987395 -0.0908852 0.195349 -0.976514 -0.188269 0.195047 -0.962555 -0.188819 0.209077 -0.959497 -0.310587 0.209273 -0.927222 -0.647619 0.589613 -0.482645 -0.592175 0.589408 -0.549479 -0.593134 0.587357 -0.550639 -0.512594 0.587102 -0.626545 -0.514435 0.582267 -0.629541 -0.40612 0.582087 -0.704444 -0.408326 0.573815 -0.709933 -0.281065 0.57384 -0.769227 -0.282531 0.563583 -0.776241 -0.159456 0.563886 -0.810313 -0.159717 0.55544 -0.816074 -0.0316711 0.554788 -0.831388 -0.0319005 0.610442 -0.791419 -0.421355 0.852583 -0.30913 -0.383117 0.852548 -0.355504 -0.383973 0.851765 -0.356456 -0.331908 0.851607 -0.405711 -0.333539 0.849816 -0.408124 -0.263331 0.849703 -0.456794 -0.265366 0.84666 -0.461246 -0.182605 0.846682 -0.499784 -0.184095 0.842957 -0.505502 -0.103807 0.843159 -0.527548 -0.104264 0.840138 -0.532257 -0.0219833 0.839765 -0.542504 -0.0213948 0.794704 -0.60662 0 0.258818 -0.965926 0 0.258818 -0.965926 0 0.610752 -0.791822 -0.0510313 0.706194 -0.706177 0 0.794886 -0.606759 0 0.965926 -0.25882 0 0.965926 -0.25882 -0.376778 0.448551 -0.810457 -0.0892329 0.932007 -0.351283 0.687772 0.445754 -0.572951 0.50811 0.859691 -0.0524891 0.303042 0.944982 -0.123182 -0.803048 0.252338 -0.539852 0.9634 0.251177 -0.0936491 0.867359 0.413125 -0.277518 0.655908 0.749956 -0.0857308 0.658646 0.741781 -0.126283 0.502451 0.817433 -0.281684 0.578846 0.795184 -0.180612 0.358347 0.859599 -0.364249 0.737969 0.643991 -0.201687 0.879012 0.470906 -0.0747302 0.90461 0.403642 -0.136946 0.277202 0.955515 -0.100747 0.106666 0.961899 -0.251738 0.182762 0.963163 -0.197268 -0.00295657 0.988586 -0.150631 0.363963 0.910855 0.194614 -0.160877 0.960617 -0.226569 0.00232602 0.996785 -0.0800888 -0.314561 0.895873 -0.313789 -0.182118 0.963003 -0.198639 -0.461237 0.795426 -0.393139 -0.594773 0.612373 -0.52081 -0.632822 0.557301 -0.537543 -0.401005 0.792939 -0.458741 -0.474746 0.723789 -0.500746 -0.174307 0.916621 -0.359755 -0.660284 0.342475 -0.668383 0.631538 0.485604 -0.604441 0.478869 0.508061 -0.715932 0.330309 0.532552 -0.779285 0.307248 0.524401 -0.794105 0.0572621 0.503811 -0.861914 0.863168 0.41644 -0.285515 0.921103 0.344496 -0.181362 0.770429 0.543786 -0.33277 0.599133 0.609367 -0.519337 0.552889 0.636821 -0.537377 0.29779 0.653633 -0.695762 0.255699 0.667062 -0.699747 -0.310454 0.518327 -0.796841 -0.177942 0.704659 -0.686872 -0.666502 0.370208 -0.647087 -0.421427 0.504665 -0.753467 -0.658754 0.344017 -0.669101 0.756038 0.653077 -0.043543 0.799108 0.585629 -0.135885 0.649012 0.685551 -0.329853 0.718451 0.660001 -0.219607 0.420402 0.759975 -0.495681 0.497864 0.762259 -0.413634 0.134913 0.767318 -0.626915 0.20363 0.790131 -0.578124 -0.120815 0.715726 -0.687852 -0.0596673 0.561596 -0.825258 -0.132143 0.537338 -0.832951 -0.784521 0.295158 -0.545352 -0.792009 0.281163 -0.541912 -0.666642 0.568476 -0.482103 -0.654329 0.590388 -0.472542 -0.526064 0.741088 -0.417187 -0.36455 0.877247 -0.312316 -0.288545 0.851915 -0.437016 0.0599847 0.970091 -0.235213 0.544363 0.830066 -0.121071 0.617814 0.786196 -0.0142268 0.359247 0.899201 -0.24976 0.438773 0.884782 -0.15697 0.135449 0.917512 -0.373933 0.0171958 0.879152 -0.476231 -0.0845679 0.848455 -0.522468 0.0475221 0.895231 -0.443062 -0.331441 0.740871 -0.584173 -0.24291 0.80078 -0.547492 -0.549477 0.578886 -0.602467 -0.50401 0.627814 -0.593147 -0.776079 0.288989 -0.560524 -0.712234 0.423633 -0.559694 -0.833177 0.175807 -0.524317 -0.786361 0.216184 -0.578706 -0.824693 0.161192 -0.542124 -0.935117 0.250568 -0.250541 -0.935107 0.250573 -0.250574 -0.775974 0.207931 -0.595507 -0.689239 0.199462 -0.696537 -0.258189 0.0691847 -0.963614 -0.258205 0.0691851 -0.96361 -0.60088 0.161003 -0.782957 -0.684551 0.684547 -0.250571 -0.684566 0.684548 -0.250526 -0.508622 0.508609 -0.694709 -0.508582 0.508588 -0.694753 -0.189009 0.189011 -0.963613 -0.189017 0.189016 -0.963611 -0.250563 0.935116 -0.250553 -0.25056 0.935114 -0.250564 -0.186156 0.694752 -0.694741 -0.186158 0.694755 -0.694738 -0.0691837 0.258199 -0.963611 -0.0691831 0.258198 -0.963612 -0.673481 0.237012 -0.700178 -0.665052 0.0924226 -0.741056 -0.689226 0.0763577 -0.720512 -0.57248 0.075876 -0.8164 -0.467879 0.0909605 -0.879099 -0.425287 0.0696481 -0.902375 -0.243652 0.0809655 -0.966477 -0.174683 0.0979374 -0.979742 -0.0791597 0.0655596 -0.994704 0.10967 0.0731769 -0.991271 0.162148 0.0877173 -0.98286 0.187813 0.0800972 -0.978934 0.2771 0.0536409 -0.959343 0.488987 0.0531886 -0.870668 0.499548 0.0463128 -0.865047 0.750031 0.017683 -0.661167 0.789976 -0.0223078 -0.612732 -0.626453 0.111268 -0.771476 -0.36058 0.31764 -0.876976 -0.246723 0.267626 -0.931399 -0.101961 0.319026 -0.942246 0.082839 0.320768 -0.943528 0.0981057 0.31198 -0.94501 0.331874 0.357614 -0.87291 0.443104 0.299689 -0.844893 0.505183 0.322722 -0.800401 0.706433 0.321614 -0.63049 0.981228 0.113986 -0.155561 0.985856 0.122318 -0.114567 0.901031 0.172633 -0.397922 -0.800552 0.027553 -0.59863 -0.58687 0.20204 -0.784069 -0.468762 0.121198 -0.87497 -0.241701 0.204785 -0.948495 -0.176265 0.158037 -0.971573 0.10559 0.224174 -0.968812 0.160044 0.179993 -0.970561 0.450081 0.216842 -0.86626 0.487151 0.179712 -0.854627 0.799203 0.182062 -0.572825 0.742484 0.233293 -0.627927 0.91059 0.178085 -0.372978 0.917299 0.0138613 -0.397957 0.986941 -0.074806 -0.14266 0.977939 -0.0223542 -0.207692 -0.1951 0 -0.980783 -0.258825 0.00275483 -0.96592 -0.555602 -0.00184423 -0.831446 -0.608823 0 -0.793306 -0.831423 0 -0.55564 -0.79331 -0.00275452 -0.608812 -0.980791 0.0036574 -0.195025 -0.965932 0 -0.258797 -0.614197 0.0470059 -0.787752 -0.542809 0.0360501 -0.839082 -0.392203 0.0321128 -0.919318 -0.184286 0.00715533 -0.982847 -0.121364 -0.00153512 -0.992607 0.038629 -0.00538183 -0.999239 0.342568 -0.0392856 -0.938671 0.652318 -0.0555471 -0.755907 0.461401 -0.0457255 -0.886012 0.240383 -0.0209889 -0.970451 0.950346 -0.0890776 -0.298174 0.80421 -0.0637721 -0.590915 0.857245 -0.0768471 -0.509142 0.618123 -0.0565515 -0.784045 0.974636 -0.0816965 -0.20835 0.995684 -0.085493 -0.0361192 0.980892 -0.0825213 -0.176183 0.981168 -0.0792051 -0.176171 0.857699 -0.0716895 -0.50913 0.787738 -0.0557188 -0.613485 0.618647 -0.0505886 -0.784039 0.494197 -0.032422 -0.868745 0.343932 -0.0237196 -0.938695 0.271509 -0.0145921 -0.962325 0.18036 -0.0074517 -0.983572 0.102997 -0.00154268 -0.994681 0.0391739 0.000971445 -0.999232 -0.0838831 0.0166593 -0.996336 -0.18288 0.0237103 -0.982849 -0.24886 0.0296956 -0.968084 -0.428176 0.040684 -0.902779 -0.391433 0.0411175 -0.919287 -0.574467 0.0560166 -0.816608 -0.61325 0.0582979 -0.787735 -0.667917 0.0642885 -0.741454 -0.555551 0.0137558 -0.831369 -0.980798 0.000854982 -0.195027 -0.995522 0.00306494 -0.094483 -0.989882 0.00757089 -0.141689 -0.960119 0.00539988 -0.279541 -0.50358 0.0187293 -0.863746 -0.677708 0.0134855 -0.735207 -0.83138 0.0101913 -0.555611 -0.786968 0.0162001 -0.616781 -0.895768 0.00796923 -0.444451 -0.195064 0.0191649 -0.980603 -0.103117 0.01402 -0.99457 -0.174814 0.0486659 -0.983398 -0.621393 0.0408288 -0.782435 -0.528388 0.163958 -0.833021 -0.395983 -0.0236467 -0.917953 -0.113075 0.0987476 -0.988667 -0.0993744 0.0638032 -0.993003 0.236192 -0.0711083 -0.969101 0.21697 -0.0283109 -0.975768 0.46264 -0.0289445 -0.886074 0.517431 -0.113071 -0.848222 0.655312 -0.00459586 -0.755344 0.761053 -0.121045 -0.637297 0.804687 -0.0570718 -0.590949 0.95181 -0.0710016 -0.298355 0.914302 0.155031 -0.374189 0.980805 -0.191843 -0.0349099 0.98972 -0.068905 -0.125325 0.989693 -0.0707273 -0.12452 0.989767 -0.0695065 -0.124623 -0.476249 -0.231818 -0.848202 -0.870156 -0.441397 -0.219082 -0.956189 -0.0752269 -0.28292 -0.892632 -0.0603461 -0.446728 -0.990746 -0.09243 -0.0993916 -0.97769 -0.103699 -0.182672 -0.938769 -0.284076 -0.194973 -0.413592 -0.669142 -0.617406 -0.26067 -0.942598 -0.208709 -0.548586 -0.8276 0.118878 -0.550127 -0.786807 -0.279812 -0.549697 -0.780194 -0.298548 -0.517346 -0.712227 -0.474432 -0.51557 -0.705196 -0.486709 -0.458655 -0.600544 -0.654967 -0.456958 -0.595674 -0.660577 -0.327642 -0.377138 -0.866266 -0.328274 -0.379426 -0.865027 -0.122012 -0.0508627 -0.991224 -0.108215 -0.00841445 -0.994092 -0.185925 -0.0223543 -0.98231 -0.15152 0.0234676 -0.988176 -0.200645 0.0270919 -0.979289 -0.174814 0.0486409 -0.983399 -0.95018 -0.273554 -0.14942 -0.520417 -0.0976847 -0.848306 -0.830502 -0.138713 -0.539468 -0.778823 -0.110199 -0.617488 -0.672839 -0.0817122 -0.735263 -0.0871171 -0.991341 -0.0982559 -0.180696 -0.837757 -0.515279 -0.19545 -0.939906 -0.279956 -0.196755 -0.933243 -0.300573 -0.183573 -0.859459 -0.477108 -0.184381 -0.849845 -0.493727 -0.16396 -0.724251 -0.669759 -0.163985 -0.722366 -0.671786 -0.115684 -0.450422 -0.885289 -0.113958 -0.465345 -0.877763 -0.0413913 -0.0402715 -0.998331 -0.041604 -0.0363561 -0.998473 -0.668168 -0.738019 -0.094227 -0.826222 -0.555132 -0.0958446 -0.816751 -0.5118 -0.266417 -0.75384 -0.629872 0.187048 -0.706865 -0.528193 -0.470483 -0.534276 -0.214655 -0.817602 -0.683232 -0.366269 -0.631697 -0.713418 -0.417418 -0.562848 -0.475911 -0.231692 -0.848426 -0.548338 -0.0583819 -0.834217 -0.502024 -0.0355834 -0.864122 0.954482 -0.179 -0.238584 -0.618228 0.0783214 -0.782087 -0.688426 0.0925136 -0.719382 -0.551364 0.112554 -0.826638 -0.390387 0.0568389 -0.918895 -0.103448 0.0100625 -0.994584 -0.115547 0.0125497 -0.993223 0.216575 -0.0336269 -0.975687 0.240687 -0.0380812 -0.969855 0.52074 -0.0802997 -0.849931 0.463483 -0.0687099 -0.883438 0.761388 -0.118242 -0.637423 0.742081 -0.113711 -0.660595 0.914359 -0.136281 -0.381281 0.849214 -0.122417 -0.513663 0.986143 -0.109834 -0.12433 0.000132825 -0.979903 -0.199473 1.47493e-05 -0.979883 -0.199571 0.0604636 -0.993303 -0.0984505 0.00317186 -0.958385 -0.28546 -0.00682862 -0.808937 -0.587856 0.0777762 -0.871668 -0.483886 -0.000609327 -0.734187 -0.678947 0.00227707 -0.453466 -0.891271 -0.0104839 -0.469282 -0.882986 0.00963439 -0.0403042 -0.999141 0.000230909 -0.055728 -0.998446 -0.804512 0.163908 -0.570872 0.929827 -0.280754 -0.237905 -0.676737 0.0797343 -0.731894 0.396944 -0.351273 -0.847964 0.0565584 -0.191211 -0.979918 0.0814299 -0.262754 -0.961421 -0.214496 -0.0875449 -0.972794 -0.552729 0.0390743 -0.832444 -0.366145 -0.139526 -0.920038 -0.383333 -0.0627485 -0.921476 -0.0380117 -0.413095 -0.909894 0.894093 -0.422845 -0.147648 0.817144 -0.437593 -0.375218 -0.694647 0.105537 -0.711567 -0.684293 0.134027 -0.716785 -0.54093 0.157265 -0.826234 0.827844 -0.42984 -0.360433 0.64984 -0.46487 -0.601335 0.635448 -0.449414 -0.62788 0.47852 -0.416812 -0.772843 0.410019 -0.391521 -0.823769 0.262124 -0.451815 -0.852733 -0.0808618 -0.258088 -0.962731 -0.505927 -0.0330691 -0.861942 -0.470509 0.0710284 -0.879532 -0.187505 -0.011907 -0.982192 -0.116885 0.00656804 -0.993124 0.128001 -0.131769 -0.982982 0.220324 -0.125802 -0.96728 0.450243 -0.200008 -0.870217 0.430449 -0.205383 -0.878938 0.714617 -0.227651 -0.661436 0.716266 -0.226668 -0.659988 0.869814 -0.292528 -0.397305 0.968236 -0.203487 -0.145298 0.906857 -0.404804 -0.117237 -0.701944 -0.514408 -0.492605 -0.0635306 -0.972166 -0.225517 -0.0200935 -0.983413 -0.180266 -0.0239634 -0.979702 -0.199022 -0.15877 -0.977903 -0.136008 -0.282254 -0.922882 -0.261958 -0.118701 -0.984372 -0.130084 -0.132565 -0.978295 -0.159265 -0.11593 -0.978179 -0.172413 -0.175322 -0.944075 -0.279259 -0.0700444 -0.985907 -0.151922 -0.0797318 -0.978928 -0.187995 -0.0536775 -0.978813 -0.197597 -0.0848043 -0.99465 -0.0589946 -0.0433527 -0.998514 -0.0330238 -0.271092 -0.945863 -0.178469 -0.170045 -0.977935 -0.121361 -0.435576 -0.846988 -0.304769 -0.817755 0.0192267 -0.575246 -0.793717 -0.180876 -0.580773 -0.74855 0.172021 -0.640377 -0.712157 -0.179451 -0.678697 -0.660286 0.207326 -0.72183 -0.607573 -0.196455 -0.769585 -0.544672 0.226949 -0.807358 -0.485255 -0.194299 -0.852511 -0.411176 0.212921 -0.88634 -0.395927 0.0454036 -0.917159 -0.317931 -0.0653148 -0.945861 -0.267516 0.20176 -0.942193 -0.190331 -0.254806 -0.948076 -0.119613 0.172451 -0.977729 -0.0495853 -0.241205 -0.969207 -0.02444 -0.469165 -0.882773 -0.00550642 -0.979766 -0.200072 -0.00543767 -0.979889 -0.199468 -0.0162392 -0.808846 -0.587796 -0.0160833 -0.807581 -0.589537 -0.0705719 -0.807125 -0.586147 -0.0718535 -0.803127 -0.591459 -0.161475 -0.803067 -0.573594 -0.163694 -0.798762 -0.57895 -0.252103 -0.798764 -0.546278 -0.254808 -0.794888 -0.550659 -0.338573 -0.794899 -0.503491 -0.341011 -0.792062 -0.506309 -0.411406 -0.792224 -0.450696 -0.413423 -0.790185 -0.452426 -0.465289 -0.790352 -0.39856 -0.466703 -0.789043 -0.399499 -0.502417 -0.789178 -0.353236 -0.586913 -0.705706 -0.396878 -0.00442701 -0.0557297 -0.998436 -0.0277548 -0.0162651 -0.999483 -0.024122 -0.465741 -0.884592 -0.105738 -0.465149 -0.878895 -0.107538 -0.454532 -0.884215 -0.241326 -0.454459 -0.857455 -0.24414 -0.442762 -0.862761 -0.37566 -0.442762 -0.814151 -0.378836 -0.432294 -0.818294 -0.503155 -0.432303 -0.748297 -0.505918 -0.424517 -0.750888 -0.610341 -0.424709 -0.66866 -0.612563 -0.419066 -0.670187 -0.689485 -0.419259 -0.59062 -0.691021 -0.415595 -0.591414 -0.744881 -0.415724 -0.521848 -0.785517 -0.308107 -0.536687 -0.772782 -0.307854 -0.555008 -0.654809 -0.168606 -0.736748 -0.722725 -0.0850261 -0.685885 -0.740523 -0.051988 -0.670017 0.337541 -0.941216 -0.0133906 0.179902 -0.976105 -0.12188 0.134478 -0.977918 -0.159976 -0.0164781 -0.968595 -0.248099 -0.214597 -0.895679 -0.389495 -0.110938 -0.950213 -0.291184 -0.4234 -0.762141 -0.48977 -0.349899 -0.8343 -0.426044 -0.556379 -0.63576 -0.535025 0.817366 -0.569823 -0.084932 0.818602 -0.56903 -0.0780787 0.653319 -0.643554 -0.398763 0.71287 -0.654217 -0.252618 0.443789 -0.626508 -0.640733 0.53182 -0.691796 -0.488452 0.357484 -0.664042 -0.656699 0.131982 -0.596914 -0.791375 0.17122 -0.62787 -0.759252 -0.189266 -0.458705 -0.868198 -0.182301 -0.466289 -0.865645 -0.511482 -0.328372 -0.794077 -0.653713 -0.121049 -0.746998 -0.568559 -0.342487 -0.747959 -0.294811 -0.60116 -0.742761 -0.321951 -0.565157 -0.759569 0.0100401 -0.76427 -0.644818 -0.0318692 -0.727773 -0.685078 0.303494 -0.82892 -0.469877 0.253712 -0.80444 -0.537127 0.540339 -0.800634 -0.258881 0.493464 -0.796984 -0.348296 0.666994 -0.736104 -0.115192 0.659135 -0.738959 -0.139571 -0.826806 0.0183793 -0.562187 -0.832674 -0.0207336 -0.553376 -0.83899 0.0192451 -0.543806 -0.734954 -0.396737 -0.549948 -0.737518 -0.390548 -0.550944 -0.695821 -0.514187 -0.501443 -0.501188 -0.781368 -0.371853 -0.561709 -0.704489 -0.433796 -0.305647 -0.918452 -0.25105 -0.404573 -0.844734 -0.35035 -0.102596 -0.987934 -0.116022 -0.227201 -0.942615 -0.244656 0.0941989 -0.995512 0.00906565 -0.0400414 -0.990965 -0.128 -0.827137 0.117877 -0.549499 -0.828571 0.12341 -0.546114 -0.85977 0.10604 -0.49955 -0.7759 -0.135314 -0.616173 -0.669198 -0.362206 -0.64883 -0.634653 -0.40622 -0.65742 -0.485571 -0.598046 -0.637622 -0.415032 -0.654463 -0.632002 -0.253605 -0.78323 -0.567657 -0.142963 -0.833715 -0.533367 -0.0040673 -0.893583 -0.448879 0.136608 -0.915674 -0.377994 0.230524 -0.925006 -0.302031 0.381679 -0.903046 -0.197053 0.427838 -0.891424 -0.149394 0.569827 -0.821514 -0.0203049 -0.428111 0.7088 -0.560646 0.428289 -0.893889 -0.132403 -0.603774 0.570367 -0.556901 -0.601437 0.568328 -0.561495 -0.466717 0.429836 -0.772927 -0.463531 0.427069 -0.776371 -0.25791 0.220947 -0.940566 -0.25422 0.217777 -0.942309 0.00725354 -0.0393496 -0.999199 0.010832 -0.0423658 -0.999043 0.280525 -0.302818 -0.910828 0.283485 -0.305233 -0.909103 0.50387 -0.513522 -0.694558 0.505923 -0.515098 -0.691893 0.644949 -0.642014 -0.414558 0.646148 -0.64281 -0.411446 0.707388 -0.693872 -0.134702 0.707844 -0.694005 -0.131585 -0.511656 0.652674 -0.558771 -0.51128 0.652243 -0.559618 -0.39546 0.494218 -0.774183 -0.394832 0.493496 -0.774964 -0.218547 0.257783 -0.941162 -0.217594 0.256692 -0.94168 0.00613176 -0.0378873 -0.999263 0.00735157 -0.0392625 -0.999202 0.237836 -0.33837 -0.910461 0.239059 -0.33971 -0.909642 0.42721 -0.579683 -0.693873 0.428266 -0.580781 -0.692301 0.546872 -0.727901 -0.413632 0.547577 -0.728545 -0.41156 0.599826 -0.78886 -0.133822 0.600153 -0.78902 -0.131391 0.497128 -0.857448 -0.132839 0.436464 -0.795047 -0.421189 0.438346 -0.798616 -0.412391 0.438924 -0.799417 -0.410216 0.348963 -0.630792 -0.693055 0.350357 -0.632879 -0.690445 0.20341 -0.360869 -0.910164 0.205989 -0.364838 -0.907999 0.0222138 -0.0273952 -0.999378 0.0260382 -0.0333245 -0.999105 -0.15595 0.298489 -0.941586 -0.151449 0.291555 -0.944489 -0.298304 0.557253 -0.774909 -0.29401 0.550763 -0.781165 -0.469637 0.861877 -0.191336 -0.358128 0.740219 -0.569052 -0.235391 0.779861 -0.580008 -0.240449 0.789851 -0.564198 -0.164713 0.591707 -0.789147 -0.170882 0.605135 -0.777567 -0.0655435 0.311457 -0.947997 -0.0721292 0.326703 -0.942371 0.0524113 -0.0386716 -0.997877 0.0464515 -0.024294 -0.998625 0.166658 -0.394946 -0.903462 0.16226 -0.384046 -0.908945 0.253385 -0.682839 -0.68522 0.250772 -0.676272 -0.692654 0.301922 -0.862482 -0.406163 0.30068 -0.85938 -0.413591 0.316667 -0.939809 -0.128381 0.31631 -0.939003 -0.134988 0.0400475 -0.993659 0.105061 -0.0217981 0.754873 -0.655509 -0.0204215 0.742311 -0.669745 -0.0165168 0.526782 -0.84984 -0.015671 0.539803 -0.841646 -0.00908455 0.230298 -0.973078 -0.00847497 0.240471 -0.970619 0.000141926 -0.120042 -0.992769 0.000423356 -0.115396 -0.993319 0.00966011 -0.46553 -0.884979 0.0095884 -0.466585 -0.884425 0.0176517 -0.742336 -0.669795 0.0172922 -0.746455 -0.665211 0.023004 -0.916143 -0.400191 0.0224821 -0.919894 -0.391522 0.0257332 -0.991891 -0.124461 0.158446 -0.978126 -0.134777 0.129505 -0.910296 -0.393179 0.128597 -0.901568 -0.413083 0.130293 -0.907545 -0.399231 0.107183 -0.715093 -0.690763 0.112133 -0.735101 -0.66862 0.0690848 -0.41619 -0.90665 0.0796395 -0.460543 -0.884058 0.0190548 -0.0459949 -0.99876 0.0362371 -0.117636 -0.992395 -0.0324172 0.318905 -0.947232 -0.0102316 0.230223 -0.973084 -0.0754126 0.612323 -0.787003 -0.0516579 0.524438 -0.84988 -0.105682 0.810264 -0.576458 -0.0836146 0.738166 -0.669417 0.764656 -0.630418 -0.133696 0.783823 -0.608198 -0.125366 0.764959 -0.614103 -0.194203 0.708128 -0.571879 -0.414136 0.717525 -0.585921 -0.376635 0.558855 -0.45352 -0.694263 0.579774 -0.480864 -0.657747 0.427416 -0.358744 -0.829831 0.309215 -0.275066 -0.910343 0.294053 -0.25933 -0.919935 0.10026 -0.100065 -0.989917 0.0108324 -0.0423653 -0.999043 -0.0506469 0.0143582 -0.998613 -0.269801 0.199465 -0.94203 -0.249671 0.175595 -0.952277 -0.502026 0.382311 -0.775763 -0.48163 0.358262 -0.799801 -0.65086 0.511792 -0.560759 -0.625371 0.476485 -0.617959 0.000122647 -0.992227 -0.12444 -0.00096495 0.755016 -0.655706 -0.000168555 -0.99223 -0.124415 -3.57876e-05 -0.992246 -0.124289 -0.000285175 -0.920156 -0.391552 -0.000344877 -0.920119 -0.391638 -0.000543173 -0.746599 -0.665274 -0.000680387 -0.746473 -0.665415 -0.000732213 -0.466622 -0.884457 -0.000975827 -0.466344 -0.884603 -0.00079033 -0.115397 -0.993319 -0.00119914 -0.114874 -0.993379 -0.00077346 0.240475 -0.970655 -0.00124637 0.241105 -0.970498 -0.000660222 0.539846 -0.841763 -0.00115499 0.540491 -0.841349 -0.000509163 0.755554 -0.655086 0.851693 -0.505332 -0.138773 0.698872 -0.605831 -0.380194 -0.631716 0.468175 -0.617857 0.164291 -0.0133492 -0.986322 0.0928487 0.0755657 -0.992809 0.0159657 0.102785 -0.994575 -0.107882 0.168024 -0.979862 -0.220477 0.213852 -0.95166 -0.251107 0.263415 -0.931428 -0.460558 0.385458 -0.799568 -0.433489 0.341208 -0.834065 -0.594168 0.494976 -0.634005 -0.594601 0.504295 -0.626208 0.379139 -0.140454 -0.914618 0.396933 -0.143778 -0.906516 0.505476 -0.248336 -0.826331 0.540296 -0.270925 -0.796668 0.646494 -0.358641 -0.673366 0.652657 -0.377925 -0.656667 0.750331 -0.438153 -0.495001 0.786149 -0.489543 -0.37725 0.845124 -0.486076 -0.222478 0.81357 -0.567642 -0.126041 0.000118357 -0.991473 -0.130313 -0.00117604 -0.992226 -0.12444 0.00172344 -0.915446 -0.402437 -0.00139621 -0.920118 -0.391639 0.0019102 -0.738983 -0.673721 -0.00141099 -0.746472 -0.665415 0.00182369 -0.461661 -0.887054 0.000196312 -0.466345 -0.884603 0.000164821 -0.29213 -0.956379 0.001531 -0.107431 -0.994211 -0.000817019 -0.114874 -0.99338 0.00104073 0.245948 -0.969283 -0.000418042 0.241105 -0.970499 0.000541408 0.542623 -0.839976 -0.000112214 0.540492 -0.841349 0.000174352 0.755905 -0.654681 5.67037e-05 0.755554 -0.655086 -0.583485 0.601226 -0.545961 -0.436276 0.645804 -0.626579 0.23197 0.96738 -0.101812 0.734854 0.665491 -0.130811 0.874287 -0.208696 -0.438256 0.684539 -0.00887586 -0.728923 0.460279 0.635961 -0.619433 0.786419 0.222505 -0.576227 0.823876 0.165348 -0.542116 0.74608 -0.0528501 -0.663756 0.782735 -0.112197 -0.612158 0.930563 0.0383996 -0.364112 0.950391 -0.0277953 -0.309815 0.88289 -0.216379 -0.416755 0.906393 -0.286127 -0.31078 0.881367 0.383595 -0.275768 0.762281 0.498737 -0.412539 0.445099 0.758856 -0.47542 0.335593 0.794074 -0.506778 0.310177 0.857271 -0.410946 0.872218 0.461916 -0.160841 0.959224 0.272394 -0.0754343 0.992192 0.0848017 -0.0914511 0.937183 -0.334625 -0.09856 0.914714 -0.403179 0.0272987 0.976253 -0.0667795 -0.206086 0.980921 -0.127656 -0.146625 0.99931 0.0353571 -0.0114099 0.952604 0.208719 -0.221321 0.995621 0.0473814 -0.0805805 0.809068 0.356734 -0.467066 0.761495 0.416225 -0.496873 0.287849 0.937347 -0.196276 0.420477 0.899877 -0.115851 0.465265 0.860252 -0.208554 0.590721 0.796198 -0.130835 0.634612 0.731501 -0.249345 0.181968 0.982892 -0.0284803 0.221875 0.971433 -0.0842002 0.165491 0.973554 -0.157498 0.396035 0.917886 -0.0253359 0.439542 0.892658 -0.0998226 0.572252 0.820074 -0.00255386 -0.343171 0.836391 -0.427415 -0.209661 0.935885 -0.283127 -0.108433 0.975817 -0.189797 -0.612662 0.572848 -0.544509 -0.611285 0.572097 -0.546842 -0.218567 0.848461 -0.482019 -0.0806256 0.905309 -0.417032 -0.393777 0.756503 -0.522153 -0.307454 0.814351 -0.492244 -0.603418 0.580622 -0.546594 -0.585205 0.603634 -0.541444 -0.591043 0.510305 -0.624705 -0.119438 0.585152 -0.80208 0.0112184 0.374274 -0.92725 -0.149939 0.437092 -0.886831 -0.298115 0.53702 -0.789137 -0.315789 0.538527 -0.781195 -0.422913 0.551093 -0.719333 -0.408653 0.651614 -0.639063 -0.156786 0.708362 -0.688216 -0.100379 0.707323 -0.699728 0.210542 0.281556 -0.936161 0.187866 0.30207 -0.934591 0.256928 0.505503 -0.823684 0.220241 0.52855 -0.819834 0.244122 0.686149 -0.685276 0.156531 0.708028 -0.688618 0.143147 0.808838 -0.570342 -0.00807797 0.995535 -0.0940455 -0.0653223 0.983189 -0.17051 0.0220524 0.996073 -0.085751 0.0971099 0.976922 -0.190243 0.070961 0.975043 -0.210368 0.12699 0.943806 -0.30513 -0.0267536 0.907173 -0.419906 0.400315 0.88026 -0.254735 0.433955 0.832864 -0.343541 0.5527 0.782249 -0.287419 0.581538 0.710002 -0.397128 0.530373 0.0965904 -0.842244 0.503913 0.127713 -0.854261 0.584086 0.356355 -0.729283 0.540632 0.397353 -0.741504 0.562581 0.531427 -0.633315 0.267922 0.707174 -0.654311 0.708716 0.553395 -0.437579 0.695407 0.635523 -0.33544 0.863385 0.480042 -0.155328 0.775318 0.562568 -0.287053 0.897225 0.42235 -0.128873 0.860789 0.508938 0.00494374 0.883557 0.464659 0.0584718 0.594598 0.79387 -0.127369 0.584421 0.799162 -0.140685 0.607116 0.791264 -0.0728821 -0.322929 0.859506 -0.396189 -0.284992 0.884489 -0.369403 -0.46064 0.751747 -0.471897 -0.434328 0.778444 -0.453192 -0.577107 0.617192 -0.53481 -0.621194 0.548542 -0.55966 -0.651426 0.501083 -0.569701 -0.547486 0.535107 -0.643366 -0.654543 0.535055 -0.534124 -0.643709 0.548503 -0.533651 -0.656973 0.54232 -0.523713 -0.447797 0.757221 -0.475493 -0.539863 0.627725 -0.560811 -0.170103 0.80491 -0.568494 -0.272173 0.764623 -0.584186 -0.171786 0.799439 -0.575662 -0.039997 0.849943 -0.525354 0.203341 0.873518 -0.442289 0.153701 0.937597 -0.311911 -0.0325962 0.905702 -0.422661 -0.127587 0.956727 -0.261525 -0.261085 0.89255 -0.36768 -0.0354275 0.755426 -0.654275 -0.119644 -0.733676 -0.668883 -0.0373489 -0.990772 -0.130292 -0.112823 -0.862577 -0.493185 -0.0892367 -0.911789 -0.400846 -0.0977189 -0.928145 -0.359163 -0.0868079 -0.978531 -0.186925 -0.115262 -0.983511 -0.139358 -0.103275 0.768548 -0.631402 -0.0472679 0.74662 -0.663569 -0.0433463 0.53717 -0.842359 -0.0446923 0.542075 -0.839141 -0.0959796 0.345548 -0.93348 -0.0736876 0.245269 -0.966651 -0.119854 -0.733364 -0.669188 -0.13185 -0.520305 -0.843741 -0.110529 -0.458833 -0.881621 -0.131943 -0.328229 -0.935338 -0.128 -0.289727 -0.948512 -0.123063 -0.237867 -0.96347 -0.107695 -0.106821 -0.988429 -0.128638 -0.0470019 -0.990577 -0.094513 0.168029 -0.981241 -0.391093 0.534635 -0.749141 -0.0469481 0.997593 -0.0510359 -0.0956412 0.990179 -0.10197 -0.0180466 0.970111 -0.241989 -0.0156084 0.976078 -0.216858 -0.0218333 0.99322 -0.114179 -0.0289474 0.990472 -0.134639 -0.0438658 0.990444 -0.130756 -0.101854 0.95834 -0.266854 -0.0620923 0.284697 -0.956604 -0.319721 0.542719 -0.776682 -0.298315 0.539387 -0.787446 -0.296475 0.370412 -0.880282 -0.179064 0.704155 -0.687096 -0.173217 0.39646 -0.901563 -0.128284 0.552666 -0.823471 -0.0825115 0.552581 -0.829365 -0.516325 0.599078 -0.611975 -0.485628 0.512862 -0.707911 -0.505392 0.363413 -0.78263 -0.141372 0.977953 -0.153695 -0.235204 0.937726 -0.255633 -0.281126 0.910455 -0.303379 -0.0376779 0.66658 -0.744481 -0.2088 0.755693 -0.620751 -0.207234 0.758886 -0.61737 -0.122712 0.758991 -0.639433 -0.121856 0.761464 -0.636651 -0.0388591 0.761206 -0.647345 -0.0517398 0.119182 -0.991523 -0.0253203 0.523543 -0.851623 -0.300941 0.896228 -0.3259 -0.344107 0.861214 -0.374034 -0.445396 0.753238 -0.483998 -0.447062 0.75095 -0.486015 -0.675935 -0.0668383 -0.733924 -0.575643 0.617173 -0.536407 -0.625213 0.500916 -0.598491 -0.490551 -0.103116 -0.86529 -0.323833 0.753899 -0.571637 -0.324557 0.752729 -0.572767 -0.118319 0.970738 -0.20897 -0.224909 0.911139 -0.345314 -0.0637071 0.993161 -0.0978436 -0.0790359 0.990301 -0.114265 -0.034746 0.808997 -0.586785 -0.0222532 0.91349 -0.406253 -0.0764159 0.91367 -0.399208 -0.0769844 0.912753 -0.401192 -0.130018 0.912708 -0.387374 -0.131073 0.911534 -0.389778 -0.180457 0.911565 -0.369437 -0.0510871 0.993197 -0.104639 -0.080503 0.986852 -0.14015 -0.649235 0.601509 -0.46549 -0.39361 -0.875392 -0.280643 -0.58163 -0.759686 -0.290833 -0.952269 -0.20447 -0.226661 -0.875158 0.361954 -0.321073 -0.985446 0.0875582 -0.145702 -0.962928 -0.219069 -0.15741 -0.991063 -0.0145471 -0.132597 -0.968692 -0.236021 -0.0770056 -0.978847 -0.202827 -0.0268398 -0.99007 -0.00791573 -0.14035 -0.996609 0.0385204 -0.072708 -0.940155 0.25139 -0.230025 -0.769766 0.215727 -0.600768 -0.37431 -0.206065 -0.904118 -0.720609 -0.127751 -0.681471 -0.724435 -0.13932 -0.675118 -0.82728 -0.0723824 -0.557107 -0.854337 -0.347864 -0.386132 -0.936608 -0.303002 -0.17594 -0.892639 -0.360305 -0.270879 -0.813593 -0.578514 -0.0582067 -0.804308 -0.508979 -0.306642 -0.883926 -0.433216 -0.176062 -0.903125 -0.134647 -0.407719 -0.944644 -0.0800267 -0.318188 -0.892829 0.185084 -0.410609 -0.60136 -0.795469 0.074807 -0.703799 -0.691953 -0.160835 -0.756811 -0.648665 -0.0804389 -0.414044 -0.811652 -0.412055 -0.446856 -0.66558 -0.597764 -0.447105 -0.681118 -0.579806 -0.473761 -0.536277 -0.69854 -0.471476 -0.468116 -0.747381 -0.221166 0.787682 -0.575016 -0.232323 0.76856 -0.596106 -0.5248 0.557398 -0.643344 -0.0932753 0.826754 -0.554777 -0.0635241 0.818279 -0.571301 -0.0855491 0.766751 -0.636218 -0.203205 0.637294 -0.743346 -0.290381 0.672668 -0.680586 -0.286723 0.678007 -0.676828 -0.352833 0.721087 -0.596274 -0.0839747 0.835275 -0.543382 -0.196946 -0.973131 -0.119286 -0.358208 -0.893584 -0.270543 -0.397823 -0.811842 -0.427375 -0.643341 -0.722363 -0.253582 -0.699069 -0.575523 -0.424354 -0.732767 -0.428001 -0.529025 -0.733456 -0.43991 -0.51819 -0.73143 -0.293814 -0.615373 -0.47857 -0.387917 -0.787713 -0.832318 -0.540769 -0.12172 -0.871905 -0.488447 -0.0346601 -0.915397 -0.390285 -0.0986195 -0.942055 -0.335238 -0.0121973 -0.973512 -0.162689 -0.160646 -0.975593 -0.0653163 -0.209646 -0.932113 0.11874 -0.342149 -0.948012 0.165451 -0.271846 -0.873544 0.340929 -0.347403 -0.876557 0.360409 -0.31899 -0.760118 0.513227 -0.39852 -0.235592 0.561289 -0.793379 -0.32284 0.372542 -0.87005 -0.230377 0.502245 -0.833472 -0.304632 0.196002 -0.932085 -0.562734 0.512638 -0.648485 -0.476848 0.455512 -0.751748 -0.486826 0.431703 -0.759364 -0.379781 0.389429 -0.839114 -0.514243 0.0453829 -0.856443 -0.349903 0.00177909 -0.936784 -0.344649 -0.0188379 -0.938543 -0.755428 0.411716 -0.509723 -0.70318 0.340986 -0.623912 -0.750711 0.249491 -0.611709 -0.63276 0.170243 -0.755402 -0.642652 0.120294 -0.756656 -0.49866 0.0627517 -0.864523 -0.56004 -0.193791 -0.805482 -0.351998 -0.83287 -0.427112 -0.469152 -0.279002 -0.837887 -0.352045 -0.921362 -0.164792 -0.516668 -0.85506 -0.0438907 -0.656834 -0.663039 -0.359093 -0.790092 -0.577812 -0.204667 -0.841977 -0.277686 -0.462564 -0.91987 -0.203428 -0.335344 -0.845292 0.114641 -0.521861 -0.893974 0.182688 -0.409189 -0.834569 0.30564 -0.458344 -0.854147 0.363429 -0.371957 -0.491589 0.67072 -0.555404 -0.485342 0.674724 -0.556049 -0.571282 0.621558 -0.536006 -0.453551 0.697544 -0.554728 -0.218689 0.788109 -0.575378 -0.156444 0.806602 -0.570017 -8.77105e-05 0.984282 -0.176603 0.0348309 0.969688 -0.24185 -0.00755303 0.896976 -0.442014 0.0101891 0.809473 -0.587069 -0.000743139 0.787859 -0.615855 -0.000736035 0.667081 -0.744985 -0.0235167 0.586583 -0.809548 -0.000498694 0.523659 -0.851928 -0.15643 0.794511 -0.586755 -0.890307 0.347227 -0.294596 -0.987615 0.119635 -0.101505 -0.987609 0.119667 -0.10153 -0.940568 0.258959 -0.219711 -0.875618 0.369045 -0.311607 -0.156133 0.74355 -0.650197 0.174024 0.750904 -0.63707 -0.452696 0.67993 -0.576855 -0.452793 0.67989 -0.576826 -0.705815 0.540178 -0.458294 -0.648341 0.58241 -0.490359 -0.759276 0.496232 -0.421015 -0.0744733 0.673818 -0.735135 -0.156348 0.662893 -0.732208 -0.453642 0.598115 -0.660657 -0.453633 0.598119 -0.660659 -0.706722 0.474831 -0.52448 -0.706732 0.474823 -0.524474 -0.890791 0.304977 -0.336868 -0.890785 0.304986 -0.336876 -0.987672 0.105061 -0.116046 -0.987672 0.10506 -0.116045 -0.156155 0.590995 -0.791417 -0.267703 0.570535 -0.776418 -0.453449 0.527771 -0.718222 -0.453553 0.527732 -0.718184 -0.706561 0.419029 -0.570251 -0.706634 0.418979 -0.570197 -0.890702 0.269176 -0.366326 -0.890746 0.269119 -0.366261 -0.969199 0.145826 -0.198464 -0.987639 0.0905598 -0.127939 -0.995808 0.054162 -0.0737149 -0.104845 0.783517 -0.612461 -0.0421098 0.532528 -0.845364 -0.119755 0.57837 -0.806937 -0.288384 0.729936 -0.6197 -0.142362 0.887866 -0.437524 -0.161154 0.913311 -0.374022 -0.181197 0.967989 -0.17368 -0.732002 0.615453 -0.292218 -0.616535 0.642332 -0.455297 -0.0981405 0.542259 -0.83446 -0.162089 0.554583 -0.816189 -0.386195 0.6259 -0.677571 -0.447405 0.627144 -0.637589 -0.629583 0.643608 -0.435195 -0.183131 0.968942 -0.166173 -0.545312 0.831832 -0.103394 -0.576202 0.817294 0.00468299 -0.809163 0.573282 -0.128848 -0.873937 0.351678 0.335494 -0.886077 0.338354 -0.316835 -0.988146 0.1533 -0.00816629 -0.884324 0.348517 -0.310656 -0.812146 0.40972 -0.41539 -0.704277 0.459765 -0.540935 -0.700189 0.462015 -0.544313 -0.453257 0.53419 -0.713582 -0.487265 0.522316 -0.699827 -0.156458 0.543324 -0.824815 -0.152069 0.543851 -0.825289 -0.0137975 0.586689 -0.809695 -0.0482272 0.624541 -0.779502 -0.103184 0.771575 -0.627714 -0.264839 0.699373 -0.663881 -0.411775 0.803178 -0.430519 -0.456503 0.812798 -0.361889 -0.53764 0.831544 -0.139568 -0.747675 0.61066 -0.260916 -0.805458 0.575946 -0.139726 -0.898133 0.337557 -0.281802 -0.958926 0.255112 -0.124011 + + + + + + + + + + + + + + +

0 0 1 0 2 0 3 1 95 1 34 1 34 2 95 2 97 2 36 3 5 3 4 3 4 4 5 4 9 4 4 5 9 5 6 5 6 6 9 6 10 6 6 7 10 7 40 7 40 8 10 8 11 8 40 9 11 9 7 9 7 10 11 10 14 10 7 11 14 11 8 11 8 12 14 12 39 12 5 13 2256 13 9 13 9 14 2256 14 2254 14 9 15 2254 15 10 15 10 16 2254 16 12 16 10 17 12 17 11 17 11 18 12 18 13 18 11 19 13 19 14 19 14 20 13 20 2249 20 14 21 2249 21 39 21 39 22 2249 22 2250 22 17 23 21 23 15 23 15 24 21 24 2446 24 15 25 16 25 17 25 17 26 16 26 2464 26 17 27 2464 27 43 27 2464 28 18 28 43 28 43 29 18 29 19 29 43 30 19 30 45 30 20 31 21 31 42 31 42 32 21 32 17 32 42 33 17 33 22 33 22 34 17 34 43 34 92 35 23 35 44 35 44 36 23 36 35 36 44 37 35 37 36 37 2456 38 29 38 24 38 2453 39 25 39 31 39 31 40 25 40 26 40 31 41 26 41 24 41 24 42 26 42 27 42 24 43 27 43 2456 43 2456 44 28 44 29 44 29 45 28 45 2459 45 29 46 2459 46 30 46 30 47 2459 47 2458 47 54 48 1 48 57 48 57 49 1 49 0 49 57 50 0 50 58 50 20 51 41 51 30 51 30 52 41 52 2 52 30 53 2 53 29 53 29 54 2 54 1 54 29 55 1 55 24 55 24 56 1 56 54 56 24 57 54 57 31 57 2458 58 32 58 30 58 30 59 32 59 33 59 30 60 33 60 20 60 20 61 33 61 2462 61 20 62 2462 62 21 62 21 63 2462 63 2461 63 21 64 2461 64 2446 64 2258 65 38 65 37 65 2158 66 2258 66 97 66 97 67 2258 67 37 67 97 68 37 68 34 68 23 69 3 69 35 69 35 70 3 70 34 70 35 71 34 71 36 71 36 72 34 72 37 72 36 73 37 73 5 73 5 74 37 74 38 74 5 75 38 75 2256 75 2250 76 59 76 39 76 39 77 59 77 58 77 39 78 58 78 8 78 8 79 58 79 0 79 8 80 0 80 7 80 7 81 0 81 2 81 7 82 2 82 40 82 40 83 2 83 41 83 40 84 41 84 6 84 6 85 41 85 20 85 6 86 20 86 4 86 4 87 20 87 42 87 4 88 42 88 36 88 36 89 42 89 22 89 36 90 22 90 44 90 44 91 22 91 43 91 44 92 43 92 92 92 92 93 43 93 45 93 92 94 45 94 46 94 47 95 88 95 87 95 48 96 49 96 86 96 73 97 2452 97 64 97 50 98 2450 98 51 98 63 99 2453 99 52 99 52 100 2453 100 31 100 52 101 31 101 53 101 53 102 31 102 54 102 53 103 54 103 55 103 55 104 54 104 57 104 55 105 57 105 56 105 56 106 57 106 58 106 56 107 58 107 60 107 60 108 58 108 59 108 60 109 59 109 2250 109 2250 110 2162 110 60 110 60 111 2162 111 61 111 60 112 61 112 56 112 56 113 61 113 66 113 56 114 66 114 55 114 55 115 66 115 65 115 55 116 65 116 53 116 53 117 65 117 62 117 53 118 62 118 52 118 52 119 62 119 51 119 51 120 2450 120 52 120 52 121 2450 121 2454 121 52 122 2454 122 63 122 2452 123 50 123 64 123 64 124 50 124 51 124 64 125 51 125 67 125 67 126 51 126 62 126 67 127 62 127 68 127 68 128 62 128 65 128 68 129 65 129 69 129 69 130 65 130 66 130 69 131 66 131 71 131 71 132 66 132 61 132 71 133 61 133 2161 133 2161 134 61 134 2162 134 74 135 73 135 64 135 74 136 64 136 77 136 77 137 64 137 67 137 77 138 67 138 78 138 78 139 67 139 68 139 78 140 68 140 80 140 80 141 68 141 69 141 80 142 69 142 70 142 70 143 69 143 71 143 70 144 71 144 72 144 72 145 71 145 2161 145 49 146 73 146 86 146 86 147 73 147 74 147 86 148 74 148 75 148 75 149 74 149 77 149 75 150 77 150 76 150 76 151 77 151 78 151 76 152 78 152 79 152 79 153 78 153 80 153 79 154 80 154 81 154 81 155 80 155 70 155 81 156 70 156 82 156 82 157 70 157 72 157 82 158 83 158 81 158 81 159 83 159 84 159 81 160 84 160 79 160 79 161 84 161 85 161 79 162 85 162 76 162 76 163 85 163 91 163 76 164 91 164 75 164 75 165 91 165 90 165 75 166 90 166 86 166 86 167 90 167 87 167 86 168 87 168 48 168 48 169 87 169 88 169 93 170 47 170 94 170 94 171 47 171 87 171 94 172 87 172 89 172 89 173 87 173 90 173 89 174 90 174 96 174 96 175 90 175 91 175 96 176 91 176 98 176 98 177 91 177 85 177 98 178 85 178 99 178 99 179 85 179 84 179 99 180 84 180 2159 180 2159 181 84 181 83 181 46 182 93 182 92 182 92 183 93 183 94 183 92 184 94 184 23 184 23 185 94 185 89 185 23 186 89 186 3 186 3 187 89 187 96 187 3 188 96 188 95 188 95 189 96 189 98 189 95 190 98 190 97 190 97 191 98 191 99 191 97 192 99 192 2158 192 2158 193 99 193 2159 193 138 194 127 194 125 194 134 195 100 195 101 195 101 196 100 196 102 196 103 197 104 197 143 197 143 198 104 198 106 198 143 199 106 199 141 199 141 200 106 200 105 200 141 201 105 201 140 201 140 202 105 202 109 202 140 203 109 203 139 203 139 204 109 204 111 204 139 205 111 205 137 205 137 206 111 206 112 206 104 207 107 207 106 207 106 208 107 208 2255 208 106 209 2255 209 105 209 105 210 2255 210 108 210 105 211 108 211 109 211 109 212 108 212 110 212 109 213 110 213 111 213 111 214 110 214 2252 214 111 215 2252 215 112 215 112 216 2252 216 2245 216 113 217 114 217 2438 217 2438 218 114 218 130 218 2438 219 2439 219 113 219 113 220 2439 220 2445 220 113 221 2445 221 115 221 2445 222 2444 222 115 222 115 223 2444 223 2442 223 115 224 2442 224 2440 224 142 225 114 225 144 225 144 226 114 226 113 226 144 227 113 227 146 227 146 228 113 228 115 228 147 229 116 229 145 229 145 230 116 230 135 230 145 231 135 231 103 231 2433 232 124 232 126 232 150 233 118 233 117 233 117 234 118 234 119 234 117 235 119 235 126 235 126 236 119 236 120 236 126 237 120 237 2433 237 2433 238 121 238 124 238 124 239 121 239 122 239 124 240 122 240 128 240 128 241 122 241 2436 241 152 242 127 242 153 242 153 243 127 243 138 243 153 244 138 244 154 244 142 245 123 245 128 245 128 246 123 246 125 246 128 247 125 247 124 247 124 248 125 248 127 248 124 249 127 249 126 249 126 250 127 250 152 250 126 251 152 251 117 251 2436 252 2435 252 128 252 128 253 2435 253 2434 253 128 254 2434 254 142 254 142 255 2434 255 2422 255 142 256 2422 256 114 256 114 257 2422 257 129 257 114 258 129 258 130 258 133 259 136 259 131 259 132 260 133 260 102 260 102 261 133 261 131 261 102 262 131 262 101 262 116 263 134 263 135 263 135 264 134 264 101 264 135 265 101 265 103 265 103 266 101 266 131 266 103 267 131 267 104 267 104 268 131 268 136 268 104 269 136 269 107 269 2245 270 155 270 112 270 112 271 155 271 154 271 112 272 154 272 137 272 137 273 154 273 138 273 137 274 138 274 139 274 139 275 138 275 125 275 139 276 125 276 140 276 140 277 125 277 123 277 140 278 123 278 141 278 141 279 123 279 142 279 141 280 142 280 143 280 143 281 142 281 144 281 143 282 144 282 103 282 103 283 144 283 146 283 103 284 146 284 145 284 145 285 146 285 115 285 145 286 115 286 147 286 147 287 115 287 2440 287 147 288 2440 288 2425 288 189 289 187 289 191 289 2424 290 148 290 149 290 2427 291 2426 291 164 291 163 292 2429 292 159 292 162 293 150 293 160 293 160 294 150 294 117 294 160 295 117 295 151 295 151 296 117 296 152 296 151 297 152 297 158 297 158 298 152 298 153 298 158 299 153 299 157 299 157 300 153 300 154 300 157 301 154 301 156 301 156 302 154 302 155 302 156 303 155 303 2245 303 2245 304 172 304 156 304 156 305 172 305 171 305 156 306 171 306 157 306 157 307 171 307 170 307 157 308 170 308 158 308 158 309 170 309 167 309 158 310 167 310 151 310 151 311 167 311 165 311 151 312 165 312 160 312 160 313 165 313 159 313 159 314 2429 314 160 314 160 315 2429 315 161 315 160 316 161 316 162 316 2426 317 163 317 164 317 164 318 163 318 159 318 164 319 159 319 174 319 174 320 159 320 165 320 174 321 165 321 166 321 166 322 165 322 167 322 166 323 167 323 168 323 168 324 167 324 170 324 168 325 170 325 169 325 169 326 170 326 171 326 169 327 171 327 176 327 176 328 171 328 172 328 173 329 2427 329 164 329 173 330 164 330 178 330 178 331 164 331 174 331 178 332 174 332 179 332 179 333 174 333 166 333 179 334 166 334 175 334 175 335 166 335 168 335 175 336 168 336 181 336 181 337 168 337 169 337 181 338 169 338 2164 338 2164 339 169 339 176 339 148 340 2427 340 149 340 149 341 2427 341 173 341 149 342 173 342 177 342 177 343 173 343 178 343 177 344 178 344 185 344 185 345 178 345 179 345 185 346 179 346 184 346 184 347 179 347 175 347 184 348 175 348 180 348 180 349 175 349 181 349 180 350 181 350 2163 350 2163 351 181 351 2164 351 2163 352 182 352 180 352 180 353 182 353 183 353 180 354 183 354 184 354 184 355 183 355 195 355 184 356 195 356 185 356 185 357 195 357 186 357 185 358 186 358 177 358 177 359 186 359 192 359 177 360 192 360 149 360 149 361 192 361 191 361 149 362 191 362 2424 362 2424 363 191 363 187 363 188 364 189 364 198 364 198 365 189 365 191 365 198 366 191 366 190 366 190 367 191 367 192 367 190 368 192 368 193 368 193 369 192 369 186 369 193 370 186 370 194 370 194 371 186 371 195 371 194 372 195 372 196 372 196 373 195 373 183 373 196 374 183 374 197 374 197 375 183 375 182 375 2425 376 188 376 147 376 147 377 188 377 198 377 147 378 198 378 116 378 116 379 198 379 190 379 116 380 190 380 134 380 134 381 190 381 193 381 134 382 193 382 100 382 100 383 193 383 194 383 100 384 194 384 102 384 102 385 194 385 196 385 102 386 196 386 132 386 132 387 196 387 197 387 225 388 228 388 227 388 300 389 301 389 238 389 238 390 301 390 237 390 240 391 242 391 249 391 249 392 242 392 199 392 249 393 199 393 248 393 248 394 199 394 201 394 248 395 201 395 247 395 247 396 201 396 200 396 247 397 200 397 246 397 246 398 200 398 203 398 246 399 203 399 244 399 244 400 203 400 205 400 242 401 2251 401 199 401 199 402 2251 402 2253 402 199 403 2253 403 201 403 201 404 2253 404 202 404 201 405 202 405 200 405 200 406 202 406 2248 406 200 407 2248 407 203 407 203 408 2248 408 204 408 203 409 204 409 205 409 205 410 204 410 2167 410 214 411 212 411 2407 411 2407 412 212 412 206 412 2407 413 207 413 214 413 214 414 207 414 208 414 214 415 208 415 209 415 208 416 210 416 209 416 209 417 210 417 211 417 209 418 211 418 251 418 233 419 212 419 250 419 250 420 212 420 214 420 250 421 214 421 213 421 213 422 214 422 209 422 298 423 215 423 216 423 216 424 215 424 239 424 216 425 239 425 240 425 2416 426 229 426 219 426 256 427 217 427 230 427 230 428 217 428 218 428 230 429 218 429 219 429 219 430 218 430 220 430 219 431 220 431 2416 431 2416 432 221 432 229 432 229 433 221 433 2418 433 229 434 2418 434 222 434 222 435 2418 435 231 435 223 436 228 436 224 436 224 437 228 437 225 437 224 438 225 438 245 438 233 439 226 439 222 439 222 440 226 440 227 440 222 441 227 441 229 441 229 442 227 442 228 442 229 443 228 443 219 443 219 444 228 444 223 444 219 445 223 445 230 445 231 446 232 446 222 446 222 447 232 447 2417 447 222 448 2417 448 233 448 233 449 2417 449 234 449 233 450 234 450 212 450 212 451 234 451 235 451 212 452 235 452 206 452 2246 453 236 453 241 453 302 454 2246 454 237 454 237 455 2246 455 241 455 237 456 241 456 238 456 215 457 300 457 239 457 239 458 300 458 238 458 239 459 238 459 240 459 240 460 238 460 241 460 240 461 241 461 242 461 242 462 241 462 236 462 242 463 236 463 2251 463 2167 464 243 464 205 464 205 465 243 465 245 465 205 466 245 466 244 466 244 467 245 467 225 467 244 468 225 468 246 468 246 469 225 469 227 469 246 470 227 470 247 470 247 471 227 471 226 471 247 472 226 472 248 472 248 473 226 473 233 473 248 474 233 474 249 474 249 475 233 475 250 475 249 476 250 476 240 476 240 477 250 477 213 477 240 478 213 478 216 478 216 479 213 479 209 479 216 480 209 480 298 480 298 481 209 481 251 481 298 482 251 482 2420 482 289 483 2409 483 291 483 252 484 2412 484 279 484 278 485 265 485 267 485 266 486 263 486 253 486 254 487 256 487 255 487 255 488 256 488 230 488 255 489 230 489 262 489 262 490 230 490 223 490 262 491 223 491 257 491 257 492 223 492 224 492 257 493 224 493 258 493 258 494 224 494 245 494 258 495 245 495 259 495 259 496 245 496 243 496 259 497 243 497 2167 497 2167 498 271 498 259 498 259 499 271 499 260 499 259 500 260 500 258 500 258 501 260 501 270 501 258 502 270 502 257 502 257 503 270 503 269 503 257 504 269 504 262 504 262 505 269 505 261 505 262 506 261 506 255 506 255 507 261 507 253 507 253 508 263 508 255 508 255 509 263 509 264 509 255 510 264 510 254 510 265 511 266 511 267 511 267 512 266 512 253 512 267 513 253 513 268 513 268 514 253 514 261 514 268 515 261 515 273 515 273 516 261 516 269 516 273 517 269 517 274 517 274 518 269 518 270 518 274 519 270 519 275 519 275 520 270 520 260 520 275 521 260 521 2168 521 2168 522 260 522 271 522 272 523 278 523 267 523 272 524 267 524 281 524 281 525 267 525 268 525 281 526 268 526 282 526 282 527 268 527 273 527 282 528 273 528 284 528 284 529 273 529 274 529 284 530 274 530 276 530 276 531 274 531 275 531 276 532 275 532 277 532 277 533 275 533 2168 533 2412 534 278 534 279 534 279 535 278 535 272 535 279 536 272 536 280 536 280 537 272 537 281 537 280 538 281 538 287 538 287 539 281 539 282 539 287 540 282 540 283 540 283 541 282 541 284 541 283 542 284 542 286 542 286 543 284 543 276 543 286 544 276 544 285 544 285 545 276 545 277 545 285 546 2165 546 286 546 286 547 2165 547 297 547 286 548 297 548 283 548 283 549 297 549 295 549 283 550 295 550 287 550 287 551 295 551 288 551 287 552 288 552 280 552 280 553 288 553 292 553 280 554 292 554 279 554 279 555 292 555 291 555 279 556 291 556 252 556 252 557 291 557 2409 557 2411 558 289 558 290 558 290 559 289 559 291 559 290 560 291 560 299 560 299 561 291 561 292 561 299 562 292 562 293 562 293 563 292 563 288 563 293 564 288 564 294 564 294 565 288 565 295 565 294 566 295 566 296 566 296 567 295 567 297 567 296 568 297 568 2166 568 2166 569 297 569 2165 569 2420 570 2411 570 298 570 298 571 2411 571 290 571 298 572 290 572 215 572 215 573 290 573 299 573 215 574 299 574 300 574 300 575 299 575 293 575 300 576 293 576 301 576 301 577 293 577 294 577 301 578 294 578 237 578 237 579 294 579 296 579 237 580 296 580 302 580 302 581 296 581 2166 581 342 582 330 582 343 582 398 583 304 583 303 583 303 584 304 584 336 584 338 585 310 585 346 585 346 586 310 586 305 586 346 587 305 587 306 587 306 588 305 588 307 588 306 589 307 589 345 589 345 590 307 590 308 590 345 591 308 591 344 591 344 592 308 592 309 592 344 593 309 593 341 593 341 594 309 594 339 594 310 595 2247 595 305 595 305 596 2247 596 311 596 305 597 311 597 307 597 307 598 311 598 312 598 307 599 312 599 308 599 308 600 312 600 313 600 308 601 313 601 309 601 309 602 313 602 2243 602 309 603 2243 603 339 603 339 604 2243 604 358 604 316 605 315 605 314 605 314 606 315 606 2383 606 314 607 317 607 316 607 316 608 317 608 318 608 316 609 318 609 349 609 318 610 319 610 349 610 349 611 319 611 320 611 349 612 320 612 350 612 333 613 315 613 321 613 321 614 315 614 316 614 321 615 316 615 347 615 347 616 316 616 349 616 322 617 397 617 348 617 348 618 397 618 337 618 348 619 337 619 338 619 2398 620 323 620 327 620 324 621 325 621 353 621 353 622 325 622 326 622 353 623 326 623 327 623 327 624 326 624 2395 624 327 625 2395 625 2398 625 2398 626 2402 626 323 626 323 627 2402 627 2401 627 323 628 2401 628 331 628 331 629 2401 629 2399 629 354 630 330 630 328 630 328 631 330 631 342 631 328 632 342 632 340 632 333 633 329 633 331 633 331 634 329 634 343 634 331 635 343 635 323 635 323 636 343 636 330 636 323 637 330 637 327 637 327 638 330 638 354 638 327 639 354 639 353 639 2399 640 332 640 331 640 331 641 332 641 2384 641 331 642 2384 642 333 642 333 643 2384 643 334 643 333 644 334 644 315 644 315 645 334 645 2404 645 315 646 2404 646 2383 646 2242 647 2241 647 335 647 402 648 2242 648 336 648 336 649 2242 649 335 649 336 650 335 650 303 650 397 651 398 651 337 651 337 652 398 652 303 652 337 653 303 653 338 653 338 654 303 654 335 654 338 655 335 655 310 655 310 656 335 656 2241 656 310 657 2241 657 2247 657 358 658 357 658 339 658 339 659 357 659 340 659 339 660 340 660 341 660 341 661 340 661 342 661 341 662 342 662 344 662 344 663 342 663 343 663 344 664 343 664 345 664 345 665 343 665 329 665 345 666 329 666 306 666 306 667 329 667 333 667 306 668 333 668 346 668 346 669 333 669 321 669 346 670 321 670 338 670 338 671 321 671 347 671 338 672 347 672 348 672 348 673 347 673 349 673 348 674 349 674 322 674 322 675 349 675 350 675 322 676 350 676 351 676 2387 677 352 677 390 677 2386 678 377 678 389 678 2390 679 2389 679 368 679 2394 680 2393 680 364 680 367 681 324 681 365 681 365 682 324 682 353 682 365 683 353 683 355 683 355 684 353 684 354 684 355 685 354 685 362 685 362 686 354 686 328 686 362 687 328 687 359 687 359 688 328 688 340 688 359 689 340 689 356 689 356 690 340 690 357 690 356 691 357 691 358 691 358 692 372 692 356 692 356 693 372 693 360 693 356 694 360 694 359 694 359 695 360 695 361 695 359 696 361 696 362 696 362 697 361 697 363 697 362 698 363 698 355 698 355 699 363 699 370 699 355 700 370 700 365 700 365 701 370 701 364 701 364 702 2393 702 365 702 365 703 2393 703 366 703 365 704 366 704 367 704 2389 705 2394 705 368 705 368 706 2394 706 364 706 368 707 364 707 373 707 373 708 364 708 370 708 373 709 370 709 369 709 369 710 370 710 363 710 369 711 363 711 375 711 375 712 363 712 361 712 375 713 361 713 376 713 376 714 361 714 360 714 376 715 360 715 371 715 371 716 360 716 372 716 378 717 2390 717 368 717 378 718 368 718 379 718 379 719 368 719 373 719 379 720 373 720 374 720 374 721 373 721 369 721 374 722 369 722 381 722 381 723 369 723 375 723 381 724 375 724 383 724 383 725 375 725 376 725 383 726 376 726 2170 726 2170 727 376 727 371 727 377 728 2390 728 389 728 389 729 2390 729 378 729 389 730 378 730 388 730 388 731 378 731 379 731 388 732 379 732 387 732 387 733 379 733 374 733 387 734 374 734 380 734 380 735 374 735 381 735 380 736 381 736 384 736 384 737 381 737 383 737 384 738 383 738 382 738 382 739 383 739 2170 739 382 740 2169 740 384 740 384 741 2169 741 385 741 384 742 385 742 380 742 380 743 385 743 394 743 380 744 394 744 387 744 387 745 394 745 386 745 387 746 386 746 388 746 388 747 386 747 392 747 388 748 392 748 389 748 389 749 392 749 390 749 389 750 390 750 2386 750 2386 751 390 751 352 751 396 752 2387 752 391 752 391 753 2387 753 390 753 391 754 390 754 393 754 393 755 390 755 392 755 393 756 392 756 399 756 399 757 392 757 386 757 399 758 386 758 400 758 400 759 386 759 394 759 400 760 394 760 401 760 401 761 394 761 385 761 401 762 385 762 395 762 395 763 385 763 2169 763 351 764 396 764 322 764 322 765 396 765 391 765 322 766 391 766 397 766 397 767 391 767 393 767 397 768 393 768 398 768 398 769 393 769 399 769 398 770 399 770 304 770 304 771 399 771 400 771 304 772 400 772 336 772 336 773 400 773 401 773 336 774 401 774 402 774 402 775 401 775 395 775 2240 776 2244 776 411 776 411 777 2244 777 404 777 411 778 404 778 414 778 414 779 404 779 403 779 2244 780 405 780 404 780 404 781 405 781 409 781 404 782 409 782 403 782 403 783 409 783 406 783 407 784 406 784 409 784 407 785 409 785 408 785 408 786 409 786 405 786 408 787 405 787 1041 787 2156 788 2240 788 410 788 410 789 2240 789 411 789 412 790 1085 790 413 790 2154 791 2156 791 413 791 413 792 2156 792 410 792 413 793 410 793 412 793 412 794 410 794 411 794 412 795 411 795 414 795 1041 796 2214 796 408 796 408 797 2214 797 416 797 408 798 416 798 407 798 407 799 416 799 417 799 2214 800 415 800 416 800 416 801 415 801 435 801 416 802 435 802 417 802 417 803 435 803 1071 803 2154 804 413 804 425 804 2154 805 425 805 2153 805 2153 806 425 806 418 806 2153 807 418 807 419 807 419 808 418 808 427 808 419 809 427 809 420 809 420 810 427 810 429 810 420 811 429 811 421 811 421 812 429 812 422 812 421 813 422 813 2148 813 2148 814 422 814 423 814 2148 815 423 815 2149 815 2149 816 423 816 433 816 2149 817 433 817 2147 817 2147 818 433 818 440 818 2147 819 440 819 424 819 413 820 1085 820 1086 820 413 821 1086 821 425 821 425 822 1086 822 426 822 425 823 426 823 418 823 418 824 426 824 428 824 418 825 428 825 427 825 427 826 428 826 430 826 427 827 430 827 429 827 429 828 430 828 1088 828 429 829 1088 829 422 829 422 830 1088 830 431 830 422 831 431 831 423 831 423 832 431 832 432 832 423 833 432 833 433 833 433 834 432 834 434 834 433 835 434 835 440 835 415 836 2146 836 435 836 435 837 2146 837 436 837 435 838 436 838 1071 838 1071 839 436 839 438 839 2146 840 2145 840 436 840 436 841 2145 841 437 841 436 842 437 842 438 842 438 843 437 843 1072 843 466 844 424 844 439 844 439 845 424 845 440 845 439 846 440 846 2079 846 2079 847 440 847 434 847 443 848 441 848 442 848 442 849 457 849 443 849 443 850 457 850 455 850 443 851 455 851 2140 851 2140 852 455 852 454 852 2140 853 454 853 444 853 444 854 454 854 445 854 445 855 454 855 449 855 445 856 449 856 2138 856 2144 857 446 857 447 857 447 858 446 858 2141 858 447 859 2141 859 448 859 448 860 2141 860 2138 860 448 861 2138 861 451 861 451 862 2138 862 449 862 1083 863 1072 863 437 863 2145 864 2144 864 437 864 437 865 2144 865 447 865 437 866 447 866 1083 866 1083 867 447 867 448 867 1083 868 448 868 450 868 450 869 448 869 451 869 450 870 451 870 452 870 452 871 451 871 449 871 452 872 449 872 453 872 453 873 449 873 454 873 453 874 454 874 1078 874 1078 875 454 875 455 875 1078 876 455 876 456 876 456 877 455 877 457 877 456 878 457 878 1077 878 1077 879 457 879 442 879 1077 880 442 880 1074 880 465 881 467 881 458 881 465 882 458 882 459 882 459 883 458 883 474 883 459 884 474 884 460 884 460 885 474 885 461 885 461 886 474 886 473 886 461 887 473 887 2150 887 468 888 462 888 470 888 470 889 462 889 463 889 470 890 463 890 464 890 464 891 463 891 2150 891 464 892 2150 892 471 892 471 893 2150 893 473 893 469 894 2099 894 477 894 465 895 466 895 467 895 467 896 466 896 439 896 467 897 439 897 2079 897 2155 898 468 898 477 898 477 899 468 899 470 899 477 900 470 900 469 900 469 901 470 901 464 901 469 902 464 902 2086 902 2086 903 464 903 471 903 2086 904 471 904 472 904 472 905 471 905 473 905 472 906 473 906 2084 906 2084 907 473 907 474 907 2084 908 474 908 2083 908 2083 909 474 909 458 909 2083 910 458 910 2082 910 2082 911 458 911 467 911 2082 912 467 912 2080 912 2080 913 467 913 2079 913 441 914 475 914 442 914 442 915 475 915 492 915 442 916 492 916 1074 916 1074 917 492 917 498 917 478 918 2103 918 476 918 476 919 2103 919 499 919 476 920 499 920 2160 920 2160 921 499 921 2157 921 2160 922 2155 922 476 922 476 923 2155 923 477 923 476 924 477 924 478 924 478 925 477 925 2099 925 2143 926 494 926 479 926 2143 927 479 927 2142 927 2142 928 479 928 480 928 2142 929 480 929 481 929 481 930 480 930 482 930 481 931 482 931 483 931 483 932 482 932 484 932 483 933 484 933 486 933 486 934 484 934 485 934 486 935 485 935 487 935 487 936 485 936 488 936 487 937 488 937 490 937 490 938 488 938 489 938 490 939 489 939 491 939 491 940 489 940 492 940 491 941 492 941 475 941 494 942 503 942 493 942 494 943 493 943 479 943 479 944 493 944 2090 944 479 945 2090 945 480 945 480 946 2090 946 2091 946 480 947 2091 947 482 947 482 948 2091 948 495 948 482 949 495 949 484 949 484 950 495 950 496 950 484 951 496 951 485 951 485 952 496 952 2095 952 485 953 2095 953 488 953 488 954 2095 954 497 954 488 955 497 955 489 955 489 956 497 956 498 956 489 957 498 957 492 957 2103 958 500 958 499 958 499 959 500 959 501 959 499 960 501 960 2157 960 2157 961 501 961 2257 961 500 962 506 962 501 962 501 963 506 963 502 963 501 964 502 964 2257 964 2257 965 502 965 2131 965 505 966 504 966 2135 966 2135 967 504 967 2136 967 2101 968 503 968 494 968 2143 969 2136 969 494 969 494 970 2136 970 504 970 494 971 504 971 2101 971 2101 972 504 972 505 972 2101 973 505 973 510 973 2222 974 2131 974 502 974 2222 975 502 975 508 975 508 976 502 976 506 976 508 977 506 977 507 977 507 978 2105 978 508 978 508 979 2105 979 509 979 508 980 509 980 2222 980 2222 981 509 981 2225 981 2105 982 510 982 509 982 509 983 510 983 505 983 509 984 505 984 2225 984 2225 985 505 985 2135 985 511 986 2177 986 2119 986 2119 987 2177 987 2178 987 511 988 523 988 2177 988 2177 989 523 989 515 989 2177 990 515 990 514 990 2176 991 2177 991 520 991 520 992 2177 992 514 992 520 993 514 993 512 993 512 994 514 994 2100 994 513 995 2100 995 521 995 521 996 2100 996 514 996 521 997 514 997 534 997 534 998 514 998 515 998 516 999 517 999 518 999 518 1000 517 1000 519 1000 518 1001 519 1001 2106 1001 2106 1002 519 1002 2104 1002 517 1003 2176 1003 519 1003 519 1004 2176 1004 520 1004 519 1005 520 1005 2104 1005 2104 1006 520 1006 512 1006 521 1007 522 1007 513 1007 513 1008 522 1008 2088 1008 534 1009 515 1009 524 1009 524 1010 515 1010 523 1010 524 1011 523 1011 511 1011 525 1012 540 1012 528 1012 2134 1013 525 1013 529 1013 2120 1014 526 1014 529 1014 529 1015 526 1015 527 1015 529 1016 527 1016 2134 1016 529 1017 530 1017 2120 1017 2120 1018 530 1018 531 1018 2120 1019 531 1019 2121 1019 2121 1020 531 1020 535 1020 2121 1021 535 1021 2122 1021 525 1022 528 1022 529 1022 529 1023 528 1023 2094 1023 529 1024 2094 1024 530 1024 530 1025 2094 1025 2093 1025 530 1026 2093 1026 531 1026 531 1027 2093 1027 2092 1027 531 1028 2092 1028 535 1028 535 1029 2092 1029 2089 1029 535 1030 2089 1030 536 1030 536 1031 2089 1031 533 1031 536 1032 533 1032 532 1032 532 1033 533 1033 522 1033 532 1034 522 1034 524 1034 524 1035 522 1035 521 1035 524 1036 521 1036 534 1036 2122 1037 535 1037 2124 1037 2124 1038 535 1038 536 1038 2124 1039 536 1039 537 1039 537 1040 536 1040 532 1040 537 1041 532 1041 538 1041 538 1042 532 1042 524 1042 538 1043 524 1043 2126 1043 2126 1044 524 1044 511 1044 2126 1045 511 1045 2119 1045 539 1046 516 1046 518 1046 539 1047 518 1047 548 1047 548 1048 518 1048 2106 1048 548 1049 2106 1049 2102 1049 1075 1050 540 1050 541 1050 541 1051 540 1051 525 1051 541 1052 525 1052 542 1052 542 1053 525 1053 2134 1053 543 1054 544 1054 545 1054 545 1055 544 1055 547 1055 545 1056 547 1056 2098 1056 2098 1057 547 1057 546 1057 544 1058 539 1058 547 1058 547 1059 539 1059 548 1059 547 1060 548 1060 546 1060 546 1061 548 1061 2102 1061 1084 1062 1082 1062 549 1062 549 1063 1082 1063 560 1063 566 1064 565 1064 553 1064 553 1065 565 1065 571 1065 553 1066 571 1066 570 1066 541 1067 542 1067 1052 1067 1075 1068 541 1068 554 1068 541 1069 1052 1069 554 1069 554 1070 1052 1070 1050 1070 554 1071 1050 1071 550 1071 1050 1072 1049 1072 550 1072 550 1073 1049 1073 1048 1073 550 1074 1048 1074 556 1074 556 1075 1048 1075 551 1075 1047 1076 559 1076 551 1076 551 1077 559 1077 558 1077 551 1078 558 1078 556 1078 1047 1079 1046 1079 559 1079 559 1080 1046 1080 1045 1080 559 1081 1045 1081 552 1081 552 1082 1045 1082 1044 1082 552 1083 1044 1083 553 1083 553 1084 1044 1084 567 1084 553 1085 567 1085 566 1085 1075 1086 554 1086 1076 1086 1076 1087 554 1087 550 1087 1076 1088 550 1088 555 1088 555 1089 550 1089 556 1089 555 1090 556 1090 1079 1090 1079 1091 556 1091 558 1091 1079 1092 558 1092 557 1092 557 1093 558 1093 559 1093 557 1094 559 1094 1080 1094 1080 1095 559 1095 552 1095 1080 1096 552 1096 1081 1096 1081 1097 552 1097 553 1097 1081 1098 553 1098 1082 1098 1082 1099 553 1099 570 1099 1082 1100 570 1100 560 1100 2107 1101 2188 1101 575 1101 575 1102 2188 1102 564 1102 561 1103 2097 1103 591 1103 591 1104 574 1104 561 1104 561 1105 574 1105 562 1105 561 1106 562 1106 2188 1106 2188 1107 562 1107 563 1107 2188 1108 563 1108 564 1108 2188 1109 543 1109 561 1109 561 1110 543 1110 545 1110 561 1111 545 1111 2097 1111 2097 1112 545 1112 2098 1112 565 1113 566 1113 1029 1113 1029 1114 566 1114 567 1114 1029 1115 567 1115 568 1115 569 1116 572 1116 549 1116 549 1117 560 1117 569 1117 569 1118 560 1118 570 1118 569 1119 570 1119 1029 1119 1029 1120 570 1120 571 1120 1029 1121 571 1121 565 1121 1029 1122 592 1122 569 1122 569 1123 592 1123 573 1123 569 1124 573 1124 572 1124 572 1125 573 1125 1070 1125 562 1126 574 1126 589 1126 589 1127 574 1127 591 1127 575 1128 564 1128 589 1128 589 1129 564 1129 563 1129 589 1130 563 1130 562 1130 575 1131 589 1131 2108 1131 2108 1132 589 1132 576 1132 2108 1133 576 1133 2112 1133 2112 1134 576 1134 587 1134 2112 1135 587 1135 2113 1135 2113 1136 587 1136 586 1136 2113 1137 586 1137 2114 1137 2114 1138 586 1138 584 1138 2114 1139 584 1139 578 1139 578 1140 584 1140 577 1140 578 1141 577 1141 2116 1141 2116 1142 577 1142 579 1142 579 1143 577 1143 580 1143 579 1144 580 1144 581 1144 582 1145 599 1145 580 1145 580 1146 599 1146 2110 1146 580 1147 2110 1147 581 1147 2081 1148 2078 1148 582 1148 582 1149 580 1149 2081 1149 2081 1150 580 1150 577 1150 2081 1151 577 1151 583 1151 583 1152 577 1152 584 1152 583 1153 584 1153 585 1153 585 1154 584 1154 586 1154 585 1155 586 1155 588 1155 588 1156 586 1156 587 1156 588 1157 587 1157 2085 1157 2085 1158 587 1158 576 1158 2085 1159 576 1159 2087 1159 2087 1160 576 1160 589 1160 2087 1161 589 1161 590 1161 590 1162 589 1162 591 1162 590 1163 591 1163 2096 1163 592 1164 595 1164 573 1164 573 1165 595 1165 593 1165 573 1166 593 1166 1070 1166 1070 1167 593 1167 594 1167 595 1168 1026 1168 593 1168 593 1169 1026 1169 596 1169 593 1170 596 1170 594 1170 594 1171 596 1171 1069 1171 2078 1172 597 1172 598 1172 2078 1173 598 1173 582 1173 582 1174 598 1174 602 1174 582 1175 602 1175 599 1175 600 1176 1069 1176 596 1176 600 1177 596 1177 621 1177 621 1178 596 1178 1026 1178 621 1179 1026 1179 1035 1179 608 1180 1062 1180 616 1180 620 1181 601 1181 1073 1181 604 1182 598 1182 597 1182 602 1183 598 1183 1064 1183 1064 1184 598 1184 604 1184 1064 1185 604 1185 603 1185 603 1186 604 1186 605 1186 603 1187 605 1187 1066 1187 616 1188 1062 1188 605 1188 605 1189 1062 1189 1068 1189 605 1190 1068 1190 1066 1190 628 1191 606 1191 613 1191 613 1192 606 1192 631 1192 613 1193 631 1193 607 1193 608 1194 616 1194 609 1194 609 1195 616 1195 618 1195 609 1196 618 1196 611 1196 611 1197 618 1197 610 1197 611 1198 610 1198 1060 1198 1060 1199 610 1199 612 1199 1060 1200 612 1200 1061 1200 1061 1201 612 1201 613 1201 1061 1202 613 1202 1055 1202 1055 1203 613 1203 607 1203 1055 1204 607 1204 1053 1204 597 1205 1089 1205 604 1205 604 1206 1089 1206 614 1206 604 1207 614 1207 605 1207 605 1208 614 1208 615 1208 605 1209 615 1209 616 1209 616 1210 615 1210 617 1210 616 1211 617 1211 618 1211 618 1212 617 1212 1087 1212 618 1213 1087 1213 610 1213 610 1214 1087 1214 619 1214 610 1215 619 1215 612 1215 612 1216 619 1216 620 1216 612 1217 620 1217 613 1217 613 1218 620 1218 1073 1218 613 1219 1073 1219 628 1219 1035 1220 622 1220 621 1220 621 1221 622 1221 624 1221 621 1222 624 1222 600 1222 600 1223 624 1223 625 1223 622 1224 623 1224 624 1224 624 1225 623 1225 626 1225 624 1226 626 1226 625 1226 625 1227 626 1227 627 1227 1034 1228 1054 1228 1053 1228 1053 1229 607 1229 1034 1229 1034 1230 607 1230 631 1230 1034 1231 631 1231 630 1231 623 1232 1034 1232 626 1232 626 1233 1034 1233 630 1233 626 1234 630 1234 627 1234 627 1235 630 1235 629 1235 1073 1236 629 1236 628 1236 628 1237 629 1237 630 1237 628 1238 630 1238 606 1238 606 1239 630 1239 631 1239 651 1240 713 1240 632 1240 632 1241 713 1241 709 1241 632 1242 709 1242 2601 1242 2601 1243 709 1243 633 1243 2601 1244 633 1244 2602 1244 2602 1245 633 1245 634 1245 2602 1246 634 1246 636 1246 634 1247 635 1247 636 1247 636 1248 635 1248 637 1248 636 1249 637 1249 2615 1249 2615 1250 637 1250 638 1250 2615 1251 638 1251 639 1251 639 1252 638 1252 640 1252 639 1253 640 1253 641 1253 641 1254 640 1254 1477 1254 641 1255 1477 1255 642 1255 642 1256 1477 1256 1476 1256 642 1257 1476 1257 643 1257 643 1258 1476 1258 1474 1258 643 1259 1474 1259 644 1259 644 1260 1474 1260 1473 1260 644 1261 1473 1261 2613 1261 2613 1262 1473 1262 645 1262 2613 1263 645 1263 2609 1263 2609 1264 645 1264 1471 1264 2609 1265 1471 1265 646 1265 646 1266 1471 1266 1470 1266 646 1267 1470 1267 647 1267 647 1268 1470 1268 648 1268 647 1269 648 1269 649 1269 649 1270 648 1270 650 1270 649 1271 650 1271 2605 1271 2605 1272 650 1272 2288 1272 2605 1273 2288 1273 2606 1273 2606 1274 2288 1274 652 1274 2606 1275 652 1275 651 1275 651 1276 652 1276 653 1276 651 1277 653 1277 713 1277 682 1278 654 1278 671 1278 654 1279 662 1279 665 1279 655 1280 656 1280 1406 1280 662 1281 678 1281 663 1281 663 1282 678 1282 661 1282 657 1283 658 1283 791 1283 791 1284 658 1284 659 1284 791 1285 659 1285 790 1285 790 1286 659 1286 660 1286 790 1287 660 1287 789 1287 789 1288 660 1288 663 1288 789 1289 663 1289 785 1289 785 1290 663 1290 661 1290 662 1291 663 1291 665 1291 665 1292 663 1292 660 1292 665 1293 660 1293 666 1293 666 1294 660 1294 659 1294 666 1295 659 1295 664 1295 664 1296 659 1296 658 1296 664 1297 658 1297 668 1297 654 1298 665 1298 671 1298 671 1299 665 1299 666 1299 671 1300 666 1300 670 1300 670 1301 666 1301 664 1301 670 1302 664 1302 667 1302 667 1303 664 1303 668 1303 667 1304 668 1304 669 1304 714 1305 715 1305 669 1305 669 1306 715 1306 716 1306 669 1307 716 1307 667 1307 667 1308 716 1308 717 1308 667 1309 717 1309 670 1309 670 1310 717 1310 718 1310 670 1311 718 1311 671 1311 671 1312 718 1312 719 1312 671 1313 719 1313 682 1313 672 1314 714 1314 676 1314 676 1315 714 1315 669 1315 676 1316 669 1316 675 1316 675 1317 669 1317 668 1317 675 1318 668 1318 673 1318 673 1319 668 1319 658 1319 673 1320 658 1320 674 1320 674 1321 658 1321 657 1321 674 1322 655 1322 673 1322 673 1323 655 1323 1406 1323 673 1324 1406 1324 675 1324 675 1325 1406 1325 677 1325 675 1326 677 1326 676 1326 676 1327 677 1327 1404 1327 676 1328 1404 1328 672 1328 672 1329 1404 1329 2291 1329 679 1330 661 1330 678 1330 679 1331 678 1331 680 1331 680 1332 678 1332 662 1332 680 1333 662 1333 705 1333 705 1334 662 1334 654 1334 705 1335 654 1335 681 1335 681 1336 654 1336 682 1336 681 1337 682 1337 708 1337 2290 1338 691 1338 697 1338 691 1339 686 1339 688 1339 704 1340 679 1340 680 1340 686 1341 1437 1341 687 1341 687 1342 1437 1342 1576 1342 804 1343 683 1343 802 1343 802 1344 683 1344 690 1344 802 1345 690 1345 684 1345 684 1346 690 1346 689 1346 684 1347 689 1347 801 1347 801 1348 689 1348 687 1348 801 1349 687 1349 685 1349 685 1350 687 1350 1576 1350 686 1351 687 1351 688 1351 688 1352 687 1352 689 1352 688 1353 689 1353 692 1353 692 1354 689 1354 690 1354 692 1355 690 1355 694 1355 694 1356 690 1356 683 1356 694 1357 683 1357 700 1357 691 1358 688 1358 697 1358 697 1359 688 1359 692 1359 697 1360 692 1360 693 1360 693 1361 692 1361 694 1361 693 1362 694 1362 695 1362 695 1363 694 1363 700 1363 695 1364 700 1364 701 1364 702 1365 710 1365 701 1365 701 1366 710 1366 711 1366 701 1367 711 1367 695 1367 695 1368 711 1368 712 1368 695 1369 712 1369 693 1369 693 1370 712 1370 696 1370 693 1371 696 1371 697 1371 697 1372 696 1372 698 1372 697 1373 698 1373 2290 1373 804 1374 805 1374 683 1374 683 1375 805 1375 699 1375 683 1376 699 1376 700 1376 700 1377 699 1377 706 1377 700 1378 706 1378 701 1378 701 1379 706 1379 707 1379 701 1380 707 1380 702 1380 702 1381 707 1381 703 1381 805 1382 704 1382 699 1382 699 1383 704 1383 680 1383 699 1384 680 1384 706 1384 706 1385 680 1385 705 1385 706 1386 705 1386 707 1386 707 1387 705 1387 681 1387 707 1388 681 1388 703 1388 703 1389 681 1389 708 1389 708 1390 633 1390 703 1390 703 1391 633 1391 709 1391 703 1392 709 1392 702 1392 702 1393 709 1393 710 1393 710 1394 709 1394 713 1394 710 1395 713 1395 711 1395 711 1396 713 1396 712 1396 712 1397 713 1397 653 1397 712 1398 653 1398 696 1398 696 1399 653 1399 698 1399 698 1400 653 1400 652 1400 698 1401 652 1401 2290 1401 2291 1402 640 1402 672 1402 672 1403 640 1403 638 1403 672 1404 638 1404 714 1404 714 1405 638 1405 715 1405 715 1406 638 1406 637 1406 715 1407 637 1407 716 1407 716 1408 637 1408 717 1408 717 1409 637 1409 635 1409 717 1410 635 1410 718 1410 718 1411 635 1411 719 1411 719 1412 635 1412 634 1412 719 1413 634 1413 682 1413 806 1414 776 1414 720 1414 720 1415 776 1415 721 1415 720 1416 721 1416 723 1416 721 1417 722 1417 723 1417 723 1418 722 1418 737 1418 723 1419 737 1419 780 1419 780 1420 737 1420 734 1420 780 1421 734 1421 724 1421 724 1422 734 1422 732 1422 724 1423 732 1423 782 1423 732 1424 725 1424 782 1424 782 1425 725 1425 745 1425 782 1426 745 1426 726 1426 726 1427 745 1427 727 1427 726 1428 727 1428 728 1428 728 1429 727 1429 747 1429 728 1430 747 1430 729 1430 729 1431 747 1431 749 1431 776 1432 730 1432 731 1432 730 1433 775 1433 1043 1433 744 1434 725 1434 742 1434 742 1435 725 1435 732 1435 742 1436 732 1436 733 1436 733 1437 732 1437 734 1437 733 1438 734 1438 735 1438 735 1439 734 1439 737 1439 735 1440 737 1440 736 1440 736 1441 737 1441 722 1441 736 1442 722 1442 731 1442 731 1443 722 1443 721 1443 731 1444 721 1444 776 1444 730 1445 1043 1445 731 1445 731 1446 1043 1446 738 1446 731 1447 738 1447 736 1447 736 1448 738 1448 739 1448 736 1449 739 1449 735 1449 735 1450 739 1450 740 1450 735 1451 740 1451 733 1451 733 1452 740 1452 741 1452 733 1453 741 1453 742 1453 742 1454 741 1454 743 1454 742 1455 743 1455 744 1455 747 1456 727 1456 744 1456 744 1457 727 1457 745 1457 744 1458 745 1458 725 1458 1051 1459 2133 1459 746 1459 746 1460 2133 1460 748 1460 743 1461 1051 1461 744 1461 744 1462 1051 1462 746 1462 744 1463 746 1463 747 1463 747 1464 746 1464 748 1464 747 1465 748 1465 749 1465 1506 1466 760 1466 793 1466 793 1467 760 1467 750 1467 793 1468 750 1468 751 1468 750 1469 768 1469 751 1469 751 1470 768 1470 766 1470 751 1471 766 1471 795 1471 795 1472 766 1472 753 1472 795 1473 753 1473 752 1473 752 1474 753 1474 763 1474 752 1475 763 1475 754 1475 763 1476 755 1476 754 1476 754 1477 755 1477 773 1477 754 1478 773 1478 756 1478 756 1479 773 1479 772 1479 756 1480 772 1480 757 1480 757 1481 772 1481 758 1481 757 1482 758 1482 759 1482 759 1483 758 1483 778 1483 760 1484 1509 1484 761 1484 1509 1485 762 1485 1063 1485 771 1486 755 1486 770 1486 770 1487 755 1487 763 1487 770 1488 763 1488 764 1488 764 1489 763 1489 753 1489 764 1490 753 1490 765 1490 765 1491 753 1491 766 1491 765 1492 766 1492 767 1492 767 1493 766 1493 768 1493 767 1494 768 1494 761 1494 761 1495 768 1495 750 1495 761 1496 750 1496 760 1496 1509 1497 1063 1497 761 1497 761 1498 1063 1498 1065 1498 761 1499 1065 1499 767 1499 767 1500 1065 1500 1067 1500 767 1501 1067 1501 765 1501 765 1502 1067 1502 769 1502 765 1503 769 1503 764 1503 764 1504 769 1504 1058 1504 764 1505 1058 1505 770 1505 770 1506 1058 1506 1059 1506 770 1507 1059 1507 771 1507 758 1508 772 1508 771 1508 771 1509 772 1509 773 1509 771 1510 773 1510 755 1510 1057 1511 1056 1511 774 1511 774 1512 1056 1512 777 1512 1059 1513 1057 1513 771 1513 771 1514 1057 1514 774 1514 771 1515 774 1515 758 1515 758 1516 774 1516 777 1516 758 1517 777 1517 778 1517 778 1518 776 1518 759 1518 759 1519 776 1519 806 1519 1056 1520 775 1520 730 1520 1056 1521 730 1521 777 1521 777 1522 730 1522 776 1522 777 1523 776 1523 778 1523 661 1524 779 1524 786 1524 779 1525 806 1525 720 1525 779 1526 720 1526 786 1526 786 1527 720 1527 723 1527 786 1528 723 1528 787 1528 787 1529 723 1529 780 1529 787 1530 780 1530 788 1530 788 1531 780 1531 724 1531 788 1532 724 1532 781 1532 781 1533 724 1533 782 1533 781 1534 782 1534 783 1534 783 1535 782 1535 726 1535 783 1536 726 1536 792 1536 792 1537 726 1537 728 1537 792 1538 728 1538 784 1538 784 1539 728 1539 729 1539 784 1540 729 1540 1575 1540 661 1541 786 1541 785 1541 785 1542 786 1542 787 1542 785 1543 787 1543 789 1543 789 1544 787 1544 788 1544 789 1545 788 1545 790 1545 790 1546 788 1546 781 1546 790 1547 781 1547 791 1547 791 1548 781 1548 783 1548 791 1549 783 1549 657 1549 657 1550 783 1550 792 1550 657 1551 792 1551 674 1551 674 1552 792 1552 784 1552 674 1553 784 1553 655 1553 655 1554 784 1554 1575 1554 655 1555 1575 1555 656 1555 1576 1556 1578 1556 794 1556 1578 1557 1506 1557 793 1557 1578 1558 793 1558 794 1558 794 1559 793 1559 751 1559 794 1560 751 1560 800 1560 800 1561 751 1561 795 1561 800 1562 795 1562 796 1562 796 1563 795 1563 752 1563 796 1564 752 1564 797 1564 797 1565 752 1565 754 1565 797 1566 754 1566 803 1566 803 1567 754 1567 756 1567 803 1568 756 1568 798 1568 798 1569 756 1569 757 1569 798 1570 757 1570 799 1570 799 1571 757 1571 759 1571 799 1572 759 1572 807 1572 1576 1573 794 1573 685 1573 685 1574 794 1574 800 1574 685 1575 800 1575 801 1575 801 1576 800 1576 796 1576 801 1577 796 1577 684 1577 684 1578 796 1578 797 1578 684 1579 797 1579 802 1579 802 1580 797 1580 803 1580 802 1581 803 1581 804 1581 804 1582 803 1582 798 1582 804 1583 798 1583 805 1583 805 1584 798 1584 799 1584 805 1585 799 1585 704 1585 704 1586 799 1586 807 1586 704 1587 807 1587 679 1587 759 1588 806 1588 779 1588 759 1589 779 1589 807 1589 807 1590 779 1590 661 1590 807 1591 661 1591 679 1591 2277 1592 2283 1592 808 1592 809 1593 2277 1593 819 1593 819 1594 2277 1594 808 1594 819 1595 808 1595 821 1595 821 1596 808 1596 810 1596 1375 1597 810 1597 808 1597 811 1598 834 1598 812 1598 811 1599 812 1599 2282 1599 2282 1600 812 1600 808 1600 2282 1601 808 1601 2283 1601 813 1602 814 1602 812 1602 812 1603 814 1603 1377 1603 812 1604 1377 1604 808 1604 808 1605 1377 1605 815 1605 808 1606 815 1606 1375 1606 809 1607 819 1607 824 1607 822 1608 816 1608 1338 1608 1338 1609 816 1609 817 1609 1338 1610 817 1610 818 1610 818 1611 817 1611 826 1611 818 1612 826 1612 1391 1612 1391 1613 826 1613 824 1613 1391 1614 824 1614 820 1614 820 1615 824 1615 819 1615 820 1616 819 1616 821 1616 1392 1617 830 1617 822 1617 822 1618 830 1618 829 1618 822 1619 829 1619 816 1619 1392 1620 823 1620 830 1620 830 1621 823 1621 836 1621 830 1622 836 1622 832 1622 809 1623 824 1623 825 1623 825 1624 824 1624 826 1624 825 1625 826 1625 827 1625 827 1626 826 1626 817 1626 827 1627 817 1627 2233 1627 2233 1628 817 1628 816 1628 2233 1629 816 1629 2234 1629 2234 1630 816 1630 829 1630 2234 1631 829 1631 828 1631 828 1632 829 1632 830 1632 828 1633 830 1633 831 1633 831 1634 830 1634 832 1634 831 1635 832 1635 833 1635 2279 1636 2260 1636 858 1636 834 1637 2279 1637 812 1637 812 1638 2279 1638 858 1638 812 1639 858 1639 813 1639 813 1640 858 1640 860 1640 840 1641 835 1641 838 1641 838 1642 2237 1642 2236 1642 838 1643 2236 1643 832 1643 832 1644 2236 1644 2235 1644 832 1645 2235 1645 833 1645 836 1646 837 1646 832 1646 832 1647 837 1647 1341 1647 832 1648 1341 1648 838 1648 838 1649 1341 1649 839 1649 838 1650 839 1650 840 1650 2201 1651 841 1651 851 1651 2205 1652 852 1652 843 1652 843 1653 852 1653 842 1653 843 1654 842 1654 844 1654 844 1655 842 1655 854 1655 862 1656 845 1656 854 1656 854 1657 845 1657 2207 1657 854 1658 2207 1658 844 1658 848 1659 846 1659 847 1659 850 1660 2215 1660 848 1660 848 1661 2215 1661 2213 1661 848 1662 2213 1662 2212 1662 841 1663 2216 1663 851 1663 851 1664 2216 1664 849 1664 851 1665 849 1665 848 1665 848 1666 849 1666 850 1666 848 1667 847 1667 851 1667 851 1668 847 1668 857 1668 851 1669 857 1669 856 1669 2205 1670 2204 1670 852 1670 852 1671 2204 1671 2203 1671 852 1672 2203 1672 856 1672 856 1673 2203 1673 853 1673 856 1674 853 1674 851 1674 851 1675 853 1675 2202 1675 851 1676 2202 1676 2201 1676 861 1677 854 1677 1398 1677 1398 1678 854 1678 842 1678 1398 1679 842 1679 855 1679 855 1680 842 1680 852 1680 855 1681 852 1681 1333 1681 1333 1682 852 1682 856 1682 1333 1683 856 1683 1371 1683 1371 1684 856 1684 857 1684 858 1685 859 1685 860 1685 860 1686 859 1686 1332 1686 861 1687 1332 1687 854 1687 854 1688 1332 1688 859 1688 854 1689 859 1689 862 1689 862 1690 859 1690 858 1690 862 1691 858 1691 2260 1691 838 1692 835 1692 1344 1692 2237 1693 838 1693 863 1693 838 1694 1344 1694 863 1694 863 1695 1344 1695 865 1695 863 1696 865 1696 864 1696 864 1697 865 1697 866 1697 864 1698 866 1698 867 1698 867 1699 866 1699 868 1699 867 1700 868 1700 875 1700 875 1701 868 1701 869 1701 875 1702 869 1702 870 1702 869 1703 1335 1703 870 1703 870 1704 1335 1704 1353 1704 870 1705 1353 1705 871 1705 871 1706 1353 1706 872 1706 871 1707 872 1707 881 1707 2237 1708 863 1708 2238 1708 2238 1709 863 1709 864 1709 2238 1710 864 1710 873 1710 873 1711 864 1711 867 1711 873 1712 867 1712 874 1712 874 1713 867 1713 875 1713 874 1714 875 1714 876 1714 876 1715 875 1715 870 1715 876 1716 870 1716 2239 1716 2239 1717 870 1717 871 1717 2239 1718 871 1718 877 1718 877 1719 871 1719 881 1719 877 1720 881 1720 1038 1720 1367 1721 846 1721 848 1721 878 1722 1362 1722 879 1722 879 1723 1362 1723 1363 1723 879 1724 1363 1724 848 1724 848 1725 1363 1725 1365 1725 848 1726 1365 1726 1367 1726 848 1727 2212 1727 880 1727 848 1728 880 1728 879 1728 879 1729 880 1729 2211 1729 879 1730 2211 1730 2210 1730 1039 1731 1038 1731 881 1731 898 1732 1039 1732 900 1732 900 1733 1039 1733 881 1733 900 1734 881 1734 882 1734 882 1735 881 1735 872 1735 903 1736 904 1736 883 1736 2200 1737 903 1737 884 1737 903 1738 883 1738 884 1738 884 1739 883 1739 1385 1739 884 1740 1385 1740 885 1740 885 1741 1385 1741 886 1741 885 1742 886 1742 892 1742 892 1743 886 1743 887 1743 892 1744 887 1744 888 1744 888 1745 887 1745 889 1745 888 1746 889 1746 894 1746 894 1747 889 1747 1358 1747 894 1748 1358 1748 896 1748 896 1749 1358 1749 878 1749 896 1750 878 1750 879 1750 2200 1751 884 1751 890 1751 890 1752 884 1752 885 1752 890 1753 885 1753 891 1753 891 1754 885 1754 892 1754 891 1755 892 1755 893 1755 893 1756 892 1756 888 1756 893 1757 888 1757 895 1757 895 1758 888 1758 894 1758 895 1759 894 1759 2209 1759 2209 1760 894 1760 896 1760 2209 1761 896 1761 897 1761 897 1762 896 1762 879 1762 897 1763 879 1763 2210 1763 1355 1764 1354 1764 901 1764 1040 1765 898 1765 900 1765 1040 1766 900 1766 899 1766 899 1767 900 1767 901 1767 899 1768 901 1768 1042 1768 882 1769 1351 1769 900 1769 900 1770 1351 1770 1349 1770 900 1771 1349 1771 901 1771 901 1772 1349 1772 902 1772 901 1773 902 1773 1355 1773 1037 1774 1042 1774 901 1774 2200 1775 1037 1775 903 1775 903 1776 1037 1776 901 1776 903 1777 901 1777 904 1777 904 1778 901 1778 1354 1778 1195 1779 908 1779 915 1779 915 1780 908 1780 910 1780 915 1781 910 1781 926 1781 926 1782 910 1782 905 1782 905 1783 910 1783 906 1783 905 1784 906 1784 1374 1784 1211 1785 907 1785 1132 1785 1132 1786 907 1786 910 1786 1132 1787 910 1787 908 1787 907 1788 932 1788 1336 1788 1336 1789 1376 1789 907 1789 907 1790 1376 1790 909 1790 907 1791 909 1791 910 1791 910 1792 909 1792 1331 1792 910 1793 1331 1793 906 1793 911 1794 918 1794 1193 1794 1187 1795 928 1795 1188 1795 1188 1796 928 1796 929 1796 1188 1797 929 1797 1189 1797 1193 1798 912 1798 911 1798 911 1799 912 1799 914 1799 911 1800 914 1800 913 1800 913 1801 914 1801 915 1801 913 1802 915 1802 926 1802 912 1803 1191 1803 914 1803 914 1804 1191 1804 916 1804 916 1805 1201 1805 914 1805 914 1806 1201 1806 1199 1806 914 1807 1199 1807 915 1807 915 1808 1199 1808 1196 1808 915 1809 1196 1809 1195 1809 1187 1810 917 1810 928 1810 928 1811 917 1811 918 1811 928 1812 918 1812 927 1812 927 1813 918 1813 911 1813 1187 1814 1185 1814 917 1814 917 1815 1185 1815 919 1815 917 1816 919 1816 918 1816 918 1817 919 1817 920 1817 918 1818 920 1818 1193 1818 1370 1819 924 1819 925 1819 921 1820 1401 1820 922 1820 922 1821 1401 1821 1400 1821 922 1822 1400 1822 1329 1822 1374 1823 921 1823 905 1823 905 1824 921 1824 922 1824 905 1825 922 1825 926 1825 1370 1826 923 1826 924 1826 924 1827 923 1827 1369 1827 924 1828 1369 1828 1368 1828 1329 1829 1403 1829 925 1829 925 1830 1403 1830 1402 1830 925 1831 1402 1831 1370 1831 926 1832 922 1832 913 1832 913 1833 922 1833 1329 1833 913 1834 1329 1834 911 1834 911 1835 1329 1835 925 1835 911 1836 925 1836 927 1836 927 1837 925 1837 924 1837 927 1838 924 1838 928 1838 928 1839 924 1839 1368 1839 928 1840 1368 1840 929 1840 931 1841 1209 1841 930 1841 930 1842 1209 1842 1208 1842 1211 1843 1209 1843 907 1843 907 1844 1209 1844 931 1844 907 1845 931 1845 932 1845 932 1846 931 1846 950 1846 932 1847 950 1847 1395 1847 933 1848 1212 1848 934 1848 933 1849 934 1849 929 1849 929 1850 934 1850 1112 1850 929 1851 1112 1851 1189 1851 929 1852 1368 1852 1366 1852 1366 1853 935 1853 929 1853 929 1854 935 1854 1364 1854 929 1855 1364 1855 933 1855 933 1856 1364 1856 1361 1856 933 1857 1361 1857 1360 1857 936 1858 938 1858 952 1858 937 1859 1395 1859 950 1859 1104 1860 938 1860 1203 1860 1203 1861 938 1861 936 1861 1203 1862 936 1862 949 1862 949 1863 936 1863 953 1863 949 1864 953 1864 947 1864 947 1865 953 1865 940 1865 940 1866 943 1866 939 1866 945 1867 940 1867 941 1867 941 1868 940 1868 939 1868 941 1869 939 1869 942 1869 943 1870 940 1870 944 1870 944 1871 940 1871 955 1871 944 1872 955 1872 951 1872 945 1873 1206 1873 940 1873 940 1874 1206 1874 946 1874 940 1875 946 1875 947 1875 947 1876 946 1876 948 1876 947 1877 948 1877 949 1877 949 1878 948 1878 1205 1878 949 1879 1205 1879 1203 1879 1208 1880 942 1880 930 1880 930 1881 942 1881 939 1881 930 1882 939 1882 931 1882 931 1883 939 1883 943 1883 931 1884 943 1884 950 1884 950 1885 943 1885 944 1885 950 1886 944 1886 937 1886 937 1887 944 1887 951 1887 952 1888 1339 1888 936 1888 936 1889 1339 1889 1393 1889 936 1890 1393 1890 953 1890 953 1891 1393 1891 954 1891 953 1892 954 1892 940 1892 940 1893 954 1893 1394 1893 940 1894 1394 1894 955 1894 970 1895 1219 1895 972 1895 1379 1896 1383 1896 956 1896 957 1897 1212 1897 933 1897 958 1898 965 1898 960 1898 1218 1899 958 1899 959 1899 959 1900 958 1900 960 1900 959 1901 960 1901 961 1901 961 1902 960 1902 962 1902 961 1903 962 1903 974 1903 959 1904 963 1904 972 1904 972 1905 1219 1905 959 1905 959 1906 1219 1906 964 1906 959 1907 964 1907 1218 1907 963 1908 959 1908 973 1908 973 1909 959 1909 1381 1909 973 1910 1381 1910 1382 1910 965 1911 1214 1911 960 1911 960 1912 1214 1912 966 1912 960 1913 966 1913 962 1913 962 1914 966 1914 957 1914 962 1915 957 1915 974 1915 974 1916 957 1916 933 1916 974 1917 933 1917 967 1917 967 1918 933 1918 1360 1918 968 1919 970 1919 969 1919 969 1920 970 1920 972 1920 969 1921 972 1921 971 1921 971 1922 972 1922 963 1922 971 1923 963 1923 956 1923 956 1924 963 1924 973 1924 956 1925 973 1925 1379 1925 1379 1926 973 1926 1382 1926 967 1927 1359 1927 974 1927 974 1928 1359 1928 975 1928 974 1929 975 1929 961 1929 961 1930 975 1930 976 1930 961 1931 976 1931 959 1931 959 1932 976 1932 1380 1932 959 1933 1380 1933 1381 1933 978 1934 977 1934 979 1934 978 1935 979 1935 1105 1935 1105 1936 979 1936 938 1936 1105 1937 938 1937 1104 1937 979 1938 1003 1938 980 1938 980 1939 981 1939 979 1939 979 1940 981 1940 1340 1940 979 1941 1340 1941 938 1941 938 1942 1340 1942 982 1942 938 1943 982 1943 952 1943 984 1944 983 1944 968 1944 968 1945 969 1945 984 1945 984 1946 969 1946 971 1946 984 1947 971 1947 985 1947 985 1948 971 1948 956 1948 985 1949 956 1949 1383 1949 1386 1950 1330 1950 994 1950 1227 1951 986 1951 998 1951 998 1952 986 1952 987 1952 998 1953 987 1953 1005 1953 1005 1954 987 1954 990 1954 1005 1955 990 1955 988 1955 989 1956 990 1956 1225 1956 1225 1957 990 1957 987 1957 1225 1958 987 1958 991 1958 991 1959 987 1959 986 1959 1224 1960 999 1960 1002 1960 1002 1961 999 1961 1000 1961 1002 1962 1000 1962 997 1962 996 1963 992 1963 1346 1963 1007 1964 993 1964 1389 1964 1007 1965 1389 1965 994 1965 994 1966 1389 1966 1387 1966 994 1967 1387 1967 1386 1967 979 1968 977 1968 995 1968 1346 1969 997 1969 996 1969 996 1970 997 1970 1000 1970 996 1971 1000 1971 998 1971 999 1972 1221 1972 1000 1972 1000 1973 1221 1973 1001 1973 1000 1974 1001 1974 998 1974 998 1975 1001 1975 1228 1975 998 1976 1228 1976 1227 1976 1346 1977 1345 1977 997 1977 997 1978 1345 1978 1343 1978 997 1979 1343 1979 1342 1979 1224 1980 1002 1980 995 1980 995 1981 1002 1981 997 1981 995 1982 997 1982 979 1982 979 1983 997 1983 1342 1983 979 1984 1342 1984 1003 1984 992 1985 996 1985 1004 1985 1004 1986 996 1986 998 1986 1004 1987 998 1987 1330 1987 1330 1988 998 1988 1005 1988 1330 1989 1005 1989 994 1989 994 1990 1005 1990 988 1990 994 1991 988 1991 1007 1991 1006 1992 983 1992 984 1992 1006 1993 984 1993 1109 1993 1109 1994 984 1994 1008 1994 1109 1995 1008 1995 1108 1995 984 1996 985 1996 1356 1996 1356 1997 1347 1997 984 1997 984 1998 1347 1998 1348 1998 984 1999 1348 1999 1008 1999 1008 2000 1348 2000 1350 2000 1008 2001 1350 2001 1334 2001 989 2002 1108 2002 990 2002 990 2003 1108 2003 1008 2003 990 2004 1008 2004 988 2004 988 2005 1008 2005 1007 2005 1007 2006 1008 2006 1334 2006 1007 2007 1334 2007 993 2007 1009 2008 1010 2008 1180 2008 1180 2009 1010 2009 1179 2009 1163 2010 2349 2010 1165 2010 1165 2011 2349 2011 1168 2011 1011 2012 1172 2012 1012 2012 1012 2013 1172 2013 1309 2013 1012 2014 1309 2014 1314 2014 1286 2015 2351 2015 1013 2015 1017 2016 2348 2016 1021 2016 1307 2017 1308 2017 2334 2017 2334 2018 1308 2018 1014 2018 2334 2019 1014 2019 1015 2019 1015 2020 1014 2020 1016 2020 1015 2021 1016 2021 1019 2021 1019 2022 1016 2022 1017 2022 1013 2023 1018 2023 1286 2023 1286 2024 1018 2024 1019 2024 1286 2025 1019 2025 1020 2025 1020 2026 1019 2026 1017 2026 1020 2027 1017 2027 1294 2027 1294 2028 1017 2028 1021 2028 1022 2029 1321 2029 1023 2029 1023 2030 1321 2030 1016 2030 1023 2031 1016 2031 2328 2031 2328 2032 1016 2032 1014 2032 775 2033 1056 2033 1032 2033 1032 2034 1251 2034 775 2034 775 2035 1251 2035 1024 2035 775 2036 1024 2036 1027 2036 1030 2037 1230 2037 595 2037 595 2038 1230 2038 1025 2038 595 2039 1025 2039 1026 2039 1027 2040 1028 2040 775 2040 775 2041 1028 2041 1247 2041 775 2042 1247 2042 568 2042 568 2043 1247 2043 1243 2043 568 2044 1243 2044 1029 2044 1029 2045 1243 2045 1234 2045 1029 2046 1234 2046 592 2046 592 2047 1234 2047 1233 2047 592 2048 1233 2048 595 2048 595 2049 1233 2049 1232 2049 595 2050 1232 2050 1030 2050 1034 2051 623 2051 1237 2051 1036 2052 1031 2052 1056 2052 1056 2053 1031 2053 1254 2053 1056 2054 1254 2054 1032 2054 1237 2055 623 2055 1238 2055 1238 2056 623 2056 622 2056 1238 2057 622 2057 1033 2057 1056 2058 1054 2058 1034 2058 1026 2059 1025 2059 1035 2059 1035 2060 1025 2060 1242 2060 1035 2061 1242 2061 622 2061 622 2062 1242 2062 1240 2062 622 2063 1240 2063 1033 2063 1237 2064 1246 2064 1034 2064 1034 2065 1246 2065 1245 2065 1034 2066 1245 2066 1056 2066 1056 2067 1245 2067 1256 2067 1056 2068 1256 2068 1036 2068 1037 2069 2200 2069 1041 2069 1038 2070 1039 2070 405 2070 405 2071 1039 2071 898 2071 898 2072 1040 2072 405 2072 405 2073 1040 2073 899 2073 405 2074 899 2074 1041 2074 1041 2075 899 2075 1042 2075 1041 2076 1042 2076 1037 2076 1043 2077 775 2077 1044 2077 1044 2078 775 2078 568 2078 1044 2079 568 2079 567 2079 1044 2080 1045 2080 1043 2080 1043 2081 1045 2081 1046 2081 1043 2082 1046 2082 738 2082 738 2083 1046 2083 1047 2083 738 2084 1047 2084 739 2084 739 2085 1047 2085 551 2085 739 2086 551 2086 740 2086 740 2087 551 2087 1048 2087 740 2088 1048 2088 741 2088 741 2089 1048 2089 1049 2089 741 2090 1049 2090 743 2090 743 2091 1049 2091 1050 2091 743 2092 1050 2092 1051 2092 1051 2093 1050 2093 1052 2093 1051 2094 1052 2094 2133 2094 2133 2095 1052 2095 542 2095 1063 2096 762 2096 602 2096 1053 2097 1054 2097 1055 2097 1055 2098 1054 2098 1056 2098 1055 2099 1056 2099 1057 2099 1058 2100 611 2100 1059 2100 1059 2101 611 2101 1060 2101 1059 2102 1060 2102 1057 2102 1057 2103 1060 2103 1061 2103 1057 2104 1061 2104 1055 2104 1067 2105 1062 2105 769 2105 769 2106 1062 2106 608 2106 769 2107 608 2107 1058 2107 1058 2108 608 2108 609 2108 1058 2109 609 2109 611 2109 602 2110 1064 2110 1063 2110 1063 2111 1064 2111 603 2111 1063 2112 603 2112 1065 2112 1065 2113 603 2113 1066 2113 1065 2114 1066 2114 1067 2114 1067 2115 1066 2115 1068 2115 1067 2116 1068 2116 1062 2116 406 2117 407 2117 600 2117 600 2118 407 2118 1069 2118 1069 2119 407 2119 417 2119 1069 2120 417 2120 594 2120 594 2121 417 2121 1071 2121 594 2122 1071 2122 1070 2122 627 2123 414 2123 403 2123 627 2124 403 2124 625 2124 625 2125 403 2125 406 2125 625 2126 406 2126 600 2126 1084 2127 549 2127 572 2127 1084 2128 572 2128 1072 2128 1070 2129 1071 2129 572 2129 572 2130 1071 2130 438 2130 572 2131 438 2131 1072 2131 629 2132 412 2132 627 2132 627 2133 412 2133 414 2133 629 2134 1073 2134 412 2134 412 2135 1073 2135 601 2135 412 2136 601 2136 1085 2136 1074 2137 1075 2137 1076 2137 1074 2138 1076 2138 1077 2138 1077 2139 1076 2139 555 2139 1077 2140 555 2140 456 2140 456 2141 555 2141 1079 2141 456 2142 1079 2142 1078 2142 1078 2143 1079 2143 557 2143 1078 2144 557 2144 453 2144 453 2145 557 2145 1080 2145 453 2146 1080 2146 452 2146 452 2147 1080 2147 1081 2147 452 2148 1081 2148 450 2148 450 2149 1081 2149 1082 2149 450 2150 1082 2150 1083 2150 1083 2151 1082 2151 1084 2151 1083 2152 1084 2152 1072 2152 1085 2153 601 2153 620 2153 1085 2154 620 2154 1086 2154 1086 2155 620 2155 619 2155 1086 2156 619 2156 426 2156 426 2157 619 2157 1087 2157 426 2158 1087 2158 428 2158 428 2159 1087 2159 617 2159 428 2160 617 2160 430 2160 430 2161 617 2161 615 2161 430 2162 615 2162 1088 2162 1088 2163 615 2163 614 2163 1088 2164 614 2164 431 2164 431 2165 614 2165 1089 2165 431 2166 1089 2166 432 2166 432 2167 1089 2167 597 2167 432 2168 597 2168 434 2168 1244 2169 1090 2169 1299 2169 1299 2170 1090 2170 1091 2170 1253 2171 1092 2171 1093 2171 1093 2172 1092 2172 1094 2172 1235 2173 1249 2173 1280 2173 1280 2174 1249 2174 1141 2174 1216 2175 1217 2175 1095 2175 1095 2176 1217 2176 1096 2176 1097 2177 1226 2177 1152 2177 1152 2178 1226 2178 1098 2178 1152 2179 1098 2179 1099 2179 1096 2180 1220 2180 1095 2180 1095 2181 1220 2181 1100 2181 1095 2182 1100 2182 1152 2182 1152 2183 1100 2183 1110 2183 1152 2184 1110 2184 1097 2184 1107 2185 1101 2185 977 2185 1104 2186 1102 2186 1103 2186 1104 2187 1103 2187 1105 2187 1105 2188 1103 2188 1260 2188 1105 2189 1260 2189 1106 2189 1106 2190 1151 2190 1105 2190 1105 2191 1151 2191 1107 2191 1105 2192 1107 2192 978 2192 978 2193 1107 2193 977 2193 1108 2194 1110 2194 1109 2194 1109 2195 1110 2195 1100 2195 1109 2196 1100 2196 1006 2196 1006 2197 1100 2197 983 2197 1111 2198 1157 2198 1156 2198 934 2199 1212 2199 1137 2199 1117 2200 1189 2200 1113 2200 1113 2201 1189 2201 1112 2201 1137 2202 1111 2202 934 2202 934 2203 1111 2203 1156 2203 934 2204 1156 2204 1112 2204 1112 2205 1156 2205 1267 2205 1112 2206 1267 2206 1113 2206 1258 2207 1103 2207 1102 2207 1116 2208 1117 2208 1114 2208 1114 2209 1117 2209 1113 2209 1202 2210 1121 2210 1102 2210 1102 2211 1121 2211 1115 2211 1102 2212 1115 2212 1258 2212 1116 2213 1118 2213 1117 2213 1117 2214 1118 2214 1270 2214 1117 2215 1270 2215 1119 2215 1119 2216 1270 2216 1271 2216 1120 2217 1192 2217 1131 2217 1131 2218 1192 2218 1190 2218 1131 2219 1190 2219 1271 2219 1271 2220 1190 2220 1186 2220 1271 2221 1186 2221 1119 2221 1202 2222 1204 2222 1121 2222 1121 2223 1204 2223 1122 2223 1121 2224 1122 2224 1124 2224 1124 2225 1122 2225 1123 2225 1265 2226 1194 2226 1130 2226 1123 2227 1125 2227 1124 2227 1124 2228 1125 2228 1207 2228 1124 2229 1207 2229 1126 2229 1194 2230 1265 2230 1127 2230 1207 2231 1128 2231 1126 2231 1126 2232 1128 2232 1210 2232 1126 2233 1210 2233 1129 2233 1129 2234 1210 2234 1127 2234 1129 2235 1127 2235 1264 2235 1264 2236 1127 2236 1265 2236 1130 2237 1197 2237 1265 2237 1265 2238 1197 2238 1198 2238 1265 2239 1198 2239 1131 2239 1131 2240 1198 2240 1200 2240 1131 2241 1200 2241 1120 2241 908 2242 1194 2242 1132 2242 1132 2243 1194 2243 1127 2243 1132 2244 1127 2244 1211 2244 1160 2245 1134 2245 1133 2245 1215 2246 1216 2246 1095 2246 1133 2247 1134 2247 1135 2247 1134 2248 1158 2248 1135 2248 1135 2249 1158 2249 1157 2249 1135 2250 1157 2250 1111 2250 1095 2251 1231 2251 1215 2251 1215 2252 1231 2252 1136 2252 1215 2253 1136 2253 1213 2253 1213 2254 1136 2254 1229 2254 1213 2255 1229 2255 1137 2255 1137 2256 1229 2256 1138 2256 1137 2257 1138 2257 1111 2257 2349 2258 1163 2258 1133 2258 1133 2259 1163 2259 1139 2259 1133 2260 1139 2260 1160 2260 1111 2261 1138 2261 1135 2261 1135 2262 1138 2262 1140 2262 1135 2263 1140 2263 1293 2263 1293 2264 1140 2264 1235 2264 1293 2265 1235 2265 1280 2265 1249 2266 1142 2266 1141 2266 1141 2267 1142 2267 2354 2267 1142 2268 1248 2268 2354 2268 2354 2269 1248 2269 1143 2269 2354 2270 1143 2270 1144 2270 1143 2271 1145 2271 1144 2271 1144 2272 1145 2272 1250 2272 1144 2273 1250 2273 1278 2273 1278 2274 1250 2274 1093 2274 1278 2275 1093 2275 1094 2275 1253 2276 1146 2276 1092 2276 1092 2277 1146 2277 2337 2277 1146 2278 1252 2278 2337 2278 2337 2279 1252 2279 1147 2279 2337 2280 1147 2280 1305 2280 1147 2281 1255 2281 1305 2281 1305 2282 1255 2282 1257 2282 1305 2283 1257 2283 1148 2283 1148 2284 1257 2284 1244 2284 1148 2285 1244 2285 1299 2285 1090 2286 1149 2286 1091 2286 1091 2287 1149 2287 2329 2287 1155 2288 1322 2288 1239 2288 1239 2289 1322 2289 2329 2289 1239 2290 2329 2290 1236 2290 1236 2291 2329 2291 1149 2291 1155 2292 1101 2292 1322 2292 1322 2293 1101 2293 1107 2293 1322 2294 1107 2294 1151 2294 1179 2295 1010 2295 1176 2295 1176 2296 1010 2296 1323 2296 1176 2297 1323 2297 1150 2297 1150 2298 1323 2298 1322 2298 1150 2299 1322 2299 1174 2299 1174 2300 1322 2300 1151 2300 1152 2301 1099 2301 1241 2301 1241 2302 1099 2302 1222 2302 1241 2303 1222 2303 1153 2303 1153 2304 1222 2304 1223 2304 1153 2305 1223 2305 1155 2305 1155 2306 1223 2306 1154 2306 1155 2307 1154 2307 1101 2307 1268 2308 1156 2308 1157 2308 1268 2309 1157 2309 1266 2309 1169 2310 1165 2310 1168 2310 1157 2311 1158 2311 1266 2311 1266 2312 1158 2312 1134 2312 1266 2313 1134 2313 1159 2313 1159 2314 1134 2314 1160 2314 1159 2315 1160 2315 1161 2315 1161 2316 1160 2316 1139 2316 1161 2317 1139 2317 1162 2317 1162 2318 1139 2318 1163 2318 1162 2319 1163 2319 1164 2319 1164 2320 1163 2320 1165 2320 1164 2321 1165 2321 1269 2321 1269 2322 1165 2322 1169 2322 1166 2323 1167 2323 1170 2323 1170 2324 1167 2324 1273 2324 1170 2325 1273 2325 1168 2325 1168 2326 1273 2326 1272 2326 1168 2327 1272 2327 1169 2327 1170 2328 1171 2328 1166 2328 1166 2329 1171 2329 1309 2329 1166 2330 1309 2330 1172 2330 1151 2331 1106 2331 1173 2331 1151 2332 1173 2332 1174 2332 1174 2333 1173 2333 1175 2333 1174 2334 1175 2334 1150 2334 1150 2335 1175 2335 1259 2335 1150 2336 1259 2336 1176 2336 1259 2337 1177 2337 1176 2337 1176 2338 1177 2338 1178 2338 1176 2339 1178 2339 1179 2339 1179 2340 1178 2340 1261 2340 1179 2341 1261 2341 1180 2341 1261 2342 1262 2342 1180 2342 1180 2343 1262 2343 1181 2343 1180 2344 1181 2344 1009 2344 1009 2345 1181 2345 1182 2345 1009 2346 1182 2346 1183 2346 1183 2347 1182 2347 1184 2347 1183 2348 1184 2348 1314 2348 1314 2349 1184 2349 1263 2349 1314 2350 1263 2350 1012 2350 1012 2351 1263 2351 1011 2351 1189 2352 1117 2352 1119 2352 1190 2353 1185 2353 1186 2353 1186 2354 1185 2354 1187 2354 1186 2355 1187 2355 1119 2355 1119 2356 1187 2356 1188 2356 1119 2357 1188 2357 1189 2357 1192 2358 920 2358 1190 2358 1190 2359 920 2359 919 2359 1190 2360 919 2360 1185 2360 1200 2361 916 2361 1120 2361 916 2362 1191 2362 1120 2362 1120 2363 1191 2363 912 2363 1120 2364 912 2364 1192 2364 1192 2365 912 2365 1193 2365 1192 2366 1193 2366 920 2366 1194 2367 908 2367 1130 2367 1130 2368 908 2368 1195 2368 1130 2369 1195 2369 1197 2369 1197 2370 1195 2370 1196 2370 1197 2371 1196 2371 1198 2371 1198 2372 1196 2372 1199 2372 1198 2373 1199 2373 1200 2373 1200 2374 1199 2374 1201 2374 1200 2375 1201 2375 916 2375 1102 2376 1104 2376 1202 2376 1202 2377 1104 2377 1203 2377 1202 2378 1203 2378 1204 2378 1204 2379 1203 2379 1205 2379 1204 2380 1205 2380 1122 2380 1122 2381 1205 2381 1123 2381 1205 2382 948 2382 1123 2382 1123 2383 948 2383 946 2383 1123 2384 946 2384 1125 2384 1125 2385 946 2385 1206 2385 1125 2386 1206 2386 1207 2386 1206 2387 945 2387 1207 2387 1207 2388 945 2388 941 2388 1207 2389 941 2389 1128 2389 1128 2390 941 2390 942 2390 1128 2391 942 2391 1210 2391 1210 2392 942 2392 1208 2392 1208 2393 1209 2393 1210 2393 1210 2394 1209 2394 1211 2394 1210 2395 1211 2395 1127 2395 1137 2396 1212 2396 957 2396 1216 2397 1215 2397 965 2397 1137 2398 957 2398 1213 2398 1213 2399 957 2399 966 2399 1213 2400 966 2400 1215 2400 1215 2401 966 2401 1214 2401 1215 2402 1214 2402 965 2402 965 2403 958 2403 1216 2403 1216 2404 958 2404 1218 2404 1216 2405 1218 2405 1217 2405 1217 2406 1218 2406 964 2406 964 2407 1219 2407 1217 2407 1217 2408 1219 2408 970 2408 1217 2409 970 2409 1096 2409 1096 2410 970 2410 968 2410 1096 2411 968 2411 1220 2411 1220 2412 968 2412 983 2412 1220 2413 983 2413 1100 2413 1228 2414 1001 2414 1099 2414 1099 2415 1001 2415 1222 2415 1001 2416 1221 2416 1222 2416 1222 2417 1221 2417 999 2417 1222 2418 999 2418 1223 2418 1223 2419 999 2419 1224 2419 1223 2420 1224 2420 1154 2420 1224 2421 995 2421 1154 2421 1154 2422 995 2422 977 2422 1154 2423 977 2423 1101 2423 1097 2424 1110 2424 1108 2424 1108 2425 989 2425 1097 2425 1097 2426 989 2426 1225 2426 1097 2427 1225 2427 1226 2427 1226 2428 1225 2428 991 2428 1226 2429 991 2429 1098 2429 1098 2430 991 2430 986 2430 1098 2431 986 2431 1099 2431 1099 2432 986 2432 1227 2432 1099 2433 1227 2433 1228 2433 1242 2434 1025 2434 1152 2434 1152 2435 1025 2435 1095 2435 1095 2436 1025 2436 1230 2436 1229 2437 1136 2437 1230 2437 1230 2438 1136 2438 1231 2438 1230 2439 1231 2439 1095 2439 1230 2440 1030 2440 1229 2440 1229 2441 1030 2441 1232 2441 1229 2442 1232 2442 1138 2442 1138 2443 1232 2443 1233 2443 1138 2444 1233 2444 1140 2444 1140 2445 1233 2445 1234 2445 1140 2446 1234 2446 1235 2446 1090 2447 1246 2447 1237 2447 1239 2448 1236 2448 1237 2448 1237 2449 1236 2449 1149 2449 1237 2450 1149 2450 1090 2450 1237 2451 1238 2451 1239 2451 1239 2452 1238 2452 1033 2452 1239 2453 1033 2453 1155 2453 1155 2454 1033 2454 1153 2454 1153 2455 1033 2455 1240 2455 1153 2456 1240 2456 1241 2456 1241 2457 1240 2457 1242 2457 1241 2458 1242 2458 1152 2458 1243 2459 1249 2459 1234 2459 1234 2460 1249 2460 1235 2460 1244 2461 1245 2461 1090 2461 1090 2462 1245 2462 1246 2462 1249 2463 1243 2463 1247 2463 1143 2464 1248 2464 1247 2464 1247 2465 1248 2465 1142 2465 1247 2466 1142 2466 1249 2466 1247 2467 1028 2467 1143 2467 1143 2468 1028 2468 1027 2468 1143 2469 1027 2469 1145 2469 1145 2470 1027 2470 1024 2470 1145 2471 1024 2471 1250 2471 1250 2472 1024 2472 1251 2472 1250 2473 1251 2473 1093 2473 1253 2474 1032 2474 1254 2474 1147 2475 1252 2475 1254 2475 1254 2476 1252 2476 1146 2476 1254 2477 1146 2477 1253 2477 1254 2478 1031 2478 1147 2478 1147 2479 1031 2479 1036 2479 1147 2480 1036 2480 1255 2480 1255 2481 1036 2481 1256 2481 1255 2482 1256 2482 1257 2482 1257 2483 1256 2483 1245 2483 1257 2484 1245 2484 1244 2484 1253 2485 1093 2485 1032 2485 1032 2486 1093 2486 1251 2486 1178 2487 1177 2487 1258 2487 1173 2488 1106 2488 1260 2488 1258 2489 1177 2489 1103 2489 1103 2490 1177 2490 1259 2490 1103 2491 1259 2491 1260 2491 1260 2492 1259 2492 1175 2492 1260 2493 1175 2493 1173 2493 1178 2494 1258 2494 1261 2494 1261 2495 1258 2495 1115 2495 1261 2496 1115 2496 1262 2496 1262 2497 1115 2497 1121 2497 1262 2498 1121 2498 1181 2498 1181 2499 1121 2499 1182 2499 1182 2500 1121 2500 1124 2500 1182 2501 1124 2501 1184 2501 1184 2502 1124 2502 1126 2502 1184 2503 1126 2503 1263 2503 1263 2504 1126 2504 1011 2504 1011 2505 1126 2505 1129 2505 1011 2506 1129 2506 1264 2506 1172 2507 1011 2507 1265 2507 1265 2508 1011 2508 1264 2508 1266 2509 1159 2509 1114 2509 1156 2510 1268 2510 1267 2510 1267 2511 1268 2511 1266 2511 1267 2512 1266 2512 1113 2512 1113 2513 1266 2513 1114 2513 1162 2514 1270 2514 1161 2514 1161 2515 1270 2515 1118 2515 1161 2516 1118 2516 1159 2516 1159 2517 1118 2517 1116 2517 1159 2518 1116 2518 1114 2518 1162 2519 1164 2519 1270 2519 1270 2520 1164 2520 1269 2520 1270 2521 1269 2521 1271 2521 1269 2522 1169 2522 1271 2522 1271 2523 1169 2523 1272 2523 1271 2524 1272 2524 1131 2524 1272 2525 1273 2525 1131 2525 1131 2526 1273 2526 1167 2526 1131 2527 1167 2527 1265 2527 1265 2528 1167 2528 1166 2528 1265 2529 1166 2529 1172 2529 1277 2530 1278 2530 1094 2530 1019 2531 1018 2531 1274 2531 1274 2532 1018 2532 1275 2532 1274 2533 1275 2533 1290 2533 1290 2534 1275 2534 1276 2534 1290 2535 1276 2535 1288 2535 1288 2536 1276 2536 1277 2536 1288 2537 1277 2537 1287 2537 1287 2538 1277 2538 1094 2538 1144 2539 1278 2539 1279 2539 1279 2540 1278 2540 1277 2540 1279 2541 1277 2541 2353 2541 2353 2542 1277 2542 1276 2542 2353 2543 1276 2543 2352 2543 2352 2544 1276 2544 1275 2544 2352 2545 1275 2545 1013 2545 1013 2546 1275 2546 1018 2546 1280 2547 1141 2547 1281 2547 1281 2548 1141 2548 1282 2548 1281 2549 1282 2549 1283 2549 1283 2550 1282 2550 2358 2550 1283 2551 2358 2551 1284 2551 1284 2552 2358 2552 2359 2552 1284 2553 2359 2553 1296 2553 1296 2554 2359 2554 1285 2554 1296 2555 1285 2555 1020 2555 1020 2556 1285 2556 1286 2556 1094 2557 1092 2557 1287 2557 1287 2558 1092 2558 2342 2558 1287 2559 2342 2559 1288 2559 1288 2560 2342 2560 1289 2560 1288 2561 1289 2561 1290 2561 1290 2562 1289 2562 1291 2562 1290 2563 1291 2563 1274 2563 1274 2564 1291 2564 2340 2564 1274 2565 2340 2565 1019 2565 1019 2566 2340 2566 1015 2566 1292 2567 1293 2567 1280 2567 1020 2568 1294 2568 1296 2568 1296 2569 1294 2569 1295 2569 1296 2570 1295 2570 1284 2570 1284 2571 1295 2571 1298 2571 1284 2572 1298 2572 1283 2572 1283 2573 1298 2573 1292 2573 1283 2574 1292 2574 1281 2574 1281 2575 1292 2575 1280 2575 1135 2576 1293 2576 2345 2576 2345 2577 1293 2577 1292 2577 2345 2578 1292 2578 1297 2578 1297 2579 1292 2579 1298 2579 1297 2580 1298 2580 2347 2580 2347 2581 1298 2581 1295 2581 2347 2582 1295 2582 1021 2582 1021 2583 1295 2583 1294 2583 1304 2584 1148 2584 1299 2584 1014 2585 1308 2585 1300 2585 1300 2586 1308 2586 1301 2586 1300 2587 1301 2587 1302 2587 1302 2588 1301 2588 1306 2588 1302 2589 1306 2589 1303 2589 1303 2590 1306 2590 1304 2590 1303 2591 1304 2591 1316 2591 1316 2592 1304 2592 1299 2592 1305 2593 1148 2593 2339 2593 2339 2594 1148 2594 1304 2594 2339 2595 1304 2595 2341 2595 2341 2596 1304 2596 1306 2596 2341 2597 1306 2597 2335 2597 2335 2598 1306 2598 1301 2598 2335 2599 1301 2599 1307 2599 1307 2600 1301 2600 1308 2600 1314 2601 1309 2601 1310 2601 1310 2602 1309 2602 1171 2602 1310 2603 1171 2603 1311 2603 1311 2604 1171 2604 1170 2604 1311 2605 1170 2605 1312 2605 1312 2606 1170 2606 1168 2606 1312 2607 1168 2607 2349 2607 1010 2608 1009 2608 1313 2608 1313 2609 1009 2609 1183 2609 1313 2610 1183 2610 1320 2610 1320 2611 1183 2611 1314 2611 1320 2612 1314 2612 1315 2612 1315 2613 1314 2613 1310 2613 1315 2614 1310 2614 1016 2614 1016 2615 1310 2615 1017 2615 1299 2616 1091 2616 1316 2616 1316 2617 1091 2617 1317 2617 1316 2618 1317 2618 1303 2618 1303 2619 1317 2619 2332 2619 1303 2620 2332 2620 1302 2620 1302 2621 2332 2621 1318 2621 1302 2622 1318 2622 1300 2622 1300 2623 1318 2623 2333 2623 1300 2624 2333 2624 1014 2624 1014 2625 2333 2625 2328 2625 1323 2626 1010 2626 1326 2626 1326 2627 1010 2627 1313 2627 1326 2628 1313 2628 1319 2628 1319 2629 1313 2629 1320 2629 1319 2630 1320 2630 1328 2630 1328 2631 1320 2631 1315 2631 1328 2632 1315 2632 1321 2632 1321 2633 1315 2633 1016 2633 1322 2634 1323 2634 1324 2634 1324 2635 1323 2635 1326 2635 1324 2636 1326 2636 1325 2636 1325 2637 1326 2637 1319 2637 1325 2638 1319 2638 1327 2638 1327 2639 1319 2639 1328 2639 1327 2640 1328 2640 1022 2640 1022 2641 1328 2641 1321 2641 1329 2642 1400 2642 1399 2642 1330 2643 1386 2643 1390 2643 906 2644 1331 2644 1372 2644 861 2645 1373 2645 1332 2645 855 2646 1333 2646 1399 2646 1334 2647 1350 2647 1352 2647 1335 2648 1388 2648 1353 2648 868 2649 866 2649 1390 2649 1396 2650 1336 2650 932 2650 821 2651 810 2651 1336 2651 1336 2652 1396 2652 821 2652 821 2653 1396 2653 1397 2653 821 2654 1397 2654 820 2654 1337 2655 1338 2655 818 2655 1393 2656 1339 2656 823 2656 823 2657 1339 2657 836 2657 1339 2658 952 2658 836 2658 836 2659 952 2659 982 2659 836 2660 982 2660 837 2660 837 2661 982 2661 1340 2661 837 2662 1340 2662 1341 2662 1341 2663 1340 2663 981 2663 1341 2664 981 2664 839 2664 839 2665 981 2665 980 2665 839 2666 980 2666 840 2666 840 2667 980 2667 835 2667 1343 2668 1344 2668 1342 2668 1342 2669 1344 2669 835 2669 1342 2670 835 2670 1003 2670 1003 2671 835 2671 980 2671 1343 2672 1345 2672 1344 2672 1344 2673 1345 2673 1346 2673 1344 2674 1346 2674 865 2674 1353 2675 1388 2675 1352 2675 1352 2676 1388 2676 993 2676 1352 2677 993 2677 1334 2677 1356 2678 902 2678 1347 2678 1347 2679 902 2679 1349 2679 1347 2680 1349 2680 1348 2680 1348 2681 1349 2681 1351 2681 1348 2682 1351 2682 1350 2682 1350 2683 1351 2683 882 2683 1350 2684 882 2684 1352 2684 1352 2685 882 2685 872 2685 1352 2686 872 2686 1353 2686 1384 2687 1356 2687 985 2687 904 2688 1354 2688 1356 2688 1356 2689 1354 2689 1355 2689 1356 2690 1355 2690 902 2690 1356 2691 1384 2691 904 2691 904 2692 1384 2692 1357 2692 904 2693 1357 2693 883 2693 1378 2694 887 2694 886 2694 889 2695 1380 2695 976 2695 889 2696 976 2696 1358 2696 976 2697 975 2697 1358 2697 1358 2698 975 2698 1359 2698 1358 2699 1359 2699 878 2699 1359 2700 967 2700 878 2700 878 2701 967 2701 1360 2701 878 2702 1360 2702 1362 2702 1360 2703 1361 2703 1362 2703 1362 2704 1361 2704 1364 2704 1362 2705 1364 2705 1363 2705 1363 2706 1364 2706 935 2706 1363 2707 935 2707 1365 2707 1365 2708 935 2708 1366 2708 1365 2709 1366 2709 1367 2709 1367 2710 1366 2710 846 2710 1366 2711 1368 2711 846 2711 846 2712 1368 2712 1369 2712 846 2713 1369 2713 847 2713 847 2714 1369 2714 923 2714 847 2715 923 2715 857 2715 857 2716 923 2716 1370 2716 857 2717 1370 2717 1371 2717 1371 2718 1370 2718 1402 2718 1371 2719 1402 2719 1333 2719 1332 2720 1373 2720 1372 2720 1372 2721 1373 2721 1374 2721 1372 2722 1374 2722 906 2722 810 2723 1375 2723 1336 2723 1336 2724 1375 2724 815 2724 1336 2725 815 2725 1376 2725 1376 2726 815 2726 1377 2726 1376 2727 1377 2727 909 2727 909 2728 1377 2728 814 2728 909 2729 814 2729 1331 2729 1331 2730 814 2730 813 2730 1331 2731 813 2731 1372 2731 1372 2732 813 2732 860 2732 1372 2733 860 2733 1332 2733 886 2734 1385 2734 1378 2734 1378 2735 1385 2735 1379 2735 1378 2736 1379 2736 1382 2736 889 2737 887 2737 1380 2737 1380 2738 887 2738 1378 2738 1380 2739 1378 2739 1381 2739 1381 2740 1378 2740 1382 2740 985 2741 1383 2741 1384 2741 1384 2742 1383 2742 1379 2742 1384 2743 1379 2743 1357 2743 1357 2744 1379 2744 1385 2744 1357 2745 1385 2745 883 2745 868 2746 1390 2746 869 2746 869 2747 1390 2747 1386 2747 869 2748 1386 2748 1335 2748 1335 2749 1386 2749 1387 2749 1335 2750 1387 2750 1388 2750 1388 2751 1387 2751 1389 2751 1388 2752 1389 2752 993 2752 865 2753 1346 2753 866 2753 866 2754 1346 2754 992 2754 866 2755 992 2755 1390 2755 1390 2756 992 2756 1004 2756 1390 2757 1004 2757 1330 2757 818 2758 1391 2758 1337 2758 1337 2759 1391 2759 937 2759 1337 2760 937 2760 951 2760 823 2761 1392 2761 1393 2761 1393 2762 1392 2762 822 2762 1393 2763 822 2763 954 2763 954 2764 822 2764 1338 2764 954 2765 1338 2765 1394 2765 1394 2766 1338 2766 1337 2766 1394 2767 1337 2767 955 2767 955 2768 1337 2768 951 2768 932 2769 1395 2769 1396 2769 1396 2770 1395 2770 937 2770 1396 2771 937 2771 1397 2771 1397 2772 937 2772 1391 2772 1397 2773 1391 2773 820 2773 855 2774 1399 2774 1398 2774 1398 2775 1399 2775 1400 2775 1398 2776 1400 2776 861 2776 861 2777 1400 2777 1401 2777 861 2778 1401 2778 1373 2778 1373 2779 1401 2779 921 2779 1373 2780 921 2780 1374 2780 1333 2781 1402 2781 1399 2781 1399 2782 1402 2782 1403 2782 1399 2783 1403 2783 1329 2783 1478 2784 2291 2784 1404 2784 1478 2785 1404 2785 1418 2785 1418 2786 1404 2786 677 2786 1418 2787 677 2787 1405 2787 1405 2788 677 2788 1406 2788 1405 2789 1406 2789 1407 2789 1407 2790 1406 2790 656 2790 1407 2791 656 2791 1548 2791 1478 2792 1418 2792 1428 2792 1418 2793 1405 2793 1414 2793 1405 2794 1407 2794 1408 2794 1409 2795 1410 2795 1433 2795 1407 2796 1548 2796 1411 2796 1407 2797 1411 2797 1408 2797 1408 2798 1411 2798 1412 2798 1408 2799 1412 2799 1415 2799 1412 2800 1551 2800 1415 2800 1415 2801 1551 2801 1552 2801 1415 2802 1552 2802 1413 2802 1413 2803 1552 2803 1554 2803 1413 2804 1554 2804 1417 2804 1405 2805 1408 2805 1414 2805 1414 2806 1408 2806 1415 2806 1414 2807 1415 2807 1420 2807 1420 2808 1415 2808 1413 2808 1420 2809 1413 2809 1416 2809 1416 2810 1413 2810 1417 2810 1416 2811 1417 2811 1421 2811 1418 2812 1414 2812 1428 2812 1428 2813 1414 2813 1420 2813 1428 2814 1420 2814 1419 2814 1419 2815 1420 2815 1416 2815 1419 2816 1416 2816 1425 2816 1425 2817 1416 2817 1421 2817 1425 2818 1421 2818 1432 2818 1422 2819 1423 2819 1432 2819 1432 2820 1423 2820 1424 2820 1432 2821 1424 2821 1425 2821 1425 2822 1424 2822 1426 2822 1425 2823 1426 2823 1419 2823 1419 2824 1426 2824 1475 2824 1419 2825 1475 2825 1428 2825 1428 2826 1475 2826 1427 2826 1428 2827 1427 2827 1478 2827 1429 2828 1422 2828 1430 2828 1430 2829 1422 2829 1432 2829 1430 2830 1432 2830 1431 2830 1431 2831 1432 2831 1421 2831 1431 2832 1421 2832 1433 2832 1433 2833 1421 2833 1417 2833 1433 2834 1417 2834 1409 2834 1409 2835 1417 2835 1554 2835 1410 2836 1442 2836 1433 2836 1433 2837 1442 2837 1441 2837 1433 2838 1441 2838 1431 2838 1431 2839 1441 2839 1434 2839 1431 2840 1434 2840 1430 2840 1430 2841 1434 2841 1439 2841 1430 2842 1439 2842 1429 2842 1429 2843 1439 2843 2287 2843 2290 2844 2289 2844 1435 2844 2290 2845 1435 2845 691 2845 691 2846 1435 2846 1436 2846 691 2847 1436 2847 686 2847 686 2848 1436 2848 1465 2848 686 2849 1465 2849 1437 2849 1437 2850 1465 2850 1572 2850 1437 2851 1572 2851 1576 2851 1472 2852 2287 2852 1439 2852 1472 2853 1439 2853 1438 2853 1438 2854 1439 2854 1434 2854 1438 2855 1434 2855 1440 2855 1440 2856 1434 2856 1441 2856 1440 2857 1441 2857 1445 2857 1445 2858 1441 2858 1442 2858 1445 2859 1442 2859 1556 2859 1472 2860 1438 2860 1451 2860 1438 2861 1440 2861 1452 2861 1440 2862 1445 2862 1443 2862 1569 2863 1570 2863 1464 2863 1445 2864 1556 2864 1444 2864 1445 2865 1444 2865 1443 2865 1443 2866 1444 2866 1565 2866 1443 2867 1565 2867 1447 2867 1565 2868 1446 2868 1447 2868 1447 2869 1446 2869 1566 2869 1447 2870 1566 2870 1449 2870 1449 2871 1566 2871 1448 2871 1449 2872 1448 2872 1463 2872 1440 2873 1443 2873 1452 2873 1452 2874 1443 2874 1447 2874 1452 2875 1447 2875 1453 2875 1453 2876 1447 2876 1449 2876 1453 2877 1449 2877 1450 2877 1450 2878 1449 2878 1463 2878 1450 2879 1463 2879 1462 2879 1438 2880 1452 2880 1451 2880 1451 2881 1452 2881 1453 2881 1451 2882 1453 2882 1458 2882 1458 2883 1453 2883 1450 2883 1458 2884 1450 2884 1457 2884 1457 2885 1450 2885 1462 2885 1457 2886 1462 2886 1455 2886 1468 2887 1454 2887 1455 2887 1455 2888 1454 2888 1456 2888 1455 2889 1456 2889 1457 2889 1457 2890 1456 2890 1469 2890 1457 2891 1469 2891 1458 2891 1458 2892 1469 2892 1459 2892 1458 2893 1459 2893 1451 2893 1451 2894 1459 2894 1460 2894 1451 2895 1460 2895 1472 2895 1467 2896 1468 2896 1466 2896 1466 2897 1468 2897 1455 2897 1466 2898 1455 2898 1461 2898 1461 2899 1455 2899 1462 2899 1461 2900 1462 2900 1464 2900 1464 2901 1462 2901 1463 2901 1464 2902 1463 2902 1569 2902 1569 2903 1463 2903 1448 2903 1570 2904 1572 2904 1464 2904 1464 2905 1572 2905 1465 2905 1464 2906 1465 2906 1461 2906 1461 2907 1465 2907 1436 2907 1461 2908 1436 2908 1466 2908 1466 2909 1436 2909 1435 2909 1466 2910 1435 2910 1467 2910 1467 2911 1435 2911 2289 2911 2289 2912 2288 2912 1467 2912 1467 2913 2288 2913 650 2913 1467 2914 650 2914 1468 2914 1468 2915 650 2915 1454 2915 1454 2916 650 2916 648 2916 1454 2917 648 2917 1456 2917 1456 2918 648 2918 1469 2918 1469 2919 648 2919 1470 2919 1469 2920 1470 2920 1459 2920 1459 2921 1470 2921 1460 2921 1460 2922 1470 2922 1471 2922 1460 2923 1471 2923 1472 2923 2287 2924 645 2924 1429 2924 1429 2925 645 2925 1473 2925 1429 2926 1473 2926 1422 2926 1422 2927 1473 2927 1423 2927 1423 2928 1473 2928 1474 2928 1423 2929 1474 2929 1424 2929 1424 2930 1474 2930 1426 2930 1426 2931 1474 2931 1476 2931 1426 2932 1476 2932 1475 2932 1475 2933 1476 2933 1427 2933 1427 2934 1476 2934 1477 2934 1427 2935 1477 2935 1478 2935 1504 2936 1488 2936 1540 2936 1540 2937 1488 2937 1492 2937 1540 2938 1492 2938 1480 2938 1492 2939 1479 2939 1480 2939 1480 2940 1479 2940 1481 2940 1480 2941 1481 2941 1542 2941 1542 2942 1481 2942 1490 2942 1542 2943 1490 2943 1543 2943 1543 2944 1490 2944 1483 2944 1543 2945 1483 2945 1482 2945 1483 2946 1484 2946 1482 2946 1482 2947 1484 2947 1501 2947 1482 2948 1501 2948 1545 2948 1545 2949 1501 2949 1485 2949 1545 2950 1485 2950 1486 2950 1486 2951 1485 2951 1503 2951 1486 2952 1503 2952 1487 2952 1487 2953 1503 2953 1535 2953 1488 2954 1505 2954 1491 2954 1505 2955 2132 2955 1493 2955 1500 2956 1484 2956 1489 2956 1489 2957 1484 2957 1483 2957 1489 2958 1483 2958 1499 2958 1499 2959 1483 2959 1490 2959 1499 2960 1490 2960 1496 2960 1496 2961 1490 2961 1481 2961 1496 2962 1481 2962 1495 2962 1495 2963 1481 2963 1479 2963 1495 2964 1479 2964 1491 2964 1491 2965 1479 2965 1492 2965 1491 2966 1492 2966 1488 2966 1505 2967 1493 2967 1491 2967 1491 2968 1493 2968 1494 2968 1491 2969 1494 2969 1495 2969 1495 2970 1494 2970 1497 2970 1495 2971 1497 2971 1496 2971 1496 2972 1497 2972 1498 2972 1496 2973 1498 2973 1499 2973 1499 2974 1498 2974 2123 2974 1499 2975 2123 2975 1489 2975 1489 2976 2123 2976 2125 2976 1489 2977 2125 2977 1500 2977 1503 2978 1485 2978 1500 2978 1500 2979 1485 2979 1501 2979 1500 2980 1501 2980 1484 2980 2118 2981 2181 2981 1502 2981 1502 2982 2181 2982 1536 2982 2125 2983 2118 2983 1500 2983 1500 2984 2118 2984 1502 2984 1500 2985 1502 2985 1503 2985 1503 2986 1502 2986 1536 2986 1503 2987 1536 2987 1535 2987 749 2988 1488 2988 729 2988 729 2989 1488 2989 1504 2989 2133 2990 2132 2990 748 2990 748 2991 2132 2991 1505 2991 748 2992 1505 2992 749 2992 749 2993 1505 2993 1488 2993 1506 2994 1563 2994 760 2994 760 2995 1563 2995 1507 2995 760 2996 1507 2996 1509 2996 1509 2997 1507 2997 1508 2997 1509 2998 1508 2998 762 2998 762 2999 1508 2999 2109 2999 1510 3000 1534 3000 1555 3000 1555 3001 1534 3001 1511 3001 1555 3002 1511 3002 1512 3002 1511 3003 1520 3003 1512 3003 1512 3004 1520 3004 1513 3004 1512 3005 1513 3005 1558 3005 1558 3006 1513 3006 1519 3006 1558 3007 1519 3007 1560 3007 1560 3008 1519 3008 1514 3008 1560 3009 1514 3009 1515 3009 1514 3010 1518 3010 1515 3010 1515 3011 1518 3011 1529 3011 1515 3012 1529 3012 1562 3012 1562 3013 1529 3013 1517 3013 1562 3014 1517 3014 1516 3014 1516 3015 1517 3015 1533 3015 1516 3016 1533 3016 1563 3016 1563 3017 1533 3017 1507 3017 1534 3018 1537 3018 1522 3018 1537 3019 1538 3019 2111 3019 1531 3020 1518 3020 1528 3020 1528 3021 1518 3021 1514 3021 1528 3022 1514 3022 1527 3022 1527 3023 1514 3023 1519 3023 1527 3024 1519 3024 1525 3024 1525 3025 1519 3025 1513 3025 1525 3026 1513 3026 1521 3026 1521 3027 1513 3027 1520 3027 1521 3028 1520 3028 1522 3028 1522 3029 1520 3029 1511 3029 1522 3030 1511 3030 1534 3030 1537 3031 2111 3031 1522 3031 1522 3032 2111 3032 1523 3032 1522 3033 1523 3033 1521 3033 1521 3034 1523 3034 1524 3034 1521 3035 1524 3035 1525 3035 1525 3036 1524 3036 1526 3036 1525 3037 1526 3037 1527 3037 1527 3038 1526 3038 2115 3038 1527 3039 2115 3039 1528 3039 1528 3040 2115 3040 2117 3040 1528 3041 2117 3041 1531 3041 1533 3042 1517 3042 1531 3042 1531 3043 1517 3043 1529 3043 1531 3044 1529 3044 1518 3044 1532 3045 2109 3045 1530 3045 1530 3046 2109 3046 1508 3046 2117 3047 1532 3047 1531 3047 1531 3048 1532 3048 1530 3048 1531 3049 1530 3049 1533 3049 1533 3050 1530 3050 1508 3050 1533 3051 1508 3051 1507 3051 1535 3052 1534 3052 1487 3052 1487 3053 1534 3053 1510 3053 1534 3054 1535 3054 1536 3054 1534 3055 1536 3055 1537 3055 1537 3056 1536 3056 2181 3056 1537 3057 2181 3057 1538 3057 1539 3058 1504 3058 1540 3058 1548 3059 1539 3059 1541 3059 1539 3060 1540 3060 1541 3060 1541 3061 1540 3061 1480 3061 1541 3062 1480 3062 1549 3062 1549 3063 1480 3063 1542 3063 1549 3064 1542 3064 1550 3064 1550 3065 1542 3065 1543 3065 1550 3066 1543 3066 1553 3066 1553 3067 1543 3067 1482 3067 1553 3068 1482 3068 1544 3068 1544 3069 1482 3069 1545 3069 1544 3070 1545 3070 1546 3070 1546 3071 1545 3071 1486 3071 1546 3072 1486 3072 1547 3072 1547 3073 1486 3073 1487 3073 1547 3074 1487 3074 1573 3074 1548 3075 1541 3075 1411 3075 1411 3076 1541 3076 1549 3076 1411 3077 1549 3077 1412 3077 1412 3078 1549 3078 1550 3078 1412 3079 1550 3079 1551 3079 1551 3080 1550 3080 1553 3080 1551 3081 1553 3081 1552 3081 1552 3082 1553 3082 1544 3082 1552 3083 1544 3083 1554 3083 1554 3084 1544 3084 1546 3084 1554 3085 1546 3085 1409 3085 1409 3086 1546 3086 1547 3086 1409 3087 1547 3087 1410 3087 1410 3088 1547 3088 1573 3088 1410 3089 1573 3089 1442 3089 1574 3090 1510 3090 1555 3090 1556 3091 1574 3091 1557 3091 1574 3092 1555 3092 1557 3092 1557 3093 1555 3093 1512 3093 1557 3094 1512 3094 1564 3094 1564 3095 1512 3095 1558 3095 1564 3096 1558 3096 1559 3096 1559 3097 1558 3097 1560 3097 1559 3098 1560 3098 1561 3098 1561 3099 1560 3099 1515 3099 1561 3100 1515 3100 1567 3100 1567 3101 1515 3101 1562 3101 1567 3102 1562 3102 1568 3102 1568 3103 1562 3103 1516 3103 1568 3104 1516 3104 1571 3104 1571 3105 1516 3105 1563 3105 1571 3106 1563 3106 1577 3106 1556 3107 1557 3107 1444 3107 1444 3108 1557 3108 1564 3108 1444 3109 1564 3109 1565 3109 1565 3110 1564 3110 1559 3110 1565 3111 1559 3111 1446 3111 1446 3112 1559 3112 1561 3112 1446 3113 1561 3113 1566 3113 1566 3114 1561 3114 1567 3114 1566 3115 1567 3115 1448 3115 1448 3116 1567 3116 1568 3116 1448 3117 1568 3117 1569 3117 1569 3118 1568 3118 1571 3118 1569 3119 1571 3119 1570 3119 1570 3120 1571 3120 1577 3120 1570 3121 1577 3121 1572 3121 1556 3122 1442 3122 1573 3122 1556 3123 1573 3123 1574 3123 1574 3124 1573 3124 1487 3124 1574 3125 1487 3125 1510 3125 1548 3126 656 3126 1575 3126 1548 3127 1575 3127 1539 3127 1539 3128 1575 3128 729 3128 1539 3129 729 3129 1504 3129 1576 3130 1572 3130 1577 3130 1576 3131 1577 3131 1578 3131 1578 3132 1577 3132 1563 3132 1578 3133 1563 3133 1506 3133 2268 3134 2264 3134 1584 3134 1585 3135 1580 3135 1584 3135 1584 3136 1580 3136 1582 3136 1584 3137 1582 3137 2268 3137 2268 3138 1582 3138 2269 3138 1579 3139 2273 3139 1604 3139 1604 3140 2273 3140 2272 3140 1604 3141 2272 3141 1582 3141 1582 3142 2272 3142 2269 3142 1582 3143 1580 3143 1799 3143 1799 3144 1581 3144 1582 3144 1582 3145 1581 3145 1798 3145 1582 3146 1798 3146 1604 3146 1604 3147 1798 3147 1583 3147 1604 3148 1583 3148 1800 3148 1584 3149 2264 3149 1593 3149 1585 3150 1584 3150 1586 3150 1585 3151 1586 3151 1838 3151 1838 3152 1586 3152 1595 3152 1838 3153 1595 3153 1587 3153 1587 3154 1595 3154 1589 3154 1587 3155 1589 3155 1588 3155 1588 3156 1589 3156 1591 3156 1588 3157 1591 3157 1590 3157 1590 3158 1591 3158 1598 3158 1590 3159 1598 3159 1592 3159 1584 3160 1593 3160 1586 3160 1586 3161 1593 3161 1594 3161 1586 3162 1594 3162 1595 3162 1595 3163 1594 3163 1596 3163 1595 3164 1596 3164 1589 3164 1589 3165 1596 3165 2232 3165 1589 3166 2232 3166 1591 3166 1591 3167 2232 3167 1597 3167 1591 3168 1597 3168 1598 3168 1598 3169 1597 3169 2230 3169 1598 3170 2230 3170 1600 3170 1600 3171 2230 3171 1606 3171 1600 3172 1606 3172 1601 3172 1592 3173 1598 3173 1599 3173 1599 3174 1598 3174 1600 3174 1599 3175 1600 3175 1602 3175 1602 3176 1600 3176 1601 3176 1602 3177 1601 3177 1603 3177 2275 3178 1579 3178 1604 3178 1800 3179 1626 3179 1604 3179 1604 3180 1626 3180 1624 3180 1604 3181 1624 3181 2275 3181 2275 3182 1624 3182 2208 3182 2229 3183 1608 3183 1605 3183 1605 3184 1608 3184 1601 3184 1605 3185 1601 3185 2231 3185 2231 3186 1601 3186 1606 3186 1608 3187 1788 3187 1607 3187 1607 3188 1791 3188 1608 3188 1608 3189 1791 3189 1609 3189 1608 3190 1609 3190 1601 3190 1601 3191 1609 3191 1792 3191 1601 3192 1792 3192 1603 3192 2208 3193 1624 3193 1610 3193 2208 3194 1610 3194 2206 3194 2206 3195 1610 3195 1611 3195 2206 3196 1611 3196 1612 3196 1612 3197 1611 3197 1622 3197 1612 3198 1622 3198 2217 3198 2217 3199 1622 3199 1614 3199 2217 3200 1614 3200 1613 3200 1613 3201 1614 3201 1620 3201 1613 3202 1620 3202 1615 3202 2218 3203 1619 3203 1616 3203 1616 3204 1619 3204 1617 3204 1616 3205 1617 3205 1807 3205 1831 3206 1618 3206 1617 3206 1617 3207 1618 3207 1805 3207 1617 3208 1805 3208 1807 3208 1619 3209 1615 3209 1617 3209 1617 3210 1615 3210 1620 3210 1617 3211 1620 3211 1831 3211 1831 3212 1620 3212 1614 3212 1831 3213 1614 3213 1621 3213 1621 3214 1614 3214 1622 3214 1621 3215 1622 3215 1623 3215 1623 3216 1622 3216 1804 3216 1804 3217 1622 3217 1611 3217 1804 3218 1611 3218 1803 3218 1803 3219 1611 3219 1610 3219 1803 3220 1610 3220 1625 3220 1625 3221 1610 3221 1624 3221 1625 3222 1624 3222 1626 3222 1608 3223 2229 3223 1630 3223 1788 3224 1608 3224 1627 3224 1788 3225 1627 3225 1628 3225 1628 3226 1627 3226 1632 3226 1628 3227 1632 3227 1629 3227 1629 3228 1632 3228 1633 3228 1629 3229 1633 3229 1845 3229 1845 3230 1633 3230 1639 3230 1845 3231 1639 3231 1637 3231 1608 3232 1630 3232 1627 3232 1627 3233 1630 3233 1631 3233 1627 3234 1631 3234 1632 3234 1632 3235 1631 3235 1634 3235 1632 3236 1634 3236 1633 3236 1633 3237 1634 3237 2226 3237 1633 3238 2226 3238 1639 3238 1639 3239 2226 3239 2228 3239 1639 3240 2228 3240 1635 3240 1635 3241 2228 3241 2227 3241 1635 3242 2227 3242 1640 3242 1640 3243 2227 3243 1636 3243 1640 3244 1636 3244 1646 3244 1637 3245 1639 3245 1638 3245 1638 3246 1639 3246 1635 3246 1638 3247 1635 3247 1783 3247 1783 3248 1635 3248 1640 3248 1783 3249 1640 3249 1849 3249 1849 3250 1640 3250 1646 3250 1849 3251 1646 3251 1781 3251 2218 3252 1616 3252 1641 3252 1641 3253 1616 3253 1644 3253 1641 3254 1644 3254 1642 3254 1642 3255 1644 3255 2219 3255 1616 3256 1807 3256 1809 3256 1809 3257 1643 3257 1616 3257 1616 3258 1643 3258 1811 3258 1616 3259 1811 3259 1644 3259 1644 3260 1811 3260 1813 3260 1644 3261 1813 3261 1814 3261 2129 3262 2128 3262 1664 3262 1645 3263 1781 3263 1664 3263 1664 3264 1781 3264 1646 3264 1664 3265 1646 3265 2129 3265 2129 3266 1646 3266 1636 3266 1666 3267 1647 3267 2223 3267 1824 3268 1666 3268 1648 3268 1666 3269 2223 3269 1648 3269 1648 3270 2223 3270 2224 3270 1648 3271 2224 3271 1649 3271 1649 3272 2224 3272 2221 3272 1649 3273 2221 3273 1650 3273 1650 3274 2221 3274 1651 3274 1650 3275 1651 3275 1656 3275 1656 3276 1651 3276 2220 3276 1656 3277 2220 3277 1657 3277 1657 3278 2220 3278 1652 3278 1657 3279 1652 3279 1658 3279 1658 3280 1652 3280 2219 3280 1658 3281 2219 3281 1644 3281 1824 3282 1648 3282 1653 3282 1653 3283 1648 3283 1649 3283 1653 3284 1649 3284 1654 3284 1654 3285 1649 3285 1650 3285 1654 3286 1650 3286 1655 3286 1655 3287 1650 3287 1656 3287 1655 3288 1656 3288 1819 3288 1819 3289 1656 3289 1657 3289 1819 3290 1657 3290 1818 3290 1818 3291 1657 3291 1658 3291 1818 3292 1658 3292 1659 3292 1659 3293 1658 3293 1644 3293 1659 3294 1644 3294 1814 3294 2128 3295 2127 3295 1664 3295 1664 3296 2127 3296 1660 3296 1664 3297 1660 3297 1663 3297 1663 3298 1660 3298 1661 3298 1663 3299 1667 3299 1662 3299 1662 3300 1822 3300 1663 3300 1663 3301 1822 3301 1665 3301 1663 3302 1665 3302 1664 3302 1664 3303 1665 3303 1820 3303 1664 3304 1820 3304 1645 3304 2130 3305 1647 3305 1666 3305 1824 3306 1667 3306 1666 3306 1666 3307 1667 3307 1663 3307 1666 3308 1663 3308 2130 3308 2130 3309 1663 3309 1661 3309 1672 3310 2041 3310 1682 3310 1682 3311 1681 3311 1672 3311 1672 3312 1681 3312 1668 3312 1672 3313 1668 3313 1669 3313 1669 3314 1668 3314 1670 3314 1669 3315 1670 3315 1834 3315 1671 3316 1836 3316 1673 3316 2041 3317 1672 3317 2039 3317 2039 3318 1672 3318 1673 3318 2039 3319 1673 3319 1700 3319 1669 3320 1801 3320 1672 3320 1672 3321 1801 3321 1797 3321 1672 3322 1797 3322 1673 3322 1673 3323 1797 3323 1674 3323 1673 3324 1674 3324 1671 3324 1685 3325 1833 3325 1686 3325 1687 3326 1686 3326 1829 3326 1834 3327 1670 3327 1675 3327 1675 3328 1670 3328 1687 3328 1675 3329 1687 3329 1676 3329 1676 3330 1687 3330 1829 3330 1695 3331 1697 3331 1685 3331 1677 3332 1680 3332 1982 3332 1982 3333 1680 3333 1678 3333 1982 3334 1678 3334 1679 3334 1679 3335 1678 3335 1985 3335 1680 3336 1668 3336 1678 3336 1678 3337 1668 3337 1681 3337 1678 3338 1681 3338 1985 3338 1985 3339 1681 3339 1682 3339 1806 3340 1683 3340 1697 3340 1697 3341 1683 3341 1684 3341 1697 3342 1684 3342 1685 3342 1685 3343 1684 3343 1830 3343 1685 3344 1830 3344 1833 3344 1695 3345 1685 3345 1694 3345 1694 3346 1685 3346 1686 3346 1694 3347 1686 3347 1677 3347 1677 3348 1686 3348 1687 3348 1677 3349 1687 3349 1680 3349 1680 3350 1687 3350 1670 3350 1680 3351 1670 3351 1668 3351 1705 3352 1696 3352 1691 3352 1691 3353 1696 3353 1689 3353 1692 3354 1980 3354 1693 3354 1693 3355 1980 3355 1688 3355 1693 3356 1688 3356 1689 3356 1689 3357 1688 3357 1690 3357 1689 3358 1690 3358 1691 3358 1982 3359 1692 3359 1677 3359 1677 3360 1692 3360 1693 3360 1677 3361 1693 3361 1694 3361 1694 3362 1693 3362 1689 3362 1694 3363 1689 3363 1695 3363 1695 3364 1689 3364 1696 3364 1695 3365 1696 3365 1697 3365 1697 3366 1696 3366 1808 3366 1697 3367 1808 3367 1806 3367 1836 3368 1716 3368 1698 3368 1836 3369 1698 3369 1673 3369 1699 3370 1700 3370 1701 3370 1701 3371 1700 3371 1673 3371 1701 3372 1673 3372 1719 3372 1719 3373 1673 3373 1698 3373 1810 3374 1808 3374 1696 3374 1815 3375 1812 3375 1733 3375 1733 3376 1812 3376 1702 3376 1733 3377 1702 3377 1696 3377 1696 3378 1702 3378 1703 3378 1696 3379 1703 3379 1810 3379 1734 3380 1733 3380 1704 3380 1704 3381 1733 3381 1696 3381 1704 3382 1696 3382 2061 3382 2061 3383 1696 3383 1705 3383 1720 3384 1699 3384 1701 3384 1841 3385 1706 3385 1721 3385 1795 3386 1794 3386 1744 3386 1710 3387 1709 3387 1707 3387 1707 3388 1709 3388 1713 3388 1707 3389 1713 3389 1975 3389 1839 3390 1840 3390 1717 3390 1717 3391 1840 3391 1708 3391 1717 3392 1708 3392 1718 3392 1718 3393 1708 3393 1709 3393 1718 3394 1709 3394 1711 3394 1711 3395 1709 3395 1710 3395 1711 3396 1710 3396 1977 3396 1723 3397 1712 3397 1713 3397 1713 3398 1712 3398 1972 3398 1713 3399 1972 3399 1975 3399 1746 3400 1714 3400 1744 3400 1744 3401 1714 3401 1722 3401 1744 3402 1722 3402 1795 3402 1721 3403 1706 3403 1722 3403 1722 3404 1706 3404 1715 3404 1722 3405 1715 3405 1795 3405 1716 3406 1839 3406 1698 3406 1698 3407 1839 3407 1717 3407 1698 3408 1717 3408 1719 3408 1719 3409 1717 3409 1718 3409 1719 3410 1718 3410 1701 3410 1701 3411 1718 3411 1711 3411 1701 3412 1711 3412 1720 3412 1720 3413 1711 3413 1977 3413 1708 3414 1841 3414 1709 3414 1709 3415 1841 3415 1721 3415 1709 3416 1721 3416 1713 3416 1713 3417 1721 3417 1722 3417 1713 3418 1722 3418 1723 3418 1723 3419 1722 3419 1714 3419 1723 3420 1714 3420 1712 3420 1741 3421 1749 3421 1750 3421 1828 3422 1736 3422 1735 3422 1724 3423 1730 3423 1725 3423 1725 3424 1964 3424 1724 3424 1724 3425 1964 3425 1966 3425 1724 3426 1966 3426 1968 3426 1726 3427 1777 3427 1739 3427 1739 3428 1777 3428 1727 3428 1739 3429 1727 3429 1728 3429 1728 3430 1727 3430 1724 3430 1728 3431 1724 3431 1740 3431 1740 3432 1724 3432 1968 3432 1740 3433 1968 3433 1742 3433 1729 3434 1731 3434 1730 3434 1730 3435 1731 3435 1732 3435 1730 3436 1732 3436 1725 3436 1733 3437 1734 3437 1961 3437 1733 3438 1961 3438 1743 3438 1735 3439 1736 3439 1743 3439 1736 3440 1817 3440 1743 3440 1743 3441 1817 3441 1816 3441 1743 3442 1816 3442 1733 3442 1733 3443 1816 3443 1737 3443 1733 3444 1737 3444 1815 3444 1826 3445 1726 3445 1738 3445 1738 3446 1726 3446 1739 3446 1738 3447 1739 3447 1751 3447 1751 3448 1739 3448 1728 3448 1751 3449 1728 3449 1750 3449 1750 3450 1728 3450 1740 3450 1750 3451 1740 3451 1741 3451 1741 3452 1740 3452 1742 3452 1727 3453 1828 3453 1724 3453 1724 3454 1828 3454 1735 3454 1724 3455 1735 3455 1730 3455 1730 3456 1735 3456 1743 3456 1730 3457 1743 3457 1729 3457 1729 3458 1743 3458 1961 3458 1729 3459 1961 3459 1731 3459 1789 3460 1759 3460 1747 3460 1794 3461 1793 3461 1744 3461 1744 3462 1793 3462 1745 3462 1744 3463 1745 3463 1747 3463 1747 3464 1745 3464 1790 3464 1747 3465 1790 3465 1789 3465 1746 3466 1744 3466 2070 3466 2070 3467 1744 3467 1747 3467 2070 3468 1747 3468 2067 3468 2067 3469 1747 3469 1769 3469 1771 3470 1826 3470 1738 3470 1771 3471 1738 3471 1748 3471 1749 3472 1971 3472 1750 3472 1750 3473 1971 3473 1748 3473 1750 3474 1748 3474 1751 3474 1751 3475 1748 3475 1738 3475 1960 3476 1958 3476 1758 3476 1847 3477 1846 3477 1752 3477 1784 3478 1754 3478 1842 3478 1842 3479 1754 3479 1843 3479 1767 3480 1786 3480 1753 3480 1767 3481 1753 3481 1760 3481 1843 3482 1754 3482 1755 3482 1755 3483 1754 3483 1756 3483 1755 3484 1756 3484 1758 3484 1758 3485 1958 3485 1755 3485 1755 3486 1958 3486 1957 3486 1755 3487 1957 3487 1955 3487 1784 3488 1847 3488 1754 3488 1754 3489 1847 3489 1752 3489 1754 3490 1752 3490 1756 3490 1756 3491 1752 3491 1776 3491 1756 3492 1776 3492 1758 3492 1758 3493 1776 3493 1757 3493 1758 3494 1757 3494 1960 3494 1960 3495 1757 3495 1959 3495 1747 3496 1759 3496 1767 3496 1767 3497 1759 3497 1787 3497 1767 3498 1787 3498 1786 3498 1753 3499 1761 3499 1760 3499 1760 3500 1761 3500 1762 3500 1760 3501 1762 3501 1755 3501 1755 3502 1762 3502 1844 3502 1755 3503 1844 3503 1843 3503 1763 3504 1951 3504 1764 3504 1764 3505 1951 3505 1953 3505 1764 3506 1953 3506 1768 3506 1766 3507 1949 3507 1763 3507 1763 3508 1949 3508 1765 3508 1763 3509 1765 3509 1951 3509 1955 3510 1766 3510 1755 3510 1755 3511 1766 3511 1763 3511 1755 3512 1763 3512 1760 3512 1760 3513 1763 3513 1764 3513 1760 3514 1764 3514 1767 3514 1767 3515 1764 3515 1768 3515 1767 3516 1768 3516 1747 3516 1747 3517 1768 3517 1769 3517 1770 3518 1771 3518 1748 3518 1971 3519 1772 3519 1748 3519 1748 3520 1772 3520 2065 3520 1748 3521 2065 3521 1774 3521 1774 3522 2065 3522 1775 3522 1780 3523 1821 3523 1774 3523 1774 3524 1821 3524 1773 3524 1774 3525 1773 3525 1748 3525 1748 3526 1773 3526 1823 3526 1748 3527 1823 3527 1770 3527 1774 3528 1775 3528 1959 3528 1959 3529 1757 3529 1774 3529 1774 3530 1757 3530 1776 3530 1774 3531 1776 3531 1780 3531 1780 3532 1776 3532 1752 3532 1780 3533 1752 3533 1846 3533 1777 3534 1726 3534 1827 3534 1653 3535 1825 3535 1778 3535 1825 3536 1653 3536 1654 3536 1830 3537 1684 3537 1618 3537 1836 3538 1671 3538 1779 3538 1848 3539 1821 3539 1780 3539 1781 3540 1645 3540 1821 3540 1821 3541 1848 3541 1781 3541 1781 3542 1848 3542 1782 3542 1781 3543 1782 3543 1849 3543 1847 3544 1784 3544 1783 3544 1783 3545 1784 3545 1842 3545 1783 3546 1842 3546 1638 3546 1638 3547 1842 3547 1785 3547 1638 3548 1785 3548 1637 3548 1637 3549 1785 3549 1845 3549 1753 3550 1628 3550 1629 3550 1753 3551 1786 3551 1628 3551 1628 3552 1786 3552 1787 3552 1628 3553 1787 3553 1788 3553 1788 3554 1787 3554 1759 3554 1788 3555 1759 3555 1607 3555 1759 3556 1789 3556 1607 3556 1607 3557 1789 3557 1790 3557 1607 3558 1790 3558 1791 3558 1791 3559 1790 3559 1745 3559 1791 3560 1745 3560 1609 3560 1609 3561 1745 3561 1793 3561 1609 3562 1793 3562 1792 3562 1792 3563 1793 3563 1794 3563 1792 3564 1794 3564 1603 3564 1603 3565 1794 3565 1602 3565 1602 3566 1794 3566 1795 3566 1602 3567 1795 3567 1599 3567 1599 3568 1795 3568 1715 3568 1599 3569 1715 3569 1592 3569 1592 3570 1715 3570 1706 3570 1592 3571 1706 3571 1590 3571 1590 3572 1796 3572 1588 3572 1588 3573 1796 3573 1587 3573 1801 3574 1798 3574 1797 3574 1797 3575 1798 3575 1581 3575 1797 3576 1581 3576 1674 3576 1674 3577 1581 3577 1799 3577 1674 3578 1799 3578 1671 3578 1671 3579 1799 3579 1580 3579 1671 3580 1580 3580 1779 3580 1835 3581 1801 3581 1669 3581 1626 3582 1800 3582 1801 3582 1801 3583 1800 3583 1583 3583 1801 3584 1583 3584 1798 3584 1801 3585 1835 3585 1626 3585 1626 3586 1835 3586 1802 3586 1626 3587 1802 3587 1625 3587 1675 3588 1676 3588 1803 3588 1803 3589 1676 3589 1829 3589 1831 3590 1621 3590 1832 3590 1832 3591 1621 3591 1623 3591 1832 3592 1623 3592 1804 3592 1618 3593 1684 3593 1805 3593 1684 3594 1683 3594 1805 3594 1805 3595 1683 3595 1806 3595 1805 3596 1806 3596 1807 3596 1807 3597 1806 3597 1808 3597 1807 3598 1808 3598 1809 3598 1808 3599 1810 3599 1809 3599 1809 3600 1810 3600 1703 3600 1809 3601 1703 3601 1643 3601 1643 3602 1703 3602 1702 3602 1643 3603 1702 3603 1811 3603 1811 3604 1702 3604 1812 3604 1811 3605 1812 3605 1813 3605 1813 3606 1812 3606 1814 3606 1812 3607 1815 3607 1814 3607 1814 3608 1815 3608 1737 3608 1814 3609 1737 3609 1659 3609 1737 3610 1816 3610 1659 3610 1659 3611 1816 3611 1817 3611 1659 3612 1817 3612 1818 3612 1655 3613 1819 3613 1827 3613 1827 3614 1819 3614 1818 3614 1645 3615 1820 3615 1821 3615 1821 3616 1820 3616 1665 3616 1821 3617 1665 3617 1773 3617 1773 3618 1665 3618 1822 3618 1773 3619 1822 3619 1823 3619 1823 3620 1822 3620 1662 3620 1823 3621 1662 3621 1770 3621 1770 3622 1662 3622 1667 3622 1770 3623 1667 3623 1778 3623 1778 3624 1667 3624 1824 3624 1778 3625 1824 3625 1653 3625 1655 3626 1827 3626 1654 3626 1654 3627 1827 3627 1726 3627 1654 3628 1726 3628 1825 3628 1825 3629 1726 3629 1826 3629 1825 3630 1826 3630 1778 3630 1778 3631 1826 3631 1771 3631 1778 3632 1771 3632 1770 3632 1817 3633 1736 3633 1818 3633 1818 3634 1736 3634 1828 3634 1818 3635 1828 3635 1827 3635 1827 3636 1828 3636 1727 3636 1827 3637 1727 3637 1777 3637 1686 3638 1832 3638 1829 3638 1829 3639 1832 3639 1804 3639 1829 3640 1804 3640 1803 3640 1618 3641 1831 3641 1830 3641 1830 3642 1831 3642 1832 3642 1830 3643 1832 3643 1833 3643 1833 3644 1832 3644 1686 3644 1669 3645 1834 3645 1835 3645 1835 3646 1834 3646 1675 3646 1835 3647 1675 3647 1802 3647 1802 3648 1675 3648 1803 3648 1802 3649 1803 3649 1625 3649 1836 3650 1779 3650 1716 3650 1716 3651 1779 3651 1837 3651 1716 3652 1837 3652 1839 3652 1580 3653 1585 3653 1779 3653 1779 3654 1585 3654 1838 3654 1779 3655 1838 3655 1837 3655 1837 3656 1838 3656 1587 3656 1837 3657 1587 3657 1839 3657 1839 3658 1587 3658 1796 3658 1839 3659 1796 3659 1840 3659 1840 3660 1796 3660 1708 3660 1590 3661 1706 3661 1796 3661 1796 3662 1706 3662 1841 3662 1796 3663 1841 3663 1708 3663 1842 3664 1843 3664 1785 3664 1785 3665 1843 3665 1844 3665 1785 3666 1844 3666 1845 3666 1845 3667 1844 3667 1762 3667 1845 3668 1762 3668 1629 3668 1629 3669 1762 3669 1761 3669 1629 3670 1761 3670 1753 3670 1780 3671 1846 3671 1848 3671 1848 3672 1846 3672 1847 3672 1848 3673 1847 3673 1782 3673 1782 3674 1847 3674 1783 3674 1782 3675 1783 3675 1849 3675 1852 3676 2196 3676 1853 3676 1853 3677 2196 3677 1863 3677 1853 3678 1863 3678 1850 3678 1850 3679 1863 3679 1864 3679 1850 3680 1864 3680 1851 3680 1851 3681 1864 3681 1866 3681 1851 3682 1866 3682 2014 3682 2014 3683 1866 3683 2013 3683 2293 3684 1852 3684 2294 3684 2294 3685 1852 3685 1853 3685 2294 3686 1853 3686 2296 3686 2296 3687 1853 3687 1850 3687 2296 3688 1850 3688 2297 3688 2297 3689 1850 3689 1851 3689 2297 3690 1851 3690 2017 3690 2017 3691 1851 3691 2014 3691 2197 3692 1854 3692 1856 3692 1856 3693 1854 3693 1855 3693 1856 3694 1855 3694 1871 3694 1871 3695 1855 3695 1857 3695 1871 3696 1857 3696 1858 3696 1858 3697 1857 3697 1859 3697 1858 3698 1859 3698 1868 3698 1868 3699 1859 3699 1861 3699 1868 3700 1861 3700 1860 3700 1860 3701 1861 3701 2019 3701 1863 3702 2196 3702 2193 3702 2285 3703 2286 3703 2316 3703 2316 3704 2286 3704 1862 3704 2316 3705 1862 3705 2315 3705 2315 3706 1862 3706 2012 3706 2315 3707 2012 3707 2314 3707 2314 3708 2012 3708 2199 3708 2314 3709 2199 3709 2000 3709 2193 3710 2314 3710 1863 3710 1863 3711 2314 3711 2000 3711 1863 3712 2000 3712 1864 3712 1864 3713 2000 3713 1865 3713 1864 3714 1865 3714 1866 3714 1866 3715 1865 3715 1867 3715 1866 3716 1867 3716 2013 3716 1872 3717 2197 3717 1874 3717 1874 3718 2197 3718 1856 3718 1874 3719 1856 3719 1870 3719 1860 3720 2026 3720 1868 3720 1868 3721 2026 3721 1869 3721 1868 3722 1869 3722 1858 3722 1858 3723 1869 3723 1870 3723 1858 3724 1870 3724 1871 3724 1871 3725 1870 3725 1856 3725 2302 3726 1872 3726 1873 3726 1873 3727 1872 3727 1874 3727 1873 3728 1874 3728 2303 3728 2303 3729 1874 3729 1870 3729 2303 3730 1870 3730 2305 3730 2305 3731 1870 3731 1869 3731 2305 3732 1869 3732 2024 3732 2024 3733 1869 3733 2026 3733 2195 3734 1876 3734 1875 3734 1875 3735 1876 3735 1895 3735 1875 3736 1895 3736 1878 3736 1890 3737 2038 3737 1891 3737 1891 3738 2038 3738 1877 3738 1891 3739 1877 3739 1879 3739 1879 3740 1877 3740 1878 3740 1879 3741 1878 3741 1893 3741 1893 3742 1878 3742 1895 3742 2194 3743 2195 3743 1880 3743 1880 3744 2195 3744 1875 3744 1880 3745 1875 3745 1881 3745 1881 3746 1875 3746 1878 3746 1881 3747 1878 3747 1882 3747 1882 3748 1878 3748 1877 3748 1882 3749 1877 3749 1883 3749 1883 3750 1877 3750 2038 3750 2192 3751 2198 3751 1898 3751 1898 3752 2198 3752 1884 3752 1898 3753 1884 3753 1885 3753 1885 3754 1884 3754 1887 3754 1885 3755 1887 3755 1886 3755 1886 3756 1887 3756 1888 3756 1886 3757 1888 3757 1897 3757 1897 3758 1888 3758 2308 3758 1897 3759 2308 3759 1889 3759 1889 3760 2308 3760 2309 3760 2077 3761 1890 3761 2326 3761 2326 3762 1890 3762 1891 3762 2326 3763 1891 3763 1892 3763 1892 3764 1891 3764 1879 3764 1892 3765 1879 3765 1894 3765 1894 3766 1879 3766 1893 3766 1894 3767 1893 3767 2324 3767 2324 3768 1893 3768 1895 3768 2324 3769 1895 3769 2323 3769 2323 3770 1895 3770 1876 3770 1896 3771 2192 3771 1901 3771 1901 3772 2192 3772 1898 3772 1901 3773 1898 3773 1902 3773 1889 3774 2031 3774 1897 3774 1897 3775 2031 3775 1904 3775 1897 3776 1904 3776 1886 3776 1886 3777 1904 3777 1902 3777 1886 3778 1902 3778 1885 3778 1885 3779 1902 3779 1898 3779 1899 3780 1896 3780 1900 3780 1900 3781 1896 3781 1901 3781 1900 3782 1901 3782 2320 3782 2320 3783 1901 3783 1902 3783 2320 3784 1902 3784 1903 3784 1903 3785 1902 3785 1904 3785 1903 3786 1904 3786 2322 3786 2322 3787 1904 3787 2031 3787 2003 3788 2063 3788 2062 3788 2003 3789 2062 3789 1905 3789 1905 3790 2062 3790 1906 3790 1905 3791 1906 3791 1909 3791 2053 3792 1907 3792 2042 3792 2042 3793 1907 3793 1909 3793 2042 3794 1909 3794 1908 3794 1908 3795 1909 3795 1906 3795 2009 3796 2008 3796 1910 3796 1910 3797 2008 3797 2007 3797 1910 3798 2007 3798 2053 3798 2053 3799 2007 3799 2006 3799 2053 3800 2006 3800 1907 3800 2009 3801 1910 3801 1911 3801 1911 3802 1910 3802 2052 3802 1911 3803 2052 3803 1912 3803 1912 3804 2052 3804 2059 3804 1912 3805 2059 3805 2011 3805 2011 3806 2059 3806 1913 3806 1913 3807 2059 3807 1915 3807 1913 3808 1915 3808 1914 3808 1914 3809 1915 3809 1998 3809 1998 3810 1915 3810 2058 3810 1989 3811 1917 3811 1924 3811 1924 3812 1917 3812 1923 3812 1989 3813 1916 3813 1917 3813 1917 3814 1916 3814 1988 3814 1917 3815 1988 3815 2048 3815 2048 3816 1988 3816 1919 3816 1988 3817 1918 3817 1919 3817 1919 3818 1918 3818 1920 3818 1919 3819 1920 3819 2055 3819 2055 3820 1920 3820 1999 3820 2055 3821 1999 3821 1921 3821 1921 3822 1999 3822 1998 3822 1921 3823 1998 3823 2058 3823 1994 3824 1995 3824 1922 3824 1922 3825 1995 3825 1996 3825 1922 3826 1996 3826 2044 3826 2044 3827 1996 3827 1997 3827 2044 3828 1997 3828 1923 3828 1923 3829 1997 3829 1993 3829 1923 3830 1993 3830 1924 3830 1925 3831 1926 3831 2184 3831 2184 3832 1926 3832 1932 3832 1927 3833 2186 3833 2185 3833 1927 3834 2185 3834 2028 3834 2028 3835 2185 3835 1928 3835 2028 3836 1928 3836 2027 3836 2027 3837 1928 3837 1929 3837 2027 3838 1929 3838 2025 3838 2025 3839 1929 3839 1930 3839 1930 3840 1929 3840 2173 3840 1930 3841 2173 3841 1931 3841 1931 3842 2173 3842 2184 3842 1931 3843 2184 3843 1932 3843 1926 3844 1925 3844 2183 3844 1926 3845 2183 3845 2032 3845 2032 3846 2183 3846 1933 3846 2032 3847 1933 3847 1934 3847 1934 3848 1933 3848 2172 3848 1934 3849 2172 3849 2029 3849 2029 3850 2172 3850 1935 3850 1935 3851 2172 3851 2182 3851 1935 3852 2182 3852 1936 3852 1936 3853 2182 3853 2180 3853 1936 3854 2180 3854 1937 3854 2186 3855 1927 3855 2189 3855 2189 3856 1927 3856 1938 3856 1937 3857 2180 3857 1943 3857 1943 3858 2180 3858 2179 3858 2071 3859 1939 3859 1940 3859 2071 3860 1940 3860 2020 3860 2020 3861 1940 3861 2171 3861 2020 3862 2171 3862 2016 3862 2016 3863 2171 3863 2191 3863 2016 3864 2191 3864 2018 3864 2018 3865 2191 3865 1941 3865 1941 3866 2191 3866 2190 3866 1941 3867 2190 3867 1942 3867 1942 3868 2190 3868 2189 3868 1942 3869 2189 3869 1938 3869 1943 3870 2179 3870 1945 3870 1943 3871 1945 3871 1944 3871 1944 3872 1945 3872 1946 3872 1944 3873 1946 3873 2037 3873 2037 3874 1946 3874 2175 3874 2037 3875 2175 3875 2036 3875 2036 3876 2175 3876 1947 3876 1947 3877 2175 3877 2174 3877 1947 3878 2174 3878 1948 3878 1948 3879 2174 3879 2187 3879 1948 3880 2187 3880 2073 3880 2073 3881 2187 3881 2071 3881 2071 3882 2187 3882 1939 3882 1949 3883 1954 3883 1765 3883 1765 3884 1954 3884 1950 3884 1765 3885 1950 3885 1951 3885 1951 3886 1950 3886 1952 3886 1951 3887 1952 3887 1953 3887 1953 3888 1952 3888 2021 3888 1953 3889 2021 3889 1768 3889 1768 3890 2021 3890 2022 3890 1768 3891 2022 3891 1769 3891 1949 3892 1766 3892 1954 3892 1954 3893 1766 3893 1955 3893 1954 3894 1955 3894 1956 3894 1956 3895 1955 3895 1957 3895 1956 3896 1957 3896 2072 3896 2072 3897 1957 3897 1958 3897 2072 3898 1958 3898 2075 3898 1775 3899 2066 3899 1959 3899 1959 3900 2066 3900 2075 3900 1959 3901 2075 3901 1960 3901 1960 3902 2075 3902 1958 3902 1966 3903 1964 3903 1967 3903 1734 3904 1962 3904 1961 3904 1961 3905 1962 3905 1963 3905 1967 3906 1964 3906 1965 3906 1964 3907 1725 3907 1965 3907 1965 3908 1725 3908 1732 3908 1965 3909 1732 3909 1963 3909 1963 3910 1732 3910 1731 3910 1963 3911 1731 3911 1961 3911 1966 3912 1967 3912 1968 3912 1968 3913 1967 3913 2074 3913 1968 3914 2074 3914 1742 3914 1969 3915 1749 3915 2074 3915 2074 3916 1749 3916 1741 3916 2074 3917 1741 3917 1742 3917 1969 3918 2076 3918 1749 3918 1749 3919 2076 3919 1970 3919 1749 3920 1970 3920 1971 3920 1746 3921 2045 3921 1714 3921 1714 3922 2045 3922 2046 3922 1714 3923 2046 3923 1712 3923 2046 3924 2047 3924 1712 3924 1712 3925 2047 3925 2049 3925 1712 3926 2049 3926 1972 3926 1972 3927 2049 3927 1973 3927 1972 3928 1973 3928 1975 3928 1975 3929 1973 3929 1974 3929 1975 3930 1974 3930 1707 3930 1707 3931 1974 3931 1976 3931 1707 3932 1976 3932 1710 3932 1710 3933 1976 3933 1977 3933 1977 3934 1976 3934 1978 3934 1977 3935 1978 3935 1720 3935 1978 3936 2056 3936 1720 3936 1720 3937 2056 3937 2054 3937 1720 3938 2054 3938 1699 3938 1699 3939 2054 3939 2057 3939 1699 3940 2057 3940 1700 3940 2043 3941 1705 3941 1691 3941 2043 3942 1691 3942 2051 3942 2051 3943 1691 3943 1690 3943 2051 3944 1690 3944 1979 3944 1979 3945 1690 3945 1688 3945 1979 3946 1688 3946 1981 3946 1682 3947 2041 3947 2040 3947 1688 3948 1980 3948 1981 3948 1981 3949 1980 3949 1692 3949 1981 3950 1692 3950 2050 3950 2050 3951 1692 3951 1982 3951 2050 3952 1982 3952 1983 3952 1983 3953 1982 3953 1679 3953 1983 3954 1679 3954 1984 3954 1984 3955 1679 3955 1985 3955 1984 3956 1985 3956 2060 3956 2060 3957 1985 3957 1682 3957 2060 3958 1682 3958 1986 3958 1986 3959 1682 3959 2040 3959 1990 3960 1987 3960 1916 3960 1916 3961 1987 3961 1988 3961 1988 3962 1987 3962 1867 3962 1988 3963 1867 3963 1918 3963 1916 3964 1989 3964 1990 3964 1990 3965 1989 3965 1924 3965 1990 3966 1924 3966 1991 3966 1991 3967 1924 3967 1993 3967 1991 3968 1993 3968 1992 3968 1992 3969 1993 3969 1997 3969 1992 3970 1997 3970 2015 3970 1994 3971 2069 3971 1995 3971 1995 3972 2069 3972 2015 3972 1995 3973 2015 3973 1996 3973 1996 3974 2015 3974 1997 3974 2001 3975 1998 3975 1999 3975 1918 3976 1867 3976 1920 3976 1920 3977 1867 3977 1865 3977 1920 3978 1865 3978 1999 3978 1999 3979 1865 3979 2000 3979 1999 3980 2000 3980 2001 3980 2002 3981 2004 3981 1905 3981 1905 3982 2004 3982 2003 3982 2003 3983 2004 3983 2064 3983 2003 3984 2064 3984 2063 3984 2002 3985 1905 3985 2035 3985 2035 3986 1905 3986 1909 3986 2035 3987 1909 3987 2033 3987 2033 3988 1909 3988 1907 3988 2033 3989 1907 3989 2005 3989 2005 3990 1907 3990 2006 3990 2005 3991 2006 3991 2284 3991 2006 3992 2007 3992 2284 3992 2284 3993 2007 3993 2008 3993 2284 3994 2008 3994 2010 3994 2008 3995 2009 3995 2010 3995 2010 3996 2009 3996 1911 3996 2010 3997 1911 3997 2286 3997 2286 3998 1911 3998 1912 3998 2286 3999 1912 3999 1862 3999 1862 4000 1912 4000 2011 4000 1862 4001 2011 4001 2012 4001 2011 4002 1913 4002 2012 4002 2012 4003 1913 4003 1914 4003 2012 4004 1914 4004 2199 4004 2069 4005 2068 4005 2017 4005 2017 4006 2068 4006 2022 4006 2014 4007 2013 4007 1990 4007 1990 4008 1991 4008 2014 4008 2014 4009 1991 4009 1992 4009 2014 4010 1992 4010 2017 4010 2017 4011 1992 4011 2015 4011 2017 4012 2015 4012 2069 4012 2022 4013 2016 4013 2017 4013 2017 4014 2016 4014 2018 4014 2017 4015 2018 4015 2298 4015 1938 4016 2019 4016 1942 4016 1942 4017 2019 4017 2298 4017 1942 4018 2298 4018 1941 4018 1941 4019 2298 4019 2018 4019 1954 4020 2071 4020 1950 4020 1950 4021 2071 4021 2020 4021 1950 4022 2020 4022 1952 4022 1952 4023 2020 4023 2016 4023 1952 4024 2016 4024 2021 4024 2021 4025 2016 4025 2022 4025 1932 4026 2309 4026 1931 4026 1931 4027 2309 4027 2023 4027 1931 4028 2023 4028 1930 4028 1930 4029 2023 4029 2025 4029 2025 4030 2023 4030 2024 4030 2025 4031 2024 4031 2027 4031 2027 4032 2024 4032 2026 4032 2027 4033 2026 4033 2028 4033 2028 4034 2026 4034 1860 4034 2028 4035 1860 4035 1927 4035 1937 4036 2077 4036 1936 4036 1936 4037 2077 4037 2030 4037 1936 4038 2030 4038 1935 4038 1935 4039 2030 4039 2029 4039 2029 4040 2030 4040 2322 4040 2029 4041 2322 4041 1934 4041 1934 4042 2322 4042 2031 4042 1934 4043 2031 4043 2032 4043 2032 4044 2031 4044 1889 4044 2032 4045 1889 4045 1926 4045 2005 4046 2285 4046 2033 4046 2033 4047 2285 4047 2312 4047 2034 4048 2064 4048 1883 4048 2064 4049 2004 4049 1883 4049 1883 4050 2004 4050 2002 4050 1883 4051 2002 4051 2312 4051 2312 4052 2002 4052 2035 4052 2312 4053 2035 4053 2033 4053 2073 4054 1967 4054 1948 4054 1948 4055 1967 4055 1965 4055 1948 4056 1965 4056 1947 4056 1947 4057 1965 4057 1963 4057 1947 4058 1963 4058 2036 4058 2036 4059 1963 4059 1962 4059 2036 4060 1962 4060 2037 4060 2037 4061 1962 4061 2034 4061 2034 4062 1883 4062 2037 4062 2037 4063 1883 4063 2038 4063 2037 4064 2038 4064 1944 4064 1944 4065 2038 4065 1890 4065 1944 4066 1890 4066 1943 4066 1700 4067 2057 4067 2039 4067 2039 4068 2057 4068 2040 4068 2039 4069 2040 4069 2041 4069 2053 4070 2042 4070 2043 4070 2043 4071 2042 4071 1908 4071 2043 4072 1908 4072 1906 4072 2044 4073 1923 4073 2045 4073 2045 4074 1923 4074 1917 4074 2045 4075 1917 4075 2046 4075 2046 4076 1917 4076 2048 4076 2046 4077 2048 4077 2047 4077 1919 4078 1973 4078 2048 4078 2048 4079 1973 4079 2049 4079 2048 4080 2049 4080 2047 4080 1981 4081 2050 4081 1979 4081 1979 4082 2050 4082 2059 4082 1979 4083 2059 4083 2051 4083 2051 4084 2059 4084 2052 4084 2051 4085 2052 4085 2043 4085 2043 4086 2052 4086 1910 4086 2043 4087 1910 4087 2053 4087 2055 4088 1976 4088 1919 4088 1919 4089 1976 4089 1974 4089 1919 4090 1974 4090 1973 4090 2057 4091 2054 4091 2055 4091 2054 4092 2056 4092 2055 4092 2055 4093 2056 4093 1978 4093 2055 4094 1978 4094 1976 4094 2055 4095 1921 4095 2057 4095 2057 4096 1921 4096 2058 4096 2057 4097 2058 4097 2040 4097 2040 4098 2058 4098 1915 4098 2040 4099 1915 4099 1986 4099 2050 4100 1983 4100 2059 4100 2059 4101 1983 4101 1984 4101 2059 4102 1984 4102 1915 4102 1915 4103 1984 4103 2060 4103 1915 4104 2060 4104 1986 4104 2061 4105 1705 4105 2043 4105 1962 4106 1734 4106 2034 4106 2034 4107 1734 4107 1704 4107 2034 4108 1704 4108 2064 4108 2043 4109 1906 4109 2061 4109 2061 4110 1906 4110 2062 4110 2061 4111 2062 4111 1704 4111 1704 4112 2062 4112 2063 4112 1704 4113 2063 4113 2064 4113 1772 4114 1971 4114 1970 4114 1772 4115 1970 4115 2065 4115 2065 4116 1970 4116 2066 4116 2065 4117 2066 4117 1775 4117 1769 4118 2022 4118 2067 4118 2067 4119 2022 4119 2068 4119 2067 4120 2068 4120 2070 4120 2070 4121 2068 4121 2069 4121 2070 4122 2069 4122 1994 4122 2045 4123 1746 4123 2044 4123 2044 4124 1746 4124 2070 4124 2044 4125 2070 4125 1922 4125 1922 4126 2070 4126 1994 4126 1954 4127 1956 4127 2071 4127 2071 4128 1956 4128 2072 4128 2076 4129 1969 4129 2073 4129 2073 4130 1969 4130 2074 4130 2073 4131 2074 4131 1967 4131 2072 4132 2075 4132 2071 4132 2071 4133 2075 4133 2066 4133 2071 4134 2066 4134 2073 4134 2073 4135 2066 4135 1970 4135 2073 4136 1970 4136 2076 4136 1943 4137 1890 4137 1937 4137 1937 4138 1890 4138 2077 4138 1932 4139 1926 4139 2309 4139 2309 4140 1926 4140 1889 4140 1927 4141 1860 4141 1938 4141 1938 4142 1860 4142 2019 4142 2079 4143 434 4143 2078 4143 2078 4144 434 4144 597 4144 1074 4145 498 4145 1075 4145 1075 4146 498 4146 540 4146 2079 4147 2078 4147 2081 4147 2079 4148 2081 4148 2080 4148 2080 4149 2081 4149 583 4149 2080 4150 583 4150 2082 4150 2082 4151 583 4151 585 4151 2082 4152 585 4152 2083 4152 2083 4153 585 4153 588 4153 2083 4154 588 4154 2084 4154 2084 4155 588 4155 2085 4155 2084 4156 2085 4156 472 4156 472 4157 2085 4157 2087 4157 472 4158 2087 4158 2086 4158 2086 4159 2087 4159 590 4159 2086 4160 590 4160 469 4160 469 4161 590 4161 2096 4161 469 4162 2096 4162 2099 4162 503 4163 2088 4163 522 4163 503 4164 522 4164 493 4164 493 4165 522 4165 533 4165 493 4166 533 4166 2090 4166 2090 4167 533 4167 2089 4167 2090 4168 2089 4168 2091 4168 2091 4169 2089 4169 2092 4169 2091 4170 2092 4170 495 4170 495 4171 2092 4171 2093 4171 495 4172 2093 4172 496 4172 496 4173 2093 4173 2094 4173 496 4174 2094 4174 2095 4174 2095 4175 2094 4175 528 4175 2095 4176 528 4176 497 4176 497 4177 528 4177 540 4177 497 4178 540 4178 498 4178 2096 4179 591 4179 2097 4179 2096 4180 2097 4180 2099 4180 2098 4181 2103 4181 2097 4181 2097 4182 2103 4182 478 4182 2097 4183 478 4183 2099 4183 2100 4184 2101 4184 512 4184 512 4185 2101 4185 510 4185 2100 4186 513 4186 2101 4186 2101 4187 513 4187 2088 4187 2101 4188 2088 4188 503 4188 2102 4189 506 4189 500 4189 2102 4190 500 4190 546 4190 546 4191 500 4191 2103 4191 546 4192 2103 4192 2098 4192 512 4193 510 4193 2105 4193 512 4194 2105 4194 2104 4194 2104 4195 2105 4195 507 4195 2104 4196 507 4196 2106 4196 507 4197 506 4197 2106 4197 2106 4198 506 4198 2102 4198 2107 4199 575 4199 2108 4199 2107 4200 2108 4200 1538 4200 599 4201 2109 4201 2110 4201 2110 4202 2109 4202 1532 4202 1538 4203 2108 4203 2111 4203 2111 4204 2108 4204 2112 4204 2111 4205 2112 4205 1523 4205 1523 4206 2112 4206 2113 4206 1523 4207 2113 4207 1524 4207 1524 4208 2113 4208 2114 4208 1524 4209 2114 4209 1526 4209 1526 4210 2114 4210 578 4210 1526 4211 578 4211 2115 4211 2115 4212 578 4212 2116 4212 2115 4213 2116 4213 2117 4213 2117 4214 2116 4214 579 4214 2117 4215 579 4215 1532 4215 1532 4216 579 4216 581 4216 1532 4217 581 4217 2110 4217 1493 4218 2132 4218 2134 4218 2181 4219 2118 4219 2178 4219 2178 4220 2118 4220 2126 4220 2178 4221 2126 4221 2119 4221 2134 4222 527 4222 1493 4222 1493 4223 527 4223 526 4223 1493 4224 526 4224 1494 4224 1494 4225 526 4225 2120 4225 1494 4226 2120 4226 1497 4226 1497 4227 2120 4227 2121 4227 1497 4228 2121 4228 1498 4228 1498 4229 2121 4229 2122 4229 1498 4230 2122 4230 2123 4230 2123 4231 2122 4231 2124 4231 2123 4232 2124 4232 2125 4232 2125 4233 2124 4233 537 4233 2125 4234 537 4234 2118 4234 2118 4235 537 4235 538 4235 2118 4236 538 4236 2126 4236 2127 4237 2128 4237 2131 4237 2131 4238 2128 4238 2129 4238 2131 4239 2129 4239 1636 4239 1647 4240 2130 4240 2222 4240 2222 4241 2130 4241 1661 4241 2222 4242 1661 4242 2131 4242 2131 4243 1661 4243 1660 4243 2131 4244 1660 4244 2127 4244 762 4245 2109 4245 602 4245 602 4246 2109 4246 599 4246 2132 4247 2133 4247 2134 4247 2134 4248 2133 4248 542 4248 415 4249 2135 4249 2136 4249 490 4250 491 4250 2137 4250 483 4251 486 4251 2137 4251 2137 4252 486 4252 487 4252 2137 4253 487 4253 490 4253 2140 4254 444 4254 2139 4254 2139 4255 444 4255 445 4255 445 4256 2138 4256 2139 4256 2139 4257 2138 4257 2141 4257 2139 4258 2141 4258 2137 4258 491 4259 475 4259 2137 4259 2137 4260 475 4260 441 4260 2137 4261 441 4261 2139 4261 2139 4262 441 4262 443 4262 2139 4263 443 4263 2140 4263 483 4264 2137 4264 481 4264 481 4265 2137 4265 2141 4265 481 4266 2141 4266 2142 4266 2142 4267 2141 4267 446 4267 2142 4268 446 4268 2143 4268 446 4269 2144 4269 2143 4269 2143 4270 2144 4270 2145 4270 2143 4271 2145 4271 2136 4271 2136 4272 2145 4272 2146 4272 2136 4273 2146 4273 415 4273 2149 4274 2147 4274 2151 4274 420 4275 421 4275 2151 4275 2151 4276 421 4276 2148 4276 2151 4277 2148 4277 2149 4277 459 4278 460 4278 2152 4278 2152 4279 460 4279 461 4279 461 4280 2150 4280 2152 4280 2152 4281 2150 4281 463 4281 2152 4282 463 4282 2151 4282 2147 4283 424 4283 2151 4283 2151 4284 424 4284 466 4284 2151 4285 466 4285 2152 4285 2152 4286 466 4286 465 4286 2152 4287 465 4287 459 4287 420 4288 2151 4288 419 4288 419 4289 2151 4289 463 4289 419 4290 463 4290 2153 4290 2153 4291 463 4291 462 4291 2153 4292 462 4292 2154 4292 2160 4293 2156 4293 2155 4293 2155 4294 2156 4294 2154 4294 2155 4295 2154 4295 468 4295 468 4296 2154 4296 462 4296 2160 4297 2157 4297 2158 4297 2158 4298 2159 4298 2160 4298 2160 4299 2159 4299 83 4299 2160 4300 83 4300 82 4300 2162 4301 2250 4301 132 4301 72 4302 2161 4302 182 4302 182 4303 2161 4303 2162 4303 182 4304 2162 4304 197 4304 197 4305 2162 4305 132 4305 2163 4306 2160 4306 182 4306 182 4307 2160 4307 82 4307 182 4308 82 4308 72 4308 172 4309 2245 4309 302 4309 2164 4310 176 4310 2165 4310 2165 4311 176 4311 172 4311 2165 4312 172 4312 2166 4312 2166 4313 172 4313 302 4313 285 4314 2160 4314 2165 4314 2165 4315 2160 4315 2163 4315 2165 4316 2163 4316 2164 4316 271 4317 2167 4317 402 4317 277 4318 2168 4318 2169 4318 2169 4319 2168 4319 271 4319 2169 4320 271 4320 395 4320 395 4321 271 4321 402 4321 2170 4322 2156 4322 382 4322 382 4323 2156 4323 2160 4323 382 4324 2160 4324 2169 4324 2169 4325 2160 4325 285 4325 2169 4326 285 4326 277 4326 358 4327 2240 4327 372 4327 372 4328 2240 4328 2156 4328 372 4329 2156 4329 371 4329 371 4330 2156 4330 2170 4330 2171 4331 1940 4331 544 4331 544 4332 1940 4332 1939 4332 2172 4333 1933 4333 2181 4333 1928 4334 1538 4334 1929 4334 1929 4335 1538 4335 2173 4335 2174 4336 2175 4336 517 4336 517 4337 2175 4337 1946 4337 517 4338 1946 4338 2176 4338 2176 4339 1946 4339 1945 4339 2176 4340 1945 4340 2177 4340 2177 4341 1945 4341 2179 4341 2177 4342 2179 4342 2178 4342 2178 4343 2179 4343 2180 4343 2178 4344 2180 4344 2181 4344 2181 4345 2180 4345 2182 4345 2181 4346 2182 4346 2172 4346 1933 4347 2183 4347 2181 4347 2181 4348 2183 4348 1925 4348 2181 4349 1925 4349 1538 4349 1538 4350 1925 4350 2184 4350 1538 4351 2184 4351 2173 4351 1928 4352 2185 4352 1538 4352 1538 4353 2185 4353 2186 4353 1538 4354 2186 4354 2189 4354 2174 4355 517 4355 2187 4355 2187 4356 517 4356 516 4356 2187 4357 516 4357 1939 4357 1939 4358 516 4358 539 4358 1939 4359 539 4359 544 4359 2107 4360 1538 4360 2188 4360 2188 4361 1538 4361 2189 4361 2188 4362 2189 4362 543 4362 543 4363 2189 4363 2190 4363 543 4364 2190 4364 544 4364 544 4365 2190 4365 2191 4365 544 4366 2191 4366 2171 4366 1899 4367 2318 4367 1896 4367 1896 4368 2318 4368 2323 4368 1896 4369 2323 4369 2192 4369 2192 4370 2323 4370 2193 4370 2192 4371 2193 4371 2198 4371 2198 4372 2193 4372 2196 4372 2197 4373 1872 4373 2302 4373 2194 4374 2310 4374 2195 4374 2195 4375 2310 4375 2193 4375 2195 4376 2193 4376 1876 4376 1876 4377 2193 4377 2323 4377 2196 4378 1852 4378 2293 4378 2302 4379 2301 4379 2197 4379 2197 4380 2301 4380 2198 4380 2197 4381 2198 4381 1854 4381 1854 4382 2198 4382 2196 4382 1854 4383 2196 4383 2299 4383 2299 4384 2196 4384 2293 4384 2000 4385 2199 4385 2001 4385 2001 4386 2199 4386 1914 4386 2001 4387 1914 4387 1998 4387 893 4388 895 4388 2214 4388 893 4389 2214 4389 891 4389 1041 4390 2200 4390 2214 4390 2214 4391 2200 4391 890 4391 2214 4392 890 4392 891 4392 2206 4393 2216 4393 841 4393 841 4394 2201 4394 2206 4394 2206 4395 2201 4395 2202 4395 2206 4396 2202 4396 853 4396 853 4397 2203 4397 2206 4397 2206 4398 2203 4398 2204 4398 2206 4399 2204 4399 2205 4399 2205 4400 843 4400 2206 4400 2206 4401 843 4401 844 4401 2206 4402 844 4402 2207 4402 2260 4403 2208 4403 862 4403 862 4404 2208 4404 2206 4404 862 4405 2206 4405 845 4405 845 4406 2206 4406 2207 4406 895 4407 2209 4407 2214 4407 2214 4408 2209 4408 897 4408 2214 4409 897 4409 2210 4409 2210 4410 2211 4410 2214 4410 2214 4411 2211 4411 880 4411 2214 4412 880 4412 2212 4412 2212 4413 2213 4413 2214 4413 2214 4414 2213 4414 2215 4414 2214 4415 2215 4415 850 4415 850 4416 849 4416 2214 4416 2214 4417 849 4417 2216 4417 2214 4418 2216 4418 1612 4418 1612 4419 2216 4419 2206 4419 1612 4420 2217 4420 2214 4420 2214 4421 2217 4421 1613 4421 2214 4422 1613 4422 1615 4422 1619 4423 2218 4423 1641 4423 2219 4424 1652 4424 2225 4424 2225 4425 1615 4425 1619 4425 1619 4426 1641 4426 2225 4426 2225 4427 1641 4427 1642 4427 2225 4428 1642 4428 2219 4428 1652 4429 2220 4429 2225 4429 2225 4430 2220 4430 1651 4430 2225 4431 1651 4431 2221 4431 1647 4432 2222 4432 2223 4432 2223 4433 2222 4433 2225 4433 2223 4434 2225 4434 2224 4434 2224 4435 2225 4435 2221 4435 1615 4436 2225 4436 2214 4436 2214 4437 2225 4437 2135 4437 2214 4438 2135 4438 415 4438 2228 4439 2226 4439 2257 4439 2131 4440 1636 4440 2257 4440 2257 4441 1636 4441 2227 4441 2257 4442 2227 4442 2228 4442 2226 4443 1634 4443 2257 4443 2257 4444 1634 4444 1631 4444 2257 4445 1631 4445 1630 4445 1630 4446 2229 4446 2257 4446 2257 4447 2229 4447 1605 4447 2257 4448 1605 4448 2231 4448 1597 4449 2244 4449 2230 4449 2230 4450 2244 4450 2257 4450 2230 4451 2257 4451 1606 4451 1606 4452 2257 4452 2231 4452 827 4453 2233 4453 1596 4453 1596 4454 2233 4454 2232 4454 1593 4455 2264 4455 809 4455 1596 4456 1594 4456 827 4456 827 4457 1594 4457 1593 4457 827 4458 1593 4458 825 4458 825 4459 1593 4459 809 4459 2233 4460 2234 4460 2232 4460 2232 4461 2234 4461 828 4461 2232 4462 828 4462 831 4462 833 4463 2235 4463 831 4463 831 4464 2235 4464 2236 4464 1597 4465 2232 4465 2244 4465 2244 4466 2232 4466 831 4466 2244 4467 831 4467 2238 4467 2238 4468 831 4468 2236 4468 2238 4469 2236 4469 2237 4469 2238 4470 873 4470 2244 4470 2244 4471 873 4471 874 4471 2244 4472 874 4472 876 4472 1038 4473 405 4473 877 4473 877 4474 405 4474 2244 4474 877 4475 2244 4475 2239 4475 2239 4476 2244 4476 876 4476 2240 4477 358 4477 2244 4477 2244 4478 358 4478 2243 4478 204 4479 2247 4479 2241 4479 204 4480 2241 4480 2167 4480 2167 4481 2241 4481 2242 4481 2167 4482 2242 4482 402 4482 2243 4483 313 4483 2244 4483 2244 4484 313 4484 312 4484 2244 4485 312 4485 311 4485 2252 4486 2251 4486 236 4486 2252 4487 236 4487 2245 4487 2245 4488 236 4488 2246 4488 2245 4489 2246 4489 302 4489 2247 4490 204 4490 311 4490 311 4491 204 4491 2248 4491 311 4492 2248 4492 2244 4492 2244 4493 2248 4493 202 4493 2244 4494 202 4494 2253 4494 2249 4495 136 4495 2250 4495 2250 4496 136 4496 133 4496 2250 4497 133 4497 132 4497 2251 4498 2252 4498 2253 4498 2253 4499 2252 4499 110 4499 2253 4500 110 4500 2244 4500 2244 4501 110 4501 108 4501 2244 4502 108 4502 2255 4502 2254 4503 2257 4503 12 4503 12 4504 2257 4504 2244 4504 12 4505 2244 4505 13 4505 13 4506 2244 4506 2255 4506 13 4507 2255 4507 2249 4507 2249 4508 2255 4508 107 4508 2249 4509 107 4509 136 4509 2254 4510 2256 4510 2257 4510 2257 4511 2256 4511 38 4511 2257 4512 38 4512 2157 4512 2157 4513 38 4513 2258 4513 2157 4514 2258 4514 2158 4514 2537 4515 2259 4515 2208 4515 2278 4516 2518 4516 2260 4516 2260 4517 2518 4517 2261 4517 2260 4518 2261 4518 2517 4518 2259 4519 2533 4519 2208 4519 2208 4520 2533 4520 2274 4520 2208 4521 2274 4521 2275 4521 2267 4522 2276 4522 809 4522 2517 4523 2515 4523 2260 4523 2260 4524 2515 4524 2262 4524 2260 4525 2262 4525 2208 4525 2208 4526 2262 4526 2263 4526 2208 4527 2263 4527 2537 4527 2270 4528 2530 4528 2264 4528 2264 4529 2530 4529 2529 4529 2264 4530 2529 4530 2265 4530 2265 4531 2525 4531 2264 4531 2264 4532 2525 4532 2266 4532 2264 4533 2266 4533 809 4533 809 4534 2266 4534 2524 4534 809 4535 2524 4535 2267 4535 2264 4536 2268 4536 2270 4536 2270 4537 2268 4537 2269 4537 2270 4538 2269 4538 2271 4538 2271 4539 2269 4539 2272 4539 2271 4540 2272 4540 2532 4540 2532 4541 2272 4541 2273 4541 2532 4542 2273 4542 2274 4542 2274 4543 2273 4543 1579 4543 2274 4544 1579 4544 2275 4544 2276 4545 2522 4545 809 4545 809 4546 2522 4546 2281 4546 809 4547 2281 4547 2277 4547 2260 4548 2279 4548 2278 4548 2278 4549 2279 4549 834 4549 2278 4550 834 4550 2520 4550 2520 4551 834 4551 811 4551 2520 4552 811 4552 2280 4552 2280 4553 811 4553 2282 4553 2280 4554 2282 4554 2281 4554 2281 4555 2282 4555 2283 4555 2281 4556 2283 4556 2277 4556 2005 4557 2284 4557 2285 4557 2285 4558 2284 4558 2010 4558 2285 4559 2010 4559 2286 4559 1990 4560 2013 4560 1987 4560 1987 4561 2013 4561 1867 4561 645 4562 2287 4562 1471 4562 1471 4563 2287 4563 1472 4563 2288 4564 2289 4564 652 4564 652 4565 2289 4565 2290 4565 708 4566 682 4566 633 4566 633 4567 682 4567 634 4567 2291 4568 1478 4568 640 4568 640 4569 1478 4569 1477 4569 2299 4570 2293 4570 2292 4570 2292 4571 2293 4571 2294 4571 2292 4572 2294 4572 2295 4572 2295 4573 2294 4573 2296 4573 2295 4574 2296 4574 2300 4574 2300 4575 2296 4575 2297 4575 2019 4576 2300 4576 2298 4576 2298 4577 2300 4577 2297 4577 2298 4578 2297 4578 2017 4578 1854 4579 2299 4579 1855 4579 1855 4580 2299 4580 2292 4580 1855 4581 2292 4581 1857 4581 1857 4582 2292 4582 2295 4582 1857 4583 2295 4583 1859 4583 1859 4584 2295 4584 2300 4584 1859 4585 2300 4585 1861 4585 1861 4586 2300 4586 2019 4586 2301 4587 2302 4587 2306 4587 2306 4588 2302 4588 1873 4588 2306 4589 1873 4589 2307 4589 2307 4590 1873 4590 2303 4590 2307 4591 2303 4591 2304 4591 2304 4592 2303 4592 2305 4592 2309 4593 2304 4593 2023 4593 2023 4594 2304 4594 2305 4594 2023 4595 2305 4595 2024 4595 2198 4596 2301 4596 1884 4596 1884 4597 2301 4597 2306 4597 1884 4598 2306 4598 1887 4598 1887 4599 2306 4599 2307 4599 1887 4600 2307 4600 1888 4600 1888 4601 2307 4601 2304 4601 1888 4602 2304 4602 2308 4602 2308 4603 2304 4603 2309 4603 2310 4604 2194 4604 2313 4604 2313 4605 2194 4605 1880 4605 2313 4606 1880 4606 2311 4606 2311 4607 1880 4607 1881 4607 2311 4608 1881 4608 2317 4608 2317 4609 1881 4609 1882 4609 2317 4610 1882 4610 2312 4610 2312 4611 1882 4611 1883 4611 2193 4612 2310 4612 2314 4612 2314 4613 2310 4613 2313 4613 2314 4614 2313 4614 2315 4614 2315 4615 2313 4615 2311 4615 2315 4616 2311 4616 2316 4616 2316 4617 2311 4617 2317 4617 2316 4618 2317 4618 2285 4618 2285 4619 2317 4619 2312 4619 2318 4620 1899 4620 2325 4620 2325 4621 1899 4621 1900 4621 2325 4622 1900 4622 2319 4622 2319 4623 1900 4623 2320 4623 2319 4624 2320 4624 2321 4624 2321 4625 2320 4625 1903 4625 2077 4626 2321 4626 2030 4626 2030 4627 2321 4627 1903 4627 2030 4628 1903 4628 2322 4628 2323 4629 2318 4629 2324 4629 2324 4630 2318 4630 2325 4630 2324 4631 2325 4631 1894 4631 1894 4632 2325 4632 2319 4632 1894 4633 2319 4633 1892 4633 1892 4634 2319 4634 2321 4634 1892 4635 2321 4635 2326 4635 2326 4636 2321 4636 2077 4636 2327 4637 1023 4637 2328 4637 1022 4638 1023 4638 1327 4638 1327 4639 1023 4639 2327 4639 1327 4640 2327 4640 1325 4640 2329 4641 1322 4641 2330 4641 2330 4642 1322 4642 1324 4642 2330 4643 1324 4643 2331 4643 2328 4644 2333 4644 2327 4644 2327 4645 2333 4645 2331 4645 2327 4646 2331 4646 1325 4646 1325 4647 2331 4647 1324 4647 1091 4648 2329 4648 1317 4648 1317 4649 2329 4649 2330 4649 1317 4650 2330 4650 2332 4650 2332 4651 2330 4651 2331 4651 2332 4652 2331 4652 1318 4652 1318 4653 2331 4653 2333 4653 2336 4654 2334 4654 1015 4654 1307 4655 2334 4655 2335 4655 2335 4656 2334 4656 2336 4656 2335 4657 2336 4657 2341 4657 2337 4658 1305 4658 2338 4658 2338 4659 1305 4659 2339 4659 2338 4660 2339 4660 2343 4660 1015 4661 2340 4661 2336 4661 2336 4662 2340 4662 2343 4662 2336 4663 2343 4663 2341 4663 2341 4664 2343 4664 2339 4664 1092 4665 2337 4665 2342 4665 2342 4666 2337 4666 2338 4666 2342 4667 2338 4667 1289 4667 1289 4668 2338 4668 2343 4668 1289 4669 2343 4669 1291 4669 1291 4670 2343 4670 2340 4670 1133 4671 1135 4671 2344 4671 2344 4672 1135 4672 2345 4672 2344 4673 2345 4673 2350 4673 2350 4674 2345 4674 1297 4674 2350 4675 1297 4675 2346 4675 2346 4676 1297 4676 2347 4676 2346 4677 2347 4677 2348 4677 2348 4678 2347 4678 1021 4678 2349 4679 1133 4679 1312 4679 1312 4680 1133 4680 2344 4680 1312 4681 2344 4681 1311 4681 1311 4682 2344 4682 2350 4682 1311 4683 2350 4683 1310 4683 1310 4684 2350 4684 2346 4684 1310 4685 2346 4685 1017 4685 1017 4686 2346 4686 2348 4686 2356 4687 2351 4687 1286 4687 1013 4688 2351 4688 2352 4688 2352 4689 2351 4689 2356 4689 2352 4690 2356 4690 2353 4690 2354 4691 1144 4691 2357 4691 2357 4692 1144 4692 1279 4692 2357 4693 1279 4693 2355 4693 1286 4694 1285 4694 2356 4694 2356 4695 1285 4695 2355 4695 2356 4696 2355 4696 2353 4696 2353 4697 2355 4697 1279 4697 1141 4698 2354 4698 1282 4698 1282 4699 2354 4699 2357 4699 1282 4700 2357 4700 2358 4700 2358 4701 2357 4701 2355 4701 2358 4702 2355 4702 2359 4702 2359 4703 2355 4703 1285 4703 2361 4704 2382 4704 2549 4704 2549 4705 2360 4705 2361 4705 2361 4706 2360 4706 2548 4706 2361 4707 2548 4707 2594 4707 2548 4708 2546 4708 2594 4708 2594 4709 2546 4709 2544 4709 2594 4710 2544 4710 2362 4710 2544 4711 2363 4711 2362 4711 2362 4712 2363 4712 2364 4712 2362 4713 2364 4713 2598 4713 2364 4714 2365 4714 2598 4714 2598 4715 2365 4715 2366 4715 2598 4716 2366 4716 2368 4716 2366 4717 2367 4717 2368 4717 2368 4718 2367 4718 2540 4718 2368 4719 2540 4719 2599 4719 2599 4720 2540 4720 2568 4720 2599 4721 2568 4721 2600 4721 2600 4722 2568 4722 2369 4722 2600 4723 2369 4723 2372 4723 2369 4724 2370 4724 2372 4724 2372 4725 2370 4725 2371 4725 2372 4726 2371 4726 2373 4726 2371 4727 2374 4727 2373 4727 2373 4728 2374 4728 2564 4728 2373 4729 2564 4729 2375 4729 2564 4730 2561 4730 2375 4730 2375 4731 2561 4731 2376 4731 2375 4732 2376 4732 2378 4732 2376 4733 2377 4733 2378 4733 2378 4734 2377 4734 2558 4734 2378 4735 2558 4735 2379 4735 2558 4736 2380 4736 2379 4736 2379 4737 2380 4737 2556 4737 2379 4738 2556 4738 2381 4738 2556 4739 2555 4739 2381 4739 2381 4740 2555 4740 2554 4740 2381 4741 2554 4741 2382 4741 2382 4742 2554 4742 2552 4742 2382 4743 2552 4743 2549 4743 314 4744 2383 4744 2403 4744 334 4745 2384 4745 2400 4745 377 4746 2386 4746 2391 4746 2391 4747 2386 4747 2385 4747 2386 4748 352 4748 2385 4748 2385 4749 352 4749 2387 4749 2385 4750 2387 4750 2406 4750 2406 4751 2387 4751 396 4751 2406 4752 396 4752 351 4752 2388 4753 2389 4753 2579 4753 2579 4754 2389 4754 2390 4754 2579 4755 2390 4755 2391 4755 2391 4756 2390 4756 377 4756 2392 4757 2393 4757 2388 4757 2388 4758 2393 4758 2394 4758 2388 4759 2394 4759 2389 4759 325 4760 324 4760 2578 4760 2578 4761 324 4761 367 4761 2578 4762 367 4762 2392 4762 2392 4763 367 4763 366 4763 2392 4764 366 4764 2393 4764 325 4765 2578 4765 326 4765 326 4766 2578 4766 2397 4766 326 4767 2397 4767 2395 4767 2396 4768 2402 4768 2397 4768 2397 4769 2402 4769 2398 4769 2397 4770 2398 4770 2395 4770 2384 4771 332 4771 2400 4771 2400 4772 332 4772 2399 4772 2400 4773 2399 4773 2396 4773 2396 4774 2399 4774 2401 4774 2396 4775 2401 4775 2402 4775 2403 4776 2383 4776 2400 4776 2400 4777 2383 4777 2404 4777 2400 4778 2404 4778 334 4778 314 4779 2403 4779 317 4779 317 4780 2403 4780 2405 4780 317 4781 2405 4781 318 4781 351 4782 350 4782 2406 4782 2406 4783 350 4783 320 4783 2406 4784 320 4784 2405 4784 2405 4785 320 4785 319 4785 2405 4786 319 4786 318 4786 2407 4787 206 4787 2570 4787 234 4788 2417 4788 2408 4788 2412 4789 252 4789 2573 4789 2573 4790 252 4790 2410 4790 252 4791 2409 4791 2410 4791 2410 4792 2409 4792 289 4792 2410 4793 289 4793 2575 4793 2575 4794 289 4794 2411 4794 2575 4795 2411 4795 2420 4795 2580 4796 265 4796 2582 4796 2582 4797 265 4797 278 4797 2582 4798 278 4798 2573 4798 2573 4799 278 4799 2412 4799 2413 4800 263 4800 2580 4800 2580 4801 263 4801 266 4801 2580 4802 266 4802 265 4802 217 4803 256 4803 2414 4803 2414 4804 256 4804 254 4804 2414 4805 254 4805 2413 4805 2413 4806 254 4806 264 4806 2413 4807 264 4807 263 4807 217 4808 2414 4808 218 4808 218 4809 2414 4809 2415 4809 218 4810 2415 4810 220 4810 2569 4811 221 4811 2415 4811 2415 4812 221 4812 2416 4812 2415 4813 2416 4813 220 4813 2417 4814 232 4814 2408 4814 2408 4815 232 4815 231 4815 2408 4816 231 4816 2569 4816 2569 4817 231 4817 2418 4817 2569 4818 2418 4818 221 4818 2570 4819 206 4819 2408 4819 2408 4820 206 4820 235 4820 2408 4821 235 4821 234 4821 2407 4822 2570 4822 207 4822 207 4823 2570 4823 2419 4823 207 4824 2419 4824 208 4824 2420 4825 251 4825 2575 4825 2575 4826 251 4826 211 4826 2575 4827 211 4827 2419 4827 2419 4828 211 4828 210 4828 2419 4829 210 4829 208 4829 2438 4830 130 4830 2421 4830 2422 4831 2434 4831 2423 4831 148 4832 2424 4832 2428 4832 2428 4833 2424 4833 2588 4833 2424 4834 187 4834 2588 4834 2588 4835 187 4835 189 4835 2588 4836 189 4836 2441 4836 2441 4837 189 4837 188 4837 2441 4838 188 4838 2425 4838 2430 4839 2426 4839 2586 4839 2586 4840 2426 4840 2427 4840 2586 4841 2427 4841 2428 4841 2428 4842 2427 4842 148 4842 2431 4843 2429 4843 2430 4843 2430 4844 2429 4844 163 4844 2430 4845 163 4845 2426 4845 118 4846 150 4846 2574 4846 2574 4847 150 4847 162 4847 2574 4848 162 4848 2431 4848 2431 4849 162 4849 161 4849 2431 4850 161 4850 2429 4850 118 4851 2574 4851 119 4851 119 4852 2574 4852 2432 4852 119 4853 2432 4853 120 4853 2437 4854 121 4854 2432 4854 2432 4855 121 4855 2433 4855 2432 4856 2433 4856 120 4856 2434 4857 2435 4857 2423 4857 2423 4858 2435 4858 2436 4858 2423 4859 2436 4859 2437 4859 2437 4860 2436 4860 122 4860 2437 4861 122 4861 121 4861 2421 4862 130 4862 2423 4862 2423 4863 130 4863 129 4863 2423 4864 129 4864 2422 4864 2438 4865 2421 4865 2439 4865 2439 4866 2421 4866 2443 4866 2439 4867 2443 4867 2445 4867 2425 4868 2440 4868 2441 4868 2441 4869 2440 4869 2442 4869 2441 4870 2442 4870 2443 4870 2443 4871 2442 4871 2444 4871 2443 4872 2444 4872 2445 4872 15 4873 2446 4873 2463 4873 2462 4874 33 4874 2460 4874 49 4875 48 4875 2449 4875 2449 4876 48 4876 2447 4876 48 4877 88 4877 2447 4877 2447 4878 88 4878 47 4878 2447 4879 47 4879 2465 4879 2465 4880 47 4880 93 4880 2465 4881 93 4881 46 4881 2451 4882 2452 4882 2448 4882 2448 4883 2452 4883 73 4883 2448 4884 73 4884 2449 4884 2449 4885 73 4885 49 4885 2587 4886 2450 4886 2451 4886 2451 4887 2450 4887 50 4887 2451 4888 50 4888 2452 4888 25 4889 2453 4889 2589 4889 2589 4890 2453 4890 63 4890 2589 4891 63 4891 2587 4891 2587 4892 63 4892 2454 4892 2587 4893 2454 4893 2450 4893 25 4894 2589 4894 26 4894 26 4895 2589 4895 2455 4895 26 4896 2455 4896 27 4896 2457 4897 28 4897 2455 4897 2455 4898 28 4898 2456 4898 2455 4899 2456 4899 27 4899 33 4900 32 4900 2460 4900 2460 4901 32 4901 2458 4901 2460 4902 2458 4902 2457 4902 2457 4903 2458 4903 2459 4903 2457 4904 2459 4904 28 4904 2463 4905 2446 4905 2460 4905 2460 4906 2446 4906 2461 4906 2460 4907 2461 4907 2462 4907 15 4908 2463 4908 16 4908 16 4909 2463 4909 2584 4909 16 4910 2584 4910 2464 4910 46 4911 45 4911 2465 4911 2465 4912 45 4912 19 4912 2465 4913 19 4913 2584 4913 2584 4914 19 4914 18 4914 2584 4915 18 4915 2464 4915 2551 4916 2488 4916 2550 4916 2550 4917 2488 4917 2466 4917 2550 4918 2466 4918 2467 4918 2467 4919 2466 4919 2468 4919 2467 4920 2468 4920 2547 4920 2547 4921 2468 4921 2491 4921 2547 4922 2491 4922 2545 4922 2545 4923 2491 4923 2469 4923 2545 4924 2469 4924 2470 4924 2470 4925 2469 4925 2494 4925 2470 4926 2494 4926 2543 4926 2543 4927 2494 4927 2471 4927 2543 4928 2471 4928 2472 4928 2472 4929 2471 4929 2496 4929 2472 4930 2496 4930 2542 4930 2542 4931 2496 4931 2473 4931 2542 4932 2473 4932 2474 4932 2474 4933 2473 4933 2499 4933 2474 4934 2499 4934 2541 4934 2541 4935 2499 4935 2500 4935 2541 4936 2500 4936 2539 4936 2539 4937 2500 4937 2475 4937 2539 4938 2475 4938 2476 4938 2476 4939 2475 4939 2477 4939 2476 4940 2477 4940 2567 4940 2567 4941 2477 4941 2503 4941 2567 4942 2503 4942 2566 4942 2566 4943 2503 4943 2478 4943 2566 4944 2478 4944 2565 4944 2565 4945 2478 4945 2479 4945 2565 4946 2479 4946 2563 4946 2563 4947 2479 4947 2506 4947 2563 4948 2506 4948 2562 4948 2562 4949 2506 4949 2480 4949 2562 4950 2480 4950 2560 4950 2560 4951 2480 4951 2507 4951 2560 4952 2507 4952 2559 4952 2559 4953 2507 4953 2508 4953 2559 4954 2508 4954 2481 4954 2481 4955 2508 4955 2510 4955 2481 4956 2510 4956 2557 4956 2557 4957 2510 4957 2482 4957 2557 4958 2482 4958 2483 4958 2483 4959 2482 4959 2484 4959 2483 4960 2484 4960 2485 4960 2485 4961 2484 4961 2512 4961 2485 4962 2512 4962 2486 4962 2486 4963 2512 4963 2513 4963 2486 4964 2513 4964 2553 4964 2553 4965 2513 4965 2487 4965 2553 4966 2487 4966 2551 4966 2551 4967 2487 4967 2488 4967 2487 4968 2516 4968 2488 4968 2488 4969 2516 4969 2489 4969 2488 4970 2489 4970 2466 4970 2466 4971 2489 4971 2490 4971 2466 4972 2490 4972 2468 4972 2468 4973 2490 4973 2519 4973 2468 4974 2519 4974 2491 4974 2491 4975 2519 4975 2492 4975 2491 4976 2492 4976 2469 4976 2469 4977 2492 4977 2493 4977 2469 4978 2493 4978 2494 4978 2494 4979 2493 4979 2495 4979 2494 4980 2495 4980 2471 4980 2471 4981 2495 4981 2521 4981 2471 4982 2521 4982 2496 4982 2496 4983 2521 4983 2497 4983 2496 4984 2497 4984 2473 4984 2473 4985 2497 4985 2498 4985 2473 4986 2498 4986 2499 4986 2499 4987 2498 4987 2523 4987 2499 4988 2523 4988 2500 4988 2500 4989 2523 4989 2501 4989 2500 4990 2501 4990 2475 4990 2475 4991 2501 4991 2502 4991 2475 4992 2502 4992 2477 4992 2477 4993 2502 4993 2526 4993 2477 4994 2526 4994 2503 4994 2503 4995 2526 4995 2527 4995 2503 4996 2527 4996 2478 4996 2478 4997 2527 4997 2528 4997 2478 4998 2528 4998 2479 4998 2479 4999 2528 4999 2504 4999 2479 5000 2504 5000 2506 5000 2506 5001 2504 5001 2505 5001 2506 5002 2505 5002 2480 5002 2480 5003 2505 5003 2531 5003 2480 5004 2531 5004 2507 5004 2507 5005 2531 5005 2509 5005 2507 5006 2509 5006 2508 5006 2508 5007 2509 5007 2534 5007 2508 5008 2534 5008 2510 5008 2510 5009 2534 5009 2535 5009 2510 5010 2535 5010 2482 5010 2482 5011 2535 5011 2536 5011 2482 5012 2536 5012 2484 5012 2484 5013 2536 5013 2511 5013 2484 5014 2511 5014 2512 5014 2512 5015 2511 5015 2538 5015 2512 5016 2538 5016 2513 5016 2513 5017 2538 5017 2514 5017 2513 5018 2514 5018 2487 5018 2487 5019 2514 5019 2516 5019 2514 5020 2515 5020 2516 5020 2516 5021 2515 5021 2517 5021 2516 5022 2517 5022 2489 5022 2489 5023 2517 5023 2261 5023 2489 5024 2261 5024 2490 5024 2490 5025 2261 5025 2518 5025 2490 5026 2518 5026 2519 5026 2519 5027 2518 5027 2278 5027 2519 5028 2278 5028 2492 5028 2492 5029 2278 5029 2520 5029 2492 5030 2520 5030 2493 5030 2493 5031 2520 5031 2280 5031 2493 5032 2280 5032 2495 5032 2495 5033 2280 5033 2281 5033 2495 5034 2281 5034 2521 5034 2521 5035 2281 5035 2522 5035 2521 5036 2522 5036 2497 5036 2497 5037 2522 5037 2276 5037 2497 5038 2276 5038 2498 5038 2498 5039 2276 5039 2267 5039 2498 5040 2267 5040 2523 5040 2523 5041 2267 5041 2524 5041 2523 5042 2524 5042 2501 5042 2501 5043 2524 5043 2266 5043 2501 5044 2266 5044 2502 5044 2502 5045 2266 5045 2525 5045 2502 5046 2525 5046 2526 5046 2526 5047 2525 5047 2265 5047 2526 5048 2265 5048 2527 5048 2527 5049 2265 5049 2529 5049 2527 5050 2529 5050 2528 5050 2528 5051 2529 5051 2530 5051 2528 5052 2530 5052 2504 5052 2504 5053 2530 5053 2270 5053 2504 5054 2270 5054 2505 5054 2505 5055 2270 5055 2271 5055 2505 5056 2271 5056 2531 5056 2531 5057 2271 5057 2532 5057 2531 5058 2532 5058 2509 5058 2509 5059 2532 5059 2274 5059 2509 5060 2274 5060 2534 5060 2534 5061 2274 5061 2533 5061 2534 5062 2533 5062 2535 5062 2535 5063 2533 5063 2259 5063 2535 5064 2259 5064 2536 5064 2536 5065 2259 5065 2537 5065 2536 5066 2537 5066 2511 5066 2511 5067 2537 5067 2263 5067 2511 5068 2263 5068 2538 5068 2538 5069 2263 5069 2262 5069 2538 5070 2262 5070 2514 5070 2514 5071 2262 5071 2515 5071 2476 5072 2568 5072 2539 5072 2539 5073 2568 5073 2540 5073 2539 5074 2540 5074 2541 5074 2541 5075 2540 5075 2367 5075 2541 5076 2367 5076 2474 5076 2474 5077 2367 5077 2366 5077 2474 5078 2366 5078 2542 5078 2542 5079 2366 5079 2365 5079 2542 5080 2365 5080 2472 5080 2472 5081 2365 5081 2364 5081 2472 5082 2364 5082 2543 5082 2543 5083 2364 5083 2363 5083 2543 5084 2363 5084 2470 5084 2470 5085 2363 5085 2544 5085 2470 5086 2544 5086 2545 5086 2545 5087 2544 5087 2546 5087 2545 5088 2546 5088 2547 5088 2547 5089 2546 5089 2548 5089 2547 5090 2548 5090 2467 5090 2467 5091 2548 5091 2360 5091 2467 5092 2360 5092 2550 5092 2550 5093 2360 5093 2549 5093 2550 5094 2549 5094 2551 5094 2551 5095 2549 5095 2552 5095 2551 5096 2552 5096 2553 5096 2553 5097 2552 5097 2554 5097 2553 5098 2554 5098 2486 5098 2486 5099 2554 5099 2555 5099 2486 5100 2555 5100 2485 5100 2485 5101 2555 5101 2556 5101 2485 5102 2556 5102 2483 5102 2483 5103 2556 5103 2380 5103 2483 5104 2380 5104 2557 5104 2557 5105 2380 5105 2558 5105 2557 5106 2558 5106 2481 5106 2481 5107 2558 5107 2377 5107 2481 5108 2377 5108 2559 5108 2559 5109 2377 5109 2376 5109 2559 5110 2376 5110 2560 5110 2560 5111 2376 5111 2561 5111 2560 5112 2561 5112 2562 5112 2562 5113 2561 5113 2564 5113 2562 5114 2564 5114 2563 5114 2563 5115 2564 5115 2374 5115 2563 5116 2374 5116 2565 5116 2565 5117 2374 5117 2371 5117 2565 5118 2371 5118 2566 5118 2566 5119 2371 5119 2370 5119 2566 5120 2370 5120 2567 5120 2567 5121 2370 5121 2369 5121 2567 5122 2369 5122 2476 5122 2476 5123 2369 5123 2568 5123 2592 5124 2583 5124 2572 5124 2423 5125 2437 5125 2572 5125 2385 5126 2406 5126 2569 5126 2569 5127 2406 5127 2408 5127 2431 5128 2430 5128 2581 5128 2406 5129 2405 5129 2408 5129 2408 5130 2405 5130 2572 5130 2408 5131 2572 5131 2570 5131 2570 5132 2572 5132 2437 5132 2570 5133 2437 5133 2432 5133 2396 5134 2571 5134 2400 5134 2400 5135 2571 5135 2572 5135 2400 5136 2572 5136 2403 5136 2403 5137 2572 5137 2405 5137 2415 5138 2579 5138 2569 5138 2569 5139 2579 5139 2391 5139 2569 5140 2391 5140 2385 5140 2581 5141 2573 5141 2431 5141 2431 5142 2573 5142 2410 5142 2431 5143 2410 5143 2574 5143 2574 5144 2410 5144 2575 5144 2574 5145 2575 5145 2432 5145 2432 5146 2575 5146 2419 5146 2432 5147 2419 5147 2570 5147 2603 5148 2576 5148 2607 5148 2607 5149 2576 5149 2577 5149 2396 5150 2397 5150 2571 5150 2571 5151 2397 5151 2578 5151 2571 5152 2578 5152 2577 5152 2577 5153 2578 5153 2392 5153 2577 5154 2392 5154 2607 5154 2607 5155 2392 5155 2388 5155 2607 5156 2388 5156 2579 5156 2415 5157 2414 5157 2579 5157 2579 5158 2414 5158 2413 5158 2579 5159 2413 5159 2607 5159 2607 5160 2413 5160 2580 5160 2607 5161 2580 5161 2581 5161 2581 5162 2580 5162 2582 5162 2581 5163 2582 5163 2573 5163 2584 5164 2463 5164 2583 5164 2583 5165 2463 5165 2460 5165 2583 5166 2460 5166 2572 5166 2572 5167 2460 5167 2457 5167 2572 5168 2457 5168 2455 5168 2608 5169 2447 5169 2583 5169 2583 5170 2447 5170 2465 5170 2583 5171 2465 5171 2584 5171 2587 5172 2451 5172 2581 5172 2581 5173 2451 5173 2448 5173 2581 5174 2448 5174 2604 5174 2604 5175 2448 5175 2449 5175 2604 5176 2449 5176 2447 5176 2611 5177 2604 5177 2610 5177 2610 5178 2604 5178 2447 5178 2610 5179 2447 5179 2585 5179 2585 5180 2447 5180 2608 5180 2430 5181 2586 5181 2581 5181 2581 5182 2586 5182 2428 5182 2581 5183 2428 5183 2587 5183 2587 5184 2428 5184 2588 5184 2587 5185 2588 5185 2589 5185 2589 5186 2588 5186 2441 5186 2589 5187 2441 5187 2455 5187 2455 5188 2441 5188 2443 5188 2455 5189 2443 5189 2572 5189 2572 5190 2443 5190 2421 5190 2572 5191 2421 5191 2423 5191 2590 5192 2612 5192 2591 5192 2591 5193 2612 5193 2592 5193 2593 5194 2378 5194 2379 5194 2597 5195 2362 5195 2571 5195 2571 5196 2362 5196 2598 5196 2373 5197 2375 5197 2572 5197 2379 5198 2381 5198 2593 5198 2593 5199 2381 5199 2382 5199 2593 5200 2382 5200 2595 5200 2373 5201 2572 5201 2372 5201 2375 5202 2378 5202 2572 5202 2572 5203 2378 5203 2593 5203 2572 5204 2593 5204 2592 5204 2592 5205 2593 5205 2614 5205 2592 5206 2614 5206 2591 5206 2382 5207 2361 5207 2595 5207 2595 5208 2361 5208 2594 5208 2595 5209 2594 5209 2616 5209 2616 5210 2594 5210 2362 5210 2616 5211 2362 5211 2596 5211 2596 5212 2362 5212 2597 5212 2598 5213 2368 5213 2571 5213 2571 5214 2368 5214 2599 5214 2571 5215 2599 5215 2572 5215 2572 5216 2599 5216 2600 5216 2572 5217 2600 5217 2372 5217 2577 5218 2601 5218 2571 5218 2571 5219 2601 5219 2602 5219 2571 5220 2602 5220 2597 5220 2607 5221 2606 5221 651 5221 2607 5222 651 5222 2603 5222 2603 5223 651 5223 632 5223 2603 5224 632 5224 2576 5224 2576 5225 632 5225 2601 5225 2576 5226 2601 5226 2577 5226 2604 5227 2605 5227 2581 5227 2581 5228 2605 5228 2606 5228 2581 5229 2606 5229 2607 5229 2608 5230 2609 5230 646 5230 2608 5231 646 5231 2585 5231 2585 5232 646 5232 647 5232 2585 5233 647 5233 2610 5233 2610 5234 647 5234 649 5234 2610 5235 649 5235 2611 5235 2611 5236 649 5236 2605 5236 2611 5237 2605 5237 2604 5237 2592 5238 2613 5238 2583 5238 2583 5239 2613 5239 2609 5239 2583 5240 2609 5240 2608 5240 2614 5241 641 5241 642 5241 2614 5242 642 5242 2591 5242 2591 5243 642 5243 643 5243 2591 5244 643 5244 2590 5244 2590 5245 643 5245 644 5245 2590 5246 644 5246 2612 5246 2612 5247 644 5247 2613 5247 2612 5248 2613 5248 2592 5248 2595 5249 639 5249 2593 5249 2593 5250 639 5250 641 5250 2593 5251 641 5251 2614 5251 2597 5252 2602 5252 636 5252 2597 5253 636 5253 2596 5253 2596 5254 636 5254 2615 5254 2596 5255 2615 5255 2616 5255 2616 5256 2615 5256 639 5256 2616 5257 639 5257 2595 5257 2639 5258 2887 5258 2618 5258 2639 5259 2618 5259 2617 5259 2617 5260 2618 5260 2884 5260 2617 5261 2884 5261 2659 5261 2659 5262 2884 5262 2882 5262 2659 5263 2882 5263 2647 5263 2647 5264 2882 5264 2619 5264 2647 5265 2619 5265 2620 5265 2731 5266 2732 5266 2619 5266 2619 5267 2732 5267 2620 5267 2621 5268 2881 5268 2622 5268 2622 5269 2881 5269 2758 5269 2622 5270 2758 5270 2640 5270 2755 5271 2754 5271 2911 5271 2911 5272 2754 5272 2623 5272 2625 5273 2913 5273 2623 5273 2623 5274 2913 5274 2912 5274 2623 5275 2912 5275 2911 5275 2627 5276 2624 5276 2629 5276 2629 5277 2624 5277 2625 5277 2625 5278 2624 5278 2626 5278 2625 5279 2626 5279 2913 5279 2627 5280 2629 5280 2628 5280 2628 5281 2629 5281 2894 5281 2628 5282 2894 5282 2631 5282 2631 5283 2894 5283 2630 5283 2631 5284 2630 5284 2632 5284 2632 5285 2630 5285 2918 5285 2918 5286 2630 5286 2633 5286 2918 5287 2633 5287 2919 5287 2919 5288 2633 5288 2921 5288 2921 5289 2633 5289 2891 5289 2921 5290 2891 5290 2634 5290 2634 5291 2891 5291 2635 5291 2635 5292 2891 5292 2636 5292 2635 5293 2636 5293 2638 5293 2638 5294 2636 5294 2637 5294 2638 5295 2637 5295 2922 5295 2887 5296 2639 5296 2637 5296 2637 5297 2639 5297 2661 5297 2637 5298 2661 5298 2922 5298 2640 5299 2641 5299 2665 5299 2929 5300 2642 5300 2652 5300 2652 5301 2642 5301 2898 5301 2662 5302 2793 5302 2643 5302 2643 5303 2932 5303 2662 5303 2662 5304 2932 5304 2931 5304 2662 5305 2931 5305 2653 5305 2654 5306 2784 5306 2765 5306 2644 5307 2654 5307 2927 5307 2927 5308 2654 5308 2898 5308 2927 5309 2898 5309 2928 5309 2928 5310 2898 5310 2642 5310 2765 5311 2784 5311 2764 5311 2764 5312 2784 5312 2787 5312 2764 5313 2787 5313 2645 5313 2645 5314 2787 5314 2646 5314 2645 5315 2646 5315 2790 5315 2647 5316 2620 5316 2759 5316 2759 5317 2620 5317 2732 5317 2759 5318 2732 5318 2657 5318 2797 5319 2644 5319 2796 5319 2796 5320 2644 5320 2648 5320 2796 5321 2648 5321 2794 5321 2794 5322 2648 5322 2649 5322 2794 5323 2649 5323 2793 5323 2793 5324 2649 5324 2924 5324 2793 5325 2924 5325 2643 5325 2797 5326 2800 5326 2644 5326 2644 5327 2800 5327 2650 5327 2644 5328 2650 5328 2654 5328 2654 5329 2650 5329 2651 5329 2654 5330 2651 5330 2784 5330 2929 5331 2652 5331 2653 5331 2653 5332 2652 5332 2901 5332 2653 5333 2901 5333 2662 5333 2765 5334 2767 5334 2654 5334 2654 5335 2767 5335 2768 5335 2654 5336 2768 5336 2735 5336 2735 5337 2768 5337 2655 5337 2735 5338 2655 5338 2734 5338 2734 5339 2655 5339 2657 5339 2734 5340 2657 5340 2656 5340 2656 5341 2657 5341 2732 5341 2759 5342 2761 5342 2647 5342 2647 5343 2761 5343 2658 5343 2647 5344 2658 5344 2659 5344 2659 5345 2658 5345 2617 5345 2617 5346 2658 5346 2660 5346 2617 5347 2660 5347 2639 5347 2639 5348 2660 5348 2763 5348 2639 5349 2763 5349 2661 5349 2915 5350 2916 5350 2662 5350 2662 5351 2916 5351 2917 5351 2662 5352 2917 5352 2793 5352 2793 5353 2917 5353 2920 5353 2793 5354 2920 5354 2792 5354 2792 5355 2920 5355 2661 5355 2792 5356 2661 5356 2790 5356 2790 5357 2661 5357 2763 5357 2790 5358 2763 5358 2645 5358 2818 5359 2663 5359 2664 5359 2664 5360 2663 5360 2914 5360 2664 5361 2914 5361 2816 5361 2666 5362 2622 5362 2640 5362 2640 5363 2665 5363 2666 5363 2666 5364 2665 5364 2753 5364 2666 5365 2753 5365 2667 5365 2667 5366 2753 5366 2663 5366 2667 5367 2663 5367 2668 5367 2668 5368 2663 5368 2818 5368 2668 5369 2818 5369 2820 5369 2914 5370 2915 5370 2816 5370 2816 5371 2915 5371 2662 5371 2816 5372 2662 5372 2815 5372 2815 5373 2662 5373 2812 5373 2666 5374 2669 5374 2622 5374 2622 5375 2669 5375 2670 5375 2622 5376 2670 5376 2621 5376 2621 5377 2670 5377 2671 5377 2621 5378 2671 5378 2752 5378 2752 5379 2671 5379 2844 5379 2752 5380 2844 5380 2672 5380 2672 5381 2844 5381 2673 5381 2674 5382 2676 5382 2822 5382 2822 5383 2676 5383 2841 5383 2822 5384 2841 5384 2820 5384 2820 5385 2841 5385 2842 5385 2820 5386 2842 5386 2668 5386 2901 5387 2903 5387 2662 5387 2662 5388 2903 5388 2905 5388 2662 5389 2905 5389 2812 5389 2674 5390 2675 5390 2676 5390 2676 5391 2675 5391 2680 5391 2676 5392 2680 5392 2840 5392 2840 5393 2680 5393 2677 5393 2840 5394 2677 5394 2673 5394 2673 5395 2677 5395 2678 5395 2673 5396 2678 5396 2672 5396 2675 5397 2679 5397 2680 5397 2680 5398 2679 5398 2811 5398 2680 5399 2811 5399 2905 5399 2905 5400 2811 5400 2681 5400 2905 5401 2681 5401 2812 5401 2699 5402 2688 5402 2682 5402 2923 5403 2687 5403 2708 5403 2730 5404 2930 5404 2683 5404 2684 5405 2809 5405 2926 5405 2926 5406 2809 5406 2685 5406 2926 5407 2685 5407 2925 5407 2925 5408 2685 5408 2686 5408 2925 5409 2686 5409 2687 5409 2687 5410 2686 5410 2807 5410 2687 5411 2807 5411 2708 5411 2688 5412 2689 5412 2682 5412 2682 5413 2689 5413 2690 5413 2682 5414 2690 5414 2730 5414 2730 5415 2690 5415 2691 5415 2730 5416 2691 5416 2930 5416 2697 5417 2692 5417 2693 5417 2693 5418 2692 5418 2874 5418 2693 5419 2874 5419 2770 5419 2694 5420 2695 5420 2696 5420 2696 5421 2695 5421 2870 5421 2696 5422 2870 5422 2697 5422 2697 5423 2870 5423 2698 5423 2697 5424 2698 5424 2692 5424 2695 5425 2700 5425 2867 5425 2867 5426 2700 5426 2699 5426 2867 5427 2699 5427 2866 5427 2866 5428 2699 5428 2682 5428 2926 5429 2700 5429 2684 5429 2684 5430 2700 5430 2695 5430 2684 5431 2695 5431 2801 5431 2801 5432 2695 5432 2694 5432 2801 5433 2694 5433 2802 5433 2802 5434 2694 5434 2781 5434 2802 5435 2781 5435 2803 5435 2803 5436 2781 5436 2701 5436 2803 5437 2701 5437 2804 5437 2804 5438 2701 5438 2702 5438 2804 5439 2702 5439 2805 5439 2805 5440 2702 5440 2777 5440 2703 5441 2730 5441 2708 5441 2708 5442 2730 5442 2683 5442 2708 5443 2683 5443 2923 5443 2711 5444 2776 5444 2886 5444 2886 5445 2776 5445 2706 5445 2874 5446 2704 5446 2770 5446 2770 5447 2704 5447 2705 5447 2770 5448 2705 5448 2773 5448 2773 5449 2705 5449 2883 5449 2773 5450 2883 5450 2706 5450 2706 5451 2883 5451 2885 5451 2706 5452 2885 5452 2886 5452 2890 5453 2707 5453 2708 5453 2708 5454 2707 5454 2709 5454 2708 5455 2709 5455 2703 5455 2708 5456 2710 5456 2890 5456 2890 5457 2710 5457 2805 5457 2890 5458 2805 5458 2711 5458 2711 5459 2805 5459 2777 5459 2711 5460 2777 5460 2776 5460 2830 5461 2852 5461 2715 5461 2864 5462 2712 5462 2730 5462 2730 5463 2712 5463 2863 5463 2730 5464 2863 5464 2682 5464 2865 5465 2864 5465 2825 5465 2825 5466 2864 5466 2730 5466 2825 5467 2730 5467 2826 5467 2826 5468 2730 5468 2828 5468 2825 5469 2713 5469 2865 5469 2865 5470 2713 5470 2837 5470 2865 5471 2837 5471 2869 5471 2869 5472 2837 5472 2836 5472 2869 5473 2836 5473 2714 5473 2714 5474 2836 5474 2834 5474 2714 5475 2834 5475 2880 5475 2880 5476 2834 5476 2878 5476 2834 5477 2832 5477 2849 5477 2849 5478 2832 5478 2715 5478 2715 5479 2832 5479 2831 5479 2715 5480 2831 5480 2830 5480 2849 5481 2847 5481 2834 5481 2834 5482 2847 5482 2860 5482 2834 5483 2860 5483 2878 5483 2878 5484 2860 5484 2716 5484 2878 5485 2716 5485 2876 5485 2876 5486 2716 5486 2858 5486 2876 5487 2858 5487 2875 5487 2858 5488 2717 5488 2875 5488 2875 5489 2717 5489 2718 5489 2875 5490 2718 5490 2719 5490 2719 5491 2718 5491 2856 5491 2719 5492 2856 5492 2721 5492 2721 5493 2856 5493 2720 5493 2721 5494 2720 5494 2722 5494 2722 5495 2720 5495 2723 5495 2723 5496 2720 5496 2725 5496 2723 5497 2725 5497 2724 5497 2724 5498 2725 5498 2726 5498 2726 5499 2725 5499 2852 5499 2726 5500 2852 5500 2889 5500 2889 5501 2852 5501 2830 5501 2889 5502 2830 5502 2892 5502 2830 5503 2727 5503 2892 5503 2892 5504 2727 5504 2728 5504 2892 5505 2728 5505 2893 5505 2893 5506 2728 5506 2828 5506 2893 5507 2828 5507 2729 5507 2729 5508 2828 5508 2730 5508 2729 5509 2730 5509 2895 5509 2895 5510 2730 5510 2703 5510 2732 5511 2731 5511 2733 5511 2732 5512 2733 5512 2656 5512 2656 5513 2733 5513 2873 5513 2656 5514 2873 5514 2734 5514 2734 5515 2873 5515 2872 5515 2734 5516 2872 5516 2735 5516 2735 5517 2872 5517 2871 5517 2735 5518 2871 5518 2654 5518 2654 5519 2871 5519 2898 5519 2898 5520 2871 5520 2868 5520 2898 5521 2868 5521 2736 5521 2868 5522 2737 5522 2736 5522 2736 5523 2737 5523 2896 5523 2738 5524 2739 5524 2737 5524 2737 5525 2739 5525 2897 5525 2737 5526 2897 5526 2896 5526 2739 5527 2738 5527 2740 5527 2740 5528 2738 5528 2861 5528 2740 5529 2861 5529 2900 5529 2900 5530 2861 5530 2902 5530 2902 5531 2861 5531 2741 5531 2902 5532 2741 5532 2742 5532 2742 5533 2741 5533 2904 5533 2904 5534 2741 5534 2862 5534 2904 5535 2862 5535 2906 5535 2906 5536 2862 5536 2743 5536 2743 5537 2862 5537 2744 5537 2743 5538 2744 5538 2907 5538 2907 5539 2744 5539 2908 5539 2908 5540 2744 5540 2745 5540 2908 5541 2745 5541 2909 5541 2909 5542 2745 5542 2746 5542 2746 5543 2745 5543 2747 5543 2746 5544 2747 5544 2748 5544 2748 5545 2747 5545 2899 5545 2899 5546 2747 5546 2750 5546 2899 5547 2750 5547 2749 5547 2749 5548 2750 5548 2879 5548 2749 5549 2879 5549 2677 5549 2677 5550 2879 5550 2678 5550 2678 5551 2879 5551 2751 5551 2678 5552 2751 5552 2672 5552 2672 5553 2751 5553 2877 5553 2672 5554 2877 5554 2752 5554 2752 5555 2877 5555 2881 5555 2752 5556 2881 5556 2621 5556 2910 5557 2663 5557 2753 5557 2754 5558 2755 5558 2756 5558 2756 5559 2755 5559 2910 5559 2910 5560 2753 5560 2756 5560 2756 5561 2753 5561 2665 5561 2756 5562 2665 5562 2888 5562 2888 5563 2665 5563 2641 5563 2888 5564 2641 5564 2757 5564 2757 5565 2641 5565 2640 5565 2757 5566 2640 5566 2758 5566 2768 5567 2769 5567 2655 5567 2655 5568 2769 5568 2782 5568 2655 5569 2782 5569 2657 5569 2657 5570 2782 5570 2760 5570 2657 5571 2760 5571 2759 5571 2759 5572 2760 5572 2771 5572 2759 5573 2771 5573 2761 5573 2761 5574 2771 5574 2772 5574 2761 5575 2772 5575 2658 5575 2658 5576 2772 5576 2774 5576 2658 5577 2774 5577 2660 5577 2660 5578 2774 5578 2762 5578 2660 5579 2762 5579 2763 5579 2763 5580 2762 5580 2775 5580 2763 5581 2775 5581 2645 5581 2645 5582 2775 5582 2778 5582 2645 5583 2778 5583 2764 5583 2764 5584 2778 5584 2779 5584 2764 5585 2779 5585 2765 5585 2765 5586 2779 5586 2780 5586 2765 5587 2780 5587 2767 5587 2767 5588 2780 5588 2766 5588 2767 5589 2766 5589 2768 5589 2768 5590 2766 5590 2769 5590 2782 5591 2697 5591 2760 5591 2760 5592 2697 5592 2693 5592 2760 5593 2693 5593 2771 5593 2771 5594 2693 5594 2770 5594 2771 5595 2770 5595 2772 5595 2772 5596 2770 5596 2773 5596 2772 5597 2773 5597 2774 5597 2774 5598 2773 5598 2706 5598 2774 5599 2706 5599 2762 5599 2762 5600 2706 5600 2776 5600 2762 5601 2776 5601 2775 5601 2775 5602 2776 5602 2777 5602 2775 5603 2777 5603 2778 5603 2778 5604 2777 5604 2702 5604 2778 5605 2702 5605 2779 5605 2779 5606 2702 5606 2701 5606 2779 5607 2701 5607 2780 5607 2780 5608 2701 5608 2781 5608 2780 5609 2781 5609 2766 5609 2766 5610 2781 5610 2694 5610 2766 5611 2694 5611 2769 5611 2769 5612 2694 5612 2696 5612 2769 5613 2696 5613 2782 5613 2782 5614 2696 5614 2697 5614 2650 5615 2783 5615 2651 5615 2651 5616 2783 5616 2810 5616 2651 5617 2810 5617 2784 5617 2784 5618 2810 5618 2785 5618 2784 5619 2785 5619 2787 5619 2787 5620 2785 5620 2786 5620 2787 5621 2786 5621 2646 5621 2646 5622 2786 5622 2788 5622 2646 5623 2788 5623 2790 5623 2790 5624 2788 5624 2789 5624 2790 5625 2789 5625 2792 5625 2792 5626 2789 5626 2791 5626 2792 5627 2791 5627 2793 5627 2793 5628 2791 5628 2806 5628 2793 5629 2806 5629 2794 5629 2794 5630 2806 5630 2808 5630 2794 5631 2808 5631 2796 5631 2796 5632 2808 5632 2795 5632 2796 5633 2795 5633 2797 5633 2797 5634 2795 5634 2798 5634 2797 5635 2798 5635 2800 5635 2800 5636 2798 5636 2799 5636 2800 5637 2799 5637 2650 5637 2650 5638 2799 5638 2783 5638 2810 5639 2801 5639 2785 5639 2785 5640 2801 5640 2802 5640 2785 5641 2802 5641 2786 5641 2786 5642 2802 5642 2803 5642 2786 5643 2803 5643 2788 5643 2788 5644 2803 5644 2804 5644 2788 5645 2804 5645 2789 5645 2789 5646 2804 5646 2805 5646 2789 5647 2805 5647 2791 5647 2791 5648 2805 5648 2710 5648 2791 5649 2710 5649 2806 5649 2806 5650 2710 5650 2708 5650 2806 5651 2708 5651 2808 5651 2808 5652 2708 5652 2807 5652 2808 5653 2807 5653 2795 5653 2795 5654 2807 5654 2686 5654 2795 5655 2686 5655 2798 5655 2798 5656 2686 5656 2685 5656 2798 5657 2685 5657 2799 5657 2799 5658 2685 5658 2809 5658 2799 5659 2809 5659 2783 5659 2783 5660 2809 5660 2684 5660 2783 5661 2684 5661 2810 5661 2810 5662 2684 5662 2801 5662 2679 5663 2824 5663 2811 5663 2811 5664 2824 5664 2838 5664 2811 5665 2838 5665 2681 5665 2681 5666 2838 5666 2813 5666 2681 5667 2813 5667 2812 5667 2812 5668 2813 5668 2814 5668 2812 5669 2814 5669 2815 5669 2815 5670 2814 5670 2827 5670 2815 5671 2827 5671 2816 5671 2816 5672 2827 5672 2829 5672 2816 5673 2829 5673 2664 5673 2664 5674 2829 5674 2817 5674 2664 5675 2817 5675 2818 5675 2818 5676 2817 5676 2819 5676 2818 5677 2819 5677 2820 5677 2820 5678 2819 5678 2821 5678 2820 5679 2821 5679 2822 5679 2822 5680 2821 5680 2823 5680 2822 5681 2823 5681 2674 5681 2674 5682 2823 5682 2833 5682 2674 5683 2833 5683 2675 5683 2675 5684 2833 5684 2835 5684 2675 5685 2835 5685 2679 5685 2679 5686 2835 5686 2824 5686 2838 5687 2713 5687 2813 5687 2813 5688 2713 5688 2825 5688 2813 5689 2825 5689 2814 5689 2814 5690 2825 5690 2826 5690 2814 5691 2826 5691 2827 5691 2827 5692 2826 5692 2828 5692 2827 5693 2828 5693 2829 5693 2829 5694 2828 5694 2728 5694 2829 5695 2728 5695 2817 5695 2817 5696 2728 5696 2727 5696 2817 5697 2727 5697 2819 5697 2819 5698 2727 5698 2830 5698 2819 5699 2830 5699 2821 5699 2821 5700 2830 5700 2831 5700 2821 5701 2831 5701 2823 5701 2823 5702 2831 5702 2832 5702 2823 5703 2832 5703 2833 5703 2833 5704 2832 5704 2834 5704 2833 5705 2834 5705 2835 5705 2835 5706 2834 5706 2836 5706 2835 5707 2836 5707 2824 5707 2824 5708 2836 5708 2837 5708 2824 5709 2837 5709 2838 5709 2838 5710 2837 5710 2713 5710 2673 5711 2839 5711 2840 5711 2840 5712 2839 5712 2845 5712 2840 5713 2845 5713 2676 5713 2676 5714 2845 5714 2846 5714 2676 5715 2846 5715 2841 5715 2841 5716 2846 5716 2848 5716 2841 5717 2848 5717 2842 5717 2842 5718 2848 5718 2850 5718 2842 5719 2850 5719 2668 5719 2668 5720 2850 5720 2851 5720 2668 5721 2851 5721 2667 5721 2667 5722 2851 5722 2853 5722 2667 5723 2853 5723 2666 5723 2666 5724 2853 5724 2854 5724 2666 5725 2854 5725 2669 5725 2669 5726 2854 5726 2843 5726 2669 5727 2843 5727 2670 5727 2670 5728 2843 5728 2855 5728 2670 5729 2855 5729 2671 5729 2671 5730 2855 5730 2857 5730 2671 5731 2857 5731 2844 5731 2844 5732 2857 5732 2859 5732 2844 5733 2859 5733 2673 5733 2673 5734 2859 5734 2839 5734 2845 5735 2860 5735 2846 5735 2846 5736 2860 5736 2847 5736 2846 5737 2847 5737 2848 5737 2848 5738 2847 5738 2849 5738 2848 5739 2849 5739 2850 5739 2850 5740 2849 5740 2715 5740 2850 5741 2715 5741 2851 5741 2851 5742 2715 5742 2852 5742 2851 5743 2852 5743 2853 5743 2853 5744 2852 5744 2725 5744 2853 5745 2725 5745 2854 5745 2854 5746 2725 5746 2720 5746 2854 5747 2720 5747 2843 5747 2843 5748 2720 5748 2856 5748 2843 5749 2856 5749 2855 5749 2855 5750 2856 5750 2718 5750 2855 5751 2718 5751 2857 5751 2857 5752 2718 5752 2717 5752 2857 5753 2717 5753 2859 5753 2859 5754 2717 5754 2858 5754 2859 5755 2858 5755 2839 5755 2839 5756 2858 5756 2716 5756 2839 5757 2716 5757 2845 5757 2845 5758 2716 5758 2860 5758 2738 5759 2866 5759 2861 5759 2861 5760 2866 5760 2682 5760 2861 5761 2682 5761 2741 5761 2741 5762 2682 5762 2863 5762 2741 5763 2863 5763 2862 5763 2862 5764 2863 5764 2712 5764 2862 5765 2712 5765 2744 5765 2744 5766 2712 5766 2864 5766 2744 5767 2864 5767 2745 5767 2745 5768 2864 5768 2865 5768 2866 5769 2738 5769 2737 5769 2866 5770 2737 5770 2867 5770 2867 5771 2737 5771 2868 5771 2867 5772 2868 5772 2695 5772 2747 5773 2745 5773 2869 5773 2869 5774 2745 5774 2865 5774 2871 5775 2870 5775 2868 5775 2868 5776 2870 5776 2695 5776 2714 5777 2750 5777 2869 5777 2869 5778 2750 5778 2747 5778 2870 5779 2871 5779 2872 5779 2870 5780 2872 5780 2698 5780 2698 5781 2872 5781 2873 5781 2698 5782 2873 5782 2692 5782 2692 5783 2873 5783 2733 5783 2692 5784 2733 5784 2874 5784 2874 5785 2733 5785 2731 5785 2874 5786 2731 5786 2704 5786 2875 5787 2881 5787 2877 5787 2875 5788 2877 5788 2876 5788 2876 5789 2877 5789 2751 5789 2876 5790 2751 5790 2878 5790 2878 5791 2751 5791 2879 5791 2878 5792 2879 5792 2880 5792 2880 5793 2879 5793 2750 5793 2880 5794 2750 5794 2714 5794 2619 5795 2705 5795 2731 5795 2731 5796 2705 5796 2704 5796 2881 5797 2875 5797 2758 5797 2758 5798 2875 5798 2719 5798 2758 5799 2719 5799 2721 5799 2705 5800 2619 5800 2882 5800 2705 5801 2882 5801 2883 5801 2883 5802 2882 5802 2884 5802 2883 5803 2884 5803 2885 5803 2885 5804 2884 5804 2618 5804 2885 5805 2618 5805 2886 5805 2886 5806 2618 5806 2887 5806 2886 5807 2887 5807 2711 5807 2726 5808 2754 5808 2756 5808 2726 5809 2756 5809 2724 5809 2724 5810 2756 5810 2888 5810 2724 5811 2888 5811 2723 5811 2723 5812 2888 5812 2757 5812 2723 5813 2757 5813 2722 5813 2722 5814 2757 5814 2758 5814 2722 5815 2758 5815 2721 5815 2637 5816 2890 5816 2887 5816 2887 5817 2890 5817 2711 5817 2889 5818 2623 5818 2726 5818 2726 5819 2623 5819 2754 5819 2890 5820 2637 5820 2636 5820 2890 5821 2636 5821 2707 5821 2707 5822 2636 5822 2891 5822 2707 5823 2891 5823 2709 5823 2625 5824 2623 5824 2892 5824 2892 5825 2623 5825 2889 5825 2625 5826 2892 5826 2629 5826 2629 5827 2892 5827 2893 5827 2629 5828 2893 5828 2894 5828 2894 5829 2893 5829 2729 5829 2894 5830 2729 5830 2630 5830 2630 5831 2729 5831 2895 5831 2630 5832 2895 5832 2633 5832 2633 5833 2895 5833 2703 5833 2633 5834 2703 5834 2891 5834 2891 5835 2703 5835 2709 5835 2896 5836 2897 5836 2736 5836 2736 5837 2897 5837 2739 5837 2736 5838 2739 5838 2898 5838 2898 5839 2739 5839 2652 5839 2748 5840 2680 5840 2746 5840 2746 5841 2680 5841 2909 5841 2748 5842 2899 5842 2680 5842 2680 5843 2899 5843 2749 5843 2680 5844 2749 5844 2677 5844 2739 5845 2740 5845 2652 5845 2652 5846 2740 5846 2900 5846 2652 5847 2900 5847 2901 5847 2900 5848 2902 5848 2901 5848 2901 5849 2902 5849 2742 5849 2901 5850 2742 5850 2903 5850 2742 5851 2904 5851 2903 5851 2903 5852 2904 5852 2906 5852 2903 5853 2906 5853 2905 5853 2906 5854 2743 5854 2905 5854 2905 5855 2743 5855 2907 5855 2905 5856 2907 5856 2680 5856 2680 5857 2907 5857 2908 5857 2680 5858 2908 5858 2909 5858 2914 5859 2663 5859 2910 5859 2910 5860 2755 5860 2914 5860 2914 5861 2755 5861 2911 5861 2914 5862 2911 5862 2912 5862 2912 5863 2913 5863 2914 5863 2914 5864 2913 5864 2626 5864 2914 5865 2626 5865 2915 5865 2626 5866 2624 5866 2915 5866 2915 5867 2624 5867 2627 5867 2915 5868 2627 5868 2916 5868 2627 5869 2628 5869 2916 5869 2916 5870 2628 5870 2631 5870 2916 5871 2631 5871 2917 5871 2631 5872 2632 5872 2917 5872 2917 5873 2632 5873 2918 5873 2917 5874 2918 5874 2920 5874 2918 5875 2919 5875 2920 5875 2920 5876 2919 5876 2921 5876 2920 5877 2921 5877 2661 5877 2661 5878 2921 5878 2634 5878 2661 5879 2634 5879 2922 5879 2922 5880 2634 5880 2635 5880 2922 5881 2635 5881 2638 5881 2683 5882 2643 5882 2923 5882 2923 5883 2643 5883 2924 5883 2923 5884 2924 5884 2687 5884 2687 5885 2924 5885 2649 5885 2687 5886 2649 5886 2925 5886 2925 5887 2649 5887 2648 5887 2925 5888 2648 5888 2926 5888 2926 5889 2648 5889 2644 5889 2926 5890 2644 5890 2700 5890 2700 5891 2644 5891 2927 5891 2700 5892 2927 5892 2699 5892 2699 5893 2927 5893 2928 5893 2699 5894 2928 5894 2688 5894 2688 5895 2928 5895 2642 5895 2688 5896 2642 5896 2689 5896 2689 5897 2642 5897 2929 5897 2689 5898 2929 5898 2690 5898 2690 5899 2929 5899 2653 5899 2690 5900 2653 5900 2691 5900 2691 5901 2653 5901 2931 5901 2691 5902 2931 5902 2930 5902 2930 5903 2931 5903 2932 5903 2930 5904 2932 5904 2683 5904 2683 5905 2932 5905 2643 5905 3892 5906 3888 5906 3014 5906 3014 5907 3888 5907 4072 5907 4067 5908 3915 5908 4068 5908 4068 5909 3915 5909 3012 5909 2946 5910 2947 5910 2933 5910 2933 5911 2947 5911 3748 5911 2933 5912 3748 5912 2934 5912 2934 5913 3748 5913 2935 5913 2934 5914 2935 5914 4109 5914 4109 5915 2935 5915 2936 5915 4109 5916 2936 5916 4108 5916 4108 5917 2936 5917 2938 5917 4108 5918 2938 5918 2937 5918 2937 5919 2938 5919 3741 5919 2937 5920 3741 5920 2939 5920 2939 5921 3741 5921 3742 5921 2939 5922 3742 5922 4111 5922 4111 5923 3742 5923 2940 5923 4111 5924 2940 5924 2941 5924 2941 5925 2940 5925 2942 5925 2941 5926 2942 5926 2943 5926 2943 5927 2942 5927 3743 5927 2943 5928 3743 5928 2944 5928 2944 5929 3743 5929 3745 5929 2944 5930 3745 5930 2945 5930 2945 5931 3745 5931 3747 5931 2945 5932 3747 5932 2946 5932 2946 5933 3747 5933 2947 5933 2960 5934 2948 5934 2949 5934 2949 5935 2948 5935 2950 5935 2949 5936 2950 5936 2951 5936 2951 5937 2950 5937 2953 5937 2951 5938 2953 5938 2952 5938 2952 5939 2953 5939 3752 5939 2952 5940 3752 5940 2954 5940 2954 5941 3752 5941 2955 5941 2954 5942 2955 5942 4103 5942 4103 5943 2955 5943 2956 5943 4103 5944 2956 5944 2957 5944 2957 5945 2956 5945 3754 5945 2957 5946 3754 5946 2958 5946 2958 5947 3754 5947 3755 5947 2958 5948 3755 5948 4105 5948 4105 5949 3755 5949 3756 5949 4105 5950 3756 5950 4106 5950 4106 5951 3756 5951 3758 5951 4106 5952 3758 5952 4107 5952 4107 5953 3758 5953 3760 5953 4107 5954 3760 5954 2959 5954 2959 5955 3760 5955 3762 5955 2959 5956 3762 5956 2960 5956 2960 5957 3762 5957 2948 5957 2971 5958 3781 5958 2961 5958 2961 5959 3781 5959 2962 5959 2961 5960 2962 5960 2963 5960 2963 5961 2962 5961 3765 5961 2963 5962 3765 5962 2964 5962 2964 5963 3765 5963 3766 5963 2964 5964 3766 5964 2965 5964 2965 5965 3766 5965 3767 5965 2965 5966 3767 5966 2966 5966 2966 5967 3767 5967 3769 5967 2966 5968 3769 5968 4099 5968 4099 5969 3769 5969 2967 5969 4099 5970 2967 5970 4102 5970 4102 5971 2967 5971 3772 5971 4102 5972 3772 5972 2968 5972 2968 5973 3772 5973 3773 5973 2968 5974 3773 5974 2969 5974 2969 5975 3773 5975 3774 5975 2969 5976 3774 5976 2970 5976 2970 5977 3774 5977 3776 5977 2970 5978 3776 5978 4100 5978 4100 5979 3776 5979 3778 5979 4100 5980 3778 5980 2971 5980 2971 5981 3778 5981 3781 5981 2972 5982 2982 5982 4098 5982 4098 5983 2982 5983 3782 5983 4098 5984 3782 5984 4094 5984 4094 5985 3782 5985 3783 5985 4094 5986 3783 5986 2973 5986 2973 5987 3783 5987 3784 5987 2973 5988 3784 5988 4095 5988 4095 5989 3784 5989 2974 5989 4095 5990 2974 5990 4093 5990 4093 5991 2974 5991 2976 5991 4093 5992 2976 5992 2975 5992 2975 5993 2976 5993 3789 5993 2975 5994 3789 5994 2977 5994 2977 5995 3789 5995 3791 5995 2977 5996 3791 5996 2978 5996 2978 5997 3791 5997 3792 5997 2978 5998 3792 5998 2979 5998 2979 5999 3792 5999 2980 5999 2979 6000 2980 6000 4096 6000 4096 6001 2980 6001 2981 6001 4096 6002 2981 6002 4097 6002 4097 6003 2981 6003 3795 6003 4097 6004 3795 6004 2972 6004 2972 6005 3795 6005 2982 6005 2993 6006 2983 6006 4087 6006 4087 6007 2983 6007 2984 6007 4087 6008 2984 6008 2985 6008 2985 6009 2984 6009 3799 6009 2985 6010 3799 6010 4088 6010 4088 6011 3799 6011 2986 6011 4088 6012 2986 6012 4089 6012 4089 6013 2986 6013 3801 6013 4089 6014 3801 6014 4085 6014 4085 6015 3801 6015 2987 6015 4085 6016 2987 6016 2988 6016 2988 6017 2987 6017 2989 6017 2988 6018 2989 6018 4086 6018 4086 6019 2989 6019 3805 6019 4086 6020 3805 6020 4091 6020 4091 6021 3805 6021 3807 6021 4091 6022 3807 6022 2990 6022 2990 6023 3807 6023 2992 6023 2990 6024 2992 6024 2991 6024 2991 6025 2992 6025 3808 6025 2991 6026 3808 6026 4090 6026 4090 6027 3808 6027 3810 6027 4090 6028 3810 6028 2993 6028 2993 6029 3810 6029 2983 6029 2994 6030 3821 6030 4078 6030 4078 6031 3821 6031 3812 6031 4078 6032 3812 6032 4079 6032 4079 6033 3812 6033 2995 6033 4079 6034 2995 6034 4080 6034 4080 6035 2995 6035 2996 6035 4080 6036 2996 6036 2997 6036 2997 6037 2996 6037 3815 6037 2997 6038 3815 6038 4077 6038 4077 6039 3815 6039 3816 6039 4077 6040 3816 6040 2998 6040 2998 6041 3816 6041 3817 6041 2998 6042 3817 6042 2999 6042 2999 6043 3817 6043 3818 6043 2999 6044 3818 6044 3000 6044 3000 6045 3818 6045 3820 6045 3000 6046 3820 6046 3002 6046 3002 6047 3820 6047 3001 6047 3002 6048 3001 6048 4081 6048 4081 6049 3001 6049 3003 6049 4081 6050 3003 6050 4082 6050 4082 6051 3003 6051 3004 6051 4082 6052 3004 6052 2994 6052 2994 6053 3004 6053 3821 6053 4075 6054 3005 6054 4074 6054 4074 6055 3005 6055 3006 6055 4071 6056 3007 6056 3008 6056 3008 6057 3007 6057 3894 6057 3009 6058 3912 6058 3049 6058 3049 6059 3912 6059 3047 6059 3053 6060 3052 6060 3010 6060 3010 6061 3052 6061 3918 6061 3915 6062 4067 6062 3920 6062 3920 6063 4067 6063 3011 6063 3920 6064 3011 6064 3918 6064 3918 6065 3011 6065 3010 6065 3912 6066 3009 6066 3910 6066 3910 6067 3009 6067 3013 6067 3910 6068 3013 6068 3012 6068 3012 6069 3013 6069 4068 6069 3892 6070 3014 6070 3015 6070 3015 6071 3014 6071 4070 6071 3015 6072 4070 6072 3894 6072 3894 6073 4070 6073 3008 6073 3005 6074 4075 6074 3016 6074 3016 6075 4075 6075 4076 6075 3016 6076 4076 6076 3888 6076 3888 6077 4076 6077 4072 6077 3020 6078 4050 6078 3017 6078 3017 6079 4050 6079 3019 6079 3017 6080 3019 6080 3018 6080 3018 6081 3019 6081 4051 6081 3018 6082 4051 6082 3136 6082 3136 6083 4051 6083 3040 6083 3231 6084 4058 6084 3020 6084 3020 6085 4058 6085 4050 6085 4065 6086 3021 6086 3024 6086 3024 6087 3021 6087 3022 6087 3021 6088 4063 6088 3022 6088 3022 6089 4063 6089 4064 6089 3022 6090 4064 6090 3230 6090 4058 6091 3231 6091 3023 6091 3023 6092 3231 6092 3230 6092 3023 6093 3230 6093 4060 6093 4060 6094 3230 6094 4064 6094 3031 6095 3029 6095 3140 6095 3140 6096 3029 6096 4065 6096 3140 6097 4065 6097 3024 6097 3033 6098 3034 6098 3025 6098 3033 6099 3025 6099 3133 6099 3133 6100 3025 6100 3026 6100 3133 6101 3026 6101 3027 6101 3027 6102 3026 6102 3028 6102 3027 6103 3028 6103 3030 6103 3030 6104 3028 6104 3029 6104 3030 6105 3029 6105 3031 6105 3032 6106 3039 6106 3033 6106 3033 6107 3039 6107 3034 6107 3043 6108 3042 6108 3035 6108 3035 6109 3042 6109 3036 6109 3035 6110 3036 6110 3037 6110 3037 6111 3036 6111 3038 6111 3037 6112 3038 6112 3135 6112 3135 6113 3038 6113 4048 6113 3135 6114 4048 6114 3032 6114 3032 6115 4048 6115 3039 6115 3136 6116 3040 6116 3041 6116 3041 6117 3040 6117 3042 6117 3041 6118 3042 6118 3043 6118 3044 6119 3288 6119 3045 6119 3044 6120 3045 6120 3046 6120 3046 6121 3045 6121 4074 6121 3046 6122 4074 6122 3006 6122 3007 6123 4071 6123 4073 6123 3007 6124 4073 6124 3897 6124 3897 6125 4073 6125 3290 6125 3897 6126 3290 6126 3899 6126 3049 6127 3047 6127 3048 6127 3049 6128 3048 6128 4066 6128 4066 6129 3048 6129 3906 6129 4066 6130 3906 6130 3272 6130 3050 6131 3921 6131 3051 6131 3050 6132 3051 6132 4069 6132 4069 6133 3051 6133 3052 6133 4069 6134 3052 6134 3053 6134 3502 6135 3491 6135 3253 6135 3562 6136 3054 6136 3055 6136 3056 6137 3434 6137 3057 6137 3569 6138 3063 6138 3058 6138 3102 6139 3055 6139 3105 6139 3059 6140 3060 6140 3061 6140 3061 6141 3060 6141 3062 6141 3061 6142 3062 6142 3063 6142 3147 6143 3057 6143 3065 6143 3569 6144 3147 6144 3064 6144 3064 6145 3147 6145 3065 6145 3064 6146 3065 6146 3844 6146 3844 6147 3065 6147 3066 6147 3067 6148 3070 6148 3078 6148 3072 6149 3846 6149 3068 6149 3068 6150 3846 6150 3069 6150 3068 6151 3069 6151 3488 6151 3078 6152 3070 6152 3245 6152 3245 6153 3070 6153 3482 6153 3245 6154 3482 6154 3071 6154 3072 6155 3073 6155 3846 6155 3846 6156 3073 6156 3079 6156 3846 6157 3079 6157 3074 6157 3246 6158 3075 6158 3076 6158 3076 6159 3075 6159 3077 6159 3076 6160 3077 6160 3069 6160 3069 6161 3077 6161 3487 6161 3069 6162 3487 6162 3488 6162 3067 6163 3078 6163 3073 6163 3073 6164 3078 6164 3848 6164 3073 6165 3848 6165 3079 6165 3081 6166 3080 6166 3243 6166 3243 6167 3080 6167 3241 6167 3597 6168 3598 6168 3088 6168 3592 6169 3081 6169 3082 6169 3082 6170 3081 6170 3243 6170 3082 6171 3243 6171 3591 6171 3591 6172 3243 6172 3233 6172 3088 6173 3598 6173 3084 6173 3598 6174 3083 6174 3084 6174 3084 6175 3083 6175 3085 6175 3084 6176 3085 6176 3232 6176 3592 6177 3593 6177 3081 6177 3081 6178 3593 6178 3086 6178 3081 6179 3086 6179 78225 6179 78225 6180 3086 6180 3087 6180 78225 6181 3087 6181 3420 6181 3420 6182 3087 6182 3597 6182 3420 6183 3597 6183 80429 6183 80429 6184 3597 6184 3088 6184 80429 6185 3088 6185 3090 6185 3633 6186 3089 6186 3088 6186 3088 6187 3089 6187 81400 6187 81400 6188 80252 6188 3088 6188 3088 6189 80252 6189 3421 6189 3088 6190 3421 6190 3090 6190 3633 6191 3088 6191 3091 6191 3091 6192 3088 6192 3134 6192 3091 6193 3134 6193 3098 6193 3092 6194 3859 6194 3093 6194 3093 6195 3859 6195 78222 6195 3093 6196 78222 6196 3089 6196 3089 6197 78222 6197 78227 6197 3089 6198 78227 6198 81400 6198 3092 6199 3628 6199 3859 6199 3859 6200 3628 6200 3629 6200 3859 6201 3629 6201 3094 6201 3094 6202 3629 6202 3630 6202 3630 6203 3095 6203 3094 6203 3094 6204 3095 6204 3096 6204 3094 6205 3096 6205 3134 6205 3134 6206 3096 6206 3097 6206 3134 6207 3097 6207 3098 6207 3267 6208 3099 6208 3240 6208 3854 6209 3240 6209 3855 6209 3855 6210 3240 6210 3099 6210 3855 6211 3099 6211 3100 6211 3834 6212 3278 6212 3837 6212 3837 6213 3278 6213 3101 6213 3837 6214 3101 6214 3838 6214 3107 6215 3704 6215 3177 6215 3105 6216 3706 6216 3707 6216 3707 6217 3709 6217 3105 6217 3105 6218 3709 6218 3111 6218 3105 6219 3111 6219 3102 6219 3103 6220 3415 6220 3118 6220 3118 6221 3415 6221 79407 6221 3704 6222 3104 6222 3177 6222 3177 6223 3104 6223 3705 6223 3177 6224 3705 6224 3105 6224 3105 6225 3705 6225 3106 6225 3105 6226 3106 6226 3706 6226 3177 6227 3118 6227 3107 6227 3107 6228 3118 6228 79407 6228 3107 6229 79407 6229 3108 6229 3108 6230 79407 6230 78209 6230 3108 6231 78209 6231 3703 6231 3703 6232 78209 6232 78239 6232 3703 6233 78239 6233 3109 6233 3109 6234 78239 6234 3111 6234 3109 6235 3111 6235 3110 6235 3110 6236 3111 6236 3709 6236 3113 6237 3670 6237 3672 6237 3662 6238 3115 6238 3112 6238 3112 6239 3115 6239 3113 6239 3112 6240 3113 6240 3673 6240 3673 6241 3113 6241 3672 6241 3117 6242 3667 6242 78282 6242 78282 6243 3667 6243 3292 6243 3292 6244 3667 6244 3668 6244 3292 6245 3668 6245 3114 6245 3662 6246 3663 6246 3115 6246 3115 6247 3663 6247 3116 6247 3115 6248 3116 6248 3118 6248 3118 6249 3116 6249 3665 6249 3118 6250 3665 6250 3117 6250 78282 6251 78448 6251 3117 6251 3117 6252 78448 6252 78446 6252 3117 6253 78446 6253 3118 6253 3118 6254 78446 6254 78094 6254 3118 6255 78094 6255 3103 6255 3063 6256 3062 6256 3058 6256 3058 6257 3062 6257 3292 6257 3058 6258 3292 6258 3113 6258 3113 6259 3292 6259 3114 6259 3113 6260 3114 6260 3670 6260 4134 6261 3124 6261 3138 6261 3217 6262 3119 6262 4127 6262 4127 6263 4128 6263 3120 6263 3120 6264 4128 6264 4129 6264 3120 6265 4129 6265 3139 6265 3139 6266 4129 6266 4132 6266 3139 6267 4132 6267 3138 6267 3138 6268 4132 6268 4133 6268 3138 6269 4133 6269 4134 6269 3131 6270 3132 6270 3122 6270 3122 6271 3132 6271 3121 6271 3122 6272 3121 6272 4121 6272 4121 6273 4123 6273 3122 6273 3122 6274 4123 6274 4124 6274 3122 6275 4124 6275 3220 6275 3220 6276 4124 6276 4125 6276 3220 6277 4125 6277 3217 6277 3217 6278 4125 6278 3123 6278 3217 6279 3123 6279 3119 6279 3124 6280 3125 6280 3138 6280 3138 6281 3125 6281 4112 6281 3138 6282 4112 6282 3225 6282 3225 6283 4112 6283 4113 6283 3225 6284 4113 6284 3224 6284 4113 6285 3126 6285 3224 6285 3224 6286 3126 6286 4115 6286 3224 6287 4115 6287 3127 6287 3127 6288 4117 6288 3224 6288 3224 6289 4117 6289 3129 6289 3224 6290 3129 6290 3128 6290 3128 6291 3129 6291 3130 6291 3128 6292 3130 6292 3131 6292 3131 6293 3130 6293 4119 6293 3131 6294 4119 6294 3132 6294 3133 6295 3027 6295 3138 6295 3035 6296 3037 6296 3134 6296 3037 6297 3135 6297 3134 6297 3134 6298 3135 6298 3032 6298 3134 6299 3032 6299 3138 6299 3138 6300 3032 6300 3033 6300 3138 6301 3033 6301 3133 6301 3084 6302 3136 6302 3088 6302 3088 6303 3136 6303 3041 6303 3088 6304 3041 6304 3134 6304 3134 6305 3041 6305 3043 6305 3134 6306 3043 6306 3035 6306 4127 6307 3120 6307 3217 6307 3217 6308 3120 6308 3022 6308 3217 6309 3022 6309 3230 6309 3231 6310 3020 6310 3137 6310 3137 6311 3020 6311 3017 6311 3137 6312 3017 6312 3084 6312 3084 6313 3017 6313 3018 6313 3084 6314 3018 6314 3136 6314 3027 6315 3030 6315 3138 6315 3138 6316 3030 6316 3031 6316 3138 6317 3031 6317 3139 6317 3139 6318 3031 6318 3140 6318 3139 6319 3140 6319 3120 6319 3120 6320 3140 6320 3024 6320 3120 6321 3024 6321 3022 6321 3141 6322 3840 6322 3102 6322 3102 6323 3840 6323 3839 6323 3102 6324 3839 6324 3055 6324 3055 6325 3839 6325 3142 6325 3055 6326 3142 6326 3101 6326 3101 6327 3142 6327 3143 6327 3101 6328 3143 6328 3838 6328 3425 6329 3165 6329 3144 6329 3057 6330 3434 6330 3144 6330 3144 6331 3434 6331 3424 6331 3144 6332 3424 6332 3425 6332 3165 6333 3145 6333 3146 6333 3146 6334 3145 6334 3428 6334 3146 6335 3428 6335 3147 6335 3147 6336 3428 6336 3429 6336 3147 6337 3429 6337 3148 6337 3148 6338 3431 6338 3147 6338 3147 6339 3431 6339 3149 6339 3147 6340 3149 6340 3057 6340 3057 6341 3149 6341 3433 6341 3057 6342 3433 6342 3056 6342 3150 6343 3554 6343 3154 6343 3055 6344 3054 6344 3105 6344 3105 6345 3054 6345 3151 6345 3105 6346 3151 6346 3150 6346 3152 6347 3558 6347 3101 6347 3101 6348 3558 6348 3153 6348 3101 6349 3153 6349 3055 6349 3055 6350 3153 6350 3560 6350 3055 6351 3560 6351 3562 6351 3554 6352 3555 6352 3154 6352 3154 6353 3555 6353 3556 6353 3154 6354 3556 6354 3101 6354 3101 6355 3556 6355 3155 6355 3101 6356 3155 6356 3152 6356 3569 6357 3058 6357 3147 6357 3147 6358 3058 6358 3113 6358 3147 6359 3113 6359 3146 6359 3146 6360 3113 6360 3115 6360 3146 6361 3115 6361 3164 6361 3156 6362 3445 6362 3287 6362 3157 6363 3289 6363 3158 6363 3158 6364 3289 6364 3287 6364 3158 6365 3287 6365 3159 6365 3159 6366 3287 6366 3445 6366 3157 6367 3160 6367 3289 6367 3289 6368 3160 6368 3161 6368 3289 6369 3161 6369 3167 6369 3167 6370 3161 6370 3162 6370 3167 6371 3162 6371 3440 6371 3163 6372 3441 6372 3164 6372 3164 6373 3441 6373 3443 6373 3165 6374 3146 6374 3144 6374 3144 6375 3146 6375 3164 6375 3144 6376 3164 6376 3287 6376 3287 6377 3164 6377 3443 6377 3287 6378 3443 6378 3156 6378 3177 6379 3170 6379 3118 6379 3118 6380 3170 6380 3186 6380 3118 6381 3186 6381 3115 6381 3115 6382 3186 6382 3166 6382 3115 6383 3166 6383 3164 6383 3164 6384 3166 6384 3167 6384 3164 6385 3167 6385 3163 6385 3163 6386 3167 6386 3440 6386 3170 6387 3172 6387 3236 6387 3236 6388 3172 6388 3544 6388 3236 6389 3544 6389 3173 6389 3547 6390 3550 6390 3235 6390 3168 6391 3551 6391 3177 6391 3177 6392 3551 6392 3169 6392 3177 6393 3169 6393 3170 6393 3170 6394 3169 6394 3171 6394 3170 6395 3171 6395 3172 6395 3173 6396 3174 6396 3236 6396 3236 6397 3174 6397 3175 6397 3236 6398 3175 6398 3235 6398 3235 6399 3175 6399 3176 6399 3235 6400 3176 6400 3547 6400 3150 6401 3154 6401 3105 6401 3105 6402 3154 6402 3235 6402 3105 6403 3235 6403 3177 6403 3177 6404 3235 6404 3550 6404 3177 6405 3550 6405 3168 6405 3178 6406 3180 6406 3179 6406 3179 6407 3180 6407 3289 6407 3179 6408 3289 6408 3455 6408 3455 6409 3289 6409 3454 6409 3178 6410 3448 6410 3180 6410 3180 6411 3448 6411 3449 6411 3180 6412 3449 6412 3200 6412 3200 6413 3449 6413 3181 6413 3200 6414 3181 6414 3182 6414 3451 6415 3183 6415 3167 6415 3167 6416 3183 6416 3184 6416 3167 6417 3184 6417 3289 6417 3289 6418 3184 6418 3453 6418 3289 6419 3453 6419 3454 6419 3191 6420 3188 6420 3236 6420 3182 6421 3451 6421 3200 6421 3200 6422 3451 6422 3167 6422 3200 6423 3167 6423 3203 6423 3203 6424 3167 6424 3166 6424 3203 6425 3166 6425 3204 6425 3204 6426 3166 6426 3186 6426 3204 6427 3186 6427 3185 6427 3185 6428 3186 6428 3170 6428 3185 6429 3170 6429 3529 6429 3529 6430 3170 6430 3187 6430 3236 6431 3188 6431 3170 6431 3170 6432 3188 6432 3538 6432 3170 6433 3538 6433 3187 6433 3529 6434 3189 6434 3185 6434 3185 6435 3189 6435 3530 6435 3185 6436 3530 6436 3205 6436 3205 6437 3530 6437 3190 6437 3205 6438 3190 6438 3532 6438 3532 6439 3534 6439 3205 6439 3205 6440 3534 6440 3535 6440 3205 6441 3535 6441 3236 6441 3236 6442 3535 6442 3536 6442 3236 6443 3536 6443 3191 6443 3192 6444 3193 6444 3122 6444 3192 6445 3122 6445 3198 6445 3194 6446 3195 6446 3180 6446 3180 6447 3195 6447 3469 6447 3180 6448 3469 6448 3196 6448 3469 6449 3197 6449 3196 6449 3196 6450 3197 6450 3458 6450 3196 6451 3458 6451 3198 6451 3463 6452 3199 6452 3200 6452 3200 6453 3199 6453 3465 6453 3200 6454 3465 6454 3180 6454 3180 6455 3465 6455 3468 6455 3180 6456 3468 6456 3194 6456 3519 6457 3224 6457 3201 6457 3201 6458 3224 6458 3202 6458 3211 6459 3526 6459 3205 6459 3522 6460 3523 6460 3208 6460 3193 6461 3463 6461 3122 6461 3122 6462 3463 6462 3200 6462 3122 6463 3200 6463 3131 6463 3131 6464 3200 6464 3203 6464 3131 6465 3203 6465 3128 6465 3128 6466 3203 6466 3204 6466 3128 6467 3204 6467 3224 6467 3224 6468 3204 6468 3185 6468 3224 6469 3185 6469 3202 6469 3202 6470 3185 6470 3528 6470 3205 6471 3526 6471 3185 6471 3185 6472 3526 6472 3206 6472 3185 6473 3206 6473 3528 6473 3522 6474 3208 6474 3519 6474 3523 6475 3207 6475 3208 6475 3208 6476 3207 6476 3209 6476 3208 6477 3209 6477 3205 6477 3205 6478 3209 6478 3210 6478 3205 6479 3210 6479 3211 6479 3212 6480 3217 6480 3213 6480 3213 6481 3217 6481 3215 6481 3213 6482 3215 6482 3471 6482 3219 6483 3474 6483 3475 6483 3475 6484 3214 6484 3219 6484 3219 6485 3214 6485 3478 6485 3219 6486 3478 6486 3215 6486 3215 6487 3478 6487 3470 6487 3215 6488 3470 6488 3471 6488 3212 6489 3216 6489 3217 6489 3217 6490 3216 6490 3218 6490 3217 6491 3218 6491 3220 6491 3220 6492 3218 6492 3472 6492 3220 6493 3472 6493 3473 6493 3198 6494 3122 6494 3196 6494 3196 6495 3122 6495 3220 6495 3196 6496 3220 6496 3219 6496 3219 6497 3220 6497 3473 6497 3219 6498 3473 6498 3474 6498 3515 6499 3221 6499 3225 6499 3225 6500 3221 6500 3222 6500 3225 6501 3222 6501 3138 6501 3138 6502 3222 6502 3504 6502 3138 6503 3504 6503 3223 6503 3513 6504 3237 6504 3512 6504 3512 6505 3237 6505 3510 6505 3519 6506 3208 6506 3224 6506 3224 6507 3208 6507 3237 6507 3224 6508 3237 6508 3225 6508 3225 6509 3237 6509 3513 6509 3225 6510 3513 6510 3515 6510 3510 6511 3237 6511 3226 6511 3226 6512 3237 6512 3249 6512 3226 6513 3249 6513 3229 6513 3223 6514 3227 6514 3249 6514 3249 6515 3227 6515 3228 6515 3249 6516 3228 6516 3229 6516 3230 6517 3231 6517 3217 6517 3217 6518 3231 6518 3137 6518 3217 6519 3137 6519 3215 6519 3215 6520 3137 6520 3234 6520 3232 6521 3233 6521 3084 6521 3084 6522 3233 6522 3243 6522 3084 6523 3243 6523 3137 6523 3137 6524 3243 6524 3076 6524 3137 6525 3076 6525 3234 6525 3234 6526 3076 6526 3069 6526 3278 6527 3277 6527 3101 6527 3101 6528 3277 6528 3276 6528 3101 6529 3276 6529 3154 6529 3154 6530 3276 6530 3275 6530 3154 6531 3275 6531 3235 6531 3235 6532 3275 6532 3274 6532 3235 6533 3274 6533 3236 6533 3236 6534 3274 6534 3270 6534 3236 6535 3270 6535 3205 6535 3205 6536 3270 6536 3271 6536 3205 6537 3271 6537 3208 6537 3208 6538 3271 6538 3273 6538 3208 6539 3273 6539 3237 6539 3237 6540 3273 6540 3238 6540 3237 6541 3238 6541 3249 6541 3249 6542 3238 6542 3239 6542 3249 6543 3239 6543 3250 6543 3250 6544 3239 6544 3267 6544 3250 6545 3267 6545 3247 6545 3247 6546 3267 6546 3240 6546 3247 6547 3240 6547 3254 6547 3241 6548 3242 6548 3243 6548 3243 6549 3242 6549 3244 6549 3243 6550 3244 6550 3076 6550 3076 6551 3244 6551 3245 6551 3076 6552 3245 6552 3246 6552 3246 6553 3245 6553 3071 6553 3258 6554 3251 6554 3247 6554 3252 6555 3502 6555 3094 6555 3094 6556 3502 6556 3253 6556 3094 6557 3253 6557 3859 6557 3859 6558 3253 6558 3864 6558 3859 6559 3864 6559 3862 6559 3862 6560 3864 6560 3248 6560 3223 6561 3249 6561 3138 6561 3138 6562 3249 6562 3250 6562 3138 6563 3250 6563 3134 6563 3134 6564 3250 6564 3247 6564 3134 6565 3247 6565 3094 6565 3094 6566 3247 6566 3251 6566 3094 6567 3251 6567 3252 6567 3491 6568 3493 6568 3253 6568 3253 6569 3493 6569 3494 6569 3253 6570 3494 6570 3254 6570 3254 6571 3494 6571 3496 6571 3254 6572 3496 6572 3255 6572 3255 6573 3256 6573 3254 6573 3254 6574 3256 6574 3257 6574 3254 6575 3257 6575 3247 6575 3247 6576 3257 6576 3500 6576 3247 6577 3500 6577 3258 6577 3902 6578 3260 6578 3259 6578 3259 6579 3260 6579 3261 6579 3259 6580 3261 6580 3987 6580 3987 6581 3261 6581 3262 6581 3262 6582 3261 6582 3955 6582 3262 6583 3955 6583 3263 6583 3263 6584 3955 6584 3264 6584 3263 6585 3264 6585 3982 6585 3982 6586 3264 6586 3953 6586 3982 6587 3953 6587 3265 6587 3824 6588 3266 6588 3857 6588 3857 6589 3099 6589 3267 6589 3824 6590 3857 6590 3906 6590 3906 6591 3857 6591 3267 6591 3906 6592 3267 6592 3272 6592 3268 6593 3831 6593 3269 6593 3269 6594 3831 6594 3921 6594 3269 6595 3921 6595 3050 6595 3267 6596 3239 6596 3272 6596 3272 6597 3239 6597 3238 6597 3272 6598 3238 6598 3273 6598 3274 6599 3050 6599 3270 6599 3270 6600 3050 6600 3272 6600 3270 6601 3272 6601 3271 6601 3271 6602 3272 6602 3273 6602 3274 6603 3275 6603 3050 6603 3050 6604 3275 6604 3276 6604 3050 6605 3276 6605 3269 6605 3269 6606 3276 6606 3277 6606 3269 6607 3277 6607 3278 6607 3978 6608 3281 6608 3279 6608 3279 6609 3281 6609 3280 6609 3279 6610 3280 6610 3859 6610 3859 6611 3280 6611 78222 6611 3281 6612 3978 6612 3976 6612 3281 6613 3976 6613 4012 6613 4012 6614 3976 6614 3974 6614 4012 6615 3974 6615 4013 6615 4013 6616 3974 6616 3284 6616 4013 6617 3284 6617 4016 6617 3972 6618 3823 6618 3283 6618 3282 6619 4016 6619 3283 6619 3283 6620 4016 6620 3284 6620 3283 6621 3284 6621 3972 6621 3961 6622 3285 6622 3962 6622 3962 6623 3285 6623 3899 6623 3962 6624 3899 6624 3290 6624 3065 6625 3057 6625 3286 6625 3286 6626 3057 6626 3144 6626 3287 6627 3288 6627 3144 6627 3144 6628 3288 6628 3044 6628 3144 6629 3044 6629 3286 6629 3286 6630 3044 6630 3885 6630 3286 6631 3885 6631 3829 6631 3287 6632 3289 6632 3288 6632 3288 6633 3289 6633 3180 6633 3288 6634 3180 6634 3290 6634 3180 6635 3196 6635 3290 6635 3290 6636 3196 6636 3219 6636 3290 6637 3219 6637 3215 6637 3846 6638 3962 6638 3069 6638 3069 6639 3962 6639 3290 6639 3069 6640 3290 6640 3234 6640 3234 6641 3290 6641 3215 6641 3936 6642 3827 6642 3867 6642 3866 6643 4005 6643 3867 6643 3867 6644 4005 6644 3935 6644 3867 6645 3935 6645 3936 6645 3292 6646 3062 6646 3291 6646 78282 6647 3292 6647 3418 6647 3418 6648 3292 6648 3291 6648 3418 6649 3291 6649 3294 6649 3294 6650 3291 6650 3293 6650 3294 6651 3293 6651 3938 6651 3294 6652 3938 6652 3296 6652 3296 6653 3938 6653 3295 6653 3296 6654 3295 6654 4010 6654 4010 6655 3295 6655 3935 6655 4010 6656 3935 6656 4005 6656 3925 6657 3833 6657 3297 6657 3297 6658 3833 6658 3951 6658 3297 6659 3951 6659 4043 6659 4043 6660 3951 6660 3298 6660 3298 6661 3951 6661 3299 6661 3298 6662 3299 6662 4038 6662 4038 6663 3299 6663 3949 6663 4038 6664 3949 6664 4040 6664 4040 6665 3949 6665 3300 6665 4040 6666 3300 6666 4042 6666 3304 6667 3922 6667 3923 6667 3301 6668 3302 6668 3305 6668 3305 6669 3302 6669 3926 6669 3557 6670 3303 6670 3929 6670 3929 6671 3303 6671 3304 6671 3929 6672 3304 6672 3926 6672 3926 6673 3304 6673 3923 6673 3926 6674 3923 6674 3305 6674 3929 6675 3930 6675 3308 6675 3306 6676 3320 6676 3314 6676 3314 6677 3320 6677 3913 6677 3314 6678 3913 6678 3315 6678 3306 6679 3553 6679 3320 6679 3320 6680 3553 6680 3307 6680 3320 6681 3307 6681 3308 6681 3308 6682 3307 6682 3309 6682 3309 6683 3561 6683 3308 6683 3308 6684 3561 6684 3310 6684 3308 6685 3310 6685 3929 6685 3929 6686 3310 6686 3559 6686 3929 6687 3559 6687 3557 6687 3303 6688 3311 6688 3304 6688 3304 6689 3311 6689 3312 6689 3304 6690 3312 6690 3919 6690 3919 6691 3312 6691 3314 6691 3919 6692 3314 6692 3313 6692 3313 6693 3314 6693 3315 6693 3316 6694 3319 6694 3543 6694 3543 6695 3319 6695 3317 6695 3543 6696 3317 6696 3545 6696 3549 6697 3548 6697 3913 6697 3913 6698 3548 6698 3546 6698 3913 6699 3546 6699 3317 6699 3317 6700 3546 6700 3318 6700 3317 6701 3318 6701 3545 6701 3316 6702 3542 6702 3319 6702 3319 6703 3542 6703 3541 6703 3319 6704 3541 6704 3320 6704 3541 6705 3552 6705 3320 6705 3320 6706 3552 6706 3321 6706 3320 6707 3321 6707 3913 6707 3913 6708 3321 6708 3322 6708 3913 6709 3322 6709 3549 6709 3319 6710 3323 6710 3539 6710 3319 6711 3539 6711 3317 6711 3317 6712 3539 6712 3324 6712 3317 6713 3324 6713 3325 6713 3325 6714 3537 6714 3317 6714 3317 6715 3537 6715 3326 6715 3317 6716 3326 6716 3914 6716 3914 6717 3326 6717 3533 6717 3323 6718 3319 6718 3540 6718 3540 6719 3319 6719 4032 6719 3540 6720 4032 6720 3327 6720 3533 6721 3328 6721 3914 6721 3914 6722 3328 6722 3531 6722 3914 6723 3531 6723 4032 6723 4032 6724 3531 6724 3329 6724 4032 6725 3329 6725 3327 6725 4032 6726 3330 6726 3331 6726 4032 6727 3331 6727 3914 6727 3914 6728 3331 6728 3527 6728 3914 6729 3527 6729 3332 6729 3332 6730 3333 6730 3914 6730 3914 6731 3333 6731 3334 6731 3914 6732 3334 6732 3335 6732 3335 6733 3334 6733 3525 6733 3330 6734 4032 6734 3518 6734 3518 6735 4032 6735 3336 6735 3518 6736 3336 6736 3520 6736 3525 6737 3524 6737 3335 6737 3335 6738 3524 6738 3521 6738 3335 6739 3521 6739 3336 6739 3336 6740 3521 6740 3337 6740 3336 6741 3337 6741 3520 6741 3506 6742 3345 6742 3507 6742 3507 6743 3345 6743 3916 6743 3507 6744 3916 6744 3508 6744 3511 6745 3338 6745 3335 6745 3335 6746 3338 6746 3339 6746 3335 6747 3339 6747 3916 6747 3916 6748 3339 6748 3509 6748 3916 6749 3509 6749 3508 6749 3506 6750 3505 6750 3345 6750 3345 6751 3505 6751 3340 6751 3345 6752 3340 6752 3336 6752 3340 6753 3517 6753 3336 6753 3336 6754 3517 6754 3516 6754 3336 6755 3516 6755 3335 6755 3335 6756 3516 6756 3514 6756 3335 6757 3514 6757 3511 6757 3497 6758 3495 6758 3353 6758 3347 6759 3341 6759 3343 6759 3343 6760 3341 6760 3342 6760 3343 6761 3342 6761 3351 6761 3351 6762 3342 6762 3499 6762 3351 6763 3499 6763 3498 6763 3495 6764 3344 6764 3353 6764 3353 6765 3344 6765 3492 6765 3353 6766 3492 6766 3345 6766 3492 6767 3503 6767 3345 6767 3345 6768 3503 6768 3501 6768 3345 6769 3501 6769 3916 6769 3916 6770 3501 6770 3346 6770 3916 6771 3346 6771 3917 6771 3917 6772 3346 6772 3911 6772 3347 6773 3343 6773 3346 6773 3346 6774 3343 6774 3909 6774 3346 6775 3909 6775 3911 6775 3903 6776 3348 6776 3350 6776 3350 6777 3348 6777 3349 6777 3350 6778 3349 6778 3351 6778 3351 6779 3349 6779 3907 6779 3351 6780 3907 6780 3343 6780 3343 6781 3907 6781 3908 6781 3343 6782 3908 6782 3352 6782 3498 6783 3497 6783 3351 6783 3351 6784 3497 6784 3353 6784 3351 6785 3353 6785 3350 6785 3350 6786 3353 6786 4022 6786 3350 6787 4022 6787 3354 6787 3898 6788 3357 6788 3355 6788 3900 6789 3356 6789 3357 6789 3357 6790 3356 6790 3358 6790 3357 6791 3358 6791 3355 6791 3485 6792 3484 6792 3991 6792 3991 6793 3484 6793 3359 6793 3991 6794 3359 6794 3989 6794 3989 6795 3359 6795 3483 6795 3355 6796 3874 6796 3989 6796 3360 6797 3898 6797 3896 6797 3896 6798 3898 6798 3355 6798 3896 6799 3355 6799 3480 6799 3480 6800 3355 6800 3361 6800 3483 6801 3362 6801 3989 6801 3989 6802 3362 6802 3481 6802 3989 6803 3481 6803 3355 6803 3355 6804 3481 6804 3363 6804 3355 6805 3363 6805 3361 6805 3485 6806 3991 6806 3486 6806 3486 6807 3991 6807 3371 6807 3486 6808 3371 6808 3891 6808 3480 6809 3490 6809 3896 6809 3896 6810 3490 6810 3489 6810 3896 6811 3489 6811 3895 6811 3895 6812 3489 6812 3486 6812 3895 6813 3486 6813 3364 6813 3364 6814 3486 6814 3891 6814 3476 6815 3372 6815 3376 6815 3991 6816 3380 6816 3365 6816 3365 6817 3366 6817 3991 6817 3991 6818 3366 6818 3367 6818 3991 6819 3367 6819 3371 6819 3371 6820 3367 6820 3368 6820 3371 6821 3368 6821 3369 6821 3369 6822 3370 6822 3371 6822 3371 6823 3370 6823 3479 6823 3371 6824 3479 6824 3376 6824 3376 6825 3479 6825 3477 6825 3376 6826 3477 6826 3476 6826 3372 6827 3373 6827 3380 6827 3380 6828 3373 6828 3374 6828 3380 6829 3374 6829 3365 6829 3376 6830 3461 6830 3460 6830 3372 6831 3380 6831 3376 6831 3376 6832 3380 6832 3381 6832 3376 6833 3381 6833 3461 6833 3467 6834 3466 6834 3384 6834 3383 6835 3375 6835 3467 6835 3460 6836 3459 6836 3376 6836 3376 6837 3459 6837 3377 6837 3376 6838 3377 6838 3383 6838 3383 6839 3377 6839 3378 6839 3383 6840 3378 6840 3375 6840 3466 6841 3464 6841 3384 6841 3384 6842 3464 6842 3379 6842 3384 6843 3379 6843 3380 6843 3380 6844 3379 6844 3462 6844 3380 6845 3462 6845 3381 6845 3383 6846 3386 6846 3382 6846 3467 6847 3384 6847 3383 6847 3383 6848 3384 6848 3385 6848 3383 6849 3385 6849 3386 6849 3382 6850 3387 6850 3383 6850 3383 6851 3387 6851 3457 6851 3383 6852 3457 6852 3398 6852 3398 6853 3457 6853 3456 6853 3452 6854 3396 6854 3388 6854 3388 6855 3396 6855 3398 6855 3388 6856 3398 6856 3389 6856 3389 6857 3398 6857 3456 6857 3452 6858 3390 6858 3396 6858 3396 6859 3390 6859 3391 6859 3396 6860 3391 6860 3384 6860 3384 6861 3391 6861 3450 6861 3384 6862 3450 6862 3385 6862 3392 6863 3442 6863 3393 6863 3393 6864 3442 6864 3394 6864 3393 6865 3394 6865 3396 6865 3392 6866 3393 6866 3444 6866 3444 6867 3393 6867 3893 6867 3444 6868 3893 6868 3446 6868 3394 6869 3395 6869 3396 6869 3396 6870 3395 6870 3439 6870 3396 6871 3439 6871 3398 6871 3398 6872 3439 6872 3397 6872 3398 6873 3397 6873 3438 6873 3438 6874 3437 6874 3398 6874 3398 6875 3437 6875 3436 6875 3398 6876 3436 6876 3893 6876 3893 6877 3436 6877 3447 6877 3893 6878 3447 6878 3446 6878 3411 6879 3432 6879 3399 6879 3432 6880 3400 6880 3399 6880 3399 6881 3400 6881 3430 6881 3399 6882 3430 6882 3393 6882 3426 6883 3401 6883 3409 6883 3409 6884 3401 6884 3402 6884 3409 6885 3402 6885 3403 6885 3403 6886 3402 6886 3435 6886 3403 6887 3435 6887 3410 6887 3430 6888 3404 6888 3393 6888 3393 6889 3404 6889 3405 6889 3393 6890 3405 6890 3893 6890 3893 6891 3405 6891 3427 6891 3893 6892 3427 6892 3889 6892 3889 6893 3427 6893 3406 6893 3426 6894 3409 6894 3427 6894 3427 6895 3409 6895 3890 6895 3427 6896 3890 6896 3406 6896 3883 6897 3884 6897 3412 6897 3412 6898 3884 6898 3407 6898 3412 6899 3407 6899 3403 6899 3403 6900 3407 6900 3408 6900 3403 6901 3408 6901 3409 6901 3409 6902 3408 6902 3886 6902 3409 6903 3886 6903 3887 6903 3410 6904 3411 6904 3403 6904 3403 6905 3411 6905 3399 6905 3403 6906 3399 6906 3412 6906 3412 6907 3399 6907 3995 6907 3412 6908 3995 6908 3878 6908 4034 6909 78239 6909 3413 6909 3413 6910 78239 6910 78209 6910 3413 6911 78209 6911 4025 6911 4025 6912 78209 6912 79407 6912 4025 6913 79407 6913 3414 6913 3414 6914 79407 6914 3415 6914 78094 6915 3416 6915 3103 6915 3103 6916 3416 6916 3414 6916 3103 6917 3414 6917 3415 6917 3416 6918 78094 6918 4015 6918 4015 6919 78094 6919 78446 6919 4015 6920 78446 6920 3417 6920 3417 6921 78446 6921 78448 6921 3417 6922 78448 6922 3418 6922 3418 6923 78448 6923 78282 6923 3265 6924 3953 6924 3419 6924 3081 6925 78225 6925 3419 6925 3419 6926 78225 6926 3988 6926 3419 6927 3988 6927 3265 6927 3988 6928 78225 6928 3997 6928 3997 6929 78225 6929 3420 6929 3997 6930 3420 6930 3996 6930 3996 6931 3420 6931 80429 6931 3996 6932 80429 6932 4003 6932 4003 6933 80429 6933 3090 6933 80252 6934 4002 6934 3421 6934 3421 6935 4002 6935 4003 6935 3421 6936 4003 6936 3090 6936 4002 6937 80252 6937 4007 6937 4007 6938 80252 6938 81400 6938 4007 6939 81400 6939 3422 6939 3422 6940 81400 6940 78227 6940 3422 6941 78227 6941 3280 6941 3280 6942 78227 6942 78222 6942 3111 6943 78239 6943 4034 6943 4042 6944 3300 6944 3423 6944 4042 6945 3423 6945 4034 6945 4034 6946 3423 6946 3102 6946 4034 6947 3102 6947 3111 6947 3434 6948 3402 6948 3424 6948 3424 6949 3402 6949 3401 6949 3424 6950 3401 6950 3425 6950 3425 6951 3401 6951 3426 6951 3425 6952 3426 6952 3165 6952 3165 6953 3426 6953 3427 6953 3165 6954 3427 6954 3145 6954 3145 6955 3427 6955 3405 6955 3145 6956 3405 6956 3428 6956 3428 6957 3405 6957 3404 6957 3428 6958 3404 6958 3429 6958 3429 6959 3404 6959 3430 6959 3429 6960 3430 6960 3148 6960 3148 6961 3430 6961 3400 6961 3148 6962 3400 6962 3431 6962 3431 6963 3400 6963 3432 6963 3431 6964 3432 6964 3149 6964 3149 6965 3432 6965 3411 6965 3149 6966 3411 6966 3433 6966 3433 6967 3411 6967 3410 6967 3433 6968 3410 6968 3056 6968 3056 6969 3410 6969 3435 6969 3056 6970 3435 6970 3434 6970 3434 6971 3435 6971 3402 6971 3158 6972 3436 6972 3157 6972 3157 6973 3436 6973 3437 6973 3157 6974 3437 6974 3160 6974 3160 6975 3437 6975 3438 6975 3160 6976 3438 6976 3161 6976 3161 6977 3438 6977 3397 6977 3161 6978 3397 6978 3162 6978 3162 6979 3397 6979 3439 6979 3162 6980 3439 6980 3440 6980 3440 6981 3439 6981 3395 6981 3440 6982 3395 6982 3163 6982 3163 6983 3395 6983 3394 6983 3163 6984 3394 6984 3441 6984 3441 6985 3394 6985 3442 6985 3441 6986 3442 6986 3443 6986 3443 6987 3442 6987 3392 6987 3443 6988 3392 6988 3156 6988 3156 6989 3392 6989 3444 6989 3156 6990 3444 6990 3445 6990 3445 6991 3444 6991 3446 6991 3445 6992 3446 6992 3159 6992 3159 6993 3446 6993 3447 6993 3159 6994 3447 6994 3158 6994 3158 6995 3447 6995 3436 6995 3179 6996 3457 6996 3178 6996 3178 6997 3457 6997 3387 6997 3178 6998 3387 6998 3448 6998 3448 6999 3387 6999 3382 6999 3448 7000 3382 7000 3449 7000 3449 7001 3382 7001 3386 7001 3449 7002 3386 7002 3181 7002 3181 7003 3386 7003 3385 7003 3181 7004 3385 7004 3182 7004 3182 7005 3385 7005 3450 7005 3182 7006 3450 7006 3451 7006 3451 7007 3450 7007 3391 7007 3451 7008 3391 7008 3183 7008 3183 7009 3391 7009 3390 7009 3183 7010 3390 7010 3184 7010 3184 7011 3390 7011 3452 7011 3184 7012 3452 7012 3453 7012 3453 7013 3452 7013 3388 7013 3453 7014 3388 7014 3454 7014 3454 7015 3388 7015 3389 7015 3454 7016 3389 7016 3455 7016 3455 7017 3389 7017 3456 7017 3455 7018 3456 7018 3179 7018 3179 7019 3456 7019 3457 7019 3469 7020 3377 7020 3197 7020 3197 7021 3377 7021 3459 7021 3197 7022 3459 7022 3458 7022 3458 7023 3459 7023 3460 7023 3458 7024 3460 7024 3198 7024 3198 7025 3460 7025 3461 7025 3198 7026 3461 7026 3192 7026 3192 7027 3461 7027 3381 7027 3192 7028 3381 7028 3193 7028 3193 7029 3381 7029 3462 7029 3193 7030 3462 7030 3463 7030 3463 7031 3462 7031 3379 7031 3463 7032 3379 7032 3199 7032 3199 7033 3379 7033 3464 7033 3199 7034 3464 7034 3465 7034 3465 7035 3464 7035 3466 7035 3465 7036 3466 7036 3468 7036 3468 7037 3466 7037 3467 7037 3468 7038 3467 7038 3194 7038 3194 7039 3467 7039 3375 7039 3194 7040 3375 7040 3195 7040 3195 7041 3375 7041 3378 7041 3195 7042 3378 7042 3469 7042 3469 7043 3378 7043 3377 7043 3478 7044 3479 7044 3470 7044 3470 7045 3479 7045 3370 7045 3470 7046 3370 7046 3471 7046 3471 7047 3370 7047 3369 7047 3471 7048 3369 7048 3213 7048 3213 7049 3369 7049 3368 7049 3213 7050 3368 7050 3212 7050 3212 7051 3368 7051 3367 7051 3212 7052 3367 7052 3216 7052 3216 7053 3367 7053 3366 7053 3216 7054 3366 7054 3218 7054 3218 7055 3366 7055 3365 7055 3218 7056 3365 7056 3472 7056 3472 7057 3365 7057 3374 7057 3472 7058 3374 7058 3473 7058 3473 7059 3374 7059 3373 7059 3473 7060 3373 7060 3474 7060 3474 7061 3373 7061 3372 7061 3474 7062 3372 7062 3475 7062 3475 7063 3372 7063 3476 7063 3475 7064 3476 7064 3214 7064 3214 7065 3476 7065 3477 7065 3214 7066 3477 7066 3478 7066 3478 7067 3477 7067 3479 7067 3072 7068 3480 7068 3073 7068 3073 7069 3480 7069 3361 7069 3073 7070 3361 7070 3067 7070 3067 7071 3361 7071 3363 7071 3067 7072 3363 7072 3070 7072 3070 7073 3363 7073 3481 7073 3070 7074 3481 7074 3482 7074 3482 7075 3481 7075 3362 7075 3482 7076 3362 7076 3071 7076 3071 7077 3362 7077 3483 7077 3071 7078 3483 7078 3246 7078 3246 7079 3483 7079 3359 7079 3246 7080 3359 7080 3075 7080 3075 7081 3359 7081 3484 7081 3075 7082 3484 7082 3077 7082 3077 7083 3484 7083 3485 7083 3077 7084 3485 7084 3487 7084 3487 7085 3485 7085 3486 7085 3487 7086 3486 7086 3488 7086 3488 7087 3486 7087 3489 7087 3488 7088 3489 7088 3068 7088 3068 7089 3489 7089 3490 7089 3068 7090 3490 7090 3072 7090 3072 7091 3490 7091 3480 7091 3491 7092 3492 7092 3493 7092 3493 7093 3492 7093 3344 7093 3493 7094 3344 7094 3494 7094 3494 7095 3344 7095 3495 7095 3494 7096 3495 7096 3496 7096 3496 7097 3495 7097 3497 7097 3496 7098 3497 7098 3255 7098 3255 7099 3497 7099 3498 7099 3255 7100 3498 7100 3256 7100 3256 7101 3498 7101 3499 7101 3256 7102 3499 7102 3257 7102 3257 7103 3499 7103 3342 7103 3257 7104 3342 7104 3500 7104 3500 7105 3342 7105 3341 7105 3500 7106 3341 7106 3258 7106 3258 7107 3341 7107 3347 7107 3258 7108 3347 7108 3251 7108 3251 7109 3347 7109 3346 7109 3251 7110 3346 7110 3252 7110 3252 7111 3346 7111 3501 7111 3252 7112 3501 7112 3502 7112 3502 7113 3501 7113 3503 7113 3502 7114 3503 7114 3491 7114 3491 7115 3503 7115 3492 7115 3222 7116 3340 7116 3504 7116 3504 7117 3340 7117 3505 7117 3504 7118 3505 7118 3223 7118 3223 7119 3505 7119 3506 7119 3223 7120 3506 7120 3227 7120 3227 7121 3506 7121 3507 7121 3227 7122 3507 7122 3228 7122 3228 7123 3507 7123 3508 7123 3228 7124 3508 7124 3229 7124 3229 7125 3508 7125 3509 7125 3229 7126 3509 7126 3226 7126 3226 7127 3509 7127 3339 7127 3226 7128 3339 7128 3510 7128 3510 7129 3339 7129 3338 7129 3510 7130 3338 7130 3512 7130 3512 7131 3338 7131 3511 7131 3512 7132 3511 7132 3513 7132 3513 7133 3511 7133 3514 7133 3513 7134 3514 7134 3515 7134 3515 7135 3514 7135 3516 7135 3515 7136 3516 7136 3221 7136 3221 7137 3516 7137 3517 7137 3221 7138 3517 7138 3222 7138 3222 7139 3517 7139 3340 7139 3202 7140 3518 7140 3201 7140 3201 7141 3518 7141 3520 7141 3201 7142 3520 7142 3519 7142 3519 7143 3520 7143 3337 7143 3519 7144 3337 7144 3522 7144 3522 7145 3337 7145 3521 7145 3522 7146 3521 7146 3523 7146 3523 7147 3521 7147 3524 7147 3523 7148 3524 7148 3207 7148 3207 7149 3524 7149 3525 7149 3207 7150 3525 7150 3209 7150 3209 7151 3525 7151 3334 7151 3209 7152 3334 7152 3210 7152 3210 7153 3334 7153 3333 7153 3210 7154 3333 7154 3211 7154 3211 7155 3333 7155 3332 7155 3211 7156 3332 7156 3526 7156 3526 7157 3332 7157 3527 7157 3526 7158 3527 7158 3206 7158 3206 7159 3527 7159 3331 7159 3206 7160 3331 7160 3528 7160 3528 7161 3331 7161 3330 7161 3528 7162 3330 7162 3202 7162 3202 7163 3330 7163 3518 7163 3529 7164 3540 7164 3189 7164 3189 7165 3540 7165 3327 7165 3189 7166 3327 7166 3530 7166 3530 7167 3327 7167 3329 7167 3530 7168 3329 7168 3190 7168 3190 7169 3329 7169 3531 7169 3190 7170 3531 7170 3532 7170 3532 7171 3531 7171 3328 7171 3532 7172 3328 7172 3534 7172 3534 7173 3328 7173 3533 7173 3534 7174 3533 7174 3535 7174 3535 7175 3533 7175 3326 7175 3535 7176 3326 7176 3536 7176 3536 7177 3326 7177 3537 7177 3536 7178 3537 7178 3191 7178 3191 7179 3537 7179 3325 7179 3191 7180 3325 7180 3188 7180 3188 7181 3325 7181 3324 7181 3188 7182 3324 7182 3538 7182 3538 7183 3324 7183 3539 7183 3538 7184 3539 7184 3187 7184 3187 7185 3539 7185 3323 7185 3187 7186 3323 7186 3529 7186 3529 7187 3323 7187 3540 7187 3169 7188 3541 7188 3171 7188 3171 7189 3541 7189 3542 7189 3171 7190 3542 7190 3172 7190 3172 7191 3542 7191 3316 7191 3172 7192 3316 7192 3544 7192 3544 7193 3316 7193 3543 7193 3544 7194 3543 7194 3173 7194 3173 7195 3543 7195 3545 7195 3173 7196 3545 7196 3174 7196 3174 7197 3545 7197 3318 7197 3174 7198 3318 7198 3175 7198 3175 7199 3318 7199 3546 7199 3175 7200 3546 7200 3176 7200 3176 7201 3546 7201 3548 7201 3176 7202 3548 7202 3547 7202 3547 7203 3548 7203 3549 7203 3547 7204 3549 7204 3550 7204 3550 7205 3549 7205 3322 7205 3550 7206 3322 7206 3168 7206 3168 7207 3322 7207 3321 7207 3168 7208 3321 7208 3551 7208 3551 7209 3321 7209 3552 7209 3551 7210 3552 7210 3169 7210 3169 7211 3552 7211 3541 7211 3054 7212 3307 7212 3151 7212 3151 7213 3307 7213 3553 7213 3151 7214 3553 7214 3150 7214 3150 7215 3553 7215 3306 7215 3150 7216 3306 7216 3554 7216 3554 7217 3306 7217 3314 7217 3554 7218 3314 7218 3555 7218 3555 7219 3314 7219 3312 7219 3555 7220 3312 7220 3556 7220 3556 7221 3312 7221 3311 7221 3556 7222 3311 7222 3155 7222 3155 7223 3311 7223 3303 7223 3155 7224 3303 7224 3152 7224 3152 7225 3303 7225 3557 7225 3152 7226 3557 7226 3558 7226 3558 7227 3557 7227 3559 7227 3558 7228 3559 7228 3153 7228 3153 7229 3559 7229 3310 7229 3153 7230 3310 7230 3560 7230 3560 7231 3310 7231 3561 7231 3560 7232 3561 7232 3562 7232 3562 7233 3561 7233 3309 7233 3562 7234 3309 7234 3054 7234 3054 7235 3309 7235 3307 7235 3839 7236 3568 7236 3142 7236 3142 7237 3568 7237 3563 7237 3142 7238 3563 7238 3143 7238 3143 7239 3563 7239 3838 7239 3841 7240 3564 7240 3566 7240 3942 7241 3836 7241 3565 7241 3841 7242 3566 7242 3568 7242 3567 7243 3944 7243 3563 7243 3946 7244 3947 7244 3944 7244 3944 7245 3947 7245 3942 7245 3944 7246 3942 7246 3563 7246 3563 7247 3942 7247 3565 7247 3948 7248 3950 7248 3566 7248 3566 7249 3950 7249 3567 7249 3566 7250 3567 7250 3568 7250 3568 7251 3567 7251 3563 7251 3061 7252 3063 7252 3575 7252 3575 7253 3063 7253 3569 7253 3575 7254 3569 7254 3570 7254 3570 7255 3569 7255 3064 7255 3571 7256 3843 7256 3940 7256 3940 7257 3843 7257 3575 7257 3932 7258 3934 7258 3577 7258 3577 7259 3934 7259 3572 7259 3574 7260 3937 7260 3573 7260 3573 7261 3940 7261 3574 7261 3574 7262 3940 7262 3575 7262 3574 7263 3575 7263 3572 7263 3572 7264 3575 7264 3570 7264 3572 7265 3570 7265 3577 7265 3577 7266 3570 7266 3576 7266 3577 7267 3576 7267 3578 7267 3254 7268 3240 7268 3853 7268 3254 7269 3853 7269 3253 7269 3253 7270 3853 7270 3581 7270 3253 7271 3581 7271 3864 7271 3583 7272 3579 7272 3968 7272 3863 7273 3858 7273 3979 7273 3979 7274 3858 7274 3581 7274 3969 7275 3971 7275 3968 7275 3968 7276 3971 7276 3973 7276 3580 7277 3975 7277 3977 7277 3977 7278 3979 7278 3580 7278 3580 7279 3979 7279 3581 7279 3580 7280 3581 7280 3973 7280 3973 7281 3581 7281 3853 7281 3973 7282 3853 7282 3968 7282 3968 7283 3853 7283 3582 7283 3968 7284 3582 7284 3583 7284 3244 7285 3242 7285 3588 7285 3244 7286 3588 7286 3245 7286 3245 7287 3588 7287 3589 7287 3245 7288 3589 7288 3078 7288 3850 7289 3851 7289 3584 7289 3850 7290 3584 7290 3588 7290 3849 7291 3964 7291 3585 7291 3585 7292 3964 7292 3847 7292 3957 7293 3586 7293 3589 7293 3958 7294 3959 7294 3586 7294 3586 7295 3959 7295 3964 7295 3586 7296 3964 7296 3589 7296 3589 7297 3964 7297 3849 7297 3587 7298 3956 7298 3584 7298 3584 7299 3956 7299 3957 7299 3584 7300 3957 7300 3588 7300 3588 7301 3957 7301 3589 7301 3233 7302 3590 7302 3591 7302 3591 7303 3590 7303 3601 7303 3591 7304 3601 7304 3082 7304 3082 7305 3601 7305 3602 7305 3082 7306 3602 7306 3592 7306 3592 7307 3602 7307 3605 7307 3592 7308 3605 7308 3593 7308 3593 7309 3605 7309 3594 7309 3593 7310 3594 7310 3086 7310 3086 7311 3594 7311 3595 7311 3086 7312 3595 7312 3087 7312 3087 7313 3595 7313 3596 7313 3087 7314 3596 7314 3597 7314 3597 7315 3596 7315 3609 7315 3597 7316 3609 7316 3598 7316 3598 7317 3609 7317 3599 7317 3598 7318 3599 7318 3083 7318 3083 7319 3599 7319 3600 7319 3083 7320 3600 7320 3085 7320 3085 7321 3600 7321 3610 7321 3085 7322 3610 7322 3232 7322 3232 7323 3610 7323 3612 7323 3232 7324 3612 7324 3233 7324 3233 7325 3612 7325 3590 7325 3601 7326 3603 7326 3602 7326 3602 7327 3603 7327 3604 7327 3602 7328 3604 7328 3605 7328 3605 7329 3604 7329 3606 7329 3605 7330 3606 7330 3594 7330 3594 7331 3606 7331 3607 7331 3594 7332 3607 7332 3595 7332 3595 7333 3607 7333 3608 7333 3595 7334 3608 7334 3596 7334 3596 7335 3608 7335 3617 7335 3596 7336 3617 7336 3609 7336 3609 7337 3617 7337 3618 7337 3609 7338 3618 7338 3599 7338 3599 7339 3618 7339 3621 7339 3599 7340 3621 7340 3600 7340 3600 7341 3621 7341 3611 7341 3600 7342 3611 7342 3610 7342 3610 7343 3611 7343 3622 7343 3610 7344 3622 7344 3612 7344 3612 7345 3622 7345 3623 7345 3612 7346 3623 7346 3590 7346 3590 7347 3623 7347 3613 7347 3590 7348 3613 7348 3601 7348 3601 7349 3613 7349 3603 7349 3613 7350 4190 7350 3603 7350 3603 7351 4190 7351 3614 7351 3603 7352 3614 7352 3604 7352 3604 7353 3614 7353 4192 7353 3604 7354 4192 7354 3606 7354 3606 7355 4192 7355 4189 7355 3606 7356 4189 7356 3607 7356 3607 7357 4189 7357 3615 7357 3607 7358 3615 7358 3608 7358 3608 7359 3615 7359 3616 7359 3608 7360 3616 7360 3617 7360 3617 7361 3616 7361 3619 7361 3617 7362 3619 7362 3618 7362 3618 7363 3619 7363 3620 7363 3618 7364 3620 7364 3621 7364 3621 7365 3620 7365 4195 7365 3621 7366 4195 7366 3611 7366 3611 7367 4195 7367 4194 7367 3611 7368 4194 7368 3622 7368 3622 7369 4194 7369 3624 7369 3622 7370 3624 7370 3623 7370 3623 7371 3624 7371 3625 7371 3623 7372 3625 7372 3613 7372 3613 7373 3625 7373 4190 7373 3093 7374 3626 7374 3092 7374 3092 7375 3626 7375 3627 7375 3092 7376 3627 7376 3628 7376 3628 7377 3627 7377 3635 7377 3628 7378 3635 7378 3629 7378 3629 7379 3635 7379 3637 7379 3629 7380 3637 7380 3630 7380 3630 7381 3637 7381 3638 7381 3630 7382 3638 7382 3095 7382 3095 7383 3638 7383 3631 7383 3095 7384 3631 7384 3096 7384 3096 7385 3631 7385 3632 7385 3096 7386 3632 7386 3097 7386 3097 7387 3632 7387 3641 7387 3097 7388 3641 7388 3098 7388 3098 7389 3641 7389 3642 7389 3098 7390 3642 7390 3091 7390 3091 7391 3642 7391 3644 7391 3091 7392 3644 7392 3633 7392 3633 7393 3644 7393 3634 7393 3633 7394 3634 7394 3089 7394 3089 7395 3634 7395 3647 7395 3089 7396 3647 7396 3093 7396 3093 7397 3647 7397 3626 7397 3627 7398 3636 7398 3635 7398 3635 7399 3636 7399 3650 7399 3635 7400 3650 7400 3637 7400 3637 7401 3650 7401 3653 7401 3637 7402 3653 7402 3638 7402 3638 7403 3653 7403 3639 7403 3638 7404 3639 7404 3631 7404 3631 7405 3639 7405 3640 7405 3631 7406 3640 7406 3632 7406 3632 7407 3640 7407 3655 7407 3632 7408 3655 7408 3641 7408 3641 7409 3655 7409 3643 7409 3641 7410 3643 7410 3642 7410 3642 7411 3643 7411 3645 7411 3642 7412 3645 7412 3644 7412 3644 7413 3645 7413 3646 7413 3644 7414 3646 7414 3634 7414 3634 7415 3646 7415 3648 7415 3634 7416 3648 7416 3647 7416 3647 7417 3648 7417 3649 7417 3647 7418 3649 7418 3626 7418 3626 7419 3649 7419 3660 7419 3626 7420 3660 7420 3627 7420 3627 7421 3660 7421 3636 7421 3660 7422 3661 7422 3636 7422 3636 7423 3661 7423 3651 7423 3636 7424 3651 7424 3650 7424 3650 7425 3651 7425 3652 7425 3650 7426 3652 7426 3653 7426 3653 7427 3652 7427 3654 7427 3653 7428 3654 7428 3639 7428 3639 7429 3654 7429 4171 7429 3639 7430 4171 7430 3640 7430 3640 7431 4171 7431 4170 7431 3640 7432 4170 7432 3655 7432 3655 7433 4170 7433 3656 7433 3655 7434 3656 7434 3643 7434 3643 7435 3656 7435 3657 7435 3643 7436 3657 7436 3645 7436 3645 7437 3657 7437 3658 7437 3645 7438 3658 7438 3646 7438 3646 7439 3658 7439 3659 7439 3646 7440 3659 7440 3648 7440 3648 7441 3659 7441 4175 7441 3648 7442 4175 7442 3649 7442 3649 7443 4175 7443 4177 7443 3649 7444 4177 7444 3660 7444 3660 7445 4177 7445 3661 7445 3112 7446 3683 7446 3662 7446 3662 7447 3683 7447 3684 7447 3662 7448 3684 7448 3663 7448 3663 7449 3684 7449 3664 7449 3663 7450 3664 7450 3116 7450 3116 7451 3664 7451 3674 7451 3116 7452 3674 7452 3665 7452 3665 7453 3674 7453 3666 7453 3665 7454 3666 7454 3117 7454 3117 7455 3666 7455 3675 7455 3117 7456 3675 7456 3667 7456 3667 7457 3675 7457 3677 7457 3667 7458 3677 7458 3668 7458 3668 7459 3677 7459 3669 7459 3668 7460 3669 7460 3114 7460 3114 7461 3669 7461 3678 7461 3114 7462 3678 7462 3670 7462 3670 7463 3678 7463 3671 7463 3670 7464 3671 7464 3672 7464 3672 7465 3671 7465 3681 7465 3672 7466 3681 7466 3673 7466 3673 7467 3681 7467 3682 7467 3673 7468 3682 7468 3112 7468 3112 7469 3682 7469 3683 7469 3684 7470 3685 7470 3664 7470 3664 7471 3685 7471 3687 7471 3664 7472 3687 7472 3674 7472 3674 7473 3687 7473 3688 7473 3674 7474 3688 7474 3666 7474 3666 7475 3688 7475 3689 7475 3666 7476 3689 7476 3675 7476 3675 7477 3689 7477 3692 7477 3675 7478 3692 7478 3677 7478 3677 7479 3692 7479 3676 7479 3677 7480 3676 7480 3669 7480 3669 7481 3676 7481 3695 7481 3669 7482 3695 7482 3678 7482 3678 7483 3695 7483 3679 7483 3678 7484 3679 7484 3671 7484 3671 7485 3679 7485 3680 7485 3671 7486 3680 7486 3681 7486 3681 7487 3680 7487 3698 7487 3681 7488 3698 7488 3682 7488 3682 7489 3698 7489 3700 7489 3682 7490 3700 7490 3683 7490 3683 7491 3700 7491 3701 7491 3683 7492 3701 7492 3684 7492 3684 7493 3701 7493 3685 7493 3701 7494 3702 7494 3685 7494 3685 7495 3702 7495 3686 7495 3685 7496 3686 7496 3687 7496 3687 7497 3686 7497 4199 7497 3687 7498 4199 7498 3688 7498 3688 7499 4199 7499 4197 7499 3688 7500 4197 7500 3689 7500 3689 7501 4197 7501 3690 7501 3689 7502 3690 7502 3692 7502 3692 7503 3690 7503 3691 7503 3692 7504 3691 7504 3676 7504 3676 7505 3691 7505 3693 7505 3676 7506 3693 7506 3695 7506 3695 7507 3693 7507 3694 7507 3695 7508 3694 7508 3679 7508 3679 7509 3694 7509 3696 7509 3679 7510 3696 7510 3680 7510 3680 7511 3696 7511 3697 7511 3680 7512 3697 7512 3698 7512 3698 7513 3697 7513 3699 7513 3698 7514 3699 7514 3700 7514 3700 7515 3699 7515 4200 7515 3700 7516 4200 7516 3701 7516 3701 7517 4200 7517 3702 7517 3703 7518 3711 7518 3108 7518 3108 7519 3711 7519 3729 7519 3108 7520 3729 7520 3107 7520 3107 7521 3729 7521 3712 7521 3107 7522 3712 7522 3704 7522 3704 7523 3712 7523 3713 7523 3704 7524 3713 7524 3104 7524 3104 7525 3713 7525 3716 7525 3104 7526 3716 7526 3705 7526 3705 7527 3716 7527 3717 7527 3705 7528 3717 7528 3106 7528 3106 7529 3717 7529 3719 7529 3106 7530 3719 7530 3706 7530 3706 7531 3719 7531 3720 7531 3706 7532 3720 7532 3707 7532 3707 7533 3720 7533 3708 7533 3707 7534 3708 7534 3709 7534 3709 7535 3708 7535 3722 7535 3709 7536 3722 7536 3110 7536 3110 7537 3722 7537 3724 7537 3110 7538 3724 7538 3109 7538 3109 7539 3724 7539 3710 7539 3109 7540 3710 7540 3703 7540 3703 7541 3710 7541 3711 7541 3729 7542 3730 7542 3712 7542 3712 7543 3730 7543 3714 7543 3712 7544 3714 7544 3713 7544 3713 7545 3714 7545 3715 7545 3713 7546 3715 7546 3716 7546 3716 7547 3715 7547 3732 7547 3716 7548 3732 7548 3717 7548 3717 7549 3732 7549 3718 7549 3717 7550 3718 7550 3719 7550 3719 7551 3718 7551 3734 7551 3719 7552 3734 7552 3720 7552 3720 7553 3734 7553 3721 7553 3720 7554 3721 7554 3708 7554 3708 7555 3721 7555 3723 7555 3708 7556 3723 7556 3722 7556 3722 7557 3723 7557 3725 7557 3722 7558 3725 7558 3724 7558 3724 7559 3725 7559 3726 7559 3724 7560 3726 7560 3710 7560 3710 7561 3726 7561 3727 7561 3710 7562 3727 7562 3711 7562 3711 7563 3727 7563 3728 7563 3711 7564 3728 7564 3729 7564 3729 7565 3728 7565 3730 7565 3728 7566 4207 7566 3730 7566 3730 7567 4207 7567 3731 7567 3730 7568 3731 7568 3714 7568 3714 7569 3731 7569 4206 7569 3714 7570 4206 7570 3715 7570 3715 7571 4206 7571 4205 7571 3715 7572 4205 7572 3732 7572 3732 7573 4205 7573 4204 7573 3732 7574 4204 7574 3718 7574 3718 7575 4204 7575 3733 7575 3718 7576 3733 7576 3734 7576 3734 7577 3733 7577 3735 7577 3734 7578 3735 7578 3721 7578 3721 7579 3735 7579 4203 7579 3721 7580 4203 7580 3723 7580 3723 7581 4203 7581 3736 7581 3723 7582 3736 7582 3725 7582 3725 7583 3736 7583 4202 7583 3725 7584 4202 7584 3726 7584 3726 7585 4202 7585 4209 7585 3726 7586 4209 7586 3727 7586 3727 7587 4209 7587 4208 7587 3727 7588 4208 7588 3728 7588 3728 7589 4208 7589 4207 7589 3748 7590 3737 7590 2935 7590 2935 7591 3737 7591 3738 7591 2935 7592 3738 7592 2936 7592 2936 7593 3738 7593 3739 7593 2936 7594 3739 7594 2938 7594 2938 7595 3739 7595 3740 7595 2938 7596 3740 7596 3741 7596 3741 7597 3740 7597 4234 7597 3741 7598 4234 7598 3742 7598 3742 7599 4234 7599 4233 7599 3742 7600 4233 7600 2940 7600 2940 7601 4233 7601 4138 7601 2940 7602 4138 7602 2942 7602 2942 7603 4138 7603 4237 7603 2942 7604 4237 7604 3743 7604 3743 7605 4237 7605 3744 7605 3743 7606 3744 7606 3745 7606 3745 7607 3744 7607 3746 7607 3745 7608 3746 7608 3747 7608 3747 7609 3746 7609 4238 7609 3747 7610 4238 7610 2947 7610 2947 7611 4238 7611 3749 7611 2947 7612 3749 7612 3748 7612 3748 7613 3749 7613 3737 7613 2950 7614 4152 7614 2953 7614 2953 7615 4152 7615 3750 7615 2953 7616 3750 7616 3752 7616 3752 7617 3750 7617 3751 7617 3752 7618 3751 7618 2955 7618 2955 7619 3751 7619 3753 7619 2955 7620 3753 7620 2956 7620 2956 7621 3753 7621 4145 7621 2956 7622 4145 7622 3754 7622 3754 7623 4145 7623 4144 7623 3754 7624 4144 7624 3755 7624 3755 7625 4144 7625 3757 7625 3755 7626 3757 7626 3756 7626 3756 7627 3757 7627 4155 7627 3756 7628 4155 7628 3758 7628 3758 7629 4155 7629 3759 7629 3758 7630 3759 7630 3760 7630 3760 7631 3759 7631 3761 7631 3760 7632 3761 7632 3762 7632 3762 7633 3761 7633 4154 7633 3762 7634 4154 7634 2948 7634 2948 7635 4154 7635 3763 7635 2948 7636 3763 7636 2950 7636 2950 7637 3763 7637 4152 7637 2962 7638 4242 7638 3765 7638 3765 7639 4242 7639 3764 7639 3765 7640 3764 7640 3766 7640 3766 7641 3764 7641 4245 7641 3766 7642 4245 7642 3767 7642 3767 7643 4245 7643 3768 7643 3767 7644 3768 7644 3769 7644 3769 7645 3768 7645 4247 7645 3769 7646 4247 7646 2967 7646 2967 7647 4247 7647 3770 7647 2967 7648 3770 7648 3772 7648 3772 7649 3770 7649 3771 7649 3772 7650 3771 7650 3773 7650 3773 7651 3771 7651 3775 7651 3773 7652 3775 7652 3774 7652 3774 7653 3775 7653 4244 7653 3774 7654 4244 7654 3776 7654 3776 7655 4244 7655 3777 7655 3776 7656 3777 7656 3778 7656 3778 7657 3777 7657 3779 7657 3778 7658 3779 7658 3781 7658 3781 7659 3779 7659 3780 7659 3781 7660 3780 7660 2962 7660 2962 7661 3780 7661 4242 7661 3782 7662 3797 7662 3783 7662 3783 7663 3797 7663 3785 7663 3783 7664 3785 7664 3784 7664 3784 7665 3785 7665 3786 7665 3784 7666 3786 7666 2974 7666 2974 7667 3786 7667 3787 7667 2974 7668 3787 7668 2976 7668 2976 7669 3787 7669 3788 7669 2976 7670 3788 7670 3789 7670 3789 7671 3788 7671 3790 7671 3789 7672 3790 7672 3791 7672 3791 7673 3790 7673 4261 7673 3791 7674 4261 7674 3792 7674 3792 7675 4261 7675 3793 7675 3792 7676 3793 7676 2980 7676 2980 7677 3793 7677 4160 7677 2980 7678 4160 7678 2981 7678 2981 7679 4160 7679 3794 7679 2981 7680 3794 7680 3795 7680 3795 7681 3794 7681 3796 7681 3795 7682 3796 7682 2982 7682 2982 7683 3796 7683 4158 7683 2982 7684 4158 7684 3782 7684 3782 7685 4158 7685 3797 7685 2984 7686 3798 7686 3799 7686 3799 7687 3798 7687 4254 7687 3799 7688 4254 7688 2986 7688 2986 7689 4254 7689 3800 7689 2986 7690 3800 7690 3801 7690 3801 7691 3800 7691 3802 7691 3801 7692 3802 7692 2987 7692 2987 7693 3802 7693 3803 7693 2987 7694 3803 7694 2989 7694 2989 7695 3803 7695 3804 7695 2989 7696 3804 7696 3805 7696 3805 7697 3804 7697 3806 7697 3805 7698 3806 7698 3807 7698 3807 7699 3806 7699 4252 7699 3807 7700 4252 7700 2992 7700 2992 7701 4252 7701 3809 7701 2992 7702 3809 7702 3808 7702 3808 7703 3809 7703 3811 7703 3808 7704 3811 7704 3810 7704 3810 7705 3811 7705 4251 7705 3810 7706 4251 7706 2983 7706 2983 7707 4251 7707 4256 7707 2983 7708 4256 7708 2984 7708 2984 7709 4256 7709 3798 7709 3812 7710 4164 7710 2995 7710 2995 7711 4164 7711 3813 7711 2995 7712 3813 7712 2996 7712 2996 7713 3813 7713 4161 7713 2996 7714 4161 7714 3815 7714 3815 7715 4161 7715 3814 7715 3815 7716 3814 7716 3816 7716 3816 7717 3814 7717 4162 7717 3816 7718 4162 7718 3817 7718 3817 7719 4162 7719 4169 7719 3817 7720 4169 7720 3818 7720 3818 7721 4169 7721 3819 7721 3818 7722 3819 7722 3820 7722 3820 7723 3819 7723 4168 7723 3820 7724 4168 7724 3001 7724 3001 7725 4168 7725 4167 7725 3001 7726 4167 7726 3003 7726 3003 7727 4167 7727 4166 7727 3003 7728 4166 7728 3004 7728 3004 7729 4166 7729 4165 7729 3004 7730 4165 7730 3821 7730 3821 7731 4165 7731 3822 7731 3821 7732 3822 7732 3812 7732 3812 7733 3822 7733 4164 7733 3823 7734 3972 7734 3970 7734 3823 7735 3970 7735 3904 7735 3904 7736 3970 7736 3967 7736 3904 7737 3967 7737 3905 7737 3905 7738 3967 7738 3266 7738 3905 7739 3266 7739 3824 7739 3285 7740 3961 7740 3960 7740 3285 7741 3960 7741 3901 7741 3901 7742 3960 7742 3825 7742 3901 7743 3825 7743 3826 7743 3826 7744 3825 7744 3260 7744 3826 7745 3260 7745 3902 7745 3827 7746 3936 7746 3933 7746 3827 7747 3933 7747 3881 7747 3881 7748 3933 7748 3828 7748 3881 7749 3828 7749 3882 7749 3882 7750 3828 7750 3829 7750 3882 7751 3829 7751 3885 7751 3831 7752 3268 7752 3830 7752 3831 7753 3830 7753 3832 7753 3832 7754 3830 7754 3945 7754 3832 7755 3945 7755 3924 7755 3924 7756 3945 7756 3833 7756 3924 7757 3833 7757 3925 7757 3838 7758 3563 7758 3565 7758 3269 7759 3278 7759 3943 7759 3943 7760 3278 7760 3834 7760 3943 7761 3834 7761 3835 7761 3835 7762 3834 7762 3836 7762 3836 7763 3834 7763 3565 7763 3565 7764 3834 7764 3837 7764 3565 7765 3837 7765 3838 7765 3839 7766 3840 7766 3568 7766 3568 7767 3840 7767 3841 7767 3841 7768 3840 7768 3564 7768 3564 7769 3840 7769 3141 7769 3564 7770 3141 7770 3952 7770 3952 7771 3141 7771 3842 7771 3842 7772 3141 7772 3102 7772 3842 7773 3102 7773 3423 7773 3061 7774 3575 7774 3843 7774 3291 7775 3062 7775 3939 7775 3939 7776 3062 7776 3060 7776 3939 7777 3060 7777 3941 7777 3941 7778 3060 7778 3571 7778 3571 7779 3060 7779 3843 7779 3843 7780 3060 7780 3059 7780 3843 7781 3059 7781 3061 7781 3064 7782 3844 7782 3570 7782 3570 7783 3844 7783 3576 7783 3576 7784 3844 7784 3578 7784 3578 7785 3844 7785 3066 7785 3578 7786 3066 7786 3931 7786 3931 7787 3066 7787 3845 7787 3845 7788 3066 7788 3065 7788 3845 7789 3065 7789 3286 7789 3962 7790 3846 7790 3963 7790 3963 7791 3846 7791 3074 7791 3585 7792 3847 7792 3074 7792 3074 7793 3847 7793 3965 7793 3074 7794 3965 7794 3963 7794 3074 7795 3079 7795 3585 7795 3585 7796 3079 7796 3848 7796 3585 7797 3848 7797 3849 7797 3849 7798 3848 7798 3078 7798 3849 7799 3078 7799 3589 7799 3242 7800 3241 7800 3588 7800 3588 7801 3241 7801 3850 7801 3850 7802 3241 7802 3851 7802 3851 7803 3241 7803 3080 7803 3851 7804 3080 7804 3954 7804 3954 7805 3080 7805 3852 7805 3852 7806 3080 7806 3081 7806 3852 7807 3081 7807 3419 7807 3853 7808 3240 7808 3854 7808 3853 7809 3854 7809 3582 7809 3582 7810 3854 7810 3855 7810 3582 7811 3855 7811 3583 7811 3583 7812 3855 7812 3579 7812 3579 7813 3855 7813 3100 7813 3579 7814 3100 7814 3966 7814 3966 7815 3100 7815 3856 7815 3856 7816 3100 7816 3099 7816 3856 7817 3099 7817 3857 7817 3864 7818 3581 7818 3858 7818 3279 7819 3859 7819 3860 7819 3860 7820 3859 7820 3862 7820 3860 7821 3862 7821 3861 7821 3861 7822 3862 7822 3863 7822 3863 7823 3862 7823 3858 7823 3858 7824 3862 7824 3248 7824 3858 7825 3248 7825 3864 7825 3879 7826 3878 7826 3865 7826 3865 7827 4001 7827 3879 7827 3879 7828 4001 7828 3998 7828 3879 7829 3998 7829 3880 7829 3880 7830 3998 7830 3866 7830 3880 7831 3866 7831 3867 7831 3297 7832 4043 7832 3868 7832 3297 7833 3868 7833 3927 7833 3927 7834 3868 7834 4036 7834 3927 7835 4036 7835 3928 7835 3928 7836 4036 7836 3869 7836 3928 7837 3869 7837 3930 7837 3259 7838 3987 7838 3871 7838 3259 7839 3871 7839 3870 7839 3870 7840 3871 7840 3872 7840 3870 7841 3872 7841 3873 7841 3873 7842 3872 7842 3985 7842 3873 7843 3985 7843 3874 7843 3875 7844 3354 7844 4024 7844 4024 7845 3876 7845 3875 7845 3875 7846 3876 7846 4019 7846 3875 7847 4019 7847 3877 7847 3877 7848 4019 7848 3282 7848 3877 7849 3282 7849 3283 7849 3880 7850 3867 7850 3827 7850 3412 7851 3878 7851 3827 7851 3827 7852 3878 7852 3879 7852 3827 7853 3879 7853 3880 7853 3412 7854 3827 7854 3881 7854 3412 7855 3881 7855 3883 7855 3883 7856 3881 7856 3882 7856 3883 7857 3882 7857 3884 7857 3884 7858 3882 7858 3885 7858 3884 7859 3885 7859 3407 7859 3407 7860 3885 7860 3408 7860 3408 7861 3885 7861 3044 7861 3408 7862 3044 7862 3886 7862 3886 7863 3044 7863 3046 7863 3886 7864 3046 7864 3887 7864 3887 7865 3046 7865 3006 7865 3887 7866 3006 7866 3409 7866 3005 7867 3890 7867 3006 7867 3006 7868 3890 7868 3409 7868 3888 7869 3889 7869 3016 7869 3016 7870 3889 7870 3406 7870 3016 7871 3406 7871 3005 7871 3005 7872 3406 7872 3890 7872 3891 7873 3371 7873 3892 7873 3892 7874 3371 7874 3376 7874 3376 7875 3383 7875 3892 7875 3892 7876 3383 7876 3398 7876 3892 7877 3398 7877 3888 7877 3888 7878 3398 7878 3893 7878 3888 7879 3893 7879 3889 7879 3894 7880 3895 7880 3015 7880 3015 7881 3895 7881 3364 7881 3015 7882 3364 7882 3892 7882 3892 7883 3364 7883 3891 7883 3007 7884 3896 7884 3894 7884 3894 7885 3896 7885 3895 7885 3896 7886 3007 7886 3897 7886 3896 7887 3897 7887 3360 7887 3360 7888 3897 7888 3899 7888 3360 7889 3899 7889 3898 7889 3285 7890 3357 7890 3899 7890 3899 7891 3357 7891 3898 7891 3357 7892 3285 7892 3901 7892 3357 7893 3901 7893 3900 7893 3900 7894 3901 7894 3826 7894 3900 7895 3826 7895 3356 7895 3356 7896 3826 7896 3902 7896 3356 7897 3902 7897 3358 7897 3355 7898 3358 7898 3902 7898 3259 7899 3870 7899 3902 7899 3902 7900 3870 7900 3873 7900 3902 7901 3873 7901 3355 7901 3355 7902 3873 7902 3874 7902 3877 7903 3283 7903 3823 7903 3350 7904 3354 7904 3823 7904 3823 7905 3354 7905 3875 7905 3823 7906 3875 7906 3877 7906 3350 7907 3823 7907 3904 7907 3350 7908 3904 7908 3903 7908 3903 7909 3904 7909 3905 7909 3903 7910 3905 7910 3348 7910 3348 7911 3905 7911 3824 7911 3348 7912 3824 7912 3349 7912 3349 7913 3824 7913 3907 7913 3907 7914 3824 7914 3906 7914 3907 7915 3906 7915 3908 7915 3908 7916 3906 7916 3048 7916 3908 7917 3048 7917 3352 7917 3352 7918 3048 7918 3047 7918 3352 7919 3047 7919 3343 7919 3912 7920 3909 7920 3047 7920 3047 7921 3909 7921 3343 7921 3012 7922 3917 7922 3910 7922 3910 7923 3917 7923 3911 7923 3910 7924 3911 7924 3912 7924 3912 7925 3911 7925 3909 7925 3315 7926 3913 7926 3915 7926 3915 7927 3913 7927 3317 7927 3317 7928 3914 7928 3915 7928 3915 7929 3914 7929 3335 7929 3915 7930 3335 7930 3012 7930 3012 7931 3335 7931 3916 7931 3012 7932 3916 7932 3917 7932 3918 7933 3919 7933 3920 7933 3920 7934 3919 7934 3313 7934 3920 7935 3313 7935 3915 7935 3915 7936 3313 7936 3315 7936 3052 7937 3304 7937 3918 7937 3918 7938 3304 7938 3919 7938 3304 7939 3052 7939 3051 7939 3304 7940 3051 7940 3922 7940 3922 7941 3051 7941 3921 7941 3922 7942 3921 7942 3923 7942 3831 7943 3305 7943 3921 7943 3921 7944 3305 7944 3923 7944 3305 7945 3831 7945 3832 7945 3305 7946 3832 7946 3301 7946 3301 7947 3832 7947 3924 7947 3301 7948 3924 7948 3302 7948 3302 7949 3924 7949 3925 7949 3302 7950 3925 7950 3926 7950 3929 7951 3926 7951 3925 7951 3297 7952 3927 7952 3925 7952 3925 7953 3927 7953 3928 7953 3925 7954 3928 7954 3929 7954 3929 7955 3928 7955 3930 7955 3845 7956 3286 7956 3829 7956 3577 7957 3578 7957 3829 7957 3829 7958 3578 7958 3931 7958 3829 7959 3931 7959 3845 7959 3577 7960 3829 7960 3828 7960 3577 7961 3828 7961 3932 7961 3932 7962 3828 7962 3933 7962 3932 7963 3933 7963 3934 7963 3934 7964 3933 7964 3936 7964 3934 7965 3936 7965 3572 7965 3935 7966 3574 7966 3936 7966 3936 7967 3574 7967 3572 7967 3574 7968 3935 7968 3295 7968 3574 7969 3295 7969 3937 7969 3937 7970 3295 7970 3938 7970 3937 7971 3938 7971 3573 7971 3573 7972 3938 7972 3293 7972 3573 7973 3293 7973 3940 7973 3293 7974 3291 7974 3939 7974 3293 7975 3939 7975 3940 7975 3940 7976 3939 7976 3941 7976 3940 7977 3941 7977 3571 7977 3268 7978 3269 7978 3943 7978 3268 7979 3943 7979 3942 7979 3942 7980 3943 7980 3835 7980 3942 7981 3835 7981 3836 7981 3944 7982 3833 7982 3945 7982 3944 7983 3945 7983 3946 7983 3946 7984 3945 7984 3830 7984 3946 7985 3830 7985 3947 7985 3947 7986 3830 7986 3268 7986 3947 7987 3268 7987 3942 7987 3567 7988 3951 7988 3944 7988 3944 7989 3951 7989 3833 7989 3566 7990 3300 7990 3949 7990 3566 7991 3949 7991 3948 7991 3948 7992 3949 7992 3299 7992 3948 7993 3299 7993 3950 7993 3950 7994 3299 7994 3951 7994 3950 7995 3951 7995 3567 7995 3842 7996 3423 7996 3300 7996 3566 7997 3564 7997 3300 7997 3300 7998 3564 7998 3952 7998 3300 7999 3952 7999 3842 7999 3852 8000 3419 8000 3953 8000 3584 8001 3851 8001 3953 8001 3953 8002 3851 8002 3954 8002 3953 8003 3954 8003 3852 8003 3584 8004 3953 8004 3264 8004 3584 8005 3264 8005 3587 8005 3587 8006 3264 8006 3955 8006 3587 8007 3955 8007 3956 8007 3956 8008 3955 8008 3261 8008 3956 8009 3261 8009 3957 8009 3260 8010 3586 8010 3261 8010 3261 8011 3586 8011 3957 8011 3586 8012 3260 8012 3825 8012 3586 8013 3825 8013 3958 8013 3958 8014 3825 8014 3960 8014 3958 8015 3960 8015 3959 8015 3959 8016 3960 8016 3961 8016 3959 8017 3961 8017 3964 8017 3961 8018 3962 8018 3963 8018 3961 8019 3963 8019 3964 8019 3964 8020 3963 8020 3965 8020 3964 8021 3965 8021 3847 8021 3856 8022 3857 8022 3266 8022 3968 8023 3579 8023 3266 8023 3266 8024 3579 8024 3966 8024 3266 8025 3966 8025 3856 8025 3968 8026 3266 8026 3967 8026 3968 8027 3967 8027 3969 8027 3969 8028 3967 8028 3970 8028 3969 8029 3970 8029 3971 8029 3971 8030 3970 8030 3972 8030 3971 8031 3972 8031 3973 8031 3284 8032 3580 8032 3972 8032 3972 8033 3580 8033 3973 8033 3580 8034 3284 8034 3974 8034 3580 8035 3974 8035 3975 8035 3975 8036 3974 8036 3976 8036 3975 8037 3976 8037 3977 8037 3977 8038 3976 8038 3978 8038 3977 8039 3978 8039 3979 8039 3978 8040 3279 8040 3860 8040 3978 8041 3860 8041 3979 8041 3979 8042 3860 8042 3861 8042 3979 8043 3861 8043 3863 8043 3262 8044 3980 8044 3987 8044 3987 8045 3980 8045 4191 8045 3980 8046 3262 8046 3263 8046 3980 8047 3263 8047 3981 8047 3981 8048 3263 8048 3982 8048 3981 8049 3982 8049 3983 8049 3983 8050 3982 8050 3265 8050 3983 8051 3265 8051 4188 8051 3989 8052 3874 8052 3984 8052 3984 8053 3874 8053 3986 8053 3874 8054 3985 8054 3986 8054 3986 8055 3985 8055 3872 8055 3986 8056 3872 8056 4235 8056 3872 8057 3871 8057 4235 8057 4235 8058 3871 8058 3987 8058 4235 8059 3987 8059 4191 8059 3988 8060 4187 8060 3265 8060 3265 8061 4187 8061 4188 8061 3991 8062 3989 8062 3990 8062 3990 8063 3989 8063 3984 8063 3990 8064 4236 8064 3991 8064 3991 8065 4236 8065 3992 8065 3991 8066 3992 8066 3380 8066 3380 8067 3992 8067 4153 8067 3380 8068 4153 8068 3384 8068 3384 8069 4153 8069 3993 8069 3384 8070 3993 8070 3396 8070 3396 8071 3993 8071 3393 8071 3393 8072 3993 8072 3994 8072 3393 8073 3994 8073 3399 8073 3399 8074 3994 8074 4196 8074 3399 8075 4196 8075 3995 8075 4003 8076 4004 8076 3996 8076 3996 8077 4004 8077 4185 8077 3996 8078 4185 8078 3997 8078 3997 8079 4185 8079 4184 8079 3997 8080 4184 8080 3988 8080 3988 8081 4184 8081 4187 8081 4006 8082 3866 8082 3998 8082 4006 8083 3998 8083 3999 8083 3999 8084 3998 8084 4001 8084 3999 8085 4001 8085 4000 8085 3995 8086 4196 8086 3878 8086 3878 8087 4196 8087 4000 8087 3878 8088 4000 8088 3865 8088 3865 8089 4000 8089 4001 8089 4002 8090 4182 8090 4003 8090 4003 8091 4182 8091 4004 8091 4011 8092 4005 8092 4006 8092 4006 8093 4005 8093 3866 8093 3280 8094 4179 8094 3422 8094 3422 8095 4179 8095 4178 8095 3422 8096 4178 8096 4007 8096 4007 8097 4178 8097 4183 8097 4007 8098 4183 8098 4002 8098 4002 8099 4183 8099 4182 8099 4008 8100 3294 8100 3296 8100 4008 8101 3296 8101 4009 8101 4009 8102 3296 8102 4010 8102 4009 8103 4010 8103 4263 8103 4263 8104 4010 8104 4005 8104 4263 8105 4005 8105 4011 8105 3281 8106 4180 8106 3280 8106 3280 8107 4180 8107 4179 8107 4014 8108 3418 8108 4008 8108 4008 8109 3418 8109 3294 8109 4180 8110 3281 8110 4012 8110 4180 8111 4012 8111 4181 8111 4181 8112 4012 8112 4013 8112 4181 8113 4013 8113 4173 8113 4173 8114 4013 8114 4016 8114 4173 8115 4016 8115 4172 8115 3418 8116 4014 8116 3417 8116 3417 8117 4014 8117 4198 8117 3417 8118 4198 8118 4015 8118 4015 8119 4198 8119 4140 8119 4015 8120 4140 8120 3416 8120 3416 8121 4140 8121 4018 8121 4172 8122 4016 8122 4017 8122 4017 8123 4016 8123 3282 8123 4017 8124 3282 8124 4020 8124 4026 8125 3414 8125 4018 8125 4018 8126 3414 8126 3416 8126 4020 8127 3282 8127 4019 8127 4020 8128 4019 8128 4021 8128 4021 8129 4019 8129 3876 8129 4021 8130 3876 8130 4023 8130 4022 8131 4030 8131 3354 8131 3354 8132 4030 8132 4023 8132 3354 8133 4023 8133 4024 8133 4024 8134 4023 8134 3876 8134 3414 8135 4026 8135 4025 8135 4025 8136 4026 8136 4027 8136 4025 8137 4027 8137 3413 8137 3413 8138 4027 8138 4028 8138 3413 8139 4028 8139 4034 8139 4034 8140 4028 8140 4029 8140 4030 8141 4022 8141 3353 8141 4030 8142 3353 8142 4232 8142 4232 8143 3353 8143 3345 8143 4232 8144 3345 8144 4253 8144 4253 8145 3345 8145 4163 8145 4163 8146 3345 8146 3336 8146 4163 8147 3336 8147 4031 8147 4031 8148 3336 8148 4032 8148 4031 8149 4032 8149 4033 8149 4032 8150 3319 8150 4033 8150 4033 8151 3319 8151 3320 8151 4033 8152 3320 8152 4211 8152 4211 8153 3320 8153 3308 8153 4211 8154 3308 8154 4212 8154 4210 8155 4042 8155 4029 8155 4029 8156 4042 8156 4034 8156 3308 8157 3930 8157 4212 8157 4212 8158 3930 8158 4035 8158 3930 8159 3869 8159 4035 8159 4035 8160 3869 8160 4036 8160 4035 8161 4036 8161 4213 8161 4036 8162 3868 8162 4213 8162 4213 8163 3868 8163 4043 8163 4213 8164 4043 8164 4037 8164 4044 8165 3298 8165 4038 8165 4044 8166 4038 8166 4039 8166 4039 8167 4038 8167 4040 8167 4039 8168 4040 8168 4041 8168 4041 8169 4040 8169 4042 8169 4041 8170 4042 8170 4210 8170 3298 8171 4044 8171 4043 8171 4043 8172 4044 8172 4037 8172 4054 8173 4215 8173 3040 8173 3040 8174 4215 8174 4045 8174 3040 8175 4045 8175 3042 8175 3042 8176 4045 8176 4219 8176 3042 8177 4219 8177 3036 8177 3036 8178 4219 8178 4046 8178 3036 8179 4046 8179 3038 8179 3038 8180 4046 8180 4047 8180 3038 8181 4047 8181 4048 8181 4048 8182 4047 8182 4221 8182 4048 8183 4221 8183 3039 8183 3039 8184 4221 8184 4049 8184 4050 8185 4056 8185 3019 8185 3019 8186 4056 8186 4052 8186 3019 8187 4052 8187 4051 8187 4051 8188 4052 8188 4053 8188 4051 8189 4053 8189 3040 8189 3040 8190 4053 8190 4054 8190 4220 8191 3034 8191 4049 8191 4049 8192 3034 8192 3039 8192 4058 8193 4055 8193 4050 8193 4050 8194 4055 8194 4056 8194 4217 8195 3029 8195 4218 8195 4218 8196 3029 8196 3028 8196 4218 8197 3028 8197 4057 8197 3034 8198 4220 8198 3025 8198 3025 8199 4220 8199 4057 8199 3025 8200 4057 8200 3026 8200 3026 8201 4057 8201 3028 8201 4059 8202 4055 8202 4058 8202 4058 8203 3023 8203 4059 8203 4059 8204 3023 8204 4060 8204 4059 8205 4060 8205 4061 8205 4061 8206 4060 8206 4064 8206 4061 8207 4064 8207 4062 8207 4065 8208 4239 8208 3021 8208 3021 8209 4239 8209 4062 8209 3021 8210 4062 8210 4063 8210 4063 8211 4062 8211 4064 8211 4248 8212 4239 8212 4065 8212 4248 8213 4065 8213 4216 8213 4216 8214 4065 8214 3029 8214 4216 8215 3029 8215 4217 8215 4066 8216 3272 8216 3050 8216 3053 8217 3010 8217 3011 8217 3011 8218 4067 8218 3053 8218 3053 8219 4067 8219 4068 8219 3053 8220 4068 8220 4069 8220 4066 8221 3050 8221 3049 8221 3049 8222 3050 8222 4069 8222 3049 8223 4069 8223 3009 8223 3009 8224 4069 8224 4068 8224 3009 8225 4068 8225 3013 8225 3045 8226 3288 8226 3290 8226 4071 8227 3008 8227 4070 8227 4070 8228 3014 8228 4071 8228 4071 8229 3014 8229 4072 8229 4071 8230 4072 8230 4073 8230 3045 8231 3290 8231 4074 8231 4074 8232 3290 8232 4073 8232 4074 8233 4073 8233 4075 8233 4075 8234 4073 8234 4072 8234 4075 8235 4072 8235 4076 8235 2997 8236 4077 8236 4083 8236 4083 8237 4077 8237 2998 8237 4083 8238 2998 8238 2999 8238 4078 8239 4079 8239 4083 8239 4083 8240 4079 8240 4080 8240 4083 8241 4080 8241 2997 8241 4081 8242 4082 8242 4083 8242 4083 8243 4082 8243 2994 8243 4083 8244 2994 8244 4078 8244 2999 8245 3000 8245 4083 8245 4083 8246 3000 8246 3002 8246 4083 8247 3002 8247 4081 8247 4089 8248 4085 8248 4084 8248 4084 8249 4085 8249 2988 8249 4084 8250 2988 8250 4086 8250 4087 8251 2985 8251 4084 8251 4084 8252 2985 8252 4088 8252 4084 8253 4088 8253 4089 8253 2991 8254 4090 8254 4084 8254 4084 8255 4090 8255 2993 8255 4084 8256 2993 8256 4087 8256 4086 8257 4091 8257 4084 8257 4084 8258 4091 8258 2990 8258 4084 8259 2990 8259 2991 8259 4095 8260 4093 8260 4092 8260 4092 8261 4093 8261 2975 8261 4092 8262 2975 8262 2977 8262 4098 8263 4094 8263 4092 8263 4092 8264 4094 8264 2973 8264 4092 8265 2973 8265 4095 8265 4096 8266 4097 8266 4092 8266 4092 8267 4097 8267 2972 8267 4092 8268 2972 8268 4098 8268 2977 8269 2978 8269 4092 8269 4092 8270 2978 8270 2979 8270 4092 8271 2979 8271 4096 8271 2965 8272 2966 8272 4101 8272 4101 8273 2966 8273 4099 8273 4101 8274 4099 8274 4102 8274 2961 8275 2963 8275 4101 8275 4101 8276 2963 8276 2964 8276 4101 8277 2964 8277 2965 8277 2970 8278 4100 8278 4101 8278 4101 8279 4100 8279 2971 8279 4101 8280 2971 8280 2961 8280 4102 8281 2968 8281 4101 8281 4101 8282 2968 8282 2969 8282 4101 8283 2969 8283 2970 8283 2954 8284 4103 8284 4104 8284 4104 8285 4103 8285 2957 8285 4104 8286 2957 8286 2958 8286 2949 8287 2951 8287 4104 8287 4104 8288 2951 8288 2952 8288 4104 8289 2952 8289 2954 8289 4107 8290 2959 8290 4104 8290 4104 8291 2959 8291 2960 8291 4104 8292 2960 8292 2949 8292 2958 8293 4105 8293 4104 8293 4104 8294 4105 8294 4106 8294 4104 8295 4106 8295 4107 8295 4108 8296 2937 8296 4110 8296 4110 8297 2937 8297 2939 8297 4110 8298 2939 8298 4111 8298 2933 8299 2934 8299 4110 8299 4110 8300 2934 8300 4109 8300 4110 8301 4109 8301 4108 8301 2944 8302 2945 8302 4110 8302 4110 8303 2945 8303 2946 8303 4110 8304 2946 8304 2933 8304 4111 8305 2941 8305 4110 8305 4110 8306 2941 8306 2943 8306 4110 8307 2943 8307 2944 8307 4112 8308 4137 8308 4113 8308 4113 8309 4137 8309 4114 8309 4113 8310 4114 8310 3126 8310 3126 8311 4114 8311 4115 8311 4115 8312 4114 8312 4223 8312 4115 8313 4223 8313 3127 8313 3127 8314 4223 8314 4116 8314 3127 8315 4116 8315 4117 8315 4117 8316 4116 8316 4222 8316 4117 8317 4222 8317 3129 8317 3129 8318 4222 8318 4118 8318 3129 8319 4118 8319 4120 8319 3129 8320 4120 8320 3130 8320 4142 8321 3132 8321 4141 8321 4141 8322 3132 8322 4119 8322 4141 8323 4119 8323 4157 8323 4157 8324 4119 8324 3130 8324 4157 8325 3130 8325 4156 8325 4156 8326 3130 8326 4120 8326 3132 8327 4142 8327 3121 8327 3121 8328 4142 8328 4146 8328 3121 8329 4146 8329 4121 8329 4121 8330 4146 8330 4122 8330 4121 8331 4122 8331 4123 8331 4123 8332 4122 8332 4149 8332 4123 8333 4149 8333 4124 8333 4124 8334 4149 8334 4148 8334 4150 8335 3123 8335 4148 8335 4148 8336 3123 8336 4125 8336 4148 8337 4125 8337 4124 8337 3123 8338 4150 8338 3119 8338 3119 8339 4150 8339 4126 8339 3119 8340 4126 8340 4127 8340 4127 8341 4126 8341 4151 8341 4127 8342 4151 8342 4128 8342 4128 8343 4151 8343 4147 8343 4128 8344 4147 8344 4129 8344 4129 8345 4147 8345 4130 8345 4129 8346 4130 8346 4132 8346 4130 8347 4229 8347 4132 8347 4132 8348 4229 8348 4131 8348 4132 8349 4131 8349 4133 8349 4133 8350 4131 8350 4139 8350 4133 8351 4139 8351 4135 8351 4133 8352 4135 8352 4134 8352 4134 8353 4135 8353 4257 8353 4134 8354 4257 8354 3124 8354 3124 8355 4257 8355 4136 8355 3124 8356 4136 8356 3125 8356 3125 8357 4136 8357 4225 8357 3125 8358 4225 8358 4112 8358 4112 8359 4225 8359 4137 8359 3806 8360 3804 8360 4163 8360 4138 8361 4233 8361 4240 8361 4135 8362 4139 8362 4250 8362 4203 8363 3735 8363 4265 8363 4140 8364 4198 8364 4159 8364 4261 8365 3790 8365 4228 8365 4146 8366 4142 8366 4145 8366 4142 8367 4141 8367 4143 8367 4145 8368 4142 8368 4144 8368 4144 8369 4142 8369 4143 8369 4144 8370 4143 8370 3757 8370 3992 8371 3750 8371 4153 8371 4153 8372 3750 8372 4152 8372 3753 8373 4149 8373 4145 8373 4145 8374 4149 8374 4122 8374 4145 8375 4122 8375 4146 8375 4151 8376 3992 8376 4147 8376 4147 8377 3992 8377 4240 8377 4147 8378 4240 8378 4130 8378 3751 8379 4150 8379 3753 8379 3753 8380 4150 8380 4148 8380 3753 8381 4148 8381 4149 8381 3751 8382 3750 8382 4150 8382 4150 8383 3750 8383 3992 8383 4150 8384 3992 8384 4126 8384 4126 8385 3992 8385 4151 8385 4152 8386 3763 8386 4153 8386 4153 8387 3763 8387 4154 8387 4153 8388 4154 8388 3993 8388 3993 8389 4154 8389 3761 8389 3757 8390 4143 8390 4155 8390 4155 8391 4143 8391 4259 8391 4155 8392 4259 8392 3759 8392 3788 8393 3787 8393 4156 8393 4156 8394 3787 8394 3786 8394 4156 8395 3786 8395 4157 8395 3786 8396 3785 8396 4157 8396 4157 8397 3785 8397 3797 8397 4157 8398 3797 8398 4258 8398 3797 8399 4158 8399 4258 8399 4258 8400 4158 8400 3796 8400 4258 8401 3796 8401 4159 8401 4159 8402 3796 8402 3794 8402 4159 8403 3794 8403 4201 8403 4201 8404 3794 8404 4160 8404 4201 8405 4160 8405 3793 8405 4224 8406 4161 8406 3813 8406 4224 8407 3813 8407 4226 8407 4161 8408 4224 8408 3814 8408 3814 8409 4224 8409 4163 8409 3814 8410 4163 8410 4162 8410 4162 8411 4163 8411 4031 8411 4162 8412 4031 8412 4169 8412 3813 8413 4164 8413 4226 8413 4226 8414 4164 8414 3822 8414 4226 8415 3822 8415 4165 8415 4165 8416 4166 8416 4260 8416 4260 8417 4166 8417 4167 8417 4260 8418 4167 8418 4033 8418 4033 8419 4167 8419 4168 8419 4033 8420 4168 8420 4031 8420 4031 8421 4168 8421 3819 8421 4031 8422 3819 8422 4169 8422 3659 8423 3658 8423 4174 8423 3658 8424 3657 8424 4174 8424 4174 8425 3657 8425 3656 8425 4174 8426 3656 8426 4017 8426 3656 8427 4170 8427 4017 8427 4017 8428 4170 8428 4171 8428 4017 8429 4171 8429 4172 8429 4172 8430 4171 8430 3654 8430 4172 8431 3654 8431 4173 8431 3659 8432 4174 8432 4175 8432 4175 8433 4174 8433 4176 8433 4175 8434 4176 8434 4177 8434 4177 8435 4176 8435 4178 8435 4177 8436 4178 8436 3661 8436 3661 8437 4178 8437 4179 8437 3661 8438 4179 8438 3651 8438 3651 8439 4179 8439 3652 8439 3652 8440 4179 8440 4180 8440 3652 8441 4180 8441 3654 8441 3654 8442 4180 8442 4181 8442 3654 8443 4181 8443 4173 8443 4004 8444 4182 8444 4176 8444 4176 8445 4182 8445 4183 8445 4176 8446 4183 8446 4178 8446 4184 8447 4185 8447 4186 8447 4186 8448 4185 8448 4004 8448 4192 8449 4191 8449 4189 8449 4189 8450 4191 8450 3980 8450 4187 8451 3616 8451 4188 8451 4188 8452 3616 8452 3615 8452 4188 8453 3615 8453 3983 8453 3983 8454 3615 8454 4189 8454 3983 8455 4189 8455 3981 8455 3981 8456 4189 8456 3980 8456 3625 8457 4193 8457 4190 8457 4190 8458 4193 8458 4191 8458 4190 8459 4191 8459 3614 8459 3614 8460 4191 8460 4192 8460 3625 8461 3624 8461 4193 8461 4193 8462 3624 8462 4194 8462 4193 8463 4194 8463 4186 8463 4186 8464 4194 8464 4195 8464 4186 8465 4195 8465 4184 8465 4184 8466 4195 8466 3620 8466 4184 8467 3620 8467 4187 8467 4187 8468 3620 8468 3619 8468 4187 8469 3619 8469 3616 8469 4011 8470 4006 8470 3994 8470 3999 8471 4000 8471 4006 8471 4006 8472 4000 8472 4196 8472 4006 8473 4196 8473 3994 8473 4197 8474 4199 8474 4259 8474 4014 8475 3693 8475 4198 8475 4198 8476 3693 8476 3691 8476 4198 8477 3691 8477 4159 8477 4197 8478 4259 8478 3690 8478 4009 8479 4262 8479 4008 8479 4008 8480 4262 8480 3699 8480 4199 8481 3686 8481 4259 8481 4259 8482 3686 8482 3702 8482 4259 8483 3702 8483 4262 8483 4262 8484 3702 8484 4200 8484 4262 8485 4200 8485 3699 8485 3699 8486 3697 8486 4008 8486 4008 8487 3697 8487 3696 8487 4008 8488 3696 8488 4014 8488 4014 8489 3696 8489 3694 8489 4014 8490 3694 8490 3693 8490 4028 8491 4027 8491 4201 8491 4201 8492 4027 8492 4026 8492 4201 8493 4026 8493 4159 8493 4159 8494 4026 8494 4018 8494 4159 8495 4018 8495 4140 8495 3735 8496 3733 8496 4264 8496 4210 8497 4202 8497 4265 8497 4265 8498 4202 8498 3736 8498 4265 8499 3736 8499 4203 8499 3733 8500 4204 8500 4264 8500 4264 8501 4204 8501 4205 8501 4264 8502 4205 8502 4201 8502 4201 8503 4205 8503 4206 8503 4201 8504 4206 8504 4028 8504 4028 8505 4206 8505 3731 8505 4028 8506 3731 8506 4029 8506 3731 8507 4207 8507 4029 8507 4029 8508 4207 8508 4208 8508 4029 8509 4208 8509 4210 8509 4210 8510 4208 8510 4209 8510 4210 8511 4209 8511 4202 8511 4041 8512 4210 8512 4039 8512 4039 8513 4210 8513 4265 8513 4039 8514 4265 8514 4044 8514 4044 8515 4265 8515 4266 8515 4044 8516 4266 8516 4037 8516 4266 8517 4211 8517 4212 8517 4212 8518 4035 8518 4266 8518 4266 8519 4035 8519 4213 8519 4266 8520 4213 8520 4037 8520 4059 8521 4061 8521 4214 8521 4214 8522 4061 8522 4062 8522 4004 8523 4176 8523 4186 8523 4186 8524 4176 8524 4215 8524 4186 8525 4215 8525 4193 8525 4193 8526 4215 8526 4054 8526 4193 8527 4054 8527 4053 8527 4053 8528 4052 8528 4193 8528 4193 8529 4052 8529 4056 8529 4193 8530 4056 8530 4214 8530 4214 8531 4056 8531 4055 8531 4214 8532 4055 8532 4059 8532 4216 8533 4217 8533 4230 8533 4230 8534 4217 8534 4218 8534 4230 8535 4218 8535 4057 8535 4047 8536 4046 8536 4174 8536 4174 8537 4046 8537 4219 8537 4174 8538 4219 8538 4176 8538 4176 8539 4219 8539 4045 8539 4176 8540 4045 8540 4215 8540 4057 8541 4220 8541 4230 8541 4230 8542 4220 8542 4049 8542 4230 8543 4049 8543 4174 8543 4174 8544 4049 8544 4221 8544 4174 8545 4221 8545 4047 8545 4222 8546 4116 8546 4226 8546 4225 8547 4136 8547 4224 8547 4224 8548 4136 8548 4257 8548 4116 8549 4223 8549 4226 8549 4226 8550 4223 8550 4114 8550 4226 8551 4114 8551 4224 8551 4224 8552 4114 8552 4137 8552 4224 8553 4137 8553 4225 8553 4222 8554 4226 8554 4118 8554 4118 8555 4226 8555 4227 8555 4118 8556 4227 8556 4120 8556 4120 8557 4227 8557 4228 8557 4120 8558 4228 8558 4156 8558 4156 8559 4228 8559 3790 8559 4156 8560 3790 8560 3788 8560 4243 8561 4249 8561 4229 8561 4229 8562 4249 8562 4131 8562 4017 8563 4020 8563 4174 8563 4174 8564 4020 8564 4231 8564 4174 8565 4231 8565 4230 8565 4230 8566 4231 8566 4255 8566 4230 8567 4255 8567 4250 8567 4021 8568 4023 8568 4020 8568 4020 8569 4023 8569 4030 8569 4020 8570 4030 8570 4231 8570 4231 8571 4030 8571 4232 8571 4231 8572 4232 8572 4255 8572 4255 8573 4232 8573 4253 8573 4240 8574 4233 8574 4214 8574 4214 8575 4233 8575 4234 8575 4214 8576 4234 8576 3740 8576 3986 8577 4235 8577 3984 8577 3984 8578 4235 8578 4191 8578 3984 8579 4191 8579 3990 8579 3990 8580 4191 8580 4193 8580 3990 8581 4193 8581 4236 8581 4236 8582 4193 8582 4214 8582 4236 8583 4214 8583 3739 8583 3739 8584 4214 8584 3740 8584 4238 8585 3746 8585 3992 8585 3992 8586 3746 8586 3744 8586 3992 8587 3744 8587 4240 8587 4240 8588 3744 8588 4237 8588 4240 8589 4237 8589 4138 8589 3739 8590 3738 8590 4236 8590 4236 8591 3738 8591 3737 8591 4236 8592 3737 8592 3992 8592 3992 8593 3737 8593 3749 8593 3992 8594 3749 8594 4238 8594 4062 8595 4239 8595 4214 8595 4214 8596 4239 8596 4241 8596 4214 8597 4241 8597 4240 8597 4240 8598 4241 8598 4243 8598 4240 8599 4243 8599 4130 8599 4130 8600 4243 8600 4229 8600 3764 8601 4242 8601 4241 8601 4241 8602 4242 8602 4243 8602 4243 8603 4242 8603 3780 8603 4243 8604 3780 8604 3779 8604 3779 8605 3777 8605 4243 8605 4243 8606 3777 8606 4244 8606 4243 8607 4244 8607 4249 8607 4249 8608 4244 8608 3775 8608 3764 8609 4241 8609 4245 8609 4245 8610 4241 8610 4246 8610 4245 8611 4246 8611 3768 8611 3775 8612 3771 8612 4249 8612 4249 8613 3771 8613 3770 8613 4249 8614 3770 8614 4246 8614 4246 8615 3770 8615 4247 8615 4246 8616 4247 8616 3768 8616 4239 8617 4248 8617 4241 8617 4241 8618 4248 8618 4216 8618 4241 8619 4216 8619 4246 8619 4246 8620 4216 8620 4230 8620 4246 8621 4230 8621 4249 8621 4249 8622 4230 8622 4250 8622 4249 8623 4250 8623 4131 8623 4131 8624 4250 8624 4139 8624 4163 8625 3804 8625 4253 8625 4256 8626 4251 8626 4224 8626 4251 8627 3811 8627 4224 8627 4224 8628 3811 8628 3809 8628 4224 8629 3809 8629 4163 8629 4163 8630 3809 8630 4252 8630 4163 8631 4252 8631 3806 8631 4255 8632 4254 8632 3798 8632 3804 8633 3803 8633 4253 8633 4253 8634 3803 8634 3802 8634 4253 8635 3802 8635 4255 8635 4255 8636 3802 8636 3800 8636 4255 8637 3800 8637 4254 8637 3798 8638 4256 8638 4255 8638 4255 8639 4256 8639 4224 8639 4255 8640 4224 8640 4250 8640 4250 8641 4224 8641 4257 8641 4250 8642 4257 8642 4135 8642 4141 8643 4157 8643 4143 8643 4143 8644 4157 8644 4258 8644 4143 8645 4258 8645 4259 8645 4259 8646 4258 8646 4159 8646 4259 8647 4159 8647 3690 8647 3690 8648 4159 8648 3691 8648 4165 8649 4260 8649 4226 8649 4226 8650 4260 8650 4264 8650 4226 8651 4264 8651 4227 8651 4227 8652 4264 8652 4201 8652 4227 8653 4201 8653 4228 8653 4228 8654 4201 8654 3793 8654 4228 8655 3793 8655 4261 8655 3761 8656 3759 8656 3993 8656 3993 8657 3759 8657 4259 8657 3993 8658 4259 8658 3994 8658 3994 8659 4259 8659 4262 8659 3994 8660 4262 8660 4011 8660 4011 8661 4262 8661 4009 8661 4011 8662 4009 8662 4263 8662 3735 8663 4264 8663 4265 8663 4265 8664 4264 8664 4260 8664 4265 8665 4260 8665 4266 8665 4266 8666 4260 8666 4033 8666 4266 8667 4033 8667 4211 8667 4298 8668 4292 8668 4293 8668 4267 8669 4268 8669 4275 8669 4275 8670 4268 8670 4291 8670 4269 8671 4270 8671 4271 8671 4272 8672 4300 8672 4273 8672 4273 8673 4300 8673 4274 8673 4273 8674 4274 8674 4296 8674 4296 8675 4274 8675 4298 8675 4296 8676 4298 8676 4294 8676 4294 8677 4298 8677 4293 8677 4271 8678 4297 8678 4269 8678 4269 8679 4297 8679 4298 8679 4269 8680 4298 8680 4291 8680 4291 8681 4298 8681 4274 8681 4291 8682 4274 8682 4275 8682 4289 8683 4276 8683 4286 8683 4277 8684 4278 8684 4276 8684 4276 8685 4278 8685 4279 8685 4276 8686 4279 8686 4286 8686 4295 8687 4280 8687 4286 8687 4286 8688 4280 8688 4281 8688 4282 8689 4288 8689 4283 8689 4283 8690 4288 8690 4287 8690 4283 8691 4287 8691 4299 8691 4290 8692 4284 8692 4285 8692 4285 8693 4284 8693 4289 8693 4285 8694 4289 8694 4287 8694 4287 8695 4289 8695 4286 8695 4287 8696 4286 8696 4299 8696 4299 8697 4286 8697 4281 8697 4283 8698 4297 8698 4282 8698 4282 8699 4297 8699 4271 8699 4282 8700 4271 8700 4288 8700 4288 8701 4271 8701 4270 8701 4288 8702 4270 8702 4287 8702 4287 8703 4270 8703 4269 8703 4275 8704 4289 8704 4267 8704 4267 8705 4289 8705 4284 8705 4267 8706 4284 8706 4268 8706 4268 8707 4284 8707 4290 8707 4268 8708 4290 8708 4291 8708 4291 8709 4290 8709 4285 8709 4285 8710 4287 8710 4291 8710 4291 8711 4287 8711 4269 8711 4298 8712 4299 8712 4292 8712 4292 8713 4299 8713 4281 8713 4292 8714 4281 8714 4293 8714 4293 8715 4281 8715 4280 8715 4293 8716 4280 8716 4294 8716 4294 8717 4280 8717 4295 8717 4294 8718 4295 8718 4296 8718 4296 8719 4295 8719 4286 8719 4297 8720 4283 8720 4298 8720 4298 8721 4283 8721 4299 8721 4276 8722 4274 8722 4277 8722 4277 8723 4274 8723 4300 8723 4277 8724 4300 8724 4278 8724 4278 8725 4300 8725 4272 8725 4278 8726 4272 8726 4279 8726 4279 8727 4272 8727 4273 8727 4296 8728 4286 8728 4273 8728 4273 8729 4286 8729 4279 8729 4276 8730 4289 8730 4274 8730 4274 8731 4289 8731 4275 8731 4304 8732 4301 8732 4328 8732 4306 8733 4302 8733 4303 8733 4303 8734 4302 8734 4310 8734 4303 8735 4310 8735 4309 8735 4328 8736 4305 8736 4304 8736 4304 8737 4305 8737 4302 8737 4304 8738 4302 8738 4307 8738 4307 8739 4302 8739 4306 8739 4307 8740 4306 8740 4323 8740 4324 8741 4326 8741 4308 8741 4308 8742 4326 8742 4309 8742 4308 8743 4309 8743 4334 8743 4334 8744 4309 8744 4310 8744 4334 8745 4310 8745 4331 8745 4331 8746 4310 8746 4311 8746 4315 8747 4322 8747 4319 8747 4319 8748 4322 8748 4312 8748 4319 8749 4312 8749 4313 8749 4329 8750 4314 8750 4330 8750 4330 8751 4314 8751 4316 8751 4330 8752 4316 8752 4315 8752 4315 8753 4316 8753 4322 8753 4322 8754 4316 8754 4321 8754 4322 8755 4321 8755 4317 8755 4318 8756 4332 8756 4333 8756 4333 8757 4332 8757 4319 8757 4333 8758 4319 8758 4320 8758 4320 8759 4319 8759 4313 8759 4320 8760 4313 8760 4325 8760 4325 8761 4313 8761 4327 8761 4321 8762 4307 8762 4317 8762 4317 8763 4307 8763 4323 8763 4317 8764 4323 8764 4322 8764 4322 8765 4323 8765 4306 8765 4322 8766 4306 8766 4312 8766 4312 8767 4306 8767 4303 8767 4308 8768 4320 8768 4324 8768 4324 8769 4320 8769 4325 8769 4324 8770 4325 8770 4326 8770 4326 8771 4325 8771 4327 8771 4326 8772 4327 8772 4309 8772 4309 8773 4327 8773 4313 8773 4313 8774 4312 8774 4309 8774 4309 8775 4312 8775 4303 8775 4304 8776 4316 8776 4301 8776 4301 8777 4316 8777 4314 8777 4301 8778 4314 8778 4328 8778 4328 8779 4314 8779 4329 8779 4328 8780 4329 8780 4305 8780 4305 8781 4329 8781 4330 8781 4305 8782 4330 8782 4302 8782 4302 8783 4330 8783 4315 8783 4307 8784 4321 8784 4304 8784 4304 8785 4321 8785 4316 8785 4333 8786 4334 8786 4318 8786 4318 8787 4334 8787 4331 8787 4318 8788 4331 8788 4332 8788 4332 8789 4331 8789 4311 8789 4332 8790 4311 8790 4319 8790 4319 8791 4311 8791 4310 8791 4302 8792 4315 8792 4310 8792 4310 8793 4315 8793 4319 8793 4333 8794 4320 8794 4334 8794 4334 8795 4320 8795 4308 8795 4336 8796 4369 8796 4335 8796 4343 8797 4364 8797 4342 8797 4344 8798 4376 8798 4381 8798 4361 8799 4336 8799 4337 8799 4337 8800 4336 8800 4335 8800 4337 8801 4335 8801 4338 8801 4338 8802 4335 8802 4339 8802 4338 8803 4339 8803 4340 8803 4340 8804 4339 8804 4374 8804 4340 8805 4374 8805 4344 8805 4345 8806 4358 8806 4357 8806 4341 8807 4376 8807 4378 8807 4378 8808 4376 8808 4344 8808 4378 8809 4344 8809 4380 8809 4380 8810 4344 8810 4374 8810 4361 8811 4337 8811 4342 8811 4342 8812 4337 8812 4367 8812 4342 8813 4367 8813 4343 8813 4381 8814 4382 8814 4344 8814 4344 8815 4382 8815 4345 8815 4344 8816 4345 8816 4355 8816 4355 8817 4345 8817 4357 8817 4370 8818 4373 8818 4346 8818 4370 8819 4346 8819 4347 8819 4366 8820 4346 8820 4365 8820 4365 8821 4346 8821 4373 8821 4365 8822 4373 8822 4363 8822 4363 8823 4373 8823 4362 8823 4360 8824 4375 8824 4350 8824 4350 8825 4375 8825 4348 8825 4350 8826 4348 8826 4377 8826 4377 8827 4349 8827 4350 8827 4350 8828 4349 8828 4379 8828 4350 8829 4379 8829 4368 8829 4368 8830 4379 8830 4351 8830 4368 8831 4351 8831 4352 8831 4352 8832 4351 8832 4372 8832 4352 8833 4372 8833 4346 8833 4346 8834 4372 8834 4371 8834 4346 8835 4371 8835 4347 8835 4350 8836 4353 8836 4354 8836 4360 8837 4350 8837 4359 8837 4359 8838 4350 8838 4354 8838 4359 8839 4354 8839 4356 8839 4350 8840 4344 8840 4353 8840 4353 8841 4344 8841 4355 8841 4353 8842 4355 8842 4354 8842 4354 8843 4355 8843 4357 8843 4354 8844 4357 8844 4356 8844 4356 8845 4357 8845 4358 8845 4356 8846 4358 8846 4359 8846 4359 8847 4358 8847 4345 8847 4359 8848 4345 8848 4360 8848 4360 8849 4345 8849 4382 8849 4373 8850 4361 8850 4362 8850 4362 8851 4361 8851 4342 8851 4362 8852 4342 8852 4363 8852 4363 8853 4342 8853 4364 8853 4363 8854 4364 8854 4365 8854 4365 8855 4364 8855 4343 8855 4365 8856 4343 8856 4366 8856 4366 8857 4343 8857 4367 8857 4366 8858 4367 8858 4346 8858 4346 8859 4367 8859 4337 8859 4346 8860 4337 8860 4338 8860 4346 8861 4338 8861 4352 8861 4352 8862 4338 8862 4340 8862 4352 8863 4340 8863 4368 8863 4368 8864 4340 8864 4344 8864 4368 8865 4344 8865 4350 8865 4336 8866 4370 8866 4369 8866 4369 8867 4370 8867 4347 8867 4369 8868 4347 8868 4335 8868 4335 8869 4347 8869 4371 8869 4335 8870 4371 8870 4339 8870 4339 8871 4371 8871 4372 8871 4361 8872 4373 8872 4336 8872 4336 8873 4373 8873 4370 8873 4339 8874 4372 8874 4374 8874 4374 8875 4372 8875 4351 8875 4375 8876 4381 8876 4348 8876 4348 8877 4381 8877 4376 8877 4348 8878 4376 8878 4377 8878 4377 8879 4376 8879 4341 8879 4377 8880 4341 8880 4349 8880 4349 8881 4341 8881 4378 8881 4349 8882 4378 8882 4379 8882 4379 8883 4378 8883 4380 8883 4380 8884 4374 8884 4379 8884 4379 8885 4374 8885 4351 8885 4375 8886 4360 8886 4381 8886 4381 8887 4360 8887 4382 8887 4383 8888 4423 8888 4420 8888 4420 8889 4423 8889 4387 8889 4413 8890 4389 8890 4412 8890 4412 8891 4389 8891 4383 8891 4412 8892 4383 8892 4410 8892 4410 8893 4383 8893 4420 8893 4423 8894 4384 8894 4387 8894 4387 8895 4384 8895 4422 8895 4387 8896 4422 8896 4385 8896 4386 8897 4419 8897 4416 8897 4416 8898 4419 8898 4387 8898 4416 8899 4387 8899 4421 8899 4421 8900 4387 8900 4385 8900 4406 8901 4388 8901 4415 8901 4415 8902 4388 8902 4404 8902 4415 8903 4404 8903 4389 8903 4389 8904 4404 8904 4409 8904 4389 8905 4409 8905 4383 8905 4383 8906 4409 8906 4408 8906 4390 8907 4391 8907 4394 8907 4392 8908 4418 8908 4391 8908 4391 8909 4418 8909 4417 8909 4393 8910 4394 8910 4395 8910 4395 8911 4394 8911 4391 8911 4395 8912 4391 8912 4396 8912 4396 8913 4391 8913 4417 8913 4407 8914 4398 8914 4397 8914 4397 8915 4398 8915 4399 8915 4397 8916 4399 8916 4400 8916 4403 8917 4405 8917 4401 8917 4394 8918 4424 8918 4390 8918 4390 8919 4424 8919 4397 8919 4390 8920 4397 8920 4411 8920 4411 8921 4397 8921 4400 8921 4407 8922 4402 8922 4398 8922 4398 8923 4402 8923 4403 8923 4398 8924 4403 8924 4414 8924 4414 8925 4403 8925 4401 8925 4403 8926 4404 8926 4405 8926 4405 8927 4404 8927 4388 8927 4405 8928 4388 8928 4401 8928 4401 8929 4388 8929 4406 8929 4401 8930 4406 8930 4414 8930 4414 8931 4406 8931 4415 8931 4397 8932 4383 8932 4407 8932 4407 8933 4383 8933 4408 8933 4407 8934 4408 8934 4402 8934 4402 8935 4408 8935 4409 8935 4404 8936 4403 8936 4409 8936 4409 8937 4403 8937 4402 8937 4420 8938 4390 8938 4410 8938 4410 8939 4390 8939 4411 8939 4410 8940 4411 8940 4412 8940 4412 8941 4411 8941 4400 8941 4412 8942 4400 8942 4413 8942 4413 8943 4400 8943 4399 8943 4413 8944 4399 8944 4389 8944 4389 8945 4399 8945 4398 8945 4398 8946 4414 8946 4389 8946 4389 8947 4414 8947 4415 8947 4416 8948 4417 8948 4386 8948 4386 8949 4417 8949 4418 8949 4386 8950 4418 8950 4419 8950 4419 8951 4418 8951 4392 8951 4419 8952 4392 8952 4387 8952 4387 8953 4392 8953 4391 8953 4391 8954 4390 8954 4387 8954 4387 8955 4390 8955 4420 8955 4396 8956 4421 8956 4395 8956 4395 8957 4421 8957 4385 8957 4395 8958 4385 8958 4393 8958 4393 8959 4385 8959 4422 8959 4393 8960 4422 8960 4394 8960 4394 8961 4422 8961 4384 8961 4396 8962 4417 8962 4421 8962 4421 8963 4417 8963 4416 8963 4394 8964 4384 8964 4423 8964 4394 8965 4423 8965 4424 8965 4424 8966 4423 8966 4383 8966 4424 8967 4383 8967 4397 8967 4453 8968 4454 8968 4455 8968 4428 8969 4425 8969 4431 8969 4431 8970 4425 8970 4426 8970 4449 8971 4447 8971 4427 8971 4427 8972 4447 8972 4425 8972 4427 8973 4425 8973 4455 8973 4455 8974 4425 8974 4428 8974 4455 8975 4428 8975 4453 8975 4453 8976 4428 8976 4452 8976 4429 8977 4430 8977 4457 8977 4457 8978 4430 8978 4431 8978 4457 8979 4431 8979 4432 8979 4432 8980 4431 8980 4426 8980 4432 8981 4426 8981 4433 8981 4433 8982 4426 8982 4450 8982 4444 8983 4434 8983 4445 8983 4458 8984 4435 8984 4441 8984 4446 8985 4436 8985 4437 8985 4437 8986 4436 8986 4448 8986 4437 8987 4448 8987 4444 8987 4438 8988 4456 8988 4439 8988 4439 8989 4456 8989 4443 8989 4439 8990 4443 8990 4440 8990 4441 8991 4442 8991 4458 8991 4458 8992 4442 8992 4437 8992 4458 8993 4437 8993 4443 8993 4443 8994 4437 8994 4444 8994 4443 8995 4444 8995 4440 8995 4440 8996 4444 8996 4445 8996 4440 8997 4445 8997 4451 8997 4437 8998 4425 8998 4446 8998 4446 8999 4425 8999 4447 8999 4446 9000 4447 9000 4436 9000 4436 9001 4447 9001 4449 9001 4436 9002 4449 9002 4448 9002 4448 9003 4449 9003 4427 9003 4426 9004 4442 9004 4450 9004 4450 9005 4442 9005 4441 9005 4450 9006 4441 9006 4433 9006 4433 9007 4441 9007 4435 9007 4433 9008 4435 9008 4432 9008 4432 9009 4435 9009 4458 9009 4425 9010 4437 9010 4426 9010 4426 9011 4437 9011 4442 9011 4428 9012 4440 9012 4452 9012 4452 9013 4440 9013 4451 9013 4452 9014 4451 9014 4453 9014 4453 9015 4451 9015 4445 9015 4453 9016 4445 9016 4454 9016 4454 9017 4445 9017 4434 9017 4454 9018 4434 9018 4455 9018 4455 9019 4434 9019 4444 9019 4444 9020 4448 9020 4455 9020 4455 9021 4448 9021 4427 9021 4439 9022 4431 9022 4438 9022 4438 9023 4431 9023 4430 9023 4438 9024 4430 9024 4456 9024 4456 9025 4430 9025 4429 9025 4456 9026 4429 9026 4443 9026 4443 9027 4429 9027 4457 9027 4439 9028 4440 9028 4431 9028 4431 9029 4440 9029 4428 9029 4432 9030 4458 9030 4457 9030 4457 9031 4458 9031 4443 9031 4459 9032 4488 9032 4465 9032 4465 9033 4488 9033 4490 9033 4463 9034 4488 9034 4460 9034 4460 9035 4488 9035 4459 9035 4460 9036 4459 9036 4461 9036 4461 9037 4459 9037 4462 9037 4463 9038 4481 9038 4488 9038 4488 9039 4481 9039 4482 9039 4488 9040 4482 9040 4484 9040 4476 9041 4477 9041 4464 9041 4464 9042 4477 9042 4465 9042 4464 9043 4465 9043 4466 9043 4466 9044 4465 9044 4490 9044 4466 9045 4490 9045 4486 9045 4486 9046 4490 9046 4467 9046 4468 9047 4469 9047 4472 9047 4470 9048 4487 9048 4491 9048 4491 9049 4487 9049 4473 9049 4491 9050 4473 9050 4492 9050 4478 9051 4479 9051 4471 9051 4471 9052 4479 9052 4480 9052 4471 9053 4480 9053 4474 9053 4472 9054 4492 9054 4468 9054 4468 9055 4492 9055 4473 9055 4468 9056 4473 9056 4480 9056 4480 9057 4473 9057 4489 9057 4480 9058 4489 9058 4474 9058 4474 9059 4489 9059 4485 9059 4474 9060 4485 9060 4483 9060 4483 9061 4485 9061 4475 9061 4464 9062 4492 9062 4476 9062 4476 9063 4492 9063 4472 9063 4476 9064 4472 9064 4477 9064 4477 9065 4472 9065 4469 9065 4477 9066 4469 9066 4465 9066 4465 9067 4469 9067 4468 9067 4471 9068 4460 9068 4478 9068 4478 9069 4460 9069 4461 9069 4478 9070 4461 9070 4479 9070 4479 9071 4461 9071 4462 9071 4479 9072 4462 9072 4480 9072 4480 9073 4462 9073 4459 9073 4463 9074 4474 9074 4481 9074 4481 9075 4474 9075 4483 9075 4481 9076 4483 9076 4482 9076 4482 9077 4483 9077 4475 9077 4482 9078 4475 9078 4484 9078 4484 9079 4475 9079 4485 9079 4484 9080 4485 9080 4488 9080 4488 9081 4485 9081 4489 9081 4460 9082 4471 9082 4463 9082 4463 9083 4471 9083 4474 9083 4491 9084 4466 9084 4470 9084 4470 9085 4466 9085 4486 9085 4470 9086 4486 9086 4487 9086 4487 9087 4486 9087 4467 9087 4487 9088 4467 9088 4473 9088 4473 9089 4467 9089 4490 9089 4488 9090 4489 9090 4490 9090 4490 9091 4489 9091 4473 9091 4491 9092 4492 9092 4466 9092 4466 9093 4492 9093 4464 9093 4468 9094 4480 9094 4465 9094 4465 9095 4480 9095 4459 9095 4493 9096 4494 9096 4516 9096 4526 9097 4513 9097 4495 9097 4495 9098 4513 9098 4501 9098 4510 9099 4496 9099 4526 9099 4526 9100 4496 9100 4497 9100 4526 9101 4497 9101 4513 9101 4513 9102 4497 9102 4493 9102 4513 9103 4493 9103 4498 9103 4498 9104 4493 9104 4516 9104 4524 9105 4500 9105 4499 9105 4499 9106 4500 9106 4495 9106 4499 9107 4495 9107 4522 9107 4522 9108 4495 9108 4501 9108 4522 9109 4501 9109 4521 9109 4521 9110 4501 9110 4502 9110 4523 9111 4525 9111 4508 9111 4508 9112 4525 9112 4503 9112 4504 9113 4520 9113 4519 9113 4515 9114 4517 9114 4514 9114 4514 9115 4517 9115 4506 9115 4511 9116 4505 9116 4512 9116 4512 9117 4505 9117 4509 9117 4512 9118 4509 9118 4506 9118 4506 9119 4509 9119 4507 9119 4506 9120 4507 9120 4514 9120 4519 9121 4518 9121 4504 9121 4504 9122 4518 9122 4507 9122 4504 9123 4507 9123 4503 9123 4503 9124 4507 9124 4509 9124 4503 9125 4509 9125 4508 9125 4526 9126 4509 9126 4510 9126 4510 9127 4509 9127 4505 9127 4510 9128 4505 9128 4496 9128 4496 9129 4505 9129 4511 9129 4496 9130 4511 9130 4497 9130 4497 9131 4511 9131 4512 9131 4507 9132 4513 9132 4514 9132 4514 9133 4513 9133 4498 9133 4514 9134 4498 9134 4515 9134 4515 9135 4498 9135 4516 9135 4515 9136 4516 9136 4517 9136 4517 9137 4516 9137 4494 9137 4517 9138 4494 9138 4506 9138 4506 9139 4494 9139 4493 9139 4501 9140 4518 9140 4502 9140 4502 9141 4518 9141 4519 9141 4502 9142 4519 9142 4521 9142 4521 9143 4519 9143 4520 9143 4521 9144 4520 9144 4522 9144 4522 9145 4520 9145 4504 9145 4513 9146 4507 9146 4501 9146 4501 9147 4507 9147 4518 9147 4508 9148 4495 9148 4523 9148 4523 9149 4495 9149 4500 9149 4523 9150 4500 9150 4525 9150 4525 9151 4500 9151 4524 9151 4525 9152 4524 9152 4503 9152 4503 9153 4524 9153 4499 9153 4522 9154 4504 9154 4499 9154 4499 9155 4504 9155 4503 9155 4508 9156 4509 9156 4495 9156 4495 9157 4509 9157 4526 9157 4512 9158 4506 9158 4497 9158 4497 9159 4506 9159 4493 9159 4560 9160 4528 9160 4527 9160 4528 9161 4556 9161 4529 9161 4527 9162 4553 9162 4537 9162 4530 9163 4531 9163 4532 9163 4532 9164 4531 9164 4527 9164 4532 9165 4527 9165 4533 9165 4533 9166 4527 9166 4528 9166 4533 9167 4528 9167 4557 9167 4557 9168 4528 9168 4529 9168 4551 9169 4534 9169 4535 9169 4535 9170 4534 9170 4553 9170 4535 9171 4553 9171 4536 9171 4536 9172 4553 9172 4527 9172 4537 9173 4538 9173 4527 9173 4527 9174 4538 9174 4539 9174 4527 9175 4539 9175 4560 9175 4540 9176 4561 9176 4541 9176 4542 9177 4554 9177 4543 9177 4543 9178 4554 9178 4548 9178 4543 9179 4548 9179 4555 9179 4562 9180 4544 9180 4550 9180 4550 9181 4544 9181 4552 9181 4550 9182 4552 9182 4545 9182 4558 9183 4546 9183 4559 9183 4559 9184 4546 9184 4555 9184 4559 9185 4555 9185 4547 9185 4547 9186 4555 9186 4548 9186 4547 9187 4548 9187 4549 9187 4549 9188 4548 9188 4562 9188 4549 9189 4562 9189 4541 9189 4541 9190 4562 9190 4550 9190 4541 9191 4550 9191 4540 9191 4536 9192 4550 9192 4535 9192 4535 9193 4550 9193 4545 9193 4535 9194 4545 9194 4551 9194 4551 9195 4545 9195 4552 9195 4551 9196 4552 9196 4534 9196 4534 9197 4552 9197 4544 9197 4534 9198 4544 9198 4553 9198 4553 9199 4544 9199 4562 9199 4543 9200 4560 9200 4542 9200 4542 9201 4560 9201 4539 9201 4542 9202 4539 9202 4554 9202 4554 9203 4539 9203 4538 9203 4554 9204 4538 9204 4548 9204 4548 9205 4538 9205 4537 9205 4528 9206 4555 9206 4556 9206 4556 9207 4555 9207 4546 9207 4556 9208 4546 9208 4529 9208 4529 9209 4546 9209 4558 9209 4529 9210 4558 9210 4557 9210 4557 9211 4558 9211 4559 9211 4557 9212 4559 9212 4533 9212 4533 9213 4559 9213 4547 9213 4560 9214 4543 9214 4528 9214 4528 9215 4543 9215 4555 9215 4540 9216 4527 9216 4561 9216 4561 9217 4527 9217 4531 9217 4561 9218 4531 9218 4541 9218 4541 9219 4531 9219 4530 9219 4541 9220 4530 9220 4549 9220 4549 9221 4530 9221 4532 9221 4533 9222 4547 9222 4532 9222 4532 9223 4547 9223 4549 9223 4540 9224 4550 9224 4527 9224 4527 9225 4550 9225 4536 9225 4562 9226 4548 9226 4553 9226 4553 9227 4548 9227 4537 9227 4574 9228 4563 9228 4567 9228 4567 9229 4563 9229 4606 9229 4567 9230 4606 9230 4604 9230 4595 9231 4594 9231 4564 9231 4564 9232 4594 9232 4565 9232 4564 9233 4565 9233 4597 9233 4597 9234 4565 9234 4566 9234 4597 9235 4566 9235 4610 9235 4610 9236 4566 9236 4585 9236 4604 9237 4602 9237 4567 9237 4567 9238 4602 9238 4608 9238 4567 9239 4608 9239 4568 9239 4568 9240 4608 9240 4570 9240 4568 9241 4570 9241 4569 9241 4569 9242 4570 9242 4571 9242 4569 9243 4571 9243 4566 9243 4566 9244 4571 9244 4572 9244 4566 9245 4572 9245 4585 9245 4590 9246 4589 9246 4573 9246 4573 9247 4589 9247 4574 9247 4573 9248 4574 9248 4592 9248 4592 9249 4574 9249 4567 9249 4581 9250 4587 9250 4586 9250 4591 9251 4582 9251 4575 9251 4575 9252 4582 9252 4607 9252 4607 9253 4582 9253 4605 9253 4605 9254 4582 9254 4583 9254 4605 9255 4583 9255 4603 9255 4588 9256 4576 9256 4575 9256 4575 9257 4576 9257 4577 9257 4575 9258 4577 9258 4591 9258 4596 9259 4579 9259 4578 9259 4578 9260 4579 9260 4580 9260 4578 9261 4580 9261 4593 9261 4593 9262 4580 9262 4600 9262 4580 9263 4581 9263 4600 9263 4600 9264 4581 9264 4586 9264 4600 9265 4586 9265 4599 9265 4599 9266 4586 9266 4584 9266 4599 9267 4584 9267 4598 9267 4598 9268 4584 9268 4609 9268 4598 9269 4609 9269 4582 9269 4582 9270 4609 9270 4601 9270 4582 9271 4601 9271 4583 9271 4571 9272 4584 9272 4572 9272 4572 9273 4584 9273 4586 9273 4572 9274 4586 9274 4585 9274 4585 9275 4586 9275 4587 9275 4585 9276 4587 9276 4610 9276 4610 9277 4587 9277 4581 9277 4575 9278 4574 9278 4588 9278 4588 9279 4574 9279 4589 9279 4588 9280 4589 9280 4576 9280 4576 9281 4589 9281 4590 9281 4576 9282 4590 9282 4577 9282 4577 9283 4590 9283 4573 9283 4577 9284 4573 9284 4591 9284 4591 9285 4573 9285 4592 9285 4591 9286 4592 9286 4582 9286 4582 9287 4592 9287 4567 9287 4600 9288 4566 9288 4593 9288 4593 9289 4566 9289 4565 9289 4593 9290 4565 9290 4578 9290 4578 9291 4565 9291 4594 9291 4578 9292 4594 9292 4596 9292 4596 9293 4594 9293 4595 9293 4596 9294 4595 9294 4579 9294 4579 9295 4595 9295 4564 9295 4579 9296 4564 9296 4580 9296 4580 9297 4564 9297 4597 9297 4582 9298 4567 9298 4568 9298 4582 9299 4568 9299 4598 9299 4598 9300 4568 9300 4569 9300 4598 9301 4569 9301 4599 9301 4599 9302 4569 9302 4566 9302 4599 9303 4566 9303 4600 9303 4601 9304 4608 9304 4583 9304 4583 9305 4608 9305 4602 9305 4583 9306 4602 9306 4603 9306 4603 9307 4602 9307 4604 9307 4603 9308 4604 9308 4605 9308 4605 9309 4604 9309 4606 9309 4605 9310 4606 9310 4607 9310 4607 9311 4606 9311 4563 9311 4574 9312 4575 9312 4563 9312 4563 9313 4575 9313 4607 9313 4570 9314 4608 9314 4609 9314 4609 9315 4608 9315 4601 9315 4609 9316 4584 9316 4570 9316 4570 9317 4584 9317 4571 9317 4581 9318 4580 9318 4610 9318 4610 9319 4580 9319 4597 9319 4621 9320 4618 9320 4653 9320 4611 9321 4613 9321 4634 9321 4634 9322 4613 9322 4617 9322 4634 9323 4617 9323 4636 9323 4615 9324 4646 9324 4644 9324 4611 9325 4612 9325 4613 9325 4613 9326 4612 9326 4614 9326 4613 9327 4614 9327 4615 9327 4615 9328 4614 9328 4616 9328 4615 9329 4616 9329 4646 9329 4653 9330 4618 9330 4617 9330 4617 9331 4618 9331 4637 9331 4617 9332 4637 9332 4636 9332 4649 9333 4619 9333 4620 9333 4620 9334 4619 9334 4621 9334 4620 9335 4621 9335 4622 9335 4622 9336 4621 9336 4653 9336 4644 9337 4642 9337 4615 9337 4615 9338 4642 9338 4641 9338 4615 9339 4641 9339 4623 9339 4654 9340 4638 9340 4627 9340 4627 9341 4638 9341 4647 9341 4624 9342 4638 9342 4625 9342 4625 9343 4638 9343 4654 9343 4625 9344 4654 9344 4633 9344 4633 9345 4654 9345 4631 9345 4651 9346 4629 9346 4650 9346 4650 9347 4629 9347 4630 9347 4650 9348 4630 9348 4648 9348 4648 9349 4630 9349 4626 9349 4647 9350 4635 9350 4627 9350 4627 9351 4635 9351 4628 9351 4627 9352 4628 9352 4629 9352 4629 9353 4628 9353 4652 9353 4629 9354 4652 9354 4630 9354 4640 9355 4643 9355 4639 9355 4639 9356 4643 9356 4632 9356 4639 9357 4632 9357 4631 9357 4631 9358 4632 9358 4645 9358 4631 9359 4645 9359 4633 9359 4647 9360 4634 9360 4635 9360 4635 9361 4634 9361 4636 9361 4635 9362 4636 9362 4628 9362 4628 9363 4636 9363 4637 9363 4628 9364 4637 9364 4652 9364 4652 9365 4637 9365 4618 9365 4611 9366 4638 9366 4612 9366 4612 9367 4638 9367 4624 9367 4612 9368 4624 9368 4614 9368 4614 9369 4624 9369 4625 9369 4614 9370 4625 9370 4616 9370 4616 9371 4625 9371 4633 9371 4631 9372 4615 9372 4639 9372 4639 9373 4615 9373 4623 9373 4639 9374 4623 9374 4640 9374 4640 9375 4623 9375 4641 9375 4640 9376 4641 9376 4643 9376 4643 9377 4641 9377 4642 9377 4643 9378 4642 9378 4632 9378 4632 9379 4642 9379 4644 9379 4632 9380 4644 9380 4645 9380 4645 9381 4644 9381 4646 9381 4616 9382 4633 9382 4646 9382 4646 9383 4633 9383 4645 9383 4634 9384 4647 9384 4611 9384 4611 9385 4647 9385 4638 9385 4630 9386 4621 9386 4626 9386 4626 9387 4621 9387 4619 9387 4626 9388 4619 9388 4648 9388 4648 9389 4619 9389 4649 9389 4648 9390 4649 9390 4650 9390 4650 9391 4649 9391 4620 9391 4650 9392 4620 9392 4651 9392 4651 9393 4620 9393 4622 9393 4651 9394 4622 9394 4629 9394 4629 9395 4622 9395 4653 9395 4630 9396 4652 9396 4621 9396 4621 9397 4652 9397 4618 9397 4629 9398 4653 9398 4617 9398 4629 9399 4617 9399 4627 9399 4627 9400 4617 9400 4613 9400 4627 9401 4613 9401 4654 9401 4654 9402 4613 9402 4615 9402 4654 9403 4615 9403 4631 9403 4655 9404 4671 9404 4656 9404 4685 9405 4674 9405 4659 9405 4659 9406 4674 9406 4675 9406 4683 9407 4682 9407 4685 9407 4685 9408 4682 9408 4657 9408 4685 9409 4657 9409 4674 9409 4674 9410 4657 9410 4655 9410 4674 9411 4655 9411 4672 9411 4672 9412 4655 9412 4656 9412 4677 9413 4658 9413 4676 9413 4676 9414 4658 9414 4659 9414 4676 9415 4659 9415 4668 9415 4668 9416 4659 9416 4675 9416 4668 9417 4675 9417 4660 9417 4660 9418 4675 9418 4670 9418 4680 9419 4663 9419 4664 9419 4661 9420 4669 9420 4663 9420 4663 9421 4669 9421 4662 9421 4663 9422 4662 9422 4664 9422 4681 9423 4684 9423 4688 9423 4688 9424 4684 9424 4687 9424 4688 9425 4687 9425 4665 9425 4679 9426 4678 9426 4686 9426 4686 9427 4678 9427 4680 9427 4686 9428 4680 9428 4687 9428 4687 9429 4680 9429 4664 9429 4687 9430 4664 9430 4665 9430 4665 9431 4664 9431 4673 9431 4665 9432 4673 9432 4666 9432 4666 9433 4673 9433 4667 9433 4663 9434 4668 9434 4661 9434 4661 9435 4668 9435 4660 9435 4661 9436 4660 9436 4669 9436 4669 9437 4660 9437 4670 9437 4669 9438 4670 9438 4662 9438 4662 9439 4670 9439 4675 9439 4655 9440 4665 9440 4671 9440 4671 9441 4665 9441 4666 9441 4671 9442 4666 9442 4656 9442 4656 9443 4666 9443 4667 9443 4656 9444 4667 9444 4672 9444 4672 9445 4667 9445 4673 9445 4672 9446 4673 9446 4674 9446 4674 9447 4673 9447 4664 9447 4664 9448 4662 9448 4674 9448 4674 9449 4662 9449 4675 9449 4676 9450 4680 9450 4677 9450 4677 9451 4680 9451 4678 9451 4677 9452 4678 9452 4658 9452 4658 9453 4678 9453 4679 9453 4658 9454 4679 9454 4659 9454 4659 9455 4679 9455 4686 9455 4668 9456 4663 9456 4676 9456 4676 9457 4663 9457 4680 9457 4688 9458 4657 9458 4681 9458 4681 9459 4657 9459 4682 9459 4681 9460 4682 9460 4684 9460 4684 9461 4682 9461 4683 9461 4684 9462 4683 9462 4687 9462 4687 9463 4683 9463 4685 9463 4659 9464 4686 9464 4685 9464 4685 9465 4686 9465 4687 9465 4688 9466 4665 9466 4657 9466 4657 9467 4665 9467 4655 9467 4689 9468 4728 9468 4690 9468 4690 9469 4728 9469 4697 9469 4713 9470 4715 9470 4691 9470 4691 9471 4715 9471 4716 9471 4691 9472 4716 9472 4692 9472 4692 9473 4716 9473 4722 9473 4692 9474 4722 9474 4721 9474 4721 9475 4719 9475 4692 9475 4692 9476 4719 9476 4718 9476 4692 9477 4718 9477 4690 9477 4690 9478 4718 9478 4729 9478 4690 9479 4729 9479 4689 9479 4693 9480 4694 9480 4695 9480 4695 9481 4694 9481 4710 9481 4695 9482 4710 9482 4697 9482 4712 9483 4690 9483 4696 9483 4696 9484 4690 9484 4697 9484 4696 9485 4697 9485 4724 9485 4724 9486 4697 9486 4710 9486 4698 9487 4730 9487 4706 9487 4703 9488 4727 9488 4698 9488 4699 9489 4700 9489 4714 9489 4725 9490 4709 9490 4701 9490 4706 9491 4730 9491 4702 9491 4702 9492 4730 9492 4717 9492 4702 9493 4717 9493 4705 9493 4708 9494 4726 9494 4703 9494 4703 9495 4726 9495 4725 9495 4703 9496 4725 9496 4711 9496 4711 9497 4725 9497 4701 9497 4714 9498 4704 9498 4699 9498 4699 9499 4704 9499 4702 9499 4699 9500 4702 9500 4723 9500 4723 9501 4702 9501 4705 9501 4723 9502 4705 9502 4720 9502 4698 9503 4706 9503 4703 9503 4703 9504 4706 9504 4707 9504 4703 9505 4707 9505 4708 9505 4725 9506 4710 9506 4709 9506 4709 9507 4710 9507 4694 9507 4709 9508 4694 9508 4701 9508 4701 9509 4694 9509 4693 9509 4701 9510 4693 9510 4711 9510 4711 9511 4693 9511 4695 9511 4724 9512 4726 9512 4696 9512 4696 9513 4726 9513 4708 9513 4696 9514 4708 9514 4712 9514 4712 9515 4708 9515 4707 9515 4712 9516 4707 9516 4690 9516 4690 9517 4707 9517 4706 9517 4692 9518 4702 9518 4691 9518 4691 9519 4702 9519 4704 9519 4691 9520 4704 9520 4713 9520 4713 9521 4704 9521 4714 9521 4713 9522 4714 9522 4715 9522 4715 9523 4714 9523 4700 9523 4715 9524 4700 9524 4716 9524 4716 9525 4700 9525 4699 9525 4717 9526 4718 9526 4705 9526 4705 9527 4718 9527 4719 9527 4705 9528 4719 9528 4720 9528 4720 9529 4719 9529 4721 9529 4720 9530 4721 9530 4723 9530 4723 9531 4721 9531 4722 9531 4716 9532 4699 9532 4722 9532 4722 9533 4699 9533 4723 9533 4690 9534 4706 9534 4692 9534 4692 9535 4706 9535 4702 9535 4710 9536 4725 9536 4724 9536 4724 9537 4725 9537 4726 9537 4703 9538 4697 9538 4727 9538 4727 9539 4697 9539 4728 9539 4727 9540 4728 9540 4698 9540 4698 9541 4728 9541 4689 9541 4703 9542 4711 9542 4697 9542 4697 9543 4711 9543 4695 9543 4698 9544 4689 9544 4729 9544 4698 9545 4729 9545 4730 9545 4730 9546 4729 9546 4718 9546 4730 9547 4718 9547 4717 9547 4764 9548 4731 9548 4759 9548 4756 9549 4732 9549 4733 9549 4733 9550 4732 9550 4739 9550 4755 9551 4734 9551 4756 9551 4756 9552 4734 9552 4735 9552 4756 9553 4735 9553 4732 9553 4732 9554 4735 9554 4764 9554 4732 9555 4764 9555 4762 9555 4762 9556 4764 9556 4759 9556 4751 9557 4736 9557 4737 9557 4737 9558 4736 9558 4733 9558 4737 9559 4733 9559 4738 9559 4738 9560 4733 9560 4739 9560 4738 9561 4739 9561 4740 9561 4740 9562 4739 9562 4741 9562 4745 9563 4742 9563 4743 9563 4748 9564 4749 9564 4758 9564 4758 9565 4749 9565 4750 9565 4758 9566 4750 9566 4744 9566 4753 9567 4754 9567 4752 9567 4752 9568 4754 9568 4757 9568 4752 9569 4757 9569 4747 9569 4743 9570 4744 9570 4745 9570 4745 9571 4744 9571 4750 9571 4745 9572 4750 9572 4757 9572 4757 9573 4750 9573 4746 9573 4757 9574 4746 9574 4747 9574 4747 9575 4746 9575 4763 9575 4747 9576 4763 9576 4760 9576 4760 9577 4763 9577 4761 9577 4758 9578 4738 9578 4748 9578 4748 9579 4738 9579 4740 9579 4748 9580 4740 9580 4749 9580 4749 9581 4740 9581 4741 9581 4749 9582 4741 9582 4750 9582 4750 9583 4741 9583 4739 9583 4737 9584 4744 9584 4751 9584 4751 9585 4744 9585 4743 9585 4751 9586 4743 9586 4736 9586 4736 9587 4743 9587 4742 9587 4736 9588 4742 9588 4733 9588 4733 9589 4742 9589 4745 9589 4752 9590 4735 9590 4753 9590 4753 9591 4735 9591 4734 9591 4753 9592 4734 9592 4754 9592 4754 9593 4734 9593 4755 9593 4754 9594 4755 9594 4757 9594 4757 9595 4755 9595 4756 9595 4733 9596 4745 9596 4756 9596 4756 9597 4745 9597 4757 9597 4738 9598 4758 9598 4737 9598 4737 9599 4758 9599 4744 9599 4764 9600 4747 9600 4731 9600 4731 9601 4747 9601 4760 9601 4731 9602 4760 9602 4759 9602 4759 9603 4760 9603 4761 9603 4759 9604 4761 9604 4762 9604 4762 9605 4761 9605 4763 9605 4762 9606 4763 9606 4732 9606 4732 9607 4763 9607 4746 9607 4746 9608 4750 9608 4732 9608 4732 9609 4750 9609 4739 9609 4752 9610 4747 9610 4735 9610 4735 9611 4747 9611 4764 9611 4779 9612 4777 9612 4776 9612 4790 9613 4787 9613 4769 9613 4769 9614 4787 9614 4786 9614 4768 9615 4795 9615 4797 9615 4782 9616 4784 9616 4765 9616 4765 9617 4784 9617 4791 9617 4765 9618 4791 9618 4776 9618 4776 9619 4791 9619 4767 9619 4776 9620 4767 9620 4779 9620 4779 9621 4767 9621 4780 9621 4797 9622 4766 9622 4768 9622 4768 9623 4766 9623 4767 9623 4768 9624 4767 9624 4786 9624 4786 9625 4767 9625 4791 9625 4786 9626 4791 9626 4769 9626 4775 9627 4778 9627 4773 9627 4798 9628 4788 9628 4789 9628 4785 9629 4783 9629 4792 9629 4792 9630 4783 9630 4794 9630 4792 9631 4794 9631 4775 9631 4796 9632 4771 9632 4770 9632 4770 9633 4771 9633 4772 9633 4770 9634 4772 9634 4774 9634 4789 9635 4793 9635 4798 9635 4798 9636 4793 9636 4792 9636 4798 9637 4792 9637 4772 9637 4772 9638 4792 9638 4775 9638 4772 9639 4775 9639 4774 9639 4774 9640 4775 9640 4773 9640 4774 9641 4773 9641 4781 9641 4775 9642 4776 9642 4778 9642 4778 9643 4776 9643 4777 9643 4778 9644 4777 9644 4773 9644 4773 9645 4777 9645 4779 9645 4773 9646 4779 9646 4781 9646 4781 9647 4779 9647 4780 9647 4781 9648 4780 9648 4774 9648 4774 9649 4780 9649 4767 9649 4765 9650 4794 9650 4782 9650 4782 9651 4794 9651 4783 9651 4782 9652 4783 9652 4784 9652 4784 9653 4783 9653 4785 9653 4784 9654 4785 9654 4791 9654 4791 9655 4785 9655 4792 9655 4798 9656 4786 9656 4788 9656 4788 9657 4786 9657 4787 9657 4788 9658 4787 9658 4789 9658 4789 9659 4787 9659 4790 9659 4789 9660 4790 9660 4793 9660 4793 9661 4790 9661 4769 9661 4791 9662 4792 9662 4769 9662 4769 9663 4792 9663 4793 9663 4776 9664 4775 9664 4765 9664 4765 9665 4775 9665 4794 9665 4768 9666 4772 9666 4795 9666 4795 9667 4772 9667 4771 9667 4795 9668 4771 9668 4797 9668 4797 9669 4771 9669 4796 9669 4797 9670 4796 9670 4766 9670 4766 9671 4796 9671 4770 9671 4770 9672 4774 9672 4766 9672 4766 9673 4774 9673 4767 9673 4798 9674 4772 9674 4786 9674 4786 9675 4772 9675 4768 9675 4827 9676 4799 9676 4800 9676 4800 9677 4820 9677 4819 9677 4821 9678 4801 9678 4802 9678 4802 9679 4801 9679 4831 9679 4802 9680 4831 9680 4803 9680 4803 9681 4831 9681 4817 9681 4812 9682 4815 9682 4799 9682 4799 9683 4815 9683 4804 9683 4799 9684 4804 9684 4800 9684 4829 9685 4805 9685 4830 9685 4830 9686 4805 9686 4827 9686 4830 9687 4827 9687 4831 9687 4831 9688 4827 9688 4800 9688 4831 9689 4800 9689 4817 9689 4817 9690 4800 9690 4819 9690 4832 9691 4825 9691 4807 9691 4810 9692 4806 9692 4828 9692 4825 9693 4824 9693 4807 9693 4807 9694 4824 9694 4823 9694 4807 9695 4823 9695 4822 9695 4826 9696 4818 9696 4808 9696 4809 9697 4814 9697 4816 9697 4816 9698 4814 9698 4813 9698 4816 9699 4813 9699 4810 9699 4828 9700 4832 9700 4810 9700 4810 9701 4832 9701 4807 9701 4810 9702 4807 9702 4816 9702 4816 9703 4807 9703 4826 9703 4816 9704 4826 9704 4811 9704 4811 9705 4826 9705 4808 9705 4799 9706 4813 9706 4812 9706 4812 9707 4813 9707 4814 9707 4812 9708 4814 9708 4815 9708 4815 9709 4814 9709 4809 9709 4815 9710 4809 9710 4804 9710 4804 9711 4809 9711 4816 9711 4826 9712 4817 9712 4818 9712 4818 9713 4817 9713 4819 9713 4818 9714 4819 9714 4808 9714 4808 9715 4819 9715 4820 9715 4808 9716 4820 9716 4811 9716 4811 9717 4820 9717 4800 9717 4803 9718 4807 9718 4802 9718 4802 9719 4807 9719 4822 9719 4802 9720 4822 9720 4821 9720 4821 9721 4822 9721 4823 9721 4821 9722 4823 9722 4801 9722 4801 9723 4823 9723 4824 9723 4801 9724 4824 9724 4831 9724 4831 9725 4824 9725 4825 9725 4817 9726 4826 9726 4803 9726 4803 9727 4826 9727 4807 9727 4810 9728 4827 9728 4806 9728 4806 9729 4827 9729 4805 9729 4806 9730 4805 9730 4828 9730 4828 9731 4805 9731 4829 9731 4828 9732 4829 9732 4832 9732 4832 9733 4829 9733 4830 9733 4831 9734 4825 9734 4830 9734 4830 9735 4825 9735 4832 9735 4810 9736 4813 9736 4827 9736 4827 9737 4813 9737 4799 9737 4816 9738 4811 9738 4804 9738 4804 9739 4811 9739 4800 9739 4840 9740 4833 9740 4863 9740 4835 9741 4864 9741 4863 9741 4865 9742 4835 9742 4834 9742 4834 9743 4835 9743 4863 9743 4834 9744 4863 9744 4836 9744 4836 9745 4863 9745 4833 9745 4836 9746 4833 9746 4859 9746 4859 9747 4833 9747 4858 9747 4863 9748 4837 9748 4868 9748 4851 9749 4852 9749 4838 9749 4838 9750 4852 9750 4837 9750 4838 9751 4837 9751 4867 9751 4867 9752 4837 9752 4863 9752 4868 9753 4855 9753 4863 9753 4863 9754 4855 9754 4839 9754 4863 9755 4839 9755 4840 9755 4847 9756 4853 9756 4849 9756 4841 9757 4842 9757 4862 9757 4862 9758 4842 9758 4843 9758 4860 9759 4857 9759 4866 9759 4866 9760 4857 9760 4856 9760 4866 9761 4856 9761 4843 9761 4843 9762 4856 9762 4844 9762 4843 9763 4844 9763 4862 9763 4845 9764 4846 9764 4861 9764 4861 9765 4846 9765 4854 9765 4861 9766 4854 9766 4856 9766 4856 9767 4854 9767 4844 9767 4844 9768 4854 9768 4847 9768 4844 9769 4847 9769 4848 9769 4848 9770 4847 9770 4849 9770 4848 9771 4849 9771 4850 9771 4867 9772 4848 9772 4838 9772 4838 9773 4848 9773 4850 9773 4838 9774 4850 9774 4851 9774 4851 9775 4850 9775 4849 9775 4851 9776 4849 9776 4852 9776 4852 9777 4849 9777 4853 9777 4852 9778 4853 9778 4837 9778 4837 9779 4853 9779 4847 9779 4861 9780 4840 9780 4845 9780 4845 9781 4840 9781 4839 9781 4845 9782 4839 9782 4846 9782 4846 9783 4839 9783 4855 9783 4846 9784 4855 9784 4854 9784 4854 9785 4855 9785 4868 9785 4833 9786 4856 9786 4858 9786 4858 9787 4856 9787 4857 9787 4858 9788 4857 9788 4859 9788 4859 9789 4857 9789 4860 9789 4859 9790 4860 9790 4836 9790 4836 9791 4860 9791 4866 9791 4840 9792 4861 9792 4833 9792 4833 9793 4861 9793 4856 9793 4844 9794 4863 9794 4862 9794 4862 9795 4863 9795 4864 9795 4862 9796 4864 9796 4841 9796 4841 9797 4864 9797 4835 9797 4841 9798 4835 9798 4842 9798 4842 9799 4835 9799 4865 9799 4842 9800 4865 9800 4843 9800 4843 9801 4865 9801 4834 9801 4836 9802 4866 9802 4834 9802 4834 9803 4866 9803 4843 9803 4844 9804 4848 9804 4863 9804 4863 9805 4848 9805 4867 9805 4847 9806 4854 9806 4837 9806 4837 9807 4854 9807 4868 9807 4878 9808 4911 9808 4901 9808 4892 9809 4916 9809 4903 9809 4903 9810 4916 9810 4869 9810 4903 9811 4869 9811 4897 9811 4911 9812 4912 9812 4901 9812 4901 9813 4912 9813 4908 9813 4901 9814 4908 9814 4871 9814 4870 9815 4899 9815 4869 9815 4869 9816 4899 9816 4898 9816 4869 9817 4898 9817 4897 9817 4871 9818 4872 9818 4901 9818 4901 9819 4872 9819 4873 9819 4901 9820 4873 9820 4874 9820 4874 9821 4873 9821 4913 9821 4874 9822 4913 9822 4875 9822 4875 9823 4913 9823 4914 9823 4875 9824 4914 9824 4903 9824 4903 9825 4914 9825 4876 9825 4903 9826 4876 9826 4892 9826 4896 9827 4895 9827 4901 9827 4901 9828 4895 9828 4877 9828 4901 9829 4877 9829 4878 9829 4915 9830 4879 9830 4880 9830 4881 9831 4893 9831 4894 9831 4907 9832 4909 9832 4906 9832 4906 9833 4909 9833 4884 9833 4906 9834 4884 9834 4905 9834 4909 9835 4910 9835 4884 9835 4884 9836 4910 9836 4881 9836 4884 9837 4881 9837 4882 9837 4882 9838 4881 9838 4894 9838 4882 9839 4894 9839 4883 9839 4905 9840 4884 9840 4885 9840 4885 9841 4884 9841 4902 9841 4885 9842 4902 9842 4891 9842 4891 9843 4902 9843 4904 9843 4891 9844 4904 9844 4880 9844 4880 9845 4904 9845 4890 9845 4880 9846 4890 9846 4915 9846 4886 9847 4888 9847 4887 9847 4887 9848 4888 9848 4889 9848 4887 9849 4889 9849 4890 9849 4890 9850 4889 9850 4900 9850 4890 9851 4900 9851 4915 9851 4914 9852 4891 9852 4876 9852 4876 9853 4891 9853 4880 9853 4876 9854 4880 9854 4892 9854 4892 9855 4880 9855 4879 9855 4892 9856 4879 9856 4916 9856 4916 9857 4879 9857 4915 9857 4881 9858 4911 9858 4893 9858 4893 9859 4911 9859 4878 9859 4893 9860 4878 9860 4894 9860 4894 9861 4878 9861 4877 9861 4894 9862 4877 9862 4883 9862 4883 9863 4877 9863 4895 9863 4883 9864 4895 9864 4882 9864 4882 9865 4895 9865 4896 9865 4882 9866 4896 9866 4884 9866 4884 9867 4896 9867 4901 9867 4890 9868 4903 9868 4887 9868 4887 9869 4903 9869 4897 9869 4887 9870 4897 9870 4886 9870 4886 9871 4897 9871 4898 9871 4886 9872 4898 9872 4888 9872 4888 9873 4898 9873 4899 9873 4888 9874 4899 9874 4889 9874 4889 9875 4899 9875 4870 9875 4889 9876 4870 9876 4900 9876 4900 9877 4870 9877 4869 9877 4884 9878 4901 9878 4874 9878 4884 9879 4874 9879 4902 9879 4902 9880 4874 9880 4875 9880 4902 9881 4875 9881 4904 9881 4904 9882 4875 9882 4903 9882 4904 9883 4903 9883 4890 9883 4905 9884 4873 9884 4906 9884 4906 9885 4873 9885 4872 9885 4906 9886 4872 9886 4907 9886 4907 9887 4872 9887 4871 9887 4907 9888 4871 9888 4909 9888 4909 9889 4871 9889 4908 9889 4909 9890 4908 9890 4910 9890 4910 9891 4908 9891 4912 9891 4911 9892 4881 9892 4912 9892 4912 9893 4881 9893 4910 9893 4913 9894 4873 9894 4885 9894 4885 9895 4873 9895 4905 9895 4885 9896 4891 9896 4913 9896 4913 9897 4891 9897 4914 9897 4915 9898 4900 9898 4916 9898 4916 9899 4900 9899 4869 9899 4917 9900 4942 9900 4920 9900 4952 9901 4918 9901 4919 9901 4945 9902 4917 9902 4921 9902 4921 9903 4917 9903 4920 9903 4921 9904 4920 9904 4926 9904 4926 9905 4920 9905 4922 9905 4923 9906 4959 9906 4924 9906 4924 9907 4959 9907 4958 9907 4945 9908 4921 9908 4946 9908 4946 9909 4921 9909 4924 9909 4946 9910 4924 9910 4956 9910 4956 9911 4924 9911 4958 9911 4956 9912 4958 9912 4957 9912 4947 9913 4919 9913 4925 9913 4925 9914 4919 9914 4926 9914 4925 9915 4926 9915 4927 9915 4927 9916 4926 9916 4922 9916 4953 9917 4952 9917 4928 9917 4928 9918 4952 9918 4919 9918 4928 9919 4919 9919 4929 9919 4929 9920 4919 9920 4947 9920 4930 9921 4932 9921 4962 9921 4962 9922 4932 9922 4931 9922 4931 9923 4932 9923 4955 9923 4931 9924 4955 9924 4941 9924 4933 9925 4934 9925 4949 9925 4949 9926 4934 9926 4954 9926 4949 9927 4954 9927 4962 9927 4962 9928 4954 9928 4948 9928 4962 9929 4948 9929 4930 9929 4960 9930 4935 9930 4936 9930 4936 9931 4935 9931 4961 9931 4936 9932 4961 9932 4937 9932 4937 9933 4961 9933 4938 9933 4941 9934 4943 9934 4931 9934 4931 9935 4943 9935 4944 9935 4931 9936 4944 9936 4935 9936 4935 9937 4944 9937 4939 9937 4935 9938 4939 9938 4961 9938 4950 9939 4951 9939 4949 9939 4949 9940 4951 9940 4940 9940 4949 9941 4940 9941 4933 9941 4955 9942 4920 9942 4941 9942 4941 9943 4920 9943 4942 9943 4941 9944 4942 9944 4943 9944 4943 9945 4942 9945 4917 9945 4943 9946 4917 9946 4944 9946 4944 9947 4917 9947 4945 9947 4944 9948 4945 9948 4939 9948 4939 9949 4945 9949 4946 9949 4922 9950 4932 9950 4927 9950 4927 9951 4932 9951 4930 9951 4927 9952 4930 9952 4925 9952 4925 9953 4930 9953 4948 9953 4925 9954 4948 9954 4947 9954 4947 9955 4948 9955 4954 9955 4949 9956 4919 9956 4950 9956 4950 9957 4919 9957 4918 9957 4950 9958 4918 9958 4951 9958 4951 9959 4918 9959 4952 9959 4951 9960 4952 9960 4940 9960 4940 9961 4952 9961 4953 9961 4940 9962 4953 9962 4933 9962 4933 9963 4953 9963 4928 9963 4933 9964 4928 9964 4934 9964 4934 9965 4928 9965 4929 9965 4947 9966 4954 9966 4929 9966 4929 9967 4954 9967 4934 9967 4920 9968 4955 9968 4922 9968 4922 9969 4955 9969 4932 9969 4961 9970 4956 9970 4938 9970 4938 9971 4956 9971 4957 9971 4938 9972 4957 9972 4937 9972 4937 9973 4957 9973 4958 9973 4937 9974 4958 9974 4936 9974 4936 9975 4958 9975 4959 9975 4936 9976 4959 9976 4960 9976 4960 9977 4959 9977 4923 9977 4960 9978 4923 9978 4935 9978 4935 9979 4923 9979 4924 9979 4961 9980 4939 9980 4956 9980 4956 9981 4939 9981 4946 9981 4935 9982 4924 9982 4921 9982 4935 9983 4921 9983 4931 9983 4931 9984 4921 9984 4926 9984 4931 9985 4926 9985 4962 9985 4962 9986 4926 9986 4919 9986 4962 9987 4919 9987 4949 9987 4963 9988 4998 9988 4964 9988 4964 9989 4998 9989 4965 9989 4971 9990 4995 9990 4994 9990 4963 9991 4966 9991 4986 9991 4990 9992 4992 9992 4993 9992 4993 9993 4992 9993 4998 9993 4993 9994 4998 9994 4967 9994 4967 9995 4998 9995 4963 9995 4967 9996 4963 9996 4985 9996 4985 9997 4963 9997 4986 9997 4968 9998 4970 9998 4969 9998 4969 9999 4970 9999 4964 9999 4969 10000 4964 10000 4994 10000 4994 10001 4964 10001 4965 10001 4994 10002 4965 10002 4971 10002 4971 10003 4965 10003 4972 10003 4981 10004 4975 10004 4987 10004 4973 10005 4991 10005 4974 10005 4974 10006 4991 10006 4981 10006 4975 10007 4984 10007 4987 10007 4987 10008 4984 10008 4976 10008 4987 10009 4976 10009 4977 10009 4987 10010 4978 10010 4982 10010 4982 10011 4979 10011 4996 10011 4989 10012 4988 10012 4978 10012 4978 10013 4988 10013 4980 10013 4978 10014 4980 10014 4982 10014 4981 10015 4987 10015 4974 10015 4974 10016 4987 10016 4982 10016 4974 10017 4982 10017 4997 10017 4997 10018 4982 10018 4996 10018 4997 10019 4996 10019 4983 10019 4975 10020 4967 10020 4984 10020 4984 10021 4967 10021 4985 10021 4984 10022 4985 10022 4976 10022 4976 10023 4985 10023 4986 10023 4976 10024 4986 10024 4977 10024 4977 10025 4986 10025 4966 10025 4977 10026 4966 10026 4987 10026 4987 10027 4966 10027 4963 10027 4969 10028 4980 10028 4968 10028 4968 10029 4980 10029 4988 10029 4968 10030 4988 10030 4970 10030 4970 10031 4988 10031 4989 10031 4970 10032 4989 10032 4964 10032 4964 10033 4989 10033 4978 10033 4978 10034 4987 10034 4964 10034 4964 10035 4987 10035 4963 10035 4993 10036 4981 10036 4990 10036 4990 10037 4981 10037 4991 10037 4990 10038 4991 10038 4992 10038 4992 10039 4991 10039 4973 10039 4992 10040 4973 10040 4998 10040 4998 10041 4973 10041 4974 10041 4967 10042 4975 10042 4993 10042 4993 10043 4975 10043 4981 10043 4982 10044 4994 10044 4979 10044 4979 10045 4994 10045 4995 10045 4979 10046 4995 10046 4996 10046 4996 10047 4995 10047 4971 10047 4996 10048 4971 10048 4983 10048 4983 10049 4971 10049 4972 10049 4983 10050 4972 10050 4997 10050 4997 10051 4972 10051 4965 10051 4998 10052 4974 10052 4965 10052 4965 10053 4974 10053 4997 10053 4982 10054 4980 10054 4994 10054 4994 10055 4980 10055 4969 10055 5032 10056 4999 10056 5034 10056 5008 10057 5000 10057 5006 10057 5006 10058 5000 10058 5038 10058 5006 10059 5038 10059 5001 10059 5032 10060 5034 10060 5002 10060 5002 10061 5034 10061 5003 10061 5003 10062 5034 10062 5036 10062 5003 10063 5036 10063 5004 10063 5004 10064 5005 10064 5003 10064 5003 10065 5005 10065 5007 10065 5003 10066 5007 10066 5006 10066 5006 10067 5007 10067 5039 10067 5006 10068 5039 10068 5008 10068 5027 10069 5029 10069 5037 10069 5037 10070 5029 10070 5006 10070 5037 10071 5006 10071 5009 10071 5009 10072 5006 10072 5001 10072 5009 10073 5001 10073 5010 10073 5010 10074 5001 10074 5026 10074 5011 10075 5012 10075 5014 10075 5030 10076 5028 10076 5024 10076 5016 10077 5013 10077 5033 10077 5011 10078 5014 10078 5031 10078 5031 10079 5014 10079 5040 10079 5031 10080 5040 10080 5018 10080 5018 10081 5040 10081 5015 10081 5018 10082 5015 10082 5020 10082 5033 10083 5017 10083 5016 10083 5016 10084 5017 10084 5018 10084 5016 10085 5018 10085 5019 10085 5019 10086 5018 10086 5020 10086 5019 10087 5020 10087 5035 10087 5025 10088 5022 10088 5021 10088 5021 10089 5022 10089 5023 10089 5021 10090 5023 10090 5024 10090 5024 10091 5023 10091 5011 10091 5024 10092 5011 10092 5030 10092 5030 10093 5011 10093 5031 10093 5021 10094 5009 10094 5025 10094 5025 10095 5009 10095 5010 10095 5025 10096 5010 10096 5022 10096 5022 10097 5010 10097 5026 10097 5022 10098 5026 10098 5023 10098 5023 10099 5026 10099 5001 10099 5037 10100 5024 10100 5027 10100 5027 10101 5024 10101 5028 10101 5027 10102 5028 10102 5029 10102 5029 10103 5028 10103 5030 10103 5029 10104 5030 10104 5006 10104 5006 10105 5030 10105 5031 10105 5003 10106 5018 10106 5002 10106 5002 10107 5018 10107 5017 10107 5002 10108 5017 10108 5032 10108 5032 10109 5017 10109 5033 10109 5032 10110 5033 10110 4999 10110 4999 10111 5033 10111 5013 10111 4999 10112 5013 10112 5034 10112 5034 10113 5013 10113 5016 10113 5015 10114 5007 10114 5020 10114 5020 10115 5007 10115 5005 10115 5020 10116 5005 10116 5035 10116 5035 10117 5005 10117 5004 10117 5035 10118 5004 10118 5019 10118 5019 10119 5004 10119 5036 10119 5034 10120 5016 10120 5036 10120 5036 10121 5016 10121 5019 10121 5006 10122 5031 10122 5003 10122 5003 10123 5031 10123 5018 10123 5009 10124 5021 10124 5037 10124 5037 10125 5021 10125 5024 10125 5011 10126 5038 10126 5012 10126 5012 10127 5038 10127 5000 10127 5012 10128 5000 10128 5014 10128 5014 10129 5000 10129 5008 10129 5011 10130 5023 10130 5038 10130 5038 10131 5023 10131 5001 10131 5014 10132 5008 10132 5039 10132 5014 10133 5039 10133 5040 10133 5040 10134 5039 10134 5007 10134 5040 10135 5007 10135 5015 10135 5063 10136 5041 10136 5044 10136 5044 10137 5041 10137 5046 10137 5071 10138 5041 10138 5065 10138 5065 10139 5041 10139 5063 10139 5065 10140 5063 10140 5064 10140 5064 10141 5063 10141 5042 10141 5071 10142 5070 10142 5041 10142 5041 10143 5070 10143 5069 10143 5041 10144 5069 10144 5068 10144 5043 10145 5060 10145 5062 10145 5062 10146 5060 10146 5044 10146 5062 10147 5044 10147 5045 10147 5045 10148 5044 10148 5046 10148 5045 10149 5046 10149 5047 10149 5047 10150 5046 10150 5072 10150 5053 10151 5074 10151 5055 10151 5055 10152 5067 10152 5056 10152 5073 10153 5048 10153 5074 10153 5074 10154 5048 10154 5049 10154 5074 10155 5049 10155 5055 10155 5050 10156 5051 10156 5066 10156 5066 10157 5051 10157 5054 10157 5066 10158 5054 10158 5057 10158 5059 10159 5061 10159 5052 10159 5052 10160 5061 10160 5053 10160 5052 10161 5053 10161 5054 10161 5054 10162 5053 10162 5055 10162 5054 10163 5055 10163 5057 10163 5057 10164 5055 10164 5056 10164 5057 10165 5056 10165 5058 10165 5052 10166 5044 10166 5059 10166 5059 10167 5044 10167 5060 10167 5059 10168 5060 10168 5061 10168 5061 10169 5060 10169 5043 10169 5061 10170 5043 10170 5053 10170 5053 10171 5043 10171 5062 10171 5063 10172 5054 10172 5042 10172 5042 10173 5054 10173 5051 10173 5042 10174 5051 10174 5064 10174 5064 10175 5051 10175 5050 10175 5064 10176 5050 10176 5065 10176 5065 10177 5050 10177 5066 10177 5055 10178 5041 10178 5067 10178 5067 10179 5041 10179 5068 10179 5067 10180 5068 10180 5056 10180 5056 10181 5068 10181 5069 10181 5056 10182 5069 10182 5058 10182 5058 10183 5069 10183 5070 10183 5058 10184 5070 10184 5057 10184 5057 10185 5070 10185 5071 10185 5065 10186 5066 10186 5071 10186 5071 10187 5066 10187 5057 10187 5044 10188 5052 10188 5063 10188 5063 10189 5052 10189 5054 10189 5046 10190 5049 10190 5072 10190 5072 10191 5049 10191 5048 10191 5072 10192 5048 10192 5047 10192 5047 10193 5048 10193 5073 10193 5047 10194 5073 10194 5045 10194 5045 10195 5073 10195 5074 10195 5074 10196 5053 10196 5045 10196 5045 10197 5053 10197 5062 10197 5055 10198 5049 10198 5041 10198 5041 10199 5049 10199 5046 10199 5099 10200 5101 10200 5082 10200 5082 10201 5101 10201 5078 10201 5082 10202 5078 10202 5077 10202 5104 10203 5103 10203 5075 10203 5075 10204 5103 10204 5077 10204 5075 10205 5077 10205 5076 10205 5076 10206 5077 10206 5078 10206 5079 10207 5106 10207 5083 10207 5083 10208 5106 10208 5108 10208 5080 10209 5098 10209 5095 10209 5095 10210 5081 10210 5080 10210 5080 10211 5081 10211 5082 10211 5080 10212 5082 10212 5108 10212 5108 10213 5082 10213 5077 10213 5108 10214 5077 10214 5083 10214 5097 10215 5084 10215 5086 10215 5107 10216 5105 10216 5084 10216 5084 10217 5105 10217 5085 10217 5084 10218 5085 10218 5086 10218 5087 10219 5088 10219 5086 10219 5086 10220 5088 10220 5093 10220 5102 10221 5100 10221 5089 10221 5089 10222 5100 10222 5091 10222 5089 10223 5091 10223 5092 10223 5094 10224 5096 10224 5090 10224 5090 10225 5096 10225 5097 10225 5090 10226 5097 10226 5091 10226 5091 10227 5097 10227 5086 10227 5091 10228 5086 10228 5092 10228 5092 10229 5086 10229 5093 10229 5090 10230 5081 10230 5094 10230 5094 10231 5081 10231 5095 10231 5094 10232 5095 10232 5096 10232 5096 10233 5095 10233 5098 10233 5096 10234 5098 10234 5097 10234 5097 10235 5098 10235 5080 10235 5082 10236 5091 10236 5099 10236 5099 10237 5091 10237 5100 10237 5099 10238 5100 10238 5101 10238 5101 10239 5100 10239 5102 10239 5101 10240 5102 10240 5078 10240 5078 10241 5102 10241 5089 10241 5086 10242 5077 10242 5087 10242 5087 10243 5077 10243 5103 10243 5087 10244 5103 10244 5088 10244 5088 10245 5103 10245 5104 10245 5088 10246 5104 10246 5093 10246 5093 10247 5104 10247 5075 10247 5093 10248 5075 10248 5092 10248 5092 10249 5075 10249 5076 10249 5078 10250 5089 10250 5076 10250 5076 10251 5089 10251 5092 10251 5081 10252 5090 10252 5082 10252 5082 10253 5090 10253 5091 10253 5083 10254 5085 10254 5079 10254 5079 10255 5085 10255 5105 10255 5079 10256 5105 10256 5106 10256 5106 10257 5105 10257 5107 10257 5106 10258 5107 10258 5108 10258 5108 10259 5107 10259 5084 10259 5084 10260 5097 10260 5108 10260 5108 10261 5097 10261 5080 10261 5086 10262 5085 10262 5077 10262 5077 10263 5085 10263 5083 10263 5134 10264 5136 10264 5140 10264 5137 10265 5142 10265 5111 10265 5111 10266 5142 10266 5127 10266 5139 10267 5109 10267 5110 10267 5110 10268 5109 10268 5142 10268 5110 10269 5142 10269 5140 10269 5140 10270 5142 10270 5137 10270 5140 10271 5137 10271 5134 10271 5134 10272 5137 10272 5133 10272 5125 10273 5124 10273 5132 10273 5132 10274 5124 10274 5111 10274 5132 10275 5111 10275 5131 10275 5131 10276 5111 10276 5127 10276 5131 10277 5127 10277 5129 10277 5129 10278 5127 10278 5112 10278 5118 10279 5113 10279 5119 10279 5141 10280 5114 10280 5115 10280 5115 10281 5114 10281 5121 10281 5138 10282 5116 10282 5141 10282 5141 10283 5116 10283 5117 10283 5141 10284 5117 10284 5114 10284 5114 10285 5117 10285 5118 10285 5114 10286 5118 10286 5135 10286 5135 10287 5118 10287 5119 10287 5130 10288 5128 10288 5120 10288 5120 10289 5128 10289 5115 10289 5120 10290 5115 10290 5126 10290 5126 10291 5115 10291 5121 10291 5126 10292 5121 10292 5123 10292 5123 10293 5121 10293 5122 10293 5121 10294 5111 10294 5122 10294 5122 10295 5111 10295 5124 10295 5122 10296 5124 10296 5123 10296 5123 10297 5124 10297 5125 10297 5123 10298 5125 10298 5126 10298 5126 10299 5125 10299 5132 10299 5127 10300 5115 10300 5112 10300 5112 10301 5115 10301 5128 10301 5112 10302 5128 10302 5129 10302 5129 10303 5128 10303 5130 10303 5129 10304 5130 10304 5131 10304 5131 10305 5130 10305 5120 10305 5120 10306 5126 10306 5131 10306 5131 10307 5126 10307 5132 10307 5137 10308 5114 10308 5133 10308 5133 10309 5114 10309 5135 10309 5133 10310 5135 10310 5134 10310 5134 10311 5135 10311 5119 10311 5134 10312 5119 10312 5136 10312 5136 10313 5119 10313 5113 10313 5136 10314 5113 10314 5140 10314 5140 10315 5113 10315 5118 10315 5111 10316 5121 10316 5137 10316 5137 10317 5121 10317 5114 10317 5141 10318 5142 10318 5138 10318 5138 10319 5142 10319 5109 10319 5138 10320 5109 10320 5116 10320 5116 10321 5109 10321 5139 10321 5116 10322 5139 10322 5117 10322 5117 10323 5139 10323 5110 10323 5140 10324 5118 10324 5110 10324 5110 10325 5118 10325 5117 10325 5141 10326 5115 10326 5142 10326 5142 10327 5115 10327 5127 10327 5170 10328 5143 10328 5168 10328 5168 10329 5174 10329 5170 10329 5170 10330 5174 10330 5176 10330 5170 10331 5176 10331 5144 10331 5144 10332 5176 10332 5151 10332 5173 10333 5145 10333 5146 10333 5146 10334 5145 10334 5176 10334 5146 10335 5176 10335 5147 10335 5147 10336 5176 10336 5174 10336 5148 10337 5162 10337 5164 10337 5164 10338 5162 10338 5144 10338 5164 10339 5144 10339 5149 10339 5149 10340 5144 10340 5151 10340 5149 10341 5151 10341 5150 10341 5150 10342 5151 10342 5165 10342 5175 10343 5152 10343 5160 10343 5159 10344 5166 10344 5158 10344 5152 10345 5171 10345 5160 10345 5160 10346 5171 10346 5153 10346 5160 10347 5153 10347 5172 10347 5169 10348 5154 10348 5167 10348 5155 10349 5163 10349 5156 10349 5156 10350 5163 10350 5157 10350 5156 10351 5157 10351 5159 10351 5158 10352 5175 10352 5159 10352 5159 10353 5175 10353 5160 10353 5159 10354 5160 10354 5156 10354 5156 10355 5160 10355 5169 10355 5156 10356 5169 10356 5161 10356 5161 10357 5169 10357 5167 10357 5156 10358 5144 10358 5155 10358 5155 10359 5144 10359 5162 10359 5155 10360 5162 10360 5163 10360 5163 10361 5162 10361 5148 10361 5163 10362 5148 10362 5157 10362 5157 10363 5148 10363 5164 10363 5151 10364 5175 10364 5165 10364 5165 10365 5175 10365 5158 10365 5165 10366 5158 10366 5150 10366 5150 10367 5158 10367 5166 10367 5150 10368 5166 10368 5149 10368 5149 10369 5166 10369 5159 10369 5159 10370 5157 10370 5149 10370 5149 10371 5157 10371 5164 10371 5170 10372 5161 10372 5143 10372 5143 10373 5161 10373 5167 10373 5143 10374 5167 10374 5168 10374 5168 10375 5167 10375 5154 10375 5168 10376 5154 10376 5174 10376 5174 10377 5154 10377 5169 10377 5144 10378 5156 10378 5170 10378 5170 10379 5156 10379 5161 10379 5152 10380 5176 10380 5171 10380 5171 10381 5176 10381 5145 10381 5171 10382 5145 10382 5153 10382 5153 10383 5145 10383 5173 10383 5153 10384 5173 10384 5172 10384 5172 10385 5173 10385 5146 10385 5172 10386 5146 10386 5160 10386 5160 10387 5146 10387 5147 10387 5174 10388 5169 10388 5147 10388 5147 10389 5169 10389 5160 10389 5152 10390 5175 10390 5176 10390 5176 10391 5175 10391 5151 10391 5209 10392 5207 10392 5211 10392 5211 10393 5207 10393 5177 10393 5195 10394 5196 10394 5178 10394 5178 10395 5196 10395 5179 10395 5178 10396 5179 10396 5180 10396 5192 10397 5190 10397 5181 10397 5181 10398 5190 10398 5183 10398 5181 10399 5183 10399 5182 10399 5182 10400 5183 10400 5211 10400 5182 10401 5211 10401 5180 10401 5180 10402 5211 10402 5177 10402 5180 10403 5177 10403 5178 10403 5202 10404 5184 10404 5201 10404 5201 10405 5184 10405 5183 10405 5201 10406 5183 10406 5204 10406 5204 10407 5183 10407 5190 10407 5205 10408 5191 10408 5193 10408 5197 10409 5185 10409 5188 10409 5188 10410 5185 10410 5194 10410 5206 10411 5208 10411 5186 10411 5186 10412 5208 10412 5210 10412 5186 10413 5210 10413 5194 10413 5194 10414 5210 10414 5187 10414 5194 10415 5187 10415 5188 10415 5203 10416 5200 10416 5189 10416 5189 10417 5200 10417 5199 10417 5189 10418 5199 10418 5212 10418 5193 10419 5198 10419 5205 10419 5205 10420 5198 10420 5187 10420 5205 10421 5187 10421 5199 10421 5199 10422 5187 10422 5210 10422 5199 10423 5210 10423 5212 10423 5205 10424 5190 10424 5191 10424 5191 10425 5190 10425 5192 10425 5191 10426 5192 10426 5193 10426 5193 10427 5192 10427 5181 10427 5193 10428 5181 10428 5198 10428 5198 10429 5181 10429 5182 10429 5178 10430 5194 10430 5195 10430 5195 10431 5194 10431 5185 10431 5195 10432 5185 10432 5196 10432 5196 10433 5185 10433 5197 10433 5196 10434 5197 10434 5179 10434 5179 10435 5197 10435 5188 10435 5179 10436 5188 10436 5180 10436 5180 10437 5188 10437 5187 10437 5187 10438 5198 10438 5180 10438 5180 10439 5198 10439 5182 10439 5204 10440 5199 10440 5201 10440 5201 10441 5199 10441 5200 10441 5201 10442 5200 10442 5202 10442 5202 10443 5200 10443 5203 10443 5202 10444 5203 10444 5184 10444 5184 10445 5203 10445 5189 10445 5184 10446 5189 10446 5183 10446 5183 10447 5189 10447 5212 10447 5190 10448 5205 10448 5204 10448 5204 10449 5205 10449 5199 10449 5186 10450 5177 10450 5206 10450 5206 10451 5177 10451 5207 10451 5206 10452 5207 10452 5208 10452 5208 10453 5207 10453 5209 10453 5208 10454 5209 10454 5210 10454 5210 10455 5209 10455 5211 10455 5183 10456 5212 10456 5211 10456 5211 10457 5212 10457 5210 10457 5186 10458 5194 10458 5177 10458 5177 10459 5194 10459 5178 10459 5245 10460 5213 10460 5248 10460 5255 10461 5254 10461 5222 10461 5222 10462 5254 10462 5244 10462 5214 10463 5215 10463 5236 10463 5236 10464 5215 10464 5232 10464 5236 10465 5232 10465 5216 10465 5216 10466 5232 10466 5244 10466 5216 10467 5244 10467 5259 10467 5259 10468 5244 10468 5254 10468 5217 10469 5218 10469 5219 10469 5219 10470 5218 10470 5241 10470 5219 10471 5241 10471 5240 10471 5240 10472 5241 10472 5220 10472 5218 10473 5245 10473 5241 10473 5241 10474 5245 10474 5248 10474 5241 10475 5248 10475 5242 10475 5242 10476 5248 10476 5249 10476 5242 10477 5249 10477 5243 10477 5243 10478 5249 10478 5221 10478 5243 10479 5221 10479 5244 10479 5244 10480 5221 10480 5257 10480 5244 10481 5257 10481 5222 10481 5246 10482 5250 10482 5224 10482 5246 10483 5224 10483 5247 10483 5239 10484 5223 10484 5238 10484 5238 10485 5223 10485 5224 10485 5238 10486 5224 10486 5237 10486 5237 10487 5224 10487 5250 10487 5252 10488 5253 10488 5226 10488 5226 10489 5253 10489 5225 10489 5225 10490 5256 10490 5226 10490 5226 10491 5256 10491 5258 10491 5226 10492 5258 10492 5227 10492 5227 10493 5258 10493 5228 10493 5227 10494 5228 10494 5229 10494 5229 10495 5228 10495 5251 10495 5229 10496 5251 10496 5224 10496 5224 10497 5251 10497 5230 10497 5224 10498 5230 10498 5247 10498 5233 10499 5234 10499 5231 10499 5231 10500 5234 10500 5235 10500 5231 10501 5235 10501 5226 10501 5226 10502 5235 10502 5260 10502 5226 10503 5260 10503 5252 10503 5226 10504 5244 10504 5231 10504 5231 10505 5244 10505 5232 10505 5231 10506 5232 10506 5233 10506 5233 10507 5232 10507 5215 10507 5233 10508 5215 10508 5234 10508 5234 10509 5215 10509 5214 10509 5234 10510 5214 10510 5235 10510 5235 10511 5214 10511 5236 10511 5235 10512 5236 10512 5260 10512 5260 10513 5236 10513 5216 10513 5250 10514 5218 10514 5237 10514 5237 10515 5218 10515 5217 10515 5237 10516 5217 10516 5238 10516 5238 10517 5217 10517 5219 10517 5238 10518 5219 10518 5239 10518 5239 10519 5219 10519 5240 10519 5239 10520 5240 10520 5223 10520 5223 10521 5240 10521 5220 10521 5223 10522 5220 10522 5224 10522 5224 10523 5220 10523 5241 10523 5224 10524 5241 10524 5242 10524 5224 10525 5242 10525 5229 10525 5229 10526 5242 10526 5243 10526 5229 10527 5243 10527 5227 10527 5227 10528 5243 10528 5244 10528 5227 10529 5244 10529 5226 10529 5245 10530 5246 10530 5213 10530 5213 10531 5246 10531 5247 10531 5213 10532 5247 10532 5248 10532 5248 10533 5247 10533 5230 10533 5248 10534 5230 10534 5249 10534 5249 10535 5230 10535 5251 10535 5218 10536 5250 10536 5245 10536 5245 10537 5250 10537 5246 10537 5249 10538 5251 10538 5221 10538 5221 10539 5251 10539 5228 10539 5252 10540 5259 10540 5253 10540 5253 10541 5259 10541 5254 10541 5253 10542 5254 10542 5225 10542 5225 10543 5254 10543 5255 10543 5225 10544 5255 10544 5256 10544 5256 10545 5255 10545 5222 10545 5256 10546 5222 10546 5258 10546 5258 10547 5222 10547 5257 10547 5257 10548 5221 10548 5258 10548 5258 10549 5221 10549 5228 10549 5252 10550 5260 10550 5259 10550 5259 10551 5260 10551 5216 10551 5297 10552 5281 10552 5264 10552 5267 10553 5261 10553 5300 10553 5261 10554 5267 10554 5262 10554 5262 10555 5267 10555 5297 10555 5262 10556 5297 10556 5263 10556 5263 10557 5297 10557 5264 10557 5263 10558 5264 10558 5288 10558 5293 10559 5266 10559 5265 10559 5265 10560 5266 10560 5267 10560 5265 10561 5267 10561 5298 10561 5298 10562 5267 10562 5300 10562 5298 10563 5300 10563 5268 10563 5290 10564 5269 10564 5270 10564 5270 10565 5269 10565 5292 10565 5271 10566 5285 10566 5272 10566 5272 10567 5282 10567 5271 10567 5271 10568 5282 10568 5281 10568 5271 10569 5281 10569 5292 10569 5292 10570 5281 10570 5297 10570 5292 10571 5297 10571 5270 10571 5299 10572 5301 10572 5302 10572 5296 10573 5286 10573 5287 10573 5273 10574 5274 10574 5296 10574 5295 10575 5294 10575 5276 10575 5276 10576 5294 10576 5275 10576 5276 10577 5275 10577 5303 10577 5303 10578 5299 10578 5276 10578 5276 10579 5299 10579 5302 10579 5276 10580 5302 10580 5296 10580 5296 10581 5302 10581 5304 10581 5296 10582 5304 10582 5286 10582 5291 10583 5277 10583 5274 10583 5274 10584 5277 10584 5278 10584 5274 10585 5278 10585 5296 10585 5283 10586 5284 10586 5279 10586 5279 10587 5284 10587 5273 10587 5279 10588 5273 10588 5280 10588 5280 10589 5273 10589 5296 10589 5280 10590 5296 10590 5289 10590 5289 10591 5296 10591 5287 10591 5280 10592 5281 10592 5279 10592 5279 10593 5281 10593 5282 10593 5279 10594 5282 10594 5283 10594 5283 10595 5282 10595 5272 10595 5283 10596 5272 10596 5284 10596 5284 10597 5272 10597 5285 10597 5284 10598 5285 10598 5273 10598 5273 10599 5285 10599 5271 10599 5286 10600 5263 10600 5287 10600 5287 10601 5263 10601 5288 10601 5287 10602 5288 10602 5289 10602 5289 10603 5288 10603 5264 10603 5281 10604 5280 10604 5264 10604 5264 10605 5280 10605 5289 10605 5297 10606 5296 10606 5270 10606 5270 10607 5296 10607 5278 10607 5270 10608 5278 10608 5290 10608 5290 10609 5278 10609 5277 10609 5290 10610 5277 10610 5269 10610 5269 10611 5277 10611 5291 10611 5269 10612 5291 10612 5292 10612 5292 10613 5291 10613 5274 10613 5274 10614 5273 10614 5292 10614 5292 10615 5273 10615 5271 10615 5265 10616 5275 10616 5293 10616 5293 10617 5275 10617 5294 10617 5293 10618 5294 10618 5266 10618 5266 10619 5294 10619 5295 10619 5266 10620 5295 10620 5267 10620 5267 10621 5295 10621 5276 10621 5276 10622 5296 10622 5267 10622 5267 10623 5296 10623 5297 10623 5303 10624 5298 10624 5299 10624 5299 10625 5298 10625 5268 10625 5299 10626 5268 10626 5301 10626 5301 10627 5268 10627 5300 10627 5301 10628 5300 10628 5302 10628 5302 10629 5300 10629 5261 10629 5303 10630 5275 10630 5298 10630 5298 10631 5275 10631 5265 10631 5302 10632 5261 10632 5262 10632 5302 10633 5262 10633 5304 10633 5304 10634 5262 10634 5263 10634 5304 10635 5263 10635 5286 10635 5311 10636 5337 10636 5322 10636 5326 10637 5305 10637 5327 10637 5327 10638 5305 10638 5312 10638 5306 10639 5330 10639 5307 10639 5307 10640 5330 10640 5310 10640 5308 10641 5325 10641 5309 10641 5309 10642 5325 10642 5322 10642 5309 10643 5322 10643 5310 10643 5310 10644 5322 10644 5337 10644 5310 10645 5337 10645 5307 10645 5335 10646 5334 10646 5338 10646 5338 10647 5334 10647 5311 10647 5338 10648 5311 10648 5312 10648 5312 10649 5311 10649 5322 10649 5312 10650 5322 10650 5327 10650 5313 10651 5329 10651 5328 10651 5321 10652 5336 10652 5318 10652 5318 10653 5336 10653 5320 10653 5323 10654 5324 10654 5321 10654 5321 10655 5324 10655 5331 10655 5321 10656 5331 10656 5336 10656 5336 10657 5331 10657 5313 10657 5336 10658 5313 10658 5314 10658 5314 10659 5313 10659 5328 10659 5315 10660 5316 10660 5317 10660 5317 10661 5316 10661 5318 10661 5317 10662 5318 10662 5319 10662 5319 10663 5318 10663 5320 10663 5319 10664 5320 10664 5333 10664 5333 10665 5320 10665 5332 10665 5321 10666 5322 10666 5323 10666 5323 10667 5322 10667 5325 10667 5323 10668 5325 10668 5324 10668 5324 10669 5325 10669 5308 10669 5324 10670 5308 10670 5331 10670 5331 10671 5308 10671 5309 10671 5327 10672 5318 10672 5326 10672 5326 10673 5318 10673 5316 10673 5326 10674 5316 10674 5305 10674 5305 10675 5316 10675 5315 10675 5305 10676 5315 10676 5312 10676 5312 10677 5315 10677 5317 10677 5322 10678 5321 10678 5327 10678 5327 10679 5321 10679 5318 10679 5337 10680 5336 10680 5307 10680 5307 10681 5336 10681 5314 10681 5307 10682 5314 10682 5306 10682 5306 10683 5314 10683 5328 10683 5306 10684 5328 10684 5330 10684 5330 10685 5328 10685 5329 10685 5330 10686 5329 10686 5310 10686 5310 10687 5329 10687 5313 10687 5313 10688 5331 10688 5310 10688 5310 10689 5331 10689 5309 10689 5320 10690 5311 10690 5332 10690 5332 10691 5311 10691 5334 10691 5332 10692 5334 10692 5333 10692 5333 10693 5334 10693 5335 10693 5333 10694 5335 10694 5319 10694 5319 10695 5335 10695 5338 10695 5320 10696 5336 10696 5311 10696 5311 10697 5336 10697 5337 10697 5312 10698 5317 10698 5338 10698 5338 10699 5317 10699 5319 10699 5371 10700 5355 10700 5341 10700 5339 10701 5356 10701 5355 10701 5355 10702 5356 10702 5372 10702 5355 10703 5372 10703 5341 10703 5361 10704 5340 10704 5341 10704 5341 10705 5340 10705 5358 10705 5342 10706 5363 10706 5367 10706 5367 10707 5363 10707 5345 10707 5367 10708 5345 10708 5346 10708 5370 10709 5343 10709 5344 10709 5344 10710 5343 10710 5371 10710 5344 10711 5371 10711 5345 10711 5345 10712 5371 10712 5341 10712 5345 10713 5341 10713 5346 10713 5346 10714 5341 10714 5358 10714 5353 10715 5365 10715 5366 10715 5366 10716 5347 10716 5354 10716 5364 10717 5348 10717 5365 10717 5365 10718 5348 10718 5362 10718 5365 10719 5362 10719 5366 10719 5357 10720 5349 10720 5350 10720 5350 10721 5349 10721 5351 10721 5350 10722 5351 10722 5360 10722 5368 10723 5369 10723 5352 10723 5352 10724 5369 10724 5353 10724 5352 10725 5353 10725 5351 10725 5351 10726 5353 10726 5366 10726 5351 10727 5366 10727 5360 10727 5360 10728 5366 10728 5354 10728 5360 10729 5354 10729 5359 10729 5355 10730 5351 10730 5339 10730 5339 10731 5351 10731 5349 10731 5339 10732 5349 10732 5356 10732 5356 10733 5349 10733 5357 10733 5356 10734 5357 10734 5372 10734 5372 10735 5357 10735 5350 10735 5366 10736 5346 10736 5347 10736 5347 10737 5346 10737 5358 10737 5347 10738 5358 10738 5354 10738 5354 10739 5358 10739 5340 10739 5354 10740 5340 10740 5359 10740 5359 10741 5340 10741 5361 10741 5359 10742 5361 10742 5360 10742 5360 10743 5361 10743 5341 10743 5367 10744 5362 10744 5342 10744 5342 10745 5362 10745 5348 10745 5342 10746 5348 10746 5363 10746 5363 10747 5348 10747 5364 10747 5363 10748 5364 10748 5345 10748 5345 10749 5364 10749 5365 10749 5346 10750 5366 10750 5367 10750 5367 10751 5366 10751 5362 10751 5352 10752 5371 10752 5368 10752 5368 10753 5371 10753 5343 10753 5368 10754 5343 10754 5369 10754 5369 10755 5343 10755 5370 10755 5369 10756 5370 10756 5353 10756 5353 10757 5370 10757 5344 10757 5345 10758 5365 10758 5344 10758 5344 10759 5365 10759 5353 10759 5352 10760 5351 10760 5371 10760 5371 10761 5351 10761 5355 10761 5350 10762 5360 10762 5372 10762 5372 10763 5360 10763 5341 10763 5408 10764 5392 10764 5393 10764 5373 10765 5400 10765 5405 10765 5407 10766 5408 10766 5404 10766 5404 10767 5408 10767 5393 10767 5404 10768 5393 10768 5375 10768 5375 10769 5393 10769 5388 10769 5403 10770 5401 10770 5410 10770 5410 10771 5401 10771 5375 10771 5410 10772 5375 10772 5374 10772 5374 10773 5375 10773 5388 10773 5374 10774 5388 10774 5376 10774 5376 10775 5388 10775 5390 10775 5399 10776 5373 10776 5404 10776 5404 10777 5373 10777 5405 10777 5404 10778 5405 10778 5407 10778 5407 10779 5405 10779 5396 10779 5407 10780 5396 10780 5377 10780 5394 10781 5406 10781 5383 10781 5378 10782 5397 10782 5379 10782 5380 10783 5381 10783 5384 10783 5382 10784 5389 10784 5383 10784 5383 10785 5389 10785 5395 10785 5383 10786 5395 10786 5394 10786 5384 10787 5398 10787 5380 10787 5380 10788 5398 10788 5383 10788 5380 10789 5383 10789 5379 10789 5379 10790 5383 10790 5406 10790 5379 10791 5406 10791 5378 10791 5385 10792 5391 10792 5409 10792 5409 10793 5391 10793 5389 10793 5409 10794 5389 10794 5386 10794 5386 10795 5389 10795 5382 10795 5386 10796 5382 10796 5387 10796 5387 10797 5382 10797 5402 10797 5388 10798 5389 10798 5390 10798 5390 10799 5389 10799 5391 10799 5390 10800 5391 10800 5376 10800 5376 10801 5391 10801 5385 10801 5376 10802 5385 10802 5374 10802 5374 10803 5385 10803 5409 10803 5408 10804 5406 10804 5392 10804 5392 10805 5406 10805 5394 10805 5392 10806 5394 10806 5393 10806 5393 10807 5394 10807 5395 10807 5395 10808 5389 10808 5393 10808 5393 10809 5389 10809 5388 10809 5396 10810 5379 10810 5377 10810 5377 10811 5379 10811 5397 10811 5377 10812 5397 10812 5407 10812 5407 10813 5397 10813 5378 10813 5404 10814 5383 10814 5399 10814 5399 10815 5383 10815 5398 10815 5399 10816 5398 10816 5373 10816 5373 10817 5398 10817 5384 10817 5373 10818 5384 10818 5400 10818 5400 10819 5384 10819 5381 10819 5400 10820 5381 10820 5405 10820 5405 10821 5381 10821 5380 10821 5382 10822 5375 10822 5402 10822 5402 10823 5375 10823 5401 10823 5402 10824 5401 10824 5387 10824 5387 10825 5401 10825 5403 10825 5387 10826 5403 10826 5386 10826 5386 10827 5403 10827 5410 10827 5382 10828 5383 10828 5375 10828 5375 10829 5383 10829 5404 10829 5380 10830 5379 10830 5405 10830 5405 10831 5379 10831 5396 10831 5378 10832 5406 10832 5407 10832 5407 10833 5406 10833 5408 10833 5374 10834 5409 10834 5410 10834 5410 10835 5409 10835 5386 10835 5433 10836 5411 10836 5418 10836 5440 10837 5435 10837 5414 10837 5418 10838 5411 10838 5416 10838 5411 10839 5428 10839 5438 10839 5443 10840 5445 10840 5413 10840 5413 10841 5445 10841 5412 10841 5413 10842 5412 10842 5446 10842 5446 10843 5412 10843 5414 10843 5447 10844 5415 10844 5450 10844 5450 10845 5415 10845 5416 10845 5450 10846 5416 10846 5412 10846 5412 10847 5416 10847 5411 10847 5412 10848 5411 10848 5414 10848 5414 10849 5411 10849 5438 10849 5414 10850 5438 10850 5440 10850 5429 10851 5417 10851 5418 10851 5418 10852 5417 10852 5419 10852 5418 10853 5419 10853 5433 10853 5422 10854 5423 10854 5427 10854 5439 10855 5420 10855 5425 10855 5425 10856 5420 10856 5426 10856 5448 10857 5421 10857 5449 10857 5449 10858 5421 10858 5422 10858 5449 10859 5422 10859 5425 10859 5425 10860 5422 10860 5427 10860 5425 10861 5427 10861 5439 10861 5423 10862 5424 10862 5444 10862 5431 10863 5430 10863 5432 10863 5432 10864 5430 10864 5425 10864 5432 10865 5425 10865 5434 10865 5434 10866 5425 10866 5426 10866 5444 10867 5442 10867 5423 10867 5423 10868 5442 10868 5441 10868 5423 10869 5441 10869 5427 10869 5427 10870 5441 10870 5437 10870 5427 10871 5437 10871 5436 10871 5439 10872 5438 10872 5420 10872 5420 10873 5438 10873 5428 10873 5420 10874 5428 10874 5426 10874 5426 10875 5428 10875 5411 10875 5418 10876 5425 10876 5429 10876 5429 10877 5425 10877 5430 10877 5429 10878 5430 10878 5417 10878 5417 10879 5430 10879 5431 10879 5417 10880 5431 10880 5419 10880 5419 10881 5431 10881 5432 10881 5419 10882 5432 10882 5433 10882 5433 10883 5432 10883 5434 10883 5434 10884 5426 10884 5433 10884 5433 10885 5426 10885 5411 10885 5440 10886 5427 10886 5435 10886 5435 10887 5427 10887 5436 10887 5435 10888 5436 10888 5414 10888 5414 10889 5436 10889 5437 10889 5438 10890 5439 10890 5440 10890 5440 10891 5439 10891 5427 10891 5446 10892 5441 10892 5413 10892 5413 10893 5441 10893 5442 10893 5413 10894 5442 10894 5443 10894 5443 10895 5442 10895 5444 10895 5443 10896 5444 10896 5445 10896 5445 10897 5444 10897 5424 10897 5445 10898 5424 10898 5412 10898 5412 10899 5424 10899 5423 10899 5414 10900 5437 10900 5446 10900 5446 10901 5437 10901 5441 10901 5450 10902 5422 10902 5447 10902 5447 10903 5422 10903 5421 10903 5447 10904 5421 10904 5415 10904 5415 10905 5421 10905 5448 10905 5415 10906 5448 10906 5416 10906 5416 10907 5448 10907 5449 10907 5412 10908 5423 10908 5450 10908 5450 10909 5423 10909 5422 10909 5416 10910 5449 10910 5418 10910 5418 10911 5449 10911 5425 10911 5459 10912 5454 10912 5461 10912 5461 10913 5471 10913 5451 10913 5482 10914 5480 10914 5452 10914 5452 10915 5480 10915 5460 10915 5452 10916 5460 10916 5474 10916 5453 10917 5455 10917 5454 10917 5454 10918 5455 10918 5456 10918 5454 10919 5456 10919 5461 10919 5475 10920 5458 10920 5457 10920 5457 10921 5458 10921 5459 10921 5457 10922 5459 10922 5460 10922 5460 10923 5459 10923 5461 10923 5460 10924 5461 10924 5474 10924 5474 10925 5461 10925 5451 10925 5466 10926 5479 10926 5470 10926 5468 10927 5469 10927 5467 10927 5467 10928 5469 10928 5478 10928 5473 10929 5472 10929 5462 10929 5462 10930 5472 10930 5470 10930 5462 10931 5470 10931 5463 10931 5463 10932 5470 10932 5479 10932 5463 10933 5479 10933 5481 10933 5481 10934 5479 10934 5464 10934 5476 10935 5465 10935 5477 10935 5477 10936 5465 10936 5466 10936 5477 10937 5466 10937 5478 10937 5478 10938 5466 10938 5470 10938 5478 10939 5470 10939 5467 10939 5467 10940 5456 10940 5468 10940 5468 10941 5456 10941 5455 10941 5468 10942 5455 10942 5469 10942 5469 10943 5455 10943 5453 10943 5469 10944 5453 10944 5478 10944 5478 10945 5453 10945 5454 10945 5461 10946 5470 10946 5471 10946 5471 10947 5470 10947 5472 10947 5471 10948 5472 10948 5451 10948 5451 10949 5472 10949 5473 10949 5451 10950 5473 10950 5474 10950 5474 10951 5473 10951 5462 10951 5456 10952 5467 10952 5461 10952 5461 10953 5467 10953 5470 10953 5457 10954 5466 10954 5475 10954 5475 10955 5466 10955 5465 10955 5475 10956 5465 10956 5458 10956 5458 10957 5465 10957 5476 10957 5458 10958 5476 10958 5459 10958 5459 10959 5476 10959 5477 10959 5477 10960 5478 10960 5459 10960 5459 10961 5478 10961 5454 10961 5479 10962 5460 10962 5464 10962 5464 10963 5460 10963 5480 10963 5464 10964 5480 10964 5481 10964 5481 10965 5480 10965 5482 10965 5481 10966 5482 10966 5463 10966 5463 10967 5482 10967 5452 10967 5479 10968 5466 10968 5460 10968 5460 10969 5466 10969 5457 10969 5474 10970 5462 10970 5452 10970 5452 10971 5462 10971 5463 10971 5502 10972 5484 10972 5483 10972 5483 10973 5484 10973 5485 10973 5483 10974 5485 10974 5499 10974 5499 10975 5485 10975 5486 10975 5499 10976 5486 10976 5498 10976 5498 10977 5486 10977 5497 10977 5505 10978 5506 10978 5503 10978 5503 10979 5506 10979 5507 10979 5512 10980 5511 10980 5509 10980 5509 10981 5514 10981 5512 10981 5512 10982 5514 10982 5486 10982 5512 10983 5486 10983 5507 10983 5507 10984 5486 10984 5485 10984 5507 10985 5485 10985 5503 10985 5491 10986 5501 10986 5510 10986 5510 10987 5501 10987 5500 10987 5487 10988 5488 10988 5489 10988 5489 10989 5488 10989 5501 10989 5489 10990 5501 10990 5490 10990 5490 10991 5501 10991 5491 10991 5490 10992 5491 10992 5504 10992 5504 10993 5491 10993 5508 10993 5492 10994 5493 10994 5513 10994 5513 10995 5493 10995 5510 10995 5513 10996 5510 10996 5494 10996 5494 10997 5510 10997 5500 10997 5494 10998 5500 10998 5495 10998 5495 10999 5500 10999 5496 10999 5486 11000 5494 11000 5497 11000 5497 11001 5494 11001 5495 11001 5497 11002 5495 11002 5498 11002 5498 11003 5495 11003 5496 11003 5498 11004 5496 11004 5499 11004 5499 11005 5496 11005 5500 11005 5489 11006 5485 11006 5487 11006 5487 11007 5485 11007 5484 11007 5487 11008 5484 11008 5488 11008 5488 11009 5484 11009 5502 11009 5488 11010 5502 11010 5501 11010 5501 11011 5502 11011 5483 11011 5503 11012 5490 11012 5505 11012 5505 11013 5490 11013 5504 11013 5505 11014 5504 11014 5506 11014 5506 11015 5504 11015 5508 11015 5506 11016 5508 11016 5507 11016 5507 11017 5508 11017 5491 11017 5485 11018 5489 11018 5503 11018 5503 11019 5489 11019 5490 11019 5513 11020 5514 11020 5492 11020 5492 11021 5514 11021 5509 11021 5492 11022 5509 11022 5493 11022 5493 11023 5509 11023 5511 11023 5493 11024 5511 11024 5510 11024 5510 11025 5511 11025 5512 11025 5507 11026 5491 11026 5512 11026 5512 11027 5491 11027 5510 11027 5513 11028 5494 11028 5514 11028 5514 11029 5494 11029 5486 11029 5500 11030 5501 11030 5499 11030 5499 11031 5501 11031 5483 11031 5542 11032 5517 11032 5516 11032 5515 11033 5552 11033 5519 11033 5543 11034 5542 11034 5545 11034 5545 11035 5542 11035 5516 11035 5545 11036 5516 11036 5546 11036 5546 11037 5516 11037 5549 11037 5517 11038 5542 11038 5540 11038 5540 11039 5542 11039 5518 11039 5540 11040 5518 11040 5521 11040 5522 11041 5515 11041 5523 11041 5523 11042 5515 11042 5519 11042 5523 11043 5519 11043 5518 11043 5518 11044 5519 11044 5520 11044 5518 11045 5520 11045 5521 11045 5559 11046 5558 11046 5525 11046 5525 11047 5558 11047 5527 11047 5522 11048 5523 11048 5524 11048 5524 11049 5523 11049 5525 11049 5524 11050 5525 11050 5526 11050 5526 11051 5525 11051 5527 11051 5526 11052 5527 11052 5528 11052 5548 11053 5530 11053 5541 11053 5539 11054 5529 11054 5560 11054 5560 11055 5529 11055 5535 11055 5535 11056 5529 11056 5554 11056 5535 11057 5554 11057 5553 11057 5541 11058 5530 11058 5560 11058 5560 11059 5530 11059 5538 11059 5560 11060 5538 11060 5539 11060 5531 11061 5547 11061 5544 11061 5544 11062 5547 11062 5548 11062 5544 11063 5548 11063 5532 11063 5532 11064 5548 11064 5541 11064 5557 11065 5536 11065 5533 11065 5533 11066 5536 11066 5534 11066 5533 11067 5534 11067 5556 11067 5556 11068 5534 11068 5555 11068 5553 11069 5551 11069 5535 11069 5535 11070 5551 11070 5550 11070 5535 11071 5550 11071 5536 11071 5536 11072 5550 11072 5537 11072 5536 11073 5537 11073 5534 11073 5530 11074 5517 11074 5538 11074 5538 11075 5517 11075 5540 11075 5538 11076 5540 11076 5539 11076 5539 11077 5540 11077 5521 11077 5539 11078 5521 11078 5529 11078 5529 11079 5521 11079 5520 11079 5541 11080 5542 11080 5532 11080 5532 11081 5542 11081 5543 11081 5532 11082 5543 11082 5544 11082 5544 11083 5543 11083 5545 11083 5544 11084 5545 11084 5531 11084 5531 11085 5545 11085 5546 11085 5531 11086 5546 11086 5547 11086 5547 11087 5546 11087 5549 11087 5547 11088 5549 11088 5548 11088 5548 11089 5549 11089 5516 11089 5517 11090 5530 11090 5516 11090 5516 11091 5530 11091 5548 11091 5524 11092 5537 11092 5522 11092 5522 11093 5537 11093 5550 11093 5522 11094 5550 11094 5515 11094 5515 11095 5550 11095 5551 11095 5515 11096 5551 11096 5552 11096 5552 11097 5551 11097 5553 11097 5552 11098 5553 11098 5519 11098 5519 11099 5553 11099 5554 11099 5554 11100 5529 11100 5519 11100 5519 11101 5529 11101 5520 11101 5534 11102 5526 11102 5555 11102 5555 11103 5526 11103 5528 11103 5555 11104 5528 11104 5556 11104 5556 11105 5528 11105 5527 11105 5556 11106 5527 11106 5533 11106 5533 11107 5527 11107 5558 11107 5533 11108 5558 11108 5557 11108 5557 11109 5558 11109 5559 11109 5557 11110 5559 11110 5536 11110 5536 11111 5559 11111 5525 11111 5534 11112 5537 11112 5526 11112 5526 11113 5537 11113 5524 11113 5536 11114 5525 11114 5523 11114 5536 11115 5523 11115 5535 11115 5535 11116 5523 11116 5518 11116 5535 11117 5518 11117 5560 11117 5560 11118 5518 11118 5542 11118 5560 11119 5542 11119 5541 11119 5561 11120 5563 11120 5562 11120 5563 11121 5580 11121 5566 11121 5577 11122 5578 11122 5564 11122 5564 11123 5578 11123 5593 11123 5575 11124 5565 11124 5587 11124 5587 11125 5565 11125 5562 11125 5587 11126 5562 11126 5584 11126 5584 11127 5562 11127 5563 11127 5584 11128 5563 11128 5583 11128 5583 11129 5563 11129 5566 11129 5590 11130 5589 11130 5594 11130 5594 11131 5589 11131 5561 11131 5594 11132 5561 11132 5593 11132 5593 11133 5561 11133 5562 11133 5593 11134 5562 11134 5564 11134 5586 11135 5585 11135 5571 11135 5569 11136 5579 11136 5568 11136 5572 11137 5573 11137 5570 11137 5570 11138 5573 11138 5574 11138 5570 11139 5574 11139 5586 11139 5588 11140 5591 11140 5567 11140 5567 11141 5591 11141 5592 11141 5567 11142 5592 11142 5581 11142 5568 11143 5576 11143 5569 11143 5569 11144 5576 11144 5570 11144 5569 11145 5570 11145 5592 11145 5592 11146 5570 11146 5586 11146 5592 11147 5586 11147 5581 11147 5581 11148 5586 11148 5571 11148 5581 11149 5571 11149 5582 11149 5570 11150 5562 11150 5572 11150 5572 11151 5562 11151 5565 11151 5572 11152 5565 11152 5573 11152 5573 11153 5565 11153 5575 11153 5573 11154 5575 11154 5574 11154 5574 11155 5575 11155 5587 11155 5564 11156 5576 11156 5577 11156 5577 11157 5576 11157 5568 11157 5577 11158 5568 11158 5578 11158 5578 11159 5568 11159 5579 11159 5578 11160 5579 11160 5593 11160 5593 11161 5579 11161 5569 11161 5562 11162 5570 11162 5564 11162 5564 11163 5570 11163 5576 11163 5563 11164 5581 11164 5580 11164 5580 11165 5581 11165 5582 11165 5580 11166 5582 11166 5566 11166 5566 11167 5582 11167 5571 11167 5566 11168 5571 11168 5583 11168 5583 11169 5571 11169 5585 11169 5583 11170 5585 11170 5584 11170 5584 11171 5585 11171 5586 11171 5586 11172 5574 11172 5584 11172 5584 11173 5574 11173 5587 11173 5567 11174 5561 11174 5588 11174 5588 11175 5561 11175 5589 11175 5588 11176 5589 11176 5591 11176 5591 11177 5589 11177 5590 11177 5591 11178 5590 11178 5592 11178 5592 11179 5590 11179 5594 11179 5567 11180 5581 11180 5561 11180 5561 11181 5581 11181 5563 11181 5593 11182 5569 11182 5594 11182 5594 11183 5569 11183 5592 11183 5625 11184 5606 11184 5609 11184 5616 11185 5595 11185 5625 11185 5596 11186 5614 11186 5597 11186 5597 11187 5614 11187 5612 11187 5597 11188 5612 11188 5610 11188 5623 11189 5622 11189 5595 11189 5595 11190 5622 11190 5598 11190 5595 11191 5598 11191 5625 11191 5599 11192 5615 11192 5619 11192 5619 11193 5615 11193 5616 11193 5619 11194 5616 11194 5612 11194 5612 11195 5616 11195 5625 11195 5612 11196 5625 11196 5610 11196 5610 11197 5625 11197 5609 11197 5603 11198 5611 11198 5613 11198 5624 11199 5618 11199 5603 11199 5608 11200 5607 11200 5626 11200 5626 11201 5607 11201 5605 11201 5626 11202 5605 11202 5604 11202 5617 11203 5600 11203 5618 11203 5618 11204 5600 11204 5620 11204 5618 11205 5620 11205 5603 11205 5621 11206 5601 11206 5602 11206 5602 11207 5601 11207 5624 11207 5602 11208 5624 11208 5605 11208 5605 11209 5624 11209 5603 11209 5605 11210 5603 11210 5604 11210 5604 11211 5603 11211 5613 11211 5625 11212 5605 11212 5606 11212 5606 11213 5605 11213 5607 11213 5606 11214 5607 11214 5609 11214 5609 11215 5607 11215 5608 11215 5609 11216 5608 11216 5610 11216 5610 11217 5608 11217 5626 11217 5603 11218 5612 11218 5611 11218 5611 11219 5612 11219 5614 11219 5611 11220 5614 11220 5613 11220 5613 11221 5614 11221 5596 11221 5613 11222 5596 11222 5604 11222 5604 11223 5596 11223 5597 11223 5619 11224 5620 11224 5599 11224 5599 11225 5620 11225 5600 11225 5599 11226 5600 11226 5615 11226 5615 11227 5600 11227 5617 11227 5615 11228 5617 11228 5616 11228 5616 11229 5617 11229 5618 11229 5612 11230 5603 11230 5619 11230 5619 11231 5603 11231 5620 11231 5602 11232 5598 11232 5621 11232 5621 11233 5598 11233 5622 11233 5621 11234 5622 11234 5601 11234 5601 11235 5622 11235 5623 11235 5601 11236 5623 11236 5624 11236 5624 11237 5623 11237 5595 11237 5616 11238 5618 11238 5595 11238 5595 11239 5618 11239 5624 11239 5602 11240 5605 11240 5598 11240 5598 11241 5605 11241 5625 11241 5626 11242 5604 11242 5610 11242 5610 11243 5604 11243 5597 11243 5631 11244 5662 11244 5627 11244 5627 11245 5662 11245 5653 11245 5668 11246 5665 11246 5628 11246 5628 11247 5665 11247 5629 11247 5661 11248 5662 11248 5630 11248 5630 11249 5662 11249 5631 11249 5630 11250 5631 11250 5632 11250 5632 11251 5631 11251 5628 11251 5632 11252 5628 11252 5663 11252 5663 11253 5628 11253 5629 11253 5663 11254 5629 11254 5633 11254 5634 11255 5654 11255 5636 11255 5636 11256 5654 11256 5635 11256 5636 11257 5635 11257 5637 11257 5637 11258 5635 11258 5638 11258 5653 11259 5652 11259 5627 11259 5627 11260 5652 11260 5651 11260 5627 11261 5651 11261 5635 11261 5635 11262 5651 11262 5659 11262 5635 11263 5659 11263 5638 11263 5667 11264 5669 11264 5639 11264 5644 11265 5640 11265 5646 11265 5645 11266 5650 11266 5643 11266 5666 11267 5667 11267 5641 11267 5641 11268 5667 11268 5639 11268 5641 11269 5639 11269 5642 11269 5642 11270 5639 11270 5664 11270 5669 11271 5667 11271 5660 11271 5660 11272 5667 11272 5670 11272 5660 11273 5670 11273 5648 11273 5643 11274 5644 11274 5645 11274 5645 11275 5644 11275 5646 11275 5645 11276 5646 11276 5670 11276 5670 11277 5646 11277 5647 11277 5670 11278 5647 11278 5648 11278 5655 11279 5656 11279 5649 11279 5649 11280 5656 11280 5657 11280 5649 11281 5657 11281 5650 11281 5650 11282 5657 11282 5658 11282 5650 11283 5658 11283 5643 11283 5643 11284 5659 11284 5644 11284 5644 11285 5659 11285 5651 11285 5644 11286 5651 11286 5640 11286 5640 11287 5651 11287 5652 11287 5640 11288 5652 11288 5646 11288 5646 11289 5652 11289 5653 11289 5650 11290 5635 11290 5649 11290 5649 11291 5635 11291 5654 11291 5649 11292 5654 11292 5655 11292 5655 11293 5654 11293 5634 11293 5655 11294 5634 11294 5656 11294 5656 11295 5634 11295 5636 11295 5656 11296 5636 11296 5657 11296 5657 11297 5636 11297 5637 11297 5657 11298 5637 11298 5658 11298 5658 11299 5637 11299 5638 11299 5659 11300 5643 11300 5638 11300 5638 11301 5643 11301 5658 11301 5632 11302 5669 11302 5630 11302 5630 11303 5669 11303 5660 11303 5630 11304 5660 11304 5661 11304 5661 11305 5660 11305 5648 11305 5661 11306 5648 11306 5662 11306 5662 11307 5648 11307 5647 11307 5647 11308 5646 11308 5662 11308 5662 11309 5646 11309 5653 11309 5639 11310 5663 11310 5664 11310 5664 11311 5663 11311 5633 11311 5664 11312 5633 11312 5642 11312 5642 11313 5633 11313 5629 11313 5642 11314 5629 11314 5641 11314 5641 11315 5629 11315 5665 11315 5641 11316 5665 11316 5666 11316 5666 11317 5665 11317 5668 11317 5666 11318 5668 11318 5667 11318 5667 11319 5668 11319 5628 11319 5639 11320 5669 11320 5663 11320 5663 11321 5669 11321 5632 11321 5667 11322 5628 11322 5631 11322 5667 11323 5631 11323 5670 11323 5670 11324 5631 11324 5627 11324 5670 11325 5627 11325 5645 11325 5645 11326 5627 11326 5635 11326 5645 11327 5635 11327 5650 11327 5699 11328 5700 11328 5676 11328 5678 11329 5677 11329 5671 11329 5671 11330 5677 11330 5706 11330 5672 11331 5673 11331 5693 11331 5704 11332 5674 11332 5675 11332 5675 11333 5674 11333 5677 11333 5675 11334 5677 11334 5676 11334 5676 11335 5677 11335 5678 11335 5676 11336 5678 11336 5699 11336 5699 11337 5678 11337 5679 11337 5695 11338 5680 11338 5706 11338 5706 11339 5680 11339 5681 11339 5706 11340 5681 11340 5671 11340 5671 11341 5681 11341 5672 11341 5671 11342 5672 11342 5690 11342 5690 11343 5672 11343 5693 11343 5702 11344 5684 11344 5685 11344 5686 11345 5703 11345 5688 11345 5697 11346 5696 11346 5682 11346 5682 11347 5696 11347 5705 11347 5682 11348 5705 11348 5683 11348 5692 11349 5694 11349 5691 11349 5691 11350 5694 11350 5683 11350 5691 11351 5683 11351 5684 11351 5684 11352 5683 11352 5705 11352 5684 11353 5705 11353 5685 11353 5685 11354 5705 11354 5686 11354 5685 11355 5686 11355 5687 11355 5687 11356 5686 11356 5688 11356 5701 11357 5689 11357 5685 11357 5685 11358 5689 11358 5698 11358 5685 11359 5698 11359 5702 11359 5684 11360 5671 11360 5691 11360 5691 11361 5671 11361 5690 11361 5691 11362 5690 11362 5692 11362 5692 11363 5690 11363 5693 11363 5692 11364 5693 11364 5694 11364 5694 11365 5693 11365 5673 11365 5694 11366 5673 11366 5683 11366 5683 11367 5673 11367 5672 11367 5706 11368 5705 11368 5695 11368 5695 11369 5705 11369 5696 11369 5695 11370 5696 11370 5680 11370 5680 11371 5696 11371 5697 11371 5680 11372 5697 11372 5681 11372 5681 11373 5697 11373 5682 11373 5682 11374 5683 11374 5681 11374 5681 11375 5683 11375 5672 11375 5678 11376 5702 11376 5679 11376 5679 11377 5702 11377 5698 11377 5679 11378 5698 11378 5699 11378 5699 11379 5698 11379 5689 11379 5699 11380 5689 11380 5700 11380 5700 11381 5689 11381 5701 11381 5700 11382 5701 11382 5676 11382 5676 11383 5701 11383 5685 11383 5671 11384 5684 11384 5678 11384 5678 11385 5684 11385 5702 11385 5686 11386 5677 11386 5703 11386 5703 11387 5677 11387 5674 11387 5703 11388 5674 11388 5688 11388 5688 11389 5674 11389 5704 11389 5688 11390 5704 11390 5687 11390 5687 11391 5704 11391 5675 11391 5676 11392 5685 11392 5675 11392 5675 11393 5685 11393 5687 11393 5686 11394 5705 11394 5677 11394 5677 11395 5705 11395 5706 11395 5731 11396 5733 11396 5707 11396 5714 11397 5727 11397 5745 11397 5710 11398 5707 11398 5735 11398 5735 11399 5707 11399 5746 11399 5735 11400 5746 11400 5736 11400 5710 11401 5737 11401 5708 11401 5731 11402 5707 11402 5709 11402 5743 11403 5729 11403 5712 11403 5708 11404 5740 11404 5710 11404 5710 11405 5740 11405 5741 11405 5710 11406 5741 11406 5707 11406 5707 11407 5741 11407 5711 11407 5707 11408 5711 11408 5709 11408 5712 11409 5713 11409 5743 11409 5743 11410 5713 11410 5714 11410 5743 11411 5714 11411 5707 11411 5707 11412 5714 11412 5745 11412 5707 11413 5745 11413 5746 11413 5726 11414 5715 11414 5721 11414 5744 11415 5728 11415 5725 11415 5719 11416 5716 11416 5717 11416 5717 11417 5718 11417 5719 11417 5719 11418 5718 11418 5739 11418 5719 11419 5739 11419 5738 11419 5724 11420 5730 11420 5720 11420 5734 11421 5722 11421 5721 11421 5721 11422 5722 11422 5723 11422 5720 11423 5742 11423 5724 11423 5724 11424 5742 11424 5734 11424 5724 11425 5734 11425 5725 11425 5725 11426 5734 11426 5721 11426 5725 11427 5721 11427 5744 11427 5719 11428 5726 11428 5716 11428 5716 11429 5726 11429 5721 11429 5716 11430 5721 11430 5732 11430 5732 11431 5721 11431 5723 11431 5714 11432 5725 11432 5727 11432 5727 11433 5725 11433 5728 11433 5727 11434 5728 11434 5745 11434 5745 11435 5728 11435 5744 11435 5743 11436 5742 11436 5729 11436 5729 11437 5742 11437 5720 11437 5729 11438 5720 11438 5712 11438 5712 11439 5720 11439 5730 11439 5712 11440 5730 11440 5713 11440 5713 11441 5730 11441 5724 11441 5711 11442 5716 11442 5709 11442 5709 11443 5716 11443 5732 11443 5709 11444 5732 11444 5731 11444 5731 11445 5732 11445 5723 11445 5731 11446 5723 11446 5733 11446 5733 11447 5723 11447 5722 11447 5733 11448 5722 11448 5707 11448 5707 11449 5722 11449 5734 11449 5726 11450 5735 11450 5715 11450 5715 11451 5735 11451 5736 11451 5715 11452 5736 11452 5721 11452 5721 11453 5736 11453 5746 11453 5710 11454 5719 11454 5737 11454 5737 11455 5719 11455 5738 11455 5737 11456 5738 11456 5708 11456 5708 11457 5738 11457 5739 11457 5708 11458 5739 11458 5740 11458 5740 11459 5739 11459 5718 11459 5740 11460 5718 11460 5741 11460 5741 11461 5718 11461 5717 11461 5735 11462 5726 11462 5710 11462 5710 11463 5726 11463 5719 11463 5717 11464 5716 11464 5741 11464 5741 11465 5716 11465 5711 11465 5734 11466 5742 11466 5707 11466 5707 11467 5742 11467 5743 11467 5724 11468 5725 11468 5713 11468 5713 11469 5725 11469 5714 11469 5744 11470 5721 11470 5745 11470 5745 11471 5721 11471 5746 11471 5771 11472 5774 11472 5755 11472 5751 11473 5747 11473 5768 11473 5748 11474 5749 11474 5777 11474 5752 11475 5750 11475 5783 11475 5783 11476 5750 11476 5751 11476 5783 11477 5751 11477 5766 11477 5766 11478 5751 11478 5768 11478 5762 11479 5753 11479 5752 11479 5752 11480 5753 11480 5754 11480 5752 11481 5754 11481 5750 11481 5752 11482 5771 11482 5762 11482 5762 11483 5771 11483 5755 11483 5762 11484 5755 11484 5761 11484 5761 11485 5755 11485 5781 11485 5761 11486 5781 11486 5777 11486 5777 11487 5781 11487 5779 11487 5777 11488 5779 11488 5748 11488 5759 11489 5780 11489 5758 11489 5773 11490 5772 11490 5775 11490 5775 11491 5772 11491 5770 11491 5775 11492 5770 11492 5782 11492 5782 11493 5770 11493 5758 11493 5757 11494 5767 11494 5756 11494 5756 11495 5769 11495 5757 11495 5757 11496 5769 11496 5784 11496 5757 11497 5784 11497 5770 11497 5770 11498 5784 11498 5776 11498 5770 11499 5776 11499 5758 11499 5758 11500 5776 11500 5778 11500 5758 11501 5778 11501 5759 11501 5763 11502 5760 11502 5764 11502 5764 11503 5760 11503 5784 11503 5764 11504 5784 11504 5765 11504 5765 11505 5784 11505 5769 11505 5761 11506 5784 11506 5762 11506 5762 11507 5784 11507 5760 11507 5762 11508 5760 11508 5753 11508 5753 11509 5760 11509 5763 11509 5753 11510 5763 11510 5754 11510 5754 11511 5763 11511 5764 11511 5754 11512 5764 11512 5750 11512 5750 11513 5764 11513 5765 11513 5757 11514 5766 11514 5767 11514 5767 11515 5766 11515 5768 11515 5767 11516 5768 11516 5756 11516 5756 11517 5768 11517 5747 11517 5756 11518 5747 11518 5769 11518 5769 11519 5747 11519 5751 11519 5750 11520 5765 11520 5751 11520 5751 11521 5765 11521 5769 11521 5783 11522 5770 11522 5752 11522 5752 11523 5770 11523 5772 11523 5752 11524 5772 11524 5771 11524 5771 11525 5772 11525 5773 11525 5771 11526 5773 11526 5774 11526 5774 11527 5773 11527 5775 11527 5774 11528 5775 11528 5755 11528 5755 11529 5775 11529 5782 11529 5776 11530 5777 11530 5778 11530 5778 11531 5777 11531 5749 11531 5778 11532 5749 11532 5759 11532 5759 11533 5749 11533 5748 11533 5759 11534 5748 11534 5780 11534 5780 11535 5748 11535 5779 11535 5780 11536 5779 11536 5758 11536 5758 11537 5779 11537 5781 11537 5755 11538 5782 11538 5781 11538 5781 11539 5782 11539 5758 11539 5766 11540 5757 11540 5783 11540 5783 11541 5757 11541 5770 11541 5776 11542 5784 11542 5777 11542 5777 11543 5784 11543 5761 11543 5813 11544 5814 11544 5785 11544 5785 11545 5814 11545 5786 11545 5785 11546 5786 11546 5815 11546 5818 11547 5816 11547 5787 11547 5787 11548 5816 11548 5815 11548 5787 11549 5815 11549 5820 11549 5820 11550 5815 11550 5786 11550 5794 11551 5788 11551 5792 11551 5789 11552 5809 11552 5790 11552 5790 11553 5809 11553 5795 11553 5790 11554 5795 11554 5791 11554 5792 11555 5793 11555 5794 11555 5794 11556 5793 11556 5785 11556 5794 11557 5785 11557 5795 11557 5795 11558 5785 11558 5815 11558 5795 11559 5815 11559 5791 11559 5796 11560 5811 11560 5797 11560 5797 11561 5811 11561 5801 11561 5797 11562 5801 11562 5807 11562 5798 11563 5800 11563 5799 11563 5799 11564 5800 11564 5807 11564 5799 11565 5807 11565 5810 11565 5810 11566 5807 11566 5801 11566 5802 11567 5803 11567 5812 11567 5808 11568 5817 11568 5806 11568 5806 11569 5817 11569 5804 11569 5806 11570 5804 11570 5819 11570 5812 11571 5805 11571 5802 11571 5802 11572 5805 11572 5797 11572 5802 11573 5797 11573 5806 11573 5806 11574 5797 11574 5807 11574 5806 11575 5807 11575 5808 11575 5791 11576 5807 11576 5790 11576 5790 11577 5807 11577 5800 11577 5790 11578 5800 11578 5789 11578 5789 11579 5800 11579 5798 11579 5789 11580 5798 11580 5809 11580 5809 11581 5798 11581 5799 11581 5809 11582 5799 11582 5795 11582 5795 11583 5799 11583 5810 11583 5797 11584 5793 11584 5796 11584 5796 11585 5793 11585 5792 11585 5796 11586 5792 11586 5811 11586 5811 11587 5792 11587 5788 11587 5811 11588 5788 11588 5801 11588 5801 11589 5788 11589 5794 11589 5795 11590 5810 11590 5794 11590 5794 11591 5810 11591 5801 11591 5785 11592 5805 11592 5813 11592 5813 11593 5805 11593 5812 11593 5813 11594 5812 11594 5814 11594 5814 11595 5812 11595 5803 11595 5814 11596 5803 11596 5786 11596 5786 11597 5803 11597 5802 11597 5808 11598 5815 11598 5817 11598 5817 11599 5815 11599 5816 11599 5817 11600 5816 11600 5804 11600 5804 11601 5816 11601 5818 11601 5804 11602 5818 11602 5819 11602 5819 11603 5818 11603 5787 11603 5819 11604 5787 11604 5806 11604 5806 11605 5787 11605 5820 11605 5786 11606 5802 11606 5820 11606 5820 11607 5802 11607 5806 11607 5808 11608 5807 11608 5815 11608 5815 11609 5807 11609 5791 11609 5793 11610 5797 11610 5785 11610 5785 11611 5797 11611 5805 11611 5844 11612 5846 11612 5829 11612 5844 11613 5829 11613 5843 11613 5842 11614 5821 11614 5823 11614 5823 11615 5821 11615 5822 11615 5823 11616 5822 11616 5826 11616 5824 11617 5825 11617 5852 11617 5852 11618 5825 11618 5826 11618 5852 11619 5826 11619 5827 11619 5827 11620 5826 11620 5822 11620 5827 11621 5822 11621 5838 11621 5840 11622 5828 11622 5851 11622 5851 11623 5828 11623 5842 11623 5851 11624 5842 11624 5829 11624 5829 11625 5842 11625 5823 11625 5829 11626 5823 11626 5843 11626 5830 11627 5845 11627 5850 11627 5837 11628 5850 11628 5848 11628 5847 11629 5830 11629 5831 11629 5831 11630 5830 11630 5850 11630 5831 11631 5850 11631 5833 11631 5833 11632 5850 11632 5837 11632 5839 11633 5841 11633 5832 11633 5832 11634 5841 11634 5833 11634 5832 11635 5833 11635 5834 11635 5834 11636 5833 11636 5837 11636 5835 11637 5849 11637 5848 11637 5848 11638 5849 11638 5854 11638 5848 11639 5854 11639 5837 11639 5837 11640 5854 11640 5853 11640 5837 11641 5853 11641 5836 11641 5821 11642 5834 11642 5822 11642 5822 11643 5834 11643 5837 11643 5822 11644 5837 11644 5838 11644 5838 11645 5837 11645 5836 11645 5838 11646 5836 11646 5827 11646 5827 11647 5836 11647 5853 11647 5832 11648 5842 11648 5839 11648 5839 11649 5842 11649 5828 11649 5839 11650 5828 11650 5841 11650 5841 11651 5828 11651 5840 11651 5841 11652 5840 11652 5833 11652 5833 11653 5840 11653 5851 11653 5832 11654 5834 11654 5842 11654 5842 11655 5834 11655 5821 11655 5823 11656 5850 11656 5843 11656 5843 11657 5850 11657 5845 11657 5843 11658 5845 11658 5844 11658 5844 11659 5845 11659 5830 11659 5844 11660 5830 11660 5846 11660 5846 11661 5830 11661 5847 11661 5846 11662 5847 11662 5829 11662 5829 11663 5847 11663 5831 11663 5848 11664 5826 11664 5835 11664 5835 11665 5826 11665 5825 11665 5835 11666 5825 11666 5849 11666 5849 11667 5825 11667 5824 11667 5849 11668 5824 11668 5854 11668 5854 11669 5824 11669 5852 11669 5848 11670 5850 11670 5826 11670 5826 11671 5850 11671 5823 11671 5831 11672 5833 11672 5829 11672 5829 11673 5833 11673 5851 11673 5827 11674 5853 11674 5852 11674 5852 11675 5853 11675 5854 11675 5866 11676 5888 11676 5859 11676 5855 11677 5856 11677 5888 11677 5888 11678 5856 11678 5857 11678 5888 11679 5857 11679 5859 11679 5882 11680 5858 11680 5881 11680 5881 11681 5858 11681 5863 11681 5881 11682 5863 11682 5859 11682 5860 11683 5861 11683 5862 11683 5862 11684 5861 11684 5864 11684 5862 11685 5864 11685 5863 11685 5863 11686 5864 11686 5865 11686 5863 11687 5865 11687 5859 11687 5859 11688 5865 11688 5876 11688 5859 11689 5876 11689 5866 11689 5866 11690 5876 11690 5867 11690 5868 11691 5883 11691 5880 11691 5884 11692 5868 11692 5885 11692 5885 11693 5868 11693 5880 11693 5885 11694 5880 11694 5879 11694 5879 11695 5880 11695 5872 11695 5886 11696 5869 11696 5870 11696 5870 11697 5869 11697 5871 11697 5870 11698 5871 11698 5880 11698 5880 11699 5871 11699 5872 11699 5872 11700 5871 11700 5887 11700 5872 11701 5887 11701 5873 11701 5874 11702 5878 11702 5877 11702 5877 11703 5878 11703 5879 11703 5877 11704 5879 11704 5875 11704 5875 11705 5879 11705 5872 11705 5865 11706 5875 11706 5876 11706 5876 11707 5875 11707 5872 11707 5876 11708 5872 11708 5867 11708 5867 11709 5872 11709 5873 11709 5867 11710 5873 11710 5866 11710 5866 11711 5873 11711 5887 11711 5877 11712 5864 11712 5874 11712 5874 11713 5864 11713 5861 11713 5874 11714 5861 11714 5878 11714 5878 11715 5861 11715 5860 11715 5878 11716 5860 11716 5879 11716 5879 11717 5860 11717 5862 11717 5877 11718 5875 11718 5864 11718 5864 11719 5875 11719 5865 11719 5859 11720 5880 11720 5881 11720 5881 11721 5880 11721 5883 11721 5881 11722 5883 11722 5882 11722 5882 11723 5883 11723 5868 11723 5882 11724 5868 11724 5858 11724 5858 11725 5868 11725 5884 11725 5858 11726 5884 11726 5863 11726 5863 11727 5884 11727 5885 11727 5870 11728 5857 11728 5886 11728 5886 11729 5857 11729 5856 11729 5886 11730 5856 11730 5869 11730 5869 11731 5856 11731 5855 11731 5869 11732 5855 11732 5871 11732 5871 11733 5855 11733 5888 11733 5870 11734 5880 11734 5857 11734 5857 11735 5880 11735 5859 11735 5885 11736 5879 11736 5863 11736 5863 11737 5879 11737 5862 11737 5866 11738 5887 11738 5888 11738 5888 11739 5887 11739 5871 11739 5920 11740 5918 11740 5893 11740 5893 11741 5918 11741 5922 11741 5889 11742 5913 11742 5917 11742 5917 11743 5913 11743 5914 11743 5917 11744 5914 11744 5890 11744 5891 11745 5892 11745 5911 11745 5911 11746 5892 11746 5912 11746 5911 11747 5912 11747 5917 11747 5903 11748 5907 11748 5902 11748 5902 11749 5907 11749 5908 11749 5902 11750 5908 11750 5912 11750 5912 11751 5908 11751 5893 11751 5912 11752 5893 11752 5917 11752 5917 11753 5893 11753 5922 11753 5917 11754 5922 11754 5889 11754 5895 11755 5896 11755 5894 11755 5894 11756 5896 11756 5905 11756 5895 11757 5916 11757 5896 11757 5896 11758 5916 11758 5915 11758 5896 11759 5915 11759 5897 11759 5919 11760 5921 11760 5898 11760 5898 11761 5921 11761 5899 11761 5898 11762 5899 11762 5896 11762 5896 11763 5899 11763 5905 11763 5905 11764 5899 11764 5900 11764 5905 11765 5900 11765 5906 11765 5909 11766 5910 11766 5901 11766 5901 11767 5910 11767 5894 11767 5901 11768 5894 11768 5904 11768 5904 11769 5894 11769 5905 11769 5902 11770 5904 11770 5903 11770 5903 11771 5904 11771 5905 11771 5903 11772 5905 11772 5907 11772 5907 11773 5905 11773 5906 11773 5907 11774 5906 11774 5908 11774 5908 11775 5906 11775 5900 11775 5901 11776 5912 11776 5909 11776 5909 11777 5912 11777 5892 11777 5909 11778 5892 11778 5910 11778 5910 11779 5892 11779 5891 11779 5910 11780 5891 11780 5894 11780 5894 11781 5891 11781 5911 11781 5901 11782 5904 11782 5912 11782 5912 11783 5904 11783 5902 11783 5889 11784 5896 11784 5913 11784 5913 11785 5896 11785 5897 11785 5913 11786 5897 11786 5914 11786 5914 11787 5897 11787 5915 11787 5914 11788 5915 11788 5890 11788 5890 11789 5915 11789 5916 11789 5890 11790 5916 11790 5917 11790 5917 11791 5916 11791 5895 11791 5898 11792 5922 11792 5919 11792 5919 11793 5922 11793 5918 11793 5919 11794 5918 11794 5921 11794 5921 11795 5918 11795 5920 11795 5921 11796 5920 11796 5899 11796 5899 11797 5920 11797 5893 11797 5898 11798 5896 11798 5922 11798 5922 11799 5896 11799 5889 11799 5895 11800 5894 11800 5917 11800 5917 11801 5894 11801 5911 11801 5908 11802 5900 11802 5893 11802 5893 11803 5900 11803 5899 11803 5957 11804 5923 11804 5929 11804 5929 11805 5923 11805 5954 11805 5924 11806 5948 11806 5952 11806 5952 11807 5948 11807 5949 11807 5952 11808 5949 11808 5951 11808 5952 11809 5958 11809 5925 11809 5958 11810 5947 11810 5925 11810 5925 11811 5947 11811 5945 11811 5925 11812 5945 11812 5944 11812 5939 11813 5927 11813 5926 11813 5926 11814 5927 11814 5928 11814 5926 11815 5928 11815 5925 11815 5925 11816 5928 11816 5929 11816 5925 11817 5929 11817 5952 11817 5952 11818 5929 11818 5954 11818 5952 11819 5954 11819 5924 11819 5941 11820 5940 11820 5932 11820 5950 11821 5930 11821 5931 11821 5932 11822 5935 11822 5941 11822 5941 11823 5935 11823 5933 11823 5941 11824 5933 11824 5937 11824 5937 11825 5933 11825 5953 11825 5943 11826 5946 11826 5942 11826 5942 11827 5946 11827 5933 11827 5942 11828 5933 11828 5934 11828 5934 11829 5933 11829 5935 11829 5955 11830 5956 11830 5936 11830 5936 11831 5956 11831 5937 11831 5936 11832 5937 11832 5931 11832 5931 11833 5937 11833 5953 11833 5931 11834 5953 11834 5950 11834 5950 11835 5953 11835 5938 11835 5926 11836 5935 11836 5939 11836 5939 11837 5935 11837 5932 11837 5939 11838 5932 11838 5927 11838 5927 11839 5932 11839 5940 11839 5927 11840 5940 11840 5928 11840 5928 11841 5940 11841 5941 11841 5934 11842 5925 11842 5942 11842 5942 11843 5925 11843 5944 11843 5942 11844 5944 11844 5943 11844 5943 11845 5944 11845 5945 11845 5943 11846 5945 11846 5946 11846 5946 11847 5945 11847 5947 11847 5946 11848 5947 11848 5933 11848 5933 11849 5947 11849 5958 11849 5934 11850 5935 11850 5925 11850 5925 11851 5935 11851 5926 11851 5924 11852 5931 11852 5948 11852 5948 11853 5931 11853 5930 11853 5948 11854 5930 11854 5949 11854 5949 11855 5930 11855 5950 11855 5949 11856 5950 11856 5951 11856 5951 11857 5950 11857 5938 11857 5951 11858 5938 11858 5952 11858 5952 11859 5938 11859 5953 11859 5936 11860 5954 11860 5955 11860 5955 11861 5954 11861 5923 11861 5955 11862 5923 11862 5956 11862 5956 11863 5923 11863 5957 11863 5956 11864 5957 11864 5937 11864 5937 11865 5957 11865 5929 11865 5936 11866 5931 11866 5954 11866 5954 11867 5931 11867 5924 11867 5953 11868 5933 11868 5952 11868 5952 11869 5933 11869 5958 11869 5928 11870 5941 11870 5929 11870 5929 11871 5941 11871 5937 11871 5959 11872 5960 11872 5982 11872 5982 11873 5960 11873 5962 11873 5966 11874 5961 11874 5985 11874 5981 11875 5980 11875 5963 11875 5963 11876 5980 11876 5962 11876 5963 11877 5962 11877 5964 11877 5964 11878 5962 11878 5960 11878 5964 11879 5960 11879 5987 11879 5967 11880 5965 11880 5988 11880 5983 11881 5966 11881 5982 11881 5982 11882 5966 11882 5985 11882 5982 11883 5985 11883 5959 11883 5959 11884 5985 11884 5967 11884 5959 11885 5967 11885 5990 11885 5990 11886 5967 11886 5988 11886 5986 11887 5968 11887 5992 11887 5992 11888 5968 11888 5969 11888 5992 11889 5969 11889 5974 11889 5970 11890 5984 11890 5977 11890 5977 11891 5984 11891 5971 11891 5977 11892 5971 11892 5978 11892 5979 11893 5972 11893 5973 11893 5973 11894 5972 11894 5974 11894 5975 11895 5989 11895 5991 11895 5991 11896 5989 11896 5976 11896 5991 11897 5976 11897 5969 11897 5969 11898 5976 11898 5977 11898 5969 11899 5977 11899 5974 11899 5974 11900 5977 11900 5978 11900 5974 11901 5978 11901 5973 11901 5973 11902 5962 11902 5979 11902 5979 11903 5962 11903 5980 11903 5979 11904 5980 11904 5972 11904 5972 11905 5980 11905 5981 11905 5972 11906 5981 11906 5974 11906 5974 11907 5981 11907 5963 11907 5982 11908 5978 11908 5983 11908 5983 11909 5978 11909 5971 11909 5983 11910 5971 11910 5966 11910 5966 11911 5971 11911 5984 11911 5966 11912 5984 11912 5961 11912 5961 11913 5984 11913 5970 11913 5961 11914 5970 11914 5985 11914 5985 11915 5970 11915 5977 11915 5962 11916 5973 11916 5982 11916 5982 11917 5973 11917 5978 11917 5992 11918 5964 11918 5986 11918 5986 11919 5964 11919 5987 11919 5986 11920 5987 11920 5968 11920 5968 11921 5987 11921 5960 11921 5968 11922 5960 11922 5969 11922 5969 11923 5960 11923 5959 11923 5967 11924 5976 11924 5965 11924 5965 11925 5976 11925 5989 11925 5965 11926 5989 11926 5988 11926 5988 11927 5989 11927 5975 11927 5988 11928 5975 11928 5990 11928 5990 11929 5975 11929 5991 11929 5991 11930 5969 11930 5990 11930 5990 11931 5969 11931 5959 11931 5992 11932 5974 11932 5964 11932 5964 11933 5974 11933 5963 11933 5985 11934 5977 11934 5967 11934 5967 11935 5977 11935 5976 11935 5993 11936 5994 11936 5995 11936 5995 11937 5994 11937 5996 11937 6009 11938 6001 11938 5997 11938 5997 11939 6001 11939 6011 11939 5997 11940 6011 11940 5998 11940 6020 11941 5999 11941 6018 11941 6018 11942 5999 11942 6000 11942 6018 11943 6000 11943 6001 11943 6016 11944 6014 11944 6023 11944 6023 11945 6014 11945 6013 11945 6023 11946 6013 11946 6000 11946 6000 11947 6013 11947 5995 11947 6000 11948 5995 11948 6001 11948 6001 11949 5995 11949 5996 11949 6001 11950 5996 11950 6011 11950 6024 11951 6015 11951 6004 11951 6024 11952 6004 11952 6025 11952 6026 11953 6010 11953 6007 11953 6007 11954 6010 11954 6002 11954 6007 11955 6002 11955 6008 11955 6022 11956 6021 11956 6003 11956 6003 11957 6021 11957 6019 11957 6003 11958 6019 11958 6017 11958 6017 11959 6019 11959 6026 11959 6017 11960 6026 11960 6004 11960 6004 11961 6026 11961 6007 11961 6004 11962 6007 11962 6025 11962 6025 11963 6007 11963 6012 11963 6025 11964 6012 11964 6006 11964 6006 11965 6012 11965 6005 11965 6012 11966 5996 11966 6005 11966 6005 11967 5996 11967 5994 11967 6005 11968 5994 11968 6006 11968 6006 11969 5994 11969 5993 11969 6006 11970 5993 11970 6025 11970 6025 11971 5993 11971 5995 11971 6011 11972 6007 11972 5998 11972 5998 11973 6007 11973 6008 11973 5998 11974 6008 11974 5997 11974 5997 11975 6008 11975 6002 11975 5997 11976 6002 11976 6009 11976 6009 11977 6002 11977 6010 11977 6009 11978 6010 11978 6001 11978 6001 11979 6010 11979 6026 11979 5996 11980 6012 11980 6011 11980 6011 11981 6012 11981 6007 11981 6024 11982 6013 11982 6015 11982 6015 11983 6013 11983 6014 11983 6015 11984 6014 11984 6004 11984 6004 11985 6014 11985 6016 11985 6004 11986 6016 11986 6017 11986 6017 11987 6016 11987 6023 11987 6018 11988 6019 11988 6020 11988 6020 11989 6019 11989 6021 11989 6020 11990 6021 11990 5999 11990 5999 11991 6021 11991 6022 11991 5999 11992 6022 11992 6000 11992 6000 11993 6022 11993 6003 11993 6003 11994 6017 11994 6000 11994 6000 11995 6017 11995 6023 11995 6024 11996 6025 11996 6013 11996 6013 11997 6025 11997 5995 11997 6001 11998 6026 11998 6018 11998 6018 11999 6026 11999 6019 11999 6047 12000 6028 12000 6027 12000 6027 12001 6028 12001 6029 12001 6027 12002 6029 12002 6030 12002 6030 12003 6029 12003 6031 12003 6057 12004 6059 12004 6032 12004 6032 12005 6059 12005 6029 12005 6032 12006 6029 12006 6033 12006 6033 12007 6029 12007 6028 12007 6054 12008 6034 12008 6056 12008 6056 12009 6034 12009 6031 12009 6056 12010 6031 12010 6061 12010 6061 12011 6031 12011 6029 12011 6035 12012 6036 12012 6052 12012 6052 12013 6036 12013 6028 12013 6052 12014 6028 12014 6046 12014 6046 12015 6028 12015 6047 12015 6053 12016 6037 12016 6038 12016 6038 12017 6037 12017 6055 12017 6038 12018 6055 12018 6044 12018 6051 12019 6039 12019 6040 12019 6040 12020 6039 12020 6050 12020 6040 12021 6050 12021 6062 12021 6058 12022 6041 12022 6042 12022 6042 12023 6041 12023 6062 12023 6042 12024 6062 12024 6060 12024 6045 12025 6048 12025 6043 12025 6043 12026 6048 12026 6049 12026 6043 12027 6049 12027 6050 12027 6050 12028 6049 12028 6038 12028 6050 12029 6038 12029 6062 12029 6062 12030 6038 12030 6044 12030 6062 12031 6044 12031 6060 12031 6043 12032 6046 12032 6045 12032 6045 12033 6046 12033 6047 12033 6045 12034 6047 12034 6048 12034 6048 12035 6047 12035 6027 12035 6048 12036 6027 12036 6049 12036 6049 12037 6027 12037 6030 12037 6052 12038 6050 12038 6035 12038 6035 12039 6050 12039 6039 12039 6035 12040 6039 12040 6036 12040 6036 12041 6039 12041 6051 12041 6036 12042 6051 12042 6028 12042 6028 12043 6051 12043 6040 12043 6046 12044 6043 12044 6052 12044 6052 12045 6043 12045 6050 12045 6038 12046 6031 12046 6053 12046 6053 12047 6031 12047 6034 12047 6053 12048 6034 12048 6037 12048 6037 12049 6034 12049 6054 12049 6037 12050 6054 12050 6055 12050 6055 12051 6054 12051 6056 12051 6055 12052 6056 12052 6044 12052 6044 12053 6056 12053 6061 12053 6033 12054 6062 12054 6032 12054 6032 12055 6062 12055 6041 12055 6032 12056 6041 12056 6057 12056 6057 12057 6041 12057 6058 12057 6057 12058 6058 12058 6059 12058 6059 12059 6058 12059 6042 12059 6059 12060 6042 12060 6029 12060 6029 12061 6042 12061 6060 12061 6060 12062 6044 12062 6029 12062 6029 12063 6044 12063 6061 12063 6038 12064 6049 12064 6031 12064 6031 12065 6049 12065 6030 12065 6028 12066 6040 12066 6033 12066 6033 12067 6040 12067 6062 12067 6063 12068 6079 12068 6065 12068 6065 12069 6064 12069 6095 12069 6095 12070 6064 12070 6102 12070 6095 12071 6102 12071 6093 12071 6065 12072 6095 12072 6063 12072 6063 12073 6095 12073 6096 12073 6063 12074 6096 12074 6098 12074 6089 12075 6088 12075 6091 12075 6091 12076 6088 12076 6063 12076 6091 12077 6063 12077 6099 12077 6099 12078 6063 12078 6098 12078 6079 12079 6078 12079 6065 12079 6065 12080 6078 12080 6076 12080 6065 12081 6076 12081 6075 12081 6083 12082 6066 12082 6081 12082 6081 12083 6066 12083 6064 12083 6081 12084 6064 12084 6080 12084 6080 12085 6064 12085 6065 12085 6086 12086 6067 12086 6087 12086 6070 12087 6101 12087 6085 12087 6086 12088 6087 12088 6100 12088 6074 12089 6077 12089 6100 12089 6082 12090 6085 12090 6068 12090 6068 12091 6085 12091 6101 12091 6068 12092 6101 12092 6084 12092 6094 12093 6069 12093 6071 12093 6071 12094 6069 12094 6070 12094 6071 12095 6070 12095 6097 12095 6097 12096 6070 12096 6085 12096 6097 12097 6085 12097 6092 12097 6092 12098 6085 12098 6090 12098 6090 12099 6085 12099 6087 12099 6087 12100 6085 12100 6072 12100 6087 12101 6072 12101 6100 12101 6100 12102 6072 12102 6073 12102 6100 12103 6073 12103 6074 12103 6072 12104 6065 12104 6073 12104 6073 12105 6065 12105 6075 12105 6073 12106 6075 12106 6074 12106 6074 12107 6075 12107 6076 12107 6074 12108 6076 12108 6077 12108 6077 12109 6076 12109 6078 12109 6077 12110 6078 12110 6100 12110 6100 12111 6078 12111 6079 12111 6080 12112 6085 12112 6081 12112 6081 12113 6085 12113 6082 12113 6081 12114 6082 12114 6083 12114 6083 12115 6082 12115 6068 12115 6083 12116 6068 12116 6066 12116 6066 12117 6068 12117 6084 12117 6066 12118 6084 12118 6064 12118 6064 12119 6084 12119 6101 12119 6065 12120 6072 12120 6080 12120 6080 12121 6072 12121 6085 12121 6086 12122 6063 12122 6067 12122 6067 12123 6063 12123 6088 12123 6067 12124 6088 12124 6087 12124 6087 12125 6088 12125 6089 12125 6087 12126 6089 12126 6090 12126 6090 12127 6089 12127 6091 12127 6090 12128 6091 12128 6092 12128 6092 12129 6091 12129 6099 12129 6102 12130 6070 12130 6093 12130 6093 12131 6070 12131 6069 12131 6093 12132 6069 12132 6095 12132 6095 12133 6069 12133 6094 12133 6095 12134 6094 12134 6096 12134 6096 12135 6094 12135 6071 12135 6096 12136 6071 12136 6098 12136 6098 12137 6071 12137 6097 12137 6097 12138 6092 12138 6098 12138 6098 12139 6092 12139 6099 12139 6086 12140 6100 12140 6063 12140 6063 12141 6100 12141 6079 12141 6064 12142 6101 12142 6102 12142 6102 12143 6101 12143 6070 12143 6103 12144 6107 12144 6138 12144 6138 12145 6107 12145 6104 12145 6130 12146 6128 12146 6131 12146 6131 12147 6128 12147 6107 12147 6131 12148 6107 12148 6134 12148 6124 12149 6125 12149 6138 12149 6138 12150 6125 12150 6126 12150 6138 12151 6126 12151 6103 12151 6117 12152 6105 12152 6137 12152 6137 12153 6105 12153 6106 12153 6137 12154 6106 12154 6128 12154 6128 12155 6106 12155 6123 12155 6128 12156 6123 12156 6107 12156 6107 12157 6123 12157 6108 12157 6107 12158 6108 12158 6104 12158 6104 12159 6108 12159 6122 12159 6133 12160 6110 12160 6135 12160 6110 12161 6127 12161 6109 12161 6135 12162 6110 12162 6136 12162 6136 12163 6110 12163 6119 12163 6136 12164 6119 12164 6118 12164 6109 12165 6111 12165 6110 12165 6110 12166 6111 12166 6112 12166 6110 12167 6112 12167 6119 12167 6119 12168 6112 12168 6113 12168 6119 12169 6113 12169 6120 12169 6114 12170 6129 12170 6135 12170 6135 12171 6129 12171 6132 12171 6135 12172 6132 12172 6133 12172 6115 12173 6121 12173 6113 12173 6113 12174 6121 12174 6116 12174 6113 12175 6116 12175 6120 12175 6137 12176 6136 12176 6117 12176 6117 12177 6136 12177 6118 12177 6117 12178 6118 12178 6105 12178 6105 12179 6118 12179 6119 12179 6105 12180 6119 12180 6106 12180 6106 12181 6119 12181 6120 12181 6113 12182 6104 12182 6115 12182 6115 12183 6104 12183 6122 12183 6115 12184 6122 12184 6121 12184 6121 12185 6122 12185 6108 12185 6121 12186 6108 12186 6116 12186 6116 12187 6108 12187 6123 12187 6106 12188 6120 12188 6123 12188 6123 12189 6120 12189 6116 12189 6138 12190 6112 12190 6124 12190 6124 12191 6112 12191 6111 12191 6124 12192 6111 12192 6125 12192 6125 12193 6111 12193 6109 12193 6125 12194 6109 12194 6126 12194 6126 12195 6109 12195 6127 12195 6126 12196 6127 12196 6103 12196 6103 12197 6127 12197 6110 12197 6135 12198 6128 12198 6114 12198 6114 12199 6128 12199 6130 12199 6114 12200 6130 12200 6129 12200 6129 12201 6130 12201 6131 12201 6129 12202 6131 12202 6132 12202 6132 12203 6131 12203 6134 12203 6132 12204 6134 12204 6133 12204 6133 12205 6134 12205 6107 12205 6103 12206 6110 12206 6107 12206 6107 12207 6110 12207 6133 12207 6135 12208 6136 12208 6128 12208 6128 12209 6136 12209 6137 12209 6104 12210 6113 12210 6138 12210 6138 12211 6113 12211 6112 12211 6139 12212 6159 12212 6161 12212 6161 12213 6163 12213 6139 12213 6139 12214 6163 12214 6140 12214 6139 12215 6140 12215 6171 12215 6171 12216 6140 12216 6145 12216 6166 12217 6165 12217 6141 12217 6141 12218 6165 12218 6140 12218 6141 12219 6140 12219 6142 12219 6142 12220 6140 12220 6163 12220 6157 12221 6144 12221 6143 12221 6143 12222 6144 12222 6171 12222 6143 12223 6171 12223 6153 12223 6153 12224 6171 12224 6145 12224 6153 12225 6145 12225 6152 12225 6152 12226 6145 12226 6146 12226 6169 12227 6168 12227 6156 12227 6156 12228 6168 12228 6148 12228 6169 12229 6164 12229 6168 12229 6168 12230 6164 12230 6147 12230 6168 12231 6147 12231 6167 12231 6150 12232 6154 12232 6151 12232 6162 12233 6160 12233 6148 12233 6148 12234 6160 12234 6149 12234 6148 12235 6149 12235 6156 12235 6156 12236 6149 12236 6172 12236 6156 12237 6172 12237 6155 12237 6156 12238 6158 12238 6169 12238 6169 12239 6158 12239 6150 12239 6169 12240 6150 12240 6170 12240 6170 12241 6150 12241 6151 12241 6145 12242 6170 12242 6146 12242 6146 12243 6170 12243 6151 12243 6146 12244 6151 12244 6152 12244 6152 12245 6151 12245 6154 12245 6152 12246 6154 12246 6153 12246 6153 12247 6154 12247 6150 12247 6172 12248 6171 12248 6155 12248 6155 12249 6171 12249 6144 12249 6155 12250 6144 12250 6156 12250 6156 12251 6144 12251 6157 12251 6156 12252 6157 12252 6158 12252 6158 12253 6157 12253 6143 12253 6153 12254 6150 12254 6143 12254 6143 12255 6150 12255 6158 12255 6139 12256 6149 12256 6159 12256 6159 12257 6149 12257 6160 12257 6159 12258 6160 12258 6161 12258 6161 12259 6160 12259 6162 12259 6161 12260 6162 12260 6163 12260 6163 12261 6162 12261 6148 12261 6169 12262 6140 12262 6164 12262 6164 12263 6140 12263 6165 12263 6164 12264 6165 12264 6147 12264 6147 12265 6165 12265 6166 12265 6147 12266 6166 12266 6167 12266 6167 12267 6166 12267 6141 12267 6167 12268 6141 12268 6168 12268 6168 12269 6141 12269 6142 12269 6163 12270 6148 12270 6142 12270 6142 12271 6148 12271 6168 12271 6169 12272 6170 12272 6140 12272 6140 12273 6170 12273 6145 12273 6171 12274 6172 12274 6139 12274 6139 12275 6172 12275 6149 12275 6204 12276 6173 12276 6174 12276 6174 12277 6173 12277 6192 12277 6204 12278 6202 12278 6201 12278 6207 12279 6209 12279 6205 12279 6205 12280 6209 12280 6173 12280 6192 12281 6193 12281 6178 12281 6201 12282 6175 12282 6204 12282 6204 12283 6175 12283 6199 12283 6204 12284 6199 12284 6173 12284 6173 12285 6199 12285 6176 12285 6173 12286 6176 12286 6205 12286 6189 12287 6177 12287 6191 12287 6191 12288 6177 12288 6174 12288 6191 12289 6174 12289 6197 12289 6197 12290 6174 12290 6192 12290 6197 12291 6192 12291 6195 12291 6195 12292 6192 12292 6178 12292 6187 12293 6188 12293 6179 12293 6179 12294 6188 12294 6190 12294 6196 12295 6194 12295 6181 12295 6181 12296 6194 12296 6180 12296 6181 12297 6180 12297 6198 12297 6210 12298 6203 12298 6182 12298 6182 12299 6203 12299 6179 12299 6182 12300 6179 12300 6180 12300 6180 12301 6179 12301 6190 12301 6180 12302 6190 12302 6198 12302 6183 12303 6206 12303 6208 12303 6208 12304 6206 12304 6182 12304 6208 12305 6182 12305 6184 12305 6184 12306 6182 12306 6180 12306 6210 12307 6185 12307 6203 12307 6203 12308 6185 12308 6200 12308 6203 12309 6200 12309 6186 12309 6179 12310 6174 12310 6187 12310 6187 12311 6174 12311 6177 12311 6187 12312 6177 12312 6188 12312 6188 12313 6177 12313 6189 12313 6188 12314 6189 12314 6190 12314 6190 12315 6189 12315 6191 12315 6192 12316 6180 12316 6193 12316 6193 12317 6180 12317 6194 12317 6193 12318 6194 12318 6178 12318 6178 12319 6194 12319 6196 12319 6178 12320 6196 12320 6195 12320 6195 12321 6196 12321 6181 12321 6195 12322 6181 12322 6197 12322 6197 12323 6181 12323 6198 12323 6198 12324 6190 12324 6197 12324 6197 12325 6190 12325 6191 12325 6210 12326 6199 12326 6185 12326 6185 12327 6199 12327 6175 12327 6185 12328 6175 12328 6200 12328 6200 12329 6175 12329 6201 12329 6200 12330 6201 12330 6186 12330 6186 12331 6201 12331 6202 12331 6186 12332 6202 12332 6203 12332 6203 12333 6202 12333 6204 12333 6176 12334 6182 12334 6205 12334 6205 12335 6182 12335 6206 12335 6205 12336 6206 12336 6207 12336 6207 12337 6206 12337 6183 12337 6207 12338 6183 12338 6209 12338 6209 12339 6183 12339 6208 12339 6209 12340 6208 12340 6173 12340 6173 12341 6208 12341 6184 12341 6199 12342 6210 12342 6176 12342 6176 12343 6210 12343 6182 12343 6184 12344 6180 12344 6173 12344 6173 12345 6180 12345 6192 12345 6174 12346 6179 12346 6204 12346 6204 12347 6179 12347 6203 12347 6233 12348 6215 12348 6246 12348 6246 12349 6215 12349 6221 12349 6233 12350 6211 12350 6212 12350 6213 12351 6214 12351 6217 12351 6217 12352 6214 12352 6215 12352 6212 12353 6234 12353 6233 12353 6233 12354 6234 12354 6236 12354 6233 12355 6236 12355 6215 12355 6215 12356 6236 12356 6216 12356 6215 12357 6216 12357 6217 12357 6221 12358 6218 12358 6220 12358 6245 12359 6219 12359 6242 12359 6242 12360 6219 12360 6246 12360 6220 12361 6240 12361 6221 12361 6221 12362 6240 12362 6237 12362 6221 12363 6237 12363 6246 12363 6246 12364 6237 12364 6222 12364 6246 12365 6222 12365 6242 12365 6231 12366 6232 12366 6223 12366 6244 12367 6223 12367 6229 12367 6224 12368 6231 12368 6230 12368 6230 12369 6231 12369 6223 12369 6230 12370 6223 12370 6225 12370 6225 12371 6223 12371 6244 12371 6244 12372 6243 12372 6225 12372 6225 12373 6243 12373 6248 12373 6225 12374 6248 12374 6226 12374 6229 12375 6227 12375 6235 12375 6235 12376 6228 12376 6229 12376 6229 12377 6228 12377 6250 12377 6229 12378 6250 12378 6244 12378 6244 12379 6250 12379 6249 12379 6244 12380 6249 12380 6247 12380 6226 12381 6238 12381 6225 12381 6225 12382 6238 12382 6239 12382 6225 12383 6239 12383 6241 12383 6230 12384 6215 12384 6224 12384 6224 12385 6215 12385 6214 12385 6224 12386 6214 12386 6231 12386 6231 12387 6214 12387 6213 12387 6231 12388 6213 12388 6232 12388 6232 12389 6213 12389 6217 12389 6232 12390 6217 12390 6223 12390 6223 12391 6217 12391 6216 12391 6233 12392 6250 12392 6211 12392 6211 12393 6250 12393 6228 12393 6211 12394 6228 12394 6212 12394 6212 12395 6228 12395 6235 12395 6212 12396 6235 12396 6234 12396 6234 12397 6235 12397 6227 12397 6234 12398 6227 12398 6236 12398 6236 12399 6227 12399 6229 12399 6229 12400 6223 12400 6236 12400 6236 12401 6223 12401 6216 12401 6226 12402 6237 12402 6238 12402 6238 12403 6237 12403 6240 12403 6238 12404 6240 12404 6239 12404 6239 12405 6240 12405 6220 12405 6239 12406 6220 12406 6241 12406 6241 12407 6220 12407 6218 12407 6241 12408 6218 12408 6225 12408 6225 12409 6218 12409 6221 12409 6222 12410 6248 12410 6242 12410 6242 12411 6248 12411 6243 12411 6242 12412 6243 12412 6245 12412 6245 12413 6243 12413 6244 12413 6245 12414 6244 12414 6219 12414 6219 12415 6244 12415 6247 12415 6219 12416 6247 12416 6246 12416 6246 12417 6247 12417 6249 12417 6237 12418 6226 12418 6222 12418 6222 12419 6226 12419 6248 12419 6249 12420 6250 12420 6246 12420 6246 12421 6250 12421 6233 12421 6215 12422 6230 12422 6221 12422 6221 12423 6230 12423 6225 12423 6272 12424 6251 12424 6270 12424 6270 12425 6251 12425 6274 12425 6268 12426 6252 12426 6253 12426 6253 12427 6252 12427 6256 12427 6253 12428 6256 12428 6269 12428 6279 12429 6276 12429 6254 12429 6254 12430 6276 12430 6275 12430 6254 12431 6275 12431 6286 12431 6286 12432 6275 12432 6256 12432 6255 12433 6283 12433 6281 12433 6281 12434 6283 12434 6285 12434 6281 12435 6285 12435 6275 12435 6275 12436 6285 12436 6270 12436 6275 12437 6270 12437 6256 12437 6256 12438 6270 12438 6274 12438 6256 12439 6274 12439 6269 12439 6278 12440 6280 12440 6257 12440 6262 12441 6282 12441 6265 12441 6265 12442 6282 12442 6258 12442 6265 12443 6258 12443 6259 12443 6278 12444 6257 12444 6277 12444 6260 12445 6265 12445 6257 12445 6257 12446 6265 12446 6259 12446 6257 12447 6259 12447 6277 12447 6273 12448 6261 12448 6262 12448 6262 12449 6261 12449 6271 12449 6262 12450 6271 12450 6282 12450 6282 12451 6271 12451 6263 12451 6282 12452 6263 12452 6284 12452 6260 12453 6264 12453 6265 12453 6265 12454 6264 12454 6266 12454 6265 12455 6266 12455 6267 12455 6260 12456 6256 12456 6264 12456 6264 12457 6256 12457 6252 12457 6264 12458 6252 12458 6266 12458 6266 12459 6252 12459 6268 12459 6266 12460 6268 12460 6267 12460 6267 12461 6268 12461 6253 12461 6267 12462 6253 12462 6265 12462 6265 12463 6253 12463 6269 12463 6270 12464 6271 12464 6272 12464 6272 12465 6271 12465 6261 12465 6272 12466 6261 12466 6251 12466 6251 12467 6261 12467 6273 12467 6251 12468 6273 12468 6274 12468 6274 12469 6273 12469 6262 12469 6262 12470 6265 12470 6274 12470 6274 12471 6265 12471 6269 12471 6259 12472 6275 12472 6277 12472 6277 12473 6275 12473 6276 12473 6277 12474 6276 12474 6278 12474 6278 12475 6276 12475 6279 12475 6278 12476 6279 12476 6280 12476 6280 12477 6279 12477 6254 12477 6280 12478 6254 12478 6257 12478 6257 12479 6254 12479 6286 12479 6281 12480 6258 12480 6255 12480 6255 12481 6258 12481 6282 12481 6255 12482 6282 12482 6283 12482 6283 12483 6282 12483 6284 12483 6283 12484 6284 12484 6285 12484 6285 12485 6284 12485 6263 12485 6275 12486 6259 12486 6281 12486 6281 12487 6259 12487 6258 12487 6263 12488 6271 12488 6285 12488 6285 12489 6271 12489 6270 12489 6256 12490 6260 12490 6286 12490 6286 12491 6260 12491 6257 12491 6308 12492 6305 12492 6287 12492 6287 12493 6305 12493 6324 12493 6287 12494 6324 12494 6310 12494 6310 12495 6324 12495 6290 12495 6288 12496 6289 12496 6311 12496 6311 12497 6289 12497 6290 12497 6311 12498 6290 12498 6326 12498 6326 12499 6290 12499 6324 12499 6326 12500 6324 12500 6294 12500 6294 12501 6324 12501 6325 12501 6325 12502 6291 12502 6317 12502 6292 12503 6320 12503 6293 12503 6293 12504 6320 12504 6294 12504 6317 12505 6316 12505 6325 12505 6325 12506 6316 12506 6315 12506 6325 12507 6315 12507 6294 12507 6294 12508 6315 12508 6323 12508 6294 12509 6323 12509 6293 12509 6321 12510 6319 12510 6299 12510 6318 12511 6296 12511 6295 12511 6295 12512 6296 12512 6297 12512 6295 12513 6297 12513 6298 12513 6298 12514 6297 12514 6299 12514 6321 12515 6299 12515 6322 12515 6304 12516 6306 12516 6307 12516 6300 12517 6312 12517 6301 12517 6301 12518 6312 12518 6303 12518 6301 12519 6303 12519 6313 12519 6313 12520 6303 12520 6314 12520 6322 12521 6299 12521 6302 12521 6302 12522 6299 12522 6297 12522 6302 12523 6297 12523 6303 12523 6303 12524 6297 12524 6304 12524 6303 12525 6304 12525 6314 12525 6314 12526 6304 12526 6307 12526 6314 12527 6307 12527 6309 12527 6304 12528 6324 12528 6306 12528 6306 12529 6324 12529 6305 12529 6306 12530 6305 12530 6307 12530 6307 12531 6305 12531 6308 12531 6307 12532 6308 12532 6309 12532 6309 12533 6308 12533 6287 12533 6309 12534 6287 12534 6314 12534 6314 12535 6287 12535 6310 12535 6326 12536 6303 12536 6311 12536 6311 12537 6303 12537 6312 12537 6311 12538 6312 12538 6288 12538 6288 12539 6312 12539 6300 12539 6288 12540 6300 12540 6289 12540 6289 12541 6300 12541 6301 12541 6289 12542 6301 12542 6290 12542 6290 12543 6301 12543 6313 12543 6313 12544 6314 12544 6290 12544 6290 12545 6314 12545 6310 12545 6298 12546 6315 12546 6295 12546 6295 12547 6315 12547 6316 12547 6295 12548 6316 12548 6318 12548 6318 12549 6316 12549 6317 12549 6318 12550 6317 12550 6296 12550 6296 12551 6317 12551 6291 12551 6296 12552 6291 12552 6297 12552 6297 12553 6291 12553 6325 12553 6323 12554 6299 12554 6293 12554 6293 12555 6299 12555 6319 12555 6293 12556 6319 12556 6292 12556 6292 12557 6319 12557 6321 12557 6292 12558 6321 12558 6320 12558 6320 12559 6321 12559 6322 12559 6320 12560 6322 12560 6294 12560 6294 12561 6322 12561 6302 12561 6315 12562 6298 12562 6323 12562 6323 12563 6298 12563 6299 12563 6324 12564 6304 12564 6325 12564 6325 12565 6304 12565 6297 12565 6302 12566 6303 12566 6294 12566 6294 12567 6303 12567 6326 12567 6341 12568 6347 12568 6327 12568 6328 12569 6329 12569 6332 12569 6332 12570 6329 12570 6330 12570 6332 12571 6330 12571 6331 12571 6344 12572 6342 12572 6345 12572 6345 12573 6342 12573 6341 12573 6345 12574 6341 12574 6331 12574 6331 12575 6341 12575 6327 12575 6331 12576 6327 12576 6332 12576 6333 12577 6348 12577 6337 12577 6337 12578 6348 12578 6334 12578 6339 12579 6338 12579 6335 12579 6335 12580 6338 12580 6337 12580 6335 12581 6337 12581 6346 12581 6346 12582 6337 12582 6336 12582 6334 12583 6340 12583 6337 12583 6337 12584 6340 12584 6343 12584 6337 12585 6343 12585 6336 12585 6332 12586 6337 12586 6328 12586 6328 12587 6337 12587 6338 12587 6328 12588 6338 12588 6329 12588 6329 12589 6338 12589 6339 12589 6329 12590 6339 12590 6330 12590 6330 12591 6339 12591 6335 12591 6334 12592 6341 12592 6340 12592 6340 12593 6341 12593 6342 12593 6340 12594 6342 12594 6343 12594 6343 12595 6342 12595 6344 12595 6343 12596 6344 12596 6336 12596 6336 12597 6344 12597 6345 12597 6336 12598 6345 12598 6346 12598 6346 12599 6345 12599 6331 12599 6330 12600 6335 12600 6331 12600 6331 12601 6335 12601 6346 12601 6347 12602 6348 12602 6327 12602 6327 12603 6348 12603 6333 12603 6341 12604 6334 12604 6347 12604 6347 12605 6334 12605 6348 12605 6327 12606 6333 12606 6332 12606 6332 12607 6333 12607 6337 12607 6371 12608 6349 12608 6381 12608 6381 12609 6349 12609 6380 12609 6381 12610 6380 12610 6350 12610 6350 12611 6380 12611 6354 12611 6377 12612 6351 12612 6378 12612 6378 12613 6351 12613 6375 12613 6378 12614 6375 12614 6354 12614 6364 12615 6365 12615 6382 12615 6382 12616 6365 12616 6366 12616 6353 12617 6368 12617 6352 12617 6352 12618 6350 12618 6353 12618 6353 12619 6350 12619 6354 12619 6353 12620 6354 12620 6366 12620 6366 12621 6354 12621 6375 12621 6366 12622 6375 12622 6382 12622 6356 12623 6367 12623 6362 12623 6372 12624 6355 12624 6373 12624 6373 12625 6355 12625 6356 12625 6373 12626 6356 12626 6379 12626 6379 12627 6356 12627 6361 12627 6357 12628 6369 12628 6367 12628 6367 12629 6369 12629 6370 12629 6367 12630 6370 12630 6358 12630 6358 12631 6359 12631 6367 12631 6367 12632 6359 12632 6363 12632 6367 12633 6363 12633 6362 12633 6360 12634 6361 12634 6376 12634 6376 12635 6361 12635 6356 12635 6376 12636 6356 12636 6374 12636 6374 12637 6356 12637 6362 12637 6382 12638 6362 12638 6364 12638 6364 12639 6362 12639 6363 12639 6364 12640 6363 12640 6365 12640 6365 12641 6363 12641 6359 12641 6365 12642 6359 12642 6366 12642 6366 12643 6359 12643 6358 12643 6367 12644 6350 12644 6357 12644 6357 12645 6350 12645 6352 12645 6357 12646 6352 12646 6369 12646 6369 12647 6352 12647 6368 12647 6369 12648 6368 12648 6370 12648 6370 12649 6368 12649 6353 12649 6366 12650 6358 12650 6353 12650 6353 12651 6358 12651 6370 12651 6381 12652 6356 12652 6371 12652 6371 12653 6356 12653 6355 12653 6371 12654 6355 12654 6349 12654 6349 12655 6355 12655 6372 12655 6349 12656 6372 12656 6380 12656 6380 12657 6372 12657 6373 12657 6374 12658 6375 12658 6376 12658 6376 12659 6375 12659 6351 12659 6376 12660 6351 12660 6360 12660 6360 12661 6351 12661 6377 12661 6360 12662 6377 12662 6361 12662 6361 12663 6377 12663 6378 12663 6361 12664 6378 12664 6379 12664 6379 12665 6378 12665 6354 12665 6380 12666 6373 12666 6354 12666 6354 12667 6373 12667 6379 12667 6350 12668 6367 12668 6381 12668 6381 12669 6367 12669 6356 12669 6375 12670 6374 12670 6382 12670 6382 12671 6374 12671 6362 12671 6404 12672 6395 12672 6383 12672 6383 12673 6395 12673 6387 12673 6396 12674 6384 12674 6387 12674 6387 12675 6384 12675 6385 12675 6387 12676 6385 12676 6388 12676 6386 12677 6383 12677 6400 12677 6400 12678 6383 12678 6387 12678 6400 12679 6387 12679 6401 12679 6401 12680 6387 12680 6388 12680 6403 12681 6389 12681 6390 12681 6390 12682 6389 12682 6398 12682 6397 12683 6391 12683 6402 12683 6402 12684 6391 12684 6390 12684 6402 12685 6390 12685 6392 12685 6392 12686 6390 12686 6393 12686 6398 12687 6399 12687 6390 12687 6390 12688 6399 12688 6394 12688 6390 12689 6394 12689 6393 12689 6404 12690 6389 12690 6395 12690 6395 12691 6389 12691 6403 12691 6387 12692 6390 12692 6396 12692 6396 12693 6390 12693 6391 12693 6396 12694 6391 12694 6384 12694 6384 12695 6391 12695 6397 12695 6384 12696 6397 12696 6385 12696 6385 12697 6397 12697 6402 12697 6398 12698 6383 12698 6399 12698 6399 12699 6383 12699 6386 12699 6399 12700 6386 12700 6394 12700 6394 12701 6386 12701 6400 12701 6394 12702 6400 12702 6393 12702 6393 12703 6400 12703 6401 12703 6393 12704 6401 12704 6392 12704 6392 12705 6401 12705 6388 12705 6385 12706 6402 12706 6388 12706 6388 12707 6402 12707 6392 12707 6395 12708 6403 12708 6387 12708 6387 12709 6403 12709 6390 12709 6383 12710 6398 12710 6404 12710 6404 12711 6398 12711 6389 12711 6405 12712 6406 12712 6426 12712 6426 12713 6406 12713 6408 12713 6407 12714 6420 12714 6408 12714 6408 12715 6420 12715 6421 12715 6408 12716 6421 12716 6425 12716 6424 12717 6426 12717 6409 12717 6409 12718 6426 12718 6408 12718 6409 12719 6408 12719 6410 12719 6410 12720 6408 12720 6425 12720 6422 12721 6411 12721 6412 12721 6413 12722 6414 12722 6415 12722 6415 12723 6414 12723 6416 12723 6415 12724 6416 12724 6423 12724 6412 12725 6419 12725 6422 12725 6422 12726 6419 12726 6417 12726 6422 12727 6417 12727 6416 12727 6416 12728 6417 12728 6418 12728 6416 12729 6418 12729 6423 12729 6405 12730 6418 12730 6406 12730 6406 12731 6418 12731 6417 12731 6408 12732 6419 12732 6407 12732 6407 12733 6419 12733 6412 12733 6407 12734 6412 12734 6420 12734 6420 12735 6412 12735 6411 12735 6420 12736 6411 12736 6421 12736 6421 12737 6411 12737 6422 12737 6423 12738 6426 12738 6415 12738 6415 12739 6426 12739 6424 12739 6415 12740 6424 12740 6413 12740 6413 12741 6424 12741 6409 12741 6413 12742 6409 12742 6414 12742 6414 12743 6409 12743 6410 12743 6414 12744 6410 12744 6416 12744 6416 12745 6410 12745 6425 12745 6421 12746 6422 12746 6425 12746 6425 12747 6422 12747 6416 12747 6406 12748 6417 12748 6408 12748 6408 12749 6417 12749 6419 12749 6426 12750 6423 12750 6405 12750 6405 12751 6423 12751 6418 12751 6430 12752 6427 12752 6431 12752 6438 12753 6440 12753 6447 12753 6447 12754 6440 12754 6428 12754 6447 12755 6428 12755 6446 12755 6429 12756 6444 12756 6445 12756 6445 12757 6444 12757 6430 12757 6445 12758 6430 12758 6446 12758 6446 12759 6430 12759 6431 12759 6446 12760 6431 12760 6447 12760 6442 12761 6441 12761 6439 12761 6432 12762 6433 12762 6443 12762 6443 12763 6433 12763 6435 12763 6443 12764 6435 12764 6448 12764 6439 12765 6434 12765 6442 12765 6442 12766 6434 12766 6437 12766 6442 12767 6437 12767 6435 12767 6435 12768 6437 12768 6436 12768 6435 12769 6436 12769 6448 12769 6427 12770 6436 12770 6431 12770 6431 12771 6436 12771 6437 12771 6447 12772 6434 12772 6438 12772 6438 12773 6434 12773 6439 12773 6438 12774 6439 12774 6440 12774 6440 12775 6439 12775 6441 12775 6440 12776 6441 12776 6428 12776 6428 12777 6441 12777 6442 12777 6448 12778 6430 12778 6443 12778 6443 12779 6430 12779 6444 12779 6443 12780 6444 12780 6432 12780 6432 12781 6444 12781 6429 12781 6432 12782 6429 12782 6433 12782 6433 12783 6429 12783 6445 12783 6433 12784 6445 12784 6435 12784 6435 12785 6445 12785 6446 12785 6428 12786 6442 12786 6446 12786 6446 12787 6442 12787 6435 12787 6431 12788 6437 12788 6447 12788 6447 12789 6437 12789 6434 12789 6430 12790 6448 12790 6427 12790 6427 12791 6448 12791 6436 12791 6467 12792 6466 12792 6449 12792 6462 12793 6450 12793 6461 12793 6461 12794 6450 12794 6452 12794 6461 12795 6452 12795 6451 12795 6451 12796 6452 12796 6467 12796 6470 12797 6451 12797 6453 12797 6453 12798 6451 12798 6467 12798 6453 12799 6467 12799 6454 12799 6454 12800 6467 12800 6449 12800 6455 12801 6456 12801 6469 12801 6456 12802 6457 12802 6469 12802 6469 12803 6457 12803 6458 12803 6469 12804 6458 12804 6465 12804 6459 12805 6464 12805 6468 12805 6468 12806 6464 12806 6463 12806 6468 12807 6463 12807 6469 12807 6469 12808 6463 12808 6460 12808 6469 12809 6460 12809 6455 12809 6461 12810 6463 12810 6462 12810 6462 12811 6463 12811 6464 12811 6462 12812 6464 12812 6450 12812 6450 12813 6464 12813 6459 12813 6450 12814 6459 12814 6452 12814 6452 12815 6459 12815 6468 12815 6456 12816 6453 12816 6457 12816 6457 12817 6453 12817 6454 12817 6457 12818 6454 12818 6458 12818 6458 12819 6454 12819 6449 12819 6458 12820 6449 12820 6465 12820 6465 12821 6449 12821 6466 12821 6465 12822 6466 12822 6469 12822 6469 12823 6466 12823 6467 12823 6452 12824 6468 12824 6467 12824 6467 12825 6468 12825 6469 12825 6470 12826 6455 12826 6451 12826 6451 12827 6455 12827 6460 12827 6453 12828 6456 12828 6470 12828 6470 12829 6456 12829 6455 12829 6451 12830 6460 12830 6461 12830 6461 12831 6460 12831 6463 12831 6477 12832 6492 12832 6475 12832 6476 12833 6488 12833 6487 12833 6471 12834 6472 12834 6474 12834 6474 12835 6472 12835 6473 12835 6474 12836 6473 12836 6475 12836 6475 12837 6473 12837 6476 12837 6475 12838 6476 12838 6477 12838 6477 12839 6476 12839 6487 12839 6477 12840 6487 12840 6486 12840 6490 12841 6478 12841 6479 12841 6479 12842 6491 12842 6490 12842 6490 12843 6491 12843 6480 12843 6490 12844 6480 12844 6481 12844 6482 12845 6483 12845 6489 12845 6489 12846 6483 12846 6490 12846 6489 12847 6490 12847 6484 12847 6484 12848 6490 12848 6481 12848 6484 12849 6481 12849 6485 12849 6492 12850 6479 12850 6475 12850 6475 12851 6479 12851 6478 12851 6474 12852 6490 12852 6471 12852 6471 12853 6490 12853 6483 12853 6471 12854 6483 12854 6472 12854 6472 12855 6483 12855 6482 12855 6472 12856 6482 12856 6473 12856 6473 12857 6482 12857 6489 12857 6491 12858 6477 12858 6480 12858 6480 12859 6477 12859 6486 12859 6480 12860 6486 12860 6481 12860 6481 12861 6486 12861 6487 12861 6481 12862 6487 12862 6485 12862 6485 12863 6487 12863 6488 12863 6485 12864 6488 12864 6484 12864 6484 12865 6488 12865 6476 12865 6473 12866 6489 12866 6476 12866 6476 12867 6489 12867 6484 12867 6475 12868 6478 12868 6474 12868 6474 12869 6478 12869 6490 12869 6477 12870 6491 12870 6492 12870 6492 12871 6491 12871 6479 12871 6515 12872 6516 12872 6501 12872 6496 12873 6510 12873 6497 12873 6493 12874 6504 12874 6514 12874 6514 12875 6504 12875 6494 12875 6514 12876 6494 12876 6495 12876 6495 12877 6494 12877 6496 12877 6501 12878 6495 12878 6515 12878 6515 12879 6495 12879 6496 12879 6515 12880 6496 12880 6507 12880 6507 12881 6496 12881 6497 12881 6511 12882 6498 12882 6505 12882 6508 12883 6509 12883 6506 12883 6506 12884 6509 12884 6512 12884 6506 12885 6512 12885 6499 12885 6500 12886 6499 12886 6502 12886 6502 12887 6499 12887 6512 12887 6502 12888 6512 12888 6513 12888 6513 12889 6512 12889 6511 12889 6513 12890 6511 12890 6503 12890 6503 12891 6511 12891 6505 12891 6500 12892 6502 12892 6516 12892 6516 12893 6502 12893 6501 12893 6502 12894 6513 12894 6501 12894 6501 12895 6513 12895 6495 12895 6514 12896 6503 12896 6493 12896 6493 12897 6503 12897 6505 12897 6493 12898 6505 12898 6504 12898 6504 12899 6505 12899 6498 12899 6504 12900 6498 12900 6494 12900 6494 12901 6498 12901 6511 12901 6499 12902 6515 12902 6506 12902 6506 12903 6515 12903 6507 12903 6506 12904 6507 12904 6508 12904 6508 12905 6507 12905 6497 12905 6508 12906 6497 12906 6509 12906 6509 12907 6497 12907 6510 12907 6509 12908 6510 12908 6512 12908 6512 12909 6510 12909 6496 12909 6494 12910 6511 12910 6496 12910 6496 12911 6511 12911 6512 12911 6495 12912 6513 12912 6514 12912 6514 12913 6513 12913 6503 12913 6515 12914 6499 12914 6516 12914 6516 12915 6499 12915 6500 12915 6517 12916 6518 12916 6533 12916 6519 12917 6529 12917 6520 12917 6520 12918 6529 12918 6536 12918 6520 12919 6536 12919 6528 12919 6528 12920 6536 12920 6517 12920 6537 12921 6528 12921 6521 12921 6521 12922 6528 12922 6517 12922 6521 12923 6517 12923 6531 12923 6531 12924 6517 12924 6533 12924 6525 12925 6527 12925 6526 12925 6530 12926 6522 12926 6523 12926 6523 12927 6522 12927 6525 12927 6523 12928 6525 12928 6535 12928 6535 12929 6525 12929 6534 12929 6532 12930 6534 12930 6524 12930 6524 12931 6534 12931 6525 12931 6524 12932 6525 12932 6538 12932 6538 12933 6525 12933 6526 12933 6526 12934 6527 12934 6537 12934 6537 12935 6527 12935 6528 12935 6520 12936 6525 12936 6519 12936 6519 12937 6525 12937 6522 12937 6519 12938 6522 12938 6529 12938 6529 12939 6522 12939 6530 12939 6529 12940 6530 12940 6536 12940 6536 12941 6530 12941 6523 12941 6538 12942 6521 12942 6524 12942 6524 12943 6521 12943 6531 12943 6524 12944 6531 12944 6532 12944 6532 12945 6531 12945 6533 12945 6532 12946 6533 12946 6534 12946 6534 12947 6533 12947 6518 12947 6534 12948 6518 12948 6535 12948 6535 12949 6518 12949 6517 12949 6536 12950 6523 12950 6517 12950 6517 12951 6523 12951 6535 12951 6528 12952 6527 12952 6520 12952 6520 12953 6527 12953 6525 12953 6521 12954 6538 12954 6537 12954 6537 12955 6538 12955 6526 12955 6539 12956 6540 12956 6543 12956 6543 12957 6540 12957 6549 12957 6550 12958 6541 12958 6549 12958 6549 12959 6541 12959 6553 12959 6549 12960 6553 12960 6544 12960 6557 12961 6543 12961 6542 12961 6542 12962 6543 12962 6549 12962 6542 12963 6549 12963 6560 12963 6560 12964 6549 12964 6544 12964 6545 12965 6548 12965 6547 12965 6547 12966 6555 12966 6545 12966 6545 12967 6555 12967 6556 12967 6545 12968 6556 12968 6546 12968 6552 12969 6551 12969 6554 12969 6554 12970 6551 12970 6545 12970 6554 12971 6545 12971 6559 12971 6559 12972 6545 12972 6546 12972 6559 12973 6546 12973 6558 12973 6547 12974 6548 12974 6539 12974 6539 12975 6548 12975 6540 12975 6549 12976 6545 12976 6550 12976 6550 12977 6545 12977 6551 12977 6550 12978 6551 12978 6541 12978 6541 12979 6551 12979 6552 12979 6541 12980 6552 12980 6553 12980 6553 12981 6552 12981 6554 12981 6555 12982 6543 12982 6556 12982 6556 12983 6543 12983 6557 12983 6556 12984 6557 12984 6546 12984 6546 12985 6557 12985 6542 12985 6546 12986 6542 12986 6558 12986 6558 12987 6542 12987 6560 12987 6558 12988 6560 12988 6559 12988 6559 12989 6560 12989 6544 12989 6553 12990 6554 12990 6544 12990 6544 12991 6554 12991 6559 12991 6540 12992 6548 12992 6549 12992 6549 12993 6548 12993 6545 12993 6543 12994 6555 12994 6539 12994 6539 12995 6555 12995 6547 12995 6561 12996 6575 12996 6576 12996 6562 12997 6563 12997 6564 12997 6564 12998 6563 12998 6581 12998 6564 12999 6581 12999 6566 12999 6580 13000 6579 13000 6565 13000 6565 13001 6579 13001 6561 13001 6565 13002 6561 13002 6566 13002 6566 13003 6561 13003 6576 13003 6566 13004 6576 13004 6564 13004 6567 13005 6568 13005 6578 13005 6578 13006 6568 13006 6569 13006 6578 13007 6569 13007 6570 13007 6570 13008 6569 13008 6573 13008 6577 13009 6571 13009 6572 13009 6572 13010 6571 13010 6582 13010 6572 13011 6582 13011 6569 13011 6569 13012 6582 13012 6574 13012 6569 13013 6574 13013 6573 13013 6573 13014 6574 13014 6575 13014 6575 13015 6574 13015 6576 13015 6564 13016 6582 13016 6562 13016 6562 13017 6582 13017 6571 13017 6562 13018 6571 13018 6563 13018 6563 13019 6571 13019 6577 13019 6563 13020 6577 13020 6581 13020 6581 13021 6577 13021 6572 13021 6570 13022 6561 13022 6578 13022 6578 13023 6561 13023 6579 13023 6578 13024 6579 13024 6567 13024 6567 13025 6579 13025 6580 13025 6567 13026 6580 13026 6568 13026 6568 13027 6580 13027 6565 13027 6568 13028 6565 13028 6569 13028 6569 13029 6565 13029 6566 13029 6581 13030 6572 13030 6566 13030 6566 13031 6572 13031 6569 13031 6576 13032 6574 13032 6564 13032 6564 13033 6574 13033 6582 13033 6561 13034 6570 13034 6575 13034 6575 13035 6570 13035 6573 13035 6586 13036 6604 13036 6602 13036 6585 13037 6602 13037 6584 13037 6585 13038 6599 13038 6583 13038 6593 13039 6594 13039 6584 13039 6584 13040 6594 13040 6600 13040 6584 13041 6600 13041 6585 13041 6602 13042 6585 13042 6586 13042 6586 13043 6585 13043 6583 13043 6586 13044 6583 13044 6596 13044 6597 13045 6598 13045 6588 13045 6588 13046 6598 13046 6587 13046 6588 13047 6587 13047 6589 13047 6589 13048 6587 13048 6591 13048 6595 13049 6590 13049 6601 13049 6601 13050 6590 13050 6603 13050 6601 13051 6603 13051 6587 13051 6587 13052 6603 13052 6592 13052 6587 13053 6592 13053 6591 13053 6591 13054 6592 13054 6604 13054 6604 13055 6592 13055 6602 13055 6584 13056 6603 13056 6593 13056 6593 13057 6603 13057 6590 13057 6593 13058 6590 13058 6594 13058 6594 13059 6590 13059 6595 13059 6594 13060 6595 13060 6600 13060 6600 13061 6595 13061 6601 13061 6589 13062 6586 13062 6588 13062 6588 13063 6586 13063 6596 13063 6588 13064 6596 13064 6597 13064 6597 13065 6596 13065 6583 13065 6597 13066 6583 13066 6598 13066 6598 13067 6583 13067 6599 13067 6598 13068 6599 13068 6587 13068 6587 13069 6599 13069 6585 13069 6600 13070 6601 13070 6585 13070 6585 13071 6601 13071 6587 13071 6602 13072 6592 13072 6584 13072 6584 13073 6592 13073 6603 13073 6586 13074 6589 13074 6604 13074 6604 13075 6589 13075 6591 13075 6622 13076 6605 13076 6615 13076 6617 13077 6606 13077 6616 13077 6616 13078 6606 13078 6619 13078 6616 13079 6619 13079 6609 13079 6607 13080 6624 13080 6608 13080 6608 13081 6624 13081 6622 13081 6608 13082 6622 13082 6609 13082 6609 13083 6622 13083 6615 13083 6609 13084 6615 13084 6616 13084 6621 13085 6620 13085 6618 13085 6625 13086 6626 13086 6623 13086 6623 13087 6626 13087 6610 13087 6623 13088 6610 13088 6614 13088 6618 13089 6611 13089 6621 13089 6621 13090 6611 13090 6612 13090 6621 13091 6612 13091 6610 13091 6610 13092 6612 13092 6613 13092 6610 13093 6613 13093 6614 13093 6613 13094 6612 13094 6605 13094 6605 13095 6612 13095 6615 13095 6616 13096 6611 13096 6617 13096 6617 13097 6611 13097 6618 13097 6617 13098 6618 13098 6606 13098 6606 13099 6618 13099 6620 13099 6606 13100 6620 13100 6619 13100 6619 13101 6620 13101 6621 13101 6614 13102 6622 13102 6623 13102 6623 13103 6622 13103 6624 13103 6623 13104 6624 13104 6625 13104 6625 13105 6624 13105 6607 13105 6625 13106 6607 13106 6626 13106 6626 13107 6607 13107 6608 13107 6626 13108 6608 13108 6610 13108 6610 13109 6608 13109 6609 13109 6619 13110 6621 13110 6609 13110 6609 13111 6621 13111 6610 13111 6615 13112 6612 13112 6616 13112 6616 13113 6612 13113 6611 13113 6622 13114 6614 13114 6605 13114 6605 13115 6614 13115 6613 13115 6630 13116 6627 13116 6628 13116 6629 13117 6644 13117 6645 13117 6645 13118 6644 13118 6630 13118 6645 13119 6630 13119 6631 13119 6631 13120 6630 13120 6628 13120 6631 13121 6628 13121 6641 13121 6641 13122 6628 13122 6637 13122 6641 13123 6637 13123 6640 13123 6640 13124 6637 13124 6638 13124 6648 13125 6636 13125 6632 13125 6639 13126 6633 13126 6646 13126 6646 13127 6633 13127 6648 13127 6646 13128 6648 13128 6647 13128 6647 13129 6648 13129 6634 13129 6635 13130 6634 13130 6643 13130 6643 13131 6634 13131 6648 13131 6643 13132 6648 13132 6642 13132 6642 13133 6648 13133 6632 13133 6632 13134 6636 13134 6627 13134 6627 13135 6636 13135 6628 13135 6637 13136 6648 13136 6638 13136 6638 13137 6648 13137 6633 13137 6638 13138 6633 13138 6640 13138 6640 13139 6633 13139 6639 13139 6640 13140 6639 13140 6641 13140 6641 13141 6639 13141 6646 13141 6642 13142 6630 13142 6643 13142 6643 13143 6630 13143 6644 13143 6643 13144 6644 13144 6635 13144 6635 13145 6644 13145 6629 13145 6635 13146 6629 13146 6634 13146 6634 13147 6629 13147 6645 13147 6634 13148 6645 13148 6647 13148 6647 13149 6645 13149 6631 13149 6641 13150 6646 13150 6631 13150 6631 13151 6646 13151 6647 13151 6628 13152 6636 13152 6637 13152 6637 13153 6636 13153 6648 13153 6630 13154 6642 13154 6627 13154 6627 13155 6642 13155 6632 13155 6670 13156 6649 13156 6650 13156 6650 13157 6649 13157 6654 13157 6661 13158 6651 13158 6654 13158 6654 13159 6651 13159 6652 13159 6654 13160 6652 13160 6668 13160 6666 13161 6650 13161 6667 13161 6667 13162 6650 13162 6654 13162 6667 13163 6654 13163 6653 13163 6653 13164 6654 13164 6668 13164 6660 13165 6664 13165 6655 13165 6664 13166 6665 13166 6655 13166 6655 13167 6665 13167 6656 13167 6655 13168 6656 13168 6657 13168 6658 13169 6659 13169 6663 13169 6663 13170 6659 13170 6662 13170 6663 13171 6662 13171 6655 13171 6655 13172 6662 13172 6669 13172 6655 13173 6669 13173 6660 13173 6670 13174 6660 13174 6649 13174 6649 13175 6660 13175 6669 13175 6654 13176 6662 13176 6661 13176 6661 13177 6662 13177 6659 13177 6661 13178 6659 13178 6651 13178 6651 13179 6659 13179 6658 13179 6651 13180 6658 13180 6652 13180 6652 13181 6658 13181 6663 13181 6664 13182 6650 13182 6665 13182 6665 13183 6650 13183 6666 13183 6665 13184 6666 13184 6656 13184 6656 13185 6666 13185 6667 13185 6656 13186 6667 13186 6657 13186 6657 13187 6667 13187 6653 13187 6657 13188 6653 13188 6655 13188 6655 13189 6653 13189 6668 13189 6652 13190 6663 13190 6668 13190 6668 13191 6663 13191 6655 13191 6649 13192 6669 13192 6654 13192 6654 13193 6669 13193 6662 13193 6650 13194 6664 13194 6670 13194 6670 13195 6664 13195 6660 13195 6672 13196 6691 13196 6675 13196 6686 13197 6687 13197 6671 13197 6671 13198 6687 13198 6688 13198 6671 13199 6688 13199 6673 13199 6673 13200 6688 13200 6672 13200 6692 13201 6673 13201 6674 13201 6674 13202 6673 13202 6672 13202 6674 13203 6672 13203 6690 13203 6690 13204 6672 13204 6675 13204 6689 13205 6676 13205 6677 13205 6677 13206 6676 13206 6679 13206 6677 13207 6679 13207 6678 13207 6678 13208 6679 13208 6685 13208 6680 13209 6682 13209 6681 13209 6681 13210 6682 13210 6683 13210 6681 13211 6683 13211 6679 13211 6679 13212 6683 13212 6684 13212 6679 13213 6684 13213 6685 13213 6671 13214 6683 13214 6686 13214 6686 13215 6683 13215 6682 13215 6686 13216 6682 13216 6687 13216 6687 13217 6682 13217 6680 13217 6687 13218 6680 13218 6688 13218 6688 13219 6680 13219 6681 13219 6678 13220 6674 13220 6677 13220 6677 13221 6674 13221 6690 13221 6677 13222 6690 13222 6689 13222 6689 13223 6690 13223 6675 13223 6689 13224 6675 13224 6676 13224 6676 13225 6675 13225 6691 13225 6676 13226 6691 13226 6679 13226 6679 13227 6691 13227 6672 13227 6688 13228 6681 13228 6672 13228 6672 13229 6681 13229 6679 13229 6685 13230 6684 13230 6692 13230 6692 13231 6684 13231 6673 13231 6674 13232 6678 13232 6692 13232 6692 13233 6678 13233 6685 13233 6673 13234 6684 13234 6671 13234 6671 13235 6684 13235 6683 13235 6702 13236 6693 13236 6695 13236 6695 13237 6693 13237 6713 13237 6694 13238 6703 13238 6713 13238 6713 13239 6703 13239 6704 13239 6713 13240 6704 13240 6712 13240 6707 13241 6695 13241 6709 13241 6709 13242 6695 13242 6713 13242 6709 13243 6713 13243 6711 13243 6711 13244 6713 13244 6712 13244 6708 13245 6710 13245 6696 13245 6696 13246 6710 13246 6697 13246 6696 13247 6697 13247 6698 13247 6698 13248 6697 13248 6701 13248 6705 13249 6699 13249 6706 13249 6706 13250 6699 13250 6714 13250 6706 13251 6714 13251 6697 13251 6697 13252 6714 13252 6700 13252 6697 13253 6700 13253 6701 13253 6701 13254 6700 13254 6702 13254 6702 13255 6700 13255 6693 13255 6713 13256 6714 13256 6694 13256 6694 13257 6714 13257 6699 13257 6694 13258 6699 13258 6703 13258 6703 13259 6699 13259 6705 13259 6703 13260 6705 13260 6704 13260 6704 13261 6705 13261 6706 13261 6698 13262 6695 13262 6696 13262 6696 13263 6695 13263 6707 13263 6696 13264 6707 13264 6708 13264 6708 13265 6707 13265 6709 13265 6708 13266 6709 13266 6710 13266 6710 13267 6709 13267 6711 13267 6710 13268 6711 13268 6697 13268 6697 13269 6711 13269 6712 13269 6704 13270 6706 13270 6712 13270 6712 13271 6706 13271 6697 13271 6693 13272 6700 13272 6713 13272 6713 13273 6700 13273 6714 13273 6695 13274 6698 13274 6702 13274 6702 13275 6698 13275 6701 13275 6725 13276 6715 13276 6716 13276 6716 13277 6715 13277 6718 13277 6726 13278 6717 13278 6718 13278 6718 13279 6717 13279 6736 13279 6718 13280 6736 13280 6735 13280 6732 13281 6716 13281 6734 13281 6734 13282 6716 13282 6718 13282 6734 13283 6718 13283 6719 13283 6719 13284 6718 13284 6735 13284 6724 13285 6731 13285 6723 13285 6731 13286 6720 13286 6723 13286 6723 13287 6720 13287 6733 13287 6723 13288 6733 13288 6721 13288 6729 13289 6728 13289 6730 13289 6730 13290 6728 13290 6727 13290 6730 13291 6727 13291 6723 13291 6723 13292 6727 13292 6722 13292 6723 13293 6722 13293 6724 13293 6724 13294 6722 13294 6725 13294 6725 13295 6722 13295 6715 13295 6718 13296 6727 13296 6726 13296 6726 13297 6727 13297 6728 13297 6726 13298 6728 13298 6717 13298 6717 13299 6728 13299 6729 13299 6717 13300 6729 13300 6736 13300 6736 13301 6729 13301 6730 13301 6731 13302 6716 13302 6720 13302 6720 13303 6716 13303 6732 13303 6720 13304 6732 13304 6733 13304 6733 13305 6732 13305 6734 13305 6733 13306 6734 13306 6721 13306 6721 13307 6734 13307 6719 13307 6721 13308 6719 13308 6723 13308 6723 13309 6719 13309 6735 13309 6736 13310 6730 13310 6735 13310 6735 13311 6730 13311 6723 13311 6715 13312 6722 13312 6718 13312 6718 13313 6722 13313 6727 13313 6716 13314 6731 13314 6725 13314 6725 13315 6731 13315 6724 13315 6757 13316 6750 13316 6739 13316 6739 13317 6750 13317 6740 13317 6737 13318 6752 13318 6740 13318 6740 13319 6752 13319 6753 13319 6740 13320 6753 13320 6755 13320 6738 13321 6739 13321 6754 13321 6754 13322 6739 13322 6740 13322 6754 13323 6740 13323 6741 13323 6741 13324 6740 13324 6755 13324 6749 13325 6742 13325 6743 13325 6744 13326 6746 13326 6745 13326 6745 13327 6746 13327 6747 13327 6745 13328 6747 13328 6748 13328 6743 13329 6751 13329 6749 13329 6749 13330 6751 13330 6756 13330 6749 13331 6756 13331 6747 13331 6747 13332 6756 13332 6758 13332 6747 13333 6758 13333 6748 13333 6758 13334 6756 13334 6757 13334 6757 13335 6756 13335 6750 13335 6740 13336 6751 13336 6737 13336 6737 13337 6751 13337 6743 13337 6737 13338 6743 13338 6752 13338 6752 13339 6743 13339 6742 13339 6752 13340 6742 13340 6753 13340 6753 13341 6742 13341 6749 13341 6748 13342 6739 13342 6745 13342 6745 13343 6739 13343 6738 13343 6745 13344 6738 13344 6744 13344 6744 13345 6738 13345 6754 13345 6744 13346 6754 13346 6746 13346 6746 13347 6754 13347 6741 13347 6746 13348 6741 13348 6747 13348 6747 13349 6741 13349 6755 13349 6753 13350 6749 13350 6755 13350 6755 13351 6749 13351 6747 13351 6750 13352 6756 13352 6740 13352 6740 13353 6756 13353 6751 13353 6739 13354 6748 13354 6757 13354 6757 13355 6748 13355 6758 13355 6780 13356 6771 13356 6759 13356 6759 13357 6771 13357 6761 13357 6772 13358 6760 13358 6761 13358 6761 13359 6760 13359 6762 13359 6761 13360 6762 13360 6779 13360 6774 13361 6759 13361 6776 13361 6776 13362 6759 13362 6761 13362 6776 13363 6761 13363 6777 13363 6777 13364 6761 13364 6779 13364 6769 13365 6763 13365 6770 13365 6773 13366 6764 13366 6765 13366 6765 13367 6764 13367 6769 13367 6765 13368 6769 13368 6778 13368 6778 13369 6769 13369 6766 13369 6775 13370 6766 13370 6767 13370 6767 13371 6766 13371 6769 13371 6767 13372 6769 13372 6768 13372 6768 13373 6769 13373 6770 13373 6770 13374 6763 13374 6780 13374 6780 13375 6763 13375 6771 13375 6761 13376 6769 13376 6772 13376 6772 13377 6769 13377 6764 13377 6772 13378 6764 13378 6760 13378 6760 13379 6764 13379 6773 13379 6760 13380 6773 13380 6762 13380 6762 13381 6773 13381 6765 13381 6768 13382 6759 13382 6767 13382 6767 13383 6759 13383 6774 13383 6767 13384 6774 13384 6775 13384 6775 13385 6774 13385 6776 13385 6775 13386 6776 13386 6766 13386 6766 13387 6776 13387 6777 13387 6766 13388 6777 13388 6778 13388 6778 13389 6777 13389 6779 13389 6762 13390 6765 13390 6779 13390 6779 13391 6765 13391 6778 13391 6771 13392 6763 13392 6761 13392 6761 13393 6763 13393 6769 13393 6759 13394 6768 13394 6780 13394 6780 13395 6768 13395 6770 13395 6794 13396 6781 13396 6799 13396 6799 13397 6782 13397 6794 13397 6794 13398 6782 13398 6783 13398 6794 13399 6783 13399 6786 13399 6784 13400 6785 13400 6797 13400 6797 13401 6785 13401 6794 13401 6797 13402 6794 13402 6798 13402 6798 13403 6794 13403 6786 13403 6789 13404 6787 13404 6790 13404 6795 13405 6788 13405 6789 13405 6789 13406 6788 13406 6796 13406 6789 13407 6796 13407 6787 13407 6791 13408 6800 13408 6792 13408 6792 13409 6800 13409 6789 13409 6792 13410 6789 13410 6793 13410 6793 13411 6789 13411 6790 13411 6800 13412 6791 13412 6781 13412 6781 13413 6791 13413 6799 13413 6782 13414 6792 13414 6783 13414 6783 13415 6792 13415 6793 13415 6783 13416 6793 13416 6786 13416 6786 13417 6793 13417 6790 13417 6786 13418 6790 13418 6798 13418 6798 13419 6790 13419 6787 13419 6789 13420 6794 13420 6795 13420 6795 13421 6794 13421 6785 13421 6795 13422 6785 13422 6788 13422 6788 13423 6785 13423 6784 13423 6788 13424 6784 13424 6796 13424 6796 13425 6784 13425 6797 13425 6798 13426 6787 13426 6797 13426 6797 13427 6787 13427 6796 13427 6799 13428 6791 13428 6782 13428 6782 13429 6791 13429 6792 13429 6794 13430 6789 13430 6781 13430 6781 13431 6789 13431 6800 13431 6801 13432 6802 13432 6803 13432 6815 13433 6804 13433 6803 13433 6803 13434 6804 13434 6817 13434 6803 13435 6817 13435 6801 13435 6805 13436 6820 13436 6806 13436 6806 13437 6820 13437 6807 13437 6806 13438 6807 13438 6817 13438 6817 13439 6807 13439 6822 13439 6817 13440 6822 13440 6801 13440 6808 13441 6819 13441 6813 13441 6816 13442 6809 13442 6818 13442 6818 13443 6809 13443 6810 13443 6821 13444 6814 13444 6810 13444 6810 13445 6814 13445 6811 13445 6810 13446 6811 13446 6818 13446 6818 13447 6811 13447 6808 13447 6818 13448 6808 13448 6812 13448 6812 13449 6808 13449 6813 13449 6811 13450 6814 13450 6822 13450 6822 13451 6814 13451 6801 13451 6814 13452 6821 13452 6801 13452 6801 13453 6821 13453 6802 13453 6803 13454 6810 13454 6815 13454 6815 13455 6810 13455 6809 13455 6815 13456 6809 13456 6804 13456 6804 13457 6809 13457 6816 13457 6804 13458 6816 13458 6817 13458 6817 13459 6816 13459 6818 13459 6808 13460 6807 13460 6819 13460 6819 13461 6807 13461 6820 13461 6819 13462 6820 13462 6813 13462 6813 13463 6820 13463 6805 13463 6813 13464 6805 13464 6812 13464 6812 13465 6805 13465 6806 13465 6817 13466 6818 13466 6806 13466 6806 13467 6818 13467 6812 13467 6802 13468 6821 13468 6803 13468 6803 13469 6821 13469 6810 13469 6807 13470 6808 13470 6822 13470 6822 13471 6808 13471 6811 13471 6842 13472 6828 13472 6841 13472 6841 13473 6828 13473 6839 13473 6841 13474 6839 13474 6823 13474 6836 13475 6835 13475 6837 13475 6837 13476 6835 13476 6841 13476 6837 13477 6841 13477 6832 13477 6832 13478 6841 13478 6823 13478 6832 13479 6823 13479 6831 13479 6834 13480 6833 13480 6827 13480 6824 13481 6825 13481 6834 13481 6834 13482 6825 13482 6838 13482 6834 13483 6838 13483 6833 13483 6840 13484 6826 13484 6829 13484 6829 13485 6826 13485 6834 13485 6829 13486 6834 13486 6830 13486 6830 13487 6834 13487 6827 13487 6842 13488 6826 13488 6828 13488 6828 13489 6826 13489 6840 13489 6839 13490 6829 13490 6823 13490 6823 13491 6829 13491 6830 13491 6823 13492 6830 13492 6831 13492 6831 13493 6830 13493 6827 13493 6831 13494 6827 13494 6832 13494 6832 13495 6827 13495 6833 13495 6834 13496 6841 13496 6824 13496 6824 13497 6841 13497 6835 13497 6824 13498 6835 13498 6825 13498 6825 13499 6835 13499 6836 13499 6825 13500 6836 13500 6838 13500 6838 13501 6836 13501 6837 13501 6832 13502 6833 13502 6837 13502 6837 13503 6833 13503 6838 13503 6828 13504 6840 13504 6839 13504 6839 13505 6840 13505 6829 13505 6841 13506 6834 13506 6842 13506 6842 13507 6834 13507 6826 13507 6843 13508 6844 13508 6862 13508 6862 13509 6844 13509 6852 13509 6862 13510 6852 13510 6853 13510 6858 13511 6845 13511 6860 13511 6860 13512 6845 13512 6862 13512 6860 13513 6862 13513 6855 13513 6855 13514 6862 13514 6853 13514 6855 13515 6853 13515 6854 13515 6847 13516 6846 13516 6850 13516 6856 13517 6857 13517 6847 13517 6847 13518 6857 13518 6859 13518 6847 13519 6859 13519 6846 13519 6851 13520 6848 13520 6861 13520 6861 13521 6848 13521 6847 13521 6861 13522 6847 13522 6849 13522 6849 13523 6847 13523 6850 13523 6843 13524 6848 13524 6844 13524 6844 13525 6848 13525 6851 13525 6852 13526 6861 13526 6853 13526 6853 13527 6861 13527 6849 13527 6853 13528 6849 13528 6854 13528 6854 13529 6849 13529 6850 13529 6854 13530 6850 13530 6855 13530 6855 13531 6850 13531 6846 13531 6847 13532 6862 13532 6856 13532 6856 13533 6862 13533 6845 13533 6856 13534 6845 13534 6857 13534 6857 13535 6845 13535 6858 13535 6857 13536 6858 13536 6859 13536 6859 13537 6858 13537 6860 13537 6855 13538 6846 13538 6860 13538 6860 13539 6846 13539 6859 13539 6844 13540 6851 13540 6852 13540 6852 13541 6851 13541 6861 13541 6862 13542 6847 13542 6843 13542 6843 13543 6847 13543 6848 13543 6873 13544 6874 13544 6867 13544 6867 13545 6874 13545 6864 13545 6863 13546 6878 13546 6877 13546 6877 13547 6876 13547 6863 13547 6863 13548 6876 13548 6865 13548 6863 13549 6865 13549 6864 13549 6864 13550 6865 13550 6866 13550 6864 13551 6866 13551 6867 13551 6881 13552 6868 13552 6879 13552 6869 13553 6875 13553 6871 13553 6871 13554 6875 13554 6872 13554 6879 13555 6870 13555 6881 13555 6881 13556 6870 13556 6871 13556 6881 13557 6871 13557 6880 13557 6880 13558 6871 13558 6872 13558 6880 13559 6872 13559 6882 13559 6867 13560 6872 13560 6873 13560 6873 13561 6872 13561 6875 13561 6873 13562 6875 13562 6874 13562 6874 13563 6875 13563 6869 13563 6874 13564 6869 13564 6864 13564 6864 13565 6869 13565 6871 13565 6881 13566 6876 13566 6868 13566 6868 13567 6876 13567 6877 13567 6868 13568 6877 13568 6879 13568 6879 13569 6877 13569 6878 13569 6879 13570 6878 13570 6870 13570 6870 13571 6878 13571 6863 13571 6864 13572 6871 13572 6863 13572 6863 13573 6871 13573 6870 13573 6865 13574 6880 13574 6866 13574 6866 13575 6880 13575 6882 13575 6876 13576 6881 13576 6865 13576 6865 13577 6881 13577 6880 13577 6866 13578 6882 13578 6867 13578 6867 13579 6882 13579 6872 13579 6914 13580 6913 13580 6890 13580 6883 13581 6884 13581 6908 13581 6908 13582 6884 13582 6911 13582 6908 13583 6911 13583 6891 13583 6891 13584 6911 13584 6889 13584 6885 13585 6886 13585 6899 13585 6899 13586 6886 13586 6903 13586 6899 13587 6903 13587 6890 13587 6890 13588 6903 13588 6887 13588 6887 13589 6888 13589 6893 13589 6916 13590 6914 13590 6889 13590 6889 13591 6914 13591 6890 13591 6889 13592 6890 13592 6891 13592 6891 13593 6890 13593 6887 13593 6891 13594 6887 13594 6892 13594 6892 13595 6887 13595 6893 13595 6894 13596 6918 13596 6900 13596 6910 13597 6909 13597 6917 13597 6917 13598 6909 13598 6894 13598 6917 13599 6894 13599 6895 13599 6895 13600 6894 13600 6896 13600 6902 13601 6901 13601 6897 13601 6897 13602 6901 13602 6900 13602 6897 13603 6900 13603 6907 13603 6907 13604 6900 13604 6906 13604 6915 13605 6896 13605 6912 13605 6912 13606 6896 13606 6894 13606 6912 13607 6894 13607 6898 13607 6898 13608 6894 13608 6900 13608 6918 13609 6904 13609 6900 13609 6900 13610 6904 13610 6905 13610 6900 13611 6905 13611 6906 13611 6899 13612 6900 13612 6885 13612 6885 13613 6900 13613 6901 13613 6885 13614 6901 13614 6886 13614 6886 13615 6901 13615 6902 13615 6886 13616 6902 13616 6903 13616 6903 13617 6902 13617 6897 13617 6918 13618 6891 13618 6904 13618 6904 13619 6891 13619 6892 13619 6904 13620 6892 13620 6905 13620 6905 13621 6892 13621 6893 13621 6905 13622 6893 13622 6906 13622 6906 13623 6893 13623 6888 13623 6906 13624 6888 13624 6907 13624 6907 13625 6888 13625 6887 13625 6903 13626 6897 13626 6887 13626 6887 13627 6897 13627 6907 13627 6908 13628 6894 13628 6883 13628 6883 13629 6894 13629 6909 13629 6883 13630 6909 13630 6884 13630 6884 13631 6909 13631 6910 13631 6884 13632 6910 13632 6911 13632 6911 13633 6910 13633 6917 13633 6898 13634 6890 13634 6912 13634 6912 13635 6890 13635 6913 13635 6912 13636 6913 13636 6915 13636 6915 13637 6913 13637 6914 13637 6915 13638 6914 13638 6896 13638 6896 13639 6914 13639 6916 13639 6896 13640 6916 13640 6895 13640 6895 13641 6916 13641 6889 13641 6911 13642 6917 13642 6889 13642 6889 13643 6917 13643 6895 13643 6891 13644 6918 13644 6908 13644 6908 13645 6918 13645 6894 13645 6890 13646 6898 13646 6899 13646 6899 13647 6898 13647 6900 13647 6949 13648 6946 13648 6924 13648 6953 13649 6950 13649 6923 13649 6926 13650 6924 13650 6932 13650 6919 13651 6942 13651 6953 13651 6953 13652 6942 13652 6951 13652 6953 13653 6951 13653 6950 13653 6926 13654 6920 13654 6939 13654 6921 13655 6922 13655 6932 13655 6932 13656 6922 13656 6940 13656 6932 13657 6940 13657 6926 13657 6923 13658 6949 13658 6953 13658 6953 13659 6949 13659 6924 13659 6953 13660 6924 13660 6925 13660 6925 13661 6924 13661 6926 13661 6925 13662 6926 13662 6936 13662 6936 13663 6926 13663 6939 13663 6947 13664 6948 13664 6952 13664 6927 13665 6943 13665 6941 13665 6941 13666 6954 13666 6927 13666 6927 13667 6954 13667 6928 13667 6927 13668 6928 13668 6952 13668 6952 13669 6928 13669 6931 13669 6935 13670 6937 13670 6928 13670 6928 13671 6937 13671 6938 13671 6928 13672 6938 13672 6931 13672 6933 13673 6929 13673 6934 13673 6934 13674 6929 13674 6930 13674 6934 13675 6930 13675 6931 13675 6931 13676 6930 13676 6944 13676 6931 13677 6944 13677 6952 13677 6952 13678 6944 13678 6945 13678 6952 13679 6945 13679 6947 13679 6932 13680 6930 13680 6921 13680 6921 13681 6930 13681 6929 13681 6921 13682 6929 13682 6922 13682 6922 13683 6929 13683 6933 13683 6922 13684 6933 13684 6940 13684 6940 13685 6933 13685 6934 13685 6928 13686 6925 13686 6935 13686 6935 13687 6925 13687 6936 13687 6935 13688 6936 13688 6937 13688 6937 13689 6936 13689 6939 13689 6937 13690 6939 13690 6938 13690 6938 13691 6939 13691 6920 13691 6938 13692 6920 13692 6931 13692 6931 13693 6920 13693 6926 13693 6940 13694 6934 13694 6926 13694 6926 13695 6934 13695 6931 13695 6953 13696 6954 13696 6919 13696 6919 13697 6954 13697 6941 13697 6919 13698 6941 13698 6942 13698 6942 13699 6941 13699 6943 13699 6942 13700 6943 13700 6951 13700 6951 13701 6943 13701 6927 13701 6944 13702 6924 13702 6945 13702 6945 13703 6924 13703 6946 13703 6945 13704 6946 13704 6947 13704 6947 13705 6946 13705 6949 13705 6947 13706 6949 13706 6948 13706 6948 13707 6949 13707 6923 13707 6948 13708 6923 13708 6952 13708 6952 13709 6923 13709 6950 13709 6951 13710 6927 13710 6950 13710 6950 13711 6927 13711 6952 13711 6925 13712 6928 13712 6953 13712 6953 13713 6928 13713 6954 13713 6924 13714 6944 13714 6932 13714 6932 13715 6944 13715 6930 13715 6981 13716 6983 13716 6955 13716 6955 13717 6983 13717 6956 13717 6955 13718 6956 13718 6957 13718 6957 13719 6956 13719 6958 13719 6973 13720 6959 13720 6990 13720 6990 13721 6959 13721 6980 13721 6990 13722 6980 13722 6960 13722 6960 13723 6980 13723 6961 13723 6962 13724 6977 13724 6978 13724 6978 13725 6977 13725 6957 13725 6958 13726 6988 13726 6963 13726 6963 13727 6986 13727 6958 13727 6958 13728 6986 13728 6960 13728 6958 13729 6960 13729 6957 13729 6957 13730 6960 13730 6961 13730 6957 13731 6961 13731 6978 13731 6989 13732 6964 13732 6982 13732 6985 13733 6987 13733 6984 13733 6984 13734 6987 13734 6965 13734 6984 13735 6965 13735 6971 13735 6975 13736 6974 13736 6966 13736 6967 13737 6976 13737 6970 13737 6970 13738 6976 13738 6968 13738 6970 13739 6968 13739 6979 13739 6982 13740 6969 13740 6989 13740 6989 13741 6969 13741 6970 13741 6989 13742 6970 13742 6965 13742 6965 13743 6970 13743 6979 13743 6965 13744 6979 13744 6971 13744 6971 13745 6979 13745 6975 13745 6971 13746 6975 13746 6972 13746 6972 13747 6975 13747 6966 13747 6990 13748 6972 13748 6973 13748 6973 13749 6972 13749 6966 13749 6973 13750 6966 13750 6959 13750 6959 13751 6966 13751 6974 13751 6959 13752 6974 13752 6980 13752 6980 13753 6974 13753 6975 13753 6970 13754 6957 13754 6967 13754 6967 13755 6957 13755 6977 13755 6967 13756 6977 13756 6976 13756 6976 13757 6977 13757 6962 13757 6976 13758 6962 13758 6968 13758 6968 13759 6962 13759 6978 13759 6968 13760 6978 13760 6979 13760 6979 13761 6978 13761 6961 13761 6980 13762 6975 13762 6961 13762 6961 13763 6975 13763 6979 13763 6955 13764 6969 13764 6981 13764 6981 13765 6969 13765 6982 13765 6981 13766 6982 13766 6983 13766 6983 13767 6982 13767 6964 13767 6983 13768 6964 13768 6956 13768 6956 13769 6964 13769 6989 13769 6971 13770 6960 13770 6984 13770 6984 13771 6960 13771 6986 13771 6984 13772 6986 13772 6985 13772 6985 13773 6986 13773 6963 13773 6985 13774 6963 13774 6987 13774 6987 13775 6963 13775 6988 13775 6987 13776 6988 13776 6965 13776 6965 13777 6988 13777 6958 13777 6956 13778 6989 13778 6958 13778 6958 13779 6989 13779 6965 13779 6957 13780 6970 13780 6955 13780 6955 13781 6970 13781 6969 13781 6960 13782 6971 13782 6990 13782 6990 13783 6971 13783 6972 13783 6996 13784 6997 13784 7006 13784 7016 13785 7018 13785 6992 13785 6992 13786 7018 13786 6991 13786 6992 13787 6991 13787 7010 13787 7010 13788 6991 13788 6998 13788 6996 13789 7014 13789 6994 13789 7007 13790 6993 13790 7006 13790 7006 13791 6993 13791 7015 13791 7006 13792 7015 13792 6996 13792 6998 13793 7023 13793 7021 13793 6994 13794 6995 13794 6996 13794 6996 13795 6995 13795 7010 13795 6996 13796 7010 13796 6997 13796 6997 13797 7010 13797 6998 13797 6997 13798 6998 13798 7020 13798 7020 13799 6998 13799 7021 13799 7024 13800 7011 13800 7012 13800 7019 13801 7017 13801 6999 13801 6999 13802 7017 13802 7000 13802 6999 13803 7000 13803 7001 13803 7001 13804 7000 13804 7024 13804 7001 13805 7024 13805 7002 13805 7002 13806 7024 13806 7012 13806 7002 13807 7012 13807 7013 13807 7003 13808 7008 13808 7009 13808 7009 13809 7008 13809 7026 13809 7009 13810 7026 13810 7025 13810 7004 13811 7022 13811 7005 13811 7005 13812 7022 13812 7001 13812 7005 13813 7001 13813 7025 13813 7025 13814 7001 13814 7002 13814 7025 13815 7002 13815 7009 13815 7006 13816 7026 13816 7007 13816 7007 13817 7026 13817 7008 13817 7007 13818 7008 13818 6993 13818 6993 13819 7008 13819 7003 13819 6993 13820 7003 13820 7015 13820 7015 13821 7003 13821 7009 13821 7024 13822 7010 13822 7011 13822 7011 13823 7010 13823 6995 13823 7011 13824 6995 13824 7012 13824 7012 13825 6995 13825 6994 13825 7012 13826 6994 13826 7013 13826 7013 13827 6994 13827 7014 13827 7013 13828 7014 13828 7002 13828 7002 13829 7014 13829 6996 13829 7015 13830 7009 13830 6996 13830 6996 13831 7009 13831 7002 13831 6992 13832 7000 13832 7016 13832 7016 13833 7000 13833 7017 13833 7016 13834 7017 13834 7018 13834 7018 13835 7017 13835 7019 13835 7018 13836 7019 13836 6991 13836 6991 13837 7019 13837 6999 13837 7025 13838 6997 13838 7005 13838 7005 13839 6997 13839 7020 13839 7005 13840 7020 13840 7004 13840 7004 13841 7020 13841 7021 13841 7004 13842 7021 13842 7022 13842 7022 13843 7021 13843 7023 13843 7022 13844 7023 13844 7001 13844 7001 13845 7023 13845 6998 13845 6991 13846 6999 13846 6998 13846 6998 13847 6999 13847 7001 13847 7010 13848 7024 13848 6992 13848 6992 13849 7024 13849 7000 13849 6997 13850 7025 13850 7006 13850 7006 13851 7025 13851 7026 13851 7031 13852 7060 13852 7030 13852 7027 13853 7046 13853 7060 13853 7060 13854 7046 13854 7047 13854 7060 13855 7047 13855 7052 13855 7050 13856 7030 13856 7028 13856 7028 13857 7030 13857 7060 13857 7028 13858 7060 13858 7029 13858 7029 13859 7060 13859 7052 13859 7030 13860 7059 13860 7031 13860 7031 13861 7059 13861 7032 13861 7031 13862 7032 13862 7034 13862 7057 13863 7033 13863 7058 13863 7058 13864 7033 13864 7031 13864 7058 13865 7031 13865 7054 13865 7054 13866 7031 13866 7034 13866 7042 13867 7035 13867 7040 13867 7055 13868 7053 13868 7056 13868 7056 13869 7053 13869 7043 13869 7036 13870 7038 13870 7037 13870 7037 13871 7038 13871 7045 13871 7037 13872 7045 13872 7039 13872 7039 13873 7045 13873 7051 13873 7040 13874 7041 13874 7042 13874 7042 13875 7041 13875 7056 13875 7042 13876 7056 13876 7045 13876 7045 13877 7056 13877 7043 13877 7045 13878 7043 13878 7044 13878 7044 13879 7048 13879 7045 13879 7045 13880 7048 13880 7049 13880 7045 13881 7049 13881 7051 13881 7060 13882 7045 13882 7027 13882 7027 13883 7045 13883 7038 13883 7027 13884 7038 13884 7046 13884 7046 13885 7038 13885 7036 13885 7046 13886 7036 13886 7047 13886 7047 13887 7036 13887 7037 13887 7044 13888 7030 13888 7048 13888 7048 13889 7030 13889 7050 13889 7048 13890 7050 13890 7049 13890 7049 13891 7050 13891 7028 13891 7049 13892 7028 13892 7051 13892 7051 13893 7028 13893 7029 13893 7051 13894 7029 13894 7039 13894 7039 13895 7029 13895 7052 13895 7047 13896 7037 13896 7052 13896 7052 13897 7037 13897 7039 13897 7059 13898 7043 13898 7032 13898 7032 13899 7043 13899 7053 13899 7032 13900 7053 13900 7034 13900 7034 13901 7053 13901 7055 13901 7034 13902 7055 13902 7054 13902 7054 13903 7055 13903 7056 13903 7042 13904 7031 13904 7035 13904 7035 13905 7031 13905 7033 13905 7035 13906 7033 13906 7040 13906 7040 13907 7033 13907 7057 13907 7040 13908 7057 13908 7041 13908 7041 13909 7057 13909 7058 13909 7054 13910 7056 13910 7058 13910 7058 13911 7056 13911 7041 13911 7030 13912 7044 13912 7059 13912 7059 13913 7044 13913 7043 13913 7031 13914 7042 13914 7060 13914 7060 13915 7042 13915 7045 13915 7069 13916 7078 13916 7070 13916 7062 13917 7082 13917 7061 13917 7062 13918 7064 13918 7066 13918 7085 13919 7087 13919 7063 13919 7063 13920 7087 13920 7064 13920 7063 13921 7064 13921 7093 13921 7093 13922 7064 13922 7062 13922 7093 13923 7062 13923 7065 13923 7065 13924 7062 13924 7061 13924 7091 13925 7088 13925 7066 13925 7066 13926 7088 13926 7067 13926 7066 13927 7067 13927 7062 13927 7062 13928 7067 13928 7069 13928 7062 13929 7069 13929 7068 13929 7068 13930 7069 13930 7070 13930 7077 13931 7073 13931 7075 13931 7071 13932 7079 13932 7084 13932 7084 13933 7079 13933 7077 13933 7084 13934 7077 13934 7083 13934 7083 13935 7077 13935 7081 13935 7089 13936 7090 13936 7073 13936 7073 13937 7090 13937 7072 13937 7073 13938 7072 13938 7092 13938 7092 13939 7074 13939 7073 13939 7073 13940 7074 13940 7086 13940 7073 13941 7086 13941 7075 13941 7080 13942 7081 13942 7076 13942 7076 13943 7081 13943 7077 13943 7076 13944 7077 13944 7094 13944 7094 13945 7077 13945 7075 13945 7069 13946 7077 13946 7078 13946 7078 13947 7077 13947 7079 13947 7078 13948 7079 13948 7070 13948 7070 13949 7079 13949 7071 13949 7070 13950 7071 13950 7068 13950 7068 13951 7071 13951 7084 13951 7094 13952 7093 13952 7076 13952 7076 13953 7093 13953 7065 13953 7076 13954 7065 13954 7080 13954 7080 13955 7065 13955 7061 13955 7080 13956 7061 13956 7081 13956 7081 13957 7061 13957 7082 13957 7081 13958 7082 13958 7083 13958 7083 13959 7082 13959 7062 13959 7068 13960 7084 13960 7062 13960 7062 13961 7084 13961 7083 13961 7063 13962 7075 13962 7085 13962 7085 13963 7075 13963 7086 13963 7085 13964 7086 13964 7087 13964 7087 13965 7086 13965 7074 13965 7087 13966 7074 13966 7064 13966 7064 13967 7074 13967 7092 13967 7073 13968 7067 13968 7089 13968 7089 13969 7067 13969 7088 13969 7089 13970 7088 13970 7090 13970 7090 13971 7088 13971 7091 13971 7090 13972 7091 13972 7072 13972 7072 13973 7091 13973 7066 13973 7064 13974 7092 13974 7066 13974 7066 13975 7092 13975 7072 13975 7093 13976 7094 13976 7063 13976 7063 13977 7094 13977 7075 13977 7067 13978 7073 13978 7069 13978 7069 13979 7073 13979 7077 13979 7095 13980 7096 13980 7128 13980 7128 13981 7096 13981 7114 13981 7128 13982 7114 13982 7101 13982 7097 13983 7119 13983 7121 13983 7125 13984 7098 13984 7126 13984 7126 13985 7098 13985 7127 13985 7099 13986 7103 13986 7118 13986 7118 13987 7103 13987 7128 13987 7118 13988 7128 13988 7100 13988 7100 13989 7128 13989 7101 13989 7121 13990 7102 13990 7097 13990 7097 13991 7102 13991 7126 13991 7097 13992 7126 13992 7103 13992 7103 13993 7126 13993 7127 13993 7103 13994 7127 13994 7128 13994 7113 13995 7110 13995 7112 13995 7104 13996 7105 13996 7106 13996 7106 13997 7105 13997 7113 13997 7106 13998 7113 13998 7107 13998 7107 13999 7113 13999 7108 13999 7123 14000 7109 14000 7110 14000 7110 14001 7109 14001 7124 14001 7120 14002 7112 14002 7122 14002 7122 14003 7112 14003 7110 14003 7122 14004 7110 14004 7111 14004 7111 14005 7110 14005 7124 14005 7117 14006 7108 14006 7116 14006 7116 14007 7108 14007 7113 14007 7116 14008 7113 14008 7115 14008 7115 14009 7113 14009 7112 14009 7128 14010 7113 14010 7095 14010 7095 14011 7113 14011 7105 14011 7095 14012 7105 14012 7096 14012 7096 14013 7105 14013 7104 14013 7096 14014 7104 14014 7114 14014 7114 14015 7104 14015 7106 14015 7115 14016 7103 14016 7116 14016 7116 14017 7103 14017 7099 14017 7116 14018 7099 14018 7117 14018 7117 14019 7099 14019 7118 14019 7117 14020 7118 14020 7108 14020 7108 14021 7118 14021 7100 14021 7108 14022 7100 14022 7107 14022 7107 14023 7100 14023 7101 14023 7114 14024 7106 14024 7101 14024 7101 14025 7106 14025 7107 14025 7097 14026 7112 14026 7119 14026 7119 14027 7112 14027 7120 14027 7119 14028 7120 14028 7121 14028 7121 14029 7120 14029 7122 14029 7121 14030 7122 14030 7102 14030 7102 14031 7122 14031 7111 14031 7110 14032 7127 14032 7123 14032 7123 14033 7127 14033 7098 14033 7123 14034 7098 14034 7109 14034 7109 14035 7098 14035 7125 14035 7109 14036 7125 14036 7124 14036 7124 14037 7125 14037 7126 14037 7102 14038 7111 14038 7126 14038 7126 14039 7111 14039 7124 14039 7103 14040 7115 14040 7097 14040 7097 14041 7115 14041 7112 14041 7127 14042 7110 14042 7128 14042 7128 14043 7110 14043 7113 14043 7141 14044 7129 14044 7161 14044 7161 14045 7129 14045 7143 14045 7161 14046 7143 14046 7146 14046 7144 14047 7130 14047 7131 14047 7131 14048 7130 14048 7161 14048 7131 14049 7161 14049 7132 14049 7132 14050 7161 14050 7146 14050 7133 14051 7150 14051 7159 14051 7159 14052 7150 14052 7157 14052 7134 14053 7156 14053 7153 14053 7153 14054 7152 14054 7134 14054 7134 14055 7152 14055 7161 14055 7134 14056 7161 14056 7157 14056 7157 14057 7161 14057 7130 14057 7157 14058 7130 14058 7159 14058 7158 14059 7151 14059 7149 14059 7148 14060 7160 14060 7135 14060 7135 14061 7160 14061 7136 14061 7135 14062 7136 14062 7139 14062 7142 14063 7137 14063 7147 14063 7147 14064 7137 14064 7135 14064 7147 14065 7135 14065 7138 14065 7138 14066 7135 14066 7139 14066 7138 14067 7139 14067 7145 14067 7140 14068 7154 14068 7162 14068 7162 14069 7154 14069 7155 14069 7162 14070 7155 14070 7135 14070 7135 14071 7155 14071 7158 14071 7135 14072 7158 14072 7148 14072 7148 14073 7158 14073 7149 14073 7161 14074 7135 14074 7141 14074 7141 14075 7135 14075 7137 14075 7141 14076 7137 14076 7129 14076 7129 14077 7137 14077 7142 14077 7129 14078 7142 14078 7143 14078 7143 14079 7142 14079 7147 14079 7160 14080 7130 14080 7136 14080 7136 14081 7130 14081 7144 14081 7136 14082 7144 14082 7139 14082 7139 14083 7144 14083 7131 14083 7139 14084 7131 14084 7145 14084 7145 14085 7131 14085 7132 14085 7145 14086 7132 14086 7138 14086 7138 14087 7132 14087 7146 14087 7143 14088 7147 14088 7146 14088 7146 14089 7147 14089 7138 14089 7159 14090 7148 14090 7133 14090 7133 14091 7148 14091 7149 14091 7133 14092 7149 14092 7150 14092 7150 14093 7149 14093 7151 14093 7150 14094 7151 14094 7157 14094 7157 14095 7151 14095 7158 14095 7162 14096 7152 14096 7140 14096 7140 14097 7152 14097 7153 14097 7140 14098 7153 14098 7154 14098 7154 14099 7153 14099 7156 14099 7154 14100 7156 14100 7155 14100 7155 14101 7156 14101 7134 14101 7157 14102 7158 14102 7134 14102 7134 14103 7158 14103 7155 14103 7130 14104 7160 14104 7159 14104 7159 14105 7160 14105 7148 14105 7152 14106 7162 14106 7161 14106 7161 14107 7162 14107 7135 14107 7186 14108 7188 14108 7163 14108 7163 14109 7188 14109 7195 14109 7163 14110 7195 14110 7164 14110 7175 14111 7177 14111 7196 14111 7196 14112 7177 14112 7167 14112 7185 14113 7182 14113 7180 14113 7193 14114 7191 14114 7165 14114 7165 14115 7191 14115 7163 14115 7165 14116 7163 14116 7166 14116 7166 14117 7163 14117 7164 14117 7180 14118 7179 14118 7185 14118 7185 14119 7179 14119 7163 14119 7185 14120 7163 14120 7167 14120 7167 14121 7163 14121 7191 14121 7167 14122 7191 14122 7196 14122 7170 14123 7168 14123 7172 14123 7189 14124 7187 14124 7169 14124 7169 14125 7187 14125 7170 14125 7169 14126 7170 14126 7194 14126 7194 14127 7170 14127 7174 14127 7171 14128 7181 14128 7168 14128 7168 14129 7181 14129 7183 14129 7176 14130 7172 14130 7178 14130 7178 14131 7172 14131 7168 14131 7178 14132 7168 14132 7184 14132 7184 14133 7168 14133 7183 14133 7173 14134 7174 14134 7192 14134 7192 14135 7174 14135 7170 14135 7192 14136 7170 14136 7190 14136 7190 14137 7170 14137 7172 14137 7196 14138 7172 14138 7175 14138 7175 14139 7172 14139 7176 14139 7175 14140 7176 14140 7177 14140 7177 14141 7176 14141 7178 14141 7177 14142 7178 14142 7167 14142 7167 14143 7178 14143 7184 14143 7168 14144 7179 14144 7171 14144 7171 14145 7179 14145 7180 14145 7171 14146 7180 14146 7181 14146 7181 14147 7180 14147 7182 14147 7181 14148 7182 14148 7183 14148 7183 14149 7182 14149 7185 14149 7167 14150 7184 14150 7185 14150 7185 14151 7184 14151 7183 14151 7163 14152 7170 14152 7186 14152 7186 14153 7170 14153 7187 14153 7186 14154 7187 14154 7188 14154 7188 14155 7187 14155 7189 14155 7188 14156 7189 14156 7195 14156 7195 14157 7189 14157 7169 14157 7190 14158 7191 14158 7192 14158 7192 14159 7191 14159 7193 14159 7192 14160 7193 14160 7173 14160 7173 14161 7193 14161 7165 14161 7173 14162 7165 14162 7174 14162 7174 14163 7165 14163 7166 14163 7174 14164 7166 14164 7194 14164 7194 14165 7166 14165 7164 14165 7195 14166 7169 14166 7164 14166 7164 14167 7169 14167 7194 14167 7179 14168 7168 14168 7163 14168 7163 14169 7168 14169 7170 14169 7191 14170 7190 14170 7196 14170 7196 14171 7190 14171 7172 14171 7215 14172 7197 14172 7201 14172 7201 14173 7197 14173 7216 14173 7201 14174 7216 14174 7222 14174 7230 14175 7224 14175 7203 14175 7198 14176 7199 14176 7229 14176 7229 14177 7199 14177 7205 14177 7218 14178 7200 14178 7220 14178 7220 14179 7200 14179 7201 14179 7220 14180 7201 14180 7202 14180 7202 14181 7201 14181 7222 14181 7203 14182 7204 14182 7230 14182 7230 14183 7204 14183 7229 14183 7230 14184 7229 14184 7200 14184 7200 14185 7229 14185 7205 14185 7200 14186 7205 14186 7201 14186 7206 14187 7209 14187 7223 14187 7223 14188 7209 14188 7212 14188 7217 14189 7207 14189 7208 14189 7208 14190 7207 14190 7209 14190 7208 14191 7209 14191 7210 14191 7210 14192 7209 14192 7221 14192 7227 14193 7228 14193 7212 14193 7212 14194 7228 14194 7213 14194 7225 14195 7223 14195 7226 14195 7226 14196 7223 14196 7212 14196 7226 14197 7212 14197 7211 14197 7211 14198 7212 14198 7213 14198 7206 14199 7219 14199 7209 14199 7209 14200 7219 14200 7214 14200 7209 14201 7214 14201 7221 14201 7201 14202 7209 14202 7215 14202 7215 14203 7209 14203 7207 14203 7215 14204 7207 14204 7197 14204 7197 14205 7207 14205 7217 14205 7197 14206 7217 14206 7216 14206 7216 14207 7217 14207 7208 14207 7206 14208 7200 14208 7219 14208 7219 14209 7200 14209 7218 14209 7219 14210 7218 14210 7214 14210 7214 14211 7218 14211 7220 14211 7214 14212 7220 14212 7221 14212 7221 14213 7220 14213 7202 14213 7221 14214 7202 14214 7210 14214 7210 14215 7202 14215 7222 14215 7216 14216 7208 14216 7222 14216 7222 14217 7208 14217 7210 14217 7230 14218 7223 14218 7224 14218 7224 14219 7223 14219 7225 14219 7224 14220 7225 14220 7203 14220 7203 14221 7225 14221 7226 14221 7203 14222 7226 14222 7204 14222 7204 14223 7226 14223 7211 14223 7212 14224 7205 14224 7227 14224 7227 14225 7205 14225 7199 14225 7227 14226 7199 14226 7228 14226 7228 14227 7199 14227 7198 14227 7228 14228 7198 14228 7213 14228 7213 14229 7198 14229 7229 14229 7204 14230 7211 14230 7229 14230 7229 14231 7211 14231 7213 14231 7200 14232 7206 14232 7230 14232 7230 14233 7206 14233 7223 14233 7205 14234 7212 14234 7201 14234 7201 14235 7212 14235 7209 14235 7236 14236 7231 14236 7264 14236 7232 14237 7245 14237 7231 14237 7231 14238 7245 14238 7233 14238 7231 14239 7233 14239 7252 14239 7250 14240 7264 14240 7234 14240 7234 14241 7264 14241 7231 14241 7234 14242 7231 14242 7251 14242 7251 14243 7231 14243 7252 14243 7264 14244 7235 14244 7236 14244 7236 14245 7235 14245 7237 14245 7236 14246 7237 14246 7256 14246 7262 14247 7259 14247 7263 14247 7263 14248 7259 14248 7236 14248 7263 14249 7236 14249 7238 14249 7238 14250 7236 14250 7256 14250 7248 14251 7244 14251 7239 14251 7239 14252 7244 14252 7258 14252 7247 14253 7246 14253 7253 14253 7253 14254 7246 14254 7244 14254 7253 14255 7244 14255 7254 14255 7254 14256 7244 14256 7240 14256 7241 14257 7260 14257 7258 14257 7258 14258 7260 14258 7261 14258 7255 14259 7239 14259 7257 14259 7257 14260 7239 14260 7258 14260 7257 14261 7258 14261 7242 14261 7242 14262 7258 14262 7261 14262 7248 14263 7249 14263 7244 14263 7244 14264 7249 14264 7243 14264 7244 14265 7243 14265 7240 14265 7231 14266 7244 14266 7232 14266 7232 14267 7244 14267 7246 14267 7232 14268 7246 14268 7245 14268 7245 14269 7246 14269 7247 14269 7245 14270 7247 14270 7233 14270 7233 14271 7247 14271 7253 14271 7248 14272 7264 14272 7249 14272 7249 14273 7264 14273 7250 14273 7249 14274 7250 14274 7243 14274 7243 14275 7250 14275 7234 14275 7243 14276 7234 14276 7240 14276 7240 14277 7234 14277 7251 14277 7240 14278 7251 14278 7254 14278 7254 14279 7251 14279 7252 14279 7233 14280 7253 14280 7252 14280 7252 14281 7253 14281 7254 14281 7235 14282 7239 14282 7237 14282 7237 14283 7239 14283 7255 14283 7237 14284 7255 14284 7256 14284 7256 14285 7255 14285 7257 14285 7256 14286 7257 14286 7238 14286 7238 14287 7257 14287 7242 14287 7258 14288 7236 14288 7241 14288 7241 14289 7236 14289 7259 14289 7241 14290 7259 14290 7260 14290 7260 14291 7259 14291 7262 14291 7260 14292 7262 14292 7261 14292 7261 14293 7262 14293 7263 14293 7238 14294 7242 14294 7263 14294 7263 14295 7242 14295 7261 14295 7264 14296 7248 14296 7235 14296 7235 14297 7248 14297 7239 14297 7236 14298 7258 14298 7231 14298 7231 14299 7258 14299 7244 14299 7298 14300 7276 14300 7278 14300 7265 14301 7292 14301 7286 14301 7286 14302 7292 14302 7298 14302 7286 14303 7298 14303 7280 14303 7280 14304 7298 14304 7278 14304 7266 14305 7284 14305 7286 14305 7286 14306 7284 14306 7281 14306 7286 14307 7281 14307 7265 14307 7265 14308 7297 14308 7292 14308 7292 14309 7297 14309 7287 14309 7292 14310 7287 14310 7288 14310 7293 14311 7267 14311 7268 14311 7268 14312 7267 14312 7292 14312 7268 14313 7292 14313 7295 14313 7295 14314 7292 14314 7288 14314 7272 14315 7269 14315 7270 14315 7279 14316 7277 14316 7271 14316 7271 14317 7277 14317 7272 14317 7271 14318 7272 14318 7285 14318 7285 14319 7272 14319 7275 14319 7291 14320 7294 14320 7269 14320 7269 14321 7294 14321 7273 14321 7269 14322 7273 14322 7274 14322 7274 14323 7290 14323 7269 14323 7269 14324 7290 14324 7289 14324 7269 14325 7289 14325 7270 14325 7283 14326 7275 14326 7282 14326 7282 14327 7275 14327 7272 14327 7282 14328 7272 14328 7296 14328 7296 14329 7272 14329 7270 14329 7298 14330 7272 14330 7276 14330 7276 14331 7272 14331 7277 14331 7276 14332 7277 14332 7278 14332 7278 14333 7277 14333 7279 14333 7278 14334 7279 14334 7280 14334 7280 14335 7279 14335 7271 14335 7296 14336 7265 14336 7282 14336 7282 14337 7265 14337 7281 14337 7282 14338 7281 14338 7283 14338 7283 14339 7281 14339 7284 14339 7283 14340 7284 14340 7275 14340 7275 14341 7284 14341 7266 14341 7275 14342 7266 14342 7285 14342 7285 14343 7266 14343 7286 14343 7280 14344 7271 14344 7286 14344 7286 14345 7271 14345 7285 14345 7297 14346 7270 14346 7287 14346 7287 14347 7270 14347 7289 14347 7287 14348 7289 14348 7288 14348 7288 14349 7289 14349 7290 14349 7288 14350 7290 14350 7295 14350 7295 14351 7290 14351 7274 14351 7269 14352 7292 14352 7291 14352 7291 14353 7292 14353 7267 14353 7291 14354 7267 14354 7294 14354 7294 14355 7267 14355 7293 14355 7294 14356 7293 14356 7273 14356 7273 14357 7293 14357 7268 14357 7295 14358 7274 14358 7268 14358 7268 14359 7274 14359 7273 14359 7265 14360 7296 14360 7297 14360 7297 14361 7296 14361 7270 14361 7292 14362 7269 14362 7298 14362 7298 14363 7269 14363 7272 14363 7299 14364 7300 14364 7332 14364 7332 14365 7300 14365 7301 14365 7332 14366 7301 14366 7322 14366 7324 14367 7326 14367 7323 14367 7323 14368 7326 14368 7302 14368 7305 14369 7329 14369 7304 14369 7319 14370 7331 14370 7303 14370 7303 14371 7331 14371 7332 14371 7303 14372 7332 14372 7321 14372 7321 14373 7332 14373 7322 14373 7304 14374 7328 14374 7305 14374 7305 14375 7328 14375 7332 14375 7305 14376 7332 14376 7302 14376 7302 14377 7332 14377 7331 14377 7302 14378 7331 14378 7323 14378 7306 14379 7307 14379 7308 14379 7327 14380 7325 14380 7330 14380 7330 14381 7325 14381 7316 14381 7317 14382 7309 14382 7318 14382 7318 14383 7309 14383 7315 14383 7318 14384 7315 14384 7310 14384 7310 14385 7315 14385 7313 14385 7316 14386 7315 14386 7330 14386 7330 14387 7315 14387 7306 14387 7330 14388 7306 14388 7311 14388 7311 14389 7306 14389 7308 14389 7320 14390 7313 14390 7312 14390 7312 14391 7313 14391 7315 14391 7312 14392 7315 14392 7314 14392 7314 14393 7315 14393 7316 14393 7332 14394 7315 14394 7299 14394 7299 14395 7315 14395 7309 14395 7299 14396 7309 14396 7300 14396 7300 14397 7309 14397 7317 14397 7300 14398 7317 14398 7301 14398 7301 14399 7317 14399 7318 14399 7314 14400 7331 14400 7312 14400 7312 14401 7331 14401 7319 14401 7312 14402 7319 14402 7320 14402 7320 14403 7319 14403 7303 14403 7320 14404 7303 14404 7313 14404 7313 14405 7303 14405 7321 14405 7313 14406 7321 14406 7310 14406 7310 14407 7321 14407 7322 14407 7301 14408 7318 14408 7322 14408 7322 14409 7318 14409 7310 14409 7323 14410 7316 14410 7324 14410 7324 14411 7316 14411 7325 14411 7324 14412 7325 14412 7326 14412 7326 14413 7325 14413 7327 14413 7326 14414 7327 14414 7302 14414 7302 14415 7327 14415 7330 14415 7306 14416 7328 14416 7307 14416 7307 14417 7328 14417 7304 14417 7307 14418 7304 14418 7308 14418 7308 14419 7304 14419 7329 14419 7308 14420 7329 14420 7311 14420 7311 14421 7329 14421 7305 14421 7302 14422 7330 14422 7305 14422 7305 14423 7330 14423 7311 14423 7331 14424 7314 14424 7323 14424 7323 14425 7314 14425 7316 14425 7328 14426 7306 14426 7332 14426 7332 14427 7306 14427 7315 14427 7351 14428 7352 14428 7366 14428 7366 14429 7352 14429 7355 14429 7366 14430 7355 14430 7333 14430 7357 14431 7356 14431 7334 14431 7334 14432 7356 14432 7366 14432 7334 14433 7366 14433 7335 14433 7335 14434 7366 14434 7333 14434 7336 14435 7360 14435 7337 14435 7337 14436 7360 14436 7340 14436 7364 14437 7338 14437 7339 14437 7339 14438 7362 14438 7364 14438 7364 14439 7362 14439 7366 14439 7364 14440 7366 14440 7340 14440 7340 14441 7366 14441 7356 14441 7340 14442 7356 14442 7337 14442 7361 14443 7341 14443 7349 14443 7342 14444 7343 14444 7344 14444 7354 14445 7353 14445 7345 14445 7345 14446 7353 14446 7344 14446 7345 14447 7344 14447 7359 14447 7359 14448 7344 14448 7343 14448 7359 14449 7343 14449 7358 14449 7363 14450 7346 14450 7347 14450 7347 14451 7346 14451 7365 14451 7347 14452 7365 14452 7348 14452 7348 14453 7361 14453 7347 14453 7347 14454 7361 14454 7349 14454 7347 14455 7349 14455 7344 14455 7344 14456 7349 14456 7350 14456 7344 14457 7350 14457 7342 14457 7366 14458 7344 14458 7351 14458 7351 14459 7344 14459 7353 14459 7351 14460 7353 14460 7352 14460 7352 14461 7353 14461 7354 14461 7352 14462 7354 14462 7355 14462 7355 14463 7354 14463 7345 14463 7350 14464 7356 14464 7342 14464 7342 14465 7356 14465 7357 14465 7342 14466 7357 14466 7343 14466 7343 14467 7357 14467 7334 14467 7343 14468 7334 14468 7358 14468 7358 14469 7334 14469 7335 14469 7358 14470 7335 14470 7359 14470 7359 14471 7335 14471 7333 14471 7355 14472 7345 14472 7333 14472 7333 14473 7345 14473 7359 14473 7337 14474 7349 14474 7336 14474 7336 14475 7349 14475 7341 14475 7336 14476 7341 14476 7360 14476 7360 14477 7341 14477 7361 14477 7360 14478 7361 14478 7340 14478 7340 14479 7361 14479 7348 14479 7347 14480 7362 14480 7363 14480 7363 14481 7362 14481 7339 14481 7363 14482 7339 14482 7346 14482 7346 14483 7339 14483 7338 14483 7346 14484 7338 14484 7365 14484 7365 14485 7338 14485 7364 14485 7340 14486 7348 14486 7364 14486 7364 14487 7348 14487 7365 14487 7356 14488 7350 14488 7337 14488 7337 14489 7350 14489 7349 14489 7362 14490 7347 14490 7366 14490 7366 14491 7347 14491 7344 14491 7367 14492 7368 14492 7373 14492 7373 14493 7368 14493 7381 14493 7373 14494 7381 14494 7387 14494 7388 14495 7389 14495 7397 14495 7397 14496 7389 14496 7372 14496 7395 14497 7394 14497 7393 14497 7369 14498 7382 14498 7370 14498 7370 14499 7382 14499 7373 14499 7370 14500 7373 14500 7371 14500 7371 14501 7373 14501 7387 14501 7393 14502 7392 14502 7395 14502 7395 14503 7392 14503 7373 14503 7395 14504 7373 14504 7372 14504 7372 14505 7373 14505 7382 14505 7372 14506 7382 14506 7397 14506 7377 14507 7400 14507 7399 14507 7374 14508 7376 14508 7375 14508 7375 14509 7376 14509 7377 14509 7375 14510 7377 14510 7386 14510 7386 14511 7377 14511 7385 14511 7391 14512 7378 14512 7400 14512 7400 14513 7378 14513 7379 14513 7380 14514 7399 14514 7390 14514 7390 14515 7399 14515 7400 14515 7390 14516 7400 14516 7396 14516 7396 14517 7400 14517 7379 14517 7384 14518 7385 14518 7383 14518 7383 14519 7385 14519 7377 14519 7383 14520 7377 14520 7398 14520 7398 14521 7377 14521 7399 14521 7373 14522 7377 14522 7367 14522 7367 14523 7377 14523 7376 14523 7367 14524 7376 14524 7368 14524 7368 14525 7376 14525 7374 14525 7368 14526 7374 14526 7381 14526 7381 14527 7374 14527 7375 14527 7398 14528 7382 14528 7383 14528 7383 14529 7382 14529 7369 14529 7383 14530 7369 14530 7384 14530 7384 14531 7369 14531 7370 14531 7384 14532 7370 14532 7385 14532 7385 14533 7370 14533 7371 14533 7385 14534 7371 14534 7386 14534 7386 14535 7371 14535 7387 14535 7381 14536 7375 14536 7387 14536 7387 14537 7375 14537 7386 14537 7397 14538 7399 14538 7388 14538 7388 14539 7399 14539 7380 14539 7388 14540 7380 14540 7389 14540 7389 14541 7380 14541 7390 14541 7389 14542 7390 14542 7372 14542 7372 14543 7390 14543 7396 14543 7400 14544 7392 14544 7391 14544 7391 14545 7392 14545 7393 14545 7391 14546 7393 14546 7378 14546 7378 14547 7393 14547 7394 14547 7378 14548 7394 14548 7379 14548 7379 14549 7394 14549 7395 14549 7372 14550 7396 14550 7395 14550 7395 14551 7396 14551 7379 14551 7382 14552 7398 14552 7397 14552 7397 14553 7398 14553 7399 14553 7392 14554 7400 14554 7373 14554 7373 14555 7400 14555 7377 14555 7417 14556 7418 14556 7401 14556 7401 14557 7418 14557 7420 14557 7401 14558 7420 14558 7425 14558 7423 14559 7408 14559 7402 14559 7402 14560 7408 14560 7401 14560 7402 14561 7401 14561 7403 14561 7403 14562 7401 14562 7425 14562 7427 14563 7429 14563 7426 14563 7426 14564 7429 14564 7404 14564 7405 14565 7433 14565 7406 14565 7406 14566 7407 14566 7405 14566 7405 14567 7407 14567 7401 14567 7405 14568 7401 14568 7404 14568 7404 14569 7401 14569 7408 14569 7404 14570 7408 14570 7426 14570 7422 14571 7424 14571 7409 14571 7421 14572 7419 14572 7410 14572 7410 14573 7419 14573 7411 14573 7410 14574 7411 14574 7409 14574 7409 14575 7411 14575 7412 14575 7412 14576 7413 14576 7428 14576 7430 14577 7431 14577 7412 14577 7412 14578 7431 14578 7432 14578 7412 14579 7432 14579 7413 14579 7414 14580 7422 14580 7415 14580 7415 14581 7422 14581 7409 14581 7415 14582 7409 14582 7434 14582 7434 14583 7409 14583 7412 14583 7434 14584 7412 14584 7416 14584 7416 14585 7412 14585 7428 14585 7401 14586 7411 14586 7417 14586 7417 14587 7411 14587 7419 14587 7417 14588 7419 14588 7418 14588 7418 14589 7419 14589 7421 14589 7418 14590 7421 14590 7420 14590 7420 14591 7421 14591 7410 14591 7415 14592 7408 14592 7414 14592 7414 14593 7408 14593 7423 14593 7414 14594 7423 14594 7422 14594 7422 14595 7423 14595 7402 14595 7422 14596 7402 14596 7424 14596 7424 14597 7402 14597 7403 14597 7424 14598 7403 14598 7409 14598 7409 14599 7403 14599 7425 14599 7420 14600 7410 14600 7425 14600 7425 14601 7410 14601 7409 14601 7426 14602 7434 14602 7427 14602 7427 14603 7434 14603 7416 14603 7427 14604 7416 14604 7429 14604 7429 14605 7416 14605 7428 14605 7429 14606 7428 14606 7404 14606 7404 14607 7428 14607 7413 14607 7412 14608 7407 14608 7430 14608 7430 14609 7407 14609 7406 14609 7430 14610 7406 14610 7431 14610 7431 14611 7406 14611 7433 14611 7431 14612 7433 14612 7432 14612 7432 14613 7433 14613 7405 14613 7404 14614 7413 14614 7405 14614 7405 14615 7413 14615 7432 14615 7408 14616 7415 14616 7426 14616 7426 14617 7415 14617 7434 14617 7407 14618 7412 14618 7401 14618 7401 14619 7412 14619 7411 14619 7438 14620 7463 14620 7435 14620 7438 14621 7457 14621 7455 14621 7436 14622 7437 14622 7435 14622 7435 14623 7437 14623 7452 14623 7435 14624 7452 14624 7438 14624 7455 14625 7453 14625 7438 14625 7438 14626 7453 14626 7467 14626 7438 14627 7467 14627 7463 14627 7463 14628 7467 14628 7459 14628 7463 14629 7459 14629 7460 14629 7465 14630 7439 14630 7466 14630 7466 14631 7439 14631 7463 14631 7466 14632 7463 14632 7440 14632 7440 14633 7463 14633 7460 14633 7440 14634 7460 14634 7441 14634 7468 14635 7442 14635 7449 14635 7442 14636 7468 14636 7443 14636 7443 14637 7468 14637 7444 14637 7443 14638 7444 14638 7462 14638 7451 14639 7450 14639 7445 14639 7445 14640 7450 14640 7468 14640 7445 14641 7468 14641 7458 14641 7446 14642 7461 14642 7447 14642 7447 14643 7461 14643 7443 14643 7447 14644 7443 14644 7448 14644 7448 14645 7443 14645 7462 14645 7448 14646 7462 14646 7464 14646 7449 14647 7454 14647 7468 14647 7468 14648 7454 14648 7456 14648 7468 14649 7456 14649 7458 14649 7435 14650 7468 14650 7436 14650 7436 14651 7468 14651 7450 14651 7436 14652 7450 14652 7437 14652 7437 14653 7450 14653 7451 14653 7437 14654 7451 14654 7452 14654 7452 14655 7451 14655 7445 14655 7442 14656 7467 14656 7449 14656 7449 14657 7467 14657 7453 14657 7449 14658 7453 14658 7454 14658 7454 14659 7453 14659 7455 14659 7454 14660 7455 14660 7456 14660 7456 14661 7455 14661 7457 14661 7456 14662 7457 14662 7458 14662 7458 14663 7457 14663 7438 14663 7452 14664 7445 14664 7438 14664 7438 14665 7445 14665 7458 14665 7459 14666 7443 14666 7460 14666 7460 14667 7443 14667 7461 14667 7460 14668 7461 14668 7441 14668 7441 14669 7461 14669 7446 14669 7441 14670 7446 14670 7440 14670 7440 14671 7446 14671 7447 14671 7444 14672 7463 14672 7462 14672 7462 14673 7463 14673 7439 14673 7462 14674 7439 14674 7464 14674 7464 14675 7439 14675 7465 14675 7464 14676 7465 14676 7448 14676 7448 14677 7465 14677 7466 14677 7440 14678 7447 14678 7466 14678 7466 14679 7447 14679 7448 14679 7467 14680 7442 14680 7459 14680 7459 14681 7442 14681 7443 14681 7463 14682 7444 14682 7435 14682 7435 14683 7444 14683 7468 14683 7475 14684 7469 14684 7473 14684 7487 14685 7488 14685 7469 14685 7469 14686 7488 14686 7470 14686 7469 14687 7470 14687 7472 14687 7492 14688 7473 14688 7495 14688 7495 14689 7473 14689 7469 14689 7495 14690 7469 14690 7471 14690 7471 14691 7469 14691 7472 14691 7473 14692 7474 14692 7475 14692 7475 14693 7474 14693 7496 14693 7475 14694 7496 14694 7476 14694 7498 14695 7477 14695 7500 14695 7500 14696 7477 14696 7475 14696 7500 14697 7475 14697 7499 14697 7499 14698 7475 14698 7476 14698 7501 14699 7491 14699 7479 14699 7484 14700 7497 14700 7485 14700 7478 14701 7479 14701 7494 14701 7494 14702 7479 14702 7491 14702 7494 14703 7491 14703 7493 14703 7489 14704 7486 14704 7490 14704 7490 14705 7486 14705 7502 14705 7490 14706 7502 14706 7479 14706 7479 14707 7502 14707 7483 14707 7480 14708 7481 14708 7483 14708 7483 14709 7481 14709 7482 14709 7483 14710 7482 14710 7479 14710 7479 14711 7482 14711 7484 14711 7479 14712 7484 14712 7501 14712 7501 14713 7484 14713 7485 14713 7469 14714 7502 14714 7487 14714 7487 14715 7502 14715 7486 14715 7487 14716 7486 14716 7488 14716 7488 14717 7486 14717 7489 14717 7488 14718 7489 14718 7470 14718 7470 14719 7489 14719 7490 14719 7491 14720 7473 14720 7493 14720 7493 14721 7473 14721 7492 14721 7493 14722 7492 14722 7494 14722 7494 14723 7492 14723 7495 14723 7494 14724 7495 14724 7478 14724 7478 14725 7495 14725 7471 14725 7478 14726 7471 14726 7479 14726 7479 14727 7471 14727 7472 14727 7470 14728 7490 14728 7472 14728 7472 14729 7490 14729 7479 14729 7474 14730 7501 14730 7496 14730 7496 14731 7501 14731 7485 14731 7496 14732 7485 14732 7476 14732 7476 14733 7485 14733 7497 14733 7476 14734 7497 14734 7499 14734 7499 14735 7497 14735 7484 14735 7483 14736 7475 14736 7480 14736 7480 14737 7475 14737 7477 14737 7480 14738 7477 14738 7481 14738 7481 14739 7477 14739 7498 14739 7481 14740 7498 14740 7482 14740 7482 14741 7498 14741 7500 14741 7499 14742 7484 14742 7500 14742 7500 14743 7484 14743 7482 14743 7473 14744 7491 14744 7474 14744 7474 14745 7491 14745 7501 14745 7475 14746 7483 14746 7469 14746 7469 14747 7483 14747 7502 14747 7516 14748 7519 14748 7515 14748 7515 14749 7519 14749 7503 14749 7515 14750 7503 14750 7507 14750 7507 14751 7503 14751 7525 14751 7507 14752 7525 14752 7535 14752 7524 14753 7504 14753 7525 14753 7525 14754 7504 14754 7521 14754 7525 14755 7521 14755 7535 14755 7535 14756 7527 14756 7507 14756 7507 14757 7527 14757 7505 14757 7507 14758 7505 14758 7528 14758 7533 14759 7506 14759 7508 14759 7508 14760 7506 14760 7507 14760 7508 14761 7507 14761 7529 14761 7529 14762 7507 14762 7528 14762 7511 14763 7509 14763 7530 14763 7518 14764 7517 14764 7526 14764 7526 14765 7517 14765 7536 14765 7526 14766 7536 14766 7523 14766 7531 14767 7532 14767 7511 14767 7511 14768 7532 14768 7534 14768 7511 14769 7534 14769 7509 14769 7530 14770 7510 14770 7511 14770 7511 14771 7510 14771 7512 14771 7511 14772 7512 14772 7536 14772 7536 14773 7512 14773 7513 14773 7536 14774 7513 14774 7520 14774 7520 14775 7522 14775 7536 14775 7536 14776 7522 14776 7514 14776 7536 14777 7514 14777 7523 14777 7515 14778 7536 14778 7516 14778 7516 14779 7536 14779 7517 14779 7516 14780 7517 14780 7519 14780 7519 14781 7517 14781 7518 14781 7519 14782 7518 14782 7503 14782 7503 14783 7518 14783 7526 14783 7513 14784 7535 14784 7520 14784 7520 14785 7535 14785 7521 14785 7520 14786 7521 14786 7522 14786 7522 14787 7521 14787 7504 14787 7522 14788 7504 14788 7514 14788 7514 14789 7504 14789 7524 14789 7514 14790 7524 14790 7523 14790 7523 14791 7524 14791 7525 14791 7503 14792 7526 14792 7525 14792 7525 14793 7526 14793 7523 14793 7527 14794 7512 14794 7505 14794 7505 14795 7512 14795 7510 14795 7505 14796 7510 14796 7528 14796 7528 14797 7510 14797 7530 14797 7528 14798 7530 14798 7529 14798 7529 14799 7530 14799 7509 14799 7511 14800 7507 14800 7531 14800 7531 14801 7507 14801 7506 14801 7531 14802 7506 14802 7532 14802 7532 14803 7506 14803 7533 14803 7532 14804 7533 14804 7534 14804 7534 14805 7533 14805 7508 14805 7529 14806 7509 14806 7508 14806 7508 14807 7509 14807 7534 14807 7535 14808 7513 14808 7527 14808 7527 14809 7513 14809 7512 14809 7507 14810 7511 14810 7515 14810 7515 14811 7511 14811 7536 14811 7554 14812 7537 14812 7544 14812 7544 14813 7537 14813 7562 14813 7544 14814 7562 14814 7538 14814 7556 14815 7539 14815 7544 14815 7544 14816 7539 14816 7555 14816 7544 14817 7555 14817 7554 14817 7540 14818 7541 14818 7544 14818 7544 14819 7541 14819 7542 14819 7544 14820 7542 14820 7556 14820 7538 14821 7543 14821 7544 14821 7544 14822 7543 14822 7559 14822 7544 14823 7559 14823 7540 14823 7545 14824 7546 14824 7548 14824 7561 14825 7546 14825 7545 14825 7545 14826 7547 14826 7557 14826 7549 14827 7547 14827 7545 14827 7548 14828 7549 14828 7545 14828 7545 14829 7550 14829 7553 14829 7558 14830 7550 14830 7545 14830 7557 14831 7558 14831 7545 14831 7545 14832 7552 14832 7560 14832 7551 14833 7552 14833 7545 14833 7553 14834 7551 14834 7545 14834 7560 14835 7561 14835 7545 14835 7561 14836 7562 14836 7546 14836 7546 14837 7562 14837 7537 14837 7546 14838 7537 14838 7548 14838 7548 14839 7537 14839 7554 14839 7548 14840 7554 14840 7549 14840 7549 14841 7554 14841 7555 14841 7549 14842 7555 14842 7547 14842 7547 14843 7555 14843 7539 14843 7547 14844 7539 14844 7557 14844 7557 14845 7539 14845 7556 14845 7557 14846 7556 14846 7558 14846 7558 14847 7556 14847 7542 14847 7558 14848 7542 14848 7550 14848 7550 14849 7542 14849 7541 14849 7550 14850 7541 14850 7553 14850 7553 14851 7541 14851 7540 14851 7553 14852 7540 14852 7551 14852 7551 14853 7540 14853 7559 14853 7551 14854 7559 14854 7552 14854 7552 14855 7559 14855 7543 14855 7552 14856 7543 14856 7560 14856 7560 14857 7543 14857 7538 14857 7560 14858 7538 14858 7561 14858 7561 14859 7538 14859 7562 14859 7577 14860 7576 14860 7565 14860 7565 14861 7576 14861 7575 14861 7565 14862 7575 14862 7566 14862 7563 14863 7564 14863 7565 14863 7565 14864 7564 14864 7578 14864 7565 14865 7578 14865 7577 14865 7584 14866 7581 14866 7565 14866 7565 14867 7581 14867 7579 14867 7565 14868 7579 14868 7563 14868 7566 14869 7588 14869 7565 14869 7565 14870 7588 14870 7585 14870 7565 14871 7585 14871 7584 14871 7573 14872 7567 14872 7568 14872 7574 14873 7567 14873 7573 14873 7573 14874 7569 14874 7572 14874 7570 14875 7569 14875 7573 14875 7568 14876 7570 14876 7573 14876 7573 14877 7580 14877 7582 14877 7571 14878 7580 14878 7573 14878 7572 14879 7571 14879 7573 14879 7573 14880 7586 14880 7587 14880 7583 14881 7586 14881 7573 14881 7582 14882 7583 14882 7573 14882 7587 14883 7574 14883 7573 14883 7574 14884 7575 14884 7567 14884 7567 14885 7575 14885 7576 14885 7567 14886 7576 14886 7568 14886 7568 14887 7576 14887 7577 14887 7568 14888 7577 14888 7570 14888 7570 14889 7577 14889 7578 14889 7570 14890 7578 14890 7569 14890 7569 14891 7578 14891 7564 14891 7569 14892 7564 14892 7572 14892 7572 14893 7564 14893 7563 14893 7572 14894 7563 14894 7571 14894 7571 14895 7563 14895 7579 14895 7571 14896 7579 14896 7580 14896 7580 14897 7579 14897 7581 14897 7580 14898 7581 14898 7582 14898 7582 14899 7581 14899 7584 14899 7582 14900 7584 14900 7583 14900 7583 14901 7584 14901 7585 14901 7583 14902 7585 14902 7586 14902 7586 14903 7585 14903 7588 14903 7586 14904 7588 14904 7587 14904 7587 14905 7588 14905 7566 14905 7587 14906 7566 14906 7574 14906 7574 14907 7566 14907 7575 14907 7589 14908 7605 14908 7592 14908 7592 14909 7605 14909 7590 14909 7592 14910 7590 14910 7613 14910 7595 14911 7591 14911 7592 14911 7592 14912 7591 14912 7607 14912 7592 14913 7607 14913 7589 14913 7610 14914 7593 14914 7592 14914 7592 14915 7593 14915 7594 14915 7592 14916 7594 14916 7595 14916 7613 14917 7612 14917 7592 14917 7592 14918 7612 14918 7611 14918 7592 14919 7611 14919 7610 14919 7596 14920 7604 14920 7598 14920 7614 14921 7604 14921 7596 14921 7596 14922 7597 14922 7608 14922 7606 14923 7597 14923 7596 14923 7598 14924 7606 14924 7596 14924 7596 14925 7599 14925 7601 14925 7609 14926 7599 14926 7596 14926 7608 14927 7609 14927 7596 14927 7596 14928 7600 14928 7603 14928 7602 14929 7600 14929 7596 14929 7601 14930 7602 14930 7596 14930 7603 14931 7614 14931 7596 14931 7614 14932 7590 14932 7604 14932 7604 14933 7590 14933 7605 14933 7604 14934 7605 14934 7598 14934 7598 14935 7605 14935 7589 14935 7598 14936 7589 14936 7606 14936 7606 14937 7589 14937 7607 14937 7606 14938 7607 14938 7597 14938 7597 14939 7607 14939 7591 14939 7597 14940 7591 14940 7608 14940 7608 14941 7591 14941 7595 14941 7608 14942 7595 14942 7609 14942 7609 14943 7595 14943 7594 14943 7609 14944 7594 14944 7599 14944 7599 14945 7594 14945 7593 14945 7599 14946 7593 14946 7601 14946 7601 14947 7593 14947 7610 14947 7601 14948 7610 14948 7602 14948 7602 14949 7610 14949 7611 14949 7602 14950 7611 14950 7600 14950 7600 14951 7611 14951 7612 14951 7600 14952 7612 14952 7603 14952 7603 14953 7612 14953 7613 14953 7603 14954 7613 14954 7614 14954 7614 14955 7613 14955 7590 14955 7615 14956 7632 14956 7620 14956 7620 14957 7632 14957 7616 14957 7620 14958 7616 14958 7622 14958 7635 14959 7617 14959 7620 14959 7620 14960 7617 14960 7618 14960 7620 14961 7618 14961 7615 14961 7619 14962 7621 14962 7620 14962 7620 14963 7621 14963 7637 14963 7620 14964 7637 14964 7635 14964 7622 14965 7640 14965 7620 14965 7620 14966 7640 14966 7623 14966 7620 14967 7623 14967 7619 14967 7626 14968 7624 14968 7631 14968 7630 14969 7624 14969 7626 14969 7626 14970 7634 14970 7625 14970 7633 14971 7634 14971 7626 14971 7631 14972 7633 14972 7626 14972 7626 14973 7638 14973 7639 14973 7636 14974 7638 14974 7626 14974 7625 14975 7636 14975 7626 14975 7626 14976 7629 14976 7627 14976 7628 14977 7629 14977 7626 14977 7639 14978 7628 14978 7626 14978 7627 14979 7630 14979 7626 14979 7630 14980 7616 14980 7624 14980 7624 14981 7616 14981 7632 14981 7624 14982 7632 14982 7631 14982 7631 14983 7632 14983 7615 14983 7631 14984 7615 14984 7633 14984 7633 14985 7615 14985 7618 14985 7633 14986 7618 14986 7634 14986 7634 14987 7618 14987 7617 14987 7634 14988 7617 14988 7625 14988 7625 14989 7617 14989 7635 14989 7625 14990 7635 14990 7636 14990 7636 14991 7635 14991 7637 14991 7636 14992 7637 14992 7638 14992 7638 14993 7637 14993 7621 14993 7638 14994 7621 14994 7639 14994 7639 14995 7621 14995 7619 14995 7639 14996 7619 14996 7628 14996 7628 14997 7619 14997 7623 14997 7628 14998 7623 14998 7629 14998 7629 14999 7623 14999 7640 14999 7629 15000 7640 15000 7627 15000 7627 15001 7640 15001 7622 15001 7627 15002 7622 15002 7630 15002 7630 15003 7622 15003 7616 15003 7641 15004 7643 15004 7642 15004 7642 15005 7643 15005 7666 15005 7642 15006 7666 15006 7644 15006 7647 15007 7645 15007 7642 15007 7642 15008 7645 15008 7646 15008 7642 15009 7646 15009 7641 15009 7660 15010 7659 15010 7642 15010 7642 15011 7659 15011 7658 15011 7642 15012 7658 15012 7647 15012 7644 15013 7664 15013 7642 15013 7642 15014 7664 15014 7661 15014 7642 15015 7661 15015 7660 15015 7651 15016 7653 15016 7654 15016 7665 15017 7653 15017 7651 15017 7651 15018 7655 15018 7656 15018 7648 15019 7655 15019 7651 15019 7654 15020 7648 15020 7651 15020 7651 15021 7649 15021 7650 15021 7657 15022 7649 15022 7651 15022 7656 15023 7657 15023 7651 15023 7651 15024 7662 15024 7663 15024 7652 15025 7662 15025 7651 15025 7650 15026 7652 15026 7651 15026 7663 15027 7665 15027 7651 15027 7665 15028 7666 15028 7653 15028 7653 15029 7666 15029 7643 15029 7653 15030 7643 15030 7654 15030 7654 15031 7643 15031 7641 15031 7654 15032 7641 15032 7648 15032 7648 15033 7641 15033 7646 15033 7648 15034 7646 15034 7655 15034 7655 15035 7646 15035 7645 15035 7655 15036 7645 15036 7656 15036 7656 15037 7645 15037 7647 15037 7656 15038 7647 15038 7657 15038 7657 15039 7647 15039 7658 15039 7657 15040 7658 15040 7649 15040 7649 15041 7658 15041 7659 15041 7649 15042 7659 15042 7650 15042 7650 15043 7659 15043 7660 15043 7650 15044 7660 15044 7652 15044 7652 15045 7660 15045 7661 15045 7652 15046 7661 15046 7662 15046 7662 15047 7661 15047 7664 15047 7662 15048 7664 15048 7663 15048 7663 15049 7664 15049 7644 15049 7663 15050 7644 15050 7665 15050 7665 15051 7644 15051 7666 15051 7678 15052 7667 15052 7668 15052 7668 15053 7667 15053 7675 15053 7668 15054 7675 15054 7691 15054 7684 15055 7681 15055 7668 15055 7668 15056 7681 15056 7680 15056 7668 15057 7680 15057 7678 15057 7687 15058 7686 15058 7668 15058 7668 15059 7686 15059 7685 15059 7668 15060 7685 15060 7684 15060 7691 15061 7689 15061 7668 15061 7668 15062 7689 15062 7669 15062 7668 15063 7669 15063 7687 15063 7671 15064 7676 15064 7677 15064 7692 15065 7676 15065 7671 15065 7671 15066 7670 15066 7682 15066 7679 15067 7670 15067 7671 15067 7677 15068 7679 15068 7671 15068 7671 15069 7672 15069 7674 15069 7683 15070 7672 15070 7671 15070 7682 15071 7683 15071 7671 15071 7671 15072 7673 15072 7690 15072 7688 15073 7673 15073 7671 15073 7674 15074 7688 15074 7671 15074 7690 15075 7692 15075 7671 15075 7692 15076 7675 15076 7676 15076 7676 15077 7675 15077 7667 15077 7676 15078 7667 15078 7677 15078 7677 15079 7667 15079 7678 15079 7677 15080 7678 15080 7679 15080 7679 15081 7678 15081 7680 15081 7679 15082 7680 15082 7670 15082 7670 15083 7680 15083 7681 15083 7670 15084 7681 15084 7682 15084 7682 15085 7681 15085 7684 15085 7682 15086 7684 15086 7683 15086 7683 15087 7684 15087 7685 15087 7683 15088 7685 15088 7672 15088 7672 15089 7685 15089 7686 15089 7672 15090 7686 15090 7674 15090 7674 15091 7686 15091 7687 15091 7674 15092 7687 15092 7688 15092 7688 15093 7687 15093 7669 15093 7688 15094 7669 15094 7673 15094 7673 15095 7669 15095 7689 15095 7673 15096 7689 15096 7690 15096 7690 15097 7689 15097 7691 15097 7690 15098 7691 15098 7692 15098 7692 15099 7691 15099 7675 15099 7696 15100 7697 15100 7724 15100 7693 15101 7720 15101 7724 15101 7724 15102 7720 15102 7723 15102 7724 15103 7723 15103 7696 15103 7721 15104 7695 15104 7694 15104 7694 15105 7695 15105 7725 15105 7694 15106 7725 15106 7696 15106 7696 15107 7725 15107 7697 15107 7697 15108 7725 15108 7726 15108 7697 15109 7726 15109 7700 15109 7715 15110 7698 15110 7717 15110 7717 15111 7698 15111 7697 15111 7717 15112 7697 15112 7699 15112 7699 15113 7697 15113 7700 15113 7699 15114 7700 15114 7701 15114 7710 15115 7713 15115 7714 15115 7712 15116 7706 15116 7703 15116 7702 15117 7719 15117 7704 15117 7704 15118 7719 15118 7703 15118 7704 15119 7703 15119 7705 15119 7705 15120 7703 15120 7706 15120 7705 15121 7706 15121 7722 15121 7716 15122 7707 15122 7708 15122 7708 15123 7707 15123 7709 15123 7708 15124 7709 15124 7718 15124 7718 15125 7710 15125 7708 15125 7708 15126 7710 15126 7714 15126 7708 15127 7714 15127 7703 15127 7703 15128 7714 15128 7711 15128 7703 15129 7711 15129 7712 15129 7718 15130 7699 15130 7710 15130 7710 15131 7699 15131 7701 15131 7710 15132 7701 15132 7713 15132 7713 15133 7701 15133 7700 15133 7713 15134 7700 15134 7714 15134 7714 15135 7700 15135 7726 15135 7717 15136 7709 15136 7715 15136 7715 15137 7709 15137 7707 15137 7715 15138 7707 15138 7698 15138 7698 15139 7707 15139 7716 15139 7698 15140 7716 15140 7697 15140 7697 15141 7716 15141 7708 15141 7717 15142 7699 15142 7709 15142 7709 15143 7699 15143 7718 15143 7724 15144 7703 15144 7693 15144 7693 15145 7703 15145 7719 15145 7693 15146 7719 15146 7720 15146 7720 15147 7719 15147 7702 15147 7720 15148 7702 15148 7723 15148 7723 15149 7702 15149 7704 15149 7711 15150 7725 15150 7712 15150 7712 15151 7725 15151 7695 15151 7712 15152 7695 15152 7706 15152 7706 15153 7695 15153 7721 15153 7706 15154 7721 15154 7722 15154 7722 15155 7721 15155 7694 15155 7722 15156 7694 15156 7705 15156 7705 15157 7694 15157 7696 15157 7723 15158 7704 15158 7696 15158 7696 15159 7704 15159 7705 15159 7697 15160 7708 15160 7724 15160 7724 15161 7708 15161 7703 15161 7725 15162 7711 15162 7726 15162 7726 15163 7711 15163 7714 15163 7758 15164 7727 15164 7749 15164 7732 15165 7728 15165 7729 15165 7732 15166 7760 15166 7743 15166 7757 15167 7730 15167 7731 15167 7731 15168 7730 15168 7760 15168 7731 15169 7760 15169 7733 15169 7733 15170 7760 15170 7732 15170 7733 15171 7732 15171 7752 15171 7752 15172 7732 15172 7729 15172 7744 15173 7745 15173 7743 15173 7743 15174 7745 15174 7734 15174 7743 15175 7734 15175 7732 15175 7732 15176 7734 15176 7758 15176 7732 15177 7758 15177 7755 15177 7755 15178 7758 15178 7749 15178 7747 15179 7746 15179 7742 15179 7742 15180 7746 15180 7740 15180 7759 15181 7756 15181 7735 15181 7739 15182 7751 15182 7741 15182 7741 15183 7751 15183 7753 15183 7736 15184 7748 15184 7750 15184 7750 15185 7748 15185 7741 15185 7750 15186 7741 15186 7754 15186 7754 15187 7741 15187 7753 15187 7754 15188 7753 15188 7737 15188 7735 15189 7738 15189 7759 15189 7759 15190 7738 15190 7739 15190 7759 15191 7739 15191 7740 15191 7740 15192 7739 15192 7741 15192 7740 15193 7741 15193 7742 15193 7743 15194 7740 15194 7744 15194 7744 15195 7740 15195 7746 15195 7744 15196 7746 15196 7745 15196 7745 15197 7746 15197 7747 15197 7745 15198 7747 15198 7734 15198 7734 15199 7747 15199 7742 15199 7758 15200 7741 15200 7727 15200 7727 15201 7741 15201 7748 15201 7727 15202 7748 15202 7749 15202 7749 15203 7748 15203 7736 15203 7749 15204 7736 15204 7755 15204 7755 15205 7736 15205 7750 15205 7739 15206 7733 15206 7751 15206 7751 15207 7733 15207 7752 15207 7751 15208 7752 15208 7753 15208 7753 15209 7752 15209 7729 15209 7753 15210 7729 15210 7737 15210 7737 15211 7729 15211 7728 15211 7737 15212 7728 15212 7754 15212 7754 15213 7728 15213 7732 15213 7755 15214 7750 15214 7732 15214 7732 15215 7750 15215 7754 15215 7759 15216 7760 15216 7756 15216 7756 15217 7760 15217 7730 15217 7756 15218 7730 15218 7735 15218 7735 15219 7730 15219 7757 15219 7735 15220 7757 15220 7738 15220 7738 15221 7757 15221 7731 15221 7733 15222 7739 15222 7731 15222 7731 15223 7739 15223 7738 15223 7734 15224 7742 15224 7758 15224 7758 15225 7742 15225 7741 15225 7759 15226 7740 15226 7760 15226 7760 15227 7740 15227 7743 15227 7778 15228 7779 15228 7780 15228 7786 15229 7784 15229 7761 15229 7761 15230 7784 15230 7783 15230 7780 15231 7781 15231 7778 15231 7778 15232 7781 15232 7761 15232 7778 15233 7761 15233 7762 15233 7762 15234 7761 15234 7783 15234 7783 15235 7763 15235 7762 15235 7762 15236 7763 15236 7764 15236 7762 15237 7764 15237 7766 15237 7776 15238 7777 15238 7765 15238 7765 15239 7777 15239 7762 15239 7765 15240 7762 15240 7788 15240 7788 15241 7762 15241 7766 15241 7774 15242 7767 15242 7775 15242 7768 15243 7772 15243 7769 15243 7789 15244 7790 15244 7770 15244 7770 15245 7790 15245 7769 15245 7770 15246 7769 15246 7771 15246 7771 15247 7769 15247 7772 15247 7782 15248 7785 15248 7791 15248 7791 15249 7785 15249 7787 15249 7791 15250 7787 15250 7773 15250 7773 15251 7774 15251 7791 15251 7791 15252 7774 15252 7775 15252 7791 15253 7775 15253 7769 15253 7769 15254 7775 15254 7792 15254 7769 15255 7792 15255 7768 15255 7765 15256 7771 15256 7776 15256 7776 15257 7771 15257 7772 15257 7776 15258 7772 15258 7777 15258 7777 15259 7772 15259 7768 15259 7777 15260 7768 15260 7762 15260 7762 15261 7768 15261 7792 15261 7778 15262 7775 15262 7779 15262 7779 15263 7775 15263 7767 15263 7779 15264 7767 15264 7780 15264 7780 15265 7767 15265 7774 15265 7780 15266 7774 15266 7781 15266 7781 15267 7774 15267 7773 15267 7791 15268 7783 15268 7782 15268 7782 15269 7783 15269 7784 15269 7782 15270 7784 15270 7785 15270 7785 15271 7784 15271 7786 15271 7785 15272 7786 15272 7787 15272 7787 15273 7786 15273 7761 15273 7781 15274 7773 15274 7761 15274 7761 15275 7773 15275 7787 15275 7770 15276 7788 15276 7789 15276 7789 15277 7788 15277 7766 15277 7789 15278 7766 15278 7790 15278 7790 15279 7766 15279 7764 15279 7790 15280 7764 15280 7769 15280 7769 15281 7764 15281 7763 15281 7783 15282 7791 15282 7763 15282 7763 15283 7791 15283 7769 15283 7762 15284 7792 15284 7778 15284 7778 15285 7792 15285 7775 15285 7770 15286 7771 15286 7788 15286 7788 15287 7771 15287 7765 15287 7821 15288 7820 15288 7795 15288 7795 15289 7820 15289 7826 15289 7795 15290 7826 15290 7797 15290 7793 15291 7794 15291 7810 15291 7810 15292 7794 15292 7795 15292 7810 15293 7795 15293 7796 15293 7796 15294 7795 15294 7797 15294 7823 15295 7812 15295 7799 15295 7816 15296 7798 15296 7800 15296 7800 15297 7798 15297 7814 15297 7799 15298 7817 15298 7823 15298 7823 15299 7817 15299 7800 15299 7823 15300 7800 15300 7794 15300 7794 15301 7800 15301 7814 15301 7794 15302 7814 15302 7795 15302 7807 15303 7825 15303 7818 15303 7809 15304 7801 15304 7813 15304 7802 15305 7803 15305 7804 15305 7804 15306 7803 15306 7825 15306 7804 15307 7825 15307 7811 15307 7811 15308 7825 15308 7824 15308 7819 15309 7805 15309 7818 15309 7818 15310 7805 15310 7822 15310 7818 15311 7822 15311 7807 15311 7815 15312 7806 15312 7807 15312 7807 15313 7806 15313 7808 15313 7807 15314 7808 15314 7825 15314 7825 15315 7808 15315 7809 15315 7825 15316 7809 15316 7824 15316 7824 15317 7809 15317 7813 15317 7797 15318 7825 15318 7796 15318 7796 15319 7825 15319 7803 15319 7796 15320 7803 15320 7810 15320 7810 15321 7803 15321 7802 15321 7810 15322 7802 15322 7793 15322 7793 15323 7802 15323 7804 15323 7793 15324 7804 15324 7794 15324 7794 15325 7804 15325 7811 15325 7823 15326 7824 15326 7812 15326 7812 15327 7824 15327 7813 15327 7812 15328 7813 15328 7799 15328 7799 15329 7813 15329 7801 15329 7799 15330 7801 15330 7817 15330 7817 15331 7801 15331 7809 15331 7807 15332 7814 15332 7815 15332 7815 15333 7814 15333 7798 15333 7815 15334 7798 15334 7806 15334 7806 15335 7798 15335 7816 15335 7806 15336 7816 15336 7808 15336 7808 15337 7816 15337 7800 15337 7817 15338 7809 15338 7800 15338 7800 15339 7809 15339 7808 15339 7818 15340 7826 15340 7819 15340 7819 15341 7826 15341 7820 15341 7819 15342 7820 15342 7805 15342 7805 15343 7820 15343 7821 15343 7805 15344 7821 15344 7822 15344 7822 15345 7821 15345 7795 15345 7814 15346 7807 15346 7795 15346 7795 15347 7807 15347 7822 15347 7794 15348 7811 15348 7823 15348 7823 15349 7811 15349 7824 15349 7818 15350 7825 15350 7826 15350 7826 15351 7825 15351 7797 15351 7827 15352 7847 15352 7828 15352 7851 15353 7830 15353 7829 15353 7829 15354 7830 15354 7831 15354 7831 15355 7833 15355 7829 15355 7829 15356 7833 15356 7827 15356 7829 15357 7827 15357 7852 15357 7852 15358 7827 15358 7828 15358 7831 15359 7832 15359 7833 15359 7833 15360 7832 15360 7854 15360 7833 15361 7854 15361 7834 15361 7845 15362 7846 15362 7858 15362 7858 15363 7846 15363 7833 15363 7858 15364 7833 15364 7857 15364 7857 15365 7833 15365 7834 15365 7841 15366 7835 15366 7840 15366 7853 15367 7836 15367 7856 15367 7856 15368 7836 15368 7855 15368 7837 15369 7849 15369 7850 15369 7848 15370 7839 15370 7838 15370 7838 15371 7839 15371 7843 15371 7840 15372 7842 15372 7841 15372 7841 15373 7842 15373 7856 15373 7841 15374 7856 15374 7843 15374 7843 15375 7856 15375 7855 15375 7843 15376 7855 15376 7838 15376 7838 15377 7855 15377 7837 15377 7838 15378 7837 15378 7844 15378 7844 15379 7837 15379 7850 15379 7858 15380 7842 15380 7845 15380 7845 15381 7842 15381 7840 15381 7845 15382 7840 15382 7846 15382 7846 15383 7840 15383 7835 15383 7846 15384 7835 15384 7833 15384 7833 15385 7835 15385 7841 15385 7827 15386 7843 15386 7847 15386 7847 15387 7843 15387 7839 15387 7847 15388 7839 15388 7828 15388 7828 15389 7839 15389 7848 15389 7828 15390 7848 15390 7852 15390 7852 15391 7848 15391 7838 15391 7837 15392 7831 15392 7849 15392 7849 15393 7831 15393 7830 15393 7849 15394 7830 15394 7850 15394 7850 15395 7830 15395 7851 15395 7850 15396 7851 15396 7844 15396 7844 15397 7851 15397 7829 15397 7852 15398 7838 15398 7829 15398 7829 15399 7838 15399 7844 15399 7856 15400 7857 15400 7853 15400 7853 15401 7857 15401 7834 15401 7853 15402 7834 15402 7836 15402 7836 15403 7834 15403 7854 15403 7836 15404 7854 15404 7855 15404 7855 15405 7854 15405 7832 15405 7831 15406 7837 15406 7832 15406 7832 15407 7837 15407 7855 15407 7833 15408 7841 15408 7827 15408 7827 15409 7841 15409 7843 15409 7856 15410 7842 15410 7857 15410 7857 15411 7842 15411 7858 15411 7890 15412 7888 15412 7859 15412 7859 15413 7888 15413 7892 15413 7859 15414 7892 15414 7880 15414 7875 15415 7860 15415 7861 15415 7861 15416 7860 15416 7872 15416 7861 15417 7872 15417 7873 15417 7862 15418 7876 15418 7877 15418 7883 15419 7881 15419 7885 15419 7885 15420 7881 15420 7880 15420 7892 15421 7872 15421 7880 15421 7880 15422 7872 15422 7860 15422 7880 15423 7860 15423 7885 15423 7885 15424 7860 15424 7862 15424 7885 15425 7862 15425 7878 15425 7878 15426 7862 15426 7877 15426 7863 15427 7882 15427 7891 15427 7891 15428 7882 15428 7884 15428 7891 15429 7884 15429 7864 15429 7865 15430 7889 15430 7887 15430 7887 15431 7889 15431 7864 15431 7887 15432 7864 15432 7866 15432 7866 15433 7864 15433 7874 15433 7879 15434 7867 15434 7886 15434 7886 15435 7867 15435 7868 15435 7886 15436 7868 15436 7869 15436 7870 15437 7874 15437 7871 15437 7871 15438 7874 15438 7864 15438 7871 15439 7864 15439 7869 15439 7869 15440 7864 15440 7884 15440 7869 15441 7884 15441 7886 15441 7872 15442 7866 15442 7873 15442 7873 15443 7866 15443 7874 15443 7873 15444 7874 15444 7861 15444 7861 15445 7874 15445 7870 15445 7861 15446 7870 15446 7875 15446 7875 15447 7870 15447 7871 15447 7875 15448 7871 15448 7860 15448 7860 15449 7871 15449 7869 15449 7862 15450 7868 15450 7876 15450 7876 15451 7868 15451 7867 15451 7876 15452 7867 15452 7877 15452 7877 15453 7867 15453 7879 15453 7877 15454 7879 15454 7878 15454 7878 15455 7879 15455 7886 15455 7891 15456 7880 15456 7863 15456 7863 15457 7880 15457 7881 15457 7863 15458 7881 15458 7882 15458 7882 15459 7881 15459 7883 15459 7882 15460 7883 15460 7884 15460 7884 15461 7883 15461 7885 15461 7878 15462 7886 15462 7885 15462 7885 15463 7886 15463 7884 15463 7887 15464 7892 15464 7865 15464 7865 15465 7892 15465 7888 15465 7865 15466 7888 15466 7889 15466 7889 15467 7888 15467 7890 15467 7889 15468 7890 15468 7864 15468 7864 15469 7890 15469 7859 15469 7880 15470 7891 15470 7859 15470 7859 15471 7891 15471 7864 15471 7860 15472 7869 15472 7862 15472 7862 15473 7869 15473 7868 15473 7887 15474 7866 15474 7892 15474 7892 15475 7866 15475 7872 15475 7893 15476 7916 15476 7917 15476 7919 15477 7914 15477 7896 15477 7896 15478 7914 15478 7893 15478 7896 15479 7893 15479 7894 15479 7894 15480 7893 15480 7917 15480 7921 15481 7895 15481 7896 15481 7896 15482 7895 15482 7920 15482 7896 15483 7920 15483 7919 15483 7898 15484 7919 15484 7926 15484 7899 15485 7897 15485 7914 15485 7925 15486 7924 15486 7926 15486 7926 15487 7924 15487 7928 15487 7926 15488 7928 15488 7898 15488 7919 15489 7898 15489 7914 15489 7914 15490 7898 15490 7911 15490 7914 15491 7911 15491 7899 15491 7913 15492 7900 15492 7915 15492 7915 15493 7900 15493 7912 15493 7915 15494 7912 15494 7909 15494 7923 15495 7901 15495 7902 15495 7902 15496 7901 15496 7908 15496 7902 15497 7908 15497 7912 15497 7910 15498 7918 15498 7903 15498 7904 15499 7905 15499 7907 15499 7907 15500 7905 15500 7906 15500 7907 15501 7906 15501 7922 15501 7908 15502 7907 15502 7912 15502 7912 15503 7907 15503 7922 15503 7912 15504 7922 15504 7909 15504 7909 15505 7922 15505 7910 15505 7909 15506 7910 15506 7927 15506 7927 15507 7910 15507 7903 15507 7898 15508 7912 15508 7911 15508 7911 15509 7912 15509 7900 15509 7911 15510 7900 15510 7899 15510 7899 15511 7900 15511 7913 15511 7899 15512 7913 15512 7897 15512 7897 15513 7913 15513 7915 15513 7897 15514 7915 15514 7914 15514 7914 15515 7915 15515 7909 15515 7893 15516 7927 15516 7916 15516 7916 15517 7927 15517 7903 15517 7916 15518 7903 15518 7917 15518 7917 15519 7903 15519 7918 15519 7917 15520 7918 15520 7894 15520 7894 15521 7918 15521 7910 15521 7907 15522 7919 15522 7904 15522 7904 15523 7919 15523 7920 15523 7904 15524 7920 15524 7905 15524 7905 15525 7920 15525 7895 15525 7905 15526 7895 15526 7906 15526 7906 15527 7895 15527 7921 15527 7906 15528 7921 15528 7922 15528 7922 15529 7921 15529 7896 15529 7894 15530 7910 15530 7896 15530 7896 15531 7910 15531 7922 15531 7902 15532 7928 15532 7923 15532 7923 15533 7928 15533 7924 15533 7923 15534 7924 15534 7901 15534 7901 15535 7924 15535 7925 15535 7901 15536 7925 15536 7908 15536 7908 15537 7925 15537 7926 15537 7919 15538 7907 15538 7926 15538 7926 15539 7907 15539 7908 15539 7914 15540 7909 15540 7893 15540 7893 15541 7909 15541 7927 15541 7902 15542 7912 15542 7928 15542 7928 15543 7912 15543 7898 15543 7929 15544 7952 15544 7932 15544 7938 15545 7930 15545 7937 15545 7931 15546 7954 15546 7932 15546 7932 15547 7954 15547 7958 15547 7932 15548 7958 15548 7929 15548 7936 15549 7937 15549 7934 15549 7949 15550 7950 15550 7952 15550 7960 15551 7933 15551 7934 15551 7934 15552 7933 15552 7964 15552 7934 15553 7964 15553 7936 15553 7935 15554 7949 15554 7936 15554 7936 15555 7949 15555 7952 15555 7936 15556 7952 15556 7937 15556 7937 15557 7952 15557 7929 15557 7937 15558 7929 15558 7938 15558 7938 15559 7929 15559 7956 15559 7942 15560 7953 15560 7962 15560 7939 15561 7940 15561 7941 15561 7941 15562 7940 15562 7942 15562 7941 15563 7942 15563 7957 15563 7957 15564 7942 15564 7944 15564 7943 15565 7959 15565 7963 15565 7963 15566 7959 15566 7962 15566 7963 15567 7962 15567 7948 15567 7948 15568 7962 15568 7947 15568 7955 15569 7944 15569 7945 15569 7945 15570 7944 15570 7942 15570 7945 15571 7942 15571 7961 15571 7961 15572 7942 15572 7962 15572 7953 15573 7951 15573 7962 15573 7962 15574 7951 15574 7946 15574 7962 15575 7946 15575 7947 15575 7936 15576 7948 15576 7935 15576 7935 15577 7948 15577 7947 15577 7935 15578 7947 15578 7949 15578 7949 15579 7947 15579 7946 15579 7949 15580 7946 15580 7950 15580 7950 15581 7946 15581 7951 15581 7950 15582 7951 15582 7952 15582 7952 15583 7951 15583 7953 15583 7932 15584 7942 15584 7931 15584 7931 15585 7942 15585 7940 15585 7931 15586 7940 15586 7954 15586 7954 15587 7940 15587 7939 15587 7954 15588 7939 15588 7958 15588 7958 15589 7939 15589 7941 15589 7961 15590 7937 15590 7945 15590 7945 15591 7937 15591 7930 15591 7945 15592 7930 15592 7955 15592 7955 15593 7930 15593 7938 15593 7955 15594 7938 15594 7944 15594 7944 15595 7938 15595 7956 15595 7944 15596 7956 15596 7957 15596 7957 15597 7956 15597 7929 15597 7958 15598 7941 15598 7929 15598 7929 15599 7941 15599 7957 15599 7963 15600 7964 15600 7943 15600 7943 15601 7964 15601 7933 15601 7943 15602 7933 15602 7959 15602 7959 15603 7933 15603 7960 15603 7959 15604 7960 15604 7962 15604 7962 15605 7960 15605 7934 15605 7937 15606 7961 15606 7934 15606 7934 15607 7961 15607 7962 15607 7952 15608 7953 15608 7932 15608 7932 15609 7953 15609 7942 15609 7963 15610 7948 15610 7964 15610 7964 15611 7948 15611 7936 15611 7987 15612 7986 15612 7993 15612 7997 15613 7981 15613 7965 15613 7987 15614 7993 15614 7966 15614 7971 15615 7968 15615 7970 15615 7992 15616 7967 15616 7994 15616 7994 15617 7967 15617 7968 15617 7994 15618 7968 15618 7993 15618 7993 15619 7968 15619 7971 15619 7993 15620 7971 15620 7966 15620 7976 15621 7969 15621 7970 15621 7970 15622 7969 15622 7979 15622 7970 15623 7979 15623 7971 15623 7971 15624 7979 15624 7997 15624 7971 15625 7997 15625 7984 15625 7984 15626 7997 15626 7965 15626 7978 15627 7977 15627 7972 15627 7972 15628 7977 15628 7975 15628 7972 15629 7975 15629 7980 15629 7983 15630 7982 15630 7985 15630 7985 15631 7982 15631 7980 15631 7985 15632 7980 15632 7989 15632 7989 15633 7980 15633 7988 15633 7973 15634 7988 15634 7974 15634 7974 15635 7988 15635 7980 15635 7974 15636 7980 15636 7995 15636 7995 15637 7980 15637 7975 15637 7995 15638 7975 15638 7996 15638 7996 15639 7975 15639 7998 15639 7996 15640 7998 15640 7991 15640 7991 15641 7998 15641 7990 15641 7970 15642 7975 15642 7976 15642 7976 15643 7975 15643 7977 15643 7976 15644 7977 15644 7969 15644 7969 15645 7977 15645 7978 15645 7969 15646 7978 15646 7979 15646 7979 15647 7978 15647 7972 15647 7997 15648 7980 15648 7981 15648 7981 15649 7980 15649 7982 15649 7981 15650 7982 15650 7965 15650 7965 15651 7982 15651 7983 15651 7965 15652 7983 15652 7984 15652 7984 15653 7983 15653 7985 15653 7995 15654 7993 15654 7974 15654 7974 15655 7993 15655 7986 15655 7974 15656 7986 15656 7973 15656 7973 15657 7986 15657 7987 15657 7973 15658 7987 15658 7988 15658 7988 15659 7987 15659 7966 15659 7988 15660 7966 15660 7989 15660 7989 15661 7966 15661 7971 15661 7984 15662 7985 15662 7971 15662 7971 15663 7985 15663 7989 15663 7998 15664 7968 15664 7990 15664 7990 15665 7968 15665 7967 15665 7990 15666 7967 15666 7991 15666 7991 15667 7967 15667 7992 15667 7991 15668 7992 15668 7996 15668 7996 15669 7992 15669 7994 15669 7993 15670 7995 15670 7994 15670 7994 15671 7995 15671 7996 15671 7979 15672 7972 15672 7997 15672 7997 15673 7972 15673 7980 15673 7998 15674 7975 15674 7968 15674 7968 15675 7975 15675 7970 15675 8027 15676 8002 15676 8029 15676 8019 15677 8020 15677 8029 15677 8029 15678 8020 15678 8022 15678 8029 15679 8022 15679 8027 15679 7999 15680 8024 15680 8004 15680 8004 15681 8024 15681 8003 15681 8034 15682 8003 15682 8000 15682 8017 15683 8018 15683 8002 15683 8031 15684 8030 15684 8000 15684 8000 15685 8030 15685 8001 15685 8000 15686 8001 15686 8034 15686 8016 15687 8017 15687 8034 15687 8034 15688 8017 15688 8002 15688 8034 15689 8002 15689 8003 15689 8003 15690 8002 15690 8027 15690 8003 15691 8027 15691 8004 15691 8012 15692 8005 15692 8006 15692 8013 15693 8007 15693 8015 15693 8015 15694 8007 15694 8008 15694 8015 15695 8008 15695 8009 15695 8028 15696 8021 15696 8010 15696 8023 15697 8011 15697 8032 15697 8032 15698 8011 15698 8025 15698 8032 15699 8025 15699 8026 15699 8006 15700 8033 15700 8012 15700 8012 15701 8033 15701 8032 15701 8012 15702 8032 15702 8015 15702 8015 15703 8032 15703 8026 15703 8015 15704 8026 15704 8013 15704 8013 15705 8026 15705 8028 15705 8013 15706 8028 15706 8014 15706 8014 15707 8028 15707 8010 15707 8034 15708 8015 15708 8016 15708 8016 15709 8015 15709 8009 15709 8016 15710 8009 15710 8017 15710 8017 15711 8009 15711 8008 15711 8017 15712 8008 15712 8018 15712 8018 15713 8008 15713 8007 15713 8018 15714 8007 15714 8002 15714 8002 15715 8007 15715 8013 15715 8029 15716 8014 15716 8019 15716 8019 15717 8014 15717 8010 15717 8019 15718 8010 15718 8020 15718 8020 15719 8010 15719 8021 15719 8020 15720 8021 15720 8022 15720 8022 15721 8021 15721 8028 15721 8032 15722 8003 15722 8023 15722 8023 15723 8003 15723 8024 15723 8023 15724 8024 15724 8011 15724 8011 15725 8024 15725 7999 15725 8011 15726 7999 15726 8025 15726 8025 15727 7999 15727 8004 15727 8025 15728 8004 15728 8026 15728 8026 15729 8004 15729 8027 15729 8022 15730 8028 15730 8027 15730 8027 15731 8028 15731 8026 15731 8002 15732 8013 15732 8029 15732 8029 15733 8013 15733 8014 15733 8012 15734 8001 15734 8005 15734 8005 15735 8001 15735 8030 15735 8005 15736 8030 15736 8006 15736 8006 15737 8030 15737 8031 15737 8006 15738 8031 15738 8033 15738 8033 15739 8031 15739 8000 15739 8003 15740 8032 15740 8000 15740 8000 15741 8032 15741 8033 15741 8034 15742 8001 15742 8015 15742 8015 15743 8001 15743 8012 15743 8065 15744 8043 15744 8060 15744 8035 15745 8061 15745 8060 15745 8060 15746 8061 15746 8036 15746 8060 15747 8036 15747 8065 15747 8037 15748 8038 15748 8064 15748 8064 15749 8038 15749 8044 15749 8042 15750 8044 15750 8039 15750 8041 15751 8058 15751 8043 15751 8069 15752 8068 15752 8039 15752 8039 15753 8068 15753 8040 15753 8039 15754 8040 15754 8042 15754 8055 15755 8041 15755 8042 15755 8042 15756 8041 15756 8043 15756 8042 15757 8043 15757 8044 15757 8044 15758 8043 15758 8065 15758 8044 15759 8065 15759 8064 15759 8063 15760 8045 15760 8046 15760 8066 15761 8067 15761 8047 15761 8047 15762 8067 15762 8070 15762 8047 15763 8070 15763 8054 15763 8054 15764 8070 15764 8048 15764 8054 15765 8048 15765 8046 15765 8046 15766 8048 15766 8062 15766 8046 15767 8062 15767 8063 15767 8057 15768 8056 15768 8049 15768 8049 15769 8056 15769 8054 15769 8049 15770 8054 15770 8059 15770 8059 15771 8054 15771 8046 15771 8059 15772 8046 15772 8050 15772 8050 15773 8046 15773 8051 15773 8050 15774 8051 15774 8052 15774 8052 15775 8051 15775 8053 15775 8042 15776 8054 15776 8055 15776 8055 15777 8054 15777 8056 15777 8055 15778 8056 15778 8041 15778 8041 15779 8056 15779 8057 15779 8041 15780 8057 15780 8058 15780 8058 15781 8057 15781 8049 15781 8058 15782 8049 15782 8043 15782 8043 15783 8049 15783 8059 15783 8060 15784 8050 15784 8035 15784 8035 15785 8050 15785 8052 15785 8035 15786 8052 15786 8061 15786 8061 15787 8052 15787 8053 15787 8061 15788 8053 15788 8036 15788 8036 15789 8053 15789 8051 15789 8048 15790 8044 15790 8062 15790 8062 15791 8044 15791 8038 15791 8062 15792 8038 15792 8063 15792 8063 15793 8038 15793 8037 15793 8063 15794 8037 15794 8045 15794 8045 15795 8037 15795 8064 15795 8045 15796 8064 15796 8046 15796 8046 15797 8064 15797 8065 15797 8036 15798 8051 15798 8065 15798 8065 15799 8051 15799 8046 15799 8047 15800 8040 15800 8066 15800 8066 15801 8040 15801 8068 15801 8066 15802 8068 15802 8067 15802 8067 15803 8068 15803 8069 15803 8067 15804 8069 15804 8070 15804 8070 15805 8069 15805 8039 15805 8044 15806 8048 15806 8039 15806 8039 15807 8048 15807 8070 15807 8043 15808 8059 15808 8060 15808 8060 15809 8059 15809 8050 15809 8047 15810 8054 15810 8040 15810 8040 15811 8054 15811 8042 15811 8073 15812 8084 15812 8071 15812 8086 15813 8088 15813 8085 15813 8085 15814 8088 15814 8089 15814 8085 15815 8089 15815 8072 15815 8071 15816 8091 15816 8073 15816 8073 15817 8091 15817 8092 15817 8073 15818 8092 15818 8089 15818 8089 15819 8092 15819 8074 15819 8089 15820 8074 15820 8072 15820 8080 15821 8079 15821 8075 15821 8080 15822 8087 15822 8076 15822 8082 15823 8083 15823 8075 15823 8075 15824 8083 15824 8090 15824 8075 15825 8090 15825 8080 15825 8077 15826 8079 15826 8078 15826 8078 15827 8079 15827 8080 15827 8078 15828 8080 15828 8081 15828 8081 15829 8080 15829 8076 15829 8075 15830 8091 15830 8082 15830 8082 15831 8091 15831 8071 15831 8082 15832 8071 15832 8083 15832 8083 15833 8071 15833 8084 15833 8083 15834 8084 15834 8090 15834 8090 15835 8084 15835 8073 15835 8072 15836 8078 15836 8085 15836 8085 15837 8078 15837 8081 15837 8085 15838 8081 15838 8086 15838 8086 15839 8081 15839 8076 15839 8086 15840 8076 15840 8088 15840 8088 15841 8076 15841 8087 15841 8088 15842 8087 15842 8089 15842 8089 15843 8087 15843 8080 15843 8080 15844 8090 15844 8089 15844 8089 15845 8090 15845 8073 15845 8092 15846 8079 15846 8074 15846 8074 15847 8079 15847 8077 15847 8091 15848 8075 15848 8092 15848 8092 15849 8075 15849 8079 15849 8074 15850 8077 15850 8072 15850 8072 15851 8077 15851 8078 15851 8093 15852 8094 15852 8111 15852 8111 15853 8094 15853 8095 15853 8111 15854 8095 15854 8108 15854 8096 15855 8104 15855 8097 15855 8097 15856 8104 15856 8109 15856 8097 15857 8109 15857 8095 15857 8095 15858 8109 15858 8098 15858 8095 15859 8098 15859 8108 15859 8110 15860 8099 15860 8112 15860 8112 15861 8099 15861 8103 15861 8100 15862 8105 15862 8103 15862 8103 15863 8105 15863 8101 15863 8106 15864 8112 15864 8107 15864 8107 15865 8112 15865 8103 15865 8107 15866 8103 15866 8102 15866 8102 15867 8103 15867 8101 15867 8103 15868 8109 15868 8100 15868 8100 15869 8109 15869 8104 15869 8100 15870 8104 15870 8105 15870 8105 15871 8104 15871 8096 15871 8105 15872 8096 15872 8101 15872 8101 15873 8096 15873 8097 15873 8111 15874 8112 15874 8093 15874 8093 15875 8112 15875 8106 15875 8093 15876 8106 15876 8094 15876 8094 15877 8106 15877 8107 15877 8094 15878 8107 15878 8095 15878 8095 15879 8107 15879 8102 15879 8102 15880 8101 15880 8095 15880 8095 15881 8101 15881 8097 15881 8098 15882 8099 15882 8108 15882 8108 15883 8099 15883 8110 15883 8109 15884 8103 15884 8098 15884 8098 15885 8103 15885 8099 15885 8108 15886 8110 15886 8111 15886 8111 15887 8110 15887 8112 15887 8113 15888 8135 15888 8132 15888 8113 15889 8132 15889 8114 15889 8114 15890 8132 15890 8133 15890 8114 15891 8133 15891 8125 15891 8115 15892 8116 15892 8125 15892 8125 15893 8116 15893 8128 15893 8117 15894 8114 15894 8118 15894 8118 15895 8114 15895 8125 15895 8118 15896 8125 15896 8129 15896 8129 15897 8125 15897 8128 15897 8123 15898 8120 15898 8119 15898 8119 15899 8120 15899 8134 15899 8123 15900 8124 15900 8120 15900 8120 15901 8124 15901 8131 15901 8120 15902 8131 15902 8130 15902 8130 15903 8121 15903 8127 15903 8136 15904 8120 15904 8122 15904 8122 15905 8120 15905 8130 15905 8122 15906 8130 15906 8126 15906 8126 15907 8130 15907 8127 15907 8119 15908 8113 15908 8123 15908 8123 15909 8113 15909 8114 15909 8123 15910 8114 15910 8124 15910 8124 15911 8114 15911 8117 15911 8124 15912 8117 15912 8131 15912 8131 15913 8117 15913 8118 15913 8125 15914 8122 15914 8115 15914 8115 15915 8122 15915 8126 15915 8115 15916 8126 15916 8116 15916 8116 15917 8126 15917 8127 15917 8116 15918 8127 15918 8128 15918 8128 15919 8127 15919 8121 15919 8128 15920 8121 15920 8129 15920 8129 15921 8121 15921 8130 15921 8130 15922 8131 15922 8129 15922 8129 15923 8131 15923 8118 15923 8120 15924 8136 15924 8132 15924 8132 15925 8136 15925 8133 15925 8134 15926 8120 15926 8135 15926 8135 15927 8120 15927 8132 15927 8113 15928 8119 15928 8135 15928 8135 15929 8119 15929 8134 15929 8133 15930 8136 15930 8125 15930 8125 15931 8136 15931 8122 15931 8146 15932 8160 15932 8147 15932 8140 15933 8137 15933 8138 15933 8138 15934 8139 15934 8140 15934 8140 15935 8139 15935 8141 15935 8140 15936 8141 15936 8148 15936 8143 15937 8145 15937 8158 15937 8142 15938 8144 15938 8143 15938 8143 15939 8144 15939 8167 15939 8143 15940 8167 15940 8145 15940 8158 15941 8146 15941 8143 15941 8143 15942 8146 15942 8147 15942 8143 15943 8147 15943 8164 15943 8164 15944 8147 15944 8140 15944 8164 15945 8140 15945 8165 15945 8165 15946 8140 15946 8148 15946 8165 15947 8148 15947 8166 15947 8156 15948 8172 15948 8155 15948 8157 15949 8152 15949 8154 15949 8149 15950 8162 15950 8150 15950 8150 15951 8162 15951 8154 15951 8150 15952 8154 15952 8151 15952 8151 15953 8154 15953 8152 15953 8153 15954 8159 15954 8161 15954 8161 15955 8159 15955 8172 15955 8161 15956 8172 15956 8171 15956 8171 15957 8172 15957 8154 15957 8168 15958 8169 15958 8155 15958 8155 15959 8169 15959 8170 15959 8155 15960 8170 15960 8156 15960 8172 15961 8156 15961 8154 15961 8154 15962 8156 15962 8163 15962 8154 15963 8163 15963 8157 15963 8145 15964 8172 15964 8158 15964 8158 15965 8172 15965 8159 15965 8158 15966 8159 15966 8146 15966 8146 15967 8159 15967 8153 15967 8146 15968 8153 15968 8160 15968 8160 15969 8153 15969 8161 15969 8160 15970 8161 15970 8147 15970 8147 15971 8161 15971 8171 15971 8140 15972 8154 15972 8137 15972 8137 15973 8154 15973 8162 15973 8137 15974 8162 15974 8138 15974 8138 15975 8162 15975 8149 15975 8138 15976 8149 15976 8139 15976 8139 15977 8149 15977 8150 15977 8156 15978 8164 15978 8163 15978 8163 15979 8164 15979 8165 15979 8163 15980 8165 15980 8157 15980 8157 15981 8165 15981 8166 15981 8157 15982 8166 15982 8152 15982 8152 15983 8166 15983 8148 15983 8152 15984 8148 15984 8151 15984 8151 15985 8148 15985 8141 15985 8139 15986 8150 15986 8141 15986 8141 15987 8150 15987 8151 15987 8155 15988 8167 15988 8168 15988 8168 15989 8167 15989 8144 15989 8168 15990 8144 15990 8169 15990 8169 15991 8144 15991 8142 15991 8169 15992 8142 15992 8170 15992 8170 15993 8142 15993 8143 15993 8164 15994 8156 15994 8143 15994 8143 15995 8156 15995 8170 15995 8147 15996 8171 15996 8140 15996 8140 15997 8171 15997 8154 15997 8145 15998 8167 15998 8172 15998 8172 15999 8167 15999 8155 15999 8191 16000 8192 16000 8205 16000 8205 16001 8192 16001 8173 16001 8205 16002 8173 16002 8204 16002 8204 16003 8173 16003 8199 16003 8196 16004 8194 16004 8199 16004 8199 16005 8194 16005 8174 16005 8199 16006 8174 16006 8175 16006 8202 16007 8200 16007 8203 16007 8203 16008 8200 16008 8206 16008 8176 16009 8187 16009 8189 16009 8189 16010 8204 16010 8176 16010 8176 16011 8204 16011 8199 16011 8176 16012 8199 16012 8206 16012 8206 16013 8199 16013 8175 16013 8206 16014 8175 16014 8203 16014 8177 16015 8178 16015 8198 16015 8183 16016 8198 16016 8180 16016 8178 16017 8179 16017 8198 16017 8198 16018 8179 16018 8195 16018 8198 16019 8195 16019 8197 16019 8193 16020 8181 16020 8180 16020 8180 16021 8181 16021 8182 16021 8180 16022 8182 16022 8183 16022 8198 16023 8183 16023 8177 16023 8177 16024 8183 16024 8190 16024 8177 16025 8190 16025 8184 16025 8185 16026 8201 16026 8186 16026 8186 16027 8201 16027 8177 16027 8186 16028 8177 16028 8188 16028 8188 16029 8177 16029 8184 16029 8176 16030 8188 16030 8187 16030 8187 16031 8188 16031 8184 16031 8187 16032 8184 16032 8189 16032 8189 16033 8184 16033 8190 16033 8189 16034 8190 16034 8204 16034 8204 16035 8190 16035 8183 16035 8205 16036 8182 16036 8191 16036 8191 16037 8182 16037 8181 16037 8191 16038 8181 16038 8192 16038 8192 16039 8181 16039 8193 16039 8192 16040 8193 16040 8173 16040 8173 16041 8193 16041 8180 16041 8178 16042 8175 16042 8179 16042 8179 16043 8175 16043 8174 16043 8179 16044 8174 16044 8195 16044 8195 16045 8174 16045 8194 16045 8195 16046 8194 16046 8197 16046 8197 16047 8194 16047 8196 16047 8197 16048 8196 16048 8198 16048 8198 16049 8196 16049 8199 16049 8173 16050 8180 16050 8199 16050 8199 16051 8180 16051 8198 16051 8186 16052 8206 16052 8185 16052 8185 16053 8206 16053 8200 16053 8185 16054 8200 16054 8201 16054 8201 16055 8200 16055 8202 16055 8201 16056 8202 16056 8177 16056 8177 16057 8202 16057 8203 16057 8175 16058 8178 16058 8203 16058 8203 16059 8178 16059 8177 16059 8204 16060 8183 16060 8205 16060 8205 16061 8183 16061 8182 16061 8176 16062 8206 16062 8188 16062 8188 16063 8206 16063 8186 16063 8233 16064 8231 16064 8215 16064 8213 16065 8207 16065 8208 16065 8209 16066 8211 16066 8235 16066 8228 16067 8210 16067 8209 16067 8209 16068 8210 16068 8229 16068 8209 16069 8229 16069 8211 16069 8214 16070 8212 16070 8224 16070 8239 16071 8238 16071 8214 16071 8214 16072 8238 16072 8242 16072 8214 16073 8242 16073 8212 16073 8224 16074 8213 16074 8214 16074 8214 16075 8213 16075 8208 16075 8214 16076 8208 16076 8215 16076 8215 16077 8208 16077 8209 16077 8215 16078 8209 16078 8233 16078 8233 16079 8209 16079 8235 16079 8216 16080 8232 16080 8230 16080 8230 16081 8232 16081 8234 16081 8217 16082 8219 16082 8218 16082 8218 16083 8219 16083 8241 16083 8218 16084 8241 16084 8221 16084 8226 16085 8225 16085 8227 16085 8227 16086 8225 16086 8220 16086 8227 16087 8220 16087 8221 16087 8221 16088 8220 16088 8222 16088 8221 16089 8222 16089 8218 16089 8237 16090 8223 16090 8236 16090 8236 16091 8223 16091 8240 16091 8236 16092 8240 16092 8220 16092 8220 16093 8240 16093 8230 16093 8220 16094 8230 16094 8222 16094 8222 16095 8230 16095 8234 16095 8212 16096 8220 16096 8224 16096 8224 16097 8220 16097 8225 16097 8224 16098 8225 16098 8213 16098 8213 16099 8225 16099 8226 16099 8213 16100 8226 16100 8207 16100 8207 16101 8226 16101 8227 16101 8207 16102 8227 16102 8208 16102 8208 16103 8227 16103 8221 16103 8209 16104 8241 16104 8228 16104 8228 16105 8241 16105 8219 16105 8228 16106 8219 16106 8210 16106 8210 16107 8219 16107 8217 16107 8210 16108 8217 16108 8229 16108 8229 16109 8217 16109 8218 16109 8230 16110 8215 16110 8216 16110 8216 16111 8215 16111 8231 16111 8216 16112 8231 16112 8232 16112 8232 16113 8231 16113 8233 16113 8232 16114 8233 16114 8234 16114 8234 16115 8233 16115 8235 16115 8234 16116 8235 16116 8222 16116 8222 16117 8235 16117 8211 16117 8229 16118 8218 16118 8211 16118 8211 16119 8218 16119 8222 16119 8236 16120 8242 16120 8237 16120 8237 16121 8242 16121 8238 16121 8237 16122 8238 16122 8223 16122 8223 16123 8238 16123 8239 16123 8223 16124 8239 16124 8240 16124 8240 16125 8239 16125 8214 16125 8215 16126 8230 16126 8214 16126 8214 16127 8230 16127 8240 16127 8208 16128 8221 16128 8209 16128 8209 16129 8221 16129 8241 16129 8212 16130 8242 16130 8220 16130 8220 16131 8242 16131 8236 16131 8243 16132 8244 16132 8245 16132 8245 16133 8244 16133 8264 16133 8245 16134 8264 16134 8271 16134 8267 16135 8247 16135 8246 16135 8246 16136 8247 16136 8245 16136 8246 16137 8245 16137 8270 16137 8270 16138 8245 16138 8271 16138 8274 16139 8248 16139 8253 16139 8253 16140 8248 16140 8252 16140 8249 16141 8250 16141 8251 16141 8251 16142 8262 16142 8249 16142 8249 16143 8262 16143 8245 16143 8249 16144 8245 16144 8252 16144 8252 16145 8245 16145 8247 16145 8252 16146 8247 16146 8253 16146 8268 16147 8269 16147 8256 16147 8254 16148 8261 16148 8275 16148 8275 16149 8261 16149 8259 16149 8275 16150 8259 16150 8256 16150 8263 16151 8255 16151 8265 16151 8265 16152 8255 16152 8256 16152 8265 16153 8256 16153 8272 16153 8272 16154 8256 16154 8269 16154 8273 16155 8257 16155 8276 16155 8276 16156 8257 16156 8258 16156 8276 16157 8258 16157 8259 16157 8259 16158 8258 16158 8266 16158 8259 16159 8266 16159 8256 16159 8256 16160 8266 16160 8260 16160 8256 16161 8260 16161 8268 16161 8249 16162 8259 16162 8250 16162 8250 16163 8259 16163 8261 16163 8250 16164 8261 16164 8251 16164 8251 16165 8261 16165 8254 16165 8251 16166 8254 16166 8262 16166 8262 16167 8254 16167 8275 16167 8245 16168 8256 16168 8243 16168 8243 16169 8256 16169 8255 16169 8243 16170 8255 16170 8244 16170 8244 16171 8255 16171 8263 16171 8244 16172 8263 16172 8264 16172 8264 16173 8263 16173 8265 16173 8266 16174 8247 16174 8260 16174 8260 16175 8247 16175 8267 16175 8260 16176 8267 16176 8268 16176 8268 16177 8267 16177 8246 16177 8268 16178 8246 16178 8269 16178 8269 16179 8246 16179 8270 16179 8269 16180 8270 16180 8272 16180 8272 16181 8270 16181 8271 16181 8264 16182 8265 16182 8271 16182 8271 16183 8265 16183 8272 16183 8276 16184 8252 16184 8273 16184 8273 16185 8252 16185 8248 16185 8273 16186 8248 16186 8257 16186 8257 16187 8248 16187 8274 16187 8257 16188 8274 16188 8258 16188 8258 16189 8274 16189 8253 16189 8247 16190 8266 16190 8253 16190 8253 16191 8266 16191 8258 16191 8262 16192 8275 16192 8245 16192 8245 16193 8275 16193 8256 16193 8249 16194 8252 16194 8259 16194 8259 16195 8252 16195 8276 16195 8306 16196 8305 16196 8277 16196 8278 16197 8299 16197 8312 16197 8280 16198 8279 16198 8307 16198 8300 16199 8281 16199 8280 16199 8280 16200 8281 16200 8303 16200 8280 16201 8303 16201 8279 16201 8282 16202 8284 16202 8285 16202 8311 16203 8283 16203 8282 16203 8282 16204 8283 16204 8309 16204 8282 16205 8309 16205 8284 16205 8285 16206 8278 16206 8282 16206 8282 16207 8278 16207 8312 16207 8282 16208 8312 16208 8277 16208 8277 16209 8312 16209 8280 16209 8277 16210 8280 16210 8306 16210 8306 16211 8280 16211 8307 16211 8287 16212 8292 16212 8308 16212 8297 16213 8296 16213 8295 16213 8302 16214 8301 16214 8308 16214 8308 16215 8301 16215 8286 16215 8308 16216 8286 16216 8287 16216 8288 16217 8310 16217 8289 16217 8289 16218 8310 16218 8290 16218 8289 16219 8290 16219 8295 16219 8295 16220 8290 16220 8304 16220 8295 16221 8304 16221 8292 16221 8292 16222 8304 16222 8291 16222 8292 16223 8291 16223 8293 16223 8293 16224 8291 16224 8294 16224 8292 16225 8287 16225 8295 16225 8295 16226 8287 16226 8298 16226 8295 16227 8298 16227 8297 16227 8284 16228 8295 16228 8285 16228 8285 16229 8295 16229 8296 16229 8285 16230 8296 16230 8278 16230 8278 16231 8296 16231 8297 16231 8278 16232 8297 16232 8299 16232 8299 16233 8297 16233 8298 16233 8299 16234 8298 16234 8312 16234 8312 16235 8298 16235 8287 16235 8280 16236 8286 16236 8300 16236 8300 16237 8286 16237 8301 16237 8300 16238 8301 16238 8281 16238 8281 16239 8301 16239 8302 16239 8281 16240 8302 16240 8303 16240 8303 16241 8302 16241 8308 16241 8304 16242 8277 16242 8291 16242 8291 16243 8277 16243 8305 16243 8291 16244 8305 16244 8294 16244 8294 16245 8305 16245 8306 16245 8294 16246 8306 16246 8293 16246 8293 16247 8306 16247 8307 16247 8293 16248 8307 16248 8292 16248 8292 16249 8307 16249 8279 16249 8303 16250 8308 16250 8279 16250 8279 16251 8308 16251 8292 16251 8289 16252 8309 16252 8288 16252 8288 16253 8309 16253 8283 16253 8288 16254 8283 16254 8310 16254 8310 16255 8283 16255 8311 16255 8310 16256 8311 16256 8290 16256 8290 16257 8311 16257 8282 16257 8277 16258 8304 16258 8282 16258 8282 16259 8304 16259 8290 16259 8312 16260 8287 16260 8280 16260 8280 16261 8287 16261 8286 16261 8284 16262 8309 16262 8295 16262 8295 16263 8309 16263 8289 16263 8316 16264 8314 16264 8342 16264 8328 16265 8331 16265 8314 16265 8314 16266 8331 16266 8338 16266 8314 16267 8338 16267 8337 16267 8334 16268 8342 16268 8313 16268 8313 16269 8342 16269 8314 16269 8313 16270 8314 16270 8315 16270 8315 16271 8314 16271 8337 16271 8342 16272 8343 16272 8316 16272 8316 16273 8343 16273 8317 16273 8316 16274 8317 16274 8340 16274 8318 16275 8319 16275 8324 16275 8324 16276 8319 16276 8316 16276 8324 16277 8316 16277 8345 16277 8345 16278 8316 16278 8340 16278 8341 16279 8320 16279 8336 16279 8344 16280 8336 16280 8332 16280 8346 16281 8339 16281 8321 16281 8320 16282 8333 16282 8336 16282 8336 16283 8333 16283 8335 16283 8336 16284 8335 16284 8322 16284 8330 16285 8329 16285 8332 16285 8332 16286 8329 16286 8327 16286 8332 16287 8327 16287 8344 16287 8323 16288 8326 16288 8344 16288 8344 16289 8326 16289 8325 16289 8344 16290 8325 16290 8336 16290 8336 16291 8325 16291 8346 16291 8336 16292 8346 16292 8341 16292 8341 16293 8346 16293 8321 16293 8324 16294 8325 16294 8318 16294 8318 16295 8325 16295 8326 16295 8318 16296 8326 16296 8319 16296 8319 16297 8326 16297 8323 16297 8319 16298 8323 16298 8316 16298 8316 16299 8323 16299 8344 16299 8314 16300 8327 16300 8328 16300 8328 16301 8327 16301 8329 16301 8328 16302 8329 16302 8331 16302 8331 16303 8329 16303 8330 16303 8331 16304 8330 16304 8338 16304 8338 16305 8330 16305 8332 16305 8320 16306 8342 16306 8333 16306 8333 16307 8342 16307 8334 16307 8333 16308 8334 16308 8335 16308 8335 16309 8334 16309 8313 16309 8335 16310 8313 16310 8322 16310 8322 16311 8313 16311 8315 16311 8322 16312 8315 16312 8336 16312 8336 16313 8315 16313 8337 16313 8338 16314 8332 16314 8337 16314 8337 16315 8332 16315 8336 16315 8346 16316 8345 16316 8339 16316 8339 16317 8345 16317 8340 16317 8339 16318 8340 16318 8321 16318 8321 16319 8340 16319 8317 16319 8321 16320 8317 16320 8341 16320 8341 16321 8317 16321 8343 16321 8342 16322 8320 16322 8343 16322 8343 16323 8320 16323 8341 16323 8316 16324 8344 16324 8314 16324 8314 16325 8344 16325 8327 16325 8324 16326 8345 16326 8325 16326 8325 16327 8345 16327 8346 16327 8362 16328 8363 16328 8365 16328 8379 16329 8347 16329 8361 16329 8378 16330 8377 16330 8379 16330 8379 16331 8377 16331 8382 16331 8379 16332 8382 16332 8347 16332 8350 16333 8373 16333 8351 16333 8367 16334 8348 16334 8349 16334 8349 16335 8348 16335 8369 16335 8349 16336 8369 16336 8365 16336 8365 16337 8369 16337 8350 16337 8361 16338 8362 16338 8379 16338 8379 16339 8362 16339 8365 16339 8379 16340 8365 16340 8370 16340 8370 16341 8365 16341 8350 16341 8370 16342 8350 16342 8371 16342 8371 16343 8350 16343 8351 16343 8376 16344 8352 16344 8357 16344 8357 16345 8352 16345 8353 16345 8357 16346 8353 16346 8380 16346 8354 16347 8372 16347 8355 16347 8355 16348 8372 16348 8374 16348 8355 16349 8374 16349 8380 16349 8380 16350 8374 16350 8356 16350 8380 16351 8356 16351 8357 16351 8368 16352 8358 16352 8375 16352 8375 16353 8358 16353 8359 16353 8375 16354 8359 16354 8381 16354 8364 16355 8360 16355 8366 16355 8366 16356 8360 16356 8356 16356 8366 16357 8356 16357 8381 16357 8381 16358 8356 16358 8374 16358 8381 16359 8374 16359 8375 16359 8347 16360 8356 16360 8361 16360 8361 16361 8356 16361 8360 16361 8361 16362 8360 16362 8362 16362 8362 16363 8360 16363 8364 16363 8362 16364 8364 16364 8363 16364 8363 16365 8364 16365 8366 16365 8363 16366 8366 16366 8365 16366 8365 16367 8366 16367 8381 16367 8349 16368 8359 16368 8367 16368 8367 16369 8359 16369 8358 16369 8367 16370 8358 16370 8348 16370 8348 16371 8358 16371 8368 16371 8348 16372 8368 16372 8369 16372 8369 16373 8368 16373 8375 16373 8380 16374 8370 16374 8355 16374 8355 16375 8370 16375 8371 16375 8355 16376 8371 16376 8354 16376 8354 16377 8371 16377 8351 16377 8354 16378 8351 16378 8372 16378 8372 16379 8351 16379 8373 16379 8372 16380 8373 16380 8374 16380 8374 16381 8373 16381 8350 16381 8369 16382 8375 16382 8350 16382 8350 16383 8375 16383 8374 16383 8357 16384 8382 16384 8376 16384 8376 16385 8382 16385 8377 16385 8376 16386 8377 16386 8352 16386 8352 16387 8377 16387 8378 16387 8352 16388 8378 16388 8353 16388 8353 16389 8378 16389 8379 16389 8370 16390 8380 16390 8379 16390 8379 16391 8380 16391 8353 16391 8365 16392 8381 16392 8349 16392 8349 16393 8381 16393 8359 16393 8347 16394 8382 16394 8356 16394 8356 16395 8382 16395 8357 16395 8385 16396 8402 16396 8403 16396 8405 16397 8383 16397 8403 16397 8403 16398 8383 16398 8392 16398 8403 16399 8392 16399 8394 16399 8401 16400 8400 16400 8384 16400 8394 16401 8395 16401 8403 16401 8403 16402 8395 16402 8401 16402 8403 16403 8401 16403 8385 16403 8385 16404 8401 16404 8384 16404 8385 16405 8384 16405 8397 16405 8404 16406 8386 16406 8406 16406 8406 16407 8386 16407 8391 16407 8393 16408 8391 16408 8387 16408 8387 16409 8391 16409 8386 16409 8387 16410 8386 16410 8388 16410 8388 16411 8386 16411 8389 16411 8388 16412 8389 16412 8390 16412 8390 16413 8396 16413 8388 16413 8388 16414 8396 16414 8398 16414 8388 16415 8398 16415 8399 16415 8383 16416 8406 16416 8392 16416 8392 16417 8406 16417 8391 16417 8392 16418 8391 16418 8394 16418 8394 16419 8391 16419 8393 16419 8394 16420 8393 16420 8395 16420 8395 16421 8393 16421 8387 16421 8390 16422 8385 16422 8396 16422 8396 16423 8385 16423 8397 16423 8396 16424 8397 16424 8398 16424 8398 16425 8397 16425 8384 16425 8398 16426 8384 16426 8399 16426 8399 16427 8384 16427 8400 16427 8399 16428 8400 16428 8388 16428 8388 16429 8400 16429 8401 16429 8401 16430 8395 16430 8388 16430 8388 16431 8395 16431 8387 16431 8389 16432 8386 16432 8402 16432 8402 16433 8386 16433 8403 16433 8386 16434 8404 16434 8403 16434 8403 16435 8404 16435 8405 16435 8385 16436 8390 16436 8402 16436 8402 16437 8390 16437 8389 16437 8405 16438 8404 16438 8383 16438 8383 16439 8404 16439 8406 16439 8415 16440 8416 16440 8407 16440 8421 16441 8420 16441 8423 16441 8423 16442 8420 16442 8408 16442 8407 16443 8424 16443 8415 16443 8415 16444 8424 16444 8423 16444 8415 16445 8423 16445 8426 16445 8426 16446 8423 16446 8408 16446 8426 16447 8408 16447 8425 16447 8419 16448 8409 16448 8410 16448 8410 16449 8409 16449 8422 16449 8410 16450 8422 16450 8414 16450 8417 16451 8411 16451 8418 16451 8418 16452 8411 16452 8412 16452 8418 16453 8412 16453 8422 16453 8422 16454 8412 16454 8413 16454 8422 16455 8413 16455 8414 16455 8415 16456 8412 16456 8416 16456 8416 16457 8412 16457 8411 16457 8416 16458 8411 16458 8407 16458 8407 16459 8411 16459 8417 16459 8407 16460 8417 16460 8424 16460 8424 16461 8417 16461 8418 16461 8410 16462 8408 16462 8419 16462 8419 16463 8408 16463 8420 16463 8419 16464 8420 16464 8409 16464 8409 16465 8420 16465 8421 16465 8409 16466 8421 16466 8422 16466 8422 16467 8421 16467 8423 16467 8423 16468 8424 16468 8422 16468 8422 16469 8424 16469 8418 16469 8425 16470 8414 16470 8426 16470 8426 16471 8414 16471 8413 16471 8408 16472 8410 16472 8425 16472 8425 16473 8410 16473 8414 16473 8426 16474 8413 16474 8415 16474 8415 16475 8413 16475 8412 16475 8448 16476 8427 16476 8434 16476 8428 16477 8429 16477 8452 16477 8452 16478 8430 16478 8428 16478 8428 16479 8430 16479 8456 16479 8428 16480 8456 16480 8431 16480 8433 16481 8445 16481 8447 16481 8460 16482 8459 16482 8433 16482 8433 16483 8459 16483 8432 16483 8433 16484 8432 16484 8445 16484 8447 16485 8448 16485 8433 16485 8433 16486 8448 16486 8434 16486 8433 16487 8434 16487 8453 16487 8453 16488 8434 16488 8428 16488 8453 16489 8428 16489 8435 16489 8435 16490 8428 16490 8431 16490 8435 16491 8431 16491 8436 16491 8437 16492 8438 16492 8451 16492 8451 16493 8439 16493 8437 16493 8437 16494 8439 16494 8450 16494 8437 16495 8450 16495 8443 16495 8443 16496 8450 16496 8446 16496 8449 16497 8440 16497 8450 16497 8450 16498 8440 16498 8441 16498 8450 16499 8441 16499 8446 16499 8457 16500 8458 16500 8462 16500 8462 16501 8458 16501 8461 16501 8462 16502 8461 16502 8446 16502 8446 16503 8461 16503 8442 16503 8446 16504 8442 16504 8443 16504 8443 16505 8442 16505 8454 16505 8443 16506 8454 16506 8455 16506 8455 16507 8454 16507 8444 16507 8445 16508 8446 16508 8447 16508 8447 16509 8446 16509 8441 16509 8447 16510 8441 16510 8448 16510 8448 16511 8441 16511 8440 16511 8448 16512 8440 16512 8427 16512 8427 16513 8440 16513 8449 16513 8427 16514 8449 16514 8434 16514 8434 16515 8449 16515 8450 16515 8428 16516 8439 16516 8429 16516 8429 16517 8439 16517 8451 16517 8429 16518 8451 16518 8452 16518 8452 16519 8451 16519 8438 16519 8452 16520 8438 16520 8430 16520 8430 16521 8438 16521 8437 16521 8442 16522 8453 16522 8454 16522 8454 16523 8453 16523 8435 16523 8454 16524 8435 16524 8444 16524 8444 16525 8435 16525 8436 16525 8444 16526 8436 16526 8455 16526 8455 16527 8436 16527 8431 16527 8455 16528 8431 16528 8443 16528 8443 16529 8431 16529 8456 16529 8430 16530 8437 16530 8456 16530 8456 16531 8437 16531 8443 16531 8462 16532 8432 16532 8457 16532 8457 16533 8432 16533 8459 16533 8457 16534 8459 16534 8458 16534 8458 16535 8459 16535 8460 16535 8458 16536 8460 16536 8461 16536 8461 16537 8460 16537 8433 16537 8453 16538 8442 16538 8433 16538 8433 16539 8442 16539 8461 16539 8434 16540 8450 16540 8428 16540 8428 16541 8450 16541 8439 16541 8462 16542 8446 16542 8432 16542 8432 16543 8446 16543 8445 16543 8466 16544 8463 16544 8465 16544 8465 16545 8463 16545 8485 16545 8465 16546 8485 16546 8464 16546 8481 16547 8482 16547 8480 16547 8480 16548 8482 16548 8465 16548 8480 16549 8465 16549 8478 16549 8478 16550 8465 16550 8464 16550 8466 16551 8475 16551 8463 16551 8463 16552 8475 16552 8474 16552 8463 16553 8474 16553 8473 16553 8468 16554 8472 16554 8469 16554 8468 16555 8467 16555 8484 16555 8467 16556 8468 16556 8477 16556 8477 16557 8468 16557 8469 16557 8477 16558 8469 16558 8476 16558 8486 16559 8470 16559 8471 16559 8471 16560 8470 16560 8468 16560 8471 16561 8468 16561 8479 16561 8479 16562 8468 16562 8484 16562 8479 16563 8484 16563 8483 16563 8468 16564 8463 16564 8472 16564 8472 16565 8463 16565 8473 16565 8472 16566 8473 16566 8469 16566 8469 16567 8473 16567 8474 16567 8469 16568 8474 16568 8476 16568 8476 16569 8474 16569 8475 16569 8476 16570 8475 16570 8477 16570 8477 16571 8475 16571 8466 16571 8478 16572 8471 16572 8480 16572 8480 16573 8471 16573 8479 16573 8480 16574 8479 16574 8481 16574 8481 16575 8479 16575 8483 16575 8481 16576 8483 16576 8482 16576 8482 16577 8483 16577 8484 16577 8482 16578 8484 16578 8465 16578 8465 16579 8484 16579 8467 16579 8467 16580 8477 16580 8465 16580 8465 16581 8477 16581 8466 16581 8485 16582 8470 16582 8464 16582 8464 16583 8470 16583 8486 16583 8463 16584 8468 16584 8485 16584 8485 16585 8468 16585 8470 16585 8464 16586 8486 16586 8478 16586 8478 16587 8486 16587 8471 16587 8503 16588 8504 16588 8518 16588 8518 16589 8504 16589 8506 16589 8518 16590 8506 16590 8490 16590 8490 16591 8506 16591 8488 16591 8490 16592 8488 16592 8489 16592 8487 16593 8510 16593 8488 16593 8488 16594 8510 16594 8507 16594 8488 16595 8507 16595 8489 16595 8489 16596 8516 16596 8490 16596 8490 16597 8516 16597 8515 16597 8490 16598 8515 16598 8493 16598 8491 16599 8500 16599 8492 16599 8492 16600 8500 16600 8490 16600 8492 16601 8490 16601 8513 16601 8513 16602 8490 16602 8493 16602 8498 16603 8495 16603 8494 16603 8494 16604 8495 16604 8508 16604 8494 16605 8508 16605 8509 16605 8505 16606 8502 16606 8496 16606 8496 16607 8502 16607 8519 16607 8496 16608 8519 16608 8494 16608 8501 16609 8499 16609 8497 16609 8497 16610 8499 16610 8520 16610 8511 16611 8512 16611 8514 16611 8519 16612 8497 16612 8494 16612 8494 16613 8497 16613 8520 16613 8494 16614 8520 16614 8498 16614 8498 16615 8520 16615 8511 16615 8498 16616 8511 16616 8517 16616 8517 16617 8511 16617 8514 16617 8492 16618 8520 16618 8491 16618 8491 16619 8520 16619 8499 16619 8491 16620 8499 16620 8500 16620 8500 16621 8499 16621 8501 16621 8500 16622 8501 16622 8490 16622 8490 16623 8501 16623 8497 16623 8518 16624 8519 16624 8503 16624 8503 16625 8519 16625 8502 16625 8503 16626 8502 16626 8504 16626 8504 16627 8502 16627 8505 16627 8504 16628 8505 16628 8506 16628 8506 16629 8505 16629 8496 16629 8498 16630 8489 16630 8495 16630 8495 16631 8489 16631 8507 16631 8495 16632 8507 16632 8508 16632 8508 16633 8507 16633 8510 16633 8508 16634 8510 16634 8509 16634 8509 16635 8510 16635 8487 16635 8509 16636 8487 16636 8494 16636 8494 16637 8487 16637 8488 16637 8506 16638 8496 16638 8488 16638 8488 16639 8496 16639 8494 16639 8511 16640 8513 16640 8512 16640 8512 16641 8513 16641 8493 16641 8512 16642 8493 16642 8514 16642 8514 16643 8493 16643 8515 16643 8514 16644 8515 16644 8517 16644 8517 16645 8515 16645 8516 16645 8489 16646 8498 16646 8516 16646 8516 16647 8498 16647 8517 16647 8490 16648 8497 16648 8518 16648 8518 16649 8497 16649 8519 16649 8511 16650 8520 16650 8513 16650 8513 16651 8520 16651 8492 16651 8537 16652 8543 16652 8541 16652 8521 16653 8522 16653 8543 16653 8543 16654 8522 16654 8531 16654 8531 16655 8534 16655 8543 16655 8543 16656 8534 16656 8535 16656 8543 16657 8535 16657 8541 16657 8523 16658 8524 16658 8539 16658 8539 16659 8524 16659 8537 16659 8539 16660 8537 16660 8540 16660 8540 16661 8537 16661 8541 16661 8525 16662 8526 16662 8527 16662 8542 16663 8544 16663 8532 16663 8532 16664 8544 16664 8527 16664 8538 16665 8528 16665 8527 16665 8527 16666 8528 16666 8529 16666 8527 16667 8529 16667 8525 16667 8533 16668 8532 16668 8530 16668 8530 16669 8532 16669 8527 16669 8530 16670 8527 16670 8536 16670 8536 16671 8527 16671 8526 16671 8522 16672 8532 16672 8531 16672 8531 16673 8532 16673 8533 16673 8531 16674 8533 16674 8534 16674 8534 16675 8533 16675 8530 16675 8534 16676 8530 16676 8535 16676 8535 16677 8530 16677 8536 16677 8535 16678 8536 16678 8541 16678 8541 16679 8536 16679 8526 16679 8527 16680 8537 16680 8538 16680 8538 16681 8537 16681 8524 16681 8538 16682 8524 16682 8528 16682 8528 16683 8524 16683 8523 16683 8528 16684 8523 16684 8529 16684 8529 16685 8523 16685 8539 16685 8529 16686 8539 16686 8525 16686 8525 16687 8539 16687 8540 16687 8541 16688 8526 16688 8540 16688 8540 16689 8526 16689 8525 16689 8544 16690 8542 16690 8543 16690 8543 16691 8542 16691 8521 16691 8537 16692 8527 16692 8543 16692 8543 16693 8527 16693 8544 16693 8521 16694 8542 16694 8522 16694 8522 16695 8542 16695 8532 16695 8549 16696 8554 16696 8560 16696 8562 16697 8545 16697 8546 16697 8555 16698 8559 16698 8547 16698 8547 16699 8559 16699 8548 16699 8547 16700 8548 16700 8560 16700 8560 16701 8548 16701 8562 16701 8560 16702 8562 16702 8549 16702 8549 16703 8562 16703 8546 16703 8564 16704 8563 16704 8550 16704 8550 16705 8563 16705 8552 16705 8558 16706 8557 16706 8552 16706 8552 16707 8557 16707 8556 16707 8553 16708 8550 16708 8551 16708 8551 16709 8550 16709 8552 16709 8551 16710 8552 16710 8561 16710 8561 16711 8552 16711 8556 16711 8546 16712 8550 16712 8549 16712 8549 16713 8550 16713 8553 16713 8549 16714 8553 16714 8554 16714 8554 16715 8553 16715 8551 16715 8554 16716 8551 16716 8560 16716 8560 16717 8551 16717 8561 16717 8547 16718 8556 16718 8555 16718 8555 16719 8556 16719 8557 16719 8555 16720 8557 16720 8559 16720 8559 16721 8557 16721 8558 16721 8559 16722 8558 16722 8548 16722 8548 16723 8558 16723 8552 16723 8560 16724 8561 16724 8547 16724 8547 16725 8561 16725 8556 16725 8563 16726 8564 16726 8562 16726 8562 16727 8564 16727 8545 16727 8548 16728 8552 16728 8562 16728 8562 16729 8552 16729 8563 16729 8545 16730 8564 16730 8546 16730 8546 16731 8564 16731 8550 16731 8565 16732 8586 16732 8566 16732 8565 16733 8566 16733 8567 16733 8579 16734 8580 16734 8568 16734 8568 16735 8580 16735 8570 16735 8568 16736 8570 16736 8569 16736 8569 16737 8570 16737 8566 16737 8584 16738 8567 16738 8583 16738 8583 16739 8567 16739 8566 16739 8583 16740 8566 16740 8571 16740 8571 16741 8566 16741 8570 16741 8582 16742 8572 16742 8574 16742 8588 16743 8587 16743 8574 16743 8574 16744 8587 16744 8573 16744 8573 16745 8585 16745 8574 16745 8574 16746 8585 16746 8575 16746 8574 16747 8575 16747 8582 16747 8581 16748 8578 16748 8576 16748 8576 16749 8578 16749 8574 16749 8576 16750 8574 16750 8577 16750 8577 16751 8574 16751 8572 16751 8569 16752 8574 16752 8568 16752 8568 16753 8574 16753 8578 16753 8568 16754 8578 16754 8579 16754 8579 16755 8578 16755 8581 16755 8579 16756 8581 16756 8580 16756 8580 16757 8581 16757 8576 16757 8580 16758 8576 16758 8570 16758 8570 16759 8576 16759 8577 16759 8571 16760 8572 16760 8583 16760 8583 16761 8572 16761 8582 16761 8583 16762 8582 16762 8584 16762 8584 16763 8582 16763 8575 16763 8584 16764 8575 16764 8567 16764 8567 16765 8575 16765 8585 16765 8567 16766 8585 16766 8565 16766 8565 16767 8585 16767 8573 16767 8570 16768 8577 16768 8571 16768 8571 16769 8577 16769 8572 16769 8587 16770 8588 16770 8586 16770 8586 16771 8588 16771 8566 16771 8565 16772 8573 16772 8586 16772 8586 16773 8573 16773 8587 16773 8566 16774 8588 16774 8569 16774 8569 16775 8588 16775 8574 16775 8589 16776 8590 16776 8608 16776 8594 16777 8608 16777 8601 16777 8591 16778 8602 16778 8601 16778 8601 16779 8602 16779 8592 16779 8601 16780 8592 16780 8594 16780 8604 16781 8589 16781 8593 16781 8593 16782 8589 16782 8608 16782 8593 16783 8608 16783 8607 16783 8607 16784 8608 16784 8594 16784 8600 16785 8605 16785 8606 16785 8609 16786 8595 16786 8610 16786 8610 16787 8595 16787 8596 16787 8603 16788 8598 16788 8597 16788 8597 16789 8598 16789 8599 16789 8597 16790 8599 16790 8606 16790 8606 16791 8599 16791 8610 16791 8606 16792 8610 16792 8600 16792 8600 16793 8610 16793 8596 16793 8601 16794 8599 16794 8591 16794 8591 16795 8599 16795 8598 16795 8591 16796 8598 16796 8602 16796 8602 16797 8598 16797 8603 16797 8602 16798 8603 16798 8592 16798 8592 16799 8603 16799 8597 16799 8595 16800 8589 16800 8596 16800 8596 16801 8589 16801 8604 16801 8596 16802 8604 16802 8600 16802 8600 16803 8604 16803 8593 16803 8600 16804 8593 16804 8605 16804 8605 16805 8593 16805 8607 16805 8605 16806 8607 16806 8606 16806 8606 16807 8607 16807 8594 16807 8592 16808 8597 16808 8594 16808 8594 16809 8597 16809 8606 16809 8609 16810 8610 16810 8590 16810 8590 16811 8610 16811 8608 16811 8589 16812 8595 16812 8590 16812 8590 16813 8595 16813 8609 16813 8608 16814 8610 16814 8601 16814 8601 16815 8610 16815 8599 16815 8629 16816 8630 16816 8627 16816 8627 16817 8630 16817 8615 16817 8611 16818 8612 16818 8615 16818 8615 16819 8612 16819 8613 16819 8615 16820 8613 16820 8614 16820 8622 16821 8627 16821 8620 16821 8620 16822 8627 16822 8615 16822 8620 16823 8615 16823 8619 16823 8619 16824 8615 16824 8614 16824 8616 16825 8628 16825 8617 16825 8623 16826 8621 16826 8628 16826 8628 16827 8621 16827 8618 16827 8628 16828 8618 16828 8617 16828 8624 16829 8625 16829 8626 16829 8626 16830 8625 16830 8632 16830 8626 16831 8632 16831 8617 16831 8617 16832 8632 16832 8631 16832 8617 16833 8631 16833 8616 16833 8614 16834 8617 16834 8619 16834 8619 16835 8617 16835 8618 16835 8619 16836 8618 16836 8620 16836 8620 16837 8618 16837 8621 16837 8620 16838 8621 16838 8622 16838 8622 16839 8621 16839 8623 16839 8622 16840 8623 16840 8627 16840 8627 16841 8623 16841 8628 16841 8626 16842 8613 16842 8624 16842 8624 16843 8613 16843 8612 16843 8624 16844 8612 16844 8625 16844 8625 16845 8612 16845 8611 16845 8625 16846 8611 16846 8632 16846 8632 16847 8611 16847 8615 16847 8626 16848 8617 16848 8613 16848 8613 16849 8617 16849 8614 16849 8616 16850 8631 16850 8629 16850 8629 16851 8631 16851 8630 16851 8627 16852 8628 16852 8629 16852 8629 16853 8628 16853 8616 16853 8630 16854 8631 16854 8615 16854 8615 16855 8631 16855 8632 16855 8653 16856 8652 16856 8644 16856 8644 16857 8652 16857 8635 16857 8644 16858 8635 16858 8643 16858 8647 16859 8646 16859 8635 16859 8635 16860 8646 16860 8633 16860 8635 16861 8633 16861 8650 16861 8650 16862 8634 16862 8635 16862 8635 16863 8634 16863 8641 16863 8635 16864 8641 16864 8643 16864 8654 16865 8636 16865 8651 16865 8637 16866 8645 16866 8648 16866 8648 16867 8645 16867 8654 16867 8648 16868 8654 16868 8649 16868 8649 16869 8654 16869 8640 16869 8642 16870 8640 16870 8638 16870 8638 16871 8640 16871 8654 16871 8638 16872 8654 16872 8639 16872 8639 16873 8654 16873 8651 16873 8650 16874 8649 16874 8634 16874 8634 16875 8649 16875 8640 16875 8634 16876 8640 16876 8641 16876 8641 16877 8640 16877 8642 16877 8641 16878 8642 16878 8643 16878 8643 16879 8642 16879 8638 16879 8643 16880 8638 16880 8644 16880 8644 16881 8638 16881 8639 16881 8648 16882 8633 16882 8637 16882 8637 16883 8633 16883 8646 16883 8637 16884 8646 16884 8645 16884 8645 16885 8646 16885 8647 16885 8645 16886 8647 16886 8654 16886 8654 16887 8647 16887 8635 16887 8648 16888 8649 16888 8633 16888 8633 16889 8649 16889 8650 16889 8651 16890 8636 16890 8653 16890 8653 16891 8636 16891 8652 16891 8644 16892 8639 16892 8653 16892 8653 16893 8639 16893 8651 16893 8652 16894 8636 16894 8635 16894 8635 16895 8636 16895 8654 16895 8655 16896 8672 16896 8675 16896 8675 16897 8672 16897 8656 16897 8656 16898 8666 16898 8675 16898 8675 16899 8666 16899 8667 16899 8675 16900 8667 16900 8668 16900 8657 16901 8673 16901 8669 16901 8669 16902 8673 16902 8675 16902 8669 16903 8675 16903 8658 16903 8658 16904 8675 16904 8668 16904 8665 16905 8662 16905 8663 16905 8659 16906 8660 16906 8662 16906 8662 16907 8660 16907 8661 16907 8662 16908 8661 16908 8663 16908 8671 16909 8664 16909 8670 16909 8670 16910 8664 16910 8676 16910 8670 16911 8676 16911 8663 16911 8663 16912 8676 16912 8674 16912 8663 16913 8674 16913 8665 16913 8666 16914 8663 16914 8667 16914 8667 16915 8663 16915 8661 16915 8667 16916 8661 16916 8668 16916 8668 16917 8661 16917 8660 16917 8668 16918 8660 16918 8658 16918 8658 16919 8660 16919 8659 16919 8658 16920 8659 16920 8669 16920 8669 16921 8659 16921 8662 16921 8670 16922 8656 16922 8671 16922 8671 16923 8656 16923 8672 16923 8671 16924 8672 16924 8664 16924 8664 16925 8672 16925 8655 16925 8664 16926 8655 16926 8676 16926 8676 16927 8655 16927 8675 16927 8670 16928 8663 16928 8656 16928 8656 16929 8663 16929 8666 16929 8665 16930 8674 16930 8657 16930 8657 16931 8674 16931 8673 16931 8669 16932 8662 16932 8657 16932 8657 16933 8662 16933 8665 16933 8673 16934 8674 16934 8675 16934 8675 16935 8674 16935 8676 16935 8693 16936 8677 16936 8694 16936 8694 16937 8677 16937 8695 16937 8695 16938 8696 16938 8694 16938 8694 16939 8696 16939 8685 16939 8694 16940 8685 16940 8687 16940 8683 16941 8697 16941 8678 16941 8678 16942 8697 16942 8694 16942 8678 16943 8694 16943 8689 16943 8689 16944 8694 16944 8687 16944 8682 16945 8698 16945 8684 16945 8690 16946 8688 16946 8698 16946 8698 16947 8688 16947 8686 16947 8698 16948 8686 16948 8684 16948 8692 16949 8679 16949 8691 16949 8691 16950 8679 16950 8680 16950 8691 16951 8680 16951 8684 16951 8684 16952 8680 16952 8681 16952 8684 16953 8681 16953 8682 16953 8682 16954 8681 16954 8683 16954 8683 16955 8681 16955 8697 16955 8696 16956 8684 16956 8685 16956 8685 16957 8684 16957 8686 16957 8685 16958 8686 16958 8687 16958 8687 16959 8686 16959 8688 16959 8687 16960 8688 16960 8689 16960 8689 16961 8688 16961 8690 16961 8689 16962 8690 16962 8678 16962 8678 16963 8690 16963 8698 16963 8691 16964 8695 16964 8692 16964 8692 16965 8695 16965 8677 16965 8692 16966 8677 16966 8679 16966 8679 16967 8677 16967 8693 16967 8679 16968 8693 16968 8680 16968 8680 16969 8693 16969 8694 16969 8691 16970 8684 16970 8695 16970 8695 16971 8684 16971 8696 16971 8697 16972 8681 16972 8694 16972 8694 16973 8681 16973 8680 16973 8678 16974 8698 16974 8683 16974 8683 16975 8698 16975 8682 16975 8718 16976 8719 16976 8700 16976 8700 16977 8719 16977 8699 16977 8713 16978 8711 16978 8699 16978 8699 16979 8711 16979 8709 16979 8699 16980 8709 16980 8716 16980 8707 16981 8700 16981 8701 16981 8701 16982 8700 16982 8699 16982 8701 16983 8699 16983 8702 16983 8702 16984 8699 16984 8716 16984 8714 16985 8710 16985 8703 16985 8708 16986 8706 16986 8704 16986 8704 16987 8706 16987 8705 16987 8704 16988 8705 16988 8715 16988 8703 16989 8712 16989 8714 16989 8714 16990 8712 16990 8720 16990 8714 16991 8720 16991 8715 16991 8715 16992 8720 16992 8717 16992 8715 16993 8717 16993 8704 16993 8716 16994 8715 16994 8702 16994 8702 16995 8715 16995 8705 16995 8702 16996 8705 16996 8701 16996 8701 16997 8705 16997 8706 16997 8701 16998 8706 16998 8707 16998 8707 16999 8706 16999 8708 16999 8707 17000 8708 17000 8700 17000 8700 17001 8708 17001 8704 17001 8714 17002 8709 17002 8710 17002 8710 17003 8709 17003 8711 17003 8710 17004 8711 17004 8703 17004 8703 17005 8711 17005 8713 17005 8703 17006 8713 17006 8712 17006 8712 17007 8713 17007 8699 17007 8714 17008 8715 17008 8709 17008 8709 17009 8715 17009 8716 17009 8717 17010 8720 17010 8718 17010 8718 17011 8720 17011 8719 17011 8700 17012 8704 17012 8718 17012 8718 17013 8704 17013 8717 17013 8719 17014 8720 17014 8699 17014 8699 17015 8720 17015 8712 17015 8722 17016 8723 17016 8724 17016 8734 17017 8721 17017 8735 17017 8735 17018 8721 17018 8732 17018 8735 17019 8732 17019 8740 17019 8740 17020 8732 17020 8722 17020 8738 17021 8740 17021 8728 17021 8728 17022 8740 17022 8722 17022 8728 17023 8722 17023 8727 17023 8727 17024 8722 17024 8724 17024 8739 17025 8730 17025 8737 17025 8729 17026 8726 17026 8730 17026 8730 17027 8726 17027 8725 17027 8730 17028 8725 17028 8737 17028 8731 17029 8733 17029 8736 17029 8736 17030 8733 17030 8742 17030 8736 17031 8742 17031 8737 17031 8737 17032 8742 17032 8741 17032 8737 17033 8741 17033 8739 17033 8722 17034 8737 17034 8723 17034 8723 17035 8737 17035 8725 17035 8723 17036 8725 17036 8724 17036 8724 17037 8725 17037 8726 17037 8724 17038 8726 17038 8727 17038 8727 17039 8726 17039 8729 17039 8727 17040 8729 17040 8728 17040 8728 17041 8729 17041 8730 17041 8736 17042 8732 17042 8731 17042 8731 17043 8732 17043 8721 17043 8731 17044 8721 17044 8733 17044 8733 17045 8721 17045 8734 17045 8733 17046 8734 17046 8742 17046 8742 17047 8734 17047 8735 17047 8736 17048 8737 17048 8732 17048 8732 17049 8737 17049 8722 17049 8739 17050 8741 17050 8738 17050 8738 17051 8741 17051 8740 17051 8728 17052 8730 17052 8738 17052 8738 17053 8730 17053 8739 17053 8740 17054 8741 17054 8735 17054 8735 17055 8741 17055 8742 17055 8743 17056 8754 17056 8755 17056 8760 17057 8758 17057 8744 17057 8744 17058 8758 17058 8763 17058 8744 17059 8763 17059 8745 17059 8755 17060 8746 17060 8743 17060 8743 17061 8746 17061 8762 17061 8743 17062 8762 17062 8744 17062 8744 17063 8762 17063 8761 17063 8744 17064 8761 17064 8760 17064 8747 17065 8759 17065 8751 17065 8748 17066 8749 17066 8764 17066 8764 17067 8749 17067 8750 17067 8750 17068 8747 17068 8764 17068 8764 17069 8747 17069 8751 17069 8764 17070 8751 17070 8752 17070 8752 17071 8751 17071 8757 17071 8752 17072 8757 17072 8753 17072 8753 17073 8757 17073 8756 17073 8743 17074 8752 17074 8754 17074 8754 17075 8752 17075 8753 17075 8754 17076 8753 17076 8755 17076 8755 17077 8753 17077 8756 17077 8755 17078 8756 17078 8746 17078 8746 17079 8756 17079 8757 17079 8749 17080 8763 17080 8750 17080 8750 17081 8763 17081 8758 17081 8750 17082 8758 17082 8747 17082 8747 17083 8758 17083 8760 17083 8747 17084 8760 17084 8759 17084 8759 17085 8760 17085 8761 17085 8759 17086 8761 17086 8751 17086 8751 17087 8761 17087 8762 17087 8746 17088 8757 17088 8762 17088 8762 17089 8757 17089 8751 17089 8748 17090 8764 17090 8745 17090 8745 17091 8764 17091 8744 17091 8763 17092 8749 17092 8745 17092 8745 17093 8749 17093 8748 17093 8744 17094 8764 17094 8743 17094 8743 17095 8764 17095 8752 17095 8768 17096 8765 17096 8787 17096 8767 17097 8772 17097 8768 17097 8766 17098 8767 17098 8769 17098 8769 17099 8767 17099 8768 17099 8769 17100 8768 17100 8788 17100 8788 17101 8768 17101 8787 17101 8770 17102 8782 17102 8771 17102 8771 17103 8782 17103 8768 17103 8771 17104 8768 17104 8785 17104 8785 17105 8768 17105 8772 17105 8773 17106 8780 17106 8774 17106 8774 17107 8780 17107 8775 17107 8774 17108 8775 17108 8776 17108 8776 17109 8777 17109 8774 17109 8774 17110 8777 17110 8783 17110 8774 17111 8783 17111 8784 17111 8778 17112 8781 17112 8779 17112 8779 17113 8781 17113 8774 17113 8779 17114 8774 17114 8786 17114 8786 17115 8774 17115 8784 17115 8780 17116 8773 17116 8765 17116 8765 17117 8773 17117 8787 17117 8788 17118 8774 17118 8769 17118 8769 17119 8774 17119 8781 17119 8769 17120 8781 17120 8766 17120 8766 17121 8781 17121 8778 17121 8766 17122 8778 17122 8767 17122 8767 17123 8778 17123 8779 17123 8767 17124 8779 17124 8772 17124 8772 17125 8779 17125 8786 17125 8775 17126 8768 17126 8776 17126 8776 17127 8768 17127 8782 17127 8776 17128 8782 17128 8777 17128 8777 17129 8782 17129 8770 17129 8777 17130 8770 17130 8783 17130 8783 17131 8770 17131 8771 17131 8783 17132 8771 17132 8784 17132 8784 17133 8771 17133 8785 17133 8772 17134 8786 17134 8785 17134 8785 17135 8786 17135 8784 17135 8787 17136 8773 17136 8788 17136 8788 17137 8773 17137 8774 17137 8768 17138 8775 17138 8765 17138 8765 17139 8775 17139 8780 17139 8789 17140 8793 17140 8799 17140 8810 17141 8790 17141 8796 17141 8791 17142 8792 17142 8794 17142 8793 17143 8796 17143 8815 17143 8823 17144 8791 17144 8793 17144 8793 17145 8791 17145 8794 17145 8793 17146 8794 17146 8796 17146 8796 17147 8794 17147 8795 17147 8796 17148 8795 17148 8810 17148 8810 17149 8795 17149 8808 17149 8815 17150 8797 17150 8793 17150 8793 17151 8797 17151 8829 17151 8793 17152 8829 17152 8799 17152 8817 17153 8798 17153 8818 17153 8818 17154 8819 17154 8817 17154 8817 17155 8819 17155 8789 17155 8817 17156 8789 17156 8830 17156 8830 17157 8789 17157 8799 17157 8830 17158 8799 17158 8826 17158 8822 17159 8800 17159 8806 17159 8820 17160 8801 17160 8802 17160 8802 17161 8801 17161 8804 17161 8802 17162 8804 17162 8824 17162 8824 17163 8804 17163 8806 17163 8827 17164 8803 17164 8828 17164 8828 17165 8803 17165 8825 17165 8828 17166 8825 17166 8804 17166 8804 17167 8825 17167 8805 17167 8804 17168 8805 17168 8806 17168 8806 17169 8805 17169 8821 17169 8806 17170 8821 17170 8822 17170 8803 17171 8814 17171 8825 17171 8825 17172 8814 17172 8813 17172 8825 17173 8813 17173 8807 17173 8811 17174 8809 17174 8812 17174 8812 17175 8809 17175 8825 17175 8812 17176 8825 17176 8816 17176 8816 17177 8825 17177 8807 17177 8795 17178 8825 17178 8808 17178 8808 17179 8825 17179 8809 17179 8808 17180 8809 17180 8810 17180 8810 17181 8809 17181 8811 17181 8810 17182 8811 17182 8790 17182 8790 17183 8811 17183 8812 17183 8790 17184 8812 17184 8796 17184 8796 17185 8812 17185 8816 17185 8815 17186 8807 17186 8797 17186 8797 17187 8807 17187 8813 17187 8797 17188 8813 17188 8829 17188 8829 17189 8813 17189 8814 17189 8796 17190 8816 17190 8815 17190 8815 17191 8816 17191 8807 17191 8817 17192 8804 17192 8798 17192 8798 17193 8804 17193 8801 17193 8798 17194 8801 17194 8818 17194 8818 17195 8801 17195 8820 17195 8818 17196 8820 17196 8819 17196 8819 17197 8820 17197 8802 17197 8819 17198 8802 17198 8789 17198 8789 17199 8802 17199 8824 17199 8805 17200 8794 17200 8821 17200 8821 17201 8794 17201 8792 17201 8821 17202 8792 17202 8822 17202 8822 17203 8792 17203 8791 17203 8822 17204 8791 17204 8800 17204 8800 17205 8791 17205 8823 17205 8800 17206 8823 17206 8806 17206 8806 17207 8823 17207 8793 17207 8789 17208 8824 17208 8793 17208 8793 17209 8824 17209 8806 17209 8805 17210 8825 17210 8794 17210 8794 17211 8825 17211 8795 17211 8799 17212 8803 17212 8826 17212 8826 17213 8803 17213 8827 17213 8826 17214 8827 17214 8830 17214 8830 17215 8827 17215 8828 17215 8829 17216 8814 17216 8799 17216 8799 17217 8814 17217 8803 17217 8830 17218 8828 17218 8817 17218 8817 17219 8828 17219 8804 17219 10111 17220 10110 17220 8850 17220 10108 17221 8844 17221 8870 17221 10427 17222 10424 17222 8863 17222 10417 17223 8832 17223 10419 17223 10419 17224 8832 17224 8855 17224 10419 17225 8855 17225 8831 17225 8832 17226 8833 17226 8855 17226 8855 17227 8833 17227 8834 17227 8855 17228 8834 17228 10240 17228 8835 17229 10422 17229 8855 17229 8855 17230 10422 17230 10420 17230 10420 17231 8836 17231 8855 17231 8855 17232 8836 17232 8837 17232 8855 17233 8837 17233 8831 17233 8841 17234 8840 17234 10437 17234 10437 17235 10435 17235 8841 17235 8841 17236 10435 17236 10434 17236 8841 17237 10434 17237 8838 17237 8838 17238 8839 17238 8841 17238 8841 17239 8839 17239 10429 17239 8841 17240 10429 17240 10431 17240 8843 17241 10113 17241 8841 17241 8841 17242 10113 17242 10125 17242 8841 17243 10125 17243 8840 17243 8841 17244 8856 17244 8843 17244 8843 17245 8856 17245 8842 17245 8843 17246 8842 17246 10105 17246 10105 17247 8842 17247 8860 17247 10105 17248 8860 17248 10117 17248 10117 17249 8860 17249 10118 17249 8844 17250 8845 17250 8870 17250 8870 17251 8845 17251 8846 17251 8870 17252 8846 17252 8868 17252 8847 17253 10111 17253 8848 17253 8848 17254 10111 17254 8850 17254 8848 17255 8850 17255 10341 17255 8869 17256 10256 17256 8850 17256 8850 17257 10256 17257 8849 17257 8850 17258 8849 17258 10341 17258 8859 17259 10251 17259 8851 17259 8851 17260 10251 17260 8852 17260 8851 17261 8852 17261 8857 17261 8857 17262 8852 17262 10257 17262 8857 17263 10257 17263 8853 17263 10240 17264 8854 17264 8855 17264 8855 17265 8854 17265 10107 17265 8855 17266 10107 17266 8859 17266 8859 17267 10107 17267 10106 17267 8859 17268 10106 17268 10251 17268 10431 17269 10427 17269 8841 17269 8841 17270 10427 17270 8863 17270 8841 17271 8863 17271 8856 17271 8856 17272 8863 17272 8862 17272 8856 17273 8862 17273 8842 17273 10257 17274 10256 17274 8853 17274 8853 17275 10256 17275 8869 17275 8853 17276 8869 17276 8857 17276 8857 17277 8869 17277 8867 17277 8857 17278 8867 17278 8851 17278 8851 17279 8867 17279 8858 17279 8851 17280 8858 17280 8859 17280 8859 17281 8858 17281 8866 17281 8859 17282 8866 17282 8855 17282 8855 17283 8866 17283 8864 17283 8855 17284 8864 17284 8835 17284 8846 17285 10118 17285 8868 17285 8868 17286 10118 17286 8860 17286 8868 17287 8860 17287 8861 17287 8861 17288 8860 17288 8842 17288 8861 17289 8842 17289 8865 17289 8865 17290 8842 17290 8862 17290 10424 17291 8835 17291 8863 17291 8863 17292 8835 17292 8864 17292 8863 17293 8864 17293 8862 17293 8862 17294 8864 17294 8866 17294 8862 17295 8866 17295 8865 17295 8865 17296 8866 17296 8858 17296 8865 17297 8858 17297 8861 17297 8861 17298 8858 17298 8867 17298 8861 17299 8867 17299 8868 17299 8868 17300 8867 17300 8869 17300 8868 17301 8869 17301 8870 17301 8870 17302 8869 17302 8850 17302 8870 17303 8850 17303 10108 17303 10108 17304 8850 17304 10110 17304 8886 17305 8871 17305 8885 17305 10542 17306 8872 17306 8891 17306 10635 17307 10636 17307 8903 17307 10636 17308 10630 17308 8903 17308 8903 17309 10630 17309 8873 17309 8903 17310 8873 17310 8905 17310 8874 17311 8899 17311 8875 17311 8875 17312 8899 17312 10620 17312 8875 17313 10620 17313 8876 17313 8876 17314 10620 17314 10634 17314 8876 17315 10634 17315 8896 17315 8896 17316 10634 17316 8877 17316 10618 17317 8898 17317 8878 17317 8878 17318 8898 17318 8879 17318 8878 17319 8879 17319 10625 17319 10625 17320 8879 17320 8880 17320 8880 17321 8879 17321 8883 17321 8880 17322 8883 17322 10627 17322 8882 17323 10549 17323 8883 17323 10548 17324 10544 17324 8883 17324 8883 17325 10544 17325 10543 17325 10543 17326 10551 17326 8883 17326 8883 17327 10551 17327 8881 17327 8883 17328 8881 17328 8882 17328 10549 17329 10621 17329 8883 17329 8883 17330 10621 17330 10629 17330 8883 17331 10629 17331 10627 17331 10727 17332 8884 17332 8885 17332 8885 17333 8884 17333 10540 17333 8885 17334 10540 17334 10539 17334 10539 17335 10538 17335 8885 17335 8885 17336 10538 17336 10537 17336 8885 17337 10537 17337 8886 17337 10727 17338 8885 17338 8887 17338 8887 17339 8885 17339 8900 17339 8887 17340 8900 17340 10729 17340 10729 17341 8900 17341 10734 17341 10734 17342 8900 17342 8888 17342 10734 17343 8888 17343 10783 17343 10783 17344 8888 17344 10785 17344 10785 17345 8888 17345 8889 17345 10785 17346 8889 17346 10741 17346 10741 17347 8889 17347 8890 17347 10741 17348 8890 17348 10755 17348 10755 17349 8890 17349 10756 17349 10756 17350 8890 17350 8902 17350 10756 17351 8902 17351 8904 17351 8872 17352 10546 17352 8891 17352 8891 17353 10546 17353 8897 17353 8891 17354 8897 17354 8892 17354 8892 17355 8897 17355 8893 17355 8892 17356 8893 17356 8894 17356 8894 17357 8893 17357 8874 17357 8894 17358 8874 17358 8895 17358 8895 17359 8874 17359 8875 17359 8895 17360 8875 17360 8901 17360 8901 17361 8875 17361 8876 17361 8901 17362 8876 17362 8903 17362 8903 17363 8876 17363 8896 17363 8903 17364 8896 17364 10635 17364 10635 17365 8896 17365 8877 17365 10546 17366 10548 17366 8897 17366 8897 17367 10548 17367 8883 17367 8897 17368 8883 17368 8893 17368 8893 17369 8883 17369 8879 17369 8893 17370 8879 17370 8874 17370 8874 17371 8879 17371 8898 17371 8874 17372 8898 17372 8899 17372 8899 17373 8898 17373 10618 17373 8899 17374 10618 17374 10620 17374 8871 17375 10542 17375 8885 17375 8885 17376 10542 17376 8891 17376 8885 17377 8891 17377 8900 17377 8900 17378 8891 17378 8892 17378 8900 17379 8892 17379 8888 17379 8888 17380 8892 17380 8894 17380 8888 17381 8894 17381 8889 17381 8889 17382 8894 17382 8895 17382 8889 17383 8895 17383 8890 17383 8890 17384 8895 17384 8901 17384 8890 17385 8901 17385 8902 17385 8902 17386 8901 17386 8903 17386 8902 17387 8903 17387 8904 17387 8904 17388 8903 17388 8905 17388 8904 17389 8905 17389 8906 17389 10619 17390 8917 17390 8907 17390 10372 17391 10377 17391 8943 17391 8943 17392 10377 17392 8944 17392 10377 17393 10378 17393 8944 17393 8944 17394 10378 17394 8937 17394 8944 17395 8937 17395 8947 17395 8943 17396 10356 17396 10354 17396 10354 17397 10349 17397 8943 17397 8943 17398 10349 17398 10371 17398 8943 17399 10371 17399 10372 17399 8908 17400 10555 17400 8909 17400 10553 17401 10555 17401 8910 17401 8910 17402 10555 17402 8908 17402 8910 17403 8908 17403 8911 17403 8915 17404 10622 17404 8912 17404 8915 17405 8912 17405 8908 17405 8908 17406 8912 17406 8913 17406 8908 17407 8913 17407 8911 17407 10623 17408 10624 17408 8914 17408 8914 17409 10624 17409 10626 17409 8914 17410 10626 17410 8915 17410 8915 17411 10626 17411 8916 17411 8915 17412 8916 17412 10622 17412 8907 17413 8917 17413 8914 17413 8914 17414 8917 17414 8918 17414 8914 17415 8918 17415 10623 17415 10619 17416 8907 17416 10632 17416 10632 17417 8907 17417 8919 17417 10632 17418 8919 17418 10633 17418 8924 17419 8920 17419 8921 17419 8921 17420 8920 17420 8922 17420 8951 17421 8923 17421 8928 17421 8924 17422 8921 17422 8925 17422 8925 17423 8921 17423 8950 17423 8925 17424 8950 17424 8926 17424 8926 17425 8950 17425 8951 17425 8926 17426 8951 17426 8927 17426 8927 17427 8951 17427 8928 17427 8927 17428 8928 17428 10616 17428 10492 17429 8929 17429 8951 17429 8929 17430 10571 17430 8951 17430 8951 17431 10571 17431 8930 17431 8951 17432 8930 17432 8923 17432 10494 17433 8931 17433 10519 17433 10519 17434 8931 17434 8952 17434 10519 17435 8952 17435 8932 17435 8932 17436 8952 17436 8933 17436 8932 17437 8933 17437 10520 17437 10520 17438 8933 17438 10521 17438 10521 17439 8933 17439 8935 17439 10521 17440 8935 17440 8934 17440 8934 17441 8935 17441 10523 17441 10523 17442 8935 17442 8949 17442 10523 17443 8949 17443 8936 17443 8939 17444 10527 17444 8949 17444 8949 17445 10527 17445 10526 17445 8949 17446 10526 17446 8936 17446 8937 17447 8938 17447 8947 17447 8947 17448 8938 17448 8940 17448 8947 17449 8940 17449 8939 17449 8939 17450 8940 17450 10529 17450 8939 17451 10529 17451 10527 17451 8922 17452 10633 17452 8921 17452 8921 17453 10633 17453 8919 17453 8921 17454 8919 17454 8948 17454 8948 17455 8919 17455 8907 17455 8948 17456 8907 17456 8941 17456 8941 17457 8907 17457 8914 17457 8941 17458 8914 17458 8946 17458 8946 17459 8914 17459 8915 17459 8946 17460 8915 17460 8945 17460 8945 17461 8915 17461 8908 17461 8945 17462 8908 17462 8942 17462 8942 17463 8908 17463 8909 17463 8942 17464 8909 17464 10357 17464 10357 17465 10356 17465 8942 17465 8942 17466 10356 17466 8943 17466 8942 17467 8943 17467 8945 17467 8945 17468 8943 17468 8944 17468 8945 17469 8944 17469 8946 17469 8946 17470 8944 17470 8947 17470 8946 17471 8947 17471 8941 17471 8941 17472 8947 17472 8939 17472 8941 17473 8939 17473 8948 17473 8948 17474 8939 17474 8949 17474 8948 17475 8949 17475 8921 17475 8921 17476 8949 17476 8935 17476 8921 17477 8935 17477 8950 17477 8950 17478 8935 17478 8933 17478 8950 17479 8933 17479 8951 17479 8951 17480 8933 17480 8952 17480 8951 17481 8952 17481 10492 17481 10492 17482 8952 17482 8931 17482 8955 17483 10208 17483 8953 17483 8953 17484 10208 17484 8954 17484 8953 17485 8954 17485 10215 17485 8955 17486 8953 17486 10126 17486 10126 17487 8953 17487 8956 17487 10126 17488 8956 17488 10127 17488 10127 17489 8956 17489 8957 17489 8957 17490 8956 17490 8986 17490 8957 17491 8986 17491 10120 17491 10120 17492 8986 17492 10119 17492 10119 17493 8986 17493 8987 17493 10119 17494 8987 17494 8958 17494 8962 17495 8959 17495 8987 17495 8987 17496 8959 17496 10116 17496 8987 17497 10116 17497 8958 17497 10121 17498 8960 17498 8961 17498 8961 17499 8960 17499 8963 17499 8961 17500 8963 17500 8962 17500 8962 17501 8963 17501 10114 17501 8962 17502 10114 17502 8959 17502 10436 17503 10122 17503 8982 17503 8964 17504 10432 17504 8967 17504 8967 17505 10432 17505 10433 17505 8967 17506 10433 17506 10436 17506 10383 17507 10440 17507 8965 17507 8965 17508 10440 17508 8966 17508 8965 17509 8966 17509 8967 17509 8967 17510 8966 17510 8968 17510 8967 17511 8968 17511 8964 17511 10384 17512 10383 17512 8969 17512 8969 17513 10383 17513 8965 17513 8969 17514 8965 17514 8970 17514 8970 17515 8965 17515 8985 17515 8984 17516 8971 17516 10391 17516 8983 17517 8972 17517 8973 17517 8973 17518 8972 17518 8988 17518 8973 17519 8988 17519 8974 17519 8975 17520 10466 17520 8988 17520 8988 17521 10466 17521 10465 17521 8988 17522 10465 17522 8974 17522 8989 17523 10462 17523 8975 17523 8975 17524 10462 17524 10470 17524 10470 17525 10469 17525 8975 17525 8975 17526 10469 17526 8976 17526 8975 17527 8976 17527 10466 17527 10451 17528 10449 17528 8977 17528 8977 17529 10449 17529 10454 17529 8977 17530 10454 17530 8979 17530 8979 17531 10454 17531 10456 17531 8979 17532 10456 17532 8978 17532 8978 17533 10456 17533 10458 17533 8978 17534 10458 17534 10460 17534 10214 17535 8980 17535 8979 17535 8979 17536 8980 17536 8981 17536 8979 17537 8981 17537 8977 17537 8977 17538 8981 17538 10452 17538 8977 17539 10452 17539 10451 17539 8982 17540 8972 17540 8984 17540 8984 17541 8972 17541 8983 17541 8984 17542 8983 17542 8971 17542 10436 17543 8982 17543 8967 17543 8967 17544 8982 17544 8984 17544 8967 17545 8984 17545 8965 17545 8965 17546 8984 17546 10391 17546 8965 17547 10391 17547 8985 17547 8956 17548 8989 17548 8986 17548 8986 17549 8989 17549 8975 17549 8986 17550 8975 17550 8987 17550 8987 17551 8975 17551 8988 17551 8987 17552 8988 17552 8962 17552 8962 17553 8988 17553 8972 17553 8962 17554 8972 17554 8961 17554 8961 17555 8972 17555 8982 17555 8961 17556 8982 17556 10121 17556 10121 17557 8982 17557 10122 17557 10215 17558 10214 17558 8953 17558 8953 17559 10214 17559 8979 17559 8953 17560 8979 17560 8956 17560 8956 17561 8979 17561 8978 17561 8956 17562 8978 17562 8989 17562 8989 17563 8978 17563 10460 17563 8989 17564 10460 17564 10462 17564 9396 17565 9395 17565 8992 17565 8992 17566 9395 17566 9393 17566 8992 17567 9393 17567 9392 17567 9402 17568 9399 17568 8992 17568 8992 17569 9399 17569 9397 17569 8992 17570 9397 17570 9396 17570 9390 17571 8990 17571 8992 17571 8992 17572 8990 17572 8991 17572 8992 17573 8991 17573 9402 17573 9392 17574 9391 17574 8992 17574 8992 17575 9391 17575 8993 17575 8992 17576 8993 17576 9390 17576 8998 17577 9443 17577 8996 17577 8996 17578 9443 17578 8994 17578 8996 17579 8994 17579 8995 17579 9447 17580 9446 17580 8996 17580 8996 17581 9446 17581 8997 17581 8996 17582 8997 17582 8998 17582 9437 17583 9435 17583 8996 17583 8996 17584 9435 17584 9448 17584 8996 17585 9448 17585 9447 17585 8995 17586 8999 17586 8996 17586 8996 17587 8999 17587 9439 17587 8996 17588 9439 17588 9437 17588 9032 17589 9031 17589 9028 17589 9025 17590 9000 17590 9026 17590 9001 17591 9012 17591 9011 17591 9021 17592 9005 17592 9004 17592 9004 17593 9845 17593 9023 17593 9002 17594 9845 17594 9003 17594 9003 17595 9845 17595 9004 17595 9003 17596 9004 17596 9865 17596 9865 17597 9004 17597 9005 17597 9836 17598 9841 17598 9006 17598 9006 17599 9841 17599 9020 17599 9006 17600 9020 17600 9030 17600 9839 17601 9837 17601 9006 17601 9006 17602 9837 17602 9007 17602 9006 17603 9007 17603 9836 17603 9032 17604 9799 17604 9797 17604 9802 17605 9009 17605 9008 17605 9008 17606 9009 17606 9010 17606 9011 17607 9012 17607 9008 17607 9008 17608 9012 17608 9803 17608 9008 17609 9803 17609 9802 17609 9944 17610 12123 17610 9013 17610 9013 17611 12123 17611 9014 17611 9013 17612 9014 17612 12122 17612 9792 17613 9015 17613 9018 17613 9018 17614 9015 17614 9016 17614 9018 17615 9016 17615 9024 17615 9024 17616 9016 17616 9017 17616 9024 17617 9017 17617 9941 17617 9792 17618 9018 17618 9019 17618 9019 17619 9018 17619 9029 17619 9019 17620 9029 17620 9022 17620 9020 17621 9021 17621 9030 17621 9030 17622 9021 17622 9004 17622 9030 17623 9004 17623 9022 17623 9022 17624 9004 17624 9023 17624 9022 17625 9023 17625 9019 17625 9028 17626 9027 17626 9013 17626 9013 17627 9027 17627 9026 17627 9013 17628 9026 17628 9944 17628 9944 17629 9026 17629 9000 17629 12122 17630 9001 17630 9013 17630 9013 17631 9001 17631 9011 17631 9013 17632 9011 17632 9028 17632 9028 17633 9011 17633 9008 17633 9028 17634 9008 17634 9032 17634 9032 17635 9008 17635 9010 17635 9032 17636 9010 17636 9799 17636 9941 17637 9025 17637 9024 17637 9024 17638 9025 17638 9026 17638 9024 17639 9026 17639 9018 17639 9018 17640 9026 17640 9027 17640 9018 17641 9027 17641 9029 17641 9029 17642 9027 17642 9028 17642 9029 17643 9028 17643 9022 17643 9022 17644 9028 17644 9031 17644 9022 17645 9031 17645 9030 17645 9030 17646 9031 17646 9032 17646 9030 17647 9032 17647 9006 17647 9006 17648 9032 17648 9797 17648 9006 17649 9797 17649 9839 17649 9779 17650 9060 17650 9057 17650 10011 17651 10007 17651 9056 17651 9040 17652 9064 17652 9033 17652 12062 17653 12061 17653 9042 17653 9036 17654 9785 17654 9784 17654 9034 17655 9035 17655 9059 17655 9059 17656 9035 17656 9036 17656 12061 17657 9037 17657 9059 17657 9059 17658 9037 17658 9038 17658 9059 17659 9038 17659 9034 17659 12062 17660 9042 17660 9979 17660 9063 17661 9064 17661 9039 17661 9039 17662 9064 17662 9040 17662 9039 17663 9040 17663 9042 17663 9042 17664 9040 17664 9041 17664 9042 17665 9041 17665 9979 17665 9048 17666 9043 17666 9047 17666 9047 17667 9043 17667 9044 17667 9047 17668 9044 17668 9045 17668 10025 17669 9046 17669 9050 17669 9050 17670 9046 17670 9977 17670 9050 17671 9977 17671 9047 17671 9047 17672 9977 17672 9975 17672 9047 17673 9975 17673 9048 17673 9051 17674 10024 17674 9050 17674 9050 17675 10024 17675 9049 17675 9050 17676 9049 17676 10025 17676 10019 17677 10022 17677 9051 17677 9051 17678 10022 17678 10023 17678 9051 17679 10023 17679 10024 17679 9052 17680 10016 17680 9053 17680 9053 17681 10016 17681 9061 17681 9054 17682 9055 17682 9056 17682 9056 17683 9055 17683 10015 17683 9056 17684 10015 17684 10017 17684 10007 17685 10006 17685 9056 17685 9056 17686 10006 17686 10014 17686 9056 17687 10014 17687 9054 17687 9779 17688 9057 17688 9780 17688 9036 17689 9784 17689 9059 17689 9059 17690 9784 17690 9783 17690 9059 17691 9783 17691 9057 17691 9057 17692 9783 17692 9058 17692 9057 17693 9058 17693 9780 17693 12061 17694 9059 17694 9042 17694 9042 17695 9059 17695 9057 17695 9042 17696 9057 17696 9039 17696 9039 17697 9057 17697 9060 17697 9039 17698 9060 17698 9063 17698 9063 17699 9060 17699 10010 17699 9063 17700 10010 17700 9062 17700 10010 17701 10011 17701 9062 17701 9062 17702 10011 17702 9056 17702 9062 17703 9056 17703 9053 17703 9053 17704 9056 17704 10017 17704 9053 17705 10017 17705 9052 17705 9061 17706 10019 17706 9053 17706 9053 17707 10019 17707 9051 17707 9053 17708 9051 17708 9062 17708 9062 17709 9051 17709 9050 17709 9062 17710 9050 17710 9063 17710 9063 17711 9050 17711 9047 17711 9063 17712 9047 17712 9064 17712 9064 17713 9047 17713 9045 17713 9064 17714 9045 17714 9033 17714 9066 17715 9065 17715 9083 17715 9071 17716 11610 17716 9069 17716 9069 17717 11610 17717 11603 17717 9069 17718 11603 17718 11609 17718 9065 17719 9066 17719 9068 17719 9066 17720 9766 17720 9068 17720 9068 17721 9766 17721 9067 17721 9068 17722 9067 17722 9069 17722 9069 17723 9067 17723 9070 17723 9069 17724 9070 17724 9071 17724 9072 17725 9074 17725 10000 17725 9072 17726 9075 17726 10034 17726 10034 17727 9998 17727 9072 17727 9072 17728 9998 17728 9073 17728 9072 17729 9073 17729 9074 17729 9075 17730 9072 17730 10033 17730 10033 17731 9072 17731 9077 17731 10033 17732 9077 17732 9078 17732 9995 17733 9076 17733 9077 17733 9076 17734 9994 17734 9077 17734 9077 17735 9994 17735 9993 17735 9077 17736 9993 17736 9078 17736 11609 17737 11595 17737 9069 17737 9069 17738 11595 17738 9079 17738 9069 17739 9079 17739 9080 17739 9080 17740 9079 17740 9081 17740 9080 17741 9081 17741 10068 17741 10070 17742 9069 17742 9082 17742 9082 17743 9069 17743 9080 17743 9082 17744 9080 17744 10091 17744 10091 17745 9080 17745 10068 17745 10070 17746 9995 17746 9069 17746 9069 17747 9995 17747 9077 17747 9069 17748 9077 17748 9068 17748 9068 17749 9077 17749 9072 17749 9068 17750 9072 17750 9065 17750 9065 17751 9072 17751 10000 17751 9065 17752 10000 17752 9083 17752 9094 17753 12085 17753 9095 17753 9095 17754 12085 17754 12082 17754 9095 17755 12082 17755 9084 17755 9084 17756 12082 17756 12084 17756 9084 17757 12084 17757 9097 17757 9097 17758 12084 17758 9085 17758 9097 17759 9085 17759 9096 17759 9096 17760 9085 17760 12098 17760 9096 17761 12098 17761 9086 17761 9086 17762 12098 17762 12099 17762 9086 17763 12099 17763 9099 17763 9099 17764 12099 17764 12079 17764 9099 17765 12079 17765 9087 17765 9087 17766 12079 17766 12078 17766 9087 17767 12078 17767 9100 17767 9100 17768 12078 17768 9088 17768 9100 17769 9088 17769 9089 17769 9089 17770 9088 17770 9090 17770 9089 17771 9090 17771 9091 17771 9091 17772 9090 17772 12087 17772 9091 17773 12087 17773 9092 17773 9092 17774 12087 17774 9093 17774 9092 17775 9093 17775 9094 17775 9094 17776 9093 17776 12085 17776 9098 17777 9095 17777 9084 17777 9094 17778 9095 17778 9098 17778 9098 17779 9096 17779 9086 17779 9097 17780 9096 17780 9098 17780 9084 17781 9097 17781 9098 17781 9098 17782 9087 17782 9100 17782 9099 17783 9087 17783 9098 17783 9086 17784 9099 17784 9098 17784 9098 17785 9091 17785 9092 17785 9089 17786 9091 17786 9098 17786 9100 17787 9089 17787 9098 17787 9092 17788 9094 17788 9098 17788 9119 17789 9111 17789 9101 17789 9101 17790 9111 17790 12092 17790 9101 17791 12092 17791 9102 17791 9102 17792 12092 17792 12088 17792 9102 17793 12088 17793 9114 17793 9114 17794 12088 17794 12089 17794 9114 17795 12089 17795 9103 17795 9103 17796 12089 17796 12090 17796 9103 17797 12090 17797 9113 17797 9113 17798 12090 17798 9104 17798 9113 17799 9104 17799 9105 17799 9105 17800 9104 17800 9106 17800 9105 17801 9106 17801 9115 17801 9115 17802 9106 17802 9107 17802 9115 17803 9107 17803 9117 17803 9117 17804 9107 17804 12081 17804 9117 17805 12081 17805 9118 17805 9118 17806 12081 17806 12095 17806 9118 17807 12095 17807 9116 17807 9116 17808 12095 17808 9109 17808 9116 17809 9109 17809 9108 17809 9108 17810 9109 17810 9110 17810 9108 17811 9110 17811 9119 17811 9119 17812 9110 17812 9111 17812 9112 17813 9101 17813 9102 17813 9119 17814 9101 17814 9112 17814 9112 17815 9103 17815 9113 17815 9114 17816 9103 17816 9112 17816 9102 17817 9114 17817 9112 17817 9112 17818 9115 17818 9117 17818 9105 17819 9115 17819 9112 17819 9113 17820 9105 17820 9112 17820 9112 17821 9116 17821 9108 17821 9118 17822 9116 17822 9112 17822 9117 17823 9118 17823 9112 17823 9108 17824 9119 17824 9112 17824 10908 17825 10903 17825 9120 17825 9120 17826 10903 17826 10901 17826 9120 17827 10901 17827 9370 17827 10912 17828 9121 17828 9362 17828 9140 17829 9349 17829 9122 17829 9122 17830 9349 17830 9350 17830 9122 17831 9350 17831 9123 17831 9123 17832 9350 17832 9124 17832 9123 17833 9124 17833 9352 17833 9126 17834 10919 17834 9354 17834 9354 17835 10919 17835 10917 17835 9354 17836 10917 17836 9352 17836 9352 17837 10917 17837 9125 17837 9352 17838 9125 17838 9123 17838 9126 17839 9356 17839 10919 17839 10919 17840 9356 17840 9357 17840 10919 17841 9357 17841 9128 17841 9128 17842 9357 17842 9127 17842 9128 17843 9127 17843 9121 17843 9121 17844 9127 17844 9129 17844 9121 17845 9129 17845 9362 17845 10912 17846 9362 17846 10913 17846 10913 17847 9362 17847 9130 17847 10913 17848 9130 17848 10914 17848 9133 17849 9132 17849 9131 17849 9131 17850 9132 17850 10914 17850 9131 17851 10914 17851 9360 17851 9360 17852 10914 17852 9130 17852 9133 17853 9359 17853 9132 17853 9132 17854 9359 17854 9134 17854 9132 17855 9134 17855 10904 17855 10904 17856 9134 17856 9135 17856 10904 17857 9135 17857 10905 17857 10905 17858 9135 17858 9136 17858 10905 17859 9136 17859 9137 17859 9137 17860 9136 17860 9138 17860 9137 17861 9138 17861 10907 17861 10907 17862 9138 17862 9366 17862 9366 17863 9364 17863 10907 17863 10907 17864 9364 17864 9139 17864 10907 17865 9139 17865 10901 17865 10901 17866 9139 17866 9368 17866 10901 17867 9368 17867 9370 17867 9120 17868 9369 17868 10908 17868 10908 17869 9369 17869 9346 17869 10908 17870 9346 17870 9140 17870 9140 17871 9346 17871 9347 17871 9140 17872 9347 17872 9349 17872 9141 17873 9142 17873 9143 17873 9143 17874 9142 17874 11006 17874 9143 17875 11006 17875 9144 17875 11004 17876 9145 17876 9382 17876 11015 17877 9146 17877 11014 17877 11014 17878 9146 17878 9147 17878 11014 17879 9147 17879 9148 17879 9148 17880 9147 17880 9372 17880 9148 17881 9372 17881 9150 17881 9373 17882 9152 17882 9374 17882 9374 17883 9152 17883 9149 17883 9374 17884 9149 17884 9150 17884 9150 17885 9149 17885 11011 17885 9150 17886 11011 17886 9148 17886 9373 17887 9151 17887 9152 17887 9152 17888 9151 17888 9375 17888 9152 17889 9375 17889 9153 17889 9153 17890 9375 17890 9154 17890 9153 17891 9154 17891 9145 17891 9145 17892 9154 17892 9155 17892 9145 17893 9155 17893 9382 17893 11004 17894 9382 17894 11005 17894 11005 17895 9382 17895 9157 17895 11005 17896 9157 17896 9156 17896 9379 17897 9158 17897 9376 17897 9376 17898 9158 17898 9156 17898 9376 17899 9156 17899 9381 17899 9381 17900 9156 17900 9157 17900 9379 17901 9380 17901 9158 17901 9158 17902 9380 17902 9384 17902 9158 17903 9384 17903 9159 17903 9159 17904 9384 17904 9160 17904 9159 17905 9160 17905 11008 17905 11008 17906 9160 17906 9162 17906 11008 17907 9162 17907 9161 17907 9161 17908 9162 17908 9163 17908 9161 17909 9163 17909 11009 17909 11009 17910 9163 17910 9164 17910 11009 17911 9164 17911 9165 17911 9164 17912 9385 17912 9165 17912 9165 17913 9385 17913 9166 17913 9165 17914 9166 17914 11006 17914 11006 17915 9166 17915 9167 17915 11006 17916 9167 17916 9144 17916 9143 17917 9387 17917 9141 17917 9141 17918 9387 17918 9168 17918 9141 17919 9168 17919 11015 17919 11015 17920 9168 17920 9169 17920 11015 17921 9169 17921 9146 17921 9183 17922 9170 17922 9171 17922 9171 17923 9170 17923 9173 17923 9171 17924 9173 17924 9172 17924 9172 17925 9173 17925 9174 17925 9172 17926 9174 17926 9175 17926 9175 17927 9174 17927 11201 17927 9175 17928 11201 17928 9176 17928 9176 17929 11201 17929 11202 17929 9176 17930 11202 17930 9177 17930 9177 17931 11202 17931 11204 17931 9177 17932 11204 17932 9452 17932 9452 17933 11204 17933 9178 17933 9452 17934 9178 17934 9179 17934 9179 17935 9178 17935 9180 17935 9179 17936 9180 17936 9454 17936 9454 17937 9180 17937 9181 17937 9454 17938 9181 17938 9455 17938 9455 17939 9181 17939 11197 17939 9455 17940 11197 17940 9182 17940 9182 17941 11197 17941 11198 17941 9182 17942 11198 17942 9450 17942 9450 17943 11198 17943 11199 17943 9450 17944 11199 17944 9183 17944 9183 17945 11199 17945 9170 17945 9197 17946 11556 17946 9184 17946 9184 17947 11556 17947 9185 17947 9184 17948 9185 17948 9492 17948 9492 17949 9185 17949 11550 17949 9492 17950 11550 17950 9493 17950 9493 17951 11550 17951 9186 17951 9493 17952 9186 17952 9188 17952 9188 17953 9186 17953 9187 17953 9188 17954 9187 17954 9189 17954 9189 17955 9187 17955 11553 17955 9189 17956 11553 17956 9190 17956 9190 17957 11553 17957 9191 17957 9190 17958 9191 17958 9496 17958 9496 17959 9191 17959 9192 17959 9496 17960 9192 17960 9497 17960 9497 17961 9192 17961 9193 17961 9497 17962 9193 17962 9498 17962 9498 17963 9193 17963 9194 17963 9498 17964 9194 17964 9195 17964 9195 17965 9194 17965 11555 17965 9195 17966 11555 17966 9499 17966 9499 17967 11555 17967 9196 17967 9499 17968 9196 17968 9197 17968 9197 17969 9196 17969 11556 17969 9480 17970 11320 17970 9482 17970 9482 17971 11320 17971 11321 17971 9482 17972 11321 17972 9483 17972 9483 17973 11321 17973 11312 17973 9483 17974 11312 17974 9198 17974 9198 17975 11312 17975 9199 17975 9198 17976 9199 17976 9201 17976 9201 17977 9199 17977 9200 17977 9201 17978 9200 17978 9202 17978 9202 17979 9200 17979 11314 17979 9202 17980 11314 17980 9203 17980 9203 17981 11314 17981 9204 17981 9203 17982 9204 17982 9205 17982 9205 17983 9204 17983 11317 17983 9205 17984 11317 17984 9487 17984 9487 17985 11317 17985 9206 17985 9487 17986 9206 17986 9489 17986 9489 17987 9206 17987 11319 17987 9489 17988 11319 17988 9490 17988 9490 17989 11319 17989 9207 17989 9490 17990 9207 17990 9479 17990 9479 17991 9207 17991 9208 17991 9479 17992 9208 17992 9480 17992 9480 17993 9208 17993 11320 17993 9209 17994 9219 17994 9525 17994 9525 17995 9219 17995 11644 17995 9525 17996 11644 17996 9526 17996 9526 17997 11644 17997 11633 17997 9526 17998 11633 17998 9528 17998 9528 17999 11633 17999 11635 17999 9528 18000 11635 18000 9530 18000 9530 18001 11635 18001 11636 18001 9530 18002 11636 18002 9531 18002 9531 18003 11636 18003 9210 18003 9531 18004 9210 18004 9532 18004 9532 18005 9210 18005 11639 18005 9532 18006 11639 18006 9212 18006 9212 18007 11639 18007 9211 18007 9212 18008 9211 18008 9213 18008 9213 18009 9211 18009 11640 18009 9213 18010 11640 18010 9534 18010 9534 18011 11640 18011 9214 18011 9534 18012 9214 18012 9215 18012 9215 18013 9214 18013 9216 18013 9215 18014 9216 18014 9217 18014 9217 18015 9216 18015 9218 18015 9217 18016 9218 18016 9209 18016 9209 18017 9218 18017 9219 18017 9281 18018 9228 18018 9220 18018 9220 18019 9228 18019 10368 18019 9220 18020 10368 18020 9283 18020 9283 18021 10368 18021 10364 18021 9283 18022 10364 18022 9222 18022 9222 18023 10364 18023 9221 18023 9222 18024 9221 18024 9284 18024 9284 18025 9221 18025 10343 18025 9284 18026 10343 18026 9223 18026 9223 18027 10343 18027 9224 18027 9223 18028 9224 18028 9285 18028 9285 18029 9224 18029 10381 18029 9285 18030 10381 18030 9287 18030 9287 18031 10381 18031 10382 18031 9287 18032 10382 18032 9288 18032 9288 18033 10382 18033 10385 18033 9288 18034 10385 18034 9289 18034 9289 18035 10385 18035 10394 18035 9289 18036 10394 18036 9225 18036 9225 18037 10394 18037 10395 18037 9225 18038 10395 18038 9226 18038 9226 18039 10395 18039 9227 18039 9226 18040 9227 18040 9281 18040 9281 18041 9227 18041 9228 18041 9293 18042 10362 18042 9294 18042 9294 18043 10362 18043 9229 18043 9294 18044 9229 18044 9296 18044 9296 18045 9229 18045 10346 18045 9296 18046 10346 18046 9230 18046 9230 18047 10346 18047 10342 18047 9230 18048 10342 18048 9231 18048 9231 18049 10342 18049 10390 18049 9231 18050 10390 18050 9232 18050 9232 18051 10390 18051 9233 18051 9232 18052 9233 18052 9234 18052 9234 18053 9233 18053 10353 18053 9234 18054 10353 18054 9300 18054 9300 18055 10353 18055 10369 18055 9300 18056 10369 18056 9301 18056 9301 18057 10369 18057 10351 18057 9301 18058 10351 18058 9302 18058 9302 18059 10351 18059 10355 18059 9302 18060 10355 18060 9235 18060 9235 18061 10355 18061 10358 18061 9235 18062 10358 18062 9291 18062 9291 18063 10358 18063 10359 18063 9291 18064 10359 18064 9293 18064 9293 18065 10359 18065 10362 18065 9237 18066 9236 18066 9254 18066 9254 18067 9236 18067 12944 18067 9241 18068 9242 18068 12976 18068 9241 18069 12976 18069 9237 18069 9237 18070 12976 18070 9238 18070 9237 18071 9238 18071 9236 18071 9243 18072 9239 18072 11123 18072 11123 18073 9239 18073 12965 18073 11123 18074 12965 18074 9241 18074 9241 18075 12965 18075 9240 18075 9241 18076 9240 18076 9242 18076 11130 18077 12959 18077 9243 18077 9243 18078 12959 18078 9244 18078 9243 18079 9244 18079 9239 18079 9246 18080 12961 18080 11130 18080 11130 18081 12961 18081 9245 18081 11130 18082 9245 18082 12959 18082 9248 18083 12962 18083 9246 18083 9246 18084 12962 18084 9247 18084 9246 18085 9247 18085 12961 18085 9251 18086 12942 18086 9248 18086 9248 18087 12942 18087 12943 18087 9248 18088 12943 18088 12962 18088 9252 18089 12921 18089 9251 18089 9251 18090 12921 18090 9249 18090 9249 18091 9250 18091 9251 18091 9251 18092 9250 18092 12902 18092 9251 18093 12902 18093 12942 18093 9258 18094 12900 18094 9257 18094 9257 18095 12900 18095 12898 18095 9257 18096 12898 18096 9252 18096 9252 18097 12898 18097 12897 18097 9252 18098 12897 18098 12921 18098 12944 18099 9253 18099 9254 18099 9254 18100 9253 18100 12891 18100 9254 18101 12891 18101 9256 18101 9256 18102 12891 18102 9255 18102 9255 18103 12896 18103 9256 18103 9256 18104 12896 18104 12895 18104 9256 18105 12895 18105 9257 18105 9257 18106 12895 18106 12894 18106 9257 18107 12894 18107 9258 18107 9261 18108 9259 18108 9262 18108 9262 18109 9259 18109 13252 18109 9262 18110 13252 18110 9280 18110 9280 18111 13252 18111 9260 18111 9261 18112 9262 18112 13254 18112 13254 18113 9262 18113 9265 18113 13254 18114 9265 18114 9263 18114 13262 18115 13260 18115 9264 18115 9264 18116 13260 18116 13259 18116 9264 18117 13259 18117 11200 18117 11200 18118 13259 18118 13257 18118 11200 18119 13257 18119 9265 18119 9265 18120 13257 18120 13256 18120 9265 18121 13256 18121 9263 18121 13262 18122 9264 18122 9266 18122 9266 18123 9264 18123 9267 18123 9266 18124 9267 18124 13264 18124 13264 18125 9267 18125 13267 18125 13267 18126 9267 18126 9268 18126 13267 18127 9268 18127 13266 18127 9271 18128 13288 18128 9268 18128 9268 18129 13288 18129 9269 18129 9268 18130 9269 18130 13266 18130 9270 18131 13284 18131 9274 18131 9274 18132 13284 18132 9272 18132 9274 18133 9272 18133 9271 18133 9271 18134 9272 18134 13285 18134 9271 18135 13285 18135 13288 18135 11205 18136 9276 18136 9274 18136 9274 18137 9276 18137 9273 18137 9274 18138 9273 18138 9270 18138 9275 18139 11205 18139 9278 18139 9278 18140 11205 18140 11203 18140 9275 18141 13281 18141 11205 18141 11205 18142 13281 18142 13279 18142 11205 18143 13279 18143 9276 18143 13274 18144 13277 18144 11203 18144 11203 18145 13277 18145 9277 18145 11203 18146 9277 18146 9278 18146 13274 18147 11203 18147 13275 18147 13275 18148 11203 18148 9279 18148 13275 18149 9279 18149 13272 18149 9260 18150 13268 18150 9280 18150 9280 18151 13268 18151 13269 18151 9280 18152 13269 18152 9279 18152 9279 18153 13269 18153 13271 18153 9279 18154 13271 18154 13272 18154 11283 18155 9226 18155 11285 18155 11285 18156 9226 18156 9281 18156 11285 18157 9281 18157 11286 18157 11286 18158 9281 18158 9220 18158 11286 18159 9220 18159 9282 18159 9282 18160 9220 18160 9283 18160 9282 18161 9283 18161 11288 18161 11288 18162 9283 18162 9222 18162 11288 18163 9222 18163 11290 18163 11290 18164 9222 18164 9284 18164 11290 18165 9284 18165 11291 18165 11291 18166 9284 18166 9223 18166 11291 18167 9223 18167 9286 18167 9286 18168 9223 18168 9285 18168 9286 18169 9285 18169 11295 18169 11295 18170 9285 18170 9287 18170 11295 18171 9287 18171 11296 18171 11296 18172 9287 18172 9288 18172 11296 18173 9288 18173 11281 18173 11281 18174 9288 18174 9289 18174 11281 18175 9289 18175 9290 18175 9290 18176 9289 18176 9225 18176 9290 18177 9225 18177 11283 18177 11283 18178 9225 18178 9226 18178 11299 18179 9291 18179 9292 18179 9292 18180 9291 18180 9293 18180 9292 18181 9293 18181 11301 18181 11301 18182 9293 18182 9294 18182 11301 18183 9294 18183 9295 18183 9295 18184 9294 18184 9296 18184 9295 18185 9296 18185 9297 18185 9297 18186 9296 18186 9230 18186 9297 18187 9230 18187 9298 18187 9298 18188 9230 18188 9231 18188 9298 18189 9231 18189 11303 18189 11303 18190 9231 18190 9232 18190 11303 18191 9232 18191 9299 18191 9299 18192 9232 18192 9234 18192 9299 18193 9234 18193 11304 18193 11304 18194 9234 18194 9300 18194 11304 18195 9300 18195 11307 18195 11307 18196 9300 18196 9301 18196 11307 18197 9301 18197 11297 18197 11297 18198 9301 18198 9302 18198 11297 18199 9302 18199 11298 18199 11298 18200 9302 18200 9235 18200 11298 18201 9235 18201 11299 18201 11299 18202 9235 18202 9291 18202 9317 18203 13244 18203 11315 18203 9316 18204 9303 18204 11316 18204 13219 18205 13218 18205 9304 18205 13218 18206 13250 18206 9304 18206 9304 18207 13250 18207 13249 18207 9304 18208 13249 18208 9305 18208 13219 18209 9304 18209 13220 18209 13220 18210 9304 18210 11313 18210 13220 18211 11313 18211 13222 18211 11322 18212 9309 18212 13226 18212 11322 18213 13226 18213 11313 18213 11313 18214 13226 18214 9306 18214 11313 18215 9306 18215 13222 18215 13230 18216 9307 18216 13231 18216 13231 18217 9307 18217 9310 18217 13230 18218 13228 18218 9307 18218 9307 18219 13228 18219 13227 18219 9307 18220 13227 18220 11322 18220 11322 18221 13227 18221 9308 18221 11322 18222 9308 18222 9309 18222 11318 18223 13235 18223 9310 18223 9310 18224 13235 18224 9311 18224 9310 18225 9311 18225 13231 18225 13241 18226 9312 18226 9313 18226 9313 18227 9312 18227 13238 18227 9313 18228 13238 18228 11318 18228 11318 18229 13238 18229 13237 18229 11318 18230 13237 18230 13235 18230 11316 18231 9303 18231 9313 18231 9313 18232 9303 18232 9314 18232 9313 18233 9314 18233 13241 18233 11315 18234 13244 18234 11316 18234 11316 18235 13244 18235 9315 18235 11316 18236 9315 18236 9316 18236 9317 18237 11315 18237 9318 18237 9318 18238 11315 18238 9319 18238 9318 18239 9319 18239 9320 18239 9323 18240 9324 18240 9319 18240 9319 18241 9324 18241 13246 18241 9319 18242 13246 18242 9320 18242 13249 18243 9321 18243 9305 18243 9305 18244 9321 18244 9322 18244 9305 18245 9322 18245 9323 18245 9323 18246 9322 18246 13248 18246 9323 18247 13248 18247 9324 18247 9328 18248 13075 18248 9327 18248 9327 18249 13075 18249 9344 18249 9327 18250 9344 18250 9325 18250 11336 18251 9326 18251 13083 18251 11336 18252 13083 18252 9327 18252 9327 18253 13083 18253 13073 18253 9327 18254 13073 18254 9328 18254 11334 18255 9330 18255 9329 18255 11334 18256 9329 18256 11336 18256 11336 18257 9329 18257 13084 18257 11336 18258 13084 18258 9326 18258 9330 18259 11334 18259 9331 18259 9331 18260 11334 18260 9332 18260 9331 18261 9332 18261 13066 18261 9333 18262 13069 18262 11341 18262 11341 18263 13069 18263 9334 18263 11341 18264 9334 18264 9332 18264 9332 18265 9334 18265 13068 18265 9332 18266 13068 18266 13066 18266 9335 18267 13061 18267 11341 18267 11341 18268 13061 18268 13070 18268 11341 18269 13070 18269 9333 18269 9337 18270 9338 18270 9335 18270 9335 18271 9338 18271 13011 18271 9335 18272 13011 18272 13061 18272 9339 18273 13007 18273 11340 18273 11340 18274 13007 18274 9336 18274 11340 18275 9336 18275 9337 18275 9337 18276 9336 18276 13009 18276 9337 18277 13009 18277 9338 18277 9339 18278 11340 18278 13008 18278 13008 18279 11340 18279 9340 18279 13008 18280 9340 18280 13004 18280 13004 18281 9340 18281 13003 18281 13003 18282 9340 18282 9341 18282 13003 18283 9341 18283 9343 18283 11338 18284 9345 18284 9341 18284 9341 18285 9345 18285 9342 18285 9341 18286 9342 18286 9343 18286 9344 18287 12999 18287 9325 18287 9325 18288 12999 18288 13000 18288 9325 18289 13000 18289 11338 18289 11338 18290 13000 18290 13001 18290 11338 18291 13001 18291 9345 18291 9346 18292 11551 18292 9347 18292 9347 18293 11551 18293 9348 18293 9347 18294 9348 18294 9349 18294 9349 18295 9348 18295 9350 18295 9350 18296 9348 18296 9351 18296 9350 18297 9351 18297 9124 18297 9124 18298 9351 18298 9352 18298 9352 18299 9351 18299 9353 18299 9352 18300 9353 18300 9354 18300 9355 18301 9357 18301 9356 18301 9355 18302 9356 18302 9353 18302 9353 18303 9356 18303 9126 18303 9353 18304 9126 18304 9354 18304 9361 18305 9129 18305 9355 18305 9355 18306 9129 18306 9127 18306 9355 18307 9127 18307 9357 18307 9131 18308 9358 18308 9133 18308 9133 18309 9358 18309 9363 18309 9133 18310 9363 18310 9359 18310 9131 18311 9360 18311 9358 18311 9358 18312 9360 18312 9130 18312 9358 18313 9130 18313 9361 18313 9361 18314 9130 18314 9362 18314 9361 18315 9362 18315 9129 18315 11554 18316 9365 18316 9138 18316 9138 18317 9136 18317 11554 18317 11554 18318 9136 18318 9135 18318 11554 18319 9135 18319 9363 18319 9363 18320 9135 18320 9134 18320 9363 18321 9134 18321 9359 18321 11552 18322 9364 18322 9365 18322 9365 18323 9364 18323 9366 18323 9365 18324 9366 18324 9138 18324 9367 18325 9368 18325 11552 18325 11552 18326 9368 18326 9139 18326 11552 18327 9139 18327 9364 18327 9346 18328 9369 18328 11551 18328 11551 18329 9369 18329 9120 18329 11551 18330 9120 18330 9367 18330 9367 18331 9120 18331 9370 18331 9367 18332 9370 18332 9368 18332 9168 18333 11634 18333 9169 18333 9169 18334 11634 18334 11645 18334 9169 18335 11645 18335 9146 18335 9146 18336 11645 18336 9147 18336 9147 18337 11645 18337 9371 18337 9147 18338 9371 18338 9372 18338 9372 18339 9371 18339 9150 18339 9150 18340 9371 18340 11643 18340 9150 18341 11643 18341 9374 18341 11642 18342 9375 18342 9151 18342 11642 18343 9151 18343 11643 18343 11643 18344 9151 18344 9373 18344 11643 18345 9373 18345 9374 18345 11641 18346 9155 18346 11642 18346 11642 18347 9155 18347 9154 18347 11642 18348 9154 18348 9375 18348 9376 18349 9377 18349 9379 18349 9379 18350 9377 18350 9378 18350 9379 18351 9378 18351 9380 18351 9376 18352 9381 18352 9377 18352 9377 18353 9381 18353 9157 18353 9377 18354 9157 18354 11641 18354 11641 18355 9157 18355 9382 18355 11641 18356 9382 18356 9155 18356 9383 18357 11638 18357 9163 18357 9163 18358 9162 18358 9383 18358 9383 18359 9162 18359 9160 18359 9383 18360 9160 18360 9378 18360 9378 18361 9160 18361 9384 18361 9378 18362 9384 18362 9380 18362 9386 18363 9385 18363 11638 18363 11638 18364 9385 18364 9164 18364 11638 18365 9164 18365 9163 18365 11637 18366 9167 18366 9386 18366 9386 18367 9167 18367 9166 18367 9386 18368 9166 18368 9385 18368 9168 18369 9387 18369 11634 18369 11634 18370 9387 18370 9143 18370 11634 18371 9143 18371 11637 18371 11637 18372 9143 18372 9144 18372 11637 18373 9144 18373 9167 18373 9401 18374 8991 18374 9388 18374 9388 18375 8991 18375 8990 18375 9388 18376 8990 18376 9389 18376 9389 18377 8990 18377 9390 18377 9389 18378 9390 18378 11129 18378 11129 18379 9390 18379 8993 18379 11129 18380 8993 18380 11128 18380 11128 18381 8993 18381 9391 18381 11128 18382 9391 18382 11127 18382 11127 18383 9391 18383 9392 18383 11127 18384 9392 18384 11126 18384 11126 18385 9392 18385 9393 18385 11126 18386 9393 18386 9394 18386 9394 18387 9393 18387 9395 18387 9394 18388 9395 18388 11125 18388 11125 18389 9395 18389 9396 18389 11125 18390 9396 18390 11124 18390 11124 18391 9396 18391 9397 18391 11124 18392 9397 18392 9398 18392 9398 18393 9397 18393 9399 18393 9398 18394 9399 18394 9400 18394 9400 18395 9399 18395 9402 18395 9400 18396 9402 18396 9401 18396 9401 18397 9402 18397 8991 18397 11146 18398 11804 18398 9403 18398 9403 18399 11804 18399 9405 18399 9403 18400 9405 18400 9404 18400 9404 18401 9405 18401 11803 18401 9404 18402 11803 18402 11154 18402 11154 18403 11803 18403 9406 18403 11154 18404 9406 18404 9407 18404 9407 18405 9406 18405 9408 18405 9407 18406 9408 18406 11155 18406 11155 18407 9408 18407 9409 18407 11155 18408 9409 18408 9411 18408 9411 18409 9409 18409 9410 18409 9411 18410 9410 18410 9413 18410 9413 18411 9410 18411 9412 18411 9413 18412 9412 18412 9414 18412 9414 18413 9412 18413 9415 18413 9414 18414 9415 18414 11148 18414 11148 18415 9415 18415 9416 18415 11148 18416 9416 18416 11147 18416 11147 18417 9416 18417 9417 18417 11147 18418 9417 18418 11157 18418 11157 18419 9417 18419 9418 18419 11157 18420 9418 18420 11146 18420 11146 18421 9418 18421 11804 18421 11163 18422 11812 18422 9419 18422 9419 18423 11812 18423 9420 18423 9419 18424 9420 18424 11159 18424 11159 18425 9420 18425 9421 18425 11159 18426 9421 18426 11144 18426 11144 18427 9421 18427 11806 18427 11144 18428 11806 18428 11143 18428 11143 18429 11806 18429 9422 18429 11143 18430 9422 18430 9423 18430 9423 18431 9422 18431 11808 18431 9423 18432 11808 18432 9424 18432 9424 18433 11808 18433 9426 18433 9424 18434 9426 18434 9425 18434 9425 18435 9426 18435 9427 18435 9425 18436 9427 18436 9428 18436 9428 18437 9427 18437 9430 18437 9428 18438 9430 18438 9429 18438 9429 18439 9430 18439 9431 18439 9429 18440 9431 18440 11151 18440 11151 18441 9431 18441 9432 18441 11151 18442 9432 18442 9433 18442 9433 18443 9432 18443 11813 18443 9433 18444 11813 18444 11163 18444 11163 18445 11813 18445 11812 18445 9434 18446 9448 18446 11333 18446 11333 18447 9448 18447 9435 18447 11333 18448 9435 18448 9436 18448 9436 18449 9435 18449 9437 18449 9436 18450 9437 18450 9438 18450 9438 18451 9437 18451 9439 18451 9438 18452 9439 18452 11339 18452 11339 18453 9439 18453 8999 18453 11339 18454 8999 18454 9440 18454 9440 18455 8999 18455 8995 18455 9440 18456 8995 18456 9441 18456 9441 18457 8995 18457 8994 18457 9441 18458 8994 18458 9442 18458 9442 18459 8994 18459 9443 18459 9442 18460 9443 18460 9444 18460 9444 18461 9443 18461 8998 18461 9444 18462 8998 18462 9445 18462 9445 18463 8998 18463 8997 18463 9445 18464 8997 18464 11337 18464 11337 18465 8997 18465 9446 18465 11337 18466 9446 18466 11335 18466 11335 18467 9446 18467 9447 18467 11335 18468 9447 18468 9434 18468 9434 18469 9447 18469 9448 18469 12050 18470 9450 18470 9449 18470 9449 18471 9450 18471 9183 18471 9449 18472 9183 18472 12038 18472 12038 18473 9183 18473 9171 18473 12038 18474 9171 18474 12039 18474 12039 18475 9171 18475 9172 18475 12039 18476 9172 18476 12041 18476 12041 18477 9172 18477 9175 18477 12041 18478 9175 18478 9451 18478 9451 18479 9175 18479 9176 18479 9451 18480 9176 18480 12044 18480 12044 18481 9176 18481 9177 18481 12044 18482 9177 18482 12045 18482 12045 18483 9177 18483 9452 18483 12045 18484 9452 18484 9453 18484 9453 18485 9452 18485 9179 18485 9453 18486 9179 18486 12046 18486 12046 18487 9179 18487 9454 18487 12046 18488 9454 18488 12048 18488 12048 18489 9454 18489 9455 18489 12048 18490 9455 18490 12049 18490 12049 18491 9455 18491 9182 18491 12049 18492 9182 18492 12050 18492 12050 18493 9182 18493 9450 18493 9503 18494 11284 18494 9456 18494 9456 18495 11284 18495 9457 18495 9456 18496 9457 18496 9505 18496 9505 18497 9457 18497 9459 18497 9505 18498 9459 18498 9458 18498 9458 18499 9459 18499 11287 18499 9458 18500 11287 18500 9460 18500 9460 18501 11287 18501 11289 18501 9460 18502 11289 18502 9506 18502 9506 18503 11289 18503 11292 18503 9506 18504 11292 18504 9508 18504 9508 18505 11292 18505 11293 18505 9508 18506 11293 18506 9510 18506 9510 18507 11293 18507 11294 18507 9510 18508 11294 18508 9511 18508 9511 18509 11294 18509 9461 18509 9511 18510 9461 18510 9513 18510 9513 18511 9461 18511 11279 18511 9513 18512 11279 18512 9462 18512 9462 18513 11279 18513 11280 18513 9462 18514 11280 18514 9501 18514 9501 18515 11280 18515 11282 18515 9501 18516 11282 18516 9503 18516 9503 18517 11282 18517 11284 18517 9477 18518 9464 18518 9463 18518 9463 18519 9464 18519 11300 18519 9463 18520 11300 18520 9518 18520 9518 18521 11300 18521 9465 18521 9518 18522 9465 18522 9519 18522 9519 18523 9465 18523 11302 18523 9519 18524 11302 18524 9466 18524 9466 18525 11302 18525 9467 18525 9466 18526 9467 18526 9468 18526 9468 18527 9467 18527 9469 18527 9468 18528 9469 18528 9522 18528 9522 18529 9469 18529 9470 18529 9522 18530 9470 18530 9471 18530 9471 18531 9470 18531 9473 18531 9471 18532 9473 18532 9472 18532 9472 18533 9473 18533 11305 18533 9472 18534 11305 18534 9474 18534 9474 18535 11305 18535 11306 18535 9474 18536 11306 18536 9523 18536 9523 18537 11306 18537 9475 18537 9523 18538 9475 18538 9476 18538 9476 18539 9475 18539 9478 18539 9476 18540 9478 18540 9477 18540 9477 18541 9478 18541 9464 18541 12142 18542 9479 18542 12143 18542 12143 18543 9479 18543 9480 18543 12143 18544 9480 18544 9481 18544 9481 18545 9480 18545 9482 18545 9481 18546 9482 18546 12132 18546 12132 18547 9482 18547 9483 18547 12132 18548 9483 18548 12133 18548 12133 18549 9483 18549 9198 18549 12133 18550 9198 18550 12135 18550 12135 18551 9198 18551 9201 18551 12135 18552 9201 18552 12137 18552 12137 18553 9201 18553 9202 18553 12137 18554 9202 18554 9484 18554 9484 18555 9202 18555 9203 18555 9484 18556 9203 18556 9485 18556 9485 18557 9203 18557 9205 18557 9485 18558 9205 18558 9486 18558 9486 18559 9205 18559 9487 18559 9486 18560 9487 18560 9488 18560 9488 18561 9487 18561 9489 18561 9488 18562 9489 18562 12140 18562 12140 18563 9489 18563 9490 18563 12140 18564 9490 18564 12142 18564 12142 18565 9490 18565 9479 18565 12253 18566 9499 18566 9491 18566 9491 18567 9499 18567 9197 18567 9491 18568 9197 18568 12240 18568 12240 18569 9197 18569 9184 18569 12240 18570 9184 18570 12241 18570 12241 18571 9184 18571 9492 18571 12241 18572 9492 18572 12243 18572 12243 18573 9492 18573 9493 18573 12243 18574 9493 18574 9494 18574 9494 18575 9493 18575 9188 18575 9494 18576 9188 18576 12245 18576 12245 18577 9188 18577 9189 18577 12245 18578 9189 18578 12246 18578 12246 18579 9189 18579 9190 18579 12246 18580 9190 18580 9495 18580 9495 18581 9190 18581 9496 18581 9495 18582 9496 18582 12247 18582 12247 18583 9496 18583 9497 18583 12247 18584 9497 18584 12249 18584 12249 18585 9497 18585 9498 18585 12249 18586 9498 18586 12251 18586 12251 18587 9498 18587 9195 18587 12251 18588 9195 18588 12253 18588 12253 18589 9195 18589 9499 18589 9500 18590 9501 18590 9640 18590 9640 18591 9501 18591 9503 18591 9640 18592 9503 18592 9502 18592 9502 18593 9503 18593 9456 18593 9502 18594 9456 18594 9641 18594 9641 18595 9456 18595 9505 18595 9641 18596 9505 18596 9504 18596 9504 18597 9505 18597 9458 18597 9504 18598 9458 18598 9643 18598 9643 18599 9458 18599 9460 18599 9643 18600 9460 18600 9642 18600 9642 18601 9460 18601 9506 18601 9642 18602 9506 18602 9507 18602 9507 18603 9506 18603 9508 18603 9507 18604 9508 18604 9509 18604 9509 18605 9508 18605 9510 18605 9509 18606 9510 18606 9512 18606 9512 18607 9510 18607 9511 18607 9512 18608 9511 18608 9645 18608 9645 18609 9511 18609 9513 18609 9645 18610 9513 18610 9514 18610 9514 18611 9513 18611 9462 18611 9514 18612 9462 18612 9500 18612 9500 18613 9462 18613 9501 18613 9646 18614 9476 18614 9515 18614 9515 18615 9476 18615 9477 18615 9515 18616 9477 18616 9516 18616 9516 18617 9477 18617 9463 18617 9516 18618 9463 18618 9517 18618 9517 18619 9463 18619 9518 18619 9517 18620 9518 18620 9647 18620 9647 18621 9518 18621 9519 18621 9647 18622 9519 18622 9520 18622 9520 18623 9519 18623 9466 18623 9520 18624 9466 18624 9521 18624 9521 18625 9466 18625 9468 18625 9521 18626 9468 18626 9648 18626 9648 18627 9468 18627 9522 18627 9648 18628 9522 18628 9653 18628 9653 18629 9522 18629 9471 18629 9653 18630 9471 18630 9650 18630 9650 18631 9471 18631 9472 18631 9650 18632 9472 18632 9651 18632 9651 18633 9472 18633 9474 18633 9651 18634 9474 18634 9649 18634 9649 18635 9474 18635 9523 18635 9649 18636 9523 18636 9646 18636 9646 18637 9523 18637 9476 18637 12264 18638 9217 18638 12266 18638 12266 18639 9217 18639 9209 18639 12266 18640 9209 18640 12254 18640 12254 18641 9209 18641 9525 18641 12254 18642 9525 18642 9524 18642 9524 18643 9525 18643 9526 18643 9524 18644 9526 18644 9527 18644 9527 18645 9526 18645 9528 18645 9527 18646 9528 18646 9529 18646 9529 18647 9528 18647 9530 18647 9529 18648 9530 18648 12257 18648 12257 18649 9530 18649 9531 18649 12257 18650 9531 18650 12258 18650 12258 18651 9531 18651 9532 18651 12258 18652 9532 18652 12259 18652 12259 18653 9532 18653 9212 18653 12259 18654 9212 18654 12260 18654 12260 18655 9212 18655 9213 18655 12260 18656 9213 18656 9533 18656 9533 18657 9213 18657 9534 18657 9533 18658 9534 18658 9535 18658 9535 18659 9534 18659 9215 18659 9535 18660 9215 18660 12264 18660 12264 18661 9215 18661 9217 18661 11716 18662 11715 18662 12279 18662 11705 18663 11704 18663 12286 18663 11700 18664 11689 18664 12275 18664 12275 18665 11689 18665 9536 18665 12275 18666 9536 18666 9540 18666 11726 18667 9537 18667 9538 18667 9538 18668 9537 18668 12275 18668 9538 18669 12275 18669 9539 18669 9539 18670 12275 18670 9540 18670 11699 18671 9541 18671 12274 18671 12274 18672 9541 18672 11697 18672 12274 18673 11697 18673 12275 18673 12275 18674 11697 18674 11701 18674 12275 18675 11701 18675 11700 18675 11694 18676 9542 18676 9543 18676 9543 18677 9542 18677 11692 18677 9543 18678 11692 18678 12274 18678 12274 18679 11692 18679 9544 18679 12274 18680 9544 18680 11699 18680 9548 18681 11690 18681 9547 18681 9547 18682 11690 18682 11696 18682 9547 18683 11696 18683 9543 18683 9543 18684 11696 18684 11695 18684 9543 18685 11695 18685 11694 18685 11707 18686 11710 18686 9545 18686 9545 18687 11710 18687 9546 18687 9545 18688 9546 18688 9547 18688 9547 18689 9546 18689 11708 18689 9547 18690 11708 18690 9548 18690 11704 18691 11703 18691 12286 18691 12286 18692 11703 18692 9549 18692 12286 18693 9549 18693 9545 18693 9545 18694 9549 18694 11706 18694 9545 18695 11706 18695 11707 18695 12292 18696 9552 18696 11702 18696 12292 18697 11702 18697 12286 18697 12286 18698 11702 18698 9550 18698 12286 18699 9550 18699 11705 18699 12292 18700 11722 18700 9551 18700 9551 18701 11711 18701 12292 18701 12292 18702 11711 18702 11712 18702 12292 18703 11712 18703 9552 18703 9553 18704 9555 18704 11721 18704 11721 18705 9555 18705 12280 18705 11721 18706 12280 18706 9554 18706 9553 18707 11725 18707 9555 18707 9555 18708 11725 18708 9556 18708 9555 18709 9556 18709 12292 18709 12292 18710 9556 18710 11724 18710 12292 18711 11724 18711 11722 18711 11715 18712 11714 18712 12279 18712 12279 18713 11714 18713 11720 18713 12279 18714 11720 18714 12280 18714 12280 18715 11720 18715 11719 18715 12280 18716 11719 18716 9554 18716 9557 18717 11729 18717 12278 18717 12278 18718 11729 18718 9558 18718 12278 18719 9558 18719 12279 18719 12279 18720 9558 18720 9559 18720 12279 18721 9559 18721 11716 18721 11731 18722 11730 18722 12277 18722 12277 18723 11730 18723 9560 18723 12277 18724 9560 18724 12278 18724 12278 18725 9560 18725 9561 18725 12278 18726 9561 18726 9557 18726 11726 18727 9562 18727 9537 18727 9537 18728 9562 18728 11727 18728 9537 18729 11727 18729 12277 18729 12277 18730 11727 18730 11728 18730 12277 18731 11728 18731 11731 18731 9563 18732 9564 18732 9569 18732 9569 18733 9564 18733 11758 18733 11750 18734 9565 18734 11749 18734 11749 18735 9565 18735 9569 18735 11749 18736 9569 18736 11748 18736 11748 18737 9569 18737 11758 18737 11764 18738 9566 18738 12269 18738 12269 18739 9566 18739 9567 18739 12269 18740 9567 18740 9569 18740 9569 18741 9567 18741 9568 18741 9569 18742 9568 18742 9563 18742 11764 18743 12269 18743 9570 18743 9570 18744 12269 18744 9571 18744 9570 18745 9571 18745 11763 18745 9574 18746 11760 18746 9571 18746 9571 18747 11760 18747 11761 18747 9571 18748 11761 18748 11763 18748 11736 18749 9572 18749 12288 18749 12288 18750 9572 18750 9573 18750 12288 18751 9573 18751 9574 18751 9574 18752 9573 18752 11738 18752 9574 18753 11738 18753 11760 18753 11736 18754 12288 18754 9575 18754 9575 18755 12288 18755 9578 18755 9575 18756 9578 18756 11734 18756 9576 18757 11740 18757 12281 18757 12281 18758 11740 18758 9577 18758 9577 18759 11741 18759 12281 18759 12281 18760 11741 18760 9579 18760 12281 18761 9579 18761 9578 18761 9578 18762 9579 18762 11733 18762 9578 18763 11733 18763 11734 18763 9582 18764 9580 18764 9581 18764 9582 18765 9581 18765 12281 18765 12281 18766 9581 18766 11747 18766 12281 18767 11747 18767 9576 18767 11743 18768 11744 18768 9584 18768 9584 18769 11744 18769 11745 18769 9584 18770 11745 18770 9582 18770 9582 18771 11745 18771 9583 18771 9582 18772 9583 18772 9580 18772 11743 18773 9584 18773 9585 18773 9585 18774 9584 18774 9586 18774 9585 18775 9586 18775 11756 18775 11756 18776 9586 18776 9587 18776 9587 18777 9586 18777 12285 18777 9587 18778 12285 18778 9589 18778 11750 18779 11752 18779 9565 18779 9565 18780 11752 18780 9588 18780 9565 18781 9588 18781 12285 18781 12285 18782 9588 18782 11754 18782 12285 18783 11754 18783 9589 18783 9590 18784 11780 18784 9591 18784 9591 18785 11780 18785 11781 18785 11774 18786 9610 18786 9592 18786 9592 18787 9610 18787 9591 18787 9592 18788 9591 18788 11782 18788 11782 18789 9591 18789 11781 18789 11787 18790 11789 18790 9593 18790 9593 18791 11789 18791 11791 18791 9593 18792 11791 18792 9591 18792 9591 18793 11791 18793 11790 18793 9591 18794 11790 18794 9590 18794 11787 18795 9593 18795 11786 18795 11786 18796 9593 18796 9594 18796 11786 18797 9594 18797 9595 18797 9597 18798 11783 18798 9594 18798 9594 18799 11783 18799 11784 18799 9594 18800 11784 18800 9595 18800 11796 18801 11799 18801 9596 18801 9596 18802 11799 18802 11797 18802 9596 18803 11797 18803 9597 18803 9597 18804 11797 18804 9598 18804 9597 18805 9598 18805 11783 18805 11796 18806 9596 18806 9599 18806 9599 18807 9596 18807 9600 18807 9599 18808 9600 18808 9601 18808 9602 18809 11801 18809 9603 18809 9603 18810 11801 18810 11800 18810 11800 18811 9604 18811 9603 18811 9603 18812 9604 18812 11792 18812 9603 18813 11792 18813 9600 18813 9600 18814 11792 18814 11794 18814 9600 18815 11794 18815 9601 18815 9607 18816 9605 18816 9606 18816 9607 18817 9606 18817 9603 18817 9603 18818 9606 18818 11802 18818 9603 18819 11802 18819 9602 18819 9608 18820 11770 18820 12271 18820 12271 18821 11770 18821 11771 18821 12271 18822 11771 18822 9607 18822 9607 18823 11771 18823 11772 18823 9607 18824 11772 18824 9605 18824 9608 18825 12271 18825 11768 18825 11768 18826 12271 18826 12270 18826 11768 18827 12270 18827 11766 18827 11766 18828 12270 18828 11779 18828 11779 18829 12270 18829 12284 18829 11779 18830 12284 18830 9609 18830 11774 18831 11776 18831 9610 18831 9610 18832 11776 18832 11777 18832 9610 18833 11777 18833 12284 18833 12284 18834 11777 18834 9611 18834 12284 18835 9611 18835 9609 18835 9622 18836 9614 18836 9619 18836 12193 18837 9612 18837 12192 18837 12192 18838 9612 18838 12422 18838 12192 18839 12422 18839 12423 18839 12454 18840 12199 18840 12434 18840 12434 18841 12199 18841 9613 18841 12434 18842 9613 18842 9616 18842 9619 18843 9614 18843 9613 18843 9613 18844 9614 18844 9615 18844 9613 18845 9615 18845 9616 18845 12441 18846 9617 18846 9624 18846 9624 18847 9617 18847 9618 18847 9624 18848 9618 18848 12197 18848 12197 18849 9618 18849 9620 18849 12197 18850 9620 18850 9619 18850 9619 18851 9620 18851 9621 18851 9619 18852 9621 18852 9622 18852 12423 18853 9623 18853 12192 18853 12192 18854 9623 18854 12438 18854 12192 18855 12438 18855 9624 18855 9624 18856 12438 18856 9625 18856 9624 18857 9625 18857 12441 18857 9626 18858 9639 18858 9627 18858 9627 18859 9639 18859 12037 18859 9627 18860 12037 18860 9679 18860 9679 18861 12037 18861 9628 18861 9679 18862 9628 18862 9681 18862 9681 18863 9628 18863 12040 18863 9681 18864 12040 18864 9682 18864 9682 18865 12040 18865 12042 18865 9682 18866 12042 18866 9629 18866 9629 18867 12042 18867 12043 18867 9629 18868 12043 18868 9631 18868 9631 18869 12043 18869 9630 18869 9631 18870 9630 18870 9632 18870 9632 18871 9630 18871 9633 18871 9632 18872 9633 18872 9684 18872 9684 18873 9633 18873 9634 18873 9684 18874 9634 18874 9686 18874 9686 18875 9634 18875 12047 18875 9686 18876 12047 18876 9636 18876 9636 18877 12047 18877 9635 18877 9636 18878 9635 18878 9638 18878 9638 18879 9635 18879 9637 18879 9638 18880 9637 18880 9626 18880 9626 18881 9637 18881 9639 18881 9644 18882 9640 18882 9502 18882 9500 18883 9640 18883 9644 18883 9644 18884 9504 18884 9643 18884 9641 18885 9504 18885 9644 18885 9502 18886 9641 18886 9644 18886 9644 18887 9507 18887 9509 18887 9642 18888 9507 18888 9644 18888 9643 18889 9642 18889 9644 18889 9644 18890 9645 18890 9514 18890 9512 18891 9645 18891 9644 18891 9509 18892 9512 18892 9644 18892 9514 18893 9500 18893 9644 18893 9652 18894 9515 18894 9516 18894 9646 18895 9515 18895 9652 18895 9652 18896 9647 18896 9520 18896 9517 18897 9647 18897 9652 18897 9516 18898 9517 18898 9652 18898 9652 18899 9648 18899 9653 18899 9521 18900 9648 18900 9652 18900 9520 18901 9521 18901 9652 18901 9652 18902 9651 18902 9649 18902 9650 18903 9651 18903 9652 18903 9653 18904 9650 18904 9652 18904 9649 18905 9646 18905 9652 18905 9687 18906 12141 18906 9689 18906 9689 18907 12141 18907 12144 18907 9689 18908 12144 18908 9691 18908 9691 18909 12144 18909 9654 18909 9691 18910 9654 18910 9692 18910 9692 18911 9654 18911 9656 18911 9692 18912 9656 18912 9655 18912 9655 18913 9656 18913 12134 18913 9655 18914 12134 18914 9657 18914 9657 18915 12134 18915 12136 18915 9657 18916 12136 18916 9694 18916 9694 18917 12136 18917 9658 18917 9694 18918 9658 18918 9695 18918 9695 18919 9658 18919 12138 18919 9695 18920 12138 18920 9696 18920 9696 18921 12138 18921 9659 18921 9696 18922 9659 18922 9697 18922 9697 18923 9659 18923 9660 18923 9697 18924 9660 18924 9661 18924 9661 18925 9660 18925 12139 18925 9661 18926 12139 18926 9662 18926 9662 18927 12139 18927 9663 18927 9662 18928 9663 18928 9687 18928 9687 18929 9663 18929 12141 18929 9711 18930 12252 18930 9713 18930 9713 18931 12252 18931 9664 18931 9713 18932 9664 18932 9715 18932 9715 18933 9664 18933 9665 18933 9715 18934 9665 18934 9716 18934 9716 18935 9665 18935 12242 18935 9716 18936 12242 18936 9666 18936 9666 18937 12242 18937 12244 18937 9666 18938 12244 18938 9667 18938 9667 18939 12244 18939 9668 18939 9667 18940 9668 18940 9718 18940 9718 18941 9668 18941 9669 18941 9718 18942 9669 18942 9720 18942 9720 18943 9669 18943 9670 18943 9720 18944 9670 18944 9671 18944 9671 18945 9670 18945 9672 18945 9671 18946 9672 18946 9724 18946 9724 18947 9672 18947 12248 18947 9724 18948 12248 18948 9725 18948 9725 18949 12248 18949 9673 18949 9725 18950 9673 18950 9674 18950 9674 18951 9673 18951 12250 18951 9674 18952 12250 18952 9711 18952 9711 18953 12250 18953 12252 18953 9675 18954 9638 18954 9676 18954 9676 18955 9638 18955 9626 18955 9676 18956 9626 18956 9677 18956 9677 18957 9626 18957 9627 18957 9677 18958 9627 18958 9678 18958 9678 18959 9627 18959 9679 18959 9678 18960 9679 18960 9727 18960 9727 18961 9679 18961 9681 18961 9727 18962 9681 18962 9680 18962 9680 18963 9681 18963 9682 18963 9680 18964 9682 18964 9729 18964 9729 18965 9682 18965 9629 18965 9729 18966 9629 18966 9683 18966 9683 18967 9629 18967 9631 18967 9683 18968 9631 18968 9728 18968 9728 18969 9631 18969 9632 18969 9728 18970 9632 18970 9731 18970 9731 18971 9632 18971 9684 18971 9731 18972 9684 18972 9730 18972 9730 18973 9684 18973 9686 18973 9730 18974 9686 18974 9685 18974 9685 18975 9686 18975 9636 18975 9685 18976 9636 18976 9675 18976 9675 18977 9636 18977 9638 18977 9741 18978 9662 18978 9688 18978 9688 18979 9662 18979 9687 18979 9688 18980 9687 18980 9734 18980 9734 18981 9687 18981 9689 18981 9734 18982 9689 18982 9690 18982 9690 18983 9689 18983 9691 18983 9690 18984 9691 18984 9733 18984 9733 18985 9691 18985 9692 18985 9733 18986 9692 18986 9737 18986 9737 18987 9692 18987 9655 18987 9737 18988 9655 18988 9736 18988 9736 18989 9655 18989 9657 18989 9736 18990 9657 18990 9735 18990 9735 18991 9657 18991 9694 18991 9735 18992 9694 18992 9693 18992 9693 18993 9694 18993 9695 18993 9693 18994 9695 18994 9738 18994 9738 18995 9695 18995 9696 18995 9738 18996 9696 18996 9739 18996 9739 18997 9696 18997 9697 18997 9739 18998 9697 18998 9740 18998 9740 18999 9697 18999 9661 18999 9740 19000 9661 19000 9741 19000 9741 19001 9661 19001 9662 19001 9744 19002 12263 19002 9698 19002 9698 19003 12263 19003 12265 19003 9698 19004 12265 19004 9746 19004 9746 19005 12265 19005 9699 19005 9746 19006 9699 19006 9748 19006 9748 19007 9699 19007 12255 19007 9748 19008 12255 19008 9700 19008 9700 19009 12255 19009 9701 19009 9700 19010 9701 19010 9750 19010 9750 19011 9701 19011 12256 19011 9750 19012 12256 19012 9702 19012 9702 19013 12256 19013 9703 19013 9702 19014 9703 19014 9705 19014 9705 19015 9703 19015 9704 19015 9705 19016 9704 19016 9706 19016 9706 19017 9704 19017 9707 19017 9706 19018 9707 19018 9755 19018 9755 19019 9707 19019 12261 19019 9755 19020 12261 19020 9709 19020 9709 19021 12261 19021 9708 19021 9709 19022 9708 19022 9742 19022 9742 19023 9708 19023 12262 19023 9742 19024 12262 19024 9744 19024 9744 19025 12262 19025 12263 19025 9761 19026 9674 19026 9710 19026 9710 19027 9674 19027 9711 19027 9710 19028 9711 19028 9712 19028 9712 19029 9711 19029 9713 19029 9712 19030 9713 19030 9757 19030 9757 19031 9713 19031 9715 19031 9757 19032 9715 19032 9714 19032 9714 19033 9715 19033 9716 19033 9714 19034 9716 19034 9760 19034 9760 19035 9716 19035 9666 19035 9760 19036 9666 19036 9759 19036 9759 19037 9666 19037 9667 19037 9759 19038 9667 19038 9717 19038 9717 19039 9667 19039 9718 19039 9717 19040 9718 19040 9719 19040 9719 19041 9718 19041 9720 19041 9719 19042 9720 19042 9721 19042 9721 19043 9720 19043 9671 19043 9721 19044 9671 19044 9722 19044 9722 19045 9671 19045 9724 19045 9722 19046 9724 19046 9723 19046 9723 19047 9724 19047 9725 19047 9723 19048 9725 19048 9761 19048 9761 19049 9725 19049 9674 19049 9726 19050 9676 19050 9677 19050 9675 19051 9676 19051 9726 19051 9726 19052 9727 19052 9680 19052 9678 19053 9727 19053 9726 19053 9677 19054 9678 19054 9726 19054 9726 19055 9683 19055 9728 19055 9729 19056 9683 19056 9726 19056 9680 19057 9729 19057 9726 19057 9726 19058 9730 19058 9685 19058 9731 19059 9730 19059 9726 19059 9728 19060 9731 19060 9726 19060 9685 19061 9675 19061 9726 19061 9732 19062 9688 19062 9734 19062 9741 19063 9688 19063 9732 19063 9732 19064 9733 19064 9737 19064 9690 19065 9733 19065 9732 19065 9734 19066 9690 19066 9732 19066 9732 19067 9735 19067 9693 19067 9736 19068 9735 19068 9732 19068 9737 19069 9736 19069 9732 19069 9732 19070 9739 19070 9740 19070 9738 19071 9739 19071 9732 19071 9693 19072 9738 19072 9732 19072 9740 19073 9741 19073 9732 19073 9756 19074 9742 19074 9763 19074 9763 19075 9742 19075 9744 19075 9763 19076 9744 19076 9743 19076 9743 19077 9744 19077 9698 19077 9743 19078 9698 19078 9745 19078 9745 19079 9698 19079 9746 19079 9745 19080 9746 19080 9747 19080 9747 19081 9746 19081 9748 19081 9747 19082 9748 19082 9749 19082 9749 19083 9748 19083 9700 19083 9749 19084 9700 19084 9751 19084 9751 19085 9700 19085 9750 19085 9751 19086 9750 19086 9764 19086 9764 19087 9750 19087 9702 19087 9764 19088 9702 19088 9752 19088 9752 19089 9702 19089 9705 19089 9752 19090 9705 19090 9753 19090 9753 19091 9705 19091 9706 19091 9753 19092 9706 19092 9754 19092 9754 19093 9706 19093 9755 19093 9754 19094 9755 19094 9765 19094 9765 19095 9755 19095 9709 19095 9765 19096 9709 19096 9756 19096 9756 19097 9709 19097 9742 19097 9758 19098 9710 19098 9712 19098 9761 19099 9710 19099 9758 19099 9758 19100 9714 19100 9760 19100 9757 19101 9714 19101 9758 19101 9712 19102 9757 19102 9758 19102 9758 19103 9717 19103 9719 19103 9759 19104 9717 19104 9758 19104 9760 19105 9759 19105 9758 19105 9758 19106 9722 19106 9723 19106 9721 19107 9722 19107 9758 19107 9719 19108 9721 19108 9758 19108 9723 19109 9761 19109 9758 19109 9762 19110 9763 19110 9743 19110 9756 19111 9763 19111 9762 19111 9762 19112 9747 19112 9749 19112 9745 19113 9747 19113 9762 19113 9743 19114 9745 19114 9762 19114 9762 19115 9764 19115 9752 19115 9751 19116 9764 19116 9762 19116 9749 19117 9751 19117 9762 19117 9762 19118 9754 19118 9765 19118 9753 19119 9754 19119 9762 19119 9752 19120 9753 19120 9762 19120 9765 19121 9756 19121 9762 19121 9067 19122 9766 19122 9767 19122 9767 19123 13385 19123 9067 19123 9067 19124 13385 19124 9768 19124 9067 19125 9768 19125 9070 19125 9769 19126 9775 19126 11612 19126 11612 19127 9775 19127 9770 19127 11612 19128 9770 19128 9774 19128 9774 19129 9770 19129 9771 19129 9771 19130 9772 19130 9774 19130 9774 19131 9772 19131 9773 19131 9774 19132 9773 19132 13372 19132 13385 19133 9771 19133 9768 19133 9768 19134 9771 19134 9770 19134 9768 19135 9770 19135 9070 19135 9070 19136 9770 19136 9775 19136 9070 19137 9775 19137 9071 19137 9071 19138 9775 19138 9769 19138 9071 19139 9769 19139 11610 19139 9776 19140 9782 19140 9777 19140 9036 19141 9035 19141 9777 19141 9781 19142 13391 19142 9779 19142 13391 19143 9778 19143 9779 19143 9779 19144 9778 19144 9991 19144 9779 19145 9991 19145 9060 19145 9779 19146 9780 19146 9781 19146 9781 19147 9780 19147 9058 19147 9781 19148 9058 19148 13373 19148 13373 19149 9058 19149 9783 19149 13373 19150 9783 19150 9782 19150 9782 19151 9783 19151 9784 19151 9782 19152 9784 19152 9777 19152 9777 19153 9784 19153 9785 19153 9777 19154 9785 19154 9036 19154 12051 19155 13375 19155 9786 19155 9776 19156 9777 19156 9786 19156 9786 19157 9777 19157 9787 19157 9786 19158 9787 19158 12051 19158 13447 19159 9793 19159 9790 19159 9790 19160 9793 19160 9794 19160 9788 19161 9019 19161 9789 19161 9789 19162 9019 19162 9023 19162 9789 19163 9023 19163 9849 19163 9789 19164 9790 19164 9788 19164 9788 19165 9790 19165 9794 19165 9788 19166 9794 19166 9019 19166 9019 19167 9794 19167 9792 19167 9791 19168 9017 19168 9016 19168 9791 19169 9016 19169 9794 19169 9794 19170 9016 19170 9015 19170 9794 19171 9015 19171 9792 19171 13447 19172 13446 19172 9793 19172 9793 19173 13446 19173 9795 19173 9793 19174 9795 19174 9794 19174 9794 19175 9795 19175 9963 19175 9794 19176 9963 19176 9791 19176 9796 19177 9797 19177 9799 19177 9801 19178 9798 19178 9799 19178 9799 19179 9798 19179 9800 19179 9799 19180 9800 19180 9796 19180 9799 19181 9010 19181 9801 19181 9801 19182 9010 19182 9009 19182 9801 19183 9009 19183 13420 19183 13418 19184 12110 19184 13417 19184 13417 19185 12110 19185 12109 19185 13420 19186 9009 19186 13419 19186 13419 19187 9009 19187 9802 19187 13419 19188 9802 19188 13418 19188 13418 19189 9802 19189 12110 19189 12110 19190 9802 19190 9803 19190 12110 19191 9803 19191 9804 19191 9803 19192 9012 19192 9804 19192 9804 19193 9012 19193 9001 19193 9804 19194 9001 19194 9805 19194 9805 19195 9001 19195 12122 19195 9806 19196 12113 19196 9809 19196 9808 19197 9827 19197 9807 19197 9807 19198 13432 19198 9808 19198 9808 19199 13432 19199 9810 19199 9808 19200 9810 19200 9809 19200 9809 19201 9810 19201 9811 19201 9809 19202 9811 19202 9806 19202 13414 19203 13413 19203 9825 19203 9825 19204 13413 19204 13412 19204 9825 19205 13412 19205 9827 19205 9827 19206 13412 19206 13410 19206 9827 19207 13410 19207 9807 19207 9828 19208 9812 19208 9824 19208 9824 19209 9812 19209 13414 19209 9828 19210 9824 19210 9813 19210 9813 19211 9824 19211 9823 19211 9813 19212 9823 19212 9898 19212 9814 19213 9815 19213 9820 19213 9820 19214 9815 19214 9821 19214 9820 19215 9821 19215 9816 19215 9817 19216 9819 19216 9969 19216 9969 19217 9819 19217 9818 19217 9969 19218 9818 19218 9971 19218 9971 19219 9818 19219 9965 19219 9965 19220 9818 19220 13335 19220 9965 19221 13335 19221 9964 19221 9817 19222 9882 19222 9819 19222 9819 19223 9882 19223 9814 19223 9819 19224 9814 19224 9818 19224 9818 19225 9814 19225 9820 19225 9818 19226 9820 19226 13335 19226 13335 19227 9820 19227 9816 19227 9822 19228 13330 19228 9821 19228 9821 19229 13330 19229 13331 19229 9821 19230 13331 19230 9816 19230 9815 19231 9898 19231 9821 19231 9821 19232 9898 19232 9823 19232 9821 19233 9823 19233 9822 19233 9822 19234 9823 19234 9824 19234 9822 19235 9824 19235 13329 19235 13414 19236 9825 19236 9824 19236 9824 19237 9825 19237 13328 19237 9824 19238 13328 19238 13329 19238 9809 19239 13215 19239 9808 19239 9808 19240 13215 19240 9826 19240 9808 19241 9826 19241 9827 19241 9827 19242 9826 19242 13214 19242 9827 19243 13214 19243 9825 19243 9825 19244 13214 19244 13216 19244 9825 19245 13216 19245 13328 19245 9885 19246 9894 19246 9896 19246 9003 19247 9865 19247 9843 19247 9840 19248 9833 19248 9842 19248 13407 19249 9828 19249 9813 19249 9882 19250 9817 19250 9871 19250 9871 19251 9817 19251 9969 19251 9871 19252 9969 19252 9870 19252 13407 19253 9813 19253 9829 19253 9829 19254 9813 19254 9899 19254 9829 19255 9899 19255 9897 19255 13404 19256 9830 19256 9831 19256 9831 19257 9830 19257 13426 19257 9831 19258 13426 19258 9895 19258 9895 19259 13426 19259 13406 19259 9895 19260 13406 19260 13405 19260 9831 19261 9893 19261 13404 19261 13404 19262 9893 19262 9832 19262 13404 19263 9832 19263 9835 19263 9842 19264 9833 19264 9832 19264 9832 19265 9833 19265 9834 19265 9832 19266 9834 19266 9835 19266 9837 19267 9839 19267 13421 19267 9836 19268 9007 19268 9838 19268 9838 19269 9007 19269 9837 19269 9838 19270 9837 19270 13402 19270 13402 19271 9837 19271 13421 19271 9839 19272 9797 19272 13421 19272 13421 19273 9797 19273 9796 19273 13421 19274 9796 19274 9800 19274 9838 19275 9840 19275 9836 19275 9836 19276 9840 19276 9842 19276 9836 19277 9842 19277 9841 19277 9841 19278 9842 19278 9890 19278 9841 19279 9890 19279 9020 19279 9020 19280 9890 19280 9021 19280 9843 19281 9864 19281 9003 19281 9003 19282 9864 19282 9844 19282 9003 19283 9844 19283 9002 19283 9002 19284 9844 19284 9845 19284 9864 19285 9862 19285 13442 19285 13442 19286 13444 19286 9864 19286 9864 19287 13444 19287 13443 19287 9864 19288 13443 19288 9844 19288 9844 19289 13443 19289 9846 19289 9844 19290 9846 19290 9845 19290 9845 19291 9846 19291 9847 19291 9845 19292 9847 19292 9023 19292 9023 19293 9847 19293 9848 19293 9023 19294 9848 19294 9849 19294 9850 19295 9907 19295 9856 19295 12437 19296 12440 19296 9851 19296 9851 19297 12440 19297 9852 19297 9851 19298 9852 19298 12439 19298 9851 19299 9908 19299 12437 19299 12437 19300 9908 19300 9853 19300 12437 19301 9853 19301 9854 19301 9854 19302 9853 19302 9907 19302 9854 19303 9907 19303 9855 19303 9855 19304 9907 19304 9850 19304 9855 19305 9850 19305 12436 19305 12436 19306 9850 19306 9859 19306 13438 19307 13437 19307 9856 19307 9856 19308 13437 19308 9857 19308 9856 19309 9857 19309 9850 19309 9850 19310 9857 19310 9858 19310 9850 19311 9858 19311 9859 19311 9859 19312 9858 19312 13439 19312 9859 19313 13439 19313 12435 19313 12435 19314 13439 19314 9860 19314 12435 19315 9860 19315 9861 19315 9861 19316 9860 19316 9862 19316 9861 19317 9862 19317 12433 19317 12433 19318 9862 19318 9864 19318 12433 19319 9864 19319 9863 19319 9863 19320 9864 19320 9843 19320 9863 19321 9843 19321 9889 19321 9889 19322 9843 19322 9865 19322 9889 19323 9865 19323 9005 19323 9894 19324 9867 19324 9866 19324 9867 19325 9894 19325 12459 19325 12459 19326 9894 19326 9885 19326 12459 19327 9885 19327 9883 19327 10044 19328 9878 19328 9868 19328 9868 19329 9878 19329 9869 19329 9868 19330 9869 19330 9870 19330 9870 19331 9869 19331 9880 19331 9870 19332 9880 19332 9871 19332 9815 19333 9814 19333 9872 19333 9872 19334 9814 19334 9873 19334 9872 19335 9873 19335 9874 19335 9874 19336 9873 19336 9881 19336 9874 19337 9881 19337 9875 19337 9875 19338 9881 19338 9879 19338 9875 19339 9879 19339 9884 19339 9884 19340 9879 19340 9877 19340 9884 19341 9877 19341 9876 19341 9876 19342 9877 19342 12461 19342 9876 19343 12461 19343 12460 19343 10044 19344 12461 19344 9878 19344 9878 19345 12461 19345 9877 19345 9878 19346 9877 19346 9869 19346 9869 19347 9877 19347 9879 19347 9869 19348 9879 19348 9880 19348 9880 19349 9879 19349 9881 19349 9880 19350 9881 19350 9871 19350 9871 19351 9881 19351 9873 19351 9871 19352 9873 19352 9882 19352 9882 19353 9873 19353 9814 19353 12460 19354 9883 19354 9876 19354 9876 19355 9883 19355 9885 19355 9876 19356 9885 19356 9884 19356 9884 19357 9885 19357 9896 19357 9884 19358 9896 19358 9875 19358 9875 19359 9896 19359 9886 19359 9875 19360 9886 19360 9874 19360 9874 19361 9886 19361 9887 19361 9874 19362 9887 19362 9872 19362 9872 19363 9887 19363 9888 19363 9872 19364 9888 19364 9815 19364 9815 19365 9888 19365 9898 19365 9005 19366 9021 19366 9889 19366 9889 19367 9021 19367 9890 19367 9889 19368 9890 19368 9891 19368 9891 19369 9890 19369 9842 19369 9891 19370 9842 19370 12456 19370 12456 19371 9842 19371 9832 19371 12456 19372 9832 19372 9892 19372 9892 19373 9832 19373 9893 19373 9892 19374 9893 19374 9866 19374 9866 19375 9893 19375 9831 19375 9866 19376 9831 19376 9894 19376 9894 19377 9831 19377 9895 19377 9894 19378 9895 19378 9896 19378 9896 19379 9895 19379 13405 19379 9896 19380 13405 19380 9886 19380 9886 19381 13405 19381 13409 19381 9886 19382 13409 19382 9887 19382 9887 19383 13409 19383 9897 19383 9887 19384 9897 19384 9888 19384 9888 19385 9897 19385 9899 19385 9888 19386 9899 19386 9898 19386 9898 19387 9899 19387 9813 19387 9900 19388 9901 19388 9902 19388 13451 19389 13438 19389 9856 19389 13433 19390 13436 19390 9914 19390 9914 19391 13436 19391 13451 19391 9921 19392 9919 19392 13433 19392 9936 19393 9900 19393 9903 19393 9903 19394 9900 19394 9902 19394 9903 19395 9902 19395 9919 19395 9919 19396 9902 19396 13434 19396 9919 19397 13434 19397 13433 19397 9904 19398 9934 19398 9938 19398 12439 19399 9905 19399 9906 19399 9906 19400 9905 19400 12421 19400 9906 19401 12421 19401 12413 19401 13451 19402 9856 19402 9914 19402 9914 19403 9856 19403 9907 19403 9914 19404 9907 19404 9916 19404 9916 19405 9907 19405 9853 19405 9916 19406 9853 19406 9909 19406 9909 19407 9853 19407 9908 19407 9909 19408 9908 19408 9933 19408 9920 19409 9904 19409 9910 19409 9910 19410 9904 19410 9938 19410 9910 19411 9938 19411 9936 19411 11260 19412 11259 19412 9911 19412 9911 19413 11259 19413 9912 19413 9911 19414 9912 19414 9922 19414 9922 19415 9912 19415 9913 19415 9922 19416 9913 19416 9920 19416 9920 19417 9913 19417 11263 19417 9920 19418 11263 19418 9904 19418 13433 19419 9914 19419 9921 19419 9921 19420 9914 19420 9916 19420 9921 19421 9916 19421 9915 19421 9915 19422 9916 19422 9909 19422 9915 19423 9909 19423 9917 19423 9917 19424 9909 19424 9933 19424 9917 19425 9933 19425 9918 19425 9918 19426 9933 19426 9932 19426 9918 19427 9932 19427 9931 19427 9936 19428 9903 19428 9910 19428 9910 19429 9903 19429 9919 19429 9910 19430 9919 19430 9920 19430 9920 19431 9919 19431 9921 19431 9920 19432 9921 19432 9922 19432 9922 19433 9921 19433 9915 19433 9922 19434 9915 19434 9911 19434 9911 19435 9915 19435 9917 19435 9911 19436 9917 19436 9924 19436 9924 19437 9917 19437 9918 19437 9924 19438 9918 19438 9925 19438 9925 19439 9918 19439 9931 19439 9925 19440 9931 19440 9927 19440 11260 19441 9911 19441 9923 19441 9923 19442 9911 19442 9924 19442 9923 19443 9924 19443 11261 19443 11261 19444 9924 19444 9925 19444 11261 19445 9925 19445 9926 19445 9926 19446 9925 19446 9927 19446 9926 19447 9927 19447 9928 19447 9929 19448 9928 19448 11651 19448 11651 19449 9928 19449 9927 19449 11651 19450 9927 19450 9930 19450 9930 19451 9927 19451 9931 19451 9930 19452 9931 19452 9906 19452 9906 19453 9931 19453 9932 19453 9906 19454 9932 19454 12439 19454 12439 19455 9932 19455 9933 19455 12439 19456 9933 19456 9851 19456 9851 19457 9933 19457 9908 19457 13445 19458 9901 19458 9900 19458 9938 19459 9934 19459 9939 19459 9935 19460 13445 19460 9948 19460 9948 19461 13445 19461 9900 19461 9948 19462 9900 19462 9949 19462 9949 19463 9900 19463 9936 19463 9949 19464 9936 19464 9937 19464 9937 19465 9936 19465 9938 19465 9937 19466 9938 19466 9958 19466 9958 19467 9938 19467 9939 19467 9958 19468 9939 19468 11262 19468 9945 19469 9947 19469 9954 19469 9791 19470 9940 19470 9017 19470 9017 19471 9940 19471 9962 19471 9017 19472 9962 19472 9941 19472 9941 19473 9962 19473 9025 19473 9962 19474 9942 19474 9025 19474 9025 19475 9942 19475 9943 19475 9025 19476 9943 19476 9000 19476 9000 19477 9943 19477 9959 19477 9000 19478 9959 19478 9944 19478 9963 19479 9795 19479 9945 19479 9945 19480 9795 19480 13446 19480 9945 19481 13446 19481 9946 19481 9946 19482 9935 19482 9945 19482 9945 19483 9935 19483 9948 19483 9945 19484 9948 19484 9947 19484 9947 19485 9948 19485 9949 19485 9947 19486 9949 19486 9937 19486 12128 19487 12131 19487 9950 19487 9950 19488 12131 19488 9960 19488 9950 19489 9960 19489 9956 19489 9956 19490 9960 19490 9961 19490 9956 19491 9961 19491 9952 19491 9952 19492 9961 19492 9951 19492 9952 19493 9951 19493 9957 19493 9957 19494 9951 19494 9954 19494 9957 19495 9954 19495 9953 19495 9953 19496 9954 19496 9947 19496 9953 19497 9947 19497 9955 19497 9955 19498 9947 19498 9937 19498 9955 19499 9937 19499 9958 19499 11270 19500 12128 19500 11271 19500 11271 19501 12128 19501 9950 19501 11271 19502 9950 19502 11273 19502 11273 19503 9950 19503 9956 19503 11273 19504 9956 19504 11274 19504 11274 19505 9956 19505 9952 19505 11274 19506 9952 19506 11275 19506 11275 19507 9952 19507 9957 19507 11275 19508 9957 19508 11276 19508 11276 19509 9957 19509 9953 19509 11276 19510 9953 19510 11267 19510 11267 19511 9953 19511 9955 19511 11267 19512 9955 19512 11265 19512 11265 19513 9955 19513 9958 19513 11265 19514 9958 19514 11262 19514 12131 19515 9959 19515 9960 19515 9960 19516 9959 19516 9943 19516 9960 19517 9943 19517 9961 19517 9961 19518 9943 19518 9942 19518 9961 19519 9942 19519 9951 19519 9951 19520 9942 19520 9962 19520 9951 19521 9962 19521 9954 19521 9954 19522 9962 19522 9940 19522 9954 19523 9940 19523 9945 19523 9945 19524 9940 19524 9791 19524 9945 19525 9791 19525 9963 19525 9969 19526 9970 19526 9967 19526 9965 19527 9964 19527 9966 19527 9965 19528 9966 19528 9971 19528 9967 19529 9970 19529 9968 19529 9969 19530 9971 19530 9970 19530 9970 19531 9971 19531 9986 19531 9970 19532 9986 19532 9968 19532 9968 19533 9986 19533 9987 19533 9972 19534 9973 19534 9988 19534 9988 19535 9973 19535 10046 19535 9988 19536 10046 19536 9987 19536 9987 19537 10046 19537 9974 19537 9987 19538 9974 19538 9968 19538 9983 19539 9048 19539 9976 19539 9976 19540 9048 19540 9975 19540 9975 19541 9977 19541 9976 19541 9976 19542 9977 19542 9046 19542 9976 19543 9046 19543 9984 19543 9981 19544 9044 19544 9983 19544 9983 19545 9044 19545 9043 19545 9983 19546 9043 19546 9048 19546 9041 19547 9040 19547 9978 19547 9978 19548 9040 19548 9033 19548 9978 19549 9033 19549 9981 19549 9981 19550 9033 19550 9045 19550 9981 19551 9045 19551 9044 19551 13189 19552 13190 19552 9979 19552 9979 19553 13190 19553 9980 19553 9979 19554 9980 19554 12062 19554 9979 19555 9041 19555 13189 19555 13189 19556 9041 19556 9978 19556 13189 19557 9978 19557 13186 19557 13186 19558 9978 19558 9981 19558 13186 19559 9981 19559 9982 19559 9982 19560 9981 19560 13184 19560 13184 19561 9981 19561 9983 19561 13184 19562 9983 19562 13296 19562 13296 19563 9983 19563 9976 19563 13296 19564 9976 19564 9972 19564 9972 19565 9976 19565 9984 19565 9972 19566 9984 19566 9973 19566 9971 19567 9966 19567 9986 19567 9986 19568 9966 19568 9985 19568 9986 19569 9985 19569 9987 19569 9987 19570 9985 19570 13301 19570 9987 19571 13301 19571 9988 19571 9988 19572 13301 19572 13299 19572 9988 19573 13299 19573 9972 19573 9972 19574 13299 19574 13298 19574 9972 19575 13298 19575 13296 19575 10021 19576 10020 19576 10057 19576 9996 19577 9989 19577 12427 19577 9968 19578 9974 19578 9990 19578 10046 19579 9973 19579 10050 19579 9991 19580 9778 19580 13381 19580 9992 19581 10037 19581 12452 19581 9993 19582 9994 19582 10071 19582 10071 19583 9994 19583 9076 19583 10071 19584 9076 19584 9995 19584 9993 19585 9989 19585 9078 19585 9078 19586 9989 19586 9996 19586 9078 19587 9996 19587 10033 19587 10034 19588 9997 19588 9998 19588 9998 19589 9997 19589 9073 19589 9073 19590 9997 19590 9074 19590 9074 19591 9997 19591 9999 19591 9074 19592 9999 19592 10000 19592 10000 19593 9999 19593 10001 19593 10000 19594 10001 19594 9083 19594 9083 19595 10001 19595 9066 19595 9066 19596 10001 19596 9767 19596 9066 19597 9767 19597 9766 19597 10037 19598 9992 19598 9997 19598 9997 19599 9992 19599 10002 19599 9997 19600 10002 19600 9999 19600 9999 19601 10002 19601 10003 19601 9999 19602 10003 19602 10001 19602 12450 19603 13382 19603 12452 19603 12452 19604 13382 19604 13396 19604 12452 19605 13396 19605 9992 19605 9992 19606 13396 19606 13384 19606 9992 19607 13384 19607 10002 19607 10008 19608 10004 19608 10032 19608 10032 19609 10004 19609 13389 19609 10032 19610 13389 19610 10005 19610 10009 19611 10006 19611 10007 19611 10032 19612 10009 19612 10008 19612 10008 19613 10009 19613 10007 19613 10008 19614 10007 19614 10013 19614 10013 19615 10007 19615 10011 19615 9060 19616 9991 19616 10010 19616 10010 19617 9991 19617 13381 19617 10010 19618 13381 19618 10011 19618 10011 19619 13381 19619 10012 19619 10011 19620 10012 19620 10013 19620 10030 19621 9054 19621 10009 19621 10009 19622 9054 19622 10014 19622 10009 19623 10014 19623 10006 19623 10018 19624 10015 19624 10030 19624 10030 19625 10015 19625 9055 19625 10030 19626 9055 19626 9054 19626 9061 19627 10016 19627 10029 19627 10029 19628 10016 19628 9052 19628 10029 19629 9052 19629 10018 19629 10018 19630 9052 19630 10017 19630 10018 19631 10017 19631 10015 19631 10059 19632 10020 19632 10019 19632 10019 19633 10020 19633 10021 19633 10019 19634 10021 19634 10022 19634 10022 19635 10021 19635 10023 19635 9049 19636 10024 19636 10056 19636 10056 19637 10024 19637 10023 19637 9984 19638 9046 19638 10025 19638 9870 19639 9969 19639 9967 19639 10063 19640 10061 19640 10026 19640 10026 19641 10061 19641 10027 19641 10026 19642 10027 19642 10028 19642 10028 19643 10027 19643 10029 19643 10028 19644 10029 19644 12443 19644 12443 19645 10029 19645 10018 19645 12443 19646 10018 19646 12446 19646 12446 19647 10018 19647 10030 19647 12446 19648 10030 19648 12447 19648 12447 19649 10030 19649 10009 19649 12447 19650 10009 19650 10031 19650 10031 19651 10009 19651 10032 19651 10031 19652 10032 19652 12450 19652 12450 19653 10032 19653 10005 19653 12450 19654 10005 19654 13382 19654 10033 19655 9996 19655 9075 19655 9075 19656 9996 19656 10035 19656 9075 19657 10035 19657 10034 19657 10034 19658 10035 19658 12430 19658 10034 19659 12430 19659 9997 19659 9997 19660 12430 19660 10036 19660 9997 19661 10036 19661 10037 19661 9993 19662 10071 19662 9989 19662 9989 19663 10071 19663 10038 19663 9989 19664 10038 19664 12427 19664 12426 19665 10042 19665 12424 19665 12424 19666 10042 19666 10075 19666 10038 19667 10039 19667 12427 19667 12427 19668 10039 19668 10073 19668 12427 19669 10073 19669 10040 19669 10040 19670 10073 19670 10041 19670 10040 19671 10041 19671 12426 19671 12426 19672 10041 19672 10074 19672 12426 19673 10074 19673 10042 19673 10062 19674 12461 19674 10043 19674 10043 19675 12461 19675 10044 19675 10043 19676 10044 19676 10054 19676 10054 19677 10044 19677 9868 19677 10054 19678 9868 19678 10052 19678 10052 19679 9868 19679 9870 19679 10052 19680 9870 19680 10045 19680 10045 19681 9870 19681 9967 19681 9974 19682 10046 19682 9990 19682 9990 19683 10046 19683 10050 19683 9990 19684 10050 19684 10053 19684 10053 19685 10050 19685 10047 19685 10053 19686 10047 19686 10048 19686 10048 19687 10047 19687 10049 19687 10048 19688 10049 19688 10058 19688 9973 19689 9984 19689 10050 19689 10050 19690 9984 19690 10055 19690 10050 19691 10055 19691 10047 19691 10047 19692 10055 19692 10051 19692 10047 19693 10051 19693 10049 19693 9967 19694 9968 19694 10045 19694 10045 19695 9968 19695 9990 19695 10045 19696 9990 19696 10052 19696 10052 19697 9990 19697 10053 19697 10052 19698 10053 19698 10054 19698 10054 19699 10053 19699 10048 19699 10054 19700 10048 19700 10043 19700 10043 19701 10048 19701 10058 19701 10043 19702 10058 19702 10062 19702 10025 19703 9049 19703 9984 19703 9984 19704 9049 19704 10056 19704 9984 19705 10056 19705 10055 19705 10055 19706 10056 19706 10023 19706 10055 19707 10023 19707 10051 19707 10051 19708 10023 19708 10021 19708 10051 19709 10021 19709 10049 19709 10049 19710 10021 19710 10057 19710 10049 19711 10057 19711 10058 19711 10058 19712 10057 19712 10060 19712 10058 19713 10060 19713 10062 19713 10019 19714 9061 19714 10059 19714 10059 19715 9061 19715 10029 19715 10059 19716 10029 19716 10020 19716 10020 19717 10029 19717 10027 19717 10020 19718 10027 19718 10057 19718 10057 19719 10027 19719 10061 19719 10057 19720 10061 19720 10060 19720 10060 19721 10061 19721 10063 19721 10060 19722 10063 19722 10062 19722 10062 19723 10063 19723 12442 19723 10062 19724 12442 19724 12461 19724 10042 19725 10074 19725 10096 19725 10064 19726 11229 19726 10065 19726 10067 19727 10066 19727 11597 19727 9079 19728 10066 19728 9081 19728 9081 19729 10066 19729 10067 19729 9081 19730 10067 19730 10068 19730 10068 19731 10067 19731 10069 19731 10068 19732 10069 19732 10091 19732 9082 19733 10092 19733 10070 19733 10070 19734 10092 19734 9995 19734 9995 19735 10092 19735 10071 19735 10071 19736 10092 19736 10072 19736 10071 19737 10072 19737 10038 19737 10038 19738 10072 19738 10039 19738 10039 19739 10072 19739 10095 19739 10039 19740 10095 19740 10073 19740 10096 19741 10074 19741 10095 19741 10095 19742 10074 19742 10041 19742 10095 19743 10041 19743 10073 19743 10042 19744 10096 19744 10075 19744 10075 19745 10096 19745 10098 19745 10075 19746 10098 19746 12420 19746 12420 19747 10098 19747 11580 19747 12420 19748 11580 19748 12407 19748 11597 19749 10064 19749 10082 19749 10082 19750 10064 19750 10065 19750 10082 19751 10065 19751 10083 19751 10083 19752 10065 19752 11231 19752 11231 19753 10076 19753 10083 19753 10083 19754 10076 19754 10077 19754 10083 19755 10077 19755 10084 19755 10084 19756 10077 19756 11233 19756 10084 19757 11233 19757 10078 19757 11233 19758 11234 19758 10078 19758 10078 19759 11234 19759 10079 19759 10078 19760 10079 19760 10086 19760 10086 19761 10079 19761 10080 19761 10086 19762 10080 19762 10088 19762 10088 19763 10080 19763 11237 19763 10088 19764 11237 19764 10081 19764 10081 19765 11237 19765 11582 19765 10081 19766 11582 19766 10089 19766 11597 19767 10082 19767 10067 19767 10067 19768 10082 19768 10083 19768 10067 19769 10083 19769 10069 19769 10069 19770 10083 19770 10084 19770 10069 19771 10084 19771 10093 19771 10093 19772 10084 19772 10078 19772 10093 19773 10078 19773 10085 19773 10085 19774 10078 19774 10086 19774 10085 19775 10086 19775 10094 19775 10094 19776 10086 19776 10088 19776 10094 19777 10088 19777 10087 19777 10087 19778 10088 19778 10081 19778 10087 19779 10081 19779 10097 19779 10097 19780 10081 19780 10089 19780 10097 19781 10089 19781 10090 19781 10091 19782 10069 19782 9082 19782 9082 19783 10069 19783 10093 19783 9082 19784 10093 19784 10092 19784 10092 19785 10093 19785 10085 19785 10092 19786 10085 19786 10072 19786 10072 19787 10085 19787 10094 19787 10072 19788 10094 19788 10095 19788 10095 19789 10094 19789 10087 19789 10095 19790 10087 19790 10096 19790 10096 19791 10087 19791 10097 19791 10096 19792 10097 19792 10098 19792 10098 19793 10097 19793 10090 19793 10098 19794 10090 19794 11580 19794 10099 19795 10100 19795 10278 19795 10316 19796 10101 19796 10233 19796 10339 19797 10210 19797 10340 19797 10102 19798 10246 19798 10244 19798 10309 19799 11007 19799 10308 19799 10103 19800 10308 19800 11003 19800 13056 19801 13057 19801 10177 19801 10991 19802 10104 19802 10135 19802 10117 19803 10115 19803 10105 19803 8849 19804 10256 19804 10259 19804 8834 19805 8833 19805 10172 19805 10106 19806 10107 19806 10237 19806 10237 19807 10107 19807 8854 19807 10241 19808 10243 19808 10251 19808 10251 19809 10243 19809 10253 19809 10341 19810 10340 19810 8848 19810 8848 19811 10340 19811 10210 19811 8848 19812 10210 19812 8847 19812 10129 19813 8844 19813 10128 19813 10128 19814 8844 19814 10108 19814 10128 19815 10108 19815 10109 19815 10109 19816 10108 19816 10110 19816 10109 19817 10110 19817 10210 19817 10210 19818 10110 19818 10111 19818 10210 19819 10111 19819 8847 19819 8845 19820 10120 19820 8846 19820 8846 19821 10120 19821 10112 19821 8846 19822 10112 19822 10118 19822 10125 19823 10113 19823 8960 19823 8960 19824 10113 19824 8843 19824 8960 19825 8843 19825 8963 19825 8963 19826 8843 19826 10105 19826 8963 19827 10105 19827 10114 19827 10114 19828 10105 19828 10115 19828 10114 19829 10115 19829 8959 19829 8959 19830 10115 19830 10117 19830 8959 19831 10117 19831 10116 19831 10116 19832 10117 19832 10118 19832 10116 19833 10118 19833 8958 19833 8958 19834 10118 19834 10112 19834 8958 19835 10112 19835 10119 19835 10119 19836 10112 19836 10120 19836 10121 19837 10122 19837 10123 19837 10123 19838 10122 19838 10124 19838 8960 19839 10121 19839 10125 19839 10125 19840 10121 19840 10123 19840 10125 19841 10123 19841 8840 19841 8840 19842 10123 19842 10124 19842 8840 19843 10124 19843 10437 19843 10208 19844 8955 19844 10109 19844 10109 19845 8955 19845 10126 19845 10126 19846 10127 19846 10109 19846 10109 19847 10127 19847 8957 19847 10109 19848 8957 19848 10128 19848 10128 19849 8957 19849 10120 19849 10128 19850 10120 19850 10129 19850 10129 19851 10120 19851 8845 19851 10129 19852 8845 19852 8844 19852 10215 19853 8954 19853 10217 19853 10446 19854 10130 19854 10131 19854 10131 19855 10130 19855 10448 19855 10131 19856 10448 19856 10221 19856 10335 19857 10445 19857 10226 19857 10226 19858 10445 19858 10132 19858 10226 19859 10132 19859 10223 19859 10223 19860 10132 19860 10446 19860 10223 19861 10446 19861 10133 19861 10133 19862 10446 19862 10131 19862 10134 19863 11071 19863 10334 19863 10334 19864 11071 19864 10991 19864 10334 19865 10991 19865 10335 19865 10335 19866 10991 19866 10135 19866 10335 19867 10135 19867 10445 19867 10134 19868 10334 19868 10136 19868 10136 19869 10334 19869 10332 19869 10136 19870 10332 19870 10137 19870 11062 19871 10138 19871 10298 19871 10298 19872 10138 19872 10139 19872 10298 19873 10139 19873 10140 19873 10140 19874 11067 19874 10298 19874 10298 19875 11067 19875 11066 19875 10298 19876 11066 19876 10332 19876 10332 19877 11066 19877 11065 19877 10332 19878 11065 19878 10137 19878 10142 19879 10141 19879 11043 19879 11041 19880 10141 19880 13058 19880 13058 19881 10141 19881 10142 19881 13058 19882 10142 19882 13086 19882 13086 19883 10142 19883 10143 19883 13057 19884 10143 19884 10178 19884 10178 19885 10143 19885 10142 19885 10178 19886 10142 19886 10181 19886 10181 19887 10142 19887 11043 19887 10181 19888 11043 19888 10182 19888 13056 19889 10177 19889 10144 19889 13052 19890 10145 19890 10146 19890 10146 19891 10145 19891 13054 19891 10146 19892 13054 19892 12806 19892 12806 19893 13054 19893 10147 19893 13054 19894 10144 19894 10147 19894 10147 19895 10144 19895 10177 19895 10147 19896 10177 19896 10148 19896 10148 19897 10177 19897 10149 19897 10150 19898 10180 19898 10151 19898 10183 19899 12803 19899 10150 19899 10152 19900 10154 19900 10279 19900 10279 19901 10154 19901 10153 19901 10153 19902 10154 19902 12797 19902 12797 19903 10154 19903 10155 19903 12797 19904 10155 19904 12796 19904 12796 19905 10155 19905 10156 19905 12796 19906 10156 19906 10157 19906 11007 19907 10309 19907 11019 19907 11019 19908 10309 19908 10299 19908 11019 19909 10299 19909 11017 19909 10250 19910 11017 19910 10158 19910 10159 19911 10160 19911 10161 19911 10161 19912 10160 19912 10162 19912 10161 19913 10162 19913 10249 19913 11021 19914 10163 19914 116247 19914 116247 19915 10163 19915 10164 19915 116247 19916 10164 19916 10166 19916 13229 19917 13232 19917 10229 19917 10229 19918 13232 19918 13233 19918 10229 19919 13233 19919 13234 19919 13240 19920 10166 19920 10165 19920 10165 19921 10166 19921 10164 19921 10165 19922 10164 19922 13239 19922 13239 19923 10164 19923 13236 19923 10246 19924 10102 19924 10167 19924 13224 19925 10168 19925 13225 19925 13225 19926 10168 19926 13223 19926 13223 19927 10168 19927 13221 19927 13221 19928 10168 19928 10236 19928 13221 19929 10236 19929 10169 19929 10416 19930 10170 19930 10235 19930 10235 19931 10170 19931 10171 19931 10238 19932 10239 19932 10172 19932 10172 19933 10239 19933 10240 19933 10172 19934 10240 19934 8834 19934 10172 19935 10173 19935 10238 19935 10238 19936 10173 19936 10174 19936 10238 19937 10174 19937 10235 19937 10235 19938 10174 19938 10175 19938 10235 19939 10175 19939 10416 19939 10183 19940 10184 19940 10197 19940 10197 19941 10184 19941 10185 19941 10197 19942 10185 19942 10198 19942 10296 19943 10294 19943 10176 19943 10176 19944 10294 19944 10293 19944 10176 19945 10293 19945 10196 19945 13057 19946 10178 19946 10177 19946 10177 19947 10178 19947 10179 19947 10177 19948 10179 19948 10149 19948 10180 19949 10149 19949 10151 19949 10151 19950 10149 19950 10179 19950 10151 19951 10179 19951 10186 19951 10186 19952 10179 19952 10178 19952 10186 19953 10178 19953 10187 19953 10187 19954 10178 19954 10181 19954 10187 19955 10181 19955 10189 19955 10189 19956 10181 19956 10182 19956 10189 19957 10182 19957 10191 19957 10183 19958 10150 19958 10184 19958 10184 19959 10150 19959 10151 19959 10184 19960 10151 19960 10185 19960 10185 19961 10151 19961 10186 19961 10185 19962 10186 19962 10198 19962 10198 19963 10186 19963 10187 19963 10198 19964 10187 19964 10188 19964 10188 19965 10187 19965 10189 19965 10188 19966 10189 19966 10190 19966 10190 19967 10189 19967 10191 19967 10190 19968 10191 19968 11029 19968 10330 19969 10329 19969 10192 19969 10192 19970 10329 19970 10194 19970 10192 19971 10194 19971 10193 19971 10193 19972 10194 19972 10195 19972 10193 19973 10195 19973 10295 19973 10290 19974 12803 19974 10196 19974 10196 19975 12803 19975 10183 19975 10196 19976 10183 19976 10176 19976 10176 19977 10183 19977 10197 19977 10176 19978 10197 19978 10296 19978 10296 19979 10197 19979 10198 19979 10296 19980 10198 19980 10297 19980 10297 19981 10198 19981 10188 19981 10297 19982 10188 19982 10199 19982 10199 19983 10188 19983 10190 19983 10199 19984 10190 19984 10200 19984 10200 19985 10190 19985 11029 19985 10200 19986 11029 19986 11329 19986 10287 19987 10201 19987 10286 19987 10101 19988 10202 19988 10233 19988 10233 19989 10202 19989 10203 19989 10233 19990 10203 19990 10204 19990 10204 19991 10203 19991 10207 19991 10204 19992 10207 19992 10206 19992 10323 19993 10206 19993 10205 19993 10205 19994 10206 19994 10207 19994 10205 19995 10207 19995 10321 19995 10321 19996 10207 19996 10203 19996 10321 19997 10203 19997 10320 19997 10320 19998 10203 19998 10202 19998 10201 19999 10287 19999 10272 19999 8954 20000 10208 20000 10217 20000 10217 20001 10208 20001 10109 20001 10217 20002 10109 20002 10209 20002 10209 20003 10109 20003 10210 20003 10209 20004 10210 20004 10219 20004 10219 20005 10210 20005 10339 20005 10219 20006 10339 20006 10211 20006 10212 20007 10337 20007 10287 20007 10287 20008 10337 20008 10213 20008 10287 20009 10213 20009 10272 20009 10272 20010 10213 20010 10338 20010 10453 20011 10214 20011 10220 20011 10220 20012 10214 20012 10215 20012 10220 20013 10215 20013 10216 20013 10216 20014 10215 20014 10217 20014 10216 20015 10217 20015 10222 20015 10222 20016 10217 20016 10209 20016 10222 20017 10209 20017 10218 20017 10218 20018 10209 20018 10219 20018 10218 20019 10219 20019 10224 20019 10224 20020 10219 20020 10211 20020 10224 20021 10211 20021 10225 20021 10453 20022 10220 20022 10221 20022 10221 20023 10220 20023 10216 20023 10221 20024 10216 20024 10131 20024 10131 20025 10216 20025 10222 20025 10131 20026 10222 20026 10133 20026 10133 20027 10222 20027 10218 20027 10133 20028 10218 20028 10223 20028 10223 20029 10218 20029 10224 20029 10223 20030 10224 20030 10226 20030 10226 20031 10224 20031 10225 20031 10226 20032 10225 20032 10335 20032 11017 20033 10299 20033 10158 20033 10158 20034 10299 20034 10300 20034 10158 20035 10300 20035 10248 20035 10163 20036 10227 20036 10164 20036 10164 20037 10227 20037 10229 20037 10164 20038 10229 20038 13236 20038 13236 20039 10229 20039 13234 20039 11021 20040 10159 20040 10163 20040 10163 20041 10159 20041 10161 20041 10163 20042 10161 20042 10227 20042 10227 20043 10161 20043 10228 20043 10227 20044 10228 20044 10229 20044 10229 20045 10228 20045 10167 20045 10229 20046 10167 20046 13229 20046 13229 20047 10167 20047 10102 20047 10230 20048 10231 20048 10232 20048 10232 20049 10231 20049 10316 20049 10232 20050 10316 20050 10283 20050 10283 20051 10316 20051 10233 20051 10283 20052 10233 20052 10285 20052 10285 20053 10233 20053 10204 20053 10285 20054 10204 20054 10288 20054 10288 20055 10204 20055 10206 20055 10288 20056 10206 20056 10234 20056 10234 20057 10206 20057 10323 20057 10171 20058 10169 20058 10235 20058 10235 20059 10169 20059 10236 20059 10235 20060 10236 20060 10238 20060 10238 20061 10236 20061 10237 20061 10238 20062 10237 20062 10239 20062 10239 20063 10237 20063 8854 20063 10239 20064 8854 20064 10240 20064 13224 20065 10102 20065 10168 20065 10168 20066 10102 20066 10244 20066 10168 20067 10244 20067 10236 20067 10236 20068 10244 20068 10243 20068 10236 20069 10243 20069 10237 20069 10237 20070 10243 20070 10241 20070 10237 20071 10241 20071 10106 20071 10106 20072 10241 20072 10251 20072 10253 20073 10243 20073 10242 20073 10242 20074 10243 20074 10244 20074 10242 20075 10244 20075 10245 20075 10245 20076 10244 20076 10246 20076 10245 20077 10246 20077 10254 20077 10254 20078 10246 20078 10167 20078 10254 20079 10167 20079 10247 20079 10247 20080 10167 20080 10228 20080 10247 20081 10228 20081 10248 20081 10248 20082 10228 20082 10161 20082 10248 20083 10161 20083 10158 20083 10158 20084 10161 20084 10249 20084 10158 20085 10249 20085 10250 20085 8852 20086 10251 20086 10307 20086 10307 20087 10251 20087 10253 20087 10307 20088 10253 20088 10252 20088 10252 20089 10253 20089 10242 20089 10252 20090 10242 20090 10304 20090 10304 20091 10242 20091 10245 20091 10304 20092 10245 20092 10303 20092 10303 20093 10245 20093 10254 20093 10303 20094 10254 20094 10302 20094 10302 20095 10254 20095 10247 20095 10302 20096 10247 20096 10255 20096 10255 20097 10247 20097 10248 20097 10256 20098 10257 20098 10259 20098 10259 20099 10257 20099 10258 20099 10259 20100 10258 20100 10260 20100 10260 20101 10258 20101 10261 20101 10260 20102 10261 20102 10271 20102 10271 20103 10261 20103 10306 20103 10271 20104 10306 20104 10270 20104 10270 20105 10306 20105 10305 20105 10270 20106 10305 20106 10263 20106 10263 20107 10305 20107 10262 20107 10263 20108 10262 20108 10264 20108 10264 20109 10262 20109 10265 20109 10264 20110 10265 20110 10267 20110 10267 20111 10265 20111 10301 20111 10267 20112 10301 20112 10266 20112 10311 20113 10282 20113 10266 20113 10266 20114 10282 20114 10268 20114 10266 20115 10268 20115 10267 20115 10267 20116 10268 20116 10269 20116 10267 20117 10269 20117 10264 20117 10264 20118 10269 20118 10284 20118 10264 20119 10284 20119 10263 20119 10263 20120 10284 20120 10286 20120 10263 20121 10286 20121 10270 20121 10270 20122 10286 20122 10201 20122 10270 20123 10201 20123 10271 20123 10271 20124 10201 20124 10272 20124 10271 20125 10272 20125 10260 20125 10260 20126 10272 20126 10338 20126 10260 20127 10338 20127 10259 20127 10103 20128 10099 20128 10273 20128 10273 20129 10099 20129 10278 20129 10273 20130 10278 20130 10310 20130 10310 20131 10278 20131 10312 20131 11023 20132 10157 20132 10274 20132 10274 20133 10157 20133 10156 20133 10274 20134 10156 20134 11003 20134 11003 20135 10156 20135 10155 20135 11003 20136 10155 20136 10103 20136 10103 20137 10155 20137 10154 20137 10103 20138 10154 20138 10099 20138 10099 20139 10154 20139 10152 20139 10099 20140 10152 20140 10100 20140 10100 20141 10152 20141 10275 20141 10275 20142 10276 20142 10100 20142 10100 20143 10276 20143 10277 20143 10100 20144 10277 20144 10278 20144 10278 20145 10277 20145 10281 20145 10278 20146 10281 20146 10312 20146 10312 20147 10281 20147 10313 20147 10279 20148 12799 20148 10152 20148 10152 20149 12799 20149 10280 20149 10152 20150 10280 20150 10275 20150 10275 20151 10280 20151 12800 20151 10275 20152 12800 20152 10276 20152 10276 20153 12800 20153 10325 20153 10276 20154 10325 20154 10277 20154 10277 20155 10325 20155 10327 20155 10277 20156 10327 20156 10281 20156 10281 20157 10327 20157 10328 20157 10281 20158 10328 20158 10313 20158 10313 20159 10328 20159 10314 20159 10282 20160 10230 20160 10268 20160 10268 20161 10230 20161 10232 20161 10268 20162 10232 20162 10269 20162 10269 20163 10232 20163 10283 20163 10269 20164 10283 20164 10284 20164 10284 20165 10283 20165 10285 20165 10284 20166 10285 20166 10286 20166 10286 20167 10285 20167 10288 20167 10286 20168 10288 20168 10287 20168 10287 20169 10288 20169 10234 20169 10287 20170 10234 20170 10212 20170 10212 20171 10234 20171 10323 20171 10289 20172 10290 20172 10326 20172 10326 20173 10290 20173 10196 20173 10326 20174 10196 20174 10291 20174 10291 20175 10196 20175 10293 20175 10291 20176 10293 20176 10292 20176 10292 20177 10293 20177 10294 20177 10292 20178 10294 20178 10295 20178 10295 20179 10294 20179 10296 20179 10295 20180 10296 20180 10193 20180 10193 20181 10296 20181 10297 20181 10193 20182 10297 20182 10192 20182 10192 20183 10297 20183 10199 20183 10192 20184 10199 20184 10330 20184 10330 20185 10199 20185 10200 20185 10330 20186 10200 20186 10298 20186 10298 20187 10200 20187 11329 20187 10298 20188 11329 20188 11062 20188 10299 20189 10311 20189 10300 20189 10300 20190 10311 20190 10266 20190 10300 20191 10266 20191 10248 20191 10248 20192 10266 20192 10301 20192 10248 20193 10301 20193 10255 20193 10255 20194 10301 20194 10265 20194 10255 20195 10265 20195 10302 20195 10302 20196 10265 20196 10262 20196 10302 20197 10262 20197 10303 20197 10303 20198 10262 20198 10305 20198 10303 20199 10305 20199 10304 20199 10304 20200 10305 20200 10306 20200 10304 20201 10306 20201 10252 20201 10252 20202 10306 20202 10261 20202 10252 20203 10261 20203 10307 20203 10307 20204 10261 20204 10258 20204 10307 20205 10258 20205 8852 20205 8852 20206 10258 20206 10257 20206 10308 20207 10103 20207 10309 20207 10309 20208 10103 20208 10273 20208 10309 20209 10273 20209 10299 20209 10299 20210 10273 20210 10310 20210 10299 20211 10310 20211 10311 20211 10311 20212 10310 20212 10312 20212 10311 20213 10312 20213 10282 20213 10282 20214 10312 20214 10313 20214 10282 20215 10313 20215 10230 20215 10230 20216 10313 20216 10314 20216 10230 20217 10314 20217 10231 20217 10231 20218 10314 20218 10315 20218 10231 20219 10315 20219 10316 20219 10316 20220 10315 20220 10317 20220 10316 20221 10317 20221 10101 20221 10101 20222 10317 20222 10318 20222 10101 20223 10318 20223 10202 20223 10202 20224 10318 20224 10319 20224 10202 20225 10319 20225 10320 20225 10320 20226 10319 20226 10331 20226 10320 20227 10331 20227 10321 20227 10321 20228 10331 20228 10333 20228 10321 20229 10333 20229 10205 20229 10205 20230 10333 20230 10322 20230 10205 20231 10322 20231 10323 20231 10323 20232 10322 20232 10324 20232 10323 20233 10324 20233 10212 20233 10212 20234 10324 20234 10336 20234 10212 20235 10336 20235 10337 20235 12800 20236 10289 20236 10325 20236 10325 20237 10289 20237 10326 20237 10325 20238 10326 20238 10327 20238 10327 20239 10326 20239 10291 20239 10327 20240 10291 20240 10328 20240 10328 20241 10291 20241 10292 20241 10328 20242 10292 20242 10314 20242 10314 20243 10292 20243 10295 20243 10314 20244 10295 20244 10315 20244 10315 20245 10295 20245 10195 20245 10315 20246 10195 20246 10317 20246 10317 20247 10195 20247 10194 20247 10317 20248 10194 20248 10318 20248 10318 20249 10194 20249 10329 20249 10318 20250 10329 20250 10319 20250 10319 20251 10329 20251 10330 20251 10319 20252 10330 20252 10331 20252 10331 20253 10330 20253 10298 20253 10331 20254 10298 20254 10333 20254 10333 20255 10298 20255 10332 20255 10333 20256 10332 20256 10322 20256 10322 20257 10332 20257 10334 20257 10322 20258 10334 20258 10324 20258 10324 20259 10334 20259 10335 20259 10324 20260 10335 20260 10336 20260 10336 20261 10335 20261 10225 20261 10336 20262 10225 20262 10337 20262 10337 20263 10225 20263 10211 20263 10337 20264 10211 20264 10213 20264 10213 20265 10211 20265 10339 20265 10213 20266 10339 20266 10338 20266 10338 20267 10339 20267 10340 20267 10338 20268 10340 20268 10259 20268 10259 20269 10340 20269 10341 20269 10259 20270 10341 20270 8849 20270 12664 20271 12660 20271 10440 20271 10390 20272 10342 20272 10388 20272 10343 20273 9221 20273 12656 20273 10346 20274 9229 20274 10344 20274 10362 20275 12594 20275 9229 20275 9229 20276 12594 20276 10345 20276 9229 20277 10345 20277 10344 20277 10344 20278 12595 20278 10346 20278 10346 20279 12595 20279 10347 20279 10346 20280 10347 20280 10342 20280 10342 20281 10347 20281 10348 20281 10342 20282 10348 20282 10388 20282 10351 20283 10349 20283 10354 20283 10350 20284 9228 20284 9227 20284 10351 20285 10354 20285 10355 20285 10375 20286 10352 20286 10353 20286 10354 20287 10356 20287 10355 20287 10355 20288 10356 20288 10357 20288 10355 20289 10357 20289 10358 20289 10358 20290 10357 20290 10360 20290 10358 20291 10360 20291 10359 20291 10359 20292 10360 20292 10361 20292 10359 20293 10361 20293 10362 20293 10362 20294 10361 20294 10363 20294 10362 20295 10363 20295 12594 20295 10364 20296 10365 20296 9221 20296 9221 20297 10365 20297 10366 20297 9221 20298 10366 20298 12656 20298 10350 20299 12622 20299 9228 20299 9228 20300 12622 20300 10367 20300 9228 20301 10367 20301 10368 20301 10353 20302 10352 20302 10369 20302 10367 20303 12651 20303 10368 20303 10368 20304 12651 20304 10370 20304 10368 20305 10370 20305 10364 20305 10364 20306 10370 20306 12653 20306 10364 20307 12653 20307 10365 20307 10349 20308 10351 20308 10371 20308 10371 20309 10351 20309 10369 20309 10371 20310 10369 20310 10372 20310 10405 20311 10373 20311 10353 20311 10353 20312 10373 20312 10374 20312 10353 20313 10374 20313 10375 20313 10352 20314 13453 20314 10369 20314 10369 20315 13453 20315 13452 20315 10369 20316 13452 20316 10372 20316 10372 20317 13452 20317 10376 20317 10372 20318 10376 20318 10377 20318 10377 20319 10376 20319 10379 20319 10377 20320 10379 20320 10378 20320 10378 20321 10379 20321 13459 20321 10504 20322 13461 20322 10398 20322 10385 20323 8969 20323 10394 20323 10394 20324 8969 20324 8970 20324 12656 20325 12659 20325 10343 20325 10343 20326 12659 20326 10380 20326 10343 20327 10380 20327 9224 20327 9224 20328 10380 20328 12664 20328 9224 20329 12664 20329 10381 20329 10381 20330 12664 20330 10440 20330 10381 20331 10440 20331 10382 20331 10382 20332 10440 20332 10383 20332 10382 20333 10383 20333 10385 20333 10385 20334 10383 20334 10384 20334 10385 20335 10384 20335 8969 20335 13485 20336 10399 20336 10386 20336 10386 20337 10399 20337 10387 20337 10386 20338 10387 20338 10402 20338 10402 20339 10387 20339 12625 20339 10402 20340 12625 20340 10403 20340 10388 20341 10389 20341 10390 20341 10390 20342 10389 20342 12604 20342 10390 20343 12604 20343 9233 20343 9233 20344 12604 20344 12602 20344 9233 20345 12602 20345 10353 20345 10353 20346 12602 20346 12601 20346 10353 20347 12601 20347 10405 20347 8971 20348 10392 20348 10391 20348 10391 20349 10392 20349 13490 20349 10391 20350 13490 20350 8985 20350 8985 20351 13490 20351 10393 20351 8985 20352 10393 20352 8970 20352 8970 20353 10393 20353 13492 20353 8970 20354 13492 20354 10394 20354 10394 20355 13492 20355 13488 20355 10394 20356 13488 20356 10395 20356 10395 20357 13488 20357 10396 20357 10395 20358 10396 20358 13489 20358 13487 20359 10504 20359 10397 20359 10397 20360 10504 20360 10398 20360 10397 20361 10398 20361 10400 20361 10400 20362 10398 20362 10399 20362 10400 20363 10399 20363 10401 20363 10401 20364 10399 20364 13485 20364 13489 20365 10402 20365 10395 20365 10395 20366 10402 20366 10403 20366 10395 20367 10403 20367 9227 20367 9227 20368 10403 20368 10404 20368 9227 20369 10404 20369 10350 20369 10399 20370 13457 20370 10387 20370 10387 20371 13457 20371 13455 20371 10387 20372 13455 20372 12598 20372 12598 20373 13455 20373 10373 20373 12598 20374 10373 20374 12599 20374 12599 20375 10373 20375 10405 20375 13242 20376 10406 20376 12725 20376 13240 20377 13242 20377 10166 20377 10166 20378 13242 20378 12725 20378 10166 20379 12725 20379 116247 20379 10406 20380 10407 20380 12725 20380 12725 20381 10407 20381 10408 20381 12725 20382 10408 20382 10409 20382 10408 20383 10410 20383 10409 20383 10409 20384 10410 20384 13243 20384 10409 20385 13243 20385 12688 20385 12688 20386 13243 20386 10411 20386 12688 20387 10411 20387 10413 20387 10413 20388 10411 20388 13247 20388 10413 20389 13247 20389 10412 20389 10412 20390 13245 20390 10413 20390 10413 20391 13245 20391 10414 20391 10413 20392 10414 20392 12710 20392 12710 20393 10414 20393 10415 20393 12710 20394 10415 20394 12704 20394 12704 20395 10415 20395 10416 20395 12704 20396 10416 20396 10175 20396 10417 20397 10173 20397 8832 20397 8832 20398 10173 20398 10172 20398 8832 20399 10172 20399 8833 20399 10175 20400 10174 20400 12704 20400 12704 20401 10174 20401 10173 20401 12704 20402 10173 20402 12703 20402 12703 20403 10173 20403 10417 20403 12703 20404 10417 20404 10418 20404 10418 20405 10417 20405 10419 20405 10418 20406 10419 20406 12691 20406 12691 20407 10419 20407 8831 20407 8831 20408 8837 20408 12691 20408 12691 20409 8837 20409 8836 20409 12691 20410 8836 20410 12697 20410 12697 20411 8836 20411 10420 20411 12697 20412 10420 20412 10421 20412 10420 20413 10422 20413 10421 20413 10421 20414 10422 20414 8835 20414 10421 20415 8835 20415 10423 20415 10423 20416 8835 20416 10424 20416 10423 20417 10424 20417 10425 20417 10425 20418 10424 20418 10426 20418 10426 20419 10424 20419 10427 20419 10426 20420 10427 20420 10430 20420 8839 20421 10428 20421 10429 20421 10429 20422 10428 20422 10430 20422 10429 20423 10430 20423 10431 20423 10431 20424 10430 20424 10427 20424 10124 20425 10122 20425 10436 20425 10432 20426 8838 20426 10433 20426 10433 20427 8838 20427 10434 20427 10433 20428 10434 20428 10436 20428 10436 20429 10434 20429 10435 20429 10436 20430 10435 20430 10124 20430 10124 20431 10435 20431 10437 20431 8839 20432 8838 20432 10428 20432 10428 20433 8838 20433 10432 20433 10428 20434 10432 20434 10438 20434 10438 20435 10432 20435 10439 20435 10440 20436 12660 20436 12673 20436 10432 20437 8964 20437 10439 20437 10439 20438 8964 20438 8968 20438 10439 20439 8968 20439 12673 20439 12673 20440 8968 20440 8966 20440 12673 20441 8966 20441 10440 20441 8980 20442 10214 20442 10453 20442 10490 20443 10441 20443 10536 20443 11002 20444 11000 20444 10442 20444 10442 20445 11000 20445 10491 20445 10443 20446 10135 20446 10444 20446 10444 20447 10135 20447 10104 20447 10443 20448 11002 20448 10135 20448 10135 20449 11002 20449 10442 20449 10135 20450 10442 20450 10445 20450 10445 20451 10442 20451 10488 20451 10445 20452 10488 20452 10132 20452 10132 20453 10488 20453 10446 20453 10446 20454 10488 20454 10130 20454 10130 20455 10488 20455 10447 20455 10130 20456 10447 20456 10448 20456 10454 20457 10449 20457 10450 20457 10450 20458 10449 20458 10451 20458 10450 20459 10451 20459 10476 20459 10476 20460 10451 20460 10487 20460 10487 20461 10451 20461 10452 20461 10487 20462 10452 20462 8981 20462 10448 20463 10447 20463 10221 20463 10221 20464 10447 20464 10487 20464 10221 20465 10487 20465 10453 20465 10453 20466 10487 20466 8981 20466 10453 20467 8981 20467 8980 20467 10450 20468 13503 20468 10454 20468 10454 20469 13503 20469 10455 20469 10454 20470 10455 20470 10456 20470 10456 20471 10455 20471 10457 20471 10456 20472 10457 20472 10458 20472 10468 20473 10470 20473 10463 20473 10463 20474 10470 20474 10462 20474 10457 20475 13501 20475 10458 20475 10458 20476 13501 20476 10459 20476 10458 20477 10459 20477 10460 20477 10460 20478 10459 20478 13499 20478 10460 20479 13499 20479 10462 20479 10462 20480 13499 20480 10461 20480 10462 20481 10461 20481 10463 20481 8973 20482 8974 20482 10464 20482 10464 20483 8974 20483 10465 20483 10464 20484 10465 20484 13497 20484 13497 20485 10465 20485 10466 20485 13497 20486 10466 20486 10467 20486 10467 20487 10466 20487 8976 20487 10467 20488 8976 20488 10468 20488 10468 20489 8976 20489 10469 20489 10468 20490 10469 20490 10470 20490 10464 20491 13495 20491 8973 20491 8973 20492 13495 20492 13494 20492 8973 20493 13494 20493 8983 20493 8983 20494 13494 20494 10392 20494 8983 20495 10392 20495 8971 20495 10477 20496 10471 20496 10516 20496 10516 20497 10471 20497 10472 20497 10516 20498 10472 20498 10473 20498 10485 20499 10474 20499 10487 20499 10487 20500 10474 20500 10475 20500 10487 20501 10475 20501 10476 20501 10477 20502 10516 20502 10478 20502 10478 20503 10516 20503 10518 20503 10478 20504 10518 20504 10479 20504 10479 20505 10518 20505 10513 20505 10479 20506 10513 20506 13500 20506 13500 20507 10513 20507 10510 20507 13500 20508 10510 20508 13498 20508 13498 20509 10510 20509 10480 20509 13498 20510 10480 20510 10481 20510 10481 20511 10480 20511 10507 20511 10481 20512 10507 20512 10482 20512 10482 20513 10507 20513 13496 20513 13496 20514 10507 20514 10506 20514 13496 20515 10506 20515 10483 20515 10483 20516 10506 20516 10484 20516 10483 20517 10484 20517 13493 20517 13493 20518 10484 20518 10504 20518 13493 20519 10504 20519 13487 20519 10473 20520 10485 20520 10516 20520 10516 20521 10485 20521 10487 20521 10516 20522 10487 20522 10486 20522 10486 20523 10487 20523 10447 20523 10486 20524 10447 20524 10489 20524 10489 20525 10447 20525 10488 20525 10489 20526 10488 20526 10536 20526 10536 20527 10488 20527 10442 20527 10536 20528 10442 20528 10490 20528 10490 20529 10442 20529 10491 20529 13473 20530 13472 20530 10510 20530 10495 20531 10571 20531 8929 20531 10492 20532 8931 20532 10532 20532 10532 20533 8931 20533 10494 20533 10493 20534 13481 20534 10494 20534 10532 20535 10533 20535 10611 20535 8929 20536 10492 20536 10495 20536 10495 20537 10492 20537 10532 20537 10495 20538 10532 20538 10666 20538 10666 20539 10532 20539 10611 20539 10496 20540 10497 20540 10534 20540 10534 20541 10497 20541 10614 20541 10534 20542 10614 20542 10533 20542 10533 20543 10614 20543 10612 20543 10533 20544 10612 20544 10611 20544 10955 20545 10959 20545 10498 20545 10498 20546 10959 20546 10499 20546 10498 20547 10499 20547 10610 20547 10956 20548 10500 20548 10535 20548 10496 20549 10534 20549 10501 20549 10501 20550 10534 20550 10535 20550 10501 20551 10535 20551 10498 20551 10498 20552 10535 20552 10500 20552 10498 20553 10500 20553 10955 20553 10441 20554 10502 20554 10535 20554 10535 20555 10502 20555 10503 20555 10535 20556 10503 20556 10956 20556 13461 20557 10504 20557 13462 20557 13462 20558 10504 20558 10484 20558 13462 20559 10484 20559 13463 20559 13463 20560 10484 20560 10505 20560 10505 20561 10484 20561 10506 20561 10505 20562 10506 20562 13464 20562 10507 20563 13467 20563 13465 20563 10507 20564 13465 20564 10506 20564 10506 20565 13465 20565 10508 20565 10506 20566 10508 20566 13464 20566 13467 20567 10507 20567 10509 20567 10509 20568 10507 20568 10480 20568 10509 20569 10480 20569 13470 20569 10510 20570 13472 20570 10480 20570 10480 20571 13472 20571 13471 20571 10480 20572 13471 20572 13470 20572 13473 20573 10510 20573 10511 20573 10511 20574 10510 20574 10513 20574 10511 20575 10513 20575 10512 20575 10512 20576 10513 20576 13475 20576 13475 20577 10513 20577 10518 20577 13475 20578 10518 20578 10514 20578 10494 20579 13481 20579 10532 20579 10532 20580 13481 20580 10515 20580 10532 20581 10515 20581 13480 20581 13480 20582 13482 20582 10532 20582 10532 20583 13482 20583 13484 20583 10532 20584 13484 20584 10531 20584 13478 20585 10517 20585 10516 20585 10516 20586 10517 20586 13479 20586 10516 20587 13479 20587 10518 20587 10518 20588 13479 20588 13477 20588 10518 20589 13477 20589 10514 20589 10494 20590 10519 20590 10493 20590 10493 20591 10519 20591 8932 20591 10493 20592 8932 20592 13476 20592 13476 20593 8932 20593 10520 20593 13476 20594 10520 20594 13474 20594 13474 20595 10520 20595 10521 20595 13474 20596 10521 20596 10525 20596 10525 20597 10521 20597 8934 20597 10522 20598 13468 20598 10523 20598 10523 20599 13468 20599 13469 20599 10523 20600 13469 20600 8934 20600 8934 20601 13469 20601 10524 20601 8934 20602 10524 20602 10525 20602 10523 20603 8936 20603 10522 20603 10522 20604 8936 20604 10526 20604 10522 20605 10526 20605 13466 20605 13466 20606 10526 20606 10527 20606 13466 20607 10527 20607 10528 20607 10528 20608 10527 20608 10529 20608 10528 20609 10529 20609 13458 20609 13458 20610 10529 20610 8940 20610 13458 20611 8940 20611 10530 20611 10530 20612 8940 20612 8938 20612 10530 20613 8938 20613 13460 20613 8938 20614 8937 20614 13460 20614 13460 20615 8937 20615 10378 20615 13460 20616 10378 20616 13459 20616 10531 20617 13478 20617 10532 20617 10532 20618 13478 20618 10516 20618 10532 20619 10516 20619 10533 20619 10533 20620 10516 20620 10486 20620 10533 20621 10486 20621 10534 20621 10534 20622 10486 20622 10489 20622 10534 20623 10489 20623 10535 20623 10535 20624 10489 20624 10536 20624 10535 20625 10536 20625 10441 20625 10537 20626 10538 20626 12538 20626 10538 20627 10539 20627 10556 20627 10556 20628 10539 20628 10540 20628 10556 20629 10540 20629 8884 20629 10537 20630 12538 20630 8886 20630 8886 20631 12538 20631 10541 20631 8886 20632 10541 20632 8871 20632 8871 20633 10541 20633 12535 20633 8871 20634 12535 20634 10542 20634 10543 20635 10544 20635 10545 20635 10545 20636 10544 20636 10548 20636 10542 20637 12535 20637 8872 20637 8872 20638 12535 20638 12534 20638 8872 20639 12534 20639 10546 20639 10546 20640 12534 20640 12545 20640 10546 20641 12545 20641 10548 20641 10548 20642 12545 20642 10547 20642 10548 20643 10547 20643 10545 20643 8912 20644 10549 20644 8913 20644 8913 20645 10549 20645 8882 20645 8913 20646 8882 20646 8911 20646 8911 20647 8882 20647 8881 20647 8911 20648 8881 20648 8910 20648 10543 20649 10545 20649 10551 20649 10551 20650 10545 20650 10550 20650 10551 20651 10550 20651 10552 20651 8881 20652 10551 20652 8910 20652 8910 20653 10551 20653 10552 20653 8910 20654 10552 20654 10553 20654 10553 20655 10552 20655 10554 20655 10553 20656 10554 20656 10555 20656 10555 20657 10554 20657 12558 20657 10555 20658 12558 20658 8909 20658 8909 20659 12558 20659 12551 20659 8909 20660 12551 20660 10357 20660 10357 20661 12551 20661 10360 20661 10538 20662 10556 20662 12538 20662 12538 20663 10556 20663 10557 20663 12538 20664 10557 20664 12540 20664 12540 20665 10557 20665 10642 20665 12540 20666 10642 20666 10558 20666 10558 20667 10642 20667 10641 20667 10558 20668 10641 20668 10643 20668 10643 20669 13251 20669 10558 20669 10558 20670 13251 20670 13253 20670 10558 20671 13253 20671 10559 20671 13253 20672 13255 20672 10559 20672 10559 20673 13255 20673 10561 20673 10559 20674 10561 20674 10560 20674 10560 20675 10561 20675 13258 20675 10560 20676 13258 20676 12514 20676 12514 20677 13258 20677 10562 20677 12514 20678 10562 20678 10916 20678 10916 20679 10562 20679 13261 20679 13261 20680 13263 20680 10916 20680 10916 20681 13263 20681 13265 20681 10916 20682 13265 20682 10563 20682 10563 20683 10564 20683 10916 20683 10916 20684 10564 20684 10565 20684 10916 20685 10565 20685 116206 20685 116206 20686 10565 20686 10566 20686 116206 20687 10566 20687 13286 20687 10795 20688 10793 20688 10751 20688 10722 20689 10576 20689 10706 20689 10775 20690 10705 20690 10774 20690 10567 20691 10672 20691 10568 20691 10799 20692 10693 20692 10798 20692 10798 20693 10693 20693 10797 20693 10620 20694 10569 20694 10634 20694 10629 20695 10628 20695 10627 20695 8917 20696 10619 20696 10617 20696 8925 20697 10631 20697 8924 20697 8923 20698 10570 20698 10665 20698 8930 20699 10571 20699 10495 20699 116206 20700 10740 20700 10572 20700 10572 20701 10740 20701 10739 20701 10572 20702 10739 20702 10737 20702 10573 20703 10922 20703 10772 20703 10577 20704 10578 20704 10704 20704 10704 20705 10578 20705 10910 20705 10704 20706 10910 20706 10703 20706 10703 20707 10910 20707 10911 20707 10703 20708 10911 20708 10574 20708 10574 20709 10911 20709 10575 20709 10574 20710 10575 20710 10573 20710 10576 20711 115938 20711 10706 20711 10706 20712 115938 20712 10906 20712 10706 20713 10906 20713 10577 20713 10577 20714 10906 20714 10902 20714 10577 20715 10902 20715 10578 20715 10576 20716 10725 20716 115938 20716 115938 20717 10725 20717 12829 20717 115938 20718 12829 20718 10579 20718 12827 20719 10723 20719 10580 20719 10580 20720 10723 20720 10581 20720 10580 20721 10581 20721 12824 20721 12824 20722 10583 20722 10582 20722 10582 20723 10583 20723 10714 20723 10582 20724 10714 20724 12822 20724 12822 20725 10714 20725 10584 20725 12822 20726 10584 20726 10585 20726 10585 20727 10584 20727 10713 20727 10585 20728 10713 20728 12818 20728 10586 20729 12819 20729 10675 20729 12817 20730 10690 20730 10587 20730 10587 20731 10690 20731 10588 20731 10587 20732 10588 20732 10589 20732 10588 20733 12886 20733 10590 20733 10591 20734 12949 20734 10593 20734 10588 20735 10590 20735 10589 20735 10589 20736 10590 20736 12889 20736 10589 20737 12889 20737 12815 20737 12815 20738 12889 20738 10591 20738 12815 20739 10591 20739 10592 20739 10592 20740 10591 20740 10593 20740 10592 20741 10593 20741 12812 20741 10594 20742 10711 20742 12951 20742 10691 20743 10595 20743 12884 20743 12884 20744 10595 20744 10594 20744 12884 20745 10594 20745 10596 20745 10596 20746 10594 20746 12951 20746 10597 20747 10683 20747 10711 20747 10782 20748 10830 20748 10683 20748 10827 20749 10598 20749 10802 20749 10802 20750 10598 20750 10837 20750 10802 20751 10837 20751 10825 20751 10604 20752 10599 20752 10801 20752 10801 20753 10599 20753 10600 20753 10604 20754 10680 20754 10601 20754 10601 20755 10808 20755 10604 20755 10604 20756 10808 20756 10812 20756 10604 20757 10812 20757 10602 20757 10602 20758 10603 20758 10604 20758 10604 20759 10603 20759 10605 20759 10604 20760 10605 20760 10606 20760 10606 20761 10816 20761 10604 20761 10604 20762 10816 20762 10607 20762 10604 20763 10607 20763 10599 20763 10804 20764 10805 20764 10608 20764 10608 20765 10805 20765 10609 20765 10608 20766 10609 20766 10680 20766 10680 20767 10609 20767 10807 20767 10680 20768 10807 20768 10601 20768 10498 20769 10610 20769 10804 20769 10670 20770 10615 20770 10501 20770 10501 20771 10615 20771 10496 20771 10666 20772 10611 20772 10613 20772 10613 20773 10611 20773 10612 20773 10613 20774 10612 20774 10667 20774 10667 20775 10612 20775 10614 20775 10667 20776 10614 20776 10615 20776 10615 20777 10614 20777 10497 20777 10615 20778 10497 20778 10496 20778 8927 20779 10616 20779 10654 20779 10654 20780 10616 20780 8928 20780 8878 20781 10617 20781 10618 20781 10618 20782 10617 20782 10619 20782 10618 20783 10619 20783 10620 20783 10620 20784 10619 20784 10632 20784 10620 20785 10632 20785 10569 20785 10549 20786 8912 20786 10621 20786 10621 20787 8912 20787 10622 20787 8917 20788 10617 20788 8918 20788 8918 20789 10617 20789 8878 20789 8918 20790 8878 20790 10623 20790 10623 20791 8878 20791 10625 20791 10623 20792 10625 20792 10624 20792 10624 20793 10625 20793 8880 20793 10624 20794 8880 20794 10626 20794 10626 20795 8880 20795 10627 20795 10626 20796 10627 20796 8916 20796 8916 20797 10627 20797 10628 20797 8916 20798 10628 20798 10622 20798 10622 20799 10628 20799 10629 20799 10622 20800 10629 20800 10621 20800 10630 20801 10631 20801 10638 20801 10638 20802 10631 20802 8925 20802 10638 20803 8925 20803 8926 20803 10632 20804 10633 20804 10569 20804 10569 20805 10633 20805 8922 20805 10569 20806 8922 20806 10634 20806 10634 20807 8922 20807 8920 20807 10634 20808 8920 20808 8877 20808 8877 20809 8920 20809 8924 20809 8877 20810 8924 20810 10635 20810 10635 20811 8924 20811 10631 20811 10635 20812 10631 20812 10636 20812 10636 20813 10631 20813 10630 20813 10649 20814 10637 20814 8904 20814 8904 20815 8906 20815 10649 20815 10649 20816 8906 20816 8905 20816 10649 20817 8905 20817 10638 20817 10638 20818 8905 20818 8873 20818 10638 20819 8873 20819 10630 20819 10556 20820 8884 20820 10727 20820 10556 20821 10727 20821 10557 20821 10557 20822 10727 20822 10728 20822 10557 20823 10728 20823 10639 20823 10640 20824 10641 20824 10639 20824 10639 20825 10641 20825 10642 20825 10639 20826 10642 20826 10557 20826 10644 20827 13270 20827 10640 20827 10640 20828 13270 20828 10643 20828 10640 20829 10643 20829 10641 20829 13280 20830 13273 20830 10644 20830 10644 20831 13273 20831 13276 20831 10644 20832 13276 20832 13270 20832 13283 20833 13282 20833 10738 20833 13283 20834 10738 20834 13287 20834 10645 20835 10646 20835 10647 20835 10647 20836 10646 20836 10764 20836 10647 20837 10764 20837 10648 20837 10637 20838 10649 20838 10650 20838 10650 20839 10649 20839 10651 20839 10650 20840 10651 20840 10652 20840 10652 20841 10651 20841 10656 20841 10652 20842 10656 20842 10645 20842 10645 20843 10656 20843 10658 20843 10645 20844 10658 20844 10646 20844 10646 20845 10658 20845 10659 20845 10646 20846 10659 20846 10764 20846 10764 20847 10659 20847 10653 20847 10764 20848 10653 20848 10763 20848 8926 20849 8927 20849 10638 20849 10638 20850 8927 20850 10654 20850 10638 20851 10654 20851 10649 20851 10649 20852 10654 20852 10661 20852 10649 20853 10661 20853 10651 20853 10651 20854 10661 20854 10655 20854 10651 20855 10655 20855 10656 20855 10656 20856 10655 20856 10664 20856 10656 20857 10664 20857 10658 20857 10658 20858 10664 20858 10657 20858 10658 20859 10657 20859 10659 20859 10659 20860 10657 20860 10660 20860 10659 20861 10660 20861 10653 20861 10653 20862 10660 20862 10762 20862 10653 20863 10762 20863 10763 20863 8928 20864 8923 20864 10654 20864 10654 20865 8923 20865 10665 20865 10654 20866 10665 20866 10661 20866 10661 20867 10665 20867 10662 20867 10661 20868 10662 20868 10655 20868 10655 20869 10662 20869 10663 20869 10655 20870 10663 20870 10664 20870 10664 20871 10663 20871 10668 20871 10664 20872 10668 20872 10657 20872 10657 20873 10668 20873 10669 20873 10657 20874 10669 20874 10660 20874 10660 20875 10669 20875 10761 20875 10660 20876 10761 20876 10762 20876 8923 20877 8930 20877 10570 20877 10570 20878 8930 20878 10495 20878 10570 20879 10495 20879 10665 20879 10665 20880 10495 20880 10666 20880 10665 20881 10666 20881 10662 20881 10662 20882 10666 20882 10613 20882 10662 20883 10613 20883 10663 20883 10663 20884 10613 20884 10667 20884 10663 20885 10667 20885 10668 20885 10668 20886 10667 20886 10615 20886 10668 20887 10615 20887 10669 20887 10669 20888 10615 20888 10670 20888 10669 20889 10670 20889 10761 20889 10677 20890 10671 20890 10679 20890 10672 20891 10567 20891 10673 20891 10673 20892 10567 20892 10674 20892 10673 20893 10674 20893 10678 20893 12817 20894 10586 20894 10690 20894 10690 20895 10586 20895 10675 20895 10690 20896 10675 20896 10689 20896 10689 20897 10675 20897 12819 20897 10689 20898 12819 20898 10713 20898 10713 20899 12819 20899 10676 20899 10713 20900 10676 20900 12818 20900 10671 20901 10677 20901 10678 20901 10678 20902 10677 20902 10681 20902 10678 20903 10681 20903 10673 20903 10673 20904 10681 20904 10682 20904 10673 20905 10682 20905 10672 20905 10672 20906 10682 20906 10800 20906 10672 20907 10800 20907 10568 20907 10498 20908 10804 20908 10679 20908 10679 20909 10804 20909 10608 20909 10679 20910 10608 20910 10677 20910 10677 20911 10608 20911 10680 20911 10677 20912 10680 20912 10681 20912 10681 20913 10680 20913 10604 20913 10681 20914 10604 20914 10682 20914 10682 20915 10604 20915 10801 20915 10682 20916 10801 20916 10800 20916 10683 20917 10597 20917 10782 20917 10782 20918 10597 20918 10684 20918 10782 20919 10684 20919 10781 20919 10781 20920 10684 20920 10685 20920 10781 20921 10685 20921 10686 20921 10686 20922 10685 20922 10687 20922 10686 20923 10687 20923 10778 20923 10778 20924 10687 20924 10688 20924 10778 20925 10688 20925 10776 20925 10689 20926 10712 20926 10690 20926 10690 20927 10712 20927 10595 20927 10690 20928 10595 20928 10588 20928 10588 20929 10595 20929 10691 20929 10588 20930 10691 20930 12886 20930 10791 20931 10792 20931 10692 20931 10692 20932 10792 20932 10794 20932 10692 20933 10794 20933 10699 20933 10699 20934 10794 20934 10797 20934 10699 20935 10797 20935 10700 20935 10700 20936 10797 20936 10693 20936 10700 20937 10693 20937 10777 20937 10777 20938 10693 20938 10799 20938 10777 20939 10799 20939 10779 20939 10697 20940 10694 20940 10695 20940 10695 20941 10694 20941 10698 20941 10695 20942 10698 20942 10701 20942 10709 20943 10705 20943 10708 20943 10708 20944 10705 20944 10775 20944 10708 20945 10775 20945 10696 20945 10790 20946 10791 20946 10697 20946 10697 20947 10791 20947 10692 20947 10697 20948 10692 20948 10694 20948 10694 20949 10692 20949 10699 20949 10694 20950 10699 20950 10698 20950 10698 20951 10699 20951 10700 20951 10698 20952 10700 20952 10701 20952 10701 20953 10700 20953 10777 20953 10573 20954 10772 20954 10574 20954 10574 20955 10772 20955 10702 20955 10574 20956 10702 20956 10703 20956 10703 20957 10702 20957 10774 20957 10703 20958 10774 20958 10704 20958 10704 20959 10774 20959 10705 20959 10704 20960 10705 20960 10577 20960 10577 20961 10705 20961 10709 20961 10577 20962 10709 20962 10706 20962 10688 20963 10707 20963 10776 20963 10776 20964 10707 20964 10715 20964 10776 20965 10715 20965 10696 20965 10696 20966 10715 20966 10716 20966 10696 20967 10716 20967 10708 20967 10708 20968 10716 20968 10718 20968 10708 20969 10718 20969 10709 20969 10709 20970 10718 20970 10720 20970 10709 20971 10720 20971 10706 20971 10706 20972 10720 20972 10710 20972 10706 20973 10710 20973 10722 20973 10723 20974 10721 20974 10581 20974 10581 20975 10721 20975 10719 20975 10581 20976 10719 20976 12824 20976 12824 20977 10719 20977 10717 20977 12824 20978 10717 20978 10583 20978 10711 20979 10594 20979 10597 20979 10597 20980 10594 20980 10595 20980 10597 20981 10595 20981 10684 20981 10684 20982 10595 20982 10712 20982 10684 20983 10712 20983 10685 20983 10685 20984 10712 20984 10689 20984 10685 20985 10689 20985 10687 20985 10687 20986 10689 20986 10713 20986 10687 20987 10713 20987 10688 20987 10688 20988 10713 20988 10584 20988 10688 20989 10584 20989 10707 20989 10707 20990 10584 20990 10714 20990 10707 20991 10714 20991 10715 20991 10715 20992 10714 20992 10583 20992 10715 20993 10583 20993 10716 20993 10716 20994 10583 20994 10717 20994 10716 20995 10717 20995 10718 20995 10718 20996 10717 20996 10719 20996 10718 20997 10719 20997 10720 20997 10720 20998 10719 20998 10721 20998 10720 20999 10721 20999 10710 20999 10710 21000 10721 21000 10723 21000 10710 21001 10723 21001 10722 21001 10722 21002 10723 21002 12827 21002 10722 21003 12827 21003 10576 21003 10576 21004 12827 21004 10724 21004 10576 21005 10724 21005 10725 21005 10725 21006 10724 21006 10726 21006 10725 21007 10726 21007 12829 21007 10727 21008 8887 21008 10728 21008 10728 21009 8887 21009 10729 21009 10728 21010 10729 21010 10639 21010 10639 21011 10729 21011 10730 21011 10639 21012 10730 21012 10640 21012 10640 21013 10730 21013 10733 21013 10640 21014 10733 21014 10644 21014 10731 21015 13278 21015 10732 21015 10732 21016 13278 21016 13280 21016 10732 21017 13280 21017 10787 21017 10787 21018 13280 21018 10644 21018 10787 21019 10644 21019 10786 21019 10786 21020 10644 21020 10733 21020 10786 21021 10733 21021 10784 21021 10784 21022 10733 21022 10730 21022 10784 21023 10730 21023 10734 21023 10734 21024 10730 21024 10729 21024 10922 21025 10735 21025 10772 21025 10772 21026 10735 21026 10737 21026 10772 21027 10737 21027 10736 21027 10736 21028 10737 21028 10739 21028 10736 21029 10739 21029 10738 21029 10738 21030 10739 21030 10740 21030 10738 21031 10740 21031 13287 21031 13287 21032 10740 21032 116206 21032 13287 21033 116206 21033 13286 21033 10785 21034 10741 21034 10742 21034 10742 21035 10741 21035 10743 21035 10742 21036 10743 21036 10788 21036 10788 21037 10743 21037 10745 21037 10788 21038 10745 21038 10744 21038 10744 21039 10745 21039 10746 21039 10744 21040 10746 21040 10789 21040 10789 21041 10746 21041 10753 21041 10789 21042 10753 21042 10748 21042 10748 21043 10753 21043 10747 21043 10748 21044 10747 21044 10749 21044 10749 21045 10747 21045 10752 21045 10749 21046 10752 21046 10750 21046 10793 21047 10750 21047 10751 21047 10751 21048 10750 21048 10752 21048 10751 21049 10752 21049 10760 21049 10760 21050 10752 21050 10747 21050 10760 21051 10747 21051 10759 21051 10759 21052 10747 21052 10753 21052 10759 21053 10753 21053 10758 21053 10758 21054 10753 21054 10746 21054 10758 21055 10746 21055 10757 21055 10757 21056 10746 21056 10745 21056 10757 21057 10745 21057 10754 21057 10754 21058 10745 21058 10743 21058 10754 21059 10743 21059 10755 21059 10755 21060 10743 21060 10741 21060 10755 21061 10756 21061 10754 21061 10754 21062 10756 21062 10770 21062 10754 21063 10770 21063 10757 21063 10757 21064 10770 21064 10769 21064 10757 21065 10769 21065 10758 21065 10758 21066 10769 21066 10768 21066 10758 21067 10768 21067 10759 21067 10759 21068 10768 21068 10767 21068 10759 21069 10767 21069 10760 21069 10760 21070 10767 21070 10766 21070 10760 21071 10766 21071 10751 21071 10751 21072 10766 21072 10765 21072 10751 21073 10765 21073 10795 21073 10795 21074 10765 21074 10796 21074 10501 21075 10498 21075 10670 21075 10670 21076 10498 21076 10679 21076 10670 21077 10679 21077 10761 21077 10761 21078 10679 21078 10671 21078 10761 21079 10671 21079 10762 21079 10762 21080 10671 21080 10678 21080 10762 21081 10678 21081 10763 21081 10763 21082 10678 21082 10674 21082 10763 21083 10674 21083 10764 21083 10764 21084 10674 21084 10796 21084 10764 21085 10796 21085 10648 21085 10648 21086 10796 21086 10765 21086 10648 21087 10765 21087 10647 21087 10647 21088 10765 21088 10766 21088 10647 21089 10766 21089 10645 21089 10645 21090 10766 21090 10767 21090 10645 21091 10767 21091 10652 21091 10652 21092 10767 21092 10768 21092 10652 21093 10768 21093 10650 21093 10650 21094 10768 21094 10769 21094 10650 21095 10769 21095 10637 21095 10637 21096 10769 21096 10770 21096 10637 21097 10770 21097 8904 21097 8904 21098 10770 21098 10756 21098 13282 21099 13278 21099 10738 21099 10738 21100 13278 21100 10731 21100 10738 21101 10731 21101 10736 21101 10736 21102 10731 21102 10771 21102 10736 21103 10771 21103 10772 21103 10772 21104 10771 21104 10773 21104 10772 21105 10773 21105 10702 21105 10702 21106 10773 21106 10790 21106 10702 21107 10790 21107 10774 21107 10774 21108 10790 21108 10697 21108 10774 21109 10697 21109 10775 21109 10775 21110 10697 21110 10695 21110 10775 21111 10695 21111 10696 21111 10696 21112 10695 21112 10701 21112 10696 21113 10701 21113 10776 21113 10776 21114 10701 21114 10777 21114 10776 21115 10777 21115 10778 21115 10778 21116 10777 21116 10779 21116 10778 21117 10779 21117 10686 21117 10686 21118 10779 21118 10780 21118 10686 21119 10780 21119 10781 21119 10781 21120 10780 21120 10802 21120 10781 21121 10802 21121 10782 21121 10782 21122 10802 21122 10825 21122 10782 21123 10825 21123 10830 21123 10734 21124 10783 21124 10784 21124 10784 21125 10783 21125 10785 21125 10784 21126 10785 21126 10786 21126 10786 21127 10785 21127 10742 21127 10786 21128 10742 21128 10787 21128 10787 21129 10742 21129 10788 21129 10787 21130 10788 21130 10732 21130 10732 21131 10788 21131 10744 21131 10732 21132 10744 21132 10731 21132 10731 21133 10744 21133 10789 21133 10731 21134 10789 21134 10771 21134 10771 21135 10789 21135 10748 21135 10771 21136 10748 21136 10773 21136 10773 21137 10748 21137 10749 21137 10773 21138 10749 21138 10790 21138 10790 21139 10749 21139 10750 21139 10790 21140 10750 21140 10791 21140 10791 21141 10750 21141 10793 21141 10791 21142 10793 21142 10792 21142 10792 21143 10793 21143 10795 21143 10792 21144 10795 21144 10794 21144 10794 21145 10795 21145 10796 21145 10794 21146 10796 21146 10797 21146 10797 21147 10796 21147 10674 21147 10797 21148 10674 21148 10798 21148 10798 21149 10674 21149 10567 21149 10798 21150 10567 21150 10799 21150 10799 21151 10567 21151 10568 21151 10799 21152 10568 21152 10779 21152 10779 21153 10568 21153 10800 21153 10779 21154 10800 21154 10780 21154 10780 21155 10800 21155 10801 21155 10780 21156 10801 21156 10802 21156 10802 21157 10801 21157 10600 21157 10802 21158 10600 21158 10827 21158 10803 21159 10804 21159 10610 21159 10805 21160 10804 21160 10803 21160 10803 21161 11104 21161 10805 21161 10805 21162 11104 21162 11105 21162 10805 21163 11105 21163 10609 21163 10609 21164 11105 21164 10806 21164 10609 21165 10806 21165 10807 21165 10807 21166 10806 21166 11106 21166 10807 21167 11106 21167 10601 21167 10601 21168 11106 21168 11107 21168 10808 21169 10601 21169 11107 21169 10603 21170 10809 21170 10605 21170 10605 21171 10809 21171 10810 21171 10605 21172 10810 21172 10606 21172 10606 21173 10810 21173 11115 21173 11107 21174 10811 21174 10808 21174 10808 21175 10811 21175 11109 21175 10808 21176 11109 21176 10812 21176 10812 21177 11109 21177 10813 21177 10812 21178 10813 21178 10602 21178 10602 21179 10813 21179 10814 21179 10602 21180 10814 21180 10603 21180 10603 21181 10814 21181 10815 21181 10603 21182 10815 21182 10809 21182 10606 21183 11115 21183 10816 21183 10816 21184 11115 21184 11116 21184 10816 21185 11116 21185 10607 21185 10593 21186 12949 21186 12950 21186 12930 21187 12931 21187 10836 21187 12930 21188 10836 21188 12950 21188 12950 21189 10836 21189 12812 21189 12950 21190 12812 21190 10593 21190 12931 21191 10817 21191 10836 21191 10836 21192 10817 21192 10818 21192 10836 21193 10818 21193 12932 21193 12932 21194 10819 21194 10836 21194 10836 21195 10819 21195 10820 21195 10836 21196 10820 21196 10838 21196 10820 21197 10821 21197 10838 21197 10838 21198 10821 21198 12937 21198 10838 21199 12937 21199 12936 21199 10842 21200 10822 21200 10844 21200 10844 21201 10822 21201 11324 21201 10844 21202 11324 21202 11054 21202 10826 21203 11121 21203 10828 21203 10828 21204 11121 21204 11122 21204 10823 21205 10600 21205 11111 21205 11111 21206 10600 21206 10599 21206 11111 21207 10599 21207 10824 21207 10824 21208 10599 21208 10607 21208 10840 21209 10825 21209 10837 21209 10823 21210 10826 21210 10600 21210 10600 21211 10826 21211 10828 21211 10600 21212 10828 21212 10827 21212 10827 21213 10828 21213 10598 21213 10829 21214 10683 21214 10840 21214 10840 21215 10683 21215 10830 21215 10840 21216 10830 21216 10825 21216 12951 21217 10711 21217 10831 21217 10831 21218 10711 21218 10683 21218 10831 21219 10683 21219 12939 21219 12939 21220 10683 21220 10829 21220 12939 21221 10829 21221 12935 21221 11027 21222 12811 21222 11028 21222 11028 21223 12811 21223 10832 21223 11028 21224 10832 21224 10833 21224 10833 21225 10832 21225 10835 21225 10833 21226 10835 21226 10834 21226 10834 21227 10835 21227 10843 21227 10834 21228 10843 21228 11053 21228 10841 21229 10843 21229 10839 21229 10839 21230 10843 21230 10835 21230 10839 21231 10835 21231 10838 21231 10838 21232 10835 21232 10832 21232 10838 21233 10832 21233 10836 21233 10836 21234 10832 21234 12811 21234 10837 21235 10598 21235 10840 21235 10840 21236 10598 21236 10828 21236 10840 21237 10828 21237 10842 21237 10842 21238 10828 21238 11122 21238 10842 21239 11122 21239 10822 21239 12936 21240 12935 21240 10838 21240 10838 21241 12935 21241 10829 21241 10838 21242 10829 21242 10839 21242 10839 21243 10829 21243 10840 21243 10839 21244 10840 21244 10841 21244 10841 21245 10840 21245 10842 21245 10841 21246 10842 21246 10843 21246 10843 21247 10842 21247 10844 21247 10843 21248 10844 21248 11053 21248 11053 21249 10844 21249 11054 21249 12805 21250 10845 21250 11196 21250 12805 21251 11196 21251 12804 21251 12804 21252 11196 21252 10846 21252 10846 21253 11196 21253 10847 21253 10846 21254 10847 21254 10851 21254 10847 21255 10848 21255 10851 21255 10851 21256 10848 21256 11131 21256 10851 21257 11131 21257 10849 21257 10849 21258 10850 21258 10851 21258 10851 21259 10850 21259 11135 21259 10851 21260 11135 21260 10878 21260 12820 21261 11132 21261 10852 21261 10852 21262 10853 21262 12820 21262 12820 21263 10853 21263 10854 21263 12820 21264 10854 21264 11136 21264 11136 21265 10855 21265 12820 21265 12820 21266 10855 21266 10856 21266 12820 21267 10856 21267 10857 21267 12825 21268 12826 21268 10883 21268 10883 21269 12826 21269 10858 21269 10883 21270 10858 21270 10857 21270 10857 21271 10858 21271 12821 21271 10857 21272 12821 21272 12820 21272 11192 21273 11193 21273 10859 21273 10859 21274 11193 21274 10860 21274 10860 21275 11193 21275 11194 21275 10860 21276 11194 21276 10845 21276 10845 21277 11194 21277 11195 21277 10845 21278 11195 21278 11196 21278 12789 21279 10869 21279 12795 21279 12795 21280 10869 21280 11190 21280 10859 21281 12798 21281 11192 21281 11192 21282 12798 21282 10861 21282 11192 21283 10861 21283 11190 21283 11190 21284 10861 21284 10862 21284 11190 21285 10862 21285 12795 21285 12788 21286 12779 21286 10867 21286 10863 21287 11183 21287 10867 21287 10867 21288 11183 21288 11188 21288 10867 21289 11188 21289 10864 21289 10874 21290 12782 21290 10864 21290 10864 21291 12782 21291 10865 21291 10865 21292 10866 21292 10864 21292 10864 21293 10866 21293 12783 21293 10864 21294 12783 21294 10867 21294 10867 21295 12783 21295 12785 21295 10867 21296 12785 21296 12788 21296 12789 21297 10868 21297 10869 21297 10869 21298 10868 21298 12793 21298 10869 21299 12793 21299 10870 21299 10870 21300 12793 21300 10871 21300 10870 21301 10871 21301 10872 21301 10872 21302 10871 21302 12791 21302 10872 21303 12791 21303 11189 21303 11189 21304 12791 21304 12790 21304 11189 21305 12790 21305 10864 21305 10864 21306 12790 21306 10873 21306 10864 21307 10873 21307 10874 21307 12810 21308 12809 21308 10851 21308 12810 21309 10851 21309 12813 21309 12814 21310 12816 21310 10875 21310 12820 21311 10876 21311 10875 21311 10875 21312 10876 21312 10877 21312 10875 21313 10877 21313 12814 21313 12816 21314 12813 21314 10875 21314 10875 21315 12813 21315 10851 21315 10875 21316 10851 21316 12820 21316 12820 21317 10851 21317 10878 21317 12820 21318 10878 21318 11132 21318 10851 21319 10880 21319 12802 21319 12802 21320 10880 21320 12801 21320 10882 21321 10879 21321 10880 21321 10880 21322 10879 21322 10881 21322 10880 21323 10881 21323 12801 21323 12809 21324 12808 21324 10851 21324 10851 21325 12808 21325 12807 21325 10851 21326 12807 21326 10880 21326 10880 21327 12807 21327 12794 21327 10880 21328 12794 21328 10882 21328 10883 21329 10884 21329 12825 21329 12825 21330 10884 21330 11137 21330 12825 21331 11137 21331 12823 21331 12823 21332 11137 21332 10885 21332 12823 21333 10885 21333 12828 21333 12828 21334 10885 21334 11138 21334 12828 21335 11138 21335 10887 21335 12835 21336 12832 21336 10886 21336 10886 21337 12832 21337 12831 21337 10886 21338 12831 21338 10887 21338 10887 21339 12831 21339 10888 21339 10887 21340 10888 21340 12828 21340 10889 21341 11166 21341 12842 21341 12842 21342 11166 21342 10890 21342 12842 21343 10890 21343 10891 21343 10895 21344 12840 21344 10892 21344 10892 21345 12840 21345 12836 21345 10892 21346 12836 21346 10893 21346 10889 21347 12838 21347 11166 21347 11166 21348 12838 21348 12840 21348 11166 21349 12840 21349 10894 21349 10894 21350 12840 21350 10895 21350 10886 21351 10896 21351 12835 21351 12835 21352 10896 21352 11142 21352 12835 21353 11142 21353 10897 21353 10897 21354 11142 21354 11140 21354 10897 21355 11140 21355 12836 21355 12836 21356 11140 21356 10898 21356 12836 21357 10898 21357 10893 21357 10920 21358 115938 21358 10579 21358 10920 21359 10579 21359 10899 21359 10899 21360 10579 21360 10900 21360 10899 21361 10900 21361 12830 21361 12830 21362 12834 21362 10899 21362 10899 21363 12834 21363 12833 21363 10899 21364 12833 21364 12837 21364 10906 21365 10901 21365 10902 21365 10902 21366 10901 21366 10903 21366 10902 21367 10903 21367 10578 21367 115938 21368 9132 21368 10904 21368 10904 21369 10905 21369 115938 21369 115938 21370 10905 21370 9137 21370 115938 21371 9137 21371 10906 21371 10906 21372 9137 21372 10907 21372 10906 21373 10907 21373 10901 21373 10578 21374 10903 21374 10910 21374 10910 21375 10903 21375 10908 21375 10910 21376 10908 21376 10909 21376 10909 21377 10908 21377 9140 21377 10909 21378 9140 21378 9122 21378 10909 21379 12473 21379 10910 21379 10910 21380 12473 21380 12475 21380 10910 21381 12475 21381 10911 21381 10911 21382 12475 21382 10921 21382 10911 21383 10921 21383 10575 21383 9121 21384 10912 21384 10920 21384 10920 21385 10912 21385 10913 21385 10920 21386 10913 21386 115938 21386 115938 21387 10913 21387 10914 21387 115938 21388 10914 21388 9132 21388 10737 21389 10923 21389 10572 21389 10572 21390 10923 21390 10915 21390 10572 21391 10915 21391 116206 21391 116206 21392 10915 21392 10916 21392 9122 21393 9123 21393 10909 21393 10909 21394 9123 21394 9125 21394 10909 21395 9125 21395 12470 21395 12470 21396 9125 21396 10917 21396 12470 21397 10917 21397 10918 21397 10918 21398 10917 21398 10919 21398 10918 21399 10919 21399 10920 21399 10920 21400 10919 21400 9128 21400 10920 21401 9128 21401 9121 21401 10921 21402 12476 21402 10575 21402 10575 21403 12476 21403 12477 21403 10575 21404 12477 21404 10573 21404 10573 21405 12477 21405 12478 21405 10573 21406 12478 21406 10922 21406 10922 21407 12478 21407 10923 21407 10922 21408 10923 21408 10735 21408 10735 21409 10923 21409 10737 21409 12462 21410 12843 21410 13098 21410 13098 21411 10924 21411 12462 21411 12462 21412 10924 21412 13099 21412 12462 21413 13099 21413 12486 21413 12486 21414 13099 21414 13101 21414 12486 21415 13101 21415 10925 21415 13105 21416 10926 21416 13104 21416 13104 21417 10926 21417 10927 21417 13104 21418 10927 21418 13103 21418 13103 21419 10927 21419 12485 21419 13103 21420 12485 21420 10925 21420 10925 21421 12485 21421 10928 21421 10925 21422 10928 21422 12486 21422 10929 21423 10940 21423 10930 21423 10929 21424 10930 21424 13113 21424 13113 21425 10930 21425 10931 21425 13113 21426 10931 21426 13117 21426 13117 21427 10931 21427 13116 21427 13116 21428 10931 21428 12515 21428 13116 21429 12515 21429 13112 21429 13112 21430 12515 21430 10932 21430 13112 21431 10932 21431 13111 21431 13111 21432 10932 21432 12491 21432 13111 21433 12491 21433 13110 21433 13110 21434 12491 21434 12490 21434 13110 21435 12490 21435 10934 21435 10934 21436 12490 21436 10933 21436 10934 21437 10933 21437 10935 21437 10935 21438 10933 21438 12489 21438 10935 21439 12489 21439 13107 21439 13107 21440 12489 21440 12488 21440 13107 21441 12488 21441 13105 21441 13105 21442 12488 21442 12483 21442 13105 21443 12483 21443 10926 21443 10936 21444 10937 21444 12519 21444 12519 21445 10937 21445 10938 21445 12519 21446 10938 21446 12521 21446 12521 21447 10938 21447 10939 21447 12521 21448 10939 21448 10943 21448 10940 21449 10929 21449 12517 21449 12517 21450 10929 21450 10941 21450 12517 21451 10941 21451 10936 21451 10936 21452 10941 21452 13118 21452 10936 21453 13118 21453 10937 21453 13122 21454 10942 21454 12546 21454 13122 21455 12546 21455 13123 21455 13123 21456 12546 21456 13124 21456 13124 21457 12546 21457 10943 21457 13124 21458 10943 21458 10939 21458 12546 21459 10942 21459 10944 21459 10944 21460 10942 21460 10945 21460 10944 21461 10945 21461 10946 21461 10946 21462 10945 21462 12566 21462 12566 21463 10945 21463 13127 21463 12566 21464 13127 21464 10947 21464 13127 21465 10948 21465 10947 21465 10947 21466 10948 21466 13130 21466 10947 21467 13130 21467 12567 21467 12567 21468 13130 21468 13131 21468 12567 21469 13131 21469 10949 21469 10949 21470 13131 21470 10950 21470 10949 21471 10950 21471 10951 21471 10952 21472 10958 21472 10955 21472 10998 21473 10953 21473 10441 21473 10441 21474 10953 21474 10954 21474 10441 21475 10954 21475 10502 21475 10955 21476 10500 21476 10952 21476 10952 21477 10500 21477 10956 21477 10952 21478 10956 21478 10957 21478 10957 21479 10956 21479 10503 21479 10957 21480 10503 21480 11256 21480 11256 21481 10503 21481 10502 21481 11256 21482 10502 21482 11257 21482 11257 21483 10502 21483 10954 21483 10959 21484 11101 21484 10499 21484 10499 21485 11101 21485 10610 21485 10958 21486 11100 21486 10955 21486 10955 21487 11100 21487 10960 21487 10955 21488 10960 21488 10959 21488 10959 21489 10960 21489 10961 21489 10959 21490 10961 21490 11101 21490 12582 21491 10965 21491 10962 21491 10962 21492 10965 21492 10963 21492 10962 21493 10963 21493 10964 21493 10964 21494 10963 21494 13137 21494 10964 21495 13137 21495 12583 21495 12582 21496 12581 21496 10965 21496 10965 21497 12581 21497 10966 21497 10965 21498 10966 21498 10968 21498 10951 21499 10950 21499 12578 21499 12578 21500 10950 21500 10968 21500 12578 21501 10968 21501 10967 21501 10967 21502 10968 21502 10966 21502 13134 21503 10974 21503 10970 21503 10970 21504 10974 21504 12615 21504 12615 21505 10969 21505 10970 21505 10970 21506 10969 21506 12616 21506 10970 21507 12616 21507 10971 21507 10971 21508 12616 21508 10972 21508 10971 21509 10972 21509 13137 21509 13137 21510 10972 21510 10973 21510 13137 21511 10973 21511 12583 21511 12620 21512 10974 21512 13139 21512 13139 21513 10974 21513 13134 21513 12635 21514 13143 21514 10975 21514 10975 21515 13143 21515 13142 21515 10975 21516 13142 21516 12634 21516 12634 21517 13142 21517 10983 21517 12634 21518 10983 21518 10984 21518 12620 21519 13139 21519 12636 21519 12636 21520 13139 21520 13143 21520 12636 21521 13143 21521 10976 21521 10976 21522 13143 21522 12635 21522 13147 21523 12644 21523 10977 21523 13147 21524 10977 21524 13146 21524 13146 21525 10977 21525 10978 21525 13146 21526 10978 21526 10980 21526 10978 21527 10979 21527 10980 21527 10980 21528 10979 21528 10981 21528 10980 21529 10981 21529 13144 21529 10981 21530 12640 21530 13144 21530 13144 21531 12640 21531 10982 21531 13144 21532 10982 21532 10983 21532 10983 21533 10982 21533 12638 21533 10983 21534 12638 21534 10984 21534 10988 21535 13155 21535 10990 21535 12644 21536 13147 21536 12661 21536 12661 21537 13147 21537 10985 21537 12661 21538 10985 21538 12683 21538 12683 21539 10985 21539 10986 21539 12683 21540 10986 21540 12682 21540 12682 21541 10986 21541 13152 21541 12682 21542 13152 21542 12670 21542 12670 21543 13152 21543 13150 21543 12670 21544 13150 21544 10987 21544 10987 21545 13150 21545 10988 21545 10987 21546 10988 21546 10989 21546 10989 21547 10988 21547 10990 21547 10993 21548 10444 21548 10104 21548 11309 21549 10104 21549 10992 21549 10992 21550 10104 21550 10991 21550 10992 21551 10991 21551 11354 21551 10995 21552 10993 21552 10996 21552 10996 21553 10993 21553 10104 21553 10996 21554 10104 21554 11308 21554 11308 21555 10104 21555 11309 21555 10997 21556 10994 21556 11002 21556 11002 21557 10443 21557 10997 21557 10997 21558 10443 21558 10444 21558 10997 21559 10444 21559 10993 21559 10993 21560 10995 21560 10997 21560 10997 21561 10995 21561 10996 21561 10997 21562 10996 21562 11308 21562 10999 21563 10998 21563 10490 21563 10490 21564 10998 21564 10441 21564 10490 21565 10491 21565 10999 21565 10999 21566 10491 21566 11000 21566 10999 21567 11000 21567 11001 21567 11001 21568 11000 21568 11002 21568 11001 21569 11002 21569 11311 21569 11311 21570 11002 21570 10994 21570 12732 21571 12733 21571 11006 21571 9153 21572 9145 21572 11003 21572 11003 21573 9145 21573 11004 21573 11003 21574 11004 21574 12735 21574 12735 21575 11004 21575 11005 21575 12735 21576 11005 21576 9156 21576 11006 21577 9142 21577 12732 21577 12732 21578 9142 21578 9141 21578 12732 21579 9141 21579 12731 21579 11007 21580 11019 21580 12730 21580 9156 21581 9158 21581 12735 21581 12735 21582 9158 21582 9159 21582 12735 21583 9159 21583 11010 21583 11010 21584 9159 21584 11008 21584 11008 21585 9161 21585 11010 21585 11010 21586 9161 21586 11009 21586 11010 21587 11009 21587 12733 21587 12733 21588 11009 21588 9165 21588 12733 21589 9165 21589 11006 21589 11014 21590 9148 21590 10308 21590 9148 21591 11011 21591 10308 21591 10308 21592 11011 21592 9149 21592 10308 21593 9149 21593 11003 21593 11003 21594 9149 21594 9152 21594 11003 21595 9152 21595 9153 21595 10162 21596 11012 21596 10249 21596 10249 21597 11012 21597 11013 21597 10249 21598 11013 21598 10250 21598 10250 21599 11013 21599 12727 21599 10250 21600 12727 21600 11017 21600 11014 21601 10308 21601 11015 21601 11015 21602 10308 21602 11007 21602 11015 21603 11007 21603 9141 21603 9141 21604 11007 21604 12730 21604 9141 21605 12730 21605 12731 21605 12727 21606 11016 21606 11017 21606 11017 21607 11016 21607 11018 21607 11017 21608 11018 21608 11019 21608 11019 21609 11018 21609 11020 21609 11019 21610 11020 21610 12730 21610 10162 21611 10160 21611 11012 21611 11012 21612 10160 21612 10159 21612 11012 21613 10159 21613 12725 21613 12725 21614 10159 21614 11021 21614 12725 21615 11021 21615 116247 21615 11022 21616 11023 21616 11025 21616 11025 21617 11023 21617 12735 21617 12735 21618 11023 21618 10274 21618 12735 21619 10274 21619 11003 21619 12780 21620 11024 21620 11025 21620 11025 21621 11024 21621 12792 21621 11025 21622 12792 21622 11022 21622 11058 21623 11057 21623 11059 21623 11026 21624 11027 21624 11028 21624 11329 21625 11029 21625 11030 21625 11030 21626 11029 21626 11031 21626 11055 21627 11328 21627 11031 21627 11031 21628 11328 21628 11331 21628 11031 21629 11331 21629 11030 21629 11032 21630 11033 21630 11048 21630 11049 21631 13018 21631 11034 21631 11032 21632 11048 21632 13020 21632 11034 21633 11035 21633 11049 21633 11049 21634 11035 21634 11036 21634 11049 21635 11036 21635 11048 21635 11048 21636 11036 21636 11037 21636 11048 21637 11037 21637 13020 21637 11033 21638 11038 21638 11048 21638 11048 21639 11038 21639 11039 21639 11048 21640 11039 21640 10146 21640 10146 21641 11039 21641 11040 21641 10146 21642 11040 21642 13052 21642 11041 21643 11042 21643 10141 21643 10141 21644 11042 21644 11043 21644 11047 21645 11044 21645 11049 21645 11049 21646 11044 21646 11045 21646 11049 21647 11045 21647 13018 21647 11029 21648 10191 21648 11031 21648 11031 21649 10191 21649 10182 21649 11031 21650 10182 21650 11046 21650 11046 21651 10182 21651 11043 21651 11046 21652 11043 21652 11047 21652 11047 21653 11043 21653 11042 21653 11047 21654 11042 21654 11044 21654 11048 21655 11060 21655 11049 21655 11049 21656 11060 21656 11059 21656 11049 21657 11059 21657 11047 21657 11047 21658 11059 21658 11057 21658 11047 21659 11057 21659 11046 21659 11056 21660 11052 21660 11050 21660 11050 21661 11052 21661 11051 21661 11050 21662 11051 21662 11055 21662 11055 21663 11051 21663 11327 21663 10833 21664 10834 21664 11052 21664 11052 21665 10834 21665 11053 21665 11052 21666 11053 21666 11051 21666 11051 21667 11053 21667 11054 21667 11051 21668 11054 21668 11327 21668 11327 21669 11054 21669 11324 21669 11055 21670 11031 21670 11050 21670 11050 21671 11031 21671 11046 21671 11050 21672 11046 21672 11056 21672 11056 21673 11046 21673 11057 21673 11056 21674 11057 21674 11052 21674 11052 21675 11057 21675 11058 21675 11052 21676 11058 21676 10833 21676 10833 21677 11058 21677 11059 21677 10833 21678 11059 21678 11028 21678 11028 21679 11059 21679 11060 21679 11028 21680 11060 21680 11026 21680 11329 21681 11061 21681 11062 21681 11062 21682 11061 21682 11063 21682 11062 21683 11063 21683 10138 21683 11352 21684 11064 21684 10137 21684 10137 21685 11065 21685 11352 21685 11352 21686 11065 21686 11066 21686 11352 21687 11066 21687 11351 21687 11351 21688 11066 21688 11067 21688 11351 21689 11067 21689 11350 21689 11350 21690 11067 21690 11068 21690 11068 21691 11067 21691 10140 21691 11068 21692 10140 21692 11069 21692 11069 21693 10140 21693 10139 21693 11069 21694 10139 21694 11349 21694 11349 21695 10139 21695 10138 21695 11349 21696 10138 21696 11063 21696 10136 21697 10137 21697 11064 21697 11064 21698 11353 21698 10136 21698 10136 21699 11353 21699 11070 21699 10136 21700 11070 21700 10134 21700 10134 21701 11070 21701 11072 21701 10134 21702 11072 21702 11071 21702 11071 21703 11072 21703 11355 21703 11071 21704 11355 21704 10991 21704 10991 21705 11355 21705 11354 21705 11073 21706 11074 21706 11076 21706 11073 21707 11076 21707 11075 21707 11075 21708 11076 21708 13154 21708 13154 21709 11076 21709 10990 21709 13154 21710 10990 21710 13155 21710 12721 21711 11076 21711 11074 21711 11083 21712 11077 21712 12720 21712 12720 21713 11077 21713 11078 21713 12720 21714 11078 21714 12689 21714 12689 21715 11078 21715 13163 21715 12689 21716 13163 21716 12716 21716 12716 21717 13163 21717 11079 21717 12716 21718 11079 21718 11080 21718 11080 21719 11079 21719 13166 21719 11080 21720 13166 21720 12714 21720 12714 21721 13166 21721 11085 21721 12714 21722 11085 21722 11086 21722 12721 21723 11074 21723 11082 21723 11082 21724 11074 21724 11081 21724 11082 21725 11081 21725 11083 21725 11083 21726 11081 21726 13158 21726 11083 21727 13158 21727 11077 21727 13173 21728 11084 21728 11087 21728 11085 21729 13168 21729 11086 21729 11086 21730 13168 21730 13169 21730 11086 21731 13169 21731 11087 21731 11087 21732 13169 21732 11088 21732 11087 21733 11088 21733 13173 21733 13173 21734 13170 21734 11084 21734 11084 21735 13170 21735 11089 21735 11084 21736 11089 21736 12745 21736 12745 21737 11089 21737 11090 21737 12745 21738 11090 21738 12743 21738 12743 21739 11090 21739 13174 21739 12743 21740 13174 21740 11091 21740 11091 21741 13174 21741 13175 21741 11091 21742 13175 21742 11092 21742 11092 21743 13175 21743 11093 21743 11092 21744 11093 21744 12739 21744 12739 21745 11093 21745 13177 21745 12739 21746 13177 21746 12738 21746 12738 21747 13177 21747 11094 21747 12738 21748 11094 21748 12737 21748 12737 21749 11094 21749 11095 21749 12737 21750 11095 21750 11099 21750 11096 21751 12778 21751 13183 21751 13183 21752 12778 21752 12772 21752 13183 21753 12772 21753 11097 21753 11097 21754 12772 21754 12776 21754 11097 21755 12776 21755 11099 21755 11099 21756 12776 21756 11098 21756 11099 21757 11098 21757 12737 21757 11100 21758 10958 21758 11393 21758 10803 21759 10610 21759 11103 21759 11103 21760 10610 21760 11101 21760 11103 21761 11101 21761 11102 21761 11102 21762 11101 21762 10961 21762 11102 21763 10961 21763 11393 21763 11393 21764 10961 21764 10960 21764 11393 21765 10960 21765 11100 21765 10803 21766 11103 21766 11104 21766 11104 21767 11103 21767 11391 21767 11104 21768 11391 21768 11105 21768 11105 21769 11391 21769 10806 21769 10806 21770 11391 21770 11389 21770 10806 21771 11389 21771 11106 21771 11106 21772 11389 21772 11388 21772 11106 21773 11388 21773 11107 21773 10809 21774 10815 21774 11108 21774 11107 21775 11388 21775 10811 21775 10811 21776 11388 21776 11387 21776 10815 21777 10814 21777 11108 21777 11108 21778 10814 21778 10813 21778 11108 21779 10813 21779 11387 21779 11387 21780 10813 21780 11109 21780 11387 21781 11109 21781 10811 21781 10809 21782 11108 21782 10810 21782 10810 21783 11108 21783 11117 21783 10810 21784 11117 21784 11115 21784 10607 21785 11116 21785 10824 21785 10824 21786 11116 21786 11110 21786 10824 21787 11110 21787 11111 21787 11110 21788 11118 21788 11111 21788 11111 21789 11118 21789 11112 21789 11111 21790 11112 21790 10823 21790 10823 21791 11112 21791 11113 21791 10823 21792 11113 21792 10826 21792 10826 21793 11113 21793 11114 21793 10826 21794 11114 21794 11121 21794 11115 21795 11117 21795 11116 21795 11116 21796 11117 21796 11385 21796 11116 21797 11385 21797 11110 21797 11114 21798 11113 21798 11405 21798 11405 21799 11113 21799 11112 21799 11405 21800 11112 21800 11385 21800 11385 21801 11112 21801 11118 21801 11385 21802 11118 21802 11110 21802 11122 21803 11119 21803 10822 21803 10822 21804 11119 21804 11323 21804 10822 21805 11323 21805 11324 21805 11114 21806 11120 21806 11121 21806 11121 21807 11120 21807 11404 21807 11121 21808 11404 21808 11122 21808 11122 21809 11404 21809 11407 21809 11122 21810 11407 21810 11119 21810 9388 21811 11130 21811 9401 21811 9401 21812 11130 21812 9243 21812 9401 21813 9243 21813 9400 21813 9400 21814 9243 21814 11123 21814 9400 21815 11123 21815 9398 21815 9398 21816 11123 21816 9241 21816 9398 21817 9241 21817 11124 21817 11124 21818 9241 21818 9237 21818 11124 21819 9237 21819 11125 21819 11125 21820 9237 21820 9254 21820 11125 21821 9254 21821 9394 21821 9394 21822 9254 21822 9256 21822 9394 21823 9256 21823 11126 21823 11126 21824 9256 21824 9257 21824 11126 21825 9257 21825 11127 21825 11127 21826 9257 21826 9252 21826 11127 21827 9252 21827 11128 21827 11128 21828 9252 21828 9251 21828 11128 21829 9251 21829 11129 21829 11129 21830 9251 21830 9248 21830 11129 21831 9248 21831 9389 21831 9389 21832 9248 21832 9246 21832 9389 21833 9246 21833 9388 21833 9388 21834 9246 21834 11130 21834 11131 21835 11134 21835 10849 21835 10849 21836 11134 21836 10850 21836 11136 21837 10854 21837 11133 21837 11133 21838 10854 21838 10853 21838 11133 21839 10853 21839 10852 21839 10852 21840 11132 21840 11133 21840 11133 21841 11132 21841 10878 21841 11133 21842 10878 21842 11134 21842 11134 21843 10878 21843 11135 21843 11134 21844 11135 21844 10850 21844 11136 21845 11133 21845 10855 21845 10855 21846 11133 21846 13353 21846 10855 21847 13353 21847 10856 21847 10856 21848 13353 21848 10857 21848 10857 21849 13353 21849 10883 21849 10883 21850 13353 21850 13352 21850 10883 21851 13352 21851 10884 21851 10884 21852 13352 21852 11137 21852 11137 21853 13352 21853 13350 21853 11137 21854 13350 21854 10885 21854 10885 21855 13350 21855 11138 21855 11138 21856 13350 21856 13349 21856 11138 21857 13349 21857 10887 21857 10886 21858 10887 21858 13349 21858 10886 21859 13349 21859 10896 21859 10896 21860 13349 21860 11141 21860 10896 21861 11141 21861 11142 21861 11139 21862 10893 21862 10898 21862 11139 21863 10898 21863 11141 21863 11141 21864 10898 21864 11140 21864 11141 21865 11140 21865 11142 21865 13362 21866 10895 21866 11139 21866 11139 21867 10895 21867 10892 21867 11139 21868 10892 21868 10893 21868 11149 21869 11166 21869 13362 21869 13362 21870 11166 21870 10894 21870 13362 21871 10894 21871 10895 21871 13362 21872 13360 21872 11149 21872 11149 21873 13360 21873 13371 21873 11149 21874 13371 21874 11418 21874 11146 21875 11144 21875 11143 21875 12877 21876 11144 21876 11145 21876 11145 21877 11144 21877 11146 21877 11145 21878 11146 21878 12857 21878 12857 21879 11146 21879 9403 21879 12857 21880 9403 21880 12858 21880 9429 21881 11149 21881 11147 21881 11147 21882 11149 21882 11418 21882 11147 21883 11418 21883 11148 21883 11148 21884 11418 21884 11187 21884 12870 21885 12869 21885 11149 21885 11149 21886 12869 21886 11150 21886 11149 21887 11150 21887 11166 21887 9429 21888 11151 21888 11149 21888 11149 21889 11151 21889 9433 21889 11149 21890 9433 21890 12870 21890 12858 21891 9403 21891 11152 21891 11152 21892 9403 21892 9404 21892 11152 21893 9404 21893 12861 21893 12861 21894 9404 21894 11154 21894 12861 21895 11154 21895 11153 21895 11153 21896 11154 21896 9407 21896 11153 21897 9407 21897 12863 21897 12863 21898 9407 21898 11155 21898 12863 21899 11155 21899 12865 21899 12865 21900 11155 21900 9411 21900 12865 21901 9411 21901 11156 21901 11156 21902 9411 21902 9413 21902 11156 21903 9413 21903 12855 21903 10863 21904 10867 21904 11186 21904 11186 21905 10867 21905 9413 21905 11186 21906 9413 21906 11187 21906 11187 21907 9413 21907 9414 21907 11187 21908 9414 21908 11148 21908 11143 21909 9423 21909 11146 21909 11146 21910 9423 21910 9424 21910 11146 21911 9424 21911 11157 21911 11157 21912 9424 21912 9425 21912 11157 21913 9425 21913 11147 21913 11147 21914 9425 21914 9428 21914 11147 21915 9428 21915 9429 21915 12877 21916 12876 21916 11144 21916 11144 21917 12876 21917 11158 21917 11144 21918 11158 21918 11159 21918 11159 21919 11158 21919 11160 21919 11159 21920 11160 21920 9419 21920 9419 21921 11160 21921 11161 21921 9419 21922 11161 21922 11163 21922 11163 21923 11161 21923 11162 21923 11163 21924 11162 21924 9433 21924 9433 21925 11162 21925 12872 21925 9433 21926 12872 21926 12870 21926 11164 21927 11165 21927 12880 21927 12880 21928 11165 21928 12879 21928 12880 21929 12879 21929 12866 21929 12866 21930 12879 21930 10890 21930 12866 21931 10890 21931 12867 21931 12867 21932 10890 21932 11166 21932 12867 21933 11166 21933 11167 21933 11167 21934 11166 21934 11150 21934 12855 21935 9413 21935 11168 21935 11168 21936 9413 21936 10867 21936 11168 21937 10867 21937 11169 21937 11170 21938 11171 21938 11172 21938 11172 21939 12850 21939 11170 21939 11170 21940 12850 21940 12852 21940 11170 21941 12852 21941 10867 21941 10867 21942 12852 21942 11173 21942 10867 21943 11173 21943 11169 21943 11174 21944 11175 21944 11179 21944 11176 21945 11177 21945 11549 21945 11549 21946 11177 21946 11179 21946 11174 21947 11179 21947 11178 21947 11178 21948 11179 21948 12882 21948 12882 21949 11179 21949 11177 21949 12882 21950 11177 21950 11180 21950 11420 21951 11419 21951 12849 21951 12849 21952 12848 21952 11181 21952 11181 21953 12848 21953 12847 21953 11181 21954 12847 21954 11182 21954 12849 21955 11181 21955 11420 21955 11420 21956 11181 21956 13181 21956 11420 21957 13181 21957 11363 21957 11187 21958 13369 21958 11185 21958 11188 21959 11183 21959 11184 21959 11184 21960 11183 21960 10863 21960 11184 21961 10863 21961 11185 21961 11185 21962 10863 21962 11186 21962 11185 21963 11186 21963 11187 21963 11188 21964 11184 21964 10864 21964 10864 21965 11184 21965 13366 21965 10864 21966 13366 21966 11189 21966 11189 21967 13366 21967 13364 21967 11189 21968 13364 21968 10872 21968 13359 21969 11190 21969 10869 21969 13359 21970 10869 21970 13364 21970 13364 21971 10869 21971 10870 21971 13364 21972 10870 21972 10872 21972 11190 21973 13359 21973 11192 21973 11192 21974 13359 21974 11191 21974 11192 21975 11191 21975 11193 21975 11193 21976 11191 21976 11194 21976 11194 21977 11191 21977 13357 21977 11194 21978 13357 21978 11195 21978 11195 21979 13357 21979 11196 21979 11196 21980 13357 21980 13356 21980 11196 21981 13356 21981 10847 21981 10847 21982 13356 21982 10848 21982 10848 21983 13356 21983 11134 21983 10848 21984 11134 21984 11131 21984 9180 21985 9271 21985 9181 21985 9181 21986 9271 21986 9268 21986 9181 21987 9268 21987 11197 21987 11197 21988 9268 21988 9267 21988 11197 21989 9267 21989 11198 21989 11198 21990 9267 21990 9264 21990 11198 21991 9264 21991 11199 21991 11199 21992 9264 21992 11200 21992 11199 21993 11200 21993 9170 21993 9170 21994 11200 21994 9265 21994 9170 21995 9265 21995 9173 21995 9173 21996 9265 21996 9262 21996 9173 21997 9262 21997 9174 21997 9174 21998 9262 21998 9280 21998 9174 21999 9280 21999 11201 21999 11201 22000 9280 22000 9279 22000 11201 22001 9279 22001 11202 22001 11202 22002 9279 22002 11203 22002 11202 22003 11203 22003 11204 22003 11204 22004 11203 22004 11205 22004 11204 22005 11205 22005 9178 22005 9178 22006 11205 22006 9274 22006 9178 22007 9274 22007 9180 22007 9180 22008 9274 22008 9271 22008 11176 22009 11549 22009 13102 22009 13102 22010 11549 22010 11206 22010 13102 22011 11206 22011 11207 22011 11207 22012 11206 22012 11209 22012 11207 22013 11209 22013 11208 22013 11208 22014 11209 22014 11563 22014 11208 22015 11563 22015 13106 22015 13106 22016 11563 22016 11562 22016 13106 22017 11562 22017 13108 22017 13108 22018 11562 22018 11210 22018 13108 22019 11210 22019 13109 22019 13109 22020 11210 22020 11211 22020 13109 22021 11211 22021 11212 22021 11212 22022 11211 22022 11583 22022 11212 22023 11583 22023 11236 22023 11236 22024 11583 22024 11213 22024 11236 22025 11213 22025 11582 22025 11216 22026 11214 22026 11215 22026 11215 22027 13128 22027 11216 22027 11216 22028 13128 22028 13126 22028 11216 22029 13126 22029 11615 22029 11615 22030 13126 22030 11217 22030 11615 22031 11217 22031 11218 22031 11240 22032 13129 22032 11219 22032 11219 22033 13129 22033 11221 22033 11219 22034 11221 22034 11220 22034 11220 22035 11221 22035 11222 22035 11220 22036 11222 22036 11223 22036 11223 22037 11222 22037 11215 22037 11223 22038 11215 22038 11224 22038 11224 22039 11215 22039 11214 22039 11218 22040 11217 22040 11225 22040 11225 22041 11217 22041 11226 22041 11225 22042 11226 22042 11625 22042 11625 22043 11226 22043 13125 22043 11625 22044 13125 22044 11626 22044 11626 22045 13125 22045 11227 22045 11626 22046 11227 22046 11613 22046 11613 22047 11227 22047 11228 22047 11613 22048 11228 22048 11599 22048 11599 22049 11228 22049 11229 22049 11229 22050 11228 22050 13120 22050 11229 22051 13120 22051 10065 22051 10065 22052 13120 22052 13121 22052 10065 22053 13121 22053 11231 22053 11231 22054 13121 22054 11230 22054 11231 22055 11230 22055 10076 22055 10076 22056 11230 22056 11232 22056 10076 22057 11232 22057 10077 22057 10077 22058 11232 22058 13119 22058 10077 22059 13119 22059 11233 22059 11233 22060 13119 22060 11234 22060 11234 22061 13119 22061 13114 22061 11234 22062 13114 22062 10079 22062 10079 22063 13114 22063 11235 22063 10079 22064 11235 22064 10080 22064 11236 22065 11582 22065 13115 22065 13115 22066 11582 22066 11237 22066 13115 22067 11237 22067 11238 22067 11238 22068 11237 22068 10080 22068 11238 22069 10080 22069 11239 22069 11239 22070 10080 22070 11235 22070 11249 22071 11241 22071 12055 22071 13202 22072 12117 22072 11244 22072 12055 22073 11241 22073 11240 22073 11240 22074 11241 22074 13132 22074 11240 22075 13132 22075 13129 22075 11244 22076 12125 22076 11242 22076 11242 22077 12125 22077 11243 22077 11243 22078 12125 22078 11277 22078 11243 22079 11277 22079 13148 22079 13204 22080 13202 22080 11248 22080 11248 22081 13202 22081 11244 22081 11248 22082 11244 22082 13145 22082 13145 22083 11244 22083 11242 22083 11245 22084 11246 22084 11247 22084 13204 22085 11248 22085 13207 22085 13207 22086 11248 22086 13140 22086 13207 22087 13140 22087 11252 22087 12055 22088 11245 22088 11249 22088 11249 22089 11245 22089 11247 22089 11249 22090 11247 22090 13133 22090 13133 22091 11247 22091 13199 22091 13133 22092 13199 22092 13138 22092 13138 22093 13199 22093 13197 22093 13138 22094 13197 22094 13136 22094 13136 22095 13197 22095 11250 22095 13140 22096 13141 22096 11252 22096 11252 22097 13141 22097 11251 22097 11252 22098 11251 22098 13208 22098 13208 22099 11251 22099 11253 22099 13208 22100 11253 22100 11254 22100 11254 22101 11253 22101 11255 22101 11254 22102 11255 22102 11250 22102 11250 22103 11255 22103 13135 22103 11250 22104 13135 22104 13136 22104 11402 22105 10954 22105 11367 22105 11367 22106 10954 22106 10953 22106 11367 22107 10953 22107 10998 22107 10957 22108 11256 22108 11402 22108 11402 22109 11256 22109 11257 22109 11402 22110 11257 22110 10954 22110 10957 22111 11402 22111 10952 22111 10952 22112 11402 22112 11393 22112 10952 22113 11393 22113 10958 22113 9929 22114 11357 22114 11258 22114 13167 22115 9926 22115 11258 22115 11258 22116 9926 22116 9928 22116 11258 22117 9928 22117 9929 22117 9913 22118 9912 22118 13162 22118 13162 22119 9912 22119 11259 22119 13162 22120 11259 22120 13164 22120 13164 22121 11259 22121 11260 22121 13164 22122 11260 22122 13165 22122 13165 22123 11260 22123 9923 22123 13165 22124 9923 22124 13167 22124 13167 22125 9923 22125 11261 22125 13167 22126 11261 22126 9926 22126 11266 22127 11265 22127 11262 22127 11266 22128 11262 22128 11264 22128 13162 22129 13161 22129 9913 22129 9913 22130 13161 22130 13160 22130 9913 22131 13160 22131 11263 22131 11263 22132 13160 22132 13159 22132 11263 22133 13159 22133 9904 22133 9904 22134 13159 22134 13157 22134 9904 22135 13157 22135 9934 22135 9934 22136 13157 22136 11264 22136 9934 22137 11264 22137 9939 22137 9939 22138 11264 22138 11262 22138 11265 22139 11266 22139 11267 22139 11267 22140 11266 22140 11268 22140 11267 22141 11268 22141 11269 22141 11272 22142 11278 22142 11270 22142 11270 22143 11271 22143 11272 22143 11272 22144 11271 22144 11273 22144 11272 22145 11273 22145 13149 22145 13149 22146 11273 22146 11274 22146 13149 22147 11274 22147 13156 22147 13156 22148 11274 22148 11275 22148 13156 22149 11275 22149 11269 22149 11269 22150 11275 22150 11276 22150 11269 22151 11276 22151 11267 22151 13148 22152 11277 22152 13153 22152 13153 22153 11277 22153 11278 22153 13153 22154 11278 22154 13151 22154 13151 22155 11278 22155 11272 22155 11279 22156 11281 22156 11280 22156 11280 22157 11281 22157 9290 22157 11280 22158 9290 22158 11282 22158 11282 22159 9290 22159 11283 22159 11282 22160 11283 22160 11284 22160 11284 22161 11283 22161 11285 22161 11284 22162 11285 22162 9457 22162 9457 22163 11285 22163 11286 22163 9457 22164 11286 22164 9459 22164 9459 22165 11286 22165 9282 22165 9459 22166 9282 22166 11287 22166 11287 22167 9282 22167 11288 22167 11287 22168 11288 22168 11289 22168 11289 22169 11288 22169 11290 22169 11289 22170 11290 22170 11292 22170 11292 22171 11290 22171 11291 22171 11292 22172 11291 22172 11293 22172 11293 22173 11291 22173 9286 22173 11293 22174 9286 22174 11294 22174 11294 22175 9286 22175 11295 22175 11294 22176 11295 22176 9461 22176 9461 22177 11295 22177 11296 22177 9461 22178 11296 22178 11279 22178 11279 22179 11296 22179 11281 22179 11306 22180 11297 22180 9475 22180 9475 22181 11297 22181 11298 22181 9475 22182 11298 22182 9478 22182 9478 22183 11298 22183 11299 22183 9478 22184 11299 22184 9464 22184 9464 22185 11299 22185 9292 22185 9464 22186 9292 22186 11300 22186 11300 22187 9292 22187 11301 22187 11300 22188 11301 22188 9465 22188 9465 22189 11301 22189 9295 22189 9465 22190 9295 22190 11302 22190 11302 22191 9295 22191 9297 22191 11302 22192 9297 22192 9467 22192 9467 22193 9297 22193 9298 22193 9467 22194 9298 22194 9469 22194 9469 22195 9298 22195 11303 22195 9469 22196 11303 22196 9470 22196 9470 22197 11303 22197 9299 22197 9470 22198 9299 22198 9473 22198 9473 22199 9299 22199 11304 22199 9473 22200 11304 22200 11305 22200 11305 22201 11304 22201 11307 22201 11305 22202 11307 22202 11306 22202 11306 22203 11307 22203 11297 22203 10997 22204 11308 22204 11373 22204 11308 22205 11309 22205 11373 22205 11373 22206 11309 22206 10992 22206 11373 22207 10992 22207 11354 22207 11373 22208 11371 22208 10997 22208 10997 22209 11371 22209 11310 22209 10997 22210 11310 22210 10994 22210 10994 22211 11310 22211 11311 22211 11311 22212 11310 22212 11370 22212 11311 22213 11370 22213 11001 22213 11001 22214 11370 22214 10999 22214 10999 22215 11370 22215 11367 22215 10999 22216 11367 22216 10998 22216 11321 22217 11313 22217 11312 22217 11312 22218 11313 22218 9304 22218 11312 22219 9304 22219 9199 22219 9199 22220 9304 22220 9305 22220 9199 22221 9305 22221 9200 22221 9200 22222 9305 22222 9323 22222 9200 22223 9323 22223 11314 22223 11314 22224 9323 22224 9319 22224 11314 22225 9319 22225 9204 22225 9204 22226 9319 22226 11315 22226 9204 22227 11315 22227 11317 22227 11317 22228 11315 22228 11316 22228 11317 22229 11316 22229 9206 22229 9206 22230 11316 22230 9313 22230 9206 22231 9313 22231 11319 22231 11319 22232 9313 22232 11318 22232 11319 22233 11318 22233 9207 22233 9207 22234 11318 22234 9310 22234 9207 22235 9310 22235 9208 22235 9208 22236 9310 22236 9307 22236 9208 22237 9307 22237 11320 22237 11320 22238 9307 22238 11322 22238 11320 22239 11322 22239 11321 22239 11321 22240 11322 22240 11313 22240 11324 22241 11323 22241 11646 22241 11324 22242 11646 22242 11327 22242 11646 22243 11325 22243 11327 22243 11327 22244 11325 22244 11326 22244 11327 22245 11326 22245 11055 22245 11055 22246 11326 22246 11647 22246 11055 22247 11647 22247 11328 22247 11328 22248 11647 22248 11330 22248 11328 22249 11330 22249 11331 22249 11332 22250 11329 22250 11030 22250 11329 22251 11332 22251 11061 22251 11330 22252 11344 22252 11331 22252 11331 22253 11344 22253 11342 22253 11331 22254 11342 22254 11030 22254 11030 22255 11342 22255 11347 22255 11030 22256 11347 22256 11332 22256 11333 22257 9332 22257 9434 22257 9434 22258 9332 22258 11334 22258 9434 22259 11334 22259 11335 22259 11335 22260 11334 22260 11336 22260 11335 22261 11336 22261 11337 22261 11337 22262 11336 22262 9327 22262 11337 22263 9327 22263 9445 22263 9445 22264 9327 22264 9325 22264 9445 22265 9325 22265 9444 22265 9444 22266 9325 22266 11338 22266 9444 22267 11338 22267 9442 22267 9442 22268 11338 22268 9341 22268 9442 22269 9341 22269 9441 22269 9441 22270 9341 22270 9340 22270 9441 22271 9340 22271 9440 22271 9440 22272 9340 22272 11340 22272 9440 22273 11340 22273 11339 22273 11339 22274 11340 22274 9337 22274 11339 22275 9337 22275 9438 22275 9438 22276 9337 22276 9335 22276 9438 22277 9335 22277 9436 22277 9436 22278 9335 22278 11341 22278 9436 22279 11341 22279 11333 22279 11333 22280 11341 22280 9332 22280 11346 22281 11342 22281 11343 22281 11343 22282 11342 22282 11344 22282 11343 22283 11344 22283 11330 22283 11063 22284 11061 22284 11345 22284 11345 22285 11061 22285 11332 22285 11345 22286 11332 22286 11346 22286 11346 22287 11332 22287 11347 22287 11346 22288 11347 22288 11342 22288 11350 22289 11068 22289 11348 22289 11348 22290 11068 22290 11069 22290 11348 22291 11069 22291 11345 22291 11345 22292 11069 22292 11349 22292 11345 22293 11349 22293 11063 22293 11350 22294 11348 22294 11351 22294 11351 22295 11348 22295 11377 22295 11351 22296 11377 22296 11352 22296 11352 22297 11377 22297 11376 22297 11352 22298 11376 22298 11064 22298 11374 22299 11373 22299 11354 22299 11064 22300 11376 22300 11353 22300 11353 22301 11376 22301 11356 22301 11354 22302 11355 22302 11374 22302 11374 22303 11355 22303 11072 22303 11374 22304 11072 22304 11356 22304 11356 22305 11072 22305 11070 22305 11356 22306 11070 22306 11353 22306 11362 22307 11663 22307 13179 22307 13179 22308 11663 22308 13180 22308 11357 22309 9929 22309 13172 22309 13172 22310 9929 22310 11358 22310 13172 22311 11358 22311 13171 22311 13171 22312 11358 22312 11658 22312 13171 22313 11658 22313 11359 22313 11359 22314 11658 22314 11657 22314 11359 22315 11657 22315 11360 22315 11360 22316 11657 22316 11361 22316 11360 22317 11361 22317 13176 22317 13176 22318 11361 22318 11362 22318 13176 22319 11362 22319 13178 22319 13178 22320 11362 22320 13179 22320 11363 22321 13181 22321 11668 22321 11668 22322 13181 22322 11364 22322 11668 22323 11364 22323 11666 22323 11666 22324 11364 22324 13180 22324 11666 22325 13180 22325 11365 22325 11365 22326 13180 22326 11663 22326 11746 22327 11366 22327 11370 22327 11370 22328 11366 22328 11367 22328 11368 22329 11395 22329 11406 22329 11343 22330 11757 22330 11346 22330 11346 22331 11757 22331 11765 22331 11755 22332 11753 22332 11369 22332 11369 22333 11753 22333 11751 22333 11369 22334 11751 22334 11343 22334 11343 22335 11751 22335 11759 22335 11343 22336 11759 22336 11757 22336 11746 22337 11370 22337 11739 22337 11739 22338 11370 22338 11310 22338 11739 22339 11310 22339 11732 22339 11732 22340 11310 22340 11371 22340 11732 22341 11371 22341 11372 22341 11372 22342 11371 22342 11373 22342 11372 22343 11373 22343 11735 22343 11735 22344 11373 22344 11374 22344 11735 22345 11374 22345 11737 22345 11737 22346 11374 22346 11356 22346 11737 22347 11356 22347 11375 22347 11375 22348 11356 22348 11376 22348 11375 22349 11376 22349 11762 22349 11762 22350 11376 22350 11377 22350 11762 22351 11377 22351 11378 22351 11378 22352 11377 22352 11348 22352 11378 22353 11348 22353 11765 22353 11765 22354 11348 22354 11345 22354 11765 22355 11345 22355 11346 22355 11379 22356 11380 22356 11381 22356 11381 22357 11380 22357 11798 22357 11381 22358 11798 22358 11403 22358 11369 22359 11398 22359 11755 22359 11755 22360 11398 22360 11698 22360 11755 22361 11698 22361 11742 22361 11742 22362 11698 22362 11382 22362 11381 22363 11718 22363 11379 22363 11379 22364 11718 22364 11717 22364 11379 22365 11717 22365 11785 22365 11785 22366 11717 22366 11368 22366 11785 22367 11368 22367 11788 22367 11788 22368 11368 22368 11406 22368 11788 22369 11406 22369 11383 22369 11383 22370 11406 22370 11405 22370 11383 22371 11405 22371 11775 22371 11775 22372 11405 22372 11385 22372 11775 22373 11385 22373 11384 22373 11384 22374 11385 22374 11117 22374 11384 22375 11117 22375 11386 22375 11386 22376 11117 22376 11108 22376 11386 22377 11108 22377 11778 22377 11778 22378 11108 22378 11387 22378 11778 22379 11387 22379 11767 22379 11767 22380 11387 22380 11388 22380 11767 22381 11388 22381 11769 22381 11769 22382 11388 22382 11389 22382 11769 22383 11389 22383 11390 22383 11390 22384 11389 22384 11391 22384 11390 22385 11391 22385 11773 22385 11773 22386 11391 22386 11103 22386 11773 22387 11103 22387 11392 22387 11392 22388 11103 22388 11102 22388 11392 22389 11102 22389 11793 22389 11793 22390 11102 22390 11393 22390 11793 22391 11393 22391 11394 22391 11394 22392 11393 22392 11402 22392 11394 22393 11402 22393 11795 22393 11366 22394 11399 22394 11367 22394 11367 22395 11399 22395 11400 22395 11367 22396 11400 22396 11401 22396 11395 22397 11396 22397 11406 22397 11406 22398 11396 22398 11397 22398 11406 22399 11397 22399 11398 22399 11398 22400 11397 22400 11688 22400 11398 22401 11688 22401 11698 22401 11382 22402 11693 22402 11742 22402 11742 22403 11693 22403 11691 22403 11742 22404 11691 22404 11399 22404 11399 22405 11691 22405 11709 22405 11399 22406 11709 22406 11400 22406 11401 22407 11713 22407 11367 22407 11367 22408 11713 22408 11723 22408 11367 22409 11723 22409 11402 22409 11402 22410 11723 22410 11403 22410 11402 22411 11403 22411 11795 22411 11795 22412 11403 22412 11798 22412 11120 22413 11114 22413 11405 22413 11120 22414 11405 22414 11404 22414 11404 22415 11405 22415 11406 22415 11404 22416 11406 22416 11407 22416 11407 22417 11406 22417 11119 22417 11119 22418 11406 22418 11398 22418 11119 22419 11398 22419 11323 22419 11417 22420 11413 22420 13365 22420 13367 22421 11408 22421 13368 22421 11409 22422 13358 22422 11410 22422 13367 22423 13368 22423 11411 22423 11413 22424 13351 22424 11412 22424 13370 22425 11417 22425 13368 22425 13368 22426 11417 22426 13365 22426 13368 22427 13365 22427 11411 22427 11412 22428 13354 22428 11413 22428 11413 22429 13354 22429 11414 22429 11413 22430 11414 22430 13365 22430 13365 22431 11414 22431 13355 22431 13365 22432 13355 22432 11410 22432 11410 22433 13355 22433 11415 22433 11410 22434 11415 22434 11409 22434 13370 22435 11416 22435 11417 22435 11417 22436 11416 22436 13361 22436 11417 22437 13361 22437 13363 22437 13371 22438 13369 22438 11418 22438 11418 22439 13369 22439 11187 22439 11419 22440 11420 22440 11426 22440 11419 22441 11426 22441 11421 22441 11421 22442 11426 22442 11422 22442 11421 22443 11422 22443 12851 22443 12851 22444 11422 22444 11424 22444 12851 22445 11424 22445 11423 22445 11423 22446 11424 22446 11442 22446 11423 22447 11442 22447 11425 22447 11420 22448 11363 22448 11426 22448 11426 22449 11363 22449 11667 22449 11426 22450 11667 22450 11422 22450 11422 22451 11667 22451 11427 22451 11422 22452 11427 22452 11424 22452 11424 22453 11427 22453 11683 22453 11424 22454 11683 22454 11442 22454 11442 22455 11683 22455 11440 22455 11473 22456 11437 22456 11434 22456 11428 22457 11470 22457 11471 22457 11467 22458 12369 22458 11429 22458 11429 22459 12369 22459 11430 22459 11429 22460 11430 22460 11465 22460 11465 22461 11430 22461 11432 22461 11465 22462 11432 22462 11431 22462 11431 22463 11432 22463 11433 22463 11437 22464 12391 22464 11434 22464 11434 22465 12391 22465 11435 22465 11434 22466 11435 22466 12370 22466 11439 22467 12390 22467 12393 22467 11472 22468 11436 22468 11437 22468 11437 22469 11436 22469 11438 22469 11437 22470 11438 22470 12391 22470 12388 22471 11673 22471 12387 22471 12387 22472 11673 22472 12386 22472 11671 22473 12384 22473 11673 22473 11673 22474 12384 22474 12385 22474 11673 22475 12385 22475 12386 22475 12388 22476 12390 22476 11673 22476 11673 22477 12390 22477 11439 22477 11673 22478 11439 22478 11440 22478 11440 22479 11439 22479 11441 22479 11440 22480 11441 22480 11444 22480 12853 22481 11425 22481 11442 22481 11442 22482 11443 22482 12853 22482 12853 22483 11443 22483 11445 22483 12853 22484 11445 22484 11447 22484 11442 22485 11440 22485 11443 22485 11443 22486 11440 22486 11444 22486 11443 22487 11444 22487 11445 22487 11445 22488 11444 22488 11446 22488 11445 22489 11446 22489 11447 22489 11447 22490 11446 22490 12854 22490 12856 22491 11448 22491 11449 22491 11449 22492 11448 22492 11469 22492 11449 22493 11469 22493 11450 22493 11450 22494 11469 22494 11460 22494 11450 22495 11460 22495 12864 22495 11451 22496 11452 22496 11454 22496 11452 22497 11453 22497 11454 22497 11454 22498 11453 22498 11455 22498 11454 22499 11455 22499 12862 22499 11455 22500 11456 22500 12862 22500 12862 22501 11456 22501 11864 22501 12862 22502 11864 22502 12860 22502 12860 22503 11864 22503 12859 22503 11864 22504 11881 22504 12859 22504 12859 22505 11881 22505 11457 22505 12859 22506 11457 22506 11476 22506 11476 22507 11457 22507 11458 22507 11476 22508 11458 22508 11459 22508 11536 22509 12878 22509 11476 22509 11454 22510 12864 22510 11451 22510 11451 22511 12864 22511 11460 22511 11451 22512 11460 22512 11461 22512 11461 22513 11460 22513 11462 22513 11470 22514 11838 22514 11468 22514 11838 22515 11470 22515 11463 22515 11463 22516 11470 22516 11428 22516 11463 22517 11428 22517 11480 22517 11874 22518 11873 22518 11477 22518 11477 22519 11873 22519 11464 22519 11477 22520 11464 22520 11478 22520 11478 22521 11464 22521 11898 22521 11478 22522 11898 22522 11431 22522 11431 22523 11898 22523 11890 22523 11431 22524 11890 22524 11465 22524 11465 22525 11890 22525 11825 22525 11465 22526 11825 22526 11429 22526 11466 22527 11475 22527 11483 22527 11483 22528 11475 22528 11474 22528 11483 22529 11474 22529 11482 22529 11482 22530 11474 22530 11473 22530 11482 22531 11473 22531 11481 22531 11481 22532 11473 22532 11434 22532 11481 22533 11434 22533 11467 22533 11467 22534 11434 22534 12370 22534 11467 22535 12370 22535 12369 22535 11462 22536 11460 22536 11468 22536 11468 22537 11460 22537 11469 22537 11468 22538 11469 22538 11470 22538 11470 22539 11469 22539 11448 22539 11470 22540 11448 22540 11471 22540 12393 22541 11472 22541 11439 22541 11439 22542 11472 22542 11437 22542 11439 22543 11437 22543 11441 22543 11441 22544 11437 22544 11473 22544 11441 22545 11473 22545 11444 22545 11444 22546 11473 22546 11474 22546 11444 22547 11474 22547 11446 22547 11446 22548 11474 22548 11475 22548 11446 22549 11475 22549 12854 22549 12854 22550 11475 22550 11466 22550 11459 22551 11874 22551 11476 22551 11476 22552 11874 22552 11477 22552 11476 22553 11477 22553 11536 22553 11536 22554 11477 22554 11478 22554 11536 22555 11478 22555 11479 22555 11479 22556 11478 22556 11431 22556 11479 22557 11431 22557 11500 22557 11500 22558 11431 22558 11433 22558 11825 22559 11824 22559 11429 22559 11429 22560 11824 22560 11480 22560 11429 22561 11480 22561 11467 22561 11467 22562 11480 22562 11428 22562 11467 22563 11428 22563 11481 22563 11481 22564 11428 22564 11471 22564 11481 22565 11471 22565 11482 22565 11482 22566 11471 22566 11448 22566 11482 22567 11448 22567 11483 22567 11483 22568 11448 22568 12856 22568 11483 22569 12856 22569 11466 22569 11531 22570 11484 22570 11526 22570 11537 22571 11511 22571 11524 22571 11485 22572 11986 22572 11512 22572 11538 22573 11559 22573 11486 22573 11488 22574 11560 22574 11487 22574 11487 22575 12376 22575 11488 22575 11488 22576 12376 22576 11489 22576 11488 22577 11489 22577 12373 22577 11493 22578 11490 22578 11538 22578 11538 22579 11490 22579 11491 22579 11538 22580 11491 22580 11559 22580 11559 22581 11491 22581 11492 22581 11559 22582 11492 22582 11560 22582 11560 22583 11492 22583 12375 22583 11560 22584 12375 22584 11487 22584 11493 22585 11538 22585 11494 22585 11494 22586 11538 22586 11495 22586 11494 22587 11495 22587 12382 22587 12382 22588 11495 22588 11496 22588 12382 22589 11496 22589 12359 22589 12359 22590 11496 22590 11541 22590 12359 22591 11541 22591 11497 22591 11497 22592 11541 22592 11498 22592 11497 22593 11498 22593 12361 22593 12361 22594 11498 22594 11513 22594 12361 22595 11513 22595 11499 22595 11499 22596 11513 22596 11534 22596 11499 22597 11534 22597 12363 22597 11500 22598 11433 22598 12363 22598 11535 22599 11502 22599 11501 22599 11503 22600 11502 22600 11979 22600 11979 22601 11502 22601 11535 22601 11979 22602 11535 22602 11949 22602 11949 22603 11535 22603 11515 22603 11503 22604 11978 22604 11502 22604 11502 22605 11978 22605 11977 22605 11502 22606 11977 22606 12875 22606 11977 22607 11504 22607 12875 22607 12875 22608 11504 22608 11975 22608 12875 22609 11975 22609 11505 22609 11975 22610 11984 22610 11505 22610 11505 22611 11984 22611 11506 22611 11505 22612 11506 22612 12874 22612 12874 22613 11506 22613 12873 22613 12873 22614 11506 22614 12011 22614 12873 22615 12011 22615 11507 22615 11485 22616 11512 22616 11987 22616 11533 22617 11532 22617 12871 22617 12871 22618 11532 22618 11530 22618 12871 22619 11530 22619 11508 22619 11508 22620 11530 22620 11509 22620 11508 22621 11509 22621 12868 22621 12868 22622 11509 22622 11529 22622 12868 22623 11529 22623 11528 22623 11522 22624 11521 22624 11527 22624 11527 22625 11521 22625 11520 22625 11519 22626 11511 22626 11510 22626 11510 22627 11511 22627 11537 22627 11510 22628 11537 22628 11486 22628 11507 22629 11987 22629 12873 22629 12873 22630 11987 22630 11512 22630 12873 22631 11512 22631 11531 22631 11531 22632 11512 22632 11986 22632 11498 22633 11940 22633 11513 22633 11513 22634 11940 22634 11942 22634 11513 22635 11942 22635 11534 22635 11534 22636 11942 22636 11514 22636 11534 22637 11514 22637 11515 22637 11515 22638 11514 22638 11950 22638 11515 22639 11950 22639 11949 22639 11986 22640 11516 22640 11531 22640 11531 22641 11516 22641 11985 22641 11531 22642 11985 22642 11484 22642 11484 22643 11985 22643 11517 22643 11484 22644 11517 22644 11518 22644 11542 22645 11520 22645 11519 22645 11519 22646 11520 22646 11521 22646 11519 22647 11521 22647 11511 22647 11511 22648 11521 22648 11522 22648 11511 22649 11522 22649 11524 22649 11523 22650 11525 22650 11524 22650 11524 22651 11525 22651 11539 22651 11524 22652 11539 22652 11537 22652 11518 22653 11540 22653 11484 22653 11484 22654 11540 22654 11525 22654 11484 22655 11525 22655 11526 22655 11526 22656 11525 22656 11523 22656 11527 22657 11528 22657 11522 22657 11522 22658 11528 22658 11529 22658 11522 22659 11529 22659 11524 22659 11524 22660 11529 22660 11509 22660 11524 22661 11509 22661 11523 22661 11523 22662 11509 22662 11530 22662 11523 22663 11530 22663 11526 22663 11526 22664 11530 22664 11532 22664 11526 22665 11532 22665 11531 22665 11531 22666 11532 22666 11533 22666 11531 22667 11533 22667 12873 22667 12363 22668 11534 22668 11500 22668 11500 22669 11534 22669 11515 22669 11500 22670 11515 22670 11479 22670 11479 22671 11515 22671 11535 22671 11479 22672 11535 22672 11536 22672 11536 22673 11535 22673 11501 22673 11536 22674 11501 22674 12878 22674 11486 22675 11537 22675 11538 22675 11538 22676 11537 22676 11539 22676 11538 22677 11539 22677 11495 22677 11495 22678 11539 22678 11525 22678 11495 22679 11525 22679 11496 22679 11496 22680 11525 22680 11540 22680 11496 22681 11540 22681 11541 22681 11541 22682 11540 22682 11518 22682 11541 22683 11518 22683 11498 22683 11498 22684 11518 22684 11938 22684 11498 22685 11938 22685 11940 22685 11542 22686 11519 22686 11546 22686 11542 22687 11546 22687 11543 22687 11543 22688 11546 22688 11547 22688 11543 22689 11547 22689 11544 22689 11544 22690 11547 22690 11548 22690 11544 22691 11548 22691 11545 22691 11545 22692 11548 22692 11179 22692 11545 22693 11179 22693 11175 22693 11519 22694 11510 22694 11546 22694 11546 22695 11510 22695 11577 22695 11546 22696 11577 22696 11547 22696 11547 22697 11577 22697 11576 22697 11547 22698 11576 22698 11548 22698 11548 22699 11576 22699 11569 22699 11548 22700 11569 22700 11179 22700 11179 22701 11569 22701 11549 22701 9185 22702 9348 22702 11550 22702 11550 22703 9348 22703 11551 22703 11550 22704 11551 22704 9186 22704 9186 22705 11551 22705 9367 22705 9186 22706 9367 22706 9187 22706 9187 22707 9367 22707 11552 22707 9187 22708 11552 22708 11553 22708 11553 22709 11552 22709 9365 22709 11553 22710 9365 22710 9191 22710 9191 22711 9365 22711 11554 22711 9191 22712 11554 22712 9192 22712 9192 22713 11554 22713 9363 22713 9192 22714 9363 22714 9193 22714 9193 22715 9363 22715 9358 22715 9193 22716 9358 22716 9194 22716 9194 22717 9358 22717 9361 22717 9194 22718 9361 22718 11555 22718 11555 22719 9361 22719 9355 22719 11555 22720 9355 22720 9196 22720 9196 22721 9355 22721 9353 22721 9196 22722 9353 22722 11556 22722 11556 22723 9353 22723 9351 22723 11556 22724 9351 22724 9185 22724 9185 22725 9351 22725 9348 22725 12397 22726 11570 22726 11558 22726 12396 22727 12401 22727 11572 22727 11572 22728 12401 22728 12400 22728 11572 22729 12400 22729 11571 22729 11571 22730 12400 22730 11557 22730 11571 22731 11557 22731 11558 22731 11558 22732 11557 22732 12398 22732 11558 22733 12398 22733 12397 22733 11575 22734 11488 22734 11572 22734 11572 22735 11488 22735 12373 22735 11572 22736 12373 22736 12396 22736 11510 22737 11486 22737 11577 22737 11577 22738 11486 22738 11559 22738 11577 22739 11559 22739 11575 22739 11575 22740 11559 22740 11560 22740 11575 22741 11560 22741 11488 22741 11593 22742 11210 22742 11562 22742 11592 22743 11593 22743 11561 22743 11570 22744 11592 22744 11566 22744 11593 22745 11562 22745 11561 22745 11561 22746 11562 22746 11563 22746 11561 22747 11563 22747 11567 22747 11567 22748 11563 22748 11209 22748 11567 22749 11209 22749 11564 22749 11564 22750 11209 22750 11206 22750 11564 22751 11206 22751 11565 22751 11565 22752 11206 22752 11549 22752 11565 22753 11549 22753 11569 22753 11592 22754 11561 22754 11566 22754 11566 22755 11561 22755 11567 22755 11566 22756 11567 22756 11568 22756 11568 22757 11567 22757 11564 22757 11568 22758 11564 22758 11573 22758 11573 22759 11564 22759 11565 22759 11573 22760 11565 22760 11574 22760 11574 22761 11565 22761 11569 22761 11574 22762 11569 22762 11576 22762 11570 22763 11566 22763 11558 22763 11558 22764 11566 22764 11568 22764 11558 22765 11568 22765 11571 22765 11571 22766 11568 22766 11573 22766 11571 22767 11573 22767 11572 22767 11572 22768 11573 22768 11574 22768 11572 22769 11574 22769 11575 22769 11575 22770 11574 22770 11576 22770 11575 22771 11576 22771 11577 22771 11591 22772 11578 22772 11590 22772 12412 22773 11586 22773 11585 22773 12409 22774 12407 22774 11579 22774 11579 22775 12407 22775 11580 22775 11579 22776 11580 22776 11584 22776 11584 22777 11580 22777 10090 22777 11584 22778 10090 22778 11581 22778 11581 22779 10090 22779 10089 22779 11581 22780 10089 22780 11213 22780 11213 22781 10089 22781 11582 22781 11213 22782 11583 22782 11581 22782 11581 22783 11583 22783 11587 22783 11581 22784 11587 22784 11584 22784 11584 22785 11587 22785 11588 22785 11584 22786 11588 22786 11579 22786 11579 22787 11588 22787 11585 22787 11579 22788 11585 22788 12409 22788 12409 22789 11585 22789 11586 22789 11583 22790 11211 22790 11587 22790 11587 22791 11211 22791 11594 22791 11587 22792 11594 22792 11588 22792 11588 22793 11594 22793 11589 22793 11588 22794 11589 22794 11585 22794 11585 22795 11589 22795 11590 22795 11585 22796 11590 22796 12412 22796 12412 22797 11590 22797 11578 22797 12397 22798 11591 22798 11570 22798 11570 22799 11591 22799 11590 22799 11570 22800 11590 22800 11592 22800 11592 22801 11590 22801 11589 22801 11592 22802 11589 22802 11593 22802 11593 22803 11589 22803 11594 22803 11593 22804 11594 22804 11210 22804 11210 22805 11594 22805 11211 22805 11595 22806 11609 22806 11596 22806 11595 22807 11596 22807 9079 22807 9079 22808 11596 22808 10066 22808 10066 22809 11596 22809 11620 22809 10066 22810 11620 22810 11597 22810 11597 22811 11620 22811 11619 22811 11597 22812 11619 22812 11598 22812 11598 22813 11613 22813 11597 22813 11597 22814 11613 22814 11599 22814 11597 22815 11599 22815 10064 22815 10064 22816 11599 22816 11229 22816 11623 22817 11621 22817 11214 22817 11600 22818 13374 22818 11601 22818 11601 22819 13374 22819 13378 22819 11601 22820 13378 22820 11604 22820 11602 22821 13372 22821 11606 22821 11606 22822 13372 22822 13387 22822 11606 22823 13387 22823 11600 22823 11600 22824 13387 22824 13388 22824 11600 22825 13388 22825 13374 22825 11609 22826 11603 22826 11611 22826 11611 22827 11603 22827 11610 22827 11604 22828 12057 22828 11601 22828 11601 22829 12057 22829 11605 22829 11601 22830 11605 22830 11600 22830 11600 22831 11605 22831 11622 22831 11600 22832 11622 22832 11606 22832 11606 22833 11622 22833 11607 22833 11606 22834 11607 22834 11602 22834 11602 22835 11607 22835 11608 22835 11602 22836 11608 22836 11611 22836 11611 22837 11608 22837 11624 22837 11611 22838 11624 22838 11609 22838 11610 22839 9769 22839 11611 22839 11611 22840 9769 22840 11612 22840 11611 22841 11612 22841 11602 22841 11602 22842 11612 22842 9774 22842 11602 22843 9774 22843 13372 22843 11613 22844 11598 22844 11626 22844 11626 22845 11598 22845 11618 22845 11214 22846 11621 22846 11224 22846 11224 22847 11621 22847 11614 22847 11224 22848 11614 22848 11223 22848 11223 22849 11614 22849 12058 22849 11223 22850 12058 22850 11220 22850 11214 22851 11216 22851 11623 22851 11623 22852 11216 22852 11615 22852 11623 22853 11615 22853 11616 22853 11616 22854 11615 22854 11218 22854 11616 22855 11218 22855 11617 22855 11617 22856 11218 22856 11225 22856 11617 22857 11225 22857 11625 22857 11598 22858 11619 22858 11618 22858 11618 22859 11619 22859 11620 22859 11618 22860 11620 22860 11624 22860 11624 22861 11620 22861 11596 22861 11624 22862 11596 22862 11609 22862 12057 22863 12058 22863 11605 22863 11605 22864 12058 22864 11614 22864 11605 22865 11614 22865 11622 22865 11622 22866 11614 22866 11621 22866 11622 22867 11621 22867 11607 22867 11607 22868 11621 22868 11623 22868 11607 22869 11623 22869 11608 22869 11608 22870 11623 22870 11616 22870 11608 22871 11616 22871 11624 22871 11624 22872 11616 22872 11617 22872 11624 22873 11617 22873 11618 22873 11618 22874 11617 22874 11625 22874 11618 22875 11625 22875 11626 22875 11220 22876 12054 22876 11219 22876 11219 22877 12054 22877 12055 22877 11219 22878 12055 22878 11240 22878 12094 22879 13201 22879 11627 22879 11627 22880 13201 22880 13195 22880 11627 22881 13195 22881 12093 22881 12093 22882 13195 22882 13196 22882 12093 22883 13196 22883 12086 22883 12086 22884 13196 22884 13198 22884 12086 22885 13198 22885 12077 22885 12077 22886 13198 22886 11628 22886 13201 22887 12094 22887 13200 22887 13200 22888 12094 22888 11632 22888 12091 22889 11630 22889 11629 22889 11629 22890 11630 22890 13203 22890 11629 22891 13203 22891 11631 22891 11631 22892 13203 22892 13205 22892 11631 22893 13205 22893 12080 22893 12080 22894 13205 22894 13206 22894 12080 22895 13206 22895 11632 22895 11632 22896 13206 22896 13200 22896 11270 22897 11278 22897 12129 22897 12129 22898 11278 22898 11277 22898 12129 22899 11277 22899 12125 22899 11644 22900 11645 22900 11633 22900 11633 22901 11645 22901 11634 22901 11633 22902 11634 22902 11635 22902 11635 22903 11634 22903 11637 22903 11635 22904 11637 22904 11636 22904 11636 22905 11637 22905 9386 22905 11636 22906 9386 22906 9210 22906 9210 22907 9386 22907 11638 22907 9210 22908 11638 22908 11639 22908 11639 22909 11638 22909 9383 22909 11639 22910 9383 22910 9211 22910 9211 22911 9383 22911 9378 22911 9211 22912 9378 22912 11640 22912 11640 22913 9378 22913 9377 22913 11640 22914 9377 22914 9214 22914 9214 22915 9377 22915 11641 22915 9214 22916 11641 22916 9216 22916 9216 22917 11641 22917 11642 22917 9216 22918 11642 22918 9218 22918 9218 22919 11642 22919 11643 22919 9218 22920 11643 22920 9219 22920 9219 22921 11643 22921 9371 22921 9219 22922 9371 22922 11644 22922 11644 22923 9371 22923 11645 22923 11646 22924 11323 22924 11398 22924 11646 22925 11398 22925 11325 22925 11325 22926 11398 22926 11326 22926 11326 22927 11398 22927 11369 22927 11326 22928 11369 22928 11647 22928 11647 22929 11369 22929 11343 22929 11647 22930 11343 22930 11330 22930 11648 22931 12418 22931 11662 22931 11648 22932 11662 22932 11649 22932 12414 22933 12416 22933 11655 22933 11358 22934 9929 22934 11650 22934 11650 22935 9929 22935 11651 22935 11650 22936 11651 22936 11654 22936 11654 22937 11651 22937 9930 22937 11654 22938 9930 22938 11656 22938 11656 22939 9930 22939 9906 22939 11656 22940 9906 22940 12413 22940 11658 22941 11358 22941 11652 22941 11652 22942 11358 22942 11650 22942 11652 22943 11650 22943 11653 22943 11653 22944 11650 22944 11654 22944 11653 22945 11654 22945 11655 22945 11655 22946 11654 22946 11656 22946 11655 22947 11656 22947 12414 22947 12414 22948 11656 22948 12413 22948 11657 22949 11658 22949 11659 22949 11659 22950 11658 22950 11652 22950 11659 22951 11652 22951 11661 22951 11661 22952 11652 22952 11653 22952 11661 22953 11653 22953 11662 22953 11662 22954 11653 22954 11655 22954 11662 22955 11655 22955 11649 22955 11649 22956 11655 22956 12416 22956 11361 22957 11657 22957 11684 22957 11684 22958 11657 22958 11659 22958 11684 22959 11659 22959 11660 22959 11660 22960 11659 22960 11661 22960 11660 22961 11661 22961 11677 22961 11677 22962 11661 22962 11662 22962 11677 22963 11662 22963 11676 22963 11676 22964 11662 22964 12418 22964 11440 22965 11683 22965 11672 22965 11685 22966 11663 22966 11664 22966 11664 22967 11663 22967 11362 22967 11664 22968 11362 22968 11665 22968 11665 22969 11362 22969 11361 22969 11665 22970 11361 22970 11684 22970 11668 22971 11666 22971 11685 22971 11685 22972 11666 22972 11365 22972 11685 22973 11365 22973 11663 22973 11685 22974 11686 22974 11668 22974 11668 22975 11686 22975 11667 22975 11668 22976 11667 22976 11363 22976 11669 22977 11670 22977 11681 22977 11681 22978 11670 22978 11671 22978 11681 22979 11671 22979 11672 22979 11672 22980 11671 22980 11673 22980 11672 22981 11673 22981 11440 22981 11669 22982 11681 22982 11674 22982 11674 22983 11681 22983 11675 22983 11674 22984 11675 22984 12403 22984 12403 22985 11675 22985 11679 22985 12403 22986 11679 22986 12405 22986 11676 22987 12405 22987 11677 22987 11677 22988 12405 22988 11679 22988 11677 22989 11679 22989 11660 22989 11684 22990 11660 22990 11678 22990 11660 22991 11679 22991 11678 22991 11678 22992 11679 22992 11675 22992 11678 22993 11675 22993 11680 22993 11680 22994 11675 22994 11681 22994 11680 22995 11681 22995 11682 22995 11682 22996 11681 22996 11672 22996 11682 22997 11672 22997 11687 22997 11687 22998 11672 22998 11683 22998 11687 22999 11683 22999 11427 22999 11684 23000 11678 23000 11665 23000 11665 23001 11678 23001 11680 23001 11665 23002 11680 23002 11664 23002 11664 23003 11680 23003 11682 23003 11664 23004 11682 23004 11685 23004 11685 23005 11682 23005 11687 23005 11685 23006 11687 23006 11686 23006 11686 23007 11687 23007 11427 23007 11686 23008 11427 23008 11667 23008 9538 23009 9539 23009 11397 23009 11397 23010 9539 23010 9540 23010 11397 23011 9540 23011 11688 23011 11688 23012 9540 23012 9536 23012 11688 23013 9536 23013 11689 23013 11693 23014 11696 23014 11691 23014 11691 23015 11696 23015 11690 23015 11691 23016 11690 23016 9548 23016 11382 23017 11692 23017 11693 23017 11693 23018 11692 23018 9542 23018 9542 23019 11694 23019 11693 23019 11693 23020 11694 23020 11695 23020 11693 23021 11695 23021 11696 23021 11697 23022 9541 23022 11698 23022 11698 23023 9541 23023 11699 23023 11698 23024 11699 23024 11382 23024 11382 23025 11699 23025 9544 23025 11382 23026 9544 23026 11692 23026 11688 23027 11689 23027 11700 23027 11688 23028 11700 23028 11698 23028 11698 23029 11700 23029 11701 23029 11698 23030 11701 23030 11697 23030 9552 23031 11713 23031 11702 23031 11702 23032 11713 23032 11401 23032 11702 23033 11401 23033 9550 23033 9550 23034 11401 23034 11705 23034 11706 23035 9549 23035 11400 23035 11400 23036 9549 23036 11703 23036 11400 23037 11703 23037 11401 23037 11401 23038 11703 23038 11704 23038 11401 23039 11704 23039 11705 23039 11706 23040 11400 23040 11707 23040 11707 23041 11400 23041 11709 23041 11707 23042 11709 23042 11710 23042 11691 23043 9548 23043 11708 23043 11691 23044 11708 23044 11709 23044 11709 23045 11708 23045 9546 23045 11709 23046 9546 23046 11710 23046 11722 23047 11723 23047 9551 23047 9551 23048 11723 23048 11711 23048 11711 23049 11723 23049 11712 23049 11712 23050 11723 23050 11713 23050 11712 23051 11713 23051 9552 23051 11714 23052 11715 23052 11718 23052 11718 23053 11715 23053 11716 23053 11718 23054 11716 23054 11717 23054 11717 23055 11716 23055 9559 23055 11717 23056 9559 23056 9558 23056 11381 23057 11719 23057 11718 23057 11718 23058 11719 23058 11720 23058 11718 23059 11720 23059 11714 23059 11725 23060 9553 23060 11403 23060 11403 23061 9553 23061 11721 23061 11403 23062 11721 23062 11381 23062 11381 23063 11721 23063 9554 23063 11381 23064 9554 23064 11719 23064 11723 23065 11722 23065 11724 23065 11723 23066 11724 23066 11403 23066 11403 23067 11724 23067 9556 23067 11403 23068 9556 23068 11725 23068 9538 23069 11397 23069 11726 23069 11726 23070 11397 23070 11396 23070 11726 23071 11396 23071 9562 23071 9562 23072 11396 23072 11727 23072 11727 23073 11396 23073 11728 23073 11728 23074 11396 23074 11395 23074 11728 23075 11395 23075 11731 23075 9557 23076 11368 23076 11729 23076 11729 23077 11368 23077 11717 23077 11729 23078 11717 23078 9558 23078 9557 23079 9561 23079 11368 23079 11368 23080 9561 23080 9560 23080 11368 23081 9560 23081 11395 23081 11395 23082 9560 23082 11730 23082 11395 23083 11730 23083 11731 23083 9579 23084 11741 23084 11732 23084 9579 23085 11732 23085 11733 23085 11733 23086 11732 23086 11372 23086 11733 23087 11372 23087 11734 23087 11734 23088 11372 23088 11735 23088 11734 23089 11735 23089 9575 23089 9575 23090 11735 23090 11736 23090 11736 23091 11735 23091 11737 23091 11736 23092 11737 23092 9572 23092 11375 23093 11738 23093 11737 23093 11737 23094 11738 23094 9573 23094 11737 23095 9573 23095 9572 23095 11747 23096 11739 23096 9576 23096 9576 23097 11739 23097 11740 23097 11740 23098 11739 23098 9577 23098 9577 23099 11739 23099 11732 23099 9577 23100 11732 23100 11741 23100 11756 23101 11742 23101 9585 23101 9585 23102 11742 23102 11399 23102 9585 23103 11399 23103 11743 23103 11743 23104 11399 23104 11744 23104 11744 23105 11399 23105 11366 23105 11744 23106 11366 23106 11745 23106 11745 23107 11366 23107 9583 23107 9583 23108 11366 23108 11746 23108 9583 23109 11746 23109 9580 23109 11739 23110 11747 23110 11746 23110 11746 23111 11747 23111 9581 23111 11746 23112 9581 23112 9580 23112 11749 23113 11748 23113 11759 23113 11749 23114 11759 23114 11750 23114 11750 23115 11759 23115 11751 23115 11750 23116 11751 23116 11752 23116 11752 23117 11751 23117 11753 23117 11752 23118 11753 23118 9588 23118 9588 23119 11753 23119 11754 23119 11754 23120 11753 23120 11755 23120 11754 23121 11755 23121 9589 23121 11742 23122 11756 23122 11755 23122 11755 23123 11756 23123 9587 23123 11755 23124 9587 23124 9589 23124 9568 23125 11757 23125 9563 23125 9563 23126 11757 23126 9564 23126 9564 23127 11757 23127 11758 23127 11758 23128 11757 23128 11759 23128 11758 23129 11759 23129 11748 23129 11738 23130 11375 23130 11760 23130 11760 23131 11375 23131 11762 23131 11760 23132 11762 23132 11761 23132 11761 23133 11762 23133 11763 23133 11763 23134 11762 23134 11378 23134 11763 23135 11378 23135 9570 23135 9570 23136 11378 23136 11764 23136 11764 23137 11378 23137 11765 23137 11764 23138 11765 23138 9566 23138 11757 23139 9568 23139 11765 23139 11765 23140 9568 23140 9567 23140 11765 23141 9567 23141 9566 23141 11766 23142 11767 23142 11768 23142 11768 23143 11767 23143 11769 23143 11768 23144 11769 23144 9608 23144 9608 23145 11769 23145 11770 23145 11770 23146 11769 23146 11390 23146 11770 23147 11390 23147 11771 23147 11771 23148 11390 23148 11772 23148 11772 23149 11390 23149 11773 23149 11772 23150 11773 23150 9605 23150 11392 23151 11802 23151 11773 23151 11773 23152 11802 23152 9606 23152 11773 23153 9606 23153 9605 23153 9592 23154 11782 23154 11775 23154 9592 23155 11775 23155 11774 23155 11774 23156 11775 23156 11384 23156 11774 23157 11384 23157 11776 23157 11776 23158 11384 23158 11386 23158 11776 23159 11386 23159 11777 23159 11777 23160 11386 23160 9611 23160 9611 23161 11386 23161 11778 23161 9611 23162 11778 23162 9609 23162 11767 23163 11766 23163 11778 23163 11778 23164 11766 23164 11779 23164 11778 23165 11779 23165 9609 23165 11790 23166 11383 23166 9590 23166 9590 23167 11383 23167 11780 23167 11780 23168 11383 23168 11781 23168 11781 23169 11383 23169 11775 23169 11781 23170 11775 23170 11782 23170 9598 23171 11380 23171 11783 23171 11783 23172 11380 23172 11379 23172 11783 23173 11379 23173 11784 23173 11784 23174 11379 23174 9595 23174 9595 23175 11379 23175 11785 23175 9595 23176 11785 23176 11786 23176 11786 23177 11785 23177 11787 23177 11787 23178 11785 23178 11788 23178 11787 23179 11788 23179 11789 23179 11383 23180 11790 23180 11788 23180 11788 23181 11790 23181 11791 23181 11788 23182 11791 23182 11789 23182 11792 23183 9604 23183 11793 23183 11792 23184 11793 23184 11794 23184 11794 23185 11793 23185 11394 23185 11794 23186 11394 23186 9601 23186 9601 23187 11394 23187 11795 23187 9601 23188 11795 23188 9599 23188 9599 23189 11795 23189 11796 23189 11796 23190 11795 23190 11798 23190 11796 23191 11798 23191 11799 23191 11380 23192 9598 23192 11798 23192 11798 23193 9598 23193 11797 23193 11798 23194 11797 23194 11799 23194 9604 23195 11800 23195 11793 23195 11793 23196 11800 23196 11801 23196 11793 23197 11801 23197 11392 23197 11392 23198 11801 23198 9602 23198 11392 23199 9602 23199 11802 23199 11803 23200 11882 23200 9406 23200 9406 23201 11882 23201 11863 23201 9406 23202 11863 23202 9408 23202 9408 23203 11863 23203 11866 23203 11803 23204 9405 23204 11882 23204 11882 23205 9405 23205 11804 23205 11882 23206 11804 23206 12145 23206 12145 23207 11804 23207 9418 23207 9418 23208 9417 23208 12145 23208 12145 23209 9417 23209 9416 23209 12145 23210 9416 23210 12156 23210 12156 23211 9416 23211 9415 23211 9415 23212 9412 23212 12156 23212 12156 23213 9412 23213 9410 23213 12156 23214 9410 23214 11866 23214 11866 23215 9410 23215 9409 23215 11866 23216 9409 23216 9408 23216 9430 23217 9427 23217 11805 23217 11805 23218 9427 23218 9426 23218 11805 23219 9426 23219 11809 23219 9430 23220 11805 23220 9431 23220 9431 23221 11805 23221 11811 23221 9431 23222 11811 23222 9432 23222 9421 23223 11810 23223 11806 23223 11806 23224 11810 23224 11807 23224 11806 23225 11807 23225 9422 23225 9422 23226 11807 23226 11809 23226 9422 23227 11809 23227 11808 23227 11808 23228 11809 23228 9426 23228 9421 23229 9420 23229 11810 23229 11810 23230 9420 23230 11812 23230 11810 23231 11812 23231 11811 23231 11811 23232 11812 23232 11813 23232 11811 23233 11813 23233 9432 23233 11829 23234 11830 23234 11818 23234 11814 23235 11828 23235 11815 23235 11814 23236 11815 23236 11817 23236 12166 23237 12165 23237 11815 23237 11815 23238 12165 23238 11816 23238 11815 23239 11816 23239 11817 23239 11829 23240 11818 23240 11828 23240 11827 23241 11819 23241 11822 23241 11822 23242 11819 23242 11820 23242 11822 23243 11820 23243 11889 23243 11828 23244 11818 23244 11815 23244 11815 23245 11818 23245 11821 23245 11815 23246 11821 23246 12168 23246 12168 23247 11821 23247 11822 23247 12168 23248 11822 23248 12167 23248 12167 23249 11822 23249 11889 23249 12167 23250 11889 23250 11823 23250 11826 23251 11825 23251 11891 23251 11891 23252 11825 23252 11890 23252 11830 23253 11831 23253 11480 23253 11480 23254 11831 23254 11832 23254 11480 23255 11832 23255 11463 23255 11830 23256 11480 23256 11818 23256 11818 23257 11480 23257 11824 23257 11818 23258 11824 23258 11821 23258 11821 23259 11824 23259 11825 23259 11821 23260 11825 23260 11822 23260 11822 23261 11825 23261 11826 23261 11822 23262 11826 23262 11827 23262 12186 23263 12185 23263 11841 23263 12186 23264 11841 23264 11814 23264 11814 23265 11841 23265 11828 23265 11828 23266 11841 23266 11862 23266 11828 23267 11862 23267 11829 23267 11862 23268 11861 23268 11829 23268 11829 23269 11861 23269 11835 23269 11829 23270 11835 23270 11830 23270 11830 23271 11835 23271 11831 23271 11835 23272 11854 23272 11831 23272 11831 23273 11854 23273 11833 23273 11831 23274 11833 23274 11832 23274 11832 23275 11833 23275 11838 23275 11832 23276 11838 23276 11463 23276 11841 23277 12185 23277 12164 23277 11451 23278 11461 23278 11836 23278 11839 23279 11867 23279 11868 23279 11843 23280 11867 23280 11844 23280 11844 23281 11867 23281 11839 23281 11844 23282 11839 23282 11847 23282 11851 23283 11852 23283 11834 23283 11834 23284 11852 23284 11860 23284 11860 23285 11852 23285 11861 23285 11861 23286 11852 23286 11855 23286 11861 23287 11855 23287 11835 23287 11836 23288 11461 23288 11850 23288 11850 23289 11837 23289 11853 23289 11853 23290 11837 23290 11833 23290 11853 23291 11833 23291 11854 23291 11461 23292 11462 23292 11850 23292 11850 23293 11462 23293 11468 23293 11850 23294 11468 23294 11837 23294 11837 23295 11468 23295 11838 23295 11837 23296 11838 23296 11833 23296 11455 23297 11453 23297 11856 23297 11858 23298 11847 23298 11840 23298 11840 23299 11847 23299 11839 23299 11840 23300 11839 23300 11856 23300 11856 23301 11839 23301 11868 23301 11856 23302 11868 23302 11455 23302 11841 23303 12164 23303 11849 23303 11849 23304 12164 23304 12163 23304 11849 23305 12163 23305 11842 23305 11842 23306 12163 23306 12161 23306 11842 23307 12161 23307 12160 23307 11866 23308 11843 23308 11845 23308 11845 23309 11843 23309 11844 23309 11845 23310 11844 23310 11846 23310 11846 23311 11844 23311 11847 23311 11846 23312 11847 23312 12159 23312 12159 23313 11847 23313 11858 23313 12159 23314 11858 23314 12160 23314 12160 23315 11858 23315 11848 23315 12160 23316 11848 23316 11842 23316 11842 23317 11848 23317 11859 23317 11842 23318 11859 23318 11849 23318 11849 23319 11859 23319 11862 23319 11849 23320 11862 23320 11841 23320 11452 23321 11451 23321 11857 23321 11857 23322 11451 23322 11836 23322 11857 23323 11836 23323 11851 23323 11851 23324 11836 23324 11850 23324 11851 23325 11850 23325 11852 23325 11852 23326 11850 23326 11853 23326 11852 23327 11853 23327 11855 23327 11855 23328 11853 23328 11854 23328 11855 23329 11854 23329 11835 23329 11453 23330 11452 23330 11856 23330 11856 23331 11452 23331 11857 23331 11856 23332 11857 23332 11840 23332 11840 23333 11857 23333 11851 23333 11840 23334 11851 23334 11858 23334 11858 23335 11851 23335 11834 23335 11858 23336 11834 23336 11848 23336 11848 23337 11834 23337 11860 23337 11848 23338 11860 23338 11859 23338 11859 23339 11860 23339 11861 23339 11859 23340 11861 23340 11862 23340 11865 23341 11863 23341 11882 23341 11869 23342 11864 23342 11456 23342 11455 23343 11868 23343 11456 23343 11456 23344 11868 23344 11865 23344 11456 23345 11865 23345 11869 23345 11869 23346 11865 23346 11882 23346 11866 23347 11863 23347 11843 23347 11843 23348 11863 23348 11865 23348 11843 23349 11865 23349 11867 23349 11867 23350 11865 23350 11868 23350 11881 23351 11864 23351 11869 23351 11875 23352 11458 23352 11457 23352 12151 23353 12150 23353 11885 23353 11878 23354 11877 23354 11895 23354 11878 23355 11895 23355 11879 23355 11870 23356 11871 23356 12149 23356 12150 23357 12149 23357 11885 23357 11885 23358 12149 23358 11871 23358 11885 23359 11871 23359 11872 23359 11872 23360 11871 23360 11870 23360 11872 23361 11870 23361 11886 23361 11886 23362 11870 23362 11879 23362 11886 23363 11879 23363 11888 23363 11888 23364 11879 23364 11895 23364 11896 23365 11464 23365 11873 23365 11896 23366 11873 23366 11887 23366 11887 23367 11873 23367 11874 23367 11887 23368 11874 23368 11875 23368 11875 23369 11874 23369 11459 23369 11875 23370 11459 23370 11458 23370 12153 23371 11877 23371 11876 23371 11876 23372 11877 23372 11878 23372 11876 23373 11878 23373 12154 23373 12154 23374 11878 23374 11879 23374 12154 23375 11879 23375 11880 23375 11880 23376 11879 23376 11870 23376 11880 23377 11870 23377 12148 23377 12148 23378 11870 23378 12149 23378 11457 23379 11881 23379 11884 23379 11884 23380 11881 23380 11869 23380 11884 23381 11869 23381 11883 23381 11883 23382 11869 23382 11882 23382 11883 23383 12151 23383 11884 23383 11884 23384 12151 23384 11885 23384 11884 23385 11885 23385 11457 23385 11457 23386 11885 23386 11872 23386 11457 23387 11872 23387 11875 23387 11875 23388 11872 23388 11886 23388 11875 23389 11886 23389 11887 23389 11887 23390 11886 23390 11888 23390 11887 23391 11888 23391 11896 23391 11896 23392 11888 23392 11895 23392 11890 23393 11898 23393 11897 23393 11893 23394 11894 23394 11889 23394 11890 23395 11897 23395 11891 23395 11891 23396 11897 23396 11892 23396 11891 23397 11892 23397 11826 23397 11889 23398 11820 23398 11893 23398 11893 23399 11820 23399 11819 23399 11893 23400 11819 23400 11892 23400 11892 23401 11819 23401 11827 23401 11892 23402 11827 23402 11826 23402 12153 23403 11894 23403 11877 23403 11877 23404 11894 23404 11893 23404 11877 23405 11893 23405 11895 23405 11895 23406 11893 23406 11892 23406 11895 23407 11892 23407 11896 23407 11896 23408 11892 23408 11897 23408 11896 23409 11897 23409 11464 23409 11464 23410 11897 23410 11898 23410 12193 23411 11901 23411 12415 23411 11908 23412 12402 23412 12195 23412 12195 23413 12402 23413 12404 23413 12195 23414 12404 23414 11899 23414 11899 23415 12406 23415 12195 23415 12195 23416 12406 23416 11900 23416 12195 23417 11900 23417 12193 23417 12193 23418 11900 23418 12417 23418 12193 23419 12417 23419 11901 23419 12415 23420 11902 23420 12193 23420 12193 23421 11902 23421 11903 23421 12193 23422 11903 23422 9612 23422 11904 23423 11905 23423 11907 23423 11907 23424 11905 23424 11906 23424 11907 23425 11906 23425 12372 23425 11908 23426 12195 23426 11909 23426 11909 23427 12195 23427 12188 23427 11909 23428 12188 23428 11910 23428 11910 23429 12188 23429 11911 23429 11911 23430 12188 23430 11913 23430 11911 23431 11913 23431 11915 23431 12394 23432 12389 23432 11917 23432 11917 23433 12389 23433 11912 23433 11917 23434 11912 23434 11913 23434 11913 23435 11912 23435 11914 23435 11913 23436 11914 23436 11915 23436 11904 23437 12392 23437 11905 23437 11905 23438 12392 23438 11916 23438 11905 23439 11916 23439 11917 23439 11917 23440 11916 23440 11918 23440 11917 23441 11918 23441 12394 23441 12371 23442 12372 23442 11906 23442 12371 23443 11906 23443 11919 23443 12367 23444 12366 23444 11906 23444 11906 23445 12366 23445 12364 23445 11906 23446 12364 23446 11919 23446 12358 23447 12360 23447 12021 23447 12021 23448 12360 23448 11920 23448 12021 23449 11920 23449 11921 23449 11921 23450 12362 23450 12021 23450 12021 23451 12362 23451 12365 23451 12021 23452 12365 23452 11906 23452 11906 23453 12365 23453 12368 23453 11906 23454 12368 23454 12367 23454 11922 23455 11923 23455 11924 23455 11924 23456 11923 23456 11925 23456 11924 23457 11925 23457 11989 23457 11517 23458 11999 23458 11518 23458 11518 23459 11999 23459 11937 23459 11937 23460 11999 23460 11926 23460 11926 23461 11999 23461 11928 23461 11926 23462 11928 23462 11927 23462 11928 23463 11929 23463 11927 23463 11927 23464 11929 23464 12012 23464 11927 23465 12012 23465 11923 23465 11923 23466 12012 23466 11991 23466 11923 23467 11991 23467 11925 23467 12229 23468 11943 23468 11930 23468 11930 23469 11943 23469 11945 23469 11930 23470 11945 23470 11941 23470 12229 23471 11930 23471 11931 23471 11931 23472 11930 23472 11939 23472 11931 23473 11939 23473 12184 23473 12184 23474 11939 23474 11932 23474 12184 23475 11932 23475 11933 23475 12228 23476 11934 23476 11936 23476 11936 23477 11934 23477 11935 23477 11936 23478 11935 23478 12182 23478 11937 23479 11926 23479 11932 23479 11932 23480 11926 23480 11927 23480 11932 23481 11927 23481 11933 23481 11933 23482 11927 23482 11923 23482 11933 23483 11923 23483 11936 23483 11936 23484 11923 23484 11922 23484 11936 23485 11922 23485 12228 23485 11938 23486 11518 23486 11937 23486 11514 23487 11942 23487 11948 23487 11948 23488 11942 23488 11946 23488 11937 23489 11932 23489 11938 23489 11938 23490 11932 23490 11939 23490 11938 23491 11939 23491 11940 23491 11940 23492 11939 23492 11930 23492 11940 23493 11930 23493 11942 23493 11942 23494 11930 23494 11941 23494 11942 23495 11941 23495 11946 23495 11953 23496 11954 23496 11965 23496 11965 23497 11954 23497 12230 23497 11943 23498 11944 23498 11945 23498 11945 23499 11944 23499 11952 23499 11945 23500 11952 23500 11941 23500 11941 23501 11952 23501 11947 23501 11941 23502 11947 23502 11946 23502 11946 23503 11947 23503 11948 23503 11948 23504 11947 23504 11950 23504 11948 23505 11950 23505 11514 23505 11949 23506 11950 23506 11957 23506 11957 23507 11950 23507 11947 23507 11957 23508 11947 23508 11951 23508 11951 23509 11947 23509 11952 23509 11951 23510 11952 23510 11953 23510 11953 23511 11952 23511 11944 23511 11953 23512 11944 23512 11954 23512 11954 23513 11944 23513 11943 23513 11976 23514 11955 23514 11984 23514 11956 23515 11979 23515 11949 23515 11957 23516 11951 23516 11958 23516 11958 23517 11951 23517 11953 23517 11972 23518 11968 23518 11959 23518 11963 23519 11964 23519 11960 23519 11960 23520 11964 23520 11961 23520 11960 23521 11961 23521 11976 23521 11976 23522 11961 23522 12179 23522 11976 23523 12179 23523 11955 23523 11955 23524 12179 23524 11809 23524 11979 23525 11956 23525 11962 23525 11962 23526 11956 23526 11972 23526 11962 23527 11972 23527 11963 23527 11963 23528 11972 23528 11959 23528 11963 23529 11959 23529 11964 23529 12230 23530 11966 23530 11965 23530 11965 23531 11966 23531 11974 23531 11965 23532 11974 23532 11953 23532 11953 23533 11974 23533 11971 23533 11953 23534 11971 23534 11958 23534 11973 23535 11967 23535 11968 23535 11968 23536 11967 23536 11969 23536 11968 23537 11969 23537 11959 23537 11959 23538 11969 23538 11970 23538 11959 23539 11970 23539 11964 23539 11949 23540 11957 23540 11956 23540 11956 23541 11957 23541 11958 23541 11956 23542 11958 23542 11972 23542 11972 23543 11958 23543 11971 23543 11972 23544 11971 23544 11968 23544 11968 23545 11971 23545 11974 23545 11968 23546 11974 23546 11973 23546 11973 23547 11974 23547 11966 23547 11984 23548 11975 23548 11976 23548 11976 23549 11975 23549 11504 23549 11976 23550 11504 23550 11960 23550 11960 23551 11504 23551 11977 23551 11960 23552 11977 23552 11963 23552 11963 23553 11977 23553 11978 23553 11963 23554 11978 23554 11962 23554 11962 23555 11978 23555 11503 23555 11962 23556 11503 23556 11979 23556 12011 23557 11506 23557 11980 23557 11980 23558 11506 23558 11983 23558 11807 23559 11810 23559 11983 23559 11983 23560 11810 23560 11981 23560 11981 23561 11982 23561 11983 23561 11983 23562 11982 23562 12005 23562 11983 23563 12005 23563 11980 23563 11809 23564 11807 23564 11955 23564 11955 23565 11807 23565 11983 23565 11955 23566 11983 23566 11984 23566 11984 23567 11983 23567 11506 23567 12013 23568 11929 23568 11928 23568 11985 23569 11516 23569 12015 23569 11986 23570 11485 23570 12016 23570 12016 23571 11485 23571 11987 23571 11988 23572 12005 23572 11982 23572 12003 23573 12169 23573 11989 23573 11929 23574 12013 23574 12012 23574 11925 23575 11991 23575 11990 23575 11990 23576 11991 23576 11992 23576 11990 23577 11992 23577 11993 23577 11993 23578 11992 23578 11994 23578 11993 23579 11994 23579 11996 23579 11989 23580 11925 23580 12003 23580 12003 23581 11925 23581 11990 23581 12003 23582 11990 23582 11995 23582 11995 23583 11990 23583 11993 23583 11995 23584 11993 23584 12002 23584 12002 23585 11993 23585 11996 23585 12007 23586 12000 23586 11997 23586 11997 23587 12000 23587 12175 23587 11997 23588 12175 23588 11998 23588 11517 23589 11985 23589 11999 23589 11999 23590 11985 23590 12015 23590 11999 23591 12015 23591 11928 23591 11928 23592 12015 23592 12014 23592 11928 23593 12014 23593 12013 23593 11810 23594 12175 23594 11981 23594 11981 23595 12175 23595 12000 23595 11981 23596 12000 23596 11982 23596 11982 23597 12000 23597 12007 23597 11982 23598 12007 23598 11988 23598 11988 23599 12007 23599 12001 23599 12173 23600 12172 23600 12002 23600 12002 23601 12172 23601 12171 23601 12002 23602 12171 23602 11995 23602 11995 23603 12171 23603 12170 23603 11995 23604 12170 23604 12003 23604 12003 23605 12170 23605 12004 23605 12003 23606 12004 23606 12169 23606 11980 23607 12005 23607 12006 23607 12006 23608 12005 23608 11988 23608 12006 23609 11988 23609 12010 23609 12010 23610 11988 23610 12001 23610 12010 23611 12001 23611 12009 23611 12009 23612 12001 23612 12007 23612 12009 23613 12007 23613 12008 23613 12008 23614 12007 23614 11997 23614 11998 23615 12173 23615 11997 23615 11997 23616 12173 23616 12002 23616 11997 23617 12002 23617 12008 23617 12008 23618 12002 23618 11996 23618 12008 23619 11996 23619 12009 23619 12009 23620 11996 23620 12016 23620 12009 23621 12016 23621 12010 23621 12010 23622 12016 23622 11987 23622 12010 23623 11987 23623 12006 23623 12006 23624 11987 23624 11507 23624 12006 23625 11507 23625 11980 23625 11980 23626 11507 23626 12011 23626 11991 23627 12012 23627 11992 23627 11992 23628 12012 23628 12013 23628 11992 23629 12013 23629 11994 23629 11994 23630 12013 23630 12014 23630 11994 23631 12014 23631 11996 23631 11996 23632 12014 23632 12015 23632 11996 23633 12015 23633 12016 23633 12016 23634 12015 23634 11516 23634 12016 23635 11516 23635 11986 23635 12023 23636 12017 23636 12019 23636 12383 23637 12358 23637 12021 23637 12018 23638 12395 23638 12035 23638 12035 23639 12395 23639 12025 23639 12019 23640 12017 23640 12020 23640 12020 23641 12017 23641 12379 23641 12020 23642 12379 23642 12378 23642 12378 23643 12377 23643 12020 23643 12020 23644 12377 23644 12380 23644 12020 23645 12380 23645 12021 23645 12021 23646 12380 23646 12381 23646 12021 23647 12381 23647 12383 23647 12027 23648 12374 23648 12019 23648 12019 23649 12374 23649 12022 23649 12019 23650 12022 23650 12023 23650 12395 23651 12024 23651 12025 23651 12025 23652 12024 23652 12026 23652 12025 23653 12026 23653 12027 23653 12027 23654 12026 23654 12028 23654 12027 23655 12028 23655 12374 23655 12408 23656 12410 23656 12204 23656 12035 23657 12029 23657 12034 23657 12030 23658 12419 23658 12204 23658 12204 23659 12419 23659 12031 23659 12204 23660 12031 23660 12408 23660 12410 23661 12411 23661 12204 23661 12204 23662 12411 23662 12032 23662 12204 23663 12032 23663 12035 23663 12035 23664 12032 23664 12033 23664 12035 23665 12033 23665 12029 23665 12034 23666 12399 23666 12035 23666 12035 23667 12399 23667 12036 23667 12035 23668 12036 23668 12018 23668 12037 23669 12038 23669 9628 23669 9628 23670 12038 23670 12039 23670 9628 23671 12039 23671 12040 23671 12040 23672 12039 23672 12041 23672 12040 23673 12041 23673 12042 23673 12042 23674 12041 23674 9451 23674 12042 23675 9451 23675 12043 23675 12043 23676 9451 23676 12044 23676 12043 23677 12044 23677 9630 23677 9630 23678 12044 23678 12045 23678 9630 23679 12045 23679 9633 23679 9633 23680 12045 23680 9453 23680 9633 23681 9453 23681 9634 23681 9634 23682 9453 23682 12046 23682 9634 23683 12046 23683 12047 23683 12047 23684 12046 23684 12048 23684 12047 23685 12048 23685 9635 23685 9635 23686 12048 23686 12049 23686 9635 23687 12049 23687 9637 23687 9637 23688 12049 23688 12050 23688 9637 23689 12050 23689 9639 23689 9639 23690 12050 23690 9449 23690 9639 23691 9449 23691 12037 23691 12037 23692 9449 23692 12038 23692 13377 23693 13376 23693 12056 23693 12056 23694 13376 23694 13375 23694 12056 23695 13375 23695 12051 23695 12051 23696 9787 23696 12056 23696 12056 23697 9787 23697 12052 23697 12056 23698 12052 23698 12059 23698 12059 23699 12052 23699 12070 23699 12059 23700 12070 23700 12053 23700 12053 23701 12070 23701 12068 23701 12053 23702 12068 23702 12054 23702 12054 23703 12068 23703 12055 23703 13378 23704 13377 23704 11604 23704 11604 23705 13377 23705 12056 23705 11604 23706 12056 23706 12057 23706 12057 23707 12056 23707 12059 23707 12057 23708 12059 23708 12058 23708 12058 23709 12059 23709 12053 23709 12058 23710 12053 23710 11220 23710 11220 23711 12053 23711 12054 23711 9034 23712 9038 23712 12060 23712 9037 23713 12061 23713 12063 23713 12063 23714 12061 23714 12062 23714 12063 23715 12062 23715 9980 23715 12052 23716 9787 23716 9777 23716 11246 23717 12065 23717 13192 23717 13192 23718 12065 23718 12067 23718 13192 23719 12067 23719 13194 23719 13194 23720 12067 23720 12063 23720 13194 23721 12063 23721 12064 23721 12064 23722 12063 23722 9980 23722 12064 23723 9980 23723 13190 23723 11246 23724 11245 23724 12065 23724 12065 23725 11245 23725 12066 23725 12065 23726 12066 23726 12067 23726 12067 23727 12066 23727 12069 23727 12067 23728 12069 23728 12063 23728 12063 23729 12069 23729 12060 23729 12063 23730 12060 23730 9037 23730 9037 23731 12060 23731 9038 23731 11245 23732 12055 23732 12066 23732 12066 23733 12055 23733 12068 23733 12066 23734 12068 23734 12069 23734 12069 23735 12068 23735 12070 23735 12069 23736 12070 23736 12060 23736 12060 23737 12070 23737 12052 23737 12060 23738 12052 23738 9034 23738 9034 23739 12052 23739 9777 23739 9034 23740 9777 23740 9035 23740 13188 23741 12071 23741 12077 23741 12077 23742 12071 23742 12072 23742 12077 23743 12072 23743 12073 23743 11628 23744 12074 23744 12077 23744 12077 23745 12074 23745 13191 23745 12077 23746 13191 23746 13193 23746 13193 23747 12075 23747 12077 23747 12077 23748 12075 23748 12076 23748 12077 23749 12076 23749 13188 23749 9090 23750 9088 23750 12104 23750 12104 23751 9088 23751 12078 23751 12104 23752 12078 23752 12079 23752 13290 23753 12073 23753 13289 23753 13337 23754 12104 23754 12079 23754 13337 23755 12079 23755 13316 23755 13316 23756 12079 23756 12101 23756 11632 23757 12081 23757 12080 23757 12080 23758 12081 23758 9107 23758 12080 23759 9107 23759 11631 23759 11631 23760 9107 23760 9106 23760 12085 23761 13294 23761 12082 23761 12082 23762 13294 23762 12083 23762 12082 23763 12083 23763 12084 23763 13290 23764 13294 23764 12073 23764 12073 23765 13294 23765 12085 23765 12073 23766 12085 23766 12077 23766 12077 23767 12085 23767 9093 23767 12077 23768 9093 23768 12086 23768 12086 23769 9093 23769 12087 23769 12086 23770 12087 23770 12093 23770 12093 23771 12087 23771 12088 23771 12088 23772 12087 23772 12089 23772 12089 23773 12087 23773 9090 23773 12089 23774 9090 23774 12090 23774 12090 23775 9090 23775 12104 23775 12090 23776 12104 23776 9104 23776 9104 23777 12104 23777 12091 23777 9104 23778 12091 23778 9106 23778 9106 23779 12091 23779 11629 23779 9106 23780 11629 23780 11631 23780 12088 23781 12092 23781 12093 23781 12093 23782 12092 23782 9111 23782 12093 23783 9111 23783 11627 23783 11627 23784 9111 23784 9110 23784 11627 23785 9110 23785 12094 23785 12094 23786 9110 23786 9109 23786 12094 23787 9109 23787 11632 23787 11632 23788 9109 23788 12095 23788 11632 23789 12095 23789 12081 23789 12083 23790 12096 23790 12084 23790 12084 23791 12096 23791 12097 23791 12084 23792 12097 23792 9085 23792 9085 23793 12097 23793 13322 23793 9085 23794 13322 23794 12098 23794 12098 23795 13322 23795 13320 23795 12098 23796 13320 23796 12099 23796 12099 23797 13320 23797 13319 23797 12099 23798 13319 23798 12079 23798 12079 23799 13319 23799 12100 23799 12079 23800 12100 23800 12101 23800 12102 23801 11630 23801 12091 23801 13212 23802 12102 23802 12105 23802 12105 23803 12102 23803 12103 23803 12103 23804 12102 23804 12091 23804 12103 23805 12091 23805 12104 23805 13212 23806 12105 23806 13210 23806 13210 23807 12105 23807 13209 23807 13210 23808 13209 23808 12106 23808 13416 23809 12107 23809 12121 23809 12108 23810 12109 23810 12127 23810 12127 23811 12109 23811 12110 23811 12127 23812 12110 23812 9804 23812 13416 23813 12121 23813 13425 23813 12111 23814 13215 23814 9809 23814 12117 23815 13213 23815 12116 23815 12116 23816 13213 23816 13211 23816 12116 23817 13211 23817 12112 23817 12112 23818 13211 23818 12111 23818 12112 23819 12111 23819 12114 23819 12114 23820 12111 23820 9809 23820 12114 23821 9809 23821 12113 23821 12113 23822 13425 23822 12114 23822 12114 23823 13425 23823 12121 23823 12114 23824 12121 23824 12112 23824 12112 23825 12121 23825 12115 23825 12112 23826 12115 23826 12116 23826 12116 23827 12115 23827 12119 23827 12116 23828 12119 23828 12117 23828 12117 23829 12119 23829 11244 23829 12125 23830 11244 23830 12118 23830 12118 23831 11244 23831 12119 23831 12118 23832 12119 23832 12120 23832 12120 23833 12119 23833 12115 23833 12120 23834 12115 23834 12127 23834 12127 23835 12115 23835 12121 23835 12127 23836 12121 23836 12108 23836 12108 23837 12121 23837 12107 23837 12123 23838 9944 23838 9959 23838 12126 23839 9805 23839 12122 23839 12123 23840 9959 23840 9014 23840 12129 23841 12125 23841 12124 23841 12124 23842 12125 23842 12118 23842 12124 23843 12118 23843 12130 23843 12130 23844 12118 23844 12120 23844 12130 23845 12120 23845 12126 23845 12126 23846 12120 23846 12127 23846 12126 23847 12127 23847 9805 23847 9805 23848 12127 23848 9804 23848 11270 23849 12129 23849 12128 23849 12128 23850 12129 23850 12124 23850 12128 23851 12124 23851 12131 23851 12131 23852 12124 23852 12130 23852 12131 23853 12130 23853 9959 23853 9959 23854 12130 23854 12126 23854 9959 23855 12126 23855 9014 23855 9014 23856 12126 23856 12122 23856 12144 23857 9481 23857 9654 23857 9654 23858 9481 23858 12132 23858 9654 23859 12132 23859 9656 23859 9656 23860 12132 23860 12133 23860 9656 23861 12133 23861 12134 23861 12134 23862 12133 23862 12135 23862 12134 23863 12135 23863 12136 23863 12136 23864 12135 23864 12137 23864 12136 23865 12137 23865 9658 23865 9658 23866 12137 23866 9484 23866 9658 23867 9484 23867 12138 23867 12138 23868 9484 23868 9485 23868 12138 23869 9485 23869 9659 23869 9659 23870 9485 23870 9486 23870 9659 23871 9486 23871 9660 23871 9660 23872 9486 23872 9488 23872 9660 23873 9488 23873 12139 23873 12139 23874 9488 23874 12140 23874 12139 23875 12140 23875 9663 23875 9663 23876 12140 23876 12142 23876 9663 23877 12142 23877 12141 23877 12141 23878 12142 23878 12143 23878 12141 23879 12143 23879 12144 23879 12144 23880 12143 23880 9481 23880 11882 23881 12145 23881 11883 23881 11883 23882 12145 23882 12147 23882 12146 23883 12148 23883 12147 23883 12147 23884 12148 23884 12149 23884 12149 23885 12150 23885 12147 23885 12147 23886 12150 23886 12151 23886 12147 23887 12151 23887 11883 23887 12155 23888 12152 23888 12153 23888 12153 23889 11876 23889 12155 23889 12155 23890 11876 23890 12154 23890 12155 23891 12154 23891 12146 23891 12146 23892 12154 23892 11880 23892 12146 23893 11880 23893 12148 23893 12156 23894 11866 23894 11845 23894 12156 23895 11845 23895 12157 23895 11845 23896 11846 23896 12157 23896 12157 23897 11846 23897 12159 23897 12157 23898 12159 23898 12158 23898 12159 23899 12160 23899 12158 23899 12158 23900 12160 23900 12161 23900 12158 23901 12161 23901 12162 23901 12162 23902 12161 23902 12163 23902 12162 23903 12163 23903 12164 23903 12185 23904 11816 23904 12165 23904 12185 23905 12165 23905 12164 23905 12164 23906 12165 23906 12166 23906 12164 23907 12166 23907 12162 23907 12155 23908 12146 23908 12147 23908 12162 23909 12166 23909 11815 23909 12167 23910 11823 23910 12152 23910 12152 23911 12155 23911 12167 23911 12167 23912 12155 23912 12147 23912 12167 23913 12147 23913 12168 23913 12168 23914 12147 23914 12145 23914 12168 23915 12145 23915 11815 23915 12158 23916 12162 23916 12157 23916 12157 23917 12162 23917 11815 23917 12157 23918 11815 23918 12156 23918 12156 23919 11815 23919 12145 23919 12170 23920 12174 23920 12004 23920 12004 23921 12174 23921 12183 23921 12004 23922 12183 23922 12169 23922 12169 23923 12183 23923 12182 23923 12169 23924 12182 23924 11989 23924 11989 23925 12182 23925 11935 23925 11989 23926 11935 23926 11934 23926 12170 23927 12171 23927 12174 23927 12174 23928 12171 23928 12172 23928 12174 23929 12172 23929 12173 23929 12173 23930 11998 23930 12174 23930 12174 23931 11998 23931 12175 23931 12174 23932 12175 23932 12176 23932 12176 23933 12175 23933 11810 23933 12176 23934 11810 23934 11811 23934 12178 23935 11970 23935 11969 23935 12230 23936 12181 23936 11966 23936 11966 23937 12181 23937 12177 23937 11966 23938 12177 23938 11973 23938 11973 23939 12177 23939 12178 23939 11973 23940 12178 23940 11967 23940 11967 23941 12178 23941 11969 23941 11970 23942 12178 23942 11964 23942 11964 23943 12178 23943 12180 23943 11964 23944 12180 23944 11961 23944 11961 23945 12180 23945 12179 23945 12179 23946 12180 23946 11805 23946 12179 23947 11805 23947 11809 23947 12183 23948 12174 23948 12176 23948 12178 23949 12177 23949 11931 23949 11931 23950 12177 23950 12181 23950 11931 23951 12181 23951 12229 23951 12182 23952 12183 23952 11936 23952 11936 23953 12183 23953 12176 23953 11936 23954 12176 23954 11933 23954 11933 23955 12176 23955 11811 23955 11933 23956 11811 23956 12184 23956 12184 23957 11811 23957 11805 23957 12184 23958 11805 23958 11931 23958 11931 23959 11805 23959 12180 23959 11931 23960 12180 23960 12178 23960 11816 23961 12185 23961 11817 23961 11817 23962 12185 23962 12186 23962 11817 23963 12186 23963 11814 23963 12153 23964 12152 23964 11894 23964 11894 23965 12152 23965 11823 23965 11894 23966 11823 23966 11889 23966 12328 23967 12187 23967 12193 23967 12195 23968 12189 23968 12188 23968 12188 23969 12189 23969 12190 23969 12211 23970 12191 23970 12207 23970 12207 23971 12191 23971 12238 23971 12207 23972 12238 23972 12208 23972 12193 23973 12192 23973 12328 23973 12328 23974 12192 23974 9624 23974 12328 23975 9624 23975 12197 23975 12187 23976 12325 23976 12193 23976 12193 23977 12325 23977 12194 23977 12193 23978 12194 23978 12195 23978 12195 23979 12194 23979 12196 23979 12195 23980 12196 23980 12189 23980 12319 23981 12021 23981 12201 23981 12201 23982 12021 23982 11906 23982 12340 23983 12019 23983 12319 23983 12319 23984 12019 23984 12020 23984 12319 23985 12020 23985 12021 23985 12035 23986 12025 23986 12340 23986 12340 23987 12025 23987 12027 23987 12340 23988 12027 23988 12019 23988 12199 23989 12329 23989 9613 23989 9613 23990 12329 23990 12328 23990 9613 23991 12328 23991 9619 23991 9619 23992 12328 23992 12197 23992 12207 23993 12198 23993 12211 23993 12211 23994 12198 23994 12331 23994 12211 23995 12331 23995 12199 23995 12199 23996 12331 23996 12200 23996 12199 23997 12200 23997 12329 23997 11906 23998 11905 23998 12201 23998 12201 23999 11905 23999 11917 23999 12201 24000 11917 24000 12190 24000 12190 24001 11917 24001 11913 24001 12190 24002 11913 24002 12188 24002 12340 24003 12339 24003 12035 24003 12035 24004 12339 24004 12202 24004 12035 24005 12202 24005 12204 24005 12204 24006 12202 24006 12203 24006 12203 24007 12335 24007 12204 24007 12204 24008 12335 24008 12205 24008 12204 24009 12205 24009 12232 24009 12232 24010 12205 24010 12207 24010 12232 24011 12207 24011 12206 24011 12206 24012 12207 24012 12208 24012 12451 24013 12453 24013 12211 24013 12451 24014 12211 24014 12449 24014 12448 24015 12449 24015 12212 24015 12212 24016 12449 24016 12209 24016 12209 24017 12449 24017 12211 24017 12209 24018 12211 24018 12210 24018 12210 24019 12211 24019 12199 24019 12210 24020 12199 24020 12454 24020 12445 24021 12215 24021 12220 24021 12212 24022 12213 24022 12448 24022 12448 24023 12213 24023 12214 24023 12448 24024 12214 24024 12215 24024 12215 24025 12214 24025 12455 24025 12215 24026 12455 24026 12220 24026 12225 24027 12216 24027 12220 24027 12220 24028 12216 24028 12217 24028 12220 24029 12217 24029 12218 24029 12218 24030 12219 24030 12220 24030 12220 24031 12219 24031 12221 24031 12220 24032 12221 24032 12222 24032 12222 24033 12223 24033 12220 24033 12220 24034 12223 24034 12444 24034 12220 24035 12444 24035 12445 24035 12458 24036 12225 24036 12224 24036 12224 24037 12225 24037 12457 24037 12458 24038 12226 24038 12225 24038 12225 24039 12226 24039 12227 24039 12225 24040 12227 24040 12216 24040 11989 24041 11934 24041 11924 24041 11924 24042 11934 24042 12228 24042 11924 24043 12228 24043 11922 24043 11943 24044 12229 24044 11954 24044 11954 24045 12229 24045 12181 24045 11954 24046 12181 24046 12230 24046 12211 24047 12453 24047 12428 24047 12211 24048 12428 24048 12191 24048 12030 24049 12204 24049 12231 24049 12231 24050 12204 24050 12232 24050 12231 24051 12232 24051 12425 24051 12425 24052 12232 24052 12233 24052 12233 24053 12232 24053 12206 24053 12233 24054 12206 24054 12234 24054 12234 24055 12206 24055 12235 24055 12235 24056 12206 24056 12208 24056 12235 24057 12208 24057 12237 24057 12238 24058 12432 24058 12208 24058 12208 24059 12432 24059 12236 24059 12208 24060 12236 24060 12237 24060 12428 24061 12429 24061 12191 24061 12191 24062 12429 24062 12239 24062 12191 24063 12239 24063 12238 24063 12238 24064 12239 24064 12431 24064 12238 24065 12431 24065 12432 24065 9664 24066 12240 24066 9665 24066 9665 24067 12240 24067 12241 24067 9665 24068 12241 24068 12242 24068 12242 24069 12241 24069 12243 24069 12242 24070 12243 24070 12244 24070 12244 24071 12243 24071 9494 24071 12244 24072 9494 24072 9668 24072 9668 24073 9494 24073 12245 24073 9668 24074 12245 24074 9669 24074 9669 24075 12245 24075 12246 24075 9669 24076 12246 24076 9670 24076 9670 24077 12246 24077 9495 24077 9670 24078 9495 24078 9672 24078 9672 24079 9495 24079 12247 24079 9672 24080 12247 24080 12248 24080 12248 24081 12247 24081 12249 24081 12248 24082 12249 24082 9673 24082 9673 24083 12249 24083 12251 24083 9673 24084 12251 24084 12250 24084 12250 24085 12251 24085 12253 24085 12250 24086 12253 24086 12252 24086 12252 24087 12253 24087 9491 24087 12252 24088 9491 24088 9664 24088 9664 24089 9491 24089 12240 24089 12265 24090 12254 24090 9699 24090 9699 24091 12254 24091 9524 24091 9699 24092 9524 24092 12255 24092 12255 24093 9524 24093 9527 24093 12255 24094 9527 24094 9701 24094 9701 24095 9527 24095 9529 24095 9701 24096 9529 24096 12256 24096 12256 24097 9529 24097 12257 24097 12256 24098 12257 24098 9703 24098 9703 24099 12257 24099 12258 24099 9703 24100 12258 24100 9704 24100 9704 24101 12258 24101 12259 24101 9704 24102 12259 24102 9707 24102 9707 24103 12259 24103 12260 24103 9707 24104 12260 24104 12261 24104 12261 24105 12260 24105 9533 24105 12261 24106 9533 24106 9708 24106 9708 24107 9533 24107 9535 24107 9708 24108 9535 24108 12262 24108 12262 24109 9535 24109 12264 24109 12262 24110 12264 24110 12263 24110 12263 24111 12264 24111 12266 24111 12263 24112 12266 24112 12265 24112 12265 24113 12266 24113 12254 24113 12280 24114 9555 24114 9596 24114 9597 24115 9594 24115 9537 24115 9537 24116 9594 24116 9593 24116 9537 24117 9593 24117 9591 24117 12288 24118 9574 24118 12267 24118 12267 24119 9574 24119 9571 24119 12267 24120 9571 24120 12303 24120 12303 24121 9571 24121 12269 24121 12303 24122 12269 24122 12268 24122 12268 24123 12269 24123 12300 24123 12284 24124 12270 24124 12298 24124 12298 24125 12270 24125 12271 24125 12298 24126 12271 24126 12272 24126 12272 24127 12271 24127 9607 24127 12272 24128 9607 24128 12273 24128 9547 24129 9543 24129 9565 24129 9565 24130 9543 24130 12300 24130 9565 24131 12300 24131 9569 24131 9569 24132 12300 24132 12269 24132 9543 24133 12274 24133 12300 24133 12300 24134 12274 24134 12275 24134 12300 24135 12275 24135 12276 24135 9537 24136 12277 24136 9597 24136 9597 24137 12277 24137 12278 24137 9597 24138 12278 24138 9596 24138 9596 24139 12278 24139 12279 24139 9596 24140 12279 24140 12280 24140 9584 24141 9582 24141 12292 24141 12292 24142 9582 24142 12281 24142 12275 24143 9537 24143 12276 24143 12276 24144 9537 24144 9591 24144 12276 24145 9591 24145 12282 24145 12282 24146 9591 24146 9610 24146 12282 24147 9610 24147 12283 24147 12283 24148 9610 24148 12284 24148 12283 24149 12284 24149 12297 24149 12297 24150 12284 24150 12298 24150 12273 24151 9607 24151 12293 24151 12293 24152 9607 24152 9603 24152 12293 24153 9603 24153 9600 24153 9565 24154 12285 24154 9547 24154 9547 24155 12285 24155 9586 24155 9547 24156 9586 24156 9545 24156 9545 24157 9586 24157 9584 24157 9545 24158 9584 24158 12286 24158 12286 24159 9584 24159 12292 24159 12267 24160 12287 24160 12288 24160 12288 24161 12287 24161 12289 24161 12288 24162 12289 24162 9578 24162 9578 24163 12289 24163 12290 24163 9578 24164 12290 24164 12281 24164 12281 24165 12290 24165 12291 24165 12281 24166 12291 24166 12292 24166 12292 24167 12291 24167 12293 24167 12292 24168 12293 24168 9555 24168 9555 24169 12293 24169 9600 24169 9555 24170 9600 24170 9596 24170 12287 24171 12294 24171 12289 24171 12289 24172 12294 24172 12347 24172 12289 24173 12347 24173 12290 24173 12290 24174 12347 24174 12348 24174 12290 24175 12348 24175 12291 24175 12291 24176 12348 24176 12295 24176 12342 24177 12293 24177 12295 24177 12295 24178 12293 24178 12291 24178 12293 24179 12342 24179 12273 24179 12273 24180 12342 24180 12343 24180 12273 24181 12343 24181 12272 24181 12272 24182 12343 24182 12344 24182 12272 24183 12344 24183 12298 24183 12298 24184 12344 24184 12296 24184 12349 24185 12297 24185 12296 24185 12296 24186 12297 24186 12298 24186 12297 24187 12349 24187 12283 24187 12283 24188 12349 24188 12350 24188 12283 24189 12350 24189 12282 24189 12282 24190 12350 24190 12299 24190 12282 24191 12299 24191 12276 24191 12276 24192 12299 24192 12352 24192 12301 24193 12300 24193 12352 24193 12352 24194 12300 24194 12276 24194 12300 24195 12301 24195 12268 24195 12268 24196 12301 24196 12354 24196 12268 24197 12354 24197 12303 24197 12303 24198 12354 24198 12302 24198 12303 24199 12302 24199 12267 24199 12267 24200 12302 24200 12304 24200 12294 24201 12287 24201 12304 24201 12304 24202 12287 24202 12267 24202 12310 24203 12338 24203 12305 24203 12305 24204 12338 24204 12306 24204 12305 24205 12306 24205 12353 24205 12353 24206 12306 24206 12320 24206 12353 24207 12320 24207 12357 24207 12357 24208 12320 24208 12307 24208 12357 24209 12307 24209 12311 24209 12318 24210 12333 24210 12308 24210 12308 24211 12333 24211 12334 24211 12308 24212 12334 24212 12345 24212 12345 24213 12334 24213 12336 24213 12345 24214 12336 24214 12351 24214 12351 24215 12336 24215 12309 24215 12351 24216 12309 24216 12310 24216 12310 24217 12309 24217 12337 24217 12310 24218 12337 24218 12338 24218 12307 24219 12321 24219 12311 24219 12311 24220 12321 24220 12322 24220 12311 24221 12322 24221 12355 24221 12355 24222 12322 24222 12323 24222 12355 24223 12323 24223 12356 24223 12356 24224 12323 24224 12324 24224 12356 24225 12324 24225 12312 24225 12312 24226 12324 24226 12313 24226 12312 24227 12313 24227 12346 24227 12346 24228 12313 24228 12314 24228 12346 24229 12314 24229 12315 24229 12314 24230 12326 24230 12315 24230 12315 24231 12326 24231 12327 24231 12315 24232 12327 24232 12316 24232 12316 24233 12327 24233 12317 24233 12316 24234 12317 24234 12341 24234 12341 24235 12317 24235 12330 24235 12341 24236 12330 24236 12318 24236 12318 24237 12330 24237 12332 24237 12318 24238 12332 24238 12333 24238 12201 24239 12307 24239 12319 24239 12319 24240 12307 24240 12320 24240 12307 24241 12201 24241 12321 24241 12321 24242 12201 24242 12190 24242 12321 24243 12190 24243 12322 24243 12322 24244 12190 24244 12189 24244 12322 24245 12189 24245 12323 24245 12323 24246 12189 24246 12196 24246 12323 24247 12196 24247 12324 24247 12324 24248 12196 24248 12194 24248 12325 24249 12313 24249 12194 24249 12194 24250 12313 24250 12324 24250 12313 24251 12325 24251 12314 24251 12314 24252 12325 24252 12187 24252 12314 24253 12187 24253 12326 24253 12326 24254 12187 24254 12328 24254 12326 24255 12328 24255 12327 24255 12327 24256 12328 24256 12329 24256 12327 24257 12329 24257 12317 24257 12317 24258 12329 24258 12200 24258 12331 24259 12330 24259 12200 24259 12200 24260 12330 24260 12317 24260 12330 24261 12331 24261 12332 24261 12332 24262 12331 24262 12198 24262 12332 24263 12198 24263 12333 24263 12333 24264 12198 24264 12207 24264 12333 24265 12207 24265 12334 24265 12334 24266 12207 24266 12205 24266 12334 24267 12205 24267 12336 24267 12336 24268 12205 24268 12335 24268 12203 24269 12309 24269 12335 24269 12335 24270 12309 24270 12336 24270 12309 24271 12203 24271 12337 24271 12337 24272 12203 24272 12202 24272 12337 24273 12202 24273 12338 24273 12338 24274 12202 24274 12339 24274 12338 24275 12339 24275 12306 24275 12306 24276 12339 24276 12340 24276 12306 24277 12340 24277 12320 24277 12320 24278 12340 24278 12319 24278 12341 24279 12342 24279 12316 24279 12316 24280 12342 24280 12295 24280 12342 24281 12341 24281 12343 24281 12343 24282 12341 24282 12318 24282 12343 24283 12318 24283 12344 24283 12344 24284 12318 24284 12308 24284 12344 24285 12308 24285 12296 24285 12296 24286 12308 24286 12345 24286 12294 24287 12312 24287 12347 24287 12347 24288 12312 24288 12346 24288 12347 24289 12346 24289 12348 24289 12348 24290 12346 24290 12315 24290 12348 24291 12315 24291 12295 24291 12295 24292 12315 24292 12316 24292 12351 24293 12349 24293 12345 24293 12345 24294 12349 24294 12296 24294 12304 24295 12356 24295 12294 24295 12294 24296 12356 24296 12312 24296 12349 24297 12351 24297 12350 24297 12350 24298 12351 24298 12310 24298 12350 24299 12310 24299 12299 24299 12299 24300 12310 24300 12305 24300 12299 24301 12305 24301 12352 24301 12352 24302 12305 24302 12353 24302 12301 24303 12357 24303 12354 24303 12354 24304 12357 24304 12311 24304 12354 24305 12311 24305 12302 24305 12302 24306 12311 24306 12355 24306 12302 24307 12355 24307 12304 24307 12304 24308 12355 24308 12356 24308 12357 24309 12301 24309 12353 24309 12353 24310 12301 24310 12352 24310 12358 24311 12359 24311 12360 24311 12360 24312 12359 24312 11497 24312 12360 24313 11497 24313 11920 24313 11920 24314 11497 24314 12361 24314 11920 24315 12361 24315 11921 24315 11921 24316 12361 24316 11499 24316 11921 24317 11499 24317 12362 24317 12362 24318 11499 24318 12363 24318 12362 24319 12363 24319 12365 24319 12365 24320 12363 24320 11433 24320 12364 24321 12366 24321 12369 24321 12365 24322 11433 24322 11432 24322 12369 24323 12366 24323 11430 24323 11430 24324 12366 24324 12367 24324 11430 24325 12367 24325 11432 24325 11432 24326 12367 24326 12368 24326 11432 24327 12368 24327 12365 24327 12364 24328 12369 24328 11919 24328 11919 24329 12369 24329 12370 24329 11919 24330 12370 24330 12371 24330 12370 24331 11435 24331 12371 24331 12371 24332 11435 24332 12391 24332 12371 24333 12391 24333 12372 24333 12395 24334 12373 24334 12024 24334 12024 24335 12373 24335 11489 24335 12024 24336 11489 24336 12026 24336 11492 24337 12374 24337 12375 24337 12375 24338 12374 24338 12028 24338 12375 24339 12028 24339 11487 24339 11487 24340 12028 24340 12026 24340 11487 24341 12026 24341 12376 24341 12376 24342 12026 24342 11489 24342 11491 24343 12023 24343 11492 24343 11492 24344 12023 24344 12022 24344 11492 24345 12022 24345 12374 24345 12380 24346 12377 24346 11493 24346 11493 24347 12377 24347 12378 24347 11493 24348 12378 24348 11490 24348 11490 24349 12378 24349 12379 24349 11490 24350 12379 24350 11491 24350 11491 24351 12379 24351 12017 24351 11491 24352 12017 24352 12023 24352 11493 24353 11494 24353 12380 24353 12380 24354 11494 24354 12382 24354 12380 24355 12382 24355 12381 24355 12359 24356 12358 24356 12382 24356 12382 24357 12358 24357 12383 24357 12382 24358 12383 24358 12381 24358 11671 24359 11909 24359 12384 24359 12384 24360 11909 24360 11910 24360 12384 24361 11910 24361 12385 24361 12385 24362 11910 24362 11911 24362 12385 24363 11911 24363 12386 24363 11911 24364 11915 24364 12386 24364 12386 24365 11915 24365 11914 24365 12386 24366 11914 24366 12387 24366 12387 24367 11914 24367 11912 24367 12387 24368 11912 24368 12388 24368 12388 24369 11912 24369 12389 24369 12388 24370 12389 24370 12390 24370 12372 24371 12391 24371 11907 24371 11907 24372 12391 24372 11438 24372 11907 24373 11438 24373 11904 24373 11904 24374 11438 24374 11436 24374 11904 24375 11436 24375 12392 24375 12392 24376 11436 24376 11472 24376 12392 24377 11472 24377 11916 24377 11916 24378 11472 24378 12393 24378 11916 24379 12393 24379 11918 24379 11918 24380 12393 24380 12390 24380 11918 24381 12390 24381 12394 24381 12394 24382 12390 24382 12389 24382 12018 24383 12396 24383 12395 24383 12395 24384 12396 24384 12373 24384 11909 24385 11671 24385 11908 24385 11908 24386 11671 24386 11670 24386 12033 24387 12397 24387 12398 24387 12033 24388 12398 24388 12029 24388 12029 24389 12398 24389 11557 24389 12029 24390 11557 24390 12034 24390 12034 24391 11557 24391 12400 24391 12034 24392 12400 24392 12399 24392 12399 24393 12400 24393 12401 24393 12399 24394 12401 24394 12036 24394 12036 24395 12401 24395 12396 24395 12036 24396 12396 24396 12018 24396 11908 24397 11670 24397 11669 24397 11908 24398 11669 24398 12402 24398 11669 24399 11674 24399 12402 24399 12402 24400 11674 24400 12403 24400 12402 24401 12403 24401 12404 24401 12404 24402 12403 24402 12405 24402 12404 24403 12405 24403 11899 24403 11899 24404 12405 24404 12406 24404 12406 24405 12405 24405 11676 24405 12406 24406 11676 24406 11900 24406 12397 24407 12033 24407 11591 24407 11591 24408 12033 24408 12032 24408 11591 24409 12032 24409 11578 24409 11578 24410 12032 24410 12411 24410 12031 24411 12407 24411 12408 24411 12408 24412 12407 24412 12409 24412 12408 24413 12409 24413 12410 24413 12410 24414 12409 24414 11586 24414 12410 24415 11586 24415 12411 24415 12411 24416 11586 24416 12412 24416 12411 24417 12412 24417 11578 24417 12413 24418 11902 24418 12414 24418 12414 24419 11902 24419 12415 24419 12414 24420 12415 24420 12416 24420 12416 24421 12415 24421 11901 24421 12416 24422 11901 24422 11649 24422 11649 24423 11901 24423 12417 24423 11649 24424 12417 24424 11648 24424 11900 24425 11676 24425 12417 24425 12417 24426 11676 24426 12418 24426 12417 24427 12418 24427 11648 24427 12407 24428 12031 24428 12420 24428 12420 24429 12031 24429 12419 24429 12420 24430 12419 24430 12030 24430 11902 24431 12413 24431 11903 24431 11903 24432 12413 24432 12421 24432 11903 24433 12421 24433 9612 24433 12231 24434 10075 24434 12030 24434 12030 24435 10075 24435 12420 24435 9905 24436 12439 24436 9623 24436 9612 24437 12421 24437 12422 24437 12422 24438 12421 24438 9905 24438 12422 24439 9905 24439 12423 24439 12423 24440 9905 24440 9623 24440 10075 24441 12231 24441 12424 24441 12424 24442 12231 24442 12425 24442 12424 24443 12425 24443 12426 24443 12426 24444 12425 24444 12233 24444 12426 24445 12233 24445 10040 24445 12233 24446 12234 24446 10040 24446 10040 24447 12234 24447 12235 24447 10040 24448 12235 24448 12427 24448 12235 24449 12237 24449 12427 24449 12427 24450 12237 24450 12236 24450 12427 24451 12236 24451 9996 24451 9996 24452 12236 24452 12432 24452 9996 24453 12432 24453 10035 24453 12453 24454 10037 24454 12428 24454 12428 24455 10037 24455 10036 24455 12428 24456 10036 24456 12429 24456 12429 24457 10036 24457 12430 24457 12429 24458 12430 24458 12239 24458 12239 24459 12430 24459 10035 24459 12239 24460 10035 24460 12431 24460 12431 24461 10035 24461 12432 24461 9863 24462 12454 24462 12433 24462 12433 24463 12454 24463 12434 24463 12433 24464 12434 24464 9861 24464 9861 24465 12434 24465 9616 24465 9861 24466 9616 24466 12435 24466 9616 24467 9615 24467 12435 24467 12435 24468 9615 24468 9614 24468 12435 24469 9614 24469 9859 24469 9859 24470 9614 24470 9622 24470 9859 24471 9622 24471 12436 24471 12436 24472 9622 24472 9621 24472 12436 24473 9621 24473 9855 24473 9855 24474 9621 24474 9620 24474 9855 24475 9620 24475 9854 24475 9854 24476 9620 24476 9618 24476 9854 24477 9618 24477 12437 24477 9623 24478 12439 24478 12438 24478 12438 24479 12439 24479 9852 24479 12438 24480 9852 24480 9625 24480 9625 24481 9852 24481 12440 24481 9625 24482 12440 24482 12441 24482 12441 24483 12440 24483 12437 24483 12441 24484 12437 24484 9617 24484 9617 24485 12437 24485 9618 24485 12217 24486 12461 24486 12442 24486 12217 24487 12442 24487 12218 24487 12218 24488 12442 24488 10063 24488 12218 24489 10063 24489 12219 24489 12219 24490 10063 24490 10026 24490 12219 24491 10026 24491 12221 24491 12221 24492 10026 24492 10028 24492 12221 24493 10028 24493 12222 24493 12222 24494 10028 24494 12443 24494 12222 24495 12443 24495 12223 24495 12223 24496 12443 24496 12446 24496 12223 24497 12446 24497 12444 24497 12444 24498 12446 24498 12445 24498 12445 24499 12446 24499 12447 24499 12445 24500 12447 24500 12215 24500 12215 24501 12447 24501 10031 24501 12215 24502 10031 24502 12448 24502 12448 24503 10031 24503 12450 24503 12448 24504 12450 24504 12449 24504 12449 24505 12450 24505 12452 24505 12449 24506 12452 24506 12451 24506 12451 24507 12452 24507 10037 24507 12451 24508 10037 24508 12453 24508 12457 24509 12225 24509 9892 24509 12454 24510 9863 24510 9889 24510 12213 24511 12212 24511 9891 24511 9891 24512 12212 24512 12209 24512 9891 24513 12209 24513 9889 24513 9889 24514 12209 24514 12210 24514 9889 24515 12210 24515 12454 24515 9892 24516 12225 24516 12456 24516 12225 24517 12220 24517 12456 24517 12456 24518 12220 24518 12455 24518 12456 24519 12455 24519 9891 24519 9891 24520 12455 24520 12214 24520 9891 24521 12214 24521 12213 24521 9892 24522 9866 24522 12457 24522 12457 24523 9866 24523 9867 24523 12457 24524 9867 24524 12224 24524 12224 24525 9867 24525 12459 24525 12224 24526 12459 24526 12458 24526 12458 24527 12459 24527 9883 24527 12458 24528 9883 24528 12226 24528 12226 24529 9883 24529 12460 24529 12226 24530 12460 24530 12227 24530 12227 24531 12460 24531 12216 24531 12216 24532 12460 24532 12461 24532 12216 24533 12461 24533 12217 24533 12843 24534 12462 24534 12463 24534 12843 24535 12463 24535 12839 24535 12839 24536 12463 24536 12464 24536 12839 24537 12464 24537 12841 24537 12841 24538 12464 24538 12466 24538 12841 24539 12466 24539 12465 24539 12465 24540 12466 24540 10899 24540 12465 24541 10899 24541 12837 24541 12462 24542 12486 24542 12463 24542 12463 24543 12486 24543 12467 24543 12463 24544 12467 24544 12464 24544 12464 24545 12467 24545 12468 24545 12464 24546 12468 24546 12466 24546 12466 24547 12468 24547 12469 24547 12466 24548 12469 24548 10899 24548 10899 24549 12469 24549 10920 24549 12512 24550 12479 24550 12502 24550 12471 24551 10918 24551 10920 24551 10918 24552 12471 24552 12470 24552 12470 24553 12471 24553 12472 24553 12470 24554 12472 24554 10909 24554 10909 24555 12472 24555 12474 24555 10909 24556 12474 24556 12473 24556 12473 24557 12474 24557 12509 24557 12473 24558 12509 24558 12475 24558 12475 24559 12509 24559 12507 24559 12475 24560 12507 24560 10921 24560 10921 24561 12507 24561 12506 24561 10921 24562 12506 24562 12476 24562 12476 24563 12506 24563 12505 24563 12476 24564 12505 24564 12477 24564 12477 24565 12505 24565 12478 24565 12478 24566 12505 24566 12504 24566 12478 24567 12504 24567 10923 24567 10923 24568 12504 24568 12502 24568 10923 24569 12502 24569 10915 24569 10915 24570 12502 24570 12479 24570 10915 24571 12479 24571 10916 24571 12468 24572 12467 24572 12480 24572 12488 24573 12481 24573 12483 24573 12483 24574 12481 24574 12482 24574 12483 24575 12482 24575 10926 24575 10926 24576 12482 24576 12484 24576 10926 24577 12484 24577 10927 24577 10927 24578 12484 24578 12500 24578 10927 24579 12500 24579 12485 24579 12485 24580 12500 24580 12480 24580 12485 24581 12480 24581 10928 24581 10928 24582 12480 24582 12467 24582 10928 24583 12467 24583 12486 24583 12489 24584 12496 24584 12488 24584 12488 24585 12496 24585 12487 24585 12488 24586 12487 24586 12481 24586 12489 24587 10933 24587 12496 24587 12496 24588 10933 24588 12490 24588 12496 24589 12490 24589 12495 24589 12495 24590 12490 24590 12491 24590 12495 24591 12491 24591 12494 24591 12494 24592 12491 24592 10932 24592 10932 24593 12492 24593 12494 24593 12494 24594 12492 24594 12493 24594 12494 24595 12493 24595 12495 24595 12495 24596 12493 24596 12503 24596 12495 24597 12503 24597 12496 24597 12496 24598 12503 24598 12497 24598 12496 24599 12497 24599 12487 24599 12487 24600 12497 24600 12498 24600 12487 24601 12498 24601 12481 24601 12481 24602 12498 24602 12499 24602 12481 24603 12499 24603 12482 24603 12482 24604 12499 24604 12508 24604 12482 24605 12508 24605 12484 24605 12484 24606 12508 24606 12510 24606 12484 24607 12510 24607 12500 24607 12500 24608 12510 24608 12511 24608 12500 24609 12511 24609 12480 24609 12480 24610 12511 24610 12501 24610 12480 24611 12501 24611 12468 24611 12468 24612 12501 24612 12469 24612 12492 24613 12512 24613 12493 24613 12493 24614 12512 24614 12502 24614 12493 24615 12502 24615 12503 24615 12503 24616 12502 24616 12504 24616 12503 24617 12504 24617 12497 24617 12497 24618 12504 24618 12505 24618 12497 24619 12505 24619 12498 24619 12498 24620 12505 24620 12506 24620 12498 24621 12506 24621 12499 24621 12499 24622 12506 24622 12507 24622 12499 24623 12507 24623 12508 24623 12508 24624 12507 24624 12509 24624 12508 24625 12509 24625 12510 24625 12510 24626 12509 24626 12474 24626 12510 24627 12474 24627 12511 24627 12511 24628 12474 24628 12472 24628 12511 24629 12472 24629 12501 24629 12501 24630 12472 24630 12471 24630 12501 24631 12471 24631 12469 24631 12469 24632 12471 24632 10920 24632 12492 24633 10932 24633 12515 24633 12512 24634 12492 24634 12522 24634 12527 24635 10560 24635 12513 24635 12513 24636 10560 24636 12514 24636 12513 24637 12514 24637 10916 24637 12492 24638 12515 24638 12522 24638 12522 24639 12515 24639 10931 24639 12522 24640 10931 24640 12524 24640 12524 24641 10931 24641 10930 24641 12524 24642 10930 24642 12516 24642 12516 24643 10930 24643 10940 24643 12516 24644 10940 24644 12526 24644 10940 24645 12517 24645 12526 24645 12526 24646 12517 24646 10936 24646 12526 24647 10936 24647 12518 24647 12518 24648 10936 24648 12519 24648 12518 24649 12519 24649 12520 24649 12520 24650 12519 24650 12521 24650 12520 24651 12521 24651 12542 24651 12479 24652 12512 24652 12528 24652 12528 24653 12512 24653 12522 24653 12528 24654 12522 24654 12523 24654 12523 24655 12522 24655 12524 24655 12523 24656 12524 24656 12525 24656 12525 24657 12524 24657 12516 24657 12525 24658 12516 24658 12529 24658 12529 24659 12516 24659 12526 24659 12529 24660 12526 24660 12530 24660 12530 24661 12526 24661 12518 24661 12530 24662 12518 24662 12532 24662 12532 24663 12518 24663 12520 24663 12532 24664 12520 24664 12533 24664 12533 24665 12520 24665 12542 24665 10916 24666 12479 24666 12513 24666 12513 24667 12479 24667 12528 24667 12513 24668 12528 24668 12527 24668 12527 24669 12528 24669 12523 24669 12527 24670 12523 24670 12541 24670 12541 24671 12523 24671 12525 24671 12541 24672 12525 24672 12539 24672 12539 24673 12525 24673 12529 24673 12539 24674 12529 24674 12537 24674 12537 24675 12529 24675 12530 24675 12537 24676 12530 24676 12531 24676 12531 24677 12530 24677 12532 24677 12531 24678 12532 24678 12536 24678 12536 24679 12532 24679 12533 24679 12545 24680 12534 24680 12536 24680 12536 24681 12534 24681 12535 24681 12536 24682 12535 24682 12531 24682 12531 24683 12535 24683 10541 24683 12531 24684 10541 24684 12537 24684 12537 24685 10541 24685 12538 24685 12537 24686 12538 24686 12539 24686 12539 24687 12538 24687 12540 24687 12539 24688 12540 24688 12541 24688 12541 24689 12540 24689 10558 24689 12541 24690 10558 24690 12527 24690 12527 24691 10558 24691 10559 24691 12527 24692 10559 24692 10560 24692 12521 24693 10943 24693 12542 24693 12542 24694 10943 24694 12548 24694 12542 24695 12548 24695 12533 24695 12533 24696 12548 24696 12543 24696 12533 24697 12543 24697 12536 24697 12536 24698 12543 24698 12544 24698 12536 24699 12544 24699 12545 24699 12545 24700 12544 24700 10547 24700 10545 24701 10547 24701 12544 24701 12548 24702 10943 24702 12546 24702 12550 24703 12543 24703 12547 24703 12547 24704 12543 24704 12548 24704 12547 24705 12548 24705 12565 24705 12565 24706 12548 24706 12546 24706 10550 24707 10545 24707 12549 24707 12549 24708 10545 24708 12544 24708 12549 24709 12544 24709 12560 24709 12560 24710 12544 24710 12543 24710 12560 24711 12543 24711 12564 24711 12564 24712 12543 24712 12550 24712 10550 24713 12549 24713 12559 24713 12576 24714 10360 24714 12551 24714 12563 24715 12576 24715 12557 24715 12567 24716 12552 24716 10947 24716 10947 24717 12552 24717 12554 24717 10947 24718 12554 24718 12566 24718 12567 24719 12570 24719 12552 24719 12552 24720 12570 24720 12553 24720 12552 24721 12553 24721 12554 24721 12554 24722 12553 24722 12561 24722 12554 24723 12561 24723 12555 24723 12555 24724 12561 24724 12556 24724 12576 24725 12551 24725 12557 24725 12557 24726 12551 24726 12558 24726 12557 24727 12558 24727 12562 24727 12562 24728 12558 24728 10554 24728 12562 24729 10554 24729 12559 24729 12559 24730 10554 24730 10552 24730 12559 24731 10552 24731 10550 24731 12549 24732 12560 24732 12559 24732 12559 24733 12560 24733 12556 24733 12559 24734 12556 24734 12562 24734 12562 24735 12556 24735 12561 24735 12562 24736 12561 24736 12557 24736 12557 24737 12561 24737 12553 24737 12557 24738 12553 24738 12563 24738 12563 24739 12553 24739 12570 24739 12560 24740 12564 24740 12556 24740 12556 24741 12564 24741 12550 24741 12556 24742 12550 24742 12555 24742 12555 24743 12550 24743 12547 24743 12555 24744 12547 24744 12565 24744 12566 24745 12554 24745 10946 24745 10946 24746 12554 24746 12555 24746 10946 24747 12555 24747 10944 24747 10944 24748 12555 24748 12565 24748 10944 24749 12565 24749 12546 24749 10949 24750 10951 24750 12569 24750 12567 24751 10949 24751 12568 24751 12568 24752 10949 24752 12569 24752 12568 24753 12569 24753 12571 24753 12567 24754 12568 24754 12570 24754 12570 24755 12568 24755 12571 24755 12570 24756 12571 24756 12563 24756 12563 24757 12571 24757 12575 24757 12563 24758 12575 24758 12576 24758 12569 24759 12572 24759 12571 24759 12571 24760 12572 24760 12573 24760 12571 24761 12573 24761 12575 24761 12575 24762 12573 24762 12574 24762 12575 24763 12574 24763 12593 24763 12593 24764 10363 24764 12575 24764 12575 24765 10363 24765 10361 24765 12575 24766 10361 24766 12576 24766 12576 24767 10361 24767 10360 24767 12593 24768 12574 24768 12584 24768 12573 24769 12572 24769 12577 24769 12569 24770 10951 24770 12578 24770 12572 24771 12569 24771 12577 24771 12577 24772 12569 24772 12578 24772 12577 24773 12578 24773 12585 24773 12585 24774 12578 24774 10967 24774 12585 24775 10967 24775 12588 24775 12588 24776 10967 24776 10966 24776 12588 24777 10966 24777 12579 24777 12579 24778 10966 24778 12581 24778 12579 24779 12581 24779 12580 24779 12580 24780 12581 24780 12582 24780 12580 24781 12582 24781 12590 24781 12590 24782 12582 24782 10962 24782 12590 24783 10962 24783 12592 24783 12592 24784 10962 24784 10964 24784 12592 24785 10964 24785 12614 24785 12614 24786 10964 24786 12583 24786 12574 24787 12573 24787 12584 24787 12584 24788 12573 24788 12577 24788 12584 24789 12577 24789 12586 24789 12586 24790 12577 24790 12585 24790 12586 24791 12585 24791 12587 24791 12587 24792 12585 24792 12588 24792 12587 24793 12588 24793 12589 24793 12589 24794 12588 24794 12579 24794 12589 24795 12579 24795 12596 24795 12596 24796 12579 24796 12580 24796 12596 24797 12580 24797 12597 24797 12597 24798 12580 24798 12590 24798 12597 24799 12590 24799 12591 24799 12591 24800 12590 24800 12592 24800 12591 24801 12592 24801 12605 24801 12605 24802 12592 24802 12614 24802 10363 24803 12593 24803 12594 24803 12594 24804 12593 24804 12584 24804 12594 24805 12584 24805 10345 24805 10345 24806 12584 24806 12586 24806 10345 24807 12586 24807 10344 24807 10344 24808 12586 24808 12587 24808 10344 24809 12587 24809 12595 24809 12595 24810 12587 24810 12589 24810 12595 24811 12589 24811 10347 24811 10347 24812 12589 24812 12596 24812 10347 24813 12596 24813 10348 24813 10348 24814 12596 24814 12597 24814 10348 24815 12597 24815 10388 24815 10388 24816 12597 24816 12591 24816 10388 24817 12591 24817 10389 24817 10389 24818 12591 24818 12605 24818 12619 24819 12598 24819 12608 24819 12608 24820 12598 24820 12599 24820 12608 24821 12599 24821 12600 24821 12600 24822 12599 24822 10405 24822 12600 24823 10405 24823 12610 24823 12610 24824 10405 24824 12601 24824 12610 24825 12601 24825 12612 24825 12612 24826 12601 24826 12602 24826 12612 24827 12602 24827 12603 24827 12603 24828 12602 24828 12604 24828 12603 24829 12604 24829 12605 24829 12605 24830 12604 24830 10389 24830 12606 24831 12619 24831 12607 24831 12607 24832 12619 24832 12608 24832 12607 24833 12608 24833 12609 24833 12609 24834 12608 24834 12600 24834 12609 24835 12600 24835 12617 24835 12617 24836 12600 24836 12610 24836 12617 24837 12610 24837 12611 24837 12611 24838 12610 24838 12612 24838 12611 24839 12612 24839 12613 24839 12613 24840 12612 24840 12603 24840 12613 24841 12603 24841 12614 24841 12614 24842 12603 24842 12605 24842 10974 24843 12606 24843 12615 24843 12615 24844 12606 24844 12607 24844 12615 24845 12607 24845 10969 24845 10969 24846 12607 24846 12609 24846 10969 24847 12609 24847 12616 24847 12616 24848 12609 24848 12617 24848 12616 24849 12617 24849 10972 24849 10972 24850 12617 24850 12611 24850 10972 24851 12611 24851 10973 24851 10973 24852 12611 24852 12613 24852 10973 24853 12613 24853 12583 24853 12583 24854 12613 24854 12614 24854 10387 24855 12598 24855 12618 24855 12618 24856 12598 24856 12619 24856 12618 24857 12619 24857 12632 24857 12632 24858 12619 24858 12606 24858 12632 24859 12606 24859 12620 24859 12620 24860 12606 24860 10974 24860 12650 24861 10367 24861 12621 24861 12621 24862 10367 24862 12622 24862 12621 24863 12622 24863 12623 24863 12623 24864 12622 24864 10350 24864 12623 24865 10350 24865 12624 24865 12624 24866 10350 24866 10404 24866 12624 24867 10404 24867 12630 24867 12630 24868 10404 24868 10403 24868 12630 24869 10403 24869 12631 24869 12631 24870 10403 24870 12625 24870 12631 24871 12625 24871 12618 24871 12618 24872 12625 24872 10387 24872 12633 24873 12650 24873 12626 24873 12626 24874 12650 24874 12621 24874 12626 24875 12621 24875 12627 24875 12627 24876 12621 24876 12623 24876 12627 24877 12623 24877 12628 24877 12628 24878 12623 24878 12624 24878 12628 24879 12624 24879 12629 24879 12629 24880 12624 24880 12630 24880 12629 24881 12630 24881 12637 24881 12637 24882 12630 24882 12631 24882 12637 24883 12631 24883 12632 24883 12632 24884 12631 24884 12618 24884 10984 24885 12633 24885 12634 24885 12634 24886 12633 24886 12626 24886 12634 24887 12626 24887 10975 24887 10975 24888 12626 24888 12627 24888 10975 24889 12627 24889 12635 24889 12635 24890 12627 24890 12628 24890 12635 24891 12628 24891 10976 24891 10976 24892 12628 24892 12629 24892 10976 24893 12629 24893 12636 24893 12636 24894 12629 24894 12637 24894 12636 24895 12637 24895 12620 24895 12620 24896 12637 24896 12632 24896 12633 24897 10984 24897 12646 24897 12646 24898 10984 24898 12638 24898 12646 24899 12638 24899 12639 24899 12639 24900 12638 24900 10982 24900 12639 24901 10982 24901 12647 24901 12647 24902 10982 24902 12640 24902 12647 24903 12640 24903 12648 24903 12648 24904 12640 24904 10981 24904 12648 24905 10981 24905 12641 24905 12641 24906 10981 24906 10979 24906 12641 24907 10979 24907 12642 24907 12642 24908 10979 24908 10978 24908 12642 24909 10978 24909 12643 24909 12643 24910 10978 24910 10977 24910 12643 24911 10977 24911 12666 24911 12666 24912 10977 24912 12644 24912 12650 24913 12633 24913 12652 24913 12652 24914 12633 24914 12646 24914 12652 24915 12646 24915 12645 24915 12645 24916 12646 24916 12639 24916 12645 24917 12639 24917 12654 24917 12654 24918 12639 24918 12647 24918 12654 24919 12647 24919 12655 24919 12655 24920 12647 24920 12648 24920 12655 24921 12648 24921 12649 24921 12649 24922 12648 24922 12641 24922 12649 24923 12641 24923 12657 24923 12657 24924 12641 24924 12642 24924 12657 24925 12642 24925 12658 24925 12658 24926 12642 24926 12643 24926 12658 24927 12643 24927 12663 24927 12663 24928 12643 24928 12666 24928 10367 24929 12650 24929 12651 24929 12651 24930 12650 24930 12652 24930 12651 24931 12652 24931 10370 24931 10370 24932 12652 24932 12645 24932 10370 24933 12645 24933 12653 24933 12653 24934 12645 24934 12654 24934 12653 24935 12654 24935 10365 24935 10365 24936 12654 24936 12655 24936 10365 24937 12655 24937 10366 24937 10366 24938 12655 24938 12649 24938 10366 24939 12649 24939 12656 24939 12656 24940 12649 24940 12657 24940 12656 24941 12657 24941 12659 24941 12659 24942 12657 24942 12658 24942 12659 24943 12658 24943 10380 24943 10380 24944 12658 24944 12663 24944 12675 24945 12660 24945 12665 24945 12665 24946 12660 24946 12664 24946 12667 24947 12661 24947 12683 24947 12683 24948 12678 24948 12667 24948 12667 24949 12678 24949 12662 24949 12667 24950 12662 24950 12665 24950 12665 24951 12662 24951 12676 24951 12665 24952 12676 24952 12675 24952 12664 24953 10380 24953 12663 24953 12664 24954 12663 24954 12665 24954 12665 24955 12663 24955 12666 24955 12665 24956 12666 24956 12667 24956 12667 24957 12666 24957 12644 24957 12667 24958 12644 24958 12661 24958 10438 24959 12668 24959 10428 24959 10428 24960 12668 24960 12687 24960 10428 24961 12687 24961 10430 24961 12686 24962 12685 24962 12679 24962 10990 24963 12686 24963 12671 24963 12681 24964 12680 24964 12669 24964 12669 24965 12680 24965 12679 24965 12669 24966 12679 24966 12668 24966 12668 24967 12679 24967 12685 24967 12668 24968 12685 24968 12687 24968 12670 24969 10987 24969 12671 24969 12671 24970 10987 24970 10989 24970 12671 24971 10989 24971 10990 24971 10439 24972 12673 24972 12672 24972 12672 24973 12673 24973 12674 24973 12672 24974 12674 24974 12677 24974 12673 24975 12660 24975 12674 24975 12674 24976 12660 24976 12675 24976 12674 24977 12675 24977 12677 24977 12677 24978 12675 24978 12676 24978 12677 24979 12676 24979 12662 24979 10438 24980 10439 24980 12668 24980 12668 24981 10439 24981 12672 24981 12668 24982 12672 24982 12669 24982 12669 24983 12672 24983 12677 24983 12669 24984 12677 24984 12681 24984 12681 24985 12677 24985 12662 24985 12681 24986 12662 24986 12678 24986 12686 24987 12679 24987 12671 24987 12671 24988 12679 24988 12680 24988 12671 24989 12680 24989 12670 24989 12670 24990 12680 24990 12681 24990 12670 24991 12681 24991 12682 24991 12682 24992 12681 24992 12678 24992 12682 24993 12678 24993 12683 24993 12684 24994 12685 24994 12692 24994 12692 24995 12685 24995 12686 24995 12692 24996 12686 24996 11076 24996 11076 24997 12686 24997 10990 24997 10426 24998 10430 24998 12693 24998 12693 24999 10430 24999 12687 24999 12693 25000 12687 25000 12696 25000 12696 25001 12687 25001 12685 25001 12696 25002 12685 25002 12701 25002 12701 25003 12685 25003 12684 25003 10409 25004 12688 25004 12723 25004 12704 25005 12703 25005 12705 25005 12689 25006 12716 25006 12690 25006 10418 25007 12691 25007 12702 25007 12696 25008 12701 25008 12699 25008 12684 25009 12692 25009 12700 25009 10426 25010 12693 25010 10425 25010 10425 25011 12693 25011 12695 25011 10425 25012 12695 25012 10423 25012 10423 25013 12695 25013 10421 25013 12697 25014 10421 25014 12694 25014 12694 25015 10421 25015 12695 25015 12694 25016 12695 25016 12699 25016 12699 25017 12695 25017 12693 25017 12699 25018 12693 25018 12696 25018 12691 25019 12697 25019 12702 25019 12702 25020 12697 25020 12694 25020 12702 25021 12694 25021 12698 25021 12698 25022 12694 25022 12699 25022 12698 25023 12699 25023 12700 25023 12700 25024 12699 25024 12701 25024 12700 25025 12701 25025 12684 25025 12700 25026 12709 25026 12698 25026 12698 25027 12709 25027 12706 25027 12698 25028 12706 25028 12702 25028 12702 25029 12706 25029 12705 25029 12702 25030 12705 25030 10418 25030 10418 25031 12705 25031 12703 25031 12689 25032 12690 25032 12720 25032 12710 25033 12704 25033 12711 25033 12711 25034 12704 25034 12705 25034 12711 25035 12705 25035 12707 25035 12707 25036 12705 25036 12706 25036 12707 25037 12706 25037 12708 25037 12708 25038 12706 25038 12709 25038 10413 25039 12710 25039 12712 25039 12712 25040 12710 25040 12711 25040 12712 25041 12711 25041 12713 25041 12713 25042 12711 25042 12707 25042 12713 25043 12707 25043 12719 25043 12719 25044 12707 25044 12708 25044 11080 25045 12714 25045 12717 25045 12717 25046 12714 25046 12715 25046 12717 25047 12715 25047 12722 25047 12716 25048 11080 25048 12690 25048 12690 25049 11080 25049 12717 25049 12690 25050 12717 25050 12718 25050 12718 25051 12717 25051 12722 25051 12718 25052 12722 25052 12723 25052 12688 25053 10413 25053 12723 25053 12723 25054 10413 25054 12712 25054 12723 25055 12712 25055 12718 25055 12718 25056 12712 25056 12713 25056 12718 25057 12713 25057 12690 25057 12690 25058 12713 25058 12719 25058 12690 25059 12719 25059 12720 25059 12720 25060 12719 25060 12708 25060 12720 25061 12708 25061 11083 25061 11083 25062 12708 25062 12709 25062 11083 25063 12709 25063 11082 25063 11082 25064 12709 25064 12700 25064 11082 25065 12700 25065 12721 25065 12721 25066 12700 25066 12692 25066 12721 25067 12692 25067 11076 25067 12714 25068 11086 25068 12715 25068 12715 25069 11086 25069 12746 25069 12715 25070 12746 25070 12722 25070 12722 25071 12746 25071 12724 25071 12722 25072 12724 25072 12723 25072 12723 25073 12724 25073 12747 25073 12723 25074 12747 25074 10409 25074 10409 25075 12747 25075 12725 25075 12774 25076 12773 25076 12734 25076 12725 25077 12764 25077 11012 25077 11012 25078 12764 25078 12726 25078 11012 25079 12726 25079 11013 25079 11013 25080 12726 25080 12727 25080 12727 25081 12726 25081 12728 25081 12727 25082 12728 25082 11016 25082 11016 25083 12728 25083 12762 25083 11016 25084 12762 25084 11018 25084 11018 25085 12762 25085 12760 25085 11018 25086 12760 25086 11020 25086 11020 25087 12760 25087 12729 25087 11020 25088 12729 25088 12730 25088 12730 25089 12729 25089 12758 25089 12730 25090 12758 25090 12731 25090 12731 25091 12758 25091 12732 25091 12732 25092 12758 25092 12757 25092 12732 25093 12757 25093 12733 25093 12733 25094 12757 25094 12734 25094 12733 25095 12734 25095 11010 25095 11010 25096 12734 25096 12773 25096 11010 25097 12773 25097 12735 25097 12724 25098 12746 25098 12748 25098 11098 25099 12736 25099 12737 25099 12737 25100 12736 25100 12755 25100 12737 25101 12755 25101 12738 25101 12738 25102 12755 25102 12740 25102 12738 25103 12740 25103 12739 25103 12739 25104 12740 25104 12741 25104 12739 25105 12741 25105 11092 25105 11092 25106 12741 25106 12752 25106 11092 25107 12752 25107 11091 25107 11091 25108 12752 25108 12742 25108 11091 25109 12742 25109 12743 25109 12743 25110 12742 25110 12744 25110 12743 25111 12744 25111 12745 25111 12745 25112 12744 25112 12750 25112 12745 25113 12750 25113 11084 25113 11084 25114 12750 25114 12748 25114 11084 25115 12748 25115 11087 25115 11087 25116 12748 25116 12746 25116 11087 25117 12746 25117 11086 25117 12747 25118 12724 25118 12765 25118 12765 25119 12724 25119 12748 25119 12765 25120 12748 25120 12749 25120 12749 25121 12748 25121 12750 25121 12749 25122 12750 25122 12763 25122 12763 25123 12750 25123 12744 25123 12763 25124 12744 25124 12761 25124 12761 25125 12744 25125 12742 25125 12761 25126 12742 25126 12759 25126 12759 25127 12742 25127 12752 25127 12759 25128 12752 25128 12751 25128 12751 25129 12752 25129 12741 25129 12751 25130 12741 25130 12753 25130 12753 25131 12741 25131 12740 25131 12753 25132 12740 25132 12754 25132 12754 25133 12740 25133 12755 25133 12754 25134 12755 25134 12756 25134 12756 25135 12755 25135 12736 25135 12756 25136 12736 25136 12775 25136 12775 25137 12736 25137 11098 25137 12775 25138 11098 25138 12776 25138 12775 25139 12774 25139 12756 25139 12756 25140 12774 25140 12734 25140 12756 25141 12734 25141 12754 25141 12754 25142 12734 25142 12757 25142 12754 25143 12757 25143 12753 25143 12753 25144 12757 25144 12758 25144 12753 25145 12758 25145 12751 25145 12751 25146 12758 25146 12729 25146 12751 25147 12729 25147 12759 25147 12759 25148 12729 25148 12760 25148 12759 25149 12760 25149 12761 25149 12761 25150 12760 25150 12762 25150 12761 25151 12762 25151 12763 25151 12763 25152 12762 25152 12728 25152 12763 25153 12728 25153 12749 25153 12749 25154 12728 25154 12726 25154 12749 25155 12726 25155 12765 25155 12765 25156 12726 25156 12764 25156 12765 25157 12764 25157 12747 25157 12747 25158 12764 25158 12725 25158 12780 25159 11025 25159 12766 25159 12766 25160 11025 25160 12767 25160 12766 25161 12767 25161 12781 25161 12781 25162 12767 25162 12768 25162 12768 25163 12767 25163 12769 25163 12768 25164 12769 25164 12770 25164 12770 25165 12769 25165 12784 25165 12784 25166 12769 25166 12771 25166 12784 25167 12771 25167 12786 25167 12786 25168 12771 25168 12787 25168 12787 25169 12771 25169 12772 25169 12787 25170 12772 25170 12778 25170 11025 25171 12735 25171 12767 25171 12767 25172 12735 25172 12773 25172 12767 25173 12773 25173 12769 25173 12769 25174 12773 25174 12774 25174 12769 25175 12774 25175 12771 25175 12771 25176 12774 25176 12775 25176 12771 25177 12775 25177 12772 25177 12772 25178 12775 25178 12776 25178 12777 25179 12846 25179 12845 25179 11096 25180 12777 25180 12778 25180 12778 25181 12777 25181 12845 25181 12778 25182 12845 25182 12788 25182 12788 25183 12845 25183 12779 25183 12790 25184 12780 25184 10873 25184 10873 25185 12780 25185 12766 25185 10873 25186 12766 25186 10874 25186 10874 25187 12766 25187 12781 25187 10874 25188 12781 25188 12782 25188 12782 25189 12781 25189 12768 25189 12782 25190 12768 25190 10865 25190 10865 25191 12768 25191 12770 25191 10865 25192 12770 25192 10866 25192 10866 25193 12770 25193 12784 25193 10866 25194 12784 25194 12783 25194 12783 25195 12784 25195 12786 25195 12783 25196 12786 25196 12785 25196 12785 25197 12786 25197 12787 25197 12785 25198 12787 25198 12788 25198 12788 25199 12787 25199 12778 25199 11024 25200 12780 25200 12790 25200 10868 25201 11022 25201 12792 25201 10868 25202 12789 25202 11022 25202 11022 25203 12789 25203 12795 25203 11022 25204 12795 25204 11023 25204 12790 25205 12791 25205 11024 25205 11024 25206 12791 25206 10871 25206 11024 25207 10871 25207 12792 25207 12792 25208 10871 25208 12793 25208 12792 25209 12793 25209 10868 25209 12806 25210 12794 25210 10146 25210 11023 25211 12795 25211 10157 25211 10157 25212 12795 25212 10862 25212 10157 25213 10862 25213 12796 25213 12796 25214 10862 25214 12797 25214 12797 25215 10862 25215 10861 25215 12797 25216 10861 25216 10153 25216 10153 25217 10861 25217 10279 25217 10279 25218 10861 25218 12798 25218 10279 25219 12798 25219 12799 25219 10860 25220 10845 25220 12800 25220 12798 25221 10859 25221 12799 25221 12799 25222 10859 25222 10860 25222 12799 25223 10860 25223 10280 25223 10280 25224 10860 25224 12800 25224 12801 25225 10150 25225 12802 25225 12802 25226 10150 25226 12803 25226 12802 25227 12803 25227 10851 25227 10851 25228 12803 25228 10290 25228 10851 25229 10290 25229 10846 25229 10846 25230 10290 25230 10289 25230 10846 25231 10289 25231 12804 25231 12804 25232 10289 25232 12800 25232 12804 25233 12800 25233 12805 25233 12805 25234 12800 25234 10845 25234 12794 25235 12806 25235 10882 25235 10882 25236 12806 25236 10147 25236 10882 25237 10147 25237 10879 25237 10879 25238 10147 25238 10148 25238 10879 25239 10148 25239 10881 25239 10881 25240 10148 25240 10149 25240 10881 25241 10149 25241 12801 25241 12801 25242 10149 25242 10180 25242 12801 25243 10180 25243 10150 25243 12807 25244 12808 25244 11026 25244 10146 25245 12794 25245 11048 25245 11048 25246 12794 25246 12807 25246 11048 25247 12807 25247 11060 25247 11060 25248 12807 25248 11026 25248 12808 25249 12809 25249 11026 25249 11026 25250 12809 25250 11027 25250 12809 25251 12810 25251 11027 25251 11027 25252 12810 25252 12811 25252 12813 25253 12816 25253 12812 25253 12812 25254 10836 25254 12813 25254 12813 25255 10836 25255 12811 25255 12813 25256 12811 25256 12810 25256 10592 25257 12812 25257 12816 25257 12814 25258 10587 25258 10589 25258 12814 25259 10589 25259 12816 25259 12816 25260 10589 25260 12815 25260 12816 25261 12815 25261 10592 25261 10587 25262 12814 25262 12817 25262 12817 25263 12814 25263 10877 25263 12817 25264 10877 25264 10586 25264 10585 25265 12818 25265 10876 25265 10876 25266 12818 25266 10676 25266 10876 25267 10676 25267 10877 25267 10877 25268 10676 25268 12819 25268 10877 25269 12819 25269 10586 25269 10876 25270 12820 25270 10585 25270 10585 25271 12820 25271 12821 25271 10585 25272 12821 25272 12822 25272 12823 25273 12824 25273 12825 25273 12825 25274 12824 25274 10582 25274 12825 25275 10582 25275 12826 25275 12826 25276 10582 25276 12822 25276 12826 25277 12822 25277 10858 25277 10858 25278 12822 25278 12821 25278 10726 25279 10724 25279 12828 25279 12828 25280 10724 25280 12827 25280 12828 25281 12827 25281 12823 25281 12823 25282 12827 25282 10580 25282 12823 25283 10580 25283 12824 25283 10726 25284 12828 25284 12829 25284 12829 25285 12828 25285 10888 25285 12829 25286 10888 25286 10579 25286 10579 25287 10888 25287 10900 25287 10900 25288 10888 25288 12831 25288 10900 25289 12831 25289 12830 25289 12830 25290 12831 25290 12832 25290 12835 25291 12833 25291 12832 25291 12832 25292 12833 25292 12834 25292 12832 25293 12834 25293 12830 25293 12835 25294 10897 25294 12833 25294 12833 25295 10897 25295 12836 25295 12833 25296 12836 25296 12837 25296 12842 25297 12843 25297 10889 25297 10889 25298 12843 25298 12839 25298 10889 25299 12839 25299 12838 25299 12838 25300 12839 25300 12841 25300 12838 25301 12841 25301 12840 25301 12840 25302 12841 25302 12465 25302 12840 25303 12465 25303 12836 25303 12836 25304 12465 25304 12837 25304 12842 25305 10891 25305 12843 25305 12843 25306 10891 25306 12881 25306 12881 25307 12883 25307 12843 25307 12843 25308 12883 25308 12844 25308 12843 25309 12844 25309 13098 25309 12847 25310 12779 25310 12845 25310 12845 25311 12846 25311 12847 25311 12847 25312 12846 25312 13182 25312 12847 25313 13182 25313 11182 25313 12779 25314 12847 25314 10867 25314 10867 25315 12847 25315 12848 25315 10867 25316 12848 25316 12849 25316 11419 25317 11170 25317 12849 25317 12849 25318 11170 25318 10867 25318 11425 25319 12852 25319 11423 25319 11423 25320 12852 25320 12850 25320 11423 25321 12850 25321 12851 25321 12851 25322 12850 25322 11172 25322 12851 25323 11172 25323 11421 25323 11421 25324 11172 25324 11171 25324 11421 25325 11171 25325 11419 25325 11419 25326 11171 25326 11170 25326 12852 25327 11425 25327 11173 25327 11173 25328 11425 25328 12853 25328 11173 25329 12853 25329 11169 25329 11169 25330 12853 25330 11447 25330 11169 25331 11447 25331 11168 25331 11168 25332 11447 25332 12854 25332 11168 25333 12854 25333 12855 25333 12854 25334 11466 25334 12855 25334 12855 25335 11466 25335 12856 25335 12855 25336 12856 25336 11156 25336 11156 25337 12856 25337 11449 25337 11156 25338 11449 25338 12865 25338 12878 25339 12857 25339 11476 25339 11476 25340 12857 25340 12858 25340 11476 25341 12858 25341 12859 25341 12859 25342 12858 25342 11152 25342 12859 25343 11152 25343 12860 25343 12860 25344 11152 25344 12861 25344 12860 25345 12861 25345 12862 25345 12862 25346 12861 25346 11153 25346 12862 25347 11153 25347 11454 25347 11454 25348 11153 25348 12863 25348 11454 25349 12863 25349 12864 25349 12864 25350 12863 25350 12865 25350 12864 25351 12865 25351 11450 25351 11450 25352 12865 25352 11449 25352 11542 25353 12866 25353 11520 25353 11520 25354 12866 25354 12867 25354 11520 25355 12867 25355 11527 25355 11527 25356 12867 25356 11167 25356 11527 25357 11167 25357 11528 25357 11528 25358 11167 25358 11150 25358 11528 25359 11150 25359 12868 25359 12868 25360 11150 25360 12869 25360 12868 25361 12869 25361 11508 25361 11508 25362 12869 25362 12870 25362 11508 25363 12870 25363 12871 25363 12871 25364 12870 25364 12872 25364 12871 25365 12872 25365 11533 25365 11533 25366 12872 25366 11162 25366 11533 25367 11162 25367 12873 25367 12873 25368 11162 25368 11161 25368 12873 25369 11161 25369 12874 25369 12874 25370 11161 25370 11160 25370 12874 25371 11160 25371 11505 25371 11505 25372 11160 25372 11158 25372 11505 25373 11158 25373 12875 25373 12875 25374 11158 25374 12876 25374 12875 25375 12876 25375 11502 25375 11502 25376 12876 25376 12877 25376 11502 25377 12877 25377 11501 25377 11501 25378 12877 25378 11145 25378 11501 25379 11145 25379 12878 25379 12878 25380 11145 25380 12857 25380 11175 25381 12879 25381 11545 25381 11545 25382 12879 25382 11165 25382 11545 25383 11165 25383 11544 25383 11544 25384 11165 25384 11164 25384 11544 25385 11164 25385 11543 25385 11543 25386 11164 25386 12880 25386 11543 25387 12880 25387 11542 25387 11542 25388 12880 25388 12866 25388 11174 25389 10890 25389 11175 25389 11175 25390 10890 25390 12879 25390 12881 25391 10891 25391 10890 25391 12882 25392 11180 25392 13100 25392 11174 25393 11178 25393 10890 25393 10890 25394 11178 25394 12882 25394 10890 25395 12882 25395 12881 25395 12881 25396 12882 25396 13100 25396 12881 25397 13100 25397 12883 25397 12924 25398 12918 25398 12923 25398 9253 25399 12944 25399 12926 25399 10596 25400 12919 25400 12884 25400 12884 25401 12919 25401 12885 25401 12884 25402 12885 25402 10691 25402 10691 25403 12885 25403 12907 25403 10691 25404 12907 25404 12886 25404 12886 25405 12907 25405 12887 25405 12886 25406 12887 25406 10590 25406 10590 25407 12887 25407 12909 25407 10590 25408 12909 25408 12889 25408 12889 25409 12909 25409 12888 25409 12889 25410 12888 25410 10591 25410 12949 25411 10591 25411 12948 25411 12948 25412 10591 25412 12888 25412 12948 25413 12888 25413 12890 25413 12890 25414 12888 25414 12911 25414 9253 25415 12926 25415 12891 25415 12891 25416 12926 25416 12892 25416 12891 25417 12892 25417 9255 25417 9255 25418 12892 25418 12925 25418 9255 25419 12925 25419 12896 25419 12893 25420 12894 25420 12925 25420 12925 25421 12894 25421 12895 25421 12925 25422 12895 25422 12896 25422 12921 25423 12897 25423 12922 25423 12922 25424 12897 25424 12898 25424 12922 25425 12898 25425 12899 25425 12899 25426 12898 25426 12900 25426 12899 25427 12900 25427 12893 25427 12893 25428 12900 25428 9258 25428 12893 25429 9258 25429 12894 25429 12917 25430 9250 25430 9249 25430 9250 25431 12917 25431 12902 25431 12902 25432 12917 25432 12901 25432 12902 25433 12901 25433 12942 25433 12903 25434 12904 25434 12917 25434 12917 25435 12904 25435 12929 25435 12917 25436 12929 25436 12901 25436 12951 25437 12905 25437 12920 25437 12920 25438 12905 25438 12941 25438 12920 25439 12941 25439 12903 25439 12903 25440 12941 25440 12906 25440 12903 25441 12906 25441 12904 25441 12919 25442 12918 25442 12885 25442 12885 25443 12918 25443 12924 25443 12885 25444 12924 25444 12907 25444 12907 25445 12924 25445 12913 25445 12907 25446 12913 25446 12887 25446 12887 25447 12913 25447 12908 25447 12887 25448 12908 25448 12909 25448 12909 25449 12908 25449 12916 25449 12909 25450 12916 25450 12888 25450 12888 25451 12916 25451 12910 25451 12888 25452 12910 25452 12911 25452 12924 25453 12912 25453 12913 25453 12913 25454 12912 25454 12914 25454 12913 25455 12914 25455 12908 25455 12908 25456 12914 25456 12915 25456 12908 25457 12915 25457 12916 25457 12916 25458 12915 25458 12927 25458 12916 25459 12927 25459 12910 25459 9249 25460 12923 25460 12917 25460 12917 25461 12923 25461 12918 25461 12917 25462 12918 25462 12903 25462 12903 25463 12918 25463 12919 25463 12903 25464 12919 25464 12920 25464 12920 25465 12919 25465 10596 25465 12920 25466 10596 25466 12951 25466 9249 25467 12921 25467 12923 25467 12923 25468 12921 25468 12922 25468 12923 25469 12922 25469 12924 25469 12924 25470 12922 25470 12899 25470 12924 25471 12899 25471 12912 25471 12912 25472 12899 25472 12893 25472 12912 25473 12893 25473 12914 25473 12914 25474 12893 25474 12925 25474 12914 25475 12925 25475 12915 25475 12915 25476 12925 25476 12892 25476 12915 25477 12892 25477 12927 25477 12927 25478 12892 25478 12926 25478 12927 25479 12926 25479 12910 25479 12910 25480 12926 25480 12991 25480 12910 25481 12991 25481 12911 25481 12928 25482 12940 25482 12984 25482 12954 25483 12988 25483 12956 25483 12946 25484 12989 25484 12988 25484 12929 25485 12904 25485 12975 25485 12931 25486 12930 25486 12953 25486 12953 25487 12930 25487 12950 25487 12933 25488 10817 25488 12931 25488 12955 25489 12938 25489 10820 25489 10820 25490 10819 25490 12955 25490 12955 25491 10819 25491 12932 25491 12955 25492 12932 25492 12933 25492 12933 25493 12932 25493 10818 25493 12933 25494 10818 25494 10817 25494 12934 25495 12985 25495 12935 25495 12935 25496 12936 25496 12934 25496 12934 25497 12936 25497 12937 25497 12934 25498 12937 25498 12938 25498 12938 25499 12937 25499 10821 25499 12938 25500 10821 25500 10820 25500 10831 25501 12939 25501 12952 25501 12952 25502 12939 25502 12983 25502 12940 25503 12941 25503 12905 25503 12942 25504 12901 25504 12943 25504 12943 25505 12901 25505 12963 25505 12944 25506 9236 25506 12945 25506 12945 25507 9236 25507 12971 25507 12945 25508 12971 25508 12969 25508 12969 25509 12971 25509 12970 25509 12991 25510 12989 25510 12911 25510 12911 25511 12989 25511 12946 25511 12911 25512 12946 25512 12890 25512 12890 25513 12946 25513 12947 25513 12890 25514 12947 25514 12948 25514 12948 25515 12947 25515 12949 25515 12988 25516 12954 25516 12946 25516 12946 25517 12954 25517 12953 25517 12946 25518 12953 25518 12947 25518 12947 25519 12953 25519 12950 25519 12947 25520 12950 25520 12949 25520 12951 25521 10831 25521 12905 25521 12905 25522 10831 25522 12952 25522 12905 25523 12952 25523 12940 25523 12940 25524 12952 25524 12983 25524 12940 25525 12983 25525 12984 25525 12931 25526 12953 25526 12933 25526 12933 25527 12953 25527 12954 25527 12933 25528 12954 25528 12955 25528 12955 25529 12954 25529 12956 25529 12955 25530 12956 25530 12938 25530 12938 25531 12956 25531 12957 25531 12938 25532 12957 25532 12934 25532 12934 25533 12957 25533 12958 25533 12934 25534 12958 25534 12985 25534 12967 25535 12959 25535 12981 25535 12981 25536 12959 25536 9245 25536 12981 25537 9245 25537 12960 25537 9245 25538 12961 25538 12960 25538 12960 25539 12961 25539 9247 25539 12960 25540 9247 25540 12963 25540 12963 25541 9247 25541 12962 25541 12963 25542 12962 25542 12943 25542 12976 25543 9242 25543 12964 25543 9242 25544 9240 25544 12964 25544 12964 25545 9240 25545 12965 25545 12964 25546 12965 25546 12966 25546 12966 25547 12965 25547 9239 25547 12966 25548 9239 25548 12967 25548 12967 25549 9239 25549 9244 25549 12967 25550 9244 25550 12959 25550 12944 25551 12945 25551 12990 25551 12990 25552 12945 25552 12969 25552 12990 25553 12969 25553 12968 25553 12968 25554 12969 25554 12970 25554 12968 25555 12970 25555 12972 25555 9236 25556 9238 25556 12971 25556 12971 25557 9238 25557 12977 25557 12971 25558 12977 25558 12970 25558 12970 25559 12977 25559 12978 25559 12970 25560 12978 25560 12972 25560 12972 25561 12978 25561 12979 25561 12972 25562 12979 25562 12987 25562 12987 25563 12979 25563 12980 25563 12987 25564 12980 25564 12974 25564 12974 25565 12980 25565 12973 25565 12974 25566 12973 25566 12986 25566 12986 25567 12973 25567 12982 25567 12986 25568 12982 25568 12984 25568 12984 25569 12982 25569 12975 25569 12984 25570 12975 25570 12928 25570 12928 25571 12975 25571 12904 25571 12928 25572 12904 25572 12940 25572 12940 25573 12904 25573 12906 25573 12940 25574 12906 25574 12941 25574 9238 25575 12976 25575 12977 25575 12977 25576 12976 25576 12964 25576 12977 25577 12964 25577 12978 25577 12978 25578 12964 25578 12966 25578 12978 25579 12966 25579 12979 25579 12979 25580 12966 25580 12967 25580 12979 25581 12967 25581 12980 25581 12980 25582 12967 25582 12981 25582 12980 25583 12981 25583 12973 25583 12973 25584 12981 25584 12960 25584 12973 25585 12960 25585 12982 25585 12982 25586 12960 25586 12963 25586 12982 25587 12963 25587 12975 25587 12975 25588 12963 25588 12901 25588 12975 25589 12901 25589 12929 25589 12939 25590 12935 25590 12983 25590 12983 25591 12935 25591 12985 25591 12983 25592 12985 25592 12984 25592 12984 25593 12985 25593 12958 25593 12984 25594 12958 25594 12986 25594 12986 25595 12958 25595 12957 25595 12986 25596 12957 25596 12974 25596 12974 25597 12957 25597 12956 25597 12974 25598 12956 25598 12987 25598 12987 25599 12956 25599 12988 25599 12987 25600 12988 25600 12972 25600 12972 25601 12988 25601 12989 25601 12972 25602 12989 25602 12968 25602 12968 25603 12989 25603 12991 25603 12968 25604 12991 25604 12990 25604 12990 25605 12991 25605 12926 25605 12990 25606 12926 25606 12944 25606 13033 25607 13034 25607 13029 25607 11032 25608 13020 25608 12993 25608 11042 25609 11041 25609 13059 25609 13051 25610 13018 25610 11045 25610 11037 25611 11036 25611 12992 25611 12992 25612 11036 25612 11035 25612 11032 25613 12993 25613 11033 25613 11033 25614 12993 25614 12994 25614 11033 25615 12994 25615 11038 25615 13053 25616 13052 25616 11040 25616 13033 25617 13029 25617 13053 25617 13053 25618 13029 25618 12995 25618 13053 25619 12995 25619 13097 25619 12996 25620 12997 25620 12995 25620 12995 25621 12997 25621 13097 25621 9344 25622 12998 25622 12999 25622 12999 25623 12998 25623 13002 25623 12999 25624 13002 25624 13000 25624 13000 25625 13002 25625 13001 25625 13001 25626 13002 25626 13026 25626 13001 25627 13026 25627 9345 25627 13047 25628 9343 25628 9342 25628 9343 25629 13047 25629 13003 25629 13003 25630 13047 25630 13041 25630 13003 25631 13041 25631 13004 25631 13004 25632 13041 25632 13005 25632 13004 25633 13005 25633 13008 25633 13006 25634 9336 25634 13007 25634 13006 25635 13007 25635 13005 25635 13005 25636 13007 25636 9339 25636 13005 25637 9339 25637 13008 25637 9336 25638 13006 25638 13009 25638 13009 25639 13006 25639 13010 25639 13009 25640 13010 25640 9338 25640 9338 25641 13010 25641 13011 25641 13011 25642 13010 25642 13071 25642 13011 25643 13071 25643 13061 25643 13012 25644 13065 25644 13013 25644 13013 25645 13065 25645 13014 25645 13013 25646 13014 25646 13015 25646 13050 25647 13016 25647 13014 25647 13014 25648 13016 25648 13017 25648 13014 25649 13017 25649 13015 25649 11034 25650 13018 25650 13024 25650 13024 25651 13018 25651 13051 25651 13024 25652 13051 25652 13023 25652 13021 25653 13019 25653 13022 25653 13022 25654 13019 25654 12993 25654 13022 25655 12993 25655 12992 25655 12992 25656 12993 25656 13020 25656 12992 25657 13020 25657 11037 25657 13046 25658 13021 25658 13049 25658 13049 25659 13021 25659 13022 25659 13049 25660 13022 25660 13023 25660 13023 25661 13022 25661 12992 25661 13023 25662 12992 25662 13024 25662 13024 25663 12992 25663 11035 25663 13024 25664 11035 25664 11034 25664 9344 25665 13076 25665 12998 25665 12998 25666 13076 25666 13025 25666 12998 25667 13025 25667 13002 25667 13002 25668 13025 25668 13028 25668 13002 25669 13028 25669 13026 25669 9342 25670 9345 25670 13045 25670 13045 25671 9345 25671 13026 25671 13045 25672 13026 25672 13027 25672 13027 25673 13026 25673 13028 25673 13027 25674 13028 25674 12996 25674 12996 25675 13028 25675 13025 25675 12996 25676 13025 25676 12997 25676 12997 25677 13025 25677 13076 25677 13034 25678 13035 25678 13029 25678 13029 25679 13035 25679 13036 25679 13029 25680 13036 25680 12995 25680 12995 25681 13036 25681 13030 25681 12995 25682 13030 25682 12996 25682 12996 25683 13030 25683 13031 25683 12996 25684 13031 25684 13027 25684 13027 25685 13031 25685 13032 25685 13027 25686 13032 25686 13045 25686 13053 25687 11040 25687 13033 25687 13033 25688 11040 25688 11039 25688 13033 25689 11039 25689 13034 25689 13034 25690 11039 25690 11038 25690 13034 25691 11038 25691 13035 25691 13035 25692 11038 25692 12994 25692 13035 25693 12994 25693 13036 25693 13036 25694 12994 25694 12993 25694 13036 25695 12993 25695 13030 25695 13030 25696 12993 25696 13019 25696 13030 25697 13019 25697 13031 25697 13031 25698 13019 25698 13021 25698 13031 25699 13021 25699 13032 25699 13032 25700 13021 25700 13046 25700 13032 25701 13046 25701 13045 25701 13065 25702 13037 25702 13014 25702 13014 25703 13037 25703 13038 25703 13014 25704 13038 25704 13050 25704 13048 25705 13039 25705 13040 25705 13040 25706 13039 25706 13050 25706 13040 25707 13050 25707 13042 25707 13042 25708 13050 25708 13038 25708 13042 25709 13038 25709 13043 25709 13043 25710 13038 25710 13037 25710 13043 25711 13037 25711 13044 25711 13047 25712 13048 25712 13041 25712 13041 25713 13048 25713 13040 25713 13041 25714 13040 25714 13005 25714 13005 25715 13040 25715 13042 25715 13005 25716 13042 25716 13006 25716 13006 25717 13042 25717 13043 25717 13006 25718 13043 25718 13010 25718 13010 25719 13043 25719 13044 25719 13010 25720 13044 25720 13071 25720 9342 25721 13045 25721 13047 25721 13047 25722 13045 25722 13046 25722 13047 25723 13046 25723 13048 25723 13048 25724 13046 25724 13049 25724 13048 25725 13049 25725 13039 25725 13039 25726 13049 25726 13023 25726 13039 25727 13023 25727 13050 25727 13050 25728 13023 25728 13051 25728 13050 25729 13051 25729 13016 25729 13016 25730 13051 25730 11045 25730 13016 25731 11045 25731 13017 25731 13017 25732 11045 25732 11044 25732 13017 25733 11044 25733 13015 25733 13015 25734 11044 25734 11042 25734 13015 25735 11042 25735 13013 25735 13013 25736 11042 25736 13059 25736 13013 25737 13059 25737 13012 25737 13037 25738 13065 25738 13060 25738 10145 25739 13052 25739 13053 25739 10145 25740 13053 25740 13054 25740 13053 25741 13055 25741 13054 25741 13054 25742 13055 25742 13062 25742 13054 25743 13062 25743 10144 25743 10144 25744 13062 25744 13063 25744 10144 25745 13063 25745 13056 25745 13056 25746 13063 25746 13064 25746 13056 25747 13064 25747 13057 25747 13057 25748 13064 25748 13088 25748 13057 25749 13088 25749 10143 25749 11041 25750 13058 25750 13059 25750 13059 25751 13058 25751 13077 25751 13059 25752 13077 25752 13012 25752 13037 25753 13060 25753 13044 25753 13070 25754 13061 25754 13072 25754 13072 25755 13061 25755 13071 25755 13053 25756 13097 25756 13055 25756 13055 25757 13097 25757 13095 25757 13055 25758 13095 25758 13062 25758 13062 25759 13095 25759 13094 25759 13062 25760 13094 25760 13063 25760 13063 25761 13094 25761 13092 25761 13063 25762 13092 25762 13064 25762 13064 25763 13092 25763 13090 25763 13064 25764 13090 25764 13088 25764 13065 25765 13012 25765 13060 25765 13060 25766 13012 25766 13077 25766 13060 25767 13077 25767 13078 25767 13079 25768 13066 25768 13067 25768 13067 25769 13066 25769 13068 25769 13068 25770 9334 25770 13067 25770 13067 25771 9334 25771 13069 25771 13067 25772 13069 25772 13072 25772 13072 25773 13069 25773 9333 25773 13072 25774 9333 25774 13070 25774 13071 25775 13044 25775 13072 25775 13072 25776 13044 25776 13060 25776 13072 25777 13060 25777 13067 25777 13067 25778 13060 25778 13078 25778 13067 25779 13078 25779 13079 25779 13083 25780 13082 25780 13073 25780 13073 25781 13082 25781 13074 25781 13073 25782 13074 25782 9328 25782 9328 25783 13074 25783 13075 25783 9344 25784 13075 25784 13076 25784 13076 25785 13075 25785 13074 25785 13076 25786 13074 25786 12997 25786 13058 25787 13086 25787 13077 25787 13077 25788 13086 25788 13087 25788 13077 25789 13087 25789 13078 25789 13078 25790 13087 25790 13089 25790 13078 25791 13089 25791 13079 25791 13079 25792 13089 25792 13091 25792 13079 25793 13091 25793 13085 25793 13085 25794 13091 25794 13080 25794 13085 25795 13080 25795 13081 25795 13081 25796 13080 25796 13093 25796 13081 25797 13093 25797 13082 25797 13082 25798 13093 25798 13096 25798 13082 25799 13096 25799 13074 25799 13074 25800 13096 25800 12997 25800 13083 25801 9326 25801 13082 25801 13082 25802 9326 25802 13084 25802 13082 25803 13084 25803 13081 25803 13081 25804 13084 25804 9329 25804 13081 25805 9329 25805 13085 25805 13085 25806 9329 25806 9330 25806 13085 25807 9330 25807 13079 25807 13079 25808 9330 25808 9331 25808 13079 25809 9331 25809 13066 25809 13086 25810 10143 25810 13087 25810 13087 25811 10143 25811 13088 25811 13087 25812 13088 25812 13089 25812 13089 25813 13088 25813 13090 25813 13089 25814 13090 25814 13091 25814 13091 25815 13090 25815 13092 25815 13091 25816 13092 25816 13080 25816 13080 25817 13092 25817 13094 25817 13080 25818 13094 25818 13093 25818 13093 25819 13094 25819 13095 25819 13093 25820 13095 25820 13096 25820 13096 25821 13095 25821 13097 25821 13096 25822 13097 25822 12997 25822 13100 25823 11180 25823 11177 25823 10924 25824 13098 25824 12844 25824 11176 25825 13099 25825 11177 25825 11177 25826 13099 25826 10924 25826 11177 25827 10924 25827 13100 25827 13100 25828 10924 25828 12844 25828 13100 25829 12844 25829 12883 25829 13099 25830 11176 25830 13101 25830 13101 25831 11176 25831 13102 25831 13101 25832 13102 25832 10925 25832 10925 25833 13102 25833 13103 25833 13103 25834 13102 25834 11207 25834 13103 25835 11207 25835 13104 25835 13104 25836 11207 25836 11208 25836 13104 25837 11208 25837 13105 25837 13105 25838 11208 25838 13106 25838 13105 25839 13106 25839 13107 25839 13107 25840 13106 25840 13108 25840 13107 25841 13108 25841 10935 25841 10935 25842 13108 25842 13109 25842 10935 25843 13109 25843 10934 25843 10934 25844 13109 25844 13110 25844 13110 25845 13109 25845 11212 25845 13110 25846 11212 25846 13111 25846 13111 25847 11212 25847 11236 25847 13111 25848 11236 25848 13112 25848 10929 25849 13113 25849 13114 25849 13116 25850 13112 25850 11236 25850 11236 25851 13115 25851 13116 25851 13116 25852 13115 25852 11238 25852 13116 25853 11238 25853 13117 25853 13117 25854 11238 25854 11239 25854 13117 25855 11239 25855 13113 25855 13113 25856 11239 25856 11235 25856 13113 25857 11235 25857 13114 25857 10929 25858 13114 25858 10941 25858 10941 25859 13114 25859 13119 25859 10941 25860 13119 25860 13118 25860 13119 25861 11232 25861 13118 25861 13118 25862 11232 25862 11230 25862 13118 25863 11230 25863 10937 25863 11227 25864 10939 25864 11228 25864 11228 25865 10939 25865 10938 25865 11228 25866 10938 25866 13120 25866 13120 25867 10938 25867 10937 25867 13120 25868 10937 25868 13121 25868 13121 25869 10937 25869 11230 25869 11217 25870 13126 25870 10942 25870 10942 25871 13122 25871 11217 25871 11217 25872 13122 25872 13123 25872 11217 25873 13123 25873 11226 25873 11226 25874 13123 25874 13124 25874 11226 25875 13124 25875 13125 25875 13125 25876 13124 25876 10939 25876 13125 25877 10939 25877 11227 25877 10945 25878 10942 25878 13126 25878 11222 25879 13127 25879 11215 25879 11215 25880 13127 25880 10945 25880 11215 25881 10945 25881 13128 25881 13128 25882 10945 25882 13126 25882 13129 25883 13131 25883 11221 25883 11221 25884 13131 25884 13130 25884 11221 25885 13130 25885 11222 25885 11222 25886 13130 25886 10948 25886 11222 25887 10948 25887 13127 25887 10950 25888 13131 25888 13132 25888 13132 25889 13131 25889 13129 25889 10950 25890 13132 25890 10968 25890 10968 25891 13132 25891 11241 25891 10968 25892 11241 25892 10965 25892 10965 25893 11241 25893 11249 25893 10965 25894 11249 25894 10963 25894 10963 25895 11249 25895 13133 25895 10963 25896 13133 25896 13137 25896 13137 25897 13133 25897 13138 25897 11255 25898 13134 25898 10970 25898 11255 25899 10970 25899 13135 25899 13135 25900 10970 25900 10971 25900 13135 25901 10971 25901 13136 25901 13136 25902 10971 25902 13137 25902 13136 25903 13137 25903 13138 25903 11253 25904 13139 25904 11255 25904 11255 25905 13139 25905 13134 25905 13140 25906 10983 25906 13142 25906 13140 25907 13142 25907 13141 25907 13141 25908 13142 25908 13143 25908 13141 25909 13143 25909 11251 25909 11251 25910 13143 25910 13139 25910 11251 25911 13139 25911 11253 25911 10983 25912 13140 25912 13144 25912 13144 25913 13140 25913 11248 25913 13144 25914 11248 25914 10980 25914 10980 25915 11248 25915 13145 25915 10980 25916 13145 25916 13146 25916 13146 25917 13145 25917 11242 25917 13146 25918 11242 25918 13147 25918 13147 25919 11242 25919 11243 25919 10985 25920 13147 25920 13148 25920 13148 25921 13147 25921 11243 25921 13156 25922 13155 25922 13149 25922 13149 25923 13155 25923 10988 25923 13149 25924 10988 25924 11272 25924 11272 25925 10988 25925 13150 25925 11272 25926 13150 25926 13151 25926 13151 25927 13150 25927 13152 25927 13151 25928 13152 25928 13153 25928 13153 25929 13152 25929 10986 25929 13153 25930 10986 25930 13148 25930 13148 25931 10986 25931 10985 25931 11075 25932 13154 25932 11269 25932 11269 25933 13154 25933 13155 25933 11269 25934 13155 25934 13156 25934 11075 25935 11269 25935 11073 25935 11073 25936 11269 25936 11268 25936 11073 25937 11268 25937 11074 25937 11074 25938 11268 25938 11266 25938 11074 25939 11266 25939 11081 25939 11266 25940 11264 25940 11081 25940 11081 25941 11264 25941 13157 25941 11081 25942 13157 25942 13158 25942 13157 25943 13159 25943 13158 25943 13158 25944 13159 25944 13160 25944 13158 25945 13160 25945 11077 25945 11077 25946 13160 25946 13161 25946 11077 25947 13161 25947 11078 25947 11078 25948 13161 25948 13162 25948 11078 25949 13162 25949 13163 25949 13163 25950 13162 25950 13164 25950 13163 25951 13164 25951 11079 25951 13164 25952 13165 25952 11079 25952 11079 25953 13165 25953 13167 25953 11079 25954 13167 25954 13166 25954 13166 25955 13167 25955 11258 25955 13166 25956 11258 25956 11085 25956 11085 25957 11258 25957 11357 25957 11085 25958 11357 25958 13168 25958 11090 25959 11089 25959 11359 25959 13168 25960 11357 25960 13169 25960 13169 25961 11357 25961 13172 25961 11359 25962 11089 25962 13171 25962 11089 25963 13170 25963 13171 25963 13171 25964 13170 25964 13173 25964 13171 25965 13173 25965 13172 25965 13172 25966 13173 25966 11088 25966 13172 25967 11088 25967 13169 25967 11090 25968 11359 25968 13174 25968 13174 25969 11359 25969 11360 25969 13174 25970 11360 25970 13175 25970 13175 25971 11360 25971 13176 25971 13175 25972 13176 25972 11093 25972 11093 25973 13176 25973 13178 25973 11093 25974 13178 25974 13177 25974 13177 25975 13178 25975 13179 25975 13177 25976 13179 25976 11094 25976 11094 25977 13179 25977 13180 25977 11094 25978 13180 25978 11095 25978 11095 25979 13180 25979 11364 25979 11095 25980 11364 25980 11099 25980 11099 25981 11364 25981 13181 25981 11099 25982 13181 25982 11097 25982 11182 25983 13182 25983 13183 25983 13182 25984 12846 25984 13183 25984 13183 25985 12846 25985 12777 25985 13183 25986 12777 25986 11096 25986 11097 25987 13181 25987 13183 25987 13183 25988 13181 25988 11181 25988 13183 25989 11181 25989 11182 25989 13184 25990 13185 25990 9982 25990 9982 25991 13185 25991 13315 25991 9982 25992 13315 25992 13186 25992 13186 25993 13315 25993 13187 25993 13186 25994 13187 25994 12073 25994 12073 25995 12072 25995 13186 25995 13186 25996 12072 25996 12071 25996 13186 25997 12071 25997 13189 25997 12071 25998 13188 25998 13189 25998 13189 25999 13188 25999 12076 25999 13189 26000 12076 26000 13190 26000 12074 26001 11246 26001 13191 26001 13191 26002 11246 26002 13192 26002 13191 26003 13192 26003 13193 26003 13193 26004 13192 26004 13194 26004 13193 26005 13194 26005 12075 26005 12075 26006 13194 26006 12064 26006 12075 26007 12064 26007 12076 26007 12076 26008 12064 26008 13190 26008 11628 26009 11247 26009 12074 26009 12074 26010 11247 26010 11246 26010 13201 26011 11254 26011 13195 26011 13195 26012 11254 26012 11250 26012 13195 26013 11250 26013 13196 26013 13196 26014 11250 26014 13197 26014 13196 26015 13197 26015 13198 26015 13198 26016 13197 26016 13199 26016 13198 26017 13199 26017 11628 26017 11628 26018 13199 26018 11247 26018 13200 26019 13208 26019 13201 26019 13201 26020 13208 26020 11254 26020 11630 26021 13202 26021 13203 26021 13203 26022 13202 26022 13204 26022 13203 26023 13204 26023 13205 26023 13205 26024 13204 26024 13207 26024 13205 26025 13207 26025 13206 26025 13206 26026 13207 26026 11252 26026 13206 26027 11252 26027 13200 26027 13200 26028 11252 26028 13208 26028 12102 26029 12117 26029 11630 26029 11630 26030 12117 26030 13202 26030 13209 26031 13215 26031 12106 26031 12106 26032 13215 26032 12111 26032 12106 26033 12111 26033 13210 26033 13210 26034 12111 26034 13211 26034 13210 26035 13211 26035 13212 26035 13212 26036 13211 26036 13213 26036 13212 26037 13213 26037 12102 26037 12102 26038 13213 26038 12117 26038 12104 26039 13214 26039 12103 26039 12103 26040 13214 26040 9826 26040 12103 26041 9826 26041 12105 26041 12105 26042 9826 26042 13215 26042 12105 26043 13215 26043 13209 26043 13214 26044 12104 26044 13338 26044 13214 26045 13338 26045 13216 26045 13216 26046 13338 26046 13326 26046 13326 26047 13327 26047 13216 26047 13216 26048 13327 26048 13217 26048 13216 26049 13217 26049 13328 26049 10416 26050 13250 26050 10170 26050 10170 26051 13250 26051 13218 26051 10170 26052 13218 26052 10171 26052 10171 26053 13218 26053 13219 26053 10171 26054 13219 26054 10169 26054 10169 26055 13219 26055 13220 26055 10169 26056 13220 26056 13221 26056 13220 26057 13222 26057 13221 26057 13221 26058 13222 26058 9306 26058 13221 26059 9306 26059 13223 26059 13223 26060 9306 26060 13226 26060 13227 26061 13229 26061 9308 26061 9308 26062 13229 26062 10102 26062 9308 26063 10102 26063 9309 26063 9309 26064 10102 26064 13224 26064 9309 26065 13224 26065 13226 26065 13226 26066 13224 26066 13225 26066 13226 26067 13225 26067 13223 26067 13238 26068 9312 26068 13240 26068 13227 26069 13228 26069 13229 26069 13229 26070 13228 26070 13230 26070 13229 26071 13230 26071 13232 26071 13232 26072 13230 26072 13231 26072 13232 26073 13231 26073 13233 26073 13233 26074 13231 26074 9311 26074 13233 26075 9311 26075 13234 26075 13234 26076 9311 26076 13235 26076 13234 26077 13235 26077 13236 26077 13236 26078 13235 26078 13237 26078 13236 26079 13237 26079 13239 26079 13239 26080 13237 26080 13238 26080 13239 26081 13238 26081 10165 26081 10165 26082 13238 26082 13240 26082 10406 26083 9316 26083 9315 26083 13240 26084 9312 26084 13241 26084 13240 26085 13241 26085 13242 26085 13242 26086 13241 26086 9314 26086 13242 26087 9314 26087 10406 26087 10406 26088 9314 26088 9303 26088 10406 26089 9303 26089 9316 26089 9318 26090 13243 26090 9317 26090 9317 26091 13243 26091 10410 26091 9317 26092 10410 26092 13244 26092 13244 26093 10410 26093 10408 26093 13244 26094 10408 26094 9315 26094 9315 26095 10408 26095 10407 26095 9315 26096 10407 26096 10406 26096 9324 26097 13245 26097 13246 26097 13246 26098 13245 26098 10412 26098 13246 26099 10412 26099 9320 26099 9320 26100 10412 26100 13247 26100 9320 26101 13247 26101 9318 26101 9318 26102 13247 26102 10411 26102 9318 26103 10411 26103 13243 26103 9324 26104 13248 26104 13245 26104 13245 26105 13248 26105 9322 26105 13245 26106 9322 26106 10414 26106 10414 26107 9322 26107 9321 26107 10414 26108 9321 26108 10415 26108 9321 26109 13249 26109 10415 26109 10415 26110 13249 26110 13250 26110 10415 26111 13250 26111 10416 26111 10643 26112 9260 26112 13252 26112 10643 26113 13252 26113 13251 26113 13251 26114 13252 26114 9259 26114 13251 26115 9259 26115 13253 26115 9259 26116 9261 26116 13253 26116 13253 26117 9261 26117 13254 26117 13253 26118 13254 26118 13255 26118 13255 26119 13254 26119 9263 26119 13255 26120 9263 26120 10561 26120 10561 26121 9263 26121 13256 26121 10561 26122 13256 26122 13258 26122 13256 26123 13257 26123 13258 26123 13258 26124 13257 26124 13259 26124 13258 26125 13259 26125 10562 26125 10562 26126 13259 26126 13260 26126 10562 26127 13260 26127 13261 26127 13261 26128 13260 26128 13262 26128 13261 26129 13262 26129 13263 26129 13263 26130 13262 26130 9266 26130 13263 26131 9266 26131 13265 26131 13265 26132 9266 26132 13264 26132 13267 26133 10564 26133 13264 26133 13264 26134 10564 26134 10563 26134 13264 26135 10563 26135 13265 26135 9269 26136 13286 26136 13266 26136 13266 26137 13286 26137 10566 26137 13266 26138 10566 26138 13267 26138 13267 26139 10566 26139 10565 26139 13267 26140 10565 26140 10564 26140 13268 26141 9260 26141 10643 26141 13268 26142 10643 26142 13269 26142 13269 26143 10643 26143 13270 26143 13269 26144 13270 26144 13271 26144 13271 26145 13270 26145 13276 26145 13271 26146 13276 26146 13272 26146 13273 26147 13274 26147 13276 26147 13276 26148 13274 26148 13275 26148 13276 26149 13275 26149 13272 26149 13280 26150 9275 26150 13273 26150 13273 26151 9275 26151 9278 26151 9278 26152 9277 26152 13273 26152 13273 26153 9277 26153 13277 26153 13273 26154 13277 26154 13274 26154 9270 26155 9273 26155 13282 26155 13282 26156 9273 26156 9276 26156 13282 26157 9276 26157 13278 26157 13278 26158 9276 26158 13279 26158 13278 26159 13279 26159 13280 26159 13280 26160 13279 26160 13281 26160 13280 26161 13281 26161 9275 26161 9270 26162 13282 26162 13284 26162 13284 26163 13282 26163 13283 26163 13284 26164 13283 26164 9272 26164 9272 26165 13283 26165 13287 26165 9272 26166 13287 26166 13285 26166 13286 26167 9269 26167 13287 26167 13287 26168 9269 26168 13288 26168 13287 26169 13288 26169 13285 26169 13315 26170 13313 26170 13187 26170 13187 26171 13313 26171 12073 26171 12073 26172 13313 26172 13289 26172 13289 26173 13313 26173 13312 26173 13289 26174 13312 26174 13290 26174 13290 26175 13312 26175 13291 26175 13290 26176 13291 26176 13294 26176 12097 26177 12096 26177 13292 26177 13292 26178 12096 26178 12083 26178 13292 26179 12083 26179 13293 26179 13293 26180 12083 26180 13294 26180 13293 26181 13294 26181 13309 26181 13309 26182 13294 26182 13291 26182 13308 26183 13348 26183 13307 26183 9966 26184 9964 26184 13336 26184 13184 26185 13296 26185 13295 26185 13295 26186 13296 26186 13298 26186 13295 26187 13298 26187 13297 26187 13297 26188 13298 26188 13299 26188 13297 26189 13299 26189 13300 26189 13300 26190 13299 26190 13301 26190 13300 26191 13301 26191 13305 26191 13305 26192 13301 26192 9985 26192 13305 26193 9985 26193 13302 26193 13302 26194 9985 26194 9966 26194 13302 26195 9966 26195 13303 26195 13303 26196 9966 26196 13336 26196 13303 26197 13336 26197 13348 26197 13348 26198 13308 26198 13303 26198 13303 26199 13308 26199 13304 26199 13303 26200 13304 26200 13302 26200 13302 26201 13304 26201 13310 26201 13302 26202 13310 26202 13305 26202 13305 26203 13310 26203 13311 26203 13305 26204 13311 26204 13300 26204 13300 26205 13311 26205 13306 26205 13300 26206 13306 26206 13297 26206 13297 26207 13306 26207 13314 26207 13297 26208 13314 26208 13295 26208 13295 26209 13314 26209 13185 26209 13295 26210 13185 26210 13184 26210 13322 26211 12097 26211 13307 26211 13307 26212 12097 26212 13292 26212 13307 26213 13292 26213 13308 26213 13308 26214 13292 26214 13293 26214 13308 26215 13293 26215 13304 26215 13304 26216 13293 26216 13309 26216 13304 26217 13309 26217 13310 26217 13310 26218 13309 26218 13291 26218 13310 26219 13291 26219 13311 26219 13311 26220 13291 26220 13312 26220 13311 26221 13312 26221 13306 26221 13306 26222 13312 26222 13313 26222 13306 26223 13313 26223 13314 26223 13314 26224 13313 26224 13315 26224 13314 26225 13315 26225 13185 26225 13337 26226 13316 26226 13323 26226 13319 26227 13317 26227 13325 26227 13317 26228 13319 26228 13318 26228 13318 26229 13319 26229 13320 26229 13318 26230 13320 26230 13321 26230 13321 26231 13320 26231 13322 26231 13321 26232 13322 26232 13307 26232 13323 26233 13316 26233 13324 26233 13324 26234 13316 26234 12101 26234 13324 26235 12101 26235 13325 26235 13325 26236 12101 26236 12100 26236 13325 26237 12100 26237 13319 26237 13339 26238 13326 26238 13338 26238 13217 26239 13327 26239 13342 26239 13342 26240 13327 26240 13326 26240 13329 26241 13328 26241 13217 26241 13217 26242 13342 26242 13329 26242 13329 26243 13342 26243 13343 26243 13329 26244 13343 26244 9822 26244 9822 26245 13343 26245 13345 26245 9822 26246 13345 26246 13330 26246 13330 26247 13345 26247 13332 26247 13330 26248 13332 26248 13331 26248 13331 26249 13332 26249 13333 26249 13331 26250 13333 26250 9816 26250 9816 26251 13333 26251 13334 26251 9816 26252 13334 26252 13335 26252 13335 26253 13334 26253 13336 26253 13335 26254 13336 26254 9964 26254 12104 26255 13337 26255 13338 26255 13338 26256 13337 26256 13323 26256 13338 26257 13323 26257 13339 26257 13339 26258 13323 26258 13324 26258 13339 26259 13324 26259 13340 26259 13340 26260 13324 26260 13325 26260 13340 26261 13325 26261 13341 26261 13341 26262 13325 26262 13317 26262 13341 26263 13317 26263 13344 26263 13344 26264 13317 26264 13318 26264 13344 26265 13318 26265 13346 26265 13346 26266 13318 26266 13321 26266 13346 26267 13321 26267 13347 26267 13347 26268 13321 26268 13307 26268 13347 26269 13307 26269 13348 26269 13326 26270 13339 26270 13342 26270 13342 26271 13339 26271 13340 26271 13342 26272 13340 26272 13343 26272 13343 26273 13340 26273 13341 26273 13343 26274 13341 26274 13345 26274 13345 26275 13341 26275 13344 26275 13345 26276 13344 26276 13332 26276 13332 26277 13344 26277 13346 26277 13332 26278 13346 26278 13333 26278 13333 26279 13346 26279 13347 26279 13333 26280 13347 26280 13334 26280 13334 26281 13347 26281 13348 26281 13334 26282 13348 26282 13336 26282 11414 26283 11133 26283 13355 26283 13355 26284 11133 26284 11134 26284 11413 26285 13349 26285 13350 26285 11413 26286 13350 26286 13351 26286 13351 26287 13350 26287 13352 26287 13351 26288 13352 26288 11412 26288 11412 26289 13352 26289 13353 26289 11412 26290 13353 26290 13354 26290 13354 26291 13353 26291 11133 26291 13354 26292 11133 26292 11414 26292 13355 26293 11134 26293 13356 26293 13355 26294 13356 26294 11415 26294 11415 26295 13356 26295 13357 26295 11415 26296 13357 26296 11409 26296 11409 26297 13357 26297 11191 26297 11409 26298 11191 26298 13358 26298 13358 26299 11191 26299 13359 26299 13358 26300 13359 26300 11410 26300 11417 26301 11141 26301 11413 26301 11413 26302 11141 26302 13349 26302 13364 26303 13365 26303 13359 26303 13359 26304 13365 26304 11410 26304 13370 26305 13371 26305 13360 26305 13370 26306 13360 26306 11416 26306 11416 26307 13360 26307 13362 26307 11416 26308 13362 26308 13361 26308 13361 26309 13362 26309 11139 26309 13361 26310 11139 26310 13363 26310 13363 26311 11139 26311 11141 26311 13363 26312 11141 26312 11417 26312 13365 26313 13364 26313 13366 26313 13365 26314 13366 26314 11411 26314 11411 26315 13366 26315 11184 26315 11411 26316 11184 26316 13367 26316 13367 26317 11184 26317 11185 26317 13367 26318 11185 26318 11408 26318 11408 26319 11185 26319 13369 26319 11408 26320 13369 26320 13368 26320 13368 26321 13369 26321 13370 26321 13370 26322 13369 26322 13371 26322 13372 26323 9773 26323 13401 26323 9781 26324 13373 26324 13390 26324 13395 26325 13378 26325 13374 26325 13375 26326 13376 26326 13395 26326 13395 26327 13376 26327 13377 26327 13395 26328 13377 26328 13378 26328 9782 26329 9776 26329 13379 26329 13379 26330 9776 26330 9786 26330 10004 26331 10008 26331 13380 26331 13380 26332 10008 26332 10013 26332 13391 26333 13392 26333 9778 26333 9778 26334 13392 26334 13380 26334 9778 26335 13380 26335 13381 26335 13381 26336 13380 26336 10013 26336 13381 26337 10013 26337 10012 26337 13397 26338 10005 26338 13389 26338 10005 26339 13397 26339 13382 26339 10003 26340 10002 26340 13383 26340 13383 26341 10002 26341 13384 26341 13383 26342 13384 26342 13396 26342 10003 26343 13383 26343 10001 26343 10001 26344 13383 26344 13398 26344 10001 26345 13398 26345 9767 26345 9767 26346 13398 26346 13386 26346 9767 26347 13386 26347 13385 26347 13385 26348 13386 26348 13400 26348 13385 26349 13400 26349 9771 26349 13372 26350 13401 26350 13387 26350 13387 26351 13401 26351 13394 26351 13387 26352 13394 26352 13388 26352 13393 26353 13399 26353 13392 26353 13392 26354 13399 26354 13397 26354 13392 26355 13397 26355 13380 26355 13380 26356 13397 26356 13389 26356 13380 26357 13389 26357 10004 26357 13373 26358 9782 26358 13390 26358 13390 26359 9782 26359 13379 26359 13390 26360 13379 26360 13395 26360 13395 26361 13379 26361 9786 26361 13395 26362 9786 26362 13375 26362 13391 26363 9781 26363 13392 26363 13392 26364 9781 26364 13390 26364 13392 26365 13390 26365 13393 26365 13393 26366 13390 26366 13395 26366 13393 26367 13395 26367 13394 26367 13394 26368 13395 26368 13374 26368 13394 26369 13374 26369 13388 26369 13396 26370 13382 26370 13383 26370 13383 26371 13382 26371 13397 26371 13383 26372 13397 26372 13398 26372 13398 26373 13397 26373 13399 26373 13398 26374 13399 26374 13386 26374 13386 26375 13399 26375 13393 26375 13386 26376 13393 26376 13400 26376 13400 26377 13393 26377 13394 26377 13400 26378 13394 26378 9771 26378 9771 26379 13394 26379 13401 26379 9771 26380 13401 26380 9772 26380 9772 26381 13401 26381 9773 26381 9838 26382 13402 26382 13421 26382 9830 26383 13404 26383 13403 26383 13403 26384 13404 26384 9835 26384 13403 26385 9835 26385 9834 26385 9838 26386 13422 26386 9840 26386 9840 26387 13422 26387 13403 26387 9840 26388 13403 26388 9833 26388 9833 26389 13403 26389 9834 26389 13408 26390 13405 26390 13427 26390 13427 26391 13405 26391 13406 26391 13427 26392 13406 26392 13426 26392 13407 26393 9829 26393 13428 26393 13428 26394 9829 26394 9897 26394 13428 26395 9897 26395 13408 26395 13408 26396 9897 26396 13409 26396 13408 26397 13409 26397 13405 26397 13431 26398 13432 26398 13411 26398 13411 26399 13432 26399 9807 26399 9807 26400 13410 26400 13411 26400 13411 26401 13410 26401 13412 26401 13411 26402 13412 26402 13413 26402 13413 26403 13414 26403 13411 26403 13411 26404 13414 26404 9812 26404 13411 26405 9812 26405 13428 26405 13428 26406 9812 26406 9828 26406 13428 26407 9828 26407 13407 26407 9810 26408 13430 26408 9811 26408 9811 26409 13430 26409 13415 26409 9811 26410 13415 26410 9806 26410 9806 26411 13415 26411 12113 26411 13424 26412 13416 26412 13425 26412 13417 26413 12109 26413 13424 26413 13417 26414 13424 26414 13418 26414 12109 26415 12108 26415 13424 26415 13424 26416 12108 26416 12107 26416 13424 26417 12107 26417 13416 26417 13418 26418 13424 26418 13419 26418 13419 26419 13424 26419 13423 26419 13419 26420 13423 26420 13420 26420 9800 26421 9798 26421 13423 26421 13423 26422 9798 26422 9801 26422 13423 26423 9801 26423 13420 26423 9838 26424 13421 26424 13422 26424 13422 26425 13421 26425 9800 26425 13422 26426 9800 26426 13429 26426 13429 26427 9800 26427 13423 26427 13429 26428 13423 26428 13430 26428 13430 26429 13423 26429 13424 26429 13430 26430 13424 26430 13415 26430 13415 26431 13424 26431 13425 26431 13415 26432 13425 26432 12113 26432 13426 26433 9830 26433 13427 26433 13427 26434 9830 26434 13403 26434 13427 26435 13403 26435 13408 26435 13408 26436 13403 26436 13422 26436 13408 26437 13422 26437 13428 26437 13428 26438 13422 26438 13429 26438 13428 26439 13429 26439 13411 26439 13411 26440 13429 26440 13430 26440 13411 26441 13430 26441 13431 26441 13431 26442 13430 26442 9810 26442 13431 26443 9810 26443 13432 26443 13433 26444 13434 26444 13435 26444 13433 26445 13435 26445 13436 26445 13436 26446 13435 26446 13450 26446 13436 26447 13450 26447 13451 26447 9857 26448 13437 26448 13440 26448 13440 26449 13437 26449 13438 26449 9858 26450 9857 26450 13439 26450 13439 26451 9857 26451 13440 26451 13439 26452 13440 26452 9860 26452 9860 26453 13440 26453 13441 26453 13444 26454 13442 26454 13441 26454 13441 26455 13442 26455 9862 26455 13441 26456 9862 26456 9860 26456 9847 26457 9846 26457 13441 26457 13441 26458 9846 26458 13443 26458 13441 26459 13443 26459 13444 26459 9848 26460 13448 26460 9849 26460 9849 26461 13448 26461 13449 26461 9849 26462 13449 26462 9789 26462 9789 26463 13449 26463 9790 26463 9790 26464 13449 26464 13450 26464 9790 26465 13450 26465 13447 26465 13434 26466 9902 26466 13435 26466 13435 26467 9902 26467 9901 26467 13435 26468 9901 26468 13450 26468 13450 26469 9901 26469 13445 26469 13450 26470 13445 26470 9935 26470 9935 26471 9946 26471 13450 26471 13450 26472 9946 26472 13446 26472 13450 26473 13446 26473 13447 26473 9848 26474 9847 26474 13448 26474 13448 26475 9847 26475 13441 26475 13448 26476 13441 26476 13449 26476 13449 26477 13441 26477 13440 26477 13449 26478 13440 26478 13450 26478 13450 26479 13440 26479 13438 26479 13450 26480 13438 26480 13451 26480 13453 26481 10352 26481 10375 26481 13452 26482 13453 26482 10376 26482 10376 26483 13453 26483 13454 26483 10376 26484 13454 26484 10379 26484 10379 26485 13454 26485 13461 26485 10379 26486 13461 26486 13459 26486 13455 26487 13457 26487 10373 26487 10373 26488 13457 26488 13456 26488 10373 26489 13456 26489 10374 26489 13453 26490 10375 26490 13454 26490 13454 26491 10375 26491 10374 26491 13454 26492 10374 26492 13461 26492 13461 26493 10374 26493 13456 26493 13461 26494 13456 26494 10398 26494 10398 26495 13456 26495 13457 26495 10398 26496 13457 26496 10399 26496 10528 26497 13458 26497 13464 26497 13459 26498 13461 26498 13460 26498 13460 26499 13461 26499 13462 26499 13460 26500 13462 26500 10530 26500 10530 26501 13462 26501 13463 26501 10530 26502 13463 26502 13458 26502 13458 26503 13463 26503 10505 26503 13458 26504 10505 26504 13464 26504 10525 26505 10524 26505 13473 26505 13464 26506 10508 26506 10528 26506 10528 26507 10508 26507 13465 26507 10528 26508 13465 26508 13466 26508 13466 26509 13465 26509 13467 26509 13466 26510 13467 26510 10522 26510 10522 26511 13467 26511 10509 26511 10522 26512 10509 26512 13468 26512 13468 26513 10509 26513 13470 26513 13468 26514 13470 26514 13469 26514 13469 26515 13470 26515 13471 26515 13469 26516 13471 26516 10524 26516 10524 26517 13471 26517 13472 26517 10524 26518 13472 26518 13473 26518 13473 26519 10511 26519 10525 26519 10525 26520 10511 26520 10512 26520 10525 26521 10512 26521 13474 26521 13474 26522 10512 26522 13475 26522 13474 26523 13475 26523 13476 26523 13476 26524 13475 26524 10514 26524 13476 26525 10514 26525 10531 26525 10531 26526 10514 26526 13477 26526 10531 26527 13477 26527 13478 26527 13478 26528 13477 26528 13479 26528 13478 26529 13479 26529 10517 26529 10531 26530 13484 26530 13476 26530 13476 26531 13484 26531 13483 26531 13476 26532 13483 26532 10493 26532 10493 26533 13483 26533 13481 26533 10515 26534 13481 26534 13480 26534 13480 26535 13481 26535 13483 26535 13480 26536 13483 26536 13482 26536 13482 26537 13483 26537 13484 26537 13485 26538 10386 26538 10402 26538 10401 26539 13485 26539 10400 26539 10400 26540 13485 26540 13486 26540 10400 26541 13486 26541 10397 26541 10397 26542 13486 26542 10392 26542 10397 26543 10392 26543 13487 26543 13488 26544 13492 26544 10396 26544 10396 26545 13492 26545 13491 26545 10396 26546 13491 26546 13489 26546 13485 26547 10402 26547 13486 26547 13486 26548 10402 26548 13489 26548 13486 26549 13489 26549 10392 26549 10392 26550 13489 26550 13491 26550 10392 26551 13491 26551 13490 26551 13490 26552 13491 26552 13492 26552 13490 26553 13492 26553 10393 26553 13487 26554 10392 26554 13493 26554 13493 26555 10392 26555 13494 26555 13493 26556 13494 26556 10483 26556 10483 26557 13494 26557 13495 26557 10483 26558 13495 26558 13496 26558 13496 26559 13495 26559 10464 26559 13496 26560 10464 26560 10482 26560 10482 26561 10464 26561 13497 26561 10482 26562 13497 26562 10481 26562 13497 26563 10467 26563 10481 26563 10481 26564 10467 26564 10468 26564 10481 26565 10468 26565 13498 26565 10468 26566 10463 26566 13498 26566 13498 26567 10463 26567 10461 26567 13498 26568 10461 26568 13500 26568 10461 26569 13499 26569 13500 26569 13500 26570 13499 26570 10459 26570 13500 26571 10459 26571 10479 26571 10459 26572 13501 26572 10479 26572 10479 26573 13501 26573 10457 26573 10479 26574 10457 26574 10478 26574 10457 26575 10455 26575 10478 26575 10478 26576 10455 26576 13502 26576 10478 26577 13502 26577 10477 26577 10477 26578 13502 26578 10471 26578 10472 26579 10471 26579 10473 26579 10473 26580 10471 26580 13502 26580 10473 26581 13502 26581 10485 26581 10485 26582 13502 26582 10455 26582 10485 26583 10455 26583 10474 26583 10474 26584 10455 26584 13503 26584 10474 26585 13503 26585 10475 26585 10475 26586 13503 26586 10450 26586 10475 26587 10450 26587 10476 26587 13544 26588 13532 26588 13540 26588 13712 26589 13710 26589 13531 26589 13504 26590 13505 26590 13817 26590 13817 26591 13505 26591 13506 26591 13817 26592 13506 26592 13507 26592 13507 26593 13506 26593 13509 26593 13507 26594 13509 26594 13508 26594 13691 26595 13690 26595 13526 26595 13526 26596 13690 26596 13547 26596 13508 26597 13509 26597 13825 26597 13825 26598 13509 26598 13680 26598 13825 26599 13680 26599 13824 26599 13824 26600 13680 26600 13693 26600 13824 26601 13693 26601 13526 26601 13526 26602 13693 26602 13692 26602 13526 26603 13692 26603 13691 26603 13690 26604 13688 26604 13547 26604 13547 26605 13688 26605 13687 26605 13547 26606 13687 26606 13510 26606 13510 26607 13687 26607 13686 26607 13510 26608 13686 26608 13504 26608 13504 26609 13686 26609 13683 26609 13504 26610 13683 26610 13505 26610 13736 26611 13511 26611 13818 26611 13818 26612 13511 26612 13504 26612 13515 26613 13512 26613 13547 26613 13547 26614 13512 26614 13517 26614 13512 26615 13740 26615 13517 26615 13517 26616 13740 26616 13739 26616 13517 26617 13739 26617 13516 26617 13516 26618 13739 26618 13513 26618 13516 26619 13513 26619 13818 26619 13818 26620 13513 26620 13514 26620 13818 26621 13514 26621 13736 26621 13511 26622 13734 26622 13504 26622 13504 26623 13734 26623 13746 26623 13504 26624 13746 26624 13510 26624 13510 26625 13746 26625 13745 26625 13510 26626 13745 26626 13547 26626 13547 26627 13745 26627 13744 26627 13547 26628 13744 26628 13515 26628 13818 26629 13821 26629 13785 26629 13785 26630 13821 26630 13786 26630 13786 26631 13821 26631 13822 26631 13786 26632 13822 26632 13788 26632 13788 26633 13822 26633 13823 26633 13788 26634 13823 26634 13520 26634 13785 26635 13783 26635 13818 26635 13818 26636 13783 26636 13782 26636 13818 26637 13782 26637 13516 26637 13516 26638 13782 26638 13519 26638 13516 26639 13519 26639 13517 26639 13791 26640 13540 26640 13518 26640 13518 26641 13540 26641 13517 26641 13518 26642 13517 26642 13792 26642 13792 26643 13517 26643 13519 26643 13520 26644 13541 26644 13789 26644 13789 26645 13541 26645 13540 26645 13789 26646 13540 26646 13521 26646 13521 26647 13540 26647 13791 26647 13823 26648 13522 26648 13542 26648 13531 26649 13710 26649 13547 26649 13710 26650 13523 26650 13547 26650 13547 26651 13523 26651 13524 26651 13547 26652 13524 26652 13526 26652 13526 26653 13524 26653 13525 26653 13525 26654 13527 26654 13526 26654 13526 26655 13527 26655 13718 26655 13526 26656 13718 26656 13828 26656 13828 26657 13718 26657 13528 26657 13828 26658 13528 26658 13835 26658 13835 26659 13528 26659 13529 26659 13835 26660 13529 26660 13834 26660 13834 26661 13529 26661 13715 26661 13834 26662 13715 26662 13558 26662 13558 26663 13715 26663 13530 26663 13558 26664 13530 26664 13531 26664 13531 26665 13530 26665 13714 26665 13531 26666 13714 26666 13712 26666 13540 26667 13532 26667 13533 26667 13554 26668 13536 26668 13832 26668 13832 26669 13536 26669 13537 26669 13537 26670 13534 26670 13832 26670 13832 26671 13534 26671 13811 26671 13832 26672 13811 26672 13830 26672 13830 26673 13811 26673 13535 26673 13830 26674 13535 26674 13532 26674 13532 26675 13535 26675 13810 26675 13532 26676 13810 26676 13533 26676 13545 26677 13816 26677 13536 26677 13536 26678 13816 26678 13815 26678 13536 26679 13815 26679 13537 26679 13546 26680 13517 26680 13538 26680 13538 26681 13517 26681 13540 26681 13538 26682 13540 26682 13539 26682 13539 26683 13540 26683 13533 26683 13520 26684 13823 26684 13541 26684 13541 26685 13823 26685 13542 26685 13541 26686 13542 26686 13540 26686 13540 26687 13542 26687 13543 26687 13540 26688 13543 26688 13544 26688 13768 26689 13766 26689 13536 26689 13536 26690 13766 26690 13517 26690 13536 26691 13517 26691 13545 26691 13545 26692 13517 26692 13546 26692 13766 26693 13765 26693 13517 26693 13517 26694 13765 26694 13548 26694 13517 26695 13548 26695 13547 26695 13547 26696 13548 26696 13764 26696 13764 26697 13762 26697 13547 26697 13547 26698 13762 26698 13549 26698 13547 26699 13549 26699 13531 26699 13531 26700 13549 26700 13550 26700 13531 26701 13550 26701 13551 26701 13551 26702 13552 26702 13531 26702 13531 26703 13552 26703 13553 26703 13531 26704 13553 26704 13536 26704 13536 26705 13553 26705 13769 26705 13536 26706 13769 26706 13768 26706 13554 26707 13555 26707 13536 26707 13536 26708 13555 26708 13556 26708 13536 26709 13556 26709 13531 26709 13531 26710 13556 26710 13557 26710 13531 26711 13557 26711 13558 26711 13849 26712 13560 26712 13559 26712 13559 26713 13560 26713 13827 26713 13560 26714 13849 26714 13561 26714 13560 26715 13561 26715 13562 26715 13562 26716 13561 26716 13563 26716 13562 26717 13563 26717 13564 26717 13564 26718 13563 26718 13842 26718 13564 26719 13842 26719 13831 26719 13831 26720 13842 26720 13565 26720 13831 26721 13565 26721 13836 26721 13566 26722 13567 26722 13565 26722 13565 26723 13567 26723 13836 26723 13567 26724 13566 26724 13839 26724 13567 26725 13839 26725 13833 26725 13833 26726 13839 26726 13838 26726 13833 26727 13838 26727 13568 26727 13568 26728 13838 26728 13570 26728 13568 26729 13570 26729 13569 26729 13569 26730 13570 26730 13571 26730 13569 26731 13571 26731 13572 26731 13846 26732 13829 26732 13571 26732 13571 26733 13829 26733 13572 26733 13829 26734 13846 26734 13573 26734 13829 26735 13573 26735 13574 26735 13574 26736 13573 26736 13853 26736 13574 26737 13853 26737 13826 26737 13826 26738 13853 26738 13851 26738 13826 26739 13851 26739 13575 26739 13575 26740 13851 26740 13576 26740 13575 26741 13576 26741 13819 26741 13857 26742 13820 26742 13576 26742 13576 26743 13820 26743 13819 26743 13820 26744 13857 26744 13577 26744 13820 26745 13577 26745 13578 26745 13578 26746 13577 26746 13580 26746 13578 26747 13580 26747 13579 26747 13579 26748 13580 26748 13581 26748 13579 26749 13581 26749 13582 26749 13582 26750 13581 26750 13559 26750 13582 26751 13559 26751 13827 26751 13707 26752 13583 26752 13847 26752 13841 26753 13843 26753 13584 26753 13807 26754 13585 26754 13584 26754 13619 26755 13586 26755 13876 26755 13648 26756 13594 26756 13587 26756 13587 26757 13594 26757 13881 26757 13587 26758 13881 26758 13879 26758 13879 26759 13588 26759 13587 26759 13587 26760 13588 26760 13589 26760 13587 26761 13589 26761 13619 26761 13619 26762 13589 26762 13590 26762 13619 26763 13590 26763 13586 26763 13595 26764 13653 26764 13591 26764 13876 26765 13592 26765 13619 26765 13619 26766 13592 26766 13874 26766 13619 26767 13874 26767 13591 26767 13591 26768 13874 26768 13896 26768 13591 26769 13896 26769 13595 26769 13884 26770 13888 26770 13656 26770 13656 26771 13888 26771 13593 26771 13656 26772 13593 26772 13648 26772 13648 26773 13593 26773 13882 26773 13648 26774 13882 26774 13594 26774 13595 26775 13891 26775 13653 26775 13653 26776 13891 26776 13596 26776 13653 26777 13596 26777 13894 26777 13654 26778 13597 26778 13656 26778 13656 26779 13597 26779 13883 26779 13656 26780 13883 26780 13884 26780 13721 26781 13598 26781 13719 26781 13719 26782 13598 26782 13599 26782 13719 26783 13599 26783 13666 26783 13632 26784 13725 26784 13664 26784 13721 26785 13722 26785 13598 26785 13598 26786 13722 26786 13723 26786 13598 26787 13723 26787 13631 26787 13725 26788 13726 26788 13664 26788 13664 26789 13726 26789 13729 26789 13664 26790 13729 26790 13653 26790 13653 26791 13729 26791 13600 26791 13653 26792 13600 26792 13591 26792 13591 26793 13600 26793 13730 26793 13591 26794 13730 26794 13731 26794 13603 26795 13607 26795 13601 26795 13601 26796 13607 26796 13656 26796 13760 26797 13747 26797 13648 26797 13648 26798 13747 26798 13602 26798 13648 26799 13602 26799 13656 26799 13656 26800 13602 26800 13749 26800 13656 26801 13749 26801 13601 26801 13603 26802 13753 26802 13584 26802 13753 26803 13604 26803 13584 26803 13584 26804 13604 26804 13755 26804 13584 26805 13755 26805 13646 26805 13646 26806 13755 26806 13605 26806 13646 26807 13605 26807 13644 26807 13644 26808 13605 26808 13606 26808 13644 26809 13606 26809 13759 26809 13603 26810 13584 26810 13607 26810 13607 26811 13584 26811 13585 26811 13607 26812 13585 26812 13795 26812 13800 26813 13610 26813 13662 26813 13662 26814 13610 26814 13845 26814 13662 26815 13845 26815 13848 26815 13795 26816 13796 26816 13607 26816 13607 26817 13796 26817 13608 26817 13607 26818 13608 26818 13662 26818 13662 26819 13608 26819 13798 26819 13662 26820 13798 26820 13800 26820 13800 26821 13609 26821 13610 26821 13610 26822 13609 26822 13611 26822 13610 26823 13611 26823 13844 26823 13844 26824 13611 26824 13612 26824 13844 26825 13612 26825 13843 26825 13843 26826 13612 26826 13805 26826 13843 26827 13805 26827 13584 26827 13584 26828 13805 26828 13806 26828 13584 26829 13806 26829 13807 26829 13587 26830 13698 26830 13701 26830 13847 26831 13583 26831 13613 26831 13650 26832 13702 26832 13649 26832 13649 26833 13702 26833 13703 26833 13649 26834 13703 26834 13614 26834 13583 26835 13695 26835 13613 26835 13613 26836 13695 26836 13696 26836 13613 26837 13696 26837 13652 26837 13703 26838 13615 26838 13614 26838 13614 26839 13615 26839 13706 26839 13614 26840 13706 26840 13616 26840 13616 26841 13706 26841 13707 26841 13616 26842 13707 26842 13617 26842 13617 26843 13707 26843 13847 26843 13621 26844 13620 26844 13618 26844 13671 26845 13673 26845 13619 26845 13619 26846 13673 26846 13675 26846 13619 26847 13675 26847 13629 26847 13620 26848 13621 26848 13670 26848 13670 26849 13621 26849 13622 26849 13670 26850 13622 26850 13623 26850 13622 26851 13852 26851 13623 26851 13623 26852 13852 26852 13624 26852 13623 26853 13624 26853 13625 26853 13625 26854 13624 26854 13626 26854 13625 26855 13626 26855 13667 26855 13667 26856 13626 26856 13627 26856 13667 26857 13627 26857 13628 26857 13628 26858 13627 26858 13651 26858 13628 26859 13651 26859 13677 26859 13677 26860 13651 26860 13629 26860 13776 26861 13630 26861 13663 26861 13780 26862 13633 26862 13664 26862 13664 26863 13633 26863 13631 26863 13664 26864 13631 26864 13632 26864 13632 26865 13631 26865 13723 26865 13633 26866 13634 26866 13631 26866 13631 26867 13634 26867 13635 26867 13631 26868 13635 26868 13636 26868 13636 26869 13635 26869 13637 26869 13636 26870 13637 26870 13856 26870 13856 26871 13637 26871 13638 26871 13856 26872 13638 26872 13855 26872 13855 26873 13638 26873 13774 26873 13855 26874 13774 26874 13642 26874 13630 26875 13639 26875 13663 26875 13663 26876 13639 26876 13640 26876 13663 26877 13640 26877 13664 26877 13664 26878 13640 26878 13641 26878 13664 26879 13641 26879 13780 26879 13774 26880 13776 26880 13642 26880 13642 26881 13776 26881 13663 26881 13642 26882 13663 26882 13854 26882 13854 26883 13663 26883 13850 26883 13614 26884 13840 26884 13649 26884 13649 26885 13840 26885 13643 26885 13649 26886 13643 26886 13644 26886 13644 26887 13643 26887 13645 26887 13644 26888 13645 26888 13646 26888 13646 26889 13645 26889 13647 26889 13646 26890 13647 26890 13584 26890 13584 26891 13647 26891 13837 26891 13584 26892 13837 26892 13841 26892 13759 26893 13760 26893 13644 26893 13644 26894 13760 26894 13648 26894 13644 26895 13648 26895 13649 26895 13649 26896 13648 26896 13587 26896 13649 26897 13587 26897 13650 26897 13650 26898 13587 26898 13701 26898 13629 26899 13651 26899 13619 26899 13619 26900 13651 26900 13613 26900 13619 26901 13613 26901 13587 26901 13587 26902 13613 26902 13652 26902 13587 26903 13652 26903 13698 26903 13655 26904 13911 26904 13653 26904 13653 26905 13911 26905 13913 26905 13894 26906 13654 26906 13653 26906 13653 26907 13654 26907 13656 26907 13653 26908 13656 26908 13655 26908 13655 26909 13656 26909 13918 26909 13914 26910 13915 26910 13656 26910 13656 26911 13915 26911 13917 26911 13656 26912 13917 26912 13918 26912 13664 26913 13658 26913 13906 26913 13913 26914 13657 26914 13653 26914 13653 26915 13657 26915 13910 26915 13653 26916 13910 26916 13664 26916 13664 26917 13910 26917 13908 26917 13664 26918 13908 26918 13658 26918 13901 26919 13659 26919 13607 26919 13607 26920 13659 26920 13898 26920 13607 26921 13898 26921 13656 26921 13656 26922 13898 26922 13660 26922 13656 26923 13660 26923 13914 26923 13665 26924 13903 26924 13607 26924 13607 26925 13903 26925 13661 26925 13607 26926 13661 26926 13901 26926 13848 26927 13850 26927 13662 26927 13662 26928 13850 26928 13663 26928 13662 26929 13663 26929 13607 26929 13607 26930 13663 26930 13664 26930 13607 26931 13664 26931 13665 26931 13665 26932 13664 26932 13906 26932 13731 26933 13666 26933 13591 26933 13591 26934 13666 26934 13599 26934 13591 26935 13599 26935 13619 26935 13619 26936 13599 26936 13621 26936 13619 26937 13621 26937 13671 26937 13671 26938 13621 26938 13618 26938 13667 26939 13668 26939 13625 26939 13625 26940 13668 26940 13669 26940 13625 26941 13669 26941 13623 26941 13623 26942 13669 26942 13679 26942 13623 26943 13679 26943 13670 26943 13670 26944 13679 26944 13681 26944 13670 26945 13681 26945 13620 26945 13620 26946 13681 26946 13682 26946 13620 26947 13682 26947 13618 26947 13618 26948 13682 26948 13684 26948 13618 26949 13684 26949 13671 26949 13671 26950 13684 26950 13685 26950 13671 26951 13685 26951 13673 26951 13673 26952 13685 26952 13672 26952 13673 26953 13672 26953 13675 26953 13675 26954 13672 26954 13674 26954 13675 26955 13674 26955 13629 26955 13629 26956 13674 26956 13676 26956 13629 26957 13676 26957 13677 26957 13677 26958 13676 26958 13689 26958 13677 26959 13689 26959 13628 26959 13628 26960 13689 26960 13678 26960 13628 26961 13678 26961 13667 26961 13667 26962 13678 26962 13668 26962 13669 26963 13680 26963 13679 26963 13679 26964 13680 26964 13509 26964 13679 26965 13509 26965 13681 26965 13681 26966 13509 26966 13506 26966 13681 26967 13506 26967 13682 26967 13682 26968 13506 26968 13505 26968 13682 26969 13505 26969 13684 26969 13684 26970 13505 26970 13683 26970 13684 26971 13683 26971 13685 26971 13685 26972 13683 26972 13686 26972 13685 26973 13686 26973 13672 26973 13672 26974 13686 26974 13687 26974 13672 26975 13687 26975 13674 26975 13674 26976 13687 26976 13688 26976 13674 26977 13688 26977 13676 26977 13676 26978 13688 26978 13690 26978 13676 26979 13690 26979 13689 26979 13689 26980 13690 26980 13691 26980 13689 26981 13691 26981 13678 26981 13678 26982 13691 26982 13692 26982 13678 26983 13692 26983 13668 26983 13668 26984 13692 26984 13693 26984 13668 26985 13693 26985 13669 26985 13669 26986 13693 26986 13680 26986 13583 26987 13694 26987 13695 26987 13695 26988 13694 26988 13717 26988 13695 26989 13717 26989 13696 26989 13696 26990 13717 26990 13697 26990 13696 26991 13697 26991 13652 26991 13652 26992 13697 26992 13699 26992 13652 26993 13699 26993 13698 26993 13698 26994 13699 26994 13700 26994 13698 26995 13700 26995 13701 26995 13701 26996 13700 26996 13708 26996 13701 26997 13708 26997 13650 26997 13650 26998 13708 26998 13709 26998 13650 26999 13709 26999 13702 26999 13702 27000 13709 27000 13711 27000 13702 27001 13711 27001 13703 27001 13703 27002 13711 27002 13713 27002 13703 27003 13713 27003 13615 27003 13615 27004 13713 27004 13704 27004 13615 27005 13704 27005 13706 27005 13706 27006 13704 27006 13705 27006 13706 27007 13705 27007 13707 27007 13707 27008 13705 27008 13716 27008 13707 27009 13716 27009 13583 27009 13583 27010 13716 27010 13694 27010 13717 27011 13718 27011 13697 27011 13697 27012 13718 27012 13527 27012 13697 27013 13527 27013 13699 27013 13699 27014 13527 27014 13525 27014 13699 27015 13525 27015 13700 27015 13700 27016 13525 27016 13524 27016 13700 27017 13524 27017 13708 27017 13708 27018 13524 27018 13523 27018 13708 27019 13523 27019 13709 27019 13709 27020 13523 27020 13710 27020 13709 27021 13710 27021 13711 27021 13711 27022 13710 27022 13712 27022 13711 27023 13712 27023 13713 27023 13713 27024 13712 27024 13714 27024 13713 27025 13714 27025 13704 27025 13704 27026 13714 27026 13530 27026 13704 27027 13530 27027 13705 27027 13705 27028 13530 27028 13715 27028 13705 27029 13715 27029 13716 27029 13716 27030 13715 27030 13529 27030 13716 27031 13529 27031 13694 27031 13694 27032 13529 27032 13528 27032 13694 27033 13528 27033 13717 27033 13717 27034 13528 27034 13718 27034 13666 27035 13720 27035 13719 27035 13719 27036 13720 27036 13732 27036 13719 27037 13732 27037 13721 27037 13721 27038 13732 27038 13733 27038 13721 27039 13733 27039 13722 27039 13722 27040 13733 27040 13735 27040 13722 27041 13735 27041 13723 27041 13723 27042 13735 27042 13724 27042 13723 27043 13724 27043 13632 27043 13632 27044 13724 27044 13737 27044 13632 27045 13737 27045 13725 27045 13725 27046 13737 27046 13738 27046 13725 27047 13738 27047 13726 27047 13726 27048 13738 27048 13727 27048 13726 27049 13727 27049 13729 27049 13729 27050 13727 27050 13728 27050 13729 27051 13728 27051 13600 27051 13600 27052 13728 27052 13741 27052 13600 27053 13741 27053 13730 27053 13730 27054 13741 27054 13742 27054 13730 27055 13742 27055 13731 27055 13731 27056 13742 27056 13743 27056 13731 27057 13743 27057 13666 27057 13666 27058 13743 27058 13720 27058 13732 27059 13746 27059 13733 27059 13733 27060 13746 27060 13734 27060 13733 27061 13734 27061 13735 27061 13735 27062 13734 27062 13511 27062 13735 27063 13511 27063 13724 27063 13724 27064 13511 27064 13736 27064 13724 27065 13736 27065 13737 27065 13737 27066 13736 27066 13514 27066 13737 27067 13514 27067 13738 27067 13738 27068 13514 27068 13513 27068 13738 27069 13513 27069 13727 27069 13727 27070 13513 27070 13739 27070 13727 27071 13739 27071 13728 27071 13728 27072 13739 27072 13740 27072 13728 27073 13740 27073 13741 27073 13741 27074 13740 27074 13512 27074 13741 27075 13512 27075 13742 27075 13742 27076 13512 27076 13515 27076 13742 27077 13515 27077 13743 27077 13743 27078 13515 27078 13744 27078 13743 27079 13744 27079 13720 27079 13720 27080 13744 27080 13745 27080 13720 27081 13745 27081 13732 27081 13732 27082 13745 27082 13746 27082 13760 27083 13761 27083 13747 27083 13747 27084 13761 27084 13748 27084 13747 27085 13748 27085 13602 27085 13602 27086 13748 27086 13750 27086 13602 27087 13750 27087 13749 27087 13749 27088 13750 27088 13763 27088 13749 27089 13763 27089 13601 27089 13601 27090 13763 27090 13751 27090 13601 27091 13751 27091 13603 27091 13603 27092 13751 27092 13752 27092 13603 27093 13752 27093 13753 27093 13753 27094 13752 27094 13754 27094 13753 27095 13754 27095 13604 27095 13604 27096 13754 27096 13767 27096 13604 27097 13767 27097 13755 27097 13755 27098 13767 27098 13756 27098 13755 27099 13756 27099 13605 27099 13605 27100 13756 27100 13757 27100 13605 27101 13757 27101 13606 27101 13606 27102 13757 27102 13758 27102 13606 27103 13758 27103 13759 27103 13759 27104 13758 27104 13770 27104 13759 27105 13770 27105 13760 27105 13760 27106 13770 27106 13761 27106 13748 27107 13549 27107 13750 27107 13750 27108 13549 27108 13762 27108 13750 27109 13762 27109 13763 27109 13763 27110 13762 27110 13764 27110 13763 27111 13764 27111 13751 27111 13751 27112 13764 27112 13548 27112 13751 27113 13548 27113 13752 27113 13752 27114 13548 27114 13765 27114 13752 27115 13765 27115 13754 27115 13754 27116 13765 27116 13766 27116 13754 27117 13766 27117 13767 27117 13767 27118 13766 27118 13768 27118 13767 27119 13768 27119 13756 27119 13756 27120 13768 27120 13769 27120 13756 27121 13769 27121 13757 27121 13757 27122 13769 27122 13553 27122 13757 27123 13553 27123 13758 27123 13758 27124 13553 27124 13552 27124 13758 27125 13552 27125 13770 27125 13770 27126 13552 27126 13551 27126 13770 27127 13551 27127 13761 27127 13761 27128 13551 27128 13550 27128 13761 27129 13550 27129 13748 27129 13748 27130 13550 27130 13549 27130 13633 27131 13771 27131 13634 27131 13634 27132 13771 27132 13793 27132 13634 27133 13793 27133 13635 27133 13635 27134 13793 27134 13772 27134 13635 27135 13772 27135 13637 27135 13637 27136 13772 27136 13773 27136 13637 27137 13773 27137 13638 27137 13638 27138 13773 27138 13784 27138 13638 27139 13784 27139 13774 27139 13774 27140 13784 27140 13787 27140 13774 27141 13787 27141 13776 27141 13776 27142 13787 27142 13775 27142 13776 27143 13775 27143 13630 27143 13630 27144 13775 27144 13777 27144 13630 27145 13777 27145 13639 27145 13639 27146 13777 27146 13778 27146 13639 27147 13778 27147 13640 27147 13640 27148 13778 27148 13790 27148 13640 27149 13790 27149 13641 27149 13641 27150 13790 27150 13779 27150 13641 27151 13779 27151 13780 27151 13780 27152 13779 27152 13781 27152 13780 27153 13781 27153 13633 27153 13633 27154 13781 27154 13771 27154 13793 27155 13782 27155 13772 27155 13772 27156 13782 27156 13783 27156 13772 27157 13783 27157 13773 27157 13773 27158 13783 27158 13785 27158 13773 27159 13785 27159 13784 27159 13784 27160 13785 27160 13786 27160 13784 27161 13786 27161 13787 27161 13787 27162 13786 27162 13788 27162 13787 27163 13788 27163 13775 27163 13775 27164 13788 27164 13520 27164 13775 27165 13520 27165 13777 27165 13777 27166 13520 27166 13789 27166 13777 27167 13789 27167 13778 27167 13778 27168 13789 27168 13521 27168 13778 27169 13521 27169 13790 27169 13790 27170 13521 27170 13791 27170 13790 27171 13791 27171 13779 27171 13779 27172 13791 27172 13518 27172 13779 27173 13518 27173 13781 27173 13781 27174 13518 27174 13792 27174 13781 27175 13792 27175 13771 27175 13771 27176 13792 27176 13519 27176 13771 27177 13519 27177 13793 27177 13793 27178 13519 27178 13782 27178 13585 27179 13794 27179 13795 27179 13795 27180 13794 27180 13808 27180 13795 27181 13808 27181 13796 27181 13796 27182 13808 27182 13809 27182 13796 27183 13809 27183 13608 27183 13608 27184 13809 27184 13797 27184 13608 27185 13797 27185 13798 27185 13798 27186 13797 27186 13799 27186 13798 27187 13799 27187 13800 27187 13800 27188 13799 27188 13801 27188 13800 27189 13801 27189 13609 27189 13609 27190 13801 27190 13802 27190 13609 27191 13802 27191 13611 27191 13611 27192 13802 27192 13803 27192 13611 27193 13803 27193 13612 27193 13612 27194 13803 27194 13804 27194 13612 27195 13804 27195 13805 27195 13805 27196 13804 27196 13812 27196 13805 27197 13812 27197 13806 27197 13806 27198 13812 27198 13813 27198 13806 27199 13813 27199 13807 27199 13807 27200 13813 27200 13814 27200 13807 27201 13814 27201 13585 27201 13585 27202 13814 27202 13794 27202 13808 27203 13545 27203 13809 27203 13809 27204 13545 27204 13546 27204 13809 27205 13546 27205 13797 27205 13797 27206 13546 27206 13538 27206 13797 27207 13538 27207 13799 27207 13799 27208 13538 27208 13539 27208 13799 27209 13539 27209 13801 27209 13801 27210 13539 27210 13533 27210 13801 27211 13533 27211 13802 27211 13802 27212 13533 27212 13810 27212 13802 27213 13810 27213 13803 27213 13803 27214 13810 27214 13535 27214 13803 27215 13535 27215 13804 27215 13804 27216 13535 27216 13811 27216 13804 27217 13811 27217 13812 27217 13812 27218 13811 27218 13534 27218 13812 27219 13534 27219 13813 27219 13813 27220 13534 27220 13537 27220 13813 27221 13537 27221 13814 27221 13814 27222 13537 27222 13815 27222 13814 27223 13815 27223 13794 27223 13794 27224 13815 27224 13816 27224 13794 27225 13816 27225 13808 27225 13808 27226 13816 27226 13545 27226 13504 27227 13817 27227 13819 27227 13504 27228 13819 27228 13818 27228 13818 27229 13819 27229 13820 27229 13818 27230 13820 27230 13821 27230 13821 27231 13820 27231 13578 27231 13821 27232 13578 27232 13822 27232 13822 27233 13578 27233 13579 27233 13822 27234 13579 27234 13823 27234 13823 27235 13579 27235 13582 27235 13823 27236 13582 27236 13522 27236 13522 27237 13582 27237 13827 27237 13522 27238 13827 27238 13542 27238 13824 27239 13829 27239 13574 27239 13824 27240 13574 27240 13825 27240 13825 27241 13574 27241 13826 27241 13825 27242 13826 27242 13508 27242 13508 27243 13826 27243 13575 27243 13508 27244 13575 27244 13507 27244 13507 27245 13575 27245 13819 27245 13507 27246 13819 27246 13817 27246 13542 27247 13827 27247 13543 27247 13543 27248 13827 27248 13560 27248 13543 27249 13560 27249 13544 27249 13828 27250 13572 27250 13526 27250 13526 27251 13572 27251 13829 27251 13526 27252 13829 27252 13824 27252 13544 27253 13560 27253 13562 27253 13544 27254 13562 27254 13532 27254 13532 27255 13562 27255 13564 27255 13532 27256 13564 27256 13830 27256 13830 27257 13564 27257 13831 27257 13830 27258 13831 27258 13832 27258 13832 27259 13831 27259 13836 27259 13832 27260 13836 27260 13554 27260 13557 27261 13567 27261 13833 27261 13557 27262 13833 27262 13558 27262 13558 27263 13833 27263 13568 27263 13558 27264 13568 27264 13834 27264 13834 27265 13568 27265 13569 27265 13834 27266 13569 27266 13835 27266 13835 27267 13569 27267 13572 27267 13835 27268 13572 27268 13828 27268 13555 27269 13554 27269 13836 27269 13555 27270 13836 27270 13556 27270 13556 27271 13836 27271 13567 27271 13556 27272 13567 27272 13557 27272 13643 27273 13840 27273 13566 27273 13841 27274 13837 27274 13565 27274 13565 27275 13837 27275 13647 27275 13565 27276 13647 27276 13566 27276 13566 27277 13647 27277 13645 27277 13566 27278 13645 27278 13643 27278 13847 27279 13571 27279 13570 27279 13847 27280 13570 27280 13617 27280 13617 27281 13570 27281 13838 27281 13617 27282 13838 27282 13616 27282 13616 27283 13838 27283 13839 27283 13616 27284 13839 27284 13614 27284 13614 27285 13839 27285 13566 27285 13614 27286 13566 27286 13840 27286 13841 27287 13565 27287 13842 27287 13841 27288 13842 27288 13843 27288 13843 27289 13842 27289 13563 27289 13843 27290 13563 27290 13844 27290 13844 27291 13563 27291 13561 27291 13844 27292 13561 27292 13610 27292 13610 27293 13561 27293 13849 27293 13610 27294 13849 27294 13845 27294 13651 27295 13627 27295 13846 27295 13651 27296 13846 27296 13613 27296 13613 27297 13846 27297 13571 27297 13613 27298 13571 27298 13847 27298 13848 27299 13845 27299 13849 27299 13848 27300 13849 27300 13850 27300 13850 27301 13849 27301 13559 27301 13850 27302 13559 27302 13854 27302 13622 27303 13576 27303 13851 27303 13622 27304 13851 27304 13852 27304 13852 27305 13851 27305 13853 27305 13852 27306 13853 27306 13624 27306 13624 27307 13853 27307 13573 27307 13624 27308 13573 27308 13626 27308 13626 27309 13573 27309 13846 27309 13626 27310 13846 27310 13627 27310 13854 27311 13559 27311 13581 27311 13854 27312 13581 27312 13642 27312 13642 27313 13581 27313 13580 27313 13642 27314 13580 27314 13855 27314 13855 27315 13580 27315 13577 27315 13855 27316 13577 27316 13856 27316 13856 27317 13577 27317 13857 27317 13856 27318 13857 27318 13636 27318 13576 27319 13622 27319 13621 27319 13621 27320 13599 27320 13576 27320 13576 27321 13599 27321 13598 27321 13576 27322 13598 27322 13857 27322 13857 27323 13598 27323 13631 27323 13857 27324 13631 27324 13636 27324 13862 27325 13889 27325 13860 27325 13893 27326 13892 27326 13895 27326 13895 27327 13892 27327 13858 27327 13895 27328 13858 27328 13890 27328 13890 27329 13858 27329 13859 27329 13886 27330 13885 27330 13887 27330 13887 27331 13885 27331 13859 27331 13887 27332 13859 27332 13889 27332 13889 27333 13859 27333 13858 27333 13889 27334 13858 27334 13860 27334 13860 27335 13858 27335 13864 27335 13860 27336 13864 27336 13877 27336 13878 27337 13861 27337 13860 27337 13860 27338 13861 27338 13880 27338 13860 27339 13880 27339 13862 27339 13875 27340 13863 27340 13864 27340 13864 27341 13863 27341 13865 27341 13864 27342 13865 27342 13877 27342 13919 27343 13897 27343 13866 27343 13872 27344 13900 27344 13902 27344 13867 27345 13912 27345 13868 27345 13904 27346 13905 27346 13907 27346 13897 27347 13909 27347 13866 27347 13866 27348 13909 27348 13867 27348 13866 27349 13867 27349 13869 27349 13869 27350 13867 27350 13868 27350 13916 27351 13870 27351 13866 27351 13866 27352 13870 27352 13871 27352 13866 27353 13871 27353 13919 27353 13899 27354 13872 27354 13897 27354 13897 27355 13872 27355 13902 27355 13897 27356 13902 27356 13909 27356 13909 27357 13902 27357 13904 27357 13909 27358 13904 27358 13873 27358 13873 27359 13904 27359 13907 27359 13864 27360 13874 27360 13875 27360 13875 27361 13874 27361 13592 27361 13875 27362 13592 27362 13863 27362 13863 27363 13592 27363 13876 27363 13863 27364 13876 27364 13865 27364 13865 27365 13876 27365 13586 27365 13865 27366 13586 27366 13877 27366 13877 27367 13586 27367 13590 27367 13860 27368 13877 27368 13589 27368 13589 27369 13877 27369 13590 27369 13860 27370 13589 27370 13878 27370 13878 27371 13589 27371 13588 27371 13878 27372 13588 27372 13861 27372 13861 27373 13588 27373 13879 27373 13861 27374 13879 27374 13880 27374 13880 27375 13879 27375 13881 27375 13880 27376 13881 27376 13862 27376 13862 27377 13881 27377 13594 27377 13593 27378 13889 27378 13882 27378 13882 27379 13889 27379 13862 27379 13882 27380 13862 27380 13594 27380 13597 27381 13859 27381 13883 27381 13883 27382 13859 27382 13885 27382 13883 27383 13885 27383 13884 27383 13884 27384 13885 27384 13886 27384 13884 27385 13886 27385 13888 27385 13888 27386 13886 27386 13887 27386 13888 27387 13887 27387 13593 27387 13593 27388 13887 27388 13889 27388 13890 27389 13859 27389 13654 27389 13654 27390 13859 27390 13597 27390 13595 27391 13858 27391 13891 27391 13891 27392 13858 27392 13892 27392 13891 27393 13892 27393 13596 27393 13596 27394 13892 27394 13893 27394 13596 27395 13893 27395 13894 27395 13894 27396 13893 27396 13895 27396 13894 27397 13895 27397 13654 27397 13654 27398 13895 27398 13890 27398 13874 27399 13864 27399 13896 27399 13896 27400 13864 27400 13858 27400 13896 27401 13858 27401 13595 27401 13897 27402 13898 27402 13899 27402 13899 27403 13898 27403 13659 27403 13899 27404 13659 27404 13872 27404 13872 27405 13659 27405 13901 27405 13872 27406 13901 27406 13900 27406 13900 27407 13901 27407 13661 27407 13900 27408 13661 27408 13902 27408 13902 27409 13661 27409 13903 27409 13904 27410 13902 27410 13665 27410 13665 27411 13902 27411 13903 27411 13904 27412 13665 27412 13905 27412 13905 27413 13665 27413 13906 27413 13905 27414 13906 27414 13907 27414 13907 27415 13906 27415 13658 27415 13907 27416 13658 27416 13873 27416 13873 27417 13658 27417 13908 27417 13873 27418 13908 27418 13909 27418 13909 27419 13908 27419 13910 27419 13867 27420 13909 27420 13657 27420 13657 27421 13909 27421 13910 27421 13655 27422 13869 27422 13911 27422 13911 27423 13869 27423 13868 27423 13911 27424 13868 27424 13913 27424 13913 27425 13868 27425 13912 27425 13913 27426 13912 27426 13657 27426 13657 27427 13912 27427 13867 27427 13655 27428 13918 27428 13869 27428 13869 27429 13918 27429 13866 27429 13660 27430 13919 27430 13914 27430 13914 27431 13919 27431 13871 27431 13914 27432 13871 27432 13915 27432 13915 27433 13871 27433 13870 27433 13915 27434 13870 27434 13917 27434 13917 27435 13870 27435 13916 27435 13917 27436 13916 27436 13918 27436 13918 27437 13916 27437 13866 27437 13660 27438 13898 27438 13919 27438 13919 27439 13898 27439 13897 27439 14187 27440 14245 27440 13920 27440 14187 27441 13920 27441 14188 27441 14188 27442 13920 27442 13921 27442 14188 27443 13921 27443 14192 27443 14192 27444 13921 27444 13922 27444 13922 27445 13921 27445 14248 27445 13922 27446 14248 27446 14194 27446 14194 27447 14248 27447 13923 27447 13923 27448 14248 27448 14249 27448 13923 27449 14249 27449 14196 27449 14196 27450 14249 27450 14197 27450 14197 27451 14249 27451 13924 27451 14197 27452 13924 27452 13929 27452 13926 27453 13930 27453 13925 27453 13925 27454 13927 27454 13926 27454 13926 27455 13927 27455 14199 27455 13926 27456 14199 27456 13924 27456 13924 27457 14199 27457 13928 27457 13924 27458 13928 27458 13929 27458 13925 27459 13930 27459 14189 27459 14189 27460 13930 27460 14244 27460 14189 27461 14244 27461 14190 27461 14241 27462 14191 27462 14244 27462 14244 27463 14191 27463 14190 27463 14073 27464 13931 27464 14071 27464 14071 27465 13931 27465 14186 27465 14071 27466 14186 27466 13932 27466 14221 27467 14200 27467 13933 27467 13933 27468 14200 27468 14184 27468 14201 27469 14200 27469 14221 27469 14201 27470 14221 27470 14204 27470 14204 27471 14221 27471 13934 27471 14204 27472 13934 27472 14205 27472 14205 27473 13934 27473 14206 27473 14206 27474 13934 27474 13935 27474 14206 27475 13935 27475 14207 27475 14207 27476 13935 27476 14208 27476 14208 27477 13935 27477 13936 27477 14208 27478 13936 27478 14209 27478 14209 27479 13936 27479 13937 27479 13937 27480 13936 27480 13939 27480 13937 27481 13939 27481 14211 27481 14211 27482 13939 27482 13938 27482 13938 27483 13939 27483 13942 27483 13938 27484 13942 27484 13940 27484 13940 27485 13942 27485 13941 27485 13941 27486 13942 27486 14219 27486 13941 27487 14219 27487 14214 27487 14214 27488 14219 27488 13943 27488 14214 27489 13943 27489 14215 27489 14215 27490 13943 27490 13944 27490 14215 27491 13944 27491 14202 27491 14226 27492 14038 27492 13945 27492 14048 27493 14202 27493 13945 27493 13945 27494 14202 27494 13944 27494 13945 27495 13944 27495 14226 27495 14038 27496 14226 27496 14235 27496 14038 27497 14235 27497 13946 27497 13946 27498 14235 27498 14233 27498 13946 27499 14233 27499 14035 27499 14035 27500 14233 27500 13947 27500 14035 27501 13947 27501 13948 27501 13948 27502 13947 27502 13949 27502 13948 27503 13949 27503 14036 27503 14237 27504 13950 27504 13949 27504 13949 27505 13950 27505 14036 27505 13950 27506 14237 27506 13951 27506 13950 27507 13951 27507 13953 27507 13953 27508 13951 27508 13952 27508 13953 27509 13952 27509 13954 27509 13954 27510 13952 27510 13955 27510 13954 27511 13955 27511 14033 27511 14033 27512 13955 27512 13956 27512 14033 27513 13956 27513 14032 27513 14187 27514 14084 27514 14245 27514 14245 27515 14084 27515 13957 27515 14245 27516 13957 27516 13956 27516 13956 27517 13957 27517 14032 27517 14243 27518 14004 27518 13958 27518 13976 27519 13979 27519 14227 27519 13976 27520 14227 27520 13959 27520 13975 27521 13960 27521 13974 27521 13974 27522 13960 27522 14105 27522 13974 27523 14105 27523 13984 27523 13984 27524 14105 27524 13961 27524 13984 27525 13961 27525 13962 27525 13962 27526 13961 27526 13964 27526 14104 27527 13963 27527 13964 27527 13964 27528 13963 27528 13965 27528 13964 27529 13965 27529 13962 27529 14227 27530 13966 27530 13959 27530 13959 27531 13966 27531 14230 27531 13959 27532 14230 27532 13967 27532 13967 27533 14230 27533 13968 27533 13967 27534 13968 27534 13969 27534 13969 27535 13968 27535 14232 27535 13969 27536 14232 27536 14103 27536 14103 27537 14232 27537 14236 27537 14103 27538 14236 27538 13970 27538 13970 27539 14236 27539 13971 27539 13970 27540 13971 27540 14104 27540 14104 27541 13971 27541 13972 27541 14104 27542 13972 27542 13963 27542 13982 27543 13973 27543 13974 27543 13974 27544 13973 27544 13979 27544 13974 27545 13979 27545 13975 27545 13975 27546 13979 27546 13976 27546 13977 27547 13978 27547 14126 27547 14126 27548 13978 27548 14216 27548 13973 27549 14121 27549 13979 27549 13979 27550 14121 27550 13980 27550 13979 27551 13980 27551 13981 27551 13981 27552 13980 27552 14132 27552 13981 27553 14132 27553 14222 27553 14222 27554 14132 27554 14130 27554 14222 27555 14130 27555 14216 27555 14216 27556 14130 27556 14127 27556 14216 27557 14127 27557 14126 27557 13982 27558 13974 27558 13983 27558 13983 27559 13974 27559 13984 27559 13983 27560 13984 27560 14123 27560 14123 27561 13984 27561 13986 27561 14123 27562 13986 27562 13985 27562 13985 27563 13986 27563 14252 27563 13985 27564 14252 27564 13977 27564 13977 27565 14252 27565 14028 27565 13977 27566 14028 27566 13978 27566 14146 27567 14225 27567 13987 27567 13987 27568 14225 27568 13989 27568 13987 27569 13989 27569 13988 27569 13988 27570 13989 27570 14026 27570 13998 27571 13990 27571 14153 27571 14153 27572 13990 27572 14225 27572 14153 27573 14225 27573 13991 27573 13991 27574 14225 27574 14146 27574 13997 27575 14150 27575 13996 27575 13996 27576 14150 27576 13992 27576 13996 27577 13992 27577 14246 27577 14246 27578 13992 27578 13993 27578 14246 27579 13993 27579 14247 27579 14247 27580 13993 27580 14025 27580 13994 27581 13995 27581 13996 27581 13996 27582 13995 27582 13990 27582 13996 27583 13990 27583 13997 27583 13997 27584 13990 27584 13998 27584 13995 27585 13999 27585 13990 27585 13990 27586 13999 27586 14169 27586 13990 27587 14169 27587 14000 27587 14000 27588 14169 27588 14182 27588 14000 27589 14182 27589 14001 27589 14001 27590 14182 27590 14002 27590 14001 27591 14002 27591 14003 27591 14002 27592 14180 27592 14003 27592 14003 27593 14180 27593 14178 27593 14003 27594 14178 27594 14004 27594 14004 27595 14178 27595 14176 27595 14004 27596 14176 27596 13958 27596 13958 27597 14176 27597 14174 27597 13994 27598 13996 27598 14005 27598 14005 27599 13996 27599 14246 27599 14005 27600 14246 27600 14173 27600 14173 27601 14246 27601 14242 27601 14173 27602 14242 27602 14174 27602 14174 27603 14242 27603 14006 27603 14174 27604 14006 27604 13958 27604 14264 27605 14262 27605 14019 27605 14007 27606 14008 27606 14014 27606 14014 27607 14008 27607 14010 27607 14264 27608 14019 27608 14265 27608 14008 27609 14253 27609 14010 27609 14010 27610 14253 27610 14009 27610 14010 27611 14009 27611 14011 27611 14262 27612 14012 27612 14019 27612 14019 27613 14012 27613 14013 27613 14019 27614 14013 27614 13978 27614 13978 27615 14013 27615 14258 27615 13978 27616 14258 27616 14257 27616 14007 27617 14014 27617 14257 27617 14257 27618 14014 27618 14218 27618 14257 27619 14218 27619 13978 27619 13978 27620 14218 27620 14217 27620 13978 27621 14217 27621 14216 27621 14015 27622 14017 27622 13989 27622 13989 27623 14017 27623 14019 27623 14225 27624 14022 27624 14016 27624 14017 27625 14275 27625 14019 27625 14019 27626 14275 27626 14273 27626 14019 27627 14273 27627 14272 27627 14225 27628 14016 27628 13989 27628 13989 27629 14016 27629 14018 27629 13989 27630 14018 27630 14015 27630 14272 27631 14271 27631 14019 27631 14019 27632 14271 27632 14010 27632 14019 27633 14010 27633 14265 27633 14265 27634 14010 27634 14011 27634 14271 27635 14020 27635 14010 27635 14010 27636 14020 27636 14268 27636 14010 27637 14268 27637 14220 27637 14220 27638 14268 27638 14021 27638 14220 27639 14021 27639 14224 27639 14224 27640 14021 27640 14022 27640 14224 27641 14022 27641 14223 27641 14223 27642 14022 27642 14225 27642 14234 27643 14003 27643 14023 27643 14023 27644 14003 27644 14004 27644 14023 27645 14004 27645 14024 27645 14024 27646 14004 27646 14243 27646 14025 27647 14026 27647 14247 27647 14247 27648 14026 27648 13989 27648 14247 27649 13989 27649 14027 27649 14027 27650 13989 27650 14019 27650 14027 27651 14019 27651 14030 27651 14028 27652 14251 27652 13978 27652 13978 27653 14251 27653 14250 27653 13978 27654 14250 27654 14019 27654 14019 27655 14250 27655 14029 27655 14019 27656 14029 27656 14030 27656 14113 27657 14077 27657 14063 27657 14031 27658 14051 27658 14213 27658 14160 27659 14162 27659 14032 27659 14032 27660 14162 27660 14163 27660 14032 27661 14163 27661 14033 27661 14033 27662 14163 27662 14034 27662 14033 27663 14034 27663 13954 27663 14034 27664 14035 27664 13948 27664 13953 27665 13954 27665 13950 27665 13950 27666 13954 27666 14034 27666 13950 27667 14034 27667 14036 27667 14036 27668 14034 27668 13948 27668 14156 27669 14157 27669 14088 27669 14032 27670 13957 27670 14160 27670 14160 27671 13957 27671 14088 27671 14160 27672 14088 27672 14158 27672 14158 27673 14088 27673 14157 27673 14163 27674 14164 27674 14034 27674 14034 27675 14164 27675 14037 27675 14034 27676 14037 27676 14035 27676 14035 27677 14037 27677 14165 27677 14035 27678 14165 27678 13946 27678 13946 27679 14165 27679 14166 27679 13946 27680 14166 27680 14038 27680 14038 27681 14166 27681 14039 27681 14038 27682 14039 27682 13945 27682 13945 27683 14039 27683 14154 27683 13945 27684 14154 27684 14156 27684 14144 27685 14048 27685 14040 27685 14040 27686 14048 27686 13945 27686 14040 27687 13945 27687 14142 27687 14134 27688 14083 27688 14041 27688 14041 27689 14083 27689 14048 27689 14041 27690 14048 27690 14042 27690 14042 27691 14048 27691 14144 27691 14156 27692 14088 27692 13945 27692 13945 27693 14088 27693 14140 27693 13945 27694 14140 27694 14142 27694 14276 27695 14083 27695 14274 27695 14274 27696 14083 27696 14044 27696 14274 27697 14044 27697 14046 27697 14048 27698 14277 27698 14213 27698 14213 27699 14277 27699 14043 27699 14213 27700 14043 27700 14267 27700 14267 27701 14269 27701 14213 27701 14213 27702 14269 27702 14270 27702 14213 27703 14270 27703 14044 27703 14044 27704 14270 27704 14045 27704 14044 27705 14045 27705 14046 27705 14276 27706 14047 27706 14083 27706 14083 27707 14047 27707 14049 27707 14083 27708 14049 27708 14048 27708 14048 27709 14049 27709 14050 27709 14048 27710 14050 27710 14277 27710 14213 27711 14051 27711 14052 27711 14052 27712 14051 27712 14254 27712 14052 27713 14254 27713 14212 27713 14261 27714 14044 27714 14260 27714 14260 27715 14044 27715 14075 27715 14260 27716 14075 27716 14259 27716 14058 27717 14210 27717 14075 27717 14075 27718 14210 27718 14212 27718 14254 27719 14053 27719 14212 27719 14212 27720 14053 27720 14255 27720 14212 27721 14255 27721 14075 27721 14075 27722 14255 27722 14256 27722 14075 27723 14256 27723 14259 27723 14261 27724 14263 27724 14044 27724 14044 27725 14263 27725 14054 27725 14044 27726 14054 27726 14213 27726 14213 27727 14054 27727 14266 27727 14213 27728 14266 27728 14031 27728 14055 27729 14112 27729 14063 27729 14063 27730 14112 27730 14056 27730 14063 27731 14056 27731 14113 27731 14075 27732 14057 27732 14118 27732 14058 27733 14075 27733 14059 27733 14059 27734 14075 27734 14118 27734 14059 27735 14118 27735 14203 27735 14118 27736 14060 27736 14203 27736 14203 27737 14060 27737 14061 27737 14203 27738 14061 27738 14055 27738 14055 27739 14061 27739 14111 27739 14055 27740 14111 27740 14112 27740 14063 27741 14068 27741 14062 27741 14070 27742 14071 27742 14092 27742 14092 27743 14071 27743 13932 27743 14092 27744 13932 27744 14090 27744 14062 27745 14064 27745 14063 27745 14063 27746 14064 27746 14100 27746 14063 27747 14100 27747 14055 27747 14055 27748 14100 27748 14102 27748 14055 27749 14102 27749 14065 27749 14065 27750 14102 27750 14089 27750 14065 27751 14089 27751 14066 27751 14066 27752 14089 27752 14090 27752 14066 27753 14090 27753 14185 27753 14185 27754 14090 27754 13932 27754 14095 27755 14068 27755 14067 27755 14067 27756 14068 27756 14076 27756 14095 27757 14067 27757 14069 27757 14069 27758 14067 27758 14183 27758 14069 27759 14183 27759 14074 27759 14070 27760 14072 27760 14071 27760 14071 27761 14072 27761 14069 27761 14071 27762 14069 27762 14073 27762 14073 27763 14069 27763 14074 27763 14195 27764 14198 27764 14075 27764 14075 27765 14198 27765 14080 27765 14068 27766 14063 27766 14076 27766 14076 27767 14063 27767 14077 27767 14076 27768 14077 27768 14078 27768 14078 27769 14077 27769 14079 27769 14078 27770 14079 27770 14080 27770 14080 27771 14079 27771 14116 27771 14080 27772 14116 27772 14075 27772 14075 27773 14116 27773 14081 27773 14075 27774 14081 27774 14057 27774 14195 27775 14075 27775 14082 27775 14082 27776 14075 27776 14044 27776 14082 27777 14044 27777 14193 27777 14193 27778 14044 27778 14083 27778 14193 27779 14083 27779 14084 27779 14134 27780 14135 27780 14083 27780 14083 27781 14135 27781 14085 27781 14083 27782 14085 27782 14084 27782 14084 27783 14085 27783 14086 27783 14084 27784 14086 27784 13957 27784 13957 27785 14086 27785 14087 27785 13957 27786 14087 27786 14088 27786 14088 27787 14087 27787 14139 27787 14088 27788 14139 27788 14140 27788 14089 27789 14108 27789 14090 27789 14090 27790 14108 27790 14109 27790 14090 27791 14109 27791 14092 27791 14092 27792 14109 27792 14091 27792 14092 27793 14091 27793 14070 27793 14070 27794 14091 27794 14093 27794 14070 27795 14093 27795 14072 27795 14072 27796 14093 27796 14094 27796 14072 27797 14094 27797 14069 27797 14069 27798 14094 27798 14096 27798 14069 27799 14096 27799 14095 27799 14095 27800 14096 27800 14097 27800 14095 27801 14097 27801 14068 27801 14068 27802 14097 27802 14098 27802 14068 27803 14098 27803 14062 27803 14062 27804 14098 27804 14099 27804 14062 27805 14099 27805 14064 27805 14064 27806 14099 27806 14106 27806 14064 27807 14106 27807 14100 27807 14100 27808 14106 27808 14101 27808 14100 27809 14101 27809 14102 27809 14102 27810 14101 27810 14107 27810 14102 27811 14107 27811 14089 27811 14089 27812 14107 27812 14108 27812 14109 27813 13967 27813 14091 27813 14091 27814 13967 27814 13969 27814 14091 27815 13969 27815 14093 27815 14093 27816 13969 27816 14103 27816 14093 27817 14103 27817 14094 27817 14094 27818 14103 27818 13970 27818 14094 27819 13970 27819 14096 27819 14096 27820 13970 27820 14104 27820 14096 27821 14104 27821 14097 27821 14097 27822 14104 27822 13964 27822 14097 27823 13964 27823 14098 27823 14098 27824 13964 27824 13961 27824 14098 27825 13961 27825 14099 27825 14099 27826 13961 27826 14105 27826 14099 27827 14105 27827 14106 27827 14106 27828 14105 27828 13960 27828 14106 27829 13960 27829 14101 27829 14101 27830 13960 27830 13975 27830 14101 27831 13975 27831 14107 27831 14107 27832 13975 27832 13976 27832 14107 27833 13976 27833 14108 27833 14108 27834 13976 27834 13959 27834 14108 27835 13959 27835 14109 27835 14109 27836 13959 27836 13967 27836 14061 27837 14110 27837 14111 27837 14111 27838 14110 27838 14131 27838 14111 27839 14131 27839 14112 27839 14112 27840 14131 27840 14119 27840 14112 27841 14119 27841 14056 27841 14056 27842 14119 27842 14120 27842 14056 27843 14120 27843 14113 27843 14113 27844 14120 27844 14114 27844 14113 27845 14114 27845 14077 27845 14077 27846 14114 27846 14115 27846 14077 27847 14115 27847 14079 27847 14079 27848 14115 27848 14122 27848 14079 27849 14122 27849 14116 27849 14116 27850 14122 27850 14124 27850 14116 27851 14124 27851 14081 27851 14081 27852 14124 27852 14117 27852 14081 27853 14117 27853 14057 27853 14057 27854 14117 27854 14125 27854 14057 27855 14125 27855 14118 27855 14118 27856 14125 27856 14128 27856 14118 27857 14128 27857 14060 27857 14060 27858 14128 27858 14129 27858 14060 27859 14129 27859 14061 27859 14061 27860 14129 27860 14110 27860 14131 27861 13980 27861 14119 27861 14119 27862 13980 27862 14121 27862 14119 27863 14121 27863 14120 27863 14120 27864 14121 27864 13973 27864 14120 27865 13973 27865 14114 27865 14114 27866 13973 27866 13982 27866 14114 27867 13982 27867 14115 27867 14115 27868 13982 27868 13983 27868 14115 27869 13983 27869 14122 27869 14122 27870 13983 27870 14123 27870 14122 27871 14123 27871 14124 27871 14124 27872 14123 27872 13985 27872 14124 27873 13985 27873 14117 27873 14117 27874 13985 27874 13977 27874 14117 27875 13977 27875 14125 27875 14125 27876 13977 27876 14126 27876 14125 27877 14126 27877 14128 27877 14128 27878 14126 27878 14127 27878 14128 27879 14127 27879 14129 27879 14129 27880 14127 27880 14130 27880 14129 27881 14130 27881 14110 27881 14110 27882 14130 27882 14132 27882 14110 27883 14132 27883 14131 27883 14131 27884 14132 27884 13980 27884 14144 27885 14152 27885 14042 27885 14042 27886 14152 27886 14145 27886 14042 27887 14145 27887 14041 27887 14041 27888 14145 27888 14133 27888 14041 27889 14133 27889 14134 27889 14134 27890 14133 27890 14136 27890 14134 27891 14136 27891 14135 27891 14135 27892 14136 27892 14147 27892 14135 27893 14147 27893 14085 27893 14085 27894 14147 27894 14137 27894 14085 27895 14137 27895 14086 27895 14086 27896 14137 27896 14138 27896 14086 27897 14138 27897 14087 27897 14087 27898 14138 27898 14148 27898 14087 27899 14148 27899 14139 27899 14139 27900 14148 27900 14149 27900 14139 27901 14149 27901 14140 27901 14140 27902 14149 27902 14141 27902 14140 27903 14141 27903 14142 27903 14142 27904 14141 27904 14151 27904 14142 27905 14151 27905 14040 27905 14040 27906 14151 27906 14143 27906 14040 27907 14143 27907 14144 27907 14144 27908 14143 27908 14152 27908 14145 27909 13991 27909 14133 27909 14133 27910 13991 27910 14146 27910 14133 27911 14146 27911 14136 27911 14136 27912 14146 27912 13987 27912 14136 27913 13987 27913 14147 27913 14147 27914 13987 27914 13988 27914 14147 27915 13988 27915 14137 27915 14137 27916 13988 27916 14026 27916 14137 27917 14026 27917 14138 27917 14138 27918 14026 27918 14025 27918 14138 27919 14025 27919 14148 27919 14148 27920 14025 27920 13993 27920 14148 27921 13993 27921 14149 27921 14149 27922 13993 27922 13992 27922 14149 27923 13992 27923 14141 27923 14141 27924 13992 27924 14150 27924 14141 27925 14150 27925 14151 27925 14151 27926 14150 27926 13997 27926 14151 27927 13997 27927 14143 27927 14143 27928 13997 27928 13998 27928 14143 27929 13998 27929 14152 27929 14152 27930 13998 27930 14153 27930 14152 27931 14153 27931 14145 27931 14145 27932 14153 27932 13991 27932 14039 27933 14167 27933 14154 27933 14154 27934 14167 27934 14155 27934 14154 27935 14155 27935 14156 27935 14156 27936 14155 27936 14168 27936 14156 27937 14168 27937 14157 27937 14157 27938 14168 27938 14159 27938 14157 27939 14159 27939 14158 27939 14158 27940 14159 27940 14170 27940 14158 27941 14170 27941 14160 27941 14160 27942 14170 27942 14161 27942 14160 27943 14161 27943 14162 27943 14162 27944 14161 27944 14171 27944 14162 27945 14171 27945 14163 27945 14163 27946 14171 27946 14172 27946 14163 27947 14172 27947 14164 27947 14164 27948 14172 27948 14175 27948 14164 27949 14175 27949 14037 27949 14037 27950 14175 27950 14177 27950 14037 27951 14177 27951 14165 27951 14165 27952 14177 27952 14179 27952 14165 27953 14179 27953 14166 27953 14166 27954 14179 27954 14181 27954 14166 27955 14181 27955 14039 27955 14039 27956 14181 27956 14167 27956 14155 27957 14169 27957 14168 27957 14168 27958 14169 27958 13999 27958 14168 27959 13999 27959 14159 27959 14159 27960 13999 27960 13995 27960 14159 27961 13995 27961 14170 27961 14170 27962 13995 27962 13994 27962 14170 27963 13994 27963 14161 27963 14161 27964 13994 27964 14005 27964 14161 27965 14005 27965 14171 27965 14171 27966 14005 27966 14173 27966 14171 27967 14173 27967 14172 27967 14172 27968 14173 27968 14174 27968 14172 27969 14174 27969 14175 27969 14175 27970 14174 27970 14176 27970 14175 27971 14176 27971 14177 27971 14177 27972 14176 27972 14178 27972 14177 27973 14178 27973 14179 27973 14179 27974 14178 27974 14180 27974 14179 27975 14180 27975 14181 27975 14181 27976 14180 27976 14002 27976 14181 27977 14002 27977 14167 27977 14167 27978 14002 27978 14182 27978 14167 27979 14182 27979 14155 27979 14155 27980 14182 27980 14169 27980 14191 27981 14241 27981 14076 27981 14076 27982 14241 27982 14240 27982 14076 27983 14240 27983 14067 27983 14067 27984 14240 27984 14239 27984 14067 27985 14239 27985 14183 27985 14183 27986 14239 27986 14238 27986 14183 27987 14238 27987 14074 27987 14074 27988 14238 27988 13931 27988 14074 27989 13931 27989 14073 27989 13933 27990 14184 27990 14055 27990 13933 27991 14055 27991 14228 27991 14055 27992 14065 27992 14228 27992 14228 27993 14065 27993 14066 27993 14228 27994 14066 27994 14229 27994 14229 27995 14066 27995 14185 27995 14229 27996 14185 27996 14231 27996 14231 27997 14185 27997 13932 27997 14231 27998 13932 27998 14186 27998 14084 27999 14187 27999 14193 27999 14193 28000 14187 28000 14188 28000 14189 28001 14190 28001 14078 28001 14078 28002 14190 28002 14191 28002 14078 28003 14191 28003 14076 28003 14189 28004 14078 28004 13925 28004 13925 28005 14078 28005 14080 28005 13925 28006 14080 28006 13927 28006 14188 28007 14192 28007 14193 28007 14193 28008 14192 28008 13922 28008 14193 28009 13922 28009 14082 28009 13922 28010 14194 28010 14082 28010 14082 28011 14194 28011 13923 28011 14082 28012 13923 28012 14195 28012 13923 28013 14196 28013 14195 28013 14195 28014 14196 28014 14197 28014 14195 28015 14197 28015 14198 28015 14197 28016 13929 28016 14198 28016 14198 28017 13929 28017 13928 28017 14198 28018 13928 28018 14080 28018 14080 28019 13928 28019 14199 28019 14080 28020 14199 28020 13927 28020 14055 28021 14184 28021 14203 28021 14203 28022 14184 28022 14200 28022 14203 28023 14200 28023 14201 28023 14202 28024 14048 28024 14213 28024 14202 28025 14213 28025 14215 28025 14201 28026 14204 28026 14203 28026 14203 28027 14204 28027 14205 28027 14203 28028 14205 28028 14059 28028 14205 28029 14206 28029 14059 28029 14059 28030 14206 28030 14207 28030 14059 28031 14207 28031 14058 28031 14207 28032 14208 28032 14058 28032 14058 28033 14208 28033 14209 28033 14058 28034 14209 28034 14210 28034 14209 28035 13937 28035 14210 28035 14210 28036 13937 28036 14211 28036 14210 28037 14211 28037 14212 28037 14211 28038 13938 28038 14212 28038 14212 28039 13938 28039 13940 28039 14212 28040 13940 28040 14052 28040 14052 28041 13940 28041 13941 28041 14052 28042 13941 28042 14213 28042 14213 28043 13941 28043 14214 28043 14213 28044 14214 28044 14215 28044 13934 28045 14222 28045 13935 28045 13935 28046 14222 28046 14216 28046 13935 28047 14216 28047 13936 28047 13936 28048 14216 28048 14217 28048 13936 28049 14217 28049 13939 28049 13939 28050 14217 28050 14218 28050 13939 28051 14218 28051 13942 28051 13942 28052 14218 28052 14014 28052 13942 28053 14014 28053 14219 28053 14219 28054 14014 28054 14010 28054 14219 28055 14010 28055 14220 28055 13934 28056 14221 28056 14222 28056 14222 28057 14221 28057 13981 28057 14223 28058 13944 28058 13943 28058 14223 28059 13943 28059 14224 28059 14224 28060 13943 28060 14219 28060 14224 28061 14219 28061 14220 28061 13981 28062 14221 28062 13979 28062 13979 28063 14221 28063 13933 28063 13979 28064 13933 28064 14227 28064 14223 28065 14225 28065 13944 28065 13944 28066 14225 28066 13990 28066 13944 28067 13990 28067 14226 28067 14226 28068 13990 28068 14000 28068 14227 28069 13933 28069 14228 28069 14227 28070 14228 28070 13966 28070 13966 28071 14228 28071 14229 28071 13966 28072 14229 28072 14230 28072 14230 28073 14229 28073 14231 28073 14230 28074 14231 28074 13968 28074 13968 28075 14231 28075 14186 28075 13968 28076 14186 28076 14232 28076 14023 28077 13949 28077 13947 28077 14023 28078 13947 28078 14234 28078 14234 28079 13947 28079 14233 28079 14234 28080 14233 28080 14003 28080 14003 28081 14233 28081 14235 28081 14003 28082 14235 28082 14001 28082 14001 28083 14235 28083 14226 28083 14001 28084 14226 28084 14000 28084 14232 28085 14186 28085 14236 28085 14236 28086 14186 28086 13931 28086 14236 28087 13931 28087 13971 28087 14024 28088 14237 28088 14023 28088 14023 28089 14237 28089 13949 28089 13971 28090 13931 28090 14238 28090 13971 28091 14238 28091 13972 28091 13972 28092 14238 28092 14239 28092 13972 28093 14239 28093 13963 28093 13963 28094 14239 28094 14240 28094 13963 28095 14240 28095 13965 28095 13965 28096 14240 28096 14241 28096 13965 28097 14241 28097 13962 28097 14242 28098 13956 28098 13955 28098 14242 28099 13955 28099 14006 28099 14006 28100 13955 28100 13952 28100 14006 28101 13952 28101 13958 28101 13958 28102 13952 28102 13951 28102 13958 28103 13951 28103 14243 28103 14243 28104 13951 28104 14237 28104 14243 28105 14237 28105 14024 28105 13962 28106 14241 28106 13984 28106 13984 28107 14241 28107 14244 28107 13984 28108 14244 28108 13986 28108 14247 28109 14245 28109 14246 28109 14246 28110 14245 28110 13956 28110 14246 28111 13956 28111 14242 28111 14244 28112 13930 28112 13986 28112 13986 28113 13930 28113 14252 28113 14030 28114 13921 28114 13920 28114 14030 28115 13920 28115 14027 28115 14027 28116 13920 28116 14245 28116 14027 28117 14245 28117 14247 28117 13921 28118 14030 28118 14248 28118 14248 28119 14030 28119 14029 28119 14248 28120 14029 28120 14249 28120 14249 28121 14029 28121 14250 28121 14249 28122 14250 28122 13924 28122 13924 28123 14250 28123 14251 28123 13924 28124 14251 28124 13926 28124 13926 28125 14251 28125 14028 28125 13926 28126 14028 28126 13930 28126 13930 28127 14028 28127 14252 28127 14051 28128 14253 28128 14254 28128 14254 28129 14253 28129 14008 28129 14254 28130 14008 28130 14053 28130 14053 28131 14008 28131 14007 28131 14053 28132 14007 28132 14255 28132 14255 28133 14007 28133 14257 28133 14255 28134 14257 28134 14256 28134 14256 28135 14257 28135 14258 28135 14256 28136 14258 28136 14259 28136 14259 28137 14258 28137 14013 28137 14259 28138 14013 28138 14260 28138 14260 28139 14013 28139 14012 28139 14260 28140 14012 28140 14261 28140 14261 28141 14012 28141 14262 28141 14261 28142 14262 28142 14263 28142 14263 28143 14262 28143 14264 28143 14263 28144 14264 28144 14054 28144 14054 28145 14264 28145 14265 28145 14054 28146 14265 28146 14266 28146 14266 28147 14265 28147 14011 28147 14266 28148 14011 28148 14031 28148 14031 28149 14011 28149 14009 28149 14031 28150 14009 28150 14051 28150 14051 28151 14009 28151 14253 28151 14043 28152 14021 28152 14267 28152 14267 28153 14021 28153 14268 28153 14267 28154 14268 28154 14269 28154 14269 28155 14268 28155 14020 28155 14269 28156 14020 28156 14270 28156 14270 28157 14020 28157 14271 28157 14270 28158 14271 28158 14045 28158 14045 28159 14271 28159 14272 28159 14045 28160 14272 28160 14046 28160 14046 28161 14272 28161 14273 28161 14046 28162 14273 28162 14274 28162 14274 28163 14273 28163 14275 28163 14274 28164 14275 28164 14276 28164 14276 28165 14275 28165 14017 28165 14276 28166 14017 28166 14047 28166 14047 28167 14017 28167 14015 28167 14047 28168 14015 28168 14049 28168 14049 28169 14015 28169 14018 28169 14049 28170 14018 28170 14050 28170 14050 28171 14018 28171 14016 28171 14050 28172 14016 28172 14277 28172 14277 28173 14016 28173 14022 28173 14277 28174 14022 28174 14043 28174 14043 28175 14022 28175 14021 28175 14634 28176 14295 28176 15239 28176 14297 28177 14543 28177 14287 28177 14287 28178 14543 28178 14278 28178 14287 28179 14278 28179 14584 28179 15248 28180 15243 28180 14540 28180 14540 28181 15243 28181 15244 28181 14540 28182 15244 28182 14539 28182 14279 28183 14282 28183 15209 28183 15209 28184 14282 28184 15212 28184 14286 28185 14587 28185 15209 28185 15209 28186 14587 28186 14588 28186 15209 28187 14588 28187 14279 28187 14322 28188 14281 28188 14280 28188 14280 28189 14281 28189 14627 28189 14282 28190 14639 28190 15212 28190 15212 28191 14639 28191 14643 28191 15212 28192 14643 28192 14283 28192 14287 28193 14284 28193 15209 28193 15209 28194 14284 28194 14285 28194 15209 28195 14285 28195 14286 28195 14584 28196 14585 28196 14287 28196 14287 28197 14585 28197 14288 28197 14287 28198 14288 28198 14284 28198 14289 28199 14484 28199 14306 28199 14535 28200 14291 28200 14290 28200 14290 28201 14291 28201 14292 28201 14525 28202 14293 28202 15252 28202 15244 28203 15240 28203 14539 28203 14539 28204 15240 28204 15242 28204 14539 28205 15242 28205 14294 28205 14294 28206 15242 28206 15239 28206 14294 28207 15239 28207 14636 28207 14636 28208 15239 28208 14295 28208 14627 28209 14631 28209 14280 28209 14280 28210 14631 28210 14296 28210 14280 28211 14296 28211 15239 28211 15239 28212 14296 28212 14632 28212 15239 28213 14632 28213 14634 28213 14297 28214 14298 28214 14543 28214 14543 28215 14298 28215 14304 28215 14543 28216 14304 28216 14305 28216 14299 28217 14479 28217 14480 28217 14480 28218 14481 28218 14299 28218 14299 28219 14481 28219 14482 28219 14299 28220 14482 28220 14306 28220 14306 28221 14482 28221 14300 28221 14306 28222 14300 28222 14289 28222 14535 28223 14301 28223 14291 28223 14291 28224 14301 28224 14302 28224 14291 28225 14302 28225 14299 28225 14299 28226 14302 28226 14477 28226 14299 28227 14477 28227 14479 28227 14303 28228 14532 28228 14320 28228 14281 28229 15586 28229 14312 28229 14281 28230 14314 28230 14308 28230 14304 28231 15223 28231 14305 28231 14305 28232 15223 28232 15220 28232 14305 28233 15220 28233 14486 28233 14486 28234 15220 28234 14306 28234 14486 28235 14306 28235 14485 28235 14485 28236 14306 28236 14484 28236 14293 28237 14527 28237 15252 28237 15252 28238 14527 28238 14529 28238 15252 28239 14529 28239 14320 28239 14320 28240 14529 28240 14307 28240 14320 28241 14307 28241 14303 28241 15248 28242 14540 28242 15252 28242 15252 28243 14540 28243 14524 28243 15252 28244 14524 28244 14525 28244 14308 28245 14309 28245 14281 28245 14281 28246 14309 28246 14310 28246 14281 28247 14310 28247 14315 28247 15582 28248 14322 28248 15580 28248 15580 28249 14322 28249 15233 28249 15580 28250 15233 28250 15578 28250 15578 28251 15233 28251 15260 28251 15578 28252 15260 28252 15577 28252 15256 28253 15574 28253 15255 28253 15255 28254 15574 28254 15576 28254 15255 28255 15576 28255 15260 28255 15260 28256 15576 28256 14311 28256 15260 28257 14311 28257 15577 28257 14312 28258 14313 28258 14281 28258 14281 28259 14313 28259 15588 28259 14281 28260 15588 28260 14314 28260 14290 28261 15570 28261 14321 28261 14283 28262 14281 28262 15212 28262 15212 28263 14281 28263 14315 28263 15212 28264 14315 28264 14316 28264 14316 28265 14315 28265 14317 28265 14316 28266 14317 28266 14325 28266 14325 28267 14317 28267 14318 28267 14325 28268 14318 28268 14319 28268 14532 28269 14290 28269 14320 28269 14320 28270 14290 28270 14321 28270 14320 28271 14321 28271 15256 28271 15256 28272 14321 28272 15573 28272 15256 28273 15573 28273 15574 28273 15582 28274 15583 28274 14322 28274 14322 28275 15583 28275 15584 28275 14322 28276 15584 28276 14281 28276 14281 28277 15584 28277 14323 28277 14281 28278 14323 28278 15586 28278 14290 28279 14324 28279 15567 28279 14319 28280 15596 28280 14325 28280 14325 28281 15596 28281 15598 28281 14325 28282 15598 28282 14292 28282 14292 28283 15598 28283 15562 28283 14292 28284 15562 28284 14327 28284 15567 28285 14326 28285 14290 28285 14290 28286 14326 28286 15569 28286 14290 28287 15569 28287 15570 28287 14327 28288 14328 28288 14292 28288 14292 28289 14328 28289 15564 28289 14292 28290 15564 28290 14290 28290 14290 28291 15564 28291 14329 28291 14290 28292 14329 28292 14324 28292 14363 28293 14361 28293 15137 28293 14911 28294 14333 28294 14330 28294 14330 28295 14333 28295 15157 28295 14330 28296 15157 28296 14929 28296 14929 28297 15157 28297 14876 28297 14331 28298 15133 28298 14340 28298 14340 28299 15133 28299 15132 28299 14343 28300 15162 28300 14332 28300 14332 28301 15162 28301 14337 28301 14911 28302 14893 28302 14333 28302 14333 28303 14893 28303 14334 28303 14333 28304 14334 28304 15158 28304 15158 28305 14334 28305 14335 28305 15158 28306 14335 28306 15159 28306 15159 28307 14335 28307 14798 28307 15159 28308 14798 28308 15161 28308 15161 28309 14798 28309 14336 28309 15161 28310 14336 28310 14337 28310 14337 28311 14336 28311 14338 28311 14337 28312 14338 28312 14332 28312 14876 28313 15157 28313 14877 28313 14877 28314 15157 28314 14339 28314 14877 28315 14339 28315 14882 28315 14363 28316 15137 28316 14727 28316 14727 28317 15137 28317 15136 28317 14727 28318 15136 28318 14746 28318 15132 28319 14341 28319 14340 28319 14340 28320 14341 28320 15169 28320 14340 28321 15169 28321 14356 28321 14356 28322 15169 28322 14342 28322 14356 28323 14342 28323 15167 28323 14343 28324 14344 28324 15162 28324 15162 28325 14344 28325 14709 28325 15162 28326 14709 28326 14351 28326 15154 28327 15151 28327 14345 28327 14345 28328 15151 28328 14347 28328 14345 28329 14347 28329 14346 28329 14346 28330 14347 28330 15150 28330 14346 28331 15150 28331 15148 28331 14355 28332 14730 28332 14354 28332 14354 28333 14730 28333 14776 28333 14354 28334 14776 28334 14348 28334 14702 28335 14349 28335 14701 28335 14701 28336 14349 28336 14351 28336 14701 28337 14351 28337 14350 28337 14350 28338 14351 28338 14709 28338 14882 28339 14339 28339 14345 28339 14345 28340 14339 28340 15155 28340 14345 28341 15155 28341 15154 28341 14776 28342 14352 28342 14348 28342 14348 28343 14352 28343 14353 28343 14348 28344 14353 28344 15136 28344 15136 28345 14353 28345 14747 28345 15136 28346 14747 28346 14746 28346 14331 28347 14340 28347 14354 28347 14354 28348 14340 28348 14726 28348 14354 28349 14726 28349 14355 28349 15167 28350 15166 28350 14356 28350 14356 28351 15166 28351 15164 28351 14356 28352 15164 28352 14357 28352 14357 28353 15164 28353 14349 28353 14357 28354 14349 28354 14693 28354 14693 28355 14349 28355 14702 28355 14836 28356 15144 28356 14359 28356 14359 28357 15144 28357 14358 28357 14359 28358 14358 28358 14844 28358 15141 28359 14858 28359 14358 28359 14358 28360 14858 28360 14360 28360 14358 28361 14360 28361 14844 28361 14361 28362 14363 28362 14362 28362 14362 28363 14363 28363 14810 28363 14362 28364 14810 28364 15141 28364 15141 28365 14810 28365 14866 28365 15141 28366 14866 28366 14858 28366 15148 28367 15146 28367 14346 28367 14346 28368 15146 28368 15145 28368 14346 28369 15145 28369 14812 28369 14812 28370 15145 28370 14364 28370 14812 28371 14364 28371 14365 28371 14365 28372 14364 28372 15144 28372 14365 28373 15144 28373 14830 28373 14830 28374 15144 28374 14836 28374 14432 28375 14366 28375 14723 28375 14723 28376 14366 28376 14642 28376 14723 28377 14642 28377 14721 28377 14721 28378 14642 28378 14561 28378 14721 28379 14561 28379 14367 28379 14367 28380 14561 28380 14368 28380 14367 28381 14368 28381 14369 28381 14369 28382 14368 28382 14560 28382 14369 28383 14560 28383 14656 28383 14656 28384 14560 28384 14559 28384 14656 28385 14559 28385 14370 28385 14370 28386 14559 28386 14558 28386 14370 28387 14558 28387 14371 28387 14371 28388 14558 28388 14372 28388 14371 28389 14372 28389 14714 28389 14714 28390 14372 28390 14373 28390 14714 28391 14373 28391 14374 28391 14553 28392 14695 28392 14554 28392 14554 28393 14695 28393 14374 28393 14554 28394 14374 28394 14555 28394 14555 28395 14374 28395 14373 28395 14378 28396 14647 28396 14550 28396 14550 28397 14647 28397 14683 28397 14550 28398 14683 28398 14375 28398 14375 28399 14683 28399 14377 28399 14375 28400 14377 28400 14376 28400 14376 28401 14377 28401 14686 28401 14376 28402 14686 28402 14547 28402 14547 28403 14686 28403 14694 28403 14547 28404 14694 28404 14551 28404 14551 28405 14694 28405 14659 28405 14551 28406 14659 28406 14553 28406 14553 28407 14659 28407 14658 28407 14553 28408 14658 28408 14695 28408 14647 28409 14378 28409 14648 28409 14648 28410 14378 28410 14538 28410 14648 28411 14538 28411 14789 28411 14789 28412 14538 28412 14451 28412 14789 28413 14451 28413 14379 28413 14379 28414 14451 28414 14381 28414 14379 28415 14381 28415 14380 28415 14380 28416 14381 28416 14382 28416 14380 28417 14382 28417 14384 28417 14384 28418 14382 28418 14383 28418 14384 28419 14383 28419 14784 28419 14784 28420 14383 28420 14385 28420 14784 28421 14385 28421 14386 28421 14386 28422 14385 28422 14449 28422 14386 28423 14449 28423 14783 28423 14783 28424 14449 28424 14388 28424 14783 28425 14388 28425 14387 28425 14394 28426 14395 28426 14445 28426 14445 28427 14395 28427 14387 28427 14445 28428 14387 28428 14447 28428 14447 28429 14387 28429 14388 28429 14435 28430 14389 28430 14391 28430 14391 28431 14389 28431 14390 28431 14391 28432 14390 28432 14439 28432 14439 28433 14390 28433 14761 28433 14439 28434 14761 28434 14438 28434 14438 28435 14761 28435 14392 28435 14438 28436 14392 28436 14442 28436 14442 28437 14392 28437 14767 28437 14442 28438 14767 28438 14443 28438 14443 28439 14767 28439 14393 28439 14443 28440 14393 28440 14394 28440 14394 28441 14393 28441 14724 28441 14394 28442 14724 28442 14395 28442 14389 28443 14435 28443 14396 28443 14396 28444 14435 28444 14434 28444 14396 28445 14434 28445 14397 28445 14397 28446 14434 28446 14398 28446 14397 28447 14398 28447 14399 28447 14399 28448 14398 28448 14504 28448 14399 28449 14504 28449 14400 28449 14400 28450 14504 28450 14503 28450 14400 28451 14503 28451 14401 28451 14401 28452 14503 28452 14402 28452 14401 28453 14402 28453 14849 28453 14849 28454 14402 28454 14403 28454 14849 28455 14403 28455 14404 28455 14404 28456 14403 28456 14500 28456 14404 28457 14500 28457 14405 28457 14405 28458 14500 28458 14499 28458 14405 28459 14499 28459 14406 28459 14410 28460 14831 28460 14495 28460 14495 28461 14831 28461 14406 28461 14495 28462 14406 28462 14497 28462 14497 28463 14406 28463 14499 28463 14412 28464 14934 28464 14493 28464 14493 28465 14934 28465 14808 28465 14493 28466 14808 28466 14407 28466 14407 28467 14808 28467 14820 28467 14407 28468 14820 28468 14491 28468 14491 28469 14820 28469 14408 28469 14491 28470 14408 28470 14409 28470 14409 28471 14408 28471 14807 28471 14409 28472 14807 28472 14494 28472 14494 28473 14807 28473 14805 28473 14494 28474 14805 28474 14410 28474 14410 28475 14805 28475 14411 28475 14410 28476 14411 28476 14831 28476 14934 28477 14412 28477 14933 28477 14933 28478 14412 28478 14542 28478 14933 28479 14542 28479 14930 28479 14930 28480 14542 28480 14413 28480 14930 28481 14413 28481 14414 28481 14414 28482 14413 28482 14415 28482 14414 28483 14415 28483 14416 28483 14416 28484 14415 28484 14604 28484 14416 28485 14604 28485 14417 28485 14417 28486 14604 28486 14603 28486 14417 28487 14603 28487 14923 28487 14923 28488 14603 28488 14418 28488 14923 28489 14418 28489 14419 28489 14419 28490 14418 28490 14600 28490 14419 28491 14600 28491 14420 28491 14420 28492 14600 28492 14421 28492 14420 28493 14421 28493 14922 28493 14422 28494 14918 28494 14423 28494 14423 28495 14918 28495 14922 28495 14423 28496 14922 28496 14599 28496 14599 28497 14922 28497 14421 28497 14424 28498 14426 28498 14425 28498 14425 28499 14426 28499 14427 28499 14425 28500 14427 28500 14428 28500 14428 28501 14427 28501 14903 28501 14428 28502 14903 28502 14595 28502 14595 28503 14903 28503 14429 28503 14595 28504 14429 28504 14594 28504 14594 28505 14429 28505 14430 28505 14594 28506 14430 28506 14597 28506 14597 28507 14430 28507 14431 28507 14597 28508 14431 28508 14422 28508 14422 28509 14431 28509 14871 28509 14422 28510 14871 28510 14918 28510 14426 28511 14424 28511 14432 28511 14432 28512 14424 28512 14366 28512 14302 28513 14301 28513 14536 28513 14302 28514 14536 28514 14463 28514 14463 28515 14536 28515 14433 28515 14463 28516 14433 28516 14437 28516 14437 28517 14433 28517 14505 28517 14437 28518 14505 28518 14441 28518 14441 28519 14505 28519 14434 28519 14441 28520 14434 28520 14435 28520 14302 28521 14463 28521 14436 28521 14463 28522 14437 28522 14452 28522 14437 28523 14441 28523 14440 28523 14442 28524 14444 28524 14438 28524 14438 28525 14444 28525 14454 28525 14438 28526 14454 28526 14439 28526 14439 28527 14454 28527 14440 28527 14439 28528 14440 28528 14391 28528 14391 28529 14440 28529 14441 28529 14391 28530 14441 28530 14435 28530 14442 28531 14443 28531 14444 28531 14444 28532 14443 28532 14394 28532 14444 28533 14394 28533 14456 28533 14456 28534 14394 28534 14445 28534 14456 28535 14445 28535 14446 28535 14446 28536 14445 28536 14447 28536 14446 28537 14447 28537 14448 28537 14381 28538 14461 28538 14460 28538 14447 28539 14388 28539 14448 28539 14448 28540 14388 28540 14449 28540 14448 28541 14449 28541 14459 28541 14459 28542 14449 28542 14385 28542 14459 28543 14385 28543 14450 28543 14450 28544 14385 28544 14383 28544 14450 28545 14383 28545 14460 28545 14460 28546 14383 28546 14382 28546 14460 28547 14382 28547 14381 28547 14381 28548 14451 28548 14461 28548 14461 28549 14451 28549 14538 28549 14461 28550 14538 28550 14462 28550 14437 28551 14440 28551 14452 28551 14452 28552 14440 28552 14454 28552 14452 28553 14454 28553 14453 28553 14453 28554 14454 28554 14444 28554 14453 28555 14444 28555 14455 28555 14455 28556 14444 28556 14456 28556 14455 28557 14456 28557 14465 28557 14465 28558 14456 28558 14446 28558 14465 28559 14446 28559 14457 28559 14457 28560 14446 28560 14448 28560 14457 28561 14448 28561 14458 28561 14458 28562 14448 28562 14459 28562 14458 28563 14459 28563 14468 28563 14468 28564 14459 28564 14450 28564 14468 28565 14450 28565 14470 28565 14470 28566 14450 28566 14460 28566 14470 28567 14460 28567 14473 28567 14473 28568 14460 28568 14461 28568 14473 28569 14461 28569 14474 28569 14474 28570 14461 28570 14462 28570 14474 28571 14462 28571 14476 28571 14463 28572 14452 28572 14436 28572 14436 28573 14452 28573 14453 28573 14436 28574 14453 28574 14478 28574 14478 28575 14453 28575 14455 28575 14478 28576 14455 28576 14464 28576 14464 28577 14455 28577 14465 28577 14464 28578 14465 28578 14466 28578 14466 28579 14465 28579 14457 28579 14466 28580 14457 28580 14483 28580 14483 28581 14457 28581 14458 28581 14483 28582 14458 28582 14467 28582 14467 28583 14458 28583 14468 28583 14467 28584 14468 28584 14469 28584 14469 28585 14468 28585 14470 28585 14469 28586 14470 28586 14471 28586 14471 28587 14470 28587 14473 28587 14471 28588 14473 28588 14472 28588 14472 28589 14473 28589 14474 28589 14472 28590 14474 28590 14475 28590 14475 28591 14474 28591 14476 28591 14475 28592 14476 28592 14487 28592 14302 28593 14436 28593 14477 28593 14477 28594 14436 28594 14478 28594 14477 28595 14478 28595 14479 28595 14479 28596 14478 28596 14464 28596 14479 28597 14464 28597 14480 28597 14480 28598 14464 28598 14466 28598 14480 28599 14466 28599 14481 28599 14481 28600 14466 28600 14483 28600 14481 28601 14483 28601 14482 28601 14482 28602 14483 28602 14467 28602 14482 28603 14467 28603 14300 28603 14300 28604 14467 28604 14469 28604 14300 28605 14469 28605 14289 28605 14289 28606 14469 28606 14471 28606 14289 28607 14471 28607 14484 28607 14484 28608 14471 28608 14472 28608 14484 28609 14472 28609 14485 28609 14485 28610 14472 28610 14475 28610 14485 28611 14475 28611 14486 28611 14486 28612 14475 28612 14487 28612 14486 28613 14487 28613 14305 28613 14540 28614 14489 28614 14488 28614 14489 28615 14490 28615 14507 28615 14490 28616 14541 28616 14506 28616 14409 28617 14508 28617 14491 28617 14491 28618 14508 28618 14492 28618 14491 28619 14492 28619 14407 28619 14407 28620 14492 28620 14506 28620 14407 28621 14506 28621 14493 28621 14493 28622 14506 28622 14541 28622 14493 28623 14541 28623 14412 28623 14409 28624 14494 28624 14508 28624 14508 28625 14494 28625 14410 28625 14508 28626 14410 28626 14509 28626 14509 28627 14410 28627 14495 28627 14509 28628 14495 28628 14496 28628 14496 28629 14495 28629 14497 28629 14496 28630 14497 28630 14498 28630 14504 28631 14515 28631 14502 28631 14497 28632 14499 28632 14498 28632 14498 28633 14499 28633 14500 28633 14498 28634 14500 28634 14512 28634 14512 28635 14500 28635 14403 28635 14512 28636 14403 28636 14501 28636 14501 28637 14403 28637 14402 28637 14501 28638 14402 28638 14502 28638 14502 28639 14402 28639 14503 28639 14502 28640 14503 28640 14504 28640 14504 28641 14398 28641 14515 28641 14515 28642 14398 28642 14434 28642 14515 28643 14434 28643 14505 28643 14490 28644 14506 28644 14507 28644 14507 28645 14506 28645 14492 28645 14507 28646 14492 28646 14516 28646 14516 28647 14492 28647 14508 28647 14516 28648 14508 28648 14517 28648 14517 28649 14508 28649 14509 28649 14517 28650 14509 28650 14510 28650 14510 28651 14509 28651 14496 28651 14510 28652 14496 28652 14511 28652 14511 28653 14496 28653 14498 28653 14511 28654 14498 28654 14520 28654 14520 28655 14498 28655 14512 28655 14520 28656 14512 28656 14513 28656 14513 28657 14512 28657 14501 28657 14513 28658 14501 28658 14514 28658 14514 28659 14501 28659 14502 28659 14514 28660 14502 28660 14521 28660 14521 28661 14502 28661 14515 28661 14521 28662 14515 28662 14523 28662 14523 28663 14515 28663 14505 28663 14523 28664 14505 28664 14433 28664 14489 28665 14507 28665 14488 28665 14488 28666 14507 28666 14516 28666 14488 28667 14516 28667 14526 28667 14526 28668 14516 28668 14517 28668 14526 28669 14517 28669 14518 28669 14518 28670 14517 28670 14510 28670 14518 28671 14510 28671 14519 28671 14519 28672 14510 28672 14511 28672 14519 28673 14511 28673 14528 28673 14528 28674 14511 28674 14520 28674 14528 28675 14520 28675 14530 28675 14530 28676 14520 28676 14513 28676 14530 28677 14513 28677 14531 28677 14531 28678 14513 28678 14514 28678 14531 28679 14514 28679 14522 28679 14522 28680 14514 28680 14521 28680 14522 28681 14521 28681 14533 28681 14533 28682 14521 28682 14523 28682 14533 28683 14523 28683 14534 28683 14534 28684 14523 28684 14433 28684 14534 28685 14433 28685 14536 28685 14540 28686 14488 28686 14524 28686 14524 28687 14488 28687 14526 28687 14524 28688 14526 28688 14525 28688 14525 28689 14526 28689 14518 28689 14525 28690 14518 28690 14293 28690 14293 28691 14518 28691 14519 28691 14293 28692 14519 28692 14527 28692 14527 28693 14519 28693 14528 28693 14527 28694 14528 28694 14529 28694 14529 28695 14528 28695 14530 28695 14529 28696 14530 28696 14307 28696 14307 28697 14530 28697 14531 28697 14307 28698 14531 28698 14303 28698 14303 28699 14531 28699 14522 28699 14303 28700 14522 28700 14532 28700 14532 28701 14522 28701 14533 28701 14532 28702 14533 28702 14290 28702 14290 28703 14533 28703 14534 28703 14290 28704 14534 28704 14535 28704 14535 28705 14534 28705 14536 28705 14535 28706 14536 28706 14301 28706 14543 28707 14305 28707 14487 28707 14543 28708 14487 28708 14544 28708 14544 28709 14487 28709 14476 28709 14544 28710 14476 28710 14546 28710 14546 28711 14476 28711 14462 28711 14546 28712 14462 28712 14537 28712 14537 28713 14462 28713 14538 28713 14537 28714 14538 28714 14378 28714 14540 28715 14539 28715 14638 28715 14540 28716 14638 28716 14489 28716 14489 28717 14638 28717 14617 28717 14489 28718 14617 28718 14490 28718 14490 28719 14617 28719 14616 28719 14490 28720 14616 28720 14541 28720 14541 28721 14616 28721 14542 28721 14541 28722 14542 28722 14412 28722 14543 28723 14544 28723 14571 28723 14544 28724 14546 28724 14545 28724 14546 28725 14537 28725 14549 28725 14547 28726 14552 28726 14376 28726 14376 28727 14552 28727 14548 28727 14376 28728 14548 28728 14375 28728 14375 28729 14548 28729 14549 28729 14375 28730 14549 28730 14550 28730 14550 28731 14549 28731 14537 28731 14550 28732 14537 28732 14378 28732 14547 28733 14551 28733 14552 28733 14552 28734 14551 28734 14553 28734 14552 28735 14553 28735 14564 28735 14564 28736 14553 28736 14554 28736 14564 28737 14554 28737 14566 28737 14566 28738 14554 28738 14555 28738 14566 28739 14555 28739 14567 28739 14368 28740 14562 28740 14556 28740 14555 28741 14373 28741 14567 28741 14567 28742 14373 28742 14372 28742 14567 28743 14372 28743 14557 28743 14557 28744 14372 28744 14558 28744 14557 28745 14558 28745 14569 28745 14569 28746 14558 28746 14559 28746 14569 28747 14559 28747 14556 28747 14556 28748 14559 28748 14560 28748 14556 28749 14560 28749 14368 28749 14368 28750 14561 28750 14562 28750 14562 28751 14561 28751 14642 28751 14562 28752 14642 28752 14641 28752 14546 28753 14549 28753 14545 28753 14545 28754 14549 28754 14548 28754 14545 28755 14548 28755 14563 28755 14563 28756 14548 28756 14552 28756 14563 28757 14552 28757 14573 28757 14573 28758 14552 28758 14564 28758 14573 28759 14564 28759 14565 28759 14565 28760 14564 28760 14566 28760 14565 28761 14566 28761 14575 28761 14575 28762 14566 28762 14567 28762 14575 28763 14567 28763 14577 28763 14577 28764 14567 28764 14557 28764 14577 28765 14557 28765 14568 28765 14568 28766 14557 28766 14569 28766 14568 28767 14569 28767 14579 28767 14579 28768 14569 28768 14556 28768 14579 28769 14556 28769 14581 28769 14581 28770 14556 28770 14562 28770 14581 28771 14562 28771 14582 28771 14582 28772 14562 28772 14641 28772 14582 28773 14641 28773 14570 28773 14544 28774 14545 28774 14571 28774 14571 28775 14545 28775 14563 28775 14571 28776 14563 28776 14583 28776 14583 28777 14563 28777 14573 28777 14583 28778 14573 28778 14572 28778 14572 28779 14573 28779 14565 28779 14572 28780 14565 28780 14574 28780 14574 28781 14565 28781 14575 28781 14574 28782 14575 28782 14576 28782 14576 28783 14575 28783 14577 28783 14576 28784 14577 28784 14578 28784 14578 28785 14577 28785 14568 28785 14578 28786 14568 28786 14586 28786 14586 28787 14568 28787 14579 28787 14586 28788 14579 28788 14580 28788 14580 28789 14579 28789 14581 28789 14580 28790 14581 28790 14589 28790 14589 28791 14581 28791 14582 28791 14589 28792 14582 28792 14590 28792 14590 28793 14582 28793 14570 28793 14590 28794 14570 28794 14591 28794 14543 28795 14571 28795 14278 28795 14278 28796 14571 28796 14583 28796 14278 28797 14583 28797 14584 28797 14584 28798 14583 28798 14572 28798 14584 28799 14572 28799 14585 28799 14585 28800 14572 28800 14574 28800 14585 28801 14574 28801 14288 28801 14288 28802 14574 28802 14576 28802 14288 28803 14576 28803 14284 28803 14284 28804 14576 28804 14578 28804 14284 28805 14578 28805 14285 28805 14285 28806 14578 28806 14586 28806 14285 28807 14586 28807 14286 28807 14286 28808 14586 28808 14580 28808 14286 28809 14580 28809 14587 28809 14587 28810 14580 28810 14589 28810 14587 28811 14589 28811 14588 28811 14588 28812 14589 28812 14590 28812 14588 28813 14590 28813 14279 28813 14279 28814 14590 28814 14591 28814 14279 28815 14591 28815 14282 28815 14643 28816 14644 28816 14618 28816 14644 28817 14592 28817 14606 28817 14592 28818 14593 28818 14607 28818 14594 28819 14608 28819 14595 28819 14595 28820 14608 28820 14596 28820 14595 28821 14596 28821 14428 28821 14428 28822 14596 28822 14607 28822 14428 28823 14607 28823 14425 28823 14425 28824 14607 28824 14593 28824 14425 28825 14593 28825 14424 28825 14594 28826 14597 28826 14608 28826 14608 28827 14597 28827 14422 28827 14608 28828 14422 28828 14598 28828 14598 28829 14422 28829 14423 28829 14598 28830 14423 28830 14610 28830 14610 28831 14423 28831 14599 28831 14610 28832 14599 28832 14611 28832 14415 28833 14605 28833 14613 28833 14599 28834 14421 28834 14611 28834 14611 28835 14421 28835 14600 28835 14611 28836 14600 28836 14601 28836 14601 28837 14600 28837 14418 28837 14601 28838 14418 28838 14602 28838 14602 28839 14418 28839 14603 28839 14602 28840 14603 28840 14613 28840 14613 28841 14603 28841 14604 28841 14613 28842 14604 28842 14415 28842 14415 28843 14413 28843 14605 28843 14605 28844 14413 28844 14542 28844 14605 28845 14542 28845 14616 28845 14592 28846 14607 28846 14606 28846 14606 28847 14607 28847 14596 28847 14606 28848 14596 28848 14619 28848 14619 28849 14596 28849 14608 28849 14619 28850 14608 28850 14621 28850 14621 28851 14608 28851 14598 28851 14621 28852 14598 28852 14622 28852 14622 28853 14598 28853 14610 28853 14622 28854 14610 28854 14609 28854 14609 28855 14610 28855 14611 28855 14609 28856 14611 28856 14612 28856 14612 28857 14611 28857 14601 28857 14612 28858 14601 28858 14624 28858 14624 28859 14601 28859 14602 28859 14624 28860 14602 28860 14625 28860 14625 28861 14602 28861 14613 28861 14625 28862 14613 28862 14614 28862 14614 28863 14613 28863 14605 28863 14614 28864 14605 28864 14615 28864 14615 28865 14605 28865 14616 28865 14615 28866 14616 28866 14617 28866 14644 28867 14606 28867 14618 28867 14618 28868 14606 28868 14619 28868 14618 28869 14619 28869 14620 28869 14620 28870 14619 28870 14621 28870 14620 28871 14621 28871 14628 28871 14628 28872 14621 28872 14622 28872 14628 28873 14622 28873 14629 28873 14629 28874 14622 28874 14609 28874 14629 28875 14609 28875 14630 28875 14630 28876 14609 28876 14612 28876 14630 28877 14612 28877 14623 28877 14623 28878 14612 28878 14624 28878 14623 28879 14624 28879 14633 28879 14633 28880 14624 28880 14625 28880 14633 28881 14625 28881 14635 28881 14635 28882 14625 28882 14614 28882 14635 28883 14614 28883 14626 28883 14626 28884 14614 28884 14615 28884 14626 28885 14615 28885 14637 28885 14637 28886 14615 28886 14617 28886 14637 28887 14617 28887 14638 28887 14643 28888 14618 28888 14283 28888 14283 28889 14618 28889 14620 28889 14283 28890 14620 28890 14281 28890 14281 28891 14620 28891 14628 28891 14281 28892 14628 28892 14627 28892 14627 28893 14628 28893 14629 28893 14627 28894 14629 28894 14631 28894 14631 28895 14629 28895 14630 28895 14631 28896 14630 28896 14296 28896 14296 28897 14630 28897 14623 28897 14296 28898 14623 28898 14632 28898 14632 28899 14623 28899 14633 28899 14632 28900 14633 28900 14634 28900 14634 28901 14633 28901 14635 28901 14634 28902 14635 28902 14295 28902 14295 28903 14635 28903 14626 28903 14295 28904 14626 28904 14636 28904 14636 28905 14626 28905 14637 28905 14636 28906 14637 28906 14294 28906 14294 28907 14637 28907 14638 28907 14294 28908 14638 28908 14539 28908 14639 28909 14282 28909 14591 28909 14639 28910 14591 28910 14645 28910 14645 28911 14591 28911 14570 28911 14645 28912 14570 28912 14640 28912 14640 28913 14570 28913 14641 28913 14640 28914 14641 28914 14646 28914 14646 28915 14641 28915 14642 28915 14646 28916 14642 28916 14366 28916 14643 28917 14639 28917 14645 28917 14643 28918 14645 28918 14644 28918 14644 28919 14645 28919 14640 28919 14644 28920 14640 28920 14592 28920 14592 28921 14640 28921 14646 28921 14592 28922 14646 28922 14593 28922 14593 28923 14646 28923 14366 28923 14593 28924 14366 28924 14424 28924 14647 28925 14648 28925 14684 28925 14684 28926 14648 28926 14759 28926 14684 28927 14759 28927 14649 28927 14649 28928 14759 28928 14758 28928 14649 28929 14758 28929 14650 28929 14650 28930 14758 28930 14651 28930 14650 28931 14651 28931 14667 28931 14667 28932 14651 28932 14755 28932 14667 28933 14755 28933 14668 28933 14668 28934 14755 28934 14652 28934 14668 28935 14652 28935 14653 28935 14653 28936 14652 28936 14754 28936 14653 28937 14754 28937 14654 28937 14654 28938 14754 28938 14655 28938 14654 28939 14655 28939 14356 28939 14356 28940 14655 28940 14340 28940 14656 28941 14370 28941 14715 28941 14371 28942 14714 28942 14657 28942 14658 28943 14659 28943 14697 28943 14377 28944 14683 28944 14685 28944 14674 28945 14332 28945 14338 28945 14356 28946 14357 28946 14654 28946 14654 28947 14357 28947 14660 28947 14654 28948 14660 28948 14653 28948 14653 28949 14660 28949 14692 28949 14344 28950 14343 28950 14718 28950 14718 28951 14343 28951 14665 28951 14718 28952 14665 28952 14661 28952 14661 28953 14665 28953 14662 28953 14661 28954 14662 28954 14717 28954 14717 28955 14662 28955 14664 28955 14717 28956 14664 28956 14663 28956 14663 28957 14664 28957 14680 28957 14663 28958 14680 28958 14715 28958 14343 28959 14332 28959 14665 28959 14665 28960 14332 28960 14674 28960 14665 28961 14674 28961 14662 28961 14662 28962 14674 28962 14666 28962 14662 28963 14666 28963 14664 28963 14664 28964 14666 28964 14678 28964 14664 28965 14678 28965 14680 28965 14680 28966 14678 28966 14681 28966 14685 28967 14649 28967 14689 28967 14689 28968 14649 28968 14650 28968 14689 28969 14650 28969 14690 28969 14690 28970 14650 28970 14667 28970 14690 28971 14667 28971 14692 28971 14692 28972 14667 28972 14668 28972 14692 28973 14668 28973 14653 28973 14693 28974 14702 28974 14669 28974 14669 28975 14702 28975 14670 28975 14669 28976 14670 28976 14691 28976 14691 28977 14670 28977 14700 28977 14691 28978 14700 28978 14671 28978 14671 28979 14700 28979 14699 28979 14671 28980 14699 28980 14688 28980 14688 28981 14699 28981 14672 28981 14688 28982 14672 28982 14687 28982 14687 28983 14672 28983 14697 28983 14338 28984 14673 28984 14674 28984 14674 28985 14673 28985 14675 28985 14674 28986 14675 28986 14666 28986 14666 28987 14675 28987 14676 28987 14666 28988 14676 28988 14678 28988 14678 28989 14676 28989 14677 28989 14678 28990 14677 28990 14681 28990 14681 28991 14677 28991 14679 28991 14681 28992 14679 28992 14682 28992 14715 28993 14680 28993 14720 28993 14720 28994 14680 28994 14681 28994 14720 28995 14681 28995 14722 28995 14722 28996 14681 28996 14682 28996 14722 28997 14682 28997 14792 28997 14683 28998 14647 28998 14685 28998 14685 28999 14647 28999 14684 28999 14685 29000 14684 29000 14649 29000 14686 29001 14377 29001 14687 29001 14687 29002 14377 29002 14685 29002 14687 29003 14685 29003 14688 29003 14688 29004 14685 29004 14689 29004 14688 29005 14689 29005 14671 29005 14671 29006 14689 29006 14690 29006 14671 29007 14690 29007 14691 29007 14691 29008 14690 29008 14692 29008 14691 29009 14692 29009 14669 29009 14669 29010 14692 29010 14660 29010 14669 29011 14660 29011 14693 29011 14693 29012 14660 29012 14357 29012 14697 29013 14659 29013 14687 29013 14687 29014 14659 29014 14694 29014 14687 29015 14694 29015 14686 29015 14695 29016 14658 29016 14696 29016 14696 29017 14658 29017 14697 29017 14696 29018 14697 29018 14707 29018 14707 29019 14697 29019 14672 29019 14707 29020 14672 29020 14698 29020 14698 29021 14672 29021 14699 29021 14698 29022 14699 29022 14705 29022 14705 29023 14699 29023 14700 29023 14705 29024 14700 29024 14704 29024 14704 29025 14700 29025 14670 29025 14704 29026 14670 29026 14701 29026 14701 29027 14670 29027 14702 29027 14701 29028 14350 29028 14704 29028 14704 29029 14350 29029 14703 29029 14704 29030 14703 29030 14705 29030 14705 29031 14703 29031 14706 29031 14705 29032 14706 29032 14698 29032 14698 29033 14706 29033 14711 29033 14698 29034 14711 29034 14707 29034 14707 29035 14711 29035 14713 29035 14707 29036 14713 29036 14696 29036 14696 29037 14713 29037 14708 29037 14696 29038 14708 29038 14695 29038 14695 29039 14708 29039 14374 29039 14350 29040 14709 29040 14703 29040 14703 29041 14709 29041 14719 29041 14703 29042 14719 29042 14706 29042 14706 29043 14719 29043 14710 29043 14706 29044 14710 29044 14711 29044 14711 29045 14710 29045 14712 29045 14711 29046 14712 29046 14713 29046 14713 29047 14712 29047 14716 29047 14713 29048 14716 29048 14708 29048 14708 29049 14716 29049 14657 29049 14708 29050 14657 29050 14374 29050 14374 29051 14657 29051 14714 29051 14370 29052 14371 29052 14715 29052 14715 29053 14371 29053 14657 29053 14715 29054 14657 29054 14663 29054 14663 29055 14657 29055 14716 29055 14663 29056 14716 29056 14717 29056 14717 29057 14716 29057 14712 29057 14717 29058 14712 29058 14661 29058 14661 29059 14712 29059 14710 29059 14661 29060 14710 29060 14718 29060 14718 29061 14710 29061 14719 29061 14718 29062 14719 29062 14344 29062 14344 29063 14719 29063 14709 29063 14656 29064 14715 29064 14369 29064 14369 29065 14715 29065 14720 29065 14369 29066 14720 29066 14367 29066 14367 29067 14720 29067 14722 29067 14367 29068 14722 29068 14721 29068 14721 29069 14722 29069 14792 29069 14721 29070 14792 29070 14723 29070 14384 29071 14784 29071 14734 29071 14386 29072 14783 29072 14785 29072 14724 29073 14393 29073 14766 29073 14761 29074 14390 29074 14741 29074 14725 29075 14726 29075 14340 29075 14363 29076 14727 29076 14728 29076 14728 29077 14727 29077 14729 29077 14728 29078 14729 29078 14745 29078 14745 29079 14729 29079 14765 29079 14730 29080 14355 29080 14731 29080 14731 29081 14355 29081 14735 29081 14731 29082 14735 29082 14732 29082 14732 29083 14735 29083 14736 29083 14732 29084 14736 29084 14733 29084 14733 29085 14736 29085 14738 29085 14733 29086 14738 29086 14786 29086 14786 29087 14738 29087 14740 29087 14786 29088 14740 29088 14734 29088 14355 29089 14726 29089 14735 29089 14735 29090 14726 29090 14725 29090 14735 29091 14725 29091 14736 29091 14736 29092 14725 29092 14737 29092 14736 29093 14737 29093 14738 29093 14738 29094 14737 29094 14739 29094 14738 29095 14739 29095 14740 29095 14740 29096 14739 29096 14756 29096 14741 29097 14742 29097 14762 29097 14762 29098 14742 29098 14743 29098 14762 29099 14743 29099 14763 29099 14763 29100 14743 29100 14795 29100 14763 29101 14795 29101 14765 29101 14765 29102 14795 29102 14744 29102 14765 29103 14744 29103 14745 29103 14746 29104 14747 29104 14764 29104 14764 29105 14747 29105 14772 29105 14764 29106 14772 29106 14748 29106 14748 29107 14772 29107 14749 29107 14748 29108 14749 29108 14750 29108 14750 29109 14749 29109 14751 29109 14750 29110 14751 29110 14753 29110 14753 29111 14751 29111 14752 29111 14753 29112 14752 29112 14760 29112 14760 29113 14752 29113 14766 29113 14340 29114 14655 29114 14725 29114 14725 29115 14655 29115 14754 29115 14725 29116 14754 29116 14737 29116 14737 29117 14754 29117 14652 29117 14737 29118 14652 29118 14739 29118 14739 29119 14652 29119 14755 29119 14739 29120 14755 29120 14756 29120 14756 29121 14755 29121 14651 29121 14756 29122 14651 29122 14758 29122 14734 29123 14740 29123 14788 29123 14788 29124 14740 29124 14756 29124 14788 29125 14756 29125 14757 29125 14757 29126 14756 29126 14758 29126 14757 29127 14758 29127 14759 29127 14390 29128 14389 29128 14741 29128 14741 29129 14389 29129 14797 29129 14741 29130 14797 29130 14742 29130 14392 29131 14761 29131 14760 29131 14760 29132 14761 29132 14741 29132 14760 29133 14741 29133 14753 29133 14753 29134 14741 29134 14762 29134 14753 29135 14762 29135 14750 29135 14750 29136 14762 29136 14763 29136 14750 29137 14763 29137 14748 29137 14748 29138 14763 29138 14765 29138 14748 29139 14765 29139 14764 29139 14764 29140 14765 29140 14729 29140 14764 29141 14729 29141 14746 29141 14746 29142 14729 29142 14727 29142 14766 29143 14393 29143 14760 29143 14760 29144 14393 29144 14767 29144 14760 29145 14767 29145 14392 29145 14395 29146 14724 29146 14768 29146 14768 29147 14724 29147 14766 29147 14768 29148 14766 29148 14775 29148 14775 29149 14766 29149 14752 29149 14775 29150 14752 29150 14769 29150 14769 29151 14752 29151 14751 29151 14769 29152 14751 29152 14770 29152 14770 29153 14751 29153 14749 29153 14770 29154 14749 29154 14771 29154 14771 29155 14749 29155 14772 29155 14771 29156 14772 29156 14353 29156 14353 29157 14772 29157 14747 29157 14353 29158 14352 29158 14771 29158 14771 29159 14352 29159 14773 29159 14771 29160 14773 29160 14770 29160 14770 29161 14773 29161 14774 29161 14770 29162 14774 29162 14769 29162 14769 29163 14774 29163 14778 29163 14769 29164 14778 29164 14775 29164 14775 29165 14778 29165 14780 29165 14775 29166 14780 29166 14768 29166 14768 29167 14780 29167 14782 29167 14768 29168 14782 29168 14395 29168 14395 29169 14782 29169 14387 29169 14352 29170 14776 29170 14773 29170 14773 29171 14776 29171 14777 29171 14773 29172 14777 29172 14774 29172 14774 29173 14777 29173 14787 29173 14774 29174 14787 29174 14778 29174 14778 29175 14787 29175 14779 29175 14778 29176 14779 29176 14780 29176 14780 29177 14779 29177 14781 29177 14780 29178 14781 29178 14782 29178 14782 29179 14781 29179 14785 29179 14782 29180 14785 29180 14387 29180 14387 29181 14785 29181 14783 29181 14784 29182 14386 29182 14734 29182 14734 29183 14386 29183 14785 29183 14734 29184 14785 29184 14786 29184 14786 29185 14785 29185 14781 29185 14786 29186 14781 29186 14733 29186 14733 29187 14781 29187 14779 29187 14733 29188 14779 29188 14732 29188 14732 29189 14779 29189 14787 29189 14732 29190 14787 29190 14731 29190 14731 29191 14787 29191 14777 29191 14731 29192 14777 29192 14730 29192 14730 29193 14777 29193 14776 29193 14384 29194 14734 29194 14380 29194 14380 29195 14734 29195 14788 29195 14380 29196 14788 29196 14379 29196 14379 29197 14788 29197 14757 29197 14379 29198 14757 29198 14789 29198 14789 29199 14757 29199 14759 29199 14789 29200 14759 29200 14648 29200 14338 29201 14336 29201 14673 29201 14673 29202 14336 29202 14801 29202 14673 29203 14801 29203 14675 29203 14675 29204 14801 29204 14676 29204 14676 29205 14801 29205 14790 29205 14676 29206 14790 29206 14677 29206 14677 29207 14790 29207 14679 29207 14679 29208 14790 29208 14791 29208 14679 29209 14791 29209 14682 29209 14682 29210 14791 29210 14792 29210 14792 29211 14791 29211 14432 29211 14792 29212 14432 29212 14723 29212 14810 29213 14363 29213 14793 29213 14793 29214 14363 29214 14728 29214 14793 29215 14728 29215 14794 29215 14794 29216 14728 29216 14745 29216 14794 29217 14745 29217 14816 29217 14816 29218 14745 29218 14744 29218 14816 29219 14744 29219 14796 29219 14796 29220 14744 29220 14795 29220 14796 29221 14795 29221 14867 29221 14867 29222 14795 29222 14743 29222 14867 29223 14743 29223 14868 29223 14868 29224 14743 29224 14742 29224 14868 29225 14742 29225 14869 29225 14869 29226 14742 29226 14797 29226 14869 29227 14797 29227 14396 29227 14396 29228 14797 29228 14389 29228 14798 29229 14799 29229 14336 29229 14336 29230 14799 29230 14801 29230 14799 29231 14874 29231 14801 29231 14801 29232 14874 29232 14800 29232 14801 29233 14800 29233 14790 29233 14800 29234 14891 29234 14790 29234 14790 29235 14891 29235 14802 29235 14790 29236 14802 29236 14791 29236 14426 29237 14432 29237 14803 29237 14803 29238 14432 29238 14791 29238 14803 29239 14791 29239 14888 29239 14888 29240 14791 29240 14802 29240 14399 29241 14400 29241 14804 29241 14401 29242 14849 29242 14855 29242 14404 29243 14405 29243 14848 29243 14411 29244 14805 29244 14806 29244 14807 29245 14408 29245 14821 29245 14820 29246 14808 29246 14809 29246 14865 29247 14866 29247 14810 29247 14346 29248 14812 29248 14811 29248 14811 29249 14812 29249 14813 29249 14811 29250 14813 29250 14814 29250 14814 29251 14813 29251 14817 29251 14810 29252 14793 29252 14865 29252 14865 29253 14793 29253 14794 29253 14865 29254 14794 29254 14815 29254 14815 29255 14794 29255 14816 29255 14815 29256 14816 29256 14862 29256 14862 29257 14816 29257 14796 29257 14862 29258 14796 29258 14860 29258 14809 29259 14819 29259 14822 29259 14822 29260 14819 29260 14936 29260 14822 29261 14936 29261 14823 29261 14823 29262 14936 29262 14937 29262 14823 29263 14937 29263 14817 29263 14817 29264 14937 29264 14939 29264 14817 29265 14939 29265 14814 29265 14808 29266 14934 29266 14809 29266 14809 29267 14934 29267 14818 29267 14809 29268 14818 29268 14819 29268 14408 29269 14820 29269 14821 29269 14821 29270 14820 29270 14809 29270 14821 29271 14809 29271 14825 29271 14825 29272 14809 29272 14822 29272 14825 29273 14822 29273 14827 29273 14827 29274 14822 29274 14823 29274 14827 29275 14823 29275 14828 29275 14828 29276 14823 29276 14817 29276 14828 29277 14817 29277 14824 29277 14824 29278 14817 29278 14813 29278 14824 29279 14813 29279 14365 29279 14365 29280 14813 29280 14812 29280 14805 29281 14807 29281 14806 29281 14806 29282 14807 29282 14821 29282 14806 29283 14821 29283 14834 29283 14834 29284 14821 29284 14825 29284 14834 29285 14825 29285 14826 29285 14826 29286 14825 29286 14827 29286 14826 29287 14827 29287 14835 29287 14835 29288 14827 29288 14828 29288 14835 29289 14828 29289 14829 29289 14829 29290 14828 29290 14824 29290 14829 29291 14824 29291 14830 29291 14830 29292 14824 29292 14365 29292 14831 29293 14411 29293 14832 29293 14832 29294 14411 29294 14806 29294 14832 29295 14806 29295 14833 29295 14833 29296 14806 29296 14834 29296 14833 29297 14834 29297 14839 29297 14839 29298 14834 29298 14826 29298 14839 29299 14826 29299 14838 29299 14838 29300 14826 29300 14835 29300 14838 29301 14835 29301 14837 29301 14837 29302 14835 29302 14829 29302 14837 29303 14829 29303 14836 29303 14836 29304 14829 29304 14830 29304 14836 29305 14359 29305 14837 29305 14837 29306 14359 29306 14843 29306 14837 29307 14843 29307 14838 29307 14838 29308 14843 29308 14846 29308 14838 29309 14846 29309 14839 29309 14839 29310 14846 29310 14840 29310 14839 29311 14840 29311 14833 29311 14833 29312 14840 29312 14841 29312 14833 29313 14841 29313 14832 29313 14832 29314 14841 29314 14842 29314 14832 29315 14842 29315 14831 29315 14831 29316 14842 29316 14406 29316 14359 29317 14844 29317 14843 29317 14843 29318 14844 29318 14845 29318 14843 29319 14845 29319 14846 29319 14846 29320 14845 29320 14853 29320 14846 29321 14853 29321 14840 29321 14840 29322 14853 29322 14852 29322 14840 29323 14852 29323 14841 29323 14841 29324 14852 29324 14847 29324 14841 29325 14847 29325 14842 29325 14842 29326 14847 29326 14848 29326 14842 29327 14848 29327 14406 29327 14406 29328 14848 29328 14405 29328 14849 29329 14404 29329 14855 29329 14855 29330 14404 29330 14848 29330 14855 29331 14848 29331 14856 29331 14856 29332 14848 29332 14847 29332 14856 29333 14847 29333 14850 29333 14850 29334 14847 29334 14852 29334 14850 29335 14852 29335 14851 29335 14851 29336 14852 29336 14853 29336 14851 29337 14853 29337 14854 29337 14854 29338 14853 29338 14845 29338 14854 29339 14845 29339 14360 29339 14360 29340 14845 29340 14844 29340 14400 29341 14401 29341 14804 29341 14804 29342 14401 29342 14855 29342 14804 29343 14855 29343 14861 29343 14861 29344 14855 29344 14856 29344 14861 29345 14856 29345 14863 29345 14863 29346 14856 29346 14850 29346 14863 29347 14850 29347 14864 29347 14864 29348 14850 29348 14851 29348 14864 29349 14851 29349 14857 29349 14857 29350 14851 29350 14854 29350 14857 29351 14854 29351 14858 29351 14858 29352 14854 29352 14360 29352 14397 29353 14399 29353 14859 29353 14859 29354 14399 29354 14804 29354 14859 29355 14804 29355 14860 29355 14860 29356 14804 29356 14861 29356 14860 29357 14861 29357 14862 29357 14862 29358 14861 29358 14863 29358 14862 29359 14863 29359 14815 29359 14815 29360 14863 29360 14864 29360 14815 29361 14864 29361 14865 29361 14865 29362 14864 29362 14857 29362 14865 29363 14857 29363 14866 29363 14866 29364 14857 29364 14858 29364 14796 29365 14867 29365 14860 29365 14860 29366 14867 29366 14868 29366 14860 29367 14868 29367 14859 29367 14859 29368 14868 29368 14869 29368 14859 29369 14869 29369 14397 29369 14397 29370 14869 29370 14396 29370 14417 29371 14923 29371 14900 29371 14419 29372 14420 29372 14870 29372 14871 29373 14431 29373 14872 29373 14903 29374 14427 29374 14873 29374 14884 29375 14882 29375 14345 29375 14798 29376 14335 29376 14799 29376 14799 29377 14335 29377 14905 29377 14799 29378 14905 29378 14874 29378 14874 29379 14905 29379 14875 29379 14876 29380 14877 29380 14926 29380 14926 29381 14877 29381 14883 29381 14926 29382 14883 29382 14878 29382 14878 29383 14883 29383 14886 29383 14878 29384 14886 29384 14925 29384 14925 29385 14886 29385 14879 29385 14925 29386 14879 29386 14880 29386 14880 29387 14879 29387 14881 29387 14880 29388 14881 29388 14900 29388 14877 29389 14882 29389 14883 29389 14883 29390 14882 29390 14884 29390 14883 29391 14884 29391 14886 29391 14886 29392 14884 29392 14885 29392 14886 29393 14885 29393 14879 29393 14879 29394 14885 29394 14887 29394 14879 29395 14887 29395 14881 29395 14881 29396 14887 29396 14902 29396 14873 29397 14888 29397 14889 29397 14889 29398 14888 29398 14802 29398 14889 29399 14802 29399 14890 29399 14890 29400 14802 29400 14891 29400 14890 29401 14891 29401 14875 29401 14875 29402 14891 29402 14800 29402 14875 29403 14800 29403 14874 29403 14334 29404 14893 29404 14892 29404 14892 29405 14893 29405 14895 29405 14892 29406 14895 29406 14894 29406 14894 29407 14895 29407 14910 29407 14894 29408 14910 29408 14904 29408 14904 29409 14910 29409 14909 29409 14904 29410 14909 29410 14896 29410 14896 29411 14909 29411 14908 29411 14896 29412 14908 29412 14897 29412 14897 29413 14908 29413 14872 29413 14345 29414 14898 29414 14884 29414 14884 29415 14898 29415 14899 29415 14884 29416 14899 29416 14885 29416 14885 29417 14899 29417 14941 29417 14885 29418 14941 29418 14887 29418 14887 29419 14941 29419 14940 29419 14887 29420 14940 29420 14902 29420 14902 29421 14940 29421 14938 29421 14902 29422 14938 29422 14935 29422 14900 29423 14881 29423 14901 29423 14901 29424 14881 29424 14902 29424 14901 29425 14902 29425 14931 29425 14931 29426 14902 29426 14935 29426 14931 29427 14935 29427 14932 29427 14427 29428 14426 29428 14873 29428 14873 29429 14426 29429 14803 29429 14873 29430 14803 29430 14888 29430 14429 29431 14903 29431 14897 29431 14897 29432 14903 29432 14873 29432 14897 29433 14873 29433 14896 29433 14896 29434 14873 29434 14889 29434 14896 29435 14889 29435 14904 29435 14904 29436 14889 29436 14890 29436 14904 29437 14890 29437 14894 29437 14894 29438 14890 29438 14875 29438 14894 29439 14875 29439 14892 29439 14892 29440 14875 29440 14905 29440 14892 29441 14905 29441 14334 29441 14334 29442 14905 29442 14335 29442 14872 29443 14431 29443 14897 29443 14897 29444 14431 29444 14430 29444 14897 29445 14430 29445 14429 29445 14918 29446 14871 29446 14906 29446 14906 29447 14871 29447 14872 29447 14906 29448 14872 29448 14907 29448 14907 29449 14872 29449 14908 29449 14907 29450 14908 29450 14916 29450 14916 29451 14908 29451 14909 29451 14916 29452 14909 29452 14914 29452 14914 29453 14909 29453 14910 29453 14914 29454 14910 29454 14912 29454 14912 29455 14910 29455 14895 29455 14912 29456 14895 29456 14911 29456 14911 29457 14895 29457 14893 29457 14911 29458 14330 29458 14912 29458 14912 29459 14330 29459 14913 29459 14912 29460 14913 29460 14914 29460 14914 29461 14913 29461 14915 29461 14914 29462 14915 29462 14916 29462 14916 29463 14915 29463 14919 29463 14916 29464 14919 29464 14907 29464 14907 29465 14919 29465 14917 29465 14907 29466 14917 29466 14906 29466 14906 29467 14917 29467 14921 29467 14906 29468 14921 29468 14918 29468 14918 29469 14921 29469 14922 29469 14330 29470 14929 29470 14913 29470 14913 29471 14929 29471 14928 29471 14913 29472 14928 29472 14915 29472 14915 29473 14928 29473 14927 29473 14915 29474 14927 29474 14919 29474 14919 29475 14927 29475 14920 29475 14919 29476 14920 29476 14917 29476 14917 29477 14920 29477 14924 29477 14917 29478 14924 29478 14921 29478 14921 29479 14924 29479 14870 29479 14921 29480 14870 29480 14922 29480 14922 29481 14870 29481 14420 29481 14923 29482 14419 29482 14900 29482 14900 29483 14419 29483 14870 29483 14900 29484 14870 29484 14880 29484 14880 29485 14870 29485 14924 29485 14880 29486 14924 29486 14925 29486 14925 29487 14924 29487 14920 29487 14925 29488 14920 29488 14878 29488 14878 29489 14920 29489 14927 29489 14878 29490 14927 29490 14926 29490 14926 29491 14927 29491 14928 29491 14926 29492 14928 29492 14876 29492 14876 29493 14928 29493 14929 29493 14417 29494 14900 29494 14416 29494 14416 29495 14900 29495 14901 29495 14416 29496 14901 29496 14414 29496 14414 29497 14901 29497 14931 29497 14414 29498 14931 29498 14930 29498 14930 29499 14931 29499 14932 29499 14930 29500 14932 29500 14933 29500 14934 29501 14933 29501 14818 29501 14818 29502 14933 29502 14932 29502 14818 29503 14932 29503 14819 29503 14819 29504 14932 29504 14935 29504 14819 29505 14935 29505 14936 29505 14936 29506 14935 29506 14938 29506 14936 29507 14938 29507 14937 29507 14937 29508 14938 29508 14940 29508 14937 29509 14940 29509 14939 29509 14939 29510 14940 29510 14941 29510 14939 29511 14941 29511 14814 29511 14814 29512 14941 29512 14899 29512 14814 29513 14899 29513 14811 29513 14811 29514 14899 29514 14898 29514 14811 29515 14898 29515 14346 29515 14346 29516 14898 29516 14345 29516 14942 29517 15007 29517 15008 29517 15009 29518 15037 29518 15008 29518 15008 29519 15037 29519 14943 29519 15008 29520 14943 29520 14942 29520 15040 29521 15039 29521 14944 29521 14944 29522 15039 29522 14945 29522 14944 29523 14945 29523 15009 29523 15009 29524 14945 29524 14946 29524 15009 29525 14946 29525 15037 29525 15040 29526 14944 29526 14947 29526 14947 29527 14944 29527 14948 29527 14947 29528 14948 29528 14949 29528 14949 29529 14948 29529 14950 29529 14950 29530 14948 29530 14951 29530 14950 29531 14951 29531 15042 29531 14953 29532 14952 29532 14951 29532 14951 29533 14952 29533 15043 29533 14951 29534 15043 29534 15042 29534 15049 29535 15048 29535 14989 29535 14989 29536 15048 29536 15046 29536 14989 29537 15046 29537 14953 29537 14953 29538 15046 29538 14954 29538 14953 29539 14954 29539 14952 29539 15049 29540 14989 29540 14955 29540 14955 29541 14989 29541 14956 29541 14955 29542 14956 29542 14957 29542 14957 29543 14956 29543 14958 29543 14958 29544 14956 29544 14959 29544 14958 29545 14959 29545 14960 29545 14963 29546 14964 29546 14959 29546 14959 29547 14964 29547 15052 29547 14959 29548 15052 29548 14960 29548 14965 29549 14961 29549 14962 29549 14962 29550 14961 29550 15055 29550 14962 29551 15055 29551 14963 29551 14963 29552 15055 29552 15054 29552 14963 29553 15054 29553 14964 29553 14965 29554 14962 29554 14966 29554 14966 29555 14962 29555 14990 29555 14966 29556 14990 29556 15058 29556 15058 29557 14990 29557 15057 29557 15057 29558 14990 29558 14968 29558 15057 29559 14968 29559 14967 29559 15000 29560 14971 29560 14968 29560 14968 29561 14971 29561 14969 29561 14968 29562 14969 29562 14967 29562 15001 29563 14974 29563 15000 29563 15000 29564 14974 29564 14970 29564 15000 29565 14970 29565 14971 29565 15017 29566 15015 29566 15002 29566 15002 29567 15015 29567 14972 29567 15002 29568 14972 29568 15001 29568 15001 29569 14972 29569 14973 29569 15001 29570 14973 29570 14974 29570 15017 29571 15002 29571 15018 29571 15018 29572 15002 29572 15005 29572 15018 29573 15005 29573 15019 29573 14975 29574 15021 29574 15005 29574 15005 29575 15021 29575 15020 29575 15005 29576 15020 29576 15019 29576 14979 29577 15022 29577 14975 29577 14975 29578 15022 29578 14976 29578 14975 29579 14976 29579 15021 29579 15025 29580 14977 29580 14980 29580 14980 29581 14977 29581 14978 29581 14980 29582 14978 29582 14979 29582 14979 29583 14978 29583 15023 29583 14979 29584 15023 29584 15022 29584 15025 29585 14980 29585 15026 29585 15026 29586 14980 29586 14981 29586 15026 29587 14981 29587 15027 29587 14996 29588 15029 29588 14981 29588 14981 29589 15029 29589 15028 29589 14981 29590 15028 29590 15027 29590 14982 29591 14983 29591 14996 29591 14996 29592 14983 29592 14984 29592 14996 29593 14984 29593 15029 29593 14942 29594 14985 29594 15007 29594 15007 29595 14985 29595 15031 29595 15007 29596 15031 29596 14982 29596 14982 29597 15031 29597 14986 29597 14982 29598 14986 29598 14983 29598 14989 29599 14987 29599 14956 29599 14956 29600 14987 29600 15461 29600 14956 29601 15461 29601 14959 29601 14951 29602 15457 29602 14953 29602 14953 29603 15457 29603 14988 29603 14953 29604 14988 29604 14989 29604 14989 29605 14988 29605 15460 29605 14989 29606 15460 29606 14987 29606 14962 29607 14994 29607 14990 29607 14990 29608 14994 29608 14998 29608 14990 29609 14998 29609 14968 29609 15461 29610 14991 29610 14959 29610 14959 29611 14991 29611 14992 29611 14959 29612 14992 29612 14963 29612 14963 29613 14992 29613 14993 29613 14963 29614 14993 29614 14962 29614 14962 29615 14993 29615 15463 29615 14962 29616 15463 29616 14994 29616 15005 29617 15474 29617 14975 29617 14975 29618 15474 29618 14995 29618 14975 29619 14995 29619 14979 29619 14981 29620 15480 29620 14996 29620 14996 29621 15480 29621 15006 29621 14996 29622 15006 29622 14982 29622 14995 29623 15476 29623 14979 29623 14979 29624 15476 29624 15477 29624 14979 29625 15477 29625 14980 29625 14980 29626 15477 29626 15479 29626 14980 29627 15479 29627 14981 29627 14981 29628 15479 29628 14997 29628 14981 29629 14997 29629 15480 29629 14944 29630 15452 29630 14948 29630 14948 29631 15452 29631 15454 29631 14948 29632 15454 29632 14951 29632 14951 29633 15454 29633 15455 29633 14951 29634 15455 29634 15457 29634 14998 29635 15465 29635 14968 29635 14968 29636 15465 29636 14999 29636 14968 29637 14999 29637 15000 29637 15000 29638 14999 29638 15467 29638 15000 29639 15467 29639 15001 29639 15467 29640 15470 29640 15001 29640 15001 29641 15470 29641 15003 29641 15001 29642 15003 29642 15002 29642 15002 29643 15003 29643 15004 29643 15002 29644 15004 29644 15005 29644 15005 29645 15004 29645 15473 29645 15005 29646 15473 29646 15474 29646 15006 29647 15481 29647 14982 29647 14982 29648 15481 29648 15482 29648 14982 29649 15482 29649 15007 29649 15007 29650 15482 29650 15485 29650 15007 29651 15485 29651 15008 29651 15485 29652 15449 29652 15008 29652 15008 29653 15449 29653 15010 29653 15008 29654 15010 29654 15009 29654 15009 29655 15010 29655 15011 29655 15009 29656 15011 29656 14944 29656 14944 29657 15011 29657 15450 29657 14944 29658 15450 29658 15452 29658 15057 29659 14967 29659 15012 29659 14967 29660 14969 29660 15012 29660 15012 29661 14969 29661 14971 29661 15012 29662 14971 29662 15013 29662 15013 29663 14971 29663 14970 29663 15013 29664 14970 29664 15014 29664 15014 29665 14970 29665 14974 29665 15014 29666 14974 29666 15087 29666 15087 29667 14974 29667 14973 29667 14973 29668 14972 29668 15087 29668 15087 29669 14972 29669 15015 29669 15087 29670 15015 29670 15086 29670 15086 29671 15015 29671 15017 29671 15086 29672 15017 29672 15016 29672 15016 29673 15017 29673 15018 29673 15016 29674 15018 29674 15082 29674 15082 29675 15018 29675 15019 29675 15019 29676 15020 29676 15082 29676 15082 29677 15020 29677 15021 29677 15082 29678 15021 29678 15081 29678 15081 29679 15021 29679 14976 29679 15081 29680 14976 29680 15079 29680 15079 29681 14976 29681 15022 29681 15079 29682 15022 29682 15077 29682 15077 29683 15022 29683 15023 29683 15023 29684 14978 29684 15077 29684 15077 29685 14978 29685 14977 29685 15077 29686 14977 29686 15024 29686 15024 29687 14977 29687 15025 29687 15024 29688 15025 29688 15076 29688 15076 29689 15025 29689 15026 29689 15076 29690 15026 29690 15074 29690 15074 29691 15026 29691 15027 29691 15027 29692 15028 29692 15074 29692 15074 29693 15028 29693 15029 29693 15074 29694 15029 29694 15072 29694 15072 29695 15029 29695 14984 29695 15072 29696 14984 29696 15071 29696 15031 29697 15030 29697 14986 29697 14986 29698 15030 29698 15071 29698 14986 29699 15071 29699 14983 29699 14983 29700 15071 29700 14984 29700 14985 29701 15032 29701 15031 29701 15031 29702 15032 29702 15033 29702 15031 29703 15033 29703 15030 29703 15037 29704 15034 29704 14943 29704 14943 29705 15034 29705 15032 29705 14943 29706 15032 29706 14942 29706 14942 29707 15032 29707 14985 29707 14946 29708 15035 29708 15037 29708 15037 29709 15035 29709 15036 29709 15037 29710 15036 29710 15034 29710 14946 29711 14945 29711 15035 29711 15035 29712 14945 29712 15039 29712 15035 29713 15039 29713 15038 29713 15038 29714 15039 29714 15040 29714 15038 29715 15040 29715 15066 29715 15066 29716 15040 29716 14947 29716 15066 29717 14947 29717 15041 29717 15041 29718 14947 29718 14949 29718 14949 29719 14950 29719 15041 29719 15041 29720 14950 29720 15042 29720 15041 29721 15042 29721 15065 29721 15065 29722 15042 29722 15043 29722 15065 29723 15043 29723 15044 29723 15044 29724 15043 29724 14952 29724 15044 29725 14952 29725 15045 29725 15045 29726 14952 29726 14954 29726 14954 29727 15046 29727 15045 29727 15045 29728 15046 29728 15048 29728 15045 29729 15048 29729 15047 29729 15047 29730 15048 29730 15049 29730 15047 29731 15049 29731 15050 29731 15050 29732 15049 29732 14955 29732 15050 29733 14955 29733 15051 29733 15051 29734 14955 29734 14957 29734 14957 29735 14958 29735 15051 29735 15051 29736 14958 29736 14960 29736 15051 29737 14960 29737 15063 29737 15063 29738 14960 29738 15052 29738 15063 29739 15052 29739 15053 29739 15053 29740 15052 29740 14964 29740 15053 29741 14964 29741 15056 29741 15056 29742 14964 29742 15054 29742 15054 29743 15055 29743 15056 29743 15056 29744 15055 29744 14961 29744 15056 29745 14961 29745 15062 29745 15062 29746 14961 29746 14965 29746 15062 29747 14965 29747 15059 29747 15012 29748 15090 29748 15057 29748 15057 29749 15090 29749 15091 29749 15057 29750 15091 29750 15058 29750 15058 29751 15091 29751 15059 29751 15058 29752 15059 29752 14966 29752 14966 29753 15059 29753 14965 29753 15091 29754 15092 29754 15059 29754 15059 29755 15092 29755 15060 29755 15059 29756 15060 29756 15062 29756 15062 29757 15060 29757 15061 29757 15062 29758 15061 29758 15056 29758 15056 29759 15061 29759 15097 29759 15056 29760 15097 29760 15053 29760 15053 29761 15097 29761 15098 29761 15053 29762 15098 29762 15063 29762 15063 29763 15098 29763 15099 29763 15063 29764 15099 29764 15051 29764 15051 29765 15099 29765 15101 29765 15051 29766 15101 29766 15050 29766 15050 29767 15101 29767 15102 29767 15050 29768 15102 29768 15047 29768 15047 29769 15102 29769 15103 29769 15047 29770 15103 29770 15045 29770 15045 29771 15103 29771 15104 29771 15045 29772 15104 29772 15044 29772 15044 29773 15104 29773 15064 29773 15044 29774 15064 29774 15065 29774 15065 29775 15064 29775 15105 29775 15065 29776 15105 29776 15041 29776 15041 29777 15105 29777 15107 29777 15041 29778 15107 29778 15066 29778 15066 29779 15107 29779 15108 29779 15066 29780 15108 29780 15038 29780 15038 29781 15108 29781 15067 29781 15038 29782 15067 29782 15035 29782 15035 29783 15067 29783 15068 29783 15035 29784 15068 29784 15036 29784 15036 29785 15068 29785 15069 29785 15036 29786 15069 29786 15034 29786 15034 29787 15069 29787 15111 29787 15034 29788 15111 29788 15032 29788 15032 29789 15111 29789 15113 29789 15032 29790 15113 29790 15033 29790 15033 29791 15113 29791 15114 29791 15033 29792 15114 29792 15030 29792 15030 29793 15114 29793 15070 29793 15030 29794 15070 29794 15071 29794 15071 29795 15070 29795 15117 29795 15071 29796 15117 29796 15072 29796 15072 29797 15117 29797 15073 29797 15072 29798 15073 29798 15074 29798 15074 29799 15073 29799 15119 29799 15074 29800 15119 29800 15076 29800 15076 29801 15119 29801 15075 29801 15076 29802 15075 29802 15024 29802 15024 29803 15075 29803 15121 29803 15024 29804 15121 29804 15077 29804 15077 29805 15121 29805 15078 29805 15077 29806 15078 29806 15079 29806 15079 29807 15078 29807 15080 29807 15079 29808 15080 29808 15081 29808 15081 29809 15080 29809 15124 29809 15081 29810 15124 29810 15082 29810 15082 29811 15124 29811 15083 29811 15082 29812 15083 29812 15016 29812 15016 29813 15083 29813 15084 29813 15016 29814 15084 29814 15086 29814 15086 29815 15084 29815 15085 29815 15086 29816 15085 29816 15087 29816 15087 29817 15085 29817 15128 29817 15087 29818 15128 29818 15014 29818 15014 29819 15128 29819 15088 29819 15014 29820 15088 29820 15013 29820 15013 29821 15088 29821 15089 29821 15013 29822 15089 29822 15012 29822 15012 29823 15089 29823 15130 29823 15012 29824 15130 29824 15090 29824 15090 29825 15130 29825 15131 29825 15090 29826 15131 29826 15091 29826 15091 29827 15131 29827 15092 29827 15131 29828 15093 29828 15092 29828 15092 29829 15093 29829 15094 29829 15092 29830 15094 29830 15060 29830 15060 29831 15094 29831 15095 29831 15060 29832 15095 29832 15061 29832 15061 29833 15095 29833 15134 29833 15061 29834 15134 29834 15097 29834 15097 29835 15134 29835 15096 29835 15097 29836 15096 29836 15098 29836 15098 29837 15096 29837 15135 29837 15098 29838 15135 29838 15099 29838 15099 29839 15135 29839 15100 29839 15099 29840 15100 29840 15101 29840 15101 29841 15100 29841 15138 29841 15101 29842 15138 29842 15102 29842 15102 29843 15138 29843 15139 29843 15102 29844 15139 29844 15103 29844 15103 29845 15139 29845 15140 29845 15103 29846 15140 29846 15104 29846 15104 29847 15140 29847 15142 29847 15104 29848 15142 29848 15064 29848 15064 29849 15142 29849 15143 29849 15064 29850 15143 29850 15105 29850 15105 29851 15143 29851 15106 29851 15105 29852 15106 29852 15107 29852 15107 29853 15106 29853 15109 29853 15107 29854 15109 29854 15108 29854 15108 29855 15109 29855 15147 29855 15108 29856 15147 29856 15067 29856 15067 29857 15147 29857 15110 29857 15067 29858 15110 29858 15068 29858 15068 29859 15110 29859 15149 29859 15068 29860 15149 29860 15069 29860 15069 29861 15149 29861 15112 29861 15069 29862 15112 29862 15111 29862 15111 29863 15112 29863 15152 29863 15111 29864 15152 29864 15113 29864 15113 29865 15152 29865 15153 29865 15113 29866 15153 29866 15114 29866 15114 29867 15153 29867 15115 29867 15114 29868 15115 29868 15070 29868 15070 29869 15115 29869 15116 29869 15070 29870 15116 29870 15117 29870 15117 29871 15116 29871 15156 29871 15117 29872 15156 29872 15073 29872 15073 29873 15156 29873 15118 29873 15073 29874 15118 29874 15119 29874 15119 29875 15118 29875 15120 29875 15119 29876 15120 29876 15075 29876 15075 29877 15120 29877 15160 29877 15075 29878 15160 29878 15121 29878 15121 29879 15160 29879 15122 29879 15121 29880 15122 29880 15078 29880 15078 29881 15122 29881 15123 29881 15078 29882 15123 29882 15080 29882 15080 29883 15123 29883 15125 29883 15080 29884 15125 29884 15124 29884 15124 29885 15125 29885 15163 29885 15124 29886 15163 29886 15083 29886 15083 29887 15163 29887 15126 29887 15083 29888 15126 29888 15084 29888 15084 29889 15126 29889 15127 29889 15084 29890 15127 29890 15085 29890 15085 29891 15127 29891 15165 29891 15085 29892 15165 29892 15128 29892 15128 29893 15165 29893 15129 29893 15128 29894 15129 29894 15088 29894 15088 29895 15129 29895 15168 29895 15088 29896 15168 29896 15089 29896 15089 29897 15168 29897 15170 29897 15089 29898 15170 29898 15130 29898 15130 29899 15170 29899 15171 29899 15130 29900 15171 29900 15131 29900 15131 29901 15171 29901 15093 29901 15171 29902 14341 29902 15093 29902 15093 29903 14341 29903 15132 29903 15093 29904 15132 29904 15094 29904 15094 29905 15132 29905 15133 29905 15094 29906 15133 29906 15095 29906 15095 29907 15133 29907 14331 29907 15095 29908 14331 29908 15134 29908 15134 29909 14331 29909 14354 29909 15134 29910 14354 29910 15096 29910 15096 29911 14354 29911 14348 29911 15096 29912 14348 29912 15135 29912 15135 29913 14348 29913 15136 29913 15135 29914 15136 29914 15100 29914 15100 29915 15136 29915 15137 29915 15100 29916 15137 29916 15138 29916 15138 29917 15137 29917 14361 29917 15138 29918 14361 29918 15139 29918 15139 29919 14361 29919 14362 29919 15139 29920 14362 29920 15140 29920 15140 29921 14362 29921 15141 29921 15140 29922 15141 29922 15142 29922 15142 29923 15141 29923 14358 29923 15142 29924 14358 29924 15143 29924 15143 29925 14358 29925 15144 29925 15143 29926 15144 29926 15106 29926 15106 29927 15144 29927 14364 29927 15106 29928 14364 29928 15109 29928 15109 29929 14364 29929 15145 29929 15109 29930 15145 29930 15147 29930 15147 29931 15145 29931 15146 29931 15147 29932 15146 29932 15110 29932 15110 29933 15146 29933 15148 29933 15110 29934 15148 29934 15149 29934 15149 29935 15148 29935 15150 29935 15149 29936 15150 29936 15112 29936 15112 29937 15150 29937 14347 29937 15112 29938 14347 29938 15152 29938 15152 29939 14347 29939 15151 29939 15152 29940 15151 29940 15153 29940 15153 29941 15151 29941 15154 29941 15153 29942 15154 29942 15115 29942 15115 29943 15154 29943 15155 29943 15115 29944 15155 29944 15116 29944 15116 29945 15155 29945 14339 29945 15116 29946 14339 29946 15156 29946 15156 29947 14339 29947 15157 29947 15156 29948 15157 29948 15118 29948 15118 29949 15157 29949 14333 29949 15118 29950 14333 29950 15120 29950 15120 29951 14333 29951 15158 29951 15120 29952 15158 29952 15160 29952 15160 29953 15158 29953 15159 29953 15160 29954 15159 29954 15122 29954 15122 29955 15159 29955 15161 29955 15122 29956 15161 29956 15123 29956 15123 29957 15161 29957 14337 29957 15123 29958 14337 29958 15125 29958 15125 29959 14337 29959 15162 29959 15125 29960 15162 29960 15163 29960 15163 29961 15162 29961 14351 29961 15163 29962 14351 29962 15126 29962 15126 29963 14351 29963 14349 29963 15126 29964 14349 29964 15127 29964 15127 29965 14349 29965 15164 29965 15127 29966 15164 29966 15165 29966 15165 29967 15164 29967 15166 29967 15165 29968 15166 29968 15129 29968 15129 29969 15166 29969 15167 29969 15129 29970 15167 29970 15168 29970 15168 29971 15167 29971 14342 29971 15168 29972 14342 29972 15170 29972 15170 29973 14342 29973 15169 29973 15170 29974 15169 29974 15171 29974 15171 29975 15169 29975 14341 29975 15172 29976 15560 29976 15650 29976 15650 29977 15560 29977 15559 29977 15650 29978 15559 29978 15173 29978 15173 29979 15559 29979 15557 29979 15173 29980 15557 29980 15652 29980 15652 29981 15557 29981 15175 29981 15652 29982 15175 29982 15174 29982 15174 29983 15175 29983 15176 29983 15174 29984 15176 29984 15653 29984 15653 29985 15176 29985 15555 29985 15653 29986 15555 29986 15654 29986 15654 29987 15555 29987 15177 29987 15654 29988 15177 29988 15655 29988 15655 29989 15177 29989 15178 29989 15655 29990 15178 29990 15656 29990 15656 29991 15178 29991 15179 29991 15656 29992 15179 29992 15659 29992 15659 29993 15179 29993 15180 29993 15659 29994 15180 29994 15181 29994 15181 29995 15180 29995 15551 29995 15181 29996 15551 29996 15182 29996 15182 29997 15551 29997 15183 29997 15182 29998 15183 29998 15661 29998 15661 29999 15183 29999 15549 29999 15661 30000 15549 30000 15184 30000 15184 30001 15549 30001 15548 30001 15184 30002 15548 30002 15185 30002 15185 30003 15548 30003 15186 30003 15185 30004 15186 30004 15666 30004 15666 30005 15186 30005 15545 30005 15666 30006 15545 30006 15187 30006 15187 30007 15545 30007 15544 30007 15187 30008 15544 30008 15667 30008 15667 30009 15544 30009 15188 30009 15667 30010 15188 30010 15189 30010 15189 30011 15188 30011 15543 30011 15189 30012 15543 30012 15190 30012 15190 30013 15543 30013 15542 30013 15190 30014 15542 30014 15191 30014 15191 30015 15542 30015 15541 30015 15191 30016 15541 30016 15192 30016 15192 30017 15541 30017 15540 30017 15192 30018 15540 30018 15635 30018 15635 30019 15540 30019 15539 30019 15635 30020 15539 30020 15636 30020 15636 30021 15539 30021 15538 30021 15636 30022 15538 30022 15637 30022 15637 30023 15538 30023 15193 30023 15637 30024 15193 30024 15194 30024 15194 30025 15193 30025 15534 30025 15194 30026 15534 30026 15639 30026 15639 30027 15534 30027 15533 30027 15639 30028 15533 30028 15195 30028 15195 30029 15533 30029 15530 30029 15195 30030 15530 30030 15196 30030 15196 30031 15530 30031 15529 30031 15196 30032 15529 30032 15197 30032 15197 30033 15529 30033 15199 30033 15197 30034 15199 30034 15198 30034 15198 30035 15199 30035 15200 30035 15198 30036 15200 30036 15644 30036 15644 30037 15200 30037 15527 30037 15644 30038 15527 30038 15202 30038 15202 30039 15527 30039 15201 30039 15202 30040 15201 30040 15203 30040 15203 30041 15201 30041 15204 30041 15203 30042 15204 30042 15646 30042 15646 30043 15204 30043 15524 30043 15646 30044 15524 30044 15648 30044 15648 30045 15524 30045 15205 30045 15648 30046 15205 30046 15172 30046 15172 30047 15205 30047 15560 30047 14304 30048 14298 30048 15221 30048 14297 30049 15434 30049 14298 30049 14298 30050 15434 30050 15206 30050 14298 30051 15206 30051 15221 30051 14287 30052 15207 30052 14297 30052 14297 30053 15207 30053 15208 30053 14297 30054 15208 30054 15434 30054 15209 30055 15437 30055 14287 30055 14287 30056 15437 30056 15210 30056 14287 30057 15210 30057 15207 30057 15212 30058 15213 30058 15209 30058 15209 30059 15213 30059 15211 30059 15209 30060 15211 30060 15437 30060 14316 30061 15441 30061 15212 30061 15212 30062 15441 30062 15440 30062 15212 30063 15440 30063 15213 30063 14325 30064 15214 30064 14316 30064 14316 30065 15214 30065 15442 30065 14316 30066 15442 30066 15441 30066 14292 30067 15216 30067 14325 30067 14325 30068 15216 30068 15446 30068 14325 30069 15446 30069 15214 30069 14291 30070 15215 30070 14292 30070 14292 30071 15215 30071 15418 30071 14292 30072 15418 30072 15216 30072 14299 30073 15421 30073 14291 30073 14291 30074 15421 30074 15420 30074 14291 30075 15420 30075 15215 30075 14306 30076 15218 30076 14299 30076 14299 30077 15218 30077 15424 30077 14299 30078 15424 30078 15421 30078 15220 30079 15217 30079 14306 30079 14306 30080 15217 30080 15426 30080 14306 30081 15426 30081 15218 30081 15223 30082 15219 30082 15220 30082 15220 30083 15219 30083 15428 30083 15220 30084 15428 30084 15217 30084 15221 30085 15431 30085 14304 30085 14304 30086 15431 30086 15222 30086 14304 30087 15222 30087 15223 30087 15223 30088 15222 30088 15430 30088 15223 30089 15430 30089 15219 30089 15357 30090 15358 30090 15227 30090 15385 30091 15224 30091 15227 30091 15227 30092 15224 30092 15387 30092 15227 30093 15387 30093 15357 30093 15225 30094 15383 30094 15227 30094 15227 30095 15383 30095 15384 30095 15227 30096 15384 30096 15385 30096 15378 30097 15379 30097 15227 30097 15227 30098 15379 30098 15226 30098 15227 30099 15226 30099 15225 30099 15376 30100 15377 30100 15227 30100 15227 30101 15377 30101 15228 30101 15227 30102 15228 30102 15378 30102 15371 30103 15374 30103 15227 30103 15227 30104 15374 30104 15375 30104 15227 30105 15375 30105 15376 30105 15229 30106 15369 30106 15227 30106 15227 30107 15369 30107 15370 30107 15227 30108 15370 30108 15371 30108 15364 30109 15230 30109 15227 30109 15227 30110 15230 30110 15367 30110 15227 30111 15367 30111 15229 30111 15361 30112 15231 30112 15227 30112 15227 30113 15231 30113 15363 30113 15227 30114 15363 30114 15364 30114 15358 30115 15360 30115 15227 30115 15227 30116 15360 30116 15232 30116 15227 30117 15232 30117 15361 30117 15260 30118 15233 30118 15234 30118 14322 30119 15235 30119 15233 30119 15233 30120 15235 30120 15345 30120 15233 30121 15345 30121 15234 30121 14280 30122 15236 30122 14322 30122 14322 30123 15236 30123 15347 30123 14322 30124 15347 30124 15235 30124 15239 30125 15349 30125 14280 30125 14280 30126 15349 30126 15237 30126 14280 30127 15237 30127 15236 30127 15242 30128 15238 30128 15239 30128 15239 30129 15238 30129 15350 30129 15239 30130 15350 30130 15349 30130 15240 30131 15353 30131 15242 30131 15242 30132 15353 30132 15241 30132 15242 30133 15241 30133 15238 30133 15244 30134 15355 30134 15240 30134 15240 30135 15355 30135 15354 30135 15240 30136 15354 30136 15353 30136 15243 30137 15247 30137 15244 30137 15244 30138 15247 30138 15245 30138 15244 30139 15245 30139 15355 30139 15248 30140 15250 30140 15243 30140 15243 30141 15250 30141 15246 30141 15243 30142 15246 30142 15247 30142 15252 30143 15249 30143 15248 30143 15248 30144 15249 30144 15333 30144 15248 30145 15333 30145 15250 30145 14320 30146 15251 30146 15252 30146 15252 30147 15251 30147 15334 30147 15252 30148 15334 30148 15249 30148 15256 30149 15253 30149 14320 30149 14320 30150 15253 30150 15254 30150 14320 30151 15254 30151 15251 30151 15255 30152 15338 30152 15256 30152 15256 30153 15338 30153 15257 30153 15256 30154 15257 30154 15253 30154 15234 30155 15258 30155 15260 30155 15260 30156 15258 30156 15259 30156 15260 30157 15259 30157 15255 30157 15255 30158 15259 30158 15261 30158 15255 30159 15261 30159 15338 30159 15264 30160 15262 30160 15273 30160 15306 30161 15308 30161 15273 30161 15273 30162 15308 30162 15263 30162 15273 30163 15263 30163 15264 30163 15268 30164 15265 30164 15273 30164 15273 30165 15265 30165 15304 30165 15273 30166 15304 30166 15306 30166 15266 30167 15267 30167 15273 30167 15273 30168 15267 30168 15301 30168 15273 30169 15301 30169 15268 30169 15295 30170 15269 30170 15273 30170 15273 30171 15269 30171 15299 30171 15273 30172 15299 30172 15266 30172 15293 30173 15270 30173 15273 30173 15273 30174 15270 30174 15271 30174 15273 30175 15271 30175 15295 30175 15272 30176 15291 30176 15273 30176 15273 30177 15291 30177 15274 30177 15273 30178 15274 30178 15293 30178 15285 30179 15287 30179 15273 30179 15273 30180 15287 30180 15275 30180 15273 30181 15275 30181 15272 30181 15282 30182 15276 30182 15273 30182 15273 30183 15276 30183 15284 30183 15273 30184 15284 30184 15285 30184 15262 30185 15280 30185 15273 30185 15273 30186 15280 30186 15277 30186 15273 30187 15277 30187 15282 30187 15264 30188 15278 30188 15262 30188 15262 30189 15278 30189 15279 30189 15262 30190 15279 30190 15280 30190 15280 30191 15279 30191 15312 30191 15280 30192 15312 30192 15277 30192 15277 30193 15312 30193 15281 30193 15277 30194 15281 30194 15282 30194 15282 30195 15281 30195 15315 30195 15282 30196 15315 30196 15276 30196 15276 30197 15315 30197 15283 30197 15276 30198 15283 30198 15284 30198 15284 30199 15283 30199 15316 30199 15284 30200 15316 30200 15285 30200 15285 30201 15316 30201 15286 30201 15285 30202 15286 30202 15287 30202 15287 30203 15286 30203 15288 30203 15287 30204 15288 30204 15275 30204 15275 30205 15288 30205 15289 30205 15275 30206 15289 30206 15272 30206 15272 30207 15289 30207 15290 30207 15272 30208 15290 30208 15291 30208 15291 30209 15290 30209 15292 30209 15291 30210 15292 30210 15274 30210 15274 30211 15292 30211 15318 30211 15274 30212 15318 30212 15293 30212 15293 30213 15318 30213 15320 30213 15293 30214 15320 30214 15270 30214 15270 30215 15320 30215 15294 30215 15270 30216 15294 30216 15271 30216 15271 30217 15294 30217 15296 30217 15271 30218 15296 30218 15295 30218 15295 30219 15296 30219 15297 30219 15295 30220 15297 30220 15269 30220 15269 30221 15297 30221 15298 30221 15269 30222 15298 30222 15299 30222 15299 30223 15298 30223 15300 30223 15299 30224 15300 30224 15266 30224 15266 30225 15300 30225 15323 30225 15266 30226 15323 30226 15267 30226 15267 30227 15323 30227 15324 30227 15267 30228 15324 30228 15301 30228 15301 30229 15324 30229 15326 30229 15301 30230 15326 30230 15268 30230 15268 30231 15326 30231 15302 30231 15268 30232 15302 30232 15265 30232 15265 30233 15302 30233 15303 30233 15265 30234 15303 30234 15304 30234 15304 30235 15303 30235 15305 30235 15304 30236 15305 30236 15306 30236 15306 30237 15305 30237 15307 30237 15306 30238 15307 30238 15308 30238 15308 30239 15307 30239 15331 30239 15308 30240 15331 30240 15263 30240 15263 30241 15331 30241 15309 30241 15263 30242 15309 30242 15264 30242 15264 30243 15309 30243 15278 30243 15309 30244 15310 30244 15278 30244 15278 30245 15310 30245 15332 30245 15278 30246 15332 30246 15279 30246 15279 30247 15332 30247 15311 30247 15279 30248 15311 30248 15312 30248 15312 30249 15311 30249 15313 30249 15312 30250 15313 30250 15281 30250 15281 30251 15313 30251 15314 30251 15281 30252 15314 30252 15315 30252 15315 30253 15314 30253 15335 30253 15315 30254 15335 30254 15283 30254 15283 30255 15335 30255 15336 30255 15283 30256 15336 30256 15316 30256 15316 30257 15336 30257 15317 30257 15316 30258 15317 30258 15286 30258 15286 30259 15317 30259 15337 30259 15286 30260 15337 30260 15288 30260 15288 30261 15337 30261 15339 30261 15288 30262 15339 30262 15289 30262 15289 30263 15339 30263 15340 30263 15289 30264 15340 30264 15290 30264 15290 30265 15340 30265 15341 30265 15290 30266 15341 30266 15292 30266 15292 30267 15341 30267 15319 30267 15292 30268 15319 30268 15318 30268 15318 30269 15319 30269 15342 30269 15318 30270 15342 30270 15320 30270 15320 30271 15342 30271 15343 30271 15320 30272 15343 30272 15294 30272 15294 30273 15343 30273 15344 30273 15294 30274 15344 30274 15296 30274 15296 30275 15344 30275 15346 30275 15296 30276 15346 30276 15297 30276 15297 30277 15346 30277 15348 30277 15297 30278 15348 30278 15298 30278 15298 30279 15348 30279 15321 30279 15298 30280 15321 30280 15300 30280 15300 30281 15321 30281 15322 30281 15300 30282 15322 30282 15323 30282 15323 30283 15322 30283 15351 30283 15323 30284 15351 30284 15324 30284 15324 30285 15351 30285 15325 30285 15324 30286 15325 30286 15326 30286 15326 30287 15325 30287 15352 30287 15326 30288 15352 30288 15302 30288 15302 30289 15352 30289 15327 30289 15302 30290 15327 30290 15303 30290 15303 30291 15327 30291 15328 30291 15303 30292 15328 30292 15305 30292 15305 30293 15328 30293 15329 30293 15305 30294 15329 30294 15307 30294 15307 30295 15329 30295 15330 30295 15307 30296 15330 30296 15331 30296 15331 30297 15330 30297 15356 30297 15331 30298 15356 30298 15309 30298 15309 30299 15356 30299 15310 30299 15356 30300 15247 30300 15310 30300 15310 30301 15247 30301 15246 30301 15310 30302 15246 30302 15332 30302 15332 30303 15246 30303 15250 30303 15332 30304 15250 30304 15311 30304 15311 30305 15250 30305 15333 30305 15311 30306 15333 30306 15313 30306 15313 30307 15333 30307 15249 30307 15313 30308 15249 30308 15314 30308 15314 30309 15249 30309 15334 30309 15314 30310 15334 30310 15335 30310 15335 30311 15334 30311 15251 30311 15335 30312 15251 30312 15336 30312 15336 30313 15251 30313 15254 30313 15336 30314 15254 30314 15317 30314 15317 30315 15254 30315 15253 30315 15317 30316 15253 30316 15337 30316 15337 30317 15253 30317 15257 30317 15337 30318 15257 30318 15339 30318 15339 30319 15257 30319 15338 30319 15339 30320 15338 30320 15340 30320 15340 30321 15338 30321 15261 30321 15340 30322 15261 30322 15341 30322 15341 30323 15261 30323 15259 30323 15341 30324 15259 30324 15319 30324 15319 30325 15259 30325 15258 30325 15319 30326 15258 30326 15342 30326 15342 30327 15258 30327 15234 30327 15342 30328 15234 30328 15343 30328 15343 30329 15234 30329 15345 30329 15343 30330 15345 30330 15344 30330 15344 30331 15345 30331 15235 30331 15344 30332 15235 30332 15346 30332 15346 30333 15235 30333 15347 30333 15346 30334 15347 30334 15348 30334 15348 30335 15347 30335 15236 30335 15348 30336 15236 30336 15321 30336 15321 30337 15236 30337 15237 30337 15321 30338 15237 30338 15322 30338 15322 30339 15237 30339 15349 30339 15322 30340 15349 30340 15351 30340 15351 30341 15349 30341 15350 30341 15351 30342 15350 30342 15325 30342 15325 30343 15350 30343 15238 30343 15325 30344 15238 30344 15352 30344 15352 30345 15238 30345 15241 30345 15352 30346 15241 30346 15327 30346 15327 30347 15241 30347 15353 30347 15327 30348 15353 30348 15328 30348 15328 30349 15353 30349 15354 30349 15328 30350 15354 30350 15329 30350 15329 30351 15354 30351 15355 30351 15329 30352 15355 30352 15330 30352 15330 30353 15355 30353 15245 30353 15330 30354 15245 30354 15356 30354 15356 30355 15245 30355 15247 30355 15357 30356 15359 30356 15358 30356 15358 30357 15359 30357 15389 30357 15358 30358 15389 30358 15360 30358 15360 30359 15389 30359 15391 30359 15360 30360 15391 30360 15232 30360 15232 30361 15391 30361 15392 30361 15232 30362 15392 30362 15361 30362 15361 30363 15392 30363 15393 30363 15361 30364 15393 30364 15231 30364 15231 30365 15393 30365 15362 30365 15231 30366 15362 30366 15363 30366 15363 30367 15362 30367 15395 30367 15363 30368 15395 30368 15364 30368 15364 30369 15395 30369 15397 30369 15364 30370 15397 30370 15230 30370 15230 30371 15397 30371 15365 30371 15230 30372 15365 30372 15367 30372 15367 30373 15365 30373 15366 30373 15367 30374 15366 30374 15229 30374 15229 30375 15366 30375 15368 30375 15229 30376 15368 30376 15369 30376 15369 30377 15368 30377 15400 30377 15369 30378 15400 30378 15370 30378 15370 30379 15400 30379 15372 30379 15370 30380 15372 30380 15371 30380 15371 30381 15372 30381 15373 30381 15371 30382 15373 30382 15374 30382 15374 30383 15373 30383 15403 30383 15374 30384 15403 30384 15375 30384 15375 30385 15403 30385 15404 30385 15375 30386 15404 30386 15376 30386 15376 30387 15404 30387 15406 30387 15376 30388 15406 30388 15377 30388 15377 30389 15406 30389 15408 30389 15377 30390 15408 30390 15228 30390 15228 30391 15408 30391 15409 30391 15228 30392 15409 30392 15378 30392 15378 30393 15409 30393 15380 30393 15378 30394 15380 30394 15379 30394 15379 30395 15380 30395 15381 30395 15379 30396 15381 30396 15226 30396 15226 30397 15381 30397 15411 30397 15226 30398 15411 30398 15225 30398 15225 30399 15411 30399 15382 30399 15225 30400 15382 30400 15383 30400 15383 30401 15382 30401 15413 30401 15383 30402 15413 30402 15384 30402 15384 30403 15413 30403 15414 30403 15384 30404 15414 30404 15385 30404 15385 30405 15414 30405 15386 30405 15385 30406 15386 30406 15224 30406 15224 30407 15386 30407 15416 30407 15224 30408 15416 30408 15387 30408 15387 30409 15416 30409 15388 30409 15387 30410 15388 30410 15357 30410 15357 30411 15388 30411 15359 30411 15388 30412 15417 30412 15359 30412 15359 30413 15417 30413 15419 30413 15359 30414 15419 30414 15389 30414 15389 30415 15419 30415 15390 30415 15389 30416 15390 30416 15391 30416 15391 30417 15390 30417 15422 30417 15391 30418 15422 30418 15392 30418 15392 30419 15422 30419 15423 30419 15392 30420 15423 30420 15393 30420 15393 30421 15423 30421 15394 30421 15393 30422 15394 30422 15362 30422 15362 30423 15394 30423 15425 30423 15362 30424 15425 30424 15395 30424 15395 30425 15425 30425 15396 30425 15395 30426 15396 30426 15397 30426 15397 30427 15396 30427 15427 30427 15397 30428 15427 30428 15365 30428 15365 30429 15427 30429 15429 30429 15365 30430 15429 30430 15366 30430 15366 30431 15429 30431 15398 30431 15366 30432 15398 30432 15368 30432 15368 30433 15398 30433 15399 30433 15368 30434 15399 30434 15400 30434 15400 30435 15399 30435 15401 30435 15400 30436 15401 30436 15372 30436 15372 30437 15401 30437 15402 30437 15372 30438 15402 30438 15373 30438 15373 30439 15402 30439 15432 30439 15373 30440 15432 30440 15403 30440 15403 30441 15432 30441 15433 30441 15403 30442 15433 30442 15404 30442 15404 30443 15433 30443 15405 30443 15404 30444 15405 30444 15406 30444 15406 30445 15405 30445 15407 30445 15406 30446 15407 30446 15408 30446 15408 30447 15407 30447 15435 30447 15408 30448 15435 30448 15409 30448 15409 30449 15435 30449 15436 30449 15409 30450 15436 30450 15380 30450 15380 30451 15436 30451 15410 30451 15380 30452 15410 30452 15381 30452 15381 30453 15410 30453 15438 30453 15381 30454 15438 30454 15411 30454 15411 30455 15438 30455 15439 30455 15411 30456 15439 30456 15382 30456 15382 30457 15439 30457 15412 30457 15382 30458 15412 30458 15413 30458 15413 30459 15412 30459 15443 30459 15413 30460 15443 30460 15414 30460 15414 30461 15443 30461 15444 30461 15414 30462 15444 30462 15386 30462 15386 30463 15444 30463 15415 30463 15386 30464 15415 30464 15416 30464 15416 30465 15415 30465 15445 30465 15416 30466 15445 30466 15388 30466 15388 30467 15445 30467 15417 30467 15445 30468 15216 30468 15417 30468 15417 30469 15216 30469 15418 30469 15417 30470 15418 30470 15419 30470 15419 30471 15418 30471 15215 30471 15419 30472 15215 30472 15390 30472 15390 30473 15215 30473 15420 30473 15390 30474 15420 30474 15422 30474 15422 30475 15420 30475 15421 30475 15422 30476 15421 30476 15423 30476 15423 30477 15421 30477 15424 30477 15423 30478 15424 30478 15394 30478 15394 30479 15424 30479 15218 30479 15394 30480 15218 30480 15425 30480 15425 30481 15218 30481 15426 30481 15425 30482 15426 30482 15396 30482 15396 30483 15426 30483 15217 30483 15396 30484 15217 30484 15427 30484 15427 30485 15217 30485 15428 30485 15427 30486 15428 30486 15429 30486 15429 30487 15428 30487 15219 30487 15429 30488 15219 30488 15398 30488 15398 30489 15219 30489 15430 30489 15398 30490 15430 30490 15399 30490 15399 30491 15430 30491 15222 30491 15399 30492 15222 30492 15401 30492 15401 30493 15222 30493 15431 30493 15401 30494 15431 30494 15402 30494 15402 30495 15431 30495 15221 30495 15402 30496 15221 30496 15432 30496 15432 30497 15221 30497 15206 30497 15432 30498 15206 30498 15433 30498 15433 30499 15206 30499 15434 30499 15433 30500 15434 30500 15405 30500 15405 30501 15434 30501 15208 30501 15405 30502 15208 30502 15407 30502 15407 30503 15208 30503 15207 30503 15407 30504 15207 30504 15435 30504 15435 30505 15207 30505 15210 30505 15435 30506 15210 30506 15436 30506 15436 30507 15210 30507 15437 30507 15436 30508 15437 30508 15410 30508 15410 30509 15437 30509 15211 30509 15410 30510 15211 30510 15438 30510 15438 30511 15211 30511 15213 30511 15438 30512 15213 30512 15439 30512 15439 30513 15213 30513 15440 30513 15439 30514 15440 30514 15412 30514 15412 30515 15440 30515 15441 30515 15412 30516 15441 30516 15443 30516 15443 30517 15441 30517 15442 30517 15443 30518 15442 30518 15444 30518 15444 30519 15442 30519 15214 30519 15444 30520 15214 30520 15415 30520 15415 30521 15214 30521 15446 30521 15415 30522 15446 30522 15445 30522 15445 30523 15446 30523 15216 30523 15485 30524 15447 30524 15449 30524 15449 30525 15447 30525 15448 30525 15449 30526 15448 30526 15010 30526 15010 30527 15448 30527 15487 30527 15010 30528 15487 30528 15011 30528 15011 30529 15487 30529 15488 30529 15011 30530 15488 30530 15450 30530 15450 30531 15488 30531 15451 30531 15450 30532 15451 30532 15452 30532 15452 30533 15451 30533 15453 30533 15452 30534 15453 30534 15454 30534 15454 30535 15453 30535 15491 30535 15454 30536 15491 30536 15455 30536 15455 30537 15491 30537 15456 30537 15455 30538 15456 30538 15457 30538 15457 30539 15456 30539 15458 30539 15457 30540 15458 30540 14988 30540 14988 30541 15458 30541 15492 30541 14988 30542 15492 30542 15460 30542 15460 30543 15492 30543 15459 30543 15460 30544 15459 30544 14987 30544 14987 30545 15459 30545 15493 30545 14987 30546 15493 30546 15461 30546 15461 30547 15493 30547 15495 30547 15461 30548 15495 30548 14991 30548 14991 30549 15495 30549 15498 30549 14991 30550 15498 30550 14992 30550 14992 30551 15498 30551 15462 30551 14992 30552 15462 30552 14993 30552 14993 30553 15462 30553 15502 30553 14993 30554 15502 30554 15463 30554 15463 30555 15502 30555 15503 30555 15463 30556 15503 30556 14994 30556 14994 30557 15503 30557 15464 30557 14994 30558 15464 30558 14998 30558 14998 30559 15464 30559 15505 30559 14998 30560 15505 30560 15465 30560 15465 30561 15505 30561 15466 30561 15465 30562 15466 30562 14999 30562 14999 30563 15466 30563 15468 30563 14999 30564 15468 30564 15467 30564 15467 30565 15468 30565 15469 30565 15467 30566 15469 30566 15470 30566 15470 30567 15469 30567 15508 30567 15470 30568 15508 30568 15003 30568 15003 30569 15508 30569 15471 30569 15003 30570 15471 30570 15004 30570 15004 30571 15471 30571 15472 30571 15004 30572 15472 30572 15473 30572 15473 30573 15472 30573 15512 30573 15473 30574 15512 30574 15474 30574 15474 30575 15512 30575 15475 30575 15474 30576 15475 30576 14995 30576 14995 30577 15475 30577 15513 30577 14995 30578 15513 30578 15476 30578 15476 30579 15513 30579 15514 30579 15476 30580 15514 30580 15477 30580 15477 30581 15514 30581 15478 30581 15477 30582 15478 30582 15479 30582 15479 30583 15478 30583 15517 30583 15479 30584 15517 30584 14997 30584 14997 30585 15517 30585 15518 30585 14997 30586 15518 30586 15480 30586 15480 30587 15518 30587 15520 30587 15480 30588 15520 30588 15006 30588 15006 30589 15520 30589 15521 30589 15006 30590 15521 30590 15481 30590 15481 30591 15521 30591 15483 30591 15481 30592 15483 30592 15482 30592 15482 30593 15483 30593 15484 30593 15482 30594 15484 30594 15485 30594 15485 30595 15484 30595 15447 30595 15484 30596 15486 30596 15447 30596 15447 30597 15486 30597 15525 30597 15447 30598 15525 30598 15448 30598 15448 30599 15525 30599 15526 30599 15448 30600 15526 30600 15487 30600 15487 30601 15526 30601 15528 30601 15487 30602 15528 30602 15488 30602 15488 30603 15528 30603 15489 30603 15488 30604 15489 30604 15451 30604 15451 30605 15489 30605 15490 30605 15451 30606 15490 30606 15453 30606 15453 30607 15490 30607 15531 30607 15453 30608 15531 30608 15491 30608 15491 30609 15531 30609 15532 30609 15491 30610 15532 30610 15456 30610 15456 30611 15532 30611 15535 30611 15456 30612 15535 30612 15458 30612 15458 30613 15535 30613 15536 30613 15458 30614 15536 30614 15492 30614 15492 30615 15536 30615 15537 30615 15492 30616 15537 30616 15459 30616 15459 30617 15537 30617 15494 30617 15459 30618 15494 30618 15493 30618 15493 30619 15494 30619 15496 30619 15493 30620 15496 30620 15495 30620 15495 30621 15496 30621 15497 30621 15495 30622 15497 30622 15498 30622 15498 30623 15497 30623 15499 30623 15498 30624 15499 30624 15462 30624 15462 30625 15499 30625 15500 30625 15462 30626 15500 30626 15502 30626 15502 30627 15500 30627 15501 30627 15502 30628 15501 30628 15503 30628 15503 30629 15501 30629 15504 30629 15503 30630 15504 30630 15464 30630 15464 30631 15504 30631 15506 30631 15464 30632 15506 30632 15505 30632 15505 30633 15506 30633 15546 30633 15505 30634 15546 30634 15466 30634 15466 30635 15546 30635 15547 30635 15466 30636 15547 30636 15468 30636 15468 30637 15547 30637 15507 30637 15468 30638 15507 30638 15469 30638 15469 30639 15507 30639 15550 30639 15469 30640 15550 30640 15508 30640 15508 30641 15550 30641 15509 30641 15508 30642 15509 30642 15471 30642 15471 30643 15509 30643 15510 30643 15471 30644 15510 30644 15472 30644 15472 30645 15510 30645 15511 30645 15472 30646 15511 30646 15512 30646 15512 30647 15511 30647 15552 30647 15512 30648 15552 30648 15475 30648 15475 30649 15552 30649 15553 30649 15475 30650 15553 30650 15513 30650 15513 30651 15553 30651 15554 30651 15513 30652 15554 30652 15514 30652 15514 30653 15554 30653 15515 30653 15514 30654 15515 30654 15478 30654 15478 30655 15515 30655 15516 30655 15478 30656 15516 30656 15517 30656 15517 30657 15516 30657 15556 30657 15517 30658 15556 30658 15518 30658 15518 30659 15556 30659 15519 30659 15518 30660 15519 30660 15520 30660 15520 30661 15519 30661 15558 30661 15520 30662 15558 30662 15521 30662 15521 30663 15558 30663 15522 30663 15521 30664 15522 30664 15483 30664 15483 30665 15522 30665 15523 30665 15483 30666 15523 30666 15484 30666 15484 30667 15523 30667 15486 30667 15523 30668 15524 30668 15486 30668 15486 30669 15524 30669 15204 30669 15486 30670 15204 30670 15525 30670 15525 30671 15204 30671 15201 30671 15525 30672 15201 30672 15526 30672 15526 30673 15201 30673 15527 30673 15526 30674 15527 30674 15528 30674 15528 30675 15527 30675 15200 30675 15528 30676 15200 30676 15489 30676 15489 30677 15200 30677 15199 30677 15489 30678 15199 30678 15490 30678 15490 30679 15199 30679 15529 30679 15490 30680 15529 30680 15531 30680 15531 30681 15529 30681 15530 30681 15531 30682 15530 30682 15532 30682 15532 30683 15530 30683 15533 30683 15532 30684 15533 30684 15535 30684 15535 30685 15533 30685 15534 30685 15535 30686 15534 30686 15536 30686 15536 30687 15534 30687 15193 30687 15536 30688 15193 30688 15537 30688 15537 30689 15193 30689 15538 30689 15537 30690 15538 30690 15494 30690 15494 30691 15538 30691 15539 30691 15494 30692 15539 30692 15496 30692 15496 30693 15539 30693 15540 30693 15496 30694 15540 30694 15497 30694 15497 30695 15540 30695 15541 30695 15497 30696 15541 30696 15499 30696 15499 30697 15541 30697 15542 30697 15499 30698 15542 30698 15500 30698 15500 30699 15542 30699 15543 30699 15500 30700 15543 30700 15501 30700 15501 30701 15543 30701 15188 30701 15501 30702 15188 30702 15504 30702 15504 30703 15188 30703 15544 30703 15504 30704 15544 30704 15506 30704 15506 30705 15544 30705 15545 30705 15506 30706 15545 30706 15546 30706 15546 30707 15545 30707 15186 30707 15546 30708 15186 30708 15547 30708 15547 30709 15186 30709 15548 30709 15547 30710 15548 30710 15507 30710 15507 30711 15548 30711 15549 30711 15507 30712 15549 30712 15550 30712 15550 30713 15549 30713 15183 30713 15550 30714 15183 30714 15509 30714 15509 30715 15183 30715 15551 30715 15509 30716 15551 30716 15510 30716 15510 30717 15551 30717 15180 30717 15510 30718 15180 30718 15511 30718 15511 30719 15180 30719 15179 30719 15511 30720 15179 30720 15552 30720 15552 30721 15179 30721 15178 30721 15552 30722 15178 30722 15553 30722 15553 30723 15178 30723 15177 30723 15553 30724 15177 30724 15554 30724 15554 30725 15177 30725 15555 30725 15554 30726 15555 30726 15515 30726 15515 30727 15555 30727 15176 30727 15515 30728 15176 30728 15516 30728 15516 30729 15176 30729 15175 30729 15516 30730 15175 30730 15556 30730 15556 30731 15175 30731 15557 30731 15556 30732 15557 30732 15519 30732 15519 30733 15557 30733 15559 30733 15519 30734 15559 30734 15558 30734 15558 30735 15559 30735 15560 30735 15558 30736 15560 30736 15522 30736 15522 30737 15560 30737 15205 30737 15522 30738 15205 30738 15523 30738 15523 30739 15205 30739 15524 30739 15598 30740 15561 30740 15562 30740 15562 30741 15561 30741 15599 30741 15562 30742 15599 30742 14327 30742 14327 30743 15599 30743 15600 30743 14327 30744 15600 30744 14328 30744 14328 30745 15600 30745 15563 30745 14328 30746 15563 30746 15564 30746 15564 30747 15563 30747 15565 30747 15564 30748 15565 30748 14329 30748 14329 30749 15565 30749 15605 30749 14329 30750 15605 30750 14324 30750 14324 30751 15605 30751 15566 30751 14324 30752 15566 30752 15567 30752 15567 30753 15566 30753 15568 30753 15567 30754 15568 30754 14326 30754 14326 30755 15568 30755 15607 30755 14326 30756 15607 30756 15569 30756 15569 30757 15607 30757 15608 30757 15569 30758 15608 30758 15570 30758 15570 30759 15608 30759 15571 30759 15570 30760 15571 30760 14321 30760 14321 30761 15571 30761 15572 30761 14321 30762 15572 30762 15573 30762 15573 30763 15572 30763 15610 30763 15573 30764 15610 30764 15574 30764 15574 30765 15610 30765 15611 30765 15574 30766 15611 30766 15576 30766 15576 30767 15611 30767 15575 30767 15576 30768 15575 30768 14311 30768 14311 30769 15575 30769 15613 30769 14311 30770 15613 30770 15577 30770 15577 30771 15613 30771 15579 30771 15577 30772 15579 30772 15578 30772 15578 30773 15579 30773 15614 30773 15578 30774 15614 30774 15580 30774 15580 30775 15614 30775 15581 30775 15580 30776 15581 30776 15582 30776 15582 30777 15581 30777 15616 30777 15582 30778 15616 30778 15583 30778 15583 30779 15616 30779 15618 30779 15583 30780 15618 30780 15584 30780 15584 30781 15618 30781 15585 30781 15584 30782 15585 30782 14323 30782 14323 30783 15585 30783 15621 30783 14323 30784 15621 30784 15586 30784 15586 30785 15621 30785 15623 30785 15586 30786 15623 30786 14312 30786 14312 30787 15623 30787 15587 30787 14312 30788 15587 30788 14313 30788 14313 30789 15587 30789 15625 30789 14313 30790 15625 30790 15588 30790 15588 30791 15625 30791 15589 30791 15588 30792 15589 30792 14314 30792 14314 30793 15589 30793 15626 30793 14314 30794 15626 30794 14308 30794 14308 30795 15626 30795 15627 30795 14308 30796 15627 30796 14309 30796 14309 30797 15627 30797 15590 30797 14309 30798 15590 30798 14310 30798 14310 30799 15590 30799 15591 30799 14310 30800 15591 30800 14315 30800 14315 30801 15591 30801 15592 30801 14315 30802 15592 30802 14317 30802 14317 30803 15592 30803 15593 30803 14317 30804 15593 30804 14318 30804 14318 30805 15593 30805 15594 30805 14318 30806 15594 30806 14319 30806 14319 30807 15594 30807 15595 30807 14319 30808 15595 30808 15596 30808 15596 30809 15595 30809 15597 30809 15596 30810 15597 30810 15598 30810 15598 30811 15597 30811 15561 30811 15597 30812 15632 30812 15561 30812 15561 30813 15632 30813 15633 30813 15561 30814 15633 30814 15599 30814 15599 30815 15633 30815 15634 30815 15599 30816 15634 30816 15600 30816 15600 30817 15634 30817 15601 30817 15600 30818 15601 30818 15563 30818 15563 30819 15601 30819 15602 30819 15563 30820 15602 30820 15565 30820 15565 30821 15602 30821 15603 30821 15565 30822 15603 30822 15605 30822 15605 30823 15603 30823 15604 30823 15605 30824 15604 30824 15566 30824 15566 30825 15604 30825 15606 30825 15566 30826 15606 30826 15568 30826 15568 30827 15606 30827 15638 30827 15568 30828 15638 30828 15607 30828 15607 30829 15638 30829 15640 30829 15607 30830 15640 30830 15608 30830 15608 30831 15640 30831 15609 30831 15608 30832 15609 30832 15571 30832 15571 30833 15609 30833 15641 30833 15571 30834 15641 30834 15572 30834 15572 30835 15641 30835 15642 30835 15572 30836 15642 30836 15610 30836 15610 30837 15642 30837 15643 30837 15610 30838 15643 30838 15611 30838 15611 30839 15643 30839 15645 30839 15611 30840 15645 30840 15575 30840 15575 30841 15645 30841 15612 30841 15575 30842 15612 30842 15613 30842 15613 30843 15612 30843 15647 30843 15613 30844 15647 30844 15579 30844 15579 30845 15647 30845 15649 30845 15579 30846 15649 30846 15614 30846 15614 30847 15649 30847 15615 30847 15614 30848 15615 30848 15581 30848 15581 30849 15615 30849 15651 30849 15581 30850 15651 30850 15616 30850 15616 30851 15651 30851 15617 30851 15616 30852 15617 30852 15618 30852 15618 30853 15617 30853 15619 30853 15618 30854 15619 30854 15585 30854 15585 30855 15619 30855 15620 30855 15585 30856 15620 30856 15621 30856 15621 30857 15620 30857 15622 30857 15621 30858 15622 30858 15623 30858 15623 30859 15622 30859 15624 30859 15623 30860 15624 30860 15587 30860 15587 30861 15624 30861 15657 30861 15587 30862 15657 30862 15625 30862 15625 30863 15657 30863 15658 30863 15625 30864 15658 30864 15589 30864 15589 30865 15658 30865 15660 30865 15589 30866 15660 30866 15626 30866 15626 30867 15660 30867 15628 30867 15626 30868 15628 30868 15627 30868 15627 30869 15628 30869 15629 30869 15627 30870 15629 30870 15590 30870 15590 30871 15629 30871 15662 30871 15590 30872 15662 30872 15591 30872 15591 30873 15662 30873 15663 30873 15591 30874 15663 30874 15592 30874 15592 30875 15663 30875 15664 30875 15592 30876 15664 30876 15593 30876 15593 30877 15664 30877 15665 30877 15593 30878 15665 30878 15594 30878 15594 30879 15665 30879 15630 30879 15594 30880 15630 30880 15595 30880 15595 30881 15630 30881 15631 30881 15595 30882 15631 30882 15597 30882 15597 30883 15631 30883 15632 30883 15631 30884 15189 30884 15632 30884 15632 30885 15189 30885 15190 30885 15632 30886 15190 30886 15633 30886 15633 30887 15190 30887 15191 30887 15633 30888 15191 30888 15634 30888 15634 30889 15191 30889 15192 30889 15634 30890 15192 30890 15601 30890 15601 30891 15192 30891 15635 30891 15601 30892 15635 30892 15602 30892 15602 30893 15635 30893 15636 30893 15602 30894 15636 30894 15603 30894 15603 30895 15636 30895 15637 30895 15603 30896 15637 30896 15604 30896 15604 30897 15637 30897 15194 30897 15604 30898 15194 30898 15606 30898 15606 30899 15194 30899 15639 30899 15606 30900 15639 30900 15638 30900 15638 30901 15639 30901 15195 30901 15638 30902 15195 30902 15640 30902 15640 30903 15195 30903 15196 30903 15640 30904 15196 30904 15609 30904 15609 30905 15196 30905 15197 30905 15609 30906 15197 30906 15641 30906 15641 30907 15197 30907 15198 30907 15641 30908 15198 30908 15642 30908 15642 30909 15198 30909 15644 30909 15642 30910 15644 30910 15643 30910 15643 30911 15644 30911 15202 30911 15643 30912 15202 30912 15645 30912 15645 30913 15202 30913 15203 30913 15645 30914 15203 30914 15612 30914 15612 30915 15203 30915 15646 30915 15612 30916 15646 30916 15647 30916 15647 30917 15646 30917 15648 30917 15647 30918 15648 30918 15649 30918 15649 30919 15648 30919 15172 30919 15649 30920 15172 30920 15615 30920 15615 30921 15172 30921 15650 30921 15615 30922 15650 30922 15651 30922 15651 30923 15650 30923 15173 30923 15651 30924 15173 30924 15617 30924 15617 30925 15173 30925 15652 30925 15617 30926 15652 30926 15619 30926 15619 30927 15652 30927 15174 30927 15619 30928 15174 30928 15620 30928 15620 30929 15174 30929 15653 30929 15620 30930 15653 30930 15622 30930 15622 30931 15653 30931 15654 30931 15622 30932 15654 30932 15624 30932 15624 30933 15654 30933 15655 30933 15624 30934 15655 30934 15657 30934 15657 30935 15655 30935 15656 30935 15657 30936 15656 30936 15658 30936 15658 30937 15656 30937 15659 30937 15658 30938 15659 30938 15660 30938 15660 30939 15659 30939 15181 30939 15660 30940 15181 30940 15628 30940 15628 30941 15181 30941 15182 30941 15628 30942 15182 30942 15629 30942 15629 30943 15182 30943 15661 30943 15629 30944 15661 30944 15662 30944 15662 30945 15661 30945 15184 30945 15662 30946 15184 30946 15663 30946 15663 30947 15184 30947 15185 30947 15663 30948 15185 30948 15664 30948 15664 30949 15185 30949 15666 30949 15664 30950 15666 30950 15665 30950 15665 30951 15666 30951 15187 30951 15665 30952 15187 30952 15630 30952 15630 30953 15187 30953 15667 30953 15630 30954 15667 30954 15631 30954 15631 30955 15667 30955 15189 30955 15753 30956 15933 30956 15668 30956 15753 30957 15668 30957 15669 30957 15669 30958 15668 30958 15938 30958 15669 30959 15938 30959 15741 30959 15741 30960 15938 30960 15670 30960 15741 30961 15670 30961 15671 30961 15671 30962 15670 30962 15672 30962 15671 30963 15672 30963 15743 30963 15743 30964 15672 30964 15736 30964 15736 30965 15672 30965 15948 30965 15736 30966 15948 30966 15882 30966 15948 30967 15947 30967 15882 30967 15882 30968 15947 30968 15881 30968 15946 30969 15673 30969 15947 30969 15947 30970 15673 30970 15883 30970 15947 30971 15883 30971 15881 30971 15673 30972 15946 30972 15674 30972 15674 30973 15946 30973 15676 30973 15674 30974 15676 30974 15675 30974 15675 30975 15676 30975 15885 30975 15885 30976 15676 30976 15677 30976 15885 30977 15677 30977 15886 30977 15886 30978 15677 30978 15887 30978 15887 30979 15677 30979 15953 30979 15887 30980 15953 30980 15888 30980 15888 30981 15953 30981 15889 30981 15889 30982 15953 30982 15678 30982 15889 30983 15678 30983 15890 30983 15890 30984 15678 30984 15892 30984 15892 30985 15678 30985 15679 30985 15892 30986 15679 30986 15893 30986 15893 30987 15679 30987 15884 30987 15884 30988 15679 30988 15949 30988 15884 30989 15949 30989 15681 30989 15945 30990 15680 30990 15949 30990 15949 30991 15680 30991 15681 30991 15788 30992 15766 30992 15939 30992 15939 30993 15766 30993 15682 30993 15933 30994 15753 30994 15780 30994 15780 30995 15753 30995 15683 30995 15684 30996 15686 30996 15718 30996 15718 30997 15686 30997 15685 30997 15685 30998 15686 30998 15687 30998 15685 30999 15687 30999 15696 30999 15935 31000 15940 31000 15854 31000 15854 31001 15940 31001 15688 31001 15854 31002 15688 31002 15690 31002 15951 31003 15701 31003 15950 31003 15950 31004 15701 31004 15857 31004 15950 31005 15857 31005 15689 31005 15689 31006 15857 31006 15690 31006 15689 31007 15690 31007 15943 31007 15943 31008 15690 31008 15688 31008 15921 31009 15691 31009 15920 31009 15920 31010 15691 31010 15692 31010 15920 31011 15692 31011 15927 31011 15927 31012 15692 31012 15693 31012 15927 31013 15693 31013 15924 31013 15924 31014 15693 31014 15707 31014 15835 31015 15921 31015 15727 31015 15727 31016 15921 31016 15694 31016 15854 31017 15695 31017 15935 31017 15935 31018 15695 31018 15853 31018 15935 31019 15853 31019 15936 31019 15936 31020 15853 31020 15852 31020 15936 31021 15852 31021 15931 31021 15931 31022 15852 31022 15850 31022 15931 31023 15850 31023 15929 31023 15929 31024 15850 31024 15697 31024 15929 31025 15697 31025 15696 31025 15696 31026 15697 31026 15698 31026 15696 31027 15698 31027 15685 31027 15685 31028 15698 31028 15699 31028 15685 31029 15699 31029 15875 31029 15875 31030 15699 31030 15700 31030 15875 31031 15700 31031 15876 31031 15876 31032 15700 31032 15701 31032 15876 31033 15701 31033 15878 31033 15878 31034 15701 31034 15951 31034 15878 31035 15951 31035 15880 31035 15702 31036 15814 31036 15711 31036 15711 31037 15814 31037 15703 31037 15711 31038 15703 31038 15706 31038 15835 31039 15704 31039 15921 31039 15921 31040 15704 31040 15705 31040 15921 31041 15705 31041 15691 31041 15691 31042 15705 31042 15706 31042 15691 31043 15706 31043 15812 31043 15812 31044 15706 31044 15703 31044 15708 31045 15932 31045 15809 31045 15809 31046 15932 31046 15934 31046 15809 31047 15934 31047 15707 31047 15707 31048 15934 31048 15923 31048 15707 31049 15923 31049 15924 31049 15807 31050 15710 31050 15708 31050 15708 31051 15710 31051 15709 31051 15708 31052 15709 31052 15932 31052 15817 31053 15713 31053 15807 31053 15807 31054 15713 31054 15937 31054 15807 31055 15937 31055 15710 31055 15702 31056 15711 31056 15817 31056 15817 31057 15711 31057 15712 31057 15817 31058 15712 31058 15713 31058 15713 31059 15712 31059 15714 31059 15713 31060 15714 31060 15722 31060 15715 31061 15726 31061 15952 31061 15952 31062 15726 31062 15720 31062 15954 31063 15716 31063 15955 31063 15955 31064 15716 31064 15870 31064 15955 31065 15870 31065 15951 31065 15951 31066 15870 31066 15717 31066 15951 31067 15717 31067 15880 31067 15718 31068 15874 31068 15684 31068 15684 31069 15874 31069 15719 31069 15684 31070 15719 31070 15913 31070 15913 31071 15719 31071 15872 31071 15913 31072 15872 31072 15915 31072 15915 31073 15872 31073 15716 31073 15915 31074 15716 31074 15720 31074 15720 31075 15716 31075 15954 31075 15720 31076 15954 31076 15952 31076 15714 31077 15721 31077 15722 31077 15722 31078 15721 31078 15723 31078 15722 31079 15723 31079 15724 31079 15724 31080 15723 31080 15726 31080 15724 31081 15726 31081 15725 31081 15725 31082 15726 31082 15715 31082 15694 31083 15917 31083 15727 31083 15727 31084 15917 31084 15728 31084 15727 31085 15728 31085 15720 31085 15720 31086 15728 31086 15729 31086 15720 31087 15729 31087 15915 31087 15891 31088 15790 31088 15735 31088 15823 31089 15730 31089 15748 31089 15748 31090 15730 31090 15731 31090 15748 31091 15731 31091 15827 31091 15732 31092 15733 31092 15790 31092 15790 31093 15733 31093 15734 31093 15790 31094 15734 31094 15735 31094 15735 31095 15867 31095 15891 31095 15891 31096 15867 31096 15752 31096 15891 31097 15752 31097 15750 31097 15829 31098 15736 31098 15737 31098 15737 31099 15736 31099 15746 31099 15737 31100 15746 31100 15827 31100 15732 31101 15738 31101 15733 31101 15733 31102 15738 31102 15739 31102 15733 31103 15739 31103 15864 31103 15864 31104 15739 31104 15740 31104 15754 31105 15741 31105 15793 31105 15793 31106 15741 31106 15671 31106 15793 31107 15671 31107 15805 31107 15805 31108 15671 31108 15743 31108 15805 31109 15743 31109 15742 31109 15742 31110 15743 31110 15736 31110 15742 31111 15736 31111 15803 31111 15790 31112 15791 31112 15732 31112 15732 31113 15791 31113 15744 31113 15732 31114 15744 31114 15846 31114 15846 31115 15744 31115 15792 31115 15846 31116 15792 31116 15844 31116 15844 31117 15792 31117 15682 31117 15844 31118 15682 31118 15745 31118 15746 31119 15747 31119 15827 31119 15827 31120 15747 31120 15749 31120 15827 31121 15749 31121 15748 31121 15748 31122 15749 31122 15750 31122 15748 31123 15750 31123 15751 31123 15751 31124 15750 31124 15752 31124 15761 31125 15753 31125 15754 31125 15754 31126 15753 31126 15669 31126 15754 31127 15669 31127 15741 31127 15760 31128 15798 31128 15765 31128 15765 31129 15798 31129 15799 31129 15819 31130 15800 31130 15755 31130 15755 31131 15800 31131 15801 31131 15755 31132 15801 31132 15756 31132 15756 31133 15801 31133 15803 31133 15756 31134 15803 31134 15757 31134 15757 31135 15803 31135 15736 31135 15757 31136 15736 31136 15831 31136 15831 31137 15736 31137 15829 31137 15758 31138 15840 31138 15894 31138 15894 31139 15840 31139 15842 31139 15765 31140 15759 31140 15760 31140 15760 31141 15759 31141 15778 31141 15760 31142 15778 31142 15795 31142 15795 31143 15778 31143 15781 31143 15795 31144 15781 31144 15761 31144 15761 31145 15781 31145 15683 31145 15761 31146 15683 31146 15753 31146 15894 31147 15898 31147 15758 31147 15758 31148 15898 31148 15762 31148 15758 31149 15762 31149 15740 31149 15740 31150 15762 31150 15763 31150 15740 31151 15763 31151 15864 31151 15745 31152 15682 31152 15764 31152 15764 31153 15682 31153 15766 31153 15764 31154 15766 31154 15767 31154 15906 31155 15908 31155 15823 31155 15823 31156 15908 31156 15768 31156 15823 31157 15768 31157 15820 31157 15820 31158 15768 31158 15765 31158 15820 31159 15765 31159 15819 31159 15819 31160 15765 31160 15799 31160 15819 31161 15799 31161 15800 31161 15766 31162 15787 31162 15767 31162 15767 31163 15787 31163 15786 31163 15767 31164 15786 31164 15842 31164 15842 31165 15786 31165 15785 31165 15842 31166 15785 31166 15894 31166 15906 31167 15823 31167 15903 31167 15903 31168 15823 31168 15748 31168 15903 31169 15748 31169 15901 31169 15901 31170 15748 31170 15859 31170 15901 31171 15859 31171 15898 31171 15898 31172 15859 31172 15862 31172 15898 31173 15862 31173 15762 31173 15926 31174 15765 31174 15918 31174 15918 31175 15765 31175 15768 31175 15918 31176 15768 31176 15910 31176 15911 31177 15769 31177 15912 31177 15912 31178 15769 31178 15919 31178 15912 31179 15919 31179 15770 31179 15770 31180 15919 31180 15918 31180 15770 31181 15918 31181 15910 31181 15902 31182 15900 31182 15771 31182 15771 31183 15900 31183 15775 31183 15775 31184 15900 31184 15899 31184 15775 31185 15899 31185 15897 31185 15902 31186 15771 31186 15772 31186 15772 31187 15771 31187 15914 31187 15772 31188 15914 31188 15904 31188 15904 31189 15914 31189 15916 31189 15904 31190 15916 31190 15773 31190 15773 31191 15916 31191 15905 31191 15905 31192 15916 31192 15774 31192 15905 31193 15774 31193 15907 31193 15907 31194 15774 31194 15909 31194 15909 31195 15774 31195 15769 31195 15909 31196 15769 31196 15911 31196 15775 31197 15897 31197 15922 31197 15922 31198 15897 31198 15896 31198 15922 31199 15896 31199 15776 31199 15922 31200 15776 31200 15782 31200 15782 31201 15776 31201 15895 31201 15765 31202 15926 31202 15777 31202 15765 31203 15777 31203 15759 31203 15759 31204 15777 31204 15925 31204 15759 31205 15925 31205 15778 31205 15778 31206 15925 31206 15779 31206 15778 31207 15779 31207 15781 31207 15781 31208 15779 31208 15780 31208 15781 31209 15780 31209 15683 31209 15784 31210 15894 31210 15785 31210 15782 31211 15895 31211 15783 31211 15783 31212 15895 31212 15784 31212 15784 31213 15785 31213 15783 31213 15783 31214 15785 31214 15786 31214 15783 31215 15786 31215 15928 31215 15928 31216 15786 31216 15787 31216 15928 31217 15787 31217 15930 31217 15930 31218 15787 31218 15766 31218 15930 31219 15766 31219 15788 31219 15680 31220 15945 31220 15789 31220 15789 31221 15945 31221 15944 31221 15789 31222 15944 31222 15790 31222 15790 31223 15944 31223 15791 31223 15791 31224 15944 31224 15942 31224 15791 31225 15942 31225 15744 31225 15744 31226 15942 31226 15941 31226 15744 31227 15941 31227 15792 31227 15792 31228 15941 31228 15939 31228 15792 31229 15939 31229 15682 31229 15805 31230 15816 31230 15793 31230 15793 31231 15816 31231 15794 31231 15793 31232 15794 31232 15754 31232 15754 31233 15794 31233 15806 31233 15754 31234 15806 31234 15761 31234 15761 31235 15806 31235 15808 31235 15761 31236 15808 31236 15795 31236 15795 31237 15808 31237 15810 31237 15795 31238 15810 31238 15760 31238 15760 31239 15810 31239 15796 31239 15760 31240 15796 31240 15798 31240 15798 31241 15796 31241 15797 31241 15798 31242 15797 31242 15799 31242 15799 31243 15797 31243 15811 31243 15799 31244 15811 31244 15800 31244 15800 31245 15811 31245 15802 31245 15800 31246 15802 31246 15801 31246 15801 31247 15802 31247 15813 31247 15801 31248 15813 31248 15803 31248 15803 31249 15813 31249 15804 31249 15803 31250 15804 31250 15742 31250 15742 31251 15804 31251 15815 31251 15742 31252 15815 31252 15805 31252 15805 31253 15815 31253 15816 31253 15794 31254 15807 31254 15806 31254 15806 31255 15807 31255 15708 31255 15806 31256 15708 31256 15808 31256 15808 31257 15708 31257 15809 31257 15808 31258 15809 31258 15810 31258 15810 31259 15809 31259 15707 31259 15810 31260 15707 31260 15796 31260 15796 31261 15707 31261 15693 31261 15796 31262 15693 31262 15797 31262 15797 31263 15693 31263 15692 31263 15797 31264 15692 31264 15811 31264 15811 31265 15692 31265 15691 31265 15811 31266 15691 31266 15802 31266 15802 31267 15691 31267 15812 31267 15802 31268 15812 31268 15813 31268 15813 31269 15812 31269 15703 31269 15813 31270 15703 31270 15804 31270 15804 31271 15703 31271 15814 31271 15804 31272 15814 31272 15815 31272 15815 31273 15814 31273 15702 31273 15815 31274 15702 31274 15816 31274 15816 31275 15702 31275 15817 31275 15816 31276 15817 31276 15794 31276 15794 31277 15817 31277 15807 31277 15831 31278 15832 31278 15757 31278 15757 31279 15832 31279 15818 31279 15757 31280 15818 31280 15756 31280 15756 31281 15818 31281 15833 31281 15756 31282 15833 31282 15755 31282 15755 31283 15833 31283 15834 31283 15755 31284 15834 31284 15819 31284 15819 31285 15834 31285 15821 31285 15819 31286 15821 31286 15820 31286 15820 31287 15821 31287 15822 31287 15820 31288 15822 31288 15823 31288 15823 31289 15822 31289 15824 31289 15823 31290 15824 31290 15730 31290 15730 31291 15824 31291 15825 31291 15730 31292 15825 31292 15731 31292 15731 31293 15825 31293 15826 31293 15731 31294 15826 31294 15827 31294 15827 31295 15826 31295 15828 31295 15827 31296 15828 31296 15737 31296 15737 31297 15828 31297 15836 31297 15737 31298 15836 31298 15829 31298 15829 31299 15836 31299 15830 31299 15829 31300 15830 31300 15831 31300 15831 31301 15830 31301 15832 31301 15818 31302 15714 31302 15833 31302 15833 31303 15714 31303 15712 31303 15833 31304 15712 31304 15834 31304 15834 31305 15712 31305 15711 31305 15834 31306 15711 31306 15821 31306 15821 31307 15711 31307 15706 31307 15821 31308 15706 31308 15822 31308 15822 31309 15706 31309 15705 31309 15822 31310 15705 31310 15824 31310 15824 31311 15705 31311 15704 31311 15824 31312 15704 31312 15825 31312 15825 31313 15704 31313 15835 31313 15825 31314 15835 31314 15826 31314 15826 31315 15835 31315 15727 31315 15826 31316 15727 31316 15828 31316 15828 31317 15727 31317 15720 31317 15828 31318 15720 31318 15836 31318 15836 31319 15720 31319 15726 31319 15836 31320 15726 31320 15830 31320 15830 31321 15726 31321 15723 31321 15830 31322 15723 31322 15832 31322 15832 31323 15723 31323 15721 31323 15832 31324 15721 31324 15818 31324 15818 31325 15721 31325 15714 31325 15732 31326 15856 31326 15738 31326 15738 31327 15856 31327 15837 31327 15738 31328 15837 31328 15739 31328 15739 31329 15837 31329 15847 31329 15739 31330 15847 31330 15740 31330 15740 31331 15847 31331 15838 31331 15740 31332 15838 31332 15758 31332 15758 31333 15838 31333 15839 31333 15758 31334 15839 31334 15840 31334 15840 31335 15839 31335 15841 31335 15840 31336 15841 31336 15842 31336 15842 31337 15841 31337 15848 31337 15842 31338 15848 31338 15767 31338 15767 31339 15848 31339 15849 31339 15767 31340 15849 31340 15764 31340 15764 31341 15849 31341 15851 31341 15764 31342 15851 31342 15745 31342 15745 31343 15851 31343 15843 31343 15745 31344 15843 31344 15844 31344 15844 31345 15843 31345 15845 31345 15844 31346 15845 31346 15846 31346 15846 31347 15845 31347 15855 31347 15846 31348 15855 31348 15732 31348 15732 31349 15855 31349 15856 31349 15837 31350 15857 31350 15847 31350 15847 31351 15857 31351 15701 31351 15847 31352 15701 31352 15838 31352 15838 31353 15701 31353 15700 31353 15838 31354 15700 31354 15839 31354 15839 31355 15700 31355 15699 31355 15839 31356 15699 31356 15841 31356 15841 31357 15699 31357 15698 31357 15841 31358 15698 31358 15848 31358 15848 31359 15698 31359 15697 31359 15848 31360 15697 31360 15849 31360 15849 31361 15697 31361 15850 31361 15849 31362 15850 31362 15851 31362 15851 31363 15850 31363 15852 31363 15851 31364 15852 31364 15843 31364 15843 31365 15852 31365 15853 31365 15843 31366 15853 31366 15845 31366 15845 31367 15853 31367 15695 31367 15845 31368 15695 31368 15855 31368 15855 31369 15695 31369 15854 31369 15855 31370 15854 31370 15856 31370 15856 31371 15854 31371 15690 31371 15856 31372 15690 31372 15837 31372 15837 31373 15690 31373 15857 31373 15867 31374 15879 31374 15752 31374 15752 31375 15879 31375 15858 31375 15752 31376 15858 31376 15751 31376 15751 31377 15858 31377 15869 31377 15751 31378 15869 31378 15748 31378 15748 31379 15869 31379 15871 31379 15748 31380 15871 31380 15859 31380 15859 31381 15871 31381 15860 31381 15859 31382 15860 31382 15862 31382 15862 31383 15860 31383 15861 31383 15862 31384 15861 31384 15762 31384 15762 31385 15861 31385 15873 31385 15762 31386 15873 31386 15763 31386 15763 31387 15873 31387 15863 31387 15763 31388 15863 31388 15864 31388 15864 31389 15863 31389 15865 31389 15864 31390 15865 31390 15733 31390 15733 31391 15865 31391 15866 31391 15733 31392 15866 31392 15734 31392 15734 31393 15866 31393 15877 31393 15734 31394 15877 31394 15735 31394 15735 31395 15877 31395 15868 31395 15735 31396 15868 31396 15867 31396 15867 31397 15868 31397 15879 31397 15858 31398 15717 31398 15869 31398 15869 31399 15717 31399 15870 31399 15869 31400 15870 31400 15871 31400 15871 31401 15870 31401 15716 31401 15871 31402 15716 31402 15860 31402 15860 31403 15716 31403 15872 31403 15860 31404 15872 31404 15861 31404 15861 31405 15872 31405 15719 31405 15861 31406 15719 31406 15873 31406 15873 31407 15719 31407 15874 31407 15873 31408 15874 31408 15863 31408 15863 31409 15874 31409 15718 31409 15863 31410 15718 31410 15865 31410 15865 31411 15718 31411 15685 31411 15865 31412 15685 31412 15866 31412 15866 31413 15685 31413 15875 31413 15866 31414 15875 31414 15877 31414 15877 31415 15875 31415 15876 31415 15877 31416 15876 31416 15868 31416 15868 31417 15876 31417 15878 31417 15868 31418 15878 31418 15879 31418 15879 31419 15878 31419 15880 31419 15879 31420 15880 31420 15858 31420 15858 31421 15880 31421 15717 31421 15881 31422 15883 31422 15882 31422 15882 31423 15883 31423 15673 31423 15882 31424 15673 31424 15736 31424 15736 31425 15673 31425 15746 31425 15681 31426 15891 31426 15884 31426 15884 31427 15891 31427 15893 31427 15681 31428 15680 31428 15891 31428 15891 31429 15680 31429 15789 31429 15891 31430 15789 31430 15790 31430 15673 31431 15674 31431 15746 31431 15746 31432 15674 31432 15675 31432 15746 31433 15675 31433 15747 31433 15675 31434 15885 31434 15747 31434 15747 31435 15885 31435 15886 31435 15747 31436 15886 31436 15749 31436 15886 31437 15887 31437 15749 31437 15749 31438 15887 31438 15888 31438 15749 31439 15888 31439 15750 31439 15888 31440 15889 31440 15750 31440 15750 31441 15889 31441 15890 31441 15750 31442 15890 31442 15891 31442 15891 31443 15890 31443 15892 31443 15891 31444 15892 31444 15893 31444 15898 31445 15894 31445 15784 31445 15784 31446 15895 31446 15898 31446 15898 31447 15895 31447 15776 31447 15898 31448 15776 31448 15896 31448 15896 31449 15897 31449 15898 31449 15898 31450 15897 31450 15899 31450 15898 31451 15899 31451 15901 31451 15899 31452 15900 31452 15901 31452 15901 31453 15900 31453 15902 31453 15901 31454 15902 31454 15903 31454 15902 31455 15772 31455 15903 31455 15903 31456 15772 31456 15904 31456 15903 31457 15904 31457 15906 31457 15904 31458 15773 31458 15906 31458 15906 31459 15773 31459 15905 31459 15906 31460 15905 31460 15908 31460 15905 31461 15907 31461 15908 31461 15908 31462 15907 31462 15909 31462 15908 31463 15909 31463 15768 31463 15768 31464 15909 31464 15911 31464 15768 31465 15911 31465 15910 31465 15910 31466 15911 31466 15912 31466 15910 31467 15912 31467 15770 31467 15775 31468 15684 31468 15771 31468 15771 31469 15684 31469 15913 31469 15771 31470 15913 31470 15914 31470 15914 31471 15913 31471 15915 31471 15914 31472 15915 31472 15916 31472 15916 31473 15915 31473 15729 31473 15916 31474 15729 31474 15774 31474 15774 31475 15729 31475 15728 31475 15774 31476 15728 31476 15769 31476 15769 31477 15728 31477 15917 31477 15921 31478 15918 31478 15919 31478 15921 31479 15919 31479 15694 31479 15694 31480 15919 31480 15769 31480 15694 31481 15769 31481 15917 31481 15775 31482 15922 31482 15684 31482 15684 31483 15922 31483 15686 31483 15920 31484 15926 31484 15921 31484 15921 31485 15926 31485 15918 31485 15782 31486 15687 31486 15922 31486 15922 31487 15687 31487 15686 31487 15934 31488 15780 31488 15779 31488 15934 31489 15779 31489 15923 31489 15923 31490 15779 31490 15925 31490 15923 31491 15925 31491 15924 31491 15924 31492 15925 31492 15777 31492 15924 31493 15777 31493 15927 31493 15927 31494 15777 31494 15926 31494 15927 31495 15926 31495 15920 31495 15687 31496 15782 31496 15783 31496 15687 31497 15783 31497 15696 31497 15696 31498 15783 31498 15928 31498 15696 31499 15928 31499 15929 31499 15929 31500 15928 31500 15930 31500 15929 31501 15930 31501 15931 31501 15931 31502 15930 31502 15788 31502 15931 31503 15788 31503 15936 31503 15932 31504 15933 31504 15934 31504 15934 31505 15933 31505 15780 31505 15939 31506 15935 31506 15788 31506 15788 31507 15935 31507 15936 31507 15713 31508 15672 31508 15670 31508 15713 31509 15670 31509 15937 31509 15937 31510 15670 31510 15938 31510 15937 31511 15938 31511 15710 31511 15710 31512 15938 31512 15668 31512 15710 31513 15668 31513 15709 31513 15709 31514 15668 31514 15933 31514 15709 31515 15933 31515 15932 31515 15935 31516 15939 31516 15941 31516 15935 31517 15941 31517 15940 31517 15940 31518 15941 31518 15942 31518 15940 31519 15942 31519 15688 31519 15688 31520 15942 31520 15944 31520 15688 31521 15944 31521 15943 31521 15943 31522 15944 31522 15945 31522 15943 31523 15945 31523 15689 31523 15722 31524 15948 31524 15713 31524 15713 31525 15948 31525 15672 31525 15949 31526 15950 31526 15945 31526 15945 31527 15950 31527 15689 31527 15725 31528 15946 31528 15947 31528 15725 31529 15947 31529 15724 31529 15724 31530 15947 31530 15948 31530 15724 31531 15948 31531 15722 31531 15949 31532 15679 31532 15950 31532 15950 31533 15679 31533 15951 31533 15946 31534 15725 31534 15676 31534 15676 31535 15725 31535 15715 31535 15676 31536 15715 31536 15677 31536 15677 31537 15715 31537 15952 31537 15677 31538 15952 31538 15953 31538 15953 31539 15952 31539 15954 31539 15953 31540 15954 31540 15678 31540 15678 31541 15954 31541 15955 31541 15678 31542 15955 31542 15679 31542 15679 31543 15955 31543 15951 31543 15956 31544 15957 31544 19095 31544 19095 31545 15957 31545 15959 31545 19095 31546 15959 31546 15958 31546 15958 31547 15959 31547 15960 31547 15958 31548 15960 31548 19091 31548 19091 31549 15960 31549 15961 31549 19091 31550 15961 31550 19090 31550 19090 31551 15961 31551 15962 31551 19090 31552 15962 31552 19087 31552 19087 31553 15962 31553 15963 31553 19087 31554 15963 31554 19088 31554 19088 31555 15963 31555 16006 31555 16004 31556 19941 31556 15964 31556 15964 31557 19941 31557 15965 31557 15964 31558 15965 31558 15966 31558 15966 31559 15965 31559 18816 31559 15966 31560 18816 31560 15967 31560 15967 31561 18816 31561 15968 31561 15967 31562 15968 31562 15969 31562 15969 31563 15968 31563 15970 31563 15969 31564 15970 31564 15971 31564 15971 31565 15970 31565 18819 31565 15971 31566 18819 31566 15972 31566 15972 31567 18819 31567 15973 31567 15972 31568 15973 31568 15974 31568 15974 31569 15973 31569 19937 31569 15994 31570 16021 31570 15975 31570 15975 31571 16021 31571 15976 31571 15975 31572 15976 31572 15977 31572 15977 31573 15976 31573 15978 31573 15977 31574 15978 31574 19098 31574 19098 31575 15978 31575 15979 31575 19098 31576 15979 31576 19099 31576 19099 31577 15979 31577 15980 31577 19099 31578 15980 31578 19171 31578 19171 31579 15980 31579 16012 31579 19171 31580 16012 31580 19170 31580 19170 31581 16012 31581 16013 31581 19170 31582 16013 31582 15981 31582 15981 31583 16013 31583 16014 31583 15981 31584 16014 31584 15982 31584 15982 31585 16014 31585 15983 31585 15982 31586 15983 31586 15984 31586 15984 31587 15983 31587 15985 31587 15984 31588 15985 31588 15986 31588 15986 31589 15985 31589 15987 31589 15986 31590 15987 31590 19097 31590 19097 31591 15987 31591 15988 31591 19097 31592 15988 31592 15989 31592 15989 31593 15988 31593 16020 31593 15989 31594 16020 31594 19089 31594 19089 31595 16020 31595 15990 31595 19089 31596 15990 31596 15991 31596 15991 31597 15990 31597 15992 31597 15991 31598 15992 31598 19096 31598 19096 31599 15992 31599 15993 31599 19096 31600 15993 31600 15994 31600 15994 31601 15993 31601 16021 31601 15974 31602 19937 31602 19138 31602 19138 31603 19937 31603 15995 31603 19138 31604 15995 31604 15996 31604 15996 31605 15995 31605 15997 31605 15996 31606 15997 31606 15998 31606 15998 31607 15997 31607 15999 31607 15998 31608 15999 31608 16000 31608 16000 31609 15999 31609 16001 31609 16000 31610 16001 31610 16002 31610 16002 31611 16001 31611 16003 31611 16002 31612 16003 31612 16004 31612 16004 31613 16003 31613 19941 31613 19088 31614 16006 31614 16005 31614 16005 31615 16006 31615 16007 31615 16005 31616 16007 31616 19092 31616 19092 31617 16007 31617 19943 31617 19092 31618 19943 31618 19215 31618 19215 31619 19943 31619 19944 31619 19215 31620 19944 31620 16008 31620 16008 31621 19944 31621 16009 31621 16008 31622 16009 31622 19094 31622 19094 31623 16009 31623 16010 31623 19094 31624 16010 31624 15956 31624 15956 31625 16010 31625 15957 31625 18848 31626 16012 31626 16011 31626 16011 31627 16012 31627 15980 31627 16012 31628 18848 31628 16013 31628 16013 31629 18848 31629 18847 31629 16013 31630 18847 31630 16014 31630 16014 31631 18847 31631 18831 31631 16014 31632 18831 31632 15983 31632 15983 31633 18831 31633 18832 31633 15976 31634 18840 31634 15978 31634 15978 31635 18840 31635 16015 31635 15978 31636 16015 31636 15979 31636 15979 31637 16015 31637 18849 31637 15979 31638 18849 31638 15980 31638 15980 31639 18849 31639 16011 31639 15983 31640 18832 31640 15985 31640 15985 31641 18832 31641 16017 31641 18840 31642 15976 31642 16016 31642 16016 31643 15976 31643 16021 31643 15985 31644 16017 31644 15987 31644 15987 31645 16017 31645 16018 31645 15987 31646 16018 31646 15988 31646 15988 31647 16018 31647 16019 31647 15988 31648 16019 31648 16020 31648 16020 31649 16019 31649 16022 31649 15990 31650 18836 31650 15992 31650 15992 31651 18836 31651 18835 31651 15992 31652 18835 31652 15993 31652 15993 31653 18835 31653 18827 31653 15993 31654 18827 31654 16021 31654 16021 31655 18827 31655 16016 31655 18836 31656 15990 31656 16022 31656 16022 31657 15990 31657 16020 31657 16046 31658 16036 31658 16045 31658 16027 31659 16023 31659 16024 31659 16024 31660 16023 31660 16025 31660 16024 31661 16025 31661 19760 31661 16026 31662 16038 31662 16035 31662 16035 31663 16038 31663 19762 31663 16035 31664 19762 31664 16027 31664 16047 31665 16028 31665 16041 31665 16041 31666 16028 31666 16029 31666 16030 31667 16031 31667 19755 31667 19755 31668 16031 31668 16032 31668 19755 31669 16032 31669 19757 31669 19757 31670 16032 31670 19758 31670 19758 31671 16032 31671 16043 31671 19758 31672 16043 31672 16033 31672 16033 31673 16043 31673 16042 31673 16033 31674 16042 31674 19751 31674 16027 31675 16024 31675 16035 31675 16035 31676 16024 31676 16034 31676 16035 31677 16034 31677 16026 31677 16036 31678 16040 31678 16037 31678 16037 31679 16040 31679 16038 31679 16037 31680 16038 31680 16039 31680 16039 31681 16038 31681 16026 31681 16036 31682 16046 31682 16040 31682 16040 31683 16046 31683 16041 31683 16040 31684 16041 31684 16038 31684 16038 31685 16041 31685 16029 31685 16038 31686 16029 31686 19762 31686 16077 31687 16042 31687 16044 31687 16044 31688 16042 31688 16043 31688 16044 31689 16043 31689 16045 31689 16045 31690 16043 31690 16032 31690 16045 31691 16032 31691 16046 31691 16046 31692 16032 31692 16031 31692 16046 31693 16031 31693 16041 31693 16041 31694 16031 31694 16030 31694 16041 31695 16030 31695 16047 31695 19909 31696 16050 31696 16048 31696 16048 31697 16050 31697 16069 31697 16048 31698 16069 31698 19905 31698 19909 31699 16049 31699 16050 31699 16050 31700 16049 31700 19908 31700 16050 31701 19908 31701 16052 31701 19908 31702 16051 31702 16052 31702 16052 31703 16051 31703 19906 31703 16052 31704 19906 31704 16070 31704 16070 31705 19906 31705 16072 31705 16072 31706 19906 31706 16053 31706 16072 31707 16053 31707 18919 31707 20267 31708 20288 31708 16061 31708 19901 31709 16073 31709 16058 31709 16058 31710 16073 31710 16074 31710 19905 31711 16069 31711 19902 31711 19902 31712 16069 31712 16054 31712 19902 31713 16054 31713 19903 31713 16055 31714 19903 31714 16056 31714 16056 31715 19903 31715 16054 31715 16056 31716 16054 31716 16057 31716 19760 31717 20240 31717 16024 31717 16024 31718 20240 31718 20239 31718 16024 31719 20239 31719 16034 31719 16034 31720 20239 31720 20283 31720 16034 31721 20283 31721 16074 31721 16074 31722 20283 31722 16059 31722 16074 31723 16059 31723 16058 31723 16058 31724 16059 31724 16060 31724 20267 31725 16061 31725 16071 31725 16071 31726 16061 31726 16062 31726 16071 31727 16062 31727 16063 31727 16063 31728 16062 31728 16076 31728 16063 31729 16076 31729 16064 31729 16064 31730 16076 31730 16065 31730 16064 31731 16065 31731 16066 31731 16066 31732 16065 31732 16075 31732 16066 31733 16075 31733 16068 31733 16068 31734 16075 31734 16067 31734 16068 31735 16067 31735 16057 31735 16057 31736 16054 31736 16068 31736 16068 31737 16054 31737 16069 31737 16068 31738 16069 31738 16066 31738 16066 31739 16069 31739 16050 31739 16066 31740 16050 31740 16064 31740 16064 31741 16050 31741 16052 31741 16064 31742 16052 31742 16063 31742 16063 31743 16052 31743 16070 31743 16063 31744 16070 31744 16071 31744 16071 31745 16070 31745 16072 31745 16071 31746 16072 31746 20267 31746 19901 31747 16055 31747 16073 31747 16073 31748 16055 31748 16056 31748 16073 31749 16056 31749 16074 31749 16074 31750 16056 31750 16057 31750 16074 31751 16057 31751 16034 31751 16034 31752 16057 31752 16067 31752 16034 31753 16067 31753 16026 31753 16026 31754 16067 31754 16075 31754 16026 31755 16075 31755 16039 31755 16039 31756 16075 31756 16065 31756 16039 31757 16065 31757 16037 31757 16037 31758 16065 31758 16076 31758 16037 31759 16076 31759 16036 31759 16036 31760 16076 31760 16062 31760 16036 31761 16062 31761 16045 31761 16045 31762 16062 31762 16061 31762 16045 31763 16061 31763 16044 31763 16044 31764 16061 31764 20288 31764 16044 31765 20288 31765 16077 31765 16123 31766 20225 31766 20220 31766 16114 31767 16078 31767 16115 31767 16079 31768 16113 31768 19632 31768 20231 31769 20226 31769 19634 31769 19634 31770 20226 31770 16079 31770 19634 31771 16079 31771 19635 31771 19635 31772 16079 31772 19632 31772 20226 31773 20227 31773 16079 31773 16079 31774 20227 31774 16126 31774 16079 31775 16126 31775 16113 31775 16113 31776 16126 31776 16080 31776 16113 31777 16080 31777 16081 31777 16081 31778 16080 31778 16127 31778 16081 31779 16127 31779 16082 31779 16082 31780 16127 31780 16083 31780 16082 31781 16083 31781 16110 31781 16110 31782 16083 31782 16128 31782 16110 31783 16128 31783 16084 31783 16084 31784 16128 31784 16129 31784 16084 31785 16129 31785 16108 31785 16086 31786 16105 31786 16085 31786 19929 31787 16090 31787 16089 31787 16086 31788 16087 31788 16105 31788 16105 31789 16087 31789 16088 31789 16105 31790 16088 31790 16089 31790 16089 31791 16088 31791 19931 31791 16089 31792 19931 31792 19929 31792 19929 31793 16091 31793 16090 31793 16090 31794 16091 31794 20214 31794 16090 31795 20214 31795 16107 31795 16093 31796 16092 31796 18884 31796 18884 31797 19925 31797 16093 31797 16093 31798 19925 31798 16095 31798 16093 31799 16095 31799 16078 31799 19925 31800 16094 31800 16095 31800 16095 31801 16094 31801 16096 31801 16095 31802 16096 31802 16097 31802 16097 31803 16096 31803 16098 31803 16097 31804 16098 31804 16100 31804 16098 31805 16099 31805 16100 31805 16100 31806 16099 31806 16101 31806 16100 31807 16101 31807 16085 31807 16085 31808 16101 31808 16102 31808 16085 31809 16102 31809 16086 31809 20227 31810 16114 31810 16116 31810 16078 31811 16095 31811 16115 31811 16115 31812 16095 31812 16097 31812 16115 31813 16097 31813 16103 31813 16103 31814 16097 31814 16100 31814 16103 31815 16100 31815 16118 31815 16118 31816 16100 31816 16085 31816 16118 31817 16085 31817 16120 31817 16120 31818 16085 31818 16105 31818 16120 31819 16105 31819 16104 31819 16104 31820 16105 31820 16089 31820 16104 31821 16089 31821 16106 31821 16106 31822 16089 31822 16090 31822 16106 31823 16090 31823 16123 31823 16123 31824 16090 31824 16107 31824 16123 31825 16107 31825 20225 31825 19630 31826 19629 31826 16108 31826 16108 31827 19629 31827 16109 31827 16108 31828 16109 31828 16084 31828 16084 31829 16109 31829 19642 31829 16084 31830 19642 31830 16110 31830 16110 31831 19642 31831 19653 31831 16110 31832 19653 31832 16082 31832 19653 31833 16111 31833 16082 31833 16082 31834 16111 31834 19537 31834 16082 31835 19537 31835 16081 31835 16081 31836 19537 31836 19538 31836 16081 31837 19538 31837 16113 31837 16113 31838 19538 31838 16112 31838 16113 31839 16112 31839 19632 31839 16114 31840 16115 31840 16116 31840 16116 31841 16115 31841 16103 31841 16116 31842 16103 31842 16117 31842 16117 31843 16103 31843 16118 31843 16117 31844 16118 31844 16119 31844 16119 31845 16118 31845 16120 31845 16119 31846 16120 31846 16121 31846 16121 31847 16120 31847 16104 31847 16121 31848 16104 31848 16122 31848 16122 31849 16104 31849 16106 31849 16122 31850 16106 31850 16130 31850 16130 31851 16106 31851 16123 31851 16130 31852 16123 31852 16124 31852 16124 31853 16123 31853 20220 31853 16124 31854 20220 31854 16125 31854 20227 31855 16116 31855 16126 31855 16126 31856 16116 31856 16117 31856 16126 31857 16117 31857 16080 31857 16080 31858 16117 31858 16119 31858 16080 31859 16119 31859 16127 31859 16127 31860 16119 31860 16121 31860 16127 31861 16121 31861 16083 31861 16083 31862 16121 31862 16122 31862 16083 31863 16122 31863 16128 31863 16128 31864 16122 31864 16130 31864 16128 31865 16130 31865 16129 31865 16129 31866 16130 31866 16124 31866 16129 31867 16124 31867 16108 31867 16108 31868 16124 31868 16125 31868 16108 31869 16125 31869 19630 31869 16160 31870 16162 31870 16164 31870 16131 31871 19554 31871 16133 31871 16133 31872 19554 31872 16132 31872 16133 31873 16132 31873 16158 31873 16158 31874 16132 31874 19552 31874 16158 31875 19552 31875 20161 31875 16131 31876 16133 31876 19556 31876 19556 31877 16133 31877 16154 31877 19556 31878 16154 31878 16134 31878 16134 31879 16154 31879 16153 31879 16134 31880 16153 31880 19558 31880 19558 31881 16153 31881 16152 31881 19558 31882 16152 31882 19559 31882 19559 31883 16152 31883 16150 31883 19559 31884 16150 31884 19560 31884 19560 31885 16150 31885 16135 31885 19560 31886 16135 31886 16138 31886 16136 31887 20152 31887 16135 31887 16135 31888 20152 31888 16137 31888 16135 31889 16137 31889 16138 31889 19888 31890 16139 31890 16159 31890 16159 31891 16139 31891 16140 31891 16159 31892 16140 31892 16141 31892 16141 31893 16140 31893 19881 31893 16141 31894 19881 31894 16142 31894 16168 31895 19889 31895 16167 31895 16167 31896 19889 31896 19888 31896 16144 31897 19887 31897 16168 31897 16168 31898 19887 31898 16143 31898 16168 31899 16143 31899 19889 31899 16147 31900 19879 31900 16144 31900 16144 31901 19879 31901 19885 31901 16144 31902 19885 31902 19887 31902 16148 31903 16149 31903 16145 31903 16145 31904 16149 31904 16146 31904 16145 31905 16146 31905 16147 31905 16147 31906 16146 31906 19884 31906 16147 31907 19884 31907 19879 31907 18954 31908 18953 31908 20175 31908 20175 31909 18953 31909 18952 31909 20175 31910 18952 31910 16148 31910 16148 31911 18952 31911 19882 31911 16148 31912 19882 31912 16149 31912 16163 31913 16136 31913 16165 31913 16165 31914 16136 31914 16135 31914 16165 31915 16135 31915 16166 31915 16166 31916 16135 31916 16150 31916 16166 31917 16150 31917 16151 31917 16151 31918 16150 31918 16152 31918 16151 31919 16152 31919 16169 31919 16169 31920 16152 31920 16153 31920 16169 31921 16153 31921 16155 31921 16155 31922 16153 31922 16154 31922 16155 31923 16154 31923 16156 31923 16156 31924 16154 31924 16133 31924 16156 31925 16133 31925 16157 31925 16157 31926 16133 31926 16158 31926 16157 31927 16158 31927 20183 31927 20183 31928 16158 31928 20161 31928 19888 31929 16159 31929 16167 31929 16167 31930 16159 31930 16141 31930 16167 31931 16141 31931 16164 31931 16164 31932 16141 31932 16142 31932 16164 31933 16142 31933 16160 31933 16147 31934 16170 31934 16145 31934 16145 31935 16170 31935 16161 31935 16145 31936 16161 31936 16148 31936 16148 31937 16161 31937 16171 31937 16148 31938 16171 31938 20175 31938 16162 31939 16163 31939 16164 31939 16164 31940 16163 31940 16165 31940 16164 31941 16165 31941 16167 31941 16167 31942 16165 31942 16166 31942 16167 31943 16166 31943 16168 31943 16168 31944 16166 31944 16151 31944 16168 31945 16151 31945 16144 31945 16144 31946 16151 31946 16169 31946 16144 31947 16169 31947 16147 31947 16147 31948 16169 31948 16155 31948 16147 31949 16155 31949 16170 31949 16170 31950 16155 31950 16156 31950 16170 31951 16156 31951 16161 31951 16161 31952 16156 31952 16157 31952 16161 31953 16157 31953 16171 31953 16171 31954 16157 31954 20183 31954 19872 31955 16194 31955 16172 31955 20142 31956 16197 31956 16173 31956 16173 31957 16197 31957 18978 31957 16172 31958 16194 31958 16196 31958 19870 31959 16198 31959 16195 31959 19872 31960 16172 31960 19873 31960 19873 31961 16172 31961 16174 31961 19873 31962 16174 31962 19859 31962 19859 31963 16174 31963 19860 31963 19860 31964 16174 31964 16211 31964 19860 31965 16211 31965 16179 31965 16175 31966 16176 31966 16180 31966 16180 31967 19867 31967 16175 31967 16175 31968 19867 31968 16177 31968 16175 31969 16177 31969 16211 31969 16211 31970 16177 31970 16178 31970 16211 31971 16178 31971 16179 31971 19865 31972 19863 31972 16180 31972 16180 31973 19863 31973 16181 31973 16180 31974 16181 31974 19867 31974 16191 31975 19335 31975 16189 31975 16189 31976 19335 31976 16182 31976 16189 31977 16182 31977 16188 31977 16188 31978 16182 31978 19333 31978 16188 31979 19333 31979 16183 31979 16192 31980 16193 31980 19338 31980 16184 31981 19362 31981 16185 31981 16184 31982 16185 31982 16186 31982 16186 31983 16185 31983 19361 31983 16186 31984 19361 31984 16193 31984 16193 31985 19361 31985 16187 31985 16193 31986 16187 31986 19338 31986 16188 31987 16215 31987 16189 31987 16189 31988 16215 31988 16190 31988 16189 31989 16190 31989 16191 31989 16191 31990 16190 31990 16213 31990 16191 31991 16213 31991 16192 31991 16192 31992 16213 31992 16212 31992 16192 31993 16212 31993 16193 31993 16193 31994 16212 31994 16210 31994 16193 31995 16210 31995 16186 31995 16186 31996 16210 31996 16209 31996 16186 31997 16209 31997 16184 31997 16184 31998 16209 31998 16208 31998 16184 31999 16208 31999 16202 31999 16194 32000 19870 32000 16196 32000 16196 32001 19870 32001 16195 32001 16196 32002 16195 32002 16197 32002 16197 32003 16195 32003 16198 32003 16197 32004 16198 32004 18978 32004 19866 32005 19865 32005 16199 32005 16199 32006 19865 32006 16180 32006 16199 32007 16180 32007 16200 32007 16200 32008 16180 32008 16176 32008 16200 32009 16176 32009 16214 32009 19862 32010 19866 32010 20116 32010 20116 32011 19866 32011 16199 32011 20116 32012 16199 32012 16201 32012 16201 32013 16199 32013 16200 32013 16201 32014 16200 32014 20114 32014 20114 32015 16200 32015 16214 32015 20114 32016 16214 32016 20112 32016 19362 32017 16184 32017 19376 32017 19376 32018 16184 32018 16202 32018 19376 32019 16202 32019 20146 32019 19338 32020 16203 32020 16192 32020 16192 32021 16203 32021 16204 32021 16192 32022 16204 32022 16191 32022 16191 32023 16204 32023 16205 32023 16191 32024 16205 32024 19335 32024 16207 32025 16206 32025 16208 32025 16208 32026 16206 32026 20145 32026 16208 32027 20145 32027 16202 32027 16197 32028 16207 32028 16196 32028 16196 32029 16207 32029 16208 32029 16196 32030 16208 32030 16172 32030 16172 32031 16208 32031 16209 32031 16172 32032 16209 32032 16174 32032 16174 32033 16209 32033 16210 32033 16174 32034 16210 32034 16211 32034 16211 32035 16210 32035 16212 32035 16211 32036 16212 32036 16175 32036 16175 32037 16212 32037 16213 32037 16175 32038 16213 32038 16176 32038 16176 32039 16213 32039 16190 32039 16176 32040 16190 32040 16214 32040 16214 32041 16190 32041 16215 32041 16214 32042 16215 32042 20112 32042 20112 32043 16215 32043 16188 32043 20112 32044 16188 32044 20110 32044 20110 32045 16188 32045 16183 32045 20110 32046 16183 32046 19332 32046 19395 32047 16254 32047 16216 32047 20069 32048 16244 32048 16217 32048 16257 32049 16259 32049 16253 32049 16218 32050 16221 32050 16220 32050 16219 32051 16225 32051 16220 32051 16219 32052 16220 32052 20067 32052 20067 32053 16220 32053 16221 32053 20067 32054 16221 32054 19456 32054 16256 32055 16248 32055 16222 32055 16222 32056 16248 32056 16223 32056 16222 32057 16223 32057 16224 32057 16224 32058 16223 32058 16226 32058 16224 32059 16226 32059 16225 32059 16225 32060 16226 32060 16220 32060 16220 32061 16226 32061 16250 32061 16220 32062 16250 32062 16218 32062 16247 32063 16248 32063 16227 32063 16227 32064 16248 32064 16256 32064 16227 32065 16256 32065 16257 32065 16257 32066 16253 32066 16227 32066 16227 32067 16253 32067 16228 32067 16227 32068 16228 32068 16247 32068 16229 32069 16236 32069 16258 32069 16237 32070 16230 32070 16238 32070 16238 32071 16230 32071 16231 32071 16232 32072 16234 32072 16233 32072 16233 32073 16234 32073 19035 32073 16229 32074 16235 32074 16236 32074 16236 32075 16235 32075 16237 32075 16236 32076 16237 32076 16260 32076 16260 32077 16237 32077 16238 32077 16260 32078 16238 32078 16262 32078 16262 32079 16238 32079 16231 32079 16262 32080 16231 32080 19822 32080 16234 32081 20098 32081 16261 32081 16261 32082 20098 32082 16252 32082 16261 32083 16252 32083 16259 32083 19826 32084 16239 32084 20070 32084 20070 32085 16239 32085 16243 32085 19828 32086 16240 32086 16241 32086 16241 32087 16240 32087 16255 32087 16241 32088 16255 32088 16242 32088 16242 32089 16255 32089 19827 32089 19827 32090 16255 32090 16239 32090 16239 32091 16255 32091 16217 32091 16239 32092 16217 32092 16243 32092 16243 32093 16217 32093 16244 32093 16243 32094 16244 32094 20070 32094 19828 32095 19833 32095 16240 32095 16240 32096 19833 32096 19832 32096 16240 32097 19832 32097 16258 32097 16258 32098 19832 32098 19831 32098 16258 32099 19831 32099 16229 32099 16251 32100 20086 32100 16245 32100 16245 32101 20086 32101 16246 32101 16245 32102 16246 32102 16216 32102 16216 32103 16246 32103 20058 32103 16216 32104 20058 32104 19395 32104 16247 32105 19392 32105 16248 32105 16248 32106 19392 32106 19388 32106 16248 32107 19388 32107 16223 32107 16223 32108 19388 32108 16249 32108 16223 32109 16249 32109 16226 32109 16226 32110 16249 32110 19458 32110 16226 32111 19458 32111 16250 32111 20098 32112 16251 32112 16252 32112 16252 32113 16251 32113 16245 32113 16252 32114 16245 32114 16259 32114 16259 32115 16245 32115 16216 32115 16259 32116 16216 32116 16253 32116 16253 32117 16216 32117 16254 32117 16253 32118 16254 32118 16228 32118 16219 32119 20069 32119 16225 32119 16225 32120 20069 32120 16217 32120 16225 32121 16217 32121 16224 32121 16224 32122 16217 32122 16255 32122 16224 32123 16255 32123 16222 32123 16222 32124 16255 32124 16240 32124 16222 32125 16240 32125 16256 32125 16256 32126 16240 32126 16258 32126 16256 32127 16258 32127 16257 32127 16257 32128 16258 32128 16236 32128 16257 32129 16236 32129 16259 32129 16259 32130 16236 32130 16260 32130 16259 32131 16260 32131 16261 32131 16261 32132 16260 32132 16262 32132 16261 32133 16262 32133 16234 32133 16234 32134 16262 32134 19822 32134 16234 32135 19822 32135 19035 32135 20029 32136 20046 32136 16295 32136 19713 32137 16263 32137 16291 32137 16291 32138 16263 32138 16265 32138 16291 32139 16265 32139 16264 32139 16264 32140 16265 32140 19729 32140 16264 32141 19729 32141 16293 32141 19713 32142 16291 32142 16267 32142 16267 32143 16291 32143 16266 32143 16267 32144 16266 32144 16268 32144 16268 32145 16266 32145 16288 32145 16268 32146 16288 32146 16269 32146 16269 32147 16288 32147 16287 32147 16269 32148 16287 32148 16270 32148 16270 32149 16287 32149 16271 32149 16270 32150 16271 32150 19715 32150 19715 32151 16271 32151 16274 32151 19715 32152 16274 32152 16272 32152 16273 32153 20006 32153 16274 32153 16274 32154 20006 32154 16275 32154 16274 32155 16275 32155 16272 32155 16276 32156 19813 32156 16294 32156 16294 32157 19813 32157 16277 32157 16294 32158 16277 32158 16278 32158 16278 32159 16277 32159 20026 32159 16278 32160 20026 32160 20028 32160 16300 32161 19814 32161 16297 32161 16297 32162 19814 32162 16276 32162 16279 32163 19809 32163 16300 32163 16300 32164 19809 32164 19810 32164 16300 32165 19810 32165 19814 32165 16301 32166 19804 32166 16279 32166 16279 32167 19804 32167 16280 32167 16279 32168 16280 32168 19809 32168 16284 32169 19808 32169 16296 32169 16296 32170 19808 32170 19807 32170 16296 32171 19807 32171 16301 32171 16301 32172 19807 32172 16281 32172 16301 32173 16281 32173 19804 32173 19078 32174 16283 32174 16282 32174 16282 32175 16283 32175 19077 32175 16282 32176 19077 32176 16284 32176 16284 32177 19077 32177 19805 32177 16284 32178 19805 32178 19808 32178 20047 32179 16273 32179 16298 32179 16298 32180 16273 32180 16274 32180 16298 32181 16274 32181 16285 32181 16285 32182 16274 32182 16271 32182 16285 32183 16271 32183 16299 32183 16299 32184 16271 32184 16287 32184 16299 32185 16287 32185 16286 32185 16286 32186 16287 32186 16288 32186 16286 32187 16288 32187 16289 32187 16289 32188 16288 32188 16266 32188 16289 32189 16266 32189 16290 32189 16290 32190 16266 32190 16291 32190 16290 32191 16291 32191 16292 32191 16292 32192 16291 32192 16264 32192 16292 32193 16264 32193 20037 32193 20037 32194 16264 32194 16293 32194 16276 32195 16294 32195 16297 32195 16297 32196 16294 32196 16278 32196 16297 32197 16278 32197 16295 32197 16295 32198 16278 32198 20028 32198 16295 32199 20028 32199 20029 32199 16301 32200 16302 32200 16296 32200 16296 32201 16302 32201 16303 32201 16296 32202 16303 32202 16284 32202 16284 32203 16303 32203 20036 32203 16284 32204 20036 32204 16282 32204 20046 32205 20047 32205 16295 32205 16295 32206 20047 32206 16298 32206 16295 32207 16298 32207 16297 32207 16297 32208 16298 32208 16285 32208 16297 32209 16285 32209 16300 32209 16300 32210 16285 32210 16299 32210 16300 32211 16299 32211 16279 32211 16279 32212 16299 32212 16286 32212 16279 32213 16286 32213 16301 32213 16301 32214 16286 32214 16289 32214 16301 32215 16289 32215 16302 32215 16302 32216 16289 32216 16290 32216 16302 32217 16290 32217 16303 32217 16303 32218 16290 32218 16292 32218 16303 32219 16292 32219 20036 32219 20036 32220 16292 32220 20037 32220 16316 32221 20003 32221 16317 32221 20003 32222 19996 32222 16312 32222 19996 32223 19990 32223 19512 32223 19996 32224 19512 32224 16312 32224 16312 32225 19512 32225 19513 32225 16312 32226 19513 32226 16313 32226 19513 32227 16304 32227 16313 32227 16313 32228 16304 32228 19514 32228 16313 32229 19514 32229 16305 32229 16305 32230 19514 32230 16306 32230 16305 32231 16306 32231 16307 32231 16306 32232 16308 32232 16307 32232 16307 32233 16308 32233 19793 32233 16307 32234 19793 32234 16309 32234 19793 32235 19795 32235 16309 32235 16309 32236 19795 32236 19796 32236 16309 32237 19796 32237 16310 32237 16310 32238 19796 32238 19797 32238 19797 32239 19798 32239 16310 32239 16310 32240 19798 32240 16311 32240 16310 32241 16311 32241 19981 32241 20003 32242 16312 32242 16317 32242 16317 32243 16312 32243 16313 32243 16317 32244 16313 32244 16318 32244 16318 32245 16313 32245 16305 32245 16318 32246 16305 32246 16314 32246 16314 32247 16305 32247 16307 32247 16314 32248 16307 32248 16320 32248 16320 32249 16307 32249 16309 32249 16320 32250 16309 32250 16322 32250 16322 32251 16309 32251 16310 32251 16322 32252 16310 32252 16315 32252 16315 32253 16310 32253 19981 32253 16315 32254 19981 32254 16324 32254 16316 32255 16317 32255 17832 32255 17832 32256 16317 32256 16318 32256 17832 32257 16318 32257 16319 32257 16319 32258 16318 32258 16314 32258 16319 32259 16314 32259 17817 32259 17817 32260 16314 32260 16320 32260 17817 32261 16320 32261 17841 32261 17841 32262 16320 32262 16322 32262 17841 32263 16322 32263 16321 32263 16321 32264 16322 32264 16315 32264 16321 32265 16315 32265 16323 32265 16323 32266 16315 32266 16324 32266 16323 32267 16324 32267 17846 32267 19845 32268 16359 32268 16325 32268 16326 32269 19008 32269 16345 32269 16360 32270 19844 32270 16372 32270 16327 32271 16328 32271 16370 32271 16329 32272 19009 32272 16371 32272 16330 32273 16331 32273 16344 32273 16355 32274 19379 32274 16357 32274 16332 32275 16334 32275 19381 32275 19381 32276 16334 32276 16333 32276 19381 32277 16333 32277 19380 32277 16334 32278 16362 32278 16333 32278 16333 32279 16362 32279 16335 32279 16333 32280 16335 32280 16374 32280 16374 32281 16336 32281 16337 32281 16337 32282 16336 32282 16376 32282 16337 32283 16376 32283 16338 32283 16338 32284 16376 32284 16378 32284 16338 32285 16378 32285 16339 32285 16339 32286 16378 32286 16383 32286 16339 32287 16383 32287 16386 32287 16375 32288 16373 32288 16340 32288 16340 32289 16373 32289 16341 32289 16340 32290 16341 32290 16343 32290 16343 32291 16341 32291 16342 32291 16343 32292 16342 32292 16344 32292 16344 32293 16342 32293 16345 32293 16344 32294 16345 32294 16330 32294 16330 32295 16345 32295 19008 32295 16377 32296 16347 32296 16346 32296 16346 32297 16347 32297 16348 32297 16346 32298 16348 32298 16369 32298 16369 32299 16348 32299 16350 32299 16369 32300 16350 32300 16371 32300 16371 32301 16350 32301 16351 32301 16371 32302 16351 32302 16329 32302 16329 32303 16351 32303 16349 32303 16347 32304 16375 32304 16348 32304 16348 32305 16375 32305 16340 32305 16348 32306 16340 32306 16350 32306 16350 32307 16340 32307 16343 32307 16350 32308 16343 32308 16351 32308 16351 32309 16343 32309 16344 32309 16351 32310 16344 32310 16349 32310 16349 32311 16344 32311 16331 32311 19842 32312 16380 32312 16352 32312 16352 32313 16380 32313 16353 32313 16352 32314 16353 32314 19849 32314 16358 32315 19843 32315 16354 32315 16332 32316 16355 32316 16364 32316 16364 32317 16355 32317 16357 32317 16364 32318 16357 32318 16356 32318 16356 32319 16357 32319 16380 32319 16356 32320 16380 32320 16358 32320 16358 32321 16380 32321 19842 32321 16358 32322 19842 32322 19843 32322 19845 32323 16360 32323 16359 32323 16359 32324 16360 32324 16372 32324 16359 32325 16372 32325 16325 32325 16325 32326 16372 32326 16361 32326 16325 32327 16361 32327 16362 32327 16362 32328 16361 32328 16363 32328 16362 32329 16363 32329 16335 32329 16332 32330 16364 32330 16334 32330 16334 32331 16364 32331 16356 32331 16334 32332 16356 32332 16362 32332 16362 32333 16356 32333 16358 32333 16362 32334 16358 32334 16325 32334 16325 32335 16358 32335 16354 32335 16325 32336 16354 32336 19845 32336 16386 32337 16387 32337 16339 32337 16339 32338 16387 32338 16365 32338 16339 32339 16365 32339 16338 32339 16338 32340 16365 32340 16366 32340 16338 32341 16366 32341 16337 32341 16366 32342 19452 32342 16337 32342 16337 32343 19452 32343 16367 32343 16337 32344 16367 32344 16374 32344 16374 32345 16367 32345 19382 32345 16374 32346 19382 32346 16333 32346 16333 32347 19382 32347 16368 32347 16333 32348 16368 32348 19380 32348 16379 32349 16377 32349 16432 32349 16432 32350 16377 32350 16346 32350 16432 32351 16346 32351 16411 32351 16411 32352 16346 32352 16369 32352 16411 32353 16369 32353 16370 32353 16370 32354 16369 32354 16371 32354 16370 32355 16371 32355 16327 32355 16327 32356 16371 32356 19009 32356 19844 32357 16326 32357 16372 32357 16372 32358 16326 32358 16345 32358 16372 32359 16345 32359 16361 32359 16361 32360 16345 32360 16342 32360 16361 32361 16342 32361 16363 32361 16363 32362 16342 32362 16341 32362 16363 32363 16341 32363 16335 32363 16335 32364 16341 32364 16373 32364 16335 32365 16373 32365 16374 32365 16374 32366 16373 32366 16375 32366 16374 32367 16375 32367 16336 32367 16336 32368 16375 32368 16347 32368 16336 32369 16347 32369 16376 32369 16376 32370 16347 32370 16377 32370 16376 32371 16377 32371 16378 32371 16378 32372 16377 32372 16379 32372 16378 32373 16379 32373 16383 32373 16395 32374 16380 32374 16357 32374 16380 32375 16395 32375 16353 32375 16392 32376 16390 32376 16428 32376 16428 32377 16390 32377 16381 32377 16428 32378 16381 32378 16429 32378 16429 32379 16381 32379 16382 32379 16429 32380 16382 32380 16431 32380 16431 32381 16382 32381 16383 32381 16431 32382 16383 32382 16379 32382 16390 32383 16389 32383 16381 32383 16381 32384 16389 32384 16384 32384 16381 32385 16384 32385 16382 32385 16382 32386 16384 32386 16386 32386 16382 32387 16386 32387 16383 32387 16385 32388 19372 32388 16389 32388 16389 32389 19372 32389 19360 32389 16389 32390 19360 32390 16384 32390 16384 32391 19360 32391 19358 32391 16384 32392 19358 32392 16386 32392 16386 32393 19358 32393 16387 32393 16424 32394 16422 32394 16423 32394 16385 32395 16389 32395 16388 32395 16388 32396 16389 32396 16390 32396 16388 32397 16390 32397 16391 32397 16391 32398 16390 32398 16392 32398 16391 32399 16392 32399 16393 32399 16393 32400 16392 32400 16426 32400 16393 32401 16426 32401 16425 32401 19849 32402 16353 32402 19851 32402 19851 32403 16353 32403 16395 32403 19851 32404 16395 32404 16394 32404 16394 32405 16395 32405 16421 32405 16370 32406 16328 32406 19015 32406 19012 32407 16399 32407 19013 32407 19013 32408 16399 32408 16398 32408 19013 32409 16398 32409 16396 32409 16396 32410 16398 32410 16397 32410 19015 32411 16397 32411 16370 32411 16370 32412 16397 32412 16398 32412 16370 32413 16398 32413 16411 32413 19012 32414 19016 32414 16399 32414 16399 32415 19016 32415 19017 32415 16399 32416 19017 32416 16401 32416 19017 32417 16400 32417 16401 32417 16401 32418 16400 32418 16402 32418 16401 32419 16402 32419 16412 32419 16412 32420 16402 32420 19847 32420 16412 32421 19847 32421 16413 32421 16413 32422 19847 32422 16403 32422 16413 32423 16403 32423 16415 32423 16422 32424 16424 32424 16416 32424 16416 32425 16424 32425 16404 32425 16416 32426 16404 32426 16414 32426 16414 32427 16404 32427 16427 32427 16414 32428 16427 32428 16405 32428 16405 32429 16427 32429 16407 32429 16405 32430 16407 32430 16406 32430 16406 32431 16407 32431 16430 32431 16406 32432 16430 32432 16408 32432 16408 32433 16430 32433 16409 32433 16408 32434 16409 32434 16410 32434 16410 32435 16409 32435 16432 32435 16410 32436 16432 32436 16411 32436 16411 32437 16398 32437 16410 32437 16410 32438 16398 32438 16399 32438 16410 32439 16399 32439 16408 32439 16408 32440 16399 32440 16401 32440 16408 32441 16401 32441 16406 32441 16406 32442 16401 32442 16412 32442 16406 32443 16412 32443 16405 32443 16405 32444 16412 32444 16413 32444 16405 32445 16413 32445 16414 32445 16414 32446 16413 32446 16415 32446 16414 32447 16415 32447 16416 32447 16357 32448 19379 32448 19354 32448 19352 32449 19353 32449 16425 32449 16425 32450 19353 32450 16417 32450 16425 32451 16417 32451 16393 32451 16393 32452 16417 32452 19351 32452 16393 32453 19351 32453 16391 32453 16391 32454 19351 32454 16418 32454 16391 32455 16418 32455 16388 32455 16388 32456 16418 32456 16419 32456 16388 32457 16419 32457 16385 32457 16403 32458 16420 32458 16415 32458 16415 32459 16420 32459 16421 32459 16415 32460 16421 32460 16416 32460 16416 32461 16421 32461 16395 32461 16416 32462 16395 32462 16422 32462 16422 32463 16395 32463 16357 32463 16422 32464 16357 32464 16423 32464 16423 32465 16357 32465 19354 32465 19354 32466 19352 32466 16423 32466 16423 32467 19352 32467 16425 32467 16423 32468 16425 32468 16424 32468 16424 32469 16425 32469 16426 32469 16424 32470 16426 32470 16404 32470 16404 32471 16426 32471 16392 32471 16404 32472 16392 32472 16427 32472 16427 32473 16392 32473 16428 32473 16427 32474 16428 32474 16407 32474 16407 32475 16428 32475 16429 32475 16407 32476 16429 32476 16430 32476 16430 32477 16429 32477 16431 32477 16430 32478 16431 32478 16409 32478 16409 32479 16431 32479 16379 32479 16409 32480 16379 32480 16432 32480 16433 32481 19750 32481 16470 32481 16434 32482 19498 32482 16440 32482 16458 32483 19494 32483 16443 32483 17736 32484 17735 32484 16438 32484 16438 32485 17735 32485 16433 32485 16433 32486 16470 32486 16438 32486 16438 32487 16470 32487 16435 32487 16438 32488 16435 32488 16468 32488 16484 32489 16483 32489 16438 32489 16438 32490 16483 32490 16482 32490 16438 32491 16482 32491 17736 32491 16442 32492 16441 32492 16436 32492 16468 32493 16437 32493 16438 32493 16438 32494 16437 32494 16439 32494 16438 32495 16439 32495 16484 32495 16484 32496 16439 32496 16436 32496 16484 32497 16436 32497 16440 32497 16440 32498 16436 32498 16441 32498 16440 32499 16441 32499 16434 32499 16434 32500 16441 32500 16442 32500 16434 32501 16442 32501 19493 32501 16439 32502 16437 32502 16475 32502 16439 32503 16475 32503 16436 32503 16436 32504 16475 32504 16458 32504 16436 32505 16458 32505 16442 32505 16442 32506 16458 32506 16443 32506 16442 32507 16443 32507 19493 32507 16467 32508 16437 32508 16468 32508 16473 32509 16474 32509 16444 32509 19749 32510 16445 32510 16469 32510 16469 32511 16445 32511 16446 32511 16469 32512 16446 32512 16444 32512 16444 32513 16446 32513 16447 32513 16444 32514 16447 32514 16473 32514 16473 32515 16447 32515 16477 32515 19490 32516 16448 32516 16479 32516 16479 32517 16448 32517 16449 32517 16479 32518 16449 32518 16452 32518 16477 32519 16450 32519 16472 32519 16450 32520 16452 32520 16451 32520 16451 32521 16452 32521 16449 32521 16451 32522 16449 32522 16455 32522 16455 32523 16449 32523 16453 32523 16455 32524 16453 32524 16454 32524 16454 32525 16453 32525 19495 32525 16454 32526 19495 32526 16458 32526 16458 32527 19495 32527 19494 32527 16450 32528 16451 32528 16472 32528 16472 32529 16451 32529 16455 32529 16472 32530 16455 32530 16456 32530 16456 32531 16455 32531 16454 32531 16456 32532 16454 32532 16457 32532 16457 32533 16454 32533 16458 32533 16457 32534 16458 32534 16475 32534 16492 32535 16459 32535 16460 32535 16460 32536 16459 32536 16480 32536 16460 32537 16480 32537 16490 32537 16490 32538 16480 32538 16462 32538 16490 32539 16462 32539 16461 32539 16461 32540 16462 32540 16478 32540 16461 32541 16478 32541 16463 32541 16463 32542 16478 32542 16464 32542 16463 32543 16464 32543 16488 32543 16488 32544 16464 32544 16465 32544 16488 32545 16465 32545 16486 32545 16486 32546 16465 32546 16466 32546 16486 32547 16466 32547 19747 32547 16474 32548 16467 32548 16444 32548 16444 32549 16467 32549 16468 32549 16444 32550 16468 32550 16469 32550 16469 32551 16468 32551 16435 32551 16469 32552 16435 32552 19749 32552 19749 32553 16435 32553 16470 32553 19749 32554 16470 32554 19750 32554 16476 32555 16471 32555 16466 32555 16466 32556 16471 32556 19748 32556 16466 32557 19748 32557 19747 32557 16477 32558 16472 32558 16473 32558 16473 32559 16472 32559 16456 32559 16473 32560 16456 32560 16474 32560 16474 32561 16456 32561 16457 32561 16474 32562 16457 32562 16467 32562 16467 32563 16457 32563 16475 32563 16467 32564 16475 32564 16437 32564 16445 32565 16476 32565 16446 32565 16446 32566 16476 32566 16466 32566 16446 32567 16466 32567 16447 32567 16447 32568 16466 32568 16465 32568 16447 32569 16465 32569 16477 32569 16477 32570 16465 32570 16464 32570 16477 32571 16464 32571 16450 32571 16450 32572 16464 32572 16478 32572 16450 32573 16478 32573 16452 32573 16452 32574 16478 32574 16462 32574 16452 32575 16462 32575 16479 32575 16479 32576 16462 32576 16480 32576 16479 32577 16480 32577 19490 32577 19490 32578 16480 32578 16459 32578 19499 32579 16481 32579 16493 32579 17765 32580 16482 32580 16483 32580 17765 32581 16483 32581 17734 32581 19498 32582 19499 32582 16440 32582 16440 32583 19499 32583 16493 32583 16440 32584 16493 32584 16484 32584 16484 32585 16493 32585 16496 32585 16484 32586 16496 32586 16483 32586 16483 32587 16496 32587 16485 32587 16483 32588 16485 32588 17734 32588 16491 32589 18851 32589 18853 32589 19747 32590 19746 32590 16486 32590 16486 32591 19746 32591 16487 32591 16486 32592 16487 32592 16488 32592 16488 32593 16487 32593 16489 32593 16488 32594 16489 32594 16463 32594 16463 32595 16489 32595 16500 32595 16463 32596 16500 32596 16461 32596 16461 32597 16500 32597 16498 32597 16461 32598 16498 32598 16490 32598 16490 32599 16498 32599 16491 32599 16490 32600 16491 32600 16460 32600 16460 32601 16491 32601 18853 32601 16460 32602 18853 32602 16492 32602 16481 32603 19501 32603 16493 32603 16493 32604 19501 32604 16494 32604 16493 32605 16494 32605 16496 32605 16496 32606 16494 32606 16495 32606 16496 32607 16495 32607 16485 32607 16485 32608 16495 32608 16507 32608 16485 32609 16507 32609 17734 32609 17734 32610 16507 32610 17839 32610 18850 32611 18851 32611 16491 32611 16497 32612 18850 32612 16529 32612 16529 32613 18850 32613 16491 32613 16529 32614 16491 32614 16547 32614 16547 32615 16491 32615 16498 32615 16547 32616 16498 32616 16499 32616 16499 32617 16498 32617 16500 32617 16499 32618 16500 32618 16501 32618 16501 32619 16500 32619 16489 32619 16501 32620 16489 32620 16545 32620 16545 32621 16489 32621 16487 32621 16545 32622 16487 32622 19520 32622 19520 32623 16487 32623 19746 32623 16502 32624 16503 32624 16521 32624 16504 32625 16505 32625 16515 32625 16515 32626 16505 32626 16559 32626 16504 32627 16515 32627 19504 32627 19504 32628 16515 32628 16517 32628 19504 32629 16517 32629 19505 32629 19505 32630 16517 32630 16506 32630 19505 32631 16506 32631 19506 32631 19506 32632 16506 32632 16519 32632 19506 32633 16519 32633 19502 32633 19502 32634 16519 32634 19503 32634 19503 32635 16519 32635 16494 32635 19503 32636 16494 32636 19501 32636 16508 32637 17839 32637 16507 32637 16507 32638 16522 32638 16508 32638 16508 32639 16522 32639 16510 32639 16508 32640 16510 32640 16509 32640 16509 32641 16510 32641 16520 32641 16509 32642 16520 32642 16511 32642 16511 32643 16520 32643 16514 32643 16511 32644 16514 32644 16513 32644 17845 32645 16513 32645 16512 32645 16512 32646 16513 32646 16514 32646 16512 32647 16514 32647 16560 32647 16560 32648 16514 32648 16503 32648 16502 32649 16521 32649 16559 32649 16559 32650 16521 32650 16515 32650 16515 32651 16521 32651 16516 32651 16515 32652 16516 32652 16517 32652 16517 32653 16516 32653 16518 32653 16517 32654 16518 32654 16506 32654 16506 32655 16518 32655 16523 32655 16506 32656 16523 32656 16519 32656 16519 32657 16523 32657 16495 32657 16519 32658 16495 32658 16494 32658 16503 32659 16514 32659 16521 32659 16521 32660 16514 32660 16520 32660 16521 32661 16520 32661 16516 32661 16516 32662 16520 32662 16510 32662 16516 32663 16510 32663 16518 32663 16518 32664 16510 32664 16522 32664 16518 32665 16522 32665 16523 32665 16523 32666 16522 32666 16507 32666 16523 32667 16507 32667 16495 32667 19621 32668 16524 32668 16530 32668 16525 32669 16529 32669 16547 32669 19659 32670 16526 32670 16552 32670 16548 32671 16527 32671 16549 32671 16549 32672 16527 32672 19484 32672 16497 32673 16529 32673 16528 32673 16528 32674 16529 32674 16525 32674 16528 32675 16525 32675 19483 32675 16524 32676 16550 32676 16530 32676 16530 32677 16550 32677 16551 32677 16530 32678 16551 32678 16531 32678 16531 32679 16551 32679 16532 32679 16531 32680 16532 32680 16546 32680 16546 32681 16532 32681 16553 32681 16546 32682 16553 32682 16548 32682 16548 32683 16553 32683 16533 32683 16548 32684 16533 32684 16527 32684 16527 32685 16533 32685 16534 32685 16527 32686 16534 32686 19484 32686 19484 32687 16534 32687 16556 32687 19484 32688 16556 32688 16535 32688 16535 32689 16556 32689 19486 32689 16542 32690 16536 32690 16557 32690 16557 32691 16536 32691 16537 32691 16557 32692 16537 32692 16558 32692 16558 32693 16537 32693 16538 32693 16558 32694 16538 32694 19487 32694 16552 32695 16526 32695 16539 32695 16539 32696 16526 32696 16562 32696 16539 32697 16562 32697 16554 32697 16554 32698 16562 32698 16540 32698 16554 32699 16540 32699 16555 32699 16555 32700 16540 32700 16541 32700 16555 32701 16541 32701 16542 32701 16542 32702 16541 32702 16563 32702 16542 32703 16563 32703 16536 32703 19620 32704 16543 32704 16552 32704 16552 32705 16543 32705 16544 32705 16552 32706 16544 32706 19659 32706 19520 32707 19621 32707 16545 32707 16545 32708 19621 32708 16530 32708 16545 32709 16530 32709 16501 32709 16501 32710 16530 32710 16531 32710 16501 32711 16531 32711 16499 32711 16499 32712 16531 32712 16546 32712 16499 32713 16546 32713 16547 32713 16547 32714 16546 32714 16548 32714 16547 32715 16548 32715 16525 32715 16525 32716 16548 32716 16549 32716 16525 32717 16549 32717 19483 32717 19483 32718 16549 32718 19484 32718 16550 32719 19620 32719 16551 32719 16551 32720 19620 32720 16552 32720 16551 32721 16552 32721 16532 32721 16532 32722 16552 32722 16539 32722 16532 32723 16539 32723 16553 32723 16553 32724 16539 32724 16554 32724 16553 32725 16554 32725 16533 32725 16533 32726 16554 32726 16555 32726 16533 32727 16555 32727 16534 32727 16534 32728 16555 32728 16542 32728 16534 32729 16542 32729 16556 32729 16556 32730 16542 32730 16557 32730 16556 32731 16557 32731 19486 32731 19486 32732 16557 32732 16558 32732 16505 32733 19471 32733 16559 32733 16559 32734 19471 32734 16580 32734 16559 32735 16580 32735 16502 32735 16502 32736 16580 32736 16592 32736 16502 32737 16592 32737 16503 32737 16503 32738 16592 32738 16582 32738 16503 32739 16582 32739 16560 32739 16560 32740 16582 32740 16596 32740 16560 32741 16596 32741 16512 32741 16512 32742 16596 32742 16583 32742 16512 32743 16583 32743 17845 32743 17845 32744 16583 32744 17847 32744 16541 32745 16540 32745 16570 32745 16569 32746 17798 32746 16598 32746 16526 32747 19659 32747 16561 32747 16561 32748 19659 32748 17800 32748 16561 32749 17800 32749 16568 32749 16570 32750 16540 32750 16561 32750 16561 32751 16540 32751 16562 32751 16561 32752 16562 32752 16526 32752 16541 32753 16570 32753 16563 32753 16563 32754 16570 32754 16572 32754 16563 32755 16572 32755 16564 32755 19487 32756 16538 32756 19479 32756 19479 32757 16538 32757 16537 32757 19479 32758 16537 32758 16564 32758 16564 32759 16537 32759 16536 32759 16564 32760 16536 32760 16563 32760 19482 32761 16566 32761 16565 32761 16565 32762 16566 32762 19480 32762 19478 32763 19482 32763 16567 32763 16567 32764 19482 32764 16565 32764 16567 32765 16565 32765 16571 32765 16568 32766 16569 32766 16561 32766 16561 32767 16569 32767 16598 32767 16561 32768 16598 32768 16570 32768 16570 32769 16598 32769 16571 32769 16570 32770 16571 32770 16572 32770 16572 32771 16571 32771 16565 32771 16572 32772 16565 32772 16564 32772 16564 32773 16565 32773 19480 32773 16564 32774 19480 32774 19479 32774 16574 32775 19472 32775 16573 32775 16574 32776 16573 32776 16575 32776 16573 32777 16589 32777 16575 32777 16575 32778 16589 32778 16590 32778 16575 32779 16590 32779 16576 32779 16576 32780 16590 32780 16577 32780 16576 32781 16577 32781 19476 32781 19476 32782 16577 32782 19474 32782 19474 32783 16577 32783 16579 32783 19474 32784 16579 32784 16578 32784 16578 32785 16579 32785 16580 32785 16578 32786 16580 32786 19471 32786 16581 32787 16582 32787 16592 32787 17847 32788 16583 32788 16595 32788 16595 32789 16583 32789 16596 32789 17847 32790 16595 32790 17849 32790 17849 32791 16595 32791 16584 32791 17849 32792 16584 32792 17835 32792 17835 32793 16584 32793 16585 32793 17835 32794 16585 32794 16586 32794 16586 32795 16585 32795 16588 32795 16586 32796 16588 32796 16587 32796 16601 32797 16587 32797 16604 32797 16604 32798 16587 32798 16588 32798 16604 32799 16588 32799 16602 32799 16573 32800 16602 32800 16593 32800 16573 32801 16593 32801 16589 32801 16589 32802 16593 32802 16591 32802 16589 32803 16591 32803 16590 32803 16590 32804 16591 32804 16594 32804 16590 32805 16594 32805 16577 32805 16577 32806 16594 32806 16581 32806 16577 32807 16581 32807 16579 32807 16579 32808 16581 32808 16592 32808 16579 32809 16592 32809 16580 32809 16602 32810 16588 32810 16593 32810 16593 32811 16588 32811 16585 32811 16593 32812 16585 32812 16591 32812 16591 32813 16585 32813 16584 32813 16591 32814 16584 32814 16594 32814 16594 32815 16584 32815 16595 32815 16594 32816 16595 32816 16581 32816 16581 32817 16595 32817 16596 32817 16581 32818 16596 32818 16582 32818 17778 32819 17777 32819 16597 32819 16599 32820 16567 32820 16603 32820 16603 32821 16567 32821 16571 32821 16603 32822 16571 32822 16597 32822 16597 32823 16571 32823 16598 32823 16597 32824 16598 32824 17778 32824 17778 32825 16598 32825 17798 32825 16599 32826 16600 32826 16567 32826 16567 32827 16600 32827 19477 32827 16567 32828 19477 32828 19478 32828 16605 32829 16601 32829 16604 32829 19472 32830 16600 32830 16573 32830 16573 32831 16600 32831 16599 32831 16573 32832 16599 32832 16602 32832 16602 32833 16599 32833 16603 32833 16602 32834 16603 32834 16604 32834 16604 32835 16603 32835 16597 32835 16604 32836 16597 32836 16605 32836 16605 32837 16597 32837 17777 32837 16607 32838 17855 32838 19699 32838 19699 32839 17855 32839 16606 32839 16612 32840 16611 32840 16610 32840 16607 32841 16608 32841 17855 32841 17855 32842 16608 32842 16609 32842 16610 32843 16611 32843 16608 32843 16608 32844 16611 32844 17851 32844 16608 32845 17851 32845 16609 32845 16612 32846 16610 32846 17853 32846 17853 32847 16610 32847 16613 32847 17853 32848 16613 32848 17850 32848 17850 32849 16613 32849 16614 32849 16614 32850 16613 32850 19711 32850 16614 32851 19711 32851 16622 32851 19707 32852 19706 32852 16615 32852 16615 32853 19706 32853 16616 32853 16616 32854 19706 32854 16617 32854 16617 32855 19706 32855 19698 32855 16617 32856 19698 32856 17857 32856 17857 32857 19698 32857 19701 32857 17857 32858 19701 32858 16618 32858 16618 32859 19701 32859 19702 32859 16618 32860 19702 32860 16619 32860 16619 32861 19702 32861 19699 32861 16619 32862 19699 32862 16606 32862 18532 32863 16630 32863 16620 32863 16620 32864 16630 32864 19712 32864 16620 32865 19712 32865 18533 32865 16622 32866 19711 32866 16621 32866 16622 32867 16621 32867 16623 32867 16623 32868 16621 32868 16624 32868 16623 32869 16624 32869 16625 32869 16625 32870 16624 32870 16626 32870 16625 32871 16626 32871 16627 32871 16627 32872 16626 32872 16628 32872 16627 32873 16628 32873 18532 32873 18532 32874 16628 32874 16629 32874 18532 32875 16629 32875 16630 32875 16638 32876 16631 32876 19709 32876 19707 32877 16615 32877 19709 32877 19709 32878 16615 32878 16632 32878 19709 32879 16632 32879 16638 32879 18531 32880 19409 32880 16633 32880 18531 32881 16633 32881 16640 32881 16640 32882 16633 32882 19408 32882 16640 32883 19408 32883 16641 32883 19409 32884 18531 32884 16634 32884 16634 32885 18531 32885 16635 32885 16634 32886 16635 32886 19407 32886 19407 32887 16635 32887 16636 32887 19407 32888 16636 32888 16637 32888 16637 32889 16636 32889 18529 32889 16637 32890 18529 32890 19406 32890 19406 32891 18529 32891 18533 32891 19406 32892 18533 32892 19712 32892 16631 32893 16638 32893 18141 32893 18141 32894 16638 32894 18538 32894 18141 32895 18538 32895 18143 32895 18143 32896 18538 32896 16647 32896 18139 32897 18140 32897 19415 32897 19415 32898 18140 32898 16639 32898 19415 32899 16639 32899 19416 32899 19416 32900 16639 32900 16640 32900 19416 32901 16640 32901 16641 32901 19415 32902 19414 32902 18139 32902 18139 32903 19414 32903 19413 32903 18139 32904 19413 32904 18138 32904 18138 32905 19413 32905 18136 32905 18136 32906 19413 32906 16654 32906 18136 32907 16654 32907 16656 32907 18225 32908 18143 32908 16647 32908 18535 32909 16657 32909 18218 32909 18535 32910 18218 32910 16642 32910 18218 32911 18221 32911 16642 32911 16642 32912 18221 32912 18223 32912 16642 32913 18223 32913 18539 32913 18539 32914 18223 32914 16644 32914 18539 32915 16644 32915 16643 32915 16643 32916 16644 32916 16645 32916 16643 32917 16645 32917 16646 32917 16646 32918 16645 32918 18227 32918 18225 32919 16647 32919 16648 32919 16647 32920 16649 32920 16648 32920 16648 32921 16649 32921 16650 32921 16648 32922 16650 32922 16651 32922 16651 32923 16650 32923 18537 32923 16651 32924 18537 32924 18229 32924 18229 32925 18537 32925 18536 32925 18229 32926 18536 32926 18227 32926 18227 32927 18536 32927 16652 32927 18227 32928 16652 32928 16646 32928 16653 32929 16655 32929 16654 32929 16654 32930 16655 32930 16656 32930 16657 32931 18535 32931 16658 32931 16658 32932 18535 32932 16659 32932 16658 32933 16659 32933 19377 32933 19377 32934 16659 32934 16660 32934 16655 32935 16653 32935 16661 32935 16655 32936 16661 32936 16663 32936 16663 32937 16661 32937 16662 32937 16663 32938 16662 32938 18134 32938 18134 32939 16662 32939 16664 32939 16664 32940 16662 32940 19417 32940 16664 32941 19417 32941 18133 32941 18133 32942 19417 32942 19418 32942 18133 32943 19418 32943 16665 32943 16665 32944 19418 32944 19419 32944 16665 32945 19419 32945 16666 32945 16666 32946 19419 32946 18534 32946 18534 32947 19419 32947 19377 32947 18534 32948 19377 32948 16660 32948 19705 32949 19704 32949 16677 32949 16677 32950 19704 32950 16667 32950 19704 32951 19703 32951 16667 32951 16667 32952 19703 32952 16671 32952 16672 32953 16668 32953 16669 32953 16669 32954 16668 32954 17860 32954 16669 32955 17860 32955 19703 32955 19703 32956 17860 32956 16670 32956 19703 32957 16670 32957 16671 32957 16672 32958 16669 32958 16673 32958 16673 32959 16669 32959 19697 32959 16673 32960 19697 32960 17862 32960 17862 32961 19697 32961 19708 32961 17862 32962 19708 32962 16674 32962 17868 32963 16675 32963 17867 32963 17867 32964 16675 32964 16676 32964 17867 32965 16676 32965 17866 32965 17866 32966 16676 32966 17865 32966 17865 32967 16676 32967 19694 32967 17865 32968 19694 32968 17864 32968 17864 32969 19694 32969 19688 32969 17864 32970 19688 32970 17863 32970 17863 32971 19688 32971 19705 32971 17863 32972 19705 32972 16677 32972 16678 32973 16680 32973 16679 32973 16679 32974 16680 32974 18558 32974 16679 32975 18558 32975 19708 32975 19708 32976 18558 32976 16674 32976 16675 32977 17868 32977 16681 32977 16681 32978 17868 32978 16682 32978 16681 32979 16682 32979 19693 32979 19693 32980 16682 32980 18550 32980 18142 32981 16698 32981 16683 32981 16683 32982 16698 32982 18556 32982 16683 32983 18556 32983 16678 32983 16678 32984 18556 32984 16680 32984 18549 32985 16684 32985 18550 32985 18550 32986 16684 32986 18144 32986 18550 32987 18144 32987 19693 32987 16685 32988 16695 32988 18219 32988 18219 32989 16695 32989 18220 32989 18219 32990 18217 32990 16685 32990 16685 32991 18217 32991 16686 32991 16685 32992 16686 32992 18560 32992 18560 32993 16686 32993 16687 32993 18560 32994 16687 32994 18216 32994 16688 32995 18226 32995 16689 32995 16688 32996 16689 32996 16690 32996 16690 32997 16689 32997 18224 32997 16690 32998 18224 32998 16691 32998 16691 32999 18224 32999 18222 32999 16691 33000 18222 33000 16692 33000 16692 33001 18222 33001 16693 33001 16692 33002 16693 33002 16695 33002 16695 33003 16693 33003 16694 33003 16695 33004 16694 33004 18220 33004 18226 33005 16688 33005 18228 33005 18228 33006 16688 33006 16697 33006 18228 33007 16697 33007 18230 33007 18230 33008 16697 33008 16696 33008 16696 33009 16697 33009 16698 33009 16696 33010 16698 33010 18142 33010 18246 33011 16699 33011 16709 33011 16700 33012 18185 33012 18232 33012 16700 33013 18232 33013 16701 33013 16701 33014 18232 33014 16702 33014 16701 33015 16702 33015 18552 33015 16702 33016 16703 33016 18552 33016 18552 33017 16703 33017 16704 33017 18552 33018 16704 33018 16706 33018 16706 33019 16704 33019 16705 33019 16706 33020 16705 33020 18553 33020 18553 33021 16705 33021 16708 33021 16705 33022 18237 33022 16708 33022 16708 33023 18237 33023 16707 33023 16708 33024 16707 33024 16709 33024 16709 33025 16707 33025 18236 33025 16709 33026 18236 33026 18246 33026 16699 33027 16710 33027 16709 33027 16709 33028 16710 33028 18244 33028 16709 33029 18244 33029 16712 33029 18244 33030 18242 33030 16712 33030 16712 33031 18242 33031 16711 33031 16712 33032 16711 33032 16715 33032 16715 33033 16711 33033 16713 33033 16715 33034 16713 33034 16714 33034 16714 33035 18250 33035 16715 33035 16715 33036 18250 33036 16716 33036 16715 33037 16716 33037 16718 33037 16716 33038 16717 33038 16718 33038 16718 33039 16717 33039 16719 33039 16718 33040 16719 33040 16720 33040 16719 33041 18254 33041 16720 33041 16720 33042 18254 33042 16721 33042 16720 33043 16721 33043 18548 33043 16721 33044 18256 33044 18548 33044 18548 33045 18256 33045 16722 33045 18548 33046 16722 33046 18549 33046 18549 33047 16722 33047 18257 33047 18549 33048 18257 33048 16684 33048 18182 33049 18561 33049 18180 33049 18180 33050 18561 33050 16723 33050 18180 33051 16723 33051 18216 33051 18216 33052 16723 33052 18560 33052 16728 33053 18184 33053 16700 33053 16700 33054 18184 33054 18187 33054 16700 33055 18187 33055 18185 33055 16724 33056 16725 33056 19420 33056 19420 33057 16725 33057 16726 33057 19420 33058 16726 33058 18182 33058 18182 33059 16726 33059 18561 33059 18184 33060 16728 33060 16727 33060 16727 33061 16728 33061 18119 33061 16727 33062 18119 33062 16740 33062 16724 33063 16731 33063 16725 33063 16725 33064 16731 33064 18130 33064 18126 33065 18125 33065 16729 33065 16729 33066 18125 33066 16730 33066 16729 33067 16730 33067 16731 33067 16731 33068 16730 33068 18131 33068 16731 33069 18131 33069 18130 33069 18126 33070 16729 33070 18128 33070 18128 33071 16729 33071 16732 33071 18128 33072 16732 33072 18124 33072 18124 33073 16732 33073 16733 33073 18124 33074 16733 33074 18554 33074 16743 33075 16742 33075 19426 33075 16743 33076 19426 33076 16734 33076 16734 33077 19426 33077 16736 33077 16734 33078 16736 33078 18122 33078 18122 33079 16736 33079 16735 33079 16735 33080 16736 33080 16737 33080 16735 33081 16737 33081 16738 33081 16738 33082 16737 33082 16739 33082 16738 33083 16739 33083 16741 33083 16741 33084 16739 33084 16740 33084 16741 33085 16740 33085 18119 33085 16733 33086 16742 33086 18554 33086 18554 33087 16742 33087 16743 33087 19691 33088 19690 33088 16758 33088 16758 33089 19690 33089 16744 33089 16744 33090 19690 33090 16745 33090 16745 33091 19690 33091 19689 33091 16745 33092 19689 33092 17873 33092 16746 33093 17872 33093 16747 33093 16746 33094 16747 33094 19689 33094 19689 33095 16747 33095 16748 33095 19689 33096 16748 33096 17873 33096 17872 33097 16746 33097 16749 33097 16749 33098 16746 33098 19695 33098 16749 33099 19695 33099 17870 33099 17870 33100 19695 33100 16750 33100 17870 33101 16750 33101 16759 33101 18577 33102 16751 33102 16753 33102 16753 33103 16751 33103 16752 33103 16753 33104 16752 33104 17877 33104 17877 33105 16752 33105 17876 33105 17876 33106 16752 33106 19687 33106 17876 33107 19687 33107 16754 33107 16754 33108 19687 33108 16755 33108 16755 33109 19687 33109 16756 33109 16755 33110 16756 33110 16757 33110 16757 33111 16756 33111 19691 33111 16757 33112 19691 33112 16758 33112 19692 33113 18586 33113 19696 33113 19696 33114 18586 33114 18585 33114 19696 33115 18585 33115 16750 33115 16750 33116 18585 33116 16759 33116 16751 33117 18577 33117 19684 33117 19684 33118 18577 33118 18576 33118 19684 33119 18576 33119 18149 33119 18149 33120 18576 33120 18575 33120 18145 33121 18587 33121 16760 33121 16760 33122 18587 33122 18586 33122 16760 33123 18586 33123 19692 33123 16761 33124 18147 33124 18575 33124 18575 33125 18147 33125 18148 33125 18575 33126 18148 33126 18149 33126 16762 33127 18587 33127 18145 33127 16766 33128 18233 33128 16763 33128 16763 33129 18233 33129 18231 33129 16763 33130 18231 33130 16796 33130 18240 33131 18235 33131 16764 33131 16764 33132 18235 33132 16765 33132 16764 33133 16765 33133 16766 33133 16766 33134 16765 33134 18234 33134 16766 33135 18234 33135 18233 33135 18240 33136 16764 33136 16767 33136 16767 33137 16764 33137 16768 33137 16767 33138 16768 33138 18241 33138 16770 33139 18238 33139 16768 33139 16768 33140 18238 33140 18239 33140 16768 33141 18239 33141 18241 33141 18249 33142 18248 33142 18588 33142 18588 33143 18248 33143 18247 33143 18588 33144 18247 33144 16769 33144 16769 33145 18247 33145 18243 33145 16769 33146 18243 33146 16770 33146 16770 33147 18243 33147 18245 33147 16770 33148 18245 33148 18238 33148 16774 33149 18252 33149 16771 33149 16771 33150 18252 33150 18251 33150 16771 33151 18251 33151 18588 33151 18588 33152 18251 33152 16772 33152 18588 33153 16772 33153 18249 33153 18145 33154 16773 33154 16762 33154 16762 33155 16773 33155 18255 33155 16762 33156 18255 33156 16771 33156 16771 33157 18255 33157 18253 33157 16771 33158 18253 33158 16774 33158 18259 33159 16777 33159 16775 33159 16775 33160 16777 33160 18574 33160 16775 33161 18574 33161 16776 33161 18259 33162 18260 33162 16777 33162 16777 33163 18260 33163 16778 33163 16777 33164 16778 33164 18579 33164 18579 33165 16778 33165 16779 33165 18579 33166 16779 33166 18580 33166 18580 33167 16779 33167 18263 33167 18580 33168 18263 33168 18265 33168 16780 33169 18583 33169 16781 33169 16781 33170 18583 33170 18582 33170 16781 33171 18582 33171 18265 33171 18265 33172 18582 33172 16782 33172 18265 33173 16782 33173 18580 33173 16783 33174 16787 33174 18273 33174 18273 33175 16787 33175 16785 33175 16780 33176 18267 33176 18583 33176 18583 33177 18267 33177 16784 33177 18583 33178 16784 33178 16785 33178 16785 33179 16784 33179 18270 33179 16785 33180 18270 33180 18273 33180 16783 33181 16786 33181 16787 33181 16787 33182 16786 33182 16792 33182 16787 33183 16792 33183 16791 33183 18275 33184 16789 33184 16788 33184 16788 33185 16789 33185 16791 33185 16788 33186 16791 33186 16790 33186 16790 33187 16791 33187 16792 33187 18275 33188 18277 33188 16789 33188 16789 33189 18277 33189 18278 33189 16789 33190 18278 33190 16793 33190 18278 33191 16794 33191 16793 33191 16793 33192 16794 33192 16795 33192 16793 33193 16795 33193 16761 33193 16761 33194 16795 33194 18280 33194 16761 33195 18280 33195 18147 33195 16763 33196 16796 33196 16799 33196 16799 33197 16796 33197 18186 33197 16799 33198 18186 33198 19428 33198 16776 33199 18574 33199 16797 33199 16797 33200 18574 33200 16801 33200 16797 33201 16801 33201 16798 33201 16799 33202 19428 33202 18584 33202 18584 33203 19428 33203 19427 33203 18584 33204 19427 33204 19424 33204 16798 33205 16801 33205 16800 33205 16800 33206 16801 33206 18573 33206 16800 33207 18573 33207 16813 33207 16813 33208 18573 33208 18111 33208 16803 33209 16804 33209 19425 33209 19425 33210 16804 33210 18584 33210 19425 33211 18584 33211 19424 33211 18117 33212 18116 33212 16805 33212 16805 33213 18116 33213 16802 33213 16805 33214 16802 33214 16803 33214 16803 33215 16802 33215 18118 33215 16803 33216 18118 33216 16804 33216 18117 33217 16805 33217 16806 33217 16806 33218 16805 33218 16814 33218 16806 33219 16814 33219 16816 33219 18114 33220 16815 33220 16807 33220 16807 33221 16815 33221 19422 33221 16807 33222 19422 33222 16808 33222 18112 33223 18113 33223 16810 33223 16810 33224 18113 33224 16809 33224 16810 33225 16809 33225 19422 33225 19422 33226 16809 33226 16811 33226 19422 33227 16811 33227 16808 33227 16810 33228 16812 33228 18112 33228 18112 33229 16812 33229 16813 33229 18112 33230 16813 33230 18111 33230 16814 33231 16815 33231 16816 33231 16816 33232 16815 33232 18114 33232 19677 33233 16818 33233 16817 33233 16817 33234 16818 33234 17881 33234 17881 33235 16818 33235 17882 33235 17882 33236 16818 33236 16819 33236 17882 33237 16819 33237 17884 33237 19678 33238 16821 33238 16820 33238 19678 33239 16820 33239 16819 33239 16819 33240 16820 33240 17885 33240 16819 33241 17885 33241 17884 33241 16821 33242 19678 33242 17880 33242 17880 33243 19678 33243 19686 33243 17880 33244 19686 33244 16822 33244 16822 33245 19686 33245 16829 33245 16822 33246 16829 33246 16830 33246 16823 33247 17893 33247 19680 33247 19680 33248 17893 33248 17894 33248 19680 33249 17894 33249 19681 33249 16823 33250 19680 33250 17891 33250 17891 33251 19680 33251 16824 33251 17891 33252 16824 33252 16825 33252 16825 33253 16824 33253 17888 33253 17888 33254 16824 33254 16826 33254 17888 33255 16826 33255 17887 33255 19677 33256 16817 33256 16826 33256 16826 33257 16817 33257 17886 33257 16826 33258 17886 33258 17887 33258 19683 33259 16834 33259 16827 33259 16827 33260 16834 33260 16828 33260 16827 33261 16828 33261 16829 33261 16829 33262 16828 33262 16830 33262 19681 33263 17894 33263 19682 33263 19682 33264 17894 33264 18598 33264 19682 33265 18598 33265 16831 33265 16831 33266 18598 33266 18597 33266 18281 33267 16833 33267 16832 33267 16832 33268 16833 33268 16834 33268 16832 33269 16834 33269 19683 33269 18596 33270 18153 33270 18597 33270 18597 33271 18153 33271 16835 33271 18597 33272 16835 33272 16831 33272 16836 33273 16837 33273 16838 33273 16838 33274 16837 33274 16839 33274 16838 33275 16839 33275 16840 33275 16840 33276 16839 33276 18258 33276 16840 33277 18258 33277 16841 33277 16845 33278 18262 33278 16844 33278 16844 33279 18262 33279 16842 33279 16844 33280 16842 33280 16836 33280 16836 33281 16842 33281 18261 33281 16836 33282 18261 33282 16837 33282 18266 33283 16844 33283 16848 33283 18266 33284 16843 33284 16844 33284 16844 33285 16843 33285 18264 33285 16844 33286 18264 33286 16845 33286 18274 33287 16846 33287 16850 33287 16850 33288 16846 33288 18272 33288 16850 33289 18272 33289 16847 33289 18272 33290 18271 33290 16847 33290 16847 33291 18271 33291 18269 33291 16847 33292 18269 33292 16848 33292 16848 33293 18269 33293 18268 33293 16848 33294 18268 33294 18266 33294 16854 33295 18276 33295 16852 33295 16852 33296 18276 33296 16849 33296 16852 33297 16849 33297 16850 33297 16850 33298 16849 33298 16851 33298 16850 33299 16851 33299 18274 33299 16856 33300 18279 33300 18605 33300 18605 33301 18279 33301 16852 33301 16852 33302 18279 33302 16853 33302 16852 33303 16853 33303 16854 33303 18605 33304 16855 33304 16856 33304 16856 33305 16855 33305 16833 33305 16856 33306 16833 33306 18281 33306 18282 33307 16865 33307 16857 33307 16857 33308 16865 33308 18595 33308 16857 33309 18595 33309 16858 33309 18290 33310 18601 33310 18289 33310 18289 33311 18601 33311 16859 33311 18289 33312 16859 33312 18286 33312 18286 33313 16859 33313 16860 33313 18286 33314 16860 33314 16861 33314 16861 33315 16860 33315 16862 33315 16861 33316 16862 33316 18284 33316 18284 33317 16862 33317 16863 33317 18284 33318 16863 33318 16864 33318 16864 33319 16863 33319 16865 33319 16864 33320 16865 33320 16866 33320 16866 33321 16865 33321 18282 33321 18290 33322 18291 33322 18601 33322 18601 33323 18291 33323 18288 33323 18601 33324 18288 33324 16867 33324 16867 33325 18288 33325 16868 33325 18296 33326 18602 33326 18292 33326 18292 33327 18602 33327 16867 33327 18292 33328 16867 33328 18293 33328 18293 33329 16867 33329 16868 33329 18296 33330 18297 33330 18602 33330 18602 33331 18297 33331 16869 33331 18602 33332 16869 33332 16870 33332 18302 33333 18600 33333 18300 33333 18300 33334 18600 33334 16870 33334 18300 33335 16870 33335 16871 33335 16871 33336 16870 33336 16869 33336 18302 33337 16872 33337 18600 33337 18600 33338 16872 33338 18304 33338 18600 33339 18304 33339 16873 33339 16873 33340 18304 33340 16874 33340 16873 33341 16874 33341 18596 33341 18596 33342 16874 33342 16875 33342 18596 33343 16875 33343 18153 33343 16840 33344 16841 33344 16879 33344 16879 33345 16841 33345 16876 33345 16879 33346 16876 33346 19429 33346 16880 33347 18189 33347 18595 33347 18595 33348 18189 33348 16877 33348 18595 33349 16877 33349 16858 33349 19431 33350 16878 33350 19430 33350 19430 33351 16878 33351 18604 33351 19430 33352 18604 33352 19429 33352 19429 33353 18604 33353 16879 33353 18189 33354 16880 33354 16882 33354 16882 33355 16880 33355 16881 33355 16882 33356 16881 33356 16883 33356 16883 33357 16881 33357 18100 33357 16884 33358 18110 33358 19432 33358 19432 33359 18110 33359 16878 33359 19432 33360 16878 33360 19431 33360 16884 33361 19432 33361 16885 33361 16885 33362 19432 33362 16886 33362 16885 33363 16886 33363 18108 33363 18108 33364 16886 33364 16888 33364 18108 33365 16888 33365 16887 33365 16887 33366 16888 33366 18107 33366 18107 33367 16888 33367 16896 33367 18107 33368 16896 33368 16889 33368 18106 33369 16890 33369 18105 33369 18105 33370 16890 33370 19421 33370 18105 33371 19421 33371 18104 33371 16895 33372 16891 33372 16893 33372 16893 33373 16891 33373 16892 33373 16893 33374 16892 33374 19421 33374 19421 33375 16892 33375 18103 33375 19421 33376 18103 33376 18104 33376 16893 33377 16894 33377 16895 33377 16895 33378 16894 33378 16883 33378 16895 33379 16883 33379 18100 33379 16896 33380 16890 33380 16889 33380 16889 33381 16890 33381 18106 33381 19669 33382 16898 33382 16908 33382 16908 33383 16898 33383 16897 33383 16897 33384 16898 33384 16900 33384 16900 33385 16898 33385 16899 33385 17901 33386 17900 33386 16899 33386 16899 33387 17900 33387 17899 33387 16899 33388 17899 33388 16900 33388 17901 33389 16899 33389 17897 33389 17897 33390 16899 33390 16901 33390 17897 33391 16901 33391 16903 33391 16903 33392 16901 33392 16902 33392 16903 33393 16902 33393 17896 33393 17896 33394 16902 33394 16910 33394 17896 33395 16910 33395 17895 33395 16911 33396 19672 33396 17909 33396 17909 33397 19672 33397 17908 33397 16905 33398 17905 33398 16904 33398 16905 33399 16904 33399 19672 33399 19672 33400 16904 33400 17907 33400 19672 33401 17907 33401 17908 33401 17905 33402 16905 33402 16906 33402 16906 33403 16905 33403 16907 33403 16906 33404 16907 33404 17904 33404 17904 33405 16907 33405 17902 33405 17902 33406 16907 33406 19669 33406 17902 33407 19669 33407 16908 33407 16909 33408 16913 33408 19676 33408 19676 33409 16913 33409 18626 33409 19676 33410 18626 33410 16910 33410 16910 33411 18626 33411 17895 33411 16911 33412 17909 33412 19675 33412 19675 33413 17909 33413 18617 33413 19675 33414 18617 33414 16912 33414 16912 33415 18617 33415 18616 33415 16913 33416 16909 33416 18627 33416 18627 33417 16909 33417 18150 33417 18627 33418 18150 33418 18152 33418 16912 33419 18616 33419 18154 33419 18154 33420 18616 33420 16914 33420 18154 33421 16914 33421 16954 33421 16915 33422 16916 33422 16956 33422 16956 33423 16916 33423 16917 33423 16956 33424 16917 33424 18191 33424 16918 33425 16923 33425 18628 33425 18628 33426 16923 33426 16919 33426 18628 33427 16919 33427 16915 33427 16915 33428 16919 33428 18283 33428 16915 33429 18283 33429 16916 33429 18287 33430 18630 33430 16920 33430 16920 33431 18630 33431 16928 33431 18287 33432 16921 33432 18630 33432 18630 33433 16921 33433 18285 33433 18630 33434 18285 33434 16918 33434 16918 33435 18285 33435 16922 33435 16918 33436 16922 33436 16923 33436 16924 33437 16934 33437 16925 33437 16925 33438 16926 33438 16924 33438 16924 33439 16926 33439 16927 33439 16924 33440 16927 33440 16928 33440 16928 33441 16927 33441 16929 33441 16928 33442 16929 33442 16920 33442 16930 33443 16931 33443 18301 33443 18301 33444 16932 33444 16930 33444 16930 33445 16932 33445 18299 33445 16930 33446 18299 33446 16933 33446 18299 33447 18298 33447 16933 33447 16933 33448 18298 33448 18295 33448 16933 33449 18295 33449 16934 33449 16934 33450 18295 33450 18294 33450 16934 33451 18294 33451 16925 33451 16931 33452 16930 33452 18303 33452 18303 33453 16930 33453 16935 33453 18303 33454 16935 33454 18305 33454 18305 33455 16935 33455 18306 33455 18306 33456 16935 33456 16936 33456 18306 33457 16936 33457 18307 33457 18307 33458 16936 33458 18627 33458 18307 33459 18627 33459 18152 33459 16937 33460 18308 33460 18309 33460 16937 33461 18309 33461 18620 33461 18309 33462 18328 33462 18620 33462 18620 33463 18328 33463 16940 33463 18620 33464 16940 33464 16938 33464 16941 33465 18621 33465 18310 33465 18310 33466 18621 33466 16938 33466 18310 33467 16938 33467 16939 33467 16939 33468 16938 33468 16940 33468 16941 33469 18312 33469 18621 33469 18621 33470 18312 33470 16942 33470 18621 33471 16942 33471 16943 33471 16943 33472 16942 33472 18311 33472 16943 33473 18311 33473 16944 33473 16944 33474 18311 33474 16945 33474 16944 33475 16945 33475 18622 33475 18622 33476 16945 33476 16946 33476 18622 33477 16946 33477 16948 33477 16946 33478 16947 33478 16948 33478 16948 33479 16947 33479 16950 33479 16948 33480 16950 33480 16949 33480 18322 33481 16953 33481 16952 33481 16950 33482 18319 33482 16949 33482 16949 33483 18319 33483 18320 33483 16949 33484 18320 33484 18618 33484 18618 33485 18320 33485 16951 33485 18618 33486 16951 33486 16952 33486 16952 33487 16951 33487 18323 33487 16952 33488 18323 33488 18322 33488 18322 33489 18324 33489 16953 33489 16953 33490 18324 33490 18326 33490 16953 33491 18326 33491 16914 33491 16914 33492 18326 33492 18327 33492 16914 33493 18327 33493 16954 33493 16955 33494 18624 33494 18192 33494 18192 33495 18624 33495 16956 33495 18192 33496 16956 33496 18191 33496 18615 33497 16959 33497 16937 33497 16937 33498 16959 33498 18194 33498 16937 33499 18194 33499 18308 33499 16957 33500 18098 33500 16958 33500 16958 33501 18098 33501 18625 33501 16958 33502 18625 33502 16955 33502 16955 33503 18625 33503 18624 33503 16959 33504 18615 33504 19439 33504 19439 33505 18615 33505 18614 33505 19439 33506 18614 33506 16960 33506 16960 33507 18614 33507 16961 33507 16957 33508 16964 33508 18098 33508 18098 33509 16964 33509 16965 33509 16962 33510 16963 33510 19437 33510 19437 33511 16963 33511 18096 33511 19437 33512 18096 33512 16964 33512 16964 33513 18096 33513 18097 33513 16964 33514 18097 33514 16965 33514 16962 33515 19437 33515 18095 33515 18095 33516 19437 33516 19438 33516 18095 33517 19438 33517 16966 33517 16966 33518 19438 33518 19435 33518 16966 33519 19435 33519 16967 33519 18092 33520 19436 33520 18091 33520 18091 33521 19436 33521 16969 33521 18091 33522 16969 33522 18090 33522 16971 33523 18087 33523 19433 33523 19433 33524 18087 33524 16968 33524 19433 33525 16968 33525 16969 33525 16969 33526 16968 33526 16970 33526 16969 33527 16970 33527 18090 33527 19433 33528 19443 33528 16971 33528 16971 33529 19443 33529 16960 33529 16971 33530 16960 33530 16961 33530 19435 33531 19436 33531 16967 33531 16967 33532 19436 33532 18092 33532 16972 33533 17911 33533 16988 33533 16988 33534 17911 33534 17914 33534 17911 33535 16972 33535 16976 33535 16976 33536 16972 33536 16973 33536 16974 33537 16975 33537 16973 33537 16973 33538 16975 33538 17913 33538 16973 33539 17913 33539 16976 33539 16974 33540 16973 33540 16977 33540 16977 33541 16973 33541 19664 33541 16977 33542 19664 33542 16978 33542 16978 33543 19664 33543 19671 33543 16978 33544 19671 33544 16979 33544 16979 33545 19671 33545 19673 33545 16979 33546 19673 33546 16980 33546 16981 33547 16982 33547 18642 33547 18642 33548 16982 33548 16983 33548 19667 33549 17918 33549 16984 33549 19667 33550 16984 33550 16982 33550 16982 33551 16984 33551 17919 33551 16982 33552 17919 33552 16983 33552 17918 33553 19667 33553 16985 33553 16985 33554 19667 33554 16987 33554 16985 33555 16987 33555 16986 33555 16986 33556 16987 33556 17915 33556 17915 33557 16987 33557 16988 33557 17915 33558 16988 33558 17914 33558 16994 33559 16993 33559 16989 33559 16989 33560 16993 33560 18644 33560 16989 33561 18644 33561 19673 33561 19673 33562 18644 33562 16980 33562 16981 33563 18642 33563 16990 33563 16990 33564 18642 33564 16991 33564 16990 33565 16991 33565 18158 33565 18158 33566 16991 33566 16992 33566 16993 33567 16994 33567 16995 33567 16995 33568 16994 33568 18155 33568 16995 33569 18155 33569 18156 33569 17047 33570 16996 33570 16992 33570 16992 33571 16996 33571 18160 33571 16992 33572 18160 33572 18158 33572 16997 33573 16999 33573 16998 33573 16998 33574 16999 33574 17000 33574 16998 33575 17000 33575 18195 33575 18332 33576 17002 33576 17001 33576 17001 33577 17002 33577 17008 33577 17001 33578 17008 33578 18333 33578 18333 33579 17008 33579 17010 33579 18332 33580 17003 33580 17002 33580 17002 33581 17003 33581 18331 33581 17002 33582 18331 33582 16997 33582 16997 33583 18331 33583 18329 33583 16997 33584 18329 33584 16999 33584 17014 33585 17004 33585 18648 33585 17005 33586 17007 33586 18314 33586 18314 33587 17007 33587 18648 33587 18314 33588 18648 33588 18315 33588 18315 33589 18648 33589 17004 33589 17005 33590 17006 33590 17007 33590 17007 33591 17006 33591 17009 33591 17007 33592 17009 33592 17008 33592 17008 33593 17009 33593 18334 33593 17008 33594 18334 33594 17010 33594 17015 33595 17011 33595 18647 33595 18647 33596 17011 33596 18317 33596 18647 33597 18317 33597 17012 33597 18317 33598 18318 33598 17012 33598 17012 33599 18318 33599 17013 33599 17012 33600 17013 33600 18648 33600 18648 33601 17013 33601 18316 33601 18648 33602 18316 33602 17014 33602 17015 33603 18647 33603 18321 33603 18321 33604 18647 33604 18646 33604 18321 33605 18646 33605 17016 33605 17016 33606 18646 33606 18325 33606 18325 33607 18646 33607 18645 33607 18325 33608 18645 33608 17017 33608 18645 33609 17018 33609 17017 33609 17017 33610 17018 33610 16995 33610 17017 33611 16995 33611 18156 33611 18196 33612 17020 33612 17019 33612 17019 33613 17020 33613 18335 33613 17019 33614 18335 33614 18640 33614 18335 33615 17021 33615 18640 33615 18640 33616 17021 33616 17022 33616 18640 33617 17022 33617 17024 33617 17024 33618 17022 33618 17023 33618 17023 33619 18337 33619 17024 33619 17024 33620 18337 33620 17025 33620 17024 33621 17025 33621 17026 33621 17026 33622 17025 33622 17027 33622 17026 33623 17027 33623 18336 33623 18336 33624 17028 33624 17026 33624 17026 33625 17028 33625 17029 33625 17026 33626 17029 33626 17032 33626 18339 33627 17030 33627 17031 33627 17031 33628 17030 33628 17032 33628 17031 33629 17032 33629 18338 33629 18338 33630 17032 33630 17029 33630 18339 33631 18341 33631 17030 33631 17030 33632 18341 33632 18340 33632 17030 33633 18340 33633 17033 33633 17033 33634 18340 33634 17034 33634 17034 33635 17035 33635 17033 33635 17033 33636 17035 33636 17036 33636 17033 33637 17036 33637 17038 33637 18342 33638 17040 33638 18343 33638 18343 33639 17040 33639 17037 33639 17036 33640 18347 33640 17038 33640 17038 33641 18347 33641 18346 33641 17038 33642 18346 33642 17037 33642 17037 33643 18346 33643 18345 33643 17037 33644 18345 33644 18343 33644 18342 33645 17039 33645 17040 33645 17040 33646 17039 33646 17041 33646 17040 33647 17041 33647 18643 33647 17041 33648 17042 33648 18643 33648 18643 33649 17042 33649 17043 33649 18643 33650 17043 33650 17044 33650 17043 33651 18348 33651 17044 33651 17044 33652 18348 33652 17045 33652 17044 33653 17045 33653 17046 33653 17045 33654 18349 33654 17046 33654 17046 33655 18349 33655 18351 33655 17046 33656 18351 33656 17047 33656 17047 33657 18351 33657 17048 33657 17047 33658 17048 33658 16996 33658 19445 33659 17054 33659 17049 33659 17049 33660 17054 33660 16998 33660 17049 33661 16998 33661 18195 33661 18196 33662 17019 33662 17050 33662 17050 33663 17019 33663 17055 33663 17050 33664 17055 33664 17051 33664 17052 33665 17056 33665 19444 33665 19444 33666 17056 33666 17053 33666 19444 33667 17053 33667 19445 33667 19445 33668 17053 33668 17054 33668 18639 33669 19449 33669 17055 33669 17055 33670 19449 33670 19447 33670 17055 33671 19447 33671 17051 33671 17052 33672 17058 33672 17056 33672 17056 33673 17058 33673 17059 33673 17057 33674 18083 33674 19442 33674 19442 33675 18083 33675 18082 33675 19442 33676 18082 33676 17058 33676 17058 33677 18082 33677 18084 33677 17058 33678 18084 33678 17059 33678 17057 33679 19442 33679 18081 33679 18081 33680 19442 33680 19441 33680 18081 33681 19441 33681 18079 33681 18079 33682 19441 33682 19440 33682 18079 33683 19440 33683 18078 33683 17067 33684 17066 33684 18077 33684 18077 33685 17066 33685 17063 33685 18077 33686 17063 33686 17060 33686 18074 33687 18075 33687 17061 33687 17061 33688 18075 33688 17062 33688 17061 33689 17062 33689 17063 33689 17063 33690 17062 33690 17064 33690 17063 33691 17064 33691 17060 33691 17061 33692 17065 33692 18074 33692 18074 33693 17065 33693 19449 33693 18074 33694 19449 33694 18639 33694 17066 33695 17067 33695 19440 33695 19440 33696 17067 33696 18078 33696 17069 33697 17923 33697 17075 33697 17075 33698 17923 33698 17076 33698 17923 33699 17069 33699 17068 33699 17068 33700 17069 33700 19603 33700 17068 33701 19603 33701 17070 33701 17070 33702 19603 33702 17071 33702 19613 33703 19616 33703 17072 33703 17072 33704 19616 33704 17931 33704 19617 33705 17074 33705 17929 33705 19617 33706 17929 33706 19616 33706 19616 33707 17929 33707 17073 33707 19616 33708 17073 33708 17931 33708 17074 33709 19617 33709 17928 33709 17928 33710 19617 33710 19619 33710 17928 33711 19619 33711 17927 33711 17927 33712 19619 33712 17926 33712 17926 33713 19619 33713 17075 33713 17926 33714 17075 33714 17076 33714 17070 33715 17071 33715 17924 33715 17924 33716 17071 33716 17077 33716 17924 33717 17077 33717 17925 33717 17079 33718 17922 33718 17078 33718 17079 33719 17078 33719 17077 33719 17077 33720 17078 33720 17080 33720 17077 33721 17080 33721 17925 33721 17922 33722 17079 33722 17081 33722 17081 33723 17079 33723 17082 33723 17081 33724 17082 33724 17920 33724 17920 33725 17082 33725 19668 33725 17920 33726 19668 33726 17083 33726 19613 33727 17072 33727 17084 33727 17084 33728 17072 33728 17085 33728 17084 33729 17085 33729 17086 33729 17086 33730 17085 33730 17088 33730 17094 33731 18670 33731 19665 33731 19665 33732 18670 33732 17087 33732 19665 33733 17087 33733 19668 33733 19668 33734 17087 33734 17083 33734 17086 33735 17088 33735 17089 33735 17089 33736 17088 33736 17090 33736 17089 33737 17090 33737 18162 33737 18162 33738 17090 33738 17091 33738 17121 33739 17092 33739 18159 33739 18159 33740 17092 33740 17093 33740 18159 33741 17093 33741 17094 33741 17094 33742 17093 33742 18670 33742 18658 33743 18385 33743 17095 33743 18658 33744 17095 33744 17096 33744 17096 33745 17095 33745 18358 33745 17096 33746 18358 33746 18664 33746 18664 33747 18358 33747 17097 33747 18664 33748 17097 33748 17099 33748 17099 33749 17097 33749 17098 33749 17099 33750 17098 33750 18665 33750 18665 33751 17098 33751 18359 33751 18665 33752 18359 33752 18666 33752 18666 33753 18359 33753 18361 33753 18666 33754 18361 33754 18667 33754 18667 33755 18361 33755 18362 33755 18667 33756 18362 33756 17100 33756 17100 33757 18362 33757 17101 33757 17100 33758 17101 33758 18662 33758 18662 33759 17101 33759 18363 33759 18662 33760 18363 33760 17102 33760 18363 33761 17103 33761 17102 33761 17102 33762 17103 33762 18366 33762 17102 33763 18366 33763 18660 33763 18660 33764 18366 33764 18162 33764 18660 33765 18162 33765 17091 33765 17106 33766 17122 33766 17104 33766 17104 33767 17105 33767 17106 33767 17106 33768 17105 33768 17111 33768 17106 33769 17111 33769 17110 33769 17112 33770 18356 33770 17107 33770 17107 33771 18356 33771 17108 33771 17107 33772 17108 33772 17109 33772 17109 33773 17108 33773 17110 33773 17109 33774 17110 33774 18674 33774 18674 33775 17110 33775 17111 33775 17107 33776 18673 33776 17112 33776 17112 33777 18673 33777 18672 33777 17112 33778 18672 33778 17113 33778 17113 33779 18672 33779 17114 33779 17113 33780 17114 33780 17115 33780 17115 33781 17114 33781 17117 33781 17114 33782 17116 33782 17117 33782 17117 33783 17116 33783 17119 33783 17117 33784 17119 33784 17118 33784 17119 33785 17120 33785 17118 33785 17118 33786 17120 33786 17092 33786 17118 33787 17092 33787 17121 33787 18385 33788 18658 33788 18197 33788 18197 33789 18658 33789 18659 33789 18197 33790 18659 33790 17124 33790 17104 33791 17122 33791 18668 33791 18668 33792 17122 33792 17123 33792 18668 33793 17123 33793 17128 33793 17124 33794 18659 33794 17125 33794 17125 33795 18659 33795 18062 33795 17125 33796 18062 33796 17126 33796 18668 33797 17128 33797 17127 33797 17127 33798 17128 33798 19451 33798 17127 33799 19451 33799 19450 33799 18067 33800 17141 33800 18065 33800 18065 33801 17141 33801 17129 33801 17130 33802 17131 33802 17129 33802 17129 33803 17131 33803 17132 33803 17129 33804 17132 33804 18065 33804 17129 33805 19285 33805 17130 33805 17130 33806 19285 33806 19283 33806 17130 33807 19283 33807 18063 33807 18063 33808 19283 33808 17126 33808 18063 33809 17126 33809 18062 33809 17133 33810 17134 33810 17135 33810 19450 33811 19448 33811 17127 33811 17127 33812 19448 33812 18072 33812 17135 33813 17134 33813 19448 33813 19448 33814 17134 33814 17136 33814 19448 33815 17136 33815 18072 33815 17133 33816 17135 33816 17137 33816 17137 33817 17135 33817 17138 33817 17137 33818 17138 33818 17139 33818 19434 33819 17140 33819 17138 33819 17138 33820 17140 33820 18068 33820 17138 33821 18068 33821 17139 33821 17141 33822 18067 33822 19280 33822 19280 33823 18067 33823 18069 33823 17140 33824 19434 33824 17142 33824 17142 33825 19434 33825 17143 33825 17142 33826 17143 33826 18069 33826 18069 33827 17143 33827 19280 33827 19604 33828 17145 33828 17144 33828 17144 33829 17145 33829 17146 33829 17145 33830 19604 33830 17147 33830 17147 33831 19604 33831 17148 33831 17147 33832 17148 33832 17932 33832 17932 33833 17148 33833 17149 33833 17149 33834 17148 33834 17934 33834 17934 33835 17148 33835 19618 33835 17934 33836 19618 33836 17150 33836 17150 33837 19618 33837 19615 33837 17150 33838 19615 33838 17151 33838 17151 33839 19615 33839 17152 33839 17152 33840 19615 33840 19614 33840 17152 33841 19614 33841 17153 33841 19606 33842 19608 33842 18689 33842 18689 33843 19608 33843 17154 33843 19610 33844 17157 33844 17155 33844 19610 33845 17155 33845 19608 33845 19608 33846 17155 33846 17156 33846 19608 33847 17156 33847 17154 33847 17157 33848 19610 33848 17937 33848 17937 33849 19610 33849 19611 33849 17937 33850 19611 33850 17158 33850 17158 33851 19611 33851 17935 33851 17935 33852 19611 33852 17144 33852 17935 33853 17144 33853 17146 33853 17164 33854 18697 33854 17159 33854 17159 33855 18697 33855 18696 33855 17159 33856 18696 33856 19614 33856 19614 33857 18696 33857 17153 33857 19606 33858 18689 33858 19602 33858 19602 33859 18689 33859 17160 33859 19602 33860 17160 33860 17161 33860 17161 33861 17160 33861 17165 33861 18161 33862 18371 33862 17162 33862 18161 33863 17162 33863 17163 33863 17163 33864 17162 33864 18697 33864 17163 33865 18697 33865 17164 33865 17161 33866 17165 33866 18166 33866 18166 33867 17165 33867 17207 33867 18166 33868 17207 33868 18410 33868 17175 33869 17166 33869 18695 33869 18695 33870 17166 33870 17167 33870 18695 33871 17167 33871 17211 33871 17171 33872 17172 33872 17169 33872 17169 33873 17172 33873 17168 33873 17169 33874 17168 33874 17170 33874 17171 33875 18384 33875 17172 33875 17172 33876 18384 33876 18383 33876 17172 33877 18383 33877 17173 33877 18383 33878 18382 33878 17173 33878 17173 33879 18382 33879 17174 33879 17173 33880 17174 33880 17175 33880 17175 33881 17174 33881 17176 33881 17175 33882 17176 33882 17166 33882 17177 33883 17178 33883 18380 33883 18380 33884 18379 33884 17177 33884 17177 33885 18379 33885 18378 33885 17177 33886 18378 33886 17168 33886 17168 33887 18378 33887 18377 33887 17168 33888 18377 33888 17170 33888 17178 33889 17177 33889 17179 33889 17179 33890 17177 33890 18699 33890 17179 33891 18699 33891 17180 33891 17180 33892 18699 33892 18698 33892 17180 33893 18698 33893 18374 33893 18373 33894 17182 33894 17181 33894 17181 33895 17182 33895 18376 33895 17181 33896 18376 33896 18698 33896 18698 33897 18376 33897 17183 33897 18698 33898 17183 33898 18374 33898 18368 33899 18365 33899 17185 33899 17185 33900 18365 33900 18364 33900 17185 33901 18364 33901 17181 33901 17181 33902 18364 33902 17184 33902 17181 33903 17184 33903 18373 33903 18368 33904 17185 33904 17186 33904 17186 33905 17185 33905 17188 33905 17186 33906 17188 33906 18369 33906 18369 33907 17188 33907 17187 33907 17187 33908 17188 33908 17189 33908 17187 33909 17189 33909 18370 33909 18370 33910 17189 33910 17162 33910 18370 33911 17162 33911 18371 33911 17190 33912 17191 33912 18687 33912 18687 33913 17191 33913 18386 33913 18687 33914 18386 33914 17193 33914 18386 33915 17192 33915 17193 33915 17193 33916 17192 33916 18389 33916 17193 33917 18389 33917 18690 33917 18690 33918 18389 33918 17194 33918 17194 33919 18388 33919 18690 33919 18690 33920 18388 33920 17195 33920 18690 33921 17195 33921 17196 33921 17196 33922 17195 33922 17197 33922 17197 33923 18394 33923 17196 33923 17196 33924 18394 33924 18393 33924 17196 33925 18393 33925 18691 33925 18691 33926 18393 33926 18392 33926 18691 33927 18392 33927 18692 33927 18692 33928 18392 33928 18390 33928 18390 33929 18395 33929 18692 33929 18692 33930 18395 33930 18396 33930 18692 33931 18396 33931 17198 33931 18396 33932 18398 33932 17198 33932 17198 33933 18398 33933 18399 33933 17198 33934 18399 33934 17200 33934 17200 33935 18399 33935 17199 33935 17199 33936 18408 33936 17200 33936 17200 33937 18408 33937 18407 33937 17200 33938 18407 33938 18693 33938 18693 33939 18407 33939 18406 33939 18402 33940 17201 33940 17202 33940 17202 33941 17201 33941 17203 33941 17202 33942 17203 33942 18404 33942 18404 33943 17203 33943 18693 33943 18404 33944 18693 33944 17204 33944 17204 33945 18693 33945 18406 33945 18402 33946 18417 33946 17201 33946 17201 33947 18417 33947 17206 33947 17201 33948 17206 33948 17205 33948 17206 33949 18416 33949 17205 33949 17205 33950 18416 33950 18413 33950 17205 33951 18413 33951 17207 33951 17207 33952 18413 33952 18411 33952 17207 33953 18411 33953 18410 33953 17208 33954 17209 33954 17210 33954 17210 33955 17209 33955 18695 33955 17210 33956 18695 33956 17211 33956 17215 33957 18198 33957 18687 33957 18687 33958 18198 33958 17212 33958 18687 33959 17212 33959 17190 33959 19282 33960 17213 33960 17214 33960 17214 33961 17213 33961 17209 33961 17214 33962 17209 33962 17208 33962 18198 33963 17215 33963 19287 33963 19287 33964 17215 33964 18686 33964 19287 33965 18686 33965 17216 33965 17216 33966 18686 33966 18685 33966 19282 33967 17217 33967 17213 33967 17213 33968 17217 33968 17218 33968 17219 33969 18058 33969 19284 33969 19284 33970 18058 33970 18059 33970 19284 33971 18059 33971 17217 33971 17217 33972 18059 33972 18060 33972 17217 33973 18060 33973 17218 33973 17219 33974 19284 33974 17220 33974 17220 33975 19284 33975 17221 33975 17220 33976 17221 33976 18057 33976 18057 33977 17221 33977 17226 33977 18057 33978 17226 33978 18694 33978 17227 33979 17225 33979 18055 33979 18055 33980 17225 33980 17222 33980 17223 33981 18053 33981 17222 33981 17222 33982 18053 33982 18054 33982 17222 33983 18054 33983 18055 33983 17222 33984 19290 33984 17223 33984 17223 33985 19290 33985 17224 33985 17223 33986 17224 33986 18051 33986 18051 33987 17224 33987 17216 33987 18051 33988 17216 33988 18685 33988 17225 33989 17227 33989 17226 33989 17226 33990 17227 33990 18694 33990 17238 33991 19598 33991 17945 33991 17945 33992 19598 33992 17228 33992 17228 33993 19598 33993 17943 33993 17943 33994 19598 33994 17230 33994 17229 33995 17231 33995 17230 33995 17230 33996 17231 33996 17941 33996 17230 33997 17941 33997 17943 33997 17230 33998 19612 33998 17229 33998 17229 33999 19612 33999 19609 33999 17229 34000 19609 34000 17232 34000 17232 34001 19609 34001 17938 34001 17938 34002 19609 34002 19607 34002 17938 34003 19607 34003 17233 34003 19601 34004 19600 34004 17954 34004 17954 34005 19600 34005 17234 34005 17237 34006 17950 34006 17235 34006 17237 34007 17235 34007 19600 34007 19600 34008 17235 34008 17236 34008 19600 34009 17236 34009 17234 34009 17950 34010 17237 34010 17949 34010 17949 34011 17237 34011 19599 34011 17949 34012 19599 34012 17947 34012 17947 34013 19599 34013 17946 34013 17946 34014 19599 34014 17238 34014 17946 34015 17238 34015 17945 34015 17242 34016 17233 34016 19607 34016 17245 34017 17240 34017 17239 34017 17239 34018 17240 34018 17242 34018 17239 34019 17242 34019 17241 34019 17241 34020 17242 34020 19607 34020 19601 34021 17954 34021 17243 34021 17243 34022 17954 34022 18710 34022 17243 34023 18710 34023 19595 34023 19595 34024 18710 34024 17244 34024 17240 34025 17245 34025 17246 34025 17246 34026 17245 34026 18165 34026 17246 34027 18165 34027 18409 34027 19595 34028 17244 34028 18168 34028 18168 34029 17244 34029 18709 34029 18168 34030 18709 34030 18456 34030 17252 34031 18423 34031 18422 34031 17252 34032 18422 34032 17277 34032 17277 34033 18422 34033 18387 34033 17277 34034 18387 34034 18199 34034 17256 34035 17248 34035 17247 34035 17247 34036 17248 34036 17250 34036 17248 34037 17249 34037 17250 34037 17250 34038 17249 34038 17251 34038 17250 34039 17251 34039 17252 34039 17252 34040 17251 34040 18424 34040 17252 34041 18424 34041 18423 34041 18400 34042 18397 34042 17253 34042 17253 34043 18397 34043 18391 34043 17253 34044 18391 34044 17254 34044 17254 34045 18391 34045 18421 34045 18421 34046 18420 34046 17254 34046 17254 34047 18420 34047 17255 34047 17254 34048 17255 34048 17247 34048 17247 34049 17255 34049 18419 34049 17247 34050 18419 34050 17256 34050 18724 34051 17259 34051 18725 34051 18725 34052 17259 34052 17257 34052 18725 34053 17257 34053 17253 34053 17253 34054 17257 34054 18401 34054 17253 34055 18401 34055 18400 34055 17258 34056 18403 34056 18724 34056 18724 34057 18403 34057 18405 34057 18724 34058 18405 34058 17259 34058 18722 34059 17246 34059 18409 34059 18409 34060 18412 34060 18722 34060 18722 34061 18412 34061 18414 34061 18722 34062 18414 34062 17260 34062 17260 34063 18414 34063 18415 34063 17260 34064 18415 34064 17258 34064 17258 34065 18415 34065 18418 34065 17258 34066 18418 34066 18403 34066 18204 34067 17261 34067 17279 34067 17279 34068 17261 34068 17262 34068 17279 34069 17262 34069 17263 34069 17263 34070 17262 34070 17264 34070 17263 34071 17264 34071 17265 34071 17265 34072 17264 34072 18435 34072 17265 34073 18435 34073 17266 34073 18435 34074 18437 34074 17266 34074 17266 34075 18437 34075 18438 34075 17266 34076 18438 34076 17268 34076 18443 34077 18715 34077 18442 34077 18442 34078 18715 34078 17267 34078 18442 34079 17267 34079 17268 34079 17268 34080 17267 34080 18713 34080 17268 34081 18713 34081 17266 34081 18443 34082 18445 34082 18715 34082 18715 34083 18445 34083 17269 34083 18715 34084 17269 34084 18716 34084 18716 34085 17269 34085 17270 34085 18716 34086 17270 34086 17271 34086 17270 34087 17272 34087 17271 34087 17271 34088 17272 34088 18448 34088 17271 34089 18448 34089 18711 34089 18711 34090 18448 34090 18440 34090 18711 34091 18440 34091 18712 34091 18712 34092 18440 34092 17273 34092 18712 34093 17273 34093 17274 34093 17273 34094 18452 34094 17274 34094 17274 34095 18452 34095 18454 34095 17274 34096 18454 34096 18709 34096 18709 34097 18454 34097 17275 34097 18709 34098 17275 34098 18456 34098 17282 34099 18720 34099 17276 34099 17276 34100 18720 34100 17277 34100 17276 34101 17277 34101 18199 34101 18708 34102 17278 34102 17279 34102 17279 34103 17278 34103 18203 34103 17279 34104 18203 34104 18204 34104 17280 34105 17281 34105 19288 34105 19288 34106 17281 34106 18721 34106 19288 34107 18721 34107 17282 34107 17282 34108 18721 34108 18720 34108 17278 34109 18708 34109 19294 34109 19294 34110 18708 34110 18707 34110 19294 34111 18707 34111 17283 34111 17283 34112 18707 34112 18706 34112 17280 34113 19289 34113 17281 34113 17281 34114 19289 34114 17284 34114 18047 34115 17285 34115 19279 34115 19279 34116 17285 34116 18048 34116 19279 34117 18048 34117 19289 34117 19289 34118 18048 34118 17286 34118 19289 34119 17286 34119 17284 34119 18047 34120 19279 34120 17287 34120 17287 34121 19279 34121 19278 34121 17287 34122 19278 34122 18046 34122 18046 34123 19278 34123 19371 34123 18046 34124 19371 34124 18718 34124 18717 34125 17288 34125 17290 34125 17290 34126 17288 34126 19297 34126 17291 34127 17289 34127 19297 34127 19297 34128 17289 34128 18045 34128 19297 34129 18045 34129 17290 34129 19297 34130 17292 34130 17291 34130 17291 34131 17292 34131 19295 34131 17291 34132 19295 34132 17293 34132 17293 34133 19295 34133 17283 34133 17293 34134 17283 34134 18706 34134 19371 34135 17288 34135 18718 34135 18718 34136 17288 34136 18717 34136 19587 34137 17295 34137 17294 34137 17294 34138 17295 34138 17958 34138 17958 34139 17295 34139 17959 34139 17959 34140 17295 34140 17297 34140 17959 34141 17297 34141 17296 34141 17296 34142 17297 34142 17298 34142 17298 34143 17297 34143 17955 34143 17955 34144 17297 34144 19586 34144 17955 34145 19586 34145 17957 34145 17957 34146 19586 34146 19585 34146 17957 34147 19585 34147 17299 34147 17299 34148 19585 34148 17300 34148 17300 34149 19585 34149 19593 34149 17300 34150 19593 34150 17301 34150 19590 34151 17304 34151 17302 34151 17302 34152 17304 34152 17303 34152 17306 34153 17305 34153 17965 34153 17306 34154 17965 34154 17304 34154 17304 34155 17965 34155 17967 34155 17304 34156 17967 34156 17303 34156 17305 34157 17306 34157 17964 34157 17964 34158 17306 34158 17308 34158 17964 34159 17308 34159 17307 34159 17307 34160 17308 34160 17961 34160 17961 34161 17308 34161 19587 34161 17961 34162 19587 34162 17294 34162 18167 34163 17311 34163 19596 34163 19596 34164 17311 34164 18741 34164 19596 34165 18741 34165 19593 34165 19593 34166 18741 34166 17301 34166 19590 34167 17302 34167 19588 34167 19588 34168 17302 34168 17309 34168 19588 34169 17309 34169 18173 34169 18173 34170 17309 34170 17313 34170 18455 34171 18742 34171 17310 34171 17310 34172 18742 34172 17311 34172 17310 34173 17311 34173 18167 34173 17312 34174 17314 34174 17313 34174 17313 34175 17314 34175 18175 34175 17313 34176 18175 34176 18173 34176 18744 34177 17315 34177 17347 34177 17347 34178 17315 34178 17316 34178 17347 34179 17316 34179 18427 34179 17317 34180 18433 34180 18434 34180 18434 34181 18429 34181 17317 34181 17317 34182 18429 34182 17318 34182 17317 34183 17318 34183 17319 34183 17318 34184 18431 34184 17319 34184 17319 34185 18431 34185 18430 34185 17319 34186 18430 34186 18744 34186 18744 34187 18430 34187 18428 34187 18744 34188 18428 34188 17315 34188 18747 34189 17320 34189 18444 34189 18444 34190 17321 34190 18747 34190 18747 34191 17321 34191 18441 34191 18747 34192 18441 34192 17322 34192 17322 34193 18441 34193 18439 34193 18439 34194 18457 34194 17322 34194 17322 34195 18457 34195 17323 34195 17322 34196 17323 34196 17317 34196 17317 34197 17323 34197 18432 34197 17317 34198 18432 34198 18433 34198 17320 34199 18747 34199 18446 34199 18446 34200 18747 34200 18746 34200 18446 34201 18746 34201 17324 34201 17324 34202 18746 34202 18745 34202 17324 34203 18745 34203 18447 34203 18447 34204 18745 34204 17325 34204 18447 34205 17325 34205 17326 34205 17326 34206 17325 34206 17327 34206 17326 34207 17327 34207 18449 34207 18449 34208 17327 34208 18451 34208 18451 34209 17327 34209 17328 34209 18451 34210 17328 34210 18450 34210 18450 34211 17328 34211 17329 34211 18450 34212 17329 34212 18453 34212 18453 34213 17329 34213 18742 34213 18453 34214 18742 34214 18455 34214 17330 34215 18459 34215 17331 34215 17331 34216 18459 34216 17332 34216 17331 34217 17332 34217 18735 34217 18735 34218 17332 34218 17334 34218 18735 34219 17334 34219 18736 34219 17333 34220 17340 34220 18738 34220 17334 34221 18460 34221 18736 34221 18736 34222 18460 34222 18461 34222 18736 34223 18461 34223 17335 34223 17335 34224 18461 34224 18464 34224 17335 34225 18464 34225 17336 34225 17336 34226 18464 34226 18466 34226 17336 34227 18466 34227 17337 34227 17337 34228 18466 34228 17338 34228 17337 34229 17338 34229 18738 34229 18738 34230 17338 34230 18467 34230 18738 34231 18467 34231 17333 34231 17341 34232 18739 34232 17339 34232 17339 34233 18739 34233 17340 34233 17339 34234 17340 34234 18469 34234 18469 34235 17340 34235 17333 34235 17341 34236 17342 34236 18739 34236 18739 34237 17342 34237 17343 34237 18739 34238 17343 34238 17344 34238 17343 34239 18475 34239 17344 34239 17344 34240 18475 34240 18473 34240 17344 34241 18473 34241 18734 34241 18734 34242 18473 34242 18472 34242 18734 34243 18472 34243 17345 34243 17345 34244 18472 34244 18471 34244 17345 34245 18471 34245 17312 34245 17312 34246 18471 34246 17346 34246 17312 34247 17346 34247 17314 34247 18201 34248 18740 34248 18202 34248 18202 34249 18740 34249 17347 34249 18202 34250 17347 34250 18427 34250 17330 34251 17331 34251 17348 34251 17348 34252 17331 34252 17352 34252 17348 34253 17352 34253 18205 34253 17349 34254 17355 34254 17351 34254 17351 34255 17355 34255 17350 34255 17351 34256 17350 34256 18201 34256 18201 34257 17350 34257 18740 34257 18205 34258 17352 34258 19300 34258 19300 34259 17352 34259 17353 34259 19300 34260 17353 34260 17365 34260 17365 34261 17353 34261 17354 34261 17349 34262 17356 34262 17355 34262 17355 34263 17356 34263 18043 34263 18041 34264 18040 34264 19296 34264 19296 34265 18040 34265 17357 34265 19296 34266 17357 34266 17356 34266 17356 34267 17357 34267 18042 34267 17356 34268 18042 34268 18043 34268 18041 34269 19296 34269 18038 34269 18038 34270 19296 34270 19293 34270 18038 34271 19293 34271 17358 34271 17358 34272 19293 34272 17366 34272 17358 34273 17366 34273 17367 34273 17359 34274 17360 34274 18037 34274 18037 34275 17360 34275 17364 34275 17361 34276 17362 34276 19303 34276 19303 34277 17362 34277 17363 34277 19303 34278 17363 34278 17360 34278 17360 34279 17363 34279 18036 34279 17360 34280 18036 34280 17364 34280 19303 34281 19302 34281 17361 34281 17361 34282 19302 34282 17365 34282 17361 34283 17365 34283 17354 34283 17366 34284 17359 34284 17367 34284 17367 34285 17359 34285 18037 34285 19584 34286 17369 34286 17368 34286 17368 34287 17369 34287 18772 34287 18772 34288 17369 34288 17972 34288 17972 34289 17369 34289 17370 34289 17972 34290 17370 34290 17970 34290 17970 34291 17370 34291 17371 34291 17970 34292 17371 34292 17969 34292 17969 34293 17371 34293 17372 34293 17372 34294 17371 34294 17373 34294 17372 34295 17373 34295 17374 34295 17374 34296 17373 34296 17375 34296 17375 34297 17373 34297 19591 34297 17375 34298 19591 34298 17381 34298 19578 34299 19579 34299 18763 34299 18763 34300 19579 34300 17977 34300 17379 34301 17376 34301 19579 34301 19579 34302 17376 34302 17976 34302 19579 34303 17976 34303 17977 34303 17377 34304 19584 34304 17368 34304 17368 34305 17973 34305 17377 34305 17377 34306 17973 34306 17378 34306 17377 34307 17378 34307 17379 34307 17379 34308 17378 34308 17975 34308 17379 34309 17975 34309 17376 34309 18171 34310 17384 34310 19589 34310 19589 34311 17384 34311 17380 34311 19589 34312 17380 34312 19591 34312 19591 34313 17380 34313 17381 34313 19578 34314 18763 34314 17382 34314 17382 34315 18763 34315 18762 34315 17382 34316 18762 34316 18176 34316 18176 34317 18762 34317 17385 34317 18174 34318 17383 34318 18170 34318 18170 34319 17383 34319 17384 34319 18170 34320 17384 34320 18171 34320 18761 34321 18495 34321 17385 34321 17385 34322 18495 34322 17386 34322 17385 34323 17386 34323 18176 34323 18465 34324 18463 34324 18771 34324 18771 34325 18463 34325 18462 34325 18771 34326 18462 34326 18768 34326 18768 34327 18462 34327 18458 34327 18768 34328 18458 34328 17387 34328 17387 34329 18458 34329 18207 34329 17387 34330 18207 34330 18769 34330 18465 34331 18771 34331 17388 34331 17388 34332 18771 34332 18770 34332 17388 34333 18770 34333 17389 34333 17391 34334 18476 34334 18468 34334 17389 34335 18770 34335 18468 34335 18468 34336 18770 34336 17390 34336 18468 34337 17390 34337 17391 34337 18476 34338 17391 34338 18474 34338 18474 34339 17391 34339 17392 34339 18474 34340 17392 34340 17393 34340 17393 34341 17392 34341 17395 34341 17393 34342 17395 34342 17394 34342 17394 34343 17395 34343 18767 34343 17394 34344 18767 34344 18470 34344 18470 34345 18767 34345 17383 34345 18470 34346 17383 34346 18174 34346 18492 34347 17402 34347 17404 34347 17410 34348 17408 34348 17396 34348 17410 34349 17396 34349 17397 34349 17396 34350 17398 34350 17397 34350 17397 34351 17398 34351 18487 34351 17397 34352 18487 34352 18760 34352 18760 34353 18487 34353 18486 34353 18760 34354 18486 34354 18764 34354 17399 34355 17400 34355 18490 34355 18490 34356 17400 34356 18766 34356 18490 34357 18766 34357 18481 34357 18481 34358 18766 34358 18765 34358 18481 34359 18765 34359 18482 34359 18482 34360 18765 34360 18764 34360 18482 34361 18764 34361 18483 34361 18483 34362 18764 34362 18486 34362 17399 34363 18489 34363 17400 34363 17400 34364 18489 34364 18488 34364 17400 34365 18488 34365 17404 34365 17404 34366 18488 34366 17401 34366 17404 34367 17401 34367 18492 34367 17402 34368 18503 34368 17404 34368 17404 34369 18503 34369 17403 34369 17404 34370 17403 34370 18758 34370 17403 34371 18501 34371 18758 34371 18758 34372 18501 34372 18499 34372 18758 34373 18499 34373 17405 34373 17405 34374 18499 34374 18497 34374 17405 34375 18497 34375 18761 34375 18761 34376 18497 34376 18495 34376 18769 34377 18207 34377 17407 34377 17407 34378 18207 34378 17406 34378 17407 34379 17406 34379 17413 34379 17408 34380 17410 34380 17409 34380 17409 34381 17410 34381 17415 34381 17409 34382 17415 34382 17411 34382 19299 34383 17416 34383 19298 34383 19298 34384 17416 34384 17412 34384 19298 34385 17412 34385 17413 34385 17413 34386 17412 34386 17407 34386 17411 34387 17415 34387 17414 34387 17414 34388 17415 34388 18022 34388 17414 34389 18022 34389 19310 34389 19299 34390 17418 34390 17416 34390 17416 34391 17418 34391 18032 34391 18030 34392 17417 34392 19301 34392 19301 34393 17417 34393 18029 34393 19301 34394 18029 34394 17418 34394 17418 34395 18029 34395 18031 34395 17418 34396 18031 34396 18032 34396 18030 34397 19301 34397 17419 34397 17419 34398 19301 34398 19291 34398 17419 34399 19291 34399 18026 34399 18026 34400 19291 34400 17420 34400 18026 34401 17420 34401 17429 34401 17428 34402 17424 34402 18025 34402 18025 34403 17424 34403 17425 34403 17427 34404 17422 34404 17421 34404 17421 34405 17422 34405 17423 34405 17421 34406 17423 34406 17424 34406 17424 34407 17423 34407 18024 34407 17424 34408 18024 34408 17425 34408 17421 34409 17426 34409 17427 34409 17427 34410 17426 34410 19310 34410 17427 34411 19310 34411 18022 34411 17420 34412 17428 34412 17429 34412 17429 34413 17428 34413 18025 34413 17430 34414 17431 34414 18791 34414 18791 34415 17431 34415 18790 34415 18790 34416 17431 34416 17984 34416 17984 34417 17431 34417 19576 34417 17984 34418 19576 34418 17432 34418 17432 34419 19576 34419 19582 34419 17432 34420 19582 34420 17981 34420 17981 34421 19582 34421 17433 34421 17433 34422 19582 34422 19581 34422 17433 34423 19581 34423 17979 34423 17979 34424 19581 34424 17434 34424 17434 34425 19581 34425 19580 34425 17434 34426 19580 34426 17440 34426 17435 34427 17436 34427 17438 34427 17438 34428 17436 34428 17442 34428 17438 34429 17442 34429 17437 34429 17435 34430 17438 34430 17987 34430 17987 34431 17438 34431 19569 34431 17987 34432 19569 34432 17985 34432 17985 34433 19569 34433 19568 34433 17985 34434 19568 34434 17439 34434 17439 34435 19568 34435 17430 34435 17439 34436 17430 34436 18791 34436 17446 34437 18788 34437 19521 34437 19521 34438 18788 34438 18787 34438 19521 34439 18787 34439 19580 34439 19580 34440 18787 34440 17440 34440 17437 34441 17442 34441 17441 34441 17441 34442 17442 34442 17443 34442 17441 34443 17443 34443 19575 34443 19575 34444 17443 34444 18784 34444 18496 34445 17444 34445 17445 34445 17445 34446 17444 34446 18788 34446 17445 34447 18788 34447 17446 34447 19575 34448 18784 34448 18178 34448 18178 34449 18784 34449 17447 34449 18178 34450 17447 34450 17448 34450 17448 34451 17447 34451 17476 34451 18485 34452 17449 34452 17450 34452 17450 34453 17449 34453 18477 34453 17450 34454 18477 34454 17477 34454 17477 34455 18477 34455 18478 34455 17477 34456 18478 34456 18479 34456 18485 34457 17450 34457 18484 34457 18484 34458 17450 34458 17451 34458 18484 34459 17451 34459 18480 34459 18480 34460 17451 34460 17458 34460 18480 34461 17458 34461 17452 34461 17453 34462 17454 34462 18491 34462 18491 34463 17454 34463 17462 34463 18491 34464 17462 34464 18494 34464 17453 34465 17455 34465 17454 34465 17454 34466 17455 34466 17456 34466 17454 34467 17456 34467 18789 34467 18789 34468 17456 34468 17457 34468 18789 34469 17457 34469 17458 34469 17458 34470 17457 34470 17459 34470 17458 34471 17459 34471 17452 34471 17464 34472 17460 34472 18493 34472 17464 34473 18493 34473 17462 34473 17462 34474 18493 34474 17461 34474 17462 34475 17461 34475 18494 34475 18502 34476 17463 34476 17464 34476 17464 34477 17463 34477 18504 34477 17464 34478 18504 34478 17460 34478 18502 34479 17464 34479 18500 34479 18500 34480 17464 34480 17465 34480 18500 34481 17465 34481 18498 34481 18498 34482 17465 34482 17444 34482 18498 34483 17444 34483 18496 34483 17469 34484 17467 34484 17466 34484 17466 34485 17467 34485 17468 34485 17466 34486 17468 34486 18212 34486 17469 34487 18520 34487 17467 34487 17467 34488 18520 34488 18518 34488 17467 34489 18518 34489 18785 34489 18785 34490 18518 34490 18517 34490 18785 34491 18517 34491 17470 34491 17470 34492 18517 34492 18516 34492 17470 34493 18516 34493 17471 34493 18510 34494 17474 34494 18512 34494 18512 34495 17474 34495 18780 34495 18512 34496 18780 34496 17472 34496 17472 34497 18780 34497 17471 34497 17472 34498 17471 34498 18515 34498 18515 34499 17471 34499 18516 34499 18508 34500 17475 34500 17473 34500 17473 34501 17475 34501 17474 34501 17473 34502 17474 34502 18509 34502 18509 34503 17474 34503 18510 34503 18508 34504 18507 34504 17475 34504 17475 34505 18507 34505 18506 34505 17475 34506 18506 34506 17476 34506 17476 34507 18506 34507 18505 34507 17476 34508 18505 34508 17448 34508 18209 34509 17478 34509 18210 34509 18210 34510 17478 34510 17477 34510 18210 34511 17477 34511 18479 34511 17482 34512 19317 34512 18783 34512 18783 34513 19317 34513 18212 34513 18783 34514 18212 34514 17468 34514 17478 34515 18209 34515 17479 34515 17479 34516 18209 34516 19304 34516 17479 34517 19304 34517 17480 34517 19317 34518 17482 34518 17481 34518 17481 34519 17482 34519 18782 34519 17481 34520 18782 34520 19315 34520 19315 34521 18782 34521 17498 34521 17479 34522 17480 34522 17483 34522 17488 34523 17484 34523 19311 34523 19311 34524 17484 34524 17485 34524 19311 34525 17485 34525 17483 34525 17483 34526 17485 34526 17486 34526 17483 34527 17486 34527 17479 34527 17490 34528 17487 34528 17488 34528 17488 34529 17487 34529 18020 34529 17488 34530 18020 34530 17484 34530 17488 34531 17489 34531 17490 34531 17490 34532 17489 34532 17499 34532 17490 34533 17499 34533 17491 34533 19313 34534 17494 34534 18786 34534 18786 34535 17494 34535 18018 34535 17496 34536 17492 34536 19312 34536 19312 34537 17492 34537 17493 34537 19312 34538 17493 34538 17494 34538 17494 34539 17493 34539 17495 34539 17494 34540 17495 34540 18018 34540 19312 34541 17497 34541 17496 34541 17496 34542 17497 34542 19315 34542 17496 34543 19315 34543 17498 34543 17499 34544 19313 34544 17491 34544 17491 34545 19313 34545 18786 34545 18006 34546 18005 34546 18015 34546 18015 34547 18005 34547 17500 34547 18015 34548 17500 34548 18013 34548 17500 34549 19319 34549 18013 34549 18013 34550 19319 34550 17502 34550 18013 34551 17502 34551 18012 34551 18012 34552 17502 34552 17501 34552 17501 34553 17502 34553 17503 34553 17501 34554 17503 34554 17504 34554 17504 34555 17503 34555 17505 34555 17505 34556 17503 34556 19321 34556 17505 34557 19321 34557 18800 34557 18800 34558 19321 34558 19323 34558 18800 34559 19323 34559 17506 34559 17506 34560 19323 34560 17507 34560 17506 34561 17507 34561 17508 34561 17508 34562 17507 34562 19324 34562 17508 34563 19324 34563 17516 34563 19566 34564 19565 34564 18802 34564 19566 34565 18802 34565 17509 34565 18802 34566 18801 34566 17509 34566 17509 34567 18801 34567 17510 34567 17509 34568 17510 34568 17511 34568 17511 34569 17510 34569 18799 34569 17511 34570 18799 34570 19562 34570 19562 34571 18799 34571 17512 34571 19562 34572 17512 34572 17513 34572 17513 34573 17512 34573 17514 34573 17513 34574 17514 34574 19563 34574 19563 34575 17514 34575 17515 34575 19563 34576 17515 34576 19564 34576 19564 34577 17515 34577 19523 34577 19523 34578 17515 34578 17516 34578 19523 34579 17516 34579 19324 34579 19565 34580 19567 34580 18802 34580 18802 34581 19567 34581 17518 34581 17519 34582 18002 34582 17991 34582 17991 34583 18002 34583 18001 34583 19567 34584 17517 34584 17518 34584 17518 34585 17517 34585 19573 34585 17518 34586 19573 34586 17993 34586 17993 34587 19573 34587 18004 34587 17993 34588 18004 34588 17519 34588 17519 34589 18004 34589 17520 34589 17519 34590 17520 34590 18002 34590 19107 34591 17522 34591 17521 34591 17521 34592 17522 34592 17523 34592 17521 34593 17523 34593 19243 34593 19243 34594 17523 34594 17524 34594 19243 34595 17524 34595 19114 34595 19107 34596 17521 34596 17525 34596 19107 34597 17525 34597 19108 34597 19108 34598 17525 34598 19255 34598 19108 34599 19255 34599 19083 34599 19251 34600 19133 34600 17526 34600 19251 34601 17526 34601 19255 34601 19255 34602 17526 34602 17527 34602 19255 34603 17527 34603 19083 34603 19133 34604 19251 34604 19105 34604 19105 34605 19251 34605 19246 34605 19105 34606 19246 34606 17528 34606 17528 34607 19246 34607 19259 34607 17528 34608 19259 34608 17532 34608 17535 34609 19235 34609 19237 34609 17535 34610 19237 34610 19081 34610 19081 34611 19237 34611 19234 34611 19081 34612 19234 34612 17529 34612 17529 34613 19234 34613 19232 34613 17529 34614 19232 34614 19116 34614 19116 34615 19232 34615 19233 34615 19116 34616 19233 34616 19117 34616 19117 34617 19233 34617 17531 34617 19117 34618 17531 34618 17530 34618 17530 34619 17531 34619 19231 34619 17530 34620 19231 34620 19980 34620 17532 34621 19259 34621 19163 34621 19163 34622 19259 34622 19164 34622 19104 34623 19181 34623 19273 34623 19273 34624 19181 34624 19180 34624 19273 34625 19180 34625 19259 34625 19259 34626 19180 34626 19165 34626 19259 34627 19165 34627 19164 34627 17533 34628 17534 34628 17551 34628 19235 34629 17535 34629 17536 34629 17536 34630 17537 34630 19235 34630 19235 34631 17537 34631 17538 34631 19235 34632 17538 34632 17551 34632 17551 34633 17538 34633 19176 34633 17551 34634 19176 34634 17533 34634 19104 34635 19273 34635 19269 34635 19104 34636 19269 34636 17539 34636 17539 34637 19269 34637 17540 34637 17539 34638 17540 34638 17541 34638 17541 34639 17540 34639 19267 34639 17541 34640 19267 34640 17542 34640 17542 34641 19267 34641 17543 34641 17542 34642 17543 34642 17544 34642 17544 34643 17543 34643 17553 34643 17544 34644 17553 34644 19103 34644 19085 34645 17552 34645 17545 34645 19085 34646 17545 34646 17546 34646 17546 34647 17545 34647 19226 34647 17546 34648 19226 34648 17547 34648 17547 34649 19226 34649 17549 34649 17547 34650 17549 34650 17548 34650 17548 34651 17549 34651 19225 34651 17548 34652 19225 34652 19086 34652 19086 34653 19225 34653 19223 34653 19086 34654 19223 34654 17550 34654 17550 34655 19223 34655 17551 34655 17550 34656 17551 34656 17534 34656 19085 34657 19211 34657 17552 34657 17552 34658 19211 34658 19210 34658 17552 34659 19210 34659 17553 34659 17553 34660 19210 34660 19084 34660 17553 34661 19084 34661 19103 34661 17562 34662 19271 34662 19391 34662 17554 34663 19402 34663 17555 34663 17555 34664 19260 34664 17554 34664 17554 34665 19260 34665 17556 34665 17554 34666 17556 34666 17557 34666 17557 34667 17556 34667 17558 34667 17557 34668 17558 34668 19400 34668 17560 34669 19397 34669 17559 34669 17559 34670 19397 34670 19400 34670 17559 34671 19400 34671 19263 34671 19263 34672 19400 34672 17558 34672 17560 34673 19262 34673 19397 34673 19397 34674 19262 34674 19261 34674 19397 34675 19261 34675 19396 34675 19396 34676 19261 34676 19268 34676 19396 34677 19268 34677 19394 34677 19394 34678 19268 34678 17561 34678 19394 34679 17561 34679 19393 34679 17561 34680 19266 34680 19393 34680 19393 34681 19266 34681 19265 34681 19393 34682 19265 34682 19391 34682 19391 34683 19265 34683 19264 34683 19391 34684 19264 34684 17562 34684 19270 34685 17565 34685 19271 34685 19271 34686 17565 34686 17563 34686 19271 34687 17563 34687 19391 34687 19270 34688 17564 34688 17565 34688 17565 34689 17564 34689 17566 34689 17565 34690 17566 34690 19389 34690 19389 34691 17566 34691 19390 34691 17566 34692 19274 34692 19390 34692 19390 34693 19274 34693 17567 34693 19390 34694 17567 34694 19385 34694 19385 34695 17567 34695 19386 34695 17567 34696 19272 34696 19386 34696 19386 34697 19272 34697 17568 34697 19386 34698 17568 34698 17582 34698 19357 34699 17570 34699 17569 34699 17569 34700 17570 34700 17571 34700 17571 34701 17570 34701 17572 34701 17572 34702 17570 34702 17573 34702 17572 34703 17573 34703 17574 34703 17574 34704 17573 34704 19383 34704 17574 34705 19383 34705 17575 34705 19383 34706 19470 34706 17575 34706 17575 34707 19470 34707 17576 34707 17575 34708 17576 34708 17577 34708 17577 34709 17576 34709 17578 34709 17577 34710 17578 34710 17579 34710 17579 34711 17578 34711 19387 34711 17579 34712 19387 34712 17580 34712 17580 34713 19387 34713 17581 34713 17580 34714 17581 34714 17568 34714 17568 34715 17581 34715 17582 34715 19217 34716 17583 34716 19714 34716 19714 34717 17583 34717 17584 34717 19714 34718 17584 34718 19405 34718 19405 34719 17584 34719 17585 34719 19405 34720 17585 34720 19412 34720 19412 34721 17585 34721 17586 34721 19412 34722 17586 34722 19403 34722 19403 34723 17586 34723 17587 34723 17587 34724 17586 34724 17555 34724 17587 34725 17555 34725 19402 34725 17588 34726 19341 34726 17589 34726 17589 34727 19341 34727 19343 34727 17589 34728 19343 34728 17591 34728 17590 34729 19344 34729 19348 34729 17590 34730 19348 34730 17594 34730 19343 34731 19345 34731 17591 34731 17591 34732 19345 34732 19344 34732 17591 34733 19344 34733 17592 34733 17592 34734 19344 34734 17590 34734 19348 34735 19347 34735 17594 34735 17594 34736 19347 34736 17593 34736 17594 34737 17593 34737 17595 34737 17595 34738 17593 34738 17596 34738 17595 34739 17596 34739 17597 34739 17597 34740 17596 34740 17598 34740 17597 34741 17598 34741 17599 34741 17599 34742 17598 34742 19350 34742 17599 34743 19350 34743 17569 34743 17569 34744 19350 34744 19356 34744 17569 34745 19356 34745 19357 34745 19731 34746 17603 34746 17600 34746 17600 34747 17603 34747 17605 34747 17600 34748 17605 34748 17604 34748 17601 34749 19229 34749 17602 34749 17602 34750 19229 34750 17603 34750 17602 34751 17603 34751 19782 34751 19782 34752 17603 34752 19731 34752 17604 34753 17605 34753 19785 34753 19785 34754 17605 34754 19218 34754 19785 34755 19218 34755 19723 34755 19723 34756 19218 34756 17606 34756 19723 34757 17606 34757 19216 34757 17607 34758 19718 34758 19216 34758 19216 34759 19718 34759 19720 34759 19216 34760 19720 34760 19723 34760 19714 34761 19716 34761 19217 34761 19217 34762 19716 34762 17608 34762 19217 34763 17608 34763 17607 34763 17607 34764 17608 34764 19717 34764 17607 34765 19717 34765 19718 34765 17609 34766 17588 34766 17589 34766 19249 34767 19340 34767 17610 34767 19254 34768 17613 34768 19331 34768 17651 34769 17611 34769 19258 34769 19258 34770 17611 34770 17612 34770 17612 34771 19326 34771 19258 34771 19258 34772 19326 34772 19329 34772 19258 34773 19329 34773 17618 34773 19331 34774 17613 34774 17614 34774 17613 34775 19257 34775 17614 34775 17614 34776 19257 34776 17615 34776 17614 34777 17615 34777 17616 34777 17616 34778 17615 34778 17617 34778 17616 34779 17617 34779 19329 34779 19329 34780 17617 34780 19256 34780 19329 34781 19256 34781 17618 34781 19336 34782 19253 34782 17619 34782 17619 34783 19253 34783 19252 34783 17619 34784 19252 34784 19334 34784 19334 34785 19252 34785 19250 34785 19334 34786 19250 34786 17620 34786 17620 34787 19250 34787 17621 34787 17620 34788 17621 34788 19331 34788 19331 34789 17621 34789 17622 34789 19331 34790 17622 34790 19254 34790 19340 34791 19249 34791 19339 34791 19249 34792 17623 34792 19339 34792 19339 34793 17623 34793 19248 34793 19339 34794 19248 34794 19337 34794 19337 34795 19248 34795 19247 34795 19337 34796 19247 34796 19336 34796 19336 34797 19247 34797 17624 34797 19336 34798 17624 34798 19253 34798 17589 34799 17625 34799 17609 34799 17609 34800 17625 34800 17626 34800 17609 34801 17626 34801 17610 34801 17610 34802 17626 34802 17627 34802 17610 34803 17627 34803 19249 34803 17652 34804 19219 34804 19771 34804 19771 34805 19219 34805 17628 34805 19771 34806 17628 34806 19763 34806 19763 34807 17628 34807 19224 34807 19763 34808 19224 34808 17629 34808 19224 34809 17630 34809 17629 34809 17629 34810 17630 34810 17631 34810 17629 34811 17631 34811 19735 34811 19735 34812 17631 34812 19222 34812 19735 34813 19222 34813 19736 34813 19736 34814 19222 34814 17632 34814 19736 34815 17632 34815 19739 34815 19739 34816 17632 34816 17633 34816 19739 34817 17633 34817 19737 34817 19737 34818 17633 34818 17634 34818 19737 34819 17634 34819 19769 34819 17634 34820 17635 34820 19769 34820 19769 34821 17635 34821 17636 34821 19769 34822 17636 34822 17639 34822 17639 34823 17636 34823 17637 34823 17637 34824 17638 34824 17639 34824 17639 34825 17638 34825 17640 34825 17639 34826 17640 34826 19662 34826 19662 34827 17640 34827 17641 34827 19662 34828 17641 34828 19752 34828 17641 34829 19228 34829 19752 34829 19752 34830 19228 34830 17642 34830 19752 34831 17642 34831 19734 34831 19734 34832 17642 34832 19227 34832 19734 34833 19227 34833 19754 34833 19754 34834 19227 34834 17643 34834 19754 34835 17643 34835 19753 34835 17643 34836 19230 34836 19753 34836 19753 34837 19230 34837 17644 34837 19753 34838 17644 34838 17645 34838 17645 34839 17644 34839 19229 34839 17645 34840 19229 34840 17601 34840 17646 34841 19245 34841 17647 34841 17647 34842 17648 34842 17646 34842 17646 34843 17648 34843 17649 34843 17646 34844 17649 34844 19238 34844 17649 34845 19367 34845 19238 34845 19238 34846 19367 34846 19368 34846 19238 34847 19368 34847 17650 34847 17650 34848 19368 34848 19277 34848 17650 34849 19277 34849 19239 34849 19239 34850 19277 34850 17611 34850 19239 34851 17611 34851 17651 34851 19219 34852 17652 34852 19220 34852 19220 34853 17652 34853 17725 34853 19220 34854 17725 34854 19221 34854 19221 34855 17725 34855 17746 34855 19221 34856 17746 34856 17653 34856 19240 34857 19542 34857 19543 34857 19240 34858 19543 34858 17654 34858 19543 34859 17655 34859 17654 34859 17654 34860 17655 34860 17656 34860 17654 34861 17656 34861 19241 34861 17656 34862 17657 34862 19241 34862 19241 34863 17657 34863 19547 34863 19241 34864 19547 34864 19242 34864 19242 34865 19547 34865 19549 34865 19242 34866 19549 34866 17658 34866 19549 34867 19550 34867 17658 34867 17658 34868 19550 34868 17659 34868 17658 34869 17659 34869 19244 34869 17659 34870 19553 34870 19244 34870 19244 34871 19553 34871 19555 34871 19244 34872 19555 34872 19245 34872 19245 34873 19555 34873 19557 34873 19245 34874 19557 34874 17647 34874 17726 34875 17751 34875 17660 34875 17660 34876 17751 34876 17729 34876 17660 34877 17729 34877 17661 34877 17661 34878 17729 34878 17728 34878 17661 34879 17728 34879 19517 34879 19517 34880 17728 34880 17829 34880 19517 34881 17829 34881 17686 34881 17653 34882 17746 34882 17662 34882 17653 34883 17662 34883 17660 34883 17660 34884 17662 34884 17663 34884 17660 34885 17663 34885 17726 34885 17676 34886 19536 34886 17681 34886 17668 34887 17669 34887 17664 34887 17664 34888 17669 34888 19236 34888 17664 34889 19236 34889 17665 34889 17665 34890 19236 34890 17691 34890 17665 34891 17691 34891 19638 34891 19526 34892 17666 34892 17668 34892 17668 34893 17666 34893 17667 34893 17668 34894 17667 34894 17669 34894 19531 34895 17671 34895 17670 34895 17670 34896 17671 34896 17666 34896 17670 34897 17666 34897 19525 34897 19525 34898 17666 34898 19526 34898 19533 34899 17672 34899 17673 34899 17673 34900 17672 34900 17674 34900 17673 34901 17674 34901 19531 34901 19531 34902 17674 34902 17675 34902 19531 34903 17675 34903 17671 34903 19536 34904 17676 34904 19535 34904 19535 34905 17676 34905 17677 34905 19535 34906 17677 34906 19533 34906 19533 34907 17677 34907 17678 34907 19533 34908 17678 34908 17672 34908 19539 34909 17679 34909 17681 34909 17681 34910 17679 34910 17680 34910 17681 34911 17680 34911 17676 34911 19542 34912 19240 34912 17683 34912 17683 34913 19240 34913 17682 34913 17683 34914 17682 34914 19540 34914 19540 34915 17682 34915 17684 34915 19540 34916 17684 34916 19539 34916 19539 34917 17684 34917 17685 34917 19539 34918 17685 34918 17679 34918 17829 34919 17819 34919 17686 34919 17686 34920 17819 34920 17687 34920 17686 34921 17687 34921 19518 34921 19516 34922 17688 34922 17690 34922 19516 34923 17690 34923 17689 34923 17689 34924 17690 34924 19638 34924 17689 34925 19638 34925 17691 34925 17687 34926 17819 34926 17802 34926 17692 34927 19518 34927 17687 34927 17687 34928 17802 34928 17692 34928 17692 34929 17802 34929 17801 34929 17692 34930 17801 34930 17693 34930 17693 34931 17801 34931 17786 34931 17693 34932 17786 34932 19515 34932 19515 34933 17786 34933 17688 34933 19515 34934 17688 34934 19516 34934 19972 34935 17844 34935 17694 34935 17694 34936 17844 34936 17833 34936 17694 34937 17833 34937 17703 34937 17703 34938 17833 34938 17695 34938 17703 34939 17695 34939 17696 34939 17696 34940 17695 34940 17697 34940 17696 34941 17697 34941 17698 34941 17698 34942 17697 34942 17699 34942 17698 34943 17699 34943 17700 34943 17700 34944 17699 34944 17701 34944 17700 34945 17701 34945 19973 34945 19973 34946 17701 34946 17824 34946 19966 34947 19972 34947 17702 34947 17702 34948 19972 34948 17694 34948 17702 34949 17694 34949 17705 34949 17705 34950 17694 34950 17703 34950 17705 34951 17703 34951 17704 34951 17704 34952 17703 34952 17696 34952 17704 34953 17696 34953 17708 34953 17708 34954 17696 34954 17698 34954 17708 34955 17698 34955 17707 34955 17707 34956 17698 34956 17700 34956 17707 34957 17700 34957 19967 34957 19967 34958 17700 34958 19973 34958 17706 34959 17705 34959 17704 34959 17702 34960 17705 34960 17706 34960 19966 34961 17702 34961 17706 34961 17706 34962 17707 34962 19967 34962 17708 34963 17707 34963 17706 34963 17704 34964 17708 34964 17706 34964 17713 34965 17825 34965 17716 34965 17716 34966 17825 34966 17818 34966 17716 34967 17818 34967 17717 34967 17717 34968 17818 34968 17821 34968 17717 34969 17821 34969 17709 34969 17709 34970 17821 34970 17710 34970 17709 34971 17710 34971 17719 34971 17719 34972 17710 34972 17820 34972 17719 34973 17820 34973 17721 34973 17721 34974 17820 34974 17711 34974 17721 34975 17711 34975 17722 34975 17722 34976 17711 34976 17848 34976 17712 34977 17713 34977 17714 34977 17714 34978 17713 34978 17716 34978 17714 34979 17716 34979 17715 34979 17715 34980 17716 34980 17717 34980 17715 34981 17717 34981 17723 34981 17723 34982 17717 34982 17709 34982 17723 34983 17709 34983 17718 34983 17718 34984 17709 34984 17719 34984 17718 34985 17719 34985 17720 34985 17720 34986 17719 34986 17721 34986 17720 34987 17721 34987 19950 34987 19950 34988 17721 34988 17722 34988 19947 34989 17715 34989 17723 34989 17714 34990 17715 34990 19947 34990 17712 34991 17714 34991 19947 34991 19947 34992 17720 34992 19950 34992 17718 34993 17720 34993 19947 34993 17723 34994 17718 34994 19947 34994 17765 34995 17734 34995 17764 34995 17725 34996 17652 34996 17724 34996 17725 34997 17724 34997 17746 34997 17747 34998 17662 34998 17746 34998 17749 34999 17726 34999 17747 34999 17747 35000 17726 35000 17663 35000 17747 35001 17663 35001 17662 35001 17727 35002 17829 35002 17728 35002 17727 35003 17728 35003 17752 35003 17752 35004 17728 35004 17729 35004 17752 35005 17729 35005 17751 35005 17752 35006 17754 35006 17727 35006 17727 35007 17754 35007 17755 35007 17727 35008 17755 35008 17730 35008 17730 35009 17755 35009 17757 35009 17730 35010 17757 35010 17731 35010 17731 35011 17757 35011 17830 35011 17830 35012 17757 35012 17759 35012 17830 35013 17759 35013 17831 35013 17831 35014 17759 35014 17732 35014 17831 35015 17732 35015 17733 35015 17733 35016 17732 35016 17823 35016 17823 35017 17732 35017 17761 35017 17823 35018 17761 35018 17822 35018 17761 35019 17762 35019 17822 35019 17822 35020 17762 35020 17764 35020 17822 35021 17764 35021 17840 35021 17840 35022 17764 35022 17734 35022 17840 35023 17734 35023 17839 35023 17735 35024 17736 35024 17763 35024 17763 35025 17736 35025 16482 35025 17739 35026 19791 35026 16433 35026 16433 35027 19791 35027 19750 35027 17740 35028 19744 35028 17738 35028 17738 35029 19744 35029 17737 35029 17738 35030 17737 35030 17739 35030 17739 35031 17737 35031 19743 35031 17739 35032 19743 35032 19791 35032 17770 35033 17742 35033 17740 35033 17740 35034 17742 35034 17741 35034 17740 35035 17741 35035 19744 35035 19774 35036 19775 35036 17770 35036 17770 35037 19775 35037 19779 35037 17770 35038 19779 35038 17742 35038 17770 35039 17769 35039 19774 35039 19774 35040 17769 35040 17743 35040 19774 35041 17743 35041 17744 35041 17744 35042 17743 35042 17745 35042 17744 35043 17745 35043 17767 35043 17746 35044 17724 35044 17747 35044 17747 35045 17724 35045 19742 35045 17747 35046 19742 35046 17750 35046 17750 35047 19742 35047 17748 35047 17750 35048 17748 35048 17766 35048 17749 35049 17747 35049 17753 35049 17753 35050 17747 35050 17750 35050 17753 35051 17750 35051 17756 35051 17756 35052 17750 35052 17766 35052 17756 35053 17766 35053 17758 35053 17751 35054 17726 35054 17752 35054 17752 35055 17726 35055 17749 35055 17752 35056 17749 35056 17754 35056 17754 35057 17749 35057 17753 35057 17754 35058 17753 35058 17755 35058 17755 35059 17753 35059 17756 35059 17755 35060 17756 35060 17757 35060 17757 35061 17756 35061 17758 35061 17757 35062 17758 35062 17759 35062 17759 35063 17758 35063 17768 35063 17759 35064 17768 35064 17732 35064 17732 35065 17768 35065 17760 35065 17732 35066 17760 35066 17761 35066 17761 35067 17760 35067 17771 35067 17761 35068 17771 35068 17762 35068 17762 35069 17771 35069 17772 35069 17762 35070 17772 35070 17764 35070 17764 35071 17772 35071 17763 35071 17764 35072 17763 35072 17765 35072 17765 35073 17763 35073 16482 35073 17748 35074 17767 35074 17766 35074 17766 35075 17767 35075 17745 35075 17766 35076 17745 35076 17758 35076 17758 35077 17745 35077 17743 35077 17758 35078 17743 35078 17768 35078 17768 35079 17743 35079 17769 35079 17768 35080 17769 35080 17760 35080 17760 35081 17769 35081 17770 35081 17760 35082 17770 35082 17771 35082 17771 35083 17770 35083 17740 35083 17771 35084 17740 35084 17772 35084 17772 35085 17740 35085 17738 35085 17772 35086 17738 35086 17763 35086 17763 35087 17738 35087 17739 35087 17763 35088 17739 35088 17735 35088 17735 35089 17739 35089 16433 35089 19622 35090 17795 35090 17799 35090 17773 35091 17774 35091 17775 35091 17786 35092 17801 35092 17776 35092 16605 35093 17777 35093 17807 35093 17807 35094 17777 35094 17778 35094 17815 35095 17814 35095 17816 35095 17816 35096 17814 35096 17813 35096 17816 35097 17813 35097 17779 35097 17779 35098 17813 35098 17812 35098 17779 35099 17812 35099 17780 35099 17780 35100 17812 35100 17809 35100 17780 35101 17809 35101 17781 35101 17781 35102 17809 35102 17808 35102 17781 35103 17808 35103 17826 35103 17826 35104 17808 35104 17782 35104 17826 35105 17782 35105 17827 35105 17827 35106 17782 35106 17783 35106 17827 35107 17783 35107 17828 35107 17828 35108 17783 35108 17803 35108 17828 35109 17803 35109 17784 35109 17802 35110 17819 35110 17803 35110 17803 35111 17819 35111 17785 35111 17803 35112 17785 35112 17784 35112 19638 35113 17690 35113 19645 35113 19645 35114 17690 35114 17688 35114 19645 35115 17688 35115 17786 35115 17786 35116 17776 35116 19645 35116 19645 35117 17776 35117 17787 35117 19645 35118 17787 35118 17789 35118 17789 35119 17787 35119 17788 35119 17789 35120 17788 35120 19519 35120 19519 35121 17788 35121 17804 35121 19519 35122 17804 35122 17790 35122 17790 35123 17791 35123 19651 35123 19651 35124 17791 35124 17805 35124 17773 35125 17775 35125 17792 35125 17792 35126 17775 35126 17793 35126 17792 35127 17793 35127 19625 35127 19625 35128 17793 35128 17794 35128 17794 35129 17793 35129 17797 35129 17794 35130 17797 35130 19624 35130 17799 35131 17795 35131 17797 35131 17797 35132 17795 35132 17796 35132 17797 35133 17796 35133 19624 35133 17798 35134 16569 35134 17799 35134 19659 35135 19622 35135 17800 35135 17800 35136 19622 35136 17799 35136 17800 35137 17799 35137 16568 35137 16568 35138 17799 35138 16569 35138 17801 35139 17802 35139 17776 35139 17776 35140 17802 35140 17803 35140 17776 35141 17803 35141 17787 35141 17787 35142 17803 35142 17783 35142 17787 35143 17783 35143 17788 35143 17788 35144 17783 35144 17782 35144 17788 35145 17782 35145 17804 35145 17804 35146 17782 35146 17808 35146 17773 35147 19651 35147 17774 35147 17774 35148 19651 35148 17805 35148 17774 35149 17805 35149 17775 35149 17775 35150 17805 35150 17810 35150 17775 35151 17810 35151 17793 35151 17793 35152 17810 35152 17811 35152 17793 35153 17811 35153 17797 35153 17797 35154 17811 35154 17806 35154 17797 35155 17806 35155 17799 35155 17799 35156 17806 35156 17807 35156 17799 35157 17807 35157 17798 35157 17798 35158 17807 35158 17778 35158 17790 35159 17804 35159 17791 35159 17791 35160 17804 35160 17808 35160 17791 35161 17808 35161 17805 35161 17805 35162 17808 35162 17809 35162 17805 35163 17809 35163 17810 35163 17810 35164 17809 35164 17812 35164 17810 35165 17812 35165 17811 35165 17811 35166 17812 35166 17813 35166 17811 35167 17813 35167 17806 35167 17806 35168 17813 35168 17814 35168 17806 35169 17814 35169 17807 35169 17807 35170 17814 35170 17815 35170 17807 35171 17815 35171 16605 35171 16605 35172 17815 35172 17816 35172 16605 35173 17816 35173 16601 35173 16319 35174 17817 35174 17819 35174 17828 35175 17784 35175 17818 35175 17818 35176 17784 35176 17785 35176 17818 35177 17785 35177 17819 35177 17727 35178 17730 35178 17731 35178 17844 35179 17846 35179 19998 35179 17838 35180 19978 35180 17840 35180 17711 35181 17820 35181 17817 35181 17817 35182 17820 35182 17710 35182 17817 35183 17710 35183 17819 35183 17819 35184 17710 35184 17821 35184 17819 35185 17821 35185 17818 35185 17840 35186 19978 35186 17822 35186 17822 35187 19978 35187 19977 35187 17822 35188 19977 35188 17823 35188 17823 35189 19977 35189 19975 35189 17823 35190 19975 35190 17733 35190 17733 35191 19975 35191 17824 35191 17733 35192 17824 35192 17831 35192 17836 35193 16601 35193 19959 35193 19959 35194 16601 35194 17816 35194 19959 35195 17816 35195 19961 35195 19961 35196 17816 35196 17779 35196 19961 35197 17779 35197 19962 35197 19962 35198 17779 35198 17780 35198 19962 35199 17780 35199 17825 35199 17780 35200 17781 35200 17825 35200 17825 35201 17781 35201 17826 35201 17825 35202 17826 35202 17818 35202 17818 35203 17826 35203 17827 35203 17818 35204 17827 35204 17828 35204 17829 35205 17727 35205 17701 35205 17701 35206 17727 35206 17731 35206 17701 35207 17731 35207 17824 35207 17824 35208 17731 35208 17830 35208 17824 35209 17830 35209 17831 35209 17829 35210 16316 35210 17819 35210 17819 35211 16316 35211 17832 35211 17819 35212 17832 35212 16319 35212 16316 35213 17833 35213 17834 35213 17834 35214 17833 35214 17843 35214 17848 35215 17835 35215 19957 35215 19957 35216 17835 35216 16586 35216 19957 35217 16586 35217 17836 35217 17836 35218 16586 35218 16587 35218 17836 35219 16587 35219 16601 35219 17701 35220 17699 35220 17829 35220 17829 35221 17699 35221 17697 35221 17829 35222 17697 35222 16316 35222 16316 35223 17697 35223 17695 35223 16316 35224 17695 35224 17833 35224 16321 35225 16323 35225 17848 35225 17848 35226 16323 35226 17846 35226 16511 35227 17844 35227 16509 35227 16509 35228 17844 35228 17837 35228 16509 35229 17837 35229 16508 35229 16508 35230 17837 35230 17838 35230 16508 35231 17838 35231 17839 35231 17839 35232 17838 35232 17840 35232 17711 35233 17817 35233 17848 35233 17848 35234 17817 35234 17841 35234 17848 35235 17841 35235 16321 35235 19998 35236 19999 35236 17844 35236 17844 35237 19999 35237 17842 35237 17844 35238 17842 35238 17833 35238 17833 35239 17842 35239 20002 35239 17833 35240 20002 35240 17843 35240 16511 35241 16513 35241 17844 35241 17844 35242 16513 35242 17845 35242 17844 35243 17845 35243 17846 35243 17846 35244 17845 35244 17847 35244 17846 35245 17847 35245 17848 35245 17848 35246 17847 35246 17849 35246 17848 35247 17849 35247 17835 35247 16622 35248 18528 35248 16614 35248 16614 35249 18528 35249 17854 35249 16614 35250 17854 35250 17850 35250 17851 35251 16611 35251 17852 35251 17852 35252 16611 35252 16612 35252 17852 35253 16612 35253 17854 35253 17854 35254 16612 35254 17853 35254 17854 35255 17853 35255 17850 35255 17851 35256 17852 35256 16609 35256 16609 35257 17852 35257 18523 35257 16609 35258 18523 35258 17855 35258 16606 35259 18524 35259 18525 35259 16606 35260 18525 35260 16619 35260 16619 35261 18525 35261 17856 35261 16619 35262 17856 35262 16618 35262 16618 35263 17856 35263 17857 35263 17857 35264 17856 35264 17858 35264 17857 35265 17858 35265 16617 35265 16617 35266 17858 35266 16616 35266 16616 35267 17858 35267 17859 35267 16616 35268 17859 35268 16615 35268 16674 35269 18557 35269 17862 35269 17862 35270 18557 35270 17861 35270 18541 35271 16670 35271 17860 35271 17860 35272 16668 35272 18541 35272 18541 35273 16668 35273 16672 35273 18541 35274 16672 35274 17861 35274 17861 35275 16672 35275 16673 35275 17861 35276 16673 35276 17862 35276 16670 35277 18541 35277 16671 35277 16671 35278 18541 35278 18542 35278 16671 35279 18542 35279 16667 35279 16677 35280 18562 35280 18546 35280 16677 35281 18546 35281 17863 35281 17863 35282 18546 35282 18545 35282 17863 35283 18545 35283 17864 35283 17864 35284 18545 35284 17865 35284 17865 35285 18545 35285 18544 35285 17865 35286 18544 35286 17866 35286 17866 35287 18544 35287 17867 35287 17867 35288 18544 35288 18547 35288 17867 35289 18547 35289 17868 35289 16759 35290 17869 35290 17870 35290 17870 35291 17869 35291 17871 35291 17870 35292 17871 35292 16749 35292 16749 35293 17871 35293 17872 35293 17872 35294 17871 35294 17874 35294 17872 35295 17874 35295 16747 35295 16744 35296 16745 35296 18566 35296 18566 35297 16745 35297 17873 35297 18566 35298 17873 35298 17874 35298 17874 35299 17873 35299 16748 35299 17874 35300 16748 35300 16747 35300 18570 35301 18569 35301 16758 35301 16758 35302 18569 35302 16757 35302 16757 35303 18569 35303 16755 35303 16755 35304 18569 35304 17875 35304 16755 35305 17875 35305 16754 35305 16754 35306 17875 35306 17876 35306 17876 35307 17875 35307 17878 35307 17876 35308 17878 35308 17877 35308 17877 35309 17878 35309 16753 35309 16753 35310 17878 35310 18578 35310 16753 35311 18578 35311 18577 35311 16830 35312 18594 35312 16822 35312 16822 35313 18594 35313 17879 35313 16822 35314 17879 35314 17880 35314 17880 35315 17879 35315 16821 35315 16821 35316 17879 35316 17883 35316 16821 35317 17883 35317 16820 35317 17881 35318 17882 35318 18589 35318 18589 35319 17882 35319 17884 35319 18589 35320 17884 35320 17883 35320 17883 35321 17884 35321 17885 35321 17883 35322 17885 35322 16820 35322 16817 35323 18606 35323 17886 35323 17886 35324 18606 35324 17889 35324 17886 35325 17889 35325 17887 35325 17887 35326 17889 35326 17888 35326 17888 35327 17889 35327 17890 35327 17888 35328 17890 35328 16825 35328 16825 35329 17890 35329 17891 35329 17891 35330 17890 35330 17892 35330 17891 35331 17892 35331 16823 35331 16823 35332 17892 35332 17893 35332 17893 35333 17892 35333 18599 35333 17893 35334 18599 35334 17894 35334 17895 35335 18610 35335 17896 35335 17896 35336 18610 35336 18609 35336 17896 35337 18609 35337 16903 35337 16903 35338 18609 35338 17897 35338 17897 35339 18609 35339 18608 35339 17897 35340 18608 35340 17901 35340 16897 35341 16900 35341 17898 35341 17898 35342 16900 35342 17899 35342 17898 35343 17899 35343 18608 35343 18608 35344 17899 35344 17900 35344 18608 35345 17900 35345 17901 35345 16908 35346 18611 35346 17902 35346 17902 35347 18611 35347 17903 35347 17902 35348 17903 35348 17904 35348 17904 35349 17903 35349 16906 35349 16906 35350 17903 35350 17906 35350 16906 35351 17906 35351 17905 35351 17905 35352 17906 35352 16904 35352 16904 35353 17906 35353 18613 35353 16904 35354 18613 35354 17907 35354 17907 35355 18613 35355 17908 35355 17908 35356 18613 35356 18619 35356 17908 35357 18619 35357 17909 35357 16980 35358 18632 35358 16979 35358 16979 35359 18632 35359 18631 35359 16979 35360 18631 35360 16978 35360 16978 35361 18631 35361 16977 35361 16977 35362 18631 35362 17910 35362 16977 35363 17910 35363 16974 35363 17911 35364 16976 35364 17912 35364 17912 35365 16976 35365 17913 35365 17912 35366 17913 35366 17910 35366 17910 35367 17913 35367 16975 35367 17910 35368 16975 35368 16974 35368 17914 35369 18637 35369 17915 35369 17915 35370 18637 35370 17916 35370 17915 35371 17916 35371 16986 35371 16986 35372 17916 35372 16985 35372 16985 35373 17916 35373 17917 35373 16985 35374 17917 35374 17918 35374 17918 35375 17917 35375 16984 35375 16984 35376 17917 35376 18638 35376 16984 35377 18638 35377 17919 35377 17919 35378 18638 35378 16983 35378 16983 35379 18638 35379 18641 35379 16983 35380 18641 35380 18642 35380 17083 35381 18671 35381 17920 35381 17920 35382 18671 35382 17921 35382 17920 35383 17921 35383 17081 35383 17081 35384 17921 35384 17922 35384 17922 35385 17921 35385 18651 35385 17922 35386 18651 35386 17078 35386 17923 35387 17068 35387 18652 35387 18652 35388 17068 35388 17070 35388 17070 35389 17924 35389 18652 35389 18652 35390 17924 35390 17925 35390 18652 35391 17925 35391 18651 35391 18651 35392 17925 35392 17080 35392 18651 35393 17080 35393 17078 35393 17076 35394 18653 35394 17926 35394 17926 35395 18653 35395 18655 35395 17926 35396 18655 35396 17927 35396 17927 35397 18655 35397 17928 35397 17928 35398 18655 35398 18654 35398 17928 35399 18654 35399 17074 35399 17074 35400 18654 35400 17929 35400 17929 35401 18654 35401 17930 35401 17929 35402 17930 35402 17073 35402 17073 35403 17930 35403 17931 35403 17931 35404 17930 35404 18661 35404 17931 35405 18661 35405 17072 35405 17153 35406 18683 35406 17152 35406 17152 35407 18683 35407 18675 35407 17152 35408 18675 35408 17151 35408 17933 35409 17934 35409 18675 35409 18675 35410 17934 35410 17150 35410 18675 35411 17150 35411 17151 35411 17145 35412 17147 35412 18676 35412 18676 35413 17147 35413 17932 35413 18676 35414 17932 35414 17933 35414 17933 35415 17932 35415 17149 35415 17933 35416 17149 35416 17934 35416 17146 35417 18677 35417 17935 35417 17935 35418 18677 35418 17936 35418 17935 35419 17936 35419 17158 35419 17158 35420 17936 35420 17937 35420 17937 35421 17936 35421 18681 35421 17937 35422 18681 35422 17157 35422 17157 35423 18681 35423 17155 35423 17155 35424 18681 35424 18684 35424 17155 35425 18684 35425 17156 35425 17156 35426 18684 35426 17154 35426 17154 35427 18684 35427 18688 35427 17154 35428 18688 35428 18689 35428 17233 35429 18719 35429 17938 35429 17938 35430 18719 35430 17939 35430 17938 35431 17939 35431 17232 35431 17232 35432 17939 35432 17940 35432 17232 35433 17940 35433 17229 35433 17229 35434 17940 35434 17231 35434 17231 35435 17940 35435 17942 35435 17231 35436 17942 35436 17941 35436 17941 35437 17942 35437 17943 35437 17943 35438 17942 35438 17944 35438 17943 35439 17944 35439 17228 35439 17945 35440 18726 35440 17946 35440 17946 35441 18726 35441 17948 35441 17946 35442 17948 35442 17947 35442 17947 35443 17948 35443 17949 35443 17949 35444 17948 35444 17951 35444 17949 35445 17951 35445 17950 35445 17950 35446 17951 35446 17235 35446 17235 35447 17951 35447 17952 35447 17235 35448 17952 35448 17236 35448 17953 35449 17954 35449 17952 35449 17952 35450 17954 35450 17234 35450 17952 35451 17234 35451 17236 35451 17301 35452 18743 35452 17300 35452 17300 35453 18743 35453 17956 35453 17300 35454 17956 35454 17299 35454 18728 35455 17955 35455 17956 35455 17956 35456 17955 35456 17957 35456 17956 35457 17957 35457 17299 35457 17958 35458 17959 35458 18748 35458 18748 35459 17959 35459 17296 35459 18748 35460 17296 35460 18728 35460 18728 35461 17296 35461 17298 35461 18728 35462 17298 35462 17955 35462 17294 35463 17960 35463 17961 35463 17961 35464 17960 35464 17962 35464 17961 35465 17962 35465 17307 35465 17307 35466 17962 35466 17964 35466 17964 35467 17962 35467 17963 35467 17964 35468 17963 35468 17305 35468 17305 35469 17963 35469 17965 35469 17965 35470 17963 35470 17966 35470 17965 35471 17966 35471 17967 35471 18733 35472 17302 35472 17966 35472 17966 35473 17302 35473 17303 35473 17966 35474 17303 35474 17967 35474 17381 35475 18752 35475 17375 35475 17375 35476 18752 35476 17968 35476 17375 35477 17968 35477 17374 35477 17374 35478 17968 35478 17372 35478 17372 35479 17968 35479 17969 35479 17969 35480 17968 35480 17971 35480 17969 35481 17971 35481 17970 35481 17970 35482 17971 35482 17972 35482 17972 35483 17971 35483 18773 35483 17972 35484 18773 35484 18772 35484 17368 35485 17974 35485 17973 35485 17973 35486 17974 35486 18754 35486 17973 35487 18754 35487 17378 35487 17378 35488 18754 35488 17975 35488 17975 35489 18754 35489 18753 35489 17975 35490 18753 35490 17376 35490 17376 35491 18753 35491 17976 35491 17976 35492 18753 35492 18751 35492 17976 35493 18751 35493 17977 35493 17977 35494 18751 35494 18757 35494 17977 35495 18757 35495 18763 35495 17440 35496 17978 35496 17434 35496 17434 35497 17978 35497 17980 35497 17434 35498 17980 35498 17979 35498 17979 35499 17980 35499 17433 35499 17433 35500 17980 35500 17981 35500 17981 35501 17980 35501 17982 35501 17981 35502 17982 35502 17432 35502 17432 35503 17982 35503 17984 35503 17984 35504 17982 35504 17983 35504 17984 35505 17983 35505 18790 35505 18775 35506 17986 35506 18791 35506 18791 35507 17986 35507 17439 35507 17439 35508 17986 35508 17985 35508 17985 35509 17986 35509 17988 35509 17985 35510 17988 35510 17987 35510 17987 35511 17988 35511 17435 35511 17435 35512 17988 35512 17989 35512 17435 35513 17989 35513 17436 35513 17436 35514 17989 35514 18781 35514 17436 35515 18781 35515 17442 35515 18001 35516 17990 35516 17991 35516 17991 35517 17990 35517 17992 35517 17991 35518 17992 35518 17519 35518 17519 35519 17992 35519 17993 35519 17993 35520 17992 35520 18792 35520 17993 35521 18792 35521 17518 35521 17518 35522 18792 35522 18793 35522 17518 35523 18793 35523 18802 35523 17994 35524 18794 35524 19522 35524 19522 35525 18794 35525 17995 35525 17995 35526 18794 35526 17996 35526 17996 35527 18794 35527 17999 35527 17996 35528 17999 35528 17997 35528 17997 35529 17999 35529 17998 35529 17998 35530 17999 35530 18000 35530 17998 35531 18000 35531 19570 35531 18000 35532 17990 35532 19570 35532 19570 35533 17990 35533 18001 35533 19570 35534 18001 35534 18003 35534 18001 35535 18002 35535 18003 35535 18003 35536 18002 35536 17520 35536 18003 35537 17520 35537 19572 35537 19572 35538 17520 35538 18004 35538 18006 35539 18796 35539 18008 35539 17500 35540 18005 35540 19306 35540 19306 35541 18005 35541 19308 35541 19308 35542 18005 35542 19309 35542 19309 35543 18005 35543 18006 35543 19309 35544 18006 35544 18007 35544 18007 35545 18006 35545 18008 35545 18007 35546 18008 35546 19305 35546 19305 35547 18008 35547 18009 35547 19305 35548 18009 35548 18010 35548 18010 35549 18009 35549 18795 35549 18010 35550 18795 35550 19314 35550 19314 35551 18795 35551 18011 35551 18011 35552 18795 35552 18810 35552 18011 35553 18810 35553 19316 35553 17504 35554 18798 35554 17501 35554 17501 35555 18798 35555 18797 35555 17501 35556 18797 35556 18012 35556 18012 35557 18797 35557 18013 35557 18013 35558 18797 35558 18014 35558 18013 35559 18014 35559 18015 35559 18015 35560 18014 35560 18796 35560 18015 35561 18796 35561 18006 35561 18779 35562 18016 35562 17498 35562 17498 35563 18016 35563 17496 35563 17496 35564 18016 35564 17492 35564 17492 35565 18016 35565 18017 35565 17492 35566 18017 35566 17493 35566 17493 35567 18017 35567 17495 35567 17495 35568 18017 35568 18774 35568 17495 35569 18774 35569 18018 35569 18018 35570 18774 35570 18777 35570 18018 35571 18777 35571 18786 35571 17491 35572 18019 35572 17490 35572 17490 35573 18019 35573 18776 35573 17484 35574 18020 35574 18776 35574 18776 35575 18020 35575 17487 35575 18776 35576 17487 35576 17490 35576 17484 35577 18776 35577 17485 35577 17485 35578 18776 35578 18021 35578 17485 35579 18021 35579 17486 35579 17486 35580 18021 35580 18778 35580 17486 35581 18778 35581 17479 35581 18759 35582 18023 35582 18022 35582 18022 35583 18023 35583 17427 35583 17427 35584 18023 35584 17422 35584 17422 35585 18023 35585 18756 35585 17422 35586 18756 35586 17423 35586 17423 35587 18756 35587 18024 35587 18024 35588 18756 35588 18750 35588 18024 35589 18750 35589 17425 35589 17425 35590 18750 35590 18749 35590 17425 35591 18749 35591 18025 35591 17429 35592 18027 35592 18026 35592 18026 35593 18027 35593 18028 35593 18026 35594 18028 35594 17419 35594 18029 35595 17417 35595 18028 35595 18028 35596 17417 35596 18030 35596 18028 35597 18030 35597 17419 35597 18029 35598 18028 35598 18031 35598 18031 35599 18028 35599 18755 35599 18031 35600 18755 35600 18032 35600 18032 35601 18755 35601 18033 35601 18032 35602 18033 35602 17416 35602 18737 35603 18034 35603 17354 35603 17354 35604 18034 35604 17361 35604 17361 35605 18034 35605 17362 35605 17362 35606 18034 35606 18732 35606 17362 35607 18732 35607 17363 35607 17363 35608 18732 35608 18036 35608 18036 35609 18732 35609 18035 35609 18036 35610 18035 35610 17364 35610 17364 35611 18035 35611 18727 35611 17364 35612 18727 35612 18037 35612 17367 35613 18731 35613 17358 35613 17358 35614 18731 35614 18039 35614 17358 35615 18039 35615 18038 35615 17357 35616 18040 35616 18039 35616 18039 35617 18040 35617 18041 35617 18039 35618 18041 35618 18038 35618 17357 35619 18039 35619 18042 35619 18042 35620 18039 35620 18729 35620 18042 35621 18729 35621 18043 35621 18043 35622 18729 35622 18730 35622 18043 35623 18730 35623 17355 35623 18706 35624 18714 35624 18044 35624 18706 35625 18044 35625 17293 35625 17293 35626 18044 35626 18705 35626 17293 35627 18705 35627 17291 35627 17291 35628 18705 35628 17289 35628 17289 35629 18705 35629 18704 35629 17289 35630 18704 35630 18045 35630 18045 35631 18704 35631 17290 35631 17290 35632 18704 35632 18701 35632 17290 35633 18701 35633 18717 35633 18718 35634 18703 35634 18046 35634 18046 35635 18703 35635 18049 35635 18046 35636 18049 35636 17287 35636 18048 35637 17285 35637 18049 35637 18049 35638 17285 35638 18047 35638 18049 35639 18047 35639 17287 35639 18048 35640 18049 35640 17286 35640 17286 35641 18049 35641 18702 35641 17286 35642 18702 35642 17284 35642 17284 35643 18702 35643 18723 35643 17284 35644 18723 35644 17281 35644 18685 35645 18682 35645 18050 35645 18685 35646 18050 35646 18051 35646 18051 35647 18050 35647 18052 35647 18051 35648 18052 35648 17223 35648 17223 35649 18052 35649 18053 35649 18053 35650 18052 35650 18680 35650 18053 35651 18680 35651 18054 35651 18054 35652 18680 35652 18055 35652 18055 35653 18680 35653 18056 35653 18055 35654 18056 35654 17227 35654 18694 35655 18679 35655 18057 35655 18057 35656 18679 35656 18678 35656 18057 35657 18678 35657 17220 35657 18059 35658 18058 35658 18678 35658 18678 35659 18058 35659 17219 35659 18678 35660 17219 35660 17220 35660 18059 35661 18678 35661 18060 35661 18060 35662 18678 35662 18061 35662 18060 35663 18061 35663 17218 35663 17218 35664 18061 35664 18700 35664 17218 35665 18700 35665 17213 35665 18062 35666 18663 35666 18650 35666 18062 35667 18650 35667 18063 35667 18063 35668 18650 35668 18064 35668 18063 35669 18064 35669 17130 35669 17130 35670 18064 35670 17131 35670 17131 35671 18064 35671 18066 35671 17131 35672 18066 35672 17132 35672 17132 35673 18066 35673 18065 35673 18065 35674 18066 35674 18657 35674 18065 35675 18657 35675 18067 35675 18068 35676 17140 35676 18656 35676 18656 35677 17140 35677 17142 35677 18656 35678 17142 35678 18069 35678 17134 35679 17133 35679 18070 35679 18070 35680 17133 35680 17137 35680 18070 35681 17137 35681 18656 35681 18656 35682 17137 35682 17139 35682 18656 35683 17139 35683 18068 35683 17134 35684 18070 35684 17136 35684 17136 35685 18070 35685 18071 35685 17136 35686 18071 35686 18072 35686 18072 35687 18071 35687 18669 35687 18072 35688 18669 35688 17127 35688 18636 35689 18073 35689 18639 35689 18639 35690 18073 35690 18074 35690 18074 35691 18073 35691 18075 35691 18075 35692 18073 35692 18634 35692 18075 35693 18634 35693 17062 35693 17062 35694 18634 35694 17064 35694 17064 35695 18634 35695 18076 35695 17064 35696 18076 35696 17060 35696 17060 35697 18076 35697 18077 35697 18077 35698 18076 35698 18635 35698 18077 35699 18635 35699 17067 35699 18078 35700 18080 35700 18079 35700 18079 35701 18080 35701 18633 35701 18079 35702 18633 35702 18081 35702 18082 35703 18083 35703 18633 35703 18633 35704 18083 35704 17057 35704 18633 35705 17057 35705 18081 35705 18082 35706 18633 35706 18084 35706 18084 35707 18633 35707 18085 35707 18084 35708 18085 35708 17059 35708 17059 35709 18085 35709 18649 35709 17059 35710 18649 35710 17056 35710 18607 35711 18086 35711 16961 35711 16961 35712 18086 35712 16971 35712 16971 35713 18086 35713 18087 35713 18087 35714 18086 35714 18088 35714 18087 35715 18088 35715 16968 35715 16968 35716 18088 35716 16970 35716 16970 35717 18088 35717 18089 35717 16970 35718 18089 35718 18090 35718 18090 35719 18089 35719 18091 35719 18091 35720 18089 35720 18623 35720 18091 35721 18623 35721 18092 35721 16967 35722 18093 35722 16966 35722 16966 35723 18093 35723 18094 35723 16966 35724 18094 35724 18095 35724 18096 35725 16963 35725 18094 35725 18094 35726 16963 35726 16962 35726 18094 35727 16962 35727 18095 35727 18096 35728 18094 35728 18097 35728 18097 35729 18094 35729 18612 35729 18097 35730 18612 35730 16965 35730 16965 35731 18612 35731 18629 35731 16965 35732 18629 35732 18098 35732 18593 35733 18099 35733 18100 35733 18100 35734 18099 35734 16895 35734 16895 35735 18099 35735 16891 35735 16891 35736 18099 35736 18101 35736 16891 35737 18101 35737 16892 35737 16892 35738 18101 35738 18103 35738 18103 35739 18101 35739 18102 35739 18103 35740 18102 35740 18104 35740 18104 35741 18102 35741 18105 35741 18105 35742 18102 35742 18592 35742 18105 35743 18592 35743 18106 35743 16889 35744 18603 35744 18107 35744 18107 35745 18603 35745 16887 35745 16887 35746 18603 35746 18108 35746 18108 35747 18603 35747 18109 35747 18108 35748 18109 35748 16885 35748 16885 35749 18109 35749 18590 35749 16885 35750 18590 35750 16884 35750 16884 35751 18590 35751 18110 35751 18110 35752 18590 35752 18591 35752 18110 35753 18591 35753 16878 35753 18581 35754 18563 35754 18111 35754 18111 35755 18563 35755 18112 35755 18112 35756 18563 35756 18113 35756 18113 35757 18563 35757 18571 35757 18113 35758 18571 35758 16809 35758 16809 35759 18571 35759 16811 35759 16811 35760 18571 35760 18565 35760 16811 35761 18565 35761 16808 35761 16808 35762 18565 35762 16807 35762 16807 35763 18565 35763 18564 35763 16807 35764 18564 35764 18114 35764 16802 35765 18116 35765 18568 35765 16806 35766 16816 35766 18115 35766 18568 35767 18116 35767 18115 35767 18115 35768 18116 35768 18117 35768 18115 35769 18117 35769 16806 35769 16802 35770 18568 35770 18118 35770 18118 35771 18568 35771 18567 35771 18118 35772 18567 35772 16804 35772 16804 35773 18567 35773 18572 35773 16804 35774 18572 35774 18584 35774 18551 35775 18120 35775 18119 35775 18119 35776 18120 35776 16741 35776 16741 35777 18120 35777 16738 35777 16738 35778 18120 35778 18121 35778 16738 35779 18121 35779 16735 35779 16735 35780 18121 35780 18122 35780 18122 35781 18121 35781 18123 35781 18122 35782 18123 35782 16734 35782 16734 35783 18123 35783 18543 35783 16734 35784 18543 35784 16743 35784 18554 35785 18555 35785 18124 35785 18124 35786 18555 35786 18127 35786 18125 35787 18126 35787 18127 35787 18127 35788 18126 35788 18128 35788 18127 35789 18128 35789 18124 35789 18129 35790 18559 35790 16725 35790 16725 35791 18130 35791 18129 35791 18129 35792 18130 35792 18131 35792 18129 35793 18131 35793 18127 35793 18127 35794 18131 35794 16730 35794 18127 35795 16730 35795 18125 35795 18540 35796 18132 35796 16666 35796 16666 35797 18132 35797 16665 35797 16665 35798 18132 35798 18133 35798 18133 35799 18132 35799 18527 35799 18133 35800 18527 35800 16664 35800 16664 35801 18527 35801 18134 35801 18134 35802 18527 35802 18522 35802 18134 35803 18522 35803 16663 35803 16663 35804 18522 35804 18521 35804 16663 35805 18521 35805 16655 35805 16656 35806 18135 35806 18136 35806 18136 35807 18135 35807 18137 35807 18136 35808 18137 35808 18138 35808 18138 35809 18137 35809 18139 35809 18139 35810 18137 35810 18526 35810 18139 35811 18526 35811 18140 35811 18530 35812 16640 35812 18526 35812 18526 35813 16640 35813 16639 35813 18526 35814 16639 35814 18140 35814 16683 35815 16678 35815 19710 35815 19710 35816 16631 35816 18141 35816 16683 35817 19710 35817 18142 35817 18142 35818 19710 35818 18141 35818 18142 35819 18141 35819 18143 35819 16684 35820 18145 35820 18144 35820 18144 35821 18145 35821 16760 35821 16760 35822 19692 35822 18144 35822 18144 35823 19692 35823 18146 35823 18144 35824 18146 35824 19693 35824 16832 35825 19683 35825 19685 35825 18281 35826 16832 35826 18147 35826 18147 35827 16832 35827 19685 35827 18147 35828 19685 35828 18148 35828 18148 35829 19685 35829 18149 35829 18150 35830 16909 35830 18151 35830 18151 35831 16831 35831 16835 35831 18150 35832 18151 35832 18152 35832 18152 35833 18151 35833 16835 35833 18152 35834 16835 35834 18153 35834 18155 35835 16994 35835 19674 35835 19674 35836 16912 35836 18154 35836 18155 35837 19674 35837 18156 35837 18156 35838 19674 35838 18154 35838 18156 35839 18154 35839 16954 35839 18159 35840 17094 35840 18157 35840 18157 35841 18158 35841 18160 35841 18159 35842 18157 35842 17121 35842 17121 35843 18157 35843 18160 35843 17121 35844 18160 35844 16996 35844 17163 35845 17164 35845 18163 35845 18162 35846 18371 35846 18161 35846 18161 35847 17163 35847 18162 35847 18162 35848 17163 35848 18163 35848 18162 35849 18163 35849 17089 35849 17089 35850 18163 35850 17086 35850 18165 35851 17245 35851 18164 35851 18409 35852 18165 35852 18410 35852 18410 35853 18165 35853 18164 35853 18410 35854 18164 35854 18166 35854 18166 35855 18164 35855 17161 35855 17310 35856 18167 35856 19597 35856 18169 35857 18455 35857 17310 35857 19597 35858 19595 35858 18168 35858 17310 35859 19597 35859 18169 35859 18169 35860 19597 35860 18168 35860 18169 35861 18168 35861 18456 35861 18175 35862 17314 35862 18174 35862 18170 35863 18171 35863 18172 35863 18170 35864 18172 35864 18174 35864 18174 35865 18172 35865 18173 35865 18174 35866 18173 35866 18175 35866 18177 35867 18176 35867 17386 35867 18495 35868 18496 35868 17386 35868 17386 35869 18496 35869 17445 35869 17386 35870 17445 35870 18177 35870 18177 35871 17445 35871 17446 35871 18178 35872 17448 35872 18179 35872 19575 35873 18178 35873 19574 35873 19574 35874 18178 35874 18179 35874 19574 35875 18179 35875 18805 35875 18805 35876 18179 35876 18806 35876 16657 35877 16658 35877 18216 35877 18216 35878 16658 35878 19377 35878 18216 35879 19377 35879 18180 35879 18180 35880 19377 35880 18181 35880 18180 35881 18181 35881 18182 35881 18183 35882 19428 35882 18186 35882 18183 35883 18186 35883 18184 35883 16796 35884 18185 35884 18186 35884 18186 35885 18185 35885 18187 35885 18186 35886 18187 35886 18184 35886 16797 35887 16798 35887 18188 35887 16776 35888 16797 35888 16841 35888 16841 35889 16797 35889 18188 35889 16841 35890 18188 35890 16876 35890 16876 35891 18188 35891 19429 35891 16877 35892 18189 35892 18190 35892 16858 35893 16877 35893 18191 35893 18191 35894 16877 35894 18190 35894 18191 35895 18190 35895 18192 35895 18192 35896 18190 35896 16955 35896 18194 35897 16959 35897 18193 35897 18308 35898 18194 35898 18195 35898 18195 35899 18194 35899 18193 35899 18195 35900 18193 35900 17049 35900 17049 35901 18193 35901 19445 35901 17050 35902 17051 35902 19446 35902 18196 35903 17050 35903 17122 35903 17122 35904 17050 35904 19446 35904 17122 35905 19446 35905 17123 35905 17123 35906 19446 35906 17128 35906 19281 35907 17208 35907 17210 35907 17124 35908 19281 35908 18197 35908 18197 35909 19281 35909 17210 35909 18197 35910 17210 35910 18385 35910 18385 35911 17210 35911 17211 35911 17212 35912 18198 35912 19286 35912 19286 35913 17282 35913 17276 35913 17212 35914 19286 35914 17190 35914 17190 35915 19286 35915 17276 35915 17190 35916 17276 35916 18199 35916 18203 35917 17278 35917 18200 35917 18200 35918 18201 35918 18202 35918 18203 35919 18200 35919 18204 35919 18204 35920 18200 35920 18202 35920 18204 35921 18202 35921 18427 35921 17348 35922 18205 35922 18206 35922 18206 35923 17413 35923 17406 35923 17348 35924 18206 35924 17330 35924 17330 35925 18206 35925 17406 35925 17330 35926 17406 35926 18207 35926 18208 35927 18209 35927 18210 35927 17411 35928 18208 35928 17409 35928 17409 35929 18208 35929 18210 35929 17409 35930 18210 35930 17408 35930 17408 35931 18210 35931 18479 35931 19317 35932 18211 35932 18212 35932 18212 35933 18211 35933 18213 35933 18212 35934 18213 35934 18214 35934 18214 35935 18213 35935 18215 35935 18214 35936 18215 35936 18804 35936 16657 35937 18216 35937 16687 35937 16657 35938 16687 35938 18218 35938 18218 35939 16687 35939 16686 35939 18218 35940 16686 35940 18217 35940 18217 35941 18219 35941 18218 35941 18218 35942 18219 35942 18220 35942 18218 35943 18220 35943 18221 35943 18221 35944 18220 35944 16694 35944 16694 35945 16693 35945 18221 35945 18221 35946 16693 35946 18222 35946 18221 35947 18222 35947 18223 35947 18223 35948 18222 35948 18224 35948 18223 35949 18224 35949 16644 35949 16644 35950 18224 35950 16645 35950 16645 35951 18224 35951 16689 35951 16645 35952 16689 35952 18227 35952 18142 35953 18143 35953 18225 35953 18142 35954 18225 35954 16696 35954 16689 35955 18226 35955 18227 35955 18227 35956 18226 35956 18228 35956 18227 35957 18228 35957 18229 35957 18229 35958 18228 35958 18230 35958 18229 35959 18230 35959 16651 35959 16651 35960 18230 35960 16696 35960 16651 35961 16696 35961 16648 35961 16648 35962 16696 35962 18225 35962 18185 35963 16796 35963 18231 35963 18185 35964 18231 35964 18232 35964 18231 35965 18233 35965 18232 35965 18232 35966 18233 35966 18234 35966 18232 35967 18234 35967 16702 35967 18234 35968 16765 35968 16702 35968 16702 35969 16765 35969 18235 35969 16702 35970 18235 35970 16703 35970 18236 35971 16707 35971 18238 35971 18238 35972 16707 35972 18237 35972 18238 35973 18237 35973 18239 35973 18239 35974 18237 35974 16705 35974 18239 35975 16705 35975 16704 35975 18235 35976 18240 35976 16703 35976 16703 35977 18240 35977 16767 35977 16703 35978 16767 35978 16704 35978 16704 35979 16767 35979 18241 35979 16704 35980 18241 35980 18239 35980 16714 35981 16713 35981 18247 35981 18247 35982 16713 35982 16711 35982 18247 35983 16711 35983 18243 35983 16711 35984 18242 35984 18243 35984 18243 35985 18242 35985 18244 35985 18243 35986 18244 35986 18245 35986 18244 35987 16710 35987 18245 35987 18245 35988 16710 35988 16699 35988 18245 35989 16699 35989 18238 35989 18238 35990 16699 35990 18246 35990 18238 35991 18246 35991 18236 35991 18247 35992 18248 35992 16714 35992 16714 35993 18248 35993 18249 35993 16714 35994 18249 35994 18250 35994 18250 35995 18249 35995 16772 35995 18250 35996 16772 35996 16716 35996 16716 35997 16772 35997 18251 35997 16716 35998 18251 35998 16717 35998 16717 35999 18251 35999 16719 35999 18145 36000 16684 36000 18257 36000 18145 36001 18257 36001 16773 36001 18251 36002 18252 36002 16719 36002 16719 36003 18252 36003 16774 36003 16719 36004 16774 36004 18254 36004 18254 36005 16774 36005 18253 36005 18254 36006 18253 36006 16721 36006 16721 36007 18253 36007 18255 36007 16721 36008 18255 36008 18256 36008 18256 36009 18255 36009 16773 36009 18256 36010 16773 36010 16722 36010 16722 36011 16773 36011 18257 36011 18259 36012 16775 36012 16839 36012 16839 36013 16775 36013 18258 36013 18258 36014 16775 36014 16776 36014 18258 36015 16776 36015 16841 36015 18259 36016 16839 36016 18260 36016 18260 36017 16839 36017 16837 36017 18260 36018 16837 36018 16778 36018 16778 36019 16837 36019 18261 36019 16778 36020 18261 36020 16779 36020 16779 36021 18261 36021 16842 36021 16779 36022 16842 36022 18263 36022 16842 36023 18262 36023 18263 36023 18263 36024 18262 36024 16845 36024 18263 36025 16845 36025 18265 36025 18265 36026 16845 36026 18264 36026 18264 36027 16843 36027 18265 36027 18265 36028 16843 36028 18266 36028 18265 36029 18266 36029 16781 36029 16781 36030 18266 36030 16780 36030 16780 36031 18266 36031 18268 36031 16780 36032 18268 36032 18267 36032 18267 36033 18268 36033 16784 36033 16784 36034 18268 36034 18269 36034 16784 36035 18269 36035 18270 36035 18270 36036 18269 36036 18271 36036 18270 36037 18271 36037 18273 36037 18273 36038 18271 36038 18272 36038 18273 36039 18272 36039 16783 36039 16783 36040 18272 36040 16846 36040 16783 36041 16846 36041 16786 36041 16786 36042 16846 36042 18274 36042 16786 36043 18274 36043 16792 36043 16792 36044 18274 36044 16851 36044 16792 36045 16851 36045 16790 36045 16790 36046 16851 36046 16849 36046 16790 36047 16849 36047 16788 36047 16788 36048 16849 36048 18276 36048 16788 36049 18276 36049 18275 36049 18275 36050 18276 36050 16854 36050 18275 36051 16854 36051 18277 36051 18277 36052 16854 36052 16853 36052 18277 36053 16853 36053 18278 36053 18278 36054 16853 36054 18279 36054 18278 36055 18279 36055 16794 36055 16794 36056 18279 36056 16856 36056 16794 36057 16856 36057 16795 36057 16795 36058 16856 36058 18280 36058 18280 36059 16856 36059 18281 36059 18280 36060 18281 36060 18147 36060 16858 36061 18191 36061 16917 36061 16858 36062 16917 36062 16857 36062 16857 36063 16917 36063 16916 36063 16857 36064 16916 36064 18282 36064 18282 36065 16916 36065 18283 36065 18282 36066 18283 36066 16866 36066 16866 36067 18283 36067 16919 36067 16866 36068 16919 36068 16864 36068 16864 36069 16919 36069 18284 36069 18284 36070 16919 36070 16923 36070 18284 36071 16923 36071 16861 36071 16923 36072 16922 36072 16861 36072 16861 36073 16922 36073 18285 36073 16861 36074 18285 36074 18286 36074 18285 36075 16921 36075 18286 36075 18286 36076 16921 36076 18287 36076 18286 36077 18287 36077 18289 36077 16927 36078 16926 36078 18288 36078 18287 36079 16920 36079 18289 36079 18289 36080 16920 36080 16929 36080 18289 36081 16929 36081 18290 36081 18290 36082 16929 36082 16927 36082 18290 36083 16927 36083 18291 36083 18291 36084 16927 36084 18288 36084 18296 36085 18292 36085 16925 36085 16925 36086 18292 36086 18293 36086 16925 36087 18293 36087 16926 36087 16926 36088 18293 36088 16868 36088 16926 36089 16868 36089 18288 36089 16925 36090 18294 36090 18296 36090 18296 36091 18294 36091 18295 36091 18296 36092 18295 36092 18297 36092 18297 36093 18295 36093 16869 36093 18295 36094 18298 36094 16869 36094 16869 36095 18298 36095 18299 36095 16869 36096 18299 36096 16871 36096 16871 36097 18299 36097 18300 36097 18299 36098 16932 36098 18300 36098 18300 36099 16932 36099 18301 36099 18300 36100 18301 36100 18302 36100 18302 36101 18301 36101 16931 36101 18302 36102 16931 36102 16872 36102 16931 36103 18303 36103 16872 36103 16872 36104 18303 36104 18305 36104 16872 36105 18305 36105 18304 36105 18304 36106 18305 36106 16874 36106 18305 36107 18306 36107 16874 36107 16874 36108 18306 36108 18307 36108 16874 36109 18307 36109 16875 36109 16875 36110 18307 36110 18152 36110 16875 36111 18152 36111 18153 36111 18324 36112 18322 36112 18325 36112 16940 36113 18328 36113 18330 36113 18308 36114 18195 36114 17000 36114 18308 36115 17000 36115 18309 36115 17000 36116 16999 36116 18309 36116 18309 36117 16999 36117 18329 36117 18309 36118 18329 36118 18328 36118 16940 36119 18330 36119 16939 36119 16939 36120 18330 36120 18310 36120 18310 36121 18330 36121 18313 36121 18310 36122 18313 36122 16941 36122 18313 36123 16945 36123 18311 36123 18311 36124 16942 36124 18313 36124 18313 36125 16942 36125 18312 36125 18313 36126 18312 36126 16941 36126 18313 36127 17009 36127 17006 36127 18313 36128 17006 36128 16945 36128 16945 36129 17006 36129 17005 36129 16945 36130 17005 36130 18314 36130 18314 36131 18315 36131 16945 36131 16945 36132 18315 36132 17004 36132 16945 36133 17004 36133 16946 36133 16946 36134 17004 36134 17014 36134 16946 36135 17014 36135 18316 36135 18319 36136 16950 36136 18317 36136 18317 36137 16950 36137 16947 36137 18317 36138 16947 36138 18318 36138 18318 36139 16947 36139 16946 36139 18318 36140 16946 36140 17013 36140 17013 36141 16946 36141 18316 36141 18317 36142 17011 36142 18319 36142 18319 36143 17011 36143 17015 36143 18319 36144 17015 36144 18320 36144 18320 36145 17015 36145 18321 36145 18325 36146 18322 36146 17016 36146 17016 36147 18322 36147 18323 36147 17016 36148 18323 36148 18321 36148 18321 36149 18323 36149 16951 36149 18321 36150 16951 36150 18320 36150 18324 36151 18325 36151 18326 36151 18326 36152 18325 36152 17017 36152 18326 36153 17017 36153 18327 36153 18327 36154 17017 36154 18156 36154 18327 36155 18156 36155 16954 36155 17001 36156 18333 36156 18313 36156 17001 36157 18313 36157 18332 36157 18328 36158 18329 36158 18330 36158 18330 36159 18329 36159 18331 36159 18330 36160 18331 36160 18313 36160 18313 36161 18331 36161 17003 36161 18313 36162 17003 36162 18332 36162 18333 36163 17010 36163 18313 36163 18313 36164 17010 36164 18334 36164 18313 36165 18334 36165 17009 36165 18354 36166 18335 36166 17122 36166 17122 36167 18335 36167 17020 36167 17122 36168 17020 36168 18196 36168 17023 36169 17022 36169 18354 36169 18354 36170 17022 36170 17021 36170 18354 36171 17021 36171 18335 36171 18336 36172 17027 36172 18355 36172 18355 36173 17027 36173 17025 36173 18355 36174 17025 36174 18354 36174 18354 36175 17025 36175 18337 36175 18354 36176 18337 36176 17023 36176 18341 36177 18339 36177 18353 36177 18338 36178 17029 36178 18355 36178 18355 36179 17029 36179 17028 36179 18355 36180 17028 36180 18336 36180 18353 36181 18339 36181 18355 36181 18355 36182 18339 36182 17031 36182 18355 36183 17031 36183 18338 36183 17035 36184 17034 36184 18353 36184 18353 36185 17034 36185 18340 36185 18353 36186 18340 36186 18341 36186 18342 36187 18343 36187 18344 36187 18344 36188 18343 36188 18345 36188 18345 36189 18346 36189 18344 36189 18344 36190 18346 36190 18347 36190 18344 36191 18347 36191 18353 36191 18353 36192 18347 36192 17036 36192 18353 36193 17036 36193 17035 36193 18352 36194 17042 36194 17041 36194 18352 36195 17041 36195 18344 36195 18344 36196 17041 36196 17039 36196 18344 36197 17039 36197 18342 36197 18350 36198 18348 36198 18352 36198 18352 36199 18348 36199 17043 36199 18352 36200 17043 36200 17042 36200 18351 36201 18349 36201 18350 36201 18350 36202 18349 36202 17045 36202 18350 36203 17045 36203 18348 36203 17121 36204 16996 36204 17048 36204 17048 36205 18351 36205 17121 36205 17121 36206 18351 36206 18350 36206 17121 36207 18350 36207 17118 36207 17118 36208 18350 36208 18352 36208 17118 36209 18352 36209 17117 36209 17117 36210 18352 36210 17115 36210 17115 36211 18352 36211 18344 36211 17115 36212 18344 36212 17113 36212 17113 36213 18344 36213 18353 36213 17113 36214 18353 36214 17112 36214 17122 36215 17106 36215 18354 36215 18354 36216 17106 36216 17110 36216 18354 36217 17110 36217 18355 36217 18355 36218 17110 36218 17108 36218 18355 36219 17108 36219 18353 36219 18353 36220 17108 36220 18356 36220 18353 36221 18356 36221 17112 36221 18366 36222 18367 36222 18162 36222 18385 36223 18357 36223 17095 36223 17095 36224 18357 36224 18358 36224 18358 36225 18357 36225 17097 36225 17097 36226 18357 36226 18360 36226 17097 36227 18360 36227 17098 36227 17098 36228 18360 36228 18359 36228 18359 36229 18360 36229 18381 36229 18359 36230 18381 36230 18361 36230 18361 36231 18381 36231 18362 36231 18362 36232 18381 36232 18375 36232 18362 36233 18375 36233 17101 36233 17101 36234 18375 36234 18363 36234 18363 36235 18375 36235 18372 36235 18363 36236 18372 36236 17103 36236 18364 36237 18365 36237 18372 36237 18372 36238 18365 36238 18368 36238 18366 36239 17103 36239 18367 36239 18367 36240 17103 36240 18372 36240 18367 36241 18372 36241 17186 36241 17186 36242 18372 36242 18368 36242 17186 36243 18369 36243 18367 36243 18367 36244 18369 36244 17187 36244 18367 36245 17187 36245 18162 36245 18162 36246 17187 36246 18370 36246 18162 36247 18370 36247 18371 36247 18375 36248 17182 36248 18373 36248 18375 36249 18373 36249 18372 36249 18372 36250 18373 36250 17184 36250 18372 36251 17184 36251 18364 36251 17178 36252 17179 36252 18381 36252 18381 36253 17179 36253 17180 36253 17180 36254 18374 36254 18381 36254 18381 36255 18374 36255 17183 36255 18381 36256 17183 36256 18375 36256 18375 36257 17183 36257 18376 36257 18375 36258 18376 36258 17182 36258 17171 36259 17169 36259 18360 36259 18360 36260 17169 36260 17170 36260 18360 36261 17170 36261 18377 36261 18377 36262 18378 36262 18360 36262 18360 36263 18378 36263 18379 36263 18360 36264 18379 36264 18381 36264 18381 36265 18379 36265 18380 36265 18381 36266 18380 36266 17178 36266 17174 36267 18382 36267 18357 36267 18357 36268 18382 36268 18383 36268 18357 36269 18383 36269 18360 36269 18360 36270 18383 36270 18384 36270 18360 36271 18384 36271 17171 36271 17211 36272 17167 36272 18385 36272 18385 36273 17167 36273 17166 36273 18385 36274 17166 36274 18357 36274 18357 36275 17166 36275 17176 36275 18357 36276 17176 36276 17174 36276 18421 36277 18391 36277 18426 36277 18386 36278 18425 36278 17192 36278 17190 36279 18199 36279 17191 36279 17191 36280 18199 36280 18387 36280 17191 36281 18387 36281 18386 36281 18386 36282 18387 36282 18422 36282 18386 36283 18422 36283 18425 36283 18394 36284 17197 36284 18426 36284 18426 36285 17197 36285 17195 36285 17195 36286 18388 36286 18426 36286 18426 36287 18388 36287 17194 36287 18426 36288 17194 36288 18425 36288 18425 36289 17194 36289 18389 36289 18425 36290 18389 36290 17192 36290 18395 36291 18390 36291 18391 36291 18391 36292 18390 36292 18392 36292 18391 36293 18392 36293 18426 36293 18426 36294 18392 36294 18393 36294 18426 36295 18393 36295 18394 36295 18395 36296 18391 36296 18396 36296 18396 36297 18391 36297 18397 36297 18396 36298 18397 36298 18398 36298 18398 36299 18397 36299 18400 36299 18398 36300 18400 36300 18399 36300 18400 36301 18401 36301 18399 36301 18399 36302 18401 36302 17257 36302 18399 36303 17257 36303 17199 36303 17199 36304 17257 36304 17259 36304 18403 36305 18418 36305 18402 36305 18402 36306 17202 36306 18403 36306 18403 36307 17202 36307 18404 36307 18403 36308 18404 36308 18405 36308 18405 36309 18404 36309 17204 36309 17204 36310 18406 36310 18405 36310 18405 36311 18406 36311 18407 36311 18405 36312 18407 36312 17259 36312 17259 36313 18407 36313 18408 36313 17259 36314 18408 36314 17199 36314 18409 36315 18410 36315 18411 36315 18409 36316 18411 36316 18412 36316 18412 36317 18411 36317 18413 36317 18412 36318 18413 36318 18414 36318 18414 36319 18413 36319 18416 36319 18414 36320 18416 36320 18415 36320 18415 36321 18416 36321 17206 36321 18415 36322 17206 36322 18418 36322 18418 36323 17206 36323 18417 36323 18418 36324 18417 36324 18402 36324 18419 36325 17255 36325 18426 36325 18426 36326 17255 36326 18420 36326 18426 36327 18420 36327 18421 36327 18422 36328 18423 36328 18425 36328 18425 36329 18423 36329 18424 36329 18425 36330 18424 36330 17251 36330 17251 36331 17249 36331 18425 36331 18425 36332 17249 36332 17248 36332 18425 36333 17248 36333 18426 36333 18426 36334 17248 36334 17256 36334 18426 36335 17256 36335 18419 36335 17264 36336 17262 36336 18430 36336 17261 36337 18204 36337 18427 36337 18427 36338 17316 36338 17261 36338 17261 36339 17316 36339 17315 36339 17261 36340 17315 36340 17262 36340 17262 36341 17315 36341 18428 36341 17262 36342 18428 36342 18430 36342 17318 36343 18429 36343 18435 36343 17264 36344 18430 36344 18435 36344 18435 36345 18430 36345 18431 36345 18435 36346 18431 36346 17318 36346 18432 36347 18436 36347 18433 36347 18433 36348 18436 36348 18434 36348 18429 36349 18434 36349 18435 36349 18435 36350 18434 36350 18436 36350 18435 36351 18436 36351 18437 36351 18437 36352 18436 36352 18438 36352 18438 36353 18436 36353 17268 36353 17268 36354 18436 36354 18439 36354 17268 36355 18439 36355 18442 36355 18451 36356 18440 36356 18449 36356 18449 36357 18440 36357 18448 36357 18439 36358 18441 36358 18442 36358 18442 36359 18441 36359 17321 36359 18442 36360 17321 36360 18443 36360 18443 36361 17321 36361 18444 36361 18443 36362 18444 36362 18445 36362 18445 36363 18444 36363 17320 36363 18445 36364 17320 36364 17269 36364 17269 36365 17320 36365 18446 36365 17269 36366 18446 36366 17270 36366 17270 36367 18446 36367 17324 36367 17270 36368 17324 36368 17272 36368 17272 36369 17324 36369 18447 36369 17272 36370 18447 36370 18448 36370 18448 36371 18447 36371 17326 36371 18448 36372 17326 36372 18449 36372 18453 36373 18454 36373 18450 36373 18450 36374 18454 36374 18452 36374 18450 36375 18452 36375 18451 36375 18451 36376 18452 36376 17273 36376 18451 36377 17273 36377 18440 36377 18453 36378 18455 36378 18454 36378 18454 36379 18455 36379 18169 36379 18454 36380 18169 36380 17275 36380 17275 36381 18169 36381 18456 36381 18432 36382 17323 36382 18436 36382 18436 36383 17323 36383 18457 36383 18436 36384 18457 36384 18439 36384 18458 36385 17334 36385 17332 36385 18458 36386 17332 36386 18207 36386 18207 36387 17332 36387 18459 36387 18207 36388 18459 36388 17330 36388 17334 36389 18458 36389 18460 36389 18460 36390 18458 36390 18462 36390 18460 36391 18462 36391 18461 36391 18461 36392 18462 36392 18463 36392 18461 36393 18463 36393 18464 36393 18464 36394 18463 36394 18465 36394 18464 36395 18465 36395 18466 36395 18466 36396 18465 36396 17388 36396 18466 36397 17388 36397 17338 36397 17338 36398 17388 36398 17389 36398 17338 36399 17389 36399 18467 36399 18468 36400 17339 36400 18469 36400 18468 36401 18469 36401 17389 36401 17389 36402 18469 36402 17333 36402 17389 36403 17333 36403 18467 36403 18476 36404 17342 36404 18468 36404 18468 36405 17342 36405 17341 36405 18468 36406 17341 36406 17339 36406 18174 36407 17314 36407 17346 36407 18174 36408 17346 36408 18470 36408 18470 36409 17346 36409 18471 36409 18470 36410 18471 36410 17394 36410 17394 36411 18471 36411 18472 36411 17394 36412 18472 36412 17393 36412 17393 36413 18472 36413 18473 36413 17393 36414 18473 36414 18474 36414 18474 36415 18473 36415 18475 36415 18474 36416 18475 36416 18476 36416 18476 36417 18475 36417 17343 36417 18476 36418 17343 36418 17342 36418 18485 36419 17398 36419 17449 36419 17449 36420 17398 36420 17396 36420 17449 36421 17396 36421 18477 36421 18477 36422 17396 36422 18478 36422 18478 36423 17396 36423 17408 36423 18478 36424 17408 36424 18479 36424 18480 36425 17452 36425 18481 36425 18481 36426 18482 36426 18480 36426 18480 36427 18482 36427 18483 36427 18480 36428 18483 36428 18484 36428 18484 36429 18483 36429 18486 36429 18484 36430 18486 36430 18485 36430 18485 36431 18486 36431 18487 36431 18485 36432 18487 36432 17398 36432 17452 36433 17459 36433 18481 36433 18481 36434 17459 36434 17457 36434 18481 36435 17457 36435 18490 36435 18488 36436 18489 36436 18494 36436 17457 36437 17456 36437 18490 36437 18490 36438 17456 36438 17455 36438 18490 36439 17455 36439 17399 36439 17399 36440 17455 36440 17453 36440 17399 36441 17453 36441 18489 36441 18489 36442 17453 36442 18491 36442 18489 36443 18491 36443 18494 36443 18504 36444 18492 36444 17460 36444 17460 36445 18492 36445 17401 36445 17460 36446 17401 36446 18493 36446 18493 36447 17401 36447 18488 36447 18493 36448 18488 36448 17461 36448 17461 36449 18488 36449 18494 36449 18496 36450 18495 36450 18497 36450 18496 36451 18497 36451 18498 36451 18498 36452 18497 36452 18499 36452 18498 36453 18499 36453 18500 36453 18500 36454 18499 36454 18501 36454 18500 36455 18501 36455 18502 36455 18502 36456 18501 36456 17403 36456 18502 36457 17403 36457 17463 36457 17463 36458 17403 36458 18503 36458 17463 36459 18503 36459 18504 36459 18504 36460 18503 36460 17402 36460 18504 36461 17402 36461 18492 36461 18214 36462 18804 36462 18803 36462 18179 36463 17448 36463 18505 36463 18179 36464 18505 36464 18806 36464 18806 36465 18505 36465 18506 36465 18806 36466 18506 36466 18807 36466 18506 36467 18507 36467 18807 36467 18807 36468 18507 36468 18508 36468 18807 36469 18508 36469 18511 36469 18511 36470 18508 36470 17473 36470 18511 36471 17473 36471 18509 36471 18509 36472 18510 36472 18511 36472 18511 36473 18510 36473 18512 36473 18511 36474 18512 36474 18513 36474 18513 36475 18512 36475 17472 36475 18513 36476 17472 36476 18514 36476 17472 36477 18515 36477 18514 36477 18514 36478 18515 36478 18516 36478 18514 36479 18516 36479 18809 36479 18809 36480 18516 36480 18517 36480 18809 36481 18517 36481 18811 36481 18811 36482 18517 36482 18518 36482 18811 36483 18518 36483 18519 36483 18519 36484 18518 36484 18520 36484 18519 36485 18520 36485 18803 36485 18212 36486 18214 36486 17466 36486 17466 36487 18214 36487 18803 36487 17466 36488 18803 36488 17469 36488 17469 36489 18803 36489 18520 36489 18527 36490 18132 36490 18540 36490 18530 36491 18521 36491 18522 36491 17858 36492 17856 36492 18528 36492 17852 36493 17854 36493 18523 36493 18523 36494 17854 36494 18528 36494 18523 36495 18528 36495 18524 36495 18524 36496 18528 36496 17856 36496 18524 36497 17856 36497 18525 36497 18526 36498 18137 36498 18530 36498 18530 36499 18137 36499 18135 36499 18530 36500 18135 36500 18521 36500 18522 36501 18527 36501 18530 36501 18530 36502 18527 36502 18540 36502 18530 36503 18540 36503 18528 36503 18528 36504 18540 36504 17859 36504 18528 36505 17859 36505 17858 36505 16622 36506 16623 36506 18528 36506 18528 36507 16623 36507 16625 36507 18528 36508 16625 36508 16627 36508 18530 36509 18529 36509 16636 36509 16636 36510 16635 36510 18530 36510 18530 36511 16635 36511 18531 36511 18530 36512 18531 36512 16640 36512 16627 36513 18532 36513 18528 36513 18528 36514 18532 36514 16620 36514 18528 36515 16620 36515 18530 36515 18530 36516 16620 36516 18533 36516 18530 36517 18533 36517 18529 36517 17855 36518 18523 36518 16606 36518 16606 36519 18523 36519 18524 36519 16660 36520 18540 36520 18534 36520 18534 36521 18540 36521 16666 36521 16660 36522 16659 36522 18540 36522 18540 36523 16659 36523 18535 36523 18540 36524 18535 36524 16642 36524 16652 36525 18536 36525 17859 36525 17859 36526 18536 36526 18537 36526 17859 36527 18537 36527 16650 36527 16650 36528 16649 36528 17859 36528 17859 36529 16649 36529 16647 36529 17859 36530 16647 36530 18538 36530 18538 36531 16638 36531 17859 36531 17859 36532 16638 36532 16632 36532 17859 36533 16632 36533 16615 36533 16642 36534 18539 36534 18540 36534 18540 36535 18539 36535 16643 36535 18540 36536 16643 36536 17859 36536 17859 36537 16643 36537 16646 36537 17859 36538 16646 36538 16652 36538 16655 36539 18521 36539 16656 36539 16656 36540 18521 36540 18135 36540 18547 36541 18557 36541 18551 36541 18551 36542 18557 36542 18559 36542 18541 36543 17861 36543 18542 36543 18542 36544 17861 36544 18557 36544 18542 36545 18557 36545 18562 36545 18562 36546 18557 36546 18546 36546 18129 36547 18127 36547 18559 36547 18559 36548 18127 36548 18555 36548 18559 36549 18555 36549 18543 36549 18120 36550 18551 36550 18121 36550 18121 36551 18551 36551 18559 36551 18121 36552 18559 36552 18123 36552 18123 36553 18559 36553 18543 36553 18547 36554 18544 36554 18557 36554 18557 36555 18544 36555 18545 36555 18557 36556 18545 36556 18546 36556 16700 36557 18551 36557 16728 36557 16728 36558 18551 36558 18119 36558 16720 36559 18548 36559 18547 36559 18547 36560 18548 36560 18549 36560 18549 36561 18550 36561 18547 36561 18547 36562 18550 36562 16682 36562 18547 36563 16682 36563 17868 36563 16700 36564 16701 36564 18551 36564 18551 36565 16701 36565 18552 36565 18551 36566 18552 36566 16706 36566 16712 36567 16715 36567 18547 36567 18547 36568 16715 36568 16718 36568 18547 36569 16718 36569 16720 36569 16706 36570 18553 36570 18551 36570 18551 36571 18553 36571 16708 36571 18551 36572 16708 36572 18547 36572 18547 36573 16708 36573 16709 36573 18547 36574 16709 36574 16712 36574 16743 36575 18543 36575 18554 36575 18554 36576 18543 36576 18555 36576 18556 36577 16698 36577 18557 36577 18557 36578 16698 36578 16697 36578 18557 36579 16697 36579 16688 36579 16674 36580 18558 36580 18557 36580 18557 36581 18558 36581 16680 36581 18557 36582 16680 36582 18556 36582 16688 36583 16690 36583 18557 36583 18557 36584 16690 36584 16691 36584 18557 36585 16691 36585 18559 36585 18559 36586 16691 36586 16692 36586 18559 36587 16692 36587 16695 36587 16695 36588 16685 36588 18559 36588 18559 36589 16685 36589 18560 36589 18559 36590 18560 36590 16723 36590 16723 36591 18561 36591 18559 36591 18559 36592 18561 36592 16726 36592 18559 36593 16726 36593 16725 36593 16667 36594 18542 36594 16677 36594 16677 36595 18542 36595 18562 36595 18571 36596 18563 36596 18581 36596 18572 36597 18564 36597 18565 36597 17874 36598 17871 36598 18566 36598 18566 36599 17871 36599 17869 36599 18566 36600 17869 36600 18570 36600 18567 36601 18568 36601 18572 36601 18572 36602 18568 36602 18115 36602 18572 36603 18115 36603 18564 36603 17878 36604 17875 36604 17869 36604 17869 36605 17875 36605 18569 36605 17869 36606 18569 36606 18570 36606 18565 36607 18571 36607 18572 36607 18572 36608 18571 36608 18581 36608 18572 36609 18581 36609 17869 36609 17869 36610 18581 36610 18578 36610 17869 36611 18578 36611 17878 36611 18581 36612 18111 36612 18573 36612 18573 36613 16801 36613 18581 36613 18581 36614 16801 36614 18574 36614 18581 36615 18574 36615 16777 36615 18578 36616 16793 36616 16761 36616 16761 36617 18575 36617 18578 36617 18578 36618 18575 36618 18576 36618 18578 36619 18576 36619 18577 36619 16787 36620 16791 36620 18578 36620 18578 36621 16791 36621 16789 36621 18578 36622 16789 36622 16793 36622 16777 36623 18579 36623 18581 36623 18581 36624 18579 36624 18580 36624 18581 36625 18580 36625 16782 36625 16782 36626 18582 36626 18581 36626 18581 36627 18582 36627 18583 36627 18581 36628 18583 36628 18578 36628 18578 36629 18583 36629 16785 36629 18578 36630 16785 36630 16787 36630 18114 36631 18564 36631 16816 36631 16816 36632 18564 36632 18115 36632 16799 36633 18584 36633 18572 36633 18587 36634 16762 36634 17869 36634 17869 36635 16762 36635 16771 36635 17869 36636 16771 36636 18588 36636 16764 36637 16766 36637 18572 36637 18572 36638 16766 36638 16763 36638 18572 36639 16763 36639 16799 36639 16759 36640 18585 36640 17869 36640 17869 36641 18585 36641 18586 36641 17869 36642 18586 36642 18587 36642 18588 36643 16769 36643 17869 36643 17869 36644 16769 36644 16770 36644 17869 36645 16770 36645 18572 36645 18572 36646 16770 36646 16768 36646 18572 36647 16768 36647 16764 36647 16744 36648 18566 36648 16758 36648 16758 36649 18566 36649 18570 36649 18101 36650 18099 36650 18593 36650 18591 36651 18592 36651 18102 36651 17892 36652 17890 36652 18594 36652 17883 36653 17879 36653 18589 36653 18589 36654 17879 36654 18594 36654 18589 36655 18594 36655 18606 36655 18606 36656 18594 36656 17890 36656 18606 36657 17890 36657 17889 36657 18590 36658 18109 36658 18591 36658 18591 36659 18109 36659 18603 36659 18591 36660 18603 36660 18592 36660 18102 36661 18101 36661 18591 36661 18591 36662 18101 36662 18593 36662 18591 36663 18593 36663 18594 36663 18594 36664 18593 36664 18599 36664 18594 36665 18599 36665 17892 36665 18593 36666 18100 36666 16881 36666 16881 36667 16880 36667 18593 36667 18593 36668 16880 36668 18595 36668 18593 36669 18595 36669 16865 36669 18599 36670 16873 36670 18596 36670 18596 36671 18597 36671 18599 36671 18599 36672 18597 36672 18598 36672 18599 36673 18598 36673 17894 36673 18602 36674 16870 36674 18599 36674 18599 36675 16870 36675 18600 36675 18599 36676 18600 36676 16873 36676 16865 36677 16863 36677 18593 36677 18593 36678 16863 36678 16862 36678 18593 36679 16862 36679 16860 36679 16860 36680 16859 36680 18593 36680 18593 36681 16859 36681 18601 36681 18593 36682 18601 36682 18599 36682 18599 36683 18601 36683 16867 36683 18599 36684 16867 36684 18602 36684 18106 36685 18592 36685 16889 36685 16889 36686 18592 36686 18603 36686 18594 36687 16833 36687 16855 36687 16878 36688 18591 36688 18604 36688 18604 36689 18591 36689 16879 36689 16830 36690 16828 36690 18594 36690 18594 36691 16828 36691 16834 36691 18594 36692 16834 36692 16833 36692 16836 36693 16838 36693 18591 36693 18591 36694 16838 36694 16840 36694 18591 36695 16840 36695 16879 36695 16855 36696 18605 36696 18594 36696 18594 36697 18605 36697 16852 36697 18594 36698 16852 36698 16850 36698 16850 36699 16847 36699 18594 36699 18594 36700 16847 36700 16848 36700 18594 36701 16848 36701 18591 36701 18591 36702 16848 36702 16844 36702 18591 36703 16844 36703 16836 36703 17881 36704 18589 36704 16817 36704 16817 36705 18589 36705 18606 36705 18088 36706 18086 36706 18607 36706 18629 36707 18623 36707 18089 36707 18613 36708 17906 36708 18610 36708 18608 36709 18609 36709 17898 36709 17898 36710 18609 36710 18610 36710 17898 36711 18610 36711 18611 36711 18611 36712 18610 36712 17906 36712 18611 36713 17906 36713 17903 36713 18612 36714 18094 36714 18629 36714 18629 36715 18094 36715 18093 36715 18629 36716 18093 36716 18623 36716 18089 36717 18088 36717 18629 36717 18629 36718 18088 36718 18607 36718 18629 36719 18607 36719 18610 36719 18610 36720 18607 36720 18619 36720 18610 36721 18619 36721 18613 36721 16953 36722 16914 36722 18619 36722 18607 36723 16961 36723 18614 36723 18614 36724 18615 36724 18607 36724 18607 36725 18615 36725 16937 36725 18607 36726 16937 36726 18620 36726 16914 36727 18616 36727 18619 36727 18619 36728 18616 36728 18617 36728 18619 36729 18617 36729 17909 36729 16949 36730 18618 36730 18619 36730 18619 36731 18618 36731 16952 36731 18619 36732 16952 36732 16953 36732 18620 36733 16938 36733 18607 36733 18607 36734 16938 36734 18621 36734 18607 36735 18621 36735 16943 36735 16943 36736 16944 36736 18607 36736 18607 36737 16944 36737 18622 36737 18607 36738 18622 36738 18619 36738 18619 36739 18622 36739 16948 36739 18619 36740 16948 36740 16949 36740 18092 36741 18623 36741 16967 36741 16967 36742 18623 36742 18093 36742 16956 36743 18624 36743 18629 36743 18629 36744 18624 36744 18625 36744 18629 36745 18625 36745 18098 36745 16913 36746 18610 36746 18626 36746 18626 36747 18610 36747 17895 36747 16913 36748 18627 36748 18610 36748 18610 36749 18627 36749 16936 36749 18610 36750 16936 36750 16935 36750 16918 36751 18628 36751 18629 36751 18629 36752 18628 36752 16915 36752 18629 36753 16915 36753 16956 36753 16935 36754 16930 36754 18610 36754 18610 36755 16930 36755 16933 36755 18610 36756 16933 36756 16934 36756 16934 36757 16924 36757 18610 36757 18610 36758 16924 36758 16928 36758 18610 36759 16928 36759 18629 36759 18629 36760 16928 36760 18630 36760 18629 36761 18630 36761 16918 36761 16897 36762 17898 36762 16908 36762 16908 36763 17898 36763 18611 36763 18649 36764 18637 36764 17912 36764 17910 36765 18631 36765 17912 36765 17912 36766 18631 36766 18632 36766 17912 36767 18632 36767 18649 36767 18085 36768 18633 36768 18649 36768 18649 36769 18633 36769 18080 36769 18649 36770 18080 36770 18637 36770 18637 36771 18080 36771 18635 36771 18635 36772 18076 36772 18634 36772 17917 36773 17916 36773 18638 36773 18638 36774 17916 36774 18637 36774 18634 36775 18073 36775 18635 36775 18635 36776 18073 36776 18636 36776 18635 36777 18636 36777 18637 36777 18637 36778 18636 36778 18641 36778 18637 36779 18641 36779 18638 36779 18639 36780 17055 36780 18636 36780 18636 36781 17055 36781 17019 36781 18636 36782 17019 36782 18640 36782 18641 36783 17046 36783 17047 36783 17037 36784 17040 36784 18641 36784 17047 36785 16992 36785 18641 36785 18641 36786 16992 36786 16991 36786 18641 36787 16991 36787 18642 36787 17040 36788 18643 36788 18641 36788 18641 36789 18643 36789 17044 36789 18641 36790 17044 36790 17046 36790 18640 36791 17024 36791 18636 36791 18636 36792 17024 36792 17026 36792 18636 36793 17026 36793 17032 36793 17032 36794 17030 36794 18636 36794 18636 36795 17030 36795 17033 36795 18636 36796 17033 36796 18641 36796 18641 36797 17033 36797 17038 36797 18641 36798 17038 36798 17037 36798 17067 36799 18635 36799 18078 36799 18078 36800 18635 36800 18080 36800 18632 36801 16995 36801 17018 36801 16998 36802 17054 36802 18649 36802 18649 36803 17054 36803 17053 36803 18649 36804 17053 36804 17056 36804 16980 36805 18644 36805 18632 36805 18632 36806 18644 36806 16993 36806 18632 36807 16993 36807 16995 36807 17018 36808 18645 36808 18632 36808 18632 36809 18645 36809 18646 36809 18632 36810 18646 36810 18647 36810 17008 36811 17002 36811 18649 36811 18649 36812 17002 36812 16997 36812 18649 36813 16997 36813 16998 36813 18647 36814 17012 36814 18632 36814 18632 36815 17012 36815 18648 36815 18632 36816 18648 36816 18649 36816 18649 36817 18648 36817 17007 36817 18649 36818 17007 36818 17008 36818 17911 36819 17912 36819 17914 36819 17914 36820 17912 36820 18637 36820 18064 36821 18650 36821 18663 36821 18669 36822 18657 36822 18066 36822 17930 36823 18654 36823 18671 36823 18651 36824 17921 36824 18652 36824 18652 36825 17921 36825 18671 36825 18652 36826 18671 36826 18653 36826 18653 36827 18671 36827 18654 36827 18653 36828 18654 36828 18655 36828 18071 36829 18070 36829 18669 36829 18669 36830 18070 36830 18656 36830 18669 36831 18656 36831 18657 36831 18066 36832 18064 36832 18669 36832 18669 36833 18064 36833 18663 36833 18669 36834 18663 36834 18671 36834 18671 36835 18663 36835 18661 36835 18671 36836 18661 36836 17930 36836 18658 36837 18663 36837 18659 36837 18659 36838 18663 36838 18062 36838 18660 36839 17091 36839 18661 36839 18661 36840 17091 36840 17090 36840 17100 36841 18662 36841 18661 36841 18661 36842 18662 36842 17102 36842 18661 36843 17102 36843 18660 36843 17090 36844 17088 36844 18661 36844 18661 36845 17088 36845 17085 36845 18661 36846 17085 36846 17072 36846 18658 36847 17096 36847 18663 36847 18663 36848 17096 36848 18664 36848 18663 36849 18664 36849 17099 36849 17099 36850 18665 36850 18663 36850 18663 36851 18665 36851 18666 36851 18663 36852 18666 36852 18661 36852 18661 36853 18666 36853 18667 36853 18661 36854 18667 36854 17100 36854 18067 36855 18657 36855 18069 36855 18069 36856 18657 36856 18656 36856 17127 36857 18669 36857 18668 36857 18668 36858 18669 36858 17104 36858 17093 36859 17092 36859 18671 36859 18671 36860 17092 36860 17120 36860 18671 36861 17120 36861 17119 36861 18674 36862 17111 36862 18669 36862 18669 36863 17111 36863 17105 36863 18669 36864 17105 36864 17104 36864 17083 36865 17087 36865 18671 36865 18671 36866 17087 36866 18670 36866 18671 36867 18670 36867 17093 36867 17119 36868 17116 36868 18671 36868 18671 36869 17116 36869 17114 36869 18671 36870 17114 36870 18672 36870 18672 36871 18673 36871 18671 36871 18671 36872 18673 36872 17107 36872 18671 36873 17107 36873 18669 36873 18669 36874 17107 36874 17109 36874 18669 36875 17109 36875 18674 36875 17923 36876 18652 36876 17076 36876 17076 36877 18652 36877 18653 36877 17933 36878 18675 36878 18676 36878 18676 36879 18675 36879 18683 36879 18676 36880 18683 36880 18677 36880 18061 36881 18678 36881 18700 36881 18700 36882 18678 36882 18679 36882 18679 36883 18056 36883 18700 36883 18700 36884 18056 36884 18680 36884 18700 36885 18680 36885 18052 36885 18684 36886 18681 36886 18683 36886 18683 36887 18681 36887 17936 36887 18683 36888 17936 36888 18677 36888 18052 36889 18050 36889 18700 36889 18700 36890 18050 36890 18682 36890 18700 36891 18682 36891 18683 36891 18683 36892 18682 36892 18688 36892 18683 36893 18688 36893 18684 36893 17205 36894 17207 36894 18688 36894 18682 36895 18685 36895 18686 36895 18686 36896 17215 36896 18682 36896 18682 36897 17215 36897 18687 36897 18682 36898 18687 36898 17193 36898 17207 36899 17165 36899 18688 36899 18688 36900 17165 36900 17160 36900 18688 36901 17160 36901 18689 36901 18693 36902 17203 36902 18688 36902 18688 36903 17203 36903 17201 36903 18688 36904 17201 36904 17205 36904 17193 36905 18690 36905 18682 36905 18682 36906 18690 36906 17196 36906 18682 36907 17196 36907 18691 36907 18691 36908 18692 36908 18682 36908 18682 36909 18692 36909 17198 36909 18682 36910 17198 36910 18688 36910 18688 36911 17198 36911 17200 36911 18688 36912 17200 36912 18693 36912 17227 36913 18056 36913 18694 36913 18694 36914 18056 36914 18679 36914 17213 36915 18700 36915 17209 36915 17209 36916 18700 36916 18695 36916 18697 36917 18683 36917 18696 36917 18696 36918 18683 36918 17153 36918 18697 36919 17162 36919 18683 36919 18683 36920 17162 36920 17189 36920 18683 36921 17189 36921 17188 36921 17172 36922 17173 36922 18700 36922 18700 36923 17173 36923 17175 36923 18700 36924 17175 36924 18695 36924 17188 36925 17185 36925 18683 36925 18683 36926 17185 36926 17181 36926 18683 36927 17181 36927 18698 36927 18698 36928 18699 36928 18683 36928 18683 36929 18699 36929 17177 36929 18683 36930 17177 36930 18700 36930 18700 36931 17177 36931 17168 36931 18700 36932 17168 36932 17172 36932 17145 36933 18676 36933 17146 36933 17146 36934 18676 36934 18677 36934 17940 36935 17939 36935 18719 36935 18705 36936 18044 36936 18714 36936 18723 36937 18701 36937 18704 36937 17952 36938 17951 36938 18719 36938 18702 36939 18049 36939 18723 36939 18723 36940 18049 36940 18703 36940 18723 36941 18703 36941 18701 36941 17942 36942 17940 36942 17944 36942 17944 36943 17940 36943 18719 36943 17944 36944 18719 36944 18726 36944 18726 36945 18719 36945 17951 36945 18726 36946 17951 36946 17948 36946 18704 36947 18705 36947 18723 36947 18723 36948 18705 36948 18714 36948 18723 36949 18714 36949 18719 36949 18719 36950 18714 36950 17953 36950 18719 36951 17953 36951 17952 36951 18714 36952 18706 36952 18707 36952 18707 36953 18708 36953 18714 36953 18714 36954 18708 36954 17279 36954 18714 36955 17279 36955 17263 36955 17953 36956 17274 36956 18709 36956 18709 36957 17244 36957 17953 36957 17953 36958 17244 36958 18710 36958 17953 36959 18710 36959 17954 36959 17271 36960 18711 36960 17953 36960 17953 36961 18711 36961 18712 36961 17953 36962 18712 36962 17274 36962 17263 36963 17265 36963 18714 36963 18714 36964 17265 36964 17266 36964 18714 36965 17266 36965 18713 36965 18713 36966 17267 36966 18714 36966 18714 36967 17267 36967 18715 36967 18714 36968 18715 36968 17953 36968 17953 36969 18715 36969 18716 36969 17953 36970 18716 36970 17271 36970 18717 36971 18701 36971 18718 36971 18718 36972 18701 36972 18703 36972 18719 36973 17246 36973 18722 36973 17277 36974 18720 36974 18723 36974 18723 36975 18720 36975 18721 36975 18723 36976 18721 36976 17281 36976 17233 36977 17242 36977 18719 36977 18719 36978 17242 36978 17240 36978 18719 36979 17240 36979 17246 36979 18722 36980 17260 36980 18719 36980 18719 36981 17260 36981 17258 36981 18719 36982 17258 36982 18724 36982 17247 36983 17250 36983 18723 36983 18723 36984 17250 36984 17252 36984 18723 36985 17252 36985 17277 36985 18724 36986 18725 36986 18719 36986 18719 36987 18725 36987 17253 36987 18719 36988 17253 36988 18723 36988 18723 36989 17253 36989 17254 36989 18723 36990 17254 36990 17247 36990 17228 36991 17944 36991 17945 36991 17945 36992 17944 36992 18726 36992 18732 36993 18034 36993 18737 36993 18730 36994 18727 36994 18035 36994 17966 36995 17963 36995 18743 36995 18728 36996 17956 36996 18748 36996 18748 36997 17956 36997 18743 36997 18748 36998 18743 36998 17960 36998 17960 36999 18743 36999 17963 36999 17960 37000 17963 37000 17962 37000 18729 37001 18039 37001 18730 37001 18730 37002 18039 37002 18731 37002 18730 37003 18731 37003 18727 37003 18035 37004 18732 37004 18730 37004 18730 37005 18732 37005 18737 37005 18730 37006 18737 37006 18743 37006 18743 37007 18737 37007 18733 37007 18743 37008 18733 37008 17966 37008 18737 37009 17354 37009 17353 37009 17353 37010 17352 37010 18737 37010 18737 37011 17352 37011 17331 37011 18737 37012 17331 37012 18735 37012 18733 37013 17345 37013 17312 37013 17312 37014 17313 37014 18733 37014 18733 37015 17313 37015 17309 37015 18733 37016 17309 37016 17302 37016 18739 37017 17344 37017 18733 37017 18733 37018 17344 37018 18734 37018 18733 37019 18734 37019 17345 37019 18735 37020 18736 37020 18737 37020 18737 37021 18736 37021 17335 37021 18737 37022 17335 37022 17336 37022 17336 37023 17337 37023 18737 37023 18737 37024 17337 37024 18738 37024 18737 37025 18738 37025 18733 37025 18733 37026 18738 37026 17340 37026 18733 37027 17340 37027 18739 37027 18037 37028 18727 37028 17367 37028 17367 37029 18727 37029 18731 37029 17347 37030 18740 37030 18730 37030 18730 37031 18740 37031 17350 37031 18730 37032 17350 37032 17355 37032 17311 37033 18743 37033 18741 37033 18741 37034 18743 37034 17301 37034 17311 37035 18742 37035 18743 37035 18743 37036 18742 37036 17329 37036 18743 37037 17329 37037 17328 37037 17317 37038 17319 37038 18730 37038 18730 37039 17319 37039 18744 37039 18730 37040 18744 37040 17347 37040 17328 37041 17327 37041 18743 37041 18743 37042 17327 37042 17325 37042 18743 37043 17325 37043 18745 37043 18745 37044 18746 37044 18743 37044 18743 37045 18746 37045 18747 37045 18743 37046 18747 37046 18730 37046 18730 37047 18747 37047 17322 37047 18730 37048 17322 37048 17317 37048 17958 37049 18748 37049 17294 37049 17294 37050 18748 37050 17960 37050 18756 37051 18023 37051 18759 37051 18033 37052 18749 37052 18750 37052 18751 37053 18753 37053 18752 37053 17971 37054 17968 37054 18773 37054 18773 37055 17968 37055 18752 37055 18773 37056 18752 37056 17974 37056 17974 37057 18752 37057 18753 37057 17974 37058 18753 37058 18754 37058 18755 37059 18028 37059 18033 37059 18033 37060 18028 37060 18027 37060 18033 37061 18027 37061 18749 37061 18750 37062 18756 37062 18033 37062 18033 37063 18756 37063 18759 37063 18033 37064 18759 37064 18752 37064 18752 37065 18759 37065 18757 37065 18752 37066 18757 37066 18751 37066 17410 37067 18759 37067 17415 37067 17415 37068 18759 37068 18022 37068 17404 37069 18758 37069 18757 37069 18757 37070 18758 37070 17405 37070 18757 37071 17405 37071 18761 37071 17410 37072 17397 37072 18759 37072 18759 37073 17397 37073 18760 37073 18759 37074 18760 37074 18764 37074 18761 37075 17385 37075 18757 37075 18757 37076 17385 37076 18762 37076 18757 37077 18762 37077 18763 37077 18764 37078 18765 37078 18759 37078 18759 37079 18765 37079 18766 37079 18759 37080 18766 37080 18757 37080 18757 37081 18766 37081 17400 37081 18757 37082 17400 37082 17404 37082 18025 37083 18749 37083 17429 37083 17429 37084 18749 37084 18027 37084 18752 37085 17383 37085 18767 37085 17416 37086 18033 37086 17412 37086 17412 37087 18033 37087 17407 37087 17381 37088 17380 37088 18752 37088 18752 37089 17380 37089 17384 37089 18752 37090 17384 37090 17383 37090 18767 37091 17395 37091 18752 37091 18752 37092 17395 37092 17392 37092 18752 37093 17392 37093 17391 37093 18768 37094 17387 37094 18033 37094 18033 37095 17387 37095 18769 37095 18033 37096 18769 37096 17407 37096 17391 37097 17390 37097 18752 37097 18752 37098 17390 37098 18770 37098 18752 37099 18770 37099 18033 37099 18033 37100 18770 37100 18771 37100 18033 37101 18771 37101 18768 37101 18772 37102 18773 37102 17368 37102 17368 37103 18773 37103 17974 37103 18017 37104 18016 37104 18779 37104 18778 37105 18777 37105 18774 37105 17989 37106 17988 37106 17978 37106 17982 37107 17980 37107 17983 37107 17983 37108 17980 37108 17978 37108 17983 37109 17978 37109 18775 37109 18775 37110 17978 37110 17988 37110 18775 37111 17988 37111 17986 37111 18021 37112 18776 37112 18778 37112 18778 37113 18776 37113 18019 37113 18778 37114 18019 37114 18777 37114 18774 37115 18017 37115 18778 37115 18778 37116 18017 37116 18779 37116 18778 37117 18779 37117 17978 37117 17978 37118 18779 37118 18781 37118 17978 37119 18781 37119 17989 37119 17468 37120 17467 37120 18779 37120 17468 37121 18779 37121 18783 37121 18780 37122 17474 37122 18781 37122 17474 37123 17475 37123 18781 37123 18781 37124 17475 37124 17476 37124 18781 37125 17476 37125 17447 37125 17498 37126 18782 37126 18779 37126 18779 37127 18782 37127 17482 37127 18779 37128 17482 37128 18783 37128 17447 37129 18784 37129 18781 37129 18781 37130 18784 37130 17443 37130 18781 37131 17443 37131 17442 37131 17467 37132 18785 37132 18779 37132 18779 37133 18785 37133 17470 37133 18779 37134 17470 37134 18781 37134 18781 37135 17470 37135 17471 37135 18781 37136 17471 37136 18780 37136 18786 37137 18777 37137 17491 37137 17491 37138 18777 37138 18019 37138 17451 37139 17450 37139 18778 37139 17444 37140 17465 37140 17978 37140 17978 37141 17465 37141 17464 37141 17978 37142 17464 37142 17462 37142 17450 37143 17477 37143 18778 37143 18778 37144 17477 37144 17478 37144 18778 37145 17478 37145 17479 37145 17440 37146 18787 37146 17978 37146 17978 37147 18787 37147 18788 37147 17978 37148 18788 37148 17444 37148 17462 37149 17454 37149 17978 37149 17978 37150 17454 37150 18789 37150 17978 37151 18789 37151 18778 37151 18778 37152 18789 37152 17458 37152 18778 37153 17458 37153 17451 37153 18790 37154 17983 37154 18791 37154 18791 37155 17983 37155 18775 37155 18798 37156 18793 37156 17994 37156 18792 37157 17992 37157 18793 37157 18793 37158 17992 37158 17990 37158 18793 37159 17990 37159 18000 37159 18000 37160 17999 37160 18793 37160 18793 37161 17999 37161 18794 37161 18793 37162 18794 37162 17994 37162 17994 37163 18810 37163 18798 37163 18798 37164 18810 37164 18795 37164 18798 37165 18795 37165 18009 37165 18014 37166 18797 37166 18796 37166 18796 37167 18797 37167 18798 37167 18796 37168 18798 37168 18008 37168 18008 37169 18798 37169 18009 37169 18798 37170 17504 37170 17505 37170 17515 37171 18793 37171 17516 37171 17516 37172 18793 37172 18798 37172 17516 37173 18798 37173 17508 37173 17515 37174 17514 37174 18793 37174 18793 37175 17514 37175 17512 37175 18793 37176 17512 37176 18799 37176 17505 37177 18800 37177 18798 37177 18798 37178 18800 37178 17506 37178 18798 37179 17506 37179 17508 37179 18799 37180 17510 37180 18793 37180 18793 37181 17510 37181 18801 37181 18793 37182 18801 37182 18802 37182 17994 37183 19522 37183 18805 37183 17994 37184 18511 37184 18513 37184 18519 37185 18803 37185 18810 37185 18810 37186 18803 37186 18804 37186 18810 37187 18804 37187 18215 37187 18805 37188 18806 37188 17994 37188 17994 37189 18806 37189 18807 37189 17994 37190 18807 37190 18511 37190 18215 37191 18213 37191 18810 37191 18810 37192 18213 37192 18808 37192 18810 37193 18808 37193 19316 37193 18513 37194 18514 37194 17994 37194 17994 37195 18514 37195 18809 37195 17994 37196 18809 37196 18810 37196 18810 37197 18809 37197 18811 37197 18810 37198 18811 37198 18519 37198 15957 37199 18841 37199 15959 37199 15959 37200 18841 37200 18812 37200 15959 37201 18812 37201 15960 37201 15960 37202 18812 37202 18828 37202 15960 37203 18828 37203 15961 37203 15961 37204 18828 37204 18826 37204 15961 37205 18826 37205 15962 37205 15962 37206 18826 37206 18825 37206 15962 37207 18825 37207 15963 37207 15963 37208 18825 37208 18813 37208 15963 37209 18813 37209 16006 37209 16006 37210 18813 37210 18814 37210 19941 37211 18815 37211 15965 37211 15965 37212 18815 37212 18844 37212 15965 37213 18844 37213 18816 37213 18816 37214 18844 37214 18817 37214 18816 37215 18817 37215 15968 37215 15968 37216 18817 37216 18818 37216 15968 37217 18818 37217 15970 37217 15970 37218 18818 37218 18820 37218 15970 37219 18820 37219 18819 37219 18819 37220 18820 37220 18833 37220 18819 37221 18833 37221 15973 37221 15973 37222 18833 37222 18821 37222 15973 37223 18821 37223 19937 37223 19937 37224 18821 37224 19938 37224 18814 37225 18813 37225 18822 37225 18845 37226 19485 37226 19940 37226 19940 37227 19485 37227 19488 37227 19940 37228 19488 37228 18815 37228 18822 37229 18813 37229 18823 37229 18823 37230 18813 37230 18825 37230 18823 37231 18825 37231 18824 37231 18824 37232 18825 37232 18826 37232 18824 37233 18826 37233 18834 37233 18834 37234 18826 37234 18828 37234 18834 37235 18828 37235 18827 37235 18827 37236 18828 37236 18812 37236 18827 37237 18812 37237 16016 37237 19939 37238 18829 37238 18831 37238 18831 37239 18829 37239 18830 37239 18831 37240 18830 37240 18832 37240 18832 37241 18830 37241 19938 37241 18832 37242 19938 37242 16017 37242 16017 37243 19938 37243 18821 37243 16017 37244 18821 37244 16018 37244 16018 37245 18821 37245 18833 37245 16018 37246 18833 37246 18820 37246 18827 37247 18835 37247 18834 37247 18834 37248 18835 37248 18836 37248 18834 37249 18836 37249 18837 37249 18849 37250 16015 37250 19489 37250 19489 37251 16015 37251 19945 37251 19489 37252 19945 37252 19491 37252 19491 37253 19945 37253 18838 37253 19491 37254 18838 37254 19492 37254 19492 37255 18838 37255 18839 37255 19492 37256 18839 37256 19496 37256 19496 37257 18839 37257 19942 37257 19496 37258 19942 37258 19497 37258 19497 37259 19942 37259 18814 37259 19497 37260 18814 37260 19500 37260 19500 37261 18814 37261 18822 37261 16016 37262 18812 37262 18840 37262 18840 37263 18812 37263 18841 37263 18840 37264 18841 37264 16015 37264 16015 37265 18841 37265 19946 37265 16015 37266 19946 37266 19945 37266 18820 37267 18842 37267 16018 37267 16018 37268 18842 37268 19473 37268 16018 37269 19473 37269 16019 37269 16019 37270 19473 37270 18837 37270 16019 37271 18837 37271 16022 37271 16022 37272 18837 37272 18836 37272 19488 37273 19481 37273 18815 37273 18815 37274 19481 37274 18843 37274 18815 37275 18843 37275 18844 37275 18844 37276 18843 37276 19475 37276 18844 37277 19475 37277 18817 37277 18817 37278 19475 37278 18842 37278 18817 37279 18842 37279 18818 37279 18818 37280 18842 37280 18820 37280 18845 37281 19939 37281 19485 37281 19485 37282 19939 37282 18831 37282 19485 37283 18831 37283 18846 37283 18846 37284 18831 37284 18847 37284 18846 37285 18847 37285 18852 37285 18852 37286 18847 37286 18848 37286 18852 37287 18848 37287 19489 37287 19489 37288 18848 37288 16011 37288 19489 37289 16011 37289 18849 37289 16497 37290 18852 37290 18850 37290 18850 37291 18852 37291 18851 37291 18851 37292 18852 37292 18853 37292 18853 37293 18852 37293 19489 37293 18853 37294 19489 37294 16492 37294 18869 37295 19200 37295 18868 37295 18868 37296 19200 37296 18855 37296 18868 37297 18855 37297 18854 37297 18854 37298 18855 37298 18856 37298 18854 37299 18856 37299 18867 37299 18867 37300 18856 37300 18857 37300 18867 37301 18857 37301 18865 37301 18865 37302 18857 37302 18858 37302 18865 37303 18858 37303 18859 37303 18859 37304 18858 37304 18860 37304 18859 37305 18860 37305 19932 37305 19932 37306 18860 37306 18861 37306 18872 37307 18873 37307 18862 37307 18862 37308 18873 37308 19927 37308 18862 37309 19927 37309 18863 37309 18863 37310 19927 37310 19926 37310 18863 37311 19926 37311 19932 37311 19932 37312 19926 37312 18864 37312 19932 37313 18864 37313 18859 37313 18859 37314 18864 37314 18883 37314 18859 37315 18883 37315 18865 37315 18865 37316 18883 37316 18866 37316 18865 37317 18866 37317 18867 37317 18866 37318 18882 37318 18867 37318 18867 37319 18882 37319 18879 37319 18867 37320 18879 37320 18854 37320 18854 37321 18879 37321 18878 37321 18854 37322 18878 37322 18868 37322 18868 37323 18878 37323 18876 37323 18868 37324 18876 37324 18869 37324 18869 37325 18876 37325 18870 37325 18869 37326 18870 37326 19934 37326 19934 37327 18870 37327 19924 37327 19934 37328 19924 37328 18871 37328 18871 37329 19924 37329 19930 37329 18871 37330 19930 37330 18872 37330 18872 37331 19930 37331 19928 37331 18872 37332 19928 37332 18873 37332 18874 37333 18870 37333 20216 37333 20216 37334 18870 37334 18876 37334 20218 37335 18875 37335 18876 37335 18876 37336 18875 37336 20215 37336 18876 37337 20215 37337 20216 37337 20218 37338 18876 37338 18877 37338 18877 37339 18876 37339 18878 37339 18877 37340 18878 37340 18880 37340 18880 37341 18878 37341 18879 37341 18880 37342 18879 37342 20191 37342 18882 37343 18881 37343 18879 37343 18879 37344 18881 37344 20192 37344 18879 37345 20192 37345 20191 37345 20205 37346 20200 37346 18882 37346 18882 37347 20200 37347 20199 37347 18882 37348 20199 37348 18881 37348 16092 37349 20206 37349 18883 37349 18883 37350 20206 37350 20205 37350 18883 37351 20205 37351 18866 37351 18866 37352 20205 37352 18882 37352 18864 37353 19925 37353 18883 37353 18883 37354 19925 37354 18884 37354 18883 37355 18884 37355 16092 37355 18890 37356 19152 37356 18889 37356 18889 37357 19152 37357 19151 37357 18889 37358 19151 37358 18885 37358 18885 37359 19151 37359 19161 37359 18885 37360 19161 37360 18897 37360 18897 37361 19161 37361 19160 37361 18897 37362 19160 37362 18886 37362 18886 37363 19160 37363 19159 37363 18886 37364 19159 37364 18895 37364 18895 37365 19159 37365 19158 37365 18895 37366 19158 37366 19917 37366 19917 37367 19158 37367 19918 37367 18897 37368 19511 37368 18885 37368 18885 37369 19511 37369 18887 37369 18885 37370 18887 37370 18889 37370 18889 37371 18887 37371 18888 37371 18889 37372 18888 37372 18890 37372 18890 37373 18888 37373 18891 37373 18890 37374 18891 37374 18892 37374 18892 37375 18891 37375 19801 37375 18892 37376 19801 37376 19922 37376 19922 37377 19801 37377 18893 37377 19922 37378 18893 37378 19921 37378 19921 37379 18893 37379 18894 37379 19921 37380 18894 37380 19920 37380 19920 37381 18894 37381 19799 37381 19920 37382 19799 37382 19919 37382 19919 37383 19799 37383 19794 37383 19919 37384 19794 37384 19917 37384 19917 37385 19794 37385 19792 37385 19917 37386 19792 37386 18895 37386 18895 37387 19792 37387 18896 37387 18895 37388 18896 37388 18886 37388 18886 37389 18896 37389 18898 37389 18886 37390 18898 37390 18897 37390 18897 37391 18898 37391 19511 37391 18907 37392 19194 37392 18900 37392 18900 37393 19194 37393 18899 37393 18900 37394 18899 37394 18901 37394 18901 37395 18899 37395 19196 37395 18901 37396 19196 37396 18902 37396 18902 37397 19196 37397 19191 37397 18902 37398 19191 37398 18918 37398 18918 37399 19191 37399 18903 37399 18918 37400 18903 37400 18916 37400 18916 37401 18903 37401 19192 37401 18916 37402 19192 37402 18914 37402 18914 37403 19192 37403 19206 37403 18904 37404 18923 37404 18902 37404 18902 37405 18923 37405 18921 37405 18902 37406 18921 37406 18901 37406 18901 37407 18921 37407 18905 37407 18901 37408 18905 37408 18900 37408 18900 37409 18905 37409 18906 37409 18900 37410 18906 37410 18907 37410 18907 37411 18906 37411 18908 37411 18907 37412 18908 37412 19916 37412 19916 37413 18908 37413 19907 37413 19916 37414 19907 37414 19914 37414 19914 37415 19907 37415 18909 37415 19914 37416 18909 37416 19913 37416 19913 37417 18909 37417 18910 37417 19913 37418 18910 37418 19912 37418 19912 37419 18910 37419 18911 37419 19912 37420 18911 37420 18912 37420 18912 37421 18911 37421 19904 37421 18912 37422 19904 37422 18913 37422 18913 37423 19904 37423 18915 37423 18913 37424 18915 37424 18914 37424 18914 37425 18915 37425 19900 37425 18914 37426 19900 37426 18916 37426 18916 37427 19900 37427 18917 37427 18916 37428 18917 37428 18918 37428 18918 37429 18917 37429 18904 37429 18918 37430 18904 37430 18902 37430 16053 37431 18908 37431 18919 37431 18919 37432 18908 37432 18906 37432 18919 37433 18906 37433 20254 37433 20254 37434 18906 37434 20255 37434 20255 37435 18906 37435 18905 37435 20255 37436 18905 37436 18920 37436 18920 37437 18905 37437 18921 37437 18920 37438 18921 37438 18922 37438 18922 37439 18921 37439 20257 37439 20257 37440 18921 37440 18923 37440 20257 37441 18923 37441 20258 37441 20258 37442 18923 37442 20260 37442 20260 37443 18923 37443 18904 37443 20260 37444 18904 37444 20262 37444 20262 37445 18904 37445 20251 37445 20251 37446 18904 37446 18917 37446 20251 37447 18917 37447 18924 37447 18924 37448 18917 37448 20281 37448 20281 37449 18917 37449 19900 37449 20281 37450 19900 37450 19899 37450 18925 37451 18926 37451 18936 37451 18936 37452 18926 37452 18927 37452 18936 37453 18927 37453 18928 37453 18928 37454 18927 37454 18929 37454 18928 37455 18929 37455 18933 37455 18933 37456 18929 37456 19110 37456 18933 37457 19110 37457 18930 37457 18930 37458 19110 37458 19113 37458 18930 37459 19113 37459 18931 37459 18931 37460 19113 37460 19112 37460 18931 37461 19112 37461 18932 37461 18932 37462 19112 37462 19111 37462 18933 37463 18934 37463 18928 37463 18928 37464 18934 37464 18935 37464 18928 37465 18935 37465 18936 37465 18936 37466 18935 37466 18946 37466 18936 37467 18946 37467 18925 37467 18925 37468 18946 37468 18937 37468 18925 37469 18937 37469 19896 37469 19896 37470 18937 37470 18938 37470 19896 37471 18938 37471 19895 37471 19895 37472 18938 37472 18940 37472 19895 37473 18940 37473 18939 37473 18940 37474 18941 37474 18939 37474 18939 37475 18941 37475 19886 37475 18939 37476 19886 37476 19893 37476 19893 37477 19886 37477 19883 37477 19893 37478 19883 37478 19890 37478 19890 37479 19883 37479 18942 37479 19890 37480 18942 37480 18932 37480 18932 37481 18942 37481 18943 37481 18932 37482 18943 37482 18931 37482 18931 37483 18943 37483 18955 37483 18931 37484 18955 37484 18930 37484 18930 37485 18955 37485 18944 37485 18930 37486 18944 37486 18933 37486 18933 37487 18944 37487 18949 37487 18933 37488 18949 37488 18934 37488 20178 37489 18937 37489 20177 37489 20177 37490 18937 37490 18946 37490 20177 37491 18946 37491 18945 37491 18945 37492 18946 37492 18935 37492 18945 37493 18935 37493 20148 37493 20148 37494 18935 37494 18947 37494 18947 37495 18935 37495 18934 37495 18947 37496 18934 37496 18948 37496 20169 37497 20182 37497 18949 37497 18949 37498 20182 37498 18950 37498 18949 37499 18950 37499 18934 37499 18934 37500 18950 37500 20181 37500 18934 37501 20181 37501 18948 37501 20169 37502 18949 37502 20171 37502 20171 37503 18949 37503 18944 37503 20171 37504 18944 37504 18951 37504 18955 37505 18956 37505 18944 37505 18944 37506 18956 37506 20172 37506 18944 37507 20172 37507 18951 37507 18952 37508 18953 37508 18943 37508 18943 37509 18953 37509 18954 37509 18943 37510 18954 37510 18955 37510 18955 37511 18954 37511 20176 37511 18955 37512 20176 37512 18956 37512 18972 37513 19129 37513 18957 37513 18957 37514 19129 37514 19128 37514 18957 37515 19128 37515 18958 37515 18958 37516 19128 37516 18959 37516 18958 37517 18959 37517 18960 37517 18960 37518 18959 37518 18961 37518 18960 37519 18961 37519 18967 37519 18967 37520 18961 37520 19136 37520 18967 37521 19136 37521 18962 37521 18962 37522 19136 37522 18963 37522 18962 37523 18963 37523 18965 37523 18965 37524 18963 37524 19126 37524 18964 37525 19869 37525 19876 37525 19876 37526 19869 37526 19868 37526 19876 37527 19868 37527 19874 37527 19874 37528 19868 37528 19864 37528 19874 37529 19864 37529 18965 37529 18965 37530 19864 37530 19861 37530 18965 37531 19861 37531 18962 37531 18962 37532 19861 37532 18966 37532 18962 37533 18966 37533 18967 37533 18967 37534 18966 37534 18968 37534 18967 37535 18968 37535 18960 37535 18968 37536 18969 37536 18960 37536 18960 37537 18969 37537 18970 37537 18960 37538 18970 37538 18958 37538 18958 37539 18970 37539 18979 37539 18958 37540 18979 37540 18957 37540 18957 37541 18979 37541 18971 37541 18957 37542 18971 37542 18972 37542 18972 37543 18971 37543 18973 37543 18972 37544 18973 37544 18974 37544 18974 37545 18973 37545 19871 37545 18974 37546 19871 37546 18975 37546 18975 37547 19871 37547 18976 37547 18975 37548 18976 37548 18964 37548 18964 37549 18976 37549 18977 37549 18964 37550 18977 37550 19869 37550 18983 37551 18980 37551 18970 37551 16173 37552 18978 37552 18973 37552 16173 37553 18973 37553 20142 37553 20142 37554 18973 37554 18971 37554 20142 37555 18971 37555 20143 37555 20143 37556 18971 37556 18979 37556 20143 37557 18979 37557 18982 37557 18970 37558 18980 37558 18979 37558 18979 37559 18980 37559 18981 37559 18979 37560 18981 37560 18982 37560 18983 37561 18970 37561 18984 37561 18984 37562 18970 37562 18969 37562 18984 37563 18969 37563 18985 37563 18985 37564 18969 37564 18968 37564 18985 37565 18968 37565 20120 37565 20120 37566 18968 37566 18986 37566 18986 37567 18968 37567 18966 37567 18986 37568 18966 37568 18987 37568 18987 37569 18966 37569 19861 37569 18987 37570 19861 37570 18988 37570 19003 37571 19167 37571 18989 37571 18989 37572 19167 37572 18991 37572 18989 37573 18991 37573 18990 37573 18990 37574 18991 37574 19175 37574 18990 37575 19175 37575 18992 37575 18992 37576 19175 37576 18993 37576 18992 37577 18993 37577 19000 37577 19000 37578 18993 37578 19166 37578 19000 37579 19166 37579 18999 37579 18999 37580 19166 37580 18994 37580 18999 37581 18994 37581 18998 37581 18998 37582 18994 37582 18995 37582 19006 37583 19850 37583 19853 37583 19853 37584 19850 37584 19852 37584 19853 37585 19852 37585 18996 37585 18996 37586 19852 37586 19848 37586 18996 37587 19848 37587 18998 37587 18998 37588 19848 37588 18997 37588 18998 37589 18997 37589 18999 37589 18999 37590 18997 37590 19018 37590 18999 37591 19018 37591 19000 37591 19000 37592 19018 37592 19001 37592 19000 37593 19001 37593 18992 37593 19001 37594 19014 37594 18992 37594 18992 37595 19014 37595 19002 37595 18992 37596 19002 37596 18990 37596 18990 37597 19002 37597 19010 37597 18990 37598 19010 37598 18989 37598 18989 37599 19010 37599 19011 37599 18989 37600 19011 37600 19003 37600 19003 37601 19011 37601 19004 37601 19003 37602 19004 37602 19857 37602 19857 37603 19004 37603 19846 37603 19857 37604 19846 37604 19005 37604 19005 37605 19846 37605 19007 37605 19005 37606 19007 37606 19006 37606 19006 37607 19007 37607 19841 37607 19006 37608 19841 37608 19850 37608 19011 37609 16331 37609 19004 37609 19004 37610 16331 37610 16330 37610 19004 37611 16330 37611 19008 37611 19010 37612 19002 37612 16327 37612 16327 37613 19009 37613 19010 37613 19010 37614 19009 37614 16329 37614 19010 37615 16329 37615 19011 37615 19011 37616 16329 37616 16349 37616 19011 37617 16349 37617 16331 37617 19014 37618 19015 37618 19002 37618 19002 37619 19015 37619 16328 37619 19002 37620 16328 37620 16327 37620 19012 37621 19013 37621 19001 37621 19001 37622 19013 37622 16396 37622 19001 37623 16396 37623 19014 37623 19014 37624 16396 37624 16397 37624 19014 37625 16397 37625 19015 37625 19012 37626 19001 37626 19016 37626 19016 37627 19001 37627 19018 37627 19016 37628 19018 37628 19017 37628 19017 37629 19018 37629 16400 37629 16400 37630 19018 37630 18997 37630 16400 37631 18997 37631 16402 37631 19025 37632 19019 37632 19023 37632 19023 37633 19019 37633 19185 37633 19023 37634 19185 37634 19022 37634 19022 37635 19185 37635 19184 37635 19022 37636 19184 37636 19033 37636 19033 37637 19184 37637 19183 37637 19033 37638 19183 37638 19032 37638 19032 37639 19183 37639 19020 37639 19032 37640 19020 37640 19031 37640 19031 37641 19020 37641 19190 37641 19031 37642 19190 37642 19029 37642 19029 37643 19190 37643 19189 37643 19033 37644 19021 37644 19022 37644 19022 37645 19021 37645 19036 37645 19022 37646 19036 37646 19023 37646 19023 37647 19036 37647 19024 37647 19023 37648 19024 37648 19025 37648 19025 37649 19024 37649 19034 37649 19025 37650 19034 37650 19026 37650 19026 37651 19034 37651 19834 37651 19026 37652 19834 37652 19839 37652 19839 37653 19834 37653 19835 37653 19839 37654 19835 37654 19838 37654 19835 37655 19830 37655 19838 37655 19838 37656 19830 37656 19028 37656 19838 37657 19028 37657 19027 37657 19027 37658 19028 37658 19829 37658 19027 37659 19829 37659 19836 37659 19836 37660 19829 37660 19825 37660 19836 37661 19825 37661 19029 37661 19029 37662 19825 37662 19030 37662 19029 37663 19030 37663 19031 37663 19031 37664 19030 37664 19043 37664 19031 37665 19043 37665 19032 37665 19032 37666 19043 37666 19042 37666 19032 37667 19042 37667 19033 37667 19033 37668 19042 37668 19040 37668 19033 37669 19040 37669 19021 37669 20057 37670 16232 37670 19034 37670 19034 37671 16232 37671 16233 37671 19034 37672 16233 37672 19035 37672 19034 37673 19024 37673 20057 37673 20057 37674 19024 37674 19036 37674 20057 37675 19036 37675 20056 37675 20056 37676 19036 37676 19037 37676 19037 37677 19036 37677 19021 37677 19037 37678 19021 37678 19038 37678 19038 37679 19021 37679 19039 37679 19039 37680 19021 37680 19040 37680 19039 37681 19040 37681 20052 37681 20052 37682 19040 37682 19041 37682 19041 37683 19040 37683 19042 37683 19041 37684 19042 37684 20049 37684 20049 37685 19042 37685 19044 37685 19044 37686 19042 37686 19043 37686 19044 37687 19043 37687 20048 37687 20048 37688 19043 37688 19030 37688 20048 37689 19030 37689 19823 37689 19052 37690 19102 37690 19045 37690 19045 37691 19102 37691 19046 37691 19045 37692 19046 37692 19050 37692 19050 37693 19046 37693 19101 37693 19050 37694 19101 37694 19047 37694 19047 37695 19101 37695 19048 37695 19047 37696 19048 37696 19062 37696 19062 37697 19048 37697 19124 37697 19062 37698 19124 37698 19061 37698 19061 37699 19124 37699 19049 37699 19061 37700 19049 37700 19059 37700 19059 37701 19049 37701 19816 37701 19047 37702 19069 37702 19050 37702 19050 37703 19069 37703 19067 37703 19050 37704 19067 37704 19045 37704 19045 37705 19067 37705 19065 37705 19045 37706 19065 37706 19052 37706 19052 37707 19065 37707 19051 37707 19052 37708 19051 37708 19819 37708 19819 37709 19051 37709 19811 37709 19819 37710 19811 37710 19053 37710 19053 37711 19811 37711 19812 37711 19053 37712 19812 37712 19054 37712 19812 37713 19815 37713 19054 37713 19054 37714 19815 37714 19055 37714 19054 37715 19055 37715 19056 37715 19056 37716 19055 37716 19806 37716 19056 37717 19806 37717 19057 37717 19057 37718 19806 37718 19058 37718 19057 37719 19058 37719 19059 37719 19059 37720 19058 37720 19060 37720 19059 37721 19060 37721 19061 37721 19061 37722 19060 37722 19075 37722 19061 37723 19075 37723 19062 37723 19062 37724 19075 37724 19074 37724 19062 37725 19074 37725 19047 37725 19047 37726 19074 37726 19071 37726 19047 37727 19071 37727 19069 37727 19063 37728 19051 37728 19064 37728 19064 37729 19051 37729 19065 37729 19064 37730 19065 37730 20032 37730 20032 37731 19065 37731 19067 37731 20032 37732 19067 37732 19066 37732 19066 37733 19067 37733 20031 37733 20031 37734 19067 37734 19068 37734 19068 37735 19067 37735 19069 37735 19068 37736 19069 37736 19070 37736 19072 37737 20035 37737 19071 37737 19071 37738 20035 37738 20034 37738 19071 37739 20034 37739 19069 37739 19069 37740 20034 37740 20033 37740 19069 37741 20033 37741 19070 37741 19072 37742 19071 37742 19073 37742 19073 37743 19071 37743 19074 37743 19073 37744 19074 37744 20021 37744 19075 37745 20024 37745 19074 37745 19074 37746 20024 37746 19076 37746 19074 37747 19076 37747 20021 37747 19077 37748 16283 37748 19060 37748 19060 37749 16283 37749 19078 37749 19060 37750 19078 37750 19075 37750 19075 37751 19078 37751 19079 37751 19075 37752 19079 37752 20024 37752 19213 37753 19214 37753 19080 37753 19116 37754 19119 37754 17529 37754 17529 37755 19119 37755 19144 37755 17529 37756 19144 37756 19081 37756 19114 37757 17524 37757 19082 37757 19083 37758 17527 37758 19132 37758 19103 37759 19084 37759 19121 37759 19085 37760 17546 37760 19208 37760 17548 37761 19086 37761 19195 37761 19195 37762 19086 37762 19205 37762 19087 37763 19088 37763 19093 37763 19203 37764 19089 37764 19204 37764 19204 37765 19089 37765 15991 37765 19090 37766 19207 37766 19091 37766 19091 37767 19207 37767 19204 37767 19091 37768 19204 37768 15958 37768 15958 37769 19204 37769 15991 37769 15958 37770 15991 37770 19095 37770 19088 37771 16005 37771 19093 37771 19093 37772 16005 37772 19092 37772 19093 37773 19092 37773 19215 37773 19098 37774 16008 37774 15977 37774 15977 37775 16008 37775 19094 37775 15977 37776 19094 37776 15975 37776 15975 37777 19094 37777 15956 37777 15975 37778 15956 37778 15994 37778 15994 37779 15956 37779 19095 37779 15994 37780 19095 37780 19096 37780 19096 37781 19095 37781 15991 37781 19137 37782 19097 37782 19203 37782 19203 37783 19097 37783 15989 37783 19203 37784 15989 37784 19089 37784 15981 37785 15982 37785 19169 37785 19169 37786 15982 37786 15984 37786 19169 37787 15984 37787 19137 37787 19137 37788 15984 37788 15986 37788 19137 37789 15986 37789 19097 37789 19098 37790 19099 37790 19173 37790 19173 37791 19099 37791 19171 37791 19208 37792 17546 37792 19195 37792 19195 37793 17546 37793 17547 37793 19195 37794 17547 37794 17548 37794 19210 37795 19100 37795 19101 37795 19101 37796 19046 37796 19210 37796 19210 37797 19046 37797 19102 37797 19210 37798 19102 37798 19084 37798 19084 37799 19102 37799 19821 37799 19084 37800 19821 37800 19121 37800 19103 37801 19121 37801 17544 37801 17544 37802 19121 37802 19123 37802 17544 37803 19123 37803 17542 37803 19181 37804 19104 37804 19179 37804 19179 37805 19104 37805 17539 37805 19179 37806 17539 37806 19182 37806 19182 37807 17539 37807 17541 37807 19182 37808 17541 37808 17542 37808 19133 37809 19105 37809 19149 37809 19149 37810 19105 37810 17528 37810 17522 37811 19107 37811 19106 37811 19106 37812 19107 37812 19108 37812 18926 37813 19898 37813 19106 37813 19109 37814 17523 37814 19113 37814 19113 37815 19110 37815 19109 37815 19109 37816 19110 37816 18929 37816 19109 37817 18929 37817 18927 37817 19892 37818 17522 37818 19894 37818 19894 37819 17522 37819 19106 37819 19894 37820 19106 37820 19897 37820 19897 37821 19106 37821 19898 37821 19892 37822 19891 37822 17522 37822 17522 37823 19891 37823 19111 37823 17522 37824 19111 37824 17523 37824 17523 37825 19111 37825 19112 37825 17523 37826 19112 37826 19113 37826 19114 37827 19082 37827 19980 37827 19120 37828 19935 37828 19115 37828 19120 37829 19115 37829 17530 37829 18860 37830 19116 37830 18861 37830 18861 37831 19116 37831 19117 37831 18861 37832 19117 37832 19933 37832 19933 37833 19117 37833 17530 37833 19933 37834 17530 37834 19118 37834 19118 37835 17530 37835 19115 37835 18860 37836 18858 37836 19116 37836 19116 37837 18858 37837 18857 37837 19116 37838 18857 37838 19119 37838 19119 37839 18857 37839 18856 37839 19119 37840 18856 37840 19144 37840 19144 37841 18856 37841 18855 37841 19935 37842 19120 37842 19936 37842 19936 37843 19120 37843 19125 37843 19936 37844 19125 37844 19200 37844 19821 37845 19820 37845 19121 37845 19121 37846 19820 37846 19818 37846 19121 37847 19818 37847 19123 37847 19123 37848 19818 37848 19122 37848 19122 37849 19817 37849 19123 37849 19123 37850 19817 37850 19816 37850 19123 37851 19816 37851 19213 37851 19816 37852 19049 37852 19213 37852 19213 37853 19049 37853 19124 37853 19213 37854 19124 37854 19100 37854 19100 37855 19124 37855 19048 37855 19100 37856 19048 37856 19101 37856 17530 37857 19980 37857 19120 37857 19120 37858 19980 37858 19082 37858 19120 37859 19082 37859 19125 37859 19125 37860 19082 37860 19139 37860 19125 37861 19139 37861 19202 37861 19202 37862 19139 37862 19141 37862 19126 37863 18963 37863 19127 37863 19875 37864 19134 37864 19877 37864 19877 37865 19134 37865 19878 37865 19128 37866 19129 37866 19149 37866 19149 37867 19129 37867 19130 37867 19149 37868 19130 37868 19131 37868 17527 37869 17526 37869 19132 37869 19132 37870 17526 37870 19133 37870 19132 37871 19133 37871 19134 37871 19134 37872 19133 37872 19149 37872 19134 37873 19149 37873 19878 37873 19878 37874 19149 37874 19131 37874 19875 37875 19126 37875 19134 37875 19134 37876 19126 37876 19127 37876 19134 37877 19127 37877 19132 37877 19132 37878 19127 37878 19106 37878 19132 37879 19106 37879 19083 37879 19083 37880 19106 37880 19108 37880 18959 37881 19135 37881 18961 37881 18961 37882 19135 37882 19127 37882 18961 37883 19127 37883 19136 37883 19136 37884 19127 37884 18963 37884 16000 37885 19141 37885 15998 37885 15998 37886 19141 37886 19169 37886 15998 37887 19169 37887 15996 37887 19137 37888 19202 37888 15966 37888 15966 37889 15967 37889 19137 37889 19137 37890 15967 37890 15969 37890 19137 37891 15969 37891 15971 37891 16000 37892 16002 37892 19141 37892 19141 37893 16002 37893 16004 37893 19141 37894 16004 37894 19202 37894 19202 37895 16004 37895 15964 37895 19202 37896 15964 37896 15966 37896 15971 37897 15972 37897 19137 37897 19137 37898 15972 37898 15974 37898 19137 37899 15974 37899 19169 37899 19169 37900 15974 37900 19138 37900 19169 37901 19138 37901 15996 37901 17524 37902 17523 37902 19082 37902 19082 37903 17523 37903 19109 37903 19082 37904 19109 37904 19139 37904 19139 37905 19109 37905 19140 37905 19139 37906 19140 37906 19141 37906 19141 37907 19140 37907 19145 37907 19141 37908 19145 37908 19169 37908 19169 37909 19145 37909 19146 37909 19142 37910 17538 37910 19143 37910 19143 37911 17538 37911 17537 37911 19143 37912 17537 37912 19201 37912 19201 37913 17537 37913 17536 37913 19201 37914 17536 37914 19144 37914 19144 37915 17536 37915 17535 37915 19144 37916 17535 37916 19081 37916 18927 37917 18926 37917 19109 37917 19109 37918 18926 37918 19106 37918 19109 37919 19106 37919 19140 37919 19140 37920 19106 37920 19127 37920 19140 37921 19127 37921 19145 37921 19145 37922 19127 37922 19135 37922 19145 37923 19135 37923 19146 37923 19146 37924 19135 37924 19147 37924 19146 37925 19147 37925 19172 37925 19172 37926 19147 37926 19148 37926 18959 37927 19128 37927 19135 37927 19135 37928 19128 37928 19149 37928 19135 37929 19149 37929 19147 37929 19147 37930 19149 37930 19162 37930 19147 37931 19162 37931 19148 37931 19148 37932 19162 37932 19150 37932 19151 37933 19152 37933 19154 37933 19154 37934 19152 37934 19153 37934 19158 37935 17538 37935 19918 37935 19918 37936 17538 37936 19142 37936 19918 37937 19142 37937 19157 37937 19153 37938 19923 37938 19154 37938 19154 37939 19923 37939 19155 37939 19154 37940 19155 37940 19142 37940 19142 37941 19155 37941 19156 37941 19142 37942 19156 37942 19157 37942 19158 37943 19159 37943 17538 37943 17538 37944 19159 37944 19160 37944 17538 37945 19160 37945 19176 37945 19176 37946 19160 37946 19161 37946 19854 37947 18995 37947 19150 37947 17528 37948 17532 37948 19149 37948 19149 37949 17532 37949 19163 37949 19149 37950 19163 37950 19162 37950 19162 37951 19163 37951 19164 37951 19162 37952 19164 37952 19150 37952 19150 37953 19164 37953 19165 37953 19150 37954 19165 37954 19854 37954 18995 37955 18994 37955 19150 37955 19150 37956 18994 37956 19166 37956 19150 37957 19166 37957 18993 37957 19175 37958 18991 37958 19174 37958 19174 37959 18991 37959 19167 37959 19174 37960 19167 37960 19180 37960 19180 37961 19167 37961 19858 37961 19858 37962 19856 37962 19180 37962 19180 37963 19856 37963 19168 37963 19180 37964 19168 37964 19165 37964 19165 37965 19168 37965 19855 37965 19165 37966 19855 37966 19854 37966 15981 37967 19169 37967 19170 37967 19170 37968 19169 37968 19146 37968 19170 37969 19146 37969 19171 37969 19171 37970 19146 37970 19172 37970 19171 37971 19172 37971 19173 37971 19173 37972 19172 37972 19148 37972 19173 37973 19148 37973 19178 37973 19178 37974 19148 37974 19150 37974 19178 37975 19150 37975 19174 37975 19174 37976 19150 37976 18993 37976 19174 37977 18993 37977 19175 37977 19161 37978 19151 37978 19176 37978 19176 37979 19151 37979 19154 37979 19176 37980 19154 37980 17533 37980 17533 37981 19154 37981 19177 37981 17533 37982 19177 37982 17534 37982 17534 37983 19177 37983 19205 37983 17534 37984 19205 37984 17550 37984 17550 37985 19205 37985 19086 37985 19098 37986 19173 37986 19214 37986 19214 37987 19173 37987 19178 37987 19214 37988 19178 37988 19080 37988 19080 37989 19178 37989 19174 37989 19080 37990 19174 37990 19179 37990 19179 37991 19174 37991 19180 37991 19179 37992 19180 37992 19181 37992 17542 37993 19123 37993 19182 37993 19182 37994 19123 37994 19019 37994 19182 37995 19019 37995 19840 37995 19213 37996 19080 37996 19123 37996 19123 37997 19080 37997 19020 37997 19123 37998 19020 37998 19183 37998 19183 37999 19184 37999 19123 37999 19123 38000 19184 38000 19185 38000 19123 38001 19185 38001 19019 38001 19188 38002 19179 38002 19186 38002 19186 38003 19179 38003 19182 38003 19186 38004 19182 38004 19187 38004 19187 38005 19182 38005 19840 38005 19188 38006 19837 38006 19179 38006 19179 38007 19837 38007 19189 38007 19179 38008 19189 38008 19080 38008 19080 38009 19189 38009 19190 38009 19080 38010 19190 38010 19020 38010 19206 38011 19192 38011 19205 38011 19196 38012 19195 38012 19191 38012 19191 38013 19195 38013 19205 38013 19191 38014 19205 38014 18903 38014 18903 38015 19205 38015 19192 38015 19193 38016 19208 38016 19194 38016 19194 38017 19208 38017 19195 38017 19194 38018 19195 38018 18899 38018 18899 38019 19195 38019 19196 38019 19193 38020 19915 38020 19208 38020 19208 38021 19915 38021 19197 38021 19208 38022 19197 38022 19198 38022 19197 38023 19911 38023 19198 38023 19198 38024 19911 38024 19910 38024 19198 38025 19910 38025 19199 38025 18855 38026 19200 38026 19144 38026 19144 38027 19200 38027 19125 38027 19144 38028 19125 38028 19201 38028 19201 38029 19125 38029 19202 38029 19201 38030 19202 38030 19143 38030 19143 38031 19202 38031 19137 38031 19143 38032 19137 38032 19142 38032 19142 38033 19137 38033 19203 38033 19142 38034 19203 38034 19154 38034 19154 38035 19203 38035 19204 38035 19154 38036 19204 38036 19177 38036 19177 38037 19204 38037 19207 38037 19177 38038 19207 38038 19205 38038 19205 38039 19207 38039 19198 38039 19205 38040 19198 38040 19206 38040 19206 38041 19198 38041 19199 38041 19090 38042 19087 38042 19207 38042 19207 38043 19087 38043 19093 38043 19207 38044 19093 38044 19198 38044 19198 38045 19093 38045 19212 38045 19198 38046 19212 38046 19208 38046 19208 38047 19212 38047 19209 38047 19208 38048 19209 38048 19085 38048 19085 38049 19209 38049 19211 38049 19210 38050 19211 38050 19100 38050 19100 38051 19211 38051 19209 38051 19100 38052 19209 38052 19213 38052 19213 38053 19209 38053 19212 38053 19213 38054 19212 38054 19214 38054 19214 38055 19212 38055 19093 38055 19214 38056 19093 38056 19098 38056 19098 38057 19093 38057 19215 38057 19098 38058 19215 38058 16008 38058 17555 38059 17586 38059 17553 38059 17553 38060 17586 38060 17585 38060 17553 38061 17585 38061 17584 38061 19216 38062 17606 38062 17552 38062 17552 38063 17606 38063 19218 38063 17584 38064 17583 38064 17553 38064 17553 38065 17583 38065 19217 38065 17553 38066 19217 38066 17552 38066 17552 38067 19217 38067 17607 38067 17552 38068 17607 38068 19216 38068 19218 38069 17605 38069 17552 38069 17552 38070 17605 38070 17603 38070 17552 38071 17603 38071 19229 38071 17551 38072 17628 38072 19219 38072 19219 38073 19220 38073 17551 38073 17551 38074 19220 38074 19221 38074 17551 38075 19221 38075 17653 38075 19222 38076 17631 38076 19223 38076 19223 38077 17631 38077 17630 38077 19223 38078 17630 38078 17551 38078 17551 38079 17630 38079 19224 38079 17551 38080 19224 38080 17628 38080 17635 38081 17634 38081 19225 38081 19225 38082 17634 38082 17633 38082 19225 38083 17633 38083 19223 38083 19223 38084 17633 38084 17632 38084 19223 38085 17632 38085 19222 38085 17640 38086 17638 38086 17549 38086 17549 38087 17638 38087 17637 38087 17549 38088 17637 38088 19225 38088 19225 38089 17637 38089 17636 38089 19225 38090 17636 38090 17635 38090 17640 38091 17549 38091 17641 38091 17641 38092 17549 38092 19226 38092 17641 38093 19226 38093 19228 38093 17545 38094 19227 38094 19226 38094 19226 38095 19227 38095 17642 38095 19226 38096 17642 38096 19228 38096 17552 38097 19229 38097 17545 38097 17545 38098 19229 38098 17644 38098 17644 38099 19230 38099 17545 38099 17545 38100 19230 38100 17643 38100 17545 38101 17643 38101 19227 38101 17685 38102 17684 38102 17531 38102 17531 38103 17684 38103 17682 38103 17531 38104 17682 38104 19231 38104 19231 38105 17682 38105 19240 38105 19231 38106 19240 38106 19243 38106 17685 38107 17531 38107 17679 38107 17679 38108 17531 38108 19233 38108 17679 38109 19233 38109 17680 38109 17672 38110 17678 38110 19232 38110 19232 38111 17678 38111 17677 38111 19232 38112 17677 38112 19233 38112 19233 38113 17677 38113 17676 38113 19233 38114 17676 38114 17680 38114 17672 38115 19232 38115 17674 38115 17674 38116 19232 38116 19234 38116 17674 38117 19234 38117 17675 38117 19237 38118 17666 38118 19234 38118 19234 38119 17666 38119 17671 38119 19234 38120 17671 38120 17675 38120 17691 38121 19235 38121 17689 38121 17689 38122 19235 38122 19516 38122 17691 38123 19236 38123 19235 38123 19235 38124 19236 38124 17669 38124 19235 38125 17669 38125 19237 38125 19237 38126 17669 38126 17667 38126 19237 38127 17667 38127 17666 38127 17646 38128 19238 38128 17521 38128 19238 38129 17650 38129 17521 38129 17521 38130 17650 38130 19239 38130 17521 38131 19239 38131 17651 38131 19240 38132 17654 38132 19243 38132 19243 38133 17654 38133 19241 38133 19243 38134 19241 38134 19242 38134 19242 38135 17658 38135 19243 38135 19243 38136 17658 38136 19244 38136 19243 38137 19244 38137 17521 38137 17521 38138 19244 38138 19245 38138 17521 38139 19245 38139 17646 38139 17589 38140 19259 38140 17625 38140 17625 38141 19259 38141 17626 38141 19248 38142 19246 38142 19247 38142 19247 38143 19246 38143 19251 38143 19247 38144 19251 38144 17624 38144 19248 38145 17623 38145 19246 38145 19246 38146 17623 38146 19249 38146 19246 38147 19249 38147 19259 38147 19259 38148 19249 38148 17627 38148 19259 38149 17627 38149 17626 38149 19250 38150 19252 38150 19251 38150 19251 38151 19252 38151 19253 38151 19251 38152 19253 38152 17624 38152 17613 38153 19254 38153 19255 38153 19255 38154 19254 38154 17622 38154 19255 38155 17622 38155 19251 38155 19251 38156 17622 38156 17621 38156 19251 38157 17621 38157 19250 38157 19256 38158 17617 38158 17525 38158 17525 38159 17617 38159 17615 38159 17525 38160 17615 38160 19255 38160 19255 38161 17615 38161 19257 38161 19255 38162 19257 38162 17613 38162 17521 38163 17651 38163 19258 38163 17521 38164 19258 38164 17525 38164 17525 38165 19258 38165 17618 38165 17525 38166 17618 38166 19256 38166 17580 38167 17568 38167 19273 38167 17580 38168 19273 38168 17579 38168 17589 38169 17591 38169 19259 38169 19259 38170 17591 38170 17592 38170 17592 38171 17590 38171 19259 38171 19259 38172 17590 38172 17594 38172 19259 38173 17594 38173 17595 38173 17571 38174 17572 38174 19273 38174 19273 38175 17572 38175 17574 38175 17595 38176 17597 38176 19259 38176 19259 38177 17597 38177 17599 38177 19259 38178 17599 38178 19273 38178 19273 38179 17599 38179 17569 38179 19273 38180 17569 38180 17571 38180 17574 38181 17575 38181 19273 38181 19273 38182 17575 38182 17577 38182 19273 38183 17577 38183 17579 38183 17558 38184 17556 38184 17543 38184 17543 38185 17556 38185 17553 38185 17553 38186 17556 38186 19260 38186 17553 38187 19260 38187 17555 38187 19268 38188 19261 38188 19267 38188 19267 38189 19261 38189 19262 38189 19262 38190 17560 38190 19267 38190 19267 38191 17560 38191 17559 38191 19267 38192 17559 38192 17543 38192 17543 38193 17559 38193 19263 38193 17543 38194 19263 38194 17558 38194 17540 38195 17562 38195 19264 38195 19264 38196 19265 38196 17540 38196 17540 38197 19265 38197 19266 38197 17540 38198 19266 38198 19267 38198 19267 38199 19266 38199 17561 38199 19267 38200 17561 38200 19268 38200 17566 38201 17564 38201 19269 38201 19269 38202 17564 38202 19270 38202 19269 38203 19270 38203 17540 38203 17540 38204 19270 38204 19271 38204 17540 38205 19271 38205 17562 38205 17568 38206 19272 38206 19273 38206 19273 38207 19272 38207 17567 38207 19273 38208 17567 38208 19269 38208 19269 38209 17567 38209 19274 38209 19269 38210 19274 38210 17566 38210 19275 38211 19276 38211 19327 38211 17611 38212 19277 38212 19327 38212 19327 38213 19277 38213 19368 38213 19322 38214 17649 38214 17648 38214 18211 38215 18808 38215 18213 38215 19371 38216 19278 38216 19359 38216 19359 38217 19278 38217 19279 38217 17225 38218 17226 38218 19359 38218 19454 38219 17221 38219 19284 38219 17141 38220 19280 38220 19454 38220 19454 38221 19280 38221 17143 38221 19454 38222 17143 38222 19434 38222 17124 38223 19282 38223 19281 38223 19281 38224 19282 38224 17214 38224 19281 38225 17214 38225 17208 38225 17124 38226 17125 38226 19282 38226 19282 38227 17125 38227 17126 38227 19282 38228 17126 38228 17217 38228 17217 38229 17126 38229 19283 38229 17217 38230 19283 38230 19284 38230 19284 38231 19283 38231 19285 38231 19284 38232 19285 38232 19454 38232 19454 38233 19285 38233 17129 38233 19454 38234 17129 38234 17141 38234 19286 38235 18198 38235 19287 38235 17282 38236 19286 38236 19288 38236 19288 38237 19286 38237 19287 38237 19288 38238 19287 38238 17280 38238 17280 38239 19287 38239 17216 38239 17280 38240 17216 38240 19289 38240 19289 38241 17216 38241 17224 38241 19289 38242 17224 38242 19279 38242 19279 38243 17224 38243 19290 38243 19279 38244 19290 38244 19359 38244 19359 38245 19290 38245 17222 38245 19359 38246 17222 38246 17225 38246 17421 38247 17424 38247 19292 38247 17360 38248 17359 38248 19370 38248 19301 38249 17360 38249 19291 38249 19291 38250 17360 38250 19370 38250 19291 38251 19370 38251 17420 38251 17420 38252 19370 38252 19292 38252 17420 38253 19292 38253 17428 38253 17428 38254 19292 38254 17424 38254 17359 38255 17366 38255 19370 38255 19370 38256 17366 38256 19293 38256 19370 38257 19293 38257 19296 38257 18200 38258 17278 38258 19294 38258 18201 38259 18200 38259 17351 38259 17351 38260 18200 38260 19294 38260 17351 38261 19294 38261 17349 38261 17349 38262 19294 38262 17283 38262 17349 38263 17283 38263 17356 38263 17356 38264 17283 38264 19295 38264 17356 38265 19295 38265 19296 38265 19296 38266 19295 38266 17292 38266 19296 38267 17292 38267 19370 38267 19370 38268 17292 38268 19297 38268 19370 38269 19297 38269 17288 38269 18206 38270 18205 38270 19300 38270 17413 38271 18206 38271 19298 38271 19298 38272 18206 38272 19300 38272 19298 38273 19300 38273 19299 38273 19299 38274 19300 38274 17365 38274 19299 38275 17365 38275 17418 38275 17418 38276 17365 38276 19302 38276 17418 38277 19302 38277 19301 38277 19301 38278 19302 38278 19303 38278 19301 38279 19303 38279 17360 38279 17411 38280 17480 38280 18208 38280 18208 38281 17480 38281 19304 38281 18208 38282 19304 38282 18209 38282 19305 38283 18010 38283 19312 38283 19308 38284 19307 38284 19306 38284 19306 38285 19307 38285 19363 38285 19306 38286 19363 38286 17500 38286 19308 38287 19309 38287 19307 38287 19307 38288 19309 38288 18007 38288 19307 38289 18007 38289 19305 38289 19312 38290 18010 38290 17497 38290 17411 38291 17414 38291 17480 38291 17480 38292 17414 38292 19310 38292 17480 38293 19310 38293 17483 38293 17483 38294 19310 38294 17426 38294 17483 38295 17426 38295 19311 38295 19311 38296 17426 38296 17421 38296 19311 38297 17421 38297 17488 38297 17488 38298 17421 38298 19292 38298 17488 38299 19292 38299 17489 38299 17489 38300 19292 38300 17499 38300 19305 38301 19312 38301 19307 38301 19307 38302 19312 38302 17494 38302 19307 38303 17494 38303 19292 38303 19292 38304 17494 38304 19313 38304 19292 38305 19313 38305 17499 38305 18010 38306 19314 38306 17497 38306 17497 38307 19314 38307 18011 38307 17497 38308 18011 38308 19315 38308 19315 38309 18011 38309 19316 38309 19315 38310 19316 38310 17481 38310 17481 38311 19316 38311 18808 38311 17481 38312 18808 38312 19317 38312 19317 38313 18808 38313 18211 38313 19318 38314 19369 38314 19321 38314 19321 38315 17503 38315 19318 38315 19318 38316 17503 38316 17502 38316 19318 38317 17502 38317 19363 38317 19363 38318 17502 38318 19319 38318 19363 38319 19319 38319 17500 38319 19369 38320 19320 38320 19321 38320 19321 38321 19320 38321 19322 38321 19321 38322 19322 38322 19323 38322 19323 38323 19322 38323 17507 38323 17507 38324 19322 38324 19324 38324 19324 38325 19322 38325 17648 38325 19324 38326 17648 38326 17647 38326 19325 38327 19329 38327 19276 38327 19276 38328 19329 38328 19326 38328 19276 38329 19326 38329 19327 38329 19327 38330 19326 38330 17612 38330 19327 38331 17612 38331 17611 38331 19325 38332 19328 38332 19329 38332 19329 38333 19328 38333 20104 38333 19329 38334 20104 38334 17616 38334 17616 38335 20104 38335 19330 38335 17616 38336 19330 38336 17614 38336 17614 38337 19330 38337 20109 38337 17614 38338 20109 38338 19331 38338 20109 38339 19332 38339 19331 38339 19331 38340 19332 38340 16183 38340 19331 38341 16183 38341 17620 38341 17620 38342 16183 38342 19333 38342 17620 38343 19333 38343 19334 38343 19333 38344 16182 38344 19334 38344 19334 38345 16182 38345 19335 38345 19334 38346 19335 38346 17619 38346 17619 38347 19335 38347 16205 38347 17619 38348 16205 38348 19336 38348 19336 38349 16205 38349 16204 38349 19336 38350 16204 38350 19337 38350 19375 38351 17609 38351 17610 38351 16204 38352 16203 38352 19337 38352 19337 38353 16203 38353 19338 38353 19337 38354 19338 38354 19339 38354 19339 38355 19338 38355 16187 38355 19339 38356 16187 38356 19340 38356 19340 38357 16187 38357 19361 38357 19340 38358 19361 38358 17610 38358 19342 38359 19341 38359 19375 38359 19375 38360 19341 38360 17588 38360 19375 38361 17588 38361 17609 38361 19374 38362 19345 38362 19342 38362 19342 38363 19345 38363 19343 38363 19342 38364 19343 38364 19341 38364 19373 38365 19348 38365 19374 38365 19374 38366 19348 38366 19344 38366 19374 38367 19344 38367 19345 38367 17598 38368 17596 38368 19346 38368 19346 38369 17596 38369 17593 38369 19346 38370 17593 38370 19373 38370 19373 38371 17593 38371 19347 38371 19373 38372 19347 38372 19348 38372 16385 38373 16419 38373 19349 38373 19349 38374 16419 38374 16418 38374 19349 38375 16418 38375 19350 38375 19350 38376 16418 38376 19351 38376 19350 38377 19351 38377 16417 38377 19354 38378 19356 38378 19352 38378 19352 38379 19356 38379 19350 38379 19352 38380 19350 38380 19353 38380 19353 38381 19350 38381 16417 38381 19354 38382 19379 38382 19356 38382 19356 38383 19379 38383 19355 38383 19356 38384 19355 38384 19357 38384 16387 38385 19359 38385 19454 38385 19454 38386 19359 38386 17226 38386 19454 38387 17226 38387 17221 38387 16387 38388 19358 38388 19359 38388 19359 38389 19358 38389 19360 38389 19359 38390 19360 38390 19372 38390 17610 38391 19361 38391 19375 38391 19375 38392 19361 38392 16185 38392 19375 38393 16185 38393 19362 38393 19376 38394 20146 38394 19363 38394 19363 38395 20146 38395 20103 38395 19363 38396 20103 38396 19364 38396 19364 38397 20141 38397 19363 38397 19363 38398 20141 38398 19365 38398 19363 38399 19365 38399 19318 38399 19318 38400 19365 38400 19366 38400 19318 38401 19366 38401 19369 38401 17649 38402 19322 38402 19367 38402 19367 38403 19322 38403 19320 38403 19367 38404 19320 38404 19368 38404 19368 38405 19320 38405 19369 38405 19368 38406 19369 38406 19327 38406 19327 38407 19369 38407 19366 38407 19327 38408 19366 38408 19275 38408 17288 38409 19371 38409 19370 38409 19370 38410 19371 38410 19359 38410 19370 38411 19359 38411 19349 38411 19349 38412 19359 38412 19372 38412 19349 38413 19372 38413 16385 38413 19350 38414 17598 38414 19349 38414 19349 38415 17598 38415 19346 38415 19349 38416 19346 38416 19370 38416 19370 38417 19346 38417 19373 38417 19370 38418 19373 38418 19292 38418 19292 38419 19373 38419 19374 38419 19292 38420 19374 38420 19307 38420 19307 38421 19374 38421 19342 38421 19307 38422 19342 38422 19363 38422 19363 38423 19342 38423 19375 38423 19363 38424 19375 38424 19376 38424 19376 38425 19375 38425 19362 38425 18190 38426 18189 38426 16882 38426 18188 38427 16798 38427 16800 38427 18181 38428 19377 38428 19419 38428 16637 38429 19378 38429 19411 38429 19411 38430 19378 38430 19405 38430 19355 38431 19379 38431 16355 38431 17570 38432 19357 38432 19355 38432 19381 38433 19380 38433 17570 38433 19355 38434 16355 38434 17570 38434 17570 38435 16355 38435 16332 38435 17570 38436 16332 38436 19381 38436 16368 38437 19382 38437 19453 38437 19383 38438 17573 38438 19463 38438 19463 38439 17573 38439 17570 38439 19384 38440 19469 38440 19470 38440 19470 38441 19469 38441 17576 38441 17576 38442 19469 38442 17578 38442 17578 38443 19469 38443 19467 38443 17578 38444 19467 38444 19387 38444 19385 38445 19386 38445 19457 38445 19457 38446 19386 38446 17582 38446 19457 38447 17582 38447 19467 38447 19467 38448 17582 38448 17581 38448 19467 38449 17581 38449 19387 38449 16249 38450 19388 38450 19391 38450 19391 38451 17563 38451 16249 38451 16249 38452 17563 38452 17565 38452 16249 38453 17565 38453 19458 38453 19458 38454 17565 38454 19389 38454 19458 38455 19389 38455 19457 38455 19457 38456 19389 38456 19390 38456 19457 38457 19390 38457 19385 38457 19388 38458 19392 38458 19391 38458 19391 38459 19392 38459 16247 38459 19391 38460 16247 38460 19393 38460 19393 38461 16247 38461 16228 38461 19393 38462 16228 38462 19394 38462 16228 38463 16254 38463 19394 38463 19394 38464 16254 38464 19395 38464 19394 38465 19395 38465 19396 38465 19396 38466 19395 38466 20058 38466 19396 38467 20058 38467 19397 38467 19397 38468 20058 38468 20059 38468 19397 38469 20059 38469 19400 38469 19400 38470 20059 38470 19399 38470 19398 38471 17587 38471 19402 38471 19399 38472 20062 38472 19400 38472 19400 38473 20062 38473 19401 38473 19400 38474 19401 38474 17557 38474 17557 38475 19401 38475 19398 38475 17557 38476 19398 38476 17554 38476 17554 38477 19398 38477 19402 38477 17587 38478 19398 38478 19403 38478 19403 38479 19398 38479 19404 38479 19403 38480 19404 38480 19412 38480 19714 38481 19405 38481 19712 38481 19712 38482 19405 38482 19378 38482 19712 38483 19378 38483 19406 38483 19406 38484 19378 38484 16637 38484 19410 38485 16634 38485 19411 38485 19411 38486 16634 38486 19407 38486 19411 38487 19407 38487 16637 38487 19460 38488 19416 38488 16641 38488 19408 38489 16633 38489 19410 38489 19410 38490 16633 38490 19409 38490 19410 38491 19409 38491 16634 38491 16641 38492 19408 38492 19460 38492 19460 38493 19408 38493 19410 38493 19460 38494 19410 38494 19404 38494 19404 38495 19410 38495 19411 38495 19404 38496 19411 38496 19412 38496 19412 38497 19411 38497 19405 38497 19426 38498 16742 38498 19423 38498 19423 38499 16742 38499 16733 38499 19423 38500 16733 38500 19468 38500 19468 38501 16733 38501 16732 38501 19468 38502 16732 38502 16729 38502 16662 38503 16661 38503 19468 38503 16661 38504 16653 38504 19468 38504 19468 38505 16653 38505 16654 38505 19468 38506 16654 38506 19465 38506 16654 38507 19413 38507 19465 38507 19465 38508 19413 38508 19414 38508 19465 38509 19414 38509 19460 38509 19460 38510 19414 38510 19415 38510 19460 38511 19415 38511 19416 38511 16662 38512 19468 38512 19417 38512 19417 38513 19468 38513 16729 38513 19417 38514 16729 38514 19418 38514 19418 38515 16729 38515 16731 38515 19418 38516 16731 38516 19419 38516 18182 38517 18181 38517 19420 38517 19420 38518 18181 38518 19419 38518 19420 38519 19419 38519 16724 38519 16724 38520 19419 38520 16731 38520 16893 38521 19421 38521 19464 38521 16893 38522 19464 38522 16894 38522 19421 38523 16890 38523 19464 38523 19464 38524 16890 38524 16896 38524 19464 38525 16896 38525 16888 38525 19422 38526 16815 38526 19423 38526 16815 38527 16814 38527 19423 38527 19423 38528 16814 38528 16805 38528 19423 38529 16805 38529 16803 38529 19424 38530 16740 38530 19425 38530 19425 38531 16740 38531 16739 38531 19425 38532 16739 38532 16803 38532 16803 38533 16739 38533 16737 38533 16803 38534 16737 38534 19423 38534 19423 38535 16737 38535 16736 38535 19423 38536 16736 38536 19426 38536 19427 38537 19428 38537 18183 38537 19424 38538 19427 38538 16740 38538 16740 38539 19427 38539 18183 38539 16740 38540 18183 38540 16727 38540 16727 38541 18183 38541 18184 38541 19429 38542 18188 38542 19430 38542 19430 38543 18188 38543 16800 38543 19430 38544 16800 38544 19431 38544 19431 38545 16800 38545 16813 38545 19431 38546 16813 38546 19432 38546 19432 38547 16813 38547 16812 38547 19432 38548 16812 38548 16886 38548 16886 38549 16812 38549 16810 38549 16886 38550 16810 38550 16888 38550 16888 38551 16810 38551 19422 38551 16888 38552 19422 38552 19464 38552 19464 38553 19422 38553 19423 38553 16955 38554 18190 38554 16958 38554 16958 38555 18190 38555 16882 38555 16958 38556 16882 38556 16957 38556 16957 38557 16882 38557 16883 38557 16957 38558 16883 38558 16964 38558 19433 38559 16969 38559 19462 38559 19454 38560 19434 38560 17138 38560 17066 38561 19462 38561 17063 38561 17063 38562 19462 38562 19454 38562 17063 38563 19454 38563 17061 38563 19438 38564 19464 38564 19435 38564 19435 38565 19464 38565 19436 38565 16883 38566 16894 38566 16964 38566 16964 38567 16894 38567 19464 38567 16964 38568 19464 38568 19437 38568 19437 38569 19464 38569 19438 38569 18193 38570 16959 38570 19439 38570 18193 38571 19439 38571 19445 38571 17066 38572 19440 38572 19462 38572 19462 38573 19440 38573 19441 38573 19462 38574 19441 38574 19433 38574 19433 38575 19441 38575 19442 38575 19433 38576 19442 38576 19443 38576 19443 38577 19442 38577 17058 38577 19443 38578 17058 38578 16960 38578 16960 38579 17058 38579 17052 38579 16960 38580 17052 38580 19439 38580 19439 38581 17052 38581 19444 38581 19439 38582 19444 38582 19445 38582 19446 38583 17051 38583 19447 38583 19446 38584 19447 38584 17128 38584 19454 38585 17138 38585 17061 38585 17061 38586 17138 38586 17135 38586 17061 38587 17135 38587 17065 38587 17065 38588 17135 38588 19448 38588 17065 38589 19448 38589 19449 38589 19449 38590 19448 38590 19450 38590 19449 38591 19450 38591 19447 38591 19447 38592 19450 38592 19451 38592 19447 38593 19451 38593 17128 38593 19382 38594 16367 38594 19453 38594 19453 38595 16367 38595 19452 38595 19453 38596 19452 38596 19462 38596 16387 38597 19454 38597 16365 38597 16365 38598 19454 38598 19462 38598 16365 38599 19462 38599 16366 38599 16366 38600 19462 38600 19452 38600 20065 38601 19465 38601 20066 38601 20066 38602 19465 38602 19455 38602 19466 38603 19456 38603 19457 38603 19457 38604 19456 38604 16221 38604 16221 38605 16218 38605 19457 38605 19457 38606 16218 38606 16250 38606 19457 38607 16250 38607 19458 38607 19398 38608 20060 38608 19404 38608 19404 38609 20060 38609 19459 38609 19404 38610 19459 38610 19460 38610 19460 38611 19459 38611 20064 38611 19460 38612 20064 38612 19465 38612 19465 38613 20064 38613 19461 38613 19465 38614 19461 38614 19455 38614 19380 38615 16368 38615 17570 38615 17570 38616 16368 38616 19453 38616 17570 38617 19453 38617 19463 38617 19463 38618 19453 38618 19462 38618 19463 38619 19462 38619 19464 38619 19464 38620 19462 38620 16969 38620 19464 38621 16969 38621 19436 38621 20065 38622 19466 38622 19465 38622 19465 38623 19466 38623 19457 38623 19465 38624 19457 38624 19468 38624 19468 38625 19457 38625 19467 38625 19468 38626 19467 38626 19423 38626 19423 38627 19467 38627 19469 38627 19423 38628 19469 38628 19464 38628 19464 38629 19469 38629 19384 38629 19464 38630 19384 38630 19463 38630 19463 38631 19384 38631 19470 38631 19463 38632 19470 38632 19383 38632 16505 38633 18834 38633 19471 38633 19471 38634 18834 38634 18837 38634 19471 38635 18837 38635 16578 38635 16578 38636 18837 38636 19473 38636 16600 38637 19472 38637 18843 38637 18843 38638 19472 38638 19475 38638 18842 38639 19476 38639 19473 38639 19473 38640 19476 38640 19474 38640 19473 38641 19474 38641 16578 38641 19472 38642 16574 38642 19475 38642 19475 38643 16574 38643 16575 38643 19475 38644 16575 38644 18842 38644 18842 38645 16575 38645 16576 38645 18842 38646 16576 38646 19476 38646 16600 38647 18843 38647 19477 38647 19477 38648 18843 38648 19481 38648 19477 38649 19481 38649 19478 38649 18852 38650 16497 38650 16528 38650 18852 38651 16528 38651 18846 38651 19488 38652 19479 38652 19481 38652 19481 38653 19479 38653 19480 38653 19480 38654 16566 38654 19481 38654 19481 38655 16566 38655 19482 38655 19481 38656 19482 38656 19478 38656 16528 38657 19483 38657 18846 38657 18846 38658 19483 38658 19484 38658 18846 38659 19484 38659 19485 38659 19485 38660 19484 38660 16535 38660 16535 38661 19486 38661 19485 38661 19485 38662 19486 38662 16558 38662 19485 38663 16558 38663 19488 38663 19488 38664 16558 38664 19487 38664 19488 38665 19487 38665 19479 38665 16492 38666 19489 38666 16459 38666 16459 38667 19489 38667 19491 38667 16459 38668 19491 38668 19490 38668 19490 38669 19491 38669 16448 38669 16448 38670 19491 38670 19492 38670 16448 38671 19492 38671 16449 38671 19496 38672 19493 38672 16443 38672 16443 38673 19494 38673 19496 38673 19496 38674 19494 38674 19495 38674 19496 38675 19495 38675 19492 38675 19492 38676 19495 38676 16453 38676 19492 38677 16453 38677 16449 38677 19493 38678 19496 38678 16434 38678 16434 38679 19496 38679 19497 38679 16434 38680 19497 38680 19498 38680 19498 38681 19497 38681 19499 38681 19499 38682 19497 38682 19500 38682 19499 38683 19500 38683 16481 38683 16505 38684 16504 38684 18834 38684 18834 38685 16504 38685 18824 38685 16481 38686 19500 38686 19501 38686 19501 38687 19500 38687 18822 38687 18823 38688 19502 38688 18822 38688 18822 38689 19502 38689 19503 38689 18822 38690 19503 38690 19501 38690 16504 38691 19504 38691 18824 38691 18824 38692 19504 38692 19505 38692 18824 38693 19505 38693 18823 38693 18823 38694 19505 38694 19506 38694 18823 38695 19506 38695 19502 38695 19803 38696 18891 38696 19507 38696 19507 38697 18891 38697 18888 38697 19507 38698 18888 38698 19508 38698 19508 38699 18888 38699 19989 38699 19989 38700 18888 38700 18887 38700 19989 38701 18887 38701 19509 38701 19509 38702 18887 38702 19510 38702 19510 38703 18887 38703 19511 38703 19510 38704 19511 38704 19990 38704 19990 38705 19511 38705 19512 38705 19512 38706 19511 38706 18898 38706 19512 38707 18898 38707 19513 38707 19513 38708 18898 38708 16304 38708 16304 38709 18898 38709 18896 38709 16304 38710 18896 38710 19514 38710 19514 38711 18896 38711 16306 38711 16306 38712 18896 38712 19792 38712 16306 38713 19792 38713 16308 38713 17661 38714 17551 38714 17660 38714 17660 38715 17551 38715 17653 38715 17692 38716 17693 38716 19235 38716 19235 38717 17693 38717 19515 38717 19235 38718 19515 38718 19516 38718 17661 38719 19517 38719 17551 38719 17551 38720 19517 38720 17686 38720 17551 38721 17686 38721 19235 38721 19235 38722 17686 38722 19518 38722 19235 38723 19518 38723 17692 38723 17789 38724 19519 38724 19644 38724 19746 38725 19605 38725 19520 38725 18163 38726 17164 38726 17159 38726 18164 38727 17245 38727 17239 38727 17243 38728 19595 38728 19594 38728 18172 38729 18171 38729 19589 38729 18177 38730 17446 38730 19521 38730 19574 38731 18805 38731 19522 38731 19564 38732 19523 38732 19561 38732 19561 38733 19523 38733 19324 38733 19652 38734 19524 38734 19546 38734 17670 38735 19527 38735 19531 38735 19527 38736 17670 38736 19636 38736 19636 38737 17670 38737 19525 38737 19636 38738 19525 38738 19526 38738 19526 38739 17668 38739 19636 38739 19636 38740 17668 38740 17664 38740 19636 38741 17664 38741 17665 38741 19527 38742 19528 38742 19529 38742 19527 38743 19529 38743 19531 38743 19531 38744 19529 38744 19530 38744 19531 38745 19530 38745 17673 38745 17673 38746 19530 38746 19532 38746 17673 38747 19532 38747 19533 38747 19532 38748 19534 38748 19533 38748 19533 38749 19534 38749 20230 38749 19533 38750 20230 38750 19535 38750 19535 38751 20230 38751 20231 38751 19535 38752 20231 38752 19536 38752 19633 38753 17681 38753 19536 38753 19537 38754 16111 38754 19541 38754 19537 38755 19541 38755 19538 38755 17681 38756 19633 38756 19539 38756 19539 38757 19633 38757 19538 38757 19539 38758 19538 38758 19540 38758 19540 38759 19538 38759 19541 38759 19540 38760 19541 38760 17683 38760 17683 38761 19541 38761 19654 38761 17683 38762 19654 38762 19542 38762 19543 38763 19652 38763 17655 38763 17655 38764 19652 38764 19546 38764 17655 38765 19546 38765 17656 38765 17656 38766 19546 38766 17657 38766 20155 38767 20156 38767 19549 38767 19561 38768 20152 38768 19548 38768 19548 38769 20152 38769 20150 38769 19548 38770 20150 38770 19544 38770 19544 38771 19545 38771 19548 38771 19548 38772 19545 38772 20153 38772 19548 38773 20153 38773 20154 38773 17657 38774 19546 38774 19547 38774 19547 38775 19546 38775 19548 38775 19547 38776 19548 38776 19549 38776 19549 38777 19548 38777 20154 38777 19549 38778 20154 38778 20155 38778 20156 38779 20158 38779 19549 38779 19549 38780 20158 38780 20160 38780 19549 38781 20160 38781 19550 38781 20160 38782 19551 38782 19550 38782 19550 38783 19551 38783 19552 38783 19550 38784 19552 38784 17659 38784 17659 38785 19552 38785 16132 38785 17659 38786 16132 38786 19553 38786 16132 38787 19554 38787 19553 38787 19553 38788 19554 38788 16131 38788 19553 38789 16131 38789 19555 38789 19555 38790 16131 38790 19556 38790 19555 38791 19556 38791 19557 38791 19557 38792 19556 38792 17647 38792 19559 38793 19324 38793 19558 38793 19558 38794 19324 38794 17647 38794 19558 38795 17647 38795 16134 38795 16134 38796 17647 38796 19556 38796 19559 38797 19560 38797 19324 38797 19324 38798 19560 38798 16138 38798 19324 38799 16138 38799 19561 38799 19561 38800 16138 38800 16137 38800 19561 38801 16137 38801 20152 38801 19546 38802 19562 38802 19548 38802 19548 38803 19562 38803 17513 38803 19548 38804 17513 38804 19561 38804 19561 38805 17513 38805 19563 38805 19561 38806 19563 38806 19564 38806 19565 38807 19566 38807 19524 38807 19524 38808 19566 38808 17509 38808 19524 38809 17509 38809 19546 38809 19546 38810 17509 38810 17511 38810 19546 38811 17511 38811 19562 38811 17517 38812 19567 38812 19657 38812 17517 38813 19657 38813 19573 38813 19577 38814 17431 38814 17430 38814 19577 38815 17430 38815 19571 38815 19571 38816 17430 38816 19568 38816 19571 38817 19568 38817 19569 38817 19522 38818 17995 38818 19569 38818 19569 38819 17995 38819 17996 38819 19570 38820 19571 38820 17998 38820 17998 38821 19571 38821 19569 38821 17998 38822 19569 38822 17997 38822 17997 38823 19569 38823 17996 38823 19570 38824 18003 38824 19571 38824 19571 38825 18003 38825 19572 38825 19571 38826 19572 38826 19657 38826 19657 38827 19572 38827 18004 38827 19657 38828 18004 38828 19573 38828 19569 38829 17438 38829 19522 38829 19522 38830 17438 38830 17437 38830 19522 38831 17437 38831 19574 38831 19574 38832 17437 38832 17441 38832 19574 38833 17441 38833 19575 38833 17373 38834 17371 38834 19583 38834 19583 38835 17371 38835 17370 38835 19583 38836 17370 38836 17369 38836 19583 38837 19582 38837 19577 38837 19577 38838 19582 38838 19576 38838 19577 38839 19576 38839 17431 38839 18176 38840 18177 38840 17382 38840 17382 38841 18177 38841 19521 38841 17382 38842 19521 38842 19578 38842 19578 38843 19521 38843 19580 38843 19578 38844 19580 38844 19579 38844 19579 38845 19580 38845 19581 38845 19579 38846 19581 38846 17379 38846 17379 38847 19581 38847 19582 38847 17379 38848 19582 38848 17377 38848 17377 38849 19582 38849 19583 38849 17377 38850 19583 38850 19584 38850 19584 38851 19583 38851 17369 38851 19585 38852 19586 38852 19592 38852 19586 38853 17297 38853 19592 38853 19592 38854 17297 38854 17295 38854 19592 38855 17295 38855 19583 38855 19583 38856 17295 38856 19587 38856 18173 38857 18172 38857 19588 38857 19588 38858 18172 38858 19589 38858 19588 38859 19589 38859 19590 38859 19590 38860 19589 38860 19591 38860 19590 38861 19591 38861 17304 38861 17304 38862 19591 38862 17373 38862 17304 38863 17373 38863 17306 38863 17306 38864 17373 38864 19583 38864 17306 38865 19583 38865 17308 38865 17308 38866 19583 38866 19587 38866 19597 38867 18167 38867 19596 38867 19585 38868 19592 38868 19593 38868 19593 38869 19592 38869 19594 38869 19593 38870 19594 38870 19596 38870 19596 38871 19594 38871 19595 38871 19596 38872 19595 38872 19597 38872 19612 38873 17230 38873 19605 38873 17238 38874 19599 38874 19592 38874 19605 38875 17230 38875 19592 38875 19592 38876 17230 38876 19598 38876 19592 38877 19598 38877 17238 38877 19599 38878 17237 38878 19592 38878 19592 38879 17237 38879 19600 38879 19592 38880 19600 38880 19594 38880 19594 38881 19600 38881 19601 38881 19594 38882 19601 38882 17243 38882 17161 38883 18164 38883 19602 38883 19602 38884 18164 38884 17239 38884 19602 38885 17239 38885 19606 38885 17069 38886 19746 38886 19603 38886 19603 38887 19746 38887 19666 38887 19603 38888 19666 38888 17071 38888 19604 38889 19605 38889 17148 38889 17148 38890 19605 38890 19746 38890 17148 38891 19746 38891 19618 38891 17239 38892 17241 38892 19606 38892 19606 38893 17241 38893 19607 38893 19606 38894 19607 38894 19608 38894 19608 38895 19607 38895 19609 38895 19608 38896 19609 38896 19610 38896 19610 38897 19609 38897 19612 38897 19610 38898 19612 38898 19611 38898 19611 38899 19612 38899 19605 38899 19611 38900 19605 38900 17144 38900 17144 38901 19605 38901 19604 38901 17086 38902 18163 38902 17084 38902 17084 38903 18163 38903 17159 38903 17084 38904 17159 38904 19613 38904 19613 38905 17159 38905 19614 38905 19613 38906 19614 38906 19616 38906 19616 38907 19614 38907 19615 38907 19616 38908 19615 38908 19617 38908 19617 38909 19615 38909 19618 38909 19617 38910 19618 38910 19619 38910 19619 38911 19618 38911 19746 38911 19619 38912 19746 38912 17075 38912 17075 38913 19746 38913 17069 38913 16543 38914 19620 38914 19592 38914 19620 38915 16550 38915 19592 38915 19592 38916 16550 38916 16524 38916 19592 38917 16524 38917 19605 38917 19605 38918 16524 38918 19621 38918 19605 38919 19621 38919 19520 38919 19659 38920 19658 38920 19622 38920 19622 38921 19658 38921 17795 38921 17795 38922 19658 38922 17796 38922 17796 38923 19658 38923 19623 38923 17796 38924 19623 38924 19624 38924 19624 38925 19623 38925 19646 38925 19624 38926 19646 38926 17794 38926 19625 38927 19626 38927 17792 38927 17792 38928 19626 38928 19649 38928 17792 38929 19649 38929 17773 38929 19650 38930 19643 38930 19627 38930 19644 38931 19519 38931 19643 38931 19643 38932 19519 38932 17790 38932 19643 38933 17790 38933 19627 38933 19642 38934 16109 38934 19628 38934 19628 38935 16109 38935 19629 38935 19628 38936 19629 38936 19637 38936 19637 38937 19629 38937 19630 38937 19637 38938 19630 38938 19631 38938 19635 38939 19632 38939 19633 38939 19633 38940 19632 38940 16112 38940 19633 38941 16112 38941 19538 38941 19536 38942 20231 38942 19633 38942 19633 38943 20231 38943 19634 38943 19633 38944 19634 38944 19635 38944 19631 38945 19639 38945 19637 38945 19637 38946 19639 38946 19636 38946 19637 38947 19636 38947 19645 38947 19645 38948 19636 38948 17665 38948 19645 38949 17665 38949 19638 38949 19639 38950 20194 38950 19636 38950 19636 38951 20194 38951 19640 38951 19636 38952 19640 38952 19527 38952 19527 38953 19640 38953 19641 38953 19527 38954 19641 38954 19528 38954 19653 38955 19642 38955 19650 38955 19650 38956 19642 38956 19628 38956 19650 38957 19628 38957 19643 38957 19643 38958 19628 38958 19637 38958 19643 38959 19637 38959 19644 38959 19644 38960 19637 38960 19645 38960 19644 38961 19645 38961 17789 38961 19623 38962 19656 38962 19646 38962 19646 38963 19656 38963 19626 38963 19646 38964 19626 38964 17794 38964 17794 38965 19626 38965 19625 38965 19656 38966 19647 38966 19626 38966 19626 38967 19647 38967 19648 38967 19626 38968 19648 38968 19649 38968 19649 38969 19648 38969 19650 38969 19649 38970 19650 38970 17773 38970 17773 38971 19650 38971 19627 38971 17773 38972 19627 38972 19651 38972 19651 38973 19627 38973 17790 38973 19542 38974 19654 38974 19543 38974 19543 38975 19654 38975 19655 38975 19543 38976 19655 38976 19652 38976 19652 38977 19655 38977 19657 38977 19652 38978 19657 38978 19524 38978 19524 38979 19657 38979 19567 38979 19524 38980 19567 38980 19565 38980 16111 38981 19653 38981 19541 38981 19541 38982 19653 38982 19650 38982 19541 38983 19650 38983 19654 38983 19654 38984 19650 38984 19648 38984 19654 38985 19648 38985 19655 38985 19655 38986 19648 38986 19647 38986 19655 38987 19647 38987 19657 38987 19657 38988 19647 38988 19656 38988 19657 38989 19656 38989 19571 38989 19571 38990 19656 38990 19623 38990 19571 38991 19623 38991 19577 38991 19577 38992 19623 38992 19658 38992 19577 38993 19658 38993 19583 38993 19583 38994 19658 38994 19659 38994 19583 38995 19659 38995 19592 38995 19592 38996 19659 38996 16544 38996 19592 38997 16544 38997 16543 38997 19775 38998 19778 38998 19779 38998 19771 38999 19763 38999 19660 38999 19738 39000 20279 39000 19661 39000 19662 39001 19768 39001 17639 39001 19768 39002 19662 39002 19751 39002 19729 39003 16265 39003 19727 39003 19676 39004 16910 39004 19663 39004 19671 39005 19664 39005 19670 39005 19670 39006 19664 39006 16973 39006 16973 39007 16972 39007 19670 39007 19670 39008 16972 39008 16988 39008 19670 39009 16988 39009 19746 39009 19746 39010 16988 39010 16987 39010 19746 39011 16987 39011 19667 39011 18157 39012 17094 39012 19665 39012 17071 39013 19666 39013 17077 39013 17077 39014 19666 39014 19746 39014 17077 39015 19746 39015 17079 39015 17079 39016 19746 39016 19667 39016 17079 39017 19667 39017 17082 39017 17082 39018 19667 39018 16982 39018 17082 39019 16982 39019 19668 39019 19668 39020 16982 39020 16981 39020 19668 39021 16981 39021 19665 39021 19665 39022 16981 39022 16990 39022 19665 39023 16990 39023 18157 39023 18157 39024 16990 39024 18158 39024 16901 39025 16899 39025 19679 39025 19663 39026 16910 39026 19679 39026 19679 39027 16910 39027 16902 39027 19679 39028 16902 39028 16901 39028 16899 39029 16898 39029 19679 39029 19679 39030 16898 39030 19669 39030 19679 39031 19669 39031 19670 39031 19674 39032 16994 39032 16989 39032 19669 39033 16907 39033 19670 39033 19670 39034 16907 39034 16905 39034 19670 39035 16905 39035 19671 39035 19671 39036 16905 39036 19672 39036 19671 39037 19672 39037 19673 39037 19673 39038 19672 39038 16911 39038 19673 39039 16911 39039 16989 39039 16989 39040 16911 39040 19675 39040 16989 39041 19675 39041 19674 39041 19674 39042 19675 39042 16912 39042 18151 39043 16909 39043 19676 39043 19676 39044 19663 39044 18151 39044 18151 39045 19663 39045 19682 39045 18151 39046 19682 39046 16831 39046 19677 39047 16826 39047 19679 39047 19686 39048 19678 39048 19745 39048 19745 39049 19678 39049 16819 39049 19745 39050 16819 39050 16818 39050 16826 39051 16824 39051 19679 39051 19679 39052 16824 39052 19680 39052 19679 39053 19680 39053 19663 39053 19663 39054 19680 39054 19681 39054 19663 39055 19681 39055 19682 39055 19685 39056 19683 39056 16827 39056 18149 39057 19685 39057 19684 39057 19684 39058 19685 39058 16827 39058 19684 39059 16827 39059 16751 39059 16751 39060 16827 39060 16829 39060 16751 39061 16829 39061 16752 39061 16752 39062 16829 39062 19686 39062 16752 39063 19686 39063 19687 39063 19687 39064 19686 39064 19745 39064 19687 39065 19745 39065 16756 39065 16756 39066 19745 39066 19691 39066 19694 39067 19745 39067 19688 39067 19688 39068 19745 39068 19787 39068 19688 39069 19787 39069 19705 39069 19694 39070 16746 39070 19689 39070 19694 39071 19689 39071 19745 39071 19745 39072 19689 39072 19690 39072 19745 39073 19690 39073 19691 39073 18146 39074 19692 39074 19696 39074 18146 39075 19696 39075 19693 39075 16746 39076 19694 39076 19695 39076 19695 39077 19694 39077 16676 39077 19695 39078 16676 39078 16750 39078 16750 39079 16676 39079 16675 39079 16750 39080 16675 39080 19696 39080 19696 39081 16675 39081 16681 39081 19696 39082 16681 39082 19693 39082 19697 39083 19701 39083 19698 39083 19697 39084 19698 39084 19708 39084 19702 39085 19700 39085 19699 39085 19699 39086 19700 39086 16607 39086 19701 39087 19697 39087 19702 39087 19702 39088 19697 39088 16669 39088 19702 39089 16669 39089 19700 39089 19700 39090 16669 39090 19703 39090 19700 39091 19703 39091 19787 39091 19787 39092 19703 39092 19704 39092 19787 39093 19704 39093 19705 39093 19709 39094 16631 39094 19710 39094 19698 39095 19706 39095 19708 39095 19708 39096 19706 39096 19707 39096 19708 39097 19707 39097 16679 39097 16679 39098 19707 39098 19709 39098 16679 39099 19709 39099 16678 39099 16678 39100 19709 39100 19710 39100 19786 39101 16610 39101 19700 39101 19700 39102 16610 39102 16608 39102 19700 39103 16608 39103 16607 39103 19783 39104 19724 39104 16624 39104 16624 39105 16621 39105 19783 39105 19783 39106 16621 39106 19711 39106 19783 39107 19711 39107 19786 39107 19786 39108 19711 39108 16613 39108 19786 39109 16613 39109 16610 39109 16630 39110 16629 39110 19727 39110 19727 39111 16629 39111 16628 39111 19727 39112 16628 39112 19725 39112 19725 39113 16628 39113 16626 39113 16269 39114 16270 39114 19714 39114 16630 39115 19727 39115 19712 39115 19712 39116 19727 39116 16265 39116 19712 39117 16265 39117 16263 39117 16263 39118 19713 39118 19712 39118 19712 39119 19713 39119 16267 39119 19712 39120 16267 39120 19714 39120 19714 39121 16267 39121 16268 39121 19714 39122 16268 39122 16269 39122 16272 39123 19717 39123 19715 39123 19715 39124 19717 39124 17608 39124 19715 39125 17608 39125 16270 39125 16270 39126 17608 39126 19716 39126 16270 39127 19716 39127 19714 39127 20008 39128 20011 39128 19725 39128 16272 39129 16275 39129 19717 39129 19717 39130 16275 39130 20006 39130 19717 39131 20006 39131 19718 39131 19718 39132 20006 39132 19719 39132 19718 39133 19719 39133 19720 39133 19720 39134 19719 39134 20004 39134 19720 39135 20004 39135 19723 39135 20004 39136 19721 39136 19723 39136 19723 39137 19721 39137 19722 39137 19723 39138 19722 39138 20007 39138 20007 39139 20008 39139 19723 39139 19723 39140 20008 39140 19725 39140 19723 39141 19725 39141 19724 39141 19724 39142 19725 39142 16626 39142 19724 39143 16626 39143 16624 39143 20011 39144 20012 39144 19725 39144 19725 39145 20012 39145 19726 39145 19725 39146 19726 39146 19727 39146 19727 39147 19726 39147 19728 39147 19727 39148 19728 39148 19729 39148 19731 39149 17600 39149 19784 39149 19784 39150 17600 39150 17604 39150 19730 39151 19782 39151 19731 39151 17645 39152 17601 39152 19732 39152 19732 39153 17601 39153 17602 39153 19733 39154 19753 39154 17645 39154 19756 39155 19734 39155 19754 39155 19734 39156 19756 39156 19752 39156 19737 39157 19769 39157 19770 39157 17629 39158 19735 39158 19661 39158 19661 39159 19735 39159 19736 39159 19770 39160 19738 39160 19737 39160 19737 39161 19738 39161 19661 39161 19737 39162 19661 39162 19739 39162 19739 39163 19661 39163 19736 39163 19741 39164 19774 39164 19740 39164 19740 39165 19774 39165 17744 39165 19740 39166 17744 39166 19741 39166 19741 39167 17744 39167 17767 39167 19741 39168 17767 39168 19772 39168 19772 39169 17767 39169 17748 39169 19772 39170 17748 39170 19742 39170 19778 39171 19775 39171 19773 39171 17742 39172 19777 39172 17741 39172 17741 39173 19777 39173 19780 39173 17741 39174 19780 39174 19744 39174 19789 39175 19790 39175 19791 39175 19791 39176 19743 39176 19789 39176 19789 39177 19743 39177 17737 39177 19789 39178 17737 39178 19744 39178 19750 39179 19745 39179 19679 39179 19679 39180 19745 39180 16818 39180 19679 39181 16818 39181 19677 39181 19746 39182 19747 39182 19670 39182 19670 39183 19747 39183 19748 39183 19670 39184 19748 39184 19679 39184 19679 39185 19748 39185 16471 39185 19679 39186 16471 39186 16476 39186 16476 39187 16445 39187 19679 39187 19679 39188 16445 39188 19749 39188 19679 39189 19749 39189 19750 39189 19662 39190 19752 39190 19751 39190 19751 39191 19752 39191 19756 39191 19751 39192 19756 39192 16033 39192 16033 39193 19756 39193 19758 39193 19733 39194 16047 39194 19753 39194 19753 39195 16047 39195 16030 39195 19753 39196 16030 39196 19754 39196 19754 39197 16030 39197 19755 39197 19754 39198 19755 39198 19756 39198 19756 39199 19755 39199 19757 39199 19756 39200 19757 39200 19758 39200 19766 39201 19759 39201 19760 39201 16023 39202 16027 39202 19761 39202 19761 39203 16027 39203 19762 39203 19761 39204 19762 39204 19773 39204 19773 39205 19762 39205 16029 39205 19773 39206 16029 39206 19733 39206 19733 39207 16029 39207 16028 39207 19733 39208 16028 39208 16047 39208 19766 39209 19760 39209 19761 39209 19761 39210 19760 39210 16025 39210 19761 39211 16025 39211 16023 39211 20279 39212 20278 39212 19661 39212 19661 39213 20278 39213 19660 39213 19661 39214 19660 39214 17629 39214 17629 39215 19660 39215 19763 39215 20278 39216 19764 39216 19660 39216 19660 39217 19764 39217 20250 39217 19660 39218 20250 39218 19766 39218 19766 39219 20250 39219 19765 39219 19766 39220 19765 39220 19759 39220 19751 39221 19767 39221 19768 39221 19768 39222 19767 39222 20249 39222 19768 39223 20249 39223 17639 39223 17639 39224 20249 39224 20247 39224 17639 39225 20247 39225 19769 39225 19769 39226 20247 39226 20280 39226 19769 39227 20280 39227 19770 39227 17652 39228 19771 39228 17724 39228 17724 39229 19771 39229 19660 39229 17724 39230 19660 39230 19742 39230 19742 39231 19660 39231 19766 39231 19742 39232 19766 39232 19772 39232 19772 39233 19766 39233 19761 39233 19772 39234 19761 39234 19741 39234 19741 39235 19761 39235 19773 39235 19741 39236 19773 39236 19774 39236 19774 39237 19773 39237 19775 39237 17645 39238 19732 39238 19733 39238 19733 39239 19732 39239 19776 39239 19733 39240 19776 39240 19773 39240 19773 39241 19776 39241 19777 39241 19773 39242 19777 39242 19778 39242 19778 39243 19777 39243 17742 39243 19778 39244 17742 39244 19779 39244 19744 39245 19780 39245 19789 39245 19789 39246 19780 39246 19777 39246 19789 39247 19777 39247 19788 39247 19788 39248 19777 39248 19776 39248 19788 39249 19776 39249 19781 39249 19781 39250 19776 39250 19732 39250 19781 39251 19732 39251 19730 39251 19730 39252 19732 39252 17602 39252 19730 39253 17602 39253 19782 39253 19786 39254 19784 39254 19783 39254 19783 39255 19784 39255 17604 39255 19783 39256 17604 39256 19724 39256 19724 39257 17604 39257 19785 39257 19724 39258 19785 39258 19723 39258 19731 39259 19784 39259 19730 39259 19730 39260 19784 39260 19786 39260 19730 39261 19786 39261 19781 39261 19781 39262 19786 39262 19700 39262 19781 39263 19700 39263 19788 39263 19788 39264 19700 39264 19787 39264 19788 39265 19787 39265 19789 39265 19789 39266 19787 39266 19745 39266 19789 39267 19745 39267 19790 39267 19790 39268 19745 39268 19750 39268 19790 39269 19750 39269 19791 39269 16308 39270 19792 39270 19793 39270 19793 39271 19792 39271 19794 39271 19793 39272 19794 39272 19795 39272 19795 39273 19794 39273 19796 39273 19796 39274 19794 39274 19799 39274 19796 39275 19799 39275 19797 39275 19797 39276 19799 39276 19798 39276 19798 39277 19799 39277 18894 39277 19798 39278 18894 39278 16311 39278 16311 39279 18894 39279 19800 39279 19800 39280 18894 39280 18893 39280 19800 39281 18893 39281 19982 39281 19982 39282 18893 39282 19983 39282 19983 39283 18893 39283 19801 39283 19983 39284 19801 39284 19985 39284 19985 39285 19801 39285 19802 39285 19802 39286 19801 39286 18891 39286 19802 39287 18891 39287 19803 39287 16280 39288 19804 39288 19055 39288 19063 39289 20027 39289 19051 39289 19051 39290 20027 39290 20026 39290 19051 39291 20026 39291 19811 39291 19077 39292 19060 39292 19805 39292 19805 39293 19060 39293 19058 39293 19805 39294 19058 39294 19806 39294 19804 39295 16281 39295 19055 39295 19055 39296 16281 39296 19807 39296 19055 39297 19807 39297 19806 39297 19806 39298 19807 39298 19808 39298 19806 39299 19808 39299 19805 39299 16280 39300 19055 39300 19809 39300 19809 39301 19055 39301 19815 39301 19809 39302 19815 39302 19810 39302 20026 39303 16277 39303 19811 39303 19811 39304 16277 39304 19813 39304 19811 39305 19813 39305 19812 39305 19812 39306 19813 39306 16276 39306 19812 39307 16276 39307 19815 39307 19815 39308 16276 39308 19814 39308 19815 39309 19814 39309 19810 39309 19059 39310 19816 39310 19057 39310 19057 39311 19816 39311 19817 39311 19057 39312 19817 39312 19056 39312 19056 39313 19817 39313 19122 39313 19056 39314 19122 39314 19054 39314 19054 39315 19122 39315 19818 39315 19054 39316 19818 39316 19053 39316 19053 39317 19818 39317 19820 39317 19053 39318 19820 39318 19819 39318 19819 39319 19820 39319 19821 39319 19819 39320 19821 39320 19052 39320 19052 39321 19821 39321 19102 39321 19035 39322 19822 39322 19034 39322 19034 39323 19822 39323 19834 39323 19823 39324 19030 39324 19824 39324 19824 39325 19030 39325 19825 39325 19824 39326 19825 39326 19826 39326 19829 39327 19827 39327 19825 39327 19825 39328 19827 39328 16239 39328 19825 39329 16239 39329 19826 39329 19833 39330 19828 39330 19028 39330 19028 39331 19828 39331 16241 39331 19028 39332 16241 39332 19829 39332 19829 39333 16241 39333 16242 39333 19829 39334 16242 39334 19827 39334 19830 39335 19831 39335 19028 39335 19028 39336 19831 39336 19832 39336 19028 39337 19832 39337 19833 39337 16230 39338 16237 39338 19830 39338 16237 39339 16235 39339 19830 39339 19830 39340 16235 39340 16229 39340 19830 39341 16229 39341 19831 39341 19822 39342 16231 39342 19834 39342 19834 39343 16231 39343 16230 39343 19834 39344 16230 39344 19835 39344 19835 39345 16230 39345 19830 39345 19029 39346 19189 39346 19836 39346 19836 39347 19189 39347 19837 39347 19836 39348 19837 39348 19027 39348 19027 39349 19837 39349 19188 39349 19027 39350 19188 39350 19838 39350 19838 39351 19188 39351 19186 39351 19838 39352 19186 39352 19839 39352 19839 39353 19186 39353 19187 39353 19839 39354 19187 39354 19026 39354 19026 39355 19187 39355 19840 39355 19026 39356 19840 39356 19025 39356 19025 39357 19840 39357 19019 39357 19841 39358 19842 39358 19850 39358 19850 39359 19842 39359 16352 39359 19850 39360 16352 39360 19849 39360 19007 39361 16354 39361 19841 39361 19841 39362 16354 39362 19843 39362 19841 39363 19843 39363 19842 39363 16326 39364 19844 39364 19007 39364 19844 39365 16360 39365 19007 39365 19007 39366 16360 39366 19845 39366 19007 39367 19845 39367 16354 39367 19007 39368 19846 39368 16326 39368 16326 39369 19846 39369 19004 39369 16326 39370 19004 39370 19008 39370 16402 39371 18997 39371 19847 39371 19847 39372 18997 39372 19848 39372 19852 39373 16420 39373 19848 39373 19848 39374 16420 39374 16403 39374 19848 39375 16403 39375 19847 39375 19849 39376 19851 39376 19850 39376 19850 39377 19851 39377 16394 39377 19850 39378 16394 39378 19852 39378 19852 39379 16394 39379 16421 39379 19852 39380 16421 39380 16420 39380 18998 39381 18995 39381 18996 39381 18996 39382 18995 39382 19854 39382 18996 39383 19854 39383 19853 39383 19853 39384 19854 39384 19855 39384 19853 39385 19855 39385 19006 39385 19006 39386 19855 39386 19168 39386 19006 39387 19168 39387 19005 39387 19005 39388 19168 39388 19856 39388 19005 39389 19856 39389 19857 39389 19857 39390 19856 39390 19858 39390 19857 39391 19858 39391 19003 39391 19003 39392 19858 39392 19167 39392 19859 39393 19860 39393 18977 39393 18978 39394 16198 39394 18973 39394 18973 39395 16198 39395 19871 39395 18988 39396 19861 39396 19862 39396 19862 39397 19861 39397 19864 39397 19862 39398 19864 39398 19866 39398 19868 39399 19863 39399 19864 39399 19864 39400 19863 39400 19865 39400 19864 39401 19865 39401 19866 39401 19869 39402 19867 39402 19868 39402 19868 39403 19867 39403 16181 39403 19868 39404 16181 39404 19863 39404 19860 39405 16179 39405 18977 39405 18977 39406 16179 39406 16178 39406 18977 39407 16178 39407 19869 39407 19869 39408 16178 39408 16177 39408 19869 39409 16177 39409 19867 39409 16198 39410 19870 39410 19871 39410 19871 39411 19870 39411 16194 39411 19871 39412 16194 39412 18976 39412 18976 39413 16194 39413 19872 39413 18976 39414 19872 39414 18977 39414 18977 39415 19872 39415 19873 39415 18977 39416 19873 39416 19859 39416 18965 39417 19126 39417 19874 39417 19874 39418 19126 39418 19875 39418 19874 39419 19875 39419 19876 39419 19876 39420 19875 39420 19877 39420 19876 39421 19877 39421 18964 39421 18964 39422 19877 39422 19878 39422 18964 39423 19878 39423 18975 39423 18975 39424 19878 39424 19131 39424 18975 39425 19131 39425 18974 39425 18974 39426 19131 39426 19130 39426 18974 39427 19130 39427 18972 39427 18972 39428 19130 39428 19129 39428 19885 39429 19879 39429 19886 39429 20178 39430 19880 39430 18937 39430 18937 39431 19880 39431 19881 39431 18937 39432 19881 39432 18938 39432 18952 39433 18943 39433 19882 39433 19882 39434 18943 39434 18942 39434 19882 39435 18942 39435 19883 39435 19879 39436 19884 39436 19886 39436 19886 39437 19884 39437 16146 39437 19886 39438 16146 39438 19883 39438 19883 39439 16146 39439 16149 39439 19883 39440 16149 39440 19882 39440 19885 39441 19886 39441 19887 39441 19887 39442 19886 39442 18941 39442 19887 39443 18941 39443 16143 39443 19881 39444 16140 39444 18938 39444 18938 39445 16140 39445 16139 39445 18938 39446 16139 39446 18940 39446 18940 39447 16139 39447 19888 39447 18940 39448 19888 39448 18941 39448 18941 39449 19888 39449 19889 39449 18941 39450 19889 39450 16143 39450 18932 39451 19111 39451 19890 39451 19890 39452 19111 39452 19891 39452 19890 39453 19891 39453 19893 39453 19893 39454 19891 39454 19892 39454 19893 39455 19892 39455 18939 39455 18939 39456 19892 39456 19894 39456 18939 39457 19894 39457 19895 39457 19895 39458 19894 39458 19897 39458 19895 39459 19897 39459 19896 39459 19896 39460 19897 39460 19898 39460 19896 39461 19898 39461 18925 39461 18925 39462 19898 39462 18926 39462 19905 39463 19902 39463 18911 39463 20252 39464 19899 39464 19900 39464 19907 39465 18908 39465 16053 39465 20252 39466 19900 39466 16060 39466 16060 39467 19900 39467 16058 39467 16058 39468 19900 39468 18915 39468 16058 39469 18915 39469 19901 39469 19901 39470 18915 39470 19904 39470 19901 39471 19904 39471 16055 39471 18911 39472 19902 39472 19904 39472 19904 39473 19902 39473 19903 39473 19904 39474 19903 39474 16055 39474 18910 39475 19909 39475 18911 39475 18911 39476 19909 39476 16048 39476 18911 39477 16048 39477 19905 39477 16053 39478 19906 39478 19907 39478 19907 39479 19906 39479 16051 39479 19907 39480 16051 39480 18909 39480 18909 39481 16051 39481 19908 39481 18909 39482 19908 39482 18910 39482 18910 39483 19908 39483 16049 39483 18910 39484 16049 39484 19909 39484 18914 39485 19206 39485 18913 39485 18913 39486 19206 39486 19199 39486 18913 39487 19199 39487 18912 39487 18912 39488 19199 39488 19910 39488 18912 39489 19910 39489 19912 39489 19912 39490 19910 39490 19911 39490 19912 39491 19911 39491 19913 39491 19913 39492 19911 39492 19197 39492 19913 39493 19197 39493 19914 39493 19914 39494 19197 39494 19915 39494 19914 39495 19915 39495 19916 39495 19916 39496 19915 39496 19193 39496 19916 39497 19193 39497 18907 39497 18907 39498 19193 39498 19194 39498 19917 39499 19918 39499 19919 39499 19919 39500 19918 39500 19157 39500 19919 39501 19157 39501 19920 39501 19920 39502 19157 39502 19156 39502 19920 39503 19156 39503 19921 39503 19921 39504 19156 39504 19155 39504 19921 39505 19155 39505 19922 39505 19922 39506 19155 39506 19923 39506 19922 39507 19923 39507 18892 39507 18892 39508 19923 39508 19153 39508 18892 39509 19153 39509 18890 39509 18890 39510 19153 39510 19152 39510 18870 39511 18874 39511 20217 39511 20217 39512 20214 39512 18870 39512 18870 39513 20214 39513 16091 39513 18870 39514 16091 39514 19924 39514 16094 39515 19925 39515 18864 39515 18864 39516 19926 39516 16094 39516 16094 39517 19926 39517 19927 39517 16094 39518 19927 39518 16096 39518 18873 39519 16099 39519 19927 39519 19927 39520 16099 39520 16098 39520 19927 39521 16098 39521 16096 39521 19928 39522 16102 39522 18873 39522 18873 39523 16102 39523 16101 39523 18873 39524 16101 39524 16099 39524 19930 39525 16087 39525 19928 39525 19928 39526 16087 39526 16086 39526 19928 39527 16086 39527 16102 39527 16091 39528 19929 39528 19924 39528 19924 39529 19929 39529 19931 39529 19924 39530 19931 39530 19930 39530 19930 39531 19931 39531 16088 39531 19930 39532 16088 39532 16087 39532 19932 39533 18861 39533 18863 39533 18863 39534 18861 39534 19933 39534 18863 39535 19933 39535 18862 39535 18862 39536 19933 39536 19118 39536 18862 39537 19118 39537 18872 39537 18872 39538 19118 39538 19115 39538 18872 39539 19115 39539 18871 39539 18871 39540 19115 39540 19935 39540 18871 39541 19935 39541 19934 39541 19934 39542 19935 39542 19936 39542 19934 39543 19936 39543 18869 39543 18869 39544 19936 39544 19200 39544 19937 39545 19938 39545 15995 39545 15995 39546 19938 39546 18830 39546 15995 39547 18830 39547 15997 39547 15997 39548 18830 39548 18829 39548 15997 39549 18829 39549 15999 39549 15999 39550 18829 39550 19939 39550 15999 39551 19939 39551 16001 39551 16001 39552 19939 39552 18845 39552 16001 39553 18845 39553 16003 39553 16003 39554 18845 39554 19940 39554 16003 39555 19940 39555 19941 39555 19941 39556 19940 39556 18815 39556 16006 39557 18814 39557 16007 39557 16007 39558 18814 39558 19942 39558 16007 39559 19942 39559 19943 39559 19943 39560 19942 39560 18839 39560 19943 39561 18839 39561 19944 39561 19944 39562 18839 39562 18838 39562 19944 39563 18838 39563 16009 39563 16009 39564 18838 39564 19945 39564 16009 39565 19945 39565 16010 39565 16010 39566 19945 39566 19946 39566 16010 39567 19946 39567 15957 39567 15957 39568 19946 39568 18841 39568 19947 39569 19952 39569 19948 39569 19951 39570 19952 39570 19947 39570 19950 39571 19951 39571 19947 39571 19947 39572 19955 39572 17712 39572 19949 39573 19955 39573 19947 39573 19948 39574 19949 39574 19947 39574 19950 39575 17722 39575 19951 39575 19951 39576 17722 39576 19956 39576 19951 39577 19956 39577 19952 39577 19952 39578 19956 39578 19958 39578 19952 39579 19958 39579 19948 39579 19948 39580 19958 39580 19960 39580 19948 39581 19960 39581 19949 39581 19949 39582 19960 39582 19953 39582 19949 39583 19953 39583 19955 39583 19955 39584 19953 39584 19954 39584 19955 39585 19954 39585 17712 39585 17712 39586 19954 39586 17713 39586 17722 39587 17848 39587 19956 39587 19956 39588 17848 39588 19957 39588 19956 39589 19957 39589 19958 39589 19958 39590 19957 39590 17836 39590 19958 39591 17836 39591 19960 39591 19960 39592 17836 39592 19959 39592 19960 39593 19959 39593 19953 39593 19953 39594 19959 39594 19961 39594 19953 39595 19961 39595 19954 39595 19954 39596 19961 39596 19962 39596 19954 39597 19962 39597 17713 39597 17713 39598 19962 39598 17825 39598 17706 39599 19964 39599 19969 39599 19963 39600 19964 39600 17706 39600 19967 39601 19963 39601 17706 39601 17706 39602 19965 39602 19966 39602 19970 39603 19965 39603 17706 39603 19969 39604 19970 39604 17706 39604 19967 39605 19973 39605 19963 39605 19963 39606 19973 39606 19974 39606 19963 39607 19974 39607 19964 39607 19964 39608 19974 39608 19976 39608 19964 39609 19976 39609 19969 39609 19969 39610 19976 39610 19968 39610 19969 39611 19968 39611 19970 39611 19970 39612 19968 39612 19971 39612 19970 39613 19971 39613 19965 39613 19965 39614 19971 39614 19979 39614 19965 39615 19979 39615 19966 39615 19966 39616 19979 39616 19972 39616 19973 39617 17824 39617 19974 39617 19974 39618 17824 39618 19975 39618 19974 39619 19975 39619 19976 39619 19976 39620 19975 39620 19977 39620 19976 39621 19977 39621 19968 39621 19968 39622 19977 39622 19978 39622 19968 39623 19978 39623 19971 39623 19971 39624 19978 39624 17838 39624 19971 39625 17838 39625 19979 39625 19979 39626 17838 39626 17837 39626 19979 39627 17837 39627 19972 39627 19972 39628 17837 39628 17844 39628 19231 39629 19243 39629 19980 39629 19980 39630 19243 39630 19114 39630 17846 39631 16324 39631 19997 39631 16324 39632 19981 39632 19991 39632 19981 39633 16311 39633 19800 39633 19981 39634 19800 39634 19991 39634 19991 39635 19800 39635 19982 39635 19991 39636 19982 39636 19984 39636 19982 39637 19983 39637 19984 39637 19984 39638 19983 39638 19985 39638 19984 39639 19985 39639 19986 39639 19985 39640 19802 39640 19986 39640 19986 39641 19802 39641 19803 39641 19986 39642 19803 39642 19987 39642 19987 39643 19803 39643 19507 39643 19987 39644 19507 39644 19993 39644 19507 39645 19508 39645 19993 39645 19993 39646 19508 39646 19989 39646 19993 39647 19989 39647 19988 39647 19988 39648 19989 39648 19509 39648 19509 39649 19510 39649 19988 39649 19988 39650 19510 39650 19990 39650 19988 39651 19990 39651 19996 39651 16324 39652 19991 39652 19997 39652 19997 39653 19991 39653 19984 39653 19997 39654 19984 39654 19992 39654 19992 39655 19984 39655 19986 39655 19992 39656 19986 39656 20000 39656 20000 39657 19986 39657 19987 39657 20000 39658 19987 39658 19994 39658 19994 39659 19987 39659 19993 39659 19994 39660 19993 39660 20001 39660 20001 39661 19993 39661 19988 39661 20001 39662 19988 39662 19995 39662 19995 39663 19988 39663 19996 39663 19995 39664 19996 39664 20003 39664 17846 39665 19997 39665 19998 39665 19998 39666 19997 39666 19992 39666 19998 39667 19992 39667 19999 39667 19999 39668 19992 39668 20000 39668 19999 39669 20000 39669 17842 39669 17842 39670 20000 39670 19994 39670 17842 39671 19994 39671 20002 39671 20002 39672 19994 39672 20001 39672 20002 39673 20001 39673 17843 39673 17843 39674 20001 39674 19995 39674 17843 39675 19995 39675 17834 39675 17834 39676 19995 39676 20003 39676 17834 39677 20003 39677 16316 39677 19721 39678 20004 39678 20005 39678 20005 39679 20004 39679 19719 39679 20005 39680 19719 39680 20020 39680 20020 39681 19719 39681 20006 39681 20020 39682 20006 39682 16273 39682 19721 39683 20005 39683 19722 39683 19722 39684 20005 39684 20017 39684 19722 39685 20017 39685 20007 39685 20007 39686 20017 39686 20009 39686 20007 39687 20009 39687 20008 39687 20008 39688 20009 39688 20010 39688 20008 39689 20010 39689 20011 39689 20011 39690 20010 39690 20013 39690 20011 39691 20013 39691 20012 39691 20012 39692 20013 39692 20016 39692 20012 39693 20016 39693 19726 39693 16293 39694 19729 39694 20016 39694 20016 39695 19729 39695 19728 39695 20016 39696 19728 39696 19726 39696 20037 39697 16293 39697 20014 39697 20014 39698 16293 39698 20016 39698 20014 39699 20016 39699 20015 39699 20015 39700 20016 39700 20013 39700 20015 39701 20013 39701 20039 39701 20039 39702 20013 39702 20010 39702 20039 39703 20010 39703 20042 39703 20042 39704 20010 39704 20009 39704 20042 39705 20009 39705 20018 39705 20018 39706 20009 39706 20017 39706 20018 39707 20017 39707 20044 39707 20044 39708 20017 39708 20005 39708 20044 39709 20005 39709 20019 39709 20019 39710 20005 39710 20020 39710 20019 39711 20020 39711 20047 39711 20047 39712 20020 39712 16273 39712 19072 39713 20022 39713 20035 39713 20035 39714 20022 39714 20040 39714 19072 39715 19073 39715 20022 39715 20022 39716 19073 39716 20021 39716 20022 39717 20021 39717 20038 39717 20021 39718 19076 39718 20038 39718 20038 39719 19076 39719 20024 39719 20038 39720 20024 39720 20023 39720 20023 39721 20024 39721 19079 39721 20023 39722 19079 39722 20025 39722 20036 39723 20023 39723 16282 39723 16282 39724 20023 39724 20025 39724 16282 39725 20025 39725 19078 39725 19078 39726 20025 39726 19079 39726 20026 39727 20027 39727 20028 39727 20028 39728 20027 39728 19063 39728 20028 39729 19063 39729 20029 39729 20029 39730 19063 39730 19064 39730 20029 39731 19064 39731 20030 39731 20043 39732 20045 39732 20030 39732 20030 39733 20045 39733 20046 39733 20030 39734 20046 39734 20029 39734 19068 39735 20041 39735 20031 39735 20031 39736 20041 39736 20043 39736 20031 39737 20043 39737 19066 39737 19066 39738 20043 39738 20030 39738 19066 39739 20030 39739 20032 39739 20032 39740 20030 39740 19064 39740 19068 39741 19070 39741 20041 39741 20041 39742 19070 39742 20033 39742 20041 39743 20033 39743 20040 39743 20040 39744 20033 39744 20034 39744 20040 39745 20034 39745 20035 39745 20036 39746 20037 39746 20023 39746 20023 39747 20037 39747 20014 39747 20023 39748 20014 39748 20038 39748 20038 39749 20014 39749 20015 39749 20038 39750 20015 39750 20022 39750 20022 39751 20015 39751 20039 39751 20022 39752 20039 39752 20040 39752 20040 39753 20039 39753 20042 39753 20040 39754 20042 39754 20041 39754 20041 39755 20042 39755 20018 39755 20041 39756 20018 39756 20043 39756 20043 39757 20018 39757 20044 39757 20043 39758 20044 39758 20045 39758 20045 39759 20044 39759 20019 39759 20045 39760 20019 39760 20046 39760 20046 39761 20019 39761 20047 39761 20048 39762 19823 39762 20070 39762 20070 39763 19823 39763 19824 39763 20070 39764 19824 39764 19826 39764 20049 39765 19044 39765 20050 39765 20050 39766 19044 39766 20048 39766 20050 39767 20048 39767 20093 39767 20093 39768 20048 39768 20070 39768 20049 39769 20050 39769 19041 39769 19041 39770 20050 39770 20051 39770 19041 39771 20051 39771 20052 39771 20052 39772 20051 39772 20053 39772 20052 39773 20053 39773 19039 39773 19039 39774 20053 39774 19038 39774 19038 39775 20053 39775 20054 39775 19038 39776 20054 39776 19037 39776 19037 39777 20054 39777 20055 39777 19037 39778 20055 39778 20056 39778 20056 39779 20055 39779 20099 39779 20056 39780 20099 39780 20057 39780 20057 39781 20099 39781 16234 39781 20057 39782 16234 39782 16232 39782 16246 39783 20078 39783 20058 39783 20058 39784 20078 39784 20059 39784 20061 39785 20062 39785 20078 39785 20078 39786 20062 39786 19399 39786 20078 39787 19399 39787 20059 39787 20063 39788 20060 39788 20076 39788 20076 39789 20060 39789 19398 39789 20076 39790 19398 39790 20061 39790 20061 39791 19398 39791 19401 39791 20061 39792 19401 39792 20062 39792 20072 39793 19461 39793 20073 39793 20073 39794 19461 39794 20064 39794 20073 39795 20064 39795 20063 39795 20063 39796 20064 39796 19459 39796 20063 39797 19459 39797 20060 39797 19466 39798 20065 39798 20071 39798 20071 39799 20065 39799 20066 39799 20071 39800 20066 39800 20072 39800 20072 39801 20066 39801 19455 39801 20072 39802 19455 39802 19461 39802 16219 39803 20067 39803 20071 39803 20071 39804 20067 39804 19456 39804 20071 39805 19456 39805 19466 39805 20069 39806 16219 39806 20068 39806 16244 39807 20069 39807 20079 39807 20070 39808 16244 39808 20087 39808 16219 39809 20071 39809 20068 39809 20068 39810 20071 39810 20072 39810 20068 39811 20072 39811 20081 39811 20081 39812 20072 39812 20073 39812 20081 39813 20073 39813 20074 39813 20074 39814 20073 39814 20063 39814 20074 39815 20063 39815 20075 39815 20075 39816 20063 39816 20076 39816 20075 39817 20076 39817 20077 39817 20077 39818 20076 39818 20061 39818 20077 39819 20061 39819 20083 39819 20083 39820 20061 39820 20078 39820 20083 39821 20078 39821 20084 39821 20084 39822 20078 39822 16246 39822 20084 39823 16246 39823 20086 39823 20069 39824 20068 39824 20079 39824 20079 39825 20068 39825 20081 39825 20079 39826 20081 39826 20080 39826 20080 39827 20081 39827 20074 39827 20080 39828 20074 39828 20089 39828 20089 39829 20074 39829 20075 39829 20089 39830 20075 39830 20090 39830 20090 39831 20075 39831 20077 39831 20090 39832 20077 39832 20082 39832 20082 39833 20077 39833 20083 39833 20082 39834 20083 39834 20092 39834 20092 39835 20083 39835 20084 39835 20092 39836 20084 39836 20085 39836 20085 39837 20084 39837 20086 39837 20085 39838 20086 39838 16251 39838 16244 39839 20079 39839 20087 39839 20087 39840 20079 39840 20080 39840 20087 39841 20080 39841 20088 39841 20088 39842 20080 39842 20089 39842 20088 39843 20089 39843 20094 39843 20094 39844 20089 39844 20090 39844 20094 39845 20090 39845 20095 39845 20095 39846 20090 39846 20082 39846 20095 39847 20082 39847 20096 39847 20096 39848 20082 39848 20092 39848 20096 39849 20092 39849 20091 39849 20091 39850 20092 39850 20085 39850 20091 39851 20085 39851 20097 39851 20097 39852 20085 39852 16251 39852 20097 39853 16251 39853 20098 39853 20070 39854 20087 39854 20093 39854 20093 39855 20087 39855 20088 39855 20093 39856 20088 39856 20050 39856 20050 39857 20088 39857 20094 39857 20050 39858 20094 39858 20051 39858 20051 39859 20094 39859 20095 39859 20051 39860 20095 39860 20053 39860 20053 39861 20095 39861 20096 39861 20053 39862 20096 39862 20054 39862 20054 39863 20096 39863 20091 39863 20054 39864 20091 39864 20055 39864 20055 39865 20091 39865 20097 39865 20055 39866 20097 39866 20099 39866 20099 39867 20097 39867 20098 39867 20099 39868 20098 39868 16234 39868 18980 39869 18983 39869 20100 39869 18984 39870 18985 39870 20101 39870 18988 39871 19862 39871 20116 39871 20104 39872 19328 39872 20102 39872 19276 39873 19275 39873 20122 39873 19364 39874 20103 39874 20147 39874 19364 39875 20147 39875 20141 39875 20104 39876 20102 39876 19330 39876 18988 39877 20116 39877 18987 39877 20109 39878 19330 39878 20111 39878 20111 39879 19330 39879 20102 39879 20111 39880 20102 39880 20113 39880 20113 39881 20102 39881 20117 39881 20113 39882 20117 39882 20105 39882 20105 39883 20117 39883 20106 39883 20105 39884 20106 39884 20115 39884 20115 39885 20106 39885 20107 39885 20115 39886 20107 39886 20108 39886 20108 39887 20107 39887 20119 39887 19332 39888 20109 39888 20110 39888 20110 39889 20109 39889 20111 39889 20110 39890 20111 39890 20112 39890 20112 39891 20111 39891 20113 39891 20112 39892 20113 39892 20114 39892 20114 39893 20113 39893 20105 39893 20114 39894 20105 39894 16201 39894 16201 39895 20105 39895 20115 39895 16201 39896 20115 39896 20116 39896 20116 39897 20115 39897 20108 39897 20116 39898 20108 39898 18987 39898 18987 39899 20108 39899 20119 39899 18987 39900 20119 39900 18986 39900 19328 39901 19325 39901 20102 39901 20102 39902 19325 39902 20121 39902 20102 39903 20121 39903 20117 39903 20117 39904 20121 39904 20123 39904 20117 39905 20123 39905 20106 39905 20106 39906 20123 39906 20118 39906 20106 39907 20118 39907 20107 39907 20107 39908 20118 39908 20125 39908 20107 39909 20125 39909 20119 39909 20119 39910 20125 39910 20101 39910 20101 39911 18985 39911 20119 39911 20119 39912 18985 39912 20120 39912 20119 39913 20120 39913 18986 39913 19325 39914 19276 39914 20121 39914 20121 39915 19276 39915 20122 39915 20121 39916 20122 39916 20123 39916 20123 39917 20122 39917 20129 39917 20123 39918 20129 39918 20118 39918 20118 39919 20129 39919 20124 39919 20118 39920 20124 39920 20125 39920 20125 39921 20124 39921 20126 39921 20125 39922 20126 39922 20101 39922 20101 39923 20126 39923 20100 39923 20101 39924 20100 39924 18984 39924 18984 39925 20100 39925 18983 39925 18981 39926 18980 39926 20131 39926 20131 39927 18980 39927 20100 39927 20131 39928 20100 39928 20133 39928 20133 39929 20100 39929 20126 39929 20133 39930 20126 39930 20127 39930 20127 39931 20126 39931 20124 39931 20127 39932 20124 39932 20128 39932 20128 39933 20124 39933 20129 39933 20128 39934 20129 39934 20130 39934 20130 39935 20129 39935 20122 39935 20130 39936 20122 39936 19366 39936 19366 39937 20122 39937 19275 39937 18982 39938 18981 39938 20136 39938 20136 39939 18981 39939 20131 39939 20136 39940 20131 39940 20132 39940 20132 39941 20131 39941 20133 39941 20132 39942 20133 39942 20134 39942 20134 39943 20133 39943 20127 39943 20134 39944 20127 39944 20139 39944 20139 39945 20127 39945 20128 39945 20139 39946 20128 39946 20140 39946 20140 39947 20128 39947 20130 39947 20140 39948 20130 39948 19365 39948 19365 39949 20130 39949 19366 39949 20143 39950 18982 39950 20135 39950 20135 39951 18982 39951 20136 39951 20135 39952 20136 39952 20144 39952 20144 39953 20136 39953 20132 39953 20144 39954 20132 39954 20137 39954 20137 39955 20132 39955 20134 39955 20137 39956 20134 39956 20138 39956 20138 39957 20134 39957 20139 39957 20138 39958 20139 39958 20147 39958 20147 39959 20139 39959 20140 39959 20147 39960 20140 39960 20141 39960 20141 39961 20140 39961 19365 39961 20142 39962 20143 39962 16197 39962 16197 39963 20143 39963 20135 39963 16197 39964 20135 39964 16207 39964 16207 39965 20135 39965 20144 39965 16207 39966 20144 39966 16206 39966 16206 39967 20144 39967 20137 39967 16206 39968 20137 39968 20145 39968 20145 39969 20137 39969 20138 39969 20145 39970 20138 39970 16202 39970 16202 39971 20138 39971 20147 39971 16202 39972 20147 39972 20146 39972 20146 39973 20147 39973 20103 39973 20179 39974 18945 39974 20148 39974 19545 39975 19544 39975 20149 39975 20149 39976 19544 39976 20150 39976 20149 39977 20150 39977 20151 39977 20151 39978 20150 39978 20152 39978 20151 39979 20152 39979 16136 39979 19545 39980 20149 39980 20153 39980 20153 39981 20149 39981 20166 39981 20153 39982 20166 39982 20154 39982 20154 39983 20166 39983 20165 39983 20154 39984 20165 39984 20155 39984 20155 39985 20165 39985 20162 39985 20155 39986 20162 39986 20156 39986 20156 39987 20162 39987 20157 39987 20156 39988 20157 39988 20158 39988 20158 39989 20157 39989 20159 39989 20158 39990 20159 39990 20160 39990 20161 39991 19552 39991 20159 39991 20159 39992 19552 39992 19551 39992 20159 39993 19551 39993 20160 39993 20183 39994 20161 39994 20184 39994 20184 39995 20161 39995 20159 39995 20184 39996 20159 39996 20186 39996 20186 39997 20159 39997 20157 39997 20186 39998 20157 39998 20163 39998 20163 39999 20157 39999 20162 39999 20163 40000 20162 40000 20164 40000 20164 40001 20162 40001 20165 40001 20164 40002 20165 40002 20188 40002 20188 40003 20165 40003 20166 40003 20188 40004 20166 40004 20167 40004 20167 40005 20166 40005 20149 40005 20167 40006 20149 40006 20168 40006 20168 40007 20149 40007 20151 40007 20168 40008 20151 40008 16163 40008 16163 40009 20151 40009 16136 40009 20169 40010 20170 40010 20182 40010 20182 40011 20170 40011 20187 40011 20169 40012 20171 40012 20170 40012 20170 40013 20171 40013 18951 40013 20170 40014 18951 40014 20185 40014 18951 40015 20172 40015 20185 40015 20185 40016 20172 40016 18956 40016 20185 40017 18956 40017 20173 40017 20173 40018 18956 40018 20176 40018 20173 40019 20176 40019 20174 40019 16171 40020 20173 40020 20175 40020 20175 40021 20173 40021 20174 40021 20175 40022 20174 40022 18954 40022 18954 40023 20174 40023 20176 40023 18945 40024 20179 40024 20177 40024 19881 40025 19880 40025 16142 40025 16142 40026 19880 40026 20178 40026 16142 40027 20178 40027 16160 40027 20178 40028 20177 40028 16160 40028 16160 40029 20177 40029 20179 40029 16160 40030 20179 40030 16162 40030 18947 40031 20180 40031 20148 40031 20148 40032 20180 40032 20189 40032 20148 40033 20189 40033 20179 40033 20179 40034 20189 40034 20190 40034 20179 40035 20190 40035 16162 40035 18947 40036 18948 40036 20180 40036 20180 40037 18948 40037 20181 40037 20180 40038 20181 40038 20187 40038 20187 40039 20181 40039 18950 40039 20187 40040 18950 40040 20182 40040 16171 40041 20183 40041 20173 40041 20173 40042 20183 40042 20184 40042 20173 40043 20184 40043 20185 40043 20185 40044 20184 40044 20186 40044 20185 40045 20186 40045 20170 40045 20170 40046 20186 40046 20163 40046 20170 40047 20163 40047 20187 40047 20187 40048 20163 40048 20164 40048 20187 40049 20164 40049 20180 40049 20180 40050 20164 40050 20188 40050 20180 40051 20188 40051 20189 40051 20189 40052 20188 40052 20167 40052 20189 40053 20167 40053 20190 40053 20190 40054 20167 40054 20168 40054 20190 40055 20168 40055 16162 40055 16162 40056 20168 40056 16163 40056 20191 40057 20192 40057 20203 40057 20207 40058 20204 40058 20211 40058 20193 40059 20221 40059 20223 40059 19641 40060 19640 40060 20193 40060 20193 40061 19640 40061 20194 40061 20193 40062 20194 40062 20221 40062 20221 40063 20194 40063 19639 40063 20221 40064 19639 40064 19631 40064 20238 40065 20195 40065 20196 40065 20196 40066 20195 40066 20197 40066 20196 40067 20197 40067 20198 40067 20198 40068 20197 40068 20229 40068 20198 40069 20229 40069 20236 40069 20236 40070 20229 40070 20228 40070 20236 40071 20228 40071 20235 40071 18881 40072 20199 40072 20201 40072 20201 40073 20199 40073 20200 40073 20201 40074 20200 40074 20202 40074 20192 40075 18881 40075 20203 40075 20203 40076 18881 40076 20201 40076 20203 40077 20201 40077 20204 40077 20200 40078 20205 40078 20202 40078 20202 40079 20205 40079 20206 40079 20202 40080 20206 40080 20213 40080 20213 40081 20206 40081 16092 40081 20213 40082 16092 40082 16093 40082 20207 40083 20211 40083 20237 40083 20237 40084 20211 40084 20212 40084 20237 40085 20212 40085 20208 40085 20208 40086 20212 40086 20209 40086 20208 40087 20209 40087 20210 40087 20210 40088 20209 40088 16078 40088 20210 40089 16078 40089 16114 40089 20204 40090 20201 40090 20211 40090 20211 40091 20201 40091 20202 40091 20211 40092 20202 40092 20212 40092 20212 40093 20202 40093 20213 40093 20212 40094 20213 40094 20209 40094 20209 40095 20213 40095 16093 40095 20209 40096 16093 40096 16078 40096 16107 40097 20214 40097 20217 40097 20215 40098 20224 40098 20216 40098 20216 40099 20224 40099 16107 40099 20216 40100 16107 40100 18874 40100 18874 40101 16107 40101 20217 40101 18875 40102 20218 40102 20219 40102 20219 40103 20218 40103 18877 40103 20219 40104 18877 40104 18880 40104 20225 40105 20223 40105 20220 40105 20220 40106 20223 40106 20221 40106 20220 40107 20221 40107 16125 40107 16125 40108 20221 40108 19631 40108 16125 40109 19631 40109 19630 40109 18880 40110 20233 40110 20219 40110 20219 40111 20233 40111 20234 40111 20219 40112 20234 40112 20235 40112 19528 40113 19641 40113 20232 40113 20232 40114 19641 40114 20193 40114 20232 40115 20193 40115 20222 40115 20222 40116 20193 40116 20223 40116 20222 40117 20223 40117 20224 40117 20224 40118 20223 40118 20225 40118 20224 40119 20225 40119 16107 40119 20231 40120 20195 40120 20226 40120 20226 40121 20195 40121 20238 40121 20226 40122 20238 40122 20227 40122 19529 40123 20228 40123 19530 40123 19530 40124 20228 40124 20229 40124 19530 40125 20229 40125 19532 40125 19532 40126 20229 40126 20197 40126 19532 40127 20197 40127 19534 40127 19534 40128 20197 40128 20195 40128 19534 40129 20195 40129 20230 40129 20230 40130 20195 40130 20231 40130 19529 40131 19528 40131 20228 40131 20228 40132 19528 40132 20232 40132 20228 40133 20232 40133 20235 40133 20235 40134 20232 40134 20222 40134 20235 40135 20222 40135 20219 40135 20219 40136 20222 40136 20224 40136 20219 40137 20224 40137 18875 40137 18875 40138 20224 40138 20215 40138 18880 40139 20191 40139 20233 40139 20233 40140 20191 40140 20203 40140 20233 40141 20203 40141 20234 40141 20234 40142 20203 40142 20204 40142 20234 40143 20204 40143 20235 40143 20235 40144 20204 40144 20207 40144 20235 40145 20207 40145 20236 40145 20236 40146 20207 40146 20237 40146 20236 40147 20237 40147 20198 40147 20198 40148 20237 40148 20208 40148 20198 40149 20208 40149 20196 40149 20196 40150 20208 40150 20210 40150 20196 40151 20210 40151 20238 40151 20238 40152 20210 40152 16114 40152 20238 40153 16114 40153 20227 40153 20283 40154 20239 40154 20268 40154 20268 40155 20239 40155 20240 40155 19751 40156 16042 40156 19767 40156 19767 40157 16042 40157 20248 40157 16042 40158 16077 40158 20248 40158 20248 40159 16077 40159 20241 40159 20248 40160 20241 40160 20246 40160 20246 40161 20241 40161 20242 40161 20246 40162 20242 40162 20245 40162 20245 40163 20242 40163 20243 40163 20245 40164 20243 40164 20244 40164 20244 40165 20243 40165 20286 40165 20244 40166 20286 40166 20277 40166 20245 40167 20280 40167 20246 40167 20246 40168 20280 40168 20247 40168 20246 40169 20247 40169 20248 40169 20248 40170 20247 40170 20249 40170 20248 40171 20249 40171 19767 40171 19765 40172 20250 40172 20264 40172 20251 40173 20269 40173 20262 40173 20262 40174 20269 40174 20261 40174 20268 40175 20269 40175 20282 40175 20282 40176 20269 40176 20251 40176 20282 40177 20251 40177 18924 40177 20281 40178 19899 40178 16059 40178 16059 40179 19899 40179 20252 40179 16059 40180 20252 40180 16060 40180 18919 40181 20254 40181 16072 40181 16072 40182 20254 40182 20253 40182 20254 40183 20255 40183 20253 40183 20253 40184 20255 40184 18920 40184 20253 40185 18920 40185 20275 40185 20275 40186 18920 40186 18922 40186 20275 40187 18922 40187 20256 40187 20256 40188 18922 40188 20257 40188 20256 40189 20257 40189 20259 40189 20259 40190 20257 40190 20258 40190 20259 40191 20258 40191 20261 40191 20261 40192 20258 40192 20260 40192 20261 40193 20260 40193 20262 40193 19759 40194 19765 40194 20263 40194 20263 40195 19765 40195 20264 40195 20263 40196 20264 40196 20270 40196 20270 40197 20264 40197 20284 40197 20270 40198 20284 40198 20271 40198 20271 40199 20284 40199 20285 40199 20271 40200 20285 40200 20272 40200 20272 40201 20285 40201 20265 40201 20272 40202 20265 40202 20273 40202 20273 40203 20265 40203 20287 40203 20273 40204 20287 40204 20274 40204 20274 40205 20287 40205 20266 40205 20274 40206 20266 40206 20276 40206 20276 40207 20266 40207 20288 40207 20276 40208 20288 40208 20267 40208 19760 40209 19759 40209 20240 40209 20240 40210 19759 40210 20263 40210 20240 40211 20263 40211 20268 40211 20268 40212 20263 40212 20270 40212 20268 40213 20270 40213 20269 40213 20269 40214 20270 40214 20271 40214 20269 40215 20271 40215 20261 40215 20261 40216 20271 40216 20272 40216 20261 40217 20272 40217 20259 40217 20259 40218 20272 40218 20273 40218 20259 40219 20273 40219 20256 40219 20256 40220 20273 40220 20274 40220 20256 40221 20274 40221 20275 40221 20275 40222 20274 40222 20276 40222 20275 40223 20276 40223 20253 40223 20253 40224 20276 40224 20267 40224 20253 40225 20267 40225 16072 40225 19764 40226 20278 40226 20277 40226 20277 40227 20278 40227 20279 40227 20277 40228 20279 40228 20244 40228 20244 40229 20279 40229 19738 40229 20244 40230 19738 40230 20245 40230 20245 40231 19738 40231 19770 40231 20245 40232 19770 40232 20280 40232 18924 40233 20281 40233 20282 40233 20282 40234 20281 40234 16059 40234 20282 40235 16059 40235 20268 40235 20268 40236 16059 40236 20283 40236 20250 40237 19764 40237 20264 40237 20264 40238 19764 40238 20277 40238 20264 40239 20277 40239 20284 40239 20284 40240 20277 40240 20286 40240 20284 40241 20286 40241 20285 40241 20285 40242 20286 40242 20243 40242 20285 40243 20243 40243 20265 40243 20265 40244 20243 40244 20242 40244 20265 40245 20242 40245 20287 40245 20287 40246 20242 40246 20241 40246 20287 40247 20241 40247 20266 40247 20266 40248 20241 40248 16077 40248 20266 40249 16077 40249 20288 40249 20949 40250 20442 40250 20289 40250 20949 40251 20289 40251 20290 40251 20290 40252 20289 40252 20291 40252 20290 40253 20291 40253 20293 40253 20293 40254 20291 40254 20292 40254 20293 40255 20292 40255 20944 40255 20944 40256 20292 40256 20443 40256 20944 40257 20443 40257 20294 40257 20294 40258 20443 40258 20445 40258 20294 40259 20445 40259 20295 40259 20500 40260 20297 40260 20296 40260 20445 40261 20447 40261 20295 40261 20295 40262 20447 40262 20426 40262 20426 40263 20425 40263 20295 40263 20295 40264 20425 40264 20495 40264 20295 40265 20495 40265 20296 40265 20296 40266 20495 40266 20496 40266 20296 40267 20496 40267 20500 40267 20296 40268 20297 40268 20299 40268 20296 40269 20299 40269 20298 40269 20298 40270 20299 40270 20431 40270 20298 40271 20431 40271 20946 40271 20946 40272 20431 40272 20301 40272 20946 40273 20301 40273 20300 40273 20300 40274 20301 40274 20302 40274 20300 40275 20302 40275 20303 40275 20303 40276 20302 40276 20430 40276 20303 40277 20430 40277 20948 40277 20430 40278 20304 40278 20948 40278 20948 40279 20304 40279 20479 40279 20948 40280 20479 40280 20308 40280 20308 40281 20479 40281 20305 40281 20308 40282 20305 40282 20306 40282 20308 40283 20306 40283 20307 40283 20308 40284 20307 40284 20958 40284 20958 40285 20307 40285 20433 40285 20958 40286 20433 40286 20959 40286 20959 40287 20433 40287 20309 40287 20959 40288 20309 40288 20962 40288 20962 40289 20309 40289 20310 40289 20962 40290 20310 40290 20963 40290 20963 40291 20310 40291 20312 40291 20963 40292 20312 40292 20311 40292 20311 40293 20312 40293 20516 40293 20510 40294 20951 40294 20511 40294 20511 40295 20951 40295 20513 40295 20516 40296 20313 40296 20311 40296 20311 40297 20313 40297 20314 40297 20311 40298 20314 40298 20951 40298 20951 40299 20314 40299 20515 40299 20951 40300 20515 40300 20513 40300 20951 40301 20510 40301 20509 40301 20951 40302 20509 40302 20315 40302 20315 40303 20509 40303 20437 40303 20315 40304 20437 40304 20316 40304 20316 40305 20437 40305 20317 40305 20316 40306 20317 40306 20954 40306 20954 40307 20317 40307 20438 40307 20954 40308 20438 40308 20955 40308 20955 40309 20438 40309 20440 40309 20955 40310 20440 40310 20319 40310 20440 40311 20318 40311 20319 40311 20319 40312 20318 40312 20320 40312 20319 40313 20320 40313 20949 40313 20949 40314 20320 40314 20483 40314 20949 40315 20483 40315 20442 40315 20623 40316 20321 40316 20384 40316 20872 40317 20842 40317 20407 40317 20884 40318 20886 40318 20394 40318 20907 40319 20908 40319 20384 40319 20917 40320 20918 40320 20395 40320 20395 40321 20918 40321 20329 40321 20395 40322 20329 40322 20322 40322 20908 40323 20911 40323 20382 40323 20382 40324 20911 40324 20323 40324 20382 40325 20323 40325 20324 40325 20324 40326 20323 40326 20325 40326 20324 40327 20325 40327 20395 40327 20395 40328 20325 40328 20914 40328 20395 40329 20914 40329 20917 40329 20327 40330 20937 40330 20386 40330 20386 40331 20937 40331 20938 40331 20386 40332 20938 40332 20384 40332 20384 40333 20938 40333 20326 40333 20384 40334 20326 40334 20907 40334 20327 40335 20386 40335 20933 40335 20933 40336 20386 40336 20328 40336 20933 40337 20328 40337 20931 40337 20882 40338 20928 40338 20929 40338 20329 40339 20922 40339 20322 40339 20322 40340 20922 40340 20925 40340 20322 40341 20925 40341 20394 40341 20394 40342 20925 40342 20330 40342 20394 40343 20330 40343 20928 40343 20405 40344 20887 40344 20418 40344 20928 40345 20882 40345 20394 40345 20394 40346 20882 40346 20883 40346 20394 40347 20883 40347 20884 40347 20331 40348 20875 40348 20328 40348 20328 40349 20875 40349 20876 40349 20328 40350 20876 40350 20931 40350 20931 40351 20876 40351 20877 40351 20931 40352 20877 40352 20929 40352 20929 40353 20877 40353 20880 40353 20929 40354 20880 40354 20882 40354 20338 40355 20339 40355 20332 40355 20588 40356 20333 40356 20334 40356 20410 40357 20590 40357 20335 40357 20590 40358 20593 40358 20335 40358 20335 40359 20593 40359 20336 40359 20335 40360 20336 40360 20332 40360 20332 40361 20336 40361 20337 40361 20332 40362 20337 40362 20338 40362 20339 40363 20580 40363 20328 40363 20328 40364 20580 40364 20582 40364 20328 40365 20582 40365 20331 40365 20331 40366 20582 40366 20340 40366 20331 40367 20340 40367 20874 40367 20874 40368 20340 40368 20341 40368 20874 40369 20341 40369 20904 40369 20904 40370 20341 40370 20588 40370 20344 40371 20342 40371 20351 40371 20351 40372 20342 40372 20893 40372 20408 40373 20895 40373 20896 40373 20896 40374 20898 40374 20408 40374 20408 40375 20898 40375 20899 40375 20408 40376 20899 40376 20334 40376 20334 40377 20899 40377 20900 40377 20334 40378 20900 40378 20588 40378 20588 40379 20900 40379 20343 40379 20588 40380 20343 40380 20904 40380 20344 40381 20351 40381 20889 40381 20889 40382 20351 40382 20419 40382 20889 40383 20419 40383 20418 40383 20345 40384 20857 40384 20861 40384 20861 40385 20863 40385 20345 40385 20345 40386 20863 40386 20864 40386 20345 40387 20864 40387 20950 40387 20857 40388 20345 40388 20346 40388 20346 40389 20345 40389 20421 40389 20346 40390 20421 40390 20854 40390 20864 40391 20347 40391 20950 40391 20950 40392 20347 40392 20866 40392 20950 40393 20866 40393 20348 40393 20348 40394 20349 40394 20950 40394 20950 40395 20349 40395 20868 40395 20950 40396 20868 40396 20871 40396 20407 40397 20842 40397 20408 40397 20408 40398 20842 40398 20843 40398 20408 40399 20843 40399 20350 40399 20350 40400 20845 40400 20408 40400 20408 40401 20845 40401 20351 40401 20408 40402 20351 40402 20895 40402 20895 40403 20351 40403 20893 40403 20845 40404 20847 40404 20351 40404 20351 40405 20847 40405 20850 40405 20351 40406 20850 40406 20421 40406 20421 40407 20850 40407 20853 40407 20421 40408 20853 40408 20854 40408 20352 40409 20353 40409 20364 40409 20364 40410 20353 40410 20354 40410 20364 40411 20354 40411 20355 40411 20359 40412 20356 40412 20357 40412 20358 40413 20736 40413 20360 40413 20359 40414 20357 40414 20738 40414 20358 40415 20360 40415 20942 40415 20942 40416 20360 40416 20361 40416 20942 40417 20361 40417 20738 40417 20726 40418 20362 40418 20364 40418 20364 40419 20362 40419 20947 40419 20364 40420 20947 40420 20352 40420 20726 40421 20728 40421 20362 40421 20362 40422 20728 40422 20730 40422 20362 40423 20730 40423 20358 40423 20358 40424 20730 40424 20733 40424 20358 40425 20733 40425 20736 40425 20356 40426 20363 40426 20357 40426 20357 40427 20363 40427 20742 40427 20357 40428 20742 40428 20364 40428 20364 40429 20742 40429 20745 40429 20364 40430 20745 40430 20726 40430 20369 40431 20404 40431 20656 40431 20373 40432 20372 40432 20943 40432 20365 40433 20367 40433 20375 40433 20373 40434 20943 40434 20371 40434 20365 40435 20668 40435 20367 40435 20367 40436 20668 40436 20366 40436 20367 40437 20366 40437 20368 40437 20656 40438 20657 40438 20369 40438 20369 40439 20657 40439 20658 40439 20369 40440 20658 40440 20370 40440 20370 40441 20658 40441 20371 40441 20370 40442 20371 40442 20945 40442 20945 40443 20371 40443 20943 40443 20372 40444 20373 40444 20374 40444 20374 40445 20373 40445 20663 40445 20374 40446 20663 40446 20375 40446 20375 40447 20663 40447 20664 40447 20375 40448 20664 40448 20365 40448 20368 40449 20651 40449 20404 40449 20404 40450 20651 40450 20652 40450 20404 40451 20652 40451 20656 40451 20376 40452 20950 40452 20407 40452 20407 40453 20950 40453 20871 40453 20407 40454 20871 40454 20872 40454 20376 40455 20547 40455 20950 40455 20950 40456 20547 40456 20377 40456 20950 40457 20377 40457 20957 40457 20957 40458 20377 40458 20550 40458 20957 40459 20550 40459 20956 40459 20956 40460 20550 40460 20379 40460 20553 40461 20417 40461 20379 40461 20379 40462 20417 40462 20952 40462 20952 40463 20953 40463 20379 40463 20379 40464 20953 40464 20378 40464 20379 40465 20378 40465 20956 40465 20540 40466 20541 40466 20416 40466 20553 40467 20556 40467 20417 40467 20417 40468 20556 40468 20380 40468 20417 40469 20380 40469 20416 40469 20416 40470 20380 40470 20557 40470 20416 40471 20557 40471 20540 40471 20541 40472 20381 40472 20407 40472 20407 40473 20381 40473 20545 40473 20407 40474 20545 40474 20376 40474 20908 40475 20382 40475 20384 40475 20384 40476 20382 40476 20383 40476 20384 40477 20383 40477 20960 40477 20965 40478 20392 40478 20964 40478 20964 40479 20392 40479 20384 40479 20964 40480 20384 40480 20961 40480 20961 40481 20384 40481 20960 40481 20388 40482 20385 40482 20386 40482 20384 40483 20321 40483 20386 40483 20386 40484 20321 40484 20387 40484 20386 40485 20387 40485 20388 40485 20389 40486 20396 40486 20629 40486 20629 40487 20396 40487 20627 40487 20390 40488 20631 40488 20392 40488 20965 40489 20391 40489 20392 40489 20392 40490 20391 40490 20396 40490 20392 40491 20396 40491 20390 40491 20390 40492 20396 40492 20389 40492 20631 40493 20619 40493 20392 40493 20392 40494 20619 40494 20393 40494 20392 40495 20393 40495 20384 40495 20384 40496 20393 40496 20621 40496 20384 40497 20621 40497 20623 40497 20887 40498 20405 40498 20886 40498 20886 40499 20405 40499 20402 40499 20886 40500 20402 40500 20394 40500 20394 40501 20402 40501 20357 40501 20394 40502 20357 40502 20322 40502 20322 40503 20357 40503 20364 40503 20322 40504 20364 40504 20395 40504 20395 40505 20364 40505 20355 40505 20395 40506 20355 40506 20324 40506 20339 40507 20328 40507 20332 40507 20332 40508 20328 40508 20386 40508 20332 40509 20386 40509 20396 40509 20396 40510 20386 40510 20385 40510 20396 40511 20385 40511 20627 40511 20403 40512 20690 40512 20692 40512 20692 40513 20397 40513 20403 40513 20403 40514 20397 40514 20398 40514 20403 40515 20398 40515 20399 40515 20399 40516 20398 40516 20695 40516 20399 40517 20695 40517 20698 40517 20406 40518 20701 40518 20405 40518 20405 40519 20701 40519 20704 40519 20405 40520 20704 40520 20402 40520 20402 40521 20704 40521 20705 40521 20705 40522 20400 40522 20402 40522 20402 40523 20400 40523 20401 40523 20402 40524 20401 40524 20687 40524 20738 40525 20357 40525 20942 40525 20942 40526 20357 40526 20402 40526 20942 40527 20402 40527 20403 40527 20403 40528 20402 40528 20687 40528 20403 40529 20687 40529 20690 40529 20368 40530 20404 40530 20367 40530 20367 40531 20404 40531 20941 40531 20367 40532 20941 40532 20420 40532 20420 40533 20941 40533 20399 40533 20420 40534 20399 40534 20405 40534 20405 40535 20399 40535 20698 40535 20405 40536 20698 40536 20406 40536 20541 40537 20407 40537 20416 40537 20416 40538 20407 40538 20408 40538 20416 40539 20408 40539 20409 40539 20409 40540 20408 40540 20334 40540 20409 40541 20334 40541 20335 40541 20335 40542 20334 40542 20333 40542 20335 40543 20333 40543 20410 40543 20391 40544 20411 40544 20396 40544 20396 40545 20411 40545 20966 40545 20396 40546 20966 40546 20332 40546 20332 40547 20966 40547 20412 40547 20332 40548 20412 40548 20335 40548 20335 40549 20412 40549 20413 40549 20335 40550 20413 40550 20409 40550 20409 40551 20413 40551 20414 40551 20409 40552 20414 40552 20416 40552 20416 40553 20414 40553 20415 40553 20416 40554 20415 40554 20417 40554 20418 40555 20419 40555 20405 40555 20405 40556 20419 40556 20351 40556 20405 40557 20351 40557 20420 40557 20420 40558 20351 40558 20421 40558 20420 40559 20421 40559 20367 40559 20367 40560 20421 40560 20345 40560 20367 40561 20345 40561 20375 40561 20422 40562 20502 40562 20432 40562 20423 40563 20424 40563 20497 40563 20425 40564 20426 40564 20485 40564 20815 40565 20810 40565 20470 40565 20427 40566 20428 40566 20429 40566 20306 40567 20305 40567 20507 40567 20297 40568 20500 40568 20497 40568 20297 40569 20497 40569 20299 40569 20304 40570 20430 40570 20497 40570 20497 40571 20430 40571 20302 40571 20302 40572 20301 40572 20497 40572 20497 40573 20301 40573 20431 40573 20497 40574 20431 40574 20299 40574 20306 40575 20507 40575 20307 40575 20312 40576 20310 40576 20432 40576 20432 40577 20310 40577 20309 40577 20432 40578 20309 40578 20507 40578 20507 40579 20309 40579 20433 40579 20507 40580 20433 40580 20307 40580 20527 40581 20528 40581 20486 40581 20509 40582 20435 40582 20539 40582 20539 40583 20435 40583 20434 40583 20530 40584 20532 40584 20435 40584 20435 40585 20532 40585 20535 40585 20435 40586 20535 40586 20434 40586 20539 40587 20436 40587 20509 40587 20509 40588 20436 40588 20520 40588 20509 40589 20520 40589 20437 40589 20437 40590 20520 40590 20521 40590 20523 40591 20438 40591 20521 40591 20521 40592 20438 40592 20317 40592 20521 40593 20317 40593 20437 40593 20527 40594 20486 40594 20439 40594 20439 40595 20486 40595 20318 40595 20439 40596 20318 40596 20523 40596 20523 40597 20318 40597 20440 40597 20523 40598 20440 40598 20438 40598 20632 40599 20441 40599 20483 40599 20483 40600 20441 40600 20442 40600 20445 40601 20443 40601 20636 40601 20442 40602 20441 40602 20289 40602 20289 40603 20441 40603 20444 40603 20289 40604 20444 40604 20291 40604 20636 40605 20443 40605 20444 40605 20444 40606 20443 40606 20292 40606 20444 40607 20292 40607 20291 40607 20640 40608 20447 40608 20446 40608 20446 40609 20447 40609 20445 40609 20446 40610 20445 40610 20638 40610 20638 40611 20445 40611 20636 40611 20640 40612 20643 40612 20447 40612 20447 40613 20643 40613 20448 40613 20447 40614 20448 40614 20429 40614 20429 40615 20448 40615 20449 40615 20429 40616 20449 40616 20427 40616 20488 40617 20748 40617 20450 40617 20488 40618 20450 40618 20517 40618 20452 40619 20451 40619 20757 40619 20757 40620 20761 40620 20452 40620 20452 40621 20761 40621 20755 40621 20452 40622 20755 40622 20484 40622 20484 40623 20755 40623 20753 40623 20484 40624 20753 40624 20491 40624 20572 40625 20574 40625 20454 40625 20574 40626 20575 40626 20454 40626 20454 40627 20575 40627 20453 40627 20454 40628 20453 40628 20514 40628 20514 40629 20453 40629 20455 40629 20514 40630 20455 40630 20562 40630 20461 40631 20456 40631 20459 40631 20459 40632 20456 40632 20568 40632 20563 40633 20457 40633 20451 40633 20451 40634 20457 40634 20458 40634 20458 40635 20457 40635 20567 40635 20458 40636 20567 40636 20764 40636 20825 40637 20459 40637 20824 40637 20824 40638 20459 40638 20506 40638 20824 40639 20506 40639 20460 40639 20469 40640 20771 40640 20467 40640 20764 40641 20567 40641 20766 40641 20766 40642 20567 40642 20461 40642 20766 40643 20461 40643 20462 40643 20462 40644 20461 40644 20459 40644 20462 40645 20459 40645 20771 40645 20771 40646 20459 40646 20825 40646 20771 40647 20825 40647 20467 40647 20819 40648 20463 40648 20823 40648 20823 40649 20463 40649 20464 40649 20823 40650 20464 40650 20466 40650 20783 40651 20465 40651 20464 40651 20464 40652 20465 40652 20777 40652 20464 40653 20777 40653 20466 40653 20466 40654 20777 40654 20778 40654 20466 40655 20778 40655 20467 40655 20467 40656 20778 40656 20468 40656 20467 40657 20468 40657 20469 40657 20815 40658 20470 40658 20814 40658 20472 40659 20800 40659 20318 40659 20471 40660 20788 40660 20320 40660 20320 40661 20788 40661 20785 40661 20320 40662 20785 40662 20814 40662 20800 40663 20793 40663 20318 40663 20318 40664 20793 40664 20795 40664 20318 40665 20795 40665 20320 40665 20320 40666 20795 40666 20791 40666 20320 40667 20791 40667 20471 40667 20472 40668 20318 40668 20473 40668 20473 40669 20318 40669 20486 40669 20473 40670 20486 40670 20803 40670 20452 40671 20474 40671 20486 40671 20486 40672 20474 40672 20805 40672 20486 40673 20805 40673 20803 40673 20810 40674 20812 40674 20484 40674 20484 40675 20812 40675 20813 40675 20484 40676 20813 40676 20452 40676 20452 40677 20813 40677 20809 40677 20452 40678 20809 40678 20474 40678 20819 40679 20817 40679 20463 40679 20463 40680 20817 40680 20475 40680 20463 40681 20475 40681 20477 40681 20460 40682 20506 40682 20829 40682 20829 40683 20506 40683 20507 40683 20829 40684 20507 40684 20832 40684 20475 40685 20476 40685 20477 40685 20477 40686 20476 40686 20837 40686 20477 40687 20837 40687 20479 40687 20837 40688 20478 40688 20479 40688 20479 40689 20478 40689 20480 40689 20479 40690 20480 40690 20305 40690 20480 40691 20836 40691 20305 40691 20305 40692 20836 40692 20481 40692 20305 40693 20481 40693 20507 40693 20507 40694 20481 40694 20482 40694 20507 40695 20482 40695 20832 40695 20814 40696 20470 40696 20320 40696 20320 40697 20470 40697 20429 40697 20320 40698 20429 40698 20483 40698 20483 40699 20429 40699 20428 40699 20483 40700 20428 40700 20632 40700 20810 40701 20484 40701 20470 40701 20470 40702 20484 40702 20485 40702 20470 40703 20485 40703 20429 40703 20429 40704 20485 40704 20426 40704 20429 40705 20426 40705 20447 40705 20528 40706 20530 40706 20486 40706 20486 40707 20530 40707 20435 40707 20486 40708 20435 40708 20452 40708 20452 40709 20435 40709 20512 40709 20452 40710 20512 40710 20451 40710 20451 40711 20512 40711 20514 40711 20451 40712 20514 40712 20563 40712 20563 40713 20514 40713 20562 40713 20678 40714 20680 40714 20517 40714 20495 40715 20494 40715 20487 40715 20680 40716 20682 40716 20517 40716 20517 40717 20682 40717 20684 40717 20517 40718 20684 40718 20488 40718 20488 40719 20684 40719 20489 40719 20488 40720 20489 40720 20490 40720 20491 40721 20750 40721 20484 40721 20484 40722 20750 40722 20748 40722 20484 40723 20748 40723 20485 40723 20485 40724 20748 40724 20488 40724 20485 40725 20488 40725 20425 40725 20425 40726 20488 40726 20490 40726 20425 40727 20490 40727 20492 40727 20492 40728 20671 40728 20425 40728 20425 40729 20671 40729 20493 40729 20425 40730 20493 40730 20495 40730 20495 40731 20493 40731 20673 40731 20495 40732 20673 40732 20494 40732 20487 40733 20678 40733 20495 40733 20495 40734 20678 40734 20517 40734 20495 40735 20517 40735 20496 40735 20496 40736 20517 40736 20498 40736 20497 40737 20424 40737 20498 40737 20424 40738 20707 40738 20498 40738 20498 40739 20707 40739 20710 40739 20498 40740 20710 40740 20496 40740 20496 40741 20710 40741 20711 40741 20720 40742 20499 40742 20500 40742 20500 40743 20499 40743 20501 40743 20500 40744 20501 40744 20497 40744 20497 40745 20501 40745 20723 40745 20497 40746 20723 40746 20423 40746 20711 40747 20713 40747 20496 40747 20496 40748 20713 40748 20716 40748 20496 40749 20716 40749 20500 40749 20500 40750 20716 40750 20717 40750 20500 40751 20717 40751 20720 40751 20432 40752 20502 40752 20504 40752 20504 40753 20502 40753 20503 40753 20504 40754 20503 40754 20598 40754 20608 40755 20610 40755 20507 40755 20507 40756 20610 40756 20612 40756 20507 40757 20612 40757 20432 40757 20432 40758 20612 40758 20505 40758 20432 40759 20505 40759 20422 40759 20598 40760 20600 40760 20504 40760 20504 40761 20600 40761 20506 40761 20504 40762 20506 40762 20454 40762 20454 40763 20506 40763 20459 40763 20454 40764 20459 40764 20572 40764 20572 40765 20459 40765 20568 40765 20600 40766 20601 40766 20506 40766 20506 40767 20601 40767 20603 40767 20506 40768 20603 40768 20507 40768 20507 40769 20603 40769 20508 40769 20507 40770 20508 40770 20608 40770 20509 40771 20510 40771 20435 40771 20435 40772 20510 40772 20511 40772 20435 40773 20511 40773 20512 40773 20512 40774 20511 40774 20513 40774 20512 40775 20513 40775 20514 40775 20514 40776 20513 40776 20515 40776 20514 40777 20515 40777 20454 40777 20454 40778 20515 40778 20314 40778 20454 40779 20314 40779 20504 40779 20504 40780 20314 40780 20313 40780 20504 40781 20313 40781 20432 40781 20432 40782 20313 40782 20516 40782 20432 40783 20516 40783 20312 40783 20450 40784 20783 40784 20517 40784 20517 40785 20783 40785 20464 40785 20517 40786 20464 40786 20498 40786 20498 40787 20464 40787 20463 40787 20498 40788 20463 40788 20497 40788 20497 40789 20463 40789 20477 40789 20497 40790 20477 40790 20304 40790 20304 40791 20477 40791 20479 40791 20518 40792 20436 40792 20539 40792 20518 40793 20555 40793 20436 40793 20436 40794 20555 40794 20554 40794 20436 40795 20554 40795 20520 40795 20554 40796 20519 40796 20520 40796 20520 40797 20519 40797 20552 40797 20520 40798 20552 40798 20521 40798 20552 40799 20551 40799 20521 40799 20521 40800 20551 40800 20522 40800 20521 40801 20522 40801 20523 40801 20523 40802 20522 40802 20549 40802 20523 40803 20549 40803 20439 40803 20549 40804 20548 40804 20439 40804 20439 40805 20548 40805 20524 40805 20439 40806 20524 40806 20527 40806 20527 40807 20524 40807 20525 40807 20525 40808 20526 40808 20527 40808 20527 40809 20526 40809 20546 40809 20527 40810 20546 40810 20528 40810 20546 40811 20529 40811 20528 40811 20528 40812 20529 40812 20544 40812 20528 40813 20544 40813 20530 40813 20544 40814 20543 40814 20530 40814 20530 40815 20543 40815 20542 40815 20530 40816 20542 40816 20532 40816 20542 40817 20531 40817 20532 40817 20532 40818 20531 40818 20533 40818 20532 40819 20533 40819 20535 40819 20533 40820 20534 40820 20535 40820 20535 40821 20534 40821 20536 40821 20535 40822 20536 40822 20434 40822 20536 40823 20537 40823 20434 40823 20434 40824 20537 40824 20538 40824 20434 40825 20538 40825 20539 40825 20539 40826 20538 40826 20558 40826 20539 40827 20558 40827 20518 40827 20540 40828 20557 40828 20537 40828 20537 40829 20536 40829 20540 40829 20540 40830 20536 40830 20534 40830 20540 40831 20534 40831 20541 40831 20534 40832 20533 40832 20541 40832 20541 40833 20533 40833 20531 40833 20541 40834 20531 40834 20381 40834 20531 40835 20542 40835 20381 40835 20381 40836 20542 40836 20543 40836 20381 40837 20543 40837 20545 40837 20543 40838 20544 40838 20545 40838 20545 40839 20544 40839 20529 40839 20545 40840 20529 40840 20376 40840 20376 40841 20529 40841 20546 40841 20376 40842 20546 40842 20547 40842 20546 40843 20526 40843 20547 40843 20547 40844 20526 40844 20525 40844 20547 40845 20525 40845 20377 40845 20525 40846 20524 40846 20377 40846 20377 40847 20524 40847 20548 40847 20377 40848 20548 40848 20550 40848 20548 40849 20549 40849 20550 40849 20550 40850 20549 40850 20522 40850 20550 40851 20522 40851 20379 40851 20522 40852 20551 40852 20379 40852 20379 40853 20551 40853 20552 40853 20379 40854 20552 40854 20553 40854 20552 40855 20519 40855 20553 40855 20553 40856 20519 40856 20554 40856 20553 40857 20554 40857 20556 40857 20554 40858 20555 40858 20556 40858 20556 40859 20555 40859 20518 40859 20556 40860 20518 40860 20380 40860 20380 40861 20518 40861 20558 40861 20380 40862 20558 40862 20557 40862 20557 40863 20558 40863 20538 40863 20557 40864 20538 40864 20537 40864 20559 40865 20455 40865 20453 40865 20559 40866 20592 40866 20455 40866 20455 40867 20592 40867 20591 40867 20455 40868 20591 40868 20562 40868 20591 40869 20560 40869 20562 40869 20562 40870 20560 40870 20561 40870 20562 40871 20561 40871 20563 40871 20561 40872 20564 40872 20563 40872 20563 40873 20564 40873 20565 40873 20563 40874 20565 40874 20457 40874 20457 40875 20565 40875 20589 40875 20457 40876 20589 40876 20567 40876 20589 40877 20566 40877 20567 40877 20567 40878 20566 40878 20587 40878 20567 40879 20587 40879 20461 40879 20461 40880 20587 40880 20586 40880 20586 40881 20585 40881 20461 40881 20461 40882 20585 40882 20584 40882 20461 40883 20584 40883 20456 40883 20584 40884 20583 40884 20456 40884 20456 40885 20583 40885 20581 40885 20456 40886 20581 40886 20568 40886 20581 40887 20569 40887 20568 40887 20568 40888 20569 40888 20570 40888 20568 40889 20570 40889 20572 40889 20570 40890 20571 40890 20572 40890 20572 40891 20571 40891 20573 40891 20572 40892 20573 40892 20574 40892 20573 40893 20579 40893 20574 40893 20574 40894 20579 40894 20578 40894 20574 40895 20578 40895 20575 40895 20578 40896 20577 40896 20575 40896 20575 40897 20577 40897 20576 40897 20575 40898 20576 40898 20453 40898 20453 40899 20576 40899 20594 40899 20453 40900 20594 40900 20559 40900 20338 40901 20337 40901 20577 40901 20577 40902 20578 40902 20338 40902 20338 40903 20578 40903 20579 40903 20338 40904 20579 40904 20339 40904 20579 40905 20573 40905 20339 40905 20339 40906 20573 40906 20571 40906 20339 40907 20571 40907 20580 40907 20571 40908 20570 40908 20580 40908 20580 40909 20570 40909 20569 40909 20580 40910 20569 40910 20582 40910 20569 40911 20581 40911 20582 40911 20582 40912 20581 40912 20583 40912 20582 40913 20583 40913 20340 40913 20583 40914 20584 40914 20340 40914 20340 40915 20584 40915 20585 40915 20340 40916 20585 40916 20341 40916 20341 40917 20585 40917 20586 40917 20341 40918 20586 40918 20588 40918 20586 40919 20587 40919 20588 40919 20588 40920 20587 40920 20566 40920 20588 40921 20566 40921 20333 40921 20566 40922 20589 40922 20333 40922 20333 40923 20589 40923 20565 40923 20333 40924 20565 40924 20410 40924 20565 40925 20564 40925 20410 40925 20410 40926 20564 40926 20561 40926 20410 40927 20561 40927 20590 40927 20561 40928 20560 40928 20590 40928 20590 40929 20560 40929 20591 40929 20590 40930 20591 40930 20593 40930 20591 40931 20592 40931 20593 40931 20593 40932 20592 40932 20559 40932 20593 40933 20559 40933 20336 40933 20336 40934 20559 40934 20594 40934 20336 40935 20594 40935 20337 40935 20337 40936 20594 40936 20576 40936 20337 40937 20576 40937 20577 40937 20615 40938 20503 40938 20502 40938 20615 40939 20595 40939 20503 40939 20503 40940 20595 40940 20596 40940 20503 40941 20596 40941 20598 40941 20596 40942 20597 40942 20598 40942 20598 40943 20597 40943 20599 40943 20598 40944 20599 40944 20600 40944 20599 40945 20628 40945 20600 40945 20600 40946 20628 40946 20626 40946 20600 40947 20626 40947 20601 40947 20601 40948 20626 40948 20602 40948 20601 40949 20602 40949 20603 40949 20602 40950 20625 40950 20603 40950 20603 40951 20625 40951 20604 40951 20603 40952 20604 40952 20508 40952 20508 40953 20604 40953 20605 40953 20605 40954 20624 40954 20508 40954 20508 40955 20624 40955 20606 40955 20508 40956 20606 40956 20608 40956 20606 40957 20607 40957 20608 40957 20608 40958 20607 40958 20609 40958 20608 40959 20609 40959 20610 40959 20609 40960 20622 40960 20610 40960 20610 40961 20622 40961 20611 40961 20610 40962 20611 40962 20612 40962 20611 40963 20613 40963 20612 40963 20612 40964 20613 40964 20620 40964 20612 40965 20620 40965 20505 40965 20620 40966 20618 40966 20505 40966 20505 40967 20618 40967 20617 40967 20505 40968 20617 40968 20422 40968 20617 40969 20616 40969 20422 40969 20422 40970 20616 40970 20614 40970 20422 40971 20614 40971 20502 40971 20502 40972 20614 40972 20630 40972 20502 40973 20630 40973 20615 40973 20619 40974 20631 40974 20616 40974 20616 40975 20617 40975 20619 40975 20619 40976 20617 40976 20618 40976 20619 40977 20618 40977 20393 40977 20618 40978 20620 40978 20393 40978 20393 40979 20620 40979 20613 40979 20393 40980 20613 40980 20621 40980 20613 40981 20611 40981 20621 40981 20621 40982 20611 40982 20622 40982 20621 40983 20622 40983 20623 40983 20622 40984 20609 40984 20623 40984 20623 40985 20609 40985 20607 40985 20623 40986 20607 40986 20321 40986 20607 40987 20606 40987 20321 40987 20321 40988 20606 40988 20624 40988 20321 40989 20624 40989 20387 40989 20387 40990 20624 40990 20605 40990 20387 40991 20605 40991 20388 40991 20605 40992 20604 40992 20388 40992 20388 40993 20604 40993 20625 40993 20388 40994 20625 40994 20385 40994 20625 40995 20602 40995 20385 40995 20385 40996 20602 40996 20626 40996 20385 40997 20626 40997 20627 40997 20626 40998 20628 40998 20627 40998 20627 40999 20628 40999 20599 40999 20627 41000 20599 41000 20629 41000 20599 41001 20597 41001 20629 41001 20629 41002 20597 41002 20596 41002 20629 41003 20596 41003 20389 41003 20596 41004 20595 41004 20389 41004 20389 41005 20595 41005 20615 41005 20389 41006 20615 41006 20390 41006 20390 41007 20615 41007 20630 41007 20390 41008 20630 41008 20631 41008 20631 41009 20630 41009 20614 41009 20631 41010 20614 41010 20616 41010 20645 41011 20632 41011 20428 41011 20645 41012 20665 41012 20632 41012 20632 41013 20665 41013 20633 41013 20632 41014 20633 41014 20441 41014 20633 41015 20662 41015 20441 41015 20441 41016 20662 41016 20634 41016 20441 41017 20634 41017 20444 41017 20634 41018 20635 41018 20444 41018 20444 41019 20635 41019 20661 41019 20444 41020 20661 41020 20636 41020 20636 41021 20661 41021 20660 41021 20636 41022 20660 41022 20638 41022 20660 41023 20659 41023 20638 41023 20638 41024 20659 41024 20637 41024 20638 41025 20637 41025 20446 41025 20446 41026 20637 41026 20639 41026 20639 41027 20655 41027 20446 41027 20446 41028 20655 41028 20654 41028 20446 41029 20654 41029 20640 41029 20654 41030 20653 41030 20640 41030 20640 41031 20653 41031 20641 41031 20640 41032 20641 41032 20643 41032 20641 41033 20642 41033 20643 41033 20643 41034 20642 41034 20644 41034 20643 41035 20644 41035 20448 41035 20644 41036 20650 41036 20448 41036 20448 41037 20650 41037 20649 41037 20448 41038 20649 41038 20449 41038 20649 41039 20648 41039 20449 41039 20449 41040 20648 41040 20647 41040 20449 41041 20647 41041 20427 41041 20647 41042 20646 41042 20427 41042 20427 41043 20646 41043 20667 41043 20427 41044 20667 41044 20428 41044 20428 41045 20667 41045 20666 41045 20428 41046 20666 41046 20645 41046 20366 41047 20668 41047 20646 41047 20646 41048 20647 41048 20366 41048 20366 41049 20647 41049 20648 41049 20366 41050 20648 41050 20368 41050 20648 41051 20649 41051 20368 41051 20368 41052 20649 41052 20650 41052 20368 41053 20650 41053 20651 41053 20650 41054 20644 41054 20651 41054 20651 41055 20644 41055 20642 41055 20651 41056 20642 41056 20652 41056 20642 41057 20641 41057 20652 41057 20652 41058 20641 41058 20653 41058 20652 41059 20653 41059 20656 41059 20653 41060 20654 41060 20656 41060 20656 41061 20654 41061 20655 41061 20656 41062 20655 41062 20657 41062 20657 41063 20655 41063 20639 41063 20657 41064 20639 41064 20658 41064 20639 41065 20637 41065 20658 41065 20658 41066 20637 41066 20659 41066 20658 41067 20659 41067 20371 41067 20659 41068 20660 41068 20371 41068 20371 41069 20660 41069 20661 41069 20371 41070 20661 41070 20373 41070 20661 41071 20635 41071 20373 41071 20373 41072 20635 41072 20634 41072 20373 41073 20634 41073 20663 41073 20634 41074 20662 41074 20663 41074 20663 41075 20662 41075 20633 41075 20663 41076 20633 41076 20664 41076 20633 41077 20665 41077 20664 41077 20664 41078 20665 41078 20645 41078 20664 41079 20645 41079 20365 41079 20365 41080 20645 41080 20666 41080 20365 41081 20666 41081 20668 41081 20668 41082 20666 41082 20667 41082 20668 41083 20667 41083 20646 41083 20686 41084 20489 41084 20684 41084 20686 41085 20703 41085 20489 41085 20489 41086 20703 41086 20702 41086 20489 41087 20702 41087 20490 41087 20702 41088 20669 41088 20490 41088 20490 41089 20669 41089 20670 41089 20490 41090 20670 41090 20492 41090 20670 41091 20700 41091 20492 41091 20492 41092 20700 41092 20699 41092 20492 41093 20699 41093 20671 41093 20671 41094 20699 41094 20697 41094 20671 41095 20697 41095 20493 41095 20697 41096 20696 41096 20493 41096 20493 41097 20696 41097 20672 41097 20493 41098 20672 41098 20673 41098 20673 41099 20672 41099 20694 41099 20694 41100 20693 41100 20673 41100 20673 41101 20693 41101 20674 41101 20673 41102 20674 41102 20494 41102 20674 41103 20675 41103 20494 41103 20494 41104 20675 41104 20691 41104 20494 41105 20691 41105 20487 41105 20691 41106 20676 41106 20487 41106 20487 41107 20676 41107 20677 41107 20487 41108 20677 41108 20678 41108 20677 41109 20689 41109 20678 41109 20678 41110 20689 41110 20688 41110 20678 41111 20688 41111 20680 41111 20688 41112 20679 41112 20680 41112 20680 41113 20679 41113 20681 41113 20680 41114 20681 41114 20682 41114 20681 41115 20706 41115 20682 41115 20682 41116 20706 41116 20683 41116 20682 41117 20683 41117 20684 41117 20684 41118 20683 41118 20685 41118 20684 41119 20685 41119 20686 41119 20401 41120 20400 41120 20706 41120 20706 41121 20681 41121 20401 41121 20401 41122 20681 41122 20679 41122 20401 41123 20679 41123 20687 41123 20679 41124 20688 41124 20687 41124 20687 41125 20688 41125 20689 41125 20687 41126 20689 41126 20690 41126 20689 41127 20677 41127 20690 41127 20690 41128 20677 41128 20676 41128 20690 41129 20676 41129 20692 41129 20676 41130 20691 41130 20692 41130 20692 41131 20691 41131 20675 41131 20692 41132 20675 41132 20397 41132 20675 41133 20674 41133 20397 41133 20397 41134 20674 41134 20693 41134 20397 41135 20693 41135 20398 41135 20398 41136 20693 41136 20694 41136 20398 41137 20694 41137 20695 41137 20694 41138 20672 41138 20695 41138 20695 41139 20672 41139 20696 41139 20695 41140 20696 41140 20698 41140 20696 41141 20697 41141 20698 41141 20698 41142 20697 41142 20699 41142 20698 41143 20699 41143 20406 41143 20699 41144 20700 41144 20406 41144 20406 41145 20700 41145 20670 41145 20406 41146 20670 41146 20701 41146 20670 41147 20669 41147 20701 41147 20701 41148 20669 41148 20702 41148 20701 41149 20702 41149 20704 41149 20702 41150 20703 41150 20704 41150 20704 41151 20703 41151 20686 41151 20704 41152 20686 41152 20705 41152 20705 41153 20686 41153 20685 41153 20705 41154 20685 41154 20400 41154 20400 41155 20685 41155 20683 41155 20400 41156 20683 41156 20706 41156 20743 41157 20707 41157 20424 41157 20743 41158 20708 41158 20707 41158 20707 41159 20708 41159 20709 41159 20707 41160 20709 41160 20710 41160 20709 41161 20741 41161 20710 41161 20710 41162 20741 41162 20740 41162 20710 41163 20740 41163 20711 41163 20740 41164 20739 41164 20711 41164 20711 41165 20739 41165 20712 41165 20711 41166 20712 41166 20713 41166 20713 41167 20712 41167 20714 41167 20713 41168 20714 41168 20716 41168 20714 41169 20737 41169 20716 41169 20716 41170 20737 41170 20715 41170 20716 41171 20715 41171 20717 41171 20717 41172 20715 41172 20718 41172 20718 41173 20719 41173 20717 41173 20717 41174 20719 41174 20735 41174 20717 41175 20735 41175 20720 41175 20735 41176 20734 41176 20720 41176 20720 41177 20734 41177 20732 41177 20720 41178 20732 41178 20499 41178 20732 41179 20731 41179 20499 41179 20499 41180 20731 41180 20721 41180 20499 41181 20721 41181 20501 41181 20721 41182 20729 41182 20501 41182 20501 41183 20729 41183 20727 41183 20501 41184 20727 41184 20723 41184 20727 41185 20722 41185 20723 41185 20723 41186 20722 41186 20724 41186 20723 41187 20724 41187 20423 41187 20724 41188 20725 41188 20423 41188 20423 41189 20725 41189 20746 41189 20423 41190 20746 41190 20424 41190 20424 41191 20746 41191 20744 41191 20424 41192 20744 41192 20743 41192 20726 41193 20745 41193 20725 41193 20725 41194 20724 41194 20726 41194 20726 41195 20724 41195 20722 41195 20726 41196 20722 41196 20728 41196 20722 41197 20727 41197 20728 41197 20728 41198 20727 41198 20729 41198 20728 41199 20729 41199 20730 41199 20729 41200 20721 41200 20730 41200 20730 41201 20721 41201 20731 41201 20730 41202 20731 41202 20733 41202 20731 41203 20732 41203 20733 41203 20733 41204 20732 41204 20734 41204 20733 41205 20734 41205 20736 41205 20734 41206 20735 41206 20736 41206 20736 41207 20735 41207 20719 41207 20736 41208 20719 41208 20360 41208 20360 41209 20719 41209 20718 41209 20360 41210 20718 41210 20361 41210 20718 41211 20715 41211 20361 41211 20361 41212 20715 41212 20737 41212 20361 41213 20737 41213 20738 41213 20737 41214 20714 41214 20738 41214 20738 41215 20714 41215 20712 41215 20738 41216 20712 41216 20359 41216 20712 41217 20739 41217 20359 41217 20359 41218 20739 41218 20740 41218 20359 41219 20740 41219 20356 41219 20740 41220 20741 41220 20356 41220 20356 41221 20741 41221 20709 41221 20356 41222 20709 41222 20363 41222 20709 41223 20708 41223 20363 41223 20363 41224 20708 41224 20743 41224 20363 41225 20743 41225 20742 41225 20742 41226 20743 41226 20744 41226 20742 41227 20744 41227 20745 41227 20745 41228 20744 41228 20746 41228 20745 41229 20746 41229 20725 41229 20901 41230 20758 41230 20451 41230 20748 41231 20747 41231 20781 41231 20748 41232 20781 41232 20450 41232 20747 41233 20748 41233 20749 41233 20749 41234 20748 41234 20750 41234 20749 41235 20750 41235 20751 41235 20751 41236 20750 41236 20890 41236 20890 41237 20750 41237 20491 41237 20890 41238 20491 41238 20891 41238 20891 41239 20491 41239 20752 41239 20752 41240 20491 41240 20753 41240 20752 41241 20753 41241 20892 41241 20892 41242 20753 41242 20754 41242 20754 41243 20753 41243 20755 41243 20754 41244 20755 41244 20894 41244 20761 41245 20897 41245 20755 41245 20755 41246 20897 41246 20756 41246 20755 41247 20756 41247 20894 41247 20451 41248 20758 41248 20757 41248 20758 41249 20759 41249 20757 41249 20757 41250 20759 41250 20760 41250 20757 41251 20760 41251 20761 41251 20761 41252 20760 41252 20762 41252 20761 41253 20762 41253 20897 41253 20901 41254 20451 41254 20902 41254 20902 41255 20451 41255 20458 41255 20902 41256 20458 41256 20903 41256 20903 41257 20458 41257 20764 41257 20903 41258 20764 41258 20905 41258 20905 41259 20764 41259 20763 41259 20763 41260 20764 41260 20766 41260 20763 41261 20766 41261 20765 41261 20765 41262 20766 41262 20767 41262 20767 41263 20766 41263 20462 41263 20767 41264 20462 41264 20768 41264 20768 41265 20462 41265 20769 41265 20769 41266 20462 41266 20771 41266 20769 41267 20771 41267 20770 41267 20770 41268 20771 41268 20772 41268 20772 41269 20771 41269 20469 41269 20772 41270 20469 41270 20773 41270 20773 41271 20469 41271 20878 41271 20878 41272 20469 41272 20468 41272 20878 41273 20468 41273 20879 41273 20778 41274 20774 41274 20468 41274 20468 41275 20774 41275 20881 41275 20468 41276 20881 41276 20879 41276 20777 41277 20465 41277 20775 41277 20775 41278 20776 41278 20777 41278 20777 41279 20776 41279 20779 41279 20777 41280 20779 41280 20778 41280 20778 41281 20779 41281 20780 41281 20778 41282 20780 41282 20774 41282 20781 41283 20888 41283 20450 41283 20450 41284 20888 41284 20782 41284 20450 41285 20782 41285 20783 41285 20783 41286 20782 41286 20784 41286 20783 41287 20784 41287 20465 41287 20465 41288 20784 41288 20885 41288 20465 41289 20885 41289 20775 41289 20799 41290 20867 41290 20800 41290 20785 41291 20860 41291 20859 41291 20785 41292 20859 41292 20814 41292 20860 41293 20785 41293 20786 41293 20786 41294 20785 41294 20788 41294 20786 41295 20788 41295 20787 41295 20787 41296 20788 41296 20862 41296 20862 41297 20788 41297 20471 41297 20862 41298 20471 41298 20789 41298 20789 41299 20471 41299 20790 41299 20790 41300 20471 41300 20791 41300 20790 41301 20791 41301 20792 41301 20795 41302 20798 41302 20791 41302 20791 41303 20798 41303 20865 41303 20791 41304 20865 41304 20792 41304 20800 41305 20867 41305 20793 41305 20867 41306 20794 41306 20793 41306 20793 41307 20794 41307 20796 41307 20793 41308 20796 41308 20795 41308 20795 41309 20796 41309 20797 41309 20795 41310 20797 41310 20798 41310 20799 41311 20800 41311 20869 41311 20869 41312 20800 41312 20472 41312 20869 41313 20472 41313 20870 41313 20870 41314 20472 41314 20473 41314 20870 41315 20473 41315 20801 41315 20801 41316 20473 41316 20802 41316 20802 41317 20473 41317 20803 41317 20802 41318 20803 41318 20873 41318 20873 41319 20803 41319 20804 41319 20804 41320 20803 41320 20805 41320 20804 41321 20805 41321 20841 41321 20841 41322 20805 41322 20806 41322 20806 41323 20805 41323 20474 41323 20806 41324 20474 41324 20807 41324 20807 41325 20474 41325 20808 41325 20808 41326 20474 41326 20809 41326 20808 41327 20809 41327 20844 41327 20844 41328 20809 41328 20846 41328 20846 41329 20809 41329 20813 41329 20846 41330 20813 41330 20848 41330 20812 41331 20810 41331 20811 41331 20811 41332 20852 41332 20812 41332 20812 41333 20852 41333 20851 41333 20812 41334 20851 41334 20813 41334 20813 41335 20851 41335 20849 41335 20813 41336 20849 41336 20848 41336 20859 41337 20858 41337 20814 41337 20814 41338 20858 41338 20856 41338 20814 41339 20856 41339 20815 41339 20815 41340 20856 41340 20855 41340 20815 41341 20855 41341 20810 41341 20810 41342 20855 41342 20816 41342 20810 41343 20816 41343 20811 41343 20936 41344 20935 41344 20824 41344 20817 41345 20923 41345 20818 41345 20817 41346 20818 41346 20475 41346 20923 41347 20817 41347 20924 41347 20924 41348 20817 41348 20819 41348 20924 41349 20819 41349 20820 41349 20820 41350 20819 41350 20821 41350 20821 41351 20819 41351 20823 41351 20821 41352 20823 41352 20822 41352 20822 41353 20823 41353 20926 41353 20926 41354 20823 41354 20466 41354 20926 41355 20466 41355 20927 41355 20467 41356 20932 41356 20466 41356 20466 41357 20932 41357 20930 41357 20466 41358 20930 41358 20927 41358 20824 41359 20935 41359 20825 41359 20935 41360 20934 41360 20825 41360 20825 41361 20934 41361 20826 41361 20825 41362 20826 41362 20467 41362 20467 41363 20826 41363 20827 41363 20467 41364 20827 41364 20932 41364 20936 41365 20824 41365 20828 41365 20828 41366 20824 41366 20460 41366 20828 41367 20460 41367 20939 41367 20939 41368 20460 41368 20829 41368 20939 41369 20829 41369 20940 41369 20940 41370 20829 41370 20830 41370 20830 41371 20829 41371 20832 41371 20830 41372 20832 41372 20831 41372 20831 41373 20832 41373 20906 41373 20906 41374 20832 41374 20482 41374 20906 41375 20482 41375 20833 41375 20833 41376 20482 41376 20834 41376 20834 41377 20482 41377 20481 41377 20834 41378 20481 41378 20835 41378 20835 41379 20481 41379 20909 41379 20909 41380 20481 41380 20836 41380 20909 41381 20836 41381 20910 41381 20910 41382 20836 41382 20912 41382 20912 41383 20836 41383 20480 41383 20912 41384 20480 41384 20839 41384 20478 41385 20837 41385 20916 41385 20916 41386 20915 41386 20478 41386 20478 41387 20915 41387 20838 41387 20478 41388 20838 41388 20480 41388 20480 41389 20838 41389 20913 41389 20480 41390 20913 41390 20839 41390 20818 41391 20921 41391 20475 41391 20475 41392 20921 41392 20920 41392 20475 41393 20920 41393 20476 41393 20476 41394 20920 41394 20840 41394 20476 41395 20840 41395 20837 41395 20837 41396 20840 41396 20919 41396 20837 41397 20919 41397 20916 41397 20842 41398 20872 41398 20873 41398 20873 41399 20804 41399 20842 41399 20842 41400 20804 41400 20841 41400 20842 41401 20841 41401 20843 41401 20841 41402 20806 41402 20843 41402 20843 41403 20806 41403 20807 41403 20843 41404 20807 41404 20350 41404 20807 41405 20808 41405 20350 41405 20350 41406 20808 41406 20844 41406 20350 41407 20844 41407 20845 41407 20845 41408 20844 41408 20846 41408 20845 41409 20846 41409 20847 41409 20846 41410 20848 41410 20847 41410 20847 41411 20848 41411 20849 41411 20847 41412 20849 41412 20850 41412 20849 41413 20851 41413 20850 41413 20850 41414 20851 41414 20852 41414 20850 41415 20852 41415 20853 41415 20852 41416 20811 41416 20853 41416 20853 41417 20811 41417 20816 41417 20853 41418 20816 41418 20854 41418 20816 41419 20855 41419 20854 41419 20854 41420 20855 41420 20856 41420 20854 41421 20856 41421 20346 41421 20346 41422 20856 41422 20858 41422 20346 41423 20858 41423 20857 41423 20858 41424 20859 41424 20857 41424 20857 41425 20859 41425 20860 41425 20857 41426 20860 41426 20861 41426 20860 41427 20786 41427 20861 41427 20861 41428 20786 41428 20787 41428 20861 41429 20787 41429 20863 41429 20787 41430 20862 41430 20863 41430 20863 41431 20862 41431 20789 41431 20863 41432 20789 41432 20864 41432 20789 41433 20790 41433 20864 41433 20864 41434 20790 41434 20792 41434 20864 41435 20792 41435 20347 41435 20347 41436 20792 41436 20865 41436 20347 41437 20865 41437 20866 41437 20865 41438 20798 41438 20866 41438 20866 41439 20798 41439 20797 41439 20866 41440 20797 41440 20348 41440 20797 41441 20796 41441 20348 41441 20348 41442 20796 41442 20794 41442 20348 41443 20794 41443 20349 41443 20794 41444 20867 41444 20349 41444 20349 41445 20867 41445 20799 41445 20349 41446 20799 41446 20868 41446 20799 41447 20869 41447 20868 41447 20868 41448 20869 41448 20870 41448 20868 41449 20870 41449 20871 41449 20871 41450 20870 41450 20801 41450 20871 41451 20801 41451 20872 41451 20872 41452 20801 41452 20802 41452 20872 41453 20802 41453 20873 41453 20331 41454 20874 41454 20765 41454 20765 41455 20767 41455 20331 41455 20331 41456 20767 41456 20768 41456 20331 41457 20768 41457 20875 41457 20768 41458 20769 41458 20875 41458 20875 41459 20769 41459 20770 41459 20875 41460 20770 41460 20876 41460 20770 41461 20772 41461 20876 41461 20876 41462 20772 41462 20773 41462 20876 41463 20773 41463 20877 41463 20773 41464 20878 41464 20877 41464 20877 41465 20878 41465 20879 41465 20877 41466 20879 41466 20880 41466 20880 41467 20879 41467 20881 41467 20880 41468 20881 41468 20882 41468 20881 41469 20774 41469 20882 41469 20882 41470 20774 41470 20780 41470 20882 41471 20780 41471 20883 41471 20780 41472 20779 41472 20883 41472 20883 41473 20779 41473 20776 41473 20883 41474 20776 41474 20884 41474 20776 41475 20775 41475 20884 41475 20884 41476 20775 41476 20885 41476 20884 41477 20885 41477 20886 41477 20885 41478 20784 41478 20886 41478 20886 41479 20784 41479 20782 41479 20886 41480 20782 41480 20887 41480 20887 41481 20782 41481 20888 41481 20887 41482 20888 41482 20418 41482 20888 41483 20781 41483 20418 41483 20418 41484 20781 41484 20747 41484 20418 41485 20747 41485 20889 41485 20747 41486 20749 41486 20889 41486 20889 41487 20749 41487 20751 41487 20889 41488 20751 41488 20344 41488 20751 41489 20890 41489 20344 41489 20344 41490 20890 41490 20891 41490 20344 41491 20891 41491 20342 41491 20891 41492 20752 41492 20342 41492 20342 41493 20752 41493 20892 41493 20342 41494 20892 41494 20893 41494 20892 41495 20754 41495 20893 41495 20893 41496 20754 41496 20894 41496 20893 41497 20894 41497 20895 41497 20895 41498 20894 41498 20756 41498 20895 41499 20756 41499 20896 41499 20756 41500 20897 41500 20896 41500 20896 41501 20897 41501 20762 41501 20896 41502 20762 41502 20898 41502 20762 41503 20760 41503 20898 41503 20898 41504 20760 41504 20759 41504 20898 41505 20759 41505 20899 41505 20759 41506 20758 41506 20899 41506 20899 41507 20758 41507 20901 41507 20899 41508 20901 41508 20900 41508 20900 41509 20901 41509 20902 41509 20900 41510 20902 41510 20343 41510 20343 41511 20902 41511 20903 41511 20343 41512 20903 41512 20904 41512 20904 41513 20903 41513 20905 41513 20904 41514 20905 41514 20874 41514 20874 41515 20905 41515 20763 41515 20874 41516 20763 41516 20765 41516 20907 41517 20326 41517 20831 41517 20831 41518 20906 41518 20907 41518 20907 41519 20906 41519 20833 41519 20907 41520 20833 41520 20908 41520 20833 41521 20834 41521 20908 41521 20908 41522 20834 41522 20835 41522 20908 41523 20835 41523 20911 41523 20835 41524 20909 41524 20911 41524 20911 41525 20909 41525 20910 41525 20911 41526 20910 41526 20323 41526 20323 41527 20910 41527 20912 41527 20323 41528 20912 41528 20325 41528 20912 41529 20839 41529 20325 41529 20325 41530 20839 41530 20913 41530 20325 41531 20913 41531 20914 41531 20913 41532 20838 41532 20914 41532 20914 41533 20838 41533 20915 41533 20914 41534 20915 41534 20917 41534 20915 41535 20916 41535 20917 41535 20917 41536 20916 41536 20919 41536 20917 41537 20919 41537 20918 41537 20919 41538 20840 41538 20918 41538 20918 41539 20840 41539 20920 41539 20918 41540 20920 41540 20329 41540 20329 41541 20920 41541 20921 41541 20329 41542 20921 41542 20922 41542 20921 41543 20818 41543 20922 41543 20922 41544 20818 41544 20923 41544 20922 41545 20923 41545 20925 41545 20923 41546 20924 41546 20925 41546 20925 41547 20924 41547 20820 41547 20925 41548 20820 41548 20330 41548 20820 41549 20821 41549 20330 41549 20330 41550 20821 41550 20822 41550 20330 41551 20822 41551 20928 41551 20822 41552 20926 41552 20928 41552 20928 41553 20926 41553 20927 41553 20928 41554 20927 41554 20929 41554 20929 41555 20927 41555 20930 41555 20929 41556 20930 41556 20931 41556 20930 41557 20932 41557 20931 41557 20931 41558 20932 41558 20827 41558 20931 41559 20827 41559 20933 41559 20827 41560 20826 41560 20933 41560 20933 41561 20826 41561 20934 41561 20933 41562 20934 41562 20327 41562 20934 41563 20935 41563 20327 41563 20327 41564 20935 41564 20936 41564 20327 41565 20936 41565 20937 41565 20936 41566 20828 41566 20937 41566 20937 41567 20828 41567 20939 41567 20937 41568 20939 41568 20938 41568 20938 41569 20939 41569 20940 41569 20938 41570 20940 41570 20326 41570 20326 41571 20940 41571 20830 41571 20326 41572 20830 41572 20831 41572 20404 41573 20369 41573 20295 41573 20404 41574 20295 41574 20941 41574 20358 41575 20942 41575 20296 41575 20296 41576 20942 41576 20403 41576 20296 41577 20403 41577 20295 41577 20295 41578 20403 41578 20399 41578 20295 41579 20399 41579 20941 41579 20374 41580 20949 41580 20290 41580 20374 41581 20290 41581 20372 41581 20372 41582 20290 41582 20293 41582 20372 41583 20293 41583 20943 41583 20943 41584 20293 41584 20944 41584 20943 41585 20944 41585 20945 41585 20945 41586 20944 41586 20294 41586 20945 41587 20294 41587 20370 41587 20370 41588 20294 41588 20295 41588 20370 41589 20295 41589 20369 41589 20358 41590 20296 41590 20298 41590 20358 41591 20298 41591 20362 41591 20362 41592 20298 41592 20946 41592 20362 41593 20946 41593 20947 41593 20947 41594 20946 41594 20300 41594 20947 41595 20300 41595 20352 41595 20352 41596 20300 41596 20303 41596 20352 41597 20303 41597 20353 41597 20353 41598 20303 41598 20948 41598 20353 41599 20948 41599 20354 41599 20949 41600 20374 41600 20375 41600 20375 41601 20345 41601 20949 41601 20949 41602 20345 41602 20950 41602 20949 41603 20950 41603 20319 41603 20319 41604 20950 41604 20957 41604 20355 41605 20354 41605 20948 41605 20355 41606 20948 41606 20324 41606 20324 41607 20948 41607 20382 41607 20382 41608 20948 41608 20308 41608 20382 41609 20308 41609 20383 41609 20417 41610 20415 41610 20951 41610 20417 41611 20951 41611 20952 41611 20951 41612 20315 41612 20952 41612 20952 41613 20315 41613 20316 41613 20952 41614 20316 41614 20953 41614 20953 41615 20316 41615 20954 41615 20953 41616 20954 41616 20378 41616 20378 41617 20954 41617 20955 41617 20378 41618 20955 41618 20956 41618 20956 41619 20955 41619 20319 41619 20956 41620 20319 41620 20957 41620 20383 41621 20308 41621 20958 41621 20383 41622 20958 41622 20960 41622 20960 41623 20958 41623 20959 41623 20960 41624 20959 41624 20961 41624 20961 41625 20959 41625 20962 41625 20961 41626 20962 41626 20964 41626 20964 41627 20962 41627 20963 41627 20964 41628 20963 41628 20965 41628 20965 41629 20963 41629 20311 41629 20965 41630 20311 41630 20391 41630 20415 41631 20414 41631 20951 41631 20951 41632 20414 41632 20413 41632 20413 41633 20412 41633 20951 41633 20951 41634 20412 41634 20966 41634 20951 41635 20966 41635 20311 41635 20311 41636 20966 41636 20411 41636 20311 41637 20411 41637 20391 41637 24945 41638 20967 41638 24944 41638 24944 41639 20967 41639 20968 41639 24944 41640 20968 41640 20969 41640 20968 41641 20970 41641 20969 41641 20969 41642 20970 41642 28705 41642 20969 41643 28705 41643 24941 41643 24941 41644 28705 41644 28693 41644 24941 41645 28693 41645 20971 41645 20971 41646 28693 41646 28694 41646 20971 41647 28694 41647 24950 41647 24950 41648 28694 41648 20972 41648 24950 41649 20972 41649 20973 41649 20973 41650 20972 41650 28651 41650 20973 41651 28651 41651 24948 41651 28651 41652 28496 41652 24948 41652 24948 41653 28496 41653 28708 41653 24948 41654 28708 41654 20974 41654 20974 41655 28708 41655 20975 41655 20974 41656 20975 41656 24955 41656 24955 41657 20975 41657 28667 41657 24955 41658 28667 41658 20976 41658 20976 41659 28667 41659 20977 41659 20976 41660 20977 41660 24954 41660 24954 41661 20977 41661 28493 41661 24954 41662 28493 41662 24952 41662 28493 41663 28610 41663 24952 41663 24952 41664 28610 41664 28696 41664 24952 41665 28696 41665 24959 41665 24959 41666 28696 41666 20978 41666 24959 41667 20978 41667 20979 41667 20979 41668 20978 41668 28492 41668 20979 41669 28492 41669 20980 41669 20980 41670 28492 41670 28682 41670 20980 41671 28682 41671 24964 41671 24964 41672 28682 41672 28683 41672 24964 41673 28683 41673 24963 41673 24963 41674 28683 41674 20981 41674 24963 41675 20981 41675 20982 41675 20981 41676 28623 41676 20982 41676 20982 41677 28623 41677 20983 41677 20982 41678 20983 41678 20984 41678 20984 41679 20983 41679 28697 41679 20984 41680 28697 41680 20985 41680 20985 41681 28697 41681 28698 41681 20985 41682 28698 41682 20986 41682 20986 41683 28698 41683 28699 41683 20986 41684 28699 41684 20987 41684 20987 41685 28699 41685 28494 41685 20987 41686 28494 41686 20988 41686 20988 41687 28494 41687 28495 41687 20988 41688 28495 41688 24946 41688 24946 41689 28495 41689 28632 41689 24946 41690 28632 41690 24945 41690 24945 41691 28632 41691 28498 41691 24945 41692 28498 41692 20967 41692 27510 41693 20993 41693 20989 41693 27510 41694 20991 41694 20992 41694 20990 41695 20991 41695 27510 41695 20989 41696 20990 41696 27510 41696 27510 41697 20997 41697 20998 41697 20995 41698 20997 41698 27510 41698 20992 41699 20995 41699 27510 41699 20993 41700 27509 41700 20989 41700 20989 41701 27509 41701 27494 41701 20989 41702 27494 41702 20990 41702 20990 41703 27494 41703 27492 41703 20990 41704 27492 41704 20991 41704 20991 41705 27492 41705 20994 41705 20991 41706 20994 41706 20992 41706 20992 41707 20994 41707 27490 41707 20992 41708 27490 41708 20995 41708 20995 41709 27490 41709 20996 41709 20995 41710 20996 41710 20997 41710 20997 41711 20996 41711 27501 41711 20997 41712 27501 41712 20998 41712 20998 41713 27501 41713 27500 41713 21000 41714 20999 41714 27483 41714 21000 41715 27483 41715 21008 41715 21008 41716 27483 41716 21002 41716 21008 41717 21002 41717 21009 41717 21009 41718 21002 41718 21001 41718 21001 41719 21002 41719 21003 41719 21001 41720 21003 41720 21004 41720 21004 41721 21003 41721 21012 41721 21012 41722 21003 41722 27481 41722 21012 41723 27481 41723 21013 41723 21013 41724 27481 41724 21005 41724 21005 41725 27481 41725 27489 41725 21005 41726 27489 41726 21006 41726 21006 41727 27489 41727 27488 41727 21006 41728 27488 41728 21011 41728 21011 41729 27488 41729 27471 41729 21011 41730 27471 41730 21007 41730 21010 41731 21000 41731 21008 41731 21009 41732 21001 41732 21010 41732 21004 41733 21012 41733 21010 41733 21013 41734 21005 41734 21010 41734 21010 41735 21011 41735 21007 41735 21006 41736 21011 41736 21010 41736 21005 41737 21006 41737 21010 41737 21012 41738 21013 41738 21010 41738 21001 41739 21004 41739 21010 41739 21008 41740 21009 41740 21010 41740 21016 41741 21014 41741 21015 41741 21016 41742 21015 41742 21017 41742 21017 41743 21015 41743 27457 41743 21017 41744 27457 41744 21018 41744 21018 41745 27457 41745 21022 41745 21022 41746 27457 41746 27454 41746 21022 41747 27454 41747 21023 41747 21023 41748 27454 41748 21024 41748 21024 41749 27454 41749 21019 41749 21024 41750 21019 41750 21020 41750 21020 41751 21019 41751 21025 41751 21025 41752 21019 41752 27453 41752 21025 41753 27453 41753 21026 41753 21026 41754 27453 41754 27462 41754 21026 41755 27462 41755 21021 41755 21021 41756 27462 41756 27446 41756 21021 41757 27446 41757 27445 41757 21027 41758 21016 41758 21017 41758 21018 41759 21022 41759 21027 41759 21023 41760 21024 41760 21027 41760 21020 41761 21025 41761 21027 41761 21027 41762 21021 41762 27445 41762 21026 41763 21021 41763 21027 41763 21025 41764 21026 41764 21027 41764 21024 41765 21020 41765 21027 41765 21022 41766 21023 41766 21027 41766 21017 41767 21018 41767 21027 41767 27424 41768 27423 41768 21028 41768 21028 41769 27423 41769 27426 41769 21028 41770 27426 41770 21029 41770 21029 41771 27426 41771 27425 41771 21029 41772 27425 41772 21032 41772 21032 41773 27425 41773 27431 41773 21032 41774 27431 41774 21030 41774 21030 41775 27431 41775 27432 41775 21030 41776 27432 41776 21031 41776 21031 41777 27432 41777 27433 41777 21031 41778 27433 41778 27412 41778 27412 41779 27433 41779 27434 41779 27408 41780 21029 41780 21032 41780 21028 41781 21029 41781 27408 41781 27424 41782 21028 41782 27408 41782 27408 41783 21031 41783 27412 41783 21030 41784 21031 41784 27408 41784 21032 41785 21030 41785 27408 41785 27390 41786 27391 41786 21037 41786 21037 41787 27391 41787 27395 41787 21037 41788 27395 41788 21033 41788 21033 41789 27395 41789 27394 41789 21033 41790 27394 41790 21034 41790 21034 41791 27394 41791 21035 41791 21034 41792 21035 41792 21036 41792 21036 41793 21035 41793 27392 41793 21036 41794 27392 41794 21039 41794 21039 41795 27392 41795 27407 41795 21039 41796 27407 41796 21038 41796 21038 41797 27407 41797 27406 41797 21038 41798 27406 41798 27385 41798 27385 41799 27406 41799 27404 41799 27384 41800 27390 41800 21037 41800 27384 41801 21034 41801 21036 41801 21033 41802 21034 41802 27384 41802 21037 41803 21033 41803 27384 41803 27384 41804 21038 41804 27385 41804 21039 41805 21038 41805 27384 41805 21036 41806 21039 41806 27384 41806 27368 41807 27373 41807 27371 41807 27368 41808 27371 41808 21041 41808 21041 41809 27371 41809 21040 41809 21041 41810 21040 41810 21050 41810 21050 41811 21040 41811 21042 41811 21042 41812 21040 41812 21044 41812 21042 41813 21044 41813 21043 41813 21043 41814 21044 41814 21051 41814 21051 41815 21044 41815 21045 41815 21051 41816 21045 41816 21053 41816 21053 41817 21045 41817 21052 41817 21052 41818 21045 41818 27381 41818 21052 41819 27381 41819 21046 41819 21046 41820 27381 41820 27380 41820 21046 41821 27380 41821 21048 41821 21048 41822 27380 41822 21047 41822 21048 41823 21047 41823 21049 41823 21054 41824 27368 41824 21041 41824 21050 41825 21042 41825 21054 41825 21043 41826 21051 41826 21054 41826 21053 41827 21052 41827 21054 41827 21054 41828 21048 41828 21049 41828 21046 41829 21048 41829 21054 41829 21052 41830 21046 41830 21054 41830 21051 41831 21053 41831 21054 41831 21042 41832 21043 41832 21054 41832 21041 41833 21050 41833 21054 41833 21055 41834 21057 41834 21056 41834 21056 41835 21057 41835 21058 41835 21056 41836 21058 41836 21059 41836 21059 41837 21058 41837 27346 41837 21059 41838 27346 41838 21060 41838 21060 41839 27346 41839 27345 41839 21060 41840 27345 41840 21061 41840 21061 41841 27345 41841 21062 41841 21061 41842 21062 41842 21063 41842 21063 41843 21062 41843 21064 41843 21063 41844 21064 41844 21065 41844 21065 41845 21064 41845 21067 41845 21065 41846 21067 41846 21066 41846 21066 41847 21067 41847 27352 41847 21068 41848 21055 41848 21056 41848 21068 41849 21060 41849 21061 41849 21059 41850 21060 41850 21068 41850 21056 41851 21059 41851 21068 41851 21068 41852 21065 41852 21066 41852 21063 41853 21065 41853 21068 41853 21061 41854 21063 41854 21068 41854 27324 41855 27333 41855 21069 41855 21069 41856 27333 41856 21070 41856 21069 41857 21070 41857 21077 41857 21077 41858 21070 41858 21078 41858 21078 41859 21070 41859 21071 41859 21078 41860 21071 41860 21072 41860 21072 41861 21071 41861 21073 41861 21073 41862 21071 41862 27336 41862 21073 41863 27336 41863 21074 41863 21074 41864 27336 41864 21075 41864 21075 41865 27336 41865 27326 41865 21075 41866 27326 41866 21082 41866 21082 41867 27326 41867 21076 41867 21076 41868 27326 41868 27328 41868 21076 41869 27328 41869 21080 41869 21080 41870 27328 41870 21081 41870 21081 41871 27328 41871 27319 41871 21081 41872 27319 41872 27318 41872 21079 41873 27324 41873 21069 41873 21077 41874 21078 41874 21079 41874 21072 41875 21073 41875 21079 41875 21074 41876 21075 41876 21079 41876 21082 41877 21076 41877 21079 41877 21079 41878 21081 41878 27318 41878 21080 41879 21081 41879 21079 41879 21076 41880 21080 41880 21079 41880 21075 41881 21082 41881 21079 41881 21073 41882 21074 41882 21079 41882 21078 41883 21072 41883 21079 41883 21069 41884 21077 41884 21079 41884 21093 41885 21083 41885 21084 41885 21093 41886 21084 41886 21085 41886 21085 41887 21084 41887 27308 41887 21085 41888 27308 41888 21086 41888 21086 41889 27308 41889 21094 41889 21094 41890 27308 41890 27314 41890 21094 41891 27314 41891 21087 41891 21087 41892 27314 41892 21088 41892 21088 41893 27314 41893 21089 41893 21088 41894 21089 41894 21095 41894 21095 41895 21089 41895 21090 41895 21090 41896 21089 41896 21091 41896 21090 41897 21091 41897 21097 41897 21097 41898 21091 41898 21092 41898 21097 41899 21092 41899 21096 41899 21096 41900 21092 41900 27312 41900 21096 41901 27312 41901 27290 41901 21098 41902 21093 41902 21085 41902 21086 41903 21094 41903 21098 41903 21087 41904 21088 41904 21098 41904 21095 41905 21090 41905 21098 41905 21098 41906 21096 41906 27290 41906 21097 41907 21096 41907 21098 41907 21090 41908 21097 41908 21098 41908 21088 41909 21095 41909 21098 41909 21094 41910 21087 41910 21098 41910 21085 41911 21086 41911 21098 41911 27260 41912 21099 41912 27279 41912 27260 41913 27279 41913 21111 41913 21111 41914 27279 41914 27278 41914 21111 41915 27278 41915 21104 41915 21104 41916 27278 41916 21105 41916 21105 41917 27278 41917 27277 41917 21105 41918 27277 41918 21100 41918 21100 41919 27277 41919 21106 41919 21106 41920 27277 41920 21101 41920 21106 41921 21101 41921 21107 41921 21107 41922 21101 41922 21110 41922 21110 41923 21101 41923 27275 41923 21110 41924 27275 41924 21102 41924 21102 41925 27275 41925 27287 41925 21102 41926 27287 41926 21103 41926 21103 41927 27287 41927 27285 41927 21103 41928 27285 41928 21109 41928 21108 41929 27260 41929 21111 41929 21104 41930 21105 41930 21108 41930 21100 41931 21106 41931 21108 41931 21107 41932 21110 41932 21108 41932 21108 41933 21103 41933 21109 41933 21102 41934 21103 41934 21108 41934 21110 41935 21102 41935 21108 41935 21106 41936 21107 41936 21108 41936 21105 41937 21100 41937 21108 41937 21111 41938 21104 41938 21108 41938 25014 41939 25008 41939 21115 41939 25018 41940 21112 41940 21114 41940 21114 41941 21112 41941 25015 41941 21114 41942 25015 41942 21113 41942 25014 41943 21115 41943 21113 41943 21113 41944 21115 41944 21128 41944 21113 41945 21128 41945 21114 41945 21114 41946 21128 41946 25020 41946 21114 41947 25020 41947 25018 41947 25008 41948 25007 41948 21115 41948 21115 41949 25007 41949 25012 41949 21115 41950 25012 41950 26603 41950 22087 41951 21445 41951 21116 41951 21116 41952 21445 41952 26603 41952 21116 41953 26603 41953 25010 41953 25010 41954 26603 41954 25012 41954 25386 41955 21232 41955 21117 41955 21117 41956 21232 41956 25406 41956 25406 41957 25395 41957 21117 41957 21117 41958 25395 41958 25393 41958 21117 41959 25393 41959 25386 41959 25386 41960 25393 41960 25394 41960 25385 41961 21118 41961 21119 41961 21119 41962 21118 41962 25375 41962 25375 41963 25376 41963 21119 41963 21119 41964 25376 41964 25377 41964 21119 41965 25377 41965 21120 41965 21120 41966 25378 41966 21119 41966 21119 41967 25378 41967 21121 41967 21119 41968 21121 41968 21122 41968 21123 41969 21115 41969 25381 41969 25381 41970 21115 41970 21122 41970 25381 41971 21122 41971 25380 41971 25380 41972 21122 41972 21121 41972 21123 41973 25382 41973 21115 41973 21115 41974 25382 41974 21124 41974 21115 41975 21124 41975 21128 41975 21128 41976 21124 41976 21125 41976 21128 41977 21125 41977 21126 41977 25348 41978 25347 41978 21127 41978 21127 41979 25347 41979 25346 41979 21126 41980 25348 41980 21128 41980 21128 41981 25348 41981 21127 41981 21128 41982 21127 41982 21129 41982 21129 41983 21127 41983 25346 41983 21129 41984 25346 41984 25344 41984 25434 41985 21131 41985 21130 41985 21130 41986 21131 41986 21132 41986 25434 41987 25436 41987 21131 41987 21131 41988 25436 41988 25437 41988 21131 41989 25437 41989 26556 41989 25437 41990 21133 41990 26556 41990 26556 41991 21133 41991 21134 41991 26556 41992 21134 41992 21227 41992 21227 41993 21134 41993 21135 41993 25439 41994 21136 41994 25400 41994 25400 41995 21136 41995 25416 41995 25417 41996 21137 41996 21138 41996 21138 41997 21137 41997 25415 41997 25416 41998 25417 41998 25400 41998 25400 41999 25417 41999 21138 41999 25400 42000 21138 42000 21139 42000 21139 42001 21138 42001 25415 42001 21139 42002 25415 42002 25413 42002 21226 42003 25447 42003 21140 42003 25447 42004 21226 42004 25452 42004 21141 42005 21142 42005 21225 42005 21224 42006 21144 42006 21143 42006 21143 42007 21144 42007 25430 42007 21143 42008 25430 42008 21145 42008 21145 42009 25430 42009 21146 42009 21145 42010 21146 42010 21131 42010 21131 42011 21146 42011 25431 42011 21131 42012 25431 42012 21132 42012 25501 42013 21221 42013 25500 42013 25500 42014 21221 42014 26554 42014 25500 42015 26554 42015 21147 42015 21147 42016 26554 42016 21161 42016 21147 42017 21161 42017 25497 42017 25505 42018 25506 42018 21223 42018 21223 42019 25506 42019 21150 42019 21148 42020 25466 42020 21149 42020 21149 42021 25466 42021 25464 42021 21150 42022 21148 42022 21223 42022 21223 42023 21148 42023 21149 42023 21223 42024 21149 42024 25462 42024 25462 42025 21149 42025 25464 42025 25462 42026 25464 42026 25463 42026 21151 42027 21153 42027 21152 42027 21153 42028 21151 42028 21154 42028 21156 42029 25515 42029 25509 42029 21158 42030 21220 42030 21155 42030 21155 42031 21220 42031 21154 42031 21155 42032 21154 42032 25509 42032 25509 42033 21154 42033 21151 42033 25509 42034 21151 42034 21156 42034 21156 42035 21151 42035 21152 42035 25493 42036 21160 42036 21157 42036 21157 42037 21160 42037 21220 42037 21157 42038 21220 42038 25491 42038 25491 42039 21220 42039 21158 42039 25493 42040 21159 42040 21160 42040 21160 42041 21159 42041 25495 42041 21160 42042 25495 42042 21161 42042 21161 42043 25495 42043 21162 42043 21161 42044 21162 42044 25497 42044 21217 42045 21163 42045 21216 42045 25576 42046 25574 42046 21218 42046 21218 42047 25574 42047 25538 42047 21164 42048 25535 42048 21165 42048 21165 42049 25535 42049 21166 42049 25538 42050 21164 42050 21218 42050 21218 42051 21164 42051 21165 42051 21218 42052 21165 42052 25531 42052 25531 42053 21165 42053 21166 42053 25531 42054 21166 42054 25533 42054 25587 42055 25592 42055 21167 42055 21167 42056 25592 42056 25591 42056 25591 42057 25590 42057 21167 42057 21167 42058 25590 42058 25584 42058 21167 42059 25584 42059 25587 42059 25587 42060 25584 42060 25586 42060 21215 42061 25559 42061 21168 42061 21168 42062 25559 42062 25561 42062 25561 42063 25562 42063 21168 42063 21168 42064 25562 42064 25570 42064 21168 42065 25570 42065 26548 42065 26548 42066 25570 42066 25569 42066 26548 42067 25569 42067 25567 42067 25567 42068 25564 42068 26548 42068 26548 42069 25564 42069 21169 42069 26548 42070 21169 42070 21170 42070 21170 42071 21169 42071 25563 42071 25563 42072 21171 42072 21170 42072 21170 42073 21171 42073 21172 42073 21170 42074 21172 42074 21163 42074 21163 42075 21172 42075 25572 42075 21163 42076 25572 42076 21216 42076 25594 42077 21174 42077 25595 42077 25595 42078 21174 42078 25581 42078 25595 42079 25581 42079 25580 42079 25541 42080 21173 42080 21213 42080 21213 42081 21173 42081 25577 42081 21213 42082 25577 42082 25594 42082 25594 42083 25577 42083 21175 42083 25594 42084 21175 42084 21174 42084 21174 42085 21175 42085 21176 42085 21174 42086 21176 42086 25581 42086 21180 42087 25522 42087 21177 42087 21177 42088 25522 42088 21178 42088 21178 42089 21179 42089 21177 42089 21177 42090 21179 42090 25526 42090 21177 42091 25526 42091 21180 42091 21180 42092 25526 42092 25527 42092 25537 42093 25557 42093 26543 42093 26543 42094 25557 42094 21181 42094 21181 42095 21182 42095 26543 42095 26543 42096 21182 42096 25555 42096 26543 42097 25555 42097 21183 42097 21183 42098 25555 42098 25553 42098 21183 42099 25553 42099 21184 42099 25547 42100 25545 42100 21185 42100 21185 42101 25545 42101 21186 42101 21185 42102 21186 42102 26545 42102 26545 42103 21186 42103 25542 42103 26545 42104 25542 42104 26547 42104 21184 42105 25550 42105 21183 42105 21183 42106 25550 42106 21187 42106 21183 42107 21187 42107 21185 42107 21185 42108 21187 42108 21188 42108 21185 42109 21188 42109 25547 42109 25476 42110 25468 42110 21197 42110 25476 42111 21197 42111 25475 42111 21191 42112 25460 42112 21189 42112 25460 42113 21191 42113 27016 42113 25455 42114 21190 42114 25458 42114 21189 42115 25455 42115 21191 42115 21191 42116 25455 42116 25458 42116 21191 42117 25458 42117 27016 42117 27016 42118 25458 42118 25488 42118 27016 42119 25488 42119 21194 42119 21194 42120 25488 42120 25485 42120 21194 42121 25485 42121 25484 42121 25484 42122 21192 42122 21194 42122 21194 42123 21192 42123 21193 42123 21194 42124 21193 42124 25481 42124 25471 42125 21196 42125 21195 42125 21195 42126 21196 42126 21194 42126 21195 42127 21194 42127 25479 42127 25479 42128 21194 42128 25481 42128 25471 42129 25472 42129 21196 42129 21196 42130 25472 42130 25473 42130 21196 42131 25473 42131 21197 42131 21197 42132 25473 42132 25474 42132 21197 42133 25474 42133 25475 42133 21198 42134 25508 42134 21200 42134 21201 42135 21199 42135 21202 42135 21202 42136 21199 42136 21203 42136 25508 42137 21201 42137 21200 42137 21200 42138 21201 42138 21202 42138 21200 42139 21202 42139 25518 42139 25518 42140 21202 42140 21203 42140 25518 42141 21203 42141 25510 42141 27022 42142 21205 42142 21204 42142 21204 42143 21205 42143 24971 42143 21204 42144 24971 42144 21194 42144 24971 42145 21206 42145 21194 42145 21194 42146 21206 42146 24974 42146 21194 42147 24974 42147 24975 42147 27016 42148 21207 42148 27017 42148 27017 42149 21207 42149 21210 42149 27017 42150 21210 42150 21208 42150 24975 42151 24977 42151 21194 42151 21194 42152 24977 42152 21209 42152 21194 42153 21209 42153 27016 42153 27016 42154 21209 42154 24970 42154 27016 42155 24970 42155 21207 42155 21207 42156 24970 42156 24966 42156 21207 42157 24966 42157 21210 42157 25468 42158 21198 42158 21197 42158 21197 42159 21198 42159 21200 42159 21197 42160 21200 42160 26539 42160 26539 42161 21200 42161 21211 42161 26539 42162 21211 42162 26540 42162 26540 42163 21211 42163 25519 42163 26540 42164 25519 42164 26541 42164 26541 42165 25519 42165 21212 42165 26541 42166 21212 42166 26543 42166 26543 42167 21212 42167 25522 42167 26543 42168 25522 42168 25537 42168 25537 42169 25522 42169 21180 42169 25542 42170 25541 42170 26547 42170 26547 42171 25541 42171 21213 42171 26547 42172 21213 42172 21214 42172 21214 42173 21213 42173 25593 42173 21214 42174 25593 42174 21168 42174 21168 42175 25593 42175 25592 42175 21168 42176 25592 42176 21215 42176 21215 42177 25592 42177 25587 42177 21216 42178 25576 42178 21217 42178 21217 42179 25576 42179 21218 42179 21217 42180 21218 42180 26552 42180 26552 42181 21218 42181 21219 42181 26552 42182 21219 42182 21220 42182 21220 42183 21219 42183 25525 42183 21220 42184 25525 42184 21154 42184 25501 42185 25505 42185 21221 42185 21221 42186 25505 42186 21223 42186 21221 42187 21223 42187 21222 42187 21222 42188 21223 42188 25448 42188 21222 42189 25448 42189 21143 42189 21143 42190 25448 42190 25450 42190 21143 42191 25450 42191 21224 42191 21224 42192 25450 42192 25452 42192 21224 42193 25452 42193 21225 42193 21225 42194 25452 42194 21226 42194 21225 42195 21226 42195 21141 42195 21141 42196 21226 42196 21140 42196 21135 42197 25439 42197 21227 42197 21227 42198 25439 42198 25400 42198 21227 42199 25400 42199 21228 42199 21228 42200 25400 42200 25403 42200 21228 42201 25403 42201 21229 42201 21229 42202 25403 42202 21230 42202 21229 42203 21230 42203 21231 42203 21231 42204 21230 42204 25405 42204 21231 42205 25405 42205 21119 42205 21119 42206 25405 42206 21232 42206 21119 42207 21232 42207 25385 42207 25385 42208 21232 42208 25386 42208 26763 42209 21233 42209 26765 42209 26765 42210 21233 42210 21787 42210 26765 42211 21787 42211 21234 42211 21234 42212 21787 42212 21789 42212 21234 42213 21789 42213 21235 42213 21235 42214 21789 42214 21236 42214 21235 42215 21236 42215 21237 42215 21237 42216 21236 42216 21792 42216 21237 42217 21792 42217 21238 42217 21238 42218 21792 42218 21239 42218 21238 42219 21239 42219 21240 42219 21240 42220 21239 42220 21795 42220 21240 42221 21795 42221 26768 42221 26768 42222 21795 42222 21796 42222 26768 42223 21796 42223 26769 42223 26769 42224 21796 42224 21242 42224 26769 42225 21242 42225 21241 42225 21241 42226 21242 42226 21243 42226 21241 42227 21243 42227 26771 42227 26771 42228 21243 42228 21798 42228 26771 42229 21798 42229 26772 42229 26772 42230 21798 42230 21799 42230 26772 42231 21799 42231 26773 42231 26773 42232 21799 42232 21801 42232 26773 42233 21801 42233 26774 42233 26774 42234 21801 42234 21244 42234 26774 42235 21244 42235 21245 42235 21245 42236 21244 42236 21246 42236 21245 42237 21246 42237 21248 42237 21248 42238 21246 42238 21247 42238 21248 42239 21247 42239 21250 42239 21250 42240 21247 42240 21249 42240 21250 42241 21249 42241 26775 42241 26775 42242 21249 42242 26112 42242 26949 42243 21252 42243 21251 42243 21251 42244 21252 42244 21948 42244 21251 42245 21948 42245 21786 42245 21786 42246 21948 42246 21949 42246 21786 42247 21949 42247 21253 42247 21253 42248 21949 42248 21254 42248 21253 42249 21254 42249 21255 42249 21255 42250 21254 42250 21256 42250 21255 42251 21256 42251 21784 42251 21784 42252 21256 42252 21258 42252 21784 42253 21258 42253 21257 42253 21257 42254 21258 42254 21259 42254 21257 42255 21259 42255 21260 42255 21260 42256 21259 42256 21955 42256 21260 42257 21955 42257 21782 42257 21782 42258 21955 42258 21956 42258 21782 42259 21956 42259 21261 42259 21261 42260 21956 42260 21957 42260 21261 42261 21957 42261 21781 42261 21781 42262 21957 42262 21958 42262 21781 42263 21958 42263 21262 42263 21262 42264 21958 42264 21961 42264 21262 42265 21961 42265 21779 42265 21779 42266 21961 42266 21963 42266 21779 42267 21963 42267 21264 42267 21264 42268 21963 42268 21263 42268 21264 42269 21263 42269 21265 42269 21265 42270 21263 42270 21965 42270 21265 42271 21965 42271 21266 42271 21266 42272 21965 42272 21966 42272 21266 42273 21966 42273 21775 42273 21775 42274 21966 42274 21967 42274 21775 42275 21967 42275 26136 42275 26136 42276 21967 42276 26925 42276 22019 42277 21267 42277 21268 42277 21268 42278 21267 42278 22020 42278 21268 42279 22020 42279 21269 42279 21269 42280 22020 42280 22021 42280 21269 42281 22021 42281 21271 42281 21271 42282 22021 42282 21270 42282 21271 42283 21270 42283 22016 42283 22016 42284 21270 42284 21272 42284 22016 42285 21272 42285 21273 42285 21273 42286 21272 42286 22024 42286 21273 42287 22024 42287 22013 42287 22013 42288 22024 42288 21274 42288 22013 42289 21274 42289 22011 42289 22011 42290 21274 42290 21275 42290 22011 42291 21275 42291 22010 42291 22010 42292 21275 42292 22027 42292 22010 42293 22027 42293 21276 42293 21276 42294 22027 42294 21277 42294 21276 42295 21277 42295 21278 42295 21278 42296 21277 42296 21279 42296 21278 42297 21279 42297 21280 42297 21280 42298 21279 42298 21281 42298 21280 42299 21281 42299 21282 42299 21282 42300 21281 42300 21283 42300 21282 42301 21283 42301 21284 42301 21284 42302 21283 42302 22028 42302 21284 42303 22028 42303 21285 42303 21285 42304 22028 42304 22030 42304 21285 42305 22030 42305 21286 42305 21286 42306 22030 42306 22031 42306 21286 42307 22031 42307 25140 42307 25140 42308 22031 42308 22032 42308 21288 42309 21287 42309 25143 42309 21288 42310 25143 42310 21289 42310 21289 42311 25143 42311 22004 42311 21289 42312 22004 42312 26601 42312 21294 42313 21296 42313 26600 42313 21294 42314 26600 42314 22004 42314 22004 42315 26600 42315 21290 42315 22004 42316 21290 42316 26601 42316 21291 42317 21292 42317 21293 42317 21291 42318 21293 42318 21294 42318 21294 42319 21293 42319 21295 42319 21294 42320 21295 42320 21296 42320 26532 42321 21297 42321 22002 42321 22002 42322 21297 42322 21298 42322 22002 42323 21298 42323 21291 42323 21291 42324 21298 42324 21299 42324 21291 42325 21299 42325 21292 42325 26532 42326 22002 42326 26531 42326 26531 42327 22002 42327 22000 42327 26531 42328 22000 42328 21302 42328 21999 42329 21300 42329 21301 42329 21999 42330 21301 42330 22000 42330 22000 42331 21301 42331 26529 42331 22000 42332 26529 42332 21302 42332 21303 42333 21306 42333 26524 42333 21303 42334 26524 42334 21999 42334 21999 42335 26524 42335 26526 42335 21999 42336 26526 42336 21300 42336 26520 42337 26521 42337 21304 42337 21304 42338 26521 42338 21305 42338 21304 42339 21305 42339 21303 42339 21303 42340 21305 42340 26523 42340 21303 42341 26523 42341 21306 42341 26520 42342 21304 42342 21307 42342 21307 42343 21304 42343 21309 42343 21307 42344 21309 42344 26517 42344 21308 42345 26513 42345 26514 42345 21308 42346 26514 42346 21309 42346 21309 42347 26514 42347 26515 42347 21309 42348 26515 42348 26517 42348 21312 42349 21310 42349 21997 42349 21997 42350 21310 42350 21311 42350 21997 42351 21311 42351 21308 42351 21308 42352 21311 42352 26511 42352 21308 42353 26511 42353 26513 42353 21312 42354 21997 42354 21313 42354 21313 42355 21997 42355 21316 42355 21313 42356 21316 42356 26508 42356 21317 42357 26507 42357 21314 42357 21317 42358 21314 42358 21316 42358 21316 42359 21314 42359 21315 42359 21316 42360 21315 42360 26508 42360 21993 42361 26502 42361 26505 42361 21993 42362 26505 42362 21317 42362 21317 42363 26505 42363 26506 42363 21317 42364 26506 42364 26507 42364 21318 42365 26500 42365 26501 42365 21318 42366 26501 42366 21993 42366 21993 42367 26501 42367 21319 42367 21993 42368 21319 42368 26502 42368 26496 42369 26498 42369 21320 42369 21320 42370 26498 42370 21321 42370 21320 42371 21321 42371 21318 42371 21318 42372 21321 42372 26499 42372 21318 42373 26499 42373 26500 42373 26496 42374 21320 42374 26494 42374 26494 42375 21320 42375 21322 42375 26494 42376 21322 42376 21325 42376 26866 42377 26867 42377 21323 42377 26866 42378 21323 42378 21322 42378 21322 42379 21323 42379 21324 42379 21322 42380 21324 42380 21325 42380 26805 42381 21327 42381 21326 42381 21326 42382 21327 42382 21329 42382 21326 42383 21329 42383 21328 42383 21328 42384 21329 42384 21970 42384 21328 42385 21970 42385 21330 42385 21330 42386 21970 42386 21971 42386 21330 42387 21971 42387 21331 42387 21331 42388 21971 42388 21972 42388 21331 42389 21972 42389 26807 42389 26807 42390 21972 42390 21975 42390 26807 42391 21975 42391 26780 42391 26780 42392 21975 42392 21332 42392 26780 42393 21332 42393 26781 42393 26781 42394 21332 42394 21333 42394 26781 42395 21333 42395 21334 42395 21334 42396 21333 42396 21335 42396 21334 42397 21335 42397 21336 42397 21336 42398 21335 42398 21978 42398 21336 42399 21978 42399 26784 42399 26784 42400 21978 42400 21337 42400 26784 42401 21337 42401 21338 42401 21338 42402 21337 42402 21339 42402 21338 42403 21339 42403 21340 42403 21340 42404 21339 42404 21341 42404 21340 42405 21341 42405 26785 42405 26785 42406 21341 42406 21982 42406 26785 42407 21982 42407 26786 42407 26786 42408 21982 42408 21983 42408 26786 42409 21983 42409 21342 42409 21342 42410 21983 42410 21984 42410 21342 42411 21984 42411 26789 42411 26789 42412 21984 42412 21988 42412 26789 42413 21988 42413 26791 42413 26791 42414 21988 42414 21989 42414 26791 42415 21989 42415 21343 42415 21343 42416 21989 42416 26808 42416 26757 42417 22072 42417 22070 42417 26757 42418 22070 42418 21344 42418 21344 42419 22070 42419 21345 42419 21344 42420 21345 42420 21346 42420 21346 42421 21345 42421 22068 42421 21346 42422 22068 42422 26760 42422 26760 42423 22068 42423 21347 42423 26760 42424 21347 42424 21348 42424 21348 42425 21347 42425 21349 42425 21348 42426 21349 42426 26759 42426 26759 42427 21349 42427 22065 42427 26759 42428 22065 42428 21350 42428 21350 42429 22065 42429 22064 42429 21350 42430 22064 42430 21351 42430 21351 42431 22064 42431 22063 42431 21351 42432 22063 42432 21352 42432 21352 42433 22063 42433 21353 42433 21352 42434 21353 42434 21354 42434 21354 42435 21353 42435 22061 42435 21354 42436 22061 42436 21355 42436 21355 42437 22061 42437 22060 42437 21355 42438 22060 42438 21356 42438 21356 42439 22060 42439 22058 42439 21356 42440 22058 42440 21357 42440 21357 42441 22058 42441 21358 42441 21357 42442 21358 42442 21359 42442 21359 42443 21358 42443 21360 42443 21359 42444 21360 42444 21361 42444 21361 42445 21360 42445 22053 42445 21361 42446 22053 42446 21362 42446 21362 42447 22053 42447 21363 42447 21362 42448 21363 42448 26776 42448 26776 42449 21363 42449 22052 42449 26776 42450 22052 42450 21364 42450 26704 42451 25185 42451 21947 42451 26704 42452 21947 42452 21365 42452 21365 42453 21947 42453 21366 42453 21365 42454 21366 42454 26730 42454 26730 42455 21366 42455 21367 42455 26730 42456 21367 42456 21368 42456 21368 42457 21367 42457 21369 42457 21368 42458 21369 42458 21370 42458 21370 42459 21369 42459 21943 42459 21370 42460 21943 42460 26727 42460 26727 42461 21943 42461 21942 42461 26727 42462 21942 42462 26726 42462 26726 42463 21942 42463 21371 42463 26726 42464 21371 42464 26724 42464 26724 42465 21371 42465 21373 42465 26724 42466 21373 42466 21372 42466 21372 42467 21373 42467 21375 42467 21372 42468 21375 42468 21374 42468 21374 42469 21375 42469 21938 42469 21374 42470 21938 42470 26721 42470 26721 42471 21938 42471 21376 42471 26721 42472 21376 42472 26720 42472 26720 42473 21376 42473 21378 42473 26720 42474 21378 42474 21377 42474 21377 42475 21378 42475 21934 42475 21377 42476 21934 42476 21379 42476 21379 42477 21934 42477 21380 42477 21379 42478 21380 42478 26718 42478 26718 42479 21380 42479 21932 42479 26718 42480 21932 42480 26717 42480 26717 42481 21932 42481 26684 42481 26717 42482 26684 42482 26683 42482 26617 42483 25109 42483 21381 42483 21381 42484 25109 42484 22034 42484 21381 42485 22034 42485 21383 42485 21383 42486 22034 42486 21382 42486 21383 42487 21382 42487 21384 42487 21384 42488 21382 42488 21385 42488 21384 42489 21385 42489 26620 42489 26620 42490 21385 42490 22039 42490 26620 42491 22039 42491 26621 42491 26621 42492 22039 42492 21387 42492 26621 42493 21387 42493 21386 42493 21386 42494 21387 42494 22040 42494 21386 42495 22040 42495 21388 42495 21388 42496 22040 42496 22042 42496 21388 42497 22042 42497 26624 42497 26624 42498 22042 42498 21390 42498 26624 42499 21390 42499 21389 42499 21389 42500 21390 42500 21391 42500 21389 42501 21391 42501 21392 42501 21392 42502 21391 42502 22044 42502 21392 42503 22044 42503 21393 42503 21393 42504 22044 42504 22045 42504 21393 42505 22045 42505 21394 42505 21394 42506 22045 42506 22046 42506 21394 42507 22046 42507 21395 42507 21395 42508 22046 42508 22049 42508 21395 42509 22049 42509 21396 42509 21396 42510 22049 42510 21397 42510 21396 42511 21397 42511 26630 42511 26630 42512 21397 42512 22051 42512 26630 42513 22051 42513 26631 42513 26631 42514 22051 42514 25094 42514 21287 42515 21398 42515 21399 42515 21399 42516 21398 42516 21400 42516 21399 42517 21400 42517 26904 42517 26904 42518 21400 42518 21481 42518 26904 42519 21481 42519 21401 42519 21401 42520 21481 42520 26902 42520 26902 42521 21481 42521 21402 42521 26902 42522 21402 42522 26903 42522 26903 42523 21402 42523 21403 42523 26903 42524 21403 42524 21404 42524 21404 42525 21403 42525 26900 42525 26900 42526 21403 42526 21485 42526 26900 42527 21485 42527 21405 42527 21405 42528 21485 42528 21406 42528 21405 42529 21406 42529 26896 42529 26896 42530 21406 42530 21407 42530 26896 42531 21407 42531 26898 42531 26898 42532 21407 42532 21408 42532 21408 42533 21407 42533 21488 42533 21408 42534 21488 42534 26895 42534 26895 42535 21488 42535 21410 42535 26895 42536 21410 42536 21409 42536 21409 42537 21410 42537 21411 42537 21411 42538 21410 42538 21413 42538 21411 42539 21413 42539 21412 42539 21412 42540 21413 42540 21491 42540 21412 42541 21491 42541 26891 42541 26891 42542 21491 42542 26893 42542 26893 42543 21491 42543 21492 42543 26893 42544 21492 42544 21415 42544 21415 42545 21492 42545 21414 42545 21415 42546 21414 42546 21416 42546 21416 42547 21414 42547 21417 42547 21417 42548 21414 42548 21494 42548 21417 42549 21494 42549 21418 42549 21418 42550 21494 42550 21419 42550 21418 42551 21419 42551 21420 42551 21420 42552 21419 42552 26889 42552 26889 42553 21419 42553 21422 42553 26889 42554 21422 42554 21421 42554 21421 42555 21422 42555 21423 42555 21421 42556 21423 42556 21424 42556 21424 42557 21423 42557 21425 42557 21425 42558 21423 42558 21497 42558 21425 42559 21497 42559 21426 42559 21426 42560 21497 42560 21427 42560 21426 42561 21427 42561 26887 42561 26887 42562 21427 42562 21428 42562 26887 42563 21428 42563 21430 42563 21430 42564 21428 42564 21429 42564 21430 42565 21429 42565 21431 42565 21431 42566 21429 42566 26883 42566 26883 42567 21429 42567 21432 42567 26883 42568 21432 42568 26885 42568 26885 42569 21432 42569 21433 42569 26885 42570 21433 42570 26886 42570 26886 42571 21433 42571 21434 42571 21434 42572 21433 42572 21499 42572 21434 42573 21499 42573 26878 42573 26878 42574 21499 42574 21500 42574 26878 42575 21500 42575 21435 42575 21435 42576 21500 42576 21502 42576 21435 42577 21502 42577 26879 42577 26879 42578 21502 42578 26881 42578 26881 42579 21502 42579 21503 42579 26881 42580 21503 42580 26876 42580 26876 42581 21503 42581 21437 42581 26876 42582 21437 42582 21436 42582 21436 42583 21437 42583 26877 42583 26877 42584 21437 42584 21504 42584 26877 42585 21504 42585 21438 42585 21438 42586 21504 42586 21440 42586 21438 42587 21440 42587 21439 42587 21439 42588 21440 42588 26873 42588 26873 42589 21440 42589 21507 42589 26873 42590 21507 42590 26870 42590 26870 42591 21507 42591 21441 42591 26870 42592 21441 42592 21442 42592 21442 42593 21441 42593 26872 42593 26872 42594 21441 42594 21444 42594 26872 42595 21444 42595 21443 42595 21443 42596 21444 42596 21508 42596 21443 42597 21508 42597 26868 42597 26604 42598 21445 42598 21482 42598 21482 42599 21445 42599 27117 42599 21482 42600 27117 42600 21483 42600 21483 42601 27117 42601 27108 42601 21483 42602 27108 42602 21484 42602 21484 42603 27108 42603 21447 42603 21484 42604 21447 42604 21446 42604 21446 42605 21447 42605 27124 42605 21446 42606 27124 42606 21486 42606 21486 42607 27124 42607 21448 42607 21486 42608 21448 42608 21487 42608 21487 42609 21448 42609 27127 42609 21487 42610 27127 42610 21449 42610 21449 42611 27127 42611 21450 42611 21449 42612 21450 42612 21489 42612 21489 42613 21450 42613 21451 42613 21489 42614 21451 42614 21490 42614 21490 42615 21451 42615 27100 42615 21490 42616 27100 42616 21452 42616 21452 42617 27100 42617 27102 42617 21452 42618 27102 42618 21454 42618 21454 42619 27102 42619 21453 42619 21454 42620 21453 42620 21493 42620 21493 42621 21453 42621 27131 42621 21493 42622 27131 42622 21455 42622 21455 42623 27131 42623 27132 42623 21455 42624 27132 42624 21456 42624 21456 42625 27132 42625 21457 42625 21456 42626 21457 42626 21458 42626 21458 42627 21457 42627 27081 42627 21458 42628 27081 42628 21495 42628 21495 42629 27081 42629 27085 42629 21495 42630 27085 42630 21496 42630 21496 42631 27085 42631 21459 42631 21496 42632 21459 42632 21460 42632 21460 42633 21459 42633 21461 42633 21460 42634 21461 42634 21463 42634 21463 42635 21461 42635 21462 42635 21463 42636 21462 42636 21464 42636 21464 42637 21462 42637 27062 42637 21464 42638 27062 42638 21498 42638 21498 42639 27062 42639 27066 42639 21498 42640 27066 42640 21465 42640 21465 42641 27066 42641 27069 42641 21465 42642 27069 42642 21466 42642 21466 42643 27069 42643 27055 42643 21466 42644 27055 42644 21467 42644 21467 42645 27055 42645 27137 42645 21467 42646 27137 42646 21501 42646 21501 42647 27137 42647 27140 42647 21501 42648 27140 42648 21468 42648 21468 42649 27140 42649 27050 42649 21468 42650 27050 42650 21469 42650 21469 42651 27050 42651 21470 42651 21469 42652 21470 42652 21505 42652 21505 42653 21470 42653 21471 42653 21505 42654 21471 42654 21506 42654 21506 42655 21471 42655 27043 42655 21506 42656 27043 42656 21472 42656 21472 42657 27043 42657 27143 42657 21472 42658 27143 42658 21473 42658 21473 42659 27143 42659 21474 42659 21473 42660 21474 42660 21475 42660 21475 42661 21474 42661 27145 42661 21475 42662 27145 42662 21476 42662 21476 42663 27145 42663 27146 42663 21476 42664 27146 42664 21477 42664 21477 42665 27146 42665 21478 42665 21477 42666 21478 42666 21479 42666 21479 42667 21478 42667 21480 42667 21479 42668 21480 42668 21512 42668 21512 42669 21480 42669 27032 42669 21398 42670 26604 42670 21400 42670 21400 42671 26604 42671 21482 42671 21400 42672 21482 42672 21481 42672 21481 42673 21482 42673 21483 42673 21481 42674 21483 42674 21402 42674 21402 42675 21483 42675 21484 42675 21402 42676 21484 42676 21403 42676 21403 42677 21484 42677 21446 42677 21403 42678 21446 42678 21485 42678 21485 42679 21446 42679 21486 42679 21485 42680 21486 42680 21406 42680 21406 42681 21486 42681 21487 42681 21406 42682 21487 42682 21407 42682 21407 42683 21487 42683 21449 42683 21407 42684 21449 42684 21488 42684 21488 42685 21449 42685 21489 42685 21488 42686 21489 42686 21410 42686 21410 42687 21489 42687 21490 42687 21410 42688 21490 42688 21413 42688 21413 42689 21490 42689 21452 42689 21413 42690 21452 42690 21491 42690 21491 42691 21452 42691 21454 42691 21491 42692 21454 42692 21492 42692 21492 42693 21454 42693 21493 42693 21492 42694 21493 42694 21414 42694 21414 42695 21493 42695 21455 42695 21414 42696 21455 42696 21494 42696 21494 42697 21455 42697 21456 42697 21494 42698 21456 42698 21419 42698 21419 42699 21456 42699 21458 42699 21419 42700 21458 42700 21422 42700 21422 42701 21458 42701 21495 42701 21422 42702 21495 42702 21423 42702 21423 42703 21495 42703 21496 42703 21423 42704 21496 42704 21497 42704 21497 42705 21496 42705 21460 42705 21497 42706 21460 42706 21427 42706 21427 42707 21460 42707 21463 42707 21427 42708 21463 42708 21428 42708 21428 42709 21463 42709 21464 42709 21428 42710 21464 42710 21429 42710 21429 42711 21464 42711 21498 42711 21429 42712 21498 42712 21432 42712 21432 42713 21498 42713 21465 42713 21432 42714 21465 42714 21433 42714 21433 42715 21465 42715 21466 42715 21433 42716 21466 42716 21499 42716 21499 42717 21466 42717 21467 42717 21499 42718 21467 42718 21500 42718 21500 42719 21467 42719 21501 42719 21500 42720 21501 42720 21502 42720 21502 42721 21501 42721 21468 42721 21502 42722 21468 42722 21503 42722 21503 42723 21468 42723 21469 42723 21503 42724 21469 42724 21437 42724 21437 42725 21469 42725 21505 42725 21437 42726 21505 42726 21504 42726 21504 42727 21505 42727 21506 42727 21504 42728 21506 42728 21440 42728 21440 42729 21506 42729 21472 42729 21440 42730 21472 42730 21507 42730 21507 42731 21472 42731 21473 42731 21507 42732 21473 42732 21441 42732 21441 42733 21473 42733 21475 42733 21441 42734 21475 42734 21444 42734 21444 42735 21475 42735 21476 42735 21444 42736 21476 42736 21508 42736 21508 42737 21476 42737 21477 42737 21508 42738 21477 42738 21509 42738 21509 42739 21477 42739 21479 42739 21509 42740 21479 42740 21513 42740 21513 42741 21479 42741 21512 42741 26868 42742 21508 42742 26869 42742 26869 42743 21508 42743 21509 42743 26869 42744 21509 42744 21510 42744 21510 42745 21509 42745 21513 42745 21510 42746 21513 42746 26865 42746 27032 42747 21515 42747 21511 42747 27032 42748 21511 42748 21512 42748 21512 42749 21511 42749 21516 42749 21512 42750 21516 42750 21513 42750 21513 42751 21516 42751 21518 42751 21513 42752 21518 42752 26865 42752 21515 42753 27022 42753 21514 42753 21515 42754 21514 42754 21511 42754 21511 42755 21514 42755 21517 42755 21511 42756 21517 42756 21516 42756 21516 42757 21517 42757 26867 42757 21516 42758 26867 42758 21518 42758 21538 42759 21553 42759 21739 42759 21519 42760 21762 42760 21520 42760 21520 42761 21762 42761 21718 42761 21520 42762 21718 42762 21522 42762 21522 42763 21718 42763 21521 42763 21522 42764 21521 42764 21592 42764 21592 42765 21521 42765 21523 42765 21592 42766 21523 42766 21524 42766 21524 42767 21523 42767 21525 42767 21524 42768 21525 42768 21526 42768 21526 42769 21525 42769 21527 42769 21526 42770 21527 42770 21528 42770 21528 42771 21527 42771 21529 42771 21546 42772 21749 42772 21531 42772 21531 42773 21749 42773 21530 42773 21531 42774 21530 42774 21532 42774 21532 42775 21530 42775 21756 42775 21532 42776 21756 42776 21582 42776 21582 42777 21756 42777 21533 42777 21582 42778 21533 42778 21583 42778 21583 42779 21533 42779 21535 42779 21583 42780 21535 42780 21534 42780 21534 42781 21535 42781 21755 42781 21534 42782 21755 42782 21584 42782 21584 42783 21755 42783 21753 42783 21584 42784 21753 42784 21585 42784 21585 42785 21753 42785 21708 42785 21585 42786 21708 42786 21587 42786 21587 42787 21708 42787 21536 42787 21587 42788 21536 42788 21588 42788 21588 42789 21536 42789 21764 42789 21588 42790 21764 42790 21519 42790 21519 42791 21764 42791 21537 42791 21519 42792 21537 42792 21762 42792 21538 42793 21739 42793 21539 42793 21739 42794 21699 42794 21539 42794 21539 42795 21699 42795 21540 42795 21539 42796 21540 42796 21577 42796 21577 42797 21540 42797 21541 42797 21577 42798 21541 42798 21542 42798 21542 42799 21541 42799 21543 42799 21542 42800 21543 42800 21578 42800 21578 42801 21543 42801 21544 42801 21578 42802 21544 42802 21546 42802 21546 42803 21544 42803 21545 42803 21546 42804 21545 42804 21749 42804 21547 42805 21732 42805 21567 42805 21567 42806 21732 42806 21548 42806 21567 42807 21548 42807 21568 42807 21568 42808 21548 42808 21549 42808 21568 42809 21549 42809 21569 42809 21569 42810 21549 42810 21730 42810 21569 42811 21730 42811 21550 42811 21550 42812 21730 42812 21735 42812 21550 42813 21735 42813 21551 42813 21551 42814 21735 42814 21552 42814 21551 42815 21552 42815 21573 42815 21573 42816 21552 42816 21742 42816 21573 42817 21742 42817 21574 42817 21574 42818 21742 42818 21741 42818 21574 42819 21741 42819 21553 42819 21553 42820 21741 42820 21740 42820 21553 42821 21740 42821 21739 42821 26312 42822 21554 42822 21555 42822 21555 42823 21554 42823 21722 42823 21555 42824 21722 42824 21556 42824 21556 42825 21722 42825 21726 42825 21556 42826 21726 42826 21557 42826 21557 42827 21726 42827 21558 42827 21557 42828 21558 42828 21566 42828 21566 42829 21558 42829 21560 42829 21566 42830 21560 42830 21559 42830 21559 42831 21560 42831 21561 42831 21559 42832 21561 42832 21547 42832 21547 42833 21561 42833 21562 42833 21547 42834 21562 42834 21732 42834 26363 42835 26254 42835 21595 42835 26264 42836 26265 42836 21634 42836 26266 42837 21563 42837 21564 42837 26310 42838 26312 42838 21555 42838 21563 42839 26310 42839 21564 42839 21564 42840 26310 42840 21555 42840 21564 42841 21555 42841 21632 42841 21632 42842 21555 42842 21556 42842 21632 42843 21556 42843 21630 42843 21630 42844 21556 42844 21557 42844 21630 42845 21557 42845 21565 42845 21565 42846 21557 42846 21566 42846 21565 42847 21566 42847 21628 42847 21628 42848 21566 42848 21559 42848 21628 42849 21559 42849 21627 42849 21627 42850 21559 42850 21547 42850 21627 42851 21547 42851 21625 42851 21625 42852 21547 42852 21567 42852 21625 42853 21567 42853 21624 42853 21624 42854 21567 42854 21568 42854 21624 42855 21568 42855 21622 42855 21622 42856 21568 42856 21569 42856 21622 42857 21569 42857 21570 42857 21570 42858 21569 42858 21550 42858 21570 42859 21550 42859 21571 42859 21571 42860 21550 42860 21551 42860 21571 42861 21551 42861 21572 42861 21572 42862 21551 42862 21573 42862 21572 42863 21573 42863 21618 42863 21618 42864 21573 42864 21574 42864 21618 42865 21574 42865 21575 42865 21575 42866 21574 42866 21553 42866 21575 42867 21553 42867 21576 42867 21576 42868 21553 42868 21538 42868 21576 42869 21538 42869 21616 42869 21616 42870 21538 42870 21539 42870 21616 42871 21539 42871 21614 42871 21614 42872 21539 42872 21577 42872 21614 42873 21577 42873 21613 42873 21613 42874 21577 42874 21542 42874 21613 42875 21542 42875 21612 42875 21612 42876 21542 42876 21578 42876 21612 42877 21578 42877 21579 42877 21579 42878 21578 42878 21546 42878 21579 42879 21546 42879 21580 42879 21580 42880 21546 42880 21531 42880 21580 42881 21531 42881 21581 42881 21581 42882 21531 42882 21532 42882 21581 42883 21532 42883 21609 42883 21609 42884 21532 42884 21582 42884 21609 42885 21582 42885 21608 42885 21608 42886 21582 42886 21583 42886 21608 42887 21583 42887 21606 42887 21606 42888 21583 42888 21534 42888 21606 42889 21534 42889 21603 42889 21603 42890 21534 42890 21584 42890 21603 42891 21584 42891 21601 42891 21601 42892 21584 42892 21585 42892 21601 42893 21585 42893 21586 42893 21586 42894 21585 42894 21587 42894 21586 42895 21587 42895 21600 42895 21600 42896 21587 42896 21588 42896 21600 42897 21588 42897 21597 42897 21597 42898 21588 42898 21519 42898 21597 42899 21519 42899 21589 42899 21589 42900 21519 42900 21520 42900 21589 42901 21520 42901 21590 42901 21590 42902 21520 42902 21522 42902 21590 42903 21522 42903 21591 42903 21591 42904 21522 42904 21592 42904 21591 42905 21592 42905 21594 42905 21594 42906 21592 42906 21524 42906 21594 42907 21524 42907 21593 42907 21593 42908 21524 42908 21526 42908 21593 42909 21526 42909 26364 42909 26364 42910 21526 42910 21528 42910 26364 42911 26363 42911 21593 42911 21593 42912 26363 42912 21595 42912 21593 42913 21595 42913 21594 42913 21594 42914 21595 42914 21667 42914 21594 42915 21667 42915 21591 42915 21591 42916 21667 42916 21666 42916 21591 42917 21666 42917 21590 42917 21590 42918 21666 42918 21596 42918 21590 42919 21596 42919 21589 42919 21589 42920 21596 42920 21598 42920 21589 42921 21598 42921 21597 42921 21597 42922 21598 42922 21664 42922 21597 42923 21664 42923 21600 42923 21600 42924 21664 42924 21599 42924 21600 42925 21599 42925 21586 42925 21586 42926 21599 42926 21602 42926 21586 42927 21602 42927 21601 42927 21601 42928 21602 42928 21604 42928 21601 42929 21604 42929 21603 42929 21603 42930 21604 42930 21605 42930 21603 42931 21605 42931 21606 42931 21606 42932 21605 42932 21607 42932 21606 42933 21607 42933 21608 42933 21608 42934 21607 42934 21657 42934 21608 42935 21657 42935 21609 42935 21609 42936 21657 42936 21610 42936 21609 42937 21610 42937 21581 42937 21581 42938 21610 42938 21656 42938 21581 42939 21656 42939 21580 42939 21580 42940 21656 42940 21654 42940 21580 42941 21654 42941 21579 42941 21579 42942 21654 42942 21611 42942 21579 42943 21611 42943 21612 42943 21612 42944 21611 42944 21652 42944 21612 42945 21652 42945 21613 42945 21613 42946 21652 42946 21615 42946 21613 42947 21615 42947 21614 42947 21614 42948 21615 42948 21617 42948 21614 42949 21617 42949 21616 42949 21616 42950 21617 42950 21649 42950 21616 42951 21649 42951 21576 42951 21576 42952 21649 42952 21647 42952 21576 42953 21647 42953 21575 42953 21575 42954 21647 42954 21646 42954 21575 42955 21646 42955 21618 42955 21618 42956 21646 42956 21619 42956 21618 42957 21619 42957 21572 42957 21572 42958 21619 42958 21620 42958 21572 42959 21620 42959 21571 42959 21571 42960 21620 42960 21644 42960 21571 42961 21644 42961 21570 42961 21570 42962 21644 42962 21621 42962 21570 42963 21621 42963 21622 42963 21622 42964 21621 42964 21623 42964 21622 42965 21623 42965 21624 42965 21624 42966 21623 42966 21626 42966 21624 42967 21626 42967 21625 42967 21625 42968 21626 42968 21643 42968 21625 42969 21643 42969 21627 42969 21627 42970 21643 42970 21640 42970 21627 42971 21640 42971 21628 42971 21628 42972 21640 42972 21629 42972 21628 42973 21629 42973 21565 42973 21565 42974 21629 42974 21639 42974 21565 42975 21639 42975 21630 42975 21630 42976 21639 42976 21635 42976 21630 42977 21635 42977 21632 42977 21632 42978 21635 42978 21631 42978 21632 42979 21631 42979 21564 42979 21564 42980 21631 42980 21634 42980 21564 42981 21634 42981 26266 42981 26266 42982 21634 42982 26265 42982 26257 42983 26264 42983 21633 42983 21633 42984 26264 42984 21634 42984 21633 42985 21634 42985 26401 42985 26401 42986 21634 42986 21631 42986 26401 42987 21631 42987 21636 42987 21636 42988 21631 42988 21635 42988 21636 42989 21635 42989 21637 42989 21637 42990 21635 42990 21639 42990 21637 42991 21639 42991 21638 42991 21638 42992 21639 42992 21629 42992 21638 42993 21629 42993 26381 42993 26381 42994 21629 42994 21640 42994 26381 42995 21640 42995 21641 42995 21641 42996 21640 42996 21643 42996 21641 42997 21643 42997 21642 42997 21642 42998 21643 42998 21626 42998 21642 42999 21626 42999 26380 42999 26380 43000 21626 43000 21623 43000 26380 43001 21623 43001 26379 43001 26379 43002 21623 43002 21621 43002 26379 43003 21621 43003 26371 43003 26371 43004 21621 43004 21644 43004 26371 43005 21644 43005 21645 43005 21645 43006 21644 43006 21620 43006 21645 43007 21620 43007 26373 43007 26373 43008 21620 43008 21619 43008 26373 43009 21619 43009 26374 43009 26374 43010 21619 43010 21646 43010 26374 43011 21646 43011 26376 43011 26376 43012 21646 43012 21647 43012 26376 43013 21647 43013 21648 43013 21648 43014 21647 43014 21649 43014 21648 43015 21649 43015 21650 43015 21650 43016 21649 43016 21617 43016 21650 43017 21617 43017 26369 43017 26369 43018 21617 43018 21615 43018 26369 43019 21615 43019 21651 43019 21651 43020 21615 43020 21652 43020 21651 43021 21652 43021 21653 43021 21653 43022 21652 43022 21611 43022 21653 43023 21611 43023 26396 43023 26396 43024 21611 43024 21654 43024 26396 43025 21654 43025 21655 43025 21655 43026 21654 43026 21656 43026 21655 43027 21656 43027 26398 43027 26398 43028 21656 43028 21610 43028 26398 43029 21610 43029 26394 43029 26394 43030 21610 43030 21657 43030 26394 43031 21657 43031 21658 43031 21658 43032 21657 43032 21607 43032 21658 43033 21607 43033 26395 43033 26395 43034 21607 43034 21605 43034 26395 43035 21605 43035 21659 43035 21659 43036 21605 43036 21604 43036 21659 43037 21604 43037 21660 43037 21660 43038 21604 43038 21602 43038 21660 43039 21602 43039 21661 43039 21661 43040 21602 43040 21599 43040 21661 43041 21599 43041 21662 43041 21662 43042 21599 43042 21664 43042 21662 43043 21664 43043 21663 43043 21663 43044 21664 43044 21598 43044 21663 43045 21598 43045 21665 43045 21665 43046 21598 43046 21596 43046 21665 43047 21596 43047 26368 43047 26368 43048 21596 43048 21666 43048 26368 43049 21666 43049 26410 43049 26410 43050 21666 43050 21667 43050 26410 43051 21667 43051 26411 43051 26411 43052 21667 43052 21595 43052 26411 43053 21595 43053 26413 43053 26413 43054 21595 43054 26254 43054 21766 43055 21681 43055 21680 43055 21668 43056 21675 43056 21673 43056 26427 43057 26428 43057 26138 43057 21769 43058 26427 43058 21770 43058 26419 43059 21669 43059 26420 43059 26420 43060 21669 43060 21671 43060 21676 43061 21675 43061 26431 43061 26431 43062 21675 43062 21668 43062 26431 43063 21668 43063 21743 43063 26417 43064 21681 43064 21670 43064 21670 43065 21681 43065 21766 43065 21670 43066 21766 43066 26424 43066 21671 43067 21669 43067 21672 43067 21672 43068 21669 43068 21723 43068 21672 43069 21723 43069 21719 43069 21746 43070 21673 43070 21674 43070 21674 43071 21673 43071 21675 43071 21674 43072 21675 43072 21677 43072 21677 43073 21675 43073 21676 43073 21677 43074 21676 43074 21678 43074 21767 43075 21680 43075 21679 43075 21679 43076 21680 43076 21681 43076 21679 43077 21681 43077 21682 43077 21682 43078 21681 43078 26417 43078 21682 43079 26417 43079 21769 43079 21684 43080 21725 43080 21724 43080 21732 43081 21562 43081 21683 43081 21683 43082 21562 43082 21684 43082 21683 43083 21684 43083 21728 43083 21728 43084 21684 43084 21724 43084 21728 43085 21724 43085 21727 43085 21685 43086 26438 43086 21686 43086 21686 43087 26438 43087 21733 43087 21686 43088 21733 43088 21729 43088 21729 43089 21733 43089 21687 43089 21729 43090 21687 43090 21731 43090 21731 43091 21687 43091 21688 43091 21689 43092 26451 43092 21734 43092 21734 43093 26451 43093 21690 43093 21734 43094 21690 43094 21691 43094 21691 43095 21690 43095 21737 43095 21691 43096 21737 43096 21692 43096 21692 43097 21737 43097 21738 43097 21692 43098 21738 43098 21552 43098 21552 43099 21738 43099 21742 43099 26450 43100 21693 43100 21736 43100 21736 43101 21693 43101 21694 43101 21736 43102 21694 43102 21696 43102 21696 43103 21694 43103 21695 43103 21696 43104 21695 43104 21697 43104 21697 43105 21695 43105 21698 43105 21693 43106 26448 43106 21694 43106 21694 43107 26448 43107 21744 43107 21694 43108 21744 43108 21695 43108 21695 43109 21744 43109 21745 43109 21695 43110 21745 43110 21698 43110 21698 43111 21745 43111 21747 43111 21698 43112 21747 43112 21699 43112 21699 43113 21747 43113 21540 43113 21700 43114 21750 43114 21748 43114 21756 43115 21530 43115 21751 43115 21751 43116 21530 43116 21700 43116 21751 43117 21700 43117 21701 43117 21701 43118 21700 43118 21748 43118 21701 43119 21748 43119 21702 43119 26416 43120 26423 43120 21703 43120 21703 43121 26423 43121 21758 43121 21703 43122 21758 43122 21704 43122 21704 43123 21758 43123 21760 43123 21704 43124 21760 43124 21752 43124 21752 43125 21760 43125 21754 43125 21757 43126 26422 43126 21759 43126 21759 43127 26422 43127 21761 43127 21759 43128 21761 43128 21705 43128 21705 43129 21761 43129 21707 43129 21705 43130 21707 43130 21706 43130 21706 43131 21707 43131 21709 43131 21706 43132 21709 43132 21708 43132 21708 43133 21709 43133 21536 43133 21710 43134 26426 43134 21711 43134 21711 43135 26426 43135 21715 43135 21711 43136 21715 43136 21712 43136 21712 43137 21715 43137 21716 43137 21712 43138 21716 43138 21763 43138 21763 43139 21716 43139 21713 43139 26426 43140 21714 43140 21715 43140 21715 43141 21714 43141 21765 43141 21715 43142 21765 43142 21716 43142 21716 43143 21765 43143 21717 43143 21716 43144 21717 43144 21713 43144 21713 43145 21717 43145 21768 43145 21713 43146 21768 43146 21718 43146 21718 43147 21768 43147 21521 43147 21719 43148 21723 43148 21721 43148 21721 43149 21723 43149 21720 43149 21721 43150 21720 43150 26140 43150 26140 43151 21720 43151 21722 43151 26140 43152 21722 43152 21554 43152 26419 43153 21727 43153 21669 43153 21669 43154 21727 43154 21724 43154 21669 43155 21724 43155 21723 43155 21723 43156 21724 43156 21725 43156 21723 43157 21725 43157 21720 43157 21720 43158 21725 43158 21726 43158 21720 43159 21726 43159 21722 43159 21562 43160 21561 43160 21684 43160 21684 43161 21561 43161 21560 43161 21684 43162 21560 43162 21725 43162 21725 43163 21560 43163 21558 43163 21725 43164 21558 43164 21726 43164 26419 43165 21685 43165 21727 43165 21727 43166 21685 43166 21686 43166 21727 43167 21686 43167 21728 43167 21728 43168 21686 43168 21729 43168 21728 43169 21729 43169 21683 43169 21683 43170 21729 43170 21731 43170 21683 43171 21731 43171 21732 43171 21735 43172 21730 43172 21688 43172 21688 43173 21730 43173 21549 43173 21688 43174 21549 43174 21731 43174 21731 43175 21549 43175 21548 43175 21731 43176 21548 43176 21732 43176 26438 43177 21689 43177 21733 43177 21733 43178 21689 43178 21734 43178 21733 43179 21734 43179 21687 43179 21687 43180 21734 43180 21691 43180 21687 43181 21691 43181 21688 43181 21688 43182 21691 43182 21692 43182 21688 43183 21692 43183 21735 43183 21735 43184 21692 43184 21552 43184 26451 43185 26450 43185 21690 43185 21690 43186 26450 43186 21736 43186 21690 43187 21736 43187 21737 43187 21737 43188 21736 43188 21696 43188 21737 43189 21696 43189 21738 43189 21738 43190 21696 43190 21697 43190 21738 43191 21697 43191 21742 43191 21699 43192 21739 43192 21698 43192 21698 43193 21739 43193 21740 43193 21698 43194 21740 43194 21697 43194 21697 43195 21740 43195 21741 43195 21697 43196 21741 43196 21742 43196 26448 43197 21743 43197 21744 43197 21744 43198 21743 43198 21668 43198 21744 43199 21668 43199 21745 43199 21745 43200 21668 43200 21673 43200 21745 43201 21673 43201 21747 43201 21747 43202 21673 43202 21746 43202 21747 43203 21746 43203 21540 43203 21540 43204 21746 43204 21541 43204 21678 43205 21702 43205 21677 43205 21677 43206 21702 43206 21748 43206 21677 43207 21748 43207 21674 43207 21674 43208 21748 43208 21750 43208 21674 43209 21750 43209 21746 43209 21746 43210 21750 43210 21543 43210 21746 43211 21543 43211 21541 43211 21530 43212 21749 43212 21700 43212 21700 43213 21749 43213 21545 43213 21700 43214 21545 43214 21750 43214 21750 43215 21545 43215 21544 43215 21750 43216 21544 43216 21543 43216 21678 43217 26416 43217 21702 43217 21702 43218 26416 43218 21703 43218 21702 43219 21703 43219 21701 43219 21701 43220 21703 43220 21704 43220 21701 43221 21704 43221 21751 43221 21751 43222 21704 43222 21752 43222 21751 43223 21752 43223 21756 43223 21753 43224 21755 43224 21754 43224 21754 43225 21755 43225 21535 43225 21754 43226 21535 43226 21752 43226 21752 43227 21535 43227 21533 43227 21752 43228 21533 43228 21756 43228 26423 43229 21757 43229 21758 43229 21758 43230 21757 43230 21759 43230 21758 43231 21759 43231 21760 43231 21760 43232 21759 43232 21705 43232 21760 43233 21705 43233 21754 43233 21754 43234 21705 43234 21706 43234 21754 43235 21706 43235 21753 43235 21753 43236 21706 43236 21708 43236 26422 43237 21710 43237 21761 43237 21761 43238 21710 43238 21711 43238 21761 43239 21711 43239 21707 43239 21707 43240 21711 43240 21712 43240 21707 43241 21712 43241 21709 43241 21709 43242 21712 43242 21763 43242 21709 43243 21763 43243 21536 43243 21718 43244 21762 43244 21713 43244 21713 43245 21762 43245 21537 43245 21713 43246 21537 43246 21763 43246 21763 43247 21537 43247 21764 43247 21763 43248 21764 43248 21536 43248 21714 43249 26424 43249 21765 43249 21765 43250 26424 43250 21766 43250 21765 43251 21766 43251 21717 43251 21717 43252 21766 43252 21680 43252 21717 43253 21680 43253 21768 43253 21768 43254 21680 43254 21767 43254 21768 43255 21767 43255 21521 43255 21521 43256 21767 43256 21523 43256 21773 43257 21527 43257 21525 43257 21769 43258 21770 43258 21682 43258 21682 43259 21770 43259 21771 43259 21682 43260 21771 43260 21679 43260 21679 43261 21771 43261 21773 43261 21679 43262 21773 43262 21767 43262 21767 43263 21773 43263 21525 43263 21767 43264 21525 43264 21523 43264 26427 43265 26138 43265 21770 43265 21770 43266 26138 43266 26137 43266 21770 43267 26137 43267 21771 43267 21771 43268 26137 43268 21772 43268 21771 43269 21772 43269 21773 43269 21773 43270 21772 43270 21529 43270 21773 43271 21529 43271 21527 43271 26136 43272 21774 43272 21775 43272 21775 43273 21774 43273 26400 43273 21775 43274 26400 43274 21266 43274 21266 43275 26400 43275 21776 43275 21266 43276 21776 43276 21265 43276 21265 43277 21776 43277 21777 43277 21265 43278 21777 43278 21264 43278 21264 43279 21777 43279 21778 43279 21264 43280 21778 43280 21779 43280 21779 43281 21778 43281 21780 43281 21779 43282 21780 43282 21262 43282 21262 43283 21780 43283 26372 43283 21262 43284 26372 43284 21781 43284 21781 43285 26372 43285 26375 43285 21781 43286 26375 43286 21261 43286 21261 43287 26375 43287 26370 43287 21261 43288 26370 43288 21782 43288 21782 43289 26370 43289 26366 43289 21782 43290 26366 43290 21260 43290 21260 43291 26366 43291 26397 43291 21260 43292 26397 43292 21257 43292 21257 43293 26397 43293 21783 43293 21257 43294 21783 43294 21784 43294 21784 43295 21783 43295 26393 43295 21784 43296 26393 43296 21255 43296 21255 43297 26393 43297 26392 43297 21255 43298 26392 43298 21253 43298 21253 43299 26392 43299 21785 43299 21253 43300 21785 43300 21786 43300 21786 43301 21785 43301 26378 43301 21786 43302 26378 43302 21251 43302 21251 43303 26378 43303 26367 43303 21251 43304 26367 43304 26949 43304 26949 43305 26367 43305 26126 43305 21233 43306 26125 43306 21787 43306 21787 43307 26125 43307 21788 43307 21787 43308 21788 43308 21789 43308 21789 43309 21788 43309 21790 43309 21789 43310 21790 43310 21236 43310 21236 43311 21790 43311 21791 43311 21236 43312 21791 43312 21792 43312 21792 43313 21791 43313 26425 43313 21792 43314 26425 43314 21239 43314 21239 43315 26425 43315 21793 43315 21239 43316 21793 43316 21795 43316 21795 43317 21793 43317 21794 43317 21795 43318 21794 43318 21796 43318 21796 43319 21794 43319 26414 43319 21796 43320 26414 43320 21242 43320 21242 43321 26414 43321 26415 43321 21242 43322 26415 43322 21243 43322 21243 43323 26415 43323 21797 43323 21243 43324 21797 43324 21798 43324 21798 43325 21797 43325 26430 43325 21798 43326 26430 43326 21799 43326 21799 43327 26430 43327 21800 43327 21799 43328 21800 43328 21801 43328 21801 43329 21800 43329 26449 43329 21801 43330 26449 43330 21244 43330 21244 43331 26449 43331 21802 43331 21244 43332 21802 43332 21246 43332 21246 43333 21802 43333 21803 43333 21246 43334 21803 43334 21247 43334 21247 43335 21803 43335 26437 43335 21247 43336 26437 43336 21249 43336 21249 43337 26437 43337 26439 43337 21249 43338 26439 43338 26112 43338 26112 43339 26439 43339 21804 43339 26099 43340 26084 43340 21805 43340 21805 43341 26084 43341 25539 43341 24167 43342 26083 43342 21806 43342 21806 43343 26083 43343 21807 43343 21806 43344 21807 43344 24164 43344 24164 43345 21807 43345 21808 43345 24164 43346 21808 43346 21809 43346 21809 43347 21808 43347 21810 43347 21809 43348 21810 43348 21811 43348 21811 43349 21810 43349 26105 43349 21811 43350 26105 43350 24163 43350 24163 43351 26105 43351 26107 43351 24163 43352 26107 43352 21812 43352 21812 43353 26107 43353 26108 43353 21812 43354 26108 43354 21813 43354 21813 43355 26108 43355 26109 43355 21814 43356 21815 43356 25536 43356 25536 43357 21815 43357 26071 43357 25925 43358 25941 43358 21816 43358 21816 43359 25941 43359 25939 43359 25937 43360 25298 43360 25939 43360 25939 43361 25298 43361 25302 43361 25939 43362 25302 43362 21816 43362 25294 43363 25295 43363 21818 43363 21818 43364 25295 43364 21817 43364 21818 43365 21817 43365 25937 43365 25937 43366 21817 43366 25297 43366 25937 43367 25297 43367 25298 43367 25294 43368 21818 43368 25293 43368 25293 43369 21818 43369 21820 43369 25293 43370 21820 43370 21819 43370 21819 43371 21820 43371 25290 43371 25290 43372 21820 43372 25934 43372 25290 43373 25934 43373 25291 43373 25291 43374 25934 43374 25286 43374 25286 43375 25934 43375 21821 43375 25286 43376 21821 43376 25288 43376 25367 43377 21822 43377 21823 43377 21823 43378 21822 43378 21826 43378 21823 43379 21826 43379 21828 43379 21829 43380 21825 43380 21824 43380 21824 43381 21825 43381 25362 43381 21824 43382 25362 43382 21826 43382 21826 43383 25362 43383 21827 43383 21826 43384 21827 43384 21828 43384 21829 43385 21824 43385 25359 43385 25359 43386 21824 43386 21830 43386 25359 43387 21830 43387 25358 43387 25358 43388 21830 43388 21831 43388 21831 43389 21830 43389 21832 43389 21831 43390 21832 43390 25356 43390 25356 43391 21832 43391 25352 43391 25352 43392 21832 43392 21833 43392 25352 43393 21833 43393 25353 43393 21834 43394 21835 43394 25900 43394 21834 43395 25900 43395 21836 43395 21836 43396 25900 43396 21838 43396 21836 43397 21838 43397 21837 43397 21837 43398 21838 43398 21839 43398 21839 43399 21838 43399 21841 43399 21839 43400 21841 43400 21840 43400 21840 43401 21841 43401 25424 43401 25424 43402 21841 43402 21842 43402 25424 43403 21842 43403 25419 43403 25419 43404 21842 43404 25887 43404 25419 43405 25887 43405 25886 43405 21843 43406 25883 43406 21844 43406 21844 43407 25883 43407 21845 43407 21844 43408 21845 43408 25477 43408 25477 43409 21845 43409 25478 43409 25478 43410 21845 43410 21847 43410 25478 43411 21847 43411 21846 43411 21846 43412 21847 43412 25878 43412 21846 43413 25878 43413 25469 43413 25544 43414 25858 43414 25543 43414 25543 43415 25858 43415 21848 43415 25543 43416 21848 43416 25540 43416 25540 43417 21848 43417 25842 43417 25540 43418 25842 43418 25841 43418 24177 43419 21849 43419 24176 43419 24176 43420 21849 43420 25831 43420 24176 43421 25831 43421 24173 43421 24173 43422 25831 43422 21850 43422 24173 43423 21850 43423 24172 43423 24172 43424 21850 43424 25836 43424 24172 43425 25836 43425 21851 43425 21851 43426 25836 43426 25837 43426 21851 43427 25837 43427 21852 43427 21852 43428 25837 43428 21853 43428 21852 43429 21853 43429 21855 43429 21855 43430 21853 43430 21854 43430 21855 43431 21854 43431 21856 43431 21856 43432 21854 43432 25810 43432 21857 43433 26971 43433 24181 43433 24181 43434 26971 43434 26978 43434 24181 43435 26978 43435 21858 43435 21858 43436 26978 43436 26979 43436 21858 43437 26979 43437 21860 43437 21860 43438 26979 43438 21859 43438 21860 43439 21859 43439 21861 43439 21861 43440 21859 43440 21862 43440 21861 43441 21862 43441 24187 43441 24187 43442 21862 43442 26981 43442 24187 43443 26981 43443 24186 43443 24186 43444 26981 43444 26983 43444 21863 43445 26035 43445 21864 43445 21864 43446 26035 43446 26034 43446 21864 43447 26034 43447 21865 43447 21865 43448 26034 43448 21866 43448 21865 43449 21866 43449 21867 43449 21867 43450 21866 43450 26037 43450 21867 43451 26037 43451 21868 43451 21868 43452 26037 43452 26039 43452 21868 43453 26039 43453 24194 43453 24194 43454 26039 43454 21870 43454 24194 43455 21870 43455 21869 43455 21869 43456 21870 43456 25801 43456 25799 43457 21871 43457 24203 43457 24203 43458 21871 43458 21872 43458 24203 43459 21872 43459 24200 43459 24200 43460 21872 43460 26005 43460 24200 43461 26005 43461 24199 43461 24199 43462 26005 43462 26007 43462 24199 43463 26007 43463 24214 43463 24214 43464 26007 43464 26009 43464 24214 43465 26009 43465 24212 43465 24212 43466 26009 43466 21873 43466 24212 43467 21873 43467 24211 43467 24211 43468 21873 43468 26011 43468 24223 43469 25795 43469 21875 43469 21875 43470 25795 43470 21874 43470 21875 43471 21874 43471 24222 43471 24222 43472 21874 43472 21876 43472 24222 43473 21876 43473 21877 43473 21877 43474 21876 43474 25983 43474 21877 43475 25983 43475 24220 43475 24220 43476 25983 43476 25984 43476 24220 43477 25984 43477 21878 43477 21878 43478 25984 43478 25986 43478 21878 43479 25986 43479 24217 43479 24217 43480 25986 43480 25987 43480 25787 43481 25967 43481 21879 43481 21879 43482 25967 43482 25957 43482 21879 43483 25957 43483 21880 43483 21880 43484 25957 43484 21881 43484 21880 43485 21881 43485 21882 43485 21882 43486 21881 43486 25958 43486 21882 43487 25958 43487 24231 43487 24231 43488 25958 43488 21883 43488 24231 43489 21883 43489 24230 43489 24230 43490 21883 43490 21884 43490 24230 43491 21884 43491 24228 43491 24228 43492 21884 43492 25779 43492 24247 43493 25940 43493 24245 43493 24245 43494 25940 43494 21886 43494 24245 43495 21886 43495 21885 43495 21885 43496 21886 43496 21887 43496 21885 43497 21887 43497 21888 43497 21888 43498 21887 43498 25926 43498 21888 43499 25926 43499 24242 43499 24242 43500 25926 43500 25930 43500 24242 43501 25930 43501 21889 43501 21889 43502 25930 43502 25929 43502 21889 43503 25929 43503 21890 43503 21890 43504 25929 43504 25931 43504 21890 43505 25931 43505 21891 43505 21891 43506 25931 43506 25932 43506 21892 43507 25919 43507 21893 43507 21893 43508 25919 43508 25920 43508 21893 43509 25920 43509 24259 43509 24259 43510 25920 43510 21894 43510 24259 43511 21894 43511 24258 43511 24258 43512 21894 43512 21895 43512 24258 43513 21895 43513 21896 43513 21896 43514 21895 43514 25915 43514 21896 43515 25915 43515 21897 43515 21897 43516 25915 43516 25914 43516 21897 43517 25914 43517 24256 43517 24256 43518 25914 43518 25911 43518 24256 43519 25911 43519 24254 43519 24254 43520 25911 43520 25772 43520 24265 43521 25771 43521 24263 43521 24263 43522 25771 43522 25901 43522 24263 43523 25901 43523 21898 43523 21898 43524 25901 43524 25902 43524 21898 43525 25902 43525 24262 43525 24262 43526 25902 43526 25905 43526 24262 43527 25905 43527 24273 43527 24273 43528 25905 43528 21899 43528 24273 43529 21899 43529 21900 43529 21900 43530 21899 43530 21901 43530 21900 43531 21901 43531 24271 43531 24271 43532 21901 43532 25764 43532 25762 43533 25881 43533 21902 43533 21902 43534 25881 43534 25882 43534 21902 43535 25882 43535 24274 43535 24274 43536 25882 43536 21903 43536 24274 43537 21903 43537 21904 43537 21904 43538 21903 43538 25884 43538 21904 43539 25884 43539 21905 43539 21905 43540 25884 43540 25885 43540 21905 43541 25885 43541 24278 43541 24278 43542 25885 43542 21906 43542 24278 43543 21906 43543 24279 43543 24279 43544 21906 43544 25873 43544 24279 43545 25873 43545 24280 43545 24280 43546 25873 43546 25874 43546 21907 43547 25857 43547 24290 43547 24290 43548 25857 43548 25859 43548 24290 43549 25859 43549 24289 43549 24289 43550 25859 43550 21908 43550 24289 43551 21908 43551 24288 43551 24288 43552 21908 43552 21909 43552 24288 43553 21909 43553 21910 43553 21910 43554 21909 43554 25862 43554 21910 43555 25862 43555 24286 43555 24286 43556 25862 43556 21911 43556 24286 43557 21911 43557 21912 43557 21912 43558 21911 43558 25753 43558 25610 43559 21913 43559 25611 43559 25611 43560 21913 43560 25275 43560 25611 43561 25275 43561 21914 43561 21914 43562 25275 43562 25263 43562 21914 43563 25263 43563 21915 43563 21916 43564 21917 43564 25927 43564 25927 43565 21917 43565 25271 43565 25927 43566 25271 43566 21918 43566 21918 43567 25271 43567 21919 43567 21918 43568 21919 43568 25610 43568 25610 43569 21919 43569 25273 43569 25610 43570 25273 43570 21913 43570 25663 43571 21920 43571 25913 43571 25913 43572 21920 43572 25340 43572 25913 43573 25340 43573 21921 43573 21921 43574 25340 43574 25607 43574 25607 43575 25340 43575 25342 43575 25607 43576 25342 43576 25608 43576 27189 43577 21922 43577 21923 43577 21923 43578 21922 43578 25412 43578 25876 43579 21927 43579 25511 43579 25876 43580 25511 43580 21925 43580 25511 43581 21924 43581 21925 43581 21925 43582 21924 43582 25863 43582 21925 43583 25863 43583 21926 43583 25876 43584 25599 43584 21927 43584 21927 43585 25599 43585 25640 43585 21927 43586 25640 43586 25641 43586 25582 43587 25583 43587 25855 43587 25582 43588 25855 43588 21929 43588 25855 43589 21928 43589 21929 43589 21929 43590 21928 43590 25851 43590 21929 43591 25851 43591 21930 43591 21931 43592 26684 43592 21932 43592 21931 43593 21932 43593 26680 43593 26680 43594 21932 43594 21380 43594 26680 43595 21380 43595 21933 43595 21933 43596 21380 43596 21934 43596 21933 43597 21934 43597 26682 43597 26682 43598 21934 43598 21378 43598 26682 43599 21378 43599 21935 43599 21935 43600 21378 43600 21376 43600 21935 43601 21376 43601 21936 43601 21936 43602 21376 43602 21938 43602 21936 43603 21938 43603 21937 43603 21937 43604 21938 43604 21375 43604 21937 43605 21375 43605 21939 43605 21939 43606 21375 43606 21373 43606 21939 43607 21373 43607 21940 43607 21940 43608 21373 43608 21371 43608 21940 43609 21371 43609 21941 43609 21941 43610 21371 43610 21942 43610 21941 43611 21942 43611 26655 43611 26655 43612 21942 43612 21943 43612 26655 43613 21943 43613 21944 43613 21944 43614 21943 43614 21369 43614 21944 43615 21369 43615 21945 43615 21945 43616 21369 43616 21367 43616 21945 43617 21367 43617 21946 43617 21946 43618 21367 43618 21366 43618 21946 43619 21366 43619 26658 43619 26658 43620 21366 43620 21947 43620 26658 43621 21947 43621 26660 43621 26660 43622 21947 43622 25185 43622 26660 43623 25185 43623 26662 43623 21252 43624 26806 43624 21948 43624 21948 43625 26806 43625 21950 43625 21948 43626 21950 43626 21949 43626 21949 43627 21950 43627 21951 43627 21949 43628 21951 43628 21254 43628 21254 43629 21951 43629 21952 43629 21254 43630 21952 43630 21256 43630 21256 43631 21952 43631 21953 43631 21256 43632 21953 43632 21258 43632 21258 43633 21953 43633 26779 43633 21258 43634 26779 43634 21259 43634 21259 43635 26779 43635 21954 43635 21259 43636 21954 43636 21955 43636 21955 43637 21954 43637 26782 43637 21955 43638 26782 43638 21956 43638 21956 43639 26782 43639 26783 43639 21956 43640 26783 43640 21957 43640 21957 43641 26783 43641 21959 43641 21957 43642 21959 43642 21958 43642 21958 43643 21959 43643 21960 43643 21958 43644 21960 43644 21961 43644 21961 43645 21960 43645 21962 43645 21961 43646 21962 43646 21963 43646 21963 43647 21962 43647 21964 43647 21963 43648 21964 43648 21263 43648 21263 43649 21964 43649 26787 43649 21263 43650 26787 43650 21965 43650 21965 43651 26787 43651 26788 43651 21965 43652 26788 43652 21966 43652 21966 43653 26788 43653 21968 43653 21966 43654 21968 43654 21967 43654 21967 43655 21968 43655 26790 43655 21967 43656 26790 43656 26925 43656 26925 43657 26790 43657 21969 43657 21327 43658 25169 43658 21329 43658 21329 43659 25169 43659 26841 43659 21329 43660 26841 43660 21970 43660 21970 43661 26841 43661 26843 43661 21970 43662 26843 43662 21971 43662 21971 43663 26843 43663 21973 43663 21971 43664 21973 43664 21972 43664 21972 43665 21973 43665 21974 43665 21972 43666 21974 43666 21975 43666 21975 43667 21974 43667 21976 43667 21975 43668 21976 43668 21332 43668 21332 43669 21976 43669 21977 43669 21332 43670 21977 43670 21333 43670 21333 43671 21977 43671 26846 43671 21333 43672 26846 43672 21335 43672 21335 43673 26846 43673 26848 43673 21335 43674 26848 43674 21978 43674 21978 43675 26848 43675 26849 43675 21978 43676 26849 43676 21337 43676 21337 43677 26849 43677 21979 43677 21337 43678 21979 43678 21339 43678 21339 43679 21979 43679 21980 43679 21339 43680 21980 43680 21341 43680 21341 43681 21980 43681 26852 43681 21341 43682 26852 43682 21982 43682 21982 43683 26852 43683 21981 43683 21982 43684 21981 43684 21983 43684 21983 43685 21981 43685 21985 43685 21983 43686 21985 43686 21984 43686 21984 43687 21985 43687 21986 43687 21984 43688 21986 43688 21988 43688 21988 43689 21986 43689 21987 43689 21988 43690 21987 43690 21989 43690 21989 43691 21987 43691 21990 43691 21989 43692 21990 43692 26808 43692 26808 43693 21990 43693 26856 43693 25154 43694 26866 43694 21322 43694 25154 43695 21322 43695 26858 43695 26858 43696 21322 43696 21320 43696 26858 43697 21320 43697 21991 43697 21991 43698 21320 43698 21318 43698 21991 43699 21318 43699 21992 43699 21992 43700 21318 43700 21993 43700 21992 43701 21993 43701 26861 43701 26861 43702 21993 43702 21317 43702 26861 43703 21317 43703 21994 43703 21994 43704 21317 43704 21316 43704 21994 43705 21316 43705 21995 43705 21995 43706 21316 43706 21997 43706 21995 43707 21997 43707 21996 43707 21996 43708 21997 43708 21308 43708 21996 43709 21308 43709 26831 43709 26831 43710 21308 43710 21309 43710 26831 43711 21309 43711 26832 43711 26832 43712 21309 43712 21304 43712 26832 43713 21304 43713 26833 43713 26833 43714 21304 43714 21303 43714 26833 43715 21303 43715 26835 43715 26835 43716 21303 43716 21999 43716 26835 43717 21999 43717 21998 43717 21998 43718 21999 43718 22000 43718 21998 43719 22000 43719 26836 43719 26836 43720 22000 43720 22002 43720 26836 43721 22002 43721 22001 43721 22001 43722 22002 43722 21291 43722 22001 43723 21291 43723 22003 43723 22003 43724 21291 43724 21294 43724 22003 43725 21294 43725 26840 43725 26840 43726 21294 43726 22004 43726 26840 43727 22004 43727 22005 43727 22005 43728 22004 43728 25143 43728 22005 43729 25143 43729 25142 43729 25140 43730 24958 43730 21286 43730 21286 43731 24958 43731 22006 43731 21286 43732 22006 43732 21285 43732 21285 43733 22006 43733 24957 43733 21285 43734 24957 43734 21284 43734 21284 43735 24957 43735 22007 43735 21284 43736 22007 43736 21282 43736 21282 43737 22007 43737 24956 43737 21282 43738 24956 43738 21280 43738 21280 43739 24956 43739 22008 43739 21280 43740 22008 43740 21278 43740 21278 43741 22008 43741 24943 43741 21278 43742 24943 43742 21276 43742 21276 43743 24943 43743 22009 43743 21276 43744 22009 43744 22010 43744 22010 43745 22009 43745 22012 43745 22010 43746 22012 43746 22011 43746 22011 43747 22012 43747 24942 43747 22011 43748 24942 43748 22013 43748 22013 43749 24942 43749 22014 43749 22013 43750 22014 43750 21273 43750 21273 43751 22014 43751 22015 43751 21273 43752 22015 43752 22016 43752 22016 43753 22015 43753 24951 43753 22016 43754 24951 43754 21271 43754 21271 43755 24951 43755 22017 43755 21271 43756 22017 43756 21269 43756 21269 43757 22017 43757 22018 43757 21269 43758 22018 43758 21268 43758 21268 43759 22018 43759 24949 43759 21268 43760 24949 43760 22019 43760 22019 43761 24949 43761 24947 43761 21267 43762 25124 43762 22020 43762 22020 43763 25124 43763 26618 43763 22020 43764 26618 43764 22021 43764 22021 43765 26618 43765 22022 43765 22021 43766 22022 43766 21270 43766 21270 43767 22022 43767 22023 43767 21270 43768 22023 43768 21272 43768 21272 43769 22023 43769 26619 43769 21272 43770 26619 43770 22024 43770 22024 43771 26619 43771 22025 43771 22024 43772 22025 43772 21274 43772 21274 43773 22025 43773 22026 43773 21274 43774 22026 43774 21275 43774 21275 43775 22026 43775 26622 43775 21275 43776 26622 43776 22027 43776 22027 43777 26622 43777 26623 43777 22027 43778 26623 43778 21277 43778 21277 43779 26623 43779 26625 43779 21277 43780 26625 43780 21279 43780 21279 43781 26625 43781 26626 43781 21279 43782 26626 43782 21281 43782 21281 43783 26626 43783 26627 43783 21281 43784 26627 43784 21283 43784 21283 43785 26627 43785 26628 43785 21283 43786 26628 43786 22028 43786 22028 43787 26628 43787 22029 43787 22028 43788 22029 43788 22030 43788 22030 43789 22029 43789 26629 43789 22030 43790 26629 43790 22031 43790 22031 43791 26629 43791 22033 43791 22031 43792 22033 43792 22032 43792 22032 43793 22033 43793 25110 43793 25109 43794 26661 43794 22034 43794 22034 43795 26661 43795 22035 43795 22034 43796 22035 43796 21382 43796 21382 43797 22035 43797 22036 43797 21382 43798 22036 43798 21385 43798 21385 43799 22036 43799 22037 43799 21385 43800 22037 43800 22039 43800 22039 43801 22037 43801 22038 43801 22039 43802 22038 43802 21387 43802 21387 43803 22038 43803 26664 43803 21387 43804 26664 43804 22040 43804 22040 43805 26664 43805 22041 43805 22040 43806 22041 43806 22042 43806 22042 43807 22041 43807 26666 43807 22042 43808 26666 43808 21390 43808 21390 43809 26666 43809 26668 43809 21390 43810 26668 43810 21391 43810 21391 43811 26668 43811 22043 43811 21391 43812 22043 43812 22044 43812 22044 43813 22043 43813 26670 43813 22044 43814 26670 43814 22045 43814 22045 43815 26670 43815 26673 43815 22045 43816 26673 43816 22046 43816 22046 43817 26673 43817 22047 43817 22046 43818 22047 43818 22049 43818 22049 43819 22047 43819 22048 43819 22049 43820 22048 43820 21397 43820 21397 43821 22048 43821 22050 43821 21397 43822 22050 43822 22051 43822 22051 43823 22050 43823 26676 43823 22051 43824 26676 43824 25094 43824 25094 43825 26676 43825 26677 43825 26716 43826 22052 43826 21363 43826 26716 43827 21363 43827 22054 43827 22054 43828 21363 43828 22053 43828 22054 43829 22053 43829 22055 43829 22055 43830 22053 43830 21360 43830 22055 43831 21360 43831 22056 43831 22056 43832 21360 43832 21358 43832 22056 43833 21358 43833 22057 43833 22057 43834 21358 43834 22058 43834 22057 43835 22058 43835 26719 43835 26719 43836 22058 43836 22060 43836 26719 43837 22060 43837 22059 43837 22059 43838 22060 43838 22061 43838 22059 43839 22061 43839 26722 43839 26722 43840 22061 43840 21353 43840 26722 43841 21353 43841 26723 43841 26723 43842 21353 43842 22063 43842 26723 43843 22063 43843 22062 43843 22062 43844 22063 43844 22064 43844 22062 43845 22064 43845 26725 43845 26725 43846 22064 43846 22065 43846 26725 43847 22065 43847 22066 43847 22066 43848 22065 43848 21349 43848 22066 43849 21349 43849 22067 43849 22067 43850 21349 43850 21347 43850 22067 43851 21347 43851 26728 43851 26728 43852 21347 43852 22068 43852 26728 43853 22068 43853 26729 43853 26729 43854 22068 43854 21345 43854 26729 43855 21345 43855 22069 43855 22069 43856 21345 43856 22070 43856 22069 43857 22070 43857 22071 43857 22071 43858 22070 43858 22072 43858 22071 43859 22072 43859 26731 43859 22073 43860 25076 43860 22074 43860 22074 43861 25076 43861 25000 43861 25071 43862 25022 43862 25006 43862 25006 43863 25022 43863 22075 43863 25006 43864 22075 43864 25005 43864 25005 43865 22075 43865 22076 43865 25005 43866 22076 43866 25011 43866 25011 43867 22076 43867 25024 43867 25011 43868 25024 43868 25075 43868 24980 43869 24979 43869 22077 43869 22077 43870 24979 43870 25064 43870 27201 43871 25047 43871 27018 43871 27018 43872 25047 43872 24991 43872 24968 43873 25042 43873 22078 43873 24968 43874 22078 43874 24967 43874 24967 43875 22078 43875 22080 43875 24967 43876 22080 43876 22079 43876 22079 43877 22080 43877 25044 43877 22079 43878 25044 43878 24965 43878 25042 43879 25043 43879 22078 43879 22078 43880 25043 43880 22081 43880 22078 43881 22081 43881 22080 43881 22080 43882 22081 43882 24887 43882 22080 43883 24887 43883 25044 43883 24882 43884 24884 43884 22083 43884 25061 43885 25041 43885 25062 43885 25062 43886 25041 43886 24882 43886 25062 43887 24882 43887 22082 43887 22082 43888 24882 43888 22083 43888 22077 43889 25064 43889 24879 43889 24879 43890 25064 43890 22084 43890 25037 43891 24877 43891 25064 43891 25064 43892 24877 43892 22084 43892 25047 43893 27201 43893 22085 43893 22085 43894 27201 43894 22086 43894 25079 43895 22074 43895 22087 43895 22087 43896 22074 43896 25001 43896 22088 43897 22089 43897 24934 43897 24934 43898 22089 43898 24933 43898 24862 43899 24532 43899 25031 43899 25031 43900 24532 43900 24533 43900 22110 43901 25028 43901 22111 43901 22111 43902 25028 43902 22090 43902 24838 43903 22111 43903 25026 43903 25026 43904 22111 43904 22090 43904 22104 43905 22091 43905 22106 43905 22106 43906 22091 43906 25023 43906 22106 43907 25023 43907 22107 43907 22107 43908 25023 43908 22092 43908 22107 43909 22092 43909 24845 43909 24845 43910 22092 43910 22093 43910 24891 43911 22094 43911 22095 43911 22095 43912 22094 43912 22096 43912 22095 43913 22096 43913 22097 43913 22097 43914 22096 43914 25021 43914 22097 43915 25021 43915 24889 43915 24889 43916 25021 43916 24890 43916 22098 43917 24552 43917 24859 43917 24859 43918 24552 43918 24479 43918 24886 43919 24885 43919 24493 43919 24493 43920 24885 43920 24940 43920 24940 43921 24885 43921 22099 43921 24940 43922 22099 43922 24855 43922 24491 43923 22100 43923 22101 43923 22101 43924 22100 43924 24886 43924 22101 43925 24886 43925 24492 43925 24492 43926 24886 43926 24493 43926 24878 43927 22102 43927 22088 43927 22088 43928 22102 43928 22089 43928 24908 43929 22103 43929 22104 43929 24908 43930 22104 43930 22105 43930 22105 43931 22104 43931 22106 43931 22105 43932 22106 43932 24904 43932 24904 43933 22106 43933 24902 43933 24902 43934 22106 43934 22107 43934 24902 43935 22107 43935 24900 43935 24900 43936 22107 43936 24845 43936 24900 43937 24845 43937 24844 43937 22108 43938 22110 43938 22109 43938 22109 43939 22110 43939 22111 43939 22109 43940 22111 43940 24909 43940 24376 43941 24291 43941 22112 43941 24376 43942 22112 43942 22113 43942 22113 43943 22112 43943 22114 43943 22113 43944 22114 43944 22115 43944 22115 43945 22114 43945 22116 43945 22115 43946 22116 43946 24386 43946 24386 43947 22116 43947 22117 43947 24386 43948 22117 43948 22118 43948 22118 43949 22117 43949 22119 43949 22118 43950 22119 43950 24387 43950 24387 43951 22119 43951 24287 43951 24387 43952 24287 43952 22120 43952 22120 43953 24287 43953 24828 43953 22120 43954 24828 43954 22121 43954 22122 43955 24827 43955 22123 43955 22122 43956 22123 43956 24397 43956 24397 43957 22123 43957 22124 43957 24397 43958 22124 43958 22125 43958 22125 43959 22124 43959 24275 43959 22125 43960 24275 43960 22126 43960 22126 43961 24275 43961 24276 43961 22126 43962 24276 43962 22127 43962 22127 43963 24276 43963 24277 43963 22127 43964 24277 43964 22128 43964 22128 43965 24277 43965 22129 43965 22128 43966 22129 43966 22130 43966 22130 43967 22129 43967 24821 43967 22130 43968 24821 43968 24820 43968 22410 43969 24266 43969 24264 43969 22410 43970 24264 43970 22131 43970 22131 43971 24264 43971 22132 43971 22131 43972 22132 43972 22133 43972 22133 43973 22132 43973 22134 43973 22133 43974 22134 43974 22135 43974 22135 43975 22134 43975 22136 43975 22135 43976 22136 43976 22411 43976 22411 43977 22136 43977 22137 43977 22411 43978 22137 43978 22138 43978 22138 43979 22137 43979 24272 43979 22138 43980 24272 43980 22140 43980 22140 43981 24272 43981 22139 43981 22140 43982 22139 43982 22413 43982 22416 43983 22141 43983 22142 43983 22416 43984 22142 43984 22143 43984 22143 43985 22142 43985 22144 43985 22143 43986 22144 43986 22145 43986 22145 43987 22144 43987 22146 43987 22145 43988 22146 43988 22415 43988 22415 43989 22146 43989 24257 43989 22415 43990 24257 43990 22147 43990 22147 43991 24257 43991 22148 43991 22147 43992 22148 43992 22417 43992 22417 43993 22148 43993 22149 43993 22417 43994 22149 43994 22150 43994 22150 43995 22149 43995 24255 43995 22150 43996 24255 43996 22419 43996 22151 43997 24249 43997 24248 43997 22151 43998 24248 43998 22425 43998 22425 43999 24248 43999 24246 43999 22425 44000 24246 44000 22152 44000 22152 44001 24246 44001 24244 44001 22152 44002 24244 44002 22424 44002 22424 44003 24244 44003 24243 44003 22424 44004 24243 44004 22429 44004 22429 44005 24243 44005 22153 44005 22429 44006 22153 44006 22430 44006 22430 44007 22153 44007 22154 44007 22430 44008 22154 44008 22155 44008 22155 44009 22154 44009 24241 44009 22155 44010 24241 44010 22431 44010 22156 44011 22157 44011 24233 44011 24234 44012 22159 44012 22158 44012 22158 44013 22159 44013 22443 44013 24233 44014 22157 44014 22159 44014 22159 44015 22157 44015 22160 44015 22159 44016 22160 44016 22443 44016 22156 44017 24233 44017 22161 44017 22161 44018 24233 44018 22162 44018 22161 44019 22162 44019 22444 44019 22444 44020 22162 44020 24232 44020 22444 44021 24232 44021 22163 44021 22163 44022 24232 44022 22164 44022 22163 44023 22164 44023 22445 44023 22445 44024 22164 44024 24229 44024 22445 44025 24229 44025 22165 44025 22458 44026 22457 44026 24224 44026 22458 44027 24224 44027 22459 44027 22459 44028 24224 44028 22166 44028 22459 44029 22166 44029 22460 44029 22460 44030 22166 44030 22167 44030 22460 44031 22167 44031 22462 44031 22462 44032 22167 44032 22168 44032 22168 44033 22167 44033 22169 44033 22168 44034 22169 44034 22170 44034 22170 44035 22169 44035 24221 44035 22170 44036 24221 44036 22464 44036 22464 44037 24221 44037 24219 44037 22464 44038 24219 44038 22466 44038 22466 44039 24219 44039 24218 44039 22466 44040 24218 44040 22467 44040 24778 44041 24204 44041 22171 44041 24778 44042 22171 44042 22391 44042 22391 44043 22171 44043 24202 44043 22391 44044 24202 44044 22172 44044 22172 44045 24202 44045 24201 44045 22172 44046 24201 44046 22173 44046 22173 44047 24201 44047 22174 44047 22173 44048 22174 44048 22175 44048 22175 44049 22174 44049 22176 44049 22175 44050 22176 44050 22392 44050 22392 44051 22176 44051 24213 44051 22392 44052 24213 44052 22177 44052 22177 44053 24213 44053 22178 44053 22177 44054 22178 44054 22393 44054 24320 44055 22179 44055 22180 44055 24320 44056 22180 44056 22181 44056 22181 44057 22180 44057 22182 44057 22181 44058 22182 44058 24322 44058 24322 44059 22182 44059 22183 44059 24322 44060 22183 44060 24327 44060 24327 44061 22183 44061 22184 44061 24327 44062 22184 44062 24326 44062 24326 44063 22184 44063 22185 44063 24326 44064 22185 44064 22186 44064 22186 44065 22185 44065 22187 44065 22186 44066 22187 44066 22188 44066 22188 44067 22187 44067 24193 44067 22188 44068 24193 44068 22189 44068 24340 44069 22190 44069 22191 44069 24340 44070 22191 44070 24341 44070 24341 44071 22191 44071 24180 44071 24341 44072 24180 44072 22192 44072 22192 44073 24180 44073 22193 44073 22192 44074 22193 44074 22194 44074 22194 44075 22193 44075 24179 44075 22194 44076 24179 44076 24343 44076 24343 44077 24179 44077 22195 44077 24343 44078 22195 44078 22196 44078 22196 44079 22195 44079 24188 44079 22196 44080 24188 44080 24342 44080 24342 44081 24188 44081 22197 44081 24342 44082 22197 44082 24344 44082 24355 44083 24757 44083 24175 44083 24355 44084 24175 44084 22198 44084 22198 44085 24175 44085 24174 44085 22198 44086 24174 44086 22199 44086 22199 44087 24174 44087 22200 44087 22199 44088 22200 44088 22201 44088 22201 44089 22200 44089 22203 44089 22201 44090 22203 44090 22202 44090 22202 44091 22203 44091 22204 44091 22202 44092 22204 44092 22205 44092 22205 44093 22204 44093 24171 44093 22205 44094 24171 44094 24357 44094 24357 44095 24171 44095 22206 44095 24357 44096 22206 44096 24365 44096 22207 44097 24168 44097 24166 44097 22207 44098 24166 44098 22208 44098 22208 44099 24166 44099 24165 44099 22208 44100 24165 44100 24368 44100 24368 44101 24165 44101 22210 44101 24368 44102 22210 44102 22209 44102 22209 44103 22210 44103 22211 44103 22209 44104 22211 44104 24369 44104 24369 44105 22211 44105 22212 44105 24369 44106 22212 44106 22214 44106 22214 44107 22212 44107 22213 44107 22214 44108 22213 44108 22215 44108 22215 44109 22213 44109 24162 44109 22215 44110 24162 44110 22216 44110 22217 44111 24732 44111 22487 44111 22487 44112 24732 44112 23032 44112 22487 44113 23032 44113 22485 44113 22485 44114 23032 44114 23031 44114 22485 44115 23031 44115 22484 44115 22484 44116 23031 44116 22218 44116 22484 44117 22218 44117 22483 44117 22483 44118 22218 44118 23028 44118 22483 44119 23028 44119 22481 44119 22481 44120 23028 44120 23027 44120 22481 44121 23027 44121 22480 44121 22480 44122 23027 44122 23026 44122 22480 44123 23026 44123 22219 44123 22219 44124 23026 44124 23023 44124 22219 44125 23023 44125 22220 44125 22220 44126 23023 44126 23022 44126 22220 44127 23022 44127 22221 44127 22221 44128 23022 44128 22222 44128 22221 44129 22222 44129 22224 44129 22224 44130 22222 44130 22223 44130 22224 44131 22223 44131 22478 44131 22478 44132 22223 44132 23019 44132 22478 44133 23019 44133 22477 44133 22477 44134 23019 44134 22225 44134 22477 44135 22225 44135 22475 44135 22475 44136 22225 44136 22226 44136 22475 44137 22226 44137 22474 44137 22474 44138 22226 44138 23015 44138 22474 44139 23015 44139 24313 44139 24313 44140 23015 44140 23014 44140 22227 44141 22228 44141 22363 44141 22227 44142 22363 44142 27246 44142 27246 44143 22363 44143 22229 44143 27246 44144 22229 44144 27247 44144 27247 44145 22229 44145 22365 44145 27247 44146 22365 44146 22230 44146 22230 44147 22365 44147 22366 44147 22230 44148 22366 44148 22231 44148 22231 44149 22366 44149 22368 44149 22231 44150 22368 44150 27236 44150 27236 44151 22368 44151 22232 44151 27236 44152 22232 44152 27216 44152 27216 44153 22232 44153 22370 44153 27216 44154 22370 44154 22233 44154 22233 44155 22370 44155 22372 44155 22233 44156 22372 44156 22234 44156 22234 44157 22372 44157 22374 44157 22234 44158 22374 44158 27215 44158 27215 44159 22374 44159 22235 44159 27215 44160 22235 44160 22237 44160 22237 44161 22235 44161 22236 44161 22237 44162 22236 44162 22238 44162 22238 44163 22236 44163 22378 44163 22238 44164 22378 44164 22239 44164 22239 44165 22378 44165 22240 44165 22239 44166 22240 44166 27252 44166 27252 44167 22240 44167 22380 44167 27252 44168 22380 44168 22241 44168 22241 44169 22380 44169 22242 44169 22241 44170 22242 44170 22243 44170 22243 44171 22242 44171 22385 44171 22243 44172 22385 44172 22244 44172 22244 44173 22385 44173 22387 44173 22244 44174 22387 44174 22245 44174 22245 44175 22387 44175 22386 44175 22245 44176 22386 44176 27256 44176 22248 44177 22291 44177 22247 44177 22360 44178 22246 44178 22290 44178 22290 44179 22246 44179 22289 44179 24659 44180 22247 44180 24648 44180 24648 44181 22247 44181 22291 44181 24648 44182 22291 44182 24660 44182 22247 44183 22249 44183 22248 44183 22248 44184 22249 44184 22250 44184 22248 44185 22250 44185 22251 44185 22251 44186 22250 44186 24614 44186 22251 44187 24614 44187 22252 44187 24614 44188 24615 44188 22252 44188 22252 44189 24615 44189 22253 44189 22252 44190 22253 44190 22294 44190 22294 44191 22253 44191 24613 44191 22294 44192 24613 44192 22296 44192 24613 44193 22254 44193 22296 44193 22296 44194 22254 44194 22256 44194 22296 44195 22256 44195 22255 44195 22255 44196 22256 44196 24609 44196 22255 44197 24609 44197 22257 44197 24609 44198 24610 44198 22257 44198 22257 44199 24610 44199 24612 44199 22257 44200 24612 44200 22258 44200 22258 44201 24612 44201 22259 44201 22258 44202 22259 44202 22260 44202 22260 44203 22259 44203 22261 44203 22260 44204 22261 44204 22301 44204 22261 44205 24608 44205 22301 44205 22301 44206 24608 44206 24607 44206 22301 44207 24607 44207 22303 44207 22303 44208 24607 44208 24606 44208 22303 44209 24606 44209 22304 44209 24606 44210 22262 44210 22304 44210 22304 44211 22262 44211 22263 44211 22304 44212 22263 44212 22306 44212 22306 44213 22263 44213 24604 44213 22306 44214 24604 44214 22307 44214 24604 44215 24603 44215 22307 44215 22307 44216 24603 44216 24601 44216 22307 44217 24601 44217 22264 44217 22264 44218 24601 44218 22265 44218 22264 44219 22265 44219 22266 44219 22265 44220 24599 44220 22266 44220 22266 44221 24599 44221 24597 44221 22266 44222 24597 44222 22267 44222 22267 44223 24597 44223 24598 44223 22267 44224 24598 44224 22269 44224 24598 44225 22268 44225 22269 44225 22269 44226 22268 44226 22270 44226 22269 44227 22270 44227 22310 44227 22310 44228 22270 44228 24594 44228 22310 44229 24594 44229 22312 44229 24594 44230 24595 44230 22312 44230 22312 44231 24595 44231 24596 44231 22312 44232 24596 44232 22313 44232 22313 44233 24596 44233 24593 44233 22313 44234 24593 44234 22315 44234 22315 44235 24593 44235 24592 44235 22315 44236 24592 44236 22316 44236 24592 44237 22271 44237 22316 44237 22316 44238 22271 44238 22272 44238 22316 44239 22272 44239 22273 44239 22273 44240 22272 44240 24588 44240 22273 44241 24588 44241 22318 44241 22318 44242 24588 44242 22274 44242 22318 44243 22274 44243 22319 44243 22319 44244 22274 44244 24589 44244 22319 44245 24589 44245 22322 44245 24589 44246 24586 44246 22322 44246 22322 44247 24586 44247 24587 44247 22322 44248 24587 44248 22275 44248 22275 44249 24587 44249 22276 44249 22275 44250 22276 44250 22277 44250 22276 44251 24583 44251 22277 44251 22277 44252 24583 44252 22278 44252 22277 44253 22278 44253 22279 44253 22279 44254 22278 44254 24584 44254 22279 44255 24584 44255 22324 44255 24584 44256 24580 44256 22324 44256 22324 44257 24580 44257 24579 44257 22324 44258 24579 44258 22280 44258 22280 44259 24579 44259 24577 44259 22280 44260 24577 44260 22281 44260 24577 44261 22282 44261 22281 44261 22281 44262 22282 44262 22283 44262 22281 44263 22283 44263 22328 44263 22328 44264 22283 44264 24576 44264 22328 44265 24576 44265 22285 44265 22285 44266 24576 44266 22284 44266 22285 44267 22284 44267 22330 44267 22284 44268 24574 44268 22330 44268 22330 44269 24574 44269 22286 44269 22330 44270 22286 44270 22287 44270 22287 44271 22286 44271 22288 44271 22287 44272 22288 44272 24657 44272 24657 44273 22288 44273 24712 44273 22289 44274 24660 44274 22290 44274 22290 44275 24660 44275 22291 44275 22290 44276 22291 44276 22292 44276 22292 44277 22291 44277 22248 44277 22292 44278 22248 44278 22358 44278 22358 44279 22248 44279 22251 44279 22358 44280 22251 44280 22293 44280 22293 44281 22251 44281 22252 44281 22293 44282 22252 44282 22356 44282 22356 44283 22252 44283 22294 44283 22356 44284 22294 44284 22355 44284 22355 44285 22294 44285 22296 44285 22355 44286 22296 44286 22295 44286 22295 44287 22296 44287 22255 44287 22295 44288 22255 44288 22297 44288 22297 44289 22255 44289 22257 44289 22297 44290 22257 44290 22298 44290 22298 44291 22257 44291 22258 44291 22298 44292 22258 44292 22299 44292 22299 44293 22258 44293 22260 44293 22299 44294 22260 44294 22300 44294 22300 44295 22260 44295 22301 44295 22300 44296 22301 44296 22302 44296 22302 44297 22301 44297 22303 44297 22302 44298 22303 44298 22352 44298 22352 44299 22303 44299 22304 44299 22352 44300 22304 44300 22305 44300 22305 44301 22304 44301 22306 44301 22305 44302 22306 44302 22351 44302 22351 44303 22306 44303 22307 44303 22351 44304 22307 44304 22349 44304 22349 44305 22307 44305 22264 44305 22349 44306 22264 44306 22308 44306 22308 44307 22264 44307 22266 44307 22308 44308 22266 44308 22348 44308 22348 44309 22266 44309 22267 44309 22348 44310 22267 44310 22309 44310 22309 44311 22267 44311 22269 44311 22309 44312 22269 44312 22311 44312 22311 44313 22269 44313 22310 44313 22311 44314 22310 44314 22345 44314 22345 44315 22310 44315 22312 44315 22345 44316 22312 44316 22344 44316 22344 44317 22312 44317 22313 44317 22344 44318 22313 44318 22343 44318 22343 44319 22313 44319 22315 44319 22343 44320 22315 44320 22314 44320 22314 44321 22315 44321 22316 44321 22314 44322 22316 44322 22317 44322 22317 44323 22316 44323 22273 44323 22317 44324 22273 44324 22340 44324 22340 44325 22273 44325 22318 44325 22340 44326 22318 44326 22339 44326 22339 44327 22318 44327 22319 44327 22339 44328 22319 44328 22320 44328 22320 44329 22319 44329 22322 44329 22320 44330 22322 44330 22321 44330 22321 44331 22322 44331 22275 44331 22321 44332 22275 44332 22323 44332 22323 44333 22275 44333 22277 44333 22323 44334 22277 44334 22336 44334 22336 44335 22277 44335 22279 44335 22336 44336 22279 44336 22334 44336 22334 44337 22279 44337 22324 44337 22334 44338 22324 44338 22325 44338 22325 44339 22324 44339 22280 44339 22325 44340 22280 44340 22326 44340 22326 44341 22280 44341 22281 44341 22326 44342 22281 44342 22327 44342 22327 44343 22281 44343 22328 44343 22327 44344 22328 44344 22329 44344 22329 44345 22328 44345 22285 44345 22329 44346 22285 44346 22331 44346 22331 44347 22285 44347 22330 44347 22331 44348 22330 44348 22332 44348 22332 44349 22330 44349 22287 44349 22332 44350 22287 44350 24623 44350 24623 44351 22287 44351 24657 44351 24623 44352 24622 44352 22332 44352 22332 44353 24622 44353 22403 44353 22332 44354 22403 44354 22331 44354 22331 44355 22403 44355 22408 44355 22331 44356 22408 44356 22329 44356 22329 44357 22408 44357 22407 44357 22329 44358 22407 44358 22327 44358 22327 44359 22407 44359 22409 44359 22327 44360 22409 44360 22326 44360 22326 44361 22409 44361 22414 44361 22326 44362 22414 44362 22325 44362 22325 44363 22414 44363 22333 44363 22325 44364 22333 44364 22334 44364 22334 44365 22333 44365 22335 44365 22334 44366 22335 44366 22336 44366 22336 44367 22335 44367 22337 44367 22336 44368 22337 44368 22323 44368 22323 44369 22337 44369 22421 44369 22323 44370 22421 44370 22321 44370 22321 44371 22421 44371 22338 44371 22321 44372 22338 44372 22320 44372 22320 44373 22338 44373 22432 44373 22320 44374 22432 44374 22339 44374 22339 44375 22432 44375 22433 44375 22339 44376 22433 44376 22340 44376 22340 44377 22433 44377 22434 44377 22340 44378 22434 44378 22317 44378 22317 44379 22434 44379 22341 44379 22317 44380 22341 44380 22314 44380 22314 44381 22341 44381 22342 44381 22314 44382 22342 44382 22343 44382 22343 44383 22342 44383 22437 44383 22343 44384 22437 44384 22344 44384 22344 44385 22437 44385 22438 44385 22344 44386 22438 44386 22345 44386 22345 44387 22438 44387 22346 44387 22345 44388 22346 44388 22311 44388 22311 44389 22346 44389 22347 44389 22311 44390 22347 44390 22309 44390 22309 44391 22347 44391 22441 44391 22309 44392 22441 44392 22348 44392 22348 44393 22441 44393 22442 44393 22348 44394 22442 44394 22308 44394 22308 44395 22442 44395 22446 44395 22308 44396 22446 44396 22349 44396 22349 44397 22446 44397 22350 44397 22349 44398 22350 44398 22351 44398 22351 44399 22350 44399 22450 44399 22351 44400 22450 44400 22305 44400 22305 44401 22450 44401 22452 44401 22305 44402 22452 44402 22352 44402 22352 44403 22452 44403 22453 44403 22352 44404 22453 44404 22302 44404 22302 44405 22453 44405 22454 44405 22302 44406 22454 44406 22300 44406 22300 44407 22454 44407 22353 44407 22300 44408 22353 44408 22299 44408 22299 44409 22353 44409 22465 44409 22299 44410 22465 44410 22298 44410 22298 44411 22465 44411 22469 44411 22298 44412 22469 44412 22297 44412 22297 44413 22469 44413 22354 44413 22297 44414 22354 44414 22295 44414 22295 44415 22354 44415 22470 44415 22295 44416 22470 44416 22355 44416 22355 44417 22470 44417 22472 44417 22355 44418 22472 44418 22356 44418 22356 44419 22472 44419 22357 44419 22356 44420 22357 44420 22293 44420 22293 44421 22357 44421 22394 44421 22293 44422 22394 44422 22358 44422 22358 44423 22394 44423 22395 44423 22358 44424 22395 44424 22292 44424 22292 44425 22395 44425 22359 44425 22292 44426 22359 44426 22290 44426 22290 44427 22359 44427 24912 44427 22290 44428 24912 44428 22360 44428 24659 44429 22361 44429 22228 44429 22228 44430 22361 44430 22363 44430 22361 44431 22362 44431 22363 44431 22363 44432 22362 44432 24667 44432 22363 44433 24667 44433 22229 44433 24671 44434 22365 44434 24672 44434 24672 44435 22365 44435 22229 44435 24672 44436 22229 44436 24666 44436 24666 44437 22229 44437 24667 44437 22364 44438 22366 44438 24678 44438 24678 44439 22366 44439 22365 44439 24678 44440 22365 44440 24676 44440 24676 44441 22365 44441 24671 44441 22364 44442 22367 44442 22366 44442 22366 44443 22367 44443 24677 44443 22366 44444 24677 44444 22368 44444 24677 44445 24682 44445 22368 44445 22368 44446 24682 44446 24685 44446 22368 44447 24685 44447 22232 44447 22369 44448 22370 44448 24687 44448 24687 44449 22370 44449 22232 44449 24687 44450 22232 44450 24684 44450 24684 44451 22232 44451 24685 44451 22369 44452 24617 44452 22370 44452 22370 44453 24617 44453 24688 44453 22370 44454 24688 44454 22372 44454 24688 44455 22371 44455 22372 44455 22372 44456 22371 44456 22373 44456 22372 44457 22373 44457 22374 44457 22373 44458 24689 44458 22374 44458 22374 44459 24689 44459 24691 44459 22374 44460 24691 44460 22235 44460 22375 44461 22236 44461 24693 44461 24693 44462 22236 44462 22235 44462 24693 44463 22235 44463 24692 44463 24692 44464 22235 44464 24691 44464 22375 44465 22376 44465 22236 44465 22236 44466 22376 44466 22377 44466 22236 44467 22377 44467 22378 44467 22377 44468 24703 44468 22378 44468 22378 44469 24703 44469 22379 44469 22378 44470 22379 44470 22240 44470 24656 44471 22380 44471 22381 44471 22381 44472 22380 44472 22240 44472 22381 44473 22240 44473 24702 44473 24702 44474 22240 44474 22379 44474 24656 44475 24706 44475 22380 44475 22380 44476 24706 44476 22382 44476 22380 44477 22382 44477 22242 44477 22384 44478 22385 44478 22383 44478 22383 44479 22385 44479 22242 44479 22383 44480 22242 44480 24709 44480 24709 44481 22242 44481 22382 44481 22384 44482 24718 44482 22385 44482 22385 44483 24718 44483 22388 44483 22385 44484 22388 44484 22387 44484 24712 44485 22386 44485 24714 44485 24714 44486 22386 44486 22387 44486 24714 44487 22387 44487 24715 44487 24715 44488 22387 44488 22388 44488 24914 44489 24912 44489 22359 44489 22389 44490 24779 44490 22390 44490 22390 44491 24779 44491 24778 44491 22390 44492 24778 44492 24487 44492 24778 44493 22391 44493 24487 44493 24487 44494 22391 44494 22172 44494 24487 44495 22172 44495 24486 44495 24486 44496 22172 44496 22173 44496 24486 44497 22173 44497 22175 44497 22392 44498 22177 44498 22394 44498 22394 44499 22177 44499 22393 44499 22394 44500 22393 44500 22395 44500 22395 44501 22393 44501 24775 44501 24775 44502 22396 44502 22395 44502 22395 44503 22396 44503 24777 44503 22395 44504 24777 44504 22397 44504 24914 44505 22359 44505 24916 44505 24918 44506 22398 44506 22399 44506 22399 44507 22398 44507 22401 44507 22399 44508 22401 44508 22400 44508 22400 44509 22401 44509 24921 44509 22389 44510 22390 44510 22401 44510 22401 44511 22390 44511 24922 44511 22401 44512 24922 44512 24921 44512 22397 44513 22398 44513 22395 44513 22395 44514 22398 44514 24918 44514 22395 44515 24918 44515 22359 44515 22359 44516 24918 44516 22402 44516 22359 44517 22402 44517 24916 44517 24622 44518 24934 44518 22403 44518 22403 44519 24934 44519 24933 44519 22403 44520 24933 44520 22408 44520 22408 44521 24933 44521 22404 44521 22408 44522 22404 44522 22405 44522 22405 44523 24930 44523 22408 44523 22408 44524 24930 44524 24929 44524 22408 44525 24929 44525 24928 44525 24923 44526 24480 44526 24924 44526 24924 44527 24480 44527 24927 44527 24814 44528 22408 44528 24480 44528 24480 44529 22408 44529 24928 44529 24480 44530 24928 44530 24927 44530 22406 44531 22407 44531 24817 44531 24817 44532 22407 44532 22408 44532 24817 44533 22408 44533 24816 44533 24816 44534 22408 44534 24814 44534 22406 44535 24819 44535 22407 44535 22407 44536 24819 44536 22410 44536 22407 44537 22410 44537 22409 44537 22409 44538 22410 44538 22131 44538 22138 44539 24478 44539 22411 44539 22411 44540 24478 44540 22412 44540 22411 44541 22412 44541 22135 44541 22135 44542 22412 44542 22133 44542 22138 44543 22140 44543 24478 44543 24478 44544 22140 44544 22413 44544 24478 44545 22413 44545 24480 44545 24480 44546 22413 44546 24812 44546 24480 44547 24812 44547 24814 44547 22131 44548 22133 44548 22409 44548 22409 44549 22133 44549 22412 44549 22409 44550 22412 44550 22414 44550 22414 44551 22412 44551 24477 44551 22414 44552 24477 44552 22333 44552 22333 44553 24477 44553 24475 44553 22333 44554 24475 44554 22335 44554 22335 44555 24475 44555 24474 44555 22335 44556 24474 44556 22337 44556 22337 44557 24474 44557 24473 44557 22421 44558 22422 44558 24809 44558 22421 44559 24809 44559 22338 44559 22145 44560 22415 44560 22418 44560 24809 44561 24811 44561 22338 44561 22338 44562 24811 44562 22416 44562 22338 44563 22416 44563 22143 44563 22415 44564 22147 44564 22418 44564 22418 44565 22147 44565 22417 44565 22418 44566 22417 44566 24471 44566 24471 44567 22417 44567 22150 44567 24471 44568 22150 44568 24473 44568 22150 44569 22419 44569 24473 44569 24473 44570 22419 44570 22420 44570 24473 44571 22420 44571 22337 44571 22337 44572 22420 44572 24806 44572 22337 44573 24806 44573 22421 44573 22421 44574 24806 44574 24807 44574 22421 44575 24807 44575 22422 44575 24800 44576 22438 44576 22428 44576 22428 44577 22438 44577 22437 44577 22151 44578 22425 44578 22439 44578 22439 44579 22425 44579 24463 44579 22429 44580 22423 44580 22424 44580 22424 44581 22423 44581 24463 44581 22424 44582 24463 44582 22152 44582 22152 44583 24463 44583 22425 44583 24797 44584 22426 44584 22437 44584 22437 44585 22426 44585 22427 44585 22437 44586 22427 44586 22428 44586 22429 44587 22430 44587 22423 44587 22423 44588 22430 44588 22155 44588 22423 44589 22155 44589 22431 44589 22143 44590 22145 44590 22338 44590 22338 44591 22145 44591 22418 44591 22338 44592 22418 44592 22432 44592 22432 44593 22418 44593 24469 44593 22432 44594 24469 44594 22433 44594 22433 44595 24469 44595 24468 44595 22433 44596 24468 44596 22434 44596 22434 44597 24468 44597 22435 44597 22434 44598 22435 44598 22341 44598 22341 44599 22435 44599 24465 44599 22341 44600 24465 44600 22342 44600 22342 44601 24465 44601 22436 44601 22342 44602 22436 44602 22437 44602 22437 44603 22436 44603 22423 44603 22437 44604 22423 44604 24797 44604 24797 44605 22423 44605 22431 44605 24800 44606 24802 44606 22438 44606 22438 44607 24802 44607 22151 44607 22438 44608 22151 44608 22346 44608 22346 44609 22151 44609 22439 44609 22346 44610 22439 44610 22347 44610 22347 44611 22439 44611 22440 44611 22347 44612 22440 44612 22441 44612 22441 44613 22440 44613 24459 44613 22441 44614 24459 44614 22442 44614 22442 44615 24459 44615 24458 44615 22442 44616 24458 44616 22446 44616 22446 44617 24458 44617 24456 44617 24796 44618 22158 44618 24453 44618 24453 44619 22158 44619 24455 44619 24455 44620 22158 44620 22443 44620 24455 44621 22443 44621 22160 44621 22160 44622 22157 44622 24455 44622 24455 44623 22157 44623 22156 44623 24455 44624 22156 44624 24456 44624 24456 44625 22156 44625 22161 44625 24456 44626 22161 44626 22444 44626 22444 44627 22163 44627 24456 44627 24456 44628 22163 44628 22445 44628 24456 44629 22445 44629 22446 44629 22446 44630 22445 44630 22165 44630 22446 44631 22165 44631 24790 44631 24790 44632 24793 44632 22446 44632 22446 44633 24793 44633 22447 44633 22446 44634 22447 44634 22350 44634 22350 44635 22447 44635 22448 44635 22350 44636 22448 44636 22450 44636 22450 44637 22448 44637 22449 44637 22449 44638 24796 44638 22450 44638 22450 44639 24796 44639 24453 44639 22450 44640 24453 44640 22452 44640 22452 44641 24453 44641 22451 44641 22452 44642 22451 44642 22453 44642 22453 44643 22451 44643 24452 44643 22453 44644 24452 44644 22454 44644 22454 44645 24452 44645 24451 44645 22454 44646 24451 44646 22353 44646 22353 44647 24451 44647 22463 44647 22465 44648 22455 44648 24782 44648 22465 44649 24782 44649 22469 44649 22469 44650 24782 44650 22456 44650 22469 44651 22456 44651 24784 44651 24787 44652 24788 44652 22468 44652 22468 44653 24788 44653 22457 44653 22468 44654 22457 44654 22461 44654 22461 44655 22457 44655 22458 44655 22461 44656 22458 44656 22459 44656 22459 44657 22460 44657 22461 44657 22461 44658 22460 44658 22462 44658 22461 44659 22462 44659 22463 44659 22463 44660 22462 44660 22168 44660 22168 44661 22170 44661 22463 44661 22463 44662 22170 44662 22464 44662 22463 44663 22464 44663 22353 44663 22353 44664 22464 44664 22466 44664 22353 44665 22466 44665 22465 44665 22465 44666 22466 44666 22467 44666 22465 44667 22467 44667 22455 44667 24784 44668 24787 44668 22469 44668 22469 44669 24787 44669 22468 44669 22469 44670 22468 44670 22354 44670 22354 44671 22468 44671 24482 44671 22354 44672 24482 44672 22470 44672 22470 44673 24482 44673 24484 44673 22470 44674 24484 44674 22472 44674 22472 44675 24484 44675 22471 44675 22472 44676 22471 44676 22357 44676 22357 44677 22471 44677 24486 44677 22357 44678 24486 44678 22394 44678 22394 44679 24486 44679 22175 44679 22394 44680 22175 44680 22392 44680 24313 44681 24314 44681 22474 44681 22474 44682 24314 44682 22473 44682 22474 44683 22473 44683 22475 44683 22475 44684 22473 44684 22476 44684 22475 44685 22476 44685 22477 44685 22477 44686 22476 44686 24150 44686 22477 44687 24150 44687 22478 44687 22478 44688 24150 44688 24149 44688 22478 44689 24149 44689 22224 44689 22224 44690 24149 44690 24148 44690 22224 44691 24148 44691 22221 44691 22221 44692 24148 44692 24155 44692 22221 44693 24155 44693 22220 44693 22220 44694 24155 44694 22479 44694 22220 44695 22479 44695 22219 44695 22219 44696 22479 44696 24157 44696 22219 44697 24157 44697 22480 44697 22480 44698 24157 44698 24159 44698 22480 44699 24159 44699 22481 44699 22481 44700 24159 44700 24160 44700 22481 44701 24160 44701 22483 44701 22483 44702 24160 44702 22482 44702 22483 44703 22482 44703 22484 44703 22484 44704 22482 44704 24147 44704 22484 44705 24147 44705 22485 44705 22485 44706 24147 44706 22486 44706 22485 44707 22486 44707 22487 44707 22487 44708 22486 44708 22488 44708 22487 44709 22488 44709 22217 44709 22217 44710 22488 44710 24295 44710 24133 44711 23184 44711 23170 44711 23199 44712 23184 44712 24133 44712 24135 44713 23199 44713 24133 44713 24133 44714 23177 44714 23179 44714 23175 44715 23177 44715 24133 44715 23170 44716 23175 44716 24133 44716 22489 44717 22490 44717 23169 44717 23173 44718 22490 44718 22489 44718 24130 44719 23173 44719 22489 44719 22489 44720 23183 44720 23182 44720 23167 44721 23183 44721 22489 44721 23169 44722 23167 44722 22489 44722 24126 44723 23186 44723 22492 44723 24126 44724 22491 44724 23171 44724 23187 44725 22491 44725 24126 44725 22492 44726 23187 44726 24126 44726 24126 44727 23174 44727 23172 44727 22493 44728 23174 44728 24126 44728 23171 44729 22493 44729 24126 44729 24121 44730 22494 44730 23178 44730 22496 44731 22494 44731 24121 44731 22495 44732 22496 44732 24121 44732 24121 44733 23193 44733 23195 44733 23192 44734 23193 44734 24121 44734 23178 44735 23192 44735 24121 44735 27255 44736 23215 44736 23214 44736 27255 44737 23214 44737 27254 44737 27254 44738 23214 44738 22497 44738 27254 44739 22497 44739 22498 44739 22498 44740 22497 44740 23211 44740 22498 44741 23211 44741 27253 44741 27253 44742 23211 44742 23209 44742 27253 44743 23209 44743 22499 44743 22499 44744 23209 44744 24109 44744 22499 44745 24109 44745 22500 44745 24115 44746 22980 44746 22979 44746 24115 44747 22979 44747 22501 44747 22501 44748 22979 44748 22977 44748 22501 44749 22977 44749 27243 44749 27243 44750 22977 44750 22502 44750 27243 44751 22502 44751 27241 44751 27241 44752 22502 44752 22975 44752 27241 44753 22975 44753 22503 44753 22503 44754 22975 44754 22974 44754 22503 44755 22974 44755 27239 44755 27239 44756 22974 44756 22504 44756 27239 44757 22504 44757 22505 44757 22505 44758 22504 44758 22506 44758 22505 44759 22506 44759 27232 44759 27232 44760 22506 44760 22507 44760 27232 44761 22507 44761 27231 44761 27231 44762 22507 44762 22508 44762 27231 44763 22508 44763 27230 44763 27230 44764 22508 44764 22973 44764 27230 44765 22973 44765 27227 44765 27227 44766 22973 44766 22972 44766 27227 44767 22972 44767 22509 44767 22509 44768 22972 44768 22970 44768 22509 44769 22970 44769 22510 44769 22510 44770 22970 44770 22511 44770 22510 44771 22511 44771 27259 44771 27259 44772 22511 44772 22512 44772 27259 44773 22512 44773 22513 44773 22513 44774 22512 44774 22966 44774 22513 44775 22966 44775 22514 44775 22514 44776 22966 44776 23215 44776 22514 44777 23215 44777 27255 44777 22515 44778 24057 44778 23826 44778 22515 44779 23826 44779 22516 44779 22516 44780 23826 44780 23217 44780 22516 44781 23217 44781 22517 44781 22517 44782 23217 44782 22518 44782 22517 44783 22518 44783 22519 44783 22518 44784 23218 44784 22519 44784 22519 44785 23218 44785 23220 44785 22519 44786 23220 44786 22520 44786 22520 44787 23220 44787 23221 44787 22520 44788 23221 44788 23079 44788 23079 44789 23221 44789 22521 44789 23079 44790 22521 44790 24060 44790 23087 44791 22522 44791 22523 44791 23087 44792 22523 44792 23076 44792 23076 44793 22523 44793 22964 44793 23076 44794 22964 44794 22524 44794 22524 44795 22964 44795 22525 44795 22524 44796 22525 44796 23081 44796 23081 44797 22525 44797 22526 44797 23081 44798 22526 44798 23067 44798 23067 44799 22526 44799 24044 44799 23067 44800 24044 44800 22527 44800 22969 44801 22533 44801 22968 44801 22968 44802 22533 44802 22528 44802 22968 44803 22528 44803 22967 44803 22967 44804 22528 44804 23150 44804 22967 44805 23150 44805 23216 44805 22538 44806 22529 44806 22971 44806 22971 44807 22529 44807 22530 44807 22971 44808 22530 44808 22531 44808 22531 44809 22530 44809 22532 44809 22531 44810 22532 44810 22969 44810 22969 44811 22532 44811 23141 44811 22969 44812 23141 44812 22533 44812 22542 44813 23122 44813 22534 44813 22534 44814 23122 44814 23123 44814 22534 44815 23123 44815 22535 44815 22535 44816 23123 44816 23119 44816 22535 44817 23119 44817 22536 44817 22536 44818 23119 44818 22537 44818 22536 44819 22537 44819 22538 44819 22538 44820 22537 44820 22539 44820 22538 44821 22539 44821 22529 44821 22544 44822 23097 44822 22976 44822 22976 44823 23097 44823 22540 44823 22976 44824 22540 44824 22541 44824 22541 44825 22540 44825 23105 44825 22541 44826 23105 44826 22542 44826 22542 44827 23105 44827 23117 44827 22542 44828 23117 44828 23122 44828 23090 44829 22543 44829 22544 44829 22544 44830 22543 44830 22545 44830 22544 44831 22545 44831 23097 44831 22544 44832 22546 44832 23090 44832 23090 44833 22546 44833 22978 44833 23090 44834 22978 44834 22547 44834 22547 44835 22978 44835 22522 44835 22547 44836 22522 44836 23087 44836 23836 44837 23837 44837 22548 44837 22548 44838 23837 44838 24006 44838 22555 44839 23984 44839 22557 44839 22557 44840 23984 44840 23347 44840 22557 44841 23347 44841 22559 44841 22559 44842 23347 44842 23344 44842 22559 44843 23344 44843 22560 44843 22560 44844 23344 44844 22550 44844 22560 44845 22550 44845 22549 44845 22549 44846 22550 44846 22552 44846 22549 44847 22552 44847 22551 44847 22551 44848 22552 44848 23345 44848 22551 44849 23345 44849 22563 44849 22563 44850 23345 44850 22553 44850 22563 44851 22553 44851 23978 44851 23978 44852 22553 44852 22554 44852 22565 44853 22555 44853 22556 44853 22556 44854 22555 44854 22557 44854 22556 44855 22557 44855 22558 44855 22558 44856 22557 44856 22559 44856 22558 44857 22559 44857 22566 44857 22566 44858 22559 44858 22560 44858 22566 44859 22560 44859 22567 44859 22567 44860 22560 44860 22549 44860 22567 44861 22549 44861 22561 44861 22561 44862 22549 44862 22551 44862 22561 44863 22551 44863 22562 44863 22562 44864 22551 44864 22563 44864 22562 44865 22563 44865 22564 44865 22564 44866 22563 44866 23978 44866 23971 44867 22565 44867 22556 44867 23971 44868 22566 44868 22567 44868 22558 44869 22566 44869 23971 44869 22556 44870 22558 44870 23971 44870 23971 44871 22562 44871 22564 44871 22561 44872 22562 44872 23971 44872 22567 44873 22561 44873 23971 44873 22571 44874 23969 44874 22572 44874 22572 44875 23969 44875 23375 44875 22572 44876 23375 44876 22573 44876 22573 44877 23375 44877 23373 44877 22573 44878 23373 44878 22576 44878 22576 44879 23373 44879 22568 44879 22576 44880 22568 44880 22569 44880 22569 44881 22568 44881 22570 44881 22569 44882 22570 44882 22579 44882 22579 44883 22570 44883 23372 44883 22579 44884 23372 44884 23954 44884 23954 44885 23372 44885 23964 44885 23963 44886 22571 44886 22581 44886 22581 44887 22571 44887 22572 44887 22581 44888 22572 44888 22574 44888 22574 44889 22572 44889 22573 44889 22574 44890 22573 44890 22575 44890 22575 44891 22573 44891 22576 44891 22575 44892 22576 44892 22577 44892 22577 44893 22576 44893 22569 44893 22577 44894 22569 44894 22578 44894 22578 44895 22569 44895 22579 44895 22578 44896 22579 44896 22580 44896 22580 44897 22579 44897 23954 44897 23947 44898 22574 44898 22575 44898 22581 44899 22574 44899 23947 44899 23963 44900 22581 44900 23947 44900 23947 44901 22578 44901 22580 44901 22577 44902 22578 44902 23947 44902 22575 44903 22577 44903 23947 44903 22589 44904 23346 44904 22591 44904 22591 44905 23346 44905 23363 44905 22591 44906 23363 44906 22582 44906 22582 44907 23363 44907 23361 44907 22582 44908 23361 44908 22583 44908 22583 44909 23361 44909 23360 44909 22583 44910 23360 44910 22584 44910 22584 44911 23360 44911 22585 44911 22584 44912 22585 44912 22593 44912 22593 44913 22585 44913 22586 44913 22593 44914 22586 44914 22596 44914 22596 44915 22586 44915 22587 44915 22596 44916 22587 44916 23933 44916 23933 44917 22587 44917 23942 44917 23940 44918 22589 44918 22588 44918 22588 44919 22589 44919 22591 44919 22588 44920 22591 44920 22590 44920 22590 44921 22591 44921 22582 44921 22590 44922 22582 44922 22592 44922 22592 44923 22582 44923 22583 44923 22592 44924 22583 44924 22598 44924 22598 44925 22583 44925 22584 44925 22598 44926 22584 44926 22599 44926 22599 44927 22584 44927 22593 44927 22599 44928 22593 44928 22594 44928 22594 44929 22593 44929 22596 44929 22594 44930 22596 44930 22595 44930 22595 44931 22596 44931 23933 44931 22597 44932 23940 44932 22588 44932 22597 44933 22592 44933 22598 44933 22590 44934 22592 44934 22597 44934 22588 44935 22590 44935 22597 44935 22597 44936 22594 44936 22595 44936 22599 44937 22594 44937 22597 44937 22598 44938 22599 44938 22597 44938 22600 44939 22601 44939 22684 44939 23313 44940 23319 44940 22691 44940 22687 44941 23313 44941 22688 44941 22655 44942 22647 44942 23315 44942 23315 44943 22647 44943 23879 44943 23320 44944 22601 44944 22602 44944 22602 44945 22601 44945 22600 44945 22602 44946 22600 44946 22683 44946 22690 44947 22684 44947 22689 44947 22689 44948 22684 44948 22601 44948 22689 44949 22601 44949 22603 44949 22603 44950 22601 44950 23320 44950 22603 44951 23320 44951 22687 44951 22646 44952 22605 44952 22604 44952 22604 44953 22605 44953 22606 44953 22604 44954 22606 44954 22647 44954 22647 44955 22606 44955 23928 44955 22647 44956 23928 44956 23879 44956 22654 44957 22649 44957 22609 44957 22658 44958 22607 44958 22656 44958 22656 44959 22607 44959 22654 44959 22656 44960 22654 44960 22608 44960 22608 44961 22654 44961 22609 44961 22608 44962 22609 44962 22648 44962 23312 44963 23310 44963 22610 44963 22610 44964 23310 44964 22659 44964 22610 44965 22659 44965 22611 44965 22611 44966 22659 44966 22612 44966 22611 44967 22612 44967 22613 44967 22613 44968 22612 44968 22661 44968 22614 44969 23309 44969 22616 44969 22616 44970 23309 44970 22615 44970 22616 44971 22615 44971 22660 44971 22660 44972 22615 44972 22617 44972 22660 44973 22617 44973 22618 44973 22618 44974 22617 44974 22664 44974 22618 44975 22664 44975 22619 44975 22619 44976 22664 44976 22620 44976 23306 44977 22623 44977 22662 44977 22662 44978 22623 44978 22621 44978 22662 44979 22621 44979 22663 44979 22663 44980 22621 44980 22625 44980 22663 44981 22625 44981 22622 44981 22622 44982 22625 44982 22627 44982 22623 44983 22624 44983 22621 44983 22621 44984 22624 44984 22666 44984 22621 44985 22666 44985 22625 44985 22625 44986 22666 44986 22626 44986 22625 44987 22626 44987 22627 44987 22627 44988 22626 44988 22628 44988 22627 44989 22628 44989 22629 44989 22629 44990 22628 44990 23050 44990 22630 44991 22632 44991 22631 44991 22631 44992 22632 44992 22669 44992 22631 44993 22669 44993 22633 44993 22633 44994 22669 44994 22635 44994 22633 44995 22635 44995 22634 44995 22634 44996 22635 44996 22671 44996 23323 44997 22636 44997 22670 44997 22670 44998 22636 44998 22637 44998 22670 44999 22637 44999 22638 44999 22638 45000 22637 45000 22675 45000 22638 45001 22675 45001 22639 45001 22639 45002 22675 45002 22640 45002 22639 45003 22640 45003 23045 45003 23045 45004 22640 45004 22677 45004 22641 45005 23322 45005 22673 45005 22673 45006 23322 45006 22642 45006 22673 45007 22642 45007 22674 45007 22674 45008 22642 45008 22643 45008 22674 45009 22643 45009 22676 45009 22676 45010 22643 45010 22679 45010 23322 45011 22681 45011 22642 45011 22642 45012 22681 45012 22682 45012 22642 45013 22682 45013 22643 45013 22643 45014 22682 45014 22644 45014 22643 45015 22644 45015 22679 45015 22679 45016 22644 45016 22645 45016 22679 45017 22645 45017 22678 45017 22678 45018 22645 45018 22685 45018 22604 45019 22651 45019 22646 45019 22646 45020 22651 45020 23063 45020 22646 45021 23063 45021 22981 45021 22655 45022 22648 45022 22647 45022 22647 45023 22648 45023 22609 45023 22647 45024 22609 45024 22604 45024 22604 45025 22609 45025 22649 45025 22604 45026 22649 45026 22651 45026 22651 45027 22649 45027 22650 45027 22651 45028 22650 45028 23063 45028 22607 45029 22652 45029 22654 45029 22654 45030 22652 45030 22653 45030 22654 45031 22653 45031 22649 45031 22649 45032 22653 45032 23061 45032 22649 45033 23061 45033 22650 45033 22655 45034 23312 45034 22648 45034 22648 45035 23312 45035 22610 45035 22648 45036 22610 45036 22608 45036 22608 45037 22610 45037 22611 45037 22608 45038 22611 45038 22656 45038 22656 45039 22611 45039 22613 45039 22656 45040 22613 45040 22658 45040 23056 45041 23059 45041 22661 45041 22661 45042 23059 45042 22657 45042 22661 45043 22657 45043 22613 45043 22613 45044 22657 45044 23057 45044 22613 45045 23057 45045 22658 45045 23310 45046 22614 45046 22659 45046 22659 45047 22614 45047 22616 45047 22659 45048 22616 45048 22612 45048 22612 45049 22616 45049 22660 45049 22612 45050 22660 45050 22661 45050 22661 45051 22660 45051 22618 45051 22661 45052 22618 45052 23056 45052 23056 45053 22618 45053 22619 45053 23309 45054 23306 45054 22615 45054 22615 45055 23306 45055 22662 45055 22615 45056 22662 45056 22617 45056 22617 45057 22662 45057 22663 45057 22617 45058 22663 45058 22664 45058 22664 45059 22663 45059 22622 45059 22664 45060 22622 45060 22620 45060 22629 45061 23054 45061 22627 45061 22627 45062 23054 45062 22665 45062 22627 45063 22665 45063 22622 45063 22622 45064 22665 45064 23053 45064 22622 45065 23053 45065 22620 45065 22624 45066 22630 45066 22666 45066 22666 45067 22630 45067 22631 45067 22666 45068 22631 45068 22626 45068 22626 45069 22631 45069 22633 45069 22626 45070 22633 45070 22628 45070 22628 45071 22633 45071 22634 45071 22628 45072 22634 45072 23050 45072 22672 45073 22667 45073 22671 45073 22671 45074 22667 45074 22668 45074 22671 45075 22668 45075 22634 45075 22634 45076 22668 45076 23049 45076 22634 45077 23049 45077 23050 45077 22632 45078 23323 45078 22669 45078 22669 45079 23323 45079 22670 45079 22669 45080 22670 45080 22635 45080 22635 45081 22670 45081 22638 45081 22635 45082 22638 45082 22671 45082 22671 45083 22638 45083 22639 45083 22671 45084 22639 45084 22672 45084 22672 45085 22639 45085 23045 45085 22636 45086 22641 45086 22637 45086 22637 45087 22641 45087 22673 45087 22637 45088 22673 45088 22675 45088 22675 45089 22673 45089 22674 45089 22675 45090 22674 45090 22640 45090 22640 45091 22674 45091 22676 45091 22640 45092 22676 45092 22677 45092 22678 45093 23043 45093 22679 45093 22679 45094 23043 45094 23044 45094 22679 45095 23044 45095 22676 45095 22676 45096 23044 45096 22680 45096 22676 45097 22680 45097 22677 45097 22681 45098 22683 45098 22682 45098 22682 45099 22683 45099 22600 45099 22682 45100 22600 45100 22644 45100 22644 45101 22600 45101 22684 45101 22644 45102 22684 45102 22645 45102 22645 45103 22684 45103 22690 45103 22645 45104 22690 45104 22685 45104 22685 45105 22690 45105 22686 45105 22694 45106 23040 45106 23041 45106 22687 45107 22688 45107 22603 45107 22603 45108 22688 45108 22692 45108 22603 45109 22692 45109 22689 45109 22689 45110 22692 45110 22694 45110 22689 45111 22694 45111 22690 45111 22690 45112 22694 45112 23041 45112 22690 45113 23041 45113 22686 45113 23313 45114 22691 45114 22688 45114 22688 45115 22691 45115 22693 45115 22688 45116 22693 45116 22692 45116 22692 45117 22693 45117 23892 45117 22692 45118 23892 45118 22694 45118 22694 45119 23892 45119 22695 45119 22694 45120 22695 45120 23040 45120 23857 45121 23856 45121 22949 45121 23857 45122 22949 45122 22696 45122 22696 45123 22949 45123 22698 45123 22696 45124 22698 45124 22697 45124 22697 45125 22698 45125 22699 45125 22697 45126 22699 45126 22700 45126 22700 45127 22699 45127 22947 45127 22700 45128 22947 45128 23336 45128 23336 45129 22947 45129 22701 45129 23336 45130 22701 45130 23334 45130 23334 45131 22701 45131 22702 45131 23334 45132 22702 45132 23333 45132 23333 45133 22702 45133 22940 45133 23333 45134 22940 45134 22703 45134 22703 45135 22940 45135 22942 45135 22703 45136 22942 45136 23331 45136 23331 45137 22942 45137 22935 45137 23331 45138 22935 45138 22704 45138 22704 45139 22935 45139 22937 45139 22704 45140 22937 45140 23329 45140 23329 45141 22937 45141 22953 45141 23329 45142 22953 45142 23327 45142 23327 45143 22953 45143 22705 45143 23327 45144 22705 45144 23326 45144 23326 45145 22705 45145 22955 45145 23326 45146 22955 45146 23318 45146 23318 45147 22955 45147 22706 45147 23318 45148 22706 45148 22707 45148 22707 45149 22706 45149 22708 45149 22707 45150 22708 45150 23316 45150 22709 45151 22711 45151 22710 45151 22710 45152 22711 45152 22712 45152 22714 45153 23147 45153 22713 45153 22713 45154 22729 45154 22714 45154 22714 45155 22729 45155 22730 45155 22714 45156 22730 45156 22715 45156 22730 45157 22716 45157 22715 45157 22715 45158 22716 45158 22727 45158 22715 45159 22727 45159 23148 45159 22727 45160 22717 45160 23148 45160 23148 45161 22717 45161 22726 45161 23148 45162 22726 45162 22718 45162 22718 45163 22726 45163 22725 45163 22718 45164 22725 45164 22719 45164 22725 45165 22724 45165 22719 45165 22719 45166 22724 45166 22723 45166 22719 45167 22723 45167 23149 45167 23787 45168 23144 45168 22720 45168 22720 45169 23144 45169 23149 45169 22720 45170 23149 45170 22721 45170 22721 45171 23149 45171 22723 45171 23787 45172 22720 45172 22722 45172 22722 45173 22720 45173 22734 45173 22720 45174 22721 45174 22734 45174 22734 45175 22721 45175 22723 45175 22734 45176 22723 45176 22733 45176 22723 45177 22724 45177 22733 45177 22733 45178 22724 45178 22725 45178 22733 45179 22725 45179 22732 45179 22725 45180 22726 45180 22732 45180 22732 45181 22726 45181 22717 45181 22732 45182 22717 45182 22731 45182 22717 45183 22727 45183 22731 45183 22731 45184 22727 45184 22716 45184 22731 45185 22716 45185 22728 45185 22713 45186 23774 45186 22729 45186 22729 45187 23774 45187 22728 45187 22729 45188 22728 45188 22730 45188 22730 45189 22728 45189 22716 45189 23774 45190 23776 45190 22728 45190 22728 45191 23776 45191 27286 45191 22728 45192 27286 45192 22731 45192 22731 45193 27286 45193 27288 45193 22731 45194 27288 45194 22732 45194 22732 45195 27288 45195 27289 45195 22732 45196 27289 45196 22733 45196 22733 45197 27289 45197 27276 45197 22733 45198 27276 45198 22734 45198 22734 45199 27276 45199 22735 45199 22734 45200 22735 45200 22722 45200 22722 45201 22735 45201 22736 45201 22738 45202 23766 45202 22737 45202 22737 45203 22754 45203 22738 45203 22738 45204 22754 45204 22739 45204 22738 45205 22739 45205 23140 45205 22739 45206 22753 45206 23140 45206 23140 45207 22753 45207 22752 45207 23140 45208 22752 45208 22740 45208 22752 45209 22741 45209 22740 45209 22740 45210 22741 45210 22742 45210 22740 45211 22742 45211 22743 45211 22743 45212 22742 45212 22751 45212 22743 45213 22751 45213 22744 45213 22751 45214 22750 45214 22744 45214 22744 45215 22750 45215 22747 45215 22744 45216 22747 45216 22746 45216 23764 45217 23138 45217 22748 45217 22748 45218 23138 45218 22746 45218 22748 45219 22746 45219 22745 45219 22745 45220 22746 45220 22747 45220 23764 45221 22748 45221 23749 45221 23749 45222 22748 45222 22749 45222 22748 45223 22745 45223 22749 45223 22749 45224 22745 45224 22747 45224 22749 45225 22747 45225 22760 45225 22747 45226 22750 45226 22760 45226 22760 45227 22750 45227 22751 45227 22760 45228 22751 45228 22759 45228 22751 45229 22742 45229 22759 45229 22759 45230 22742 45230 22741 45230 22759 45231 22741 45231 22757 45231 22741 45232 22752 45232 22757 45232 22757 45233 22752 45233 22753 45233 22757 45234 22753 45234 22755 45234 22737 45235 23756 45235 22754 45235 22754 45236 23756 45236 22755 45236 22754 45237 22755 45237 22739 45237 22739 45238 22755 45238 22753 45238 23756 45239 23757 45239 22755 45239 22755 45240 23757 45240 22756 45240 22755 45241 22756 45241 22757 45241 22757 45242 22756 45242 22758 45242 22757 45243 22758 45243 22759 45243 22759 45244 22758 45244 27313 45244 22759 45245 27313 45245 22760 45245 22760 45246 27313 45246 27306 45246 22760 45247 27306 45247 22749 45247 22749 45248 27306 45248 27307 45248 22749 45249 27307 45249 23749 45249 23749 45250 27307 45250 27309 45250 22761 45251 23748 45251 22769 45251 22769 45252 23748 45252 23129 45252 22769 45253 23129 45253 22762 45253 22762 45254 23129 45254 22763 45254 22762 45255 22763 45255 22773 45255 22773 45256 22763 45256 22764 45256 22773 45257 22764 45257 22765 45257 22765 45258 22764 45258 23128 45258 22765 45259 23128 45259 22766 45259 22766 45260 23128 45260 23127 45260 22766 45261 23127 45261 22767 45261 22767 45262 23127 45262 23743 45262 22776 45263 22761 45263 22768 45263 22768 45264 22761 45264 22769 45264 22768 45265 22769 45265 22770 45265 22770 45266 22769 45266 22771 45266 22771 45267 22769 45267 22762 45267 22771 45268 22762 45268 22772 45268 22772 45269 22762 45269 22777 45269 22777 45270 22762 45270 22773 45270 22777 45271 22773 45271 22779 45271 22779 45272 22773 45272 22780 45272 22780 45273 22773 45273 22765 45273 22780 45274 22765 45274 22782 45274 22782 45275 22765 45275 22774 45275 22774 45276 22765 45276 22766 45276 22774 45277 22766 45277 22785 45277 22785 45278 22766 45278 22775 45278 22775 45279 22766 45279 22767 45279 22775 45280 22767 45280 22783 45280 27334 45281 23730 45281 22776 45281 22776 45282 22768 45282 27334 45282 27334 45283 22768 45283 22770 45283 27334 45284 22770 45284 27335 45284 22770 45285 22771 45285 27335 45285 27335 45286 22771 45286 22772 45286 27335 45287 22772 45287 22778 45287 22772 45288 22777 45288 22778 45288 22778 45289 22777 45289 22779 45289 22778 45290 22779 45290 27327 45290 27327 45291 22779 45291 22780 45291 27327 45292 22780 45292 22781 45292 22780 45293 22782 45293 22781 45293 22781 45294 22782 45294 22774 45294 22781 45295 22774 45295 22784 45295 22783 45296 27329 45296 22775 45296 22775 45297 27329 45297 22784 45297 22775 45298 22784 45298 22785 45298 22785 45299 22784 45299 22774 45299 22786 45300 23729 45300 22794 45300 22794 45301 23729 45301 22787 45301 22794 45302 22787 45302 22788 45302 22788 45303 22787 45303 23118 45303 22788 45304 23118 45304 22796 45304 22796 45305 23118 45305 22790 45305 22796 45306 22790 45306 22789 45306 22789 45307 22790 45307 22791 45307 22789 45308 22791 45308 22792 45308 22792 45309 22791 45309 23121 45309 22792 45310 23121 45310 22793 45310 22793 45311 23121 45311 23116 45311 22805 45312 22786 45312 22804 45312 22804 45313 22786 45313 22794 45313 22804 45314 22794 45314 22795 45314 22795 45315 22794 45315 22788 45315 22795 45316 22788 45316 22803 45316 22803 45317 22788 45317 22796 45317 22803 45318 22796 45318 22800 45318 22800 45319 22796 45319 22789 45319 22800 45320 22789 45320 22798 45320 22798 45321 22789 45321 22792 45321 22798 45322 22792 45322 22797 45322 22797 45323 22792 45323 22793 45323 22797 45324 27351 45324 22798 45324 22798 45325 27351 45325 22799 45325 22798 45326 22799 45326 22800 45326 22800 45327 22799 45327 22801 45327 22800 45328 22801 45328 22803 45328 22803 45329 22801 45329 22802 45329 22803 45330 22802 45330 22795 45330 22795 45331 22802 45331 27344 45331 22795 45332 27344 45332 22804 45332 22804 45333 27344 45333 22806 45333 22804 45334 22806 45334 22805 45334 22805 45335 22806 45335 22807 45335 22812 45336 23109 45336 22813 45336 22813 45337 23109 45337 23108 45337 22813 45338 23108 45338 22814 45338 22814 45339 23108 45339 23107 45339 22814 45340 23107 45340 22816 45340 22816 45341 23107 45341 23106 45341 22816 45342 23106 45342 22809 45342 22809 45343 23106 45343 22808 45343 22809 45344 22808 45344 22821 45344 22821 45345 22808 45345 22810 45345 22821 45346 22810 45346 22823 45346 22823 45347 22810 45347 22811 45347 22823 45348 22811 45348 23699 45348 23699 45349 22811 45349 23705 45349 23704 45350 22812 45350 22813 45350 23704 45351 22813 45351 22825 45351 22825 45352 22813 45352 22814 45352 22825 45353 22814 45353 22826 45353 22826 45354 22814 45354 22815 45354 22815 45355 22814 45355 22816 45355 22815 45356 22816 45356 22817 45356 22817 45357 22816 45357 22818 45357 22818 45358 22816 45358 22809 45358 22818 45359 22809 45359 22819 45359 22819 45360 22809 45360 22820 45360 22820 45361 22809 45361 22821 45361 22820 45362 22821 45362 22822 45362 22822 45363 22821 45363 22823 45363 22822 45364 22823 45364 22827 45364 22827 45365 22823 45365 23699 45365 22827 45366 23699 45366 23698 45366 27372 45367 23704 45367 27370 45367 27370 45368 23704 45368 22825 45368 27370 45369 22825 45369 22824 45369 22824 45370 22825 45370 22826 45370 22826 45371 22815 45371 22824 45371 22824 45372 22815 45372 22817 45372 22824 45373 22817 45373 27369 45373 22817 45374 22818 45374 27369 45374 27369 45375 22818 45375 22819 45375 27369 45376 22819 45376 27379 45376 23698 45377 27377 45377 22827 45377 22827 45378 27377 45378 27378 45378 22827 45379 27378 45379 22822 45379 22822 45380 27378 45380 27379 45380 22822 45381 27379 45381 22820 45381 22820 45382 27379 45382 22819 45382 22832 45383 23084 45383 22833 45383 22833 45384 23084 45384 23083 45384 22833 45385 23083 45385 22835 45385 22835 45386 23083 45386 23092 45386 22835 45387 23092 45387 22836 45387 22836 45388 23092 45388 22829 45388 22836 45389 22829 45389 22828 45389 22828 45390 22829 45390 23096 45390 22828 45391 23096 45391 22831 45391 22831 45392 23096 45392 22830 45392 22831 45393 22830 45393 23689 45393 23689 45394 22830 45394 23690 45394 23688 45395 22832 45395 22842 45395 22842 45396 22832 45396 22833 45396 22842 45397 22833 45397 22834 45397 22834 45398 22833 45398 22835 45398 22834 45399 22835 45399 22840 45399 22840 45400 22835 45400 22836 45400 22840 45401 22836 45401 22838 45401 22838 45402 22836 45402 22828 45402 22838 45403 22828 45403 22837 45403 22837 45404 22828 45404 22831 45404 22837 45405 22831 45405 23677 45405 23677 45406 22831 45406 23689 45406 23677 45407 27403 45407 22837 45407 22837 45408 27403 45408 27405 45408 22837 45409 27405 45409 22838 45409 22838 45410 27405 45410 22839 45410 22838 45411 22839 45411 22840 45411 22840 45412 22839 45412 22841 45412 22840 45413 22841 45413 22834 45413 22834 45414 22841 45414 27393 45414 22834 45415 27393 45415 22842 45415 22842 45416 27393 45416 22843 45416 22842 45417 22843 45417 23688 45417 23688 45418 22843 45418 22844 45418 23667 45419 23078 45419 22851 45419 22851 45420 23078 45420 22845 45420 22851 45421 22845 45421 22855 45421 22855 45422 22845 45422 22846 45422 22855 45423 22846 45423 22847 45423 22847 45424 22846 45424 22848 45424 22847 45425 22848 45425 22857 45425 22857 45426 22848 45426 23077 45426 22857 45427 23077 45427 22850 45427 22850 45428 23077 45428 22849 45428 22850 45429 22849 45429 22860 45429 22860 45430 22849 45430 23668 45430 22861 45431 23667 45431 22862 45431 22862 45432 23667 45432 22851 45432 22862 45433 22851 45433 22852 45433 22852 45434 22851 45434 22853 45434 22853 45435 22851 45435 22855 45435 22853 45436 22855 45436 22854 45436 22854 45437 22855 45437 22856 45437 22856 45438 22855 45438 22847 45438 22856 45439 22847 45439 22867 45439 22867 45440 22847 45440 22868 45440 22868 45441 22847 45441 22857 45441 22868 45442 22857 45442 22869 45442 22869 45443 22857 45443 22858 45443 22858 45444 22857 45444 22850 45444 22858 45445 22850 45445 22872 45445 22872 45446 22850 45446 22859 45446 22859 45447 22850 45447 22860 45447 22859 45448 22860 45448 23657 45448 22863 45449 27427 45449 22861 45449 22861 45450 22862 45450 22863 45450 22863 45451 22862 45451 22852 45451 22863 45452 22852 45452 22864 45452 22852 45453 22853 45453 22864 45453 22864 45454 22853 45454 22854 45454 22864 45455 22854 45455 22865 45455 22854 45456 22856 45456 22865 45456 22865 45457 22856 45457 22867 45457 22865 45458 22867 45458 22866 45458 22866 45459 22867 45459 22868 45459 22866 45460 22868 45460 22870 45460 22868 45461 22869 45461 22870 45461 22870 45462 22869 45462 22858 45462 22870 45463 22858 45463 22871 45463 23657 45464 23658 45464 22859 45464 22859 45465 23658 45465 22871 45465 22859 45466 22871 45466 22872 45466 22872 45467 22871 45467 22858 45467 22876 45468 23072 45468 22877 45468 22877 45469 23072 45469 23070 45469 22877 45470 23070 45470 22873 45470 22873 45471 23070 45471 23068 45471 22873 45472 23068 45472 22878 45472 22878 45473 23068 45473 22874 45473 22878 45474 22874 45474 22879 45474 22879 45475 22874 45475 23066 45475 22879 45476 23066 45476 22881 45476 22881 45477 23066 45477 22875 45477 22881 45478 22875 45478 23639 45478 23639 45479 22875 45479 23648 45479 22889 45480 22876 45480 22888 45480 22888 45481 22876 45481 22877 45481 22888 45482 22877 45482 22886 45482 22886 45483 22877 45483 22873 45483 22886 45484 22873 45484 22885 45484 22885 45485 22873 45485 22878 45485 22885 45486 22878 45486 22880 45486 22880 45487 22878 45487 22879 45487 22880 45488 22879 45488 22884 45488 22884 45489 22879 45489 22881 45489 22884 45490 22881 45490 23630 45490 23630 45491 22881 45491 23639 45491 23630 45492 22882 45492 22884 45492 22884 45493 22882 45493 22883 45493 22884 45494 22883 45494 22880 45494 22880 45495 22883 45495 27463 45495 22880 45496 27463 45496 22885 45496 22885 45497 27463 45497 27455 45497 22885 45498 27455 45498 22886 45498 22886 45499 27455 45499 27456 45499 22886 45500 27456 45500 22888 45500 22888 45501 27456 45501 22887 45501 22888 45502 22887 45502 22889 45502 22889 45503 22887 45503 23638 45503 22890 45504 23238 45504 22891 45504 22891 45505 23238 45505 22892 45505 22891 45506 22892 45506 22901 45506 22901 45507 22892 45507 22893 45507 22901 45508 22893 45508 22894 45508 22894 45509 22893 45509 22895 45509 22894 45510 22895 45510 22904 45510 22904 45511 22895 45511 23243 45511 22904 45512 23243 45512 22908 45512 22908 45513 23243 45513 23241 45513 22908 45514 23241 45514 22909 45514 22909 45515 23241 45515 22896 45515 22909 45516 22896 45516 22911 45516 22911 45517 22896 45517 22897 45517 22898 45518 22890 45518 22891 45518 22898 45519 22891 45519 22899 45519 22899 45520 22891 45520 22901 45520 22899 45521 22901 45521 22900 45521 22900 45522 22901 45522 22902 45522 22902 45523 22901 45523 22894 45523 22902 45524 22894 45524 22913 45524 22913 45525 22894 45525 22903 45525 22903 45526 22894 45526 22904 45526 22903 45527 22904 45527 22905 45527 22905 45528 22904 45528 22906 45528 22906 45529 22904 45529 22908 45529 22906 45530 22908 45530 22907 45530 22907 45531 22908 45531 22909 45531 22907 45532 22909 45532 22910 45532 22910 45533 22909 45533 22911 45533 22910 45534 22911 45534 22916 45534 27484 45535 22898 45535 22912 45535 22912 45536 22898 45536 22899 45536 22912 45537 22899 45537 27482 45537 27482 45538 22899 45538 22900 45538 22900 45539 22902 45539 27482 45539 27482 45540 22902 45540 22913 45540 27482 45541 22913 45541 22914 45541 22913 45542 22903 45542 22914 45542 22914 45543 22903 45543 22905 45543 22914 45544 22905 45544 22915 45544 22916 45545 27487 45545 22910 45545 22910 45546 27487 45546 22917 45546 22910 45547 22917 45547 22907 45547 22907 45548 22917 45548 22915 45548 22907 45549 22915 45549 22906 45549 22906 45550 22915 45550 22905 45550 23612 45551 23613 45551 22918 45551 22918 45552 23613 45552 23160 45552 22918 45553 23160 45553 22919 45553 22919 45554 23160 45554 22920 45554 22919 45555 22920 45555 22926 45555 22926 45556 22920 45556 23159 45556 22926 45557 23159 45557 22921 45557 22921 45558 23159 45558 23157 45558 22921 45559 23157 45559 22928 45559 22928 45560 23157 45560 22922 45560 22928 45561 22922 45561 22923 45561 22923 45562 22922 45562 23606 45562 22924 45563 23612 45563 22925 45563 22925 45564 23612 45564 22918 45564 22925 45565 22918 45565 22934 45565 22934 45566 22918 45566 22919 45566 22934 45567 22919 45567 22932 45567 22932 45568 22919 45568 22926 45568 22932 45569 22926 45569 22931 45569 22931 45570 22926 45570 22921 45570 22931 45571 22921 45571 22927 45571 22927 45572 22921 45572 22928 45572 22927 45573 22928 45573 22929 45573 22929 45574 22928 45574 22923 45574 22929 45575 23602 45575 22927 45575 22927 45576 23602 45576 22930 45576 22927 45577 22930 45577 22931 45577 22931 45578 22930 45578 27502 45578 22931 45579 27502 45579 22932 45579 22932 45580 27502 45580 22933 45580 22932 45581 22933 45581 22934 45581 22934 45582 22933 45582 27491 45582 22934 45583 27491 45583 22925 45583 22925 45584 27491 45584 27493 45584 22925 45585 27493 45585 22924 45585 22924 45586 27493 45586 23594 45586 23039 45587 24097 45587 22942 45587 22937 45588 22935 45588 24084 45588 24084 45589 22935 45589 22939 45589 23492 45590 22936 45590 24084 45590 24084 45591 22936 45591 24120 45591 24084 45592 24120 45592 22937 45592 24097 45593 23411 45593 22942 45593 22942 45594 23411 45594 23412 45594 22942 45595 23412 45595 22935 45595 22935 45596 23412 45596 22938 45596 22935 45597 22938 45597 22939 45597 23414 45598 22940 45598 24086 45598 24086 45599 22940 45599 22702 45599 24086 45600 22702 45600 22944 45600 23039 45601 22942 45601 22941 45601 22941 45602 22942 45602 22940 45602 22941 45603 22940 45603 22943 45603 22943 45604 22940 45604 23414 45604 22943 45605 23414 45605 24105 45605 22946 45606 23038 45606 22945 45606 22945 45607 23038 45607 24107 45607 22945 45608 24107 45608 23495 45608 22944 45609 22702 45609 22945 45609 22945 45610 22702 45610 22701 45610 22945 45611 22701 45611 22946 45611 22946 45612 22701 45612 22947 45612 22946 45613 22947 45613 23036 45613 23036 45614 22947 45614 22699 45614 23036 45615 22699 45615 23034 45615 23034 45616 22699 45616 22698 45616 23034 45617 22698 45617 22948 45617 22948 45618 22698 45618 22949 45618 22948 45619 22949 45619 22950 45619 22950 45620 22949 45620 23856 45620 22950 45621 23856 45621 22951 45621 24120 45622 23007 45622 22937 45622 22937 45623 23007 45623 22952 45623 22937 45624 22952 45624 22953 45624 22953 45625 22952 45625 23010 45625 22953 45626 23010 45626 22705 45626 22705 45627 23010 45627 22954 45627 22705 45628 22954 45628 22955 45628 22955 45629 22954 45629 23012 45629 22955 45630 23012 45630 22706 45630 22706 45631 23012 45631 22956 45631 22706 45632 22956 45632 22708 45632 22957 45633 23230 45633 22959 45633 22957 45634 22959 45634 22958 45634 22958 45635 22959 45635 23260 45635 22958 45636 23260 45636 22960 45636 22960 45637 23260 45637 23258 45637 22960 45638 23258 45638 22961 45638 22961 45639 23258 45639 23257 45639 22961 45640 23257 45640 24024 45640 24024 45641 23257 45641 23255 45641 24024 45642 23255 45642 24028 45642 22522 45643 22980 45643 22962 45643 22522 45644 22962 45644 22523 45644 22523 45645 22962 45645 22963 45645 22523 45646 22963 45646 22964 45646 22964 45647 22963 45647 22965 45647 22964 45648 22965 45648 22525 45648 22525 45649 22965 45649 24112 45649 22525 45650 24112 45650 22526 45650 22526 45651 24112 45651 24117 45651 22526 45652 24117 45652 24044 45652 23216 45653 23215 45653 22966 45653 23216 45654 22966 45654 22967 45654 22967 45655 22966 45655 22512 45655 22967 45656 22512 45656 22968 45656 22968 45657 22512 45657 22511 45657 22968 45658 22511 45658 22969 45658 22969 45659 22511 45659 22970 45659 22969 45660 22970 45660 22531 45660 22531 45661 22970 45661 22972 45661 22531 45662 22972 45662 22971 45662 22971 45663 22972 45663 22973 45663 22971 45664 22973 45664 22538 45664 22538 45665 22973 45665 22508 45665 22538 45666 22508 45666 22536 45666 22536 45667 22508 45667 22507 45667 22536 45668 22507 45668 22535 45668 22535 45669 22507 45669 22506 45669 22535 45670 22506 45670 22534 45670 22534 45671 22506 45671 22504 45671 22534 45672 22504 45672 22542 45672 22542 45673 22504 45673 22974 45673 22542 45674 22974 45674 22541 45674 22541 45675 22974 45675 22975 45675 22541 45676 22975 45676 22976 45676 22976 45677 22975 45677 22502 45677 22976 45678 22502 45678 22544 45678 22544 45679 22502 45679 22977 45679 22544 45680 22977 45680 22546 45680 22546 45681 22977 45681 22979 45681 22546 45682 22979 45682 22978 45682 22978 45683 22979 45683 22980 45683 22978 45684 22980 45684 22522 45684 22981 45685 23064 45685 23930 45685 23930 45686 23064 45686 22982 45686 23930 45687 22982 45687 23927 45687 23927 45688 22982 45688 22983 45688 22983 45689 22982 45689 22984 45689 22983 45690 22984 45690 22985 45690 22988 45691 23920 45691 22984 45691 22984 45692 23920 45692 22986 45692 22984 45693 22986 45693 22985 45693 22989 45694 22987 45694 22988 45694 22988 45695 22987 45695 23922 45695 22988 45696 23922 45696 23920 45696 23205 45697 23916 45697 22989 45697 22989 45698 23916 45698 23915 45698 22989 45699 23915 45699 22987 45699 22991 45700 23919 45700 23205 45700 23205 45701 23919 45701 22990 45701 23205 45702 22990 45702 23916 45702 23860 45703 23858 45703 22994 45703 22994 45704 23858 45704 22992 45704 22994 45705 22992 45705 22991 45705 22991 45706 22992 45706 22993 45706 22991 45707 22993 45707 23919 45707 23860 45708 22994 45708 22995 45708 22995 45709 22994 45709 22996 45709 22995 45710 22996 45710 23907 45710 23907 45711 22996 45711 23908 45711 23908 45712 22996 45712 22997 45712 23908 45713 22997 45713 23909 45713 23909 45714 22997 45714 22999 45714 22999 45715 22997 45715 22998 45715 22999 45716 22998 45716 23000 45716 23000 45717 22998 45717 23905 45717 23905 45718 22998 45718 23197 45718 23905 45719 23197 45719 23001 45719 23001 45720 23197 45720 23002 45720 23002 45721 23197 45721 23196 45721 23002 45722 23196 45722 23003 45722 23005 45723 23898 45723 23004 45723 23005 45724 23004 45724 23196 45724 23196 45725 23004 45725 23885 45725 23196 45726 23885 45726 23003 45726 23898 45727 23005 45727 23899 45727 23899 45728 23005 45728 23194 45728 23899 45729 23194 45729 23897 45729 23897 45730 23194 45730 23006 45730 23006 45731 23194 45731 23191 45731 23006 45732 23191 45732 22695 45732 24120 45733 24741 45733 23007 45733 23007 45734 24741 45734 23008 45734 23007 45735 23008 45735 22952 45735 22952 45736 23008 45736 23009 45736 22952 45737 23009 45737 23010 45737 23010 45738 23009 45738 23011 45738 23010 45739 23011 45739 22954 45739 22954 45740 23011 45740 24739 45740 22954 45741 24739 45741 23012 45741 23012 45742 24739 45742 23013 45742 23012 45743 23013 45743 22956 45743 22956 45744 23013 45744 23014 45744 22956 45745 23014 45745 23302 45745 23302 45746 23014 45746 23015 45746 23302 45747 23015 45747 23300 45747 23300 45748 23015 45748 22226 45748 23300 45749 22226 45749 23016 45749 23016 45750 22226 45750 22225 45750 23016 45751 22225 45751 23017 45751 23017 45752 22225 45752 23019 45752 23017 45753 23019 45753 23018 45753 23018 45754 23019 45754 22223 45754 23018 45755 22223 45755 23020 45755 23020 45756 22223 45756 22222 45756 23020 45757 22222 45757 23021 45757 23021 45758 22222 45758 23022 45758 23021 45759 23022 45759 23296 45759 23296 45760 23022 45760 23023 45760 23296 45761 23023 45761 23024 45761 23024 45762 23023 45762 23026 45762 23024 45763 23026 45763 23025 45763 23025 45764 23026 45764 23027 45764 23025 45765 23027 45765 23029 45765 23029 45766 23027 45766 23028 45766 23029 45767 23028 45767 23030 45767 23030 45768 23028 45768 22218 45768 23030 45769 22218 45769 23290 45769 23290 45770 22218 45770 23031 45770 23290 45771 23031 45771 23289 45771 23289 45772 23031 45772 23032 45772 23289 45773 23032 45773 22951 45773 22951 45774 23032 45774 24732 45774 22951 45775 24732 45775 22950 45775 22950 45776 24732 45776 23033 45776 22950 45777 23033 45777 22948 45777 22948 45778 23033 45778 24730 45778 22948 45779 24730 45779 23034 45779 23034 45780 24730 45780 23035 45780 23034 45781 23035 45781 23036 45781 23036 45782 23035 45782 24729 45782 23036 45783 24729 45783 22946 45783 22946 45784 24729 45784 23037 45784 22946 45785 23037 45785 23038 45785 23038 45786 23037 45786 27226 45786 24099 45787 23039 45787 24736 45787 24736 45788 23039 45788 22941 45788 22695 45789 23191 45789 23040 45789 23040 45790 23191 45790 23180 45790 22678 45791 22685 45791 23042 45791 23042 45792 22685 45792 22686 45792 23042 45793 22686 45793 23180 45793 23180 45794 22686 45794 23041 45794 23180 45795 23041 45795 23040 45795 22678 45796 23042 45796 23043 45796 23043 45797 23042 45797 23181 45797 23043 45798 23181 45798 23044 45798 23044 45799 23181 45799 22680 45799 22680 45800 23181 45800 23046 45800 22680 45801 23046 45801 22677 45801 22677 45802 23046 45802 23045 45802 23045 45803 23046 45803 23168 45803 23045 45804 23168 45804 22672 45804 22672 45805 23168 45805 22667 45805 22667 45806 23168 45806 23047 45806 22667 45807 23047 45807 22668 45807 22668 45808 23047 45808 23049 45808 23049 45809 23047 45809 23048 45809 23049 45810 23048 45810 23050 45810 23052 45811 23054 45811 23048 45811 23048 45812 23054 45812 22629 45812 23048 45813 22629 45813 23050 45813 23051 45814 23053 45814 23052 45814 23052 45815 23053 45815 22665 45815 23052 45816 22665 45816 23054 45816 23055 45817 22619 45817 23051 45817 23051 45818 22619 45818 22620 45818 23051 45819 22620 45819 23053 45819 23188 45820 23059 45820 23055 45820 23055 45821 23059 45821 23056 45821 23055 45822 23056 45822 22619 45822 22607 45823 22658 45823 23058 45823 23058 45824 22658 45824 23057 45824 23058 45825 23057 45825 23188 45825 23188 45826 23057 45826 22657 45826 23188 45827 22657 45827 23059 45827 22607 45828 23058 45828 22652 45828 22652 45829 23058 45829 23060 45829 22652 45830 23060 45830 22653 45830 22653 45831 23060 45831 23061 45831 23061 45832 23060 45832 23062 45832 23061 45833 23062 45833 22650 45833 22650 45834 23062 45834 23063 45834 23063 45835 23062 45835 23064 45835 23063 45836 23064 45836 22981 45836 23065 45837 23161 45837 24026 45837 22537 45838 23165 45838 22539 45838 23105 45839 23114 45839 23117 45839 24057 45840 22515 45840 23066 45840 23081 45841 23067 45841 23080 45841 23080 45842 23067 45842 22515 45842 23080 45843 22515 45843 22516 45843 23066 45844 22515 45844 22875 45844 22875 45845 22515 45845 23067 45845 22875 45846 23067 45846 23648 45846 23068 45847 23069 45847 22874 45847 22874 45848 23069 45848 24056 45848 22874 45849 24056 45849 23066 45849 23066 45850 24056 45850 24058 45850 23066 45851 24058 45851 24057 45851 23070 45852 23071 45852 23068 45852 23068 45853 23071 45853 24055 45853 23068 45854 24055 45854 23069 45854 23072 45855 23073 45855 23070 45855 23070 45856 23073 45856 24052 45856 23070 45857 24052 45857 23071 45857 23654 45858 23653 45858 24046 45858 24046 45859 23653 45859 24045 45859 24046 45860 24049 45860 23654 45860 23654 45861 24049 45861 24048 45861 23654 45862 24048 45862 23072 45862 23072 45863 24048 45863 24050 45863 23072 45864 24050 45864 23073 45864 23653 45865 23074 45865 24045 45865 24045 45866 23074 45866 23075 45866 24045 45867 23075 45867 22527 45867 22527 45868 23075 45868 23651 45868 22527 45869 23651 45869 23067 45869 23067 45870 23651 45870 23650 45870 23067 45871 23650 45871 23648 45871 23076 45872 23077 45872 22848 45872 22524 45873 23669 45873 23668 45873 22524 45874 23668 45874 23076 45874 23076 45875 23668 45875 22849 45875 23076 45876 22849 45876 23077 45876 22520 45877 22845 45877 22519 45877 22519 45878 22845 45878 23078 45878 22519 45879 23078 45879 22517 45879 22517 45880 23078 45880 23674 45880 22517 45881 23674 45881 23672 45881 23088 45882 23076 45882 23079 45882 23079 45883 23076 45883 22848 45883 23079 45884 22848 45884 22520 45884 22520 45885 22848 45885 22846 45885 22520 45886 22846 45886 22845 45886 22516 45887 22517 45887 23080 45887 23080 45888 22517 45888 23672 45888 23080 45889 23672 45889 23081 45889 23081 45890 23672 45890 23082 45890 23081 45891 23082 45891 22524 45891 22524 45892 23082 45892 23671 45892 22524 45893 23671 45893 23669 45893 24064 45894 23083 45894 23084 45894 22543 45895 23090 45895 23096 45895 24064 45896 23084 45896 24062 45896 23086 45897 23079 45897 23692 45897 23692 45898 23079 45898 24062 45898 23692 45899 24062 45899 23085 45899 23085 45900 24062 45900 23084 45900 23086 45901 23691 45901 23079 45901 23079 45902 23691 45902 22547 45902 23079 45903 22547 45903 23088 45903 23088 45904 22547 45904 23087 45904 23088 45905 23087 45905 23076 45905 23691 45906 23089 45906 22547 45906 22547 45907 23089 45907 23690 45907 22547 45908 23690 45908 23090 45908 23090 45909 23690 45909 22830 45909 23090 45910 22830 45910 23096 45910 22829 45911 23092 45911 23091 45911 23083 45912 24064 45912 23092 45912 23092 45913 24064 45913 23093 45913 23092 45914 23093 45914 23091 45914 23091 45915 23093 45915 23094 45915 23091 45916 23094 45916 23095 45916 23708 45917 23091 45917 23709 45917 23709 45918 23091 45918 23095 45918 23709 45919 23095 45919 24067 45919 23096 45920 22829 45920 22543 45920 22543 45921 22829 45921 23091 45921 22543 45922 23091 45922 22545 45922 22545 45923 23091 45923 23708 45923 22545 45924 23708 45924 23097 45924 23097 45925 23708 45925 23705 45925 23110 45926 23098 45926 23102 45926 23109 45927 23099 45927 23100 45927 23100 45928 23099 45928 23101 45928 23100 45929 23101 45929 24067 45929 24067 45930 23101 45930 23710 45930 24067 45931 23710 45931 23709 45931 23102 45932 23098 45932 23103 45932 23103 45933 23098 45933 23104 45933 23103 45934 23104 45934 23388 45934 23705 45935 22811 45935 23097 45935 23097 45936 22811 45936 22810 45936 23097 45937 22810 45937 22540 45937 22540 45938 22810 45938 22808 45938 22540 45939 22808 45939 23105 45939 22808 45940 23106 45940 23105 45940 23105 45941 23106 45941 23107 45941 23105 45942 23107 45942 23114 45942 23114 45943 23107 45943 23108 45943 23100 45944 23110 45944 23109 45944 23109 45945 23110 45945 23102 45945 23109 45946 23102 45946 23108 45946 23108 45947 23102 45947 23111 45947 23108 45948 23111 45948 23114 45948 23114 45949 23111 45949 23112 45949 23114 45950 23165 45950 23113 45950 23113 45951 23165 45951 23727 45951 23113 45952 23726 45952 23114 45952 23114 45953 23726 45953 23115 45953 23114 45954 23115 45954 23117 45954 23117 45955 23115 45955 23116 45955 23117 45956 23116 45956 23122 45956 23123 45957 23118 45957 23119 45957 23119 45958 23118 45958 22787 45958 23119 45959 22787 45959 22537 45959 22537 45960 22787 45960 23729 45960 22537 45961 23729 45961 23165 45961 23165 45962 23729 45962 23120 45962 23165 45963 23120 45963 23727 45963 23116 45964 23121 45964 23122 45964 23122 45965 23121 45965 22791 45965 23122 45966 22791 45966 23123 45966 23123 45967 22791 45967 22790 45967 23123 45968 22790 45968 23118 45968 23141 45969 22532 45969 23124 45969 23124 45970 22532 45970 23130 45970 23124 45971 23130 45971 24014 45971 23385 45972 24012 45972 23125 45972 23125 45973 24012 45973 23484 45973 23133 45974 23135 45974 24008 45974 24008 45975 23135 45975 23743 45975 24008 45976 23743 45976 24011 45976 24012 45977 24011 45977 23484 45977 23484 45978 24011 45978 23743 45978 23484 45979 23743 45979 23126 45979 23126 45980 23743 45980 23127 45980 23126 45981 23127 45981 23338 45981 22764 45982 22529 45982 23128 45982 23128 45983 22529 45983 22539 45983 23128 45984 22539 45984 23127 45984 23127 45985 22539 45985 23165 45985 23127 45986 23165 45986 23338 45986 22764 45987 22763 45987 22529 45987 22529 45988 22763 45988 23129 45988 22529 45989 23129 45989 22530 45989 22530 45990 23129 45990 23748 45990 22530 45991 23748 45991 22532 45991 22532 45992 23748 45992 23747 45992 22532 45993 23747 45993 23130 45993 23130 45994 23747 45994 23132 45994 23130 45995 23132 45995 23131 45995 23131 45996 23132 45996 23745 45996 23131 45997 23745 45997 23133 45997 23133 45998 23745 45998 23134 45998 23133 45999 23134 45999 23135 45999 24021 46000 23136 46000 24019 46000 24019 46001 23136 46001 23137 46001 24019 46002 23137 46002 24017 46002 23769 46003 23150 46003 23770 46003 23770 46004 23150 46004 22528 46004 23770 46005 22528 46005 23138 46005 23137 46006 23767 46006 24017 46006 24017 46007 23767 46007 23766 46007 24017 46008 23766 46008 23139 46008 23139 46009 23766 46009 22738 46009 23139 46010 22738 46010 23140 46010 23138 46011 22528 46011 22746 46011 22746 46012 22528 46012 22533 46012 22746 46013 22533 46013 22744 46013 24014 46014 23139 46014 23124 46014 23124 46015 23139 46015 23140 46015 23124 46016 23140 46016 23141 46016 23141 46017 23140 46017 22740 46017 23141 46018 22740 46018 22533 46018 22533 46019 22740 46019 22743 46019 22533 46020 22743 46020 22744 46020 23142 46021 23143 46021 23786 46021 24026 46022 23161 46022 24025 46022 23142 46023 23786 46023 24042 46023 23143 46024 23142 46024 23144 46024 23144 46025 23142 46025 23145 46025 23144 46026 23145 46026 23149 46026 23162 46027 23783 46027 23161 46027 23161 46028 23783 46028 23146 46028 23161 46029 23146 46029 24025 46029 24025 46030 23146 46030 23147 46030 24025 46031 23147 46031 24023 46031 23147 46032 22714 46032 24023 46032 24023 46033 22714 46033 22715 46033 24023 46034 22715 46034 24022 46034 24022 46035 22715 46035 23148 46035 23150 46036 22718 46036 23145 46036 23145 46037 22718 46037 22719 46037 23145 46038 22719 46038 23149 46038 23148 46039 22718 46039 24022 46039 24022 46040 22718 46040 23150 46040 24022 46041 23150 46041 24021 46041 24021 46042 23150 46042 23769 46042 24021 46043 23769 46043 23136 46043 23160 46044 23613 46044 24041 46044 24041 46045 23613 46045 23151 46045 24041 46046 23151 46046 23152 46046 23152 46047 23151 46047 23611 46047 23152 46048 23611 46048 24040 46048 24040 46049 23611 46049 23153 46049 24040 46050 23153 46050 24039 46050 24039 46051 23153 46051 23609 46051 24039 46052 23609 46052 23154 46052 23154 46053 23609 46053 23155 46053 23154 46054 23155 46054 24038 46054 24038 46055 23155 46055 23606 46055 23156 46056 23157 46056 23159 46056 23065 46057 23158 46057 22920 46057 22920 46058 23158 46058 24029 46058 22920 46059 24029 46059 23159 46059 23159 46060 24029 46060 24027 46060 23159 46061 24027 46061 23156 46061 22920 46062 23160 46062 23065 46062 23065 46063 23160 46063 24041 46063 23065 46064 24041 46064 23161 46064 23161 46065 24041 46065 24042 46065 23161 46066 24042 46066 23162 46066 23162 46067 24042 46067 23786 46067 22922 46068 24035 46068 23606 46068 23606 46069 24035 46069 24036 46069 23606 46070 24036 46070 24038 46070 23156 46071 24032 46071 23157 46071 23157 46072 24032 46072 24033 46072 23157 46073 24033 46073 22922 46073 22922 46074 24033 46074 23163 46074 22922 46075 23163 46075 24035 46075 23112 46076 23164 46076 23114 46076 23114 46077 23164 46077 23340 46077 23114 46078 23340 46078 23165 46078 23165 46079 23340 46079 23166 46079 23165 46080 23166 46080 23338 46080 23046 46081 23167 46081 23168 46081 23168 46082 23167 46082 23169 46082 23168 46083 23169 46083 23047 46083 23047 46084 23169 46084 22490 46084 23047 46085 22490 46085 23048 46085 23048 46086 22490 46086 23173 46086 24124 46087 24125 46087 23170 46087 23170 46088 24125 46088 23175 46088 23052 46089 23174 46089 23051 46089 23051 46090 23174 46090 22493 46090 23051 46091 22493 46091 23055 46091 22493 46092 23171 46092 23055 46092 23055 46093 23171 46093 22491 46093 23055 46094 22491 46094 23188 46094 24131 46095 23178 46095 24129 46095 24129 46096 23178 46096 23176 46096 24129 46097 23176 46097 24130 46097 23176 46098 23172 46098 24130 46098 24130 46099 23172 46099 23174 46099 24130 46100 23174 46100 23173 46100 23173 46101 23174 46101 23052 46101 23173 46102 23052 46102 23048 46102 23062 46103 23184 46103 23064 46103 23064 46104 23184 46104 22982 46104 24125 46105 24123 46105 23175 46105 23175 46106 24123 46106 23176 46106 23175 46107 23176 46107 23177 46107 23177 46108 23176 46108 23178 46108 23177 46109 23178 46109 23179 46109 23180 46110 24128 46110 23042 46110 23042 46111 24128 46111 24127 46111 23042 46112 24127 46112 23181 46112 23181 46113 24127 46113 23182 46113 23181 46114 23182 46114 23046 46114 23046 46115 23182 46115 23183 46115 23046 46116 23183 46116 23167 46116 23170 46117 23184 46117 24124 46117 24124 46118 23184 46118 23062 46118 24124 46119 23062 46119 23185 46119 23185 46120 23062 46120 23060 46120 23185 46121 23060 46121 23186 46121 23186 46122 23060 46122 23058 46122 23186 46123 23058 46123 22492 46123 22492 46124 23058 46124 23188 46124 22492 46125 23188 46125 23187 46125 23187 46126 23188 46126 22491 46126 23180 46127 23192 46127 24128 46127 24128 46128 23192 46128 23178 46128 24128 46129 23178 46129 24132 46129 24132 46130 23178 46130 24131 46130 22494 46131 23206 46131 23189 46131 22494 46132 23189 46132 23178 46132 23178 46133 23189 46133 23190 46133 23178 46134 23190 46134 23179 46134 23180 46135 23191 46135 23192 46135 23192 46136 23191 46136 23194 46136 23192 46137 23194 46137 23193 46137 23193 46138 23194 46138 23005 46138 23193 46139 23005 46139 23195 46139 23195 46140 23005 46140 23196 46140 23195 46141 23196 46141 23198 46141 23198 46142 23196 46142 23197 46142 23198 46143 23197 46143 23200 46143 22982 46144 23184 46144 22984 46144 22984 46145 23184 46145 23199 46145 22984 46146 23199 46146 22988 46146 22988 46147 23199 46147 24135 46147 22988 46148 24135 46148 22989 46148 22991 46149 23205 46149 23206 46149 23200 46150 23197 46150 23201 46150 23201 46151 23197 46151 22998 46151 23201 46152 22998 46152 23202 46152 24135 46153 23203 46153 22989 46153 22989 46154 23203 46154 23204 46154 22989 46155 23204 46155 23205 46155 23205 46156 23204 46156 24134 46156 23205 46157 24134 46157 23206 46157 22494 46158 22496 46158 23206 46158 23206 46159 22496 46159 22495 46159 23206 46160 22495 46160 22991 46160 22991 46161 22495 46161 23207 46161 22991 46162 23207 46162 22994 46162 23202 46163 22998 46163 24122 46163 24122 46164 22998 46164 22997 46164 24122 46165 22997 46165 23207 46165 23207 46166 22997 46166 22996 46166 23207 46167 22996 46167 22994 46167 23208 46168 24109 46168 23209 46168 23208 46169 23209 46169 23210 46169 23210 46170 23209 46170 23211 46170 23210 46171 23211 46171 23212 46171 23212 46172 23211 46172 22497 46172 23212 46173 22497 46173 23213 46173 23213 46174 22497 46174 23214 46174 23213 46175 23214 46175 24043 46175 24043 46176 23214 46176 23215 46176 24043 46177 23215 46177 23216 46177 24066 46178 24065 46178 23261 46178 23826 46179 23827 46179 23217 46179 23217 46180 23827 46180 23219 46180 23217 46181 23219 46181 22518 46181 22518 46182 23219 46182 23218 46182 23218 46183 23219 46183 23273 46183 23218 46184 23273 46184 23220 46184 23220 46185 23273 46185 23221 46185 23221 46186 23273 46186 23222 46186 23221 46187 23222 46187 22521 46187 23223 46188 24061 46188 23222 46188 23222 46189 24061 46189 24060 46189 23222 46190 24060 46190 22521 46190 23261 46191 24065 46191 23225 46191 24065 46192 23224 46192 23225 46192 23225 46193 23224 46193 23226 46193 23225 46194 23226 46194 23223 46194 23223 46195 23226 46195 24063 46195 23223 46196 24063 46196 24061 46196 24066 46197 23261 46197 23227 46197 23227 46198 23261 46198 23248 46198 23227 46199 23248 46199 24068 46199 24068 46200 23248 46200 23269 46200 24068 46201 23269 46201 23228 46201 24013 46202 23845 46202 23245 46202 24013 46203 23245 46203 23229 46203 23229 46204 23245 46204 23265 46204 23229 46205 23265 46205 24015 46205 23266 46206 23233 46206 23265 46206 23265 46207 23233 46207 24016 46207 23265 46208 24016 46208 24015 46208 23232 46209 22959 46209 23230 46209 23230 46210 23231 46210 23232 46210 23232 46211 23231 46211 24020 46211 23232 46212 24020 46212 23266 46212 23266 46213 24020 46213 24018 46213 23266 46214 24018 46214 23233 46214 23234 46215 24000 46215 24003 46215 23234 46216 24003 46216 23626 46216 23626 46217 24003 46217 24004 46217 23626 46218 24004 46218 23235 46218 23235 46219 24004 46219 23997 46219 23235 46220 23997 46220 23627 46220 23627 46221 23997 46221 23998 46221 23627 46222 23998 46222 23236 46222 23236 46223 23998 46223 23237 46223 23236 46224 23237 46224 23238 46224 23238 46225 23237 46225 23239 46225 23238 46226 23239 46226 22892 46226 22892 46227 23239 46227 23986 46227 22892 46228 23986 46228 22893 46228 24000 46229 23234 46229 23999 46229 23999 46230 23234 46230 22897 46230 23999 46231 22897 46231 23994 46231 23990 46232 23243 46232 23240 46232 23240 46233 23243 46233 22895 46233 23240 46234 22895 46234 23989 46234 22897 46235 22896 46235 23994 46235 23994 46236 22896 46236 23241 46236 23994 46237 23241 46237 23242 46237 23242 46238 23241 46238 23243 46238 23242 46239 23243 46239 23992 46239 23992 46240 23243 46240 23990 46240 23244 46241 23988 46241 23986 46241 23986 46242 23988 46242 23989 46242 23986 46243 23989 46243 22893 46243 22893 46244 23989 46244 22895 46244 23265 46245 23245 46245 23246 46245 23468 46246 23469 46246 23251 46246 23452 46247 23247 46247 23276 46247 23261 46248 23263 46248 23248 46248 23248 46249 23263 46249 23249 46249 23248 46250 23249 46250 23269 46250 23269 46251 23249 46251 23480 46251 23269 46252 23480 46252 23472 46252 23387 46253 22712 46253 23269 46253 23269 46254 22712 46254 22711 46254 23250 46255 23845 46255 23838 46255 23838 46256 23845 46256 23844 46256 23250 46257 23468 46257 23845 46257 23845 46258 23468 46258 23251 46258 23845 46259 23251 46259 23245 46259 23245 46260 23251 46260 23479 46260 23245 46261 23479 46261 23246 46261 23271 46262 23501 46262 23343 46262 23452 46263 23276 46263 23451 46263 23252 46264 23254 46264 23253 46264 23253 46265 23254 46265 23255 46265 23253 46266 23255 46266 23256 46266 23256 46267 23255 46267 23257 46267 23256 46268 23257 46268 23488 46268 23488 46269 23257 46269 23258 46269 23488 46270 23258 46270 23259 46270 23259 46271 23258 46271 23260 46271 23259 46272 23260 46272 22959 46272 23225 46273 23274 46273 23261 46273 23261 46274 23274 46274 23262 46274 23261 46275 23262 46275 23263 46275 23844 46276 23842 46276 23838 46276 23838 46277 23842 46277 23264 46277 23838 46278 23264 46278 23839 46278 23246 46279 23477 46279 23265 46279 23265 46280 23477 46280 23476 46280 23265 46281 23476 46281 23266 46281 23266 46282 23476 46282 23259 46282 23266 46283 23259 46283 23232 46283 23232 46284 23259 46284 22959 46284 23472 46285 23267 46285 23269 46285 23269 46286 23267 46286 23474 46286 23269 46287 23474 46287 23387 46287 23268 46288 23830 46288 23831 46288 23831 46289 23830 46289 23269 46289 23831 46290 23269 46290 23834 46290 23834 46291 23269 46291 22711 46291 23270 46292 23271 46292 23827 46292 23827 46293 23271 46293 23343 46293 23827 46294 23343 46294 23219 46294 23219 46295 23343 46295 23272 46295 23219 46296 23272 46296 23273 46296 23273 46297 23272 46297 23490 46297 23273 46298 23490 46298 23222 46298 23222 46299 23490 46299 23274 46299 23222 46300 23274 46300 23223 46300 23223 46301 23274 46301 23225 46301 23459 46302 23460 46302 23343 46302 23343 46303 23460 46303 23275 46303 23343 46304 23275 46304 23413 46304 23413 46305 23451 46305 23343 46305 23343 46306 23451 46306 23276 46306 23343 46307 23276 46307 23367 46307 23367 46308 23276 46308 23506 46308 23367 46309 23506 46309 23253 46309 23253 46310 23506 46310 23277 46310 23253 46311 23277 46311 23252 46311 23247 46312 23454 46312 23276 46312 23276 46313 23454 46313 23281 46313 23276 46314 23281 46314 23504 46314 23504 46315 23281 46315 23511 46315 23504 46316 23511 46316 23278 46316 23513 46317 23512 46317 23279 46317 23279 46318 23512 46318 23280 46318 23279 46319 23280 46319 23281 46319 23281 46320 23280 46320 23463 46320 23281 46321 23463 46321 23511 46321 23501 46322 23502 46322 23343 46322 23343 46323 23502 46323 23282 46323 23343 46324 23282 46324 23459 46324 23459 46325 23282 46325 23283 46325 23459 46326 23283 46326 23458 46326 23458 46327 23283 46327 23508 46327 23508 46328 23507 46328 23458 46328 23458 46329 23507 46329 23467 46329 23458 46330 23467 46330 23284 46330 23285 46331 23515 46331 23286 46331 23286 46332 23515 46332 23458 46332 23286 46333 23458 46333 23287 46333 23287 46334 23458 46334 23284 46334 24101 46335 23288 46335 23448 46335 23448 46336 23288 46336 23995 46336 22951 46337 23856 46337 23855 46337 22951 46338 23855 46338 23289 46338 23289 46339 23855 46339 23852 46339 23289 46340 23852 46340 23290 46340 23290 46341 23852 46341 23291 46341 23290 46342 23291 46342 23030 46342 23030 46343 23291 46343 23292 46343 23030 46344 23292 46344 23029 46344 23029 46345 23292 46345 23293 46345 23029 46346 23293 46346 23025 46346 23025 46347 23293 46347 23294 46347 23025 46348 23294 46348 23024 46348 23024 46349 23294 46349 23295 46349 23024 46350 23295 46350 23296 46350 23296 46351 23295 46351 23849 46351 23296 46352 23849 46352 23021 46352 23021 46353 23849 46353 23297 46353 23021 46354 23297 46354 23020 46354 23020 46355 23297 46355 23848 46355 23020 46356 23848 46356 23018 46356 23018 46357 23848 46357 23298 46357 23018 46358 23298 46358 23017 46358 23017 46359 23298 46359 23299 46359 23017 46360 23299 46360 23016 46360 23016 46361 23299 46361 23846 46361 23016 46362 23846 46362 23300 46362 23300 46363 23846 46363 23301 46363 23300 46364 23301 46364 23302 46364 23302 46365 23301 46365 22708 46365 23302 46366 22708 46366 22956 46366 23303 46367 22630 46367 23304 46367 23304 46368 22630 46368 22624 46368 23304 46369 22624 46369 23305 46369 22624 46370 22623 46370 23305 46370 23305 46371 22623 46371 23306 46371 23305 46372 23306 46372 23307 46372 23307 46373 23306 46373 23309 46373 23307 46374 23309 46374 23308 46374 23309 46375 22614 46375 23308 46375 23308 46376 22614 46376 23310 46376 23308 46377 23310 46377 23311 46377 23311 46378 23310 46378 23312 46378 23311 46379 23312 46379 23847 46379 23847 46380 23312 46380 22655 46380 23847 46381 22655 46381 23316 46381 23857 46382 23313 46382 23854 46382 23854 46383 23313 46383 22687 46383 23854 46384 22687 46384 23314 46384 23314 46385 22687 46385 23320 46385 23314 46386 23320 46386 23853 46386 22655 46387 23315 46387 23316 46387 23316 46388 23315 46388 23880 46388 23316 46389 23880 46389 22707 46389 22707 46390 23880 46390 23317 46390 22707 46391 23317 46391 23318 46391 23318 46392 23317 46392 23325 46392 23318 46393 23325 46393 23326 46393 22697 46394 23900 46394 22696 46394 22696 46395 23900 46395 23893 46395 22696 46396 23893 46396 23857 46396 23857 46397 23893 46397 23319 46397 23857 46398 23319 46398 23313 46398 23320 46399 22602 46399 23853 46399 23853 46400 22602 46400 22683 46400 23853 46401 22683 46401 23321 46401 23321 46402 22683 46402 22681 46402 23321 46403 22681 46403 23851 46403 22681 46404 23322 46404 23851 46404 23851 46405 23322 46405 22641 46405 23851 46406 22641 46406 23850 46406 23850 46407 22641 46407 22636 46407 23850 46408 22636 46408 23324 46408 23324 46409 22636 46409 23323 46409 23324 46410 23323 46410 23303 46410 23303 46411 23323 46411 22632 46411 23303 46412 22632 46412 22630 46412 23325 46413 23923 46413 23326 46413 23326 46414 23923 46414 23328 46414 23326 46415 23328 46415 23327 46415 23327 46416 23328 46416 23875 46416 23327 46417 23875 46417 23329 46417 23875 46418 23873 46418 23329 46418 23329 46419 23873 46419 23872 46419 23329 46420 23872 46420 22704 46420 22704 46421 23872 46421 23330 46421 22704 46422 23330 46422 23331 46422 23331 46423 23330 46423 23332 46423 23331 46424 23332 46424 22703 46424 23332 46425 23910 46425 22703 46425 22703 46426 23910 46426 23871 46426 22703 46427 23871 46427 23333 46427 23333 46428 23871 46428 23870 46428 23333 46429 23870 46429 23334 46429 23870 46430 23868 46430 23334 46430 23334 46431 23868 46431 23335 46431 23334 46432 23335 46432 23336 46432 23336 46433 23335 46433 23337 46433 23336 46434 23337 46434 22700 46434 22700 46435 23337 46435 23865 46435 22700 46436 23865 46436 22697 46436 22697 46437 23865 46437 23866 46437 22697 46438 23866 46438 23900 46438 23582 46439 23338 46439 23166 46439 23582 46440 23166 46440 23339 46440 23339 46441 23166 46441 23340 46441 23339 46442 23340 46442 23341 46442 23341 46443 23340 46443 23164 46443 23341 46444 23164 46444 23342 46444 23342 46445 23164 46445 23112 46445 23342 46446 23112 46446 23589 46446 23586 46447 23262 46447 23579 46447 23579 46448 23262 46448 23274 46448 23343 46449 23369 46449 23813 46449 23343 46450 22550 46450 23344 46450 23570 46451 23945 46451 23350 46451 22554 46452 22553 46452 23813 46452 23813 46453 22553 46453 23345 46453 23813 46454 23345 46454 23343 46454 23343 46455 23345 46455 22552 46455 23343 46456 22552 46456 22550 46456 23346 46457 23946 46457 23365 46457 23344 46458 23347 46458 23343 46458 23343 46459 23347 46459 23984 46459 23343 46460 23984 46460 23348 46460 23348 46461 23984 46461 23349 46461 23350 46462 23944 46462 23570 46462 23570 46463 23944 46463 23942 46463 23570 46464 23942 46464 23351 46464 23351 46465 23942 46465 22587 46465 22587 46466 22586 46466 23351 46466 23351 46467 22586 46467 22585 46467 23351 46468 22585 46468 23352 46468 23349 46469 23353 46469 23348 46469 23348 46470 23353 46470 23983 46470 23348 46471 23983 46471 23354 46471 23354 46472 23983 46472 23355 46472 23354 46473 23355 46473 23356 46473 23356 46474 23355 46474 23981 46474 23356 46475 23981 46475 23357 46475 23357 46476 23981 46476 22554 46476 23357 46477 22554 46477 23812 46477 23812 46478 22554 46478 23813 46478 23365 46479 23946 46479 23819 46479 23819 46480 23946 46480 23358 46480 23819 46481 23358 46481 23359 46481 22585 46482 23360 46482 23352 46482 23352 46483 23360 46483 23361 46483 23352 46484 23361 46484 23362 46484 23362 46485 23361 46485 23363 46485 23362 46486 23363 46486 23364 46486 23364 46487 23363 46487 23346 46487 23364 46488 23346 46488 23817 46488 23817 46489 23346 46489 23365 46489 23354 46490 23823 46490 23348 46490 23348 46491 23823 46491 23366 46491 23348 46492 23366 46492 23570 46492 23570 46493 23366 46493 23359 46493 23570 46494 23359 46494 23945 46494 23945 46495 23359 46495 23358 46495 23352 46496 23809 46496 23367 46496 23367 46497 23809 46497 23368 46497 23367 46498 23368 46498 23343 46498 23343 46499 23368 46499 23807 46499 23343 46500 23807 46500 23369 46500 23372 46501 23253 46501 23964 46501 23964 46502 23253 46502 23370 46502 23378 46503 23967 46503 23370 46503 23969 46504 23380 46504 23375 46504 23375 46505 23380 46505 23803 46505 23967 46506 23965 46506 23370 46506 23370 46507 23965 46507 23371 46507 23370 46508 23371 46508 23964 46508 23372 46509 22570 46509 23253 46509 23253 46510 22570 46510 22568 46510 23253 46511 22568 46511 23792 46511 23792 46512 22568 46512 23373 46512 23792 46513 23373 46513 23793 46513 23793 46514 23373 46514 23375 46514 23793 46515 23375 46515 23374 46515 23374 46516 23375 46516 23803 46516 23352 46517 23367 46517 23351 46517 23351 46518 23367 46518 23376 46518 23351 46519 23376 46519 23381 46519 23805 46520 23806 46520 23570 46520 23570 46521 23806 46521 23800 46521 23570 46522 23800 46522 23370 46522 23370 46523 23800 46523 23377 46523 23370 46524 23377 46524 23378 46524 23378 46525 23377 46525 23380 46525 23378 46526 23380 46526 23379 46526 23379 46527 23380 46527 23969 46527 23381 46528 23796 46528 23351 46528 23351 46529 23796 46529 23799 46529 23351 46530 23799 46530 23570 46530 23570 46531 23799 46531 23382 46531 23570 46532 23382 46532 23805 46532 23792 46533 23790 46533 23253 46533 23253 46534 23790 46534 23788 46534 23253 46535 23788 46535 23367 46535 23367 46536 23788 46536 23383 46536 23367 46537 23383 46537 23376 46537 23384 46538 23259 46538 23561 46538 23561 46539 23259 46539 23476 46539 23568 46540 23479 46540 23471 46540 23471 46541 23479 46541 23251 46541 23250 46542 23838 46542 23386 46542 23386 46543 23838 46543 23836 46543 23386 46544 23836 46544 22548 46544 23125 46545 23577 46545 23385 46545 23385 46546 23577 46546 23386 46546 22548 46547 24006 46547 23386 46547 23386 46548 24006 46548 24005 46548 23386 46549 24005 46549 23385 46549 23593 46550 23103 46550 23592 46550 23592 46551 23103 46551 23388 46551 22712 46552 23387 46552 22710 46552 22710 46553 23387 46553 23592 46553 22710 46554 23592 46554 24071 46554 24071 46555 23592 46555 23388 46555 23389 46556 23472 46556 23481 46556 23481 46557 23472 46557 23480 46557 23390 46558 23571 46558 23392 46558 23569 46559 23573 46559 23565 46559 23573 46560 23390 46560 23565 46560 23565 46561 23390 46561 23392 46561 23565 46562 23392 46562 23391 46562 23391 46563 23392 46563 23590 46563 23391 46564 23590 46564 23393 46564 23404 46565 23402 46565 23571 46565 23571 46566 23402 46566 23394 46566 23571 46567 23394 46567 23392 46567 23575 46568 23576 46568 23395 46568 23395 46569 23576 46569 23391 46569 23395 46570 23391 46570 23396 46570 23396 46571 23391 46571 23393 46571 23396 46572 23393 46572 23584 46572 23584 46573 23393 46573 23397 46573 23563 46574 23564 46574 23560 46574 23560 46575 23564 46575 23569 46575 23560 46576 23569 46576 23398 46576 23398 46577 23569 46577 23565 46577 23398 46578 23565 46578 23567 46578 23567 46579 23565 46579 23566 46579 23578 46580 23580 46580 23581 46580 23591 46581 23399 46581 23400 46581 23400 46582 23399 46582 23401 46582 23400 46583 23401 46583 23588 46583 23588 46584 23401 46584 23402 46584 23588 46585 23402 46585 23403 46585 23403 46586 23402 46586 23404 46586 23403 46587 23404 46587 23587 46587 23587 46588 23404 46588 23578 46588 23587 46589 23578 46589 23405 46589 23405 46590 23578 46590 23581 46590 23505 46591 23406 46591 23497 46591 23497 46592 23406 46592 23407 46592 23829 46593 23252 46593 24030 46593 24030 46594 23252 46594 23277 46594 24098 46595 23408 46595 23411 46595 23411 46596 23408 46596 23410 46596 23455 46597 23409 46597 23410 46597 23410 46598 23409 46598 24090 46598 23410 46599 24090 46599 23411 46599 23411 46600 24090 46600 24083 46600 23411 46601 24083 46601 23412 46601 23985 46602 23451 46602 23462 46602 23462 46603 23451 46603 23413 46603 24080 46604 23449 46604 23416 46604 23416 46605 23446 46605 24105 46605 24105 46606 23446 46606 24102 46606 24105 46607 23414 46607 23415 46607 24105 46608 23415 46608 23416 46608 23416 46609 23415 46609 24076 46609 23416 46610 24076 46610 24080 46610 24054 46611 23501 46611 24059 46611 24059 46612 23501 46612 23271 46612 24051 46613 23424 46613 23500 46613 23500 46614 23424 46614 23423 46614 23417 46615 23418 46615 23437 46615 23437 46616 23418 46616 24047 46616 24083 46617 24090 46617 24089 46617 24096 46618 24095 46618 23419 46618 24096 46619 23419 46619 24092 46619 24089 46620 23420 46620 24083 46620 24083 46621 23420 46621 23421 46621 24083 46622 23421 46622 23419 46622 23419 46623 23421 46623 24093 46623 23419 46624 24093 46624 24092 46624 23422 46625 23423 46625 24095 46625 24095 46626 23423 46626 23424 46626 24095 46627 23424 46627 23419 46627 23419 46628 23424 46628 23425 46628 23419 46629 23425 46629 23426 46629 24111 46630 23438 46630 24106 46630 24106 46631 23438 46631 24037 46631 24076 46632 23415 46632 23427 46632 23427 46633 23415 46633 23433 46633 24072 46634 23428 46634 23406 46634 23406 46635 23428 46635 23407 46635 23429 46636 23430 46636 23431 46636 23431 46637 23430 46637 23407 46637 23428 46638 24075 46638 23407 46638 23407 46639 24075 46639 24073 46639 23407 46640 24073 46640 23431 46640 23431 46641 24073 46641 23432 46641 23431 46642 23432 46642 23415 46642 23415 46643 23432 46643 24082 46643 23415 46644 24082 46644 23433 46644 24044 46645 24117 46645 24116 46645 24044 46646 24116 46646 23434 46646 23434 46647 24116 46647 23436 46647 23434 46648 23436 46648 23435 46648 23435 46649 23436 46649 23437 46649 23435 46650 23437 46650 24047 46650 23438 46651 24111 46651 23439 46651 23438 46652 23439 46652 23441 46652 23441 46653 23439 46653 23440 46653 23441 46654 23440 46654 23442 46654 23442 46655 23440 46655 24109 46655 23442 46656 24109 46656 23208 46656 23995 46657 23288 46657 23443 46657 23995 46658 23443 46658 23996 46658 23996 46659 23443 46659 23444 46659 23996 46660 23444 46660 23445 46660 23445 46661 23444 46661 24102 46661 23445 46662 24102 46662 23446 46662 23408 46663 24098 46663 24100 46663 23408 46664 24100 46664 24001 46664 24001 46665 24100 46665 23447 46665 24001 46666 23447 46666 24002 46666 24002 46667 23447 46667 24101 46667 24002 46668 24101 46668 23448 46668 24079 46669 23453 46669 24078 46669 24078 46670 23453 46670 23416 46670 24078 46671 23416 46671 23449 46671 23451 46672 23985 46672 23450 46672 23451 46673 23450 46673 23452 46673 23452 46674 23450 46674 23987 46674 23452 46675 23987 46675 23247 46675 23247 46676 23987 46676 23453 46676 23247 46677 23453 46677 23454 46677 23454 46678 23453 46678 24079 46678 23454 46679 24079 46679 23281 46679 23455 46680 23410 46680 23456 46680 23456 46681 23410 46681 23993 46681 23456 46682 23993 46682 23457 46682 23457 46683 23993 46683 23458 46683 23458 46684 23993 46684 23459 46684 23459 46685 23993 46685 23991 46685 23459 46686 23991 46686 23460 46686 23460 46687 23991 46687 23461 46687 23460 46688 23461 46688 23275 46688 23275 46689 23461 46689 23462 46689 23275 46690 23462 46690 23413 46690 24074 46691 23511 46691 23464 46691 23464 46692 23511 46692 23463 46692 23464 46693 23463 46693 23465 46693 23465 46694 23463 46694 23280 46694 23517 46695 23287 46695 24091 46695 24091 46696 23287 46696 23284 46696 24091 46697 23284 46697 23466 46697 23466 46698 23284 46698 23467 46698 23250 46699 23386 46699 23468 46699 23468 46700 23386 46700 23572 46700 23468 46701 23572 46701 23469 46701 23469 46702 23572 46702 23470 46702 23469 46703 23470 46703 23251 46703 23251 46704 23470 46704 23471 46704 23472 46705 23389 46705 23267 46705 23267 46706 23389 46706 23473 46706 23267 46707 23473 46707 23474 46707 23474 46708 23473 46708 23475 46708 23474 46709 23475 46709 23387 46709 23387 46710 23475 46710 23592 46710 23561 46711 23476 46711 23477 46711 23561 46712 23477 46712 23562 46712 23562 46713 23477 46713 23246 46713 23562 46714 23246 46714 23478 46714 23478 46715 23246 46715 23479 46715 23478 46716 23479 46716 23568 46716 23481 46717 23480 46717 23249 46717 23481 46718 23249 46718 23583 46718 23583 46719 23249 46719 23263 46719 23583 46720 23263 46720 23585 46720 23585 46721 23263 46721 23262 46721 23585 46722 23262 46722 23586 46722 23589 46723 23112 46723 23111 46723 23589 46724 23111 46724 23482 46724 23482 46725 23111 46725 23102 46725 23482 46726 23102 46726 23483 46726 23483 46727 23102 46727 23103 46727 23483 46728 23103 46728 23593 46728 23577 46729 23125 46729 23484 46729 23577 46730 23484 46730 23485 46730 23485 46731 23484 46731 23126 46731 23485 46732 23126 46732 23486 46732 23486 46733 23126 46733 23338 46733 23486 46734 23338 46734 23582 46734 23370 46735 23253 46735 23256 46735 23370 46736 23256 46736 23487 46736 23487 46737 23256 46737 23488 46737 23487 46738 23488 46738 23489 46738 23489 46739 23488 46739 23259 46739 23489 46740 23259 46740 23384 46740 23579 46741 23274 46741 23490 46741 23579 46742 23490 46742 23574 46742 23574 46743 23490 46743 23272 46743 23574 46744 23272 46744 23491 46744 23491 46745 23272 46745 23343 46745 23491 46746 23343 46746 23348 46746 23424 46747 24051 46747 23494 46747 23418 46748 23417 46748 23494 46748 23494 46749 23417 46749 23492 46749 24084 46750 23493 46750 23492 46750 23492 46751 23493 46751 23426 46751 23492 46752 23426 46752 23494 46752 23494 46753 23426 46753 23425 46753 23494 46754 23425 46754 23424 46754 23430 46755 23429 46755 23495 46755 23495 46756 23429 46756 24085 46756 23495 46757 24085 46757 22945 46757 24106 46758 24037 46758 23495 46758 23495 46759 24037 46759 23496 46759 23495 46760 23496 46760 23430 46760 23430 46761 23496 46761 23497 46761 23430 46762 23497 46762 23407 46762 23498 46763 23499 46763 23422 46763 23422 46764 23499 46764 23500 46764 23422 46765 23500 46765 23423 46765 23501 46766 24054 46766 24053 46766 23501 46767 24053 46767 23502 46767 23502 46768 24053 46768 23503 46768 23502 46769 23503 46769 23282 46769 23282 46770 23503 46770 23499 46770 23282 46771 23499 46771 23283 46771 23283 46772 23499 46772 23498 46772 23283 46773 23498 46773 23508 46773 23504 46774 23509 46774 24034 46774 24034 46775 23509 46775 23505 46775 23505 46776 23509 46776 24072 46776 23505 46777 24072 46777 23406 46777 23504 46778 24034 46778 23276 46778 23276 46779 24034 46779 24031 46779 23276 46780 24031 46780 23506 46780 23506 46781 24031 46781 24030 46781 23506 46782 24030 46782 23277 46782 23466 46783 23467 46783 23507 46783 23466 46784 23507 46784 24094 46784 24094 46785 23507 46785 23508 46785 24094 46786 23508 46786 23498 46786 23509 46787 23504 46787 23278 46787 23509 46788 23278 46788 23510 46788 23510 46789 23278 46789 23511 46789 23510 46790 23511 46790 24074 46790 23465 46791 23280 46791 23512 46791 23465 46792 23512 46792 24081 46792 24081 46793 23512 46793 23513 46793 24081 46794 23513 46794 23514 46794 23514 46795 23513 46795 23279 46795 23514 46796 23279 46796 24077 46796 24077 46797 23279 46797 23281 46797 24077 46798 23281 46798 24079 46798 23457 46799 23458 46799 23515 46799 23457 46800 23515 46800 24087 46800 24087 46801 23515 46801 23285 46801 24087 46802 23285 46802 23516 46802 23516 46803 23285 46803 23286 46803 23516 46804 23286 46804 24088 46804 24088 46805 23286 46805 23287 46805 24088 46806 23287 46806 23517 46806 23539 46807 23798 46807 23518 46807 23518 46808 23798 46808 23531 46808 23525 46809 23519 46809 23520 46809 23525 46810 23520 46810 23521 46810 23521 46811 23520 46811 23522 46811 23521 46812 23522 46812 23523 46812 23523 46813 23522 46813 23802 46813 23523 46814 23802 46814 24144 46814 24144 46815 23802 46815 23801 46815 24144 46816 23801 46816 24146 46816 23524 46817 23530 46817 23525 46817 23525 46818 23530 46818 23519 46818 23526 46819 23789 46819 23527 46819 23527 46820 23789 46820 23528 46820 23527 46821 23528 46821 23529 46821 23529 46822 23528 46822 23791 46822 23529 46823 23791 46823 24143 46823 24143 46824 23791 46824 23794 46824 24143 46825 23794 46825 23524 46825 23524 46826 23794 46826 23530 46826 23535 46827 23797 46827 23526 46827 23526 46828 23797 46828 23789 46828 23518 46829 23531 46829 23532 46829 23532 46830 23531 46830 23795 46830 23532 46831 23795 46831 23533 46831 23533 46832 23795 46832 23534 46832 23533 46833 23534 46833 23535 46833 23535 46834 23534 46834 23797 46834 24145 46835 23540 46835 23536 46835 23536 46836 23540 46836 23537 46836 23536 46837 23537 46837 23538 46837 23538 46838 23537 46838 23804 46838 23538 46839 23804 46839 23539 46839 23539 46840 23804 46840 23798 46840 24146 46841 23801 46841 24145 46841 24145 46842 23801 46842 23540 46842 23551 46843 23542 46843 23541 46843 23541 46844 23542 46844 23815 46844 23541 46845 23815 46845 23543 46845 23543 46846 23815 46846 23816 46846 23543 46847 23816 46847 23544 46847 23544 46848 23816 46848 23818 46848 23544 46849 23818 46849 24138 46849 24138 46850 23818 46850 23545 46850 24138 46851 23545 46851 24139 46851 24139 46852 23545 46852 23820 46852 23554 46853 23808 46853 23546 46853 23546 46854 23808 46854 23547 46854 23808 46855 23548 46855 23547 46855 23547 46856 23548 46856 23549 46856 23547 46857 23549 46857 24137 46857 23542 46858 23551 46858 23550 46858 23550 46859 23551 46859 24137 46859 23550 46860 24137 46860 23552 46860 23552 46861 24137 46861 23549 46861 23553 46862 23814 46862 23546 46862 23546 46863 23814 46863 23554 46863 24141 46864 23810 46864 24140 46864 24140 46865 23810 46865 23811 46865 24140 46866 23811 46866 23555 46866 23555 46867 23811 46867 23556 46867 23555 46868 23556 46868 23553 46868 23553 46869 23556 46869 23814 46869 23558 46870 23822 46870 24141 46870 24141 46871 23822 46871 23810 46871 23557 46872 23824 46872 24142 46872 24142 46873 23824 46873 23821 46873 24142 46874 23821 46874 24136 46874 24136 46875 23821 46875 23559 46875 24136 46876 23559 46876 23558 46876 23558 46877 23559 46877 23822 46877 24139 46878 23820 46878 23557 46878 23557 46879 23820 46879 23824 46879 23561 46880 23560 46880 23384 46880 23384 46881 23560 46881 23398 46881 23560 46882 23561 46882 23562 46882 23560 46883 23562 46883 23563 46883 23563 46884 23562 46884 23478 46884 23563 46885 23478 46885 23564 46885 23564 46886 23478 46886 23568 46886 23564 46887 23568 46887 23569 46887 23565 46888 23370 46888 23487 46888 23565 46889 23487 46889 23566 46889 23566 46890 23487 46890 23489 46890 23566 46891 23489 46891 23567 46891 23567 46892 23489 46892 23384 46892 23567 46893 23384 46893 23398 46893 23471 46894 23573 46894 23568 46894 23568 46895 23573 46895 23569 46895 23370 46896 23565 46896 23570 46896 23570 46897 23565 46897 23391 46897 23570 46898 23391 46898 23348 46898 23386 46899 23404 46899 23572 46899 23572 46900 23404 46900 23571 46900 23572 46901 23571 46901 23470 46901 23470 46902 23571 46902 23390 46902 23470 46903 23390 46903 23471 46903 23471 46904 23390 46904 23573 46904 23395 46905 23579 46905 23574 46905 23395 46906 23574 46906 23575 46906 23575 46907 23574 46907 23491 46907 23575 46908 23491 46908 23576 46908 23576 46909 23491 46909 23348 46909 23576 46910 23348 46910 23391 46910 23577 46911 23578 46911 23386 46911 23386 46912 23578 46912 23404 46912 23396 46913 23586 46913 23395 46913 23395 46914 23586 46914 23579 46914 23578 46915 23577 46915 23485 46915 23578 46916 23485 46916 23580 46916 23580 46917 23485 46917 23486 46917 23580 46918 23486 46918 23581 46918 23581 46919 23486 46919 23582 46919 23581 46920 23582 46920 23405 46920 23393 46921 23481 46921 23583 46921 23393 46922 23583 46922 23397 46922 23397 46923 23583 46923 23585 46923 23397 46924 23585 46924 23584 46924 23584 46925 23585 46925 23586 46925 23584 46926 23586 46926 23396 46926 23405 46927 23582 46927 23339 46927 23405 46928 23339 46928 23587 46928 23587 46929 23339 46929 23341 46929 23587 46930 23341 46930 23403 46930 23403 46931 23341 46931 23342 46931 23403 46932 23342 46932 23588 46932 23588 46933 23342 46933 23589 46933 23588 46934 23589 46934 23400 46934 23590 46935 23389 46935 23393 46935 23393 46936 23389 46936 23481 46936 23400 46937 23589 46937 23482 46937 23400 46938 23482 46938 23591 46938 23591 46939 23482 46939 23483 46939 23591 46940 23483 46940 23399 46940 23399 46941 23483 46941 23593 46941 23399 46942 23593 46942 23401 46942 23389 46943 23590 46943 23473 46943 23473 46944 23590 46944 23392 46944 23473 46945 23392 46945 23475 46945 23475 46946 23392 46946 23394 46946 23475 46947 23394 46947 23592 46947 23592 46948 23394 46948 23402 46948 23592 46949 23402 46949 23593 46949 23593 46950 23402 46950 23401 46950 22924 46951 23594 46951 23595 46951 23595 46952 23594 46952 23597 46952 23595 46953 23597 46953 23596 46953 23596 46954 23597 46954 27495 46954 23596 46955 27495 46955 23598 46955 23598 46956 27495 46956 27498 46956 23598 46957 27498 46957 23603 46957 23603 46958 27498 46958 23600 46958 23603 46959 23600 46959 23599 46959 23599 46960 23600 46960 23601 46960 23599 46961 23601 46961 22929 46961 22929 46962 23601 46962 23602 46962 22929 46963 22923 46963 23599 46963 23599 46964 22923 46964 23607 46964 23599 46965 23607 46965 23603 46965 23603 46966 23607 46966 23608 46966 23603 46967 23608 46967 23598 46967 23598 46968 23608 46968 23604 46968 23598 46969 23604 46969 23596 46969 23596 46970 23604 46970 23610 46970 23596 46971 23610 46971 23595 46971 23595 46972 23610 46972 23605 46972 23595 46973 23605 46973 22924 46973 22924 46974 23605 46974 23612 46974 22923 46975 23606 46975 23607 46975 23607 46976 23606 46976 23155 46976 23607 46977 23155 46977 23608 46977 23608 46978 23155 46978 23609 46978 23608 46979 23609 46979 23604 46979 23604 46980 23609 46980 23153 46980 23604 46981 23153 46981 23610 46981 23610 46982 23153 46982 23611 46982 23610 46983 23611 46983 23605 46983 23605 46984 23611 46984 23151 46984 23605 46985 23151 46985 23612 46985 23612 46986 23151 46986 23613 46986 22898 46987 27484 46987 23614 46987 23614 46988 27484 46988 27485 46988 23614 46989 27485 46989 23622 46989 23622 46990 27485 46990 27486 46990 23622 46991 27486 46991 23616 46991 23616 46992 27486 46992 23615 46992 23616 46993 23615 46993 23617 46993 23617 46994 23615 46994 23618 46994 23617 46995 23618 46995 23620 46995 23620 46996 23618 46996 23619 46996 23620 46997 23619 46997 22916 46997 22916 46998 23619 46998 27487 46998 22916 46999 22911 46999 23620 46999 23620 47000 22911 47000 23624 47000 23620 47001 23624 47001 23617 47001 23617 47002 23624 47002 23625 47002 23617 47003 23625 47003 23616 47003 23616 47004 23625 47004 23621 47004 23616 47005 23621 47005 23622 47005 23622 47006 23621 47006 23623 47006 23622 47007 23623 47007 23614 47007 23614 47008 23623 47008 23628 47008 23614 47009 23628 47009 22898 47009 22898 47010 23628 47010 22890 47010 22911 47011 22897 47011 23624 47011 23624 47012 22897 47012 23234 47012 23624 47013 23234 47013 23625 47013 23625 47014 23234 47014 23626 47014 23625 47015 23626 47015 23621 47015 23621 47016 23626 47016 23235 47016 23621 47017 23235 47017 23623 47017 23623 47018 23235 47018 23627 47018 23623 47019 23627 47019 23628 47019 23628 47020 23627 47020 23236 47020 23628 47021 23236 47021 22890 47021 22890 47022 23236 47022 23238 47022 22882 47023 23630 47023 23629 47023 23629 47024 23630 47024 23640 47024 23629 47025 23640 47025 23632 47025 23632 47026 23640 47026 23631 47026 23631 47027 23633 47027 23632 47027 23632 47028 23633 47028 23641 47028 23632 47029 23641 47029 27460 47029 23641 47030 23634 47030 27460 47030 27460 47031 23634 47031 23635 47031 27460 47032 23635 47032 23636 47032 22889 47033 23638 47033 23637 47033 23637 47034 23638 47034 27458 47034 23637 47035 27458 47035 23646 47035 23646 47036 27458 47036 23636 47036 23646 47037 23636 47037 23644 47037 23644 47038 23636 47038 23635 47038 23630 47039 23639 47039 23649 47039 23630 47040 23649 47040 23640 47040 23640 47041 23649 47041 23652 47041 23640 47042 23652 47042 23631 47042 23631 47043 23652 47043 23633 47043 23633 47044 23652 47044 23642 47044 23633 47045 23642 47045 23641 47045 23641 47046 23642 47046 23634 47046 23634 47047 23642 47047 23643 47047 23634 47048 23643 47048 23635 47048 23635 47049 23643 47049 23644 47049 23644 47050 23643 47050 23645 47050 23644 47051 23645 47051 23646 47051 23646 47052 23645 47052 23647 47052 23646 47053 23647 47053 23637 47053 23637 47054 23647 47054 22876 47054 23637 47055 22876 47055 22889 47055 23639 47056 23648 47056 23649 47056 23649 47057 23648 47057 23650 47057 23649 47058 23650 47058 23652 47058 23652 47059 23650 47059 23651 47059 23652 47060 23651 47060 23642 47060 23642 47061 23651 47061 23075 47061 23642 47062 23075 47062 23643 47062 23643 47063 23075 47063 23074 47063 23643 47064 23074 47064 23645 47064 23645 47065 23074 47065 23653 47065 23645 47066 23653 47066 23647 47066 23647 47067 23653 47067 23654 47067 23647 47068 23654 47068 22876 47068 22876 47069 23654 47069 23072 47069 22861 47070 27427 47070 23666 47070 23666 47071 27427 47071 23655 47071 23666 47072 23655 47072 23665 47072 23665 47073 23655 47073 27429 47073 23665 47074 27429 47074 23663 47074 23663 47075 27429 47075 27430 47075 23663 47076 27430 47076 23661 47076 23661 47077 27430 47077 23656 47077 23661 47078 23656 47078 23659 47078 23659 47079 23656 47079 27435 47079 23659 47080 27435 47080 23657 47080 23657 47081 27435 47081 23658 47081 23657 47082 22860 47082 23659 47082 23659 47083 22860 47083 23660 47083 23659 47084 23660 47084 23661 47084 23661 47085 23660 47085 23670 47085 23661 47086 23670 47086 23663 47086 23663 47087 23670 47087 23662 47087 23663 47088 23662 47088 23665 47088 23665 47089 23662 47089 23664 47089 23665 47090 23664 47090 23666 47090 23666 47091 23664 47091 23673 47091 23666 47092 23673 47092 22861 47092 22861 47093 23673 47093 23667 47093 22860 47094 23668 47094 23660 47094 23660 47095 23668 47095 23669 47095 23660 47096 23669 47096 23670 47096 23670 47097 23669 47097 23671 47097 23670 47098 23671 47098 23662 47098 23662 47099 23671 47099 23082 47099 23662 47100 23082 47100 23664 47100 23664 47101 23082 47101 23672 47101 23664 47102 23672 47102 23673 47102 23673 47103 23672 47103 23674 47103 23673 47104 23674 47104 23667 47104 23667 47105 23674 47105 23078 47105 23688 47106 22844 47106 23686 47106 23686 47107 22844 47107 23675 47107 23686 47108 23675 47108 23684 47108 23684 47109 23675 47109 23676 47109 23684 47110 23676 47110 23683 47110 23683 47111 23676 47111 27398 47111 23683 47112 27398 47112 23681 47112 23681 47113 27398 47113 27400 47113 23681 47114 27400 47114 23678 47114 23678 47115 27400 47115 27401 47115 23678 47116 27401 47116 23677 47116 23677 47117 27401 47117 27403 47117 23677 47118 23689 47118 23678 47118 23678 47119 23689 47119 23679 47119 23678 47120 23679 47120 23681 47120 23681 47121 23679 47121 23680 47121 23681 47122 23680 47122 23683 47122 23683 47123 23680 47123 23682 47123 23683 47124 23682 47124 23684 47124 23684 47125 23682 47125 23685 47125 23684 47126 23685 47126 23686 47126 23686 47127 23685 47127 23687 47127 23686 47128 23687 47128 23688 47128 23688 47129 23687 47129 22832 47129 23689 47130 23690 47130 23679 47130 23679 47131 23690 47131 23089 47131 23679 47132 23089 47132 23680 47132 23680 47133 23089 47133 23691 47133 23680 47134 23691 47134 23682 47134 23682 47135 23691 47135 23086 47135 23682 47136 23086 47136 23685 47136 23685 47137 23086 47137 23692 47137 23685 47138 23692 47138 23687 47138 23687 47139 23692 47139 23085 47139 23687 47140 23085 47140 22832 47140 22832 47141 23085 47141 23084 47141 23704 47142 27372 47142 23693 47142 23693 47143 27372 47143 27374 47143 23693 47144 27374 47144 23703 47144 23703 47145 27374 47145 23694 47145 23703 47146 23694 47146 23701 47146 23701 47147 23694 47147 23695 47147 23701 47148 23695 47148 23700 47148 23700 47149 23695 47149 27375 47149 23700 47150 27375 47150 23696 47150 23696 47151 27375 47151 23697 47151 23696 47152 23697 47152 23698 47152 23698 47153 23697 47153 27377 47153 23698 47154 23699 47154 23696 47154 23696 47155 23699 47155 23706 47155 23696 47156 23706 47156 23700 47156 23700 47157 23706 47157 23707 47157 23700 47158 23707 47158 23701 47158 23701 47159 23707 47159 23702 47159 23701 47160 23702 47160 23703 47160 23703 47161 23702 47161 23711 47161 23703 47162 23711 47162 23693 47162 23693 47163 23711 47163 23712 47163 23693 47164 23712 47164 23704 47164 23704 47165 23712 47165 22812 47165 23699 47166 23705 47166 23706 47166 23706 47167 23705 47167 23708 47167 23706 47168 23708 47168 23707 47168 23707 47169 23708 47169 23709 47169 23707 47170 23709 47170 23702 47170 23702 47171 23709 47171 23710 47171 23702 47172 23710 47172 23711 47172 23711 47173 23710 47173 23101 47173 23711 47174 23101 47174 23712 47174 23712 47175 23101 47175 23099 47175 23712 47176 23099 47176 22812 47176 22812 47177 23099 47177 23109 47177 22805 47178 22807 47178 23724 47178 23724 47179 22807 47179 23713 47179 23724 47180 23713 47180 23722 47180 23722 47181 23713 47181 27348 47181 23722 47182 27348 47182 23721 47182 23721 47183 27348 47183 23714 47183 23721 47184 23714 47184 23715 47184 23715 47185 23714 47185 23716 47185 23715 47186 23716 47186 23718 47186 23718 47187 23716 47187 23717 47187 23718 47188 23717 47188 22797 47188 22797 47189 23717 47189 27351 47189 22797 47190 22793 47190 23718 47190 23718 47191 22793 47191 23719 47191 23718 47192 23719 47192 23715 47192 23715 47193 23719 47193 23725 47193 23715 47194 23725 47194 23721 47194 23721 47195 23725 47195 23720 47195 23721 47196 23720 47196 23722 47196 23722 47197 23720 47197 23723 47197 23722 47198 23723 47198 23724 47198 23724 47199 23723 47199 23728 47199 23724 47200 23728 47200 22805 47200 22805 47201 23728 47201 22786 47201 22793 47202 23116 47202 23719 47202 23719 47203 23116 47203 23115 47203 23719 47204 23115 47204 23725 47204 23725 47205 23115 47205 23726 47205 23725 47206 23726 47206 23720 47206 23720 47207 23726 47207 23113 47207 23720 47208 23113 47208 23723 47208 23723 47209 23113 47209 23727 47209 23723 47210 23727 47210 23728 47210 23728 47211 23727 47211 23120 47211 23728 47212 23120 47212 22786 47212 22786 47213 23120 47213 23729 47213 22776 47214 23730 47214 23741 47214 23741 47215 23730 47215 23731 47215 23741 47216 23731 47216 23732 47216 23732 47217 23731 47217 23734 47217 23732 47218 23734 47218 23733 47218 23733 47219 23734 47219 27330 47219 23733 47220 27330 47220 23740 47220 23740 47221 27330 47221 23735 47221 23740 47222 23735 47222 23737 47222 23737 47223 23735 47223 23736 47223 23737 47224 23736 47224 22783 47224 22783 47225 23736 47225 27329 47225 22783 47226 22767 47226 23737 47226 23737 47227 22767 47227 23738 47227 23737 47228 23738 47228 23740 47228 23740 47229 23738 47229 23739 47229 23740 47230 23739 47230 23733 47230 23733 47231 23739 47231 23744 47231 23733 47232 23744 47232 23732 47232 23732 47233 23744 47233 23746 47233 23732 47234 23746 47234 23741 47234 23741 47235 23746 47235 23742 47235 23741 47236 23742 47236 22776 47236 22776 47237 23742 47237 22761 47237 22767 47238 23743 47238 23738 47238 23738 47239 23743 47239 23135 47239 23738 47240 23135 47240 23739 47240 23739 47241 23135 47241 23134 47241 23739 47242 23134 47242 23744 47242 23744 47243 23134 47243 23745 47243 23744 47244 23745 47244 23746 47244 23746 47245 23745 47245 23132 47245 23746 47246 23132 47246 23742 47246 23742 47247 23132 47247 23747 47247 23742 47248 23747 47248 22761 47248 22761 47249 23747 47249 23748 47249 23749 47250 27309 47250 23750 47250 23750 47251 27309 47251 23751 47251 23750 47252 23751 47252 23752 47252 23752 47253 23751 47253 23753 47253 23752 47254 23753 47254 23760 47254 23760 47255 23753 47255 23754 47255 23760 47256 23754 47256 23759 47256 23759 47257 23754 47257 23755 47257 23759 47258 23755 47258 23758 47258 23758 47259 23755 47259 27310 47259 23758 47260 27310 47260 23756 47260 23756 47261 27310 47261 23757 47261 23756 47262 22737 47262 23758 47262 23758 47263 22737 47263 23765 47263 23758 47264 23765 47264 23759 47264 23759 47265 23765 47265 23768 47265 23759 47266 23768 47266 23760 47266 23760 47267 23768 47267 23761 47267 23760 47268 23761 47268 23752 47268 23752 47269 23761 47269 23762 47269 23752 47270 23762 47270 23750 47270 23750 47271 23762 47271 23763 47271 23750 47272 23763 47272 23749 47272 23749 47273 23763 47273 23764 47273 22737 47274 23766 47274 23765 47274 23765 47275 23766 47275 23767 47275 23765 47276 23767 47276 23768 47276 23768 47277 23767 47277 23137 47277 23768 47278 23137 47278 23761 47278 23761 47279 23137 47279 23136 47279 23761 47280 23136 47280 23762 47280 23762 47281 23136 47281 23769 47281 23762 47282 23769 47282 23763 47282 23763 47283 23769 47283 23770 47283 23763 47284 23770 47284 23764 47284 23764 47285 23770 47285 23138 47285 22722 47286 22736 47286 23771 47286 23771 47287 22736 47287 27280 47287 23771 47288 27280 47288 23781 47288 23781 47289 27280 47289 27281 47289 23781 47290 27281 47290 23780 47290 23780 47291 27281 47291 23772 47291 23780 47292 23772 47292 23773 47292 23773 47293 23772 47293 27283 47293 23773 47294 27283 47294 23777 47294 23777 47295 27283 47295 23775 47295 23777 47296 23775 47296 23774 47296 23774 47297 23775 47297 23776 47297 23774 47298 22713 47298 23777 47298 23777 47299 22713 47299 23778 47299 23777 47300 23778 47300 23773 47300 23773 47301 23778 47301 23779 47301 23773 47302 23779 47302 23780 47302 23780 47303 23779 47303 23784 47303 23780 47304 23784 47304 23781 47304 23781 47305 23784 47305 23785 47305 23781 47306 23785 47306 23771 47306 23771 47307 23785 47307 23782 47307 23771 47308 23782 47308 22722 47308 22722 47309 23782 47309 23787 47309 22713 47310 23147 47310 23778 47310 23778 47311 23147 47311 23146 47311 23778 47312 23146 47312 23779 47312 23779 47313 23146 47313 23783 47313 23779 47314 23783 47314 23784 47314 23784 47315 23783 47315 23162 47315 23784 47316 23162 47316 23785 47316 23785 47317 23162 47317 23786 47317 23785 47318 23786 47318 23782 47318 23782 47319 23786 47319 23143 47319 23782 47320 23143 47320 23787 47320 23787 47321 23143 47321 23144 47321 23788 47322 23789 47322 23383 47322 23383 47323 23789 47323 23797 47323 23789 47324 23788 47324 23528 47324 23528 47325 23788 47325 23790 47325 23528 47326 23790 47326 23791 47326 23791 47327 23790 47327 23792 47327 23791 47328 23792 47328 23794 47328 23794 47329 23792 47329 23793 47329 23794 47330 23793 47330 23530 47330 23530 47331 23793 47331 23374 47331 23531 47332 23796 47332 23795 47332 23795 47333 23796 47333 23381 47333 23795 47334 23381 47334 23534 47334 23534 47335 23381 47335 23376 47335 23534 47336 23376 47336 23797 47336 23797 47337 23376 47337 23383 47337 23803 47338 23519 47338 23374 47338 23374 47339 23519 47339 23530 47339 23798 47340 23799 47340 23531 47340 23531 47341 23799 47341 23796 47341 23800 47342 23801 47342 23377 47342 23377 47343 23801 47343 23802 47343 23377 47344 23802 47344 23380 47344 23519 47345 23803 47345 23520 47345 23520 47346 23803 47346 23380 47346 23520 47347 23380 47347 23522 47347 23522 47348 23380 47348 23802 47348 23540 47349 23806 47349 23537 47349 23537 47350 23806 47350 23805 47350 23537 47351 23805 47351 23804 47351 23804 47352 23805 47352 23382 47352 23804 47353 23382 47353 23798 47353 23798 47354 23382 47354 23799 47354 23806 47355 23540 47355 23800 47355 23800 47356 23540 47356 23801 47356 23368 47357 23554 47357 23807 47357 23807 47358 23554 47358 23814 47358 23362 47359 23364 47359 23542 47359 23542 47360 23550 47360 23362 47360 23362 47361 23550 47361 23552 47361 23362 47362 23552 47362 23352 47362 23352 47363 23552 47363 23549 47363 23352 47364 23549 47364 23809 47364 23554 47365 23368 47365 23808 47365 23808 47366 23368 47366 23809 47366 23808 47367 23809 47367 23548 47367 23548 47368 23809 47368 23549 47368 23810 47369 23812 47369 23811 47369 23811 47370 23812 47370 23813 47370 23811 47371 23813 47371 23556 47371 23556 47372 23813 47372 23369 47372 23556 47373 23369 47373 23814 47373 23814 47374 23369 47374 23807 47374 23817 47375 23815 47375 23364 47375 23364 47376 23815 47376 23542 47376 23822 47377 23357 47377 23810 47377 23810 47378 23357 47378 23812 47378 23815 47379 23817 47379 23816 47379 23816 47380 23817 47380 23365 47380 23816 47381 23365 47381 23818 47381 23818 47382 23365 47382 23819 47382 23818 47383 23819 47383 23545 47383 23545 47384 23819 47384 23359 47384 23545 47385 23359 47385 23820 47385 23820 47386 23359 47386 23366 47386 23824 47387 23823 47387 23821 47387 23821 47388 23823 47388 23354 47388 23821 47389 23354 47389 23559 47389 23559 47390 23354 47390 23356 47390 23559 47391 23356 47391 23822 47391 23822 47392 23356 47392 23357 47392 23823 47393 23824 47393 23366 47393 23366 47394 23824 47394 23820 47394 24059 47395 23271 47395 23825 47395 23825 47396 23271 47396 23270 47396 23825 47397 23270 47397 23826 47397 23826 47398 23270 47398 23827 47398 24028 47399 23255 47399 23828 47399 23828 47400 23255 47400 23254 47400 23828 47401 23254 47401 23829 47401 23829 47402 23254 47402 23252 47402 23228 47403 23269 47403 23830 47403 23228 47404 23830 47404 24069 47404 24069 47405 23830 47405 23268 47405 24069 47406 23268 47406 24070 47406 24070 47407 23268 47407 23831 47407 24070 47408 23831 47408 23832 47408 23832 47409 23831 47409 23834 47409 23832 47410 23834 47410 23833 47410 23833 47411 23834 47411 23835 47411 23835 47412 23834 47412 22711 47412 23835 47413 22711 47413 22709 47413 23836 47414 23838 47414 23837 47414 23837 47415 23838 47415 23839 47415 23837 47416 23839 47416 24007 47416 24007 47417 23839 47417 23840 47417 23840 47418 23839 47418 23264 47418 23840 47419 23264 47419 23841 47419 23841 47420 23264 47420 23843 47420 23843 47421 23264 47421 23842 47421 23843 47422 23842 47422 24010 47422 24010 47423 23842 47423 23844 47423 24010 47424 23844 47424 24009 47424 24009 47425 23844 47425 23845 47425 24009 47426 23845 47426 24013 47426 23316 47427 22708 47427 23301 47427 23316 47428 23301 47428 23847 47428 23847 47429 23301 47429 23846 47429 23847 47430 23846 47430 23311 47430 23311 47431 23846 47431 23299 47431 23311 47432 23299 47432 23308 47432 23308 47433 23299 47433 23298 47433 23308 47434 23298 47434 23307 47434 23307 47435 23298 47435 23848 47435 23307 47436 23848 47436 23305 47436 23305 47437 23848 47437 23297 47437 23305 47438 23297 47438 23304 47438 23304 47439 23297 47439 23849 47439 23304 47440 23849 47440 23303 47440 23303 47441 23849 47441 23295 47441 23303 47442 23295 47442 23324 47442 23324 47443 23295 47443 23294 47443 23324 47444 23294 47444 23850 47444 23850 47445 23294 47445 23293 47445 23850 47446 23293 47446 23851 47446 23851 47447 23293 47447 23292 47447 23851 47448 23292 47448 23321 47448 23321 47449 23292 47449 23291 47449 23321 47450 23291 47450 23853 47450 23853 47451 23291 47451 23852 47451 23853 47452 23852 47452 23314 47452 23314 47453 23852 47453 23855 47453 23314 47454 23855 47454 23854 47454 23854 47455 23855 47455 23856 47455 23854 47456 23856 47456 23857 47456 22985 47457 22986 47457 23924 47457 23924 47458 22986 47458 23921 47458 23858 47459 23860 47459 23859 47459 23859 47460 23860 47460 23906 47460 23878 47461 23877 47461 23925 47461 23861 47462 23862 47462 23913 47462 23864 47463 23901 47463 23902 47463 23330 47464 23872 47464 23889 47464 23337 47465 23335 47465 23863 47465 23319 47466 23893 47466 23894 47466 23337 47467 23901 47467 23865 47467 23865 47468 23901 47468 23864 47468 23865 47469 23864 47469 23866 47469 23863 47470 23335 47470 23867 47470 23867 47471 23335 47471 23868 47471 23867 47472 23868 47472 23869 47472 23869 47473 23868 47473 23870 47473 23869 47474 23870 47474 23888 47474 23888 47475 23870 47475 23871 47475 23888 47476 23871 47476 23911 47476 23330 47477 23862 47477 23332 47477 23332 47478 23862 47478 23861 47478 23332 47479 23861 47479 23910 47479 23889 47480 23872 47480 23890 47480 23890 47481 23872 47481 23873 47481 23890 47482 23873 47482 23874 47482 23874 47483 23873 47483 23875 47483 23874 47484 23875 47484 23876 47484 23876 47485 23875 47485 23328 47485 23876 47486 23328 47486 23891 47486 23317 47487 23877 47487 23325 47487 23325 47488 23877 47488 23878 47488 23325 47489 23878 47489 23923 47489 23315 47490 23879 47490 23880 47490 23880 47491 23879 47491 23926 47491 23880 47492 23926 47492 23317 47492 23892 47493 22693 47493 23894 47493 23894 47494 22693 47494 22691 47494 23894 47495 22691 47495 23319 47495 23881 47496 23895 47496 23882 47496 23893 47497 23900 47497 23882 47497 23882 47498 23900 47498 23883 47498 23882 47499 23883 47499 23881 47499 23881 47500 23883 47500 23884 47500 23881 47501 23884 47501 23885 47501 23885 47502 23884 47502 23003 47502 23886 47503 23863 47503 23887 47503 23887 47504 23863 47504 23867 47504 23887 47505 23867 47505 23904 47505 23904 47506 23867 47506 23869 47506 23904 47507 23869 47507 23903 47507 23903 47508 23869 47508 23888 47508 23903 47509 23888 47509 23906 47509 23906 47510 23888 47510 23911 47510 23906 47511 23911 47511 23859 47511 23912 47512 23889 47512 23918 47512 23918 47513 23889 47513 23890 47513 23918 47514 23890 47514 23917 47514 23917 47515 23890 47515 23874 47515 23917 47516 23874 47516 23914 47516 23914 47517 23874 47517 23876 47517 23914 47518 23876 47518 23921 47518 23921 47519 23876 47519 23891 47519 23921 47520 23891 47520 23924 47520 23894 47521 23896 47521 23892 47521 23892 47522 23896 47522 23006 47522 23892 47523 23006 47523 22695 47523 23893 47524 23882 47524 23894 47524 23894 47525 23882 47525 23895 47525 23894 47526 23895 47526 23896 47526 23896 47527 23895 47527 23897 47527 23896 47528 23897 47528 23006 47528 23885 47529 23004 47529 23881 47529 23881 47530 23004 47530 23898 47530 23881 47531 23898 47531 23895 47531 23895 47532 23898 47532 23899 47532 23895 47533 23899 47533 23897 47533 23900 47534 23866 47534 23883 47534 23883 47535 23866 47535 23864 47535 23883 47536 23864 47536 23884 47536 23884 47537 23864 47537 23902 47537 23884 47538 23902 47538 23003 47538 23003 47539 23902 47539 23002 47539 23337 47540 23863 47540 23901 47540 23901 47541 23863 47541 23886 47541 23901 47542 23886 47542 23902 47542 23902 47543 23886 47543 23001 47543 23902 47544 23001 47544 23002 47544 23903 47545 23909 47545 23904 47545 23904 47546 23909 47546 22999 47546 23904 47547 22999 47547 23887 47547 23887 47548 22999 47548 23000 47548 23887 47549 23000 47549 23886 47549 23886 47550 23000 47550 23905 47550 23886 47551 23905 47551 23001 47551 23860 47552 22995 47552 23906 47552 23906 47553 22995 47553 23907 47553 23906 47554 23907 47554 23903 47554 23903 47555 23907 47555 23908 47555 23903 47556 23908 47556 23909 47556 23871 47557 23910 47557 23911 47557 23911 47558 23910 47558 23861 47558 23911 47559 23861 47559 23859 47559 23859 47560 23861 47560 23913 47560 23859 47561 23913 47561 23858 47561 23858 47562 23913 47562 22992 47562 23330 47563 23889 47563 23862 47563 23862 47564 23889 47564 23912 47564 23862 47565 23912 47565 23913 47565 23913 47566 23912 47566 22993 47566 23913 47567 22993 47567 22992 47567 23914 47568 23915 47568 23917 47568 23917 47569 23915 47569 23916 47569 23917 47570 23916 47570 23918 47570 23918 47571 23916 47571 22990 47571 23918 47572 22990 47572 23912 47572 23912 47573 22990 47573 23919 47573 23912 47574 23919 47574 22993 47574 22986 47575 23920 47575 23921 47575 23921 47576 23920 47576 23922 47576 23921 47577 23922 47577 23914 47577 23914 47578 23922 47578 22987 47578 23914 47579 22987 47579 23915 47579 23328 47580 23923 47580 23891 47580 23891 47581 23923 47581 23878 47581 23891 47582 23878 47582 23924 47582 23924 47583 23878 47583 23925 47583 23924 47584 23925 47584 22985 47584 22985 47585 23925 47585 22983 47585 23929 47586 23930 47586 23927 47586 23317 47587 23926 47587 23877 47587 23877 47588 23926 47588 23929 47588 23877 47589 23929 47589 23925 47589 23925 47590 23929 47590 23927 47590 23925 47591 23927 47591 22983 47591 23879 47592 23928 47592 23926 47592 23926 47593 23928 47593 22606 47593 23926 47594 22606 47594 23929 47594 23929 47595 22606 47595 22605 47595 23929 47596 22605 47596 23930 47596 23930 47597 22605 47597 22646 47597 23930 47598 22646 47598 22981 47598 22597 47599 23931 47599 23935 47599 23934 47600 23931 47600 22597 47600 22595 47601 23934 47601 22597 47601 22597 47602 23939 47602 23940 47602 23932 47603 23939 47603 22597 47603 23935 47604 23932 47604 22597 47604 22595 47605 23933 47605 23934 47605 23934 47606 23933 47606 23943 47606 23934 47607 23943 47607 23931 47607 23931 47608 23943 47608 23936 47608 23931 47609 23936 47609 23935 47609 23935 47610 23936 47610 23937 47610 23935 47611 23937 47611 23932 47611 23932 47612 23937 47612 23938 47612 23932 47613 23938 47613 23939 47613 23939 47614 23938 47614 23941 47614 23939 47615 23941 47615 23940 47615 23940 47616 23941 47616 22589 47616 23933 47617 23942 47617 23943 47617 23943 47618 23942 47618 23944 47618 23943 47619 23944 47619 23936 47619 23936 47620 23944 47620 23350 47620 23936 47621 23350 47621 23937 47621 23937 47622 23350 47622 23945 47622 23937 47623 23945 47623 23938 47623 23938 47624 23945 47624 23358 47624 23938 47625 23358 47625 23941 47625 23941 47626 23358 47626 23946 47626 23941 47627 23946 47627 22589 47627 22589 47628 23946 47628 23346 47628 23947 47629 22580 47629 23953 47629 23956 47630 23948 47630 23947 47630 23957 47631 23949 47631 23947 47631 23952 47632 23959 47632 23947 47632 23951 47633 23950 47633 23947 47633 23947 47634 23962 47634 23963 47634 23961 47635 23962 47635 23947 47635 23950 47636 23961 47636 23947 47636 23959 47637 23951 47637 23947 47637 23949 47638 23952 47638 23947 47638 23948 47639 23957 47639 23947 47639 23953 47640 23956 47640 23947 47640 22580 47641 23954 47641 23953 47641 23953 47642 23954 47642 23955 47642 23953 47643 23955 47643 23956 47643 23956 47644 23955 47644 23948 47644 23948 47645 23955 47645 23958 47645 23948 47646 23958 47646 23957 47646 23957 47647 23958 47647 23949 47647 23949 47648 23958 47648 23966 47648 23949 47649 23966 47649 23952 47649 23952 47650 23966 47650 23959 47650 23959 47651 23966 47651 23960 47651 23959 47652 23960 47652 23951 47652 23951 47653 23960 47653 23950 47653 23950 47654 23960 47654 23968 47654 23950 47655 23968 47655 23961 47655 23961 47656 23968 47656 23962 47656 23962 47657 23968 47657 22571 47657 23962 47658 22571 47658 23963 47658 23954 47659 23964 47659 23955 47659 23955 47660 23964 47660 23371 47660 23955 47661 23371 47661 23958 47661 23958 47662 23371 47662 23965 47662 23958 47663 23965 47663 23966 47663 23966 47664 23965 47664 23967 47664 23966 47665 23967 47665 23960 47665 23960 47666 23967 47666 23378 47666 23960 47667 23378 47667 23968 47667 23968 47668 23378 47668 23379 47668 23968 47669 23379 47669 22571 47669 22571 47670 23379 47670 23969 47670 23971 47671 23970 47671 23972 47671 23973 47672 23970 47672 23971 47672 22564 47673 23973 47673 23971 47673 23971 47674 23977 47674 22565 47674 23974 47675 23977 47675 23971 47675 23972 47676 23974 47676 23971 47676 22564 47677 23978 47677 23973 47677 23973 47678 23978 47678 23979 47678 23973 47679 23979 47679 23970 47679 23970 47680 23979 47680 23980 47680 23970 47681 23980 47681 23972 47681 23972 47682 23980 47682 23982 47682 23972 47683 23982 47683 23974 47683 23974 47684 23982 47684 23975 47684 23974 47685 23975 47685 23977 47685 23977 47686 23975 47686 23976 47686 23977 47687 23976 47687 22565 47687 22565 47688 23976 47688 22555 47688 23978 47689 22554 47689 23979 47689 23979 47690 22554 47690 23981 47690 23979 47691 23981 47691 23980 47691 23980 47692 23981 47692 23355 47692 23980 47693 23355 47693 23982 47693 23982 47694 23355 47694 23983 47694 23982 47695 23983 47695 23975 47695 23975 47696 23983 47696 23353 47696 23975 47697 23353 47697 23976 47697 23976 47698 23353 47698 23349 47698 23976 47699 23349 47699 22555 47699 22555 47700 23349 47700 23984 47700 23989 47701 23985 47701 23240 47701 23240 47702 23985 47702 23462 47702 23986 47703 23416 47703 23453 47703 23986 47704 23453 47704 23244 47704 23244 47705 23453 47705 23987 47705 23244 47706 23987 47706 23988 47706 23987 47707 23450 47707 23988 47707 23988 47708 23450 47708 23985 47708 23988 47709 23985 47709 23989 47709 23240 47710 23462 47710 23461 47710 23240 47711 23461 47711 23990 47711 23990 47712 23461 47712 23991 47712 23990 47713 23991 47713 23992 47713 23992 47714 23991 47714 23993 47714 23992 47715 23993 47715 23242 47715 23242 47716 23993 47716 23410 47716 23242 47717 23410 47717 23994 47717 23239 47718 23446 47718 23986 47718 23986 47719 23446 47719 23416 47719 23408 47720 23999 47720 23410 47720 23410 47721 23999 47721 23994 47721 23997 47722 23995 47722 23996 47722 23997 47723 23996 47723 23998 47723 23998 47724 23996 47724 23445 47724 23998 47725 23445 47725 23237 47725 23237 47726 23445 47726 23446 47726 23237 47727 23446 47727 23239 47727 23999 47728 23408 47728 24001 47728 23999 47729 24001 47729 24000 47729 24000 47730 24001 47730 24002 47730 24000 47731 24002 47731 24003 47731 24003 47732 24002 47732 23448 47732 24003 47733 23448 47733 24004 47733 23448 47734 23995 47734 24004 47734 24004 47735 23995 47735 23997 47735 24005 47736 24006 47736 23837 47736 23837 47737 24007 47737 24005 47737 24005 47738 24007 47738 23840 47738 24005 47739 23840 47739 23841 47739 24013 47740 23133 47740 24009 47740 24009 47741 23133 47741 24008 47741 24009 47742 24008 47742 24010 47742 24010 47743 24008 47743 24011 47743 24010 47744 24011 47744 23843 47744 23843 47745 24011 47745 24012 47745 23843 47746 24012 47746 23841 47746 23841 47747 24012 47747 23385 47747 23841 47748 23385 47748 24005 47748 23133 47749 24013 47749 23131 47749 23131 47750 24013 47750 23229 47750 23131 47751 23229 47751 23130 47751 23130 47752 23229 47752 24015 47752 23130 47753 24015 47753 24014 47753 24014 47754 24015 47754 23139 47754 23139 47755 24015 47755 24016 47755 23139 47756 24016 47756 24017 47756 24016 47757 23233 47757 24017 47757 24017 47758 23233 47758 24018 47758 24017 47759 24018 47759 24019 47759 24018 47760 24020 47760 24019 47760 24019 47761 24020 47761 23231 47761 24019 47762 23231 47762 24021 47762 24021 47763 23231 47763 23230 47763 24021 47764 23230 47764 24022 47764 23230 47765 22957 47765 24022 47765 24022 47766 22957 47766 22958 47766 24022 47767 22958 47767 24023 47767 24028 47768 23158 47768 23065 47768 24028 47769 23065 47769 24024 47769 22958 47770 22960 47770 24023 47770 24023 47771 22960 47771 22961 47771 24023 47772 22961 47772 24025 47772 24025 47773 22961 47773 24024 47773 24025 47774 24024 47774 24026 47774 24026 47775 24024 47775 23065 47775 23829 47776 24027 47776 23828 47776 23828 47777 24027 47777 24029 47777 23828 47778 24029 47778 24028 47778 24028 47779 24029 47779 23158 47779 24030 47780 23156 47780 23829 47780 23829 47781 23156 47781 24027 47781 23156 47782 24030 47782 24031 47782 23156 47783 24031 47783 24032 47783 24032 47784 24031 47784 24034 47784 24032 47785 24034 47785 24033 47785 24033 47786 24034 47786 23505 47786 24033 47787 23505 47787 23163 47787 23497 47788 24035 47788 23505 47788 23505 47789 24035 47789 23163 47789 24035 47790 23497 47790 23496 47790 24035 47791 23496 47791 24036 47791 24036 47792 23496 47792 24037 47792 24036 47793 24037 47793 24038 47793 23438 47794 23154 47794 24037 47794 24037 47795 23154 47795 24038 47795 23154 47796 23438 47796 23441 47796 23154 47797 23441 47797 24039 47797 24039 47798 23441 47798 23442 47798 24039 47799 23442 47799 24040 47799 24040 47800 23442 47800 23208 47800 24040 47801 23208 47801 23152 47801 23152 47802 23208 47802 23210 47802 23152 47803 23210 47803 24041 47803 24041 47804 23210 47804 23212 47804 24041 47805 23212 47805 24042 47805 24042 47806 23212 47806 23213 47806 24042 47807 23213 47807 23142 47807 23142 47808 23213 47808 24043 47808 23142 47809 24043 47809 23145 47809 23145 47810 24043 47810 23216 47810 23145 47811 23216 47811 23150 47811 22527 47812 24044 47812 23434 47812 22527 47813 23434 47813 24045 47813 24045 47814 23434 47814 23435 47814 24045 47815 23435 47815 24046 47815 24046 47816 23435 47816 24047 47816 24046 47817 24047 47817 24049 47817 23418 47818 24048 47818 24047 47818 24047 47819 24048 47819 24049 47819 24048 47820 23418 47820 23494 47820 24048 47821 23494 47821 24050 47821 24050 47822 23494 47822 24051 47822 24050 47823 24051 47823 23073 47823 23500 47824 24052 47824 24051 47824 24051 47825 24052 47825 23073 47825 24052 47826 23500 47826 23499 47826 24052 47827 23499 47827 23071 47827 23071 47828 23499 47828 23503 47828 23071 47829 23503 47829 24055 47829 23503 47830 24053 47830 24055 47830 24055 47831 24053 47831 24054 47831 24055 47832 24054 47832 23069 47832 24059 47833 24056 47833 24054 47833 24054 47834 24056 47834 23069 47834 23826 47835 24057 47835 23825 47835 23825 47836 24057 47836 24058 47836 23825 47837 24058 47837 24059 47837 24059 47838 24058 47838 24056 47838 24062 47839 23079 47839 24060 47839 24060 47840 24061 47840 24062 47840 24062 47841 24061 47841 24063 47841 24062 47842 24063 47842 24064 47842 24063 47843 23226 47843 24064 47843 24064 47844 23226 47844 23224 47844 24064 47845 23224 47845 23093 47845 23093 47846 23224 47846 24065 47846 23093 47847 24065 47847 24066 47847 24067 47848 23095 47848 24066 47848 24066 47849 23095 47849 23094 47849 24066 47850 23094 47850 23093 47850 23228 47851 23100 47851 24068 47851 24068 47852 23100 47852 24067 47852 24068 47853 24067 47853 23227 47853 23227 47854 24067 47854 24066 47854 22709 47855 22710 47855 24071 47855 23100 47856 23228 47856 23110 47856 23110 47857 23228 47857 24069 47857 23110 47858 24069 47858 23098 47858 23098 47859 24069 47859 24070 47859 23098 47860 24070 47860 23104 47860 23104 47861 24070 47861 23832 47861 23104 47862 23832 47862 23388 47862 23388 47863 23832 47863 23833 47863 23388 47864 23833 47864 24071 47864 24071 47865 23833 47865 23835 47865 24071 47866 23835 47866 22709 47866 24074 47867 24075 47867 23510 47867 23510 47868 24075 47868 23428 47868 23510 47869 23428 47869 23509 47869 23509 47870 23428 47870 24072 47870 23465 47871 23432 47871 23464 47871 23464 47872 23432 47872 24073 47872 23464 47873 24073 47873 24074 47873 24074 47874 24073 47874 24075 47874 24080 47875 24076 47875 23427 47875 23449 47876 24077 47876 24078 47876 24078 47877 24077 47877 24079 47877 23449 47878 24080 47878 24077 47878 24077 47879 24080 47879 23427 47879 24077 47880 23427 47880 23514 47880 23514 47881 23427 47881 23433 47881 23514 47882 23433 47882 24081 47882 24081 47883 23433 47883 24082 47883 24081 47884 24082 47884 23465 47884 23465 47885 24082 47885 23432 47885 23419 47886 23426 47886 23493 47886 23412 47887 24083 47887 22938 47887 22938 47888 24083 47888 23419 47888 22938 47889 23419 47889 22939 47889 22939 47890 23419 47890 23493 47890 22939 47891 23493 47891 24084 47891 22945 47892 24085 47892 22944 47892 22944 47893 24085 47893 23429 47893 22944 47894 23429 47894 23431 47894 23415 47895 23414 47895 23431 47895 23431 47896 23414 47896 24086 47896 23431 47897 24086 47897 22944 47897 24090 47898 23409 47898 24087 47898 23409 47899 23455 47899 24087 47899 24087 47900 23455 47900 23456 47900 24087 47901 23456 47901 23457 47901 23517 47902 24093 47902 24088 47902 24088 47903 24093 47903 23421 47903 24088 47904 23421 47904 23516 47904 23516 47905 23421 47905 23420 47905 23516 47906 23420 47906 24087 47906 24087 47907 23420 47907 24089 47907 24087 47908 24089 47908 24090 47908 23466 47909 24096 47909 24091 47909 24091 47910 24096 47910 24092 47910 24091 47911 24092 47911 23517 47911 23517 47912 24092 47912 24093 47912 23498 47913 23422 47913 24094 47913 24094 47914 23422 47914 24095 47914 24094 47915 24095 47915 23466 47915 23466 47916 24095 47916 24096 47916 24098 47917 23411 47917 24097 47917 27223 47918 24098 47918 24099 47918 24099 47919 24098 47919 24097 47919 24099 47920 24097 47920 23039 47920 27217 47921 24101 47921 23447 47921 27217 47922 23447 47922 27218 47922 27218 47923 23447 47923 24100 47923 27218 47924 24100 47924 27219 47924 27219 47925 24100 47925 24098 47925 27219 47926 24098 47926 27223 47926 23288 47927 24101 47927 24104 47927 24104 47928 24101 47928 27217 47928 27251 47929 24102 47929 23444 47929 27251 47930 23444 47930 27214 47930 27214 47931 23444 47931 23443 47931 27214 47932 23443 47932 24103 47932 24103 47933 23443 47933 23288 47933 24103 47934 23288 47934 24104 47934 24736 47935 22941 47935 22943 47935 27251 47936 24736 47936 24102 47936 24102 47937 24736 47937 22943 47937 24102 47938 22943 47938 24105 47938 27226 47939 27225 47939 24106 47939 23038 47940 27226 47940 24107 47940 24107 47941 27226 47941 24106 47941 24107 47942 24106 47942 23495 47942 24108 47943 24111 47943 27225 47943 27225 47944 24111 47944 24106 47944 22500 47945 24109 47945 23440 47945 22500 47946 23440 47946 24110 47946 24110 47947 23440 47947 23439 47947 24110 47948 23439 47948 27250 47948 27250 47949 23439 47949 24111 47949 27250 47950 24111 47950 24108 47950 27237 47951 24117 47951 24112 47951 27237 47952 24112 47952 24113 47952 24113 47953 24112 47953 22965 47953 24113 47954 22965 47954 27249 47954 27249 47955 22965 47955 22963 47955 27249 47956 22963 47956 27248 47956 27248 47957 22963 47957 22962 47957 27248 47958 22962 47958 24114 47958 24114 47959 22962 47959 22980 47959 24114 47960 22980 47960 24115 47960 24119 47961 23437 47961 23436 47961 24119 47962 23436 47962 27220 47962 27220 47963 23436 47963 24116 47963 27220 47964 24116 47964 24118 47964 24118 47965 24116 47965 24117 47965 24118 47966 24117 47966 27237 47966 27222 47967 23417 47967 24119 47967 24119 47968 23417 47968 23437 47968 23417 47969 27222 47969 24741 47969 24741 47970 24120 47970 23417 47970 23417 47971 24120 47971 22936 47971 23417 47972 22936 47972 23492 47972 24121 47973 23195 47973 23198 47973 24121 47974 23201 47974 23202 47974 23200 47975 23201 47975 24121 47975 23198 47976 23200 47976 24121 47976 24121 47977 23207 47977 22495 47977 24122 47978 23207 47978 24121 47978 23202 47979 24122 47979 24121 47979 24126 47980 24123 47980 24125 47980 23176 47981 24123 47981 24126 47981 23172 47982 23176 47982 24126 47982 24126 47983 23185 47983 23186 47983 24124 47984 23185 47984 24126 47984 24125 47985 24124 47985 24126 47985 22489 47986 24128 47986 24132 47986 24127 47987 24128 47987 22489 47987 23182 47988 24127 47988 22489 47988 22489 47989 24129 47989 24130 47989 24131 47990 24129 47990 22489 47990 24132 47991 24131 47991 22489 47991 24133 47992 23179 47992 23190 47992 24133 47993 23206 47993 24134 47993 23189 47994 23206 47994 24133 47994 23190 47995 23189 47995 24133 47995 24133 47996 23203 47996 24135 47996 23204 47997 23203 47997 24133 47997 24134 47998 23204 47998 24133 47998 24142 47999 24136 47999 23558 47999 23546 48000 23541 48000 23543 48000 23546 48001 24139 48001 23557 48001 23547 48002 24137 48002 23546 48002 23546 48003 24137 48003 23551 48003 23546 48004 23551 48004 23541 48004 23543 48005 23544 48005 23546 48005 23546 48006 23544 48006 24138 48006 23546 48007 24138 48007 24139 48007 24140 48008 23555 48008 24141 48008 24141 48009 23555 48009 23553 48009 24141 48010 23553 48010 23558 48010 23558 48011 23553 48011 23546 48011 23558 48012 23546 48012 24142 48012 24142 48013 23546 48013 23557 48013 23535 48014 23526 48014 24146 48014 23529 48015 24143 48015 23527 48015 23527 48016 24143 48016 23524 48016 23527 48017 23524 48017 23526 48017 23526 48018 23524 48018 23525 48018 23526 48019 23525 48019 23521 48019 23521 48020 23523 48020 23526 48020 23526 48021 23523 48021 24144 48021 23526 48022 24144 48022 24146 48022 23536 48023 23538 48023 24145 48023 24145 48024 23538 48024 23539 48024 24145 48025 23539 48025 24146 48025 24146 48026 23539 48026 23518 48026 23518 48027 23532 48027 24146 48027 24146 48028 23532 48028 23533 48028 24146 48029 23533 48029 23535 48029 24302 48030 24299 48030 24157 48030 24157 48031 24299 48031 24298 48031 24147 48032 22482 48032 24160 48032 24148 48033 24149 48033 24155 48033 24155 48034 24149 48034 24150 48034 24155 48035 24150 48035 22476 48035 24151 48036 24312 48036 24155 48036 24155 48037 24312 48037 24152 48037 24155 48038 24152 48038 24153 48038 24153 48039 24154 48039 24155 48039 24155 48040 24154 48040 24307 48040 24155 48041 24307 48041 24306 48041 24306 48042 24156 48042 24155 48042 24155 48043 24156 48043 24304 48043 24155 48044 24304 48044 22479 48044 22479 48045 24304 48045 24157 48045 24157 48046 24304 48046 24303 48046 24157 48047 24303 48047 24302 48047 24298 48048 24158 48048 24157 48048 24157 48049 24158 48049 24295 48049 24157 48050 24295 48050 22488 48050 22488 48051 22486 48051 24157 48051 24157 48052 22486 48052 24147 48052 24157 48053 24147 48053 24159 48053 24159 48054 24147 48054 24160 48054 22476 48055 22473 48055 24155 48055 24155 48056 22473 48056 24314 48056 24155 48057 24314 48057 24151 48057 24748 48058 24747 48058 26080 48058 26080 48059 24747 48059 24161 48059 26080 48060 24161 48060 26078 48060 26078 48061 24161 48061 24744 48061 26078 48062 24744 48062 26077 48062 26077 48063 24744 48063 24742 48063 26077 48064 24742 48064 21813 48064 21813 48065 24742 48065 24162 48065 21813 48066 24162 48066 21812 48066 21812 48067 24162 48067 22213 48067 21812 48068 22213 48068 24163 48068 24163 48069 22213 48069 22212 48069 24163 48070 22212 48070 21811 48070 21811 48071 22212 48071 22211 48071 21811 48072 22211 48072 21809 48072 21809 48073 22211 48073 22210 48073 21809 48074 22210 48074 24164 48074 24164 48075 22210 48075 24165 48075 24164 48076 24165 48076 21806 48076 21806 48077 24165 48077 24166 48077 21806 48078 24166 48078 24167 48078 24167 48079 24166 48079 24168 48079 24167 48080 24168 48080 26082 48080 26082 48081 24168 48081 24169 48081 26082 48082 24169 48082 24170 48082 24170 48083 24169 48083 24748 48083 24170 48084 24748 48084 26080 48084 24755 48085 24754 48085 25814 48085 25814 48086 24754 48086 24753 48086 25814 48087 24753 48087 25812 48087 25812 48088 24753 48088 24751 48088 25812 48089 24751 48089 25811 48089 25811 48090 24751 48090 24750 48090 25811 48091 24750 48091 21856 48091 21856 48092 24750 48092 22206 48092 21856 48093 22206 48093 21855 48093 21855 48094 22206 48094 24171 48094 21855 48095 24171 48095 21852 48095 21852 48096 24171 48096 22204 48096 21852 48097 22204 48097 21851 48097 21851 48098 22204 48098 22203 48098 21851 48099 22203 48099 24172 48099 24172 48100 22203 48100 22200 48100 24172 48101 22200 48101 24173 48101 24173 48102 22200 48102 24174 48102 24173 48103 24174 48103 24176 48103 24176 48104 24174 48104 24175 48104 24176 48105 24175 48105 24177 48105 24177 48106 24175 48106 24757 48106 24177 48107 24757 48107 25816 48107 25816 48108 24757 48108 24756 48108 25816 48109 24756 48109 24178 48109 24178 48110 24756 48110 24755 48110 24178 48111 24755 48111 25814 48111 22195 48112 24179 48112 21860 48112 21860 48113 24179 48113 22193 48113 21860 48114 22193 48114 21858 48114 21858 48115 22193 48115 24180 48115 21858 48116 24180 48116 24181 48116 24181 48117 24180 48117 22191 48117 24181 48118 22191 48118 21857 48118 21857 48119 22191 48119 22190 48119 21857 48120 22190 48120 24183 48120 24183 48121 22190 48121 24182 48121 24183 48122 24182 48122 25808 48122 25808 48123 24182 48123 24758 48123 25808 48124 24758 48124 24184 48124 24184 48125 24758 48125 24762 48125 24184 48126 24762 48126 25806 48126 25806 48127 24762 48127 24185 48127 25806 48128 24185 48128 25805 48128 25805 48129 24185 48129 24759 48129 25805 48130 24759 48130 24186 48130 24186 48131 24759 48131 22197 48131 24186 48132 22197 48132 24187 48132 24187 48133 22197 48133 24188 48133 24187 48134 24188 48134 21861 48134 21861 48135 24188 48135 22195 48135 21861 48136 22195 48136 21860 48136 24197 48137 24198 48137 24189 48137 24189 48138 24198 48138 24190 48138 24189 48139 24190 48139 24192 48139 24192 48140 24190 48140 24191 48140 24192 48141 24191 48141 21869 48141 21869 48142 24191 48142 24193 48142 21869 48143 24193 48143 24194 48143 24194 48144 24193 48144 22187 48144 24194 48145 22187 48145 21868 48145 21868 48146 22187 48146 22185 48146 21868 48147 22185 48147 21867 48147 22185 48148 22184 48148 21867 48148 21867 48149 22184 48149 22183 48149 21867 48150 22183 48150 21865 48150 21865 48151 22183 48151 22182 48151 21865 48152 22182 48152 21864 48152 21864 48153 22182 48153 22180 48153 21864 48154 22180 48154 21863 48154 21863 48155 22180 48155 22179 48155 21863 48156 22179 48156 24195 48156 24195 48157 22179 48157 24774 48157 24195 48158 24774 48158 24196 48158 24196 48159 24774 48159 24772 48159 24196 48160 24772 48160 24197 48160 24197 48161 24772 48161 24769 48161 24197 48162 24769 48162 24198 48162 22176 48163 22174 48163 24199 48163 24199 48164 22174 48164 24201 48164 24199 48165 24201 48165 24200 48165 24200 48166 24201 48166 24202 48166 24200 48167 24202 48167 24203 48167 24203 48168 24202 48168 22171 48168 24203 48169 22171 48169 25799 48169 25799 48170 22171 48170 24204 48170 25799 48171 24204 48171 25798 48171 25798 48172 24204 48172 24780 48172 25798 48173 24780 48173 24205 48173 24205 48174 24780 48174 24206 48174 24205 48175 24206 48175 24208 48175 24208 48176 24206 48176 24207 48176 24208 48177 24207 48177 24210 48177 24210 48178 24207 48178 24209 48178 24210 48179 24209 48179 25796 48179 25796 48180 24209 48180 24776 48180 25796 48181 24776 48181 24211 48181 24211 48182 24776 48182 22178 48182 24211 48183 22178 48183 24212 48183 24212 48184 22178 48184 24213 48184 24212 48185 24213 48185 24214 48185 24214 48186 24213 48186 22176 48186 24214 48187 22176 48187 24199 48187 24786 48188 24785 48188 25790 48188 25790 48189 24785 48189 24783 48189 25790 48190 24783 48190 25789 48190 25789 48191 24783 48191 24216 48191 25789 48192 24216 48192 24215 48192 24215 48193 24216 48193 24781 48193 24215 48194 24781 48194 24217 48194 24217 48195 24781 48195 24218 48195 24217 48196 24218 48196 21878 48196 21878 48197 24218 48197 24219 48197 21878 48198 24219 48198 24220 48198 24220 48199 24219 48199 24221 48199 24220 48200 24221 48200 21877 48200 21877 48201 24221 48201 22169 48201 21877 48202 22169 48202 24222 48202 24222 48203 22169 48203 22167 48203 24222 48204 22167 48204 21875 48204 21875 48205 22167 48205 22166 48205 21875 48206 22166 48206 24223 48206 24223 48207 22166 48207 24224 48207 24223 48208 24224 48208 24225 48208 24225 48209 24224 48209 24789 48209 24225 48210 24789 48210 25794 48210 25794 48211 24789 48211 24786 48211 25794 48212 24786 48212 25790 48212 24794 48213 24226 48213 25783 48213 25783 48214 24226 48214 24792 48214 25783 48215 24792 48215 25782 48215 25782 48216 24792 48216 24227 48216 25782 48217 24227 48217 25780 48217 25780 48218 24227 48218 24791 48218 25780 48219 24791 48219 24228 48219 24228 48220 24791 48220 24229 48220 24228 48221 24229 48221 24230 48221 24230 48222 24229 48222 22164 48222 24230 48223 22164 48223 24231 48223 24231 48224 22164 48224 24232 48224 24231 48225 24232 48225 21882 48225 21882 48226 24232 48226 22162 48226 21882 48227 22162 48227 21880 48227 21880 48228 22162 48228 24233 48228 21880 48229 24233 48229 21879 48229 21879 48230 24233 48230 22159 48230 21879 48231 22159 48231 25787 48231 25787 48232 22159 48232 24234 48232 25787 48233 24234 48233 24235 48233 24235 48234 24234 48234 24795 48234 24235 48235 24795 48235 25784 48235 25784 48236 24795 48236 24794 48236 25784 48237 24794 48237 25783 48237 24799 48238 24236 48238 24251 48238 24251 48239 24236 48239 24798 48239 24251 48240 24798 48240 24238 48240 24238 48241 24798 48241 24237 48241 24238 48242 24237 48242 24239 48242 24239 48243 24237 48243 24240 48243 24239 48244 24240 48244 21891 48244 21891 48245 24240 48245 24241 48245 21891 48246 24241 48246 21890 48246 21890 48247 24241 48247 22154 48247 21890 48248 22154 48248 21889 48248 21889 48249 22154 48249 22153 48249 21889 48250 22153 48250 24242 48250 24242 48251 22153 48251 24243 48251 24242 48252 24243 48252 21888 48252 21888 48253 24243 48253 24244 48253 21888 48254 24244 48254 21885 48254 21885 48255 24244 48255 24246 48255 21885 48256 24246 48256 24245 48256 24245 48257 24246 48257 24248 48257 24245 48258 24248 48258 24247 48258 24247 48259 24248 48259 24249 48259 24247 48260 24249 48260 25778 48260 25778 48261 24249 48261 24801 48261 25778 48262 24801 48262 24250 48262 24250 48263 24801 48263 24799 48263 24250 48264 24799 48264 24251 48264 24808 48265 24252 48265 25775 48265 25775 48266 24252 48266 24805 48266 25775 48267 24805 48267 25773 48267 25773 48268 24805 48268 24804 48268 25773 48269 24804 48269 24253 48269 24253 48270 24804 48270 24803 48270 24253 48271 24803 48271 24254 48271 24254 48272 24803 48272 24255 48272 24254 48273 24255 48273 24256 48273 24256 48274 24255 48274 22149 48274 24256 48275 22149 48275 21897 48275 21897 48276 22149 48276 22148 48276 21897 48277 22148 48277 21896 48277 21896 48278 22148 48278 24257 48278 21896 48279 24257 48279 24258 48279 24258 48280 24257 48280 22146 48280 24258 48281 22146 48281 24259 48281 24259 48282 22146 48282 22144 48282 24259 48283 22144 48283 21893 48283 21893 48284 22144 48284 22142 48284 21893 48285 22142 48285 21892 48285 21892 48286 22142 48286 22141 48286 21892 48287 22141 48287 24260 48287 24260 48288 22141 48288 24810 48288 24260 48289 24810 48289 24261 48289 24261 48290 24810 48290 24808 48290 24261 48291 24808 48291 25775 48291 24262 48292 22134 48292 21898 48292 21898 48293 22134 48293 22132 48293 21898 48294 22132 48294 24263 48294 24263 48295 22132 48295 24264 48295 24263 48296 24264 48296 24265 48296 24265 48297 24264 48297 24266 48297 24265 48298 24266 48298 25770 48298 25770 48299 24266 48299 24267 48299 25770 48300 24267 48300 25768 48300 25768 48301 24267 48301 24818 48301 25768 48302 24818 48302 24268 48302 24818 48303 24815 48303 24268 48303 24268 48304 24815 48304 24269 48304 24268 48305 24269 48305 25766 48305 25766 48306 24269 48306 24813 48306 25766 48307 24813 48307 25763 48307 25763 48308 24813 48308 24270 48308 25763 48309 24270 48309 24271 48309 24271 48310 24270 48310 22139 48310 24271 48311 22139 48311 21900 48311 21900 48312 22139 48312 24272 48312 21900 48313 24272 48313 24273 48313 24273 48314 24272 48314 22137 48314 24273 48315 22137 48315 24262 48315 24262 48316 22137 48316 22136 48316 24262 48317 22136 48317 22134 48317 22123 48318 21902 48318 22124 48318 22124 48319 21902 48319 24274 48319 22124 48320 24274 48320 24275 48320 24275 48321 24274 48321 21904 48321 24275 48322 21904 48322 24276 48322 24276 48323 21904 48323 21905 48323 24276 48324 21905 48324 24277 48324 24277 48325 21905 48325 24278 48325 24277 48326 24278 48326 22129 48326 22129 48327 24278 48327 24279 48327 22129 48328 24279 48328 24821 48328 24821 48329 24279 48329 24280 48329 24821 48330 24280 48330 24822 48330 24822 48331 24280 48331 25758 48331 24822 48332 25758 48332 24281 48332 24281 48333 25758 48333 25759 48333 24281 48334 25759 48334 24282 48334 24282 48335 25759 48335 25761 48335 24282 48336 25761 48336 24824 48336 24824 48337 25761 48337 24283 48337 24824 48338 24283 48338 24825 48338 24825 48339 24283 48339 24284 48339 24825 48340 24284 48340 24827 48340 24827 48341 24284 48341 25762 48341 24827 48342 25762 48342 22123 48342 22123 48343 25762 48343 21902 48343 24293 48344 24834 48344 24285 48344 24285 48345 24834 48345 24831 48345 24285 48346 24831 48346 25754 48346 25754 48347 24831 48347 24830 48347 25754 48348 24830 48348 21912 48348 21912 48349 24830 48349 24828 48349 21912 48350 24828 48350 24286 48350 24286 48351 24828 48351 24287 48351 24286 48352 24287 48352 21910 48352 21910 48353 24287 48353 22119 48353 21910 48354 22119 48354 24288 48354 22119 48355 22117 48355 24288 48355 24288 48356 22117 48356 22116 48356 24288 48357 22116 48357 24289 48357 24289 48358 22116 48358 22114 48358 24289 48359 22114 48359 24290 48359 24290 48360 22114 48360 22112 48360 24290 48361 22112 48361 21907 48361 21907 48362 22112 48362 24291 48362 21907 48363 24291 48363 25757 48363 25757 48364 24291 48364 24836 48364 25757 48365 24836 48365 24292 48365 24292 48366 24836 48366 24294 48366 24292 48367 24294 48367 24293 48367 24293 48368 24294 48368 24835 48368 24293 48369 24835 48369 24834 48369 22217 48370 24295 48370 24731 48370 24731 48371 24295 48371 24158 48371 24731 48372 24158 48372 24296 48372 24296 48373 24158 48373 24298 48373 24296 48374 24298 48374 24297 48374 24297 48375 24298 48375 24299 48375 24297 48376 24299 48376 24300 48376 24300 48377 24299 48377 24302 48377 24300 48378 24302 48378 24301 48378 24301 48379 24302 48379 24303 48379 24301 48380 24303 48380 24733 48380 24733 48381 24303 48381 24304 48381 24733 48382 24304 48382 24305 48382 24305 48383 24304 48383 24156 48383 24305 48384 24156 48384 24735 48384 24735 48385 24156 48385 24306 48385 24735 48386 24306 48386 24308 48386 24308 48387 24306 48387 24307 48387 24308 48388 24307 48388 24740 48388 24740 48389 24307 48389 24154 48389 24740 48390 24154 48390 24309 48390 24309 48391 24154 48391 24153 48391 24309 48392 24153 48392 24310 48392 24310 48393 24153 48393 24152 48393 24310 48394 24152 48394 24311 48394 24311 48395 24152 48395 24312 48395 24311 48396 24312 48396 24738 48396 24738 48397 24312 48397 24151 48397 24738 48398 24151 48398 24313 48398 24313 48399 24151 48399 24314 48399 24745 48400 24359 48400 24371 48400 24315 48401 24351 48401 24350 48401 22181 48402 24322 48402 24316 48402 24664 48403 24326 48403 22186 48403 22186 48404 22188 48404 24664 48404 24664 48405 22188 48405 22189 48405 24664 48406 22189 48406 24317 48406 24317 48407 22189 48407 24767 48407 24767 48408 24768 48408 24317 48408 24317 48409 24768 48409 24770 48409 24317 48410 24770 48410 24496 48410 24496 48411 24770 48411 24771 48411 24496 48412 24771 48412 24318 48412 24771 48413 24773 48413 24318 48413 24318 48414 24773 48414 24319 48414 24318 48415 24319 48415 24316 48415 24316 48416 24319 48416 24320 48416 24316 48417 24320 48417 22181 48417 24494 48418 24316 48418 24321 48418 24321 48419 24316 48419 24322 48419 24321 48420 24322 48420 24897 48420 24897 48421 24322 48421 24327 48421 24323 48422 24324 48422 24905 48422 24323 48423 24905 48423 24664 48423 24905 48424 24903 48424 24664 48424 24664 48425 24903 48425 24901 48425 24664 48426 24901 48426 24326 48426 24326 48427 24901 48427 24325 48427 24326 48428 24325 48428 24327 48428 24327 48429 24325 48429 24328 48429 24327 48430 24328 48430 24897 48430 24333 48431 24624 48431 24329 48431 24329 48432 24624 48432 24331 48432 24329 48433 24331 48433 24330 48433 24330 48434 24331 48434 24939 48434 24936 48435 24335 48435 24332 48435 24332 48436 24335 48436 24624 48436 24332 48437 24624 48437 24937 48437 24937 48438 24624 48438 24333 48438 24934 48439 24622 48439 24334 48439 24334 48440 24622 48440 24335 48440 24334 48441 24335 48441 24935 48441 24935 48442 24335 48442 24936 48442 24502 48443 24679 48443 24501 48443 24501 48444 24679 48444 24336 48444 24501 48445 24336 48445 24500 48445 24500 48446 24336 48446 24337 48446 24500 48447 24337 48447 24498 48447 24498 48448 24337 48448 24645 48448 24498 48449 24645 48449 24496 48449 24496 48450 24645 48450 24668 48450 24496 48451 24668 48451 24317 48451 24345 48452 24760 48452 24346 48452 24760 48453 24761 48453 24346 48453 24346 48454 24761 48454 24338 48454 24346 48455 24338 48455 24339 48455 24339 48456 24338 48456 24763 48456 24339 48457 24763 48457 24764 48457 24764 48458 24765 48458 24339 48458 24339 48459 24765 48459 24766 48459 24339 48460 24766 48460 24502 48460 24766 48461 24340 48461 24502 48461 24502 48462 24340 48462 24341 48462 24502 48463 24341 48463 24679 48463 24679 48464 24341 48464 22192 48464 24679 48465 22192 48465 22194 48465 24342 48466 24642 48466 22196 48466 22196 48467 24642 48467 24679 48467 22196 48468 24679 48468 24343 48468 24343 48469 24679 48469 22194 48469 24342 48470 24344 48470 24642 48470 24642 48471 24344 48471 24345 48471 24642 48472 24345 48472 24643 48472 24643 48473 24345 48473 24346 48473 24643 48474 24346 48474 24644 48474 24644 48475 24346 48475 24505 48475 24644 48476 24505 48476 24347 48476 24347 48477 24505 48477 24349 48477 24347 48478 24349 48478 24348 48478 24348 48479 24349 48479 24508 48479 24348 48480 24508 48480 24640 48480 24640 48481 24508 48481 24510 48481 24350 48482 24351 48482 24353 48482 24351 48483 24352 48483 24353 48483 24353 48484 24352 48484 24354 48484 24353 48485 24354 48485 24510 48485 24510 48486 24354 48486 24355 48486 24510 48487 24355 48487 24640 48487 24640 48488 24355 48488 22198 48488 24640 48489 22198 48489 22199 48489 22199 48490 22201 48490 24640 48490 24640 48491 22201 48491 22202 48491 24640 48492 22202 48492 24356 48492 24356 48493 22202 48493 22205 48493 24356 48494 22205 48494 24637 48494 24637 48495 22205 48495 24357 48495 24365 48496 24358 48496 24350 48496 24350 48497 24358 48497 24752 48497 24350 48498 24752 48498 24315 48498 24371 48499 24359 48499 24514 48499 24359 48500 24746 48500 24514 48500 24514 48501 24746 48501 24749 48501 24514 48502 24749 48502 24360 48502 24749 48503 24366 48503 24360 48503 24360 48504 24366 48504 24367 48504 24360 48505 24367 48505 24361 48505 24361 48506 24367 48506 24362 48506 24361 48507 24362 48507 24513 48507 24513 48508 24362 48508 24636 48508 24513 48509 24636 48509 24363 48509 24363 48510 24636 48510 24364 48510 24363 48511 24364 48511 24350 48511 24350 48512 24364 48512 24637 48512 24350 48513 24637 48513 24365 48513 24365 48514 24637 48514 24357 48514 24366 48515 22207 48515 24367 48515 24367 48516 22207 48516 22208 48516 24367 48517 22208 48517 24633 48517 22208 48518 24368 48518 24633 48518 24633 48519 24368 48519 22209 48519 24633 48520 22209 48520 24370 48520 24370 48521 22209 48521 24369 48521 24370 48522 24369 48522 22214 48522 22215 48523 22216 48523 24371 48523 24371 48524 22216 48524 24743 48524 24371 48525 24743 48525 24745 48525 22214 48526 22215 48526 24370 48526 24370 48527 22215 48527 24371 48527 24370 48528 24371 48528 24631 48528 24631 48529 24371 48529 24372 48529 24631 48530 24372 48530 24696 48530 24696 48531 24372 48531 24373 48531 24696 48532 24373 48532 24374 48532 24374 48533 24373 48533 24375 48533 24374 48534 24375 48534 24379 48534 24837 48535 24376 48535 24380 48535 24833 48536 24377 48536 24385 48536 24385 48537 24377 48537 24381 48537 24375 48538 24378 48538 24379 48538 24379 48539 24378 48539 24518 48539 24379 48540 24518 48540 24704 48540 24704 48541 24518 48541 24385 48541 24704 48542 24385 48542 24380 48542 24380 48543 24385 48543 24381 48543 24380 48544 24381 48544 24837 48544 24376 48545 22113 48545 24380 48545 24380 48546 22113 48546 22115 48546 24380 48547 22115 48547 24382 48547 24387 48548 22120 48548 24383 48548 24383 48549 22120 48549 22121 48549 24383 48550 22121 48550 24384 48550 24384 48551 22121 48551 24829 48551 24384 48552 24829 48552 24385 48552 24385 48553 24829 48553 24832 48553 24385 48554 24832 48554 24833 48554 22115 48555 24386 48555 24382 48555 24382 48556 24386 48556 22118 48556 24382 48557 22118 48557 24388 48557 22118 48558 24387 48558 24388 48558 24388 48559 24387 48559 24383 48559 24388 48560 24383 48560 24621 48560 24621 48561 24383 48561 24523 48561 24621 48562 24523 48562 24626 48562 24523 48563 24525 48563 24626 48563 24626 48564 24525 48564 24389 48564 24626 48565 24389 48565 24390 48565 24390 48566 24389 48566 24526 48566 24390 48567 24526 48567 24627 48567 24391 48568 24528 48568 24820 48568 24820 48569 24528 48569 24331 48569 24820 48570 24331 48570 22130 48570 24391 48571 24823 48571 24528 48571 24528 48572 24823 48572 24392 48572 24528 48573 24392 48573 24526 48573 24392 48574 24393 48574 24526 48574 24526 48575 24393 48575 24394 48575 24526 48576 24394 48576 24627 48576 24627 48577 24394 48577 24395 48577 24627 48578 24395 48578 24396 48578 24396 48579 24826 48579 24627 48579 24627 48580 24826 48580 22122 48580 24627 48581 22122 48581 24629 48581 22122 48582 24397 48582 24629 48582 24629 48583 24397 48583 22125 48583 24629 48584 22125 48584 24624 48584 22125 48585 22126 48585 24624 48585 24624 48586 22126 48586 22127 48586 24624 48587 22127 48587 24331 48587 24331 48588 22127 48588 22128 48588 24331 48589 22128 48589 22130 48589 24479 48590 24552 48590 24398 48590 24398 48591 24552 48591 24550 48591 24398 48592 24550 48592 24476 48592 24476 48593 24550 48593 24399 48593 24399 48594 24550 48594 24400 48594 24399 48595 24400 48595 24401 48595 24401 48596 24400 48596 24402 48596 24402 48597 24400 48597 24403 48597 24402 48598 24403 48598 24472 48598 24472 48599 24403 48599 24404 48599 24404 48600 24403 48600 24405 48600 24404 48601 24405 48601 24470 48601 24470 48602 24405 48602 24467 48602 24467 48603 24405 48603 24549 48603 24467 48604 24549 48604 24406 48604 24406 48605 24549 48605 24466 48605 24466 48606 24549 48606 24547 48606 24466 48607 24547 48607 24407 48607 24407 48608 24547 48608 24408 48608 24408 48609 24547 48609 24409 48609 24408 48610 24409 48610 24464 48610 24464 48611 24409 48611 24462 48611 24462 48612 24409 48612 24410 48612 24462 48613 24410 48613 24461 48613 24543 48614 24411 48614 24410 48614 24410 48615 24411 48615 24460 48615 24410 48616 24460 48616 24461 48616 24542 48617 24412 48617 24416 48617 24416 48618 24454 48618 24542 48618 24542 48619 24454 48619 24413 48619 24542 48620 24413 48620 24543 48620 24543 48621 24413 48621 24457 48621 24543 48622 24457 48622 24411 48622 24539 48623 24537 48623 24414 48623 24414 48624 24449 48624 24539 48624 24539 48625 24449 48625 24450 48625 24539 48626 24450 48626 24412 48626 24412 48627 24450 48627 24415 48627 24412 48628 24415 48628 24416 48628 24418 48629 24535 48629 24485 48629 24485 48630 24417 48630 24418 48630 24418 48631 24417 48631 24483 48631 24418 48632 24483 48632 24537 48632 24537 48633 24483 48633 24481 48633 24537 48634 24481 48634 24414 48634 24419 48635 24532 48635 24863 48635 24863 48636 24488 48636 24419 48636 24419 48637 24488 48637 24420 48637 24419 48638 24420 48638 24535 48638 24535 48639 24420 48639 24421 48639 24535 48640 24421 48640 24485 48640 24490 48641 24572 48641 24495 48641 24495 48642 24572 48642 24422 48642 24495 48643 24422 48643 24497 48643 24497 48644 24422 48644 24423 48644 24423 48645 24422 48645 24424 48645 24423 48646 24424 48646 24499 48646 24499 48647 24424 48647 24425 48647 24425 48648 24424 48648 24569 48648 24425 48649 24569 48649 24426 48649 24426 48650 24569 48650 24427 48650 24427 48651 24569 48651 24428 48651 24427 48652 24428 48652 24503 48652 24503 48653 24428 48653 24504 48653 24504 48654 24428 48654 24566 48654 24504 48655 24566 48655 24506 48655 24506 48656 24566 48656 24507 48656 24507 48657 24566 48657 24429 48657 24507 48658 24429 48658 24509 48658 24509 48659 24429 48659 24511 48659 24511 48660 24429 48660 24431 48660 24511 48661 24431 48661 24512 48661 24512 48662 24431 48662 24430 48662 24430 48663 24431 48663 24433 48663 24430 48664 24433 48664 24432 48664 24432 48665 24433 48665 24434 48665 24434 48666 24433 48666 24563 48666 24434 48667 24563 48667 24435 48667 24561 48668 24560 48668 24436 48668 24436 48669 24517 48669 24561 48669 24561 48670 24517 48670 24516 48670 24561 48671 24516 48671 24563 48671 24563 48672 24516 48672 24515 48672 24563 48673 24515 48673 24435 48673 24557 48674 24555 48674 24521 48674 24521 48675 24520 48675 24557 48675 24557 48676 24520 48676 24519 48676 24557 48677 24519 48677 24560 48677 24560 48678 24519 48678 24437 48678 24560 48679 24437 48679 24436 48679 24439 48680 24554 48680 24438 48680 24438 48681 24524 48681 24439 48681 24439 48682 24524 48682 24440 48682 24439 48683 24440 48683 24555 48683 24555 48684 24440 48684 24522 48684 24555 48685 24522 48685 24521 48685 24553 48686 24888 48686 24530 48686 24530 48687 24527 48687 24553 48687 24553 48688 24527 48688 24441 48688 24553 48689 24441 48689 24554 48689 24554 48690 24441 48690 24442 48690 24554 48691 24442 48691 24438 48691 24445 48692 24443 48692 24444 48692 24861 48693 24445 48693 24863 48693 24863 48694 24445 48694 24444 48694 24863 48695 24444 48695 24488 48695 24923 48696 24448 48696 24479 48696 24859 48697 24479 48697 24446 48697 24446 48698 24479 48698 24448 48698 24446 48699 24448 48699 24447 48699 24447 48700 24448 48700 24926 48700 22461 48701 22463 48701 24449 48701 24449 48702 22463 48702 24451 48702 24449 48703 24451 48703 24450 48703 24450 48704 24451 48704 24452 48704 24450 48705 24452 48705 24415 48705 24415 48706 24452 48706 22451 48706 24415 48707 22451 48707 24416 48707 24416 48708 22451 48708 24453 48708 24416 48709 24453 48709 24454 48709 24454 48710 24453 48710 24455 48710 24454 48711 24455 48711 24413 48711 24413 48712 24455 48712 24456 48712 24413 48713 24456 48713 24457 48713 24457 48714 24456 48714 24458 48714 24457 48715 24458 48715 24411 48715 24411 48716 24458 48716 24459 48716 24411 48717 24459 48717 24460 48717 24460 48718 24459 48718 22440 48718 24460 48719 22440 48719 24461 48719 24461 48720 22440 48720 22439 48720 24461 48721 22439 48721 24462 48721 24462 48722 22439 48722 24463 48722 24462 48723 24463 48723 24464 48723 24464 48724 24463 48724 22423 48724 24464 48725 22423 48725 24408 48725 24408 48726 22423 48726 22436 48726 24408 48727 22436 48727 24407 48727 24407 48728 22436 48728 24465 48728 24407 48729 24465 48729 24466 48729 24466 48730 24465 48730 22435 48730 24466 48731 22435 48731 24406 48731 24406 48732 22435 48732 24468 48732 24406 48733 24468 48733 24467 48733 24467 48734 24468 48734 24469 48734 24467 48735 24469 48735 24470 48735 24470 48736 24469 48736 22418 48736 24470 48737 22418 48737 24404 48737 24404 48738 22418 48738 24471 48738 24404 48739 24471 48739 24472 48739 24472 48740 24471 48740 24473 48740 24472 48741 24473 48741 24402 48741 24402 48742 24473 48742 24474 48742 24402 48743 24474 48743 24401 48743 24401 48744 24474 48744 24475 48744 24401 48745 24475 48745 24399 48745 24399 48746 24475 48746 24477 48746 24399 48747 24477 48747 24476 48747 24476 48748 24477 48748 22412 48748 24476 48749 22412 48749 24398 48749 24398 48750 22412 48750 24478 48750 24398 48751 24478 48751 24479 48751 24479 48752 24478 48752 24480 48752 24479 48753 24480 48753 24923 48753 24449 48754 24414 48754 22461 48754 22461 48755 24414 48755 24481 48755 22461 48756 24481 48756 22468 48756 22468 48757 24481 48757 24482 48757 24481 48758 24483 48758 24482 48758 24482 48759 24483 48759 24417 48759 24482 48760 24417 48760 24484 48760 24484 48761 24417 48761 22471 48761 24417 48762 24485 48762 22471 48762 22471 48763 24485 48763 24421 48763 22471 48764 24421 48764 24486 48764 24486 48765 24421 48765 24420 48765 24486 48766 24420 48766 24487 48766 24487 48767 24420 48767 24488 48767 24487 48768 24488 48768 22390 48768 22390 48769 24488 48769 24444 48769 22390 48770 24444 48770 24922 48770 24899 48771 24489 48771 24495 48771 24495 48772 24489 48772 24868 48772 24495 48773 24868 48773 24490 48773 24490 48774 24868 48774 24867 48774 24529 48775 24939 48775 24331 48775 24491 48776 22101 48776 24529 48776 24529 48777 22101 48777 24492 48777 24529 48778 24492 48778 24493 48778 24494 48779 24899 48779 24316 48779 24316 48780 24899 48780 24495 48780 24316 48781 24495 48781 24318 48781 24318 48782 24495 48782 24497 48782 24318 48783 24497 48783 24496 48783 24496 48784 24497 48784 24423 48784 24496 48785 24423 48785 24498 48785 24498 48786 24423 48786 24499 48786 24498 48787 24499 48787 24500 48787 24500 48788 24499 48788 24425 48788 24500 48789 24425 48789 24501 48789 24501 48790 24425 48790 24426 48790 24501 48791 24426 48791 24502 48791 24502 48792 24426 48792 24427 48792 24502 48793 24427 48793 24339 48793 24339 48794 24427 48794 24503 48794 24339 48795 24503 48795 24346 48795 24346 48796 24503 48796 24504 48796 24346 48797 24504 48797 24505 48797 24505 48798 24504 48798 24506 48798 24505 48799 24506 48799 24349 48799 24349 48800 24506 48800 24507 48800 24349 48801 24507 48801 24508 48801 24508 48802 24507 48802 24509 48802 24508 48803 24509 48803 24510 48803 24510 48804 24509 48804 24511 48804 24510 48805 24511 48805 24353 48805 24430 48806 24363 48806 24350 48806 24353 48807 24511 48807 24350 48807 24350 48808 24511 48808 24512 48808 24350 48809 24512 48809 24430 48809 24434 48810 24361 48810 24513 48810 24363 48811 24430 48811 24513 48811 24513 48812 24430 48812 24432 48812 24513 48813 24432 48813 24434 48813 24361 48814 24434 48814 24360 48814 24360 48815 24434 48815 24435 48815 24360 48816 24435 48816 24514 48816 24514 48817 24435 48817 24515 48817 24514 48818 24515 48818 24371 48818 24371 48819 24515 48819 24516 48819 24371 48820 24516 48820 24372 48820 24372 48821 24516 48821 24517 48821 24372 48822 24517 48822 24373 48822 24373 48823 24517 48823 24436 48823 24373 48824 24436 48824 24375 48824 24375 48825 24436 48825 24437 48825 24375 48826 24437 48826 24378 48826 24378 48827 24437 48827 24519 48827 24378 48828 24519 48828 24518 48828 24518 48829 24519 48829 24520 48829 24518 48830 24520 48830 24385 48830 24385 48831 24520 48831 24521 48831 24385 48832 24521 48832 24384 48832 24384 48833 24521 48833 24522 48833 24384 48834 24522 48834 24383 48834 24383 48835 24522 48835 24440 48835 24383 48836 24440 48836 24523 48836 24523 48837 24440 48837 24524 48837 24523 48838 24524 48838 24525 48838 24525 48839 24524 48839 24438 48839 24525 48840 24438 48840 24389 48840 24389 48841 24438 48841 24442 48841 24389 48842 24442 48842 24526 48842 24526 48843 24442 48843 24441 48843 24526 48844 24441 48844 24528 48844 24528 48845 24441 48845 24527 48845 24528 48846 24527 48846 24331 48846 24331 48847 24527 48847 24530 48847 24331 48848 24530 48848 24529 48848 24529 48849 24530 48849 24531 48849 24529 48850 24531 48850 24491 48850 24533 48851 24532 48851 24419 48851 24533 48852 24419 48852 24534 48852 24534 48853 24419 48853 24535 48853 24534 48854 24535 48854 24536 48854 24536 48855 24535 48855 24418 48855 24536 48856 24418 48856 27010 48856 27010 48857 24418 48857 24537 48857 27010 48858 24537 48858 24538 48858 24538 48859 24537 48859 24539 48859 24538 48860 24539 48860 27008 48860 27008 48861 24539 48861 24412 48861 27008 48862 24412 48862 24540 48862 24540 48863 24412 48863 24542 48863 24540 48864 24542 48864 24541 48864 24541 48865 24542 48865 24543 48865 24541 48866 24543 48866 24544 48866 24544 48867 24543 48867 24410 48867 24544 48868 24410 48868 24545 48868 24545 48869 24410 48869 24409 48869 24545 48870 24409 48870 24546 48870 24546 48871 24409 48871 24547 48871 24546 48872 24547 48872 27005 48872 27005 48873 24547 48873 24549 48873 27005 48874 24549 48874 24548 48874 24548 48875 24549 48875 24405 48875 24548 48876 24405 48876 27002 48876 27002 48877 24405 48877 24403 48877 27002 48878 24403 48878 27001 48878 27001 48879 24403 48879 24400 48879 27001 48880 24400 48880 27000 48880 27000 48881 24400 48881 24550 48881 27000 48882 24550 48882 24551 48882 24551 48883 24550 48883 24552 48883 24551 48884 24552 48884 22086 48884 25045 48885 24888 48885 24553 48885 25045 48886 24553 48886 26998 48886 26998 48887 24553 48887 24554 48887 26998 48888 24554 48888 26996 48888 26996 48889 24554 48889 24439 48889 26996 48890 24439 48890 26995 48890 26995 48891 24439 48891 24555 48891 26995 48892 24555 48892 24556 48892 24556 48893 24555 48893 24557 48893 24556 48894 24557 48894 24558 48894 24558 48895 24557 48895 24560 48895 24558 48896 24560 48896 24559 48896 24559 48897 24560 48897 24561 48897 24559 48898 24561 48898 24562 48898 24562 48899 24561 48899 24563 48899 24562 48900 24563 48900 26992 48900 26992 48901 24563 48901 24433 48901 26992 48902 24433 48902 24564 48902 24564 48903 24433 48903 24431 48903 24564 48904 24431 48904 24565 48904 24565 48905 24431 48905 24429 48905 24565 48906 24429 48906 26990 48906 26990 48907 24429 48907 24566 48907 26990 48908 24566 48908 24567 48908 24567 48909 24566 48909 24428 48909 24567 48910 24428 48910 24568 48910 24568 48911 24428 48911 24569 48911 24568 48912 24569 48912 24570 48912 24570 48913 24569 48913 24424 48913 24570 48914 24424 48914 24571 48914 24571 48915 24424 48915 24422 48915 24571 48916 24422 48916 26988 48916 26988 48917 24422 48917 24572 48917 26988 48918 24572 48918 24573 48918 22286 48919 24574 48919 24575 48919 22286 48920 24575 48920 22288 48920 22288 48921 24575 48921 22386 48921 22288 48922 22386 48922 24712 48922 22283 48923 24578 48923 24576 48923 24576 48924 24578 48924 24575 48924 24576 48925 24575 48925 22284 48925 22284 48926 24575 48926 24574 48926 24579 48927 24719 48927 24577 48927 24577 48928 24719 48928 24578 48928 24577 48929 24578 48929 22282 48929 22282 48930 24578 48930 22283 48930 24579 48931 24580 48931 24719 48931 24719 48932 24580 48932 24584 48932 24719 48933 24584 48933 24582 48933 22276 48934 24581 48934 24583 48934 24583 48935 24581 48935 24582 48935 24583 48936 24582 48936 22278 48936 22278 48937 24582 48937 24584 48937 24589 48938 24585 48938 24586 48938 24586 48939 24585 48939 24581 48939 24586 48940 24581 48940 24587 48940 24587 48941 24581 48941 22276 48941 22272 48942 24590 48942 24588 48942 24588 48943 24590 48943 24585 48943 24588 48944 24585 48944 22274 48944 22274 48945 24585 48945 24589 48945 22272 48946 22271 48946 24590 48946 24590 48947 22271 48947 24592 48947 24590 48948 24592 48948 24591 48948 24591 48949 24592 48949 24593 48949 24591 48950 24593 48950 24596 48950 22270 48951 24724 48951 24594 48951 24594 48952 24724 48952 24591 48952 24594 48953 24591 48953 24595 48953 24595 48954 24591 48954 24596 48954 24597 48955 24600 48955 24598 48955 24598 48956 24600 48956 24724 48956 24598 48957 24724 48957 22268 48957 22268 48958 24724 48958 22270 48958 24597 48959 24599 48959 24600 48959 24600 48960 24599 48960 22265 48960 24600 48961 22265 48961 24602 48961 22265 48962 24601 48962 24602 48962 24602 48963 24601 48963 24603 48963 24602 48964 24603 48964 24605 48964 24605 48965 24603 48965 24604 48965 24605 48966 24604 48966 22263 48966 22263 48967 22262 48967 24605 48967 24605 48968 22262 48968 24606 48968 24605 48969 24606 48969 24725 48969 24725 48970 24606 48970 24607 48970 24725 48971 24607 48971 24608 48971 24612 48972 24611 48972 22259 48972 22259 48973 24611 48973 24725 48973 22259 48974 24725 48974 22261 48974 22261 48975 24725 48975 24608 48975 22256 48976 24727 48976 24609 48976 24609 48977 24727 48977 24611 48977 24609 48978 24611 48978 24610 48978 24610 48979 24611 48979 24612 48979 22253 48980 24728 48980 24613 48980 24613 48981 24728 48981 24727 48981 24613 48982 24727 48982 22254 48982 22254 48983 24727 48983 22256 48983 22250 48984 24616 48984 24614 48984 24614 48985 24616 48985 24728 48985 24614 48986 24728 48986 24615 48986 24615 48987 24728 48987 22253 48987 24659 48988 22228 48988 22247 48988 22247 48989 22228 48989 24616 48989 22247 48990 24616 48990 22249 48990 22249 48991 24616 48991 22250 48991 24713 48992 24657 48992 24712 48992 24617 48993 22369 48993 24618 48993 24630 48994 24707 48994 24710 48994 24681 48995 24619 48995 24683 48995 24662 48996 24646 48996 24663 48996 24347 48997 24348 48997 24620 48997 24696 48998 24374 48998 24698 48998 24379 48999 24704 48999 24705 48999 24621 49000 24626 49000 24711 49000 24622 49001 24623 49001 24625 49001 24628 49002 24624 49002 24625 49002 24625 49003 24624 49003 24335 49003 24625 49004 24335 49004 24622 49004 24626 49005 24390 49005 24658 49005 24658 49006 24390 49006 24627 49006 24658 49007 24627 49007 24628 49007 24628 49008 24627 49008 24629 49008 24628 49009 24629 49009 24624 49009 24380 49010 24382 49010 24630 49010 24630 49011 24382 49011 24388 49011 24630 49012 24388 49012 24707 49012 24707 49013 24388 49013 24621 49013 24370 49014 24631 49014 24697 49014 24697 49015 24631 49015 24696 49015 24632 49016 24633 49016 24370 49016 24633 49017 24632 49017 24367 49017 24367 49018 24632 49018 24634 49018 24367 49019 24634 49019 24362 49019 24362 49020 24634 49020 24635 49020 24362 49021 24635 49021 24636 49021 24636 49022 24635 49022 24638 49022 24636 49023 24638 49023 24364 49023 24364 49024 24638 49024 24637 49024 24637 49025 24638 49025 24639 49025 24637 49026 24639 49026 24356 49026 24356 49027 24639 49027 24640 49027 24640 49028 24639 49028 24641 49028 24640 49029 24641 49029 24348 49029 24679 49030 24642 49030 24681 49030 24681 49031 24642 49031 24643 49031 24681 49032 24643 49032 24619 49032 24619 49033 24643 49033 24644 49033 24619 49034 24644 49034 24347 49034 24668 49035 24645 49035 24674 49035 24674 49036 24645 49036 24337 49036 24664 49037 24317 49037 24670 49037 24670 49038 24317 49038 24668 49038 24661 49039 24906 49039 24662 49039 24664 49040 24646 49040 24323 49040 24323 49041 24646 49041 24662 49041 24323 49042 24662 49042 24324 49042 24324 49043 24662 49043 24906 49043 24647 49044 24648 49044 24660 49044 24649 49045 24675 49045 24673 49045 24337 49046 24336 49046 24673 49046 24673 49047 24336 49047 24680 49047 24673 49048 24680 49048 24649 49048 24649 49049 24680 49049 24650 49049 24649 49050 24650 49050 24677 49050 24677 49051 24650 49051 24682 49051 24632 49052 24695 49052 24634 49052 24634 49053 24695 49053 24651 49053 24634 49054 24651 49054 24635 49054 24635 49055 24651 49055 24690 49055 24635 49056 24690 49056 24638 49056 24638 49057 24690 49057 24652 49057 24638 49058 24652 49058 24639 49058 24639 49059 24652 49059 24653 49059 24639 49060 24653 49060 24641 49060 24641 49061 24653 49061 24618 49061 24654 49062 24701 49062 24699 49062 24374 49063 24379 49063 24699 49063 24699 49064 24379 49064 24705 49064 24699 49065 24705 49065 24654 49065 24654 49066 24705 49066 24655 49066 24654 49067 24655 49067 24656 49067 24656 49068 24655 49068 24706 49068 24623 49069 24657 49069 24625 49069 24625 49070 24657 49070 24713 49070 24625 49071 24713 49071 24628 49071 24628 49072 24713 49072 24716 49072 24628 49073 24716 49073 24658 49073 24658 49074 24716 49074 24717 49074 24659 49075 24648 49075 22361 49075 22361 49076 24648 49076 24647 49076 22361 49077 24647 49077 22362 49077 22289 49078 24661 49078 24660 49078 24660 49079 24661 49079 24662 49079 24660 49080 24662 49080 24647 49080 24647 49081 24662 49081 24663 49081 24647 49082 24663 49082 22362 49082 22362 49083 24663 49083 24667 49083 24665 49084 24672 49084 24666 49084 24664 49085 24670 49085 24646 49085 24646 49086 24670 49086 24665 49086 24646 49087 24665 49087 24663 49087 24663 49088 24665 49088 24666 49088 24663 49089 24666 49089 24667 49089 24668 49090 24674 49090 24670 49090 24670 49091 24674 49091 24669 49091 24670 49092 24669 49092 24665 49092 24665 49093 24669 49093 24671 49093 24665 49094 24671 49094 24672 49094 24337 49095 24673 49095 24674 49095 24674 49096 24673 49096 24675 49096 24674 49097 24675 49097 24669 49097 24669 49098 24675 49098 24676 49098 24669 49099 24676 49099 24671 49099 24677 49100 22367 49100 24649 49100 24649 49101 22367 49101 22364 49101 24649 49102 22364 49102 24675 49102 24675 49103 22364 49103 24678 49103 24675 49104 24678 49104 24676 49104 24336 49105 24679 49105 24680 49105 24680 49106 24679 49106 24681 49106 24680 49107 24681 49107 24650 49107 24650 49108 24681 49108 24683 49108 24650 49109 24683 49109 24682 49109 24682 49110 24683 49110 24685 49110 24686 49111 24687 49111 24684 49111 24347 49112 24620 49112 24619 49112 24619 49113 24620 49113 24686 49113 24619 49114 24686 49114 24683 49114 24683 49115 24686 49115 24684 49115 24683 49116 24684 49116 24685 49116 24348 49117 24641 49117 24620 49117 24620 49118 24641 49118 24618 49118 24620 49119 24618 49119 24686 49119 24686 49120 24618 49120 22369 49120 24686 49121 22369 49121 24687 49121 24617 49122 24618 49122 24688 49122 24688 49123 24618 49123 24653 49123 24688 49124 24653 49124 22371 49124 22371 49125 24653 49125 24652 49125 22371 49126 24652 49126 22373 49126 22373 49127 24652 49127 24689 49127 24689 49128 24652 49128 24690 49128 24689 49129 24690 49129 24691 49129 24691 49130 24690 49130 24651 49130 24691 49131 24651 49131 24692 49131 24692 49132 24651 49132 24695 49132 24692 49133 24695 49133 24693 49133 24694 49134 22376 49134 22375 49134 24370 49135 24697 49135 24632 49135 24632 49136 24697 49136 24694 49136 24632 49137 24694 49137 24695 49137 24695 49138 24694 49138 22375 49138 24695 49139 22375 49139 24693 49139 24696 49140 24698 49140 24697 49140 24697 49141 24698 49141 24700 49141 24697 49142 24700 49142 24694 49142 24694 49143 24700 49143 22377 49143 24694 49144 22377 49144 22376 49144 24374 49145 24699 49145 24698 49145 24698 49146 24699 49146 24701 49146 24698 49147 24701 49147 24700 49147 24700 49148 24701 49148 24703 49148 24700 49149 24703 49149 22377 49149 24656 49150 22381 49150 24654 49150 24654 49151 22381 49151 24702 49151 24654 49152 24702 49152 24701 49152 24701 49153 24702 49153 22379 49153 24701 49154 22379 49154 24703 49154 24704 49155 24380 49155 24705 49155 24705 49156 24380 49156 24630 49156 24705 49157 24630 49157 24655 49157 24655 49158 24630 49158 24710 49158 24655 49159 24710 49159 24706 49159 24706 49160 24710 49160 22382 49160 24708 49161 22383 49161 24709 49161 24621 49162 24711 49162 24707 49162 24707 49163 24711 49163 24708 49163 24707 49164 24708 49164 24710 49164 24710 49165 24708 49165 24709 49165 24710 49166 24709 49166 22382 49166 24626 49167 24658 49167 24711 49167 24711 49168 24658 49168 24717 49168 24711 49169 24717 49169 24708 49169 24708 49170 24717 49170 22384 49170 24708 49171 22384 49171 22383 49171 24712 49172 24714 49172 24713 49172 24713 49173 24714 49173 24715 49173 24713 49174 24715 49174 24716 49174 24716 49175 24715 49175 22388 49175 24716 49176 22388 49176 24717 49176 24717 49177 22388 49177 24718 49177 24717 49178 24718 49178 22384 49178 27256 49179 22386 49179 24575 49179 27256 49180 24575 49180 27257 49180 27257 49181 24575 49181 24578 49181 27257 49182 24578 49182 24720 49182 24720 49183 24578 49183 24719 49183 24720 49184 24719 49184 27258 49184 27258 49185 24719 49185 24582 49185 27258 49186 24582 49186 24721 49186 24721 49187 24582 49187 24581 49187 24721 49188 24581 49188 24722 49188 24722 49189 24581 49189 24585 49189 24722 49190 24585 49190 24723 49190 24723 49191 24585 49191 24590 49191 24723 49192 24590 49192 27228 49192 27228 49193 24590 49193 24591 49193 27228 49194 24591 49194 27229 49194 27229 49195 24591 49195 24724 49195 27229 49196 24724 49196 27233 49196 27233 49197 24724 49197 24600 49197 27233 49198 24600 49198 27234 49198 27234 49199 24600 49199 24602 49199 27234 49200 24602 49200 27235 49200 27235 49201 24602 49201 24605 49201 27235 49202 24605 49202 27238 49202 27238 49203 24605 49203 24725 49203 27238 49204 24725 49204 27240 49204 27240 49205 24725 49205 24611 49205 27240 49206 24611 49206 24726 49206 24726 49207 24611 49207 24727 49207 24726 49208 24727 49208 27242 49208 27242 49209 24727 49209 24728 49209 27242 49210 24728 49210 27244 49210 27244 49211 24728 49211 24616 49211 27244 49212 24616 49212 27245 49212 27245 49213 24616 49213 22228 49213 27245 49214 22228 49214 22227 49214 24301 49215 23037 49215 24300 49215 24300 49216 23037 49216 24729 49216 24300 49217 24729 49217 24297 49217 24297 49218 24729 49218 23035 49218 24297 49219 23035 49219 24296 49219 24296 49220 23035 49220 24730 49220 24296 49221 24730 49221 24731 49221 24731 49222 24730 49222 23033 49222 24731 49223 23033 49223 22217 49223 22217 49224 23033 49224 24732 49224 24305 49225 24737 49225 24733 49225 24733 49226 24737 49226 24734 49226 24733 49227 24734 49227 24301 49227 24301 49228 24734 49228 27226 49228 24301 49229 27226 49229 23037 49229 24735 49230 24099 49230 24305 49230 24305 49231 24099 49231 24736 49231 24305 49232 24736 49232 24737 49232 24740 49233 24741 49233 24308 49233 24308 49234 24741 49234 27221 49234 24308 49235 27221 49235 24735 49235 24735 49236 27221 49236 27224 49236 24735 49237 27224 49237 24099 49237 24313 49238 23014 49238 24738 49238 24738 49239 23014 49239 23013 49239 24738 49240 23013 49240 24311 49240 24311 49241 23013 49241 24739 49241 24311 49242 24739 49242 24310 49242 24310 49243 24739 49243 23011 49243 24310 49244 23011 49244 24309 49244 24309 49245 23011 49245 23009 49245 24309 49246 23009 49246 24740 49246 24740 49247 23009 49247 23008 49247 24740 49248 23008 49248 24741 49248 22216 49249 24162 49249 24742 49249 22216 49250 24742 49250 24743 49250 24743 49251 24742 49251 24744 49251 24743 49252 24744 49252 24745 49252 24745 49253 24744 49253 24161 49253 24745 49254 24161 49254 24359 49254 24359 49255 24161 49255 24747 49255 24359 49256 24747 49256 24746 49256 24746 49257 24747 49257 24748 49257 24746 49258 24748 49258 24749 49258 24749 49259 24748 49259 24169 49259 24749 49260 24169 49260 24366 49260 24366 49261 24169 49261 24168 49261 24366 49262 24168 49262 22207 49262 24365 49263 22206 49263 24750 49263 24365 49264 24750 49264 24358 49264 24358 49265 24750 49265 24751 49265 24358 49266 24751 49266 24752 49266 24752 49267 24751 49267 24753 49267 24752 49268 24753 49268 24315 49268 24315 49269 24753 49269 24754 49269 24315 49270 24754 49270 24351 49270 24351 49271 24754 49271 24755 49271 24351 49272 24755 49272 24352 49272 24352 49273 24755 49273 24756 49273 24352 49274 24756 49274 24354 49274 24354 49275 24756 49275 24757 49275 24354 49276 24757 49276 24355 49276 24764 49277 24763 49277 24758 49277 24344 49278 22197 49278 24759 49278 24344 49279 24759 49279 24345 49279 24345 49280 24759 49280 24185 49280 24345 49281 24185 49281 24760 49281 24760 49282 24185 49282 24762 49282 24760 49283 24762 49283 24761 49283 24758 49284 24763 49284 24762 49284 24762 49285 24763 49285 24338 49285 24762 49286 24338 49286 24761 49286 24764 49287 24758 49287 24765 49287 24765 49288 24758 49288 24182 49288 24765 49289 24182 49289 24766 49289 24766 49290 24182 49290 22190 49290 24766 49291 22190 49291 24340 49291 22189 49292 24193 49292 24191 49292 22189 49293 24191 49293 24767 49293 24767 49294 24191 49294 24190 49294 24767 49295 24190 49295 24768 49295 24768 49296 24190 49296 24198 49296 24768 49297 24198 49297 24770 49297 24770 49298 24198 49298 24769 49298 24770 49299 24769 49299 24771 49299 24771 49300 24769 49300 24772 49300 24771 49301 24772 49301 24773 49301 24773 49302 24772 49302 24774 49302 24773 49303 24774 49303 24319 49303 24319 49304 24774 49304 22179 49304 24319 49305 22179 49305 24320 49305 22393 49306 22178 49306 24775 49306 24775 49307 22178 49307 24776 49307 24775 49308 24776 49308 22396 49308 22396 49309 24776 49309 24777 49309 24777 49310 24776 49310 24209 49310 24777 49311 24209 49311 22397 49311 22397 49312 24209 49312 24207 49312 22397 49313 24207 49313 22398 49313 22398 49314 24207 49314 24206 49314 22398 49315 24206 49315 22401 49315 22401 49316 24206 49316 24780 49316 22401 49317 24780 49317 22389 49317 24204 49318 24778 49318 24780 49318 24780 49319 24778 49319 24779 49319 24780 49320 24779 49320 22389 49320 22467 49321 24218 49321 24781 49321 22467 49322 24781 49322 22455 49322 22455 49323 24781 49323 24216 49323 22455 49324 24216 49324 24782 49324 24782 49325 24216 49325 24783 49325 24782 49326 24783 49326 22456 49326 22456 49327 24783 49327 24785 49327 22456 49328 24785 49328 24784 49328 24784 49329 24785 49329 24786 49329 24784 49330 24786 49330 24787 49330 24787 49331 24786 49331 24789 49331 24787 49332 24789 49332 24788 49332 24788 49333 24789 49333 24224 49333 24788 49334 24224 49334 22457 49334 22165 49335 24229 49335 24791 49335 22165 49336 24791 49336 24790 49336 24790 49337 24791 49337 24227 49337 24790 49338 24227 49338 24793 49338 24793 49339 24227 49339 24792 49339 24793 49340 24792 49340 22447 49340 22447 49341 24792 49341 24226 49341 22447 49342 24226 49342 22448 49342 22448 49343 24226 49343 24794 49343 22448 49344 24794 49344 22449 49344 22449 49345 24794 49345 24795 49345 22449 49346 24795 49346 24796 49346 24796 49347 24795 49347 24234 49347 24796 49348 24234 49348 22158 49348 22431 49349 24241 49349 24240 49349 22431 49350 24240 49350 24797 49350 24797 49351 24240 49351 24237 49351 24797 49352 24237 49352 22426 49352 22426 49353 24237 49353 24798 49353 22426 49354 24798 49354 22427 49354 22427 49355 24798 49355 24236 49355 22427 49356 24236 49356 22428 49356 22428 49357 24236 49357 24799 49357 22428 49358 24799 49358 24800 49358 24800 49359 24799 49359 24801 49359 24800 49360 24801 49360 24802 49360 24802 49361 24801 49361 24249 49361 24802 49362 24249 49362 22151 49362 22419 49363 24255 49363 24803 49363 22419 49364 24803 49364 22420 49364 22420 49365 24803 49365 24804 49365 22420 49366 24804 49366 24806 49366 24806 49367 24804 49367 24805 49367 24806 49368 24805 49368 24807 49368 24807 49369 24805 49369 24252 49369 24807 49370 24252 49370 22422 49370 22422 49371 24252 49371 24808 49371 22422 49372 24808 49372 24809 49372 24809 49373 24808 49373 24810 49373 24809 49374 24810 49374 24811 49374 24811 49375 24810 49375 22141 49375 24811 49376 22141 49376 22416 49376 22413 49377 22139 49377 24270 49377 22413 49378 24270 49378 24812 49378 24812 49379 24270 49379 24813 49379 24812 49380 24813 49380 24814 49380 24814 49381 24813 49381 24269 49381 24814 49382 24269 49382 24816 49382 24816 49383 24269 49383 24815 49383 24816 49384 24815 49384 24817 49384 24817 49385 24815 49385 24818 49385 24817 49386 24818 49386 22406 49386 22406 49387 24818 49387 24267 49387 22406 49388 24267 49388 24819 49388 24819 49389 24267 49389 24266 49389 24819 49390 24266 49390 22410 49390 24391 49391 24820 49391 24821 49391 24391 49392 24821 49392 24823 49392 24823 49393 24821 49393 24822 49393 24823 49394 24822 49394 24392 49394 24392 49395 24822 49395 24281 49395 24392 49396 24281 49396 24393 49396 24393 49397 24281 49397 24282 49397 24393 49398 24282 49398 24394 49398 24394 49399 24282 49399 24824 49399 24394 49400 24824 49400 24395 49400 24395 49401 24824 49401 24825 49401 24395 49402 24825 49402 24396 49402 24396 49403 24825 49403 24826 49403 24826 49404 24825 49404 24827 49404 24826 49405 24827 49405 22122 49405 22121 49406 24828 49406 24830 49406 22121 49407 24830 49407 24829 49407 24829 49408 24830 49408 24831 49408 24829 49409 24831 49409 24832 49409 24832 49410 24831 49410 24834 49410 24832 49411 24834 49411 24833 49411 24833 49412 24834 49412 24835 49412 24833 49413 24835 49413 24377 49413 24377 49414 24835 49414 24294 49414 24377 49415 24294 49415 24381 49415 24381 49416 24294 49416 24836 49416 24381 49417 24836 49417 24837 49417 24837 49418 24836 49418 24291 49418 24837 49419 24291 49419 24376 49419 24909 49420 22111 49420 24838 49420 24909 49421 24838 49421 24839 49421 24839 49422 24838 49422 24841 49422 24839 49423 24841 49423 24907 49423 24917 49424 24843 49424 24840 49424 24840 49425 24843 49425 24893 49425 22110 49426 22108 49426 24910 49426 24910 49427 24911 49427 22110 49427 22110 49428 24911 49428 24913 49428 22110 49429 24913 49429 24893 49429 24893 49430 24913 49430 24915 49430 24893 49431 24915 49431 24840 49431 24841 49432 22104 49432 24907 49432 24907 49433 22104 49433 22103 49433 24842 49434 24865 49434 24919 49434 24919 49435 24865 49435 24843 49435 24919 49436 24843 49436 24917 49436 24844 49437 24845 49437 24866 49437 24866 49438 24845 49438 24891 49438 22089 49439 22102 49439 24932 49439 24932 49440 22102 49440 24876 49440 24932 49441 24876 49441 24846 49441 24846 49442 24876 49442 24847 49442 24846 49443 24847 49443 24848 49443 24848 49444 24847 49444 24874 49444 24848 49445 24874 49445 24931 49445 24880 49446 24878 49446 24853 49446 24853 49447 24878 49447 22088 49447 24938 49448 24883 49448 24849 49448 24849 49449 24883 49449 24881 49449 24849 49450 24881 49450 24850 49450 24850 49451 24881 49451 24851 49451 24850 49452 24851 49452 24852 49452 24852 49453 24851 49453 24880 49453 24852 49454 24880 49454 24853 49454 24931 49455 24874 49455 24854 49455 24854 49456 24874 49456 24871 49456 24854 49457 24871 49457 24858 49457 24855 49458 22099 49458 24856 49458 24856 49459 22099 49459 24883 49459 24856 49460 24883 49460 24938 49460 24530 49461 24888 49461 24531 49461 24531 49462 24888 49462 22100 49462 24531 49463 22100 49463 24491 49463 24860 49464 24925 49464 24857 49464 24857 49465 24925 49465 24858 49465 24857 49466 24858 49466 24871 49466 22098 49467 24859 49467 24870 49467 24870 49468 24859 49468 24446 49468 24870 49469 24446 49469 24860 49469 24860 49470 24446 49470 24447 49470 24860 49471 24447 49471 24925 49471 24925 49472 24447 49472 24926 49472 24896 49473 24445 49473 24861 49473 24896 49474 24861 49474 24862 49474 24862 49475 24861 49475 24863 49475 24862 49476 24863 49476 24532 49476 24445 49477 24896 49477 24443 49477 24443 49478 24896 49478 24864 49478 24443 49479 24864 49479 24920 49479 24920 49480 24864 49480 24865 49480 24920 49481 24865 49481 24842 49481 22095 49482 24898 49482 24891 49482 24891 49483 24898 49483 24866 49483 24572 49484 24490 49484 24889 49484 24889 49485 24490 49485 24867 49485 24889 49486 24867 49486 22097 49486 22097 49487 24867 49487 24868 49487 22097 49488 24868 49488 22095 49488 22095 49489 24868 49489 24489 49489 22095 49490 24489 49490 24898 49490 22086 49491 24552 49491 22085 49491 22085 49492 24552 49492 22098 49492 22085 49493 22098 49493 24869 49493 24869 49494 22098 49494 24870 49494 24871 49495 24873 49495 24857 49495 24857 49496 24873 49496 24869 49496 24857 49497 24869 49497 24860 49497 24860 49498 24869 49498 24870 49498 24874 49499 24872 49499 24871 49499 24871 49500 24872 49500 24873 49500 24875 49501 24872 49501 24874 49501 24874 49502 24847 49502 24875 49502 24875 49503 24847 49503 24876 49503 24875 49504 24876 49504 24877 49504 24877 49505 24876 49505 22102 49505 24877 49506 22102 49506 22084 49506 22084 49507 22102 49507 24878 49507 22084 49508 24878 49508 24879 49508 24879 49509 24878 49509 24880 49509 24879 49510 24880 49510 25040 49510 25041 49511 25040 49511 24880 49511 25041 49512 24880 49512 24882 49512 24883 49513 24884 49513 24881 49513 24881 49514 24884 49514 24882 49514 24881 49515 24882 49515 24851 49515 24851 49516 24882 49516 24880 49516 22099 49517 25043 49517 24883 49517 24883 49518 25043 49518 24884 49518 22081 49519 25043 49519 22099 49519 22099 49520 24885 49520 22081 49520 22081 49521 24885 49521 24886 49521 22081 49522 24886 49522 24887 49522 24887 49523 24886 49523 22100 49523 24887 49524 22100 49524 25045 49524 25045 49525 22100 49525 24888 49525 24572 49526 24889 49526 24573 49526 24573 49527 24889 49527 24890 49527 24845 49528 22093 49528 24891 49528 24891 49529 22093 49529 22094 49529 24841 49530 25027 49530 22104 49530 22104 49531 25027 49531 22091 49531 24841 49532 24838 49532 25027 49532 25027 49533 24838 49533 25026 49533 24893 49534 24843 49534 24894 49534 25028 49535 22110 49535 25029 49535 25029 49536 22110 49536 24893 49536 25029 49537 24893 49537 24892 49537 24892 49538 24893 49538 24894 49538 24865 49539 24895 49539 24843 49539 24843 49540 24895 49540 24894 49540 24895 49541 24865 49541 25034 49541 25034 49542 24865 49542 24864 49542 25034 49543 24864 49543 25033 49543 25033 49544 24864 49544 24896 49544 25033 49545 24896 49545 25031 49545 25031 49546 24896 49546 24862 49546 24898 49547 24489 49547 24899 49547 24897 49548 24866 49548 24321 49548 24321 49549 24866 49549 24898 49549 24321 49550 24898 49550 24494 49550 24494 49551 24898 49551 24899 49551 24866 49552 24897 49552 24844 49552 24844 49553 24897 49553 24328 49553 24844 49554 24328 49554 24325 49554 24844 49555 24325 49555 24900 49555 24900 49556 24325 49556 24901 49556 24900 49557 24901 49557 24902 49557 24902 49558 24901 49558 24903 49558 24902 49559 24903 49559 24904 49559 24904 49560 24903 49560 24905 49560 24904 49561 24905 49561 22105 49561 22105 49562 24905 49562 24324 49562 24906 49563 24661 49563 24907 49563 22105 49564 24324 49564 24908 49564 24908 49565 24324 49565 24906 49565 24908 49566 24906 49566 22103 49566 22103 49567 24906 49567 24907 49567 22246 49568 22360 49568 24909 49568 22246 49569 24909 49569 22289 49569 24909 49570 24839 49570 22289 49570 22289 49571 24839 49571 24907 49571 22289 49572 24907 49572 24661 49572 22109 49573 24909 49573 22360 49573 24912 49574 24911 49574 24910 49574 24912 49575 24910 49575 22360 49575 22360 49576 24910 49576 22108 49576 22360 49577 22108 49577 22109 49577 24911 49578 24912 49578 24913 49578 24913 49579 24912 49579 24914 49579 24913 49580 24914 49580 24915 49580 24915 49581 24914 49581 24916 49581 24915 49582 24916 49582 24840 49582 24840 49583 24916 49583 22402 49583 24840 49584 22402 49584 24917 49584 24917 49585 22402 49585 24918 49585 24917 49586 24918 49586 24919 49586 24919 49587 24918 49587 22399 49587 24919 49588 22399 49588 24842 49588 24842 49589 22399 49589 22400 49589 24842 49590 22400 49590 24920 49590 24920 49591 22400 49591 24921 49591 24921 49592 24922 49592 24920 49592 24920 49593 24922 49593 24444 49593 24920 49594 24444 49594 24443 49594 24448 49595 24923 49595 24924 49595 24927 49596 24858 49596 24924 49596 24924 49597 24858 49597 24925 49597 24924 49598 24925 49598 24448 49598 24448 49599 24925 49599 24926 49599 24858 49600 24927 49600 24854 49600 24854 49601 24927 49601 24928 49601 24854 49602 24928 49602 24931 49602 24931 49603 24928 49603 24929 49603 24931 49604 24929 49604 24930 49604 24931 49605 24930 49605 24848 49605 24930 49606 22405 49606 24848 49606 24848 49607 22405 49607 22404 49607 24848 49608 22404 49608 24846 49608 24846 49609 22404 49609 24932 49609 24932 49610 22404 49610 24933 49610 24932 49611 24933 49611 22089 49611 24853 49612 22088 49612 24334 49612 24334 49613 22088 49613 24934 49613 24853 49614 24334 49614 24935 49614 24853 49615 24935 49615 24852 49615 24852 49616 24935 49616 24936 49616 24852 49617 24936 49617 24850 49617 24850 49618 24936 49618 24332 49618 24850 49619 24332 49619 24849 49619 24849 49620 24332 49620 24937 49620 24849 49621 24937 49621 24938 49621 24938 49622 24937 49622 24856 49622 24856 49623 24937 49623 24333 49623 24856 49624 24333 49624 24855 49624 24855 49625 24333 49625 24329 49625 24855 49626 24329 49626 24940 49626 24940 49627 24329 49627 24330 49627 24330 49628 24939 49628 24940 49628 24940 49629 24939 49629 24529 49629 24940 49630 24529 49630 24493 49630 24950 49631 22015 49631 20971 49631 20971 49632 22015 49632 22014 49632 20971 49633 22014 49633 24941 49633 24941 49634 22014 49634 24942 49634 24941 49635 24942 49635 20969 49635 24942 49636 22012 49636 20969 49636 20969 49637 22012 49637 22009 49637 20969 49638 22009 49638 24944 49638 24944 49639 22009 49639 24943 49639 24944 49640 24943 49640 24945 49640 24945 49641 24943 49641 22008 49641 24945 49642 22008 49642 24946 49642 24946 49643 22008 49643 24956 49643 24946 49644 24956 49644 20988 49644 24955 49645 24947 49645 20974 49645 20974 49646 24947 49646 24949 49646 20974 49647 24949 49647 24948 49647 24948 49648 24949 49648 22018 49648 24948 49649 22018 49649 20973 49649 20973 49650 22018 49650 22017 49650 20973 49651 22017 49651 24950 49651 24950 49652 22017 49652 24951 49652 24950 49653 24951 49653 22015 49653 24959 49654 24961 49654 24952 49654 24952 49655 24961 49655 25129 49655 24952 49656 25129 49656 24954 49656 24954 49657 25129 49657 24953 49657 24954 49658 24953 49658 20976 49658 20976 49659 24953 49659 25127 49659 20976 49660 25127 49660 24955 49660 24955 49661 25127 49661 25125 49661 24955 49662 25125 49662 24947 49662 24956 49663 22007 49663 20988 49663 20988 49664 22007 49664 24957 49664 20988 49665 24957 49665 20987 49665 20987 49666 24957 49666 22006 49666 20987 49667 22006 49667 20986 49667 20986 49668 22006 49668 24958 49668 20986 49669 24958 49669 20985 49669 24964 49670 25134 49670 20980 49670 20980 49671 25134 49671 25132 49671 20980 49672 25132 49672 20979 49672 20979 49673 25132 49673 25131 49673 20979 49674 25131 49674 24959 49674 24959 49675 25131 49675 24960 49675 24959 49676 24960 49676 24961 49676 24958 49677 25141 49677 20985 49677 20985 49678 25141 49678 25139 49678 20985 49679 25139 49679 20984 49679 20984 49680 25139 49680 25138 49680 20984 49681 25138 49681 20982 49681 20982 49682 25138 49682 24962 49682 20982 49683 24962 49683 24963 49683 24963 49684 24962 49684 25137 49684 24963 49685 25137 49685 24964 49685 24964 49686 25137 49686 25135 49686 24964 49687 25135 49687 25134 49687 27015 49688 27017 49688 25046 49688 25046 49689 27017 49689 21208 49689 25046 49690 21208 49690 24965 49690 24965 49691 21208 49691 21210 49691 24965 49692 21210 49692 22079 49692 22079 49693 21210 49693 24966 49693 22079 49694 24966 49694 24967 49694 24967 49695 24966 49695 24970 49695 24967 49696 24970 49696 24968 49696 24968 49697 24970 49697 24969 49697 24969 49698 24970 49698 21209 49698 24969 49699 21209 49699 25058 49699 25058 49700 21209 49700 24977 49700 24971 49701 25063 49701 24972 49701 24971 49702 24972 49702 21206 49702 21206 49703 24972 49703 24973 49703 21206 49704 24973 49704 24974 49704 24974 49705 24973 49705 24976 49705 24974 49706 24976 49706 24975 49706 24975 49707 24976 49707 25058 49707 24975 49708 25058 49708 24977 49708 24978 49709 24979 49709 24980 49709 24978 49710 24980 49710 21205 49710 21205 49711 24980 49711 25063 49711 21205 49712 25063 49712 24971 49712 24984 49713 24981 49713 25069 49713 24984 49714 25069 49714 24982 49714 24982 49715 25069 49715 25068 49715 24982 49716 25068 49716 27021 49716 25068 49717 25067 49717 27021 49717 27021 49718 25067 49718 25065 49718 27021 49719 25065 49719 24983 49719 24983 49720 25065 49720 24979 49720 24983 49721 24979 49721 24978 49721 24981 49722 24984 49722 25059 49722 25059 49723 24984 49723 24985 49723 25059 49724 24985 49724 24988 49724 24988 49725 24985 49725 24986 49725 24986 49726 24987 49726 24988 49726 24988 49727 24987 49727 24989 49727 24987 49728 27019 49728 24989 49728 24989 49729 27019 49729 24990 49729 24989 49730 24990 49730 25048 49730 25048 49731 24990 49731 24991 49731 24991 49732 24990 49732 24992 49732 24991 49733 24992 49733 27018 49733 27191 49734 24993 49734 24994 49734 27191 49735 24994 49735 25056 49735 25056 49736 24994 49736 24995 49736 25056 49737 24995 49737 25055 49737 25055 49738 24995 49738 24996 49738 25055 49739 24996 49739 25053 49739 25053 49740 24996 49740 27121 49740 25053 49741 27121 49741 25052 49741 25052 49742 27121 49742 24997 49742 24997 49743 27121 49743 24998 49743 24997 49744 24998 49744 25072 49744 25072 49745 24998 49745 24999 49745 25001 49746 22074 49746 25000 49746 25001 49747 25000 49747 27118 49747 27118 49748 25000 49748 25002 49748 27118 49749 25002 49749 27119 49749 27119 49750 25002 49750 25004 49750 27119 49751 25004 49751 25003 49751 25003 49752 25004 49752 25072 49752 25003 49753 25072 49753 24999 49753 25009 49754 25079 49754 21116 49754 21116 49755 25079 49755 22087 49755 25007 49756 25005 49756 25011 49756 25005 49757 25007 49757 25006 49757 25006 49758 25007 49758 25008 49758 25006 49759 25008 49759 25071 49759 25009 49760 21116 49760 25075 49760 25075 49761 21116 49761 25010 49761 25075 49762 25010 49762 25011 49762 25011 49763 25010 49763 25012 49763 25011 49764 25012 49764 25007 49764 25071 49765 25008 49765 25013 49765 25013 49766 25008 49766 25014 49766 25013 49767 25014 49767 25070 49767 25070 49768 25014 49768 21113 49768 25070 49769 21113 49769 25015 49769 25070 49770 25015 49770 25016 49770 25016 49771 25015 49771 21112 49771 25016 49772 21112 49772 25017 49772 25017 49773 21112 49773 25018 49773 25017 49774 25018 49774 25019 49774 25019 49775 25018 49775 25020 49775 25019 49776 25020 49776 27013 49776 22094 49777 25051 49777 25050 49777 22094 49778 25050 49778 22096 49778 22096 49779 25050 49779 25049 49779 22096 49780 25049 49780 25021 49780 25021 49781 25049 49781 24890 49781 24890 49782 25049 49782 26987 49782 24890 49783 26987 49783 24573 49783 25051 49784 22094 49784 25022 49784 25022 49785 22094 49785 22093 49785 25022 49786 22093 49786 22075 49786 22075 49787 22093 49787 22092 49787 22075 49788 22092 49788 22076 49788 22076 49789 22092 49789 25023 49789 22076 49790 25023 49790 25024 49790 25024 49791 25023 49791 22091 49791 25024 49792 22091 49792 25074 49792 25074 49793 22091 49793 25027 49793 22090 49794 22073 49794 25025 49794 22090 49795 25025 49795 25026 49795 25026 49796 25025 49796 25074 49796 25026 49797 25074 49797 25027 49797 22073 49798 22090 49798 25076 49798 25076 49799 22090 49799 25028 49799 25076 49800 25028 49800 25077 49800 25077 49801 25028 49801 25029 49801 25077 49802 25029 49802 25078 49802 25078 49803 25029 49803 24892 49803 25078 49804 24892 49804 25073 49804 25073 49805 24892 49805 24894 49805 25073 49806 24894 49806 25030 49806 25030 49807 24894 49807 24895 49807 25031 49808 24533 49808 25057 49808 25031 49809 25057 49809 25033 49809 25057 49810 25032 49810 25033 49810 25033 49811 25032 49811 25054 49811 25033 49812 25054 49812 25034 49812 25034 49813 25054 49813 25030 49813 25034 49814 25030 49814 24895 49814 24873 49815 25035 49815 25036 49815 24873 49816 25036 49816 24869 49816 24869 49817 25036 49817 25047 49817 24869 49818 25047 49818 22085 49818 25035 49819 24873 49819 25060 49819 25060 49820 24873 49820 24872 49820 24875 49821 24877 49821 25037 49821 25060 49822 24872 49822 25038 49822 25038 49823 24872 49823 24875 49823 25038 49824 24875 49824 25066 49824 25066 49825 24875 49825 25037 49825 25039 49826 22077 49826 25040 49826 25040 49827 22077 49827 24879 49827 25039 49828 25040 49828 25061 49828 25061 49829 25040 49829 25041 49829 22083 49830 24884 49830 25042 49830 25042 49831 24884 49831 25043 49831 27152 49832 25044 49832 25045 49832 25045 49833 25044 49833 24887 49833 27152 49834 27015 49834 25044 49834 25044 49835 27015 49835 25046 49835 25044 49836 25046 49836 24965 49836 25047 49837 25036 49837 24991 49837 24991 49838 25036 49838 25048 49838 25048 49839 25036 49839 24989 49839 24989 49840 25036 49840 25035 49840 24989 49841 25035 49841 24988 49841 27013 49842 26987 49842 25019 49842 25019 49843 26987 49843 25049 49843 25019 49844 25049 49844 25017 49844 25017 49845 25049 49845 25050 49845 25017 49846 25050 49846 25016 49846 25016 49847 25050 49847 25051 49847 25016 49848 25051 49848 25070 49848 25053 49849 25052 49849 25030 49849 25053 49850 25030 49850 25055 49850 25030 49851 25054 49851 25055 49851 25055 49852 25054 49852 25032 49852 25055 49853 25032 49853 25056 49853 25056 49854 25032 49854 25057 49854 25056 49855 25057 49855 27191 49855 25058 49856 22083 49856 24969 49856 24969 49857 22083 49857 25042 49857 24969 49858 25042 49858 24968 49858 24988 49859 25035 49859 25059 49859 25059 49860 25035 49860 25060 49860 25059 49861 25060 49861 24981 49861 25063 49862 25039 49862 24972 49862 24972 49863 25039 49863 25061 49863 24972 49864 25061 49864 24973 49864 25061 49865 25062 49865 24973 49865 24973 49866 25062 49866 22082 49866 24973 49867 22082 49867 24976 49867 24976 49868 22082 49868 22083 49868 24976 49869 22083 49869 25058 49869 25063 49870 24980 49870 25039 49870 25039 49871 24980 49871 22077 49871 24981 49872 25060 49872 25069 49872 25069 49873 25060 49873 25038 49873 25064 49874 24979 49874 25037 49874 25037 49875 24979 49875 25065 49875 25037 49876 25065 49876 25066 49876 25066 49877 25065 49877 25067 49877 25066 49878 25067 49878 25038 49878 25038 49879 25067 49879 25068 49879 25038 49880 25068 49880 25069 49880 25070 49881 25051 49881 25013 49881 25013 49882 25051 49882 25022 49882 25013 49883 25022 49883 25071 49883 25072 49884 25073 49884 24997 49884 24997 49885 25073 49885 25030 49885 24997 49886 25030 49886 25052 49886 25024 49887 25074 49887 25075 49887 25075 49888 25074 49888 25009 49888 25000 49889 25076 49889 25077 49889 25000 49890 25077 49890 25002 49890 25002 49891 25077 49891 25078 49891 25002 49892 25078 49892 25004 49892 25004 49893 25078 49893 25073 49893 25004 49894 25073 49894 25072 49894 22073 49895 22074 49895 25079 49895 22073 49896 25079 49896 25025 49896 25025 49897 25079 49897 25009 49897 25025 49898 25009 49898 25074 49898 26731 49899 22072 49899 26756 49899 26731 49900 26756 49900 25080 49900 25080 49901 26756 49901 26755 49901 25080 49902 26755 49902 26733 49902 26733 49903 26755 49903 25081 49903 26733 49904 25081 49904 26734 49904 26734 49905 25081 49905 25082 49905 26734 49906 25082 49906 26706 49906 26706 49907 25082 49907 26751 49907 26706 49908 26751 49908 25083 49908 25083 49909 26751 49909 25084 49909 25083 49910 25084 49910 25086 49910 25086 49911 25084 49911 25085 49911 25086 49912 25085 49912 26707 49912 26707 49913 25085 49913 26748 49913 26707 49914 26748 49914 26709 49914 26709 49915 26748 49915 26746 49915 26709 49916 26746 49916 26711 49916 26711 49917 26746 49917 26745 49917 26711 49918 26745 49918 25088 49918 25088 49919 26745 49919 25087 49919 25088 49920 25087 49920 26713 49920 26713 49921 25087 49921 26743 49921 26713 49922 26743 49922 25089 49922 25089 49923 26743 49923 26740 49923 25089 49924 26740 49924 25091 49924 25091 49925 26740 49925 25090 49925 25091 49926 25090 49926 25092 49926 25092 49927 25090 49927 26737 49927 25092 49928 26737 49928 25093 49928 25093 49929 26737 49929 26735 49929 25093 49930 26735 49930 26715 49930 26715 49931 26735 49931 22052 49931 26715 49932 22052 49932 26716 49932 25094 49933 26677 49933 26636 49933 26636 49934 26677 49934 26679 49934 26636 49935 26679 49935 25095 49935 25095 49936 26679 49936 25096 49936 25095 49937 25096 49937 26638 49937 26638 49938 25096 49938 26681 49938 26638 49939 26681 49939 26639 49939 26639 49940 26681 49940 25097 49940 26639 49941 25097 49941 26640 49941 26640 49942 25097 49942 25098 49942 26640 49943 25098 49943 26641 49943 26641 49944 25098 49944 26654 49944 26641 49945 26654 49945 25099 49945 25099 49946 26654 49946 25100 49946 25099 49947 25100 49947 26643 49947 26643 49948 25100 49948 25102 49948 26643 49949 25102 49949 25101 49949 25101 49950 25102 49950 25104 49950 25101 49951 25104 49951 25103 49951 25103 49952 25104 49952 26656 49952 25103 49953 26656 49953 26646 49953 26646 49954 26656 49954 25105 49954 26646 49955 25105 49955 25106 49955 25106 49956 25105 49956 26657 49956 25106 49957 26657 49957 26649 49957 26649 49958 26657 49958 25107 49958 26649 49959 25107 49959 26651 49959 26651 49960 25107 49960 25108 49960 26651 49961 25108 49961 26653 49961 26653 49962 25108 49962 26659 49962 26653 49963 26659 49963 25109 49963 25109 49964 26659 49964 26661 49964 22032 49965 25110 49965 26908 49965 26908 49966 25110 49966 25111 49966 26908 49967 25111 49967 26910 49967 26910 49968 25111 49968 25113 49968 26910 49969 25113 49969 25112 49969 25112 49970 25113 49970 26634 49970 25112 49971 26634 49971 26912 49971 26912 49972 26634 49972 26635 49972 26912 49973 26635 49973 26913 49973 26913 49974 26635 49974 25114 49974 26913 49975 25114 49975 26915 49975 26915 49976 25114 49976 26608 49976 26915 49977 26608 49977 26916 49977 26916 49978 26608 49978 26610 49978 26916 49979 26610 49979 26917 49979 26917 49980 26610 49980 25115 49980 26917 49981 25115 49981 26920 49981 26920 49982 25115 49982 26613 49982 26920 49983 26613 49983 25116 49983 25116 49984 26613 49984 25117 49984 25116 49985 25117 49985 25118 49985 25118 49986 25117 49986 26614 49986 25118 49987 26614 49987 25119 49987 25119 49988 26614 49988 25120 49988 25119 49989 25120 49989 25121 49989 25121 49990 25120 49990 26615 49990 25121 49991 26615 49991 25122 49991 25122 49992 26615 49992 26616 49992 25122 49993 26616 49993 26924 49993 26924 49994 26616 49994 25123 49994 26924 49995 25123 49995 21267 49995 21267 49996 25123 49996 25124 49996 22019 49997 24947 49997 26923 49997 26923 49998 24947 49998 25125 49998 26923 49999 25125 49999 25126 49999 25126 50000 25125 50000 25127 50000 25126 50001 25127 50001 25128 50001 25128 50002 25127 50002 24953 50002 25128 50003 24953 50003 26922 50003 26922 50004 24953 50004 25129 50004 26922 50005 25129 50005 26921 50005 26921 50006 25129 50006 24961 50006 26921 50007 24961 50007 26919 50007 26919 50008 24961 50008 24960 50008 26919 50009 24960 50009 26918 50009 26918 50010 24960 50010 25131 50010 26918 50011 25131 50011 25130 50011 25130 50012 25131 50012 25132 50012 25130 50013 25132 50013 25133 50013 25133 50014 25132 50014 25134 50014 25133 50015 25134 50015 26914 50015 26914 50016 25134 50016 25135 50016 26914 50017 25135 50017 25136 50017 25136 50018 25135 50018 25137 50018 25136 50019 25137 50019 26911 50019 26911 50020 25137 50020 24962 50020 26911 50021 24962 50021 26909 50021 26909 50022 24962 50022 25138 50022 26909 50023 25138 50023 26907 50023 26907 50024 25138 50024 25139 50024 26907 50025 25139 50025 26906 50025 26906 50026 25139 50026 25141 50026 26906 50027 25141 50027 25140 50027 25140 50028 25141 50028 24958 50028 25142 50029 25143 50029 26905 50029 25142 50030 26905 50030 26842 50030 26842 50031 26905 50031 26901 50031 26842 50032 26901 50032 25144 50032 25144 50033 26901 50033 26897 50033 25144 50034 26897 50034 26844 50034 26844 50035 26897 50035 26899 50035 26844 50036 26899 50036 26845 50036 26845 50037 26899 50037 26894 50037 26845 50038 26894 50038 25145 50038 25145 50039 26894 50039 26892 50039 25145 50040 26892 50040 25146 50040 25146 50041 26892 50041 26890 50041 25146 50042 26890 50042 26847 50042 26847 50043 26890 50043 25147 50043 26847 50044 25147 50044 25148 50044 25148 50045 25147 50045 26888 50045 25148 50046 26888 50046 26850 50046 26850 50047 26888 50047 25149 50047 26850 50048 25149 50048 25150 50048 25150 50049 25149 50049 26884 50049 25150 50050 26884 50050 26851 50050 26851 50051 26884 50051 26882 50051 26851 50052 26882 50052 26853 50052 26853 50053 26882 50053 26880 50053 26853 50054 26880 50054 26854 50054 26854 50055 26880 50055 26875 50055 26854 50056 26875 50056 26855 50056 26855 50057 26875 50057 26874 50057 26855 50058 26874 50058 25151 50058 25151 50059 26874 50059 26871 50059 25151 50060 26871 50060 25152 50060 25152 50061 26871 50061 26864 50061 25152 50062 26864 50062 25153 50062 25153 50063 26864 50063 26866 50063 25153 50064 26866 50064 25154 50064 26808 50065 26856 50065 25155 50065 25155 50066 26856 50066 26857 50066 25155 50067 26857 50067 25156 50067 25156 50068 26857 50068 26859 50068 25156 50069 26859 50069 26811 50069 26811 50070 26859 50070 26860 50070 26811 50071 26860 50071 26812 50071 26812 50072 26860 50072 25157 50072 26812 50073 25157 50073 26813 50073 26813 50074 25157 50074 26862 50074 26813 50075 26862 50075 26815 50075 26815 50076 26862 50076 25158 50076 26815 50077 25158 50077 26817 50077 26817 50078 25158 50078 26863 50078 26817 50079 26863 50079 25159 50079 25159 50080 26863 50080 25160 50080 25159 50081 25160 50081 25161 50081 25161 50082 25160 50082 26830 50082 25161 50083 26830 50083 25162 50083 25162 50084 26830 50084 25163 50084 25162 50085 25163 50085 26820 50085 26820 50086 25163 50086 26834 50086 26820 50087 26834 50087 26822 50087 26822 50088 26834 50088 25164 50088 26822 50089 25164 50089 25165 50089 25165 50090 25164 50090 25166 50090 25165 50091 25166 50091 26824 50091 26824 50092 25166 50092 26837 50092 26824 50093 26837 50093 25167 50093 25167 50094 26837 50094 26838 50094 25167 50095 26838 50095 26827 50095 26827 50096 26838 50096 25168 50096 26827 50097 25168 50097 26829 50097 26829 50098 25168 50098 26839 50098 26829 50099 26839 50099 21327 50099 21327 50100 26839 50100 25169 50100 26925 50101 21969 50101 26926 50101 26926 50102 21969 50102 25170 50102 26926 50103 25170 50103 25171 50103 25171 50104 25170 50104 26792 50104 25171 50105 26792 50105 26929 50105 26929 50106 26792 50106 26794 50106 26929 50107 26794 50107 26931 50107 26931 50108 26794 50108 25172 50108 26931 50109 25172 50109 26934 50109 26934 50110 25172 50110 26796 50110 26934 50111 26796 50111 25173 50111 25173 50112 26796 50112 26798 50112 25173 50113 26798 50113 26936 50113 26936 50114 26798 50114 25174 50114 26936 50115 25174 50115 26937 50115 26937 50116 25174 50116 25175 50116 26937 50117 25175 50117 26938 50117 26938 50118 25175 50118 26801 50118 26938 50119 26801 50119 26940 50119 26940 50120 26801 50120 26802 50120 26940 50121 26802 50121 25176 50121 25176 50122 26802 50122 25177 50122 25176 50123 25177 50123 25179 50123 25179 50124 25177 50124 25178 50124 25179 50125 25178 50125 25180 50125 25180 50126 25178 50126 26803 50126 25180 50127 26803 50127 25182 50127 25182 50128 26803 50128 25181 50128 25182 50129 25181 50129 26947 50129 26947 50130 25181 50130 25183 50130 26947 50131 25183 50131 26948 50131 26948 50132 25183 50132 25184 50132 26948 50133 25184 50133 21252 50133 21252 50134 25184 50134 26806 50134 26662 50135 25185 50135 25186 50135 26662 50136 25186 50136 26663 50136 26663 50137 25186 50137 26702 50137 26663 50138 26702 50138 25187 50138 25187 50139 26702 50139 26701 50139 25187 50140 26701 50140 25188 50140 25188 50141 26701 50141 26698 50141 25188 50142 26698 50142 26665 50142 26665 50143 26698 50143 26697 50143 26665 50144 26697 50144 25189 50144 25189 50145 26697 50145 25190 50145 25189 50146 25190 50146 26667 50146 26667 50147 25190 50147 26694 50147 26667 50148 26694 50148 25191 50148 25191 50149 26694 50149 26693 50149 25191 50150 26693 50150 26669 50150 26669 50151 26693 50151 26692 50151 26669 50152 26692 50152 25192 50152 25192 50153 26692 50153 25193 50153 25192 50154 25193 50154 26671 50154 26671 50155 25193 50155 26690 50155 26671 50156 26690 50156 26672 50156 26672 50157 26690 50157 26688 50157 26672 50158 26688 50158 26674 50158 26674 50159 26688 50159 25194 50159 26674 50160 25194 50160 25195 50160 25195 50161 25194 50161 26687 50161 25195 50162 26687 50162 26675 50162 26675 50163 26687 50163 25196 50163 26675 50164 25196 50164 26678 50164 26678 50165 25196 50165 26684 50165 26678 50166 26684 50166 21931 50166 27088 50167 25684 50167 25197 50167 25683 50168 27078 50168 25198 50168 25198 50169 27078 50169 27133 50169 25198 50170 27133 50170 25199 50170 25199 50171 27133 50171 25200 50171 25199 50172 25200 50172 25201 50172 25201 50173 25200 50173 27092 50173 25201 50174 27092 50174 25197 50174 25197 50175 27092 50175 25202 50175 25197 50176 25202 50176 27088 50176 25682 50177 25204 50177 25203 50177 25203 50178 25204 50178 25205 50178 25203 50179 25205 50179 27079 50179 27079 50180 25205 50180 25207 50180 27079 50181 25207 50181 25206 50181 25206 50182 25207 50182 25214 50182 25206 50183 25214 50183 25212 50183 25682 50184 25203 50184 25208 50184 25208 50185 25203 50185 27078 50185 25208 50186 27078 50186 25683 50186 27088 50187 27090 50187 25684 50187 25684 50188 27090 50188 25209 50188 25209 50189 27090 50189 25210 50189 25210 50190 27090 50190 25211 50190 25210 50191 25211 50191 25686 50191 25686 50192 25211 50192 25685 50192 25685 50193 25211 50193 27095 50193 25685 50194 27095 50194 25690 50194 25690 50195 27095 50195 27094 50195 25690 50196 27094 50196 25691 50196 27134 50197 25212 50197 25213 50197 25213 50198 25212 50198 25214 50198 27093 50199 25249 50199 27094 50199 27094 50200 25249 50200 25691 50200 25216 50201 25955 50201 25217 50201 25217 50202 25955 50202 25215 50202 25215 50203 25955 50203 25943 50203 25215 50204 25943 50204 27074 50204 25216 50205 25217 50205 25953 50205 25953 50206 25217 50206 25218 50206 25953 50207 25218 50207 25219 50207 25219 50208 25218 50208 25220 50208 25219 50209 25220 50209 25951 50209 25948 50210 25950 50210 27082 50210 25220 50211 27087 50211 25951 50211 25951 50212 27087 50212 25222 50212 25951 50213 25222 50213 25221 50213 25221 50214 25222 50214 25223 50214 25221 50215 25223 50215 25224 50215 25224 50216 25223 50216 27086 50216 25224 50217 27086 50217 25225 50217 25225 50218 27086 50218 27084 50218 25225 50219 27084 50219 25226 50219 25226 50220 27084 50220 27083 50220 25226 50221 27083 50221 25950 50221 25950 50222 27083 50222 25227 50222 25950 50223 25227 50223 27082 50223 27082 50224 27080 50224 25948 50224 25948 50225 27080 50225 25228 50225 25948 50226 25228 50226 25947 50226 25947 50227 25228 50227 25229 50227 25947 50228 25229 50228 25230 50228 25230 50229 25229 50229 25231 50229 25230 50230 25231 50230 25946 50230 25946 50231 25231 50231 27134 50231 25946 50232 27134 50232 25213 50232 25232 50233 25233 50233 25234 50233 25232 50234 25234 50234 25235 50234 25235 50235 25234 50235 25972 50235 25235 50236 25972 50236 25236 50236 25236 50237 25972 50237 25973 50237 25236 50238 25973 50238 25237 50238 25237 50239 25973 50239 27099 50239 27099 50240 25973 50240 25974 50240 27099 50241 25974 50241 27101 50241 27101 50242 25974 50242 25975 50242 27101 50243 25975 50243 27104 50243 27104 50244 25975 50244 25238 50244 27104 50245 25238 50245 25239 50245 25239 50246 25238 50246 25240 50246 25239 50247 25240 50247 27103 50247 27103 50248 25240 50248 25241 50248 27103 50249 25241 50249 25242 50249 25241 50250 25977 50250 25242 50250 25242 50251 25977 50251 25243 50251 25242 50252 25243 50252 25244 50252 25244 50253 25243 50253 25245 50253 25244 50254 25245 50254 27130 50254 27130 50255 25245 50255 25246 50255 25246 50256 25980 50256 27130 50256 27130 50257 25980 50257 25248 50257 27130 50258 25248 50258 27091 50258 27091 50259 25248 50259 25247 50259 25247 50260 25248 50260 25249 50260 25247 50261 25249 50261 27093 50261 27074 50262 25943 50262 27072 50262 27072 50263 25943 50263 25944 50263 25232 50264 27129 50264 25233 50264 25233 50265 27129 50265 25694 50265 27076 50266 25251 50266 27195 50266 27195 50267 25251 50267 25250 50267 25250 50268 25251 50268 25676 50268 25676 50269 25251 50269 25252 50269 25676 50270 25252 50270 25253 50270 25253 50271 25252 50271 25673 50271 25673 50272 25252 50272 27073 50272 25673 50273 27073 50273 25680 50273 25680 50274 27073 50274 27072 50274 25680 50275 27072 50275 25944 50275 25254 50276 25695 50276 25259 50276 25259 50277 25695 50277 25255 50277 25259 50278 25255 50278 25256 50278 25256 50279 25255 50279 25257 50279 25256 50280 25257 50280 27098 50280 27098 50281 25257 50281 25694 50281 27098 50282 25694 50282 27129 50282 25254 50283 25259 50283 25258 50283 25258 50284 25259 50284 27097 50284 25258 50285 27097 50285 25697 50285 27076 50286 27195 50286 25260 50286 25260 50287 27195 50287 25261 50287 25260 50288 25261 50288 27135 50288 27135 50289 25261 50289 27188 50289 27135 50290 27188 50290 25262 50290 25263 50291 25276 50291 25264 50291 25264 50292 25276 50292 27063 50292 25264 50293 27063 50293 25262 50293 25262 50294 27063 50294 27136 50294 25262 50295 27136 50295 27135 50295 27116 50296 25277 50296 27125 50296 27125 50297 25277 50297 25265 50297 27125 50298 25265 50298 27126 50298 27126 50299 25265 50299 25266 50299 27126 50300 25266 50300 27128 50300 27128 50301 25266 50301 27213 50301 27128 50302 27213 50302 25268 50302 25268 50303 27213 50303 25267 50303 25268 50304 25267 50304 25269 50304 25269 50305 25267 50305 25270 50305 25269 50306 25270 50306 27097 50306 27097 50307 25270 50307 25697 50307 25672 50308 27061 50308 21916 50308 21916 50309 27061 50309 25272 50309 21916 50310 25272 50310 21917 50310 21917 50311 25272 50311 25271 50311 25271 50312 25272 50312 21919 50312 21919 50313 25272 50313 25274 50313 21919 50314 25274 50314 25273 50314 25273 50315 25274 50315 21913 50315 21913 50316 25274 50316 27060 50316 21913 50317 27060 50317 25275 50317 25275 50318 27060 50318 25276 50318 25275 50319 25276 50319 25263 50319 27116 50320 25279 50320 25277 50320 25277 50321 25279 50321 25702 50321 25702 50322 25279 50322 25278 50322 25278 50323 25279 50323 25280 50323 25278 50324 25280 50324 25700 50324 25700 50325 25280 50325 25281 50325 25281 50326 25280 50326 25282 50326 25281 50327 25282 50327 25283 50327 25283 50328 25282 50328 27113 50328 25283 50329 27113 50329 25285 50329 25300 50330 27061 50330 25924 50330 25924 50331 27061 50331 25672 50331 27115 50332 25284 50332 27113 50332 27113 50333 25284 50333 25285 50333 25289 50334 25286 50334 25287 50334 25287 50335 25286 50335 25288 50335 25287 50336 25288 50336 25316 50336 25293 50337 21819 50337 27053 50337 27053 50338 21819 50338 25290 50338 27053 50339 25290 50339 25289 50339 25289 50340 25290 50340 25291 50340 25289 50341 25291 50341 25286 50341 27067 50342 25302 50342 25292 50342 25292 50343 25302 50343 25298 50343 27053 50344 27054 50344 25293 50344 25293 50345 27054 50345 27056 50345 25293 50346 27056 50346 25294 50346 25294 50347 27056 50347 27052 50347 25294 50348 27052 50348 25295 50348 25295 50349 27052 50349 27071 50349 25295 50350 27071 50350 21817 50350 21817 50351 27071 50351 25296 50351 21817 50352 25296 50352 25297 50352 25297 50353 25296 50353 27070 50353 25297 50354 27070 50354 25298 50354 25298 50355 27070 50355 27068 50355 25298 50356 27068 50356 25292 50356 25299 50357 25300 50357 25924 50357 27067 50358 27065 50358 25302 50358 25302 50359 27065 50359 25301 50359 25302 50360 25301 50360 21816 50360 21816 50361 25301 50361 25299 50361 21816 50362 25299 50362 25925 50362 25925 50363 25299 50363 25924 50363 25317 50364 25990 50364 25303 50364 25317 50365 25303 50365 25304 50365 25304 50366 25303 50366 25991 50366 25304 50367 25991 50367 27110 50367 27110 50368 25991 50368 25305 50368 27110 50369 25305 50369 27109 50369 27109 50370 25305 50370 25306 50370 27109 50371 25306 50371 27107 50371 27107 50372 25306 50372 25307 50372 27107 50373 25307 50373 27111 50373 27111 50374 25307 50374 27112 50374 27112 50375 25307 50375 25994 50375 27112 50376 25994 50376 25308 50376 25308 50377 25994 50377 25995 50377 25308 50378 25995 50378 25309 50378 25309 50379 25995 50379 25998 50379 25309 50380 25998 50380 25310 50380 25310 50381 25998 50381 25311 50381 25310 50382 25311 50382 25312 50382 25311 50383 25996 50383 25312 50383 25312 50384 25996 50384 25999 50384 25312 50385 25999 50385 25313 50385 25313 50386 25999 50386 26000 50386 25313 50387 26000 50387 25314 50387 26000 50388 26001 50388 25314 50388 25314 50389 26001 50389 25315 50389 25314 50390 25315 50390 27123 50390 27123 50391 25315 50391 25284 50391 27123 50392 25284 50392 27115 50392 25316 50393 25288 50393 27057 50393 27057 50394 25288 50394 25922 50394 25317 50395 25328 50395 25990 50395 25990 50396 25328 50396 25327 50396 25318 50397 25319 50397 25331 50397 25331 50398 25319 50398 25665 50398 25665 50399 25319 50399 25667 50399 25667 50400 25319 50400 27059 50400 25667 50401 27059 50401 25666 50401 25666 50402 27059 50402 25320 50402 25320 50403 27059 50403 25322 50403 25320 50404 25322 50404 25321 50404 25321 50405 25322 50405 27057 50405 25321 50406 27057 50406 25922 50406 25706 50407 25324 50407 25323 50407 25323 50408 25324 50408 25703 50408 25323 50409 25703 50409 27106 50409 27106 50410 25703 50410 25325 50410 27106 50411 25325 50411 25326 50411 25326 50412 25325 50412 25327 50412 25326 50413 25327 50413 25328 50413 25706 50414 25323 50414 25329 50414 25329 50415 25323 50415 25330 50415 25329 50416 25330 50416 27014 50416 25318 50417 25331 50417 27138 50417 27138 50418 25331 50418 25332 50418 27138 50419 25332 50419 27139 50419 27139 50420 25332 50420 25333 50420 27139 50421 25333 50421 25334 50421 25334 50422 25333 50422 27207 50422 25334 50423 27207 50423 25335 50423 27207 50424 27206 50424 25335 50424 25335 50425 27206 50425 25342 50425 25335 50426 25342 50426 27049 50426 27141 50427 25337 50427 25336 50427 25336 50428 25337 50428 25338 50428 25338 50429 25337 50429 25339 50429 25339 50430 25337 50430 27142 50430 25339 50431 27142 50431 21920 50431 21920 50432 27142 50432 25341 50432 21920 50433 25341 50433 25340 50433 25340 50434 25341 50434 27049 50434 25340 50435 27049 50435 25342 50435 21129 50436 25344 50436 27012 50436 27012 50437 25344 50437 25711 50437 25711 50438 25344 50438 25343 50438 25343 50439 25344 50439 25346 50439 25343 50440 25346 50440 25345 50440 25345 50441 25346 50441 25708 50441 25708 50442 25346 50442 25347 50442 25708 50443 25347 50443 25713 50443 25713 50444 25347 50444 25348 50444 25713 50445 25348 50445 25350 50445 25365 50446 27141 50446 25349 50446 25349 50447 27141 50447 25336 50447 21126 50448 26032 50448 25348 50448 25348 50449 26032 50449 25350 50449 25356 50450 25352 50450 25351 50450 25351 50451 25352 50451 25354 50451 25354 50452 25352 50452 25353 50452 25354 50453 25353 50453 25355 50453 25356 50454 25351 50454 21831 50454 21831 50455 25351 50455 25357 50455 21831 50456 25357 50456 25358 50456 25358 50457 25357 50457 27042 50457 25358 50458 27042 50458 25359 50458 25359 50459 27042 50459 25360 50459 25359 50460 25360 50460 21829 50460 21829 50461 25360 50461 25361 50461 21829 50462 25361 50462 21825 50462 21825 50463 25361 50463 27041 50463 21825 50464 27041 50464 25362 50464 25362 50465 27041 50465 25363 50465 25362 50466 25363 50466 21827 50466 21827 50467 25363 50467 25364 50467 21827 50468 25364 50468 21828 50468 25367 50469 21823 50469 25366 50469 21828 50470 25364 50470 21823 50470 21823 50471 25364 50471 27040 50471 21823 50472 27040 50472 25366 50472 25372 50473 25365 50473 25349 50473 25366 50474 27051 50474 25367 50474 25367 50475 27051 50475 25368 50475 25367 50476 25368 50476 25369 50476 25369 50477 25368 50477 25370 50477 25369 50478 25370 50478 25371 50478 25371 50479 25370 50479 25372 50479 25371 50480 25372 50480 25909 50480 25909 50481 25372 50481 25349 50481 25385 50482 25387 50482 25373 50482 25385 50483 25373 50483 21118 50483 21118 50484 25373 50484 25374 50484 21118 50485 25374 50485 25375 50485 25375 50486 25374 50486 26020 50486 25375 50487 26020 50487 25376 50487 25376 50488 26020 50488 26021 50488 25376 50489 26021 50489 25377 50489 25377 50490 26021 50490 26022 50490 25377 50491 26022 50491 21120 50491 21120 50492 26022 50492 25378 50492 25378 50493 26022 50493 26023 50493 25378 50494 26023 50494 21121 50494 21121 50495 26023 50495 25379 50495 21121 50496 25379 50496 25380 50496 25380 50497 25379 50497 26027 50497 25380 50498 26027 50498 25381 50498 25381 50499 26027 50499 26026 50499 25381 50500 26026 50500 21123 50500 26026 50501 26028 50501 21123 50501 21123 50502 26028 50502 26029 50502 21123 50503 26029 50503 25382 50503 25382 50504 26029 50504 25383 50504 25382 50505 25383 50505 21124 50505 25383 50506 26030 50506 21124 50506 21124 50507 26030 50507 25384 50507 21124 50508 25384 50508 21125 50508 21125 50509 25384 50509 26032 50509 21125 50510 26032 50510 21126 50510 25355 50511 25353 50511 25391 50511 25391 50512 25353 50512 25392 50512 25385 50513 25386 50513 25387 50513 25387 50514 25386 50514 26018 50514 27046 50515 25388 50515 25396 50515 25396 50516 25388 50516 25661 50516 25661 50517 25388 50517 25659 50517 25659 50518 25388 50518 27047 50518 25659 50519 27047 50519 25389 50519 25389 50520 27047 50520 25658 50520 25658 50521 27047 50521 25390 50521 25658 50522 25390 50522 25662 50522 25662 50523 25390 50523 25391 50523 25662 50524 25391 50524 25392 50524 25720 50525 25719 50525 25395 50525 25395 50526 25719 50526 25714 50526 25395 50527 25714 50527 25393 50527 25393 50528 25714 50528 25716 50528 25393 50529 25716 50529 25394 50529 25394 50530 25716 50530 26018 50530 25394 50531 26018 50531 25386 50531 25720 50532 25395 50532 25721 50532 25721 50533 25395 50533 25406 50533 25721 50534 25406 50534 25722 50534 27046 50535 25396 50535 27045 50535 27045 50536 25396 50536 25397 50536 27045 50537 25397 50537 27144 50537 27144 50538 25397 50538 27205 50538 27144 50539 27205 50539 27147 50539 27147 50540 27205 50540 25398 50540 27147 50541 25398 50541 27148 50541 27148 50542 25398 50542 27204 50542 27148 50543 27204 50543 27149 50543 27149 50544 27204 50544 25399 50544 27149 50545 25399 50545 27024 50545 27024 50546 25399 50546 21923 50546 21139 50547 27161 50547 25400 50547 25400 50548 27161 50548 25401 50548 25400 50549 25401 50549 25403 50549 25403 50550 25401 50550 25402 50550 25403 50551 25402 50551 21230 50551 21230 50552 25402 50552 25404 50552 21230 50553 25404 50553 25405 50553 25405 50554 25404 50554 27168 50554 25405 50555 27168 50555 21232 50555 21232 50556 27168 50556 27166 50556 21232 50557 27166 50557 25406 50557 25406 50558 27166 50558 25722 50558 25656 50559 27150 50559 27026 50559 25656 50560 27026 50560 25407 50560 25407 50561 27026 50561 27025 50561 25407 50562 27025 50562 25408 50562 25408 50563 27025 50563 25409 50563 25409 50564 27025 50564 25410 50564 25409 50565 25410 50565 25411 50565 25411 50566 25410 50566 25412 50566 25412 50567 25410 50567 27024 50567 25412 50568 27024 50568 21923 50568 21139 50569 25413 50569 27161 50569 27161 50570 25413 50570 25727 50570 25727 50571 25413 50571 25725 50571 25725 50572 25413 50572 25415 50572 25725 50573 25415 50573 25414 50573 25414 50574 25415 50574 25724 50574 25724 50575 25415 50575 21137 50575 25724 50576 21137 50576 25729 50576 25729 50577 21137 50577 25417 50577 25729 50578 25417 50578 25730 50578 27027 50579 27150 50579 25890 50579 25890 50580 27150 50580 25656 50580 25416 50581 26059 50581 25417 50581 25417 50582 26059 50582 25730 50582 25419 50583 25418 50583 27034 50583 25418 50584 25419 50584 27035 50584 27035 50585 25419 50585 25886 50585 27035 50586 25886 50586 25420 50586 25421 50587 27030 50587 25895 50587 25895 50588 21835 50588 25421 50588 25421 50589 21835 50589 21834 50589 25421 50590 21834 50590 25422 50590 25422 50591 21834 50591 21836 50591 25422 50592 21836 50592 27031 50592 27031 50593 21836 50593 21837 50593 27031 50594 21837 50594 27033 50594 27033 50595 21837 50595 21839 50595 27033 50596 21839 50596 25423 50596 25423 50597 21839 50597 21840 50597 25423 50598 21840 50598 27034 50598 27034 50599 21840 50599 25424 50599 27034 50600 25424 50600 25419 50600 27030 50601 25425 50601 25895 50601 25895 50602 25425 50602 27029 50602 25895 50603 27029 50603 25894 50603 25894 50604 27029 50604 27028 50604 25894 50605 27028 50605 25893 50605 25893 50606 27028 50606 25426 50606 25893 50607 25426 50607 25428 50607 25428 50608 25426 50608 25427 50608 25428 50609 25427 50609 25892 50609 25892 50610 25427 50610 27027 50610 25892 50611 27027 50611 25890 50611 21224 50612 26045 50612 26046 50612 21224 50613 26046 50613 21144 50613 21144 50614 26046 50614 25429 50614 21144 50615 25429 50615 25430 50615 25430 50616 25429 50616 26047 50616 25430 50617 26047 50617 21146 50617 21146 50618 26047 50618 25431 50618 25431 50619 26047 50619 25432 50619 25431 50620 25432 50620 21132 50620 21132 50621 25432 50621 25433 50621 21132 50622 25433 50622 21130 50622 21130 50623 25433 50623 25434 50623 25434 50624 25433 50624 25435 50624 25434 50625 25435 50625 25436 50625 25436 50626 25435 50626 26053 50626 25436 50627 26053 50627 25437 50627 25437 50628 26053 50628 26051 50628 25437 50629 26051 50629 21133 50629 26051 50630 26050 50630 21133 50630 21133 50631 26050 50631 26049 50631 21133 50632 26049 50632 21134 50632 21134 50633 26049 50633 26054 50633 21134 50634 26054 50634 21135 50634 21135 50635 26054 50635 25438 50635 25438 50636 26055 50636 21135 50636 21135 50637 26055 50637 26056 50637 21135 50638 26056 50638 25439 50638 25439 50639 26056 50639 21136 50639 21136 50640 26056 50640 26059 50640 21136 50641 26059 50641 25416 50641 25420 50642 25886 50642 25444 50642 25444 50643 25886 50643 25888 50643 21224 50644 21225 50644 26045 50644 26045 50645 21225 50645 26044 50645 25440 50646 25442 50646 25647 50646 25647 50647 25442 50647 25648 50647 25648 50648 25442 50648 25441 50648 25441 50649 25442 50649 27039 50649 25441 50650 27039 50650 25649 50650 25649 50651 27039 50651 25443 50651 25443 50652 27039 50652 27036 50652 25443 50653 27036 50653 25651 50653 25651 50654 27036 50654 25444 50654 25651 50655 25444 50655 25888 50655 25735 50656 25734 50656 21140 50656 21140 50657 25734 50657 25445 50657 21140 50658 25445 50658 21141 50658 21141 50659 25445 50659 25733 50659 21141 50660 25733 50660 21142 50660 21142 50661 25733 50661 26044 50661 21142 50662 26044 50662 21225 50662 25735 50663 21140 50663 25446 50663 25446 50664 21140 50664 25447 50664 25446 50665 25447 50665 25738 50665 25462 50666 25741 50666 21223 50666 21223 50667 25741 50667 25449 50667 21223 50668 25449 50668 25448 50668 25448 50669 25449 50669 25451 50669 25448 50670 25451 50670 25450 50670 25450 50671 25451 50671 27172 50671 25450 50672 27172 50672 25452 50672 27172 50673 27170 50673 25452 50673 25452 50674 27170 50674 25738 50674 25452 50675 25738 50675 25447 50675 25645 50676 25453 50676 21189 50676 21189 50677 25453 50677 25454 50677 21189 50678 25454 50678 25455 50678 25455 50679 25454 50679 25456 50679 25455 50680 25456 50680 21190 50680 21190 50681 25456 50681 25457 50681 21190 50682 25457 50682 25458 50682 25645 50683 21189 50683 25459 50683 25459 50684 21189 50684 25460 50684 25459 50685 25460 50685 25461 50685 25462 50686 25463 50686 25741 50686 25741 50687 25463 50687 25745 50687 25745 50688 25463 50688 25744 50688 25744 50689 25463 50689 25464 50689 25744 50690 25464 50690 25465 50690 25465 50691 25464 50691 25742 50691 25742 50692 25464 50692 25466 50692 25742 50693 25466 50693 25467 50693 25467 50694 25466 50694 21148 50694 25467 50695 21148 50695 25817 50695 25488 50696 25458 50696 25865 50696 25865 50697 25458 50697 25457 50697 21150 50698 25507 50698 21148 50698 21148 50699 25507 50699 25817 50699 21846 50700 25468 50700 25476 50700 25468 50701 21846 50701 21198 50701 21198 50702 21846 50702 25469 50702 21198 50703 25469 50703 25508 50703 25470 50704 25868 50704 25471 50704 25471 50705 25868 50705 25472 50705 25868 50706 25871 50706 25472 50706 25472 50707 25871 50707 25872 50707 25472 50708 25872 50708 25473 50708 25473 50709 25872 50709 21843 50709 25473 50710 21843 50710 25474 50710 25474 50711 21843 50711 21844 50711 25474 50712 21844 50712 25475 50712 25475 50713 21844 50713 25477 50713 25475 50714 25477 50714 25476 50714 25476 50715 25477 50715 25478 50715 25476 50716 25478 50716 21846 50716 25471 50717 21195 50717 25470 50717 25470 50718 21195 50718 25479 50718 25470 50719 25479 50719 25480 50719 25480 50720 25479 50720 25481 50720 25480 50721 25481 50721 25482 50721 25481 50722 21193 50722 25482 50722 25482 50723 21193 50723 21192 50723 25482 50724 21192 50724 25483 50724 25483 50725 21192 50725 25484 50725 25483 50726 25484 50726 25486 50726 25486 50727 25484 50727 25485 50727 25486 50728 25485 50728 25487 50728 25487 50729 25485 50729 25488 50729 25487 50730 25488 50730 25865 50730 21155 50731 25818 50731 25489 50731 21155 50732 25489 50732 21158 50732 21158 50733 25489 50733 25490 50733 21158 50734 25490 50734 25491 50734 25491 50735 25490 50735 25492 50735 25491 50736 25492 50736 21157 50736 21157 50737 25492 50737 25493 50737 25493 50738 25492 50738 25821 50738 25493 50739 25821 50739 21159 50739 21159 50740 25821 50740 25494 50740 21159 50741 25494 50741 25495 50741 25495 50742 25494 50742 25824 50742 25495 50743 25824 50743 21162 50743 21162 50744 25824 50744 25496 50744 21162 50745 25496 50745 25497 50745 25497 50746 25496 50746 25823 50746 25497 50747 25823 50747 21147 50747 25823 50748 25498 50748 21147 50748 21147 50749 25498 50749 25499 50749 21147 50750 25499 50750 25500 50750 25500 50751 25499 50751 25825 50751 25500 50752 25825 50752 25501 50752 25501 50753 25825 50753 25502 50753 25502 50754 25503 50754 25501 50754 25501 50755 25503 50755 25504 50755 25501 50756 25504 50756 25505 50756 25505 50757 25504 50757 25506 50757 25506 50758 25504 50758 25507 50758 25506 50759 25507 50759 21150 50759 25508 50760 25469 50760 21201 50760 21201 50761 25469 50761 25863 50761 21155 50762 25509 50762 25818 50762 25818 50763 25509 50763 25750 50763 25518 50764 25510 50764 25642 50764 25642 50765 25510 50765 25641 50765 25641 50766 25510 50766 21927 50766 21927 50767 25510 50767 21203 50767 21927 50768 21203 50768 25511 50768 25511 50769 21203 50769 21199 50769 25511 50770 21199 50770 21924 50770 21924 50771 21199 50771 21201 50771 21924 50772 21201 50772 25863 50772 25751 50773 25512 50773 21152 50773 21152 50774 25512 50774 25513 50774 21152 50775 25513 50775 21156 50775 21156 50776 25513 50776 25514 50776 21156 50777 25514 50777 25515 50777 25515 50778 25514 50778 25750 50778 25515 50779 25750 50779 25509 50779 25751 50780 21152 50780 25516 50780 25516 50781 21152 50781 21153 50781 25516 50782 21153 50782 25517 50782 25518 50783 25642 50783 21200 50783 21200 50784 25642 50784 27185 50784 21200 50785 27185 50785 21211 50785 21211 50786 27185 50786 25520 50786 21211 50787 25520 50787 25519 50787 25519 50788 25520 50788 25521 50788 25519 50789 25521 50789 21212 50789 21212 50790 25521 50790 27184 50790 21212 50791 27184 50791 25522 50791 25522 50792 27184 50792 25523 50792 25522 50793 25523 50793 21178 50793 21178 50794 25523 50794 25524 50794 25531 50795 26066 50795 21218 50795 21218 50796 26066 50796 27178 50796 21218 50797 27178 50797 21219 50797 21219 50798 27178 50798 27177 50798 21219 50799 27177 50799 27174 50799 25517 50800 21153 50800 27173 50800 27173 50801 21153 50801 21154 50801 27173 50802 21154 50802 27174 50802 27174 50803 21154 50803 25525 50803 27174 50804 25525 50804 21219 50804 25637 50805 25636 50805 21179 50805 21179 50806 25636 50806 25635 50806 21179 50807 25635 50807 25526 50807 25526 50808 25635 50808 25528 50808 25526 50809 25528 50809 25527 50809 25527 50810 25528 50810 25529 50810 25527 50811 25529 50811 21180 50811 25637 50812 21179 50812 25530 50812 25530 50813 21179 50813 21178 50813 25530 50814 21178 50814 25524 50814 25531 50815 25533 50815 26066 50815 26066 50816 25533 50816 26067 50816 26067 50817 25533 50817 25532 50817 25532 50818 25533 50818 21166 50818 25532 50819 21166 50819 26069 50819 26069 50820 21166 50820 26070 50820 26070 50821 21166 50821 25535 50821 26070 50822 25535 50822 25534 50822 25534 50823 25535 50823 26071 50823 26071 50824 25535 50824 21164 50824 26071 50825 21164 50825 25536 50825 25537 50826 21180 50826 25843 50826 25843 50827 21180 50827 25529 50827 25538 50828 25539 50828 21164 50828 21164 50829 25539 50829 25536 50829 25841 50830 25577 50830 21173 50830 25841 50831 21173 50831 25540 50831 25540 50832 21173 50832 25541 50832 25540 50833 25541 50833 25543 50833 25543 50834 25541 50834 25542 50834 25543 50835 25542 50835 25544 50835 25542 50836 21186 50836 25544 50836 25544 50837 21186 50837 25545 50837 25544 50838 25545 50838 25546 50838 25546 50839 25545 50839 25547 50839 25546 50840 25547 50840 25850 50840 25850 50841 25547 50841 21188 50841 25850 50842 21188 50842 25548 50842 25548 50843 21188 50843 21187 50843 25548 50844 21187 50844 25549 50844 25549 50845 21187 50845 25550 50845 25549 50846 25550 50846 25551 50846 25551 50847 25550 50847 21184 50847 25551 50848 21184 50848 25552 50848 25552 50849 21184 50849 25553 50849 25552 50850 25553 50850 25554 50850 25554 50851 25553 50851 25555 50851 25554 50852 25555 50852 25848 50852 25848 50853 25555 50853 21182 50853 25848 50854 21182 50854 25847 50854 25847 50855 21182 50855 21181 50855 25847 50856 21181 50856 25556 50856 25556 50857 21181 50857 25557 50857 25556 50858 25557 50858 25844 50858 25844 50859 25557 50859 25537 50859 25844 50860 25537 50860 25843 50860 25558 50861 25559 50861 26090 50861 26090 50862 25559 50862 21215 50862 26090 50863 21215 50863 26085 50863 25558 50864 26089 50864 25559 50864 25559 50865 26089 50865 25560 50865 25559 50866 25560 50866 25561 50866 25561 50867 25560 50867 26091 50867 25561 50868 26091 50868 25562 50868 25562 50869 26091 50869 26092 50869 25572 50870 21172 50870 26097 50870 26097 50871 21172 50871 21171 50871 26097 50872 21171 50872 26098 50872 26098 50873 21171 50873 25563 50873 26098 50874 25563 50874 26093 50874 26093 50875 25563 50875 21169 50875 26093 50876 21169 50876 25565 50876 25565 50877 21169 50877 25564 50877 25565 50878 25564 50878 25566 50878 25566 50879 25564 50879 25567 50879 25566 50880 25567 50880 25568 50880 25568 50881 25567 50881 25569 50881 25568 50882 25569 50882 26092 50882 26092 50883 25569 50883 25570 50883 26092 50884 25570 50884 25562 50884 26097 50885 25571 50885 25572 50885 25572 50886 25571 50886 26095 50886 25572 50887 26095 50887 21216 50887 21216 50888 26095 50888 26101 50888 21216 50889 26101 50889 25576 50889 25539 50890 25538 50890 21805 50890 21805 50891 25538 50891 25574 50891 21805 50892 25574 50892 25573 50892 25573 50893 25574 50893 25576 50893 25573 50894 25576 50894 25575 50894 25575 50895 25576 50895 26101 50895 25577 50896 25841 50896 21175 50896 21175 50897 25841 50897 25583 50897 21215 50898 25587 50898 26085 50898 26085 50899 25587 50899 25578 50899 25595 50900 25580 50900 25579 50900 25579 50901 25580 50901 25630 50901 25630 50902 25580 50902 25629 50902 25629 50903 25580 50903 25581 50903 25629 50904 25581 50904 21930 50904 21930 50905 25581 50905 21176 50905 21930 50906 21176 50906 21929 50906 21929 50907 21176 50907 25582 50907 25582 50908 21176 50908 21175 50908 25582 50909 21175 50909 25583 50909 25588 50910 26074 50910 25590 50910 25590 50911 26074 50911 25585 50911 25590 50912 25585 50912 25584 50912 25584 50913 25585 50913 26073 50913 25584 50914 26073 50914 25586 50914 25586 50915 26073 50915 25578 50915 25586 50916 25578 50916 25587 50916 25588 50917 25590 50917 25589 50917 25589 50918 25590 50918 25591 50918 25589 50919 25591 50919 26076 50919 25595 50920 25579 50920 27154 50920 26076 50921 25591 50921 27180 50921 27180 50922 25591 50922 25592 50922 27180 50923 25592 50923 27179 50923 27179 50924 25592 50924 25593 50924 27179 50925 25593 50925 27153 50925 27153 50926 25593 50926 21213 50926 27153 50927 21213 50927 27154 50927 27154 50928 21213 50928 25594 50928 27154 50929 25594 50929 25595 50929 27155 50930 25596 50930 25597 50930 25597 50931 25596 50931 25631 50931 25597 50932 25631 50932 25598 50932 25598 50933 25852 50933 25638 50933 25598 50934 25638 50934 25597 50934 25597 50935 25638 50935 25639 50935 25597 50936 25639 50936 27182 50936 27151 50937 27186 50937 25640 50937 25876 50938 25600 50938 25599 50938 25599 50939 25600 50939 25646 50939 25599 50940 25646 50940 25640 50940 25640 50941 25646 50941 25601 50941 25640 50942 25601 50942 27151 50942 21922 50943 27189 50943 27202 50943 25603 50944 25896 50944 25897 50944 27202 50945 25602 50945 21922 50945 21922 50946 25602 50946 25603 50946 21922 50947 25603 50947 25653 50947 25653 50948 25603 50948 25897 50948 25606 50949 25657 50949 25604 50949 25604 50950 25605 50950 25606 50950 25606 50951 25605 50951 25912 50951 25606 50952 25912 50952 25913 50952 25913 50953 21921 50953 25606 50953 25606 50954 21921 50954 25607 50954 25606 50955 25607 50955 25608 50955 25612 50956 27199 50956 25669 50956 25669 50957 25609 50957 25612 50957 25612 50958 25609 50958 25668 50958 25612 50959 25668 50959 25610 50959 25610 50960 25611 50960 25612 50960 25612 50961 25611 50961 21914 50961 25612 50962 21914 50962 21915 50962 25613 50963 27196 50963 25679 50963 25679 50964 25678 50964 25613 50964 25613 50965 25678 50965 25677 50965 25613 50966 25677 50966 25959 50966 25959 50967 25614 50967 25613 50967 25613 50968 25614 50968 25615 50968 25613 50969 25615 50969 27210 50969 27194 50970 25616 50970 25619 50970 25619 50971 25616 50971 25688 50971 25619 50972 25688 50972 25687 50972 25687 50973 25617 50973 25618 50973 25687 50974 25618 50974 25619 50974 25619 50975 25618 50975 25696 50975 25619 50976 25696 50976 25698 50976 26003 50977 26004 50977 25620 50977 25620 50978 26004 50978 25621 50978 25620 50979 25621 50979 25699 50979 25699 50980 25621 50980 27211 50980 27211 50981 25621 50981 25707 50981 27211 50982 25707 50982 27190 50982 25710 50983 25622 50983 25623 50983 25623 50984 25622 50984 25624 50984 25623 50985 25624 50985 25712 50985 25712 50986 25624 50986 27163 50986 27163 50987 25624 50987 25723 50987 27163 50988 25723 50988 27164 50988 25626 50989 27162 50989 25625 50989 25625 50990 25728 50990 25626 50990 25626 50991 25728 50991 25726 50991 25626 50992 25726 50992 26972 50992 26972 50993 25736 50993 25626 50993 25626 50994 25736 50994 25737 50994 25626 50995 25737 50995 27169 50995 25627 50996 25739 50996 25740 50996 25740 50997 25746 50997 25627 50997 25627 50998 25746 50998 25830 50998 25627 50999 25830 50999 25828 50999 25828 51000 25752 51000 25627 51000 25627 51001 25752 51001 25628 51001 25627 51002 25628 51002 27159 51002 25598 51003 25630 51003 25851 51003 25851 51004 25630 51004 25629 51004 25851 51005 25629 51005 21930 51005 27155 51006 25579 51006 25596 51006 25596 51007 25579 51007 25630 51007 25596 51008 25630 51008 25631 51008 25631 51009 25630 51009 25598 51009 25852 51010 25632 51010 25635 51010 25635 51011 25632 51011 25633 51011 25635 51012 25633 51012 25528 51012 25528 51013 25633 51013 25634 51013 25528 51014 25634 51014 25529 51014 25635 51015 25636 51015 25852 51015 25852 51016 25636 51016 25637 51016 25852 51017 25637 51017 25638 51017 25638 51018 25637 51018 25530 51018 25638 51019 25530 51019 25639 51019 25639 51020 25530 51020 25524 51020 25639 51021 25524 51021 27182 51021 25640 51022 27186 51022 25641 51022 25641 51023 27186 51023 25642 51023 25600 51024 25643 51024 25454 51024 25454 51025 25643 51025 25644 51025 25454 51026 25644 51026 25456 51026 25456 51027 25644 51027 25864 51027 25456 51028 25864 51028 25457 51028 25454 51029 25453 51029 25600 51029 25600 51030 25453 51030 25645 51030 25600 51031 25645 51031 25646 51031 25646 51032 25645 51032 25459 51032 25646 51033 25459 51033 25601 51033 25601 51034 25459 51034 25461 51034 25601 51035 25461 51035 27151 51035 27202 51036 25647 51036 25602 51036 25602 51037 25647 51037 25648 51037 25443 51038 25652 51038 25649 51038 25649 51039 25652 51039 25650 51039 25649 51040 25650 51040 25441 51040 25441 51041 25650 51041 25896 51041 25441 51042 25896 51042 25648 51042 25648 51043 25896 51043 25603 51043 25648 51044 25603 51044 25602 51044 25443 51045 25651 51045 25652 51045 25652 51046 25651 51046 25888 51046 25652 51047 25888 51047 25889 51047 25412 51048 21922 51048 25411 51048 25411 51049 21922 51049 25653 51049 25411 51050 25653 51050 25409 51050 25409 51051 25653 51051 25897 51051 25409 51052 25897 51052 25408 51052 25408 51053 25897 51053 25654 51053 25408 51054 25654 51054 25407 51054 25407 51055 25654 51055 25655 51055 25407 51056 25655 51056 25656 51056 25657 51057 25396 51057 25604 51057 25604 51058 25396 51058 25661 51058 25658 51059 25910 51059 25389 51059 25389 51060 25910 51060 25660 51060 25389 51061 25660 51061 25659 51061 25659 51062 25660 51062 25912 51062 25659 51063 25912 51063 25661 51063 25661 51064 25912 51064 25605 51064 25661 51065 25605 51065 25604 51065 25658 51066 25662 51066 25910 51066 25910 51067 25662 51067 25392 51067 25910 51068 25392 51068 25906 51068 21920 51069 25663 51069 25339 51069 25339 51070 25663 51070 25664 51070 25339 51071 25664 51071 25338 51071 25338 51072 25664 51072 25907 51072 25338 51073 25907 51073 25336 51073 27199 51074 25331 51074 25669 51074 25669 51075 25331 51075 25665 51075 25320 51076 25670 51076 25666 51076 25666 51077 25670 51077 25928 51077 25666 51078 25928 51078 25667 51078 25667 51079 25928 51079 25668 51079 25667 51080 25668 51080 25665 51080 25665 51081 25668 51081 25609 51081 25665 51082 25609 51082 25669 51082 25320 51083 25321 51083 25670 51083 25670 51084 25321 51084 25922 51084 25670 51085 25922 51085 25671 51085 25927 51086 25942 51086 21916 51086 21916 51087 25942 51087 25672 51087 27196 51088 27195 51088 25679 51088 25679 51089 27195 51089 25250 51089 25673 51090 25674 51090 25253 51090 25253 51091 25674 51091 25675 51091 25253 51092 25675 51092 25676 51092 25676 51093 25675 51093 25677 51093 25676 51094 25677 51094 25250 51094 25250 51095 25677 51095 25678 51095 25250 51096 25678 51096 25679 51096 25673 51097 25680 51097 25674 51097 25674 51098 25680 51098 25944 51098 25674 51099 25944 51099 25960 51099 25959 51100 25956 51100 25205 51100 25205 51101 25956 51101 25681 51101 25205 51102 25681 51102 25207 51102 25207 51103 25681 51103 25945 51103 25207 51104 25945 51104 25214 51104 25205 51105 25204 51105 25959 51105 25959 51106 25204 51106 25682 51106 25959 51107 25682 51107 25614 51107 25614 51108 25682 51108 25208 51108 25614 51109 25208 51109 25615 51109 25615 51110 25208 51110 25683 51110 25615 51111 25683 51111 27210 51111 27194 51112 25684 51112 25616 51112 25616 51113 25684 51113 25209 51113 25685 51114 25689 51114 25686 51114 25686 51115 25689 51115 25982 51115 25686 51116 25982 51116 25210 51116 25210 51117 25982 51117 25687 51117 25210 51118 25687 51118 25209 51118 25209 51119 25687 51119 25688 51119 25209 51120 25688 51120 25616 51120 25685 51121 25690 51121 25689 51121 25689 51122 25690 51122 25691 51122 25689 51123 25691 51123 25968 51123 25617 51124 25692 51124 25255 51124 25255 51125 25692 51125 25693 51125 25255 51126 25693 51126 25257 51126 25257 51127 25693 51127 25969 51127 25257 51128 25969 51128 25694 51128 25255 51129 25695 51129 25617 51129 25617 51130 25695 51130 25254 51130 25617 51131 25254 51131 25618 51131 25618 51132 25254 51132 25258 51132 25618 51133 25258 51133 25696 51133 25696 51134 25258 51134 25697 51134 25696 51135 25697 51135 25698 51135 27211 51136 25277 51136 25699 51136 25699 51137 25277 51137 25702 51137 25281 51138 26006 51138 25700 51138 25700 51139 26006 51139 25701 51139 25700 51140 25701 51140 25278 51140 25278 51141 25701 51141 26003 51141 25278 51142 26003 51142 25702 51142 25702 51143 26003 51143 25620 51143 25702 51144 25620 51144 25699 51144 25281 51145 25283 51145 26006 51145 26006 51146 25283 51146 25285 51146 26006 51147 25285 51147 26008 51147 26004 51148 25704 51148 25703 51148 25703 51149 25704 51149 25705 51149 25703 51150 25705 51150 25325 51150 25325 51151 25705 51151 26016 51151 25325 51152 26016 51152 25327 51152 25703 51153 25324 51153 26004 51153 26004 51154 25324 51154 25706 51154 26004 51155 25706 51155 25621 51155 25621 51156 25706 51156 25329 51156 25621 51157 25329 51157 25707 51157 25707 51158 25329 51158 27014 51158 25707 51159 27014 51159 27190 51159 27163 51160 27012 51160 25712 51160 25712 51161 27012 51161 25711 51161 25708 51162 25709 51162 25345 51162 25345 51163 25709 51163 26033 51163 25345 51164 26033 51164 25343 51164 25343 51165 26033 51165 25710 51165 25343 51166 25710 51166 25711 51166 25711 51167 25710 51167 25623 51167 25711 51168 25623 51168 25712 51168 25708 51169 25713 51169 25709 51169 25709 51170 25713 51170 25350 51170 25709 51171 25350 51171 26036 51171 25622 51172 25715 51172 25714 51172 25714 51173 25715 51173 25717 51173 25714 51174 25717 51174 25716 51174 25716 51175 25717 51175 25718 51175 25716 51176 25718 51176 26018 51176 25714 51177 25719 51177 25622 51177 25622 51178 25719 51178 25720 51178 25622 51179 25720 51179 25624 51179 25624 51180 25720 51180 25721 51180 25624 51181 25721 51181 25723 51181 25723 51182 25721 51182 25722 51182 25723 51183 25722 51183 27164 51183 27162 51184 27161 51184 25625 51184 25625 51185 27161 51185 25727 51185 25724 51186 25731 51186 25414 51186 25414 51187 25731 51187 26970 51187 25414 51188 26970 51188 25725 51188 25725 51189 26970 51189 25726 51189 25725 51190 25726 51190 25727 51190 25727 51191 25726 51191 25728 51191 25727 51192 25728 51192 25625 51192 25724 51193 25729 51193 25731 51193 25731 51194 25729 51194 25730 51194 25731 51195 25730 51195 26977 51195 26972 51196 25732 51196 25445 51196 25445 51197 25732 51197 26974 51197 25445 51198 26974 51198 25733 51198 25733 51199 26974 51199 26973 51199 25733 51200 26973 51200 26044 51200 25445 51201 25734 51201 26972 51201 26972 51202 25734 51202 25735 51202 26972 51203 25735 51203 25736 51203 25736 51204 25735 51204 25446 51204 25736 51205 25446 51205 25737 51205 25737 51206 25446 51206 25738 51206 25737 51207 25738 51207 27169 51207 25739 51208 25741 51208 25740 51208 25740 51209 25741 51209 25745 51209 25742 51210 25747 51210 25465 51210 25465 51211 25747 51211 25743 51211 25465 51212 25743 51212 25744 51212 25744 51213 25743 51213 25830 51213 25744 51214 25830 51214 25745 51214 25745 51215 25830 51215 25746 51215 25745 51216 25746 51216 25740 51216 25742 51217 25467 51217 25747 51217 25747 51218 25467 51218 25817 51218 25747 51219 25817 51219 25832 51219 25828 51220 25829 51220 25513 51220 25513 51221 25829 51221 25748 51221 25513 51222 25748 51222 25514 51222 25514 51223 25748 51223 25749 51223 25514 51224 25749 51224 25750 51224 25513 51225 25512 51225 25828 51225 25828 51226 25512 51226 25751 51226 25828 51227 25751 51227 25752 51227 25752 51228 25751 51228 25516 51228 25752 51229 25516 51229 25628 51229 25628 51230 25516 51230 25517 51230 25628 51231 25517 51231 27159 51231 21912 51232 25753 51232 25754 51232 25754 51233 25753 51233 25755 51233 25754 51234 25755 51234 24285 51234 24285 51235 25755 51235 25853 51235 24285 51236 25853 51236 24293 51236 24293 51237 25853 51237 25756 51237 24293 51238 25756 51238 24292 51238 24292 51239 25756 51239 25854 51239 24292 51240 25854 51240 25757 51240 25757 51241 25854 51241 25856 51241 25757 51242 25856 51242 21907 51242 21907 51243 25856 51243 25857 51243 24280 51244 25874 51244 25758 51244 25758 51245 25874 51245 25875 51245 25758 51246 25875 51246 25759 51246 25759 51247 25875 51247 25877 51247 25759 51248 25877 51248 25761 51248 25761 51249 25877 51249 25760 51249 25761 51250 25760 51250 24283 51250 24283 51251 25760 51251 25879 51251 24283 51252 25879 51252 24284 51252 24284 51253 25879 51253 25880 51253 24284 51254 25880 51254 25762 51254 25762 51255 25880 51255 25881 51255 24271 51256 25764 51256 25763 51256 25763 51257 25764 51257 25765 51257 25763 51258 25765 51258 25766 51258 25766 51259 25765 51259 25898 51259 25766 51260 25898 51260 24268 51260 24268 51261 25898 51261 25767 51261 24268 51262 25767 51262 25768 51262 25768 51263 25767 51263 25769 51263 25768 51264 25769 51264 25770 51264 25770 51265 25769 51265 25899 51265 25770 51266 25899 51266 24265 51266 24265 51267 25899 51267 25771 51267 24254 51268 25772 51268 24253 51268 24253 51269 25772 51269 25774 51269 24253 51270 25774 51270 25773 51270 25773 51271 25774 51271 25916 51271 25773 51272 25916 51272 25775 51272 25775 51273 25916 51273 25917 51273 25775 51274 25917 51274 24261 51274 24261 51275 25917 51275 25776 51275 24261 51276 25776 51276 24260 51276 24260 51277 25776 51277 25918 51277 24260 51278 25918 51278 21892 51278 21892 51279 25918 51279 25919 51279 21891 51280 25932 51280 24239 51280 24239 51281 25932 51281 25933 51281 24239 51282 25933 51282 24238 51282 24238 51283 25933 51283 25935 51283 24238 51284 25935 51284 24251 51284 24251 51285 25935 51285 25777 51285 24251 51286 25777 51286 24250 51286 24250 51287 25777 51287 25936 51287 24250 51288 25936 51288 25778 51288 25778 51289 25936 51289 25938 51289 25778 51290 25938 51290 24247 51290 24247 51291 25938 51291 25940 51291 24228 51292 25779 51292 25780 51292 25780 51293 25779 51293 25781 51293 25780 51294 25781 51294 25782 51294 25782 51295 25781 51295 25963 51295 25782 51296 25963 51296 25783 51296 25783 51297 25963 51297 25964 51297 25783 51298 25964 51298 25784 51298 25784 51299 25964 51299 25785 51299 25784 51300 25785 51300 24235 51300 24235 51301 25785 51301 25786 51301 24235 51302 25786 51302 25787 51302 25787 51303 25786 51303 25967 51303 24217 51304 25987 51304 24215 51304 24215 51305 25987 51305 25788 51305 24215 51306 25788 51306 25789 51306 25789 51307 25788 51307 25791 51307 25789 51308 25791 51308 25790 51308 25790 51309 25791 51309 25792 51309 25790 51310 25792 51310 25794 51310 25794 51311 25792 51311 25793 51311 25794 51312 25793 51312 24225 51312 24225 51313 25793 51313 25989 51313 24225 51314 25989 51314 24223 51314 24223 51315 25989 51315 25795 51315 24211 51316 26011 51316 25796 51316 25796 51317 26011 51317 26013 51317 25796 51318 26013 51318 24210 51318 24210 51319 26013 51319 26014 51319 24210 51320 26014 51320 24208 51320 24208 51321 26014 51321 25797 51321 24208 51322 25797 51322 24205 51322 24205 51323 25797 51323 26017 51323 24205 51324 26017 51324 25798 51324 25798 51325 26017 51325 25800 51325 25798 51326 25800 51326 25799 51326 25799 51327 25800 51327 21871 51327 21869 51328 25801 51328 24192 51328 24192 51329 25801 51329 25802 51329 24192 51330 25802 51330 24189 51330 24189 51331 25802 51331 25803 51331 24189 51332 25803 51332 24197 51332 24197 51333 25803 51333 25804 51333 24197 51334 25804 51334 24196 51334 24196 51335 25804 51335 26043 51335 24196 51336 26043 51336 24195 51336 24195 51337 26043 51337 26041 51337 24195 51338 26041 51338 21863 51338 21863 51339 26041 51339 26035 51339 24186 51340 26983 51340 25805 51340 25805 51341 26983 51341 26984 51341 25805 51342 26984 51342 25806 51342 25806 51343 26984 51343 25807 51343 25806 51344 25807 51344 24184 51344 24184 51345 25807 51345 26976 51345 24184 51346 26976 51346 25808 51346 25808 51347 26976 51347 26975 51347 25808 51348 26975 51348 24183 51348 24183 51349 26975 51349 25809 51349 24183 51350 25809 51350 21857 51350 21857 51351 25809 51351 26971 51351 21856 51352 25810 51352 25811 51352 25811 51353 25810 51353 25840 51353 25811 51354 25840 51354 25812 51354 25812 51355 25840 51355 25813 51355 25812 51356 25813 51356 25814 51356 25814 51357 25813 51357 25815 51357 25814 51358 25815 51358 24178 51358 24178 51359 25815 51359 25827 51359 24178 51360 25827 51360 25816 51360 25816 51361 25827 51361 25826 51361 25816 51362 25826 51362 24177 51362 24177 51363 25826 51363 21849 51363 25507 51364 25833 51364 25817 51364 25817 51365 25833 51365 25832 51365 25750 51366 25749 51366 25818 51366 25818 51367 25749 51367 25819 51367 25818 51368 25819 51368 25489 51368 25489 51369 25819 51369 25839 51369 25489 51370 25839 51370 25490 51370 25490 51371 25839 51371 25492 51371 25492 51372 25839 51372 25820 51372 25492 51373 25820 51373 25821 51373 25821 51374 25820 51374 25494 51374 25494 51375 25820 51375 25822 51375 25494 51376 25822 51376 25824 51376 25499 51377 25498 51377 25838 51377 25838 51378 25498 51378 25823 51378 25838 51379 25823 51379 25822 51379 25822 51380 25823 51380 25496 51380 25822 51381 25496 51381 25824 51381 25499 51382 25838 51382 25825 51382 25825 51383 25838 51383 25835 51383 25825 51384 25835 51384 25502 51384 25502 51385 25835 51385 25503 51385 25503 51386 25835 51386 25834 51386 25503 51387 25834 51387 25504 51387 25504 51388 25834 51388 25833 51388 25504 51389 25833 51389 25507 51389 25826 51390 25827 51390 25830 51390 25830 51391 25827 51391 25828 51391 25840 51392 25749 51392 25813 51392 25813 51393 25749 51393 25748 51393 25827 51394 25815 51394 25828 51394 25828 51395 25815 51395 25813 51395 25828 51396 25813 51396 25829 51396 25829 51397 25813 51397 25748 51397 25830 51398 25743 51398 25826 51398 25826 51399 25743 51399 25747 51399 25826 51400 25747 51400 21849 51400 21849 51401 25747 51401 25832 51401 21849 51402 25832 51402 25831 51402 25831 51403 25832 51403 25833 51403 25831 51404 25833 51404 21850 51404 21850 51405 25833 51405 25834 51405 21850 51406 25834 51406 25836 51406 25836 51407 25834 51407 25835 51407 25836 51408 25835 51408 25837 51408 25837 51409 25835 51409 25838 51409 25837 51410 25838 51410 21853 51410 21853 51411 25838 51411 25822 51411 21853 51412 25822 51412 21854 51412 21854 51413 25822 51413 25820 51413 21854 51414 25820 51414 25810 51414 25810 51415 25820 51415 25839 51415 25810 51416 25839 51416 25840 51416 25840 51417 25839 51417 25819 51417 25840 51418 25819 51418 25749 51418 25841 51419 25842 51419 25583 51419 25583 51420 25842 51420 25855 51420 25529 51421 25634 51421 25843 51421 25843 51422 25634 51422 25845 51422 25843 51423 25845 51423 25844 51423 25844 51424 25845 51424 25846 51424 25844 51425 25846 51425 25556 51425 25556 51426 25846 51426 25847 51426 25847 51427 25846 51427 25861 51427 25847 51428 25861 51428 25848 51428 25549 51429 25551 51429 25860 51429 25860 51430 25551 51430 25552 51430 25860 51431 25552 51431 25861 51431 25861 51432 25552 51432 25554 51432 25861 51433 25554 51433 25848 51433 25549 51434 25860 51434 25548 51434 25548 51435 25860 51435 25849 51435 25548 51436 25849 51436 25850 51436 25850 51437 25849 51437 25546 51437 25546 51438 25849 51438 25858 51438 25546 51439 25858 51439 25544 51439 25753 51440 21911 51440 25634 51440 25851 51441 21928 51441 25756 51441 25634 51442 25633 51442 25753 51442 25753 51443 25633 51443 25632 51443 25753 51444 25632 51444 25852 51444 25756 51445 21928 51445 25854 51445 25851 51446 25756 51446 25598 51446 25598 51447 25756 51447 25853 51447 25598 51448 25853 51448 25852 51448 25852 51449 25853 51449 25755 51449 25852 51450 25755 51450 25753 51450 21928 51451 25855 51451 25854 51451 25854 51452 25855 51452 25842 51452 25854 51453 25842 51453 25856 51453 25856 51454 25842 51454 21848 51454 25856 51455 21848 51455 25857 51455 25857 51456 21848 51456 25858 51456 25857 51457 25858 51457 25859 51457 25859 51458 25858 51458 25849 51458 25859 51459 25849 51459 21908 51459 21908 51460 25849 51460 25860 51460 21908 51461 25860 51461 21909 51461 21909 51462 25860 51462 25861 51462 21909 51463 25861 51463 25862 51463 25862 51464 25861 51464 25846 51464 25862 51465 25846 51465 21911 51465 21911 51466 25846 51466 25845 51466 21911 51467 25845 51467 25634 51467 25469 51468 25878 51468 25863 51468 25863 51469 25878 51469 21926 51469 25457 51470 25864 51470 25865 51470 25865 51471 25864 51471 25866 51471 25865 51472 25866 51472 25487 51472 25487 51473 25866 51473 25867 51473 25487 51474 25867 51474 25486 51474 25486 51475 25867 51475 25483 51475 25483 51476 25867 51476 25870 51476 25483 51477 25870 51477 25482 51477 25871 51478 25868 51478 25869 51478 25869 51479 25868 51479 25470 51479 25869 51480 25470 51480 25870 51480 25870 51481 25470 51481 25480 51481 25870 51482 25480 51482 25482 51482 25871 51483 25869 51483 25872 51483 25872 51484 25869 51484 25883 51484 25872 51485 25883 51485 21843 51485 25600 51486 25874 51486 25873 51486 25600 51487 25873 51487 25643 51487 25874 51488 25600 51488 25875 51488 25875 51489 25600 51489 25876 51489 25875 51490 25876 51490 25877 51490 25877 51491 25876 51491 21925 51491 25877 51492 21925 51492 25760 51492 21925 51493 21926 51493 25760 51493 25760 51494 21926 51494 25878 51494 25760 51495 25878 51495 25879 51495 25879 51496 25878 51496 21847 51496 25879 51497 21847 51497 25880 51497 25880 51498 21847 51498 21845 51498 25880 51499 21845 51499 25881 51499 25881 51500 21845 51500 25883 51500 25881 51501 25883 51501 25882 51501 25882 51502 25883 51502 25869 51502 25882 51503 25869 51503 21903 51503 21903 51504 25869 51504 25870 51504 21903 51505 25870 51505 25884 51505 25884 51506 25870 51506 25867 51506 25884 51507 25867 51507 25885 51507 25885 51508 25867 51508 25866 51508 25885 51509 25866 51509 21906 51509 21906 51510 25866 51510 25864 51510 21906 51511 25864 51511 25873 51511 25873 51512 25864 51512 25644 51512 25873 51513 25644 51513 25643 51513 25886 51514 25887 51514 25888 51514 25888 51515 25887 51515 25889 51515 25656 51516 25655 51516 25890 51516 25890 51517 25655 51517 25891 51517 25890 51518 25891 51518 25892 51518 25892 51519 25891 51519 25904 51519 25892 51520 25904 51520 25428 51520 25428 51521 25904 51521 25893 51521 25893 51522 25904 51522 25903 51522 25893 51523 25903 51523 25894 51523 25894 51524 25903 51524 25895 51524 25895 51525 25903 51525 25900 51525 25895 51526 25900 51526 21835 51526 25765 51527 25764 51527 25896 51527 25896 51528 25764 51528 25897 51528 21899 51529 25905 51529 25655 51529 25764 51530 21901 51530 25897 51530 25897 51531 21901 51531 21899 51531 25897 51532 21899 51532 25654 51532 25654 51533 21899 51533 25655 51533 25898 51534 25887 51534 25767 51534 25767 51535 25887 51535 21842 51535 25767 51536 21842 51536 25769 51536 25769 51537 21842 51537 21841 51537 25769 51538 21841 51538 25899 51538 25899 51539 21841 51539 21838 51539 25899 51540 21838 51540 25771 51540 25771 51541 21838 51541 25900 51541 25771 51542 25900 51542 25901 51542 25901 51543 25900 51543 25903 51543 25901 51544 25903 51544 25902 51544 25902 51545 25903 51545 25904 51545 25902 51546 25904 51546 25905 51546 25905 51547 25904 51547 25891 51547 25905 51548 25891 51548 25655 51548 25896 51549 25650 51549 25765 51549 25765 51550 25650 51550 25652 51550 25765 51551 25652 51551 25898 51551 25898 51552 25652 51552 25889 51552 25898 51553 25889 51553 25887 51553 25353 51554 21833 51554 25392 51554 25392 51555 21833 51555 25906 51555 25336 51556 25907 51556 25349 51556 25349 51557 25907 51557 25908 51557 25349 51558 25908 51558 25909 51558 25909 51559 25908 51559 25921 51559 25909 51560 25921 51560 25371 51560 25371 51561 25921 51561 25369 51561 25369 51562 25921 51562 21822 51562 25369 51563 21822 51563 25367 51563 25912 51564 25660 51564 25772 51564 25772 51565 25660 51565 25910 51565 25772 51566 25910 51566 25774 51566 25772 51567 25911 51567 25912 51567 25912 51568 25911 51568 25914 51568 25912 51569 25914 51569 25913 51569 25913 51570 25914 51570 25915 51570 25913 51571 25915 51571 25663 51571 25910 51572 25906 51572 25774 51572 25774 51573 25906 51573 21833 51573 25774 51574 21833 51574 25916 51574 25916 51575 21833 51575 21832 51575 25916 51576 21832 51576 25917 51576 25917 51577 21832 51577 21830 51577 25917 51578 21830 51578 25776 51578 25776 51579 21830 51579 21824 51579 25776 51580 21824 51580 25918 51580 25918 51581 21824 51581 21826 51581 25918 51582 21826 51582 25919 51582 25919 51583 21826 51583 21822 51583 25919 51584 21822 51584 25920 51584 25920 51585 21822 51585 25921 51585 25920 51586 25921 51586 21894 51586 21894 51587 25921 51587 25908 51587 21894 51588 25908 51588 21895 51588 21895 51589 25908 51589 25907 51589 21895 51590 25907 51590 25915 51590 25915 51591 25907 51591 25664 51591 25915 51592 25664 51592 25663 51592 25288 51593 21821 51593 25922 51593 25922 51594 21821 51594 25671 51594 25672 51595 25942 51595 25924 51595 25924 51596 25942 51596 25923 51596 25923 51597 25941 51597 25924 51597 25924 51598 25941 51598 25925 51598 25926 51599 21887 51599 25927 51599 25668 51600 25930 51600 25610 51600 25610 51601 25930 51601 25926 51601 25610 51602 25926 51602 21918 51602 21918 51603 25926 51603 25927 51603 25928 51604 25931 51604 25668 51604 25668 51605 25931 51605 25929 51605 25668 51606 25929 51606 25930 51606 25928 51607 25670 51607 25931 51607 25931 51608 25670 51608 25671 51608 25931 51609 25671 51609 25932 51609 25932 51610 25671 51610 21821 51610 25932 51611 21821 51611 25933 51611 25933 51612 21821 51612 25934 51612 25933 51613 25934 51613 25935 51613 25935 51614 25934 51614 21820 51614 25935 51615 21820 51615 25777 51615 25777 51616 21820 51616 21818 51616 25777 51617 21818 51617 25936 51617 25936 51618 21818 51618 25937 51618 25936 51619 25937 51619 25938 51619 25938 51620 25937 51620 25939 51620 25938 51621 25939 51621 25940 51621 25940 51622 25939 51622 25941 51622 25940 51623 25941 51623 21886 51623 21886 51624 25941 51624 25923 51624 21886 51625 25923 51625 21887 51625 21887 51626 25923 51626 25942 51626 21887 51627 25942 51627 25927 51627 25943 51628 25954 51628 25944 51628 25944 51629 25954 51629 25960 51629 25214 51630 25945 51630 25213 51630 25213 51631 25945 51631 25966 51631 25213 51632 25966 51632 25946 51632 25946 51633 25966 51633 25965 51633 25946 51634 25965 51634 25230 51634 25230 51635 25965 51635 25947 51635 25947 51636 25965 51636 25948 51636 25948 51637 25965 51637 25949 51637 25948 51638 25949 51638 25950 51638 25950 51639 25949 51639 25226 51639 25226 51640 25949 51640 25952 51640 25226 51641 25952 51641 25225 51641 25951 51642 25221 51642 25952 51642 25952 51643 25221 51643 25224 51643 25952 51644 25224 51644 25225 51644 25951 51645 25952 51645 25219 51645 25219 51646 25952 51646 25962 51646 25219 51647 25962 51647 25953 51647 25953 51648 25962 51648 25961 51648 25953 51649 25961 51649 25216 51649 25216 51650 25961 51650 25955 51650 25955 51651 25961 51651 25954 51651 25955 51652 25954 51652 25943 51652 25675 51653 25674 51653 21883 51653 25956 51654 25959 51654 25957 51654 21883 51655 25674 51655 21884 51655 25675 51656 21883 51656 25677 51656 25677 51657 21883 51657 25958 51657 25677 51658 25958 51658 25959 51658 25959 51659 25958 51659 21881 51659 25959 51660 21881 51660 25957 51660 25674 51661 25960 51661 21884 51661 21884 51662 25960 51662 25954 51662 21884 51663 25954 51663 25779 51663 25779 51664 25954 51664 25961 51664 25779 51665 25961 51665 25781 51665 25781 51666 25961 51666 25962 51666 25781 51667 25962 51667 25963 51667 25963 51668 25962 51668 25952 51668 25963 51669 25952 51669 25964 51669 25964 51670 25952 51670 25949 51670 25964 51671 25949 51671 25785 51671 25785 51672 25949 51672 25965 51672 25785 51673 25965 51673 25786 51673 25786 51674 25965 51674 25966 51674 25786 51675 25966 51675 25967 51675 25967 51676 25966 51676 25945 51676 25967 51677 25945 51677 25957 51677 25957 51678 25945 51678 25681 51678 25957 51679 25681 51679 25956 51679 25249 51680 25985 51680 25691 51680 25691 51681 25985 51681 25968 51681 25694 51682 25969 51682 25233 51682 25233 51683 25969 51683 25970 51683 25233 51684 25970 51684 25234 51684 25234 51685 25970 51685 25971 51685 25234 51686 25971 51686 25972 51686 25972 51687 25971 51687 25973 51687 25973 51688 25971 51688 25976 51688 25973 51689 25976 51689 25974 51689 25974 51690 25976 51690 25975 51690 25975 51691 25976 51691 25978 51691 25975 51692 25978 51692 25238 51692 25243 51693 25977 51693 25988 51693 25988 51694 25977 51694 25241 51694 25988 51695 25241 51695 25978 51695 25978 51696 25241 51696 25240 51696 25978 51697 25240 51697 25238 51697 25243 51698 25988 51698 25245 51698 25245 51699 25988 51699 25979 51699 25245 51700 25979 51700 25246 51700 25246 51701 25979 51701 25980 51701 25980 51702 25979 51702 25981 51702 25980 51703 25981 51703 25248 51703 25248 51704 25981 51704 25985 51704 25248 51705 25985 51705 25249 51705 25687 51706 25983 51706 21876 51706 25687 51707 21876 51707 25617 51707 25989 51708 25969 51708 25795 51708 25795 51709 25969 51709 25693 51709 21876 51710 21874 51710 25617 51710 25617 51711 21874 51711 25795 51711 25617 51712 25795 51712 25692 51712 25692 51713 25795 51713 25693 51713 25687 51714 25982 51714 25983 51714 25983 51715 25982 51715 25689 51715 25983 51716 25689 51716 25984 51716 25689 51717 25968 51717 25984 51717 25984 51718 25968 51718 25985 51718 25984 51719 25985 51719 25986 51719 25986 51720 25985 51720 25981 51720 25986 51721 25981 51721 25987 51721 25987 51722 25981 51722 25979 51722 25987 51723 25979 51723 25788 51723 25788 51724 25979 51724 25988 51724 25788 51725 25988 51725 25791 51725 25791 51726 25988 51726 25978 51726 25791 51727 25978 51727 25792 51727 25792 51728 25978 51728 25976 51728 25792 51729 25976 51729 25793 51729 25793 51730 25976 51730 25971 51730 25793 51731 25971 51731 25989 51731 25989 51732 25971 51732 25970 51732 25989 51733 25970 51733 25969 51733 25284 51734 26002 51734 25285 51734 25285 51735 26002 51735 26008 51735 25327 51736 26016 51736 25990 51736 25990 51737 26016 51737 26015 51737 25990 51738 26015 51738 25303 51738 25303 51739 26015 51739 25992 51739 25303 51740 25992 51740 25991 51740 25991 51741 25992 51741 25305 51741 25305 51742 25992 51742 25306 51742 25306 51743 25992 51743 25993 51743 25306 51744 25993 51744 25307 51744 25307 51745 25993 51745 25994 51745 25994 51746 25993 51746 25997 51746 25994 51747 25997 51747 25995 51747 25996 51748 25311 51748 25997 51748 25997 51749 25311 51749 25998 51749 25997 51750 25998 51750 25995 51750 25996 51751 25997 51751 25999 51751 25999 51752 25997 51752 26012 51752 25999 51753 26012 51753 26000 51753 26000 51754 26012 51754 26010 51754 26000 51755 26010 51755 26001 51755 26001 51756 26010 51756 25315 51756 25315 51757 26010 51757 26002 51757 25315 51758 26002 51758 25284 51758 26005 51759 21872 51759 26003 51759 26003 51760 21872 51760 26004 51760 21872 51761 21871 51761 26004 51761 26004 51762 21871 51762 25800 51762 26004 51763 25800 51763 25704 51763 26003 51764 25701 51764 26005 51764 26005 51765 25701 51765 26006 51765 26005 51766 26006 51766 26007 51766 26007 51767 26006 51767 26008 51767 26007 51768 26008 51768 26009 51768 26009 51769 26008 51769 26002 51769 26009 51770 26002 51770 21873 51770 21873 51771 26002 51771 26010 51771 21873 51772 26010 51772 26011 51772 26011 51773 26010 51773 26012 51773 26011 51774 26012 51774 26013 51774 26012 51775 25997 51775 26013 51775 26013 51776 25997 51776 25993 51776 26013 51777 25993 51777 26014 51777 26014 51778 25993 51778 25992 51778 26014 51779 25992 51779 25797 51779 25797 51780 25992 51780 26015 51780 25797 51781 26015 51781 26017 51781 26017 51782 26015 51782 26016 51782 26017 51783 26016 51783 25800 51783 25800 51784 26016 51784 25705 51784 25800 51785 25705 51785 25704 51785 26032 51786 26031 51786 25350 51786 25350 51787 26031 51787 26036 51787 26018 51788 25718 51788 25387 51788 25387 51789 25718 51789 26019 51789 25387 51790 26019 51790 25373 51790 25373 51791 26019 51791 26042 51791 25373 51792 26042 51792 25374 51792 25374 51793 26042 51793 26020 51793 26020 51794 26042 51794 26021 51794 26021 51795 26042 51795 26024 51795 26021 51796 26024 51796 26022 51796 26022 51797 26024 51797 26023 51797 26023 51798 26024 51798 26025 51798 26023 51799 26025 51799 25379 51799 26028 51800 26026 51800 26025 51800 26025 51801 26026 51801 26027 51801 26025 51802 26027 51802 25379 51802 26028 51803 26025 51803 26029 51803 26029 51804 26025 51804 26040 51804 26029 51805 26040 51805 25383 51805 25383 51806 26040 51806 26038 51806 25383 51807 26038 51807 26030 51807 26030 51808 26038 51808 25384 51808 25384 51809 26038 51809 26031 51809 25384 51810 26031 51810 26032 51810 26033 51811 25709 51811 26034 51811 26034 51812 25709 51812 21866 51812 26033 51813 26034 51813 25710 51813 25710 51814 26034 51814 26035 51814 25710 51815 26035 51815 25622 51815 25802 51816 25801 51816 26025 51816 26025 51817 25801 51817 26040 51817 25709 51818 26036 51818 21866 51818 21866 51819 26036 51819 26031 51819 21866 51820 26031 51820 26037 51820 26037 51821 26031 51821 26038 51821 26037 51822 26038 51822 26039 51822 26039 51823 26038 51823 26040 51823 26039 51824 26040 51824 21870 51824 21870 51825 26040 51825 25801 51825 26035 51826 26041 51826 25622 51826 25622 51827 26041 51827 26043 51827 25622 51828 26043 51828 25715 51828 26025 51829 26024 51829 25802 51829 25802 51830 26024 51830 26042 51830 25802 51831 26042 51831 25803 51831 25803 51832 26042 51832 26019 51832 25803 51833 26019 51833 25804 51833 25804 51834 26019 51834 25718 51834 25804 51835 25718 51835 26043 51835 26043 51836 25718 51836 25717 51836 26043 51837 25717 51837 25715 51837 26059 51838 26058 51838 25730 51838 25730 51839 26058 51839 26977 51839 26044 51840 26973 51840 26045 51840 26045 51841 26973 51841 26986 51841 26045 51842 26986 51842 26046 51842 26046 51843 26986 51843 26985 51843 26046 51844 26985 51844 25429 51844 25429 51845 26985 51845 26047 51845 26047 51846 26985 51846 26048 51846 26047 51847 26048 51847 25432 51847 25432 51848 26048 51848 25433 51848 25433 51849 26048 51849 26052 51849 25433 51850 26052 51850 25435 51850 26049 51851 26050 51851 26982 51851 26982 51852 26050 51852 26051 51852 26982 51853 26051 51853 26052 51853 26052 51854 26051 51854 26053 51854 26052 51855 26053 51855 25435 51855 26049 51856 26982 51856 26054 51856 26054 51857 26982 51857 26980 51857 26054 51858 26980 51858 25438 51858 25438 51859 26980 51859 26055 51859 26055 51860 26980 51860 26057 51860 26055 51861 26057 51861 26056 51861 26056 51862 26057 51862 26058 51862 26056 51863 26058 51863 26059 51863 26063 51864 26060 51864 26061 51864 26061 51865 26062 51865 26063 51865 26063 51866 26062 51866 26068 51866 26063 51867 26068 51867 26064 51867 26064 51868 26075 51868 26063 51868 26063 51869 26075 51869 26065 51869 26063 51870 26065 51870 27157 51870 26060 51871 26066 51871 26061 51871 26061 51872 26066 51872 26067 51872 26061 51873 26067 51873 26062 51873 26062 51874 26067 51874 25532 51874 26062 51875 25532 51875 26068 51875 26068 51876 25532 51876 26069 51876 26068 51877 26069 51877 26103 51877 26103 51878 26069 51878 26070 51878 26103 51879 26070 51879 21815 51879 21815 51880 26070 51880 25534 51880 21815 51881 25534 51881 26071 51881 26064 51882 26072 51882 25585 51882 25585 51883 26072 51883 26111 51883 25585 51884 26111 51884 26073 51884 26073 51885 26111 51885 26086 51885 26073 51886 26086 51886 25578 51886 25585 51887 26074 51887 26064 51887 26064 51888 26074 51888 25588 51888 26064 51889 25588 51889 26075 51889 26075 51890 25588 51890 25589 51890 26075 51891 25589 51891 26065 51891 26065 51892 25589 51892 26076 51892 26065 51893 26076 51893 27157 51893 21813 51894 26109 51894 26077 51894 26077 51895 26109 51895 26110 51895 26077 51896 26110 51896 26078 51896 26078 51897 26110 51897 26102 51897 26078 51898 26102 51898 26080 51898 26080 51899 26102 51899 26079 51899 26080 51900 26079 51900 24170 51900 24170 51901 26079 51901 26081 51901 24170 51902 26081 51902 26082 51902 26082 51903 26081 51903 26104 51903 26082 51904 26104 51904 24167 51904 24167 51905 26104 51905 26083 51905 25539 51906 26084 51906 25536 51906 25536 51907 26084 51907 21814 51907 25578 51908 26086 51908 26085 51908 26085 51909 26086 51909 26087 51909 26098 51910 26093 51910 26094 51910 26088 51911 25560 51911 26089 51911 26085 51912 26087 51912 26090 51912 26090 51913 26087 51913 26088 51913 26090 51914 26088 51914 25558 51914 25558 51915 26088 51915 26089 51915 25560 51916 26088 51916 26091 51916 26091 51917 26088 51917 26106 51917 26091 51918 26106 51918 26092 51918 26093 51919 25565 51919 26094 51919 26094 51920 25565 51920 25566 51920 26094 51921 25566 51921 26106 51921 26106 51922 25566 51922 25568 51922 26106 51923 25568 51923 26092 51923 26100 51924 26095 51924 26096 51924 26096 51925 26095 51925 25571 51925 26096 51926 25571 51926 26094 51926 26094 51927 25571 51927 26097 51927 26094 51928 26097 51928 26098 51928 26099 51929 21805 51929 26100 51929 26100 51930 21805 51930 25573 51930 25573 51931 25575 51931 26100 51931 26100 51932 25575 51932 26101 51932 26100 51933 26101 51933 26095 51933 26081 51934 26079 51934 26068 51934 26072 51935 26064 51935 26110 51935 26068 51936 26079 51936 26064 51936 26064 51937 26079 51937 26102 51937 26064 51938 26102 51938 26110 51938 26068 51939 26103 51939 26081 51939 26081 51940 26103 51940 21815 51940 26081 51941 21815 51941 26104 51941 21815 51942 21814 51942 26104 51942 26104 51943 21814 51943 26084 51943 26104 51944 26084 51944 26083 51944 26083 51945 26084 51945 26099 51945 26083 51946 26099 51946 21807 51946 21807 51947 26099 51947 26100 51947 21807 51948 26100 51948 21808 51948 21808 51949 26100 51949 26096 51949 21808 51950 26096 51950 21810 51950 21810 51951 26096 51951 26094 51951 21810 51952 26094 51952 26105 51952 26105 51953 26094 51953 26106 51953 26105 51954 26106 51954 26107 51954 26107 51955 26106 51955 26088 51955 26107 51956 26088 51956 26108 51956 26108 51957 26088 51957 26087 51957 26108 51958 26087 51958 26109 51958 26109 51959 26087 51959 26086 51959 26109 51960 26086 51960 26110 51960 26110 51961 26086 51961 26111 51961 26110 51962 26111 51962 26072 51962 26112 51963 21804 51963 26113 51963 26113 51964 21804 51964 26421 51964 26113 51965 26421 51965 26114 51965 26114 51966 26421 51966 26418 51966 26114 51967 26418 51967 26952 51967 26952 51968 26418 51968 26115 51968 26952 51969 26115 51969 26953 51969 26953 51970 26115 51970 26457 51970 26953 51971 26457 51971 26955 51971 26955 51972 26457 51972 26458 51972 26955 51973 26458 51973 26116 51973 26116 51974 26458 51974 26117 51974 26116 51975 26117 51975 26119 51975 26119 51976 26117 51976 26118 51976 26119 51977 26118 51977 26959 51977 26959 51978 26118 51978 26447 51978 26959 51979 26447 51979 26120 51979 26120 51980 26447 51980 26446 51980 26120 51981 26446 51981 26962 51981 26962 51982 26446 51982 26444 51982 26962 51983 26444 51983 26121 51983 26121 51984 26444 51984 26122 51984 26121 51985 26122 51985 26123 51985 26123 51986 26122 51986 26441 51986 26123 51987 26441 51987 26965 51987 26965 51988 26441 51988 26440 51988 26965 51989 26440 51989 26966 51989 26966 51990 26440 51990 26124 51990 26966 51991 26124 51991 26967 51991 26967 51992 26124 51992 26434 51992 26967 51993 26434 51993 26969 51993 26969 51994 26434 51994 26432 51994 26969 51995 26432 51995 21233 51995 21233 51996 26432 51996 26125 51996 26949 51997 26126 51997 26946 51997 26946 51998 26126 51998 26412 51998 26946 51999 26412 51999 26945 51999 26945 52000 26412 52000 26389 52000 26945 52001 26389 52001 26944 52001 26944 52002 26389 52002 26390 52002 26944 52003 26390 52003 26943 52003 26943 52004 26390 52004 26386 52004 26943 52005 26386 52005 26942 52005 26942 52006 26386 52006 26127 52006 26942 52007 26127 52007 26941 52007 26941 52008 26127 52008 26409 52008 26941 52009 26409 52009 26939 52009 26939 52010 26409 52010 26129 52010 26939 52011 26129 52011 26128 52011 26128 52012 26129 52012 26383 52012 26128 52013 26383 52013 26130 52013 26130 52014 26383 52014 26385 52014 26130 52015 26385 52015 26935 52015 26935 52016 26385 52016 26131 52016 26935 52017 26131 52017 26933 52017 26933 52018 26131 52018 26132 52018 26933 52019 26132 52019 26932 52019 26932 52020 26132 52020 26133 52020 26932 52021 26133 52021 26930 52021 26930 52022 26133 52022 26407 52022 26930 52023 26407 52023 26928 52023 26928 52024 26407 52024 26402 52024 26928 52025 26402 52025 26927 52025 26927 52026 26402 52026 26404 52026 26927 52027 26404 52027 26134 52027 26134 52028 26404 52028 26135 52028 26134 52029 26135 52029 26136 52029 26136 52030 26135 52030 21774 52030 26137 52031 26138 52031 26253 52031 21671 52032 21672 52032 26216 52032 21719 52033 21721 52033 26139 52033 26140 52034 21554 52034 26460 52034 21721 52035 26140 52035 26139 52035 26139 52036 26140 52036 26460 52036 26139 52037 26460 52037 26215 52037 26215 52038 26460 52038 26461 52038 26215 52039 26461 52039 26213 52039 26213 52040 26461 52040 26141 52040 26213 52041 26141 52041 26142 52041 26142 52042 26141 52042 26462 52042 26142 52043 26462 52043 26210 52043 26210 52044 26462 52044 26143 52044 26210 52045 26143 52045 26208 52045 26208 52046 26143 52046 26465 52046 26208 52047 26465 52047 26207 52047 26207 52048 26465 52048 26144 52048 26207 52049 26144 52049 26205 52049 26205 52050 26144 52050 26145 52050 26205 52051 26145 52051 26204 52051 26204 52052 26145 52052 26146 52052 26204 52053 26146 52053 26147 52053 26147 52054 26146 52054 26470 52054 26147 52055 26470 52055 26148 52055 26148 52056 26470 52056 26149 52056 26148 52057 26149 52057 26150 52057 26150 52058 26149 52058 26471 52058 26150 52059 26471 52059 26200 52059 26200 52060 26471 52060 26152 52060 26200 52061 26152 52061 26151 52061 26151 52062 26152 52062 26473 52062 26151 52063 26473 52063 26153 52063 26153 52064 26473 52064 26154 52064 26153 52065 26154 52065 26198 52065 26198 52066 26154 52066 26475 52066 26198 52067 26475 52067 26196 52067 26196 52068 26475 52068 26155 52068 26196 52069 26155 52069 26194 52069 26194 52070 26155 52070 26157 52070 26194 52071 26157 52071 26156 52071 26156 52072 26157 52072 26478 52072 26156 52073 26478 52073 26193 52073 26193 52074 26478 52074 26158 52074 26193 52075 26158 52075 26192 52075 26192 52076 26158 52076 26159 52076 26192 52077 26159 52077 26190 52077 26190 52078 26159 52078 26161 52078 26190 52079 26161 52079 26160 52079 26160 52080 26161 52080 26481 52080 26160 52081 26481 52081 26162 52081 26162 52082 26481 52082 26483 52082 26162 52083 26483 52083 26188 52083 26188 52084 26483 52084 26163 52084 26188 52085 26163 52085 26186 52085 26186 52086 26163 52086 26164 52086 26186 52087 26164 52087 26165 52087 26165 52088 26164 52088 26166 52088 26165 52089 26166 52089 26184 52089 26184 52090 26166 52090 26485 52090 26184 52091 26485 52091 26167 52091 26167 52092 26485 52092 26168 52092 26167 52093 26168 52093 26169 52093 26169 52094 26168 52094 26170 52094 26169 52095 26170 52095 26181 52095 26181 52096 26170 52096 26171 52096 26181 52097 26171 52097 26172 52097 26172 52098 26171 52098 26173 52098 26172 52099 26173 52099 26174 52099 26174 52100 26173 52100 26175 52100 26174 52101 26175 52101 26178 52101 26178 52102 26175 52102 26491 52102 26178 52103 26491 52103 26177 52103 26177 52104 26491 52104 26176 52104 26177 52105 26176 52105 21772 52105 21772 52106 26176 52106 21529 52106 21772 52107 26137 52107 26177 52107 26177 52108 26137 52108 26253 52108 26177 52109 26253 52109 26178 52109 26178 52110 26253 52110 26179 52110 26178 52111 26179 52111 26174 52111 26174 52112 26179 52112 26251 52112 26174 52113 26251 52113 26172 52113 26172 52114 26251 52114 26180 52114 26172 52115 26180 52115 26181 52115 26181 52116 26180 52116 26250 52116 26181 52117 26250 52117 26169 52117 26169 52118 26250 52118 26182 52118 26169 52119 26182 52119 26167 52119 26167 52120 26182 52120 26183 52120 26167 52121 26183 52121 26184 52121 26184 52122 26183 52122 26185 52122 26184 52123 26185 52123 26165 52123 26165 52124 26185 52124 26247 52124 26165 52125 26247 52125 26186 52125 26186 52126 26247 52126 26187 52126 26186 52127 26187 52127 26188 52127 26188 52128 26187 52128 26189 52128 26188 52129 26189 52129 26162 52129 26162 52130 26189 52130 26242 52130 26162 52131 26242 52131 26160 52131 26160 52132 26242 52132 26241 52132 26160 52133 26241 52133 26190 52133 26190 52134 26241 52134 26191 52134 26190 52135 26191 52135 26192 52135 26192 52136 26191 52136 26239 52136 26192 52137 26239 52137 26193 52137 26193 52138 26239 52138 26237 52138 26193 52139 26237 52139 26156 52139 26156 52140 26237 52140 26236 52140 26156 52141 26236 52141 26194 52141 26194 52142 26236 52142 26195 52142 26194 52143 26195 52143 26196 52143 26196 52144 26195 52144 26197 52144 26196 52145 26197 52145 26198 52145 26198 52146 26197 52146 26232 52146 26198 52147 26232 52147 26153 52147 26153 52148 26232 52148 26231 52148 26153 52149 26231 52149 26151 52149 26151 52150 26231 52150 26199 52150 26151 52151 26199 52151 26200 52151 26200 52152 26199 52152 26228 52152 26200 52153 26228 52153 26150 52153 26150 52154 26228 52154 26201 52154 26150 52155 26201 52155 26148 52155 26148 52156 26201 52156 26202 52156 26148 52157 26202 52157 26147 52157 26147 52158 26202 52158 26203 52158 26147 52159 26203 52159 26204 52159 26204 52160 26203 52160 26226 52160 26204 52161 26226 52161 26205 52161 26205 52162 26226 52162 26206 52162 26205 52163 26206 52163 26207 52163 26207 52164 26206 52164 26223 52164 26207 52165 26223 52165 26208 52165 26208 52166 26223 52166 26209 52166 26208 52167 26209 52167 26210 52167 26210 52168 26209 52168 26211 52168 26210 52169 26211 52169 26142 52169 26142 52170 26211 52170 26212 52170 26142 52171 26212 52171 26213 52171 26213 52172 26212 52172 26214 52172 26213 52173 26214 52173 26215 52173 26215 52174 26214 52174 26219 52174 26215 52175 26219 52175 26139 52175 26139 52176 26219 52176 26216 52176 26139 52177 26216 52177 21719 52177 21719 52178 26216 52178 21672 52178 26420 52179 21671 52179 26217 52179 26217 52180 21671 52180 26216 52180 26217 52181 26216 52181 26218 52181 26218 52182 26216 52182 26219 52182 26218 52183 26219 52183 26220 52183 26220 52184 26219 52184 26214 52184 26220 52185 26214 52185 26221 52185 26221 52186 26214 52186 26212 52186 26221 52187 26212 52187 26222 52187 26222 52188 26212 52188 26211 52188 26222 52189 26211 52189 26455 52189 26455 52190 26211 52190 26209 52190 26455 52191 26209 52191 26456 52191 26456 52192 26209 52192 26223 52192 26456 52193 26223 52193 26224 52193 26224 52194 26223 52194 26206 52194 26224 52195 26206 52195 26225 52195 26225 52196 26206 52196 26226 52196 26225 52197 26226 52197 26459 52197 26459 52198 26226 52198 26203 52198 26459 52199 26203 52199 26227 52199 26227 52200 26203 52200 26202 52200 26227 52201 26202 52201 26452 52201 26452 52202 26202 52202 26201 52202 26452 52203 26201 52203 26453 52203 26453 52204 26201 52204 26228 52204 26453 52205 26228 52205 26229 52205 26229 52206 26228 52206 26199 52206 26229 52207 26199 52207 26454 52207 26454 52208 26199 52208 26231 52208 26454 52209 26231 52209 26230 52209 26230 52210 26231 52210 26232 52210 26230 52211 26232 52211 26233 52211 26233 52212 26232 52212 26197 52212 26233 52213 26197 52213 26234 52213 26234 52214 26197 52214 26195 52214 26234 52215 26195 52215 26235 52215 26235 52216 26195 52216 26236 52216 26235 52217 26236 52217 26445 52217 26445 52218 26236 52218 26237 52218 26445 52219 26237 52219 26238 52219 26238 52220 26237 52220 26239 52220 26238 52221 26239 52221 26240 52221 26240 52222 26239 52222 26191 52222 26240 52223 26191 52223 26443 52223 26443 52224 26191 52224 26241 52224 26443 52225 26241 52225 26442 52225 26442 52226 26241 52226 26242 52226 26442 52227 26242 52227 26243 52227 26243 52228 26242 52228 26189 52228 26243 52229 26189 52229 26244 52229 26244 52230 26189 52230 26187 52230 26244 52231 26187 52231 26245 52231 26245 52232 26187 52232 26247 52232 26245 52233 26247 52233 26246 52233 26246 52234 26247 52234 26185 52234 26246 52235 26185 52235 26248 52235 26248 52236 26185 52236 26183 52236 26248 52237 26183 52237 26249 52237 26249 52238 26183 52238 26182 52238 26249 52239 26182 52239 26435 52239 26435 52240 26182 52240 26250 52240 26435 52241 26250 52241 26436 52241 26436 52242 26250 52242 26180 52242 26436 52243 26180 52243 26433 52243 26433 52244 26180 52244 26251 52244 26433 52245 26251 52245 26252 52245 26252 52246 26251 52246 26179 52246 26252 52247 26179 52247 26429 52247 26429 52248 26179 52248 26253 52248 26429 52249 26253 52249 26428 52249 26428 52250 26253 52250 26138 52250 26263 52251 26262 52251 26270 52251 26258 52252 26268 52252 26336 52252 26255 52253 26413 52253 26254 52253 26388 52254 26255 52254 26256 52254 26399 52255 26313 52255 26257 52255 26257 52256 26313 52256 26264 52256 26377 52257 26268 52257 26259 52257 26259 52258 26268 52258 26258 52258 26259 52259 26258 52259 26260 52259 26261 52260 26262 52260 26391 52260 26391 52261 26262 52261 26263 52261 26391 52262 26263 52262 26387 52262 26264 52263 26313 52263 26265 52263 26265 52264 26313 52264 26315 52264 26265 52265 26315 52265 26266 52265 26337 52266 26336 52266 26340 52266 26340 52267 26336 52267 26268 52267 26340 52268 26268 52268 26267 52268 26267 52269 26268 52269 26377 52269 26267 52270 26377 52270 26269 52270 26361 52271 26270 52271 26271 52271 26271 52272 26270 52272 26262 52272 26271 52273 26262 52273 26272 52273 26272 52274 26262 52274 26261 52274 26272 52275 26261 52275 26388 52275 26316 52276 26273 52276 26314 52276 26323 52277 26274 52277 26322 52277 26322 52278 26274 52278 26316 52278 26322 52279 26316 52279 26320 52279 26320 52280 26316 52280 26314 52280 26320 52281 26314 52281 26319 52281 26405 52282 26275 52282 26276 52282 26276 52283 26275 52283 26277 52283 26276 52284 26277 52284 26321 52284 26321 52285 26277 52285 26278 52285 26321 52286 26278 52286 26325 52286 26325 52287 26278 52287 26324 52287 26403 52288 26279 52288 26280 52288 26280 52289 26279 52289 26328 52289 26280 52290 26328 52290 26326 52290 26326 52291 26328 52291 26329 52291 26326 52292 26329 52292 26327 52292 26327 52293 26329 52293 26282 52293 26327 52294 26282 52294 26281 52294 26281 52295 26282 52295 26472 52295 26406 52296 26286 52296 26283 52296 26283 52297 26286 52297 26289 52297 26283 52298 26289 52298 26330 52298 26330 52299 26289 52299 26285 52299 26330 52300 26285 52300 26284 52300 26284 52301 26285 52301 26333 52301 26286 52302 26287 52302 26289 52302 26289 52303 26287 52303 26288 52303 26289 52304 26288 52304 26285 52304 26285 52305 26288 52305 26335 52305 26285 52306 26335 52306 26333 52306 26333 52307 26335 52307 26290 52307 26333 52308 26290 52308 26331 52308 26331 52309 26290 52309 26476 52309 26292 52310 26341 52310 26293 52310 26480 52311 26342 52311 26345 52311 26345 52312 26342 52312 26292 52312 26345 52313 26292 52313 26291 52313 26291 52314 26292 52314 26293 52314 26291 52315 26293 52315 26339 52315 26384 52316 26382 52316 26294 52316 26294 52317 26382 52317 26350 52317 26294 52318 26350 52318 26295 52318 26295 52319 26350 52319 26352 52319 26295 52320 26352 52320 26349 52320 26349 52321 26352 52321 26347 52321 26351 52322 26296 52322 26353 52322 26353 52323 26296 52323 26297 52323 26353 52324 26297 52324 26354 52324 26354 52325 26297 52325 26298 52325 26354 52326 26298 52326 26299 52326 26299 52327 26298 52327 26355 52327 26299 52328 26355 52328 26300 52328 26300 52329 26355 52329 26486 52329 26408 52330 26301 52330 26302 52330 26302 52331 26301 52331 26304 52331 26302 52332 26304 52332 26303 52332 26303 52333 26304 52333 26305 52333 26303 52334 26305 52334 26357 52334 26357 52335 26305 52335 26307 52335 26301 52336 26358 52336 26304 52336 26304 52337 26358 52337 26359 52337 26304 52338 26359 52338 26305 52338 26305 52339 26359 52339 26306 52339 26305 52340 26306 52340 26307 52340 26307 52341 26306 52341 26360 52341 26307 52342 26360 52342 26308 52342 26308 52343 26360 52343 26489 52343 26266 52344 26315 52344 21563 52344 21563 52345 26315 52345 26309 52345 21563 52346 26309 52346 26310 52346 26310 52347 26309 52347 26311 52347 26310 52348 26311 52348 26312 52348 26399 52349 26319 52349 26313 52349 26313 52350 26319 52350 26314 52350 26313 52351 26314 52351 26315 52351 26315 52352 26314 52352 26273 52352 26315 52353 26273 52353 26309 52353 26309 52354 26273 52354 26318 52354 26309 52355 26318 52355 26311 52355 26274 52356 26317 52356 26316 52356 26316 52357 26317 52357 26464 52357 26316 52358 26464 52358 26273 52358 26273 52359 26464 52359 26463 52359 26273 52360 26463 52360 26318 52360 26399 52361 26405 52361 26319 52361 26319 52362 26405 52362 26276 52362 26319 52363 26276 52363 26320 52363 26320 52364 26276 52364 26321 52364 26320 52365 26321 52365 26322 52365 26322 52366 26321 52366 26325 52366 26322 52367 26325 52367 26323 52367 26469 52368 26468 52368 26324 52368 26324 52369 26468 52369 26467 52369 26324 52370 26467 52370 26325 52370 26325 52371 26467 52371 26466 52371 26325 52372 26466 52372 26323 52372 26275 52373 26403 52373 26277 52373 26277 52374 26403 52374 26280 52374 26277 52375 26280 52375 26278 52375 26278 52376 26280 52376 26326 52376 26278 52377 26326 52377 26324 52377 26324 52378 26326 52378 26327 52378 26324 52379 26327 52379 26469 52379 26469 52380 26327 52380 26281 52380 26279 52381 26406 52381 26328 52381 26328 52382 26406 52382 26283 52382 26328 52383 26283 52383 26329 52383 26329 52384 26283 52384 26330 52384 26329 52385 26330 52385 26282 52385 26282 52386 26330 52386 26284 52386 26282 52387 26284 52387 26472 52387 26331 52388 26332 52388 26333 52388 26333 52389 26332 52389 26474 52389 26333 52390 26474 52390 26284 52390 26284 52391 26474 52391 26334 52391 26284 52392 26334 52392 26472 52392 26287 52393 26260 52393 26288 52393 26288 52394 26260 52394 26258 52394 26288 52395 26258 52395 26335 52395 26335 52396 26258 52396 26336 52396 26335 52397 26336 52397 26290 52397 26290 52398 26336 52398 26337 52398 26290 52399 26337 52399 26476 52399 26476 52400 26337 52400 26338 52400 26269 52401 26339 52401 26267 52401 26267 52402 26339 52402 26293 52402 26267 52403 26293 52403 26340 52403 26340 52404 26293 52404 26341 52404 26340 52405 26341 52405 26337 52405 26337 52406 26341 52406 26477 52406 26337 52407 26477 52407 26338 52407 26342 52408 26343 52408 26292 52408 26292 52409 26343 52409 26344 52409 26292 52410 26344 52410 26341 52410 26341 52411 26344 52411 26479 52411 26341 52412 26479 52412 26477 52412 26269 52413 26384 52413 26339 52413 26339 52414 26384 52414 26294 52414 26339 52415 26294 52415 26291 52415 26291 52416 26294 52416 26295 52416 26291 52417 26295 52417 26345 52417 26345 52418 26295 52418 26349 52418 26345 52419 26349 52419 26480 52419 26484 52420 26346 52420 26347 52420 26347 52421 26346 52421 26348 52421 26347 52422 26348 52422 26349 52422 26349 52423 26348 52423 26482 52423 26349 52424 26482 52424 26480 52424 26382 52425 26351 52425 26350 52425 26350 52426 26351 52426 26353 52426 26350 52427 26353 52427 26352 52427 26352 52428 26353 52428 26354 52428 26352 52429 26354 52429 26347 52429 26347 52430 26354 52430 26299 52430 26347 52431 26299 52431 26484 52431 26484 52432 26299 52432 26300 52432 26296 52433 26408 52433 26297 52433 26297 52434 26408 52434 26302 52434 26297 52435 26302 52435 26298 52435 26298 52436 26302 52436 26303 52436 26298 52437 26303 52437 26355 52437 26355 52438 26303 52438 26357 52438 26355 52439 26357 52439 26486 52439 26308 52440 26488 52440 26307 52440 26307 52441 26488 52441 26356 52441 26307 52442 26356 52442 26357 52442 26357 52443 26356 52443 26487 52443 26357 52444 26487 52444 26486 52444 26358 52445 26387 52445 26359 52445 26359 52446 26387 52446 26263 52446 26359 52447 26263 52447 26306 52447 26306 52448 26263 52448 26270 52448 26306 52449 26270 52449 26360 52449 26360 52450 26270 52450 26361 52450 26360 52451 26361 52451 26489 52451 26489 52452 26361 52452 26490 52452 26365 52453 26493 52453 26492 52453 26388 52454 26256 52454 26272 52454 26272 52455 26256 52455 26362 52455 26272 52456 26362 52456 26271 52456 26271 52457 26362 52457 26365 52457 26271 52458 26365 52458 26361 52458 26361 52459 26365 52459 26492 52459 26361 52460 26492 52460 26490 52460 26255 52461 26254 52461 26256 52461 26256 52462 26254 52462 26363 52462 26256 52463 26363 52463 26362 52463 26362 52464 26363 52464 26364 52464 26362 52465 26364 52465 26365 52465 26365 52466 26364 52466 21528 52466 26365 52467 21528 52467 26493 52467 21774 52468 26135 52468 26399 52468 26366 52469 21651 52469 21653 52469 26372 52470 21780 52470 26371 52470 26367 52471 26378 52471 26368 52471 26368 52472 26378 52472 21665 52472 21785 52473 26392 52473 21660 52473 26366 52474 21653 52474 26397 52474 21651 52475 26366 52475 26369 52475 26369 52476 26366 52476 26370 52476 26369 52477 26370 52477 21650 52477 21650 52478 26370 52478 21648 52478 21648 52479 26370 52479 26375 52479 21648 52480 26375 52480 26376 52480 26371 52481 21645 52481 26372 52481 26372 52482 21645 52482 26373 52482 26372 52483 26373 52483 26375 52483 26375 52484 26373 52484 26374 52484 26375 52485 26374 52485 26376 52485 26385 52486 26377 52486 26131 52486 26131 52487 26377 52487 26259 52487 26131 52488 26259 52488 26132 52488 26132 52489 26259 52489 26260 52489 26132 52490 26260 52490 26133 52490 21660 52491 21661 52491 21785 52491 21785 52492 21661 52492 21662 52492 21785 52493 21662 52493 26378 52493 26378 52494 21662 52494 21663 52494 26378 52495 21663 52495 21665 52495 21778 52496 26380 52496 21780 52496 21780 52497 26380 52497 26379 52497 21780 52498 26379 52498 26371 52498 21777 52499 21641 52499 21778 52499 21778 52500 21641 52500 21642 52500 21778 52501 21642 52501 26380 52501 21776 52502 21638 52502 21777 52502 21777 52503 21638 52503 26381 52503 21777 52504 26381 52504 21641 52504 26129 52505 26382 52505 26383 52505 26383 52506 26382 52506 26384 52506 26383 52507 26384 52507 26385 52507 26385 52508 26384 52508 26269 52508 26385 52509 26269 52509 26377 52509 26390 52510 26387 52510 26386 52510 26386 52511 26387 52511 26358 52511 26386 52512 26358 52512 26127 52512 26412 52513 26388 52513 26389 52513 26389 52514 26388 52514 26261 52514 26389 52515 26261 52515 26390 52515 26390 52516 26261 52516 26391 52516 26390 52517 26391 52517 26387 52517 26393 52518 26395 52518 26392 52518 26392 52519 26395 52519 21659 52519 26392 52520 21659 52520 21660 52520 21783 52521 26394 52521 26393 52521 26393 52522 26394 52522 21658 52522 26393 52523 21658 52523 26395 52523 21653 52524 26396 52524 26397 52524 26397 52525 26396 52525 21655 52525 26397 52526 21655 52526 21783 52526 21783 52527 21655 52527 26398 52527 21783 52528 26398 52528 26394 52528 26400 52529 21636 52529 21776 52529 21776 52530 21636 52530 21637 52530 21776 52531 21637 52531 21638 52531 26399 52532 26257 52532 21774 52532 21774 52533 26257 52533 21633 52533 21774 52534 21633 52534 26400 52534 26400 52535 21633 52535 26401 52535 26400 52536 26401 52536 21636 52536 26402 52537 26403 52537 26404 52537 26404 52538 26403 52538 26275 52538 26404 52539 26275 52539 26135 52539 26135 52540 26275 52540 26405 52540 26135 52541 26405 52541 26399 52541 26260 52542 26287 52542 26133 52542 26133 52543 26287 52543 26286 52543 26133 52544 26286 52544 26407 52544 26407 52545 26286 52545 26406 52545 26407 52546 26406 52546 26402 52546 26402 52547 26406 52547 26279 52547 26402 52548 26279 52548 26403 52548 26358 52549 26301 52549 26127 52549 26127 52550 26301 52550 26408 52550 26127 52551 26408 52551 26409 52551 26409 52552 26408 52552 26296 52552 26409 52553 26296 52553 26129 52553 26129 52554 26296 52554 26351 52554 26129 52555 26351 52555 26382 52555 26368 52556 26410 52556 26367 52556 26367 52557 26410 52557 26411 52557 26367 52558 26411 52558 26126 52558 26126 52559 26411 52559 26413 52559 26126 52560 26413 52560 26412 52560 26412 52561 26413 52561 26255 52561 26412 52562 26255 52562 26388 52562 21791 52563 21790 52563 26417 52563 21804 52564 26439 52564 26419 52564 26245 52565 26246 52565 26440 52565 26414 52566 26423 52566 26415 52566 26415 52567 26423 52567 26416 52567 26415 52568 26416 52568 21797 52568 26417 52569 21790 52569 21769 52569 21769 52570 21790 52570 21788 52570 21769 52571 21788 52571 26427 52571 26115 52572 26418 52572 26222 52572 26421 52573 26220 52573 26418 52573 26418 52574 26220 52574 26221 52574 26418 52575 26221 52575 26222 52575 26419 52576 26420 52576 21804 52576 21804 52577 26420 52577 26217 52577 21804 52578 26217 52578 26421 52578 26421 52579 26217 52579 26218 52579 26421 52580 26218 52580 26220 52580 21793 52581 21710 52581 21794 52581 21794 52582 21710 52582 26422 52582 21794 52583 26422 52583 26414 52583 26414 52584 26422 52584 21757 52584 26414 52585 21757 52585 26423 52585 26417 52586 21670 52586 21791 52586 21791 52587 21670 52587 26424 52587 21791 52588 26424 52588 26425 52588 26425 52589 26424 52589 21714 52589 26425 52590 21714 52590 21793 52590 21793 52591 21714 52591 26426 52591 21793 52592 26426 52592 21710 52592 26427 52593 21788 52593 26428 52593 26428 52594 21788 52594 26125 52594 26428 52595 26125 52595 26429 52595 26429 52596 26125 52596 26432 52596 26429 52597 26432 52597 26252 52597 26440 52598 26246 52598 26124 52598 26416 52599 21678 52599 21797 52599 21797 52600 21678 52600 21676 52600 21797 52601 21676 52601 26430 52601 26430 52602 21676 52602 26431 52602 26430 52603 26431 52603 21800 52603 21800 52604 26431 52604 21743 52604 21800 52605 21743 52605 26449 52605 26252 52606 26432 52606 26433 52606 26433 52607 26432 52607 26434 52607 26433 52608 26434 52608 26436 52608 26246 52609 26248 52609 26124 52609 26124 52610 26248 52610 26249 52610 26124 52611 26249 52611 26434 52611 26434 52612 26249 52612 26435 52612 26434 52613 26435 52613 26436 52613 21803 52614 21689 52614 26437 52614 26437 52615 21689 52615 26438 52615 26437 52616 26438 52616 26439 52616 26439 52617 26438 52617 21685 52617 26439 52618 21685 52618 26419 52618 26245 52619 26440 52619 26244 52619 26244 52620 26440 52620 26441 52620 26244 52621 26441 52621 26243 52621 26243 52622 26441 52622 26442 52622 26442 52623 26441 52623 26122 52623 26442 52624 26122 52624 26443 52624 26117 52625 26458 52625 26227 52625 26443 52626 26122 52626 26240 52626 26240 52627 26122 52627 26444 52627 26240 52628 26444 52628 26238 52628 26238 52629 26444 52629 26445 52629 26445 52630 26444 52630 26446 52630 26445 52631 26446 52631 26235 52631 26235 52632 26446 52632 26234 52632 26234 52633 26446 52633 26447 52633 26234 52634 26447 52634 26233 52634 21743 52635 26448 52635 26449 52635 26449 52636 26448 52636 21693 52636 26449 52637 21693 52637 21802 52637 21802 52638 21693 52638 26450 52638 21802 52639 26450 52639 21803 52639 21803 52640 26450 52640 26451 52640 21803 52641 26451 52641 21689 52641 26233 52642 26447 52642 26230 52642 26230 52643 26447 52643 26118 52643 26230 52644 26118 52644 26454 52644 26227 52645 26452 52645 26117 52645 26117 52646 26452 52646 26453 52646 26117 52647 26453 52647 26118 52647 26118 52648 26453 52648 26229 52648 26118 52649 26229 52649 26454 52649 26222 52650 26455 52650 26115 52650 26115 52651 26455 52651 26456 52651 26115 52652 26456 52652 26457 52652 26456 52653 26224 52653 26457 52653 26457 52654 26224 52654 26225 52654 26457 52655 26225 52655 26458 52655 26458 52656 26225 52656 26459 52656 26458 52657 26459 52657 26227 52657 21554 52658 26312 52658 26460 52658 26460 52659 26312 52659 26311 52659 26460 52660 26311 52660 26461 52660 26461 52661 26311 52661 26318 52661 26461 52662 26318 52662 26141 52662 26141 52663 26318 52663 26463 52663 26141 52664 26463 52664 26462 52664 26462 52665 26463 52665 26464 52665 26462 52666 26464 52666 26143 52666 26143 52667 26464 52667 26317 52667 26143 52668 26317 52668 26465 52668 26317 52669 26274 52669 26465 52669 26465 52670 26274 52670 26323 52670 26465 52671 26323 52671 26144 52671 26144 52672 26323 52672 26466 52672 26144 52673 26466 52673 26145 52673 26145 52674 26466 52674 26467 52674 26145 52675 26467 52675 26146 52675 26146 52676 26467 52676 26468 52676 26146 52677 26468 52677 26470 52677 26470 52678 26468 52678 26469 52678 26470 52679 26469 52679 26149 52679 26149 52680 26469 52680 26281 52680 26149 52681 26281 52681 26471 52681 26471 52682 26281 52682 26472 52682 26471 52683 26472 52683 26152 52683 26152 52684 26472 52684 26334 52684 26152 52685 26334 52685 26473 52685 26473 52686 26334 52686 26474 52686 26473 52687 26474 52687 26154 52687 26154 52688 26474 52688 26332 52688 26154 52689 26332 52689 26475 52689 26332 52690 26331 52690 26475 52690 26475 52691 26331 52691 26476 52691 26475 52692 26476 52692 26155 52692 26155 52693 26476 52693 26338 52693 26155 52694 26338 52694 26157 52694 26157 52695 26338 52695 26477 52695 26157 52696 26477 52696 26478 52696 26478 52697 26477 52697 26479 52697 26478 52698 26479 52698 26158 52698 26479 52699 26344 52699 26158 52699 26158 52700 26344 52700 26343 52700 26158 52701 26343 52701 26159 52701 26159 52702 26343 52702 26342 52702 26159 52703 26342 52703 26161 52703 26161 52704 26342 52704 26480 52704 26161 52705 26480 52705 26481 52705 26481 52706 26480 52706 26482 52706 26481 52707 26482 52707 26483 52707 26483 52708 26482 52708 26348 52708 26483 52709 26348 52709 26163 52709 26163 52710 26348 52710 26346 52710 26163 52711 26346 52711 26164 52711 26164 52712 26346 52712 26484 52712 26164 52713 26484 52713 26166 52713 26166 52714 26484 52714 26300 52714 26166 52715 26300 52715 26485 52715 26485 52716 26300 52716 26486 52716 26485 52717 26486 52717 26168 52717 26168 52718 26486 52718 26487 52718 26168 52719 26487 52719 26170 52719 26487 52720 26356 52720 26170 52720 26170 52721 26356 52721 26488 52721 26170 52722 26488 52722 26171 52722 26171 52723 26488 52723 26308 52723 26171 52724 26308 52724 26173 52724 26173 52725 26308 52725 26489 52725 26173 52726 26489 52726 26175 52726 26175 52727 26489 52727 26490 52727 26175 52728 26490 52728 26491 52728 26491 52729 26490 52729 26492 52729 26491 52730 26492 52730 26176 52730 26176 52731 26492 52731 26493 52731 26176 52732 26493 52732 21529 52732 21529 52733 26493 52733 21528 52733 26867 52734 21517 52734 21323 52734 21323 52735 21517 52735 26562 52735 21323 52736 26562 52736 21324 52736 21324 52737 26562 52737 26495 52737 21324 52738 26495 52738 21325 52738 21325 52739 26495 52739 26494 52739 26494 52740 26495 52740 26563 52740 26494 52741 26563 52741 26496 52741 26496 52742 26563 52742 26497 52742 26496 52743 26497 52743 26498 52743 26498 52744 26497 52744 21321 52744 21321 52745 26497 52745 26565 52745 21321 52746 26565 52746 26499 52746 26499 52747 26565 52747 26568 52747 26499 52748 26568 52748 26500 52748 26500 52749 26568 52749 26569 52749 26500 52750 26569 52750 26501 52750 26501 52751 26569 52751 21319 52751 21319 52752 26569 52752 26503 52752 21319 52753 26503 52753 26502 52753 26502 52754 26503 52754 26504 52754 26502 52755 26504 52755 26505 52755 26505 52756 26504 52756 26506 52756 26506 52757 26504 52757 26572 52757 26506 52758 26572 52758 26507 52758 26507 52759 26572 52759 26573 52759 26507 52760 26573 52760 21314 52760 21314 52761 26573 52761 21315 52761 21315 52762 26573 52762 26575 52762 21315 52763 26575 52763 26508 52763 26508 52764 26575 52764 26509 52764 26508 52765 26509 52765 21313 52765 21313 52766 26509 52766 21312 52766 21312 52767 26509 52767 26510 52767 21312 52768 26510 52768 21310 52768 21310 52769 26510 52769 26512 52769 21310 52770 26512 52770 21311 52770 21311 52771 26512 52771 26511 52771 26511 52772 26512 52772 26579 52772 26511 52773 26579 52773 26513 52773 26513 52774 26579 52774 26516 52774 26513 52775 26516 52775 26514 52775 26514 52776 26516 52776 26515 52776 26515 52777 26516 52777 26580 52777 26515 52778 26580 52778 26517 52778 26517 52779 26580 52779 26518 52779 26517 52780 26518 52780 21307 52780 21307 52781 26518 52781 26519 52781 21307 52782 26519 52782 26520 52782 26520 52783 26519 52783 26522 52783 26520 52784 26522 52784 26521 52784 26521 52785 26522 52785 21305 52785 21305 52786 26522 52786 26583 52786 21305 52787 26583 52787 26523 52787 26523 52788 26583 52788 26585 52788 26523 52789 26585 52789 21306 52789 21306 52790 26585 52790 26524 52790 26524 52791 26585 52791 26525 52791 26524 52792 26525 52792 26526 52792 26526 52793 26525 52793 26527 52793 26526 52794 26527 52794 21300 52794 21300 52795 26527 52795 26528 52795 21300 52796 26528 52796 21301 52796 21301 52797 26528 52797 26529 52797 26529 52798 26528 52798 26589 52798 26529 52799 26589 52799 21302 52799 21302 52800 26589 52800 26530 52800 21302 52801 26530 52801 26531 52801 26531 52802 26530 52802 26532 52802 26532 52803 26530 52803 26533 52803 26532 52804 26533 52804 21297 52804 21297 52805 26533 52805 26593 52805 21297 52806 26593 52806 21298 52806 21298 52807 26593 52807 21299 52807 21299 52808 26593 52808 26534 52808 21299 52809 26534 52809 21292 52809 21292 52810 26534 52810 26594 52810 21292 52811 26594 52811 21293 52811 21293 52812 26594 52812 21295 52812 21295 52813 26594 52813 26596 52813 21295 52814 26596 52814 21296 52814 21296 52815 26596 52815 26535 52815 21296 52816 26535 52816 26600 52816 21514 52817 27022 52817 26536 52817 26536 52818 27022 52818 21204 52818 26536 52819 21204 52819 26537 52819 26537 52820 21204 52820 21194 52820 26537 52821 21194 52821 26538 52821 26538 52822 21194 52822 21196 52822 26538 52823 21196 52823 26564 52823 26564 52824 21196 52824 21197 52824 26564 52825 21197 52825 26566 52825 26566 52826 21197 52826 26539 52826 26566 52827 26539 52827 26567 52827 26567 52828 26539 52828 26540 52828 26567 52829 26540 52829 26570 52829 26570 52830 26540 52830 26541 52830 26570 52831 26541 52831 26542 52831 26542 52832 26541 52832 26543 52832 26542 52833 26543 52833 26571 52833 26571 52834 26543 52834 21183 52834 26571 52835 21183 52835 26574 52835 26574 52836 21183 52836 21185 52836 26574 52837 21185 52837 26544 52837 26544 52838 21185 52838 26545 52838 26544 52839 26545 52839 26546 52839 26546 52840 26545 52840 26547 52840 26546 52841 26547 52841 26576 52841 26576 52842 26547 52842 21214 52842 26576 52843 21214 52843 26577 52843 26577 52844 21214 52844 21168 52844 26577 52845 21168 52845 26578 52845 26578 52846 21168 52846 26548 52846 26578 52847 26548 52847 26549 52847 26549 52848 26548 52848 21170 52848 26549 52849 21170 52849 26550 52849 26550 52850 21170 52850 21163 52850 26550 52851 21163 52851 26551 52851 26551 52852 21163 52852 21217 52852 26551 52853 21217 52853 26581 52853 26581 52854 21217 52854 26552 52854 26581 52855 26552 52855 26553 52855 26553 52856 26552 52856 21220 52856 26553 52857 21220 52857 26582 52857 26582 52858 21220 52858 21160 52858 26582 52859 21160 52859 26584 52859 26584 52860 21160 52860 21161 52860 26584 52861 21161 52861 26586 52861 26586 52862 21161 52862 26554 52862 26586 52863 26554 52863 26555 52863 26555 52864 26554 52864 21221 52864 26555 52865 21221 52865 26587 52865 26587 52866 21221 52866 21222 52866 26587 52867 21222 52867 26588 52867 26588 52868 21222 52868 21143 52868 26588 52869 21143 52869 26590 52869 26590 52870 21143 52870 21145 52870 26590 52871 21145 52871 26591 52871 26591 52872 21145 52872 21131 52872 26591 52873 21131 52873 26592 52873 26592 52874 21131 52874 26556 52874 26592 52875 26556 52875 26557 52875 26557 52876 26556 52876 21227 52876 26557 52877 21227 52877 26558 52877 26558 52878 21227 52878 21228 52878 26558 52879 21228 52879 26595 52879 26595 52880 21228 52880 21229 52880 26595 52881 21229 52881 26597 52881 26597 52882 21229 52882 21231 52882 26597 52883 21231 52883 26559 52883 26559 52884 21231 52884 21119 52884 26559 52885 21119 52885 26560 52885 26560 52886 21119 52886 21122 52886 26560 52887 21122 52887 26561 52887 26561 52888 21122 52888 21115 52888 21517 52889 21514 52889 26562 52889 26562 52890 21514 52890 26536 52890 26562 52891 26536 52891 26495 52891 26495 52892 26536 52892 26537 52892 26495 52893 26537 52893 26563 52893 26563 52894 26537 52894 26538 52894 26563 52895 26538 52895 26497 52895 26497 52896 26538 52896 26564 52896 26497 52897 26564 52897 26565 52897 26565 52898 26564 52898 26566 52898 26565 52899 26566 52899 26568 52899 26568 52900 26566 52900 26567 52900 26568 52901 26567 52901 26569 52901 26569 52902 26567 52902 26570 52902 26569 52903 26570 52903 26503 52903 26503 52904 26570 52904 26542 52904 26503 52905 26542 52905 26504 52905 26504 52906 26542 52906 26571 52906 26504 52907 26571 52907 26572 52907 26572 52908 26571 52908 26574 52908 26572 52909 26574 52909 26573 52909 26573 52910 26574 52910 26544 52910 26573 52911 26544 52911 26575 52911 26575 52912 26544 52912 26546 52912 26575 52913 26546 52913 26509 52913 26509 52914 26546 52914 26576 52914 26509 52915 26576 52915 26510 52915 26510 52916 26576 52916 26577 52916 26510 52917 26577 52917 26512 52917 26512 52918 26577 52918 26578 52918 26512 52919 26578 52919 26579 52919 26579 52920 26578 52920 26549 52920 26579 52921 26549 52921 26516 52921 26516 52922 26549 52922 26550 52922 26516 52923 26550 52923 26580 52923 26580 52924 26550 52924 26551 52924 26580 52925 26551 52925 26518 52925 26518 52926 26551 52926 26581 52926 26518 52927 26581 52927 26519 52927 26519 52928 26581 52928 26553 52928 26519 52929 26553 52929 26522 52929 26522 52930 26553 52930 26582 52930 26522 52931 26582 52931 26583 52931 26583 52932 26582 52932 26584 52932 26583 52933 26584 52933 26585 52933 26585 52934 26584 52934 26586 52934 26585 52935 26586 52935 26525 52935 26525 52936 26586 52936 26555 52936 26525 52937 26555 52937 26527 52937 26527 52938 26555 52938 26587 52938 26527 52939 26587 52939 26528 52939 26528 52940 26587 52940 26588 52940 26528 52941 26588 52941 26589 52941 26589 52942 26588 52942 26590 52942 26589 52943 26590 52943 26530 52943 26530 52944 26590 52944 26591 52944 26530 52945 26591 52945 26533 52945 26533 52946 26591 52946 26592 52946 26533 52947 26592 52947 26593 52947 26593 52948 26592 52948 26557 52948 26593 52949 26557 52949 26534 52949 26534 52950 26557 52950 26558 52950 26534 52951 26558 52951 26594 52951 26594 52952 26558 52952 26595 52952 26594 52953 26595 52953 26596 52953 26596 52954 26595 52954 26597 52954 26596 52955 26597 52955 26535 52955 26535 52956 26597 52956 26559 52956 26535 52957 26559 52957 26598 52957 26598 52958 26559 52958 26560 52958 26598 52959 26560 52959 26599 52959 26599 52960 26560 52960 26561 52960 26600 52961 26535 52961 21290 52961 21290 52962 26535 52962 26598 52962 21290 52963 26598 52963 26601 52963 26601 52964 26598 52964 26599 52964 26601 52965 26599 52965 21289 52965 21115 52966 26603 52966 26602 52966 21115 52967 26602 52967 26561 52967 26561 52968 26602 52968 26605 52968 26561 52969 26605 52969 26599 52969 26599 52970 26605 52970 21288 52970 26599 52971 21288 52971 21289 52971 26603 52972 21445 52972 26604 52972 26603 52973 26604 52973 26602 52973 26602 52974 26604 52974 21398 52974 26602 52975 21398 52975 26605 52975 26605 52976 21398 52976 21287 52976 26605 52977 21287 52977 21288 52977 26635 52978 26606 52978 25114 52978 25114 52979 26606 52979 26607 52979 25114 52980 26607 52980 26608 52980 26608 52981 26607 52981 26609 52981 26608 52982 26609 52982 26610 52982 26610 52983 26609 52983 26611 52983 26610 52984 26611 52984 25115 52984 25115 52985 26611 52985 26642 52985 25115 52986 26642 52986 26613 52986 26613 52987 26642 52987 26612 52987 26613 52988 26612 52988 25117 52988 25117 52989 26612 52989 26644 52989 25117 52990 26644 52990 26614 52990 26614 52991 26644 52991 26645 52991 26614 52992 26645 52992 25120 52992 25120 52993 26645 52993 26647 52993 25120 52994 26647 52994 26615 52994 26615 52995 26647 52995 26648 52995 26615 52996 26648 52996 26616 52996 26616 52997 26648 52997 26650 52997 26616 52998 26650 52998 25123 52998 25123 52999 26650 52999 26652 52999 25123 53000 26652 53000 25124 53000 25124 53001 26652 53001 26617 53001 25124 53002 26617 53002 26618 53002 26618 53003 26617 53003 21381 53003 26618 53004 21381 53004 22022 53004 22022 53005 21381 53005 21383 53005 22022 53006 21383 53006 22023 53006 22023 53007 21383 53007 21384 53007 22023 53008 21384 53008 26619 53008 26619 53009 21384 53009 26620 53009 26619 53010 26620 53010 22025 53010 22025 53011 26620 53011 26621 53011 22025 53012 26621 53012 22026 53012 22026 53013 26621 53013 21386 53013 22026 53014 21386 53014 26622 53014 26622 53015 21386 53015 21388 53015 26622 53016 21388 53016 26623 53016 26623 53017 21388 53017 26624 53017 26623 53018 26624 53018 26625 53018 26625 53019 26624 53019 21389 53019 26625 53020 21389 53020 26626 53020 26626 53021 21389 53021 21392 53021 26626 53022 21392 53022 26627 53022 26627 53023 21392 53023 21393 53023 26627 53024 21393 53024 26628 53024 26628 53025 21393 53025 21394 53025 26628 53026 21394 53026 22029 53026 22029 53027 21394 53027 21395 53027 22029 53028 21395 53028 26629 53028 26629 53029 21395 53029 21396 53029 26629 53030 21396 53030 22033 53030 22033 53031 21396 53031 26630 53031 22033 53032 26630 53032 25110 53032 25110 53033 26630 53033 26631 53033 25110 53034 26631 53034 25111 53034 25111 53035 26631 53035 26632 53035 25111 53036 26632 53036 25113 53036 25113 53037 26632 53037 26633 53037 25113 53038 26633 53038 26634 53038 26634 53039 26633 53039 26637 53039 26634 53040 26637 53040 26635 53040 26635 53041 26637 53041 26606 53041 26631 53042 25094 53042 26632 53042 26632 53043 25094 53043 26636 53043 26632 53044 26636 53044 26633 53044 26633 53045 26636 53045 25095 53045 26633 53046 25095 53046 26637 53046 26637 53047 25095 53047 26638 53047 26637 53048 26638 53048 26606 53048 26606 53049 26638 53049 26639 53049 26606 53050 26639 53050 26607 53050 26607 53051 26639 53051 26640 53051 26607 53052 26640 53052 26609 53052 26609 53053 26640 53053 26641 53053 26609 53054 26641 53054 26611 53054 26611 53055 26641 53055 25099 53055 26611 53056 25099 53056 26642 53056 26642 53057 25099 53057 26643 53057 26642 53058 26643 53058 26612 53058 26612 53059 26643 53059 25101 53059 26612 53060 25101 53060 26644 53060 26644 53061 25101 53061 25103 53061 26644 53062 25103 53062 26645 53062 26645 53063 25103 53063 26646 53063 26645 53064 26646 53064 26647 53064 26647 53065 26646 53065 25106 53065 26647 53066 25106 53066 26648 53066 26648 53067 25106 53067 26649 53067 26648 53068 26649 53068 26650 53068 26650 53069 26649 53069 26651 53069 26650 53070 26651 53070 26652 53070 26652 53071 26651 53071 26653 53071 26652 53072 26653 53072 26617 53072 26617 53073 26653 53073 25109 53073 25098 53074 21936 53074 26654 53074 26654 53075 21936 53075 21937 53075 26654 53076 21937 53076 25100 53076 25100 53077 21937 53077 21939 53077 25100 53078 21939 53078 25102 53078 25102 53079 21939 53079 21940 53079 25102 53080 21940 53080 25104 53080 25104 53081 21940 53081 21941 53081 25104 53082 21941 53082 26656 53082 26656 53083 21941 53083 26655 53083 26656 53084 26655 53084 25105 53084 25105 53085 26655 53085 21944 53085 25105 53086 21944 53086 26657 53086 26657 53087 21944 53087 21945 53087 26657 53088 21945 53088 25107 53088 25107 53089 21945 53089 21946 53089 25107 53090 21946 53090 25108 53090 25108 53091 21946 53091 26658 53091 25108 53092 26658 53092 26659 53092 26659 53093 26658 53093 26660 53093 26659 53094 26660 53094 26661 53094 26661 53095 26660 53095 26662 53095 26661 53096 26662 53096 22035 53096 22035 53097 26662 53097 26663 53097 22035 53098 26663 53098 22036 53098 22036 53099 26663 53099 25187 53099 22036 53100 25187 53100 22037 53100 22037 53101 25187 53101 25188 53101 22037 53102 25188 53102 22038 53102 22038 53103 25188 53103 26665 53103 22038 53104 26665 53104 26664 53104 26664 53105 26665 53105 25189 53105 26664 53106 25189 53106 22041 53106 22041 53107 25189 53107 26667 53107 22041 53108 26667 53108 26666 53108 26666 53109 26667 53109 25191 53109 26666 53110 25191 53110 26668 53110 26668 53111 25191 53111 26669 53111 26668 53112 26669 53112 22043 53112 22043 53113 26669 53113 25192 53113 22043 53114 25192 53114 26670 53114 26670 53115 25192 53115 26671 53115 26670 53116 26671 53116 26673 53116 26673 53117 26671 53117 26672 53117 26673 53118 26672 53118 22047 53118 22047 53119 26672 53119 26674 53119 22047 53120 26674 53120 22048 53120 22048 53121 26674 53121 25195 53121 22048 53122 25195 53122 22050 53122 22050 53123 25195 53123 26675 53123 22050 53124 26675 53124 26676 53124 26676 53125 26675 53125 26678 53125 26676 53126 26678 53126 26677 53126 26677 53127 26678 53127 21931 53127 26677 53128 21931 53128 26679 53128 26679 53129 21931 53129 26680 53129 26679 53130 26680 53130 25096 53130 25096 53131 26680 53131 21933 53131 25096 53132 21933 53132 26681 53132 26681 53133 21933 53133 26682 53133 26681 53134 26682 53134 25097 53134 25097 53135 26682 53135 21935 53135 25097 53136 21935 53136 25098 53136 25098 53137 21935 53137 21936 53137 26683 53138 26684 53138 25196 53138 26683 53139 25196 53139 26685 53139 26685 53140 25196 53140 26687 53140 26685 53141 26687 53141 26686 53141 26686 53142 26687 53142 25194 53142 26686 53143 25194 53143 26714 53143 26714 53144 25194 53144 26688 53144 26714 53145 26688 53145 26689 53145 26689 53146 26688 53146 26690 53146 26689 53147 26690 53147 26691 53147 26691 53148 26690 53148 25193 53148 26691 53149 25193 53149 26712 53149 26712 53150 25193 53150 26692 53150 26712 53151 26692 53151 26710 53151 26710 53152 26692 53152 26693 53152 26710 53153 26693 53153 26695 53153 26695 53154 26693 53154 26694 53154 26695 53155 26694 53155 26708 53155 26708 53156 26694 53156 25190 53156 26708 53157 25190 53157 26696 53157 26696 53158 25190 53158 26697 53158 26696 53159 26697 53159 26699 53159 26699 53160 26697 53160 26698 53160 26699 53161 26698 53161 26700 53161 26700 53162 26698 53162 26701 53162 26700 53163 26701 53163 26705 53163 26705 53164 26701 53164 26702 53164 26705 53165 26702 53165 26732 53165 26732 53166 26702 53166 25186 53166 26732 53167 25186 53167 26703 53167 26703 53168 25186 53168 25185 53168 26703 53169 25185 53169 26704 53169 26732 53170 26734 53170 26705 53170 26705 53171 26734 53171 26706 53171 26705 53172 26706 53172 26700 53172 26700 53173 26706 53173 25083 53173 26700 53174 25083 53174 26699 53174 26699 53175 25083 53175 25086 53175 26699 53176 25086 53176 26696 53176 26696 53177 25086 53177 26707 53177 26696 53178 26707 53178 26708 53178 26708 53179 26707 53179 26709 53179 26708 53180 26709 53180 26695 53180 26695 53181 26709 53181 26711 53181 26695 53182 26711 53182 26710 53182 26710 53183 26711 53183 25088 53183 26710 53184 25088 53184 26712 53184 26712 53185 25088 53185 26713 53185 26712 53186 26713 53186 26691 53186 26691 53187 26713 53187 25089 53187 26691 53188 25089 53188 26689 53188 26689 53189 25089 53189 25091 53189 26689 53190 25091 53190 26714 53190 26714 53191 25091 53191 25092 53191 26714 53192 25092 53192 26686 53192 26686 53193 25092 53193 25093 53193 26686 53194 25093 53194 26685 53194 26685 53195 25093 53195 26715 53195 26685 53196 26715 53196 26683 53196 26683 53197 26715 53197 26716 53197 26683 53198 26716 53198 26717 53198 26717 53199 26716 53199 22054 53199 26717 53200 22054 53200 26718 53200 22054 53201 22055 53201 26718 53201 26718 53202 22055 53202 22056 53202 26718 53203 22056 53203 21379 53203 21379 53204 22056 53204 22057 53204 21379 53205 22057 53205 21377 53205 21377 53206 22057 53206 26719 53206 21377 53207 26719 53207 26720 53207 26720 53208 26719 53208 22059 53208 26720 53209 22059 53209 26721 53209 26721 53210 22059 53210 26722 53210 26721 53211 26722 53211 21374 53211 21374 53212 26722 53212 26723 53212 21374 53213 26723 53213 21372 53213 21372 53214 26723 53214 22062 53214 21372 53215 22062 53215 26724 53215 26724 53216 22062 53216 26725 53216 26724 53217 26725 53217 26726 53217 26726 53218 26725 53218 22066 53218 26726 53219 22066 53219 26727 53219 26727 53220 22066 53220 22067 53220 26727 53221 22067 53221 21370 53221 21370 53222 22067 53222 26728 53222 21370 53223 26728 53223 21368 53223 21368 53224 26728 53224 26729 53224 21368 53225 26729 53225 26730 53225 26730 53226 26729 53226 22069 53226 26730 53227 22069 53227 21365 53227 21365 53228 22069 53228 22071 53228 21365 53229 22071 53229 26704 53229 26704 53230 22071 53230 26731 53230 26704 53231 26731 53231 26703 53231 26703 53232 26731 53232 25080 53232 26703 53233 25080 53233 26732 53233 26732 53234 25080 53234 26733 53234 26732 53235 26733 53235 26734 53235 21364 53236 22052 53236 26735 53236 21364 53237 26735 53237 26736 53237 26736 53238 26735 53238 26737 53238 26736 53239 26737 53239 26738 53239 26738 53240 26737 53240 25090 53240 26738 53241 25090 53241 26739 53241 26739 53242 25090 53242 26740 53242 26739 53243 26740 53243 26741 53243 26741 53244 26740 53244 26743 53244 26741 53245 26743 53245 26742 53245 26742 53246 26743 53246 25087 53246 26742 53247 25087 53247 26744 53247 26744 53248 25087 53248 26745 53248 26744 53249 26745 53249 26770 53249 26770 53250 26745 53250 26746 53250 26770 53251 26746 53251 26747 53251 26747 53252 26746 53252 26748 53252 26747 53253 26748 53253 26749 53253 26749 53254 26748 53254 25085 53254 26749 53255 25085 53255 26750 53255 26750 53256 25085 53256 25084 53256 26750 53257 25084 53257 26752 53257 26752 53258 25084 53258 26751 53258 26752 53259 26751 53259 26753 53259 26753 53260 26751 53260 25082 53260 26753 53261 25082 53261 26767 53261 26767 53262 25082 53262 25081 53262 26767 53263 25081 53263 26766 53263 26766 53264 25081 53264 26755 53264 26766 53265 26755 53265 26754 53265 26754 53266 26755 53266 26756 53266 26754 53267 26756 53267 26764 53267 26764 53268 26756 53268 22072 53268 26764 53269 22072 53269 26757 53269 21357 53270 26954 53270 21356 53270 21356 53271 26954 53271 26956 53271 21356 53272 26956 53272 21355 53272 21355 53273 26956 53273 26957 53273 21355 53274 26957 53274 21354 53274 21354 53275 26957 53275 26958 53275 21354 53276 26958 53276 21352 53276 21352 53277 26958 53277 26758 53277 21352 53278 26758 53278 21351 53278 21351 53279 26758 53279 26960 53279 21351 53280 26960 53280 21350 53280 21350 53281 26960 53281 26961 53281 21350 53282 26961 53282 26759 53282 26759 53283 26961 53283 26963 53283 26759 53284 26963 53284 21348 53284 21348 53285 26963 53285 26964 53285 21348 53286 26964 53286 26760 53286 26760 53287 26964 53287 26761 53287 26760 53288 26761 53288 21346 53288 21346 53289 26761 53289 26762 53289 21346 53290 26762 53290 21344 53290 21344 53291 26762 53291 26968 53291 21344 53292 26968 53292 26757 53292 26757 53293 26968 53293 26763 53293 26757 53294 26763 53294 26764 53294 26764 53295 26763 53295 26765 53295 26764 53296 26765 53296 26754 53296 26754 53297 26765 53297 21234 53297 26754 53298 21234 53298 26766 53298 26766 53299 21234 53299 21235 53299 26766 53300 21235 53300 26767 53300 26767 53301 21235 53301 21237 53301 26767 53302 21237 53302 26753 53302 26753 53303 21237 53303 21238 53303 26753 53304 21238 53304 26752 53304 26752 53305 21238 53305 21240 53305 26752 53306 21240 53306 26750 53306 26750 53307 21240 53307 26768 53307 26750 53308 26768 53308 26749 53308 26749 53309 26768 53309 26769 53309 26749 53310 26769 53310 26747 53310 26747 53311 26769 53311 21241 53311 26747 53312 21241 53312 26770 53312 26770 53313 21241 53313 26771 53313 26770 53314 26771 53314 26744 53314 26744 53315 26771 53315 26772 53315 26744 53316 26772 53316 26742 53316 26742 53317 26772 53317 26773 53317 26742 53318 26773 53318 26741 53318 26741 53319 26773 53319 26774 53319 26741 53320 26774 53320 26739 53320 26739 53321 26774 53321 21245 53321 26739 53322 21245 53322 26738 53322 26738 53323 21245 53323 21248 53323 26738 53324 21248 53324 26736 53324 26736 53325 21248 53325 21250 53325 26736 53326 21250 53326 21364 53326 21364 53327 21250 53327 26775 53327 21364 53328 26775 53328 26776 53328 26776 53329 26775 53329 26950 53329 26776 53330 26950 53330 21362 53330 21362 53331 26950 53331 26777 53331 21362 53332 26777 53332 21361 53332 21361 53333 26777 53333 26951 53333 21361 53334 26951 53334 21359 53334 21359 53335 26951 53335 26778 53335 21359 53336 26778 53336 21357 53336 21357 53337 26778 53337 26954 53337 26779 53338 26780 53338 21954 53338 21954 53339 26780 53339 26781 53339 21954 53340 26781 53340 26782 53340 26782 53341 26781 53341 21334 53341 26782 53342 21334 53342 26783 53342 26783 53343 21334 53343 21336 53343 26783 53344 21336 53344 21959 53344 21959 53345 21336 53345 26784 53345 21959 53346 26784 53346 21960 53346 21960 53347 26784 53347 21338 53347 21960 53348 21338 53348 21962 53348 21962 53349 21338 53349 21340 53349 21962 53350 21340 53350 21964 53350 21964 53351 21340 53351 26785 53351 21964 53352 26785 53352 26787 53352 26787 53353 26785 53353 26786 53353 26787 53354 26786 53354 26788 53354 26788 53355 26786 53355 21342 53355 26788 53356 21342 53356 21968 53356 21968 53357 21342 53357 26789 53357 21968 53358 26789 53358 26790 53358 26790 53359 26789 53359 26791 53359 26790 53360 26791 53360 21969 53360 21969 53361 26791 53361 21343 53361 21969 53362 21343 53362 25170 53362 25170 53363 21343 53363 26809 53363 25170 53364 26809 53364 26792 53364 26792 53365 26809 53365 26793 53365 26792 53366 26793 53366 26794 53366 26794 53367 26793 53367 26795 53367 26794 53368 26795 53368 25172 53368 25172 53369 26795 53369 26810 53369 25172 53370 26810 53370 26796 53370 26810 53371 26797 53371 26796 53371 26796 53372 26797 53372 26814 53372 26796 53373 26814 53373 26798 53373 26798 53374 26814 53374 26799 53374 26798 53375 26799 53375 25174 53375 25174 53376 26799 53376 26816 53376 25174 53377 26816 53377 25175 53377 25175 53378 26816 53378 26818 53378 25175 53379 26818 53379 26801 53379 26801 53380 26818 53380 26800 53380 26801 53381 26800 53381 26802 53381 26802 53382 26800 53382 26819 53382 26802 53383 26819 53383 25177 53383 25177 53384 26819 53384 26821 53384 25177 53385 26821 53385 25178 53385 25178 53386 26821 53386 26823 53386 25178 53387 26823 53387 26803 53387 26803 53388 26823 53388 26825 53388 26803 53389 26825 53389 25181 53389 25181 53390 26825 53390 26826 53390 25181 53391 26826 53391 25183 53391 25183 53392 26826 53392 26804 53392 25183 53393 26804 53393 25184 53393 25184 53394 26804 53394 26828 53394 25184 53395 26828 53395 26806 53395 26806 53396 26828 53396 26805 53396 26806 53397 26805 53397 21950 53397 21950 53398 26805 53398 21326 53398 21950 53399 21326 53399 21951 53399 21951 53400 21326 53400 21328 53400 21951 53401 21328 53401 21952 53401 21952 53402 21328 53402 21330 53402 21952 53403 21330 53403 21953 53403 21953 53404 21330 53404 21331 53404 21953 53405 21331 53405 26779 53405 26779 53406 21331 53406 26807 53406 26779 53407 26807 53407 26780 53407 21343 53408 26808 53408 26809 53408 26809 53409 26808 53409 25155 53409 26809 53410 25155 53410 26793 53410 26793 53411 25155 53411 25156 53411 26793 53412 25156 53412 26795 53412 26795 53413 25156 53413 26811 53413 26795 53414 26811 53414 26810 53414 26810 53415 26811 53415 26812 53415 26810 53416 26812 53416 26797 53416 26797 53417 26812 53417 26813 53417 26797 53418 26813 53418 26814 53418 26814 53419 26813 53419 26815 53419 26814 53420 26815 53420 26799 53420 26799 53421 26815 53421 26817 53421 26799 53422 26817 53422 26816 53422 26816 53423 26817 53423 25159 53423 26816 53424 25159 53424 26818 53424 26818 53425 25159 53425 25161 53425 26818 53426 25161 53426 26800 53426 26800 53427 25161 53427 25162 53427 26800 53428 25162 53428 26819 53428 26819 53429 25162 53429 26820 53429 26819 53430 26820 53430 26821 53430 26821 53431 26820 53431 26822 53431 26821 53432 26822 53432 26823 53432 26823 53433 26822 53433 25165 53433 26823 53434 25165 53434 26825 53434 26825 53435 25165 53435 26824 53435 26825 53436 26824 53436 26826 53436 26826 53437 26824 53437 25167 53437 26826 53438 25167 53438 26804 53438 26804 53439 25167 53439 26827 53439 26804 53440 26827 53440 26828 53440 26828 53441 26827 53441 26829 53441 26828 53442 26829 53442 26805 53442 26805 53443 26829 53443 21327 53443 26863 53444 21996 53444 25160 53444 25160 53445 21996 53445 26831 53445 25160 53446 26831 53446 26830 53446 26830 53447 26831 53447 26832 53447 26830 53448 26832 53448 25163 53448 25163 53449 26832 53449 26833 53449 25163 53450 26833 53450 26834 53450 26834 53451 26833 53451 26835 53451 26834 53452 26835 53452 25164 53452 25164 53453 26835 53453 21998 53453 25164 53454 21998 53454 25166 53454 25166 53455 21998 53455 26836 53455 25166 53456 26836 53456 26837 53456 26837 53457 26836 53457 22001 53457 26837 53458 22001 53458 26838 53458 26838 53459 22001 53459 22003 53459 26838 53460 22003 53460 25168 53460 25168 53461 22003 53461 26840 53461 25168 53462 26840 53462 26839 53462 26839 53463 26840 53463 22005 53463 26839 53464 22005 53464 25169 53464 25169 53465 22005 53465 25142 53465 25169 53466 25142 53466 26841 53466 26841 53467 25142 53467 26842 53467 26841 53468 26842 53468 26843 53468 26843 53469 26842 53469 25144 53469 26843 53470 25144 53470 21973 53470 21973 53471 25144 53471 26844 53471 21973 53472 26844 53472 21974 53472 21974 53473 26844 53473 26845 53473 21974 53474 26845 53474 21976 53474 21976 53475 26845 53475 25145 53475 21976 53476 25145 53476 21977 53476 21977 53477 25145 53477 25146 53477 21977 53478 25146 53478 26846 53478 26846 53479 25146 53479 26847 53479 26846 53480 26847 53480 26848 53480 26848 53481 26847 53481 25148 53481 26848 53482 25148 53482 26849 53482 26849 53483 25148 53483 26850 53483 26849 53484 26850 53484 21979 53484 21979 53485 26850 53485 25150 53485 21979 53486 25150 53486 21980 53486 21980 53487 25150 53487 26851 53487 21980 53488 26851 53488 26852 53488 26852 53489 26851 53489 26853 53489 26852 53490 26853 53490 21981 53490 21981 53491 26853 53491 26854 53491 21981 53492 26854 53492 21985 53492 21985 53493 26854 53493 26855 53493 21985 53494 26855 53494 21986 53494 21986 53495 26855 53495 25151 53495 21986 53496 25151 53496 21987 53496 21987 53497 25151 53497 25152 53497 21987 53498 25152 53498 21990 53498 21990 53499 25152 53499 25153 53499 21990 53500 25153 53500 26856 53500 26856 53501 25153 53501 25154 53501 26856 53502 25154 53502 26857 53502 26857 53503 25154 53503 26858 53503 26857 53504 26858 53504 26859 53504 26859 53505 26858 53505 21991 53505 26859 53506 21991 53506 26860 53506 26860 53507 21991 53507 21992 53507 26860 53508 21992 53508 25157 53508 25157 53509 21992 53509 26861 53509 25157 53510 26861 53510 26862 53510 26862 53511 26861 53511 21994 53511 26862 53512 21994 53512 25158 53512 25158 53513 21994 53513 21995 53513 25158 53514 21995 53514 26863 53514 26863 53515 21995 53515 21996 53515 26864 53516 21510 53516 26865 53516 26864 53517 26865 53517 26866 53517 26866 53518 26865 53518 21518 53518 26866 53519 21518 53519 26867 53519 26871 53520 21443 53520 26868 53520 26871 53521 26868 53521 26864 53521 26864 53522 26868 53522 26869 53522 26864 53523 26869 53523 21510 53523 26873 53524 26870 53524 26874 53524 26874 53525 26870 53525 21442 53525 26874 53526 21442 53526 26871 53526 26871 53527 21442 53527 26872 53527 26871 53528 26872 53528 21443 53528 26873 53529 26874 53529 21439 53529 21439 53530 26874 53530 26875 53530 21439 53531 26875 53531 21438 53531 26880 53532 26876 53532 21436 53532 26880 53533 21436 53533 26875 53533 26875 53534 21436 53534 26877 53534 26875 53535 26877 53535 21438 53535 26878 53536 21435 53536 26882 53536 26882 53537 21435 53537 26879 53537 26882 53538 26879 53538 26880 53538 26880 53539 26879 53539 26881 53539 26880 53540 26881 53540 26876 53540 26878 53541 26882 53541 21434 53541 21434 53542 26882 53542 26884 53542 21434 53543 26884 53543 26886 53543 21430 53544 21431 53544 25149 53544 25149 53545 21431 53545 26883 53545 25149 53546 26883 53546 26884 53546 26884 53547 26883 53547 26885 53547 26884 53548 26885 53548 26886 53548 21430 53549 25149 53549 26887 53549 26887 53550 25149 53550 26888 53550 26887 53551 26888 53551 21426 53551 26889 53552 21421 53552 25147 53552 25147 53553 21421 53553 21424 53553 25147 53554 21424 53554 26888 53554 26888 53555 21424 53555 21425 53555 26888 53556 21425 53556 21426 53556 26889 53557 25147 53557 21420 53557 21420 53558 25147 53558 26890 53558 21420 53559 26890 53559 21418 53559 26892 53560 21415 53560 21416 53560 26892 53561 21416 53561 26890 53561 26890 53562 21416 53562 21417 53562 26890 53563 21417 53563 21418 53563 21411 53564 21412 53564 26894 53564 26894 53565 21412 53565 26891 53565 26894 53566 26891 53566 26892 53566 26892 53567 26891 53567 26893 53567 26892 53568 26893 53568 21415 53568 21411 53569 26894 53569 21409 53569 21409 53570 26894 53570 26899 53570 21409 53571 26899 53571 26895 53571 21405 53572 26896 53572 26897 53572 26897 53573 26896 53573 26898 53573 26897 53574 26898 53574 26899 53574 26899 53575 26898 53575 21408 53575 26899 53576 21408 53576 26895 53576 21405 53577 26897 53577 26900 53577 26900 53578 26897 53578 26901 53578 26900 53579 26901 53579 21404 53579 26904 53580 21401 53580 26905 53580 26905 53581 21401 53581 26902 53581 26905 53582 26902 53582 26901 53582 26901 53583 26902 53583 26903 53583 26901 53584 26903 53584 21404 53584 26904 53585 26905 53585 21399 53585 21399 53586 26905 53586 25143 53586 21399 53587 25143 53587 21287 53587 25140 53588 22032 53588 26906 53588 26906 53589 22032 53589 26908 53589 26906 53590 26908 53590 26907 53590 26907 53591 26908 53591 26910 53591 26907 53592 26910 53592 26909 53592 26909 53593 26910 53593 25112 53593 26909 53594 25112 53594 26911 53594 26911 53595 25112 53595 26912 53595 26911 53596 26912 53596 25136 53596 25136 53597 26912 53597 26913 53597 25136 53598 26913 53598 26914 53598 26914 53599 26913 53599 26915 53599 26914 53600 26915 53600 25133 53600 25133 53601 26915 53601 26916 53601 25133 53602 26916 53602 25130 53602 25130 53603 26916 53603 26917 53603 25130 53604 26917 53604 26918 53604 26918 53605 26917 53605 26920 53605 26918 53606 26920 53606 26919 53606 26919 53607 26920 53607 25116 53607 26919 53608 25116 53608 26921 53608 26921 53609 25116 53609 25118 53609 26921 53610 25118 53610 26922 53610 26922 53611 25118 53611 25119 53611 26922 53612 25119 53612 25128 53612 25128 53613 25119 53613 25121 53613 25128 53614 25121 53614 25126 53614 25126 53615 25121 53615 25122 53615 25126 53616 25122 53616 26923 53616 26923 53617 25122 53617 26924 53617 26923 53618 26924 53618 22019 53618 22019 53619 26924 53619 21267 53619 26136 53620 26925 53620 26134 53620 26134 53621 26925 53621 26926 53621 26134 53622 26926 53622 26927 53622 26927 53623 26926 53623 25171 53623 26927 53624 25171 53624 26928 53624 26928 53625 25171 53625 26929 53625 26928 53626 26929 53626 26930 53626 26930 53627 26929 53627 26931 53627 26930 53628 26931 53628 26932 53628 26932 53629 26931 53629 26934 53629 26932 53630 26934 53630 26933 53630 26933 53631 26934 53631 25173 53631 26933 53632 25173 53632 26935 53632 26935 53633 25173 53633 26936 53633 26935 53634 26936 53634 26130 53634 26130 53635 26936 53635 26937 53635 26130 53636 26937 53636 26128 53636 26128 53637 26937 53637 26938 53637 26128 53638 26938 53638 26939 53638 26939 53639 26938 53639 26940 53639 26939 53640 26940 53640 26941 53640 26941 53641 26940 53641 25176 53641 26941 53642 25176 53642 26942 53642 26942 53643 25176 53643 25179 53643 26942 53644 25179 53644 26943 53644 26943 53645 25179 53645 25180 53645 26943 53646 25180 53646 26944 53646 26944 53647 25180 53647 25182 53647 26944 53648 25182 53648 26945 53648 26945 53649 25182 53649 26947 53649 26945 53650 26947 53650 26946 53650 26946 53651 26947 53651 26948 53651 26946 53652 26948 53652 26949 53652 26949 53653 26948 53653 21252 53653 26775 53654 26112 53654 26950 53654 26950 53655 26112 53655 26113 53655 26950 53656 26113 53656 26777 53656 26777 53657 26113 53657 26114 53657 26777 53658 26114 53658 26951 53658 26951 53659 26114 53659 26952 53659 26951 53660 26952 53660 26778 53660 26778 53661 26952 53661 26953 53661 26778 53662 26953 53662 26954 53662 26954 53663 26953 53663 26955 53663 26954 53664 26955 53664 26956 53664 26956 53665 26955 53665 26116 53665 26956 53666 26116 53666 26957 53666 26957 53667 26116 53667 26119 53667 26957 53668 26119 53668 26958 53668 26958 53669 26119 53669 26959 53669 26958 53670 26959 53670 26758 53670 26758 53671 26959 53671 26120 53671 26758 53672 26120 53672 26960 53672 26960 53673 26120 53673 26962 53673 26960 53674 26962 53674 26961 53674 26961 53675 26962 53675 26121 53675 26961 53676 26121 53676 26963 53676 26963 53677 26121 53677 26123 53677 26963 53678 26123 53678 26964 53678 26964 53679 26123 53679 26965 53679 26964 53680 26965 53680 26761 53680 26761 53681 26965 53681 26966 53681 26761 53682 26966 53682 26762 53682 26762 53683 26966 53683 26967 53683 26762 53684 26967 53684 26968 53684 26968 53685 26967 53685 26969 53685 26968 53686 26969 53686 26763 53686 26763 53687 26969 53687 21233 53687 26970 53688 25731 53688 26971 53688 26971 53689 25731 53689 26978 53689 26970 53690 26971 53690 25726 53690 25726 53691 26971 53691 25809 53691 25726 53692 25809 53692 26972 53692 25807 53693 26973 53693 26976 53693 26976 53694 26973 53694 26974 53694 25809 53695 26975 53695 26972 53695 26972 53696 26975 53696 26976 53696 26972 53697 26976 53697 25732 53697 25732 53698 26976 53698 26974 53698 25731 53699 26977 53699 26978 53699 26978 53700 26977 53700 26058 53700 26978 53701 26058 53701 26979 53701 26979 53702 26058 53702 26057 53702 26979 53703 26057 53703 21859 53703 21859 53704 26057 53704 26980 53704 21859 53705 26980 53705 21862 53705 21862 53706 26980 53706 26982 53706 21862 53707 26982 53707 26981 53707 26981 53708 26982 53708 26052 53708 26981 53709 26052 53709 26983 53709 26983 53710 26052 53710 26048 53710 26983 53711 26048 53711 26984 53711 26984 53712 26048 53712 26985 53712 26984 53713 26985 53713 25807 53713 25807 53714 26985 53714 26986 53714 25807 53715 26986 53715 26973 53715 24573 53716 26987 53716 27165 53716 24573 53717 27165 53717 26988 53717 26988 53718 27165 53718 27167 53718 26988 53719 27167 53719 24571 53719 24571 53720 27167 53720 27160 53720 24571 53721 27160 53721 24570 53721 24570 53722 27160 53722 26989 53722 24570 53723 26989 53723 24568 53723 24568 53724 26989 53724 27171 53724 24568 53725 27171 53725 24567 53725 24567 53726 27171 53726 27158 53726 24567 53727 27158 53727 26990 53727 26990 53728 27158 53728 26991 53728 26990 53729 26991 53729 24565 53729 24565 53730 26991 53730 27175 53730 24565 53731 27175 53731 24564 53731 24564 53732 27175 53732 27176 53732 24564 53733 27176 53733 26992 53733 26992 53734 27176 53734 26993 53734 26992 53735 26993 53735 24562 53735 24562 53736 26993 53736 27181 53736 24562 53737 27181 53737 24559 53737 24559 53738 27181 53738 26994 53738 24559 53739 26994 53739 24558 53739 24558 53740 26994 53740 27156 53740 24558 53741 27156 53741 24556 53741 24556 53742 27156 53742 27183 53742 24556 53743 27183 53743 26995 53743 26995 53744 27183 53744 27187 53744 26995 53745 27187 53745 26996 53745 26996 53746 27187 53746 26997 53746 26996 53747 26997 53747 26998 53747 26998 53748 26997 53748 27152 53748 26998 53749 27152 53749 25045 53749 22086 53750 27201 53750 27203 53750 22086 53751 27203 53751 24551 53751 24551 53752 27203 53752 26999 53752 24551 53753 26999 53753 27000 53753 27000 53754 26999 53754 27200 53754 27000 53755 27200 53755 27001 53755 27001 53756 27200 53756 27003 53756 27001 53757 27003 53757 27002 53757 27002 53758 27003 53758 27004 53758 27002 53759 27004 53759 24548 53759 24548 53760 27004 53760 27208 53760 24548 53761 27208 53761 27005 53761 27005 53762 27208 53762 27006 53762 27005 53763 27006 53763 24546 53763 24546 53764 27006 53764 27007 53764 24546 53765 27007 53765 24545 53765 24545 53766 27007 53766 27197 53766 24545 53767 27197 53767 24544 53767 24544 53768 27197 53768 27198 53768 24544 53769 27198 53769 24541 53769 24541 53770 27198 53770 27209 53770 24541 53771 27209 53771 24540 53771 24540 53772 27209 53772 27193 53772 24540 53773 27193 53773 27008 53773 27008 53774 27193 53774 27009 53774 27008 53775 27009 53775 24538 53775 24538 53776 27009 53776 27192 53776 24538 53777 27192 53777 27010 53777 27010 53778 27192 53778 27011 53778 27010 53779 27011 53779 24536 53779 24536 53780 27011 53780 27212 53780 24536 53781 27212 53781 24534 53781 24534 53782 27212 53782 25057 53782 24534 53783 25057 53783 24533 53783 21129 53784 27012 53784 21128 53784 21128 53785 27012 53785 27013 53785 21128 53786 27013 53786 25020 53786 27014 53787 25330 53787 27191 53787 27191 53788 25330 53788 27120 53788 27191 53789 27120 53789 24993 53789 25461 53790 25460 53790 27015 53790 27015 53791 25460 53791 27016 53791 27015 53792 27016 53792 27017 53792 25440 53793 25647 53793 27037 53793 27037 53794 25647 53794 27018 53794 27037 53795 27018 53795 24992 53795 24985 53796 24984 53796 27032 53796 24990 53797 27019 53797 27020 53797 27020 53798 27019 53798 24987 53798 27020 53799 24987 53799 24986 53799 24985 53800 27032 53800 24986 53800 24986 53801 27032 53801 27037 53801 24986 53802 27037 53802 27020 53802 27020 53803 27037 53803 24992 53803 27020 53804 24992 53804 24990 53804 24984 53805 24982 53805 27032 53805 27032 53806 24982 53806 27021 53806 27032 53807 27021 53807 21515 53807 21205 53808 27022 53808 24978 53808 24978 53809 27022 53809 21515 53809 24978 53810 21515 53810 24983 53810 24983 53811 21515 53811 27021 53811 27150 53812 27149 53812 27023 53812 27023 53813 27149 53813 27024 53813 27024 53814 25410 53814 27023 53814 27023 53815 25410 53815 27025 53815 27023 53816 27025 53816 27150 53816 27150 53817 27025 53817 27026 53817 27027 53818 25427 53818 21478 53818 21478 53819 25427 53819 25426 53819 25426 53820 27028 53820 21478 53820 21478 53821 27028 53821 27029 53821 21478 53822 27029 53822 25425 53822 25425 53823 27030 53823 21478 53823 21478 53824 27030 53824 25421 53824 21478 53825 25421 53825 21480 53825 25421 53826 25422 53826 21480 53826 21480 53827 25422 53827 27031 53827 21480 53828 27031 53828 27032 53828 27032 53829 27031 53829 27033 53829 27032 53830 27033 53830 25423 53830 25423 53831 27034 53831 27032 53831 27032 53832 27034 53832 25418 53832 27032 53833 25418 53833 27037 53833 27037 53834 25418 53834 27035 53834 27037 53835 27035 53835 25420 53835 25444 53836 27036 53836 27038 53836 27038 53837 27036 53837 27039 53837 25420 53838 25444 53838 27037 53838 27037 53839 25444 53839 27038 53839 27037 53840 27038 53840 25440 53840 25440 53841 27038 53841 27039 53841 25440 53842 27039 53842 25442 53842 25364 53843 21471 53843 27040 53843 27040 53844 21471 53844 25366 53844 25361 53845 27043 53845 27041 53845 27041 53846 27043 53846 21471 53846 27041 53847 21471 53847 25363 53847 25363 53848 21471 53848 25364 53848 25357 53849 27143 53849 27042 53849 27042 53850 27143 53850 27043 53850 27042 53851 27043 53851 25360 53851 25360 53852 27043 53852 25361 53852 25351 53853 25354 53853 27045 53853 27045 53854 25354 53854 25355 53854 25391 53855 25390 53855 27044 53855 27044 53856 25390 53856 27047 53856 25355 53857 25391 53857 27045 53857 27045 53858 25391 53858 27044 53858 27045 53859 27044 53859 27046 53859 27046 53860 27044 53860 27047 53860 27046 53861 27047 53861 25388 53861 27048 53862 27049 53862 25341 53862 27049 53863 27048 53863 25335 53863 27142 53864 25337 53864 27141 53864 25365 53865 25372 53865 27050 53865 27050 53866 25372 53866 25370 53866 27050 53867 25370 53867 21470 53867 21470 53868 25370 53868 25368 53868 21470 53869 25368 53869 21471 53869 21471 53870 25368 53870 27051 53870 21471 53871 27051 53871 25366 53871 27071 53872 27052 53872 27069 53872 27069 53873 27052 53873 27055 53873 27053 53874 27137 53874 27054 53874 27054 53875 27137 53875 27055 53875 27054 53876 27055 53876 27056 53876 27056 53877 27055 53877 27052 53877 25289 53878 25287 53878 27138 53878 27138 53879 25287 53879 25316 53879 27057 53880 25322 53880 27058 53880 27058 53881 25322 53881 27059 53881 25316 53882 27057 53882 27138 53882 27138 53883 27057 53883 27058 53883 27138 53884 27058 53884 25318 53884 25318 53885 27058 53885 27059 53885 25318 53886 27059 53886 25319 53886 27064 53887 25276 53887 27060 53887 25276 53888 27064 53888 27063 53888 25274 53889 25272 53889 27061 53889 25299 53890 27062 53890 25300 53890 25300 53891 27062 53891 27063 53891 25300 53892 27063 53892 27061 53892 27061 53893 27063 53893 27064 53893 27061 53894 27064 53894 25274 53894 25274 53895 27064 53895 27060 53895 25299 53896 25301 53896 27062 53896 27062 53897 25301 53897 27065 53897 27062 53898 27065 53898 27066 53898 27066 53899 27065 53899 27067 53899 27066 53900 27067 53900 25292 53900 25292 53901 27068 53901 27066 53901 27066 53902 27068 53902 27070 53902 27066 53903 27070 53903 27069 53903 27069 53904 27070 53904 25296 53904 27069 53905 25296 53905 27071 53905 25220 53906 25218 53906 21459 53906 21459 53907 25218 53907 21461 53907 25217 53908 25215 53908 25260 53908 25260 53909 25215 53909 27074 53909 27072 53910 27073 53910 27075 53910 27075 53911 27073 53911 25252 53911 27074 53912 27072 53912 25260 53912 25260 53913 27072 53913 27075 53913 25260 53914 27075 53914 27076 53914 27076 53915 27075 53915 25252 53915 27076 53916 25252 53916 25251 53916 25212 53917 27133 53917 27077 53917 27077 53918 27133 53918 27078 53918 27078 53919 25203 53919 27077 53919 27077 53920 25203 53920 27079 53920 27077 53921 27079 53921 25212 53921 25212 53922 27079 53922 25206 53922 27134 53923 25231 53923 21457 53923 21457 53924 25231 53924 25229 53924 25229 53925 25228 53925 21457 53925 21457 53926 25228 53926 27080 53926 21457 53927 27080 53927 27081 53927 27081 53928 27080 53928 27082 53928 27081 53929 27082 53929 25227 53929 25227 53930 27083 53930 27081 53930 27081 53931 27083 53931 27084 53931 27081 53932 27084 53932 27085 53932 27085 53933 27084 53933 27086 53933 27086 53934 25223 53934 27085 53934 27085 53935 25223 53935 25222 53935 27085 53936 25222 53936 21459 53936 21459 53937 25222 53937 27087 53937 21459 53938 27087 53938 25220 53938 25202 53939 27089 53939 27088 53939 27088 53940 27089 53940 25211 53940 27088 53941 25211 53941 27090 53941 27091 53942 25247 53942 27092 53942 27092 53943 25247 53943 27093 53943 27092 53944 27093 53944 25202 53944 25202 53945 27093 53945 27094 53945 25202 53946 27094 53946 27089 53946 27089 53947 27094 53947 27095 53947 27089 53948 27095 53948 25211 53948 27129 53949 25269 53949 27096 53949 27096 53950 25269 53950 27097 53950 27097 53951 25259 53951 27096 53951 27096 53952 25259 53952 25256 53952 27096 53953 25256 53953 27129 53953 27129 53954 25256 53954 27098 53954 25232 53955 25235 53955 21451 53955 21451 53956 25235 53956 25236 53956 25236 53957 25237 53957 21451 53957 21451 53958 25237 53958 27099 53958 21451 53959 27099 53959 27100 53959 27100 53960 27099 53960 27101 53960 27100 53961 27101 53961 27104 53961 25242 53962 27102 53962 27103 53962 27103 53963 27102 53963 27100 53963 27103 53964 27100 53964 25239 53964 25239 53965 27100 53965 27104 53965 27105 53966 25330 53966 25323 53966 25330 53967 27105 53967 27120 53967 27106 53968 25326 53968 25328 53968 27109 53969 27107 53969 27108 53969 27109 53970 27108 53970 27110 53970 25323 53971 27106 53971 27105 53971 27105 53972 27106 53972 25328 53972 27105 53973 25328 53973 27120 53973 27120 53974 25328 53974 25317 53974 27120 53975 25317 53975 27108 53975 27108 53976 25317 53976 25304 53976 27108 53977 25304 53977 27110 53977 27107 53978 27111 53978 27108 53978 27108 53979 27111 53979 27112 53979 27108 53980 27112 53980 21447 53980 25310 53981 27124 53981 25309 53981 25309 53982 27124 53982 21447 53982 25309 53983 21447 53983 25308 53983 25308 53984 21447 53984 27112 53984 25310 53985 25312 53985 27124 53985 27124 53986 25312 53986 25313 53986 27124 53987 25313 53987 25314 53987 27123 53988 27115 53988 27125 53988 27113 53989 25282 53989 27114 53989 27114 53990 25282 53990 25280 53990 27115 53991 27113 53991 27125 53991 27125 53992 27113 53992 27114 53992 27125 53993 27114 53993 27116 53993 27116 53994 27114 53994 25280 53994 27116 53995 25280 53995 25279 53995 21445 53996 22087 53996 27117 53996 27117 53997 22087 53997 25001 53997 27117 53998 25001 53998 27108 53998 25001 53999 27118 53999 27108 53999 27108 54000 27118 54000 27119 54000 27108 54001 27119 54001 25003 54001 27120 54002 27122 54002 24993 54002 24993 54003 27122 54003 24995 54003 24993 54004 24995 54004 24994 54004 25003 54005 24999 54005 27108 54005 27108 54006 24999 54006 24998 54006 27108 54007 24998 54007 27120 54007 27120 54008 24998 54008 27121 54008 27120 54009 27121 54009 27122 54009 27122 54010 27121 54010 24996 54010 27122 54011 24996 54011 24995 54011 25314 54012 27123 54012 27124 54012 27124 54013 27123 54013 27125 54013 27124 54014 27125 54014 21448 54014 21448 54015 27125 54015 27126 54015 21448 54016 27126 54016 27127 54016 27127 54017 27126 54017 27128 54017 27127 54018 27128 54018 21450 54018 21450 54019 27128 54019 25268 54019 21450 54020 25268 54020 21451 54020 21451 54021 25268 54021 25269 54021 21451 54022 25269 54022 25232 54022 25232 54023 25269 54023 27129 54023 25242 54024 25244 54024 27102 54024 27102 54025 25244 54025 27130 54025 27102 54026 27130 54026 21453 54026 21453 54027 27130 54027 27091 54027 21453 54028 27091 54028 27131 54028 27131 54029 27091 54029 27092 54029 27131 54030 27092 54030 27132 54030 27132 54031 27092 54031 25200 54031 27132 54032 25200 54032 21457 54032 21457 54033 25200 54033 27133 54033 21457 54034 27133 54034 27134 54034 27134 54035 27133 54035 25212 54035 25218 54036 25217 54036 21461 54036 21461 54037 25217 54037 25260 54037 21461 54038 25260 54038 21462 54038 21462 54039 25260 54039 27135 54039 21462 54040 27135 54040 27062 54040 27062 54041 27135 54041 27136 54041 27062 54042 27136 54042 27063 54042 27053 54043 25289 54043 27137 54043 27137 54044 25289 54044 27138 54044 27137 54045 27138 54045 27140 54045 27140 54046 27138 54046 27139 54046 27140 54047 27139 54047 27050 54047 27050 54048 27139 54048 25334 54048 27050 54049 25334 54049 25365 54049 25365 54050 25334 54050 25335 54050 25365 54051 25335 54051 27141 54051 27141 54052 25335 54052 27048 54052 27141 54053 27048 54053 27142 54053 27142 54054 27048 54054 25341 54054 25357 54055 25351 54055 27143 54055 27143 54056 25351 54056 27045 54056 27143 54057 27045 54057 21474 54057 21474 54058 27045 54058 27144 54058 21474 54059 27144 54059 27145 54059 27145 54060 27144 54060 27147 54060 27145 54061 27147 54061 27146 54061 27146 54062 27147 54062 27148 54062 27146 54063 27148 54063 21478 54063 21478 54064 27148 54064 27149 54064 21478 54065 27149 54065 27027 54065 27027 54066 27149 54066 27150 54066 27164 54067 25722 54067 27166 54067 27182 54068 25524 54068 25523 54068 25461 54069 27015 54069 27151 54069 27151 54070 27015 54070 27152 54070 27151 54071 27152 54071 27186 54071 27186 54072 27152 54072 26997 54072 27182 54073 27183 54073 27156 54073 27154 54074 25579 54074 27155 54074 27153 54075 27154 54075 26994 54075 26994 54076 27154 54076 27155 54076 26994 54077 27155 54077 27156 54077 27156 54078 27155 54078 25597 54078 27156 54079 25597 54079 27182 54079 27181 54080 26993 54080 27157 54080 27157 54081 26993 54081 26063 54081 26063 54082 26993 54082 26060 54082 26060 54083 26993 54083 27176 54083 26060 54084 27176 54084 26066 54084 25517 54085 27173 54085 27159 54085 27159 54086 27173 54086 27175 54086 27159 54087 27175 54087 26991 54087 25449 54088 25741 54088 27158 54088 27158 54089 25741 54089 25739 54089 27158 54090 25739 54090 26991 54090 26991 54091 25739 54091 25627 54091 26991 54092 25627 54092 27159 54092 27169 54093 27171 54093 26989 54093 27169 54094 25738 54094 27170 54094 25401 54095 27161 54095 27160 54095 27160 54096 27161 54096 27162 54096 27160 54097 27162 54097 26989 54097 26989 54098 27162 54098 25626 54098 26989 54099 25626 54099 27169 54099 27013 54100 27012 54100 26987 54100 26987 54101 27012 54101 27163 54101 26987 54102 27163 54102 27165 54102 27163 54103 27164 54103 27165 54103 27165 54104 27164 54104 27166 54104 27165 54105 27166 54105 27167 54105 27166 54106 27168 54106 27167 54106 27167 54107 27168 54107 25404 54107 27167 54108 25404 54108 27160 54108 27160 54109 25404 54109 25402 54109 27160 54110 25402 54110 25401 54110 27169 54111 27170 54111 27171 54111 27171 54112 27170 54112 27172 54112 27171 54113 27172 54113 27158 54113 27158 54114 27172 54114 25451 54114 27158 54115 25451 54115 25449 54115 27173 54116 27174 54116 27175 54116 27175 54117 27174 54117 27177 54117 27175 54118 27177 54118 27176 54118 27176 54119 27177 54119 27178 54119 27176 54120 27178 54120 26066 54120 27153 54121 26994 54121 27179 54121 27179 54122 26994 54122 27181 54122 27179 54123 27181 54123 27180 54123 27180 54124 27181 54124 27157 54124 27180 54125 27157 54125 26076 54125 27182 54126 25523 54126 27183 54126 27183 54127 25523 54127 27184 54127 27183 54128 27184 54128 27187 54128 25642 54129 27186 54129 27185 54129 27185 54130 27186 54130 26997 54130 27185 54131 26997 54131 25520 54131 25520 54132 26997 54132 27187 54132 25520 54133 27187 54133 25521 54133 25521 54134 27187 54134 27184 54134 27188 54135 25261 54135 27197 54135 27189 54136 21923 54136 25399 54136 25698 54137 25697 54137 25270 54137 27014 54138 27191 54138 27190 54138 27190 54139 27191 54139 25057 54139 27190 54140 25057 54140 27211 54140 27211 54141 25057 54141 27212 54141 25698 54142 27192 54142 27009 54142 25197 54143 25684 54143 27194 54143 25201 54144 25197 54144 27193 54144 27193 54145 25197 54145 27194 54145 27193 54146 27194 54146 27009 54146 27009 54147 27194 54147 25619 54147 27009 54148 25619 54148 25698 54148 27210 54149 27209 54149 27198 54149 25261 54150 27195 54150 27197 54150 27197 54151 27195 54151 27196 54151 27197 54152 27196 54152 27198 54152 27198 54153 27196 54153 25613 54153 27198 54154 25613 54154 27210 54154 21915 54155 27007 54155 27006 54155 25332 54156 25331 54156 27208 54156 27208 54157 25331 54157 27199 54157 27208 54158 27199 54158 27006 54158 27006 54159 27199 54159 25612 54159 27006 54160 25612 54160 21915 54160 25608 54161 27004 54161 27003 54161 25608 54162 25342 54162 27206 54162 25397 54163 25396 54163 27200 54163 27200 54164 25396 54164 25657 54164 27200 54165 25657 54165 27003 54165 27003 54166 25657 54166 25606 54166 27003 54167 25606 54167 25608 54167 27018 54168 25647 54168 27201 54168 27201 54169 25647 54169 27202 54169 27201 54170 27202 54170 27203 54170 27202 54171 27189 54171 27203 54171 27203 54172 27189 54172 25399 54172 27203 54173 25399 54173 26999 54173 25399 54174 27204 54174 26999 54174 26999 54175 27204 54175 25398 54175 26999 54176 25398 54176 27200 54176 27200 54177 25398 54177 27205 54177 27200 54178 27205 54178 25397 54178 25608 54179 27206 54179 27004 54179 27004 54180 27206 54180 27207 54180 27004 54181 27207 54181 27208 54181 27208 54182 27207 54182 25333 54182 27208 54183 25333 54183 25332 54183 27188 54184 27197 54184 25262 54184 25262 54185 27197 54185 27007 54185 25262 54186 27007 54186 25264 54186 25264 54187 27007 54187 21915 54187 25264 54188 21915 54188 25263 54188 25201 54189 27193 54189 25199 54189 25199 54190 27193 54190 27209 54190 25199 54191 27209 54191 25198 54191 25198 54192 27209 54192 27210 54192 25198 54193 27210 54193 25683 54193 25698 54194 25270 54194 27192 54194 27192 54195 25270 54195 25267 54195 27192 54196 25267 54196 27011 54196 25277 54197 27211 54197 25265 54197 25265 54198 27211 54198 27212 54198 25265 54199 27212 54199 25266 54199 25266 54200 27212 54200 27011 54200 25266 54201 27011 54201 27213 54201 27213 54202 27011 54202 25267 54202 27251 54203 27214 54203 22238 54203 22238 54204 27214 54204 22237 54204 22237 54205 27214 54205 24103 54205 22237 54206 24103 54206 27215 54206 27216 54207 22233 54207 27220 54207 24103 54208 24104 54208 27215 54208 27215 54209 24104 54209 27217 54209 27215 54210 27217 54210 22234 54210 22234 54211 27217 54211 27218 54211 22234 54212 27218 54212 22233 54212 22233 54213 27218 54213 27219 54213 22233 54214 27219 54214 27220 54214 27220 54215 27219 54215 27223 54215 27220 54216 27223 54216 24119 54216 24119 54217 27223 54217 27222 54217 24737 54218 24736 54218 27251 54218 24741 54219 27222 54219 27221 54219 27221 54220 27222 54220 27223 54220 27221 54221 27223 54221 27224 54221 27224 54222 27223 54222 24099 54222 27251 54223 24108 54223 27225 54223 24737 54224 27251 54224 24734 54224 24734 54225 27251 54225 27225 54225 24734 54226 27225 54226 27226 54226 22510 54227 24722 54227 22509 54227 22509 54228 24722 54228 24723 54228 22509 54229 24723 54229 27227 54229 27227 54230 24723 54230 27228 54230 27227 54231 27228 54231 27230 54231 27230 54232 27228 54232 27229 54232 27230 54233 27229 54233 27231 54233 27231 54234 27229 54234 27233 54234 27231 54235 27233 54235 27232 54235 27232 54236 27233 54236 27234 54236 27232 54237 27234 54237 22505 54237 22505 54238 27234 54238 27235 54238 22505 54239 27235 54239 27239 54239 27220 54240 24118 54240 27216 54240 27216 54241 24118 54241 27237 54241 27216 54242 27237 54242 27236 54242 27236 54243 27237 54243 24113 54243 27235 54244 27238 54244 27239 54244 27239 54245 27238 54245 27240 54245 27239 54246 27240 54246 22503 54246 22503 54247 27240 54247 24726 54247 22503 54248 24726 54248 27241 54248 27241 54249 24726 54249 27242 54249 27241 54250 27242 54250 27243 54250 27243 54251 27242 54251 27244 54251 27243 54252 27244 54252 22501 54252 22501 54253 27244 54253 27245 54253 22501 54254 27245 54254 24115 54254 24115 54255 27245 54255 22227 54255 24115 54256 22227 54256 24114 54256 24114 54257 22227 54257 27246 54257 24114 54258 27246 54258 27248 54258 27248 54259 27246 54259 27247 54259 27248 54260 27247 54260 27249 54260 27249 54261 27247 54261 22230 54261 27249 54262 22230 54262 24113 54262 24113 54263 22230 54263 22231 54263 24113 54264 22231 54264 27236 54264 24108 54265 27251 54265 27250 54265 27250 54266 27251 54266 22238 54266 27250 54267 22238 54267 24110 54267 24110 54268 22238 54268 22239 54268 24110 54269 22239 54269 22500 54269 22500 54270 22239 54270 27252 54270 22500 54271 27252 54271 22499 54271 22499 54272 27252 54272 22241 54272 22499 54273 22241 54273 27253 54273 27253 54274 22241 54274 22243 54274 27253 54275 22243 54275 22498 54275 22498 54276 22243 54276 22244 54276 22498 54277 22244 54277 27254 54277 27254 54278 22244 54278 22245 54278 27254 54279 22245 54279 27255 54279 27255 54280 22245 54280 27256 54280 27255 54281 27256 54281 22514 54281 22514 54282 27256 54282 27257 54282 22514 54283 27257 54283 22513 54283 22513 54284 27257 54284 24720 54284 22513 54285 24720 54285 27259 54285 27259 54286 24720 54286 27258 54286 27259 54287 27258 54287 22510 54287 22510 54288 27258 54288 24721 54288 22510 54289 24721 54289 24722 54289 21108 54290 21109 54290 27265 54290 27264 54291 27266 54291 21108 54291 27268 54292 27269 54292 21108 54292 27263 54293 27270 54293 21108 54293 27262 54294 27272 54294 21108 54294 21108 54295 27274 54295 27260 54295 27261 54296 27274 54296 21108 54296 27272 54297 27261 54297 21108 54297 27270 54298 27262 54298 21108 54298 27269 54299 27263 54299 21108 54299 27266 54300 27268 54300 21108 54300 27265 54301 27264 54301 21108 54301 21109 54302 27285 54302 27265 54302 27265 54303 27285 54303 27284 54303 27265 54304 27284 54304 27264 54304 27264 54305 27284 54305 27266 54305 27266 54306 27284 54306 27267 54306 27266 54307 27267 54307 27268 54307 27268 54308 27267 54308 27269 54308 27269 54309 27267 54309 27271 54309 27269 54310 27271 54310 27263 54310 27263 54311 27271 54311 27270 54311 27270 54312 27271 54312 27282 54312 27270 54313 27282 54313 27262 54313 27262 54314 27282 54314 27272 54314 27272 54315 27282 54315 27273 54315 27272 54316 27273 54316 27261 54316 27261 54317 27273 54317 27274 54317 27274 54318 27273 54318 21099 54318 27274 54319 21099 54319 27260 54319 27275 54320 21101 54320 27289 54320 27289 54321 21101 54321 27277 54321 27289 54322 27277 54322 27276 54322 27276 54323 27277 54323 27278 54323 27276 54324 27278 54324 22735 54324 22735 54325 27278 54325 27279 54325 22735 54326 27279 54326 22736 54326 22736 54327 27279 54327 21099 54327 22736 54328 21099 54328 27280 54328 27280 54329 21099 54329 27273 54329 27280 54330 27273 54330 27281 54330 27281 54331 27273 54331 27282 54331 27281 54332 27282 54332 23772 54332 23772 54333 27282 54333 27271 54333 23772 54334 27271 54334 27283 54334 27283 54335 27271 54335 27267 54335 27283 54336 27267 54336 23775 54336 23775 54337 27267 54337 27284 54337 23775 54338 27284 54338 23776 54338 23776 54339 27284 54339 27285 54339 23776 54340 27285 54340 27286 54340 27286 54341 27285 54341 27287 54341 27286 54342 27287 54342 27288 54342 27288 54343 27287 54343 27275 54343 27288 54344 27275 54344 27289 54344 21098 54345 27290 54345 27291 54345 27298 54346 27297 54346 21098 54346 27292 54347 27293 54347 21098 54347 27300 54348 27296 54348 21098 54348 27303 54349 27295 54349 21098 54349 21098 54350 27305 54350 21093 54350 27294 54351 27305 54351 21098 54351 27295 54352 27294 54352 21098 54352 27296 54353 27303 54353 21098 54353 27293 54354 27300 54354 21098 54354 27297 54355 27292 54355 21098 54355 27291 54356 27298 54356 21098 54356 27290 54357 27312 54357 27291 54357 27291 54358 27312 54358 27299 54358 27291 54359 27299 54359 27298 54359 27298 54360 27299 54360 27297 54360 27297 54361 27299 54361 27311 54361 27297 54362 27311 54362 27292 54362 27292 54363 27311 54363 27293 54363 27293 54364 27311 54364 27301 54364 27293 54365 27301 54365 27300 54365 27300 54366 27301 54366 27296 54366 27296 54367 27301 54367 27302 54367 27296 54368 27302 54368 27303 54368 27303 54369 27302 54369 27295 54369 27295 54370 27302 54370 27304 54370 27295 54371 27304 54371 27294 54371 27294 54372 27304 54372 27305 54372 27305 54373 27304 54373 21083 54373 27305 54374 21083 54374 21093 54374 27313 54375 27314 54375 27306 54375 27306 54376 27314 54376 27308 54376 27306 54377 27308 54377 27307 54377 27307 54378 27308 54378 21084 54378 27307 54379 21084 54379 27309 54379 27309 54380 21084 54380 21083 54380 27309 54381 21083 54381 23751 54381 23751 54382 21083 54382 27304 54382 23751 54383 27304 54383 23753 54383 23753 54384 27304 54384 27302 54384 23753 54385 27302 54385 23754 54385 23754 54386 27302 54386 27301 54386 23754 54387 27301 54387 23755 54387 23755 54388 27301 54388 27311 54388 23755 54389 27311 54389 27310 54389 27310 54390 27311 54390 27299 54390 27310 54391 27299 54391 23757 54391 23757 54392 27299 54392 27312 54392 23757 54393 27312 54393 22756 54393 22756 54394 27312 54394 21092 54394 22756 54395 21092 54395 22758 54395 22758 54396 21092 54396 21091 54396 22758 54397 21091 54397 27313 54397 27313 54398 21091 54398 21089 54398 27313 54399 21089 54399 27314 54399 21079 54400 27323 54400 27317 54400 27320 54401 27323 54401 21079 54401 27318 54402 27320 54402 21079 54402 21079 54403 27316 54403 27324 54403 27315 54404 27316 54404 21079 54404 27317 54405 27315 54405 21079 54405 27318 54406 27319 54406 27320 54406 27320 54407 27319 54407 27321 54407 27320 54408 27321 54408 27323 54408 27323 54409 27321 54409 27322 54409 27323 54410 27322 54410 27317 54410 27317 54411 27322 54411 27331 54411 27317 54412 27331 54412 27315 54412 27315 54413 27331 54413 27332 54413 27315 54414 27332 54414 27316 54414 27316 54415 27332 54415 27325 54415 27316 54416 27325 54416 27324 54416 27324 54417 27325 54417 27333 54417 27335 54418 22778 54418 27336 54418 27336 54419 22778 54419 27327 54419 27336 54420 27327 54420 27326 54420 27326 54421 27327 54421 22781 54421 27326 54422 22781 54422 27328 54422 27328 54423 22781 54423 22784 54423 27328 54424 22784 54424 27319 54424 27319 54425 22784 54425 27329 54425 27319 54426 27329 54426 27321 54426 27321 54427 27329 54427 23736 54427 27321 54428 23736 54428 27322 54428 27322 54429 23736 54429 23735 54429 27322 54430 23735 54430 27331 54430 27331 54431 23735 54431 27330 54431 27331 54432 27330 54432 27332 54432 27332 54433 27330 54433 23734 54433 27332 54434 23734 54434 27325 54434 27325 54435 23734 54435 23731 54435 27325 54436 23731 54436 27333 54436 27333 54437 23731 54437 23730 54437 27333 54438 23730 54438 21070 54438 21070 54439 23730 54439 27334 54439 21070 54440 27334 54440 21071 54440 21071 54441 27334 54441 27335 54441 21071 54442 27335 54442 27336 54442 21068 54443 27340 54443 27338 54443 27339 54444 27340 54444 21068 54444 21066 54445 27339 54445 21068 54445 21068 54446 27343 54446 21055 54446 27337 54447 27343 54447 21068 54447 27338 54448 27337 54448 21068 54448 21066 54449 27352 54449 27339 54449 27339 54450 27352 54450 27350 54450 27339 54451 27350 54451 27340 54451 27340 54452 27350 54452 27349 54452 27340 54453 27349 54453 27338 54453 27338 54454 27349 54454 27341 54454 27338 54455 27341 54455 27337 54455 27337 54456 27341 54456 27342 54456 27337 54457 27342 54457 27343 54457 27343 54458 27342 54458 27347 54458 27343 54459 27347 54459 21055 54459 21055 54460 27347 54460 21057 54460 21064 54461 21062 54461 22802 54461 22802 54462 21062 54462 27345 54462 22802 54463 27345 54463 27344 54463 27344 54464 27345 54464 27346 54464 27344 54465 27346 54465 22806 54465 22806 54466 27346 54466 21058 54466 22806 54467 21058 54467 22807 54467 22807 54468 21058 54468 21057 54468 22807 54469 21057 54469 23713 54469 23713 54470 21057 54470 27347 54470 23713 54471 27347 54471 27348 54471 27348 54472 27347 54472 27342 54472 27348 54473 27342 54473 23714 54473 23714 54474 27342 54474 27341 54474 23714 54475 27341 54475 23716 54475 23716 54476 27341 54476 27349 54476 23716 54477 27349 54477 23717 54477 23717 54478 27349 54478 27350 54478 23717 54479 27350 54479 27351 54479 27351 54480 27350 54480 27352 54480 27351 54481 27352 54481 22799 54481 22799 54482 27352 54482 21067 54482 22799 54483 21067 54483 22801 54483 22801 54484 21067 54484 21064 54484 22801 54485 21064 54485 22802 54485 21054 54486 21049 54486 27356 54486 27358 54487 27353 54487 21054 54487 27359 54488 27360 54488 21054 54488 27362 54489 27354 54489 21054 54489 27355 54490 27364 54490 21054 54490 21054 54491 27367 54491 27368 54491 27365 54492 27367 54492 21054 54492 27364 54493 27365 54493 21054 54493 27354 54494 27355 54494 21054 54494 27360 54495 27362 54495 21054 54495 27353 54496 27359 54496 21054 54496 27356 54497 27358 54497 21054 54497 21049 54498 21047 54498 27356 54498 27356 54499 21047 54499 27357 54499 27356 54500 27357 54500 27358 54500 27358 54501 27357 54501 27353 54501 27353 54502 27357 54502 27376 54502 27353 54503 27376 54503 27359 54503 27359 54504 27376 54504 27360 54504 27360 54505 27376 54505 27361 54505 27360 54506 27361 54506 27362 54506 27362 54507 27361 54507 27354 54507 27354 54508 27361 54508 27363 54508 27354 54509 27363 54509 27355 54509 27355 54510 27363 54510 27364 54510 27364 54511 27363 54511 27366 54511 27364 54512 27366 54512 27365 54512 27365 54513 27366 54513 27367 54513 27367 54514 27366 54514 27373 54514 27367 54515 27373 54515 27368 54515 27381 54516 21045 54516 27369 54516 27369 54517 21045 54517 21044 54517 27369 54518 21044 54518 22824 54518 22824 54519 21044 54519 21040 54519 22824 54520 21040 54520 27370 54520 27370 54521 21040 54521 27371 54521 27370 54522 27371 54522 27372 54522 27372 54523 27371 54523 27373 54523 27372 54524 27373 54524 27374 54524 27374 54525 27373 54525 27366 54525 27374 54526 27366 54526 23694 54526 23694 54527 27366 54527 27363 54527 23694 54528 27363 54528 23695 54528 23695 54529 27363 54529 27361 54529 23695 54530 27361 54530 27375 54530 27375 54531 27361 54531 27376 54531 27375 54532 27376 54532 23697 54532 23697 54533 27376 54533 27357 54533 23697 54534 27357 54534 27377 54534 27377 54535 27357 54535 21047 54535 27377 54536 21047 54536 27378 54536 27378 54537 21047 54537 27380 54537 27378 54538 27380 54538 27379 54538 27379 54539 27380 54539 27381 54539 27379 54540 27381 54540 27369 54540 27384 54541 27388 54541 27382 54541 27383 54542 27388 54542 27384 54542 27385 54543 27383 54543 27384 54543 27384 54544 27386 54544 27390 54544 27389 54545 27386 54545 27384 54545 27382 54546 27389 54546 27384 54546 27385 54547 27404 54547 27383 54547 27383 54548 27404 54548 27387 54548 27383 54549 27387 54549 27388 54549 27388 54550 27387 54550 27402 54550 27388 54551 27402 54551 27382 54551 27382 54552 27402 54552 27399 54552 27382 54553 27399 54553 27389 54553 27389 54554 27399 54554 27397 54554 27389 54555 27397 54555 27386 54555 27386 54556 27397 54556 27396 54556 27386 54557 27396 54557 27390 54557 27390 54558 27396 54558 27391 54558 27407 54559 27392 54559 22841 54559 22841 54560 27392 54560 21035 54560 22841 54561 21035 54561 27393 54561 27393 54562 21035 54562 27394 54562 27393 54563 27394 54563 22843 54563 22843 54564 27394 54564 27395 54564 22843 54565 27395 54565 22844 54565 22844 54566 27395 54566 27391 54566 22844 54567 27391 54567 23675 54567 23675 54568 27391 54568 27396 54568 23675 54569 27396 54569 23676 54569 23676 54570 27396 54570 27397 54570 23676 54571 27397 54571 27398 54571 27398 54572 27397 54572 27399 54572 27398 54573 27399 54573 27400 54573 27400 54574 27399 54574 27402 54574 27400 54575 27402 54575 27401 54575 27401 54576 27402 54576 27387 54576 27401 54577 27387 54577 27403 54577 27403 54578 27387 54578 27404 54578 27403 54579 27404 54579 27405 54579 27405 54580 27404 54580 27406 54580 27405 54581 27406 54581 22839 54581 22839 54582 27406 54582 27407 54582 22839 54583 27407 54583 22841 54583 27408 54584 27412 54584 27411 54584 27415 54585 27416 54585 27408 54585 27417 54586 27418 54586 27408 54586 27419 54587 27421 54587 27408 54587 27408 54588 27409 54588 27424 54588 27410 54589 27409 54589 27408 54589 27421 54590 27410 54590 27408 54590 27418 54591 27419 54591 27408 54591 27416 54592 27417 54592 27408 54592 27411 54593 27415 54593 27408 54593 27412 54594 27434 54594 27413 54594 27412 54595 27413 54595 27411 54595 27411 54596 27413 54596 27414 54596 27411 54597 27414 54597 27415 54597 27415 54598 27414 54598 27416 54598 27416 54599 27414 54599 27436 54599 27416 54600 27436 54600 27417 54600 27417 54601 27436 54601 27418 54601 27418 54602 27436 54602 27420 54602 27418 54603 27420 54603 27419 54603 27419 54604 27420 54604 27421 54604 27421 54605 27420 54605 27422 54605 27421 54606 27422 54606 27410 54606 27410 54607 27422 54607 27428 54607 27410 54608 27428 54608 27409 54608 27409 54609 27428 54609 27423 54609 27409 54610 27423 54610 27424 54610 27431 54611 27425 54611 22864 54611 22864 54612 27425 54612 22863 54612 22863 54613 27425 54613 27426 54613 22863 54614 27426 54614 27427 54614 27427 54615 27426 54615 27423 54615 27427 54616 27423 54616 23655 54616 23655 54617 27423 54617 27428 54617 23655 54618 27428 54618 27429 54618 27429 54619 27428 54619 27422 54619 27429 54620 27422 54620 27430 54620 22864 54621 22865 54621 27431 54621 27431 54622 22865 54622 22866 54622 27431 54623 22866 54623 27432 54623 27432 54624 22866 54624 22870 54624 27432 54625 22870 54625 27433 54625 27433 54626 22870 54626 22871 54626 27433 54627 22871 54627 27434 54627 27434 54628 22871 54628 23658 54628 27434 54629 23658 54629 27413 54629 27413 54630 23658 54630 27435 54630 27413 54631 27435 54631 27414 54631 27414 54632 27435 54632 23656 54632 27414 54633 23656 54633 27436 54633 27436 54634 23656 54634 27430 54634 27436 54635 27430 54635 27420 54635 27420 54636 27430 54636 27422 54636 21027 54637 27445 54637 27443 54637 27444 54638 27447 54638 21027 54638 27449 54639 27442 54639 21027 54639 27451 54640 27440 54640 21027 54640 27441 54641 27438 54641 21027 54641 21027 54642 27437 54642 21016 54642 27439 54643 27437 54643 21027 54643 27438 54644 27439 54644 21027 54644 27440 54645 27441 54645 21027 54645 27442 54646 27451 54646 21027 54646 27447 54647 27449 54647 21027 54647 27443 54648 27444 54648 21027 54648 27445 54649 27446 54649 27443 54649 27443 54650 27446 54650 27461 54650 27443 54651 27461 54651 27444 54651 27444 54652 27461 54652 27447 54652 27447 54653 27461 54653 27448 54653 27447 54654 27448 54654 27449 54654 27449 54655 27448 54655 27442 54655 27442 54656 27448 54656 27450 54656 27442 54657 27450 54657 27451 54657 27451 54658 27450 54658 27440 54658 27440 54659 27450 54659 27459 54659 27440 54660 27459 54660 27441 54660 27441 54661 27459 54661 27438 54661 27438 54662 27459 54662 27452 54662 27438 54663 27452 54663 27439 54663 27439 54664 27452 54664 27437 54664 27437 54665 27452 54665 21014 54665 27437 54666 21014 54666 21016 54666 27453 54667 21019 54667 27455 54667 27455 54668 21019 54668 27454 54668 27455 54669 27454 54669 27456 54669 27456 54670 27454 54670 27457 54670 27456 54671 27457 54671 22887 54671 22887 54672 27457 54672 21015 54672 22887 54673 21015 54673 23638 54673 23638 54674 21015 54674 21014 54674 23638 54675 21014 54675 27458 54675 27458 54676 21014 54676 27452 54676 27458 54677 27452 54677 23636 54677 23636 54678 27452 54678 27459 54678 23636 54679 27459 54679 27460 54679 27460 54680 27459 54680 27450 54680 27460 54681 27450 54681 23632 54681 23632 54682 27450 54682 27448 54682 23632 54683 27448 54683 23629 54683 23629 54684 27448 54684 27461 54684 23629 54685 27461 54685 22882 54685 22882 54686 27461 54686 27446 54686 22882 54687 27446 54687 22883 54687 22883 54688 27446 54688 27462 54688 22883 54689 27462 54689 27463 54689 27463 54690 27462 54690 27453 54690 27463 54691 27453 54691 27455 54691 21010 54692 21007 54692 27470 54692 27464 54693 27473 54693 21010 54693 27474 54694 27465 54694 21010 54694 27466 54695 27469 54695 21010 54695 27467 54696 27477 54696 21010 54696 21010 54697 27468 54697 21000 54697 27479 54698 27468 54698 21010 54698 27477 54699 27479 54699 21010 54699 27469 54700 27467 54700 21010 54700 27465 54701 27466 54701 21010 54701 27473 54702 27474 54702 21010 54702 27470 54703 27464 54703 21010 54703 21007 54704 27471 54704 27470 54704 27470 54705 27471 54705 27472 54705 27470 54706 27472 54706 27464 54706 27464 54707 27472 54707 27473 54707 27473 54708 27472 54708 27475 54708 27473 54709 27475 54709 27474 54709 27474 54710 27475 54710 27465 54710 27465 54711 27475 54711 27476 54711 27465 54712 27476 54712 27466 54712 27466 54713 27476 54713 27469 54713 27469 54714 27476 54714 27478 54714 27469 54715 27478 54715 27467 54715 27467 54716 27478 54716 27477 54716 27477 54717 27478 54717 27480 54717 27477 54718 27480 54718 27479 54718 27479 54719 27480 54719 27468 54719 27468 54720 27480 54720 20999 54720 27468 54721 20999 54721 21000 54721 27489 54722 27481 54722 22914 54722 22914 54723 27481 54723 21003 54723 22914 54724 21003 54724 27482 54724 27482 54725 21003 54725 21002 54725 27482 54726 21002 54726 22912 54726 22912 54727 21002 54727 27483 54727 22912 54728 27483 54728 27484 54728 27484 54729 27483 54729 20999 54729 27484 54730 20999 54730 27485 54730 27485 54731 20999 54731 27480 54731 27485 54732 27480 54732 27486 54732 27486 54733 27480 54733 27478 54733 27486 54734 27478 54734 23615 54734 23615 54735 27478 54735 27476 54735 23615 54736 27476 54736 23618 54736 23618 54737 27476 54737 27475 54737 23618 54738 27475 54738 23619 54738 23619 54739 27475 54739 27472 54739 23619 54740 27472 54740 27487 54740 27487 54741 27472 54741 27471 54741 27487 54742 27471 54742 22917 54742 22917 54743 27471 54743 27488 54743 22917 54744 27488 54744 22915 54744 22915 54745 27488 54745 27489 54745 22915 54746 27489 54746 22914 54746 20996 54747 27490 54747 22933 54747 22933 54748 27490 54748 20994 54748 22933 54749 20994 54749 27491 54749 27491 54750 20994 54750 27492 54750 27491 54751 27492 54751 27493 54751 27493 54752 27492 54752 27494 54752 27493 54753 27494 54753 23594 54753 23594 54754 27494 54754 27509 54754 23594 54755 27509 54755 23597 54755 23597 54756 27509 54756 27508 54756 23597 54757 27508 54757 27495 54757 27495 54758 27508 54758 27496 54758 27495 54759 27496 54759 27498 54759 27498 54760 27496 54760 27497 54760 27498 54761 27497 54761 23600 54761 23600 54762 27497 54762 27499 54762 23600 54763 27499 54763 23601 54763 23601 54764 27499 54764 27504 54764 23601 54765 27504 54765 23602 54765 23602 54766 27504 54766 27500 54766 23602 54767 27500 54767 22930 54767 22930 54768 27500 54768 27501 54768 22930 54769 27501 54769 27502 54769 27502 54770 27501 54770 20996 54770 27502 54771 20996 54771 22933 54771 20998 54772 27500 54772 27511 54772 27511 54773 27500 54773 27504 54773 27511 54774 27504 54774 27503 54774 27503 54775 27504 54775 27499 54775 27503 54776 27499 54776 27505 54776 27505 54777 27499 54777 27497 54777 27505 54778 27497 54778 27506 54778 27506 54779 27497 54779 27496 54779 27506 54780 27496 54780 27507 54780 27507 54781 27496 54781 27508 54781 27507 54782 27508 54782 20993 54782 20993 54783 27508 54783 27509 54783 27510 54784 27503 54784 27505 54784 27511 54785 27503 54785 27510 54785 20998 54786 27511 54786 27510 54786 27510 54787 27507 54787 20993 54787 27506 54788 27507 54788 27510 54788 27505 54789 27506 54789 27510 54789 28243 54790 28263 54790 27512 54790 27512 54791 28263 54791 27513 54791 27512 54792 27513 54792 28242 54792 28242 54793 27513 54793 28266 54793 28242 54794 28266 54794 28240 54794 28240 54795 28266 54795 28267 54795 28240 54796 28267 54796 28239 54796 28239 54797 28267 54797 27514 54797 28239 54798 27514 54798 27515 54798 27515 54799 27514 54799 28269 54799 27515 54800 28269 54800 28237 54800 28237 54801 28269 54801 28271 54801 28237 54802 28271 54802 28235 54802 28235 54803 28271 54803 27516 54803 28235 54804 27516 54804 28233 54804 28233 54805 27516 54805 27518 54805 28233 54806 27518 54806 27517 54806 27517 54807 27518 54807 28273 54807 27517 54808 28273 54808 28231 54808 28231 54809 28273 54809 27520 54809 28231 54810 27520 54810 27519 54810 27519 54811 27520 54811 27521 54811 27519 54812 27521 54812 27522 54812 27522 54813 27521 54813 27523 54813 27522 54814 27523 54814 28229 54814 28229 54815 27523 54815 27524 54815 28229 54816 27524 54816 28228 54816 28228 54817 27524 54817 28245 54817 28228 54818 28245 54818 27525 54818 27525 54819 28245 54819 27526 54819 27525 54820 27526 54820 28226 54820 28226 54821 27526 54821 27527 54821 28226 54822 27527 54822 29428 54822 29428 54823 27527 54823 28248 54823 28812 54824 28304 54824 27528 54824 27528 54825 28304 54825 28306 54825 27528 54826 28306 54826 27529 54826 27529 54827 28306 54827 28307 54827 27529 54828 28307 54828 28289 54828 28289 54829 28307 54829 28309 54829 28289 54830 28309 54830 28287 54830 28287 54831 28309 54831 27530 54831 28287 54832 27530 54832 27531 54832 27531 54833 27530 54833 27532 54833 27531 54834 27532 54834 27533 54834 27533 54835 27532 54835 27534 54835 27533 54836 27534 54836 27535 54836 27535 54837 27534 54837 28311 54837 27535 54838 28311 54838 27536 54838 27536 54839 28311 54839 28312 54839 27536 54840 28312 54840 28283 54840 28283 54841 28312 54841 28313 54841 28283 54842 28313 54842 27537 54842 27537 54843 28313 54843 27539 54843 27537 54844 27539 54844 27538 54844 27538 54845 27539 54845 28316 54845 27538 54846 28316 54846 28280 54846 28280 54847 28316 54847 28317 54847 28280 54848 28317 54848 28279 54848 28279 54849 28317 54849 27540 54849 28279 54850 27540 54850 28278 54850 28278 54851 27540 54851 28319 54851 28278 54852 28319 54852 28277 54852 28277 54853 28319 54853 27541 54853 28277 54854 27541 54854 27542 54854 27542 54855 27541 54855 28321 54855 27542 54856 28321 54856 28831 54856 28831 54857 28321 54857 28322 54857 27543 54858 29409 54858 27544 54858 27543 54859 27544 54859 28324 54859 28324 54860 27544 54860 28329 54860 28324 54861 28329 54861 27545 54861 27545 54862 28329 54862 27546 54862 27545 54863 27546 54863 27547 54863 27547 54864 27546 54864 28330 54864 27547 54865 28330 54865 28327 54865 28327 54866 28330 54866 27548 54866 28327 54867 27548 54867 28291 54867 28291 54868 27548 54868 28332 54868 28291 54869 28332 54869 28292 54869 28292 54870 28332 54870 28334 54870 28292 54871 28334 54871 28294 54871 28294 54872 28334 54872 27549 54872 28294 54873 27549 54873 27550 54873 27550 54874 27549 54874 27551 54874 27550 54875 27551 54875 28296 54875 28296 54876 27551 54876 27552 54876 28296 54877 27552 54877 28297 54877 28297 54878 27552 54878 27553 54878 28297 54879 27553 54879 27554 54879 27554 54880 27553 54880 27555 54880 27554 54881 27555 54881 28299 54881 28299 54882 27555 54882 27556 54882 28299 54883 27556 54883 28300 54883 28300 54884 27556 54884 28339 54884 28300 54885 28339 54885 27557 54885 27557 54886 28339 54886 28341 54886 27557 54887 28341 54887 27558 54887 27558 54888 28341 54888 28342 54888 27558 54889 28342 54889 28302 54889 28302 54890 28342 54890 27559 54890 28302 54891 27559 54891 28303 54891 28303 54892 27559 54892 28797 54892 28303 54893 28797 54893 28305 54893 27560 54894 28177 54894 27561 54894 27560 54895 27561 54895 27562 54895 27562 54896 27561 54896 27563 54896 27562 54897 27563 54897 28144 54897 28144 54898 27563 54898 27564 54898 28144 54899 27564 54899 27565 54899 27565 54900 27564 54900 28179 54900 27565 54901 28179 54901 28146 54901 28146 54902 28179 54902 27566 54902 28146 54903 27566 54903 28148 54903 28148 54904 27566 54904 27567 54904 28148 54905 27567 54905 28150 54905 28150 54906 27567 54906 28182 54906 28150 54907 28182 54907 27568 54907 27568 54908 28182 54908 28184 54908 27568 54909 28184 54909 28151 54909 28151 54910 28184 54910 28185 54910 28151 54911 28185 54911 27569 54911 27569 54912 28185 54912 28187 54912 27569 54913 28187 54913 28155 54913 28155 54914 28187 54914 27570 54914 28155 54915 27570 54915 28156 54915 28156 54916 27570 54916 27572 54916 28156 54917 27572 54917 27571 54917 27571 54918 27572 54918 27573 54918 27571 54919 27573 54919 28157 54919 28157 54920 27573 54920 27575 54920 28157 54921 27575 54921 27574 54921 27574 54922 27575 54922 27576 54922 27574 54923 27576 54923 27577 54923 27577 54924 27576 54924 27578 54924 27577 54925 27578 54925 27579 54925 27579 54926 27578 54926 28850 54926 27579 54927 28850 54927 29375 54927 28141 54928 28160 54928 28138 54928 28138 54929 28160 54929 27580 54929 28138 54930 27580 54930 27581 54930 27581 54931 27580 54931 27582 54931 27581 54932 27582 54932 27584 54932 27584 54933 27582 54933 27583 54933 27584 54934 27583 54934 27585 54934 27585 54935 27583 54935 28162 54935 27585 54936 28162 54936 28136 54936 28136 54937 28162 54937 27586 54937 28136 54938 27586 54938 28132 54938 28132 54939 27586 54939 27588 54939 28132 54940 27588 54940 27587 54940 27587 54941 27588 54941 27589 54941 27587 54942 27589 54942 28130 54942 28130 54943 27589 54943 28165 54943 28130 54944 28165 54944 28129 54944 28129 54945 28165 54945 27590 54945 28129 54946 27590 54946 28128 54946 28128 54947 27590 54947 27591 54947 28128 54948 27591 54948 27592 54948 27592 54949 27591 54949 28168 54949 27592 54950 28168 54950 28126 54950 28126 54951 28168 54951 27593 54951 28126 54952 27593 54952 28125 54952 28125 54953 27593 54953 27594 54953 28125 54954 27594 54954 28124 54954 28124 54955 27594 54955 27595 54955 28124 54956 27595 54956 28123 54956 28123 54957 27595 54957 28173 54957 28123 54958 28173 54958 28122 54958 28122 54959 28173 54959 28175 54959 28122 54960 28175 54960 27596 54960 27596 54961 28175 54961 29355 54961 28350 54962 29353 54962 28384 54962 28350 54963 28384 54963 27597 54963 27597 54964 28384 54964 28385 54964 27597 54965 28385 54965 27598 54965 27598 54966 28385 54966 28386 54966 27598 54967 28386 54967 28354 54967 28354 54968 28386 54968 28387 54968 28354 54969 28387 54969 28355 54969 28355 54970 28387 54970 28389 54970 28355 54971 28389 54971 27599 54971 27599 54972 28389 54972 28391 54972 27599 54973 28391 54973 28357 54973 28357 54974 28391 54974 28392 54974 28357 54975 28392 54975 28358 54975 28358 54976 28392 54976 28394 54976 28358 54977 28394 54977 28359 54977 28359 54978 28394 54978 28395 54978 28359 54979 28395 54979 27600 54979 27600 54980 28395 54980 27602 54980 27600 54981 27602 54981 27601 54981 27601 54982 27602 54982 28396 54982 27601 54983 28396 54983 27603 54983 27603 54984 28396 54984 28397 54984 27603 54985 28397 54985 27604 54985 27604 54986 28397 54986 28398 54986 27604 54987 28398 54987 27605 54987 27605 54988 28398 54988 28400 54988 27605 54989 28400 54989 27606 54989 27606 54990 28400 54990 27607 54990 27606 54991 27607 54991 28363 54991 28363 54992 27607 54992 27608 54992 28363 54993 27608 54993 27610 54993 27610 54994 27608 54994 27609 54994 27610 54995 27609 54995 28365 54995 28365 54996 27609 54996 27611 54996 28365 54997 27611 54997 28366 54997 27612 54998 27613 54998 27615 54998 27615 54999 27613 54999 27614 54999 27875 55000 28644 55000 27616 55000 27614 55001 27871 55001 27615 55001 27615 55002 27871 55002 27617 55002 27615 55003 27617 55003 27616 55003 27616 55004 27617 55004 27873 55004 27616 55005 27873 55005 27875 55005 27875 55006 27876 55006 28644 55006 28644 55007 27876 55007 27877 55007 28644 55008 27877 55008 27619 55008 27877 55009 27618 55009 27619 55009 27619 55010 27618 55010 27620 55010 27619 55011 27620 55011 27623 55011 27621 55012 27622 55012 27879 55012 27879 55013 27622 55013 27623 55013 27879 55014 27623 55014 27624 55014 27624 55015 27623 55015 27620 55015 27625 55016 28559 55016 27626 55016 27627 55017 28630 55017 28629 55017 27626 55018 27863 55018 27625 55018 27625 55019 27863 55019 27628 55019 27625 55020 27628 55020 28629 55020 28629 55021 27628 55021 27629 55021 28629 55022 27629 55022 27627 55022 27627 55023 27866 55023 28630 55023 28630 55024 27866 55024 27630 55024 28630 55025 27630 55025 28631 55025 29337 55026 28633 55026 27631 55026 27631 55027 28633 55027 27632 55027 27631 55028 27632 55028 27868 55028 27868 55029 27632 55029 28631 55029 27868 55030 28631 55030 27633 55030 27633 55031 28631 55031 27630 55031 27636 55032 28567 55032 29328 55032 29328 55033 27634 55033 27636 55033 27636 55034 27634 55034 27635 55034 27636 55035 27635 55035 28568 55035 27635 55036 27854 55036 28568 55036 28568 55037 27854 55037 27856 55037 28568 55038 27856 55038 27637 55038 27856 55039 27857 55039 27637 55039 27637 55040 27857 55040 27639 55040 27637 55041 27639 55041 27638 55041 27639 55042 27858 55042 27638 55042 27638 55043 27858 55043 27859 55043 27638 55044 27859 55044 27640 55044 27640 55045 27859 55045 27860 55045 27640 55046 27860 55046 27643 55046 27641 55047 27642 55047 27862 55047 27862 55048 27642 55048 27643 55048 27862 55049 27643 55049 27644 55049 27644 55050 27643 55050 27860 55050 27645 55051 27943 55051 27646 55051 27646 55052 27943 55052 27944 55052 27647 55053 27651 55053 28508 55053 27944 55054 27945 55054 27646 55054 27646 55055 27945 55055 27648 55055 27646 55056 27648 55056 28508 55056 28508 55057 27648 55057 27649 55057 28508 55058 27649 55058 27647 55058 27647 55059 27650 55059 27651 55059 27651 55060 27650 55060 27653 55060 27651 55061 27653 55061 27652 55061 27653 55062 27654 55062 27652 55062 27652 55063 27654 55063 27949 55063 27652 55064 27949 55064 27658 55064 27950 55065 27656 55065 27655 55065 27655 55066 27656 55066 27658 55066 27655 55067 27658 55067 27657 55067 27657 55068 27658 55068 27949 55068 27941 55069 28622 55069 27659 55069 27659 55070 28622 55070 28621 55070 27659 55071 28621 55071 27660 55071 27660 55072 28621 55072 27661 55072 27660 55073 27661 55073 27663 55073 27663 55074 27661 55074 27662 55074 27663 55075 27662 55075 27664 55075 27664 55076 27662 55076 28503 55076 27664 55077 28503 55077 27938 55077 27938 55078 28503 55078 27665 55078 27938 55079 27665 55079 29311 55079 29311 55080 27665 55080 29312 55080 27668 55081 27666 55081 27926 55081 27926 55082 27667 55082 27668 55082 27668 55083 27667 55083 27928 55083 27668 55084 27928 55084 27669 55084 27670 55085 28522 55085 27671 55085 27928 55086 27929 55086 27669 55086 27669 55087 27929 55087 27931 55087 27669 55088 27931 55088 27671 55088 27671 55089 27931 55089 27932 55089 27671 55090 27932 55090 27670 55090 27670 55091 27672 55091 28522 55091 28522 55092 27672 55092 27934 55092 28522 55093 27934 55093 27673 55093 27673 55094 27934 55094 27676 55094 27673 55095 27676 55095 28520 55095 29061 55096 28615 55096 27674 55096 27674 55097 28615 55097 28520 55097 27674 55098 28520 55098 27675 55098 27675 55099 28520 55099 27676 55099 27678 55100 27677 55100 29299 55100 29299 55101 27919 55101 27678 55101 27678 55102 27919 55102 27679 55102 27678 55103 27679 55103 28535 55103 27682 55104 27683 55104 28536 55104 27679 55105 27920 55105 28535 55105 28535 55106 27920 55106 27680 55106 28535 55107 27680 55107 28536 55107 28536 55108 27680 55108 27681 55108 28536 55109 27681 55109 27682 55109 27682 55110 27921 55110 27683 55110 27683 55111 27921 55111 27922 55111 27683 55112 27922 55112 28537 55112 28537 55113 27922 55113 27684 55113 28537 55114 27684 55114 27688 55114 27925 55115 27686 55115 27685 55115 27685 55116 27686 55116 27688 55116 27685 55117 27688 55117 27687 55117 27687 55118 27688 55118 27684 55118 28603 55119 28611 55119 29082 55119 27914 55120 27689 55120 28605 55120 29082 55121 27911 55121 28603 55121 28603 55122 27911 55122 27690 55122 28603 55123 27690 55123 28605 55123 28605 55124 27690 55124 27691 55124 28605 55125 27691 55125 27914 55125 27914 55126 27692 55126 27689 55126 27689 55127 27692 55127 27693 55127 27689 55128 27693 55128 28600 55128 27694 55129 28606 55129 27917 55129 27917 55130 28606 55130 28602 55130 27917 55131 28602 55131 27695 55131 27695 55132 28602 55132 28600 55132 27695 55133 28600 55133 27915 55133 27915 55134 28600 55134 27693 55134 27698 55135 28593 55135 29285 55135 29285 55136 27696 55136 27698 55136 27698 55137 27696 55137 27697 55137 27698 55138 27697 55138 27701 55138 27699 55139 27705 55139 27703 55139 27697 55140 27700 55140 27701 55140 27701 55141 27700 55141 27702 55141 27701 55142 27702 55142 27703 55142 27703 55143 27702 55143 27704 55143 27703 55144 27704 55144 27699 55144 27699 55145 27706 55145 27705 55145 27705 55146 27706 55146 27707 55146 27705 55147 27707 55147 28592 55147 28592 55148 27707 55148 27708 55148 28592 55149 27708 55149 27711 55149 29282 55150 27709 55150 27710 55150 27710 55151 27709 55151 27711 55151 27710 55152 27711 55152 27712 55152 27712 55153 27711 55153 27708 55153 27713 55154 28546 55154 27903 55154 27903 55155 28546 55155 28587 55155 27903 55156 28587 55156 27901 55156 27901 55157 28587 55157 27714 55157 27901 55158 27714 55158 27899 55158 27899 55159 27714 55159 28586 55159 27899 55160 28586 55160 27894 55160 27894 55161 28586 55161 28585 55161 27894 55162 28585 55162 27715 55162 27715 55163 28585 55163 27716 55163 27715 55164 27716 55164 27717 55164 27717 55165 27716 55165 28590 55165 29099 55166 28580 55166 27718 55166 27718 55167 28580 55167 27719 55167 27718 55168 27719 55168 27891 55168 27891 55169 27719 55169 27720 55169 27891 55170 27720 55170 27890 55170 27890 55171 27720 55171 27721 55171 27890 55172 27721 55172 27723 55172 27723 55173 27721 55173 27722 55173 27723 55174 27722 55174 27724 55174 27724 55175 27722 55175 27725 55175 27724 55176 27725 55176 29105 55176 29105 55177 27725 55177 27726 55177 27728 55178 28572 55178 27727 55178 27882 55179 27731 55179 28579 55179 27727 55180 27881 55180 27728 55180 27728 55181 27881 55181 27729 55181 27728 55182 27729 55182 28579 55182 28579 55183 27729 55183 27730 55183 28579 55184 27730 55184 27882 55184 27882 55185 27732 55185 27731 55185 27731 55186 27732 55186 27733 55186 27731 55187 27733 55187 27734 55187 29266 55188 28569 55188 27887 55188 27887 55189 28569 55189 28578 55189 27887 55190 28578 55190 27884 55190 27884 55191 28578 55191 27734 55191 27884 55192 27734 55192 27735 55192 27735 55193 27734 55193 27733 55193 27927 55194 27737 55194 27736 55194 27736 55195 27737 55195 29625 55195 27736 55196 29625 55196 27930 55196 27930 55197 29625 55197 29484 55197 27930 55198 29484 55198 27933 55198 27933 55199 29484 55199 29483 55199 27933 55200 29483 55200 27935 55200 27935 55201 29483 55201 29482 55201 27935 55202 29482 55202 27738 55202 27738 55203 29482 55203 29481 55203 27738 55204 29481 55204 27936 55204 27936 55205 29481 55205 29480 55205 27740 55206 29594 55206 29055 55206 29055 55207 27739 55207 27740 55207 27740 55208 27739 55208 27741 55208 27740 55209 27741 55209 27742 55209 27741 55210 27942 55210 27742 55210 27742 55211 27942 55211 27743 55211 27742 55212 27743 55212 27744 55212 27743 55213 27940 55213 27744 55213 27744 55214 27940 55214 27745 55214 27744 55215 27745 55215 29590 55215 27745 55216 27746 55216 29590 55216 29590 55217 27746 55217 27747 55217 29590 55218 27747 55218 29596 55218 29596 55219 27747 55219 27749 55219 29596 55220 27749 55220 29597 55220 29252 55221 27748 55221 27937 55221 27937 55222 27748 55222 29597 55222 27937 55223 29597 55223 27939 55223 27939 55224 29597 55224 27749 55224 27750 55225 29246 55225 29487 55225 29487 55226 29246 55226 27751 55226 27752 55227 29496 55227 29490 55227 27751 55228 27753 55228 29487 55228 29487 55229 27753 55229 27754 55229 29487 55230 27754 55230 29490 55230 29490 55231 27754 55231 27948 55231 29490 55232 27948 55232 27752 55232 27752 55233 27755 55233 29496 55233 29496 55234 27755 55234 27756 55234 29496 55235 27756 55235 27757 55235 27756 55236 27947 55236 27757 55236 27757 55237 27947 55237 27759 55237 27757 55238 27759 55238 29497 55238 29239 55239 29499 55239 27758 55239 27758 55240 29499 55240 29497 55240 27758 55241 29497 55241 27946 55241 27946 55242 29497 55242 27759 55242 27760 55243 29237 55243 27855 55243 27855 55244 29237 55244 29501 55244 27855 55245 29501 55245 27761 55245 27761 55246 29501 55246 29500 55246 27761 55247 29500 55247 27762 55247 27762 55248 29500 55248 29503 55248 27762 55249 29503 55249 27764 55249 27764 55250 29503 55250 27763 55250 27764 55251 27763 55251 27861 55251 27861 55252 27763 55252 27765 55252 27861 55253 27765 55253 29129 55253 29129 55254 27765 55254 27766 55254 27767 55255 29576 55255 27768 55255 27768 55256 29576 55256 29577 55256 27768 55257 29577 55257 27864 55257 27864 55258 29577 55258 29578 55258 27864 55259 29578 55259 27865 55259 27865 55260 29578 55260 27769 55260 27865 55261 27769 55261 27867 55261 27867 55262 27769 55262 27770 55262 27867 55263 27770 55263 27869 55263 27869 55264 27770 55264 27772 55264 27869 55265 27772 55265 27771 55265 27771 55266 27772 55266 27773 55266 27771 55267 27773 55267 27870 55267 27870 55268 27773 55268 29229 55268 29574 55269 29109 55269 29671 55269 29671 55270 29109 55270 27880 55270 27778 55271 29568 55271 27776 55271 27880 55272 27774 55272 29671 55272 29671 55273 27774 55273 27775 55273 29671 55274 27775 55274 27776 55274 27776 55275 27775 55275 27777 55275 27776 55276 27777 55276 27778 55276 27778 55277 27878 55277 29568 55277 29568 55278 27878 55278 27779 55278 29568 55279 27779 55279 29567 55279 27779 55280 27874 55280 29567 55280 29567 55281 27874 55281 27784 55281 29567 55282 27784 55282 27780 55282 27781 55283 27783 55283 27782 55283 27782 55284 27783 55284 27780 55284 27782 55285 27780 55285 27872 55285 27872 55286 27780 55286 27784 55286 29108 55287 29551 55287 27785 55287 27785 55288 29551 55288 27786 55288 27785 55289 27786 55289 27787 55289 27787 55290 27786 55290 29563 55290 27787 55291 29563 55291 27788 55291 27788 55292 29563 55292 29564 55292 27788 55293 29564 55293 27883 55293 27883 55294 29564 55294 27790 55294 27883 55295 27790 55295 27789 55295 27789 55296 27790 55296 29561 55296 27789 55297 29561 55297 27885 55297 27885 55298 29561 55298 29559 55298 27885 55299 29559 55299 27886 55299 27886 55300 29559 55300 29213 55300 29547 55301 27791 55301 27792 55301 27792 55302 27893 55302 29547 55302 29547 55303 27893 55303 27793 55303 29547 55304 27793 55304 29556 55304 27793 55305 27794 55305 29556 55305 29556 55306 27794 55306 27795 55306 29556 55307 27795 55307 29558 55307 27795 55308 27892 55308 29558 55308 29558 55309 27892 55309 27889 55309 29558 55310 27889 55310 29656 55310 27889 55311 27796 55311 29656 55311 29656 55312 27796 55312 27797 55312 29656 55313 27797 55313 29541 55313 29541 55314 27797 55314 27799 55314 29541 55315 27799 55315 29542 55315 29210 55316 29212 55316 27798 55316 27798 55317 29212 55317 29542 55317 27798 55318 29542 55318 27888 55318 27888 55319 29542 55319 27799 55319 27802 55320 27800 55320 29195 55320 29195 55321 27801 55321 27802 55321 27802 55322 27801 55322 27902 55322 27802 55323 27902 55323 27804 55323 27902 55324 27904 55324 27804 55324 27804 55325 27904 55325 27803 55325 27804 55326 27803 55326 29536 55326 27803 55327 27900 55327 29536 55327 29536 55328 27900 55328 27898 55328 29536 55329 27898 55329 27805 55329 27898 55330 27897 55330 27805 55330 27805 55331 27897 55331 27896 55331 27805 55332 27896 55332 29539 55332 29539 55333 27896 55333 27895 55333 29539 55334 27895 55334 29540 55334 29098 55335 29201 55335 27806 55335 27806 55336 29201 55336 29540 55336 27806 55337 29540 55337 27807 55337 27807 55338 29540 55338 27895 55338 29091 55339 27808 55339 27905 55339 27905 55340 27808 55340 27809 55340 27905 55341 27809 55341 27906 55341 27906 55342 27809 55342 27810 55342 27906 55343 27810 55343 27907 55343 27907 55344 27810 55344 29521 55344 27907 55345 29521 55345 27811 55345 27811 55346 29521 55346 27812 55346 27811 55347 27812 55347 27908 55347 27908 55348 27812 55348 29524 55348 27908 55349 29524 55349 27909 55349 27909 55350 29524 55350 29526 55350 29083 55351 27813 55351 27910 55351 27910 55352 27813 55352 29520 55352 27910 55353 29520 55353 27912 55353 27912 55354 29520 55354 29519 55354 27912 55355 29519 55355 27913 55355 27913 55356 29519 55356 29518 55356 27913 55357 29518 55357 27814 55357 27814 55358 29518 55358 27815 55358 27814 55359 27815 55359 27916 55359 27916 55360 27815 55360 29513 55360 27916 55361 29513 55361 27918 55361 27918 55362 29513 55362 27816 55362 27918 55363 27816 55363 29077 55363 29077 55364 27816 55364 29516 55364 29180 55365 29182 55365 27817 55365 27817 55366 29182 55366 27818 55366 27817 55367 27818 55367 27819 55367 27819 55368 27818 55368 29472 55368 27819 55369 29472 55369 27820 55369 27820 55370 29472 55370 29473 55370 27820 55371 29473 55371 27923 55371 27923 55372 29473 55372 29474 55372 27923 55373 29474 55373 27924 55373 27924 55374 29474 55374 29469 55374 27924 55375 29469 55375 29175 55375 29175 55376 29469 55376 29468 55376 27821 55377 27822 55377 27823 55377 27823 55378 27822 55378 29450 55378 27823 55379 29450 55379 29174 55379 27821 55380 27823 55380 29449 55380 29449 55381 27823 55381 28462 55381 29449 55382 28462 55382 29447 55382 29447 55383 28462 55383 28460 55383 29447 55384 28460 55384 27824 55384 27824 55385 28460 55385 28458 55385 27824 55386 28458 55386 29554 55386 29554 55387 28458 55387 28457 55387 29554 55388 28457 55388 27825 55388 27825 55389 28457 55389 27826 55389 27825 55390 27826 55390 27827 55390 27827 55391 27826 55391 27828 55391 27827 55392 27828 55392 27829 55392 27829 55393 27828 55393 27830 55393 27829 55394 27830 55394 29512 55394 29512 55395 27830 55395 28454 55395 29512 55396 28454 55396 27831 55396 27831 55397 28454 55397 27832 55397 27831 55398 27832 55398 29570 55398 29570 55399 27832 55399 27833 55399 29570 55400 27833 55400 29510 55400 29510 55401 27833 55401 28453 55401 29510 55402 28453 55402 27834 55402 27834 55403 28453 55403 27836 55403 27834 55404 27836 55404 27835 55404 27835 55405 27836 55405 28451 55405 27835 55406 28451 55406 27837 55406 27837 55407 28451 55407 27838 55407 27837 55408 27838 55408 29157 55408 28563 55409 29155 55409 28465 55409 28470 55410 28646 55410 27839 55410 27839 55411 28646 55411 28562 55411 27839 55412 28562 55412 28465 55412 28465 55413 28562 55413 27840 55413 28465 55414 27840 55414 28563 55414 27841 55415 28557 55415 27842 55415 27842 55416 28557 55416 27843 55416 27843 55417 28627 55417 27842 55417 27842 55418 28627 55418 28626 55418 27842 55419 28626 55419 28470 55419 28470 55420 28626 55420 27844 55420 28470 55421 27844 55421 28646 55421 28642 55422 27841 55422 28471 55422 28642 55423 28552 55423 27841 55423 27841 55424 28552 55424 27845 55424 27841 55425 27845 55425 28557 55425 28549 55426 27846 55426 28483 55426 28483 55427 27846 55427 27847 55427 28483 55428 27847 55428 28481 55428 28481 55429 27847 55429 27848 55429 28481 55430 27848 55430 28478 55430 28478 55431 27848 55431 28551 55431 28478 55432 28551 55432 28475 55432 28475 55433 28551 55433 28636 55433 28475 55434 28636 55434 27849 55434 27849 55435 28636 55435 28639 55435 27849 55436 28639 55436 28471 55436 28471 55437 28639 55437 27850 55437 28471 55438 27850 55438 28642 55438 27851 55439 28548 55439 27852 55439 27851 55440 27852 55440 28483 55440 28483 55441 27852 55441 27853 55441 28483 55442 27853 55442 28549 55442 28548 55443 27851 55443 28501 55443 28501 55444 27851 55444 28486 55444 28501 55445 28486 55445 28502 55445 28502 55446 28486 55446 28664 55446 28664 55447 28486 55447 28491 55447 28664 55448 28491 55448 28545 55448 28545 55449 28491 55449 29141 55449 28545 55450 29141 55450 29140 55450 29328 55451 27760 55451 27634 55451 27634 55452 27760 55452 27855 55452 27634 55453 27855 55453 27635 55453 27635 55454 27855 55454 27854 55454 27854 55455 27855 55455 27761 55455 27854 55456 27761 55456 27856 55456 27856 55457 27761 55457 27857 55457 27857 55458 27761 55458 27762 55458 27857 55459 27762 55459 27639 55459 27639 55460 27762 55460 27858 55460 27858 55461 27762 55461 27764 55461 27858 55462 27764 55462 27859 55462 27859 55463 27764 55463 27860 55463 27860 55464 27764 55464 27861 55464 27860 55465 27861 55465 27644 55465 27644 55466 27861 55466 27862 55466 27862 55467 27861 55467 29129 55467 27862 55468 29129 55468 27641 55468 27626 55469 27767 55469 27768 55469 27626 55470 27768 55470 27863 55470 27863 55471 27768 55471 27864 55471 27863 55472 27864 55472 27628 55472 27628 55473 27864 55473 27629 55473 27629 55474 27864 55474 27865 55474 27629 55475 27865 55475 27627 55475 27627 55476 27865 55476 27866 55476 27866 55477 27865 55477 27867 55477 27866 55478 27867 55478 27630 55478 27630 55479 27867 55479 27633 55479 27633 55480 27867 55480 27869 55480 27633 55481 27869 55481 27868 55481 27868 55482 27869 55482 27771 55482 27868 55483 27771 55483 27631 55483 27631 55484 27771 55484 27870 55484 27631 55485 27870 55485 29337 55485 27613 55486 27781 55486 27614 55486 27614 55487 27781 55487 27782 55487 27614 55488 27782 55488 27871 55488 27871 55489 27782 55489 27872 55489 27871 55490 27872 55490 27617 55490 27617 55491 27872 55491 27784 55491 27617 55492 27784 55492 27873 55492 27873 55493 27784 55493 27874 55493 27873 55494 27874 55494 27875 55494 27875 55495 27874 55495 27779 55495 27875 55496 27779 55496 27876 55496 27876 55497 27779 55497 27878 55497 27876 55498 27878 55498 27877 55498 27877 55499 27878 55499 27778 55499 27877 55500 27778 55500 27618 55500 27618 55501 27778 55501 27777 55501 27618 55502 27777 55502 27620 55502 27620 55503 27777 55503 27775 55503 27620 55504 27775 55504 27624 55504 27624 55505 27775 55505 27774 55505 27624 55506 27774 55506 27879 55506 27879 55507 27774 55507 27880 55507 27879 55508 27880 55508 27621 55508 27621 55509 27880 55509 29109 55509 27727 55510 29108 55510 27785 55510 27727 55511 27785 55511 27881 55511 27881 55512 27785 55512 27787 55512 27881 55513 27787 55513 27729 55513 27729 55514 27787 55514 27730 55514 27730 55515 27787 55515 27788 55515 27730 55516 27788 55516 27882 55516 27882 55517 27788 55517 27732 55517 27732 55518 27788 55518 27883 55518 27732 55519 27883 55519 27733 55519 27733 55520 27883 55520 27735 55520 27735 55521 27883 55521 27789 55521 27735 55522 27789 55522 27884 55522 27884 55523 27789 55523 27885 55523 27884 55524 27885 55524 27887 55524 27887 55525 27885 55525 27886 55525 27887 55526 27886 55526 29266 55526 29210 55527 27798 55527 29105 55527 29105 55528 27798 55528 27724 55528 27798 55529 27888 55529 27724 55529 27724 55530 27888 55530 27799 55530 27724 55531 27799 55531 27723 55531 27799 55532 27797 55532 27723 55532 27723 55533 27797 55533 27796 55533 27723 55534 27796 55534 27890 55534 27796 55535 27889 55535 27890 55535 27890 55536 27889 55536 27892 55536 27890 55537 27892 55537 27891 55537 27892 55538 27795 55538 27891 55538 27891 55539 27795 55539 27794 55539 27891 55540 27794 55540 27718 55540 27792 55541 29099 55541 27893 55541 27893 55542 29099 55542 27718 55542 27893 55543 27718 55543 27793 55543 27793 55544 27718 55544 27794 55544 29098 55545 27806 55545 27717 55545 27717 55546 27806 55546 27715 55546 27806 55547 27807 55547 27715 55547 27715 55548 27807 55548 27895 55548 27715 55549 27895 55549 27894 55549 27895 55550 27896 55550 27894 55550 27894 55551 27896 55551 27897 55551 27894 55552 27897 55552 27899 55552 27897 55553 27898 55553 27899 55553 27899 55554 27898 55554 27900 55554 27899 55555 27900 55555 27901 55555 27900 55556 27803 55556 27901 55556 27901 55557 27803 55557 27904 55557 27901 55558 27904 55558 27903 55558 29195 55559 27713 55559 27801 55559 27801 55560 27713 55560 27903 55560 27801 55561 27903 55561 27902 55561 27902 55562 27903 55562 27904 55562 29285 55563 29091 55563 27696 55563 27696 55564 29091 55564 27905 55564 27696 55565 27905 55565 27697 55565 27697 55566 27905 55566 27700 55566 27700 55567 27905 55567 27906 55567 27700 55568 27906 55568 27702 55568 27702 55569 27906 55569 27704 55569 27704 55570 27906 55570 27907 55570 27704 55571 27907 55571 27699 55571 27699 55572 27907 55572 27706 55572 27706 55573 27907 55573 27811 55573 27706 55574 27811 55574 27707 55574 27707 55575 27811 55575 27708 55575 27708 55576 27811 55576 27908 55576 27708 55577 27908 55577 27712 55577 27712 55578 27908 55578 27710 55578 27710 55579 27908 55579 27909 55579 27710 55580 27909 55580 29282 55580 29082 55581 29083 55581 27910 55581 29082 55582 27910 55582 27911 55582 27911 55583 27910 55583 27912 55583 27911 55584 27912 55584 27690 55584 27690 55585 27912 55585 27691 55585 27691 55586 27912 55586 27913 55586 27691 55587 27913 55587 27914 55587 27914 55588 27913 55588 27692 55588 27692 55589 27913 55589 27814 55589 27692 55590 27814 55590 27693 55590 27693 55591 27814 55591 27915 55591 27915 55592 27814 55592 27916 55592 27915 55593 27916 55593 27695 55593 27695 55594 27916 55594 27918 55594 27695 55595 27918 55595 27917 55595 27917 55596 27918 55596 29077 55596 27917 55597 29077 55597 27694 55597 29299 55598 29180 55598 27919 55598 27919 55599 29180 55599 27817 55599 27919 55600 27817 55600 27679 55600 27679 55601 27817 55601 27920 55601 27920 55602 27817 55602 27819 55602 27920 55603 27819 55603 27680 55603 27680 55604 27819 55604 27681 55604 27681 55605 27819 55605 27820 55605 27681 55606 27820 55606 27682 55606 27682 55607 27820 55607 27921 55607 27921 55608 27820 55608 27923 55608 27921 55609 27923 55609 27922 55609 27922 55610 27923 55610 27684 55610 27684 55611 27923 55611 27924 55611 27684 55612 27924 55612 27687 55612 27687 55613 27924 55613 27685 55613 27685 55614 27924 55614 29175 55614 27685 55615 29175 55615 27925 55615 27926 55616 27927 55616 27667 55616 27667 55617 27927 55617 27736 55617 27667 55618 27736 55618 27928 55618 27928 55619 27736 55619 27929 55619 27929 55620 27736 55620 27930 55620 27929 55621 27930 55621 27931 55621 27931 55622 27930 55622 27932 55622 27932 55623 27930 55623 27933 55623 27932 55624 27933 55624 27670 55624 27670 55625 27933 55625 27672 55625 27672 55626 27933 55626 27935 55626 27672 55627 27935 55627 27934 55627 27934 55628 27935 55628 27676 55628 27676 55629 27935 55629 27738 55629 27676 55630 27738 55630 27675 55630 27675 55631 27738 55631 27674 55631 27674 55632 27738 55632 27936 55632 27674 55633 27936 55633 29061 55633 29252 55634 27937 55634 29311 55634 29311 55635 27937 55635 27938 55635 27937 55636 27939 55636 27938 55636 27938 55637 27939 55637 27749 55637 27938 55638 27749 55638 27664 55638 27749 55639 27747 55639 27664 55639 27664 55640 27747 55640 27746 55640 27664 55641 27746 55641 27663 55641 27746 55642 27745 55642 27663 55642 27663 55643 27745 55643 27940 55643 27663 55644 27940 55644 27660 55644 27940 55645 27743 55645 27660 55645 27660 55646 27743 55646 27942 55646 27660 55647 27942 55647 27659 55647 29055 55648 27941 55648 27739 55648 27739 55649 27941 55649 27659 55649 27739 55650 27659 55650 27741 55650 27741 55651 27659 55651 27942 55651 27943 55652 29239 55652 27944 55652 27944 55653 29239 55653 27758 55653 27944 55654 27758 55654 27945 55654 27945 55655 27758 55655 27946 55655 27945 55656 27946 55656 27648 55656 27648 55657 27946 55657 27759 55657 27648 55658 27759 55658 27649 55658 27649 55659 27759 55659 27947 55659 27649 55660 27947 55660 27647 55660 27647 55661 27947 55661 27756 55661 27647 55662 27756 55662 27650 55662 27650 55663 27756 55663 27755 55663 27650 55664 27755 55664 27653 55664 27653 55665 27755 55665 27752 55665 27653 55666 27752 55666 27654 55666 27654 55667 27752 55667 27948 55667 27654 55668 27948 55668 27949 55668 27949 55669 27948 55669 27754 55669 27949 55670 27754 55670 27657 55670 27657 55671 27754 55671 27753 55671 27657 55672 27753 55672 27655 55672 27655 55673 27753 55673 27751 55673 27655 55674 27751 55674 27950 55674 27950 55675 27751 55675 29246 55675 29043 55676 29042 55676 29638 55676 29638 55677 29042 55677 27951 55677 29638 55678 27951 55678 29505 55678 29505 55679 27951 55679 27953 55679 29505 55680 27953 55680 27952 55680 27952 55681 27953 55681 27955 55681 27952 55682 27955 55682 27954 55682 27954 55683 27955 55683 27963 55683 27954 55684 27963 55684 27956 55684 27956 55685 27963 55685 27958 55685 27956 55686 27958 55686 27957 55686 27957 55687 27958 55687 29034 55687 27957 55688 29034 55688 29508 55688 27959 55689 29034 55689 27960 55689 27960 55690 29034 55690 27958 55690 27960 55691 27958 55691 27961 55691 27961 55692 27958 55692 27963 55692 27961 55693 27963 55693 27962 55693 27962 55694 27963 55694 27955 55694 27962 55695 27955 55695 28700 55695 28700 55696 27955 55696 27953 55696 28700 55697 27953 55697 27964 55697 27964 55698 27953 55698 27951 55698 27964 55699 27951 55699 29024 55699 29024 55700 27951 55700 29042 55700 27971 55701 29584 55701 27972 55701 27972 55702 29584 55702 27965 55702 27972 55703 27965 55703 27974 55703 27974 55704 27965 55704 29583 55704 27974 55705 29583 55705 27975 55705 27975 55706 29583 55706 27966 55706 27975 55707 27966 55707 27976 55707 27976 55708 27966 55708 27967 55708 27976 55709 27967 55709 27968 55709 27968 55710 27967 55710 29664 55710 27968 55711 29664 55711 27978 55711 27978 55712 29664 55712 27969 55712 28553 55713 27971 55713 27970 55713 27970 55714 27971 55714 27972 55714 27970 55715 27972 55715 27973 55715 27973 55716 27972 55716 27974 55716 27973 55717 27974 55717 28650 55717 28650 55718 27974 55718 27975 55718 28650 55719 27975 55719 28690 55719 28690 55720 27975 55720 27976 55720 28690 55721 27976 55721 28691 55721 28691 55722 27976 55722 27968 55722 28691 55723 27968 55723 27977 55723 27977 55724 27968 55724 27978 55724 28993 55725 29552 55725 27986 55725 27986 55726 29552 55726 29566 55726 27986 55727 29566 55727 27988 55727 27988 55728 29566 55728 27979 55728 27988 55729 27979 55729 27980 55729 27980 55730 27979 55730 27981 55730 27980 55731 27981 55731 27982 55731 27982 55732 27981 55732 27983 55732 27982 55733 27983 55733 27984 55733 27984 55734 27983 55734 29562 55734 27984 55735 29562 55735 27985 55735 27985 55736 29562 55736 29550 55736 28574 55737 28993 55737 28575 55737 28575 55738 28993 55738 27986 55738 28575 55739 27986 55739 27987 55739 27987 55740 27986 55740 27988 55740 27987 55741 27988 55741 27989 55741 27989 55742 27988 55742 27980 55742 27989 55743 27980 55743 27990 55743 27990 55744 27980 55744 27982 55744 27990 55745 27982 55745 27991 55745 27991 55746 27982 55746 27984 55746 27991 55747 27984 55747 27992 55747 27992 55748 27984 55748 27985 55748 28000 55749 29604 55749 27993 55749 27993 55750 29604 55750 27994 55750 27993 55751 27994 55751 28001 55751 28001 55752 27994 55752 27995 55752 28001 55753 27995 55753 27996 55753 27996 55754 27995 55754 29531 55754 27996 55755 29531 55755 27997 55755 27997 55756 29531 55756 29532 55756 27997 55757 29532 55757 27998 55757 27998 55758 29532 55758 27999 55758 27998 55759 27999 55759 28004 55759 28004 55760 27999 55760 28981 55760 28661 55761 28000 55761 28652 55761 28652 55762 28000 55762 27993 55762 28652 55763 27993 55763 28653 55763 28653 55764 27993 55764 28001 55764 28653 55765 28001 55765 28002 55765 28002 55766 28001 55766 27996 55766 28002 55767 27996 55767 28654 55767 28654 55768 27996 55768 27997 55768 28654 55769 27997 55769 28655 55769 28655 55770 27997 55770 27998 55770 28655 55771 27998 55771 28003 55771 28003 55772 27998 55772 28004 55772 28009 55773 29612 55773 28010 55773 28010 55774 29612 55774 28005 55774 28010 55775 28005 55775 28011 55775 28011 55776 28005 55776 29610 55776 28011 55777 29610 55777 28006 55777 28006 55778 29610 55778 29606 55778 28006 55779 29606 55779 28007 55779 28007 55780 29606 55780 29608 55780 28007 55781 29608 55781 28014 55781 28014 55782 29608 55782 29609 55782 28014 55783 29609 55783 28970 55783 28970 55784 29609 55784 28008 55784 28709 55785 28009 55785 28710 55785 28710 55786 28009 55786 28010 55786 28710 55787 28010 55787 28711 55787 28711 55788 28010 55788 28011 55788 28711 55789 28011 55789 28012 55789 28012 55790 28011 55790 28006 55790 28012 55791 28006 55791 28712 55791 28712 55792 28006 55792 28007 55792 28712 55793 28007 55793 28013 55793 28013 55794 28007 55794 28014 55794 28013 55795 28014 55795 28964 55795 28964 55796 28014 55796 28970 55796 28015 55797 29453 55797 28032 55797 28032 55798 28033 55798 28015 55798 28015 55799 28033 55799 28016 55799 28015 55800 28016 55800 28018 55800 28016 55801 28017 55801 28018 55801 28018 55802 28017 55802 28031 55802 28018 55803 28031 55803 29459 55803 29459 55804 28031 55804 28030 55804 29459 55805 28030 55805 28019 55805 28030 55806 28028 55806 28019 55806 28019 55807 28028 55807 28020 55807 28019 55808 28020 55808 28022 55808 28020 55809 28021 55809 28022 55809 28022 55810 28021 55810 28025 55810 28022 55811 28025 55811 28023 55811 28960 55812 28963 55812 28026 55812 28026 55813 28963 55813 28023 55813 28026 55814 28023 55814 28024 55814 28024 55815 28023 55815 28025 55815 28959 55816 28960 55816 28026 55816 28959 55817 28026 55817 28672 55817 28672 55818 28026 55818 28024 55818 28672 55819 28024 55819 28027 55819 28024 55820 28025 55820 28027 55820 28027 55821 28025 55821 28021 55821 28027 55822 28021 55822 28029 55822 28029 55823 28021 55823 28020 55823 28020 55824 28028 55824 28029 55824 28029 55825 28028 55825 28030 55825 28029 55826 28030 55826 28668 55826 28030 55827 28031 55827 28668 55827 28668 55828 28031 55828 28017 55828 28668 55829 28017 55829 28673 55829 28032 55830 28674 55830 28033 55830 28033 55831 28674 55831 28673 55831 28033 55832 28673 55832 28016 55832 28016 55833 28673 55833 28017 55833 28035 55834 29471 55834 28034 55834 28034 55835 28051 55835 28035 55835 28035 55836 28051 55836 28036 55836 28035 55837 28036 55837 28037 55837 28036 55838 28038 55838 28037 55838 28037 55839 28038 55839 28050 55839 28037 55840 28050 55840 29476 55840 29476 55841 28050 55841 28049 55841 29476 55842 28049 55842 28039 55842 28049 55843 28040 55843 28039 55843 28039 55844 28040 55844 28041 55844 28039 55845 28041 55845 28042 55845 28041 55846 28043 55846 28042 55846 28042 55847 28043 55847 28044 55847 28042 55848 28044 55848 28045 55848 28948 55849 28951 55849 28046 55849 28046 55850 28951 55850 28045 55850 28046 55851 28045 55851 28047 55851 28047 55852 28045 55852 28044 55852 28946 55853 28948 55853 28046 55853 28946 55854 28046 55854 28526 55854 28526 55855 28046 55855 28047 55855 28526 55856 28047 55856 28523 55856 28047 55857 28044 55857 28523 55857 28523 55858 28044 55858 28043 55858 28523 55859 28043 55859 28531 55859 28531 55860 28043 55860 28041 55860 28041 55861 28040 55861 28531 55861 28531 55862 28040 55862 28049 55862 28531 55863 28049 55863 28048 55863 28049 55864 28050 55864 28048 55864 28048 55865 28050 55865 28038 55865 28048 55866 28038 55866 28534 55866 28034 55867 28533 55867 28051 55867 28051 55868 28533 55868 28534 55868 28051 55869 28534 55869 28036 55869 28036 55870 28534 55870 28038 55870 28060 55871 29631 55871 28052 55871 28052 55872 29631 55872 29629 55872 28052 55873 29629 55873 28053 55873 28053 55874 29629 55874 28054 55874 28053 55875 28054 55875 28055 55875 28055 55876 28054 55876 28056 55876 28055 55877 28056 55877 28063 55877 28063 55878 28056 55878 28057 55878 28063 55879 28057 55879 28058 55879 28058 55880 28057 55880 29626 55880 28058 55881 29626 55881 28928 55881 28928 55882 29626 55882 29620 55882 28059 55883 28060 55883 28681 55883 28681 55884 28060 55884 28052 55884 28681 55885 28052 55885 28061 55885 28061 55886 28052 55886 28053 55886 28061 55887 28053 55887 28678 55887 28678 55888 28053 55888 28055 55888 28678 55889 28055 55889 28062 55889 28062 55890 28055 55890 28063 55890 28062 55891 28063 55891 28677 55891 28677 55892 28063 55892 28058 55892 28677 55893 28058 55893 28927 55893 28927 55894 28058 55894 28928 55894 28070 55895 29491 55895 28064 55895 28064 55896 29491 55896 28065 55896 28064 55897 28065 55897 28071 55897 28071 55898 28065 55898 28066 55898 28071 55899 28066 55899 28067 55899 28067 55900 28066 55900 28068 55900 28067 55901 28068 55901 28073 55901 28073 55902 28068 55902 29600 55902 28073 55903 29600 55903 28074 55903 28074 55904 29600 55904 29599 55904 28074 55905 29599 55905 28923 55905 28923 55906 29599 55906 29616 55906 28069 55907 28070 55907 28685 55907 28685 55908 28070 55908 28064 55908 28685 55909 28064 55909 28686 55909 28686 55910 28064 55910 28071 55910 28686 55911 28071 55911 28072 55911 28072 55912 28071 55912 28067 55912 28072 55913 28067 55913 28687 55913 28687 55914 28067 55914 28073 55914 28687 55915 28073 55915 28688 55915 28688 55916 28073 55916 28074 55916 28688 55917 28074 55917 28075 55917 28075 55918 28074 55918 28923 55918 28085 55919 28076 55919 28109 55919 28102 55920 28104 55920 28737 55920 28737 55921 28104 55921 28077 55921 28078 55922 28083 55922 28468 55922 28468 55923 28467 55923 28078 55923 28078 55924 28467 55924 28466 55924 28078 55925 28466 55925 28104 55925 28104 55926 28466 55926 28079 55926 28104 55927 28079 55927 28077 55927 28105 55928 28106 55928 28469 55928 28469 55929 28080 55929 28105 55929 28105 55930 28080 55930 28081 55930 28105 55931 28081 55931 28083 55931 28083 55932 28081 55932 28082 55932 28083 55933 28082 55933 28468 55933 28109 55934 28076 55934 28107 55934 28076 55935 28084 55935 28107 55935 28107 55936 28084 55936 28473 55936 28107 55937 28473 55937 28106 55937 28106 55938 28473 55938 28472 55938 28106 55939 28472 55939 28469 55939 28085 55940 28109 55940 28474 55940 28474 55941 28109 55941 28086 55941 28474 55942 28086 55942 28476 55942 28476 55943 28086 55943 28111 55943 28476 55944 28111 55944 28477 55944 28477 55945 28111 55945 28479 55945 28479 55946 28111 55946 28087 55946 28479 55947 28087 55947 28480 55947 28480 55948 28087 55948 28088 55948 28088 55949 28087 55949 28089 55949 28088 55950 28089 55950 28482 55950 28482 55951 28089 55951 28484 55951 28484 55952 28089 55952 28112 55952 28484 55953 28112 55953 28485 55953 28485 55954 28112 55954 28090 55954 28090 55955 28112 55955 28114 55955 28090 55956 28114 55956 28091 55956 28091 55957 28114 55957 28487 55957 28487 55958 28114 55958 28115 55958 28487 55959 28115 55959 28488 55959 28488 55960 28115 55960 28092 55960 28092 55961 28115 55961 28093 55961 28092 55962 28093 55962 28490 55962 28490 55963 28093 55963 28884 55963 28490 55964 28884 55964 28489 55964 28899 55965 28120 55965 28094 55965 28094 55966 28120 55966 28095 55966 28094 55967 28095 55967 28902 55967 28902 55968 28095 55968 28096 55968 28902 55969 28096 55969 28904 55969 28904 55970 28096 55970 28127 55970 28904 55971 28127 55971 28097 55971 28097 55972 28127 55972 28098 55972 28097 55973 28098 55973 28907 55973 28907 55974 28098 55974 28099 55974 28907 55975 28099 55975 28101 55975 28101 55976 28099 55976 28100 55976 28101 55977 28100 55977 28908 55977 28908 55978 28100 55978 28103 55978 28908 55979 28103 55979 28102 55979 28102 55980 28103 55980 28121 55980 28102 55981 28121 55981 28104 55981 28104 55982 28121 55982 28882 55982 28104 55983 28882 55983 28078 55983 28078 55984 28882 55984 28881 55984 28078 55985 28881 55985 28083 55985 28083 55986 28881 55986 28880 55986 28083 55987 28880 55987 28105 55987 28105 55988 28880 55988 28879 55988 28105 55989 28879 55989 28106 55989 28106 55990 28879 55990 28108 55990 28106 55991 28108 55991 28107 55991 28107 55992 28108 55992 28877 55992 28107 55993 28877 55993 28109 55993 28109 55994 28877 55994 28110 55994 28109 55995 28110 55995 28086 55995 28110 55996 28876 55996 28086 55996 28086 55997 28876 55997 28874 55997 28086 55998 28874 55998 28111 55998 28111 55999 28874 55999 28873 55999 28111 56000 28873 56000 28087 56000 28087 56001 28873 56001 28871 56001 28087 56002 28871 56002 28089 56002 28089 56003 28871 56003 28870 56003 28089 56004 28870 56004 28112 56004 28112 56005 28870 56005 28113 56005 28112 56006 28113 56006 28114 56006 28114 56007 28113 56007 28869 56007 28114 56008 28869 56008 28115 56008 28115 56009 28869 56009 28868 56009 28115 56010 28868 56010 28093 56010 28093 56011 28868 56011 28867 56011 28093 56012 28867 56012 28884 56012 28884 56013 28867 56013 28142 56013 28884 56014 28142 56014 28885 56014 28885 56015 28142 56015 28140 56015 28885 56016 28140 56016 28116 56016 28116 56017 28140 56017 28139 56017 28116 56018 28139 56018 28892 56018 28892 56019 28139 56019 28137 56019 28892 56020 28137 56020 28890 56020 28890 56021 28137 56021 28118 56021 28890 56022 28118 56022 28117 56022 28117 56023 28118 56023 28135 56023 28117 56024 28135 56024 28894 56024 28894 56025 28135 56025 28134 56025 28894 56026 28134 56026 28119 56026 28119 56027 28134 56027 28133 56027 28119 56028 28133 56028 28899 56028 28899 56029 28133 56029 28131 56029 28899 56030 28131 56030 28120 56030 27596 56031 28121 56031 28122 56031 28122 56032 28121 56032 28103 56032 28122 56033 28103 56033 28123 56033 28123 56034 28103 56034 28100 56034 28123 56035 28100 56035 28124 56035 28124 56036 28100 56036 28099 56036 28124 56037 28099 56037 28125 56037 28125 56038 28099 56038 28098 56038 28125 56039 28098 56039 28126 56039 28126 56040 28098 56040 28127 56040 28126 56041 28127 56041 27592 56041 27592 56042 28127 56042 28096 56042 27592 56043 28096 56043 28128 56043 28128 56044 28096 56044 28095 56044 28128 56045 28095 56045 28129 56045 28129 56046 28095 56046 28120 56046 28129 56047 28120 56047 28130 56047 28130 56048 28120 56048 28131 56048 28130 56049 28131 56049 27587 56049 27587 56050 28131 56050 28133 56050 27587 56051 28133 56051 28132 56051 28132 56052 28133 56052 28134 56052 28132 56053 28134 56053 28136 56053 28136 56054 28134 56054 28135 56054 28136 56055 28135 56055 27585 56055 27585 56056 28135 56056 28118 56056 27585 56057 28118 56057 27584 56057 27584 56058 28118 56058 28137 56058 27584 56059 28137 56059 27581 56059 27581 56060 28137 56060 28139 56060 27581 56061 28139 56061 28138 56061 28138 56062 28139 56062 28140 56062 28138 56063 28140 56063 28141 56063 28141 56064 28140 56064 28142 56064 29356 56065 27562 56065 28143 56065 28143 56066 27562 56066 28144 56066 28143 56067 28144 56067 28145 56067 28145 56068 28144 56068 27565 56068 28145 56069 27565 56069 29360 56069 29360 56070 27565 56070 28146 56070 29360 56071 28146 56071 28147 56071 28147 56072 28146 56072 28148 56072 28147 56073 28148 56073 29362 56073 29362 56074 28148 56074 28150 56074 29362 56075 28150 56075 28149 56075 28149 56076 28150 56076 27568 56076 28149 56077 27568 56077 29364 56077 29364 56078 27568 56078 28151 56078 29364 56079 28151 56079 28152 56079 28152 56080 28151 56080 27569 56080 28152 56081 27569 56081 28153 56081 28153 56082 27569 56082 28155 56082 28153 56083 28155 56083 28154 56083 28154 56084 28155 56084 28156 56084 28154 56085 28156 56085 29368 56085 29368 56086 28156 56086 27571 56086 29368 56087 27571 56087 29371 56087 29371 56088 27571 56088 28157 56088 29371 56089 28157 56089 29373 56089 29373 56090 28157 56090 27574 56090 29373 56091 27574 56091 28158 56091 28158 56092 27574 56092 27577 56092 28158 56093 27577 56093 28159 56093 28159 56094 27577 56094 27579 56094 28159 56095 27579 56095 28160 56095 28160 56096 27579 56096 29375 56096 28160 56097 29375 56097 27580 56097 27580 56098 29375 56098 28161 56098 27580 56099 28161 56099 27582 56099 27582 56100 28161 56100 29377 56100 27582 56101 29377 56101 27583 56101 27583 56102 29377 56102 29378 56102 27583 56103 29378 56103 28162 56103 28162 56104 29378 56104 29380 56104 28162 56105 29380 56105 27586 56105 27586 56106 29380 56106 28163 56106 27586 56107 28163 56107 27588 56107 27588 56108 28163 56108 28164 56108 27588 56109 28164 56109 27589 56109 27589 56110 28164 56110 28166 56110 27589 56111 28166 56111 28165 56111 28165 56112 28166 56112 29382 56112 28165 56113 29382 56113 27590 56113 27590 56114 29382 56114 28167 56114 27590 56115 28167 56115 27591 56115 27591 56116 28167 56116 29384 56116 27591 56117 29384 56117 28168 56117 28168 56118 29384 56118 28169 56118 28168 56119 28169 56119 27593 56119 27593 56120 28169 56120 28170 56120 27593 56121 28170 56121 27594 56121 27594 56122 28170 56122 28171 56122 27594 56123 28171 56123 27595 56123 27595 56124 28171 56124 28172 56124 27595 56125 28172 56125 28173 56125 28173 56126 28172 56126 28174 56126 28173 56127 28174 56127 28175 56127 28175 56128 28174 56128 28176 56128 28175 56129 28176 56129 29355 56129 29355 56130 28176 56130 27560 56130 29355 56131 27560 56131 29356 56131 29356 56132 27560 56132 27562 56132 28177 56133 28218 56133 28219 56133 28177 56134 28219 56134 27561 56134 27561 56135 28219 56135 28220 56135 27561 56136 28220 56136 27563 56136 27563 56137 28220 56137 28221 56137 27563 56138 28221 56138 27564 56138 27564 56139 28221 56139 28178 56139 27564 56140 28178 56140 28179 56140 28179 56141 28178 56141 28180 56141 28179 56142 28180 56142 27566 56142 27566 56143 28180 56143 28181 56143 27566 56144 28181 56144 27567 56144 27567 56145 28181 56145 28224 56145 27567 56146 28224 56146 28182 56146 28182 56147 28224 56147 28183 56147 28182 56148 28183 56148 28184 56148 28184 56149 28183 56149 28192 56149 28184 56150 28192 56150 28185 56150 28185 56151 28192 56151 28186 56151 28185 56152 28186 56152 28187 56152 28187 56153 28186 56153 28194 56153 28187 56154 28194 56154 27570 56154 27570 56155 28194 56155 28188 56155 27570 56156 28188 56156 27572 56156 27572 56157 28188 56157 28189 56157 27572 56158 28189 56158 27573 56158 27573 56159 28189 56159 28196 56159 27573 56160 28196 56160 27575 56160 27575 56161 28196 56161 28190 56161 27575 56162 28190 56162 27576 56162 27576 56163 28190 56163 28198 56163 27576 56164 28198 56164 27578 56164 27578 56165 28198 56165 28199 56165 27578 56166 28199 56166 28850 56166 28224 56167 28191 56167 28183 56167 28183 56168 28191 56168 28841 56168 28183 56169 28841 56169 28192 56169 28192 56170 28841 56170 28193 56170 28192 56171 28193 56171 28186 56171 28186 56172 28193 56172 28840 56172 28186 56173 28840 56173 28194 56173 28194 56174 28840 56174 28839 56174 28194 56175 28839 56175 28188 56175 28188 56176 28839 56176 28195 56176 28188 56177 28195 56177 28189 56177 28189 56178 28195 56178 28836 56178 28189 56179 28836 56179 28196 56179 28196 56180 28836 56180 28197 56180 28196 56181 28197 56181 28190 56181 28190 56182 28197 56182 28834 56182 28190 56183 28834 56183 28198 56183 28198 56184 28834 56184 28833 56184 28198 56185 28833 56185 28199 56185 28199 56186 28833 56186 28832 56186 28199 56187 28832 56187 28200 56187 28200 56188 28832 56188 28201 56188 28200 56189 28201 56189 28852 56189 28852 56190 28201 56190 28202 56190 28852 56191 28202 56191 28854 56191 28854 56192 28202 56192 28204 56192 28854 56193 28204 56193 28203 56193 28203 56194 28204 56194 28241 56194 28203 56195 28241 56195 28205 56195 28205 56196 28241 56196 28238 56196 28205 56197 28238 56197 28207 56197 28207 56198 28238 56198 28206 56198 28207 56199 28206 56199 28857 56199 28857 56200 28206 56200 28236 56200 28857 56201 28236 56201 28208 56201 28208 56202 28236 56202 28234 56202 28208 56203 28234 56203 28860 56203 28860 56204 28234 56204 28209 56204 28860 56205 28209 56205 28861 56205 28861 56206 28209 56206 28232 56206 28861 56207 28232 56207 28862 56207 28862 56208 28232 56208 28230 56208 28862 56209 28230 56209 28863 56209 28863 56210 28230 56210 28211 56210 28863 56211 28211 56211 28210 56211 28210 56212 28211 56212 28212 56212 28210 56213 28212 56213 28213 56213 28213 56214 28212 56214 28214 56214 28213 56215 28214 56215 28215 56215 28215 56216 28214 56216 28227 56216 28215 56217 28227 56217 28216 56217 28216 56218 28227 56218 28217 56218 28216 56219 28217 56219 28218 56219 28218 56220 28217 56220 28225 56220 28218 56221 28225 56221 28219 56221 28219 56222 28225 56222 28849 56222 28219 56223 28849 56223 28220 56223 28220 56224 28849 56224 28222 56224 28220 56225 28222 56225 28221 56225 28221 56226 28222 56226 28847 56226 28221 56227 28847 56227 28178 56227 28178 56228 28847 56228 28845 56228 28178 56229 28845 56229 28180 56229 28180 56230 28845 56230 28844 56230 28180 56231 28844 56231 28181 56231 28181 56232 28844 56232 28223 56232 28181 56233 28223 56233 28224 56233 28224 56234 28223 56234 28191 56234 29428 56235 28225 56235 28226 56235 28226 56236 28225 56236 28217 56236 28226 56237 28217 56237 27525 56237 27525 56238 28217 56238 28227 56238 27525 56239 28227 56239 28228 56239 28228 56240 28227 56240 28214 56240 28228 56241 28214 56241 28229 56241 28229 56242 28214 56242 28212 56242 28229 56243 28212 56243 27522 56243 27522 56244 28212 56244 28211 56244 27522 56245 28211 56245 27519 56245 27519 56246 28211 56246 28230 56246 27519 56247 28230 56247 28231 56247 28231 56248 28230 56248 28232 56248 28231 56249 28232 56249 27517 56249 27517 56250 28232 56250 28209 56250 27517 56251 28209 56251 28233 56251 28233 56252 28209 56252 28234 56252 28233 56253 28234 56253 28235 56253 28235 56254 28234 56254 28236 56254 28235 56255 28236 56255 28237 56255 28237 56256 28236 56256 28206 56256 28237 56257 28206 56257 27515 56257 27515 56258 28206 56258 28238 56258 27515 56259 28238 56259 28239 56259 28239 56260 28238 56260 28241 56260 28239 56261 28241 56261 28240 56261 28240 56262 28241 56262 28204 56262 28240 56263 28204 56263 28242 56263 28242 56264 28204 56264 28202 56264 28242 56265 28202 56265 27512 56265 27512 56266 28202 56266 28201 56266 27512 56267 28201 56267 28243 56267 28243 56268 28201 56268 28832 56268 27521 56269 28282 56269 27523 56269 27523 56270 28282 56270 28281 56270 27523 56271 28281 56271 27524 56271 27524 56272 28281 56272 28244 56272 27524 56273 28244 56273 28245 56273 28245 56274 28244 56274 28246 56274 28245 56275 28246 56275 27526 56275 27526 56276 28246 56276 28247 56276 27526 56277 28247 56277 27527 56277 27527 56278 28247 56278 28276 56278 27527 56279 28276 56279 28248 56279 28248 56280 28276 56280 28275 56280 28248 56281 28275 56281 29430 56281 29430 56282 28275 56282 28249 56282 29430 56283 28249 56283 28250 56283 28250 56284 28249 56284 28830 56284 28250 56285 28830 56285 28251 56285 28251 56286 28830 56286 28252 56286 28251 56287 28252 56287 28253 56287 28253 56288 28252 56288 28829 56288 28253 56289 28829 56289 28254 56289 28254 56290 28829 56290 28827 56290 28254 56291 28827 56291 28255 56291 28255 56292 28827 56292 28825 56292 28255 56293 28825 56293 28256 56293 28256 56294 28825 56294 28824 56294 28256 56295 28824 56295 29434 56295 29434 56296 28824 56296 28258 56296 29434 56297 28258 56297 28257 56297 28257 56298 28258 56298 28259 56298 28257 56299 28259 56299 29437 56299 29437 56300 28259 56300 28820 56300 29437 56301 28820 56301 29438 56301 29438 56302 28820 56302 28819 56302 29438 56303 28819 56303 29439 56303 29439 56304 28819 56304 28816 56304 29439 56305 28816 56305 28260 56305 28260 56306 28816 56306 28261 56306 28260 56307 28261 56307 29441 56307 29441 56308 28261 56308 28262 56308 29441 56309 28262 56309 29444 56309 29444 56310 28262 56310 28814 56310 29444 56311 28814 56311 29445 56311 29445 56312 28814 56312 28813 56312 29445 56313 28813 56313 28263 56313 28263 56314 28813 56314 28264 56314 28263 56315 28264 56315 27513 56315 27513 56316 28264 56316 28290 56316 27513 56317 28290 56317 28266 56317 28266 56318 28290 56318 28265 56318 28266 56319 28265 56319 28267 56319 28267 56320 28265 56320 28268 56320 28267 56321 28268 56321 27514 56321 27514 56322 28268 56322 28270 56322 27514 56323 28270 56323 28269 56323 28269 56324 28270 56324 28288 56324 28269 56325 28288 56325 28271 56325 28271 56326 28288 56326 28286 56326 28271 56327 28286 56327 27516 56327 27516 56328 28286 56328 28285 56328 27516 56329 28285 56329 27518 56329 27518 56330 28285 56330 28272 56330 27518 56331 28272 56331 28273 56331 28273 56332 28272 56332 28284 56332 28273 56333 28284 56333 27520 56333 27520 56334 28284 56334 28274 56334 27520 56335 28274 56335 27521 56335 27521 56336 28274 56336 28282 56336 28831 56337 28275 56337 27542 56337 27542 56338 28275 56338 28276 56338 27542 56339 28276 56339 28277 56339 28277 56340 28276 56340 28247 56340 28277 56341 28247 56341 28278 56341 28278 56342 28247 56342 28246 56342 28278 56343 28246 56343 28279 56343 28279 56344 28246 56344 28244 56344 28279 56345 28244 56345 28280 56345 28280 56346 28244 56346 28281 56346 28280 56347 28281 56347 27538 56347 27538 56348 28281 56348 28282 56348 27538 56349 28282 56349 27537 56349 27537 56350 28282 56350 28274 56350 27537 56351 28274 56351 28283 56351 28283 56352 28274 56352 28284 56352 28283 56353 28284 56353 27536 56353 27536 56354 28284 56354 28272 56354 27536 56355 28272 56355 27535 56355 27535 56356 28272 56356 28285 56356 27535 56357 28285 56357 27533 56357 27533 56358 28285 56358 28286 56358 27533 56359 28286 56359 27531 56359 27531 56360 28286 56360 28288 56360 27531 56361 28288 56361 28287 56361 28287 56362 28288 56362 28270 56362 28287 56363 28270 56363 28289 56363 28289 56364 28270 56364 28268 56364 28289 56365 28268 56365 27529 56365 27529 56366 28268 56366 28265 56366 27529 56367 28265 56367 27528 56367 27528 56368 28265 56368 28290 56368 27528 56369 28290 56369 28812 56369 28812 56370 28290 56370 28264 56370 28326 56371 28327 56371 29414 56371 29414 56372 28327 56372 28291 56372 29414 56373 28291 56373 29415 56373 29415 56374 28291 56374 28292 56374 29415 56375 28292 56375 28293 56375 28293 56376 28292 56376 28294 56376 28293 56377 28294 56377 29417 56377 29417 56378 28294 56378 27550 56378 29417 56379 27550 56379 28295 56379 28295 56380 27550 56380 28296 56380 28295 56381 28296 56381 29418 56381 29418 56382 28296 56382 28297 56382 29418 56383 28297 56383 29419 56383 29419 56384 28297 56384 27554 56384 29419 56385 27554 56385 28298 56385 28298 56386 27554 56386 28299 56386 28298 56387 28299 56387 29422 56387 29422 56388 28299 56388 28300 56388 29422 56389 28300 56389 29423 56389 29423 56390 28300 56390 27557 56390 29423 56391 27557 56391 28301 56391 28301 56392 27557 56392 27558 56392 28301 56393 27558 56393 29424 56393 29424 56394 27558 56394 28302 56394 29424 56395 28302 56395 29427 56395 29427 56396 28302 56396 28303 56396 29427 56397 28303 56397 28304 56397 28304 56398 28303 56398 28305 56398 28304 56399 28305 56399 28306 56399 28306 56400 28305 56400 29389 56400 28306 56401 29389 56401 28307 56401 28307 56402 29389 56402 29392 56402 28307 56403 29392 56403 28309 56403 29392 56404 28308 56404 28309 56404 28309 56405 28308 56405 29393 56405 28309 56406 29393 56406 27530 56406 27530 56407 29393 56407 29394 56407 27530 56408 29394 56408 27532 56408 27532 56409 29394 56409 28310 56409 27532 56410 28310 56410 27534 56410 27534 56411 28310 56411 29396 56411 27534 56412 29396 56412 28311 56412 28311 56413 29396 56413 29399 56413 28311 56414 29399 56414 28312 56414 28312 56415 29399 56415 28314 56415 28312 56416 28314 56416 28313 56416 28313 56417 28314 56417 29401 56417 28313 56418 29401 56418 27539 56418 27539 56419 29401 56419 29402 56419 27539 56420 29402 56420 28316 56420 28316 56421 29402 56421 28315 56421 28316 56422 28315 56422 28317 56422 28317 56423 28315 56423 28318 56423 28317 56424 28318 56424 27540 56424 27540 56425 28318 56425 29406 56425 27540 56426 29406 56426 28319 56426 28319 56427 29406 56427 28320 56427 28319 56428 28320 56428 27541 56428 27541 56429 28320 56429 29408 56429 27541 56430 29408 56430 28321 56430 28321 56431 29408 56431 28323 56431 28321 56432 28323 56432 28322 56432 28322 56433 28323 56433 27543 56433 28322 56434 27543 56434 29411 56434 29411 56435 27543 56435 28324 56435 29411 56436 28324 56436 28325 56436 28325 56437 28324 56437 27545 56437 28325 56438 27545 56438 28326 56438 28326 56439 27545 56439 27547 56439 28326 56440 27547 56440 28327 56440 29409 56441 28349 56441 28328 56441 29409 56442 28328 56442 27544 56442 27544 56443 28328 56443 28351 56443 27544 56444 28351 56444 28329 56444 28329 56445 28351 56445 28352 56445 28329 56446 28352 56446 27546 56446 27546 56447 28352 56447 28353 56447 27546 56448 28353 56448 28330 56448 28330 56449 28353 56449 28356 56449 28330 56450 28356 56450 27548 56450 27548 56451 28356 56451 28331 56451 27548 56452 28331 56452 28332 56452 28332 56453 28331 56453 28333 56453 28332 56454 28333 56454 28334 56454 28334 56455 28333 56455 28335 56455 28334 56456 28335 56456 27549 56456 27549 56457 28335 56457 28336 56457 27549 56458 28336 56458 27551 56458 27551 56459 28336 56459 28360 56459 27551 56460 28360 56460 27552 56460 27552 56461 28360 56461 28361 56461 27552 56462 28361 56462 27553 56462 27553 56463 28361 56463 28362 56463 27553 56464 28362 56464 27555 56464 27555 56465 28362 56465 28337 56465 27555 56466 28337 56466 27556 56466 27556 56467 28337 56467 28338 56467 27556 56468 28338 56468 28339 56468 28339 56469 28338 56469 28364 56469 28339 56470 28364 56470 28341 56470 28341 56471 28364 56471 28340 56471 28341 56472 28340 56472 28342 56472 28342 56473 28340 56473 28343 56473 28342 56474 28343 56474 27559 56474 27559 56475 28343 56475 28344 56475 27559 56476 28344 56476 28797 56476 28345 56477 29350 56477 28808 56477 28808 56478 29350 56478 28346 56478 28808 56479 28346 56479 28347 56479 28347 56480 28346 56480 29351 56480 28347 56481 29351 56481 28810 56481 28810 56482 29351 56482 28348 56482 28810 56483 28348 56483 28349 56483 28349 56484 28348 56484 28350 56484 28349 56485 28350 56485 28328 56485 28328 56486 28350 56486 27597 56486 28328 56487 27597 56487 28351 56487 28351 56488 27597 56488 27598 56488 28351 56489 27598 56489 28352 56489 28352 56490 27598 56490 28354 56490 28352 56491 28354 56491 28353 56491 28353 56492 28354 56492 28355 56492 28353 56493 28355 56493 28356 56493 28356 56494 28355 56494 27599 56494 28356 56495 27599 56495 28331 56495 28331 56496 27599 56496 28357 56496 28331 56497 28357 56497 28333 56497 28333 56498 28357 56498 28358 56498 28333 56499 28358 56499 28335 56499 28335 56500 28358 56500 28359 56500 28335 56501 28359 56501 28336 56501 28336 56502 28359 56502 27600 56502 28336 56503 27600 56503 28360 56503 28360 56504 27600 56504 27601 56504 28360 56505 27601 56505 28361 56505 28361 56506 27601 56506 27603 56506 28361 56507 27603 56507 28362 56507 28362 56508 27603 56508 27604 56508 28362 56509 27604 56509 28337 56509 28337 56510 27604 56510 27605 56510 28337 56511 27605 56511 28338 56511 28338 56512 27605 56512 27606 56512 28338 56513 27606 56513 28364 56513 28364 56514 27606 56514 28363 56514 28364 56515 28363 56515 28340 56515 28340 56516 28363 56516 27610 56516 28340 56517 27610 56517 28343 56517 28343 56518 27610 56518 28365 56518 28343 56519 28365 56519 28344 56519 28344 56520 28365 56520 28366 56520 28344 56521 28366 56521 28367 56521 28367 56522 28366 56522 28368 56522 28367 56523 28368 56523 28798 56523 28798 56524 28368 56524 28369 56524 28798 56525 28369 56525 28799 56525 28799 56526 28369 56526 29341 56526 28799 56527 29341 56527 28800 56527 28800 56528 29341 56528 29343 56528 28800 56529 29343 56529 28370 56529 28370 56530 29343 56530 29344 56530 28370 56531 29344 56531 28371 56531 28371 56532 29344 56532 28372 56532 28371 56533 28372 56533 28803 56533 28803 56534 28372 56534 28374 56534 28803 56535 28374 56535 28373 56535 28373 56536 28374 56536 29345 56536 28373 56537 29345 56537 28375 56537 28375 56538 29345 56538 28376 56538 28375 56539 28376 56539 28377 56539 28377 56540 28376 56540 28379 56540 28377 56541 28379 56541 28378 56541 28378 56542 28379 56542 28380 56542 28378 56543 28380 56543 28806 56543 28806 56544 28380 56544 28381 56544 28806 56545 28381 56545 28807 56545 28807 56546 28381 56546 29349 56546 28807 56547 29349 56547 28345 56547 28345 56548 29349 56548 29350 56548 29353 56549 28796 56549 28382 56549 29353 56550 28382 56550 28384 56550 28384 56551 28382 56551 28383 56551 28384 56552 28383 56552 28385 56552 28385 56553 28383 56553 28419 56553 28385 56554 28419 56554 28386 56554 28386 56555 28419 56555 28417 56555 28386 56556 28417 56556 28387 56556 28387 56557 28417 56557 28388 56557 28387 56558 28388 56558 28389 56558 28389 56559 28388 56559 28390 56559 28389 56560 28390 56560 28391 56560 28391 56561 28390 56561 28415 56561 28391 56562 28415 56562 28392 56562 28392 56563 28415 56563 28393 56563 28392 56564 28393 56564 28394 56564 28394 56565 28393 56565 28414 56565 28394 56566 28414 56566 28395 56566 28395 56567 28414 56567 28413 56567 28395 56568 28413 56568 27602 56568 27602 56569 28413 56569 28411 56569 27602 56570 28411 56570 28396 56570 28396 56571 28411 56571 28409 56571 28396 56572 28409 56572 28397 56572 28397 56573 28409 56573 28407 56573 28397 56574 28407 56574 28398 56574 28398 56575 28407 56575 28399 56575 28398 56576 28399 56576 28400 56576 28400 56577 28399 56577 28401 56577 28400 56578 28401 56578 27607 56578 27607 56579 28401 56579 28402 56579 27607 56580 28402 56580 27608 56580 27608 56581 28402 56581 28403 56581 27608 56582 28403 56582 27609 56582 27609 56583 28403 56583 28404 56583 27609 56584 28404 56584 27611 56584 28405 56585 28404 56585 28403 56585 28405 56586 28403 56586 28428 56586 28428 56587 28403 56587 28402 56587 28428 56588 28402 56588 28429 56588 28429 56589 28402 56589 28401 56589 28429 56590 28401 56590 28430 56590 28430 56591 28401 56591 28399 56591 28430 56592 28399 56592 28406 56592 28406 56593 28399 56593 28407 56593 28406 56594 28407 56594 28423 56594 28423 56595 28407 56595 28409 56595 28423 56596 28409 56596 28408 56596 28408 56597 28409 56597 28411 56597 28408 56598 28411 56598 28410 56598 28410 56599 28411 56599 28413 56599 28410 56600 28413 56600 28412 56600 28412 56601 28413 56601 28414 56601 28412 56602 28414 56602 28435 56602 28435 56603 28414 56603 28393 56603 28435 56604 28393 56604 28436 56604 28436 56605 28393 56605 28415 56605 28436 56606 28415 56606 28416 56606 28416 56607 28415 56607 28390 56607 28416 56608 28390 56608 28440 56608 28440 56609 28390 56609 28388 56609 28440 56610 28388 56610 28441 56610 28441 56611 28388 56611 28417 56611 28441 56612 28417 56612 28418 56612 28418 56613 28417 56613 28419 56613 28418 56614 28419 56614 28420 56614 28420 56615 28419 56615 28383 56615 28420 56616 28383 56616 28432 56616 28432 56617 28383 56617 28382 56617 28432 56618 28382 56618 28421 56618 28421 56619 28382 56619 28796 56619 28421 56620 28796 56620 28422 56620 28463 56621 28430 56621 28461 56621 28461 56622 28430 56622 28406 56622 28461 56623 28406 56623 28459 56623 28459 56624 28406 56624 28423 56624 28459 56625 28423 56625 28424 56625 28424 56626 28423 56626 28408 56626 28424 56627 28408 56627 28425 56627 28425 56628 28408 56628 28410 56628 28425 56629 28410 56629 28456 56629 28744 56630 28450 56630 28743 56630 28743 56631 28450 56631 28427 56631 28743 56632 28427 56632 28426 56632 28426 56633 28427 56633 28775 56633 28426 56634 28775 56634 28740 56634 28740 56635 28775 56635 28405 56635 28740 56636 28405 56636 28464 56636 28464 56637 28405 56637 28428 56637 28464 56638 28428 56638 28463 56638 28463 56639 28428 56639 28429 56639 28463 56640 28429 56640 28430 56640 28431 56641 28420 56641 28452 56641 28452 56642 28420 56642 28432 56642 28452 56643 28432 56643 28433 56643 28433 56644 28432 56644 28421 56644 28433 56645 28421 56645 28434 56645 28434 56646 28421 56646 28422 56646 28434 56647 28422 56647 28759 56647 28759 56648 28422 56648 28761 56648 28759 56649 28761 56649 28758 56649 28410 56650 28412 56650 28456 56650 28456 56651 28412 56651 28435 56651 28456 56652 28435 56652 28437 56652 28437 56653 28435 56653 28436 56653 28437 56654 28436 56654 28455 56654 28455 56655 28436 56655 28416 56655 28455 56656 28416 56656 28438 56656 28438 56657 28416 56657 28440 56657 28438 56658 28440 56658 28439 56658 28439 56659 28440 56659 28441 56659 28439 56660 28441 56660 28431 56660 28431 56661 28441 56661 28418 56661 28431 56662 28418 56662 28420 56662 28761 56663 28763 56663 28758 56663 28758 56664 28763 56664 28442 56664 28758 56665 28442 56665 28443 56665 28443 56666 28442 56666 28764 56666 28443 56667 28764 56667 28757 56667 28757 56668 28764 56668 28444 56668 28757 56669 28444 56669 28755 56669 28755 56670 28444 56670 28445 56670 28755 56671 28445 56671 28752 56671 28752 56672 28445 56672 28765 56672 28752 56673 28765 56673 28751 56673 28765 56674 28767 56674 28751 56674 28751 56675 28767 56675 28769 56675 28751 56676 28769 56676 28750 56676 28750 56677 28769 56677 28446 56677 28750 56678 28446 56678 28749 56678 28749 56679 28446 56679 28771 56679 28749 56680 28771 56680 28746 56680 28746 56681 28771 56681 28447 56681 28746 56682 28447 56682 28745 56682 28745 56683 28447 56683 28448 56683 28745 56684 28448 56684 28744 56684 28744 56685 28448 56685 28449 56685 28744 56686 28449 56686 28450 56686 28434 56687 27838 56687 28451 56687 28434 56688 28451 56688 28433 56688 28433 56689 28451 56689 27836 56689 28433 56690 27836 56690 28452 56690 28452 56691 27836 56691 28453 56691 28452 56692 28453 56692 28431 56692 28431 56693 28453 56693 27833 56693 28431 56694 27833 56694 28439 56694 28439 56695 27833 56695 27832 56695 28439 56696 27832 56696 28438 56696 28438 56697 27832 56697 28454 56697 28438 56698 28454 56698 28455 56698 28455 56699 28454 56699 27830 56699 28455 56700 27830 56700 28437 56700 28437 56701 27830 56701 27828 56701 28437 56702 27828 56702 28456 56702 28456 56703 27828 56703 27826 56703 28456 56704 27826 56704 28425 56704 28425 56705 27826 56705 28457 56705 28425 56706 28457 56706 28424 56706 28424 56707 28457 56707 28458 56707 28424 56708 28458 56708 28459 56708 28459 56709 28458 56709 28460 56709 28459 56710 28460 56710 28461 56710 28461 56711 28460 56711 28462 56711 28461 56712 28462 56712 28463 56712 28463 56713 28462 56713 27823 56713 28463 56714 27823 56714 28464 56714 28464 56715 27823 56715 29174 56715 28464 56716 29174 56716 28740 56716 28465 56717 29155 56717 28737 56717 28737 56718 28077 56718 28465 56718 28465 56719 28077 56719 28079 56719 28465 56720 28079 56720 27839 56720 27839 56721 28079 56721 28466 56721 28466 56722 28467 56722 27839 56722 27839 56723 28467 56723 28468 56723 27839 56724 28468 56724 28470 56724 28469 56725 27841 56725 27842 56725 28468 56726 28082 56726 28470 56726 28470 56727 28082 56727 28081 56727 28470 56728 28081 56728 27842 56728 27842 56729 28081 56729 28080 56729 27842 56730 28080 56730 28469 56730 28076 56731 27849 56731 28471 56731 28469 56732 28472 56732 27841 56732 27841 56733 28472 56733 28473 56733 27841 56734 28473 56734 28471 56734 28471 56735 28473 56735 28084 56735 28471 56736 28084 56736 28076 56736 28076 56737 28085 56737 27849 56737 27849 56738 28085 56738 28474 56738 27849 56739 28474 56739 28475 56739 28474 56740 28476 56740 28475 56740 28475 56741 28476 56741 28477 56741 28475 56742 28477 56742 28478 56742 28477 56743 28479 56743 28478 56743 28478 56744 28479 56744 28480 56744 28478 56745 28480 56745 28481 56745 28480 56746 28088 56746 28481 56746 28481 56747 28088 56747 28482 56747 28481 56748 28482 56748 28483 56748 28482 56749 28484 56749 28483 56749 28483 56750 28484 56750 28485 56750 28483 56751 28485 56751 27851 56751 28485 56752 28090 56752 27851 56752 27851 56753 28090 56753 28091 56753 27851 56754 28091 56754 28486 56754 28091 56755 28487 56755 28486 56755 28486 56756 28487 56756 28488 56756 28486 56757 28488 56757 28491 56757 28489 56758 29141 56758 28490 56758 28490 56759 29141 56759 28491 56759 28490 56760 28491 56760 28092 56760 28092 56761 28491 56761 28488 56761 28492 56762 28684 56762 28682 56762 20977 56763 28670 56763 28493 56763 20972 56764 28659 56764 28651 56764 28494 56765 28648 56765 28495 56765 28910 56766 28911 56766 28507 56766 28708 56767 28496 56767 28591 56767 28591 56768 28496 56768 28651 56768 20968 56769 20967 56769 28497 56769 28497 56770 20967 56770 28498 56770 29301 56771 28499 56771 28524 56771 27962 56772 28700 56772 28500 56772 28557 56773 28702 56773 27843 56773 28550 56774 28635 56774 28636 56774 28657 56775 28501 56775 28502 56775 28503 56776 27662 56776 28515 56776 28511 56777 28514 56777 29153 56777 28507 56778 27651 56778 27652 56778 27652 56779 27658 56779 28507 56779 28507 56780 27658 56780 27656 56780 28507 56781 27656 56781 28504 56781 28504 56782 27656 56782 29323 56782 28504 56783 29323 56783 29322 56783 29320 56784 29319 56784 28563 56784 28563 56785 29319 56785 29317 56785 28563 56786 29317 56786 29156 56786 29156 56787 29317 56787 27645 56787 29156 56788 27645 56788 28505 56788 28505 56789 27645 56789 27646 56789 28505 56790 27646 56790 28508 56790 28911 56791 28506 56791 28507 56791 28507 56792 28506 56792 28505 56792 28507 56793 28505 56793 27651 56793 27651 56794 28505 56794 28508 56794 28506 56795 28915 56795 28505 56795 28505 56796 28915 56796 28510 56796 28505 56797 28510 56797 28509 56797 28509 56798 28510 56798 28069 56798 28509 56799 28069 56799 28511 56799 28511 56800 28069 56800 28685 56800 29315 56801 28514 56801 28513 56801 28513 56802 28514 56802 28512 56802 28513 56803 28512 56803 28689 56803 29315 56804 29313 56804 28514 56804 28514 56805 29313 56805 29312 56805 28514 56806 29312 56806 29153 56806 29153 56807 29312 56807 27665 56807 29153 56808 27665 56808 29151 56808 29151 56809 27665 56809 28503 56809 28503 56810 28515 56810 29151 56810 29151 56811 28515 56811 28516 56811 29151 56812 28516 56812 28517 56812 28517 56813 28516 56813 28518 56813 28518 56814 28516 56814 28519 56814 28518 56815 28519 56815 29149 56815 29150 56816 28619 56816 27666 56816 28615 56817 28524 56817 28520 56817 28520 56818 28524 56818 28525 56818 28520 56819 28525 56819 27673 56819 27666 56820 27668 56820 29150 56820 29150 56821 27668 56821 27669 56821 29150 56822 27669 56822 28521 56822 28521 56823 27669 56823 27671 56823 28521 56824 27671 56824 28525 56824 28525 56825 27671 56825 28522 56825 28525 56826 28522 56826 27673 56826 28530 56827 28525 56827 28523 56827 28527 56828 28944 56828 28524 56828 28524 56829 28944 56829 28946 56829 28524 56830 28946 56830 28525 56830 28525 56831 28946 56831 28526 56831 28525 56832 28526 56832 28523 56832 28527 56833 28524 56833 28528 56833 28528 56834 28524 56834 28499 56834 28528 56835 28499 56835 28529 56835 28523 56836 28531 56836 28530 56836 28530 56837 28531 56837 28048 56837 28530 56838 28048 56838 29147 56838 29147 56839 28048 56839 28534 56839 29147 56840 28534 56840 28536 56840 28529 56841 28499 56841 28532 56841 28532 56842 28499 56842 27677 56842 28532 56843 27677 56843 28533 56843 28533 56844 27677 56844 27678 56844 28533 56845 27678 56845 28534 56845 28534 56846 27678 56846 28535 56846 28534 56847 28535 56847 28536 56847 28536 56848 27683 56848 29147 56848 29147 56849 27683 56849 28537 56849 29147 56850 28537 56850 28716 56850 28538 56851 28539 56851 28601 56851 28601 56852 28539 56852 28599 56852 28544 56853 28540 56853 28541 56853 28541 56854 28540 56854 29143 56854 28541 56855 29143 56855 28542 56855 28542 56856 29143 56856 29142 56856 28542 56857 29142 56857 28543 56857 29140 56858 28544 56858 29283 56858 28707 56859 28587 56859 28545 56859 28587 56860 28546 56860 28545 56860 28545 56861 28546 56861 28547 56861 28545 56862 28547 56862 28664 56862 28501 56863 28657 56863 28548 56863 28548 56864 28657 56864 28658 56864 28548 56865 28658 56865 27852 56865 28584 56866 28549 56866 28582 56866 28582 56867 28549 56867 27853 56867 28582 56868 27853 56868 27852 56868 27847 56869 28577 56869 27848 56869 27848 56870 28577 56870 28550 56870 27848 56871 28550 56871 28551 56871 28551 56872 28550 56872 28636 56872 28643 56873 28691 56873 27977 56873 28643 56874 27977 56874 28640 56874 28640 56875 27977 56875 29008 56875 28640 56876 29008 56876 28641 56876 28552 56877 28642 56877 28556 56877 28553 56878 28558 56878 28554 56878 28554 56879 28558 56879 28552 56879 28554 56880 28552 56880 28555 56880 28555 56881 28552 56881 28556 56881 28702 56882 28557 56882 28558 56882 28558 56883 28557 56883 27845 56883 28558 56884 27845 56884 28552 56884 28624 56885 28559 56885 28626 56885 28626 56886 28559 56886 28560 56886 28626 56887 28560 56887 27844 56887 27962 56888 28500 56888 27961 56888 27960 56889 28562 56889 27959 56889 27959 56890 28562 56890 28646 56890 27959 56891 28646 56891 28561 56891 28565 56892 27638 56892 27640 56892 29326 56893 29324 56893 28500 56893 28500 56894 29324 56894 28562 56894 28500 56895 28562 56895 27961 56895 27961 56896 28562 56896 27960 56896 28568 56897 27637 56897 28563 56897 27640 56898 27643 56898 28565 56898 28565 56899 27643 56899 27642 56899 28565 56900 27642 56900 28500 56900 28500 56901 27642 56901 28564 56901 28500 56902 28564 56902 29326 56902 29322 56903 29320 56903 28504 56903 28504 56904 29320 56904 28563 56904 28504 56905 28563 56905 28565 56905 28565 56906 28563 56906 27637 56906 28565 56907 27637 56907 27638 56907 29324 56908 29327 56908 28562 56908 28562 56909 29327 56909 28566 56909 28562 56910 28566 56910 27840 56910 27840 56911 28566 56911 28567 56911 27840 56912 28567 56912 28563 56912 28563 56913 28567 56913 27636 56913 28563 56914 27636 56914 28568 56914 28569 56915 29267 56915 28577 56915 28577 56916 29267 56916 29264 56916 28577 56917 29264 56917 28550 56917 28550 56918 28571 56918 28570 56918 28570 56919 28571 56919 29261 56919 28570 56920 29261 56920 27992 56920 27992 56921 29261 56921 27991 56921 27991 56922 29261 56922 28572 56922 27991 56923 28572 56923 27990 56923 28570 56924 28989 56924 28550 56924 28550 56925 28989 56925 28992 56925 28550 56926 28992 56926 28635 56926 28635 56927 28992 56927 28573 56927 28635 56928 28573 56928 28994 56928 28574 56929 28575 56929 28645 56929 28575 56930 27987 56930 28645 56930 28645 56931 27987 56931 27989 56931 28645 56932 27989 56932 27990 56932 27846 56933 28576 56933 27847 56933 27847 56934 28576 56934 28692 56934 27847 56935 28692 56935 28577 56935 28577 56936 28692 56936 28578 56936 28577 56937 28578 56937 28569 56937 28572 56938 27728 56938 27990 56938 27990 56939 27728 56939 28579 56939 27990 56940 28579 56940 28645 56940 28645 56941 28579 56941 27731 56941 28645 56942 27731 56942 28692 56942 28692 56943 27731 56943 27734 56943 28692 56944 27734 56944 28578 56944 28658 56945 27719 56945 28580 56945 27852 56946 28658 56946 28582 56946 28582 56947 28658 56947 28580 56947 28582 56948 28580 56948 28581 56948 27726 56949 27725 56949 28694 56949 28694 56950 27725 56950 20972 56950 20972 56951 27725 56951 27722 56951 20972 56952 27722 56952 28659 56952 28659 56953 27722 56953 27721 56953 28659 56954 27721 56954 28658 56954 28658 56955 27721 56955 27720 56955 28658 56956 27720 56956 27719 56956 28581 56957 29271 56957 28582 56957 28582 56958 29271 56958 28583 56958 28582 56959 28583 56959 28584 56959 28584 56960 28583 56960 29273 56960 28584 56961 29273 56961 28704 56961 28704 56962 29273 56962 29275 56962 28704 56963 29275 56963 29277 56963 27716 56964 28585 56964 28713 56964 28713 56965 28585 56965 28586 56965 28713 56966 28586 56966 28707 56966 28707 56967 28586 56967 27714 56967 28707 56968 27714 56968 28587 56968 28591 56969 28662 56969 28588 56969 28588 56970 28589 56970 28591 56970 28591 56971 28589 56971 28590 56971 28591 56972 28590 56972 28708 56972 28664 56973 28547 56973 28663 56973 28663 56974 28547 56974 29281 56974 28663 56975 29281 56975 28662 56975 28662 56976 29281 56976 29280 56976 28662 56977 29280 56977 28588 56977 27705 56978 28592 56978 28541 56978 28541 56979 28592 56979 27711 56979 28541 56980 27711 56980 28544 56980 28544 56981 27711 56981 27709 56981 28544 56982 27709 56982 29283 56982 27703 56983 28675 56983 27701 56983 27701 56984 28675 56984 28676 56984 27701 56985 28676 56985 27698 56985 27698 56986 28676 56986 28593 56986 29140 56987 29283 56987 28594 56987 28594 56988 29283 56988 28595 56988 28594 56989 28595 56989 28596 56989 28596 56990 28595 56990 29284 56990 28596 56991 29284 56991 29289 56991 28716 56992 28597 56992 28598 56992 28598 56993 28597 56993 28717 56993 28598 56994 28717 56994 28599 56994 28599 56995 28717 56995 28718 56995 28599 56996 28718 56996 28601 56996 28601 56997 28718 56997 27689 56997 28601 56998 27689 56998 28600 56998 28600 56999 28602 56999 28601 56999 28601 57000 28602 57000 28606 57000 28601 57001 28606 57001 28671 57001 28610 57002 28611 57002 28604 57002 28604 57003 28611 57003 28603 57003 28604 57004 28603 57004 28605 57004 28606 57005 28607 57005 28671 57005 28671 57006 28607 57006 28608 57006 28671 57007 28608 57007 28670 57007 28670 57008 28608 57008 28609 57008 28670 57009 28609 57009 28493 57009 28493 57010 28609 57010 29292 57010 28493 57011 29292 57011 28610 57011 28610 57012 29292 57012 29291 57012 28610 57013 29291 57013 28611 57013 27688 57014 27686 57014 28612 57014 28612 57015 27686 57015 28613 57015 28612 57016 28613 57016 28614 57016 28613 57017 29296 57017 28614 57017 28614 57018 29296 57018 29295 57018 28614 57019 29295 57019 28616 57019 28615 57020 28617 57020 28524 57020 28524 57021 28617 57021 28616 57021 28524 57022 28616 57022 29301 57022 29301 57023 28616 57023 29295 57023 28617 57024 29306 57024 28616 57024 28616 57025 29306 57025 29304 57025 28616 57026 29304 57026 28618 57026 28618 57027 29304 57027 29308 57027 28618 57028 29308 57028 28619 57028 28619 57029 29308 57029 28620 57029 28619 57030 28620 57030 27666 57030 27661 57031 28621 57031 28679 57031 28679 57032 28621 57032 28622 57032 28679 57033 28622 57033 20981 57033 20981 57034 28622 57034 29316 57034 20981 57035 29316 57035 28623 57035 28624 57036 28626 57036 28625 57036 28625 57037 28626 57037 28627 57037 28625 57038 28627 57038 28628 57038 28628 57039 28627 57039 28703 57039 28628 57040 28703 57040 29334 57040 29334 57041 28703 57041 28701 57041 29334 57042 28701 57042 29336 57042 28559 57043 27625 57043 28560 57043 28560 57044 27625 57044 28629 57044 28560 57045 28629 57045 28648 57045 28648 57046 28629 57046 28630 57046 28648 57047 28630 57047 28495 57047 28495 57048 28630 57048 28631 57048 28495 57049 28631 57049 28632 57049 28632 57050 28631 57050 27632 57050 28632 57051 27632 57051 28633 57051 27622 57052 28634 57052 28635 57052 28635 57053 28634 57053 28637 57053 28635 57054 28637 57054 28636 57054 28636 57055 28637 57055 28638 57055 28636 57056 28638 57056 28639 57056 28639 57057 28638 57057 29339 57057 28639 57058 29339 57058 27850 57058 27850 57059 29339 57059 28640 57059 27850 57060 28640 57060 28642 57060 28642 57061 28640 57061 28641 57061 28642 57062 28641 57062 28556 57062 28994 57063 28574 57063 28635 57063 28635 57064 28574 57064 28645 57064 28635 57065 28645 57065 27622 57065 27622 57066 28645 57066 27623 57066 27615 57067 28643 57067 27612 57067 27612 57068 28643 57068 28640 57068 27612 57069 28640 57069 29338 57069 29338 57070 28640 57070 29339 57070 27615 57071 27616 57071 28643 57071 28643 57072 27616 57072 28644 57072 28643 57073 28644 57073 28645 57073 28645 57074 28644 57074 27619 57074 28645 57075 27619 57075 27623 57075 28561 57076 28646 57076 29030 57076 29030 57077 28646 57077 27844 57077 29030 57078 27844 57078 28647 57078 28647 57079 27844 57079 28560 57079 28647 57080 28560 57080 29026 57080 29026 57081 28560 57081 28648 57081 29026 57082 28648 57082 28649 57082 28494 57083 27964 57083 28648 57083 28648 57084 27964 57084 29024 57084 28648 57085 29024 57085 28649 57085 27970 57086 28632 57086 28701 57086 28701 57087 28632 57087 28633 57087 28701 57088 28633 57088 29336 57088 27970 57089 27973 57089 28632 57089 28632 57090 27973 57090 28650 57090 28632 57091 28650 57091 28498 57091 28651 57092 28652 57092 28653 57092 28651 57093 28653 57093 28591 57093 28591 57094 28653 57094 28002 57094 28591 57095 28002 57095 28662 57095 28662 57096 28002 57096 28654 57096 28662 57097 28654 57097 28655 57097 28657 57098 28003 57098 28656 57098 28656 57099 28977 57099 28657 57099 28657 57100 28977 57100 28978 57100 28657 57101 28978 57101 28658 57101 28658 57102 28978 57102 28980 57102 28658 57103 28980 57103 28659 57103 28659 57104 28980 57104 28660 57104 28659 57105 28660 57105 28651 57105 28651 57106 28660 57106 28661 57106 28651 57107 28661 57107 28652 57107 28655 57108 28003 57108 28662 57108 28662 57109 28003 57109 28657 57109 28662 57110 28657 57110 28663 57110 28663 57111 28657 57111 28502 57111 28663 57112 28502 57112 28664 57112 28676 57113 28665 57113 28669 57113 28666 57114 28593 57114 20975 57114 20975 57115 28593 57115 28676 57115 20975 57116 28676 57116 28667 57116 28667 57117 28676 57117 20977 57117 28668 57118 28673 57118 28542 57118 28676 57119 28669 57119 20977 57119 20977 57120 28669 57120 28959 57120 20977 57121 28959 57121 28670 57121 28670 57122 28959 57122 28672 57122 28670 57123 28672 57123 28671 57123 28671 57124 28672 57124 28027 57124 28671 57125 28027 57125 28029 57125 28538 57126 28601 57126 28543 57126 28543 57127 28601 57127 28671 57127 28543 57128 28671 57128 28542 57128 28542 57129 28671 57129 28029 57129 28542 57130 28029 57130 28668 57130 28673 57131 28674 57131 28542 57131 28542 57132 28674 57132 28675 57132 28542 57133 28675 57133 28541 57133 28541 57134 28675 57134 27703 57134 28541 57135 27703 57135 27705 57135 28674 57136 28952 57136 28675 57136 28675 57137 28952 57137 28953 57137 28675 57138 28953 57138 28676 57138 28676 57139 28953 57139 28955 57139 28676 57140 28955 57140 28665 57140 28061 57141 28678 57141 28680 57141 28680 57142 28678 57142 28619 57142 28680 57143 28619 57143 29149 57143 29149 57144 28619 57144 29150 57144 28927 57145 28618 57145 28677 57145 28677 57146 28618 57146 28619 57146 28677 57147 28619 57147 28062 57147 28062 57148 28619 57148 28678 57148 20981 57149 28934 57149 28679 57149 28679 57150 28934 57150 28935 57150 28679 57151 28935 57151 28715 57151 28715 57152 28935 57152 28059 57152 28715 57153 28059 57153 28680 57153 28680 57154 28059 57154 28681 57154 28680 57155 28681 57155 28061 57155 28684 57156 28695 57156 28929 57156 28682 57157 28684 57157 28683 57157 28683 57158 28684 57158 28929 57158 28683 57159 28929 57159 20981 57159 20981 57160 28929 57160 28930 57160 20981 57161 28930 57161 28934 57161 28685 57162 28686 57162 28511 57162 28511 57163 28686 57163 28072 57163 28511 57164 28072 57164 28514 57164 28514 57165 28072 57165 28687 57165 28514 57166 28687 57166 28512 57166 28512 57167 28687 57167 28688 57167 28512 57168 28688 57168 28075 57168 29316 57169 28689 57169 28623 57169 28623 57170 28689 57170 28512 57170 28623 57171 28512 57171 20983 57171 20983 57172 28512 57172 28075 57172 28650 57173 28690 57173 28498 57173 28498 57174 28690 57174 28691 57174 28498 57175 28691 57175 28497 57175 28497 57176 28691 57176 28643 57176 28497 57177 28643 57177 20968 57177 20968 57178 28643 57178 28645 57178 20968 57179 28645 57179 20970 57179 20970 57180 28645 57180 28692 57180 20970 57181 28692 57181 28705 57181 28693 57182 28704 57182 28694 57182 28694 57183 28704 57183 29277 57183 28694 57184 29277 57184 27726 57184 28708 57185 28596 57185 20975 57185 20975 57186 28596 57186 29289 57186 20975 57187 29289 57187 28666 57187 28927 57188 28695 57188 28618 57188 28618 57189 28695 57189 28684 57189 28618 57190 28684 57190 28616 57190 28616 57191 28684 57191 28492 57191 28616 57192 28492 57192 28614 57192 28614 57193 28492 57193 20978 57193 28614 57194 20978 57194 28604 57194 28604 57195 20978 57195 28696 57195 28604 57196 28696 57196 28610 57196 28075 57197 28910 57197 20983 57197 20983 57198 28910 57198 28507 57198 20983 57199 28507 57199 28697 57199 28697 57200 28507 57200 28504 57200 28697 57201 28504 57201 28698 57201 28698 57202 28504 57202 28565 57202 28698 57203 28565 57203 28699 57203 28699 57204 28565 57204 28500 57204 28699 57205 28500 57205 28494 57205 28494 57206 28500 57206 28700 57206 28494 57207 28700 57207 27964 57207 28553 57208 27970 57208 28558 57208 28558 57209 27970 57209 28701 57209 28558 57210 28701 57210 28702 57210 28702 57211 28701 57211 28703 57211 28702 57212 28703 57212 27843 57212 27843 57213 28703 57213 28627 57213 27846 57214 28549 57214 28576 57214 28576 57215 28549 57215 28584 57215 28576 57216 28584 57216 28692 57216 28692 57217 28584 57217 28704 57217 28692 57218 28704 57218 28705 57218 28705 57219 28704 57219 28693 57219 28964 57220 28706 57220 28707 57220 28968 57221 28709 57221 28713 57221 28545 57222 29140 57222 28707 57222 28707 57223 29140 57223 28594 57223 28707 57224 28594 57224 28964 57224 28964 57225 28594 57225 28013 57225 28590 57226 27716 57226 28708 57226 28708 57227 27716 57227 28713 57227 28708 57228 28713 57228 28596 57228 28596 57229 28713 57229 28709 57229 28596 57230 28709 57230 28710 57230 28710 57231 28711 57231 28596 57231 28596 57232 28711 57232 28012 57232 28596 57233 28012 57233 28594 57233 28594 57234 28012 57234 28712 57234 28594 57235 28712 57235 28013 57235 28706 57236 28966 57236 28707 57236 28707 57237 28966 57237 28714 57237 28707 57238 28714 57238 28713 57238 28713 57239 28714 57239 28967 57239 28713 57240 28967 57240 28968 57240 29149 57241 28519 57241 28680 57241 28680 57242 28519 57242 28516 57242 28680 57243 28516 57243 28715 57243 28715 57244 28516 57244 28515 57244 28715 57245 28515 57245 28679 57245 28679 57246 28515 57246 27662 57246 28679 57247 27662 57247 27661 57247 28537 57248 27688 57248 28716 57248 28716 57249 27688 57249 28612 57249 28716 57250 28612 57250 28597 57250 28597 57251 28612 57251 28614 57251 28597 57252 28614 57252 28717 57252 28717 57253 28614 57253 28604 57253 28717 57254 28604 57254 28718 57254 28718 57255 28604 57255 28605 57255 28718 57256 28605 57256 27689 57256 28720 57257 29141 57257 28489 57257 28489 57258 28719 57258 28720 57258 28720 57259 28719 57259 28721 57259 28720 57260 28721 57260 28722 57260 28722 57261 28721 57261 28888 57261 28891 57262 29145 57262 29144 57262 28888 57263 28887 57263 28722 57263 28722 57264 28887 57264 28886 57264 28722 57265 28886 57265 29144 57265 29144 57266 28886 57266 28723 57266 29144 57267 28723 57267 28891 57267 28896 57268 29148 57268 28724 57268 28891 57269 28889 57269 29145 57269 29145 57270 28889 57270 28725 57270 29145 57271 28725 57271 28724 57271 28724 57272 28725 57272 28726 57272 28724 57273 28726 57273 28896 57273 28897 57274 29146 57274 28727 57274 28896 57275 28895 57275 29148 57275 29148 57276 28895 57276 28893 57276 29148 57277 28893 57277 28727 57277 28727 57278 28893 57278 28883 57278 28727 57279 28883 57279 28897 57279 28897 57280 28898 57280 29146 57280 29146 57281 28898 57281 28900 57281 29146 57282 28900 57282 28728 57282 28900 57283 28901 57283 28728 57283 28728 57284 28901 57284 28729 57284 28728 57285 28729 57285 28730 57285 28729 57286 28903 57286 28730 57286 28730 57287 28903 57287 28731 57287 28730 57288 28731 57288 29152 57288 28731 57289 28905 57289 29152 57289 29152 57290 28905 57290 28732 57290 29152 57291 28732 57291 28733 57291 28732 57292 28906 57292 28733 57292 28733 57293 28906 57293 28734 57293 28733 57294 28734 57294 28736 57294 28734 57295 28735 57295 28736 57295 28736 57296 28735 57296 28739 57296 28736 57297 28739 57297 29154 57297 28737 57298 29155 57298 28909 57298 28909 57299 29155 57299 29154 57299 28909 57300 29154 57300 28738 57300 28738 57301 29154 57301 28739 57301 28740 57302 29174 57302 29172 57302 28740 57303 29172 57303 28426 57303 28426 57304 29172 57304 28741 57304 28426 57305 28741 57305 28743 57305 28743 57306 28741 57306 28742 57306 28743 57307 28742 57307 28744 57307 28744 57308 28742 57308 29164 57308 28744 57309 29164 57309 28745 57309 28745 57310 29164 57310 28747 57310 28745 57311 28747 57311 28746 57311 28746 57312 28747 57312 28748 57312 28746 57313 28748 57313 28749 57313 28749 57314 28748 57314 29167 57314 28749 57315 29167 57315 28750 57315 28750 57316 29167 57316 29168 57316 28750 57317 29168 57317 28751 57317 28751 57318 29168 57318 28753 57318 28751 57319 28753 57319 28752 57319 28752 57320 28753 57320 28754 57320 28752 57321 28754 57321 28755 57321 28755 57322 28754 57322 28756 57322 28755 57323 28756 57323 28757 57323 28757 57324 28756 57324 29161 57324 28757 57325 29161 57325 28443 57325 28443 57326 29161 57326 29159 57326 28443 57327 29159 57327 28758 57327 28758 57328 29159 57328 29158 57328 28758 57329 29158 57329 28759 57329 28759 57330 29158 57330 27838 57330 28759 57331 27838 57331 28434 57331 28422 57332 28796 57332 28760 57332 28422 57333 28760 57333 28761 57333 28761 57334 28760 57334 28762 57334 28761 57335 28762 57335 28763 57335 28763 57336 28762 57336 28792 57336 28763 57337 28792 57337 28442 57337 28442 57338 28792 57338 28791 57338 28442 57339 28791 57339 28764 57339 28764 57340 28791 57340 28789 57340 28764 57341 28789 57341 28444 57341 28444 57342 28789 57342 28788 57342 28444 57343 28788 57343 28445 57343 28445 57344 28788 57344 28787 57344 28445 57345 28787 57345 28765 57345 28765 57346 28787 57346 28766 57346 28765 57347 28766 57347 28767 57347 28767 57348 28766 57348 28768 57348 28767 57349 28768 57349 28769 57349 28769 57350 28768 57350 28770 57350 28769 57351 28770 57351 28446 57351 28446 57352 28770 57352 28783 57352 28446 57353 28783 57353 28771 57353 28771 57354 28783 57354 28772 57354 28771 57355 28772 57355 28447 57355 28447 57356 28772 57356 28780 57356 28447 57357 28780 57357 28448 57357 28448 57358 28780 57358 28779 57358 28448 57359 28779 57359 28449 57359 28449 57360 28779 57360 28773 57360 28449 57361 28773 57361 28450 57361 28450 57362 28773 57362 28777 57362 28450 57363 28777 57363 28427 57363 28427 57364 28777 57364 28774 57364 28427 57365 28774 57365 28775 57365 28775 57366 28774 57366 28404 57366 28775 57367 28404 57367 28405 57367 27611 57368 28404 57368 28774 57368 27611 57369 28774 57369 29340 57369 29340 57370 28774 57370 28777 57370 29340 57371 28777 57371 28776 57371 28776 57372 28777 57372 28773 57372 28776 57373 28773 57373 28778 57373 28778 57374 28773 57374 28779 57374 28778 57375 28779 57375 29342 57375 29342 57376 28779 57376 28780 57376 29342 57377 28780 57377 28781 57377 28781 57378 28780 57378 28772 57378 28781 57379 28772 57379 28782 57379 28782 57380 28772 57380 28783 57380 28782 57381 28783 57381 28784 57381 28784 57382 28783 57382 28770 57382 28784 57383 28770 57383 28785 57383 28785 57384 28770 57384 28768 57384 28785 57385 28768 57385 28786 57385 28786 57386 28768 57386 28766 57386 28786 57387 28766 57387 29346 57387 29346 57388 28766 57388 28787 57388 29346 57389 28787 57389 29347 57389 29347 57390 28787 57390 28788 57390 29347 57391 28788 57391 28790 57391 28790 57392 28788 57392 28789 57392 28790 57393 28789 57393 29348 57393 29348 57394 28789 57394 28791 57394 29348 57395 28791 57395 28793 57395 28793 57396 28791 57396 28792 57396 28793 57397 28792 57397 28794 57397 28794 57398 28792 57398 28762 57398 28794 57399 28762 57399 28795 57399 28795 57400 28762 57400 28760 57400 28795 57401 28760 57401 29352 57401 29352 57402 28760 57402 28796 57402 29352 57403 28796 57403 29353 57403 28797 57404 28344 57404 28367 57404 28797 57405 28367 57405 29388 57405 29388 57406 28367 57406 28798 57406 29388 57407 28798 57407 29390 57407 29390 57408 28798 57408 28799 57408 29390 57409 28799 57409 29391 57409 29391 57410 28799 57410 28800 57410 29391 57411 28800 57411 28801 57411 28801 57412 28800 57412 28370 57412 28801 57413 28370 57413 28802 57413 28802 57414 28370 57414 28371 57414 28802 57415 28371 57415 29395 57415 29395 57416 28371 57416 28803 57416 29395 57417 28803 57417 29397 57417 29397 57418 28803 57418 28373 57418 29397 57419 28373 57419 29398 57419 29398 57420 28373 57420 28375 57420 29398 57421 28375 57421 29400 57421 29400 57422 28375 57422 28377 57422 29400 57423 28377 57423 28804 57423 28804 57424 28377 57424 28378 57424 28804 57425 28378 57425 28805 57425 28805 57426 28378 57426 28806 57426 28805 57427 28806 57427 29403 57427 29403 57428 28806 57428 28807 57428 29403 57429 28807 57429 29404 57429 29404 57430 28807 57430 28345 57430 29404 57431 28345 57431 29405 57431 29405 57432 28345 57432 28808 57432 29405 57433 28808 57433 29407 57433 29407 57434 28808 57434 28347 57434 29407 57435 28347 57435 28809 57435 28809 57436 28347 57436 28810 57436 28809 57437 28810 57437 28811 57437 28811 57438 28810 57438 28349 57438 28811 57439 28349 57439 29409 57439 28812 57440 28264 57440 29426 57440 29426 57441 28264 57441 28813 57441 29426 57442 28813 57442 29425 57442 29425 57443 28813 57443 28814 57443 29425 57444 28814 57444 28815 57444 28815 57445 28814 57445 28262 57445 28815 57446 28262 57446 29421 57446 29421 57447 28262 57447 28261 57447 29421 57448 28261 57448 28817 57448 28817 57449 28261 57449 28816 57449 28817 57450 28816 57450 29420 57450 29420 57451 28816 57451 28819 57451 29420 57452 28819 57452 28818 57452 28818 57453 28819 57453 28820 57453 28818 57454 28820 57454 28821 57454 28821 57455 28820 57455 28259 57455 28821 57456 28259 57456 28822 57456 28822 57457 28259 57457 28258 57457 28822 57458 28258 57458 28823 57458 28823 57459 28258 57459 28824 57459 28823 57460 28824 57460 29416 57460 29416 57461 28824 57461 28825 57461 29416 57462 28825 57462 28826 57462 28826 57463 28825 57463 28827 57463 28826 57464 28827 57464 28828 57464 28828 57465 28827 57465 28829 57465 28828 57466 28829 57466 29413 57466 29413 57467 28829 57467 28252 57467 29413 57468 28252 57468 29412 57468 29412 57469 28252 57469 28830 57469 29412 57470 28830 57470 29410 57470 29410 57471 28830 57471 28249 57471 29410 57472 28249 57472 28831 57472 28831 57473 28249 57473 28275 57473 28243 57474 28832 57474 29443 57474 29443 57475 28832 57475 28833 57475 29443 57476 28833 57476 29442 57476 29442 57477 28833 57477 28834 57477 29442 57478 28834 57478 29440 57478 29440 57479 28834 57479 28197 57479 29440 57480 28197 57480 28835 57480 28835 57481 28197 57481 28836 57481 28835 57482 28836 57482 28837 57482 28837 57483 28836 57483 28195 57483 28837 57484 28195 57484 29436 57484 29436 57485 28195 57485 28839 57485 29436 57486 28839 57486 28838 57486 28838 57487 28839 57487 28840 57487 28838 57488 28840 57488 29435 57488 29435 57489 28840 57489 28193 57489 29435 57490 28193 57490 29433 57490 29433 57491 28193 57491 28841 57491 29433 57492 28841 57492 29432 57492 29432 57493 28841 57493 28191 57493 29432 57494 28191 57494 28842 57494 28842 57495 28191 57495 28223 57495 28842 57496 28223 57496 28843 57496 28843 57497 28223 57497 28844 57497 28843 57498 28844 57498 29431 57498 29431 57499 28844 57499 28845 57499 29431 57500 28845 57500 28846 57500 28846 57501 28845 57501 28847 57501 28846 57502 28847 57502 28848 57502 28848 57503 28847 57503 28222 57503 28848 57504 28222 57504 29429 57504 29429 57505 28222 57505 28849 57505 29429 57506 28849 57506 29428 57506 29428 57507 28849 57507 28225 57507 28850 57508 28199 57508 28200 57508 28850 57509 28200 57509 29376 57509 29376 57510 28200 57510 28852 57510 29376 57511 28852 57511 28851 57511 28851 57512 28852 57512 28854 57512 28851 57513 28854 57513 28853 57513 28853 57514 28854 57514 28203 57514 28853 57515 28203 57515 29379 57515 29379 57516 28203 57516 28205 57516 29379 57517 28205 57517 28855 57517 28855 57518 28205 57518 28207 57518 28855 57519 28207 57519 28856 57519 28856 57520 28207 57520 28857 57520 28856 57521 28857 57521 28858 57521 28858 57522 28857 57522 28208 57522 28858 57523 28208 57523 28859 57523 28859 57524 28208 57524 28860 57524 28859 57525 28860 57525 29381 57525 29381 57526 28860 57526 28861 57526 29381 57527 28861 57527 29383 57527 29383 57528 28861 57528 28862 57528 29383 57529 28862 57529 29385 57529 29385 57530 28862 57530 28863 57530 29385 57531 28863 57531 29386 57531 29386 57532 28863 57532 28210 57532 29386 57533 28210 57533 28864 57533 28864 57534 28210 57534 28213 57534 28864 57535 28213 57535 28865 57535 28865 57536 28213 57536 28215 57536 28865 57537 28215 57537 29387 57537 29387 57538 28215 57538 28216 57538 29387 57539 28216 57539 28866 57539 28866 57540 28216 57540 28218 57540 28866 57541 28218 57541 28177 57541 28141 57542 28142 57542 29374 57542 29374 57543 28142 57543 28867 57543 29374 57544 28867 57544 29372 57544 29372 57545 28867 57545 28868 57545 29372 57546 28868 57546 29370 57546 29370 57547 28868 57547 28869 57547 29370 57548 28869 57548 29369 57548 29369 57549 28869 57549 28113 57549 29369 57550 28113 57550 29367 57550 29367 57551 28113 57551 28870 57551 29367 57552 28870 57552 29366 57552 29366 57553 28870 57553 28871 57553 29366 57554 28871 57554 28872 57554 28872 57555 28871 57555 28873 57555 28872 57556 28873 57556 29365 57556 29365 57557 28873 57557 28874 57557 29365 57558 28874 57558 28875 57558 28875 57559 28874 57559 28876 57559 28875 57560 28876 57560 29363 57560 29363 57561 28876 57561 28110 57561 29363 57562 28110 57562 29361 57562 29361 57563 28110 57563 28877 57563 29361 57564 28877 57564 28878 57564 28878 57565 28877 57565 28108 57565 28878 57566 28108 57566 29359 57566 29359 57567 28108 57567 28879 57567 29359 57568 28879 57568 29358 57568 29358 57569 28879 57569 28880 57569 29358 57570 28880 57570 29357 57570 29357 57571 28880 57571 28881 57571 29357 57572 28881 57572 29354 57572 29354 57573 28881 57573 28882 57573 29354 57574 28882 57574 27596 57574 27596 57575 28882 57575 28121 57575 28883 57576 28893 57576 28119 57576 28884 57577 28885 57577 28489 57577 28489 57578 28885 57578 28719 57578 28116 57579 28892 57579 28886 57579 28886 57580 28887 57580 28116 57580 28116 57581 28887 57581 28888 57581 28116 57582 28888 57582 28885 57582 28885 57583 28888 57583 28721 57583 28885 57584 28721 57584 28719 57584 28890 57585 28117 57585 28725 57585 28725 57586 28889 57586 28890 57586 28890 57587 28889 57587 28891 57587 28890 57588 28891 57588 28892 57588 28892 57589 28891 57589 28723 57589 28892 57590 28723 57590 28886 57590 28119 57591 28893 57591 28894 57591 28893 57592 28895 57592 28894 57592 28894 57593 28895 57593 28896 57593 28894 57594 28896 57594 28117 57594 28117 57595 28896 57595 28726 57595 28117 57596 28726 57596 28725 57596 28883 57597 28119 57597 28897 57597 28897 57598 28119 57598 28899 57598 28897 57599 28899 57599 28898 57599 28898 57600 28899 57600 28094 57600 28898 57601 28094 57601 28900 57601 28900 57602 28094 57602 28901 57602 28901 57603 28094 57603 28902 57603 28901 57604 28902 57604 28729 57604 28729 57605 28902 57605 28903 57605 28903 57606 28902 57606 28904 57606 28903 57607 28904 57607 28731 57607 28731 57608 28904 57608 28905 57608 28905 57609 28904 57609 28097 57609 28905 57610 28097 57610 28732 57610 28732 57611 28097 57611 28906 57611 28906 57612 28097 57612 28907 57612 28906 57613 28907 57613 28734 57613 28734 57614 28907 57614 28735 57614 28735 57615 28907 57615 28101 57615 28735 57616 28101 57616 28739 57616 28739 57617 28101 57617 28738 57617 28738 57618 28101 57618 28908 57618 28738 57619 28908 57619 28909 57619 28909 57620 28908 57620 28102 57620 28909 57621 28102 57621 28737 57621 28075 57622 28923 57622 28924 57622 28075 57623 28924 57623 28910 57623 28910 57624 28924 57624 28926 57624 28910 57625 28926 57625 28911 57625 28926 57626 28912 57626 28911 57626 28911 57627 28912 57627 28913 57627 28911 57628 28913 57628 28506 57628 28506 57629 28913 57629 28914 57629 28914 57630 28922 57630 28506 57630 28506 57631 28922 57631 28921 57631 28506 57632 28921 57632 28915 57632 28921 57633 28916 57633 28915 57633 28915 57634 28916 57634 28920 57634 28915 57635 28920 57635 28510 57635 28070 57636 28069 57636 28917 57636 28917 57637 28069 57637 28510 57637 28917 57638 28510 57638 28919 57638 28919 57639 28510 57639 28920 57639 28918 57640 29491 57640 28070 57640 28070 57641 28917 57641 28918 57641 28918 57642 28917 57642 28919 57642 28918 57643 28919 57643 29489 57643 28919 57644 28920 57644 29489 57644 29489 57645 28920 57645 28916 57645 29489 57646 28916 57646 29488 57646 28916 57647 28921 57647 29488 57647 29488 57648 28921 57648 28922 57648 29488 57649 28922 57649 29486 57649 29486 57650 28922 57650 28914 57650 29486 57651 28914 57651 29618 57651 28914 57652 28913 57652 29618 57652 29618 57653 28913 57653 28912 57653 29618 57654 28912 57654 28925 57654 28923 57655 29616 57655 28924 57655 28924 57656 29616 57656 28925 57656 28924 57657 28925 57657 28926 57657 28926 57658 28925 57658 28912 57658 28927 57659 28928 57659 28695 57659 28695 57660 28928 57660 28937 57660 28695 57661 28937 57661 28929 57661 28929 57662 28937 57662 28931 57662 28929 57663 28931 57663 28930 57663 28930 57664 28931 57664 28932 57664 28930 57665 28932 57665 28934 57665 28934 57666 28932 57666 28933 57666 28934 57667 28933 57667 28935 57667 28935 57668 28933 57668 28936 57668 28935 57669 28936 57669 28059 57669 28059 57670 28936 57670 28060 57670 29631 57671 28060 57671 29632 57671 29632 57672 28060 57672 28936 57672 28928 57673 29620 57673 28937 57673 28937 57674 29620 57674 29622 57674 28937 57675 29622 57675 28931 57675 28931 57676 29622 57676 28938 57676 28931 57677 28938 57677 28932 57677 28932 57678 28938 57678 29657 57678 28932 57679 29657 57679 28933 57679 28933 57680 29657 57680 28939 57680 28933 57681 28939 57681 28936 57681 28936 57682 28939 57682 28940 57682 28936 57683 28940 57683 29632 57683 28533 57684 28034 57684 28532 57684 28532 57685 28034 57685 28941 57685 28532 57686 28941 57686 28529 57686 28529 57687 28941 57687 28942 57687 28529 57688 28942 57688 28528 57688 28528 57689 28942 57689 28943 57689 28528 57690 28943 57690 28527 57690 28527 57691 28943 57691 28945 57691 28527 57692 28945 57692 28944 57692 28944 57693 28945 57693 28947 57693 28944 57694 28947 57694 28946 57694 28946 57695 28947 57695 28948 57695 28034 57696 29471 57696 28941 57696 28941 57697 29471 57697 29470 57697 28941 57698 29470 57698 28942 57698 28942 57699 29470 57699 29460 57699 28942 57700 29460 57700 28943 57700 28943 57701 29460 57701 28949 57701 28943 57702 28949 57702 28945 57702 28945 57703 28949 57703 29463 57703 28945 57704 29463 57704 28947 57704 28947 57705 29463 57705 28950 57705 28947 57706 28950 57706 28948 57706 28948 57707 28950 57707 28951 57707 28674 57708 28032 57708 28952 57708 28952 57709 28032 57709 28961 57709 28952 57710 28961 57710 28953 57710 28953 57711 28961 57711 28954 57711 28953 57712 28954 57712 28955 57712 28955 57713 28954 57713 28956 57713 28955 57714 28956 57714 28665 57714 28665 57715 28956 57715 28957 57715 28665 57716 28957 57716 28669 57716 28669 57717 28957 57717 28958 57717 28669 57718 28958 57718 28959 57718 28959 57719 28958 57719 28960 57719 28032 57720 29453 57720 28961 57720 28961 57721 29453 57721 29523 57721 28961 57722 29523 57722 28954 57722 28954 57723 29523 57723 29522 57723 28954 57724 29522 57724 28956 57724 28956 57725 29522 57725 29528 57725 28956 57726 29528 57726 28957 57726 28957 57727 29528 57727 28962 57727 28957 57728 28962 57728 28958 57728 28958 57729 28962 57729 29641 57729 28958 57730 29641 57730 28960 57730 28960 57731 29641 57731 28963 57731 28964 57732 28970 57732 28706 57732 28706 57733 28970 57733 28971 57733 28706 57734 28971 57734 28966 57734 28966 57735 28971 57735 28965 57735 28966 57736 28965 57736 28714 57736 28714 57737 28965 57737 28974 57737 28714 57738 28974 57738 28967 57738 28967 57739 28974 57739 28975 57739 28967 57740 28975 57740 28968 57740 28968 57741 28975 57741 28969 57741 28968 57742 28969 57742 28709 57742 28709 57743 28969 57743 28009 57743 28970 57744 28008 57744 28971 57744 28971 57745 28008 57745 28972 57745 28971 57746 28972 57746 28965 57746 28965 57747 28972 57747 28973 57747 28965 57748 28973 57748 28974 57748 28974 57749 28973 57749 29614 57749 28974 57750 29614 57750 28975 57750 28975 57751 29614 57751 29613 57751 28975 57752 29613 57752 28969 57752 28969 57753 29613 57753 28976 57753 28969 57754 28976 57754 28009 57754 28009 57755 28976 57755 29612 57755 28003 57756 28004 57756 28656 57756 28656 57757 28004 57757 28982 57757 28656 57758 28982 57758 28977 57758 28977 57759 28982 57759 28984 57759 28977 57760 28984 57760 28978 57760 28978 57761 28984 57761 28979 57761 28978 57762 28979 57762 28980 57762 28980 57763 28979 57763 28985 57763 28980 57764 28985 57764 28660 57764 28660 57765 28985 57765 28987 57765 28660 57766 28987 57766 28661 57766 28661 57767 28987 57767 28000 57767 28004 57768 28981 57768 28982 57768 28982 57769 28981 57769 28983 57769 28982 57770 28983 57770 28984 57770 28984 57771 28983 57771 29535 57771 28984 57772 29535 57772 28979 57772 28979 57773 29535 57773 29555 57773 28979 57774 29555 57774 28985 57774 28985 57775 29555 57775 28986 57775 28985 57776 28986 57776 28987 57776 28987 57777 28986 57777 29557 57777 28987 57778 29557 57778 28000 57778 28000 57779 29557 57779 29604 57779 27992 57780 27985 57780 29005 57780 27992 57781 29005 57781 28570 57781 28570 57782 29005 57782 28988 57782 28570 57783 28988 57783 28989 57783 28988 57784 29007 57784 28989 57784 28989 57785 29007 57785 28990 57785 28989 57786 28990 57786 28992 57786 28992 57787 28990 57787 28991 57787 28991 57788 29003 57788 28992 57788 28992 57789 29003 57789 29002 57789 28992 57790 29002 57790 28573 57790 29002 57791 29000 57791 28573 57791 28573 57792 29000 57792 28999 57792 28573 57793 28999 57793 28994 57793 28993 57794 28574 57794 28996 57794 28996 57795 28574 57795 28994 57795 28996 57796 28994 57796 28995 57796 28995 57797 28994 57797 28999 57797 28997 57798 29552 57798 28993 57798 28993 57799 28996 57799 28997 57799 28997 57800 28996 57800 28995 57800 28997 57801 28995 57801 28998 57801 28995 57802 28999 57802 28998 57802 28998 57803 28999 57803 29000 57803 28998 57804 29000 57804 29001 57804 29000 57805 29002 57805 29001 57805 29001 57806 29002 57806 29003 57806 29001 57807 29003 57807 29548 57807 29548 57808 29003 57808 28991 57808 29548 57809 28991 57809 29004 57809 28991 57810 28990 57810 29004 57810 29004 57811 28990 57811 29007 57811 29004 57812 29007 57812 29006 57812 27985 57813 29550 57813 29005 57813 29005 57814 29550 57814 29006 57814 29005 57815 29006 57815 28988 57815 28988 57816 29006 57816 29007 57816 27977 57817 27978 57817 29022 57817 27977 57818 29022 57818 29008 57818 29008 57819 29022 57819 29009 57819 29008 57820 29009 57820 28641 57820 29009 57821 29010 57821 28641 57821 28641 57822 29010 57822 29021 57822 28641 57823 29021 57823 28556 57823 28556 57824 29021 57824 29020 57824 29020 57825 29018 57825 28556 57825 28556 57826 29018 57826 29011 57826 28556 57827 29011 57827 28555 57827 29011 57828 29016 57828 28555 57828 28555 57829 29016 57829 29012 57829 28555 57830 29012 57830 28554 57830 27971 57831 28553 57831 29013 57831 29013 57832 28553 57832 28554 57832 29013 57833 28554 57833 29015 57833 29015 57834 28554 57834 29012 57834 29014 57835 29584 57835 27971 57835 27971 57836 29013 57836 29014 57836 29014 57837 29013 57837 29015 57837 29014 57838 29015 57838 29569 57838 29015 57839 29012 57839 29569 57839 29569 57840 29012 57840 29016 57840 29569 57841 29016 57841 29017 57841 29016 57842 29011 57842 29017 57842 29017 57843 29011 57843 29018 57843 29017 57844 29018 57844 29571 57844 29571 57845 29018 57845 29020 57845 29571 57846 29020 57846 29019 57846 29020 57847 29021 57847 29019 57847 29019 57848 29021 57848 29010 57848 29019 57849 29010 57849 29023 57849 27978 57850 27969 57850 29022 57850 29022 57851 27969 57851 29023 57851 29022 57852 29023 57852 29009 57852 29009 57853 29023 57853 29010 57853 29024 57854 29042 57854 29025 57854 29024 57855 29025 57855 28649 57855 28649 57856 29025 57856 29044 57856 28649 57857 29044 57857 29026 57857 29044 57858 29041 57858 29026 57858 29026 57859 29041 57859 29027 57859 29026 57860 29027 57860 28647 57860 28647 57861 29027 57861 29039 57861 29039 57862 29028 57862 28647 57862 28647 57863 29028 57863 29029 57863 28647 57864 29029 57864 29030 57864 29029 57865 29037 57865 29030 57865 29030 57866 29037 57866 29031 57866 29030 57867 29031 57867 28561 57867 29034 57868 27959 57868 29032 57868 29032 57869 27959 57869 28561 57869 29032 57870 28561 57870 29035 57870 29035 57871 28561 57871 29031 57871 29033 57872 29508 57872 29034 57872 29034 57873 29032 57873 29033 57873 29033 57874 29032 57874 29035 57874 29033 57875 29035 57875 29509 57875 29035 57876 29031 57876 29509 57876 29509 57877 29031 57877 29037 57877 29509 57878 29037 57878 29036 57878 29037 57879 29029 57879 29036 57879 29036 57880 29029 57880 29028 57880 29036 57881 29028 57881 29038 57881 29038 57882 29028 57882 29039 57882 29038 57883 29039 57883 29040 57883 29039 57884 29027 57884 29040 57884 29040 57885 29027 57885 29041 57885 29040 57886 29041 57886 29045 57886 29042 57887 29043 57887 29025 57887 29025 57888 29043 57888 29045 57888 29025 57889 29045 57889 29044 57889 29044 57890 29045 57890 29041 57890 29246 57891 29046 57891 27950 57891 27950 57892 29046 57892 29321 57892 29046 57893 29047 57893 29321 57893 29321 57894 29047 57894 29048 57894 29321 57895 29048 57895 29050 57895 29048 57896 29049 57896 29050 57896 29050 57897 29049 57897 29244 57897 29050 57898 29244 57898 29051 57898 29244 57899 29243 57899 29051 57899 29051 57900 29243 57900 29242 57900 29051 57901 29242 57901 29052 57901 29242 57902 29053 57902 29052 57902 29052 57903 29053 57903 29054 57903 29052 57904 29054 57904 29318 57904 29239 57905 27943 57905 29240 57905 29240 57906 27943 57906 29318 57906 29240 57907 29318 57907 29241 57907 29241 57908 29318 57908 29054 57908 27941 57909 29055 57909 29056 57909 29056 57910 29055 57910 29248 57910 29056 57911 29248 57911 29057 57911 29057 57912 29248 57912 29249 57912 29057 57913 29249 57913 29058 57913 29058 57914 29249 57914 29250 57914 29058 57915 29250 57915 29314 57915 29314 57916 29250 57916 29059 57916 29314 57917 29059 57917 29060 57917 29060 57918 29059 57918 29251 57918 29060 57919 29251 57919 29311 57919 29311 57920 29251 57920 29252 57920 29061 57921 27936 57921 29062 57921 29061 57922 29062 57922 29305 57922 29305 57923 29062 57923 29254 57923 29305 57924 29254 57924 29063 57924 29063 57925 29254 57925 29064 57925 29064 57926 29254 57926 29065 57926 29064 57927 29065 57927 29303 57927 29303 57928 29065 57928 29066 57928 29066 57929 29065 57929 29257 57929 29066 57930 29257 57930 29307 57930 29307 57931 29257 57931 29310 57931 29310 57932 29257 57932 29258 57932 29310 57933 29258 57933 29309 57933 29309 57934 29258 57934 29067 57934 29309 57935 29067 57935 29068 57935 29068 57936 29067 57936 27927 57936 29068 57937 27927 57937 27926 57937 27925 57938 29175 57938 29176 57938 27925 57939 29176 57939 29069 57939 29069 57940 29176 57940 29177 57940 29069 57941 29177 57941 29070 57941 29070 57942 29177 57942 29071 57942 29071 57943 29177 57943 29072 57943 29071 57944 29072 57944 29297 57944 29297 57945 29072 57945 29298 57945 29298 57946 29072 57946 29073 57946 29298 57947 29073 57947 29302 57947 29302 57948 29073 57948 29074 57948 29074 57949 29073 57949 29178 57949 29074 57950 29178 57950 29300 57950 29300 57951 29178 57951 29179 57951 29300 57952 29179 57952 29075 57952 29075 57953 29179 57953 29180 57953 29075 57954 29180 57954 29299 57954 27694 57955 29077 57955 29076 57955 29076 57956 29077 57956 29183 57956 29076 57957 29183 57957 29294 57957 29294 57958 29183 57958 29184 57958 29294 57959 29184 57959 29078 57959 29078 57960 29184 57960 29185 57960 29078 57961 29185 57961 29293 57961 29293 57962 29185 57962 29079 57962 29293 57963 29079 57963 29081 57963 29081 57964 29079 57964 29080 57964 29081 57965 29080 57965 29082 57965 29082 57966 29080 57966 29083 57966 29282 57967 27909 57967 29084 57967 29282 57968 29084 57968 29085 57968 29085 57969 29084 57969 29188 57969 29085 57970 29188 57970 29086 57970 29086 57971 29188 57971 29087 57971 29087 57972 29188 57972 29190 57972 29087 57973 29190 57973 29088 57973 29088 57974 29190 57974 29089 57974 29089 57975 29190 57975 29191 57975 29089 57976 29191 57976 29290 57976 29290 57977 29191 57977 29288 57977 29288 57978 29191 57978 29192 57978 29288 57979 29192 57979 29287 57979 29287 57980 29192 57980 29090 57980 29287 57981 29090 57981 29286 57981 29286 57982 29090 57982 29091 57982 29286 57983 29091 57983 29285 57983 27713 57984 29195 57984 29092 57984 29092 57985 29195 57985 29196 57985 29092 57986 29196 57986 29093 57986 29093 57987 29196 57987 29198 57987 29093 57988 29198 57988 29094 57988 29094 57989 29198 57989 29095 57989 29094 57990 29095 57990 29096 57990 29096 57991 29095 57991 29200 57991 29096 57992 29200 57992 29279 57992 29279 57993 29200 57993 29097 57993 29279 57994 29097 57994 27717 57994 27717 57995 29097 57995 29098 57995 29099 57996 27792 57996 29268 57996 29268 57997 27792 57997 29202 57997 29268 57998 29202 57998 29269 57998 29269 57999 29202 57999 29270 57999 29270 58000 29202 58000 29100 58000 29270 58001 29100 58001 29101 58001 29101 58002 29100 58002 29272 58002 29272 58003 29100 58003 29205 58003 29272 58004 29205 58004 29102 58004 29102 58005 29205 58005 29103 58005 29103 58006 29205 58006 29207 58006 29103 58007 29207 58007 29274 58007 29274 58008 29207 58008 29276 58008 29276 58009 29207 58009 29209 58009 29276 58010 29209 58010 29104 58010 29104 58011 29209 58011 29278 58011 29278 58012 29209 58012 29210 58012 29278 58013 29210 58013 29105 58013 29266 58014 27886 58014 29265 58014 29265 58015 27886 58015 29106 58015 29265 58016 29106 58016 29263 58016 29263 58017 29106 58017 29215 58017 29263 58018 29215 58018 29107 58018 29107 58019 29215 58019 29217 58019 29107 58020 29217 58020 29262 58020 29262 58021 29217 58021 29219 58021 29262 58022 29219 58022 29260 58022 29260 58023 29219 58023 29220 58023 29260 58024 29220 58024 27727 58024 27727 58025 29220 58025 29108 58025 29109 58026 29227 58026 27621 58026 27621 58027 29227 58027 29110 58027 29227 58028 29111 58028 29110 58028 29110 58029 29111 58029 29112 58029 29110 58030 29112 58030 29113 58030 29112 58031 29114 58031 29113 58031 29113 58032 29114 58032 29115 58032 29113 58033 29115 58033 29117 58033 29115 58034 29116 58034 29117 58034 29117 58035 29116 58035 29118 58035 29117 58036 29118 58036 29119 58036 29118 58037 29120 58037 29119 58037 29119 58038 29120 58038 29121 58038 29119 58039 29121 58039 29122 58039 27781 58040 27613 58040 29123 58040 29123 58041 27613 58041 29122 58041 29123 58042 29122 58042 29222 58042 29222 58043 29122 58043 29121 58043 29337 58044 27870 58044 29124 58044 29124 58045 27870 58045 29228 58045 29124 58046 29228 58046 29335 58046 29335 58047 29228 58047 29125 58047 29335 58048 29125 58048 29333 58048 29333 58049 29125 58049 29126 58049 29333 58050 29126 58050 29332 58050 29332 58051 29126 58051 29127 58051 29332 58052 29127 58052 29128 58052 29128 58053 29127 58053 29230 58053 29128 58054 29230 58054 27626 58054 27626 58055 29230 58055 27767 58055 27641 58056 29129 58056 29232 58056 27641 58057 29232 58057 29130 58057 29130 58058 29232 58058 29132 58058 29130 58059 29132 58059 29131 58059 29131 58060 29132 58060 29325 58060 29325 58061 29132 58061 29133 58061 29325 58062 29133 58062 29134 58062 29134 58063 29133 58063 29135 58063 29135 58064 29133 58064 29136 58064 29135 58065 29136 58065 29331 58065 29331 58066 29136 58066 29330 58066 29330 58067 29136 58067 29137 58067 29330 58068 29137 58068 29138 58068 29138 58069 29137 58069 29139 58069 29138 58070 29139 58070 29329 58070 29329 58071 29139 58071 27760 58071 29329 58072 27760 58072 29328 58072 28722 58073 28544 58073 28720 58073 28720 58074 28544 58074 29140 58074 28720 58075 29140 58075 29141 58075 28543 58076 29142 58076 29144 58076 29144 58077 29142 58077 29143 58077 29144 58078 29143 58078 28722 58078 28722 58079 29143 58079 28540 58079 28722 58080 28540 58080 28544 58080 28543 58081 29144 58081 28538 58081 28538 58082 29144 58082 29145 58082 28538 58083 29145 58083 28539 58083 28728 58084 28525 58084 29146 58084 29146 58085 28525 58085 28530 58085 29146 58086 28530 58086 28727 58086 28727 58087 28530 58087 29147 58087 28727 58088 29147 58088 29148 58088 29148 58089 29147 58089 28716 58089 29148 58090 28716 58090 28724 58090 28724 58091 28716 58091 28598 58091 28724 58092 28598 58092 29145 58092 29145 58093 28598 58093 28599 58093 29145 58094 28599 58094 28539 58094 29152 58095 29149 58095 28730 58095 28730 58096 29149 58096 29150 58096 28730 58097 29150 58097 28728 58097 28728 58098 29150 58098 28521 58098 28728 58099 28521 58099 28525 58099 29151 58100 28517 58100 29152 58100 29152 58101 28517 58101 28518 58101 29152 58102 28518 58102 29149 58102 29151 58103 29152 58103 29153 58103 29153 58104 29152 58104 28733 58104 29153 58105 28733 58105 28511 58105 28511 58106 28733 58106 28736 58106 28511 58107 28736 58107 28509 58107 28509 58108 28736 58108 28505 58108 28505 58109 28736 58109 29154 58109 28505 58110 29154 58110 29156 58110 29156 58111 29154 58111 29155 58111 29156 58112 29155 58112 28563 58112 29157 58113 27838 58113 29158 58113 29157 58114 29158 58114 29498 58114 29498 58115 29158 58115 29159 58115 29498 58116 29159 58116 29492 58116 29492 58117 29159 58117 29161 58117 29492 58118 29161 58118 29160 58118 29160 58119 29161 58119 29162 58119 29162 58120 29161 58120 28756 58120 29162 58121 28756 58121 29163 58121 28753 58122 29627 58122 28754 58122 28754 58123 29627 58123 29628 58123 28754 58124 29628 58124 28756 58124 28756 58125 29628 58125 29595 58125 28756 58126 29595 58126 29163 58126 29164 58127 29165 58127 28747 58127 28747 58128 29165 58128 29166 58128 28747 58129 29166 58129 28748 58129 28748 58130 29166 58130 29475 58130 28748 58131 29475 58131 29167 58131 29167 58132 29475 58132 29477 58132 29167 58133 29477 58133 29168 58133 29168 58134 29477 58134 29478 58134 29168 58135 29478 58135 28753 58135 28753 58136 29478 58136 29169 58136 28753 58137 29169 58137 29627 58137 29455 58138 29465 58138 29164 58138 29164 58139 29465 58139 29170 58139 29164 58140 29170 58140 29165 58140 29455 58141 29164 58141 29171 58141 29171 58142 29164 58142 28742 58142 29171 58143 28742 58143 29456 58143 29456 58144 28742 58144 28741 58144 29456 58145 28741 58145 29452 58145 29451 58146 29527 58146 29172 58146 29172 58147 29527 58147 28741 58147 28741 58148 29527 58148 29525 58148 28741 58149 29525 58149 29452 58149 29451 58150 29172 58150 29173 58150 29173 58151 29172 58151 29174 58151 29173 58152 29174 58152 29450 58152 29175 58153 29468 58153 29176 58153 29176 58154 29468 58154 29467 58154 29176 58155 29467 58155 29177 58155 29177 58156 29467 58156 29637 58156 29177 58157 29637 58157 29072 58157 29072 58158 29637 58158 29635 58158 29072 58159 29635 58159 29073 58159 29073 58160 29635 58160 29461 58160 29073 58161 29461 58161 29178 58161 29178 58162 29461 58162 29466 58162 29178 58163 29466 58163 29179 58163 29179 58164 29466 58164 29181 58164 29179 58165 29181 58165 29180 58165 29180 58166 29181 58166 29182 58166 29077 58167 29516 58167 29183 58167 29183 58168 29516 58168 29517 58168 29183 58169 29517 58169 29184 58169 29184 58170 29517 58170 29633 58170 29184 58171 29633 58171 29185 58171 29185 58172 29633 58172 29515 58172 29185 58173 29515 58173 29079 58173 29079 58174 29515 58174 29186 58174 29079 58175 29186 58175 29080 58175 29080 58176 29186 58176 29650 58176 29080 58177 29650 58177 29083 58177 29083 58178 29650 58178 27813 58178 27909 58179 29526 58179 29084 58179 29084 58180 29526 58180 29187 58180 29084 58181 29187 58181 29188 58181 29188 58182 29187 58182 29189 58182 29188 58183 29189 58183 29190 58183 29190 58184 29189 58184 29530 58184 29190 58185 29530 58185 29191 58185 29191 58186 29530 58186 29193 58186 29191 58187 29193 58187 29192 58187 29192 58188 29193 58188 29194 58188 29192 58189 29194 58189 29090 58189 29090 58190 29194 58190 29529 58190 29090 58191 29529 58191 29091 58191 29091 58192 29529 58192 27808 58192 29195 58193 27800 58193 29196 58193 29196 58194 27800 58194 29197 58194 29196 58195 29197 58195 29198 58195 29198 58196 29197 58196 29534 58196 29198 58197 29534 58197 29095 58197 29095 58198 29534 58198 29533 58198 29095 58199 29533 58199 29200 58199 29200 58200 29533 58200 29199 58200 29200 58201 29199 58201 29097 58201 29097 58202 29199 58202 29645 58202 29097 58203 29645 58203 29098 58203 29098 58204 29645 58204 29201 58204 27792 58205 27791 58205 29202 58205 29202 58206 27791 58206 29203 58206 29202 58207 29203 58207 29100 58207 29100 58208 29203 58208 29204 58208 29100 58209 29204 58209 29205 58209 29205 58210 29204 58210 29206 58210 29205 58211 29206 58211 29207 58211 29207 58212 29206 58212 29208 58212 29207 58213 29208 58213 29209 58213 29209 58214 29208 58214 29211 58214 29209 58215 29211 58215 29210 58215 29210 58216 29211 58216 29212 58216 27886 58217 29213 58217 29106 58217 29106 58218 29213 58218 29214 58218 29106 58219 29214 58219 29215 58219 29215 58220 29214 58220 29216 58220 29215 58221 29216 58221 29217 58221 29217 58222 29216 58222 29218 58222 29217 58223 29218 58223 29219 58223 29219 58224 29218 58224 29549 58224 29219 58225 29549 58225 29220 58225 29220 58226 29549 58226 29221 58226 29220 58227 29221 58227 29108 58227 29108 58228 29221 58228 29551 58228 29573 58229 27783 58229 27781 58229 27781 58230 29123 58230 29573 58230 29573 58231 29123 58231 29222 58231 29573 58232 29222 58232 29223 58232 29116 58233 29224 58233 29511 58233 29222 58234 29121 58234 29223 58234 29223 58235 29121 58235 29120 58235 29223 58236 29120 58236 29511 58236 29511 58237 29120 58237 29118 58237 29511 58238 29118 58238 29116 58238 29116 58239 29115 58239 29224 58239 29224 58240 29115 58240 29114 58240 29224 58241 29114 58241 29225 58241 29225 58242 29114 58242 29112 58242 29225 58243 29112 58243 29226 58243 29109 58244 29574 58244 29227 58244 29227 58245 29574 58245 29226 58245 29227 58246 29226 58246 29111 58246 29111 58247 29226 58247 29112 58247 27870 58248 29229 58248 29228 58248 29228 58249 29229 58249 29582 58249 29228 58250 29582 58250 29125 58250 29125 58251 29582 58251 29585 58251 29125 58252 29585 58252 29126 58252 29126 58253 29585 58253 29581 58253 29126 58254 29581 58254 29127 58254 29127 58255 29581 58255 29580 58255 29127 58256 29580 58256 29230 58256 29230 58257 29580 58257 29231 58257 29230 58258 29231 58258 27767 58258 27767 58259 29231 58259 29576 58259 29129 58260 27766 58260 29232 58260 29232 58261 27766 58261 29233 58261 29232 58262 29233 58262 29132 58262 29132 58263 29233 58263 29234 58263 29132 58264 29234 58264 29133 58264 29133 58265 29234 58265 29507 58265 29133 58266 29507 58266 29136 58266 29136 58267 29507 58267 29506 58267 29136 58268 29506 58268 29137 58268 29137 58269 29506 58269 29235 58269 29137 58270 29235 58270 29139 58270 29139 58271 29235 58271 29236 58271 29139 58272 29236 58272 27760 58272 27760 58273 29236 58273 29237 58273 29238 58274 29499 58274 29239 58274 29239 58275 29240 58275 29238 58275 29238 58276 29240 58276 29241 58276 29238 58277 29241 58277 29495 58277 29243 58278 29245 58278 29493 58278 29241 58279 29054 58279 29495 58279 29495 58280 29054 58280 29053 58280 29495 58281 29053 58281 29493 58281 29493 58282 29053 58282 29242 58282 29493 58283 29242 58283 29243 58283 29243 58284 29244 58284 29245 58284 29245 58285 29244 58285 29049 58285 29245 58286 29049 58286 29504 58286 29504 58287 29049 58287 29048 58287 29504 58288 29048 58288 29247 58288 29246 58289 27750 58289 29046 58289 29046 58290 27750 58290 29247 58290 29046 58291 29247 58291 29047 58291 29047 58292 29247 58292 29048 58292 29055 58293 29594 58293 29248 58293 29248 58294 29594 58294 29592 58294 29248 58295 29592 58295 29249 58295 29249 58296 29592 58296 29591 58296 29249 58297 29591 58297 29250 58297 29250 58298 29591 58298 29649 58298 29250 58299 29649 58299 29059 58299 29059 58300 29649 58300 29598 58300 29059 58301 29598 58301 29251 58301 29251 58302 29598 58302 29253 58302 29251 58303 29253 58303 29252 58303 29252 58304 29253 58304 27748 58304 27936 58305 29480 58305 29062 58305 29062 58306 29480 58306 29479 58306 29062 58307 29479 58307 29254 58307 29254 58308 29479 58308 29255 58308 29254 58309 29255 58309 29065 58309 29065 58310 29255 58310 29256 58310 29065 58311 29256 58311 29257 58311 29257 58312 29256 58312 29621 58312 29257 58313 29621 58313 29258 58313 29258 58314 29621 58314 29619 58314 29258 58315 29619 58315 29067 58315 29067 58316 29619 58316 29259 58316 29067 58317 29259 58317 27927 58317 27927 58318 29259 58318 27737 58318 27727 58319 28572 58319 29260 58319 29260 58320 28572 58320 29261 58320 29260 58321 29261 58321 29262 58321 29262 58322 29261 58322 28571 58322 29262 58323 28571 58323 29107 58323 29107 58324 28571 58324 28550 58324 29107 58325 28550 58325 29263 58325 29263 58326 28550 58326 29264 58326 29263 58327 29264 58327 29265 58327 29265 58328 29264 58328 29267 58328 29265 58329 29267 58329 29266 58329 29266 58330 29267 58330 28569 58330 28581 58331 28580 58331 29099 58331 29099 58332 29268 58332 28581 58332 28581 58333 29268 58333 29269 58333 28581 58334 29269 58334 29271 58334 29102 58335 29273 58335 28583 58335 29269 58336 29270 58336 29271 58336 29271 58337 29270 58337 29101 58337 29271 58338 29101 58338 28583 58338 28583 58339 29101 58339 29272 58339 28583 58340 29272 58340 29102 58340 29102 58341 29103 58341 29273 58341 29273 58342 29103 58342 29274 58342 29273 58343 29274 58343 29275 58343 29275 58344 29274 58344 29276 58344 29275 58345 29276 58345 29277 58345 29105 58346 27726 58346 29278 58346 29278 58347 27726 58347 29277 58347 29278 58348 29277 58348 29104 58348 29104 58349 29277 58349 29276 58349 27717 58350 28590 58350 29279 58350 29279 58351 28590 58351 28589 58351 29279 58352 28589 58352 29096 58352 29096 58353 28589 58353 28588 58353 29096 58354 28588 58354 29094 58354 29094 58355 28588 58355 29280 58355 29094 58356 29280 58356 29093 58356 29093 58357 29280 58357 29281 58357 29093 58358 29281 58358 29092 58358 29092 58359 29281 58359 28547 58359 29092 58360 28547 58360 27713 58360 27713 58361 28547 58361 28546 58361 29283 58362 27709 58362 29282 58362 29088 58363 29284 58363 28595 58363 29282 58364 29085 58364 29283 58364 29283 58365 29085 58365 29086 58365 29283 58366 29086 58366 28595 58366 28595 58367 29086 58367 29087 58367 28595 58368 29087 58368 29088 58368 29088 58369 29089 58369 29284 58369 29284 58370 29089 58370 29290 58370 29284 58371 29290 58371 29289 58371 29285 58372 28593 58372 29286 58372 29286 58373 28593 58373 28666 58373 29286 58374 28666 58374 29287 58374 29287 58375 28666 58375 29289 58375 29287 58376 29289 58376 29288 58376 29288 58377 29289 58377 29290 58377 29082 58378 28611 58378 29081 58378 29081 58379 28611 58379 29291 58379 29081 58380 29291 58380 29293 58380 29293 58381 29291 58381 29292 58381 29293 58382 29292 58382 29078 58382 29078 58383 29292 58383 28609 58383 29078 58384 28609 58384 29294 58384 29294 58385 28609 58385 28608 58385 29294 58386 28608 58386 29076 58386 29076 58387 28608 58387 28607 58387 29076 58388 28607 58388 27694 58388 27694 58389 28607 58389 28606 58389 28613 58390 27686 58390 27925 58390 29297 58391 29295 58391 29296 58391 27925 58392 29069 58392 28613 58392 28613 58393 29069 58393 29070 58393 28613 58394 29070 58394 29296 58394 29296 58395 29070 58395 29071 58395 29296 58396 29071 58396 29297 58396 29297 58397 29298 58397 29295 58397 29295 58398 29298 58398 29302 58398 29295 58399 29302 58399 29301 58399 29299 58400 27677 58400 29075 58400 29075 58401 27677 58401 28499 58401 29075 58402 28499 58402 29300 58402 29300 58403 28499 58403 29301 58403 29300 58404 29301 58404 29074 58404 29074 58405 29301 58405 29302 58405 28617 58406 28615 58406 29061 58406 29303 58407 29304 58407 29306 58407 29061 58408 29305 58408 28617 58408 28617 58409 29305 58409 29063 58409 28617 58410 29063 58410 29306 58410 29306 58411 29063 58411 29064 58411 29306 58412 29064 58412 29303 58412 29303 58413 29066 58413 29304 58413 29304 58414 29066 58414 29307 58414 29304 58415 29307 58415 29308 58415 27926 58416 27666 58416 29068 58416 29068 58417 27666 58417 28620 58417 29068 58418 28620 58418 29309 58418 29309 58419 28620 58419 29308 58419 29309 58420 29308 58420 29310 58420 29310 58421 29308 58421 29307 58421 29311 58422 29312 58422 29060 58422 29060 58423 29312 58423 29313 58423 29060 58424 29313 58424 29314 58424 29314 58425 29313 58425 29315 58425 29314 58426 29315 58426 29058 58426 29058 58427 29315 58427 28513 58427 29058 58428 28513 58428 29057 58428 29057 58429 28513 58429 28689 58429 29057 58430 28689 58430 29056 58430 29056 58431 28689 58431 29316 58431 29056 58432 29316 58432 27941 58432 27941 58433 29316 58433 28622 58433 27943 58434 27645 58434 29318 58434 29318 58435 27645 58435 29317 58435 29318 58436 29317 58436 29052 58436 29052 58437 29317 58437 29319 58437 29052 58438 29319 58438 29051 58438 29051 58439 29319 58439 29320 58439 29051 58440 29320 58440 29050 58440 29050 58441 29320 58441 29322 58441 29050 58442 29322 58442 29321 58442 29321 58443 29322 58443 29323 58443 29321 58444 29323 58444 27950 58444 27950 58445 29323 58445 27656 58445 28564 58446 27642 58446 27641 58446 29134 58447 29324 58447 29326 58447 27641 58448 29130 58448 28564 58448 28564 58449 29130 58449 29131 58449 28564 58450 29131 58450 29326 58450 29326 58451 29131 58451 29325 58451 29326 58452 29325 58452 29134 58452 29134 58453 29135 58453 29324 58453 29324 58454 29135 58454 29331 58454 29324 58455 29331 58455 29327 58455 29328 58456 28567 58456 29329 58456 29329 58457 28567 58457 28566 58457 29329 58458 28566 58458 29138 58458 29138 58459 28566 58459 29327 58459 29138 58460 29327 58460 29330 58460 29330 58461 29327 58461 29331 58461 27626 58462 28559 58462 29128 58462 29128 58463 28559 58463 28624 58463 29128 58464 28624 58464 29332 58464 29332 58465 28624 58465 28625 58465 29332 58466 28625 58466 29333 58466 29333 58467 28625 58467 28628 58467 29333 58468 28628 58468 29335 58468 29335 58469 28628 58469 29334 58469 29335 58470 29334 58470 29124 58470 29124 58471 29334 58471 29336 58471 29124 58472 29336 58472 29337 58472 29337 58473 29336 58473 28633 58473 27613 58474 27612 58474 29122 58474 29122 58475 27612 58475 29338 58475 29122 58476 29338 58476 29119 58476 29119 58477 29338 58477 29339 58477 29119 58478 29339 58478 29117 58478 29117 58479 29339 58479 28638 58479 29117 58480 28638 58480 29113 58480 29113 58481 28638 58481 28637 58481 29113 58482 28637 58482 29110 58482 29110 58483 28637 58483 28634 58483 29110 58484 28634 58484 27621 58484 27621 58485 28634 58485 27622 58485 28366 58486 27611 58486 29340 58486 28366 58487 29340 58487 28368 58487 28368 58488 29340 58488 28776 58488 28368 58489 28776 58489 28369 58489 28369 58490 28776 58490 28778 58490 28369 58491 28778 58491 29341 58491 29341 58492 28778 58492 29342 58492 29341 58493 29342 58493 29343 58493 29343 58494 29342 58494 28781 58494 29343 58495 28781 58495 29344 58495 29344 58496 28781 58496 28782 58496 29344 58497 28782 58497 28372 58497 28372 58498 28782 58498 28784 58498 28372 58499 28784 58499 28374 58499 28374 58500 28784 58500 28785 58500 28374 58501 28785 58501 29345 58501 29345 58502 28785 58502 28786 58502 29345 58503 28786 58503 28376 58503 28376 58504 28786 58504 29346 58504 28376 58505 29346 58505 28379 58505 28379 58506 29346 58506 29347 58506 28379 58507 29347 58507 28380 58507 28380 58508 29347 58508 28790 58508 28380 58509 28790 58509 28381 58509 28381 58510 28790 58510 29348 58510 28381 58511 29348 58511 29349 58511 29349 58512 29348 58512 28793 58512 29349 58513 28793 58513 29350 58513 29350 58514 28793 58514 28794 58514 29350 58515 28794 58515 28346 58515 28346 58516 28794 58516 28795 58516 28346 58517 28795 58517 29351 58517 29351 58518 28795 58518 29352 58518 29351 58519 29352 58519 28348 58519 28348 58520 29352 58520 29353 58520 28348 58521 29353 58521 28350 58521 27596 58522 29355 58522 29354 58522 29354 58523 29355 58523 29356 58523 29354 58524 29356 58524 29357 58524 29357 58525 29356 58525 28143 58525 29357 58526 28143 58526 29358 58526 29358 58527 28143 58527 28145 58527 29358 58528 28145 58528 29359 58528 29359 58529 28145 58529 29360 58529 29359 58530 29360 58530 28878 58530 28878 58531 29360 58531 28147 58531 28878 58532 28147 58532 29361 58532 29361 58533 28147 58533 29362 58533 29361 58534 29362 58534 29363 58534 29363 58535 29362 58535 28149 58535 29363 58536 28149 58536 28875 58536 28875 58537 28149 58537 29364 58537 28875 58538 29364 58538 29365 58538 29365 58539 29364 58539 28152 58539 29365 58540 28152 58540 28872 58540 28872 58541 28152 58541 28153 58541 28872 58542 28153 58542 29366 58542 29366 58543 28153 58543 28154 58543 29366 58544 28154 58544 29367 58544 29367 58545 28154 58545 29368 58545 29367 58546 29368 58546 29369 58546 29369 58547 29368 58547 29371 58547 29369 58548 29371 58548 29370 58548 29370 58549 29371 58549 29373 58549 29370 58550 29373 58550 29372 58550 29372 58551 29373 58551 28158 58551 29372 58552 28158 58552 29374 58552 29374 58553 28158 58553 28159 58553 29374 58554 28159 58554 28141 58554 28141 58555 28159 58555 28160 58555 29375 58556 28850 58556 29376 58556 29375 58557 29376 58557 28161 58557 28161 58558 29376 58558 28851 58558 28161 58559 28851 58559 29377 58559 29377 58560 28851 58560 28853 58560 29377 58561 28853 58561 29378 58561 29378 58562 28853 58562 29379 58562 29378 58563 29379 58563 29380 58563 29380 58564 29379 58564 28855 58564 29380 58565 28855 58565 28163 58565 28163 58566 28855 58566 28856 58566 28163 58567 28856 58567 28164 58567 28164 58568 28856 58568 28858 58568 28164 58569 28858 58569 28166 58569 28166 58570 28858 58570 28859 58570 28166 58571 28859 58571 29382 58571 29382 58572 28859 58572 29381 58572 29382 58573 29381 58573 28167 58573 28167 58574 29381 58574 29383 58574 28167 58575 29383 58575 29384 58575 29384 58576 29383 58576 29385 58576 29384 58577 29385 58577 28169 58577 28169 58578 29385 58578 29386 58578 28169 58579 29386 58579 28170 58579 28170 58580 29386 58580 28864 58580 28170 58581 28864 58581 28171 58581 28171 58582 28864 58582 28865 58582 28171 58583 28865 58583 28172 58583 28172 58584 28865 58584 29387 58584 28172 58585 29387 58585 28174 58585 28174 58586 29387 58586 28866 58586 28174 58587 28866 58587 28176 58587 28176 58588 28866 58588 28177 58588 28176 58589 28177 58589 27560 58589 28305 58590 28797 58590 29388 58590 28305 58591 29388 58591 29389 58591 29389 58592 29388 58592 29390 58592 29389 58593 29390 58593 29392 58593 29392 58594 29390 58594 29391 58594 29392 58595 29391 58595 28308 58595 28308 58596 29391 58596 28801 58596 28308 58597 28801 58597 29393 58597 29393 58598 28801 58598 28802 58598 29393 58599 28802 58599 29394 58599 29394 58600 28802 58600 29395 58600 29394 58601 29395 58601 28310 58601 28310 58602 29395 58602 29397 58602 28310 58603 29397 58603 29396 58603 29396 58604 29397 58604 29398 58604 29396 58605 29398 58605 29399 58605 29399 58606 29398 58606 29400 58606 29399 58607 29400 58607 28314 58607 28314 58608 29400 58608 28804 58608 28314 58609 28804 58609 29401 58609 29401 58610 28804 58610 28805 58610 29401 58611 28805 58611 29402 58611 29402 58612 28805 58612 29403 58612 29402 58613 29403 58613 28315 58613 28315 58614 29403 58614 29404 58614 28315 58615 29404 58615 28318 58615 28318 58616 29404 58616 29405 58616 28318 58617 29405 58617 29406 58617 29406 58618 29405 58618 29407 58618 29406 58619 29407 58619 28320 58619 28320 58620 29407 58620 28809 58620 28320 58621 28809 58621 29408 58621 29408 58622 28809 58622 28811 58622 29408 58623 28811 58623 28323 58623 28323 58624 28811 58624 29409 58624 28323 58625 29409 58625 27543 58625 28831 58626 28322 58626 29410 58626 29410 58627 28322 58627 29411 58627 29410 58628 29411 58628 29412 58628 29412 58629 29411 58629 28325 58629 29412 58630 28325 58630 29413 58630 29413 58631 28325 58631 28326 58631 29413 58632 28326 58632 28828 58632 28828 58633 28326 58633 29414 58633 28828 58634 29414 58634 28826 58634 28826 58635 29414 58635 29415 58635 28826 58636 29415 58636 29416 58636 29416 58637 29415 58637 28293 58637 29416 58638 28293 58638 28823 58638 28823 58639 28293 58639 29417 58639 28823 58640 29417 58640 28822 58640 28822 58641 29417 58641 28295 58641 28822 58642 28295 58642 28821 58642 28821 58643 28295 58643 29418 58643 28821 58644 29418 58644 28818 58644 28818 58645 29418 58645 29419 58645 28818 58646 29419 58646 29420 58646 29420 58647 29419 58647 28298 58647 29420 58648 28298 58648 28817 58648 28817 58649 28298 58649 29422 58649 28817 58650 29422 58650 29421 58650 29421 58651 29422 58651 29423 58651 29421 58652 29423 58652 28815 58652 28815 58653 29423 58653 28301 58653 28815 58654 28301 58654 29425 58654 29425 58655 28301 58655 29424 58655 29425 58656 29424 58656 29426 58656 29426 58657 29424 58657 29427 58657 29426 58658 29427 58658 28812 58658 28812 58659 29427 58659 28304 58659 29428 58660 28248 58660 29429 58660 29429 58661 28248 58661 29430 58661 29429 58662 29430 58662 28848 58662 28848 58663 29430 58663 28250 58663 28848 58664 28250 58664 28846 58664 28846 58665 28250 58665 28251 58665 28846 58666 28251 58666 29431 58666 29431 58667 28251 58667 28253 58667 29431 58668 28253 58668 28843 58668 28843 58669 28253 58669 28254 58669 28843 58670 28254 58670 28842 58670 28842 58671 28254 58671 28255 58671 28842 58672 28255 58672 29432 58672 29432 58673 28255 58673 28256 58673 29432 58674 28256 58674 29433 58674 29433 58675 28256 58675 29434 58675 29433 58676 29434 58676 29435 58676 29435 58677 29434 58677 28257 58677 29435 58678 28257 58678 28838 58678 28838 58679 28257 58679 29437 58679 28838 58680 29437 58680 29436 58680 29436 58681 29437 58681 29438 58681 29436 58682 29438 58682 28837 58682 28837 58683 29438 58683 29439 58683 28837 58684 29439 58684 28835 58684 28835 58685 29439 58685 28260 58685 28835 58686 28260 58686 29440 58686 29440 58687 28260 58687 29441 58687 29440 58688 29441 58688 29442 58688 29442 58689 29441 58689 29444 58689 29442 58690 29444 58690 29443 58690 29443 58691 29444 58691 29445 58691 29443 58692 29445 58692 28243 58692 28243 58693 29445 58693 28263 58693 29641 58694 28962 58694 29643 58694 29599 58695 29598 58695 29649 58695 27772 58696 27770 58696 29446 58696 29573 58697 29223 58697 29572 58697 29552 58698 28997 58698 29575 58698 27821 58699 29615 58699 27822 58699 29447 58700 29448 58700 29449 58700 27827 58701 29553 58701 27825 58701 29570 58702 29572 58702 27831 58702 29162 58703 29485 58703 29601 58703 29525 58704 29454 58704 29452 58704 29173 58705 29605 58705 29451 58705 27822 58706 29615 58706 29450 58706 29607 58707 29189 58707 29605 58707 29605 58708 29189 58708 29187 58708 29605 58709 29187 58709 29451 58709 29451 58710 29187 58710 29526 58710 29456 58711 28018 58711 29459 58711 28018 58712 29456 58712 28015 58712 28015 58713 29456 58713 29452 58713 28015 58714 29452 58714 29453 58714 29453 58715 29452 58715 29454 58715 29453 58716 29454 58716 29523 58716 29455 58717 29171 58717 29457 58717 29457 58718 29171 58718 29456 58718 29457 58719 29456 58719 29458 58719 29458 58720 29456 58720 29459 58720 29458 58721 29459 58721 28019 58721 28949 58722 29460 58722 29461 58722 28951 58723 28950 58723 29462 58723 29462 58724 28950 58724 29463 58724 29637 58725 29467 58725 29636 58725 29636 58726 29467 58726 29165 58726 29636 58727 29165 58727 29464 58727 29464 58728 29165 58728 29170 58728 29464 58729 29170 58729 29465 58729 27818 58730 29182 58730 29470 58730 29470 58731 29182 58731 29181 58731 29470 58732 29181 58732 29460 58732 29460 58733 29181 58733 29466 58733 29460 58734 29466 58734 29461 58734 29467 58735 29468 58735 29165 58735 29165 58736 29468 58736 29469 58736 29165 58737 29469 58737 29166 58737 29166 58738 29469 58738 29474 58738 29166 58739 29474 58739 29475 58739 29470 58740 29471 58740 27818 58740 27818 58741 29471 58741 28035 58741 27818 58742 28035 58742 29472 58742 29472 58743 28035 58743 29475 58743 29472 58744 29475 58744 29473 58744 29473 58745 29475 58745 29474 58745 28035 58746 28037 58746 29475 58746 29475 58747 28037 58747 29476 58747 29475 58748 29476 58748 29477 58748 29477 58749 29476 58749 28039 58749 29477 58750 28039 58750 29478 58750 29478 58751 28039 58751 28042 58751 29478 58752 28042 58752 28045 58752 29480 58753 29481 58753 29478 58753 29665 58754 29256 58754 29462 58754 29462 58755 29256 58755 29255 58755 29462 58756 29255 58756 29479 58756 28045 58757 28951 58757 29478 58757 29478 58758 28951 58758 29462 58758 29478 58759 29462 58759 29480 58759 29480 58760 29462 58760 29479 58760 29620 58761 29626 58761 29259 58761 29259 58762 29626 58762 27737 58762 29481 58763 29482 58763 29478 58763 29478 58764 29482 58764 29483 58764 29478 58765 29483 58765 29169 58765 29169 58766 29483 58766 29484 58766 29169 58767 29484 58767 29625 58767 29162 58768 29163 58768 29485 58768 29485 58769 29163 58769 29595 58769 29485 58770 29595 58770 29589 58770 28068 58771 28066 58771 29160 58771 29160 58772 28066 58772 28065 58772 29160 58773 28065 58773 29492 58773 29486 58774 29487 58774 29488 58774 29488 58775 29487 58775 29490 58775 29488 58776 29490 58776 29489 58776 29489 58777 29490 58777 29496 58777 29489 58778 29496 58778 28918 58778 28918 58779 29496 58779 29492 58779 28918 58780 29492 58780 29491 58780 29491 58781 29492 58781 28065 58781 29493 58782 29245 58782 29157 58782 27750 58783 29640 58783 29247 58783 29247 58784 29640 58784 29494 58784 29247 58785 29494 58785 29504 58785 29493 58786 29157 58786 29495 58786 29496 58787 27757 58787 29492 58787 29492 58788 27757 58788 29497 58788 29492 58789 29497 58789 29498 58789 29498 58790 29497 58790 29499 58790 29498 58791 29499 58791 29157 58791 29157 58792 29499 58792 29238 58792 29157 58793 29238 58793 29495 58793 29502 58794 27765 58794 27763 58794 29503 58795 29500 58795 29157 58795 29157 58796 29500 58796 29501 58796 29157 58797 29501 58797 27837 58797 27765 58798 29502 58798 27766 58798 27763 58799 29503 58799 29502 58799 29502 58800 29503 58800 29157 58800 29502 58801 29157 58801 29494 58801 29494 58802 29157 58802 29245 58802 29494 58803 29245 58803 29504 58803 29501 58804 29237 58804 27837 58804 27837 58805 29237 58805 29236 58805 27837 58806 29236 58806 27835 58806 27835 58807 29236 58807 29235 58807 27835 58808 29235 58808 27957 58808 27957 58809 29235 58809 29506 58809 27957 58810 29506 58810 27956 58810 29638 58811 29505 58811 29502 58811 29502 58812 29505 58812 27952 58812 29502 58813 27952 58813 27766 58813 27766 58814 27952 58814 29233 58814 27956 58815 29506 58815 27954 58815 27954 58816 29506 58816 29507 58816 27954 58817 29507 58817 27952 58817 27952 58818 29507 58818 29234 58818 27952 58819 29234 58819 29233 58819 27957 58820 29508 58820 27835 58820 27835 58821 29508 58821 29033 58821 27835 58822 29033 58822 27834 58822 27834 58823 29033 58823 29509 58823 27834 58824 29509 58824 29036 58824 29584 58825 29014 58825 29510 58825 29510 58826 29014 58826 29570 58826 29572 58827 29223 58827 27831 58827 27831 58828 29223 58828 29511 58828 27831 58829 29511 58829 29512 58829 29575 58830 28997 58830 29512 58830 29214 58831 29553 58831 29216 58831 29216 58832 29553 58832 27827 58832 29216 58833 27827 58833 29218 58833 29218 58834 27827 58834 27829 58834 29218 58835 27829 58835 29549 58835 28997 58836 28998 58836 29512 58836 29512 58837 28998 58837 29001 58837 29512 58838 29001 58838 27829 58838 27804 58839 29537 58839 27802 58839 27802 58840 29537 58840 29615 58840 27802 58841 29615 58841 27800 58841 27800 58842 29615 58842 27821 58842 27800 58843 27821 58843 29197 58843 29197 58844 27821 58844 29449 58844 29197 58845 29449 58845 29534 58845 29534 58846 29449 58846 29448 58846 29461 58847 29635 58847 29672 58847 27816 58848 29513 58848 29457 58848 29457 58849 29513 58849 27815 58849 29457 58850 27815 58850 29514 58850 29514 58851 27815 58851 29518 58851 29514 58852 29518 58852 29672 58852 29650 58853 29186 58853 29634 58853 29634 58854 29186 58854 29515 58854 29634 58855 29515 58855 29633 58855 27816 58856 29457 58856 29516 58856 29516 58857 29457 58857 29458 58857 29516 58858 29458 58858 29517 58858 29517 58859 29458 58859 28019 58859 29517 58860 28019 58860 29633 58860 29518 58861 29519 58861 29672 58861 29672 58862 29519 58862 29520 58862 29672 58863 29520 58863 29673 58863 29673 58864 29520 58864 27813 58864 29673 58865 27813 58865 29651 58865 29521 58866 27810 58866 29528 58866 29528 58867 27810 58867 27809 58867 29528 58868 29522 58868 29521 58868 29521 58869 29522 58869 29523 58869 29521 58870 29523 58870 27812 58870 27812 58871 29523 58871 29454 58871 27812 58872 29454 58872 29524 58872 29524 58873 29454 58873 29525 58873 29524 58874 29525 58874 29526 58874 29526 58875 29525 58875 29527 58875 29526 58876 29527 58876 29451 58876 29529 58877 29611 58877 27808 58877 27808 58878 29611 58878 29643 58878 27808 58879 29643 58879 27809 58879 27809 58880 29643 58880 28962 58880 27809 58881 28962 58881 29528 58881 29529 58882 29194 58882 29611 58882 29611 58883 29194 58883 29193 58883 29611 58884 29193 58884 29607 58884 29607 58885 29193 58885 29530 58885 29607 58886 29530 58886 29189 58886 29538 58887 29540 58887 29201 58887 27995 58888 29645 58888 29531 58888 29531 58889 29645 58889 29199 58889 29531 58890 29199 58890 29532 58890 29532 58891 29199 58891 29533 58891 29532 58892 29533 58892 27999 58892 27999 58893 29533 58893 29534 58893 27999 58894 29534 58894 28981 58894 28981 58895 29534 58895 29448 58895 28981 58896 29448 58896 28983 58896 28983 58897 29448 58897 29447 58897 28983 58898 29447 58898 29535 58898 29535 58899 29447 58899 27824 58899 29535 58900 27824 58900 29555 58900 27804 58901 29536 58901 29537 58901 29537 58902 29536 58902 27805 58902 29537 58903 27805 58903 29538 58903 29538 58904 27805 58904 29539 58904 29538 58905 29539 58905 29540 58905 29656 58906 29541 58906 29679 58906 29679 58907 29541 58907 29542 58907 29679 58908 29542 58908 29543 58908 29543 58909 29542 58909 29212 58909 29543 58910 29212 58910 29560 58910 29560 58911 29212 58911 29211 58911 29560 58912 29211 58912 29544 58912 29211 58913 29208 58913 29544 58913 29544 58914 29208 58914 29206 58914 29544 58915 29206 58915 29545 58915 29206 58916 29204 58916 29545 58916 29545 58917 29204 58917 29203 58917 29545 58918 29203 58918 29546 58918 29546 58919 29203 58919 27791 58919 29546 58920 27791 58920 29547 58920 29001 58921 29548 58921 27829 58921 27829 58922 29548 58922 29004 58922 27829 58923 29004 58923 29549 58923 29549 58924 29004 58924 29006 58924 29549 58925 29006 58925 29221 58925 29221 58926 29006 58926 29550 58926 29221 58927 29550 58927 29551 58927 29551 58928 29550 58928 29562 58928 29551 58929 29562 58929 27786 58929 29565 58930 29566 58930 29552 58930 29214 58931 29213 58931 29553 58931 29553 58932 29213 58932 29560 58932 29553 58933 29560 58933 27825 58933 27825 58934 29560 58934 29544 58934 27825 58935 29544 58935 29554 58935 29554 58936 29544 58936 29545 58936 29554 58937 29545 58937 27824 58937 27824 58938 29545 58938 29546 58938 27824 58939 29546 58939 29555 58939 29555 58940 29546 58940 29547 58940 29555 58941 29547 58941 28986 58941 28986 58942 29547 58942 29556 58942 28986 58943 29556 58943 29557 58943 29557 58944 29556 58944 29558 58944 29557 58945 29558 58945 29656 58945 29213 58946 29559 58946 29560 58946 29560 58947 29559 58947 29561 58947 29560 58948 29561 58948 27790 58948 27786 58949 29562 58949 29563 58949 29563 58950 29562 58950 27983 58950 29563 58951 27983 58951 29564 58951 29564 58952 27983 58952 27981 58952 29564 58953 27981 58953 29565 58953 29565 58954 27981 58954 27979 58954 29565 58955 27979 58955 29566 58955 29019 58956 29023 58956 27780 58956 27780 58957 29023 58957 27969 58957 27780 58958 27969 58958 29567 58958 29567 58959 27969 58959 29664 58959 29567 58960 29664 58960 29568 58960 29014 58961 29569 58961 29570 58961 29570 58962 29569 58962 29017 58962 29570 58963 29017 58963 29572 58963 29572 58964 29017 58964 29571 58964 29572 58965 29571 58965 29573 58965 29573 58966 29571 58966 29019 58966 29573 58967 29019 58967 27783 58967 27783 58968 29019 58968 27780 58968 29552 58969 29575 58969 29565 58969 29565 58970 29575 58970 29574 58970 29565 58971 29574 58971 29671 58971 29511 58972 29224 58972 29512 58972 29512 58973 29224 58973 29225 58973 29512 58974 29225 58974 29575 58974 29575 58975 29225 58975 29226 58975 29575 58976 29226 58976 29574 58976 29587 58977 29588 58977 29576 58977 29576 58978 29588 58978 29577 58978 29577 58979 29588 58979 29038 58979 29577 58980 29038 58980 29578 58980 29578 58981 29038 58981 29040 58981 29578 58982 29040 58982 27769 58982 27769 58983 29040 58983 29045 58983 27769 58984 29045 58984 27770 58984 29579 58985 29229 58985 29646 58985 29646 58986 29229 58986 27773 58986 29576 58987 29231 58987 29587 58987 29587 58988 29231 58988 29580 58988 29587 58989 29580 58989 29586 58989 29586 58990 29580 58990 29581 58990 29586 58991 29581 58991 29585 58991 29585 58992 29582 58992 29583 58992 29583 58993 29582 58993 29229 58993 29583 58994 29229 58994 27966 58994 27966 58995 29229 58995 29579 58995 27966 58996 29579 58996 27967 58996 29583 58997 27965 58997 29585 58997 29585 58998 27965 58998 29584 58998 29585 58999 29584 58999 29586 58999 29586 59000 29584 59000 29510 59000 29586 59001 29510 59001 29587 59001 29587 59002 29510 59002 27834 59002 29587 59003 27834 59003 29588 59003 29588 59004 27834 59004 29036 59004 29588 59005 29036 59005 29038 59005 27742 59006 27744 59006 29589 59006 29589 59007 27744 59007 29590 59007 29589 59008 29590 59008 29485 59008 29649 59009 29591 59009 29658 59009 29658 59010 29591 59010 29592 59010 29658 59011 29592 59011 29593 59011 29593 59012 29592 59012 29594 59012 29593 59013 29594 59013 28939 59013 28939 59014 29594 59014 27740 59014 28939 59015 27740 59015 28940 59015 28940 59016 27740 59016 27742 59016 28940 59017 27742 59017 29632 59017 29632 59018 27742 59018 29589 59018 29632 59019 29589 59019 29630 59019 29630 59020 29589 59020 29595 59020 29630 59021 29595 59021 29628 59021 29590 59022 29596 59022 29485 59022 29485 59023 29596 59023 29597 59023 29485 59024 29597 59024 29601 59024 29601 59025 29597 59025 27748 59025 29601 59026 27748 59026 29253 59026 29598 59027 29599 59027 29253 59027 29599 59028 29600 59028 29253 59028 29253 59029 29600 59029 28068 59029 29253 59030 28068 59030 29601 59030 29601 59031 28068 59031 29160 59031 29601 59032 29160 59032 29162 59032 27776 59033 29568 59033 29602 59033 29602 59034 29568 59034 29664 59034 29602 59035 29664 59035 29603 59035 29604 59036 29655 59036 27994 59036 27994 59037 29655 59037 29654 59037 27994 59038 29654 59038 27995 59038 29173 59039 29450 59039 29605 59039 29605 59040 29450 59040 29615 59040 29605 59041 29615 59041 28008 59041 29610 59042 29611 59042 29606 59042 29606 59043 29611 59043 29607 59043 29606 59044 29607 59044 29608 59044 29608 59045 29607 59045 29605 59045 29608 59046 29605 59046 29609 59046 29609 59047 29605 59047 28008 59047 29610 59048 28005 59048 29611 59048 29611 59049 28005 59049 29612 59049 29611 59050 29612 59050 29538 59050 29538 59051 29612 59051 28976 59051 28976 59052 29613 59052 29538 59052 29538 59053 29613 59053 29614 59053 29538 59054 29614 59054 29537 59054 29537 59055 29614 59055 28973 59055 29537 59056 28973 59056 29615 59056 29615 59057 28973 59057 28972 59057 29615 59058 28972 59058 28008 59058 29616 59059 29617 59059 28925 59059 28925 59060 29617 59060 29639 59060 28925 59061 29639 59061 29618 59061 29618 59062 29639 59062 29486 59062 29259 59063 29619 59063 29620 59063 29620 59064 29619 59064 29621 59064 29620 59065 29621 59065 29622 59065 29622 59066 29621 59066 29623 59066 29622 59067 29623 59067 28938 59067 28938 59068 29623 59068 29624 59068 28938 59069 29624 59069 29657 59069 27737 59070 29626 59070 29625 59070 29625 59071 29626 59071 28057 59071 29625 59072 28057 59072 29169 59072 29169 59073 28057 59073 28056 59073 29169 59074 28056 59074 29627 59074 29627 59075 28056 59075 28054 59075 29627 59076 28054 59076 29628 59076 29628 59077 28054 59077 29629 59077 29628 59078 29629 59078 29630 59078 29630 59079 29629 59079 29631 59079 29630 59080 29631 59080 29632 59080 28019 59081 28022 59081 29633 59081 29633 59082 28022 59082 28023 59082 29633 59083 28023 59083 29634 59083 29634 59084 28023 59084 28963 59084 29634 59085 28963 59085 29642 59085 27770 59086 29045 59086 29446 59086 29446 59087 29045 59087 29043 59087 29446 59088 29043 59088 29647 59088 29455 59089 29457 59089 29465 59089 29465 59090 29457 59090 29514 59090 29465 59091 29514 59091 29464 59091 29464 59092 29514 59092 29672 59092 29464 59093 29672 59093 29636 59093 29636 59094 29672 59094 29635 59094 29636 59095 29635 59095 29637 59095 29043 59096 29638 59096 29647 59096 29647 59097 29638 59097 29502 59097 29647 59098 29502 59098 29648 59098 29648 59099 29502 59099 29494 59099 29648 59100 29494 59100 29639 59100 29639 59101 29494 59101 29640 59101 29639 59102 29640 59102 29486 59102 29486 59103 29640 59103 27750 59103 29486 59104 27750 59104 29487 59104 28963 59105 29641 59105 29642 59105 29642 59106 29641 59106 29643 59106 29642 59107 29643 59107 29644 59107 29644 59108 29643 59108 29611 59108 29644 59109 29611 59109 29654 59109 29654 59110 29611 59110 29538 59110 29654 59111 29538 59111 27995 59111 27995 59112 29538 59112 29201 59112 27995 59113 29201 59113 29645 59113 27773 59114 27772 59114 29646 59114 29646 59115 27772 59115 29446 59115 29646 59116 29446 59116 29662 59116 29662 59117 29446 59117 29647 59117 29662 59118 29647 59118 29660 59118 29660 59119 29647 59119 29648 59119 29660 59120 29648 59120 29659 59120 29659 59121 29648 59121 29639 59121 29659 59122 29639 59122 29658 59122 29658 59123 29639 59123 29617 59123 29658 59124 29617 59124 29649 59124 29649 59125 29617 59125 29616 59125 29649 59126 29616 59126 29599 59126 27813 59127 29650 59127 29651 59127 29651 59128 29650 59128 29634 59128 29651 59129 29634 59129 29676 59129 29676 59130 29634 59130 29642 59130 29676 59131 29642 59131 29652 59131 29652 59132 29642 59132 29644 59132 29652 59133 29644 59133 29653 59133 29653 59134 29644 59134 29654 59134 29653 59135 29654 59135 29679 59135 29679 59136 29654 59136 29655 59136 29679 59137 29655 59137 29656 59137 29656 59138 29655 59138 29604 59138 29656 59139 29604 59139 29557 59139 28939 59140 29657 59140 29593 59140 29593 59141 29657 59141 29624 59141 29593 59142 29624 59142 29658 59142 29658 59143 29624 59143 29667 59143 29658 59144 29667 59144 29659 59144 29659 59145 29667 59145 29668 59145 29659 59146 29668 59146 29660 59146 29660 59147 29668 59147 29661 59147 29660 59148 29661 59148 29662 59148 29662 59149 29661 59149 29670 59149 29662 59150 29670 59150 29646 59150 29646 59151 29670 59151 29663 59151 29646 59152 29663 59152 29579 59152 29579 59153 29663 59153 29603 59153 29579 59154 29603 59154 27967 59154 27967 59155 29603 59155 29664 59155 29621 59156 29256 59156 29623 59156 29623 59157 29256 59157 29665 59157 29623 59158 29665 59158 29624 59158 29624 59159 29665 59159 29666 59159 29624 59160 29666 59160 29667 59160 29667 59161 29666 59161 29674 59161 29667 59162 29674 59162 29668 59162 29668 59163 29674 59163 29675 59163 29668 59164 29675 59164 29661 59164 29661 59165 29675 59165 29669 59165 29661 59166 29669 59166 29670 59166 29670 59167 29669 59167 29677 59167 29670 59168 29677 59168 29663 59168 29663 59169 29677 59169 29678 59169 29663 59170 29678 59170 29603 59170 29603 59171 29678 59171 29680 59171 29603 59172 29680 59172 29602 59172 29602 59173 29680 59173 29565 59173 29602 59174 29565 59174 27776 59174 27776 59175 29565 59175 29671 59175 29463 59176 28949 59176 29462 59176 29462 59177 28949 59177 29461 59177 29462 59178 29461 59178 29665 59178 29665 59179 29461 59179 29672 59179 29665 59180 29672 59180 29666 59180 29666 59181 29672 59181 29673 59181 29666 59182 29673 59182 29674 59182 29674 59183 29673 59183 29651 59183 29674 59184 29651 59184 29675 59184 29675 59185 29651 59185 29676 59185 29675 59186 29676 59186 29669 59186 29669 59187 29676 59187 29652 59187 29669 59188 29652 59188 29677 59188 29677 59189 29652 59189 29653 59189 29677 59190 29653 59190 29678 59190 29678 59191 29653 59191 29679 59191 29678 59192 29679 59192 29680 59192 29680 59193 29679 59193 29543 59193 29680 59194 29543 59194 29565 59194 29565 59195 29543 59195 29560 59195 29565 59196 29560 59196 29564 59196 29564 59197 29560 59197 27790 59197 29688 59198 30035 59198 29681 59198 29682 59199 29683 59199 29972 59199 29980 59200 29683 59200 29684 59200 29684 59201 29683 59201 29682 59201 29684 59202 29682 59202 29685 59202 29685 59203 29682 59203 29687 59203 30017 59204 29979 59204 29682 59204 29682 59205 29979 59205 29686 59205 29686 59206 29987 59206 29682 59206 29682 59207 29987 59207 29977 59207 29682 59208 29977 59208 29687 59208 30048 59209 30043 59209 29688 59209 29688 59210 30043 59210 30040 59210 30036 59211 30035 59211 30037 59211 30037 59212 30035 59212 29688 59212 30037 59213 29688 59213 30039 59213 30039 59214 29688 59214 30040 59214 29689 59215 29690 59215 29688 59215 29688 59216 29690 59216 30033 59216 29688 59217 30033 59217 30048 59217 29689 59218 29688 59218 29691 59218 29691 59219 29688 59219 29681 59219 29691 59220 29681 59220 29974 59220 29974 59221 29681 59221 29692 59221 29974 59222 29692 59222 29972 59222 29972 59223 29692 59223 29695 59223 29972 59224 29695 59224 29682 59224 29682 59225 29695 59225 29693 59225 29682 59226 29693 59226 30017 59226 30078 59227 30031 59227 29701 59227 30029 59228 29700 59228 29698 59228 30011 59229 30014 59229 29699 59229 30015 59230 30018 59230 29694 59230 30018 59231 29693 59231 29694 59231 29694 59232 29693 59232 29695 59232 29694 59233 29695 59233 29696 59233 29696 59234 29695 59234 29692 59234 29696 59235 29692 59235 29697 59235 29697 59236 29692 59236 29681 59236 29697 59237 29681 59237 30034 59237 30034 59238 29681 59238 30035 59238 30034 59239 30029 59239 29697 59239 29697 59240 30029 59240 29698 59240 29697 59241 29698 59241 29696 59241 29696 59242 29698 59242 29702 59242 29696 59243 29702 59243 29694 59243 29694 59244 29702 59244 29699 59244 29694 59245 29699 59245 30015 59245 30015 59246 29699 59246 30014 59246 29700 59247 30078 59247 29698 59247 29698 59248 30078 59248 29701 59248 29698 59249 29701 59249 29702 59249 29702 59250 29701 59250 29975 59250 29702 59251 29975 59251 29699 59251 29699 59252 29975 59252 29703 59252 29699 59253 29703 59253 30011 59253 30011 59254 29703 59254 29704 59254 29921 59255 29932 59255 29750 59255 29921 59256 29750 59256 29706 59256 29750 59257 29705 59257 29706 59257 29706 59258 29705 59258 29748 59258 29706 59259 29748 59259 29707 59259 29707 59260 29748 59260 29708 59260 29708 59261 29748 59261 29709 59261 29708 59262 29709 59262 29710 59262 29900 59263 29711 59263 29747 59263 29747 59264 29711 59264 29712 59264 29747 59265 29712 59265 29713 59265 29713 59266 29712 59266 29714 59266 29713 59267 29714 59267 29715 59267 29715 59268 29714 59268 29935 59268 29718 59269 29710 59269 29709 59269 29716 59270 29717 59270 29939 59270 29709 59271 29737 59271 29718 59271 29718 59272 29737 59272 29719 59272 29718 59273 29719 59273 29939 59273 29939 59274 29719 59274 29720 59274 29939 59275 29720 59275 29716 59275 29716 59276 29721 59276 29717 59276 29717 59277 29721 59277 29732 59277 29717 59278 29732 59278 29722 59278 29715 59279 29935 59279 29723 59279 29723 59280 29935 59280 29937 59280 29723 59281 29937 59281 29724 59281 29724 59282 29937 59282 29722 59282 29724 59283 29722 59283 29734 59283 29734 59284 29722 59284 29732 59284 29750 59285 29932 59285 29739 59285 29739 59286 29932 59286 29931 59286 29739 59287 29931 59287 29725 59287 29725 59288 29931 59288 29929 59288 29725 59289 29929 59289 29743 59289 29743 59290 29929 59290 29726 59290 29743 59291 29726 59291 29901 59291 29901 59292 29726 59292 29928 59292 29920 59293 29921 59293 29727 59293 29727 59294 29921 59294 29706 59294 29727 59295 29706 59295 29728 59295 29728 59296 29706 59296 29707 59296 29728 59297 29707 59297 29916 59297 29916 59298 29707 59298 29708 59298 29916 59299 29708 59299 29729 59299 29737 59300 29709 59300 29768 59300 29765 59301 29715 59301 29730 59301 29730 59302 29715 59302 29723 59302 29730 59303 29723 59303 29731 59303 29731 59304 29723 59304 29772 59304 29732 59305 29733 59305 29734 59305 29734 59306 29733 59306 29772 59306 29734 59307 29772 59307 29724 59307 29724 59308 29772 59308 29723 59308 29716 59309 29775 59309 29721 59309 29721 59310 29775 59310 29735 59310 29721 59311 29735 59311 29732 59311 29732 59312 29735 59312 29736 59312 29732 59313 29736 59313 29733 59313 29738 59314 29771 59314 29720 59314 29720 59315 29771 59315 29770 59315 29720 59316 29770 59316 29716 59316 29716 59317 29770 59317 29769 59317 29716 59318 29769 59318 29775 59318 29768 59319 29767 59319 29737 59319 29737 59320 29767 59320 29738 59320 29737 59321 29738 59321 29719 59321 29719 59322 29738 59322 29720 59322 29880 59323 29750 59323 29740 59323 29740 59324 29750 59324 29739 59324 29740 59325 29739 59325 29741 59325 29741 59326 29739 59326 29725 59326 29741 59327 29725 59327 29824 59327 29824 59328 29725 59328 29742 59328 29742 59329 29725 59329 29743 59329 29742 59330 29743 59330 29744 59330 29744 59331 29743 59331 29745 59331 29745 59332 29743 59332 29901 59332 29745 59333 29901 59333 29828 59333 29746 59334 29900 59334 29868 59334 29868 59335 29900 59335 29747 59335 29868 59336 29747 59336 29863 59336 29863 59337 29747 59337 29713 59337 29863 59338 29713 59338 29765 59338 29765 59339 29713 59339 29715 59339 29768 59340 29709 59340 29748 59340 29768 59341 29748 59341 29749 59341 29749 59342 29748 59342 29705 59342 29749 59343 29705 59343 29879 59343 29879 59344 29705 59344 29750 59344 29879 59345 29750 59345 29880 59345 29789 59346 29898 59346 29859 59346 29890 59347 29789 59347 29790 59347 29889 59348 29757 59348 29751 59348 29751 59349 29757 59349 29760 59349 29751 59350 29760 59350 29752 59350 29752 59351 29760 59351 29761 59351 29752 59352 29761 59352 29887 59352 29887 59353 29761 59353 29762 59353 29756 59354 29874 59354 29873 59354 29753 59355 29802 59355 29759 59355 29759 59356 29802 59356 29754 59356 29759 59357 29754 59357 29756 59357 29756 59358 29754 59358 29755 59358 29756 59359 29755 59359 29874 59359 29764 59360 29757 59360 29758 59360 29758 59361 29757 59361 29889 59361 29758 59362 29889 59362 29793 59362 29764 59363 29753 59363 29757 59363 29757 59364 29753 59364 29759 59364 29757 59365 29759 59365 29760 59365 29760 59366 29759 59366 29756 59366 29760 59367 29756 59367 29761 59367 29761 59368 29756 59368 29873 59368 29761 59369 29873 59369 29762 59369 29797 59370 29763 59370 29764 59370 29764 59371 29763 59371 29800 59371 29764 59372 29800 59372 29753 59372 29891 59373 29890 59373 29794 59373 29794 59374 29890 59374 29790 59374 29794 59375 29790 59375 29795 59375 29795 59376 29790 59376 29796 59376 29776 59377 29799 59377 29773 59377 29731 59378 29798 59378 29730 59378 29730 59379 29798 59379 29864 59379 29730 59380 29864 59380 29765 59380 29766 59381 29767 59381 29788 59381 29788 59382 29767 59382 29768 59382 29788 59383 29768 59383 29885 59383 29769 59384 29770 59384 29786 59384 29786 59385 29770 59385 29771 59385 29786 59386 29771 59386 29766 59386 29766 59387 29771 59387 29738 59387 29766 59388 29738 59388 29767 59388 29731 59389 29772 59389 29799 59389 29799 59390 29772 59390 29733 59390 29799 59391 29733 59391 29773 59391 29773 59392 29733 59392 29736 59392 29773 59393 29736 59393 29774 59393 29774 59394 29736 59394 29735 59394 29774 59395 29735 59395 29786 59395 29786 59396 29735 59396 29775 59396 29786 59397 29775 59397 29769 59397 29776 59398 29777 59398 29779 59398 29779 59399 29777 59399 29778 59399 29779 59400 29778 59400 29801 59400 29801 59401 29778 59401 29780 59401 29801 59402 29780 59402 29781 59402 29781 59403 29780 59403 29787 59403 29781 59404 29787 59404 29782 59404 29782 59405 29787 59405 29783 59405 29782 59406 29783 59406 29784 59406 29784 59407 29783 59407 29785 59407 29784 59408 29785 59408 29882 59408 29776 59409 29773 59409 29777 59409 29777 59410 29773 59410 29774 59410 29777 59411 29774 59411 29778 59411 29778 59412 29774 59412 29786 59412 29778 59413 29786 59413 29780 59413 29780 59414 29786 59414 29766 59414 29780 59415 29766 59415 29787 59415 29787 59416 29766 59416 29788 59416 29787 59417 29788 59417 29783 59417 29783 59418 29788 59418 29885 59418 29783 59419 29885 59419 29785 59419 29789 59420 29859 59420 29790 59420 29790 59421 29859 59421 29791 59421 29790 59422 29791 59422 29796 59422 29796 59423 29791 59423 29858 59423 29796 59424 29858 59424 29792 59424 29793 59425 29891 59425 29758 59425 29758 59426 29891 59426 29794 59426 29758 59427 29794 59427 29764 59427 29764 59428 29794 59428 29795 59428 29764 59429 29795 59429 29797 59429 29797 59430 29795 59430 29796 59430 29797 59431 29796 59431 29798 59431 29798 59432 29796 59432 29792 59432 29798 59433 29792 59433 29864 59433 29731 59434 29799 59434 29798 59434 29798 59435 29799 59435 29776 59435 29798 59436 29776 59436 29797 59436 29797 59437 29776 59437 29779 59437 29797 59438 29779 59438 29763 59438 29763 59439 29779 59439 29801 59439 29763 59440 29801 59440 29800 59440 29800 59441 29801 59441 29781 59441 29800 59442 29781 59442 29753 59442 29753 59443 29781 59443 29782 59443 29753 59444 29782 59444 29802 59444 29802 59445 29782 59445 29784 59445 29802 59446 29784 59446 29754 59446 29754 59447 29784 59447 29882 59447 29754 59448 29882 59448 29755 59448 29834 59449 29746 59449 29836 59449 29814 59450 29811 59450 29813 59450 29838 59451 29803 59451 29866 59451 29871 59452 29822 59452 29804 59452 29804 59453 29822 59453 29821 59453 29804 59454 29821 59454 29805 59454 29805 59455 29821 59455 29819 59455 29805 59456 29819 59456 29817 59456 29806 59457 29866 59457 29892 59457 29849 59458 29808 59458 29807 59458 29807 59459 29808 59459 29809 59459 29809 59460 29808 59460 29810 59460 29809 59461 29810 59461 29813 59461 29813 59462 29811 59462 29809 59462 29809 59463 29811 59463 29851 59463 29809 59464 29851 59464 29807 59464 29810 59465 29812 59465 29813 59465 29813 59466 29812 59466 29816 59466 29813 59467 29816 59467 29814 59467 29814 59468 29816 59468 29818 59468 29814 59469 29818 59469 29853 59469 29853 59470 29818 59470 29820 59470 29853 59471 29820 59471 29815 59471 29815 59472 29820 59472 29878 59472 29815 59473 29878 59473 29876 59473 29812 59474 29817 59474 29816 59474 29816 59475 29817 59475 29819 59475 29816 59476 29819 59476 29818 59476 29818 59477 29819 59477 29821 59477 29818 59478 29821 59478 29820 59478 29820 59479 29821 59479 29822 59479 29820 59480 29822 59480 29878 59480 29823 59481 29742 59481 29744 59481 29823 59482 29744 59482 29826 59482 29742 59483 29823 59483 29824 59483 29824 59484 29823 59484 29845 59484 29824 59485 29845 59485 29741 59485 29741 59486 29845 59486 29844 59486 29741 59487 29844 59487 29740 59487 29880 59488 29740 59488 29825 59488 29825 59489 29740 59489 29844 59489 29825 59490 29844 59490 29875 59490 29744 59491 29745 59491 29826 59491 29826 59492 29745 59492 29828 59492 29826 59493 29828 59493 29827 59493 29827 59494 29828 59494 29829 59494 29827 59495 29829 59495 29832 59495 29832 59496 29829 59496 29830 59496 29832 59497 29830 59497 29831 59497 29831 59498 29833 59498 29832 59498 29832 59499 29833 59499 29834 59499 29832 59500 29834 59500 29835 59500 29835 59501 29834 59501 29836 59501 29835 59502 29836 59502 29837 59502 29866 59503 29806 59503 29838 59503 29838 59504 29806 59504 29850 59504 29838 59505 29850 59505 29848 59505 29848 59506 29850 59506 29839 59506 29848 59507 29839 59507 29847 59507 29847 59508 29839 59508 29852 59508 29847 59509 29852 59509 29840 59509 29840 59510 29852 59510 29841 59510 29840 59511 29841 59511 29846 59511 29846 59512 29841 59512 29854 59512 29846 59513 29854 59513 29842 59513 29842 59514 29854 59514 29855 59514 29842 59515 29855 59515 29843 59515 29843 59516 29855 59516 29856 59516 29843 59517 29856 59517 29875 59517 29875 59518 29844 59518 29843 59518 29843 59519 29844 59519 29845 59519 29843 59520 29845 59520 29842 59520 29842 59521 29845 59521 29823 59521 29842 59522 29823 59522 29846 59522 29846 59523 29823 59523 29826 59523 29846 59524 29826 59524 29840 59524 29840 59525 29826 59525 29827 59525 29840 59526 29827 59526 29847 59526 29847 59527 29827 59527 29832 59527 29847 59528 29832 59528 29848 59528 29848 59529 29832 59529 29835 59529 29848 59530 29835 59530 29838 59530 29838 59531 29835 59531 29837 59531 29838 59532 29837 59532 29803 59532 29892 59533 29849 59533 29806 59533 29806 59534 29849 59534 29807 59534 29806 59535 29807 59535 29850 59535 29850 59536 29807 59536 29851 59536 29850 59537 29851 59537 29839 59537 29839 59538 29851 59538 29811 59538 29839 59539 29811 59539 29852 59539 29852 59540 29811 59540 29814 59540 29852 59541 29814 59541 29841 59541 29841 59542 29814 59542 29853 59542 29841 59543 29853 59543 29854 59543 29854 59544 29853 59544 29815 59544 29854 59545 29815 59545 29855 59545 29855 59546 29815 59546 29876 59546 29855 59547 29876 59547 29856 59547 29860 59548 29857 59548 29867 59548 29862 59549 29892 59549 29866 59549 29859 59550 29898 59550 29897 59550 29858 59551 29791 59551 29860 59551 29860 59552 29791 59552 29859 59552 29859 59553 29897 59553 29860 59553 29860 59554 29897 59554 29896 59554 29860 59555 29896 59555 29857 59555 29857 59556 29896 59556 29861 59556 29857 59557 29861 59557 29862 59557 29864 59558 29792 59558 29865 59558 29865 59559 29792 59559 29858 59559 29765 59560 29864 59560 29863 59560 29863 59561 29864 59561 29865 59561 29863 59562 29865 59562 29868 59562 29862 59563 29866 59563 29857 59563 29857 59564 29866 59564 29803 59564 29857 59565 29803 59565 29867 59565 29867 59566 29803 59566 29837 59566 29867 59567 29837 59567 29836 59567 29858 59568 29860 59568 29865 59568 29865 59569 29860 59569 29867 59569 29865 59570 29867 59570 29868 59570 29868 59571 29867 59571 29836 59571 29868 59572 29836 59572 29746 59572 29825 59573 29875 59573 29884 59573 29895 59574 29869 59574 29870 59574 29871 59575 29894 59575 29822 59575 29822 59576 29894 59576 29872 59576 29887 59577 29762 59577 29888 59577 29888 59578 29762 59578 29869 59578 29883 59579 29877 59579 29881 59579 29881 59580 29877 59580 29872 59580 29869 59581 29762 59581 29870 59581 29870 59582 29762 59582 29873 59582 29870 59583 29873 59583 29874 59583 29894 59584 29895 59584 29872 59584 29872 59585 29895 59585 29870 59585 29872 59586 29870 59586 29881 59586 29881 59587 29870 59587 29874 59587 29875 59588 29856 59588 29877 59588 29877 59589 29856 59589 29876 59589 29877 59590 29876 59590 29872 59590 29872 59591 29876 59591 29878 59591 29872 59592 29878 59592 29822 59592 29749 59593 29879 59593 29884 59593 29884 59594 29879 59594 29880 59594 29884 59595 29880 59595 29825 59595 29874 59596 29755 59596 29881 59596 29881 59597 29755 59597 29882 59597 29881 59598 29882 59598 29883 59598 29883 59599 29882 59599 29785 59599 29883 59600 29785 59600 29885 59600 29875 59601 29877 59601 29884 59601 29884 59602 29877 59602 29883 59602 29884 59603 29883 59603 29749 59603 29749 59604 29883 59604 29885 59604 29749 59605 29885 59605 29768 59605 29886 59606 29887 59606 29888 59606 29886 59607 29793 59607 29889 59607 29889 59608 29751 59608 29886 59608 29886 59609 29751 59609 29752 59609 29886 59610 29752 59610 29887 59610 29789 59611 29890 59611 29886 59611 29886 59612 29890 59612 29891 59612 29886 59613 29891 59613 29793 59613 29893 59614 29892 59614 29862 59614 29849 59615 29892 59615 29808 59615 29808 59616 29892 59616 29893 59616 29808 59617 29893 59617 29810 59617 29871 59618 29804 59618 29893 59618 29893 59619 29804 59619 29805 59619 29805 59620 29817 59620 29893 59620 29893 59621 29817 59621 29812 59621 29893 59622 29812 59622 29810 59622 29871 59623 29893 59623 29894 59623 29894 59624 29893 59624 29862 59624 29894 59625 29862 59625 29895 59625 29895 59626 29862 59626 29861 59626 29895 59627 29861 59627 29869 59627 29869 59628 29861 59628 29896 59628 29869 59629 29896 59629 29888 59629 29888 59630 29896 59630 29897 59630 29888 59631 29897 59631 29886 59631 29886 59632 29897 59632 29898 59632 29886 59633 29898 59633 29789 59633 29834 59634 29833 59634 29899 59634 29833 59635 29831 59635 29899 59635 29899 59636 29831 59636 29830 59636 29899 59637 29830 59637 29901 59637 29901 59638 29830 59638 29829 59638 29901 59639 29829 59639 29828 59639 29899 59640 29902 59640 29834 59640 29834 59641 29902 59641 29900 59641 29834 59642 29900 59642 29746 59642 29901 59643 29928 59643 29899 59643 29899 59644 29928 59644 29927 59644 29899 59645 29927 59645 29902 59645 29902 59646 29927 59646 29903 59646 29902 59647 29903 59647 29900 59647 29900 59648 29903 59648 29711 59648 29907 59649 30060 59649 29909 59649 30064 59650 29904 59650 29905 59650 29909 59651 30060 59651 29905 59651 29905 59652 30060 59652 30065 59652 29905 59653 30065 59653 30064 59653 29910 59654 29911 59654 30031 59654 30031 59655 30030 59655 29910 59655 29910 59656 30030 59656 29906 59656 29910 59657 29906 59657 29909 59657 29909 59658 29906 59658 30066 59658 29909 59659 30066 59659 29907 59659 29905 59660 29908 59660 29909 59660 29909 59661 29908 59661 29938 59661 29909 59662 29938 59662 29910 59662 29910 59663 29938 59663 29936 59663 29910 59664 29936 59664 29911 59664 29911 59665 29936 59665 29912 59665 29917 59666 29913 59666 29915 59666 29915 59667 29913 59667 29914 59667 29915 59668 29914 59668 29905 59668 29905 59669 29914 59669 29908 59669 29942 59670 29916 59670 29957 59670 29957 59671 29916 59671 29729 59671 29957 59672 29729 59672 29917 59672 29917 59673 29729 59673 29708 59673 29917 59674 29708 59674 29913 59674 29918 59675 29930 59675 29922 59675 29727 59676 29919 59676 29920 59676 29920 59677 29919 59677 29954 59677 29920 59678 29954 59678 29921 59678 29921 59679 29954 59679 29951 59679 29921 59680 29951 59680 29922 59680 29922 59681 29951 59681 29952 59681 29922 59682 29952 59682 29918 59682 29918 59683 29923 59683 29930 59683 29930 59684 29923 59684 29950 59684 29930 59685 29950 59685 29924 59685 29944 59686 29933 59686 29946 59686 29946 59687 29933 59687 29925 59687 29946 59688 29925 59688 29926 59688 29926 59689 29925 59689 29924 59689 29926 59690 29924 59690 29948 59690 29948 59691 29924 59691 29950 59691 29932 59692 29921 59692 29922 59692 29928 59693 29930 59693 29924 59693 29711 59694 29903 59694 29924 59694 29924 59695 29903 59695 29927 59695 29924 59696 29927 59696 29928 59696 29928 59697 29726 59697 29930 59697 29930 59698 29726 59698 29929 59698 29930 59699 29929 59699 29922 59699 29922 59700 29929 59700 29931 59700 29922 59701 29931 59701 29932 59701 29924 59702 29925 59702 29711 59702 29711 59703 29925 59703 29933 59703 29711 59704 29933 59704 29712 59704 29712 59705 29933 59705 29934 59705 29712 59706 29934 59706 29714 59706 29714 59707 29934 59707 29912 59707 29714 59708 29912 59708 29935 59708 29935 59709 29912 59709 29936 59709 29935 59710 29936 59710 29937 59710 29937 59711 29936 59711 29938 59711 29937 59712 29938 59712 29722 59712 29722 59713 29938 59713 29908 59713 29708 59714 29710 59714 29913 59714 29913 59715 29710 59715 29718 59715 29913 59716 29718 59716 29914 59716 29914 59717 29718 59717 29939 59717 29914 59718 29939 59718 29908 59718 29908 59719 29939 59719 29717 59719 29908 59720 29717 59720 29722 59720 29916 59721 29942 59721 29940 59721 29916 59722 29940 59722 29728 59722 29728 59723 29940 59723 29919 59723 29728 59724 29919 59724 29727 59724 29959 59725 29919 59725 29941 59725 29941 59726 29919 59726 29940 59726 29941 59727 29940 59727 29960 59727 29942 59728 29962 59728 29940 59728 29940 59729 29962 59729 29961 59729 29940 59730 29961 59730 29960 59730 29911 59731 29912 59731 29943 59731 29943 59732 29912 59732 29934 59732 29943 59733 29934 59733 29944 59733 29944 59734 29934 59734 29933 59734 29954 59735 29919 59735 29959 59735 29704 59736 29944 59736 29945 59736 29945 59737 29944 59737 29946 59737 29945 59738 29946 59738 30019 59738 30019 59739 29946 59739 29947 59739 29946 59740 29926 59740 29947 59740 29947 59741 29926 59741 29948 59741 29947 59742 29948 59742 30020 59742 29918 59743 29949 59743 29923 59743 29923 59744 29949 59744 30020 59744 29923 59745 30020 59745 29950 59745 29950 59746 30020 59746 29948 59746 29951 59747 29992 59747 29952 59747 29952 59748 29992 59748 29991 59748 29952 59749 29991 59749 29918 59749 29918 59750 29991 59750 30001 59750 29918 59751 30001 59751 29949 59751 29959 59752 29953 59752 29954 59752 29954 59753 29953 59753 30010 59753 29954 59754 30010 59754 29951 59754 29951 59755 30010 59755 29955 59755 29951 59756 29955 59756 29992 59756 29962 59757 29942 59757 30055 59757 30055 59758 29942 59758 29957 59758 30055 59759 29957 59759 29956 59759 29956 59760 29957 59760 29917 59760 29956 59761 29917 59761 30054 59761 30054 59762 29917 59762 29958 59762 29958 59763 29917 59763 29915 59763 29958 59764 29915 59764 30053 59764 30053 59765 29915 59765 30062 59765 30062 59766 29915 59766 29905 59766 30062 59767 29905 59767 29904 59767 29971 59768 30052 59768 29689 59768 30052 59769 29971 59769 30047 59769 29968 59770 29963 59770 29969 59770 30000 59771 29959 59771 29941 59771 29996 59772 29997 59772 29968 59772 29968 59773 29997 59773 30000 59773 30000 59774 29941 59774 29968 59774 29968 59775 29941 59775 29960 59775 29968 59776 29960 59776 29963 59776 29963 59777 29960 59777 29961 59777 29963 59778 29961 59778 29962 59778 29965 59779 29995 59779 29967 59779 29967 59780 29995 59780 29996 59780 29962 59781 30057 59781 29963 59781 29963 59782 30057 59782 30058 59782 29963 59783 30058 59783 29969 59783 29969 59784 30058 59784 29964 59784 29969 59785 29964 59785 29970 59785 29973 59786 29965 59786 29966 59786 29966 59787 29965 59787 29967 59787 29966 59788 29967 59788 29971 59788 29996 59789 29968 59789 29967 59789 29967 59790 29968 59790 29969 59790 29967 59791 29969 59791 29971 59791 29971 59792 29969 59792 29970 59792 29971 59793 29970 59793 30047 59793 29683 59794 29973 59794 29972 59794 29972 59795 29973 59795 29966 59795 29972 59796 29966 59796 29974 59796 29974 59797 29966 59797 29971 59797 29974 59798 29971 59798 29691 59798 29691 59799 29971 59799 29689 59799 30031 59800 29911 59800 29701 59800 29701 59801 29911 59801 29943 59801 29701 59802 29943 59802 29975 59802 29975 59803 29943 59803 29703 59803 29703 59804 29943 59804 29944 59804 29703 59805 29944 59805 29704 59805 29989 59806 29976 59806 29984 59806 29687 59807 29977 59807 29978 59807 29979 59808 30017 59808 30016 59808 29989 59809 29987 59809 29976 59809 29976 59810 29987 59810 29686 59810 29976 59811 29686 59811 29979 59811 29980 59812 29684 59812 30027 59812 30027 59813 29684 59813 29685 59813 30027 59814 29685 59814 30026 59814 30027 59815 30028 59815 29980 59815 29980 59816 30028 59816 29973 59816 29980 59817 29973 59817 29683 59817 29685 59818 29687 59818 30026 59818 30026 59819 29687 59819 29978 59819 30026 59820 29978 59820 29981 59820 29981 59821 29978 59821 29988 59821 29981 59822 29988 59822 29982 59822 29982 59823 29988 59823 29983 59823 29982 59824 29983 59824 30023 59824 30023 59825 29983 59825 29990 59825 30023 59826 29990 59826 30022 59826 29945 59827 30019 59827 30012 59827 30012 59828 30019 59828 29986 59828 29979 59829 30016 59829 29976 59829 29976 59830 30016 59830 30013 59830 29976 59831 30013 59831 29984 59831 29984 59832 30013 59832 30012 59832 29984 59833 30012 59833 29985 59833 29985 59834 30012 59834 29986 59834 29985 59835 29986 59835 30021 59835 29977 59836 29987 59836 29978 59836 29978 59837 29987 59837 29989 59837 29978 59838 29989 59838 29988 59838 29988 59839 29989 59839 29984 59839 29988 59840 29984 59840 29983 59840 29983 59841 29984 59841 29985 59841 29983 59842 29985 59842 29990 59842 29990 59843 29985 59843 30021 59843 29990 59844 30021 59844 30022 59844 29991 59845 29992 59845 30002 59845 30002 59846 29992 59846 29955 59846 30002 59847 29955 59847 30010 59847 29949 59848 30001 59848 29993 59848 29965 59849 29994 59849 29995 59849 29995 59850 29994 59850 30006 59850 29995 59851 30006 59851 29996 59851 29996 59852 30006 59852 29998 59852 29996 59853 29998 59853 29997 59853 29997 59854 29998 59854 29999 59854 29997 59855 29999 59855 30000 59855 30000 59856 29999 59856 30009 59856 30000 59857 30009 59857 29959 59857 29959 59858 30009 59858 29953 59858 30001 59859 29991 59859 29993 59859 29993 59860 29991 59860 30002 59860 29993 59861 30002 59861 30024 59861 30024 59862 30002 59862 30008 59862 30024 59863 30008 59863 30025 59863 30025 59864 30008 59864 30007 59864 30025 59865 30007 59865 30003 59865 30003 59866 30007 59866 30005 59866 30003 59867 30005 59867 30004 59867 29994 59868 30004 59868 30006 59868 30006 59869 30004 59869 30005 59869 30006 59870 30005 59870 29998 59870 29998 59871 30005 59871 30007 59871 29998 59872 30007 59872 29999 59872 29999 59873 30007 59873 30008 59873 29999 59874 30008 59874 30009 59874 30009 59875 30008 59875 30002 59875 30009 59876 30002 59876 29953 59876 29953 59877 30002 59877 30010 59877 29704 59878 29945 59878 30011 59878 30011 59879 29945 59879 30012 59879 30011 59880 30012 59880 30014 59880 30014 59881 30012 59881 30013 59881 30014 59882 30013 59882 30015 59882 30015 59883 30013 59883 30016 59883 30015 59884 30016 59884 30018 59884 30018 59885 30016 59885 30017 59885 30018 59886 30017 59886 29693 59886 30019 59887 29947 59887 29986 59887 29986 59888 29947 59888 30020 59888 29986 59889 30020 59889 30021 59889 30021 59890 30020 59890 29949 59890 30021 59891 29949 59891 30022 59891 30022 59892 29949 59892 29993 59892 30022 59893 29993 59893 30023 59893 30023 59894 29993 59894 30024 59894 30023 59895 30024 59895 29982 59895 29982 59896 30024 59896 30025 59896 29982 59897 30025 59897 29981 59897 29981 59898 30025 59898 30003 59898 29981 59899 30003 59899 30026 59899 30026 59900 30003 59900 30004 59900 30026 59901 30004 59901 30027 59901 30027 59902 30004 59902 29994 59902 30027 59903 29994 59903 30028 59903 30028 59904 29994 59904 29965 59904 30028 59905 29965 59905 29973 59905 29700 59906 30029 59906 30070 59906 30030 59907 30031 59907 30078 59907 29964 59908 30058 59908 30032 59908 30045 59909 30083 59909 30041 59909 30048 59910 30033 59910 30049 59910 30049 59911 30033 59911 29690 59911 30049 59912 29690 59912 30051 59912 30051 59913 29690 59913 29689 59913 30051 59914 29689 59914 30052 59914 30079 59915 30034 59915 30035 59915 30036 59916 30037 59916 30038 59916 30038 59917 30037 59917 30039 59917 30038 59918 30039 59918 30042 59918 30042 59919 30039 59919 30040 59919 30042 59920 30040 59920 30041 59920 30029 59921 30034 59921 30070 59921 30070 59922 30034 59922 30079 59922 30070 59923 30079 59923 30080 59923 30041 59924 30083 59924 30042 59924 30042 59925 30083 59925 30081 59925 30042 59926 30081 59926 30038 59926 30040 59927 30043 59927 30041 59927 30041 59928 30043 59928 30044 59928 30041 59929 30044 59929 30045 59929 30045 59930 30044 59930 30046 59930 30045 59931 30046 59931 30085 59931 30085 59932 30046 59932 30050 59932 30085 59933 30050 59933 30086 59933 30086 59934 30050 59934 30047 59934 30086 59935 30047 59935 29970 59935 30043 59936 30048 59936 30044 59936 30044 59937 30048 59937 30049 59937 30044 59938 30049 59938 30046 59938 30046 59939 30049 59939 30051 59939 30046 59940 30051 59940 30050 59940 30050 59941 30051 59941 30052 59941 30050 59942 30052 59942 30047 59942 30062 59943 30063 59943 30053 59943 30053 59944 30063 59944 30073 59944 30053 59945 30073 59945 29958 59945 29958 59946 30073 59946 30054 59946 30054 59947 30073 59947 30071 59947 30054 59948 30071 59948 29956 59948 29956 59949 30071 59949 30056 59949 29956 59950 30056 59950 30055 59950 29962 59951 30055 59951 30057 59951 30057 59952 30055 59952 30056 59952 30057 59953 30056 59953 30058 59953 29907 59954 30059 59954 30060 59954 30060 59955 30059 59955 30061 59955 30062 59956 29904 59956 30063 59956 30063 59957 29904 59957 30064 59957 30063 59958 30064 59958 30061 59958 30061 59959 30064 59959 30065 59959 30061 59960 30065 59960 30060 59960 29907 59961 30066 59961 30059 59961 30059 59962 30066 59962 29906 59962 30059 59963 29906 59963 30030 59963 29964 59964 30032 59964 30087 59964 30087 59965 30032 59965 30072 59965 30087 59966 30072 59966 30067 59966 30067 59967 30072 59967 30074 59967 30067 59968 30074 59968 30068 59968 30068 59969 30074 59969 30075 59969 30068 59970 30075 59970 30084 59970 30084 59971 30075 59971 30076 59971 30084 59972 30076 59972 30082 59972 30082 59973 30076 59973 30069 59973 30082 59974 30069 59974 30080 59974 30080 59975 30069 59975 30070 59975 30070 59976 30069 59976 30077 59976 30070 59977 30077 59977 29700 59977 30058 59978 30056 59978 30032 59978 30032 59979 30056 59979 30071 59979 30032 59980 30071 59980 30072 59980 30072 59981 30071 59981 30073 59981 30072 59982 30073 59982 30074 59982 30074 59983 30073 59983 30063 59983 30074 59984 30063 59984 30075 59984 30075 59985 30063 59985 30061 59985 30075 59986 30061 59986 30076 59986 30076 59987 30061 59987 30059 59987 30076 59988 30059 59988 30069 59988 30069 59989 30059 59989 30030 59989 30069 59990 30030 59990 30077 59990 30077 59991 30030 59991 30078 59991 30077 59992 30078 59992 29700 59992 30035 59993 30036 59993 30079 59993 30079 59994 30036 59994 30038 59994 30079 59995 30038 59995 30080 59995 30080 59996 30038 59996 30081 59996 30080 59997 30081 59997 30082 59997 30082 59998 30081 59998 30083 59998 30082 59999 30083 59999 30084 59999 30084 60000 30083 60000 30045 60000 30084 60001 30045 60001 30068 60001 30068 60002 30045 60002 30085 60002 30068 60003 30085 60003 30067 60003 30067 60004 30085 60004 30086 60004 30067 60005 30086 60005 30087 60005 30087 60006 30086 60006 29970 60006 30087 60007 29970 60007 29964 60007 30089 60008 30292 60008 30088 60008 30089 60009 30088 60009 30376 60009 30376 60010 30088 60010 30291 60010 30376 60011 30291 60011 30373 60011 30373 60012 30291 60012 30289 60012 30373 60013 30289 60013 30374 60013 30295 60014 30292 60014 30089 60014 30098 60015 30090 60015 30326 60015 30326 60016 30090 60016 30091 60016 30326 60017 30091 60017 30331 60017 30331 60018 30091 60018 30332 60018 30091 60019 30301 60019 30332 60019 30332 60020 30301 60020 30302 60020 30332 60021 30302 60021 30092 60021 30092 60022 30302 60022 30298 60022 30092 60023 30298 60023 30333 60023 30333 60024 30298 60024 30093 60024 30093 60025 30298 60025 30297 60025 30093 60026 30297 60026 30097 60026 30094 60027 30329 60027 30095 60027 30095 60028 30329 60028 30328 60028 30095 60029 30328 60029 30297 60029 30297 60030 30328 60030 30096 60030 30297 60031 30096 60031 30097 60031 30089 60032 30330 60032 30295 60032 30295 60033 30330 60033 30094 60033 30295 60034 30094 60034 30296 60034 30296 60035 30094 60035 30095 60035 30103 60036 30102 60036 30390 60036 30390 60037 30102 60037 30305 60037 30390 60038 30305 60038 30384 60038 30384 60039 30305 60039 30099 60039 30384 60040 30099 60040 30098 60040 30098 60041 30099 60041 30090 60041 30468 60042 30100 60042 30465 60042 30465 60043 30100 60043 30290 60043 30465 60044 30290 60044 30491 60044 30491 60045 30290 60045 30101 60045 30491 60046 30101 60046 30490 60046 30490 60047 30101 60047 30488 60047 30490 60048 30488 60048 30464 60048 30419 60049 30459 60049 30104 60049 30419 60050 30104 60050 30391 60050 30104 60051 30105 60051 30391 60051 30391 60052 30105 60052 30102 60052 30391 60053 30102 60053 30103 60053 30104 60054 30106 60054 30105 60054 30105 60055 30106 60055 30480 60055 30105 60056 30480 60056 30102 60056 30102 60057 30480 60057 30487 60057 30231 60058 30141 60058 30234 60058 30234 60059 30141 60059 30116 60059 30234 60060 30116 60060 30108 60060 30108 60061 30116 60061 30107 60061 30108 60062 30107 60062 30109 60062 30235 60063 30110 60063 30118 60063 30118 60064 30110 60064 30107 60064 30107 60065 30110 60065 30111 60065 30107 60066 30111 60066 30109 60066 30118 60067 30114 60067 30235 60067 30235 60068 30114 60068 30113 60068 30235 60069 30113 60069 30237 60069 30237 60070 30113 60070 30123 60070 30237 60071 30123 60071 30271 60071 30112 60072 30124 60072 30123 60072 30123 60073 30113 60073 30112 60073 30112 60074 30113 60074 30114 60074 30112 60075 30114 60075 30115 60075 30141 60076 30117 60076 30116 60076 30116 60077 30117 60077 30482 60077 30116 60078 30482 60078 30107 60078 30107 60079 30482 60079 30115 60079 30107 60080 30115 60080 30118 60080 30118 60081 30115 60081 30114 60081 30132 60082 30466 60082 30144 60082 30144 60083 30466 60083 30121 60083 30144 60084 30121 60084 30122 60084 30135 60085 30119 60085 30121 60085 30121 60086 30119 60086 30120 60086 30121 60087 30120 60087 30122 60087 30123 60088 30124 60088 30156 60088 30156 60089 30124 60089 30125 60089 30156 60090 30125 60090 30126 60090 30126 60091 30125 60091 30486 60091 30467 60092 30466 60092 30132 60092 30288 60093 30126 60093 30127 60093 30127 60094 30126 60094 30128 60094 30127 60095 30128 60095 30170 60095 30170 60096 30128 60096 30198 60096 30128 60097 30129 60097 30198 60097 30198 60098 30129 60098 30475 60098 30198 60099 30475 60099 30131 60099 30130 60100 30201 60100 30472 60100 30472 60101 30201 60101 30131 60101 30472 60102 30131 60102 30473 60102 30473 60103 30131 60103 30475 60103 30132 60104 30194 60104 30467 60104 30467 60105 30194 60105 30195 60105 30467 60106 30195 60106 30469 60106 30469 60107 30195 60107 30186 60107 30469 60108 30186 60108 30133 60108 30133 60109 30186 60109 30157 60109 30133 60110 30157 60110 30130 60110 30130 60111 30157 60111 30134 60111 30130 60112 30134 60112 30201 60112 30119 60113 30135 60113 30136 60113 30136 60114 30135 60114 30137 60114 30136 60115 30137 60115 30138 60115 30138 60116 30137 60116 30140 60116 30138 60117 30140 60117 30139 60117 30139 60118 30140 60118 30141 60118 30139 60119 30141 60119 30231 60119 30151 60120 30142 60120 30143 60120 30142 60121 30151 60121 30228 60121 30150 60122 30145 60122 30148 60122 30183 60123 30132 60123 30144 60123 30180 60124 30182 60124 30150 60124 30150 60125 30182 60125 30183 60125 30183 60126 30144 60126 30150 60126 30150 60127 30144 60127 30122 60127 30150 60128 30122 60128 30145 60128 30145 60129 30122 60129 30120 60129 30145 60130 30120 60130 30119 60130 30149 60131 30179 60131 30146 60131 30146 60132 30179 60132 30180 60132 30119 60133 30147 60133 30145 60133 30145 60134 30147 60134 30229 60134 30145 60135 30229 60135 30148 60135 30148 60136 30229 60136 30244 60136 30148 60137 30244 60137 30152 60137 30165 60138 30149 60138 30155 60138 30155 60139 30149 60139 30146 60139 30155 60140 30146 60140 30151 60140 30180 60141 30150 60141 30146 60141 30146 60142 30150 60142 30148 60142 30146 60143 30148 60143 30151 60143 30151 60144 30148 60144 30152 60144 30151 60145 30152 60145 30228 60145 30153 60146 30165 60146 30154 60146 30154 60147 30165 60147 30155 60147 30154 60148 30155 60148 30268 60148 30268 60149 30155 60149 30151 60149 30268 60150 30151 60150 30267 60150 30267 60151 30151 60151 30143 60151 30156 60152 30126 60152 30288 60152 30288 60153 30287 60153 30156 60153 30156 60154 30287 60154 30285 60154 30156 60155 30285 60155 30123 60155 30123 60156 30285 60156 30284 60156 30123 60157 30284 60157 30271 60157 30134 60158 30157 60158 30187 60158 30186 60159 30195 60159 30158 60159 30175 60160 30160 60160 30177 60160 30159 60161 30174 60161 30176 60161 30171 60162 30262 60162 30172 60162 30175 60163 30264 60163 30160 60163 30160 60164 30264 60164 30161 60164 30160 60165 30161 60165 30171 60165 30164 60166 30261 60166 30162 60166 30162 60167 30261 60167 30163 60167 30162 60168 30163 60168 30206 60168 30162 60169 30209 60169 30164 60169 30164 60170 30209 60170 30165 60170 30164 60171 30165 60171 30153 60171 30163 60172 30159 60172 30206 60172 30206 60173 30159 60173 30176 60173 30206 60174 30176 60174 30205 60174 30205 60175 30176 60175 30166 60175 30205 60176 30166 60176 30204 60176 30204 60177 30166 60177 30167 60177 30204 60178 30167 60178 30168 60178 30168 60179 30167 60179 30169 60179 30168 60180 30169 60180 30202 60180 30127 60181 30170 60181 30196 60181 30196 60182 30170 60182 30199 60182 30171 60183 30172 60183 30160 60183 30160 60184 30172 60184 30173 60184 30160 60185 30173 60185 30177 60185 30177 60186 30173 60186 30196 60186 30177 60187 30196 60187 30178 60187 30178 60188 30196 60188 30199 60188 30178 60189 30199 60189 30200 60189 30174 60190 30264 60190 30176 60190 30176 60191 30264 60191 30175 60191 30176 60192 30175 60192 30166 60192 30166 60193 30175 60193 30177 60193 30166 60194 30177 60194 30167 60194 30167 60195 30177 60195 30178 60195 30167 60196 30178 60196 30169 60196 30169 60197 30178 60197 30200 60197 30169 60198 30200 60198 30202 60198 30134 60199 30187 60199 30201 60199 30149 60200 30208 60200 30179 60200 30179 60201 30208 60201 30193 60201 30179 60202 30193 60202 30180 60202 30180 60203 30193 60203 30181 60203 30180 60204 30181 60204 30182 60204 30182 60205 30181 60205 30184 60205 30182 60206 30184 60206 30183 60206 30183 60207 30184 60207 30185 60207 30183 60208 30185 60208 30132 60208 30132 60209 30185 60209 30194 60209 30157 60210 30186 60210 30187 60210 30187 60211 30186 60211 30158 60211 30187 60212 30158 60212 30203 60212 30203 60213 30158 60213 30188 60213 30203 60214 30188 60214 30190 60214 30190 60215 30188 60215 30189 60215 30190 60216 30189 60216 30191 60216 30191 60217 30189 60217 30192 60217 30191 60218 30192 60218 30207 60218 30208 60219 30207 60219 30193 60219 30193 60220 30207 60220 30192 60220 30193 60221 30192 60221 30181 60221 30181 60222 30192 60222 30189 60222 30181 60223 30189 60223 30184 60223 30184 60224 30189 60224 30188 60224 30184 60225 30188 60225 30185 60225 30185 60226 30188 60226 30158 60226 30185 60227 30158 60227 30194 60227 30194 60228 30158 60228 30195 60228 30288 60229 30127 60229 30272 60229 30272 60230 30127 60230 30196 60230 30272 60231 30196 60231 30273 60231 30273 60232 30196 60232 30173 60232 30273 60233 30173 60233 30282 60233 30282 60234 30173 60234 30172 60234 30282 60235 30172 60235 30197 60235 30197 60236 30172 60236 30262 60236 30197 60237 30262 60237 30275 60237 30170 60238 30198 60238 30199 60238 30199 60239 30198 60239 30131 60239 30199 60240 30131 60240 30200 60240 30200 60241 30131 60241 30201 60241 30200 60242 30201 60242 30202 60242 30202 60243 30201 60243 30187 60243 30202 60244 30187 60244 30168 60244 30168 60245 30187 60245 30203 60245 30168 60246 30203 60246 30204 60246 30204 60247 30203 60247 30190 60247 30204 60248 30190 60248 30205 60248 30205 60249 30190 60249 30191 60249 30205 60250 30191 60250 30206 60250 30206 60251 30191 60251 30207 60251 30206 60252 30207 60252 30162 60252 30162 60253 30207 60253 30208 60253 30162 60254 30208 60254 30209 60254 30209 60255 30208 60255 30149 60255 30209 60256 30149 60256 30165 60256 30237 60257 30271 60257 30238 60257 30220 60258 30257 60258 30219 60258 30210 60259 30279 60259 30211 60259 30225 60260 30212 60260 30226 60260 30226 60261 30212 60261 30213 60261 30226 60262 30213 60262 30214 60262 30214 60263 30213 60263 30143 60263 30214 60264 30143 60264 30142 60264 30251 60265 30211 60265 30265 60265 30252 60266 30215 60266 30253 60266 30253 60267 30215 60267 30216 60267 30253 60268 30216 60268 30218 60268 30218 60269 30216 60269 30217 60269 30218 60270 30217 60270 30219 60270 30219 60271 30257 60271 30218 60271 30218 60272 30257 60272 30255 60272 30218 60273 30255 60273 30253 60273 30217 60274 30223 60274 30219 60274 30219 60275 30223 60275 30224 60275 30219 60276 30224 60276 30220 60276 30220 60277 30224 60277 30227 60277 30220 60278 30227 60278 30221 60278 30221 60279 30227 60279 30222 60279 30221 60280 30222 60280 30260 60280 30260 60281 30222 60281 30228 60281 30260 60282 30228 60282 30152 60282 30223 60283 30225 60283 30224 60283 30224 60284 30225 60284 30226 60284 30224 60285 30226 60285 30227 60285 30227 60286 30226 60286 30214 60286 30227 60287 30214 60287 30222 60287 30222 60288 30214 60288 30142 60288 30222 60289 30142 60289 30228 60289 30229 60290 30147 60290 30230 60290 30230 60291 30147 60291 30119 60291 30230 60292 30119 60292 30136 60292 30248 60293 30111 60293 30236 60293 30236 60294 30111 60294 30110 60294 30136 60295 30138 60295 30230 60295 30230 60296 30138 60296 30139 60296 30230 60297 30139 60297 30245 60297 30245 60298 30139 60298 30231 60298 30245 60299 30231 60299 30232 60299 30232 60300 30231 60300 30234 60300 30232 60301 30234 60301 30233 60301 30233 60302 30234 60302 30108 60302 30233 60303 30108 60303 30248 60303 30248 60304 30108 60304 30109 60304 30248 60305 30109 60305 30111 60305 30110 60306 30235 60306 30236 60306 30236 60307 30235 60307 30237 60307 30236 60308 30237 60308 30250 60308 30250 60309 30237 60309 30238 60309 30250 60310 30238 60310 30283 60310 30211 60311 30251 60311 30210 60311 30210 60312 30251 60312 30254 60312 30210 60313 30254 60313 30249 60313 30249 60314 30254 60314 30256 60314 30249 60315 30256 60315 30239 60315 30239 60316 30256 60316 30258 60316 30239 60317 30258 60317 30240 60317 30240 60318 30258 60318 30241 60318 30240 60319 30241 60319 30247 60319 30247 60320 30241 60320 30259 60320 30247 60321 30259 60321 30246 60321 30246 60322 30259 60322 30243 60322 30246 60323 30243 60323 30242 60323 30242 60324 30243 60324 30244 60324 30242 60325 30244 60325 30229 60325 30229 60326 30230 60326 30242 60326 30242 60327 30230 60327 30245 60327 30242 60328 30245 60328 30246 60328 30246 60329 30245 60329 30232 60329 30246 60330 30232 60330 30247 60330 30247 60331 30232 60331 30233 60331 30247 60332 30233 60332 30240 60332 30240 60333 30233 60333 30248 60333 30240 60334 30248 60334 30239 60334 30239 60335 30248 60335 30236 60335 30239 60336 30236 60336 30249 60336 30249 60337 30236 60337 30250 60337 30249 60338 30250 60338 30210 60338 30210 60339 30250 60339 30283 60339 30210 60340 30283 60340 30279 60340 30265 60341 30252 60341 30251 60341 30251 60342 30252 60342 30253 60342 30251 60343 30253 60343 30254 60343 30254 60344 30253 60344 30255 60344 30254 60345 30255 60345 30256 60345 30256 60346 30255 60346 30257 60346 30256 60347 30257 60347 30258 60347 30258 60348 30257 60348 30220 60348 30258 60349 30220 60349 30241 60349 30241 60350 30220 60350 30221 60350 30241 60351 30221 60351 30259 60351 30259 60352 30221 60352 30260 60352 30259 60353 30260 60353 30243 60353 30243 60354 30260 60354 30152 60354 30243 60355 30152 60355 30244 60355 30266 60356 30265 60356 30277 60356 30263 60357 30153 60357 30154 60357 30164 60358 30153 60358 30261 60358 30261 60359 30153 60359 30263 60359 30261 60360 30263 60360 30163 60360 30163 60361 30263 60361 30159 60361 30262 60362 30171 60362 30263 60362 30263 60363 30171 60363 30161 60363 30161 60364 30264 60364 30263 60364 30263 60365 30264 60365 30174 60365 30263 60366 30174 60366 30159 60366 30225 60367 30223 60367 30266 60367 30266 60368 30223 60368 30217 60368 30252 60369 30265 60369 30215 60369 30215 60370 30265 60370 30266 60370 30215 60371 30266 60371 30216 60371 30216 60372 30266 60372 30217 60372 30143 60373 30213 60373 30266 60373 30266 60374 30213 60374 30212 60374 30266 60375 30212 60375 30225 60375 30143 60376 30266 60376 30267 60376 30267 60377 30266 60377 30277 60377 30267 60378 30277 60378 30268 60378 30268 60379 30277 60379 30269 60379 30268 60380 30269 60380 30154 60380 30154 60381 30269 60381 30270 60381 30154 60382 30270 60382 30263 60382 30263 60383 30270 60383 30275 60383 30263 60384 30275 60384 30262 60384 30238 60385 30271 60385 30284 60385 30279 60386 30283 60386 30280 60386 30272 60387 30273 60387 30286 60387 30282 60388 30197 60388 30274 60388 30197 60389 30275 60389 30274 60389 30274 60390 30275 60390 30270 60390 30274 60391 30270 60391 30276 60391 30276 60392 30270 60392 30269 60392 30276 60393 30269 60393 30278 60393 30278 60394 30269 60394 30277 60394 30278 60395 30277 60395 30211 60395 30211 60396 30277 60396 30265 60396 30211 60397 30279 60397 30278 60397 30278 60398 30279 60398 30280 60398 30278 60399 30280 60399 30276 60399 30276 60400 30280 60400 30281 60400 30276 60401 30281 60401 30274 60401 30274 60402 30281 60402 30286 60402 30274 60403 30286 60403 30282 60403 30282 60404 30286 60404 30273 60404 30283 60405 30238 60405 30280 60405 30280 60406 30238 60406 30284 60406 30280 60407 30284 60407 30281 60407 30281 60408 30284 60408 30285 60408 30281 60409 30285 60409 30286 60409 30286 60410 30285 60410 30287 60410 30286 60411 30287 60411 30272 60411 30272 60412 30287 60412 30288 60412 30100 60413 30303 60413 30289 60413 30100 60414 30289 60414 30290 60414 30289 60415 30291 60415 30290 60415 30290 60416 30291 60416 30088 60416 30290 60417 30088 60417 30101 60417 30101 60418 30088 60418 30488 60418 30488 60419 30088 60419 30292 60419 30488 60420 30292 60420 30489 60420 30489 60421 30292 60421 30293 60421 30293 60422 30292 60422 30295 60422 30293 60423 30295 60423 30294 60423 30295 60424 30296 60424 30294 60424 30294 60425 30296 60425 30095 60425 30294 60426 30095 60426 30481 60426 30481 60427 30095 60427 30297 60427 30481 60428 30297 60428 30483 60428 30483 60429 30297 60429 30298 60429 30483 60430 30298 60430 30299 60430 30090 60431 30300 60431 30091 60431 30091 60432 30300 60432 30484 60432 30091 60433 30484 60433 30301 60433 30301 60434 30484 60434 30299 60434 30301 60435 30299 60435 30302 60435 30302 60436 30299 60436 30298 60436 30289 60437 30303 60437 30456 60437 30456 60438 30303 60438 30479 60438 30456 60439 30479 60439 30457 60439 30457 60440 30479 60440 30478 60440 30457 60441 30478 60441 30458 60441 30458 60442 30478 60442 30304 60442 30458 60443 30304 60443 30460 60443 30460 60444 30304 60444 30477 60444 30460 60445 30477 60445 30104 60445 30104 60446 30477 60446 30106 60446 30102 60447 30487 60447 30305 60447 30305 60448 30487 60448 30306 60448 30305 60449 30306 60449 30099 60449 30099 60450 30306 60450 30485 60450 30099 60451 30485 60451 30090 60451 30090 60452 30485 60452 30300 60452 30307 60453 30378 60453 30380 60453 30446 60454 30307 60454 30308 60454 30445 60455 30321 60455 30309 60455 30309 60456 30321 60456 30310 60456 30309 60457 30310 60457 30311 60457 30311 60458 30310 60458 30322 60458 30311 60459 30322 60459 30312 60459 30312 60460 30322 60460 30313 60460 30318 60461 30368 60461 30323 60461 30314 60462 30315 60462 30316 60462 30316 60463 30315 60463 30317 60463 30316 60464 30317 60464 30318 60464 30318 60465 30317 60465 30362 60465 30318 60466 30362 60466 30368 60466 30319 60467 30321 60467 30320 60467 30320 60468 30321 60468 30445 60468 30320 60469 30445 60469 30349 60469 30319 60470 30314 60470 30321 60470 30321 60471 30314 60471 30316 60471 30321 60472 30316 60472 30310 60472 30310 60473 30316 60473 30318 60473 30310 60474 30318 60474 30322 60474 30322 60475 30318 60475 30323 60475 30322 60476 30323 60476 30313 60476 30324 60477 30359 60477 30319 60477 30319 60478 30359 60478 30325 60478 30319 60479 30325 60479 30314 60479 30350 60480 30446 60480 30351 60480 30351 60481 30446 60481 30308 60481 30351 60482 30308 60482 30352 60482 30352 60483 30308 60483 30347 60483 30357 60484 30356 60484 30334 60484 30331 60485 30353 60485 30326 60485 30326 60486 30353 60486 30355 60486 30326 60487 30355 60487 30098 60487 30345 60488 30330 60488 30327 60488 30327 60489 30330 60489 30089 60489 30327 60490 30089 60490 30377 60490 30096 60491 30328 60491 30336 60491 30336 60492 30328 60492 30329 60492 30336 60493 30329 60493 30345 60493 30345 60494 30329 60494 30094 60494 30345 60495 30094 60495 30330 60495 30331 60496 30332 60496 30356 60496 30356 60497 30332 60497 30092 60497 30356 60498 30092 60498 30334 60498 30334 60499 30092 60499 30333 60499 30334 60500 30333 60500 30335 60500 30335 60501 30333 60501 30093 60501 30335 60502 30093 60502 30336 60502 30336 60503 30093 60503 30097 60503 30336 60504 30097 60504 30096 60504 30357 60505 30344 60505 30358 60505 30358 60506 30344 60506 30337 60506 30358 60507 30337 60507 30360 60507 30360 60508 30337 60508 30338 60508 30360 60509 30338 60509 30339 60509 30339 60510 30338 60510 30346 60510 30339 60511 30346 60511 30340 60511 30340 60512 30346 60512 30341 60512 30340 60513 30341 60513 30343 60513 30343 60514 30341 60514 30342 60514 30343 60515 30342 60515 30361 60515 30357 60516 30334 60516 30344 60516 30344 60517 30334 60517 30335 60517 30344 60518 30335 60518 30337 60518 30337 60519 30335 60519 30336 60519 30337 60520 30336 60520 30338 60520 30338 60521 30336 60521 30345 60521 30338 60522 30345 60522 30346 60522 30346 60523 30345 60523 30327 60523 30346 60524 30327 60524 30341 60524 30341 60525 30327 60525 30377 60525 30341 60526 30377 60526 30342 60526 30307 60527 30380 60527 30308 60527 30308 60528 30380 60528 30348 60528 30308 60529 30348 60529 30347 60529 30347 60530 30348 60530 30379 60530 30347 60531 30379 60531 30354 60531 30349 60532 30350 60532 30320 60532 30320 60533 30350 60533 30351 60533 30320 60534 30351 60534 30319 60534 30319 60535 30351 60535 30352 60535 30319 60536 30352 60536 30324 60536 30324 60537 30352 60537 30347 60537 30324 60538 30347 60538 30353 60538 30353 60539 30347 60539 30354 60539 30353 60540 30354 60540 30355 60540 30331 60541 30356 60541 30353 60541 30353 60542 30356 60542 30357 60542 30353 60543 30357 60543 30324 60543 30324 60544 30357 60544 30358 60544 30324 60545 30358 60545 30359 60545 30359 60546 30358 60546 30360 60546 30359 60547 30360 60547 30325 60547 30325 60548 30360 60548 30339 60548 30325 60549 30339 60549 30314 60549 30314 60550 30339 60550 30340 60550 30314 60551 30340 60551 30315 60551 30315 60552 30340 60552 30343 60552 30315 60553 30343 60553 30317 60553 30317 60554 30343 60554 30361 60554 30317 60555 30361 60555 30362 60555 30411 60556 30429 60556 30363 60556 30364 60557 30365 60557 30367 60557 30366 60558 30369 60558 30409 60558 30409 60559 30369 60559 30372 60559 30312 60560 30313 60560 30453 60560 30453 60561 30313 60561 30365 60561 30375 60562 30371 60562 30370 60562 30370 60563 30371 60563 30372 60563 30365 60564 30313 60564 30367 60564 30367 60565 30313 60565 30323 60565 30367 60566 30323 60566 30368 60566 30369 60567 30364 60567 30372 60567 30372 60568 30364 60568 30367 60568 30372 60569 30367 60569 30370 60569 30370 60570 30367 60570 30368 60570 30429 60571 30428 60571 30371 60571 30371 60572 30428 60572 30404 60572 30371 60573 30404 60573 30372 60573 30372 60574 30404 60574 30403 60574 30372 60575 30403 60575 30409 60575 30376 60576 30373 60576 30363 60576 30363 60577 30373 60577 30374 60577 30363 60578 30374 60578 30411 60578 30368 60579 30362 60579 30370 60579 30370 60580 30362 60580 30361 60580 30370 60581 30361 60581 30375 60581 30375 60582 30361 60582 30342 60582 30375 60583 30342 60583 30377 60583 30429 60584 30371 60584 30363 60584 30363 60585 30371 60585 30375 60585 30363 60586 30375 60586 30376 60586 30376 60587 30375 60587 30377 60587 30376 60588 30377 60588 30089 60588 30388 60589 30385 60589 30389 60589 30452 60590 30447 60590 30422 60590 30380 60591 30378 60591 30454 60591 30379 60592 30348 60592 30388 60592 30388 60593 30348 60593 30380 60593 30380 60594 30454 60594 30388 60594 30388 60595 30454 60595 30381 60595 30388 60596 30381 60596 30385 60596 30385 60597 30381 60597 30382 60597 30385 60598 30382 60598 30452 60598 30355 60599 30354 60599 30383 60599 30383 60600 30354 60600 30379 60600 30098 60601 30355 60601 30384 60601 30384 60602 30355 60602 30383 60602 30384 60603 30383 60603 30390 60603 30452 60604 30422 60604 30385 60604 30385 60605 30422 60605 30386 60605 30385 60606 30386 60606 30389 60606 30389 60607 30386 60607 30387 60607 30389 60608 30387 60608 30392 60608 30379 60609 30388 60609 30383 60609 30383 60610 30388 60610 30389 60610 30383 60611 30389 60611 30390 60611 30390 60612 30389 60612 30392 60612 30390 60613 30392 60613 30103 60613 30391 60614 30103 60614 30392 60614 30393 60615 30438 60615 30401 60615 30394 60616 30386 60616 30422 60616 30366 60617 30409 60617 30395 60617 30395 60618 30409 60618 30407 60618 30395 60619 30407 60619 30449 60619 30449 60620 30407 60620 30405 60620 30449 60621 30405 60621 30396 60621 30423 60622 30422 60622 30447 60622 30448 60623 30397 60623 30436 60623 30436 60624 30397 60624 30398 60624 30398 60625 30397 60625 30400 60625 30398 60626 30400 60626 30401 60626 30401 60627 30438 60627 30398 60627 30398 60628 30438 60628 30399 60628 30398 60629 30399 60629 30436 60629 30400 60630 30450 60630 30401 60630 30401 60631 30450 60631 30402 60631 30401 60632 30402 60632 30393 60632 30393 60633 30402 60633 30406 60633 30393 60634 30406 60634 30441 60634 30441 60635 30406 60635 30408 60635 30441 60636 30408 60636 30443 60636 30443 60637 30408 60637 30403 60637 30443 60638 30403 60638 30404 60638 30450 60639 30396 60639 30402 60639 30402 60640 30396 60640 30405 60640 30402 60641 30405 60641 30406 60641 30406 60642 30405 60642 30407 60642 30406 60643 30407 60643 30408 60643 30408 60644 30407 60644 30409 60644 30408 60645 30409 60645 30403 60645 30433 60646 30430 60646 30414 60646 30414 60647 30430 60647 30410 60647 30410 60648 30430 60648 30412 60648 30410 60649 30412 60649 30455 60649 30374 60650 30455 60650 30411 60650 30411 60651 30455 60651 30412 60651 30411 60652 30412 60652 30429 60652 30417 60653 30413 60653 30420 60653 30420 60654 30413 60654 30459 60654 30414 60655 30415 60655 30433 60655 30433 60656 30415 60656 30462 60656 30433 60657 30462 60657 30416 60657 30416 60658 30462 60658 30418 60658 30416 60659 30418 60659 30417 60659 30417 60660 30418 60660 30461 60660 30417 60661 30461 60661 30413 60661 30459 60662 30419 60662 30420 60662 30420 60663 30419 60663 30391 60663 30420 60664 30391 60664 30421 60664 30421 60665 30391 60665 30392 60665 30421 60666 30392 60666 30387 60666 30422 60667 30423 60667 30394 60667 30394 60668 30423 60668 30424 60668 30394 60669 30424 60669 30435 60669 30435 60670 30424 60670 30437 60670 30435 60671 30437 60671 30425 60671 30425 60672 30437 60672 30439 60672 30425 60673 30439 60673 30434 60673 30434 60674 30439 60674 30440 60674 30434 60675 30440 60675 30432 60675 30432 60676 30440 60676 30442 60676 30432 60677 30442 60677 30426 60677 30426 60678 30442 60678 30427 60678 30426 60679 30427 60679 30431 60679 30431 60680 30427 60680 30428 60680 30431 60681 30428 60681 30429 60681 30429 60682 30412 60682 30431 60682 30431 60683 30412 60683 30430 60683 30431 60684 30430 60684 30426 60684 30426 60685 30430 60685 30433 60685 30426 60686 30433 60686 30432 60686 30432 60687 30433 60687 30416 60687 30432 60688 30416 60688 30434 60688 30434 60689 30416 60689 30417 60689 30434 60690 30417 60690 30425 60690 30425 60691 30417 60691 30420 60691 30425 60692 30420 60692 30435 60692 30435 60693 30420 60693 30421 60693 30435 60694 30421 60694 30394 60694 30394 60695 30421 60695 30387 60695 30394 60696 30387 60696 30386 60696 30447 60697 30448 60697 30423 60697 30423 60698 30448 60698 30436 60698 30423 60699 30436 60699 30424 60699 30424 60700 30436 60700 30399 60700 30424 60701 30399 60701 30437 60701 30437 60702 30399 60702 30438 60702 30437 60703 30438 60703 30439 60703 30439 60704 30438 60704 30393 60704 30439 60705 30393 60705 30440 60705 30440 60706 30393 60706 30441 60706 30440 60707 30441 60707 30442 60707 30442 60708 30441 60708 30443 60708 30442 60709 30443 60709 30427 60709 30427 60710 30443 60710 30404 60710 30427 60711 30404 60711 30428 60711 30444 60712 30312 60712 30453 60712 30444 60713 30349 60713 30445 60713 30445 60714 30309 60714 30444 60714 30444 60715 30309 60715 30311 60715 30444 60716 30311 60716 30312 60716 30307 60717 30446 60717 30444 60717 30444 60718 30446 60718 30350 60718 30444 60719 30350 60719 30349 60719 30451 60720 30447 60720 30452 60720 30448 60721 30447 60721 30397 60721 30397 60722 30447 60722 30451 60722 30397 60723 30451 60723 30400 60723 30366 60724 30395 60724 30451 60724 30451 60725 30395 60725 30449 60725 30449 60726 30396 60726 30451 60726 30451 60727 30396 60727 30450 60727 30451 60728 30450 60728 30400 60728 30366 60729 30451 60729 30369 60729 30369 60730 30451 60730 30452 60730 30369 60731 30452 60731 30364 60731 30364 60732 30452 60732 30382 60732 30364 60733 30382 60733 30365 60733 30365 60734 30382 60734 30381 60734 30365 60735 30381 60735 30453 60735 30453 60736 30381 60736 30454 60736 30453 60737 30454 60737 30444 60737 30444 60738 30454 60738 30378 60738 30444 60739 30378 60739 30307 60739 30374 60740 30289 60740 30455 60740 30455 60741 30289 60741 30456 60741 30455 60742 30456 60742 30410 60742 30410 60743 30456 60743 30457 60743 30410 60744 30457 60744 30414 60744 30414 60745 30457 60745 30415 60745 30415 60746 30457 60746 30458 60746 30415 60747 30458 60747 30462 60747 30460 60748 30104 60748 30459 60748 30459 60749 30413 60749 30460 60749 30460 60750 30413 60750 30461 60750 30460 60751 30461 60751 30458 60751 30458 60752 30461 60752 30418 60752 30458 60753 30418 60753 30462 60753 30140 60754 30463 60754 30141 60754 30141 60755 30463 60755 30117 60755 30135 60756 30490 60756 30137 60756 30137 60757 30490 60757 30464 60757 30137 60758 30464 60758 30140 60758 30140 60759 30464 60759 30488 60759 30140 60760 30488 60760 30463 60760 30130 60761 30471 60761 30470 60761 30465 60762 30466 60762 30468 60762 30468 60763 30466 60763 30467 60763 30468 60764 30467 60764 30100 60764 30100 60765 30467 60765 30469 60765 30100 60766 30469 60766 30470 60766 30470 60767 30469 60767 30133 60767 30470 60768 30133 60768 30130 60768 30130 60769 30472 60769 30471 60769 30471 60770 30472 60770 30473 60770 30471 60771 30473 60771 30476 60771 30126 60772 30486 60772 30128 60772 30128 60773 30486 60773 30474 60773 30128 60774 30474 60774 30129 60774 30129 60775 30474 60775 30476 60775 30129 60776 30476 60776 30475 60776 30475 60777 30476 60777 30473 60777 30303 60778 30100 60778 30470 60778 30477 60779 30471 60779 30476 60779 30477 60780 30304 60780 30471 60780 30471 60781 30304 60781 30478 60781 30471 60782 30478 60782 30470 60782 30470 60783 30478 60783 30479 60783 30470 60784 30479 60784 30303 60784 30487 60785 30480 60785 30476 60785 30476 60786 30480 60786 30106 60786 30476 60787 30106 60787 30477 60787 30481 60788 30482 60788 30117 60788 30481 60789 30483 60789 30482 60789 30482 60790 30483 60790 30299 60790 30482 60791 30299 60791 30115 60791 30115 60792 30299 60792 30484 60792 30115 60793 30484 60793 30112 60793 30112 60794 30484 60794 30300 60794 30112 60795 30300 60795 30124 60795 30124 60796 30300 60796 30485 60796 30124 60797 30485 60797 30125 60797 30125 60798 30485 60798 30306 60798 30125 60799 30306 60799 30486 60799 30486 60800 30306 60800 30487 60800 30486 60801 30487 60801 30474 60801 30474 60802 30487 60802 30476 60802 30488 60803 30489 60803 30463 60803 30463 60804 30489 60804 30293 60804 30463 60805 30293 60805 30117 60805 30117 60806 30293 60806 30294 60806 30117 60807 30294 60807 30481 60807 30490 60808 30135 60808 30121 60808 30490 60809 30121 60809 30491 60809 30491 60810 30121 60810 30466 60810 30491 60811 30466 60811 30465 60811 30492 60812 30895 60812 30493 60812 30493 60813 30895 60813 30495 60813 30493 60814 30495 60814 30494 60814 30495 60815 30520 60815 30494 60815 30494 60816 30520 60816 30496 60816 30494 60817 30496 60817 30498 60817 30498 60818 30496 60818 30497 60818 30498 60819 30497 60819 30499 60819 30499 60820 30497 60820 30500 60820 30499 60821 30500 60821 30501 60821 30513 60822 30502 60822 30503 60822 30503 60823 30502 60823 30715 60823 30503 60824 30715 60824 30504 60824 30504 60825 30715 60825 30501 60825 30504 60826 30501 60826 30515 60826 30515 60827 30501 60827 30500 60827 30530 60828 30707 60828 30505 60828 30505 60829 30707 60829 30708 60829 30505 60830 30708 60830 30506 60830 30506 60831 30708 60831 30711 60831 30506 60832 30711 60832 30507 60832 30507 60833 30711 60833 30682 60833 30697 60834 30892 60834 30508 60834 30508 60835 30892 60835 30893 60835 30508 60836 30893 60836 30509 60836 30509 60837 30893 60837 30511 60837 30509 60838 30511 60838 30510 60838 30510 60839 30511 60839 30712 60839 30510 60840 30712 60840 30694 60840 30495 60841 30895 60841 30664 60841 30647 60842 30513 60842 30512 60842 30512 60843 30513 60843 30503 60843 30512 60844 30503 60844 30577 60844 30577 60845 30503 60845 30514 60845 30503 60846 30504 60846 30514 60846 30514 60847 30504 60847 30515 60847 30514 60848 30515 60848 30516 60848 30516 60849 30515 60849 30500 60849 30516 60850 30500 60850 30554 60850 30554 60851 30500 60851 30517 60851 30517 60852 30500 60852 30497 60852 30517 60853 30497 60853 30518 60853 30551 60854 30549 60854 30496 60854 30496 60855 30549 60855 30548 60855 30496 60856 30548 60856 30497 60856 30497 60857 30548 60857 30519 60857 30497 60858 30519 60858 30518 60858 30664 60859 30547 60859 30495 60859 30495 60860 30547 60860 30551 60860 30495 60861 30551 60861 30520 60861 30520 60862 30551 60862 30496 60862 30609 60863 30530 60863 30521 60863 30521 60864 30530 60864 30505 60864 30521 60865 30505 60865 30606 60865 30606 60866 30505 60866 30506 60866 30606 60867 30506 60867 30522 60867 30522 60868 30506 60868 30507 60868 30522 60869 30507 60869 30605 60869 30523 60870 30524 60870 30649 60870 30649 60871 30524 60871 30525 60871 30649 60872 30525 60872 30526 60872 30526 60873 30525 60873 30897 60873 30526 60874 30897 60874 30647 60874 30647 60875 30897 60875 30513 60875 30664 60876 30895 60876 30894 60876 30664 60877 30894 60877 30527 60877 30527 60878 30894 60878 30528 60878 30527 60879 30528 60879 30529 60879 30529 60880 30528 60880 30530 60880 30529 60881 30530 60881 30609 60881 30570 60882 30674 60882 30571 60882 30543 60883 30570 60883 30572 60883 30537 60884 30531 60884 30666 60884 30666 60885 30531 60885 30539 60885 30666 60886 30539 60886 30667 60886 30667 60887 30539 60887 30540 60887 30667 60888 30540 60888 30652 60888 30652 60889 30540 60889 30653 60889 30541 60890 30532 60890 30655 60890 30533 60891 30581 60891 30538 60891 30538 60892 30581 60892 30583 60892 30538 60893 30583 60893 30541 60893 30541 60894 30583 60894 30534 60894 30541 60895 30534 60895 30532 60895 30535 60896 30531 60896 30536 60896 30536 60897 30531 60897 30537 60897 30536 60898 30537 60898 30574 60898 30535 60899 30533 60899 30531 60899 30531 60900 30533 60900 30538 60900 30531 60901 30538 60901 30539 60901 30539 60902 30538 60902 30541 60902 30539 60903 30541 60903 30540 60903 30540 60904 30541 60904 30655 60904 30540 60905 30655 60905 30653 60905 30576 60906 30579 60906 30535 60906 30535 60907 30579 60907 30580 60907 30535 60908 30580 60908 30533 60908 30542 60909 30543 60909 30575 60909 30575 60910 30543 60910 30572 60910 30575 60911 30572 60911 30544 60911 30544 60912 30572 60912 30545 60912 30562 60913 30552 60913 30553 60913 30577 60914 30578 60914 30512 60914 30512 60915 30578 60915 30546 60915 30512 60916 30546 60916 30647 60916 30550 60917 30547 60917 30567 60917 30567 60918 30547 60918 30664 60918 30567 60919 30664 60919 30568 60919 30519 60920 30548 60920 30555 60920 30555 60921 30548 60921 30549 60921 30555 60922 30549 60922 30550 60922 30550 60923 30549 60923 30551 60923 30550 60924 30551 60924 30547 60924 30577 60925 30514 60925 30552 60925 30552 60926 30514 60926 30516 60926 30552 60927 30516 60927 30553 60927 30553 60928 30516 60928 30554 60928 30553 60929 30554 60929 30564 60929 30564 60930 30554 60930 30517 60930 30564 60931 30517 60931 30555 60931 30555 60932 30517 60932 30518 60932 30555 60933 30518 60933 30519 60933 30562 60934 30563 60934 30556 60934 30556 60935 30563 60935 30557 60935 30556 60936 30557 60936 30558 60936 30558 60937 30557 60937 30565 60937 30558 60938 30565 60938 30559 60938 30559 60939 30565 60939 30566 60939 30559 60940 30566 60940 30560 60940 30560 60941 30566 60941 30561 60941 30560 60942 30561 60942 30582 60942 30582 60943 30561 60943 30569 60943 30582 60944 30569 60944 30584 60944 30562 60945 30553 60945 30563 60945 30563 60946 30553 60946 30564 60946 30563 60947 30564 60947 30557 60947 30557 60948 30564 60948 30555 60948 30557 60949 30555 60949 30565 60949 30565 60950 30555 60950 30550 60950 30565 60951 30550 60951 30566 60951 30566 60952 30550 60952 30567 60952 30566 60953 30567 60953 30561 60953 30561 60954 30567 60954 30568 60954 30561 60955 30568 60955 30569 60955 30570 60956 30571 60956 30572 60956 30572 60957 30571 60957 30641 60957 30572 60958 30641 60958 30545 60958 30545 60959 30641 60959 30573 60959 30545 60960 30573 60960 30646 60960 30574 60961 30542 60961 30536 60961 30536 60962 30542 60962 30575 60962 30536 60963 30575 60963 30535 60963 30535 60964 30575 60964 30544 60964 30535 60965 30544 60965 30576 60965 30576 60966 30544 60966 30545 60966 30576 60967 30545 60967 30578 60967 30578 60968 30545 60968 30646 60968 30578 60969 30646 60969 30546 60969 30577 60970 30552 60970 30578 60970 30578 60971 30552 60971 30562 60971 30578 60972 30562 60972 30576 60972 30576 60973 30562 60973 30556 60973 30576 60974 30556 60974 30579 60974 30579 60975 30556 60975 30558 60975 30579 60976 30558 60976 30580 60976 30580 60977 30558 60977 30559 60977 30580 60978 30559 60978 30533 60978 30533 60979 30559 60979 30560 60979 30533 60980 30560 60980 30581 60980 30581 60981 30560 60981 30582 60981 30581 60982 30582 60982 30583 60982 30583 60983 30582 60983 30584 60983 30583 60984 30584 60984 30534 60984 30680 60985 30523 60985 30650 60985 30635 60986 30596 60986 30597 60986 30629 60987 30585 60987 30586 60987 30651 60988 30588 60988 30587 60988 30587 60989 30588 60989 30590 60989 30587 60990 30590 60990 30589 60990 30589 60991 30590 60991 30591 60991 30589 60992 30591 60992 30592 60992 30632 60993 30586 60993 30631 60993 30633 60994 30669 60994 30593 60994 30593 60995 30669 60995 30595 60995 30595 60996 30669 60996 30594 60996 30595 60997 30594 60997 30597 60997 30597 60998 30596 60998 30595 60998 30595 60999 30596 60999 30634 60999 30595 61000 30634 61000 30593 61000 30594 61001 30603 61001 30597 61001 30597 61002 30603 61002 30598 61002 30597 61003 30598 61003 30635 61003 30635 61004 30598 61004 30599 61004 30635 61005 30599 61005 30636 61005 30636 61006 30599 61006 30600 61006 30636 61007 30600 61007 30601 61007 30601 61008 30600 61008 30659 61008 30601 61009 30659 61009 30602 61009 30603 61010 30592 61010 30598 61010 30598 61011 30592 61011 30591 61011 30598 61012 30591 61012 30599 61012 30599 61013 30591 61013 30590 61013 30599 61014 30590 61014 30600 61014 30600 61015 30590 61015 30588 61015 30600 61016 30588 61016 30659 61016 30605 61017 30675 61017 30612 61017 30612 61018 30604 61018 30605 61018 30605 61019 30604 61019 30624 61019 30605 61020 30624 61020 30522 61020 30522 61021 30624 61021 30607 61021 30522 61022 30607 61022 30606 61022 30606 61023 30607 61023 30521 61023 30657 61024 30608 61024 30607 61024 30607 61025 30608 61025 30609 61025 30607 61026 30609 61026 30521 61026 30611 61027 30613 61027 30614 61027 30614 61028 30610 61028 30611 61028 30611 61029 30610 61029 30612 61029 30611 61030 30612 61030 30676 61030 30676 61031 30612 61031 30675 61031 30613 61032 30615 61032 30614 61032 30614 61033 30615 61033 30680 61033 30614 61034 30680 61034 30616 61034 30616 61035 30680 61035 30650 61035 30616 61036 30650 61036 30630 61036 30586 61037 30632 61037 30629 61037 30629 61038 30632 61038 30617 61038 30629 61039 30617 61039 30628 61039 30628 61040 30617 61040 30618 61040 30628 61041 30618 61041 30627 61041 30627 61042 30618 61042 30619 61042 30627 61043 30619 61043 30621 61043 30621 61044 30619 61044 30620 61044 30621 61045 30620 61045 30622 61045 30622 61046 30620 61046 30623 61046 30622 61047 30623 61047 30626 61047 30626 61048 30623 61048 30637 61048 30626 61049 30637 61049 30625 61049 30625 61050 30637 61050 30638 61050 30625 61051 30638 61051 30657 61051 30657 61052 30607 61052 30625 61052 30625 61053 30607 61053 30624 61053 30625 61054 30624 61054 30626 61054 30626 61055 30624 61055 30604 61055 30626 61056 30604 61056 30622 61056 30622 61057 30604 61057 30612 61057 30622 61058 30612 61058 30621 61058 30621 61059 30612 61059 30610 61059 30621 61060 30610 61060 30627 61060 30627 61061 30610 61061 30614 61061 30627 61062 30614 61062 30628 61062 30628 61063 30614 61063 30616 61063 30628 61064 30616 61064 30629 61064 30629 61065 30616 61065 30630 61065 30629 61066 30630 61066 30585 61066 30631 61067 30633 61067 30632 61067 30632 61068 30633 61068 30593 61068 30632 61069 30593 61069 30617 61069 30617 61070 30593 61070 30634 61070 30617 61071 30634 61071 30618 61071 30618 61072 30634 61072 30596 61072 30618 61073 30596 61073 30619 61073 30619 61074 30596 61074 30635 61074 30619 61075 30635 61075 30620 61075 30620 61076 30635 61076 30636 61076 30620 61077 30636 61077 30623 61077 30623 61078 30636 61078 30601 61078 30623 61079 30601 61079 30637 61079 30637 61080 30601 61080 30602 61080 30637 61081 30602 61081 30638 61081 30642 61082 30643 61082 30639 61082 30645 61083 30631 61083 30586 61083 30571 61084 30674 61084 30640 61084 30573 61085 30641 61085 30642 61085 30642 61086 30641 61086 30571 61086 30571 61087 30640 61087 30642 61087 30642 61088 30640 61088 30644 61088 30642 61089 30644 61089 30643 61089 30643 61090 30644 61090 30672 61090 30643 61091 30672 61091 30645 61091 30546 61092 30646 61092 30648 61092 30648 61093 30646 61093 30573 61093 30647 61094 30546 61094 30526 61094 30526 61095 30546 61095 30648 61095 30526 61096 30648 61096 30649 61096 30645 61097 30586 61097 30643 61097 30643 61098 30586 61098 30585 61098 30643 61099 30585 61099 30639 61099 30639 61100 30585 61100 30630 61100 30639 61101 30630 61101 30650 61101 30573 61102 30642 61102 30648 61102 30648 61103 30642 61103 30639 61103 30648 61104 30639 61104 30649 61104 30649 61105 30639 61105 30650 61105 30649 61106 30650 61106 30523 61106 30608 61107 30657 61107 30660 61107 30656 61108 30671 61108 30654 61108 30651 61109 30670 61109 30588 61109 30588 61110 30670 61110 30658 61110 30652 61111 30653 61111 30665 61111 30665 61112 30653 61112 30671 61112 30663 61113 30662 61113 30661 61113 30661 61114 30662 61114 30658 61114 30671 61115 30653 61115 30654 61115 30654 61116 30653 61116 30655 61116 30654 61117 30655 61117 30532 61117 30670 61118 30656 61118 30658 61118 30658 61119 30656 61119 30654 61119 30658 61120 30654 61120 30661 61120 30661 61121 30654 61121 30532 61121 30657 61122 30638 61122 30662 61122 30662 61123 30638 61123 30602 61123 30662 61124 30602 61124 30658 61124 30658 61125 30602 61125 30659 61125 30658 61126 30659 61126 30588 61126 30527 61127 30529 61127 30660 61127 30660 61128 30529 61128 30609 61128 30660 61129 30609 61129 30608 61129 30532 61130 30534 61130 30661 61130 30661 61131 30534 61131 30584 61131 30661 61132 30584 61132 30663 61132 30663 61133 30584 61133 30569 61133 30663 61134 30569 61134 30568 61134 30657 61135 30662 61135 30660 61135 30660 61136 30662 61136 30663 61136 30660 61137 30663 61137 30527 61137 30527 61138 30663 61138 30568 61138 30527 61139 30568 61139 30664 61139 30673 61140 30652 61140 30665 61140 30673 61141 30574 61141 30537 61141 30537 61142 30666 61142 30673 61142 30673 61143 30666 61143 30667 61143 30673 61144 30667 61144 30652 61144 30570 61145 30543 61145 30673 61145 30673 61146 30543 61146 30542 61146 30673 61147 30542 61147 30574 61147 30668 61148 30631 61148 30645 61148 30633 61149 30631 61149 30669 61149 30669 61150 30631 61150 30668 61150 30669 61151 30668 61151 30594 61151 30651 61152 30587 61152 30668 61152 30668 61153 30587 61153 30589 61153 30589 61154 30592 61154 30668 61154 30668 61155 30592 61155 30603 61155 30668 61156 30603 61156 30594 61156 30651 61157 30668 61157 30670 61157 30670 61158 30668 61158 30645 61158 30670 61159 30645 61159 30656 61159 30656 61160 30645 61160 30672 61160 30656 61161 30672 61161 30671 61161 30671 61162 30672 61162 30644 61162 30671 61163 30644 61163 30665 61163 30665 61164 30644 61164 30640 61164 30665 61165 30640 61165 30673 61165 30673 61166 30640 61166 30674 61166 30673 61167 30674 61167 30570 61167 30605 61168 30507 61168 30675 61168 30675 61169 30507 61169 30683 61169 30675 61170 30683 61170 30676 61170 30676 61171 30683 61171 30611 61171 30611 61172 30683 61172 30685 61172 30611 61173 30685 61173 30613 61173 30613 61174 30685 61174 30677 61174 30613 61175 30677 61175 30615 61175 30677 61176 30678 61176 30615 61176 30615 61177 30678 61177 30679 61177 30615 61178 30679 61178 30680 61178 30680 61179 30679 61179 30524 61179 30680 61180 30524 61180 30523 61180 30896 61181 30524 61181 30709 61181 30709 61182 30524 61182 30679 61182 30709 61183 30679 61183 30681 61183 30681 61184 30679 61184 30678 61184 30507 61185 30682 61185 30683 61185 30683 61186 30682 61186 30684 61186 30683 61187 30684 61187 30685 61187 30685 61188 30684 61188 30681 61188 30685 61189 30681 61189 30677 61189 30677 61190 30681 61190 30678 61190 30686 61191 30839 61191 30687 61191 30686 61192 30687 61192 30688 61192 30687 61193 30689 61193 30688 61193 30688 61194 30689 61194 30690 61194 30688 61195 30690 61195 30757 61195 30687 61196 30714 61196 30689 61196 30689 61197 30714 61197 30691 61197 30689 61198 30691 61198 30690 61198 30690 61199 30691 61199 30716 61199 30736 61200 30713 61200 30739 61200 30739 61201 30713 61201 30692 61201 30739 61202 30692 61202 30741 61202 30741 61203 30692 61203 30693 61203 30741 61204 30693 61204 30687 61204 30687 61205 30693 61205 30714 61205 30735 61206 30510 61206 30695 61206 30695 61207 30510 61207 30694 61207 30695 61208 30694 61208 30736 61208 30736 61209 30694 61209 30712 61209 30736 61210 30712 61210 30713 61210 30508 61211 30723 61211 30697 61211 30697 61212 30723 61212 30696 61212 30697 61213 30696 61213 30892 61213 30892 61214 30696 61214 30733 61214 30892 61215 30733 61215 30698 61215 30698 61216 30733 61216 30699 61216 30698 61217 30699 61217 30710 61217 30710 61218 30699 61218 30700 61218 30710 61219 30700 61219 30701 61219 30701 61220 30700 61220 30706 61220 30701 61221 30706 61221 30704 61221 30725 61222 30718 61222 30702 61222 30702 61223 30718 61223 30703 61223 30702 61224 30703 61224 30705 61224 30705 61225 30703 61225 30704 61225 30705 61226 30704 61226 30727 61226 30727 61227 30704 61227 30706 61227 30707 61228 30892 61228 30698 61228 30710 61229 30711 61229 30698 61229 30698 61230 30711 61230 30708 61230 30698 61231 30708 61231 30707 61231 30896 61232 30709 61232 30704 61232 30704 61233 30709 61233 30681 61233 30704 61234 30681 61234 30701 61234 30701 61235 30681 61235 30684 61235 30701 61236 30684 61236 30710 61236 30710 61237 30684 61237 30682 61237 30710 61238 30682 61238 30711 61238 30498 61239 30693 61239 30692 61239 30712 61240 30492 61240 30713 61240 30713 61241 30492 61241 30493 61241 30713 61242 30493 61242 30692 61242 30692 61243 30493 61243 30494 61243 30692 61244 30494 61244 30498 61244 30498 61245 30499 61245 30693 61245 30693 61246 30499 61246 30501 61246 30693 61247 30501 61247 30714 61247 30714 61248 30501 61248 30715 61248 30714 61249 30715 61249 30691 61249 30691 61250 30715 61250 30502 61250 30691 61251 30502 61251 30716 61251 30716 61252 30502 61252 30898 61252 30716 61253 30898 61253 30717 61253 30717 61254 30898 61254 30719 61254 30717 61255 30719 61255 30718 61255 30718 61256 30719 61256 30896 61256 30718 61257 30896 61257 30703 61257 30703 61258 30896 61258 30704 61258 30510 61259 30735 61259 30720 61259 30510 61260 30720 61260 30509 61260 30509 61261 30720 61261 30723 61261 30509 61262 30723 61262 30508 61262 30731 61263 30723 61263 30745 61263 30745 61264 30723 61264 30720 61264 30745 61265 30720 61265 30746 61265 30735 61266 30721 61266 30720 61266 30720 61267 30721 61267 30722 61267 30720 61268 30722 61268 30746 61268 30690 61269 30716 61269 30758 61269 30758 61270 30716 61270 30717 61270 30758 61271 30717 61271 30725 61271 30725 61272 30717 61272 30718 61272 30696 61273 30723 61273 30731 61273 30800 61274 30725 61274 30724 61274 30724 61275 30725 61275 30702 61275 30724 61276 30702 61276 30772 61276 30772 61277 30702 61277 30805 61277 30702 61278 30705 61278 30805 61278 30805 61279 30705 61279 30727 61279 30805 61280 30727 61280 30726 61280 30726 61281 30727 61281 30706 61281 30726 61282 30706 61282 30728 61282 30728 61283 30706 61283 30700 61283 30728 61284 30700 61284 30730 61284 30799 61285 30729 61285 30699 61285 30699 61286 30729 61286 30785 61286 30699 61287 30785 61287 30700 61287 30700 61288 30785 61288 30783 61288 30700 61289 30783 61289 30730 61289 30731 61290 30732 61290 30696 61290 30696 61291 30732 61291 30799 61291 30696 61292 30799 61292 30733 61292 30733 61293 30799 61293 30699 61293 30830 61294 30831 61294 30736 61294 30721 61295 30735 61295 30734 61295 30734 61296 30735 61296 30695 61296 30831 61297 30835 61297 30736 61297 30736 61298 30835 61298 30834 61298 30736 61299 30834 61299 30695 61299 30695 61300 30834 61300 30833 61300 30695 61301 30833 61301 30734 61301 30830 61302 30736 61302 30737 61302 30737 61303 30736 61303 30739 61303 30737 61304 30739 61304 30738 61304 30738 61305 30739 61305 30842 61305 30842 61306 30739 61306 30741 61306 30842 61307 30741 61307 30740 61307 30687 61308 30839 61308 30741 61308 30741 61309 30839 61309 30742 61309 30741 61310 30742 61310 30740 61310 30755 61311 30828 61311 30743 61311 30828 61312 30755 61312 30829 61312 30751 61313 30747 61313 30748 61313 30789 61314 30731 61314 30745 61314 30750 61315 30744 61315 30751 61315 30751 61316 30744 61316 30789 61316 30789 61317 30745 61317 30751 61317 30751 61318 30745 61318 30746 61318 30751 61319 30746 61319 30747 61319 30747 61320 30746 61320 30722 61320 30747 61321 30722 61321 30721 61321 30786 61322 30787 61322 30752 61322 30752 61323 30787 61323 30750 61323 30721 61324 30837 61324 30747 61324 30747 61325 30837 61325 30838 61325 30747 61326 30838 61326 30748 61326 30748 61327 30838 61327 30854 61327 30748 61328 30854 61328 30753 61328 30767 61329 30786 61329 30749 61329 30749 61330 30786 61330 30752 61330 30749 61331 30752 61331 30755 61331 30750 61332 30751 61332 30752 61332 30752 61333 30751 61333 30748 61333 30752 61334 30748 61334 30755 61334 30755 61335 30748 61335 30753 61335 30755 61336 30753 61336 30829 61336 30869 61337 30767 61337 30870 61337 30870 61338 30767 61338 30749 61338 30870 61339 30749 61339 30754 61339 30754 61340 30749 61340 30755 61340 30754 61341 30755 61341 30756 61341 30756 61342 30755 61342 30743 61342 30757 61343 30690 61343 30888 61343 30888 61344 30690 61344 30758 61344 30888 61345 30758 61345 30889 61345 30889 61346 30758 61346 30891 61346 30891 61347 30758 61347 30725 61347 30891 61348 30725 61348 30800 61348 30729 61349 30799 61349 30759 61349 30780 61350 30774 61350 30775 61350 30871 61351 30779 61351 30768 61351 30762 61352 30803 61352 30773 61352 30780 61353 30760 61353 30774 61353 30774 61354 30760 61354 30761 61354 30774 61355 30761 61355 30762 61355 30766 61356 30763 61356 30812 61356 30812 61357 30763 61357 30764 61357 30812 61358 30764 61358 30811 61358 30812 61359 30765 61359 30766 61359 30766 61360 30765 61360 30767 61360 30766 61361 30767 61361 30869 61361 30764 61362 30871 61362 30811 61362 30811 61363 30871 61363 30768 61363 30811 61364 30768 61364 30769 61364 30769 61365 30768 61365 30770 61365 30769 61366 30770 61366 30809 61366 30809 61367 30770 61367 30781 61367 30809 61368 30781 61368 30771 61368 30771 61369 30781 61369 30782 61369 30771 61370 30782 61370 30807 61370 30724 61371 30772 61371 30776 61371 30776 61372 30772 61372 30778 61372 30762 61373 30773 61373 30774 61373 30774 61374 30773 61374 30802 61374 30774 61375 30802 61375 30775 61375 30775 61376 30802 61376 30776 61376 30775 61377 30776 61377 30777 61377 30777 61378 30776 61378 30778 61378 30777 61379 30778 61379 30806 61379 30779 61380 30760 61380 30768 61380 30768 61381 30760 61381 30780 61381 30768 61382 30780 61382 30770 61382 30770 61383 30780 61383 30775 61383 30770 61384 30775 61384 30781 61384 30781 61385 30775 61385 30777 61385 30781 61386 30777 61386 30782 61386 30782 61387 30777 61387 30806 61387 30782 61388 30806 61388 30807 61388 30728 61389 30730 61389 30784 61389 30784 61390 30730 61390 30783 61390 30784 61391 30783 61391 30785 61391 30786 61392 30793 61392 30787 61392 30787 61393 30793 61393 30795 61393 30787 61394 30795 61394 30750 61394 30750 61395 30795 61395 30788 61395 30750 61396 30788 61396 30744 61396 30744 61397 30788 61397 30797 61397 30744 61398 30797 61398 30789 61398 30789 61399 30797 61399 30798 61399 30789 61400 30798 61400 30731 61400 30731 61401 30798 61401 30732 61401 30785 61402 30729 61402 30784 61402 30784 61403 30729 61403 30759 61403 30784 61404 30759 61404 30808 61404 30808 61405 30759 61405 30790 61405 30808 61406 30790 61406 30792 61406 30792 61407 30790 61407 30791 61407 30792 61408 30791 61408 30810 61408 30810 61409 30791 61409 30796 61409 30810 61410 30796 61410 30794 61410 30793 61411 30794 61411 30795 61411 30795 61412 30794 61412 30796 61412 30795 61413 30796 61413 30788 61413 30788 61414 30796 61414 30791 61414 30788 61415 30791 61415 30797 61415 30797 61416 30791 61416 30790 61416 30797 61417 30790 61417 30798 61417 30798 61418 30790 61418 30759 61418 30798 61419 30759 61419 30732 61419 30732 61420 30759 61420 30799 61420 30800 61421 30724 61421 30801 61421 30801 61422 30724 61422 30776 61422 30801 61423 30776 61423 30886 61423 30886 61424 30776 61424 30802 61424 30886 61425 30802 61425 30876 61425 30876 61426 30802 61426 30773 61426 30876 61427 30773 61427 30877 61427 30877 61428 30773 61428 30803 61428 30877 61429 30803 61429 30804 61429 30772 61430 30805 61430 30778 61430 30778 61431 30805 61431 30726 61431 30778 61432 30726 61432 30806 61432 30806 61433 30726 61433 30728 61433 30806 61434 30728 61434 30807 61434 30807 61435 30728 61435 30784 61435 30807 61436 30784 61436 30771 61436 30771 61437 30784 61437 30808 61437 30771 61438 30808 61438 30809 61438 30809 61439 30808 61439 30792 61439 30809 61440 30792 61440 30769 61440 30769 61441 30792 61441 30810 61441 30769 61442 30810 61442 30811 61442 30811 61443 30810 61443 30794 61443 30811 61444 30794 61444 30812 61444 30812 61445 30794 61445 30793 61445 30812 61446 30793 61446 30765 61446 30765 61447 30793 61447 30786 61447 30765 61448 30786 61448 30767 61448 30688 61449 30757 61449 30843 61449 30863 61450 30861 61450 30821 61450 30858 61451 30881 61451 30845 61451 30827 61452 30813 61452 30815 61452 30815 61453 30813 61453 30814 61453 30815 61454 30814 61454 30816 61454 30816 61455 30814 61455 30743 61455 30816 61456 30743 61456 30828 61456 30846 61457 30845 61457 30817 61457 30872 61458 30873 61458 30820 61458 30820 61459 30873 61459 30818 61459 30820 61460 30818 61460 30819 61460 30819 61461 30818 61461 30874 61461 30819 61462 30874 61462 30821 61462 30821 61463 30861 61463 30819 61463 30819 61464 30861 61464 30860 61464 30819 61465 30860 61465 30820 61465 30874 61466 30822 61466 30821 61466 30821 61467 30822 61467 30823 61467 30821 61468 30823 61468 30863 61468 30863 61469 30823 61469 30824 61469 30863 61470 30824 61470 30864 61470 30864 61471 30824 61471 30825 61471 30864 61472 30825 61472 30826 61472 30826 61473 30825 61473 30829 61473 30826 61474 30829 61474 30753 61474 30822 61475 30827 61475 30823 61475 30823 61476 30827 61476 30815 61476 30823 61477 30815 61477 30824 61477 30824 61478 30815 61478 30816 61478 30824 61479 30816 61479 30825 61479 30825 61480 30816 61480 30828 61480 30825 61481 30828 61481 30829 61481 30855 61482 30737 61482 30738 61482 30855 61483 30738 61483 30856 61483 30737 61484 30855 61484 30830 61484 30830 61485 30855 61485 30836 61485 30830 61486 30836 61486 30831 61486 30734 61487 30833 61487 30832 61487 30832 61488 30833 61488 30834 61488 30832 61489 30834 61489 30836 61489 30836 61490 30834 61490 30835 61490 30836 61491 30835 61491 30831 61491 30721 61492 30734 61492 30837 61492 30837 61493 30734 61493 30832 61493 30837 61494 30832 61494 30838 61494 30839 61495 30840 61495 30742 61495 30742 61496 30840 61496 30841 61496 30742 61497 30841 61497 30740 61497 30740 61498 30841 61498 30856 61498 30740 61499 30856 61499 30842 61499 30842 61500 30856 61500 30738 61500 30839 61501 30686 61501 30840 61501 30840 61502 30686 61502 30688 61502 30840 61503 30688 61503 30844 61503 30844 61504 30688 61504 30843 61504 30844 61505 30843 61505 30887 61505 30845 61506 30846 61506 30858 61506 30858 61507 30846 61507 30859 61507 30858 61508 30859 61508 30847 61508 30847 61509 30859 61509 30862 61509 30847 61510 30862 61510 30848 61510 30848 61511 30862 61511 30849 61511 30848 61512 30849 61512 30857 61512 30857 61513 30849 61513 30851 61513 30857 61514 30851 61514 30850 61514 30850 61515 30851 61515 30865 61515 30850 61516 30865 61516 30852 61516 30852 61517 30865 61517 30866 61517 30852 61518 30866 61518 30853 61518 30853 61519 30866 61519 30854 61519 30853 61520 30854 61520 30838 61520 30838 61521 30832 61521 30853 61521 30853 61522 30832 61522 30836 61522 30853 61523 30836 61523 30852 61523 30852 61524 30836 61524 30855 61524 30852 61525 30855 61525 30850 61525 30850 61526 30855 61526 30856 61526 30850 61527 30856 61527 30857 61527 30857 61528 30856 61528 30841 61528 30857 61529 30841 61529 30848 61529 30848 61530 30841 61530 30840 61530 30848 61531 30840 61531 30847 61531 30847 61532 30840 61532 30844 61532 30847 61533 30844 61533 30858 61533 30858 61534 30844 61534 30887 61534 30858 61535 30887 61535 30881 61535 30817 61536 30872 61536 30846 61536 30846 61537 30872 61537 30820 61537 30846 61538 30820 61538 30859 61538 30859 61539 30820 61539 30860 61539 30859 61540 30860 61540 30862 61540 30862 61541 30860 61541 30861 61541 30862 61542 30861 61542 30849 61542 30849 61543 30861 61543 30863 61543 30849 61544 30863 61544 30851 61544 30851 61545 30863 61545 30864 61545 30851 61546 30864 61546 30865 61546 30865 61547 30864 61547 30826 61547 30865 61548 30826 61548 30866 61548 30866 61549 30826 61549 30753 61549 30866 61550 30753 61550 30854 61550 30867 61551 30817 61551 30880 61551 30868 61552 30869 61552 30870 61552 30766 61553 30869 61553 30763 61553 30763 61554 30869 61554 30868 61554 30763 61555 30868 61555 30764 61555 30764 61556 30868 61556 30871 61556 30803 61557 30762 61557 30868 61557 30868 61558 30762 61558 30761 61558 30761 61559 30760 61559 30868 61559 30868 61560 30760 61560 30779 61560 30868 61561 30779 61561 30871 61561 30827 61562 30822 61562 30867 61562 30867 61563 30822 61563 30874 61563 30872 61564 30817 61564 30873 61564 30873 61565 30817 61565 30867 61565 30873 61566 30867 61566 30818 61566 30818 61567 30867 61567 30874 61567 30743 61568 30814 61568 30867 61568 30867 61569 30814 61569 30813 61569 30867 61570 30813 61570 30827 61570 30743 61571 30867 61571 30756 61571 30756 61572 30867 61572 30880 61572 30756 61573 30880 61573 30754 61573 30754 61574 30880 61574 30875 61574 30754 61575 30875 61575 30870 61575 30870 61576 30875 61576 30878 61576 30870 61577 30878 61577 30868 61577 30868 61578 30878 61578 30804 61578 30868 61579 30804 61579 30803 61579 30843 61580 30757 61580 30888 61580 30881 61581 30887 61581 30882 61581 30801 61582 30886 61582 30890 61582 30876 61583 30877 61583 30885 61583 30877 61584 30804 61584 30885 61584 30885 61585 30804 61585 30878 61585 30885 61586 30878 61586 30883 61586 30883 61587 30878 61587 30875 61587 30883 61588 30875 61588 30879 61588 30879 61589 30875 61589 30880 61589 30879 61590 30880 61590 30845 61590 30845 61591 30880 61591 30817 61591 30845 61592 30881 61592 30879 61592 30879 61593 30881 61593 30882 61593 30879 61594 30882 61594 30883 61594 30883 61595 30882 61595 30884 61595 30883 61596 30884 61596 30885 61596 30885 61597 30884 61597 30890 61597 30885 61598 30890 61598 30876 61598 30876 61599 30890 61599 30886 61599 30887 61600 30843 61600 30882 61600 30882 61601 30843 61601 30888 61601 30882 61602 30888 61602 30884 61602 30884 61603 30888 61603 30889 61603 30884 61604 30889 61604 30890 61604 30890 61605 30889 61605 30891 61605 30890 61606 30891 61606 30801 61606 30801 61607 30891 61607 30800 61607 30892 61608 30707 61608 30530 61608 30892 61609 30530 61609 30893 61609 30530 61610 30528 61610 30893 61610 30893 61611 30528 61611 30894 61611 30893 61612 30894 61612 30511 61612 30511 61613 30894 61613 30712 61613 30712 61614 30894 61614 30895 61614 30712 61615 30895 61615 30492 61615 30524 61616 30896 61616 30525 61616 30525 61617 30896 61617 30719 61617 30525 61618 30719 61618 30897 61618 30897 61619 30719 61619 30898 61619 30897 61620 30898 61620 30513 61620 30513 61621 30898 61621 30502 61621 31184 61622 30916 61622 30899 61622 30899 61623 30916 61623 30917 61623 30899 61624 30917 61624 31180 61624 30900 61625 30902 61625 30901 61625 30901 61626 30902 61626 30903 61626 30901 61627 30903 61627 30917 61627 30917 61628 30903 61628 31179 61628 30917 61629 31179 61629 31180 61629 30900 61630 30901 61630 30904 61630 30904 61631 30901 61631 30919 61631 30904 61632 30919 61632 30905 61632 30905 61633 30919 61633 30906 61633 30905 61634 30906 61634 30907 61634 30907 61635 30906 61635 30908 61635 30907 61636 30908 61636 30909 61636 30908 61637 30910 61637 30909 61637 30909 61638 30910 61638 30911 61638 30909 61639 30911 61639 31163 61639 31163 61640 30911 61640 30912 61640 31163 61641 30912 61641 30913 61641 31271 61642 30912 61642 31267 61642 31267 61643 30912 61643 30911 61643 31267 61644 30911 61644 30914 61644 30914 61645 30911 61645 30910 61645 30910 61646 30908 61646 30914 61646 30914 61647 30908 61647 30906 61647 30914 61648 30906 61648 30915 61648 30916 61649 31086 61649 30917 61649 30917 61650 31086 61650 30918 61650 30917 61651 30918 61651 30901 61651 30901 61652 30918 61652 30915 61652 30901 61653 30915 61653 30919 61653 30919 61654 30915 61654 30906 61654 30920 61655 30921 61655 31251 61655 31251 61656 30921 61656 30922 61656 31251 61657 30922 61657 31017 61657 31251 61658 30923 61658 30920 61658 30920 61659 30923 61659 31276 61659 30936 61660 31011 61660 30999 61660 31011 61661 30936 61661 30924 61661 30928 61662 30931 61662 30933 61662 30969 61663 30925 61663 30926 61663 30967 61664 30927 61664 30928 61664 30928 61665 30927 61665 30969 61665 30969 61666 30926 61666 30928 61666 30928 61667 30926 61667 30929 61667 30928 61668 30929 61668 30931 61668 30931 61669 30929 61669 31284 61669 30931 61670 31284 61670 31015 61670 30935 61671 30965 61671 30930 61671 30930 61672 30965 61672 30967 61672 31015 61673 31016 61673 30931 61673 30931 61674 31016 61674 31029 61674 30931 61675 31029 61675 30933 61675 30933 61676 31029 61676 30932 61676 30933 61677 30932 61677 30934 61677 30947 61678 30935 61678 30938 61678 30938 61679 30935 61679 30930 61679 30938 61680 30930 61680 30936 61680 30967 61681 30928 61681 30930 61681 30930 61682 30928 61682 30933 61682 30930 61683 30933 61683 30936 61683 30936 61684 30933 61684 30934 61684 30936 61685 30934 61685 30924 61685 31042 61686 30947 61686 30937 61686 30937 61687 30947 61687 30938 61687 30937 61688 30938 61688 31053 61688 31053 61689 30938 61689 30936 61689 31053 61690 30936 61690 30939 61690 30939 61691 30936 61691 30999 61691 30940 61692 30921 61692 30920 61692 30940 61693 30920 61693 30941 61693 30941 61694 30920 61694 30942 61694 30941 61695 30942 61695 31069 61695 31069 61696 30942 61696 31285 61696 31069 61697 31285 61697 30983 61697 30971 61698 31297 61698 30972 61698 30961 61699 30943 61699 30957 61699 30949 61700 31045 61700 30951 61700 31043 61701 30987 61701 30986 61701 30961 61702 30960 61702 30943 61702 30943 61703 30960 61703 30944 61703 30943 61704 30944 61704 31043 61704 30946 61705 30945 61705 30993 61705 30993 61706 30945 61706 30948 61706 30993 61707 30948 61707 30950 61707 30993 61708 30994 61708 30946 61708 30946 61709 30994 61709 30947 61709 30946 61710 30947 61710 31042 61710 30948 61711 30949 61711 30950 61711 30950 61712 30949 61712 30951 61712 30950 61713 30951 61713 30992 61713 30992 61714 30951 61714 30952 61714 30992 61715 30952 61715 30953 61715 30953 61716 30952 61716 30962 61716 30953 61717 30962 61717 30991 61717 30991 61718 30962 61718 30963 61718 30991 61719 30963 61719 30954 61719 30955 61720 30988 61720 30985 61720 30985 61721 30988 61721 30958 61721 31043 61722 30986 61722 30943 61722 30943 61723 30986 61723 30956 61723 30943 61724 30956 61724 30957 61724 30957 61725 30956 61725 30985 61725 30957 61726 30985 61726 30959 61726 30959 61727 30985 61727 30958 61727 30959 61728 30958 61728 30989 61728 31045 61729 30960 61729 30951 61729 30951 61730 30960 61730 30961 61730 30951 61731 30961 61731 30952 61731 30952 61732 30961 61732 30957 61732 30952 61733 30957 61733 30962 61733 30962 61734 30957 61734 30959 61734 30962 61735 30959 61735 30963 61735 30963 61736 30959 61736 30989 61736 30963 61737 30989 61737 30954 61737 31293 61738 31294 61738 30990 61738 30990 61739 31294 61739 30964 61739 30990 61740 30964 61740 31295 61740 30935 61741 30978 61741 30965 61741 30965 61742 30978 61742 30966 61742 30965 61743 30966 61743 30967 61743 30967 61744 30966 61744 30979 61744 30967 61745 30979 61745 30927 61745 30927 61746 30979 61746 30968 61746 30927 61747 30968 61747 30969 61747 30969 61748 30968 61748 30982 61748 30969 61749 30982 61749 30925 61749 30925 61750 30982 61750 30970 61750 31295 61751 30971 61751 30990 61751 30990 61752 30971 61752 30972 61752 30990 61753 30972 61753 30973 61753 30973 61754 30972 61754 30981 61754 30973 61755 30981 61755 30974 61755 30974 61756 30981 61756 30980 61756 30974 61757 30980 61757 30976 61757 30976 61758 30980 61758 30975 61758 30976 61759 30975 61759 30977 61759 30978 61760 30977 61760 30966 61760 30966 61761 30977 61761 30975 61761 30966 61762 30975 61762 30979 61762 30979 61763 30975 61763 30980 61763 30979 61764 30980 61764 30968 61764 30968 61765 30980 61765 30981 61765 30968 61766 30981 61766 30982 61766 30982 61767 30981 61767 30972 61767 30982 61768 30972 61768 30970 61768 30970 61769 30972 61769 31297 61769 30983 61770 30955 61770 30984 61770 30984 61771 30955 61771 30985 61771 30984 61772 30985 61772 31054 61772 31054 61773 30985 61773 30956 61773 31054 61774 30956 61774 31055 61774 31055 61775 30956 61775 30986 61775 31055 61776 30986 61776 31056 61776 31056 61777 30986 61777 30987 61777 31056 61778 30987 61778 31057 61778 30988 61779 31290 61779 30958 61779 30958 61780 31290 61780 31291 61780 30958 61781 31291 61781 30989 61781 30989 61782 31291 61782 31293 61782 30989 61783 31293 61783 30954 61783 30954 61784 31293 61784 30990 61784 30954 61785 30990 61785 30991 61785 30991 61786 30990 61786 30973 61786 30991 61787 30973 61787 30953 61787 30953 61788 30973 61788 30974 61788 30953 61789 30974 61789 30992 61789 30992 61790 30974 61790 30976 61790 30992 61791 30976 61791 30950 61791 30950 61792 30976 61792 30977 61792 30950 61793 30977 61793 30993 61793 30993 61794 30977 61794 30978 61794 30993 61795 30978 61795 30994 61795 30994 61796 30978 61796 30935 61796 30994 61797 30935 61797 30947 61797 30922 61798 30921 61798 31066 61798 31005 61799 30995 61799 31004 61799 31037 61800 31061 61800 31060 61800 31009 61801 30996 61801 30997 61801 30997 61802 30996 61802 31051 61802 30997 61803 31051 61803 30998 61803 30998 61804 31051 61804 30999 61804 30998 61805 30999 61805 31011 61805 31038 61806 31060 61806 31000 61806 31039 61807 31047 61807 31003 61807 31003 61808 31047 61808 31049 61808 31003 61809 31049 61809 31001 61809 31001 61810 31049 61810 31050 61810 31001 61811 31050 61811 31004 61811 31004 61812 30995 61812 31001 61812 31001 61813 30995 61813 31002 61813 31001 61814 31002 61814 31003 61814 31050 61815 31046 61815 31004 61815 31004 61816 31046 61816 31010 61816 31004 61817 31010 61817 31005 61817 31005 61818 31010 61818 31006 61818 31005 61819 31006 61819 31007 61819 31007 61820 31006 61820 31012 61820 31007 61821 31012 61821 31008 61821 31008 61822 31012 61822 30924 61822 31008 61823 30924 61823 30934 61823 31046 61824 31009 61824 31010 61824 31010 61825 31009 61825 30997 61825 31010 61826 30997 61826 31006 61826 31006 61827 30997 61827 30998 61827 31006 61828 30998 61828 31012 61828 31012 61829 30998 61829 31011 61829 31012 61830 31011 61830 30924 61830 31032 61831 31302 61831 31304 61831 31032 61832 31304 61832 31033 61832 31302 61833 31032 61833 31301 61833 31301 61834 31032 61834 31013 61834 31301 61835 31013 61835 31014 61835 31014 61836 31013 61836 31030 61836 31014 61837 31030 61837 31298 61837 31015 61838 31298 61838 31016 61838 31016 61839 31298 61839 31030 61839 31016 61840 31030 61840 31029 61840 30922 61841 31066 61841 31017 61841 31306 61842 31018 61842 31019 61842 31019 61843 31020 61843 31306 61843 31306 61844 31020 61844 31033 61844 31306 61845 31033 61845 31305 61845 31305 61846 31033 61846 31304 61846 31018 61847 31309 61847 31019 61847 31019 61848 31309 61848 31017 61848 31019 61849 31017 61849 31021 61849 31021 61850 31017 61850 31066 61850 31021 61851 31066 61851 31022 61851 31060 61852 31038 61852 31037 61852 31037 61853 31038 61853 31023 61853 31037 61854 31023 61854 31036 61854 31036 61855 31023 61855 31040 61855 31036 61856 31040 61856 31035 61856 31035 61857 31040 61857 31024 61857 31035 61858 31024 61858 31034 61858 31034 61859 31024 61859 31025 61859 31034 61860 31025 61860 31026 61860 31026 61861 31025 61861 31027 61861 31026 61862 31027 61862 31031 61862 31031 61863 31027 61863 31041 61863 31031 61864 31041 61864 31028 61864 31028 61865 31041 61865 30932 61865 31028 61866 30932 61866 31029 61866 31029 61867 31030 61867 31028 61867 31028 61868 31030 61868 31013 61868 31028 61869 31013 61869 31031 61869 31031 61870 31013 61870 31032 61870 31031 61871 31032 61871 31026 61871 31026 61872 31032 61872 31033 61872 31026 61873 31033 61873 31034 61873 31034 61874 31033 61874 31020 61874 31034 61875 31020 61875 31035 61875 31035 61876 31020 61876 31019 61876 31035 61877 31019 61877 31036 61877 31036 61878 31019 61878 31021 61878 31036 61879 31021 61879 31037 61879 31037 61880 31021 61880 31022 61880 31037 61881 31022 61881 31061 61881 31000 61882 31039 61882 31038 61882 31038 61883 31039 61883 31003 61883 31038 61884 31003 61884 31023 61884 31023 61885 31003 61885 31002 61885 31023 61886 31002 61886 31040 61886 31040 61887 31002 61887 30995 61887 31040 61888 30995 61888 31024 61888 31024 61889 30995 61889 31005 61889 31024 61890 31005 61890 31025 61890 31025 61891 31005 61891 31007 61891 31025 61892 31007 61892 31027 61892 31027 61893 31007 61893 31008 61893 31027 61894 31008 61894 31041 61894 31041 61895 31008 61895 30934 61895 31041 61896 30934 61896 30932 61896 31048 61897 31000 61897 31052 61897 31044 61898 31042 61898 30937 61898 30946 61899 31042 61899 30945 61899 30945 61900 31042 61900 31044 61900 30945 61901 31044 61901 30948 61901 30948 61902 31044 61902 30949 61902 30987 61903 31043 61903 31044 61903 31044 61904 31043 61904 30944 61904 30944 61905 30960 61905 31044 61905 31044 61906 30960 61906 31045 61906 31044 61907 31045 61907 30949 61907 31009 61908 31046 61908 31048 61908 31048 61909 31046 61909 31050 61909 31039 61910 31000 61910 31047 61910 31047 61911 31000 61911 31048 61911 31047 61912 31048 61912 31049 61912 31049 61913 31048 61913 31050 61913 30999 61914 31051 61914 31048 61914 31048 61915 31051 61915 30996 61915 31048 61916 30996 61916 31009 61916 30999 61917 31048 61917 30939 61917 30939 61918 31048 61918 31052 61918 30939 61919 31052 61919 31053 61919 31053 61920 31052 61920 31059 61920 31053 61921 31059 61921 30937 61921 30937 61922 31059 61922 31058 61922 30937 61923 31058 61923 31044 61923 31044 61924 31058 61924 31057 61924 31044 61925 31057 61925 30987 61925 31066 61926 30921 61926 30940 61926 31061 61927 31022 61927 31067 61927 30984 61928 31054 61928 31065 61928 31055 61929 31056 61929 31064 61929 31056 61930 31057 61930 31064 61930 31064 61931 31057 61931 31058 61931 31064 61932 31058 61932 31063 61932 31063 61933 31058 61933 31059 61933 31063 61934 31059 61934 31062 61934 31062 61935 31059 61935 31052 61935 31062 61936 31052 61936 31060 61936 31060 61937 31052 61937 31000 61937 31060 61938 31061 61938 31062 61938 31062 61939 31061 61939 31067 61939 31062 61940 31067 61940 31063 61940 31063 61941 31067 61941 31068 61941 31063 61942 31068 61942 31064 61942 31064 61943 31068 61943 31065 61943 31064 61944 31065 61944 31055 61944 31055 61945 31065 61945 31054 61945 31022 61946 31066 61946 31067 61946 31067 61947 31066 61947 30940 61947 31067 61948 30940 61948 31068 61948 31068 61949 30940 61949 30941 61949 31068 61950 30941 61950 31065 61950 31065 61951 30941 61951 31069 61951 31065 61952 31069 61952 30984 61952 30984 61953 31069 61953 30983 61953 31269 61954 31070 61954 31108 61954 31269 61955 31108 61955 31072 61955 31108 61956 31071 61956 31072 61956 31072 61957 31071 61957 31106 61957 31072 61958 31106 61958 31073 61958 31073 61959 31106 61959 31074 61959 31074 61960 31106 61960 31105 61960 31074 61961 31105 61961 31265 61961 30912 61962 31271 61962 31075 61962 31075 61963 31271 61963 31273 61963 31075 61964 31273 61964 31076 61964 31076 61965 31273 61965 31274 61965 31076 61966 31274 61966 31089 61966 31089 61967 31274 61967 31275 61967 31265 61968 31105 61968 31077 61968 31077 61969 31105 61969 31098 61969 31077 61970 31098 61970 31078 61970 31098 61971 31099 61971 31078 61971 31078 61972 31099 61972 31079 61972 31078 61973 31079 61973 31280 61973 31280 61974 31079 61974 31094 61974 31280 61975 31094 61975 31080 61975 31080 61976 31094 61976 31093 61976 31080 61977 31093 61977 31278 61977 31089 61978 31275 61978 31081 61978 31081 61979 31275 61979 31082 61979 31081 61980 31082 61980 31083 61980 31083 61981 31082 61981 31278 61981 31083 61982 31278 61982 31084 61982 31084 61983 31278 61983 31093 61983 31108 61984 31070 61984 31101 61984 31101 61985 31070 61985 31085 61985 31101 61986 31085 61986 30916 61986 30916 61987 31085 61987 31086 61987 31073 61988 31074 61988 31257 61988 31258 61989 31269 61989 31087 61989 31087 61990 31269 61990 31072 61990 31087 61991 31072 61991 31088 61991 31088 61992 31072 61992 31073 61992 31088 61993 31073 61993 31281 61993 31281 61994 31073 61994 31257 61994 31098 61995 31105 61995 31130 61995 31104 61996 31089 61996 31126 61996 31126 61997 31089 61997 31081 61997 31126 61998 31081 61998 31090 61998 31090 61999 31081 61999 31091 61999 31081 62000 31083 62000 31091 62000 31091 62001 31083 62001 31084 62001 31091 62002 31084 62002 31092 62002 31092 62003 31084 62003 31093 62003 31092 62004 31093 62004 31133 62004 31133 62005 31093 62005 31134 62005 31134 62006 31093 62006 31094 62006 31134 62007 31094 62007 31097 62007 31095 62008 31132 62008 31079 62008 31079 62009 31132 62009 31096 62009 31079 62010 31096 62010 31094 62010 31094 62011 31096 62011 31135 62011 31094 62012 31135 62012 31097 62012 31130 62013 31128 62013 31098 62013 31098 62014 31128 62014 31095 62014 31098 62015 31095 62015 31099 62015 31099 62016 31095 62016 31079 62016 31183 62017 31100 62017 31108 62017 31108 62018 31101 62018 31183 62018 31183 62019 31101 62019 30916 62019 31183 62020 30916 62020 31184 62020 30913 62021 30912 62021 31102 62021 31102 62022 30912 62022 31075 62022 31102 62023 31075 62023 31103 62023 31103 62024 31075 62024 31076 62024 31103 62025 31076 62025 31104 62025 31104 62026 31076 62026 31089 62026 31130 62027 31105 62027 31106 62027 31130 62028 31106 62028 31236 62028 31236 62029 31106 62029 31071 62029 31236 62030 31071 62030 31107 62030 31107 62031 31071 62031 31108 62031 31107 62032 31108 62032 31100 62032 31239 62033 31213 62033 31109 62033 31124 62034 31239 62034 31148 62034 31116 62035 31115 62035 31110 62035 31110 62036 31115 62036 31118 62036 31110 62037 31118 62037 31111 62037 31111 62038 31118 62038 31112 62038 31111 62039 31112 62039 31238 62039 31238 62040 31112 62040 31225 62040 31119 62041 31230 62041 31120 62041 31160 62042 31161 62042 31117 62042 31117 62043 31161 62043 31162 62043 31117 62044 31162 62044 31119 62044 31119 62045 31162 62045 31113 62045 31119 62046 31113 62046 31230 62046 31122 62047 31115 62047 31114 62047 31114 62048 31115 62048 31116 62048 31114 62049 31116 62049 31240 62049 31122 62050 31160 62050 31115 62050 31115 62051 31160 62051 31117 62051 31115 62052 31117 62052 31118 62052 31118 62053 31117 62053 31119 62053 31118 62054 31119 62054 31112 62054 31112 62055 31119 62055 31120 62055 31112 62056 31120 62056 31225 62056 31152 62057 31121 62057 31122 62057 31122 62058 31121 62058 31158 62058 31122 62059 31158 62059 31160 62059 31151 62060 31124 62060 31123 62060 31123 62061 31124 62061 31148 62061 31123 62062 31148 62062 31153 62062 31153 62063 31148 62063 31150 62063 31125 62064 31155 62064 31142 62064 31090 62065 31156 62065 31126 62065 31126 62066 31156 62066 31127 62066 31126 62067 31127 62067 31104 62067 31131 62068 31128 62068 31129 62068 31129 62069 31128 62069 31130 62069 31129 62070 31130 62070 31237 62070 31135 62071 31096 62071 31145 62071 31145 62072 31096 62072 31132 62072 31145 62073 31132 62073 31131 62073 31131 62074 31132 62074 31095 62074 31131 62075 31095 62075 31128 62075 31090 62076 31091 62076 31155 62076 31155 62077 31091 62077 31092 62077 31155 62078 31092 62078 31142 62078 31142 62079 31092 62079 31133 62079 31142 62080 31133 62080 31143 62080 31143 62081 31133 62081 31134 62081 31143 62082 31134 62082 31145 62082 31145 62083 31134 62083 31097 62083 31145 62084 31097 62084 31135 62084 31125 62085 31136 62085 31157 62085 31157 62086 31136 62086 31144 62086 31157 62087 31144 62087 31137 62087 31137 62088 31144 62088 31138 62088 31137 62089 31138 62089 31159 62089 31159 62090 31138 62090 31146 62090 31159 62091 31146 62091 31139 62091 31139 62092 31146 62092 31140 62092 31139 62093 31140 62093 31141 62093 31141 62094 31140 62094 31147 62094 31141 62095 31147 62095 31232 62095 31125 62096 31142 62096 31136 62096 31136 62097 31142 62097 31143 62097 31136 62098 31143 62098 31144 62098 31144 62099 31143 62099 31145 62099 31144 62100 31145 62100 31138 62100 31138 62101 31145 62101 31131 62101 31138 62102 31131 62102 31146 62102 31146 62103 31131 62103 31129 62103 31146 62104 31129 62104 31140 62104 31140 62105 31129 62105 31237 62105 31140 62106 31237 62106 31147 62106 31239 62107 31109 62107 31148 62107 31148 62108 31109 62108 31149 62108 31148 62109 31149 62109 31150 62109 31150 62110 31149 62110 31220 62110 31150 62111 31220 62111 31154 62111 31240 62112 31151 62112 31114 62112 31114 62113 31151 62113 31123 62113 31114 62114 31123 62114 31122 62114 31122 62115 31123 62115 31153 62115 31122 62116 31153 62116 31152 62116 31152 62117 31153 62117 31150 62117 31152 62118 31150 62118 31156 62118 31156 62119 31150 62119 31154 62119 31156 62120 31154 62120 31127 62120 31090 62121 31155 62121 31156 62121 31156 62122 31155 62122 31125 62122 31156 62123 31125 62123 31152 62123 31152 62124 31125 62124 31157 62124 31152 62125 31157 62125 31121 62125 31121 62126 31157 62126 31137 62126 31121 62127 31137 62127 31158 62127 31158 62128 31137 62128 31159 62128 31158 62129 31159 62129 31160 62129 31160 62130 31159 62130 31139 62130 31160 62131 31139 62131 31161 62131 31161 62132 31139 62132 31141 62132 31161 62133 31141 62133 31162 62133 31162 62134 31141 62134 31232 62134 31162 62135 31232 62135 31113 62135 31163 62136 30913 62136 31219 62136 31222 62137 31100 62137 31183 62137 31206 62138 31204 62138 31169 62138 31164 62139 31165 62139 31166 62139 31224 62140 31178 62140 31243 62140 31243 62141 31178 62141 31177 62141 31243 62142 31177 62142 31244 62142 31244 62143 31177 62143 31176 62143 31244 62144 31176 62144 31167 62144 31199 62145 31166 62145 31241 62145 31198 62146 31242 62146 31200 62146 31200 62147 31242 62147 31168 62147 31168 62148 31242 62148 31170 62148 31168 62149 31170 62149 31169 62149 31169 62150 31204 62150 31168 62150 31168 62151 31204 62151 31201 62151 31168 62152 31201 62152 31200 62152 31170 62153 31171 62153 31169 62153 31169 62154 31171 62154 31172 62154 31169 62155 31172 62155 31206 62155 31206 62156 31172 62156 31175 62156 31206 62157 31175 62157 31208 62157 31208 62158 31175 62158 31173 62158 31208 62159 31173 62159 31210 62159 31210 62160 31173 62160 31174 62160 31210 62161 31174 62161 31228 62161 31171 62162 31167 62162 31172 62162 31172 62163 31167 62163 31176 62163 31172 62164 31176 62164 31175 62164 31175 62165 31176 62165 31177 62165 31175 62166 31177 62166 31173 62166 31173 62167 31177 62167 31178 62167 31173 62168 31178 62168 31174 62168 30902 62169 31194 62169 30903 62169 30903 62170 31194 62170 31181 62170 30903 62171 31181 62171 31179 62171 31179 62172 31181 62172 31180 62172 31180 62173 31181 62173 31193 62173 31180 62174 31193 62174 30899 62174 31234 62175 31222 62175 31182 62175 31182 62176 31222 62176 31183 62176 31182 62177 31183 62177 31193 62177 31193 62178 31183 62178 31184 62178 31193 62179 31184 62179 30899 62179 30907 62180 31186 62180 30905 62180 30905 62181 31186 62181 31185 62181 30905 62182 31185 62182 30904 62182 30904 62183 31185 62183 31194 62183 30904 62184 31194 62184 30900 62184 30900 62185 31194 62185 30902 62185 30907 62186 30909 62186 31186 62186 31186 62187 30909 62187 31163 62187 31186 62188 31163 62188 31196 62188 31196 62189 31163 62189 31219 62189 31196 62190 31219 62190 31197 62190 31166 62191 31199 62191 31164 62191 31164 62192 31199 62192 31202 62192 31164 62193 31202 62193 31195 62193 31195 62194 31202 62194 31203 62194 31195 62195 31203 62195 31187 62195 31187 62196 31203 62196 31205 62196 31187 62197 31205 62197 31188 62197 31188 62198 31205 62198 31207 62198 31188 62199 31207 62199 31189 62199 31189 62200 31207 62200 31209 62200 31189 62201 31209 62201 31190 62201 31190 62202 31209 62202 31211 62202 31190 62203 31211 62203 31191 62203 31191 62204 31211 62204 31192 62204 31191 62205 31192 62205 31234 62205 31234 62206 31182 62206 31191 62206 31191 62207 31182 62207 31193 62207 31191 62208 31193 62208 31190 62208 31190 62209 31193 62209 31181 62209 31190 62210 31181 62210 31189 62210 31189 62211 31181 62211 31194 62211 31189 62212 31194 62212 31188 62212 31188 62213 31194 62213 31185 62213 31188 62214 31185 62214 31187 62214 31187 62215 31185 62215 31186 62215 31187 62216 31186 62216 31195 62216 31195 62217 31186 62217 31196 62217 31195 62218 31196 62218 31164 62218 31164 62219 31196 62219 31197 62219 31164 62220 31197 62220 31165 62220 31241 62221 31198 62221 31199 62221 31199 62222 31198 62222 31200 62222 31199 62223 31200 62223 31202 62223 31202 62224 31200 62224 31201 62224 31202 62225 31201 62225 31203 62225 31203 62226 31201 62226 31204 62226 31203 62227 31204 62227 31205 62227 31205 62228 31204 62228 31206 62228 31205 62229 31206 62229 31207 62229 31207 62230 31206 62230 31208 62230 31207 62231 31208 62231 31209 62231 31209 62232 31208 62232 31210 62232 31209 62233 31210 62233 31211 62233 31211 62234 31210 62234 31228 62234 31211 62235 31228 62235 31192 62235 31212 62236 31215 62236 31221 62236 31218 62237 31241 62237 31166 62237 31109 62238 31213 62238 31214 62238 31220 62239 31149 62239 31212 62239 31212 62240 31149 62240 31109 62240 31109 62241 31214 62241 31212 62241 31212 62242 31214 62242 31248 62242 31212 62243 31248 62243 31215 62243 31215 62244 31248 62244 31216 62244 31215 62245 31216 62245 31218 62245 31127 62246 31154 62246 31217 62246 31217 62247 31154 62247 31220 62247 31104 62248 31127 62248 31103 62248 31103 62249 31127 62249 31217 62249 31103 62250 31217 62250 31102 62250 31218 62251 31166 62251 31215 62251 31215 62252 31166 62252 31165 62252 31215 62253 31165 62253 31221 62253 31221 62254 31165 62254 31197 62254 31221 62255 31197 62255 31219 62255 31220 62256 31212 62256 31217 62256 31217 62257 31212 62257 31221 62257 31217 62258 31221 62258 31102 62258 31102 62259 31221 62259 31219 62259 31102 62260 31219 62260 30913 62260 31222 62261 31234 62261 31229 62261 31247 62262 31223 62262 31226 62262 31224 62263 31246 62263 31178 62263 31178 62264 31246 62264 31227 62264 31238 62265 31225 62265 31249 62265 31249 62266 31225 62266 31223 62266 31233 62267 31235 62267 31231 62267 31231 62268 31235 62268 31227 62268 31223 62269 31225 62269 31226 62269 31226 62270 31225 62270 31120 62270 31226 62271 31120 62271 31230 62271 31246 62272 31247 62272 31227 62272 31227 62273 31247 62273 31226 62273 31227 62274 31226 62274 31231 62274 31231 62275 31226 62275 31230 62275 31234 62276 31192 62276 31235 62276 31235 62277 31192 62277 31228 62277 31235 62278 31228 62278 31227 62278 31227 62279 31228 62279 31174 62279 31227 62280 31174 62280 31178 62280 31236 62281 31107 62281 31229 62281 31229 62282 31107 62282 31100 62282 31229 62283 31100 62283 31222 62283 31230 62284 31113 62284 31231 62284 31231 62285 31113 62285 31232 62285 31231 62286 31232 62286 31233 62286 31233 62287 31232 62287 31147 62287 31233 62288 31147 62288 31237 62288 31234 62289 31235 62289 31229 62289 31229 62290 31235 62290 31233 62290 31229 62291 31233 62291 31236 62291 31236 62292 31233 62292 31237 62292 31236 62293 31237 62293 31130 62293 31250 62294 31238 62294 31249 62294 31250 62295 31240 62295 31116 62295 31116 62296 31110 62296 31250 62296 31250 62297 31110 62297 31111 62297 31250 62298 31111 62298 31238 62298 31239 62299 31124 62299 31250 62299 31250 62300 31124 62300 31151 62300 31250 62301 31151 62301 31240 62301 31245 62302 31241 62302 31218 62302 31198 62303 31241 62303 31242 62303 31242 62304 31241 62304 31245 62304 31242 62305 31245 62305 31170 62305 31224 62306 31243 62306 31245 62306 31245 62307 31243 62307 31244 62307 31244 62308 31167 62308 31245 62308 31245 62309 31167 62309 31171 62309 31245 62310 31171 62310 31170 62310 31224 62311 31245 62311 31246 62311 31246 62312 31245 62312 31218 62312 31246 62313 31218 62313 31247 62313 31247 62314 31218 62314 31216 62314 31247 62315 31216 62315 31223 62315 31223 62316 31216 62316 31248 62316 31223 62317 31248 62317 31249 62317 31249 62318 31248 62318 31214 62318 31249 62319 31214 62319 31250 62319 31250 62320 31214 62320 31213 62320 31250 62321 31213 62321 31239 62321 30923 62322 31251 62322 31277 62322 31277 62323 31251 62323 31252 62323 31277 62324 31252 62324 31279 62324 31252 62325 31308 62325 31279 62325 31279 62326 31308 62326 31307 62326 31279 62327 31307 62327 31266 62327 31266 62328 31307 62328 31303 62328 31266 62329 31303 62329 31254 62329 31303 62330 31253 62330 31254 62330 31254 62331 31253 62331 31255 62331 31254 62332 31255 62332 31074 62332 31074 62333 31255 62333 31257 62333 31256 62334 31281 62334 31299 62334 31299 62335 31281 62335 31257 62335 31299 62336 31257 62336 31300 62336 31300 62337 31257 62337 31255 62337 31087 62338 31283 62338 31258 62338 31258 62339 31283 62339 31296 62339 31258 62340 31296 62340 31269 62340 31269 62341 31296 62341 31259 62341 31269 62342 31259 62342 31270 62342 31270 62343 31259 62343 31260 62343 31270 62344 31260 62344 31262 62344 31262 62345 31260 62345 31261 62345 31262 62346 31261 62346 31268 62346 31268 62347 31261 62347 31292 62347 31268 62348 31292 62348 31264 62348 31285 62349 31287 62349 31288 62349 31288 62350 31287 62350 31272 62350 31288 62351 31272 62351 31263 62351 31263 62352 31272 62352 31264 62352 31263 62353 31264 62353 31289 62353 31289 62354 31264 62354 31292 62354 31280 62355 31279 62355 31266 62355 31074 62356 31265 62356 31254 62356 31254 62357 31265 62357 31077 62357 31254 62358 31077 62358 31266 62358 31266 62359 31077 62359 31078 62359 31266 62360 31078 62360 31280 62360 31271 62361 31267 62361 31264 62361 31264 62362 31267 62362 30914 62362 31264 62363 30914 62363 31268 62363 31268 62364 30914 62364 30915 62364 31268 62365 30915 62365 31262 62365 31070 62366 31269 62366 31270 62366 30915 62367 30918 62367 31262 62367 31262 62368 30918 62368 31086 62368 31262 62369 31086 62369 31270 62369 31270 62370 31086 62370 31085 62370 31270 62371 31085 62371 31070 62371 31264 62372 31272 62372 31271 62372 31271 62373 31272 62373 31287 62373 31271 62374 31287 62374 31273 62374 31273 62375 31287 62375 31286 62375 31273 62376 31286 62376 31274 62376 31274 62377 31286 62377 31276 62377 31274 62378 31276 62378 31275 62378 31275 62379 31276 62379 30923 62379 31275 62380 30923 62380 31082 62380 31082 62381 30923 62381 31277 62381 31082 62382 31277 62382 31278 62382 31278 62383 31277 62383 31279 62383 31278 62384 31279 62384 31080 62384 31080 62385 31279 62385 31280 62385 31281 62386 31256 62386 31282 62386 31281 62387 31282 62387 31088 62387 31088 62388 31282 62388 31283 62388 31088 62389 31283 62389 31087 62389 30925 62390 31283 62390 30926 62390 30926 62391 31283 62391 31282 62391 30926 62392 31282 62392 30929 62392 31256 62393 31015 62393 31282 62393 31282 62394 31015 62394 31284 62394 31282 62395 31284 62395 30929 62395 30920 62396 31276 62396 30942 62396 30942 62397 31276 62397 31286 62397 30942 62398 31286 62398 31285 62398 31285 62399 31286 62399 31287 62399 31296 62400 31283 62400 30925 62400 30983 62401 31285 62401 30955 62401 30955 62402 31285 62402 31288 62402 30955 62403 31288 62403 30988 62403 30988 62404 31288 62404 31290 62404 31288 62405 31263 62405 31290 62405 31290 62406 31263 62406 31289 62406 31290 62407 31289 62407 31291 62407 31291 62408 31289 62408 31292 62408 31291 62409 31292 62409 31293 62409 31293 62410 31292 62410 31261 62410 31293 62411 31261 62411 31294 62411 31297 62412 30971 62412 31260 62412 31260 62413 30971 62413 31295 62413 31260 62414 31295 62414 31261 62414 31261 62415 31295 62415 30964 62415 31261 62416 30964 62416 31294 62416 30925 62417 30970 62417 31296 62417 31296 62418 30970 62418 31297 62418 31296 62419 31297 62419 31259 62419 31259 62420 31297 62420 31260 62420 31298 62421 31015 62421 31256 62421 31256 62422 31299 62422 31298 62422 31298 62423 31299 62423 31300 62423 31298 62424 31300 62424 31014 62424 31014 62425 31300 62425 31255 62425 31014 62426 31255 62426 31301 62426 31301 62427 31255 62427 31253 62427 31301 62428 31253 62428 31302 62428 31302 62429 31253 62429 31303 62429 31302 62430 31303 62430 31304 62430 31304 62431 31303 62431 31305 62431 31305 62432 31303 62432 31307 62432 31305 62433 31307 62433 31306 62433 31307 62434 31308 62434 31306 62434 31306 62435 31308 62435 31252 62435 31306 62436 31252 62436 31018 62436 31251 62437 31017 62437 31252 62437 31252 62438 31017 62438 31309 62438 31252 62439 31309 62439 31018 62439 31397 62440 31329 62440 31310 62440 31310 62441 31329 62441 31311 62441 31310 62442 31311 62442 31394 62442 31394 62443 31311 62443 31315 62443 31312 62444 31710 62444 31403 62444 31403 62445 31402 62445 31312 62445 31312 62446 31402 62446 31400 62446 31312 62447 31400 62447 31712 62447 31712 62448 31400 62448 31313 62448 31712 62449 31313 62449 31714 62449 31714 62450 31313 62450 31314 62450 31714 62451 31314 62451 31315 62451 31315 62452 31314 62452 31396 62452 31315 62453 31396 62453 31394 62453 31694 62454 31321 62454 31707 62454 31707 62455 31321 62455 31316 62455 31707 62456 31316 62456 31317 62456 31316 62457 31318 62457 31317 62457 31317 62458 31318 62458 31319 62458 31317 62459 31319 62459 31320 62459 31320 62460 31319 62460 31399 62460 31320 62461 31399 62461 31710 62461 31710 62462 31399 62462 31404 62462 31710 62463 31404 62463 31403 62463 31321 62464 31694 62464 31443 62464 31443 62465 31694 62465 31323 62465 31443 62466 31323 62466 31322 62466 31322 62467 31323 62467 31324 62467 31322 62468 31324 62468 31437 62468 31437 62469 31324 62469 31325 62469 31479 62470 31482 62470 31693 62470 31479 62471 31693 62471 31326 62471 31326 62472 31693 62472 31327 62472 31326 62473 31327 62473 31328 62473 31328 62474 31327 62474 31329 62474 31328 62475 31329 62475 31397 62475 31366 62476 31433 62476 31367 62476 31464 62477 31366 62477 31330 62477 31461 62478 31331 62478 31462 62478 31462 62479 31331 62479 31339 62479 31462 62480 31339 62480 31463 62480 31463 62481 31339 62481 31332 62481 31463 62482 31332 62482 31459 62482 31459 62483 31332 62483 31448 62483 31341 62484 31336 62484 31333 62484 31343 62485 31378 62485 31340 62485 31340 62486 31378 62486 31334 62486 31340 62487 31334 62487 31341 62487 31341 62488 31334 62488 31335 62488 31341 62489 31335 62489 31336 62489 31337 62490 31331 62490 31338 62490 31338 62491 31331 62491 31461 62491 31338 62492 31461 62492 31368 62492 31337 62493 31343 62493 31331 62493 31331 62494 31343 62494 31340 62494 31331 62495 31340 62495 31339 62495 31339 62496 31340 62496 31341 62496 31339 62497 31341 62497 31332 62497 31332 62498 31341 62498 31333 62498 31332 62499 31333 62499 31448 62499 31374 62500 31375 62500 31337 62500 31337 62501 31375 62501 31342 62501 31337 62502 31342 62502 31343 62502 31369 62503 31464 62503 31370 62503 31370 62504 31464 62504 31330 62504 31370 62505 31330 62505 31371 62505 31371 62506 31330 62506 31344 62506 31721 62507 31345 62507 31360 62507 31360 62508 31345 62508 31720 62508 31360 62509 31720 62509 31350 62509 31353 62510 31372 62510 31360 62510 31373 62511 31346 62511 31723 62511 31721 62512 31360 62512 31722 62512 31722 62513 31360 62513 31372 62513 31722 62514 31372 62514 31723 62514 31346 62515 31373 62515 31347 62515 31347 62516 31373 62516 31438 62516 31347 62517 31438 62517 31437 62517 31479 62518 31365 62518 31349 62518 31361 62519 31348 62519 31363 62519 31363 62520 31348 62520 31476 62520 31363 62521 31476 62521 31349 62521 31349 62522 31476 62522 31475 62522 31349 62523 31475 62523 31479 62523 31720 62524 31719 62524 31350 62524 31350 62525 31719 62525 31351 62525 31350 62526 31351 62526 31361 62526 31361 62527 31351 62527 31352 62527 31361 62528 31352 62528 31348 62528 31353 62529 31355 62529 31354 62529 31354 62530 31355 62530 31357 62530 31354 62531 31357 62531 31356 62531 31356 62532 31357 62532 31358 62532 31356 62533 31358 62533 31376 62533 31376 62534 31358 62534 31362 62534 31376 62535 31362 62535 31377 62535 31377 62536 31362 62536 31364 62536 31377 62537 31364 62537 31379 62537 31379 62538 31364 62538 31359 62538 31379 62539 31359 62539 31456 62539 31353 62540 31360 62540 31355 62540 31355 62541 31360 62541 31350 62541 31355 62542 31350 62542 31357 62542 31357 62543 31350 62543 31361 62543 31357 62544 31361 62544 31358 62544 31358 62545 31361 62545 31363 62545 31358 62546 31363 62546 31362 62546 31362 62547 31363 62547 31349 62547 31362 62548 31349 62548 31364 62548 31364 62549 31349 62549 31365 62549 31364 62550 31365 62550 31359 62550 31366 62551 31367 62551 31330 62551 31330 62552 31367 62552 31435 62552 31330 62553 31435 62553 31344 62553 31344 62554 31435 62554 31434 62554 31344 62555 31434 62555 31436 62555 31368 62556 31369 62556 31338 62556 31338 62557 31369 62557 31370 62557 31338 62558 31370 62558 31337 62558 31337 62559 31370 62559 31371 62559 31337 62560 31371 62560 31374 62560 31374 62561 31371 62561 31344 62561 31374 62562 31344 62562 31373 62562 31373 62563 31344 62563 31436 62563 31373 62564 31436 62564 31438 62564 31723 62565 31372 62565 31373 62565 31373 62566 31372 62566 31353 62566 31373 62567 31353 62567 31374 62567 31374 62568 31353 62568 31354 62568 31374 62569 31354 62569 31375 62569 31375 62570 31354 62570 31356 62570 31375 62571 31356 62571 31342 62571 31342 62572 31356 62572 31376 62572 31342 62573 31376 62573 31343 62573 31343 62574 31376 62574 31377 62574 31343 62575 31377 62575 31378 62575 31378 62576 31377 62576 31379 62576 31378 62577 31379 62577 31334 62577 31334 62578 31379 62578 31456 62578 31334 62579 31456 62579 31335 62579 31316 62580 31321 62580 31444 62580 31380 62581 31427 62581 31385 62581 31407 62582 31441 62582 31406 62582 31447 62583 31454 62583 31381 62583 31381 62584 31454 62584 31392 62584 31381 62585 31392 62585 31382 62585 31382 62586 31392 62586 31391 62586 31382 62587 31391 62587 31389 62587 31423 62588 31406 62588 31465 62588 31383 62589 31466 62589 31424 62589 31424 62590 31466 62590 31386 62590 31386 62591 31466 62591 31384 62591 31386 62592 31384 62592 31385 62592 31385 62593 31427 62593 31386 62593 31386 62594 31427 62594 31426 62594 31386 62595 31426 62595 31424 62595 31384 62596 31468 62596 31385 62596 31385 62597 31468 62597 31390 62597 31385 62598 31390 62598 31380 62598 31380 62599 31390 62599 31387 62599 31380 62600 31387 62600 31429 62600 31429 62601 31387 62601 31393 62601 31429 62602 31393 62602 31430 62602 31430 62603 31393 62603 31388 62603 31430 62604 31388 62604 31453 62604 31468 62605 31389 62605 31390 62605 31390 62606 31389 62606 31391 62606 31390 62607 31391 62607 31387 62607 31387 62608 31391 62608 31392 62608 31387 62609 31392 62609 31393 62609 31393 62610 31392 62610 31454 62610 31393 62611 31454 62611 31388 62611 31310 62612 31394 62612 31418 62612 31418 62613 31394 62613 31396 62613 31418 62614 31396 62614 31395 62614 31395 62615 31396 62615 31314 62615 31395 62616 31314 62616 31419 62616 31419 62617 31314 62617 31313 62617 31419 62618 31313 62618 31401 62618 31417 62619 31445 62619 31418 62619 31418 62620 31445 62620 31397 62620 31418 62621 31397 62621 31310 62621 31421 62622 31404 62622 31398 62622 31398 62623 31404 62623 31399 62623 31398 62624 31399 62624 31319 62624 31313 62625 31400 62625 31401 62625 31401 62626 31400 62626 31402 62626 31401 62627 31402 62627 31421 62627 31421 62628 31402 62628 31403 62628 31421 62629 31403 62629 31404 62629 31319 62630 31318 62630 31398 62630 31398 62631 31318 62631 31316 62631 31398 62632 31316 62632 31405 62632 31405 62633 31316 62633 31444 62633 31405 62634 31444 62634 31422 62634 31406 62635 31423 62635 31407 62635 31407 62636 31423 62636 31425 62636 31407 62637 31425 62637 31408 62637 31408 62638 31425 62638 31409 62638 31408 62639 31409 62639 31410 62639 31410 62640 31409 62640 31411 62640 31410 62641 31411 62641 31420 62641 31420 62642 31411 62642 31428 62642 31420 62643 31428 62643 31412 62643 31412 62644 31428 62644 31413 62644 31412 62645 31413 62645 31414 62645 31414 62646 31413 62646 31415 62646 31414 62647 31415 62647 31416 62647 31416 62648 31415 62648 31452 62648 31416 62649 31452 62649 31417 62649 31417 62650 31418 62650 31416 62650 31416 62651 31418 62651 31395 62651 31416 62652 31395 62652 31414 62652 31414 62653 31395 62653 31419 62653 31414 62654 31419 62654 31412 62654 31412 62655 31419 62655 31401 62655 31412 62656 31401 62656 31420 62656 31420 62657 31401 62657 31421 62657 31420 62658 31421 62658 31410 62658 31410 62659 31421 62659 31398 62659 31410 62660 31398 62660 31408 62660 31408 62661 31398 62661 31405 62661 31408 62662 31405 62662 31407 62662 31407 62663 31405 62663 31422 62663 31407 62664 31422 62664 31441 62664 31465 62665 31383 62665 31423 62665 31423 62666 31383 62666 31424 62666 31423 62667 31424 62667 31425 62667 31425 62668 31424 62668 31426 62668 31425 62669 31426 62669 31409 62669 31409 62670 31426 62670 31427 62670 31409 62671 31427 62671 31411 62671 31411 62672 31427 62672 31380 62672 31411 62673 31380 62673 31428 62673 31428 62674 31380 62674 31429 62674 31428 62675 31429 62675 31413 62675 31413 62676 31429 62676 31430 62676 31413 62677 31430 62677 31415 62677 31415 62678 31430 62678 31453 62678 31415 62679 31453 62679 31452 62679 31442 62680 31431 62680 31432 62680 31440 62681 31465 62681 31406 62681 31367 62682 31433 62682 31473 62682 31434 62683 31435 62683 31442 62683 31442 62684 31435 62684 31367 62684 31367 62685 31473 62685 31442 62685 31442 62686 31473 62686 31472 62686 31442 62687 31472 62687 31431 62687 31431 62688 31472 62688 31471 62688 31431 62689 31471 62689 31440 62689 31438 62690 31436 62690 31439 62690 31439 62691 31436 62691 31434 62691 31437 62692 31438 62692 31322 62692 31322 62693 31438 62693 31439 62693 31322 62694 31439 62694 31443 62694 31440 62695 31406 62695 31431 62695 31431 62696 31406 62696 31441 62696 31431 62697 31441 62697 31432 62697 31432 62698 31441 62698 31422 62698 31432 62699 31422 62699 31444 62699 31434 62700 31442 62700 31439 62700 31439 62701 31442 62701 31432 62701 31439 62702 31432 62702 31443 62702 31443 62703 31432 62703 31444 62703 31443 62704 31444 62704 31321 62704 31445 62705 31417 62705 31457 62705 31470 62706 31450 62706 31446 62706 31447 62707 31469 62707 31454 62707 31454 62708 31469 62708 31451 62708 31459 62709 31448 62709 31460 62709 31460 62710 31448 62710 31450 62710 31458 62711 31449 62711 31455 62711 31455 62712 31449 62712 31451 62712 31450 62713 31448 62713 31446 62713 31446 62714 31448 62714 31333 62714 31446 62715 31333 62715 31336 62715 31469 62716 31470 62716 31451 62716 31451 62717 31470 62717 31446 62717 31451 62718 31446 62718 31455 62718 31455 62719 31446 62719 31336 62719 31417 62720 31452 62720 31449 62720 31449 62721 31452 62721 31453 62721 31449 62722 31453 62722 31451 62722 31451 62723 31453 62723 31388 62723 31451 62724 31388 62724 31454 62724 31326 62725 31328 62725 31457 62725 31457 62726 31328 62726 31397 62726 31457 62727 31397 62727 31445 62727 31336 62728 31335 62728 31455 62728 31455 62729 31335 62729 31456 62729 31455 62730 31456 62730 31458 62730 31458 62731 31456 62731 31359 62731 31458 62732 31359 62732 31365 62732 31417 62733 31449 62733 31457 62733 31457 62734 31449 62734 31458 62734 31457 62735 31458 62735 31326 62735 31326 62736 31458 62736 31365 62736 31326 62737 31365 62737 31479 62737 31474 62738 31459 62738 31460 62738 31474 62739 31368 62739 31461 62739 31461 62740 31462 62740 31474 62740 31474 62741 31462 62741 31463 62741 31474 62742 31463 62742 31459 62742 31366 62743 31464 62743 31474 62743 31474 62744 31464 62744 31369 62744 31474 62745 31369 62745 31368 62745 31467 62746 31465 62746 31440 62746 31383 62747 31465 62747 31466 62747 31466 62748 31465 62748 31467 62748 31466 62749 31467 62749 31384 62749 31447 62750 31381 62750 31467 62750 31467 62751 31381 62751 31382 62751 31382 62752 31389 62752 31467 62752 31467 62753 31389 62753 31468 62753 31467 62754 31468 62754 31384 62754 31447 62755 31467 62755 31469 62755 31469 62756 31467 62756 31440 62756 31469 62757 31440 62757 31470 62757 31470 62758 31440 62758 31471 62758 31470 62759 31471 62759 31450 62759 31450 62760 31471 62760 31472 62760 31450 62761 31472 62761 31460 62761 31460 62762 31472 62762 31473 62762 31460 62763 31473 62763 31474 62763 31474 62764 31473 62764 31433 62764 31474 62765 31433 62765 31366 62765 31475 62766 31476 62766 31477 62766 31477 62767 31478 62767 31475 62767 31475 62768 31478 62768 31482 62768 31475 62769 31482 62769 31479 62769 31477 62770 31480 62770 31478 62770 31478 62771 31480 62771 31481 62771 31478 62772 31481 62772 31482 62772 31482 62773 31481 62773 31483 62773 31484 62774 31486 62774 31485 62774 31485 62775 31486 62775 31487 62775 31485 62776 31487 62776 31488 62776 31488 62777 31487 62777 31577 62777 31488 62778 31577 62778 31489 62778 31489 62779 31577 62779 31490 62779 31489 62780 31490 62780 31491 62780 31491 62781 31490 62781 31492 62781 31491 62782 31492 62782 31493 62782 31493 62783 31492 62783 31580 62783 31484 62784 31485 62784 31494 62784 31494 62785 31485 62785 31495 62785 31494 62786 31495 62786 31586 62786 31586 62787 31495 62787 31501 62787 31586 62788 31501 62788 31496 62788 31496 62789 31501 62789 31500 62789 31496 62790 31500 62790 31497 62790 31497 62791 31500 62791 31525 62791 31497 62792 31525 62792 31498 62792 31716 62793 31525 62793 31499 62793 31499 62794 31525 62794 31500 62794 31499 62795 31500 62795 31690 62795 31690 62796 31500 62796 31501 62796 31690 62797 31501 62797 31511 62797 31511 62798 31501 62798 31495 62798 31511 62799 31495 62799 31502 62799 31502 62800 31495 62800 31485 62800 31502 62801 31485 62801 31512 62801 31493 62802 31510 62802 31491 62802 31491 62803 31510 62803 31514 62803 31491 62804 31514 62804 31489 62804 31489 62805 31514 62805 31512 62805 31489 62806 31512 62806 31488 62806 31488 62807 31512 62807 31485 62807 31519 62808 31518 62808 31503 62808 31540 62809 31509 62809 31521 62809 31503 62810 31504 62810 31519 62810 31519 62811 31504 62811 31505 62811 31519 62812 31505 62812 31521 62812 31521 62813 31505 62813 31537 62813 31521 62814 31537 62814 31540 62814 31526 62815 31523 62815 31529 62815 31529 62816 31523 62816 31506 62816 31529 62817 31506 62817 31533 62817 31533 62818 31506 62818 31715 62818 31533 62819 31715 62819 31532 62819 31532 62820 31715 62820 31507 62820 31532 62821 31507 62821 31508 62821 31508 62822 31507 62822 31509 62822 31508 62823 31509 62823 31530 62823 31530 62824 31509 62824 31540 62824 31564 62825 31515 62825 31493 62825 31493 62826 31515 62826 31510 62826 31512 62827 31514 62827 31708 62827 31698 62828 31509 62828 31507 62828 31507 62829 31715 62829 31483 62829 31708 62830 31514 62830 31695 62830 31698 62831 31507 62831 31480 62831 31480 62832 31507 62832 31483 62832 31480 62833 31483 62833 31481 62833 31691 62834 31690 62834 31511 62834 31708 62835 31709 62835 31512 62835 31512 62836 31709 62836 31711 62836 31512 62837 31711 62837 31502 62837 31502 62838 31711 62838 31713 62838 31502 62839 31713 62839 31511 62839 31511 62840 31713 62840 31513 62840 31511 62841 31513 62841 31691 62841 31514 62842 31510 62842 31695 62842 31695 62843 31510 62843 31515 62843 31695 62844 31515 62844 31516 62844 31516 62845 31515 62845 31527 62845 31516 62846 31527 62846 31517 62846 31517 62847 31527 62847 31518 62847 31517 62848 31518 62848 31702 62848 31702 62849 31518 62849 31519 62849 31702 62850 31519 62850 31703 62850 31703 62851 31519 62851 31521 62851 31703 62852 31521 62852 31520 62852 31520 62853 31521 62853 31509 62853 31520 62854 31509 62854 31522 62854 31522 62855 31509 62855 31698 62855 31523 62856 31526 62856 31524 62856 31523 62857 31524 62857 31717 62857 31717 62858 31524 62858 31525 62858 31717 62859 31525 62859 31716 62859 31498 62860 31525 62860 31544 62860 31544 62861 31525 62861 31524 62861 31544 62862 31524 62862 31545 62862 31526 62863 31632 62863 31524 62863 31524 62864 31632 62864 31546 62864 31524 62865 31546 62865 31545 62865 31503 62866 31518 62866 31563 62866 31563 62867 31518 62867 31527 62867 31563 62868 31527 62868 31564 62868 31564 62869 31527 62869 31515 62869 31528 62870 31564 62870 31579 62870 31579 62871 31564 62871 31493 62871 31579 62872 31493 62872 31580 62872 31632 62873 31526 62873 31628 62873 31628 62874 31526 62874 31529 62874 31628 62875 31529 62875 31535 62875 31535 62876 31529 62876 31533 62876 31540 62877 31633 62877 31530 62877 31530 62878 31633 62878 31531 62878 31530 62879 31531 62879 31508 62879 31508 62880 31531 62880 31630 62880 31508 62881 31630 62881 31532 62881 31532 62882 31630 62882 31629 62882 31532 62883 31629 62883 31533 62883 31533 62884 31629 62884 31534 62884 31533 62885 31534 62885 31535 62885 31503 62886 31536 62886 31504 62886 31504 62887 31536 62887 31636 62887 31504 62888 31636 62888 31505 62888 31636 62889 31635 62889 31505 62889 31505 62890 31635 62890 31538 62890 31505 62891 31538 62891 31537 62891 31537 62892 31538 62892 31539 62892 31537 62893 31539 62893 31540 62893 31540 62894 31539 62894 31634 62894 31540 62895 31634 62895 31633 62895 31541 62896 31626 62896 31616 62896 31626 62897 31541 62897 31558 62897 31557 62898 31551 62898 31552 62898 31543 62899 31498 62899 31544 62899 31556 62900 31542 62900 31557 62900 31557 62901 31542 62901 31543 62901 31543 62902 31544 62902 31557 62902 31557 62903 31544 62903 31545 62903 31557 62904 31545 62904 31551 62904 31551 62905 31545 62905 31546 62905 31551 62906 31546 62906 31632 62906 31554 62907 31548 62907 31547 62907 31547 62908 31548 62908 31556 62908 31632 62909 31549 62909 31551 62909 31551 62910 31549 62910 31550 62910 31551 62911 31550 62911 31552 62911 31552 62912 31550 62912 31553 62912 31552 62913 31553 62913 31660 62913 31559 62914 31554 62914 31555 62914 31555 62915 31554 62915 31547 62915 31555 62916 31547 62916 31541 62916 31556 62917 31557 62917 31547 62917 31547 62918 31557 62918 31552 62918 31547 62919 31552 62919 31541 62919 31541 62920 31552 62920 31660 62920 31541 62921 31660 62921 31558 62921 31662 62922 31559 62922 31560 62922 31560 62923 31559 62923 31555 62923 31560 62924 31555 62924 31561 62924 31561 62925 31555 62925 31541 62925 31561 62926 31541 62926 31674 62926 31674 62927 31541 62927 31616 62927 31687 62928 31536 62928 31503 62928 31687 62929 31503 62929 31562 62929 31562 62930 31503 62930 31563 62930 31562 62931 31563 62931 31689 62931 31689 62932 31563 62932 31564 62932 31689 62933 31564 62933 31528 62933 31570 62934 31567 62934 31568 62934 31666 62935 31565 62935 31566 62935 31666 62936 31566 62936 31581 62936 31661 62937 31663 62937 31567 62937 31567 62938 31663 62938 31664 62938 31567 62939 31664 62939 31568 62939 31568 62940 31664 62940 31665 62940 31568 62941 31665 62941 31574 62941 31559 62942 31569 62942 31554 62942 31554 62943 31569 62943 31571 62943 31554 62944 31571 62944 31548 62944 31548 62945 31571 62945 31609 62945 31573 62946 31609 62946 31570 62946 31570 62947 31609 62947 31571 62947 31570 62948 31571 62948 31567 62948 31567 62949 31571 62949 31569 62949 31567 62950 31569 62950 31661 62950 31661 62951 31569 62951 31559 62951 31661 62952 31559 62952 31662 62952 31598 62953 31566 62953 31600 62953 31600 62954 31566 62954 31565 62954 31600 62955 31565 62955 31572 62955 31573 62956 31570 62956 31608 62956 31608 62957 31570 62957 31568 62957 31608 62958 31568 62958 31607 62958 31607 62959 31568 62959 31574 62959 31607 62960 31574 62960 31575 62960 31575 62961 31574 62961 31582 62961 31575 62962 31582 62962 31603 62962 31576 62963 31490 62963 31577 62963 31576 62964 31577 62964 31587 62964 31492 62965 31490 62965 31578 62965 31578 62966 31490 62966 31576 62966 31578 62967 31576 62967 31604 62967 31579 62968 31580 62968 31583 62968 31583 62969 31580 62969 31492 62969 31665 62970 31667 62970 31574 62970 31574 62971 31667 62971 31581 62971 31574 62972 31581 62972 31582 62972 31582 62973 31581 62973 31566 62973 31582 62974 31566 62974 31603 62974 31603 62975 31566 62975 31598 62975 31603 62976 31598 62976 31583 62976 31498 62977 31543 62977 31584 62977 31498 62978 31584 62978 31497 62978 31497 62979 31584 62979 31585 62979 31497 62980 31585 62980 31496 62980 31496 62981 31585 62981 31586 62981 31586 62982 31585 62982 31588 62982 31586 62983 31588 62983 31494 62983 31577 62984 31487 62984 31587 62984 31587 62985 31487 62985 31486 62985 31587 62986 31486 62986 31588 62986 31588 62987 31486 62987 31484 62987 31588 62988 31484 62988 31494 62988 31604 62989 31589 62989 31605 62989 31605 62990 31589 62990 31590 62990 31605 62991 31590 62991 31606 62991 31606 62992 31590 62992 31595 62992 31606 62993 31595 62993 31591 62993 31591 62994 31595 62994 31596 62994 31591 62995 31596 62995 31592 62995 31592 62996 31596 62996 31593 62996 31592 62997 31593 62997 31594 62997 31594 62998 31593 62998 31542 62998 31594 62999 31542 62999 31556 62999 31604 63000 31576 63000 31589 63000 31589 63001 31576 63001 31587 63001 31589 63002 31587 63002 31590 63002 31590 63003 31587 63003 31588 63003 31590 63004 31588 63004 31595 63004 31595 63005 31588 63005 31585 63005 31595 63006 31585 63006 31596 63006 31596 63007 31585 63007 31584 63007 31596 63008 31584 63008 31593 63008 31593 63009 31584 63009 31543 63009 31593 63010 31543 63010 31542 63010 31528 63011 31579 63011 31597 63011 31597 63012 31579 63012 31583 63012 31597 63013 31583 63013 31677 63013 31677 63014 31583 63014 31598 63014 31677 63015 31598 63015 31599 63015 31599 63016 31598 63016 31600 63016 31599 63017 31600 63017 31601 63017 31601 63018 31600 63018 31572 63018 31601 63019 31572 63019 31602 63019 31492 63020 31578 63020 31583 63020 31583 63021 31578 63021 31604 63021 31583 63022 31604 63022 31603 63022 31603 63023 31604 63023 31605 63023 31603 63024 31605 63024 31575 63024 31575 63025 31605 63025 31606 63025 31575 63026 31606 63026 31607 63026 31607 63027 31606 63027 31591 63027 31607 63028 31591 63028 31608 63028 31608 63029 31591 63029 31592 63029 31608 63030 31592 63030 31573 63030 31573 63031 31592 63031 31594 63031 31573 63032 31594 63032 31609 63032 31609 63033 31594 63033 31556 63033 31609 63034 31556 63034 31548 63034 31636 63035 31536 63035 31685 63035 31610 63036 31611 63036 31621 63036 31651 63037 31612 63037 31680 63037 31672 63038 31614 63038 31613 63038 31613 63039 31614 63039 31615 63039 31613 63040 31615 63040 31625 63040 31625 63041 31615 63041 31616 63041 31625 63042 31616 63042 31626 63042 31637 63043 31680 63043 31652 63043 31669 63044 31617 63044 31653 63044 31653 63045 31617 63045 31670 63045 31653 63046 31670 63046 31619 63046 31619 63047 31670 63047 31668 63047 31619 63048 31668 63048 31621 63048 31621 63049 31611 63049 31619 63049 31619 63050 31611 63050 31618 63050 31619 63051 31618 63051 31653 63051 31668 63052 31620 63052 31621 63052 31621 63053 31620 63053 31624 63053 31621 63054 31624 63054 31610 63054 31610 63055 31624 63055 31622 63055 31610 63056 31622 63056 31623 63056 31623 63057 31622 63057 31627 63057 31623 63058 31627 63058 31658 63058 31658 63059 31627 63059 31558 63059 31658 63060 31558 63060 31660 63060 31620 63061 31672 63061 31624 63061 31624 63062 31672 63062 31613 63062 31624 63063 31613 63063 31622 63063 31622 63064 31613 63064 31625 63064 31622 63065 31625 63065 31627 63065 31627 63066 31625 63066 31626 63066 31627 63067 31626 63067 31558 63067 31628 63068 31535 63068 31643 63068 31643 63069 31535 63069 31534 63069 31643 63070 31534 63070 31644 63070 31644 63071 31534 63071 31629 63071 31644 63072 31629 63072 31645 63072 31645 63073 31629 63073 31630 63073 31645 63074 31630 63074 31631 63074 31550 63075 31549 63075 31643 63075 31643 63076 31549 63076 31632 63076 31643 63077 31632 63077 31628 63077 31630 63078 31531 63078 31631 63078 31631 63079 31531 63079 31633 63079 31631 63080 31633 63080 31647 63080 31647 63081 31633 63081 31634 63081 31647 63082 31634 63082 31648 63082 31648 63083 31634 63083 31539 63083 31648 63084 31539 63084 31538 63084 31538 63085 31635 63085 31648 63085 31648 63086 31635 63086 31636 63086 31648 63087 31636 63087 31650 63087 31650 63088 31636 63088 31685 63088 31650 63089 31685 63089 31684 63089 31680 63090 31637 63090 31651 63090 31651 63091 31637 63091 31654 63091 31651 63092 31654 63092 31649 63092 31649 63093 31654 63093 31638 63093 31649 63094 31638 63094 31639 63094 31639 63095 31638 63095 31655 63095 31639 63096 31655 63096 31640 63096 31640 63097 31655 63097 31656 63097 31640 63098 31656 63098 31646 63098 31646 63099 31656 63099 31657 63099 31646 63100 31657 63100 31641 63100 31641 63101 31657 63101 31659 63101 31641 63102 31659 63102 31642 63102 31642 63103 31659 63103 31553 63103 31642 63104 31553 63104 31550 63104 31550 63105 31643 63105 31642 63105 31642 63106 31643 63106 31644 63106 31642 63107 31644 63107 31641 63107 31641 63108 31644 63108 31645 63108 31641 63109 31645 63109 31646 63109 31646 63110 31645 63110 31631 63110 31646 63111 31631 63111 31640 63111 31640 63112 31631 63112 31647 63112 31640 63113 31647 63113 31639 63113 31639 63114 31647 63114 31648 63114 31639 63115 31648 63115 31649 63115 31649 63116 31648 63116 31650 63116 31649 63117 31650 63117 31651 63117 31651 63118 31650 63118 31684 63118 31651 63119 31684 63119 31612 63119 31652 63120 31669 63120 31637 63120 31637 63121 31669 63121 31653 63121 31637 63122 31653 63122 31654 63122 31654 63123 31653 63123 31618 63123 31654 63124 31618 63124 31638 63124 31638 63125 31618 63125 31611 63125 31638 63126 31611 63126 31655 63126 31655 63127 31611 63127 31610 63127 31655 63128 31610 63128 31656 63128 31656 63129 31610 63129 31623 63129 31656 63130 31623 63130 31657 63130 31657 63131 31623 63131 31658 63131 31657 63132 31658 63132 31659 63132 31659 63133 31658 63133 31660 63133 31659 63134 31660 63134 31553 63134 31671 63135 31652 63135 31673 63135 31676 63136 31662 63136 31560 63136 31661 63137 31662 63137 31663 63137 31663 63138 31662 63138 31676 63138 31663 63139 31676 63139 31664 63139 31664 63140 31676 63140 31665 63140 31572 63141 31565 63141 31676 63141 31676 63142 31565 63142 31666 63142 31666 63143 31581 63143 31676 63143 31676 63144 31581 63144 31667 63144 31676 63145 31667 63145 31665 63145 31672 63146 31620 63146 31671 63146 31671 63147 31620 63147 31668 63147 31669 63148 31652 63148 31617 63148 31617 63149 31652 63149 31671 63149 31617 63150 31671 63150 31670 63150 31670 63151 31671 63151 31668 63151 31616 63152 31615 63152 31671 63152 31671 63153 31615 63153 31614 63153 31671 63154 31614 63154 31672 63154 31616 63155 31671 63155 31674 63155 31674 63156 31671 63156 31673 63156 31674 63157 31673 63157 31561 63157 31561 63158 31673 63158 31678 63158 31561 63159 31678 63159 31560 63159 31560 63160 31678 63160 31675 63160 31560 63161 31675 63161 31676 63161 31676 63162 31675 63162 31602 63162 31676 63163 31602 63163 31572 63163 31685 63164 31536 63164 31687 63164 31612 63165 31684 63165 31681 63165 31597 63166 31677 63166 31688 63166 31599 63167 31601 63167 31683 63167 31601 63168 31602 63168 31683 63168 31683 63169 31602 63169 31675 63169 31683 63170 31675 63170 31682 63170 31682 63171 31675 63171 31678 63171 31682 63172 31678 63172 31679 63172 31679 63173 31678 63173 31673 63173 31679 63174 31673 63174 31680 63174 31680 63175 31673 63175 31652 63175 31680 63176 31612 63176 31679 63176 31679 63177 31612 63177 31681 63177 31679 63178 31681 63178 31682 63178 31682 63179 31681 63179 31686 63179 31682 63180 31686 63180 31683 63180 31683 63181 31686 63181 31688 63181 31683 63182 31688 63182 31599 63182 31599 63183 31688 63183 31677 63183 31684 63184 31685 63184 31681 63184 31681 63185 31685 63185 31687 63185 31681 63186 31687 63186 31686 63186 31686 63187 31687 63187 31562 63187 31686 63188 31562 63188 31688 63188 31688 63189 31562 63189 31689 63189 31688 63190 31689 63190 31597 63190 31597 63191 31689 63191 31528 63191 31690 63192 31691 63192 31329 63192 31690 63193 31329 63193 31692 63193 31329 63194 31327 63194 31692 63194 31692 63195 31327 63195 31693 63195 31692 63196 31693 63196 31718 63196 31718 63197 31693 63197 31715 63197 31715 63198 31693 63198 31482 63198 31715 63199 31482 63199 31483 63199 31694 63200 31695 63200 31323 63200 31323 63201 31695 63201 31516 63201 31323 63202 31516 63202 31324 63202 31324 63203 31516 63203 31517 63203 31324 63204 31517 63204 31325 63204 31325 63205 31517 63205 31702 63205 31698 63206 31480 63206 31477 63206 31477 63207 31696 63207 31698 63207 31698 63208 31696 63208 31697 63208 31698 63209 31697 63209 31522 63209 31522 63210 31697 63210 31699 63210 31699 63211 31700 63211 31522 63211 31522 63212 31700 63212 31706 63212 31522 63213 31706 63213 31520 63213 31325 63214 31702 63214 31701 63214 31701 63215 31702 63215 31703 63215 31701 63216 31703 63216 31704 63216 31704 63217 31703 63217 31520 63217 31704 63218 31520 63218 31705 63218 31705 63219 31520 63219 31706 63219 31708 63220 31695 63220 31694 63220 31710 63221 31711 63221 31709 63221 31694 63222 31707 63222 31708 63222 31708 63223 31707 63223 31317 63223 31708 63224 31317 63224 31709 63224 31709 63225 31317 63225 31320 63225 31709 63226 31320 63226 31710 63226 31710 63227 31312 63227 31711 63227 31711 63228 31312 63228 31712 63228 31711 63229 31712 63229 31713 63229 31329 63230 31691 63230 31311 63230 31311 63231 31691 63231 31513 63231 31311 63232 31513 63232 31315 63232 31315 63233 31513 63233 31713 63233 31315 63234 31713 63234 31714 63234 31714 63235 31713 63235 31712 63235 31718 63236 31715 63236 31506 63236 31499 63237 31690 63237 31716 63237 31716 63238 31690 63238 31692 63238 31716 63239 31692 63239 31717 63239 31717 63240 31692 63240 31718 63240 31717 63241 31718 63241 31523 63241 31523 63242 31718 63242 31506 63242 31719 63243 31720 63243 31699 63243 31699 63244 31720 63244 31700 63244 31700 63245 31720 63245 31345 63245 31700 63246 31345 63246 31706 63246 31706 63247 31345 63247 31721 63247 31706 63248 31721 63248 31705 63248 31705 63249 31721 63249 31722 63249 31705 63250 31722 63250 31704 63250 31704 63251 31722 63251 31723 63251 31704 63252 31723 63252 31701 63252 31701 63253 31723 63253 31346 63253 31701 63254 31346 63254 31325 63254 31325 63255 31346 63255 31347 63255 31325 63256 31347 63256 31437 63256 31719 63257 31699 63257 31351 63257 31351 63258 31699 63258 31697 63258 31351 63259 31697 63259 31352 63259 31352 63260 31697 63260 31696 63260 31352 63261 31696 63261 31348 63261 31348 63262 31696 63262 31477 63262 31348 63263 31477 63263 31476 63263 31734 63264 31724 63264 31735 63264 31729 63265 32029 63265 32030 63265 32038 63266 32029 63266 31725 63266 31725 63267 32029 63267 31729 63267 31725 63268 31729 63268 31726 63268 31726 63269 31729 63269 31731 63269 32072 63270 32036 63270 31729 63270 31729 63271 32036 63271 31727 63271 31727 63272 31728 63272 31729 63272 31729 63273 31728 63273 31730 63273 31729 63274 31730 63274 31731 63274 32086 63275 32097 63275 31734 63275 31734 63276 32097 63276 32096 63276 32090 63277 31724 63277 32091 63277 32091 63278 31724 63278 31734 63278 32091 63279 31734 63279 32092 63279 32092 63280 31734 63280 32096 63280 32089 63281 31732 63281 31734 63281 31734 63282 31732 63282 31733 63282 31734 63283 31733 63283 32086 63283 32089 63284 31734 63284 31736 63284 31736 63285 31734 63285 31735 63285 31736 63286 31735 63286 31737 63286 31737 63287 31735 63287 31743 63287 31737 63288 31743 63288 32030 63288 32030 63289 31743 63289 31742 63289 32030 63290 31742 63290 31729 63290 31729 63291 31742 63291 31740 63291 31729 63292 31740 63292 32072 63292 31750 63293 32014 63293 31752 63293 31738 63294 31739 63294 31746 63294 32045 63295 32075 63295 31748 63295 31749 63296 32071 63296 31741 63296 32071 63297 31740 63297 31741 63297 31741 63298 31740 63298 31742 63298 31741 63299 31742 63299 31747 63299 31747 63300 31742 63300 31743 63300 31747 63301 31743 63301 31745 63301 31745 63302 31743 63302 31735 63302 31745 63303 31735 63303 31744 63303 31744 63304 31735 63304 31724 63304 31744 63305 31738 63305 31745 63305 31745 63306 31738 63306 31746 63306 31745 63307 31746 63307 31747 63307 31747 63308 31746 63308 31751 63308 31747 63309 31751 63309 31741 63309 31741 63310 31751 63310 31748 63310 31741 63311 31748 63311 31749 63311 31749 63312 31748 63312 32075 63312 31739 63313 31750 63313 31746 63313 31746 63314 31750 63314 31752 63314 31746 63315 31752 63315 31751 63315 31751 63316 31752 63316 31753 63316 31751 63317 31753 63317 31748 63317 31748 63318 31753 63318 32033 63318 31748 63319 32033 63319 32045 63319 32045 63320 32033 63320 32002 63320 31779 63321 31991 63321 31774 63321 31779 63322 31774 63322 31780 63322 31774 63323 31802 63323 31780 63323 31780 63324 31802 63324 31801 63324 31780 63325 31801 63325 31781 63325 31781 63326 31801 63326 31778 63326 31778 63327 31801 63327 31956 63327 31778 63328 31956 63328 31754 63328 31770 63329 31755 63329 31756 63329 31756 63330 31755 63330 31758 63330 31756 63331 31758 63331 31757 63331 31757 63332 31758 63332 31759 63332 31757 63333 31759 63333 31800 63333 31800 63334 31759 63334 31766 63334 31760 63335 31761 63335 31762 63335 31762 63336 31784 63336 31760 63336 31760 63337 31784 63337 31763 63337 31760 63338 31763 63338 31767 63338 31767 63339 31763 63339 31764 63339 31800 63340 31766 63340 31765 63340 31765 63341 31766 63341 31994 63341 31765 63342 31994 63342 31768 63342 31768 63343 31994 63343 31767 63343 31768 63344 31767 63344 31769 63344 31769 63345 31767 63345 31764 63345 31755 63346 31770 63346 31986 63346 31986 63347 31770 63347 31791 63347 31986 63348 31791 63348 31771 63348 31791 63349 31772 63349 31771 63349 31771 63350 31772 63350 31795 63350 31771 63351 31795 63351 31773 63351 31773 63352 31795 63352 31796 63352 31773 63353 31796 63353 31989 63353 31989 63354 31796 63354 31790 63354 31989 63355 31790 63355 31776 63355 31774 63356 31991 63356 31787 63356 31787 63357 31991 63357 31775 63357 31787 63358 31775 63358 31788 63358 31788 63359 31775 63359 31776 63359 31788 63360 31776 63360 31777 63360 31777 63361 31776 63361 31790 63361 31781 63362 31778 63362 31782 63362 31970 63363 31779 63363 31969 63363 31969 63364 31779 63364 31780 63364 31969 63365 31780 63365 31997 63365 31997 63366 31780 63366 31781 63366 31997 63367 31781 63367 31983 63367 31983 63368 31781 63368 31782 63368 31825 63369 31800 63369 31826 63369 31826 63370 31800 63370 31765 63370 31826 63371 31765 63371 31768 63371 31819 63372 31824 63372 31769 63372 31769 63373 31824 63373 31823 63373 31769 63374 31823 63374 31768 63374 31768 63375 31823 63375 31822 63375 31768 63376 31822 63376 31826 63376 31769 63377 31764 63377 31819 63377 31819 63378 31764 63378 31763 63378 31819 63379 31763 63379 31783 63379 31783 63380 31763 63380 31784 63380 31783 63381 31784 63381 31785 63381 31785 63382 31784 63382 31762 63382 31785 63383 31762 63383 31829 63383 31939 63384 31774 63384 31786 63384 31786 63385 31774 63385 31787 63385 31786 63386 31787 63386 31789 63386 31789 63387 31787 63387 31788 63387 31789 63388 31788 63388 31873 63388 31873 63389 31788 63389 31777 63389 31873 63390 31777 63390 31875 63390 31875 63391 31777 63391 31790 63391 31875 63392 31790 63392 31877 63392 31877 63393 31790 63393 31881 63393 31881 63394 31790 63394 31882 63394 31882 63395 31790 63395 31796 63395 31882 63396 31796 63396 31883 63396 31770 63397 31924 63397 31791 63397 31791 63398 31924 63398 31886 63398 31791 63399 31886 63399 31772 63399 31886 63400 31792 63400 31772 63400 31772 63401 31792 63401 31793 63401 31772 63402 31793 63402 31795 63402 31795 63403 31793 63403 31794 63403 31795 63404 31794 63404 31796 63404 31796 63405 31794 63405 31797 63405 31796 63406 31797 63406 31883 63406 31924 63407 31770 63407 31798 63407 31798 63408 31770 63408 31756 63408 31798 63409 31756 63409 31799 63409 31799 63410 31756 63410 31757 63410 31799 63411 31757 63411 31825 63411 31825 63412 31757 63412 31800 63412 31945 63413 31956 63413 31801 63413 31945 63414 31801 63414 31944 63414 31944 63415 31801 63415 31802 63415 31944 63416 31802 63416 31938 63416 31938 63417 31802 63417 31774 63417 31938 63418 31774 63418 31939 63418 31805 63419 31803 63419 31912 63419 31804 63420 31805 63420 31806 63420 31946 63421 31813 63421 31947 63421 31947 63422 31813 63422 31814 63422 31947 63423 31814 63423 31807 63423 31807 63424 31814 63424 31815 63424 31807 63425 31815 63425 31930 63425 31930 63426 31815 63426 31932 63426 31810 63427 31935 63427 31816 63427 31812 63428 31855 63428 31808 63428 31808 63429 31855 63429 31809 63429 31808 63430 31809 63430 31810 63430 31810 63431 31809 63431 31940 63431 31810 63432 31940 63432 31935 63432 31811 63433 31813 63433 31845 63433 31845 63434 31813 63434 31946 63434 31845 63435 31946 63435 31949 63435 31811 63436 31812 63436 31813 63436 31813 63437 31812 63437 31808 63437 31813 63438 31808 63438 31814 63438 31814 63439 31808 63439 31810 63439 31814 63440 31810 63440 31815 63440 31815 63441 31810 63441 31816 63441 31815 63442 31816 63442 31932 63442 31850 63443 31817 63443 31811 63443 31811 63444 31817 63444 31853 63444 31811 63445 31853 63445 31812 63445 31844 63446 31804 63446 31846 63446 31846 63447 31804 63447 31806 63447 31846 63448 31806 63448 31818 63448 31818 63449 31806 63449 31843 63449 31819 63450 31783 63450 31821 63450 31821 63451 31783 63451 31828 63451 31820 63452 31849 63452 31821 63452 31826 63453 31822 63453 31849 63453 31849 63454 31822 63454 31823 63454 31849 63455 31823 63455 31821 63455 31821 63456 31823 63456 31824 63456 31821 63457 31824 63457 31819 63457 31848 63458 31825 63458 31847 63458 31847 63459 31825 63459 31826 63459 31945 63460 31842 63460 31957 63460 31957 63461 31842 63461 31827 63461 31957 63462 31827 63462 31833 63462 31833 63463 31827 63463 31840 63463 31783 63464 31785 63464 31828 63464 31828 63465 31785 63465 31829 63465 31828 63466 31829 63466 31830 63466 31830 63467 31829 63467 31831 63467 31830 63468 31831 63468 31840 63468 31840 63469 31831 63469 31832 63469 31840 63470 31832 63470 31833 63470 31820 63471 31839 63471 31851 63471 31851 63472 31839 63472 31834 63472 31851 63473 31834 63473 31852 63473 31852 63474 31834 63474 31835 63474 31852 63475 31835 63475 31854 63475 31854 63476 31835 63476 31841 63476 31854 63477 31841 63477 31856 63477 31856 63478 31841 63478 31836 63478 31856 63479 31836 63479 31837 63479 31837 63480 31836 63480 31838 63480 31837 63481 31838 63481 31941 63481 31820 63482 31821 63482 31839 63482 31839 63483 31821 63483 31828 63483 31839 63484 31828 63484 31834 63484 31834 63485 31828 63485 31830 63485 31834 63486 31830 63486 31835 63486 31835 63487 31830 63487 31840 63487 31835 63488 31840 63488 31841 63488 31841 63489 31840 63489 31827 63489 31841 63490 31827 63490 31836 63490 31836 63491 31827 63491 31842 63491 31836 63492 31842 63492 31838 63492 31805 63493 31912 63493 31806 63493 31806 63494 31912 63494 31913 63494 31806 63495 31913 63495 31843 63495 31843 63496 31913 63496 31920 63496 31843 63497 31920 63497 31919 63497 31949 63498 31844 63498 31845 63498 31845 63499 31844 63499 31846 63499 31845 63500 31846 63500 31811 63500 31811 63501 31846 63501 31818 63501 31811 63502 31818 63502 31850 63502 31850 63503 31818 63503 31843 63503 31850 63504 31843 63504 31847 63504 31847 63505 31843 63505 31919 63505 31847 63506 31919 63506 31848 63506 31826 63507 31849 63507 31847 63507 31847 63508 31849 63508 31820 63508 31847 63509 31820 63509 31850 63509 31850 63510 31820 63510 31851 63510 31850 63511 31851 63511 31817 63511 31817 63512 31851 63512 31852 63512 31817 63513 31852 63513 31853 63513 31853 63514 31852 63514 31854 63514 31853 63515 31854 63515 31812 63515 31812 63516 31854 63516 31856 63516 31812 63517 31856 63517 31855 63517 31855 63518 31856 63518 31837 63518 31855 63519 31837 63519 31809 63519 31809 63520 31837 63520 31941 63520 31809 63521 31941 63521 31940 63521 31886 63522 31924 63522 31887 63522 31907 63523 31857 63523 31865 63523 31889 63524 31858 63524 31911 63524 31927 63525 31929 63525 31859 63525 31859 63526 31929 63526 31860 63526 31859 63527 31860 63527 31950 63527 31950 63528 31860 63528 31869 63528 31950 63529 31869 63529 31868 63529 31861 63530 31911 63530 31902 63530 31903 63531 31862 63531 31863 63531 31863 63532 31862 63532 31864 63532 31864 63533 31862 63533 31952 63533 31864 63534 31952 63534 31865 63534 31865 63535 31857 63535 31864 63535 31864 63536 31857 63536 31904 63536 31864 63537 31904 63537 31863 63537 31952 63538 31951 63538 31865 63538 31865 63539 31951 63539 31866 63539 31865 63540 31866 63540 31907 63540 31907 63541 31866 63541 31870 63541 31907 63542 31870 63542 31908 63542 31908 63543 31870 63543 31871 63543 31908 63544 31871 63544 31867 63544 31867 63545 31871 63545 31872 63545 31867 63546 31872 63546 31910 63546 31951 63547 31868 63547 31866 63547 31866 63548 31868 63548 31869 63548 31866 63549 31869 63549 31870 63549 31870 63550 31869 63550 31860 63550 31870 63551 31860 63551 31871 63551 31871 63552 31860 63552 31929 63552 31871 63553 31929 63553 31872 63553 31786 63554 31789 63554 31878 63554 31878 63555 31789 63555 31873 63555 31878 63556 31873 63556 31874 63556 31874 63557 31873 63557 31875 63557 31874 63558 31875 63558 31876 63558 31876 63559 31875 63559 31877 63559 31876 63560 31877 63560 31880 63560 31896 63561 31879 63561 31878 63561 31878 63562 31879 63562 31939 63562 31878 63563 31939 63563 31786 63563 31899 63564 31797 63564 31884 63564 31884 63565 31797 63565 31794 63565 31884 63566 31794 63566 31793 63566 31877 63567 31881 63567 31880 63567 31880 63568 31881 63568 31882 63568 31880 63569 31882 63569 31899 63569 31899 63570 31882 63570 31883 63570 31899 63571 31883 63571 31797 63571 31793 63572 31792 63572 31884 63572 31884 63573 31792 63573 31886 63573 31884 63574 31886 63574 31885 63574 31885 63575 31886 63575 31887 63575 31885 63576 31887 63576 31888 63576 31911 63577 31861 63577 31889 63577 31889 63578 31861 63578 31890 63578 31889 63579 31890 63579 31901 63579 31901 63580 31890 63580 31905 63580 31901 63581 31905 63581 31900 63581 31900 63582 31905 63582 31906 63582 31900 63583 31906 63583 31898 63583 31898 63584 31906 63584 31891 63584 31898 63585 31891 63585 31897 63585 31897 63586 31891 63586 31892 63586 31897 63587 31892 63587 31893 63587 31893 63588 31892 63588 31909 63588 31893 63589 31909 63589 31894 63589 31894 63590 31909 63590 31895 63590 31894 63591 31895 63591 31896 63591 31896 63592 31878 63592 31894 63592 31894 63593 31878 63593 31874 63593 31894 63594 31874 63594 31893 63594 31893 63595 31874 63595 31876 63595 31893 63596 31876 63596 31897 63596 31897 63597 31876 63597 31880 63597 31897 63598 31880 63598 31898 63598 31898 63599 31880 63599 31899 63599 31898 63600 31899 63600 31900 63600 31900 63601 31899 63601 31884 63601 31900 63602 31884 63602 31901 63602 31901 63603 31884 63603 31885 63603 31901 63604 31885 63604 31889 63604 31889 63605 31885 63605 31888 63605 31889 63606 31888 63606 31858 63606 31902 63607 31903 63607 31861 63607 31861 63608 31903 63608 31863 63608 31861 63609 31863 63609 31890 63609 31890 63610 31863 63610 31904 63610 31890 63611 31904 63611 31905 63611 31905 63612 31904 63612 31857 63612 31905 63613 31857 63613 31906 63613 31906 63614 31857 63614 31907 63614 31906 63615 31907 63615 31891 63615 31891 63616 31907 63616 31908 63616 31891 63617 31908 63617 31892 63617 31892 63618 31908 63618 31867 63618 31892 63619 31867 63619 31909 63619 31909 63620 31867 63620 31910 63620 31909 63621 31910 63621 31895 63621 31922 63622 31916 63622 31923 63622 31918 63623 31902 63623 31911 63623 31912 63624 31803 63624 31914 63624 31920 63625 31913 63625 31922 63625 31922 63626 31913 63626 31912 63626 31912 63627 31914 63627 31922 63627 31922 63628 31914 63628 31915 63628 31922 63629 31915 63629 31916 63629 31916 63630 31915 63630 31917 63630 31916 63631 31917 63631 31918 63631 31848 63632 31919 63632 31921 63632 31921 63633 31919 63633 31920 63633 31825 63634 31848 63634 31799 63634 31799 63635 31848 63635 31921 63635 31799 63636 31921 63636 31798 63636 31918 63637 31911 63637 31916 63637 31916 63638 31911 63638 31858 63638 31916 63639 31858 63639 31923 63639 31923 63640 31858 63640 31888 63640 31923 63641 31888 63641 31887 63641 31920 63642 31922 63642 31921 63642 31921 63643 31922 63643 31923 63643 31921 63644 31923 63644 31798 63644 31798 63645 31923 63645 31887 63645 31798 63646 31887 63646 31924 63646 31879 63647 31896 63647 31943 63647 31934 63648 31925 63648 31926 63648 31927 63649 31928 63649 31929 63649 31929 63650 31928 63650 31937 63650 31930 63651 31932 63651 31931 63651 31931 63652 31932 63652 31925 63652 31942 63653 31936 63653 31933 63653 31933 63654 31936 63654 31937 63654 31925 63655 31932 63655 31926 63655 31926 63656 31932 63656 31816 63656 31926 63657 31816 63657 31935 63657 31928 63658 31934 63658 31937 63658 31937 63659 31934 63659 31926 63659 31937 63660 31926 63660 31933 63660 31933 63661 31926 63661 31935 63661 31896 63662 31895 63662 31936 63662 31936 63663 31895 63663 31910 63663 31936 63664 31910 63664 31937 63664 31937 63665 31910 63665 31872 63665 31937 63666 31872 63666 31929 63666 31944 63667 31938 63667 31943 63667 31943 63668 31938 63668 31939 63668 31943 63669 31939 63669 31879 63669 31935 63670 31940 63670 31933 63670 31933 63671 31940 63671 31941 63671 31933 63672 31941 63672 31942 63672 31942 63673 31941 63673 31838 63673 31942 63674 31838 63674 31842 63674 31896 63675 31936 63675 31943 63675 31943 63676 31936 63676 31942 63676 31943 63677 31942 63677 31944 63677 31944 63678 31942 63678 31842 63678 31944 63679 31842 63679 31945 63679 31948 63680 31930 63680 31931 63680 31948 63681 31949 63681 31946 63681 31946 63682 31947 63682 31948 63682 31948 63683 31947 63683 31807 63683 31948 63684 31807 63684 31930 63684 31805 63685 31804 63685 31948 63685 31948 63686 31804 63686 31844 63686 31948 63687 31844 63687 31949 63687 31953 63688 31902 63688 31918 63688 31903 63689 31902 63689 31862 63689 31862 63690 31902 63690 31953 63690 31862 63691 31953 63691 31952 63691 31927 63692 31859 63692 31953 63692 31953 63693 31859 63693 31950 63693 31950 63694 31868 63694 31953 63694 31953 63695 31868 63695 31951 63695 31953 63696 31951 63696 31952 63696 31927 63697 31953 63697 31928 63697 31928 63698 31953 63698 31918 63698 31928 63699 31918 63699 31934 63699 31934 63700 31918 63700 31917 63700 31934 63701 31917 63701 31925 63701 31925 63702 31917 63702 31915 63702 31925 63703 31915 63703 31931 63703 31931 63704 31915 63704 31914 63704 31931 63705 31914 63705 31948 63705 31948 63706 31914 63706 31803 63706 31948 63707 31803 63707 31805 63707 31829 63708 31762 63708 31831 63708 31831 63709 31762 63709 31954 63709 31831 63710 31954 63710 31832 63710 31832 63711 31954 63711 31955 63711 31832 63712 31955 63712 31833 63712 31833 63713 31955 63713 31957 63713 31957 63714 31955 63714 31956 63714 31957 63715 31956 63715 31945 63715 31762 63716 31761 63716 31954 63716 31954 63717 31761 63717 31958 63717 31954 63718 31958 63718 31955 63718 31955 63719 31958 63719 31959 63719 31955 63720 31959 63720 31956 63720 31956 63721 31959 63721 31754 63721 32047 63722 31972 63722 31960 63722 31960 63723 31972 63723 31973 63723 31960 63724 31973 63724 31961 63724 31961 63725 31973 63725 31962 63725 31961 63726 31962 63726 32055 63726 32055 63727 31962 63727 31964 63727 31964 63728 31962 63728 31963 63728 31964 63729 31963 63729 31965 63729 31965 63730 31963 63730 31966 63730 31966 63731 31963 63731 31971 63731 31966 63732 31971 63732 32069 63732 32069 63733 31971 63733 31967 63733 32069 63734 31967 63734 31968 63734 31969 63735 31967 63735 31970 63735 31970 63736 31967 63736 31971 63736 31970 63737 31971 63737 31779 63737 31779 63738 31971 63738 31963 63738 31972 63739 31996 63739 31973 63739 31973 63740 31996 63740 31987 63740 31973 63741 31987 63741 31962 63741 31962 63742 31987 63742 31988 63742 31962 63743 31988 63743 31963 63743 31963 63744 31988 63744 31990 63744 31963 63745 31990 63745 31779 63745 31974 63746 32031 63746 31975 63746 31975 63747 32031 63747 32013 63747 31975 63748 32013 63748 31976 63748 32013 63749 31977 63749 31976 63749 31976 63750 31977 63750 31978 63750 31976 63751 31978 63751 31993 63751 31993 63752 31978 63752 32011 63752 31993 63753 32011 63753 31979 63753 31979 63754 32011 63754 32008 63754 31979 63755 32008 63755 31992 63755 31992 63756 32008 63756 31980 63756 31992 63757 31980 63757 31981 63757 31982 63758 31983 63758 31984 63758 31984 63759 31983 63759 31782 63759 31984 63760 31782 63760 31981 63760 31981 63761 31782 63761 31778 63761 31981 63762 31778 63762 31992 63762 32032 63763 31995 63763 32003 63763 32003 63764 31995 63764 31985 63764 32003 63765 31985 63765 31972 63765 31972 63766 31985 63766 31996 63766 31991 63767 31779 63767 31990 63767 31993 63768 31979 63768 31761 63768 31755 63769 31986 63769 31996 63769 31996 63770 31986 63770 31771 63770 31996 63771 31771 63771 31987 63771 31771 63772 31773 63772 31987 63772 31987 63773 31773 63773 31989 63773 31987 63774 31989 63774 31988 63774 31988 63775 31989 63775 31776 63775 31988 63776 31776 63776 31990 63776 31990 63777 31776 63777 31775 63777 31990 63778 31775 63778 31991 63778 31778 63779 31754 63779 31992 63779 31992 63780 31754 63780 31959 63780 31992 63781 31959 63781 31979 63781 31979 63782 31959 63782 31958 63782 31979 63783 31958 63783 31761 63783 31761 63784 31760 63784 31993 63784 31993 63785 31760 63785 31767 63785 31993 63786 31767 63786 31976 63786 31976 63787 31767 63787 31994 63787 31976 63788 31994 63788 31975 63788 31975 63789 31994 63789 31766 63789 31975 63790 31766 63790 31974 63790 31974 63791 31766 63791 31759 63791 31974 63792 31759 63792 32001 63792 32001 63793 31759 63793 31758 63793 32001 63794 31758 63794 31995 63794 31995 63795 31758 63795 31755 63795 31995 63796 31755 63796 31985 63796 31985 63797 31755 63797 31996 63797 31983 63798 31982 63798 31999 63798 31983 63799 31999 63799 31997 63799 31997 63800 31999 63800 31967 63800 31997 63801 31967 63801 31969 63801 31968 63802 31967 63802 31998 63802 31998 63803 31967 63803 31999 63803 31998 63804 31999 63804 32020 63804 31982 63805 32107 63805 31999 63805 31999 63806 32107 63806 32021 63806 31999 63807 32021 63807 32020 63807 32031 63808 31974 63808 32000 63808 32000 63809 31974 63809 32001 63809 32000 63810 32001 63810 32032 63810 32032 63811 32001 63811 31995 63811 32002 63812 32032 63812 32046 63812 32046 63813 32032 63813 32003 63813 32046 63814 32003 63814 32044 63814 32044 63815 32003 63815 32004 63815 32004 63816 32003 63816 31972 63816 32004 63817 31972 63817 32047 63817 32107 63818 31982 63818 32005 63818 32005 63819 31982 63819 31984 63819 32005 63820 31984 63820 32006 63820 32006 63821 31984 63821 31981 63821 32006 63822 31981 63822 32105 63822 32105 63823 31981 63823 31980 63823 32105 63824 31980 63824 32007 63824 32007 63825 31980 63825 32008 63825 32007 63826 32008 63826 32009 63826 32009 63827 32008 63827 32010 63827 32010 63828 32008 63828 32012 63828 32012 63829 32008 63829 32011 63829 32012 63830 32011 63830 32110 63830 32031 63831 32014 63831 32013 63831 32013 63832 32014 63832 32015 63832 32013 63833 32015 63833 31977 63833 32015 63834 32016 63834 31977 63834 31977 63835 32016 63835 32112 63835 31977 63836 32112 63836 31978 63836 31978 63837 32112 63837 32108 63837 31978 63838 32108 63838 32011 63838 32011 63839 32108 63839 32111 63839 32011 63840 32111 63840 32110 63840 32028 63841 32017 63841 32089 63841 32017 63842 32028 63842 32100 63842 32019 63843 32022 63843 32024 63843 32060 63844 31968 63844 31998 63844 32018 63845 32058 63845 32019 63845 32019 63846 32058 63846 32060 63846 32060 63847 31998 63847 32019 63847 32019 63848 31998 63848 32020 63848 32019 63849 32020 63849 32022 63849 32022 63850 32020 63850 32021 63850 32022 63851 32021 63851 32107 63851 32026 63852 32056 63852 32027 63852 32027 63853 32056 63853 32018 63853 32107 63854 32106 63854 32022 63854 32022 63855 32106 63855 32124 63855 32022 63856 32124 63856 32024 63856 32024 63857 32124 63857 32023 63857 32024 63858 32023 63858 32101 63858 32082 63859 32026 63859 32025 63859 32025 63860 32026 63860 32027 63860 32025 63861 32027 63861 32028 63861 32018 63862 32019 63862 32027 63862 32027 63863 32019 63863 32024 63863 32027 63864 32024 63864 32028 63864 32028 63865 32024 63865 32101 63865 32028 63866 32101 63866 32100 63866 32029 63867 32082 63867 32030 63867 32030 63868 32082 63868 32025 63868 32030 63869 32025 63869 31737 63869 31737 63870 32025 63870 32028 63870 31737 63871 32028 63871 31736 63871 31736 63872 32028 63872 32089 63872 31752 63873 32014 63873 32031 63873 31752 63874 32031 63874 31753 63874 31753 63875 32031 63875 32000 63875 31753 63876 32000 63876 32033 63876 32033 63877 32000 63877 32032 63877 32033 63878 32032 63878 32002 63878 32055 63879 31964 63879 32062 63879 31965 63880 31966 63880 32063 63880 32040 63881 32034 63881 32035 63881 31727 63882 32036 63882 32037 63882 31727 63883 32037 63883 31728 63883 32038 63884 31725 63884 32039 63884 32039 63885 31725 63885 31726 63885 32039 63886 31726 63886 32040 63886 32040 63887 31726 63887 31731 63887 32040 63888 31731 63888 32034 63888 32039 63889 32081 63889 32038 63889 32038 63890 32081 63890 32082 63890 32038 63891 32082 63891 32029 63891 32074 63892 32037 63892 32070 63892 32070 63893 32037 63893 32036 63893 32070 63894 32036 63894 32072 63894 32035 63895 32034 63895 32041 63895 32041 63896 32034 63896 32073 63896 32041 63897 32073 63897 32053 63897 32042 63898 32050 63898 32076 63898 32076 63899 32050 63899 32043 63899 32004 63900 32048 63900 32044 63900 32044 63901 32048 63901 32046 63901 32045 63902 32002 63902 32051 63902 32051 63903 32002 63903 32046 63903 32004 63904 32047 63904 32048 63904 32048 63905 32047 63905 32043 63905 32048 63906 32043 63906 32049 63906 32049 63907 32043 63907 32050 63907 32049 63908 32050 63908 32052 63908 32052 63909 32050 63909 32042 63909 32052 63910 32042 63910 32054 63910 32046 63911 32048 63911 32051 63911 32051 63912 32048 63912 32049 63912 32051 63913 32049 63913 32053 63913 32053 63914 32049 63914 32052 63914 32053 63915 32052 63915 32041 63915 32041 63916 32052 63916 32054 63916 32041 63917 32054 63917 32035 63917 32055 63918 32062 63918 31961 63918 32026 63919 32065 63919 32056 63919 32056 63920 32065 63920 32057 63920 32056 63921 32057 63921 32018 63921 32018 63922 32057 63922 32059 63922 32018 63923 32059 63923 32058 63923 32058 63924 32059 63924 32067 63924 32058 63925 32067 63925 32060 63925 32060 63926 32067 63926 32061 63926 32060 63927 32061 63927 31968 63927 31968 63928 32061 63928 32069 63928 31964 63929 31965 63929 32062 63929 32062 63930 31965 63930 32063 63930 32062 63931 32063 63931 32077 63931 32077 63932 32063 63932 32068 63932 32077 63933 32068 63933 32078 63933 32078 63934 32068 63934 32064 63934 32078 63935 32064 63935 32079 63935 32079 63936 32064 63936 32066 63936 32079 63937 32066 63937 32080 63937 32065 63938 32080 63938 32057 63938 32057 63939 32080 63939 32066 63939 32057 63940 32066 63940 32059 63940 32059 63941 32066 63941 32064 63941 32059 63942 32064 63942 32067 63942 32067 63943 32064 63943 32068 63943 32067 63944 32068 63944 32061 63944 32061 63945 32068 63945 32063 63945 32061 63946 32063 63946 32069 63946 32069 63947 32063 63947 31966 63947 32075 63948 32074 63948 31749 63948 31749 63949 32074 63949 32070 63949 31749 63950 32070 63950 32071 63950 32071 63951 32070 63951 32072 63951 32071 63952 32072 63952 31740 63952 31731 63953 31730 63953 32034 63953 32034 63954 31730 63954 31728 63954 32034 63955 31728 63955 32073 63955 32073 63956 31728 63956 32037 63956 32073 63957 32037 63957 32053 63957 32053 63958 32037 63958 32074 63958 32053 63959 32074 63959 32051 63959 32051 63960 32074 63960 32075 63960 32051 63961 32075 63961 32045 63961 32047 63962 31960 63962 32043 63962 32043 63963 31960 63963 31961 63963 32043 63964 31961 63964 32076 63964 32076 63965 31961 63965 32062 63965 32076 63966 32062 63966 32042 63966 32042 63967 32062 63967 32077 63967 32042 63968 32077 63968 32054 63968 32054 63969 32077 63969 32078 63969 32054 63970 32078 63970 32035 63970 32035 63971 32078 63971 32079 63971 32035 63972 32079 63972 32040 63972 32040 63973 32079 63973 32080 63973 32040 63974 32080 63974 32039 63974 32039 63975 32080 63975 32065 63975 32039 63976 32065 63976 32081 63976 32081 63977 32065 63977 32026 63977 32081 63978 32026 63978 32082 63978 32015 63979 32014 63979 31750 63979 32083 63980 32084 63980 32085 63980 32130 63981 31738 63981 31744 63981 32086 63982 31733 63982 32087 63982 32087 63983 31733 63983 31732 63983 32087 63984 31732 63984 32088 63984 32088 63985 31732 63985 32089 63985 32088 63986 32089 63986 32017 63986 32131 63987 31744 63987 31724 63987 32090 63988 32091 63988 32093 63988 32093 63989 32091 63989 32092 63989 32093 63990 32092 63990 32094 63990 32094 63991 32092 63991 32096 63991 32094 63992 32096 63992 32085 63992 32085 63993 32084 63993 32094 63993 32094 63994 32084 63994 32095 63994 32094 63995 32095 63995 32093 63995 32096 63996 32097 63996 32085 63996 32085 63997 32097 63997 32102 63997 32085 63998 32102 63998 32083 63998 32083 63999 32102 63999 32098 63999 32083 64000 32098 64000 32133 64000 32133 64001 32098 64001 32103 64001 32133 64002 32103 64002 32099 64002 32099 64003 32103 64003 32100 64003 32099 64004 32100 64004 32101 64004 32097 64005 32086 64005 32102 64005 32102 64006 32086 64006 32087 64006 32102 64007 32087 64007 32098 64007 32098 64008 32087 64008 32088 64008 32098 64009 32088 64009 32103 64009 32103 64010 32088 64010 32017 64010 32103 64011 32017 64011 32100 64011 32005 64012 32006 64012 32104 64012 32104 64013 32006 64013 32105 64013 32104 64014 32105 64014 32125 64014 32125 64015 32105 64015 32007 64015 32125 64016 32007 64016 32126 64016 32126 64017 32007 64017 32009 64017 32126 64018 32009 64018 32109 64018 32124 64019 32106 64019 32104 64019 32104 64020 32106 64020 32107 64020 32104 64021 32107 64021 32005 64021 32128 64022 32111 64022 32113 64022 32113 64023 32111 64023 32108 64023 32113 64024 32108 64024 32112 64024 32009 64025 32010 64025 32109 64025 32109 64026 32010 64026 32012 64026 32109 64027 32012 64027 32128 64027 32128 64028 32012 64028 32110 64028 32128 64029 32110 64029 32111 64029 32112 64030 32016 64030 32113 64030 32113 64031 32016 64031 32015 64031 32113 64032 32015 64032 32114 64032 32114 64033 32015 64033 31750 64033 32114 64034 31750 64034 31739 64034 31744 64035 32131 64035 32130 64035 32130 64036 32131 64036 32115 64036 32130 64037 32115 64037 32129 64037 32129 64038 32115 64038 32116 64038 32129 64039 32116 64039 32117 64039 32117 64040 32116 64040 32118 64040 32117 64041 32118 64041 32127 64041 32127 64042 32118 64042 32132 64042 32127 64043 32132 64043 32119 64043 32119 64044 32132 64044 32121 64044 32119 64045 32121 64045 32120 64045 32120 64046 32121 64046 32122 64046 32120 64047 32122 64047 32123 64047 32123 64048 32122 64048 32023 64048 32123 64049 32023 64049 32124 64049 32124 64050 32104 64050 32123 64050 32123 64051 32104 64051 32125 64051 32123 64052 32125 64052 32120 64052 32120 64053 32125 64053 32126 64053 32120 64054 32126 64054 32119 64054 32119 64055 32126 64055 32109 64055 32119 64056 32109 64056 32127 64056 32127 64057 32109 64057 32128 64057 32127 64058 32128 64058 32117 64058 32117 64059 32128 64059 32113 64059 32117 64060 32113 64060 32129 64060 32129 64061 32113 64061 32114 64061 32129 64062 32114 64062 32130 64062 32130 64063 32114 64063 31739 64063 32130 64064 31739 64064 31738 64064 31724 64065 32090 64065 32131 64065 32131 64066 32090 64066 32093 64066 32131 64067 32093 64067 32115 64067 32115 64068 32093 64068 32095 64068 32115 64069 32095 64069 32116 64069 32116 64070 32095 64070 32084 64070 32116 64071 32084 64071 32118 64071 32118 64072 32084 64072 32083 64072 32118 64073 32083 64073 32132 64073 32132 64074 32083 64074 32133 64074 32132 64075 32133 64075 32121 64075 32121 64076 32133 64076 32099 64076 32121 64077 32099 64077 32122 64077 32122 64078 32099 64078 32101 64078 32122 64079 32101 64079 32023 64079 32455 64080 32134 64080 32164 64080 32146 64081 32181 64081 32144 64081 32177 64082 32135 64082 32136 64082 32137 64083 32138 64083 32139 64083 32139 64084 32138 64084 32151 64084 32139 64085 32151 64085 32140 64085 32140 64086 32151 64086 32149 64086 32140 64087 32149 64087 32141 64087 32178 64088 32136 64088 32222 64088 32179 64089 32223 64089 32142 64089 32142 64090 32223 64090 32143 64090 32143 64091 32223 64091 32225 64091 32143 64092 32225 64092 32144 64092 32144 64093 32181 64093 32143 64093 32143 64094 32181 64094 32180 64094 32143 64095 32180 64095 32142 64095 32225 64096 32226 64096 32144 64096 32144 64097 32226 64097 32145 64097 32144 64098 32145 64098 32146 64098 32146 64099 32145 64099 32150 64099 32146 64100 32150 64100 32185 64100 32185 64101 32150 64101 32147 64101 32185 64102 32147 64102 32148 64102 32148 64103 32147 64103 32152 64103 32148 64104 32152 64104 32187 64104 32226 64105 32141 64105 32145 64105 32145 64106 32141 64106 32149 64106 32145 64107 32149 64107 32150 64107 32150 64108 32149 64108 32151 64108 32150 64109 32151 64109 32147 64109 32147 64110 32151 64110 32138 64110 32147 64111 32138 64111 32152 64111 32153 64112 32154 64112 32156 64112 32156 64113 32154 64113 32155 64113 32156 64114 32155 64114 32172 64114 32172 64115 32155 64115 32453 64115 32172 64116 32453 64116 32157 64116 32157 64117 32453 64117 32452 64117 32157 64118 32452 64118 32173 64118 32158 64119 32209 64119 32156 64119 32156 64120 32209 64120 32447 64120 32156 64121 32447 64121 32153 64121 32175 64122 32459 64122 32159 64122 32159 64123 32459 64123 32458 64123 32159 64124 32458 64124 32456 64124 32452 64125 32160 64125 32173 64125 32173 64126 32160 64126 32161 64126 32173 64127 32161 64127 32175 64127 32175 64128 32161 64128 32450 64128 32175 64129 32450 64129 32459 64129 32456 64130 32162 64130 32159 64130 32159 64131 32162 64131 32455 64131 32159 64132 32455 64132 32163 64132 32163 64133 32455 64133 32164 64133 32163 64134 32164 64134 32196 64134 32136 64135 32178 64135 32177 64135 32177 64136 32178 64136 32165 64136 32177 64137 32165 64137 32176 64137 32176 64138 32165 64138 32182 64138 32176 64139 32182 64139 32166 64139 32166 64140 32182 64140 32183 64140 32166 64141 32183 64141 32174 64141 32174 64142 32183 64142 32184 64142 32174 64143 32184 64143 32167 64143 32167 64144 32184 64144 32168 64144 32167 64145 32168 64145 32169 64145 32169 64146 32168 64146 32186 64146 32169 64147 32186 64147 32171 64147 32171 64148 32186 64148 32170 64148 32171 64149 32170 64149 32158 64149 32158 64150 32156 64150 32171 64150 32171 64151 32156 64151 32172 64151 32171 64152 32172 64152 32169 64152 32169 64153 32172 64153 32157 64153 32169 64154 32157 64154 32167 64154 32167 64155 32157 64155 32173 64155 32167 64156 32173 64156 32174 64156 32174 64157 32173 64157 32175 64157 32174 64158 32175 64158 32166 64158 32166 64159 32175 64159 32159 64159 32166 64160 32159 64160 32176 64160 32176 64161 32159 64161 32163 64161 32176 64162 32163 64162 32177 64162 32177 64163 32163 64163 32196 64163 32177 64164 32196 64164 32135 64164 32222 64165 32179 64165 32178 64165 32178 64166 32179 64166 32142 64166 32178 64167 32142 64167 32165 64167 32165 64168 32142 64168 32180 64168 32165 64169 32180 64169 32182 64169 32182 64170 32180 64170 32181 64170 32182 64171 32181 64171 32183 64171 32183 64172 32181 64172 32146 64172 32183 64173 32146 64173 32184 64173 32184 64174 32146 64174 32185 64174 32184 64175 32185 64175 32168 64175 32168 64176 32185 64176 32148 64176 32168 64177 32148 64177 32186 64177 32186 64178 32148 64178 32187 64178 32186 64179 32187 64179 32170 64179 32188 64180 32192 64180 32195 64180 32189 64181 32222 64181 32136 64181 32190 64182 32229 64182 32228 64182 32503 64183 32502 64183 32188 64183 32188 64184 32502 64184 32190 64184 32190 64185 32228 64185 32188 64185 32188 64186 32228 64186 32191 64186 32188 64187 32191 64187 32192 64187 32192 64188 32191 64188 32227 64188 32192 64189 32227 64189 32189 64189 32193 64190 32508 64190 32197 64190 32197 64191 32508 64191 32503 64191 32461 64192 32193 64192 32194 64192 32194 64193 32193 64193 32197 64193 32194 64194 32197 64194 32460 64194 32189 64195 32136 64195 32192 64195 32192 64196 32136 64196 32135 64196 32192 64197 32135 64197 32195 64197 32195 64198 32135 64198 32196 64198 32195 64199 32196 64199 32164 64199 32503 64200 32188 64200 32197 64200 32197 64201 32188 64201 32195 64201 32197 64202 32195 64202 32460 64202 32460 64203 32195 64203 32164 64203 32460 64204 32164 64204 32134 64204 32209 64205 32158 64205 32208 64205 32198 64206 32201 64206 32205 64206 32137 64207 32199 64207 32138 64207 32138 64208 32199 64208 32202 64208 32468 64209 32203 64209 32200 64209 32200 64210 32203 64210 32201 64210 32214 64211 32212 64211 32210 64211 32210 64212 32212 64212 32202 64212 32201 64213 32203 64213 32205 64213 32205 64214 32203 64214 32204 64214 32205 64215 32204 64215 32206 64215 32199 64216 32198 64216 32202 64216 32202 64217 32198 64217 32205 64217 32202 64218 32205 64218 32210 64218 32210 64219 32205 64219 32206 64219 32158 64220 32170 64220 32212 64220 32212 64221 32170 64221 32187 64221 32212 64222 32187 64222 32202 64222 32202 64223 32187 64223 32152 64223 32202 64224 32152 64224 32138 64224 32213 64225 32207 64225 32208 64225 32208 64226 32207 64226 32447 64226 32208 64227 32447 64227 32209 64227 32206 64228 32211 64228 32210 64228 32210 64229 32211 64229 32494 64229 32210 64230 32494 64230 32214 64230 32214 64231 32494 64231 32498 64231 32214 64232 32498 64232 32215 64232 32158 64233 32212 64233 32208 64233 32208 64234 32212 64234 32214 64234 32208 64235 32214 64235 32213 64235 32213 64236 32214 64236 32215 64236 32213 64237 32215 64237 32216 64237 32218 64238 32468 64238 32200 64238 32218 64239 32221 64239 32474 64239 32474 64240 32465 64240 32218 64240 32218 64241 32465 64241 32217 64241 32218 64242 32217 64242 32468 64242 32499 64243 32219 64243 32218 64243 32218 64244 32219 64244 32220 64244 32218 64245 32220 64245 32221 64245 32224 64246 32222 64246 32189 64246 32179 64247 32222 64247 32223 64247 32223 64248 32222 64248 32224 64248 32223 64249 32224 64249 32225 64249 32137 64250 32139 64250 32224 64250 32224 64251 32139 64251 32140 64251 32140 64252 32141 64252 32224 64252 32224 64253 32141 64253 32226 64253 32224 64254 32226 64254 32225 64254 32137 64255 32224 64255 32199 64255 32199 64256 32224 64256 32189 64256 32199 64257 32189 64257 32198 64257 32198 64258 32189 64258 32227 64258 32198 64259 32227 64259 32201 64259 32201 64260 32227 64260 32191 64260 32201 64261 32191 64261 32200 64261 32200 64262 32191 64262 32228 64262 32200 64263 32228 64263 32218 64263 32218 64264 32228 64264 32229 64264 32218 64265 32229 64265 32499 64265 32484 64266 32446 64266 32486 64266 32486 64267 32446 64267 32231 64267 32486 64268 32231 64268 32488 64268 32488 64269 32231 64269 32489 64269 32489 64270 32231 64270 32232 64270 32489 64271 32232 64271 32482 64271 32482 64272 32232 64272 32480 64272 32480 64273 32232 64273 32233 64273 32480 64274 32233 64274 32230 64274 32230 64275 32233 64275 32462 64275 32230 64276 32462 64276 32216 64276 32446 64277 32539 64277 32231 64277 32231 64278 32539 64278 32540 64278 32231 64279 32540 64279 32232 64279 32232 64280 32540 64280 32533 64280 32232 64281 32533 64281 32233 64281 32233 64282 32533 64282 32234 64282 32233 64283 32234 64283 32462 64283 32462 64284 32234 64284 32532 64284 32309 64285 32235 64285 32236 64285 32236 64286 32235 64286 32237 64286 32236 64287 32237 64287 32310 64287 32310 64288 32237 64288 32238 64288 32238 64289 32237 64289 32239 64289 32238 64290 32239 64290 32306 64290 32306 64291 32239 64291 32240 64291 32240 64292 32239 64292 32243 64292 32240 64293 32243 64293 32305 64293 32305 64294 32243 64294 32242 64294 32305 64295 32242 64295 32304 64295 32438 64296 32242 64296 32241 64296 32241 64297 32242 64297 32243 64297 32241 64298 32243 64298 32244 64298 32244 64299 32243 64299 32239 64299 32235 64300 32528 64300 32237 64300 32237 64301 32528 64301 32245 64301 32237 64302 32245 64302 32239 64302 32239 64303 32245 64303 32530 64303 32239 64304 32530 64304 32244 64304 32304 64305 32242 64305 32268 64305 32268 64306 32242 64306 32542 64306 32268 64307 32542 64307 32246 64307 32247 64308 32272 64308 32542 64308 32542 64309 32272 64309 32271 64309 32542 64310 32271 64310 32246 64310 32517 64311 32248 64311 32281 64311 32281 64312 32248 64312 32249 64312 32281 64313 32249 64313 32250 64313 32250 64314 32249 64314 32525 64314 32254 64315 32252 64315 32329 64315 32254 64316 32329 64316 32250 64316 32250 64317 32329 64317 32251 64317 32250 64318 32251 64318 32323 64318 32252 64319 32254 64319 32253 64319 32253 64320 32254 64320 32255 64320 32253 64321 32255 64321 32297 64321 32235 64322 32309 64322 32294 64322 32235 64323 32294 64323 32255 64323 32255 64324 32294 64324 32256 64324 32255 64325 32256 64325 32297 64325 32272 64326 32247 64326 32257 64326 32257 64327 32247 64327 32258 64327 32257 64328 32258 64328 32359 64328 32359 64329 32258 64329 32523 64329 32359 64330 32523 64330 32259 64330 32259 64331 32523 64331 32522 64331 32259 64332 32522 64332 32260 64332 32260 64333 32522 64333 32261 64333 32260 64334 32261 64334 32360 64334 32360 64335 32261 64335 32365 64335 32365 64336 32261 64336 32366 64336 32366 64337 32261 64337 32264 64337 32366 64338 32264 64338 32368 64338 32517 64339 32407 64339 32262 64339 32262 64340 32407 64340 32371 64340 32262 64341 32371 64341 32519 64341 32371 64342 32370 64342 32519 64342 32519 64343 32370 64343 32364 64343 32519 64344 32364 64344 32263 64344 32263 64345 32364 64345 32363 64345 32263 64346 32363 64346 32264 64346 32264 64347 32363 64347 32265 64347 32264 64348 32265 64348 32368 64348 32279 64349 32341 64349 32340 64349 32341 64350 32279 64350 32357 64350 32269 64351 32270 64351 32266 64351 32267 64352 32304 64352 32268 64352 32276 64353 32318 64353 32269 64353 32269 64354 32318 64354 32267 64354 32267 64355 32268 64355 32269 64355 32269 64356 32268 64356 32246 64356 32269 64357 32246 64357 32270 64357 32270 64358 32246 64358 32271 64358 32270 64359 32271 64359 32272 64359 32286 64360 32273 64360 32277 64360 32277 64361 32273 64361 32276 64361 32272 64362 32274 64362 32270 64362 32270 64363 32274 64363 32362 64363 32270 64364 32362 64364 32266 64364 32266 64365 32362 64365 32393 64365 32266 64366 32393 64366 32392 64366 32275 64367 32286 64367 32278 64367 32278 64368 32286 64368 32277 64368 32278 64369 32277 64369 32279 64369 32276 64370 32269 64370 32277 64370 32277 64371 32269 64371 32266 64371 32277 64372 32266 64372 32279 64372 32279 64373 32266 64373 32392 64373 32279 64374 32392 64374 32357 64374 32394 64375 32275 64375 32404 64375 32404 64376 32275 64376 32278 64376 32404 64377 32278 64377 32280 64377 32280 64378 32278 64378 32279 64378 32280 64379 32279 64379 32401 64379 32401 64380 32279 64380 32340 64380 32407 64381 32517 64381 32416 64381 32416 64382 32517 64382 32281 64382 32416 64383 32281 64383 32419 64383 32419 64384 32281 64384 32420 64384 32420 64385 32281 64385 32250 64385 32420 64386 32250 64386 32323 64386 32251 64387 32329 64387 32330 64387 32256 64388 32294 64388 32296 64388 32292 64389 32282 64389 32293 64389 32396 64390 32395 64390 32302 64390 32396 64391 32302 64391 32299 64391 32289 64392 32283 64392 32282 64392 32282 64393 32283 64393 32284 64393 32282 64394 32284 64394 32293 64394 32293 64395 32284 64395 32397 64395 32293 64396 32397 64396 32285 64396 32275 64397 32288 64397 32286 64397 32286 64398 32288 64398 32287 64398 32286 64399 32287 64399 32273 64399 32273 64400 32287 64400 32335 64400 32290 64401 32335 64401 32292 64401 32292 64402 32335 64402 32287 64402 32292 64403 32287 64403 32282 64403 32282 64404 32287 64404 32288 64404 32282 64405 32288 64405 32289 64405 32289 64406 32288 64406 32275 64406 32289 64407 32275 64407 32394 64407 32303 64408 32302 64408 32327 64408 32327 64409 32302 64409 32395 64409 32327 64410 32395 64410 32328 64410 32290 64411 32292 64411 32291 64411 32291 64412 32292 64412 32293 64412 32291 64413 32293 64413 32333 64413 32333 64414 32293 64414 32285 64414 32333 64415 32285 64415 32332 64415 32332 64416 32285 64416 32300 64416 32332 64417 32300 64417 32301 64417 32296 64418 32294 64418 32319 64418 32311 64419 32295 64419 32296 64419 32329 64420 32252 64420 32295 64420 32295 64421 32252 64421 32253 64421 32295 64422 32253 64422 32296 64422 32296 64423 32253 64423 32297 64423 32296 64424 32297 64424 32256 64424 32397 64425 32298 64425 32285 64425 32285 64426 32298 64426 32299 64426 32285 64427 32299 64427 32300 64427 32300 64428 32299 64428 32302 64428 32300 64429 32302 64429 32301 64429 32301 64430 32302 64430 32303 64430 32301 64431 32303 64431 32330 64431 32304 64432 32267 64432 32322 64432 32304 64433 32322 64433 32305 64433 32305 64434 32322 64434 32307 64434 32305 64435 32307 64435 32240 64435 32240 64436 32307 64436 32306 64436 32306 64437 32307 64437 32308 64437 32306 64438 32308 64438 32238 64438 32294 64439 32309 64439 32319 64439 32319 64440 32309 64440 32236 64440 32319 64441 32236 64441 32308 64441 32308 64442 32236 64442 32310 64442 32308 64443 32310 64443 32238 64443 32311 64444 32312 64444 32331 64444 32331 64445 32312 64445 32320 64445 32331 64446 32320 64446 32313 64446 32313 64447 32320 64447 32314 64447 32313 64448 32314 64448 32315 64448 32315 64449 32314 64449 32321 64449 32315 64450 32321 64450 32334 64450 32334 64451 32321 64451 32316 64451 32334 64452 32316 64452 32317 64452 32317 64453 32316 64453 32318 64453 32317 64454 32318 64454 32276 64454 32311 64455 32296 64455 32312 64455 32312 64456 32296 64456 32319 64456 32312 64457 32319 64457 32320 64457 32320 64458 32319 64458 32308 64458 32320 64459 32308 64459 32314 64459 32314 64460 32308 64460 32307 64460 32314 64461 32307 64461 32321 64461 32321 64462 32307 64462 32322 64462 32321 64463 32322 64463 32316 64463 32316 64464 32322 64464 32267 64464 32316 64465 32267 64465 32318 64465 32323 64466 32251 64466 32324 64466 32324 64467 32251 64467 32330 64467 32324 64468 32330 64468 32325 64468 32325 64469 32330 64469 32303 64469 32325 64470 32303 64470 32326 64470 32326 64471 32303 64471 32327 64471 32326 64472 32327 64472 32408 64472 32408 64473 32327 64473 32328 64473 32408 64474 32328 64474 32406 64474 32329 64475 32295 64475 32330 64475 32330 64476 32295 64476 32311 64476 32330 64477 32311 64477 32301 64477 32301 64478 32311 64478 32331 64478 32301 64479 32331 64479 32332 64479 32332 64480 32331 64480 32313 64480 32332 64481 32313 64481 32333 64481 32333 64482 32313 64482 32315 64482 32333 64483 32315 64483 32291 64483 32291 64484 32315 64484 32334 64484 32291 64485 32334 64485 32290 64485 32290 64486 32334 64486 32317 64486 32290 64487 32317 64487 32335 64487 32335 64488 32317 64488 32276 64488 32335 64489 32276 64489 32273 64489 32371 64490 32407 64490 32415 64490 32391 64491 32390 64491 32350 64491 32336 64492 32385 64492 32373 64492 32337 64493 32400 64493 32338 64493 32338 64494 32400 64494 32339 64494 32338 64495 32339 64495 32356 64495 32356 64496 32339 64496 32340 64496 32356 64497 32340 64497 32341 64497 32342 64498 32373 64498 32343 64498 32386 64499 32344 64499 32345 64499 32345 64500 32344 64500 32346 64500 32345 64501 32346 64501 32347 64501 32347 64502 32346 64502 32348 64502 32347 64503 32348 64503 32350 64503 32350 64504 32390 64504 32347 64504 32347 64505 32390 64505 32349 64505 32347 64506 32349 64506 32345 64506 32348 64507 32398 64507 32350 64507 32350 64508 32398 64508 32354 64508 32350 64509 32354 64509 32391 64509 32391 64510 32354 64510 32355 64510 32391 64511 32355 64511 32352 64511 32352 64512 32355 64512 32351 64512 32352 64513 32351 64513 32353 64513 32353 64514 32351 64514 32357 64514 32353 64515 32357 64515 32392 64515 32398 64516 32337 64516 32354 64516 32354 64517 32337 64517 32338 64517 32354 64518 32338 64518 32355 64518 32355 64519 32338 64519 32356 64519 32355 64520 32356 64520 32351 64520 32351 64521 32356 64521 32341 64521 32351 64522 32341 64522 32357 64522 32257 64523 32359 64523 32358 64523 32358 64524 32359 64524 32259 64524 32358 64525 32259 64525 32381 64525 32381 64526 32259 64526 32260 64526 32381 64527 32260 64527 32361 64527 32361 64528 32260 64528 32360 64528 32361 64529 32360 64529 32384 64529 32362 64530 32274 64530 32358 64530 32358 64531 32274 64531 32272 64531 32358 64532 32272 64532 32257 64532 32367 64533 32265 64533 32369 64533 32369 64534 32265 64534 32363 64534 32369 64535 32363 64535 32364 64535 32360 64536 32365 64536 32384 64536 32384 64537 32365 64537 32366 64537 32384 64538 32366 64538 32367 64538 32367 64539 32366 64539 32368 64539 32367 64540 32368 64540 32265 64540 32364 64541 32370 64541 32369 64541 32369 64542 32370 64542 32371 64542 32369 64543 32371 64543 32372 64543 32372 64544 32371 64544 32415 64544 32372 64545 32415 64545 32414 64545 32373 64546 32342 64546 32336 64546 32336 64547 32342 64547 32387 64547 32336 64548 32387 64548 32374 64548 32374 64549 32387 64549 32388 64549 32374 64550 32388 64550 32375 64550 32375 64551 32388 64551 32389 64551 32375 64552 32389 64552 32383 64552 32383 64553 32389 64553 32376 64553 32383 64554 32376 64554 32377 64554 32377 64555 32376 64555 32378 64555 32377 64556 32378 64556 32382 64556 32382 64557 32378 64557 32379 64557 32382 64558 32379 64558 32380 64558 32380 64559 32379 64559 32393 64559 32380 64560 32393 64560 32362 64560 32362 64561 32358 64561 32380 64561 32380 64562 32358 64562 32381 64562 32380 64563 32381 64563 32382 64563 32382 64564 32381 64564 32361 64564 32382 64565 32361 64565 32377 64565 32377 64566 32361 64566 32384 64566 32377 64567 32384 64567 32383 64567 32383 64568 32384 64568 32367 64568 32383 64569 32367 64569 32375 64569 32375 64570 32367 64570 32369 64570 32375 64571 32369 64571 32374 64571 32374 64572 32369 64572 32372 64572 32374 64573 32372 64573 32336 64573 32336 64574 32372 64574 32414 64574 32336 64575 32414 64575 32385 64575 32343 64576 32386 64576 32342 64576 32342 64577 32386 64577 32345 64577 32342 64578 32345 64578 32387 64578 32387 64579 32345 64579 32349 64579 32387 64580 32349 64580 32388 64580 32388 64581 32349 64581 32390 64581 32388 64582 32390 64582 32389 64582 32389 64583 32390 64583 32391 64583 32389 64584 32391 64584 32376 64584 32376 64585 32391 64585 32352 64585 32376 64586 32352 64586 32378 64586 32378 64587 32352 64587 32353 64587 32378 64588 32353 64588 32379 64588 32379 64589 32353 64589 32392 64589 32379 64590 32392 64590 32393 64590 32399 64591 32343 64591 32410 64591 32405 64592 32394 64592 32404 64592 32289 64593 32394 64593 32283 64593 32283 64594 32394 64594 32405 64594 32283 64595 32405 64595 32284 64595 32284 64596 32405 64596 32397 64596 32328 64597 32395 64597 32405 64597 32405 64598 32395 64598 32396 64598 32396 64599 32299 64599 32405 64599 32405 64600 32299 64600 32298 64600 32405 64601 32298 64601 32397 64601 32337 64602 32398 64602 32399 64602 32399 64603 32398 64603 32348 64603 32386 64604 32343 64604 32344 64604 32344 64605 32343 64605 32399 64605 32344 64606 32399 64606 32346 64606 32346 64607 32399 64607 32348 64607 32340 64608 32339 64608 32399 64608 32399 64609 32339 64609 32400 64609 32399 64610 32400 64610 32337 64610 32340 64611 32399 64611 32401 64611 32401 64612 32399 64612 32410 64612 32401 64613 32410 64613 32280 64613 32280 64614 32410 64614 32402 64614 32280 64615 32402 64615 32404 64615 32404 64616 32402 64616 32403 64616 32404 64617 32403 64617 32405 64617 32405 64618 32403 64618 32406 64618 32405 64619 32406 64619 32328 64619 32415 64620 32407 64620 32416 64620 32385 64621 32414 64621 32413 64621 32324 64622 32325 64622 32418 64622 32326 64623 32408 64623 32409 64623 32408 64624 32406 64624 32409 64624 32409 64625 32406 64625 32403 64625 32409 64626 32403 64626 32412 64626 32412 64627 32403 64627 32402 64627 32412 64628 32402 64628 32411 64628 32411 64629 32402 64629 32410 64629 32411 64630 32410 64630 32373 64630 32373 64631 32410 64631 32343 64631 32373 64632 32385 64632 32411 64632 32411 64633 32385 64633 32413 64633 32411 64634 32413 64634 32412 64634 32412 64635 32413 64635 32417 64635 32412 64636 32417 64636 32409 64636 32409 64637 32417 64637 32418 64637 32409 64638 32418 64638 32326 64638 32326 64639 32418 64639 32325 64639 32414 64640 32415 64640 32413 64640 32413 64641 32415 64641 32416 64641 32413 64642 32416 64642 32417 64642 32417 64643 32416 64643 32419 64643 32417 64644 32419 64644 32418 64644 32418 64645 32419 64645 32420 64645 32418 64646 32420 64646 32324 64646 32324 64647 32420 64647 32323 64647 32244 64648 32421 64648 32464 64648 32244 64649 32464 64649 32439 64649 32464 64650 32463 64650 32439 64650 32439 64651 32463 64651 32422 64651 32439 64652 32422 64652 32441 64652 32441 64653 32422 64653 32531 64653 32531 64654 32422 64654 32462 64654 32531 64655 32462 64655 32532 64655 32430 64656 32423 64656 32425 64656 32425 64657 32423 64657 32424 64657 32425 64658 32424 64658 32426 64658 32426 64659 32424 64659 32536 64659 32426 64660 32536 64660 32442 64660 32442 64661 32536 64661 32427 64661 32442 64662 32427 64662 32428 64662 32428 64663 32427 64663 32538 64663 32428 64664 32538 64664 32445 64664 32445 64665 32538 64665 32429 64665 32445 64666 32429 64666 32446 64666 32446 64667 32429 64667 32539 64667 32527 64668 32423 64668 32430 64668 32449 64669 32529 64669 32431 64669 32430 64670 32454 64670 32527 64670 32527 64671 32454 64671 32432 64671 32527 64672 32432 64672 32431 64672 32431 64673 32432 64673 32457 64673 32431 64674 32457 64674 32449 64674 32449 64675 32433 64675 32529 64675 32529 64676 32433 64676 32437 64676 32529 64677 32437 64677 32436 64677 32464 64678 32421 64678 32434 64678 32434 64679 32421 64679 32435 64679 32434 64680 32435 64680 32448 64680 32448 64681 32435 64681 32436 64681 32448 64682 32436 64682 32451 64682 32451 64683 32436 64683 32437 64683 32441 64684 32531 64684 32524 64684 32241 64685 32244 64685 32438 64685 32438 64686 32244 64686 32439 64686 32438 64687 32439 64687 32440 64687 32440 64688 32439 64688 32441 64688 32440 64689 32441 64689 32541 64689 32541 64690 32441 64690 32524 64690 32461 64691 32442 64691 32443 64691 32443 64692 32442 64692 32428 64692 32443 64693 32428 64693 32444 64693 32444 64694 32428 64694 32445 64694 32444 64695 32445 64695 32477 64695 32477 64696 32445 64696 32483 64696 32483 64697 32445 64697 32446 64697 32483 64698 32446 64698 32484 64698 32447 64699 32464 64699 32153 64699 32153 64700 32464 64700 32434 64700 32153 64701 32434 64701 32154 64701 32154 64702 32434 64702 32448 64702 32433 64703 32449 64703 32450 64703 32450 64704 32161 64704 32433 64704 32433 64705 32161 64705 32160 64705 32433 64706 32160 64706 32437 64706 32437 64707 32160 64707 32452 64707 32437 64708 32452 64708 32451 64708 32451 64709 32452 64709 32453 64709 32451 64710 32453 64710 32448 64710 32448 64711 32453 64711 32155 64711 32448 64712 32155 64712 32154 64712 32430 64713 32134 64713 32454 64713 32454 64714 32134 64714 32455 64714 32454 64715 32455 64715 32432 64715 32455 64716 32162 64716 32432 64716 32432 64717 32162 64717 32456 64717 32432 64718 32456 64718 32457 64718 32457 64719 32456 64719 32458 64719 32457 64720 32458 64720 32449 64720 32449 64721 32458 64721 32459 64721 32449 64722 32459 64722 32450 64722 32134 64723 32430 64723 32460 64723 32460 64724 32430 64724 32425 64724 32460 64725 32425 64725 32194 64725 32194 64726 32425 64726 32426 64726 32194 64727 32426 64727 32461 64727 32461 64728 32426 64728 32442 64728 32216 64729 32462 64729 32422 64729 32216 64730 32422 64730 32213 64730 32213 64731 32422 64731 32463 64731 32213 64732 32463 64732 32207 64732 32207 64733 32463 64733 32464 64733 32207 64734 32464 64734 32447 64734 32499 64735 32229 64735 32190 64735 32219 64736 32499 64736 32500 64736 32474 64737 32473 64737 32465 64737 32465 64738 32473 64738 32466 64738 32465 64739 32466 64739 32217 64739 32217 64740 32466 64740 32467 64740 32217 64741 32467 64741 32468 64741 32468 64742 32467 64742 32203 64742 32472 64743 32206 64743 32204 64743 32515 64744 32469 64744 32470 64744 32470 64745 32469 64745 32471 64745 32470 64746 32471 64746 32472 64746 32472 64747 32471 64747 32211 64747 32472 64748 32211 64748 32206 64748 32505 64749 32473 64749 32504 64749 32504 64750 32473 64750 32474 64750 32504 64751 32474 64751 32221 64751 32505 64752 32515 64752 32473 64752 32473 64753 32515 64753 32470 64753 32473 64754 32470 64754 32466 64754 32466 64755 32470 64755 32472 64755 32466 64756 32472 64756 32467 64756 32467 64757 32472 64757 32204 64757 32467 64758 32204 64758 32203 64758 32507 64759 32511 64759 32505 64759 32505 64760 32511 64760 32513 64760 32505 64761 32513 64761 32515 64761 32220 64762 32219 64762 32475 64762 32475 64763 32219 64763 32500 64763 32475 64764 32500 64764 32506 64764 32506 64765 32500 64765 32501 64765 32509 64766 32476 64766 32478 64766 32443 64767 32444 64767 32476 64767 32476 64768 32444 64768 32477 64768 32476 64769 32477 64769 32478 64769 32478 64770 32477 64770 32483 64770 32478 64771 32483 64771 32485 64771 32193 64772 32461 64772 32510 64772 32510 64773 32461 64773 32443 64773 32216 64774 32215 64774 32479 64774 32216 64775 32479 64775 32230 64775 32230 64776 32479 64776 32481 64776 32230 64777 32481 64777 32480 64777 32480 64778 32481 64778 32482 64778 32482 64779 32481 64779 32487 64779 32482 64780 32487 64780 32489 64780 32483 64781 32484 64781 32485 64781 32485 64782 32484 64782 32486 64782 32485 64783 32486 64783 32487 64783 32487 64784 32486 64784 32488 64784 32487 64785 32488 64785 32489 64785 32509 64786 32495 64786 32490 64786 32490 64787 32495 64787 32491 64787 32490 64788 32491 64788 32512 64788 32512 64789 32491 64789 32493 64789 32512 64790 32493 64790 32492 64790 32492 64791 32493 64791 32496 64791 32492 64792 32496 64792 32514 64792 32514 64793 32496 64793 32497 64793 32514 64794 32497 64794 32516 64794 32516 64795 32497 64795 32498 64795 32516 64796 32498 64796 32494 64796 32509 64797 32478 64797 32495 64797 32495 64798 32478 64798 32485 64798 32495 64799 32485 64799 32491 64799 32491 64800 32485 64800 32487 64800 32491 64801 32487 64801 32493 64801 32493 64802 32487 64802 32481 64802 32493 64803 32481 64803 32496 64803 32496 64804 32481 64804 32479 64804 32496 64805 32479 64805 32497 64805 32497 64806 32479 64806 32215 64806 32497 64807 32215 64807 32498 64807 32499 64808 32190 64808 32500 64808 32500 64809 32190 64809 32502 64809 32500 64810 32502 64810 32501 64810 32501 64811 32502 64811 32503 64811 32501 64812 32503 64812 32508 64812 32221 64813 32220 64813 32504 64813 32504 64814 32220 64814 32475 64814 32504 64815 32475 64815 32505 64815 32505 64816 32475 64816 32506 64816 32505 64817 32506 64817 32507 64817 32507 64818 32506 64818 32501 64818 32507 64819 32501 64819 32510 64819 32510 64820 32501 64820 32508 64820 32510 64821 32508 64821 32193 64821 32443 64822 32476 64822 32510 64822 32510 64823 32476 64823 32509 64823 32510 64824 32509 64824 32507 64824 32507 64825 32509 64825 32490 64825 32507 64826 32490 64826 32511 64826 32511 64827 32490 64827 32512 64827 32511 64828 32512 64828 32513 64828 32513 64829 32512 64829 32492 64829 32513 64830 32492 64830 32515 64830 32515 64831 32492 64831 32514 64831 32515 64832 32514 64832 32469 64832 32469 64833 32514 64833 32516 64833 32469 64834 32516 64834 32471 64834 32471 64835 32516 64835 32494 64835 32471 64836 32494 64836 32211 64836 32248 64837 32517 64837 32537 64837 32537 64838 32517 64838 32262 64838 32537 64839 32262 64839 32518 64839 32262 64840 32519 64840 32518 64840 32518 64841 32519 64841 32263 64841 32518 64842 32263 64842 32520 64842 32520 64843 32263 64843 32264 64843 32520 64844 32264 64844 32534 64844 32534 64845 32264 64845 32261 64845 32534 64846 32261 64846 32521 64846 32521 64847 32261 64847 32522 64847 32521 64848 32522 64848 32523 64848 32247 64849 32541 64849 32258 64849 32258 64850 32541 64850 32524 64850 32258 64851 32524 64851 32523 64851 32523 64852 32524 64852 32531 64852 32523 64853 32531 64853 32521 64853 32250 64854 32525 64854 32254 64854 32254 64855 32525 64855 32526 64855 32254 64856 32526 64856 32255 64856 32255 64857 32526 64857 32535 64857 32255 64858 32535 64858 32235 64858 32235 64859 32535 64859 32528 64859 32421 64860 32244 64860 32530 64860 32423 64861 32527 64861 32535 64861 32535 64862 32527 64862 32431 64862 32535 64863 32431 64863 32528 64863 32528 64864 32431 64864 32529 64864 32528 64865 32529 64865 32245 64865 32245 64866 32529 64866 32436 64866 32245 64867 32436 64867 32530 64867 32530 64868 32436 64868 32435 64868 32530 64869 32435 64869 32421 64869 32540 64870 32520 64870 32534 64870 32531 64871 32532 64871 32521 64871 32521 64872 32532 64872 32234 64872 32521 64873 32234 64873 32534 64873 32534 64874 32234 64874 32533 64874 32534 64875 32533 64875 32540 64875 32535 64876 32526 64876 32423 64876 32423 64877 32526 64877 32525 64877 32423 64878 32525 64878 32424 64878 32424 64879 32525 64879 32249 64879 32424 64880 32249 64880 32536 64880 32536 64881 32249 64881 32248 64881 32536 64882 32248 64882 32427 64882 32427 64883 32248 64883 32537 64883 32427 64884 32537 64884 32538 64884 32538 64885 32537 64885 32518 64885 32538 64886 32518 64886 32429 64886 32429 64887 32518 64887 32520 64887 32429 64888 32520 64888 32539 64888 32539 64889 32520 64889 32540 64889 32541 64890 32247 64890 32542 64890 32541 64891 32542 64891 32440 64891 32440 64892 32542 64892 32242 64892 32440 64893 32242 64893 32438 64893 32950 64894 32543 64894 32555 64894 32555 64895 32543 64895 32760 64895 32555 64896 32760 64896 32724 64896 32724 64897 32760 64897 32544 64897 32763 64898 32573 64898 32545 64898 32545 64899 32573 64899 32565 64899 32545 64900 32565 64900 32754 64900 32565 64901 32566 64901 32754 64901 32754 64902 32566 64902 32567 64902 32754 64903 32567 64903 32546 64903 32546 64904 32567 64904 32570 64904 32546 64905 32570 64905 32756 64905 32756 64906 32570 64906 32562 64906 32756 64907 32562 64907 32549 64907 32945 64908 32548 64908 32547 64908 32547 64909 32548 64909 32757 64909 32547 64910 32757 64910 32559 64910 32559 64911 32757 64911 32549 64911 32559 64912 32549 64912 32561 64912 32561 64913 32549 64913 32562 64913 32550 64914 32551 64914 32744 64914 32739 64915 32944 64915 32552 64915 32552 64916 32944 64916 32946 64916 32552 64917 32946 64917 32768 64917 32768 64918 32946 64918 32550 64918 32768 64919 32550 64919 32766 64919 32766 64920 32550 64920 32744 64920 32597 64921 32950 64921 32553 64921 32553 64922 32950 64922 32555 64922 32553 64923 32555 64923 32554 64923 32554 64924 32555 64924 32724 64924 32554 64925 32724 64925 32556 64925 32701 64926 32945 64926 32557 64926 32557 64927 32945 64927 32547 64927 32557 64928 32547 64928 32558 64928 32558 64929 32547 64929 32559 64929 32558 64930 32559 64930 32560 64930 32560 64931 32559 64931 32561 64931 32560 64932 32561 64932 32648 64932 32648 64933 32561 64933 32562 64933 32648 64934 32562 64934 32563 64934 32563 64935 32562 64935 32653 64935 32653 64936 32562 64936 32564 64936 32564 64937 32562 64937 32570 64937 32564 64938 32570 64938 32571 64938 32573 64939 32572 64939 32565 64939 32565 64940 32572 64940 32655 64940 32565 64941 32655 64941 32566 64941 32655 64942 32654 64942 32566 64942 32566 64943 32654 64943 32651 64943 32566 64944 32651 64944 32567 64944 32567 64945 32651 64945 32568 64945 32567 64946 32568 64946 32570 64946 32570 64947 32568 64947 32569 64947 32570 64948 32569 64948 32571 64948 32572 64949 32573 64949 32690 64949 32690 64950 32573 64950 32574 64950 32690 64951 32574 64951 32685 64951 32685 64952 32574 64952 32575 64952 32685 64953 32575 64953 32597 64953 32597 64954 32575 64954 32950 64954 32601 64955 32947 64955 32576 64955 32601 64956 32576 64956 32707 64956 32707 64957 32576 64957 32577 64957 32707 64958 32577 64958 32578 64958 32578 64959 32577 64959 32945 64959 32578 64960 32945 64960 32701 64960 32723 64961 32579 64961 32580 64961 32581 64962 32723 64962 32617 64962 32710 64963 32588 64963 32582 64963 32582 64964 32588 64964 32589 64964 32582 64965 32589 64965 32583 64965 32583 64966 32589 64966 32591 64966 32583 64967 32591 64967 32711 64967 32711 64968 32591 64968 32695 64968 32590 64969 32702 64969 32592 64969 32629 64970 32585 64970 32584 64970 32584 64971 32585 64971 32630 64971 32584 64972 32630 64972 32590 64972 32590 64973 32630 64973 32703 64973 32590 64974 32703 64974 32702 64974 32587 64975 32588 64975 32586 64975 32586 64976 32588 64976 32710 64976 32586 64977 32710 64977 32709 64977 32587 64978 32629 64978 32588 64978 32588 64979 32629 64979 32584 64979 32588 64980 32584 64980 32589 64980 32589 64981 32584 64981 32590 64981 32589 64982 32590 64982 32591 64982 32591 64983 32590 64983 32592 64983 32591 64984 32592 64984 32695 64984 32625 64985 32627 64985 32587 64985 32587 64986 32627 64986 32628 64986 32587 64987 32628 64987 32629 64987 32712 64988 32581 64988 32593 64988 32593 64989 32581 64989 32617 64989 32593 64990 32617 64990 32620 64990 32620 64991 32617 64991 32621 64991 32603 64992 32602 64992 32611 64992 32624 64993 32594 64993 32611 64993 32553 64994 32554 64994 32594 64994 32594 64995 32554 64995 32556 64995 32594 64996 32556 64996 32611 64996 32611 64997 32556 64997 32595 64997 32611 64998 32595 64998 32603 64998 32596 64999 32597 64999 32622 64999 32622 65000 32597 65000 32553 65000 32598 65001 32729 65001 32614 65001 32614 65002 32729 65002 32599 65002 32614 65003 32599 65003 32600 65003 32600 65004 32599 65004 32601 65004 32600 65005 32601 65005 32706 65005 32598 65006 32614 65006 32725 65006 32725 65007 32614 65007 32612 65007 32725 65008 32612 65008 32727 65008 32602 65009 32603 65009 32612 65009 32612 65010 32603 65010 32604 65010 32612 65011 32604 65011 32727 65011 32624 65012 32605 65012 32626 65012 32626 65013 32605 65013 32606 65013 32626 65014 32606 65014 32607 65014 32607 65015 32606 65015 32613 65015 32607 65016 32613 65016 32608 65016 32608 65017 32613 65017 32615 65017 32608 65018 32615 65018 32609 65018 32609 65019 32615 65019 32616 65019 32609 65020 32616 65020 32610 65020 32610 65021 32616 65021 32705 65021 32610 65022 32705 65022 32704 65022 32624 65023 32611 65023 32605 65023 32605 65024 32611 65024 32602 65024 32605 65025 32602 65025 32606 65025 32606 65026 32602 65026 32612 65026 32606 65027 32612 65027 32613 65027 32613 65028 32612 65028 32614 65028 32613 65029 32614 65029 32615 65029 32615 65030 32614 65030 32600 65030 32615 65031 32600 65031 32616 65031 32616 65032 32600 65032 32706 65032 32616 65033 32706 65033 32705 65033 32723 65034 32580 65034 32617 65034 32617 65035 32580 65035 32618 65035 32617 65036 32618 65036 32621 65036 32621 65037 32618 65037 32619 65037 32621 65038 32619 65038 32623 65038 32709 65039 32712 65039 32586 65039 32586 65040 32712 65040 32593 65040 32586 65041 32593 65041 32587 65041 32587 65042 32593 65042 32620 65042 32587 65043 32620 65043 32625 65043 32625 65044 32620 65044 32621 65044 32625 65045 32621 65045 32622 65045 32622 65046 32621 65046 32623 65046 32622 65047 32623 65047 32596 65047 32553 65048 32594 65048 32622 65048 32622 65049 32594 65049 32624 65049 32622 65050 32624 65050 32625 65050 32625 65051 32624 65051 32626 65051 32625 65052 32626 65052 32627 65052 32627 65053 32626 65053 32607 65053 32627 65054 32607 65054 32628 65054 32628 65055 32607 65055 32608 65055 32628 65056 32608 65056 32629 65056 32629 65057 32608 65057 32609 65057 32629 65058 32609 65058 32585 65058 32585 65059 32609 65059 32610 65059 32585 65060 32610 65060 32630 65060 32630 65061 32610 65061 32704 65061 32630 65062 32704 65062 32703 65062 32655 65063 32572 65063 32631 65063 32639 65064 32632 65064 32633 65064 32669 65065 32671 65065 32686 65065 32634 65066 32692 65066 32716 65066 32716 65067 32692 65067 32646 65067 32716 65068 32646 65068 32717 65068 32717 65069 32646 65069 32644 65069 32717 65070 32644 65070 32643 65070 32672 65071 32686 65071 32714 65071 32635 65072 32637 65072 32674 65072 32674 65073 32637 65073 32636 65073 32636 65074 32637 65074 32715 65074 32636 65075 32715 65075 32633 65075 32633 65076 32632 65076 32636 65076 32636 65077 32632 65077 32675 65077 32636 65078 32675 65078 32674 65078 32715 65079 32638 65079 32633 65079 32633 65080 32638 65080 32645 65080 32633 65081 32645 65081 32639 65081 32639 65082 32645 65082 32641 65082 32639 65083 32641 65083 32640 65083 32640 65084 32641 65084 32647 65084 32640 65085 32647 65085 32642 65085 32642 65086 32647 65086 32699 65086 32642 65087 32699 65087 32679 65087 32638 65088 32643 65088 32645 65088 32645 65089 32643 65089 32644 65089 32645 65090 32644 65090 32641 65090 32641 65091 32644 65091 32646 65091 32641 65092 32646 65092 32647 65092 32647 65093 32646 65093 32692 65093 32647 65094 32692 65094 32699 65094 32557 65095 32558 65095 32650 65095 32650 65096 32558 65096 32560 65096 32650 65097 32560 65097 32664 65097 32664 65098 32560 65098 32648 65098 32664 65099 32648 65099 32666 65099 32666 65100 32648 65100 32563 65100 32666 65101 32563 65101 32652 65101 32663 65102 32649 65102 32650 65102 32650 65103 32649 65103 32701 65103 32650 65104 32701 65104 32557 65104 32667 65105 32569 65105 32668 65105 32668 65106 32569 65106 32568 65106 32668 65107 32568 65107 32651 65107 32563 65108 32653 65108 32652 65108 32652 65109 32653 65109 32564 65109 32652 65110 32564 65110 32667 65110 32667 65111 32564 65111 32571 65111 32667 65112 32571 65112 32569 65112 32651 65113 32654 65113 32668 65113 32668 65114 32654 65114 32655 65114 32668 65115 32655 65115 32670 65115 32670 65116 32655 65116 32631 65116 32670 65117 32631 65117 32687 65117 32686 65118 32672 65118 32669 65118 32669 65119 32672 65119 32673 65119 32669 65120 32673 65120 32656 65120 32656 65121 32673 65121 32676 65121 32656 65122 32676 65122 32657 65122 32657 65123 32676 65123 32659 65123 32657 65124 32659 65124 32658 65124 32658 65125 32659 65125 32677 65125 32658 65126 32677 65126 32660 65126 32660 65127 32677 65127 32661 65127 32660 65128 32661 65128 32665 65128 32665 65129 32661 65129 32678 65129 32665 65130 32678 65130 32662 65130 32662 65131 32678 65131 32680 65131 32662 65132 32680 65132 32663 65132 32663 65133 32650 65133 32662 65133 32662 65134 32650 65134 32664 65134 32662 65135 32664 65135 32665 65135 32665 65136 32664 65136 32666 65136 32665 65137 32666 65137 32660 65137 32660 65138 32666 65138 32652 65138 32660 65139 32652 65139 32658 65139 32658 65140 32652 65140 32667 65140 32658 65141 32667 65141 32657 65141 32657 65142 32667 65142 32668 65142 32657 65143 32668 65143 32656 65143 32656 65144 32668 65144 32670 65144 32656 65145 32670 65145 32669 65145 32669 65146 32670 65146 32687 65146 32669 65147 32687 65147 32671 65147 32714 65148 32635 65148 32672 65148 32672 65149 32635 65149 32674 65149 32672 65150 32674 65150 32673 65150 32673 65151 32674 65151 32675 65151 32673 65152 32675 65152 32676 65152 32676 65153 32675 65153 32632 65153 32676 65154 32632 65154 32659 65154 32659 65155 32632 65155 32639 65155 32659 65156 32639 65156 32677 65156 32677 65157 32639 65157 32640 65157 32677 65158 32640 65158 32661 65158 32661 65159 32640 65159 32642 65159 32661 65160 32642 65160 32678 65160 32678 65161 32642 65161 32679 65161 32678 65162 32679 65162 32680 65162 32681 65163 32684 65163 32689 65163 32719 65164 32714 65164 32686 65164 32580 65165 32579 65165 32682 65165 32619 65166 32618 65166 32681 65166 32681 65167 32618 65167 32580 65167 32580 65168 32682 65168 32681 65168 32681 65169 32682 65169 32683 65169 32681 65170 32683 65170 32684 65170 32684 65171 32683 65171 32721 65171 32684 65172 32721 65172 32719 65172 32596 65173 32623 65173 32688 65173 32688 65174 32623 65174 32619 65174 32597 65175 32596 65175 32685 65175 32685 65176 32596 65176 32688 65176 32685 65177 32688 65177 32690 65177 32719 65178 32686 65178 32684 65178 32684 65179 32686 65179 32671 65179 32684 65180 32671 65180 32689 65180 32689 65181 32671 65181 32687 65181 32689 65182 32687 65182 32631 65182 32619 65183 32681 65183 32688 65183 32688 65184 32681 65184 32689 65184 32688 65185 32689 65185 32690 65185 32690 65186 32689 65186 32631 65186 32690 65187 32631 65187 32572 65187 32649 65188 32663 65188 32691 65188 32718 65189 32720 65189 32698 65189 32634 65190 32696 65190 32692 65190 32692 65191 32696 65191 32700 65191 32711 65192 32695 65192 32722 65192 32722 65193 32695 65193 32720 65193 32693 65194 32694 65194 32697 65194 32697 65195 32694 65195 32700 65195 32720 65196 32695 65196 32698 65196 32698 65197 32695 65197 32592 65197 32698 65198 32592 65198 32702 65198 32696 65199 32718 65199 32700 65199 32700 65200 32718 65200 32698 65200 32700 65201 32698 65201 32697 65201 32697 65202 32698 65202 32702 65202 32663 65203 32680 65203 32694 65203 32694 65204 32680 65204 32679 65204 32694 65205 32679 65205 32700 65205 32700 65206 32679 65206 32699 65206 32700 65207 32699 65207 32692 65207 32707 65208 32578 65208 32691 65208 32691 65209 32578 65209 32701 65209 32691 65210 32701 65210 32649 65210 32702 65211 32703 65211 32697 65211 32697 65212 32703 65212 32704 65212 32697 65213 32704 65213 32693 65213 32693 65214 32704 65214 32705 65214 32693 65215 32705 65215 32706 65215 32663 65216 32694 65216 32691 65216 32691 65217 32694 65217 32693 65217 32691 65218 32693 65218 32707 65218 32707 65219 32693 65219 32706 65219 32707 65220 32706 65220 32601 65220 32708 65221 32711 65221 32722 65221 32708 65222 32709 65222 32710 65222 32710 65223 32582 65223 32708 65223 32708 65224 32582 65224 32583 65224 32708 65225 32583 65225 32711 65225 32723 65226 32581 65226 32708 65226 32708 65227 32581 65227 32712 65227 32708 65228 32712 65228 32709 65228 32713 65229 32714 65229 32719 65229 32635 65230 32714 65230 32637 65230 32637 65231 32714 65231 32713 65231 32637 65232 32713 65232 32715 65232 32634 65233 32716 65233 32713 65233 32713 65234 32716 65234 32717 65234 32717 65235 32643 65235 32713 65235 32713 65236 32643 65236 32638 65236 32713 65237 32638 65237 32715 65237 32634 65238 32713 65238 32696 65238 32696 65239 32713 65239 32719 65239 32696 65240 32719 65240 32718 65240 32718 65241 32719 65241 32721 65241 32718 65242 32721 65242 32720 65242 32720 65243 32721 65243 32683 65243 32720 65244 32683 65244 32722 65244 32722 65245 32683 65245 32682 65245 32722 65246 32682 65246 32708 65246 32708 65247 32682 65247 32579 65247 32708 65248 32579 65248 32723 65248 32556 65249 32724 65249 32595 65249 32595 65250 32724 65250 32730 65250 32595 65251 32730 65251 32603 65251 32603 65252 32730 65252 32732 65252 32598 65253 32725 65253 32726 65253 32726 65254 32725 65254 32727 65254 32726 65255 32727 65255 32732 65255 32732 65256 32727 65256 32604 65256 32732 65257 32604 65257 32603 65257 32598 65258 32726 65258 32729 65258 32729 65259 32726 65259 32728 65259 32729 65260 32728 65260 32599 65260 32599 65261 32728 65261 32947 65261 32599 65262 32947 65262 32601 65262 32724 65263 32544 65263 32730 65263 32730 65264 32544 65264 32731 65264 32730 65265 32731 65265 32732 65265 32732 65266 32731 65266 32751 65266 32732 65267 32751 65267 32726 65267 32726 65268 32751 65268 32750 65268 32726 65269 32750 65269 32728 65269 32728 65270 32750 65270 32733 65270 32728 65271 32733 65271 32947 65271 32947 65272 32733 65272 32948 65272 32781 65273 32780 65273 32734 65273 32734 65274 32780 65274 32738 65274 32734 65275 32738 65275 32838 65275 32838 65276 32738 65276 32740 65276 32838 65277 32740 65277 32735 65277 32735 65278 32740 65278 32836 65278 32836 65279 32740 65279 32736 65279 32836 65280 32736 65280 32737 65280 32738 65281 32780 65281 32747 65281 32552 65282 32736 65282 32739 65282 32739 65283 32736 65283 32740 65283 32739 65284 32740 65284 32944 65284 32944 65285 32740 65285 32738 65285 32944 65286 32738 65286 32758 65286 32758 65287 32738 65287 32747 65287 32742 65288 32770 65288 32741 65288 32783 65289 32749 65289 32759 65289 32741 65290 32792 65290 32742 65290 32742 65291 32792 65291 32794 65291 32742 65292 32794 65292 32759 65292 32759 65293 32794 65293 32795 65293 32759 65294 32795 65294 32783 65294 32765 65295 32766 65295 32743 65295 32743 65296 32766 65296 32744 65296 32743 65297 32744 65297 32789 65297 32789 65298 32744 65298 32551 65298 32789 65299 32551 65299 32745 65299 32745 65300 32551 65300 32752 65300 32745 65301 32752 65301 32746 65301 32746 65302 32752 65302 32749 65302 32746 65303 32749 65303 32785 65303 32785 65304 32749 65304 32783 65304 32755 65305 32747 65305 32780 65305 32780 65306 32779 65306 32755 65306 32755 65307 32779 65307 32777 65307 32755 65308 32777 65308 32753 65308 32812 65309 32762 65309 32748 65309 32748 65310 32762 65310 32764 65310 32748 65311 32764 65311 32773 65311 32773 65312 32764 65312 32753 65312 32773 65313 32753 65313 32775 65313 32775 65314 32753 65314 32777 65314 32759 65315 32749 65315 32731 65315 32752 65316 32750 65316 32749 65316 32749 65317 32750 65317 32751 65317 32749 65318 32751 65318 32731 65318 32551 65319 32948 65319 32752 65319 32752 65320 32948 65320 32733 65320 32752 65321 32733 65321 32750 65321 32763 65322 32545 65322 32753 65322 32753 65323 32545 65323 32754 65323 32753 65324 32754 65324 32755 65324 32754 65325 32546 65325 32755 65325 32755 65326 32546 65326 32756 65326 32755 65327 32756 65327 32747 65327 32756 65328 32549 65328 32747 65328 32747 65329 32549 65329 32757 65329 32747 65330 32757 65330 32758 65330 32758 65331 32757 65331 32548 65331 32758 65332 32548 65332 32944 65332 32731 65333 32544 65333 32759 65333 32759 65334 32544 65334 32760 65334 32759 65335 32760 65335 32742 65335 32742 65336 32760 65336 32543 65336 32742 65337 32543 65337 32770 65337 32770 65338 32543 65338 32949 65338 32770 65339 32949 65339 32771 65339 32771 65340 32949 65340 32761 65340 32771 65341 32761 65341 32762 65341 32762 65342 32761 65342 32763 65342 32762 65343 32763 65343 32764 65343 32764 65344 32763 65344 32753 65344 32766 65345 32765 65345 32767 65345 32766 65346 32767 65346 32768 65346 32768 65347 32767 65347 32736 65347 32768 65348 32736 65348 32552 65348 32737 65349 32736 65349 32799 65349 32799 65350 32736 65350 32767 65350 32799 65351 32767 65351 32801 65351 32765 65352 32804 65352 32767 65352 32767 65353 32804 65353 32769 65353 32767 65354 32769 65354 32801 65354 32741 65355 32770 65355 32810 65355 32810 65356 32770 65356 32771 65356 32810 65357 32771 65357 32812 65357 32812 65358 32771 65358 32762 65358 32943 65359 32812 65359 32772 65359 32772 65360 32812 65360 32748 65360 32772 65361 32748 65361 32834 65361 32834 65362 32748 65362 32773 65362 32834 65363 32773 65363 32774 65363 32774 65364 32773 65364 32775 65364 32774 65365 32775 65365 32776 65365 32776 65366 32775 65366 32777 65366 32776 65367 32777 65367 32831 65367 32831 65368 32777 65368 32778 65368 32778 65369 32777 65369 32779 65369 32778 65370 32779 65370 32837 65370 32837 65371 32779 65371 32780 65371 32837 65372 32780 65372 32781 65372 32804 65373 32765 65373 32782 65373 32782 65374 32765 65374 32743 65374 32782 65375 32743 65375 32878 65375 32878 65376 32743 65376 32789 65376 32783 65377 32784 65377 32785 65377 32785 65378 32784 65378 32786 65378 32785 65379 32786 65379 32746 65379 32746 65380 32786 65380 32787 65380 32746 65381 32787 65381 32745 65381 32745 65382 32787 65382 32788 65382 32745 65383 32788 65383 32789 65383 32789 65384 32788 65384 32790 65384 32789 65385 32790 65385 32878 65385 32741 65386 32791 65386 32792 65386 32792 65387 32791 65387 32884 65387 32792 65388 32884 65388 32794 65388 32884 65389 32793 65389 32794 65389 32794 65390 32793 65390 32883 65390 32794 65391 32883 65391 32795 65391 32795 65392 32883 65392 32882 65392 32795 65393 32882 65393 32783 65393 32783 65394 32882 65394 32880 65394 32783 65395 32880 65395 32784 65395 32807 65396 32868 65396 32867 65396 32868 65397 32807 65397 32796 65397 32800 65398 32802 65398 32797 65398 32798 65399 32737 65399 32799 65399 32862 65400 32843 65400 32800 65400 32800 65401 32843 65401 32798 65401 32798 65402 32799 65402 32800 65402 32800 65403 32799 65403 32801 65403 32800 65404 32801 65404 32802 65404 32802 65405 32801 65405 32769 65405 32802 65406 32769 65406 32804 65406 32806 65407 32819 65407 32803 65407 32803 65408 32819 65408 32862 65408 32804 65409 32805 65409 32802 65409 32802 65410 32805 65410 32894 65410 32802 65411 32894 65411 32797 65411 32797 65412 32894 65412 32913 65412 32797 65413 32913 65413 32912 65413 32822 65414 32806 65414 32809 65414 32809 65415 32806 65415 32803 65415 32809 65416 32803 65416 32807 65416 32862 65417 32800 65417 32803 65417 32803 65418 32800 65418 32797 65418 32803 65419 32797 65419 32807 65419 32807 65420 32797 65420 32912 65420 32807 65421 32912 65421 32796 65421 32915 65422 32822 65422 32808 65422 32808 65423 32822 65423 32809 65423 32808 65424 32809 65424 32926 65424 32926 65425 32809 65425 32807 65425 32926 65426 32807 65426 32924 65426 32924 65427 32807 65427 32867 65427 32930 65428 32791 65428 32741 65428 32930 65429 32741 65429 32941 65429 32941 65430 32741 65430 32810 65430 32941 65431 32810 65431 32811 65431 32811 65432 32810 65432 32812 65432 32811 65433 32812 65433 32943 65433 32826 65434 32815 65434 32816 65434 32813 65435 32825 65435 32854 65435 32813 65436 32854 65436 32853 65436 32914 65437 32814 65437 32815 65437 32815 65438 32814 65438 32817 65438 32815 65439 32817 65439 32816 65439 32816 65440 32817 65440 32916 65440 32816 65441 32916 65441 32828 65441 32822 65442 32818 65442 32806 65442 32806 65443 32818 65443 32821 65443 32806 65444 32821 65444 32819 65444 32819 65445 32821 65445 32820 65445 32860 65446 32820 65446 32826 65446 32826 65447 32820 65447 32821 65447 32826 65448 32821 65448 32815 65448 32815 65449 32821 65449 32818 65449 32815 65450 32818 65450 32914 65450 32914 65451 32818 65451 32822 65451 32914 65452 32822 65452 32915 65452 32823 65453 32854 65453 32824 65453 32824 65454 32854 65454 32825 65454 32824 65455 32825 65455 32929 65455 32860 65456 32826 65456 32858 65456 32858 65457 32826 65457 32816 65457 32858 65458 32816 65458 32827 65458 32827 65459 32816 65459 32828 65459 32827 65460 32828 65460 32830 65460 32830 65461 32828 65461 32829 65461 32830 65462 32829 65462 32856 65462 32778 65463 32845 65463 32831 65463 32831 65464 32845 65464 32832 65464 32831 65465 32832 65465 32776 65465 32839 65466 32833 65466 32832 65466 32776 65467 32832 65467 32774 65467 32774 65468 32832 65468 32833 65468 32774 65469 32833 65469 32834 65469 32931 65470 32943 65470 32835 65470 32835 65471 32943 65471 32772 65471 32835 65472 32772 65472 32834 65472 32737 65473 32798 65473 32836 65473 32836 65474 32798 65474 32850 65474 32836 65475 32850 65475 32735 65475 32735 65476 32850 65476 32849 65476 32778 65477 32837 65477 32845 65477 32845 65478 32837 65478 32781 65478 32845 65479 32781 65479 32847 65479 32847 65480 32781 65480 32734 65480 32847 65481 32734 65481 32849 65481 32849 65482 32734 65482 32838 65482 32849 65483 32838 65483 32735 65483 32839 65484 32844 65484 32840 65484 32840 65485 32844 65485 32846 65485 32840 65486 32846 65486 32857 65486 32857 65487 32846 65487 32841 65487 32857 65488 32841 65488 32842 65488 32842 65489 32841 65489 32848 65489 32842 65490 32848 65490 32859 65490 32859 65491 32848 65491 32851 65491 32859 65492 32851 65492 32861 65492 32861 65493 32851 65493 32843 65493 32861 65494 32843 65494 32862 65494 32839 65495 32832 65495 32844 65495 32844 65496 32832 65496 32845 65496 32844 65497 32845 65497 32846 65497 32846 65498 32845 65498 32847 65498 32846 65499 32847 65499 32841 65499 32841 65500 32847 65500 32849 65500 32841 65501 32849 65501 32848 65501 32848 65502 32849 65502 32850 65502 32848 65503 32850 65503 32851 65503 32851 65504 32850 65504 32798 65504 32851 65505 32798 65505 32843 65505 32855 65506 32823 65506 32932 65506 32932 65507 32823 65507 32824 65507 32932 65508 32824 65508 32933 65508 32933 65509 32824 65509 32929 65509 32933 65510 32929 65510 32928 65510 32916 65511 32852 65511 32828 65511 32828 65512 32852 65512 32853 65512 32828 65513 32853 65513 32829 65513 32829 65514 32853 65514 32854 65514 32829 65515 32854 65515 32856 65515 32856 65516 32854 65516 32823 65516 32856 65517 32823 65517 32835 65517 32835 65518 32823 65518 32855 65518 32835 65519 32855 65519 32931 65519 32834 65520 32833 65520 32835 65520 32835 65521 32833 65521 32839 65521 32835 65522 32839 65522 32856 65522 32856 65523 32839 65523 32840 65523 32856 65524 32840 65524 32830 65524 32830 65525 32840 65525 32857 65525 32830 65526 32857 65526 32827 65526 32827 65527 32857 65527 32842 65527 32827 65528 32842 65528 32858 65528 32858 65529 32842 65529 32859 65529 32858 65530 32859 65530 32860 65530 32860 65531 32859 65531 32861 65531 32860 65532 32861 65532 32820 65532 32820 65533 32861 65533 32862 65533 32820 65534 32862 65534 32819 65534 32884 65535 32791 65535 32885 65535 32873 65536 32909 65536 32870 65536 32902 65537 32863 65537 32936 65537 32876 65538 32923 65538 32864 65538 32864 65539 32923 65539 32865 65539 32864 65540 32865 65540 32866 65540 32866 65541 32865 65541 32867 65541 32866 65542 32867 65542 32868 65542 32887 65543 32936 65543 32904 65543 32920 65544 32869 65544 32905 65544 32905 65545 32869 65545 32921 65545 32905 65546 32921 65546 32871 65546 32871 65547 32921 65547 32919 65547 32871 65548 32919 65548 32870 65548 32870 65549 32909 65549 32871 65549 32871 65550 32909 65550 32908 65550 32871 65551 32908 65551 32905 65551 32919 65552 32918 65552 32870 65552 32870 65553 32918 65553 32872 65553 32870 65554 32872 65554 32873 65554 32873 65555 32872 65555 32875 65555 32873 65556 32875 65556 32874 65556 32874 65557 32875 65557 32877 65557 32874 65558 32877 65558 32910 65558 32910 65559 32877 65559 32796 65559 32910 65560 32796 65560 32912 65560 32918 65561 32876 65561 32872 65561 32872 65562 32876 65562 32864 65562 32872 65563 32864 65563 32875 65563 32875 65564 32864 65564 32866 65564 32875 65565 32866 65565 32877 65565 32877 65566 32866 65566 32868 65566 32877 65567 32868 65567 32796 65567 32782 65568 32878 65568 32895 65568 32895 65569 32878 65569 32790 65569 32895 65570 32790 65570 32896 65570 32896 65571 32790 65571 32788 65571 32896 65572 32788 65572 32898 65572 32898 65573 32788 65573 32787 65573 32898 65574 32787 65574 32879 65574 32894 65575 32805 65575 32895 65575 32895 65576 32805 65576 32804 65576 32895 65577 32804 65577 32782 65577 32787 65578 32786 65578 32879 65578 32879 65579 32786 65579 32784 65579 32879 65580 32784 65580 32901 65580 32901 65581 32784 65581 32880 65581 32901 65582 32880 65582 32881 65582 32881 65583 32880 65583 32882 65583 32881 65584 32882 65584 32883 65584 32883 65585 32793 65585 32881 65585 32881 65586 32793 65586 32884 65586 32881 65587 32884 65587 32903 65587 32903 65588 32884 65588 32885 65588 32903 65589 32885 65589 32886 65589 32936 65590 32887 65590 32902 65590 32902 65591 32887 65591 32906 65591 32902 65592 32906 65592 32888 65592 32888 65593 32906 65593 32907 65593 32888 65594 32907 65594 32900 65594 32900 65595 32907 65595 32889 65595 32900 65596 32889 65596 32891 65596 32891 65597 32889 65597 32890 65597 32891 65598 32890 65598 32899 65598 32899 65599 32890 65599 32892 65599 32899 65600 32892 65600 32897 65600 32897 65601 32892 65601 32911 65601 32897 65602 32911 65602 32893 65602 32893 65603 32911 65603 32913 65603 32893 65604 32913 65604 32894 65604 32894 65605 32895 65605 32893 65605 32893 65606 32895 65606 32896 65606 32893 65607 32896 65607 32897 65607 32897 65608 32896 65608 32898 65608 32897 65609 32898 65609 32899 65609 32899 65610 32898 65610 32879 65610 32899 65611 32879 65611 32891 65611 32891 65612 32879 65612 32901 65612 32891 65613 32901 65613 32900 65613 32900 65614 32901 65614 32881 65614 32900 65615 32881 65615 32888 65615 32888 65616 32881 65616 32903 65616 32888 65617 32903 65617 32902 65617 32902 65618 32903 65618 32886 65618 32902 65619 32886 65619 32863 65619 32904 65620 32920 65620 32887 65620 32887 65621 32920 65621 32905 65621 32887 65622 32905 65622 32906 65622 32906 65623 32905 65623 32908 65623 32906 65624 32908 65624 32907 65624 32907 65625 32908 65625 32909 65625 32907 65626 32909 65626 32889 65626 32889 65627 32909 65627 32873 65627 32889 65628 32873 65628 32890 65628 32890 65629 32873 65629 32874 65629 32890 65630 32874 65630 32892 65630 32892 65631 32874 65631 32910 65631 32892 65632 32910 65632 32911 65632 32911 65633 32910 65633 32912 65633 32911 65634 32912 65634 32913 65634 32922 65635 32904 65635 32925 65635 32917 65636 32915 65636 32808 65636 32914 65637 32915 65637 32814 65637 32814 65638 32915 65638 32917 65638 32814 65639 32917 65639 32817 65639 32817 65640 32917 65640 32916 65640 32929 65641 32825 65641 32917 65641 32917 65642 32825 65642 32813 65642 32813 65643 32853 65643 32917 65643 32917 65644 32853 65644 32852 65644 32917 65645 32852 65645 32916 65645 32876 65646 32918 65646 32922 65646 32922 65647 32918 65647 32919 65647 32920 65648 32904 65648 32869 65648 32869 65649 32904 65649 32922 65649 32869 65650 32922 65650 32921 65650 32921 65651 32922 65651 32919 65651 32867 65652 32865 65652 32922 65652 32922 65653 32865 65653 32923 65653 32922 65654 32923 65654 32876 65654 32867 65655 32922 65655 32924 65655 32924 65656 32922 65656 32925 65656 32924 65657 32925 65657 32926 65657 32926 65658 32925 65658 32935 65658 32926 65659 32935 65659 32808 65659 32808 65660 32935 65660 32927 65660 32808 65661 32927 65661 32917 65661 32917 65662 32927 65662 32928 65662 32917 65663 32928 65663 32929 65663 32885 65664 32791 65664 32930 65664 32863 65665 32886 65665 32938 65665 32931 65666 32855 65666 32942 65666 32932 65667 32933 65667 32940 65667 32933 65668 32928 65668 32940 65668 32940 65669 32928 65669 32927 65669 32940 65670 32927 65670 32934 65670 32934 65671 32927 65671 32935 65671 32934 65672 32935 65672 32937 65672 32937 65673 32935 65673 32925 65673 32937 65674 32925 65674 32936 65674 32936 65675 32925 65675 32904 65675 32936 65676 32863 65676 32937 65676 32937 65677 32863 65677 32938 65677 32937 65678 32938 65678 32934 65678 32934 65679 32938 65679 32939 65679 32934 65680 32939 65680 32940 65680 32940 65681 32939 65681 32942 65681 32940 65682 32942 65682 32932 65682 32932 65683 32942 65683 32855 65683 32886 65684 32885 65684 32938 65684 32938 65685 32885 65685 32930 65685 32938 65686 32930 65686 32939 65686 32939 65687 32930 65687 32941 65687 32939 65688 32941 65688 32942 65688 32942 65689 32941 65689 32811 65689 32942 65690 32811 65690 32931 65690 32931 65691 32811 65691 32943 65691 32944 65692 32548 65692 32945 65692 32944 65693 32945 65693 32946 65693 32945 65694 32577 65694 32946 65694 32946 65695 32577 65695 32576 65695 32946 65696 32576 65696 32550 65696 32550 65697 32576 65697 32551 65697 32551 65698 32576 65698 32947 65698 32551 65699 32947 65699 32948 65699 32573 65700 32763 65700 32574 65700 32574 65701 32763 65701 32761 65701 32574 65702 32761 65702 32575 65702 32575 65703 32761 65703 32949 65703 32575 65704 32949 65704 32950 65704 32950 65705 32949 65705 32543 65705 32962 65706 32951 65706 32952 65706 32952 65707 32951 65707 33205 65707 32952 65708 33205 65708 32953 65708 33163 65709 32954 65709 32965 65709 32965 65710 32954 65710 33166 65710 32965 65711 33166 65711 32964 65711 32964 65712 33166 65712 33167 65712 32964 65713 33167 65713 32955 65713 32955 65714 33167 65714 33170 65714 32955 65715 33170 65715 32962 65715 32962 65716 33170 65716 33169 65716 32962 65717 33169 65717 32951 65717 33163 65718 32965 65718 33165 65718 33165 65719 32965 65719 32956 65719 33165 65720 32956 65720 33184 65720 33184 65721 32956 65721 32957 65721 33184 65722 32957 65722 33185 65722 33185 65723 32957 65723 32960 65723 33185 65724 32960 65724 32958 65724 32958 65725 32960 65725 32959 65725 32958 65726 32959 65726 33186 65726 33336 65727 32959 65727 33337 65727 33337 65728 32959 65728 32960 65728 33337 65729 32960 65729 33334 65729 32960 65730 32957 65730 33334 65730 33334 65731 32957 65731 32956 65731 33334 65732 32956 65732 32961 65732 32961 65733 32956 65733 32965 65733 32961 65734 32965 65734 33335 65734 32952 65735 33339 65735 32962 65735 32962 65736 33339 65736 32963 65736 32962 65737 32963 65737 32955 65737 32955 65738 32963 65738 33335 65738 32955 65739 33335 65739 32964 65739 32964 65740 33335 65740 32965 65740 33013 65741 33359 65741 32966 65741 32966 65742 33359 65742 32967 65742 32966 65743 32967 65743 33012 65743 33012 65744 32967 65744 32968 65744 33012 65745 32968 65745 33345 65745 33359 65746 33138 65746 32967 65746 32967 65747 33138 65747 32969 65747 32967 65748 32969 65748 32968 65748 32968 65749 32969 65749 33139 65749 32970 65750 33056 65750 33041 65750 33056 65751 32970 65751 32971 65751 32976 65752 32972 65752 32984 65752 32973 65753 33345 65753 32977 65753 32974 65754 32975 65754 32976 65754 32976 65755 32975 65755 32973 65755 32973 65756 32977 65756 32976 65756 32976 65757 32977 65757 33347 65757 32976 65758 33347 65758 32972 65758 32972 65759 33347 65759 32978 65759 32972 65760 32978 65760 32980 65760 32993 65761 32979 65761 32983 65761 32983 65762 32979 65762 32974 65762 32980 65763 32981 65763 32972 65763 32972 65764 32981 65764 33083 65764 32972 65765 33083 65765 32984 65765 32984 65766 33083 65766 33081 65766 32984 65767 33081 65767 33051 65767 32999 65768 32993 65768 32982 65768 32982 65769 32993 65769 32983 65769 32982 65770 32983 65770 32970 65770 32974 65771 32976 65771 32983 65771 32983 65772 32976 65772 32984 65772 32983 65773 32984 65773 32970 65773 32970 65774 32984 65774 33051 65774 32970 65775 33051 65775 32971 65775 33096 65776 32999 65776 33094 65776 33094 65777 32999 65777 32982 65777 33094 65778 32982 65778 33109 65778 33109 65779 32982 65779 32970 65779 33109 65780 32970 65780 33107 65780 33107 65781 32970 65781 33041 65781 33123 65782 33038 65782 33312 65782 33123 65783 33312 65783 33124 65783 33124 65784 33312 65784 33348 65784 33124 65785 33348 65785 32985 65785 32985 65786 33348 65786 32986 65786 32985 65787 32986 65787 32987 65787 32996 65788 32988 65788 32992 65788 32989 65789 33000 65789 33010 65789 32989 65790 33010 65790 33099 65790 33095 65791 32990 65791 32988 65791 32988 65792 32990 65792 32991 65792 32988 65793 32991 65793 32992 65793 32992 65794 32991 65794 33101 65794 32992 65795 33101 65795 33009 65795 32999 65796 32998 65796 32993 65796 32993 65797 32998 65797 32997 65797 32993 65798 32997 65798 32979 65798 32979 65799 32997 65799 32994 65799 32995 65800 32994 65800 32996 65800 32996 65801 32994 65801 32997 65801 32996 65802 32997 65802 32988 65802 32988 65803 32997 65803 32998 65803 32988 65804 32998 65804 33095 65804 33095 65805 32998 65805 32999 65805 33095 65806 32999 65806 33096 65806 33029 65807 33010 65807 33030 65807 33030 65808 33010 65808 33000 65808 33030 65809 33000 65809 33098 65809 32995 65810 32996 65810 33001 65810 33001 65811 32996 65811 32992 65811 33001 65812 32992 65812 33036 65812 33036 65813 32992 65813 33009 65813 33036 65814 33009 65814 33002 65814 33002 65815 33009 65815 33003 65815 33002 65816 33003 65816 33011 65816 33015 65817 33004 65817 33005 65817 33005 65818 33004 65818 33024 65818 33005 65819 33024 65819 33006 65819 33033 65820 33008 65820 33024 65820 33353 65821 33352 65821 33028 65821 33028 65822 33352 65822 33032 65822 33006 65823 33024 65823 33007 65823 33007 65824 33024 65824 33008 65824 33007 65825 33008 65825 33032 65825 33101 65826 33100 65826 33009 65826 33009 65827 33100 65827 33099 65827 33009 65828 33099 65828 33003 65828 33003 65829 33099 65829 33010 65829 33003 65830 33010 65830 33011 65830 33011 65831 33010 65831 33029 65831 33011 65832 33029 65832 33028 65832 33345 65833 32973 65833 33012 65833 33012 65834 32973 65834 33014 65834 33017 65835 33358 65835 33025 65835 33025 65836 33358 65836 33013 65836 33025 65837 33013 65837 33014 65837 33014 65838 33013 65838 32966 65838 33014 65839 32966 65839 33012 65839 33015 65840 33016 65840 33004 65840 33004 65841 33016 65841 33354 65841 33004 65842 33354 65842 33017 65842 33017 65843 33354 65843 33356 65843 33017 65844 33356 65844 33358 65844 33033 65845 33018 65845 33034 65845 33034 65846 33018 65846 33019 65846 33034 65847 33019 65847 33035 65847 33035 65848 33019 65848 33020 65848 33035 65849 33020 65849 33037 65849 33037 65850 33020 65850 33021 65850 33037 65851 33021 65851 33022 65851 33022 65852 33021 65852 33026 65852 33022 65853 33026 65853 33023 65853 33023 65854 33026 65854 32975 65854 33023 65855 32975 65855 32974 65855 33033 65856 33024 65856 33018 65856 33018 65857 33024 65857 33004 65857 33018 65858 33004 65858 33019 65858 33019 65859 33004 65859 33017 65859 33019 65860 33017 65860 33020 65860 33020 65861 33017 65861 33025 65861 33020 65862 33025 65862 33021 65862 33021 65863 33025 65863 33014 65863 33021 65864 33014 65864 33026 65864 33026 65865 33014 65865 32973 65865 33026 65866 32973 65866 32975 65866 32987 65867 33353 65867 33112 65867 33112 65868 33353 65868 33028 65868 33112 65869 33028 65869 33027 65869 33027 65870 33028 65870 33029 65870 33027 65871 33029 65871 33114 65871 33114 65872 33029 65872 33030 65872 33114 65873 33030 65873 33031 65873 33031 65874 33030 65874 33098 65874 33031 65875 33098 65875 33115 65875 33032 65876 33008 65876 33028 65876 33028 65877 33008 65877 33033 65877 33028 65878 33033 65878 33011 65878 33011 65879 33033 65879 33034 65879 33011 65880 33034 65880 33002 65880 33002 65881 33034 65881 33035 65881 33002 65882 33035 65882 33036 65882 33036 65883 33035 65883 33037 65883 33036 65884 33037 65884 33001 65884 33001 65885 33037 65885 33022 65885 33001 65886 33022 65886 32995 65886 32995 65887 33022 65887 33023 65887 32995 65888 33023 65888 32994 65888 32994 65889 33023 65889 32974 65889 32994 65890 32974 65890 32979 65890 33365 65891 33038 65891 33072 65891 33090 65892 33089 65892 33039 65892 33086 65893 33119 65893 33117 65893 33053 65894 33106 65894 33055 65894 33055 65895 33106 65895 33105 65895 33055 65896 33105 65896 33040 65896 33040 65897 33105 65897 33041 65897 33040 65898 33041 65898 33056 65898 33073 65899 33117 65899 33103 65899 33042 65900 33102 65900 33043 65900 33043 65901 33102 65901 33044 65901 33043 65902 33044 65902 33046 65902 33046 65903 33044 65903 33047 65903 33046 65904 33047 65904 33039 65904 33039 65905 33089 65905 33046 65905 33046 65906 33089 65906 33045 65906 33046 65907 33045 65907 33043 65907 33047 65908 33052 65908 33039 65908 33039 65909 33052 65909 33054 65909 33039 65910 33054 65910 33090 65910 33090 65911 33054 65911 33048 65911 33090 65912 33048 65912 33092 65912 33092 65913 33048 65913 33049 65913 33092 65914 33049 65914 33050 65914 33050 65915 33049 65915 32971 65915 33050 65916 32971 65916 33051 65916 33052 65917 33053 65917 33054 65917 33054 65918 33053 65918 33055 65918 33054 65919 33055 65919 33048 65919 33048 65920 33055 65920 33040 65920 33048 65921 33040 65921 33049 65921 33049 65922 33040 65922 33056 65922 33049 65923 33056 65923 32971 65923 33062 65924 33360 65924 33061 65924 33061 65925 33360 65925 33058 65925 33061 65926 33058 65926 33057 65926 33057 65927 33058 65927 33059 65927 33057 65928 33059 65928 33060 65928 33060 65929 33059 65929 33063 65929 33060 65930 33063 65930 33064 65930 33083 65931 32981 65931 33061 65931 33061 65932 32981 65932 32980 65932 33061 65933 32980 65933 33062 65933 33063 65934 33065 65934 33064 65934 33064 65935 33065 65935 33066 65935 33064 65936 33066 65936 33085 65936 33085 65937 33066 65937 33067 65937 33085 65938 33067 65938 33068 65938 33068 65939 33067 65939 33069 65939 33068 65940 33069 65940 33366 65940 33366 65941 33070 65941 33068 65941 33068 65942 33070 65942 33365 65942 33068 65943 33365 65943 33071 65943 33071 65944 33365 65944 33072 65944 33071 65945 33072 65945 33087 65945 33117 65946 33073 65946 33086 65946 33086 65947 33073 65947 33088 65947 33086 65948 33088 65948 33074 65948 33074 65949 33088 65949 33075 65949 33074 65950 33075 65950 33076 65950 33076 65951 33075 65951 33077 65951 33076 65952 33077 65952 33078 65952 33078 65953 33077 65953 33091 65953 33078 65954 33091 65954 33084 65954 33084 65955 33091 65955 33079 65955 33084 65956 33079 65956 33080 65956 33080 65957 33079 65957 33093 65957 33080 65958 33093 65958 33082 65958 33082 65959 33093 65959 33081 65959 33082 65960 33081 65960 33083 65960 33083 65961 33061 65961 33082 65961 33082 65962 33061 65962 33057 65962 33082 65963 33057 65963 33080 65963 33080 65964 33057 65964 33060 65964 33080 65965 33060 65965 33084 65965 33084 65966 33060 65966 33064 65966 33084 65967 33064 65967 33078 65967 33078 65968 33064 65968 33085 65968 33078 65969 33085 65969 33076 65969 33076 65970 33085 65970 33068 65970 33076 65971 33068 65971 33074 65971 33074 65972 33068 65972 33071 65972 33074 65973 33071 65973 33086 65973 33086 65974 33071 65974 33087 65974 33086 65975 33087 65975 33119 65975 33103 65976 33042 65976 33073 65976 33073 65977 33042 65977 33043 65977 33073 65978 33043 65978 33088 65978 33088 65979 33043 65979 33045 65979 33088 65980 33045 65980 33075 65980 33075 65981 33045 65981 33089 65981 33075 65982 33089 65982 33077 65982 33077 65983 33089 65983 33090 65983 33077 65984 33090 65984 33091 65984 33091 65985 33090 65985 33092 65985 33091 65986 33092 65986 33079 65986 33079 65987 33092 65987 33050 65987 33079 65988 33050 65988 33093 65988 33093 65989 33050 65989 33051 65989 33093 65990 33051 65990 33081 65990 33104 65991 33103 65991 33108 65991 33097 65992 33096 65992 33094 65992 33095 65993 33096 65993 32990 65993 32990 65994 33096 65994 33097 65994 32990 65995 33097 65995 32991 65995 32991 65996 33097 65996 33101 65996 33098 65997 33000 65997 33097 65997 33097 65998 33000 65998 32989 65998 32989 65999 33099 65999 33097 65999 33097 66000 33099 66000 33100 66000 33097 66001 33100 66001 33101 66001 33053 66002 33052 66002 33104 66002 33104 66003 33052 66003 33047 66003 33042 66004 33103 66004 33102 66004 33102 66005 33103 66005 33104 66005 33102 66006 33104 66006 33044 66006 33044 66007 33104 66007 33047 66007 33041 66008 33105 66008 33104 66008 33104 66009 33105 66009 33106 66009 33104 66010 33106 66010 33053 66010 33041 66011 33104 66011 33107 66011 33107 66012 33104 66012 33108 66012 33107 66013 33108 66013 33109 66013 33109 66014 33108 66014 33110 66014 33109 66015 33110 66015 33094 66015 33094 66016 33110 66016 33111 66016 33094 66017 33111 66017 33097 66017 33097 66018 33111 66018 33115 66018 33097 66019 33115 66019 33098 66019 33072 66020 33038 66020 33123 66020 33119 66021 33087 66021 33120 66021 33112 66022 33027 66022 33113 66022 33114 66023 33031 66023 33122 66023 33031 66024 33115 66024 33122 66024 33122 66025 33115 66025 33111 66025 33122 66026 33111 66026 33116 66026 33116 66027 33111 66027 33110 66027 33116 66028 33110 66028 33118 66028 33118 66029 33110 66029 33108 66029 33118 66030 33108 66030 33117 66030 33117 66031 33108 66031 33103 66031 33117 66032 33119 66032 33118 66032 33118 66033 33119 66033 33120 66033 33118 66034 33120 66034 33116 66034 33116 66035 33120 66035 33121 66035 33116 66036 33121 66036 33122 66036 33122 66037 33121 66037 33113 66037 33122 66038 33113 66038 33114 66038 33114 66039 33113 66039 33027 66039 33087 66040 33072 66040 33120 66040 33120 66041 33072 66041 33123 66041 33120 66042 33123 66042 33121 66042 33121 66043 33123 66043 33124 66043 33121 66044 33124 66044 33113 66044 33113 66045 33124 66045 32985 66045 33113 66046 32985 66046 33112 66046 33112 66047 32985 66047 32987 66047 33325 66048 33332 66048 33145 66048 33325 66049 33145 66049 33125 66049 33145 66050 33161 66050 33125 66050 33125 66051 33161 66051 33126 66051 33125 66052 33126 66052 33137 66052 33137 66053 33126 66053 33319 66053 33319 66054 33126 66054 32959 66054 33319 66055 32959 66055 33336 66055 33151 66056 33127 66056 33158 66056 33158 66057 33127 66057 33128 66057 33158 66058 33128 66058 33159 66058 33159 66059 33128 66059 33342 66059 33159 66060 33342 66060 33129 66060 33129 66061 33342 66061 33340 66061 33129 66062 33340 66062 32952 66062 32952 66063 33340 66063 33339 66063 33131 66064 33127 66064 33151 66064 33157 66065 33130 66065 33338 66065 33151 66066 33153 66066 33131 66066 33131 66067 33153 66067 33132 66067 33131 66068 33132 66068 33338 66068 33338 66069 33132 66069 33133 66069 33338 66070 33133 66070 33157 66070 33157 66071 33148 66071 33130 66071 33130 66072 33148 66072 33149 66072 33130 66073 33149 66073 33134 66073 33145 66074 33332 66074 33135 66074 33135 66075 33332 66075 33136 66075 33135 66076 33136 66076 33146 66076 33146 66077 33136 66077 33134 66077 33146 66078 33134 66078 33150 66078 33150 66079 33134 66079 33149 66079 33137 66080 33319 66080 33141 66080 33139 66081 32969 66081 33138 66081 33138 66082 33325 66082 33139 66082 33139 66083 33325 66083 33125 66083 33139 66084 33125 66084 33344 66084 33344 66085 33125 66085 33137 66085 33344 66086 33137 66086 33140 66086 33140 66087 33137 66087 33141 66087 32952 66088 32953 66088 33129 66088 33129 66089 32953 66089 33142 66089 33143 66090 33145 66090 33144 66090 33144 66091 33145 66091 33135 66091 33144 66092 33135 66092 33226 66092 33226 66093 33135 66093 33146 66093 33148 66094 33157 66094 33147 66094 33147 66095 33235 66095 33148 66095 33148 66096 33235 66096 33234 66096 33148 66097 33234 66097 33149 66097 33149 66098 33234 66098 33231 66098 33149 66099 33231 66099 33150 66099 33150 66100 33231 66100 33230 66100 33150 66101 33230 66101 33146 66101 33146 66102 33230 66102 33228 66102 33146 66103 33228 66103 33226 66103 33151 66104 33152 66104 33153 66104 33153 66105 33152 66105 33238 66105 33153 66106 33238 66106 33132 66106 33238 66107 33154 66107 33132 66107 33132 66108 33154 66108 33155 66108 33132 66109 33155 66109 33133 66109 33133 66110 33155 66110 33156 66110 33133 66111 33156 66111 33157 66111 33157 66112 33156 66112 33237 66112 33157 66113 33237 66113 33147 66113 33152 66114 33151 66114 33277 66114 33277 66115 33151 66115 33158 66115 33277 66116 33158 66116 33274 66116 33274 66117 33158 66117 33159 66117 33274 66118 33159 66118 33142 66118 33142 66119 33159 66119 33129 66119 33186 66120 32959 66120 33126 66120 33186 66121 33126 66121 33160 66121 33160 66122 33126 66122 33161 66122 33160 66123 33161 66123 33288 66123 33288 66124 33161 66124 33145 66124 33288 66125 33145 66125 33143 66125 33311 66126 33162 66126 33269 66126 32951 66127 33169 66127 33168 66127 33163 66128 33165 66128 33164 66128 33164 66129 33165 66129 33184 66129 33164 66130 33184 66130 33197 66130 33163 66131 33164 66131 32954 66131 32954 66132 33164 66132 33196 66132 32954 66133 33196 66133 33166 66133 33166 66134 33196 66134 33194 66134 33166 66135 33194 66135 33167 66135 33168 66136 33169 66136 33194 66136 33194 66137 33169 66137 33170 66137 33194 66138 33170 66138 33167 66138 33205 66139 32951 66139 33207 66139 33142 66140 32953 66140 33273 66140 33273 66141 32953 66141 33206 66141 33298 66142 33311 66142 33200 66142 33177 66143 33176 66143 33171 66143 33171 66144 33176 66144 33172 66144 33171 66145 33172 66145 33173 66145 33173 66146 33172 66146 33180 66146 33173 66147 33180 66147 33279 66147 33279 66148 33180 66148 33181 66148 33175 66149 33291 66149 33282 66149 33209 66150 33174 66150 33179 66150 33179 66151 33174 66151 33212 66151 33179 66152 33212 66152 33175 66152 33175 66153 33212 66153 33292 66153 33175 66154 33292 66154 33291 66154 33204 66155 33176 66155 33178 66155 33178 66156 33176 66156 33177 66156 33178 66157 33177 66157 33300 66157 33204 66158 33209 66158 33176 66158 33176 66159 33209 66159 33179 66159 33176 66160 33179 66160 33172 66160 33172 66161 33179 66161 33175 66161 33172 66162 33175 66162 33180 66162 33180 66163 33175 66163 33282 66163 33180 66164 33282 66164 33181 66164 33208 66165 33182 66165 33204 66165 33204 66166 33182 66166 33183 66166 33204 66167 33183 66167 33209 66167 33299 66168 33298 66168 33202 66168 33202 66169 33298 66169 33200 66169 33202 66170 33200 66170 33203 66170 33203 66171 33200 66171 33201 66171 33184 66172 33185 66172 33197 66172 33197 66173 33185 66173 32958 66173 33197 66174 32958 66174 33187 66174 33187 66175 32958 66175 33186 66175 33187 66176 33186 66176 33188 66176 33207 66177 33195 66177 33189 66177 33189 66178 33195 66178 33190 66178 33189 66179 33190 66179 33191 66179 33191 66180 33190 66180 33192 66180 33191 66181 33192 66181 33193 66181 33193 66182 33192 66182 33198 66182 33193 66183 33198 66183 33210 66183 33210 66184 33198 66184 33199 66184 33210 66185 33199 66185 33211 66185 33211 66186 33199 66186 33295 66186 33211 66187 33295 66187 33213 66187 32951 66188 33168 66188 33207 66188 33207 66189 33168 66189 33194 66189 33207 66190 33194 66190 33195 66190 33195 66191 33194 66191 33196 66191 33195 66192 33196 66192 33190 66192 33190 66193 33196 66193 33164 66193 33190 66194 33164 66194 33192 66194 33192 66195 33164 66195 33197 66195 33192 66196 33197 66196 33198 66196 33198 66197 33197 66197 33187 66197 33198 66198 33187 66198 33199 66198 33199 66199 33187 66199 33188 66199 33199 66200 33188 66200 33295 66200 33311 66201 33269 66201 33200 66201 33200 66202 33269 66202 33268 66202 33200 66203 33268 66203 33201 66203 33201 66204 33268 66204 33272 66204 33201 66205 33272 66205 33271 66205 33300 66206 33299 66206 33178 66206 33178 66207 33299 66207 33202 66207 33178 66208 33202 66208 33204 66208 33204 66209 33202 66209 33203 66209 33204 66210 33203 66210 33208 66210 33208 66211 33203 66211 33201 66211 33208 66212 33201 66212 33206 66212 33206 66213 33201 66213 33271 66213 33206 66214 33271 66214 33273 66214 32953 66215 33205 66215 33206 66215 33206 66216 33205 66216 33207 66216 33206 66217 33207 66217 33208 66217 33208 66218 33207 66218 33189 66218 33208 66219 33189 66219 33182 66219 33182 66220 33189 66220 33191 66220 33182 66221 33191 66221 33183 66221 33183 66222 33191 66222 33193 66222 33183 66223 33193 66223 33209 66223 33209 66224 33193 66224 33210 66224 33209 66225 33210 66225 33174 66225 33174 66226 33210 66226 33211 66226 33174 66227 33211 66227 33212 66227 33212 66228 33211 66228 33213 66228 33212 66229 33213 66229 33292 66229 33238 66230 33152 66230 33240 66230 33220 66231 33260 66231 33219 66231 33242 66232 33275 66232 33241 66232 33214 66233 33278 66233 33303 66233 33303 66234 33278 66234 33225 66234 33303 66235 33225 66235 33304 66235 33304 66236 33225 66236 33215 66236 33304 66237 33215 66237 33216 66237 33255 66238 33241 66238 33301 66238 33256 66239 33302 66239 33257 66239 33257 66240 33302 66240 33217 66240 33217 66241 33302 66241 33218 66241 33217 66242 33218 66242 33219 66242 33219 66243 33260 66243 33217 66243 33217 66244 33260 66244 33259 66244 33217 66245 33259 66245 33257 66245 33218 66246 33305 66246 33219 66246 33219 66247 33305 66247 33223 66247 33219 66248 33223 66248 33220 66248 33220 66249 33223 66249 33224 66249 33220 66250 33224 66250 33221 66250 33221 66251 33224 66251 33222 66251 33221 66252 33222 66252 33263 66252 33263 66253 33222 66253 33287 66253 33263 66254 33287 66254 33286 66254 33305 66255 33216 66255 33223 66255 33223 66256 33216 66256 33215 66256 33223 66257 33215 66257 33224 66257 33224 66258 33215 66258 33225 66258 33224 66259 33225 66259 33222 66259 33222 66260 33225 66260 33278 66260 33222 66261 33278 66261 33287 66261 33144 66262 33226 66262 33227 66262 33227 66263 33226 66263 33228 66263 33227 66264 33228 66264 33250 66264 33250 66265 33228 66265 33230 66265 33250 66266 33230 66266 33229 66266 33229 66267 33230 66267 33231 66267 33229 66268 33231 66268 33236 66268 33248 66269 33290 66269 33227 66269 33227 66270 33290 66270 33143 66270 33227 66271 33143 66271 33144 66271 33232 66272 33237 66272 33233 66272 33233 66273 33237 66273 33156 66273 33233 66274 33156 66274 33155 66274 33231 66275 33234 66275 33236 66275 33236 66276 33234 66276 33235 66276 33236 66277 33235 66277 33232 66277 33232 66278 33235 66278 33147 66278 33232 66279 33147 66279 33237 66279 33155 66280 33154 66280 33233 66280 33233 66281 33154 66281 33238 66281 33233 66282 33238 66282 33239 66282 33239 66283 33238 66283 33240 66283 33239 66284 33240 66284 33254 66284 33241 66285 33255 66285 33242 66285 33242 66286 33255 66286 33258 66286 33242 66287 33258 66287 33243 66287 33243 66288 33258 66288 33244 66288 33243 66289 33244 66289 33253 66289 33253 66290 33244 66290 33245 66290 33253 66291 33245 66291 33252 66291 33252 66292 33245 66292 33261 66292 33252 66293 33261 66293 33246 66293 33246 66294 33261 66294 33262 66294 33246 66295 33262 66295 33251 66295 33251 66296 33262 66296 33264 66296 33251 66297 33264 66297 33249 66297 33249 66298 33264 66298 33247 66298 33249 66299 33247 66299 33248 66299 33248 66300 33227 66300 33249 66300 33249 66301 33227 66301 33250 66301 33249 66302 33250 66302 33251 66302 33251 66303 33250 66303 33229 66303 33251 66304 33229 66304 33246 66304 33246 66305 33229 66305 33236 66305 33246 66306 33236 66306 33252 66306 33252 66307 33236 66307 33232 66307 33252 66308 33232 66308 33253 66308 33253 66309 33232 66309 33233 66309 33253 66310 33233 66310 33243 66310 33243 66311 33233 66311 33239 66311 33243 66312 33239 66312 33242 66312 33242 66313 33239 66313 33254 66313 33242 66314 33254 66314 33275 66314 33301 66315 33256 66315 33255 66315 33255 66316 33256 66316 33257 66316 33255 66317 33257 66317 33258 66317 33258 66318 33257 66318 33259 66318 33258 66319 33259 66319 33244 66319 33244 66320 33259 66320 33260 66320 33244 66321 33260 66321 33245 66321 33245 66322 33260 66322 33220 66322 33245 66323 33220 66323 33261 66323 33261 66324 33220 66324 33221 66324 33261 66325 33221 66325 33262 66325 33262 66326 33221 66326 33263 66326 33262 66327 33263 66327 33264 66327 33264 66328 33263 66328 33286 66328 33264 66329 33286 66329 33247 66329 33267 66330 33270 66330 33265 66330 33308 66331 33301 66331 33241 66331 33269 66332 33162 66332 33266 66332 33272 66333 33268 66333 33267 66333 33267 66334 33268 66334 33269 66334 33269 66335 33266 66335 33267 66335 33267 66336 33266 66336 33310 66336 33267 66337 33310 66337 33270 66337 33270 66338 33310 66338 33309 66338 33270 66339 33309 66339 33308 66339 33273 66340 33271 66340 33276 66340 33276 66341 33271 66341 33272 66341 33142 66342 33273 66342 33274 66342 33274 66343 33273 66343 33276 66343 33274 66344 33276 66344 33277 66344 33308 66345 33241 66345 33270 66345 33270 66346 33241 66346 33275 66346 33270 66347 33275 66347 33265 66347 33265 66348 33275 66348 33254 66348 33265 66349 33254 66349 33240 66349 33272 66350 33267 66350 33276 66350 33276 66351 33267 66351 33265 66351 33276 66352 33265 66352 33277 66352 33277 66353 33265 66353 33240 66353 33277 66354 33240 66354 33152 66354 33290 66355 33248 66355 33289 66355 33283 66356 33280 66356 33284 66356 33214 66357 33306 66357 33278 66357 33278 66358 33306 66358 33281 66358 33279 66359 33181 66359 33296 66359 33296 66360 33181 66360 33280 66360 33294 66361 33285 66361 33293 66361 33293 66362 33285 66362 33281 66362 33280 66363 33181 66363 33284 66363 33284 66364 33181 66364 33282 66364 33284 66365 33282 66365 33291 66365 33306 66366 33283 66366 33281 66366 33281 66367 33283 66367 33284 66367 33281 66368 33284 66368 33293 66368 33293 66369 33284 66369 33291 66369 33248 66370 33247 66370 33285 66370 33285 66371 33247 66371 33286 66371 33285 66372 33286 66372 33281 66372 33281 66373 33286 66373 33287 66373 33281 66374 33287 66374 33278 66374 33160 66375 33288 66375 33289 66375 33289 66376 33288 66376 33143 66376 33289 66377 33143 66377 33290 66377 33291 66378 33292 66378 33293 66378 33293 66379 33292 66379 33213 66379 33293 66380 33213 66380 33294 66380 33294 66381 33213 66381 33295 66381 33294 66382 33295 66382 33188 66382 33248 66383 33285 66383 33289 66383 33289 66384 33285 66384 33294 66384 33289 66385 33294 66385 33160 66385 33160 66386 33294 66386 33188 66386 33160 66387 33188 66387 33186 66387 33297 66388 33279 66388 33296 66388 33297 66389 33300 66389 33177 66389 33177 66390 33171 66390 33297 66390 33297 66391 33171 66391 33173 66391 33297 66392 33173 66392 33279 66392 33311 66393 33298 66393 33297 66393 33297 66394 33298 66394 33299 66394 33297 66395 33299 66395 33300 66395 33307 66396 33301 66396 33308 66396 33256 66397 33301 66397 33302 66397 33302 66398 33301 66398 33307 66398 33302 66399 33307 66399 33218 66399 33214 66400 33303 66400 33307 66400 33307 66401 33303 66401 33304 66401 33304 66402 33216 66402 33307 66402 33307 66403 33216 66403 33305 66403 33307 66404 33305 66404 33218 66404 33214 66405 33307 66405 33306 66405 33306 66406 33307 66406 33308 66406 33306 66407 33308 66407 33283 66407 33283 66408 33308 66408 33309 66408 33283 66409 33309 66409 33280 66409 33280 66410 33309 66410 33310 66410 33280 66411 33310 66411 33296 66411 33296 66412 33310 66412 33266 66412 33296 66413 33266 66413 33297 66413 33297 66414 33266 66414 33162 66414 33297 66415 33162 66415 33311 66415 33314 66416 33341 66416 33312 66416 33361 66417 33323 66417 33315 66417 33312 66418 33364 66418 33314 66418 33314 66419 33364 66419 33313 66419 33314 66420 33313 66420 33315 66420 33315 66421 33313 66421 33316 66421 33315 66422 33316 66422 33361 66422 33317 66423 33140 66423 33318 66423 33318 66424 33140 66424 33141 66424 33318 66425 33141 66425 33363 66425 33363 66426 33141 66426 33319 66426 33363 66427 33319 66427 33320 66427 33320 66428 33319 66428 33322 66428 33320 66429 33322 66429 33321 66429 33321 66430 33322 66430 33323 66430 33321 66431 33323 66431 33362 66431 33362 66432 33323 66432 33361 66432 33357 66433 33324 66433 33359 66433 33359 66434 33324 66434 33325 66434 33359 66435 33325 66435 33138 66435 33357 66436 33355 66436 33324 66436 33324 66437 33355 66437 33326 66437 33324 66438 33326 66438 33327 66438 33326 66439 33328 66439 33327 66439 33327 66440 33328 66440 33350 66440 33327 66441 33350 66441 33333 66441 32986 66442 33349 66442 33351 66442 33351 66443 33349 66443 33329 66443 33351 66444 33329 66444 33330 66444 33330 66445 33329 66445 33333 66445 33330 66446 33333 66446 33331 66446 33331 66447 33333 66447 33350 66447 33332 66448 33325 66448 33324 66448 33127 66449 33131 66449 33333 66449 33333 66450 33131 66450 33338 66450 33333 66451 33338 66451 33327 66451 33315 66452 33323 66452 33335 66452 33322 66453 33334 66453 33323 66453 33323 66454 33334 66454 32961 66454 33323 66455 32961 66455 33335 66455 33319 66456 33336 66456 33322 66456 33322 66457 33336 66457 33337 66457 33322 66458 33337 66458 33334 66458 33338 66459 33130 66459 33327 66459 33327 66460 33130 66460 33134 66460 33327 66461 33134 66461 33324 66461 33324 66462 33134 66462 33136 66462 33324 66463 33136 66463 33332 66463 33335 66464 32963 66464 33315 66464 33315 66465 32963 66465 33339 66465 33315 66466 33339 66466 33314 66466 33314 66467 33339 66467 33340 66467 33314 66468 33340 66468 33341 66468 33341 66469 33340 66469 33342 66469 33341 66470 33342 66470 33343 66470 33343 66471 33342 66471 33128 66471 33343 66472 33128 66472 33349 66472 33349 66473 33128 66473 33127 66473 33349 66474 33127 66474 33329 66474 33329 66475 33127 66475 33333 66475 33140 66476 33317 66476 33346 66476 33140 66477 33346 66477 33344 66477 33344 66478 33346 66478 32968 66478 33344 66479 32968 66479 33139 66479 33345 66480 32968 66480 32977 66480 32977 66481 32968 66481 33346 66481 32977 66482 33346 66482 33347 66482 33317 66483 32980 66483 33346 66483 33346 66484 32980 66484 32978 66484 33346 66485 32978 66485 33347 66485 33312 66486 33341 66486 33348 66486 33348 66487 33341 66487 33343 66487 33348 66488 33343 66488 32986 66488 32986 66489 33343 66489 33349 66489 33016 66490 33015 66490 33326 66490 33326 66491 33015 66491 33328 66491 33328 66492 33015 66492 33005 66492 33328 66493 33005 66493 33350 66493 33350 66494 33005 66494 33006 66494 33350 66495 33006 66495 33331 66495 33331 66496 33006 66496 33007 66496 33331 66497 33007 66497 33330 66497 33330 66498 33007 66498 33032 66498 33330 66499 33032 66499 33351 66499 33351 66500 33032 66500 33352 66500 33351 66501 33352 66501 32986 66501 32986 66502 33352 66502 33353 66502 32986 66503 33353 66503 32987 66503 33016 66504 33326 66504 33354 66504 33354 66505 33326 66505 33355 66505 33354 66506 33355 66506 33356 66506 33356 66507 33355 66507 33357 66507 33356 66508 33357 66508 33358 66508 33358 66509 33357 66509 33359 66509 33358 66510 33359 66510 33013 66510 32980 66511 33317 66511 33062 66511 33062 66512 33317 66512 33318 66512 33062 66513 33318 66513 33360 66513 33360 66514 33318 66514 33363 66514 33361 66515 33066 66515 33362 66515 33362 66516 33066 66516 33065 66516 33362 66517 33065 66517 33321 66517 33321 66518 33065 66518 33063 66518 33321 66519 33063 66519 33320 66519 33320 66520 33063 66520 33059 66520 33320 66521 33059 66521 33363 66521 33363 66522 33059 66522 33058 66522 33363 66523 33058 66523 33360 66523 33312 66524 33038 66524 33364 66524 33364 66525 33038 66525 33365 66525 33364 66526 33365 66526 33313 66526 33365 66527 33070 66527 33313 66527 33313 66528 33070 66528 33366 66528 33313 66529 33366 66529 33316 66529 33316 66530 33366 66530 33069 66530 33316 66531 33069 66531 33361 66531 33361 66532 33069 66532 33067 66532 33361 66533 33067 66533 33066 66533 33459 66534 33460 66534 33739 66534 33739 66535 33762 66535 33459 66535 33459 66536 33762 66536 33763 66536 33459 66537 33763 66537 33457 66537 33457 66538 33763 66538 33367 66538 33457 66539 33367 66539 33368 66539 33368 66540 33367 66540 33759 66540 33368 66541 33759 66541 33455 66541 33455 66542 33759 66542 33758 66542 33455 66543 33758 66543 33456 66543 33456 66544 33758 66544 33369 66544 33369 66545 33758 66545 33756 66545 33369 66546 33756 66546 33370 66546 33756 66547 33371 66547 33370 66547 33370 66548 33371 66548 33755 66548 33370 66549 33755 66549 33464 66549 33464 66550 33755 66550 33372 66550 33372 66551 33755 66551 33373 66551 33372 66552 33373 66552 33468 66552 33437 66553 33742 66553 33374 66553 33374 66554 33742 66554 33743 66554 33374 66555 33743 66555 33376 66555 33376 66556 33743 66556 33375 66556 33376 66557 33375 66557 33769 66557 33769 66558 33375 66558 33745 66558 33378 66559 33377 66559 33740 66559 33378 66560 33740 66560 33379 66560 33379 66561 33740 66561 33380 66561 33379 66562 33380 66562 33508 66562 33508 66563 33380 66563 33739 66563 33508 66564 33739 66564 33460 66564 33516 66565 33493 66565 33420 66565 33392 66566 33516 66566 33395 66566 33513 66567 33381 66567 33514 66567 33514 66568 33381 66568 33382 66568 33514 66569 33382 66569 33515 66569 33515 66570 33382 66570 33388 66570 33515 66571 33388 66571 33499 66571 33499 66572 33388 66572 33390 66572 33383 66573 33502 66573 33389 66573 33387 66574 33434 66574 33384 66574 33384 66575 33434 66575 33385 66575 33384 66576 33385 66576 33383 66576 33383 66577 33385 66577 33509 66577 33383 66578 33509 66578 33502 66578 33391 66579 33381 66579 33423 66579 33423 66580 33381 66580 33513 66580 33423 66581 33513 66581 33386 66581 33391 66582 33387 66582 33381 66582 33381 66583 33387 66583 33384 66583 33381 66584 33384 66584 33382 66584 33382 66585 33384 66585 33383 66585 33382 66586 33383 66586 33388 66586 33388 66587 33383 66587 33389 66587 33388 66588 33389 66588 33390 66588 33425 66589 33430 66589 33391 66589 33391 66590 33430 66590 33431 66590 33391 66591 33431 66591 33387 66591 33424 66592 33392 66592 33393 66592 33393 66593 33392 66593 33395 66593 33393 66594 33395 66594 33394 66594 33394 66595 33395 66595 33422 66595 33410 66596 33405 66596 33396 66596 33404 66597 33426 66597 33397 66597 33397 66598 33426 66598 33428 66598 33397 66599 33428 66599 33769 66599 33403 66600 33398 66600 33399 66600 33399 66601 33398 66601 33378 66601 33399 66602 33378 66602 33419 66602 33400 66603 33401 66603 33409 66603 33409 66604 33401 66604 33402 66604 33409 66605 33402 66605 33403 66605 33403 66606 33402 66606 33776 66606 33403 66607 33776 66607 33398 66607 33404 66608 33770 66608 33405 66608 33405 66609 33770 66609 33775 66609 33405 66610 33775 66610 33396 66610 33396 66611 33775 66611 33406 66611 33396 66612 33406 66612 33407 66612 33407 66613 33406 66613 33773 66613 33407 66614 33773 66614 33409 66614 33409 66615 33773 66615 33408 66615 33409 66616 33408 66616 33400 66616 33410 66617 33411 66617 33429 66617 33429 66618 33411 66618 33416 66618 33429 66619 33416 66619 33412 66619 33412 66620 33416 66620 33417 66620 33412 66621 33417 66621 33432 66621 33432 66622 33417 66622 33418 66622 33432 66623 33418 66623 33433 66623 33433 66624 33418 66624 33413 66624 33433 66625 33413 66625 33435 66625 33435 66626 33413 66626 33414 66626 33435 66627 33414 66627 33415 66627 33410 66628 33396 66628 33411 66628 33411 66629 33396 66629 33407 66629 33411 66630 33407 66630 33416 66630 33416 66631 33407 66631 33409 66631 33416 66632 33409 66632 33417 66632 33417 66633 33409 66633 33403 66633 33417 66634 33403 66634 33418 66634 33418 66635 33403 66635 33399 66635 33418 66636 33399 66636 33413 66636 33413 66637 33399 66637 33419 66637 33413 66638 33419 66638 33414 66638 33516 66639 33420 66639 33395 66639 33395 66640 33420 66640 33421 66640 33395 66641 33421 66641 33422 66641 33422 66642 33421 66642 33497 66642 33422 66643 33497 66643 33427 66643 33386 66644 33424 66644 33423 66644 33423 66645 33424 66645 33393 66645 33423 66646 33393 66646 33391 66646 33391 66647 33393 66647 33394 66647 33391 66648 33394 66648 33425 66648 33425 66649 33394 66649 33422 66649 33425 66650 33422 66650 33426 66650 33426 66651 33422 66651 33427 66651 33426 66652 33427 66652 33428 66652 33404 66653 33405 66653 33426 66653 33426 66654 33405 66654 33410 66654 33426 66655 33410 66655 33425 66655 33425 66656 33410 66656 33429 66656 33425 66657 33429 66657 33430 66657 33430 66658 33429 66658 33412 66658 33430 66659 33412 66659 33431 66659 33431 66660 33412 66660 33432 66660 33431 66661 33432 66661 33387 66661 33387 66662 33432 66662 33433 66662 33387 66663 33433 66663 33434 66663 33434 66664 33433 66664 33435 66664 33434 66665 33435 66665 33385 66665 33385 66666 33435 66666 33415 66666 33385 66667 33415 66667 33509 66667 33436 66668 33437 66668 33469 66668 33449 66669 33487 66669 33446 66669 33470 66670 33483 66670 33443 66670 33438 66671 33439 66671 33440 66671 33440 66672 33439 66672 33441 66672 33440 66673 33441 66673 33521 66673 33521 66674 33441 66674 33452 66674 33521 66675 33452 66675 33522 66675 33442 66676 33443 66676 33519 66676 33518 66677 33520 66677 33444 66677 33444 66678 33520 66678 33445 66678 33445 66679 33520 66679 33523 66679 33445 66680 33523 66680 33446 66680 33446 66681 33487 66681 33445 66681 33445 66682 33487 66682 33485 66682 33445 66683 33485 66683 33444 66683 33523 66684 33447 66684 33446 66684 33446 66685 33447 66685 33448 66685 33446 66686 33448 66686 33449 66686 33449 66687 33448 66687 33453 66687 33449 66688 33453 66688 33450 66688 33450 66689 33453 66689 33454 66689 33450 66690 33454 66690 33490 66690 33490 66691 33454 66691 33451 66691 33490 66692 33451 66692 33507 66692 33447 66693 33522 66693 33448 66693 33448 66694 33522 66694 33452 66694 33448 66695 33452 66695 33453 66695 33453 66696 33452 66696 33441 66696 33453 66697 33441 66697 33454 66697 33454 66698 33441 66698 33439 66698 33454 66699 33439 66699 33451 66699 33477 66700 33455 66700 33456 66700 33477 66701 33456 66701 33479 66701 33455 66702 33477 66702 33368 66702 33368 66703 33477 66703 33458 66703 33368 66704 33458 66704 33457 66704 33457 66705 33458 66705 33462 66705 33457 66706 33462 66706 33459 66706 33460 66707 33459 66707 33461 66707 33461 66708 33459 66708 33462 66708 33461 66709 33462 66709 33463 66709 33468 66710 33467 66710 33372 66710 33372 66711 33467 66711 33465 66711 33372 66712 33465 66712 33464 66712 33464 66713 33465 66713 33466 66713 33464 66714 33466 66714 33370 66714 33370 66715 33466 66715 33479 66715 33370 66716 33479 66716 33369 66716 33369 66717 33479 66717 33456 66717 33482 66718 33467 66718 33469 66718 33469 66719 33467 66719 33468 66719 33469 66720 33468 66720 33436 66720 33443 66721 33442 66721 33470 66721 33470 66722 33442 66722 33484 66722 33470 66723 33484 66723 33481 66723 33481 66724 33484 66724 33471 66724 33481 66725 33471 66725 33480 66725 33480 66726 33471 66726 33486 66726 33480 66727 33486 66727 33478 66727 33478 66728 33486 66728 33488 66728 33478 66729 33488 66729 33472 66729 33472 66730 33488 66730 33489 66730 33472 66731 33489 66731 33473 66731 33473 66732 33489 66732 33475 66732 33473 66733 33475 66733 33474 66733 33474 66734 33475 66734 33476 66734 33474 66735 33476 66735 33463 66735 33463 66736 33462 66736 33474 66736 33474 66737 33462 66737 33458 66737 33474 66738 33458 66738 33473 66738 33473 66739 33458 66739 33477 66739 33473 66740 33477 66740 33472 66740 33472 66741 33477 66741 33479 66741 33472 66742 33479 66742 33478 66742 33478 66743 33479 66743 33466 66743 33478 66744 33466 66744 33480 66744 33480 66745 33466 66745 33465 66745 33480 66746 33465 66746 33481 66746 33481 66747 33465 66747 33467 66747 33481 66748 33467 66748 33470 66748 33470 66749 33467 66749 33482 66749 33470 66750 33482 66750 33483 66750 33519 66751 33518 66751 33442 66751 33442 66752 33518 66752 33444 66752 33442 66753 33444 66753 33484 66753 33484 66754 33444 66754 33485 66754 33484 66755 33485 66755 33471 66755 33471 66756 33485 66756 33487 66756 33471 66757 33487 66757 33486 66757 33486 66758 33487 66758 33449 66758 33486 66759 33449 66759 33488 66759 33488 66760 33449 66760 33450 66760 33488 66761 33450 66761 33489 66761 33489 66762 33450 66762 33490 66762 33489 66763 33490 66763 33475 66763 33475 66764 33490 66764 33507 66764 33475 66765 33507 66765 33476 66765 33491 66766 33496 66766 33492 66766 33524 66767 33519 66767 33443 66767 33420 66768 33493 66768 33494 66768 33497 66769 33421 66769 33491 66769 33491 66770 33421 66770 33420 66770 33420 66771 33494 66771 33491 66771 33491 66772 33494 66772 33527 66772 33491 66773 33527 66773 33496 66773 33496 66774 33527 66774 33526 66774 33496 66775 33526 66775 33524 66775 33428 66776 33427 66776 33495 66776 33495 66777 33427 66777 33497 66777 33769 66778 33428 66778 33376 66778 33376 66779 33428 66779 33495 66779 33376 66780 33495 66780 33374 66780 33524 66781 33443 66781 33496 66781 33496 66782 33443 66782 33483 66782 33496 66783 33483 66783 33492 66783 33492 66784 33483 66784 33482 66784 33492 66785 33482 66785 33469 66785 33497 66786 33491 66786 33495 66786 33495 66787 33491 66787 33492 66787 33495 66788 33492 66788 33374 66788 33374 66789 33492 66789 33469 66789 33374 66790 33469 66790 33437 66790 33461 66791 33463 66791 33511 66791 33525 66792 33498 66792 33501 66792 33438 66793 33503 66793 33439 66793 33439 66794 33503 66794 33504 66794 33499 66795 33390 66795 33500 66795 33500 66796 33390 66796 33498 66796 33510 66797 33506 66797 33505 66797 33505 66798 33506 66798 33504 66798 33498 66799 33390 66799 33501 66799 33501 66800 33390 66800 33389 66800 33501 66801 33389 66801 33502 66801 33503 66802 33525 66802 33504 66802 33504 66803 33525 66803 33501 66803 33504 66804 33501 66804 33505 66804 33505 66805 33501 66805 33502 66805 33463 66806 33476 66806 33506 66806 33506 66807 33476 66807 33507 66807 33506 66808 33507 66808 33504 66808 33504 66809 33507 66809 33451 66809 33504 66810 33451 66810 33439 66810 33379 66811 33508 66811 33511 66811 33511 66812 33508 66812 33460 66812 33511 66813 33460 66813 33461 66813 33502 66814 33509 66814 33505 66814 33505 66815 33509 66815 33415 66815 33505 66816 33415 66816 33510 66816 33510 66817 33415 66817 33414 66817 33510 66818 33414 66818 33419 66818 33463 66819 33506 66819 33511 66819 33511 66820 33506 66820 33510 66820 33511 66821 33510 66821 33379 66821 33379 66822 33510 66822 33419 66822 33379 66823 33419 66823 33378 66823 33512 66824 33499 66824 33500 66824 33512 66825 33386 66825 33513 66825 33513 66826 33514 66826 33512 66826 33512 66827 33514 66827 33515 66827 33512 66828 33515 66828 33499 66828 33516 66829 33392 66829 33512 66829 33512 66830 33392 66830 33424 66830 33512 66831 33424 66831 33386 66831 33517 66832 33519 66832 33524 66832 33518 66833 33519 66833 33520 66833 33520 66834 33519 66834 33517 66834 33520 66835 33517 66835 33523 66835 33438 66836 33440 66836 33517 66836 33517 66837 33440 66837 33521 66837 33521 66838 33522 66838 33517 66838 33517 66839 33522 66839 33447 66839 33517 66840 33447 66840 33523 66840 33438 66841 33517 66841 33503 66841 33503 66842 33517 66842 33524 66842 33503 66843 33524 66843 33525 66843 33525 66844 33524 66844 33526 66844 33525 66845 33526 66845 33498 66845 33498 66846 33526 66846 33527 66846 33498 66847 33527 66847 33500 66847 33500 66848 33527 66848 33494 66848 33500 66849 33494 66849 33512 66849 33512 66850 33494 66850 33493 66850 33512 66851 33493 66851 33516 66851 33742 66852 33437 66852 33373 66852 33373 66853 33437 66853 33436 66853 33373 66854 33436 66854 33468 66854 33373 66855 33528 66855 33742 66855 33742 66856 33528 66856 33555 66856 33678 66857 33676 66857 33544 66857 33671 66858 33669 66858 33545 66858 33545 66859 33669 66859 33668 66859 33545 66860 33668 66860 33529 66860 33529 66861 33668 66861 33530 66861 33529 66862 33530 66862 33672 66862 33544 66863 33676 66863 33545 66863 33545 66864 33676 66864 33531 66864 33545 66865 33531 66865 33671 66865 33678 66866 33544 66866 33532 66866 33532 66867 33544 66867 33533 66867 33532 66868 33533 66868 33535 66868 33533 66869 33534 66869 33535 66869 33535 66870 33534 66870 33542 66870 33535 66871 33542 66871 33536 66871 33536 66872 33542 66872 33537 66872 33536 66873 33537 66873 33679 66873 33679 66874 33537 66874 33681 66874 33537 66875 33538 66875 33681 66875 33681 66876 33538 66876 33600 66876 33681 66877 33600 66877 33539 66877 33541 66878 33560 66878 33600 66878 33534 66879 33543 66879 33540 66879 33600 66880 33538 66880 33541 66880 33541 66881 33538 66881 33537 66881 33541 66882 33537 66882 33540 66882 33540 66883 33537 66883 33542 66883 33540 66884 33542 66884 33534 66884 33534 66885 33533 66885 33543 66885 33543 66886 33533 66886 33544 66886 33543 66887 33544 66887 33563 66887 33563 66888 33544 66888 33545 66888 33563 66889 33545 66889 33741 66889 33741 66890 33545 66890 33529 66890 33741 66891 33529 66891 33768 66891 33581 66892 33767 66892 33584 66892 33584 66893 33767 66893 33764 66893 33584 66894 33764 66894 33529 66894 33529 66895 33764 66895 33768 66895 33546 66896 33551 66896 33553 66896 33566 66897 33567 66897 33547 66897 33547 66898 33567 66898 33574 66898 33547 66899 33574 66899 33738 66899 33738 66900 33574 66900 33579 66900 33738 66901 33579 66901 33553 66901 33553 66902 33579 66902 33548 66902 33553 66903 33548 66903 33546 66903 33546 66904 33578 66904 33551 66904 33551 66905 33578 66905 33550 66905 33551 66906 33550 66906 33552 66906 33572 66907 33558 66907 33576 66907 33576 66908 33558 66908 33557 66908 33576 66909 33557 66909 33549 66909 33549 66910 33557 66910 33552 66910 33549 66911 33552 66911 33577 66911 33577 66912 33552 66912 33550 66912 33554 66913 33738 66913 33553 66913 33556 66914 33551 66914 33552 66914 33556 66915 33757 66915 33551 66915 33551 66916 33757 66916 33760 66916 33551 66917 33760 66917 33553 66917 33553 66918 33760 66918 33761 66918 33553 66919 33761 66919 33554 66919 33555 66920 33528 66920 33552 66920 33552 66921 33528 66921 33754 66921 33552 66922 33754 66922 33556 66922 33552 66923 33557 66923 33555 66923 33555 66924 33557 66924 33558 66924 33555 66925 33558 66925 33744 66925 33744 66926 33558 66926 33573 66926 33744 66927 33573 66927 33559 66927 33559 66928 33573 66928 33560 66928 33559 66929 33560 66929 33751 66929 33751 66930 33560 66930 33541 66930 33751 66931 33541 66931 33561 66931 33561 66932 33541 66932 33540 66932 33561 66933 33540 66933 33562 66933 33562 66934 33540 66934 33543 66934 33562 66935 33543 66935 33749 66935 33741 66936 33746 66936 33563 66936 33563 66937 33746 66937 33748 66937 33563 66938 33748 66938 33543 66938 33543 66939 33748 66939 33564 66939 33543 66940 33564 66940 33749 66940 33767 66941 33581 66941 33569 66941 33767 66942 33569 66942 33565 66942 33565 66943 33569 66943 33567 66943 33565 66944 33567 66944 33566 66944 33587 66945 33567 66945 33568 66945 33568 66946 33567 66946 33569 66946 33568 66947 33569 66947 33590 66947 33581 66948 33675 66948 33569 66948 33569 66949 33675 66949 33570 66949 33569 66950 33570 66950 33590 66950 33600 66951 33560 66951 33571 66951 33571 66952 33560 66952 33573 66952 33571 66953 33573 66953 33572 66953 33572 66954 33573 66954 33558 66954 33574 66955 33567 66955 33587 66955 33737 66956 33572 66956 33575 66956 33575 66957 33572 66957 33576 66957 33575 66958 33576 66958 33610 66958 33610 66959 33576 66959 33642 66959 33576 66960 33549 66960 33642 66960 33642 66961 33549 66961 33577 66961 33642 66962 33577 66962 33644 66962 33546 66963 33645 66963 33578 66963 33578 66964 33645 66964 33644 66964 33578 66965 33644 66965 33550 66965 33550 66966 33644 66966 33577 66966 33587 66967 33635 66967 33574 66967 33574 66968 33635 66968 33636 66968 33574 66969 33636 66969 33579 66969 33579 66970 33636 66970 33622 66970 33579 66971 33622 66971 33548 66971 33548 66972 33622 66972 33580 66972 33548 66973 33580 66973 33546 66973 33546 66974 33580 66974 33601 66974 33546 66975 33601 66975 33645 66975 33675 66976 33581 66976 33582 66976 33582 66977 33581 66977 33584 66977 33582 66978 33584 66978 33583 66978 33583 66979 33584 66979 33529 66979 33583 66980 33529 66980 33672 66980 33595 66981 33585 66981 33712 66981 33585 66982 33595 66982 33662 66982 33588 66983 33589 66983 33596 66983 33586 66984 33587 66984 33568 66984 33593 66985 33621 66985 33588 66985 33588 66986 33621 66986 33586 66986 33586 66987 33568 66987 33588 66987 33588 66988 33568 66988 33590 66988 33588 66989 33590 66989 33589 66989 33589 66990 33590 66990 33570 66990 33589 66991 33570 66991 33675 66991 33652 66992 33620 66992 33594 66992 33594 66993 33620 66993 33593 66993 33675 66994 33673 66994 33589 66994 33589 66995 33673 66995 33687 66995 33589 66996 33687 66996 33596 66996 33596 66997 33687 66997 33591 66997 33596 66998 33591 66998 33702 66998 33592 66999 33652 66999 33598 66999 33598 67000 33652 67000 33594 67000 33598 67001 33594 67001 33595 67001 33593 67002 33588 67002 33594 67002 33594 67003 33588 67003 33596 67003 33594 67004 33596 67004 33595 67004 33595 67005 33596 67005 33702 67005 33595 67006 33702 67006 33662 67006 33597 67007 33592 67007 33719 67007 33719 67008 33592 67008 33598 67008 33719 67009 33598 67009 33718 67009 33718 67010 33598 67010 33595 67010 33718 67011 33595 67011 33716 67011 33716 67012 33595 67012 33712 67012 33571 67013 33572 67013 33737 67013 33737 67014 33736 67014 33571 67014 33571 67015 33736 67015 33599 67015 33571 67016 33599 67016 33600 67016 33600 67017 33599 67017 33735 67017 33600 67018 33735 67018 33539 67018 33601 67019 33580 67019 33624 67019 33622 67020 33636 67020 33623 67020 33614 67021 33611 67021 33612 67021 33706 67022 33602 67022 33613 67022 33604 67023 33641 67023 33640 67023 33614 67024 33603 67024 33611 67024 33611 67025 33603 67025 33707 67025 33611 67026 33707 67026 33604 67026 33605 67027 33704 67027 33650 67027 33650 67028 33704 67028 33606 67028 33650 67029 33606 67029 33648 67029 33650 67030 33651 67030 33605 67030 33605 67031 33651 67031 33592 67031 33605 67032 33592 67032 33597 67032 33606 67033 33706 67033 33648 67033 33648 67034 33706 67034 33613 67034 33648 67035 33613 67035 33647 67035 33647 67036 33613 67036 33615 67036 33647 67037 33615 67037 33607 67037 33607 67038 33615 67038 33616 67038 33607 67039 33616 67039 33609 67039 33609 67040 33616 67040 33608 67040 33609 67041 33608 67041 33618 67041 33575 67042 33610 67042 33638 67042 33638 67043 33610 67043 33643 67043 33604 67044 33640 67044 33611 67044 33611 67045 33640 67045 33639 67045 33611 67046 33639 67046 33612 67046 33612 67047 33639 67047 33638 67047 33612 67048 33638 67048 33617 67048 33617 67049 33638 67049 33643 67049 33617 67050 33643 67050 33646 67050 33602 67051 33603 67051 33613 67051 33613 67052 33603 67052 33614 67052 33613 67053 33614 67053 33615 67053 33615 67054 33614 67054 33612 67054 33615 67055 33612 67055 33616 67055 33616 67056 33612 67056 33617 67056 33616 67057 33617 67057 33608 67057 33608 67058 33617 67058 33646 67058 33608 67059 33646 67059 33618 67059 33601 67060 33624 67060 33645 67060 33652 67061 33630 67061 33620 67061 33620 67062 33630 67062 33619 67062 33620 67063 33619 67063 33593 67063 33593 67064 33619 67064 33632 67064 33593 67065 33632 67065 33621 67065 33621 67066 33632 67066 33633 67066 33621 67067 33633 67067 33586 67067 33586 67068 33633 67068 33634 67068 33586 67069 33634 67069 33587 67069 33587 67070 33634 67070 33635 67070 33580 67071 33622 67071 33624 67071 33624 67072 33622 67072 33623 67072 33624 67073 33623 67073 33625 67073 33625 67074 33623 67074 33626 67074 33625 67075 33626 67075 33627 67075 33627 67076 33626 67076 33628 67076 33627 67077 33628 67077 33629 67077 33629 67078 33628 67078 33631 67078 33629 67079 33631 67079 33649 67079 33630 67080 33649 67080 33619 67080 33619 67081 33649 67081 33631 67081 33619 67082 33631 67082 33632 67082 33632 67083 33631 67083 33628 67083 33632 67084 33628 67084 33633 67084 33633 67085 33628 67085 33626 67085 33633 67086 33626 67086 33634 67086 33634 67087 33626 67087 33623 67087 33634 67088 33623 67088 33635 67088 33635 67089 33623 67089 33636 67089 33737 67090 33575 67090 33637 67090 33637 67091 33575 67091 33638 67091 33637 67092 33638 67092 33734 67092 33734 67093 33638 67093 33639 67093 33734 67094 33639 67094 33733 67094 33733 67095 33639 67095 33640 67095 33733 67096 33640 67096 33724 67096 33724 67097 33640 67097 33641 67097 33724 67098 33641 67098 33726 67098 33610 67099 33642 67099 33643 67099 33643 67100 33642 67100 33644 67100 33643 67101 33644 67101 33646 67101 33646 67102 33644 67102 33645 67102 33646 67103 33645 67103 33618 67103 33618 67104 33645 67104 33624 67104 33618 67105 33624 67105 33609 67105 33609 67106 33624 67106 33625 67106 33609 67107 33625 67107 33607 67107 33607 67108 33625 67108 33627 67108 33607 67109 33627 67109 33647 67109 33647 67110 33627 67110 33629 67110 33647 67111 33629 67111 33648 67111 33648 67112 33629 67112 33649 67112 33648 67113 33649 67113 33650 67113 33650 67114 33649 67114 33630 67114 33650 67115 33630 67115 33651 67115 33651 67116 33630 67116 33652 67116 33651 67117 33652 67117 33592 67117 33681 67118 33539 67118 33720 67118 33582 67119 33583 67119 33674 67119 33661 67120 33698 67120 33653 67120 33692 67121 33729 67121 33656 67121 33715 67122 33714 67122 33654 67122 33654 67123 33714 67123 33655 67123 33654 67124 33655 67124 33665 67124 33665 67125 33655 67125 33712 67125 33665 67126 33712 67126 33585 67126 33694 67127 33656 67127 33709 67127 33708 67128 33710 67128 33693 67128 33693 67129 33710 67129 33657 67129 33693 67130 33657 67130 33658 67130 33658 67131 33657 67131 33711 67131 33658 67132 33711 67132 33653 67132 33653 67133 33698 67133 33658 67133 33658 67134 33698 67134 33659 67134 33658 67135 33659 67135 33693 67135 33711 67136 33660 67136 33653 67136 33653 67137 33660 67137 33663 67137 33653 67138 33663 67138 33661 67138 33661 67139 33663 67139 33664 67139 33661 67140 33664 67140 33699 67140 33699 67141 33664 67141 33666 67141 33699 67142 33666 67142 33701 67142 33701 67143 33666 67143 33662 67143 33701 67144 33662 67144 33702 67144 33660 67145 33715 67145 33663 67145 33663 67146 33715 67146 33654 67146 33663 67147 33654 67147 33664 67147 33664 67148 33654 67148 33665 67148 33664 67149 33665 67149 33666 67149 33666 67150 33665 67150 33585 67150 33666 67151 33585 67151 33662 67151 33677 67152 33670 67152 33531 67152 33530 67153 33668 67153 33667 67153 33667 67154 33668 67154 33669 67154 33667 67155 33669 67155 33670 67155 33670 67156 33669 67156 33671 67156 33670 67157 33671 67157 33531 67157 33674 67158 33583 67158 33667 67158 33667 67159 33583 67159 33672 67159 33667 67160 33672 67160 33530 67160 33687 67161 33673 67161 33674 67161 33674 67162 33673 67162 33675 67162 33674 67163 33675 67163 33582 67163 33690 67164 33535 67164 33691 67164 33691 67165 33535 67165 33536 67165 33531 67166 33676 67166 33677 67166 33677 67167 33676 67167 33678 67167 33677 67168 33678 67168 33690 67168 33690 67169 33678 67169 33532 67169 33690 67170 33532 67170 33535 67170 33536 67171 33679 67171 33691 67171 33691 67172 33679 67172 33681 67172 33691 67173 33681 67173 33680 67173 33680 67174 33681 67174 33720 67174 33680 67175 33720 67175 33721 67175 33656 67176 33694 67176 33692 67176 33692 67177 33694 67177 33695 67177 33692 67178 33695 67178 33682 67178 33682 67179 33695 67179 33696 67179 33682 67180 33696 67180 33683 67180 33683 67181 33696 67181 33697 67181 33683 67182 33697 67182 33684 67182 33684 67183 33697 67183 33685 67183 33684 67184 33685 67184 33689 67184 33689 67185 33685 67185 33700 67185 33689 67186 33700 67186 33686 67186 33686 67187 33700 67187 33703 67187 33686 67188 33703 67188 33688 67188 33688 67189 33703 67189 33591 67189 33688 67190 33591 67190 33687 67190 33687 67191 33674 67191 33688 67191 33688 67192 33674 67192 33667 67192 33688 67193 33667 67193 33686 67193 33686 67194 33667 67194 33670 67194 33686 67195 33670 67195 33689 67195 33689 67196 33670 67196 33677 67196 33689 67197 33677 67197 33684 67197 33684 67198 33677 67198 33690 67198 33684 67199 33690 67199 33683 67199 33683 67200 33690 67200 33691 67200 33683 67201 33691 67201 33682 67201 33682 67202 33691 67202 33680 67202 33682 67203 33680 67203 33692 67203 33692 67204 33680 67204 33721 67204 33692 67205 33721 67205 33729 67205 33709 67206 33708 67206 33694 67206 33694 67207 33708 67207 33693 67207 33694 67208 33693 67208 33695 67208 33695 67209 33693 67209 33659 67209 33695 67210 33659 67210 33696 67210 33696 67211 33659 67211 33698 67211 33696 67212 33698 67212 33697 67212 33697 67213 33698 67213 33661 67213 33697 67214 33661 67214 33685 67214 33685 67215 33661 67215 33699 67215 33685 67216 33699 67216 33700 67216 33700 67217 33699 67217 33701 67217 33700 67218 33701 67218 33703 67218 33703 67219 33701 67219 33702 67219 33703 67220 33702 67220 33591 67220 33713 67221 33709 67221 33717 67221 33705 67222 33597 67222 33719 67222 33605 67223 33597 67223 33704 67223 33704 67224 33597 67224 33705 67224 33704 67225 33705 67225 33606 67225 33606 67226 33705 67226 33706 67226 33641 67227 33604 67227 33705 67227 33705 67228 33604 67228 33707 67228 33707 67229 33603 67229 33705 67229 33705 67230 33603 67230 33602 67230 33705 67231 33602 67231 33706 67231 33715 67232 33660 67232 33713 67232 33713 67233 33660 67233 33711 67233 33708 67234 33709 67234 33710 67234 33710 67235 33709 67235 33713 67235 33710 67236 33713 67236 33657 67236 33657 67237 33713 67237 33711 67237 33712 67238 33655 67238 33713 67238 33713 67239 33655 67239 33714 67239 33713 67240 33714 67240 33715 67240 33712 67241 33713 67241 33716 67241 33716 67242 33713 67242 33717 67242 33716 67243 33717 67243 33718 67243 33718 67244 33717 67244 33728 67244 33718 67245 33728 67245 33719 67245 33719 67246 33728 67246 33727 67246 33719 67247 33727 67247 33705 67247 33705 67248 33727 67248 33726 67248 33705 67249 33726 67249 33641 67249 33720 67250 33539 67250 33735 67250 33729 67251 33721 67251 33722 67251 33637 67252 33734 67252 33723 67252 33733 67253 33724 67253 33725 67253 33724 67254 33726 67254 33725 67254 33725 67255 33726 67255 33727 67255 33725 67256 33727 67256 33731 67256 33731 67257 33727 67257 33728 67257 33731 67258 33728 67258 33730 67258 33730 67259 33728 67259 33717 67259 33730 67260 33717 67260 33656 67260 33656 67261 33717 67261 33709 67261 33656 67262 33729 67262 33730 67262 33730 67263 33729 67263 33722 67263 33730 67264 33722 67264 33731 67264 33731 67265 33722 67265 33732 67265 33731 67266 33732 67266 33725 67266 33725 67267 33732 67267 33723 67267 33725 67268 33723 67268 33733 67268 33733 67269 33723 67269 33734 67269 33721 67270 33720 67270 33722 67270 33722 67271 33720 67271 33735 67271 33722 67272 33735 67272 33732 67272 33732 67273 33735 67273 33599 67273 33732 67274 33599 67274 33723 67274 33723 67275 33599 67275 33736 67275 33723 67276 33736 67276 33637 67276 33637 67277 33736 67277 33737 67277 33738 67278 33554 67278 33739 67278 33738 67279 33739 67279 33765 67279 33739 67280 33380 67280 33765 67280 33765 67281 33380 67281 33740 67281 33765 67282 33740 67282 33766 67282 33766 67283 33740 67283 33741 67283 33741 67284 33740 67284 33377 67284 33741 67285 33377 67285 33746 67285 33742 67286 33555 67286 33743 67286 33743 67287 33555 67287 33744 67287 33743 67288 33744 67288 33375 67288 33375 67289 33744 67289 33559 67289 33375 67290 33559 67290 33745 67290 33745 67291 33559 67291 33751 67291 33748 67292 33746 67292 33377 67292 33771 67293 33749 67293 33564 67293 33377 67294 33747 67294 33748 67294 33748 67295 33747 67295 33778 67295 33748 67296 33778 67296 33564 67296 33564 67297 33778 67297 33777 67297 33564 67298 33777 67298 33771 67298 33771 67299 33772 67299 33749 67299 33749 67300 33772 67300 33774 67300 33749 67301 33774 67301 33562 67301 33745 67302 33751 67302 33750 67302 33750 67303 33751 67303 33561 67303 33750 67304 33561 67304 33752 67304 33752 67305 33561 67305 33562 67305 33752 67306 33562 67306 33753 67306 33753 67307 33562 67307 33774 67307 33528 67308 33373 67308 33754 67308 33754 67309 33373 67309 33755 67309 33754 67310 33755 67310 33556 67310 33755 67311 33371 67311 33556 67311 33556 67312 33371 67312 33756 67312 33556 67313 33756 67313 33757 67313 33757 67314 33756 67314 33758 67314 33757 67315 33758 67315 33760 67315 33758 67316 33759 67316 33760 67316 33760 67317 33759 67317 33367 67317 33760 67318 33367 67318 33761 67318 33739 67319 33554 67319 33762 67319 33762 67320 33554 67320 33761 67320 33762 67321 33761 67321 33763 67321 33763 67322 33761 67322 33367 67322 33768 67323 33764 67323 33767 67323 33547 67324 33738 67324 33566 67324 33566 67325 33738 67325 33765 67325 33566 67326 33765 67326 33565 67326 33565 67327 33765 67327 33766 67327 33565 67328 33766 67328 33767 67328 33767 67329 33766 67329 33741 67329 33767 67330 33741 67330 33768 67330 33747 67331 33377 67331 33378 67331 33769 67332 33745 67332 33397 67332 33397 67333 33745 67333 33750 67333 33397 67334 33750 67334 33404 67334 33404 67335 33750 67335 33770 67335 33774 67336 33775 67336 33753 67336 33753 67337 33775 67337 33770 67337 33753 67338 33770 67338 33752 67338 33752 67339 33770 67339 33750 67339 33771 67340 33408 67340 33772 67340 33772 67341 33408 67341 33773 67341 33772 67342 33773 67342 33774 67342 33774 67343 33773 67343 33406 67343 33774 67344 33406 67344 33775 67344 33776 67345 33402 67345 33777 67345 33777 67346 33402 67346 33401 67346 33777 67347 33401 67347 33771 67347 33771 67348 33401 67348 33400 67348 33771 67349 33400 67349 33408 67349 33378 67350 33398 67350 33747 67350 33747 67351 33398 67351 33776 67351 33747 67352 33776 67352 33778 67352 33778 67353 33776 67353 33777 67353 34702 67354 33782 67354 33787 67354 33781 67355 33779 67355 33785 67355 34609 67356 34614 67356 33780 67356 33780 67357 34614 67357 33781 67357 33780 67358 33781 67358 33806 67358 33806 67359 33781 67359 33785 67359 33782 67360 34704 67360 33787 67360 33787 67361 34704 67361 33783 67361 33787 67362 33783 67362 33779 67362 33779 67363 33783 67363 33784 67363 33779 67364 33784 67364 33785 67364 34701 67365 34702 67365 33786 67365 33786 67366 34702 67366 33787 67366 33786 67367 33787 67367 33792 67367 33792 67368 33787 67368 33779 67368 33792 67369 33779 67369 33794 67369 33794 67370 33779 67370 33781 67370 33794 67371 33781 67371 33788 67371 33788 67372 33781 67372 34614 67372 33789 67373 34701 67373 33790 67373 33790 67374 34701 67374 33786 67374 33790 67375 33786 67375 33791 67375 33791 67376 33786 67376 33792 67376 33791 67377 33792 67377 33793 67377 33793 67378 33792 67378 33794 67378 33793 67379 33794 67379 34975 67379 34975 67380 33794 67380 33788 67380 34975 67381 33788 67381 34613 67381 34825 67382 34824 67382 33795 67382 34825 67383 33795 67383 33804 67383 34827 67384 33796 67384 33797 67384 33797 67385 33796 67385 33798 67385 33797 67386 33798 67386 33799 67386 33799 67387 33798 67387 33800 67387 33799 67388 33800 67388 33801 67388 33801 67389 33800 67389 33802 67389 33796 67390 34825 67390 33798 67390 33798 67391 34825 67391 33804 67391 33798 67392 33804 67392 33800 67392 33800 67393 33804 67393 33805 67393 33800 67394 33805 67394 33802 67394 33802 67395 33805 67395 34605 67395 33795 67396 34993 67396 33804 67396 33804 67397 34993 67397 33803 67397 33804 67398 33803 67398 33805 67398 33805 67399 33803 67399 35016 67399 33805 67400 35016 67400 34605 67400 34605 67401 35016 67401 34607 67401 34609 67402 33780 67402 34608 67402 34608 67403 33780 67403 33807 67403 33780 67404 33806 67404 33807 67404 33807 67405 33806 67405 33785 67405 33807 67406 33785 67406 33832 67406 33832 67407 33785 67407 33784 67407 33832 67408 33784 67408 33808 67408 33808 67409 33784 67409 33783 67409 33808 67410 33783 67410 34704 67410 34827 67411 33797 67411 33809 67411 33797 67412 33799 67412 33811 67412 33799 67413 33801 67413 33810 67413 33799 67414 33810 67414 33811 67414 33811 67415 33810 67415 33812 67415 33811 67416 33812 67416 33813 67416 33813 67417 33812 67417 33814 67417 33813 67418 33814 67418 33816 67418 33816 67419 33814 67419 33835 67419 33816 67420 33835 67420 33817 67420 33797 67421 33811 67421 33809 67421 33809 67422 33811 67422 33813 67422 33809 67423 33813 67423 33815 67423 33815 67424 33813 67424 33816 67424 33815 67425 33816 67425 33818 67425 33818 67426 33816 67426 33817 67426 33818 67427 33817 67427 33819 67427 34827 67428 33809 67428 33820 67428 33820 67429 33809 67429 33815 67429 33820 67430 33815 67430 33821 67430 33821 67431 33815 67431 33818 67431 33821 67432 33818 67432 33822 67432 33822 67433 33818 67433 33819 67433 33822 67434 33819 67434 34756 67434 33839 67435 33838 67435 33828 67435 33838 67436 33823 67436 33827 67436 33823 67437 34583 67437 34584 67437 33823 67438 34584 67438 33827 67438 33827 67439 34584 67439 33824 67439 33827 67440 33824 67440 33825 67440 33825 67441 33824 67441 33826 67441 33825 67442 33826 67442 33829 67442 33829 67443 33826 67443 34608 67443 33829 67444 34608 67444 33807 67444 33838 67445 33827 67445 33828 67445 33828 67446 33827 67446 33825 67446 33828 67447 33825 67447 33830 67447 33830 67448 33825 67448 33829 67448 33830 67449 33829 67449 33831 67449 33831 67450 33829 67450 33807 67450 33831 67451 33807 67451 33832 67451 33839 67452 33828 67452 33833 67452 33833 67453 33828 67453 33830 67453 33833 67454 33830 67454 33834 67454 33834 67455 33830 67455 33831 67455 33834 67456 33831 67456 34706 67456 34706 67457 33831 67457 33832 67457 34706 67458 33832 67458 33808 67458 33835 67459 34610 67459 33836 67459 33835 67460 33836 67460 33817 67460 33817 67461 33836 67461 33854 67461 33817 67462 33854 67462 33819 67462 33819 67463 33854 67463 34755 67463 33819 67464 34755 67464 34756 67464 34583 67465 33823 67465 33848 67465 33823 67466 33838 67466 33837 67466 33838 67467 33839 67467 34714 67467 33838 67468 34714 67468 33837 67468 33837 67469 34714 67469 33840 67469 33837 67470 33840 67470 33841 67470 33841 67471 33840 67471 34712 67471 33841 67472 34712 67472 33844 67472 33844 67473 34712 67473 34711 67473 33844 67474 34711 67474 33846 67474 33846 67475 34711 67475 33842 67475 33846 67476 33842 67476 33847 67476 33823 67477 33837 67477 33848 67477 33848 67478 33837 67478 33841 67478 33848 67479 33841 67479 33843 67479 33843 67480 33841 67480 33844 67480 33843 67481 33844 67481 33849 67481 33849 67482 33844 67482 33846 67482 33849 67483 33846 67483 33845 67483 33845 67484 33846 67484 33847 67484 33845 67485 33847 67485 33851 67485 34583 67486 33848 67486 34630 67486 34630 67487 33848 67487 33843 67487 34630 67488 33843 67488 34662 67488 34662 67489 33843 67489 33849 67489 34662 67490 33849 67490 34663 67490 34663 67491 33849 67491 33845 67491 34663 67492 33845 67492 33850 67492 33850 67493 33845 67493 33851 67493 33850 67494 33851 67494 33852 67494 34755 67495 33854 67495 33853 67495 33854 67496 33836 67496 33860 67496 33836 67497 34610 67497 34582 67497 33836 67498 34582 67498 33860 67498 33860 67499 34582 67499 33855 67499 33860 67500 33855 67500 33856 67500 33856 67501 33855 67501 33857 67501 33856 67502 33857 67502 33858 67502 33858 67503 33857 67503 33897 67503 33858 67504 33897 67504 33859 67504 33854 67505 33860 67505 33853 67505 33853 67506 33860 67506 33856 67506 33853 67507 33856 67507 33861 67507 33861 67508 33856 67508 33858 67508 33861 67509 33858 67509 33864 67509 33864 67510 33858 67510 33859 67510 33864 67511 33859 67511 33862 67511 34755 67512 33853 67512 34753 67512 34753 67513 33853 67513 33861 67513 34753 67514 33861 67514 33863 67514 33863 67515 33861 67515 33864 67515 33863 67516 33864 67516 33865 67516 33865 67517 33864 67517 33862 67517 33865 67518 33862 67518 33866 67518 33867 67519 33872 67519 33868 67519 33903 67520 33901 67520 33869 67520 33898 67521 34629 67521 34591 67521 33898 67522 34591 67522 33901 67522 33903 67523 33869 67523 33872 67523 33867 67524 33868 67524 34715 67524 33901 67525 34591 67525 33869 67525 33869 67526 34591 67526 34623 67526 33869 67527 34623 67527 33873 67527 33873 67528 34623 67528 33870 67528 33873 67529 33870 67529 33875 67529 33875 67530 33870 67530 34647 67530 33875 67531 34647 67531 33871 67531 33872 67532 33869 67532 33868 67532 33868 67533 33869 67533 33873 67533 33868 67534 33873 67534 33874 67534 33874 67535 33873 67535 33875 67535 33874 67536 33875 67536 33877 67536 33877 67537 33875 67537 33871 67537 33877 67538 33871 67538 33878 67538 34715 67539 33868 67539 33876 67539 33876 67540 33868 67540 33874 67540 33876 67541 33874 67541 34717 67541 34717 67542 33874 67542 33877 67542 34717 67543 33877 67543 34716 67543 34716 67544 33877 67544 33878 67544 34716 67545 33878 67545 34959 67545 33879 67546 33907 67546 33880 67546 33907 67547 33883 67547 33881 67547 33883 67548 33906 67548 33882 67548 33883 67549 33882 67549 33881 67549 33881 67550 33882 67550 34798 67550 33881 67551 34798 67551 33884 67551 33884 67552 34798 67552 33885 67552 33884 67553 33885 67553 33889 67553 33889 67554 33885 67554 33886 67554 33889 67555 33886 67555 33892 67555 33892 67556 33886 67556 33888 67556 33892 67557 33888 67557 33887 67557 33887 67558 33888 67558 33866 67558 33887 67559 33866 67559 33862 67559 33907 67560 33881 67560 33880 67560 33880 67561 33881 67561 33884 67561 33880 67562 33884 67562 33890 67562 33890 67563 33884 67563 33889 67563 33890 67564 33889 67564 33894 67564 33894 67565 33889 67565 33892 67565 33894 67566 33892 67566 33891 67566 33891 67567 33892 67567 33887 67567 33891 67568 33887 67568 33893 67568 33893 67569 33887 67569 33862 67569 33893 67570 33862 67570 33859 67570 33879 67571 33880 67571 34659 67571 34659 67572 33880 67572 33890 67572 34659 67573 33890 67573 34660 67573 34660 67574 33890 67574 33894 67574 34660 67575 33894 67575 33895 67575 33895 67576 33894 67576 33891 67576 33895 67577 33891 67577 33896 67577 33896 67578 33891 67578 33893 67578 33896 67579 33893 67579 34643 67579 34643 67580 33893 67580 33859 67580 34643 67581 33859 67581 33897 67581 34629 67582 33898 67582 33899 67582 33899 67583 33898 67583 33925 67583 33925 67584 33898 67584 33900 67584 33900 67585 33898 67585 33901 67585 33900 67586 33901 67586 33902 67586 33902 67587 33901 67587 33903 67587 33902 67588 33903 67588 33904 67588 33904 67589 33903 67589 33872 67589 33904 67590 33872 67590 33931 67590 33872 67591 33867 67591 33931 67591 33931 67592 33867 67592 34715 67592 33931 67593 34715 67593 33905 67593 33906 67594 33883 67594 33914 67594 33883 67595 33907 67595 33908 67595 33907 67596 33879 67596 34657 67596 33907 67597 34657 67597 33908 67597 33908 67598 34657 67598 34622 67598 33908 67599 34622 67599 33909 67599 33909 67600 34622 67600 33910 67600 33909 67601 33910 67601 33911 67601 33910 67602 34646 67602 33911 67602 33911 67603 34646 67603 33933 67603 33911 67604 33933 67604 33935 67604 33883 67605 33908 67605 33914 67605 33914 67606 33908 67606 33909 67606 33914 67607 33909 67607 33912 67607 33912 67608 33909 67608 33911 67608 33912 67609 33911 67609 33916 67609 33916 67610 33911 67610 33935 67610 33916 67611 33935 67611 33936 67611 33906 67612 33914 67612 33913 67612 33913 67613 33914 67613 33912 67613 33913 67614 33912 67614 33915 67614 33915 67615 33912 67615 33916 67615 33915 67616 33916 67616 33917 67616 33917 67617 33916 67617 33936 67617 33917 67618 33936 67618 33938 67618 33927 67619 33940 67619 33918 67619 33940 67620 33919 67620 33920 67620 33940 67621 33920 67621 33918 67621 33918 67622 33920 67622 33921 67622 33918 67623 33921 67623 33928 67623 33928 67624 33921 67624 33926 67624 33928 67625 33926 67625 33930 67625 33922 67626 33899 67626 33925 67626 33925 67627 33926 67627 33922 67627 33922 67628 33926 67628 33921 67628 33922 67629 33921 67629 33923 67629 33923 67630 33921 67630 33920 67630 33923 67631 33920 67631 34590 67631 34590 67632 33920 67632 33919 67632 34590 67633 33919 67633 33924 67633 33925 67634 33900 67634 33926 67634 33926 67635 33900 67635 33902 67635 33926 67636 33902 67636 33930 67636 33930 67637 33902 67637 33904 67637 33930 67638 33904 67638 33931 67638 33927 67639 33918 67639 33929 67639 33929 67640 33918 67640 33928 67640 33929 67641 33928 67641 34720 67641 34720 67642 33928 67642 33930 67642 34720 67643 33930 67643 34719 67643 34719 67644 33930 67644 33931 67644 34719 67645 33931 67645 33905 67645 34646 67646 34577 67646 33932 67646 34646 67647 33932 67647 33933 67647 33933 67648 33932 67648 33934 67648 33933 67649 33934 67649 33935 67649 33935 67650 33934 67650 33937 67650 33935 67651 33937 67651 33936 67651 33936 67652 33937 67652 34747 67652 33936 67653 34747 67653 33938 67653 33924 67654 33919 67654 33942 67654 33919 67655 33940 67655 33939 67655 33940 67656 33927 67656 34729 67656 33940 67657 34729 67657 33939 67657 33939 67658 34729 67658 33941 67658 33939 67659 33941 67659 33943 67659 33943 67660 33941 67660 34727 67660 33943 67661 34727 67661 33944 67661 33944 67662 34727 67662 34725 67662 33944 67663 34725 67663 33946 67663 34725 67664 34724 67664 34944 67664 34725 67665 34944 67665 33946 67665 33946 67666 34944 67666 34945 67666 33946 67667 34945 67667 34946 67667 33919 67668 33939 67668 33942 67668 33942 67669 33939 67669 33943 67669 33942 67670 33943 67670 33949 67670 33949 67671 33943 67671 33944 67671 33949 67672 33944 67672 33945 67672 33945 67673 33944 67673 33946 67673 33945 67674 33946 67674 33952 67674 33952 67675 33946 67675 34946 67675 33952 67676 34946 67676 33947 67676 33924 67677 33942 67677 33948 67677 33948 67678 33942 67678 33949 67678 33948 67679 33949 67679 33950 67679 33950 67680 33949 67680 33945 67680 33950 67681 33945 67681 33951 67681 33951 67682 33945 67682 33952 67682 33951 67683 33952 67683 34638 67683 34638 67684 33952 67684 33947 67684 34638 67685 33947 67685 34639 67685 34576 67686 34633 67686 33953 67686 33953 67687 34633 67687 33962 67687 33953 67688 33962 67688 33954 67688 33954 67689 33962 67689 33960 67689 33954 67690 33960 67690 33955 67690 33955 67691 33960 67691 33959 67691 34577 67692 34576 67692 33932 67692 33932 67693 34576 67693 33953 67693 33932 67694 33953 67694 33934 67694 33934 67695 33953 67695 33954 67695 33934 67696 33954 67696 33937 67696 33937 67697 33954 67697 33955 67697 33937 67698 33955 67698 34747 67698 34747 67699 33955 67699 34748 67699 33959 67700 33958 67700 33955 67700 33955 67701 33958 67701 34750 67701 33955 67702 34750 67702 34748 67702 33956 67703 33958 67703 33957 67703 33957 67704 33958 67704 33959 67704 33957 67705 33959 67705 33987 67705 33987 67706 33959 67706 33960 67706 33987 67707 33960 67707 33961 67707 33961 67708 33960 67708 33962 67708 33961 67709 33962 67709 33992 67709 33992 67710 33962 67710 34633 67710 33992 67711 34633 67711 33963 67711 34003 67712 33966 67712 33969 67712 33964 67713 34000 67713 33968 67713 33998 67714 33965 67714 34592 67714 33964 67715 33968 67715 33966 67715 34003 67716 33969 67716 34004 67716 34655 67717 33972 67717 34656 67717 34656 67718 33972 67718 33970 67718 34656 67719 33970 67719 33967 67719 33967 67720 33970 67720 33968 67720 33967 67721 33968 67721 34592 67721 34592 67722 33968 67722 34000 67722 34592 67723 34000 67723 33998 67723 33966 67724 33968 67724 33969 67724 33969 67725 33968 67725 33970 67725 33969 67726 33970 67726 33971 67726 33971 67727 33970 67727 33972 67727 33971 67728 33972 67728 33975 67728 34655 67729 34952 67729 33972 67729 33972 67730 34952 67730 33973 67730 33972 67731 33973 67731 33975 67731 33975 67732 33973 67732 33974 67732 33975 67733 33974 67733 33979 67733 34004 67734 33969 67734 33976 67734 33976 67735 33969 67735 33971 67735 33976 67736 33971 67736 33977 67736 33977 67737 33971 67737 33975 67737 33977 67738 33975 67738 33978 67738 33978 67739 33975 67739 33979 67739 33978 67740 33979 67740 33980 67740 34009 67741 34010 67741 33993 67741 34010 67742 34007 67742 33981 67742 34007 67743 34006 67743 34803 67743 34007 67744 34803 67744 33981 67744 33981 67745 34803 67745 33982 67745 33981 67746 33982 67746 33988 67746 33988 67747 33982 67747 34801 67747 33988 67748 34801 67748 33983 67748 33983 67749 34801 67749 33984 67749 33983 67750 33984 67750 33990 67750 33990 67751 33984 67751 33985 67751 33990 67752 33985 67752 33986 67752 33985 67753 33956 67753 33957 67753 33985 67754 33957 67754 33986 67754 33986 67755 33957 67755 33987 67755 33986 67756 33987 67756 33961 67756 34010 67757 33981 67757 33993 67757 33993 67758 33981 67758 33988 67758 33993 67759 33988 67759 33989 67759 33989 67760 33988 67760 33983 67760 33989 67761 33983 67761 33991 67761 33991 67762 33983 67762 33990 67762 33991 67763 33990 67763 33995 67763 33995 67764 33990 67764 33986 67764 33995 67765 33986 67765 33996 67765 33996 67766 33986 67766 33961 67766 33996 67767 33961 67767 33992 67767 34009 67768 33993 67768 33994 67768 33994 67769 33993 67769 33989 67769 33994 67770 33989 67770 34651 67770 34651 67771 33989 67771 33991 67771 34651 67772 33991 67772 34652 67772 34652 67773 33991 67773 33995 67773 34652 67774 33995 67774 33997 67774 33997 67775 33995 67775 33996 67775 33997 67776 33996 67776 34632 67776 34632 67777 33996 67777 33992 67777 34632 67778 33992 67778 33963 67778 33965 67779 33998 67779 34636 67779 34636 67780 33998 67780 34023 67780 34023 67781 33998 67781 33999 67781 33999 67782 33998 67782 34000 67782 33999 67783 34000 67783 34001 67783 34001 67784 34000 67784 33964 67784 34001 67785 33964 67785 34002 67785 34002 67786 33964 67786 33966 67786 34002 67787 33966 67787 34032 67787 33966 67788 34003 67788 34032 67788 34032 67789 34003 67789 34004 67789 34032 67790 34004 67790 34005 67790 34006 67791 34007 67791 34014 67791 34007 67792 34010 67792 34008 67792 34010 67793 34009 67793 34635 67793 34010 67794 34635 67794 34008 67794 34008 67795 34635 67795 34011 67795 34008 67796 34011 67796 34015 67796 34015 67797 34011 67797 34012 67797 34015 67798 34012 67798 34017 67798 34012 67799 34034 67799 34017 67799 34017 67800 34034 67800 34013 67800 34017 67801 34013 67801 34036 67801 34007 67802 34008 67802 34014 67802 34014 67803 34008 67803 34015 67803 34014 67804 34015 67804 34016 67804 34016 67805 34015 67805 34017 67805 34016 67806 34017 67806 34018 67806 34018 67807 34017 67807 34036 67807 34018 67808 34036 67808 34019 67808 34006 67809 34014 67809 34741 67809 34741 67810 34014 67810 34016 67810 34741 67811 34016 67811 34744 67811 34744 67812 34016 67812 34018 67812 34744 67813 34018 67813 34743 67813 34743 67814 34018 67814 34019 67814 34743 67815 34019 67815 34740 67815 34040 67816 34041 67816 34021 67816 34020 67817 34043 67817 34022 67817 34046 67818 34045 67818 34594 67818 34020 67819 34022 67819 34041 67819 34040 67820 34021 67820 34039 67820 34041 67821 34022 67821 34021 67821 34021 67822 34022 67822 34025 67822 34021 67823 34025 67823 34029 67823 34029 67824 34025 67824 34024 67824 34029 67825 34024 67825 34030 67825 34587 67826 34636 67826 34023 67826 34023 67827 34024 67827 34587 67827 34587 67828 34024 67828 34025 67828 34587 67829 34025 67829 34026 67829 34026 67830 34025 67830 34022 67830 34026 67831 34022 67831 34594 67831 34594 67832 34022 67832 34043 67832 34594 67833 34043 67833 34046 67833 34023 67834 33999 67834 34024 67834 34024 67835 33999 67835 34001 67835 34024 67836 34001 67836 34030 67836 34030 67837 34001 67837 34002 67837 34030 67838 34002 67838 34032 67838 34039 67839 34021 67839 34027 67839 34027 67840 34021 67840 34029 67840 34027 67841 34029 67841 34028 67841 34028 67842 34029 67842 34030 67842 34028 67843 34030 67843 34031 67843 34031 67844 34030 67844 34032 67844 34031 67845 34032 67845 34005 67845 34034 67846 34033 67846 34056 67846 34034 67847 34056 67847 34013 67847 34013 67848 34056 67848 34035 67848 34013 67849 34035 67849 34036 67849 34036 67850 34035 67850 34037 67850 34036 67851 34037 67851 34019 67851 34019 67852 34037 67852 34038 67852 34019 67853 34038 67853 34740 67853 34039 67854 34822 67854 34040 67854 34040 67855 34822 67855 34048 67855 34040 67856 34048 67856 34041 67856 34041 67857 34048 67857 34042 67857 34047 67858 34043 67858 34042 67858 34042 67859 34043 67859 34020 67859 34042 67860 34020 67860 34041 67860 34044 67861 34045 67861 34047 67861 34047 67862 34045 67862 34046 67862 34047 67863 34046 67863 34043 67863 34822 67864 34821 67864 34048 67864 34048 67865 34821 67865 34051 67865 34048 67866 34051 67866 34042 67866 34042 67867 34051 67867 34049 67867 34042 67868 34049 67868 34047 67868 34047 67869 34049 67869 34052 67869 34047 67870 34052 67870 34044 67870 34044 67871 34052 67871 34053 67871 34821 67872 34050 67872 34051 67872 34051 67873 34050 67873 34879 67873 34051 67874 34879 67874 34049 67874 34049 67875 34879 67875 34890 67875 34049 67876 34890 67876 34052 67876 34052 67877 34890 67877 34899 67877 34052 67878 34899 67878 34053 67878 34053 67879 34899 67879 34054 67879 34737 67880 34739 67880 34057 67880 34060 67881 34061 67881 34940 67881 34940 67882 34937 67882 34060 67882 34060 67883 34937 67883 34936 67883 34060 67884 34936 67884 34063 67884 34033 67885 34055 67885 34056 67885 34056 67886 34055 67886 34062 67886 34056 67887 34062 67887 34035 67887 34035 67888 34062 67888 34059 67888 34035 67889 34059 67889 34037 67889 34037 67890 34059 67890 34057 67890 34037 67891 34057 67891 34038 67891 34038 67892 34057 67892 34739 67892 34064 67893 34737 67893 34058 67893 34058 67894 34737 67894 34057 67894 34058 67895 34057 67895 34063 67895 34063 67896 34057 67896 34059 67896 34063 67897 34059 67897 34060 67897 34060 67898 34059 67898 34062 67898 34060 67899 34062 67899 34061 67899 34061 67900 34062 67900 34055 67900 34936 67901 34935 67901 34063 67901 34063 67902 34935 67902 34934 67902 34063 67903 34934 67903 34058 67903 34058 67904 34934 67904 34933 67904 34058 67905 34933 67905 34064 67905 34064 67906 34933 67906 34734 67906 34105 67907 34075 67907 34074 67907 34122 67908 34081 67908 34123 67908 34093 67909 34779 67909 34094 67909 34071 67910 34066 67910 34096 67910 34149 67911 34065 67911 34097 67911 34066 67912 34763 67912 34097 67912 34097 67913 34763 67913 34762 67913 34097 67914 34762 67914 34149 67914 34067 67915 34068 67915 34124 67915 34124 67916 34068 67916 34758 67916 34124 67917 34758 67917 34069 67917 34069 67918 34758 67918 34070 67918 34069 67919 34070 67919 34121 67919 34121 67920 34070 67920 34764 67920 34121 67921 34764 67921 34071 67921 34072 67922 34074 67922 34073 67922 34073 67923 34074 67923 34075 67923 34073 67924 34075 67924 34759 67924 34101 67925 34146 67925 34102 67925 34788 67926 34077 67926 34076 67926 34076 67927 34077 67927 34796 67927 34076 67928 34796 67928 34794 67928 34794 67929 34156 67929 34076 67929 34076 67930 34156 67930 34078 67930 34078 67931 34156 67931 34157 67931 34078 67932 34157 67932 34079 67932 34079 67933 34157 67933 34099 67933 34079 67934 34099 67934 34100 67934 34080 67935 34108 67935 34109 67935 34080 67936 34109 67936 34104 67936 34789 67937 34107 67937 34790 67937 34790 67938 34107 67938 34108 67938 34790 67939 34108 67939 34791 67939 34791 67940 34108 67940 34080 67940 34791 67941 34080 67941 34792 67941 34081 67942 34113 67942 34123 67942 34123 67943 34113 67943 34083 67943 34123 67944 34083 67944 34082 67944 34082 67945 34083 67945 34084 67945 34082 67946 34084 67946 34085 67946 34085 67947 34084 67947 34114 67947 34085 67948 34114 67948 34125 67948 34125 67949 34114 67949 34126 67949 34118 67950 34117 67950 34088 67950 34088 67951 34117 67951 34086 67951 34088 67952 34086 67952 34090 67952 34090 67953 34086 67953 34111 67953 34119 67954 34118 67954 34087 67954 34087 67955 34118 67955 34088 67955 34087 67956 34088 67956 34089 67956 34089 67957 34088 67957 34090 67957 34089 67958 34090 67958 34091 67958 34091 67959 34090 67959 34111 67959 34091 67960 34111 67960 34776 67960 34776 67961 34092 67961 34091 67961 34091 67962 34092 67962 34093 67962 34091 67963 34093 67963 34089 67963 34089 67964 34093 67964 34094 67964 34089 67965 34094 67965 34087 67965 34087 67966 34094 67966 34095 67966 34087 67967 34095 67967 34119 67967 34066 67968 34097 67968 34096 67968 34096 67969 34097 67969 34098 67969 34096 67970 34098 67970 34122 67970 34099 67971 34162 67971 34100 67971 34100 67972 34162 67972 34101 67972 34100 67973 34101 67973 34110 67973 34110 67974 34101 67974 34102 67974 34110 67975 34102 67975 34760 67975 34109 67976 34103 67976 34104 67976 34104 67977 34103 67977 34105 67977 34104 67978 34105 67978 34106 67978 34106 67979 34105 67979 34074 67979 34106 67980 34074 67980 34067 67980 34067 67981 34074 67981 34072 67981 34067 67982 34072 67982 34068 67982 34789 67983 34788 67983 34107 67983 34107 67984 34788 67984 34076 67984 34107 67985 34076 67985 34108 67985 34108 67986 34076 67986 34078 67986 34108 67987 34078 67987 34109 67987 34109 67988 34078 67988 34079 67988 34109 67989 34079 67989 34103 67989 34103 67990 34079 67990 34100 67990 34103 67991 34100 67991 34105 67991 34105 67992 34100 67992 34110 67992 34105 67993 34110 67993 34075 67993 34075 67994 34110 67994 34760 67994 34075 67995 34760 67995 34759 67995 34112 67996 34778 67996 34111 67996 34111 67997 34778 67997 34777 67997 34111 67998 34777 67998 34776 67998 34086 67999 34129 67999 34111 67999 34111 68000 34129 68000 34112 68000 34112 68001 34129 68001 34775 68001 34113 68002 34120 68002 34083 68002 34083 68003 34120 68003 34780 68003 34083 68004 34780 68004 34084 68004 34084 68005 34780 68005 34115 68005 34084 68006 34115 68006 34114 68006 34114 68007 34115 68007 34116 68007 34114 68008 34116 68008 34126 68008 34126 68009 34116 68009 34787 68009 34126 68010 34787 68010 34786 68010 34065 68011 34117 68011 34097 68011 34097 68012 34117 68012 34118 68012 34097 68013 34118 68013 34098 68013 34098 68014 34118 68014 34119 68014 34098 68015 34119 68015 34122 68015 34122 68016 34119 68016 34095 68016 34122 68017 34095 68017 34081 68017 34081 68018 34095 68018 34094 68018 34081 68019 34094 68019 34113 68019 34113 68020 34094 68020 34779 68020 34113 68021 34779 68021 34120 68021 34071 68022 34096 68022 34121 68022 34121 68023 34096 68023 34122 68023 34121 68024 34122 68024 34069 68024 34069 68025 34122 68025 34123 68025 34069 68026 34123 68026 34124 68026 34124 68027 34123 68027 34082 68027 34124 68028 34082 68028 34067 68028 34067 68029 34082 68029 34085 68029 34067 68030 34085 68030 34106 68030 34106 68031 34085 68031 34125 68031 34106 68032 34125 68032 34104 68032 34104 68033 34125 68033 34126 68033 34104 68034 34126 68034 34080 68034 34080 68035 34126 68035 34786 68035 34080 68036 34786 68036 34792 68036 34793 68037 34127 68037 34155 68037 34128 68038 34065 68038 34149 68038 34165 68039 34166 68039 34143 68039 34129 68040 34086 68040 34134 68040 34775 68041 34129 68041 34132 68041 34132 68042 34129 68042 34130 68042 34135 68043 34161 68043 34770 68043 34133 68044 34772 68044 34130 68044 34130 68045 34772 68045 34131 68045 34130 68046 34131 68046 34132 68046 34130 68047 34129 68047 34134 68047 34130 68048 34134 68048 34133 68048 34133 68049 34134 68049 34135 68049 34133 68050 34135 68050 34774 68050 34774 68051 34135 68051 34770 68051 34160 68052 34140 68052 34158 68052 34139 68053 34138 68053 34136 68053 34136 68054 34138 68054 34155 68054 34127 68055 34782 68055 34155 68055 34155 68056 34782 68056 34781 68056 34155 68057 34781 68057 34136 68057 34139 68058 34136 68058 34140 68058 34140 68059 34136 68059 34785 68059 34140 68060 34785 68060 34158 68060 34162 68061 34099 68061 34137 68061 34137 68062 34099 68062 34138 68062 34137 68063 34138 68063 34164 68063 34164 68064 34138 68064 34139 68064 34164 68065 34139 68065 34167 68065 34167 68066 34139 68066 34140 68066 34167 68067 34140 68067 34168 68067 34168 68068 34140 68068 34160 68068 34168 68069 34160 68069 34141 68069 34141 68070 34160 68070 34161 68070 34141 68071 34161 68071 34170 68071 34170 68072 34161 68072 34135 68072 34170 68073 34135 68073 34142 68073 34142 68074 34135 68074 34134 68074 34142 68075 34134 68075 34117 68075 34117 68076 34134 68076 34086 68076 34143 68077 34144 68077 34165 68077 34165 68078 34144 68078 34145 68078 34165 68079 34145 68079 34148 68079 34146 68080 34101 68080 34147 68080 34147 68081 34101 68081 34163 68081 34147 68082 34163 68082 34767 68082 34767 68083 34163 68083 34148 68083 34767 68084 34148 68084 34768 68084 34768 68085 34148 68085 34145 68085 34149 68086 34150 68086 34128 68086 34128 68087 34150 68087 34766 68087 34128 68088 34766 68088 34152 68088 34766 68089 34151 68089 34152 68089 34152 68090 34151 68090 34153 68090 34152 68091 34153 68091 34169 68091 34169 68092 34153 68092 34765 68092 34169 68093 34765 68093 34166 68093 34166 68094 34765 68094 34154 68094 34166 68095 34154 68095 34143 68095 34794 68096 34793 68096 34156 68096 34156 68097 34793 68097 34155 68097 34156 68098 34155 68098 34138 68098 34156 68099 34138 68099 34157 68099 34157 68100 34138 68100 34099 68100 34158 68101 34159 68101 34160 68101 34160 68102 34159 68102 34769 68102 34160 68103 34769 68103 34161 68103 34161 68104 34769 68104 34771 68104 34161 68105 34771 68105 34770 68105 34101 68106 34162 68106 34163 68106 34163 68107 34162 68107 34137 68107 34163 68108 34137 68108 34148 68108 34148 68109 34137 68109 34164 68109 34148 68110 34164 68110 34165 68110 34165 68111 34164 68111 34167 68111 34165 68112 34167 68112 34166 68112 34166 68113 34167 68113 34168 68113 34166 68114 34168 68114 34169 68114 34169 68115 34168 68115 34141 68115 34169 68116 34141 68116 34152 68116 34152 68117 34141 68117 34170 68117 34152 68118 34170 68118 34128 68118 34128 68119 34170 68119 34142 68119 34128 68120 34142 68120 34065 68120 34065 68121 34142 68121 34117 68121 34210 68122 34177 68122 34176 68122 34233 68123 34190 68123 34191 68123 34202 68124 34231 68124 34229 68124 34171 68125 34172 68125 34206 68125 34560 68126 34241 68126 34205 68126 34172 68127 34173 68127 34205 68127 34205 68128 34173 68128 34552 68128 34205 68129 34552 68129 34560 68129 34174 68130 34547 68130 34235 68130 34235 68131 34547 68131 34555 68131 34235 68132 34555 68132 34234 68132 34234 68133 34555 68133 34554 68133 34234 68134 34554 68134 34232 68134 34232 68135 34554 68135 34175 68135 34232 68136 34175 68136 34171 68136 34212 68137 34176 68137 34178 68137 34178 68138 34176 68138 34177 68138 34178 68139 34177 68139 34548 68139 34179 68140 34551 68140 34550 68140 34180 68141 34181 68141 34214 68141 34214 68142 34181 68142 34846 68142 34214 68143 34846 68143 34182 68143 34182 68144 34184 68144 34214 68144 34214 68145 34184 68145 34183 68145 34183 68146 34184 68146 34271 68146 34183 68147 34271 68147 34185 68147 34185 68148 34271 68148 34208 68148 34185 68149 34208 68149 34218 68149 34189 68150 34215 68150 34216 68150 34189 68151 34216 68151 34239 68151 34213 68152 34187 68152 34186 68152 34186 68153 34187 68153 34215 68153 34186 68154 34215 68154 34188 68154 34188 68155 34215 68155 34189 68155 34188 68156 34189 68156 34845 68156 34190 68157 34230 68157 34191 68157 34191 68158 34230 68158 34220 68158 34191 68159 34220 68159 34236 68159 34236 68160 34220 68160 34192 68160 34236 68161 34192 68161 34237 68161 34237 68162 34192 68162 34222 68162 34237 68163 34222 68163 34238 68163 34238 68164 34222 68164 34193 68164 34227 68165 34226 68165 34196 68165 34196 68166 34226 68166 34194 68166 34196 68167 34194 68167 34197 68167 34197 68168 34194 68168 34198 68168 34204 68169 34227 68169 34195 68169 34195 68170 34227 68170 34196 68170 34195 68171 34196 68171 34203 68171 34203 68172 34196 68172 34197 68172 34203 68173 34197 68173 34201 68173 34201 68174 34197 68174 34198 68174 34201 68175 34198 68175 34199 68175 34199 68176 34200 68176 34201 68176 34201 68177 34200 68177 34202 68177 34201 68178 34202 68178 34203 68178 34203 68179 34202 68179 34229 68179 34203 68180 34229 68180 34195 68180 34195 68181 34229 68181 34228 68181 34195 68182 34228 68182 34204 68182 34172 68183 34205 68183 34206 68183 34206 68184 34205 68184 34207 68184 34206 68185 34207 68185 34233 68185 34208 68186 34209 68186 34218 68186 34218 68187 34209 68187 34179 68187 34218 68188 34179 68188 34219 68188 34219 68189 34179 68189 34550 68189 34219 68190 34550 68190 34549 68190 34216 68191 34217 68191 34239 68191 34239 68192 34217 68192 34210 68192 34239 68193 34210 68193 34211 68193 34211 68194 34210 68194 34176 68194 34211 68195 34176 68195 34174 68195 34174 68196 34176 68196 34212 68196 34174 68197 34212 68197 34547 68197 34213 68198 34180 68198 34187 68198 34187 68199 34180 68199 34214 68199 34187 68200 34214 68200 34215 68200 34215 68201 34214 68201 34183 68201 34215 68202 34183 68202 34216 68202 34216 68203 34183 68203 34185 68203 34216 68204 34185 68204 34217 68204 34217 68205 34185 68205 34218 68205 34217 68206 34218 68206 34210 68206 34210 68207 34218 68207 34219 68207 34210 68208 34219 68208 34177 68208 34177 68209 34219 68209 34549 68209 34177 68210 34549 68210 34548 68210 34571 68211 34573 68211 34198 68211 34198 68212 34573 68212 34572 68212 34198 68213 34572 68213 34199 68213 34194 68214 34243 68214 34198 68214 34198 68215 34243 68215 34571 68215 34571 68216 34243 68216 34570 68216 34230 68217 34221 68217 34220 68217 34220 68218 34221 68218 34574 68218 34220 68219 34574 68219 34192 68219 34192 68220 34574 68220 34844 68220 34192 68221 34844 68221 34222 68221 34222 68222 34844 68222 34223 68222 34222 68223 34223 68223 34193 68223 34193 68224 34223 68224 34224 68224 34193 68225 34224 68225 34225 68225 34241 68226 34226 68226 34205 68226 34205 68227 34226 68227 34227 68227 34205 68228 34227 68228 34207 68228 34207 68229 34227 68229 34204 68229 34207 68230 34204 68230 34233 68230 34233 68231 34204 68231 34228 68231 34233 68232 34228 68232 34190 68232 34190 68233 34228 68233 34229 68233 34190 68234 34229 68234 34230 68234 34230 68235 34229 68235 34231 68235 34230 68236 34231 68236 34221 68236 34171 68237 34206 68237 34232 68237 34232 68238 34206 68238 34233 68238 34232 68239 34233 68239 34234 68239 34234 68240 34233 68240 34191 68240 34234 68241 34191 68241 34235 68241 34235 68242 34191 68242 34236 68242 34235 68243 34236 68243 34174 68243 34174 68244 34236 68244 34237 68244 34174 68245 34237 68245 34211 68245 34211 68246 34237 68246 34238 68246 34211 68247 34238 68247 34239 68247 34239 68248 34238 68248 34193 68248 34239 68249 34193 68249 34189 68249 34189 68250 34193 68250 34225 68250 34189 68251 34225 68251 34845 68251 34269 68252 34240 68252 34248 68252 34281 68253 34241 68253 34560 68253 34258 68254 34267 68254 34268 68254 34243 68255 34194 68255 34242 68255 34570 68256 34243 68256 34565 68256 34565 68257 34243 68257 34244 68257 34257 68258 34245 68258 34276 68258 34569 68259 34567 68259 34244 68259 34244 68260 34567 68260 34566 68260 34244 68261 34566 68261 34565 68261 34244 68262 34243 68262 34242 68262 34244 68263 34242 68263 34569 68263 34569 68264 34242 68264 34257 68264 34569 68265 34257 68265 34246 68265 34246 68266 34257 68266 34276 68266 34274 68267 34251 68267 34272 68267 34254 68268 34270 68268 34247 68268 34247 68269 34270 68269 34248 68269 34240 68270 34249 68270 34248 68270 34248 68271 34249 68271 34250 68271 34248 68272 34250 68272 34247 68272 34254 68273 34247 68273 34251 68273 34251 68274 34247 68274 34252 68274 34251 68275 34252 68275 34272 68275 34209 68276 34208 68276 34253 68276 34253 68277 34208 68277 34270 68277 34253 68278 34270 68278 34277 68278 34277 68279 34270 68279 34254 68279 34277 68280 34254 68280 34278 68280 34278 68281 34254 68281 34251 68281 34278 68282 34251 68282 34255 68282 34255 68283 34251 68283 34274 68283 34255 68284 34274 68284 34256 68284 34256 68285 34274 68285 34245 68285 34256 68286 34245 68286 34280 68286 34280 68287 34245 68287 34257 68287 34280 68288 34257 68288 34282 68288 34282 68289 34257 68289 34242 68289 34282 68290 34242 68290 34226 68290 34226 68291 34242 68291 34194 68291 34268 68292 34259 68292 34258 68292 34258 68293 34259 68293 34264 68293 34258 68294 34264 68294 34263 68294 34551 68295 34179 68295 34561 68295 34561 68296 34179 68296 34260 68296 34561 68297 34260 68297 34261 68297 34261 68298 34260 68298 34263 68298 34261 68299 34263 68299 34262 68299 34262 68300 34263 68300 34264 68300 34560 68301 34559 68301 34281 68301 34281 68302 34559 68302 34558 68302 34281 68303 34558 68303 34265 68303 34558 68304 34557 68304 34265 68304 34265 68305 34557 68305 34556 68305 34265 68306 34556 68306 34279 68306 34279 68307 34556 68307 34266 68307 34279 68308 34266 68308 34267 68308 34267 68309 34266 68309 34562 68309 34267 68310 34562 68310 34268 68310 34182 68311 34269 68311 34184 68311 34184 68312 34269 68312 34248 68312 34184 68313 34248 68313 34270 68313 34184 68314 34270 68314 34271 68314 34271 68315 34270 68315 34208 68315 34272 68316 34842 68316 34274 68316 34274 68317 34842 68317 34273 68317 34274 68318 34273 68318 34245 68318 34245 68319 34273 68319 34275 68319 34245 68320 34275 68320 34276 68320 34179 68321 34209 68321 34260 68321 34260 68322 34209 68322 34253 68322 34260 68323 34253 68323 34263 68323 34263 68324 34253 68324 34277 68324 34263 68325 34277 68325 34258 68325 34258 68326 34277 68326 34278 68326 34258 68327 34278 68327 34267 68327 34267 68328 34278 68328 34255 68328 34267 68329 34255 68329 34279 68329 34279 68330 34255 68330 34256 68330 34279 68331 34256 68331 34265 68331 34265 68332 34256 68332 34280 68332 34265 68333 34280 68333 34281 68333 34281 68334 34280 68334 34282 68334 34281 68335 34282 68335 34241 68335 34241 68336 34282 68336 34226 68336 34323 68337 34331 68337 34324 68337 34342 68338 34283 68338 34344 68338 34284 68339 34285 68339 34313 68339 34293 68340 34315 68340 34343 68340 34529 68341 34352 68341 34316 68341 34315 68342 34286 68342 34316 68342 34316 68343 34286 68343 34287 68343 34316 68344 34287 68344 34529 68344 34346 68345 34525 68345 34345 68345 34345 68346 34525 68346 34288 68346 34345 68347 34288 68347 34289 68347 34289 68348 34288 68348 34290 68348 34289 68349 34290 68349 34291 68349 34291 68350 34290 68350 34292 68350 34291 68351 34292 68351 34293 68351 34325 68352 34324 68352 34526 68352 34526 68353 34324 68353 34331 68353 34526 68354 34331 68354 34527 68354 34294 68355 34295 68355 34528 68355 34851 68356 34296 68356 34297 68356 34297 68357 34296 68357 34860 68357 34297 68358 34860 68358 34859 68358 34859 68359 34298 68359 34297 68359 34297 68360 34298 68360 34329 68360 34329 68361 34298 68361 34299 68361 34329 68362 34299 68362 34330 68362 34330 68363 34299 68363 34318 68363 34330 68364 34318 68364 34300 68364 34301 68365 34327 68365 34328 68365 34301 68366 34328 68366 34349 68366 34326 68367 34302 68367 34853 68367 34853 68368 34302 68368 34327 68368 34853 68369 34327 68369 34855 68369 34855 68370 34327 68370 34301 68370 34855 68371 34301 68371 34856 68371 34283 68372 34334 68372 34344 68372 34344 68373 34334 68373 34304 68373 34344 68374 34304 68374 34303 68374 34303 68375 34304 68375 34336 68375 34303 68376 34336 68376 34347 68376 34347 68377 34336 68377 34305 68377 34347 68378 34305 68378 34306 68378 34306 68379 34305 68379 34350 68379 34339 68380 34369 68380 34308 68380 34308 68381 34369 68381 34354 68381 34308 68382 34354 68382 34307 68382 34307 68383 34354 68383 34309 68383 34340 68384 34339 68384 34314 68384 34314 68385 34339 68385 34308 68385 34314 68386 34308 68386 34312 68386 34312 68387 34308 68387 34307 68387 34312 68388 34307 68388 34311 68388 34311 68389 34307 68389 34309 68389 34311 68390 34309 68390 34541 68390 34541 68391 34310 68391 34311 68391 34311 68392 34310 68392 34284 68392 34311 68393 34284 68393 34312 68393 34312 68394 34284 68394 34313 68394 34312 68395 34313 68395 34314 68395 34314 68396 34313 68396 34341 68396 34314 68397 34341 68397 34340 68397 34315 68398 34316 68398 34343 68398 34343 68399 34316 68399 34317 68399 34343 68400 34317 68400 34342 68400 34318 68401 34319 68401 34300 68401 34300 68402 34319 68402 34294 68402 34300 68403 34294 68403 34320 68403 34320 68404 34294 68404 34528 68404 34320 68405 34528 68405 34321 68405 34328 68406 34322 68406 34349 68406 34349 68407 34322 68407 34323 68407 34349 68408 34323 68408 34348 68408 34348 68409 34323 68409 34324 68409 34348 68410 34324 68410 34346 68410 34346 68411 34324 68411 34325 68411 34346 68412 34325 68412 34525 68412 34326 68413 34851 68413 34302 68413 34302 68414 34851 68414 34297 68414 34302 68415 34297 68415 34327 68415 34327 68416 34297 68416 34329 68416 34327 68417 34329 68417 34328 68417 34328 68418 34329 68418 34330 68418 34328 68419 34330 68419 34322 68419 34322 68420 34330 68420 34300 68420 34322 68421 34300 68421 34323 68421 34323 68422 34300 68422 34320 68422 34323 68423 34320 68423 34331 68423 34331 68424 34320 68424 34321 68424 34331 68425 34321 68425 34527 68425 34543 68426 34332 68426 34309 68426 34309 68427 34332 68427 34542 68427 34309 68428 34542 68428 34541 68428 34354 68429 34353 68429 34309 68429 34309 68430 34353 68430 34543 68430 34543 68431 34353 68431 34333 68431 34334 68432 34335 68432 34304 68432 34304 68433 34335 68433 34545 68433 34304 68434 34545 68434 34336 68434 34336 68435 34545 68435 34337 68435 34336 68436 34337 68436 34305 68436 34305 68437 34337 68437 34849 68437 34305 68438 34849 68438 34350 68438 34350 68439 34849 68439 34338 68439 34350 68440 34338 68440 34850 68440 34352 68441 34369 68441 34316 68441 34316 68442 34369 68442 34339 68442 34316 68443 34339 68443 34317 68443 34317 68444 34339 68444 34340 68444 34317 68445 34340 68445 34342 68445 34342 68446 34340 68446 34341 68446 34342 68447 34341 68447 34283 68447 34283 68448 34341 68448 34313 68448 34283 68449 34313 68449 34334 68449 34334 68450 34313 68450 34285 68450 34334 68451 34285 68451 34335 68451 34293 68452 34343 68452 34291 68452 34291 68453 34343 68453 34342 68453 34291 68454 34342 68454 34289 68454 34289 68455 34342 68455 34344 68455 34289 68456 34344 68456 34345 68456 34345 68457 34344 68457 34303 68457 34345 68458 34303 68458 34346 68458 34346 68459 34303 68459 34347 68459 34346 68460 34347 68460 34348 68460 34348 68461 34347 68461 34306 68461 34348 68462 34306 68462 34349 68462 34349 68463 34306 68463 34350 68463 34349 68464 34350 68464 34301 68464 34301 68465 34350 68465 34850 68465 34301 68466 34850 68466 34856 68466 34351 68467 34361 68467 34380 68467 34378 68468 34352 68468 34529 68468 34372 68469 34389 68469 34371 68469 34353 68470 34354 68470 34370 68470 34333 68471 34353 68471 34356 68471 34356 68472 34353 68472 34357 68472 34358 68473 34368 68473 34537 68473 34540 68474 34355 68474 34357 68474 34357 68475 34355 68475 34539 68475 34357 68476 34539 68476 34356 68476 34357 68477 34353 68477 34370 68477 34357 68478 34370 68478 34540 68478 34540 68479 34370 68479 34358 68479 34540 68480 34358 68480 34536 68480 34536 68481 34358 68481 34537 68481 34367 68482 34364 68482 34359 68482 34366 68483 34360 68483 34363 68483 34363 68484 34360 68484 34380 68484 34361 68485 34362 68485 34380 68485 34380 68486 34362 68486 34848 68486 34380 68487 34848 68487 34363 68487 34366 68488 34363 68488 34364 68488 34364 68489 34363 68489 34365 68489 34364 68490 34365 68490 34359 68490 34319 68491 34318 68491 34385 68491 34385 68492 34318 68492 34360 68492 34385 68493 34360 68493 34386 68493 34386 68494 34360 68494 34366 68494 34386 68495 34366 68495 34387 68495 34387 68496 34366 68496 34364 68496 34387 68497 34364 68497 34388 68497 34388 68498 34364 68498 34367 68498 34388 68499 34367 68499 34391 68499 34391 68500 34367 68500 34368 68500 34391 68501 34368 68501 34393 68501 34393 68502 34368 68502 34358 68502 34393 68503 34358 68503 34394 68503 34394 68504 34358 68504 34370 68504 34394 68505 34370 68505 34369 68505 34369 68506 34370 68506 34354 68506 34371 68507 34373 68507 34372 68507 34372 68508 34373 68508 34377 68508 34372 68509 34377 68509 34384 68509 34295 68510 34294 68510 34374 68510 34374 68511 34294 68511 34383 68511 34374 68512 34383 68512 34375 68512 34375 68513 34383 68513 34384 68513 34375 68514 34384 68514 34376 68514 34376 68515 34384 68515 34377 68515 34529 68516 34534 68516 34378 68516 34378 68517 34534 68517 34533 68517 34378 68518 34533 68518 34392 68518 34533 68519 34532 68519 34392 68519 34392 68520 34532 68520 34379 68520 34392 68521 34379 68521 34390 68521 34390 68522 34379 68522 34531 68522 34390 68523 34531 68523 34389 68523 34389 68524 34531 68524 34535 68524 34389 68525 34535 68525 34371 68525 34859 68526 34351 68526 34298 68526 34298 68527 34351 68527 34380 68527 34298 68528 34380 68528 34360 68528 34298 68529 34360 68529 34299 68529 34299 68530 34360 68530 34318 68530 34359 68531 34847 68531 34367 68531 34367 68532 34847 68532 34381 68532 34367 68533 34381 68533 34368 68533 34368 68534 34381 68534 34382 68534 34368 68535 34382 68535 34537 68535 34294 68536 34319 68536 34383 68536 34383 68537 34319 68537 34385 68537 34383 68538 34385 68538 34384 68538 34384 68539 34385 68539 34386 68539 34384 68540 34386 68540 34372 68540 34372 68541 34386 68541 34387 68541 34372 68542 34387 68542 34389 68542 34389 68543 34387 68543 34388 68543 34389 68544 34388 68544 34390 68544 34390 68545 34388 68545 34391 68545 34390 68546 34391 68546 34392 68546 34392 68547 34391 68547 34393 68547 34392 68548 34393 68548 34378 68548 34378 68549 34393 68549 34394 68549 34378 68550 34394 68550 34352 68550 34352 68551 34394 68551 34369 68551 34519 68552 34395 68552 34417 68552 34431 68553 34441 68553 34433 68553 34396 68554 34452 68554 34455 68554 34397 68555 34520 68555 34419 68555 34869 68556 34868 68556 34437 68556 34508 68557 34423 68557 34424 68557 34462 68558 34461 68558 34398 68558 34423 68559 34507 68559 34398 68559 34398 68560 34507 68560 34399 68560 34398 68561 34399 68561 34462 68561 34400 68562 34435 68562 34401 68562 34401 68563 34435 68563 34403 68563 34401 68564 34403 68564 34402 68564 34402 68565 34403 68565 34404 68565 34402 68566 34404 68566 34405 68566 34405 68567 34404 68567 34406 68567 34405 68568 34406 68568 34508 68568 34434 68569 34433 68569 34407 68569 34407 68570 34433 68570 34441 68570 34407 68571 34441 68571 34504 68571 34428 68572 34511 68572 34429 68572 34426 68573 34440 68573 34470 68573 34470 68574 34440 68574 34408 68574 34408 68575 34440 68575 34438 68575 34408 68576 34438 68576 34409 68576 34409 68577 34438 68577 34437 68577 34409 68578 34437 68578 34868 68578 34409 68579 34868 68579 34489 68579 34410 68580 34411 68580 34439 68580 34410 68581 34439 68581 34458 68581 34410 68582 34460 68582 34872 68582 34872 68583 34870 68583 34410 68583 34410 68584 34870 68584 34436 68584 34410 68585 34436 68585 34411 68585 34452 68586 34454 68586 34455 68586 34455 68587 34454 68587 34445 68587 34455 68588 34445 68588 34412 68588 34412 68589 34445 68589 34413 68589 34412 68590 34413 68590 34456 68590 34456 68591 34413 68591 34414 68591 34456 68592 34414 68592 34457 68592 34457 68593 34414 68593 34459 68593 34417 68594 34418 68594 34415 68594 34415 68595 34418 68595 34422 68595 34415 68596 34422 68596 34503 68596 34421 68597 34453 68597 34416 68597 34416 68598 34453 68598 34451 68598 34416 68599 34451 68599 34449 68599 34395 68600 34397 68600 34417 68600 34417 68601 34397 68601 34419 68601 34417 68602 34419 68602 34418 68602 34418 68603 34419 68603 34420 68603 34418 68604 34420 68604 34422 68604 34520 68605 34521 68605 34419 68605 34419 68606 34521 68606 34421 68606 34419 68607 34421 68607 34420 68607 34420 68608 34421 68608 34416 68608 34420 68609 34416 68609 34422 68609 34422 68610 34416 68610 34449 68610 34422 68611 34449 68611 34503 68611 34423 68612 34398 68612 34424 68612 34424 68613 34398 68613 34450 68613 34424 68614 34450 68614 34396 68614 34470 68615 34425 68615 34426 68615 34426 68616 34425 68616 34428 68616 34426 68617 34428 68617 34427 68617 34427 68618 34428 68618 34429 68618 34427 68619 34429 68619 34505 68619 34439 68620 34430 68620 34458 68620 34458 68621 34430 68621 34431 68621 34458 68622 34431 68622 34432 68622 34432 68623 34431 68623 34433 68623 34432 68624 34433 68624 34400 68624 34400 68625 34433 68625 34434 68625 34400 68626 34434 68626 34435 68626 34870 68627 34869 68627 34436 68627 34436 68628 34869 68628 34437 68628 34436 68629 34437 68629 34411 68629 34411 68630 34437 68630 34438 68630 34411 68631 34438 68631 34439 68631 34439 68632 34438 68632 34440 68632 34439 68633 34440 68633 34430 68633 34430 68634 34440 68634 34426 68634 34430 68635 34426 68635 34431 68635 34431 68636 34426 68636 34427 68636 34431 68637 34427 68637 34441 68637 34441 68638 34427 68638 34505 68638 34441 68639 34505 68639 34504 68639 34415 68640 34442 68640 34417 68640 34417 68641 34442 68641 34519 68641 34519 68642 34442 68642 34443 68642 34454 68643 34444 68643 34445 68643 34445 68644 34444 68644 34523 68644 34445 68645 34523 68645 34413 68645 34413 68646 34523 68646 34446 68646 34413 68647 34446 68647 34414 68647 34414 68648 34446 68648 34447 68648 34414 68649 34447 68649 34459 68649 34459 68650 34447 68650 34448 68650 34461 68651 34503 68651 34398 68651 34398 68652 34503 68652 34449 68652 34398 68653 34449 68653 34450 68653 34450 68654 34449 68654 34451 68654 34450 68655 34451 68655 34396 68655 34396 68656 34451 68656 34453 68656 34396 68657 34453 68657 34452 68657 34452 68658 34453 68658 34421 68658 34452 68659 34421 68659 34454 68659 34454 68660 34421 68660 34521 68660 34454 68661 34521 68661 34444 68661 34508 68662 34424 68662 34405 68662 34405 68663 34424 68663 34396 68663 34405 68664 34396 68664 34402 68664 34402 68665 34396 68665 34455 68665 34402 68666 34455 68666 34401 68666 34401 68667 34455 68667 34412 68667 34401 68668 34412 68668 34400 68668 34400 68669 34412 68669 34456 68669 34400 68670 34456 68670 34432 68670 34432 68671 34456 68671 34457 68671 34432 68672 34457 68672 34458 68672 34458 68673 34457 68673 34459 68673 34458 68674 34459 68674 34410 68674 34410 68675 34459 68675 34448 68675 34410 68676 34448 68676 34460 68676 34862 68677 34867 68677 34490 68677 34484 68678 34461 68678 34462 68678 34479 68679 34498 68679 34478 68679 34442 68680 34415 68680 34477 68680 34443 68681 34442 68681 34463 68681 34463 68682 34442 68682 34465 68682 34475 68683 34494 68683 34496 68683 34517 68684 34518 68684 34465 68684 34465 68685 34518 68685 34464 68685 34465 68686 34464 68686 34463 68686 34465 68687 34442 68687 34477 68687 34465 68688 34477 68688 34517 68688 34517 68689 34477 68689 34475 68689 34517 68690 34475 68690 34515 68690 34515 68691 34475 68691 34496 68691 34492 68692 34466 68692 34467 68692 34469 68693 34472 68693 34468 68693 34468 68694 34472 68694 34490 68694 34867 68695 34866 68695 34490 68695 34490 68696 34866 68696 34865 68696 34490 68697 34865 68697 34468 68697 34469 68698 34468 68698 34466 68698 34466 68699 34468 68699 34864 68699 34466 68700 34864 68700 34467 68700 34425 68701 34470 68701 34471 68701 34471 68702 34470 68702 34472 68702 34471 68703 34472 68703 34473 68703 34473 68704 34472 68704 34469 68704 34473 68705 34469 68705 34497 68705 34497 68706 34469 68706 34466 68706 34497 68707 34466 68707 34499 68707 34499 68708 34466 68708 34492 68708 34499 68709 34492 68709 34501 68709 34501 68710 34492 68710 34494 68710 34501 68711 34494 68711 34474 68711 34474 68712 34494 68712 34475 68712 34474 68713 34475 68713 34476 68713 34476 68714 34475 68714 34477 68714 34476 68715 34477 68715 34503 68715 34503 68716 34477 68716 34415 68716 34478 68717 34514 68717 34479 68717 34479 68718 34514 68718 34513 68718 34479 68719 34513 68719 34482 68719 34511 68720 34428 68720 34480 68720 34480 68721 34428 68721 34481 68721 34480 68722 34481 68722 34512 68722 34512 68723 34481 68723 34482 68723 34512 68724 34482 68724 34483 68724 34483 68725 34482 68725 34513 68725 34462 68726 34485 68726 34484 68726 34484 68727 34485 68727 34486 68727 34484 68728 34486 68728 34502 68728 34486 68729 34510 68729 34502 68729 34502 68730 34510 68730 34509 68730 34502 68731 34509 68731 34500 68731 34500 68732 34509 68732 34487 68732 34500 68733 34487 68733 34498 68733 34498 68734 34487 68734 34488 68734 34498 68735 34488 68735 34478 68735 34489 68736 34862 68736 34409 68736 34409 68737 34862 68737 34490 68737 34409 68738 34490 68738 34472 68738 34409 68739 34472 68739 34408 68739 34408 68740 34472 68740 34470 68740 34467 68741 34491 68741 34492 68741 34492 68742 34491 68742 34493 68742 34492 68743 34493 68743 34494 68743 34494 68744 34493 68744 34495 68744 34494 68745 34495 68745 34496 68745 34428 68746 34425 68746 34481 68746 34481 68747 34425 68747 34471 68747 34481 68748 34471 68748 34482 68748 34482 68749 34471 68749 34473 68749 34482 68750 34473 68750 34479 68750 34479 68751 34473 68751 34497 68751 34479 68752 34497 68752 34498 68752 34498 68753 34497 68753 34499 68753 34498 68754 34499 68754 34500 68754 34500 68755 34499 68755 34501 68755 34500 68756 34501 68756 34502 68756 34502 68757 34501 68757 34474 68757 34502 68758 34474 68758 34484 68758 34484 68759 34474 68759 34476 68759 34484 68760 34476 68760 34461 68760 34461 68761 34476 68761 34503 68761 34506 68762 34403 68762 34435 68762 34435 68763 34434 68763 34506 68763 34506 68764 34434 68764 34407 68764 34506 68765 34407 68765 34504 68765 34504 68766 34505 68766 34506 68766 34506 68767 34505 68767 34429 68767 34506 68768 34429 68768 34511 68768 34506 68769 34462 68769 34399 68769 34399 68770 34507 68770 34506 68770 34506 68771 34507 68771 34423 68771 34506 68772 34423 68772 34508 68772 34508 68773 34406 68773 34506 68773 34506 68774 34406 68774 34404 68774 34506 68775 34404 68775 34403 68775 34488 68776 34487 68776 34506 68776 34506 68777 34487 68777 34509 68777 34506 68778 34509 68778 34510 68778 34510 68779 34486 68779 34506 68779 34506 68780 34486 68780 34485 68780 34506 68781 34485 68781 34462 68781 34506 68782 34511 68782 34480 68782 34480 68783 34512 68783 34506 68783 34506 68784 34512 68784 34483 68784 34506 68785 34483 68785 34513 68785 34513 68786 34514 68786 34506 68786 34506 68787 34514 68787 34478 68787 34506 68788 34478 68788 34488 68788 34491 68789 34596 68789 34493 68789 34493 68790 34596 68790 34597 68790 34517 68791 34515 68791 34516 68791 34516 68792 34515 68792 34496 68792 34516 68793 34496 68793 34597 68793 34597 68794 34496 68794 34495 68794 34597 68795 34495 68795 34493 68795 34517 68796 34516 68796 34518 68796 34518 68797 34516 68797 34585 68797 34518 68798 34585 68798 34464 68798 34395 68799 34519 68799 34586 68799 34586 68800 34519 68800 34443 68800 34586 68801 34443 68801 34585 68801 34585 68802 34443 68802 34463 68802 34585 68803 34463 68803 34464 68803 34395 68804 34586 68804 34397 68804 34397 68805 34586 68805 34626 68805 34397 68806 34626 68806 34520 68806 34520 68807 34626 68807 34521 68807 34521 68808 34626 68808 34522 68808 34521 68809 34522 68809 34444 68809 34444 68810 34522 68810 34523 68810 34523 68811 34522 68811 34524 68811 34523 68812 34524 68812 34446 68812 34530 68813 34288 68813 34525 68813 34525 68814 34325 68814 34530 68814 34530 68815 34325 68815 34526 68815 34530 68816 34526 68816 34527 68816 34527 68817 34321 68817 34530 68817 34530 68818 34321 68818 34528 68818 34530 68819 34528 68819 34295 68819 34530 68820 34529 68820 34287 68820 34287 68821 34286 68821 34530 68821 34530 68822 34286 68822 34315 68822 34530 68823 34315 68823 34293 68823 34293 68824 34292 68824 34530 68824 34530 68825 34292 68825 34290 68825 34530 68826 34290 68826 34288 68826 34535 68827 34531 68827 34530 68827 34530 68828 34531 68828 34379 68828 34530 68829 34379 68829 34532 68829 34532 68830 34533 68830 34530 68830 34530 68831 34533 68831 34534 68831 34530 68832 34534 68832 34529 68832 34530 68833 34295 68833 34374 68833 34374 68834 34375 68834 34530 68834 34530 68835 34375 68835 34376 68835 34530 68836 34376 68836 34377 68836 34377 68837 34373 68837 34530 68837 34530 68838 34373 68838 34371 68838 34530 68839 34371 68839 34535 68839 34847 68840 34640 68840 34381 68840 34381 68841 34640 68841 34641 68841 34381 68842 34641 68842 34382 68842 34654 68843 34536 68843 34641 68843 34641 68844 34536 68844 34537 68844 34641 68845 34537 68845 34382 68845 34356 68846 34539 68846 34538 68846 34538 68847 34539 68847 34355 68847 34538 68848 34355 68848 34654 68848 34654 68849 34355 68849 34540 68849 34654 68850 34540 68850 34536 68850 34356 68851 34538 68851 34333 68851 34333 68852 34538 68852 34634 68852 34333 68853 34634 68853 34543 68853 34650 68854 34284 68854 34310 68854 34310 68855 34541 68855 34650 68855 34650 68856 34541 68856 34542 68856 34650 68857 34542 68857 34634 68857 34634 68858 34542 68858 34332 68858 34634 68859 34332 68859 34543 68859 34284 68860 34650 68860 34285 68860 34285 68861 34650 68861 34544 68861 34285 68862 34544 68862 34335 68862 34335 68863 34544 68863 34545 68863 34545 68864 34544 68864 34546 68864 34545 68865 34546 68865 34337 68865 34553 68866 34555 68866 34547 68866 34547 68867 34212 68867 34553 68867 34553 68868 34212 68868 34178 68868 34553 68869 34178 68869 34548 68869 34548 68870 34549 68870 34553 68870 34553 68871 34549 68871 34550 68871 34553 68872 34550 68872 34551 68872 34553 68873 34560 68873 34552 68873 34552 68874 34173 68874 34553 68874 34553 68875 34173 68875 34172 68875 34553 68876 34172 68876 34171 68876 34171 68877 34175 68877 34553 68877 34553 68878 34175 68878 34554 68878 34553 68879 34554 68879 34555 68879 34562 68880 34266 68880 34553 68880 34553 68881 34266 68881 34556 68881 34553 68882 34556 68882 34557 68882 34557 68883 34558 68883 34553 68883 34553 68884 34558 68884 34559 68884 34553 68885 34559 68885 34560 68885 34553 68886 34551 68886 34561 68886 34561 68887 34261 68887 34553 68887 34553 68888 34261 68888 34262 68888 34553 68889 34262 68889 34264 68889 34264 68890 34259 68890 34553 68890 34553 68891 34259 68891 34268 68891 34553 68892 34268 68892 34562 68892 34842 68893 34563 68893 34273 68893 34273 68894 34563 68894 34564 68894 34273 68895 34564 68895 34275 68895 34568 68896 34246 68896 34564 68896 34564 68897 34246 68897 34276 68897 34564 68898 34276 68898 34275 68898 34565 68899 34566 68899 34624 68899 34624 68900 34566 68900 34567 68900 34624 68901 34567 68901 34568 68901 34568 68902 34567 68902 34569 68902 34568 68903 34569 68903 34246 68903 34565 68904 34624 68904 34570 68904 34570 68905 34624 68905 34645 68905 34570 68906 34645 68906 34571 68906 34628 68907 34202 68907 34200 68907 34200 68908 34199 68908 34628 68908 34628 68909 34199 68909 34572 68909 34628 68910 34572 68910 34645 68910 34645 68911 34572 68911 34573 68911 34645 68912 34573 68912 34571 68912 34202 68913 34628 68913 34231 68913 34231 68914 34628 68914 34658 68914 34231 68915 34658 68915 34221 68915 34221 68916 34658 68916 34574 68916 34574 68917 34658 68917 34575 68917 34574 68918 34575 68918 34844 68918 34055 68919 34033 68919 34593 68919 34861 68920 34636 68920 34587 68920 34576 68921 34577 68921 34858 68921 34841 68922 34608 68922 33826 68922 34797 68923 34578 68923 34795 68923 34795 68924 34578 68924 34579 68924 34795 68925 34579 68925 34581 68925 34614 68926 34609 68926 34773 68926 34579 68927 34580 68927 34581 68927 34581 68928 34580 68928 35021 68928 34581 68929 35021 68929 34615 68929 34582 68930 34610 68930 34644 68930 34592 68931 33965 68931 34538 68931 34857 68932 33899 68932 33922 68932 34583 68933 34843 68933 34584 68933 34584 68934 34843 68934 34841 68934 34584 68935 34841 68935 33824 68935 33824 68936 34841 68936 33826 68936 34516 68937 34918 68937 34585 68937 34585 68938 34918 68938 34920 68938 34585 68939 34920 68939 34586 68939 34587 68940 34026 68940 34861 68940 34861 68941 34026 68941 34594 68941 34861 68942 34594 68942 34863 68942 34588 68943 33835 68943 33814 68943 34582 68944 34644 68944 33855 68944 33924 68945 34589 68945 34590 68945 34590 68946 34589 68946 34857 68946 34590 68947 34857 68947 33923 68947 33923 68948 34857 68948 33922 68948 34920 68949 34921 68949 34586 68949 34586 68950 34921 68950 34922 68950 34586 68951 34922 68951 34626 68951 33814 68952 33812 68952 34588 68952 34588 68953 33812 68953 33810 68953 34588 68954 33810 68954 34603 68954 34623 68955 34591 68955 34624 68955 34592 68956 34538 68956 33967 68956 33924 68957 33948 68957 34589 68957 34589 68958 33948 68958 33950 68958 34589 68959 33950 68959 34637 68959 34873 68960 34939 68960 34871 68960 34871 68961 34939 68961 34940 68961 34871 68962 34940 68962 34593 68962 34593 68963 34940 68963 34061 68963 34593 68964 34061 68964 34055 68964 34597 68965 34599 68965 34516 68965 34516 68966 34599 68966 34917 68966 34516 68967 34917 68967 34918 68967 34594 68968 34045 68968 34863 68968 34863 68969 34045 68969 34044 68969 34863 68970 34044 68970 34595 68970 34595 68971 34044 68971 34053 68971 34595 68972 34053 68972 34596 68972 34596 68973 34053 68973 34054 68973 34596 68974 34054 68974 34597 68974 34597 68975 34054 68975 34598 68975 34597 68976 34598 68976 34599 68976 34600 68977 34601 68977 34797 68977 34797 68978 34601 68978 34602 68978 34797 68979 34602 68979 34578 68979 33810 68980 33801 68980 34603 68980 34603 68981 33801 68981 33802 68981 34603 68982 33802 68982 34604 68982 34604 68983 33802 68983 34605 68983 34604 68984 34605 68984 34606 68984 34606 68985 34605 68985 34607 68985 34606 68986 34607 68986 34600 68986 34600 68987 34607 68987 35018 68987 34600 68988 35018 68988 34601 68988 34841 68989 34644 68989 34608 68989 34608 68990 34644 68990 34610 68990 34608 68991 34610 68991 34609 68991 34609 68992 34610 68992 33835 68992 34609 68993 33835 68993 34773 68993 34773 68994 33835 68994 34588 68994 34621 68995 34611 68995 34612 68995 34612 68996 34611 68996 34613 68996 34612 68997 34613 68997 34773 68997 34773 68998 34613 68998 33788 68998 34773 68999 33788 68999 34614 68999 35021 69000 34616 69000 34615 69000 34615 69001 34616 69001 34617 69001 34615 69002 34617 69002 34784 69002 34784 69003 34617 69003 34618 69003 34784 69004 34618 69004 34783 69004 34783 69005 34618 69005 34619 69005 34783 69006 34619 69006 34621 69006 34621 69007 34619 69007 34620 69007 34621 69008 34620 69008 34611 69008 34622 69009 34657 69009 34645 69009 34623 69010 34624 69010 33870 69010 34634 69011 34034 69011 34012 69011 34922 69012 34625 69012 34626 69012 34626 69013 34625 69013 34923 69013 34626 69014 34923 69014 34522 69014 34522 69015 34923 69015 34924 69015 34522 69016 34924 69016 34524 69016 34524 69017 34924 69017 34627 69017 34524 69018 34627 69018 34873 69018 34873 69019 34627 69019 34932 69019 34873 69020 34932 69020 34939 69020 34645 69021 34657 69021 34628 69021 34857 69022 34858 69022 33899 69022 33899 69023 34858 69023 34577 69023 33899 69024 34577 69024 34629 69024 34629 69025 34577 69025 34646 69025 34583 69026 34630 69026 34843 69026 34843 69027 34630 69027 34662 69027 34843 69028 34662 69028 34631 69028 34854 69029 34632 69029 34852 69029 34852 69030 34632 69030 33963 69030 34852 69031 33963 69031 34858 69031 34858 69032 33963 69032 34633 69032 34858 69033 34633 69033 34576 69033 34012 69034 34011 69034 34634 69034 34634 69035 34011 69035 34635 69035 34634 69036 34635 69036 34650 69036 34861 69037 34593 69037 34636 69037 34636 69038 34593 69038 34033 69038 34636 69039 34033 69039 33965 69039 33965 69040 34033 69040 34034 69040 33965 69041 34034 69041 34538 69041 34538 69042 34034 69042 34634 69042 33950 69043 33951 69043 34637 69043 34637 69044 33951 69044 34638 69044 34637 69045 34638 69045 34640 69045 34640 69046 34638 69046 34639 69046 34640 69047 34639 69047 34641 69047 34661 69048 34643 69048 34642 69048 34642 69049 34643 69049 33897 69049 34642 69050 33897 69050 34644 69050 34644 69051 33897 69051 33857 69051 34644 69052 33857 69052 33855 69052 34591 69053 34629 69053 34624 69053 34624 69054 34629 69054 34646 69054 34624 69055 34646 69055 34645 69055 34645 69056 34646 69056 33910 69056 34645 69057 33910 69057 34622 69057 33870 69058 34624 69058 34647 69058 34647 69059 34624 69059 34568 69059 34647 69060 34568 69060 34966 69060 34966 69061 34568 69061 34564 69061 34966 69062 34564 69062 34649 69062 34563 69063 34963 69063 34564 69063 34564 69064 34963 69064 34648 69064 34564 69065 34648 69065 34649 69065 34635 69066 34009 69066 34650 69066 34650 69067 34009 69067 33994 69067 34650 69068 33994 69068 34544 69068 34544 69069 33994 69069 34651 69069 34544 69070 34651 69070 34546 69070 34546 69071 34651 69071 34652 69071 34546 69072 34652 69072 34854 69072 34854 69073 34652 69073 33997 69073 34854 69074 33997 69074 34632 69074 34639 69075 34950 69075 34641 69075 34641 69076 34950 69076 34653 69076 34641 69077 34653 69077 34654 69077 34654 69078 34653 69078 34655 69078 34654 69079 34655 69079 34538 69079 34538 69080 34655 69080 34656 69080 34538 69081 34656 69081 33967 69081 34657 69082 33879 69082 34628 69082 34628 69083 33879 69083 34659 69083 34628 69084 34659 69084 34658 69084 34658 69085 34659 69085 34660 69085 34658 69086 34660 69086 34575 69086 34575 69087 34660 69087 33895 69087 34575 69088 33895 69088 34661 69088 34661 69089 33895 69089 33896 69089 34661 69090 33896 69090 34643 69090 34662 69091 34663 69091 34631 69091 34631 69092 34663 69092 33850 69092 34631 69093 33850 69093 34563 69093 34563 69094 33850 69094 33852 69094 34563 69095 33852 69095 34963 69095 34686 69096 34754 69096 34683 69096 34749 69097 34687 69097 34726 69097 34804 69098 34682 69098 34687 69098 34721 69099 34722 69099 34664 69099 34828 69100 34665 69100 34693 69100 34666 69101 34800 69101 34713 69101 34828 69102 34693 69102 34826 69102 34667 69103 34698 69103 34675 69103 34675 69104 34698 69104 34699 69104 34675 69105 34699 69105 34665 69105 34665 69106 34699 69106 34700 69106 34665 69107 34700 69107 34693 69107 34713 69108 34800 69108 34669 69108 34669 69109 34800 69109 34668 69109 34669 69110 34668 69110 34670 69110 34670 69111 34668 69111 34751 69111 34670 69112 34751 69112 34709 69112 34709 69113 34751 69113 34671 69113 34709 69114 34671 69114 34708 69114 34738 69115 34672 69115 34823 69115 34672 69116 34738 69116 34820 69116 34820 69117 34738 69117 34733 69117 34820 69118 34733 69118 34694 69118 34694 69119 34733 69119 34673 69119 34694 69120 34673 69120 34735 69120 34754 69121 34686 69121 34752 69121 34752 69122 34686 69122 34705 69122 34752 69123 34705 69123 34757 69123 34757 69124 34705 69124 34674 69124 34757 69125 34674 69125 34675 69125 34675 69126 34674 69126 34703 69126 34675 69127 34703 69127 34667 69127 34726 69128 34728 69128 34749 69128 34749 69129 34728 69129 34676 69129 34749 69130 34676 69130 34677 69130 34677 69131 34676 69131 34718 69131 34677 69132 34718 69132 34679 69132 34679 69133 34718 69133 34678 69133 34679 69134 34678 69134 34751 69134 34751 69135 34678 69135 34680 69135 34751 69136 34680 69136 34671 69136 34749 69137 34745 69137 34687 69137 34687 69138 34745 69138 34681 69138 34687 69139 34681 69139 34746 69139 34687 69140 34682 69140 34664 69140 34664 69141 34682 69141 34691 69141 34664 69142 34691 69142 34721 69142 34683 69143 34684 69143 34686 69143 34686 69144 34684 69144 34685 69144 34686 69145 34685 69145 34713 69145 34713 69146 34685 69146 34799 69146 34713 69147 34799 69147 34666 69147 34746 69148 34688 69148 34687 69148 34687 69149 34688 69149 34802 69149 34687 69150 34802 69150 34804 69150 34823 69151 34731 69151 34738 69151 34738 69152 34731 69152 34732 69152 34738 69153 34732 69153 34689 69153 34689 69154 34732 69154 34730 69154 34689 69155 34730 69155 34742 69155 34742 69156 34730 69156 34690 69156 34742 69157 34690 69157 34691 69157 34691 69158 34690 69158 34692 69158 34691 69159 34692 69159 34721 69159 34735 69160 34806 69160 34694 69160 34694 69161 34806 69161 34808 69161 34694 69162 34808 69162 34695 69162 34826 69163 34693 69163 34839 69163 34839 69164 34693 69164 34836 69164 34839 69165 34836 69165 34837 69165 34817 69166 34694 69166 34814 69166 34814 69167 34694 69167 34695 69167 34814 69168 34695 69168 34811 69168 34811 69169 34695 69169 34810 69169 34835 69170 34836 69170 34696 69170 34696 69171 34836 69171 34693 69171 34696 69172 34693 69172 34831 69172 34831 69173 34693 69173 34697 69173 34667 69174 33789 69174 34969 69174 34667 69175 34969 69175 34698 69175 34698 69176 34969 69176 34967 69176 34698 69177 34967 69177 34699 69177 34699 69178 34967 69178 35007 69178 34699 69179 35007 69179 34700 69179 34704 69180 33782 69180 34674 69180 34674 69181 33782 69181 34703 69181 33789 69182 34667 69182 34701 69182 34701 69183 34667 69183 34703 69183 34701 69184 34703 69184 34702 69184 34702 69185 34703 69185 33782 69185 34704 69186 34674 69186 33808 69186 33808 69187 34674 69187 34705 69187 33839 69188 33833 69188 34713 69188 34713 69189 33833 69189 34686 69189 33808 69190 34705 69190 34706 69190 34706 69191 34705 69191 34686 69191 34706 69192 34686 69192 33834 69192 33834 69193 34686 69193 33833 69193 34671 69194 34959 69194 34707 69194 34671 69195 34707 69195 34708 69195 34707 69196 34957 69196 34708 69196 34708 69197 34957 69197 34955 69197 34708 69198 34955 69198 34709 69198 34955 69199 34710 69199 34709 69199 34709 69200 34710 69200 33842 69200 34709 69201 33842 69201 34670 69201 34670 69202 33842 69202 34711 69202 34670 69203 34711 69203 34669 69203 34711 69204 34712 69204 34669 69204 34669 69205 34712 69205 33840 69205 34669 69206 33840 69206 34713 69206 34713 69207 33840 69207 34714 69207 34713 69208 34714 69208 33839 69208 34715 69209 33876 69209 34678 69209 34678 69210 33876 69210 34680 69210 34959 69211 34671 69211 34716 69211 34716 69212 34671 69212 34680 69212 34716 69213 34680 69213 34717 69213 34717 69214 34680 69214 33876 69214 34715 69215 34678 69215 33905 69215 33905 69216 34678 69216 34718 69216 33927 69217 33929 69217 34728 69217 34728 69218 33929 69218 34676 69218 33905 69219 34718 69219 34719 69219 34719 69220 34718 69220 34676 69220 34719 69221 34676 69221 34720 69221 34720 69222 34676 69222 33929 69222 34721 69223 33980 69223 34723 69223 34721 69224 34723 69224 34722 69224 34722 69225 34723 69225 34943 69225 34722 69226 34943 69226 34664 69226 34664 69227 34943 69227 34942 69227 34664 69228 34942 69228 34687 69228 34942 69229 34724 69229 34687 69229 34687 69230 34724 69230 34725 69230 34687 69231 34725 69231 34726 69231 34726 69232 34725 69232 34727 69232 33927 69233 34728 69233 34729 69233 34729 69234 34728 69234 34726 69234 34729 69235 34726 69235 33941 69235 33941 69236 34726 69236 34727 69236 34004 69237 33976 69237 34690 69237 34690 69238 33976 69238 34692 69238 33980 69239 34721 69239 33978 69239 33978 69240 34721 69240 34692 69240 33978 69241 34692 69241 33977 69241 33977 69242 34692 69242 33976 69242 34004 69243 34690 69243 34005 69243 34005 69244 34690 69244 34730 69244 34039 69245 34027 69245 34731 69245 34731 69246 34027 69246 34732 69246 34005 69247 34730 69247 34031 69247 34031 69248 34730 69248 34732 69248 34031 69249 34732 69249 34028 69249 34028 69250 34732 69250 34027 69250 34733 69251 34734 69251 34927 69251 34733 69252 34927 69252 34673 69252 34673 69253 34927 69253 34736 69253 34673 69254 34736 69254 34735 69254 34735 69255 34736 69255 34925 69255 34735 69256 34925 69256 34806 69256 34038 69257 34739 69257 34689 69257 34689 69258 34739 69258 34738 69258 34734 69259 34733 69259 34064 69259 34064 69260 34733 69260 34738 69260 34064 69261 34738 69261 34737 69261 34737 69262 34738 69262 34739 69262 34038 69263 34689 69263 34740 69263 34740 69264 34689 69264 34742 69264 34682 69265 34006 69265 34741 69265 34682 69266 34741 69266 34691 69266 34740 69267 34742 69267 34743 69267 34743 69268 34742 69268 34691 69268 34743 69269 34691 69269 34744 69269 34744 69270 34691 69270 34741 69270 34745 69271 33956 69271 33985 69271 34745 69272 33985 69272 34681 69272 34681 69273 33985 69273 33984 69273 34681 69274 33984 69274 34746 69274 34746 69275 33984 69275 34801 69275 34746 69276 34801 69276 34688 69276 34747 69277 34748 69277 34677 69277 34677 69278 34748 69278 34749 69278 33956 69279 34745 69279 33958 69279 33958 69280 34745 69280 34749 69280 33958 69281 34749 69281 34750 69281 34750 69282 34749 69282 34748 69282 34747 69283 34677 69283 33938 69283 33938 69284 34677 69284 34679 69284 34668 69285 33906 69285 33913 69285 34668 69286 33913 69286 34751 69286 33938 69287 34679 69287 33917 69287 33917 69288 34679 69288 34751 69288 33917 69289 34751 69289 33915 69289 33915 69290 34751 69290 33913 69290 34683 69291 33866 69291 33888 69291 34683 69292 33888 69292 34684 69292 34684 69293 33888 69293 33886 69293 34684 69294 33886 69294 34685 69294 34685 69295 33886 69295 33885 69295 34685 69296 33885 69296 34799 69296 34752 69297 34755 69297 34753 69297 34752 69298 34753 69298 34754 69298 33866 69299 34683 69299 33865 69299 33865 69300 34683 69300 34754 69300 33865 69301 34754 69301 33863 69301 33863 69302 34754 69302 34753 69302 34755 69303 34752 69303 34756 69303 34756 69304 34752 69304 34757 69304 34665 69305 34827 69305 33820 69305 34665 69306 33820 69306 34675 69306 34756 69307 34757 69307 33822 69307 33822 69308 34757 69308 34675 69308 33822 69309 34675 69309 33821 69309 33821 69310 34675 69310 33820 69310 34761 69311 34758 69311 34068 69311 34068 69312 34072 69312 34761 69312 34761 69313 34072 69313 34073 69313 34761 69314 34073 69314 34759 69314 34759 69315 34760 69315 34761 69315 34761 69316 34760 69316 34102 69316 34761 69317 34102 69317 34146 69317 34761 69318 34149 69318 34762 69318 34762 69319 34763 69319 34761 69319 34761 69320 34763 69320 34066 69320 34761 69321 34066 69321 34071 69321 34071 69322 34764 69322 34761 69322 34761 69323 34764 69323 34070 69323 34761 69324 34070 69324 34758 69324 34154 69325 34765 69325 34761 69325 34761 69326 34765 69326 34153 69326 34761 69327 34153 69327 34151 69327 34151 69328 34766 69328 34761 69328 34761 69329 34766 69329 34150 69329 34761 69330 34150 69330 34149 69330 34761 69331 34146 69331 34147 69331 34147 69332 34767 69332 34761 69332 34761 69333 34767 69333 34768 69333 34761 69334 34768 69334 34145 69334 34145 69335 34144 69335 34761 69335 34761 69336 34144 69336 34143 69336 34761 69337 34143 69337 34154 69337 34159 69338 34783 69338 34769 69338 34769 69339 34783 69339 34621 69339 34769 69340 34621 69340 34771 69340 34612 69341 34774 69341 34621 69341 34621 69342 34774 69342 34770 69342 34621 69343 34770 69343 34771 69343 34132 69344 34131 69344 34773 69344 34773 69345 34131 69345 34772 69345 34773 69346 34772 69346 34612 69346 34612 69347 34772 69347 34133 69347 34612 69348 34133 69348 34774 69348 34132 69349 34773 69349 34775 69349 34775 69350 34773 69350 34588 69350 34775 69351 34588 69351 34112 69351 34603 69352 34093 69352 34092 69352 34092 69353 34776 69353 34603 69353 34603 69354 34776 69354 34777 69354 34603 69355 34777 69355 34588 69355 34588 69356 34777 69356 34778 69356 34588 69357 34778 69357 34112 69357 34093 69358 34603 69358 34779 69358 34779 69359 34603 69359 34604 69359 34779 69360 34604 69360 34120 69360 34120 69361 34604 69361 34780 69361 34780 69362 34604 69362 34606 69362 34780 69363 34606 69363 34115 69363 34615 69364 34781 69364 34581 69364 34581 69365 34781 69365 34782 69365 34581 69366 34782 69366 34127 69366 34784 69367 34783 69367 34159 69367 34159 69368 34158 69368 34784 69368 34784 69369 34158 69369 34785 69369 34784 69370 34785 69370 34615 69370 34615 69371 34785 69371 34136 69371 34615 69372 34136 69372 34781 69372 34115 69373 34606 69373 34116 69373 34116 69374 34606 69374 34600 69374 34792 69375 34786 69375 34600 69375 34600 69376 34786 69376 34787 69376 34600 69377 34787 69377 34116 69377 34788 69378 34789 69378 34797 69378 34797 69379 34789 69379 34790 69379 34797 69380 34790 69380 34600 69380 34600 69381 34790 69381 34791 69381 34600 69382 34791 69382 34792 69382 34127 69383 34793 69383 34581 69383 34581 69384 34793 69384 34794 69384 34581 69385 34794 69385 34795 69385 34795 69386 34794 69386 34796 69386 34795 69387 34796 69387 34797 69387 34797 69388 34796 69388 34077 69388 34797 69389 34077 69389 34788 69389 34799 69390 33885 69390 34798 69390 34799 69391 34798 69391 34666 69391 34666 69392 34798 69392 33882 69392 34666 69393 33882 69393 34800 69393 34800 69394 33882 69394 33906 69394 34800 69395 33906 69395 34668 69395 34688 69396 34801 69396 33982 69396 34688 69397 33982 69397 34802 69397 34802 69398 33982 69398 34803 69398 34802 69399 34803 69399 34804 69399 34804 69400 34803 69400 34006 69400 34804 69401 34006 69401 34682 69401 34925 69402 34805 69402 34806 69402 34806 69403 34805 69403 34808 69403 34887 69404 34695 69404 34807 69404 34807 69405 34695 69405 34808 69405 34807 69406 34808 69406 34888 69406 34888 69407 34808 69407 34805 69407 34887 69408 34886 69408 34695 69408 34695 69409 34886 69409 34885 69409 34695 69410 34885 69410 34810 69410 34885 69411 34809 69411 34810 69411 34810 69412 34809 69412 34812 69412 34810 69413 34812 69413 34811 69413 34812 69414 34883 69414 34811 69414 34811 69415 34883 69415 34813 69415 34811 69416 34813 69416 34814 69416 34813 69417 34881 69417 34814 69417 34814 69418 34881 69418 34815 69418 34814 69419 34815 69419 34817 69419 34815 69420 34816 69420 34817 69420 34817 69421 34816 69421 34818 69421 34817 69422 34818 69422 34694 69422 34694 69423 34818 69423 34875 69423 34050 69424 34820 69424 34878 69424 34878 69425 34820 69425 34694 69425 34878 69426 34694 69426 34819 69426 34819 69427 34694 69427 34875 69427 34820 69428 34050 69428 34821 69428 34820 69429 34821 69429 34672 69429 34672 69430 34821 69430 34822 69430 34672 69431 34822 69431 34823 69431 34823 69432 34822 69432 34039 69432 34823 69433 34039 69433 34731 69433 34839 69434 34824 69434 34825 69434 34839 69435 34825 69435 34826 69435 34826 69436 34825 69436 33796 69436 34826 69437 33796 69437 34828 69437 34828 69438 33796 69438 34827 69438 34828 69439 34827 69439 34665 69439 35007 69440 34829 69440 34700 69440 34700 69441 34829 69441 34693 69441 34829 69442 34830 69442 34693 69442 34693 69443 34830 69443 34991 69443 34693 69444 34991 69444 34697 69444 34987 69445 34831 69445 34832 69445 34832 69446 34831 69446 34697 69446 34832 69447 34697 69447 34989 69447 34989 69448 34697 69448 34991 69448 34987 69449 34986 69449 34831 69449 34831 69450 34986 69450 34833 69450 34831 69451 34833 69451 34696 69451 34983 69452 34835 69452 34985 69452 34985 69453 34835 69453 34696 69453 34985 69454 34696 69454 34834 69454 34834 69455 34696 69455 34833 69455 34983 69456 34982 69456 34835 69456 34835 69457 34982 69457 34981 69457 34835 69458 34981 69458 34836 69458 34836 69459 34981 69459 34838 69459 34836 69460 34838 69460 34837 69460 34837 69461 34838 69461 34978 69461 34824 69462 34839 69462 34980 69462 34980 69463 34839 69463 34837 69463 34980 69464 34837 69464 34840 69464 34840 69465 34837 69465 34978 69465 34843 69466 34250 69466 34841 69466 34841 69467 34250 69467 34249 69467 34841 69468 34249 69468 34240 69468 34631 69469 34563 69469 34842 69469 34842 69470 34272 69470 34631 69470 34631 69471 34272 69471 34252 69471 34631 69472 34252 69472 34843 69472 34843 69473 34252 69473 34247 69473 34843 69474 34247 69474 34250 69474 34844 69475 34575 69475 34223 69475 34223 69476 34575 69476 34661 69476 34845 69477 34225 69477 34661 69477 34661 69478 34225 69478 34224 69478 34661 69479 34224 69479 34223 69479 34180 69480 34213 69480 34642 69480 34642 69481 34213 69481 34186 69481 34642 69482 34186 69482 34661 69482 34661 69483 34186 69483 34188 69483 34661 69484 34188 69484 34845 69484 34240 69485 34269 69485 34841 69485 34841 69486 34269 69486 34182 69486 34841 69487 34182 69487 34644 69487 34644 69488 34182 69488 34846 69488 34644 69489 34846 69489 34642 69489 34642 69490 34846 69490 34181 69490 34642 69491 34181 69491 34180 69491 34589 69492 34848 69492 34857 69492 34857 69493 34848 69493 34362 69493 34857 69494 34362 69494 34361 69494 34637 69495 34640 69495 34847 69495 34847 69496 34359 69496 34637 69496 34637 69497 34359 69497 34365 69497 34637 69498 34365 69498 34589 69498 34589 69499 34365 69499 34363 69499 34589 69500 34363 69500 34848 69500 34337 69501 34546 69501 34849 69501 34849 69502 34546 69502 34854 69502 34856 69503 34850 69503 34854 69503 34854 69504 34850 69504 34338 69504 34854 69505 34338 69505 34849 69505 34851 69506 34326 69506 34852 69506 34852 69507 34326 69507 34853 69507 34852 69508 34853 69508 34854 69508 34854 69509 34853 69509 34855 69509 34854 69510 34855 69510 34856 69510 34361 69511 34351 69511 34857 69511 34857 69512 34351 69512 34859 69512 34857 69513 34859 69513 34858 69513 34858 69514 34859 69514 34860 69514 34858 69515 34860 69515 34852 69515 34852 69516 34860 69516 34296 69516 34852 69517 34296 69517 34851 69517 34867 69518 34862 69518 34861 69518 34861 69519 34862 69519 34489 69519 34861 69520 34489 69520 34593 69520 34467 69521 34864 69521 34863 69521 34864 69522 34468 69522 34863 69522 34863 69523 34468 69523 34865 69523 34863 69524 34865 69524 34861 69524 34861 69525 34865 69525 34866 69525 34861 69526 34866 69526 34867 69526 34863 69527 34595 69527 34467 69527 34467 69528 34595 69528 34596 69528 34467 69529 34596 69529 34491 69529 34446 69530 34524 69530 34447 69530 34447 69531 34524 69531 34873 69531 34447 69532 34873 69532 34448 69532 34448 69533 34873 69533 34460 69533 34489 69534 34868 69534 34593 69534 34593 69535 34868 69535 34869 69535 34593 69536 34869 69536 34871 69536 34871 69537 34869 69537 34870 69537 34871 69538 34870 69538 34873 69538 34873 69539 34870 69539 34872 69539 34873 69540 34872 69540 34460 69540 34054 69541 34899 69541 34874 69541 34899 69542 34890 69542 34900 69542 34890 69543 34879 69543 34877 69543 34889 69544 34805 69544 34925 69544 34818 69545 34880 69545 34875 69545 34875 69546 34880 69546 34876 69546 34875 69547 34876 69547 34819 69547 34819 69548 34876 69548 34877 69548 34819 69549 34877 69549 34878 69549 34878 69550 34877 69550 34879 69550 34878 69551 34879 69551 34050 69551 34818 69552 34816 69552 34880 69552 34880 69553 34816 69553 34815 69553 34880 69554 34815 69554 34891 69554 34891 69555 34815 69555 34881 69555 34891 69556 34881 69556 34882 69556 34881 69557 34813 69557 34882 69557 34882 69558 34813 69558 34883 69558 34882 69559 34883 69559 34894 69559 34894 69560 34883 69560 34812 69560 34894 69561 34812 69561 34884 69561 34884 69562 34812 69562 34809 69562 34809 69563 34885 69563 34884 69563 34884 69564 34885 69564 34886 69564 34884 69565 34886 69565 34896 69565 34896 69566 34886 69566 34887 69566 34896 69567 34887 69567 34897 69567 34897 69568 34887 69568 34807 69568 34897 69569 34807 69569 34889 69569 34889 69570 34807 69570 34888 69570 34889 69571 34888 69571 34805 69571 34890 69572 34877 69572 34900 69572 34900 69573 34877 69573 34876 69573 34900 69574 34876 69574 34901 69574 34901 69575 34876 69575 34880 69575 34901 69576 34880 69576 34902 69576 34902 69577 34880 69577 34891 69577 34902 69578 34891 69578 34892 69578 34892 69579 34891 69579 34882 69579 34892 69580 34882 69580 34904 69580 34904 69581 34882 69581 34894 69581 34904 69582 34894 69582 34893 69582 34893 69583 34894 69583 34884 69583 34893 69584 34884 69584 34895 69584 34895 69585 34884 69585 34896 69585 34895 69586 34896 69586 34907 69586 34907 69587 34896 69587 34897 69587 34907 69588 34897 69588 34910 69588 34910 69589 34897 69589 34889 69589 34910 69590 34889 69590 34911 69590 34925 69591 34926 69591 34889 69591 34889 69592 34926 69592 34898 69592 34889 69593 34898 69593 34911 69593 34911 69594 34898 69594 34930 69594 34911 69595 34930 69595 34913 69595 34899 69596 34900 69596 34874 69596 34874 69597 34900 69597 34901 69597 34874 69598 34901 69598 34915 69598 34915 69599 34901 69599 34902 69599 34915 69600 34902 69600 34916 69600 34916 69601 34902 69601 34892 69601 34916 69602 34892 69602 34903 69602 34903 69603 34892 69603 34904 69603 34903 69604 34904 69604 34919 69604 34919 69605 34904 69605 34893 69605 34919 69606 34893 69606 34905 69606 34905 69607 34893 69607 34895 69607 34905 69608 34895 69608 34906 69608 34906 69609 34895 69609 34907 69609 34906 69610 34907 69610 34908 69610 34908 69611 34907 69611 34910 69611 34908 69612 34910 69612 34909 69612 34909 69613 34910 69613 34911 69613 34909 69614 34911 69614 34912 69614 34912 69615 34911 69615 34913 69615 34912 69616 34913 69616 34914 69616 34054 69617 34874 69617 34598 69617 34598 69618 34874 69618 34915 69618 34598 69619 34915 69619 34599 69619 34599 69620 34915 69620 34916 69620 34599 69621 34916 69621 34917 69621 34917 69622 34916 69622 34903 69622 34917 69623 34903 69623 34918 69623 34918 69624 34903 69624 34919 69624 34918 69625 34919 69625 34920 69625 34920 69626 34919 69626 34905 69626 34920 69627 34905 69627 34921 69627 34921 69628 34905 69628 34906 69628 34921 69629 34906 69629 34922 69629 34922 69630 34906 69630 34908 69630 34922 69631 34908 69631 34625 69631 34625 69632 34908 69632 34909 69632 34625 69633 34909 69633 34923 69633 34923 69634 34909 69634 34912 69634 34923 69635 34912 69635 34924 69635 34924 69636 34912 69636 34914 69636 34924 69637 34914 69637 34627 69637 34925 69638 34736 69638 34926 69638 34926 69639 34736 69639 34931 69639 34927 69640 34734 69640 34933 69640 34927 69641 34933 69641 34928 69641 34914 69642 34913 69642 34929 69642 34929 69643 34913 69643 34930 69643 34929 69644 34930 69644 34931 69644 34931 69645 34930 69645 34898 69645 34931 69646 34898 69646 34926 69646 34736 69647 34927 69647 34931 69647 34931 69648 34927 69648 34928 69648 34931 69649 34928 69649 34929 69649 34929 69650 34928 69650 34938 69650 34932 69651 34627 69651 34914 69651 34933 69652 34934 69652 34928 69652 34928 69653 34934 69653 34935 69653 34928 69654 34935 69654 34938 69654 34938 69655 34935 69655 34936 69655 34938 69656 34936 69656 34937 69656 34914 69657 34929 69657 34932 69657 34932 69658 34929 69658 34938 69658 34932 69659 34938 69659 34939 69659 34939 69660 34938 69660 34937 69660 34939 69661 34937 69661 34940 69661 34948 69662 34723 69662 33980 69662 34944 69663 34724 69663 34941 69663 34941 69664 34724 69664 34942 69664 34941 69665 34942 69665 34943 69665 33980 69666 33979 69666 34948 69666 34948 69667 33979 69667 33974 69667 34948 69668 33974 69668 34951 69668 34944 69669 34941 69669 34945 69669 34945 69670 34941 69670 34949 69670 34945 69671 34949 69671 34946 69671 34946 69672 34949 69672 34947 69672 34946 69673 34947 69673 33947 69673 33947 69674 34947 69674 34950 69674 33947 69675 34950 69675 34639 69675 34943 69676 34723 69676 34941 69676 34941 69677 34723 69677 34948 69677 34941 69678 34948 69678 34949 69678 34949 69679 34948 69679 34951 69679 34949 69680 34951 69680 34947 69680 34947 69681 34951 69681 34953 69681 34947 69682 34953 69682 34950 69682 34950 69683 34953 69683 34653 69683 33974 69684 33973 69684 34951 69684 34951 69685 33973 69685 34952 69685 34951 69686 34952 69686 34953 69686 34953 69687 34952 69687 34655 69687 34953 69688 34655 69688 34653 69688 33852 69689 33851 69689 34961 69689 33851 69690 33847 69690 34960 69690 33847 69691 33842 69691 34710 69691 33847 69692 34710 69692 34960 69692 34960 69693 34710 69693 34955 69693 34960 69694 34955 69694 34954 69694 34954 69695 34955 69695 34957 69695 34954 69696 34957 69696 34956 69696 34956 69697 34957 69697 34707 69697 34956 69698 34707 69698 34958 69698 34958 69699 34707 69699 34959 69699 34958 69700 34959 69700 33878 69700 33851 69701 34960 69701 34961 69701 34961 69702 34960 69702 34954 69702 34961 69703 34954 69703 34964 69703 34964 69704 34954 69704 34956 69704 34964 69705 34956 69705 34965 69705 34965 69706 34956 69706 34958 69706 34965 69707 34958 69707 34962 69707 34962 69708 34958 69708 33878 69708 34962 69709 33878 69709 33871 69709 33852 69710 34961 69710 34963 69710 34963 69711 34961 69711 34964 69711 34963 69712 34964 69712 34648 69712 34648 69713 34964 69713 34965 69713 34648 69714 34965 69714 34649 69714 34649 69715 34965 69715 34962 69715 34649 69716 34962 69716 34966 69716 34966 69717 34962 69717 33871 69717 34966 69718 33871 69718 34647 69718 35007 69719 34967 69719 34968 69719 34968 69720 34967 69720 34973 69720 34968 69721 34973 69721 34970 69721 34969 69722 33789 69722 33790 69722 34969 69723 33790 69723 34974 69723 34970 69724 34973 69724 35008 69724 35008 69725 34973 69725 34971 69725 35008 69726 34971 69726 35009 69726 35009 69727 34971 69727 34972 69727 34972 69728 34971 69728 34620 69728 34972 69729 34620 69729 34619 69729 34967 69730 34969 69730 34973 69730 34973 69731 34969 69731 34974 69731 34973 69732 34974 69732 34971 69732 34971 69733 34974 69733 34976 69733 34971 69734 34976 69734 34620 69734 34620 69735 34976 69735 34611 69735 33790 69736 33791 69736 34974 69736 34974 69737 33791 69737 33793 69737 34974 69738 33793 69738 34976 69738 34976 69739 33793 69739 34975 69739 34976 69740 34975 69740 34611 69740 34611 69741 34975 69741 34613 69741 34993 69742 33795 69742 34979 69742 34977 69743 34829 69743 35007 69743 34838 69744 34996 69744 34978 69744 34978 69745 34996 69745 34994 69745 34978 69746 34994 69746 34840 69746 34840 69747 34994 69747 34979 69747 34840 69748 34979 69748 34980 69748 34980 69749 34979 69749 33795 69749 34980 69750 33795 69750 34824 69750 34838 69751 34981 69751 34996 69751 34996 69752 34981 69752 34982 69752 34996 69753 34982 69753 34998 69753 34998 69754 34982 69754 34983 69754 34998 69755 34983 69755 34984 69755 34983 69756 34985 69756 34984 69756 34984 69757 34985 69757 34834 69757 34984 69758 34834 69758 35001 69758 35001 69759 34834 69759 34833 69759 35001 69760 34833 69760 34988 69760 34988 69761 34833 69761 34986 69761 34986 69762 34987 69762 34988 69762 34988 69763 34987 69763 34832 69763 34988 69764 34832 69764 35004 69764 35004 69765 34832 69765 34989 69765 35004 69766 34989 69766 34990 69766 34990 69767 34989 69767 34991 69767 34990 69768 34991 69768 34977 69768 34977 69769 34991 69769 34830 69769 34977 69770 34830 69770 34829 69770 34992 69771 33803 69771 34993 69771 34993 69772 34979 69772 34992 69772 34992 69773 34979 69773 34994 69773 34992 69774 34994 69774 34995 69774 34995 69775 34994 69775 34996 69775 34995 69776 34996 69776 34997 69776 34997 69777 34996 69777 34998 69777 34997 69778 34998 69778 34999 69778 34999 69779 34998 69779 34984 69779 34999 69780 34984 69780 35000 69780 35000 69781 34984 69781 35001 69781 35000 69782 35001 69782 35002 69782 35002 69783 35001 69783 34988 69783 35002 69784 34988 69784 35003 69784 35003 69785 34988 69785 35004 69785 35003 69786 35004 69786 35015 69786 35015 69787 35004 69787 34990 69787 35015 69788 34990 69788 35005 69788 35005 69789 34990 69789 34977 69789 35005 69790 34977 69790 35006 69790 35017 69791 35016 69791 33803 69791 35007 69792 34968 69792 34977 69792 34977 69793 34968 69793 34970 69793 34977 69794 34970 69794 35006 69794 35006 69795 34970 69795 35008 69795 35006 69796 35008 69796 35009 69796 33803 69797 34992 69797 35017 69797 35017 69798 34992 69798 34995 69798 35017 69799 34995 69799 35010 69799 35010 69800 34995 69800 34997 69800 35010 69801 34997 69801 35019 69801 35019 69802 34997 69802 34999 69802 35019 69803 34999 69803 35011 69803 35011 69804 34999 69804 35000 69804 35011 69805 35000 69805 35020 69805 35020 69806 35000 69806 35002 69806 35020 69807 35002 69807 35012 69807 35012 69808 35002 69808 35003 69808 35012 69809 35003 69809 35013 69809 35013 69810 35003 69810 35015 69810 35013 69811 35015 69811 35014 69811 35014 69812 35015 69812 35005 69812 35014 69813 35005 69813 35022 69813 35022 69814 35005 69814 35006 69814 35022 69815 35006 69815 35023 69815 35023 69816 35006 69816 35009 69816 35023 69817 35009 69817 34972 69817 35018 69818 34607 69818 35016 69818 35016 69819 35017 69819 35018 69819 35018 69820 35017 69820 35010 69820 35018 69821 35010 69821 34601 69821 34601 69822 35010 69822 35019 69822 34601 69823 35019 69823 34602 69823 34602 69824 35019 69824 35011 69824 34602 69825 35011 69825 34578 69825 34578 69826 35011 69826 35020 69826 34578 69827 35020 69827 34579 69827 34579 69828 35020 69828 35012 69828 34579 69829 35012 69829 34580 69829 34580 69830 35012 69830 35013 69830 34580 69831 35013 69831 35021 69831 35021 69832 35013 69832 35014 69832 35021 69833 35014 69833 34616 69833 34616 69834 35014 69834 35022 69834 34616 69835 35022 69835 34617 69835 34617 69836 35022 69836 35023 69836 34617 69837 35023 69837 34618 69837 34618 69838 35023 69838 34972 69838 34618 69839 34972 69839 34619 69839 35066 69840 35048 69840 35042 69840 35042 69841 35048 69841 35376 69841 35042 69842 35376 69842 35377 69842 35024 69843 35025 69843 35026 69843 35032 69844 35027 69844 35036 69844 35026 69845 35028 69845 35958 69845 35958 69846 35028 69846 35385 69846 35958 69847 35385 69847 35389 69847 35025 69848 35335 69848 35026 69848 35026 69849 35335 69849 35336 69849 35026 69850 35336 69850 35028 69850 35029 69851 35033 69851 35034 69851 35953 69852 35030 69852 35291 69852 35291 69853 35030 69853 35971 69853 35291 69854 35971 69854 35052 69854 35963 69855 35039 69855 35036 69855 35036 69856 35039 69856 35031 69856 35036 69857 35031 69857 35032 69857 35381 69858 35383 69858 35047 69858 35033 69859 35331 69859 35034 69859 35034 69860 35331 69860 35035 69860 35034 69861 35035 69861 35026 69861 35026 69862 35035 69862 35332 69862 35026 69863 35332 69863 35024 69863 35027 69864 35226 69864 35036 69864 35036 69865 35226 69865 35037 69865 35036 69866 35037 69866 35966 69866 35277 69867 35279 69867 35963 69867 35963 69868 35279 69868 35038 69868 35963 69869 35038 69869 35039 69869 36000 69870 35997 69870 35286 69870 35286 69871 35997 69871 35040 69871 35286 69872 35040 69872 35041 69872 35377 69873 35043 69873 35042 69873 35042 69874 35043 69874 35380 69874 35042 69875 35380 69875 35047 69875 35047 69876 35380 69876 35044 69876 35047 69877 35044 69877 35381 69877 35040 69878 35045 69878 35041 69878 35041 69879 35045 69879 35992 69879 35041 69880 35992 69880 35384 69880 35384 69881 35992 69881 35047 69881 35384 69882 35047 69882 35046 69882 35046 69883 35047 69883 35383 69883 35049 69884 36332 69884 35048 69884 35048 69885 36332 69885 35061 69885 35953 69886 35291 69886 35034 69886 35034 69887 35291 69887 35330 69887 35034 69888 35330 69888 35029 69888 36328 69889 36330 69889 35048 69889 35048 69890 36330 69890 36331 69890 35048 69891 36331 69891 35049 69891 35037 69892 35229 69892 35966 69892 35966 69893 35229 69893 35230 69893 35966 69894 35230 69894 35050 69894 35971 69895 35969 69895 35052 69895 35052 69896 35969 69896 35051 69896 35052 69897 35051 69897 35053 69897 35053 69898 35051 69898 35966 69898 35053 69899 35966 69899 35233 69899 35233 69900 35966 69900 35050 69900 36317 69901 36005 69901 35055 69901 35055 69902 36005 69902 35054 69902 35055 69903 35054 69903 35056 69903 35069 69904 35057 69904 35058 69904 35059 69905 36325 69905 35048 69905 35048 69906 36325 69906 36327 69906 35048 69907 36327 69907 36328 69907 35065 69908 35986 69908 36319 69908 36319 69909 35986 69909 36005 69909 36319 69910 36005 69910 35060 69910 35060 69911 36005 69911 36317 69911 36307 69912 36309 69912 35277 69912 35070 69913 35077 69913 35078 69913 35389 69914 35048 69914 35958 69914 35958 69915 35048 69915 35061 69915 35958 69916 35061 69916 35960 69916 35960 69917 35061 69917 35062 69917 35960 69918 35062 69918 35063 69918 35063 69919 35062 69919 36335 69919 35063 69920 36335 69920 35064 69920 36000 69921 35286 69921 35069 69921 35069 69922 35286 69922 35270 69922 35069 69923 35270 69923 35057 69923 35071 69924 35066 69924 35065 69924 35065 69925 35066 69925 35987 69925 35065 69926 35987 69926 35986 69926 35067 69927 35068 69927 35963 69927 35963 69928 35068 69928 35073 69928 35058 69929 35273 69929 35069 69929 35069 69930 35273 69930 35274 69930 35069 69931 35274 69931 35078 69931 35078 69932 35274 69932 35275 69932 35078 69933 35275 69933 35070 69933 36309 69934 36310 69934 35277 69934 35277 69935 36310 69935 36312 69935 35277 69936 36312 69936 35079 69936 35064 69937 36337 69937 35063 69937 35063 69938 36337 69938 36339 69938 35063 69939 36339 69939 35067 69939 35067 69940 36339 69940 36302 69940 35067 69941 36302 69941 35068 69941 35071 69942 36320 69942 35066 69942 35066 69943 36320 69943 35072 69943 35066 69944 35072 69944 35048 69944 35048 69945 35072 69945 36323 69945 35048 69946 36323 69946 35059 69946 35073 69947 35074 69947 35963 69947 35963 69948 35074 69948 35075 69948 35963 69949 35075 69949 35277 69949 35277 69950 35075 69950 35076 69950 35277 69951 35076 69951 36307 69951 35077 69952 35277 69952 35078 69952 35078 69953 35277 69953 35079 69953 35078 69954 35079 69954 35054 69954 35054 69955 35079 69955 36315 69955 35054 69956 36315 69956 35056 69956 35093 69957 35893 69957 35472 69957 35472 69958 35893 69958 35892 69958 35892 69959 35891 69959 35472 69959 35472 69960 35891 69960 35923 69960 35472 69961 35923 69961 35095 69961 35095 69962 35923 69962 35080 69962 35095 69963 35080 69963 35921 69963 35081 69964 35097 69964 35409 69964 35409 69965 35097 69965 35082 69965 35583 69966 35111 69966 35083 69966 35083 69967 35111 69967 35897 69967 35083 69968 35897 69968 35084 69968 35084 69969 35897 69969 35608 69969 35608 69970 35897 69970 35085 69970 35085 69971 35897 69971 35086 69971 35085 69972 35086 69972 35087 69972 35087 69973 35086 69973 35555 69973 35555 69974 35086 69974 35896 69974 35555 69975 35896 69975 35088 69975 35094 69976 35526 69976 35089 69976 35089 69977 35526 69977 35090 69977 35089 69978 35090 69978 35091 69978 35091 69979 35090 69979 35503 69979 35091 69980 35503 69980 35092 69980 35092 69981 35503 69981 35502 69981 35092 69982 35502 69982 35101 69982 35093 69983 35472 69983 35089 69983 35089 69984 35472 69984 35532 69984 35089 69985 35532 69985 35094 69985 35921 69986 35920 69986 35095 69986 35095 69987 35920 69987 35919 69987 35095 69988 35919 69988 35402 69988 35402 69989 35919 69989 35917 69989 35402 69990 35917 69990 35435 69990 35098 69991 35446 69991 35917 69991 35917 69992 35446 69992 35448 69992 35917 69993 35448 69993 35435 69993 35081 69994 35096 69994 35097 69994 35097 69995 35096 69995 35099 69995 35097 69996 35099 69996 35098 69996 35098 69997 35099 69997 35454 69997 35098 69998 35454 69998 35446 69998 35896 69999 35100 69999 35088 69999 35088 70000 35100 70000 35895 70000 35088 70001 35895 70001 35468 70001 35468 70002 35895 70002 35092 70002 35468 70003 35092 70003 35486 70003 35486 70004 35092 70004 35101 70004 35105 70005 35630 70005 35106 70005 35106 70006 35630 70006 35102 70006 35106 70007 35102 70007 35913 70007 35913 70008 35102 70008 35621 70008 35913 70009 35621 70009 35915 70009 35915 70010 35621 70010 35620 70010 35915 70011 35620 70011 35103 70011 35103 70012 35620 70012 35537 70012 35103 70013 35537 70013 35082 70013 35082 70014 35537 70014 35104 70014 35082 70015 35104 70015 35409 70015 35105 70016 35106 70016 35107 70016 35107 70017 35106 70017 35911 70017 35107 70018 35911 70018 35108 70018 35115 70019 35109 70019 35623 70019 35623 70020 35109 70020 35110 70020 35110 70021 35906 70021 35623 70021 35623 70022 35906 70022 35905 70022 35623 70023 35905 70023 35113 70023 35113 70024 35905 70024 35904 70024 35113 70025 35904 70025 35903 70025 35583 70026 35584 70026 35111 70026 35111 70027 35584 70027 35112 70027 35111 70028 35112 70028 35900 70028 35900 70029 35112 70029 35556 70029 35900 70030 35556 70030 35114 70030 35114 70031 35556 70031 35113 70031 35114 70032 35113 70032 35901 70032 35901 70033 35113 70033 35903 70033 35623 70034 35678 70034 35115 70034 35115 70035 35678 70035 35679 70035 35115 70036 35679 70036 35911 70036 35911 70037 35679 70037 35671 70037 35911 70038 35671 70038 35108 70038 35184 70039 35116 70039 35117 70039 35117 70040 35116 70040 35309 70040 35117 70041 35309 70041 35118 70041 35118 70042 35309 70042 35308 70042 35118 70043 35308 70043 35119 70043 35119 70044 35308 70044 35120 70044 35119 70045 35120 70045 35121 70045 35121 70046 35120 70046 35122 70046 35121 70047 35122 70047 35465 70047 35465 70048 35122 70048 35123 70048 35465 70049 35123 70049 35460 70049 35460 70050 35123 70050 35124 70050 35460 70051 35124 70051 35125 70051 35125 70052 35124 70052 35126 70052 35125 70053 35126 70053 35127 70053 35127 70054 35126 70054 35128 70054 35127 70055 35128 70055 35130 70055 35129 70056 35439 70056 35301 70056 35301 70057 35439 70057 35130 70057 35301 70058 35130 70058 35304 70058 35304 70059 35130 70059 35128 70059 35285 70060 35427 70060 35296 70060 35296 70061 35427 70061 35131 70061 35296 70062 35131 70062 35295 70062 35295 70063 35131 70063 35132 70063 35295 70064 35132 70064 35133 70064 35133 70065 35132 70065 35134 70065 35133 70066 35134 70066 35293 70066 35293 70067 35134 70067 35438 70067 35293 70068 35438 70068 35299 70068 35299 70069 35438 70069 35135 70069 35299 70070 35135 70070 35129 70070 35129 70071 35135 70071 35440 70071 35129 70072 35440 70072 35439 70072 35427 70073 35285 70073 35536 70073 35536 70074 35285 70074 35284 70074 35536 70075 35284 70075 35137 70075 35137 70076 35284 70076 35136 70076 35137 70077 35136 70077 35138 70077 35138 70078 35136 70078 35202 70078 35138 70079 35202 70079 35518 70079 35518 70080 35202 70080 35139 70080 35518 70081 35139 70081 35519 70081 35519 70082 35139 70082 35201 70082 35519 70083 35201 70083 35515 70083 35515 70084 35201 70084 35199 70084 35515 70085 35199 70085 35516 70085 35516 70086 35199 70086 35197 70086 35516 70087 35197 70087 35467 70087 35467 70088 35197 70088 35140 70088 35467 70089 35140 70089 35143 70089 35141 70090 35496 70090 35142 70090 35142 70091 35496 70091 35143 70091 35142 70092 35143 70092 35196 70092 35196 70093 35143 70093 35140 70093 35192 70094 35480 70094 35191 70094 35191 70095 35480 70095 35144 70095 35191 70096 35144 70096 35190 70096 35190 70097 35144 70097 35483 70097 35190 70098 35483 70098 35145 70098 35145 70099 35483 70099 35482 70099 35145 70100 35482 70100 35146 70100 35146 70101 35482 70101 35488 70101 35146 70102 35488 70102 35193 70102 35193 70103 35488 70103 35147 70103 35193 70104 35147 70104 35141 70104 35141 70105 35147 70105 35148 70105 35141 70106 35148 70106 35496 70106 35480 70107 35192 70107 35541 70107 35541 70108 35192 70108 35187 70108 35541 70109 35187 70109 35617 70109 35617 70110 35187 70110 35149 70110 35617 70111 35149 70111 35609 70111 35609 70112 35149 70112 35245 70112 35609 70113 35245 70113 35150 70113 35150 70114 35245 70114 35244 70114 35150 70115 35244 70115 35602 70115 35602 70116 35244 70116 35151 70116 35602 70117 35151 70117 35552 70117 35552 70118 35151 70118 35152 70118 35552 70119 35152 70119 35153 70119 35153 70120 35152 70120 35242 70120 35153 70121 35242 70121 35595 70121 35595 70122 35242 70122 35154 70122 35595 70123 35154 70123 35589 70123 35155 70124 35163 70124 35156 70124 35156 70125 35163 70125 35589 70125 35156 70126 35589 70126 35157 70126 35157 70127 35589 70127 35154 70127 35290 70128 35158 70128 35159 70128 35159 70129 35158 70129 35160 70129 35159 70130 35160 70130 35239 70130 35239 70131 35160 70131 35565 70131 35239 70132 35565 70132 35161 70132 35161 70133 35565 70133 35564 70133 35161 70134 35564 70134 35237 70134 35237 70135 35564 70135 35572 70135 35237 70136 35572 70136 35240 70136 35240 70137 35572 70137 35162 70137 35240 70138 35162 70138 35155 70138 35155 70139 35162 70139 35576 70139 35155 70140 35576 70140 35163 70140 35158 70141 35290 70141 35164 70141 35164 70142 35290 70142 35165 70142 35164 70143 35165 70143 35166 70143 35166 70144 35165 70144 35167 70144 35166 70145 35167 70145 35168 70145 35168 70146 35167 70146 35353 70146 35168 70147 35353 70147 35169 70147 35169 70148 35353 70148 35170 70148 35169 70149 35170 70149 35665 70149 35665 70150 35170 70150 35352 70150 35665 70151 35352 70151 35171 70151 35171 70152 35352 70152 35351 70152 35171 70153 35351 70153 35172 70153 35172 70154 35351 70154 35350 70154 35172 70155 35350 70155 35173 70155 35173 70156 35350 70156 35348 70156 35173 70157 35348 70157 35174 70157 35343 70158 35181 70158 35345 70158 35345 70159 35181 70159 35174 70159 35345 70160 35174 70160 35347 70160 35347 70161 35174 70161 35348 70161 35183 70162 35182 70162 35341 70162 35341 70163 35182 70163 35619 70163 35341 70164 35619 70164 35175 70164 35175 70165 35619 70165 35638 70165 35175 70166 35638 70166 35339 70166 35339 70167 35638 70167 35645 70167 35339 70168 35645 70168 35176 70168 35176 70169 35645 70169 35177 70169 35176 70170 35177 70170 35178 70170 35178 70171 35177 70171 35179 70171 35178 70172 35179 70172 35343 70172 35343 70173 35179 70173 35180 70173 35343 70174 35180 70174 35181 70174 35182 70175 35183 70175 35184 70175 35184 70176 35183 70176 35116 70176 35039 70177 35038 70177 35278 70177 35039 70178 35278 70178 35215 70178 35215 70179 35278 70179 35269 70179 35215 70180 35269 70180 35205 70180 35205 70181 35269 70181 35185 70181 35205 70182 35185 70182 35186 70182 35186 70183 35185 70183 35187 70183 35186 70184 35187 70184 35192 70184 35039 70185 35215 70185 35188 70185 35215 70186 35205 70186 35206 70186 35205 70187 35186 70187 35207 70187 35146 70188 35208 70188 35145 70188 35145 70189 35208 70189 35189 70189 35145 70190 35189 70190 35190 70190 35190 70191 35189 70191 35207 70191 35190 70192 35207 70192 35191 70192 35191 70193 35207 70193 35186 70193 35191 70194 35186 70194 35192 70194 35146 70195 35193 70195 35208 70195 35208 70196 35193 70196 35141 70196 35208 70197 35141 70197 35194 70197 35194 70198 35141 70198 35142 70198 35194 70199 35142 70199 35195 70199 35195 70200 35142 70200 35196 70200 35195 70201 35196 70201 35210 70201 35202 70202 35203 70202 35213 70202 35196 70203 35140 70203 35210 70203 35210 70204 35140 70204 35197 70204 35210 70205 35197 70205 35198 70205 35198 70206 35197 70206 35199 70206 35198 70207 35199 70207 35200 70207 35200 70208 35199 70208 35201 70208 35200 70209 35201 70209 35213 70209 35213 70210 35201 70210 35139 70210 35213 70211 35139 70211 35202 70211 35202 70212 35136 70212 35203 70212 35203 70213 35136 70213 35284 70213 35203 70214 35284 70214 35204 70214 35205 70215 35207 70215 35206 70215 35206 70216 35207 70216 35189 70216 35206 70217 35189 70217 35209 70217 35209 70218 35189 70218 35208 70218 35209 70219 35208 70219 35216 70219 35216 70220 35208 70220 35194 70220 35216 70221 35194 70221 35217 70221 35217 70222 35194 70222 35195 70222 35217 70223 35195 70223 35211 70223 35211 70224 35195 70224 35210 70224 35211 70225 35210 70225 35218 70225 35218 70226 35210 70226 35198 70226 35218 70227 35198 70227 35219 70227 35219 70228 35198 70228 35200 70228 35219 70229 35200 70229 35212 70229 35212 70230 35200 70230 35213 70230 35212 70231 35213 70231 35214 70231 35214 70232 35213 70232 35203 70232 35214 70233 35203 70233 35222 70233 35222 70234 35203 70234 35204 70234 35222 70235 35204 70235 35282 70235 35215 70236 35206 70236 35188 70236 35188 70237 35206 70237 35209 70237 35188 70238 35209 70238 35223 70238 35223 70239 35209 70239 35216 70239 35223 70240 35216 70240 35224 70240 35224 70241 35216 70241 35217 70241 35224 70242 35217 70242 35225 70242 35225 70243 35217 70243 35211 70243 35225 70244 35211 70244 35227 70244 35227 70245 35211 70245 35218 70245 35227 70246 35218 70246 35228 70246 35228 70247 35218 70247 35219 70247 35228 70248 35219 70248 35220 70248 35220 70249 35219 70249 35212 70249 35220 70250 35212 70250 35231 70250 35231 70251 35212 70251 35214 70251 35231 70252 35214 70252 35232 70252 35232 70253 35214 70253 35222 70253 35232 70254 35222 70254 35221 70254 35221 70255 35222 70255 35282 70255 35221 70256 35282 70256 35281 70256 35039 70257 35188 70257 35031 70257 35031 70258 35188 70258 35223 70258 35031 70259 35223 70259 35032 70259 35032 70260 35223 70260 35224 70260 35032 70261 35224 70261 35027 70261 35027 70262 35224 70262 35225 70262 35027 70263 35225 70263 35226 70263 35226 70264 35225 70264 35227 70264 35226 70265 35227 70265 35037 70265 35037 70266 35227 70266 35228 70266 35037 70267 35228 70267 35229 70267 35229 70268 35228 70268 35220 70268 35229 70269 35220 70269 35230 70269 35230 70270 35220 70270 35231 70270 35230 70271 35231 70271 35050 70271 35050 70272 35231 70272 35232 70272 35050 70273 35232 70273 35233 70273 35233 70274 35232 70274 35221 70274 35233 70275 35221 70275 35053 70275 35053 70276 35221 70276 35281 70276 35053 70277 35281 70277 35052 70277 35286 70278 35235 70278 35234 70278 35235 70279 35236 70279 35257 70279 35236 70280 35289 70280 35247 70280 35237 70281 35249 70281 35161 70281 35161 70282 35249 70282 35238 70282 35161 70283 35238 70283 35239 70283 35239 70284 35238 70284 35247 70284 35239 70285 35247 70285 35159 70285 35159 70286 35247 70286 35289 70286 35159 70287 35289 70287 35290 70287 35237 70288 35240 70288 35249 70288 35249 70289 35240 70289 35155 70289 35249 70290 35155 70290 35241 70290 35241 70291 35155 70291 35156 70291 35241 70292 35156 70292 35251 70292 35251 70293 35156 70293 35157 70293 35251 70294 35157 70294 35253 70294 35245 70295 35246 70295 35256 70295 35157 70296 35154 70296 35253 70296 35253 70297 35154 70297 35242 70297 35253 70298 35242 70298 35254 70298 35254 70299 35242 70299 35152 70299 35254 70300 35152 70300 35243 70300 35243 70301 35152 70301 35151 70301 35243 70302 35151 70302 35256 70302 35256 70303 35151 70303 35244 70303 35256 70304 35244 70304 35245 70304 35245 70305 35149 70305 35246 70305 35246 70306 35149 70306 35187 70306 35246 70307 35187 70307 35185 70307 35236 70308 35247 70308 35257 70308 35257 70309 35247 70309 35238 70309 35257 70310 35238 70310 35258 70310 35258 70311 35238 70311 35249 70311 35258 70312 35249 70312 35248 70312 35248 70313 35249 70313 35241 70313 35248 70314 35241 70314 35250 70314 35250 70315 35241 70315 35251 70315 35250 70316 35251 70316 35260 70316 35260 70317 35251 70317 35253 70317 35260 70318 35253 70318 35252 70318 35252 70319 35253 70319 35254 70319 35252 70320 35254 70320 35263 70320 35263 70321 35254 70321 35243 70321 35263 70322 35243 70322 35255 70322 35255 70323 35243 70323 35256 70323 35255 70324 35256 70324 35266 70324 35266 70325 35256 70325 35246 70325 35266 70326 35246 70326 35267 70326 35267 70327 35246 70327 35185 70327 35267 70328 35185 70328 35269 70328 35235 70329 35257 70329 35234 70329 35234 70330 35257 70330 35258 70330 35234 70331 35258 70331 35271 70331 35271 70332 35258 70332 35248 70332 35271 70333 35248 70333 35259 70333 35259 70334 35248 70334 35250 70334 35259 70335 35250 70335 35272 70335 35272 70336 35250 70336 35260 70336 35272 70337 35260 70337 35261 70337 35261 70338 35260 70338 35252 70338 35261 70339 35252 70339 35262 70339 35262 70340 35252 70340 35263 70340 35262 70341 35263 70341 35276 70341 35276 70342 35263 70342 35255 70342 35276 70343 35255 70343 35264 70343 35264 70344 35255 70344 35266 70344 35264 70345 35266 70345 35265 70345 35265 70346 35266 70346 35267 70346 35265 70347 35267 70347 35268 70347 35268 70348 35267 70348 35269 70348 35268 70349 35269 70349 35278 70349 35286 70350 35234 70350 35270 70350 35270 70351 35234 70351 35271 70351 35270 70352 35271 70352 35057 70352 35057 70353 35271 70353 35259 70353 35057 70354 35259 70354 35058 70354 35058 70355 35259 70355 35272 70355 35058 70356 35272 70356 35273 70356 35273 70357 35272 70357 35261 70357 35273 70358 35261 70358 35274 70358 35274 70359 35261 70359 35262 70359 35274 70360 35262 70360 35275 70360 35275 70361 35262 70361 35276 70361 35275 70362 35276 70362 35070 70362 35070 70363 35276 70363 35264 70363 35070 70364 35264 70364 35077 70364 35077 70365 35264 70365 35265 70365 35077 70366 35265 70366 35277 70366 35277 70367 35265 70367 35268 70367 35277 70368 35268 70368 35279 70368 35279 70369 35268 70369 35278 70369 35279 70370 35278 70370 35038 70370 35291 70371 35052 70371 35281 70371 35291 70372 35281 70372 35280 70372 35280 70373 35281 70373 35282 70373 35280 70374 35282 70374 35283 70374 35283 70375 35282 70375 35204 70375 35283 70376 35204 70376 35297 70376 35297 70377 35204 70377 35284 70377 35297 70378 35284 70378 35285 70378 35286 70379 35041 70379 35375 70379 35286 70380 35375 70380 35235 70380 35235 70381 35375 70381 35287 70381 35235 70382 35287 70382 35236 70382 35236 70383 35287 70383 35288 70383 35236 70384 35288 70384 35289 70384 35289 70385 35288 70385 35165 70385 35289 70386 35165 70386 35290 70386 35291 70387 35280 70387 35292 70387 35280 70388 35283 70388 35312 70388 35283 70389 35297 70389 35311 70389 35293 70390 35298 70390 35133 70390 35133 70391 35298 70391 35294 70391 35133 70392 35294 70392 35295 70392 35295 70393 35294 70393 35311 70393 35295 70394 35311 70394 35296 70394 35296 70395 35311 70395 35297 70395 35296 70396 35297 70396 35285 70396 35293 70397 35299 70397 35298 70397 35298 70398 35299 70398 35129 70398 35298 70399 35129 70399 35300 70399 35300 70400 35129 70400 35301 70400 35300 70401 35301 70401 35302 70401 35302 70402 35301 70402 35304 70402 35302 70403 35304 70403 35303 70403 35120 70404 35307 70404 35306 70404 35304 70405 35128 70405 35303 70405 35303 70406 35128 70406 35126 70406 35303 70407 35126 70407 35315 70407 35315 70408 35126 70408 35124 70408 35315 70409 35124 70409 35305 70409 35305 70410 35124 70410 35123 70410 35305 70411 35123 70411 35306 70411 35306 70412 35123 70412 35122 70412 35306 70413 35122 70413 35120 70413 35120 70414 35308 70414 35307 70414 35307 70415 35308 70415 35309 70415 35307 70416 35309 70416 35310 70416 35283 70417 35311 70417 35312 70417 35312 70418 35311 70418 35294 70418 35312 70419 35294 70419 35318 70419 35318 70420 35294 70420 35298 70420 35318 70421 35298 70421 35319 70421 35319 70422 35298 70422 35300 70422 35319 70423 35300 70423 35321 70423 35321 70424 35300 70424 35302 70424 35321 70425 35302 70425 35313 70425 35313 70426 35302 70426 35303 70426 35313 70427 35303 70427 35314 70427 35314 70428 35303 70428 35315 70428 35314 70429 35315 70429 35324 70429 35324 70430 35315 70430 35305 70430 35324 70431 35305 70431 35326 70431 35326 70432 35305 70432 35306 70432 35326 70433 35306 70433 35328 70433 35328 70434 35306 70434 35307 70434 35328 70435 35307 70435 35316 70435 35316 70436 35307 70436 35310 70436 35316 70437 35310 70437 35387 70437 35280 70438 35312 70438 35292 70438 35292 70439 35312 70439 35318 70439 35292 70440 35318 70440 35317 70440 35317 70441 35318 70441 35319 70441 35317 70442 35319 70442 35320 70442 35320 70443 35319 70443 35321 70443 35320 70444 35321 70444 35322 70444 35322 70445 35321 70445 35313 70445 35322 70446 35313 70446 35323 70446 35323 70447 35313 70447 35314 70447 35323 70448 35314 70448 35325 70448 35325 70449 35314 70449 35324 70449 35325 70450 35324 70450 35333 70450 35333 70451 35324 70451 35326 70451 35333 70452 35326 70452 35334 70452 35334 70453 35326 70453 35328 70453 35334 70454 35328 70454 35327 70454 35327 70455 35328 70455 35316 70455 35327 70456 35316 70456 35329 70456 35329 70457 35316 70457 35387 70457 35329 70458 35387 70458 35386 70458 35291 70459 35292 70459 35330 70459 35330 70460 35292 70460 35317 70460 35330 70461 35317 70461 35029 70461 35029 70462 35317 70462 35320 70462 35029 70463 35320 70463 35033 70463 35033 70464 35320 70464 35322 70464 35033 70465 35322 70465 35331 70465 35331 70466 35322 70466 35323 70466 35331 70467 35323 70467 35035 70467 35035 70468 35323 70468 35325 70468 35035 70469 35325 70469 35332 70469 35332 70470 35325 70470 35333 70470 35332 70471 35333 70471 35024 70471 35024 70472 35333 70472 35334 70472 35024 70473 35334 70473 35025 70473 35025 70474 35334 70474 35327 70474 35025 70475 35327 70475 35335 70475 35335 70476 35327 70476 35329 70476 35335 70477 35329 70477 35336 70477 35336 70478 35329 70478 35386 70478 35336 70479 35386 70479 35028 70479 35389 70480 35337 70480 35364 70480 35337 70481 35391 70481 35338 70481 35391 70482 35393 70482 35342 70482 35176 70483 35357 70483 35339 70483 35339 70484 35357 70484 35340 70484 35339 70485 35340 70485 35175 70485 35175 70486 35340 70486 35342 70486 35175 70487 35342 70487 35341 70487 35341 70488 35342 70488 35393 70488 35341 70489 35393 70489 35183 70489 35176 70490 35178 70490 35357 70490 35357 70491 35178 70491 35343 70491 35357 70492 35343 70492 35358 70492 35358 70493 35343 70493 35345 70493 35358 70494 35345 70494 35344 70494 35344 70495 35345 70495 35347 70495 35344 70496 35347 70496 35346 70496 35353 70497 35354 70497 35362 70497 35347 70498 35348 70498 35346 70498 35346 70499 35348 70499 35350 70499 35346 70500 35350 70500 35349 70500 35349 70501 35350 70501 35351 70501 35349 70502 35351 70502 35360 70502 35360 70503 35351 70503 35352 70503 35360 70504 35352 70504 35362 70504 35362 70505 35352 70505 35170 70505 35362 70506 35170 70506 35353 70506 35353 70507 35167 70507 35354 70507 35354 70508 35167 70508 35165 70508 35354 70509 35165 70509 35288 70509 35391 70510 35342 70510 35338 70510 35338 70511 35342 70511 35340 70511 35338 70512 35340 70512 35355 70512 35355 70513 35340 70513 35357 70513 35355 70514 35357 70514 35356 70514 35356 70515 35357 70515 35358 70515 35356 70516 35358 70516 35359 70516 35359 70517 35358 70517 35344 70517 35359 70518 35344 70518 35368 70518 35368 70519 35344 70519 35346 70519 35368 70520 35346 70520 35369 70520 35369 70521 35346 70521 35349 70521 35369 70522 35349 70522 35370 70522 35370 70523 35349 70523 35360 70523 35370 70524 35360 70524 35361 70524 35361 70525 35360 70525 35362 70525 35361 70526 35362 70526 35363 70526 35363 70527 35362 70527 35354 70527 35363 70528 35354 70528 35373 70528 35373 70529 35354 70529 35288 70529 35373 70530 35288 70530 35287 70530 35337 70531 35338 70531 35364 70531 35364 70532 35338 70532 35355 70532 35364 70533 35355 70533 35365 70533 35365 70534 35355 70534 35356 70534 35365 70535 35356 70535 35366 70535 35366 70536 35356 70536 35359 70536 35366 70537 35359 70537 35367 70537 35367 70538 35359 70538 35368 70538 35367 70539 35368 70539 35378 70539 35378 70540 35368 70540 35369 70540 35378 70541 35369 70541 35379 70541 35379 70542 35369 70542 35370 70542 35379 70543 35370 70543 35382 70543 35382 70544 35370 70544 35361 70544 35382 70545 35361 70545 35371 70545 35371 70546 35361 70546 35363 70546 35371 70547 35363 70547 35372 70547 35372 70548 35363 70548 35373 70548 35372 70549 35373 70549 35374 70549 35374 70550 35373 70550 35287 70550 35374 70551 35287 70551 35375 70551 35389 70552 35364 70552 35048 70552 35048 70553 35364 70553 35365 70553 35048 70554 35365 70554 35376 70554 35376 70555 35365 70555 35366 70555 35376 70556 35366 70556 35377 70556 35377 70557 35366 70557 35367 70557 35377 70558 35367 70558 35043 70558 35043 70559 35367 70559 35378 70559 35043 70560 35378 70560 35380 70560 35380 70561 35378 70561 35379 70561 35380 70562 35379 70562 35044 70562 35044 70563 35379 70563 35382 70563 35044 70564 35382 70564 35381 70564 35381 70565 35382 70565 35371 70565 35381 70566 35371 70566 35383 70566 35383 70567 35371 70567 35372 70567 35383 70568 35372 70568 35046 70568 35046 70569 35372 70569 35374 70569 35046 70570 35374 70570 35384 70570 35384 70571 35374 70571 35375 70571 35384 70572 35375 70572 35041 70572 35385 70573 35028 70573 35386 70573 35385 70574 35386 70574 35390 70574 35390 70575 35386 70575 35387 70575 35390 70576 35387 70576 35392 70576 35392 70577 35387 70577 35310 70577 35392 70578 35310 70578 35388 70578 35388 70579 35310 70579 35309 70579 35388 70580 35309 70580 35116 70580 35389 70581 35385 70581 35390 70581 35389 70582 35390 70582 35337 70582 35337 70583 35390 70583 35392 70583 35337 70584 35392 70584 35391 70584 35391 70585 35392 70585 35388 70585 35391 70586 35388 70586 35393 70586 35393 70587 35388 70587 35116 70587 35393 70588 35116 70588 35183 70588 35472 70589 35095 70589 35473 70589 35473 70590 35095 70590 35401 70590 35473 70591 35401 70591 35394 70591 35394 70592 35401 70592 35403 70592 35394 70593 35403 70593 35474 70593 35474 70594 35403 70594 35414 70594 35474 70595 35414 70595 35395 70595 35395 70596 35414 70596 35413 70596 35395 70597 35413 70597 35396 70597 35396 70598 35413 70598 35397 70598 35396 70599 35397 70599 35534 70599 35534 70600 35397 70600 35412 70600 35534 70601 35412 70601 35398 70601 35398 70602 35412 70602 35399 70602 35398 70603 35399 70603 35536 70603 35536 70604 35399 70604 35427 70604 35465 70605 35460 70605 35400 70605 35125 70606 35127 70606 35459 70606 35440 70607 35135 70607 35442 70607 35132 70608 35131 70608 35411 70608 35410 70609 35409 70609 35104 70609 35095 70610 35402 70610 35401 70610 35401 70611 35402 70611 35436 70611 35401 70612 35436 70612 35403 70612 35403 70613 35436 70613 35433 70613 35096 70614 35081 70614 35464 70614 35464 70615 35081 70615 35404 70615 35464 70616 35404 70616 35462 70616 35462 70617 35404 70617 35405 70617 35462 70618 35405 70618 35407 70618 35407 70619 35405 70619 35406 70619 35407 70620 35406 70620 35408 70620 35408 70621 35406 70621 35423 70621 35408 70622 35423 70622 35400 70622 35081 70623 35409 70623 35404 70623 35404 70624 35409 70624 35410 70624 35404 70625 35410 70625 35405 70625 35405 70626 35410 70626 35418 70626 35405 70627 35418 70627 35406 70627 35406 70628 35418 70628 35419 70628 35406 70629 35419 70629 35423 70629 35423 70630 35419 70630 35425 70630 35411 70631 35412 70631 35430 70631 35430 70632 35412 70632 35397 70632 35430 70633 35397 70633 35431 70633 35431 70634 35397 70634 35413 70634 35431 70635 35413 70635 35433 70635 35433 70636 35413 70636 35414 70636 35433 70637 35414 70637 35403 70637 35435 70638 35448 70638 35434 70638 35434 70639 35448 70639 35447 70639 35434 70640 35447 70640 35432 70640 35432 70641 35447 70641 35444 70641 35432 70642 35444 70642 35429 70642 35429 70643 35444 70643 35415 70643 35429 70644 35415 70644 35428 70644 35428 70645 35415 70645 35416 70645 35428 70646 35416 70646 35437 70646 35437 70647 35416 70647 35442 70647 35104 70648 35417 70648 35410 70648 35410 70649 35417 70649 35539 70649 35410 70650 35539 70650 35418 70650 35418 70651 35539 70651 35420 70651 35418 70652 35420 70652 35419 70652 35419 70653 35420 70653 35421 70653 35419 70654 35421 70654 35425 70654 35425 70655 35421 70655 35422 70655 35425 70656 35422 70656 35426 70656 35400 70657 35423 70657 35424 70657 35424 70658 35423 70658 35425 70658 35424 70659 35425 70659 35466 70659 35466 70660 35425 70660 35426 70660 35466 70661 35426 70661 35540 70661 35131 70662 35427 70662 35411 70662 35411 70663 35427 70663 35399 70663 35411 70664 35399 70664 35412 70664 35134 70665 35132 70665 35437 70665 35437 70666 35132 70666 35411 70666 35437 70667 35411 70667 35428 70667 35428 70668 35411 70668 35430 70668 35428 70669 35430 70669 35429 70669 35429 70670 35430 70670 35431 70670 35429 70671 35431 70671 35432 70671 35432 70672 35431 70672 35433 70672 35432 70673 35433 70673 35434 70673 35434 70674 35433 70674 35436 70674 35434 70675 35436 70675 35435 70675 35435 70676 35436 70676 35402 70676 35442 70677 35135 70677 35437 70677 35437 70678 35135 70678 35438 70678 35437 70679 35438 70679 35134 70679 35439 70680 35440 70680 35441 70680 35441 70681 35440 70681 35442 70681 35441 70682 35442 70682 35452 70682 35452 70683 35442 70683 35416 70683 35452 70684 35416 70684 35451 70684 35451 70685 35416 70685 35415 70685 35451 70686 35415 70686 35443 70686 35443 70687 35415 70687 35444 70687 35443 70688 35444 70688 35445 70688 35445 70689 35444 70689 35447 70689 35445 70690 35447 70690 35446 70690 35446 70691 35447 70691 35448 70691 35446 70692 35454 70692 35445 70692 35445 70693 35454 70693 35449 70693 35445 70694 35449 70694 35443 70694 35443 70695 35449 70695 35450 70695 35443 70696 35450 70696 35451 70696 35451 70697 35450 70697 35456 70697 35451 70698 35456 70698 35452 70698 35452 70699 35456 70699 35453 70699 35452 70700 35453 70700 35441 70700 35441 70701 35453 70701 35458 70701 35441 70702 35458 70702 35439 70702 35439 70703 35458 70703 35130 70703 35454 70704 35099 70704 35449 70704 35449 70705 35099 70705 35455 70705 35449 70706 35455 70706 35450 70706 35450 70707 35455 70707 35463 70707 35450 70708 35463 70708 35456 70708 35456 70709 35463 70709 35461 70709 35456 70710 35461 70710 35453 70710 35453 70711 35461 70711 35457 70711 35453 70712 35457 70712 35458 70712 35458 70713 35457 70713 35459 70713 35458 70714 35459 70714 35130 70714 35130 70715 35459 70715 35127 70715 35460 70716 35125 70716 35400 70716 35400 70717 35125 70717 35459 70717 35400 70718 35459 70718 35408 70718 35408 70719 35459 70719 35457 70719 35408 70720 35457 70720 35407 70720 35407 70721 35457 70721 35461 70721 35407 70722 35461 70722 35462 70722 35462 70723 35461 70723 35463 70723 35462 70724 35463 70724 35464 70724 35464 70725 35463 70725 35455 70725 35464 70726 35455 70726 35096 70726 35096 70727 35455 70727 35099 70727 35465 70728 35400 70728 35121 70728 35121 70729 35400 70729 35424 70729 35121 70730 35424 70730 35119 70730 35119 70731 35424 70731 35466 70731 35119 70732 35466 70732 35118 70732 35118 70733 35466 70733 35540 70733 35118 70734 35540 70734 35117 70734 35138 70735 35518 70735 35520 70735 35519 70736 35515 70736 35521 70736 35516 70737 35467 70737 35514 70737 35148 70738 35147 70738 35487 70738 35488 70739 35482 70739 35489 70739 35483 70740 35144 70740 35481 70740 35530 70741 35532 70741 35472 70741 35088 70742 35468 70742 35470 70742 35470 70743 35468 70743 35469 70743 35470 70744 35469 70744 35546 70744 35546 70745 35469 70745 35471 70745 35472 70746 35473 70746 35530 70746 35530 70747 35473 70747 35394 70747 35530 70748 35394 70748 35529 70748 35529 70749 35394 70749 35474 70749 35529 70750 35474 70750 35475 70750 35475 70751 35474 70751 35395 70751 35475 70752 35395 70752 35527 70752 35481 70753 35477 70753 35476 70753 35476 70754 35477 70754 35478 70754 35476 70755 35478 70755 35484 70755 35484 70756 35478 70756 35545 70756 35484 70757 35545 70757 35471 70757 35471 70758 35545 70758 35479 70758 35471 70759 35479 70759 35546 70759 35144 70760 35480 70760 35481 70760 35481 70761 35480 70761 35542 70761 35481 70762 35542 70762 35477 70762 35482 70763 35483 70763 35489 70763 35489 70764 35483 70764 35481 70764 35489 70765 35481 70765 35491 70765 35491 70766 35481 70766 35476 70766 35491 70767 35476 70767 35493 70767 35493 70768 35476 70768 35484 70768 35493 70769 35484 70769 35485 70769 35485 70770 35484 70770 35471 70770 35485 70771 35471 70771 35495 70771 35495 70772 35471 70772 35469 70772 35495 70773 35469 70773 35486 70773 35486 70774 35469 70774 35468 70774 35147 70775 35488 70775 35487 70775 35487 70776 35488 70776 35489 70776 35487 70777 35489 70777 35490 70777 35490 70778 35489 70778 35491 70778 35490 70779 35491 70779 35492 70779 35492 70780 35491 70780 35493 70780 35492 70781 35493 70781 35494 70781 35494 70782 35493 70782 35485 70782 35494 70783 35485 70783 35500 70783 35500 70784 35485 70784 35495 70784 35500 70785 35495 70785 35101 70785 35101 70786 35495 70786 35486 70786 35496 70787 35148 70787 35497 70787 35497 70788 35148 70788 35487 70788 35497 70789 35487 70789 35498 70789 35498 70790 35487 70790 35490 70790 35498 70791 35490 70791 35504 70791 35504 70792 35490 70792 35492 70792 35504 70793 35492 70793 35499 70793 35499 70794 35492 70794 35494 70794 35499 70795 35494 70795 35501 70795 35501 70796 35494 70796 35500 70796 35501 70797 35500 70797 35502 70797 35502 70798 35500 70798 35101 70798 35502 70799 35503 70799 35501 70799 35501 70800 35503 70800 35505 70800 35501 70801 35505 70801 35499 70801 35499 70802 35505 70802 35508 70802 35499 70803 35508 70803 35504 70803 35504 70804 35508 70804 35509 70804 35504 70805 35509 70805 35498 70805 35498 70806 35509 70806 35511 70806 35498 70807 35511 70807 35497 70807 35497 70808 35511 70808 35512 70808 35497 70809 35512 70809 35496 70809 35496 70810 35512 70810 35143 70810 35503 70811 35090 70811 35505 70811 35505 70812 35090 70812 35506 70812 35505 70813 35506 70813 35508 70813 35508 70814 35506 70814 35507 70814 35508 70815 35507 70815 35509 70815 35509 70816 35507 70816 35510 70816 35509 70817 35510 70817 35511 70817 35511 70818 35510 70818 35513 70818 35511 70819 35513 70819 35512 70819 35512 70820 35513 70820 35514 70820 35512 70821 35514 70821 35143 70821 35143 70822 35514 70822 35467 70822 35515 70823 35516 70823 35521 70823 35521 70824 35516 70824 35514 70824 35521 70825 35514 70825 35522 70825 35522 70826 35514 70826 35513 70826 35522 70827 35513 70827 35517 70827 35517 70828 35513 70828 35510 70828 35517 70829 35510 70829 35524 70829 35524 70830 35510 70830 35507 70830 35524 70831 35507 70831 35525 70831 35525 70832 35507 70832 35506 70832 35525 70833 35506 70833 35526 70833 35526 70834 35506 70834 35090 70834 35518 70835 35519 70835 35520 70835 35520 70836 35519 70836 35521 70836 35520 70837 35521 70837 35528 70837 35528 70838 35521 70838 35522 70838 35528 70839 35522 70839 35523 70839 35523 70840 35522 70840 35517 70840 35523 70841 35517 70841 35531 70841 35531 70842 35517 70842 35524 70842 35531 70843 35524 70843 35533 70843 35533 70844 35524 70844 35525 70844 35533 70845 35525 70845 35094 70845 35094 70846 35525 70846 35526 70846 35137 70847 35138 70847 35535 70847 35535 70848 35138 70848 35520 70848 35535 70849 35520 70849 35527 70849 35527 70850 35520 70850 35528 70850 35527 70851 35528 70851 35475 70851 35475 70852 35528 70852 35523 70852 35475 70853 35523 70853 35529 70853 35529 70854 35523 70854 35531 70854 35529 70855 35531 70855 35530 70855 35530 70856 35531 70856 35533 70856 35530 70857 35533 70857 35532 70857 35532 70858 35533 70858 35094 70858 35395 70859 35396 70859 35527 70859 35527 70860 35396 70860 35534 70860 35527 70861 35534 70861 35535 70861 35535 70862 35534 70862 35398 70862 35535 70863 35398 70863 35137 70863 35137 70864 35398 70864 35536 70864 35104 70865 35537 70865 35417 70865 35417 70866 35537 70866 35538 70866 35417 70867 35538 70867 35539 70867 35539 70868 35538 70868 35420 70868 35420 70869 35538 70869 35550 70869 35420 70870 35550 70870 35421 70870 35421 70871 35550 70871 35422 70871 35422 70872 35550 70872 35551 70872 35422 70873 35551 70873 35426 70873 35426 70874 35551 70874 35540 70874 35540 70875 35551 70875 35184 70875 35540 70876 35184 70876 35117 70876 35480 70877 35541 70877 35542 70877 35542 70878 35541 70878 35616 70878 35542 70879 35616 70879 35477 70879 35477 70880 35616 70880 35543 70880 35477 70881 35543 70881 35478 70881 35478 70882 35543 70882 35544 70882 35478 70883 35544 70883 35545 70883 35545 70884 35544 70884 35614 70884 35545 70885 35614 70885 35479 70885 35479 70886 35614 70886 35559 70886 35479 70887 35559 70887 35546 70887 35546 70888 35559 70888 35547 70888 35546 70889 35547 70889 35470 70889 35470 70890 35547 70890 35558 70890 35470 70891 35558 70891 35088 70891 35088 70892 35558 70892 35555 70892 35620 70893 35548 70893 35537 70893 35537 70894 35548 70894 35538 70894 35548 70895 35549 70895 35538 70895 35538 70896 35549 70896 35629 70896 35538 70897 35629 70897 35550 70897 35629 70898 35628 70898 35550 70898 35550 70899 35628 70899 35627 70899 35550 70900 35627 70900 35551 70900 35182 70901 35184 70901 35636 70901 35636 70902 35184 70902 35551 70902 35636 70903 35551 70903 35626 70903 35626 70904 35551 70904 35627 70904 35609 70905 35150 70905 35601 70905 35602 70906 35552 70906 35596 70906 35153 70907 35595 70907 35553 70907 35576 70908 35162 70908 35578 70908 35572 70909 35564 70909 35554 70909 35565 70910 35160 70910 35560 70910 35557 70911 35087 70911 35555 70911 35113 70912 35556 70912 35682 70912 35682 70913 35556 70913 35571 70913 35682 70914 35571 70914 35563 70914 35563 70915 35571 70915 35570 70915 35555 70916 35558 70916 35557 70916 35557 70917 35558 70917 35547 70917 35557 70918 35547 70918 35613 70918 35613 70919 35547 70919 35559 70919 35613 70920 35559 70920 35612 70920 35612 70921 35559 70921 35614 70921 35612 70922 35614 70922 35610 70922 35560 70923 35689 70923 35568 70923 35568 70924 35689 70924 35688 70924 35568 70925 35688 70925 35561 70925 35561 70926 35688 70926 35685 70926 35561 70927 35685 70927 35570 70927 35570 70928 35685 70928 35562 70928 35570 70929 35562 70929 35563 70929 35160 70930 35158 70930 35560 70930 35560 70931 35158 70931 35690 70931 35560 70932 35690 70932 35689 70932 35564 70933 35565 70933 35554 70933 35554 70934 35565 70934 35560 70934 35554 70935 35560 70935 35566 70935 35566 70936 35560 70936 35568 70936 35566 70937 35568 70937 35567 70937 35567 70938 35568 70938 35561 70938 35567 70939 35561 70939 35569 70939 35569 70940 35561 70940 35570 70940 35569 70941 35570 70941 35575 70941 35575 70942 35570 70942 35571 70942 35575 70943 35571 70943 35112 70943 35112 70944 35571 70944 35556 70944 35162 70945 35572 70945 35578 70945 35578 70946 35572 70946 35554 70946 35578 70947 35554 70947 35579 70947 35579 70948 35554 70948 35566 70948 35579 70949 35566 70949 35573 70949 35573 70950 35566 70950 35567 70950 35573 70951 35567 70951 35581 70951 35581 70952 35567 70952 35569 70952 35581 70953 35569 70953 35574 70953 35574 70954 35569 70954 35575 70954 35574 70955 35575 70955 35584 70955 35584 70956 35575 70956 35112 70956 35163 70957 35576 70957 35577 70957 35577 70958 35576 70958 35578 70958 35577 70959 35578 70959 35587 70959 35587 70960 35578 70960 35579 70960 35587 70961 35579 70961 35580 70961 35580 70962 35579 70962 35573 70962 35580 70963 35573 70963 35582 70963 35582 70964 35573 70964 35581 70964 35582 70965 35581 70965 35586 70965 35586 70966 35581 70966 35574 70966 35586 70967 35574 70967 35583 70967 35583 70968 35574 70968 35584 70968 35583 70969 35083 70969 35586 70969 35586 70970 35083 70970 35585 70970 35586 70971 35585 70971 35582 70971 35582 70972 35585 70972 35590 70972 35582 70973 35590 70973 35580 70973 35580 70974 35590 70974 35591 70974 35580 70975 35591 70975 35587 70975 35587 70976 35591 70976 35593 70976 35587 70977 35593 70977 35577 70977 35577 70978 35593 70978 35588 70978 35577 70979 35588 70979 35163 70979 35163 70980 35588 70980 35589 70980 35083 70981 35084 70981 35585 70981 35585 70982 35084 70982 35600 70982 35585 70983 35600 70983 35590 70983 35590 70984 35600 70984 35598 70984 35590 70985 35598 70985 35591 70985 35591 70986 35598 70986 35592 70986 35591 70987 35592 70987 35593 70987 35593 70988 35592 70988 35594 70988 35593 70989 35594 70989 35588 70989 35588 70990 35594 70990 35553 70990 35588 70991 35553 70991 35589 70991 35589 70992 35553 70992 35595 70992 35552 70993 35153 70993 35596 70993 35596 70994 35153 70994 35553 70994 35596 70995 35553 70995 35604 70995 35604 70996 35553 70996 35594 70996 35604 70997 35594 70997 35597 70997 35597 70998 35594 70998 35592 70998 35597 70999 35592 70999 35599 70999 35599 71000 35592 71000 35598 71000 35599 71001 35598 71001 35607 71001 35607 71002 35598 71002 35600 71002 35607 71003 35600 71003 35608 71003 35608 71004 35600 71004 35084 71004 35150 71005 35602 71005 35601 71005 35601 71006 35602 71006 35596 71006 35601 71007 35596 71007 35603 71007 35603 71008 35596 71008 35604 71008 35603 71009 35604 71009 35611 71009 35611 71010 35604 71010 35597 71010 35611 71011 35597 71011 35605 71011 35605 71012 35597 71012 35599 71012 35605 71013 35599 71013 35606 71013 35606 71014 35599 71014 35607 71014 35606 71015 35607 71015 35085 71015 35085 71016 35607 71016 35608 71016 35617 71017 35609 71017 35615 71017 35615 71018 35609 71018 35601 71018 35615 71019 35601 71019 35610 71019 35610 71020 35601 71020 35603 71020 35610 71021 35603 71021 35612 71021 35612 71022 35603 71022 35611 71022 35612 71023 35611 71023 35613 71023 35613 71024 35611 71024 35605 71024 35613 71025 35605 71025 35557 71025 35557 71026 35605 71026 35606 71026 35557 71027 35606 71027 35087 71027 35087 71028 35606 71028 35085 71028 35614 71029 35544 71029 35610 71029 35610 71030 35544 71030 35543 71030 35610 71031 35543 71031 35615 71031 35615 71032 35543 71032 35616 71032 35615 71033 35616 71033 35617 71033 35617 71034 35616 71034 35541 71034 35168 71035 35169 71035 35618 71035 35665 71036 35171 71036 35666 71036 35172 71037 35173 71037 35659 71037 35180 71038 35179 71038 35644 71038 35638 71039 35619 71039 35635 71039 35677 71040 35678 71040 35623 71040 35620 71041 35621 71041 35548 71041 35548 71042 35621 71042 35622 71042 35548 71043 35622 71043 35549 71043 35549 71044 35622 71044 35643 71044 35623 71045 35683 71045 35677 71045 35677 71046 35683 71046 35624 71046 35677 71047 35624 71047 35676 71047 35676 71048 35624 71048 35684 71048 35676 71049 35684 71049 35625 71049 35625 71050 35684 71050 35680 71050 35625 71051 35680 71051 35673 71051 35635 71052 35626 71052 35639 71052 35639 71053 35626 71053 35627 71053 35639 71054 35627 71054 35641 71054 35641 71055 35627 71055 35628 71055 35641 71056 35628 71056 35643 71056 35643 71057 35628 71057 35629 71057 35643 71058 35629 71058 35549 71058 35102 71059 35630 71059 35631 71059 35631 71060 35630 71060 35649 71060 35631 71061 35649 71061 35642 71061 35642 71062 35649 71062 35632 71062 35642 71063 35632 71063 35640 71063 35640 71064 35632 71064 35633 71064 35640 71065 35633 71065 35634 71065 35634 71066 35633 71066 35647 71066 35634 71067 35647 71067 35637 71067 35637 71068 35647 71068 35644 71068 35619 71069 35182 71069 35635 71069 35635 71070 35182 71070 35636 71070 35635 71071 35636 71071 35626 71071 35645 71072 35638 71072 35637 71072 35637 71073 35638 71073 35635 71073 35637 71074 35635 71074 35634 71074 35634 71075 35635 71075 35639 71075 35634 71076 35639 71076 35640 71076 35640 71077 35639 71077 35641 71077 35640 71078 35641 71078 35642 71078 35642 71079 35641 71079 35643 71079 35642 71080 35643 71080 35631 71080 35631 71081 35643 71081 35622 71081 35631 71082 35622 71082 35102 71082 35102 71083 35622 71083 35621 71083 35644 71084 35179 71084 35637 71084 35637 71085 35179 71085 35177 71085 35637 71086 35177 71086 35645 71086 35181 71087 35180 71087 35655 71087 35655 71088 35180 71088 35644 71088 35655 71089 35644 71089 35646 71089 35646 71090 35644 71090 35647 71090 35646 71091 35647 71091 35652 71091 35652 71092 35647 71092 35633 71092 35652 71093 35633 71093 35651 71093 35651 71094 35633 71094 35632 71094 35651 71095 35632 71095 35648 71095 35648 71096 35632 71096 35649 71096 35648 71097 35649 71097 35105 71097 35105 71098 35649 71098 35630 71098 35105 71099 35107 71099 35648 71099 35648 71100 35107 71100 35650 71100 35648 71101 35650 71101 35651 71101 35651 71102 35650 71102 35656 71102 35651 71103 35656 71103 35652 71103 35652 71104 35656 71104 35653 71104 35652 71105 35653 71105 35646 71105 35646 71106 35653 71106 35654 71106 35646 71107 35654 71107 35655 71107 35655 71108 35654 71108 35658 71108 35655 71109 35658 71109 35181 71109 35181 71110 35658 71110 35174 71110 35107 71111 35108 71111 35650 71111 35650 71112 35108 71112 35664 71112 35650 71113 35664 71113 35656 71113 35656 71114 35664 71114 35663 71114 35656 71115 35663 71115 35653 71115 35653 71116 35663 71116 35657 71116 35653 71117 35657 71117 35654 71117 35654 71118 35657 71118 35660 71118 35654 71119 35660 71119 35658 71119 35658 71120 35660 71120 35659 71120 35658 71121 35659 71121 35174 71121 35174 71122 35659 71122 35173 71122 35171 71123 35172 71123 35666 71123 35666 71124 35172 71124 35659 71124 35666 71125 35659 71125 35661 71125 35661 71126 35659 71126 35660 71126 35661 71127 35660 71127 35667 71127 35667 71128 35660 71128 35657 71128 35667 71129 35657 71129 35662 71129 35662 71130 35657 71130 35663 71130 35662 71131 35663 71131 35669 71131 35669 71132 35663 71132 35664 71132 35669 71133 35664 71133 35671 71133 35671 71134 35664 71134 35108 71134 35169 71135 35665 71135 35618 71135 35618 71136 35665 71136 35666 71136 35618 71137 35666 71137 35674 71137 35674 71138 35666 71138 35661 71138 35674 71139 35661 71139 35675 71139 35675 71140 35661 71140 35667 71140 35675 71141 35667 71141 35668 71141 35668 71142 35667 71142 35662 71142 35668 71143 35662 71143 35670 71143 35670 71144 35662 71144 35669 71144 35670 71145 35669 71145 35679 71145 35679 71146 35669 71146 35671 71146 35166 71147 35168 71147 35672 71147 35672 71148 35168 71148 35618 71148 35672 71149 35618 71149 35673 71149 35673 71150 35618 71150 35674 71150 35673 71151 35674 71151 35625 71151 35625 71152 35674 71152 35675 71152 35625 71153 35675 71153 35676 71153 35676 71154 35675 71154 35668 71154 35676 71155 35668 71155 35677 71155 35677 71156 35668 71156 35670 71156 35677 71157 35670 71157 35678 71157 35678 71158 35670 71158 35679 71158 35680 71159 35686 71159 35673 71159 35673 71160 35686 71160 35687 71160 35673 71161 35687 71161 35672 71161 35672 71162 35687 71162 35681 71162 35672 71163 35681 71163 35166 71163 35166 71164 35681 71164 35164 71164 35623 71165 35113 71165 35683 71165 35683 71166 35113 71166 35682 71166 35683 71167 35682 71167 35624 71167 35624 71168 35682 71168 35563 71168 35624 71169 35563 71169 35684 71169 35684 71170 35563 71170 35562 71170 35684 71171 35562 71171 35680 71171 35680 71172 35562 71172 35685 71172 35680 71173 35685 71173 35686 71173 35686 71174 35685 71174 35688 71174 35686 71175 35688 71175 35687 71175 35687 71176 35688 71176 35689 71176 35687 71177 35689 71177 35681 71177 35681 71178 35689 71178 35690 71178 35681 71179 35690 71179 35164 71179 35164 71180 35690 71180 35158 71180 35789 71181 35731 71181 35751 71181 35693 71182 35790 71182 35751 71182 35751 71183 35790 71183 35788 71183 35751 71184 35788 71184 35789 71184 35694 71185 35691 71185 35753 71185 35753 71186 35691 71186 35692 71186 35753 71187 35692 71187 35693 71187 35693 71188 35692 71188 35792 71188 35693 71189 35792 71189 35790 71189 35694 71190 35753 71190 35795 71190 35795 71191 35753 71191 35696 71191 35795 71192 35696 71192 35695 71192 35695 71193 35696 71193 35697 71193 35697 71194 35696 71194 35699 71194 35697 71195 35699 71195 35796 71195 35703 71196 35698 71196 35699 71196 35699 71197 35698 71197 35700 71197 35699 71198 35700 71198 35796 71198 35704 71199 35701 71199 35747 71199 35747 71200 35701 71200 35799 71200 35747 71201 35799 71201 35703 71201 35703 71202 35799 71202 35702 71202 35703 71203 35702 71203 35698 71203 35704 71204 35747 71204 35800 71204 35800 71205 35747 71205 35706 71205 35800 71206 35706 71206 35705 71206 35705 71207 35706 71207 35801 71207 35801 71208 35706 71208 35737 71208 35801 71209 35737 71209 35707 71209 35748 71210 35709 71210 35737 71210 35737 71211 35709 71211 35802 71211 35737 71212 35802 71212 35707 71212 35807 71213 35806 71213 35749 71213 35749 71214 35806 71214 35708 71214 35749 71215 35708 71215 35748 71215 35748 71216 35708 71216 35804 71216 35748 71217 35804 71217 35709 71217 35807 71218 35749 71218 35710 71218 35710 71219 35749 71219 35744 71219 35710 71220 35744 71220 35711 71220 35711 71221 35744 71221 35712 71221 35712 71222 35744 71222 35713 71222 35712 71223 35713 71223 35762 71223 35715 71224 35764 71224 35713 71224 35713 71225 35764 71225 35714 71225 35713 71226 35714 71226 35762 71226 35716 71227 35717 71227 35715 71227 35715 71228 35717 71228 35765 71228 35715 71229 35765 71229 35764 71229 35771 71230 35769 71230 35742 71230 35742 71231 35769 71231 35768 71231 35742 71232 35768 71232 35716 71232 35716 71233 35768 71233 35767 71233 35716 71234 35767 71234 35717 71234 35771 71235 35742 71235 35772 71235 35772 71236 35742 71236 35718 71236 35772 71237 35718 71237 35773 71237 35721 71238 35719 71238 35718 71238 35718 71239 35719 71239 35775 71239 35718 71240 35775 71240 35773 71240 35720 71241 35777 71241 35721 71241 35721 71242 35777 71242 35776 71242 35721 71243 35776 71243 35719 71243 35779 71244 35723 71244 35722 71244 35722 71245 35723 71245 35724 71245 35722 71246 35724 71246 35720 71246 35720 71247 35724 71247 35725 71247 35720 71248 35725 71248 35777 71248 35779 71249 35722 71249 35726 71249 35726 71250 35722 71250 35727 71250 35726 71251 35727 71251 35781 71251 35730 71252 35783 71252 35727 71252 35727 71253 35783 71253 35782 71253 35727 71254 35782 71254 35781 71254 35728 71255 35729 71255 35730 71255 35730 71256 35729 71256 35784 71256 35730 71257 35784 71257 35783 71257 35789 71258 35786 71258 35731 71258 35731 71259 35786 71259 35732 71259 35731 71260 35732 71260 35728 71260 35728 71261 35732 71261 35733 71261 35728 71262 35733 71262 35729 71262 35718 71263 35734 71263 35721 71263 35721 71264 35734 71264 35735 71264 35721 71265 35735 71265 35720 71265 35747 71266 35736 71266 35706 71266 35706 71267 35736 71267 36199 71267 35706 71268 36199 71268 35737 71268 35713 71269 36210 71269 35715 71269 35715 71270 36210 71270 35738 71270 35715 71271 35738 71271 35716 71271 35738 71272 35739 71272 35716 71272 35716 71273 35739 71273 35740 71273 35716 71274 35740 71274 35742 71274 35742 71275 35740 71275 35741 71275 35742 71276 35741 71276 35718 71276 35718 71277 35741 71277 35743 71277 35718 71278 35743 71278 35734 71278 35749 71279 36205 71279 35744 71279 35744 71280 36205 71280 36206 71280 35744 71281 36206 71281 35713 71281 35713 71282 36206 71282 36209 71282 35713 71283 36209 71283 36210 71283 35735 71284 35745 71284 35720 71284 35720 71285 35745 71285 36213 71285 35720 71286 36213 71286 35722 71286 35722 71287 36213 71287 35746 71287 35722 71288 35746 71288 35727 71288 35699 71289 35755 71289 35703 71289 35703 71290 35755 71290 36196 71290 35703 71291 36196 71291 35747 71291 35747 71292 36196 71292 36198 71292 35747 71293 36198 71293 35736 71293 36199 71294 36200 71294 35737 71294 35737 71295 36200 71295 36201 71295 35737 71296 36201 71296 35748 71296 35748 71297 36201 71297 36203 71297 35748 71298 36203 71298 35749 71298 35749 71299 36203 71299 35750 71299 35749 71300 35750 71300 36205 71300 35751 71301 35761 71301 35693 71301 35693 71302 35761 71302 36192 71302 35693 71303 36192 71303 35753 71303 36192 71304 35752 71304 35753 71304 35753 71305 35752 71305 35754 71305 35753 71306 35754 71306 35696 71306 35696 71307 35754 71307 36194 71307 35696 71308 36194 71308 35699 71308 35699 71309 36194 71309 36195 71309 35699 71310 36195 71310 35755 71310 35746 71311 35756 71311 35727 71311 35727 71312 35756 71312 35757 71312 35727 71313 35757 71313 35730 71313 35730 71314 35757 71314 35758 71314 35730 71315 35758 71315 35728 71315 35758 71316 35759 71316 35728 71316 35728 71317 35759 71317 36217 71317 35728 71318 36217 71318 35731 71318 35731 71319 36217 71319 35760 71319 35731 71320 35760 71320 35751 71320 35751 71321 35760 71321 36191 71321 35751 71322 36191 71322 35761 71322 35712 71323 35762 71323 35763 71323 35762 71324 35714 71324 35763 71324 35763 71325 35714 71325 35764 71325 35763 71326 35764 71326 35844 71326 35844 71327 35764 71327 35765 71327 35844 71328 35765 71328 35766 71328 35766 71329 35765 71329 35717 71329 35766 71330 35717 71330 35842 71330 35842 71331 35717 71331 35767 71331 35767 71332 35768 71332 35842 71332 35842 71333 35768 71333 35769 71333 35842 71334 35769 71334 35770 71334 35770 71335 35769 71335 35771 71335 35770 71336 35771 71336 35840 71336 35840 71337 35771 71337 35772 71337 35840 71338 35772 71338 35774 71338 35774 71339 35772 71339 35773 71339 35773 71340 35775 71340 35774 71340 35774 71341 35775 71341 35719 71341 35774 71342 35719 71342 35838 71342 35838 71343 35719 71343 35776 71343 35838 71344 35776 71344 35837 71344 35837 71345 35776 71345 35777 71345 35837 71346 35777 71346 35778 71346 35778 71347 35777 71347 35725 71347 35725 71348 35724 71348 35778 71348 35778 71349 35724 71349 35723 71349 35778 71350 35723 71350 35835 71350 35835 71351 35723 71351 35779 71351 35835 71352 35779 71352 35780 71352 35780 71353 35779 71353 35726 71353 35780 71354 35726 71354 35834 71354 35834 71355 35726 71355 35781 71355 35781 71356 35782 71356 35834 71356 35834 71357 35782 71357 35783 71357 35834 71358 35783 71358 35833 71358 35833 71359 35783 71359 35784 71359 35833 71360 35784 71360 35785 71360 35732 71361 35829 71361 35733 71361 35733 71362 35829 71362 35785 71362 35733 71363 35785 71363 35729 71363 35729 71364 35785 71364 35784 71364 35786 71365 35826 71365 35732 71365 35732 71366 35826 71366 35828 71366 35732 71367 35828 71367 35829 71367 35790 71368 35787 71368 35788 71368 35788 71369 35787 71369 35826 71369 35788 71370 35826 71370 35789 71370 35789 71371 35826 71371 35786 71371 35792 71372 35793 71372 35790 71372 35790 71373 35793 71373 35791 71373 35790 71374 35791 71374 35787 71374 35792 71375 35692 71375 35793 71375 35793 71376 35692 71376 35691 71376 35793 71377 35691 71377 35824 71377 35824 71378 35691 71378 35694 71378 35824 71379 35694 71379 35794 71379 35794 71380 35694 71380 35795 71380 35794 71381 35795 71381 35820 71381 35820 71382 35795 71382 35695 71382 35695 71383 35697 71383 35820 71383 35820 71384 35697 71384 35796 71384 35820 71385 35796 71385 35819 71385 35819 71386 35796 71386 35700 71386 35819 71387 35700 71387 35797 71387 35797 71388 35700 71388 35698 71388 35797 71389 35698 71389 35798 71389 35798 71390 35698 71390 35702 71390 35702 71391 35799 71391 35798 71391 35798 71392 35799 71392 35701 71392 35798 71393 35701 71393 35816 71393 35816 71394 35701 71394 35704 71394 35816 71395 35704 71395 35814 71395 35814 71396 35704 71396 35800 71396 35814 71397 35800 71397 35813 71397 35813 71398 35800 71398 35705 71398 35705 71399 35801 71399 35813 71399 35813 71400 35801 71400 35707 71400 35813 71401 35707 71401 35810 71401 35810 71402 35707 71402 35802 71402 35810 71403 35802 71403 35803 71403 35803 71404 35802 71404 35709 71404 35803 71405 35709 71405 35805 71405 35805 71406 35709 71406 35804 71406 35804 71407 35708 71407 35805 71407 35805 71408 35708 71408 35806 71408 35805 71409 35806 71409 35808 71409 35808 71410 35806 71410 35807 71410 35808 71411 35807 71411 35809 71411 35763 71412 35845 71412 35712 71412 35712 71413 35845 71413 35848 71413 35712 71414 35848 71414 35711 71414 35711 71415 35848 71415 35809 71415 35711 71416 35809 71416 35710 71416 35710 71417 35809 71417 35807 71417 35848 71418 35850 71418 35809 71418 35809 71419 35850 71419 35852 71419 35809 71420 35852 71420 35808 71420 35808 71421 35852 71421 35854 71421 35808 71422 35854 71422 35805 71422 35805 71423 35854 71423 35855 71423 35805 71424 35855 71424 35803 71424 35803 71425 35855 71425 35811 71425 35803 71426 35811 71426 35810 71426 35810 71427 35811 71427 35812 71427 35810 71428 35812 71428 35813 71428 35813 71429 35812 71429 35815 71429 35813 71430 35815 71430 35814 71430 35814 71431 35815 71431 35860 71431 35814 71432 35860 71432 35816 71432 35816 71433 35860 71433 35817 71433 35816 71434 35817 71434 35798 71434 35798 71435 35817 71435 35818 71435 35798 71436 35818 71436 35797 71436 35797 71437 35818 71437 35865 71437 35797 71438 35865 71438 35819 71438 35819 71439 35865 71439 35866 71439 35819 71440 35866 71440 35820 71440 35820 71441 35866 71441 35821 71441 35820 71442 35821 71442 35794 71442 35794 71443 35821 71443 35822 71443 35794 71444 35822 71444 35824 71444 35824 71445 35822 71445 35823 71445 35824 71446 35823 71446 35793 71446 35793 71447 35823 71447 35868 71447 35793 71448 35868 71448 35791 71448 35791 71449 35868 71449 35825 71449 35791 71450 35825 71450 35787 71450 35787 71451 35825 71451 35827 71451 35787 71452 35827 71452 35826 71452 35826 71453 35827 71453 35872 71453 35826 71454 35872 71454 35828 71454 35828 71455 35872 71455 35873 71455 35828 71456 35873 71456 35829 71456 35829 71457 35873 71457 35830 71457 35829 71458 35830 71458 35785 71458 35785 71459 35830 71459 35831 71459 35785 71460 35831 71460 35833 71460 35833 71461 35831 71461 35832 71461 35833 71462 35832 71462 35834 71462 35834 71463 35832 71463 35875 71463 35834 71464 35875 71464 35780 71464 35780 71465 35875 71465 35876 71465 35780 71466 35876 71466 35835 71466 35835 71467 35876 71467 35877 71467 35835 71468 35877 71468 35778 71468 35778 71469 35877 71469 35836 71469 35778 71470 35836 71470 35837 71470 35837 71471 35836 71471 35880 71471 35837 71472 35880 71472 35838 71472 35838 71473 35880 71473 35883 71473 35838 71474 35883 71474 35774 71474 35774 71475 35883 71475 35839 71475 35774 71476 35839 71476 35840 71476 35840 71477 35839 71477 35841 71477 35840 71478 35841 71478 35770 71478 35770 71479 35841 71479 35884 71479 35770 71480 35884 71480 35842 71480 35842 71481 35884 71481 35843 71481 35842 71482 35843 71482 35766 71482 35766 71483 35843 71483 35886 71483 35766 71484 35886 71484 35844 71484 35844 71485 35886 71485 35887 71485 35844 71486 35887 71486 35763 71486 35763 71487 35887 71487 35846 71487 35763 71488 35846 71488 35845 71488 35845 71489 35846 71489 35847 71489 35845 71490 35847 71490 35848 71490 35848 71491 35847 71491 35850 71491 35847 71492 35849 71492 35850 71492 35850 71493 35849 71493 35851 71493 35850 71494 35851 71494 35852 71494 35852 71495 35851 71495 35853 71495 35852 71496 35853 71496 35854 71496 35854 71497 35853 71497 35894 71497 35854 71498 35894 71498 35855 71498 35855 71499 35894 71499 35856 71499 35855 71500 35856 71500 35811 71500 35811 71501 35856 71501 35857 71501 35811 71502 35857 71502 35812 71502 35812 71503 35857 71503 35858 71503 35812 71504 35858 71504 35815 71504 35815 71505 35858 71505 35859 71505 35815 71506 35859 71506 35860 71506 35860 71507 35859 71507 35861 71507 35860 71508 35861 71508 35817 71508 35817 71509 35861 71509 35862 71509 35817 71510 35862 71510 35818 71510 35818 71511 35862 71511 35863 71511 35818 71512 35863 71512 35865 71512 35865 71513 35863 71513 35864 71513 35865 71514 35864 71514 35866 71514 35866 71515 35864 71515 35898 71515 35866 71516 35898 71516 35821 71516 35821 71517 35898 71517 35899 71517 35821 71518 35899 71518 35822 71518 35822 71519 35899 71519 35867 71519 35822 71520 35867 71520 35823 71520 35823 71521 35867 71521 35902 71521 35823 71522 35902 71522 35868 71522 35868 71523 35902 71523 35869 71523 35868 71524 35869 71524 35825 71524 35825 71525 35869 71525 35870 71525 35825 71526 35870 71526 35827 71526 35827 71527 35870 71527 35871 71527 35827 71528 35871 71528 35872 71528 35872 71529 35871 71529 35907 71529 35872 71530 35907 71530 35873 71530 35873 71531 35907 71531 35908 71531 35873 71532 35908 71532 35830 71532 35830 71533 35908 71533 35909 71533 35830 71534 35909 71534 35831 71534 35831 71535 35909 71535 35910 71535 35831 71536 35910 71536 35832 71536 35832 71537 35910 71537 35874 71537 35832 71538 35874 71538 35875 71538 35875 71539 35874 71539 35912 71539 35875 71540 35912 71540 35876 71540 35876 71541 35912 71541 35914 71541 35876 71542 35914 71542 35877 71542 35877 71543 35914 71543 35878 71543 35877 71544 35878 71544 35836 71544 35836 71545 35878 71545 35879 71545 35836 71546 35879 71546 35880 71546 35880 71547 35879 71547 35881 71547 35880 71548 35881 71548 35883 71548 35883 71549 35881 71549 35882 71549 35883 71550 35882 71550 35839 71550 35839 71551 35882 71551 35916 71551 35839 71552 35916 71552 35841 71552 35841 71553 35916 71553 35918 71553 35841 71554 35918 71554 35884 71554 35884 71555 35918 71555 35885 71555 35884 71556 35885 71556 35843 71556 35843 71557 35885 71557 35922 71557 35843 71558 35922 71558 35886 71558 35886 71559 35922 71559 35888 71559 35886 71560 35888 71560 35887 71560 35887 71561 35888 71561 35889 71561 35887 71562 35889 71562 35846 71562 35846 71563 35889 71563 35890 71563 35846 71564 35890 71564 35847 71564 35847 71565 35890 71565 35849 71565 35890 71566 35891 71566 35849 71566 35849 71567 35891 71567 35892 71567 35849 71568 35892 71568 35851 71568 35851 71569 35892 71569 35893 71569 35851 71570 35893 71570 35853 71570 35853 71571 35893 71571 35093 71571 35853 71572 35093 71572 35894 71572 35894 71573 35093 71573 35089 71573 35894 71574 35089 71574 35856 71574 35856 71575 35089 71575 35091 71575 35856 71576 35091 71576 35857 71576 35857 71577 35091 71577 35092 71577 35857 71578 35092 71578 35858 71578 35858 71579 35092 71579 35895 71579 35858 71580 35895 71580 35859 71580 35859 71581 35895 71581 35100 71581 35859 71582 35100 71582 35861 71582 35861 71583 35100 71583 35896 71583 35861 71584 35896 71584 35862 71584 35862 71585 35896 71585 35086 71585 35862 71586 35086 71586 35863 71586 35863 71587 35086 71587 35897 71587 35863 71588 35897 71588 35864 71588 35864 71589 35897 71589 35111 71589 35864 71590 35111 71590 35898 71590 35898 71591 35111 71591 35900 71591 35898 71592 35900 71592 35899 71592 35899 71593 35900 71593 35114 71593 35899 71594 35114 71594 35867 71594 35867 71595 35114 71595 35901 71595 35867 71596 35901 71596 35902 71596 35902 71597 35901 71597 35903 71597 35902 71598 35903 71598 35869 71598 35869 71599 35903 71599 35904 71599 35869 71600 35904 71600 35870 71600 35870 71601 35904 71601 35905 71601 35870 71602 35905 71602 35871 71602 35871 71603 35905 71603 35906 71603 35871 71604 35906 71604 35907 71604 35907 71605 35906 71605 35110 71605 35907 71606 35110 71606 35908 71606 35908 71607 35110 71607 35109 71607 35908 71608 35109 71608 35909 71608 35909 71609 35109 71609 35115 71609 35909 71610 35115 71610 35910 71610 35910 71611 35115 71611 35911 71611 35910 71612 35911 71612 35874 71612 35874 71613 35911 71613 35106 71613 35874 71614 35106 71614 35912 71614 35912 71615 35106 71615 35913 71615 35912 71616 35913 71616 35914 71616 35914 71617 35913 71617 35915 71617 35914 71618 35915 71618 35878 71618 35878 71619 35915 71619 35103 71619 35878 71620 35103 71620 35879 71620 35879 71621 35103 71621 35082 71621 35879 71622 35082 71622 35881 71622 35881 71623 35082 71623 35097 71623 35881 71624 35097 71624 35882 71624 35882 71625 35097 71625 35098 71625 35882 71626 35098 71626 35916 71626 35916 71627 35098 71627 35917 71627 35916 71628 35917 71628 35918 71628 35918 71629 35917 71629 35919 71629 35918 71630 35919 71630 35885 71630 35885 71631 35919 71631 35920 71631 35885 71632 35920 71632 35922 71632 35922 71633 35920 71633 35921 71633 35922 71634 35921 71634 35888 71634 35888 71635 35921 71635 35080 71635 35888 71636 35080 71636 35889 71636 35889 71637 35080 71637 35923 71637 35889 71638 35923 71638 35890 71638 35890 71639 35923 71639 35891 71639 35951 71640 36298 71640 35924 71640 35924 71641 36298 71641 35925 71641 35924 71642 35925 71642 35926 71642 35926 71643 35925 71643 35927 71643 35926 71644 35927 71644 35928 71644 35928 71645 35927 71645 35929 71645 35928 71646 35929 71646 36400 71646 36400 71647 35929 71647 35930 71647 36400 71648 35930 71648 36403 71648 36403 71649 35930 71649 35932 71649 36403 71650 35932 71650 35931 71650 35931 71651 35932 71651 36294 71651 35931 71652 36294 71652 35933 71652 35933 71653 36294 71653 36291 71653 35933 71654 36291 71654 36405 71654 36405 71655 36291 71655 36290 71655 36405 71656 36290 71656 36406 71656 36406 71657 36290 71657 35934 71657 36406 71658 35934 71658 35935 71658 35935 71659 35934 71659 36288 71659 35935 71660 36288 71660 36409 71660 36409 71661 36288 71661 36287 71661 36409 71662 36287 71662 36410 71662 36410 71663 36287 71663 36284 71663 36410 71664 36284 71664 35936 71664 35936 71665 36284 71665 36283 71665 35936 71666 36283 71666 36411 71666 36411 71667 36283 71667 36280 71667 36411 71668 36280 71668 36412 71668 36412 71669 36280 71669 36279 71669 36412 71670 36279 71670 35937 71670 35937 71671 36279 71671 36278 71671 35937 71672 36278 71672 35938 71672 35938 71673 36278 71673 35939 71673 35938 71674 35939 71674 35940 71674 35940 71675 35939 71675 35941 71675 35940 71676 35941 71676 35942 71676 35942 71677 35941 71677 36276 71677 35942 71678 36276 71678 35944 71678 35944 71679 36276 71679 35943 71679 35944 71680 35943 71680 35945 71680 35945 71681 35943 71681 36275 71681 35945 71682 36275 71682 36378 71682 36378 71683 36275 71683 36274 71683 36378 71684 36274 71684 36379 71684 36379 71685 36274 71685 36273 71685 36379 71686 36273 71686 36382 71686 36382 71687 36273 71687 35946 71687 36382 71688 35946 71688 36383 71688 36383 71689 35946 71689 36272 71689 36383 71690 36272 71690 35947 71690 35947 71691 36272 71691 35948 71691 35947 71692 35948 71692 36386 71692 36386 71693 35948 71693 36270 71693 36386 71694 36270 71694 36388 71694 36388 71695 36270 71695 36269 71695 36388 71696 36269 71696 36389 71696 36389 71697 36269 71697 36268 71697 36389 71698 36268 71698 36391 71698 36391 71699 36268 71699 35949 71699 36391 71700 35949 71700 36392 71700 36392 71701 35949 71701 35950 71701 36392 71702 35950 71702 36394 71702 36394 71703 35950 71703 36266 71703 36394 71704 36266 71704 36395 71704 36395 71705 36266 71705 36264 71705 36395 71706 36264 71706 36396 71706 36396 71707 36264 71707 36301 71707 36396 71708 36301 71708 36398 71708 36398 71709 36301 71709 36300 71709 36398 71710 36300 71710 35951 71710 35951 71711 36300 71711 36298 71711 35971 71712 35030 71712 35952 71712 35953 71713 36181 71713 35030 71713 35030 71714 36181 71714 36178 71714 35030 71715 36178 71715 35952 71715 35034 71716 36182 71716 35953 71716 35953 71717 36182 71717 35954 71717 35953 71718 35954 71718 36181 71718 35026 71719 36185 71719 35034 71719 35034 71720 36185 71720 36183 71720 35034 71721 36183 71721 36182 71721 35958 71722 35955 71722 35026 71722 35026 71723 35955 71723 35956 71723 35026 71724 35956 71724 36185 71724 35960 71725 35957 71725 35958 71725 35958 71726 35957 71726 35959 71726 35958 71727 35959 71727 35955 71727 35063 71728 36188 71728 35960 71728 35960 71729 36188 71729 36187 71729 35960 71730 36187 71730 35957 71730 35067 71731 36166 71731 35063 71731 35063 71732 36166 71732 35961 71732 35063 71733 35961 71733 36188 71733 35963 71734 35962 71734 35067 71734 35067 71735 35962 71735 36168 71735 35067 71736 36168 71736 36166 71736 35036 71737 35965 71737 35963 71737 35963 71738 35965 71738 35964 71738 35963 71739 35964 71739 35962 71739 35966 71740 35968 71740 35036 71740 35036 71741 35968 71741 36169 71741 35036 71742 36169 71742 35965 71742 35051 71743 36172 71743 35966 71743 35966 71744 36172 71744 35967 71744 35966 71745 35967 71745 35968 71745 35969 71746 36174 71746 35051 71746 35051 71747 36174 71747 36173 71747 35051 71748 36173 71748 36172 71748 35952 71749 35970 71749 35971 71749 35971 71750 35970 71750 36177 71750 35971 71751 36177 71751 35969 71751 35969 71752 36177 71752 36175 71752 35969 71753 36175 71753 36174 71753 36105 71754 36107 71754 35972 71754 35976 71755 35973 71755 35972 71755 35972 71756 35973 71756 35974 71756 35972 71757 35974 71757 36105 71757 35977 71758 35975 71758 35972 71758 35972 71759 35975 71759 36135 71759 35972 71760 36135 71760 35976 71760 36128 71761 36130 71761 35972 71761 35972 71762 36130 71762 36131 71762 35972 71763 36131 71763 35977 71763 36124 71764 35978 71764 35972 71764 35972 71765 35978 71765 36125 71765 35972 71766 36125 71766 36128 71766 36120 71767 36121 71767 35972 71767 35972 71768 36121 71768 35979 71768 35972 71769 35979 71769 36124 71769 36113 71770 36116 71770 35972 71770 35972 71771 36116 71771 36117 71771 35972 71772 36117 71772 36120 71772 35980 71773 35981 71773 35972 71773 35972 71774 35981 71774 36112 71774 35972 71775 36112 71775 36113 71775 35982 71776 35983 71776 35972 71776 35972 71777 35983 71777 35984 71777 35972 71778 35984 71778 35980 71778 36107 71779 36108 71779 35972 71779 35972 71780 36108 71780 35985 71780 35972 71781 35985 71781 35982 71781 35986 71782 35987 71782 36007 71782 35066 71783 35988 71783 35987 71783 35987 71784 35988 71784 35989 71784 35987 71785 35989 71785 36007 71785 35042 71786 36098 71786 35066 71786 35066 71787 36098 71787 35990 71787 35066 71788 35990 71788 35988 71788 35047 71789 36099 71789 35042 71789 35042 71790 36099 71790 35991 71790 35042 71791 35991 71791 36098 71791 35992 71792 36101 71792 35047 71792 35047 71793 36101 71793 36100 71793 35047 71794 36100 71794 36099 71794 35045 71795 35993 71795 35992 71795 35992 71796 35993 71796 36103 71796 35992 71797 36103 71797 36101 71797 35040 71798 35994 71798 35045 71798 35045 71799 35994 71799 35995 71799 35045 71800 35995 71800 35993 71800 35997 71801 35998 71801 35040 71801 35040 71802 35998 71802 35996 71802 35040 71803 35996 71803 35994 71803 36000 71804 36001 71804 35997 71804 35997 71805 36001 71805 36084 71805 35997 71806 36084 71806 35998 71806 35069 71807 35999 71807 36000 71807 36000 71808 35999 71808 36086 71808 36000 71809 36086 71809 36001 71809 35078 71810 36004 71810 35069 71810 35069 71811 36004 71811 36002 71811 35069 71812 36002 71812 35999 71812 35054 71813 36003 71813 35078 71813 35078 71814 36003 71814 36088 71814 35078 71815 36088 71815 36004 71815 36005 71816 36006 71816 35054 71816 35054 71817 36006 71817 36090 71817 35054 71818 36090 71818 36003 71818 36007 71819 36093 71819 35986 71819 35986 71820 36093 71820 36008 71820 35986 71821 36008 71821 36005 71821 36005 71822 36008 71822 36009 71822 36005 71823 36009 71823 36006 71823 36010 71824 36022 71824 36020 71824 36046 71825 36047 71825 36020 71825 36020 71826 36047 71826 36050 71826 36020 71827 36050 71827 36010 71827 36041 71828 36011 71828 36020 71828 36020 71829 36011 71829 36044 71829 36020 71830 36044 71830 36046 71830 36039 71831 36040 71831 36020 71831 36020 71832 36040 71832 36012 71832 36020 71833 36012 71833 36041 71833 36015 71834 36037 71834 36020 71834 36020 71835 36037 71835 36013 71835 36020 71836 36013 71836 36039 71836 36033 71837 36035 71837 36020 71837 36020 71838 36035 71838 36014 71838 36020 71839 36014 71839 36015 71839 36016 71840 36031 71840 36020 71840 36020 71841 36031 71841 36032 71841 36020 71842 36032 71842 36033 71842 36028 71843 36029 71843 36020 71843 36020 71844 36029 71844 36017 71844 36020 71845 36017 71845 36016 71845 36021 71846 36025 71846 36020 71846 36020 71847 36025 71847 36018 71847 36020 71848 36018 71848 36028 71848 36022 71849 36019 71849 36020 71849 36020 71850 36019 71850 36023 71850 36020 71851 36023 71851 36021 71851 36010 71852 36052 71852 36022 71852 36022 71853 36052 71853 36053 71853 36022 71854 36053 71854 36019 71854 36019 71855 36053 71855 36055 71855 36019 71856 36055 71856 36023 71856 36023 71857 36055 71857 36024 71857 36023 71858 36024 71858 36021 71858 36021 71859 36024 71859 36026 71859 36021 71860 36026 71860 36025 71860 36025 71861 36026 71861 36027 71861 36025 71862 36027 71862 36018 71862 36018 71863 36027 71863 36059 71863 36018 71864 36059 71864 36028 71864 36028 71865 36059 71865 36060 71865 36028 71866 36060 71866 36029 71866 36029 71867 36060 71867 36063 71867 36029 71868 36063 71868 36017 71868 36017 71869 36063 71869 36064 71869 36017 71870 36064 71870 36016 71870 36016 71871 36064 71871 36030 71871 36016 71872 36030 71872 36031 71872 36031 71873 36030 71873 36066 71873 36031 71874 36066 71874 36032 71874 36032 71875 36066 71875 36067 71875 36032 71876 36067 71876 36033 71876 36033 71877 36067 71877 36034 71877 36033 71878 36034 71878 36035 71878 36035 71879 36034 71879 36069 71879 36035 71880 36069 71880 36014 71880 36014 71881 36069 71881 36036 71881 36014 71882 36036 71882 36015 71882 36015 71883 36036 71883 36070 71883 36015 71884 36070 71884 36037 71884 36037 71885 36070 71885 36072 71885 36037 71886 36072 71886 36013 71886 36013 71887 36072 71887 36038 71887 36013 71888 36038 71888 36039 71888 36039 71889 36038 71889 36074 71889 36039 71890 36074 71890 36040 71890 36040 71891 36074 71891 36076 71891 36040 71892 36076 71892 36012 71892 36012 71893 36076 71893 36042 71893 36012 71894 36042 71894 36041 71894 36041 71895 36042 71895 36043 71895 36041 71896 36043 71896 36011 71896 36011 71897 36043 71897 36079 71897 36011 71898 36079 71898 36044 71898 36044 71899 36079 71899 36045 71899 36044 71900 36045 71900 36046 71900 36046 71901 36045 71901 36048 71901 36046 71902 36048 71902 36047 71902 36047 71903 36048 71903 36049 71903 36047 71904 36049 71904 36050 71904 36050 71905 36049 71905 36051 71905 36050 71906 36051 71906 36010 71906 36010 71907 36051 71907 36052 71907 36051 71908 36082 71908 36052 71908 36052 71909 36082 71909 36085 71909 36052 71910 36085 71910 36053 71910 36053 71911 36085 71911 36054 71911 36053 71912 36054 71912 36055 71912 36055 71913 36054 71913 36087 71913 36055 71914 36087 71914 36024 71914 36024 71915 36087 71915 36056 71915 36024 71916 36056 71916 36026 71916 36026 71917 36056 71917 36057 71917 36026 71918 36057 71918 36027 71918 36027 71919 36057 71919 36058 71919 36027 71920 36058 71920 36059 71920 36059 71921 36058 71921 36089 71921 36059 71922 36089 71922 36060 71922 36060 71923 36089 71923 36061 71923 36060 71924 36061 71924 36063 71924 36063 71925 36061 71925 36062 71925 36063 71926 36062 71926 36064 71926 36064 71927 36062 71927 36091 71927 36064 71928 36091 71928 36030 71928 36030 71929 36091 71929 36065 71929 36030 71930 36065 71930 36066 71930 36066 71931 36065 71931 36092 71931 36066 71932 36092 71932 36067 71932 36067 71933 36092 71933 36068 71933 36067 71934 36068 71934 36034 71934 36034 71935 36068 71935 36094 71935 36034 71936 36094 71936 36069 71936 36069 71937 36094 71937 36095 71937 36069 71938 36095 71938 36036 71938 36036 71939 36095 71939 36071 71939 36036 71940 36071 71940 36070 71940 36070 71941 36071 71941 36096 71941 36070 71942 36096 71942 36072 71942 36072 71943 36096 71943 36097 71943 36072 71944 36097 71944 36038 71944 36038 71945 36097 71945 36073 71945 36038 71946 36073 71946 36074 71946 36074 71947 36073 71947 36075 71947 36074 71948 36075 71948 36076 71948 36076 71949 36075 71949 36077 71949 36076 71950 36077 71950 36042 71950 36042 71951 36077 71951 36102 71951 36042 71952 36102 71952 36043 71952 36043 71953 36102 71953 36078 71953 36043 71954 36078 71954 36079 71954 36079 71955 36078 71955 36080 71955 36079 71956 36080 71956 36045 71956 36045 71957 36080 71957 36104 71957 36045 71958 36104 71958 36048 71958 36048 71959 36104 71959 36081 71959 36048 71960 36081 71960 36049 71960 36049 71961 36081 71961 36083 71961 36049 71962 36083 71962 36051 71962 36051 71963 36083 71963 36082 71963 36083 71964 35998 71964 36082 71964 36082 71965 35998 71965 36084 71965 36082 71966 36084 71966 36085 71966 36085 71967 36084 71967 36001 71967 36085 71968 36001 71968 36054 71968 36054 71969 36001 71969 36086 71969 36054 71970 36086 71970 36087 71970 36087 71971 36086 71971 35999 71971 36087 71972 35999 71972 36056 71972 36056 71973 35999 71973 36002 71973 36056 71974 36002 71974 36057 71974 36057 71975 36002 71975 36004 71975 36057 71976 36004 71976 36058 71976 36058 71977 36004 71977 36088 71977 36058 71978 36088 71978 36089 71978 36089 71979 36088 71979 36003 71979 36089 71980 36003 71980 36061 71980 36061 71981 36003 71981 36090 71981 36061 71982 36090 71982 36062 71982 36062 71983 36090 71983 36006 71983 36062 71984 36006 71984 36091 71984 36091 71985 36006 71985 36009 71985 36091 71986 36009 71986 36065 71986 36065 71987 36009 71987 36008 71987 36065 71988 36008 71988 36092 71988 36092 71989 36008 71989 36093 71989 36092 71990 36093 71990 36068 71990 36068 71991 36093 71991 36007 71991 36068 71992 36007 71992 36094 71992 36094 71993 36007 71993 35989 71993 36094 71994 35989 71994 36095 71994 36095 71995 35989 71995 35988 71995 36095 71996 35988 71996 36071 71996 36071 71997 35988 71997 35990 71997 36071 71998 35990 71998 36096 71998 36096 71999 35990 71999 36098 71999 36096 72000 36098 72000 36097 72000 36097 72001 36098 72001 35991 72001 36097 72002 35991 72002 36073 72002 36073 72003 35991 72003 36099 72003 36073 72004 36099 72004 36075 72004 36075 72005 36099 72005 36100 72005 36075 72006 36100 72006 36077 72006 36077 72007 36100 72007 36101 72007 36077 72008 36101 72008 36102 72008 36102 72009 36101 72009 36103 72009 36102 72010 36103 72010 36078 72010 36078 72011 36103 72011 35993 72011 36078 72012 35993 72012 36080 72012 36080 72013 35993 72013 35995 72013 36080 72014 35995 72014 36104 72014 36104 72015 35995 72015 35994 72015 36104 72016 35994 72016 36081 72016 36081 72017 35994 72017 35996 72017 36081 72018 35996 72018 36083 72018 36083 72019 35996 72019 35998 72019 36105 72020 36137 72020 36107 72020 36107 72021 36137 72021 36106 72021 36107 72022 36106 72022 36108 72022 36108 72023 36106 72023 36139 72023 36108 72024 36139 72024 35985 72024 35985 72025 36139 72025 36141 72025 35985 72026 36141 72026 35982 72026 35982 72027 36141 72027 36109 72027 35982 72028 36109 72028 35983 72028 35983 72029 36109 72029 36143 72029 35983 72030 36143 72030 35984 72030 35984 72031 36143 72031 36110 72031 35984 72032 36110 72032 35980 72032 35980 72033 36110 72033 36111 72033 35980 72034 36111 72034 35981 72034 35981 72035 36111 72035 36146 72035 35981 72036 36146 72036 36112 72036 36112 72037 36146 72037 36114 72037 36112 72038 36114 72038 36113 72038 36113 72039 36114 72039 36115 72039 36113 72040 36115 72040 36116 72040 36116 72041 36115 72041 36149 72041 36116 72042 36149 72042 36117 72042 36117 72043 36149 72043 36118 72043 36117 72044 36118 72044 36120 72044 36120 72045 36118 72045 36119 72045 36120 72046 36119 72046 36121 72046 36121 72047 36119 72047 36122 72047 36121 72048 36122 72048 35979 72048 35979 72049 36122 72049 36123 72049 35979 72050 36123 72050 36124 72050 36124 72051 36123 72051 36153 72051 36124 72052 36153 72052 35978 72052 35978 72053 36153 72053 36126 72053 35978 72054 36126 72054 36125 72054 36125 72055 36126 72055 36127 72055 36125 72056 36127 72056 36128 72056 36128 72057 36127 72057 36156 72057 36128 72058 36156 72058 36130 72058 36130 72059 36156 72059 36129 72059 36130 72060 36129 72060 36131 72060 36131 72061 36129 72061 36132 72061 36131 72062 36132 72062 35977 72062 35977 72063 36132 72063 36133 72063 35977 72064 36133 72064 35975 72064 35975 72065 36133 72065 36134 72065 35975 72066 36134 72066 36135 72066 36135 72067 36134 72067 36161 72067 36135 72068 36161 72068 35976 72068 35976 72069 36161 72069 36162 72069 35976 72070 36162 72070 35973 72070 35973 72071 36162 72071 36164 72071 35973 72072 36164 72072 35974 72072 35974 72073 36164 72073 36136 72073 35974 72074 36136 72074 36105 72074 36105 72075 36136 72075 36137 72075 36136 72076 36165 72076 36137 72076 36137 72077 36165 72077 36167 72077 36137 72078 36167 72078 36106 72078 36106 72079 36167 72079 36138 72079 36106 72080 36138 72080 36139 72080 36139 72081 36138 72081 36140 72081 36139 72082 36140 72082 36141 72082 36141 72083 36140 72083 36142 72083 36141 72084 36142 72084 36109 72084 36109 72085 36142 72085 36170 72085 36109 72086 36170 72086 36143 72086 36143 72087 36170 72087 36144 72087 36143 72088 36144 72088 36110 72088 36110 72089 36144 72089 36171 72089 36110 72090 36171 72090 36111 72090 36111 72091 36171 72091 36145 72091 36111 72092 36145 72092 36146 72092 36146 72093 36145 72093 36147 72093 36146 72094 36147 72094 36114 72094 36114 72095 36147 72095 36148 72095 36114 72096 36148 72096 36115 72096 36115 72097 36148 72097 36176 72097 36115 72098 36176 72098 36149 72098 36149 72099 36176 72099 36150 72099 36149 72100 36150 72100 36118 72100 36118 72101 36150 72101 36151 72101 36118 72102 36151 72102 36119 72102 36119 72103 36151 72103 36179 72103 36119 72104 36179 72104 36122 72104 36122 72105 36179 72105 36180 72105 36122 72106 36180 72106 36123 72106 36123 72107 36180 72107 36152 72107 36123 72108 36152 72108 36153 72108 36153 72109 36152 72109 36154 72109 36153 72110 36154 72110 36126 72110 36126 72111 36154 72111 36184 72111 36126 72112 36184 72112 36127 72112 36127 72113 36184 72113 36155 72113 36127 72114 36155 72114 36156 72114 36156 72115 36155 72115 36157 72115 36156 72116 36157 72116 36129 72116 36129 72117 36157 72117 36158 72117 36129 72118 36158 72118 36132 72118 36132 72119 36158 72119 36186 72119 36132 72120 36186 72120 36133 72120 36133 72121 36186 72121 36159 72121 36133 72122 36159 72122 36134 72122 36134 72123 36159 72123 36160 72123 36134 72124 36160 72124 36161 72124 36161 72125 36160 72125 36163 72125 36161 72126 36163 72126 36162 72126 36162 72127 36163 72127 36189 72127 36162 72128 36189 72128 36164 72128 36164 72129 36189 72129 36190 72129 36164 72130 36190 72130 36136 72130 36136 72131 36190 72131 36165 72131 36190 72132 36166 72132 36165 72132 36165 72133 36166 72133 36168 72133 36165 72134 36168 72134 36167 72134 36167 72135 36168 72135 35962 72135 36167 72136 35962 72136 36138 72136 36138 72137 35962 72137 35964 72137 36138 72138 35964 72138 36140 72138 36140 72139 35964 72139 35965 72139 36140 72140 35965 72140 36142 72140 36142 72141 35965 72141 36169 72141 36142 72142 36169 72142 36170 72142 36170 72143 36169 72143 35968 72143 36170 72144 35968 72144 36144 72144 36144 72145 35968 72145 35967 72145 36144 72146 35967 72146 36171 72146 36171 72147 35967 72147 36172 72147 36171 72148 36172 72148 36145 72148 36145 72149 36172 72149 36173 72149 36145 72150 36173 72150 36147 72150 36147 72151 36173 72151 36174 72151 36147 72152 36174 72152 36148 72152 36148 72153 36174 72153 36175 72153 36148 72154 36175 72154 36176 72154 36176 72155 36175 72155 36177 72155 36176 72156 36177 72156 36150 72156 36150 72157 36177 72157 35970 72157 36150 72158 35970 72158 36151 72158 36151 72159 35970 72159 35952 72159 36151 72160 35952 72160 36179 72160 36179 72161 35952 72161 36178 72161 36179 72162 36178 72162 36180 72162 36180 72163 36178 72163 36181 72163 36180 72164 36181 72164 36152 72164 36152 72165 36181 72165 35954 72165 36152 72166 35954 72166 36154 72166 36154 72167 35954 72167 36182 72167 36154 72168 36182 72168 36184 72168 36184 72169 36182 72169 36183 72169 36184 72170 36183 72170 36155 72170 36155 72171 36183 72171 36185 72171 36155 72172 36185 72172 36157 72172 36157 72173 36185 72173 35956 72173 36157 72174 35956 72174 36158 72174 36158 72175 35956 72175 35955 72175 36158 72176 35955 72176 36186 72176 36186 72177 35955 72177 35959 72177 36186 72178 35959 72178 36159 72178 36159 72179 35959 72179 35957 72179 36159 72180 35957 72180 36160 72180 36160 72181 35957 72181 36187 72181 36160 72182 36187 72182 36163 72182 36163 72183 36187 72183 36188 72183 36163 72184 36188 72184 36189 72184 36189 72185 36188 72185 35961 72185 36189 72186 35961 72186 36190 72186 36190 72187 35961 72187 36166 72187 35760 72188 36218 72188 36191 72188 36191 72189 36218 72189 36219 72189 36191 72190 36219 72190 35761 72190 35761 72191 36219 72191 36220 72191 35761 72192 36220 72192 36192 72192 36192 72193 36220 72193 36222 72193 36192 72194 36222 72194 35752 72194 35752 72195 36222 72195 36223 72195 35752 72196 36223 72196 35754 72196 35754 72197 36223 72197 36193 72197 35754 72198 36193 72198 36194 72198 36194 72199 36193 72199 36228 72199 36194 72200 36228 72200 36195 72200 36195 72201 36228 72201 36229 72201 36195 72202 36229 72202 35755 72202 35755 72203 36229 72203 36230 72203 35755 72204 36230 72204 36196 72204 36196 72205 36230 72205 36197 72205 36196 72206 36197 72206 36198 72206 36198 72207 36197 72207 36233 72207 36198 72208 36233 72208 35736 72208 35736 72209 36233 72209 36236 72209 35736 72210 36236 72210 36199 72210 36199 72211 36236 72211 36237 72211 36199 72212 36237 72212 36200 72212 36200 72213 36237 72213 36238 72213 36200 72214 36238 72214 36201 72214 36201 72215 36238 72215 36202 72215 36201 72216 36202 72216 36203 72216 36203 72217 36202 72217 36204 72217 36203 72218 36204 72218 35750 72218 35750 72219 36204 72219 36243 72219 35750 72220 36243 72220 36205 72220 36205 72221 36243 72221 36244 72221 36205 72222 36244 72222 36206 72222 36206 72223 36244 72223 36207 72223 36206 72224 36207 72224 36209 72224 36209 72225 36207 72225 36208 72225 36209 72226 36208 72226 36210 72226 36210 72227 36208 72227 36247 72227 36210 72228 36247 72228 35738 72228 35738 72229 36247 72229 36248 72229 35738 72230 36248 72230 35739 72230 35739 72231 36248 72231 36249 72231 35739 72232 36249 72232 35740 72232 35740 72233 36249 72233 36211 72233 35740 72234 36211 72234 35741 72234 35741 72235 36211 72235 36251 72235 35741 72236 36251 72236 35743 72236 35743 72237 36251 72237 36212 72237 35743 72238 36212 72238 35734 72238 35734 72239 36212 72239 36252 72239 35734 72240 36252 72240 35735 72240 35735 72241 36252 72241 36253 72241 35735 72242 36253 72242 35745 72242 35745 72243 36253 72243 36254 72243 35745 72244 36254 72244 36213 72244 36213 72245 36254 72245 36214 72245 36213 72246 36214 72246 35746 72246 35746 72247 36214 72247 36256 72247 35746 72248 36256 72248 35756 72248 35756 72249 36256 72249 36257 72249 35756 72250 36257 72250 35757 72250 35757 72251 36257 72251 36215 72251 35757 72252 36215 72252 35758 72252 35758 72253 36215 72253 36216 72253 35758 72254 36216 72254 35759 72254 35759 72255 36216 72255 36261 72255 35759 72256 36261 72256 36217 72256 36217 72257 36261 72257 36262 72257 36217 72258 36262 72258 35760 72258 35760 72259 36262 72259 36218 72259 36262 72260 36263 72260 36218 72260 36218 72261 36263 72261 36265 72261 36218 72262 36265 72262 36219 72262 36219 72263 36265 72263 36267 72263 36219 72264 36267 72264 36220 72264 36220 72265 36267 72265 36221 72265 36220 72266 36221 72266 36222 72266 36222 72267 36221 72267 36224 72267 36222 72268 36224 72268 36223 72268 36223 72269 36224 72269 36225 72269 36223 72270 36225 72270 36193 72270 36193 72271 36225 72271 36226 72271 36193 72272 36226 72272 36228 72272 36228 72273 36226 72273 36227 72273 36228 72274 36227 72274 36229 72274 36229 72275 36227 72275 36271 72275 36229 72276 36271 72276 36230 72276 36230 72277 36271 72277 36231 72277 36230 72278 36231 72278 36197 72278 36197 72279 36231 72279 36232 72279 36197 72280 36232 72280 36233 72280 36233 72281 36232 72281 36234 72281 36233 72282 36234 72282 36236 72282 36236 72283 36234 72283 36235 72283 36236 72284 36235 72284 36237 72284 36237 72285 36235 72285 36239 72285 36237 72286 36239 72286 36238 72286 36238 72287 36239 72287 36240 72287 36238 72288 36240 72288 36202 72288 36202 72289 36240 72289 36241 72289 36202 72290 36241 72290 36204 72290 36204 72291 36241 72291 36242 72291 36204 72292 36242 72292 36243 72292 36243 72293 36242 72293 36277 72293 36243 72294 36277 72294 36244 72294 36244 72295 36277 72295 36245 72295 36244 72296 36245 72296 36207 72296 36207 72297 36245 72297 36246 72297 36207 72298 36246 72298 36208 72298 36208 72299 36246 72299 36281 72299 36208 72300 36281 72300 36247 72300 36247 72301 36281 72301 36282 72301 36247 72302 36282 72302 36248 72302 36248 72303 36282 72303 36285 72303 36248 72304 36285 72304 36249 72304 36249 72305 36285 72305 36286 72305 36249 72306 36286 72306 36211 72306 36211 72307 36286 72307 36250 72307 36211 72308 36250 72308 36251 72308 36251 72309 36250 72309 36289 72309 36251 72310 36289 72310 36212 72310 36212 72311 36289 72311 36292 72311 36212 72312 36292 72312 36252 72312 36252 72313 36292 72313 36293 72313 36252 72314 36293 72314 36253 72314 36253 72315 36293 72315 36295 72315 36253 72316 36295 72316 36254 72316 36254 72317 36295 72317 36296 72317 36254 72318 36296 72318 36214 72318 36214 72319 36296 72319 36255 72319 36214 72320 36255 72320 36256 72320 36256 72321 36255 72321 36297 72321 36256 72322 36297 72322 36257 72322 36257 72323 36297 72323 36258 72323 36257 72324 36258 72324 36215 72324 36215 72325 36258 72325 36259 72325 36215 72326 36259 72326 36216 72326 36216 72327 36259 72327 36260 72327 36216 72328 36260 72328 36261 72328 36261 72329 36260 72329 36299 72329 36261 72330 36299 72330 36262 72330 36262 72331 36299 72331 36263 72331 36299 72332 36301 72332 36263 72332 36263 72333 36301 72333 36264 72333 36263 72334 36264 72334 36265 72334 36265 72335 36264 72335 36266 72335 36265 72336 36266 72336 36267 72336 36267 72337 36266 72337 35950 72337 36267 72338 35950 72338 36221 72338 36221 72339 35950 72339 35949 72339 36221 72340 35949 72340 36224 72340 36224 72341 35949 72341 36268 72341 36224 72342 36268 72342 36225 72342 36225 72343 36268 72343 36269 72343 36225 72344 36269 72344 36226 72344 36226 72345 36269 72345 36270 72345 36226 72346 36270 72346 36227 72346 36227 72347 36270 72347 35948 72347 36227 72348 35948 72348 36271 72348 36271 72349 35948 72349 36272 72349 36271 72350 36272 72350 36231 72350 36231 72351 36272 72351 35946 72351 36231 72352 35946 72352 36232 72352 36232 72353 35946 72353 36273 72353 36232 72354 36273 72354 36234 72354 36234 72355 36273 72355 36274 72355 36234 72356 36274 72356 36235 72356 36235 72357 36274 72357 36275 72357 36235 72358 36275 72358 36239 72358 36239 72359 36275 72359 35943 72359 36239 72360 35943 72360 36240 72360 36240 72361 35943 72361 36276 72361 36240 72362 36276 72362 36241 72362 36241 72363 36276 72363 35941 72363 36241 72364 35941 72364 36242 72364 36242 72365 35941 72365 35939 72365 36242 72366 35939 72366 36277 72366 36277 72367 35939 72367 36278 72367 36277 72368 36278 72368 36245 72368 36245 72369 36278 72369 36279 72369 36245 72370 36279 72370 36246 72370 36246 72371 36279 72371 36280 72371 36246 72372 36280 72372 36281 72372 36281 72373 36280 72373 36283 72373 36281 72374 36283 72374 36282 72374 36282 72375 36283 72375 36284 72375 36282 72376 36284 72376 36285 72376 36285 72377 36284 72377 36287 72377 36285 72378 36287 72378 36286 72378 36286 72379 36287 72379 36288 72379 36286 72380 36288 72380 36250 72380 36250 72381 36288 72381 35934 72381 36250 72382 35934 72382 36289 72382 36289 72383 35934 72383 36290 72383 36289 72384 36290 72384 36292 72384 36292 72385 36290 72385 36291 72385 36292 72386 36291 72386 36293 72386 36293 72387 36291 72387 36294 72387 36293 72388 36294 72388 36295 72388 36295 72389 36294 72389 35932 72389 36295 72390 35932 72390 36296 72390 36296 72391 35932 72391 35930 72391 36296 72392 35930 72392 36255 72392 36255 72393 35930 72393 35929 72393 36255 72394 35929 72394 36297 72394 36297 72395 35929 72395 35927 72395 36297 72396 35927 72396 36258 72396 36258 72397 35927 72397 35925 72397 36258 72398 35925 72398 36259 72398 36259 72399 35925 72399 36298 72399 36259 72400 36298 72400 36260 72400 36260 72401 36298 72401 36300 72401 36260 72402 36300 72402 36299 72402 36299 72403 36300 72403 36301 72403 36339 72404 36340 72404 36302 72404 36302 72405 36340 72405 36303 72405 36302 72406 36303 72406 35068 72406 35068 72407 36303 72407 36304 72407 35068 72408 36304 72408 35073 72408 35073 72409 36304 72409 36343 72409 35073 72410 36343 72410 35074 72410 35074 72411 36343 72411 36305 72411 35074 72412 36305 72412 35075 72412 35075 72413 36305 72413 36306 72413 35075 72414 36306 72414 35076 72414 35076 72415 36306 72415 36308 72415 35076 72416 36308 72416 36307 72416 36307 72417 36308 72417 36345 72417 36307 72418 36345 72418 36309 72418 36309 72419 36345 72419 36346 72419 36309 72420 36346 72420 36310 72420 36310 72421 36346 72421 36311 72421 36310 72422 36311 72422 36312 72422 36312 72423 36311 72423 36348 72423 36312 72424 36348 72424 35079 72424 35079 72425 36348 72425 36313 72425 35079 72426 36313 72426 36315 72426 36315 72427 36313 72427 36314 72427 36315 72428 36314 72428 35056 72428 35056 72429 36314 72429 36350 72429 35056 72430 36350 72430 35055 72430 35055 72431 36350 72431 36316 72431 35055 72432 36316 72432 36317 72432 36317 72433 36316 72433 36318 72433 36317 72434 36318 72434 35060 72434 35060 72435 36318 72435 36353 72435 35060 72436 36353 72436 36319 72436 36319 72437 36353 72437 36354 72437 36319 72438 36354 72438 35065 72438 35065 72439 36354 72439 36357 72439 35065 72440 36357 72440 35071 72440 35071 72441 36357 72441 36359 72441 35071 72442 36359 72442 36320 72442 36320 72443 36359 72443 36321 72443 36320 72444 36321 72444 35072 72444 35072 72445 36321 72445 36322 72445 35072 72446 36322 72446 36323 72446 36323 72447 36322 72447 36361 72447 36323 72448 36361 72448 35059 72448 35059 72449 36361 72449 36324 72449 35059 72450 36324 72450 36325 72450 36325 72451 36324 72451 36326 72451 36325 72452 36326 72452 36327 72452 36327 72453 36326 72453 36363 72453 36327 72454 36363 72454 36328 72454 36328 72455 36363 72455 36329 72455 36328 72456 36329 72456 36330 72456 36330 72457 36329 72457 36364 72457 36330 72458 36364 72458 36331 72458 36331 72459 36364 72459 36366 72459 36331 72460 36366 72460 35049 72460 35049 72461 36366 72461 36368 72461 35049 72462 36368 72462 36332 72462 36332 72463 36368 72463 36333 72463 36332 72464 36333 72464 35061 72464 35061 72465 36333 72465 36334 72465 35061 72466 36334 72466 35062 72466 35062 72467 36334 72467 36336 72467 35062 72468 36336 72468 36335 72468 36335 72469 36336 72469 36373 72469 36335 72470 36373 72470 35064 72470 35064 72471 36373 72471 36374 72471 35064 72472 36374 72472 36337 72472 36337 72473 36374 72473 36338 72473 36337 72474 36338 72474 36339 72474 36339 72475 36338 72475 36340 72475 36338 72476 36376 72476 36340 72476 36340 72477 36376 72477 36341 72477 36340 72478 36341 72478 36303 72478 36303 72479 36341 72479 36342 72479 36303 72480 36342 72480 36304 72480 36304 72481 36342 72481 36377 72481 36304 72482 36377 72482 36343 72482 36343 72483 36377 72483 36344 72483 36343 72484 36344 72484 36305 72484 36305 72485 36344 72485 36380 72485 36305 72486 36380 72486 36306 72486 36306 72487 36380 72487 36381 72487 36306 72488 36381 72488 36308 72488 36308 72489 36381 72489 36384 72489 36308 72490 36384 72490 36345 72490 36345 72491 36384 72491 36385 72491 36345 72492 36385 72492 36346 72492 36346 72493 36385 72493 36387 72493 36346 72494 36387 72494 36311 72494 36311 72495 36387 72495 36347 72495 36311 72496 36347 72496 36348 72496 36348 72497 36347 72497 36390 72497 36348 72498 36390 72498 36313 72498 36313 72499 36390 72499 36349 72499 36313 72500 36349 72500 36314 72500 36314 72501 36349 72501 36351 72501 36314 72502 36351 72502 36350 72502 36350 72503 36351 72503 36393 72503 36350 72504 36393 72504 36316 72504 36316 72505 36393 72505 36352 72505 36316 72506 36352 72506 36318 72506 36318 72507 36352 72507 36397 72507 36318 72508 36397 72508 36353 72508 36353 72509 36397 72509 36355 72509 36353 72510 36355 72510 36354 72510 36354 72511 36355 72511 36356 72511 36354 72512 36356 72512 36357 72512 36357 72513 36356 72513 36358 72513 36357 72514 36358 72514 36359 72514 36359 72515 36358 72515 36399 72515 36359 72516 36399 72516 36321 72516 36321 72517 36399 72517 36360 72517 36321 72518 36360 72518 36322 72518 36322 72519 36360 72519 36401 72519 36322 72520 36401 72520 36361 72520 36361 72521 36401 72521 36402 72521 36361 72522 36402 72522 36324 72522 36324 72523 36402 72523 36404 72523 36324 72524 36404 72524 36326 72524 36326 72525 36404 72525 36362 72525 36326 72526 36362 72526 36363 72526 36363 72527 36362 72527 36407 72527 36363 72528 36407 72528 36329 72528 36329 72529 36407 72529 36365 72529 36329 72530 36365 72530 36364 72530 36364 72531 36365 72531 36408 72531 36364 72532 36408 72532 36366 72532 36366 72533 36408 72533 36367 72533 36366 72534 36367 72534 36368 72534 36368 72535 36367 72535 36369 72535 36368 72536 36369 72536 36333 72536 36333 72537 36369 72537 36370 72537 36333 72538 36370 72538 36334 72538 36334 72539 36370 72539 36371 72539 36334 72540 36371 72540 36336 72540 36336 72541 36371 72541 36372 72541 36336 72542 36372 72542 36373 72542 36373 72543 36372 72543 36413 72543 36373 72544 36413 72544 36374 72544 36374 72545 36413 72545 36375 72545 36374 72546 36375 72546 36338 72546 36338 72547 36375 72547 36376 72547 36375 72548 35940 72548 36376 72548 36376 72549 35940 72549 35942 72549 36376 72550 35942 72550 36341 72550 36341 72551 35942 72551 35944 72551 36341 72552 35944 72552 36342 72552 36342 72553 35944 72553 35945 72553 36342 72554 35945 72554 36377 72554 36377 72555 35945 72555 36378 72555 36377 72556 36378 72556 36344 72556 36344 72557 36378 72557 36379 72557 36344 72558 36379 72558 36380 72558 36380 72559 36379 72559 36382 72559 36380 72560 36382 72560 36381 72560 36381 72561 36382 72561 36383 72561 36381 72562 36383 72562 36384 72562 36384 72563 36383 72563 35947 72563 36384 72564 35947 72564 36385 72564 36385 72565 35947 72565 36386 72565 36385 72566 36386 72566 36387 72566 36387 72567 36386 72567 36388 72567 36387 72568 36388 72568 36347 72568 36347 72569 36388 72569 36389 72569 36347 72570 36389 72570 36390 72570 36390 72571 36389 72571 36391 72571 36390 72572 36391 72572 36349 72572 36349 72573 36391 72573 36392 72573 36349 72574 36392 72574 36351 72574 36351 72575 36392 72575 36394 72575 36351 72576 36394 72576 36393 72576 36393 72577 36394 72577 36395 72577 36393 72578 36395 72578 36352 72578 36352 72579 36395 72579 36396 72579 36352 72580 36396 72580 36397 72580 36397 72581 36396 72581 36398 72581 36397 72582 36398 72582 36355 72582 36355 72583 36398 72583 35951 72583 36355 72584 35951 72584 36356 72584 36356 72585 35951 72585 35924 72585 36356 72586 35924 72586 36358 72586 36358 72587 35924 72587 35926 72587 36358 72588 35926 72588 36399 72588 36399 72589 35926 72589 35928 72589 36399 72590 35928 72590 36360 72590 36360 72591 35928 72591 36400 72591 36360 72592 36400 72592 36401 72592 36401 72593 36400 72593 36403 72593 36401 72594 36403 72594 36402 72594 36402 72595 36403 72595 35931 72595 36402 72596 35931 72596 36404 72596 36404 72597 35931 72597 35933 72597 36404 72598 35933 72598 36362 72598 36362 72599 35933 72599 36405 72599 36362 72600 36405 72600 36407 72600 36407 72601 36405 72601 36406 72601 36407 72602 36406 72602 36365 72602 36365 72603 36406 72603 35935 72603 36365 72604 35935 72604 36408 72604 36408 72605 35935 72605 36409 72605 36408 72606 36409 72606 36367 72606 36367 72607 36409 72607 36410 72607 36367 72608 36410 72608 36369 72608 36369 72609 36410 72609 35936 72609 36369 72610 35936 72610 36370 72610 36370 72611 35936 72611 36411 72611 36370 72612 36411 72612 36371 72612 36371 72613 36411 72613 36412 72613 36371 72614 36412 72614 36372 72614 36372 72615 36412 72615 35937 72615 36372 72616 35937 72616 36413 72616 36413 72617 35937 72617 35938 72617 36413 72618 35938 72618 36375 72618 36375 72619 35938 72619 35940 72619 36440 72620 36414 72620 36416 72620 36440 72621 36416 72621 36415 72621 36415 72622 36416 72622 36417 72622 36415 72623 36417 72623 37063 72623 37063 72624 36417 72624 36578 72624 37063 72625 36578 72625 36418 72625 36418 72626 36578 72626 36576 72626 36418 72627 36576 72627 37066 72627 37066 72628 36576 72628 36419 72628 37066 72629 36419 72629 37067 72629 36634 72630 36422 72630 37060 72630 36419 72631 36580 72631 37067 72631 37067 72632 36580 72632 36420 72632 36420 72633 36626 72633 37067 72633 37067 72634 36626 72634 36421 72634 37067 72635 36421 72635 37060 72635 37060 72636 36421 72636 36632 72636 37060 72637 36632 72637 36634 72637 37060 72638 36422 72638 36557 72638 37060 72639 36557 72639 37069 72639 37069 72640 36557 72640 36423 72640 37069 72641 36423 72641 37071 72641 37071 72642 36423 72642 36424 72642 37071 72643 36424 72643 36425 72643 36425 72644 36424 72644 36556 72644 36425 72645 36556 72645 37072 72645 37072 72646 36556 72646 36555 72646 37072 72647 36555 72647 37074 72647 36555 72648 36554 72648 37074 72648 37074 72649 36554 72649 36607 72649 37074 72650 36607 72650 37076 72650 37076 72651 36607 72651 36604 72651 37076 72652 36604 72652 36558 72652 37076 72653 36558 72653 36559 72653 37076 72654 36559 72654 37086 72654 37086 72655 36559 72655 36426 72655 37086 72656 36426 72656 37087 72656 37087 72657 36426 72657 36428 72657 37087 72658 36428 72658 36427 72658 36427 72659 36428 72659 36561 72659 36427 72660 36561 72660 36429 72660 36429 72661 36561 72661 36560 72661 36429 72662 36560 72662 37090 72662 36430 72663 36435 72663 36434 72663 36430 72664 36434 72664 36645 72664 37090 72665 36560 72665 36649 72665 36649 72666 36431 72666 37090 72666 37090 72667 36431 72667 36432 72667 37090 72668 36432 72668 36434 72668 36434 72669 36432 72669 36433 72669 36434 72670 36433 72670 36645 72670 36434 72671 36435 72671 36567 72671 36434 72672 36567 72672 36436 72672 36436 72673 36567 72673 36437 72673 36436 72674 36437 72674 36438 72674 36438 72675 36437 72675 36573 72675 36438 72676 36573 72676 37081 72676 37081 72677 36573 72677 36571 72677 37081 72678 36571 72678 36439 72678 36439 72679 36571 72679 36569 72679 36439 72680 36569 72680 37084 72680 36613 72681 36414 72681 36440 72681 36613 72682 36440 72682 36612 72682 36612 72683 36440 72683 36441 72683 36441 72684 36440 72684 37084 72684 36441 72685 37084 72685 36569 72685 36753 72686 36755 72686 36442 72686 36471 72687 36443 72687 37015 72687 36459 72688 36524 72688 36444 72688 36445 72689 36513 72689 36442 72689 36450 72690 37040 72690 36527 72690 36527 72691 37040 72691 37041 72691 36527 72692 37041 72692 36455 72692 36513 72693 37033 72693 37077 72693 37077 72694 37033 72694 36446 72694 37077 72695 36446 72695 36447 72695 36447 72696 36446 72696 36448 72696 36447 72697 36448 72697 36527 72697 36527 72698 36448 72698 36449 72698 36527 72699 36449 72699 36450 72699 37053 72700 36451 72700 36452 72700 36452 72701 36451 72701 36453 72701 36452 72702 36453 72702 36442 72702 36442 72703 36453 72703 37056 72703 36442 72704 37056 72704 36445 72704 37041 72705 36454 72705 36455 72705 36455 72706 36454 72706 36456 72706 36455 72707 36456 72707 36444 72707 36444 72708 36456 72708 37045 72708 36444 72709 37045 72709 37049 72709 37053 72710 36452 72710 37052 72710 37052 72711 36452 72711 36462 72711 37052 72712 36462 72712 37051 72712 37049 72713 36457 72713 37004 72713 37004 72714 36457 72714 36460 72714 36548 72715 36458 72715 37015 72715 37004 72716 37005 72716 37049 72716 37049 72717 37005 72717 37008 72717 37049 72718 37008 72718 36444 72718 36444 72719 37008 72719 37010 72719 36444 72720 37010 72720 36459 72720 36457 72721 37051 72721 36460 72721 36460 72722 37051 72722 36462 72722 36460 72723 36462 72723 36461 72723 36461 72724 36462 72724 37003 72724 36720 72725 36721 72725 36542 72725 36476 72726 36543 72726 36541 72726 36463 72727 36707 72727 36710 72727 36721 72728 36464 72728 36542 72728 36542 72729 36464 72729 36465 72729 36542 72730 36465 72730 36463 72730 36463 72731 36465 72731 36466 72731 36463 72732 36466 72732 36707 72732 36710 72733 36467 72733 36462 72733 36462 72734 36467 72734 36468 72734 36462 72735 36468 72735 37003 72735 37003 72736 36468 72736 36470 72736 37003 72737 36470 72737 36469 72737 36469 72738 36470 72738 36716 72738 36469 72739 36716 72739 37030 72739 37030 72740 36716 72740 36476 72740 36443 72741 36471 72741 36549 72741 36471 72742 37018 72742 36549 72742 36549 72743 37018 72743 37020 72743 36549 72744 37020 72744 37021 72744 36472 72745 37022 72745 36473 72745 36473 72746 36474 72746 36472 72746 36472 72747 36474 72747 36475 72747 36472 72748 36475 72748 36541 72748 36541 72749 36475 72749 37028 72749 36541 72750 37028 72750 36476 72750 36476 72751 37028 72751 37029 72751 36476 72752 37029 72752 37030 72752 36550 72753 36984 72753 36477 72753 36550 72754 36477 72754 36479 72754 36479 72755 36477 72755 36478 72755 36479 72756 36478 72756 36988 72756 36988 72757 36992 72757 36479 72757 36479 72758 36992 72758 36480 72758 36479 72759 36480 72759 36482 72759 36482 72760 36480 72760 36994 72760 36994 72761 36481 72761 36482 72761 36482 72762 36481 72762 36999 72762 36482 72763 36999 72763 36483 72763 36483 72764 36484 72764 36482 72764 36482 72765 36484 72765 37002 72765 36482 72766 37002 72766 36485 72766 37002 72767 36971 72767 36485 72767 36485 72768 36971 72768 36973 72768 36485 72769 36973 72769 36472 72769 36472 72770 36973 72770 36976 72770 36472 72771 36976 72771 36486 72771 36486 72772 36980 72772 36472 72772 36472 72773 36980 72773 36549 72773 36472 72774 36549 72774 37022 72774 37022 72775 36549 72775 37021 72775 36980 72776 36487 72776 36549 72776 36549 72777 36487 72777 36488 72777 36549 72778 36488 72778 36550 72778 36550 72779 36488 72779 36983 72779 36550 72780 36983 72780 36984 72780 36489 72781 37070 72781 36526 72781 36526 72782 37070 72782 37073 72782 37073 72783 36490 72783 36526 72783 36526 72784 36490 72784 37075 72784 36526 72785 37075 72785 37078 72785 36872 72786 36874 72786 36525 72786 36872 72787 36525 72787 36870 72787 36489 72788 36491 72788 37068 72788 37068 72789 36491 72789 36864 72789 36864 72790 36492 72790 37068 72790 37068 72791 36492 72791 36493 72791 37068 72792 36493 72792 36531 72792 36531 72793 36493 72793 36869 72793 36531 72794 36869 72794 36870 72794 36874 72795 36878 72795 36525 72795 36525 72796 36878 72796 36881 72796 36525 72797 36881 72797 36526 72797 36881 72798 36882 72798 36526 72798 36526 72799 36882 72799 36859 72799 36526 72800 36859 72800 36489 72800 36489 72801 36859 72801 36862 72801 36489 72802 36862 72802 36491 72802 36536 72803 36494 72803 37059 72803 36494 72804 36495 72804 37059 72804 37059 72805 36495 72805 36790 72805 37059 72806 36790 72806 36496 72806 36537 72807 36497 72807 36536 72807 36790 72808 36793 72808 36496 72808 36496 72809 36793 72809 36795 72809 36496 72810 36795 72810 37065 72810 37065 72811 36795 72811 36498 72811 37065 72812 36498 72812 37064 72812 36499 72813 36500 72813 36537 72813 36537 72814 36500 72814 36803 72814 36537 72815 36803 72815 36497 72815 37064 72816 36498 72816 36501 72816 36501 72817 36498 72817 36502 72817 36501 72818 36502 72818 37062 72818 37062 72819 36502 72819 37061 72819 37061 72820 36502 72820 36799 72820 37061 72821 36799 72821 36499 72821 36499 72822 36799 72822 36801 72822 36499 72823 36801 72823 36500 72823 36672 72824 36503 72824 36485 72824 36503 72825 36674 72825 36485 72825 36485 72826 36674 72826 36678 72826 36485 72827 36678 72827 36482 72827 36678 72828 36679 72828 36482 72828 36482 72829 36679 72829 36504 72829 36482 72830 36504 72830 36505 72830 36505 72831 36504 72831 36506 72831 36505 72832 36506 72832 37083 72832 37083 72833 36506 72833 36509 72833 36507 72834 36508 72834 36509 72834 36509 72835 36508 72835 37079 72835 37079 72836 37080 72836 36509 72836 36509 72837 37080 72837 37082 72837 36509 72838 37082 72838 37083 72838 36507 72839 36683 72839 36508 72839 36508 72840 36683 72840 36510 72840 36508 72841 36510 72841 36512 72841 36510 72842 36511 72842 36512 72842 36512 72843 36511 72843 36671 72843 36512 72844 36671 72844 36672 72844 36513 72845 37077 72845 36442 72845 36442 72846 37077 72846 37085 72846 36442 72847 37085 72847 36516 72847 37088 72848 36521 72848 36514 72848 36514 72849 36521 72849 36442 72849 36514 72850 36442 72850 36515 72850 36515 72851 36442 72851 36516 72851 36517 72852 36522 72852 36520 72852 36759 72853 36761 72853 36452 72853 36518 72854 36745 72854 36521 72854 36517 72855 36520 72855 36764 72855 36442 72856 36755 72856 36452 72856 36452 72857 36755 72857 36758 72857 36452 72858 36758 72858 36759 72858 37088 72859 36519 72859 36521 72859 36521 72860 36519 72860 36520 72860 36521 72861 36520 72861 36518 72861 36518 72862 36520 72862 36522 72862 36745 72863 36523 72863 36521 72863 36521 72864 36523 72864 36749 72864 36521 72865 36749 72865 36442 72865 36442 72866 36749 72866 36752 72866 36442 72867 36752 72867 36753 72867 36458 72868 36548 72868 36524 72868 36524 72869 36548 72869 36535 72869 36524 72870 36535 72870 36444 72870 36444 72871 36535 72871 36525 72871 36444 72872 36525 72872 36455 72872 36455 72873 36525 72873 36526 72873 36455 72874 36526 72874 36527 72874 36527 72875 36526 72875 37078 72875 36527 72876 37078 72876 36447 72876 36710 72877 36462 72877 36463 72877 36463 72878 36462 72878 36452 72878 36463 72879 36452 72879 36520 72879 36520 72880 36452 72880 36761 72880 36520 72881 36761 72881 36764 72881 36842 72882 36824 72882 36535 72882 36535 72883 36824 72883 36532 72883 36528 72884 36827 72884 36829 72884 36829 72885 36830 72885 36528 72885 36528 72886 36830 72886 36529 72886 36528 72887 36529 72887 36530 72887 36530 72888 36529 72888 36833 72888 36530 72889 36833 72889 36834 72889 36870 72890 36525 72890 36531 72890 36531 72891 36525 72891 36535 72891 36531 72892 36535 72892 36528 72892 36528 72893 36535 72893 36532 72893 36528 72894 36532 72894 36827 72894 36533 72895 36837 72895 36548 72895 36548 72896 36837 72896 36534 72896 36548 72897 36534 72897 36535 72897 36535 72898 36534 72898 36840 72898 36535 72899 36840 72899 36842 72899 36536 72900 37059 72900 36537 72900 36537 72901 37059 72901 36538 72901 36537 72902 36538 72902 36539 72902 36539 72903 36538 72903 36530 72903 36539 72904 36530 72904 36548 72904 36548 72905 36530 72905 36834 72905 36548 72906 36834 72906 36533 72906 36672 72907 36485 72907 36512 72907 36512 72908 36485 72908 36472 72908 36512 72909 36472 72909 36540 72909 36540 72910 36472 72910 36541 72910 36540 72911 36541 72911 36542 72911 36542 72912 36541 72912 36543 72912 36542 72913 36543 72913 36720 72913 36519 72914 37091 72914 36520 72914 36520 72915 37091 72915 36544 72915 36520 72916 36544 72916 36463 72916 36463 72917 36544 72917 36545 72917 36463 72918 36545 72918 36542 72918 36542 72919 36545 72919 37089 72919 36542 72920 37089 72920 36540 72920 36540 72921 37089 72921 36546 72921 36540 72922 36546 72922 36512 72922 36512 72923 36546 72923 36547 72923 36512 72924 36547 72924 36508 72924 37015 72925 36443 72925 36548 72925 36548 72926 36443 72926 36549 72926 36548 72927 36549 72927 36539 72927 36539 72928 36549 72928 36550 72928 36539 72929 36550 72929 36537 72929 36537 72930 36550 72930 36479 72930 36537 72931 36479 72931 36499 72931 36626 72932 36420 72932 36551 72932 36552 72933 36942 72933 36611 72933 36558 72934 36604 72934 36610 72934 36422 72935 36634 72935 36553 72935 36422 72936 36553 72936 36557 72936 36554 72937 36555 72937 36553 72937 36553 72938 36555 72938 36556 72938 36556 72939 36424 72939 36553 72939 36553 72940 36424 72940 36423 72940 36553 72941 36423 72941 36557 72941 36558 72942 36610 72942 36559 72942 36560 72943 36561 72943 36648 72943 36648 72944 36561 72944 36428 72944 36648 72945 36428 72945 36610 72945 36610 72946 36428 72946 36426 72946 36610 72947 36426 72947 36559 72947 36567 72948 36644 72948 36562 72948 36562 72949 36644 72949 36565 72949 36570 72950 36563 72950 36441 72950 36564 72951 36663 72951 36644 72951 36644 72952 36663 72952 36668 72952 36644 72953 36668 72953 36565 72953 36441 72954 36563 72954 36596 72954 36596 72955 36563 72955 36660 72955 36596 72956 36660 72956 36661 72956 36562 72957 36566 72957 36567 72957 36567 72958 36566 72958 36568 72958 36567 72959 36568 72959 36437 72959 36437 72960 36568 72960 36572 72960 36441 72961 36569 72961 36570 72961 36570 72962 36569 72962 36571 72962 36570 72963 36571 72963 36572 72963 36572 72964 36571 72964 36573 72964 36572 72965 36573 72965 36437 72965 36613 72966 36615 72966 36574 72966 36784 72967 36614 72967 36783 72967 36783 72968 36614 72968 36575 72968 36613 72969 36574 72969 36414 72969 36419 72970 36576 72970 36772 72970 36575 72971 36614 72971 36778 72971 36778 72972 36614 72972 36580 72972 36778 72973 36580 72973 36777 72973 36414 72974 36574 72974 36416 72974 36416 72975 36574 72975 36577 72975 36416 72976 36577 72976 36417 72976 36772 72977 36576 72977 36577 72977 36577 72978 36576 72978 36578 72978 36577 72979 36578 72979 36417 72979 36772 72980 36579 72980 36419 72980 36419 72981 36579 72981 36775 72981 36419 72982 36775 72982 36580 72982 36580 72983 36775 72983 36776 72983 36580 72984 36776 72984 36777 72984 36622 72985 36625 72985 36885 72985 36622 72986 36885 72986 36651 72986 36616 72987 36617 72987 36581 72987 36581 72988 36897 72988 36616 72988 36616 72989 36897 72989 36582 72989 36616 72990 36582 72990 36624 72990 36624 72991 36582 72991 36893 72991 36624 72992 36893 72992 36889 72992 36700 72993 36701 72993 36642 72993 36700 72994 36642 72994 36699 72994 36702 72995 36704 72995 36647 72995 36692 72996 36584 72996 36617 72996 36704 72997 36705 72997 36647 72997 36647 72998 36705 72998 36583 72998 36647 72999 36583 72999 36646 72999 36646 73000 36583 73000 36687 73000 36646 73001 36687 73001 36690 73001 36617 73002 36584 73002 36585 73002 36585 73003 36584 73003 36693 73003 36585 73004 36693 73004 36586 73004 36586 73005 36693 73005 36587 73005 36587 73006 36693 73006 36699 73006 36587 73007 36699 73007 36904 73007 36904 73008 36699 73008 36642 73008 36904 73009 36642 73009 36601 73009 36598 73010 36599 73010 36588 73010 36588 73011 36599 73011 36589 73011 36588 73012 36589 73012 36951 73012 36954 73013 36951 73013 36911 73013 36650 73014 36917 73014 36589 73014 36589 73015 36917 73015 36590 73015 36589 73016 36590 73016 36951 73016 36951 73017 36590 73017 36914 73017 36951 73018 36914 73018 36911 73018 36591 73019 36918 73019 36441 73019 36552 73020 36611 73020 36921 73020 36591 73021 36441 73021 36592 73021 36592 73022 36441 73022 36596 73022 36592 73023 36596 73023 36933 73023 36918 73024 36593 73024 36441 73024 36441 73025 36593 73025 36927 73025 36441 73026 36927 73026 36612 73026 36612 73027 36927 73027 36926 73027 36612 73028 36926 73028 36924 73028 36924 73029 36922 73029 36612 73029 36612 73030 36922 73030 36920 73030 36612 73031 36920 73031 36921 73031 36942 73032 36937 73032 36624 73032 36624 73033 36937 73033 36594 73033 36624 73034 36594 73034 36616 73034 36594 73035 36935 73035 36616 73035 36616 73036 36935 73036 36595 73036 36616 73037 36595 73037 36596 73037 36596 73038 36595 73038 36597 73038 36596 73039 36597 73039 36933 73039 36598 73040 36946 73040 36599 73040 36599 73041 36946 73041 36967 73041 36599 73042 36967 73042 36652 73042 36641 73043 36610 73043 36603 73043 36603 73044 36610 73044 36960 73044 36911 73045 36600 73045 36954 73045 36954 73046 36600 73046 36601 73046 36954 73047 36601 73047 36602 73047 36602 73048 36601 73048 36642 73048 36602 73049 36642 73049 36956 73049 36956 73050 36642 73050 36641 73050 36956 73051 36641 73051 36959 73051 36959 73052 36641 73052 36603 73052 36604 73053 36607 73053 36605 73053 36967 73054 36968 73054 36652 73054 36652 73055 36968 73055 36606 73055 36652 73056 36606 73056 36607 73056 36607 73057 36606 73057 36608 73057 36607 73058 36608 73058 36605 73058 36605 73059 36609 73059 36604 73059 36604 73060 36609 73060 36964 73060 36604 73061 36964 73061 36610 73061 36610 73062 36964 73062 36963 73062 36610 73063 36963 73063 36960 73063 36921 73064 36611 73064 36612 73064 36612 73065 36611 73065 36614 73065 36612 73066 36614 73066 36613 73066 36613 73067 36614 73067 36784 73067 36613 73068 36784 73068 36615 73068 36942 73069 36624 73069 36611 73069 36611 73070 36624 73070 36551 73070 36611 73071 36551 73071 36614 73071 36614 73072 36551 73072 36420 73072 36614 73073 36420 73073 36580 73073 36661 73074 36564 73074 36596 73074 36596 73075 36564 73075 36644 73075 36596 73076 36644 73076 36616 73076 36616 73077 36644 73077 36618 73077 36616 73078 36618 73078 36617 73078 36617 73079 36618 73079 36646 73079 36617 73080 36646 73080 36692 73080 36692 73081 36646 73081 36690 73081 36619 73082 36620 73082 36651 73082 36421 73083 36630 73083 36816 73083 36620 73084 36621 73084 36651 73084 36651 73085 36621 73085 36823 73085 36651 73086 36823 73086 36622 73086 36622 73087 36823 73087 36623 73087 36622 73088 36623 73088 36627 73088 36889 73089 36887 73089 36624 73089 36624 73090 36887 73090 36625 73090 36624 73091 36625 73091 36551 73091 36551 73092 36625 73092 36622 73092 36551 73093 36622 73093 36626 73093 36626 73094 36622 73094 36627 73094 36626 73095 36627 73095 36808 73095 36808 73096 36810 73096 36626 73096 36626 73097 36810 73097 36628 73097 36626 73098 36628 73098 36421 73098 36421 73099 36628 73099 36629 73099 36421 73100 36629 73100 36630 73100 36843 73101 36637 73101 36844 73101 36844 73102 36637 73102 36553 73102 36844 73103 36553 73103 36631 73103 36845 73104 36846 73104 36632 73104 36638 73105 36633 73105 36634 73105 36634 73106 36633 73106 36635 73106 36634 73107 36635 73107 36553 73107 36553 73108 36635 73108 36636 73108 36553 73109 36636 73109 36631 73109 36843 73110 36845 73110 36637 73110 36637 73111 36845 73111 36632 73111 36637 73112 36632 73112 36651 73112 36651 73113 36632 73113 36421 73113 36651 73114 36421 73114 36619 73114 36619 73115 36421 73115 36816 73115 36846 73116 36847 73116 36632 73116 36632 73117 36847 73117 36849 73117 36632 73118 36849 73118 36634 73118 36634 73119 36849 73119 36851 73119 36634 73120 36851 73120 36638 73120 36726 73121 36639 73121 36640 73121 36726 73122 36640 73122 36744 73122 36744 73123 36640 73123 36648 73123 36744 73124 36648 73124 36742 73124 36730 73125 36731 73125 36641 73125 36641 73126 36731 73126 36733 73126 36641 73127 36733 73127 36610 73127 36610 73128 36733 73128 36734 73128 36610 73129 36734 73129 36738 73129 36639 73130 36730 73130 36640 73130 36640 73131 36730 73131 36641 73131 36640 73132 36641 73132 36647 73132 36647 73133 36641 73133 36642 73133 36647 73134 36642 73134 36702 73134 36702 73135 36642 73135 36701 73135 36738 73136 36643 73136 36610 73136 36610 73137 36643 73137 36740 73137 36610 73138 36740 73138 36648 73138 36648 73139 36740 73139 36741 73139 36648 73140 36741 73140 36742 73140 36567 73141 36435 73141 36644 73141 36644 73142 36435 73142 36430 73142 36644 73143 36430 73143 36618 73143 36618 73144 36430 73144 36645 73144 36618 73145 36645 73145 36646 73145 36646 73146 36645 73146 36433 73146 36646 73147 36433 73147 36647 73147 36647 73148 36433 73148 36432 73148 36647 73149 36432 73149 36640 73149 36640 73150 36432 73150 36431 73150 36640 73151 36431 73151 36648 73151 36648 73152 36431 73152 36649 73152 36648 73153 36649 73153 36560 73153 36885 73154 36650 73154 36651 73154 36651 73155 36650 73155 36589 73155 36651 73156 36589 73156 36637 73156 36637 73157 36589 73157 36599 73157 36637 73158 36599 73158 36553 73158 36553 73159 36599 73159 36652 73159 36553 73160 36652 73160 36554 73160 36554 73161 36652 73161 36607 73161 36684 73162 36566 73162 36562 73162 36684 73163 36682 73163 36566 73163 36566 73164 36682 73164 36681 73164 36566 73165 36681 73165 36568 73165 36681 73166 36653 73166 36568 73166 36568 73167 36653 73167 36654 73167 36568 73168 36654 73168 36572 73168 36654 73169 36655 73169 36572 73169 36572 73170 36655 73170 36656 73170 36572 73171 36656 73171 36570 73171 36570 73172 36656 73172 36657 73172 36570 73173 36657 73173 36563 73173 36657 73174 36680 73174 36563 73174 36563 73175 36680 73175 36658 73175 36563 73176 36658 73176 36660 73176 36660 73177 36658 73177 36659 73177 36659 73178 36677 73178 36660 73178 36660 73179 36677 73179 36676 73179 36660 73180 36676 73180 36661 73180 36676 73181 36675 73181 36661 73181 36661 73182 36675 73182 36673 73182 36661 73183 36673 73183 36564 73183 36673 73184 36662 73184 36564 73184 36564 73185 36662 73185 36664 73185 36564 73186 36664 73186 36663 73186 36664 73187 36665 73187 36663 73187 36663 73188 36665 73188 36666 73188 36663 73189 36666 73189 36668 73189 36666 73190 36667 73190 36668 73190 36668 73191 36667 73191 36669 73191 36668 73192 36669 73192 36565 73192 36669 73193 36686 73193 36565 73193 36565 73194 36686 73194 36685 73194 36565 73195 36685 73195 36562 73195 36562 73196 36685 73196 36670 73196 36562 73197 36670 73197 36684 73197 36671 73198 36511 73198 36686 73198 36686 73199 36669 73199 36671 73199 36671 73200 36669 73200 36667 73200 36671 73201 36667 73201 36672 73201 36667 73202 36666 73202 36672 73202 36672 73203 36666 73203 36665 73203 36672 73204 36665 73204 36503 73204 36665 73205 36664 73205 36503 73205 36503 73206 36664 73206 36662 73206 36503 73207 36662 73207 36674 73207 36662 73208 36673 73208 36674 73208 36674 73209 36673 73209 36675 73209 36674 73210 36675 73210 36678 73210 36675 73211 36676 73211 36678 73211 36678 73212 36676 73212 36677 73212 36678 73213 36677 73213 36679 73213 36679 73214 36677 73214 36659 73214 36679 73215 36659 73215 36504 73215 36659 73216 36658 73216 36504 73216 36504 73217 36658 73217 36680 73217 36504 73218 36680 73218 36506 73218 36680 73219 36657 73219 36506 73219 36506 73220 36657 73220 36656 73220 36506 73221 36656 73221 36509 73221 36656 73222 36655 73222 36509 73222 36509 73223 36655 73223 36654 73223 36509 73224 36654 73224 36507 73224 36654 73225 36653 73225 36507 73225 36507 73226 36653 73226 36681 73226 36507 73227 36681 73227 36683 73227 36681 73228 36682 73228 36683 73228 36683 73229 36682 73229 36684 73229 36683 73230 36684 73230 36510 73230 36510 73231 36684 73231 36670 73231 36510 73232 36670 73232 36511 73232 36511 73233 36670 73233 36685 73233 36511 73234 36685 73234 36686 73234 36723 73235 36687 73235 36583 73235 36723 73236 36688 73236 36687 73236 36687 73237 36688 73237 36689 73237 36687 73238 36689 73238 36690 73238 36689 73239 36722 73239 36690 73239 36690 73240 36722 73240 36719 73240 36690 73241 36719 73241 36692 73241 36719 73242 36718 73242 36692 73242 36692 73243 36718 73243 36691 73243 36692 73244 36691 73244 36584 73244 36584 73245 36691 73245 36694 73245 36584 73246 36694 73246 36693 73246 36694 73247 36695 73247 36693 73247 36693 73248 36695 73248 36717 73248 36693 73249 36717 73249 36699 73249 36699 73250 36717 73250 36696 73250 36696 73251 36697 73251 36699 73251 36699 73252 36697 73252 36698 73252 36699 73253 36698 73253 36700 73253 36698 73254 36715 73254 36700 73254 36700 73255 36715 73255 36714 73255 36700 73256 36714 73256 36701 73256 36714 73257 36713 73257 36701 73257 36701 73258 36713 73258 36712 73258 36701 73259 36712 73259 36702 73259 36712 73260 36711 73260 36702 73260 36702 73261 36711 73261 36703 73261 36702 73262 36703 73262 36704 73262 36703 73263 36709 73263 36704 73263 36704 73264 36709 73264 36708 73264 36704 73265 36708 73265 36705 73265 36708 73266 36706 73266 36705 73266 36705 73267 36706 73267 36725 73267 36705 73268 36725 73268 36583 73268 36583 73269 36725 73269 36724 73269 36583 73270 36724 73270 36723 73270 36707 73271 36466 73271 36706 73271 36706 73272 36708 73272 36707 73272 36707 73273 36708 73273 36709 73273 36707 73274 36709 73274 36710 73274 36709 73275 36703 73275 36710 73275 36710 73276 36703 73276 36711 73276 36710 73277 36711 73277 36467 73277 36711 73278 36712 73278 36467 73278 36467 73279 36712 73279 36713 73279 36467 73280 36713 73280 36468 73280 36713 73281 36714 73281 36468 73281 36468 73282 36714 73282 36715 73282 36468 73283 36715 73283 36470 73283 36470 73284 36715 73284 36698 73284 36470 73285 36698 73285 36716 73285 36698 73286 36697 73286 36716 73286 36716 73287 36697 73287 36696 73287 36716 73288 36696 73288 36476 73288 36696 73289 36717 73289 36476 73289 36476 73290 36717 73290 36695 73290 36476 73291 36695 73291 36543 73291 36695 73292 36694 73292 36543 73292 36543 73293 36694 73293 36691 73293 36543 73294 36691 73294 36720 73294 36691 73295 36718 73295 36720 73295 36720 73296 36718 73296 36719 73296 36720 73297 36719 73297 36721 73297 36719 73298 36722 73298 36721 73298 36721 73299 36722 73299 36689 73299 36721 73300 36689 73300 36464 73300 36689 73301 36688 73301 36464 73301 36464 73302 36688 73302 36723 73302 36464 73303 36723 73303 36465 73303 36465 73304 36723 73304 36724 73304 36465 73305 36724 73305 36466 73305 36466 73306 36724 73306 36725 73306 36466 73307 36725 73307 36706 73307 36766 73308 36726 73308 36744 73308 36766 73309 36727 73309 36726 73309 36726 73310 36727 73310 36728 73310 36726 73311 36728 73311 36639 73311 36728 73312 36729 73312 36639 73312 36639 73313 36729 73313 36765 73313 36639 73314 36765 73314 36730 73314 36765 73315 36763 73315 36730 73315 36730 73316 36763 73316 36762 73316 36730 73317 36762 73317 36731 73317 36731 73318 36762 73318 36760 73318 36731 73319 36760 73319 36733 73319 36760 73320 36732 73320 36733 73320 36733 73321 36732 73321 36735 73321 36733 73322 36735 73322 36734 73322 36734 73323 36735 73323 36736 73323 36736 73324 36737 73324 36734 73324 36734 73325 36737 73325 36757 73325 36734 73326 36757 73326 36738 73326 36757 73327 36756 73327 36738 73327 36738 73328 36756 73328 36754 73328 36738 73329 36754 73329 36643 73329 36754 73330 36739 73330 36643 73330 36643 73331 36739 73331 36751 73331 36643 73332 36751 73332 36740 73332 36751 73333 36750 73333 36740 73333 36740 73334 36750 73334 36748 73334 36740 73335 36748 73335 36741 73335 36748 73336 36747 73336 36741 73336 36741 73337 36747 73337 36746 73337 36741 73338 36746 73338 36742 73338 36746 73339 36743 73339 36742 73339 36742 73340 36743 73340 36768 73340 36742 73341 36768 73341 36744 73341 36744 73342 36768 73342 36767 73342 36744 73343 36767 73343 36766 73343 36523 73344 36745 73344 36743 73344 36743 73345 36746 73345 36523 73345 36523 73346 36746 73346 36747 73346 36523 73347 36747 73347 36749 73347 36747 73348 36748 73348 36749 73348 36749 73349 36748 73349 36750 73349 36749 73350 36750 73350 36752 73350 36750 73351 36751 73351 36752 73351 36752 73352 36751 73352 36739 73352 36752 73353 36739 73353 36753 73353 36739 73354 36754 73354 36753 73354 36753 73355 36754 73355 36756 73355 36753 73356 36756 73356 36755 73356 36755 73357 36756 73357 36757 73357 36755 73358 36757 73358 36758 73358 36757 73359 36737 73359 36758 73359 36758 73360 36737 73360 36736 73360 36758 73361 36736 73361 36759 73361 36736 73362 36735 73362 36759 73362 36759 73363 36735 73363 36732 73363 36759 73364 36732 73364 36761 73364 36732 73365 36760 73365 36761 73365 36761 73366 36760 73366 36762 73366 36761 73367 36762 73367 36764 73367 36762 73368 36763 73368 36764 73368 36764 73369 36763 73369 36765 73369 36764 73370 36765 73370 36517 73370 36765 73371 36729 73371 36517 73371 36517 73372 36729 73372 36728 73372 36517 73373 36728 73373 36522 73373 36728 73374 36727 73374 36522 73374 36522 73375 36727 73375 36766 73375 36522 73376 36766 73376 36518 73376 36518 73377 36766 73377 36767 73377 36518 73378 36767 73378 36745 73378 36745 73379 36767 73379 36768 73379 36745 73380 36768 73380 36743 73380 36802 73381 36615 73381 36784 73381 36802 73382 36800 73382 36615 73382 36615 73383 36800 73383 36769 73383 36615 73384 36769 73384 36574 73384 36769 73385 36798 73385 36574 73385 36574 73386 36798 73386 36797 73386 36574 73387 36797 73387 36577 73387 36797 73388 36770 73388 36577 73388 36577 73389 36770 73389 36771 73389 36577 73390 36771 73390 36772 73390 36772 73391 36771 73391 36773 73391 36772 73392 36773 73392 36579 73392 36773 73393 36796 73393 36579 73393 36579 73394 36796 73394 36774 73394 36579 73395 36774 73395 36775 73395 36775 73396 36774 73396 36794 73396 36794 73397 36792 73397 36775 73397 36775 73398 36792 73398 36791 73398 36775 73399 36791 73399 36776 73399 36791 73400 36789 73400 36776 73400 36776 73401 36789 73401 36788 73401 36776 73402 36788 73402 36777 73402 36788 73403 36787 73403 36777 73403 36777 73404 36787 73404 36786 73404 36777 73405 36786 73405 36778 73405 36786 73406 36779 73406 36778 73406 36778 73407 36779 73407 36780 73407 36778 73408 36780 73408 36575 73408 36780 73409 36781 73409 36575 73409 36575 73410 36781 73410 36782 73410 36575 73411 36782 73411 36783 73411 36782 73412 36805 73412 36783 73412 36783 73413 36805 73413 36785 73413 36783 73414 36785 73414 36784 73414 36784 73415 36785 73415 36804 73415 36784 73416 36804 73416 36802 73416 36497 73417 36803 73417 36805 73417 36805 73418 36782 73418 36497 73418 36497 73419 36782 73419 36781 73419 36497 73420 36781 73420 36536 73420 36781 73421 36780 73421 36536 73421 36536 73422 36780 73422 36779 73422 36536 73423 36779 73423 36494 73423 36779 73424 36786 73424 36494 73424 36494 73425 36786 73425 36787 73425 36494 73426 36787 73426 36495 73426 36787 73427 36788 73427 36495 73427 36495 73428 36788 73428 36789 73428 36495 73429 36789 73429 36790 73429 36789 73430 36791 73430 36790 73430 36790 73431 36791 73431 36792 73431 36790 73432 36792 73432 36793 73432 36793 73433 36792 73433 36794 73433 36793 73434 36794 73434 36795 73434 36794 73435 36774 73435 36795 73435 36795 73436 36774 73436 36796 73436 36795 73437 36796 73437 36498 73437 36796 73438 36773 73438 36498 73438 36498 73439 36773 73439 36771 73439 36498 73440 36771 73440 36502 73440 36771 73441 36770 73441 36502 73441 36502 73442 36770 73442 36797 73442 36502 73443 36797 73443 36799 73443 36797 73444 36798 73444 36799 73444 36799 73445 36798 73445 36769 73445 36799 73446 36769 73446 36801 73446 36769 73447 36800 73447 36801 73447 36801 73448 36800 73448 36802 73448 36801 73449 36802 73449 36500 73449 36500 73450 36802 73450 36804 73450 36500 73451 36804 73451 36803 73451 36803 73452 36804 73452 36785 73452 36803 73453 36785 73453 36805 73453 36839 73454 36623 73454 36823 73454 36839 73455 36838 73455 36623 73455 36623 73456 36838 73456 36806 73456 36623 73457 36806 73457 36627 73457 36806 73458 36807 73458 36627 73458 36627 73459 36807 73459 36836 73459 36627 73460 36836 73460 36808 73460 36836 73461 36809 73461 36808 73461 36808 73462 36809 73462 36835 73462 36808 73463 36835 73463 36810 73463 36810 73464 36835 73464 36811 73464 36810 73465 36811 73465 36628 73465 36811 73466 36812 73466 36628 73466 36628 73467 36812 73467 36813 73467 36628 73468 36813 73468 36629 73468 36629 73469 36813 73469 36814 73469 36814 73470 36832 73470 36629 73470 36629 73471 36832 73471 36831 73471 36629 73472 36831 73472 36630 73472 36831 73473 36828 73473 36630 73473 36630 73474 36828 73474 36815 73474 36630 73475 36815 73475 36816 73475 36815 73476 36826 73476 36816 73476 36816 73477 36826 73477 36817 73477 36816 73478 36817 73478 36619 73478 36817 73479 36825 73479 36619 73479 36619 73480 36825 73480 36818 73480 36619 73481 36818 73481 36620 73481 36818 73482 36819 73482 36620 73482 36620 73483 36819 73483 36820 73483 36620 73484 36820 73484 36621 73484 36820 73485 36821 73485 36621 73485 36621 73486 36821 73486 36822 73486 36621 73487 36822 73487 36823 73487 36823 73488 36822 73488 36841 73488 36823 73489 36841 73489 36839 73489 36824 73490 36842 73490 36821 73490 36821 73491 36820 73491 36824 73491 36824 73492 36820 73492 36819 73492 36824 73493 36819 73493 36532 73493 36819 73494 36818 73494 36532 73494 36532 73495 36818 73495 36825 73495 36532 73496 36825 73496 36827 73496 36825 73497 36817 73497 36827 73497 36827 73498 36817 73498 36826 73498 36827 73499 36826 73499 36829 73499 36826 73500 36815 73500 36829 73500 36829 73501 36815 73501 36828 73501 36829 73502 36828 73502 36830 73502 36830 73503 36828 73503 36831 73503 36830 73504 36831 73504 36529 73504 36831 73505 36832 73505 36529 73505 36529 73506 36832 73506 36814 73506 36529 73507 36814 73507 36833 73507 36814 73508 36813 73508 36833 73508 36833 73509 36813 73509 36812 73509 36833 73510 36812 73510 36834 73510 36812 73511 36811 73511 36834 73511 36834 73512 36811 73512 36835 73512 36834 73513 36835 73513 36533 73513 36835 73514 36809 73514 36533 73514 36533 73515 36809 73515 36836 73515 36533 73516 36836 73516 36837 73516 36836 73517 36807 73517 36837 73517 36837 73518 36807 73518 36806 73518 36837 73519 36806 73519 36534 73519 36806 73520 36838 73520 36534 73520 36534 73521 36838 73521 36839 73521 36534 73522 36839 73522 36840 73522 36840 73523 36839 73523 36841 73523 36840 73524 36841 73524 36842 73524 36842 73525 36841 73525 36822 73525 36842 73526 36822 73526 36821 73526 36880 73527 36843 73527 36844 73527 36880 73528 36879 73528 36843 73528 36843 73529 36879 73529 36877 73529 36843 73530 36877 73530 36845 73530 36877 73531 36876 73531 36845 73531 36845 73532 36876 73532 36875 73532 36845 73533 36875 73533 36846 73533 36875 73534 36873 73534 36846 73534 36846 73535 36873 73535 36871 73535 36846 73536 36871 73536 36847 73536 36847 73537 36871 73537 36848 73537 36847 73538 36848 73538 36849 73538 36848 73539 36850 73539 36849 73539 36849 73540 36850 73540 36868 73540 36849 73541 36868 73541 36851 73541 36851 73542 36868 73542 36852 73542 36852 73543 36853 73543 36851 73543 36851 73544 36853 73544 36867 73544 36851 73545 36867 73545 36638 73545 36867 73546 36866 73546 36638 73546 36638 73547 36866 73547 36865 73547 36638 73548 36865 73548 36633 73548 36865 73549 36854 73549 36633 73549 36633 73550 36854 73550 36863 73550 36633 73551 36863 73551 36635 73551 36863 73552 36855 73552 36635 73552 36635 73553 36855 73553 36856 73553 36635 73554 36856 73554 36636 73554 36856 73555 36861 73555 36636 73555 36636 73556 36861 73556 36857 73556 36636 73557 36857 73557 36631 73557 36857 73558 36860 73558 36631 73558 36631 73559 36860 73559 36883 73559 36631 73560 36883 73560 36844 73560 36844 73561 36883 73561 36858 73561 36844 73562 36858 73562 36880 73562 36859 73563 36882 73563 36860 73563 36860 73564 36857 73564 36859 73564 36859 73565 36857 73565 36861 73565 36859 73566 36861 73566 36862 73566 36861 73567 36856 73567 36862 73567 36862 73568 36856 73568 36855 73568 36862 73569 36855 73569 36491 73569 36855 73570 36863 73570 36491 73570 36491 73571 36863 73571 36854 73571 36491 73572 36854 73572 36864 73572 36854 73573 36865 73573 36864 73573 36864 73574 36865 73574 36866 73574 36864 73575 36866 73575 36492 73575 36492 73576 36866 73576 36867 73576 36492 73577 36867 73577 36493 73577 36867 73578 36853 73578 36493 73578 36493 73579 36853 73579 36852 73579 36493 73580 36852 73580 36869 73580 36852 73581 36868 73581 36869 73581 36869 73582 36868 73582 36850 73582 36869 73583 36850 73583 36870 73583 36850 73584 36848 73584 36870 73584 36870 73585 36848 73585 36871 73585 36870 73586 36871 73586 36872 73586 36871 73587 36873 73587 36872 73587 36872 73588 36873 73588 36875 73588 36872 73589 36875 73589 36874 73589 36875 73590 36876 73590 36874 73590 36874 73591 36876 73591 36877 73591 36874 73592 36877 73592 36878 73592 36877 73593 36879 73593 36878 73593 36878 73594 36879 73594 36880 73594 36878 73595 36880 73595 36881 73595 36881 73596 36880 73596 36858 73596 36881 73597 36858 73597 36882 73597 36882 73598 36858 73598 36883 73598 36882 73599 36883 73599 36860 73599 37027 73600 37026 73600 36617 73600 36625 73601 37016 73601 36884 73601 36625 73602 36884 73602 36885 73602 37016 73603 36625 73603 36886 73603 36886 73604 36625 73604 36887 73604 36886 73605 36887 73605 36888 73605 36888 73606 36887 73606 37017 73606 37017 73607 36887 73607 36889 73607 37017 73608 36889 73608 37019 73608 37019 73609 36889 73609 36890 73609 36890 73610 36889 73610 36893 73610 36890 73611 36893 73611 36891 73611 36891 73612 36893 73612 36892 73612 36892 73613 36893 73613 36582 73613 36892 73614 36582 73614 36895 73614 36897 73615 37023 73615 36582 73615 36582 73616 37023 73616 36894 73616 36582 73617 36894 73617 36895 73617 36617 73618 37026 73618 36581 73618 37026 73619 36896 73619 36581 73619 36581 73620 36896 73620 37025 73620 36581 73621 37025 73621 36897 73621 36897 73622 37025 73622 37024 73622 36897 73623 37024 73623 37023 73623 37027 73624 36617 73624 36898 73624 36898 73625 36617 73625 36585 73625 36898 73626 36585 73626 36899 73626 36899 73627 36585 73627 36586 73627 36899 73628 36586 73628 36900 73628 36900 73629 36586 73629 36901 73629 36901 73630 36586 73630 36587 73630 36901 73631 36587 73631 36902 73631 36902 73632 36587 73632 36903 73632 36903 73633 36587 73633 36904 73633 36903 73634 36904 73634 36905 73634 36905 73635 36904 73635 36906 73635 36906 73636 36904 73636 36601 73636 36906 73637 36601 73637 36907 73637 36907 73638 36601 73638 36908 73638 36908 73639 36601 73639 36600 73639 36908 73640 36600 73640 36909 73640 36909 73641 36600 73641 36910 73641 36910 73642 36600 73642 36911 73642 36910 73643 36911 73643 37006 73643 36914 73644 36912 73644 36911 73644 36911 73645 36912 73645 37007 73645 36911 73646 37007 73646 37006 73646 36590 73647 36917 73647 36913 73647 36913 73648 37011 73648 36590 73648 36590 73649 37011 73649 36915 73649 36590 73650 36915 73650 36914 73650 36914 73651 36915 73651 37009 73651 36914 73652 37009 73652 36912 73652 36884 73653 37014 73653 36885 73653 36885 73654 37014 73654 37013 73654 36885 73655 37013 73655 36650 73655 36650 73656 37013 73656 36916 73656 36650 73657 36916 73657 36917 73657 36917 73658 36916 73658 37012 73658 36917 73659 37012 73659 36913 73659 37001 73660 37000 73660 36918 73660 36920 73661 36919 73661 36987 73661 36920 73662 36987 73662 36921 73662 36919 73663 36920 73663 36989 73663 36989 73664 36920 73664 36922 73664 36989 73665 36922 73665 36990 73665 36990 73666 36922 73666 36923 73666 36923 73667 36922 73667 36924 73667 36923 73668 36924 73668 36991 73668 36991 73669 36924 73669 36993 73669 36993 73670 36924 73670 36926 73670 36993 73671 36926 73671 36925 73671 36927 73672 36928 73672 36926 73672 36926 73673 36928 73673 36995 73673 36926 73674 36995 73674 36925 73674 36918 73675 37000 73675 36593 73675 37000 73676 36998 73676 36593 73676 36593 73677 36998 73677 36997 73677 36593 73678 36997 73678 36927 73678 36927 73679 36997 73679 36996 73679 36927 73680 36996 73680 36928 73680 37001 73681 36918 73681 36929 73681 36929 73682 36918 73682 36591 73682 36929 73683 36591 73683 36930 73683 36930 73684 36591 73684 36592 73684 36930 73685 36592 73685 36931 73685 36931 73686 36592 73686 36932 73686 36932 73687 36592 73687 36933 73687 36932 73688 36933 73688 36972 73688 36972 73689 36933 73689 36934 73689 36934 73690 36933 73690 36597 73690 36934 73691 36597 73691 36974 73691 36974 73692 36597 73692 36975 73692 36975 73693 36597 73693 36595 73693 36975 73694 36595 73694 36977 73694 36977 73695 36595 73695 36978 73695 36978 73696 36595 73696 36935 73696 36978 73697 36935 73697 36979 73697 36979 73698 36935 73698 36936 73698 36936 73699 36935 73699 36594 73699 36936 73700 36594 73700 36981 73700 36937 73701 36942 73701 36943 73701 36943 73702 36938 73702 36937 73702 36937 73703 36938 73703 36939 73703 36937 73704 36939 73704 36594 73704 36594 73705 36939 73705 36982 73705 36594 73706 36982 73706 36981 73706 36987 73707 36940 73707 36921 73707 36921 73708 36940 73708 36986 73708 36921 73709 36986 73709 36552 73709 36552 73710 36986 73710 36985 73710 36552 73711 36985 73711 36942 73711 36942 73712 36985 73712 36941 73712 36942 73713 36941 73713 36943 73713 37054 73714 36944 73714 36956 73714 36946 73715 37044 73715 36945 73715 36946 73716 36945 73716 36967 73716 37044 73717 36946 73717 36947 73717 36947 73718 36946 73718 36598 73718 36947 73719 36598 73719 36948 73719 36948 73720 36598 73720 36949 73720 36949 73721 36598 73721 36588 73721 36949 73722 36588 73722 37046 73722 37046 73723 36588 73723 37047 73723 37047 73724 36588 73724 36951 73724 37047 73725 36951 73725 37048 73725 37048 73726 36951 73726 36950 73726 36950 73727 36951 73727 36954 73727 36950 73728 36954 73728 37050 73728 36956 73729 36944 73729 36602 73729 36944 73730 36952 73730 36602 73730 36602 73731 36952 73731 36953 73731 36602 73732 36953 73732 36954 73732 36954 73733 36953 73733 36955 73733 36954 73734 36955 73734 37050 73734 37054 73735 36956 73735 36957 73735 36957 73736 36956 73736 36959 73736 36957 73737 36959 73737 36958 73737 36958 73738 36959 73738 36603 73738 36958 73739 36603 73739 37055 73739 37055 73740 36603 73740 37057 73740 37057 73741 36603 73741 36960 73741 37057 73742 36960 73742 37058 73742 37058 73743 36960 73743 36961 73743 36961 73744 36960 73744 36963 73744 36961 73745 36963 73745 36962 73745 36962 73746 36963 73746 37031 73746 37031 73747 36963 73747 36964 73747 37031 73748 36964 73748 37032 73748 37032 73749 36964 73749 36965 73749 36965 73750 36964 73750 36609 73750 36965 73751 36609 73751 37034 73751 36605 73752 37036 73752 36609 73752 36609 73753 37036 73753 37035 73753 36609 73754 37035 73754 37034 73754 36608 73755 36606 73755 37039 73755 37039 73756 37038 73756 36608 73756 36608 73757 37038 73757 36966 73757 36608 73758 36966 73758 36605 73758 36605 73759 36966 73759 37037 73759 36605 73760 37037 73760 37036 73760 36945 73761 37043 73761 36967 73761 36967 73762 37043 73762 37042 73762 36967 73763 37042 73763 36968 73763 36968 73764 37042 73764 36969 73764 36968 73765 36969 73765 36606 73765 36606 73766 36969 73766 36970 73766 36606 73767 36970 73767 37039 73767 36973 73768 36971 73768 36972 73768 36972 73769 36934 73769 36973 73769 36973 73770 36934 73770 36974 73770 36973 73771 36974 73771 36976 73771 36974 73772 36975 73772 36976 73772 36976 73773 36975 73773 36977 73773 36976 73774 36977 73774 36486 73774 36977 73775 36978 73775 36486 73775 36486 73776 36978 73776 36979 73776 36486 73777 36979 73777 36980 73777 36980 73778 36979 73778 36936 73778 36980 73779 36936 73779 36487 73779 36936 73780 36981 73780 36487 73780 36487 73781 36981 73781 36982 73781 36487 73782 36982 73782 36488 73782 36982 73783 36939 73783 36488 73783 36488 73784 36939 73784 36938 73784 36488 73785 36938 73785 36983 73785 36938 73786 36943 73786 36983 73786 36983 73787 36943 73787 36941 73787 36983 73788 36941 73788 36984 73788 36941 73789 36985 73789 36984 73789 36984 73790 36985 73790 36986 73790 36984 73791 36986 73791 36477 73791 36477 73792 36986 73792 36940 73792 36477 73793 36940 73793 36478 73793 36940 73794 36987 73794 36478 73794 36478 73795 36987 73795 36919 73795 36478 73796 36919 73796 36988 73796 36919 73797 36989 73797 36988 73797 36988 73798 36989 73798 36990 73798 36988 73799 36990 73799 36992 73799 36990 73800 36923 73800 36992 73800 36992 73801 36923 73801 36991 73801 36992 73802 36991 73802 36480 73802 36991 73803 36993 73803 36480 73803 36480 73804 36993 73804 36925 73804 36480 73805 36925 73805 36994 73805 36994 73806 36925 73806 36995 73806 36994 73807 36995 73807 36481 73807 36995 73808 36928 73808 36481 73808 36481 73809 36928 73809 36996 73809 36481 73810 36996 73810 36999 73810 36996 73811 36997 73811 36999 73811 36999 73812 36997 73812 36998 73812 36999 73813 36998 73813 36483 73813 36998 73814 37000 73814 36483 73814 36483 73815 37000 73815 37001 73815 36483 73816 37001 73816 36484 73816 37001 73817 36929 73817 36484 73817 36484 73818 36929 73818 36930 73818 36484 73819 36930 73819 37002 73819 37002 73820 36930 73820 36931 73820 37002 73821 36931 73821 36971 73821 36971 73822 36931 73822 36932 73822 36971 73823 36932 73823 36972 73823 37003 73824 36469 73824 36902 73824 36902 73825 36903 73825 37003 73825 37003 73826 36903 73826 36905 73826 37003 73827 36905 73827 36461 73827 36905 73828 36906 73828 36461 73828 36461 73829 36906 73829 36907 73829 36461 73830 36907 73830 36460 73830 36907 73831 36908 73831 36460 73831 36460 73832 36908 73832 36909 73832 36460 73833 36909 73833 37004 73833 36909 73834 36910 73834 37004 73834 37004 73835 36910 73835 37006 73835 37004 73836 37006 73836 37005 73836 37005 73837 37006 73837 37007 73837 37005 73838 37007 73838 37008 73838 37007 73839 36912 73839 37008 73839 37008 73840 36912 73840 37009 73840 37008 73841 37009 73841 37010 73841 37009 73842 36915 73842 37010 73842 37010 73843 36915 73843 37011 73843 37010 73844 37011 73844 36459 73844 37011 73845 36913 73845 36459 73845 36459 73846 36913 73846 37012 73846 36459 73847 37012 73847 36524 73847 37012 73848 36916 73848 36524 73848 36524 73849 36916 73849 37013 73849 36524 73850 37013 73850 36458 73850 36458 73851 37013 73851 37014 73851 36458 73852 37014 73852 37015 73852 37014 73853 36884 73853 37015 73853 37015 73854 36884 73854 37016 73854 37015 73855 37016 73855 36471 73855 37016 73856 36886 73856 36471 73856 36471 73857 36886 73857 36888 73857 36471 73858 36888 73858 37018 73858 36888 73859 37017 73859 37018 73859 37018 73860 37017 73860 37019 73860 37018 73861 37019 73861 37020 73861 37019 73862 36890 73862 37020 73862 37020 73863 36890 73863 36891 73863 37020 73864 36891 73864 37021 73864 37021 73865 36891 73865 36892 73865 37021 73866 36892 73866 37022 73866 36892 73867 36895 73867 37022 73867 37022 73868 36895 73868 36894 73868 37022 73869 36894 73869 36473 73869 36894 73870 37023 73870 36473 73870 36473 73871 37023 73871 37024 73871 36473 73872 37024 73872 36474 73872 37024 73873 37025 73873 36474 73873 36474 73874 37025 73874 36896 73874 36474 73875 36896 73875 36475 73875 36896 73876 37026 73876 36475 73876 36475 73877 37026 73877 37027 73877 36475 73878 37027 73878 37028 73878 37028 73879 37027 73879 36898 73879 37028 73880 36898 73880 37029 73880 37029 73881 36898 73881 36899 73881 37029 73882 36899 73882 37030 73882 37030 73883 36899 73883 36900 73883 37030 73884 36900 73884 36469 73884 36469 73885 36900 73885 36901 73885 36469 73886 36901 73886 36902 73886 36445 73887 37056 73887 37058 73887 37058 73888 36961 73888 36445 73888 36445 73889 36961 73889 36962 73889 36445 73890 36962 73890 36513 73890 36962 73891 37031 73891 36513 73891 36513 73892 37031 73892 37032 73892 36513 73893 37032 73893 37033 73893 37032 73894 36965 73894 37033 73894 37033 73895 36965 73895 37034 73895 37033 73896 37034 73896 36446 73896 36446 73897 37034 73897 37035 73897 36446 73898 37035 73898 36448 73898 37035 73899 37036 73899 36448 73899 36448 73900 37036 73900 37037 73900 36448 73901 37037 73901 36449 73901 37037 73902 36966 73902 36449 73902 36449 73903 36966 73903 37038 73903 36449 73904 37038 73904 36450 73904 37038 73905 37039 73905 36450 73905 36450 73906 37039 73906 36970 73906 36450 73907 36970 73907 37040 73907 36970 73908 36969 73908 37040 73908 37040 73909 36969 73909 37042 73909 37040 73910 37042 73910 37041 73910 37041 73911 37042 73911 37043 73911 37041 73912 37043 73912 36454 73912 37043 73913 36945 73913 36454 73913 36454 73914 36945 73914 37044 73914 36454 73915 37044 73915 36456 73915 37044 73916 36947 73916 36456 73916 36456 73917 36947 73917 36948 73917 36456 73918 36948 73918 37045 73918 36948 73919 36949 73919 37045 73919 37045 73920 36949 73920 37046 73920 37045 73921 37046 73921 37049 73921 37046 73922 37047 73922 37049 73922 37049 73923 37047 73923 37048 73923 37049 73924 37048 73924 36457 73924 36457 73925 37048 73925 36950 73925 36457 73926 36950 73926 37051 73926 36950 73927 37050 73927 37051 73927 37051 73928 37050 73928 36955 73928 37051 73929 36955 73929 37052 73929 36955 73930 36953 73930 37052 73930 37052 73931 36953 73931 36952 73931 37052 73932 36952 73932 37053 73932 36952 73933 36944 73933 37053 73933 37053 73934 36944 73934 37054 73934 37053 73935 37054 73935 36451 73935 37054 73936 36957 73936 36451 73936 36451 73937 36957 73937 36958 73937 36451 73938 36958 73938 36453 73938 36453 73939 36958 73939 37055 73939 36453 73940 37055 73940 37056 73940 37056 73941 37055 73941 37057 73941 37056 73942 37057 73942 37058 73942 36496 73943 37067 73943 37059 73943 37059 73944 37067 73944 36538 73944 37068 73945 36531 73945 37060 73945 37060 73946 36531 73946 36528 73946 37060 73947 36528 73947 37067 73947 37067 73948 36528 73948 36530 73948 37067 73949 36530 73949 36538 73949 37061 73950 36440 73950 36415 73950 37061 73951 36415 73951 37062 73951 37062 73952 36415 73952 37063 73952 37062 73953 37063 73953 36501 73953 36501 73954 37063 73954 36418 73954 36501 73955 36418 73955 37064 73955 37064 73956 36418 73956 37066 73956 37064 73957 37066 73957 37065 73957 37065 73958 37066 73958 37067 73958 37065 73959 37067 73959 36496 73959 37068 73960 37060 73960 37069 73960 37068 73961 37069 73961 36489 73961 36489 73962 37069 73962 37071 73962 36489 73963 37071 73963 37070 73963 37070 73964 37071 73964 36425 73964 37070 73965 36425 73965 37073 73965 37073 73966 36425 73966 37072 73966 37073 73967 37072 73967 36490 73967 36490 73968 37072 73968 37074 73968 36490 73969 37074 73969 37075 73969 37061 73970 36499 73970 36440 73970 36440 73971 36499 73971 36479 73971 36440 73972 36479 73972 37084 73972 37084 73973 36479 73973 36482 73973 37084 73974 36482 73974 36505 73974 37078 73975 37075 73975 37074 73975 37076 73976 37085 73976 37077 73976 37076 73977 37077 73977 37074 73977 37074 73978 37077 73978 36447 73978 37074 73979 36447 73979 37078 73979 36508 73980 36547 73980 36434 73980 36508 73981 36434 73981 37079 73981 36434 73982 36436 73982 37079 73982 37079 73983 36436 73983 36438 73983 37079 73984 36438 73984 37080 73984 37080 73985 36438 73985 37081 73985 37080 73986 37081 73986 37082 73986 37082 73987 37081 73987 36439 73987 37082 73988 36439 73988 37083 73988 37083 73989 36439 73989 37084 73989 37083 73990 37084 73990 36505 73990 37085 73991 37076 73991 37086 73991 37085 73992 37086 73992 36516 73992 36516 73993 37086 73993 37087 73993 36516 73994 37087 73994 36515 73994 36515 73995 37087 73995 36427 73995 36515 73996 36427 73996 36514 73996 36514 73997 36427 73997 36429 73997 36514 73998 36429 73998 37088 73998 37088 73999 36429 73999 37090 73999 37088 74000 37090 74000 36519 74000 37089 74001 36434 74001 36546 74001 36546 74002 36434 74002 36547 74002 37089 74003 36545 74003 36434 74003 36434 74004 36545 74004 36544 74004 36434 74005 36544 74005 37090 74005 37090 74006 36544 74006 37091 74006 37090 74007 37091 74007 36519 74007 37114 74008 44670 74008 41117 74008 41117 74009 44670 74009 44871 74009 41117 74010 44871 74010 37093 74010 44871 74011 37092 74011 37093 74011 37093 74012 37092 74012 44873 74012 37093 74013 44873 74013 37094 74013 37094 74014 44873 74014 44874 74014 37094 74015 44874 74015 37095 74015 37095 74016 44874 74016 44756 74016 37095 74017 44756 74017 41115 74017 41115 74018 44756 74018 44668 74018 41115 74019 44668 74019 41113 74019 41113 74020 44668 74020 37097 74020 41113 74021 37097 74021 37096 74021 37097 74022 44669 74022 37096 74022 37096 74023 44669 74023 44767 74023 37096 74024 44767 74024 41112 74024 41112 74025 44767 74025 37098 74025 41112 74026 37098 74026 37099 74026 37099 74027 37098 74027 44835 74027 37099 74028 44835 74028 41125 74028 41125 74029 44835 74029 44838 74029 41125 74030 44838 74030 41123 74030 41123 74031 44838 74031 37100 74031 41123 74032 37100 74032 41122 74032 37100 74033 44782 74033 41122 74033 41122 74034 44782 74034 37101 74034 41122 74035 37101 74035 41121 74035 41121 74036 37101 74036 44879 74036 41121 74037 44879 74037 37103 74037 37103 74038 44879 74038 37102 74038 37103 74039 37102 74039 41131 74039 41131 74040 37102 74040 44863 74040 41131 74041 44863 74041 37104 74041 37104 74042 44863 74042 37105 74042 37104 74043 37105 74043 41129 74043 41129 74044 37105 74044 37106 74044 41129 74045 37106 74045 37107 74045 37106 74046 44795 74046 37107 74046 37107 74047 44795 74047 37108 74047 37107 74048 37108 74048 41127 74048 41127 74049 37108 74049 37109 74049 41127 74050 37109 74050 41126 74050 41126 74051 37109 74051 37110 74051 41126 74052 37110 74052 37111 74052 37111 74053 37110 74053 44882 74053 37111 74054 44882 74054 37112 74054 37112 74055 44882 74055 44883 74055 37112 74056 44883 74056 37113 74056 37113 74057 44883 74057 44817 74057 37113 74058 44817 74058 41120 74058 41120 74059 44817 74059 44796 74059 41120 74060 44796 74060 37114 74060 37114 74061 44796 74061 37115 74061 37114 74062 37115 74062 44670 74062 37117 74063 37123 74063 37124 74063 37122 74064 37126 74064 37117 74064 37128 74065 37129 74065 37117 74065 37130 74066 37116 74066 37117 74066 37118 74067 37120 74067 37117 74067 37117 74068 37132 74068 37119 74068 37121 74069 37132 74069 37117 74069 37120 74070 37121 74070 37117 74070 37116 74071 37118 74071 37117 74071 37129 74072 37130 74072 37117 74072 37126 74073 37128 74073 37117 74073 37124 74074 37122 74074 37117 74074 37123 74075 43712 74075 37124 74075 37124 74076 43712 74076 37125 74076 37124 74077 37125 74077 37122 74077 37122 74078 37125 74078 37126 74078 37126 74079 37125 74079 37127 74079 37126 74080 37127 74080 37128 74080 37128 74081 37127 74081 37129 74081 37129 74082 37127 74082 37131 74082 37129 74083 37131 74083 37130 74083 37130 74084 37131 74084 37116 74084 37116 74085 37131 74085 43708 74085 37116 74086 43708 74086 37118 74086 37118 74087 43708 74087 37120 74087 37120 74088 43708 74088 43706 74088 37120 74089 43706 74089 37121 74089 37121 74090 43706 74090 37132 74090 37132 74091 43706 74091 43716 74091 37132 74092 43716 74092 37119 74092 37133 74093 37134 74093 37142 74093 37142 74094 37134 74094 37135 74094 37142 74095 37135 74095 37143 74095 37143 74096 37135 74096 43697 74096 37143 74097 43697 74097 37136 74097 37136 74098 43697 74098 37138 74098 37136 74099 37138 74099 37137 74099 37137 74100 37138 74100 43696 74100 37137 74101 43696 74101 37140 74101 37140 74102 43696 74102 37139 74102 37140 74103 37139 74103 37141 74103 37141 74104 37139 74104 43695 74104 37141 74105 43695 74105 43687 74105 43687 74106 43695 74106 43694 74106 37144 74107 37133 74107 37142 74107 37144 74108 37136 74108 37137 74108 37143 74109 37136 74109 37144 74109 37142 74110 37143 74110 37144 74110 37144 74111 37141 74111 43687 74111 37140 74112 37141 74112 37144 74112 37137 74113 37140 74113 37144 74113 37152 74114 43670 74114 37151 74114 37151 74115 43670 74115 37145 74115 37151 74116 37145 74116 37146 74116 37146 74117 37145 74117 37147 74117 37146 74118 37147 74118 37150 74118 37150 74119 37147 74119 43673 74119 37150 74120 43673 74120 37153 74120 37153 74121 43673 74121 43676 74121 37153 74122 43676 74122 37148 74122 37148 74123 43676 74123 43678 74123 37148 74124 43678 74124 37149 74124 37149 74125 43678 74125 43680 74125 43658 74126 37146 74126 37150 74126 37151 74127 37146 74127 43658 74127 37152 74128 37151 74128 43658 74128 43658 74129 37148 74129 37149 74129 37153 74130 37148 74130 43658 74130 37150 74131 37153 74131 43658 74131 43630 74132 43643 74132 37154 74132 37154 74133 43643 74133 37155 74133 37154 74134 37155 74134 37156 74134 37156 74135 37155 74135 37158 74135 37156 74136 37158 74136 37157 74136 37157 74137 37158 74137 37159 74137 37157 74138 37159 74138 37160 74138 37160 74139 37159 74139 37161 74139 37160 74140 37161 74140 37162 74140 37162 74141 37161 74141 43653 74141 37162 74142 43653 74142 43629 74142 43629 74143 43653 74143 43656 74143 43628 74144 37156 74144 37157 74144 37154 74145 37156 74145 43628 74145 43630 74146 37154 74146 43628 74146 43628 74147 37162 74147 43629 74147 37160 74148 37162 74148 43628 74148 37157 74149 37160 74149 43628 74149 43604 74150 43621 74150 37171 74150 37171 74151 43621 74151 37163 74151 37171 74152 37163 74152 37164 74152 37164 74153 37163 74153 37166 74153 37164 74154 37166 74154 37165 74154 37165 74155 37166 74155 43626 74155 37165 74156 43626 74156 37172 74156 37172 74157 43626 74157 37167 74157 37172 74158 37167 74158 37173 74158 37173 74159 37167 74159 43627 74159 37173 74160 43627 74160 37168 74160 37168 74161 43627 74161 43614 74161 37168 74162 43614 74162 37169 74162 37169 74163 43614 74163 37170 74163 37174 74164 43604 74164 37171 74164 37174 74165 37165 74165 37172 74165 37164 74166 37165 74166 37174 74166 37171 74167 37164 74167 37174 74167 37174 74168 37168 74168 37169 74168 37173 74169 37168 74169 37174 74169 37172 74170 37173 74170 37174 74170 43575 74171 43589 74171 37175 74171 37175 74172 43589 74172 43601 74172 37175 74173 43601 74173 37176 74173 37176 74174 43601 74174 37177 74174 37176 74175 37177 74175 37178 74175 37178 74176 37177 74176 37179 74176 37178 74177 37179 74177 37181 74177 37181 74178 37179 74178 43591 74178 37181 74179 43591 74179 37180 74179 37180 74180 43591 74180 43593 74180 37180 74181 43593 74181 43580 74181 43580 74182 43593 74182 43595 74182 43576 74183 37176 74183 37178 74183 37175 74184 37176 74184 43576 74184 43575 74185 37175 74185 43576 74185 43576 74186 37180 74186 43580 74186 37181 74187 37180 74187 43576 74187 37178 74188 37181 74188 43576 74188 43560 74189 37182 74189 37183 74189 37183 74190 37182 74190 37184 74190 37183 74191 37184 74191 37185 74191 37185 74192 37184 74192 37186 74192 37185 74193 37186 74193 37187 74193 37187 74194 37186 74194 37188 74194 37187 74195 37188 74195 37195 74195 37195 74196 37188 74196 37189 74196 37195 74197 37189 74197 37190 74197 37190 74198 37189 74198 37191 74198 37190 74199 37191 74199 37196 74199 37196 74200 37191 74200 37193 74200 37196 74201 37193 74201 37192 74201 37192 74202 37193 74202 37194 74202 43556 74203 43560 74203 37183 74203 43556 74204 37187 74204 37195 74204 37185 74205 37187 74205 43556 74205 37183 74206 37185 74206 43556 74206 43556 74207 37196 74207 37192 74207 37190 74208 37196 74208 43556 74208 37195 74209 37190 74209 43556 74209 37197 74210 43550 74210 37198 74210 37198 74211 43550 74211 37199 74211 37198 74212 37199 74212 37207 74212 37207 74213 37199 74213 37200 74213 37200 74214 37199 74214 37201 74214 37200 74215 37201 74215 37208 74215 37208 74216 37201 74216 37209 74216 37209 74217 37201 74217 37202 74217 37209 74218 37202 74218 37213 74218 37213 74219 37202 74219 37203 74219 37203 74220 37202 74220 37204 74220 37203 74221 37204 74221 37212 74221 37212 74222 37204 74222 37205 74222 37205 74223 37204 74223 37206 74223 37205 74224 37206 74224 37211 74224 37211 74225 37206 74225 37210 74225 37210 74226 37206 74226 43531 74226 37210 74227 43531 74227 43532 74227 43527 74228 37197 74228 37198 74228 37207 74229 37200 74229 43527 74229 37208 74230 37209 74230 43527 74230 37213 74231 37203 74231 43527 74231 37212 74232 37205 74232 43527 74232 43527 74233 37210 74233 43532 74233 37211 74234 37210 74234 43527 74234 37205 74235 37211 74235 43527 74235 37203 74236 37212 74236 43527 74236 37209 74237 37213 74237 43527 74237 37200 74238 37208 74238 43527 74238 37198 74239 37207 74239 43527 74239 37225 74240 43513 74240 43520 74240 37225 74241 43520 74241 37228 74241 37228 74242 43520 74242 37214 74242 37228 74243 37214 74243 37215 74243 37215 74244 37214 74244 37216 74244 37216 74245 37214 74245 37217 74245 37216 74246 37217 74246 37227 74246 37227 74247 37217 74247 37226 74247 37226 74248 37217 74248 37220 74248 37226 74249 37220 74249 37218 74249 37218 74250 37220 74250 37219 74250 37219 74251 37220 74251 37222 74251 37219 74252 37222 74252 37221 74252 37221 74253 37222 74253 43514 74253 37221 74254 43514 74254 37223 74254 37223 74255 43514 74255 43515 74255 37223 74256 43515 74256 37224 74256 43498 74257 37225 74257 37228 74257 37215 74258 37216 74258 43498 74258 37227 74259 37226 74259 43498 74259 37218 74260 37219 74260 43498 74260 43498 74261 37223 74261 37224 74261 37221 74262 37223 74262 43498 74262 37219 74263 37221 74263 43498 74263 37226 74264 37218 74264 43498 74264 37216 74265 37227 74265 43498 74265 37228 74266 37215 74266 43498 74266 43482 74267 43481 74267 37229 74267 37229 74268 43481 74268 37230 74268 37229 74269 37230 74269 37231 74269 37231 74270 37230 74270 43496 74270 37231 74271 43496 74271 37232 74271 37232 74272 43496 74272 43484 74272 37232 74273 43484 74273 37238 74273 37238 74274 43484 74274 37233 74274 37238 74275 37233 74275 37237 74275 37237 74276 37233 74276 37234 74276 37237 74277 37234 74277 37236 74277 37236 74278 37234 74278 37235 74278 43470 74279 37231 74279 37232 74279 37229 74280 37231 74280 43470 74280 43482 74281 37229 74281 43470 74281 43470 74282 37237 74282 37236 74282 37238 74283 37237 74283 43470 74283 37232 74284 37238 74284 43470 74284 41175 74285 41170 74285 37242 74285 37243 74286 37239 74286 37240 74286 37240 74287 37239 74287 41176 74287 37240 74288 41176 74288 37241 74288 41175 74289 37242 74289 37241 74289 37241 74290 37242 74290 37255 74290 37241 74291 37255 74291 37240 74291 37240 74292 37255 74292 41179 74292 37240 74293 41179 74293 37243 74293 41170 74294 37244 74294 37242 74294 37242 74295 37244 74295 37245 74295 37242 74296 37245 74296 42839 74296 43331 74297 37559 74297 41171 74297 41171 74298 37559 74298 42839 74298 41171 74299 42839 74299 37246 74299 37246 74300 42839 74300 37245 74300 41587 74301 37247 74301 37248 74301 37248 74302 37247 74302 41601 74302 41601 74303 41600 74303 37248 74303 37248 74304 41600 74304 37249 74304 37248 74305 37249 74305 41587 74305 41587 74306 37249 74306 41599 74306 37371 74307 37250 74307 42792 74307 42792 74308 37250 74308 41574 74308 41574 74309 37251 74309 42792 74309 42792 74310 37251 74310 37252 74310 42792 74311 37252 74311 41577 74311 41577 74312 37253 74312 42792 74312 42792 74313 37253 74313 41579 74313 42792 74314 41579 74314 42794 74314 41583 74315 37242 74315 41582 74315 41582 74316 37242 74316 42794 74316 41582 74317 42794 74317 41580 74317 41580 74318 42794 74318 41579 74318 41583 74319 41584 74319 37242 74319 37242 74320 41584 74320 37254 74320 37242 74321 37254 74321 37255 74321 37255 74322 37254 74322 41586 74322 37255 74323 41586 74323 37260 74323 37256 74324 37258 74324 37257 74324 37257 74325 37258 74325 37259 74325 37260 74326 37256 74326 37255 74326 37255 74327 37256 74327 37257 74327 37255 74328 37257 74328 43230 74328 43230 74329 37257 74329 37259 74329 43230 74330 37259 74330 41549 74330 41643 74331 37261 74331 37262 74331 37262 74332 37261 74332 37281 74332 41643 74333 41644 74333 37261 74333 37261 74334 41644 74334 37263 74334 37261 74335 37263 74335 37264 74335 37263 74336 41646 74336 37264 74336 37264 74337 41646 74337 37265 74337 37264 74338 37265 74338 37266 74338 37266 74339 37265 74339 41648 74339 37369 74340 41650 74340 37267 74340 37267 74341 41650 74341 37270 74341 41620 74342 37268 74342 37269 74342 37269 74343 37268 74343 37271 74343 37270 74344 41620 74344 37267 74344 37267 74345 41620 74345 37269 74345 37267 74346 37269 74346 41605 74346 41605 74347 37269 74347 37271 74347 41605 74348 37271 74348 37272 74348 37273 74349 41661 74349 41655 74349 41661 74350 37273 74350 41665 74350 37274 74351 41658 74351 37275 74351 37276 74352 37277 74352 37368 74352 37368 74353 37277 74353 37278 74353 37368 74354 37278 74354 42784 74354 42784 74355 37278 74355 37279 74355 42784 74356 37279 74356 37261 74356 37261 74357 37279 74357 37280 74357 37261 74358 37280 74358 37281 74358 37282 74359 37283 74359 41704 74359 41704 74360 37283 74360 42783 74360 41704 74361 42783 74361 37284 74361 37284 74362 42783 74362 37285 74362 37284 74363 37285 74363 41703 74363 41707 74364 41708 74364 37365 74364 37365 74365 41708 74365 37287 74365 37288 74366 41675 74366 37286 74366 37286 74367 41675 74367 41673 74367 37287 74368 37288 74368 37365 74368 37365 74369 37288 74369 37286 74369 37365 74370 37286 74370 37289 74370 37289 74371 37286 74371 41673 74371 37289 74372 41673 74372 41671 74372 37290 74373 37291 74373 41719 74373 37291 74374 37290 74374 37292 74374 37295 74375 41717 74375 37293 74375 41695 74376 37297 74376 37294 74376 37294 74377 37297 74377 37292 74377 37294 74378 37292 74378 37293 74378 37293 74379 37292 74379 37290 74379 37293 74380 37290 74380 37295 74380 37295 74381 37290 74381 41719 74381 37299 74382 42780 74382 37296 74382 37296 74383 42780 74383 37297 74383 37296 74384 37297 74384 37298 74384 37298 74385 37297 74385 41695 74385 37299 74386 41699 74386 42780 74386 42780 74387 41699 74387 37300 74387 42780 74388 37300 74388 37285 74388 37285 74389 37300 74389 41702 74389 37285 74390 41702 74390 41703 74390 42778 74391 42776 74391 41770 74391 41771 74392 37301 74392 37363 74392 37363 74393 37301 74393 41772 74393 41739 74394 37302 74394 37303 74394 37303 74395 37302 74395 41735 74395 41772 74396 41739 74396 37363 74396 37363 74397 41739 74397 37303 74397 37363 74398 37303 74398 41726 74398 41726 74399 37303 74399 41735 74399 41726 74400 41735 74400 37304 74400 37306 74401 41794 74401 37305 74401 37305 74402 41794 74402 41793 74402 41793 74403 41786 74403 37305 74403 37305 74404 41786 74404 41787 74404 37305 74405 41787 74405 37306 74405 37306 74406 41787 74406 41788 74406 37307 74407 37308 74407 37362 74407 37362 74408 37308 74408 37309 74408 37309 74409 41768 74409 37362 74409 37362 74410 41768 74410 41767 74410 37362 74411 41767 74411 37311 74411 37311 74412 41767 74412 41766 74412 37311 74413 41766 74413 37310 74413 37310 74414 41764 74414 37311 74414 37311 74415 41764 74415 41763 74415 37311 74416 41763 74416 37312 74416 37312 74417 41763 74417 37313 74417 37313 74418 41762 74418 37312 74418 37312 74419 41762 74419 37314 74419 37312 74420 37314 74420 42776 74420 42776 74421 37314 74421 41769 74421 42776 74422 41769 74422 41770 74422 41798 74423 37315 74423 41780 74423 41780 74424 37315 74424 37316 74424 41780 74425 37316 74425 41781 74425 37359 74426 41742 74426 41796 74426 41796 74427 41742 74427 41776 74427 41796 74428 41776 74428 41798 74428 41798 74429 41776 74429 41777 74429 41798 74430 41777 74430 37315 74430 37315 74431 41777 74431 41784 74431 37315 74432 41784 74432 37316 74432 37321 74433 37357 74433 37319 74433 37319 74434 37357 74434 37317 74434 37317 74435 37318 74435 37319 74435 37319 74436 37318 74436 37320 74436 37319 74437 37320 74437 37321 74437 37321 74438 37320 74438 37322 74438 37356 74439 41759 74439 42769 74439 42769 74440 41759 74440 41758 74440 41758 74441 37323 74441 42769 74441 42769 74442 37323 74442 41755 74442 42769 74443 41755 74443 37326 74443 37326 74444 41755 74444 41753 74444 37326 74445 41753 74445 41752 74445 41747 74446 41746 74446 37324 74446 37324 74447 41746 74447 41744 74447 37324 74448 41744 74448 42772 74448 42772 74449 41744 74449 37358 74449 42772 74450 37358 74450 42773 74450 41752 74451 37325 74451 37326 74451 37326 74452 37325 74452 41750 74452 37326 74453 41750 74453 37324 74453 37324 74454 41750 74454 41749 74454 37324 74455 41749 74455 41747 74455 41687 74456 37327 74456 42765 74456 41687 74457 42765 74457 37340 74457 37330 74458 41670 74458 41667 74458 41670 74459 37330 74459 37331 74459 37329 74460 41669 74460 37328 74460 41667 74461 37329 74461 37330 74461 37330 74462 37329 74462 37328 74462 37330 74463 37328 74463 37331 74463 37331 74464 37328 74464 37332 74464 37331 74465 37332 74465 42763 74465 42763 74466 37332 74466 37333 74466 42763 74467 37333 74467 37334 74467 37334 74468 41691 74468 42763 74468 42763 74469 41691 74469 41689 74469 42763 74470 41689 74470 37335 74470 37336 74471 37339 74471 37337 74471 37337 74472 37339 74472 42763 74472 37337 74473 42763 74473 37338 74473 37338 74474 42763 74474 37335 74474 37336 74475 41681 74475 37339 74475 37339 74476 41681 74476 41684 74476 37339 74477 41684 74477 42765 74477 42765 74478 41684 74478 41685 74478 42765 74479 41685 74479 37340 74479 41677 74480 37341 74480 37342 74480 37343 74481 41713 74481 37344 74481 37344 74482 41713 74482 37345 74482 37341 74483 37343 74483 37342 74483 37342 74484 37343 74484 37344 74484 37342 74485 37344 74485 37346 74485 37346 74486 37344 74486 37345 74486 37346 74487 37345 74487 37347 74487 42762 74488 43242 74488 37348 74488 37348 74489 43242 74489 41147 74489 37348 74490 41147 74490 42763 74490 41147 74491 41148 74491 42763 74491 42763 74492 41148 74492 41150 74492 42763 74493 41150 74493 37350 74493 37331 74494 37353 74494 43233 74494 43233 74495 37353 74495 37349 74495 43233 74496 37349 74496 41138 74496 37350 74497 37351 74497 42763 74497 42763 74498 37351 74498 37352 74498 42763 74499 37352 74499 37331 74499 37331 74500 37352 74500 41145 74500 37331 74501 41145 74501 37353 74501 37353 74502 41145 74502 41142 74502 37353 74503 41142 74503 37349 74503 37327 74504 41677 74504 42765 74504 42765 74505 41677 74505 37342 74505 42765 74506 37342 74506 37354 74506 37354 74507 37342 74507 41721 74507 37354 74508 41721 74508 42767 74508 42767 74509 41721 74509 41723 74509 42767 74510 41723 74510 37355 74510 37355 74511 41723 74511 41724 74511 37355 74512 41724 74512 42769 74512 42769 74513 41724 74513 37357 74513 42769 74514 37357 74514 37356 74514 37356 74515 37357 74515 37321 74515 37358 74516 37359 74516 42773 74516 42773 74517 37359 74517 41796 74517 42773 74518 41796 74518 37360 74518 37360 74519 41796 74519 37361 74519 37360 74520 37361 74520 37362 74520 37362 74521 37361 74521 41794 74521 37362 74522 41794 74522 37307 74522 37307 74523 41794 74523 37306 74523 41770 74524 41771 74524 42778 74524 42778 74525 41771 74525 37363 74525 42778 74526 37363 74526 37364 74526 37364 74527 37363 74527 41729 74527 37364 74528 41729 74528 37297 74528 37297 74529 41729 74529 41728 74529 37297 74530 41728 74530 37292 74530 37282 74531 41707 74531 37283 74531 37283 74532 41707 74532 37365 74532 37283 74533 37365 74533 37366 74533 37366 74534 37365 74534 41662 74534 37366 74535 41662 74535 37368 74535 37368 74536 41662 74536 37367 74536 37368 74537 37367 74537 37276 74537 37276 74538 37367 74538 41665 74538 37276 74539 41665 74539 37275 74539 37275 74540 41665 74540 37273 74540 37275 74541 37273 74541 37274 74541 37274 74542 37273 74542 41655 74542 41648 74543 37369 74543 37266 74543 37266 74544 37369 74544 37267 74544 37266 74545 37267 74545 42787 74545 42787 74546 37267 74546 41607 74546 42787 74547 41607 74547 42788 74547 42788 74548 41607 74548 41609 74548 42788 74549 41609 74549 42789 74549 42789 74550 41609 74550 37370 74550 42789 74551 37370 74551 42792 74551 42792 74552 37370 74552 37247 74552 42792 74553 37247 74553 37371 74553 37371 74554 37247 74554 41587 74554 43000 74555 37372 74555 43002 74555 43002 74556 37372 74556 37373 74556 43002 74557 37373 74557 37374 74557 37374 74558 37373 74558 37375 74558 37374 74559 37375 74559 37376 74559 37376 74560 37375 74560 37377 74560 37376 74561 37377 74561 37378 74561 37378 74562 37377 74562 37379 74562 37378 74563 37379 74563 43006 74563 43006 74564 37379 74564 37909 74564 43006 74565 37909 74565 43008 74565 43008 74566 37909 74566 37380 74566 43008 74567 37380 74567 43009 74567 43009 74568 37380 74568 37382 74568 43009 74569 37382 74569 37381 74569 37381 74570 37382 74570 37912 74570 37381 74571 37912 74571 37383 74571 37383 74572 37912 74572 37384 74572 37383 74573 37384 74573 43012 74573 43012 74574 37384 74574 37914 74574 43012 74575 37914 74575 37385 74575 37385 74576 37914 74576 37916 74576 37385 74577 37916 74577 37386 74577 37386 74578 37916 74578 37917 74578 37386 74579 37917 74579 42977 74579 42977 74580 37917 74580 37387 74580 42977 74581 37387 74581 42978 74581 42978 74582 37387 74582 37919 74582 42978 74583 37919 74583 42980 74583 42980 74584 37919 74584 37920 74584 42980 74585 37920 74585 42982 74585 42982 74586 37920 74586 37921 74586 42982 74587 37921 74587 42983 74587 42983 74588 37921 74588 42330 74588 43168 74589 41383 74589 37388 74589 37388 74590 41383 74590 38055 74590 37388 74591 38055 74591 37904 74591 37904 74592 38055 74592 38056 74592 37904 74593 38056 74593 37389 74593 37389 74594 38056 74594 37391 74594 37389 74595 37391 74595 37390 74595 37390 74596 37391 74596 38057 74596 37390 74597 38057 74597 37903 74597 37903 74598 38057 74598 38059 74598 37903 74599 38059 74599 37902 74599 37902 74600 38059 74600 38060 74600 37902 74601 38060 74601 37901 74601 37901 74602 38060 74602 38062 74602 37901 74603 38062 74603 37900 74603 37900 74604 38062 74604 38063 74604 37900 74605 38063 74605 37898 74605 37898 74606 38063 74606 37392 74606 37898 74607 37392 74607 37393 74607 37393 74608 37392 74608 37394 74608 37393 74609 37394 74609 37896 74609 37896 74610 37394 74610 38064 74610 37896 74611 38064 74611 37893 74611 37893 74612 38064 74612 38065 74612 37893 74613 38065 74613 37892 74613 37892 74614 38065 74614 38066 74614 37892 74615 38066 74615 37891 74615 37891 74616 38066 74616 37395 74616 37891 74617 37395 74617 37396 74617 37396 74618 37395 74618 37397 74618 37396 74619 37397 74619 37890 74619 37890 74620 37397 74620 38069 74620 37890 74621 38069 74621 43146 74621 43146 74622 38069 74622 38070 74622 37398 74623 43145 74623 37399 74623 37399 74624 43145 74624 38123 74624 37399 74625 38123 74625 37400 74625 37400 74626 38123 74626 37401 74626 37400 74627 37401 74627 37402 74627 37402 74628 37401 74628 38126 74628 37402 74629 38126 74629 38119 74629 38119 74630 38126 74630 37403 74630 38119 74631 37403 74631 38117 74631 38117 74632 37403 74632 38129 74632 38117 74633 38129 74633 38116 74633 38116 74634 38129 74634 38131 74634 38116 74635 38131 74635 37404 74635 37404 74636 38131 74636 37405 74636 37404 74637 37405 74637 38114 74637 38114 74638 37405 74638 37406 74638 38114 74639 37406 74639 37407 74639 37407 74640 37406 74640 38135 74640 37407 74641 38135 74641 37408 74641 37408 74642 38135 74642 38136 74642 37408 74643 38136 74643 38113 74643 38113 74644 38136 74644 38138 74644 38113 74645 38138 74645 38111 74645 38111 74646 38138 74646 37409 74646 38111 74647 37409 74647 38110 74647 38110 74648 37409 74648 38141 74648 38110 74649 38141 74649 38107 74649 38107 74650 38141 74650 37410 74650 38107 74651 37410 74651 37411 74651 37411 74652 37410 74652 37412 74652 37411 74653 37412 74653 41316 74653 41316 74654 37412 74654 38143 74654 42841 74655 37518 74655 37413 74655 42841 74656 37413 74656 42842 74656 42842 74657 37413 74657 38106 74657 42842 74658 38106 74658 42837 74658 37414 74659 42760 74659 38105 74659 38105 74660 42760 74660 37415 74660 38105 74661 37415 74661 38106 74661 38106 74662 37415 74662 37416 74662 38106 74663 37416 74663 42837 74663 37414 74664 38105 74664 37417 74664 37417 74665 38105 74665 37418 74665 37417 74666 37418 74666 37421 74666 37423 74667 37419 74667 37420 74667 37423 74668 37420 74668 37418 74668 37418 74669 37420 74669 42757 74669 37418 74670 42757 74670 37421 74670 42753 74671 42754 74671 37424 74671 37424 74672 42754 74672 37422 74672 37424 74673 37422 74673 37423 74673 37423 74674 37422 74674 42756 74674 37423 74675 42756 74675 37419 74675 42753 74676 37424 74676 42752 74676 42752 74677 37424 74677 37426 74677 42752 74678 37426 74678 42751 74678 37425 74679 37432 74679 42749 74679 37425 74680 42749 74680 37426 74680 37426 74681 42749 74681 37427 74681 37426 74682 37427 74682 42751 74682 37428 74683 37429 74683 38099 74683 38099 74684 37429 74684 37430 74684 38099 74685 37430 74685 37425 74685 37425 74686 37430 74686 37431 74686 37425 74687 37431 74687 37432 74687 37428 74688 38099 74688 37433 74688 37433 74689 38099 74689 38098 74689 37433 74690 38098 74690 42748 74690 42744 74691 37434 74691 37435 74691 37435 74692 37434 74692 42745 74692 37435 74693 42745 74693 38098 74693 38098 74694 42745 74694 42747 74694 38098 74695 42747 74695 42748 74695 42744 74696 37435 74696 42741 74696 42741 74697 37435 74697 38096 74697 42741 74698 38096 74698 37436 74698 42738 74699 37437 74699 38095 74699 38095 74700 37437 74700 42740 74700 38095 74701 42740 74701 38096 74701 38096 74702 42740 74702 37438 74702 38096 74703 37438 74703 37436 74703 42738 74704 38095 74704 37439 74704 37439 74705 38095 74705 37440 74705 37439 74706 37440 74706 42737 74706 37441 74707 42733 74707 37442 74707 37441 74708 37442 74708 37440 74708 37440 74709 37442 74709 42734 74709 37440 74710 42734 74710 42737 74710 42730 74711 37443 74711 37445 74711 37445 74712 37443 74712 37444 74712 37445 74713 37444 74713 37441 74713 37441 74714 37444 74714 42732 74714 37441 74715 42732 74715 42733 74715 42730 74716 37445 74716 42728 74716 42728 74717 37445 74717 37447 74717 42728 74718 37447 74718 37449 74718 42725 74719 37446 74719 38090 74719 38090 74720 37446 74720 42726 74720 38090 74721 42726 74721 37447 74721 37447 74722 42726 74722 37448 74722 37447 74723 37448 74723 37449 74723 42725 74724 38090 74724 42723 74724 42723 74725 38090 74725 38089 74725 42723 74726 38089 74726 37450 74726 43023 74727 43067 74727 43025 74727 43025 74728 43067 74728 38071 74728 43025 74729 38071 74729 37451 74729 37451 74730 38071 74730 38073 74730 37451 74731 38073 74731 43028 74731 43028 74732 38073 74732 37452 74732 43028 74733 37452 74733 43029 74733 43029 74734 37452 74734 38074 74734 43029 74735 38074 74735 37453 74735 37453 74736 38074 74736 38075 74736 37453 74737 38075 74737 37454 74737 37454 74738 38075 74738 38077 74738 37454 74739 38077 74739 43031 74739 43031 74740 38077 74740 37455 74740 43031 74741 37455 74741 43033 74741 43033 74742 37455 74742 37456 74742 43033 74743 37456 74743 43035 74743 43035 74744 37456 74744 38080 74744 43035 74745 38080 74745 37457 74745 37457 74746 38080 74746 38081 74746 37457 74747 38081 74747 37458 74747 37458 74748 38081 74748 38083 74748 37458 74749 38083 74749 43039 74749 43039 74750 38083 74750 37459 74750 43039 74751 37459 74751 43040 74751 43040 74752 37459 74752 37460 74752 43040 74753 37460 74753 43041 74753 43041 74754 37460 74754 38086 74754 43041 74755 38086 74755 37461 74755 37461 74756 38086 74756 37462 74756 37461 74757 37462 74757 37463 74757 37463 74758 37462 74758 37464 74758 37463 74759 37464 74759 37466 74759 37466 74760 37464 74760 37465 74760 37466 74761 37465 74761 43052 74761 43052 74762 37465 74762 38087 74762 37467 74763 42975 74763 38176 74763 37467 74764 38176 74764 37468 74764 37468 74765 38176 74765 37469 74765 37468 74766 37469 74766 37470 74766 37470 74767 37469 74767 38175 74767 37470 74768 38175 74768 42998 74768 42998 74769 38175 74769 38174 74769 42998 74770 38174 74770 42997 74770 42997 74771 38174 74771 37471 74771 42997 74772 37471 74772 42995 74772 42995 74773 37471 74773 37472 74773 42995 74774 37472 74774 37473 74774 37473 74775 37472 74775 38170 74775 37473 74776 38170 74776 37474 74776 37474 74777 38170 74777 37476 74777 37474 74778 37476 74778 37475 74778 37475 74779 37476 74779 38167 74779 37475 74780 38167 74780 42991 74780 42991 74781 38167 74781 38166 74781 42991 74782 38166 74782 42989 74782 42989 74783 38166 74783 38164 74783 42989 74784 38164 74784 37477 74784 37477 74785 38164 74785 37478 74785 37477 74786 37478 74786 42988 74786 42988 74787 37478 74787 38163 74787 42988 74788 38163 74788 42987 74788 42987 74789 38163 74789 37479 74789 42987 74790 37479 74790 42985 74790 42985 74791 37479 74791 37480 74791 42985 74792 37480 74792 42984 74792 42984 74793 37480 74793 37482 74793 42984 74794 37482 74794 37481 74794 37481 74795 37482 74795 38158 74795 37481 74796 38158 74796 42981 74796 42937 74797 37483 74797 37484 74797 42937 74798 37484 74798 42947 74798 42947 74799 37484 74799 37486 74799 42947 74800 37486 74800 37485 74800 37485 74801 37486 74801 37488 74801 37485 74802 37488 74802 37487 74802 37487 74803 37488 74803 38053 74803 37487 74804 38053 74804 37489 74804 37489 74805 38053 74805 38052 74805 37489 74806 38052 74806 42943 74806 42943 74807 38052 74807 37490 74807 42943 74808 37490 74808 42942 74808 42942 74809 37490 74809 37491 74809 42942 74810 37491 74810 42941 74810 42941 74811 37491 74811 38049 74811 42941 74812 38049 74812 37492 74812 37492 74813 38049 74813 38047 74813 37492 74814 38047 74814 37493 74814 37493 74815 38047 74815 38045 74815 37493 74816 38045 74816 37494 74816 37494 74817 38045 74817 37495 74817 37494 74818 37495 74818 37496 74818 37496 74819 37495 74819 38044 74819 37496 74820 38044 74820 37497 74820 37497 74821 38044 74821 38042 74821 37497 74822 38042 74822 42938 74822 42938 74823 38042 74823 37498 74823 42938 74824 37498 74824 37499 74824 37499 74825 37498 74825 38041 74825 37499 74826 38041 74826 37500 74826 37500 74827 38041 74827 37501 74827 37500 74828 37501 74828 42961 74828 42862 74829 41275 74829 42863 74829 42863 74830 41275 74830 37502 74830 42863 74831 37502 74831 37503 74831 37503 74832 37502 74832 38144 74832 37503 74833 38144 74833 42864 74833 42864 74834 38144 74834 37505 74834 42864 74835 37505 74835 37504 74835 37504 74836 37505 74836 37506 74836 37504 74837 37506 74837 42865 74837 42865 74838 37506 74838 37507 74838 42865 74839 37507 74839 42866 74839 42866 74840 37507 74840 38147 74840 42866 74841 38147 74841 37508 74841 37508 74842 38147 74842 37509 74842 37508 74843 37509 74843 42867 74843 42867 74844 37509 74844 38149 74844 42867 74845 38149 74845 42868 74845 42868 74846 38149 74846 37511 74846 42868 74847 37511 74847 37510 74847 37510 74848 37511 74848 37512 74848 37510 74849 37512 74849 42845 74849 42845 74850 37512 74850 37513 74850 42845 74851 37513 74851 37514 74851 37514 74852 37513 74852 38152 74852 37514 74853 38152 74853 42846 74853 42846 74854 38152 74854 37515 74854 42846 74855 37515 74855 42848 74855 42848 74856 37515 74856 38153 74856 42848 74857 38153 74857 42849 74857 42849 74858 38153 74858 37517 74858 42849 74859 37517 74859 37516 74859 37516 74860 37517 74860 42871 74860 37518 74861 37519 74861 43130 74861 43130 74862 37519 74862 37594 74862 43130 74863 37594 74863 37520 74863 37520 74864 37594 74864 37595 74864 37520 74865 37595 74865 37521 74865 37521 74866 37595 74866 37522 74866 37522 74867 37595 74867 37597 74867 37522 74868 37597 74868 37524 74868 37524 74869 37597 74869 37523 74869 37524 74870 37523 74870 43126 74870 43126 74871 37523 74871 43127 74871 43127 74872 37523 74872 37600 74872 43127 74873 37600 74873 43128 74873 43128 74874 37600 74874 37601 74874 43128 74875 37601 74875 43129 74875 43129 74876 37601 74876 37525 74876 43129 74877 37525 74877 43125 74877 43125 74878 37525 74878 37526 74878 37526 74879 37525 74879 37527 74879 37526 74880 37527 74880 43124 74880 43124 74881 37527 74881 37528 74881 43124 74882 37528 74882 43123 74882 43123 74883 37528 74883 37529 74883 37529 74884 37528 74884 37605 74884 37529 74885 37605 74885 37530 74885 37530 74886 37605 74886 37606 74886 37530 74887 37606 74887 43120 74887 43120 74888 37606 74888 43121 74888 43121 74889 37606 74889 37608 74889 43121 74890 37608 74890 43122 74890 43122 74891 37608 74891 37531 74891 43122 74892 37531 74892 43119 74892 43119 74893 37531 74893 43116 74893 43116 74894 37531 74894 37609 74894 43116 74895 37609 74895 43117 74895 43117 74896 37609 74896 37532 74896 43117 74897 37532 74897 43118 74897 43118 74898 37532 74898 37533 74898 37533 74899 37532 74899 37534 74899 37533 74900 37534 74900 43114 74900 43114 74901 37534 74901 37536 74901 43114 74902 37536 74902 37535 74902 37535 74903 37536 74903 37537 74903 37537 74904 37536 74904 37611 74904 37537 74905 37611 74905 37538 74905 37538 74906 37611 74906 37612 74906 37538 74907 37612 74907 37539 74907 37539 74908 37612 74908 37613 74908 37539 74909 37613 74909 43113 74909 43113 74910 37613 74910 37541 74910 43113 74911 37541 74911 37540 74911 37540 74912 37541 74912 43112 74912 43112 74913 37541 74913 37615 74913 43112 74914 37615 74914 37542 74914 37542 74915 37615 74915 37543 74915 37542 74916 37543 74916 37544 74916 37544 74917 37543 74917 37545 74917 37545 74918 37543 74918 37546 74918 37545 74919 37546 74919 37547 74919 37547 74920 37546 74920 37618 74920 37547 74921 37618 74921 37548 74921 37548 74922 37618 74922 37620 74922 37548 74923 37620 74923 43111 74923 43111 74924 37620 74924 37549 74924 37549 74925 37620 74925 37550 74925 37549 74926 37550 74926 43106 74926 43106 74927 37550 74927 37623 74927 43106 74928 37623 74928 43107 74928 43107 74929 37623 74929 43109 74929 43109 74930 37623 74930 37624 74930 43109 74931 37624 74931 37551 74931 37551 74932 37624 74932 37552 74932 37551 74933 37552 74933 43105 74933 43105 74934 37552 74934 37553 74934 37553 74935 37552 74935 37554 74935 37553 74936 37554 74936 43101 74936 43101 74937 37554 74937 37555 74937 43101 74938 37555 74938 43102 74938 43102 74939 37555 74939 43103 74939 43103 74940 37555 74940 37556 74940 43103 74941 37556 74941 37557 74941 37557 74942 37556 74942 37629 74942 37557 74943 37629 74943 43100 74943 37558 74944 37559 74944 37561 74944 37561 74945 37559 74945 37560 74945 37561 74946 37560 74946 37596 74946 37596 74947 37560 74947 37562 74947 37596 74948 37562 74948 37564 74948 37564 74949 37562 74949 37563 74949 37564 74950 37563 74950 37598 74950 37598 74951 37563 74951 43326 74951 37598 74952 43326 74952 37599 74952 37599 74953 43326 74953 37565 74953 37599 74954 37565 74954 37602 74954 37602 74955 37565 74955 37566 74955 37602 74956 37566 74956 37603 74956 37603 74957 37566 74957 37567 74957 37603 74958 37567 74958 37604 74958 37604 74959 37567 74959 43315 74959 37604 74960 43315 74960 37568 74960 37568 74961 43315 74961 43317 74961 37568 74962 43317 74962 37569 74962 37569 74963 43317 74963 37570 74963 37569 74964 37570 74964 37607 74964 37607 74965 37570 74965 37571 74965 37607 74966 37571 74966 37572 74966 37572 74967 37571 74967 37573 74967 37572 74968 37573 74968 37574 74968 37574 74969 37573 74969 43347 74969 37574 74970 43347 74970 37575 74970 37575 74971 43347 74971 43348 74971 37575 74972 43348 74972 37576 74972 37576 74973 43348 74973 37577 74973 37576 74974 37577 74974 37610 74974 37610 74975 37577 74975 43304 74975 37610 74976 43304 74976 37578 74976 37578 74977 43304 74977 37579 74977 37578 74978 37579 74978 37580 74978 37580 74979 37579 74979 43350 74979 37580 74980 43350 74980 37581 74980 37581 74981 43350 74981 43351 74981 37581 74982 43351 74982 37582 74982 37582 74983 43351 74983 43352 74983 37582 74984 43352 74984 37614 74984 37614 74985 43352 74985 37583 74985 37614 74986 37583 74986 37616 74986 37616 74987 37583 74987 37584 74987 37616 74988 37584 74988 37585 74988 37585 74989 37584 74989 43276 74989 37585 74990 43276 74990 37617 74990 37617 74991 43276 74991 43353 74991 37617 74992 43353 74992 37619 74992 37619 74993 43353 74993 37586 74993 37619 74994 37586 74994 37621 74994 37621 74995 37586 74995 43355 74995 37621 74996 43355 74996 37622 74996 37622 74997 43355 74997 43273 74997 37622 74998 43273 74998 37588 74998 37588 74999 43273 74999 37587 74999 37588 75000 37587 75000 37589 75000 37589 75001 37587 75001 43264 75001 37589 75002 43264 75002 37625 75002 37625 75003 43264 75003 43266 75003 37625 75004 43266 75004 37626 75004 37626 75005 43266 75005 43358 75005 37626 75006 43358 75006 37590 75006 37590 75007 43358 75007 37591 75007 37590 75008 37591 75008 37627 75008 37627 75009 37591 75009 43361 75009 37627 75010 43361 75010 37628 75010 37628 75011 43361 75011 37593 75011 37628 75012 37593 75012 37592 75012 37592 75013 37593 75013 43256 75013 37592 75014 43256 75014 37635 75014 37635 75015 43256 75015 43257 75015 37519 75016 37558 75016 37594 75016 37594 75017 37558 75017 37561 75017 37594 75018 37561 75018 37595 75018 37595 75019 37561 75019 37596 75019 37595 75020 37596 75020 37597 75020 37597 75021 37596 75021 37564 75021 37597 75022 37564 75022 37523 75022 37523 75023 37564 75023 37598 75023 37523 75024 37598 75024 37600 75024 37600 75025 37598 75025 37599 75025 37600 75026 37599 75026 37601 75026 37601 75027 37599 75027 37602 75027 37601 75028 37602 75028 37525 75028 37525 75029 37602 75029 37603 75029 37525 75030 37603 75030 37527 75030 37527 75031 37603 75031 37604 75031 37527 75032 37604 75032 37528 75032 37528 75033 37604 75033 37568 75033 37528 75034 37568 75034 37605 75034 37605 75035 37568 75035 37569 75035 37605 75036 37569 75036 37606 75036 37606 75037 37569 75037 37607 75037 37606 75038 37607 75038 37608 75038 37608 75039 37607 75039 37572 75039 37608 75040 37572 75040 37531 75040 37531 75041 37572 75041 37574 75041 37531 75042 37574 75042 37609 75042 37609 75043 37574 75043 37575 75043 37609 75044 37575 75044 37532 75044 37532 75045 37575 75045 37576 75045 37532 75046 37576 75046 37534 75046 37534 75047 37576 75047 37610 75047 37534 75048 37610 75048 37536 75048 37536 75049 37610 75049 37578 75049 37536 75050 37578 75050 37611 75050 37611 75051 37578 75051 37580 75051 37611 75052 37580 75052 37612 75052 37612 75053 37580 75053 37581 75053 37612 75054 37581 75054 37613 75054 37613 75055 37581 75055 37582 75055 37613 75056 37582 75056 37541 75056 37541 75057 37582 75057 37614 75057 37541 75058 37614 75058 37615 75058 37615 75059 37614 75059 37616 75059 37615 75060 37616 75060 37543 75060 37543 75061 37616 75061 37585 75061 37543 75062 37585 75062 37546 75062 37546 75063 37585 75063 37617 75063 37546 75064 37617 75064 37618 75064 37618 75065 37617 75065 37619 75065 37618 75066 37619 75066 37620 75066 37620 75067 37619 75067 37621 75067 37620 75068 37621 75068 37550 75068 37550 75069 37621 75069 37622 75069 37550 75070 37622 75070 37623 75070 37623 75071 37622 75071 37588 75071 37623 75072 37588 75072 37624 75072 37624 75073 37588 75073 37589 75073 37624 75074 37589 75074 37552 75074 37552 75075 37589 75075 37625 75075 37552 75076 37625 75076 37554 75076 37554 75077 37625 75077 37626 75077 37554 75078 37626 75078 37555 75078 37555 75079 37626 75079 37590 75079 37555 75080 37590 75080 37556 75080 37556 75081 37590 75081 37627 75081 37556 75082 37627 75082 37629 75082 37629 75083 37627 75083 37628 75083 37629 75084 37628 75084 37631 75084 37631 75085 37628 75085 37592 75085 37631 75086 37592 75086 37637 75086 37637 75087 37592 75087 37635 75087 43100 75088 37629 75088 37630 75088 37630 75089 37629 75089 37631 75089 37630 75090 37631 75090 37632 75090 37632 75091 37631 75091 37637 75091 37632 75092 37637 75092 37633 75092 43257 75093 43244 75093 37634 75093 43257 75094 37634 75094 37635 75094 37635 75095 37634 75095 37636 75095 37635 75096 37636 75096 37637 75096 37637 75097 37636 75097 37638 75097 37637 75098 37638 75098 37633 75098 43244 75099 42762 75099 42795 75099 43244 75100 42795 75100 37634 75100 37634 75101 42795 75101 42724 75101 37634 75102 42724 75102 37636 75102 37636 75103 42724 75103 37450 75103 37636 75104 37450 75104 37638 75104 37639 75105 42713 75105 37793 75105 37793 75106 42713 75106 37641 75106 37793 75107 37641 75107 37640 75107 37640 75108 37641 75108 37642 75108 37640 75109 37642 75109 37643 75109 37643 75110 37642 75110 37644 75110 37643 75111 37644 75111 37798 75111 37798 75112 37644 75112 37646 75112 37798 75113 37646 75113 37645 75113 37645 75114 37646 75114 37731 75114 37645 75115 37731 75115 37648 75115 37731 75116 37647 75116 37648 75116 37648 75117 37647 75117 37739 75117 37648 75118 37739 75118 37799 75118 37799 75119 37739 75119 37650 75119 37799 75120 37650 75120 37649 75120 37649 75121 37650 75121 37651 75121 37649 75122 37651 75122 37801 75122 37801 75123 37651 75123 37740 75123 37801 75124 37740 75124 37652 75124 37652 75125 37740 75125 37743 75125 37652 75126 37743 75126 37654 75126 37654 75127 37743 75127 37653 75127 37654 75128 37653 75128 37803 75128 37803 75129 37653 75129 37655 75129 37803 75130 37655 75130 37656 75130 37656 75131 37655 75131 37657 75131 37656 75132 37657 75132 37658 75132 37658 75133 37657 75133 37659 75133 37658 75134 37659 75134 37808 75134 37808 75135 37659 75135 37660 75135 37808 75136 37660 75136 37661 75136 37660 75137 37704 75137 37661 75137 37661 75138 37704 75138 37754 75138 37661 75139 37754 75139 37809 75139 37809 75140 37754 75140 37662 75140 37809 75141 37662 75141 37663 75141 37663 75142 37662 75142 37760 75142 37663 75143 37760 75143 37811 75143 37811 75144 37760 75144 37761 75144 37811 75145 37761 75145 37665 75145 37761 75146 37664 75146 37665 75146 37665 75147 37664 75147 37666 75147 37665 75148 37666 75148 37813 75148 37813 75149 37666 75149 37712 75149 37813 75150 37712 75150 37667 75150 37667 75151 37712 75151 37765 75151 37667 75152 37765 75152 37668 75152 37668 75153 37765 75153 37766 75153 37668 75154 37766 75154 37669 75154 37669 75155 37766 75155 37670 75155 37669 75156 37670 75156 37671 75156 37671 75157 37670 75157 37673 75157 37671 75158 37673 75158 37672 75158 37672 75159 37673 75159 37771 75159 37672 75160 37771 75160 37674 75160 37674 75161 37771 75161 37772 75161 37674 75162 37772 75162 37675 75162 37675 75163 37772 75163 37676 75163 37675 75164 37676 75164 37816 75164 37816 75165 37676 75165 37685 75165 37816 75166 37685 75166 37684 75166 42684 75167 42464 75167 37783 75167 37783 75168 42464 75168 37677 75168 37783 75169 37677 75169 37784 75169 37784 75170 37677 75170 37823 75170 37784 75171 37823 75171 37678 75171 37678 75172 37823 75172 37680 75172 37678 75173 37680 75173 37679 75173 37679 75174 37680 75174 37681 75174 37679 75175 37681 75175 37682 75175 37682 75176 37681 75176 37818 75176 37682 75177 37818 75177 37683 75177 37683 75178 37818 75178 37684 75178 37683 75179 37684 75179 37777 75179 37777 75180 37684 75180 37685 75180 37760 75181 37662 75181 37759 75181 37686 75182 37689 75182 37781 75182 42594 75183 42595 75183 37687 75183 37785 75184 42594 75184 37788 75184 37733 75185 37688 75185 42538 75185 42538 75186 37688 75186 42539 75186 42592 75187 37689 75187 42603 75187 42603 75188 37689 75188 37686 75188 42603 75189 37686 75189 37780 75189 42539 75190 37688 75190 42537 75190 42537 75191 37688 75191 37728 75191 42537 75192 37728 75192 42468 75192 37782 75193 37781 75193 37690 75193 37690 75194 37781 75194 37689 75194 37690 75195 37689 75195 37691 75195 37691 75196 37689 75196 42592 75196 37691 75197 42592 75197 37785 75197 37732 75198 37729 75198 37727 75198 37739 75199 37647 75199 37737 75199 37737 75200 37647 75200 37732 75200 37737 75201 37732 75201 37692 75201 37692 75202 37732 75202 37727 75202 37692 75203 37727 75203 37734 75203 37735 75204 42583 75204 37736 75204 37736 75205 42583 75205 37742 75205 37736 75206 37742 75206 37694 75206 37694 75207 37742 75207 37693 75207 37694 75208 37693 75208 37738 75208 37738 75209 37693 75209 37741 75209 42581 75210 37696 75210 37695 75210 37695 75211 37696 75211 37697 75211 37695 75212 37697 75212 37698 75212 37698 75213 37697 75213 37699 75213 37698 75214 37699 75214 37744 75214 37744 75215 37699 75215 37747 75215 37744 75216 37747 75216 37653 75216 37653 75217 37747 75217 37655 75217 42579 75218 42577 75218 37745 75218 37745 75219 42577 75219 37702 75219 37745 75220 37702 75220 37746 75220 37746 75221 37702 75221 37700 75221 37746 75222 37700 75222 37748 75222 37748 75223 37700 75223 37703 75223 42577 75224 37701 75224 37702 75224 37702 75225 37701 75225 37749 75225 37702 75226 37749 75226 37700 75226 37700 75227 37749 75227 37751 75227 37700 75228 37751 75228 37703 75228 37703 75229 37751 75229 37752 75229 37703 75230 37752 75230 37704 75230 37704 75231 37752 75231 37754 75231 42588 75232 37705 75232 37756 75232 37756 75233 37705 75233 37706 75233 37756 75234 37706 75234 37757 75234 37757 75235 37706 75235 37707 75235 37757 75236 37707 75236 37758 75236 37758 75237 37707 75237 37711 75237 37705 75238 37708 75238 37706 75238 37706 75239 37708 75239 37762 75239 37706 75240 37762 75240 37707 75240 37707 75241 37762 75241 37709 75241 37707 75242 37709 75242 37711 75242 37711 75243 37709 75243 37710 75243 37711 75244 37710 75244 37712 75244 37712 75245 37710 75245 37765 75245 42584 75246 42574 75246 37763 75246 37763 75247 42574 75247 37713 75247 37763 75248 37713 75248 37714 75248 37714 75249 37713 75249 37768 75249 37714 75250 37768 75250 37764 75250 37764 75251 37768 75251 37769 75251 42591 75252 42589 75252 37767 75252 37767 75253 42589 75253 37774 75253 37767 75254 37774 75254 37770 75254 37770 75255 37774 75255 37775 75255 37770 75256 37775 75256 37715 75256 37715 75257 37775 75257 37716 75257 37715 75258 37716 75258 37772 75258 37772 75259 37716 75259 37676 75259 37773 75260 37717 75260 37718 75260 37718 75261 37717 75261 37720 75261 37718 75262 37720 75262 37776 75262 37776 75263 37720 75263 37721 75263 37776 75264 37721 75264 37778 75264 37778 75265 37721 75265 37724 75265 37717 75266 37719 75266 37720 75266 37720 75267 37719 75267 37779 75267 37720 75268 37779 75268 37721 75268 37721 75269 37779 75269 37722 75269 37721 75270 37722 75270 37724 75270 37724 75271 37722 75271 37723 75271 37724 75272 37723 75272 37682 75272 37682 75273 37723 75273 37679 75273 42468 75274 37728 75274 37725 75274 37725 75275 37728 75275 37730 75275 37725 75276 37730 75276 37726 75276 37726 75277 37730 75277 37641 75277 37726 75278 37641 75278 42713 75278 37733 75279 37734 75279 37688 75279 37688 75280 37734 75280 37727 75280 37688 75281 37727 75281 37728 75281 37728 75282 37727 75282 37729 75282 37728 75283 37729 75283 37730 75283 37730 75284 37729 75284 37642 75284 37730 75285 37642 75285 37641 75285 37647 75286 37731 75286 37732 75286 37732 75287 37731 75287 37646 75287 37732 75288 37646 75288 37729 75288 37729 75289 37646 75289 37644 75289 37729 75290 37644 75290 37642 75290 37733 75291 37735 75291 37734 75291 37734 75292 37735 75292 37736 75292 37734 75293 37736 75293 37692 75293 37692 75294 37736 75294 37694 75294 37692 75295 37694 75295 37737 75295 37737 75296 37694 75296 37738 75296 37737 75297 37738 75297 37739 75297 37743 75298 37740 75298 37741 75298 37741 75299 37740 75299 37651 75299 37741 75300 37651 75300 37738 75300 37738 75301 37651 75301 37650 75301 37738 75302 37650 75302 37739 75302 42583 75303 42581 75303 37742 75303 37742 75304 42581 75304 37695 75304 37742 75305 37695 75305 37693 75305 37693 75306 37695 75306 37698 75306 37693 75307 37698 75307 37741 75307 37741 75308 37698 75308 37744 75308 37741 75309 37744 75309 37743 75309 37743 75310 37744 75310 37653 75310 37696 75311 42579 75311 37697 75311 37697 75312 42579 75312 37745 75312 37697 75313 37745 75313 37699 75313 37699 75314 37745 75314 37746 75314 37699 75315 37746 75315 37747 75315 37747 75316 37746 75316 37748 75316 37747 75317 37748 75317 37655 75317 37704 75318 37660 75318 37703 75318 37703 75319 37660 75319 37659 75319 37703 75320 37659 75320 37748 75320 37748 75321 37659 75321 37657 75321 37748 75322 37657 75322 37655 75322 37701 75323 37755 75323 37749 75323 37749 75324 37755 75324 37750 75324 37749 75325 37750 75325 37751 75325 37751 75326 37750 75326 37753 75326 37751 75327 37753 75327 37752 75327 37752 75328 37753 75328 37759 75328 37752 75329 37759 75329 37754 75329 37754 75330 37759 75330 37662 75330 37755 75331 42588 75331 37750 75331 37750 75332 42588 75332 37756 75332 37750 75333 37756 75333 37753 75333 37753 75334 37756 75334 37757 75334 37753 75335 37757 75335 37759 75335 37759 75336 37757 75336 37758 75336 37759 75337 37758 75337 37760 75337 37712 75338 37666 75338 37711 75338 37711 75339 37666 75339 37664 75339 37711 75340 37664 75340 37758 75340 37758 75341 37664 75341 37761 75341 37758 75342 37761 75342 37760 75342 37708 75343 42584 75343 37762 75343 37762 75344 42584 75344 37763 75344 37762 75345 37763 75345 37709 75345 37709 75346 37763 75346 37714 75346 37709 75347 37714 75347 37710 75347 37710 75348 37714 75348 37764 75348 37710 75349 37764 75349 37765 75349 37771 75350 37673 75350 37769 75350 37769 75351 37673 75351 37670 75351 37769 75352 37670 75352 37764 75352 37764 75353 37670 75353 37766 75353 37764 75354 37766 75354 37765 75354 42574 75355 42591 75355 37713 75355 37713 75356 42591 75356 37767 75356 37713 75357 37767 75357 37768 75357 37768 75358 37767 75358 37770 75358 37768 75359 37770 75359 37769 75359 37769 75360 37770 75360 37715 75360 37769 75361 37715 75361 37771 75361 37771 75362 37715 75362 37772 75362 42589 75363 37773 75363 37774 75363 37774 75364 37773 75364 37718 75364 37774 75365 37718 75365 37775 75365 37775 75366 37718 75366 37776 75366 37775 75367 37776 75367 37716 75367 37716 75368 37776 75368 37778 75368 37716 75369 37778 75369 37676 75369 37682 75370 37683 75370 37724 75370 37724 75371 37683 75371 37777 75371 37724 75372 37777 75372 37778 75372 37778 75373 37777 75373 37685 75373 37778 75374 37685 75374 37676 75374 37719 75375 37780 75375 37779 75375 37779 75376 37780 75376 37686 75376 37779 75377 37686 75377 37722 75377 37722 75378 37686 75378 37781 75378 37722 75379 37781 75379 37723 75379 37723 75380 37781 75380 37782 75380 37723 75381 37782 75381 37679 75381 37679 75382 37782 75382 37678 75382 37787 75383 37783 75383 37784 75383 37785 75384 37788 75384 37691 75384 37691 75385 37788 75385 37786 75385 37691 75386 37786 75386 37690 75386 37690 75387 37786 75387 37787 75387 37690 75388 37787 75388 37782 75388 37782 75389 37787 75389 37784 75389 37782 75390 37784 75390 37678 75390 42594 75391 37687 75391 37788 75391 37788 75392 37687 75392 42466 75392 37788 75393 42466 75393 37786 75393 37786 75394 42466 75394 37789 75394 37786 75395 37789 75395 37787 75395 37787 75396 37789 75396 42684 75396 37787 75397 42684 75397 37783 75397 37790 75398 42358 75398 37791 75398 37857 75399 42361 75399 37792 75399 42408 75400 42409 75400 37856 75400 37794 75401 37639 75401 37793 75401 42409 75402 37794 75402 37856 75402 37856 75403 37794 75403 37793 75403 37856 75404 37793 75404 37795 75404 37795 75405 37793 75405 37640 75405 37795 75406 37640 75406 37796 75406 37796 75407 37640 75407 37643 75407 37796 75408 37643 75408 37797 75408 37797 75409 37643 75409 37798 75409 37797 75410 37798 75410 37853 75410 37853 75411 37798 75411 37645 75411 37853 75412 37645 75412 37852 75412 37852 75413 37645 75413 37648 75413 37852 75414 37648 75414 37850 75414 37850 75415 37648 75415 37799 75415 37850 75416 37799 75416 37800 75416 37800 75417 37799 75417 37649 75417 37800 75418 37649 75418 37849 75418 37849 75419 37649 75419 37801 75419 37849 75420 37801 75420 37802 75420 37802 75421 37801 75421 37652 75421 37802 75422 37652 75422 37847 75422 37847 75423 37652 75423 37654 75423 37847 75424 37654 75424 37845 75424 37845 75425 37654 75425 37803 75425 37845 75426 37803 75426 37804 75426 37804 75427 37803 75427 37656 75427 37804 75428 37656 75428 37805 75428 37805 75429 37656 75429 37658 75429 37805 75430 37658 75430 37806 75430 37806 75431 37658 75431 37808 75431 37806 75432 37808 75432 37807 75432 37807 75433 37808 75433 37661 75433 37807 75434 37661 75434 37840 75434 37840 75435 37661 75435 37809 75435 37840 75436 37809 75436 37810 75436 37810 75437 37809 75437 37663 75437 37810 75438 37663 75438 37812 75438 37812 75439 37663 75439 37811 75439 37812 75440 37811 75440 37838 75440 37838 75441 37811 75441 37665 75441 37838 75442 37665 75442 37836 75442 37836 75443 37665 75443 37813 75443 37836 75444 37813 75444 37835 75444 37835 75445 37813 75445 37667 75445 37835 75446 37667 75446 37814 75446 37814 75447 37667 75447 37668 75447 37814 75448 37668 75448 37833 75448 37833 75449 37668 75449 37669 75449 37833 75450 37669 75450 37832 75450 37832 75451 37669 75451 37671 75451 37832 75452 37671 75452 37815 75452 37815 75453 37671 75453 37672 75453 37815 75454 37672 75454 37831 75454 37831 75455 37672 75455 37674 75455 37831 75456 37674 75456 37830 75456 37830 75457 37674 75457 37675 75457 37830 75458 37675 75458 37828 75458 37828 75459 37675 75459 37816 75459 37828 75460 37816 75460 37817 75460 37817 75461 37816 75461 37684 75461 37817 75462 37684 75462 37819 75462 37819 75463 37684 75463 37818 75463 37819 75464 37818 75464 37820 75464 37820 75465 37818 75465 37681 75465 37820 75466 37681 75466 37821 75466 37821 75467 37681 75467 37680 75467 37821 75468 37680 75468 37822 75468 37822 75469 37680 75469 37823 75469 37822 75470 37823 75470 37824 75470 37824 75471 37823 75471 37677 75471 37824 75472 37677 75472 37825 75472 37825 75473 37677 75473 42464 75473 37825 75474 37790 75474 37824 75474 37824 75475 37790 75475 37791 75475 37824 75476 37791 75476 37822 75476 37822 75477 37791 75477 37826 75477 37822 75478 37826 75478 37821 75478 37821 75479 37826 75479 37888 75479 37821 75480 37888 75480 37820 75480 37820 75481 37888 75481 37887 75481 37820 75482 37887 75482 37819 75482 37819 75483 37887 75483 37827 75483 37819 75484 37827 75484 37817 75484 37817 75485 37827 75485 37885 75485 37817 75486 37885 75486 37828 75486 37828 75487 37885 75487 37829 75487 37828 75488 37829 75488 37830 75488 37830 75489 37829 75489 37884 75489 37830 75490 37884 75490 37831 75490 37831 75491 37884 75491 37883 75491 37831 75492 37883 75492 37815 75492 37815 75493 37883 75493 37881 75493 37815 75494 37881 75494 37832 75494 37832 75495 37881 75495 37880 75495 37832 75496 37880 75496 37833 75496 37833 75497 37880 75497 37834 75497 37833 75498 37834 75498 37814 75498 37814 75499 37834 75499 37878 75499 37814 75500 37878 75500 37835 75500 37835 75501 37878 75501 37877 75501 37835 75502 37877 75502 37836 75502 37836 75503 37877 75503 37837 75503 37836 75504 37837 75504 37838 75504 37838 75505 37837 75505 37875 75505 37838 75506 37875 75506 37812 75506 37812 75507 37875 75507 37874 75507 37812 75508 37874 75508 37810 75508 37810 75509 37874 75509 37839 75509 37810 75510 37839 75510 37840 75510 37840 75511 37839 75511 37841 75511 37840 75512 37841 75512 37807 75512 37807 75513 37841 75513 37872 75513 37807 75514 37872 75514 37806 75514 37806 75515 37872 75515 37842 75515 37806 75516 37842 75516 37805 75516 37805 75517 37842 75517 37843 75517 37805 75518 37843 75518 37804 75518 37804 75519 37843 75519 37844 75519 37804 75520 37844 75520 37845 75520 37845 75521 37844 75521 37846 75521 37845 75522 37846 75522 37847 75522 37847 75523 37846 75523 37848 75523 37847 75524 37848 75524 37802 75524 37802 75525 37848 75525 37866 75525 37802 75526 37866 75526 37849 75526 37849 75527 37866 75527 37864 75527 37849 75528 37864 75528 37800 75528 37800 75529 37864 75529 37863 75529 37800 75530 37863 75530 37850 75530 37850 75531 37863 75531 37851 75531 37850 75532 37851 75532 37852 75532 37852 75533 37851 75533 37854 75533 37852 75534 37854 75534 37853 75534 37853 75535 37854 75535 37860 75535 37853 75536 37860 75536 37797 75536 37797 75537 37860 75537 37859 75537 37797 75538 37859 75538 37796 75538 37796 75539 37859 75539 37855 75539 37796 75540 37855 75540 37795 75540 37795 75541 37855 75541 37858 75541 37795 75542 37858 75542 37856 75542 37856 75543 37858 75543 37792 75543 37856 75544 37792 75544 42408 75544 42408 75545 37792 75545 42361 75545 42629 75546 37857 75546 42630 75546 42630 75547 37857 75547 37792 75547 42630 75548 37792 75548 42633 75548 42633 75549 37792 75549 37858 75549 42633 75550 37858 75550 42634 75550 42634 75551 37858 75551 37855 75551 42634 75552 37855 75552 42680 75552 42680 75553 37855 75553 37859 75553 42680 75554 37859 75554 42681 75554 42681 75555 37859 75555 37860 75555 42681 75556 37860 75556 37861 75556 37861 75557 37860 75557 37854 75557 37861 75558 37854 75558 42677 75558 42677 75559 37854 75559 37851 75559 42677 75560 37851 75560 42678 75560 42678 75561 37851 75561 37863 75561 42678 75562 37863 75562 37862 75562 37862 75563 37863 75563 37864 75563 37862 75564 37864 75564 37865 75564 37865 75565 37864 75565 37866 75565 37865 75566 37866 75566 37867 75566 37867 75567 37866 75567 37848 75567 37867 75568 37848 75568 42676 75568 42676 75569 37848 75569 37846 75569 42676 75570 37846 75570 37868 75570 37868 75571 37846 75571 37844 75571 37868 75572 37844 75572 37869 75572 37869 75573 37844 75573 37843 75573 37869 75574 37843 75574 37870 75574 37870 75575 37843 75575 37842 75575 37870 75576 37842 75576 37871 75576 37871 75577 37842 75577 37872 75577 37871 75578 37872 75578 42672 75578 42672 75579 37872 75579 37841 75579 42672 75580 37841 75580 42673 75580 42673 75581 37841 75581 37839 75581 42673 75582 37839 75582 37873 75582 37873 75583 37839 75583 37874 75583 37873 75584 37874 75584 42670 75584 42670 75585 37874 75585 37875 75585 42670 75586 37875 75586 42671 75586 42671 75587 37875 75587 37837 75587 42671 75588 37837 75588 37876 75588 37876 75589 37837 75589 37877 75589 37876 75590 37877 75590 42661 75590 42661 75591 37877 75591 37878 75591 42661 75592 37878 75592 37879 75592 37879 75593 37878 75593 37834 75593 37879 75594 37834 75594 42658 75594 42658 75595 37834 75595 37880 75595 42658 75596 37880 75596 37882 75596 37882 75597 37880 75597 37881 75597 37882 75598 37881 75598 42660 75598 42660 75599 37881 75599 37883 75599 42660 75600 37883 75600 42652 75600 42652 75601 37883 75601 37884 75601 42652 75602 37884 75602 42653 75602 42653 75603 37884 75603 37829 75603 42653 75604 37829 75604 37886 75604 37886 75605 37829 75605 37885 75605 37886 75606 37885 75606 42656 75606 42656 75607 37885 75607 37827 75607 42656 75608 37827 75608 42657 75608 42657 75609 37827 75609 37887 75609 42657 75610 37887 75610 42644 75610 42644 75611 37887 75611 37888 75611 42644 75612 37888 75612 42643 75612 42643 75613 37888 75613 37826 75613 42643 75614 37826 75614 37889 75614 37889 75615 37826 75615 37791 75615 37889 75616 37791 75616 42631 75616 42631 75617 37791 75617 42358 75617 43146 75618 42597 75618 37890 75618 37890 75619 42597 75619 42596 75619 37890 75620 42596 75620 37396 75620 37396 75621 42596 75621 42593 75621 37396 75622 42593 75622 37891 75622 37891 75623 42593 75623 42575 75623 37891 75624 42575 75624 37892 75624 37892 75625 42575 75625 37894 75625 37892 75626 37894 75626 37893 75626 37893 75627 37894 75627 37895 75627 37893 75628 37895 75628 37896 75628 37896 75629 37895 75629 37897 75629 37896 75630 37897 75630 37393 75630 37393 75631 37897 75631 42590 75631 37393 75632 42590 75632 37898 75632 37898 75633 42590 75633 37899 75633 37898 75634 37899 75634 37900 75634 37900 75635 37899 75635 42585 75635 37900 75636 42585 75636 37901 75636 37901 75637 42585 75637 42586 75637 37901 75638 42586 75638 37902 75638 37902 75639 42586 75639 42587 75639 37902 75640 42587 75640 37903 75640 37903 75641 42587 75641 42576 75641 37903 75642 42576 75642 37390 75642 37390 75643 42576 75643 42578 75643 37390 75644 42578 75644 37389 75644 37389 75645 42578 75645 42580 75645 37389 75646 42580 75646 37904 75646 37904 75647 42580 75647 42582 75647 37904 75648 42582 75648 37388 75648 37388 75649 42582 75649 37905 75649 37388 75650 37905 75650 43168 75650 43168 75651 37905 75651 42348 75651 37372 75652 37906 75652 37373 75652 37373 75653 37906 75653 37907 75653 37373 75654 37907 75654 37375 75654 37375 75655 37907 75655 42679 75655 37375 75656 42679 75656 37377 75656 37377 75657 42679 75657 37908 75657 37377 75658 37908 75658 37379 75658 37379 75659 37908 75659 42674 75659 37379 75660 42674 75660 37909 75660 37909 75661 42674 75661 42675 75661 37909 75662 42675 75662 37380 75662 37380 75663 42675 75663 37910 75663 37380 75664 37910 75664 37382 75664 37382 75665 37910 75665 37911 75665 37382 75666 37911 75666 37912 75666 37912 75667 37911 75667 37913 75667 37912 75668 37913 75668 37384 75668 37384 75669 37913 75669 42669 75669 37384 75670 42669 75670 37914 75670 37914 75671 42669 75671 37915 75671 37914 75672 37915 75672 37916 75672 37916 75673 37915 75673 42662 75673 37916 75674 42662 75674 37917 75674 37917 75675 42662 75675 42659 75675 37917 75676 42659 75676 37387 75676 37387 75677 42659 75677 37918 75677 37387 75678 37918 75678 37919 75678 37919 75679 37918 75679 42654 75679 37919 75680 42654 75680 37920 75680 37920 75681 42654 75681 42655 75681 37920 75682 42655 75682 37921 75682 37921 75683 42655 75683 42645 75683 37921 75684 42645 75684 42330 75684 42330 75685 42645 75685 42632 75685 42325 75686 42324 75686 41773 75686 41773 75687 42324 75687 42301 75687 42300 75688 42323 75688 37923 75688 37923 75689 42323 75689 37922 75689 37923 75690 37922 75690 40349 75690 40349 75691 37922 75691 42326 75691 40349 75692 42326 75692 37924 75692 37924 75693 42326 75693 42328 75693 37924 75694 42328 75694 37925 75694 37925 75695 42328 75695 37926 75695 37925 75696 37926 75696 40358 75696 40358 75697 37926 75697 37927 75697 40358 75698 37927 75698 37928 75698 37928 75699 37927 75699 42329 75699 42302 75700 42282 75700 41740 75700 41740 75701 42282 75701 41737 75701 41505 75702 37929 75702 41504 75702 41504 75703 37929 75703 42142 75703 42141 75704 41499 75704 42142 75704 42142 75705 41499 75705 41502 75705 42142 75706 41502 75706 41504 75706 41493 75707 37931 75707 37930 75707 37930 75708 37931 75708 37932 75708 37930 75709 37932 75709 42141 75709 42141 75710 37932 75710 41496 75710 42141 75711 41496 75711 41499 75711 41493 75712 37930 75712 41492 75712 41492 75713 37930 75713 42139 75713 41492 75714 42139 75714 37933 75714 37933 75715 42139 75715 37934 75715 37934 75716 42139 75716 37937 75716 37934 75717 37937 75717 37935 75717 37935 75718 37937 75718 37936 75718 37936 75719 37937 75719 37938 75719 37936 75720 37938 75720 37939 75720 41567 75721 42127 75721 37940 75721 37940 75722 42127 75722 37944 75722 37940 75723 37944 75723 37941 75723 41560 75724 37943 75724 37942 75724 37942 75725 37943 75725 41564 75725 37942 75726 41564 75726 37944 75726 37944 75727 41564 75727 41565 75727 37944 75728 41565 75728 37941 75728 41560 75729 37942 75729 37945 75729 37945 75730 37942 75730 42126 75730 37945 75731 42126 75731 37946 75731 37946 75732 42126 75732 37947 75732 37947 75733 42126 75733 37948 75733 37947 75734 37948 75734 41555 75734 41555 75735 37948 75735 37949 75735 37949 75736 37948 75736 42125 75736 37949 75737 42125 75737 41558 75737 37951 75738 37950 75738 42099 75738 37951 75739 42099 75739 37952 75739 37952 75740 42099 75740 37953 75740 37952 75741 37953 75741 41628 75741 41628 75742 37953 75742 41629 75742 41629 75743 37953 75743 42113 75743 41629 75744 42113 75744 37954 75744 37954 75745 42113 75745 41632 75745 41632 75746 42113 75746 42111 75746 41632 75747 42111 75747 41633 75747 41633 75748 42111 75748 42110 75748 41633 75749 42110 75749 42092 75749 42078 75750 42077 75750 37955 75750 37955 75751 42077 75751 37956 75751 37955 75752 37956 75752 37957 75752 37957 75753 37956 75753 41686 75753 41686 75754 37956 75754 37958 75754 41686 75755 37958 75755 37959 75755 37959 75756 37958 75756 42086 75756 37959 75757 42086 75757 41678 75757 41745 75758 42070 75758 41743 75758 41743 75759 42070 75759 42068 75759 41743 75760 42068 75760 37960 75760 37960 75761 42068 75761 42067 75761 37960 75762 42067 75762 41741 75762 40364 75763 37961 75763 40363 75763 40363 75764 37961 75764 37962 75764 40363 75765 37962 75765 40362 75765 40362 75766 37962 75766 42044 75766 40362 75767 42044 75767 40371 75767 40371 75768 42044 75768 37963 75768 40371 75769 37963 75769 40370 75769 40370 75770 37963 75770 37964 75770 40370 75771 37964 75771 40369 75771 40369 75772 37964 75772 42046 75772 40369 75773 42046 75773 42015 75773 42015 75774 42046 75774 42016 75774 37965 75775 42014 75775 40375 75775 40375 75776 42014 75776 37967 75776 40375 75777 37967 75777 37966 75777 37966 75778 37967 75778 43187 75778 37966 75779 43187 75779 37968 75779 37968 75780 43187 75780 37969 75780 37968 75781 37969 75781 37970 75781 37970 75782 37969 75782 37972 75782 37970 75783 37972 75783 37971 75783 37971 75784 37972 75784 43188 75784 37971 75785 43188 75785 37973 75785 37973 75786 43188 75786 43189 75786 40382 75787 42245 75787 40384 75787 40384 75788 42245 75788 42244 75788 40384 75789 42244 75789 40385 75789 40385 75790 42244 75790 37974 75790 40385 75791 37974 75791 40387 75791 40387 75792 37974 75792 42250 75792 40387 75793 42250 75793 37975 75793 37975 75794 42250 75794 42251 75794 37975 75795 42251 75795 40389 75795 40389 75796 42251 75796 42252 75796 40389 75797 42252 75797 40378 75797 40378 75798 42252 75798 42253 75798 40378 75799 42253 75799 42000 75799 42000 75800 42253 75800 42001 75800 37976 75801 37977 75801 40392 75801 40392 75802 37977 75802 42217 75802 40392 75803 42217 75803 37978 75803 37978 75804 42217 75804 37980 75804 37978 75805 37980 75805 37979 75805 37979 75806 37980 75806 42219 75806 37979 75807 42219 75807 37981 75807 37981 75808 42219 75808 42220 75808 37981 75809 42220 75809 37982 75809 37982 75810 42220 75810 37983 75810 37982 75811 37983 75811 40397 75811 40397 75812 37983 75812 41994 75812 40402 75813 41993 75813 37984 75813 37984 75814 41993 75814 42191 75814 37984 75815 42191 75815 37986 75815 37986 75816 42191 75816 37985 75816 37986 75817 37985 75817 37987 75817 37987 75818 37985 75818 37989 75818 37987 75819 37989 75819 37988 75819 37988 75820 37989 75820 42194 75820 37988 75821 42194 75821 37990 75821 37990 75822 42194 75822 37991 75822 37990 75823 37991 75823 40408 75823 40408 75824 37991 75824 41983 75824 37992 75825 37993 75825 40415 75825 40415 75826 37993 75826 37994 75826 40415 75827 37994 75827 37995 75827 37995 75828 37994 75828 42161 75828 37995 75829 42161 75829 37996 75829 37996 75830 42161 75830 42160 75830 37996 75831 42160 75831 40416 75831 40416 75832 42160 75832 42163 75832 40416 75833 42163 75833 40417 75833 40417 75834 42163 75834 42164 75834 40417 75835 42164 75835 37997 75835 37997 75836 42164 75836 42166 75836 40429 75837 42143 75837 40431 75837 40431 75838 42143 75838 42144 75838 40431 75839 42144 75839 40433 75839 40433 75840 42144 75840 42132 75840 40433 75841 42132 75841 37998 75841 37998 75842 42132 75842 42131 75842 37998 75843 42131 75843 37999 75843 37999 75844 42131 75844 42136 75844 37999 75845 42136 75845 40420 75845 40420 75846 42136 75846 42135 75846 40420 75847 42135 75847 38001 75847 38001 75848 42135 75848 38000 75848 38001 75849 38000 75849 38002 75849 38002 75850 38000 75850 38003 75850 40444 75851 42128 75851 38004 75851 38004 75852 42128 75852 38005 75852 38004 75853 38005 75853 40441 75853 40441 75854 38005 75854 42123 75854 40441 75855 42123 75855 40439 75855 40439 75856 42123 75856 38006 75856 40439 75857 38006 75857 40438 75857 40438 75858 38006 75858 38007 75858 40438 75859 38007 75859 40437 75859 40437 75860 38007 75860 38008 75860 40437 75861 38008 75861 40436 75861 40436 75862 38008 75862 42122 75862 38009 75863 38010 75863 38011 75863 38011 75864 38010 75864 42114 75864 38011 75865 42114 75865 40455 75865 40455 75866 42114 75866 42115 75866 40455 75867 42115 75867 40452 75867 40452 75868 42115 75868 42105 75868 40452 75869 42105 75869 40451 75869 40451 75870 42105 75870 42107 75870 40451 75871 42107 75871 38012 75871 38012 75872 42107 75872 38014 75872 38012 75873 38014 75873 38013 75873 38013 75874 38014 75874 38015 75874 40464 75875 41956 75875 40462 75875 40462 75876 41956 75876 38016 75876 40462 75877 38016 75877 40461 75877 40461 75878 38016 75878 42088 75878 40461 75879 42088 75879 38017 75879 38017 75880 42088 75880 42091 75880 38017 75881 42091 75881 40473 75881 40473 75882 42091 75882 42081 75882 40473 75883 42081 75883 40472 75883 40472 75884 42081 75884 42084 75884 40472 75885 42084 75885 41951 75885 41951 75886 42084 75886 42083 75886 38018 75887 42069 75887 40477 75887 40477 75888 42069 75888 42071 75888 40477 75889 42071 75889 38019 75889 38019 75890 42071 75890 38020 75890 38019 75891 38020 75891 40475 75891 40475 75892 38020 75892 42072 75892 40475 75893 42072 75893 40489 75893 40489 75894 42072 75894 38021 75894 40489 75895 38021 75895 40488 75895 40488 75896 38021 75896 38022 75896 40488 75897 38022 75897 40486 75897 40486 75898 38022 75898 41947 75898 38027 75899 38029 75899 38023 75899 38023 75900 38029 75900 41478 75900 38023 75901 41478 75901 38024 75901 38024 75902 41478 75902 41465 75902 38024 75903 41465 75903 43400 75903 38025 75904 41473 75904 41876 75904 41876 75905 41473 75905 41475 75905 41876 75906 41475 75906 42133 75906 42133 75907 41475 75907 38026 75907 42133 75908 38026 75908 38027 75908 38027 75909 38026 75909 38028 75909 38027 75910 38028 75910 38029 75910 41865 75911 41546 75911 41811 75911 41811 75912 41546 75912 38031 75912 41811 75913 38031 75913 38030 75913 38030 75914 38031 75914 41812 75914 41812 75915 38031 75915 41544 75915 41812 75916 41544 75916 43405 75916 43408 75917 41804 75917 41615 75917 41615 75918 41804 75918 38032 75918 42079 75919 41711 75919 41712 75919 42079 75920 41712 75920 38033 75920 38033 75921 41712 75921 41714 75921 38033 75922 41714 75922 38034 75922 38034 75923 41714 75923 38035 75923 38034 75924 38035 75924 38036 75924 42079 75925 41802 75925 41711 75925 41711 75926 41802 75926 38037 75926 41711 75927 38037 75927 41710 75927 38038 75928 41778 75928 42064 75928 38038 75929 42064 75929 38039 75929 42064 75930 38040 75930 38039 75930 38039 75931 38040 75931 41835 75931 38039 75932 41835 75932 41783 75932 41401 75933 37501 75933 38041 75933 41401 75934 38041 75934 42912 75934 42912 75935 38041 75935 37498 75935 42912 75936 37498 75936 42914 75936 42914 75937 37498 75937 38042 75937 42914 75938 38042 75938 38043 75938 38043 75939 38042 75939 38044 75939 38043 75940 38044 75940 42916 75940 42916 75941 38044 75941 37495 75941 42916 75942 37495 75942 42917 75942 42917 75943 37495 75943 38045 75943 42917 75944 38045 75944 38046 75944 38046 75945 38045 75945 38047 75945 38046 75946 38047 75946 38048 75946 38048 75947 38047 75947 38049 75947 38048 75948 38049 75948 42921 75948 42921 75949 38049 75949 37491 75949 42921 75950 37491 75950 38050 75950 38050 75951 37491 75951 37490 75951 38050 75952 37490 75952 38051 75952 38051 75953 37490 75953 38052 75953 38051 75954 38052 75954 42888 75954 42888 75955 38052 75955 38053 75955 42888 75956 38053 75956 42889 75956 42889 75957 38053 75957 37488 75957 42889 75958 37488 75958 42892 75958 42892 75959 37488 75959 37486 75959 42892 75960 37486 75960 42893 75960 42893 75961 37486 75961 37484 75961 42893 75962 37484 75962 42894 75962 42894 75963 37484 75963 37483 75963 42894 75964 37483 75964 38054 75964 41383 75965 41384 75965 38055 75965 38055 75966 41384 75966 43024 75966 38055 75967 43024 75967 38056 75967 38056 75968 43024 75968 43026 75968 38056 75969 43026 75969 37391 75969 37391 75970 43026 75970 38058 75970 37391 75971 38058 75971 38057 75971 38057 75972 38058 75972 43027 75972 38057 75973 43027 75973 38059 75973 38059 75974 43027 75974 38061 75974 38059 75975 38061 75975 38060 75975 38060 75976 38061 75976 43030 75976 38060 75977 43030 75977 38062 75977 38062 75978 43030 75978 43032 75978 38062 75979 43032 75979 38063 75979 38063 75980 43032 75980 43034 75980 38063 75981 43034 75981 37392 75981 37392 75982 43034 75982 43036 75982 37392 75983 43036 75983 37394 75983 37394 75984 43036 75984 43037 75984 37394 75985 43037 75985 38064 75985 38064 75986 43037 75986 43038 75986 38064 75987 43038 75987 38065 75987 38065 75988 43038 75988 38067 75988 38065 75989 38067 75989 38066 75989 38066 75990 38067 75990 38068 75990 38066 75991 38068 75991 37395 75991 37395 75992 38068 75992 43042 75992 37395 75993 43042 75993 37397 75993 37397 75994 43042 75994 43043 75994 37397 75995 43043 75995 38069 75995 38069 75996 43043 75996 43044 75996 38069 75997 43044 75997 38070 75997 38070 75998 43044 75998 43045 75998 43067 75999 43092 75999 38071 75999 38071 76000 43092 76000 38072 76000 38071 76001 38072 76001 38073 76001 38073 76002 38072 76002 43094 76002 38073 76003 43094 76003 37452 76003 37452 76004 43094 76004 43095 76004 37452 76005 43095 76005 38074 76005 38074 76006 43095 76006 43096 76006 38074 76007 43096 76007 38075 76007 38075 76008 43096 76008 38076 76008 38075 76009 38076 76009 38077 76009 38077 76010 38076 76010 43099 76010 38077 76011 43099 76011 37455 76011 37455 76012 43099 76012 38078 76012 37455 76013 38078 76013 37456 76013 37456 76014 38078 76014 43068 76014 37456 76015 43068 76015 38080 76015 38080 76016 43068 76016 38079 76016 38080 76017 38079 76017 38081 76017 38081 76018 38079 76018 38082 76018 38081 76019 38082 76019 38083 76019 38083 76020 38082 76020 43070 76020 38083 76021 43070 76021 37459 76021 37459 76022 43070 76022 38084 76022 37459 76023 38084 76023 37460 76023 37460 76024 38084 76024 38085 76024 37460 76025 38085 76025 38086 76025 38086 76026 38085 76026 43073 76026 38086 76027 43073 76027 37462 76027 37462 76028 43073 76028 43075 76028 37462 76029 43075 76029 37464 76029 37464 76030 43075 76030 43076 76030 37464 76031 43076 76031 37465 76031 37465 76032 43076 76032 38088 76032 37465 76033 38088 76033 38087 76033 38087 76034 38088 76034 41344 76034 43077 76035 38089 76035 38090 76035 43077 76036 38090 76036 38091 76036 38091 76037 38090 76037 37447 76037 38091 76038 37447 76038 38092 76038 38092 76039 37447 76039 37445 76039 38092 76040 37445 76040 43081 76040 43081 76041 37445 76041 37441 76041 43081 76042 37441 76042 38093 76042 38093 76043 37441 76043 37440 76043 38093 76044 37440 76044 38094 76044 38094 76045 37440 76045 38095 76045 38094 76046 38095 76046 43083 76046 43083 76047 38095 76047 38096 76047 43083 76048 38096 76048 43084 76048 43084 76049 38096 76049 37435 76049 43084 76050 37435 76050 38097 76050 38097 76051 37435 76051 38098 76051 38097 76052 38098 76052 43085 76052 43085 76053 38098 76053 38099 76053 43085 76054 38099 76054 38100 76054 38100 76055 38099 76055 37425 76055 38100 76056 37425 76056 38101 76056 38101 76057 37425 76057 37426 76057 38101 76058 37426 76058 38102 76058 38102 76059 37426 76059 37424 76059 38102 76060 37424 76060 38103 76060 38103 76061 37424 76061 37423 76061 38103 76062 37423 76062 43089 76062 43089 76063 37423 76063 37418 76063 43089 76064 37418 76064 38104 76064 38104 76065 37418 76065 38105 76065 38104 76066 38105 76066 43090 76066 43090 76067 38105 76067 38106 76067 43090 76068 38106 76068 43091 76068 43091 76069 38106 76069 37413 76069 43091 76070 37413 76070 41320 76070 41316 76071 41318 76071 37411 76071 37411 76072 41318 76072 41116 76072 37411 76073 41116 76073 38107 76073 38107 76074 41116 76074 38108 76074 38107 76075 38108 76075 38110 76075 38110 76076 38108 76076 38109 76076 38110 76077 38109 76077 38111 76077 38111 76078 38109 76078 38112 76078 38111 76079 38112 76079 38113 76079 38113 76080 38112 76080 41119 76080 38113 76081 41119 76081 37408 76081 37408 76082 41119 76082 41118 76082 37408 76083 41118 76083 37407 76083 37407 76084 41118 76084 41137 76084 37407 76085 41137 76085 38114 76085 38114 76086 41137 76086 41136 76086 38114 76087 41136 76087 37404 76087 37404 76088 41136 76088 38115 76088 37404 76089 38115 76089 38116 76089 38116 76090 38115 76090 41135 76090 38116 76091 41135 76091 38117 76091 38117 76092 41135 76092 38118 76092 38117 76093 38118 76093 38119 76093 38119 76094 38118 76094 41134 76094 38119 76095 41134 76095 37402 76095 37402 76096 41134 76096 41114 76096 37402 76097 41114 76097 37400 76097 37400 76098 41114 76098 38120 76098 37400 76099 38120 76099 37399 76099 37399 76100 38120 76100 38121 76100 37399 76101 38121 76101 37398 76101 37398 76102 38121 76102 38122 76102 43145 76103 41297 76103 38123 76103 38123 76104 41297 76104 38124 76104 38123 76105 38124 76105 37401 76105 37401 76106 38124 76106 38125 76106 37401 76107 38125 76107 38126 76107 38126 76108 38125 76108 38127 76108 38126 76109 38127 76109 37403 76109 37403 76110 38127 76110 38128 76110 37403 76111 38128 76111 38129 76111 38129 76112 38128 76112 38130 76112 38129 76113 38130 76113 38131 76113 38131 76114 38130 76114 38132 76114 38131 76115 38132 76115 37405 76115 37405 76116 38132 76116 38133 76116 37405 76117 38133 76117 37406 76117 37406 76118 38133 76118 38134 76118 37406 76119 38134 76119 38135 76119 38135 76120 38134 76120 42869 76120 38135 76121 42869 76121 38136 76121 38136 76122 42869 76122 38137 76122 38136 76123 38137 76123 38138 76123 38138 76124 38137 76124 42844 76124 38138 76125 42844 76125 37409 76125 37409 76126 42844 76126 38139 76126 37409 76127 38139 76127 38141 76127 38141 76128 38139 76128 38140 76128 38141 76129 38140 76129 37410 76129 37410 76130 38140 76130 38142 76130 37410 76131 38142 76131 37412 76131 37412 76132 38142 76132 42847 76132 37412 76133 42847 76133 38143 76133 38143 76134 42847 76134 41278 76134 41275 76135 42895 76135 37502 76135 37502 76136 42895 76136 42896 76136 37502 76137 42896 76137 38144 76137 38144 76138 42896 76138 38145 76138 38144 76139 38145 76139 37505 76139 37505 76140 38145 76140 42898 76140 37505 76141 42898 76141 37506 76141 37506 76142 42898 76142 38146 76142 37506 76143 38146 76143 37507 76143 37507 76144 38146 76144 42900 76144 37507 76145 42900 76145 38147 76145 38147 76146 42900 76146 38148 76146 38147 76147 38148 76147 37509 76147 37509 76148 38148 76148 42904 76148 37509 76149 42904 76149 38149 76149 38149 76150 42904 76150 38150 76150 38149 76151 38150 76151 37511 76151 37511 76152 38150 76152 38151 76152 37511 76153 38151 76153 37512 76153 37512 76154 38151 76154 42906 76154 37512 76155 42906 76155 37513 76155 37513 76156 42906 76156 42907 76156 37513 76157 42907 76157 38152 76157 38152 76158 42907 76158 42908 76158 38152 76159 42908 76159 37515 76159 37515 76160 42908 76160 38154 76160 37515 76161 38154 76161 38153 76161 38153 76162 38154 76162 38155 76162 38153 76163 38155 76163 37517 76163 37517 76164 38155 76164 38156 76164 37517 76165 38156 76165 42871 76165 42871 76166 38156 76166 38157 76166 41265 76167 38158 76167 37482 76167 41265 76168 37482 76168 38159 76168 38159 76169 37482 76169 37480 76169 38159 76170 37480 76170 38160 76170 38160 76171 37480 76171 37479 76171 38160 76172 37479 76172 38161 76172 38161 76173 37479 76173 38163 76173 38161 76174 38163 76174 38162 76174 38162 76175 38163 76175 37478 76175 38162 76176 37478 76176 42939 76176 42939 76177 37478 76177 38164 76177 42939 76178 38164 76178 38165 76178 38165 76179 38164 76179 38166 76179 38165 76180 38166 76180 38168 76180 38168 76181 38166 76181 38167 76181 38168 76182 38167 76182 38169 76182 38169 76183 38167 76183 37476 76183 38169 76184 37476 76184 42940 76184 42940 76185 37476 76185 38170 76185 42940 76186 38170 76186 38171 76186 38171 76187 38170 76187 37472 76187 38171 76188 37472 76188 38172 76188 38172 76189 37472 76189 37471 76189 38172 76190 37471 76190 42944 76190 42944 76191 37471 76191 38174 76191 42944 76192 38174 76192 38173 76192 38173 76193 38174 76193 38175 76193 38173 76194 38175 76194 42945 76194 42945 76195 38175 76195 37469 76195 42945 76196 37469 76196 42946 76196 42946 76197 37469 76197 38176 76197 42946 76198 38176 76198 38177 76198 38177 76199 38176 76199 42975 76199 38177 76200 42975 76200 42948 76200 41188 76201 41242 76201 38178 76201 38178 76202 41242 76202 41166 76202 41173 76203 41183 76203 38179 76203 38179 76204 41183 76204 38180 76204 41185 76205 41241 76205 38181 76205 38181 76206 41241 76206 38182 76206 38181 76207 38182 76207 41187 76207 41187 76208 38182 76208 41172 76208 41187 76209 41172 76209 38180 76209 38180 76210 41172 76210 38183 76210 38180 76211 38183 76211 38179 76211 38184 76212 38185 76212 41211 76212 41211 76213 38185 76213 38186 76213 38187 76214 41204 76214 43406 76214 43406 76215 41204 76215 41161 76215 41144 76216 41229 76216 38188 76216 41144 76217 38188 76217 41143 76217 41143 76218 38188 76218 38189 76218 41143 76219 38189 76219 41141 76219 41141 76220 38189 76220 41213 76220 41141 76221 41213 76221 41140 76221 41229 76222 38190 76222 38188 76222 38188 76223 38190 76223 41057 76223 38188 76224 41057 76224 38189 76224 38189 76225 41057 76225 41214 76225 38189 76226 41214 76226 41213 76226 38192 76227 41052 76227 41236 76227 41231 76228 38191 76228 41233 76228 41233 76229 38191 76229 38192 76229 41233 76230 38192 76230 41234 76230 41234 76231 38192 76231 41236 76231 41211 76232 38186 76232 41212 76232 41212 76233 38186 76233 38193 76233 41210 76234 41206 76234 38186 76234 38186 76235 41206 76235 38193 76235 41204 76236 38187 76236 41205 76236 41205 76237 38187 76237 40750 76237 41244 76238 38178 76238 43331 76238 43331 76239 38178 76239 43332 76239 41104 76240 41016 76240 38194 76240 38194 76241 41016 76241 41103 76241 38195 76242 38196 76242 41197 76242 41197 76243 38196 76243 40732 76243 41063 76244 41062 76244 38218 76244 38218 76245 41062 76245 38198 76245 41007 76246 38218 76246 38197 76246 38197 76247 38218 76247 38198 76247 38212 76248 41184 76248 38214 76248 38214 76249 41184 76249 38199 76249 38214 76250 38199 76250 38215 76250 38215 76251 38199 76251 41186 76251 38215 76252 41186 76252 41060 76252 41060 76253 41186 76253 38200 76253 41061 76254 41180 76254 38202 76254 38202 76255 41180 76255 38201 76255 38202 76256 38201 76256 38203 76256 38203 76257 38201 76257 38204 76257 38203 76258 38204 76258 41039 76258 41039 76259 38204 76259 41182 76259 41028 76260 38205 76260 40652 76260 40652 76261 38205 76261 40653 76261 38211 76262 38207 76262 38206 76262 38206 76263 38207 76263 38208 76263 38208 76264 38207 76264 41056 76264 38208 76265 41056 76265 38209 76265 41026 76266 41058 76266 40693 76266 40693 76267 41058 76267 38211 76267 40693 76268 38211 76268 38210 76268 38210 76269 38211 76269 38206 76269 41049 76270 41048 76270 41104 76270 41104 76271 41048 76271 41016 76271 41077 76272 41012 76272 38212 76272 41077 76273 38212 76273 38213 76273 38213 76274 38212 76274 38214 76274 38213 76275 38214 76275 41075 76275 41075 76276 38214 76276 41074 76276 41074 76277 38214 76277 38215 76277 41074 76278 38215 76278 38216 76278 38216 76279 38215 76279 41060 76279 38216 76280 41060 76280 41014 76280 41085 76281 41063 76281 38217 76281 38217 76282 41063 76282 38218 76282 38217 76283 38218 76283 41080 76283 41006 76284 40480 76284 40478 76284 41006 76285 40478 76285 40587 76285 40587 76286 40478 76286 40476 76286 40587 76287 40476 76287 40588 76287 40588 76288 40476 76288 38219 76288 40588 76289 38219 76289 38220 76289 38220 76290 38219 76290 38221 76290 38220 76291 38221 76291 38222 76291 38222 76292 38221 76292 38223 76292 38222 76293 38223 76293 38224 76293 38224 76294 38223 76294 38226 76294 38224 76295 38226 76295 38225 76295 38225 76296 38226 76296 40487 76296 38225 76297 40487 76297 38227 76297 41003 76298 41002 76298 38228 76298 41003 76299 38228 76299 38229 76299 38229 76300 38228 76300 40463 76300 38229 76301 40463 76301 38231 76301 38231 76302 40463 76302 38230 76302 38231 76303 38230 76303 38232 76303 38232 76304 38230 76304 38233 76304 38232 76305 38233 76305 40592 76305 40592 76306 38233 76306 38234 76306 40592 76307 38234 76307 38235 76307 38235 76308 38234 76308 40474 76308 38235 76309 40474 76309 38236 76309 38236 76310 40474 76310 40995 76310 38236 76311 40995 76311 40594 76311 40993 76312 40456 76312 38237 76312 40993 76313 38237 76313 38522 76313 38522 76314 38237 76314 38239 76314 38522 76315 38239 76315 38238 76315 38238 76316 38239 76316 40454 76316 38238 76317 40454 76317 38511 76317 38511 76318 40454 76318 40453 76318 38511 76319 40453 76319 38510 76319 38510 76320 40453 76320 38240 76320 38510 76321 38240 76321 38512 76321 38512 76322 38240 76322 38241 76322 38512 76323 38241 76323 38513 76323 38513 76324 38241 76324 40450 76324 38513 76325 40450 76325 38514 76325 40989 76326 40443 76326 40442 76326 40989 76327 40442 76327 38242 76327 38242 76328 40442 76328 38243 76328 38242 76329 38243 76329 38245 76329 38245 76330 38243 76330 38244 76330 38245 76331 38244 76331 38528 76331 38528 76332 38244 76332 40440 76332 38528 76333 40440 76333 38530 76333 38530 76334 40440 76334 38246 76334 38530 76335 38246 76335 38247 76335 38247 76336 38246 76336 38249 76336 38247 76337 38249 76337 38248 76337 38248 76338 38249 76338 40983 76338 38248 76339 40983 76339 38534 76339 38556 76340 40428 76340 40430 76340 38556 76341 40430 76341 38551 76341 38551 76342 40430 76342 40432 76342 38551 76343 40432 76343 38552 76343 38552 76344 40432 76344 38250 76344 38552 76345 38250 76345 38251 76345 38251 76346 38250 76346 40419 76346 38251 76347 40419 76347 38554 76347 38554 76348 40419 76348 38252 76348 38554 76349 38252 76349 38555 76349 38555 76350 38252 76350 38253 76350 38555 76351 38253 76351 38544 76351 38544 76352 38253 76352 40421 76352 38544 76353 40421 76353 38254 76353 38255 76354 38256 76354 38259 76354 40976 76355 40414 76355 38566 76355 38566 76356 40414 76356 38257 76356 38259 76357 38256 76357 40414 76357 40414 76358 38256 76358 38258 76358 40414 76359 38258 76359 38257 76359 38255 76360 38259 76360 38567 76360 38567 76361 38259 76361 38260 76361 38567 76362 38260 76362 38568 76362 38568 76363 38260 76363 38261 76363 38568 76364 38261 76364 38563 76364 38563 76365 38261 76365 38262 76365 38563 76366 38262 76366 38263 76366 38263 76367 38262 76367 40968 76367 38263 76368 40968 76368 40969 76368 38584 76369 40403 76369 40401 76369 38584 76370 40401 76370 38264 76370 38264 76371 40401 76371 40400 76371 38264 76372 40400 76372 38586 76372 38586 76373 40400 76373 40399 76373 38586 76374 40399 76374 38587 76374 38587 76375 40399 76375 38265 76375 38587 76376 38265 76376 38588 76376 38588 76377 38265 76377 40398 76377 38588 76378 40398 76378 38576 76378 38576 76379 40398 76379 40409 76379 38576 76380 40409 76380 38266 76380 38266 76381 40409 76381 38267 76381 38266 76382 38267 76382 38577 76382 40962 76383 40961 76383 38268 76383 40962 76384 38268 76384 38494 76384 38494 76385 38268 76385 40391 76385 38494 76386 40391 76386 38495 76386 38495 76387 40391 76387 38269 76387 38495 76388 38269 76388 38270 76388 38270 76389 38269 76389 38271 76389 38270 76390 38271 76390 38272 76390 38272 76391 38271 76391 40390 76391 38272 76392 40390 76392 38273 76392 38273 76393 40390 76393 38274 76393 38273 76394 38274 76394 38276 76394 38276 76395 38274 76395 38275 76395 38276 76396 38275 76396 40953 76396 38278 76397 38277 76397 40383 76397 38278 76398 40383 76398 40505 76398 40505 76399 40383 76399 38279 76399 40505 76400 38279 76400 40513 76400 40513 76401 38279 76401 40386 76401 40513 76402 40386 76402 40516 76402 40516 76403 40386 76403 38280 76403 40516 76404 38280 76404 38281 76404 38281 76405 38280 76405 40388 76405 38281 76406 40388 76406 38282 76406 38282 76407 40388 76407 40377 76407 38282 76408 40377 76408 38283 76408 38283 76409 40377 76409 38284 76409 38283 76410 38284 76410 38285 76410 40539 76411 40946 76411 38286 76411 40539 76412 38286 76412 38288 76412 38288 76413 38286 76413 38287 76413 38288 76414 38287 76414 38289 76414 38289 76415 38287 76415 38290 76415 38289 76416 38290 76416 40531 76416 40531 76417 38290 76417 38291 76417 40531 76418 38291 76418 40533 76418 40533 76419 38291 76419 38292 76419 40533 76420 38292 76420 40532 76420 40532 76421 38292 76421 38293 76421 40532 76422 38293 76422 40540 76422 40540 76423 38293 76423 40374 76423 40540 76424 40374 76424 40541 76424 40940 76425 40365 76425 38294 76425 40940 76426 38294 76426 40549 76426 40549 76427 38294 76427 38295 76427 40549 76428 38295 76428 38297 76428 38297 76429 38295 76429 38296 76429 38297 76430 38296 76430 38298 76430 38298 76431 38296 76431 40361 76431 38298 76432 40361 76432 38299 76432 38299 76433 40361 76433 38300 76433 38299 76434 38300 76434 40551 76434 40551 76435 38300 76435 38301 76435 40551 76436 38301 76436 40563 76436 40563 76437 38301 76437 38302 76437 40563 76438 38302 76438 40561 76438 40931 76439 40350 76439 38303 76439 40931 76440 38303 76440 40564 76440 40564 76441 38303 76441 38304 76441 40564 76442 38304 76442 40565 76442 40565 76443 38304 76443 40348 76443 40565 76444 40348 76444 38305 76444 38305 76445 40348 76445 38306 76445 38305 76446 38306 76446 40568 76446 40568 76447 38306 76447 40360 76447 40568 76448 40360 76448 40569 76448 40569 76449 40360 76449 40359 76449 40569 76450 40359 76450 38307 76450 38307 76451 40359 76451 38308 76451 38307 76452 38308 76452 38309 76452 38610 76453 38311 76453 38310 76453 38310 76454 38311 76454 38312 76454 38310 76455 38312 76455 38608 76455 38608 76456 38312 76456 39186 76456 38608 76457 39186 76457 38606 76457 38606 76458 39186 76458 38313 76458 38606 76459 38313 76459 38314 76459 38314 76460 38313 76460 39184 76460 38314 76461 39184 76461 38603 76461 38603 76462 39184 76462 38315 76462 38603 76463 38315 76463 38602 76463 38602 76464 38315 76464 39181 76464 38602 76465 39181 76465 38600 76465 38600 76466 39181 76466 39180 76466 38600 76467 39180 76467 38316 76467 38316 76468 39180 76468 39177 76468 38316 76469 39177 76469 38599 76469 38599 76470 39177 76470 38318 76470 38599 76471 38318 76471 38317 76471 38317 76472 38318 76472 38320 76472 38317 76473 38320 76473 38319 76473 38319 76474 38320 76474 38321 76474 38319 76475 38321 76475 38596 76475 38596 76476 38321 76476 38323 76476 38596 76477 38323 76477 38322 76477 38322 76478 38323 76478 38324 76478 38322 76479 38324 76479 38594 76479 38594 76480 38324 76480 39172 76480 38594 76481 39172 76481 38593 76481 38593 76482 39172 76482 39171 76482 40912 76483 38466 76483 38326 76483 40912 76484 38326 76484 38325 76484 38325 76485 38326 76485 38471 76485 38325 76486 38471 76486 43442 76486 43442 76487 38471 76487 38470 76487 43442 76488 38470 76488 43441 76488 43441 76489 38470 76489 38327 76489 43441 76490 38327 76490 43440 76490 43440 76491 38327 76491 38474 76491 43440 76492 38474 76492 43439 76492 43439 76493 38474 76493 38476 76493 43439 76494 38476 76494 43425 76494 43425 76495 38476 76495 38328 76495 43425 76496 38328 76496 43432 76496 43432 76497 38328 76497 38480 76497 43432 76498 38480 76498 38329 76498 38329 76499 38480 76499 38330 76499 38329 76500 38330 76500 43433 76500 43433 76501 38330 76501 38483 76501 43433 76502 38483 76502 43428 76502 43428 76503 38483 76503 38484 76503 43428 76504 38484 76504 43426 76504 43426 76505 38484 76505 38331 76505 43426 76506 38331 76506 38332 76506 38332 76507 38331 76507 38333 76507 38332 76508 38333 76508 38334 76508 38334 76509 38333 76509 38486 76509 38334 76510 38486 76510 43461 76510 43461 76511 38486 76511 38335 76511 43461 76512 38335 76512 43460 76512 43460 76513 38335 76513 38490 76513 43460 76514 38490 76514 38336 76514 38336 76515 38490 76515 38337 76515 38336 76516 38337 76516 38338 76516 38338 76517 38337 76517 40766 76517 38338 76518 40766 76518 43456 76518 38395 76519 38343 76519 38339 76519 38340 76520 41079 76520 38341 76520 38341 76521 41079 76521 41078 76521 38341 76522 41078 76522 41082 76522 38342 76523 38339 76523 40838 76523 40838 76524 38339 76524 38343 76524 40838 76525 38343 76525 40840 76525 38339 76526 40795 76526 38395 76526 38395 76527 40795 76527 38344 76527 38395 76528 38344 76528 38396 76528 38396 76529 38344 76529 40794 76529 38396 76530 40794 76530 38345 76530 40794 76531 40792 76531 38345 76531 38345 76532 40792 76532 38346 76532 38345 76533 38346 76533 38397 76533 38397 76534 38346 76534 38347 76534 38397 76535 38347 76535 38348 76535 38347 76536 40791 76536 38348 76536 38348 76537 40791 76537 38349 76537 38348 76538 38349 76538 38350 76538 38350 76539 38349 76539 38351 76539 38350 76540 38351 76540 38352 76540 38351 76541 40789 76541 38352 76541 38352 76542 40789 76542 40788 76542 38352 76543 40788 76543 38399 76543 38399 76544 40788 76544 38353 76544 38399 76545 38353 76545 38401 76545 38401 76546 38353 76546 38354 76546 38401 76547 38354 76547 38402 76547 38354 76548 38355 76548 38402 76548 38402 76549 38355 76549 38357 76549 38402 76550 38357 76550 38356 76550 38356 76551 38357 76551 40787 76551 38356 76552 40787 76552 38359 76552 40787 76553 38358 76553 38359 76553 38359 76554 38358 76554 38360 76554 38359 76555 38360 76555 38361 76555 38361 76556 38360 76556 40786 76556 38361 76557 40786 76557 38405 76557 40786 76558 38362 76558 38405 76558 38405 76559 38362 76559 40785 76559 38405 76560 40785 76560 38406 76560 38406 76561 40785 76561 38363 76561 38406 76562 38363 76562 38407 76562 38363 76563 40782 76563 38407 76563 38407 76564 40782 76564 40783 76564 38407 76565 40783 76565 38408 76565 38408 76566 40783 76566 40784 76566 38408 76567 40784 76567 38409 76567 40784 76568 38364 76568 38409 76568 38409 76569 38364 76569 38366 76569 38409 76570 38366 76570 38365 76570 38365 76571 38366 76571 38367 76571 38365 76572 38367 76572 38412 76572 38367 76573 40780 76573 38412 76573 38412 76574 40780 76574 38368 76574 38412 76575 38368 76575 38413 76575 38413 76576 38368 76576 38369 76576 38413 76577 38369 76577 38370 76577 38370 76578 38369 76578 38371 76578 38370 76579 38371 76579 38372 76579 38371 76580 38373 76580 38372 76580 38372 76581 38373 76581 38375 76581 38372 76582 38375 76582 38374 76582 38374 76583 38375 76583 40777 76583 38374 76584 40777 76584 38415 76584 38415 76585 40777 76585 38376 76585 38415 76586 38376 76586 38416 76586 38416 76587 38376 76587 38377 76587 38416 76588 38377 76588 38379 76588 38377 76589 40775 76589 38379 76589 38379 76590 40775 76590 38378 76590 38379 76591 38378 76591 38380 76591 38380 76592 38378 76592 38381 76592 38380 76593 38381 76593 38383 76593 38381 76594 38382 76594 38383 76594 38383 76595 38382 76595 38384 76595 38383 76596 38384 76596 38418 76596 38418 76597 38384 76597 38385 76597 38418 76598 38385 76598 38386 76598 38385 76599 40772 76599 38386 76599 38386 76600 40772 76600 38387 76600 38386 76601 38387 76601 38421 76601 38421 76602 38387 76602 40771 76602 38421 76603 40771 76603 38389 76603 40771 76604 38388 76604 38389 76604 38389 76605 38388 76605 38390 76605 38389 76606 38390 76606 38391 76606 38391 76607 38390 76607 40769 76607 38391 76608 40769 76608 38392 76608 38392 76609 40769 76609 40768 76609 38392 76610 40768 76610 38425 76610 40768 76611 40767 76611 38425 76611 38425 76612 40767 76612 38393 76612 38425 76613 38393 76613 38426 76613 38426 76614 38393 76614 40765 76614 38426 76615 40765 76615 40835 76615 40835 76616 40765 76616 38394 76616 41082 76617 40840 76617 38341 76617 38341 76618 40840 76618 38343 76618 38341 76619 38343 76619 38463 76619 38463 76620 38343 76620 38395 76620 38463 76621 38395 76621 38462 76621 38462 76622 38395 76622 38396 76622 38462 76623 38396 76623 38460 76623 38460 76624 38396 76624 38345 76624 38460 76625 38345 76625 38458 76625 38458 76626 38345 76626 38397 76626 38458 76627 38397 76627 38457 76627 38457 76628 38397 76628 38348 76628 38457 76629 38348 76629 38398 76629 38398 76630 38348 76630 38350 76630 38398 76631 38350 76631 38456 76631 38456 76632 38350 76632 38352 76632 38456 76633 38352 76633 38454 76633 38454 76634 38352 76634 38399 76634 38454 76635 38399 76635 38453 76635 38453 76636 38399 76636 38401 76636 38453 76637 38401 76637 38400 76637 38400 76638 38401 76638 38402 76638 38400 76639 38402 76639 38451 76639 38451 76640 38402 76640 38356 76640 38451 76641 38356 76641 38403 76641 38403 76642 38356 76642 38359 76642 38403 76643 38359 76643 38404 76643 38404 76644 38359 76644 38361 76644 38404 76645 38361 76645 38448 76645 38448 76646 38361 76646 38405 76646 38448 76647 38405 76647 38447 76647 38447 76648 38405 76648 38406 76648 38447 76649 38406 76649 38446 76649 38446 76650 38406 76650 38407 76650 38446 76651 38407 76651 38445 76651 38445 76652 38407 76652 38408 76652 38445 76653 38408 76653 38444 76653 38444 76654 38408 76654 38409 76654 38444 76655 38409 76655 38410 76655 38410 76656 38409 76656 38365 76656 38410 76657 38365 76657 38411 76657 38411 76658 38365 76658 38412 76658 38411 76659 38412 76659 38442 76659 38442 76660 38412 76660 38413 76660 38442 76661 38413 76661 38441 76661 38441 76662 38413 76662 38370 76662 38441 76663 38370 76663 38414 76663 38414 76664 38370 76664 38372 76664 38414 76665 38372 76665 38439 76665 38439 76666 38372 76666 38374 76666 38439 76667 38374 76667 38438 76667 38438 76668 38374 76668 38415 76668 38438 76669 38415 76669 38437 76669 38437 76670 38415 76670 38416 76670 38437 76671 38416 76671 38436 76671 38436 76672 38416 76672 38379 76672 38436 76673 38379 76673 38417 76673 38417 76674 38379 76674 38380 76674 38417 76675 38380 76675 38435 76675 38435 76676 38380 76676 38383 76676 38435 76677 38383 76677 38433 76677 38433 76678 38383 76678 38418 76678 38433 76679 38418 76679 38419 76679 38419 76680 38418 76680 38386 76680 38419 76681 38386 76681 38420 76681 38420 76682 38386 76682 38421 76682 38420 76683 38421 76683 38422 76683 38422 76684 38421 76684 38389 76684 38422 76685 38389 76685 38423 76685 38423 76686 38389 76686 38391 76686 38423 76687 38391 76687 38424 76687 38424 76688 38391 76688 38392 76688 38424 76689 38392 76689 38429 76689 38429 76690 38392 76690 38425 76690 38429 76691 38425 76691 38428 76691 38428 76692 38425 76692 38426 76692 38428 76693 38426 76693 38427 76693 38427 76694 38426 76694 40835 76694 38427 76695 40521 76695 38428 76695 38428 76696 40521 76696 38507 76696 38428 76697 38507 76697 38429 76697 38429 76698 38507 76698 38430 76698 38429 76699 38430 76699 38424 76699 38424 76700 38430 76700 38431 76700 38424 76701 38431 76701 38423 76701 38423 76702 38431 76702 38523 76702 38423 76703 38523 76703 38422 76703 38422 76704 38523 76704 38525 76704 38422 76705 38525 76705 38420 76705 38420 76706 38525 76706 38432 76706 38420 76707 38432 76707 38419 76707 38419 76708 38432 76708 38526 76708 38419 76709 38526 76709 38433 76709 38433 76710 38526 76710 38532 76710 38433 76711 38532 76711 38435 76711 38435 76712 38532 76712 38434 76712 38435 76713 38434 76713 38417 76713 38417 76714 38434 76714 38529 76714 38417 76715 38529 76715 38436 76715 38436 76716 38529 76716 38537 76716 38436 76717 38537 76717 38437 76717 38437 76718 38537 76718 38539 76718 38437 76719 38539 76719 38438 76719 38438 76720 38539 76720 38540 76720 38438 76721 38540 76721 38439 76721 38439 76722 38540 76722 38440 76722 38439 76723 38440 76723 38414 76723 38414 76724 38440 76724 38542 76724 38414 76725 38542 76725 38441 76725 38441 76726 38542 76726 38545 76726 38441 76727 38545 76727 38442 76727 38442 76728 38545 76728 38550 76728 38442 76729 38550 76729 38411 76729 38411 76730 38550 76730 38443 76730 38411 76731 38443 76731 38410 76731 38410 76732 38443 76732 38557 76732 38410 76733 38557 76733 38444 76733 38444 76734 38557 76734 38559 76734 38444 76735 38559 76735 38445 76735 38445 76736 38559 76736 38560 76736 38445 76737 38560 76737 38446 76737 38446 76738 38560 76738 38561 76738 38446 76739 38561 76739 38447 76739 38447 76740 38561 76740 38449 76740 38447 76741 38449 76741 38448 76741 38448 76742 38449 76742 38570 76742 38448 76743 38570 76743 38404 76743 38404 76744 38570 76744 38572 76744 38404 76745 38572 76745 38403 76745 38403 76746 38572 76746 38450 76746 38403 76747 38450 76747 38451 76747 38451 76748 38450 76748 38452 76748 38451 76749 38452 76749 38400 76749 38400 76750 38452 76750 38575 76750 38400 76751 38575 76751 38453 76751 38453 76752 38575 76752 38578 76752 38453 76753 38578 76753 38454 76753 38454 76754 38578 76754 38455 76754 38454 76755 38455 76755 38456 76755 38456 76756 38455 76756 38589 76756 38456 76757 38589 76757 38398 76757 38398 76758 38589 76758 38591 76758 38398 76759 38591 76759 38457 76759 38457 76760 38591 76760 38592 76760 38457 76761 38592 76761 38458 76761 38458 76762 38592 76762 38459 76762 38458 76763 38459 76763 38460 76763 38460 76764 38459 76764 38461 76764 38460 76765 38461 76765 38462 76765 38462 76766 38461 76766 38496 76766 38462 76767 38496 76767 38463 76767 38463 76768 38496 76768 38464 76768 38463 76769 38464 76769 38341 76769 38341 76770 38464 76770 38465 76770 38341 76771 38465 76771 38340 76771 38342 76772 40837 76772 38466 76772 38466 76773 40837 76773 38326 76773 40837 76774 38467 76774 38326 76774 38326 76775 38467 76775 40842 76775 38326 76776 40842 76776 38471 76776 38468 76777 38470 76777 38469 76777 38469 76778 38470 76778 38471 76778 38469 76779 38471 76779 40844 76779 40844 76780 38471 76780 40842 76780 38468 76781 40850 76781 38470 76781 38470 76782 40850 76782 40853 76782 38470 76783 40853 76783 38327 76783 40851 76784 38474 76784 38472 76784 38472 76785 38474 76785 38327 76785 38472 76786 38327 76786 40852 76786 40852 76787 38327 76787 40853 76787 38475 76788 38476 76788 38473 76788 38473 76789 38476 76789 38474 76789 38473 76790 38474 76790 40825 76790 40825 76791 38474 76791 40851 76791 38475 76792 40857 76792 38476 76792 38476 76793 40857 76793 38477 76793 38476 76794 38477 76794 38328 76794 38477 76795 38478 76795 38328 76795 38328 76796 38478 76796 38479 76796 38328 76797 38479 76797 38480 76797 38479 76798 40863 76798 38480 76798 38480 76799 40863 76799 38481 76799 38480 76800 38481 76800 38330 76800 38481 76801 38482 76801 38330 76801 38330 76802 38482 76802 40866 76802 38330 76803 40866 76803 38483 76803 40873 76804 38484 76804 40874 76804 40874 76805 38484 76805 38483 76805 40874 76806 38483 76806 40869 76806 40869 76807 38483 76807 40866 76807 40873 76808 40870 76808 38484 76808 38484 76809 40870 76809 40877 76809 38484 76810 40877 76810 38331 76810 40877 76811 40881 76811 38331 76811 38331 76812 40881 76812 40880 76812 38331 76813 40880 76813 38333 76813 38485 76814 38486 76814 38487 76814 38487 76815 38486 76815 38333 76815 38487 76816 38333 76816 40878 76816 40878 76817 38333 76817 40880 76817 38485 76818 40834 76818 38486 76818 38486 76819 40834 76819 40885 76819 38486 76820 40885 76820 38335 76820 40892 76821 38490 76821 40888 76821 40888 76822 38490 76822 38335 76822 40888 76823 38335 76823 38488 76823 38488 76824 38335 76824 40885 76824 40892 76825 38489 76825 38490 76825 38490 76826 38489 76826 40890 76826 38490 76827 40890 76827 38337 76827 38394 76828 40766 76828 38491 76828 38491 76829 40766 76829 38337 76829 38491 76830 38337 76830 38492 76830 38492 76831 38337 76831 40890 76831 40689 76832 38493 76832 40962 76832 40962 76833 38494 76833 40689 76833 40689 76834 38494 76834 38495 76834 40689 76835 38495 76835 40687 76835 40687 76836 38495 76836 38270 76836 40687 76837 38270 76837 38272 76837 38273 76838 38276 76838 38461 76838 38461 76839 38276 76839 40953 76839 38461 76840 40953 76840 38496 76840 38496 76841 40953 76841 38497 76841 38496 76842 38497 76842 40956 76842 38500 76843 38465 76843 38464 76843 38505 76844 38506 76844 38498 76844 38498 76845 38506 76845 41089 76845 40956 76846 38498 76846 38496 76846 38496 76847 38498 76847 41089 76847 38496 76848 41089 76848 38464 76848 38464 76849 41089 76849 38499 76849 38464 76850 38499 76850 38500 76850 40690 76851 38501 76851 38493 76851 38493 76852 38501 76852 40959 76852 38493 76853 40959 76853 40962 76853 40690 76854 38502 76854 38501 76854 38501 76855 38502 76855 38503 76855 38501 76856 38503 76856 38505 76856 38505 76857 38503 76857 38504 76857 38505 76858 38504 76858 38506 76858 40521 76859 38194 76859 38507 76859 38507 76860 38194 76860 41103 76860 38507 76861 41103 76861 38430 76861 38430 76862 41103 76862 41102 76862 41102 76863 41100 76863 38430 76863 38430 76864 41100 76864 41099 76864 38430 76865 41099 76865 38518 76865 38508 76866 38509 76866 38516 76866 38516 76867 38509 76867 41097 76867 38516 76868 41097 76868 40651 76868 38512 76869 40682 76869 38510 76869 38510 76870 40682 76870 40681 76870 38510 76871 40681 76871 38511 76871 38511 76872 40681 76872 38238 76872 38512 76873 38513 76873 40682 76873 40682 76874 38513 76874 38514 76874 40682 76875 38514 76875 38516 76875 38516 76876 38514 76876 38515 76876 38515 76877 38517 76877 38516 76877 38516 76878 38517 76878 38430 76878 38516 76879 38430 76879 38508 76879 38508 76880 38430 76880 38518 76880 38521 76881 38431 76881 38519 76881 38519 76882 38431 76882 38430 76882 38519 76883 38430 76883 38520 76883 38520 76884 38430 76884 38517 76884 38521 76885 40992 76885 38431 76885 38431 76886 40992 76886 40993 76886 38431 76887 40993 76887 38523 76887 38523 76888 40993 76888 38522 76888 38522 76889 38238 76889 38523 76889 38523 76890 38238 76890 40681 76890 38523 76891 40681 76891 38525 76891 38525 76892 40681 76892 38524 76892 38525 76893 38524 76893 38432 76893 38432 76894 38524 76894 40677 76894 38432 76895 40677 76895 38526 76895 38526 76896 40677 76896 38527 76896 38526 76897 38527 76897 38532 76897 38532 76898 38527 76898 38533 76898 38245 76899 38528 76899 38536 76899 38529 76900 40989 76900 38242 76900 38528 76901 38530 76901 38536 76901 38536 76902 38530 76902 38247 76902 38536 76903 38247 76903 40674 76903 40674 76904 38247 76904 38248 76904 40674 76905 38248 76905 38533 76905 38535 76906 38434 76906 38531 76906 38531 76907 38434 76907 38532 76907 38531 76908 38532 76908 40984 76908 40984 76909 38532 76909 38533 76909 40984 76910 38533 76910 38534 76910 38534 76911 38533 76911 38248 76911 38535 76912 40985 76912 38434 76912 38434 76913 40985 76913 40987 76913 38434 76914 40987 76914 38529 76914 38529 76915 40987 76915 40988 76915 38529 76916 40988 76916 40989 76916 38242 76917 38245 76917 38529 76917 38529 76918 38245 76918 38536 76918 38529 76919 38536 76919 38537 76919 38537 76920 38536 76920 38538 76920 38537 76921 38538 76921 38539 76921 38539 76922 38538 76922 38541 76922 38539 76923 38541 76923 38540 76923 38540 76924 38541 76924 40672 76924 38540 76925 40672 76925 38440 76925 38440 76926 40672 76926 38543 76926 38440 76927 38543 76927 38542 76927 38542 76928 38543 76928 40670 76928 38542 76929 40670 76929 38545 76929 38545 76930 40670 76930 40667 76930 40667 76931 38555 76931 38544 76931 38544 76932 38254 76932 40667 76932 40667 76933 38254 76933 38546 76933 40667 76934 38546 76934 38545 76934 38545 76935 38546 76935 38547 76935 38545 76936 38547 76936 38548 76936 38548 76937 38549 76937 38545 76937 38545 76938 38549 76938 40979 76938 38545 76939 40979 76939 38550 76939 38550 76940 40979 76940 40980 76940 38550 76941 40980 76941 40981 76941 38556 76942 38551 76942 40665 76942 40665 76943 38551 76943 38553 76943 38551 76944 38552 76944 38553 76944 38553 76945 38552 76945 38251 76945 38553 76946 38251 76946 40667 76946 40667 76947 38251 76947 38554 76947 40667 76948 38554 76948 38555 76948 40981 76949 40982 76949 38550 76949 38550 76950 40982 76950 38556 76950 38550 76951 38556 76951 38443 76951 38443 76952 38556 76952 40665 76952 38443 76953 40665 76953 38557 76953 38557 76954 40665 76954 38558 76954 38557 76955 38558 76955 38559 76955 38559 76956 38558 76956 40662 76956 38559 76957 40662 76957 38560 76957 38560 76958 40662 76958 38562 76958 38560 76959 38562 76959 38561 76959 38561 76960 38562 76960 40661 76960 38568 76961 38563 76961 40661 76961 40661 76962 38563 76962 38263 76962 40661 76963 38263 76963 38561 76963 38561 76964 38263 76964 40969 76964 38561 76965 40969 76965 38564 76965 38565 76966 38566 76966 38571 76966 38564 76967 40971 76967 38561 76967 38561 76968 40971 76968 40972 76968 38561 76969 40972 76969 38449 76969 38449 76970 40972 76970 40974 76970 38449 76971 40974 76971 38570 76971 38570 76972 40974 76972 38569 76972 38571 76973 38566 76973 40659 76973 40659 76974 38566 76974 38257 76974 40659 76975 38257 76975 38258 76975 38258 76976 38256 76976 40659 76976 40659 76977 38256 76977 38255 76977 40659 76978 38255 76978 40661 76978 40661 76979 38255 76979 38567 76979 40661 76980 38567 76980 38568 76980 38569 76981 38565 76981 38570 76981 38570 76982 38565 76982 38571 76982 38570 76983 38571 76983 38572 76983 38572 76984 38571 76984 40657 76984 38572 76985 40657 76985 38450 76985 38450 76986 40657 76986 38573 76986 38450 76987 38573 76987 38452 76987 38452 76988 38573 76988 38574 76988 38452 76989 38574 76989 38575 76989 38575 76990 38574 76990 40655 76990 38577 76991 38578 76991 38266 76991 38266 76992 38578 76992 38575 76992 38266 76993 38575 76993 38576 76993 38576 76994 38575 76994 40655 76994 38576 76995 40655 76995 38588 76995 38577 76996 38579 76996 38578 76996 38578 76997 38579 76997 40964 76997 38578 76998 40964 76998 38455 76998 38455 76999 40964 76999 38580 76999 38455 77000 38580 77000 38581 77000 38582 77001 40967 77001 38583 77001 38583 77002 40967 77002 38584 77002 38583 77003 38584 77003 38585 77003 38584 77004 38264 77004 38585 77004 38585 77005 38264 77005 38586 77005 38585 77006 38586 77006 40655 77006 40655 77007 38586 77007 38587 77007 40655 77008 38587 77008 38588 77008 38581 77009 38582 77009 38455 77009 38455 77010 38582 77010 38583 77010 38455 77011 38583 77011 38589 77011 38589 77012 38583 77012 38590 77012 38589 77013 38590 77013 38591 77013 38591 77014 38590 77014 40684 77014 38591 77015 40684 77015 38592 77015 38592 77016 40684 77016 40686 77016 38592 77017 40686 77017 38459 77017 38459 77018 40686 77018 40687 77018 38459 77019 40687 77019 38461 77019 38461 77020 40687 77020 38272 77020 38461 77021 38272 77021 38273 77021 38593 77022 40335 77022 38594 77022 38594 77023 40335 77023 40337 77023 38594 77024 40337 77024 38322 77024 38322 77025 40337 77025 38595 77025 38322 77026 38595 77026 38596 77026 38596 77027 38595 77027 38597 77027 38596 77028 38597 77028 38319 77028 38319 77029 38597 77029 40336 77029 38319 77030 40336 77030 38317 77030 38317 77031 40336 77031 38598 77031 38317 77032 38598 77032 38599 77032 38599 77033 38598 77033 40345 77033 38599 77034 40345 77034 38316 77034 38316 77035 40345 77035 40347 77035 38316 77036 40347 77036 38600 77036 38600 77037 40347 77037 40346 77037 38600 77038 40346 77038 38602 77038 38602 77039 40346 77039 38601 77039 38602 77040 38601 77040 38603 77040 38603 77041 38601 77041 40340 77041 38603 77042 40340 77042 38314 77042 38314 77043 40340 77043 38604 77043 38314 77044 38604 77044 38606 77044 38606 77045 38604 77045 38605 77045 38606 77046 38605 77046 38608 77046 38608 77047 38605 77047 38607 77047 38608 77048 38607 77048 38310 77048 38310 77049 38607 77049 38609 77049 38310 77050 38609 77050 38610 77050 38610 77051 38609 77051 40339 77051 38611 77052 39365 77052 38612 77052 38611 77053 39379 77053 38614 77053 38613 77054 39379 77054 38611 77054 38612 77055 38613 77055 38611 77055 38611 77056 39378 77056 39377 77056 38615 77057 39378 77057 38611 77057 38614 77058 38615 77058 38611 77058 40315 77059 39362 77059 39371 77059 40315 77060 39368 77060 39367 77060 39369 77061 39368 77061 40315 77061 39371 77062 39369 77062 40315 77062 40315 77063 38616 77063 39356 77063 38617 77064 38616 77064 40315 77064 39367 77065 38617 77065 40315 77065 40311 77066 38618 77066 38619 77066 39372 77067 38618 77067 40311 77067 38620 77068 39372 77068 40311 77068 40311 77069 39350 77069 38621 77069 39351 77070 39350 77070 40311 77070 38619 77071 39351 77071 40311 77071 38623 77072 39334 77072 39345 77072 39357 77073 39334 77073 38623 77073 39359 77074 39357 77074 38623 77074 38623 77075 38622 77075 39343 77075 39352 77076 38622 77076 38623 77076 39345 77077 39352 77077 38623 77077 38624 77078 39386 77078 39384 77078 38624 77079 39384 77079 43457 77079 43457 77080 39384 77080 39383 77080 43457 77081 39383 77081 43458 77081 43458 77082 39383 77082 38625 77082 43458 77083 38625 77083 43459 77083 43459 77084 38625 77084 38626 77084 43459 77085 38626 77085 43462 77085 43462 77086 38626 77086 38627 77086 43462 77087 38627 77087 43463 77087 43444 77088 40302 77088 38628 77088 43444 77089 38628 77089 43445 77089 43445 77090 38628 77090 39130 77090 43445 77091 39130 77091 43447 77091 43447 77092 39130 77092 38629 77092 43447 77093 38629 77093 38630 77093 38630 77094 38629 77094 38632 77094 38630 77095 38632 77095 38631 77095 38631 77096 38632 77096 39128 77096 38631 77097 39128 77097 38633 77097 38633 77098 39128 77098 39127 77098 38633 77099 39127 77099 38634 77099 38634 77100 39127 77100 39126 77100 38634 77101 39126 77101 43450 77101 43450 77102 39126 77102 38636 77102 43450 77103 38636 77103 38635 77103 38635 77104 38636 77104 38637 77104 38635 77105 38637 77105 43451 77105 43451 77106 38637 77106 39124 77106 43451 77107 39124 77107 38638 77107 38638 77108 39124 77108 39122 77108 38638 77109 39122 77109 38639 77109 38639 77110 39122 77110 38640 77110 38639 77111 38640 77111 43453 77111 43453 77112 38640 77112 39120 77112 43453 77113 39120 77113 43454 77113 43454 77114 39120 77114 39118 77114 43454 77115 39118 77115 38641 77115 38641 77116 39118 77116 38642 77116 38641 77117 38642 77117 38643 77117 38643 77118 38642 77118 39386 77118 38643 77119 39386 77119 38624 77119 39232 77120 39236 77120 40247 77120 39232 77121 40247 77121 39226 77121 39226 77122 40247 77122 38644 77122 39226 77123 38644 77123 39242 77123 39242 77124 38644 77124 38645 77124 39242 77125 38645 77125 39240 77125 38645 77126 39391 77126 39240 77126 39240 77127 39391 77127 39392 77127 39240 77128 39392 77128 39245 77128 39245 77129 39392 77129 38646 77129 39245 77130 38646 77130 40250 77130 40250 77131 38646 77131 39398 77131 40250 77132 39398 77132 39397 77132 38647 77133 38648 77133 39112 77133 38647 77134 39112 77134 38649 77134 38649 77135 39112 77135 38650 77135 38649 77136 38650 77136 38651 77136 38651 77137 38650 77137 39114 77137 38651 77138 39114 77138 38652 77138 38652 77139 39114 77139 39116 77139 38652 77140 39116 77140 38653 77140 38653 77141 39116 77141 40233 77141 38653 77142 40233 77142 39228 77142 38657 77143 39304 77143 39119 77143 39119 77144 39304 77144 39299 77144 39119 77145 39299 77145 38654 77145 38654 77146 39299 77146 40232 77146 38654 77147 40232 77147 40231 77147 38663 77148 38655 77148 39123 77148 39123 77149 38655 77149 38656 77149 39123 77150 38656 77150 39121 77150 39121 77151 38656 77151 39278 77151 39121 77152 39278 77152 38657 77152 38657 77153 39278 77153 38658 77153 38657 77154 38658 77154 39304 77154 38666 77155 38668 77155 38659 77155 38659 77156 38668 77156 39275 77156 38659 77157 39275 77157 39125 77157 39125 77158 39275 77158 38661 77158 39125 77159 38661 77159 38660 77159 38660 77160 38661 77160 38662 77160 38660 77161 38662 77161 38663 77161 38663 77162 38662 77162 38664 77162 38663 77163 38664 77163 38655 77163 38669 77164 38671 77164 39129 77164 39129 77165 38671 77165 39259 77165 39129 77166 39259 77166 38665 77166 38665 77167 39259 77167 39261 77167 38665 77168 39261 77168 38666 77168 38666 77169 39261 77169 38667 77169 38666 77170 38667 77170 38668 77170 39255 77171 39256 77171 38669 77171 38669 77172 39256 77172 38670 77172 38669 77173 38670 77173 38671 77173 38669 77174 38672 77174 39255 77174 39255 77175 38672 77175 39131 77175 39255 77176 39131 77176 39250 77176 39250 77177 39131 77177 38648 77177 39250 77178 38648 77178 38647 77178 40014 77179 38674 77179 38673 77179 38673 77180 38674 77180 40198 77180 40183 77181 38675 77181 38676 77181 38676 77182 38675 77182 38677 77182 38676 77183 38677 77183 38685 77183 38685 77184 38677 77184 38679 77184 38685 77185 38679 77185 38678 77185 38678 77186 38679 77186 39498 77186 38678 77187 39498 77187 38680 77187 38680 77188 39498 77188 39497 77188 38680 77189 39497 77189 38681 77189 38681 77190 39497 77190 39496 77190 38681 77191 39496 77191 38682 77191 38682 77192 39496 77192 39495 77192 38682 77193 39495 77193 38683 77193 38683 77194 39495 77194 40178 77194 40170 77195 40183 77195 38684 77195 38684 77196 40183 77196 38676 77196 38684 77197 38676 77197 38688 77197 38688 77198 38676 77198 38685 77198 38688 77199 38685 77199 38686 77199 38686 77200 38685 77200 38678 77200 38686 77201 38678 77201 38689 77201 38689 77202 38678 77202 38680 77202 38689 77203 38680 77203 38690 77203 38690 77204 38680 77204 38681 77204 38690 77205 38681 77205 38687 77205 38687 77206 38681 77206 38682 77206 38687 77207 38682 77207 40171 77207 40171 77208 38682 77208 38683 77208 40169 77209 40170 77209 38684 77209 40169 77210 38686 77210 38689 77210 38688 77211 38686 77211 40169 77211 38684 77212 38688 77212 40169 77212 40169 77213 38687 77213 40171 77213 38690 77214 38687 77214 40169 77214 38689 77215 38690 77215 40169 77215 38700 77216 38691 77216 38702 77216 38702 77217 38691 77217 39528 77217 38702 77218 39528 77218 38692 77218 38692 77219 39528 77219 38694 77219 38692 77220 38694 77220 38693 77220 38693 77221 38694 77221 39525 77221 38693 77222 39525 77222 38705 77222 38705 77223 39525 77223 38695 77223 38705 77224 38695 77224 38696 77224 38696 77225 38695 77225 38698 77225 38696 77226 38698 77226 38697 77226 38697 77227 38698 77227 38699 77227 40150 77228 38700 77228 38715 77228 38715 77229 38700 77229 38702 77229 38715 77230 38702 77230 38701 77230 38701 77231 38702 77231 38708 77231 38708 77232 38702 77232 38692 77232 38708 77233 38692 77233 38703 77233 38703 77234 38692 77234 38704 77234 38704 77235 38692 77235 38693 77235 38704 77236 38693 77236 38709 77236 38709 77237 38693 77237 38713 77237 38713 77238 38693 77238 38705 77238 38713 77239 38705 77239 38710 77239 38710 77240 38705 77240 38706 77240 38706 77241 38705 77241 38696 77241 38706 77242 38696 77242 38712 77242 38712 77243 38696 77243 38707 77243 38707 77244 38696 77244 38697 77244 38707 77245 38697 77245 38711 77245 38714 77246 40150 77246 38715 77246 38701 77247 38708 77247 38714 77247 38703 77248 38704 77248 38714 77248 38709 77249 38713 77249 38714 77249 38710 77250 38706 77250 38714 77250 38714 77251 38707 77251 38711 77251 38712 77252 38707 77252 38714 77252 38706 77253 38712 77253 38714 77253 38713 77254 38710 77254 38714 77254 38704 77255 38709 77255 38714 77255 38708 77256 38703 77256 38714 77256 38715 77257 38701 77257 38714 77257 38717 77258 38716 77258 40135 77258 40135 77259 38718 77259 38717 77259 38717 77260 38718 77260 38719 77260 38717 77261 38719 77261 39507 77261 38719 77262 38720 77262 39507 77262 39507 77263 38720 77263 38736 77263 39507 77264 38736 77264 38721 77264 38736 77265 38722 77265 38721 77265 38721 77266 38722 77266 38723 77266 38721 77267 38723 77267 39508 77267 39508 77268 38723 77268 38724 77268 39508 77269 38724 77269 38725 77269 38724 77270 38726 77270 38725 77270 38725 77271 38726 77271 38727 77271 38725 77272 38727 77272 38728 77272 38729 77273 39504 77273 38731 77273 38731 77274 39504 77274 38728 77274 38731 77275 38728 77275 38732 77275 38732 77276 38728 77276 38727 77276 38730 77277 38729 77277 38738 77277 38738 77278 38729 77278 38731 77278 38738 77279 38731 77279 38745 77279 38745 77280 38731 77280 38732 77280 38745 77281 38732 77281 38733 77281 38733 77282 38732 77282 38727 77282 38733 77283 38727 77283 38744 77283 38744 77284 38727 77284 38726 77284 38744 77285 38726 77285 38734 77285 38734 77286 38726 77286 38724 77286 38734 77287 38724 77287 38739 77287 38739 77288 38724 77288 38723 77288 38739 77289 38723 77289 38735 77289 38735 77290 38723 77290 38722 77290 38735 77291 38722 77291 38743 77291 38743 77292 38722 77292 38736 77292 38743 77293 38736 77293 38737 77293 38737 77294 38736 77294 38720 77294 38737 77295 38720 77295 38742 77295 38742 77296 38720 77296 38719 77296 38742 77297 38719 77297 38740 77297 38740 77298 38719 77298 38718 77298 38740 77299 38718 77299 38741 77299 38741 77300 38718 77300 40135 77300 40134 77301 38730 77301 38738 77301 38745 77302 38733 77302 40134 77302 38744 77303 38734 77303 40134 77303 38739 77304 38735 77304 40134 77304 38743 77305 38737 77305 40134 77305 40134 77306 38740 77306 38741 77306 38742 77307 38740 77307 40134 77307 38737 77308 38742 77308 40134 77308 38735 77309 38743 77309 40134 77309 38734 77310 38739 77310 40134 77310 38733 77311 38744 77311 40134 77311 38738 77312 38745 77312 40134 77312 38830 77313 38750 77313 38831 77313 38747 77314 39482 77314 38746 77314 39483 77315 38747 77315 38748 77315 39480 77316 39478 77316 38787 77316 38752 77317 38750 77317 38749 77317 38749 77318 38750 77318 38830 77318 38749 77319 38830 77319 38829 77319 38832 77320 38831 77320 38751 77320 38751 77321 38831 77321 38750 77321 38751 77322 38750 77322 38753 77322 38753 77323 38750 77323 38752 77323 38753 77324 38752 77324 39483 77324 38795 77325 38791 77325 38755 77325 39216 77326 38794 77326 38754 77326 38754 77327 38794 77327 38795 77327 38754 77328 38795 77328 38799 77328 38799 77329 38795 77329 38755 77329 38799 77330 38755 77330 38798 77330 38796 77331 38803 77331 38797 77331 38797 77332 38803 77332 38756 77332 38797 77333 38756 77333 38800 77333 38800 77334 38756 77334 38757 77334 38800 77335 38757 77335 38758 77335 38758 77336 38757 77336 38806 77336 38759 77337 39476 77337 38804 77337 38804 77338 39476 77338 38808 77338 38804 77339 38808 77339 38805 77339 38805 77340 38808 77340 38760 77340 38805 77341 38760 77341 38761 77341 38761 77342 38760 77342 38810 77342 38761 77343 38810 77343 39212 77343 39212 77344 38810 77344 39213 77344 38807 77345 38762 77345 38763 77345 38763 77346 38762 77346 38766 77346 38763 77347 38766 77347 38809 77347 38809 77348 38766 77348 38764 77348 38809 77349 38764 77349 38765 77349 38765 77350 38764 77350 38767 77350 38762 77351 39486 77351 38766 77351 38766 77352 39486 77352 38813 77352 38766 77353 38813 77353 38764 77353 38764 77354 38813 77354 38814 77354 38764 77355 38814 77355 38767 77355 38767 77356 38814 77356 38815 77356 38767 77357 38815 77357 39209 77357 39209 77358 38815 77358 39208 77358 39485 77359 38768 77359 38769 77359 38769 77360 38768 77360 38820 77360 38769 77361 38820 77361 38770 77361 38770 77362 38820 77362 38771 77362 38770 77363 38771 77363 38818 77363 38818 77364 38771 77364 38821 77364 38772 77365 38773 77365 38774 77365 38774 77366 38773 77366 38776 77366 38774 77367 38776 77367 38775 77367 38775 77368 38776 77368 38825 77368 38775 77369 38825 77369 38822 77369 38822 77370 38825 77370 38826 77370 38822 77371 38826 77371 38777 77371 38777 77372 38826 77372 38828 77372 39475 77373 38781 77373 38824 77373 38824 77374 38781 77374 38779 77374 38824 77375 38779 77375 38778 77375 38778 77376 38779 77376 38780 77376 38778 77377 38780 77377 38827 77377 38827 77378 38780 77378 38784 77378 38781 77379 39474 77379 38779 77379 38779 77380 39474 77380 38782 77380 38779 77381 38782 77381 38780 77381 38780 77382 38782 77382 38783 77382 38780 77383 38783 77383 38784 77383 38784 77384 38783 77384 38786 77384 38784 77385 38786 77385 38785 77385 38785 77386 38786 77386 39197 77386 39480 77387 38787 77387 40130 77387 40130 77388 38787 77388 38790 77388 40130 77389 38790 77389 38788 77389 38788 77390 38790 77390 38793 77390 38788 77391 38793 77391 38789 77391 38789 77392 38793 77392 39223 77392 38789 77393 39223 77393 39132 77393 39478 77394 38798 77394 38787 77394 38787 77395 38798 77395 38755 77395 38787 77396 38755 77396 38790 77396 38790 77397 38755 77397 38791 77397 38790 77398 38791 77398 38793 77398 38793 77399 38791 77399 38792 77399 38793 77400 38792 77400 39223 77400 38794 77401 39218 77401 38795 77401 38795 77402 39218 77402 39219 77402 38795 77403 39219 77403 38791 77403 38791 77404 39219 77404 39220 77404 38791 77405 39220 77405 38792 77405 39478 77406 38796 77406 38798 77406 38798 77407 38796 77407 38797 77407 38798 77408 38797 77408 38799 77408 38799 77409 38797 77409 38800 77409 38799 77410 38800 77410 38754 77410 38754 77411 38800 77411 38758 77411 38754 77412 38758 77412 39216 77412 39215 77413 38801 77413 38806 77413 38806 77414 38801 77414 39217 77414 38806 77415 39217 77415 38758 77415 38758 77416 39217 77416 38802 77416 38758 77417 38802 77417 39216 77417 38803 77418 38759 77418 38756 77418 38756 77419 38759 77419 38804 77419 38756 77420 38804 77420 38757 77420 38757 77421 38804 77421 38805 77421 38757 77422 38805 77422 38806 77422 38806 77423 38805 77423 38761 77423 38806 77424 38761 77424 39215 77424 39215 77425 38761 77425 39212 77425 39476 77426 38807 77426 38808 77426 38808 77427 38807 77427 38763 77427 38808 77428 38763 77428 38760 77428 38760 77429 38763 77429 38809 77429 38760 77430 38809 77430 38810 77430 38810 77431 38809 77431 38765 77431 38810 77432 38765 77432 39213 77432 39209 77433 38811 77433 38767 77433 38767 77434 38811 77434 38812 77434 38767 77435 38812 77435 38765 77435 38765 77436 38812 77436 39211 77436 38765 77437 39211 77437 39213 77437 39486 77438 39485 77438 38813 77438 38813 77439 39485 77439 38769 77439 38813 77440 38769 77440 38814 77440 38814 77441 38769 77441 38770 77441 38814 77442 38770 77442 38815 77442 38815 77443 38770 77443 38818 77443 38815 77444 38818 77444 39208 77444 38823 77445 38816 77445 38821 77445 38821 77446 38816 77446 38817 77446 38821 77447 38817 77447 38818 77447 38818 77448 38817 77448 38819 77448 38818 77449 38819 77449 39208 77449 38768 77450 38772 77450 38820 77450 38820 77451 38772 77451 38774 77451 38820 77452 38774 77452 38771 77452 38771 77453 38774 77453 38775 77453 38771 77454 38775 77454 38821 77454 38821 77455 38775 77455 38822 77455 38821 77456 38822 77456 38823 77456 38823 77457 38822 77457 38777 77457 38773 77458 39475 77458 38776 77458 38776 77459 39475 77459 38824 77459 38776 77460 38824 77460 38825 77460 38825 77461 38824 77461 38778 77461 38825 77462 38778 77462 38826 77462 38826 77463 38778 77463 38827 77463 38826 77464 38827 77464 38828 77464 38785 77465 39202 77465 38784 77465 38784 77466 39202 77466 39203 77466 38784 77467 39203 77467 38827 77467 38827 77468 39203 77468 39204 77468 38827 77469 39204 77469 38828 77469 39474 77470 38829 77470 38782 77470 38782 77471 38829 77471 38830 77471 38782 77472 38830 77472 38783 77472 38783 77473 38830 77473 38831 77473 38783 77474 38831 77474 38786 77474 38786 77475 38831 77475 38832 77475 38786 77476 38832 77476 39197 77476 39197 77477 38832 77477 39198 77477 38833 77478 39201 77478 39199 77478 39483 77479 38748 77479 38753 77479 38753 77480 38748 77480 38834 77480 38753 77481 38834 77481 38751 77481 38751 77482 38834 77482 38833 77482 38751 77483 38833 77483 38832 77483 38832 77484 38833 77484 39199 77484 38832 77485 39199 77485 39198 77485 38747 77486 38746 77486 38748 77486 38748 77487 38746 77487 40076 77487 38748 77488 40076 77488 38834 77488 38834 77489 40076 77489 38835 77489 38834 77490 38835 77490 38833 77490 38833 77491 38835 77491 39161 77491 38833 77492 39161 77492 39201 77492 38837 77493 39101 77493 38836 77493 38837 77494 38836 77494 38838 77494 38838 77495 38836 77495 38839 77495 38838 77496 38839 77496 39471 77496 39471 77497 38839 77497 38840 77497 39471 77498 38840 77498 39470 77498 39470 77499 38840 77499 38841 77499 39470 77500 38841 77500 38842 77500 38842 77501 38841 77501 39100 77501 38842 77502 39100 77502 38844 77502 38844 77503 39100 77503 38843 77503 38844 77504 38843 77504 38845 77504 38845 77505 38843 77505 39097 77505 38845 77506 39097 77506 39466 77506 39466 77507 39097 77507 39091 77507 39466 77508 39091 77508 38846 77508 38846 77509 39091 77509 39092 77509 38846 77510 39092 77510 38847 77510 38847 77511 39092 77511 38848 77511 38847 77512 38848 77512 38849 77512 38849 77513 38848 77513 38850 77513 38849 77514 38850 77514 39465 77514 39465 77515 38850 77515 39104 77515 39465 77516 39104 77516 38851 77516 38851 77517 39104 77517 39105 77517 38851 77518 39105 77518 39463 77518 39463 77519 39105 77519 38852 77519 39463 77520 38852 77520 38853 77520 38853 77521 38852 77521 39107 77521 38853 77522 39107 77522 39479 77522 38854 77523 38855 77523 40258 77523 40258 77524 38855 77524 39431 77524 39974 77525 38856 77525 38865 77525 38865 77526 38856 77526 38857 77526 38865 77527 38857 77527 38858 77527 38858 77528 38857 77528 38859 77528 38858 77529 38859 77529 38860 77529 38860 77530 38859 77530 39311 77530 38860 77531 39311 77531 38868 77531 38868 77532 39311 77532 39310 77532 38868 77533 39310 77533 38871 77533 38871 77534 39310 77534 38861 77534 38871 77535 38861 77535 39962 77535 39962 77536 38861 77536 38862 77536 39967 77537 39974 77537 38863 77537 38863 77538 39974 77538 38865 77538 38863 77539 38865 77539 38864 77539 38864 77540 38865 77540 38873 77540 38873 77541 38865 77541 38858 77541 38873 77542 38858 77542 38874 77542 38874 77543 38858 77543 38866 77543 38866 77544 38858 77544 38860 77544 38866 77545 38860 77545 38875 77545 38875 77546 38860 77546 38867 77546 38867 77547 38860 77547 38868 77547 38867 77548 38868 77548 38869 77548 38869 77549 38868 77549 38876 77549 38876 77550 38868 77550 38871 77550 38876 77551 38871 77551 38878 77551 38878 77552 38871 77552 38870 77552 38870 77553 38871 77553 39962 77553 38870 77554 39962 77554 39960 77554 43495 77555 39956 77555 39967 77555 39967 77556 38863 77556 43495 77556 43495 77557 38863 77557 38864 77557 43495 77558 38864 77558 38872 77558 38864 77559 38873 77559 38872 77559 38872 77560 38873 77560 38874 77560 38872 77561 38874 77561 43483 77561 38874 77562 38866 77562 43483 77562 43483 77563 38866 77563 38875 77563 43483 77564 38875 77564 43485 77564 43485 77565 38875 77565 38867 77565 43485 77566 38867 77566 43486 77566 38867 77567 38869 77567 43486 77567 43486 77568 38869 77568 38876 77568 43486 77569 38876 77569 38877 77569 39960 77570 43487 77570 38870 77570 38870 77571 43487 77571 38877 77571 38870 77572 38877 77572 38878 77572 38878 77573 38877 77573 38876 77573 39302 77574 39301 77574 39948 77574 39948 77575 38892 77575 39302 77575 39302 77576 38892 77576 38894 77576 39302 77577 38894 77577 38879 77577 38894 77578 38880 77578 38879 77578 38879 77579 38880 77579 38897 77579 38879 77580 38897 77580 38882 77580 38897 77581 38881 77581 38882 77581 38882 77582 38881 77582 38884 77582 38882 77583 38884 77583 38883 77583 38883 77584 38884 77584 38885 77584 38883 77585 38885 77585 38886 77585 38885 77586 38887 77586 38886 77586 38886 77587 38887 77587 38902 77587 38886 77588 38902 77588 38890 77588 38904 77589 38888 77589 38889 77589 38889 77590 38888 77590 38890 77590 38889 77591 38890 77591 38891 77591 38891 77592 38890 77592 38902 77592 39948 77593 38912 77593 38892 77593 38892 77594 38912 77594 38893 77594 38892 77595 38893 77595 38894 77595 38894 77596 38893 77596 38895 77596 38894 77597 38895 77597 38880 77597 38880 77598 38895 77598 38896 77598 38880 77599 38896 77599 38897 77599 38897 77600 38896 77600 38898 77600 38897 77601 38898 77601 38881 77601 38881 77602 38898 77602 38899 77602 38881 77603 38899 77603 38884 77603 38884 77604 38899 77604 38909 77604 38884 77605 38909 77605 38885 77605 38885 77606 38909 77606 38900 77606 38885 77607 38900 77607 38887 77607 38887 77608 38900 77608 38901 77608 38887 77609 38901 77609 38902 77609 38902 77610 38901 77610 38903 77610 38902 77611 38903 77611 38891 77611 38891 77612 38903 77612 38907 77612 38891 77613 38907 77613 38889 77613 38889 77614 38907 77614 38906 77614 38889 77615 38906 77615 38904 77615 38904 77616 38906 77616 38905 77616 43521 77617 43519 77617 38905 77617 38905 77618 38906 77618 43521 77618 43521 77619 38906 77619 38907 77619 43521 77620 38907 77620 38908 77620 38907 77621 38903 77621 38908 77621 38908 77622 38903 77622 38901 77622 38908 77623 38901 77623 43522 77623 38901 77624 38900 77624 43522 77624 43522 77625 38900 77625 38909 77625 43522 77626 38909 77626 38910 77626 38910 77627 38909 77627 38899 77627 38910 77628 38899 77628 38911 77628 38899 77629 38898 77629 38911 77629 38911 77630 38898 77630 38896 77630 38911 77631 38896 77631 43523 77631 38912 77632 43516 77632 38893 77632 38893 77633 43516 77633 43523 77633 38893 77634 43523 77634 38895 77634 38895 77635 43523 77635 38896 77635 39938 77636 38914 77636 38913 77636 38913 77637 38914 77637 38915 77637 38913 77638 38915 77638 38917 77638 38917 77639 38915 77639 38916 77639 38917 77640 38916 77640 38919 77640 38919 77641 38916 77641 39290 77641 38919 77642 39290 77642 38922 77642 38922 77643 39290 77643 39283 77643 38922 77644 39283 77644 38923 77644 38923 77645 39283 77645 39284 77645 38923 77646 39284 77646 38924 77646 38924 77647 39284 77647 39289 77647 38924 77648 39289 77648 38926 77648 38926 77649 39289 77649 39291 77649 38927 77650 39938 77650 38913 77650 38927 77651 38913 77651 38928 77651 38928 77652 38913 77652 38917 77652 38928 77653 38917 77653 38929 77653 38929 77654 38917 77654 38918 77654 38918 77655 38917 77655 38919 77655 38918 77656 38919 77656 38930 77656 38930 77657 38919 77657 38920 77657 38920 77658 38919 77658 38922 77658 38920 77659 38922 77659 38921 77659 38921 77660 38922 77660 38933 77660 38933 77661 38922 77661 38923 77661 38933 77662 38923 77662 38932 77662 38932 77663 38923 77663 38924 77663 38932 77664 38924 77664 38925 77664 38925 77665 38924 77665 38926 77665 38925 77666 38926 77666 39927 77666 43549 77667 38927 77667 43548 77667 43548 77668 38927 77668 38928 77668 43548 77669 38928 77669 38931 77669 38931 77670 38928 77670 38929 77670 38929 77671 38918 77671 38931 77671 38931 77672 38918 77672 38930 77672 38931 77673 38930 77673 43547 77673 38930 77674 38920 77674 43547 77674 43547 77675 38920 77675 38921 77675 43547 77676 38921 77676 43546 77676 39927 77677 43544 77677 38925 77677 38925 77678 43544 77678 43545 77678 38925 77679 43545 77679 38932 77679 38932 77680 43545 77680 43546 77680 38932 77681 43546 77681 38933 77681 38933 77682 43546 77682 38921 77682 39923 77683 39288 77683 38934 77683 38934 77684 39288 77684 39287 77684 38934 77685 39287 77685 38935 77685 38935 77686 39287 77686 39277 77686 38935 77687 39277 77687 38942 77687 38942 77688 39277 77688 39276 77688 38942 77689 39276 77689 38936 77689 38936 77690 39276 77690 38937 77690 38936 77691 38937 77691 38938 77691 38938 77692 38937 77692 38939 77692 38938 77693 38939 77693 38940 77693 38940 77694 38939 77694 39274 77694 38940 77695 39274 77695 38944 77695 38944 77696 39274 77696 39916 77696 39905 77697 39923 77697 38934 77697 39905 77698 38934 77698 38945 77698 38945 77699 38934 77699 38935 77699 38945 77700 38935 77700 38946 77700 38946 77701 38935 77701 38947 77701 38947 77702 38935 77702 38942 77702 38947 77703 38942 77703 38948 77703 38948 77704 38942 77704 38941 77704 38941 77705 38942 77705 38936 77705 38941 77706 38936 77706 38950 77706 38950 77707 38936 77707 38954 77707 38954 77708 38936 77708 38938 77708 38954 77709 38938 77709 38943 77709 38943 77710 38938 77710 38940 77710 38943 77711 38940 77711 38953 77711 38953 77712 38940 77712 38944 77712 38953 77713 38944 77713 39898 77713 43567 77714 39905 77714 43566 77714 43566 77715 39905 77715 38945 77715 43566 77716 38945 77716 43565 77716 43565 77717 38945 77717 38946 77717 38946 77718 38947 77718 43565 77718 43565 77719 38947 77719 38948 77719 43565 77720 38948 77720 38949 77720 38948 77721 38941 77721 38949 77721 38949 77722 38941 77722 38950 77722 38949 77723 38950 77723 38951 77723 39898 77724 38952 77724 38953 77724 38953 77725 38952 77725 43564 77725 38953 77726 43564 77726 38943 77726 38943 77727 43564 77727 38951 77727 38943 77728 38951 77728 38954 77728 38954 77729 38951 77729 38950 77729 39881 77730 39269 77730 38958 77730 38958 77731 39269 77731 39263 77731 38958 77732 39263 77732 38959 77732 38959 77733 39263 77733 39262 77733 38959 77734 39262 77734 38961 77734 38961 77735 39262 77735 39260 77735 38961 77736 39260 77736 38963 77736 38963 77737 39260 77737 38955 77737 38963 77738 38955 77738 38964 77738 38964 77739 38955 77739 38956 77739 38964 77740 38956 77740 39879 77740 39879 77741 38956 77741 39271 77741 38957 77742 39881 77742 38966 77742 38966 77743 39881 77743 38958 77743 38966 77744 38958 77744 38967 77744 38967 77745 38958 77745 38960 77745 38960 77746 38958 77746 38959 77746 38960 77747 38959 77747 38969 77747 38969 77748 38959 77748 38970 77748 38970 77749 38959 77749 38961 77749 38970 77750 38961 77750 38972 77750 38972 77751 38961 77751 38962 77751 38962 77752 38961 77752 38963 77752 38962 77753 38963 77753 38973 77753 38973 77754 38963 77754 38974 77754 38974 77755 38963 77755 38964 77755 38974 77756 38964 77756 38976 77756 38976 77757 38964 77757 38965 77757 38965 77758 38964 77758 39879 77758 38965 77759 39879 77759 38975 77759 43602 77760 39868 77760 38957 77760 38957 77761 38966 77761 43602 77761 43602 77762 38966 77762 38967 77762 43602 77763 38967 77763 38968 77763 38967 77764 38960 77764 38968 77764 38968 77765 38960 77765 38969 77765 38968 77766 38969 77766 43590 77766 38969 77767 38970 77767 43590 77767 43590 77768 38970 77768 38972 77768 43590 77769 38972 77769 38971 77769 38971 77770 38972 77770 38962 77770 38971 77771 38962 77771 43592 77771 38962 77772 38973 77772 43592 77772 43592 77773 38973 77773 38974 77773 43592 77774 38974 77774 43594 77774 38975 77775 39878 77775 38965 77775 38965 77776 39878 77776 43594 77776 38965 77777 43594 77777 38976 77777 38976 77778 43594 77778 38974 77778 39867 77779 38977 77779 38978 77779 38978 77780 38977 77780 39252 77780 38978 77781 39252 77781 38984 77781 38984 77782 39252 77782 38979 77782 38984 77783 38979 77783 38987 77783 38987 77784 38979 77784 39257 77784 38987 77785 39257 77785 38988 77785 38988 77786 39257 77786 38980 77786 38988 77787 38980 77787 38990 77787 38990 77788 38980 77788 39254 77788 38990 77789 39254 77789 38991 77789 38991 77790 39254 77790 38981 77790 38991 77791 38981 77791 38993 77791 38993 77792 38981 77792 39858 77792 38982 77793 39867 77793 38978 77793 38982 77794 38978 77794 38994 77794 38994 77795 38978 77795 38984 77795 38994 77796 38984 77796 38983 77796 38983 77797 38984 77797 38985 77797 38985 77798 38984 77798 38987 77798 38985 77799 38987 77799 38995 77799 38995 77800 38987 77800 38986 77800 38986 77801 38987 77801 38988 77801 38986 77802 38988 77802 38999 77802 38999 77803 38988 77803 38989 77803 38989 77804 38988 77804 38990 77804 38989 77805 38990 77805 38998 77805 38998 77806 38990 77806 38991 77806 38998 77807 38991 77807 38992 77807 38992 77808 38991 77808 38993 77808 38992 77809 38993 77809 39843 77809 43623 77810 38982 77810 43624 77810 43624 77811 38982 77811 38994 77811 43624 77812 38994 77812 43625 77812 43625 77813 38994 77813 38983 77813 38983 77814 38985 77814 43625 77814 43625 77815 38985 77815 38995 77815 43625 77816 38995 77816 38996 77816 38995 77817 38986 77817 38996 77817 38996 77818 38986 77818 38999 77818 38996 77819 38999 77819 43615 77819 39843 77820 43612 77820 38992 77820 38992 77821 43612 77821 38997 77821 38992 77822 38997 77822 38998 77822 38998 77823 38997 77823 43615 77823 38998 77824 43615 77824 38989 77824 38989 77825 43615 77825 38999 77825 39005 77826 39241 77826 39006 77826 39006 77827 39241 77827 39000 77827 39006 77828 39000 77828 39010 77828 39010 77829 39000 77829 39001 77829 39010 77830 39001 77830 39011 77830 39011 77831 39001 77831 39244 77831 39011 77832 39244 77832 39012 77832 39012 77833 39244 77833 39002 77833 39012 77834 39002 77834 39003 77834 39003 77835 39002 77835 39004 77835 39003 77836 39004 77836 39014 77836 39014 77837 39004 77837 39838 77837 39837 77838 39005 77838 39007 77838 39007 77839 39005 77839 39006 77839 39007 77840 39006 77840 39008 77840 39008 77841 39006 77841 39010 77841 39008 77842 39010 77842 39009 77842 39009 77843 39010 77843 39011 77843 39009 77844 39011 77844 39016 77844 39016 77845 39011 77845 39012 77845 39016 77846 39012 77846 39013 77846 39013 77847 39012 77847 39003 77847 39013 77848 39003 77848 39015 77848 39015 77849 39003 77849 39014 77849 39015 77850 43655 77850 39013 77850 39013 77851 43655 77851 43654 77851 39013 77852 43654 77852 39016 77852 39016 77853 43654 77853 39017 77853 39016 77854 39017 77854 39009 77854 39009 77855 39017 77855 43652 77855 39009 77856 43652 77856 39008 77856 39008 77857 43652 77857 39018 77857 39008 77858 39018 77858 39007 77858 39007 77859 39018 77859 39019 77859 39007 77860 39019 77860 39837 77860 39837 77861 39019 77861 43651 77861 39816 77862 39020 77862 39021 77862 39021 77863 39020 77863 39022 77863 39021 77864 39022 77864 39023 77864 39023 77865 39022 77865 39234 77865 39023 77866 39234 77866 39024 77866 39024 77867 39234 77867 39025 77867 39024 77868 39025 77868 39033 77868 39033 77869 39025 77869 39235 77869 39033 77870 39235 77870 39026 77870 39026 77871 39235 77871 39231 77871 39026 77872 39231 77872 39027 77872 39027 77873 39231 77873 39230 77873 39035 77874 39816 77874 39028 77874 39028 77875 39816 77875 39021 77875 39028 77876 39021 77876 39029 77876 39029 77877 39021 77877 39037 77877 39037 77878 39021 77878 39023 77878 39037 77879 39023 77879 39030 77879 39030 77880 39023 77880 39031 77880 39031 77881 39023 77881 39024 77881 39031 77882 39024 77882 39032 77882 39032 77883 39024 77883 39039 77883 39039 77884 39024 77884 39033 77884 39039 77885 39033 77885 39034 77885 39034 77886 39033 77886 39040 77886 39040 77887 39033 77887 39026 77887 39040 77888 39026 77888 39042 77888 39042 77889 39026 77889 39041 77889 39041 77890 39026 77890 39027 77890 39041 77891 39027 77891 39810 77891 39036 77892 39805 77892 39035 77892 39035 77893 39028 77893 39036 77893 39036 77894 39028 77894 39029 77894 39036 77895 39029 77895 39038 77895 39029 77896 39037 77896 39038 77896 39038 77897 39037 77897 39030 77897 39038 77898 39030 77898 43674 77898 39030 77899 39031 77899 43674 77899 43674 77900 39031 77900 39032 77900 43674 77901 39032 77901 43675 77901 43675 77902 39032 77902 39039 77902 43675 77903 39039 77903 43677 77903 39039 77904 39034 77904 43677 77904 43677 77905 39034 77905 39040 77905 43677 77906 39040 77906 43679 77906 39810 77907 43681 77907 39041 77907 39041 77908 43681 77908 43679 77908 39041 77909 43679 77909 39042 77909 39042 77910 43679 77910 39040 77910 39053 77911 39043 77911 39044 77911 39044 77912 39043 77912 39045 77912 39044 77913 39045 77913 39046 77913 39046 77914 39045 77914 39048 77914 39046 77915 39048 77915 39047 77915 39047 77916 39048 77916 39049 77916 39047 77917 39049 77917 39056 77917 39056 77918 39049 77918 39413 77918 39056 77919 39413 77919 39057 77919 39057 77920 39413 77920 39050 77920 39057 77921 39050 77921 39051 77921 39051 77922 39050 77922 39052 77922 39051 77923 39052 77923 39797 77923 39797 77924 39052 77924 39798 77924 39784 77925 39053 77925 39044 77925 39784 77926 39044 77926 39059 77926 39059 77927 39044 77927 39046 77927 39059 77928 39046 77928 39054 77928 39054 77929 39046 77929 39061 77929 39061 77930 39046 77930 39047 77930 39061 77931 39047 77931 39063 77931 39063 77932 39047 77932 39064 77932 39064 77933 39047 77933 39056 77933 39064 77934 39056 77934 39055 77934 39055 77935 39056 77935 39070 77935 39070 77936 39056 77936 39057 77936 39070 77937 39057 77937 39069 77937 39069 77938 39057 77938 39051 77938 39069 77939 39051 77939 39066 77939 39066 77940 39051 77940 39797 77940 39066 77941 39797 77941 39787 77941 39785 77942 39784 77942 39058 77942 39058 77943 39784 77943 39059 77943 39058 77944 39059 77944 39060 77944 39060 77945 39059 77945 39054 77945 39054 77946 39061 77946 39060 77946 39060 77947 39061 77947 39063 77947 39060 77948 39063 77948 39062 77948 39063 77949 39064 77949 39062 77949 39062 77950 39064 77950 39055 77950 39062 77951 39055 77951 39068 77951 39787 77952 39065 77952 39066 77952 39066 77953 39065 77953 39067 77953 39066 77954 39067 77954 39069 77954 39069 77955 39067 77955 39068 77955 39069 77956 39068 77956 39070 77956 39070 77957 39068 77957 39055 77957 39766 77958 39071 77958 39072 77958 39072 77959 39071 77959 39073 77959 39072 77960 39073 77960 39078 77960 39078 77961 39073 77961 39074 77961 39078 77962 39074 77962 39075 77962 39075 77963 39074 77963 39076 77963 39075 77964 39076 77964 39077 77964 39077 77965 39076 77965 39320 77965 39077 77966 39320 77966 39081 77966 39081 77967 39320 77967 39321 77967 39081 77968 39321 77968 39762 77968 39762 77969 39321 77969 39769 77969 39087 77970 39766 77970 39086 77970 39086 77971 39766 77971 39072 77971 39086 77972 39072 77972 39084 77972 39084 77973 39072 77973 39078 77973 39084 77974 39078 77974 39079 77974 39079 77975 39078 77975 39075 77975 39079 77976 39075 77976 39083 77976 39083 77977 39075 77977 39077 77977 39083 77978 39077 77978 39082 77978 39082 77979 39077 77979 39081 77979 39082 77980 39081 77980 39080 77980 39080 77981 39081 77981 39762 77981 39080 77982 43704 77982 39082 77982 39082 77983 43704 77983 43705 77983 39082 77984 43705 77984 39083 77984 39083 77985 43705 77985 43707 77985 39083 77986 43707 77986 39079 77986 39079 77987 43707 77987 43709 77987 39079 77988 43709 77988 39084 77988 39084 77989 43709 77989 43710 77989 39084 77990 43710 77990 39086 77990 39086 77991 43710 77991 39085 77991 39086 77992 39085 77992 39087 77992 39087 77993 39085 77993 43711 77993 39088 77994 40284 77994 39091 77994 38848 77995 39092 77995 39089 77995 39089 77996 39092 77996 39093 77996 39648 77997 40307 77997 39089 77997 39089 77998 40307 77998 39162 77998 39089 77999 39162 77999 38848 77999 40284 78000 39090 78000 39091 78000 39091 78001 39090 78001 40271 78001 39091 78002 40271 78002 39092 78002 39092 78003 40271 78003 40272 78003 39092 78004 40272 78004 39093 78004 39098 78005 39097 78005 39094 78005 39094 78006 39097 78006 38843 78006 39094 78007 38843 78007 40276 78007 39088 78008 39091 78008 39095 78008 39095 78009 39091 78009 39097 78009 39095 78010 39097 78010 39096 78010 39096 78011 39097 78011 39098 78011 39096 78012 39098 78012 39567 78012 39193 78013 39099 78013 40273 78013 40273 78014 39099 78014 40292 78014 40273 78015 40292 78015 39651 78015 40276 78016 38843 78016 40273 78016 40273 78017 38843 78017 39100 78017 40273 78018 39100 78018 39193 78018 39193 78019 39100 78019 38841 78019 39193 78020 38841 78020 39192 78020 39192 78021 38841 78021 38840 78021 39192 78022 38840 78022 39190 78022 39190 78023 38840 78023 38839 78023 39190 78024 38839 78024 39189 78024 39189 78025 38839 78025 38836 78025 39189 78026 38836 78026 39102 78026 39102 78027 38836 78027 39101 78027 39102 78028 39101 78028 39188 78028 39162 78029 39103 78029 38848 78029 38848 78030 39103 78030 39164 78030 38848 78031 39164 78031 38850 78031 38850 78032 39164 78032 39166 78032 38850 78033 39166 78033 39104 78033 39104 78034 39166 78034 39168 78034 39104 78035 39168 78035 39105 78035 39105 78036 39168 78036 39169 78036 39105 78037 39169 78037 38852 78037 38852 78038 39169 78038 39106 78038 38852 78039 39106 78039 39107 78039 40212 78040 39108 78040 39419 78040 40212 78041 39419 78041 40213 78041 40213 78042 39419 78042 39418 78042 40213 78043 39418 78043 39109 78043 39109 78044 39418 78044 39110 78044 39109 78045 39110 78045 40214 78045 40214 78046 39110 78046 39434 78046 40214 78047 39434 78047 40217 78047 40217 78048 39434 78048 39111 78048 40217 78049 39111 78049 40004 78049 38648 78050 40302 78050 40301 78050 38648 78051 40301 78051 39112 78051 39112 78052 40301 78052 39113 78052 39112 78053 39113 78053 38650 78053 38650 78054 39113 78054 40296 78054 38650 78055 40296 78055 39114 78055 39114 78056 40296 78056 39115 78056 39114 78057 39115 78057 39116 78057 39116 78058 39115 78058 39117 78058 39116 78059 39117 78059 40233 78059 40231 78060 39386 78060 38642 78060 40231 78061 38642 78061 38654 78061 38654 78062 38642 78062 39118 78062 38654 78063 39118 78063 39119 78063 39119 78064 39118 78064 39120 78064 39119 78065 39120 78065 38657 78065 38657 78066 39120 78066 38640 78066 38657 78067 38640 78067 39121 78067 39121 78068 38640 78068 39122 78068 39121 78069 39122 78069 39123 78069 39123 78070 39122 78070 39124 78070 39123 78071 39124 78071 38663 78071 38663 78072 39124 78072 38637 78072 38663 78073 38637 78073 38660 78073 38660 78074 38637 78074 38636 78074 38660 78075 38636 78075 39125 78075 39125 78076 38636 78076 39126 78076 39125 78077 39126 78077 38659 78077 38659 78078 39126 78078 39127 78078 38659 78079 39127 78079 38666 78079 38666 78080 39127 78080 39128 78080 38666 78081 39128 78081 38665 78081 38665 78082 39128 78082 38632 78082 38665 78083 38632 78083 39129 78083 39129 78084 38632 78084 38629 78084 39129 78085 38629 78085 38669 78085 38669 78086 38629 78086 39130 78086 38669 78087 39130 78087 38672 78087 38672 78088 39130 78088 38628 78088 38672 78089 38628 78089 39131 78089 39131 78090 38628 78090 40302 78090 39131 78091 40302 78091 38648 78091 39132 78092 39134 78092 39133 78092 39133 78093 39134 78093 39374 78093 39133 78094 39374 78094 39135 78094 39135 78095 39374 78095 40126 78095 40126 78096 39374 78096 39137 78096 40126 78097 39137 78097 39136 78097 39140 78098 39141 78098 39137 78098 39137 78099 39141 78099 39138 78099 39137 78100 39138 78100 39136 78100 39139 78101 40118 78101 39140 78101 39140 78102 40118 78102 40117 78102 39140 78103 40117 78103 39141 78103 39144 78104 39142 78104 39139 78104 39139 78105 39142 78105 39143 78105 39139 78106 39143 78106 40118 78106 39149 78107 39151 78107 39144 78107 39144 78108 39151 78108 39145 78108 39144 78109 39145 78109 39142 78109 39146 78110 39147 78110 39338 78110 39338 78111 39147 78111 39148 78111 39338 78112 39148 78112 39149 78112 39149 78113 39148 78113 39150 78113 39149 78114 39150 78114 39151 78114 39146 78115 39338 78115 39152 78115 39152 78116 39338 78116 39364 78116 39152 78117 39364 78117 39153 78117 39153 78118 39364 78118 39154 78118 39154 78119 39364 78119 39363 78119 39154 78120 39363 78120 40060 78120 40060 78121 39363 78121 39155 78121 39155 78122 39363 78122 39156 78122 39155 78123 39156 78123 40090 78123 40090 78124 39156 78124 39157 78124 39157 78125 39156 78125 39158 78125 39157 78126 39158 78126 40093 78126 40093 78127 39158 78127 39159 78127 39159 78128 39158 78128 39342 78128 39159 78129 39342 78129 40050 78129 39344 78130 40082 78130 40081 78130 39344 78131 40081 78131 39342 78131 39342 78132 40081 78132 40051 78132 39342 78133 40051 78133 40050 78133 40082 78134 39344 78134 40083 78134 40083 78135 39344 78135 39160 78135 40083 78136 39160 78136 40084 78136 40084 78137 39160 78137 40077 78137 40077 78138 39160 78138 39196 78138 40077 78139 39196 78139 39161 78139 39162 78140 40306 78140 39103 78140 39103 78141 40306 78141 39163 78141 39103 78142 39163 78142 39164 78142 39164 78143 39163 78143 39165 78143 39164 78144 39165 78144 39166 78144 39166 78145 39165 78145 39167 78145 39166 78146 39167 78146 39168 78146 39168 78147 39167 78147 40925 78147 39168 78148 40925 78148 39169 78148 39169 78149 40925 78149 39170 78149 39169 78150 39170 78150 39106 78150 39106 78151 39170 78151 39171 78151 39106 78152 39171 78152 39462 78152 39462 78153 39171 78153 39172 78153 39462 78154 39172 78154 39173 78154 39173 78155 39172 78155 38324 78155 39173 78156 38324 78156 39459 78156 39459 78157 38324 78157 38323 78157 39459 78158 38323 78158 39174 78158 39174 78159 38323 78159 38321 78159 39174 78160 38321 78160 39175 78160 39175 78161 38321 78161 38320 78161 39175 78162 38320 78162 39457 78162 39457 78163 38320 78163 38318 78163 39457 78164 38318 78164 39176 78164 39176 78165 38318 78165 39177 78165 39176 78166 39177 78166 39178 78166 39178 78167 39177 78167 39180 78167 39178 78168 39180 78168 39179 78168 39179 78169 39180 78169 39181 78169 39179 78170 39181 78170 39182 78170 39182 78171 39181 78171 38315 78171 39182 78172 38315 78172 39455 78172 39455 78173 38315 78173 39184 78173 39455 78174 39184 78174 39183 78174 39183 78175 39184 78175 38313 78175 39183 78176 38313 78176 39185 78176 39185 78177 38313 78177 39186 78177 39185 78178 39186 78178 39187 78178 39187 78179 39186 78179 38312 78179 39187 78180 38312 78180 39188 78180 39188 78181 38312 78181 38311 78181 39188 78182 38311 78182 39102 78182 39102 78183 38311 78183 40916 78183 39102 78184 40916 78184 39189 78184 39189 78185 40916 78185 40914 78185 39189 78186 40914 78186 39190 78186 39190 78187 40914 78187 39191 78187 39190 78188 39191 78188 39192 78188 39192 78189 39191 78189 39194 78189 39192 78190 39194 78190 39193 78190 39193 78191 39194 78191 39195 78191 39193 78192 39195 78192 39099 78192 39099 78193 39195 78193 40293 78193 40285 78194 39088 78194 43435 78194 43435 78195 39088 78195 39095 78195 39161 78196 39196 78196 39201 78196 39201 78197 39196 78197 39200 78197 38785 78198 39197 78198 39354 78198 39354 78199 39197 78199 39198 78199 39354 78200 39198 78200 39200 78200 39200 78201 39198 78201 39199 78201 39200 78202 39199 78202 39201 78202 38785 78203 39354 78203 39202 78203 39202 78204 39354 78204 39355 78204 39202 78205 39355 78205 39203 78205 39203 78206 39355 78206 39204 78206 39204 78207 39355 78207 39205 78207 39204 78208 39205 78208 38828 78208 38828 78209 39205 78209 38777 78209 38777 78210 39205 78210 39206 78210 38777 78211 39206 78211 38823 78211 38823 78212 39206 78212 38816 78212 38816 78213 39206 78213 39207 78213 38816 78214 39207 78214 38817 78214 38817 78215 39207 78215 38819 78215 38819 78216 39207 78216 39210 78216 38819 78217 39210 78217 39208 78217 39370 78218 38811 78218 39210 78218 39210 78219 38811 78219 39209 78219 39210 78220 39209 78220 39208 78220 39360 78221 39211 78221 39370 78221 39370 78222 39211 78222 38812 78222 39370 78223 38812 78223 38811 78223 39361 78224 39212 78224 39360 78224 39360 78225 39212 78225 39213 78225 39360 78226 39213 78226 39211 78226 39214 78227 38801 78227 39361 78227 39361 78228 38801 78228 39215 78228 39361 78229 39215 78229 39212 78229 38794 78230 39216 78230 39373 78230 39373 78231 39216 78231 38802 78231 39373 78232 38802 78232 39214 78232 39214 78233 38802 78233 39217 78233 39214 78234 39217 78234 38801 78234 38794 78235 39373 78235 39218 78235 39218 78236 39373 78236 39221 78236 39218 78237 39221 78237 39219 78237 39219 78238 39221 78238 39220 78238 39220 78239 39221 78239 39222 78239 39220 78240 39222 78240 38792 78240 38792 78241 39222 78241 39223 78241 39223 78242 39222 78242 39134 78242 39223 78243 39134 78243 39132 78243 39314 78244 39316 78244 40216 78244 39261 78245 39331 78245 38667 78245 39256 78246 39273 78246 38670 78246 39224 78247 40242 78247 40243 78247 38652 78248 38653 78248 39225 78248 39225 78249 38653 78249 39232 78249 39225 78250 39232 78250 39226 78250 39228 78251 39818 78251 39229 78251 39020 78252 39237 78252 39022 78252 39022 78253 39237 78253 39227 78253 39022 78254 39227 78254 39234 78254 39234 78255 39227 78255 39224 78255 39228 78256 39229 78256 38653 78256 39229 78257 39230 78257 38653 78257 38653 78258 39230 78258 39231 78258 38653 78259 39231 78259 39232 78259 39232 78260 39231 78260 39235 78260 39232 78261 39235 78261 39236 78261 39224 78262 40243 78262 39234 78262 39234 78263 40243 78263 39233 78263 39234 78264 39233 78264 39025 78264 39025 78265 39233 78265 40249 78265 39025 78266 40249 78266 39235 78266 39235 78267 40249 78267 40248 78267 39235 78268 40248 78268 39236 78268 39239 78269 40238 78269 39020 78269 39020 78270 40238 78270 40239 78270 39020 78271 40239 78271 39237 78271 39818 78272 39228 78272 39820 78272 39820 78273 39228 78273 39238 78273 39820 78274 39238 78274 39822 78274 39822 78275 39238 78275 40235 78275 39822 78276 40235 78276 39239 78276 39239 78277 40235 78277 40237 78277 39239 78278 40237 78278 40238 78278 39244 78279 38649 78279 39002 78279 39002 78280 38649 78280 39004 78280 39245 78281 39000 78281 39240 78281 39240 78282 39000 78282 39241 78282 39240 78283 39241 78283 39242 78283 39242 78284 39241 78284 39243 78284 39242 78285 39243 78285 39246 78285 39004 78286 38649 78286 39838 78286 39838 78287 38649 78287 38651 78287 39838 78288 38651 78288 39249 78288 39251 78289 38649 78289 40250 78289 40250 78290 38649 78290 39244 78290 40250 78291 39244 78291 39245 78291 39245 78292 39244 78292 39001 78292 39245 78293 39001 78293 39000 78293 39226 78294 39242 78294 39225 78294 39225 78295 39242 78295 39246 78295 39225 78296 39246 78296 38652 78296 38652 78297 39246 78297 39247 78297 38652 78298 39247 78298 38651 78298 38651 78299 39247 78299 39248 78299 38651 78300 39248 78300 39249 78300 39861 78301 39859 78301 39250 78301 39253 78302 39864 78302 40250 78302 40250 78303 39864 78303 39863 78303 39859 78304 39858 78304 39250 78304 39250 78305 39858 78305 38981 78305 39250 78306 38981 78306 39255 78306 39863 78307 39861 78307 40250 78307 40250 78308 39861 78308 39250 78308 40250 78309 39250 78309 39251 78309 39251 78310 39250 78310 38647 78310 39251 78311 38647 78311 38649 78311 38979 78312 39252 78312 39258 78312 39258 78313 39252 78313 38977 78313 39258 78314 38977 78314 39253 78314 39253 78315 38977 78315 39865 78315 39253 78316 39865 78316 39864 78316 38981 78317 39254 78317 39255 78317 39255 78318 39254 78318 38980 78318 39255 78319 38980 78319 39256 78319 39256 78320 38980 78320 39257 78320 39256 78321 39257 78321 39273 78321 39273 78322 39257 78322 38979 78322 39273 78323 38979 78323 40253 78323 40253 78324 38979 78324 39258 78324 39259 78325 38671 78325 38956 78325 38956 78326 38955 78326 39259 78326 39259 78327 38955 78327 39260 78327 39259 78328 39260 78328 39261 78328 39261 78329 39260 78329 39262 78329 39261 78330 39262 78330 39331 78330 39331 78331 39262 78331 39263 78331 39264 78332 40259 78332 39265 78332 39265 78333 40259 78333 39266 78333 39266 78334 40259 78334 40261 78334 39266 78335 40261 78335 39267 78335 39889 78336 39272 78336 39886 78336 39886 78337 39272 78337 39268 78337 39886 78338 39268 78338 39884 78338 39884 78339 39268 78339 39264 78339 39884 78340 39264 78340 39269 78340 39269 78341 39264 78341 39265 78341 39269 78342 39265 78342 39263 78342 39263 78343 39265 78343 39270 78343 39263 78344 39270 78344 39331 78344 39331 78345 39270 78345 39330 78345 40253 78346 40256 78346 39273 78346 39273 78347 40256 78347 40255 78347 39273 78348 40255 78348 39272 78348 39891 78349 39896 78349 38671 78349 38671 78350 39896 78350 39271 78350 38671 78351 39271 78351 38956 78351 39889 78352 39890 78352 39272 78352 39272 78353 39890 78353 39891 78353 39272 78354 39891 78354 39273 78354 39273 78355 39891 78355 38671 78355 39273 78356 38671 78356 38670 78356 39331 78357 39917 78357 38667 78357 38667 78358 39917 78358 39916 78358 38667 78359 39916 78359 38668 78359 39288 78360 39922 78360 39332 78360 39922 78361 39921 78361 39332 78361 39332 78362 39921 78362 39920 78362 39332 78363 39920 78363 39331 78363 39331 78364 39920 78364 39918 78364 39331 78365 39918 78365 39917 78365 39916 78366 39274 78366 38668 78366 38668 78367 39274 78367 38939 78367 38668 78368 38939 78368 39275 78368 38939 78369 38937 78369 39275 78369 39275 78370 38937 78370 39276 78370 39275 78371 39276 78371 38661 78371 39276 78372 39277 78372 38661 78372 38661 78373 39277 78373 39287 78373 38661 78374 39287 78374 38662 78374 38658 78375 39278 78375 39303 78375 39303 78376 39278 78376 39279 78376 39303 78377 39279 78377 40206 78377 38656 78378 38914 78378 39278 78378 39278 78379 38914 78379 39280 78379 39278 78380 39280 78380 39279 78380 39279 78381 39280 78381 39936 78381 39279 78382 39936 78382 39282 78382 39282 78383 39936 78383 39281 78383 39282 78384 39281 78384 40199 78384 39283 78385 38655 78385 39284 78385 39284 78386 38655 78386 38664 78386 39285 78387 40203 78387 39634 78387 39634 78388 40203 78388 39292 78388 39281 78389 39935 78389 40199 78389 40199 78390 39935 78390 39286 78390 40199 78391 39286 78391 40201 78391 40201 78392 39286 78392 39291 78392 40201 78393 39291 78393 40202 78393 39287 78394 39288 78394 38662 78394 38662 78395 39288 78395 39332 78395 38662 78396 39332 78396 38664 78396 38664 78397 39332 78397 39289 78397 38664 78398 39289 78398 39284 78398 39283 78399 39290 78399 38655 78399 38655 78400 39290 78400 38916 78400 38655 78401 38916 78401 38656 78401 38656 78402 38916 78402 38915 78402 38656 78403 38915 78403 38914 78403 40203 78404 40202 78404 39292 78404 39292 78405 40202 78405 39291 78405 39292 78406 39291 78406 39293 78406 39293 78407 39291 78407 39289 78407 39293 78408 39289 78408 39294 78408 39294 78409 39289 78409 39332 78409 39300 78410 39295 78410 39296 78410 39296 78411 39295 78411 39297 78411 39297 78412 39295 78412 40211 78412 39297 78413 40211 78413 39298 78413 39298 78414 40211 78414 40232 78414 39298 78415 40232 78415 39955 78415 39955 78416 40232 78416 39299 78416 39955 78417 39299 78417 38888 78417 38888 78418 39299 78418 38890 78418 38890 78419 39299 78419 39304 78419 38890 78420 39304 78420 38886 78420 39296 78421 39951 78421 39300 78421 39300 78422 39951 78422 39301 78422 39300 78423 39301 78423 40207 78423 40207 78424 39301 78424 39302 78424 40207 78425 39302 78425 38879 78425 40206 78426 40207 78426 39303 78426 39303 78427 40207 78427 38879 78427 39303 78428 38879 78428 38658 78428 38658 78429 38879 78429 38882 78429 38658 78430 38882 78430 39304 78430 39304 78431 38882 78431 38883 78431 39304 78432 38883 78432 38886 78432 39311 78433 40211 78433 39309 78433 40211 78434 39311 78434 40232 78434 40232 78435 39311 78435 38859 78435 40232 78436 38859 78436 40230 78436 38859 78437 38857 78437 40230 78437 40230 78438 38857 78438 38856 78438 40230 78439 38856 78439 39305 78439 40216 78440 39316 78440 40215 78440 38856 78441 39973 78441 39305 78441 39305 78442 39973 78442 39972 78442 39305 78443 39972 78443 39306 78443 39317 78444 39971 78444 39316 78444 39316 78445 39971 78445 39307 78445 39316 78446 39307 78446 40215 78446 40215 78447 39307 78447 38862 78447 40215 78448 38862 78448 39308 78448 39308 78449 38862 78449 38861 78449 39308 78450 38861 78450 39309 78450 39309 78451 38861 78451 39310 78451 39309 78452 39310 78452 39311 78452 39318 78453 39320 78453 39313 78453 39313 78454 39320 78454 39076 78454 39314 78455 40219 78455 39074 78455 39074 78456 40219 78456 40218 78456 39074 78457 40218 78457 39076 78457 39076 78458 40218 78458 39312 78458 39076 78459 39312 78459 39313 78459 39074 78460 39073 78460 39314 78460 39314 78461 39073 78461 39315 78461 39314 78462 39315 78462 39316 78462 39316 78463 39315 78463 39306 78463 39316 78464 39306 78464 39317 78464 39317 78465 39306 78465 39972 78465 39769 78466 39321 78466 40222 78466 39318 78467 39319 78467 39320 78467 39320 78468 39319 78468 40221 78468 39320 78469 40221 78469 39321 78469 39321 78470 40221 78470 40223 78470 39321 78471 40223 78471 40222 78471 39073 78472 39071 78472 39315 78472 39315 78473 39071 78473 39775 78473 39315 78474 39775 78474 39323 78474 39323 78475 39775 78475 39322 78475 39323 78476 39322 78476 39324 78476 39322 78477 39773 78477 39324 78477 39324 78478 39773 78478 39326 78478 39324 78479 39326 78479 39325 78479 39325 78480 39326 78480 39327 78480 39325 78481 39327 78481 39328 78481 39328 78482 39327 78482 39329 78482 39328 78483 39329 78483 40227 78483 40227 78484 39329 78484 39769 78484 40227 78485 39769 78485 40226 78485 40226 78486 39769 78486 40222 78486 39330 78487 39489 78487 39331 78487 39331 78488 39489 78488 39333 78488 39331 78489 39333 78489 39332 78489 39332 78490 39333 78490 39487 78490 39332 78491 39487 78491 39294 78491 39334 78492 39357 78492 39361 78492 39361 78493 39357 78493 39350 78493 39139 78494 39335 78494 39144 78494 39144 78495 39335 78495 40316 78495 39144 78496 40316 78496 39149 78496 39149 78497 40316 78497 39336 78497 39149 78498 39336 78498 39338 78498 39338 78499 39336 78499 39337 78499 39338 78500 39337 78500 39377 78500 39158 78501 39156 78501 39339 78501 39339 78502 39156 78502 39340 78502 39339 78503 39341 78503 39158 78503 39158 78504 39341 78504 40308 78504 39158 78505 40308 78505 39342 78505 39342 78506 40308 78506 39343 78506 39342 78507 39343 78507 39344 78507 39344 78508 39343 78508 38622 78508 39344 78509 38622 78509 39160 78509 39160 78510 38622 78510 39352 78510 39160 78511 39352 78511 39196 78511 39352 78512 39345 78512 39346 78512 39361 78513 39347 78513 39334 78513 39334 78514 39347 78514 39348 78514 39334 78515 39348 78515 39345 78515 39345 78516 39348 78516 39349 78516 39345 78517 39349 78517 39346 78517 39350 78518 39351 78518 39361 78518 39361 78519 39351 78519 38619 78519 39361 78520 38619 78520 39214 78520 39196 78521 39352 78521 39200 78521 39200 78522 39352 78522 39346 78522 39200 78523 39346 78523 39354 78523 39354 78524 39346 78524 39353 78524 39354 78525 39353 78525 39355 78525 39355 78526 39353 78526 39356 78526 39355 78527 39356 78527 39205 78527 40312 78528 40313 78528 39357 78528 40313 78529 39358 78529 39357 78529 39357 78530 39358 78530 38621 78530 39357 78531 38621 78531 39350 78531 39338 78532 39359 78532 40309 78532 39356 78533 38616 78533 39205 78533 39205 78534 38616 78534 38617 78534 39205 78535 38617 78535 39206 78535 39360 78536 39371 78536 39361 78536 39361 78537 39371 78537 39362 78537 39361 78538 39362 78538 39347 78538 39140 78539 39375 78539 38613 78539 39340 78540 39156 78540 40310 78540 40310 78541 39156 78541 39363 78541 40310 78542 39363 78542 40309 78542 40309 78543 39363 78543 39364 78543 40309 78544 39364 78544 39338 78544 38613 78545 38612 78545 39140 78545 39140 78546 38612 78546 39365 78546 39140 78547 39365 78547 39139 78547 39139 78548 39365 78548 39366 78548 39139 78549 39366 78549 39335 78549 38617 78550 39367 78550 39206 78550 39206 78551 39367 78551 39368 78551 39206 78552 39368 78552 39207 78552 39207 78553 39368 78553 39369 78553 39207 78554 39369 78554 39210 78554 39210 78555 39369 78555 39371 78555 39210 78556 39371 78556 39370 78556 39370 78557 39371 78557 39360 78557 38619 78558 38618 78558 39214 78558 39214 78559 38618 78559 39372 78559 39214 78560 39372 78560 39373 78560 39373 78561 39372 78561 38620 78561 39373 78562 38620 78562 39221 78562 39221 78563 38620 78563 40314 78563 39221 78564 40314 78564 39222 78564 39222 78565 40314 78565 39376 78565 39140 78566 39137 78566 39375 78566 39375 78567 39137 78567 39374 78567 39375 78568 39374 78568 39376 78568 39376 78569 39374 78569 39134 78569 39376 78570 39134 78570 39222 78570 39357 78571 39359 78571 40312 78571 40312 78572 39359 78572 39338 78572 40312 78573 39338 78573 39378 78573 39378 78574 39338 78574 39377 78574 39378 78575 38615 78575 40312 78575 40312 78576 38615 78576 38614 78576 40312 78577 38614 78577 39375 78577 39375 78578 38614 78578 39379 78578 39375 78579 39379 78579 38613 78579 39380 78580 38627 78580 38626 78580 39380 78581 38626 78581 40229 78581 40229 78582 38626 78582 38625 78582 40229 78583 38625 78583 39381 78583 39381 78584 38625 78584 39383 78584 39381 78585 39383 78585 39382 78585 39382 78586 39383 78586 39384 78586 39382 78587 39384 78587 39385 78587 39385 78588 39384 78588 39386 78588 39385 78589 39386 78589 40231 78589 39400 78590 39387 78590 39388 78590 40247 78591 39389 78591 38644 78591 38644 78592 39389 78592 39390 78592 38644 78593 39390 78593 38645 78593 38645 78594 39390 78594 39391 78594 39391 78595 39390 78595 39393 78595 39391 78596 39393 78596 39392 78596 39392 78597 39393 78597 38646 78597 38646 78598 39393 78598 39394 78598 38646 78599 39394 78599 39398 78599 39395 78600 39396 78600 39394 78600 39394 78601 39396 78601 39397 78601 39394 78602 39397 78602 39398 78602 39388 78603 39387 78603 39399 78603 39387 78604 40254 78604 39399 78604 39399 78605 40254 78605 40252 78605 39399 78606 40252 78606 39395 78606 39395 78607 40252 78607 40251 78607 39395 78608 40251 78608 39396 78608 39400 78609 39388 78609 40257 78609 40257 78610 39388 78610 39430 78610 40257 78611 39430 78611 39401 78611 39401 78612 39430 78612 39432 78612 39401 78613 39432 78613 40008 78613 40024 78614 40023 78614 39421 78614 40024 78615 39421 78615 39402 78615 39402 78616 39421 78616 39403 78616 39402 78617 39403 78617 40205 78617 39406 78618 40208 78618 39403 78618 39403 78619 40208 78619 39404 78619 39403 78620 39404 78620 40205 78620 39427 78621 39419 78621 39108 78621 39108 78622 39405 78622 39427 78622 39427 78623 39405 78623 40210 78623 39427 78624 40210 78624 39406 78624 39406 78625 40210 78625 40209 78625 39406 78626 40209 78626 40208 78626 40187 78627 39050 78627 39413 78627 39799 78628 39798 78628 39407 78628 39407 78629 39798 78629 40187 78629 40187 78630 39798 78630 39052 78630 40187 78631 39052 78631 39050 78631 39407 78632 39408 78632 39799 78632 39799 78633 39408 78633 40194 78633 39799 78634 40194 78634 39409 78634 39409 78635 40194 78635 40196 78635 39409 78636 40196 78636 39801 78636 39801 78637 40196 78637 39803 78637 39412 78638 39410 78638 39411 78638 39411 78639 40187 78639 39412 78639 39412 78640 40187 78640 39413 78640 39412 78641 39413 78641 40185 78641 40185 78642 39413 78642 39049 78642 40196 78643 39414 78643 39803 78643 39803 78644 39414 78644 40190 78644 39803 78645 40190 78645 39415 78645 39415 78646 40190 78646 40191 78646 39415 78647 40191 78647 39043 78647 39043 78648 40191 78648 40188 78648 39043 78649 40188 78649 39045 78649 39045 78650 40188 78650 39417 78650 39045 78651 39417 78651 39048 78651 40184 78652 39416 78652 39417 78652 39417 78653 39416 78653 40185 78653 39417 78654 40185 78654 39048 78654 39048 78655 40185 78655 39049 78655 39403 78656 39421 78656 39625 78656 39420 78657 39617 78657 39536 78657 39425 78658 39616 78658 40023 78658 39640 78659 39418 78659 39419 78659 39423 78660 39606 78660 39532 78660 39616 78661 39420 78661 40023 78661 40023 78662 39420 78662 39536 78662 40023 78663 39536 78663 39421 78663 39421 78664 39536 78664 39422 78664 39421 78665 39422 78665 39625 78665 39604 78666 39423 78666 39657 78666 39418 78667 39640 78667 39110 78667 39110 78668 39640 78668 39639 78668 39110 78669 39639 78669 39434 78669 39434 78670 39639 78670 39638 78670 39434 78671 39638 78671 39530 78671 39424 78672 39669 78672 39446 78672 40019 78673 40015 78673 40021 78673 40021 78674 40015 78674 39425 78674 40021 78675 39425 78675 40022 78675 40022 78676 39425 78676 40023 78676 39625 78677 39624 78677 39403 78677 39403 78678 39624 78678 39426 78678 39403 78679 39426 78679 39406 78679 39406 78680 39426 78680 39640 78680 39406 78681 39640 78681 39427 78681 39427 78682 39640 78682 39419 78682 39657 78683 39423 78683 39656 78683 39656 78684 39423 78684 39532 78684 39656 78685 39532 78685 39428 78685 39428 78686 39532 78686 39644 78686 39428 78687 39644 78687 39437 78687 39606 78688 39608 78688 39532 78688 39532 78689 39608 78689 39429 78689 39532 78690 39429 78690 39530 78690 39388 78691 39628 78691 39430 78691 39430 78692 39628 78692 39627 78692 39430 78693 39627 78693 39432 78693 39432 78694 39627 78694 39541 78694 39432 78695 39541 78695 39620 78695 39539 78696 39431 78696 39432 78696 39432 78697 39431 78697 38855 78697 39429 78698 39433 78698 39530 78698 39530 78699 39433 78699 39446 78699 39530 78700 39446 78700 39434 78700 39434 78701 39446 78701 39669 78701 39669 78702 39562 78702 39434 78702 39434 78703 39562 78703 39560 78703 39434 78704 39560 78704 39111 78704 39111 78705 39560 78705 40006 78705 39399 78706 39438 78706 39388 78706 39388 78707 39438 78707 39435 78707 39388 78708 39435 78708 39628 78708 39436 78709 39437 78709 39389 78709 39389 78710 39437 78710 39644 78710 39389 78711 39644 78711 39390 78711 39390 78712 39644 78712 39643 78712 39390 78713 39643 78713 39393 78713 39393 78714 39643 78714 39642 78714 39393 78715 39642 78715 39394 78715 39394 78716 39642 78716 39438 78716 39394 78717 39438 78717 39395 78717 39395 78718 39438 78718 39399 78718 40010 78719 40007 78719 39439 78719 39439 78720 40007 78720 39432 78720 39439 78721 39432 78721 40012 78721 40012 78722 39432 78722 38855 78722 39620 78723 39621 78723 39432 78723 39432 78724 39621 78724 39440 78724 39432 78725 39440 78725 39539 78725 39657 78726 39671 78726 39604 78726 39604 78727 39671 78727 39441 78727 39604 78728 39441 78728 39615 78728 39611 78729 39442 78729 39445 78729 39443 78730 39444 78730 39447 78730 39447 78731 39444 78731 39610 78731 39615 78732 39612 78732 39604 78732 39604 78733 39612 78733 39611 78733 39604 78734 39611 78734 39681 78734 39681 78735 39611 78735 39445 78735 39424 78736 39446 78736 39666 78736 39666 78737 39446 78737 39447 78737 39666 78738 39447 78738 39662 78738 39662 78739 39447 78739 39610 78739 39662 78740 39610 78740 39448 78740 39449 78741 39450 78741 39447 78741 39447 78742 39450 78742 39676 78742 39447 78743 39676 78743 39443 78743 39596 78744 39451 78744 40197 78744 40197 78745 39451 78745 39590 78745 39188 78746 39101 78746 40040 78746 39188 78747 40040 78747 39187 78747 39187 78748 40040 78748 40039 78748 39187 78749 40039 78749 39185 78749 39185 78750 40039 78750 39452 78750 39185 78751 39452 78751 39183 78751 39183 78752 39452 78752 39453 78752 39183 78753 39453 78753 39455 78753 39455 78754 39453 78754 39454 78754 39455 78755 39454 78755 39182 78755 39182 78756 39454 78756 40034 78756 39182 78757 40034 78757 39179 78757 39179 78758 40034 78758 39456 78758 39179 78759 39456 78759 39178 78759 39178 78760 39456 78760 40031 78760 39178 78761 40031 78761 39176 78761 39176 78762 40031 78762 40030 78762 39176 78763 40030 78763 39457 78763 39457 78764 40030 78764 40029 78764 39457 78765 40029 78765 39175 78765 39175 78766 40029 78766 40027 78766 39175 78767 40027 78767 39174 78767 39174 78768 40027 78768 39458 78768 39174 78769 39458 78769 39459 78769 39459 78770 39458 78770 39460 78770 39459 78771 39460 78771 39173 78771 39173 78772 39460 78772 39461 78772 39173 78773 39461 78773 39462 78773 39462 78774 39461 78774 39107 78774 39462 78775 39107 78775 39106 78775 39471 78776 40085 78776 38838 78776 38838 78777 40085 78777 39481 78777 38838 78778 39481 78778 38837 78778 38849 78779 40114 78779 38847 78779 38847 78780 40114 78780 40067 78780 38847 78781 40067 78781 38846 78781 39479 78782 40043 78782 38853 78782 38853 78783 40043 78783 39464 78783 38853 78784 39464 78784 39463 78784 39464 78785 40048 78785 39463 78785 39463 78786 40048 78786 40044 78786 39463 78787 40044 78787 38851 78787 38851 78788 40044 78788 40045 78788 38851 78789 40045 78789 39465 78789 39465 78790 40045 78790 40120 78790 39465 78791 40120 78791 38849 78791 38849 78792 40120 78792 40071 78792 38849 78793 40071 78793 40114 78793 40067 78794 40109 78794 38846 78794 38846 78795 40109 78795 40064 78795 38846 78796 40064 78796 39466 78796 39466 78797 40064 78797 40104 78797 39466 78798 40104 78798 38845 78798 38845 78799 40104 78799 40102 78799 38845 78800 40102 78800 38844 78800 40102 78801 39467 78801 38844 78801 38844 78802 39467 78802 39468 78802 38844 78803 39468 78803 38842 78803 38842 78804 39468 78804 39469 78804 38842 78805 39469 78805 39470 78805 39470 78806 39469 78806 40095 78806 39470 78807 40095 78807 39471 78807 39471 78808 40095 78808 39472 78808 39471 78809 39472 78809 40085 78809 40028 78810 38807 78810 39473 78810 39473 78811 38807 78811 39476 78811 39473 78812 39476 78812 40026 78812 40036 78813 39475 78813 40035 78813 40035 78814 39475 78814 38773 78814 40035 78815 38773 78815 40033 78815 40041 78816 38749 78816 40038 78816 40038 78817 38749 78817 38829 78817 40038 78818 38829 78818 40037 78818 40037 78819 38829 78819 39474 78819 40037 78820 39474 78820 40036 78820 40036 78821 39474 78821 38781 78821 40036 78822 38781 78822 39475 78822 39476 78823 38759 78823 40026 78823 40026 78824 38759 78824 38803 78824 40026 78825 38803 78825 40025 78825 40025 78826 38803 78826 38796 78826 40025 78827 38796 78827 39477 78827 39477 78828 38796 78828 39478 78828 39477 78829 39478 78829 39479 78829 39479 78830 39478 78830 39480 78830 39479 78831 39480 78831 40043 78831 39481 78832 39482 78832 38837 78832 38837 78833 39482 78833 38747 78833 38837 78834 38747 78834 40042 78834 40042 78835 38747 78835 39483 78835 40042 78836 39483 78836 40041 78836 40041 78837 39483 78837 38752 78837 40041 78838 38752 78838 38749 78838 38773 78839 38772 78839 40033 78839 40033 78840 38772 78840 38768 78840 40033 78841 38768 78841 40032 78841 40032 78842 38768 78842 39485 78842 40032 78843 39485 78843 39484 78843 39484 78844 39485 78844 39486 78844 39484 78845 39486 78845 40028 78845 40028 78846 39486 78846 38762 78846 40028 78847 38762 78847 38807 78847 39637 78848 39294 78848 39487 78848 39637 78849 39487 78849 39488 78849 39488 78850 39487 78850 39333 78850 39488 78851 39333 78851 39740 78851 39740 78852 39333 78852 39489 78852 39740 78853 39489 78853 39742 78853 39742 78854 39489 78854 39330 78854 39742 78855 39330 78855 39631 78855 39735 78856 39435 78856 39490 78856 39490 78857 39435 78857 39438 78857 39509 78858 39514 78858 39506 78858 39491 78859 39492 78859 39644 78859 39644 78860 39492 78860 39996 78860 39498 78861 38679 78861 39644 78861 39493 78862 40179 78862 39494 78862 39494 78863 40179 78863 39512 78863 38679 78864 38677 78864 39644 78864 39644 78865 38677 78865 38675 78865 39644 78866 38675 78866 39494 78866 39494 78867 38675 78867 40182 78867 39494 78868 40182 78868 39493 78868 40178 78869 39495 78869 39996 78869 39996 78870 39495 78870 39496 78870 39996 78871 39496 78871 39644 78871 39644 78872 39496 78872 39497 78872 39644 78873 39497 78873 39498 78873 39509 78874 38728 78874 39499 78874 39499 78875 38728 78875 39504 78875 39499 78876 39504 78876 39500 78876 39500 78877 39504 78877 39503 78877 39502 78878 39519 78878 39501 78878 39501 78879 39519 78879 39494 78879 40143 78880 39519 78880 40144 78880 40144 78881 39519 78881 39502 78881 40144 78882 39502 78882 40145 78882 40145 78883 39502 78883 39503 78883 40145 78884 39503 78884 40147 78884 40147 78885 39503 78885 39504 78885 40143 78886 39505 78886 39519 78886 39519 78887 39505 78887 38716 78887 39519 78888 38716 78888 39506 78888 39506 78889 38716 78889 38717 78889 39506 78890 38717 78890 39507 78890 39507 78891 38721 78891 39506 78891 39506 78892 38721 78892 39508 78892 39506 78893 39508 78893 39509 78893 39509 78894 39508 78894 38725 78894 39509 78895 38725 78895 38728 78895 39996 78896 40000 78896 40178 78896 40178 78897 40000 78897 39999 78897 40178 78898 39999 78898 39510 78898 39510 78899 39999 78899 39511 78899 39510 78900 39511 78900 39512 78900 39512 78901 39511 78901 39513 78901 39512 78902 39513 78902 39494 78902 39494 78903 39513 78903 40002 78903 39494 78904 40002 78904 39501 78904 39491 78905 39644 78905 39992 78905 39992 78906 39644 78906 39532 78906 39992 78907 39532 78907 39514 78907 39514 78908 39532 78908 39506 78908 39506 78909 39532 78909 39515 78909 39506 78910 39515 78910 39979 78910 39979 78911 39516 78911 39506 78911 39506 78912 39516 78912 39990 78912 39506 78913 39990 78913 39519 78913 39519 78914 39990 78914 39517 78914 39519 78915 39517 78915 39988 78915 39988 78916 39518 78916 39519 78916 39519 78917 39518 78917 39520 78917 39519 78918 39520 78918 39521 78918 39521 78919 39520 78919 39986 78919 39521 78920 39986 78920 39985 78920 39521 78921 39524 78921 39522 78921 38691 78922 39523 78922 39985 78922 39985 78923 39523 78923 40165 78923 39985 78924 40165 78924 39521 78924 39521 78925 40165 78925 40164 78925 39521 78926 40164 78926 39524 78926 39522 78927 40162 78927 39521 78927 39521 78928 40162 78928 38699 78928 39521 78929 38699 78929 39530 78929 39530 78930 38699 78930 38698 78930 38698 78931 38695 78931 39530 78931 39530 78932 38695 78932 39525 78932 39530 78933 39525 78933 39526 78933 39526 78934 39525 78934 38694 78934 39526 78935 38694 78935 39976 78935 39976 78936 38694 78936 39528 78936 39976 78937 39528 78937 39527 78937 39527 78938 39528 78938 38691 78938 39527 78939 38691 78939 39529 78939 39529 78940 38691 78940 39985 78940 39526 78941 39978 78941 39530 78941 39530 78942 39978 78942 39531 78942 39530 78943 39531 78943 39532 78943 39532 78944 39531 78944 39533 78944 39532 78945 39533 78945 39515 78945 39641 78946 39640 78946 39534 78946 39534 78947 39640 78947 39426 78947 39535 78948 39422 78948 39619 78948 39619 78949 39422 78949 39536 78949 39616 78950 39425 78950 39537 78950 39537 78951 39425 78951 40014 78951 39537 78952 40014 78952 38673 78952 39634 78953 39633 78953 39285 78953 39285 78954 39633 78954 39537 78954 38673 78955 40198 78955 39537 78955 39537 78956 40198 78956 39538 78956 39537 78957 39538 78957 39285 78957 39752 78958 39266 78958 39751 78958 39751 78959 39266 78959 39267 78959 39431 78960 39539 78960 40258 78960 40258 78961 39539 78961 39751 78961 40258 78962 39751 78962 40262 78962 40262 78963 39751 78963 39267 78963 39540 78964 39620 78964 39745 78964 39745 78965 39620 78965 39541 78965 39548 78966 39550 78966 39733 78966 39733 78967 39550 78967 39729 78967 39733 78968 39729 78968 39542 78968 39542 78969 39729 78969 39545 78969 39542 78970 39545 78970 39543 78970 39543 78971 39545 78971 39730 78971 39549 78972 39723 78972 39544 78972 39728 78973 39556 78973 39545 78973 39545 78974 39556 78974 39750 78974 39545 78975 39750 78975 39730 78975 39725 78976 39546 78976 39548 78976 39548 78977 39546 78977 39547 78977 39548 78978 39547 78978 39550 78978 39550 78979 39547 78979 39549 78979 39550 78980 39549 78980 39551 78980 39551 78981 39549 78981 39544 78981 39739 78982 39552 78982 39744 78982 39744 78983 39552 78983 39734 78983 39744 78984 39734 78984 39748 78984 39748 78985 39734 78985 39730 78985 39748 78986 39730 78986 39553 78986 39553 78987 39730 78987 39750 78987 39736 78988 39737 78988 39738 78988 39747 78989 39554 78989 39555 78989 39555 78990 39554 78990 39753 78990 39555 78991 39753 78991 39743 78991 39743 78992 39753 78992 39556 78992 39743 78993 39556 78993 39741 78993 39741 78994 39556 78994 39728 78994 39741 78995 39728 78995 39557 78995 39557 78996 39728 78996 39736 78996 39557 78997 39736 78997 39558 78997 39558 78998 39736 78998 39738 78998 39664 78999 39559 78999 40224 78999 40224 79000 39559 79000 39582 79000 40220 79001 39560 79001 39561 79001 39561 79002 39560 79002 39562 79002 39563 79003 39564 79003 39090 79003 39090 79004 39564 79004 40189 79004 39603 79005 39565 79005 40189 79005 40189 79006 39565 79006 39566 79006 40189 79007 39566 79007 39090 79007 39090 79008 39566 79008 39574 79008 39090 79009 39574 79009 40271 79009 39602 79010 39429 79010 40186 79010 40186 79011 39429 79011 39608 79011 40267 79012 39600 79012 39568 79012 39568 79013 40192 79013 39567 79013 39567 79014 40192 79014 40291 79014 39567 79015 39098 79015 39578 79015 39567 79016 39578 79016 39568 79016 39568 79017 39578 79017 40268 79017 39568 79018 40268 79018 40267 79018 40246 79019 39428 79019 40245 79019 40245 79020 39428 79020 39437 79020 39645 79021 39569 79021 40240 79021 40240 79022 39569 79022 39570 79022 39571 79023 39572 79023 39573 79023 39573 79024 39572 79024 40236 79024 39574 79025 39566 79025 39575 79025 40281 79026 40283 79026 39577 79026 40281 79027 39577 79027 40282 79027 39575 79028 39576 79028 39574 79028 39574 79029 39576 79029 40280 79029 39574 79030 40280 79030 39577 79030 39577 79031 40280 79031 40279 79031 39577 79032 40279 79032 40282 79032 39660 79033 39570 79033 40283 79033 40283 79034 39570 79034 39569 79034 40283 79035 39569 79035 39577 79035 39577 79036 39569 79036 39650 79036 39577 79037 39650 79037 39649 79037 39586 79038 39587 79038 39652 79038 39652 79039 39587 79039 39653 79039 40268 79040 39578 79040 39579 79040 39579 79041 39578 79041 39583 79041 39665 79042 40264 79042 39559 79042 39559 79043 40264 79043 39582 79043 40275 79044 39654 79044 39580 79044 39580 79045 39654 79045 39582 79045 40264 79046 39581 79046 39582 79046 39582 79047 39581 79047 40266 79047 39582 79048 40266 79048 39580 79048 39580 79049 40266 79049 40265 79049 39580 79050 40265 79050 39578 79050 39578 79051 40265 79051 40269 79051 39578 79052 40269 79052 39583 79052 40233 79053 39117 79053 39584 79053 40233 79054 39584 79054 40234 79054 40234 79055 39584 79055 40303 79055 40234 79056 40303 79056 39585 79056 39585 79057 40303 79057 39573 79057 39585 79058 39573 79058 40236 79058 39587 79059 39586 79059 39588 79059 39587 79060 39588 79060 39589 79060 39589 79061 39588 79061 40294 79061 39589 79062 40294 79062 40228 79062 40228 79063 40294 79063 38627 79063 40228 79064 38627 79064 39380 79064 39590 79065 39451 79065 39592 79065 39590 79066 39592 79066 39591 79066 39591 79067 39592 79067 39593 79067 39591 79068 39593 79068 39594 79068 39594 79069 39593 79069 40291 79069 39594 79070 40291 79070 40192 79070 39564 79071 39563 79071 40288 79071 39564 79072 40288 79072 40193 79072 40193 79073 40288 79073 39595 79073 40193 79074 39595 79074 40195 79074 40195 79075 39595 79075 39596 79075 40195 79076 39596 79076 40197 79076 39597 79077 39447 79077 39446 79077 39597 79078 39598 79078 39599 79078 39599 79079 39598 79079 39568 79079 39599 79080 39568 79080 39600 79080 39597 79081 39446 79081 39598 79081 39598 79082 39446 79082 39433 79082 39598 79083 39433 79083 39601 79083 39601 79084 39433 79084 39429 79084 39601 79085 39429 79085 39602 79085 39604 79086 39679 79086 39605 79086 39605 79087 39679 79087 40189 79087 40189 79088 39679 79088 40277 79088 40189 79089 40277 79089 39603 79089 39604 79090 39605 79090 39423 79090 39423 79091 39605 79091 39607 79091 39423 79092 39607 79092 39606 79092 39606 79093 39607 79093 40186 79093 39606 79094 40186 79094 39608 79094 39674 79095 39610 79095 39609 79095 39609 79096 39610 79096 39444 79096 39609 79097 39444 79097 39675 79097 39675 79098 39444 79098 39443 79098 40278 79099 39611 79099 39613 79099 39613 79100 39611 79100 39612 79100 39613 79101 39612 79101 39614 79101 39614 79102 39612 79102 39615 79102 39616 79103 39537 79103 39420 79103 39420 79104 39537 79104 39727 79104 39420 79105 39727 79105 39617 79105 39617 79106 39727 79106 39618 79106 39617 79107 39618 79107 39536 79107 39536 79108 39618 79108 39619 79108 39620 79109 39540 79109 39621 79109 39621 79110 39540 79110 39622 79110 39621 79111 39622 79111 39440 79111 39440 79112 39622 79112 39749 79112 39440 79113 39749 79113 39539 79113 39539 79114 39749 79114 39751 79114 39534 79115 39426 79115 39624 79115 39534 79116 39624 79116 39623 79116 39623 79117 39624 79117 39625 79117 39623 79118 39625 79118 39626 79118 39626 79119 39625 79119 39422 79119 39626 79120 39422 79120 39535 79120 39745 79121 39541 79121 39627 79121 39745 79122 39627 79122 39629 79122 39629 79123 39627 79123 39628 79123 39629 79124 39628 79124 39630 79124 39630 79125 39628 79125 39435 79125 39630 79126 39435 79126 39735 79126 39631 79127 39330 79127 39270 79127 39631 79128 39270 79128 39746 79128 39746 79129 39270 79129 39265 79129 39746 79130 39265 79130 39632 79130 39632 79131 39265 79131 39266 79131 39632 79132 39266 79132 39752 79132 39633 79133 39634 79133 39292 79133 39633 79134 39292 79134 39635 79134 39635 79135 39292 79135 39293 79135 39635 79136 39293 79136 39636 79136 39636 79137 39293 79137 39294 79137 39636 79138 39294 79138 39637 79138 39521 79139 39530 79139 39638 79139 39521 79140 39638 79140 39724 79140 39724 79141 39638 79141 39639 79141 39724 79142 39639 79142 39726 79142 39726 79143 39639 79143 39640 79143 39726 79144 39640 79144 39641 79144 39490 79145 39438 79145 39642 79145 39490 79146 39642 79146 39731 79146 39731 79147 39642 79147 39643 79147 39731 79148 39643 79148 39732 79148 39732 79149 39643 79149 39644 79149 39732 79150 39644 79150 39494 79150 39569 79151 39645 79151 39646 79151 39572 79152 39571 79152 39646 79152 39646 79153 39571 79153 39648 79153 39089 79154 39647 79154 39648 79154 39648 79155 39647 79155 39649 79155 39648 79156 39649 79156 39646 79156 39646 79157 39649 79157 39650 79157 39646 79158 39650 79158 39569 79158 39654 79159 40275 79159 39651 79159 39651 79160 40275 79160 40274 79160 39651 79161 40274 79161 40273 79161 39652 79162 39653 79162 39651 79162 39651 79163 39653 79163 40225 79163 39651 79164 40225 79164 39654 79164 39654 79165 40225 79165 40224 79165 39654 79166 40224 79166 39582 79166 39659 79167 39671 79167 39657 79167 40246 79168 40244 79168 39428 79168 39428 79169 40244 79169 39656 79169 40244 79170 39655 79170 39656 79170 39656 79171 39655 79171 40241 79171 39656 79172 40241 79172 39657 79172 39657 79173 40241 79173 39658 79173 39657 79174 39658 79174 39659 79174 39659 79175 39658 79175 39661 79175 39659 79176 39661 79176 39660 79176 39660 79177 39661 79177 40240 79177 39660 79178 40240 79178 39570 79178 39662 79179 39672 79179 39663 79179 39663 79180 39672 79180 39664 79180 39664 79181 39672 79181 39665 79181 39664 79182 39665 79182 39559 79182 39662 79183 39663 79183 39666 79183 39666 79184 39663 79184 39667 79184 39666 79185 39667 79185 39424 79185 39424 79186 39667 79186 39668 79186 39424 79187 39668 79187 39669 79187 39669 79188 39668 79188 39561 79188 39669 79189 39561 79189 39562 79189 39614 79190 39615 79190 39441 79190 39614 79191 39441 79191 39670 79191 39670 79192 39441 79192 39671 79192 39670 79193 39671 79193 39659 79193 39672 79194 39662 79194 39448 79194 39672 79195 39448 79195 39673 79195 39673 79196 39448 79196 39610 79196 39673 79197 39610 79197 39674 79197 39675 79198 39443 79198 39676 79198 39675 79199 39676 79199 40270 79199 40270 79200 39676 79200 39450 79200 40270 79201 39450 79201 39677 79201 39677 79202 39450 79202 39449 79202 39677 79203 39449 79203 39678 79203 39678 79204 39449 79204 39447 79204 39678 79205 39447 79205 39597 79205 39679 79206 39604 79206 39681 79206 39679 79207 39681 79207 39680 79207 39680 79208 39681 79208 39445 79208 39680 79209 39445 79209 39682 79209 39682 79210 39445 79210 39442 79210 39682 79211 39442 79211 39683 79211 39683 79212 39442 79212 39611 79212 39683 79213 39611 79213 40278 79213 39684 79214 39685 79214 40331 79214 40331 79215 39685 79215 39983 79215 39688 79216 39981 79216 40332 79216 40332 79217 39981 79217 39686 79217 40332 79218 39686 79218 39687 79218 39687 79219 39686 79219 39984 79219 39687 79220 39984 79220 40333 79220 40333 79221 39984 79221 39705 79221 39690 79222 39982 79222 39688 79222 39688 79223 39982 79223 39981 79223 39696 79224 39689 79224 39695 79224 39695 79225 39689 79225 40334 79225 39689 79226 39977 79226 40334 79226 40334 79227 39977 79227 39694 79227 40334 79228 39694 79228 39693 79228 39982 79229 39690 79229 39691 79229 39691 79230 39690 79230 39693 79230 39691 79231 39693 79231 39692 79231 39692 79232 39693 79232 39694 79232 39701 79233 39975 79233 39695 79233 39695 79234 39975 79234 39696 79234 40331 79235 39983 79235 39697 79235 40331 79236 39697 79236 39698 79236 39698 79237 39697 79237 39980 79237 39698 79238 39980 79238 39699 79238 39699 79239 39980 79239 39700 79239 39699 79240 39700 79240 40330 79240 40330 79241 39700 79241 39975 79241 40330 79242 39975 79242 39701 79242 40329 79243 39702 79243 39703 79243 39703 79244 39702 79244 39987 79244 39703 79245 39987 79245 39704 79245 39704 79246 39987 79246 39989 79246 39704 79247 39989 79247 39684 79247 39684 79248 39989 79248 39685 79248 40333 79249 39705 79249 40329 79249 40329 79250 39705 79250 39702 79250 40322 79251 39994 79251 40321 79251 40321 79252 39994 79252 39998 79252 40321 79253 39998 79253 39706 79253 39706 79254 39998 79254 39707 79254 39706 79255 39707 79255 40320 79255 40320 79256 39707 79256 39708 79256 40320 79257 39708 79257 40317 79257 40317 79258 39708 79258 40001 79258 40318 79259 39710 79259 40319 79259 40319 79260 39710 79260 39993 79260 40319 79261 39993 79261 40323 79261 40323 79262 39993 79262 39709 79262 40323 79263 39709 79263 40322 79263 40322 79264 39709 79264 39994 79264 40327 79265 39991 79265 40318 79265 40318 79266 39991 79266 39710 79266 40326 79267 39711 79267 39995 79267 40326 79268 39995 79268 39712 79268 39712 79269 39995 79269 39997 79269 39712 79270 39997 79270 40328 79270 40328 79271 39997 79271 39714 79271 40328 79272 39714 79272 39713 79272 39713 79273 39714 79273 39991 79273 39713 79274 39991 79274 40327 79274 40325 79275 39721 79275 40326 79275 40326 79276 39721 79276 39711 79276 39722 79277 39715 79277 39716 79277 39722 79278 39716 79278 39717 79278 39717 79279 39716 79279 39718 79279 39717 79280 39718 79280 39720 79280 39720 79281 39718 79281 39719 79281 39720 79282 39719 79282 40324 79282 40324 79283 39719 79283 39721 79283 40324 79284 39721 79284 40325 79284 40317 79285 40001 79285 39722 79285 39722 79286 40001 79286 39715 79286 39534 79287 39549 79287 39641 79287 39641 79288 39549 79288 39547 79288 39549 79289 39534 79289 39623 79289 39549 79290 39623 79290 39723 79290 39723 79291 39623 79291 39626 79291 39723 79292 39626 79292 39544 79292 39544 79293 39626 79293 39535 79293 39544 79294 39535 79294 39551 79294 39548 79295 39521 79295 39724 79295 39548 79296 39724 79296 39725 79296 39725 79297 39724 79297 39726 79297 39725 79298 39726 79298 39546 79298 39546 79299 39726 79299 39641 79299 39546 79300 39641 79300 39547 79300 39619 79301 39550 79301 39535 79301 39535 79302 39550 79302 39551 79302 39521 79303 39548 79303 39519 79303 39519 79304 39548 79304 39733 79304 39519 79305 39733 79305 39494 79305 39537 79306 39728 79306 39727 79306 39727 79307 39728 79307 39545 79307 39727 79308 39545 79308 39618 79308 39618 79309 39545 79309 39729 79309 39618 79310 39729 79310 39619 79310 39619 79311 39729 79311 39550 79311 39730 79312 39490 79312 39731 79312 39730 79313 39731 79313 39543 79313 39543 79314 39731 79314 39732 79314 39543 79315 39732 79315 39542 79315 39542 79316 39732 79316 39494 79316 39542 79317 39494 79317 39733 79317 39633 79318 39736 79318 39537 79318 39537 79319 39736 79319 39728 79319 39734 79320 39735 79320 39730 79320 39730 79321 39735 79321 39490 79321 39736 79322 39633 79322 39635 79322 39736 79323 39635 79323 39737 79323 39737 79324 39635 79324 39636 79324 39737 79325 39636 79325 39738 79325 39738 79326 39636 79326 39637 79326 39738 79327 39637 79327 39558 79327 39744 79328 39745 79328 39629 79328 39744 79329 39629 79329 39739 79329 39739 79330 39629 79330 39630 79330 39739 79331 39630 79331 39552 79331 39552 79332 39630 79332 39735 79332 39552 79333 39735 79333 39734 79333 39558 79334 39637 79334 39488 79334 39558 79335 39488 79335 39557 79335 39557 79336 39488 79336 39740 79336 39557 79337 39740 79337 39741 79337 39741 79338 39740 79338 39742 79338 39741 79339 39742 79339 39743 79339 39743 79340 39742 79340 39631 79340 39743 79341 39631 79341 39555 79341 39748 79342 39540 79342 39744 79342 39744 79343 39540 79343 39745 79343 39555 79344 39631 79344 39746 79344 39555 79345 39746 79345 39747 79345 39747 79346 39746 79346 39632 79346 39747 79347 39632 79347 39554 79347 39554 79348 39632 79348 39752 79348 39554 79349 39752 79349 39753 79349 39540 79350 39748 79350 39622 79350 39622 79351 39748 79351 39553 79351 39622 79352 39553 79352 39749 79352 39749 79353 39553 79353 39750 79353 39749 79354 39750 79354 39751 79354 39751 79355 39750 79355 39556 79355 39751 79356 39556 79356 39752 79356 39752 79357 39556 79357 39753 79357 43704 79358 39080 79358 43703 79358 43703 79359 39080 79359 39763 79359 43703 79360 39763 79360 39754 79360 39754 79361 39763 79361 39755 79361 39755 79362 39764 79362 39754 79362 39754 79363 39764 79363 39756 79363 39754 79364 39756 79364 43700 79364 39756 79365 39757 79365 43700 79365 43700 79366 39757 79366 39758 79366 43700 79367 39758 79367 39760 79367 39087 79368 43711 79368 39767 79368 39767 79369 43711 79369 43713 79369 39767 79370 43713 79370 39759 79370 39759 79371 43713 79371 39760 79371 39759 79372 39760 79372 39761 79372 39761 79373 39760 79373 39758 79373 39080 79374 39762 79374 39768 79374 39080 79375 39768 79375 39763 79375 39763 79376 39768 79376 39770 79376 39763 79377 39770 79377 39755 79377 39755 79378 39770 79378 39764 79378 39764 79379 39770 79379 39771 79379 39764 79380 39771 79380 39756 79380 39756 79381 39771 79381 39757 79381 39757 79382 39771 79382 39772 79382 39757 79383 39772 79383 39758 79383 39758 79384 39772 79384 39761 79384 39761 79385 39772 79385 39765 79385 39761 79386 39765 79386 39759 79386 39759 79387 39765 79387 39774 79387 39759 79388 39774 79388 39767 79388 39767 79389 39774 79389 39766 79389 39767 79390 39766 79390 39087 79390 39762 79391 39769 79391 39768 79391 39768 79392 39769 79392 39329 79392 39768 79393 39329 79393 39770 79393 39770 79394 39329 79394 39327 79394 39770 79395 39327 79395 39771 79395 39771 79396 39327 79396 39326 79396 39771 79397 39326 79397 39772 79397 39772 79398 39326 79398 39773 79398 39772 79399 39773 79399 39765 79399 39765 79400 39773 79400 39322 79400 39765 79401 39322 79401 39774 79401 39774 79402 39322 79402 39775 79402 39774 79403 39775 79403 39766 79403 39766 79404 39775 79404 39071 79404 39776 79405 39065 79405 39787 79405 39787 79406 39788 79406 39776 79406 39776 79407 39788 79407 39790 79407 39776 79408 39790 79408 39777 79408 39790 79409 39778 79409 39777 79409 39777 79410 39778 79410 39779 79410 39777 79411 39779 79411 39781 79411 39779 79412 39792 79412 39781 79412 39781 79413 39792 79413 39780 79413 39781 79414 39780 79414 43698 79414 43698 79415 39780 79415 39793 79415 43698 79416 39793 79416 39782 79416 39793 79417 39794 79417 39782 79417 39782 79418 39794 79418 39783 79418 39782 79419 39783 79419 39786 79419 39784 79420 39785 79420 39796 79420 39796 79421 39785 79421 39786 79421 39796 79422 39786 79422 39795 79422 39795 79423 39786 79423 39783 79423 39787 79424 39797 79424 39788 79424 39788 79425 39797 79425 39789 79425 39788 79426 39789 79426 39790 79426 39790 79427 39789 79427 39778 79427 39778 79428 39789 79428 39791 79428 39778 79429 39791 79429 39779 79429 39779 79430 39791 79430 39792 79430 39792 79431 39791 79431 39800 79431 39792 79432 39800 79432 39780 79432 39780 79433 39800 79433 39793 79433 39793 79434 39800 79434 39802 79434 39793 79435 39802 79435 39794 79435 39794 79436 39802 79436 39783 79436 39783 79437 39802 79437 39804 79437 39783 79438 39804 79438 39795 79438 39795 79439 39804 79439 39796 79439 39796 79440 39804 79440 39053 79440 39796 79441 39053 79441 39784 79441 39797 79442 39798 79442 39789 79442 39789 79443 39798 79443 39799 79443 39789 79444 39799 79444 39791 79444 39791 79445 39799 79445 39409 79445 39791 79446 39409 79446 39800 79446 39800 79447 39409 79447 39801 79447 39800 79448 39801 79448 39802 79448 39802 79449 39801 79449 39803 79449 39802 79450 39803 79450 39804 79450 39804 79451 39803 79451 39415 79451 39804 79452 39415 79452 39053 79452 39053 79453 39415 79453 39043 79453 39035 79454 39805 79454 39806 79454 39806 79455 39805 79455 43671 79455 39806 79456 43671 79456 39814 79456 39814 79457 43671 79457 43672 79457 39814 79458 43672 79458 39807 79458 39807 79459 43672 79459 39808 79459 39807 79460 39808 79460 39812 79460 39812 79461 39808 79461 39809 79461 39812 79462 39809 79462 39811 79462 39811 79463 39809 79463 43682 79463 39811 79464 43682 79464 39810 79464 39810 79465 43682 79465 43681 79465 39810 79466 39027 79466 39811 79466 39811 79467 39027 79467 39817 79467 39811 79468 39817 79468 39812 79468 39812 79469 39817 79469 39813 79469 39812 79470 39813 79470 39807 79470 39807 79471 39813 79471 39819 79471 39807 79472 39819 79472 39814 79472 39814 79473 39819 79473 39821 79473 39814 79474 39821 79474 39806 79474 39806 79475 39821 79475 39815 79475 39806 79476 39815 79476 39035 79476 39035 79477 39815 79477 39816 79477 39027 79478 39230 79478 39817 79478 39817 79479 39230 79479 39229 79479 39817 79480 39229 79480 39813 79480 39813 79481 39229 79481 39818 79481 39813 79482 39818 79482 39819 79482 39819 79483 39818 79483 39820 79483 39819 79484 39820 79484 39821 79484 39821 79485 39820 79485 39822 79485 39821 79486 39822 79486 39815 79486 39815 79487 39822 79487 39239 79487 39815 79488 39239 79488 39816 79488 39816 79489 39239 79489 39020 79489 39823 79490 43655 79490 39015 79490 39015 79491 39832 79491 39823 79491 39823 79492 39832 79492 39824 79492 39823 79493 39824 79493 43645 79493 39824 79494 39833 79494 43645 79494 43645 79495 39833 79495 39825 79495 43645 79496 39825 79496 43646 79496 39825 79497 39834 79497 43646 79497 43646 79498 39834 79498 39826 79498 43646 79499 39826 79499 43647 79499 43647 79500 39826 79500 39827 79500 43647 79501 39827 79501 39828 79501 39827 79502 39836 79502 39828 79502 39828 79503 39836 79503 39829 79503 39828 79504 39829 79504 43649 79504 39837 79505 43651 79505 39830 79505 39830 79506 43651 79506 43649 79506 39830 79507 43649 79507 39831 79507 39831 79508 43649 79508 39829 79508 39015 79509 39014 79509 39832 79509 39832 79510 39014 79510 39839 79510 39832 79511 39839 79511 39824 79511 39824 79512 39839 79512 39833 79512 39833 79513 39839 79513 39840 79513 39833 79514 39840 79514 39825 79514 39825 79515 39840 79515 39834 79515 39834 79516 39840 79516 39835 79516 39834 79517 39835 79517 39826 79517 39826 79518 39835 79518 39827 79518 39827 79519 39835 79519 39841 79519 39827 79520 39841 79520 39836 79520 39836 79521 39841 79521 39829 79521 39829 79522 39841 79522 39842 79522 39829 79523 39842 79523 39831 79523 39831 79524 39842 79524 39830 79524 39830 79525 39842 79525 39005 79525 39830 79526 39005 79526 39837 79526 39014 79527 39838 79527 39839 79527 39839 79528 39838 79528 39249 79528 39839 79529 39249 79529 39840 79529 39840 79530 39249 79530 39248 79530 39840 79531 39248 79531 39835 79531 39835 79532 39248 79532 39247 79532 39835 79533 39247 79533 39841 79533 39841 79534 39247 79534 39246 79534 39841 79535 39246 79535 39842 79535 39842 79536 39246 79536 39243 79536 39842 79537 39243 79537 39005 79537 39005 79538 39243 79538 39241 79538 43611 79539 43612 79539 39843 79539 39843 79540 39844 79540 43611 79540 43611 79541 39844 79541 39849 79541 43611 79542 39849 79542 43610 79542 39849 79543 39845 79543 43610 79543 43610 79544 39845 79544 39850 79544 43610 79545 39850 79545 43617 79545 39850 79546 39851 79546 43617 79546 43617 79547 39851 79547 39852 79547 43617 79548 39852 79548 43618 79548 43618 79549 39852 79549 39854 79549 43618 79550 39854 79550 39846 79550 39854 79551 39847 79551 39846 79551 39846 79552 39847 79552 39855 79552 39846 79553 39855 79553 43622 79553 38982 79554 43623 79554 39848 79554 39848 79555 43623 79555 43622 79555 39848 79556 43622 79556 39856 79556 39856 79557 43622 79557 39855 79557 39843 79558 38993 79558 39844 79558 39844 79559 38993 79559 39857 79559 39844 79560 39857 79560 39849 79560 39849 79561 39857 79561 39845 79561 39845 79562 39857 79562 39860 79562 39845 79563 39860 79563 39850 79563 39850 79564 39860 79564 39851 79564 39851 79565 39860 79565 39862 79565 39851 79566 39862 79566 39852 79566 39852 79567 39862 79567 39854 79567 39854 79568 39862 79568 39853 79568 39854 79569 39853 79569 39847 79569 39847 79570 39853 79570 39855 79570 39855 79571 39853 79571 39866 79571 39855 79572 39866 79572 39856 79572 39856 79573 39866 79573 39848 79573 39848 79574 39866 79574 39867 79574 39848 79575 39867 79575 38982 79575 38993 79576 39858 79576 39857 79576 39857 79577 39858 79577 39859 79577 39857 79578 39859 79578 39860 79578 39860 79579 39859 79579 39861 79579 39860 79580 39861 79580 39862 79580 39862 79581 39861 79581 39863 79581 39862 79582 39863 79582 39853 79582 39853 79583 39863 79583 39864 79583 39853 79584 39864 79584 39866 79584 39866 79585 39864 79585 39865 79585 39866 79586 39865 79586 39867 79586 39867 79587 39865 79587 38977 79587 38957 79588 39868 79588 39869 79588 39869 79589 39868 79589 39870 79589 39869 79590 39870 79590 39871 79590 39871 79591 39870 79591 39872 79591 39871 79592 39872 79592 39873 79592 39873 79593 39872 79593 39874 79593 39873 79594 39874 79594 39875 79594 39875 79595 39874 79595 43598 79595 39875 79596 43598 79596 39876 79596 39876 79597 43598 79597 39877 79597 39876 79598 39877 79598 38975 79598 38975 79599 39877 79599 39878 79599 39879 79600 39895 79600 38975 79600 38975 79601 39895 79601 39876 79601 39895 79602 39897 79602 39876 79602 39876 79603 39897 79603 39894 79603 39876 79604 39894 79604 39875 79604 39894 79605 39893 79605 39875 79605 39875 79606 39893 79606 39892 79606 39875 79607 39892 79607 39873 79607 39892 79608 39880 79608 39873 79608 39873 79609 39880 79609 39888 79609 39873 79610 39888 79610 39871 79610 39888 79611 39887 79611 39871 79611 39871 79612 39887 79612 39883 79612 39871 79613 39883 79613 39869 79613 39881 79614 38957 79614 39885 79614 39885 79615 38957 79615 39869 79615 39885 79616 39869 79616 39882 79616 39882 79617 39869 79617 39883 79617 39884 79618 39269 79618 39881 79618 39881 79619 39885 79619 39884 79619 39884 79620 39885 79620 39882 79620 39884 79621 39882 79621 39886 79621 39882 79622 39883 79622 39886 79622 39886 79623 39883 79623 39887 79623 39886 79624 39887 79624 39889 79624 39887 79625 39888 79625 39889 79625 39889 79626 39888 79626 39880 79626 39889 79627 39880 79627 39890 79627 39890 79628 39880 79628 39892 79628 39890 79629 39892 79629 39891 79629 39892 79630 39893 79630 39891 79630 39891 79631 39893 79631 39894 79631 39891 79632 39894 79632 39896 79632 39879 79633 39271 79633 39895 79633 39895 79634 39271 79634 39896 79634 39895 79635 39896 79635 39897 79635 39897 79636 39896 79636 39894 79636 43562 79637 38952 79637 39898 79637 39898 79638 39899 79638 43562 79638 43562 79639 39899 79639 39900 79639 43562 79640 39900 79640 43561 79640 39900 79641 39909 79641 43561 79641 43561 79642 39909 79642 39910 79642 43561 79643 39910 79643 43573 79643 39910 79644 39901 79644 43573 79644 43573 79645 39901 79645 39902 79645 43573 79646 39902 79646 43571 79646 43571 79647 39902 79647 39911 79647 43571 79648 39911 79648 39903 79648 39911 79649 39904 79649 39903 79649 39903 79650 39904 79650 39914 79650 39903 79651 39914 79651 43568 79651 39905 79652 43567 79652 39906 79652 39906 79653 43567 79653 43568 79653 39906 79654 43568 79654 39907 79654 39907 79655 43568 79655 39914 79655 39898 79656 38944 79656 39899 79656 39899 79657 38944 79657 39908 79657 39899 79658 39908 79658 39900 79658 39900 79659 39908 79659 39909 79659 39909 79660 39908 79660 39919 79660 39909 79661 39919 79661 39910 79661 39910 79662 39919 79662 39901 79662 39901 79663 39919 79663 39912 79663 39901 79664 39912 79664 39902 79664 39902 79665 39912 79665 39911 79665 39911 79666 39912 79666 39913 79666 39911 79667 39913 79667 39904 79667 39904 79668 39913 79668 39914 79668 39914 79669 39913 79669 39915 79669 39914 79670 39915 79670 39907 79670 39907 79671 39915 79671 39906 79671 39906 79672 39915 79672 39923 79672 39906 79673 39923 79673 39905 79673 38944 79674 39916 79674 39908 79674 39908 79675 39916 79675 39917 79675 39908 79676 39917 79676 39919 79676 39919 79677 39917 79677 39918 79677 39919 79678 39918 79678 39912 79678 39912 79679 39918 79679 39920 79679 39912 79680 39920 79680 39913 79680 39913 79681 39920 79681 39921 79681 39913 79682 39921 79682 39915 79682 39915 79683 39921 79683 39922 79683 39915 79684 39922 79684 39923 79684 39923 79685 39922 79685 39288 79685 38927 79686 43549 79686 39924 79686 39924 79687 43549 79687 39925 79687 39924 79688 39925 79688 39931 79688 39931 79689 39925 79689 43551 79689 39931 79690 43551 79690 39926 79690 39926 79691 43551 79691 43552 79691 39926 79692 43552 79692 39929 79692 39929 79693 43552 79693 43542 79693 39929 79694 43542 79694 39928 79694 39928 79695 43542 79695 43543 79695 39928 79696 43543 79696 39927 79696 39927 79697 43543 79697 43544 79697 39927 79698 38926 79698 39928 79698 39928 79699 38926 79699 39933 79699 39928 79700 39933 79700 39929 79700 39929 79701 39933 79701 39930 79701 39929 79702 39930 79702 39926 79702 39926 79703 39930 79703 39934 79703 39926 79704 39934 79704 39931 79704 39931 79705 39934 79705 39937 79705 39931 79706 39937 79706 39924 79706 39924 79707 39937 79707 39932 79707 39924 79708 39932 79708 38927 79708 38927 79709 39932 79709 39938 79709 38926 79710 39291 79710 39933 79710 39933 79711 39291 79711 39286 79711 39933 79712 39286 79712 39930 79712 39930 79713 39286 79713 39935 79713 39930 79714 39935 79714 39934 79714 39934 79715 39935 79715 39281 79715 39934 79716 39281 79716 39937 79716 39937 79717 39281 79717 39936 79717 39937 79718 39936 79718 39932 79718 39932 79719 39936 79719 39280 79719 39932 79720 39280 79720 39938 79720 39938 79721 39280 79721 38914 79721 38905 79722 43519 79722 39939 79722 39939 79723 43519 79723 39940 79723 39939 79724 39940 79724 39941 79724 39941 79725 39940 79725 39942 79725 39941 79726 39942 79726 39943 79726 39943 79727 39942 79727 43517 79727 39943 79728 43517 79728 39944 79728 39944 79729 43517 79729 39945 79729 39944 79730 39945 79730 39946 79730 39946 79731 39945 79731 39947 79731 39946 79732 39947 79732 38912 79732 38912 79733 39947 79733 43516 79733 38912 79734 39948 79734 39946 79734 39946 79735 39948 79735 39949 79735 39946 79736 39949 79736 39944 79736 39944 79737 39949 79737 39950 79737 39944 79738 39950 79738 39943 79738 39943 79739 39950 79739 39952 79739 39943 79740 39952 79740 39941 79740 39941 79741 39952 79741 39953 79741 39941 79742 39953 79742 39939 79742 39939 79743 39953 79743 39954 79743 39939 79744 39954 79744 38905 79744 38905 79745 39954 79745 38904 79745 39948 79746 39301 79746 39949 79746 39949 79747 39301 79747 39951 79747 39949 79748 39951 79748 39950 79748 39950 79749 39951 79749 39296 79749 39950 79750 39296 79750 39952 79750 39952 79751 39296 79751 39297 79751 39952 79752 39297 79752 39953 79752 39953 79753 39297 79753 39298 79753 39953 79754 39298 79754 39954 79754 39954 79755 39298 79755 39955 79755 39954 79756 39955 79756 38904 79756 38904 79757 39955 79757 38888 79757 39967 79758 39956 79758 39957 79758 39957 79759 39956 79759 43494 79759 39957 79760 43494 79760 39958 79760 39958 79761 43494 79761 43493 79761 39958 79762 43493 79762 39964 79762 39964 79763 43493 79763 43492 79763 39964 79764 43492 79764 39963 79764 39963 79765 43492 79765 39959 79765 39963 79766 39959 79766 39961 79766 39961 79767 39959 79767 43489 79767 39961 79768 43489 79768 39960 79768 39960 79769 43489 79769 43487 79769 39960 79770 39962 79770 39961 79770 39961 79771 39962 79771 39968 79771 39961 79772 39968 79772 39963 79772 39963 79773 39968 79773 39969 79773 39963 79774 39969 79774 39964 79774 39964 79775 39969 79775 39970 79775 39964 79776 39970 79776 39958 79776 39958 79777 39970 79777 39965 79777 39958 79778 39965 79778 39957 79778 39957 79779 39965 79779 39966 79779 39957 79780 39966 79780 39967 79780 39967 79781 39966 79781 39974 79781 39962 79782 38862 79782 39968 79782 39968 79783 38862 79783 39307 79783 39968 79784 39307 79784 39969 79784 39969 79785 39307 79785 39971 79785 39969 79786 39971 79786 39970 79786 39970 79787 39971 79787 39317 79787 39970 79788 39317 79788 39965 79788 39965 79789 39317 79789 39972 79789 39965 79790 39972 79790 39966 79790 39966 79791 39972 79791 39973 79791 39966 79792 39973 79792 39974 79792 39974 79793 39973 79793 38856 79793 39531 79794 39696 79794 39533 79794 39533 79795 39696 79795 39975 79795 39976 79796 39527 79796 39982 79796 39982 79797 39691 79797 39976 79797 39976 79798 39691 79798 39692 79798 39976 79799 39692 79799 39526 79799 39526 79800 39692 79800 39694 79800 39526 79801 39694 79801 39978 79801 39696 79802 39531 79802 39689 79802 39689 79803 39531 79803 39978 79803 39689 79804 39978 79804 39977 79804 39977 79805 39978 79805 39694 79805 39515 79806 39533 79806 39975 79806 39983 79807 39516 79807 39697 79807 39697 79808 39516 79808 39979 79808 39697 79809 39979 79809 39980 79809 39980 79810 39979 79810 39515 79810 39980 79811 39515 79811 39700 79811 39700 79812 39515 79812 39975 79812 39529 79813 39981 79813 39527 79813 39527 79814 39981 79814 39982 79814 39685 79815 39990 79815 39983 79815 39983 79816 39990 79816 39516 79816 39981 79817 39529 79817 39686 79817 39686 79818 39529 79818 39985 79818 39686 79819 39985 79819 39984 79819 39984 79820 39985 79820 39986 79820 39984 79821 39986 79821 39705 79821 39705 79822 39986 79822 39520 79822 39702 79823 39518 79823 39987 79823 39987 79824 39518 79824 39988 79824 39987 79825 39988 79825 39989 79825 39989 79826 39988 79826 39517 79826 39989 79827 39517 79827 39685 79827 39685 79828 39517 79828 39990 79828 39518 79829 39702 79829 39520 79829 39520 79830 39702 79830 39705 79830 39992 79831 39710 79831 39491 79831 39491 79832 39710 79832 39991 79832 39710 79833 39992 79833 39993 79833 39993 79834 39992 79834 39514 79834 39993 79835 39514 79835 39709 79835 39709 79836 39514 79836 39509 79836 39709 79837 39509 79837 39994 79837 39994 79838 39509 79838 39499 79838 39492 79839 39491 79839 39991 79839 39711 79840 40000 79840 39995 79840 39995 79841 40000 79841 39996 79841 39995 79842 39996 79842 39997 79842 39997 79843 39996 79843 39492 79843 39997 79844 39492 79844 39714 79844 39714 79845 39492 79845 39991 79845 39500 79846 39998 79846 39499 79846 39499 79847 39998 79847 39994 79847 39721 79848 39999 79848 39711 79848 39711 79849 39999 79849 40000 79849 39998 79850 39500 79850 39707 79850 39707 79851 39500 79851 39503 79851 39707 79852 39503 79852 39708 79852 39708 79853 39503 79853 39502 79853 39708 79854 39502 79854 40001 79854 40001 79855 39502 79855 39501 79855 39511 79856 39999 79856 39721 79856 39715 79857 40002 79857 39716 79857 39716 79858 40002 79858 39513 79858 39716 79859 39513 79859 39718 79859 39718 79860 39513 79860 39511 79860 39718 79861 39511 79861 39719 79861 39719 79862 39511 79862 39721 79862 40002 79863 39715 79863 39501 79863 39501 79864 39715 79864 40001 79864 40245 79865 39437 79865 40003 79865 40003 79866 39437 79866 39436 79866 40003 79867 39436 79867 40247 79867 40247 79868 39436 79868 39389 79868 40004 79869 39111 79869 40005 79869 40005 79870 39111 79870 40006 79870 40005 79871 40006 79871 40220 79871 40220 79872 40006 79872 39560 79872 40008 79873 39432 79873 40007 79873 40008 79874 40007 79874 40009 79874 40009 79875 40007 79875 40010 79875 40009 79876 40010 79876 40011 79876 40011 79877 40010 79877 39439 79877 40011 79878 39439 79878 40260 79878 40260 79879 39439 79879 40012 79879 40260 79880 40012 79880 40013 79880 40013 79881 40012 79881 40263 79881 40263 79882 40012 79882 38855 79882 40263 79883 38855 79883 38854 79883 40014 79884 39425 79884 38674 79884 38674 79885 39425 79885 40015 79885 38674 79886 40015 79886 40016 79886 40016 79887 40015 79887 40017 79887 40017 79888 40015 79888 40019 79888 40017 79889 40019 79889 40204 79889 40204 79890 40019 79890 40018 79890 40018 79891 40019 79891 40021 79891 40018 79892 40021 79892 40020 79892 40020 79893 40021 79893 40022 79893 40020 79894 40022 79894 40200 79894 40200 79895 40022 79895 40023 79895 40200 79896 40023 79896 40024 79896 39479 79897 39107 79897 39461 79897 39479 79898 39461 79898 39477 79898 39477 79899 39461 79899 39460 79899 39477 79900 39460 79900 40025 79900 40025 79901 39460 79901 39458 79901 40025 79902 39458 79902 40026 79902 40026 79903 39458 79903 40027 79903 40026 79904 40027 79904 39473 79904 39473 79905 40027 79905 40029 79905 39473 79906 40029 79906 40028 79906 40028 79907 40029 79907 40030 79907 40028 79908 40030 79908 39484 79908 39484 79909 40030 79909 40031 79909 39484 79910 40031 79910 40032 79910 40032 79911 40031 79911 39456 79911 40032 79912 39456 79912 40033 79912 40033 79913 39456 79913 40034 79913 40033 79914 40034 79914 40035 79914 40035 79915 40034 79915 39454 79915 40035 79916 39454 79916 40036 79916 40036 79917 39454 79917 39453 79917 40036 79918 39453 79918 40037 79918 40037 79919 39453 79919 39452 79919 40037 79920 39452 79920 40038 79920 40038 79921 39452 79921 40039 79921 40038 79922 40039 79922 40041 79922 40041 79923 40039 79923 40040 79923 40041 79924 40040 79924 40042 79924 40042 79925 40040 79925 39101 79925 40042 79926 39101 79926 38837 79926 40121 79927 40047 79927 40123 79927 40043 79928 39480 79928 40130 79928 39464 79929 40043 79929 40131 79929 39482 79930 39481 79930 40078 79930 40048 79931 40047 79931 40044 79931 40044 79932 40047 79932 40121 79932 40044 79933 40121 79933 40045 79933 40125 79934 40123 79934 40128 79934 40128 79935 40123 79935 40047 79935 40128 79936 40047 79936 40046 79936 40046 79937 40047 79937 40048 79937 40046 79938 40048 79938 39464 79938 40052 79939 40049 79939 40054 79939 40050 79940 40051 79940 40089 79940 40089 79941 40051 79941 40052 79941 40089 79942 40052 79942 40053 79942 40053 79943 40052 79943 40054 79943 40053 79944 40054 79944 40087 79944 40085 79945 39472 79945 40086 79945 40086 79946 39472 79946 40094 79946 40086 79947 40094 79947 40088 79947 40088 79948 40094 79948 40055 79948 40088 79949 40055 79949 40092 79949 40092 79950 40055 79950 40091 79950 40095 79951 39469 79951 40057 79951 40057 79952 39469 79952 40056 79952 40057 79953 40056 79953 40058 79953 40058 79954 40056 79954 40097 79954 40058 79955 40097 79955 40059 79955 40059 79956 40097 79956 40099 79956 40059 79957 40099 79957 39155 79957 39155 79958 40099 79958 40060 79958 39468 79959 39467 79959 40096 79959 40096 79960 39467 79960 40061 79960 40096 79961 40061 79961 40098 79961 40098 79962 40061 79962 40062 79962 40098 79963 40062 79963 40101 79963 40101 79964 40062 79964 40100 79964 39467 79965 40102 79965 40061 79965 40061 79966 40102 79966 40103 79966 40061 79967 40103 79967 40062 79967 40062 79968 40103 79968 40063 79968 40062 79969 40063 79969 40100 79969 40100 79970 40063 79970 40106 79970 40100 79971 40106 79971 39146 79971 39146 79972 40106 79972 39147 79972 40104 79973 40064 79973 40105 79973 40105 79974 40064 79974 40065 79974 40105 79975 40065 79975 40066 79975 40066 79976 40065 79976 40111 79976 40066 79977 40111 79977 40107 79977 40107 79978 40111 79978 40108 79978 40109 79979 40067 79979 40110 79979 40110 79980 40067 79980 40068 79980 40110 79981 40068 79981 40112 79981 40112 79982 40068 79982 40069 79982 40112 79983 40069 79983 40113 79983 40113 79984 40069 79984 40115 79984 40113 79985 40115 79985 39142 79985 39142 79986 40115 79986 39143 79986 40114 79987 40071 79987 40070 79987 40070 79988 40071 79988 40072 79988 40070 79989 40072 79989 40074 79989 40074 79990 40072 79990 40073 79990 40074 79991 40073 79991 40119 79991 40119 79992 40073 79992 40116 79992 40071 79993 40120 79993 40072 79993 40072 79994 40120 79994 40075 79994 40072 79995 40075 79995 40073 79995 40073 79996 40075 79996 40122 79996 40073 79997 40122 79997 40116 79997 40116 79998 40122 79998 40124 79998 40116 79999 40124 79999 39138 79999 39138 80000 40124 80000 39136 80000 39482 80001 40078 80001 38746 80001 38746 80002 40078 80002 40079 80002 38746 80003 40079 80003 40076 80003 40076 80004 40079 80004 40080 80004 40076 80005 40080 80005 38835 80005 38835 80006 40080 80006 40077 80006 38835 80007 40077 80007 39161 80007 39481 80008 40087 80008 40078 80008 40078 80009 40087 80009 40054 80009 40078 80010 40054 80010 40079 80010 40079 80011 40054 80011 40049 80011 40079 80012 40049 80012 40080 80012 40080 80013 40049 80013 40084 80013 40080 80014 40084 80014 40077 80014 40051 80015 40081 80015 40052 80015 40052 80016 40081 80016 40082 80016 40052 80017 40082 80017 40049 80017 40049 80018 40082 80018 40083 80018 40049 80019 40083 80019 40084 80019 39481 80020 40085 80020 40087 80020 40087 80021 40085 80021 40086 80021 40087 80022 40086 80022 40053 80022 40053 80023 40086 80023 40088 80023 40053 80024 40088 80024 40089 80024 40089 80025 40088 80025 40092 80025 40089 80026 40092 80026 40050 80026 40090 80027 39157 80027 40091 80027 40091 80028 39157 80028 40093 80028 40091 80029 40093 80029 40092 80029 40092 80030 40093 80030 39159 80030 40092 80031 39159 80031 40050 80031 39472 80032 40095 80032 40094 80032 40094 80033 40095 80033 40057 80033 40094 80034 40057 80034 40055 80034 40055 80035 40057 80035 40058 80035 40055 80036 40058 80036 40091 80036 40091 80037 40058 80037 40059 80037 40091 80038 40059 80038 40090 80038 40090 80039 40059 80039 39155 80039 39469 80040 39468 80040 40056 80040 40056 80041 39468 80041 40096 80041 40056 80042 40096 80042 40097 80042 40097 80043 40096 80043 40098 80043 40097 80044 40098 80044 40099 80044 40099 80045 40098 80045 40101 80045 40099 80046 40101 80046 40060 80046 39146 80047 39152 80047 40100 80047 40100 80048 39152 80048 39153 80048 40100 80049 39153 80049 40101 80049 40101 80050 39153 80050 39154 80050 40101 80051 39154 80051 40060 80051 40102 80052 40104 80052 40103 80052 40103 80053 40104 80053 40105 80053 40103 80054 40105 80054 40063 80054 40063 80055 40105 80055 40066 80055 40063 80056 40066 80056 40106 80056 40106 80057 40066 80057 40107 80057 40106 80058 40107 80058 39147 80058 39145 80059 39151 80059 40108 80059 40108 80060 39151 80060 39150 80060 40108 80061 39150 80061 40107 80061 40107 80062 39150 80062 39148 80062 40107 80063 39148 80063 39147 80063 40064 80064 40109 80064 40065 80064 40065 80065 40109 80065 40110 80065 40065 80066 40110 80066 40111 80066 40111 80067 40110 80067 40112 80067 40111 80068 40112 80068 40108 80068 40108 80069 40112 80069 40113 80069 40108 80070 40113 80070 39145 80070 39145 80071 40113 80071 39142 80071 40067 80072 40114 80072 40068 80072 40068 80073 40114 80073 40070 80073 40068 80074 40070 80074 40069 80074 40069 80075 40070 80075 40074 80075 40069 80076 40074 80076 40115 80076 40115 80077 40074 80077 40119 80077 40115 80078 40119 80078 39143 80078 39138 80079 39141 80079 40116 80079 40116 80080 39141 80080 40117 80080 40116 80081 40117 80081 40119 80081 40119 80082 40117 80082 40118 80082 40119 80083 40118 80083 39143 80083 40120 80084 40045 80084 40075 80084 40075 80085 40045 80085 40121 80085 40075 80086 40121 80086 40122 80086 40122 80087 40121 80087 40123 80087 40122 80088 40123 80088 40124 80088 40124 80089 40123 80089 40125 80089 40124 80090 40125 80090 39136 80090 39136 80091 40125 80091 40126 80091 40129 80092 39133 80092 39135 80092 39464 80093 40131 80093 40046 80093 40046 80094 40131 80094 40127 80094 40046 80095 40127 80095 40128 80095 40128 80096 40127 80096 40129 80096 40128 80097 40129 80097 40125 80097 40125 80098 40129 80098 39135 80098 40125 80099 39135 80099 40126 80099 40043 80100 40130 80100 40131 80100 40131 80101 40130 80101 38788 80101 40131 80102 38788 80102 40127 80102 40127 80103 38788 80103 38789 80103 40127 80104 38789 80104 40129 80104 40129 80105 38789 80105 39132 80105 40129 80106 39132 80106 39133 80106 40134 80107 40137 80107 40133 80107 40132 80108 40137 80108 40134 80108 38741 80109 40132 80109 40134 80109 40134 80110 40142 80110 38730 80110 40139 80111 40142 80111 40134 80111 40133 80112 40139 80112 40134 80112 38741 80113 40135 80113 40132 80113 40132 80114 40135 80114 40136 80114 40132 80115 40136 80115 40137 80115 40137 80116 40136 80116 40138 80116 40137 80117 40138 80117 40133 80117 40133 80118 40138 80118 40140 80118 40133 80119 40140 80119 40139 80119 40139 80120 40140 80120 40141 80120 40139 80121 40141 80121 40142 80121 40142 80122 40141 80122 40146 80122 40142 80123 40146 80123 38730 80123 38730 80124 40146 80124 38729 80124 40135 80125 38716 80125 40136 80125 40136 80126 38716 80126 39505 80126 40136 80127 39505 80127 40138 80127 40138 80128 39505 80128 40143 80128 40138 80129 40143 80129 40140 80129 40140 80130 40143 80130 40144 80130 40140 80131 40144 80131 40141 80131 40141 80132 40144 80132 40145 80132 40141 80133 40145 80133 40146 80133 40146 80134 40145 80134 40147 80134 40146 80135 40147 80135 38729 80135 38729 80136 40147 80136 39504 80136 38714 80137 38711 80137 40154 80137 40155 80138 40148 80138 38714 80138 40153 80139 40157 80139 38714 80139 40152 80140 40149 80140 38714 80140 38714 80141 40160 80141 40150 80141 40151 80142 40160 80142 38714 80142 40149 80143 40151 80143 38714 80143 40157 80144 40152 80144 38714 80144 40148 80145 40153 80145 38714 80145 40154 80146 40155 80146 38714 80146 38711 80147 38697 80147 40161 80147 38711 80148 40161 80148 40154 80148 40154 80149 40161 80149 40163 80149 40154 80150 40163 80150 40155 80150 40155 80151 40163 80151 40148 80151 40148 80152 40163 80152 40156 80152 40148 80153 40156 80153 40153 80153 40153 80154 40156 80154 40157 80154 40157 80155 40156 80155 40158 80155 40157 80156 40158 80156 40152 80156 40152 80157 40158 80157 40149 80157 40149 80158 40158 80158 40159 80158 40149 80159 40159 80159 40151 80159 40151 80160 40159 80160 40166 80160 40151 80161 40166 80161 40160 80161 40160 80162 40166 80162 38700 80162 40160 80163 38700 80163 40150 80163 38697 80164 38699 80164 40161 80164 40161 80165 38699 80165 40162 80165 40161 80166 40162 80166 40163 80166 40163 80167 40162 80167 39522 80167 40163 80168 39522 80168 40156 80168 40156 80169 39522 80169 39524 80169 40156 80170 39524 80170 40158 80170 40158 80171 39524 80171 40164 80171 40158 80172 40164 80172 40159 80172 40159 80173 40164 80173 40165 80173 40159 80174 40165 80174 40166 80174 40166 80175 40165 80175 39523 80175 40166 80176 39523 80176 38700 80176 38700 80177 39523 80177 38691 80177 40169 80178 40168 80178 40167 80178 40172 80179 40168 80179 40169 80179 40171 80180 40172 80180 40169 80180 40169 80181 40177 80181 40170 80181 40176 80182 40177 80182 40169 80182 40167 80183 40176 80183 40169 80183 40171 80184 38683 80184 40172 80184 40172 80185 38683 80185 40173 80185 40172 80186 40173 80186 40168 80186 40168 80187 40173 80187 40174 80187 40168 80188 40174 80188 40167 80188 40167 80189 40174 80189 40175 80189 40167 80190 40175 80190 40176 80190 40176 80191 40175 80191 40180 80191 40176 80192 40180 80192 40177 80192 40177 80193 40180 80193 40181 80193 40177 80194 40181 80194 40170 80194 40170 80195 40181 80195 40183 80195 38683 80196 40178 80196 40173 80196 40173 80197 40178 80197 39510 80197 40173 80198 39510 80198 40174 80198 40174 80199 39510 80199 39512 80199 40174 80200 39512 80200 40175 80200 40175 80201 39512 80201 40179 80201 40175 80202 40179 80202 40180 80202 40180 80203 40179 80203 39493 80203 40180 80204 39493 80204 40181 80204 40181 80205 39493 80205 40182 80205 40181 80206 40182 80206 40183 80206 40183 80207 40182 80207 38675 80207 40185 80208 39602 80208 39412 80208 39412 80209 39602 80209 40186 80209 39417 80210 39568 80210 39598 80210 39417 80211 39598 80211 40184 80211 40184 80212 39598 80212 39601 80212 40184 80213 39601 80213 39416 80213 39416 80214 39601 80214 39602 80214 39416 80215 39602 80215 40185 80215 39412 80216 40186 80216 39607 80216 39412 80217 39607 80217 39410 80217 39410 80218 39607 80218 39605 80218 39410 80219 39605 80219 39411 80219 39411 80220 39605 80220 40189 80220 39411 80221 40189 80221 40187 80221 40188 80222 40192 80222 39417 80222 39417 80223 40192 80223 39568 80223 39564 80224 39407 80224 40189 80224 40189 80225 39407 80225 40187 80225 39414 80226 39590 80226 39591 80226 39414 80227 39591 80227 40190 80227 40190 80228 39591 80228 39594 80228 40190 80229 39594 80229 40191 80229 40191 80230 39594 80230 40192 80230 40191 80231 40192 80231 40188 80231 39407 80232 39564 80232 40193 80232 39407 80233 40193 80233 39408 80233 39408 80234 40193 80234 40195 80234 39408 80235 40195 80235 40194 80235 40194 80236 40195 80236 40197 80236 40194 80237 40197 80237 40196 80237 40197 80238 39590 80238 40196 80238 40196 80239 39590 80239 39414 80239 39538 80240 40198 80240 38674 80240 38674 80241 40016 80241 39538 80241 39538 80242 40016 80242 40017 80242 39538 80243 40017 80243 40204 80243 40024 80244 40199 80244 40200 80244 40200 80245 40199 80245 40201 80245 40200 80246 40201 80246 40020 80246 40020 80247 40201 80247 40202 80247 40020 80248 40202 80248 40018 80248 40018 80249 40202 80249 40203 80249 40018 80250 40203 80250 40204 80250 40204 80251 40203 80251 39285 80251 40204 80252 39285 80252 39538 80252 40199 80253 40024 80253 39282 80253 39282 80254 40024 80254 39402 80254 39282 80255 39402 80255 39279 80255 39279 80256 39402 80256 40205 80256 39279 80257 40205 80257 40206 80257 40206 80258 40205 80258 40207 80258 40207 80259 40205 80259 39404 80259 40207 80260 39404 80260 39300 80260 39404 80261 40208 80261 39300 80261 39300 80262 40208 80262 40209 80262 39300 80263 40209 80263 39295 80263 40209 80264 40210 80264 39295 80264 39295 80265 40210 80265 39405 80265 39295 80266 39405 80266 40211 80266 40211 80267 39405 80267 39108 80267 40211 80268 39108 80268 39309 80268 39108 80269 40212 80269 39309 80269 39309 80270 40212 80270 40213 80270 39309 80271 40213 80271 39308 80271 40004 80272 40219 80272 39314 80272 40004 80273 39314 80273 40217 80273 40213 80274 39109 80274 39308 80274 39308 80275 39109 80275 40214 80275 39308 80276 40214 80276 40215 80276 40215 80277 40214 80277 40217 80277 40215 80278 40217 80278 40216 80278 40216 80279 40217 80279 39314 80279 40220 80280 39312 80280 40005 80280 40005 80281 39312 80281 40218 80281 40005 80282 40218 80282 40004 80282 40004 80283 40218 80283 40219 80283 39561 80284 39313 80284 40220 80284 40220 80285 39313 80285 39312 80285 39313 80286 39561 80286 39668 80286 39313 80287 39668 80287 39318 80287 39318 80288 39668 80288 39667 80288 39318 80289 39667 80289 39319 80289 39319 80290 39667 80290 39663 80290 39319 80291 39663 80291 40221 80291 40221 80292 39663 80292 39664 80292 40221 80293 39664 80293 40223 80293 40224 80294 40222 80294 39664 80294 39664 80295 40222 80295 40223 80295 40222 80296 40224 80296 40225 80296 40222 80297 40225 80297 40226 80297 40226 80298 40225 80298 39653 80298 40226 80299 39653 80299 40227 80299 39587 80300 39328 80300 39653 80300 39653 80301 39328 80301 40227 80301 39328 80302 39587 80302 39589 80302 39328 80303 39589 80303 39325 80303 39325 80304 39589 80304 40228 80304 39325 80305 40228 80305 39324 80305 39324 80306 40228 80306 39380 80306 39324 80307 39380 80307 39323 80307 39323 80308 39380 80308 40229 80308 39323 80309 40229 80309 39315 80309 39315 80310 40229 80310 39381 80310 39315 80311 39381 80311 39306 80311 39306 80312 39381 80312 39382 80312 39306 80313 39382 80313 39305 80313 39305 80314 39382 80314 39385 80314 39305 80315 39385 80315 40230 80315 40230 80316 39385 80316 40231 80316 40230 80317 40231 80317 40232 80317 39228 80318 40233 80318 40234 80318 39228 80319 40234 80319 39238 80319 39238 80320 40234 80320 39585 80320 39238 80321 39585 80321 40235 80321 40235 80322 39585 80322 40236 80322 40235 80323 40236 80323 40237 80323 39572 80324 40238 80324 40236 80324 40236 80325 40238 80325 40237 80325 40238 80326 39572 80326 39646 80326 40238 80327 39646 80327 40239 80327 40239 80328 39646 80328 39645 80328 40239 80329 39645 80329 39237 80329 40240 80330 39227 80330 39645 80330 39645 80331 39227 80331 39237 80331 39227 80332 40240 80332 39661 80332 39227 80333 39661 80333 39224 80333 39224 80334 39661 80334 39658 80334 39224 80335 39658 80335 40242 80335 39658 80336 40241 80336 40242 80336 40242 80337 40241 80337 39655 80337 40242 80338 39655 80338 40243 80338 39655 80339 40244 80339 40243 80339 40243 80340 40244 80340 40246 80340 40243 80341 40246 80341 39233 80341 40245 80342 40249 80342 40246 80342 40246 80343 40249 80343 39233 80343 40247 80344 39236 80344 40003 80344 40003 80345 39236 80345 40248 80345 40003 80346 40248 80346 40245 80346 40245 80347 40248 80347 40249 80347 39253 80348 40250 80348 39397 80348 39397 80349 39396 80349 39253 80349 39253 80350 39396 80350 40251 80350 39253 80351 40251 80351 39258 80351 40251 80352 40252 80352 39258 80352 39258 80353 40252 80353 40254 80353 39258 80354 40254 80354 40253 80354 40253 80355 40254 80355 39387 80355 40253 80356 39387 80356 39400 80356 39272 80357 40255 80357 39400 80357 39400 80358 40255 80358 40256 80358 39400 80359 40256 80359 40253 80359 40008 80360 39268 80360 39401 80360 39401 80361 39268 80361 39272 80361 39401 80362 39272 80362 40257 80362 40257 80363 39272 80363 39400 80363 38854 80364 40258 80364 40262 80364 39268 80365 40008 80365 39264 80365 39264 80366 40008 80366 40009 80366 39264 80367 40009 80367 40259 80367 40259 80368 40009 80368 40011 80368 40259 80369 40011 80369 40261 80369 40261 80370 40011 80370 40260 80370 40261 80371 40260 80371 39267 80371 39267 80372 40260 80372 40013 80372 39267 80373 40013 80373 40262 80373 40262 80374 40013 80374 40263 80374 40262 80375 40263 80375 38854 80375 39674 80376 39581 80376 39673 80376 39673 80377 39581 80377 40264 80377 39673 80378 40264 80378 39672 80378 39672 80379 40264 80379 39665 80379 39675 80380 40265 80380 39609 80380 39609 80381 40265 80381 40266 80381 39609 80382 40266 80382 39674 80382 39674 80383 40266 80383 39581 80383 40267 80384 40268 80384 39579 80384 39600 80385 39678 80385 39599 80385 39599 80386 39678 80386 39597 80386 39600 80387 40267 80387 39678 80387 39678 80388 40267 80388 39579 80388 39678 80389 39579 80389 39677 80389 39677 80390 39579 80390 39583 80390 39677 80391 39583 80391 40270 80391 40270 80392 39583 80392 40269 80392 40270 80393 40269 80393 39675 80393 39675 80394 40269 80394 40265 80394 39577 80395 39649 80395 39647 80395 40271 80396 39574 80396 40272 80396 40272 80397 39574 80397 39577 80397 40272 80398 39577 80398 39093 80398 39093 80399 39577 80399 39647 80399 39093 80400 39647 80400 39089 80400 40273 80401 40274 80401 40276 80401 40276 80402 40274 80402 40275 80402 40276 80403 40275 80403 39580 80403 39578 80404 39098 80404 39580 80404 39580 80405 39098 80405 39094 80405 39580 80406 39094 80406 40276 80406 39566 80407 39565 80407 39680 80407 39565 80408 39603 80408 39680 80408 39680 80409 39603 80409 40277 80409 39680 80410 40277 80410 39679 80410 40278 80411 40279 80411 39683 80411 39683 80412 40279 80412 40280 80412 39683 80413 40280 80413 39682 80413 39682 80414 40280 80414 39576 80414 39682 80415 39576 80415 39680 80415 39680 80416 39576 80416 39575 80416 39680 80417 39575 80417 39566 80417 39614 80418 40281 80418 39613 80418 39613 80419 40281 80419 40282 80419 39613 80420 40282 80420 40278 80420 40278 80421 40282 80421 40279 80421 39659 80422 39660 80422 39670 80422 39670 80423 39660 80423 40283 80423 39670 80424 40283 80424 39614 80424 39614 80425 40283 80425 40281 80425 39563 80426 39090 80426 40284 80426 43437 80427 39563 80427 40285 80427 40285 80428 39563 80428 40284 80428 40285 80429 40284 80429 39088 80429 40286 80430 39596 80430 39595 80430 40286 80431 39595 80431 40287 80431 40287 80432 39595 80432 40288 80432 40287 80433 40288 80433 43430 80433 43430 80434 40288 80434 39563 80434 43430 80435 39563 80435 43437 80435 39451 80436 39596 80436 43434 80436 43434 80437 39596 80437 40286 80437 40289 80438 40291 80438 39593 80438 40289 80439 39593 80439 43427 80439 43427 80440 39593 80440 39592 80440 43427 80441 39592 80441 40290 80441 40290 80442 39592 80442 39451 80442 40290 80443 39451 80443 43434 80443 43435 80444 39095 80444 39096 80444 40289 80445 43435 80445 40291 80445 40291 80446 43435 80446 39096 80446 40291 80447 39096 80447 39567 80447 40293 80448 43466 80448 39652 80448 39099 80449 40293 80449 40292 80449 40292 80450 40293 80450 39652 80450 40292 80451 39652 80451 39651 80451 43465 80452 39586 80452 43466 80452 43466 80453 39586 80453 39652 80453 43463 80454 38627 80454 40294 80454 43463 80455 40294 80455 43464 80455 43464 80456 40294 80456 39588 80456 43464 80457 39588 80457 40295 80457 40295 80458 39588 80458 39586 80458 40295 80459 39586 80459 43465 80459 40304 80460 39117 80460 39115 80460 40304 80461 39115 80461 40297 80461 40297 80462 39115 80462 40296 80462 40297 80463 40296 80463 40298 80463 40298 80464 40296 80464 39113 80464 40298 80465 39113 80465 40299 80465 40299 80466 39113 80466 40301 80466 40299 80467 40301 80467 40300 80467 40300 80468 40301 80468 40302 80468 40300 80469 40302 80469 43444 80469 43429 80470 39573 80470 40303 80470 43429 80471 40303 80471 43431 80471 43431 80472 40303 80472 39584 80472 43431 80473 39584 80473 43438 80473 43438 80474 39584 80474 39117 80474 43438 80475 39117 80475 40304 80475 40305 80476 39571 80476 43429 80476 43429 80477 39571 80477 39573 80477 39571 80478 40305 80478 40306 80478 40306 80479 39162 80479 39571 80479 39571 80480 39162 80480 40307 80480 39571 80481 40307 80481 39648 80481 38623 80482 39343 80482 40308 80482 38623 80483 39339 80483 39340 80483 39341 80484 39339 80484 38623 80484 40308 80485 39341 80485 38623 80485 38623 80486 40309 80486 39359 80486 40310 80487 40309 80487 38623 80487 39340 80488 40310 80488 38623 80488 40311 80489 38621 80489 39358 80489 40311 80490 40312 80490 39375 80490 40313 80491 40312 80491 40311 80491 39358 80492 40313 80492 40311 80492 40311 80493 40314 80493 38620 80493 39376 80494 40314 80494 40311 80494 39375 80495 39376 80495 40311 80495 40315 80496 39346 80496 39349 80496 39353 80497 39346 80497 40315 80497 39356 80498 39353 80498 40315 80498 40315 80499 39347 80499 39362 80499 39348 80500 39347 80500 40315 80500 39349 80501 39348 80501 40315 80501 38611 80502 39336 80502 40316 80502 39337 80503 39336 80503 38611 80503 39377 80504 39337 80504 38611 80504 38611 80505 39366 80505 39365 80505 39335 80506 39366 80506 38611 80506 40316 80507 39335 80507 38611 80507 40317 80508 39722 80508 40327 80508 40326 80509 39712 80509 40328 80509 40327 80510 40318 80510 40317 80510 40317 80511 40318 80511 40319 80511 40317 80512 40319 80512 40323 80512 39706 80513 40320 80513 40321 80513 40321 80514 40320 80514 40317 80514 40321 80515 40317 80515 40322 80515 40322 80516 40317 80516 40323 80516 39722 80517 39717 80517 40327 80517 40327 80518 39717 80518 39720 80518 40327 80519 39720 80519 40324 80519 40324 80520 40325 80520 40327 80520 40327 80521 40325 80521 40326 80521 40327 80522 40326 80522 39713 80522 39713 80523 40326 80523 40328 80523 40334 80524 39693 80524 39690 80524 40329 80525 39701 80525 39695 80525 39703 80526 39704 80526 40329 80526 40329 80527 39704 80527 39684 80527 40329 80528 39684 80528 40331 80528 40330 80529 39701 80529 39699 80529 39699 80530 39701 80530 40329 80530 39699 80531 40329 80531 39698 80531 39698 80532 40329 80532 40331 80532 40332 80533 39687 80533 39688 80533 39688 80534 39687 80534 40333 80534 39688 80535 40333 80535 39690 80535 39690 80536 40333 80536 40329 80536 39690 80537 40329 80537 40334 80537 40334 80538 40329 80538 39695 80538 40335 80539 40504 80539 40339 80539 40339 80540 40504 80540 40338 80540 38597 80541 40339 80541 40336 80541 40336 80542 40339 80542 38598 80542 38597 80543 38595 80543 40339 80543 40339 80544 38595 80544 40337 80544 40339 80545 40337 80545 40335 80545 40338 80546 40502 80546 40339 80546 40339 80547 40502 80547 40501 80547 40339 80548 40501 80548 40500 80548 40500 80549 40499 80549 40339 80549 40339 80550 40499 80550 40498 80550 40339 80551 40498 80551 40496 80551 40496 80552 40495 80552 40339 80552 40339 80553 40495 80553 40492 80553 40339 80554 40492 80554 40341 80554 38607 80555 38605 80555 40345 80555 40345 80556 38605 80556 38604 80556 40345 80557 38604 80557 40340 80557 40341 80558 40342 80558 40339 80558 40339 80559 40342 80559 40343 80559 40339 80560 40343 80560 40344 80560 38598 80561 40339 80561 40345 80561 40345 80562 40339 80562 38609 80562 40345 80563 38609 80563 38607 80563 40340 80564 38601 80564 40345 80564 40345 80565 38601 80565 40346 80565 40345 80566 40346 80566 40347 80566 40360 80567 38306 80567 37924 80567 37924 80568 38306 80568 40348 80568 37924 80569 40348 80569 40349 80569 40349 80570 40348 80570 38304 80570 40349 80571 38304 80571 37923 80571 37923 80572 38304 80572 38303 80572 37923 80573 38303 80573 42300 80573 42300 80574 38303 80574 40350 80574 42300 80575 40350 80575 42299 80575 42299 80576 40350 80576 40929 80576 42299 80577 40929 80577 40351 80577 40351 80578 40929 80578 40352 80578 40351 80579 40352 80579 42296 80579 42296 80580 40352 80580 40353 80580 42296 80581 40353 80581 42295 80581 42295 80582 40353 80582 40354 80582 42295 80583 40354 80583 42294 80583 42294 80584 40354 80584 40355 80584 42294 80585 40355 80585 40356 80585 40356 80586 40355 80586 40357 80586 40356 80587 40357 80587 37928 80587 37928 80588 40357 80588 38308 80588 37928 80589 38308 80589 40358 80589 40358 80590 38308 80590 40359 80590 40358 80591 40359 80591 37925 80591 37925 80592 40359 80592 40360 80592 37925 80593 40360 80593 37924 80593 38300 80594 40361 80594 40371 80594 40371 80595 40361 80595 38296 80595 40371 80596 38296 80596 40362 80596 40362 80597 38296 80597 38295 80597 40362 80598 38295 80598 40363 80598 40363 80599 38295 80599 38294 80599 40363 80600 38294 80600 40364 80600 40364 80601 38294 80601 40365 80601 40364 80602 40365 80602 42020 80602 42020 80603 40365 80603 40939 80603 42020 80604 40939 80604 42019 80604 42019 80605 40939 80605 40366 80605 42019 80606 40366 80606 42018 80606 42018 80607 40366 80607 40937 80607 42018 80608 40937 80608 42017 80608 42017 80609 40937 80609 40935 80609 42017 80610 40935 80610 40367 80610 40367 80611 40935 80611 40934 80611 40367 80612 40934 80612 40368 80612 40368 80613 40934 80613 40932 80613 40368 80614 40932 80614 42015 80614 42015 80615 40932 80615 38302 80615 42015 80616 38302 80616 40369 80616 40369 80617 38302 80617 38301 80617 40369 80618 38301 80618 40370 80618 40370 80619 38301 80619 38300 80619 40370 80620 38300 80620 40371 80620 42009 80621 40942 80621 42007 80621 42007 80622 40942 80622 40941 80622 42007 80623 40941 80623 40372 80623 40372 80624 40941 80624 40373 80624 40372 80625 40373 80625 37973 80625 37973 80626 40373 80626 40374 80626 37973 80627 40374 80627 37971 80627 37971 80628 40374 80628 38293 80628 37971 80629 38293 80629 37970 80629 37970 80630 38293 80630 38292 80630 37970 80631 38292 80631 37968 80631 38292 80632 38291 80632 37968 80632 37968 80633 38291 80633 38290 80633 37968 80634 38290 80634 37966 80634 37966 80635 38290 80635 38287 80635 37966 80636 38287 80636 40375 80636 40375 80637 38287 80637 38286 80637 40375 80638 38286 80638 37965 80638 37965 80639 38286 80639 40946 80639 37965 80640 40946 80640 42012 80640 42012 80641 40946 80641 40945 80641 42012 80642 40945 80642 42010 80642 42010 80643 40945 80643 40376 80643 42010 80644 40376 80644 42009 80644 42009 80645 40376 80645 40944 80645 42009 80646 40944 80646 40942 80646 40388 80647 40389 80647 40377 80647 40377 80648 40389 80648 40378 80648 40377 80649 40378 80649 38284 80649 38284 80650 40378 80650 42000 80650 38284 80651 42000 80651 40948 80651 40948 80652 42000 80652 42002 80652 40948 80653 42002 80653 40949 80653 40949 80654 42002 80654 42003 80654 40949 80655 42003 80655 40379 80655 40379 80656 42003 80656 42004 80656 40379 80657 42004 80657 40951 80657 40951 80658 42004 80658 40380 80658 40951 80659 40380 80659 40950 80659 40950 80660 40380 80660 40381 80660 40950 80661 40381 80661 38277 80661 38277 80662 40381 80662 40382 80662 38277 80663 40382 80663 40383 80663 40383 80664 40382 80664 40384 80664 40383 80665 40384 80665 38279 80665 38279 80666 40384 80666 40385 80666 38279 80667 40385 80667 40386 80667 40386 80668 40385 80668 40387 80668 40386 80669 40387 80669 38280 80669 38280 80670 40387 80670 37975 80670 38280 80671 37975 80671 40388 80671 40388 80672 37975 80672 40389 80672 40390 80673 38271 80673 37979 80673 37979 80674 38271 80674 38269 80674 37979 80675 38269 80675 37978 80675 37978 80676 38269 80676 40391 80676 37978 80677 40391 80677 40392 80677 40392 80678 40391 80678 38268 80678 40392 80679 38268 80679 37976 80679 37976 80680 38268 80680 40961 80680 37976 80681 40961 80681 41998 80681 41998 80682 40961 80682 40960 80682 41998 80683 40960 80683 41997 80683 41997 80684 40960 80684 40958 80684 41997 80685 40958 80685 41995 80685 41995 80686 40958 80686 40957 80686 41995 80687 40957 80687 40394 80687 40394 80688 40957 80688 40393 80688 40394 80689 40393 80689 40395 80689 40395 80690 40393 80690 40955 80690 40395 80691 40955 80691 40396 80691 40396 80692 40955 80692 40954 80692 40396 80693 40954 80693 40397 80693 40397 80694 40954 80694 38275 80694 40397 80695 38275 80695 37982 80695 37982 80696 38275 80696 38274 80696 37982 80697 38274 80697 37981 80697 37981 80698 38274 80698 40390 80698 37981 80699 40390 80699 37979 80699 40398 80700 38265 80700 37987 80700 37987 80701 38265 80701 40399 80701 37987 80702 40399 80702 37986 80702 37986 80703 40399 80703 40400 80703 37986 80704 40400 80704 37984 80704 37984 80705 40400 80705 40401 80705 37984 80706 40401 80706 40402 80706 40402 80707 40401 80707 40403 80707 40402 80708 40403 80708 41992 80708 41992 80709 40403 80709 40966 80709 41992 80710 40966 80710 41989 80710 41989 80711 40966 80711 40404 80711 41989 80712 40404 80712 41988 80712 41988 80713 40404 80713 40965 80713 41988 80714 40965 80714 41986 80714 41986 80715 40965 80715 40405 80715 41986 80716 40405 80716 40406 80716 40406 80717 40405 80717 40407 80717 40406 80718 40407 80718 41985 80718 41985 80719 40407 80719 40963 80719 41985 80720 40963 80720 40408 80720 40408 80721 40963 80721 38267 80721 40408 80722 38267 80722 37990 80722 37990 80723 38267 80723 40409 80723 37990 80724 40409 80724 37988 80724 37988 80725 40409 80725 40398 80725 37988 80726 40398 80726 37987 80726 40418 80727 41976 80727 40970 80727 40970 80728 41976 80728 41977 80728 40970 80729 41977 80729 40410 80729 40410 80730 41977 80730 41979 80730 40410 80731 41979 80731 40973 80731 40973 80732 41979 80732 40411 80732 40973 80733 40411 80733 40975 80733 40975 80734 40411 80734 40412 80734 40975 80735 40412 80735 40413 80735 40413 80736 40412 80736 41982 80736 40413 80737 41982 80737 40976 80737 40976 80738 41982 80738 37992 80738 40976 80739 37992 80739 40414 80739 40414 80740 37992 80740 40415 80740 40414 80741 40415 80741 38259 80741 38259 80742 40415 80742 37995 80742 38259 80743 37995 80743 38260 80743 38260 80744 37995 80744 37996 80744 38260 80745 37996 80745 38261 80745 38261 80746 37996 80746 40416 80746 38261 80747 40416 80747 38262 80747 38262 80748 40416 80748 40417 80748 38262 80749 40417 80749 40968 80749 40968 80750 40417 80750 37997 80750 40968 80751 37997 80751 40418 80751 40418 80752 37997 80752 41976 80752 38250 80753 37998 80753 40419 80753 40419 80754 37998 80754 37999 80754 40419 80755 37999 80755 38252 80755 38252 80756 37999 80756 40420 80756 38252 80757 40420 80757 38253 80757 38253 80758 40420 80758 38001 80758 38253 80759 38001 80759 40421 80759 40421 80760 38001 80760 38002 80760 40421 80761 38002 80761 40977 80761 40977 80762 38002 80762 41971 80762 40977 80763 41971 80763 40978 80763 40978 80764 41971 80764 40422 80764 40978 80765 40422 80765 40423 80765 40423 80766 40422 80766 40424 80766 40423 80767 40424 80767 40425 80767 40425 80768 40424 80768 41973 80768 40425 80769 41973 80769 40426 80769 40426 80770 41973 80770 40427 80770 40426 80771 40427 80771 40428 80771 40428 80772 40427 80772 40429 80772 40428 80773 40429 80773 40430 80773 40430 80774 40429 80774 40431 80774 40430 80775 40431 80775 40432 80775 40432 80776 40431 80776 40433 80776 40432 80777 40433 80777 38250 80777 38250 80778 40433 80778 37998 80778 41965 80779 40447 80779 41964 80779 41964 80780 40447 80780 40434 80780 41964 80781 40434 80781 41963 80781 41963 80782 40434 80782 40435 80782 41963 80783 40435 80783 40436 80783 40436 80784 40435 80784 40983 80784 40436 80785 40983 80785 40437 80785 40437 80786 40983 80786 38249 80786 40437 80787 38249 80787 40438 80787 40438 80788 38249 80788 38246 80788 40438 80789 38246 80789 40439 80789 38246 80790 40440 80790 40439 80790 40439 80791 40440 80791 38244 80791 40439 80792 38244 80792 40441 80792 40441 80793 38244 80793 38243 80793 40441 80794 38243 80794 38004 80794 38004 80795 38243 80795 40442 80795 38004 80796 40442 80796 40444 80796 40444 80797 40442 80797 40443 80797 40444 80798 40443 80798 41968 80798 41968 80799 40443 80799 40986 80799 41968 80800 40986 80800 41966 80800 41966 80801 40986 80801 40445 80801 41966 80802 40445 80802 41965 80802 41965 80803 40445 80803 40446 80803 41965 80804 40446 80804 40447 80804 41959 80805 40990 80805 41958 80805 41958 80806 40990 80806 40448 80806 41958 80807 40448 80807 41957 80807 41957 80808 40448 80808 40449 80808 41957 80809 40449 80809 38013 80809 38013 80810 40449 80810 40450 80810 38013 80811 40450 80811 38012 80811 38012 80812 40450 80812 38241 80812 38012 80813 38241 80813 40451 80813 40451 80814 38241 80814 38240 80814 40451 80815 38240 80815 40452 80815 38240 80816 40453 80816 40452 80816 40452 80817 40453 80817 40454 80817 40452 80818 40454 80818 40455 80818 40455 80819 40454 80819 38239 80819 40455 80820 38239 80820 38011 80820 38011 80821 38239 80821 38237 80821 38011 80822 38237 80822 38009 80822 38009 80823 38237 80823 40456 80823 38009 80824 40456 80824 40457 80824 40457 80825 40456 80825 40991 80825 40457 80826 40991 80826 40458 80826 40458 80827 40991 80827 40459 80827 40458 80828 40459 80828 41959 80828 41959 80829 40459 80829 40460 80829 41959 80830 40460 80830 40990 80830 38017 80831 38230 80831 40461 80831 40461 80832 38230 80832 40463 80832 40461 80833 40463 80833 40462 80833 40462 80834 40463 80834 38228 80834 40462 80835 38228 80835 40464 80835 40464 80836 38228 80836 41002 80836 40464 80837 41002 80837 40465 80837 40465 80838 41002 80838 41001 80838 40465 80839 41001 80839 41955 80839 41955 80840 41001 80840 40466 80840 41955 80841 40466 80841 40468 80841 40468 80842 40466 80842 40467 80842 40468 80843 40467 80843 40469 80843 40469 80844 40467 80844 40471 80844 40469 80845 40471 80845 40470 80845 40470 80846 40471 80846 40997 80846 40470 80847 40997 80847 41951 80847 41951 80848 40997 80848 40995 80848 41951 80849 40995 80849 40472 80849 40472 80850 40995 80850 40474 80850 40472 80851 40474 80851 40473 80851 40473 80852 40474 80852 38234 80852 40473 80853 38234 80853 38017 80853 38017 80854 38234 80854 38233 80854 38017 80855 38233 80855 38230 80855 38223 80856 38221 80856 40475 80856 40475 80857 38221 80857 38219 80857 40475 80858 38219 80858 38019 80858 38019 80859 38219 80859 40476 80859 38019 80860 40476 80860 40477 80860 40477 80861 40476 80861 40478 80861 40477 80862 40478 80862 38018 80862 38018 80863 40478 80863 40480 80863 38018 80864 40480 80864 40479 80864 40479 80865 40480 80865 40481 80865 40479 80866 40481 80866 40482 80866 40482 80867 40481 80867 41005 80867 40482 80868 41005 80868 41950 80868 41950 80869 41005 80869 40483 80869 41950 80870 40483 80870 41949 80870 41949 80871 40483 80871 40484 80871 41949 80872 40484 80872 41948 80872 41948 80873 40484 80873 40485 80873 41948 80874 40485 80874 40486 80874 40486 80875 40485 80875 40487 80875 40486 80876 40487 80876 40488 80876 40488 80877 40487 80877 38226 80877 40488 80878 38226 80878 40489 80878 40489 80879 38226 80879 38223 80879 40489 80880 38223 80880 40475 80880 38610 80881 40339 80881 40915 80881 40915 80882 40339 80882 40344 80882 40915 80883 40344 80883 40490 80883 40490 80884 40344 80884 40343 80884 40490 80885 40343 80885 40913 80885 40913 80886 40343 80886 40342 80886 40913 80887 40342 80887 40491 80887 40491 80888 40342 80888 40341 80888 40491 80889 40341 80889 40919 80889 40919 80890 40341 80890 40492 80890 40919 80891 40492 80891 40493 80891 40493 80892 40492 80892 40495 80892 40493 80893 40495 80893 40494 80893 40494 80894 40495 80894 40496 80894 40494 80895 40496 80895 40497 80895 40497 80896 40496 80896 40498 80896 40497 80897 40498 80897 40921 80897 40921 80898 40498 80898 40499 80898 40921 80899 40499 80899 40920 80899 40920 80900 40499 80900 40500 80900 40920 80901 40500 80901 40926 80901 40926 80902 40500 80902 40501 80902 40926 80903 40501 80903 40503 80903 40503 80904 40501 80904 40502 80904 40503 80905 40502 80905 40924 80905 40924 80906 40502 80906 40338 80906 40924 80907 40338 80907 40923 80907 40923 80908 40338 80908 40504 80908 40923 80909 40504 80909 38593 80909 38593 80910 40504 80910 40335 80910 40505 80911 40513 80911 40512 80911 40819 80912 38281 80912 38282 80912 38282 80913 38283 80913 40819 80913 40819 80914 38283 80914 38285 80914 40819 80915 38285 80915 40506 80915 40506 80916 38285 80916 40947 80916 40505 80917 40512 80917 38278 80917 40507 80918 40510 80918 40508 80918 40508 80919 40510 80919 40527 80919 40508 80920 40527 80920 40526 80920 40507 80921 40509 80921 40510 80921 40510 80922 40509 80922 40952 80922 40510 80923 40952 80923 40512 80923 40512 80924 40952 80924 40511 80924 40512 80925 40511 80925 38278 80925 40694 80926 40512 80926 41070 80926 41070 80927 40512 80927 40513 80927 41070 80928 40513 80928 40517 80928 40517 80929 40513 80929 40516 80929 40820 80930 41076 80930 40514 80930 40820 80931 40514 80931 40819 80931 40514 80932 41073 80932 40819 80932 40819 80933 41073 80933 41072 80933 40819 80934 41072 80934 38281 80934 38281 80935 41072 80935 40515 80935 38281 80936 40515 80936 40516 80936 40516 80937 40515 80937 41071 80937 40516 80938 41071 80938 40517 80938 40520 80939 40591 80939 40518 80939 40518 80940 40591 80940 40593 80940 40518 80941 40593 80941 41109 80941 41109 80942 40593 80942 41110 80942 40524 80943 40522 80943 40519 80943 40519 80944 40522 80944 40591 80944 40519 80945 40591 80945 41107 80945 41107 80946 40591 80946 40520 80946 38194 80947 40521 80947 41105 80947 41105 80948 40521 80948 40522 80948 41105 80949 40522 80949 40523 80949 40523 80950 40522 80950 40524 80950 40947 80951 40525 80951 40506 80951 40506 80952 40525 80952 40526 80952 40506 80953 40526 80953 40846 80953 40846 80954 40526 80954 40527 80954 40846 80955 40527 80955 40817 80955 40817 80956 40527 80956 40698 80956 40817 80957 40698 80957 40528 80957 40528 80958 40698 80958 40699 80958 40528 80959 40699 80959 40823 80959 40823 80960 40699 80960 40529 80960 40823 80961 40529 80961 40530 80961 40530 80962 40529 80962 40701 80962 40701 80963 38288 80963 40530 80963 40530 80964 38288 80964 38289 80964 40530 80965 38289 80965 40531 80965 40540 80966 40812 80966 40532 80966 40532 80967 40812 80967 40530 80967 40532 80968 40530 80968 40533 80968 40533 80969 40530 80969 40531 80969 40542 80970 40943 80970 40535 80970 40943 80971 40534 80971 40535 80971 40535 80972 40534 80972 40536 80972 40535 80973 40536 80973 40702 80973 40536 80974 40537 80974 40702 80974 40702 80975 40537 80975 40538 80975 40702 80976 40538 80976 40701 80976 40701 80977 40538 80977 40539 80977 40701 80978 40539 80978 38288 80978 40540 80979 40541 80979 40812 80979 40812 80980 40541 80980 40542 80980 40812 80981 40542 80981 40813 80981 40813 80982 40542 80982 40535 80982 40813 80983 40535 80983 40814 80983 40814 80984 40535 80984 40543 80984 40814 80985 40543 80985 40815 80985 40815 80986 40543 80986 40544 80986 40815 80987 40544 80987 40545 80987 40545 80988 40544 80988 40705 80988 40545 80989 40705 80989 40550 80989 40550 80990 40705 80990 40706 80990 40933 80991 40546 80991 40560 80991 40933 80992 40560 80992 40561 80992 40546 80993 40936 80993 40560 80993 40560 80994 40936 80994 40547 80994 40560 80995 40547 80995 40709 80995 40547 80996 40938 80996 40709 80996 40709 80997 40938 80997 40548 80997 40709 80998 40548 80998 40706 80998 40706 80999 40548 80999 40940 80999 40706 81000 40940 81000 40550 81000 40550 81001 40940 81001 40549 81001 40550 81002 40549 81002 38297 81002 38297 81003 38298 81003 40550 81003 40550 81004 38298 81004 38299 81004 40550 81005 38299 81005 40810 81005 40810 81006 38299 81006 40551 81006 40810 81007 40551 81007 40562 81007 40562 81008 40551 81008 40563 81008 38309 81009 40552 81009 40570 81009 38309 81010 40570 81010 38307 81010 40552 81011 40553 81011 40570 81011 40570 81012 40553 81012 40554 81012 40570 81013 40554 81013 40555 81013 40554 81014 40927 81014 40555 81014 40555 81015 40927 81015 40928 81015 40555 81016 40928 81016 40556 81016 40928 81017 40930 81017 40556 81017 40556 81018 40930 81018 40806 81018 40556 81019 40806 81019 40557 81019 40557 81020 40806 81020 40807 81020 40557 81021 40807 81021 40558 81021 40558 81022 40807 81022 40559 81022 40558 81023 40559 81023 40710 81023 40710 81024 40559 81024 40809 81024 40710 81025 40809 81025 40560 81025 40560 81026 40809 81026 40562 81026 40560 81027 40562 81027 40561 81027 40561 81028 40562 81028 40563 81028 40930 81029 40931 81029 40806 81029 40806 81030 40931 81030 40564 81030 40806 81031 40564 81031 40566 81031 40564 81032 40565 81032 40566 81032 40566 81033 40565 81033 38305 81033 40566 81034 38305 81034 40567 81034 40567 81035 38305 81035 40568 81035 40567 81036 40568 81036 40569 81036 40569 81037 38307 81037 40567 81037 40567 81038 38307 81038 40570 81038 40567 81039 40570 81039 40572 81039 40572 81040 40570 81040 40571 81040 40572 81041 40571 81041 40573 81041 40573 81042 40571 81042 40713 81042 40573 81043 40713 81043 40796 81043 40796 81044 40713 81044 40714 81044 40796 81045 40714 81045 40830 81045 40574 81046 40802 81046 38222 81046 38224 81047 38225 81047 40575 81047 40575 81048 38225 81048 38227 81048 40575 81049 38227 81049 40719 81049 40719 81050 38227 81050 40576 81050 40576 81051 40577 81051 40719 81051 40719 81052 40577 81052 41004 81052 40719 81053 41004 81053 40585 81053 40585 81054 41004 81054 40578 81054 40585 81055 40578 81055 40579 81055 40579 81056 40580 81056 40585 81056 40585 81057 40580 81057 40581 81057 40585 81058 40581 81058 40582 81058 40714 81059 40583 81059 40830 81059 40830 81060 40583 81060 40715 81060 40830 81061 40715 81061 40584 81061 40584 81062 40715 81062 40585 81062 40584 81063 40585 81063 40586 81063 40586 81064 40585 81064 40582 81064 40586 81065 40582 81065 41006 81065 41006 81066 40587 81066 40586 81066 40586 81067 40587 81067 40588 81067 40586 81068 40588 81068 40802 81068 40802 81069 40588 81069 38220 81069 40802 81070 38220 81070 38222 81070 38222 81071 38224 81071 40574 81071 40574 81072 38224 81072 40575 81072 40574 81073 40575 81073 40804 81073 40804 81074 40575 81074 40589 81074 40804 81075 40589 81075 40797 81075 40589 81076 40723 81076 40797 81076 40797 81077 40723 81077 40725 81077 40797 81078 40725 81078 40590 81078 40590 81079 40725 81079 40726 81079 40590 81080 40726 81080 40597 81080 40591 81081 40801 81081 38231 81081 38235 81082 40593 81082 40592 81082 40592 81083 40593 81083 40591 81083 40592 81084 40591 81084 38232 81084 38232 81085 40591 81085 38231 81085 40994 81086 40729 81086 40594 81086 40594 81087 40729 81087 40593 81087 40594 81088 40593 81088 38236 81088 38236 81089 40593 81089 38235 81089 40994 81090 40996 81090 40729 81090 40729 81091 40996 81091 40595 81091 40729 81092 40595 81092 40726 81092 40595 81093 40998 81093 40726 81093 40726 81094 40998 81094 40999 81094 40726 81095 40999 81095 40597 81095 40597 81096 40999 81096 41000 81096 40597 81097 41000 81097 40596 81097 40596 81098 40598 81098 40597 81098 40597 81099 40598 81099 41003 81099 40597 81100 41003 81100 40801 81100 40801 81101 41003 81101 38229 81101 40801 81102 38229 81102 38231 81102 40653 81103 38205 81103 40680 81103 40680 81104 38205 81104 40599 81104 40680 81105 40599 81105 40679 81105 40679 81106 40599 81106 40678 81106 40678 81107 40599 81107 40600 81107 40678 81108 40600 81108 40676 81108 40676 81109 40600 81109 40602 81109 40602 81110 40600 81110 40601 81110 40602 81111 40601 81111 40603 81111 40603 81112 40601 81112 40675 81112 40675 81113 40601 81113 40604 81113 40675 81114 40604 81114 40673 81114 40673 81115 40604 81115 40605 81115 40605 81116 40604 81116 40607 81116 40605 81117 40607 81117 40606 81117 40606 81118 40607 81118 40671 81118 40671 81119 40607 81119 40746 81119 40671 81120 40746 81120 40608 81120 40608 81121 40746 81121 40669 81121 40669 81122 40746 81122 40744 81122 40669 81123 40744 81123 40668 81123 40668 81124 40744 81124 40666 81124 40666 81125 40744 81125 40609 81125 40666 81126 40609 81126 40664 81126 40743 81127 40610 81127 40609 81127 40609 81128 40610 81128 40663 81128 40609 81129 40663 81129 40664 81129 40611 81130 40612 81130 40658 81130 40658 81131 40613 81131 40611 81131 40611 81132 40613 81132 40660 81132 40611 81133 40660 81133 40743 81133 40743 81134 40660 81134 40614 81134 40743 81135 40614 81135 40610 81135 40739 81136 40737 81136 40615 81136 40615 81137 40616 81137 40739 81137 40739 81138 40616 81138 40656 81138 40739 81139 40656 81139 40612 81139 40612 81140 40656 81140 40617 81140 40612 81141 40617 81141 40658 81141 40619 81142 40618 81142 40685 81142 40685 81143 40683 81143 40619 81143 40619 81144 40683 81144 40620 81144 40619 81145 40620 81145 40737 81145 40737 81146 40620 81146 40621 81146 40737 81147 40621 81147 40615 81147 40733 81148 38196 81148 41035 81148 41035 81149 40622 81149 40733 81149 40733 81150 40622 81150 40623 81150 40733 81151 40623 81151 40618 81151 40618 81152 40623 81152 40688 81152 40618 81153 40688 81153 40685 81153 40624 81154 40764 81154 40691 81154 40691 81155 40764 81155 40625 81155 40691 81156 40625 81156 40696 81156 40696 81157 40625 81157 40697 81157 40697 81158 40625 81158 40626 81158 40697 81159 40626 81159 40627 81159 40627 81160 40626 81160 40628 81160 40628 81161 40626 81161 40629 81161 40628 81162 40629 81162 40630 81162 40630 81163 40629 81163 40700 81163 40700 81164 40629 81164 40762 81164 40700 81165 40762 81165 40703 81165 40703 81166 40762 81166 40704 81166 40704 81167 40762 81167 40631 81167 40704 81168 40631 81168 40632 81168 40632 81169 40631 81169 40633 81169 40633 81170 40631 81170 40760 81170 40633 81171 40760 81171 40707 81171 40707 81172 40760 81172 40708 81172 40708 81173 40760 81173 40635 81173 40708 81174 40635 81174 40634 81174 40634 81175 40635 81175 40636 81175 40636 81176 40635 81176 40758 81176 40636 81177 40758 81177 40637 81177 40637 81178 40758 81178 40711 81178 40711 81179 40758 81179 40638 81179 40711 81180 40638 81180 40639 81180 40640 81181 40755 81181 40644 81181 40644 81182 40712 81182 40640 81182 40640 81183 40712 81183 40641 81183 40640 81184 40641 81184 40638 81184 40638 81185 40641 81185 40642 81185 40638 81186 40642 81186 40639 81186 40754 81187 40752 81187 40718 81187 40718 81188 40717 81188 40754 81188 40754 81189 40717 81189 40716 81189 40754 81190 40716 81190 40755 81190 40755 81191 40716 81191 40643 81191 40755 81192 40643 81192 40644 81192 40645 81193 40649 81193 40724 81193 40724 81194 40722 81194 40645 81194 40645 81195 40722 81195 40721 81195 40645 81196 40721 81196 40752 81196 40752 81197 40721 81197 40720 81197 40752 81198 40720 81198 40718 81198 40647 81199 40646 81199 40730 81199 40730 81200 40648 81200 40647 81200 40647 81201 40648 81201 40728 81201 40647 81202 40728 81202 40649 81202 40649 81203 40728 81203 40727 81203 40649 81204 40727 81204 40724 81204 40650 81205 41094 81205 41092 81205 41034 81206 40650 81206 41035 81206 41035 81207 40650 81207 41092 81207 41035 81208 41092 81208 40622 81208 40651 81209 41095 81209 40653 81209 40652 81210 40653 81210 41030 81210 41030 81211 40653 81211 41095 81211 41030 81212 41095 81212 41033 81212 41033 81213 41095 81213 40654 81213 38585 81214 40655 81214 40616 81214 40616 81215 40655 81215 38574 81215 40616 81216 38574 81216 40656 81216 40656 81217 38574 81217 38573 81217 40656 81218 38573 81218 40617 81218 40617 81219 38573 81219 40657 81219 40617 81220 40657 81220 40658 81220 40658 81221 40657 81221 38571 81221 40658 81222 38571 81222 40613 81222 40613 81223 38571 81223 40659 81223 40613 81224 40659 81224 40660 81224 40660 81225 40659 81225 40661 81225 40660 81226 40661 81226 40614 81226 40614 81227 40661 81227 38562 81227 40614 81228 38562 81228 40610 81228 40610 81229 38562 81229 40662 81229 40610 81230 40662 81230 40663 81230 40663 81231 40662 81231 38558 81231 40663 81232 38558 81232 40664 81232 40664 81233 38558 81233 40665 81233 40664 81234 40665 81234 40666 81234 40666 81235 40665 81235 38553 81235 40666 81236 38553 81236 40668 81236 40668 81237 38553 81237 40667 81237 40668 81238 40667 81238 40669 81238 40669 81239 40667 81239 40670 81239 40669 81240 40670 81240 40608 81240 40608 81241 40670 81241 38543 81241 40608 81242 38543 81242 40671 81242 40671 81243 38543 81243 40672 81243 40671 81244 40672 81244 40606 81244 40606 81245 40672 81245 38541 81245 40606 81246 38541 81246 40605 81246 40605 81247 38541 81247 38538 81247 40605 81248 38538 81248 40673 81248 40673 81249 38538 81249 38536 81249 40673 81250 38536 81250 40675 81250 40675 81251 38536 81251 40674 81251 40675 81252 40674 81252 40603 81252 40603 81253 40674 81253 38533 81253 40603 81254 38533 81254 40602 81254 40602 81255 38533 81255 38527 81255 40602 81256 38527 81256 40676 81256 40676 81257 38527 81257 40677 81257 40676 81258 40677 81258 40678 81258 40678 81259 40677 81259 38524 81259 40678 81260 38524 81260 40679 81260 40679 81261 38524 81261 40681 81261 40679 81262 40681 81262 40680 81262 40680 81263 40681 81263 40682 81263 40680 81264 40682 81264 40653 81264 40653 81265 40682 81265 38516 81265 40653 81266 38516 81266 40651 81266 40616 81267 40615 81267 38585 81267 38585 81268 40615 81268 40621 81268 38585 81269 40621 81269 38583 81269 38583 81270 40621 81270 38590 81270 40621 81271 40620 81271 38590 81271 38590 81272 40620 81272 40683 81272 38590 81273 40683 81273 40684 81273 40684 81274 40683 81274 40686 81274 40683 81275 40685 81275 40686 81275 40686 81276 40685 81276 40688 81276 40686 81277 40688 81277 40687 81277 40687 81278 40688 81278 40623 81278 40687 81279 40623 81279 40689 81279 40689 81280 40623 81280 40622 81280 40689 81281 40622 81281 38493 81281 38493 81282 40622 81282 41092 81282 38493 81283 41092 81283 40690 81283 40695 81284 41041 81284 40691 81284 40691 81285 41041 81285 41040 81285 40691 81286 41040 81286 40624 81286 40624 81287 41040 81287 40692 81287 41111 81288 41110 81288 40593 81288 41026 81289 40693 81289 41111 81289 41111 81290 40693 81290 38210 81290 41111 81291 38210 81291 38206 81291 40694 81292 40695 81292 40512 81292 40512 81293 40695 81293 40691 81293 40512 81294 40691 81294 40510 81294 40510 81295 40691 81295 40696 81295 40510 81296 40696 81296 40527 81296 40527 81297 40696 81297 40697 81297 40527 81298 40697 81298 40698 81298 40698 81299 40697 81299 40627 81299 40698 81300 40627 81300 40699 81300 40699 81301 40627 81301 40628 81301 40699 81302 40628 81302 40529 81302 40529 81303 40628 81303 40630 81303 40529 81304 40630 81304 40701 81304 40701 81305 40630 81305 40700 81305 40701 81306 40700 81306 40702 81306 40702 81307 40700 81307 40703 81307 40702 81308 40703 81308 40535 81308 40535 81309 40703 81309 40704 81309 40535 81310 40704 81310 40543 81310 40543 81311 40704 81311 40632 81311 40543 81312 40632 81312 40544 81312 40544 81313 40632 81313 40633 81313 40544 81314 40633 81314 40705 81314 40705 81315 40633 81315 40707 81315 40705 81316 40707 81316 40706 81316 40706 81317 40707 81317 40708 81317 40706 81318 40708 81318 40709 81318 40636 81319 40710 81319 40560 81319 40709 81320 40708 81320 40560 81320 40560 81321 40708 81321 40634 81321 40560 81322 40634 81322 40636 81322 40711 81323 40557 81323 40558 81323 40710 81324 40636 81324 40558 81324 40558 81325 40636 81325 40637 81325 40558 81326 40637 81326 40711 81326 40557 81327 40711 81327 40556 81327 40556 81328 40711 81328 40639 81328 40556 81329 40639 81329 40555 81329 40555 81330 40639 81330 40642 81330 40555 81331 40642 81331 40570 81331 40570 81332 40642 81332 40641 81332 40570 81333 40641 81333 40571 81333 40571 81334 40641 81334 40712 81334 40571 81335 40712 81335 40713 81335 40713 81336 40712 81336 40644 81336 40713 81337 40644 81337 40714 81337 40714 81338 40644 81338 40643 81338 40714 81339 40643 81339 40583 81339 40583 81340 40643 81340 40716 81340 40583 81341 40716 81341 40715 81341 40715 81342 40716 81342 40717 81342 40715 81343 40717 81343 40585 81343 40585 81344 40717 81344 40718 81344 40585 81345 40718 81345 40719 81345 40719 81346 40718 81346 40720 81346 40719 81347 40720 81347 40575 81347 40575 81348 40720 81348 40721 81348 40575 81349 40721 81349 40589 81349 40589 81350 40721 81350 40722 81350 40589 81351 40722 81351 40723 81351 40723 81352 40722 81352 40724 81352 40723 81353 40724 81353 40725 81353 40725 81354 40724 81354 40727 81354 40725 81355 40727 81355 40726 81355 40726 81356 40727 81356 40728 81356 40726 81357 40728 81357 40729 81357 40729 81358 40728 81358 40648 81358 40729 81359 40648 81359 40593 81359 40593 81360 40648 81360 40730 81360 40593 81361 40730 81361 41111 81361 41111 81362 40730 81362 40731 81362 41111 81363 40731 81363 41026 81363 40732 81364 38196 81364 40733 81364 40732 81365 40733 81365 40734 81365 40734 81366 40733 81366 40618 81366 40734 81367 40618 81367 40735 81367 40735 81368 40618 81368 40619 81368 40735 81369 40619 81369 40736 81369 40736 81370 40619 81370 40737 81370 40736 81371 40737 81371 40738 81371 40738 81372 40737 81372 40739 81372 40738 81373 40739 81373 40740 81373 40740 81374 40739 81374 40612 81374 40740 81375 40612 81375 40741 81375 40741 81376 40612 81376 40611 81376 40741 81377 40611 81377 40742 81377 40742 81378 40611 81378 40743 81378 40742 81379 40743 81379 43225 81379 43225 81380 40743 81380 40609 81380 43225 81381 40609 81381 43223 81381 43223 81382 40609 81382 40744 81382 43223 81383 40744 81383 40745 81383 40745 81384 40744 81384 40746 81384 40745 81385 40746 81385 43220 81385 43220 81386 40746 81386 40607 81386 43220 81387 40607 81387 40747 81387 40747 81388 40607 81388 40604 81388 40747 81389 40604 81389 43219 81389 43219 81390 40604 81390 40601 81390 43219 81391 40601 81391 40748 81391 40748 81392 40601 81392 40600 81392 40748 81393 40600 81393 40749 81393 40749 81394 40600 81394 40599 81394 40749 81395 40599 81395 43217 81395 43217 81396 40599 81396 38205 81396 43217 81397 38205 81397 40750 81397 40751 81398 40646 81398 40647 81398 40751 81399 40647 81399 43216 81399 43216 81400 40647 81400 40649 81400 43216 81401 40649 81401 43213 81401 43213 81402 40649 81402 40645 81402 43213 81403 40645 81403 43210 81403 43210 81404 40645 81404 40752 81404 43210 81405 40752 81405 40753 81405 40753 81406 40752 81406 40754 81406 40753 81407 40754 81407 43209 81407 43209 81408 40754 81408 40755 81408 43209 81409 40755 81409 43207 81409 43207 81410 40755 81410 40640 81410 43207 81411 40640 81411 40756 81411 40756 81412 40640 81412 40638 81412 40756 81413 40638 81413 40757 81413 40757 81414 40638 81414 40758 81414 40757 81415 40758 81415 40759 81415 40759 81416 40758 81416 40635 81416 40759 81417 40635 81417 43202 81417 43202 81418 40635 81418 40760 81418 43202 81419 40760 81419 40761 81419 40761 81420 40760 81420 40631 81420 40761 81421 40631 81421 43201 81421 43201 81422 40631 81422 40762 81422 43201 81423 40762 81423 43200 81423 43200 81424 40762 81424 40629 81424 43200 81425 40629 81425 43199 81425 43199 81426 40629 81426 40626 81426 43199 81427 40626 81427 40763 81427 40763 81428 40626 81428 40625 81428 40763 81429 40625 81429 43195 81429 43195 81430 40625 81430 40764 81430 43195 81431 40764 81431 41059 81431 38360 81432 38358 81432 40905 81432 38393 81433 40893 81433 40765 81433 40765 81434 40893 81434 40766 81434 40765 81435 40766 81435 38394 81435 38393 81436 40767 81436 40893 81436 40893 81437 40767 81437 40768 81437 40893 81438 40768 81438 40770 81438 40770 81439 40768 81439 40769 81439 40770 81440 40769 81440 38390 81440 38390 81441 38388 81441 40770 81441 40770 81442 38388 81442 40771 81442 40770 81443 40771 81443 40895 81443 40771 81444 38387 81444 40895 81444 40895 81445 38387 81445 40772 81445 40895 81446 40772 81446 40773 81446 40773 81447 40772 81447 38385 81447 40773 81448 38385 81448 38384 81448 38384 81449 38382 81449 40773 81449 40773 81450 38382 81450 38381 81450 40773 81451 38381 81451 40774 81451 38381 81452 38378 81452 40774 81452 40774 81453 38378 81453 40775 81453 40774 81454 40775 81454 40776 81454 40776 81455 40775 81455 38377 81455 40776 81456 38377 81456 38376 81456 38376 81457 40777 81457 40776 81457 40776 81458 40777 81458 38375 81458 40776 81459 38375 81459 40779 81459 38369 81460 40778 81460 38371 81460 38371 81461 40778 81461 40779 81461 38371 81462 40779 81462 38373 81462 38373 81463 40779 81463 38375 81463 38369 81464 38368 81464 40778 81464 40778 81465 38368 81465 40780 81465 40778 81466 40780 81466 40781 81466 40781 81467 40780 81467 38367 81467 40781 81468 38367 81468 38366 81468 38366 81469 38364 81469 40781 81469 40781 81470 38364 81470 40784 81470 40781 81471 40784 81471 40902 81471 38363 81472 40904 81472 40782 81472 40782 81473 40904 81473 40902 81473 40782 81474 40902 81474 40783 81474 40783 81475 40902 81475 40784 81475 38363 81476 40785 81476 40904 81476 40904 81477 40785 81477 38362 81477 40904 81478 38362 81478 40905 81478 40905 81479 38362 81479 40786 81479 40905 81480 40786 81480 38360 81480 38358 81481 40787 81481 40905 81481 40905 81482 40787 81482 38357 81482 40905 81483 38357 81483 40907 81483 38353 81484 40908 81484 38354 81484 38354 81485 40908 81485 40907 81485 38354 81486 40907 81486 38355 81486 38355 81487 40907 81487 38357 81487 38353 81488 40788 81488 40908 81488 40908 81489 40788 81489 40789 81489 40908 81490 40789 81490 40790 81490 40790 81491 40789 81491 38351 81491 40790 81492 38351 81492 38349 81492 38349 81493 40791 81493 40790 81493 40790 81494 40791 81494 38347 81494 40790 81495 38347 81495 40793 81495 40794 81496 40911 81496 40792 81496 40792 81497 40911 81497 40793 81497 40792 81498 40793 81498 38346 81498 38346 81499 40793 81499 38347 81499 40794 81500 38344 81500 40911 81500 40911 81501 38344 81501 40795 81501 40911 81502 40795 81502 38466 81502 38466 81503 40795 81503 38339 81503 38466 81504 38339 81504 38342 81504 40889 81505 40835 81505 38394 81505 38478 81506 38477 81506 40829 81506 40883 81507 40803 81507 40884 81507 40856 81508 40858 81508 40859 81508 40841 81509 40843 81509 40845 81509 40815 81510 40545 81510 40860 81510 40573 81511 40796 81511 40875 81511 40830 81512 40584 81512 40882 81512 40804 81513 40797 81513 40886 81513 40521 81514 38427 81514 40798 81514 40800 81515 40591 81515 40798 81515 40798 81516 40591 81516 40522 81516 40798 81517 40522 81517 40521 81517 40797 81518 40590 81518 40799 81518 40799 81519 40590 81519 40597 81519 40799 81520 40597 81520 40800 81520 40800 81521 40597 81521 40801 81521 40800 81522 40801 81522 40591 81522 40586 81523 40802 81523 40883 81523 40883 81524 40802 81524 40574 81524 40883 81525 40574 81525 40803 81525 40803 81526 40574 81526 40804 81526 40567 81527 40572 81527 40805 81527 40805 81528 40572 81528 40573 81528 40871 81529 40566 81529 40567 81529 40566 81530 40871 81530 40806 81530 40806 81531 40871 81531 40826 81531 40806 81532 40826 81532 40807 81532 40807 81533 40826 81533 40808 81533 40807 81534 40808 81534 40559 81534 40559 81535 40808 81535 40827 81535 40559 81536 40827 81536 40809 81536 40809 81537 40827 81537 40562 81537 40562 81538 40827 81538 40811 81538 40562 81539 40811 81539 40810 81539 40810 81540 40811 81540 40550 81540 40550 81541 40811 81541 40828 81541 40550 81542 40828 81542 40545 81542 40530 81543 40812 81543 40856 81543 40856 81544 40812 81544 40813 81544 40856 81545 40813 81545 40858 81545 40858 81546 40813 81546 40814 81546 40858 81547 40814 81547 40815 81547 40846 81548 40817 81548 40816 81548 40816 81549 40817 81549 40528 81549 40819 81550 40506 81550 40847 81550 40847 81551 40506 81551 40846 81551 41084 81552 40818 81552 40841 81552 40819 81553 40843 81553 40820 81553 40820 81554 40843 81554 40841 81554 40820 81555 40841 81555 41076 81555 41076 81556 40841 81556 40818 81556 40839 81557 40838 81557 40840 81557 40821 81558 40854 81558 40822 81558 40528 81559 40823 81559 40822 81559 40822 81560 40823 81560 40824 81560 40822 81561 40824 81561 40821 81561 40821 81562 40824 81562 40855 81562 40821 81563 40855 81563 40851 81563 40851 81564 40855 81564 40825 81564 40871 81565 40868 81565 40826 81565 40826 81566 40868 81566 40867 81566 40826 81567 40867 81567 40808 81567 40808 81568 40867 81568 40865 81568 40808 81569 40865 81569 40827 81569 40827 81570 40865 81570 40864 81570 40827 81571 40864 81571 40811 81571 40811 81572 40864 81572 40862 81572 40811 81573 40862 81573 40828 81573 40828 81574 40862 81574 40829 81574 40832 81575 40879 81575 40831 81575 40796 81576 40830 81576 40831 81576 40831 81577 40830 81577 40882 81577 40831 81578 40882 81578 40832 81578 40832 81579 40882 81579 40833 81579 40832 81580 40833 81580 38485 81580 38485 81581 40833 81581 40834 81581 38427 81582 40835 81582 40798 81582 40798 81583 40835 81583 40889 81583 40798 81584 40889 81584 40800 81584 40800 81585 40889 81585 40836 81585 40800 81586 40836 81586 40799 81586 40799 81587 40836 81587 40891 81587 38342 81588 40838 81588 40837 81588 40837 81589 40838 81589 40839 81589 40837 81590 40839 81590 38467 81590 41082 81591 41084 81591 40840 81591 40840 81592 41084 81592 40841 81592 40840 81593 40841 81593 40839 81593 40839 81594 40841 81594 40845 81594 40839 81595 40845 81595 38467 81595 38467 81596 40845 81596 40842 81596 40849 81597 38469 81597 40844 81597 40819 81598 40847 81598 40843 81598 40843 81599 40847 81599 40849 81599 40843 81600 40849 81600 40845 81600 40845 81601 40849 81601 40844 81601 40845 81602 40844 81602 40842 81602 40846 81603 40816 81603 40847 81603 40847 81604 40816 81604 40848 81604 40847 81605 40848 81605 40849 81605 40849 81606 40848 81606 38468 81606 40849 81607 38468 81607 38469 81607 40528 81608 40822 81608 40816 81608 40816 81609 40822 81609 40854 81609 40816 81610 40854 81610 40848 81610 40848 81611 40854 81611 40850 81611 40848 81612 40850 81612 38468 81612 40851 81613 38472 81613 40821 81613 40821 81614 38472 81614 40852 81614 40821 81615 40852 81615 40854 81615 40854 81616 40852 81616 40853 81616 40854 81617 40853 81617 40850 81617 40823 81618 40530 81618 40824 81618 40824 81619 40530 81619 40856 81619 40824 81620 40856 81620 40855 81620 40855 81621 40856 81621 40859 81621 40855 81622 40859 81622 40825 81622 40825 81623 40859 81623 38473 81623 40861 81624 40857 81624 38475 81624 40815 81625 40860 81625 40858 81625 40858 81626 40860 81626 40861 81626 40858 81627 40861 81627 40859 81627 40859 81628 40861 81628 38475 81628 40859 81629 38475 81629 38473 81629 40545 81630 40828 81630 40860 81630 40860 81631 40828 81631 40829 81631 40860 81632 40829 81632 40861 81632 40861 81633 40829 81633 38477 81633 40861 81634 38477 81634 40857 81634 38478 81635 40829 81635 38479 81635 38479 81636 40829 81636 40862 81636 38479 81637 40862 81637 40863 81637 40863 81638 40862 81638 40864 81638 40863 81639 40864 81639 38481 81639 38481 81640 40864 81640 38482 81640 38482 81641 40864 81641 40865 81641 38482 81642 40865 81642 40866 81642 40866 81643 40865 81643 40867 81643 40866 81644 40867 81644 40869 81644 40869 81645 40867 81645 40868 81645 40869 81646 40868 81646 40874 81646 40872 81647 40870 81647 40873 81647 40567 81648 40805 81648 40871 81648 40871 81649 40805 81649 40872 81649 40871 81650 40872 81650 40868 81650 40868 81651 40872 81651 40873 81651 40868 81652 40873 81652 40874 81652 40573 81653 40875 81653 40805 81653 40805 81654 40875 81654 40876 81654 40805 81655 40876 81655 40872 81655 40872 81656 40876 81656 40877 81656 40872 81657 40877 81657 40870 81657 40796 81658 40831 81658 40875 81658 40875 81659 40831 81659 40879 81659 40875 81660 40879 81660 40876 81660 40876 81661 40879 81661 40881 81661 40876 81662 40881 81662 40877 81662 38485 81663 38487 81663 40832 81663 40832 81664 38487 81664 40878 81664 40832 81665 40878 81665 40879 81665 40879 81666 40878 81666 40880 81666 40879 81667 40880 81667 40881 81667 40584 81668 40586 81668 40882 81668 40882 81669 40586 81669 40883 81669 40882 81670 40883 81670 40833 81670 40833 81671 40883 81671 40884 81671 40833 81672 40884 81672 40834 81672 40834 81673 40884 81673 40885 81673 40887 81674 40888 81674 38488 81674 40804 81675 40886 81675 40803 81675 40803 81676 40886 81676 40887 81676 40803 81677 40887 81677 40884 81677 40884 81678 40887 81678 38488 81678 40884 81679 38488 81679 40885 81679 40797 81680 40799 81680 40886 81680 40886 81681 40799 81681 40891 81681 40886 81682 40891 81682 40887 81682 40887 81683 40891 81683 40892 81683 40887 81684 40892 81684 40888 81684 38394 81685 38491 81685 40889 81685 40889 81686 38491 81686 38492 81686 40889 81687 38492 81687 40836 81687 40836 81688 38492 81688 40890 81688 40836 81689 40890 81689 40891 81689 40891 81690 40890 81690 38489 81690 40891 81691 38489 81691 40892 81691 43456 81692 40766 81692 40893 81692 43456 81693 40893 81693 43455 81693 43455 81694 40893 81694 40770 81694 43455 81695 40770 81695 40894 81695 40894 81696 40770 81696 40895 81696 40894 81697 40895 81697 40896 81697 40896 81698 40895 81698 40773 81698 40896 81699 40773 81699 40897 81699 40897 81700 40773 81700 40774 81700 40897 81701 40774 81701 43452 81701 43452 81702 40774 81702 40776 81702 43452 81703 40776 81703 40898 81703 40898 81704 40776 81704 40779 81704 40898 81705 40779 81705 40899 81705 40899 81706 40779 81706 40778 81706 40899 81707 40778 81707 40900 81707 40900 81708 40778 81708 40781 81708 40900 81709 40781 81709 40901 81709 40901 81710 40781 81710 40902 81710 40901 81711 40902 81711 43449 81711 43449 81712 40902 81712 40904 81712 43449 81713 40904 81713 40903 81713 40903 81714 40904 81714 40905 81714 40903 81715 40905 81715 40906 81715 40906 81716 40905 81716 40907 81716 40906 81717 40907 81717 43448 81717 43448 81718 40907 81718 40908 81718 43448 81719 40908 81719 40909 81719 40909 81720 40908 81720 40790 81720 40909 81721 40790 81721 40910 81721 40910 81722 40790 81722 40793 81722 40910 81723 40793 81723 43446 81723 43446 81724 40793 81724 40911 81724 43446 81725 40911 81725 43443 81725 43443 81726 40911 81726 38466 81726 43443 81727 38466 81727 40912 81727 40919 81728 39195 81728 40491 81728 40491 81729 39195 81729 39194 81729 40491 81730 39194 81730 40913 81730 40913 81731 39194 81731 39191 81731 40913 81732 39191 81732 40490 81732 40490 81733 39191 81733 40914 81733 40490 81734 40914 81734 40915 81734 40915 81735 40914 81735 40916 81735 40915 81736 40916 81736 38610 81736 38610 81737 40916 81737 38311 81737 40494 81738 40917 81738 40493 81738 40493 81739 40917 81739 40918 81739 40493 81740 40918 81740 40919 81740 40919 81741 40918 81741 40293 81741 40919 81742 40293 81742 39195 81742 40497 81743 40285 81743 40494 81743 40494 81744 40285 81744 43435 81744 40494 81745 43435 81745 40917 81745 40920 81746 40306 81746 40921 81746 40921 81747 40306 81747 43436 81747 40921 81748 43436 81748 40497 81748 40497 81749 43436 81749 40922 81749 40497 81750 40922 81750 40285 81750 38593 81751 39171 81751 40923 81751 40923 81752 39171 81752 39170 81752 40923 81753 39170 81753 40924 81753 40924 81754 39170 81754 40925 81754 40924 81755 40925 81755 40503 81755 40503 81756 40925 81756 39167 81756 40503 81757 39167 81757 40926 81757 40926 81758 39167 81758 39165 81758 40926 81759 39165 81759 40920 81759 40920 81760 39165 81760 39163 81760 40920 81761 39163 81761 40306 81761 38309 81762 38308 81762 40357 81762 38309 81763 40357 81763 40552 81763 40552 81764 40357 81764 40355 81764 40552 81765 40355 81765 40553 81765 40553 81766 40355 81766 40354 81766 40553 81767 40354 81767 40554 81767 40554 81768 40354 81768 40353 81768 40554 81769 40353 81769 40927 81769 40927 81770 40353 81770 40352 81770 40927 81771 40352 81771 40928 81771 40928 81772 40352 81772 40929 81772 40928 81773 40929 81773 40930 81773 40930 81774 40929 81774 40350 81774 40930 81775 40350 81775 40931 81775 40561 81776 38302 81776 40932 81776 40561 81777 40932 81777 40933 81777 40933 81778 40932 81778 40934 81778 40933 81779 40934 81779 40546 81779 40546 81780 40934 81780 40935 81780 40546 81781 40935 81781 40936 81781 40936 81782 40935 81782 40937 81782 40936 81783 40937 81783 40547 81783 40547 81784 40937 81784 40366 81784 40547 81785 40366 81785 40938 81785 40938 81786 40366 81786 40939 81786 40938 81787 40939 81787 40548 81787 40548 81788 40939 81788 40365 81788 40548 81789 40365 81789 40940 81789 40541 81790 40374 81790 40373 81790 40541 81791 40373 81791 40542 81791 40542 81792 40373 81792 40941 81792 40542 81793 40941 81793 40943 81793 40943 81794 40941 81794 40942 81794 40943 81795 40942 81795 40534 81795 40534 81796 40942 81796 40944 81796 40534 81797 40944 81797 40536 81797 40536 81798 40944 81798 40376 81798 40536 81799 40376 81799 40537 81799 40537 81800 40376 81800 40945 81800 40537 81801 40945 81801 40538 81801 40538 81802 40945 81802 40946 81802 40538 81803 40946 81803 40539 81803 38285 81804 38284 81804 40947 81804 40947 81805 38284 81805 40948 81805 40947 81806 40948 81806 40525 81806 40525 81807 40948 81807 40949 81807 40525 81808 40949 81808 40526 81808 40526 81809 40949 81809 40379 81809 40526 81810 40379 81810 40508 81810 40508 81811 40379 81811 40951 81811 40508 81812 40951 81812 40507 81812 40950 81813 38277 81813 38278 81813 38278 81814 40511 81814 40950 81814 40950 81815 40511 81815 40952 81815 40950 81816 40952 81816 40951 81816 40951 81817 40952 81817 40509 81817 40951 81818 40509 81818 40507 81818 40953 81819 38275 81819 40954 81819 40953 81820 40954 81820 38497 81820 38497 81821 40954 81821 40955 81821 38497 81822 40955 81822 40956 81822 40956 81823 40955 81823 40393 81823 40956 81824 40393 81824 38498 81824 38498 81825 40393 81825 40957 81825 38498 81826 40957 81826 38505 81826 38505 81827 40957 81827 40958 81827 38505 81828 40958 81828 38501 81828 38501 81829 40958 81829 40960 81829 38501 81830 40960 81830 40959 81830 40959 81831 40960 81831 40961 81831 40959 81832 40961 81832 40962 81832 38577 81833 38267 81833 40963 81833 38577 81834 40963 81834 38579 81834 38579 81835 40963 81835 40407 81835 38579 81836 40407 81836 40964 81836 40964 81837 40407 81837 40405 81837 40964 81838 40405 81838 38580 81838 38580 81839 40405 81839 40965 81839 38580 81840 40965 81840 38581 81840 38581 81841 40965 81841 40404 81841 38581 81842 40404 81842 38582 81842 38582 81843 40404 81843 40966 81843 38582 81844 40966 81844 40967 81844 40967 81845 40966 81845 40403 81845 40967 81846 40403 81846 38584 81846 40969 81847 40968 81847 40418 81847 40969 81848 40418 81848 38564 81848 38564 81849 40418 81849 40970 81849 38564 81850 40970 81850 40971 81850 40971 81851 40970 81851 40410 81851 40971 81852 40410 81852 40972 81852 40972 81853 40410 81853 40973 81853 40972 81854 40973 81854 40974 81854 40974 81855 40973 81855 40975 81855 40974 81856 40975 81856 38569 81856 38569 81857 40975 81857 40413 81857 38569 81858 40413 81858 38565 81858 38565 81859 40413 81859 40976 81859 38565 81860 40976 81860 38566 81860 38254 81861 40421 81861 40977 81861 38254 81862 40977 81862 38546 81862 38546 81863 40977 81863 40978 81863 38546 81864 40978 81864 38547 81864 38547 81865 40978 81865 38548 81865 38548 81866 40978 81866 40423 81866 38548 81867 40423 81867 38549 81867 38549 81868 40423 81868 40979 81868 40979 81869 40423 81869 40425 81869 40979 81870 40425 81870 40980 81870 40980 81871 40425 81871 40981 81871 40981 81872 40425 81872 40426 81872 40981 81873 40426 81873 40982 81873 40982 81874 40426 81874 40428 81874 40982 81875 40428 81875 38556 81875 38534 81876 40983 81876 40435 81876 38534 81877 40435 81877 40984 81877 40984 81878 40435 81878 40434 81878 40984 81879 40434 81879 38531 81879 38531 81880 40434 81880 40447 81880 38531 81881 40447 81881 38535 81881 38535 81882 40447 81882 40446 81882 38535 81883 40446 81883 40985 81883 40985 81884 40446 81884 40445 81884 40985 81885 40445 81885 40987 81885 40987 81886 40445 81886 40986 81886 40987 81887 40986 81887 40988 81887 40988 81888 40986 81888 40443 81888 40988 81889 40443 81889 40989 81889 38514 81890 40450 81890 40449 81890 38514 81891 40449 81891 38515 81891 38515 81892 40449 81892 40448 81892 38515 81893 40448 81893 38517 81893 38517 81894 40448 81894 40990 81894 38517 81895 40990 81895 38520 81895 38520 81896 40990 81896 40460 81896 38520 81897 40460 81897 38519 81897 38519 81898 40460 81898 40459 81898 38519 81899 40459 81899 38521 81899 38521 81900 40459 81900 40991 81900 38521 81901 40991 81901 40992 81901 40992 81902 40991 81902 40456 81902 40992 81903 40456 81903 40993 81903 40994 81904 40594 81904 40995 81904 40994 81905 40995 81905 40996 81905 40996 81906 40995 81906 40997 81906 40996 81907 40997 81907 40595 81907 40595 81908 40997 81908 40471 81908 40595 81909 40471 81909 40998 81909 40998 81910 40471 81910 40467 81910 40998 81911 40467 81911 40999 81911 40999 81912 40467 81912 40466 81912 40999 81913 40466 81913 41000 81913 41000 81914 40466 81914 41001 81914 41000 81915 41001 81915 40596 81915 40596 81916 41001 81916 40598 81916 40598 81917 41001 81917 41002 81917 40598 81918 41002 81918 41003 81918 40576 81919 38227 81919 40487 81919 40576 81920 40487 81920 40577 81920 40577 81921 40487 81921 40485 81921 40577 81922 40485 81922 41004 81922 41004 81923 40485 81923 40484 81923 41004 81924 40484 81924 40578 81924 40578 81925 40484 81925 40579 81925 40579 81926 40484 81926 40483 81926 40579 81927 40483 81927 40580 81927 40580 81928 40483 81928 41005 81928 40580 81929 41005 81929 40581 81929 40581 81930 41005 81930 40481 81930 40581 81931 40481 81931 40582 81931 40582 81932 40481 81932 40480 81932 40582 81933 40480 81933 41006 81933 41080 81934 38218 81934 41007 81934 41080 81935 41007 81935 41081 81935 41081 81936 41007 81936 41011 81936 41081 81937 41011 81937 41083 81937 41013 81938 41008 81938 41010 81938 41010 81939 41008 81939 41064 81939 41063 81940 41085 81940 41009 81940 41009 81941 41086 81941 41063 81941 41063 81942 41086 81942 41087 81942 41063 81943 41087 81943 41064 81943 41064 81944 41087 81944 41088 81944 41064 81945 41088 81945 41010 81945 41011 81946 38212 81946 41083 81946 41083 81947 38212 81947 41012 81947 41091 81948 41069 81948 41090 81948 41090 81949 41069 81949 41008 81949 41090 81950 41008 81950 41013 81950 41014 81951 41060 81951 41015 81951 41015 81952 41060 81952 41061 81952 41016 81953 41048 81953 41101 81953 41101 81954 41048 81954 41047 81954 41101 81955 41047 81955 41017 81955 41017 81956 41047 81956 41018 81956 41017 81957 41018 81957 41019 81957 41019 81958 41018 81958 41024 81958 41019 81959 41024 81959 41020 81959 41050 81960 41049 81960 41021 81960 41021 81961 41049 81961 41104 81961 41025 81962 41055 81962 41022 81962 41022 81963 41055 81963 41053 81963 41022 81964 41053 81964 41023 81964 41023 81965 41053 81965 41054 81965 41023 81966 41054 81966 41106 81966 41106 81967 41054 81967 41050 81967 41106 81968 41050 81968 41021 81968 41020 81969 41024 81969 41098 81969 41098 81970 41024 81970 41042 81970 41098 81971 41042 81971 41096 81971 38209 81972 41056 81972 41108 81972 41108 81973 41056 81973 41055 81973 41108 81974 41055 81974 41025 81974 40730 81975 40646 81975 40731 81975 40731 81976 40646 81976 41058 81976 40731 81977 41058 81977 41026 81977 41031 81978 41032 81978 41027 81978 41027 81979 41032 81979 41096 81979 41027 81980 41096 81980 41042 81980 41028 81981 40652 81981 41029 81981 41029 81982 40652 81982 41030 81982 41029 81983 41030 81983 41031 81983 41031 81984 41030 81984 41033 81984 41031 81985 41033 81985 41032 81985 41032 81986 41033 81986 40654 81986 41067 81987 40650 81987 41034 81987 41067 81988 41034 81988 38195 81988 38195 81989 41034 81989 41035 81989 38195 81990 41035 81990 38196 81990 40650 81991 41067 81991 41094 81991 41094 81992 41067 81992 41037 81992 41094 81993 41037 81993 41093 81993 41093 81994 41037 81994 41036 81994 41036 81995 41037 81995 41069 81995 41036 81996 41069 81996 41091 81996 38202 81997 41038 81997 41061 81997 41061 81998 41038 81998 41015 81998 40764 81999 40624 81999 41039 81999 41039 82000 40624 82000 40692 82000 41039 82001 40692 82001 38203 82001 38203 82002 40692 82002 41040 82002 38203 82003 41040 82003 38202 82003 38202 82004 41040 82004 41041 82004 38202 82005 41041 82005 41038 82005 40750 82006 38205 82006 41205 82006 41205 82007 38205 82007 41028 82007 41205 82008 41028 82008 41203 82008 41042 82009 41045 82009 41027 82009 41027 82010 41045 82010 41043 82010 41027 82011 41043 82011 41031 82011 41031 82012 41043 82012 41203 82012 41031 82013 41203 82013 41029 82013 41029 82014 41203 82014 41028 82014 41024 82015 41044 82015 41042 82015 41042 82016 41044 82016 41045 82016 41046 82017 41044 82017 41024 82017 41024 82018 41018 82018 41046 82018 41046 82019 41018 82019 41047 82019 41046 82020 41047 82020 41206 82020 41206 82021 41047 82021 41048 82021 41206 82022 41048 82022 38193 82022 38193 82023 41048 82023 41049 82023 38193 82024 41049 82024 41212 82024 41212 82025 41049 82025 41050 82025 41212 82026 41050 82026 41051 82026 38191 82027 41051 82027 41050 82027 38191 82028 41050 82028 38192 82028 41055 82029 41052 82029 41053 82029 41053 82030 41052 82030 38192 82030 41053 82031 38192 82031 41054 82031 41054 82032 38192 82032 41050 82032 41056 82033 38190 82033 41055 82033 41055 82034 38190 82034 41052 82034 41057 82035 38190 82035 41056 82035 41056 82036 38207 82036 41057 82036 41057 82037 38207 82037 38211 82037 41057 82038 38211 82038 41214 82038 41214 82039 38211 82039 41058 82039 41214 82040 41058 82040 40751 82040 40751 82041 41058 82041 40646 82041 40764 82042 41039 82042 41059 82042 41059 82043 41039 82043 41182 82043 41060 82044 38200 82044 41061 82044 41061 82045 38200 82045 41180 82045 41011 82046 41191 82046 38212 82046 38212 82047 41191 82047 41184 82047 41011 82048 41007 82048 41191 82048 41191 82049 41007 82049 38197 82049 41064 82050 41008 82050 41196 82050 41062 82051 41063 82051 41193 82051 41193 82052 41063 82052 41064 82052 41193 82053 41064 82053 41065 82053 41065 82054 41064 82054 41196 82054 41069 82055 41066 82055 41008 82055 41008 82056 41066 82056 41196 82056 38195 82057 41197 82057 41067 82057 41067 82058 41197 82058 41068 82058 41067 82059 41068 82059 41037 82059 41037 82060 41068 82060 41199 82060 41037 82061 41199 82061 41069 82061 41069 82062 41199 82062 41066 82062 41038 82063 41041 82063 40695 82063 40517 82064 41015 82064 41070 82064 41070 82065 41015 82065 41038 82065 41070 82066 41038 82066 40694 82066 40694 82067 41038 82067 40695 82067 41015 82068 40517 82068 41014 82068 41014 82069 40517 82069 41071 82069 41014 82070 41071 82070 40515 82070 41014 82071 40515 82071 38216 82071 38216 82072 40515 82072 41072 82072 38216 82073 41072 82073 41074 82073 41074 82074 41072 82074 41073 82074 41074 82075 41073 82075 41075 82075 41075 82076 41073 82076 40514 82076 41075 82077 40514 82077 38213 82077 38213 82078 40514 82078 41076 82078 40818 82079 41084 82079 41083 82079 38213 82080 41076 82080 41077 82080 41077 82081 41076 82081 40818 82081 41077 82082 40818 82082 41012 82082 41012 82083 40818 82083 41083 82083 41078 82084 41079 82084 41080 82084 41078 82085 41080 82085 41082 82085 41080 82086 41081 82086 41082 82086 41082 82087 41081 82087 41083 82087 41082 82088 41083 82088 41084 82088 38340 82089 38465 82089 41086 82089 41086 82090 41009 82090 38340 82090 38340 82091 41009 82091 41085 82091 38340 82092 41085 82092 41079 82092 41079 82093 41085 82093 38217 82093 41079 82094 38217 82094 41080 82094 41086 82095 38465 82095 41087 82095 41087 82096 38465 82096 38500 82096 41087 82097 38500 82097 41088 82097 41088 82098 38500 82098 38499 82098 41088 82099 38499 82099 41010 82099 41010 82100 38499 82100 41089 82100 41010 82101 41089 82101 41013 82101 41013 82102 41089 82102 38506 82102 41013 82103 38506 82103 41090 82103 41090 82104 38506 82104 38504 82104 41090 82105 38504 82105 41091 82105 41091 82106 38504 82106 38503 82106 41091 82107 38503 82107 41036 82107 41036 82108 38503 82108 38502 82108 38502 82109 40690 82109 41036 82109 41036 82110 40690 82110 41092 82110 41036 82111 41092 82111 41093 82111 41093 82112 41092 82112 41094 82112 41095 82113 40651 82113 41097 82113 38509 82114 41096 82114 41097 82114 41097 82115 41096 82115 41032 82115 41097 82116 41032 82116 41095 82116 41095 82117 41032 82117 40654 82117 41096 82118 38509 82118 41098 82118 41098 82119 38509 82119 38508 82119 41098 82120 38508 82120 41020 82120 41020 82121 38508 82121 38518 82121 41020 82122 38518 82122 41099 82122 41020 82123 41099 82123 41019 82123 41099 82124 41100 82124 41019 82124 41019 82125 41100 82125 41102 82125 41019 82126 41102 82126 41017 82126 41017 82127 41102 82127 41101 82127 41101 82128 41102 82128 41103 82128 41101 82129 41103 82129 41016 82129 41021 82130 41104 82130 41105 82130 41105 82131 41104 82131 38194 82131 41021 82132 41105 82132 40523 82132 41021 82133 40523 82133 41106 82133 41106 82134 40523 82134 40524 82134 41106 82135 40524 82135 41023 82135 41023 82136 40524 82136 40519 82136 41023 82137 40519 82137 41022 82137 41022 82138 40519 82138 41107 82138 41022 82139 41107 82139 41025 82139 41025 82140 41107 82140 41108 82140 41108 82141 41107 82141 40520 82141 41108 82142 40520 82142 38209 82142 38209 82143 40520 82143 40518 82143 38209 82144 40518 82144 38208 82144 38208 82145 40518 82145 41109 82145 41109 82146 41110 82146 38208 82146 38208 82147 41110 82147 41111 82147 38208 82148 41111 82148 38206 82148 37099 82149 38122 82149 41112 82149 41112 82150 38122 82150 38121 82150 41112 82151 38121 82151 37096 82151 37096 82152 38121 82152 38120 82152 37096 82153 38120 82153 41113 82153 41113 82154 38120 82154 41114 82154 41113 82155 41114 82155 41115 82155 37113 82156 38108 82156 37112 82156 37112 82157 38108 82157 41116 82157 37112 82158 41116 82158 37111 82158 37111 82159 41116 82159 41318 82159 37111 82160 41318 82160 41126 82160 37093 82161 41137 82161 41117 82161 41117 82162 41137 82162 41118 82162 41117 82163 41118 82163 37114 82163 37114 82164 41118 82164 41119 82164 37114 82165 41119 82165 41120 82165 41120 82166 41119 82166 38112 82166 41120 82167 38112 82167 37113 82167 37113 82168 38112 82168 38109 82168 37113 82169 38109 82169 38108 82169 41121 82170 41305 82170 41122 82170 41122 82171 41305 82171 41124 82171 41122 82172 41124 82172 41123 82172 41123 82173 41124 82173 41302 82173 41123 82174 41302 82174 41125 82174 41125 82175 41302 82175 41300 82175 41125 82176 41300 82176 37099 82176 37099 82177 41300 82177 41299 82177 37099 82178 41299 82178 38122 82178 41318 82179 41317 82179 41126 82179 41126 82180 41317 82180 41128 82180 41126 82181 41128 82181 41127 82181 41127 82182 41128 82182 41315 82182 41127 82183 41315 82183 37107 82183 37107 82184 41315 82184 41314 82184 37107 82185 41314 82185 41129 82185 41129 82186 41314 82186 41311 82186 41129 82187 41311 82187 37104 82187 41311 82188 41130 82188 37104 82188 37104 82189 41130 82189 41308 82189 37104 82190 41308 82190 41131 82190 41131 82191 41308 82191 41307 82191 41131 82192 41307 82192 37103 82192 37103 82193 41307 82193 41132 82193 37103 82194 41132 82194 41121 82194 41121 82195 41132 82195 41133 82195 41121 82196 41133 82196 41305 82196 41114 82197 41134 82197 41115 82197 41115 82198 41134 82198 38118 82198 41115 82199 38118 82199 37095 82199 37095 82200 38118 82200 41135 82200 37095 82201 41135 82201 37094 82201 37094 82202 41135 82202 38115 82202 37094 82203 38115 82203 37093 82203 37093 82204 38115 82204 41136 82204 37093 82205 41136 82205 41137 82205 43370 82206 43233 82206 41139 82206 41139 82207 43233 82207 41138 82207 41139 82208 41138 82208 41140 82208 41140 82209 41138 82209 37349 82209 41140 82210 37349 82210 41141 82210 41141 82211 37349 82211 41142 82211 41141 82212 41142 82212 41143 82212 41143 82213 41142 82213 41145 82213 41143 82214 41145 82214 41144 82214 41144 82215 41145 82215 41146 82215 41146 82216 41145 82216 37352 82216 41146 82217 37352 82217 41228 82217 41228 82218 37352 82218 37351 82218 41147 82219 41151 82219 41232 82219 41147 82220 41232 82220 41148 82220 41148 82221 41232 82221 41149 82221 41148 82222 41149 82222 41150 82222 41150 82223 41149 82223 41235 82223 41150 82224 41235 82224 37350 82224 37350 82225 41235 82225 41228 82225 37350 82226 41228 82226 37351 82226 43243 82227 38185 82227 38184 82227 43243 82228 38184 82228 43242 82228 43242 82229 38184 82229 41151 82229 43242 82230 41151 82230 41147 82230 41156 82231 41152 82231 41153 82231 41156 82232 41153 82232 43241 82232 43241 82233 41153 82233 41154 82233 43241 82234 41154 82234 43246 82234 41154 82235 41238 82235 43246 82235 43246 82236 41238 82236 41155 82236 43246 82237 41155 82237 43245 82237 43245 82238 41155 82238 38185 82238 43245 82239 38185 82239 43243 82239 41152 82240 41156 82240 41230 82240 41230 82241 41156 82241 41158 82241 41230 82242 41158 82242 41157 82242 41157 82243 41158 82243 43240 82243 41157 82244 43240 82244 43239 82244 41157 82245 43239 82245 41218 82245 41218 82246 43239 82246 41159 82246 41218 82247 41159 82247 41216 82247 41216 82248 41159 82248 43237 82248 41216 82249 43237 82249 41160 82249 41160 82250 43237 82250 41161 82250 41161 82251 43237 82251 43236 82251 41161 82252 43236 82252 43406 82252 41227 82253 43232 82253 41162 82253 41227 82254 41162 82254 41225 82254 41225 82255 41162 82255 43336 82255 41225 82256 43336 82256 41223 82256 41223 82257 43336 82257 43339 82257 41223 82258 43339 82258 41222 82258 41222 82259 43339 82259 43337 82259 41222 82260 43337 82260 41240 82260 41240 82261 43337 82261 41163 82261 41163 82262 43337 82262 41165 82262 41163 82263 41165 82263 41164 82263 41164 82264 41165 82264 41169 82264 43332 82265 38178 82265 41166 82265 43332 82266 41166 82266 43333 82266 43333 82267 41166 82267 41243 82267 43333 82268 41243 82268 43334 82268 43334 82269 41243 82269 41167 82269 43334 82270 41167 82270 41168 82270 41168 82271 41167 82271 41164 82271 41168 82272 41164 82272 41169 82272 41245 82273 41244 82273 41171 82273 41171 82274 41244 82274 43331 82274 41173 82275 38179 82275 41170 82275 41170 82276 38179 82276 37244 82276 41245 82277 41171 82277 41241 82277 41241 82278 41171 82278 37246 82278 41241 82279 37246 82279 38182 82279 38182 82280 37246 82280 37245 82280 38182 82281 37245 82281 41172 82281 41172 82282 37245 82282 37244 82282 41172 82283 37244 82283 38183 82283 38183 82284 37244 82284 38179 82284 41173 82285 41170 82285 41174 82285 41174 82286 41170 82286 41175 82286 41174 82287 41175 82287 41239 82287 41239 82288 41175 82288 37241 82288 41239 82289 37241 82289 41176 82289 41239 82290 41176 82290 41177 82290 41177 82291 41176 82291 37239 82291 41177 82292 37239 82292 41220 82292 41220 82293 37239 82293 37243 82293 41220 82294 37243 82294 41178 82294 41178 82295 37243 82295 41179 82295 41178 82296 41179 82296 43378 82296 41180 82297 41181 82297 41221 82297 41180 82298 41221 82298 38201 82298 38201 82299 41221 82299 41219 82299 38201 82300 41219 82300 38204 82300 38204 82301 41219 82301 41182 82301 41182 82302 41219 82302 43194 82302 41182 82303 43194 82303 41059 82303 41181 82304 41180 82304 41183 82304 41183 82305 41180 82305 38200 82305 41191 82306 41190 82306 41184 82306 41184 82307 41190 82307 41185 82307 41184 82308 41185 82308 38199 82308 38199 82309 41185 82309 38181 82309 38199 82310 38181 82310 41186 82310 41183 82311 38200 82311 38180 82311 38180 82312 38200 82312 41186 82312 38180 82313 41186 82313 41187 82313 41187 82314 41186 82314 38181 82314 38198 82315 41188 82315 41189 82315 38198 82316 41189 82316 38197 82316 38197 82317 41189 82317 41190 82317 38197 82318 41190 82318 41191 82318 41188 82319 38198 82319 41242 82319 41242 82320 38198 82320 41062 82320 41242 82321 41062 82321 41192 82321 41192 82322 41062 82322 41193 82322 41192 82323 41193 82323 41194 82323 41194 82324 41193 82324 41065 82324 41194 82325 41065 82325 41195 82325 41195 82326 41065 82326 41196 82326 41195 82327 41196 82327 41200 82327 41200 82328 41196 82328 41066 82328 41197 82329 40732 82329 41226 82329 41197 82330 41226 82330 41068 82330 41226 82331 41224 82331 41068 82331 41068 82332 41224 82332 41198 82332 41068 82333 41198 82333 41199 82333 41199 82334 41198 82334 41200 82334 41199 82335 41200 82335 41066 82335 41045 82336 41201 82336 41217 82336 41045 82337 41217 82337 41043 82337 41043 82338 41217 82338 41202 82338 41043 82339 41202 82339 41203 82339 41202 82340 41215 82340 41203 82340 41203 82341 41215 82341 41204 82341 41203 82342 41204 82342 41205 82342 41201 82343 41045 82343 41207 82343 41207 82344 41045 82344 41044 82344 41046 82345 41206 82345 41210 82345 41207 82346 41044 82346 41208 82346 41208 82347 41044 82347 41046 82347 41208 82348 41046 82348 41209 82348 41209 82349 41046 82349 41210 82349 41237 82350 41211 82350 41051 82350 41051 82351 41211 82351 41212 82351 41237 82352 41051 82352 41231 82352 41231 82353 41051 82353 38191 82353 41236 82354 41052 82354 41229 82354 41229 82355 41052 82355 38190 82355 43215 82356 41213 82356 40751 82356 40751 82357 41213 82357 41214 82357 43215 82358 43370 82358 41213 82358 41213 82359 43370 82359 41139 82359 41213 82360 41139 82360 41140 82360 41161 82361 41204 82361 41160 82361 41160 82362 41204 82362 41215 82362 41160 82363 41215 82363 41216 82363 41215 82364 41202 82364 41216 82364 41216 82365 41202 82365 41217 82365 41216 82366 41217 82366 41218 82366 41218 82367 41217 82367 41201 82367 41218 82368 41201 82368 41157 82368 43378 82369 43194 82369 41178 82369 41178 82370 43194 82370 41219 82370 41178 82371 41219 82371 41220 82371 41220 82372 41219 82372 41221 82372 41220 82373 41221 82373 41177 82373 41177 82374 41221 82374 41181 82374 41177 82375 41181 82375 41239 82375 41222 82376 41240 82376 41200 82376 41222 82377 41200 82377 41223 82377 41200 82378 41198 82378 41223 82378 41223 82379 41198 82379 41224 82379 41223 82380 41224 82380 41225 82380 41225 82381 41224 82381 41226 82381 41225 82382 41226 82382 41227 82382 41228 82383 41236 82383 41146 82383 41146 82384 41236 82384 41229 82384 41146 82385 41229 82385 41144 82385 41157 82386 41201 82386 41230 82386 41230 82387 41201 82387 41207 82387 41230 82388 41207 82388 41152 82388 41151 82389 41237 82389 41232 82389 41232 82390 41237 82390 41231 82390 41232 82391 41231 82391 41149 82391 41231 82392 41233 82392 41149 82392 41149 82393 41233 82393 41234 82393 41149 82394 41234 82394 41235 82394 41235 82395 41234 82395 41236 82395 41235 82396 41236 82396 41228 82396 41151 82397 38184 82397 41237 82397 41237 82398 38184 82398 41211 82398 41152 82399 41207 82399 41153 82399 41153 82400 41207 82400 41208 82400 38186 82401 38185 82401 41210 82401 41210 82402 38185 82402 41155 82402 41210 82403 41155 82403 41209 82403 41209 82404 41155 82404 41238 82404 41209 82405 41238 82405 41208 82405 41208 82406 41238 82406 41154 82406 41208 82407 41154 82407 41153 82407 41239 82408 41181 82408 41174 82408 41174 82409 41181 82409 41183 82409 41174 82410 41183 82410 41173 82410 41164 82411 41195 82411 41163 82411 41163 82412 41195 82412 41200 82412 41163 82413 41200 82413 41240 82413 41185 82414 41190 82414 41241 82414 41241 82415 41190 82415 41245 82415 41166 82416 41242 82416 41192 82416 41166 82417 41192 82417 41243 82417 41243 82418 41192 82418 41194 82418 41243 82419 41194 82419 41167 82419 41167 82420 41194 82420 41195 82420 41167 82421 41195 82421 41164 82421 41188 82422 38178 82422 41244 82422 41188 82423 41244 82423 41189 82423 41189 82424 41244 82424 41245 82424 41189 82425 41245 82425 41190 82425 42948 82426 42975 82426 42973 82426 42948 82427 42973 82427 42949 82427 42949 82428 42973 82428 42972 82428 42949 82429 42972 82429 41246 82429 41246 82430 42972 82430 42971 82430 41246 82431 42971 82431 41247 82431 41247 82432 42971 82432 42970 82432 41247 82433 42970 82433 41248 82433 41248 82434 42970 82434 41249 82434 41248 82435 41249 82435 41250 82435 41250 82436 41249 82436 42969 82436 41250 82437 42969 82437 42951 82437 42951 82438 42969 82438 42968 82438 42951 82439 42968 82439 41251 82439 41251 82440 42968 82440 42965 82440 41251 82441 42965 82441 42953 82441 42953 82442 42965 82442 41252 82442 42953 82443 41252 82443 41253 82443 41253 82444 41252 82444 41254 82444 41253 82445 41254 82445 41255 82445 41255 82446 41254 82446 41256 82446 41255 82447 41256 82447 42955 82447 42955 82448 41256 82448 41257 82448 42955 82449 41257 82449 41258 82449 41258 82450 41257 82450 42964 82450 41258 82451 42964 82451 42958 82451 42958 82452 42964 82452 41259 82452 42958 82453 41259 82453 41260 82453 41260 82454 41259 82454 41261 82454 41260 82455 41261 82455 41262 82455 41262 82456 41261 82456 41263 82456 41262 82457 41263 82457 41264 82457 41264 82458 41263 82458 38158 82458 41264 82459 38158 82459 41265 82459 42871 82460 38157 82460 42872 82460 42872 82461 38157 82461 42911 82461 42872 82462 42911 82462 42874 82462 42874 82463 42911 82463 42913 82463 42874 82464 42913 82464 42875 82464 42875 82465 42913 82465 41266 82465 42875 82466 41266 82466 42876 82466 42876 82467 41266 82467 42915 82467 42876 82468 42915 82468 42877 82468 42877 82469 42915 82469 41267 82469 42877 82470 41267 82470 42878 82470 42878 82471 41267 82471 42918 82471 42878 82472 42918 82472 42880 82472 42880 82473 42918 82473 41268 82473 42880 82474 41268 82474 42882 82474 42882 82475 41268 82475 42919 82475 42882 82476 42919 82476 42884 82476 42884 82477 42919 82477 42920 82477 42884 82478 42920 82478 42886 82478 42886 82479 42920 82479 42922 82479 42886 82480 42922 82480 42887 82480 42887 82481 42922 82481 41269 82481 42887 82482 41269 82482 41270 82482 41270 82483 41269 82483 41271 82483 41270 82484 41271 82484 41272 82484 41272 82485 41271 82485 42890 82485 41272 82486 42890 82486 41273 82486 41273 82487 42890 82487 42891 82487 41273 82488 42891 82488 41274 82488 41274 82489 42891 82489 41276 82489 41274 82490 41276 82490 41275 82490 41275 82491 41276 82491 42895 82491 38143 82492 41278 82492 41277 82492 41277 82493 41278 82493 41279 82493 41277 82494 41279 82494 41280 82494 41280 82495 41279 82495 41281 82495 41280 82496 41281 82496 43133 82496 43133 82497 41281 82497 41282 82497 43133 82498 41282 82498 43134 82498 43134 82499 41282 82499 41284 82499 43134 82500 41284 82500 41283 82500 41283 82501 41284 82501 41285 82501 41283 82502 41285 82502 43135 82502 43135 82503 41285 82503 41286 82503 43135 82504 41286 82504 41287 82504 41287 82505 41286 82505 41288 82505 41287 82506 41288 82506 43138 82506 43138 82507 41288 82507 41289 82507 43138 82508 41289 82508 43139 82508 43139 82509 41289 82509 42854 82509 43139 82510 42854 82510 43141 82510 43141 82511 42854 82511 41290 82511 43141 82512 41290 82512 43142 82512 43142 82513 41290 82513 42855 82513 43142 82514 42855 82514 41291 82514 41291 82515 42855 82515 41293 82515 41291 82516 41293 82516 41292 82516 41292 82517 41293 82517 41294 82517 41292 82518 41294 82518 41295 82518 41295 82519 41294 82519 41296 82519 41295 82520 41296 82520 43144 82520 43144 82521 41296 82521 42860 82521 43144 82522 42860 82522 43145 82522 43145 82523 42860 82523 41297 82523 37398 82524 38122 82524 41298 82524 41298 82525 38122 82525 41299 82525 41298 82526 41299 82526 43143 82526 43143 82527 41299 82527 41300 82527 43143 82528 41300 82528 41301 82528 41301 82529 41300 82529 41302 82529 41301 82530 41302 82530 41303 82530 41303 82531 41302 82531 41124 82531 41303 82532 41124 82532 41304 82532 41304 82533 41124 82533 41305 82533 41304 82534 41305 82534 43140 82534 43140 82535 41305 82535 41133 82535 43140 82536 41133 82536 41306 82536 41306 82537 41133 82537 41132 82537 41306 82538 41132 82538 43137 82538 43137 82539 41132 82539 41307 82539 43137 82540 41307 82540 43136 82540 43136 82541 41307 82541 41308 82541 43136 82542 41308 82542 41309 82542 41309 82543 41308 82543 41130 82543 41309 82544 41130 82544 41310 82544 41310 82545 41130 82545 41311 82545 41310 82546 41311 82546 41312 82546 41312 82547 41311 82547 41314 82547 41312 82548 41314 82548 41313 82548 41313 82549 41314 82549 41315 82549 41313 82550 41315 82550 43132 82550 43132 82551 41315 82551 41128 82551 43132 82552 41128 82552 43131 82552 43131 82553 41128 82553 41317 82553 43131 82554 41317 82554 41316 82554 41316 82555 41317 82555 41318 82555 41320 82556 37413 82556 41319 82556 41320 82557 41319 82557 43093 82557 43093 82558 41319 82558 41321 82558 43093 82559 41321 82559 41322 82559 41322 82560 41321 82560 41323 82560 41322 82561 41323 82561 41324 82561 41324 82562 41323 82562 41325 82562 41324 82563 41325 82563 41326 82563 41326 82564 41325 82564 41327 82564 41326 82565 41327 82565 43097 82565 43097 82566 41327 82566 41328 82566 43097 82567 41328 82567 43098 82567 43098 82568 41328 82568 41329 82568 43098 82569 41329 82569 41330 82569 41330 82570 41329 82570 43115 82570 41330 82571 43115 82571 43069 82571 43069 82572 43115 82572 41331 82572 43069 82573 41331 82573 41332 82573 41332 82574 41331 82574 41333 82574 41332 82575 41333 82575 41335 82575 41335 82576 41333 82576 41334 82576 41335 82577 41334 82577 43071 82577 43071 82578 41334 82578 43110 82578 43071 82579 43110 82579 41336 82579 41336 82580 43110 82580 43108 82580 41336 82581 43108 82581 43072 82581 43072 82582 43108 82582 41337 82582 43072 82583 41337 82583 43074 82583 43074 82584 41337 82584 43104 82584 43074 82585 43104 82585 41338 82585 41338 82586 43104 82586 41340 82586 41338 82587 41340 82587 41339 82587 41339 82588 41340 82588 41342 82588 41339 82589 41342 82589 41341 82589 41341 82590 41342 82590 38089 82590 41341 82591 38089 82591 43077 82591 38087 82592 41344 82592 41343 82592 41343 82593 41344 82593 43078 82593 41343 82594 43078 82594 41345 82594 41345 82595 43078 82595 43079 82595 41345 82596 43079 82596 41346 82596 41346 82597 43079 82597 41347 82597 41346 82598 41347 82598 41348 82598 41348 82599 41347 82599 43080 82599 41348 82600 43080 82600 43055 82600 43055 82601 43080 82601 41349 82601 43055 82602 41349 82602 43056 82602 43056 82603 41349 82603 43082 82603 43056 82604 43082 82604 43058 82604 43058 82605 43082 82605 41350 82605 43058 82606 41350 82606 41351 82606 41351 82607 41350 82607 41353 82607 41351 82608 41353 82608 41352 82608 41352 82609 41353 82609 41354 82609 41352 82610 41354 82610 41355 82610 41355 82611 41354 82611 43086 82611 41355 82612 43086 82612 43061 82612 43061 82613 43086 82613 43087 82613 43061 82614 43087 82614 43063 82614 43063 82615 43087 82615 41356 82615 43063 82616 41356 82616 41357 82616 41357 82617 41356 82617 43088 82617 41357 82618 43088 82618 41358 82618 41358 82619 43088 82619 41359 82619 41358 82620 41359 82620 41361 82620 41361 82621 41359 82621 41360 82621 41361 82622 41360 82622 41362 82622 41362 82623 41360 82623 41363 82623 41362 82624 41363 82624 43066 82624 43066 82625 41363 82625 41364 82625 43066 82626 41364 82626 43067 82626 43067 82627 41364 82627 43092 82627 38070 82628 43045 82628 43147 82628 43147 82629 43045 82629 41365 82629 43147 82630 41365 82630 43148 82630 43148 82631 41365 82631 43047 82631 43148 82632 43047 82632 41366 82632 41366 82633 43047 82633 41368 82633 41366 82634 41368 82634 41367 82634 41367 82635 41368 82635 43048 82635 41367 82636 43048 82636 43152 82636 43152 82637 43048 82637 41369 82637 43152 82638 41369 82638 41370 82638 41370 82639 41369 82639 43015 82639 41370 82640 43015 82640 41371 82640 41371 82641 43015 82641 41372 82641 41371 82642 41372 82642 43156 82642 43156 82643 41372 82643 41373 82643 43156 82644 41373 82644 41374 82644 41374 82645 41373 82645 41375 82645 41374 82646 41375 82646 43159 82646 43159 82647 41375 82647 41376 82647 43159 82648 41376 82648 41378 82648 41378 82649 41376 82649 41377 82649 41378 82650 41377 82650 41379 82650 41379 82651 41377 82651 41380 82651 41379 82652 41380 82652 43160 82652 43160 82653 41380 82653 41381 82653 43160 82654 41381 82654 43163 82654 43163 82655 41381 82655 43020 82655 43163 82656 43020 82656 43165 82656 43165 82657 43020 82657 43021 82657 43165 82658 43021 82658 43167 82658 43167 82659 43021 82659 41382 82659 43167 82660 41382 82660 41383 82660 41383 82661 41382 82661 41384 82661 38054 82662 37483 82662 41385 82662 38054 82663 41385 82663 42897 82663 42897 82664 41385 82664 42933 82664 42897 82665 42933 82665 41386 82665 41386 82666 42933 82666 41387 82666 41386 82667 41387 82667 42899 82667 42899 82668 41387 82668 42931 82668 42899 82669 42931 82669 41388 82669 41388 82670 42931 82670 42930 82670 41388 82671 42930 82671 42901 82671 42901 82672 42930 82672 41389 82672 42901 82673 41389 82673 42902 82673 42902 82674 41389 82674 41390 82674 42902 82675 41390 82675 42903 82675 42903 82676 41390 82676 41391 82676 42903 82677 41391 82677 41392 82677 41392 82678 41391 82678 42926 82678 41392 82679 42926 82679 42905 82679 42905 82680 42926 82680 42925 82680 42905 82681 42925 82681 41393 82681 41393 82682 42925 82682 41394 82682 41393 82683 41394 82683 41395 82683 41395 82684 41394 82684 42923 82684 41395 82685 42923 82685 41397 82685 41397 82686 42923 82686 41396 82686 41397 82687 41396 82687 42909 82687 42909 82688 41396 82688 41398 82688 42909 82689 41398 82689 42910 82689 42910 82690 41398 82690 41399 82690 42910 82691 41399 82691 41400 82691 41400 82692 41399 82692 37501 82692 41400 82693 37501 82693 41401 82693 41402 82694 41414 82694 41406 82694 41413 82695 41412 82695 43418 82695 43418 82696 41412 82696 41404 82696 43418 82697 41404 82697 41403 82697 41403 82698 41404 82698 43349 82698 41403 82699 43349 82699 41405 82699 41405 82700 43349 82700 43346 82700 41405 82701 43346 82701 41406 82701 41406 82702 43346 82702 41407 82702 41406 82703 41407 82703 41402 82703 41408 82704 41886 82704 43295 82704 43295 82705 41886 82705 41885 82705 43295 82706 41885 82706 43296 82706 43296 82707 41885 82707 41410 82707 43296 82708 41410 82708 41409 82708 41409 82709 41410 82709 41884 82709 41409 82710 41884 82710 43293 82710 41408 82711 43295 82711 41411 82711 41411 82712 43295 82712 41412 82712 41411 82713 41412 82713 41413 82713 41402 82714 43308 82714 41414 82714 41414 82715 43308 82715 41891 82715 41891 82716 43308 82716 41890 82716 41890 82717 43308 82717 43307 82717 41890 82718 43307 82718 41889 82718 41889 82719 43307 82719 41415 82719 41415 82720 43307 82720 41416 82720 41415 82721 41416 82721 41417 82721 41417 82722 41416 82722 41421 82722 41417 82723 41421 82723 42175 82723 41418 82724 43293 82724 41419 82724 41419 82725 43293 82725 41884 82725 41420 82726 41422 82726 41421 82726 41421 82727 41422 82727 42175 82727 42158 82728 41423 82728 41425 82728 41425 82729 41423 82729 41424 82729 41424 82730 41423 82730 42147 82730 41424 82731 42147 82731 43289 82731 42158 82732 41425 82732 42157 82732 42157 82733 41425 82733 41426 82733 42157 82734 41426 82734 42156 82734 42156 82735 41426 82735 43305 82735 42156 82736 43305 82736 41427 82736 41434 82737 42153 82737 41428 82737 43305 82738 41429 82738 41427 82738 41427 82739 41429 82739 43303 82739 41427 82740 43303 82740 41430 82740 41430 82741 43303 82741 43302 82741 41430 82742 43302 82742 41431 82742 41431 82743 43302 82743 43301 82743 41431 82744 43301 82744 42154 82744 42154 82745 43301 82745 43300 82745 42154 82746 43300 82746 41432 82746 41432 82747 43300 82747 43299 82747 41432 82748 43299 82748 42153 82748 42153 82749 43299 82749 41433 82749 42153 82750 41433 82750 41428 82750 41428 82751 43298 82751 41434 82751 41434 82752 43298 82752 41435 82752 41434 82753 41435 82753 42152 82753 42152 82754 41435 82754 43297 82754 42152 82755 43297 82755 42150 82755 42150 82756 43297 82756 41436 82756 42150 82757 41436 82757 42149 82757 42149 82758 41436 82758 41418 82758 42149 82759 41418 82759 41419 82759 41451 82760 42178 82760 42180 82760 41451 82761 42180 82761 43314 82761 43314 82762 42180 82762 41437 82762 43314 82763 41437 82763 41438 82763 41438 82764 41437 82764 41439 82764 41438 82765 41439 82765 41440 82765 41440 82766 41439 82766 42182 82766 41440 82767 42182 82767 43316 82767 43316 82768 42182 82768 42184 82768 43316 82769 42184 82769 41441 82769 41441 82770 42184 82770 43318 82770 43318 82771 42184 82771 41442 82771 43318 82772 41442 82772 43319 82772 43319 82773 41442 82773 42185 82773 43319 82774 42185 82774 41443 82774 41443 82775 42185 82775 42187 82775 41443 82776 42187 82776 41444 82776 41444 82777 42187 82777 41445 82777 41444 82778 41445 82778 43344 82778 41445 82779 41446 82779 43344 82779 43344 82780 41446 82780 41447 82780 43344 82781 41447 82781 43345 82781 43345 82782 41447 82782 41448 82782 43345 82783 41448 82783 41449 82783 41448 82784 42188 82784 41449 82784 41449 82785 42188 82785 42189 82785 41449 82786 42189 82786 43309 82786 43309 82787 42189 82787 41422 82787 43309 82788 41422 82788 41420 82788 43289 82789 42147 82789 43290 82789 43290 82790 42147 82790 41450 82790 41451 82791 41452 82791 42178 82791 42178 82792 41452 82792 42177 82792 43292 82793 41454 82793 41878 82793 41878 82794 41454 82794 41453 82794 41453 82795 41454 82795 41880 82795 41880 82796 41454 82796 41455 82796 41880 82797 41455 82797 41456 82797 41456 82798 41455 82798 41457 82798 41457 82799 41455 82799 41458 82799 41457 82800 41458 82800 41459 82800 41459 82801 41458 82801 43290 82801 41459 82802 43290 82802 41450 82802 41460 82803 41894 82803 41461 82803 41461 82804 41894 82804 41892 82804 41461 82805 41892 82805 43312 82805 43312 82806 41892 82806 41462 82806 43312 82807 41462 82807 43313 82807 43313 82808 41462 82808 42177 82808 43313 82809 42177 82809 41452 82809 41460 82810 41461 82810 41895 82810 41895 82811 41461 82811 43311 82811 41895 82812 43311 82812 41897 82812 43292 82813 41878 82813 41463 82813 41463 82814 41878 82814 41464 82814 41463 82815 41464 82815 41469 82815 41469 82816 41464 82816 43417 82816 41469 82817 43417 82817 43416 82817 41465 82818 43283 82818 41466 82818 41466 82819 43283 82819 41467 82819 41466 82820 41467 82820 43416 82820 43416 82821 41467 82821 41468 82821 43416 82822 41468 82822 41469 82822 41479 82823 43419 82823 43340 82823 43340 82824 43419 82824 43421 82824 43340 82825 43421 82825 43341 82825 43341 82826 43421 82826 43423 82826 43341 82827 43423 82827 41470 82827 41470 82828 43423 82828 41471 82828 41470 82829 41471 82829 43342 82829 43342 82830 41471 82830 43424 82830 43342 82831 43424 82831 43343 82831 43343 82832 43424 82832 41472 82832 43343 82833 41472 82833 43311 82833 43311 82834 41472 82834 41897 82834 41877 82835 43284 82835 38025 82835 38025 82836 43284 82836 41474 82836 38025 82837 41474 82837 41473 82837 41473 82838 41474 82838 41475 82838 41475 82839 41474 82839 38026 82839 38026 82840 41474 82840 41476 82840 38026 82841 41476 82841 38028 82841 38028 82842 41476 82842 38029 82842 38029 82843 41476 82843 41477 82843 38029 82844 41477 82844 41478 82844 41478 82845 41477 82845 43283 82845 41478 82846 43283 82846 41465 82846 41479 82847 41480 82847 43419 82847 43419 82848 41480 82848 41481 82848 41481 82849 41480 82849 41482 82849 41482 82850 41480 82850 43330 82850 41482 82851 43330 82851 41483 82851 41483 82852 43330 82852 41901 82852 41901 82853 43330 82853 43328 82853 41901 82854 43328 82854 41484 82854 41484 82855 43328 82855 41487 82855 41484 82856 41487 82856 41485 82856 43285 82857 43284 82857 42130 82857 42130 82858 43284 82858 41877 82858 41486 82859 41525 82859 41487 82859 41487 82860 41525 82860 41485 82860 37935 82861 37936 82861 41490 82861 41490 82862 37936 82862 41488 82862 41488 82863 37936 82863 37939 82863 41488 82864 37939 82864 43279 82864 43288 82865 41502 82865 41489 82865 41489 82866 41502 82866 41499 82866 37935 82867 41490 82867 37934 82867 37934 82868 41490 82868 41491 82868 37934 82869 41491 82869 37933 82869 37933 82870 41491 82870 43277 82870 37933 82871 43277 82871 41492 82871 41492 82872 43277 82872 43278 82872 41492 82873 43278 82873 41493 82873 41493 82874 43278 82874 41494 82874 41493 82875 41494 82875 37931 82875 37931 82876 41494 82876 41495 82876 37931 82877 41495 82877 37932 82877 37932 82878 41495 82878 41497 82878 37932 82879 41497 82879 41496 82879 41496 82880 41497 82880 41498 82880 41496 82881 41498 82881 41499 82881 41499 82882 41498 82882 41500 82882 41499 82883 41500 82883 41489 82883 41501 82884 43285 82884 42130 82884 43288 82885 43287 82885 41502 82885 41502 82886 43287 82886 41503 82886 41502 82887 41503 82887 41504 82887 41504 82888 41503 82888 41501 82888 41504 82889 41501 82889 41505 82889 41505 82890 41501 82890 42130 82890 43324 82891 42204 82891 41506 82891 43324 82892 41506 82892 41507 82892 41507 82893 41506 82893 41509 82893 41507 82894 41509 82894 41508 82894 41508 82895 41509 82895 42207 82895 41508 82896 42207 82896 43321 82896 43321 82897 42207 82897 41510 82897 41510 82898 42207 82898 41511 82898 41510 82899 41511 82899 43325 82899 43325 82900 41511 82900 42209 82900 43325 82901 42209 82901 41512 82901 41512 82902 42209 82902 41513 82902 41512 82903 41513 82903 41515 82903 41515 82904 41513 82904 41514 82904 41515 82905 41514 82905 41516 82905 41516 82906 41514 82906 41517 82906 41516 82907 41517 82907 41518 82907 41517 82908 41519 82908 41518 82908 41518 82909 41519 82909 42210 82909 41518 82910 42210 82910 41520 82910 41520 82911 42210 82911 42212 82911 41520 82912 42212 82912 41521 82912 41521 82913 42212 82913 42214 82913 42214 82914 41522 82914 41521 82914 41521 82915 41522 82915 41523 82915 41521 82916 41523 82916 41524 82916 41524 82917 41523 82917 43327 82917 43327 82918 41523 82918 41525 82918 43327 82919 41525 82919 41486 82919 43279 82920 37939 82920 43280 82920 43280 82921 37939 82921 41530 82921 43324 82922 41534 82922 42204 82922 42204 82923 41534 82923 42203 82923 41526 82924 41527 82924 41538 82924 41538 82925 41527 82925 41872 82925 41872 82926 41527 82926 41871 82926 41871 82927 41527 82927 43282 82927 41871 82928 43282 82928 41528 82928 41528 82929 43282 82929 41873 82929 41873 82930 43282 82930 41529 82930 41873 82931 41529 82931 41874 82931 41874 82932 41529 82932 43280 82932 41874 82933 43280 82933 41530 82933 41907 82934 41531 82934 43320 82934 43320 82935 41531 82935 41532 82935 43320 82936 41532 82936 43323 82936 43323 82937 41532 82937 41905 82937 43323 82938 41905 82938 41533 82938 41533 82939 41905 82939 42203 82939 41533 82940 42203 82940 41534 82940 41907 82941 43320 82941 41535 82941 41535 82942 43320 82942 41536 82942 41535 82943 41536 82943 43231 82943 41526 82944 41538 82944 41537 82944 41537 82945 41538 82945 41539 82945 41537 82946 41539 82946 43354 82946 43354 82947 41539 82947 43415 82947 43354 82948 43415 82948 41540 82948 41540 82949 43415 82949 41541 82949 41540 82950 41541 82950 41542 82950 41541 82951 41543 82951 41542 82951 41542 82952 41543 82952 41544 82952 41542 82953 41544 82953 43271 82953 43272 82954 41545 82954 42117 82954 42117 82955 41545 82955 41867 82955 41867 82956 41545 82956 41864 82956 41864 82957 41545 82957 41547 82957 41864 82958 41547 82958 41546 82958 41546 82959 41547 82959 41548 82959 41546 82960 41548 82960 38031 82960 38031 82961 41548 82961 43271 82961 38031 82962 43271 82962 41544 82962 43230 82963 41549 82963 43379 82963 43379 82964 41549 82964 41910 82964 41910 82965 41549 82965 41550 82965 41550 82966 41549 82966 37259 82966 41550 82967 37259 82967 41551 82967 41551 82968 37259 82968 41552 82968 41552 82969 37259 82969 37258 82969 41552 82970 37258 82970 41553 82970 41553 82971 37258 82971 37256 82971 41553 82972 37256 82972 41554 82972 43356 82973 43272 82973 42118 82973 42118 82974 43272 82974 42117 82974 37260 82975 42228 82975 37256 82975 37256 82976 42228 82976 41554 82976 41555 82977 37949 82977 41556 82977 41556 82978 37949 82978 41557 82978 41557 82979 37949 82979 41558 82979 41557 82980 41558 82980 43267 82980 41555 82981 41556 82981 37947 82981 37947 82982 41556 82982 43357 82982 37947 82983 43357 82983 37946 82983 37946 82984 43357 82984 41559 82984 37946 82985 41559 82985 37945 82985 37945 82986 41559 82986 41561 82986 37945 82987 41561 82987 41560 82987 41560 82988 41561 82988 41562 82988 41560 82989 41562 82989 37943 82989 37943 82990 41562 82990 41563 82990 37943 82991 41563 82991 41564 82991 41564 82992 41563 82992 43265 82992 41564 82993 43265 82993 41565 82993 41565 82994 43265 82994 41566 82994 41565 82995 41566 82995 37941 82995 41567 82996 37940 82996 43275 82996 37941 82997 41566 82997 37940 82997 37940 82998 41566 82998 43263 82998 37940 82999 43263 82999 43275 82999 41571 83000 43356 83000 42118 83000 43275 83001 41568 83001 41567 83001 41567 83002 41568 83002 43274 83002 41567 83003 43274 83003 42120 83003 42120 83004 43274 83004 41570 83004 42120 83005 41570 83005 41569 83005 41569 83006 41570 83006 41571 83006 41569 83007 41571 83007 41572 83007 41572 83008 41571 83008 42118 83008 37371 83009 42231 83009 42233 83009 37371 83010 42233 83010 37250 83010 37250 83011 42233 83011 41573 83011 37250 83012 41573 83012 41574 83012 41574 83013 41573 83013 41575 83013 41574 83014 41575 83014 37251 83014 37251 83015 41575 83015 37252 83015 37252 83016 41575 83016 41576 83016 37252 83017 41576 83017 41577 83017 41577 83018 41576 83018 42235 83018 41577 83019 42235 83019 37253 83019 37253 83020 42235 83020 41578 83020 37253 83021 41578 83021 41579 83021 41579 83022 41578 83022 42239 83022 41579 83023 42239 83023 41580 83023 41580 83024 42239 83024 41581 83024 41580 83025 41581 83025 41582 83025 41581 83026 42238 83026 41582 83026 41582 83027 42238 83027 42237 83027 41582 83028 42237 83028 41583 83028 41583 83029 42237 83029 42240 83029 41583 83030 42240 83030 41584 83030 41584 83031 42240 83031 42241 83031 42241 83032 41585 83032 41584 83032 41584 83033 41585 83033 42243 83033 41584 83034 42243 83034 37254 83034 37254 83035 42243 83035 41586 83035 41586 83036 42243 83036 42228 83036 41586 83037 42228 83037 37260 83037 43267 83038 41558 83038 41596 83038 41596 83039 41558 83039 41862 83039 37371 83040 41587 83040 42231 83040 42231 83041 41587 83041 41588 83041 41589 83042 41591 83042 43403 83042 43403 83043 41591 83043 41860 83043 41860 83044 41591 83044 41590 83044 41590 83045 41591 83045 43268 83045 41590 83046 43268 83046 41592 83046 41592 83047 43268 83047 41593 83047 41593 83048 43268 83048 41594 83048 41593 83049 41594 83049 41595 83049 41595 83050 41594 83050 41596 83050 41595 83051 41596 83051 41862 83051 41917 83052 41597 83052 41600 83052 41600 83053 41597 83053 41915 83053 41600 83054 41915 83054 37249 83054 37249 83055 41915 83055 41598 83055 37249 83056 41598 83056 41599 83056 41599 83057 41598 83057 41588 83057 41599 83058 41588 83058 41587 83058 41917 83059 41600 83059 41919 83059 41919 83060 41600 83060 41601 83060 41919 83061 41601 83061 41921 83061 41589 83062 43403 83062 41603 83062 41603 83063 43403 83063 41602 83063 41603 83064 41602 83064 43359 83064 43359 83065 41602 83065 41604 83065 43359 83066 41604 83066 43360 83066 43360 83067 41604 83067 43413 83067 43360 83068 43413 83068 43362 83068 43362 83069 43413 83069 43411 83069 43362 83070 43411 83070 43247 83070 43247 83071 43411 83071 43410 83071 43247 83072 43410 83072 41614 83072 41614 83073 43410 83073 41615 83073 41605 83074 41616 83074 37267 83074 37267 83075 41616 83075 41606 83075 37267 83076 41606 83076 41607 83076 41607 83077 41606 83077 41608 83077 41607 83078 41608 83078 41609 83078 41609 83079 41608 83079 43382 83079 41609 83080 43382 83080 37370 83080 37370 83081 43382 83081 43381 83081 37370 83082 43381 83082 37247 83082 37247 83083 43381 83083 43366 83083 37247 83084 43366 83084 41601 83084 41601 83085 43366 83085 41921 83085 41611 83086 43251 83086 41610 83086 41611 83087 41610 83087 41857 83087 41857 83088 41610 83088 43249 83088 41857 83089 43249 83089 41612 83089 41612 83090 43249 83090 41613 83090 41613 83091 43249 83091 43248 83091 41613 83092 43248 83092 41856 83092 41856 83093 43248 83093 38032 83093 38032 83094 43248 83094 41614 83094 38032 83095 41614 83095 41615 83095 41605 83096 37272 83096 41616 83096 41616 83097 37272 83097 41928 83097 41928 83098 37272 83098 41617 83098 41617 83099 37272 83099 37271 83099 41617 83100 37271 83100 41924 83100 41924 83101 37271 83101 41618 83101 41618 83102 37271 83102 37268 83102 41618 83103 37268 83103 41619 83103 41619 83104 37268 83104 41620 83104 41619 83105 41620 83105 41621 83105 43363 83106 43251 83106 42094 83106 42094 83107 43251 83107 41611 83107 37270 83108 42259 83108 41620 83108 41620 83109 42259 83109 41621 83109 41633 83110 41622 83110 41631 83110 41622 83111 41633 83111 41623 83111 41623 83112 41633 83112 42092 83112 41623 83113 42092 83113 41624 83113 43254 83114 41625 83114 41626 83114 41626 83115 37950 83115 43254 83115 43254 83116 37950 83116 37951 83116 43254 83117 37951 83117 41627 83117 41627 83118 37951 83118 37952 83118 41627 83119 37952 83119 43255 83119 43255 83120 37952 83120 41628 83120 43255 83121 41628 83121 43258 83121 43258 83122 41628 83122 41629 83122 43258 83123 41629 83123 41630 83123 41630 83124 41629 83124 37954 83124 41630 83125 37954 83125 41631 83125 41631 83126 37954 83126 41632 83126 41631 83127 41632 83127 41633 83127 41625 83128 43253 83128 41626 83128 41626 83129 43253 83129 43252 83129 41626 83130 43252 83130 41634 83130 41634 83131 43252 83131 41635 83131 41634 83132 41635 83132 42097 83132 42097 83133 41635 83133 41636 83133 42097 83134 41636 83134 42095 83134 42095 83135 41636 83135 41637 83135 42095 83136 41637 83136 41638 83136 41638 83137 41637 83137 43363 83137 41638 83138 43363 83138 42094 83138 37276 83139 41639 83139 41640 83139 37276 83140 41640 83140 37277 83140 37277 83141 41640 83141 41641 83141 37277 83142 41641 83142 37278 83142 37278 83143 41641 83143 42263 83143 37278 83144 42263 83144 37279 83144 37279 83145 42263 83145 37280 83145 37280 83146 42263 83146 41642 83146 37280 83147 41642 83147 37281 83147 37281 83148 41642 83148 42264 83148 37281 83149 42264 83149 37262 83149 37262 83150 42264 83150 41643 83150 41643 83151 42264 83151 42268 83151 41643 83152 42268 83152 41644 83152 41644 83153 42268 83153 41645 83153 41644 83154 41645 83154 37263 83154 37263 83155 41645 83155 42267 83155 37263 83156 42267 83156 41646 83156 42267 83157 42265 83157 41646 83157 41646 83158 42265 83158 42269 83158 41646 83159 42269 83159 37265 83159 37265 83160 42269 83160 41647 83160 37265 83161 41647 83161 41648 83161 41648 83162 41647 83162 42270 83162 42270 83163 42271 83163 41648 83163 41648 83164 42271 83164 41649 83164 41648 83165 41649 83165 37369 83165 37369 83166 41649 83166 41650 83166 41650 83167 41649 83167 42259 83167 41650 83168 42259 83168 37270 83168 41624 83169 42092 83169 43259 83169 43259 83170 42092 83170 41855 83170 37276 83171 37275 83171 41639 83171 41639 83172 37275 83172 41659 83172 43234 83173 43262 83173 43407 83173 43407 83174 43262 83174 41854 83174 41854 83175 43262 83175 41651 83175 41651 83176 43262 83176 43261 83176 41651 83177 43261 83177 41852 83177 41852 83178 43261 83178 41653 83178 41653 83179 43261 83179 41652 83179 41653 83180 41652 83180 41654 83180 41654 83181 41652 83181 43259 83181 41654 83182 43259 83182 41855 83182 41933 83183 41932 83183 41655 83183 41655 83184 41932 83184 41656 83184 41655 83185 41656 83185 37274 83185 37274 83186 41656 83186 41657 83186 37274 83187 41657 83187 41658 83187 41658 83188 41657 83188 41659 83188 41658 83189 41659 83189 37275 83189 41933 83190 41655 83190 41660 83190 41660 83191 41655 83191 41661 83191 41660 83192 41661 83192 41666 83192 37289 83193 41935 83193 37365 83193 37365 83194 41935 83194 43374 83194 37365 83195 43374 83195 41662 83195 41662 83196 43374 83196 41663 83196 41662 83197 41663 83197 37367 83197 37367 83198 41663 83198 43385 83198 37367 83199 43385 83199 41665 83199 43385 83200 41664 83200 41665 83200 41665 83201 41664 83201 41666 83201 41665 83202 41666 83202 41661 83202 41848 83203 41847 83203 41667 83203 41667 83204 41847 83204 41845 83204 41667 83205 41845 83205 37329 83205 37329 83206 41845 83206 41668 83206 37329 83207 41668 83207 41669 83207 41669 83208 41668 83208 41846 83208 41669 83209 41846 83209 37328 83209 41848 83210 41667 83210 41849 83210 41849 83211 41667 83211 41670 83211 41849 83212 41670 83212 41851 83212 37289 83213 41671 83213 41935 83213 41935 83214 41671 83214 41939 83214 41939 83215 41671 83215 41937 83215 41937 83216 41671 83216 41673 83216 41937 83217 41673 83217 41672 83217 41672 83218 41673 83218 41940 83218 41940 83219 41673 83219 41675 83219 41940 83220 41675 83220 41674 83220 41674 83221 41675 83221 37288 83221 41674 83222 37288 83222 41676 83222 37332 83223 37328 83223 42074 83223 42074 83224 37328 83224 41846 83224 37287 83225 42037 83225 37288 83225 37288 83226 42037 83226 41676 83226 37959 83227 37327 83227 41687 83227 37327 83228 37959 83228 41677 83228 41677 83229 37959 83229 41678 83229 41677 83230 41678 83230 37341 83230 41679 83231 41680 83231 37336 83231 37336 83232 41680 83232 41681 83232 41680 83233 41682 83233 41681 83233 41681 83234 41682 83234 41683 83234 41681 83235 41683 83235 41684 83235 41684 83236 41683 83236 42078 83236 41684 83237 42078 83237 41685 83237 41685 83238 42078 83238 37955 83238 41685 83239 37955 83239 37340 83239 37340 83240 37955 83240 37957 83240 37340 83241 37957 83241 41687 83241 41687 83242 37957 83242 41686 83242 41687 83243 41686 83243 37959 83243 37336 83244 37337 83244 41679 83244 41679 83245 37337 83245 37338 83245 41679 83246 37338 83246 41688 83246 41688 83247 37338 83247 37335 83247 41688 83248 37335 83248 41690 83248 37335 83249 41689 83249 41690 83249 41690 83250 41689 83250 41691 83250 41690 83251 41691 83251 41692 83251 41692 83252 41691 83252 37334 83252 41692 83253 37334 83253 41693 83253 41693 83254 37334 83254 37333 83254 41693 83255 37333 83255 41694 83255 41694 83256 37333 83256 37332 83256 41694 83257 37332 83257 42074 83257 37294 83258 41709 83258 41696 83258 37294 83259 41696 83259 41695 83259 41695 83260 41696 83260 41697 83260 41695 83261 41697 83261 37298 83261 37298 83262 41697 83262 42026 83262 37298 83263 42026 83263 37296 83263 37296 83264 42026 83264 37299 83264 37299 83265 42026 83265 41698 83265 37299 83266 41698 83266 41699 83266 41699 83267 41698 83267 41700 83267 41699 83268 41700 83268 37300 83268 37300 83269 41700 83269 41701 83269 37300 83270 41701 83270 41702 83270 41702 83271 41701 83271 42032 83271 41702 83272 42032 83272 41703 83272 41703 83273 42032 83273 42030 83273 41703 83274 42030 83274 37284 83274 42030 83275 42028 83275 37284 83275 37284 83276 42028 83276 41705 83276 37284 83277 41705 83277 41704 83277 41704 83278 41705 83278 41706 83278 41704 83279 41706 83279 37282 83279 37282 83280 41706 83280 42034 83280 42034 83281 42035 83281 37282 83281 37282 83282 42035 83282 42036 83282 37282 83283 42036 83283 41707 83283 41707 83284 42036 83284 41708 83284 41708 83285 42036 83285 42037 83285 41708 83286 42037 83286 37287 83286 37341 83287 41678 83287 37343 83287 37343 83288 41678 83288 38036 83288 37294 83289 37293 83289 41709 83289 41709 83290 37293 83290 41718 83290 37346 83291 37347 83291 43392 83291 43392 83292 37347 83292 41710 83292 41710 83293 37347 83293 41711 83293 41711 83294 37347 83294 37345 83294 41711 83295 37345 83295 41712 83295 41712 83296 37345 83296 41713 83296 41712 83297 41713 83297 41714 83297 41714 83298 41713 83298 38035 83298 38035 83299 41713 83299 37343 83299 38035 83300 37343 83300 38036 83300 41945 83301 41715 83301 41719 83301 41719 83302 41715 83302 41942 83302 41719 83303 41942 83303 37295 83303 37295 83304 41942 83304 41716 83304 37295 83305 41716 83305 41717 83305 41717 83306 41716 83306 41718 83306 41717 83307 41718 83307 37293 83307 41945 83308 41719 83308 41720 83308 41720 83309 41719 83309 37291 83309 41720 83310 37291 83310 41727 83310 37346 83311 43392 83311 37342 83311 37342 83312 43392 83312 43393 83312 37342 83313 43393 83313 41721 83313 41721 83314 43393 83314 41722 83314 41721 83315 41722 83315 41723 83315 41723 83316 41722 83316 43395 83316 41723 83317 43395 83317 41724 83317 41724 83318 43395 83318 43391 83318 41724 83319 43391 83319 37357 83319 37357 83320 43391 83320 41725 83320 37357 83321 41725 83321 37317 83321 37317 83322 41725 83322 43368 83322 41726 83323 42276 83323 37363 83323 37363 83324 42276 83324 43365 83324 37363 83325 43365 83325 41729 83325 41729 83326 43365 83326 43364 83326 41729 83327 43364 83327 43386 83327 41727 83328 37291 83328 43387 83328 43387 83329 37291 83329 37292 83329 43387 83330 37292 83330 43386 83330 43386 83331 37292 83331 41728 83331 43386 83332 41728 83332 41729 83332 41842 83333 41839 83333 37318 83333 37318 83334 41839 83334 41730 83334 37318 83335 41730 83335 37320 83335 37320 83336 41730 83336 41731 83336 37320 83337 41731 83337 37322 83337 37322 83338 41731 83338 41738 83338 37322 83339 41738 83339 37321 83339 41842 83340 37318 83340 41732 83340 41732 83341 37318 83341 37317 83341 41732 83342 37317 83342 43368 83342 41726 83343 37304 83343 42276 83343 42276 83344 37304 83344 41733 83344 41733 83345 37304 83345 41734 83345 41734 83346 37304 83346 41735 83346 41734 83347 41735 83347 42281 83347 42281 83348 41735 83348 42283 83348 42283 83349 41735 83349 37302 83349 42283 83350 37302 83350 41736 83350 41736 83351 37302 83351 41737 83351 41737 83352 37302 83352 41739 83352 41737 83353 41739 83353 41740 83353 37356 83354 37321 83354 42048 83354 42048 83355 37321 83355 41738 83355 41772 83356 42301 83356 41739 83356 41739 83357 42301 83357 41740 83357 41741 83358 41776 83358 41742 83358 41741 83359 41742 83359 37960 83359 37960 83360 41742 83360 37359 83360 37960 83361 37359 83361 41743 83361 41743 83362 37359 83362 37358 83362 41743 83363 37358 83363 41745 83363 37358 83364 41744 83364 41745 83364 41745 83365 41744 83365 41746 83365 41745 83366 41746 83366 42058 83366 42058 83367 41746 83367 41747 83367 42058 83368 41747 83368 41748 83368 41748 83369 41747 83369 41749 83369 41748 83370 41749 83370 42057 83370 42057 83371 41749 83371 41750 83371 42057 83372 41750 83372 42056 83372 42056 83373 41750 83373 37325 83373 42056 83374 37325 83374 41751 83374 41751 83375 37325 83375 41752 83375 41751 83376 41752 83376 42054 83376 42054 83377 41752 83377 41753 83377 42054 83378 41753 83378 41754 83378 41754 83379 41753 83379 41755 83379 41754 83380 41755 83380 42055 83380 42055 83381 41755 83381 37323 83381 42055 83382 37323 83382 41756 83382 41756 83383 37323 83383 41758 83383 41756 83384 41758 83384 41757 83384 41757 83385 41758 83385 41759 83385 41757 83386 41759 83386 42050 83386 42050 83387 41759 83387 37356 83387 42050 83388 37356 83388 42048 83388 41760 83389 37308 83389 42306 83389 42306 83390 37308 83390 37307 83390 42306 83391 37307 83391 41779 83391 41760 83392 42305 83392 37308 83392 37308 83393 42305 83393 41761 83393 37308 83394 41761 83394 37309 83394 37309 83395 41761 83395 42308 83395 37309 83396 42308 83396 41768 83396 41768 83397 42308 83397 42309 83397 41769 83398 37314 83398 42316 83398 42316 83399 37314 83399 41762 83399 42316 83400 41762 83400 42318 83400 42318 83401 41762 83401 37313 83401 42318 83402 37313 83402 42310 83402 42310 83403 37313 83403 41763 83403 42310 83404 41763 83404 42311 83404 42311 83405 41763 83405 41764 83405 42311 83406 41764 83406 41765 83406 41765 83407 41764 83407 37310 83407 41765 83408 37310 83408 42313 83408 42313 83409 37310 83409 41766 83409 42313 83410 41766 83410 42309 83410 42309 83411 41766 83411 41767 83411 42309 83412 41767 83412 41768 83412 42316 83413 42315 83413 41769 83413 41769 83414 42315 83414 42314 83414 41769 83415 42314 83415 41770 83415 41770 83416 42314 83416 41775 83416 41770 83417 41775 83417 41771 83417 42301 83418 41772 83418 41773 83418 41773 83419 41772 83419 37301 83419 41773 83420 37301 83420 42320 83420 42320 83421 37301 83421 41771 83421 42320 83422 41771 83422 41774 83422 41774 83423 41771 83423 41775 83423 41776 83424 41741 83424 41777 83424 41777 83425 41741 83425 41778 83425 37307 83426 37306 83426 41779 83426 41779 83427 37306 83427 41789 83427 41780 83428 41781 83428 41792 83428 41792 83429 41781 83429 41782 83429 41782 83430 41781 83430 41836 83430 41836 83431 41781 83431 37316 83431 41836 83432 37316 83432 41783 83432 41783 83433 37316 83433 41784 83433 41783 83434 41784 83434 38039 83434 38039 83435 41784 83435 38038 83435 38038 83436 41784 83436 41777 83436 38038 83437 41777 83437 41778 83437 41790 83438 41785 83438 41786 83438 41786 83439 41785 83439 42287 83439 41786 83440 42287 83440 41787 83440 41787 83441 42287 83441 42286 83441 41787 83442 42286 83442 41788 83442 41788 83443 42286 83443 41789 83443 41788 83444 41789 83444 37306 83444 41790 83445 41786 83445 41791 83445 41791 83446 41786 83446 41793 83446 41791 83447 41793 83447 42291 83447 41780 83448 41792 83448 41799 83448 42291 83449 41793 83449 43389 83449 43389 83450 41793 83450 41794 83450 43389 83451 41794 83451 41795 83451 41795 83452 41794 83452 37361 83452 41795 83453 37361 83453 41797 83453 41797 83454 37361 83454 41796 83454 41797 83455 41796 83455 41799 83455 41799 83456 41796 83456 41798 83456 41799 83457 41798 83457 41780 83457 43371 83458 41837 83458 43373 83458 43373 83459 41837 83459 41800 83459 43373 83460 41800 83460 41834 83460 41834 83461 41840 83461 41841 83461 41834 83462 41841 83462 43373 83462 43373 83463 41841 83463 41843 83463 43373 83464 41843 83464 43367 83464 43369 83465 43394 83465 38037 83465 42079 83466 41801 83466 41802 83466 41802 83467 41801 83467 41803 83467 41802 83468 41803 83468 38037 83468 38037 83469 41803 83469 41850 83469 38037 83470 41850 83470 43369 83470 41804 83471 43408 83471 41805 83471 41807 83472 42100 83472 42101 83472 41805 83473 41806 83473 41804 83473 41804 83474 41806 83474 41807 83474 41804 83475 41807 83475 41808 83475 41808 83476 41807 83476 42101 83476 41809 83477 41858 83477 41859 83477 41859 83478 41810 83478 41809 83478 41809 83479 41810 83479 41861 83479 41809 83480 41861 83480 41811 83480 41811 83481 38030 83481 41809 83481 41809 83482 38030 83482 41812 83482 41809 83483 41812 83483 43405 83483 41814 83484 43402 83484 41869 83484 41869 83485 41813 83485 41814 83485 41814 83486 41813 83486 42134 83486 41814 83487 42134 83487 38027 83487 38027 83488 38023 83488 41814 83488 41814 83489 38023 83489 38024 83489 41814 83490 38024 83490 43400 83490 41816 83491 41815 83491 41879 83491 41879 83492 41881 83492 41816 83492 41816 83493 41881 83493 41817 83493 41816 83494 41817 83494 41818 83494 41818 83495 41887 83495 41816 83495 41816 83496 41887 83496 41819 83496 41816 83497 41819 83497 41888 83497 43398 83498 41821 83498 41820 83498 41820 83499 41821 83499 41822 83499 41820 83500 41822 83500 42190 83500 42190 83501 41893 83501 41823 83501 42190 83502 41823 83502 41820 83502 41820 83503 41823 83503 41896 83503 41820 83504 41896 83504 41898 83504 42216 83505 41906 83505 41824 83505 41824 83506 41906 83506 41908 83506 41824 83507 41908 83507 41899 83507 41899 83508 41908 83508 43420 83508 43420 83509 41908 83509 41909 83509 43420 83510 41909 83510 43396 83510 42248 83511 41914 83511 41825 83511 41825 83512 41914 83512 41918 83512 41825 83513 41918 83513 41913 83513 41913 83514 41918 83514 43380 83514 43380 83515 41918 83515 41920 83515 43380 83516 41920 83516 41922 83516 41826 83517 41827 83517 41923 83517 41923 83518 41927 83518 41826 83518 41826 83519 41927 83519 43193 83519 41826 83520 43193 83520 43186 83520 43186 83521 41934 83521 41826 83521 41826 83522 41934 83522 41828 83522 41826 83523 41828 83523 43383 83523 41832 83524 41829 83524 41830 83524 41830 83525 41831 83525 41832 83525 41832 83526 41831 83526 41938 83526 41832 83527 41938 83527 42041 83527 42041 83528 41946 83528 41832 83528 41832 83529 41946 83529 41833 83529 41832 83530 41833 83530 43376 83530 41834 83531 41782 83531 41835 83531 41835 83532 41782 83532 41836 83532 41835 83533 41836 83533 41783 83533 43371 83534 41792 83534 41837 83534 41837 83535 41792 83535 41782 83535 41837 83536 41782 83536 41800 83536 41800 83537 41782 83537 41834 83537 41840 83538 42062 83538 41730 83538 41730 83539 42062 83539 41838 83539 41730 83540 41838 83540 41731 83540 41731 83541 41838 83541 42073 83541 41731 83542 42073 83542 41738 83542 41730 83543 41839 83543 41840 83543 41840 83544 41839 83544 41842 83544 41840 83545 41842 83545 41841 83545 41841 83546 41842 83546 41732 83546 41841 83547 41732 83547 41843 83547 41843 83548 41732 83548 43368 83548 41843 83549 43368 83549 43367 83549 38037 83550 43394 83550 41710 83550 41710 83551 43394 83551 43392 83551 41801 83552 41844 83552 41845 83552 41845 83553 41844 83553 42085 83553 41845 83554 42085 83554 41668 83554 41668 83555 42085 83555 42082 83555 41668 83556 42082 83556 41846 83556 41845 83557 41847 83557 41801 83557 41801 83558 41847 83558 41848 83558 41801 83559 41848 83559 41803 83559 41803 83560 41848 83560 41849 83560 41803 83561 41849 83561 41850 83561 41850 83562 41849 83562 41851 83562 41850 83563 41851 83563 43369 83563 41805 83564 43407 83564 41806 83564 41806 83565 43407 83565 41854 83565 41653 83566 42103 83566 41852 83566 41852 83567 42103 83567 41853 83567 41852 83568 41853 83568 41651 83568 41651 83569 41853 83569 42100 83569 41651 83570 42100 83570 41854 83570 41854 83571 42100 83571 41807 83571 41854 83572 41807 83572 41806 83572 41653 83573 41654 83573 42103 83573 42103 83574 41654 83574 41855 83574 42103 83575 41855 83575 42109 83575 38032 83576 41804 83576 41856 83576 41856 83577 41804 83577 41808 83577 41856 83578 41808 83578 41613 83578 41613 83579 41808 83579 42101 83579 41613 83580 42101 83580 41612 83580 41612 83581 42101 83581 42108 83581 41612 83582 42108 83582 41857 83582 41857 83583 42108 83583 42106 83583 41857 83584 42106 83584 41611 83584 41858 83585 43403 83585 41859 83585 41859 83586 43403 83586 41860 83586 41593 83587 41863 83587 41592 83587 41592 83588 41863 83588 42121 83588 41592 83589 42121 83589 41590 83589 41590 83590 42121 83590 41861 83590 41590 83591 41861 83591 41860 83591 41860 83592 41861 83592 41810 83592 41860 83593 41810 83593 41859 83593 41593 83594 41595 83594 41863 83594 41863 83595 41595 83595 41862 83595 41863 83596 41862 83596 42116 83596 41546 83597 41865 83597 41864 83597 41864 83598 41865 83598 41866 83598 41864 83599 41866 83599 41867 83599 41867 83600 41866 83600 41868 83600 41867 83601 41868 83601 42117 83601 43402 83602 41538 83602 41869 83602 41869 83603 41538 83603 41872 83603 41873 83604 41875 83604 41528 83604 41528 83605 41875 83605 41870 83605 41528 83606 41870 83606 41871 83606 41871 83607 41870 83607 42134 83607 41871 83608 42134 83608 41872 83608 41872 83609 42134 83609 41813 83609 41872 83610 41813 83610 41869 83610 41873 83611 41874 83611 41875 83611 41875 83612 41874 83612 41530 83612 41875 83613 41530 83613 42137 83613 41876 83614 42146 83614 38025 83614 38025 83615 42146 83615 41877 83615 41815 83616 41878 83616 41879 83616 41879 83617 41878 83617 41453 83617 41457 83618 41882 83618 41456 83618 41456 83619 41882 83619 42162 83619 41456 83620 42162 83620 41880 83620 41880 83621 42162 83621 41817 83621 41880 83622 41817 83622 41453 83622 41453 83623 41817 83623 41881 83623 41453 83624 41881 83624 41879 83624 41457 83625 41459 83625 41882 83625 41882 83626 41459 83626 41450 83626 41882 83627 41450 83627 42165 83627 41818 83628 42159 83628 41885 83628 41885 83629 42159 83629 41883 83629 41885 83630 41883 83630 41410 83630 41410 83631 41883 83631 42148 83631 41410 83632 42148 83632 41884 83632 41885 83633 41886 83633 41818 83633 41818 83634 41886 83634 41408 83634 41818 83635 41408 83635 41887 83635 41887 83636 41408 83636 41411 83636 41887 83637 41411 83637 41819 83637 41819 83638 41411 83638 41413 83638 41819 83639 41413 83639 41888 83639 43398 83640 41414 83640 41821 83640 41821 83641 41414 83641 41891 83641 41415 83642 42193 83642 41889 83642 41889 83643 42193 83643 42192 83643 41889 83644 42192 83644 41890 83644 41890 83645 42192 83645 42190 83645 41890 83646 42190 83646 41891 83646 41891 83647 42190 83647 41822 83647 41891 83648 41822 83648 41821 83648 41415 83649 41417 83649 42193 83649 42193 83650 41417 83650 42175 83650 42193 83651 42175 83651 42195 83651 41893 83652 42202 83652 41892 83652 41892 83653 42202 83653 42201 83653 41892 83654 42201 83654 41462 83654 41462 83655 42201 83655 42200 83655 41462 83656 42200 83656 42177 83656 41892 83657 41894 83657 41893 83657 41893 83658 41894 83658 41460 83658 41893 83659 41460 83659 41823 83659 41823 83660 41460 83660 41895 83660 41823 83661 41895 83661 41896 83661 41896 83662 41895 83662 41897 83662 41896 83663 41897 83663 41898 83663 43420 83664 43419 83664 41899 83664 41899 83665 43419 83665 41481 83665 41901 83666 42218 83666 41483 83666 41483 83667 42218 83667 41900 83667 41483 83668 41900 83668 41482 83668 41482 83669 41900 83669 42216 83669 41482 83670 42216 83670 41481 83670 41481 83671 42216 83671 41824 83671 41481 83672 41824 83672 41899 83672 41901 83673 41484 83673 42218 83673 42218 83674 41484 83674 41485 83674 42218 83675 41485 83675 41902 83675 41906 83676 41903 83676 41532 83676 41532 83677 41903 83677 41904 83677 41532 83678 41904 83678 41905 83678 41905 83679 41904 83679 42227 83679 41905 83680 42227 83680 42203 83680 41532 83681 41531 83681 41906 83681 41906 83682 41531 83682 41907 83682 41906 83683 41907 83683 41908 83683 41908 83684 41907 83684 41535 83684 41908 83685 41535 83685 41909 83685 41909 83686 41535 83686 43231 83686 41909 83687 43231 83687 43396 83687 43380 83688 43379 83688 41913 83688 41913 83689 43379 83689 41910 83689 41552 83690 41911 83690 41551 83690 41551 83691 41911 83691 41912 83691 41551 83692 41912 83692 41550 83692 41550 83693 41912 83693 42248 83693 41550 83694 42248 83694 41910 83694 41910 83695 42248 83695 41825 83695 41910 83696 41825 83696 41913 83696 41552 83697 41553 83697 41911 83697 41911 83698 41553 83698 41554 83698 41911 83699 41554 83699 42249 83699 41914 83700 42247 83700 41915 83700 41915 83701 42247 83701 41916 83701 41915 83702 41916 83702 41598 83702 41598 83703 41916 83703 42230 83703 41598 83704 42230 83704 41588 83704 41915 83705 41597 83705 41914 83705 41914 83706 41597 83706 41917 83706 41914 83707 41917 83707 41918 83707 41918 83708 41917 83708 41919 83708 41918 83709 41919 83709 41920 83709 41920 83710 41919 83710 41921 83710 41920 83711 41921 83711 41922 83711 41827 83712 41616 83712 41923 83712 41923 83713 41616 83713 41928 83713 41618 83714 41925 83714 41924 83714 41924 83715 41925 83715 41926 83715 41924 83716 41926 83716 41617 83716 41617 83717 41926 83717 43193 83717 41617 83718 43193 83718 41928 83718 41928 83719 43193 83719 41927 83719 41928 83720 41927 83720 41923 83720 41618 83721 41619 83721 41925 83721 41925 83722 41619 83722 41621 83722 41925 83723 41621 83723 41929 83723 43186 83724 41930 83724 41656 83724 41656 83725 41930 83725 43185 83725 41656 83726 43185 83726 41657 83726 41657 83727 43185 83727 41931 83727 41657 83728 41931 83728 41659 83728 41656 83729 41932 83729 43186 83729 43186 83730 41932 83730 41933 83730 43186 83731 41933 83731 41934 83731 41934 83732 41933 83732 41660 83732 41934 83733 41660 83733 41828 83733 41828 83734 41660 83734 41666 83734 41828 83735 41666 83735 43383 83735 41829 83736 41935 83736 41830 83736 41830 83737 41935 83737 41939 83737 41940 83738 41941 83738 41672 83738 41672 83739 41941 83739 41936 83739 41672 83740 41936 83740 41937 83740 41937 83741 41936 83741 41938 83741 41937 83742 41938 83742 41939 83742 41939 83743 41938 83743 41831 83743 41939 83744 41831 83744 41830 83744 41940 83745 41674 83745 41941 83745 41941 83746 41674 83746 41676 83746 41941 83747 41676 83747 42022 83747 42041 83748 41943 83748 41942 83748 41942 83749 41943 83749 41944 83749 41942 83750 41944 83750 41716 83750 41716 83751 41944 83751 42023 83751 41716 83752 42023 83752 41718 83752 41942 83753 41715 83753 42041 83753 42041 83754 41715 83754 41945 83754 42041 83755 41945 83755 41946 83755 41946 83756 41945 83756 41720 83756 41946 83757 41720 83757 41833 83757 41833 83758 41720 83758 41727 83758 41833 83759 41727 83759 43376 83759 40486 83760 41947 83760 41948 83760 41948 83761 41947 83761 42061 83761 41948 83762 42061 83762 41949 83762 41949 83763 42061 83763 42060 83763 41949 83764 42060 83764 41950 83764 41950 83765 42060 83765 42063 83765 41950 83766 42063 83766 40482 83766 40482 83767 42063 83767 42065 83767 40482 83768 42065 83768 40479 83768 40479 83769 42065 83769 42066 83769 40479 83770 42066 83770 38018 83770 38018 83771 42066 83771 42069 83771 41951 83772 42083 83772 40470 83772 40470 83773 42083 83773 42080 83773 40470 83774 42080 83774 40469 83774 40469 83775 42080 83775 41952 83775 40469 83776 41952 83776 40468 83776 40468 83777 41952 83777 41953 83777 40468 83778 41953 83778 41955 83778 41955 83779 41953 83779 41954 83779 41955 83780 41954 83780 40465 83780 40465 83781 41954 83781 42087 83781 40465 83782 42087 83782 40464 83782 40464 83783 42087 83783 41956 83783 38013 83784 38015 83784 41957 83784 41957 83785 38015 83785 42102 83785 41957 83786 42102 83786 41958 83786 41958 83787 42102 83787 42104 83787 41958 83788 42104 83788 41959 83788 41959 83789 42104 83789 41960 83789 41959 83790 41960 83790 40458 83790 40458 83791 41960 83791 42112 83791 40458 83792 42112 83792 40457 83792 40457 83793 42112 83793 41961 83793 40457 83794 41961 83794 38009 83794 38009 83795 41961 83795 38010 83795 40436 83796 42122 83796 41963 83796 41963 83797 42122 83797 41962 83797 41963 83798 41962 83798 41964 83798 41964 83799 41962 83799 42124 83799 41964 83800 42124 83800 41965 83800 41965 83801 42124 83801 41967 83801 41965 83802 41967 83802 41966 83802 41966 83803 41967 83803 41969 83803 41966 83804 41969 83804 41968 83804 41968 83805 41969 83805 41970 83805 41968 83806 41970 83806 40444 83806 40444 83807 41970 83807 42128 83807 38002 83808 38003 83808 41971 83808 41971 83809 38003 83809 42138 83809 41971 83810 42138 83810 40422 83810 40422 83811 42138 83811 41972 83811 40422 83812 41972 83812 40424 83812 40424 83813 41972 83813 42140 83813 40424 83814 42140 83814 41973 83814 41973 83815 42140 83815 41974 83815 41973 83816 41974 83816 40427 83816 40427 83817 41974 83817 41975 83817 40427 83818 41975 83818 40429 83818 40429 83819 41975 83819 42143 83819 37997 83820 42166 83820 41976 83820 41976 83821 42166 83821 42168 83821 41976 83822 42168 83822 41977 83822 41977 83823 42168 83823 41978 83823 41977 83824 41978 83824 41979 83824 41979 83825 41978 83825 41980 83825 41979 83826 41980 83826 40411 83826 40411 83827 41980 83827 42171 83827 40411 83828 42171 83828 40412 83828 40412 83829 42171 83829 42173 83829 40412 83830 42173 83830 41982 83830 41982 83831 42173 83831 41981 83831 41982 83832 41981 83832 37992 83832 37992 83833 41981 83833 37993 83833 40408 83834 41983 83834 41985 83834 41985 83835 41983 83835 41984 83835 41985 83836 41984 83836 40406 83836 40406 83837 41984 83837 41987 83837 40406 83838 41987 83838 41986 83838 41986 83839 41987 83839 42198 83839 41986 83840 42198 83840 41988 83840 41988 83841 42198 83841 41990 83841 41988 83842 41990 83842 41989 83842 41989 83843 41990 83843 41991 83843 41989 83844 41991 83844 41992 83844 41992 83845 41991 83845 42199 83845 41992 83846 42199 83846 40402 83846 40402 83847 42199 83847 41993 83847 40397 83848 41994 83848 40396 83848 40396 83849 41994 83849 42223 83849 40396 83850 42223 83850 40395 83850 40395 83851 42223 83851 42224 83851 40395 83852 42224 83852 40394 83852 40394 83853 42224 83853 42225 83853 40394 83854 42225 83854 41995 83854 41995 83855 42225 83855 41996 83855 41995 83856 41996 83856 41997 83856 41997 83857 41996 83857 42226 83857 41997 83858 42226 83858 41998 83858 41998 83859 42226 83859 41999 83859 41998 83860 41999 83860 37976 83860 37976 83861 41999 83861 37977 83861 42000 83862 42001 83862 42002 83862 42002 83863 42001 83863 42256 83863 42002 83864 42256 83864 42003 83864 42003 83865 42256 83865 42258 83865 42003 83866 42258 83866 42004 83866 42004 83867 42258 83867 42005 83867 42004 83868 42005 83868 40380 83868 40380 83869 42005 83869 42246 83869 40380 83870 42246 83870 40381 83870 40381 83871 42246 83871 42006 83871 40381 83872 42006 83872 40382 83872 40382 83873 42006 83873 42245 83873 37973 83874 43189 83874 40372 83874 40372 83875 43189 83875 43192 83875 40372 83876 43192 83876 42007 83876 42007 83877 43192 83877 42008 83877 42007 83878 42008 83878 42009 83878 42009 83879 42008 83879 43184 83879 42009 83880 43184 83880 42010 83880 42010 83881 43184 83881 42011 83881 42010 83882 42011 83882 42012 83882 42012 83883 42011 83883 42013 83883 42012 83884 42013 83884 37965 83884 37965 83885 42013 83885 42014 83885 42015 83886 42016 83886 40368 83886 40368 83887 42016 83887 42047 83887 40368 83888 42047 83888 40367 83888 40367 83889 42047 83889 42039 83889 40367 83890 42039 83890 42017 83890 42017 83891 42039 83891 42038 83891 42017 83892 42038 83892 42018 83892 42018 83893 42038 83893 42040 83893 42018 83894 42040 83894 42019 83894 42019 83895 42040 83895 42021 83895 42019 83896 42021 83896 42020 83896 42020 83897 42021 83897 42042 83897 42020 83898 42042 83898 40364 83898 40364 83899 42042 83899 37961 83899 42037 83900 42043 83900 41676 83900 41676 83901 42043 83901 42022 83901 41718 83902 42023 83902 41709 83902 41709 83903 42023 83903 42024 83903 41709 83904 42024 83904 41696 83904 41696 83905 42024 83905 42025 83905 41696 83906 42025 83906 41697 83906 41697 83907 42025 83907 42026 83907 42026 83908 42025 83908 42027 83908 42026 83909 42027 83909 41698 83909 41698 83910 42027 83910 41700 83910 41700 83911 42027 83911 42031 83911 41700 83912 42031 83912 41701 83912 41705 83913 42028 83913 42029 83913 42029 83914 42028 83914 42030 83914 42029 83915 42030 83915 42031 83915 42031 83916 42030 83916 42032 83916 42031 83917 42032 83917 41701 83917 41705 83918 42029 83918 41706 83918 41706 83919 42029 83919 42033 83919 41706 83920 42033 83920 42034 83920 42034 83921 42033 83921 42035 83921 42035 83922 42033 83922 42045 83922 42035 83923 42045 83923 42036 83923 42036 83924 42045 83924 42043 83924 42036 83925 42043 83925 42037 83925 42038 83926 42039 83926 41944 83926 41938 83927 42040 83927 42041 83927 42041 83928 42040 83928 42038 83928 42041 83929 42038 83929 41943 83929 41943 83930 42038 83930 41944 83930 41936 83931 42042 83931 41938 83931 41938 83932 42042 83932 42021 83932 41938 83933 42021 83933 42040 83933 41936 83934 41941 83934 42042 83934 42042 83935 41941 83935 42022 83935 42042 83936 42022 83936 37961 83936 37961 83937 42022 83937 42043 83937 37961 83938 42043 83938 37962 83938 37962 83939 42043 83939 42045 83939 37962 83940 42045 83940 42044 83940 42044 83941 42045 83941 42033 83941 42044 83942 42033 83942 37963 83942 37963 83943 42033 83943 42029 83943 37963 83944 42029 83944 37964 83944 37964 83945 42029 83945 42031 83945 37964 83946 42031 83946 42046 83946 42046 83947 42031 83947 42027 83947 42046 83948 42027 83948 42016 83948 42016 83949 42027 83949 42025 83949 42016 83950 42025 83950 42047 83950 42047 83951 42025 83951 42024 83951 42047 83952 42024 83952 42039 83952 42039 83953 42024 83953 42023 83953 42039 83954 42023 83954 41944 83954 41741 83955 42067 83955 41778 83955 41778 83956 42067 83956 42064 83956 41738 83957 42073 83957 42048 83957 42048 83958 42073 83958 42049 83958 42048 83959 42049 83959 42050 83959 42050 83960 42049 83960 42051 83960 42050 83961 42051 83961 41757 83961 41757 83962 42051 83962 41756 83962 41756 83963 42051 83963 42052 83963 41756 83964 42052 83964 42055 83964 42056 83965 41751 83965 42053 83965 42053 83966 41751 83966 42054 83966 42053 83967 42054 83967 42052 83967 42052 83968 42054 83968 41754 83968 42052 83969 41754 83969 42055 83969 42056 83970 42053 83970 42057 83970 42057 83971 42053 83971 42059 83971 42057 83972 42059 83972 41748 83972 41748 83973 42059 83973 42058 83973 42058 83974 42059 83974 42070 83974 42058 83975 42070 83975 41745 83975 41834 83976 42063 83976 42060 83976 41834 83977 42060 83977 41840 83977 38022 83978 42073 83978 41947 83978 41947 83979 42073 83979 41838 83979 42060 83980 42061 83980 41840 83980 41840 83981 42061 83981 41947 83981 41840 83982 41947 83982 42062 83982 42062 83983 41947 83983 41838 83983 41834 83984 41835 83984 42063 83984 42063 83985 41835 83985 38040 83985 42063 83986 38040 83986 42065 83986 38040 83987 42064 83987 42065 83987 42065 83988 42064 83988 42067 83988 42065 83989 42067 83989 42066 83989 42066 83990 42067 83990 42068 83990 42066 83991 42068 83991 42069 83991 42069 83992 42068 83992 42070 83992 42069 83993 42070 83993 42071 83993 42071 83994 42070 83994 42059 83994 42071 83995 42059 83995 38020 83995 38020 83996 42059 83996 42053 83996 38020 83997 42053 83997 42072 83997 42072 83998 42053 83998 42052 83998 42072 83999 42052 83999 38021 83999 38021 84000 42052 84000 42051 84000 38021 84001 42051 84001 38022 84001 38022 84002 42051 84002 42049 84002 38022 84003 42049 84003 42073 84003 41678 84004 42086 84004 38036 84004 38036 84005 42086 84005 38034 84005 41846 84006 42082 84006 42074 84006 42074 84007 42082 84007 42075 84007 42074 84008 42075 84008 41694 84008 41694 84009 42075 84009 42090 84009 41694 84010 42090 84010 41693 84010 41693 84011 42090 84011 41692 84011 41692 84012 42090 84012 42089 84012 41692 84013 42089 84013 41690 84013 41682 84014 41680 84014 42076 84014 42076 84015 41680 84015 41679 84015 42076 84016 41679 84016 42089 84016 42089 84017 41679 84017 41688 84017 42089 84018 41688 84018 41690 84018 41682 84019 42076 84019 41683 84019 41683 84020 42076 84020 42077 84020 41683 84021 42077 84021 42078 84021 41953 84022 41952 84022 38033 84022 38033 84023 41952 84023 42079 84023 42079 84024 41952 84024 42080 84024 42079 84025 42080 84025 41801 84025 42081 84026 42082 84026 42084 84026 42084 84027 42082 84027 42085 84027 42080 84028 42083 84028 41801 84028 41801 84029 42083 84029 42084 84029 41801 84030 42084 84030 41844 84030 41844 84031 42084 84031 42085 84031 38033 84032 38034 84032 41953 84032 41953 84033 38034 84033 42086 84033 41953 84034 42086 84034 41954 84034 41954 84035 42086 84035 37958 84035 41954 84036 37958 84036 42087 84036 42087 84037 37958 84037 37956 84037 42087 84038 37956 84038 41956 84038 41956 84039 37956 84039 42077 84039 41956 84040 42077 84040 38016 84040 38016 84041 42077 84041 42076 84041 38016 84042 42076 84042 42088 84042 42088 84043 42076 84043 42089 84043 42088 84044 42089 84044 42091 84044 42091 84045 42089 84045 42090 84045 42091 84046 42090 84046 42081 84046 42081 84047 42090 84047 42075 84047 42081 84048 42075 84048 42082 84048 42092 84049 42110 84049 41855 84049 41855 84050 42110 84050 42109 84050 41611 84051 42106 84051 42094 84051 42094 84052 42106 84052 42093 84052 42094 84053 42093 84053 41638 84053 41638 84054 42093 84054 42096 84054 41638 84055 42096 84055 42095 84055 42095 84056 42096 84056 42097 84056 42097 84057 42096 84057 42098 84057 42097 84058 42098 84058 41634 84058 41634 84059 42098 84059 41626 84059 41626 84060 42098 84060 42099 84060 41626 84061 42099 84061 37950 84061 42102 84062 38015 84062 42100 84062 42100 84063 38015 84063 42101 84063 42100 84064 41853 84064 42102 84064 42102 84065 41853 84065 42103 84065 42102 84066 42103 84066 42104 84066 42107 84067 42105 84067 42106 84067 38015 84068 38014 84068 42101 84068 42101 84069 38014 84069 42107 84069 42101 84070 42107 84070 42108 84070 42108 84071 42107 84071 42106 84071 42103 84072 42109 84072 42104 84072 42104 84073 42109 84073 42110 84073 42104 84074 42110 84074 41960 84074 41960 84075 42110 84075 42111 84075 41960 84076 42111 84076 42112 84076 42112 84077 42111 84077 42113 84077 42112 84078 42113 84078 41961 84078 41961 84079 42113 84079 37953 84079 41961 84080 37953 84080 38010 84080 38010 84081 37953 84081 42099 84081 38010 84082 42099 84082 42114 84082 42114 84083 42099 84083 42098 84083 42114 84084 42098 84084 42115 84084 42115 84085 42098 84085 42096 84085 42115 84086 42096 84086 42105 84086 42105 84087 42096 84087 42093 84087 42105 84088 42093 84088 42106 84088 41558 84089 42125 84089 41862 84089 41862 84090 42125 84090 42116 84090 42117 84091 41868 84091 42118 84091 42118 84092 41868 84092 42119 84092 42118 84093 42119 84093 41572 84093 41572 84094 42119 84094 42129 84094 41572 84095 42129 84095 41569 84095 41569 84096 42129 84096 42120 84096 42120 84097 42129 84097 42127 84097 42120 84098 42127 84098 41567 84098 42121 84099 41863 84099 42122 84099 42122 84100 41863 84100 41962 84100 42121 84101 42122 84101 41861 84101 41861 84102 42122 84102 38008 84102 41861 84103 38008 84103 41811 84103 42123 84104 41868 84104 38006 84104 38006 84105 41868 84105 41866 84105 38008 84106 38007 84106 41811 84106 41811 84107 38007 84107 38006 84107 41811 84108 38006 84108 41865 84108 41865 84109 38006 84109 41866 84109 41863 84110 42116 84110 41962 84110 41962 84111 42116 84111 42125 84111 41962 84112 42125 84112 42124 84112 42124 84113 42125 84113 37948 84113 42124 84114 37948 84114 41967 84114 41967 84115 37948 84115 42126 84115 41967 84116 42126 84116 41969 84116 41969 84117 42126 84117 37942 84117 41969 84118 37942 84118 41970 84118 41970 84119 37942 84119 37944 84119 41970 84120 37944 84120 42128 84120 42128 84121 37944 84121 42127 84121 42128 84122 42127 84122 38005 84122 38005 84123 42127 84123 42129 84123 38005 84124 42129 84124 42123 84124 42123 84125 42129 84125 42119 84125 42123 84126 42119 84126 41868 84126 37939 84127 37938 84127 41530 84127 41530 84128 37938 84128 42137 84128 41877 84129 42146 84129 42130 84129 42130 84130 42146 84130 42145 84130 42145 84131 37929 84131 42130 84131 42130 84132 37929 84132 41505 84132 42131 84133 42132 84133 41876 84133 42134 84134 42136 84134 38027 84134 38027 84135 42136 84135 42131 84135 38027 84136 42131 84136 42133 84136 42133 84137 42131 84137 41876 84137 41870 84138 38000 84138 42134 84138 42134 84139 38000 84139 42135 84139 42134 84140 42135 84140 42136 84140 41870 84141 41875 84141 38000 84141 38000 84142 41875 84142 42137 84142 38000 84143 42137 84143 38003 84143 38003 84144 42137 84144 37938 84144 38003 84145 37938 84145 42138 84145 42138 84146 37938 84146 37937 84146 42138 84147 37937 84147 41972 84147 41972 84148 37937 84148 42139 84148 41972 84149 42139 84149 42140 84149 42140 84150 42139 84150 37930 84150 42140 84151 37930 84151 41974 84151 41974 84152 37930 84152 42141 84152 41974 84153 42141 84153 41975 84153 41975 84154 42141 84154 42142 84154 41975 84155 42142 84155 42143 84155 42143 84156 42142 84156 37929 84156 42143 84157 37929 84157 42144 84157 42144 84158 37929 84158 42145 84158 42144 84159 42145 84159 42132 84159 42132 84160 42145 84160 42146 84160 42132 84161 42146 84161 41876 84161 42147 84162 42167 84162 41450 84162 41450 84163 42167 84163 42165 84163 41884 84164 42148 84164 41419 84164 41419 84165 42148 84165 42174 84165 41419 84166 42174 84166 42149 84166 42149 84167 42174 84167 42151 84167 42149 84168 42151 84168 42150 84168 42150 84169 42151 84169 42152 84169 42152 84170 42151 84170 41434 84170 41434 84171 42151 84171 42172 84171 41434 84172 42172 84172 42153 84172 42153 84173 42172 84173 41432 84173 41432 84174 42172 84174 42155 84174 41432 84175 42155 84175 42154 84175 41427 84176 41430 84176 42155 84176 42155 84177 41430 84177 41431 84177 42155 84178 41431 84178 42154 84178 41427 84179 42155 84179 42156 84179 42156 84180 42155 84180 42170 84180 42156 84181 42170 84181 42157 84181 42157 84182 42170 84182 42169 84182 42157 84183 42169 84183 42158 84183 42158 84184 42169 84184 41423 84184 41423 84185 42169 84185 42167 84185 41423 84186 42167 84186 42147 84186 42163 84187 42160 84187 41817 84187 42159 84188 41818 84188 37994 84188 41817 84189 42160 84189 41818 84189 41818 84190 42160 84190 42161 84190 41818 84191 42161 84191 37994 84191 41817 84192 42162 84192 42163 84192 42163 84193 42162 84193 41882 84193 42163 84194 41882 84194 42164 84194 42164 84195 41882 84195 42165 84195 42164 84196 42165 84196 42166 84196 42166 84197 42165 84197 42167 84197 42166 84198 42167 84198 42168 84198 42168 84199 42167 84199 42169 84199 42168 84200 42169 84200 41978 84200 41978 84201 42169 84201 42170 84201 41978 84202 42170 84202 41980 84202 41980 84203 42170 84203 42155 84203 41980 84204 42155 84204 42171 84204 42171 84205 42155 84205 42172 84205 42171 84206 42172 84206 42173 84206 42173 84207 42172 84207 42151 84207 42173 84208 42151 84208 41981 84208 41981 84209 42151 84209 42174 84209 41981 84210 42174 84210 37993 84210 37993 84211 42174 84211 42148 84211 37993 84212 42148 84212 37994 84212 37994 84213 42148 84213 41883 84213 37994 84214 41883 84214 42159 84214 41422 84215 42176 84215 42175 84215 42175 84216 42176 84216 42195 84216 42177 84217 42200 84217 42178 84217 42178 84218 42200 84218 42179 84218 42178 84219 42179 84219 42180 84219 42180 84220 42179 84220 42181 84220 42180 84221 42181 84221 41437 84221 41437 84222 42181 84222 41439 84222 41439 84223 42181 84223 42182 84223 42182 84224 42181 84224 42183 84224 42182 84225 42183 84225 42184 84225 42184 84226 42183 84226 41442 84226 41442 84227 42183 84227 42186 84227 41442 84228 42186 84228 42185 84228 41446 84229 41445 84229 42186 84229 42186 84230 41445 84230 42187 84230 42186 84231 42187 84231 42185 84231 41446 84232 42186 84232 41447 84232 41447 84233 42186 84233 42197 84233 41447 84234 42197 84234 41448 84234 41448 84235 42197 84235 42196 84235 41448 84236 42196 84236 42188 84236 42188 84237 42196 84237 42189 84237 42189 84238 42196 84238 42176 84238 42189 84239 42176 84239 41422 84239 37989 84240 37985 84240 42190 84240 42190 84241 37985 84241 41893 84241 37985 84242 42191 84242 41893 84242 41893 84243 42191 84243 41993 84243 41893 84244 41993 84244 42202 84244 42190 84245 42192 84245 37989 84245 37989 84246 42192 84246 42193 84246 37989 84247 42193 84247 42194 84247 42194 84248 42193 84248 42195 84248 42194 84249 42195 84249 37991 84249 37991 84250 42195 84250 42176 84250 37991 84251 42176 84251 41983 84251 41983 84252 42176 84252 42196 84252 41983 84253 42196 84253 41984 84253 41984 84254 42196 84254 42197 84254 41984 84255 42197 84255 41987 84255 41987 84256 42197 84256 42186 84256 41987 84257 42186 84257 42198 84257 42198 84258 42186 84258 42183 84258 42198 84259 42183 84259 41990 84259 41990 84260 42183 84260 42181 84260 41990 84261 42181 84261 41991 84261 41991 84262 42181 84262 42179 84262 41991 84263 42179 84263 42199 84263 42199 84264 42179 84264 42200 84264 42199 84265 42200 84265 41993 84265 41993 84266 42200 84266 42201 84266 41993 84267 42201 84267 42202 84267 41525 84268 42215 84268 41485 84268 41485 84269 42215 84269 41902 84269 42203 84270 42227 84270 42204 84270 42204 84271 42227 84271 42205 84271 42204 84272 42205 84272 41506 84272 41506 84273 42205 84273 42206 84273 41506 84274 42206 84274 41509 84274 41509 84275 42206 84275 42207 84275 42207 84276 42206 84276 42208 84276 42207 84277 42208 84277 41511 84277 41511 84278 42208 84278 42209 84278 42209 84279 42208 84279 42211 84279 42209 84280 42211 84280 41513 84280 42210 84281 41519 84281 42222 84281 42222 84282 41519 84282 41517 84282 42222 84283 41517 84283 42211 84283 42211 84284 41517 84284 41514 84284 42211 84285 41514 84285 41513 84285 42210 84286 42222 84286 42212 84286 42212 84287 42222 84287 42213 84287 42212 84288 42213 84288 42214 84288 42214 84289 42213 84289 41522 84289 41522 84290 42213 84290 42221 84290 41522 84291 42221 84291 41523 84291 41523 84292 42221 84292 42215 84292 41523 84293 42215 84293 41525 84293 37980 84294 42217 84294 42216 84294 42216 84295 42217 84295 41906 84295 42216 84296 41900 84296 37980 84296 37980 84297 41900 84297 42218 84297 37980 84298 42218 84298 42219 84298 42217 84299 37977 84299 41906 84299 41906 84300 37977 84300 41999 84300 41906 84301 41999 84301 41903 84301 42218 84302 41902 84302 42219 84302 42219 84303 41902 84303 42215 84303 42219 84304 42215 84304 42220 84304 42220 84305 42215 84305 42221 84305 42220 84306 42221 84306 37983 84306 37983 84307 42221 84307 42213 84307 37983 84308 42213 84308 41994 84308 41994 84309 42213 84309 42222 84309 41994 84310 42222 84310 42223 84310 42223 84311 42222 84311 42211 84311 42223 84312 42211 84312 42224 84312 42224 84313 42211 84313 42208 84313 42224 84314 42208 84314 42225 84314 42225 84315 42208 84315 42206 84315 42225 84316 42206 84316 41996 84316 41996 84317 42206 84317 42205 84317 41996 84318 42205 84318 42226 84318 42226 84319 42205 84319 42227 84319 42226 84320 42227 84320 41999 84320 41999 84321 42227 84321 41904 84321 41999 84322 41904 84322 41903 84322 42228 84323 42229 84323 41554 84323 41554 84324 42229 84324 42249 84324 41588 84325 42230 84325 42231 84325 42231 84326 42230 84326 42232 84326 42231 84327 42232 84327 42233 84327 42233 84328 42232 84328 42234 84328 42233 84329 42234 84329 41573 84329 41573 84330 42234 84330 41575 84330 41575 84331 42234 84331 42257 84331 41575 84332 42257 84332 41576 84332 41576 84333 42257 84333 42235 84333 42235 84334 42257 84334 42236 84334 42235 84335 42236 84335 41578 84335 42237 84336 42238 84336 42255 84336 42255 84337 42238 84337 41581 84337 42255 84338 41581 84338 42236 84338 42236 84339 41581 84339 42239 84339 42236 84340 42239 84340 41578 84340 42237 84341 42255 84341 42240 84341 42240 84342 42255 84342 42254 84342 42240 84343 42254 84343 42241 84343 42241 84344 42254 84344 41585 84344 41585 84345 42254 84345 42242 84345 41585 84346 42242 84346 42243 84346 42243 84347 42242 84347 42229 84347 42243 84348 42229 84348 42228 84348 42244 84349 42245 84349 42248 84349 42248 84350 42245 84350 41914 84350 42005 84351 42230 84351 42246 84351 42246 84352 42230 84352 41916 84352 42245 84353 42006 84353 41914 84353 41914 84354 42006 84354 42246 84354 41914 84355 42246 84355 42247 84355 42247 84356 42246 84356 41916 84356 42248 84357 41912 84357 42244 84357 42244 84358 41912 84358 41911 84358 42244 84359 41911 84359 37974 84359 37974 84360 41911 84360 42249 84360 37974 84361 42249 84361 42250 84361 42250 84362 42249 84362 42229 84362 42250 84363 42229 84363 42251 84363 42251 84364 42229 84364 42242 84364 42251 84365 42242 84365 42252 84365 42252 84366 42242 84366 42254 84366 42252 84367 42254 84367 42253 84367 42253 84368 42254 84368 42255 84368 42253 84369 42255 84369 42001 84369 42001 84370 42255 84370 42236 84370 42001 84371 42236 84371 42256 84371 42256 84372 42236 84372 42257 84372 42256 84373 42257 84373 42258 84373 42258 84374 42257 84374 42234 84374 42258 84375 42234 84375 42005 84375 42005 84376 42234 84376 42232 84376 42005 84377 42232 84377 42230 84377 42259 84378 42260 84378 41621 84378 41621 84379 42260 84379 41929 84379 41659 84380 41931 84380 41639 84380 41639 84381 41931 84381 42261 84381 41639 84382 42261 84382 41640 84382 41640 84383 42261 84383 42262 84383 41640 84384 42262 84384 41641 84384 41641 84385 42262 84385 42263 84385 42263 84386 42262 84386 43191 84386 42263 84387 43191 84387 41642 84387 41642 84388 43191 84388 42264 84388 42264 84389 43191 84389 43190 84389 42264 84390 43190 84390 42268 84390 42269 84391 42265 84391 42266 84391 42266 84392 42265 84392 42267 84392 42266 84393 42267 84393 43190 84393 43190 84394 42267 84394 41645 84394 43190 84395 41645 84395 42268 84395 42269 84396 42266 84396 41647 84396 41647 84397 42266 84397 42272 84397 41647 84398 42272 84398 42270 84398 42270 84399 42272 84399 42271 84399 42271 84400 42272 84400 42273 84400 42271 84401 42273 84401 41649 84401 41649 84402 42273 84402 42260 84402 41649 84403 42260 84403 42259 84403 42274 84404 42275 84404 42277 84404 42277 84405 42278 84405 42274 84405 42274 84406 42278 84406 42279 84406 42274 84407 42279 84407 42288 84407 42288 84408 42289 84408 42274 84408 42274 84409 42289 84409 42290 84409 42274 84410 42290 84410 43390 84410 42275 84411 42276 84411 42277 84411 42277 84412 42276 84412 41733 84412 42277 84413 41733 84413 42278 84413 42278 84414 41733 84414 41734 84414 42278 84415 41734 84415 42279 84415 42279 84416 41734 84416 42281 84416 42279 84417 42281 84417 42280 84417 42280 84418 42281 84418 42283 84418 42280 84419 42283 84419 42282 84419 42282 84420 42283 84420 41736 84420 42282 84421 41736 84421 41737 84421 42288 84422 42284 84422 42287 84422 42287 84423 42284 84423 42285 84423 42287 84424 42285 84424 42286 84424 42286 84425 42285 84425 42303 84425 42286 84426 42303 84426 41789 84426 42287 84427 41785 84427 42288 84427 42288 84428 41785 84428 41790 84428 42288 84429 41790 84429 42289 84429 42289 84430 41790 84430 41791 84430 42289 84431 41791 84431 42290 84431 42290 84432 41791 84432 42291 84432 42290 84433 42291 84433 43390 84433 37928 84434 42329 84434 40356 84434 40356 84435 42329 84435 42292 84435 40356 84436 42292 84436 42294 84436 42294 84437 42292 84437 42293 84437 42294 84438 42293 84438 42295 84438 42295 84439 42293 84439 42297 84439 42295 84440 42297 84440 42296 84440 42296 84441 42297 84441 42298 84441 42296 84442 42298 84442 40351 84442 40351 84443 42298 84443 42321 84443 40351 84444 42321 84444 42299 84444 42299 84445 42321 84445 42322 84445 42299 84446 42322 84446 42300 84446 42300 84447 42322 84447 42323 84447 42301 84448 42324 84448 41740 84448 41740 84449 42324 84449 42302 84449 41789 84450 42303 84450 41779 84450 41779 84451 42303 84451 42307 84451 42318 84452 42310 84452 42317 84452 42304 84453 41761 84453 42305 84453 41779 84454 42307 84454 42306 84454 42306 84455 42307 84455 42304 84455 42306 84456 42304 84456 41760 84456 41760 84457 42304 84457 42305 84457 41761 84458 42304 84458 42308 84458 42308 84459 42304 84459 42312 84459 42308 84460 42312 84460 42309 84460 42310 84461 42311 84461 42317 84461 42317 84462 42311 84462 41765 84462 42317 84463 41765 84463 42312 84463 42312 84464 41765 84464 42313 84464 42312 84465 42313 84465 42309 84465 42319 84466 42314 84466 42327 84466 42327 84467 42314 84467 42315 84467 42327 84468 42315 84468 42317 84468 42317 84469 42315 84469 42316 84469 42317 84470 42316 84470 42318 84470 42325 84471 41773 84471 42319 84471 42319 84472 41773 84472 42320 84472 42320 84473 41774 84473 42319 84473 42319 84474 41774 84474 41775 84474 42319 84475 41775 84475 42314 84475 42288 84476 42279 84476 42297 84476 42297 84477 42279 84477 42298 84477 42298 84478 42279 84478 42280 84478 42298 84479 42280 84479 42321 84479 42297 84480 42293 84480 42288 84480 42288 84481 42293 84481 42292 84481 42288 84482 42292 84482 42284 84482 42284 84483 42292 84483 42285 84483 42280 84484 42282 84484 42321 84484 42321 84485 42282 84485 42302 84485 42321 84486 42302 84486 42322 84486 42322 84487 42302 84487 42324 84487 42322 84488 42324 84488 42323 84488 42323 84489 42324 84489 42325 84489 42323 84490 42325 84490 37922 84490 37922 84491 42325 84491 42319 84491 37922 84492 42319 84492 42326 84492 42326 84493 42319 84493 42327 84493 42326 84494 42327 84494 42328 84494 42328 84495 42327 84495 42317 84495 42328 84496 42317 84496 37926 84496 37926 84497 42317 84497 42312 84497 37926 84498 42312 84498 37927 84498 37927 84499 42312 84499 42304 84499 37927 84500 42304 84500 42329 84500 42329 84501 42304 84501 42307 84501 42329 84502 42307 84502 42292 84502 42292 84503 42307 84503 42303 84503 42292 84504 42303 84504 42285 84504 42330 84505 42632 84505 43170 84505 43170 84506 42632 84506 42331 84506 43170 84507 42331 84507 42332 84507 42332 84508 42331 84508 42642 84508 42332 84509 42642 84509 43173 84509 43173 84510 42642 84510 42333 84510 43173 84511 42333 84511 42335 84511 42335 84512 42333 84512 42334 84512 42335 84513 42334 84513 42336 84513 42336 84514 42334 84514 42337 84514 42336 84515 42337 84515 42338 84515 42338 84516 42337 84516 42650 84516 42338 84517 42650 84517 43176 84517 43176 84518 42650 84518 42339 84518 43176 84519 42339 84519 43177 84519 43177 84520 42339 84520 42340 84520 43177 84521 42340 84521 42341 84521 42341 84522 42340 84522 42665 84522 42341 84523 42665 84523 42342 84523 42342 84524 42665 84524 42343 84524 42342 84525 42343 84525 42344 84525 42344 84526 42343 84526 42667 84526 42344 84527 42667 84527 43179 84527 43179 84528 42667 84528 42668 84528 43179 84529 42668 84529 42345 84529 42345 84530 42668 84530 42646 84530 42345 84531 42646 84531 42346 84531 42346 84532 42646 84532 42648 84532 42346 84533 42648 84533 43182 84533 43182 84534 42648 84534 42636 84534 43182 84535 42636 84535 42347 84535 42347 84536 42636 84536 42637 84536 42347 84537 42637 84537 37372 84537 37372 84538 42637 84538 37906 84538 43168 84539 42348 84539 43166 84539 43166 84540 42348 84540 42573 84540 43166 84541 42573 84541 43164 84541 43164 84542 42573 84542 42600 84542 43164 84543 42600 84543 43162 84543 43162 84544 42600 84544 42349 84544 43162 84545 42349 84545 43161 84545 43161 84546 42349 84546 42627 84546 43161 84547 42627 84547 42350 84547 42350 84548 42627 84548 42613 84548 42350 84549 42613 84549 42351 84549 42351 84550 42613 84550 42623 84550 42351 84551 42623 84551 43158 84551 43158 84552 42623 84552 42624 84552 43158 84553 42624 84553 43157 84553 43157 84554 42624 84554 42610 84554 43157 84555 42610 84555 43155 84555 43155 84556 42610 84556 42621 84556 43155 84557 42621 84557 43154 84557 43154 84558 42621 84558 42352 84558 43154 84559 42352 84559 43153 84559 43153 84560 42352 84560 42605 84560 43153 84561 42605 84561 43151 84561 43151 84562 42605 84562 42617 84562 43151 84563 42617 84563 42353 84563 42353 84564 42617 84564 42354 84564 42353 84565 42354 84565 43150 84565 43150 84566 42354 84566 42607 84566 43150 84567 42607 84567 43149 84567 43149 84568 42607 84568 42608 84568 43149 84569 42608 84569 42355 84569 42355 84570 42608 84570 42598 84570 42355 84571 42598 84571 43146 84571 43146 84572 42598 84572 42597 84572 42457 84573 42359 84573 42356 84573 42430 84574 42357 84574 42431 84574 42461 84575 42631 84575 42358 84575 42641 84576 42461 84576 42462 84576 42416 84577 42410 84577 42629 84577 42629 84578 42410 84578 37857 84578 42365 84579 42357 84579 42666 84579 42666 84580 42357 84580 42430 84580 42666 84581 42430 84581 42429 84581 42663 84582 42359 84582 42360 84582 42360 84583 42359 84583 42457 84583 42360 84584 42457 84584 42456 84584 37857 84585 42410 84585 42361 84585 42361 84586 42410 84586 42362 84586 42361 84587 42362 84587 42408 84587 42435 84588 42431 84588 42363 84588 42363 84589 42431 84589 42357 84589 42363 84590 42357 84590 42364 84590 42364 84591 42357 84591 42365 84591 42364 84592 42365 84592 42432 84592 42366 84593 42356 84593 42367 84593 42367 84594 42356 84594 42359 84594 42367 84595 42359 84595 42368 84595 42368 84596 42359 84596 42663 84596 42368 84597 42663 84597 42641 84597 42369 84598 42412 84598 42411 84598 42370 84599 42721 84599 42420 84599 42420 84600 42721 84600 42369 84600 42420 84601 42369 84601 42418 84601 42418 84602 42369 84602 42411 84602 42418 84603 42411 84603 42417 84603 42638 84604 42635 84604 42419 84604 42419 84605 42635 84605 42371 84605 42419 84606 42371 84606 42421 84606 42421 84607 42371 84607 42372 84607 42421 84608 42372 84608 42373 84608 42373 84609 42372 84609 42422 84609 42649 84610 42425 84610 42424 84610 42424 84611 42425 84611 42374 84611 42424 84612 42374 84612 42375 84612 42375 84613 42374 84613 42427 84613 42375 84614 42427 84614 42377 84614 42377 84615 42427 84615 42376 84615 42377 84616 42376 84616 42378 84616 42378 84617 42376 84617 42379 84617 42647 84618 42380 84618 42426 84618 42426 84619 42380 84619 42382 84619 42426 84620 42382 84620 42381 84620 42381 84621 42382 84621 42383 84621 42381 84622 42383 84622 42384 84622 42384 84623 42383 84623 42388 84623 42380 84624 42385 84624 42382 84624 42382 84625 42385 84625 42386 84625 42382 84626 42386 84626 42383 84626 42383 84627 42386 84627 42387 84627 42383 84628 42387 84628 42388 84628 42388 84629 42387 84629 42389 84629 42388 84630 42389 84630 42702 84630 42702 84631 42389 84631 42390 84631 42391 84632 42439 84632 42434 84632 42444 84633 42436 84633 42443 84633 42443 84634 42436 84634 42391 84634 42443 84635 42391 84635 42442 84635 42442 84636 42391 84636 42434 84636 42442 84637 42434 84637 42433 84637 42640 84638 42639 84638 42441 84638 42441 84639 42639 84639 42447 84639 42441 84640 42447 84640 42393 84640 42393 84641 42447 84641 42392 84641 42393 84642 42392 84642 42445 84642 42445 84643 42392 84643 42394 84643 42446 84644 42651 84644 42395 84644 42395 84645 42651 84645 42450 84645 42395 84646 42450 84646 42448 84646 42448 84647 42450 84647 42451 84647 42448 84648 42451 84648 42396 84648 42396 84649 42451 84649 42452 84649 42396 84650 42452 84650 42397 84650 42397 84651 42452 84651 42455 84651 42664 84652 42399 84652 42398 84652 42398 84653 42399 84653 42401 84653 42398 84654 42401 84654 42453 84654 42453 84655 42401 84655 42402 84655 42453 84656 42402 84656 42454 84656 42454 84657 42402 84657 42404 84657 42399 84658 42400 84658 42401 84658 42401 84659 42400 84659 42403 84659 42401 84660 42403 84660 42402 84660 42402 84661 42403 84661 42458 84661 42402 84662 42458 84662 42404 84662 42404 84663 42458 84663 42406 84663 42404 84664 42406 84664 42405 84664 42405 84665 42406 84665 42407 84665 42408 84666 42362 84666 42409 84666 42409 84667 42362 84667 42413 84667 42409 84668 42413 84668 37794 84668 37794 84669 42413 84669 42715 84669 37794 84670 42715 84670 37639 84670 42416 84671 42417 84671 42410 84671 42410 84672 42417 84672 42411 84672 42410 84673 42411 84673 42362 84673 42362 84674 42411 84674 42412 84674 42362 84675 42412 84675 42413 84675 42413 84676 42412 84676 42415 84676 42413 84677 42415 84677 42715 84677 42721 84678 42414 84678 42369 84678 42369 84679 42414 84679 42719 84679 42369 84680 42719 84680 42412 84680 42412 84681 42719 84681 42716 84681 42412 84682 42716 84682 42415 84682 42416 84683 42638 84683 42417 84683 42417 84684 42638 84684 42419 84684 42417 84685 42419 84685 42418 84685 42418 84686 42419 84686 42421 84686 42418 84687 42421 84687 42420 84687 42420 84688 42421 84688 42373 84688 42420 84689 42373 84689 42370 84689 42710 84690 42423 84690 42422 84690 42422 84691 42423 84691 42707 84691 42422 84692 42707 84692 42373 84692 42373 84693 42707 84693 42706 84693 42373 84694 42706 84694 42370 84694 42635 84695 42649 84695 42371 84695 42371 84696 42649 84696 42424 84696 42371 84697 42424 84697 42372 84697 42372 84698 42424 84698 42375 84698 42372 84699 42375 84699 42422 84699 42422 84700 42375 84700 42377 84700 42422 84701 42377 84701 42710 84701 42710 84702 42377 84702 42378 84702 42425 84703 42647 84703 42374 84703 42374 84704 42647 84704 42426 84704 42374 84705 42426 84705 42427 84705 42427 84706 42426 84706 42381 84706 42427 84707 42381 84707 42376 84707 42376 84708 42381 84708 42384 84708 42376 84709 42384 84709 42379 84709 42702 84710 42712 84710 42388 84710 42388 84711 42712 84711 42428 84711 42388 84712 42428 84712 42384 84712 42384 84713 42428 84713 42711 84713 42384 84714 42711 84714 42379 84714 42385 84715 42429 84715 42386 84715 42386 84716 42429 84716 42430 84716 42386 84717 42430 84717 42387 84717 42387 84718 42430 84718 42431 84718 42387 84719 42431 84719 42389 84719 42389 84720 42431 84720 42435 84720 42389 84721 42435 84721 42390 84721 42390 84722 42435 84722 42704 84722 42432 84723 42433 84723 42364 84723 42364 84724 42433 84724 42434 84724 42364 84725 42434 84725 42363 84725 42363 84726 42434 84726 42439 84726 42363 84727 42439 84727 42435 84727 42435 84728 42439 84728 42440 84728 42435 84729 42440 84729 42704 84729 42436 84730 42691 84730 42391 84730 42391 84731 42691 84731 42437 84731 42391 84732 42437 84732 42439 84732 42439 84733 42437 84733 42438 84733 42439 84734 42438 84734 42440 84734 42432 84735 42640 84735 42433 84735 42433 84736 42640 84736 42441 84736 42433 84737 42441 84737 42442 84737 42442 84738 42441 84738 42393 84738 42442 84739 42393 84739 42443 84739 42443 84740 42393 84740 42445 84740 42443 84741 42445 84741 42444 84741 42449 84742 42697 84742 42394 84742 42394 84743 42697 84743 42696 84743 42394 84744 42696 84744 42445 84744 42445 84745 42696 84745 42694 84745 42445 84746 42694 84746 42444 84746 42639 84747 42446 84747 42447 84747 42447 84748 42446 84748 42395 84748 42447 84749 42395 84749 42392 84749 42392 84750 42395 84750 42448 84750 42392 84751 42448 84751 42394 84751 42394 84752 42448 84752 42396 84752 42394 84753 42396 84753 42449 84753 42449 84754 42396 84754 42397 84754 42651 84755 42664 84755 42450 84755 42450 84756 42664 84756 42398 84756 42450 84757 42398 84757 42451 84757 42451 84758 42398 84758 42453 84758 42451 84759 42453 84759 42452 84759 42452 84760 42453 84760 42454 84760 42452 84761 42454 84761 42455 84761 42405 84762 42689 84762 42404 84762 42404 84763 42689 84763 42701 84763 42404 84764 42701 84764 42454 84764 42454 84765 42701 84765 42700 84765 42454 84766 42700 84766 42455 84766 42400 84767 42456 84767 42403 84767 42403 84768 42456 84768 42457 84768 42403 84769 42457 84769 42458 84769 42458 84770 42457 84770 42356 84770 42458 84771 42356 84771 42406 84771 42406 84772 42356 84772 42366 84772 42406 84773 42366 84773 42407 84773 42407 84774 42366 84774 42687 84774 42460 84775 42465 84775 42459 84775 42641 84776 42462 84776 42368 84776 42368 84777 42462 84777 42463 84777 42368 84778 42463 84778 42367 84778 42367 84779 42463 84779 42460 84779 42367 84780 42460 84780 42366 84780 42366 84781 42460 84781 42459 84781 42366 84782 42459 84782 42687 84782 42461 84783 42358 84783 42462 84783 42462 84784 42358 84784 37790 84784 42462 84785 37790 84785 42463 84785 42463 84786 37790 84786 37825 84786 42463 84787 37825 84787 42460 84787 42460 84788 37825 84788 42464 84788 42460 84789 42464 84789 42465 84789 42466 84790 37687 84790 42571 84790 42539 84791 42537 84791 42467 84791 42468 84792 37725 84792 42536 84792 37726 84793 42713 84793 42714 84793 37725 84794 37726 84794 42536 84794 42536 84795 37726 84795 42714 84795 42536 84796 42714 84796 42469 84796 42469 84797 42714 84797 42470 84797 42469 84798 42470 84798 42533 84798 42533 84799 42470 84799 42717 84799 42533 84800 42717 84800 42532 84800 42532 84801 42717 84801 42718 84801 42532 84802 42718 84802 42531 84802 42531 84803 42718 84803 42720 84803 42531 84804 42720 84804 42529 84804 42529 84805 42720 84805 42722 84805 42529 84806 42722 84806 42527 84806 42527 84807 42722 84807 42471 84807 42527 84808 42471 84808 42526 84808 42526 84809 42471 84809 42472 84809 42526 84810 42472 84810 42525 84810 42525 84811 42472 84811 42708 84811 42525 84812 42708 84812 42473 84812 42473 84813 42708 84813 42709 84813 42473 84814 42709 84814 42524 84814 42524 84815 42709 84815 42474 84815 42524 84816 42474 84816 42476 84816 42476 84817 42474 84817 42475 84817 42476 84818 42475 84818 42477 84818 42477 84819 42475 84819 42478 84819 42477 84820 42478 84820 42520 84820 42520 84821 42478 84821 42683 84821 42520 84822 42683 84822 42519 84822 42519 84823 42683 84823 42682 84823 42519 84824 42682 84824 42479 84824 42479 84825 42682 84825 42480 84825 42479 84826 42480 84826 42481 84826 42481 84827 42480 84827 42703 84827 42481 84828 42703 84828 42515 84828 42515 84829 42703 84829 42482 84829 42515 84830 42482 84830 42514 84830 42514 84831 42482 84831 42705 84831 42514 84832 42705 84832 42483 84832 42483 84833 42705 84833 42485 84833 42483 84834 42485 84834 42484 84834 42484 84835 42485 84835 42692 84835 42484 84836 42692 84836 42486 84836 42486 84837 42692 84837 42693 84837 42486 84838 42693 84838 42511 84838 42511 84839 42693 84839 42487 84839 42511 84840 42487 84840 42488 84840 42488 84841 42487 84841 42489 84841 42488 84842 42489 84842 42510 84842 42510 84843 42489 84843 42695 84843 42510 84844 42695 84844 42490 84844 42490 84845 42695 84845 42491 84845 42490 84846 42491 84846 42507 84846 42507 84847 42491 84847 42698 84847 42507 84848 42698 84848 42492 84848 42492 84849 42698 84849 42493 84849 42492 84850 42493 84850 42494 84850 42494 84851 42493 84851 42699 84851 42494 84852 42699 84852 42495 84852 42495 84853 42699 84853 42496 84853 42495 84854 42496 84854 42504 84854 42504 84855 42496 84855 42690 84855 42504 84856 42690 84856 42502 84856 42502 84857 42690 84857 42688 84857 42502 84858 42688 84858 42501 84858 42501 84859 42688 84859 42686 84859 42501 84860 42686 84860 42497 84860 42497 84861 42686 84861 42685 84861 42497 84862 42685 84862 42499 84862 42499 84863 42685 84863 42498 84863 42499 84864 42498 84864 37789 84864 37789 84865 42498 84865 42684 84865 37789 84866 42466 84866 42499 84866 42499 84867 42466 84867 42571 84867 42499 84868 42571 84868 42497 84868 42497 84869 42571 84869 42569 84869 42497 84870 42569 84870 42501 84870 42501 84871 42569 84871 42500 84871 42501 84872 42500 84872 42502 84872 42502 84873 42500 84873 42503 84873 42502 84874 42503 84874 42504 84874 42504 84875 42503 84875 42568 84875 42504 84876 42568 84876 42495 84876 42495 84877 42568 84877 42505 84877 42495 84878 42505 84878 42494 84878 42494 84879 42505 84879 42565 84879 42494 84880 42565 84880 42492 84880 42492 84881 42565 84881 42506 84881 42492 84882 42506 84882 42507 84882 42507 84883 42506 84883 42508 84883 42507 84884 42508 84884 42490 84884 42490 84885 42508 84885 42509 84885 42490 84886 42509 84886 42510 84886 42510 84887 42509 84887 42563 84887 42510 84888 42563 84888 42488 84888 42488 84889 42563 84889 42562 84889 42488 84890 42562 84890 42511 84890 42511 84891 42562 84891 42561 84891 42511 84892 42561 84892 42486 84892 42486 84893 42561 84893 42512 84893 42486 84894 42512 84894 42484 84894 42484 84895 42512 84895 42559 84895 42484 84896 42559 84896 42483 84896 42483 84897 42559 84897 42513 84897 42483 84898 42513 84898 42514 84898 42514 84899 42513 84899 42557 84899 42514 84900 42557 84900 42515 84900 42515 84901 42557 84901 42516 84901 42515 84902 42516 84902 42481 84902 42481 84903 42516 84903 42517 84903 42481 84904 42517 84904 42479 84904 42479 84905 42517 84905 42518 84905 42479 84906 42518 84906 42519 84906 42519 84907 42518 84907 42554 84907 42519 84908 42554 84908 42520 84908 42520 84909 42554 84909 42553 84909 42520 84910 42553 84910 42477 84910 42477 84911 42553 84911 42521 84911 42477 84912 42521 84912 42476 84912 42476 84913 42521 84913 42522 84913 42476 84914 42522 84914 42524 84914 42524 84915 42522 84915 42523 84915 42524 84916 42523 84916 42473 84916 42473 84917 42523 84917 42548 84917 42473 84918 42548 84918 42525 84918 42525 84919 42548 84919 42546 84919 42525 84920 42546 84920 42526 84920 42526 84921 42546 84921 42545 84921 42526 84922 42545 84922 42527 84922 42527 84923 42545 84923 42528 84923 42527 84924 42528 84924 42529 84924 42529 84925 42528 84925 42543 84925 42529 84926 42543 84926 42531 84926 42531 84927 42543 84927 42530 84927 42531 84928 42530 84928 42532 84928 42532 84929 42530 84929 42542 84929 42532 84930 42542 84930 42533 84930 42533 84931 42542 84931 42534 84931 42533 84932 42534 84932 42469 84932 42469 84933 42534 84933 42535 84933 42469 84934 42535 84934 42536 84934 42536 84935 42535 84935 42467 84935 42536 84936 42467 84936 42468 84936 42468 84937 42467 84937 42537 84937 42538 84938 42539 84938 42572 84938 42572 84939 42539 84939 42467 84939 42572 84940 42467 84940 42540 84940 42540 84941 42467 84941 42535 84941 42540 84942 42535 84942 42602 84942 42602 84943 42535 84943 42534 84943 42602 84944 42534 84944 42541 84944 42541 84945 42534 84945 42542 84945 42541 84946 42542 84946 42601 84946 42601 84947 42542 84947 42530 84947 42601 84948 42530 84948 42625 84948 42625 84949 42530 84949 42543 84949 42625 84950 42543 84950 42626 84950 42626 84951 42543 84951 42528 84951 42626 84952 42528 84952 42544 84952 42544 84953 42528 84953 42545 84953 42544 84954 42545 84954 42628 84954 42628 84955 42545 84955 42546 84955 42628 84956 42546 84956 42547 84956 42547 84957 42546 84957 42548 84957 42547 84958 42548 84958 42549 84958 42549 84959 42548 84959 42523 84959 42549 84960 42523 84960 42550 84960 42550 84961 42523 84961 42522 84961 42550 84962 42522 84962 42551 84962 42551 84963 42522 84963 42521 84963 42551 84964 42521 84964 42552 84964 42552 84965 42521 84965 42553 84965 42552 84966 42553 84966 42612 84966 42612 84967 42553 84967 42554 84967 42612 84968 42554 84968 42611 84968 42611 84969 42554 84969 42518 84969 42611 84970 42518 84970 42555 84970 42555 84971 42518 84971 42517 84971 42555 84972 42517 84972 42556 84972 42556 84973 42517 84973 42516 84973 42556 84974 42516 84974 42622 84974 42622 84975 42516 84975 42557 84975 42622 84976 42557 84976 42558 84976 42558 84977 42557 84977 42513 84977 42558 84978 42513 84978 42619 84978 42619 84979 42513 84979 42559 84979 42619 84980 42559 84980 42620 84980 42620 84981 42559 84981 42512 84981 42620 84982 42512 84982 42560 84982 42560 84983 42512 84983 42561 84983 42560 84984 42561 84984 42614 84984 42614 84985 42561 84985 42562 84985 42614 84986 42562 84986 42615 84986 42615 84987 42562 84987 42563 84987 42615 84988 42563 84988 42616 84988 42616 84989 42563 84989 42509 84989 42616 84990 42509 84990 42564 84990 42564 84991 42509 84991 42508 84991 42564 84992 42508 84992 42618 84992 42618 84993 42508 84993 42506 84993 42618 84994 42506 84994 42606 84994 42606 84995 42506 84995 42565 84995 42606 84996 42565 84996 42566 84996 42566 84997 42565 84997 42505 84997 42566 84998 42505 84998 42567 84998 42567 84999 42505 84999 42568 84999 42567 85000 42568 85000 42609 85000 42609 85001 42568 85001 42503 85001 42609 85002 42503 85002 42604 85002 42604 85003 42503 85003 42500 85003 42604 85004 42500 85004 42599 85004 42599 85005 42500 85005 42569 85005 42599 85006 42569 85006 42570 85006 42570 85007 42569 85007 42571 85007 42570 85008 42571 85008 42595 85008 42595 85009 42571 85009 37687 85009 42348 85010 37905 85010 37733 85010 37733 85011 42538 85011 42348 85011 42348 85012 42538 85012 42572 85012 42348 85013 42572 85013 42573 85013 42590 85014 42574 85014 37899 85014 37899 85015 42574 85015 42584 85015 37899 85016 42584 85016 42585 85016 42575 85017 42593 85017 42592 85017 42576 85018 42577 85018 42578 85018 42578 85019 42577 85019 42579 85019 42578 85020 42579 85020 42580 85020 42579 85021 37696 85021 42580 85021 42580 85022 37696 85022 42581 85022 42580 85023 42581 85023 42582 85023 42582 85024 42581 85024 42583 85024 42582 85025 42583 85025 37905 85025 37905 85026 42583 85026 37735 85026 37905 85027 37735 85027 37733 85027 42584 85028 37708 85028 42585 85028 42585 85029 37708 85029 37705 85029 42585 85030 37705 85030 42586 85030 42586 85031 37705 85031 42588 85031 42586 85032 42588 85032 42587 85032 42587 85033 42588 85033 37755 85033 42587 85034 37755 85034 42576 85034 42576 85035 37755 85035 37701 85035 42576 85036 37701 85036 42577 85036 37895 85037 37773 85037 37897 85037 37897 85038 37773 85038 42589 85038 37897 85039 42589 85039 42590 85039 42590 85040 42589 85040 42591 85040 42590 85041 42591 85041 42574 85041 42592 85042 42593 85042 37785 85042 37785 85043 42593 85043 42596 85043 37785 85044 42596 85044 42594 85044 42594 85045 42596 85045 42595 85045 42595 85046 42596 85046 42597 85046 42595 85047 42597 85047 42570 85047 42570 85048 42597 85048 42598 85048 42570 85049 42598 85049 42599 85049 42349 85050 42600 85050 42601 85050 42572 85051 42540 85051 42573 85051 42573 85052 42540 85052 42602 85052 42573 85053 42602 85053 42600 85053 42600 85054 42602 85054 42541 85054 42600 85055 42541 85055 42601 85055 42592 85056 42603 85056 42575 85056 42575 85057 42603 85057 37780 85057 42575 85058 37780 85058 37894 85058 37894 85059 37780 85059 37719 85059 37894 85060 37719 85060 37895 85060 37895 85061 37719 85061 37717 85061 37895 85062 37717 85062 37773 85062 42599 85063 42598 85063 42604 85063 42604 85064 42598 85064 42608 85064 42604 85065 42608 85065 42609 85065 42607 85066 42354 85066 42618 85066 42617 85067 42605 85067 42614 85067 42352 85068 42620 85068 42605 85068 42605 85069 42620 85069 42560 85069 42605 85070 42560 85070 42614 85070 42618 85071 42606 85071 42607 85071 42607 85072 42606 85072 42566 85072 42607 85073 42566 85073 42608 85073 42608 85074 42566 85074 42567 85074 42608 85075 42567 85075 42609 85075 42610 85076 42624 85076 42611 85076 42611 85077 42624 85077 42612 85077 42623 85078 42613 85078 42549 85078 42614 85079 42615 85079 42617 85079 42617 85080 42615 85080 42616 85080 42617 85081 42616 85081 42354 85081 42354 85082 42616 85082 42564 85082 42354 85083 42564 85083 42618 85083 42621 85084 42558 85084 42352 85084 42352 85085 42558 85085 42619 85085 42352 85086 42619 85086 42620 85086 42611 85087 42555 85087 42610 85087 42610 85088 42555 85088 42556 85088 42610 85089 42556 85089 42621 85089 42621 85090 42556 85090 42622 85090 42621 85091 42622 85091 42558 85091 42549 85092 42550 85092 42623 85092 42623 85093 42550 85093 42551 85093 42623 85094 42551 85094 42624 85094 42624 85095 42551 85095 42552 85095 42624 85096 42552 85096 42612 85096 42601 85097 42625 85097 42349 85097 42349 85098 42625 85098 42626 85098 42349 85099 42626 85099 42627 85099 42626 85100 42544 85100 42627 85100 42627 85101 42544 85101 42628 85101 42627 85102 42628 85102 42613 85102 42613 85103 42628 85103 42547 85103 42613 85104 42547 85104 42549 85104 37906 85105 42637 85105 42416 85105 42331 85106 42632 85106 42631 85106 42416 85107 42629 85107 37906 85107 37906 85108 42629 85108 42630 85108 37906 85109 42630 85109 37907 85109 42631 85110 42632 85110 37889 85110 37889 85111 42632 85111 42645 85111 37889 85112 42645 85112 42643 85112 42630 85113 42633 85113 37907 85113 37907 85114 42633 85114 42634 85114 37907 85115 42634 85115 42679 85115 42648 85116 42649 85116 42636 85116 42636 85117 42649 85117 42635 85117 42636 85118 42635 85118 42637 85118 42637 85119 42635 85119 42638 85119 42637 85120 42638 85120 42416 85120 42339 85121 42639 85121 42340 85121 42340 85122 42639 85122 42640 85122 42340 85123 42640 85123 42665 85123 42631 85124 42461 85124 42331 85124 42331 85125 42461 85125 42641 85125 42331 85126 42641 85126 42642 85126 42642 85127 42641 85127 42663 85127 42642 85128 42663 85128 42333 85128 42643 85129 42645 85129 42644 85129 42644 85130 42645 85130 42655 85130 42644 85131 42655 85131 42657 85131 42654 85132 37918 85132 42652 85132 42659 85133 42662 85133 37879 85133 42668 85134 42380 85134 42646 85134 42646 85135 42380 85135 42647 85135 42646 85136 42647 85136 42648 85136 42648 85137 42647 85137 42425 85137 42648 85138 42425 85138 42649 85138 42337 85139 42664 85139 42650 85139 42650 85140 42664 85140 42651 85140 42650 85141 42651 85141 42339 85141 42339 85142 42651 85142 42446 85142 42339 85143 42446 85143 42639 85143 42652 85144 42653 85144 42654 85144 42654 85145 42653 85145 37886 85145 42654 85146 37886 85146 42655 85146 42655 85147 37886 85147 42656 85147 42655 85148 42656 85148 42657 85148 37879 85149 42658 85149 42659 85149 42659 85150 42658 85150 37882 85150 42659 85151 37882 85151 37918 85151 37918 85152 37882 85152 42660 85152 37918 85153 42660 85153 42652 85153 37915 85154 37876 85154 42662 85154 42662 85155 37876 85155 42661 85155 42662 85156 42661 85156 37879 85156 37910 85157 37868 85157 37911 85157 37911 85158 37868 85158 37869 85158 42663 85159 42360 85159 42333 85159 42333 85160 42360 85160 42456 85160 42333 85161 42456 85161 42334 85161 42334 85162 42456 85162 42400 85162 42334 85163 42400 85163 42337 85163 42337 85164 42400 85164 42399 85164 42337 85165 42399 85165 42664 85165 37869 85166 37870 85166 37911 85166 37911 85167 37870 85167 37871 85167 37911 85168 37871 85168 37913 85168 42640 85169 42432 85169 42665 85169 42665 85170 42432 85170 42365 85170 42665 85171 42365 85171 42343 85171 42343 85172 42365 85172 42666 85172 42343 85173 42666 85173 42667 85173 42667 85174 42666 85174 42429 85174 42667 85175 42429 85175 42668 85175 42668 85176 42429 85176 42385 85176 42668 85177 42385 85177 42380 85177 42669 85178 42670 85178 37915 85178 37915 85179 42670 85179 42671 85179 37915 85180 42671 85180 37876 85180 37871 85181 42672 85181 37913 85181 37913 85182 42672 85182 42673 85182 37913 85183 42673 85183 42669 85183 42669 85184 42673 85184 37873 85184 42669 85185 37873 85185 42670 85185 42675 85186 42674 85186 37862 85186 37862 85187 37865 85187 42675 85187 42675 85188 37865 85188 37867 85188 42675 85189 37867 85189 37910 85189 37910 85190 37867 85190 42676 85190 37910 85191 42676 85191 37868 85191 37908 85192 42677 85192 42674 85192 42674 85193 42677 85193 42678 85193 42674 85194 42678 85194 37862 85194 42634 85195 42680 85195 42679 85195 42679 85196 42680 85196 42681 85196 42679 85197 42681 85197 37908 85197 37908 85198 42681 85198 37861 85198 37908 85199 37861 85199 42677 85199 42682 85200 42683 85200 42712 85200 42464 85201 42684 85201 42465 85201 42465 85202 42684 85202 42498 85202 42465 85203 42498 85203 42459 85203 42459 85204 42498 85204 42685 85204 42459 85205 42685 85205 42687 85205 42687 85206 42685 85206 42686 85206 42687 85207 42686 85207 42407 85207 42407 85208 42686 85208 42688 85208 42407 85209 42688 85209 42405 85209 42405 85210 42688 85210 42690 85210 42405 85211 42690 85211 42689 85211 42689 85212 42690 85212 42496 85212 42485 85213 42691 85213 42692 85213 42692 85214 42691 85214 42436 85214 42692 85215 42436 85215 42693 85215 42693 85216 42436 85216 42444 85216 42693 85217 42444 85217 42487 85217 42487 85218 42444 85218 42694 85218 42487 85219 42694 85219 42489 85219 42489 85220 42694 85220 42696 85220 42489 85221 42696 85221 42695 85221 42695 85222 42696 85222 42697 85222 42695 85223 42697 85223 42491 85223 42491 85224 42697 85224 42449 85224 42491 85225 42449 85225 42698 85225 42698 85226 42449 85226 42397 85226 42698 85227 42397 85227 42493 85227 42493 85228 42397 85228 42455 85228 42493 85229 42455 85229 42699 85229 42699 85230 42455 85230 42700 85230 42699 85231 42700 85231 42496 85231 42496 85232 42700 85232 42701 85232 42496 85233 42701 85233 42689 85233 42682 85234 42712 85234 42480 85234 42712 85235 42702 85235 42480 85235 42480 85236 42702 85236 42390 85236 42480 85237 42390 85237 42703 85237 42703 85238 42390 85238 42704 85238 42703 85239 42704 85239 42482 85239 42482 85240 42704 85240 42440 85240 42482 85241 42440 85241 42705 85241 42705 85242 42440 85242 42438 85242 42705 85243 42438 85243 42485 85243 42485 85244 42438 85244 42437 85244 42485 85245 42437 85245 42691 85245 42722 85246 42370 85246 42471 85246 42471 85247 42370 85247 42706 85247 42471 85248 42706 85248 42472 85248 42472 85249 42706 85249 42707 85249 42472 85250 42707 85250 42708 85250 42708 85251 42707 85251 42423 85251 42708 85252 42423 85252 42709 85252 42709 85253 42423 85253 42710 85253 42709 85254 42710 85254 42474 85254 42474 85255 42710 85255 42378 85255 42474 85256 42378 85256 42475 85256 42475 85257 42378 85257 42379 85257 42475 85258 42379 85258 42478 85258 42478 85259 42379 85259 42711 85259 42478 85260 42711 85260 42683 85260 42683 85261 42711 85261 42428 85261 42683 85262 42428 85262 42712 85262 42713 85263 37639 85263 42714 85263 42714 85264 37639 85264 42715 85264 42714 85265 42715 85265 42470 85265 42470 85266 42715 85266 42415 85266 42470 85267 42415 85267 42717 85267 42717 85268 42415 85268 42716 85268 42717 85269 42716 85269 42718 85269 42718 85270 42716 85270 42719 85270 42718 85271 42719 85271 42720 85271 42720 85272 42719 85272 42414 85272 42720 85273 42414 85273 42722 85273 42722 85274 42414 85274 42721 85274 42722 85275 42721 85275 42370 85275 37450 85276 42724 85276 42723 85276 42723 85277 42724 85277 42796 85277 42723 85278 42796 85278 42725 85278 42725 85279 42796 85279 42797 85279 42725 85280 42797 85280 37446 85280 37446 85281 42797 85281 42726 85281 42726 85282 42797 85282 42799 85282 42726 85283 42799 85283 37448 85283 37448 85284 42799 85284 42727 85284 37448 85285 42727 85285 37449 85285 37449 85286 42727 85286 42728 85286 42728 85287 42727 85287 42729 85287 42728 85288 42729 85288 42730 85288 42730 85289 42729 85289 42801 85289 42730 85290 42801 85290 37443 85290 37443 85291 42801 85291 42731 85291 37443 85292 42731 85292 37444 85292 37444 85293 42731 85293 42732 85293 42732 85294 42731 85294 42804 85294 42732 85295 42804 85295 42733 85295 42733 85296 42804 85296 42805 85296 42733 85297 42805 85297 37442 85297 37442 85298 42805 85298 42734 85298 42734 85299 42805 85299 42735 85299 42734 85300 42735 85300 42737 85300 42737 85301 42735 85301 42736 85301 42737 85302 42736 85302 37439 85302 37439 85303 42736 85303 42738 85303 42738 85304 42736 85304 42808 85304 42738 85305 42808 85305 37437 85305 37437 85306 42808 85306 42739 85306 37437 85307 42739 85307 42740 85307 42740 85308 42739 85308 37438 85308 37438 85309 42739 85309 42810 85309 37438 85310 42810 85310 37436 85310 37436 85311 42810 85311 42742 85311 37436 85312 42742 85312 42741 85312 42741 85313 42742 85313 42744 85313 42744 85314 42742 85314 42743 85314 42744 85315 42743 85315 37434 85315 37434 85316 42743 85316 42813 85316 37434 85317 42813 85317 42745 85317 42745 85318 42813 85318 42747 85318 42747 85319 42813 85319 42746 85319 42747 85320 42746 85320 42748 85320 42748 85321 42746 85321 42814 85321 42748 85322 42814 85322 37433 85322 37433 85323 42814 85323 42817 85323 37433 85324 42817 85324 37428 85324 37428 85325 42817 85325 42818 85325 37428 85326 42818 85326 37429 85326 37429 85327 42818 85327 37430 85327 37430 85328 42818 85328 42819 85328 37430 85329 42819 85329 37431 85329 37431 85330 42819 85330 42820 85330 37431 85331 42820 85331 37432 85331 37432 85332 42820 85332 42749 85332 42749 85333 42820 85333 42821 85333 42749 85334 42821 85334 37427 85334 37427 85335 42821 85335 42750 85335 37427 85336 42750 85336 42751 85336 42751 85337 42750 85337 42824 85337 42751 85338 42824 85338 42752 85338 42752 85339 42824 85339 42753 85339 42753 85340 42824 85340 42826 85340 42753 85341 42826 85341 42754 85341 42754 85342 42826 85342 42755 85342 42754 85343 42755 85343 37422 85343 37422 85344 42755 85344 42756 85344 42756 85345 42755 85345 42829 85345 42756 85346 42829 85346 37419 85346 37419 85347 42829 85347 42830 85347 37419 85348 42830 85348 37420 85348 37420 85349 42830 85349 42757 85349 42757 85350 42830 85350 42758 85350 42757 85351 42758 85351 37421 85351 37421 85352 42758 85352 42832 85352 37421 85353 42832 85353 37417 85353 37417 85354 42832 85354 37414 85354 37414 85355 42832 85355 42759 85355 37414 85356 42759 85356 42760 85356 42760 85357 42759 85357 42836 85357 42760 85358 42836 85358 37415 85358 42795 85359 42762 85359 42761 85359 42761 85360 42762 85360 37348 85360 42761 85361 37348 85361 42798 85361 42798 85362 37348 85362 42763 85362 42798 85363 42763 85363 42800 85363 42800 85364 42763 85364 37339 85364 42800 85365 37339 85365 42764 85365 42764 85366 37339 85366 42765 85366 42764 85367 42765 85367 42766 85367 42766 85368 42765 85368 37354 85368 42766 85369 37354 85369 42802 85369 42802 85370 37354 85370 42767 85370 42802 85371 42767 85371 42803 85371 42803 85372 42767 85372 37355 85372 42803 85373 37355 85373 42768 85373 42768 85374 37355 85374 42769 85374 42768 85375 42769 85375 42806 85375 42806 85376 42769 85376 37326 85376 42806 85377 37326 85377 42807 85377 42807 85378 37326 85378 37324 85378 42807 85379 37324 85379 42770 85379 42770 85380 37324 85380 42772 85380 42770 85381 42772 85381 42771 85381 42771 85382 42772 85382 42773 85382 42771 85383 42773 85383 42809 85383 42809 85384 42773 85384 37360 85384 42809 85385 37360 85385 42774 85385 42774 85386 37360 85386 37362 85386 42774 85387 37362 85387 42811 85387 42811 85388 37362 85388 37311 85388 42811 85389 37311 85389 42812 85389 42812 85390 37311 85390 37312 85390 42812 85391 37312 85391 42775 85391 42775 85392 37312 85392 42776 85392 42775 85393 42776 85393 42777 85393 42777 85394 42776 85394 42778 85394 42777 85395 42778 85395 42815 85395 42815 85396 42778 85396 37364 85396 42815 85397 37364 85397 42816 85397 42816 85398 37364 85398 37297 85398 42816 85399 37297 85399 42779 85399 42779 85400 37297 85400 42780 85400 42779 85401 42780 85401 42781 85401 42781 85402 42780 85402 37285 85402 42781 85403 37285 85403 42782 85403 42782 85404 37285 85404 42783 85404 42782 85405 42783 85405 42822 85405 42822 85406 42783 85406 37283 85406 42822 85407 37283 85407 42823 85407 42823 85408 37283 85408 37366 85408 42823 85409 37366 85409 42825 85409 42825 85410 37366 85410 37368 85410 42825 85411 37368 85411 42827 85411 42827 85412 37368 85412 42784 85412 42827 85413 42784 85413 42828 85413 42828 85414 42784 85414 37261 85414 42828 85415 37261 85415 42785 85415 42785 85416 37261 85416 37264 85416 42785 85417 37264 85417 42831 85417 42831 85418 37264 85418 37266 85418 42831 85419 37266 85419 42786 85419 42786 85420 37266 85420 42787 85420 42786 85421 42787 85421 42833 85421 42833 85422 42787 85422 42788 85422 42833 85423 42788 85423 42790 85423 42790 85424 42788 85424 42789 85424 42790 85425 42789 85425 42791 85425 42791 85426 42789 85426 42792 85426 42791 85427 42792 85427 42793 85427 42793 85428 42792 85428 42794 85428 42793 85429 42794 85429 42835 85429 42835 85430 42794 85430 37242 85430 42724 85431 42795 85431 42796 85431 42796 85432 42795 85432 42761 85432 42796 85433 42761 85433 42797 85433 42797 85434 42761 85434 42798 85434 42797 85435 42798 85435 42799 85435 42799 85436 42798 85436 42800 85436 42799 85437 42800 85437 42727 85437 42727 85438 42800 85438 42764 85438 42727 85439 42764 85439 42729 85439 42729 85440 42764 85440 42766 85440 42729 85441 42766 85441 42801 85441 42801 85442 42766 85442 42802 85442 42801 85443 42802 85443 42731 85443 42731 85444 42802 85444 42803 85444 42731 85445 42803 85445 42804 85445 42804 85446 42803 85446 42768 85446 42804 85447 42768 85447 42805 85447 42805 85448 42768 85448 42806 85448 42805 85449 42806 85449 42735 85449 42735 85450 42806 85450 42807 85450 42735 85451 42807 85451 42736 85451 42736 85452 42807 85452 42770 85452 42736 85453 42770 85453 42808 85453 42808 85454 42770 85454 42771 85454 42808 85455 42771 85455 42739 85455 42739 85456 42771 85456 42809 85456 42739 85457 42809 85457 42810 85457 42810 85458 42809 85458 42774 85458 42810 85459 42774 85459 42742 85459 42742 85460 42774 85460 42811 85460 42742 85461 42811 85461 42743 85461 42743 85462 42811 85462 42812 85462 42743 85463 42812 85463 42813 85463 42813 85464 42812 85464 42775 85464 42813 85465 42775 85465 42746 85465 42746 85466 42775 85466 42777 85466 42746 85467 42777 85467 42814 85467 42814 85468 42777 85468 42815 85468 42814 85469 42815 85469 42817 85469 42817 85470 42815 85470 42816 85470 42817 85471 42816 85471 42818 85471 42818 85472 42816 85472 42779 85472 42818 85473 42779 85473 42819 85473 42819 85474 42779 85474 42781 85474 42819 85475 42781 85475 42820 85475 42820 85476 42781 85476 42782 85476 42820 85477 42782 85477 42821 85477 42821 85478 42782 85478 42822 85478 42821 85479 42822 85479 42750 85479 42750 85480 42822 85480 42823 85480 42750 85481 42823 85481 42824 85481 42824 85482 42823 85482 42825 85482 42824 85483 42825 85483 42826 85483 42826 85484 42825 85484 42827 85484 42826 85485 42827 85485 42755 85485 42755 85486 42827 85486 42828 85486 42755 85487 42828 85487 42829 85487 42829 85488 42828 85488 42785 85488 42829 85489 42785 85489 42830 85489 42830 85490 42785 85490 42831 85490 42830 85491 42831 85491 42758 85491 42758 85492 42831 85492 42786 85492 42758 85493 42786 85493 42832 85493 42832 85494 42786 85494 42833 85494 42832 85495 42833 85495 42759 85495 42759 85496 42833 85496 42790 85496 42759 85497 42790 85497 42836 85497 42836 85498 42790 85498 42791 85498 42836 85499 42791 85499 42838 85499 42838 85500 42791 85500 42793 85500 42838 85501 42793 85501 42834 85501 42834 85502 42793 85502 42835 85502 37415 85503 42836 85503 37416 85503 37416 85504 42836 85504 42838 85504 37416 85505 42838 85505 42837 85505 42837 85506 42838 85506 42834 85506 42837 85507 42834 85507 42842 85507 37242 85508 42839 85508 42843 85508 37242 85509 42843 85509 42835 85509 42835 85510 42843 85510 42840 85510 42835 85511 42840 85511 42834 85511 42834 85512 42840 85512 42841 85512 42834 85513 42841 85513 42842 85513 42839 85514 37559 85514 37558 85514 42839 85515 37558 85515 42843 85515 42843 85516 37558 85516 37519 85516 42843 85517 37519 85517 42840 85517 42840 85518 37519 85518 37518 85518 42840 85519 37518 85519 42841 85519 42844 85520 42845 85520 38139 85520 38139 85521 42845 85521 37514 85521 38139 85522 37514 85522 38140 85522 38140 85523 37514 85523 42846 85523 38140 85524 42846 85524 38142 85524 38142 85525 42846 85525 42848 85525 38142 85526 42848 85526 42847 85526 42847 85527 42848 85527 42849 85527 42847 85528 42849 85528 41278 85528 41278 85529 42849 85529 37516 85529 41278 85530 37516 85530 41279 85530 41279 85531 37516 85531 42870 85531 41279 85532 42870 85532 41281 85532 41281 85533 42870 85533 42850 85533 41281 85534 42850 85534 41282 85534 41282 85535 42850 85535 42873 85535 41282 85536 42873 85536 41284 85536 41284 85537 42873 85537 42851 85537 41284 85538 42851 85538 41285 85538 41285 85539 42851 85539 42852 85539 41285 85540 42852 85540 41286 85540 41286 85541 42852 85541 42853 85541 41286 85542 42853 85542 41288 85542 41288 85543 42853 85543 42879 85543 41288 85544 42879 85544 41289 85544 41289 85545 42879 85545 42881 85545 41289 85546 42881 85546 42854 85546 42854 85547 42881 85547 42883 85547 42854 85548 42883 85548 41290 85548 41290 85549 42883 85549 42885 85549 41290 85550 42885 85550 42855 85550 42855 85551 42885 85551 42856 85551 42855 85552 42856 85552 41293 85552 41293 85553 42856 85553 42857 85553 41293 85554 42857 85554 41294 85554 41294 85555 42857 85555 42858 85555 41294 85556 42858 85556 41296 85556 41296 85557 42858 85557 42859 85557 41296 85558 42859 85558 42860 85558 42860 85559 42859 85559 42861 85559 42860 85560 42861 85560 41297 85560 41297 85561 42861 85561 42862 85561 41297 85562 42862 85562 38124 85562 38124 85563 42862 85563 42863 85563 38124 85564 42863 85564 38125 85564 38125 85565 42863 85565 37503 85565 38125 85566 37503 85566 38127 85566 38127 85567 37503 85567 42864 85567 38127 85568 42864 85568 38128 85568 38128 85569 42864 85569 37504 85569 38128 85570 37504 85570 38130 85570 38130 85571 37504 85571 42865 85571 38130 85572 42865 85572 38132 85572 38132 85573 42865 85573 42866 85573 38132 85574 42866 85574 38133 85574 38133 85575 42866 85575 37508 85575 38133 85576 37508 85576 38134 85576 38134 85577 37508 85577 42867 85577 38134 85578 42867 85578 42869 85578 42869 85579 42867 85579 42868 85579 42869 85580 42868 85580 38137 85580 38137 85581 42868 85581 37510 85581 38137 85582 37510 85582 42844 85582 42844 85583 37510 85583 42845 85583 37516 85584 42871 85584 42870 85584 42870 85585 42871 85585 42872 85585 42870 85586 42872 85586 42850 85586 42850 85587 42872 85587 42874 85587 42850 85588 42874 85588 42873 85588 42873 85589 42874 85589 42875 85589 42873 85590 42875 85590 42851 85590 42851 85591 42875 85591 42876 85591 42851 85592 42876 85592 42852 85592 42852 85593 42876 85593 42877 85593 42852 85594 42877 85594 42853 85594 42853 85595 42877 85595 42878 85595 42853 85596 42878 85596 42879 85596 42879 85597 42878 85597 42880 85597 42879 85598 42880 85598 42881 85598 42881 85599 42880 85599 42882 85599 42881 85600 42882 85600 42883 85600 42883 85601 42882 85601 42884 85601 42883 85602 42884 85602 42885 85602 42885 85603 42884 85603 42886 85603 42885 85604 42886 85604 42856 85604 42856 85605 42886 85605 42887 85605 42856 85606 42887 85606 42857 85606 42857 85607 42887 85607 41270 85607 42857 85608 41270 85608 42858 85608 42858 85609 41270 85609 41272 85609 42858 85610 41272 85610 42859 85610 42859 85611 41272 85611 41273 85611 42859 85612 41273 85612 42861 85612 42861 85613 41273 85613 41274 85613 42861 85614 41274 85614 42862 85614 42862 85615 41274 85615 41275 85615 42922 85616 38051 85616 41269 85616 41269 85617 38051 85617 42888 85617 41269 85618 42888 85618 41271 85618 41271 85619 42888 85619 42889 85619 41271 85620 42889 85620 42890 85620 42890 85621 42889 85621 42892 85621 42890 85622 42892 85622 42891 85622 42891 85623 42892 85623 42893 85623 42891 85624 42893 85624 41276 85624 41276 85625 42893 85625 42894 85625 41276 85626 42894 85626 42895 85626 42895 85627 42894 85627 38054 85627 42895 85628 38054 85628 42896 85628 42896 85629 38054 85629 42897 85629 42896 85630 42897 85630 38145 85630 38145 85631 42897 85631 41386 85631 38145 85632 41386 85632 42898 85632 42898 85633 41386 85633 42899 85633 42898 85634 42899 85634 38146 85634 38146 85635 42899 85635 41388 85635 38146 85636 41388 85636 42900 85636 42900 85637 41388 85637 42901 85637 42900 85638 42901 85638 38148 85638 38148 85639 42901 85639 42902 85639 38148 85640 42902 85640 42904 85640 42904 85641 42902 85641 42903 85641 42904 85642 42903 85642 38150 85642 38150 85643 42903 85643 41392 85643 38150 85644 41392 85644 38151 85644 38151 85645 41392 85645 42905 85645 38151 85646 42905 85646 42906 85646 42906 85647 42905 85647 41393 85647 42906 85648 41393 85648 42907 85648 42907 85649 41393 85649 41395 85649 42907 85650 41395 85650 42908 85650 42908 85651 41395 85651 41397 85651 42908 85652 41397 85652 38154 85652 38154 85653 41397 85653 42909 85653 38154 85654 42909 85654 38155 85654 38155 85655 42909 85655 42910 85655 38155 85656 42910 85656 38156 85656 38156 85657 42910 85657 41400 85657 38156 85658 41400 85658 38157 85658 38157 85659 41400 85659 41401 85659 38157 85660 41401 85660 42911 85660 42911 85661 41401 85661 42912 85661 42911 85662 42912 85662 42913 85662 42913 85663 42912 85663 42914 85663 42913 85664 42914 85664 41266 85664 41266 85665 42914 85665 38043 85665 41266 85666 38043 85666 42915 85666 42915 85667 38043 85667 42916 85667 42915 85668 42916 85668 41267 85668 41267 85669 42916 85669 42917 85669 41267 85670 42917 85670 42918 85670 42918 85671 42917 85671 38046 85671 42918 85672 38046 85672 41268 85672 41268 85673 38046 85673 38048 85673 41268 85674 38048 85674 42919 85674 42919 85675 38048 85675 42921 85675 42919 85676 42921 85676 42920 85676 42920 85677 42921 85677 38050 85677 42920 85678 38050 85678 42922 85678 42922 85679 38050 85679 38051 85679 42961 85680 37501 85680 41399 85680 42961 85681 41399 85681 42960 85681 42960 85682 41399 85682 41398 85682 42960 85683 41398 85683 42959 85683 42959 85684 41398 85684 41396 85684 42959 85685 41396 85685 42924 85685 42924 85686 41396 85686 42923 85686 42924 85687 42923 85687 42957 85687 42957 85688 42923 85688 41394 85688 42957 85689 41394 85689 42956 85689 42956 85690 41394 85690 42925 85690 42956 85691 42925 85691 42954 85691 42954 85692 42925 85692 42926 85692 42954 85693 42926 85693 42927 85693 42927 85694 42926 85694 41391 85694 42927 85695 41391 85695 42928 85695 42928 85696 41391 85696 41390 85696 42928 85697 41390 85697 42952 85697 42952 85698 41390 85698 41389 85698 42952 85699 41389 85699 42929 85699 42929 85700 41389 85700 42930 85700 42929 85701 42930 85701 42950 85701 42950 85702 42930 85702 42931 85702 42950 85703 42931 85703 42932 85703 42932 85704 42931 85704 41387 85704 42932 85705 41387 85705 42934 85705 42934 85706 41387 85706 42933 85706 42934 85707 42933 85707 42935 85707 42935 85708 42933 85708 41385 85708 42935 85709 41385 85709 42936 85709 42936 85710 41385 85710 37483 85710 42936 85711 37483 85711 42937 85711 37499 85712 38161 85712 42938 85712 42938 85713 38161 85713 38162 85713 42938 85714 38162 85714 37497 85714 37497 85715 38162 85715 42939 85715 37497 85716 42939 85716 37496 85716 37496 85717 42939 85717 38165 85717 37496 85718 38165 85718 37494 85718 37494 85719 38165 85719 38168 85719 37494 85720 38168 85720 37493 85720 37493 85721 38168 85721 38169 85721 37493 85722 38169 85722 37492 85722 37492 85723 38169 85723 42940 85723 37492 85724 42940 85724 42941 85724 42941 85725 42940 85725 38171 85725 42941 85726 38171 85726 42942 85726 42942 85727 38171 85727 38172 85727 42942 85728 38172 85728 42943 85728 42943 85729 38172 85729 42944 85729 42943 85730 42944 85730 37489 85730 37489 85731 42944 85731 38173 85731 37489 85732 38173 85732 37487 85732 37487 85733 38173 85733 42945 85733 37487 85734 42945 85734 37485 85734 37485 85735 42945 85735 42946 85735 37485 85736 42946 85736 42947 85736 42947 85737 42946 85737 38177 85737 42947 85738 38177 85738 42937 85738 42937 85739 38177 85739 42948 85739 42937 85740 42948 85740 42936 85740 42936 85741 42948 85741 42949 85741 42936 85742 42949 85742 42935 85742 42949 85743 41246 85743 42935 85743 42935 85744 41246 85744 41247 85744 42935 85745 41247 85745 42934 85745 42934 85746 41247 85746 41248 85746 42934 85747 41248 85747 42932 85747 42932 85748 41248 85748 41250 85748 42932 85749 41250 85749 42950 85749 42950 85750 41250 85750 42951 85750 42950 85751 42951 85751 42929 85751 42929 85752 42951 85752 41251 85752 42929 85753 41251 85753 42952 85753 42952 85754 41251 85754 42953 85754 42952 85755 42953 85755 42928 85755 42928 85756 42953 85756 41253 85756 42928 85757 41253 85757 42927 85757 42927 85758 41253 85758 41255 85758 42927 85759 41255 85759 42954 85759 42954 85760 41255 85760 42955 85760 42954 85761 42955 85761 42956 85761 42956 85762 42955 85762 41258 85762 42956 85763 41258 85763 42957 85763 42957 85764 41258 85764 42958 85764 42957 85765 42958 85765 42924 85765 42924 85766 42958 85766 41260 85766 42924 85767 41260 85767 42959 85767 42959 85768 41260 85768 41262 85768 42959 85769 41262 85769 42960 85769 42960 85770 41262 85770 41264 85770 42960 85771 41264 85771 42961 85771 42961 85772 41264 85772 41265 85772 42961 85773 41265 85773 37500 85773 37500 85774 41265 85774 38159 85774 37500 85775 38159 85775 37499 85775 37499 85776 38159 85776 38160 85776 37499 85777 38160 85777 38161 85777 42981 85778 38158 85778 41263 85778 42981 85779 41263 85779 42962 85779 42962 85780 41263 85780 41261 85780 42962 85781 41261 85781 42963 85781 42963 85782 41261 85782 41259 85782 42963 85783 41259 85783 42979 85783 42979 85784 41259 85784 42964 85784 42979 85785 42964 85785 42976 85785 42976 85786 42964 85786 41257 85786 42976 85787 41257 85787 43014 85787 43014 85788 41257 85788 41256 85788 43014 85789 41256 85789 43013 85789 43013 85790 41256 85790 41254 85790 43013 85791 41254 85791 43011 85791 43011 85792 41254 85792 41252 85792 43011 85793 41252 85793 43010 85793 43010 85794 41252 85794 42965 85794 43010 85795 42965 85795 42966 85795 42966 85796 42965 85796 42968 85796 42966 85797 42968 85797 42967 85797 42967 85798 42968 85798 42969 85798 42967 85799 42969 85799 43007 85799 43007 85800 42969 85800 41249 85800 43007 85801 41249 85801 43005 85801 43005 85802 41249 85802 42970 85802 43005 85803 42970 85803 43004 85803 43004 85804 42970 85804 42971 85804 43004 85805 42971 85805 43003 85805 43003 85806 42971 85806 42972 85806 43003 85807 42972 85807 43001 85807 43001 85808 42972 85808 42973 85808 43001 85809 42973 85809 42974 85809 42974 85810 42973 85810 42975 85810 42974 85811 42975 85811 37467 85811 43014 85812 37386 85812 42976 85812 42976 85813 37386 85813 42977 85813 42976 85814 42977 85814 42979 85814 42979 85815 42977 85815 42978 85815 42979 85816 42978 85816 42963 85816 42963 85817 42978 85817 42980 85817 42963 85818 42980 85818 42962 85818 42962 85819 42980 85819 42982 85819 42962 85820 42982 85820 42981 85820 42981 85821 42982 85821 42983 85821 42981 85822 42983 85822 37481 85822 37481 85823 42983 85823 43169 85823 37481 85824 43169 85824 42984 85824 42984 85825 43169 85825 42986 85825 42984 85826 42986 85826 42985 85826 42985 85827 42986 85827 43171 85827 42985 85828 43171 85828 42987 85828 42987 85829 43171 85829 43172 85829 42987 85830 43172 85830 42988 85830 42988 85831 43172 85831 43174 85831 42988 85832 43174 85832 37477 85832 37477 85833 43174 85833 43175 85833 37477 85834 43175 85834 42989 85834 42989 85835 43175 85835 42990 85835 42989 85836 42990 85836 42991 85836 42991 85837 42990 85837 42992 85837 42991 85838 42992 85838 37475 85838 37475 85839 42992 85839 42993 85839 37475 85840 42993 85840 37474 85840 37474 85841 42993 85841 42994 85841 37474 85842 42994 85842 37473 85842 37473 85843 42994 85843 42996 85843 37473 85844 42996 85844 42995 85844 42995 85845 42996 85845 43178 85845 42995 85846 43178 85846 42997 85846 42997 85847 43178 85847 43180 85847 42997 85848 43180 85848 42998 85848 42998 85849 43180 85849 43181 85849 42998 85850 43181 85850 37470 85850 37470 85851 43181 85851 42999 85851 37470 85852 42999 85852 37468 85852 37468 85853 42999 85853 43183 85853 37468 85854 43183 85854 37467 85854 37467 85855 43183 85855 43000 85855 37467 85856 43000 85856 42974 85856 42974 85857 43000 85857 43002 85857 42974 85858 43002 85858 43001 85858 43001 85859 43002 85859 37374 85859 43001 85860 37374 85860 43003 85860 43003 85861 37374 85861 37376 85861 43003 85862 37376 85862 43004 85862 43004 85863 37376 85863 37378 85863 43004 85864 37378 85864 43005 85864 43005 85865 37378 85865 43006 85865 43005 85866 43006 85866 43007 85866 43007 85867 43006 85867 43008 85867 43007 85868 43008 85868 42967 85868 42967 85869 43008 85869 43009 85869 42967 85870 43009 85870 42966 85870 42966 85871 43009 85871 37381 85871 42966 85872 37381 85872 43010 85872 43010 85873 37381 85873 37383 85873 43010 85874 37383 85874 43011 85874 43011 85875 37383 85875 43012 85875 43011 85876 43012 85876 43013 85876 43013 85877 43012 85877 37385 85877 43013 85878 37385 85878 43014 85878 43014 85879 37385 85879 37386 85879 41369 85880 43051 85880 43015 85880 43015 85881 43051 85881 43057 85881 43015 85882 43057 85882 41372 85882 41372 85883 43057 85883 43059 85883 41372 85884 43059 85884 41373 85884 41373 85885 43059 85885 43016 85885 41373 85886 43016 85886 41375 85886 41375 85887 43016 85887 43060 85887 41375 85888 43060 85888 41376 85888 41376 85889 43060 85889 43017 85889 41376 85890 43017 85890 41377 85890 41377 85891 43017 85891 43062 85891 41377 85892 43062 85892 41380 85892 41380 85893 43062 85893 43018 85893 41380 85894 43018 85894 41381 85894 41381 85895 43018 85895 43019 85895 41381 85896 43019 85896 43020 85896 43020 85897 43019 85897 43064 85897 43020 85898 43064 85898 43021 85898 43021 85899 43064 85899 43022 85899 43021 85900 43022 85900 41382 85900 41382 85901 43022 85901 43065 85901 41382 85902 43065 85902 41384 85902 41384 85903 43065 85903 43023 85903 41384 85904 43023 85904 43024 85904 43024 85905 43023 85905 43025 85905 43024 85906 43025 85906 43026 85906 43026 85907 43025 85907 37451 85907 43026 85908 37451 85908 38058 85908 38058 85909 37451 85909 43028 85909 38058 85910 43028 85910 43027 85910 43027 85911 43028 85911 43029 85911 43027 85912 43029 85912 38061 85912 43029 85913 37453 85913 38061 85913 38061 85914 37453 85914 37454 85914 38061 85915 37454 85915 43030 85915 43030 85916 37454 85916 43031 85916 43030 85917 43031 85917 43032 85917 43032 85918 43031 85918 43033 85918 43032 85919 43033 85919 43034 85919 43034 85920 43033 85920 43035 85920 43034 85921 43035 85921 43036 85921 43036 85922 43035 85922 37457 85922 43036 85923 37457 85923 43037 85923 43037 85924 37457 85924 37458 85924 43037 85925 37458 85925 43038 85925 43038 85926 37458 85926 43039 85926 43038 85927 43039 85927 38067 85927 38067 85928 43039 85928 43040 85928 38067 85929 43040 85929 38068 85929 38068 85930 43040 85930 43041 85930 38068 85931 43041 85931 43042 85931 43042 85932 43041 85932 37461 85932 43042 85933 37461 85933 43043 85933 43043 85934 37461 85934 37463 85934 43043 85935 37463 85935 43044 85935 43044 85936 37463 85936 37466 85936 43044 85937 37466 85937 43045 85937 43045 85938 37466 85938 43052 85938 43045 85939 43052 85939 41365 85939 41365 85940 43052 85940 43046 85940 41365 85941 43046 85941 43047 85941 43047 85942 43046 85942 43053 85942 43047 85943 43053 85943 41368 85943 41368 85944 43053 85944 43054 85944 41368 85945 43054 85945 43048 85945 43048 85946 43054 85946 43049 85946 43048 85947 43049 85947 41369 85947 41369 85948 43049 85948 43050 85948 41369 85949 43050 85949 43051 85949 43052 85950 38087 85950 43046 85950 43046 85951 38087 85951 41343 85951 43046 85952 41343 85952 43053 85952 43053 85953 41343 85953 41345 85953 43053 85954 41345 85954 43054 85954 43054 85955 41345 85955 41346 85955 43054 85956 41346 85956 43049 85956 43049 85957 41346 85957 41348 85957 43049 85958 41348 85958 43050 85958 43050 85959 41348 85959 43055 85959 43050 85960 43055 85960 43051 85960 43051 85961 43055 85961 43056 85961 43051 85962 43056 85962 43057 85962 43057 85963 43056 85963 43058 85963 43057 85964 43058 85964 43059 85964 43059 85965 43058 85965 41351 85965 43059 85966 41351 85966 43016 85966 43016 85967 41351 85967 41352 85967 43016 85968 41352 85968 43060 85968 43060 85969 41352 85969 41355 85969 43060 85970 41355 85970 43017 85970 43017 85971 41355 85971 43061 85971 43017 85972 43061 85972 43062 85972 43062 85973 43061 85973 43063 85973 43062 85974 43063 85974 43018 85974 43018 85975 43063 85975 41357 85975 43018 85976 41357 85976 43019 85976 43019 85977 41357 85977 41358 85977 43019 85978 41358 85978 43064 85978 43064 85979 41358 85979 41361 85979 43064 85980 41361 85980 43022 85980 43022 85981 41361 85981 41362 85981 43022 85982 41362 85982 43065 85982 43065 85983 41362 85983 43066 85983 43065 85984 43066 85984 43023 85984 43023 85985 43066 85985 43067 85985 38078 85986 41330 85986 43068 85986 43068 85987 41330 85987 43069 85987 43068 85988 43069 85988 38079 85988 38079 85989 43069 85989 41332 85989 38079 85990 41332 85990 38082 85990 38082 85991 41332 85991 41335 85991 38082 85992 41335 85992 43070 85992 43070 85993 41335 85993 43071 85993 43070 85994 43071 85994 38084 85994 38084 85995 43071 85995 41336 85995 38084 85996 41336 85996 38085 85996 38085 85997 41336 85997 43072 85997 38085 85998 43072 85998 43073 85998 43073 85999 43072 85999 43074 85999 43073 86000 43074 86000 43075 86000 43075 86001 43074 86001 41338 86001 43075 86002 41338 86002 43076 86002 43076 86003 41338 86003 41339 86003 43076 86004 41339 86004 38088 86004 38088 86005 41339 86005 41341 86005 38088 86006 41341 86006 41344 86006 41344 86007 41341 86007 43077 86007 41344 86008 43077 86008 43078 86008 43078 86009 43077 86009 38091 86009 43078 86010 38091 86010 43079 86010 43079 86011 38091 86011 38092 86011 43079 86012 38092 86012 41347 86012 41347 86013 38092 86013 43081 86013 41347 86014 43081 86014 43080 86014 43080 86015 43081 86015 38093 86015 43080 86016 38093 86016 41349 86016 41349 86017 38093 86017 38094 86017 41349 86018 38094 86018 43082 86018 43082 86019 38094 86019 43083 86019 43082 86020 43083 86020 41350 86020 41350 86021 43083 86021 43084 86021 41350 86022 43084 86022 41353 86022 41353 86023 43084 86023 38097 86023 41353 86024 38097 86024 41354 86024 41354 86025 38097 86025 43085 86025 41354 86026 43085 86026 43086 86026 43086 86027 43085 86027 38100 86027 43086 86028 38100 86028 43087 86028 43087 86029 38100 86029 38101 86029 43087 86030 38101 86030 41356 86030 41356 86031 38101 86031 38102 86031 41356 86032 38102 86032 43088 86032 43088 86033 38102 86033 38103 86033 43088 86034 38103 86034 41359 86034 41359 86035 38103 86035 43089 86035 41359 86036 43089 86036 41360 86036 41360 86037 43089 86037 38104 86037 41360 86038 38104 86038 41363 86038 41363 86039 38104 86039 43090 86039 41363 86040 43090 86040 41364 86040 41364 86041 43090 86041 43091 86041 41364 86042 43091 86042 43092 86042 43092 86043 43091 86043 41320 86043 43092 86044 41320 86044 38072 86044 38072 86045 41320 86045 43093 86045 38072 86046 43093 86046 43094 86046 43094 86047 43093 86047 41322 86047 43094 86048 41322 86048 43095 86048 43095 86049 41322 86049 41324 86049 43095 86050 41324 86050 43096 86050 43096 86051 41324 86051 41326 86051 43096 86052 41326 86052 38076 86052 38076 86053 41326 86053 43097 86053 38076 86054 43097 86054 43099 86054 43099 86055 43097 86055 43098 86055 43099 86056 43098 86056 38078 86056 38078 86057 43098 86057 41330 86057 37630 86058 37632 86058 41342 86058 41342 86059 37632 86059 37633 86059 41342 86060 37633 86060 38089 86060 38089 86061 37633 86061 37638 86061 38089 86062 37638 86062 37450 86062 37630 86063 41342 86063 43100 86063 43100 86064 41342 86064 41340 86064 43100 86065 41340 86065 37557 86065 37553 86066 43101 86066 43104 86066 43104 86067 43101 86067 43102 86067 43104 86068 43102 86068 41340 86068 41340 86069 43102 86069 43103 86069 41340 86070 43103 86070 37557 86070 37553 86071 43104 86071 43105 86071 43105 86072 43104 86072 41337 86072 43105 86073 41337 86073 37551 86073 43108 86074 43106 86074 43107 86074 43108 86075 43107 86075 41337 86075 41337 86076 43107 86076 43109 86076 41337 86077 43109 86077 37551 86077 43110 86078 37548 86078 43111 86078 43110 86079 43111 86079 43108 86079 43108 86080 43111 86080 37549 86080 43108 86081 37549 86081 43106 86081 37542 86082 37544 86082 41334 86082 41334 86083 37544 86083 37545 86083 41334 86084 37545 86084 43110 86084 43110 86085 37545 86085 37547 86085 43110 86086 37547 86086 37548 86086 37542 86087 41334 86087 43112 86087 43112 86088 41334 86088 41333 86088 43112 86089 41333 86089 37540 86089 41331 86090 37538 86090 37539 86090 41331 86091 37539 86091 41333 86091 41333 86092 37539 86092 43113 86092 41333 86093 43113 86093 37540 86093 43115 86094 43114 86094 37535 86094 43115 86095 37535 86095 41331 86095 41331 86096 37535 86096 37537 86096 41331 86097 37537 86097 37538 86097 43116 86098 43117 86098 41329 86098 41329 86099 43117 86099 43118 86099 41329 86100 43118 86100 43115 86100 43115 86101 43118 86101 37533 86101 43115 86102 37533 86102 43114 86102 43116 86103 41329 86103 43119 86103 43119 86104 41329 86104 41328 86104 43119 86105 41328 86105 43122 86105 37529 86106 37530 86106 41327 86106 41327 86107 37530 86107 43120 86107 41327 86108 43120 86108 41328 86108 41328 86109 43120 86109 43121 86109 41328 86110 43121 86110 43122 86110 37529 86111 41327 86111 43123 86111 43123 86112 41327 86112 41325 86112 43123 86113 41325 86113 43124 86113 41323 86114 43129 86114 43125 86114 41323 86115 43125 86115 41325 86115 41325 86116 43125 86116 37526 86116 41325 86117 37526 86117 43124 86117 41321 86118 43126 86118 43127 86118 41321 86119 43127 86119 41323 86119 41323 86120 43127 86120 43128 86120 41323 86121 43128 86121 43129 86121 41319 86122 37521 86122 37522 86122 41319 86123 37522 86123 41321 86123 41321 86124 37522 86124 37524 86124 41321 86125 37524 86125 43126 86125 37413 86126 37518 86126 43130 86126 37413 86127 43130 86127 41319 86127 41319 86128 43130 86128 37520 86128 41319 86129 37520 86129 37521 86129 41316 86130 38143 86130 43131 86130 43131 86131 38143 86131 41277 86131 43131 86132 41277 86132 43132 86132 43132 86133 41277 86133 41280 86133 43132 86134 41280 86134 41313 86134 41313 86135 41280 86135 43133 86135 41313 86136 43133 86136 41312 86136 41312 86137 43133 86137 43134 86137 41312 86138 43134 86138 41310 86138 41310 86139 43134 86139 41283 86139 41310 86140 41283 86140 41309 86140 41309 86141 41283 86141 43135 86141 41309 86142 43135 86142 43136 86142 43136 86143 43135 86143 41287 86143 43136 86144 41287 86144 43137 86144 43137 86145 41287 86145 43138 86145 43137 86146 43138 86146 41306 86146 41306 86147 43138 86147 43139 86147 41306 86148 43139 86148 43140 86148 43140 86149 43139 86149 43141 86149 43140 86150 43141 86150 41304 86150 41304 86151 43141 86151 43142 86151 41304 86152 43142 86152 41303 86152 41303 86153 43142 86153 41291 86153 41303 86154 41291 86154 41301 86154 41301 86155 41291 86155 41292 86155 41301 86156 41292 86156 43143 86156 43143 86157 41292 86157 41295 86157 43143 86158 41295 86158 41298 86158 41298 86159 41295 86159 43144 86159 41298 86160 43144 86160 37398 86160 37398 86161 43144 86161 43145 86161 43146 86162 38070 86162 42355 86162 42355 86163 38070 86163 43147 86163 42355 86164 43147 86164 43149 86164 43149 86165 43147 86165 43148 86165 43149 86166 43148 86166 43150 86166 43150 86167 43148 86167 41366 86167 43150 86168 41366 86168 42353 86168 42353 86169 41366 86169 41367 86169 42353 86170 41367 86170 43151 86170 43151 86171 41367 86171 43152 86171 43151 86172 43152 86172 43153 86172 43153 86173 43152 86173 41370 86173 43153 86174 41370 86174 43154 86174 43154 86175 41370 86175 41371 86175 43154 86176 41371 86176 43155 86176 43155 86177 41371 86177 43156 86177 43155 86178 43156 86178 43157 86178 43157 86179 43156 86179 41374 86179 43157 86180 41374 86180 43158 86180 43158 86181 41374 86181 43159 86181 43158 86182 43159 86182 42351 86182 42351 86183 43159 86183 41378 86183 42351 86184 41378 86184 42350 86184 42350 86185 41378 86185 41379 86185 42350 86186 41379 86186 43161 86186 43161 86187 41379 86187 43160 86187 43161 86188 43160 86188 43162 86188 43162 86189 43160 86189 43163 86189 43162 86190 43163 86190 43164 86190 43164 86191 43163 86191 43165 86191 43164 86192 43165 86192 43166 86192 43166 86193 43165 86193 43167 86193 43166 86194 43167 86194 43168 86194 43168 86195 43167 86195 41383 86195 42983 86196 42330 86196 43169 86196 43169 86197 42330 86197 43170 86197 43169 86198 43170 86198 42986 86198 42986 86199 43170 86199 42332 86199 42986 86200 42332 86200 43171 86200 43171 86201 42332 86201 43173 86201 43171 86202 43173 86202 43172 86202 43172 86203 43173 86203 42335 86203 43172 86204 42335 86204 43174 86204 43174 86205 42335 86205 42336 86205 43174 86206 42336 86206 43175 86206 43175 86207 42336 86207 42338 86207 43175 86208 42338 86208 42990 86208 42990 86209 42338 86209 43176 86209 42990 86210 43176 86210 42992 86210 42992 86211 43176 86211 43177 86211 42992 86212 43177 86212 42993 86212 42993 86213 43177 86213 42341 86213 42993 86214 42341 86214 42994 86214 42994 86215 42341 86215 42342 86215 42994 86216 42342 86216 42996 86216 42996 86217 42342 86217 42344 86217 42996 86218 42344 86218 43178 86218 43178 86219 42344 86219 43179 86219 43178 86220 43179 86220 43180 86220 43180 86221 43179 86221 42345 86221 43180 86222 42345 86222 43181 86222 43181 86223 42345 86223 42346 86223 43181 86224 42346 86224 42999 86224 42999 86225 42346 86225 43182 86225 42999 86226 43182 86226 43183 86226 43183 86227 43182 86227 42347 86227 43183 86228 42347 86228 43000 86228 43000 86229 42347 86229 37372 86229 42008 86230 41931 86230 43184 86230 43184 86231 41931 86231 43185 86231 43185 86232 41930 86232 43184 86232 43184 86233 41930 86233 43186 86233 43184 86234 43186 86234 42011 86234 42011 86235 43186 86235 42013 86235 42013 86236 43186 86236 43193 86236 42013 86237 43193 86237 42014 86237 37967 86238 42260 86238 43187 86238 43187 86239 42260 86239 42273 86239 43187 86240 42273 86240 37969 86240 37969 86241 42273 86241 42272 86241 37969 86242 42272 86242 37972 86242 37972 86243 42272 86243 42266 86243 37972 86244 42266 86244 43188 86244 43188 86245 42266 86245 43190 86245 43188 86246 43190 86246 43189 86246 43189 86247 43190 86247 43191 86247 43189 86248 43191 86248 43192 86248 43192 86249 43191 86249 42262 86249 43192 86250 42262 86250 42008 86250 42008 86251 42262 86251 42261 86251 42008 86252 42261 86252 41931 86252 43193 86253 41926 86253 42014 86253 42014 86254 41926 86254 41925 86254 42014 86255 41925 86255 37967 86255 37967 86256 41925 86256 41929 86256 37967 86257 41929 86257 42260 86257 41059 86258 43194 86258 43196 86258 41059 86259 43196 86259 43195 86259 43195 86260 43196 86260 43197 86260 43195 86261 43197 86261 40763 86261 40763 86262 43197 86262 43198 86262 40763 86263 43198 86263 43199 86263 43199 86264 43198 86264 43377 86264 43199 86265 43377 86265 43200 86265 43200 86266 43377 86266 43384 86266 43200 86267 43384 86267 43201 86267 43201 86268 43384 86268 43375 86268 43201 86269 43375 86269 40761 86269 40761 86270 43375 86270 43203 86270 40761 86271 43203 86271 43202 86271 43202 86272 43203 86272 43204 86272 43202 86273 43204 86273 40759 86273 40759 86274 43204 86274 43205 86274 40759 86275 43205 86275 40757 86275 40757 86276 43205 86276 43206 86276 40757 86277 43206 86277 40756 86277 40756 86278 43206 86278 43388 86278 40756 86279 43388 86279 43207 86279 43207 86280 43388 86280 43208 86280 43207 86281 43208 86281 43209 86281 43209 86282 43208 86282 43372 86282 43209 86283 43372 86283 40753 86283 40753 86284 43372 86284 43211 86284 40753 86285 43211 86285 43210 86285 43210 86286 43211 86286 43212 86286 43210 86287 43212 86287 43213 86287 43213 86288 43212 86288 43214 86288 43213 86289 43214 86289 43216 86289 43216 86290 43214 86290 43215 86290 43216 86291 43215 86291 40751 86291 40750 86292 38187 86292 43409 86292 40750 86293 43409 86293 43217 86293 43217 86294 43409 86294 43412 86294 43217 86295 43412 86295 40749 86295 40749 86296 43412 86296 43404 86296 40749 86297 43404 86297 40748 86297 40748 86298 43404 86298 43218 86298 40748 86299 43218 86299 43219 86299 43219 86300 43218 86300 43414 86300 43219 86301 43414 86301 40747 86301 40747 86302 43414 86302 43401 86302 40747 86303 43401 86303 43220 86303 43220 86304 43401 86304 43221 86304 43220 86305 43221 86305 40745 86305 40745 86306 43221 86306 43222 86306 40745 86307 43222 86307 43223 86307 43223 86308 43222 86308 43224 86308 43223 86309 43224 86309 43225 86309 43225 86310 43224 86310 43226 86310 43225 86311 43226 86311 40742 86311 40742 86312 43226 86312 43227 86312 40742 86313 43227 86313 40741 86313 40741 86314 43227 86314 43399 86314 40741 86315 43399 86315 40740 86315 40740 86316 43399 86316 43228 86316 40740 86317 43228 86317 40738 86317 40738 86318 43228 86318 43397 86318 40738 86319 43397 86319 40736 86319 40736 86320 43397 86320 43229 86320 40736 86321 43229 86321 40735 86321 40735 86322 43229 86322 43422 86322 40735 86323 43422 86323 40734 86323 40734 86324 43422 86324 41226 86324 40734 86325 41226 86325 40732 86325 43230 86326 43379 86326 37255 86326 37255 86327 43379 86327 43378 86327 37255 86328 43378 86328 41179 86328 43231 86329 41536 86329 41227 86329 41227 86330 41536 86330 43338 86330 41227 86331 43338 86331 43232 86331 41851 86332 41670 86332 43370 86332 43370 86333 41670 86333 37331 86333 43370 86334 37331 86334 43233 86334 43234 86335 43407 86335 43235 86335 43235 86336 43407 86336 43406 86336 43235 86337 43406 86337 43236 86337 41158 86338 41156 86338 43257 86338 43237 86339 41159 86339 43238 86339 43238 86340 41159 86340 43239 86340 43238 86341 43239 86341 43240 86341 41158 86342 43257 86342 43240 86342 43240 86343 43257 86343 43235 86343 43240 86344 43235 86344 43238 86344 43238 86345 43235 86345 43236 86345 43238 86346 43236 86346 43237 86346 41156 86347 43241 86347 43257 86347 43257 86348 43241 86348 43246 86348 43257 86349 43246 86349 43244 86349 43242 86350 42762 86350 43243 86350 43243 86351 42762 86351 43244 86351 43243 86352 43244 86352 43245 86352 43245 86353 43244 86353 43246 86353 43251 86354 43247 86354 43250 86354 43250 86355 43247 86355 41614 86355 41614 86356 43248 86356 43250 86356 43250 86357 43248 86357 43249 86357 43250 86358 43249 86358 43251 86358 43251 86359 43249 86359 41610 86359 43363 86360 41637 86360 37593 86360 37593 86361 41637 86361 41636 86361 41636 86362 41635 86362 37593 86362 37593 86363 41635 86363 43252 86363 37593 86364 43252 86364 43253 86364 43253 86365 41625 86365 37593 86365 37593 86366 41625 86366 43254 86366 37593 86367 43254 86367 43256 86367 43254 86368 41627 86368 43256 86368 43256 86369 41627 86369 43255 86369 43256 86370 43255 86370 43257 86370 43257 86371 43255 86371 43258 86371 43257 86372 43258 86372 41630 86372 41630 86373 41631 86373 43257 86373 43257 86374 41631 86374 41622 86374 43257 86375 41622 86375 43235 86375 43235 86376 41622 86376 41623 86376 43235 86377 41623 86377 41624 86377 43259 86378 41652 86378 43260 86378 43260 86379 41652 86379 43261 86379 41624 86380 43259 86380 43235 86380 43235 86381 43259 86381 43260 86381 43235 86382 43260 86382 43234 86382 43234 86383 43260 86383 43261 86383 43234 86384 43261 86384 43262 86384 41566 86385 37587 86385 43263 86385 43263 86386 37587 86386 43275 86386 41562 86387 43264 86387 41563 86387 41563 86388 43264 86388 37587 86388 41563 86389 37587 86389 43265 86389 43265 86390 37587 86390 41566 86390 43357 86391 43266 86391 41559 86391 41559 86392 43266 86392 43264 86392 41559 86393 43264 86393 41561 86393 41561 86394 43264 86394 41562 86394 41556 86395 41557 86395 41603 86395 41603 86396 41557 86396 43267 86396 41596 86397 41594 86397 43269 86397 43269 86398 41594 86398 43268 86398 43267 86399 41596 86399 41603 86399 41603 86400 41596 86400 43269 86400 41603 86401 43269 86401 41589 86401 41589 86402 43269 86402 43268 86402 41589 86403 43268 86403 41591 86403 43270 86404 43271 86404 41548 86404 43271 86405 43270 86405 41542 86405 41547 86406 41545 86406 43272 86406 43356 86407 41571 86407 43355 86407 43355 86408 41571 86408 41570 86408 43355 86409 41570 86409 43273 86409 43273 86410 41570 86410 43274 86410 43273 86411 43274 86411 37587 86411 37587 86412 43274 86412 41568 86412 37587 86413 41568 86413 43275 86413 41495 86414 41494 86414 37584 86414 37584 86415 41494 86415 43276 86415 41491 86416 43353 86416 43277 86416 43277 86417 43353 86417 43276 86417 43277 86418 43276 86418 43278 86418 43278 86419 43276 86419 41494 86419 41490 86420 41488 86420 41537 86420 41537 86421 41488 86421 43279 86421 43280 86422 41529 86422 43281 86422 43281 86423 41529 86423 43282 86423 43279 86424 43280 86424 41537 86424 41537 86425 43280 86425 43281 86425 41537 86426 43281 86426 41526 86426 41526 86427 43281 86427 43282 86427 41526 86428 43282 86428 41527 86428 43286 86429 43283 86429 41477 86429 43283 86430 43286 86430 41467 86430 41476 86431 41474 86431 43284 86431 41501 86432 43352 86432 43285 86432 43285 86433 43352 86433 41467 86433 43285 86434 41467 86434 43284 86434 43284 86435 41467 86435 43286 86435 43284 86436 43286 86436 41476 86436 41476 86437 43286 86437 41477 86437 41501 86438 41503 86438 43352 86438 43352 86439 41503 86439 43287 86439 43352 86440 43287 86440 37583 86440 37583 86441 43287 86441 43288 86441 37583 86442 43288 86442 41489 86442 41489 86443 41500 86443 37583 86443 37583 86444 41500 86444 41498 86444 37583 86445 41498 86445 37584 86445 37584 86446 41498 86446 41497 86446 37584 86447 41497 86447 41495 86447 43305 86448 41426 86448 37579 86448 37579 86449 41426 86449 43350 86449 41425 86450 41424 86450 41463 86450 41463 86451 41424 86451 43289 86451 43290 86452 41458 86452 43291 86452 43291 86453 41458 86453 41455 86453 43289 86454 43290 86454 41463 86454 41463 86455 43290 86455 43291 86455 41463 86456 43291 86456 43292 86456 43292 86457 43291 86457 41455 86457 43292 86458 41455 86458 41454 86458 43293 86459 41404 86459 43294 86459 43294 86460 41404 86460 41412 86460 41412 86461 43295 86461 43294 86461 43294 86462 43295 86462 43296 86462 43294 86463 43296 86463 43293 86463 43293 86464 43296 86464 41409 86464 41418 86465 41436 86465 43348 86465 43348 86466 41436 86466 43297 86466 43297 86467 41435 86467 43348 86467 43348 86468 41435 86468 43298 86468 43348 86469 43298 86469 37577 86469 37577 86470 43298 86470 41428 86470 37577 86471 41428 86471 41433 86471 41433 86472 43299 86472 37577 86472 37577 86473 43299 86473 43300 86473 37577 86474 43300 86474 43304 86474 43304 86475 43300 86475 43301 86475 43301 86476 43302 86476 43304 86476 43304 86477 43302 86477 43303 86477 43304 86478 43303 86478 37579 86478 37579 86479 43303 86479 41429 86479 37579 86480 41429 86480 43305 86480 41407 86481 43306 86481 41402 86481 41402 86482 43306 86482 43307 86482 41402 86483 43307 86483 43308 86483 41449 86484 43309 86484 43346 86484 43346 86485 43309 86485 41420 86485 43346 86486 41420 86486 41407 86486 41407 86487 41420 86487 41421 86487 41407 86488 41421 86488 43306 86488 43306 86489 41421 86489 41416 86489 43306 86490 41416 86490 43307 86490 41452 86491 43343 86491 43310 86491 43310 86492 43343 86492 43311 86492 43311 86493 41461 86493 43310 86493 43310 86494 41461 86494 43312 86494 43310 86495 43312 86495 41452 86495 41452 86496 43312 86496 43313 86496 41451 86497 43314 86497 43315 86497 43315 86498 43314 86498 41438 86498 41438 86499 41440 86499 43315 86499 43315 86500 41440 86500 43316 86500 43315 86501 43316 86501 43317 86501 43317 86502 43316 86502 41441 86502 43317 86503 41441 86503 43318 86503 41444 86504 37570 86504 41443 86504 41443 86505 37570 86505 43317 86505 41443 86506 43317 86506 43319 86506 43319 86507 43317 86507 43318 86507 43322 86508 41536 86508 43320 86508 41536 86509 43322 86509 43338 86509 43323 86510 41533 86510 41534 86510 43321 86511 41510 86511 37562 86511 43321 86512 37562 86512 41508 86512 43320 86513 43323 86513 43322 86513 43322 86514 43323 86514 41534 86514 43322 86515 41534 86515 43338 86515 43338 86516 41534 86516 43324 86516 43338 86517 43324 86517 37562 86517 37562 86518 43324 86518 41507 86518 37562 86519 41507 86519 41508 86519 41510 86520 43325 86520 37562 86520 37562 86521 43325 86521 41512 86521 37562 86522 41512 86522 37563 86522 41518 86523 43326 86523 41516 86523 41516 86524 43326 86524 37563 86524 41516 86525 37563 86525 41515 86525 41515 86526 37563 86526 41512 86526 41518 86527 41520 86527 43326 86527 43326 86528 41520 86528 41521 86528 43326 86529 41521 86529 41524 86529 43327 86530 41486 86530 43340 86530 41487 86531 43328 86531 43329 86531 43329 86532 43328 86532 43330 86532 41486 86533 41487 86533 43340 86533 43340 86534 41487 86534 43329 86534 43340 86535 43329 86535 41479 86535 41479 86536 43329 86536 43330 86536 41479 86537 43330 86537 41480 86537 37559 86538 43331 86538 37560 86538 37560 86539 43331 86539 43332 86539 37560 86540 43332 86540 37562 86540 43332 86541 43333 86541 37562 86541 37562 86542 43333 86542 43334 86542 37562 86543 43334 86543 41168 86543 43338 86544 43335 86544 43232 86544 43232 86545 43335 86545 43336 86545 43232 86546 43336 86546 41162 86546 41168 86547 41169 86547 37562 86547 37562 86548 41169 86548 41165 86548 37562 86549 41165 86549 43338 86549 43338 86550 41165 86550 43337 86550 43338 86551 43337 86551 43335 86551 43335 86552 43337 86552 43339 86552 43335 86553 43339 86553 43336 86553 41524 86554 43327 86554 43326 86554 43326 86555 43327 86555 43340 86555 43326 86556 43340 86556 37565 86556 37565 86557 43340 86557 43341 86557 37565 86558 43341 86558 37566 86558 37566 86559 43341 86559 41470 86559 37566 86560 41470 86560 37567 86560 37567 86561 41470 86561 43342 86561 37567 86562 43342 86562 43315 86562 43315 86563 43342 86563 43343 86563 43315 86564 43343 86564 41451 86564 41451 86565 43343 86565 41452 86565 41444 86566 43344 86566 37570 86566 37570 86567 43344 86567 43345 86567 37570 86568 43345 86568 37571 86568 37571 86569 43345 86569 41449 86569 37571 86570 41449 86570 37573 86570 37573 86571 41449 86571 43346 86571 37573 86572 43346 86572 43347 86572 43347 86573 43346 86573 43349 86573 43347 86574 43349 86574 43348 86574 43348 86575 43349 86575 41404 86575 43348 86576 41404 86576 41418 86576 41418 86577 41404 86577 43293 86577 41426 86578 41425 86578 43350 86578 43350 86579 41425 86579 41463 86579 43350 86580 41463 86580 43351 86580 43351 86581 41463 86581 41469 86581 43351 86582 41469 86582 43352 86582 43352 86583 41469 86583 41468 86583 43352 86584 41468 86584 41467 86584 41491 86585 41490 86585 43353 86585 43353 86586 41490 86586 41537 86586 43353 86587 41537 86587 37586 86587 37586 86588 41537 86588 43354 86588 37586 86589 43354 86589 43355 86589 43355 86590 43354 86590 41540 86590 43355 86591 41540 86591 43356 86591 43356 86592 41540 86592 41542 86592 43356 86593 41542 86593 43272 86593 43272 86594 41542 86594 43270 86594 43272 86595 43270 86595 41547 86595 41547 86596 43270 86596 41548 86596 43357 86597 41556 86597 43266 86597 43266 86598 41556 86598 41603 86598 43266 86599 41603 86599 43358 86599 43358 86600 41603 86600 43359 86600 43358 86601 43359 86601 37591 86601 37591 86602 43359 86602 43360 86602 37591 86603 43360 86603 43361 86603 43361 86604 43360 86604 43362 86604 43361 86605 43362 86605 37593 86605 37593 86606 43362 86606 43247 86606 37593 86607 43247 86607 43363 86607 43363 86608 43247 86608 43251 86608 43364 86609 43365 86609 43205 86609 41922 86610 41921 86610 43366 86610 43367 86611 43368 86611 41725 86611 41851 86612 43370 86612 43369 86612 43369 86613 43370 86613 43215 86613 43369 86614 43215 86614 43394 86614 43394 86615 43215 86615 43214 86615 43367 86616 43211 86616 43372 86616 41799 86617 41792 86617 43371 86617 41797 86618 41799 86618 43208 86618 43208 86619 41799 86619 43371 86619 43208 86620 43371 86620 43372 86620 43372 86621 43371 86621 43373 86621 43372 86622 43373 86622 43367 86622 43390 86623 43388 86623 43206 86623 43365 86624 42276 86624 43205 86624 43205 86625 42276 86625 42275 86625 43205 86626 42275 86626 43206 86626 43206 86627 42275 86627 42274 86627 43206 86628 42274 86628 43390 86628 43376 86629 43204 86629 43203 86629 43374 86630 41935 86630 43375 86630 43375 86631 41935 86631 41829 86631 43375 86632 41829 86632 43203 86632 43203 86633 41829 86633 41832 86633 43203 86634 41832 86634 43376 86634 43383 86635 43384 86635 43377 86635 43383 86636 41666 86636 41664 86636 41606 86637 41616 86637 43198 86637 43198 86638 41616 86638 41827 86638 43198 86639 41827 86639 43377 86639 43377 86640 41827 86640 41826 86640 43377 86641 41826 86641 43383 86641 43378 86642 43379 86642 43194 86642 43194 86643 43379 86643 43380 86643 43194 86644 43380 86644 43196 86644 43380 86645 41922 86645 43196 86645 43196 86646 41922 86646 43366 86646 43196 86647 43366 86647 43197 86647 43366 86648 43381 86648 43197 86648 43197 86649 43381 86649 43382 86649 43197 86650 43382 86650 43198 86650 43198 86651 43382 86651 41608 86651 43198 86652 41608 86652 41606 86652 43383 86653 41664 86653 43384 86653 43384 86654 41664 86654 43385 86654 43384 86655 43385 86655 43375 86655 43375 86656 43385 86656 41663 86656 43375 86657 41663 86657 43374 86657 43364 86658 43205 86658 43386 86658 43386 86659 43205 86659 43204 86659 43386 86660 43204 86660 43387 86660 43387 86661 43204 86661 43376 86661 43387 86662 43376 86662 41727 86662 41797 86663 43208 86663 41795 86663 41795 86664 43208 86664 43388 86664 41795 86665 43388 86665 43389 86665 43389 86666 43388 86666 43390 86666 43389 86667 43390 86667 42291 86667 43367 86668 41725 86668 43211 86668 43211 86669 41725 86669 43391 86669 43211 86670 43391 86670 43212 86670 43392 86671 43394 86671 43393 86671 43393 86672 43394 86672 43214 86672 43393 86673 43214 86673 41722 86673 41722 86674 43214 86674 43212 86674 41722 86675 43212 86675 43395 86675 43395 86676 43212 86676 43391 86676 43408 86677 41615 86677 43410 86677 41898 86678 41897 86678 41472 86678 43231 86679 41227 86679 43396 86679 43396 86680 41227 86680 41226 86680 43396 86681 41226 86681 43420 86681 43420 86682 41226 86682 43422 86682 41898 86683 43397 86683 43228 86683 41406 86684 41414 86684 43398 86684 41405 86685 41406 86685 43399 86685 43399 86686 41406 86686 43398 86686 43399 86687 43398 86687 43228 86687 43228 86688 43398 86688 41820 86688 43228 86689 41820 86689 41898 86689 43227 86690 43226 86690 41888 86690 41888 86691 43226 86691 41816 86691 41816 86692 43226 86692 41815 86692 41815 86693 43226 86693 43224 86693 41815 86694 43224 86694 41878 86694 41465 86695 41466 86695 43400 86695 43400 86696 41466 86696 43222 86696 43400 86697 43222 86697 43221 86697 41539 86698 41538 86698 43401 86698 43401 86699 41538 86699 43402 86699 43401 86700 43402 86700 43221 86700 43221 86701 43402 86701 41814 86701 43221 86702 41814 86702 43400 86702 43405 86703 43414 86703 43218 86703 43405 86704 41544 86704 41543 86704 41602 86705 43403 86705 43404 86705 43404 86706 43403 86706 41858 86706 43404 86707 41858 86707 43218 86707 43218 86708 41858 86708 41809 86708 43218 86709 41809 86709 43405 86709 43406 86710 43407 86710 38187 86710 38187 86711 43407 86711 41805 86711 38187 86712 41805 86712 43409 86712 41805 86713 43408 86713 43409 86713 43409 86714 43408 86714 43410 86714 43409 86715 43410 86715 43412 86715 43410 86716 43411 86716 43412 86716 43412 86717 43411 86717 43413 86717 43412 86718 43413 86718 43404 86718 43404 86719 43413 86719 41604 86719 43404 86720 41604 86720 41602 86720 43405 86721 41543 86721 43414 86721 43414 86722 41543 86722 41541 86722 43414 86723 41541 86723 43401 86723 43401 86724 41541 86724 43415 86724 43401 86725 43415 86725 41539 86725 41466 86726 43416 86726 43222 86726 43222 86727 43416 86727 43417 86727 43222 86728 43417 86728 43224 86728 43224 86729 43417 86729 41464 86729 43224 86730 41464 86730 41878 86730 41405 86731 43399 86731 41403 86731 41403 86732 43399 86732 43227 86732 41403 86733 43227 86733 43418 86733 43418 86734 43227 86734 41888 86734 43418 86735 41888 86735 41413 86735 41898 86736 41472 86736 43397 86736 43397 86737 41472 86737 43424 86737 43397 86738 43424 86738 43229 86738 43419 86739 43420 86739 43421 86739 43421 86740 43420 86740 43422 86740 43421 86741 43422 86741 43423 86741 43423 86742 43422 86742 43229 86742 43423 86743 43229 86743 41471 86743 41471 86744 43229 86744 43424 86744 43425 86745 43432 86745 43431 86745 40289 86746 43427 86746 43426 86746 43426 86747 43427 86747 43428 86747 43428 86748 43427 86748 40290 86748 43428 86749 40290 86749 43433 86749 40305 86750 43429 86750 43437 86750 43437 86751 43429 86751 43431 86751 43437 86752 43431 86752 43430 86752 43430 86753 43431 86753 43432 86753 43430 86754 43432 86754 40287 86754 40287 86755 43432 86755 38329 86755 40287 86756 38329 86756 40286 86756 40286 86757 38329 86757 43433 86757 40286 86758 43433 86758 43434 86758 43434 86759 43433 86759 40290 86759 40917 86760 43435 86760 40289 86760 40306 86761 40305 86761 43436 86761 43436 86762 40305 86762 43437 86762 43436 86763 43437 86763 40922 86763 40922 86764 43437 86764 40285 86764 43431 86765 43438 86765 43425 86765 43425 86766 43438 86766 40304 86766 43425 86767 40304 86767 43439 86767 43439 86768 40304 86768 40297 86768 43439 86769 40297 86769 43440 86769 43440 86770 40297 86770 43441 86770 43441 86771 40297 86771 40298 86771 43441 86772 40298 86772 43442 86772 43442 86773 40298 86773 40299 86773 43442 86774 40299 86774 38325 86774 38325 86775 40299 86775 40300 86775 38325 86776 40300 86776 40912 86776 40912 86777 40300 86777 43444 86777 40912 86778 43444 86778 43443 86778 43443 86779 43444 86779 43445 86779 43443 86780 43445 86780 43446 86780 43446 86781 43445 86781 43447 86781 43446 86782 43447 86782 40910 86782 40910 86783 43447 86783 38630 86783 40910 86784 38630 86784 40909 86784 40909 86785 38630 86785 38631 86785 40909 86786 38631 86786 43448 86786 40917 86787 40289 86787 40918 86787 40918 86788 40289 86788 43466 86788 40918 86789 43466 86789 40293 86789 43448 86790 38631 86790 40906 86790 40906 86791 38631 86791 38633 86791 40906 86792 38633 86792 40903 86792 40903 86793 38633 86793 38634 86793 40903 86794 38634 86794 43449 86794 43449 86795 38634 86795 43450 86795 43449 86796 43450 86796 40901 86796 40901 86797 43450 86797 38635 86797 40901 86798 38635 86798 40900 86798 40900 86799 38635 86799 43451 86799 40900 86800 43451 86800 40899 86800 40899 86801 43451 86801 38638 86801 40899 86802 38638 86802 40898 86802 40898 86803 38638 86803 38639 86803 40898 86804 38639 86804 43452 86804 43452 86805 38639 86805 43453 86805 43452 86806 43453 86806 40897 86806 40897 86807 43453 86807 40896 86807 40896 86808 43453 86808 43454 86808 40896 86809 43454 86809 40894 86809 40894 86810 43454 86810 38641 86810 40894 86811 38641 86811 43455 86811 43455 86812 38641 86812 38643 86812 43455 86813 38643 86813 43456 86813 43456 86814 38643 86814 38624 86814 43456 86815 38624 86815 38338 86815 38338 86816 38624 86816 43457 86816 38338 86817 43457 86817 38336 86817 38336 86818 43457 86818 43458 86818 38336 86819 43458 86819 43460 86819 43460 86820 43458 86820 43459 86820 43460 86821 43459 86821 43461 86821 43461 86822 43459 86822 43462 86822 43461 86823 43462 86823 38334 86823 38334 86824 43462 86824 43463 86824 38334 86825 43463 86825 38332 86825 38332 86826 43463 86826 43464 86826 38332 86827 43464 86827 43426 86827 43426 86828 43464 86828 40295 86828 43426 86829 40295 86829 40289 86829 40289 86830 40295 86830 43465 86830 40289 86831 43465 86831 43466 86831 43470 86832 37236 86832 43473 86832 43474 86833 43475 86833 43470 86833 43472 86834 43471 86834 43470 86834 43467 86835 43468 86835 43470 86835 43477 86836 43478 86836 43470 86836 43470 86837 43469 86837 43482 86837 43480 86838 43469 86838 43470 86838 43478 86839 43480 86839 43470 86839 43468 86840 43477 86840 43470 86840 43471 86841 43467 86841 43470 86841 43475 86842 43472 86842 43470 86842 43473 86843 43474 86843 43470 86843 37236 86844 37235 86844 43473 86844 43473 86845 37235 86845 43488 86845 43473 86846 43488 86846 43474 86846 43474 86847 43488 86847 43475 86847 43475 86848 43488 86848 43490 86848 43475 86849 43490 86849 43472 86849 43472 86850 43490 86850 43471 86850 43471 86851 43490 86851 43491 86851 43471 86852 43491 86852 43467 86852 43467 86853 43491 86853 43468 86853 43468 86854 43491 86854 43476 86854 43468 86855 43476 86855 43477 86855 43477 86856 43476 86856 43478 86856 43478 86857 43476 86857 43479 86857 43478 86858 43479 86858 43480 86858 43480 86859 43479 86859 43469 86859 43469 86860 43479 86860 43481 86860 43469 86861 43481 86861 43482 86861 38872 86862 43483 86862 43484 86862 43484 86863 43483 86863 43485 86863 43484 86864 43485 86864 37233 86864 37233 86865 43485 86865 43486 86865 37233 86866 43486 86866 37234 86866 37234 86867 43486 86867 38877 86867 37234 86868 38877 86868 37235 86868 37235 86869 38877 86869 43487 86869 37235 86870 43487 86870 43488 86870 43488 86871 43487 86871 43489 86871 43488 86872 43489 86872 43490 86872 43490 86873 43489 86873 39959 86873 43490 86874 39959 86874 43491 86874 43491 86875 39959 86875 43492 86875 43491 86876 43492 86876 43476 86876 43476 86877 43492 86877 43493 86877 43476 86878 43493 86878 43479 86878 43479 86879 43493 86879 43494 86879 43479 86880 43494 86880 43481 86880 43481 86881 43494 86881 39956 86881 43481 86882 39956 86882 37230 86882 37230 86883 39956 86883 43495 86883 37230 86884 43495 86884 43496 86884 43496 86885 43495 86885 38872 86885 43496 86886 38872 86886 43484 86886 43498 86887 37224 86887 43501 86887 43497 86888 43502 86888 43498 86888 43504 86889 43506 86889 43498 86889 43507 86890 43508 86890 43498 86890 43510 86891 43511 86891 43498 86891 43498 86892 43512 86892 37225 86892 43499 86893 43512 86893 43498 86893 43511 86894 43499 86894 43498 86894 43508 86895 43510 86895 43498 86895 43506 86896 43507 86896 43498 86896 43502 86897 43504 86897 43498 86897 43501 86898 43497 86898 43498 86898 37224 86899 43515 86899 43501 86899 43501 86900 43515 86900 43500 86900 43501 86901 43500 86901 43497 86901 43497 86902 43500 86902 43502 86902 43502 86903 43500 86903 43503 86903 43502 86904 43503 86904 43504 86904 43504 86905 43503 86905 43506 86905 43506 86906 43503 86906 43505 86906 43506 86907 43505 86907 43507 86907 43507 86908 43505 86908 43508 86908 43508 86909 43505 86909 43509 86909 43508 86910 43509 86910 43510 86910 43510 86911 43509 86911 43511 86911 43511 86912 43509 86912 43518 86912 43511 86913 43518 86913 43499 86913 43499 86914 43518 86914 43512 86914 43512 86915 43518 86915 43513 86915 43512 86916 43513 86916 37225 86916 43514 86917 43523 86917 43515 86917 43515 86918 43523 86918 43516 86918 43515 86919 43516 86919 43500 86919 43500 86920 43516 86920 39947 86920 43500 86921 39947 86921 43503 86921 43503 86922 39947 86922 39945 86922 43503 86923 39945 86923 43505 86923 43505 86924 39945 86924 43517 86924 43505 86925 43517 86925 43509 86925 43509 86926 43517 86926 39942 86926 43509 86927 39942 86927 43518 86927 43518 86928 39942 86928 39940 86928 43518 86929 39940 86929 43513 86929 43513 86930 39940 86930 43519 86930 43513 86931 43519 86931 43520 86931 43520 86932 43519 86932 43521 86932 43520 86933 43521 86933 37214 86933 37214 86934 43521 86934 38908 86934 37214 86935 38908 86935 37217 86935 37217 86936 38908 86936 43522 86936 37217 86937 43522 86937 37220 86937 37220 86938 43522 86938 38910 86938 37220 86939 38910 86939 37222 86939 37222 86940 38910 86940 38911 86940 37222 86941 38911 86941 43514 86941 43514 86942 38911 86942 43523 86942 43527 86943 43532 86943 43524 86943 43525 86944 43526 86944 43527 86944 43530 86945 43535 86945 43527 86945 43536 86946 43537 86946 43527 86946 43527 86947 43528 86947 37197 86947 43529 86948 43528 86948 43527 86948 43537 86949 43529 86949 43527 86949 43535 86950 43536 86950 43527 86950 43526 86951 43530 86951 43527 86951 43524 86952 43525 86952 43527 86952 43532 86953 43531 86953 43533 86953 43532 86954 43533 86954 43524 86954 43524 86955 43533 86955 43534 86955 43524 86956 43534 86956 43525 86956 43525 86957 43534 86957 43526 86957 43526 86958 43534 86958 43541 86958 43526 86959 43541 86959 43530 86959 43530 86960 43541 86960 43535 86960 43535 86961 43541 86961 43540 86961 43535 86962 43540 86962 43536 86962 43536 86963 43540 86963 43537 86963 43537 86964 43540 86964 43538 86964 43537 86965 43538 86965 43529 86965 43529 86966 43538 86966 43539 86966 43529 86967 43539 86967 43528 86967 43528 86968 43539 86968 43550 86968 43528 86969 43550 86969 37197 86969 43538 86970 43540 86970 43552 86970 43552 86971 43540 86971 43541 86971 43552 86972 43541 86972 43542 86972 43542 86973 43541 86973 43534 86973 43542 86974 43534 86974 43543 86974 43543 86975 43534 86975 43533 86975 43543 86976 43533 86976 43544 86976 43544 86977 43533 86977 43531 86977 43544 86978 43531 86978 43545 86978 43545 86979 43531 86979 37206 86979 43545 86980 37206 86980 43546 86980 43546 86981 37206 86981 37204 86981 43546 86982 37204 86982 43547 86982 43547 86983 37204 86983 37202 86983 43547 86984 37202 86984 38931 86984 38931 86985 37202 86985 37201 86985 38931 86986 37201 86986 43548 86986 43548 86987 37201 86987 37199 86987 43548 86988 37199 86988 43549 86988 43549 86989 37199 86989 43550 86989 43549 86990 43550 86990 39925 86990 39925 86991 43550 86991 43539 86991 39925 86992 43539 86992 43551 86992 43551 86993 43539 86993 43538 86993 43551 86994 43538 86994 43552 86994 43556 86995 43553 86995 43559 86995 43554 86996 43553 86996 43556 86996 37192 86997 43554 86997 43556 86997 43556 86998 43555 86998 43560 86998 43557 86999 43555 86999 43556 86999 43559 87000 43557 87000 43556 87000 37192 87001 37194 87001 43554 87001 43554 87002 37194 87002 43563 87002 43554 87003 43563 87003 43553 87003 43553 87004 43563 87004 43558 87004 43553 87005 43558 87005 43559 87005 43559 87006 43558 87006 43572 87006 43559 87007 43572 87007 43557 87007 43557 87008 43572 87008 43570 87008 43557 87009 43570 87009 43555 87009 43555 87010 43570 87010 43569 87010 43555 87011 43569 87011 43560 87011 43560 87012 43569 87012 37182 87012 43572 87013 43558 87013 43561 87013 43561 87014 43558 87014 43562 87014 43562 87015 43558 87015 43563 87015 43562 87016 43563 87016 38952 87016 38952 87017 43563 87017 37194 87017 38952 87018 37194 87018 43564 87018 43564 87019 37194 87019 37193 87019 43564 87020 37193 87020 38951 87020 38951 87021 37193 87021 37191 87021 38951 87022 37191 87022 38949 87022 37191 87023 37189 87023 38949 87023 38949 87024 37189 87024 37188 87024 38949 87025 37188 87025 43565 87025 43565 87026 37188 87026 37186 87026 43565 87027 37186 87027 43566 87027 43566 87028 37186 87028 37184 87028 43566 87029 37184 87029 43567 87029 43567 87030 37184 87030 37182 87030 43567 87031 37182 87031 43568 87031 43568 87032 37182 87032 43569 87032 43568 87033 43569 87033 39903 87033 39903 87034 43569 87034 43570 87034 39903 87035 43570 87035 43571 87035 43571 87036 43570 87036 43572 87036 43571 87037 43572 87037 43573 87037 43573 87038 43572 87038 43561 87038 43576 87039 43580 87039 43581 87039 43574 87040 43582 87040 43576 87040 43579 87041 43578 87041 43576 87041 43583 87042 43584 87042 43576 87042 43586 87043 43577 87043 43576 87043 43576 87044 43588 87044 43575 87044 43587 87045 43588 87045 43576 87045 43577 87046 43587 87046 43576 87046 43584 87047 43586 87047 43576 87047 43578 87048 43583 87048 43576 87048 43582 87049 43579 87049 43576 87049 43581 87050 43574 87050 43576 87050 43580 87051 43595 87051 43581 87051 43581 87052 43595 87052 43596 87052 43581 87053 43596 87053 43574 87053 43574 87054 43596 87054 43582 87054 43582 87055 43596 87055 43597 87055 43582 87056 43597 87056 43579 87056 43579 87057 43597 87057 43578 87057 43578 87058 43597 87058 43585 87058 43578 87059 43585 87059 43583 87059 43583 87060 43585 87060 43584 87060 43584 87061 43585 87061 43599 87061 43584 87062 43599 87062 43586 87062 43586 87063 43599 87063 43577 87063 43577 87064 43599 87064 43600 87064 43577 87065 43600 87065 43587 87065 43587 87066 43600 87066 43588 87066 43588 87067 43600 87067 43589 87067 43588 87068 43589 87068 43575 87068 38968 87069 43590 87069 37179 87069 37179 87070 43590 87070 38971 87070 37179 87071 38971 87071 43591 87071 43591 87072 38971 87072 43592 87072 43591 87073 43592 87073 43593 87073 43593 87074 43592 87074 43594 87074 43593 87075 43594 87075 43595 87075 43595 87076 43594 87076 39878 87076 43595 87077 39878 87077 43596 87077 43596 87078 39878 87078 39877 87078 43596 87079 39877 87079 43597 87079 43597 87080 39877 87080 43598 87080 43597 87081 43598 87081 43585 87081 43585 87082 43598 87082 39874 87082 43585 87083 39874 87083 43599 87083 43599 87084 39874 87084 39872 87084 43599 87085 39872 87085 43600 87085 43600 87086 39872 87086 39870 87086 43600 87087 39870 87087 43589 87087 43589 87088 39870 87088 39868 87088 43589 87089 39868 87089 43601 87089 43601 87090 39868 87090 43602 87090 43601 87091 43602 87091 37177 87091 37177 87092 43602 87092 38968 87092 37177 87093 38968 87093 37179 87093 37174 87094 43603 87094 43608 87094 43606 87095 43603 87095 37174 87095 37169 87096 43606 87096 37174 87096 37174 87097 43609 87097 43604 87097 43605 87098 43609 87098 37174 87098 43608 87099 43605 87099 37174 87099 37169 87100 37170 87100 43606 87100 43606 87101 37170 87101 43613 87101 43606 87102 43613 87102 43603 87102 43603 87103 43613 87103 43607 87103 43603 87104 43607 87104 43608 87104 43608 87105 43607 87105 43616 87105 43608 87106 43616 87106 43605 87106 43605 87107 43616 87107 43619 87107 43605 87108 43619 87108 43609 87108 43609 87109 43619 87109 43620 87109 43609 87110 43620 87110 43604 87110 43604 87111 43620 87111 43621 87111 43616 87112 43607 87112 43610 87112 43610 87113 43607 87113 43611 87113 43611 87114 43607 87114 43613 87114 43611 87115 43613 87115 43612 87115 43612 87116 43613 87116 37170 87116 43612 87117 37170 87117 38997 87117 38997 87118 37170 87118 43614 87118 38997 87119 43614 87119 43615 87119 43615 87120 43614 87120 43627 87120 43615 87121 43627 87121 38996 87121 43610 87122 43617 87122 43616 87122 43616 87123 43617 87123 43618 87123 43616 87124 43618 87124 43619 87124 43619 87125 43618 87125 39846 87125 43619 87126 39846 87126 43620 87126 43620 87127 39846 87127 43622 87127 43620 87128 43622 87128 43621 87128 43621 87129 43622 87129 43623 87129 43621 87130 43623 87130 37163 87130 37163 87131 43623 87131 43624 87131 37163 87132 43624 87132 37166 87132 37166 87133 43624 87133 43625 87133 37166 87134 43625 87134 43626 87134 43626 87135 43625 87135 38996 87135 43626 87136 38996 87136 37167 87136 37167 87137 38996 87137 43627 87137 43628 87138 43629 87138 43634 87138 43636 87139 43637 87139 43628 87139 43638 87140 43639 87140 43628 87140 43633 87141 43641 87141 43628 87141 43642 87142 43631 87142 43628 87142 43628 87143 43644 87143 43630 87143 43632 87144 43644 87144 43628 87144 43631 87145 43632 87145 43628 87145 43641 87146 43642 87146 43628 87146 43639 87147 43633 87147 43628 87147 43637 87148 43638 87148 43628 87148 43634 87149 43636 87149 43628 87149 43629 87150 43656 87150 43634 87150 43634 87151 43656 87151 43635 87151 43634 87152 43635 87152 43636 87152 43636 87153 43635 87153 43637 87153 43637 87154 43635 87154 43657 87154 43637 87155 43657 87155 43638 87155 43638 87156 43657 87156 43639 87156 43639 87157 43657 87157 43640 87157 43639 87158 43640 87158 43633 87158 43633 87159 43640 87159 43641 87159 43641 87160 43640 87160 43648 87160 43641 87161 43648 87161 43642 87161 43642 87162 43648 87162 43631 87162 43631 87163 43648 87163 43650 87163 43631 87164 43650 87164 43632 87164 43632 87165 43650 87165 43644 87165 43644 87166 43650 87166 43643 87166 43644 87167 43643 87167 43630 87167 43645 87168 43646 87168 43640 87168 43640 87169 43646 87169 43647 87169 43640 87170 43647 87170 43648 87170 43648 87171 43647 87171 39828 87171 43648 87172 39828 87172 43650 87172 43650 87173 39828 87173 43649 87173 43650 87174 43649 87174 43643 87174 43643 87175 43649 87175 43651 87175 43643 87176 43651 87176 37155 87176 37155 87177 43651 87177 39019 87177 37155 87178 39019 87178 37158 87178 37158 87179 39019 87179 39018 87179 37158 87180 39018 87180 37159 87180 37159 87181 39018 87181 43652 87181 37159 87182 43652 87182 37161 87182 37161 87183 43652 87183 39017 87183 37161 87184 39017 87184 43653 87184 43653 87185 39017 87185 43654 87185 43653 87186 43654 87186 43656 87186 43656 87187 43654 87187 43655 87187 43656 87188 43655 87188 43635 87188 43635 87189 43655 87189 39823 87189 43635 87190 39823 87190 43657 87190 43657 87191 39823 87191 43645 87191 43657 87192 43645 87192 43640 87192 43658 87193 37149 87193 43660 87193 43658 87194 43663 87194 43665 87194 43662 87195 43663 87195 43658 87195 43660 87196 43662 87196 43658 87196 43658 87197 43659 87197 37152 87197 43667 87198 43659 87198 43658 87198 43665 87199 43667 87199 43658 87199 37149 87200 43680 87200 43660 87200 43660 87201 43680 87201 43661 87201 43660 87202 43661 87202 43662 87202 43662 87203 43661 87203 43683 87203 43662 87204 43683 87204 43663 87204 43663 87205 43683 87205 43664 87205 43663 87206 43664 87206 43665 87206 43665 87207 43664 87207 43666 87207 43665 87208 43666 87208 43667 87208 43667 87209 43666 87209 43668 87209 43667 87210 43668 87210 43659 87210 43659 87211 43668 87211 43669 87211 43659 87212 43669 87212 37152 87212 37152 87213 43669 87213 43670 87213 43673 87214 37147 87214 39038 87214 39038 87215 37147 87215 39036 87215 39036 87216 37147 87216 37145 87216 39036 87217 37145 87217 39805 87217 39805 87218 37145 87218 43670 87218 39805 87219 43670 87219 43671 87219 43671 87220 43670 87220 43669 87220 43671 87221 43669 87221 43672 87221 43672 87222 43669 87222 43668 87222 43672 87223 43668 87223 39808 87223 39038 87224 43674 87224 43673 87224 43673 87225 43674 87225 43675 87225 43673 87226 43675 87226 43676 87226 43676 87227 43675 87227 43677 87227 43676 87228 43677 87228 43678 87228 43678 87229 43677 87229 43679 87229 43678 87230 43679 87230 43680 87230 43680 87231 43679 87231 43681 87231 43680 87232 43681 87232 43661 87232 43661 87233 43681 87233 43682 87233 43661 87234 43682 87234 43683 87234 43683 87235 43682 87235 39809 87235 43683 87236 39809 87236 43664 87236 43664 87237 39809 87237 39808 87237 43664 87238 39808 87238 43666 87238 43666 87239 39808 87239 43668 87239 37144 87240 43684 87240 43690 87240 43685 87241 43684 87241 37144 87241 43687 87242 43685 87242 37144 87242 37144 87243 43686 87243 37133 87243 43691 87244 43686 87244 37144 87244 43690 87245 43691 87245 37144 87245 43687 87246 43694 87246 43685 87246 43685 87247 43694 87247 43688 87247 43685 87248 43688 87248 43684 87248 43684 87249 43688 87249 43689 87249 43684 87250 43689 87250 43690 87250 43690 87251 43689 87251 43699 87251 43690 87252 43699 87252 43691 87252 43691 87253 43699 87253 43692 87253 43691 87254 43692 87254 43686 87254 43686 87255 43692 87255 43693 87255 43686 87256 43693 87256 37133 87256 37133 87257 43693 87257 37134 87257 43699 87258 43689 87258 39777 87258 39777 87259 43689 87259 39776 87259 39776 87260 43689 87260 43688 87260 39776 87261 43688 87261 39065 87261 39065 87262 43688 87262 43694 87262 39065 87263 43694 87263 39067 87263 39067 87264 43694 87264 43695 87264 39067 87265 43695 87265 39068 87265 39068 87266 43695 87266 37139 87266 39068 87267 37139 87267 39062 87267 37139 87268 43696 87268 39062 87268 39062 87269 43696 87269 37138 87269 39062 87270 37138 87270 39060 87270 39060 87271 37138 87271 43697 87271 39060 87272 43697 87272 39058 87272 39058 87273 43697 87273 37135 87273 39058 87274 37135 87274 39785 87274 39785 87275 37135 87275 37134 87275 39785 87276 37134 87276 39786 87276 39786 87277 37134 87277 43693 87277 39786 87278 43693 87278 39782 87278 39782 87279 43693 87279 43692 87279 39782 87280 43692 87280 43698 87280 43698 87281 43692 87281 43699 87281 43698 87282 43699 87282 39781 87282 39781 87283 43699 87283 39777 87283 43715 87284 43721 87284 43700 87284 43700 87285 43721 87285 43719 87285 43700 87286 43719 87286 39754 87286 39754 87287 43719 87287 43701 87287 39754 87288 43701 87288 43703 87288 43703 87289 43701 87289 43702 87289 43703 87290 43702 87290 43704 87290 43704 87291 43702 87291 43716 87291 43704 87292 43716 87292 43705 87292 43705 87293 43716 87293 43706 87293 43705 87294 43706 87294 43707 87294 43707 87295 43706 87295 43708 87295 43707 87296 43708 87296 43709 87296 43709 87297 43708 87297 37131 87297 43709 87298 37131 87298 43710 87298 43710 87299 37131 87299 37127 87299 43710 87300 37127 87300 39085 87300 39085 87301 37127 87301 37125 87301 39085 87302 37125 87302 43711 87302 43711 87303 37125 87303 43712 87303 43711 87304 43712 87304 43713 87304 43713 87305 43712 87305 43714 87305 43713 87306 43714 87306 39760 87306 39760 87307 43714 87307 43715 87307 39760 87308 43715 87308 43700 87308 37119 87309 43716 87309 43702 87309 37119 87310 43702 87310 43727 87310 43727 87311 43702 87311 43701 87311 43727 87312 43701 87312 43717 87312 43717 87313 43701 87313 43718 87313 43718 87314 43701 87314 43719 87314 43718 87315 43719 87315 43724 87315 43724 87316 43719 87316 43720 87316 43720 87317 43719 87317 43721 87317 43720 87318 43721 87318 43725 87318 43725 87319 43721 87319 43726 87319 43726 87320 43721 87320 43715 87320 43726 87321 43715 87321 43722 87321 43722 87322 43715 87322 43714 87322 43722 87323 43714 87323 43723 87323 43723 87324 43714 87324 43712 87324 43723 87325 43712 87325 37123 87325 37117 87326 37119 87326 43727 87326 43717 87327 43718 87327 37117 87327 43724 87328 43720 87328 37117 87328 43725 87329 43726 87329 37117 87329 37117 87330 43723 87330 37123 87330 43722 87331 43723 87331 37117 87331 43726 87332 43722 87332 37117 87332 43720 87333 43725 87333 37117 87333 43718 87334 43724 87334 37117 87334 43727 87335 43717 87335 37117 87335 44420 87336 45603 87336 43728 87336 43728 87337 45603 87337 44444 87337 43728 87338 44444 87338 43729 87338 43729 87339 44444 87339 43730 87339 43729 87340 43730 87340 43731 87340 43731 87341 43730 87341 43732 87341 43731 87342 43732 87342 43733 87342 43733 87343 43732 87343 43734 87343 43733 87344 43734 87344 43735 87344 43735 87345 43734 87345 43736 87345 43735 87346 43736 87346 44419 87346 44419 87347 43736 87347 44447 87347 44419 87348 44447 87348 43737 87348 43737 87349 44447 87349 43738 87349 43737 87350 43738 87350 44417 87350 44417 87351 43738 87351 44450 87351 44417 87352 44450 87352 44415 87352 44415 87353 44450 87353 44421 87353 44415 87354 44421 87354 44413 87354 44413 87355 44421 87355 43739 87355 44413 87356 43739 87356 43740 87356 43740 87357 43739 87357 43741 87357 43740 87358 43741 87358 44411 87358 44411 87359 43741 87359 43742 87359 44411 87360 43742 87360 43743 87360 43743 87361 43742 87361 44424 87361 43743 87362 44424 87362 43744 87362 43744 87363 44424 87363 43745 87363 43744 87364 43745 87364 43746 87364 43746 87365 43745 87365 43748 87365 43746 87366 43748 87366 43747 87366 43747 87367 43748 87367 43749 87367 43747 87368 43749 87368 45031 87368 45031 87369 43749 87369 44425 87369 44463 87370 44477 87370 43750 87370 43750 87371 44477 87371 44479 87371 43750 87372 44479 87372 43751 87372 43751 87373 44479 87373 44480 87373 43751 87374 44480 87374 43752 87374 43752 87375 44480 87375 44482 87375 43752 87376 44482 87376 43753 87376 43753 87377 44482 87377 43754 87377 43753 87378 43754 87378 43755 87378 43755 87379 43754 87379 44485 87379 43755 87380 44485 87380 43756 87380 43756 87381 44485 87381 43757 87381 43756 87382 43757 87382 43758 87382 43758 87383 43757 87383 44488 87383 43758 87384 44488 87384 43759 87384 43759 87385 44488 87385 44489 87385 43759 87386 44489 87386 44459 87386 44459 87387 44489 87387 44492 87387 44459 87388 44492 87388 43760 87388 43760 87389 44492 87389 44493 87389 43760 87390 44493 87390 43761 87390 43761 87391 44493 87391 44495 87391 43761 87392 44495 87392 44456 87392 44456 87393 44495 87393 44496 87393 44456 87394 44496 87394 43762 87394 43762 87395 44496 87395 43764 87395 43762 87396 43764 87396 43763 87396 43763 87397 43764 87397 43765 87397 43763 87398 43765 87398 43766 87398 43766 87399 43765 87399 44500 87399 43766 87400 44500 87400 43767 87400 43767 87401 44500 87401 44501 87401 43767 87402 44501 87402 45569 87402 45569 87403 44501 87403 43768 87403 43769 87404 45568 87404 43770 87404 43769 87405 43770 87405 43771 87405 43771 87406 43770 87406 44506 87406 43771 87407 44506 87407 44504 87407 44504 87408 44506 87408 44508 87408 44504 87409 44508 87409 43772 87409 43772 87410 44508 87410 44509 87410 43772 87411 44509 87411 43773 87411 43773 87412 44509 87412 43774 87412 43773 87413 43774 87413 44465 87413 44465 87414 43774 87414 44511 87414 44465 87415 44511 87415 44467 87415 44467 87416 44511 87416 44512 87416 44467 87417 44512 87417 43775 87417 43775 87418 44512 87418 43776 87418 43775 87419 43776 87419 43777 87419 43777 87420 43776 87420 44513 87420 43777 87421 44513 87421 44470 87421 44470 87422 44513 87422 43778 87422 44470 87423 43778 87423 44471 87423 44471 87424 43778 87424 44516 87424 44471 87425 44516 87425 43779 87425 43779 87426 44516 87426 44517 87426 43779 87427 44517 87427 44473 87427 44473 87428 44517 87428 44518 87428 44473 87429 44518 87429 44474 87429 44474 87430 44518 87430 44520 87430 44474 87431 44520 87431 43780 87431 43780 87432 44520 87432 44521 87432 43780 87433 44521 87433 44476 87433 44476 87434 44521 87434 43782 87434 44476 87435 43782 87435 43781 87435 43781 87436 43782 87436 44523 87436 43781 87437 44523 87437 43783 87437 43783 87438 44523 87438 43784 87438 43783 87439 43784 87439 44478 87439 43785 87440 44357 87440 43786 87440 43785 87441 43786 87441 44338 87441 44338 87442 43786 87442 43787 87442 44338 87443 43787 87443 44340 87443 44340 87444 43787 87444 43788 87444 44340 87445 43788 87445 44342 87445 44342 87446 43788 87446 44358 87446 44342 87447 44358 87447 43789 87447 43789 87448 44358 87448 44359 87448 43789 87449 44359 87449 44343 87449 44343 87450 44359 87450 43790 87450 44343 87451 43790 87451 44346 87451 44346 87452 43790 87452 44361 87452 44346 87453 44361 87453 44348 87453 44348 87454 44361 87454 43791 87454 44348 87455 43791 87455 43793 87455 43793 87456 43791 87456 43792 87456 43793 87457 43792 87457 44349 87457 44349 87458 43792 87458 44364 87458 44349 87459 44364 87459 44350 87459 44350 87460 44364 87460 43794 87460 44350 87461 43794 87461 43795 87461 43795 87462 43794 87462 43797 87462 43795 87463 43797 87463 43796 87463 43796 87464 43797 87464 43799 87464 43796 87465 43799 87465 43798 87465 43798 87466 43799 87466 44368 87466 43798 87467 44368 87467 44354 87467 44354 87468 44368 87468 44369 87468 44354 87469 44369 87469 44355 87469 44355 87470 44369 87470 44370 87470 44355 87471 44370 87471 43800 87471 43800 87472 44370 87472 45032 87472 43800 87473 45032 87473 43801 87473 45538 87474 44356 87474 43802 87474 43802 87475 44356 87475 43803 87475 43802 87476 43803 87476 43804 87476 43804 87477 43803 87477 44322 87477 43804 87478 44322 87478 43805 87478 43805 87479 44322 87479 44323 87479 43805 87480 44323 87480 43806 87480 43806 87481 44323 87481 43807 87481 43806 87482 43807 87482 43808 87482 43808 87483 43807 87483 43810 87483 43808 87484 43810 87484 43809 87484 43809 87485 43810 87485 44327 87485 43809 87486 44327 87486 44317 87486 44317 87487 44327 87487 43811 87487 44317 87488 43811 87488 43812 87488 43812 87489 43811 87489 44328 87489 43812 87490 44328 87490 43813 87490 43813 87491 44328 87491 43814 87491 43813 87492 43814 87492 44315 87492 44315 87493 43814 87493 43815 87493 44315 87494 43815 87494 44312 87494 44312 87495 43815 87495 44330 87495 44312 87496 44330 87496 44311 87496 44311 87497 44330 87497 44332 87497 44311 87498 44332 87498 44310 87498 44310 87499 44332 87499 43817 87499 44310 87500 43817 87500 43816 87500 43816 87501 43817 87501 44334 87501 43816 87502 44334 87502 43818 87502 43818 87503 44334 87503 44335 87503 43818 87504 44335 87504 44309 87504 44309 87505 44335 87505 44336 87505 44309 87506 44336 87506 45061 87506 45061 87507 44336 87507 45518 87507 44534 87508 45517 87508 43819 87508 44534 87509 43819 87509 44536 87509 44536 87510 43819 87510 44564 87510 44536 87511 44564 87511 44538 87511 44538 87512 44564 87512 43820 87512 44538 87513 43820 87513 44539 87513 44539 87514 43820 87514 43821 87514 44539 87515 43821 87515 44541 87515 44541 87516 43821 87516 44565 87516 44541 87517 44565 87517 43822 87517 43822 87518 44565 87518 44567 87518 43822 87519 44567 87519 44543 87519 44543 87520 44567 87520 44568 87520 44543 87521 44568 87521 43823 87521 43823 87522 44568 87522 44570 87522 43823 87523 44570 87523 44547 87523 44547 87524 44570 87524 44572 87524 44547 87525 44572 87525 43824 87525 43824 87526 44572 87526 43825 87526 43824 87527 43825 87527 43826 87527 43826 87528 43825 87528 43827 87528 43826 87529 43827 87529 44548 87529 44548 87530 43827 87530 43828 87530 44548 87531 43828 87531 44549 87531 44549 87532 43828 87532 43830 87532 44549 87533 43830 87533 43829 87533 43829 87534 43830 87534 43831 87534 43829 87535 43831 87535 43832 87535 43832 87536 43831 87536 44576 87536 43832 87537 44576 87537 44553 87537 44553 87538 44576 87538 44578 87538 44553 87539 44578 87539 43833 87539 43833 87540 44578 87540 44580 87540 43833 87541 44580 87541 44554 87541 44554 87542 44580 87542 43834 87542 44554 87543 43834 87543 43835 87543 44059 87544 44803 87544 44058 87544 44058 87545 44803 87545 43836 87545 44058 87546 43836 87546 44056 87546 44056 87547 43836 87547 43837 87547 44056 87548 43837 87548 44054 87548 44054 87549 43837 87549 43838 87549 44054 87550 43838 87550 43839 87550 43839 87551 43838 87551 44815 87551 43839 87552 44815 87552 44049 87552 44049 87553 44815 87553 43840 87553 44049 87554 43840 87554 44048 87554 44048 87555 43840 87555 44814 87555 44048 87556 44814 87556 45498 87556 45498 87557 44814 87557 44813 87557 44725 87558 44802 87558 45494 87558 44040 87559 43842 87559 43841 87559 45494 87560 44036 87560 44725 87560 44725 87561 44036 87561 44037 87561 44725 87562 44037 87562 43841 87562 43841 87563 44037 87563 44039 87563 43841 87564 44039 87564 44040 87564 44040 87565 44041 87565 43842 87565 43842 87566 44041 87566 43843 87566 43842 87567 43843 87567 43846 87567 43844 87568 44821 87568 44045 87568 44045 87569 44821 87569 43845 87569 44045 87570 43845 87570 44043 87570 44043 87571 43845 87571 43846 87571 44043 87572 43846 87572 43847 87572 43847 87573 43846 87573 43843 87573 45487 87574 43848 87574 43849 87574 43849 87575 43848 87575 44737 87575 43849 87576 44737 87576 43850 87576 43850 87577 44737 87577 44736 87577 43850 87578 44736 87578 44031 87578 44031 87579 44736 87579 43852 87579 44031 87580 43852 87580 43851 87580 43851 87581 43852 87581 43853 87581 43851 87582 43853 87582 44029 87582 44029 87583 43853 87583 44735 87583 44029 87584 44735 87584 43854 87584 43854 87585 44735 87585 44734 87585 43854 87586 44734 87586 45290 87586 45290 87587 44734 87587 43855 87587 45481 87588 44678 87588 44149 87588 44149 87589 44678 87589 43856 87589 44149 87590 43856 87590 44147 87590 44147 87591 43856 87591 43857 87591 44147 87592 43857 87592 44145 87592 44145 87593 43857 87593 44677 87593 44145 87594 44677 87594 44142 87594 44142 87595 44677 87595 43858 87595 44142 87596 43858 87596 43859 87596 43859 87597 43858 87597 44680 87597 43859 87598 44680 87598 43860 87598 43860 87599 44680 87599 43862 87599 43860 87600 43862 87600 43861 87600 43861 87601 43862 87601 45476 87601 43863 87602 44688 87602 44132 87602 44132 87603 44133 87603 43863 87603 43863 87604 44133 87604 44134 87604 43863 87605 44134 87605 44690 87605 44134 87606 44135 87606 44690 87606 44690 87607 44135 87607 44137 87607 44690 87608 44137 87608 43864 87608 44137 87609 43865 87609 43864 87609 43864 87610 43865 87610 43866 87610 43864 87611 43866 87611 44674 87611 43866 87612 44139 87612 44674 87612 44674 87613 44139 87613 43868 87613 44674 87614 43868 87614 43867 87614 43867 87615 43868 87615 44140 87615 43867 87616 44140 87616 43871 87616 45204 87617 43870 87617 43869 87617 43869 87618 43870 87618 43871 87618 43869 87619 43871 87619 43872 87619 43872 87620 43871 87620 44140 87620 44701 87621 45470 87621 43873 87621 43873 87622 44120 87622 44701 87622 44701 87623 44120 87623 44121 87623 44701 87624 44121 87624 43874 87624 44126 87625 43875 87625 44703 87625 44121 87626 44123 87626 43874 87626 43874 87627 44123 87627 44124 87627 43874 87628 44124 87628 44703 87628 44703 87629 44124 87629 44125 87629 44703 87630 44125 87630 44126 87630 44126 87631 44128 87631 43875 87631 43875 87632 44128 87632 44129 87632 43875 87633 44129 87633 44696 87633 44696 87634 44129 87634 43876 87634 44696 87635 43876 87635 44791 87635 44131 87636 45464 87636 43877 87636 43877 87637 45464 87637 44791 87637 43877 87638 44791 87638 43878 87638 43878 87639 44791 87639 43876 87639 44116 87640 44897 87640 44115 87640 44115 87641 44897 87641 43879 87641 44115 87642 43879 87642 44113 87642 44113 87643 43879 87643 43880 87643 44113 87644 43880 87644 44111 87644 44111 87645 43880 87645 43881 87645 44111 87646 43881 87646 44109 87646 44109 87647 43881 87647 44709 87647 44109 87648 44709 87648 43882 87648 43882 87649 44709 87649 44708 87649 43882 87650 44708 87650 45459 87650 45459 87651 44708 87651 44707 87651 43883 87652 44785 87652 45242 87652 45242 87653 44097 87653 43883 87653 43883 87654 44097 87654 44100 87654 43883 87655 44100 87655 43884 87655 43887 87656 43888 87656 44901 87656 44100 87657 43885 87657 43884 87657 43884 87658 43885 87658 43886 87658 43884 87659 43886 87659 44901 87659 44901 87660 43886 87660 44102 87660 44901 87661 44102 87661 43887 87661 43887 87662 44103 87662 43888 87662 43888 87663 44103 87663 44105 87663 43888 87664 44105 87664 43889 87664 43889 87665 44105 87665 44108 87665 43889 87666 44108 87666 43890 87666 43891 87667 44779 87667 43892 87667 43892 87668 44779 87668 43890 87668 43892 87669 43890 87669 43893 87669 43893 87670 43890 87670 44108 87670 45456 87671 44892 87671 43894 87671 43894 87672 44892 87672 44774 87672 43894 87673 44774 87673 43895 87673 43895 87674 44774 87674 44772 87674 43895 87675 44772 87675 44094 87675 44094 87676 44772 87676 44847 87676 44094 87677 44847 87677 44092 87677 44092 87678 44847 87678 44846 87678 44092 87679 44846 87679 44091 87679 44091 87680 44846 87680 43896 87680 44091 87681 43896 87681 44089 87681 44089 87682 43896 87682 43897 87682 44089 87683 43897 87683 45247 87683 45247 87684 43897 87684 45448 87684 43898 87685 45446 87685 44080 87685 44084 87686 44764 87686 44877 87686 44080 87687 44081 87687 43898 87687 43898 87688 44081 87688 44082 87688 43898 87689 44082 87689 44877 87689 44877 87690 44082 87690 43899 87690 44877 87691 43899 87691 44084 87691 44084 87692 44085 87692 44764 87692 44764 87693 44085 87693 43903 87693 44764 87694 43903 87694 43902 87694 45248 87695 44766 87695 44087 87695 44087 87696 44766 87696 43900 87696 44087 87697 43900 87697 43901 87697 43901 87698 43900 87698 43902 87698 43901 87699 43902 87699 44086 87699 44086 87700 43902 87700 43903 87700 44875 87701 43904 87701 43907 87701 43907 87702 43904 87702 43905 87702 43908 87703 43910 87703 44757 87703 43905 87704 44072 87704 43907 87704 43907 87705 44072 87705 43906 87705 43907 87706 43906 87706 44757 87706 44757 87707 43906 87707 44074 87707 44757 87708 44074 87708 43908 87708 43908 87709 43909 87709 43910 87709 43910 87710 43909 87710 43912 87710 43910 87711 43912 87711 43911 87711 43912 87712 44076 87712 43911 87712 43911 87713 44076 87713 44078 87713 43911 87714 44078 87714 43913 87714 45425 87715 44754 87715 44079 87715 44079 87716 44754 87716 43913 87716 44079 87717 43913 87717 43914 87717 43914 87718 43913 87718 44078 87718 43915 87719 45416 87719 45415 87719 45415 87720 44060 87720 43915 87720 43915 87721 44060 87721 43916 87721 43915 87722 43916 87722 44745 87722 43916 87723 44061 87723 44745 87723 44745 87724 44061 87724 44062 87724 44745 87725 44062 87725 43918 87725 44062 87726 43917 87726 43918 87726 43918 87727 43917 87727 43919 87727 43918 87728 43919 87728 44747 87728 43919 87729 43920 87729 44747 87729 44747 87730 43920 87730 44064 87730 44747 87731 44064 87731 44750 87731 44750 87732 44064 87732 44066 87732 44750 87733 44066 87733 44751 87733 43921 87734 44753 87734 44069 87734 44069 87735 44753 87735 44751 87735 44069 87736 44751 87736 44067 87736 44067 87737 44751 87737 44066 87737 44119 87738 45630 87738 44122 87738 44122 87739 45630 87739 45790 87739 44122 87740 45790 87740 43922 87740 43922 87741 45790 87741 43923 87741 43922 87742 43923 87742 44127 87742 44127 87743 43923 87743 45629 87743 44127 87744 45629 87744 43924 87744 43924 87745 45629 87745 45628 87745 43924 87746 45628 87746 44130 87746 44130 87747 45628 87747 43925 87747 44130 87748 43925 87748 45214 87748 45214 87749 43925 87749 45624 87749 45408 87750 45746 87750 44136 87750 44136 87751 45746 87751 43926 87751 44136 87752 43926 87752 43927 87752 43927 87753 43926 87753 43928 87753 43927 87754 43928 87754 44138 87754 44138 87755 43928 87755 45744 87755 44138 87756 45744 87756 43929 87756 43929 87757 45744 87757 45742 87757 43929 87758 45742 87758 43930 87758 43930 87759 45742 87759 45740 87759 43930 87760 45740 87760 43931 87760 43931 87761 45740 87761 45739 87761 45814 87762 45640 87762 43932 87762 44144 87763 43933 87763 45637 87763 43932 87764 43934 87764 45814 87764 45814 87765 43934 87765 44148 87765 45814 87766 44148 87766 45637 87766 45637 87767 44148 87767 44146 87767 45637 87768 44146 87768 44144 87768 44144 87769 43935 87769 43933 87769 43933 87770 43935 87770 43936 87770 43933 87771 43936 87771 43937 87771 45203 87772 43938 87772 44141 87772 44141 87773 43938 87773 43940 87773 44141 87774 43940 87774 43939 87774 43939 87775 43940 87775 43937 87775 43939 87776 43937 87776 44143 87776 44143 87777 43937 87777 43936 87777 43941 87778 45392 87778 44035 87778 43942 87779 43944 87779 45655 87779 44035 87780 44034 87780 43941 87780 43941 87781 44034 87781 44033 87781 43941 87782 44033 87782 45655 87782 45655 87783 44033 87783 44032 87783 45655 87784 44032 87784 43942 87784 43942 87785 43943 87785 43944 87785 43944 87786 43943 87786 44030 87786 43944 87787 44030 87787 43947 87787 43945 87788 45644 87788 43946 87788 43946 87789 45644 87789 45643 87789 43946 87790 45643 87790 44028 87790 44028 87791 45643 87791 43947 87791 44028 87792 43947 87792 43948 87792 43948 87793 43947 87793 44030 87793 45283 87794 45725 87794 43949 87794 43949 87795 45725 87795 45727 87795 43949 87796 45727 87796 44038 87796 44038 87797 45727 87797 45729 87797 44038 87798 45729 87798 43950 87798 43950 87799 45729 87799 45730 87799 43950 87800 45730 87800 43951 87800 43951 87801 45730 87801 43952 87801 43951 87802 43952 87802 44042 87802 44042 87803 43952 87803 45606 87803 44042 87804 45606 87804 44044 87804 44044 87805 45606 87805 45732 87805 44044 87806 45732 87806 45276 87806 45276 87807 45732 87807 45388 87807 43953 87808 43954 87808 43955 87808 44053 87809 45715 87809 45841 87809 43955 87810 43956 87810 43953 87810 43953 87811 43956 87811 44057 87811 43953 87812 44057 87812 45841 87812 45841 87813 44057 87813 44055 87813 45841 87814 44055 87814 44053 87814 44053 87815 44052 87815 45715 87815 45715 87816 44052 87816 44051 87816 45715 87817 44051 87817 45716 87817 44046 87818 45757 87818 44047 87818 44047 87819 45757 87819 45760 87819 44047 87820 45760 87820 43957 87820 43957 87821 45760 87821 45716 87821 43957 87822 45716 87822 44050 87822 44050 87823 45716 87823 44051 87823 45369 87824 45368 87824 43958 87824 43958 87825 45368 87825 43959 87825 43958 87826 43959 87826 43960 87826 43960 87827 43959 87827 45703 87827 43960 87828 45703 87828 44063 87828 44063 87829 45703 87829 45850 87829 44063 87830 45850 87830 44065 87830 44065 87831 45850 87831 43961 87831 44065 87832 43961 87832 44068 87832 44068 87833 43961 87833 45704 87833 44068 87834 45704 87834 44070 87834 44070 87835 45704 87835 45379 87835 45765 87836 45360 87836 43964 87836 43964 87837 45360 87837 43962 87837 44077 87838 45827 87838 45767 87838 43962 87839 43963 87839 43964 87839 43964 87840 43963 87840 43965 87840 43964 87841 43965 87841 45767 87841 45767 87842 43965 87842 43966 87842 45767 87843 43966 87843 44077 87843 44077 87844 44075 87844 45827 87844 45827 87845 44075 87845 43967 87845 45827 87846 43967 87846 45826 87846 43967 87847 43968 87847 45826 87847 45826 87848 43968 87848 44073 87848 45826 87849 44073 87849 45698 87849 44071 87850 45367 87850 43969 87850 43969 87851 45367 87851 45698 87851 43969 87852 45698 87852 43970 87852 43970 87853 45698 87853 44073 87853 45359 87854 43971 87854 43972 87854 43972 87855 43971 87855 45694 87855 43972 87856 45694 87856 44083 87856 44083 87857 45694 87857 43974 87857 44083 87858 43974 87858 43973 87858 43973 87859 43974 87859 43976 87859 43973 87860 43976 87860 43975 87860 43975 87861 43976 87861 43977 87861 43975 87862 43977 87862 43978 87862 43978 87863 43977 87863 45663 87863 43978 87864 45663 87864 43979 87864 43979 87865 45663 87865 43980 87865 43979 87866 43980 87866 45249 87866 45249 87867 43980 87867 45664 87867 45613 87868 45685 87868 44096 87868 43981 87869 45676 87869 43984 87869 44096 87870 44095 87870 45613 87870 45613 87871 44095 87871 43982 87871 45613 87872 43982 87872 43984 87872 43984 87873 43982 87873 43983 87873 43984 87874 43983 87874 43981 87874 43981 87875 44093 87875 45676 87875 45676 87876 44093 87876 43985 87876 45676 87877 43985 87877 43988 87877 43986 87878 45680 87878 44088 87878 44088 87879 45680 87879 45681 87879 44088 87880 45681 87880 44090 87880 44090 87881 45681 87881 43988 87881 44090 87882 43988 87882 43987 87882 43987 87883 43988 87883 43985 87883 44098 87884 43989 87884 44099 87884 44099 87885 43989 87885 45675 87885 44099 87886 45675 87886 44101 87886 44101 87887 45675 87887 45674 87887 44101 87888 45674 87888 44104 87888 44104 87889 45674 87889 45672 87889 44104 87890 45672 87890 44106 87890 44106 87891 45672 87891 45671 87891 44106 87892 45671 87892 44107 87892 44107 87893 45671 87893 43990 87893 44107 87894 43990 87894 45343 87894 45343 87895 43990 87895 45669 87895 45620 87896 45340 87896 45339 87896 45339 87897 44117 87897 45620 87897 45620 87898 44117 87898 44118 87898 45620 87899 44118 87899 43991 87899 44118 87900 44114 87900 43991 87900 43991 87901 44114 87901 44112 87901 43991 87902 44112 87902 43993 87902 44112 87903 43992 87903 43993 87903 43993 87904 43992 87904 43994 87904 43993 87905 43994 87905 45621 87905 43994 87906 44110 87906 45621 87906 45621 87907 44110 87907 43995 87907 45621 87908 43995 87908 43997 87908 43997 87909 43995 87909 43996 87909 43997 87910 43996 87910 45622 87910 43998 87911 44000 87911 43999 87911 43999 87912 44000 87912 45622 87912 43999 87913 45622 87913 44001 87913 44001 87914 45622 87914 43996 87914 45607 87915 45772 87915 44002 87915 44002 87916 45772 87916 44003 87916 44002 87917 44003 87917 45335 87917 45607 87918 44002 87918 44004 87918 44004 87919 44002 87919 44005 87919 44004 87920 44005 87920 45689 87920 45689 87921 44005 87921 44006 87921 45689 87922 44006 87922 45713 87922 45713 87923 44006 87923 44643 87923 45713 87924 44643 87924 45711 87924 45711 87925 44643 87925 44641 87925 45711 87926 44641 87926 45710 87926 45710 87927 44641 87927 44640 87927 45710 87928 44640 87928 45708 87928 45708 87929 44640 87929 44638 87929 45708 87930 44638 87930 45661 87930 45661 87931 44638 87931 44007 87931 45661 87932 44007 87932 45658 87932 45658 87933 44007 87933 44636 87933 45658 87934 44636 87934 45657 87934 45657 87935 44636 87935 44008 87935 45657 87936 44008 87936 45755 87936 45755 87937 44008 87937 44634 87937 45755 87938 44634 87938 45610 87938 45610 87939 44634 87939 44009 87939 45610 87940 44009 87940 45721 87940 45721 87941 44009 87941 44632 87941 45721 87942 44632 87942 45649 87942 45649 87943 44632 87943 44631 87943 45649 87944 44631 87944 45645 87944 45645 87945 44631 87945 44010 87945 45645 87946 44010 87946 45310 87946 45309 87947 45308 87947 44646 87947 44016 87948 44011 87948 44012 87948 44012 87949 44011 87949 44729 87949 44012 87950 44729 87950 44646 87950 44646 87951 44729 87951 44733 87951 44646 87952 44733 87952 45309 87952 44648 87953 44013 87953 44014 87953 44014 87954 44013 87954 44673 87954 44673 87955 44015 87955 44014 87955 44014 87956 44015 87956 44801 87956 44014 87957 44801 87957 44016 87957 44016 87958 44801 87958 44819 87958 44016 87959 44819 87959 44011 87959 44810 87960 44648 87960 44652 87960 44810 87961 44719 87961 44648 87961 44648 87962 44719 87962 44724 87962 44648 87963 44724 87963 44013 87963 44022 87964 44886 87964 44021 87964 44021 87965 44886 87965 44017 87965 44021 87966 44017 87966 44660 87966 44660 87967 44017 87967 44743 87967 44660 87968 44743 87968 44657 87968 44657 87969 44743 87969 44742 87969 44657 87970 44742 87970 44019 87970 44019 87971 44742 87971 44018 87971 44019 87972 44018 87972 44020 87972 44020 87973 44018 87973 44806 87973 44020 87974 44806 87974 44652 87974 44652 87975 44806 87975 44809 87975 44652 87976 44809 87976 44810 87976 44025 87977 44023 87977 44830 87977 44025 87978 44830 87978 44021 87978 44021 87979 44830 87979 44717 87979 44021 87980 44717 87980 44022 87980 44023 87981 44025 87981 44024 87981 44024 87982 44025 87982 44026 87982 44024 87983 44026 87983 44716 87983 44716 87984 44026 87984 44715 87984 44715 87985 44026 87985 44665 87985 44715 87986 44665 87986 44765 87986 44765 87987 44665 87987 44664 87987 44765 87988 44664 87988 44027 87988 45290 87989 43945 87989 43946 87989 45290 87990 43946 87990 43854 87990 43854 87991 43946 87991 44028 87991 43854 87992 44028 87992 44029 87992 44029 87993 44028 87993 43948 87993 44029 87994 43948 87994 43851 87994 43948 87995 44030 87995 43851 87995 43851 87996 44030 87996 43943 87996 43851 87997 43943 87997 44031 87997 43943 87998 43942 87998 44031 87998 44031 87999 43942 87999 44032 87999 44031 88000 44032 88000 43850 88000 44032 88001 44033 88001 43850 88001 43850 88002 44033 88002 44034 88002 43850 88003 44034 88003 43849 88003 43849 88004 44034 88004 44035 88004 43849 88005 44035 88005 45487 88005 45494 88006 45283 88006 43949 88006 45494 88007 43949 88007 44036 88007 44036 88008 43949 88008 44038 88008 44036 88009 44038 88009 44037 88009 44037 88010 44038 88010 44039 88010 44039 88011 44038 88011 43950 88011 44039 88012 43950 88012 44040 88012 44040 88013 43950 88013 44041 88013 44041 88014 43950 88014 43951 88014 44041 88015 43951 88015 43843 88015 43843 88016 43951 88016 43847 88016 43847 88017 43951 88017 44042 88017 43847 88018 44042 88018 44043 88018 44043 88019 44042 88019 44044 88019 44043 88020 44044 88020 44045 88020 44045 88021 44044 88021 45276 88021 44045 88022 45276 88022 43844 88022 45498 88023 44046 88023 44047 88023 45498 88024 44047 88024 44048 88024 44048 88025 44047 88025 43957 88025 44048 88026 43957 88026 44049 88026 44049 88027 43957 88027 44050 88027 44049 88028 44050 88028 43839 88028 44050 88029 44051 88029 43839 88029 43839 88030 44051 88030 44052 88030 43839 88031 44052 88031 44054 88031 44052 88032 44053 88032 44054 88032 44054 88033 44053 88033 44055 88033 44054 88034 44055 88034 44056 88034 44055 88035 44057 88035 44056 88035 44056 88036 44057 88036 43956 88036 44056 88037 43956 88037 44058 88037 44058 88038 43956 88038 43955 88038 44058 88039 43955 88039 44059 88039 45415 88040 45369 88040 44060 88040 44060 88041 45369 88041 43958 88041 44060 88042 43958 88042 43916 88042 43916 88043 43958 88043 44061 88043 44061 88044 43958 88044 43960 88044 44061 88045 43960 88045 44062 88045 44062 88046 43960 88046 43917 88046 43917 88047 43960 88047 44063 88047 43917 88048 44063 88048 43919 88048 43919 88049 44063 88049 43920 88049 43920 88050 44063 88050 44065 88050 43920 88051 44065 88051 44064 88051 44064 88052 44065 88052 44066 88052 44066 88053 44065 88053 44068 88053 44066 88054 44068 88054 44067 88054 44067 88055 44068 88055 44069 88055 44069 88056 44068 88056 44070 88056 44069 88057 44070 88057 43921 88057 43904 88058 44071 88058 43905 88058 43905 88059 44071 88059 43969 88059 43905 88060 43969 88060 44072 88060 44072 88061 43969 88061 43970 88061 44072 88062 43970 88062 43906 88062 43906 88063 43970 88063 44073 88063 43906 88064 44073 88064 44074 88064 44074 88065 44073 88065 43968 88065 44074 88066 43968 88066 43908 88066 43908 88067 43968 88067 43967 88067 43908 88068 43967 88068 43909 88068 43909 88069 43967 88069 44075 88069 43909 88070 44075 88070 43912 88070 43912 88071 44075 88071 44077 88071 43912 88072 44077 88072 44076 88072 44076 88073 44077 88073 43966 88073 44076 88074 43966 88074 44078 88074 44078 88075 43966 88075 43965 88075 44078 88076 43965 88076 43914 88076 43914 88077 43965 88077 43963 88077 43914 88078 43963 88078 44079 88078 44079 88079 43963 88079 43962 88079 44079 88080 43962 88080 45425 88080 45425 88081 43962 88081 45360 88081 44080 88082 45359 88082 43972 88082 44080 88083 43972 88083 44081 88083 44081 88084 43972 88084 44083 88084 44081 88085 44083 88085 44082 88085 44082 88086 44083 88086 43899 88086 43899 88087 44083 88087 43973 88087 43899 88088 43973 88088 44084 88088 44084 88089 43973 88089 44085 88089 44085 88090 43973 88090 43975 88090 44085 88091 43975 88091 43903 88091 43903 88092 43975 88092 44086 88092 44086 88093 43975 88093 43978 88093 44086 88094 43978 88094 43901 88094 43901 88095 43978 88095 43979 88095 43901 88096 43979 88096 44087 88096 44087 88097 43979 88097 45249 88097 44087 88098 45249 88098 45248 88098 45247 88099 43986 88099 44088 88099 45247 88100 44088 88100 44089 88100 44089 88101 44088 88101 44090 88101 44089 88102 44090 88102 44091 88102 44091 88103 44090 88103 43987 88103 44091 88104 43987 88104 44092 88104 43987 88105 43985 88105 44092 88105 44092 88106 43985 88106 44093 88106 44092 88107 44093 88107 44094 88107 44093 88108 43981 88108 44094 88108 44094 88109 43981 88109 43983 88109 44094 88110 43983 88110 43895 88110 43983 88111 43982 88111 43895 88111 43895 88112 43982 88112 44095 88112 43895 88113 44095 88113 43894 88113 43894 88114 44095 88114 44096 88114 43894 88115 44096 88115 45456 88115 45242 88116 44098 88116 44097 88116 44097 88117 44098 88117 44099 88117 44097 88118 44099 88118 44100 88118 44100 88119 44099 88119 43885 88119 43885 88120 44099 88120 44101 88120 43885 88121 44101 88121 43886 88121 43886 88122 44101 88122 44102 88122 44102 88123 44101 88123 44104 88123 44102 88124 44104 88124 43887 88124 43887 88125 44104 88125 44103 88125 44103 88126 44104 88126 44106 88126 44103 88127 44106 88127 44105 88127 44105 88128 44106 88128 44108 88128 44108 88129 44106 88129 44107 88129 44108 88130 44107 88130 43893 88130 43893 88131 44107 88131 43892 88131 43892 88132 44107 88132 45343 88132 43892 88133 45343 88133 43891 88133 43998 88134 43999 88134 45459 88134 45459 88135 43999 88135 43882 88135 43999 88136 44001 88136 43882 88136 43882 88137 44001 88137 43996 88137 43882 88138 43996 88138 44109 88138 43996 88139 43995 88139 44109 88139 44109 88140 43995 88140 44110 88140 44109 88141 44110 88141 44111 88141 44110 88142 43994 88142 44111 88142 44111 88143 43994 88143 43992 88143 44111 88144 43992 88144 44113 88144 43992 88145 44112 88145 44113 88145 44113 88146 44112 88146 44114 88146 44113 88147 44114 88147 44115 88147 45339 88148 44116 88148 44117 88148 44117 88149 44116 88149 44115 88149 44117 88150 44115 88150 44118 88150 44118 88151 44115 88151 44114 88151 43873 88152 44119 88152 44120 88152 44120 88153 44119 88153 44122 88153 44120 88154 44122 88154 44121 88154 44121 88155 44122 88155 44123 88155 44123 88156 44122 88156 43922 88156 44123 88157 43922 88157 44124 88157 44124 88158 43922 88158 44125 88158 44125 88159 43922 88159 44127 88159 44125 88160 44127 88160 44126 88160 44126 88161 44127 88161 44128 88161 44128 88162 44127 88162 43924 88162 44128 88163 43924 88163 44129 88163 44129 88164 43924 88164 43876 88164 43876 88165 43924 88165 44130 88165 43876 88166 44130 88166 43878 88166 43878 88167 44130 88167 43877 88167 43877 88168 44130 88168 45214 88168 43877 88169 45214 88169 44131 88169 44132 88170 45408 88170 44133 88170 44133 88171 45408 88171 44136 88171 44133 88172 44136 88172 44134 88172 44134 88173 44136 88173 44135 88173 44135 88174 44136 88174 43927 88174 44135 88175 43927 88175 44137 88175 44137 88176 43927 88176 43865 88176 43865 88177 43927 88177 44138 88177 43865 88178 44138 88178 43866 88178 43866 88179 44138 88179 44139 88179 44139 88180 44138 88180 43929 88180 44139 88181 43929 88181 43868 88181 43868 88182 43929 88182 44140 88182 44140 88183 43929 88183 43930 88183 44140 88184 43930 88184 43872 88184 43872 88185 43930 88185 43869 88185 43869 88186 43930 88186 43931 88186 43869 88187 43931 88187 45204 88187 43861 88188 45203 88188 44141 88188 43861 88189 44141 88189 43860 88189 43860 88190 44141 88190 43939 88190 43860 88191 43939 88191 43859 88191 43859 88192 43939 88192 44143 88192 43859 88193 44143 88193 44142 88193 44143 88194 43936 88194 44142 88194 44142 88195 43936 88195 43935 88195 44142 88196 43935 88196 44145 88196 43935 88197 44144 88197 44145 88197 44145 88198 44144 88198 44146 88198 44145 88199 44146 88199 44147 88199 44146 88200 44148 88200 44147 88200 44147 88201 44148 88201 43934 88201 44147 88202 43934 88202 44149 88202 44149 88203 43934 88203 43932 88203 44149 88204 43932 88204 45481 88204 45192 88205 44164 88205 44150 88205 44150 88206 44164 88206 44162 88206 44150 88207 44162 88207 44151 88207 44151 88208 44162 88208 44161 88208 44151 88209 44161 88209 45652 88209 45652 88210 44161 88210 44160 88210 45652 88211 44160 88211 44153 88211 44153 88212 44160 88212 44152 88212 44153 88213 44152 88213 44154 88213 44154 88214 44152 88214 44158 88214 44154 88215 44158 88215 44156 88215 44156 88216 44158 88216 44155 88216 44156 88217 44155 88217 44157 88217 44727 88218 44155 88218 44731 88218 44731 88219 44155 88219 44158 88219 44731 88220 44158 88220 44730 88220 44730 88221 44158 88221 44152 88221 44730 88222 44152 88222 44159 88222 44159 88223 44152 88223 44160 88223 44159 88224 44160 88224 44671 88224 44671 88225 44160 88225 44161 88225 44671 88226 44161 88226 44816 88226 44816 88227 44161 88227 44162 88227 44816 88228 44162 88228 44163 88228 44163 88229 44162 88229 44164 88229 44170 88230 45754 88230 44165 88230 44165 88231 45754 88231 44166 88231 44165 88232 44166 88232 44172 88232 44172 88233 44166 88233 44167 88233 44172 88234 44167 88234 44173 88234 44173 88235 44167 88235 44168 88235 44173 88236 44168 88236 44174 88236 44174 88237 44168 88237 45733 88237 44174 88238 45733 88238 44176 88238 44176 88239 45733 88239 45762 88239 44176 88240 45762 88240 45173 88240 45173 88241 45762 88241 45761 88241 44169 88242 44170 88242 44820 88242 44820 88243 44170 88243 44165 88243 44820 88244 44165 88244 44171 88244 44171 88245 44165 88245 44172 88245 44171 88246 44172 88246 44823 88246 44823 88247 44172 88247 44173 88247 44823 88248 44173 88248 44869 88248 44869 88249 44173 88249 44174 88249 44869 88250 44174 88250 44175 88250 44175 88251 44174 88251 44176 88251 44175 88252 44176 88252 45172 88252 45172 88253 44176 88253 45173 88253 45165 88254 45171 88254 44177 88254 44177 88255 45171 88255 45702 88255 44177 88256 45702 88256 44185 88256 44185 88257 45702 88257 45701 88257 44185 88258 45701 88258 44178 88258 44178 88259 45701 88259 45705 88259 44178 88260 45705 88260 44179 88260 44179 88261 45705 88261 44180 88261 44179 88262 44180 88262 44187 88262 44187 88263 44180 88263 44181 88263 44187 88264 44181 88264 44182 88264 44182 88265 44181 88265 45166 88265 45163 88266 45165 88266 44183 88266 44183 88267 45165 88267 44177 88267 44183 88268 44177 88268 44184 88268 44184 88269 44177 88269 44185 88269 44184 88270 44185 88270 44186 88270 44186 88271 44185 88271 44178 88271 44186 88272 44178 88272 44748 88272 44748 88273 44178 88273 44179 88273 44748 88274 44179 88274 44746 88274 44746 88275 44179 88275 44187 88275 44746 88276 44187 88276 44744 88276 44744 88277 44187 88277 44182 88277 44195 88278 44188 88278 44196 88278 44196 88279 44188 88279 45770 88279 44196 88280 45770 88280 44189 88280 44189 88281 45770 88281 44190 88281 44189 88282 44190 88282 44191 88282 44191 88283 44190 88283 44193 88283 44191 88284 44193 88284 44192 88284 44192 88285 44193 88285 45693 88285 44192 88286 45693 88286 44199 88286 44199 88287 45693 88287 45692 88287 44199 88288 45692 88288 45146 88288 45146 88289 45692 88289 45151 88289 44833 88290 44195 88290 44194 88290 44194 88291 44195 88291 44196 88291 44194 88292 44196 88292 44824 88292 44824 88293 44196 88293 44189 88293 44824 88294 44189 88294 44197 88294 44197 88295 44189 88295 44191 88295 44197 88296 44191 88296 44825 88296 44825 88297 44191 88297 44192 88297 44825 88298 44192 88298 44198 88298 44198 88299 44192 88299 44199 88299 44198 88300 44199 88300 45145 88300 45145 88301 44199 88301 45146 88301 45138 88302 45775 88302 44207 88302 44207 88303 45775 88303 45782 88303 44207 88304 45782 88304 44209 88304 44209 88305 45782 88305 44200 88305 44209 88306 44200 88306 44210 88306 44210 88307 44200 88307 44201 88307 44210 88308 44201 88308 44202 88308 44202 88309 44201 88309 45780 88309 44202 88310 45780 88310 44203 88310 44203 88311 45780 88311 44204 88311 44203 88312 44204 88312 44205 88312 44205 88313 44204 88313 45779 88313 45137 88314 45138 88314 44206 88314 44206 88315 45138 88315 44207 88315 44206 88316 44207 88316 44208 88316 44208 88317 44207 88317 44209 88317 44208 88318 44209 88318 44211 88318 44211 88319 44209 88319 44210 88319 44211 88320 44210 88320 44212 88320 44212 88321 44210 88321 44202 88321 44212 88322 44202 88322 44213 88322 44213 88323 44202 88323 44203 88323 44213 88324 44203 88324 45133 88324 45133 88325 44203 88325 44205 88325 45132 88326 45798 88326 44220 88326 44220 88327 45798 88327 45801 88327 44220 88328 45801 88328 44221 88328 44221 88329 45801 88329 45802 88329 44221 88330 45802 88330 44214 88330 44214 88331 45802 88331 45803 88331 44214 88332 45803 88332 44215 88332 44215 88333 45803 88333 44216 88333 44215 88334 44216 88334 44217 88334 44217 88335 44216 88335 45804 88335 44217 88336 45804 88336 45124 88336 45124 88337 45804 88337 45805 88337 44839 88338 45132 88338 44218 88338 44218 88339 45132 88339 44220 88339 44218 88340 44220 88340 44219 88340 44219 88341 44220 88341 44221 88341 44219 88342 44221 88342 44844 88342 44844 88343 44221 88343 44214 88343 44844 88344 44214 88344 44222 88344 44222 88345 44214 88345 44215 88345 44222 88346 44215 88346 44223 88346 44223 88347 44215 88347 44217 88347 44223 88348 44217 88348 44845 88348 44845 88349 44217 88349 45124 88349 44228 88350 44224 88350 44229 88350 44229 88351 44224 88351 45627 88351 44229 88352 45627 88352 44231 88352 44231 88353 45627 88353 45615 88353 44231 88354 45615 88354 44232 88354 44232 88355 45615 88355 45616 88355 44232 88356 45616 88356 44225 88356 44225 88357 45616 88357 44226 88357 44225 88358 44226 88358 44235 88358 44235 88359 44226 88359 45614 88359 44235 88360 45614 88360 44227 88360 44227 88361 45614 88361 45623 88361 44705 88362 44228 88362 44706 88362 44706 88363 44228 88363 44229 88363 44706 88364 44229 88364 44230 88364 44230 88365 44229 88365 44231 88365 44230 88366 44231 88366 44711 88366 44711 88367 44231 88367 44232 88367 44711 88368 44232 88368 44710 88368 44710 88369 44232 88369 44225 88369 44710 88370 44225 88370 44233 88370 44233 88371 44225 88371 44235 88371 44233 88372 44235 88372 44234 88372 44234 88373 44235 88373 44227 88373 44241 88374 45796 88374 44243 88374 44243 88375 45796 88375 45794 88375 44243 88376 45794 88376 44244 88376 44244 88377 45794 88377 44237 88377 44244 88378 44237 88378 44236 88378 44236 88379 44237 88379 45792 88379 44236 88380 45792 88380 44238 88380 44238 88381 45792 88381 44240 88381 44238 88382 44240 88382 44239 88382 44239 88383 44240 88383 45631 88383 44239 88384 45631 88384 45100 88384 45100 88385 45631 88385 45787 88385 44861 88386 44241 88386 44862 88386 44862 88387 44241 88387 44243 88387 44862 88388 44243 88388 44242 88388 44242 88389 44243 88389 44244 88389 44242 88390 44244 88390 44854 88390 44854 88391 44244 88391 44236 88391 44854 88392 44236 88392 44853 88392 44853 88393 44236 88393 44238 88393 44853 88394 44238 88394 44852 88394 44852 88395 44238 88395 44239 88395 44852 88396 44239 88396 44878 88396 44878 88397 44239 88397 45100 88397 45093 88398 44245 88398 44251 88398 44251 88399 44245 88399 45635 88399 44251 88400 45635 88400 44246 88400 44246 88401 45635 88401 45634 88401 44246 88402 45634 88402 44254 88402 44254 88403 45634 88403 45633 88403 44254 88404 45633 88404 44247 88404 44247 88405 45633 88405 45747 88405 44247 88406 45747 88406 44248 88406 44248 88407 45747 88407 45749 88407 44248 88408 45749 88408 44257 88408 44257 88409 45749 88409 45750 88409 44257 88410 45750 88410 45088 88410 45088 88411 45750 88411 45094 88411 44249 88412 45093 88412 44250 88412 44250 88413 45093 88413 44251 88413 44250 88414 44251 88414 44252 88414 44252 88415 44251 88415 44246 88415 44252 88416 44246 88416 44253 88416 44253 88417 44246 88417 44254 88417 44253 88418 44254 88418 44255 88418 44255 88419 44254 88419 44247 88419 44255 88420 44247 88420 44868 88420 44868 88421 44247 88421 44248 88421 44868 88422 44248 88422 44256 88422 44256 88423 44248 88423 44257 88423 44256 88424 44257 88424 44880 88424 44880 88425 44257 88425 45088 88425 44655 88426 44651 88426 44294 88426 45087 88427 44258 88427 44923 88427 44923 88428 44258 88428 44262 88428 44291 88429 44264 88429 44259 88429 44259 88430 44260 88430 44291 88430 44291 88431 44260 88431 44261 88431 44291 88432 44261 88432 44258 88432 44258 88433 44261 88433 44647 88433 44258 88434 44647 88434 44262 88434 44263 88435 44269 88435 44653 88435 44653 88436 44650 88436 44263 88436 44263 88437 44650 88437 44649 88437 44263 88438 44649 88438 44264 88438 44264 88439 44649 88439 44265 88439 44264 88440 44265 88440 44259 88440 44294 88441 44651 88441 44268 88441 44651 88442 44266 88442 44268 88442 44268 88443 44266 88443 44267 88443 44268 88444 44267 88444 44269 88444 44269 88445 44267 88445 44654 88445 44269 88446 44654 88446 44653 88446 44655 88447 44294 88447 44270 88447 44270 88448 44294 88448 44271 88448 44270 88449 44271 88449 44656 88449 44656 88450 44271 88450 44295 88450 44656 88451 44295 88451 44272 88451 44272 88452 44295 88452 44658 88452 44658 88453 44295 88453 44297 88453 44658 88454 44297 88454 44659 88454 44659 88455 44297 88455 44273 88455 44273 88456 44297 88456 44298 88456 44273 88457 44298 88457 44274 88457 44274 88458 44298 88458 44275 88458 44275 88459 44298 88459 44276 88459 44275 88460 44276 88460 44661 88460 44661 88461 44276 88461 44277 88461 44277 88462 44276 88462 44278 88462 44277 88463 44278 88463 44279 88463 44279 88464 44278 88464 44662 88464 44662 88465 44278 88465 44280 88465 44662 88466 44280 88466 44667 88466 44667 88467 44280 88467 44666 88467 44666 88468 44280 88468 44301 88468 44666 88469 44301 88469 44281 88469 44281 88470 44301 88470 44302 88470 44281 88471 44302 88471 44663 88471 44308 88472 44282 88472 45074 88472 45074 88473 44282 88473 44314 88473 45074 88474 44314 88474 44283 88474 44283 88475 44314 88475 44313 88475 44283 88476 44313 88476 45078 88476 45078 88477 44313 88477 44284 88477 45078 88478 44284 88478 44285 88478 44285 88479 44284 88479 44286 88479 44285 88480 44286 88480 45082 88480 45082 88481 44286 88481 44287 88481 45082 88482 44287 88482 45084 88482 45084 88483 44287 88483 44288 88483 45084 88484 44288 88484 45086 88484 45086 88485 44288 88485 44289 88485 45086 88486 44289 88486 45087 88486 45087 88487 44289 88487 44290 88487 45087 88488 44290 88488 44258 88488 44258 88489 44290 88489 45060 88489 44258 88490 45060 88490 44291 88490 44291 88491 45060 88491 44292 88491 44291 88492 44292 88492 44264 88492 44264 88493 44292 88493 45058 88493 44264 88494 45058 88494 44263 88494 44263 88495 45058 88495 44293 88495 44263 88496 44293 88496 44269 88496 44269 88497 44293 88497 45057 88497 44269 88498 45057 88498 44268 88498 44268 88499 45057 88499 45056 88499 44268 88500 45056 88500 44294 88500 44294 88501 45056 88501 45054 88501 44294 88502 45054 88502 44271 88502 45054 88503 45053 88503 44271 88503 44271 88504 45053 88504 45052 88504 44271 88505 45052 88505 44295 88505 44295 88506 45052 88506 44296 88506 44295 88507 44296 88507 44297 88507 44297 88508 44296 88508 45050 88508 44297 88509 45050 88509 44298 88509 44298 88510 45050 88510 45049 88510 44298 88511 45049 88511 44276 88511 44276 88512 45049 88512 44299 88512 44276 88513 44299 88513 44278 88513 44278 88514 44299 88514 44300 88514 44278 88515 44300 88515 44280 88515 44280 88516 44300 88516 45048 88516 44280 88517 45048 88517 44301 88517 44301 88518 45048 88518 45047 88518 44301 88519 45047 88519 44302 88519 44302 88520 45047 88520 45046 88520 44302 88521 45046 88521 44303 88521 44303 88522 45046 88522 44304 88522 44303 88523 44304 88523 44305 88523 44305 88524 44304 88524 44321 88524 44305 88525 44321 88525 45068 88525 45068 88526 44321 88526 44320 88526 45068 88527 44320 88527 45066 88527 45066 88528 44320 88528 44306 88528 45066 88529 44306 88529 45071 88529 45071 88530 44306 88530 44319 88530 45071 88531 44319 88531 45069 88531 45069 88532 44319 88532 44318 88532 45069 88533 44318 88533 45072 88533 45072 88534 44318 88534 44307 88534 45072 88535 44307 88535 44308 88535 44308 88536 44307 88536 44316 88536 44308 88537 44316 88537 44282 88537 45061 88538 44290 88538 44309 88538 44309 88539 44290 88539 44289 88539 44309 88540 44289 88540 43818 88540 43818 88541 44289 88541 44288 88541 43818 88542 44288 88542 43816 88542 43816 88543 44288 88543 44287 88543 43816 88544 44287 88544 44310 88544 44310 88545 44287 88545 44286 88545 44310 88546 44286 88546 44311 88546 44311 88547 44286 88547 44284 88547 44311 88548 44284 88548 44312 88548 44312 88549 44284 88549 44313 88549 44312 88550 44313 88550 44315 88550 44315 88551 44313 88551 44314 88551 44315 88552 44314 88552 43813 88552 43813 88553 44314 88553 44282 88553 43813 88554 44282 88554 43812 88554 43812 88555 44282 88555 44316 88555 43812 88556 44316 88556 44317 88556 44317 88557 44316 88557 44307 88557 44317 88558 44307 88558 43809 88558 43809 88559 44307 88559 44318 88559 43809 88560 44318 88560 43808 88560 43808 88561 44318 88561 44319 88561 43808 88562 44319 88562 43806 88562 43806 88563 44319 88563 44306 88563 43806 88564 44306 88564 43805 88564 43805 88565 44306 88565 44320 88565 43805 88566 44320 88566 43804 88566 43804 88567 44320 88567 44321 88567 43804 88568 44321 88568 43802 88568 43802 88569 44321 88569 44304 88569 43802 88570 44304 88570 45538 88570 45538 88571 44304 88571 45046 88571 43803 88572 45541 88572 44322 88572 44322 88573 45541 88573 45542 88573 44322 88574 45542 88574 44323 88574 44323 88575 45542 88575 45543 88575 44323 88576 45543 88576 43807 88576 43807 88577 45543 88577 44324 88577 43807 88578 44324 88578 43810 88578 43810 88579 44324 88579 44325 88579 43810 88580 44325 88580 44327 88580 44327 88581 44325 88581 44326 88581 44327 88582 44326 88582 43811 88582 43811 88583 44326 88583 45547 88583 43811 88584 45547 88584 44328 88584 44328 88585 45547 88585 45548 88585 44328 88586 45548 88586 43814 88586 43814 88587 45548 88587 44329 88587 43814 88588 44329 88588 43815 88588 43815 88589 44329 88589 45550 88589 43815 88590 45550 88590 44330 88590 44330 88591 45550 88591 44331 88591 44330 88592 44331 88592 44332 88592 44332 88593 44331 88593 44333 88593 44332 88594 44333 88594 43817 88594 43817 88595 44333 88595 45554 88595 43817 88596 45554 88596 44334 88596 44334 88597 45554 88597 45555 88597 44334 88598 45555 88598 44335 88598 44335 88599 45555 88599 45556 88599 44335 88600 45556 88600 44336 88600 44336 88601 45556 88601 45557 88601 44336 88602 45557 88602 45518 88602 45518 88603 45557 88603 43785 88603 45518 88604 43785 88604 44337 88604 44337 88605 43785 88605 44338 88605 44337 88606 44338 88606 45520 88606 45520 88607 44338 88607 44340 88607 45520 88608 44340 88608 44339 88608 44339 88609 44340 88609 44342 88609 44339 88610 44342 88610 44341 88610 44341 88611 44342 88611 43789 88611 44341 88612 43789 88612 44344 88612 44344 88613 43789 88613 44343 88613 44344 88614 44343 88614 44345 88614 44345 88615 44343 88615 44346 88615 44345 88616 44346 88616 44347 88616 44347 88617 44346 88617 44348 88617 44347 88618 44348 88618 45526 88618 45526 88619 44348 88619 43793 88619 45526 88620 43793 88620 45527 88620 45527 88621 43793 88621 44349 88621 45527 88622 44349 88622 45529 88622 45529 88623 44349 88623 44350 88623 45529 88624 44350 88624 45531 88624 45531 88625 44350 88625 43795 88625 45531 88626 43795 88626 44351 88626 44351 88627 43795 88627 43796 88627 44351 88628 43796 88628 44352 88628 44352 88629 43796 88629 43798 88629 44352 88630 43798 88630 44353 88630 44353 88631 43798 88631 44354 88631 44353 88632 44354 88632 45536 88632 45536 88633 44354 88633 44355 88633 45536 88634 44355 88634 45539 88634 45539 88635 44355 88635 43800 88635 45539 88636 43800 88636 44356 88636 44356 88637 43800 88637 43801 88637 44356 88638 43801 88638 43803 88638 43803 88639 43801 88639 45541 88639 44357 88640 44372 88640 44373 88640 44357 88641 44373 88641 43786 88641 43786 88642 44373 88642 44375 88642 43786 88643 44375 88643 43787 88643 43787 88644 44375 88644 44376 88644 43787 88645 44376 88645 43788 88645 43788 88646 44376 88646 44377 88646 43788 88647 44377 88647 44358 88647 44358 88648 44377 88648 44378 88648 44358 88649 44378 88649 44359 88649 44359 88650 44378 88650 44379 88650 44359 88651 44379 88651 43790 88651 43790 88652 44379 88652 44360 88652 43790 88653 44360 88653 44361 88653 44361 88654 44360 88654 44362 88654 44361 88655 44362 88655 43791 88655 43791 88656 44362 88656 44363 88656 43791 88657 44363 88657 43792 88657 43792 88658 44363 88658 44381 88658 43792 88659 44381 88659 44364 88659 44364 88660 44381 88660 44365 88660 44364 88661 44365 88661 43794 88661 43794 88662 44365 88662 44384 88662 43794 88663 44384 88663 43797 88663 43797 88664 44384 88664 44366 88664 43797 88665 44366 88665 43799 88665 43799 88666 44366 88666 44385 88666 43799 88667 44385 88667 44368 88667 44368 88668 44385 88668 44367 88668 44368 88669 44367 88669 44369 88669 44369 88670 44367 88670 44387 88670 44369 88671 44387 88671 44370 88671 44370 88672 44387 88672 44388 88672 44370 88673 44388 88673 45032 88673 45044 88674 44371 88674 44372 88674 44372 88675 44371 88675 44374 88675 44372 88676 44374 88676 44373 88676 44373 88677 44374 88677 45030 88677 44373 88678 45030 88678 44375 88678 44375 88679 45030 88679 45029 88679 44375 88680 45029 88680 44376 88680 44376 88681 45029 88681 45027 88681 44376 88682 45027 88682 44377 88682 44377 88683 45027 88683 45026 88683 44377 88684 45026 88684 44378 88684 44378 88685 45026 88685 45025 88685 44378 88686 45025 88686 44379 88686 44379 88687 45025 88687 45023 88687 44379 88688 45023 88688 44360 88688 44360 88689 45023 88689 45022 88689 44360 88690 45022 88690 44362 88690 44362 88691 45022 88691 44380 88691 44362 88692 44380 88692 44363 88692 44363 88693 44380 88693 45018 88693 44363 88694 45018 88694 44381 88694 44381 88695 45018 88695 44382 88695 44381 88696 44382 88696 44365 88696 44365 88697 44382 88697 44383 88697 44365 88698 44383 88698 44384 88698 44384 88699 44383 88699 45016 88699 44384 88700 45016 88700 44366 88700 44366 88701 45016 88701 45014 88701 44366 88702 45014 88702 44385 88702 44385 88703 45014 88703 45013 88703 44385 88704 45013 88704 44367 88704 44367 88705 45013 88705 44386 88705 44367 88706 44386 88706 44387 88706 44387 88707 44386 88707 45011 88707 44387 88708 45011 88708 44388 88708 44388 88709 45011 88709 45009 88709 44388 88710 45009 88710 45033 88710 45033 88711 45009 88711 44389 88711 45033 88712 44389 88712 45034 88712 45034 88713 44389 88713 44390 88713 45034 88714 44390 88714 44391 88714 44391 88715 44390 88715 44392 88715 44391 88716 44392 88716 45037 88716 45037 88717 44392 88717 44393 88717 45037 88718 44393 88718 44395 88718 44395 88719 44393 88719 44394 88719 44395 88720 44394 88720 44397 88720 44397 88721 44394 88721 44396 88721 44397 88722 44396 88722 44398 88722 44398 88723 44396 88723 44399 88723 44398 88724 44399 88724 45039 88724 45039 88725 44399 88725 44418 88725 45039 88726 44418 88726 44400 88726 44400 88727 44418 88727 44416 88727 44400 88728 44416 88728 44401 88728 44401 88729 44416 88729 44414 88729 44401 88730 44414 88730 44402 88730 44402 88731 44414 88731 44412 88731 44402 88732 44412 88732 44403 88732 44403 88733 44412 88733 44410 88733 44403 88734 44410 88734 44404 88734 44404 88735 44410 88735 44405 88735 44404 88736 44405 88736 44406 88736 44406 88737 44405 88737 44409 88737 44406 88738 44409 88738 44407 88738 44407 88739 44409 88739 44408 88739 44407 88740 44408 88740 45044 88740 45044 88741 44408 88741 44371 88741 45031 88742 44374 88742 43747 88742 43747 88743 44374 88743 44371 88743 43747 88744 44371 88744 43746 88744 43746 88745 44371 88745 44408 88745 43746 88746 44408 88746 43744 88746 43744 88747 44408 88747 44409 88747 43744 88748 44409 88748 43743 88748 43743 88749 44409 88749 44405 88749 43743 88750 44405 88750 44411 88750 44411 88751 44405 88751 44410 88751 44411 88752 44410 88752 43740 88752 43740 88753 44410 88753 44412 88753 43740 88754 44412 88754 44413 88754 44413 88755 44412 88755 44414 88755 44413 88756 44414 88756 44415 88756 44415 88757 44414 88757 44416 88757 44415 88758 44416 88758 44417 88758 44417 88759 44416 88759 44418 88759 44417 88760 44418 88760 43737 88760 43737 88761 44418 88761 44399 88761 43737 88762 44399 88762 44419 88762 44419 88763 44399 88763 44396 88763 44419 88764 44396 88764 43735 88764 43735 88765 44396 88765 44394 88765 43735 88766 44394 88766 43733 88766 43733 88767 44394 88767 44393 88767 43733 88768 44393 88768 43731 88768 43731 88769 44393 88769 44392 88769 43731 88770 44392 88770 43729 88770 43729 88771 44392 88771 44390 88771 43729 88772 44390 88772 43728 88772 43728 88773 44390 88773 44389 88773 43728 88774 44389 88774 44420 88774 44420 88775 44389 88775 45009 88775 44450 88776 44451 88776 44421 88776 44421 88777 44451 88777 44422 88777 44421 88778 44422 88778 43739 88778 43739 88779 44422 88779 44423 88779 43739 88780 44423 88780 43741 88780 43741 88781 44423 88781 44458 88781 43741 88782 44458 88782 43742 88782 43742 88783 44458 88783 44457 88783 43742 88784 44457 88784 44424 88784 44424 88785 44457 88785 44455 88785 44424 88786 44455 88786 43745 88786 43745 88787 44455 88787 44454 88787 43745 88788 44454 88788 43748 88788 43748 88789 44454 88789 44453 88789 43748 88790 44453 88790 43749 88790 43749 88791 44453 88791 44452 88791 43749 88792 44452 88792 44425 88792 44425 88793 44452 88793 44426 88793 44425 88794 44426 88794 44428 88794 44428 88795 44426 88795 44427 88795 44428 88796 44427 88796 45587 88796 45587 88797 44427 88797 45008 88797 45587 88798 45008 88798 44429 88798 44429 88799 45008 88799 44430 88799 44429 88800 44430 88800 45590 88800 45590 88801 44430 88801 45005 88801 45590 88802 45005 88802 45591 88802 45591 88803 45005 88803 44431 88803 45591 88804 44431 88804 45592 88804 45592 88805 44431 88805 44432 88805 45592 88806 44432 88806 45593 88806 45593 88807 44432 88807 45003 88807 45593 88808 45003 88808 45595 88808 45595 88809 45003 88809 44433 88809 45595 88810 44433 88810 45596 88810 45596 88811 44433 88811 44434 88811 45596 88812 44434 88812 44435 88812 44435 88813 44434 88813 44436 88813 44435 88814 44436 88814 45598 88814 45598 88815 44436 88815 44999 88815 45598 88816 44999 88816 45599 88816 45599 88817 44999 88817 44437 88817 45599 88818 44437 88818 45600 88818 45600 88819 44437 88819 44996 88819 45600 88820 44996 88820 44438 88820 44438 88821 44996 88821 44440 88821 44438 88822 44440 88822 44439 88822 44439 88823 44440 88823 44441 88823 44439 88824 44441 88824 44442 88824 44442 88825 44441 88825 44443 88825 44442 88826 44443 88826 45603 88826 45603 88827 44443 88827 44464 88827 45603 88828 44464 88828 44444 88828 44444 88829 44464 88829 44462 88829 44444 88830 44462 88830 43730 88830 43730 88831 44462 88831 44445 88831 43730 88832 44445 88832 43732 88832 43732 88833 44445 88833 44461 88833 43732 88834 44461 88834 43734 88834 43734 88835 44461 88835 44446 88835 43734 88836 44446 88836 43736 88836 43736 88837 44446 88837 44460 88837 43736 88838 44460 88838 44447 88838 44447 88839 44460 88839 44448 88839 44447 88840 44448 88840 43738 88840 43738 88841 44448 88841 44449 88841 43738 88842 44449 88842 44450 88842 44450 88843 44449 88843 44451 88843 45569 88844 44426 88844 43767 88844 43767 88845 44426 88845 44452 88845 43767 88846 44452 88846 43766 88846 43766 88847 44452 88847 44453 88847 43766 88848 44453 88848 43763 88848 43763 88849 44453 88849 44454 88849 43763 88850 44454 88850 43762 88850 43762 88851 44454 88851 44455 88851 43762 88852 44455 88852 44456 88852 44456 88853 44455 88853 44457 88853 44456 88854 44457 88854 43761 88854 43761 88855 44457 88855 44458 88855 43761 88856 44458 88856 43760 88856 43760 88857 44458 88857 44423 88857 43760 88858 44423 88858 44459 88858 44459 88859 44423 88859 44422 88859 44459 88860 44422 88860 43759 88860 43759 88861 44422 88861 44451 88861 43759 88862 44451 88862 43758 88862 43758 88863 44451 88863 44449 88863 43758 88864 44449 88864 43756 88864 43756 88865 44449 88865 44448 88865 43756 88866 44448 88866 43755 88866 43755 88867 44448 88867 44460 88867 43755 88868 44460 88868 43753 88868 43753 88869 44460 88869 44446 88869 43753 88870 44446 88870 43752 88870 43752 88871 44446 88871 44461 88871 43752 88872 44461 88872 43751 88872 43751 88873 44461 88873 44445 88873 43751 88874 44445 88874 43750 88874 43750 88875 44445 88875 44462 88875 43750 88876 44462 88876 44463 88876 44463 88877 44462 88877 44464 88877 45571 88878 43773 88878 45573 88878 45573 88879 43773 88879 44465 88879 45573 88880 44465 88880 44466 88880 44466 88881 44465 88881 44467 88881 44466 88882 44467 88882 44468 88882 44468 88883 44467 88883 43775 88883 44468 88884 43775 88884 45576 88884 45576 88885 43775 88885 43777 88885 45576 88886 43777 88886 44469 88886 44469 88887 43777 88887 44470 88887 44469 88888 44470 88888 45577 88888 45577 88889 44470 88889 44471 88889 45577 88890 44471 88890 44472 88890 44472 88891 44471 88891 43779 88891 44472 88892 43779 88892 45579 88892 45579 88893 43779 88893 44473 88893 45579 88894 44473 88894 45580 88894 45580 88895 44473 88895 44474 88895 45580 88896 44474 88896 45581 88896 45581 88897 44474 88897 43780 88897 45581 88898 43780 88898 44475 88898 44475 88899 43780 88899 44476 88899 44475 88900 44476 88900 45584 88900 45584 88901 44476 88901 43781 88901 45584 88902 43781 88902 45585 88902 45585 88903 43781 88903 43783 88903 45585 88904 43783 88904 44477 88904 44477 88905 43783 88905 44478 88905 44477 88906 44478 88906 44479 88906 44479 88907 44478 88907 45558 88907 44479 88908 45558 88908 44480 88908 44480 88909 45558 88909 44481 88909 44480 88910 44481 88910 44482 88910 44481 88911 44483 88911 44482 88911 44482 88912 44483 88912 44484 88912 44482 88913 44484 88913 43754 88913 43754 88914 44484 88914 45560 88914 43754 88915 45560 88915 44485 88915 44485 88916 45560 88916 44486 88916 44485 88917 44486 88917 43757 88917 43757 88918 44486 88918 44487 88918 43757 88919 44487 88919 44488 88919 44488 88920 44487 88920 45562 88920 44488 88921 45562 88921 44489 88921 44489 88922 45562 88922 44490 88922 44489 88923 44490 88923 44492 88923 44492 88924 44490 88924 44491 88924 44492 88925 44491 88925 44493 88925 44493 88926 44491 88926 45565 88926 44493 88927 45565 88927 44495 88927 44495 88928 45565 88928 44494 88928 44495 88929 44494 88929 44496 88929 44496 88930 44494 88930 44497 88930 44496 88931 44497 88931 43764 88931 43764 88932 44497 88932 44498 88932 43764 88933 44498 88933 43765 88933 43765 88934 44498 88934 44499 88934 43765 88935 44499 88935 44500 88935 44500 88936 44499 88936 44502 88936 44500 88937 44502 88937 44501 88937 44501 88938 44502 88938 45567 88938 44501 88939 45567 88939 43768 88939 43768 88940 45567 88940 43769 88940 43768 88941 43769 88941 44503 88941 44503 88942 43769 88942 43771 88942 44503 88943 43771 88943 45570 88943 45570 88944 43771 88944 44504 88944 45570 88945 44504 88945 45571 88945 45571 88946 44504 88946 43772 88946 45571 88947 43772 88947 43773 88947 45568 88948 44535 88948 44537 88948 45568 88949 44537 88949 43770 88949 43770 88950 44537 88950 44505 88950 43770 88951 44505 88951 44506 88951 44506 88952 44505 88952 44507 88952 44506 88953 44507 88953 44508 88953 44508 88954 44507 88954 44510 88954 44508 88955 44510 88955 44509 88955 44509 88956 44510 88956 44540 88956 44509 88957 44540 88957 43774 88957 43774 88958 44540 88958 44542 88958 43774 88959 44542 88959 44511 88959 44511 88960 44542 88960 44544 88960 44511 88961 44544 88961 44512 88961 44512 88962 44544 88962 44545 88962 44512 88963 44545 88963 43776 88963 43776 88964 44545 88964 44546 88964 43776 88965 44546 88965 44513 88965 44513 88966 44546 88966 44514 88966 44513 88967 44514 88967 43778 88967 43778 88968 44514 88968 44515 88968 43778 88969 44515 88969 44516 88969 44516 88970 44515 88970 44550 88970 44516 88971 44550 88971 44517 88971 44517 88972 44550 88972 44551 88972 44517 88973 44551 88973 44518 88973 44518 88974 44551 88974 44519 88974 44518 88975 44519 88975 44520 88975 44520 88976 44519 88976 44552 88976 44520 88977 44552 88977 44521 88977 44521 88978 44552 88978 44522 88978 44521 88979 44522 88979 43782 88979 43782 88980 44522 88980 44555 88980 43782 88981 44555 88981 44523 88981 44523 88982 44555 88982 44556 88982 44523 88983 44556 88983 43784 88983 44561 88984 45505 88984 44524 88984 44524 88985 45505 88985 45506 88985 44524 88986 45506 88986 44525 88986 44525 88987 45506 88987 45507 88987 44525 88988 45507 88988 44981 88988 44981 88989 45507 88989 45508 88989 44981 88990 45508 88990 44526 88990 44526 88991 45508 88991 45509 88991 44526 88992 45509 88992 44527 88992 44527 88993 45509 88993 44528 88993 44527 88994 44528 88994 44529 88994 44529 88995 44528 88995 44530 88995 44529 88996 44530 88996 44531 88996 44531 88997 44530 88997 45511 88997 44531 88998 45511 88998 44985 88998 44985 88999 45511 88999 44532 88999 44985 89000 44532 89000 44987 89000 44987 89001 44532 89001 45513 89001 44987 89002 45513 89002 44989 89002 44989 89003 45513 89003 44533 89003 44989 89004 44533 89004 44991 89004 44991 89005 44533 89005 45515 89005 44991 89006 45515 89006 44992 89006 44992 89007 45515 89007 45516 89007 44992 89008 45516 89008 44535 89008 44535 89009 45516 89009 44534 89009 44535 89010 44534 89010 44537 89010 44537 89011 44534 89011 44536 89011 44537 89012 44536 89012 44505 89012 44505 89013 44536 89013 44538 89013 44505 89014 44538 89014 44507 89014 44507 89015 44538 89015 44539 89015 44507 89016 44539 89016 44510 89016 44510 89017 44539 89017 44541 89017 44510 89018 44541 89018 44540 89018 44540 89019 44541 89019 43822 89019 44540 89020 43822 89020 44542 89020 44542 89021 43822 89021 44543 89021 44542 89022 44543 89022 44544 89022 44544 89023 44543 89023 43823 89023 44544 89024 43823 89024 44545 89024 44545 89025 43823 89025 44547 89025 44545 89026 44547 89026 44546 89026 44546 89027 44547 89027 43824 89027 44546 89028 43824 89028 44514 89028 44514 89029 43824 89029 43826 89029 44514 89030 43826 89030 44515 89030 44515 89031 43826 89031 44548 89031 44515 89032 44548 89032 44550 89032 44550 89033 44548 89033 44549 89033 44550 89034 44549 89034 44551 89034 44551 89035 44549 89035 43829 89035 44551 89036 43829 89036 44519 89036 44519 89037 43829 89037 43832 89037 44519 89038 43832 89038 44552 89038 44552 89039 43832 89039 44553 89039 44552 89040 44553 89040 44522 89040 44522 89041 44553 89041 43833 89041 44522 89042 43833 89042 44555 89042 44555 89043 43833 89043 44554 89043 44555 89044 44554 89044 44556 89044 44556 89045 44554 89045 43835 89045 44556 89046 43835 89046 44975 89046 44975 89047 43835 89047 45501 89047 44975 89048 45501 89048 44557 89048 44557 89049 45501 89049 45502 89049 44557 89050 45502 89050 44558 89050 44558 89051 45502 89051 45504 89051 44558 89052 45504 89052 44560 89052 44560 89053 45504 89053 44559 89053 44560 89054 44559 89054 44561 89054 44561 89055 44559 89055 45505 89055 45517 89056 44594 89056 44562 89056 45517 89057 44562 89057 43819 89057 43819 89058 44562 89058 44592 89058 43819 89059 44592 89059 44564 89059 44564 89060 44592 89060 44563 89060 44564 89061 44563 89061 43820 89061 43820 89062 44563 89062 44591 89062 43820 89063 44591 89063 43821 89063 43821 89064 44591 89064 44566 89064 43821 89065 44566 89065 44565 89065 44565 89066 44566 89066 44590 89066 44565 89067 44590 89067 44567 89067 44567 89068 44590 89068 44589 89068 44567 89069 44589 89069 44568 89069 44568 89070 44589 89070 44569 89070 44568 89071 44569 89071 44570 89071 44570 89072 44569 89072 44571 89072 44570 89073 44571 89073 44572 89073 44572 89074 44571 89074 44586 89074 44572 89075 44586 89075 43825 89075 43825 89076 44586 89076 44573 89076 43825 89077 44573 89077 43827 89077 43827 89078 44573 89078 44584 89078 43827 89079 44584 89079 43828 89079 43828 89080 44584 89080 44574 89080 43828 89081 44574 89081 43830 89081 43830 89082 44574 89082 44575 89082 43830 89083 44575 89083 43831 89083 43831 89084 44575 89084 44582 89084 43831 89085 44582 89085 44576 89085 44576 89086 44582 89086 44577 89086 44576 89087 44577 89087 44578 89087 44578 89088 44577 89088 44579 89088 44578 89089 44579 89089 44580 89089 44580 89090 44579 89090 44581 89090 44580 89091 44581 89091 43834 89091 44598 89092 44581 89092 44579 89092 44598 89093 44579 89093 44622 89093 44622 89094 44579 89094 44577 89094 44622 89095 44577 89095 44623 89095 44623 89096 44577 89096 44582 89096 44623 89097 44582 89097 44624 89097 44624 89098 44582 89098 44575 89098 44624 89099 44575 89099 44583 89099 44583 89100 44575 89100 44574 89100 44583 89101 44574 89101 44627 89101 44627 89102 44574 89102 44584 89102 44627 89103 44584 89103 44628 89103 44628 89104 44584 89104 44573 89104 44628 89105 44573 89105 44585 89105 44585 89106 44573 89106 44586 89106 44585 89107 44586 89107 44630 89107 44630 89108 44586 89108 44571 89108 44630 89109 44571 89109 44587 89109 44587 89110 44571 89110 44569 89110 44587 89111 44569 89111 44588 89111 44588 89112 44569 89112 44589 89112 44588 89113 44589 89113 44618 89113 44618 89114 44589 89114 44590 89114 44618 89115 44590 89115 44619 89115 44619 89116 44590 89116 44566 89116 44619 89117 44566 89117 44620 89117 44620 89118 44566 89118 44591 89118 44620 89119 44591 89119 44621 89119 44621 89120 44591 89120 44563 89120 44621 89121 44563 89121 44593 89121 44593 89122 44563 89122 44592 89122 44593 89123 44592 89123 44610 89123 44610 89124 44592 89124 44562 89124 44610 89125 44562 89125 44595 89125 44595 89126 44562 89126 44594 89126 44595 89127 44594 89127 44613 89127 44928 89128 44596 89128 44927 89128 44927 89129 44596 89129 44951 89129 44927 89130 44951 89130 44597 89130 44597 89131 44951 89131 44953 89131 44597 89132 44953 89132 44645 89132 44645 89133 44953 89133 44598 89133 44645 89134 44598 89134 44644 89134 44644 89135 44598 89135 44622 89135 44644 89136 44622 89136 44599 89136 44614 89137 44939 89137 44934 89137 44934 89138 44939 89138 44600 89138 44934 89139 44600 89139 44601 89139 44601 89140 44600 89140 44940 89140 44601 89141 44940 89141 44932 89141 44932 89142 44940 89142 44602 89142 44932 89143 44602 89143 44603 89143 44603 89144 44602 89144 44604 89144 44603 89145 44604 89145 44931 89145 44604 89146 44605 89146 44931 89146 44931 89147 44605 89147 44606 89147 44931 89148 44606 89148 44930 89148 44930 89149 44606 89149 44942 89149 44930 89150 44942 89150 44929 89150 44929 89151 44942 89151 44943 89151 44929 89152 44943 89152 44607 89152 44607 89153 44943 89153 44945 89153 44607 89154 44945 89154 44608 89154 44608 89155 44945 89155 44947 89155 44608 89156 44947 89156 44928 89156 44928 89157 44947 89157 44948 89157 44928 89158 44948 89158 44596 89158 44633 89159 44593 89159 44609 89159 44609 89160 44593 89160 44610 89160 44609 89161 44610 89161 44611 89161 44611 89162 44610 89162 44595 89162 44611 89163 44595 89163 44612 89163 44612 89164 44595 89164 44613 89164 44612 89165 44613 89165 44935 89165 44935 89166 44613 89166 44615 89166 44935 89167 44615 89167 44614 89167 44614 89168 44615 89168 44938 89168 44614 89169 44938 89169 44939 89169 44639 89170 44587 89170 44637 89170 44637 89171 44587 89171 44588 89171 44637 89172 44588 89172 44616 89172 44616 89173 44588 89173 44618 89173 44616 89174 44618 89174 44617 89174 44617 89175 44618 89175 44619 89175 44617 89176 44619 89176 44635 89176 44635 89177 44619 89177 44620 89177 44635 89178 44620 89178 44633 89178 44633 89179 44620 89179 44621 89179 44633 89180 44621 89180 44593 89180 44622 89181 44623 89181 44599 89181 44599 89182 44623 89182 44624 89182 44599 89183 44624 89183 44625 89183 44625 89184 44624 89184 44583 89184 44625 89185 44583 89185 44626 89185 44626 89186 44583 89186 44627 89186 44626 89187 44627 89187 44642 89187 44642 89188 44627 89188 44628 89188 44642 89189 44628 89189 44629 89189 44629 89190 44628 89190 44585 89190 44629 89191 44585 89191 44639 89191 44639 89192 44585 89192 44630 89192 44639 89193 44630 89193 44587 89193 44612 89194 44010 89194 44631 89194 44612 89195 44631 89195 44611 89195 44611 89196 44631 89196 44632 89196 44611 89197 44632 89197 44609 89197 44609 89198 44632 89198 44009 89198 44609 89199 44009 89199 44633 89199 44633 89200 44009 89200 44634 89200 44633 89201 44634 89201 44635 89201 44635 89202 44634 89202 44008 89202 44635 89203 44008 89203 44617 89203 44617 89204 44008 89204 44636 89204 44617 89205 44636 89205 44616 89205 44616 89206 44636 89206 44007 89206 44616 89207 44007 89207 44637 89207 44637 89208 44007 89208 44638 89208 44637 89209 44638 89209 44639 89209 44639 89210 44638 89210 44640 89210 44639 89211 44640 89211 44629 89211 44629 89212 44640 89212 44641 89212 44629 89213 44641 89213 44642 89213 44642 89214 44641 89214 44643 89214 44642 89215 44643 89215 44626 89215 44626 89216 44643 89216 44006 89216 44626 89217 44006 89217 44625 89217 44625 89218 44006 89218 44005 89218 44625 89219 44005 89219 44599 89219 44599 89220 44005 89220 44002 89220 44599 89221 44002 89221 44644 89221 44644 89222 44002 89222 45335 89222 44644 89223 45335 89223 44645 89223 44646 89224 45308 89224 44923 89224 44923 89225 44262 89225 44646 89225 44646 89226 44262 89226 44647 89226 44646 89227 44647 89227 44012 89227 44012 89228 44647 89228 44261 89228 44261 89229 44260 89229 44012 89229 44012 89230 44260 89230 44259 89230 44012 89231 44259 89231 44016 89231 44653 89232 44648 89232 44014 89232 44259 89233 44265 89233 44016 89233 44016 89234 44265 89234 44649 89234 44016 89235 44649 89235 44014 89235 44014 89236 44649 89236 44650 89236 44014 89237 44650 89237 44653 89237 44651 89238 44020 89238 44652 89238 44653 89239 44654 89239 44648 89239 44648 89240 44654 89240 44267 89240 44648 89241 44267 89241 44652 89241 44652 89242 44267 89242 44266 89242 44652 89243 44266 89243 44651 89243 44651 89244 44655 89244 44020 89244 44020 89245 44655 89245 44270 89245 44020 89246 44270 89246 44019 89246 44270 89247 44656 89247 44019 89247 44019 89248 44656 89248 44272 89248 44019 89249 44272 89249 44657 89249 44272 89250 44658 89250 44657 89250 44657 89251 44658 89251 44659 89251 44657 89252 44659 89252 44660 89252 44659 89253 44273 89253 44660 89253 44660 89254 44273 89254 44274 89254 44660 89255 44274 89255 44021 89255 44274 89256 44275 89256 44021 89256 44021 89257 44275 89257 44661 89257 44021 89258 44661 89258 44025 89258 44661 89259 44277 89259 44025 89259 44025 89260 44277 89260 44279 89260 44025 89261 44279 89261 44026 89261 44279 89262 44662 89262 44026 89262 44026 89263 44662 89263 44667 89263 44026 89264 44667 89264 44665 89264 44663 89265 44664 89265 44281 89265 44281 89266 44664 89266 44665 89266 44281 89267 44665 89267 44666 89267 44666 89268 44665 89268 44667 89268 37102 89269 44864 89269 44863 89269 44838 89270 44840 89270 37100 89270 44668 89271 44758 89271 37097 89271 44881 89272 45090 89272 44681 89272 44769 89273 44669 89273 37097 89273 44871 89274 44670 89274 44870 89274 44870 89275 44670 89275 37115 89275 44159 89276 44671 89276 44726 89276 44801 89277 44672 89277 44819 89277 44013 89278 44723 89278 44673 89278 44017 89279 44752 89279 44743 89279 43864 89280 44674 89280 44896 89280 44685 89281 44686 89281 44689 89281 45479 89282 45478 89282 44676 89282 44676 89283 45478 89283 45309 89283 44676 89284 45309 89284 44675 89284 44681 89285 44678 89285 44676 89285 44676 89286 44678 89286 45480 89286 44676 89287 45480 89287 45479 89287 43858 89288 44677 89288 44681 89288 44677 89289 43857 89289 44681 89289 44681 89290 43857 89290 43856 89290 44681 89291 43856 89291 44678 89291 45478 89292 44679 89292 45309 89292 45309 89293 44679 89293 45477 89293 45309 89294 45477 89294 45307 89294 45307 89295 45477 89295 45476 89295 45307 89296 45476 89296 45305 89296 45305 89297 45476 89297 43862 89297 45305 89298 43862 89298 44680 89298 45090 89299 45091 89299 44681 89299 44681 89300 45091 89300 45305 89300 44681 89301 45305 89301 43858 89301 43858 89302 45305 89302 44680 89302 45091 89303 44682 89303 45305 89303 45305 89304 44682 89304 44683 89304 45305 89305 44683 89305 44684 89305 44683 89306 44249 89306 44684 89306 44684 89307 44249 89307 44250 89307 44684 89308 44250 89308 44685 89308 44687 89309 44686 89309 45474 89309 45474 89310 44686 89310 44866 89310 45474 89311 44866 89311 44867 89311 44687 89312 45475 89312 44686 89312 44686 89313 45475 89313 44688 89313 44686 89314 44688 89314 44689 89314 44689 89315 44688 89315 43863 89315 44689 89316 43863 89316 44691 89316 44691 89317 43863 89317 44690 89317 44691 89318 44690 89318 43864 89318 43864 89319 44896 89319 44691 89319 44691 89320 44896 89320 44693 89320 44691 89321 44693 89321 44692 89321 44692 89322 44693 89322 45303 89322 45303 89323 44693 89323 44694 89323 45303 89324 44694 89324 44695 89324 44855 89325 44699 89325 44695 89325 44695 89326 44699 89326 44700 89326 44696 89327 44791 89327 45297 89327 45297 89328 44791 89328 44792 89328 44697 89329 44698 89329 44699 89329 44699 89330 44698 89330 45470 89330 44699 89331 45470 89331 44700 89331 45470 89332 44701 89332 44700 89332 44700 89333 44701 89333 43874 89333 44700 89334 43874 89334 44702 89334 44702 89335 43874 89335 44703 89335 44702 89336 44703 89336 45297 89336 45297 89337 44703 89337 43875 89337 45297 89338 43875 89338 44696 89338 45114 89339 45116 89339 44792 89339 45298 89340 45297 89340 44230 89340 45116 89341 44704 89341 44792 89341 44792 89342 44704 89342 44705 89342 44792 89343 44705 89343 45297 89343 45297 89344 44705 89344 44706 89344 45297 89345 44706 89345 44230 89345 43879 89346 45300 89346 43880 89346 43880 89347 45300 89347 45299 89347 43880 89348 45299 89348 43881 89348 43881 89349 45299 89349 45298 89349 43881 89350 45298 89350 44709 89350 45112 89351 44790 89351 45110 89351 45110 89352 44790 89352 44707 89352 45110 89353 44707 89353 44234 89353 44234 89354 44707 89354 44708 89354 44234 89355 44708 89355 44233 89355 44233 89356 44708 89356 44709 89356 44233 89357 44709 89357 44710 89357 44710 89358 44709 89358 45298 89358 44710 89359 45298 89359 44711 89359 44711 89360 45298 89360 44230 89360 45295 89361 44712 89361 44841 89361 44841 89362 44712 89362 44777 89362 45291 89363 45294 89363 44773 89363 44773 89364 45294 89364 44713 89364 44773 89365 44713 89365 44836 89365 44836 89366 44713 89366 45292 89366 44836 89367 45292 89367 44842 89367 44765 89368 44027 89368 44890 89368 44714 89369 44771 89369 44828 89369 44765 89370 45434 89370 44715 89370 44715 89371 45434 89371 44714 89371 44715 89372 44714 89372 44716 89372 44716 89373 44714 89373 44828 89373 44716 89374 44828 89374 44024 89374 44024 89375 44828 89375 44023 89375 44717 89376 44755 89376 44022 89376 44022 89377 44755 89377 44718 89377 44886 89378 44887 89378 44017 89378 44017 89379 44887 89379 44749 89379 44017 89380 44749 89380 44752 89380 44018 89381 44742 89381 45419 89381 44872 89382 44175 89382 45172 89382 44719 89383 44810 89383 44721 89383 44169 89384 44884 89384 44720 89384 44720 89385 44884 89385 44719 89385 44720 89386 44719 89386 45176 89386 45176 89387 44719 89387 44721 89387 44872 89388 45172 89388 44808 89388 44808 89389 45172 89389 45174 89389 44808 89390 45174 89390 44722 89390 44723 89391 44013 89391 44884 89391 44884 89392 44013 89392 44724 89392 44884 89393 44724 89393 44719 89393 44672 89394 44801 89394 44802 89394 43842 89395 44818 89395 43841 89395 43841 89396 44818 89396 44672 89396 43841 89397 44672 89397 44725 89397 44725 89398 44672 89398 44802 89398 44159 89399 44726 89399 44730 89399 44731 89400 44729 89400 44727 89400 44727 89401 44729 89401 44011 89401 44728 89402 45485 89402 44726 89402 44726 89403 45485 89403 44729 89403 44726 89404 44729 89404 44730 89404 44730 89405 44729 89405 44731 89405 45485 89406 44732 89406 44729 89406 44729 89407 44732 89407 45482 89407 44729 89408 45482 89408 44733 89408 44733 89409 45482 89409 43855 89409 44733 89410 43855 89410 45309 89410 45309 89411 43855 89411 44734 89411 44734 89412 44735 89412 45309 89412 45309 89413 44735 89413 43853 89413 45309 89414 43853 89414 44675 89414 44675 89415 43853 89415 43852 89415 44675 89416 43852 89416 44736 89416 44736 89417 44737 89417 44675 89417 44675 89418 44737 89418 43848 89418 44675 89419 43848 89419 44726 89419 44726 89420 43848 89420 44738 89420 44726 89421 44738 89421 44728 89421 45162 89422 44811 89422 44739 89422 44739 89423 44811 89423 44740 89423 44746 89424 44744 89424 45416 89424 44018 89425 45419 89425 44811 89425 44811 89426 45419 89426 45418 89426 44811 89427 45418 89427 44740 89427 44740 89428 45418 89428 45417 89428 44740 89429 45417 89429 45160 89429 45163 89430 44183 89430 44741 89430 44741 89431 44183 89431 44184 89431 44741 89432 44184 89432 44186 89432 44742 89433 44743 89433 45419 89433 45419 89434 44743 89434 44752 89434 45419 89435 44752 89435 45422 89435 45422 89436 44752 89436 45424 89436 45416 89437 44744 89437 45417 89437 45417 89438 44744 89438 45158 89438 45417 89439 45158 89439 45160 89439 44745 89440 43918 89440 44748 89440 44746 89441 45416 89441 44748 89441 44748 89442 45416 89442 43915 89442 44748 89443 43915 89443 44745 89443 44747 89444 44749 89444 43918 89444 43918 89445 44749 89445 44741 89445 43918 89446 44741 89446 44748 89446 44748 89447 44741 89447 44186 89447 44747 89448 44750 89448 44749 89448 44749 89449 44750 89449 44751 89449 44749 89450 44751 89450 44752 89450 44752 89451 44751 89451 44753 89451 44752 89452 44753 89452 45424 89452 44754 89453 44759 89453 44755 89453 43913 89454 44754 89454 44831 89454 44831 89455 44754 89455 44755 89455 44831 89456 44755 89456 44830 89456 44830 89457 44755 89457 44717 89457 44875 89458 43907 89458 44756 89458 44756 89459 43907 89459 44668 89459 44668 89460 43907 89460 44757 89460 44668 89461 44757 89461 44758 89461 44758 89462 44757 89462 43910 89462 44758 89463 43910 89463 44831 89463 44831 89464 43910 89464 43911 89464 44831 89465 43911 89465 43913 89465 44759 89466 44760 89466 44755 89466 44755 89467 44760 89467 44761 89467 44755 89468 44761 89468 44718 89468 44718 89469 44761 89469 45431 89469 44718 89470 45431 89470 44888 89470 44888 89471 45431 89471 44762 89471 44888 89472 44762 89472 45432 89472 44763 89473 44877 89473 44764 89473 44763 89474 44764 89474 44890 89474 44764 89475 43902 89475 44890 89475 44890 89476 43902 89476 43900 89476 44890 89477 43900 89477 44765 89477 44765 89478 43900 89478 44766 89478 44765 89479 44766 89479 45434 89479 45446 89480 43898 89480 44767 89480 44768 89481 45446 89481 44769 89481 44769 89482 45446 89482 44767 89482 44769 89483 44767 89483 44669 89483 45434 89484 45438 89484 44714 89484 44714 89485 45438 89485 44770 89485 44714 89486 44770 89486 44771 89486 44771 89487 44770 89487 45441 89487 44771 89488 45441 89488 44769 89488 44769 89489 45441 89489 45443 89489 44769 89490 45443 89490 44768 89490 44847 89491 44772 89491 44773 89491 44773 89492 44772 89492 44774 89492 44773 89493 44774 89493 45291 89493 44876 89494 45450 89494 37098 89494 44846 89495 44775 89495 43896 89495 43896 89496 44775 89496 44834 89496 43896 89497 44834 89497 43897 89497 43897 89498 44834 89498 45448 89498 44893 89499 45455 89499 45453 89499 44893 89500 45453 89500 44894 89500 44894 89501 45453 89501 45452 89501 44894 89502 45452 89502 44876 89502 43889 89503 43890 89503 44841 89503 44841 89504 43890 89504 44779 89504 44841 89505 44779 89505 44843 89505 45300 89506 44899 89506 45301 89506 45301 89507 44899 89507 44776 89507 45301 89508 44776 89508 44777 89508 44777 89509 44776 89509 44778 89509 44777 89510 44778 89510 44841 89510 44841 89511 44778 89511 43888 89511 44841 89512 43888 89512 43889 89512 44779 89513 44780 89513 44843 89513 44843 89514 44780 89514 44781 89514 44843 89515 44781 89515 44840 89515 44840 89516 44781 89516 45457 89516 44840 89517 45457 89517 37100 89517 37100 89518 45457 89518 44783 89518 37100 89519 44783 89519 44782 89519 44786 89520 43884 89520 44901 89520 44783 89521 44784 89521 44782 89521 44782 89522 44784 89522 44785 89522 44782 89523 44785 89523 44786 89523 44786 89524 44785 89524 43883 89524 44786 89525 43883 89525 43884 89525 45463 89526 44900 89526 44787 89526 44787 89527 44900 89527 44898 89527 44787 89528 44898 89528 44897 89528 45463 89529 44788 89529 44900 89529 44900 89530 44788 89530 45461 89530 44900 89531 45461 89531 44793 89531 44793 89532 45461 89532 44789 89532 44793 89533 44789 89533 44792 89533 44792 89534 44789 89534 44790 89534 44792 89535 44790 89535 45114 89535 45114 89536 44790 89536 45112 89536 44697 89537 44851 89537 45469 89537 45469 89538 44851 89538 44793 89538 44791 89539 45464 89539 44792 89539 44792 89540 45464 89540 45466 89540 44792 89541 45466 89541 44793 89541 44793 89542 45466 89542 45465 89542 44793 89543 45465 89543 45469 89543 43867 89544 43871 89544 44857 89544 44857 89545 43871 89545 43870 89545 44857 89546 43870 89546 37106 89546 37106 89547 43870 89547 44794 89547 37106 89548 44794 89548 44795 89548 44796 89549 43845 89549 44821 89549 43845 89550 44796 89550 43846 89550 43846 89551 44796 89551 44817 89551 43846 89552 44817 89552 43842 89552 44822 89553 44797 89553 44885 89553 44885 89554 44797 89554 45490 89554 44885 89555 45490 89555 44798 89555 44798 89556 45490 89556 44799 89556 44798 89557 44799 89557 44015 89557 44015 89558 44799 89558 44800 89558 44015 89559 44800 89559 44801 89559 44801 89560 44800 89560 45496 89560 44801 89561 45496 89561 44802 89561 44803 89562 45499 89562 44811 89562 44811 89563 45499 89563 44804 89563 44811 89564 44804 89564 44018 89564 44018 89565 44804 89565 44805 89565 44018 89566 44805 89566 44806 89566 44806 89567 44805 89567 44807 89567 44806 89568 44807 89568 44809 89568 44809 89569 44807 89569 44808 89569 44809 89570 44808 89570 44810 89570 44810 89571 44808 89571 44722 89571 44810 89572 44722 89572 44721 89572 45162 89573 45163 89573 44811 89573 44811 89574 45163 89574 44741 89574 44811 89575 44741 89575 44803 89575 44803 89576 44741 89576 43836 89576 44807 89577 44812 89577 44808 89577 44808 89578 44812 89578 44813 89578 44808 89579 44813 89579 44872 89579 44872 89580 44813 89580 44814 89580 44872 89581 44814 89581 43840 89581 43840 89582 44815 89582 44872 89582 44872 89583 44815 89583 43838 89583 44872 89584 43838 89584 44741 89584 44741 89585 43838 89585 43837 89585 44741 89586 43837 89586 43836 89586 44816 89587 44163 89587 44818 89587 43842 89588 44817 89588 44818 89588 44818 89589 44817 89589 44883 89589 44818 89590 44883 89590 44816 89590 44163 89591 45183 89591 44818 89591 44818 89592 45183 89592 45184 89592 44818 89593 45184 89593 44672 89593 44672 89594 45184 89594 45186 89594 44672 89595 45186 89595 44819 89595 44819 89596 45186 89596 45188 89596 44819 89597 45188 89597 44011 89597 44011 89598 45188 89598 45190 89598 44011 89599 45190 89599 44727 89599 44820 89600 44796 89600 44885 89600 44885 89601 44796 89601 44821 89601 44885 89602 44821 89602 44822 89602 44820 89603 44171 89603 44796 89603 44796 89604 44171 89604 44823 89604 44796 89605 44823 89605 37115 89605 44825 89606 44771 89606 44197 89606 44197 89607 44771 89607 44769 89607 44197 89608 44769 89608 44824 89608 44824 89609 44769 89609 37097 89609 44824 89610 37097 89610 44194 89610 44825 89611 44198 89611 44771 89611 44771 89612 44198 89612 45145 89612 44771 89613 45145 89613 44828 89613 44828 89614 45145 89614 44826 89614 44828 89615 44826 89615 44827 89615 44827 89616 44829 89616 44828 89616 44828 89617 44829 89617 44831 89617 44828 89618 44831 89618 44023 89618 44023 89619 44831 89619 44830 89619 44829 89620 45149 89620 44831 89620 44831 89621 45149 89621 44832 89621 44831 89622 44832 89622 44758 89622 44758 89623 44832 89623 45150 89623 44758 89624 45150 89624 37097 89624 37097 89625 45150 89625 44833 89625 37097 89626 44833 89626 44194 89626 44834 89627 45126 89627 44837 89627 45450 89628 45448 89628 37098 89628 37098 89629 45448 89629 44834 89629 37098 89630 44834 89630 44835 89630 44835 89631 44834 89631 44838 89631 44222 89632 44223 89632 44836 89632 44834 89633 44837 89633 44838 89633 44838 89634 44837 89634 44839 89634 44838 89635 44839 89635 44840 89635 44840 89636 44839 89636 44218 89636 44840 89637 44218 89637 44843 89637 44843 89638 44218 89638 44219 89638 44843 89639 44219 89639 44844 89639 45295 89640 44841 89640 44842 89640 44842 89641 44841 89641 44843 89641 44842 89642 44843 89642 44836 89642 44836 89643 44843 89643 44844 89643 44836 89644 44844 89644 44222 89644 44223 89645 44845 89645 44836 89645 44836 89646 44845 89646 44775 89646 44836 89647 44775 89647 44773 89647 44773 89648 44775 89648 44846 89648 44773 89649 44846 89649 44847 89649 44845 89650 44848 89650 44775 89650 44775 89651 44848 89651 44849 89651 44775 89652 44849 89652 44834 89652 44834 89653 44849 89653 44850 89653 44834 89654 44850 89654 45126 89654 44853 89655 44852 89655 44699 89655 44697 89656 44699 89656 44851 89656 44851 89657 44699 89657 44852 89657 44851 89658 44852 89658 44878 89658 44853 89659 44699 89659 44854 89659 44854 89660 44699 89660 44855 89660 44854 89661 44855 89661 44242 89661 44864 89662 44856 89662 44865 89662 37106 89663 44858 89663 44857 89663 44857 89664 44858 89664 44859 89664 44857 89665 44859 89665 44860 89665 44860 89666 44859 89666 44861 89666 44860 89667 44861 89667 44855 89667 44855 89668 44861 89668 44862 89668 44855 89669 44862 89669 44242 89669 44863 89670 44864 89670 37105 89670 37105 89671 44864 89671 44865 89671 37105 89672 44865 89672 37106 89672 37106 89673 44865 89673 45103 89673 37106 89674 45103 89674 44858 89674 44256 89675 44880 89675 44866 89675 44794 89676 44867 89676 44795 89676 44795 89677 44867 89677 44866 89677 44795 89678 44866 89678 37108 89678 37108 89679 44866 89679 44880 89679 44250 89680 44252 89680 44685 89680 44685 89681 44252 89681 44253 89681 44685 89682 44253 89682 44686 89682 44686 89683 44253 89683 44255 89683 44686 89684 44255 89684 44866 89684 44866 89685 44255 89685 44868 89685 44866 89686 44868 89686 44256 89686 44823 89687 44869 89687 37115 89687 37115 89688 44869 89688 44175 89688 37115 89689 44175 89689 44870 89689 44870 89690 44175 89690 44872 89690 44870 89691 44872 89691 44871 89691 44871 89692 44872 89692 44741 89692 44871 89693 44741 89693 37092 89693 37092 89694 44741 89694 44749 89694 37092 89695 44749 89695 44873 89695 44874 89696 44888 89696 44756 89696 44756 89697 44888 89697 45432 89697 44756 89698 45432 89698 44875 89698 44876 89699 37098 89699 44894 89699 44894 89700 37098 89700 44767 89700 44894 89701 44767 89701 44763 89701 44763 89702 44767 89702 43898 89702 44763 89703 43898 89703 44877 89703 44878 89704 44856 89704 44851 89704 44851 89705 44856 89705 44864 89705 44851 89706 44864 89706 44793 89706 44793 89707 44864 89707 37102 89707 44793 89708 37102 89708 44900 89708 44900 89709 37102 89709 44879 89709 44900 89710 44879 89710 44786 89710 44786 89711 44879 89711 37101 89711 44786 89712 37101 89712 44782 89712 44880 89713 44881 89713 37108 89713 37108 89714 44881 89714 44681 89714 37108 89715 44681 89715 37109 89715 37109 89716 44681 89716 44676 89716 37109 89717 44676 89717 37110 89717 37110 89718 44676 89718 44675 89718 37110 89719 44675 89719 44882 89719 44882 89720 44675 89720 44726 89720 44882 89721 44726 89721 44883 89721 44883 89722 44726 89722 44671 89722 44883 89723 44671 89723 44816 89723 44169 89724 44820 89724 44884 89724 44884 89725 44820 89725 44885 89725 44884 89726 44885 89726 44723 89726 44723 89727 44885 89727 44798 89727 44723 89728 44798 89728 44673 89728 44673 89729 44798 89729 44015 89729 44886 89730 44022 89730 44887 89730 44887 89731 44022 89731 44718 89731 44887 89732 44718 89732 44749 89732 44749 89733 44718 89733 44888 89733 44749 89734 44888 89734 44873 89734 44873 89735 44888 89735 44874 89735 44212 89736 44213 89736 44893 89736 44893 89737 44213 89737 45133 89737 44889 89738 45134 89738 44890 89738 44890 89739 45134 89739 44891 89739 44890 89740 44891 89740 44763 89740 44763 89741 44891 89741 45135 89741 44774 89742 44892 89742 45291 89742 45291 89743 44892 89743 45455 89743 45291 89744 45455 89744 44027 89744 44027 89745 45455 89745 44893 89745 44027 89746 44893 89746 44890 89746 44890 89747 44893 89747 45133 89747 44890 89748 45133 89748 44889 89748 44212 89749 44893 89749 44211 89749 44211 89750 44893 89750 44894 89750 44211 89751 44894 89751 44208 89751 45135 89752 44895 89752 44763 89752 44763 89753 44895 89753 45137 89753 44763 89754 45137 89754 44894 89754 44894 89755 45137 89755 44206 89755 44894 89756 44206 89756 44208 89756 44695 89757 44694 89757 44855 89757 44855 89758 44694 89758 44693 89758 44855 89759 44693 89759 44860 89759 44860 89760 44693 89760 44896 89760 44860 89761 44896 89761 44857 89761 44857 89762 44896 89762 44674 89762 44857 89763 44674 89763 43867 89763 43879 89764 44897 89764 45300 89764 45300 89765 44897 89765 44898 89765 45300 89766 44898 89766 44899 89766 44899 89767 44898 89767 44900 89767 44899 89768 44900 89768 44776 89768 44776 89769 44900 89769 44786 89769 44776 89770 44786 89770 44778 89770 44778 89771 44786 89771 44901 89771 44778 89772 44901 89772 43888 89772 44902 89773 44664 89773 44663 89773 44663 89774 44903 89774 44902 89774 44902 89775 44903 89775 45063 89775 44902 89776 45063 89776 44905 89776 44905 89777 45063 89777 44904 89777 45067 89778 45296 89778 45293 89778 44904 89779 45062 89779 44905 89779 44905 89780 45062 89780 44906 89780 44905 89781 44906 89781 45293 89781 45293 89782 44906 89782 44907 89782 45293 89783 44907 89783 45067 89783 45070 89784 44912 89784 44909 89784 45067 89785 45065 89785 45296 89785 45296 89786 45065 89786 45064 89786 45296 89787 45064 89787 44909 89787 44909 89788 45064 89788 44908 89788 44909 89789 44908 89789 45070 89789 44916 89790 44910 89790 44913 89790 45070 89791 44911 89791 44912 89791 44912 89792 44911 89792 44914 89792 44912 89793 44914 89793 44913 89793 44913 89794 44914 89794 44915 89794 44913 89795 44915 89795 44916 89795 44916 89796 45073 89796 44910 89796 44910 89797 45073 89797 45075 89797 44910 89798 45075 89798 44917 89798 45075 89799 45076 89799 44917 89799 44917 89800 45076 89800 45077 89800 44917 89801 45077 89801 45302 89801 45077 89802 44918 89802 45302 89802 45302 89803 44918 89803 45079 89803 45302 89804 45079 89804 44919 89804 45079 89805 45080 89805 44919 89805 44919 89806 45080 89806 44920 89806 44919 89807 44920 89807 45304 89807 44920 89808 45081 89808 45304 89808 45304 89809 45081 89809 44921 89809 45304 89810 44921 89810 45306 89810 44921 89811 45083 89811 45306 89811 45306 89812 45083 89812 44922 89812 45306 89813 44922 89813 44925 89813 44923 89814 45308 89814 44924 89814 44924 89815 45308 89815 44925 89815 44924 89816 44925 89816 45085 89816 45085 89817 44925 89817 44922 89817 44645 89818 45335 89818 44926 89818 44645 89819 44926 89819 44597 89819 44597 89820 44926 89820 45333 89820 44597 89821 45333 89821 44927 89821 44927 89822 45333 89822 45330 89822 44927 89823 45330 89823 44928 89823 44928 89824 45330 89824 45319 89824 44928 89825 45319 89825 44608 89825 44608 89826 45319 89826 45320 89826 44608 89827 45320 89827 44607 89827 44607 89828 45320 89828 45322 89828 44607 89829 45322 89829 44929 89829 44929 89830 45322 89830 45323 89830 44929 89831 45323 89831 44930 89831 44930 89832 45323 89832 45326 89832 44930 89833 45326 89833 44931 89833 44931 89834 45326 89834 45328 89834 44931 89835 45328 89835 44603 89835 44603 89836 45328 89836 45318 89836 44603 89837 45318 89837 44932 89837 44932 89838 45318 89838 44933 89838 44932 89839 44933 89839 44601 89839 44601 89840 44933 89840 45315 89840 44601 89841 45315 89841 44934 89841 44934 89842 45315 89842 45313 89842 44934 89843 45313 89843 44614 89843 44614 89844 45313 89844 45312 89844 44614 89845 45312 89845 44935 89845 44935 89846 45312 89846 44010 89846 44935 89847 44010 89847 44612 89847 44613 89848 44594 89848 44936 89848 44613 89849 44936 89849 44615 89849 44615 89850 44936 89850 44937 89850 44615 89851 44937 89851 44938 89851 44938 89852 44937 89852 44972 89852 44938 89853 44972 89853 44939 89853 44939 89854 44972 89854 44970 89854 44939 89855 44970 89855 44600 89855 44600 89856 44970 89856 44968 89856 44600 89857 44968 89857 44940 89857 44940 89858 44968 89858 44967 89858 44940 89859 44967 89859 44602 89859 44602 89860 44967 89860 44966 89860 44602 89861 44966 89861 44604 89861 44604 89862 44966 89862 44964 89862 44604 89863 44964 89863 44605 89863 44605 89864 44964 89864 44941 89864 44605 89865 44941 89865 44606 89865 44606 89866 44941 89866 44960 89866 44606 89867 44960 89867 44942 89867 44942 89868 44960 89868 44959 89868 44942 89869 44959 89869 44943 89869 44943 89870 44959 89870 44944 89870 44943 89871 44944 89871 44945 89871 44945 89872 44944 89872 44946 89872 44945 89873 44946 89873 44947 89873 44947 89874 44946 89874 44949 89874 44947 89875 44949 89875 44948 89875 44948 89876 44949 89876 44955 89876 44948 89877 44955 89877 44596 89877 44596 89878 44955 89878 44950 89878 44596 89879 44950 89879 44951 89879 44951 89880 44950 89880 44952 89880 44951 89881 44952 89881 44953 89881 44953 89882 44952 89882 44581 89882 44953 89883 44581 89883 44598 89883 43834 89884 44581 89884 44952 89884 43834 89885 44952 89885 45500 89885 45500 89886 44952 89886 44950 89886 45500 89887 44950 89887 44954 89887 44954 89888 44950 89888 44955 89888 44954 89889 44955 89889 45503 89889 45503 89890 44955 89890 44949 89890 45503 89891 44949 89891 44956 89891 44956 89892 44949 89892 44946 89892 44956 89893 44946 89893 44957 89893 44957 89894 44946 89894 44944 89894 44957 89895 44944 89895 44958 89895 44958 89896 44944 89896 44959 89896 44958 89897 44959 89897 44961 89897 44961 89898 44959 89898 44960 89898 44961 89899 44960 89899 44962 89899 44962 89900 44960 89900 44941 89900 44962 89901 44941 89901 44963 89901 44963 89902 44941 89902 44964 89902 44963 89903 44964 89903 44965 89903 44965 89904 44964 89904 44966 89904 44965 89905 44966 89905 45510 89905 45510 89906 44966 89906 44967 89906 45510 89907 44967 89907 45512 89907 45512 89908 44967 89908 44968 89908 45512 89909 44968 89909 44969 89909 44969 89910 44968 89910 44970 89910 44969 89911 44970 89911 44971 89911 44971 89912 44970 89912 44972 89912 44971 89913 44972 89913 45514 89913 45514 89914 44972 89914 44937 89914 45514 89915 44937 89915 44973 89915 44973 89916 44937 89916 44936 89916 44973 89917 44936 89917 44974 89917 44974 89918 44936 89918 44594 89918 44974 89919 44594 89919 45517 89919 43784 89920 44556 89920 44975 89920 43784 89921 44975 89921 44976 89921 44976 89922 44975 89922 44557 89922 44976 89923 44557 89923 44977 89923 44977 89924 44557 89924 44558 89924 44977 89925 44558 89925 44978 89925 44978 89926 44558 89926 44560 89926 44978 89927 44560 89927 45559 89927 45559 89928 44560 89928 44561 89928 45559 89929 44561 89929 44979 89929 44979 89930 44561 89930 44524 89930 44979 89931 44524 89931 45561 89931 45561 89932 44524 89932 44525 89932 45561 89933 44525 89933 44980 89933 44980 89934 44525 89934 44981 89934 44980 89935 44981 89935 45563 89935 45563 89936 44981 89936 44526 89936 45563 89937 44526 89937 44982 89937 44982 89938 44526 89938 44527 89938 44982 89939 44527 89939 44983 89939 44983 89940 44527 89940 44529 89940 44983 89941 44529 89941 44984 89941 44984 89942 44529 89942 44531 89942 44984 89943 44531 89943 45564 89943 45564 89944 44531 89944 44985 89944 45564 89945 44985 89945 44986 89945 44986 89946 44985 89946 44987 89946 44986 89947 44987 89947 44988 89947 44988 89948 44987 89948 44989 89948 44988 89949 44989 89949 44990 89949 44990 89950 44989 89950 44991 89950 44990 89951 44991 89951 45566 89951 45566 89952 44991 89952 44992 89952 45566 89953 44992 89953 44993 89953 44993 89954 44992 89954 44535 89954 44993 89955 44535 89955 45568 89955 44463 89956 44464 89956 44994 89956 44994 89957 44464 89957 44443 89957 44994 89958 44443 89958 45583 89958 45583 89959 44443 89959 44441 89959 45583 89960 44441 89960 45582 89960 45582 89961 44441 89961 44440 89961 45582 89962 44440 89962 44995 89962 44995 89963 44440 89963 44996 89963 44995 89964 44996 89964 44997 89964 44997 89965 44996 89965 44437 89965 44997 89966 44437 89966 45578 89966 45578 89967 44437 89967 44999 89967 45578 89968 44999 89968 44998 89968 44998 89969 44999 89969 44436 89969 44998 89970 44436 89970 45000 89970 45000 89971 44436 89971 44434 89971 45000 89972 44434 89972 45001 89972 45001 89973 44434 89973 44433 89973 45001 89974 44433 89974 45002 89974 45002 89975 44433 89975 45003 89975 45002 89976 45003 89976 45575 89976 45575 89977 45003 89977 44432 89977 45575 89978 44432 89978 45574 89978 45574 89979 44432 89979 44431 89979 45574 89980 44431 89980 45004 89980 45004 89981 44431 89981 45005 89981 45004 89982 45005 89982 45572 89982 45572 89983 45005 89983 44430 89983 45572 89984 44430 89984 45006 89984 45006 89985 44430 89985 45008 89985 45006 89986 45008 89986 45007 89986 45007 89987 45008 89987 44427 89987 45007 89988 44427 89988 45569 89988 45569 89989 44427 89989 44426 89989 44420 89990 45009 89990 45010 89990 45010 89991 45009 89991 45011 89991 45010 89992 45011 89992 45602 89992 45602 89993 45011 89993 44386 89993 45602 89994 44386 89994 45601 89994 45601 89995 44386 89995 45013 89995 45601 89996 45013 89996 45012 89996 45012 89997 45013 89997 45014 89997 45012 89998 45014 89998 45015 89998 45015 89999 45014 89999 45016 89999 45015 90000 45016 90000 45597 90000 45597 90001 45016 90001 44383 90001 45597 90002 44383 90002 45017 90002 45017 90003 44383 90003 44382 90003 45017 90004 44382 90004 45594 90004 45594 90005 44382 90005 45018 90005 45594 90006 45018 90006 45019 90006 45019 90007 45018 90007 44380 90007 45019 90008 44380 90008 45020 90008 45020 90009 44380 90009 45022 90009 45020 90010 45022 90010 45021 90010 45021 90011 45022 90011 45023 90011 45021 90012 45023 90012 45024 90012 45024 90013 45023 90013 45025 90013 45024 90014 45025 90014 45589 90014 45589 90015 45025 90015 45026 90015 45589 90016 45026 90016 45588 90016 45588 90017 45026 90017 45027 90017 45588 90018 45027 90018 45028 90018 45028 90019 45027 90019 45029 90019 45028 90020 45029 90020 45586 90020 45586 90021 45029 90021 45030 90021 45586 90022 45030 90022 45031 90022 45031 90023 45030 90023 44374 90023 45032 90024 44388 90024 45033 90024 45032 90025 45033 90025 45540 90025 45540 90026 45033 90026 45034 90026 45540 90027 45034 90027 45035 90027 45035 90028 45034 90028 44391 90028 45035 90029 44391 90029 45036 90029 45036 90030 44391 90030 45037 90030 45036 90031 45037 90031 45544 90031 45544 90032 45037 90032 44395 90032 45544 90033 44395 90033 45545 90033 45545 90034 44395 90034 44397 90034 45545 90035 44397 90035 45546 90035 45546 90036 44397 90036 44398 90036 45546 90037 44398 90037 45038 90037 45038 90038 44398 90038 45039 90038 45038 90039 45039 90039 45040 90039 45040 90040 45039 90040 44400 90040 45040 90041 44400 90041 45041 90041 45041 90042 44400 90042 44401 90042 45041 90043 44401 90043 45549 90043 45549 90044 44401 90044 44402 90044 45549 90045 44402 90045 45551 90045 45551 90046 44402 90046 44403 90046 45551 90047 44403 90047 45552 90047 45552 90048 44403 90048 44404 90048 45552 90049 44404 90049 45553 90049 45553 90050 44404 90050 44406 90050 45553 90051 44406 90051 45042 90051 45042 90052 44406 90052 44407 90052 45042 90053 44407 90053 45043 90053 45043 90054 44407 90054 45044 90054 45043 90055 45044 90055 45045 90055 45045 90056 45044 90056 44372 90056 45045 90057 44372 90057 44357 90057 45538 90058 45046 90058 45537 90058 45537 90059 45046 90059 45047 90059 45537 90060 45047 90060 45535 90060 45535 90061 45047 90061 45048 90061 45535 90062 45048 90062 45534 90062 45534 90063 45048 90063 44300 90063 45534 90064 44300 90064 45533 90064 45533 90065 44300 90065 44299 90065 45533 90066 44299 90066 45532 90066 45532 90067 44299 90067 45049 90067 45532 90068 45049 90068 45530 90068 45530 90069 45049 90069 45050 90069 45530 90070 45050 90070 45528 90070 45528 90071 45050 90071 44296 90071 45528 90072 44296 90072 45051 90072 45051 90073 44296 90073 45052 90073 45051 90074 45052 90074 45525 90074 45525 90075 45052 90075 45053 90075 45525 90076 45053 90076 45524 90076 45524 90077 45053 90077 45054 90077 45524 90078 45054 90078 45055 90078 45055 90079 45054 90079 45056 90079 45055 90080 45056 90080 45523 90080 45523 90081 45056 90081 45057 90081 45523 90082 45057 90082 45522 90082 45522 90083 45057 90083 44293 90083 45522 90084 44293 90084 45521 90084 45521 90085 44293 90085 45058 90085 45521 90086 45058 90086 45519 90086 45519 90087 45058 90087 44292 90087 45519 90088 44292 90088 45059 90088 45059 90089 44292 90089 45060 90089 45059 90090 45060 90090 45061 90090 45061 90091 45060 90091 44290 90091 44915 90092 44914 90092 45072 90092 44302 90093 44303 90093 44663 90093 44663 90094 44303 90094 44903 90094 44305 90095 45068 90095 44906 90095 44906 90096 45062 90096 44305 90096 44305 90097 45062 90097 44904 90097 44305 90098 44904 90098 44303 90098 44303 90099 44904 90099 45063 90099 44303 90100 45063 90100 44903 90100 45066 90101 45071 90101 45064 90101 45064 90102 45065 90102 45066 90102 45066 90103 45065 90103 45067 90103 45066 90104 45067 90104 45068 90104 45068 90105 45067 90105 44907 90105 45068 90106 44907 90106 44906 90106 45072 90107 44914 90107 45069 90107 44914 90108 44911 90108 45069 90108 45069 90109 44911 90109 45070 90109 45069 90110 45070 90110 45071 90110 45071 90111 45070 90111 44908 90111 45071 90112 44908 90112 45064 90112 44915 90113 45072 90113 44916 90113 44916 90114 45072 90114 44308 90114 44916 90115 44308 90115 45073 90115 45073 90116 44308 90116 45074 90116 45073 90117 45074 90117 45075 90117 45075 90118 45074 90118 45076 90118 45076 90119 45074 90119 44283 90119 45076 90120 44283 90120 45077 90120 45077 90121 44283 90121 44918 90121 44918 90122 44283 90122 45078 90122 44918 90123 45078 90123 45079 90123 45079 90124 45078 90124 45080 90124 45080 90125 45078 90125 44285 90125 45080 90126 44285 90126 44920 90126 44920 90127 44285 90127 45081 90127 45081 90128 44285 90128 45082 90128 45081 90129 45082 90129 44921 90129 44921 90130 45082 90130 45083 90130 45083 90131 45082 90131 45084 90131 45083 90132 45084 90132 44922 90132 44922 90133 45084 90133 45085 90133 45085 90134 45084 90134 45086 90134 45085 90135 45086 90135 44924 90135 44924 90136 45086 90136 45087 90136 44924 90137 45087 90137 44923 90137 44880 90138 45088 90138 44881 90138 44881 90139 45088 90139 45089 90139 44881 90140 45089 90140 45090 90140 45090 90141 45089 90141 45095 90141 45090 90142 45095 90142 45091 90142 45091 90143 45095 90143 45092 90143 45091 90144 45092 90144 44682 90144 44682 90145 45092 90145 45098 90145 44682 90146 45098 90146 44683 90146 44683 90147 45098 90147 45099 90147 44683 90148 45099 90148 44249 90148 44249 90149 45099 90149 45093 90149 45088 90150 45094 90150 45089 90150 45089 90151 45094 90151 45783 90151 45089 90152 45783 90152 45095 90152 45095 90153 45783 90153 45096 90153 45095 90154 45096 90154 45092 90154 45092 90155 45096 90155 45636 90155 45092 90156 45636 90156 45098 90156 45098 90157 45636 90157 45097 90157 45098 90158 45097 90158 45099 90158 45099 90159 45097 90159 45638 90159 45099 90160 45638 90160 45093 90160 45093 90161 45638 90161 44245 90161 44878 90162 45100 90162 44856 90162 44856 90163 45100 90163 45101 90163 44856 90164 45101 90164 44865 90164 44865 90165 45101 90165 45102 90165 44865 90166 45102 90166 45103 90166 45103 90167 45102 90167 45104 90167 45103 90168 45104 90168 44858 90168 44858 90169 45104 90169 45108 90169 44858 90170 45108 90170 44859 90170 44859 90171 45108 90171 45105 90171 44859 90172 45105 90172 44861 90172 44861 90173 45105 90173 44241 90173 45796 90174 44241 90174 45797 90174 45797 90175 44241 90175 45105 90175 45100 90176 45787 90176 45101 90176 45101 90177 45787 90177 45106 90177 45101 90178 45106 90178 45102 90178 45102 90179 45106 90179 45107 90179 45102 90180 45107 90180 45104 90180 45104 90181 45107 90181 45109 90181 45104 90182 45109 90182 45108 90182 45108 90183 45109 90183 45738 90183 45108 90184 45738 90184 45105 90184 45105 90185 45738 90185 45741 90185 45105 90186 45741 90186 45797 90186 44234 90187 44227 90187 45110 90187 45110 90188 44227 90188 45111 90188 45110 90189 45111 90189 45112 90189 45112 90190 45111 90190 45113 90190 45112 90191 45113 90191 45114 90191 45114 90192 45113 90192 45115 90192 45114 90193 45115 90193 45116 90193 45116 90194 45115 90194 45119 90194 45116 90195 45119 90195 44704 90195 44704 90196 45119 90196 45123 90196 44704 90197 45123 90197 44705 90197 44705 90198 45123 90198 44228 90198 44227 90199 45623 90199 45111 90199 45111 90200 45623 90200 45117 90200 45111 90201 45117 90201 45113 90201 45113 90202 45117 90202 45118 90202 45113 90203 45118 90203 45115 90203 45115 90204 45118 90204 45120 90204 45115 90205 45120 90205 45119 90205 45119 90206 45120 90206 45121 90206 45119 90207 45121 90207 45123 90207 45123 90208 45121 90208 45122 90208 45123 90209 45122 90209 44228 90209 44228 90210 45122 90210 44224 90210 44845 90211 45124 90211 44848 90211 44848 90212 45124 90212 45125 90212 44848 90213 45125 90213 44849 90213 44849 90214 45125 90214 45128 90214 44849 90215 45128 90215 44850 90215 44850 90216 45128 90216 45130 90216 44850 90217 45130 90217 45126 90217 45126 90218 45130 90218 45127 90218 45126 90219 45127 90219 44837 90219 44837 90220 45127 90220 45131 90220 44837 90221 45131 90221 44839 90221 44839 90222 45131 90222 45132 90222 45124 90223 45805 90223 45125 90223 45125 90224 45805 90224 45129 90224 45125 90225 45129 90225 45128 90225 45128 90226 45129 90226 45677 90226 45128 90227 45677 90227 45130 90227 45130 90228 45677 90228 45678 90228 45130 90229 45678 90229 45127 90229 45127 90230 45678 90230 45604 90230 45127 90231 45604 90231 45131 90231 45131 90232 45604 90232 45815 90232 45131 90233 45815 90233 45132 90233 45132 90234 45815 90234 45798 90234 45133 90235 44205 90235 44889 90235 44889 90236 44205 90236 45139 90236 44889 90237 45139 90237 45134 90237 45134 90238 45139 90238 45140 90238 45134 90239 45140 90239 44891 90239 44891 90240 45140 90240 45143 90240 44891 90241 45143 90241 45135 90241 45135 90242 45143 90242 45136 90242 45135 90243 45136 90243 44895 90243 44895 90244 45136 90244 45144 90244 44895 90245 45144 90245 45137 90245 45137 90246 45144 90246 45138 90246 44205 90247 45779 90247 45139 90247 45139 90248 45779 90248 45141 90248 45139 90249 45141 90249 45140 90249 45140 90250 45141 90250 45777 90250 45140 90251 45777 90251 45143 90251 45143 90252 45777 90252 45142 90252 45143 90253 45142 90253 45136 90253 45136 90254 45142 90254 45776 90254 45136 90255 45776 90255 45144 90255 45144 90256 45776 90256 45773 90256 45144 90257 45773 90257 45138 90257 45138 90258 45773 90258 45775 90258 45145 90259 45146 90259 44826 90259 44826 90260 45146 90260 45147 90260 44826 90261 45147 90261 44827 90261 44827 90262 45147 90262 45148 90262 44827 90263 45148 90263 44829 90263 44829 90264 45148 90264 45152 90264 44829 90265 45152 90265 45149 90265 45149 90266 45152 90266 45154 90266 45149 90267 45154 90267 44832 90267 44832 90268 45154 90268 45155 90268 44832 90269 45155 90269 45150 90269 45150 90270 45155 90270 45157 90270 45150 90271 45157 90271 44833 90271 44833 90272 45157 90272 44195 90272 45146 90273 45151 90273 45147 90273 45147 90274 45151 90274 45690 90274 45147 90275 45690 90275 45148 90275 45148 90276 45690 90276 45153 90276 45148 90277 45153 90277 45152 90277 45152 90278 45153 90278 45688 90278 45152 90279 45688 90279 45154 90279 45154 90280 45688 90280 45766 90280 45154 90281 45766 90281 45155 90281 45155 90282 45766 90282 45156 90282 45155 90283 45156 90283 45157 90283 45157 90284 45156 90284 45768 90284 45157 90285 45768 90285 44195 90285 44195 90286 45768 90286 44188 90286 44744 90287 44182 90287 45158 90287 45158 90288 44182 90288 45159 90288 45158 90289 45159 90289 45160 90289 45160 90290 45159 90290 45161 90290 45160 90291 45161 90291 44740 90291 44740 90292 45161 90292 45167 90292 44740 90293 45167 90293 44739 90293 44739 90294 45167 90294 45168 90294 44739 90295 45168 90295 45162 90295 45162 90296 45168 90296 45164 90296 45162 90297 45164 90297 45163 90297 45163 90298 45164 90298 45165 90298 44182 90299 45166 90299 45159 90299 45159 90300 45166 90300 45707 90300 45159 90301 45707 90301 45161 90301 45161 90302 45707 90302 45706 90302 45161 90303 45706 90303 45167 90303 45167 90304 45706 90304 45662 90304 45167 90305 45662 90305 45168 90305 45168 90306 45662 90306 45169 90306 45168 90307 45169 90307 45164 90307 45164 90308 45169 90308 45170 90308 45164 90309 45170 90309 45165 90309 45165 90310 45170 90310 45171 90310 45172 90311 45173 90311 45174 90311 45174 90312 45173 90312 45177 90312 45174 90313 45177 90313 44722 90313 44722 90314 45177 90314 45175 90314 44722 90315 45175 90315 44721 90315 44721 90316 45175 90316 45178 90316 44721 90317 45178 90317 45176 90317 45176 90318 45178 90318 45179 90318 45176 90319 45179 90319 44720 90319 44720 90320 45179 90320 45181 90320 44720 90321 45181 90321 44169 90321 44169 90322 45181 90322 44170 90322 45173 90323 45761 90323 45177 90323 45177 90324 45761 90324 45759 90324 45177 90325 45759 90325 45175 90325 45175 90326 45759 90326 45758 90326 45175 90327 45758 90327 45178 90327 45178 90328 45758 90328 45756 90328 45178 90329 45756 90329 45179 90329 45179 90330 45756 90330 45180 90330 45179 90331 45180 90331 45181 90331 45181 90332 45180 90332 45182 90332 45181 90333 45182 90333 44170 90333 44170 90334 45182 90334 45754 90334 44163 90335 44164 90335 45183 90335 45183 90336 44164 90336 45193 90336 45183 90337 45193 90337 45184 90337 45184 90338 45193 90338 45185 90338 45184 90339 45185 90339 45186 90339 45186 90340 45185 90340 45187 90340 45186 90341 45187 90341 45188 90341 45188 90342 45187 90342 45189 90342 45188 90343 45189 90343 45190 90343 45190 90344 45189 90344 45191 90344 45190 90345 45191 90345 44727 90345 44727 90346 45191 90346 44155 90346 44164 90347 45192 90347 45193 90347 45193 90348 45192 90348 45194 90348 45193 90349 45194 90349 45185 90349 45185 90350 45194 90350 45728 90350 45185 90351 45728 90351 45187 90351 45187 90352 45728 90352 45723 90352 45187 90353 45723 90353 45189 90353 45189 90354 45723 90354 45722 90354 45189 90355 45722 90355 45191 90355 45191 90356 45722 90356 45720 90356 45191 90357 45720 90357 44155 90357 44155 90358 45720 90358 44157 90358 45481 90359 43932 90359 45195 90359 45195 90360 43932 90360 45196 90360 45195 90361 45196 90361 45197 90361 45197 90362 45196 90362 45395 90362 45197 90363 45395 90363 45198 90363 45198 90364 45395 90364 45200 90364 45198 90365 45200 90365 45199 90365 45199 90366 45200 90366 45201 90366 45199 90367 45201 90367 45202 90367 45202 90368 45201 90368 45399 90368 45202 90369 45399 90369 43861 90369 43861 90370 45399 90370 45203 90370 45204 90371 43931 90371 45400 90371 45204 90372 45400 90372 45472 90372 45472 90373 45400 90373 45205 90373 45472 90374 45205 90374 45206 90374 45206 90375 45205 90375 45207 90375 45207 90376 45205 90376 45402 90376 45207 90377 45402 90377 45208 90377 45208 90378 45402 90378 45473 90378 45473 90379 45402 90379 45404 90379 45473 90380 45404 90380 45209 90380 45209 90381 45404 90381 45210 90381 45210 90382 45404 90382 45212 90382 45210 90383 45212 90383 45211 90383 45211 90384 45212 90384 45406 90384 45211 90385 45406 90385 45213 90385 45213 90386 45406 90386 45408 90386 45213 90387 45408 90387 44132 90387 44131 90388 45214 90388 45215 90388 44131 90389 45215 90389 45216 90389 45216 90390 45215 90390 45217 90390 45216 90391 45217 90391 45467 90391 45467 90392 45217 90392 45468 90392 45468 90393 45217 90393 45410 90393 45468 90394 45410 90394 45218 90394 45218 90395 45410 90395 45219 90395 45219 90396 45410 90396 45412 90396 45219 90397 45412 90397 45220 90397 45220 90398 45412 90398 45471 90398 45471 90399 45412 90399 45413 90399 45471 90400 45413 90400 45221 90400 45221 90401 45413 90401 45223 90401 45221 90402 45223 90402 45222 90402 45222 90403 45223 90403 44119 90403 45222 90404 44119 90404 43873 90404 44116 90405 45339 90405 45224 90405 44116 90406 45224 90406 45225 90406 45225 90407 45224 90407 45341 90407 45225 90408 45341 90408 45462 90408 45462 90409 45341 90409 45227 90409 45462 90410 45227 90410 45226 90410 45227 90411 45228 90411 45226 90411 45226 90412 45228 90412 45229 90412 45226 90413 45229 90413 45230 90413 45229 90414 45231 90414 45230 90414 45230 90415 45231 90415 45338 90415 45230 90416 45338 90416 45234 90416 45338 90417 45232 90417 45234 90417 45234 90418 45232 90418 45233 90418 45234 90419 45233 90419 45460 90419 45460 90420 45233 90420 43998 90420 45460 90421 43998 90421 45459 90421 43891 90422 45343 90422 45235 90422 45235 90423 45343 90423 45236 90423 45235 90424 45236 90424 45458 90424 45458 90425 45236 90425 45237 90425 45458 90426 45237 90426 45238 90426 45238 90427 45237 90427 45239 90427 45238 90428 45239 90428 45240 90428 45240 90429 45239 90429 45346 90429 45240 90430 45346 90430 45241 90430 45241 90431 45346 90431 45348 90431 45241 90432 45348 90432 45242 90432 45242 90433 45348 90433 44098 90433 45456 90434 44096 90434 45454 90434 45454 90435 44096 90435 45349 90435 45454 90436 45349 90436 45243 90436 45243 90437 45349 90437 45244 90437 45243 90438 45244 90438 45451 90438 45451 90439 45244 90439 45246 90439 45451 90440 45246 90440 45245 90440 45245 90441 45246 90441 45352 90441 45245 90442 45352 90442 45449 90442 45449 90443 45352 90443 45353 90443 45449 90444 45353 90444 45247 90444 45247 90445 45353 90445 43986 90445 45248 90446 45249 90446 45433 90446 45433 90447 45249 90447 45354 90447 45433 90448 45354 90448 45436 90448 45436 90449 45354 90449 45250 90449 45250 90450 45354 90450 45251 90450 45250 90451 45251 90451 45437 90451 45437 90452 45251 90452 45439 90452 45439 90453 45251 90453 45356 90453 45439 90454 45356 90454 45435 90454 45435 90455 45356 90455 45440 90455 45440 90456 45356 90456 45252 90456 45440 90457 45252 90457 45442 90457 45442 90458 45252 90458 45444 90458 45444 90459 45252 90459 45358 90459 45444 90460 45358 90460 45447 90460 45447 90461 45358 90461 45445 90461 45445 90462 45358 90462 45359 90462 45445 90463 45359 90463 44080 90463 45425 90464 45360 90464 45253 90464 45253 90465 45360 90465 45361 90465 45253 90466 45361 90466 45426 90466 45426 90467 45361 90467 45254 90467 45254 90468 45361 90468 45255 90468 45254 90469 45255 90469 45256 90469 45256 90470 45255 90470 45427 90470 45427 90471 45255 90471 45362 90471 45427 90472 45362 90472 45428 90472 45428 90473 45362 90473 45429 90473 45429 90474 45362 90474 45258 90474 45429 90475 45258 90475 45430 90475 45430 90476 45258 90476 45257 90476 45257 90477 45258 90477 45366 90477 45257 90478 45366 90478 45259 90478 45259 90479 45366 90479 45260 90479 45260 90480 45366 90480 44071 90480 45260 90481 44071 90481 43904 90481 44070 90482 45380 90482 43921 90482 43921 90483 45380 90483 45423 90483 45380 90484 45381 90484 45423 90484 45423 90485 45381 90485 45382 90485 45423 90486 45382 90486 45421 90486 45382 90487 45377 90487 45421 90487 45421 90488 45377 90488 45375 90488 45421 90489 45375 90489 45420 90489 45375 90490 45261 90490 45420 90490 45420 90491 45261 90491 45262 90491 45420 90492 45262 90492 45263 90492 45262 90493 45264 90493 45263 90493 45263 90494 45264 90494 45372 90494 45263 90495 45372 90495 45266 90495 45369 90496 45415 90496 45371 90496 45371 90497 45415 90497 45266 90497 45371 90498 45266 90498 45265 90498 45265 90499 45266 90499 45372 90499 44059 90500 43955 90500 45267 90500 45267 90501 43955 90501 45269 90501 45267 90502 45269 90502 45268 90502 45268 90503 45269 90503 45270 90503 45268 90504 45270 90504 45271 90504 45271 90505 45270 90505 45273 90505 45271 90506 45273 90506 45272 90506 45272 90507 45273 90507 45384 90507 45272 90508 45384 90508 45274 90508 45274 90509 45384 90509 45386 90509 45274 90510 45386 90510 45498 90510 45498 90511 45386 90511 44046 90511 43844 90512 45276 90512 45275 90512 45275 90513 45276 90513 45277 90513 45275 90514 45277 90514 45488 90514 45488 90515 45277 90515 45489 90515 45489 90516 45277 90516 45390 90516 45489 90517 45390 90517 45278 90517 45278 90518 45390 90518 45280 90518 45280 90519 45390 90519 45279 90519 45280 90520 45279 90520 45491 90520 45491 90521 45279 90521 45492 90521 45492 90522 45279 90522 45391 90522 45492 90523 45391 90523 45493 90523 45493 90524 45391 90524 45281 90524 45281 90525 45391 90525 45282 90525 45281 90526 45282 90526 45497 90526 45497 90527 45282 90527 45495 90527 45495 90528 45282 90528 45283 90528 45495 90529 45283 90529 45494 90529 45487 90530 44035 90530 45486 90530 45486 90531 44035 90531 45284 90531 45486 90532 45284 90532 45484 90532 45484 90533 45284 90533 45393 90533 45484 90534 45393 90534 45286 90534 45286 90535 45393 90535 45285 90535 45286 90536 45285 90536 45483 90536 45483 90537 45285 90537 45288 90537 45483 90538 45288 90538 45287 90538 45287 90539 45288 90539 45289 90539 45287 90540 45289 90540 45290 90540 45290 90541 45289 90541 43945 90541 44905 90542 45291 90542 44902 90542 44902 90543 45291 90543 44027 90543 44902 90544 44027 90544 44664 90544 44842 90545 45292 90545 45293 90545 45293 90546 45292 90546 44713 90546 45293 90547 44713 90547 44905 90547 44905 90548 44713 90548 45294 90548 44905 90549 45294 90549 45291 90549 44842 90550 45293 90550 45295 90550 45295 90551 45293 90551 45296 90551 45295 90552 45296 90552 44712 90552 44917 90553 45297 90553 44910 90553 44910 90554 45297 90554 45298 90554 44910 90555 45298 90555 44913 90555 44913 90556 45298 90556 45299 90556 44913 90557 45299 90557 44912 90557 44912 90558 45299 90558 45300 90558 44912 90559 45300 90559 44909 90559 44909 90560 45300 90560 45301 90560 44909 90561 45301 90561 45296 90561 45296 90562 45301 90562 44777 90562 45296 90563 44777 90563 44712 90563 44919 90564 44695 90564 45302 90564 45302 90565 44695 90565 44700 90565 45302 90566 44700 90566 44917 90566 44917 90567 44700 90567 44702 90567 44917 90568 44702 90568 45297 90568 44691 90569 44692 90569 44919 90569 44919 90570 44692 90570 45303 90570 44919 90571 45303 90571 44695 90571 44691 90572 44919 90572 44689 90572 44689 90573 44919 90573 45304 90573 44689 90574 45304 90574 44685 90574 44685 90575 45304 90575 45306 90575 44685 90576 45306 90576 44684 90576 44684 90577 45306 90577 45305 90577 45305 90578 45306 90578 44925 90578 45305 90579 44925 90579 45307 90579 45307 90580 44925 90580 45308 90580 45307 90581 45308 90581 45309 90581 45310 90582 44010 90582 45312 90582 45310 90583 45312 90583 45311 90583 45311 90584 45312 90584 45313 90584 45311 90585 45313 90585 45639 90585 45639 90586 45313 90586 45315 90586 45639 90587 45315 90587 45314 90587 45314 90588 45315 90588 45316 90588 45316 90589 45315 90589 44933 90589 45316 90590 44933 90590 45734 90590 45328 90591 45317 90591 45318 90591 45318 90592 45317 90592 45793 90592 45318 90593 45793 90593 44933 90593 44933 90594 45793 90594 45735 90594 44933 90595 45735 90595 45734 90595 45319 90596 45321 90596 45320 90596 45320 90597 45321 90597 45619 90597 45320 90598 45619 90598 45322 90598 45322 90599 45619 90599 45324 90599 45322 90600 45324 90600 45323 90600 45323 90601 45324 90601 45325 90601 45323 90602 45325 90602 45326 90602 45326 90603 45325 90603 45327 90603 45326 90604 45327 90604 45328 90604 45328 90605 45327 90605 45791 90605 45328 90606 45791 90606 45317 90606 45806 90607 45808 90607 45319 90607 45319 90608 45808 90608 45329 90608 45319 90609 45329 90609 45321 90609 45806 90610 45319 90610 45667 90610 45667 90611 45319 90611 45330 90611 45667 90612 45330 90612 45331 90612 45331 90613 45330 90613 45333 90613 45331 90614 45333 90614 45334 90614 45686 90615 45332 90615 44926 90615 44926 90616 45332 90616 45333 90616 45333 90617 45332 90617 45687 90617 45333 90618 45687 90618 45334 90618 45686 90619 44926 90619 45611 90619 45611 90620 44926 90620 45335 90620 45611 90621 45335 90621 44003 90621 45336 90622 44000 90622 43998 90622 45231 90623 45810 90623 45337 90623 43998 90624 45233 90624 45336 90624 45336 90625 45233 90625 45232 90625 45336 90626 45232 90626 45337 90626 45337 90627 45232 90627 45338 90627 45337 90628 45338 90628 45231 90628 45231 90629 45229 90629 45810 90629 45810 90630 45229 90630 45228 90630 45810 90631 45228 90631 45342 90631 45339 90632 45340 90632 45224 90632 45224 90633 45340 90633 45617 90633 45224 90634 45617 90634 45341 90634 45341 90635 45617 90635 45342 90635 45341 90636 45342 90636 45227 90636 45227 90637 45342 90637 45228 90637 45343 90638 45669 90638 45236 90638 45236 90639 45669 90639 45344 90639 45236 90640 45344 90640 45237 90640 45237 90641 45344 90641 45345 90641 45237 90642 45345 90642 45239 90642 45239 90643 45345 90643 45800 90643 45239 90644 45800 90644 45346 90644 45346 90645 45800 90645 45670 90645 45346 90646 45670 90646 45348 90646 45348 90647 45670 90647 45347 90647 45348 90648 45347 90648 44098 90648 44098 90649 45347 90649 43989 90649 44096 90650 45685 90650 45349 90650 45349 90651 45685 90651 45350 90651 45349 90652 45350 90652 45244 90652 45244 90653 45350 90653 45684 90653 45244 90654 45684 90654 45246 90654 45246 90655 45684 90655 45351 90655 45246 90656 45351 90656 45352 90656 45352 90657 45351 90657 45682 90657 45352 90658 45682 90658 45353 90658 45353 90659 45682 90659 45679 90659 45353 90660 45679 90660 43986 90660 43986 90661 45679 90661 45680 90661 45249 90662 45664 90662 45354 90662 45354 90663 45664 90663 45666 90663 45354 90664 45666 90664 45251 90664 45251 90665 45666 90665 45355 90665 45251 90666 45355 90666 45356 90666 45356 90667 45355 90667 45691 90667 45356 90668 45691 90668 45252 90668 45252 90669 45691 90669 45357 90669 45252 90670 45357 90670 45358 90670 45358 90671 45357 90671 45817 90671 45358 90672 45817 90672 45359 90672 45359 90673 45817 90673 43971 90673 45360 90674 45765 90674 45361 90674 45361 90675 45765 90675 45764 90675 45361 90676 45764 90676 45255 90676 45255 90677 45764 90677 45363 90677 45255 90678 45363 90678 45362 90678 45362 90679 45363 90679 45364 90679 45362 90680 45364 90680 45258 90680 45258 90681 45364 90681 45700 90681 45258 90682 45700 90682 45366 90682 45366 90683 45700 90683 45365 90683 45366 90684 45365 90684 44071 90684 44071 90685 45365 90685 45367 90685 45370 90686 45368 90686 45369 90686 45369 90687 45371 90687 45370 90687 45370 90688 45371 90688 45265 90688 45370 90689 45265 90689 45373 90689 45261 90690 45376 90690 45374 90690 45265 90691 45372 90691 45373 90691 45373 90692 45372 90692 45264 90692 45373 90693 45264 90693 45374 90693 45374 90694 45264 90694 45262 90694 45374 90695 45262 90695 45261 90695 45261 90696 45375 90696 45376 90696 45376 90697 45375 90697 45377 90697 45376 90698 45377 90698 45378 90698 45378 90699 45377 90699 45382 90699 45378 90700 45382 90700 45709 90700 44070 90701 45379 90701 45380 90701 45380 90702 45379 90702 45709 90702 45380 90703 45709 90703 45381 90703 45381 90704 45709 90704 45382 90704 43955 90705 43954 90705 45269 90705 45269 90706 43954 90706 45717 90706 45269 90707 45717 90707 45270 90707 45270 90708 45717 90708 45383 90708 45270 90709 45383 90709 45273 90709 45273 90710 45383 90710 45659 90710 45273 90711 45659 90711 45384 90711 45384 90712 45659 90712 45385 90712 45384 90713 45385 90713 45386 90713 45386 90714 45385 90714 45387 90714 45386 90715 45387 90715 44046 90715 44046 90716 45387 90716 45757 90716 45276 90717 45388 90717 45277 90717 45277 90718 45388 90718 45389 90718 45277 90719 45389 90719 45390 90719 45390 90720 45389 90720 45753 90720 45390 90721 45753 90721 45279 90721 45279 90722 45753 90722 45751 90722 45279 90723 45751 90723 45391 90723 45391 90724 45751 90724 45719 90724 45391 90725 45719 90725 45282 90725 45282 90726 45719 90726 45724 90726 45282 90727 45724 90727 45283 90727 45283 90728 45724 90728 45725 90728 44035 90729 45392 90729 45284 90729 45284 90730 45392 90730 45654 90730 45284 90731 45654 90731 45393 90731 45393 90732 45654 90732 45653 90732 45393 90733 45653 90733 45285 90733 45285 90734 45653 90734 45651 90734 45285 90735 45651 90735 45288 90735 45288 90736 45651 90736 45650 90736 45288 90737 45650 90737 45289 90737 45289 90738 45650 90738 45394 90738 45289 90739 45394 90739 43945 90739 43945 90740 45394 90740 45644 90740 43932 90741 45640 90741 45196 90741 45196 90742 45640 90742 45396 90742 45196 90743 45396 90743 45395 90743 45395 90744 45396 90744 45648 90744 45395 90745 45648 90745 45200 90745 45200 90746 45648 90746 45397 90746 45200 90747 45397 90747 45201 90747 45201 90748 45397 90748 45398 90748 45201 90749 45398 90749 45399 90749 45399 90750 45398 90750 45642 90750 45399 90751 45642 90751 45203 90751 45203 90752 45642 90752 43938 90752 43931 90753 45739 90753 45400 90753 45400 90754 45739 90754 45736 90754 45400 90755 45736 90755 45205 90755 45205 90756 45736 90756 45401 90756 45205 90757 45401 90757 45402 90757 45402 90758 45401 90758 45403 90758 45402 90759 45403 90759 45404 90759 45404 90760 45403 90760 45405 90760 45404 90761 45405 90761 45212 90761 45212 90762 45405 90762 45748 90762 45212 90763 45748 90763 45406 90763 45406 90764 45748 90764 45407 90764 45406 90765 45407 90765 45408 90765 45408 90766 45407 90766 45746 90766 45214 90767 45624 90767 45215 90767 45215 90768 45624 90768 45409 90768 45215 90769 45409 90769 45217 90769 45217 90770 45409 90770 45626 90770 45217 90771 45626 90771 45410 90771 45410 90772 45626 90772 45411 90772 45410 90773 45411 90773 45412 90773 45412 90774 45411 90774 45788 90774 45412 90775 45788 90775 45413 90775 45413 90776 45788 90776 45786 90776 45413 90777 45786 90777 45223 90777 45223 90778 45786 90778 45414 90778 45223 90779 45414 90779 44119 90779 44119 90780 45414 90780 45630 90780 45415 90781 45416 90781 45266 90781 45266 90782 45416 90782 45417 90782 45266 90783 45417 90783 45263 90783 45263 90784 45417 90784 45418 90784 45263 90785 45418 90785 45420 90785 45420 90786 45418 90786 45419 90786 45420 90787 45419 90787 45421 90787 45421 90788 45419 90788 45422 90788 45421 90789 45422 90789 45423 90789 45423 90790 45422 90790 45424 90790 45423 90791 45424 90791 43921 90791 43921 90792 45424 90792 44753 90792 44759 90793 44754 90793 45425 90793 45425 90794 45253 90794 44759 90794 44759 90795 45253 90795 45426 90795 44759 90796 45426 90796 44760 90796 45428 90797 45431 90797 44761 90797 45426 90798 45254 90798 44760 90798 44760 90799 45254 90799 45256 90799 44760 90800 45256 90800 44761 90800 44761 90801 45256 90801 45427 90801 44761 90802 45427 90802 45428 90802 45428 90803 45429 90803 45431 90803 45431 90804 45429 90804 45430 90804 45431 90805 45430 90805 44762 90805 44762 90806 45430 90806 45257 90806 44762 90807 45257 90807 45432 90807 43904 90808 44875 90808 45260 90808 45260 90809 44875 90809 45432 90809 45260 90810 45432 90810 45259 90810 45259 90811 45432 90811 45257 90811 45434 90812 44766 90812 45248 90812 45248 90813 45433 90813 45434 90813 45434 90814 45433 90814 45436 90814 45434 90815 45436 90815 45438 90815 45435 90816 45441 90816 44770 90816 45436 90817 45250 90817 45438 90817 45438 90818 45250 90818 45437 90818 45438 90819 45437 90819 44770 90819 44770 90820 45437 90820 45439 90820 44770 90821 45439 90821 45435 90821 45435 90822 45440 90822 45441 90822 45441 90823 45440 90823 45442 90823 45441 90824 45442 90824 45443 90824 45443 90825 45442 90825 45444 90825 45443 90826 45444 90826 44768 90826 44080 90827 45446 90827 45445 90827 45445 90828 45446 90828 44768 90828 45445 90829 44768 90829 45447 90829 45447 90830 44768 90830 45444 90830 45247 90831 45448 90831 45449 90831 45449 90832 45448 90832 45450 90832 45449 90833 45450 90833 45245 90833 45245 90834 45450 90834 44876 90834 45245 90835 44876 90835 45451 90835 45451 90836 44876 90836 45452 90836 45451 90837 45452 90837 45243 90837 45243 90838 45452 90838 45453 90838 45243 90839 45453 90839 45454 90839 45454 90840 45453 90840 45455 90840 45454 90841 45455 90841 45456 90841 45456 90842 45455 90842 44892 90842 45242 90843 44785 90843 45241 90843 45241 90844 44785 90844 44784 90844 45241 90845 44784 90845 45240 90845 45240 90846 44784 90846 44783 90846 45240 90847 44783 90847 45238 90847 45238 90848 44783 90848 45457 90848 45238 90849 45457 90849 45458 90849 45458 90850 45457 90850 44781 90850 45458 90851 44781 90851 45235 90851 45235 90852 44781 90852 44780 90852 45235 90853 44780 90853 43891 90853 43891 90854 44780 90854 44779 90854 45459 90855 44707 90855 45460 90855 45460 90856 44707 90856 44790 90856 45460 90857 44790 90857 45234 90857 45234 90858 44790 90858 44789 90858 45234 90859 44789 90859 45230 90859 45230 90860 44789 90860 45461 90860 45230 90861 45461 90861 45226 90861 45226 90862 45461 90862 44788 90862 45226 90863 44788 90863 45462 90863 45462 90864 44788 90864 45463 90864 45462 90865 45463 90865 45225 90865 45225 90866 45463 90866 44787 90866 45225 90867 44787 90867 44116 90867 44116 90868 44787 90868 44897 90868 45466 90869 45464 90869 44131 90869 45218 90870 45469 90870 45465 90870 44131 90871 45216 90871 45466 90871 45466 90872 45216 90872 45467 90872 45466 90873 45467 90873 45465 90873 45465 90874 45467 90874 45468 90874 45465 90875 45468 90875 45218 90875 45218 90876 45219 90876 45469 90876 45469 90877 45219 90877 45220 90877 45469 90878 45220 90878 44697 90878 43873 90879 45470 90879 45222 90879 45222 90880 45470 90880 44698 90880 45222 90881 44698 90881 45221 90881 45221 90882 44698 90882 44697 90882 45221 90883 44697 90883 45471 90883 45471 90884 44697 90884 45220 90884 44794 90885 43870 90885 45204 90885 45208 90886 45474 90886 44867 90886 45204 90887 45472 90887 44794 90887 44794 90888 45472 90888 45206 90888 44794 90889 45206 90889 44867 90889 44867 90890 45206 90890 45207 90890 44867 90891 45207 90891 45208 90891 45208 90892 45473 90892 45474 90892 45474 90893 45473 90893 45209 90893 45474 90894 45209 90894 44687 90894 44132 90895 44688 90895 45213 90895 45213 90896 44688 90896 45475 90896 45213 90897 45475 90897 45211 90897 45211 90898 45475 90898 44687 90898 45211 90899 44687 90899 45210 90899 45210 90900 44687 90900 45209 90900 43861 90901 45476 90901 45202 90901 45202 90902 45476 90902 45477 90902 45202 90903 45477 90903 45199 90903 45199 90904 45477 90904 44679 90904 45199 90905 44679 90905 45198 90905 45198 90906 44679 90906 45478 90906 45198 90907 45478 90907 45197 90907 45197 90908 45478 90908 45479 90908 45197 90909 45479 90909 45195 90909 45195 90910 45479 90910 45480 90910 45195 90911 45480 90911 45481 90911 45481 90912 45480 90912 44678 90912 45290 90913 43855 90913 45287 90913 45287 90914 43855 90914 45482 90914 45287 90915 45482 90915 45483 90915 45483 90916 45482 90916 44732 90916 45483 90917 44732 90917 45286 90917 45286 90918 44732 90918 45485 90918 45286 90919 45485 90919 45484 90919 45484 90920 45485 90920 44728 90920 45484 90921 44728 90921 45486 90921 45486 90922 44728 90922 44738 90922 45486 90923 44738 90923 45487 90923 45487 90924 44738 90924 43848 90924 44822 90925 44821 90925 43844 90925 43844 90926 45275 90926 44822 90926 44822 90927 45275 90927 45488 90927 44822 90928 45488 90928 44797 90928 45491 90929 44799 90929 45490 90929 45488 90930 45489 90930 44797 90930 44797 90931 45489 90931 45278 90931 44797 90932 45278 90932 45490 90932 45490 90933 45278 90933 45280 90933 45490 90934 45280 90934 45491 90934 45491 90935 45492 90935 44799 90935 44799 90936 45492 90936 45493 90936 44799 90937 45493 90937 44800 90937 44800 90938 45493 90938 45281 90938 44800 90939 45281 90939 45496 90939 45494 90940 44802 90940 45495 90940 45495 90941 44802 90941 45496 90941 45495 90942 45496 90942 45497 90942 45497 90943 45496 90943 45281 90943 45498 90944 44813 90944 45274 90944 45274 90945 44813 90945 44812 90945 45274 90946 44812 90946 45272 90946 45272 90947 44812 90947 44807 90947 45272 90948 44807 90948 45271 90948 45271 90949 44807 90949 44805 90949 45271 90950 44805 90950 45268 90950 45268 90951 44805 90951 44804 90951 45268 90952 44804 90952 45267 90952 45267 90953 44804 90953 45499 90953 45267 90954 45499 90954 44059 90954 44059 90955 45499 90955 44803 90955 43835 90956 43834 90956 45500 90956 43835 90957 45500 90957 45501 90957 45501 90958 45500 90958 44954 90958 45501 90959 44954 90959 45502 90959 45502 90960 44954 90960 45503 90960 45502 90961 45503 90961 45504 90961 45504 90962 45503 90962 44956 90962 45504 90963 44956 90963 44559 90963 44559 90964 44956 90964 44957 90964 44559 90965 44957 90965 45505 90965 45505 90966 44957 90966 44958 90966 45505 90967 44958 90967 45506 90967 45506 90968 44958 90968 44961 90968 45506 90969 44961 90969 45507 90969 45507 90970 44961 90970 44962 90970 45507 90971 44962 90971 45508 90971 45508 90972 44962 90972 44963 90972 45508 90973 44963 90973 45509 90973 45509 90974 44963 90974 44965 90974 45509 90975 44965 90975 44528 90975 44528 90976 44965 90976 45510 90976 44528 90977 45510 90977 44530 90977 44530 90978 45510 90978 45512 90978 44530 90979 45512 90979 45511 90979 45511 90980 45512 90980 44969 90980 45511 90981 44969 90981 44532 90981 44532 90982 44969 90982 44971 90982 44532 90983 44971 90983 45513 90983 45513 90984 44971 90984 45514 90984 45513 90985 45514 90985 44533 90985 44533 90986 45514 90986 44973 90986 44533 90987 44973 90987 45515 90987 45515 90988 44973 90988 44974 90988 45515 90989 44974 90989 45516 90989 45516 90990 44974 90990 45517 90990 45516 90991 45517 90991 44534 90991 45061 90992 45518 90992 45059 90992 45059 90993 45518 90993 44337 90993 45059 90994 44337 90994 45519 90994 45519 90995 44337 90995 45520 90995 45519 90996 45520 90996 45521 90996 45521 90997 45520 90997 44339 90997 45521 90998 44339 90998 45522 90998 45522 90999 44339 90999 44341 90999 45522 91000 44341 91000 45523 91000 45523 91001 44341 91001 44344 91001 45523 91002 44344 91002 45055 91002 45055 91003 44344 91003 44345 91003 45055 91004 44345 91004 45524 91004 45524 91005 44345 91005 44347 91005 45524 91006 44347 91006 45525 91006 45525 91007 44347 91007 45526 91007 45525 91008 45526 91008 45051 91008 45051 91009 45526 91009 45527 91009 45051 91010 45527 91010 45528 91010 45528 91011 45527 91011 45529 91011 45528 91012 45529 91012 45530 91012 45530 91013 45529 91013 45531 91013 45530 91014 45531 91014 45532 91014 45532 91015 45531 91015 44351 91015 45532 91016 44351 91016 45533 91016 45533 91017 44351 91017 44352 91017 45533 91018 44352 91018 45534 91018 45534 91019 44352 91019 44353 91019 45534 91020 44353 91020 45535 91020 45535 91021 44353 91021 45536 91021 45535 91022 45536 91022 45537 91022 45537 91023 45536 91023 45539 91023 45537 91024 45539 91024 45538 91024 45538 91025 45539 91025 44356 91025 43801 91026 45032 91026 45540 91026 43801 91027 45540 91027 45541 91027 45541 91028 45540 91028 45035 91028 45541 91029 45035 91029 45542 91029 45542 91030 45035 91030 45036 91030 45542 91031 45036 91031 45543 91031 45543 91032 45036 91032 45544 91032 45543 91033 45544 91033 44324 91033 44324 91034 45544 91034 45545 91034 44324 91035 45545 91035 44325 91035 44325 91036 45545 91036 45546 91036 44325 91037 45546 91037 44326 91037 44326 91038 45546 91038 45038 91038 44326 91039 45038 91039 45547 91039 45547 91040 45038 91040 45040 91040 45547 91041 45040 91041 45548 91041 45548 91042 45040 91042 45041 91042 45548 91043 45041 91043 44329 91043 44329 91044 45041 91044 45549 91044 44329 91045 45549 91045 45550 91045 45550 91046 45549 91046 45551 91046 45550 91047 45551 91047 44331 91047 44331 91048 45551 91048 45552 91048 44331 91049 45552 91049 44333 91049 44333 91050 45552 91050 45553 91050 44333 91051 45553 91051 45554 91051 45554 91052 45553 91052 45042 91052 45554 91053 45042 91053 45555 91053 45555 91054 45042 91054 45043 91054 45555 91055 45043 91055 45556 91055 45556 91056 45043 91056 45045 91056 45556 91057 45045 91057 45557 91057 45557 91058 45045 91058 44357 91058 45557 91059 44357 91059 43785 91059 44478 91060 43784 91060 44976 91060 44478 91061 44976 91061 45558 91061 45558 91062 44976 91062 44977 91062 45558 91063 44977 91063 44481 91063 44481 91064 44977 91064 44978 91064 44481 91065 44978 91065 44483 91065 44483 91066 44978 91066 45559 91066 44483 91067 45559 91067 44484 91067 44484 91068 45559 91068 44979 91068 44484 91069 44979 91069 45560 91069 45560 91070 44979 91070 45561 91070 45560 91071 45561 91071 44486 91071 44486 91072 45561 91072 44980 91072 44486 91073 44980 91073 44487 91073 44487 91074 44980 91074 45563 91074 44487 91075 45563 91075 45562 91075 45562 91076 45563 91076 44982 91076 45562 91077 44982 91077 44490 91077 44490 91078 44982 91078 44983 91078 44490 91079 44983 91079 44491 91079 44491 91080 44983 91080 44984 91080 44491 91081 44984 91081 45565 91081 45565 91082 44984 91082 45564 91082 45565 91083 45564 91083 44494 91083 44494 91084 45564 91084 44986 91084 44494 91085 44986 91085 44497 91085 44497 91086 44986 91086 44988 91086 44497 91087 44988 91087 44498 91087 44498 91088 44988 91088 44990 91088 44498 91089 44990 91089 44499 91089 44499 91090 44990 91090 45566 91090 44499 91091 45566 91091 44502 91091 44502 91092 45566 91092 44993 91092 44502 91093 44993 91093 45567 91093 45567 91094 44993 91094 45568 91094 45567 91095 45568 91095 43769 91095 45569 91096 43768 91096 45007 91096 45007 91097 43768 91097 44503 91097 45007 91098 44503 91098 45006 91098 45006 91099 44503 91099 45570 91099 45006 91100 45570 91100 45572 91100 45572 91101 45570 91101 45571 91101 45572 91102 45571 91102 45004 91102 45004 91103 45571 91103 45573 91103 45004 91104 45573 91104 45574 91104 45574 91105 45573 91105 44466 91105 45574 91106 44466 91106 45575 91106 45575 91107 44466 91107 44468 91107 45575 91108 44468 91108 45002 91108 45002 91109 44468 91109 45576 91109 45002 91110 45576 91110 45001 91110 45001 91111 45576 91111 44469 91111 45001 91112 44469 91112 45000 91112 45000 91113 44469 91113 45577 91113 45000 91114 45577 91114 44998 91114 44998 91115 45577 91115 44472 91115 44998 91116 44472 91116 45578 91116 45578 91117 44472 91117 45579 91117 45578 91118 45579 91118 44997 91118 44997 91119 45579 91119 45580 91119 44997 91120 45580 91120 44995 91120 44995 91121 45580 91121 45581 91121 44995 91122 45581 91122 45582 91122 45582 91123 45581 91123 44475 91123 45582 91124 44475 91124 45583 91124 45583 91125 44475 91125 45584 91125 45583 91126 45584 91126 44994 91126 44994 91127 45584 91127 45585 91127 44994 91128 45585 91128 44463 91128 44463 91129 45585 91129 44477 91129 45031 91130 44425 91130 45586 91130 45586 91131 44425 91131 44428 91131 45586 91132 44428 91132 45028 91132 45028 91133 44428 91133 45587 91133 45028 91134 45587 91134 45588 91134 45588 91135 45587 91135 44429 91135 45588 91136 44429 91136 45589 91136 45589 91137 44429 91137 45590 91137 45589 91138 45590 91138 45024 91138 45024 91139 45590 91139 45591 91139 45024 91140 45591 91140 45021 91140 45021 91141 45591 91141 45592 91141 45021 91142 45592 91142 45020 91142 45020 91143 45592 91143 45593 91143 45020 91144 45593 91144 45019 91144 45019 91145 45593 91145 45595 91145 45019 91146 45595 91146 45594 91146 45594 91147 45595 91147 45596 91147 45594 91148 45596 91148 45017 91148 45017 91149 45596 91149 44435 91149 45017 91150 44435 91150 45597 91150 45597 91151 44435 91151 45598 91151 45597 91152 45598 91152 45015 91152 45015 91153 45598 91153 45599 91153 45015 91154 45599 91154 45012 91154 45012 91155 45599 91155 45600 91155 45012 91156 45600 91156 45601 91156 45601 91157 45600 91157 44438 91157 45601 91158 44438 91158 45602 91158 45602 91159 44438 91159 44439 91159 45602 91160 44439 91160 45010 91160 45010 91161 44439 91161 44442 91161 45010 91162 44442 91162 44420 91162 44420 91163 44442 91163 45603 91163 44150 91164 44151 91164 45646 91164 45815 91165 45604 91165 45605 91165 45606 91166 43952 91166 45818 91166 45607 91167 45665 91167 45772 91167 45689 91168 45608 91168 44004 91168 45708 91169 45609 91169 45710 91169 45610 91170 45721 91170 45718 91170 45718 91171 45721 91171 45726 91171 45667 91172 45807 91172 45806 91172 45687 91173 45612 91173 45334 91173 45686 91174 45611 91174 45771 91174 45771 91175 45611 91175 44003 91175 43984 91176 45612 91176 45613 91176 45613 91177 45612 91177 45687 91177 45613 91178 45687 91178 45685 91178 45120 91179 45118 91179 45810 91179 45324 91180 45619 91180 45614 91180 45121 91181 45625 91181 45122 91181 45122 91182 45625 91182 44224 91182 45627 91183 45327 91183 45615 91183 45615 91184 45327 91184 45325 91184 45615 91185 45325 91185 45616 91185 45616 91186 45325 91186 45324 91186 45616 91187 45324 91187 44226 91187 44226 91188 45324 91188 45614 91188 45117 91189 45336 91189 45118 91189 45118 91190 45336 91190 45337 91190 45118 91191 45337 91191 45810 91191 45342 91192 45617 91192 45811 91192 45811 91193 45617 91193 45321 91193 45811 91194 45321 91194 45618 91194 45618 91195 45321 91195 45329 91195 45618 91196 45329 91196 45808 91196 45617 91197 45340 91197 45321 91197 45321 91198 45340 91198 45620 91198 45321 91199 45620 91199 45619 91199 45619 91200 45620 91200 43991 91200 43991 91201 43993 91201 45619 91201 45619 91202 43993 91202 45621 91202 45619 91203 45621 91203 45614 91203 45614 91204 45621 91204 43997 91204 45614 91205 43997 91205 45623 91205 45623 91206 43997 91206 45622 91206 45623 91207 45622 91207 45117 91207 45117 91208 45622 91208 44000 91208 45117 91209 44000 91209 45336 91209 45624 91210 43925 91210 45327 91210 45832 91211 45411 91211 45625 91211 45625 91212 45411 91212 45626 91212 45625 91213 45626 91213 45409 91213 45627 91214 44224 91214 45327 91214 45327 91215 44224 91215 45625 91215 45327 91216 45625 91216 45624 91216 45624 91217 45625 91217 45409 91217 43925 91218 45628 91218 45327 91218 45327 91219 45628 91219 45629 91219 45327 91220 45629 91220 45791 91220 45791 91221 45629 91221 43923 91221 45791 91222 43923 91222 45790 91222 45790 91223 45630 91223 44240 91223 44240 91224 45630 91224 45631 91224 45631 91225 45630 91225 45414 91225 45631 91226 45414 91226 45787 91226 45734 91227 45745 91227 45316 91227 45316 91228 45745 91228 45632 91228 45316 91229 45632 91229 45314 91229 45314 91230 45632 91230 45747 91230 45314 91231 45747 91231 45633 91231 45633 91232 45634 91232 45314 91232 45314 91233 45634 91233 45635 91233 45314 91234 45635 91234 45639 91234 45639 91235 45635 91235 44245 91235 45639 91236 45637 91236 43933 91236 45096 91237 45814 91237 45636 91237 45636 91238 45814 91238 45637 91238 45636 91239 45637 91239 45097 91239 45097 91240 45637 91240 45639 91240 45097 91241 45639 91241 45638 91241 45638 91242 45639 91242 44245 91242 43933 91243 43937 91243 45639 91243 45639 91244 43937 91244 43940 91244 45639 91245 43940 91245 45311 91245 45311 91246 43940 91246 43938 91246 45311 91247 43938 91247 45310 91247 45640 91248 45641 91248 45396 91248 45396 91249 45641 91249 45647 91249 45396 91250 45647 91250 45648 91250 43938 91251 45642 91251 45310 91251 45310 91252 45642 91252 45398 91252 45310 91253 45398 91253 45397 91253 43944 91254 43947 91254 45310 91254 45310 91255 43947 91255 45643 91255 45310 91256 45643 91256 45645 91256 45645 91257 45643 91257 45644 91257 45645 91258 45644 91258 45649 91258 45655 91259 43944 91259 45646 91259 45646 91260 43944 91260 45310 91260 45646 91261 45310 91261 45647 91261 45647 91262 45310 91262 45397 91262 45647 91263 45397 91263 45648 91263 44154 91264 44156 91264 45649 91264 45644 91265 45394 91265 45649 91265 45649 91266 45394 91266 45650 91266 45649 91267 45650 91267 44154 91267 44154 91268 45650 91268 45651 91268 44154 91269 45651 91269 44153 91269 44153 91270 45651 91270 45652 91270 45651 91271 45653 91271 45652 91271 45652 91272 45653 91272 45654 91272 45652 91273 45654 91273 44151 91273 44151 91274 45654 91274 45392 91274 44151 91275 45392 91275 45646 91275 45646 91276 45392 91276 43941 91276 45646 91277 43941 91277 45655 91277 45755 91278 45656 91278 45657 91278 45657 91279 45656 91279 45387 91279 45387 91280 45385 91280 45657 91280 45657 91281 45385 91281 45659 91281 45657 91282 45659 91282 45658 91282 45658 91283 45659 91283 45383 91283 45658 91284 45383 91284 45660 91284 45706 91285 45661 91285 45662 91285 45662 91286 45661 91286 45658 91286 45663 91287 45778 91287 43980 91287 43980 91288 45778 91288 45665 91288 43980 91289 45665 91289 45664 91289 45664 91290 45665 91290 45607 91290 45664 91291 45607 91291 45666 91291 45666 91292 45607 91292 44004 91292 45666 91293 44004 91293 45355 91293 45355 91294 44004 91294 45608 91294 45669 91295 43990 91295 45807 91295 45667 91296 45331 91296 45807 91296 45807 91297 45331 91297 45668 91297 45807 91298 45668 91298 45669 91298 45669 91299 45668 91299 45344 91299 45347 91300 45670 91300 45799 91300 45799 91301 45670 91301 45800 91301 43990 91302 45671 91302 45807 91302 45807 91303 45671 91303 45672 91303 45807 91304 45672 91304 45809 91304 45809 91305 45672 91305 45674 91305 45809 91306 45674 91306 45673 91306 45673 91307 45674 91307 45675 91307 45673 91308 45675 91308 45843 91308 45843 91309 45675 91309 43989 91309 45843 91310 43989 91310 45846 91310 45676 91311 45677 91311 45129 91311 45677 91312 45676 91312 45678 91312 45678 91313 45676 91313 43988 91313 45678 91314 43988 91314 45681 91314 45679 91315 45781 91315 45680 91315 45680 91316 45781 91316 45605 91316 45680 91317 45605 91317 45681 91317 45681 91318 45605 91318 45604 91318 45681 91319 45604 91319 45678 91319 45679 91320 45682 91320 45781 91320 45781 91321 45682 91321 45351 91321 45781 91322 45351 91322 45683 91322 45683 91323 45351 91323 45684 91323 45683 91324 45684 91324 45771 91324 45771 91325 45684 91325 45350 91325 45771 91326 45350 91326 45686 91326 45686 91327 45350 91327 45685 91327 45686 91328 45685 91328 45332 91328 45332 91329 45685 91329 45687 91329 45766 91330 45688 91330 45713 91330 45713 91331 45688 91331 45153 91331 45713 91332 45153 91332 45689 91332 45689 91333 45153 91333 45690 91333 45689 91334 45690 91334 45608 91334 45608 91335 45690 91335 45151 91335 45608 91336 45151 91336 45355 91336 45355 91337 45151 91337 45692 91337 45355 91338 45692 91338 45691 91338 45691 91339 45692 91339 45693 91339 45691 91340 45693 91340 45357 91340 45357 91341 45693 91341 44193 91341 45774 91342 45694 91342 43971 91342 45663 91343 43977 91343 45778 91343 45778 91344 43977 91344 43976 91344 45778 91345 43976 91345 45774 91345 45774 91346 43976 91346 43974 91346 45774 91347 43974 91347 45694 91347 45695 91348 45696 91348 45365 91348 45365 91349 45696 91349 45367 91349 45367 91350 45696 91350 45697 91350 45367 91351 45697 91351 45698 91351 45698 91352 45697 91352 45699 91352 45698 91353 45699 91353 45826 91353 45365 91354 45700 91354 45695 91354 45695 91355 45700 91355 45364 91355 45695 91356 45364 91356 45712 91356 45701 91357 45702 91357 45842 91357 45842 91358 45702 91358 45171 91358 45842 91359 45171 91359 45660 91359 45660 91360 45171 91360 45170 91360 45660 91361 45170 91361 45658 91361 45658 91362 45170 91362 45169 91362 45658 91363 45169 91363 45662 91363 45850 91364 45703 91364 45842 91364 45704 91365 43961 91365 45696 91365 45704 91366 45696 91366 45379 91366 45701 91367 45842 91367 45705 91367 45705 91368 45842 91368 45703 91368 45705 91369 45703 91369 44180 91369 44180 91370 45703 91370 43959 91370 44180 91371 43959 91371 44181 91371 44181 91372 43959 91372 45368 91372 44181 91373 45368 91373 45166 91373 45166 91374 45368 91374 45370 91374 45166 91375 45370 91375 45707 91375 45707 91376 45370 91376 45373 91376 45707 91377 45373 91377 45374 91377 45706 91378 45707 91378 45661 91378 45661 91379 45707 91379 45374 91379 45661 91380 45374 91380 45708 91380 45708 91381 45374 91381 45376 91381 45708 91382 45376 91382 45609 91382 45609 91383 45376 91383 45378 91383 45609 91384 45378 91384 45709 91384 45709 91385 45379 91385 45609 91385 45609 91386 45379 91386 45696 91386 45609 91387 45696 91387 45710 91387 45710 91388 45696 91388 45695 91388 45710 91389 45695 91389 45711 91389 45711 91390 45695 91390 45712 91390 45711 91391 45712 91391 45713 91391 45713 91392 45712 91392 45763 91392 45713 91393 45763 91393 45766 91393 45841 91394 45715 91394 45714 91394 45714 91395 45715 91395 45716 91395 43953 91396 45842 91396 43954 91396 43954 91397 45842 91397 45660 91397 43954 91398 45660 91398 45717 91398 45717 91399 45660 91399 45383 91399 45718 91400 45724 91400 45719 91400 45610 91401 45718 91401 45752 91401 45752 91402 45718 91402 45719 91402 45752 91403 45719 91403 45751 91403 44156 91404 44157 91404 45649 91404 45649 91405 44157 91405 45720 91405 45649 91406 45720 91406 45721 91406 45721 91407 45720 91407 45722 91407 45721 91408 45722 91408 45726 91408 45726 91409 45722 91409 45723 91409 45726 91410 45723 91410 45728 91410 45724 91411 45718 91411 45725 91411 45725 91412 45718 91412 45726 91412 45725 91413 45726 91413 45727 91413 45727 91414 45726 91414 45728 91414 45727 91415 45728 91415 45729 91415 45729 91416 45728 91416 45730 91416 45730 91417 45728 91417 45194 91417 45730 91418 45194 91418 43952 91418 45731 91419 45388 91419 45829 91419 45829 91420 45388 91420 45732 91420 45753 91421 44166 91421 45754 91421 44166 91422 45753 91422 44167 91422 45753 91423 45389 91423 44167 91423 44167 91424 45389 91424 45388 91424 44167 91425 45388 91425 44168 91425 44168 91426 45388 91426 45731 91426 44168 91427 45731 91427 45733 91427 45734 91428 45735 91428 45745 91428 45745 91429 45735 91429 45743 91429 45745 91430 45743 91430 45744 91430 45744 91431 45743 91431 45742 91431 45403 91432 45401 91432 45821 91432 45821 91433 45401 91433 45736 91433 45821 91434 45736 91434 45737 91434 45737 91435 45736 91435 45739 91435 45737 91436 45739 91436 45738 91436 45738 91437 45739 91437 45740 91437 45738 91438 45740 91438 45741 91438 45741 91439 45740 91439 45742 91439 45741 91440 45742 91440 45797 91440 45797 91441 45742 91441 45743 91441 45797 91442 45743 91442 45795 91442 45795 91443 45743 91443 45735 91443 45795 91444 45735 91444 45793 91444 45744 91445 43928 91445 45745 91445 45745 91446 43928 91446 43926 91446 45745 91447 43926 91447 45632 91447 45632 91448 43926 91448 45746 91448 45632 91449 45746 91449 45747 91449 45747 91450 45746 91450 45407 91450 45747 91451 45407 91451 45749 91451 45749 91452 45407 91452 45748 91452 45749 91453 45748 91453 45750 91453 45750 91454 45748 91454 45405 91454 45750 91455 45405 91455 45403 91455 45751 91456 45753 91456 45752 91456 45752 91457 45753 91457 45754 91457 45752 91458 45754 91458 45610 91458 45610 91459 45754 91459 45182 91459 45610 91460 45182 91460 45755 91460 45755 91461 45182 91461 45180 91461 45755 91462 45180 91462 45656 91462 45656 91463 45180 91463 45756 91463 45656 91464 45756 91464 45387 91464 45387 91465 45756 91465 45758 91465 45387 91466 45758 91466 45757 91466 45757 91467 45758 91467 45759 91467 45757 91468 45759 91468 45760 91468 45760 91469 45759 91469 45761 91469 45760 91470 45761 91470 45716 91470 45716 91471 45761 91471 45762 91471 45716 91472 45762 91472 45714 91472 45714 91473 45762 91473 45830 91473 45364 91474 45363 91474 45712 91474 45712 91475 45363 91475 45764 91475 45712 91476 45764 91476 45763 91476 45763 91477 45764 91477 45765 91477 45763 91478 45765 91478 45766 91478 45766 91479 45765 91479 43964 91479 45766 91480 43964 91480 45156 91480 45156 91481 43964 91481 45767 91481 45156 91482 45767 91482 45768 91482 45768 91483 45767 91483 45827 91483 45768 91484 45827 91484 44188 91484 44188 91485 45827 91485 45769 91485 44188 91486 45769 91486 45770 91486 45770 91487 45769 91487 45825 91487 45770 91488 45825 91488 44190 91488 45779 91489 45771 91489 45665 91489 45665 91490 45771 91490 44003 91490 45665 91491 44003 91491 45772 91491 45773 91492 45774 91492 45775 91492 45775 91493 45774 91493 45781 91493 45775 91494 45781 91494 45782 91494 45773 91495 45776 91495 45774 91495 45774 91496 45776 91496 45142 91496 45774 91497 45142 91497 45778 91497 45778 91498 45142 91498 45777 91498 45778 91499 45777 91499 45665 91499 45665 91500 45777 91500 45141 91500 45665 91501 45141 91501 45779 91501 45779 91502 44204 91502 45771 91502 45771 91503 44204 91503 45780 91503 45771 91504 45780 91504 45683 91504 45683 91505 45780 91505 44201 91505 45683 91506 44201 91506 45781 91506 45781 91507 44201 91507 44200 91507 45781 91508 44200 91508 45782 91508 45094 91509 45784 91509 45783 91509 45783 91510 45784 91510 45785 91510 45783 91511 45785 91511 45096 91511 45414 91512 45786 91512 45787 91512 45787 91513 45786 91513 45788 91513 45787 91514 45788 91514 45106 91514 45106 91515 45788 91515 45831 91515 45106 91516 45831 91516 45107 91516 45107 91517 45831 91517 45789 91517 45107 91518 45789 91518 45109 91518 45790 91519 44240 91519 45791 91519 45791 91520 44240 91520 45792 91520 45791 91521 45792 91521 45317 91521 45317 91522 45792 91522 44237 91522 45317 91523 44237 91523 45793 91523 45793 91524 44237 91524 45794 91524 45793 91525 45794 91525 45795 91525 45795 91526 45794 91526 45796 91526 45795 91527 45796 91527 45797 91527 45822 91528 45799 91528 45798 91528 45798 91529 45799 91529 45800 91529 45798 91530 45800 91530 45801 91530 45801 91531 45800 91531 45345 91531 45801 91532 45345 91532 45802 91532 45802 91533 45345 91533 45344 91533 45802 91534 45344 91534 45803 91534 45803 91535 45344 91535 45668 91535 45803 91536 45668 91536 44216 91536 44216 91537 45668 91537 45331 91537 44216 91538 45331 91538 45804 91538 45804 91539 45331 91539 45334 91539 45804 91540 45334 91540 45805 91540 45805 91541 45334 91541 45612 91541 45805 91542 45612 91542 45129 91542 45129 91543 45612 91543 43984 91543 45129 91544 43984 91544 45676 91544 43952 91545 45194 91545 45818 91545 45818 91546 45194 91546 45192 91546 45818 91547 45192 91547 45812 91547 45806 91548 45807 91548 45808 91548 45808 91549 45807 91549 45809 91549 45808 91550 45809 91550 45618 91550 45618 91551 45809 91551 45673 91551 45618 91552 45673 91552 45811 91552 45811 91553 45673 91553 45810 91553 45811 91554 45810 91554 45342 91554 45192 91555 44150 91555 45812 91555 45812 91556 44150 91556 45646 91556 45812 91557 45646 91557 45813 91557 45813 91558 45646 91558 45647 91558 45813 91559 45647 91559 45785 91559 45785 91560 45647 91560 45641 91560 45785 91561 45641 91561 45096 91561 45096 91562 45641 91562 45640 91562 45096 91563 45640 91563 45814 91563 45798 91564 45815 91564 45822 91564 45822 91565 45815 91565 45605 91565 45822 91566 45605 91566 45816 91566 45816 91567 45605 91567 45781 91567 45816 91568 45781 91568 45825 91568 45825 91569 45781 91569 45774 91569 45825 91570 45774 91570 44190 91570 44190 91571 45774 91571 43971 91571 44190 91572 43971 91572 44193 91572 44193 91573 43971 91573 45817 91573 44193 91574 45817 91574 45357 91574 45732 91575 45606 91575 45829 91575 45829 91576 45606 91576 45818 91576 45829 91577 45818 91577 45819 91577 45819 91578 45818 91578 45812 91578 45819 91579 45812 91579 45828 91579 45828 91580 45812 91580 45813 91580 45828 91581 45813 91581 45820 91581 45820 91582 45813 91582 45785 91582 45820 91583 45785 91583 45821 91583 45821 91584 45785 91584 45784 91584 45821 91585 45784 91585 45403 91585 45403 91586 45784 91586 45094 91586 45403 91587 45094 91587 45750 91587 43989 91588 45347 91588 45846 91588 45846 91589 45347 91589 45799 91589 45846 91590 45799 91590 45823 91590 45823 91591 45799 91591 45822 91591 45823 91592 45822 91592 45824 91592 45824 91593 45822 91593 45816 91593 45824 91594 45816 91594 45849 91594 45849 91595 45816 91595 45825 91595 45849 91596 45825 91596 45699 91596 45699 91597 45825 91597 45769 91597 45699 91598 45769 91598 45826 91598 45826 91599 45769 91599 45827 91599 45738 91600 45109 91600 45737 91600 45737 91601 45109 91601 45789 91601 45737 91602 45789 91602 45821 91602 45821 91603 45789 91603 45833 91603 45821 91604 45833 91604 45820 91604 45820 91605 45833 91605 45834 91605 45820 91606 45834 91606 45828 91606 45828 91607 45834 91607 45836 91607 45828 91608 45836 91608 45819 91608 45819 91609 45836 91609 45838 91609 45819 91610 45838 91610 45829 91610 45829 91611 45838 91611 45839 91611 45829 91612 45839 91612 45731 91612 45731 91613 45839 91613 45830 91613 45731 91614 45830 91614 45733 91614 45733 91615 45830 91615 45762 91615 45788 91616 45411 91616 45831 91616 45831 91617 45411 91617 45832 91617 45831 91618 45832 91618 45789 91618 45789 91619 45832 91619 45844 91619 45789 91620 45844 91620 45833 91620 45833 91621 45844 91621 45845 91621 45833 91622 45845 91622 45834 91622 45834 91623 45845 91623 45835 91623 45834 91624 45835 91624 45836 91624 45836 91625 45835 91625 45837 91625 45836 91626 45837 91626 45838 91626 45838 91627 45837 91627 45847 91627 45838 91628 45847 91628 45839 91628 45839 91629 45847 91629 45848 91629 45839 91630 45848 91630 45830 91630 45830 91631 45848 91631 45840 91631 45830 91632 45840 91632 45714 91632 45714 91633 45840 91633 45842 91633 45714 91634 45842 91634 45841 91634 45841 91635 45842 91635 43953 91635 45121 91636 45120 91636 45625 91636 45625 91637 45120 91637 45810 91637 45625 91638 45810 91638 45832 91638 45832 91639 45810 91639 45673 91639 45832 91640 45673 91640 45844 91640 45844 91641 45673 91641 45843 91641 45844 91642 45843 91642 45845 91642 45845 91643 45843 91643 45846 91643 45845 91644 45846 91644 45835 91644 45835 91645 45846 91645 45823 91645 45835 91646 45823 91646 45837 91646 45837 91647 45823 91647 45824 91647 45837 91648 45824 91648 45847 91648 45847 91649 45824 91649 45849 91649 45847 91650 45849 91650 45848 91650 45848 91651 45849 91651 45699 91651 45848 91652 45699 91652 45840 91652 45840 91653 45699 91653 45697 91653 45840 91654 45697 91654 45842 91654 45842 91655 45697 91655 45696 91655 45842 91656 45696 91656 45850 91656 45850 91657 45696 91657 43961 91657 45857 91658 46208 91658 45872 91658 45865 91659 45851 91659 45862 91659 46161 91660 45851 91660 45852 91660 45852 91661 45851 91661 45865 91661 45852 91662 45865 91662 45853 91662 45853 91663 45865 91663 46155 91663 45866 91664 46157 91664 45865 91664 45865 91665 46157 91665 46159 91665 46159 91666 46167 91666 45865 91666 45865 91667 46167 91667 45854 91667 45865 91668 45854 91668 46155 91668 45859 91669 46215 91669 45857 91669 45857 91670 46215 91670 45855 91670 46249 91671 46208 91671 45856 91671 45856 91672 46208 91672 45857 91672 45856 91673 45857 91673 46210 91673 46210 91674 45857 91674 45855 91674 46149 91675 46206 91675 45857 91675 45857 91676 46206 91676 45858 91676 45857 91677 45858 91677 45859 91677 46149 91678 45857 91678 45860 91678 45860 91679 45857 91679 45872 91679 45860 91680 45872 91680 45861 91680 45861 91681 45872 91681 45871 91681 45861 91682 45871 91682 45862 91682 45862 91683 45871 91683 45863 91683 45862 91684 45863 91684 45865 91684 45865 91685 45863 91685 45864 91685 45865 91686 45864 91686 45866 91686 46248 91687 46085 91687 45880 91687 45874 91688 45867 91688 45875 91688 45868 91689 46193 91689 45878 91689 45879 91690 45869 91690 45877 91690 45869 91691 45864 91691 45877 91691 45877 91692 45864 91692 45863 91692 45877 91693 45863 91693 45870 91693 45870 91694 45863 91694 45871 91694 45870 91695 45871 91695 45873 91695 45873 91696 45871 91696 45872 91696 45873 91697 45872 91697 46212 91697 46212 91698 45872 91698 46208 91698 46212 91699 45874 91699 45873 91699 45873 91700 45874 91700 45875 91700 45873 91701 45875 91701 45870 91701 45870 91702 45875 91702 45876 91702 45870 91703 45876 91703 45877 91703 45877 91704 45876 91704 45878 91704 45877 91705 45878 91705 45879 91705 45879 91706 45878 91706 46193 91706 45867 91707 46248 91707 45875 91707 45875 91708 46248 91708 45880 91708 45875 91709 45880 91709 45876 91709 45876 91710 45880 91710 46152 91710 45876 91711 46152 91711 45878 91711 45878 91712 46152 91712 46153 91712 45878 91713 46153 91713 45868 91713 45868 91714 46153 91714 46192 91714 46097 91715 46104 91715 45881 91715 46097 91716 45881 91716 45902 91716 45881 91717 45930 91717 45902 91717 45902 91718 45930 91718 45882 91718 45902 91719 45882 91719 45883 91719 45883 91720 45882 91720 45884 91720 45884 91721 45882 91721 45906 91721 45884 91722 45906 91722 46110 91722 46079 91723 46108 91723 45926 91723 45926 91724 46108 91724 45885 91724 45926 91725 45885 91725 45887 91725 45887 91726 45885 91726 45886 91726 45887 91727 45886 91727 45929 91727 45929 91728 45886 91728 45888 91728 46111 91729 46110 91729 45906 91729 45889 91730 45891 91730 46112 91730 45906 91731 45905 91731 46111 91731 46111 91732 45905 91732 45890 91732 46111 91733 45890 91733 46112 91733 46112 91734 45890 91734 45915 91734 46112 91735 45915 91735 45889 91735 45889 91736 45912 91736 45891 91736 45891 91737 45912 91737 45892 91737 45891 91738 45892 91738 45893 91738 45929 91739 45888 91739 45908 91739 45908 91740 45888 91740 45894 91740 45908 91741 45894 91741 45911 91741 45911 91742 45894 91742 45893 91742 45911 91743 45893 91743 45895 91743 45895 91744 45893 91744 45892 91744 45881 91745 46104 91745 45896 91745 45896 91746 46104 91746 46107 91746 45896 91747 46107 91747 45923 91747 45923 91748 46107 91748 45897 91748 45923 91749 45897 91749 45899 91749 45899 91750 45897 91750 45898 91750 45899 91751 45898 91751 45900 91751 45900 91752 45898 91752 46105 91752 46095 91753 46097 91753 45901 91753 45901 91754 46097 91754 45902 91754 45901 91755 45902 91755 45903 91755 45903 91756 45902 91756 45883 91756 45903 91757 45883 91757 46113 91757 46113 91758 45883 91758 45884 91758 46113 91759 45884 91759 45904 91759 45905 91760 45906 91760 45920 91760 45928 91761 45929 91761 45907 91761 45907 91762 45929 91762 45908 91762 45907 91763 45908 91763 45951 91763 45951 91764 45908 91764 45909 91764 45892 91765 45910 91765 45895 91765 45895 91766 45910 91766 45909 91766 45895 91767 45909 91767 45911 91767 45911 91768 45909 91768 45908 91768 45889 91769 45919 91769 45912 91769 45912 91770 45919 91770 45913 91770 45912 91771 45913 91771 45892 91771 45892 91772 45913 91772 45914 91772 45892 91773 45914 91773 45910 91773 45922 91774 45916 91774 45915 91774 45915 91775 45916 91775 45917 91775 45915 91776 45917 91776 45889 91776 45889 91777 45917 91777 45918 91777 45889 91778 45918 91778 45919 91778 45920 91779 45921 91779 45905 91779 45905 91780 45921 91780 45922 91780 45905 91781 45922 91781 45890 91781 45890 91782 45922 91782 45915 91782 46051 91783 45881 91783 46000 91783 46000 91784 45881 91784 45896 91784 46000 91785 45896 91785 45999 91785 45999 91786 45896 91786 45923 91786 45999 91787 45923 91787 45998 91787 45998 91788 45923 91788 45995 91788 45995 91789 45923 91789 45899 91789 45995 91790 45899 91790 45996 91790 45996 91791 45899 91791 46003 91791 46003 91792 45899 91792 45900 91792 46003 91793 45900 91793 45924 91793 46077 91794 46079 91794 45925 91794 45925 91795 46079 91795 45926 91795 45925 91796 45926 91796 45927 91796 45927 91797 45926 91797 45887 91797 45927 91798 45887 91798 45928 91798 45928 91799 45887 91799 45929 91799 45920 91800 45906 91800 45882 91800 45920 91801 45882 91801 46055 91801 46055 91802 45882 91802 45930 91802 46055 91803 45930 91803 45931 91803 45931 91804 45930 91804 45881 91804 45931 91805 45881 91805 46051 91805 45932 91806 46034 91806 46036 91806 45933 91807 45932 91807 45947 91807 46056 91808 45939 91808 46057 91808 46057 91809 45939 91809 45941 91809 46057 91810 45941 91810 46058 91810 46058 91811 45941 91811 45934 91811 46058 91812 45934 91812 46059 91812 46059 91813 45934 91813 46047 91813 45942 91814 45935 91814 45936 91814 45940 91815 45975 91815 45937 91815 45937 91816 45975 91816 45977 91816 45937 91817 45977 91817 45942 91817 45942 91818 45977 91818 45938 91818 45942 91819 45938 91819 45935 91819 45944 91820 45939 91820 45965 91820 45965 91821 45939 91821 46056 91821 45965 91822 46056 91822 46061 91822 45944 91823 45940 91823 45939 91823 45939 91824 45940 91824 45937 91824 45939 91825 45937 91825 45941 91825 45941 91826 45937 91826 45942 91826 45941 91827 45942 91827 45934 91827 45934 91828 45942 91828 45936 91828 45934 91829 45936 91829 46047 91829 45966 91830 45943 91830 45944 91830 45944 91831 45943 91831 45945 91831 45944 91832 45945 91832 45940 91832 46060 91833 45933 91833 45946 91833 45946 91834 45933 91834 45947 91834 45946 91835 45947 91835 45948 91835 45948 91836 45947 91836 45967 91836 45971 91837 45969 91837 45952 91837 45951 91838 45970 91838 45907 91838 45907 91839 45970 91839 45949 91839 45907 91840 45949 91840 45928 91840 45961 91841 45921 91841 45950 91841 45950 91842 45921 91842 45920 91842 45950 91843 45920 91843 45962 91843 45918 91844 45917 91844 45953 91844 45953 91845 45917 91845 45916 91845 45953 91846 45916 91846 45961 91846 45961 91847 45916 91847 45922 91847 45961 91848 45922 91848 45921 91848 45951 91849 45909 91849 45969 91849 45969 91850 45909 91850 45910 91850 45969 91851 45910 91851 45952 91851 45952 91852 45910 91852 45914 91852 45952 91853 45914 91853 45959 91853 45959 91854 45914 91854 45913 91854 45959 91855 45913 91855 45953 91855 45953 91856 45913 91856 45919 91856 45953 91857 45919 91857 45918 91857 45971 91858 45958 91858 45972 91858 45972 91859 45958 91859 45955 91859 45972 91860 45955 91860 45954 91860 45954 91861 45955 91861 45956 91861 45954 91862 45956 91862 45973 91862 45973 91863 45956 91863 45960 91863 45973 91864 45960 91864 45974 91864 45974 91865 45960 91865 45963 91865 45974 91866 45963 91866 45976 91866 45976 91867 45963 91867 45957 91867 45976 91868 45957 91868 46053 91868 45971 91869 45952 91869 45958 91869 45958 91870 45952 91870 45959 91870 45958 91871 45959 91871 45955 91871 45955 91872 45959 91872 45953 91872 45955 91873 45953 91873 45956 91873 45956 91874 45953 91874 45961 91874 45956 91875 45961 91875 45960 91875 45960 91876 45961 91876 45950 91876 45960 91877 45950 91877 45963 91877 45963 91878 45950 91878 45962 91878 45963 91879 45962 91879 45957 91879 45932 91880 46036 91880 45947 91880 45947 91881 46036 91881 46035 91881 45947 91882 46035 91882 45967 91882 45967 91883 46035 91883 45964 91883 45967 91884 45964 91884 45968 91884 46061 91885 46060 91885 45965 91885 45965 91886 46060 91886 45946 91886 45965 91887 45946 91887 45944 91887 45944 91888 45946 91888 45948 91888 45944 91889 45948 91889 45966 91889 45966 91890 45948 91890 45967 91890 45966 91891 45967 91891 45970 91891 45970 91892 45967 91892 45968 91892 45970 91893 45968 91893 45949 91893 45951 91894 45969 91894 45970 91894 45970 91895 45969 91895 45971 91895 45970 91896 45971 91896 45966 91896 45966 91897 45971 91897 45972 91897 45966 91898 45972 91898 45943 91898 45943 91899 45972 91899 45954 91899 45943 91900 45954 91900 45945 91900 45945 91901 45954 91901 45973 91901 45945 91902 45973 91902 45940 91902 45940 91903 45973 91903 45974 91903 45940 91904 45974 91904 45975 91904 45975 91905 45974 91905 45976 91905 45975 91906 45976 91906 45977 91906 45977 91907 45976 91907 46053 91907 45977 91908 46053 91908 45938 91908 45978 91909 46077 91909 46009 91909 45987 91910 46026 91910 45979 91910 46012 91911 46041 91911 46040 91911 46064 91912 45993 91912 45980 91912 45980 91913 45993 91913 45981 91913 45980 91914 45981 91914 45982 91914 45982 91915 45981 91915 45992 91915 45982 91916 45992 91916 46066 91916 46011 91917 46040 91917 45983 91917 46024 91918 45985 91918 45984 91918 45984 91919 45985 91919 45986 91919 45986 91920 45985 91920 46063 91920 45986 91921 46063 91921 45979 91921 45979 91922 46026 91922 45986 91922 45986 91923 46026 91923 46025 91923 45986 91924 46025 91924 45984 91924 46063 91925 46067 91925 45979 91925 45979 91926 46067 91926 45988 91926 45979 91927 45988 91927 45987 91927 45987 91928 45988 91928 45990 91928 45987 91929 45990 91929 45989 91929 45989 91930 45990 91930 45994 91930 45989 91931 45994 91931 46030 91931 46030 91932 45994 91932 45991 91932 46030 91933 45991 91933 46032 91933 46067 91934 46066 91934 45988 91934 45988 91935 46066 91935 45992 91935 45988 91936 45992 91936 45990 91936 45990 91937 45992 91937 45981 91937 45990 91938 45981 91938 45994 91938 45994 91939 45981 91939 45993 91939 45994 91940 45993 91940 45991 91940 45997 91941 45995 91941 45996 91941 45997 91942 45996 91942 46004 91942 45995 91943 45997 91943 45998 91943 45998 91944 45997 91944 46020 91944 45998 91945 46020 91945 45999 91945 45999 91946 46020 91946 46019 91946 45999 91947 46019 91947 46000 91947 46051 91948 46000 91948 46001 91948 46001 91949 46000 91949 46019 91949 46001 91950 46019 91950 46002 91950 45996 91951 46003 91951 46004 91951 46004 91952 46003 91952 45924 91952 46004 91953 45924 91953 46022 91953 46022 91954 45924 91954 46005 91954 46022 91955 46005 91955 46006 91955 46006 91956 46005 91956 46074 91956 46006 91957 46074 91957 46073 91957 46073 91958 46007 91958 46006 91958 46006 91959 46007 91959 45978 91959 46006 91960 45978 91960 46008 91960 46008 91961 45978 91961 46009 91961 46008 91962 46009 91962 46010 91962 46040 91963 46011 91963 46012 91963 46012 91964 46011 91964 46013 91964 46012 91965 46013 91965 46023 91965 46023 91966 46013 91966 46015 91966 46023 91967 46015 91967 46014 91967 46014 91968 46015 91968 46027 91968 46014 91969 46027 91969 46016 91969 46016 91970 46027 91970 46028 91970 46016 91971 46028 91971 46017 91971 46017 91972 46028 91972 46029 91972 46017 91973 46029 91973 46021 91973 46021 91974 46029 91974 46031 91974 46021 91975 46031 91975 46018 91975 46018 91976 46031 91976 46049 91976 46018 91977 46049 91977 46002 91977 46002 91978 46019 91978 46018 91978 46018 91979 46019 91979 46020 91979 46018 91980 46020 91980 46021 91980 46021 91981 46020 91981 45997 91981 46021 91982 45997 91982 46017 91982 46017 91983 45997 91983 46004 91983 46017 91984 46004 91984 46016 91984 46016 91985 46004 91985 46022 91985 46016 91986 46022 91986 46014 91986 46014 91987 46022 91987 46006 91987 46014 91988 46006 91988 46023 91988 46023 91989 46006 91989 46008 91989 46023 91990 46008 91990 46012 91990 46012 91991 46008 91991 46010 91991 46012 91992 46010 91992 46041 91992 45983 91993 46024 91993 46011 91993 46011 91994 46024 91994 45984 91994 46011 91995 45984 91995 46013 91995 46013 91996 45984 91996 46025 91996 46013 91997 46025 91997 46015 91997 46015 91998 46025 91998 46026 91998 46015 91999 46026 91999 46027 91999 46027 92000 46026 92000 45987 92000 46027 92001 45987 92001 46028 92001 46028 92002 45987 92002 45989 92002 46028 92003 45989 92003 46029 92003 46029 92004 45989 92004 46030 92004 46029 92005 46030 92005 46031 92005 46031 92006 46030 92006 46032 92006 46031 92007 46032 92007 46049 92007 46033 92008 46038 92008 46042 92008 46062 92009 45983 92009 46040 92009 46036 92010 46034 92010 46071 92010 45964 92011 46035 92011 46033 92011 46033 92012 46035 92012 46036 92012 46036 92013 46071 92013 46033 92013 46033 92014 46071 92014 46037 92014 46033 92015 46037 92015 46038 92015 46038 92016 46037 92016 46069 92016 46038 92017 46069 92017 46062 92017 45949 92018 45968 92018 46039 92018 46039 92019 45968 92019 45964 92019 45928 92020 45949 92020 45927 92020 45927 92021 45949 92021 46039 92021 45927 92022 46039 92022 45925 92022 46062 92023 46040 92023 46038 92023 46038 92024 46040 92024 46041 92024 46038 92025 46041 92025 46042 92025 46042 92026 46041 92026 46010 92026 46042 92027 46010 92027 46009 92027 45964 92028 46033 92028 46039 92028 46039 92029 46033 92029 46042 92029 46039 92030 46042 92030 45925 92030 45925 92031 46042 92031 46009 92031 45925 92032 46009 92032 46077 92032 46001 92033 46002 92033 46043 92033 46068 92034 46070 92034 46048 92034 46064 92035 46044 92035 45993 92035 45993 92036 46044 92036 46050 92036 46059 92037 46047 92037 46045 92037 46045 92038 46047 92038 46070 92038 46046 92039 46054 92039 46052 92039 46052 92040 46054 92040 46050 92040 46070 92041 46047 92041 46048 92041 46048 92042 46047 92042 45936 92042 46048 92043 45936 92043 45935 92043 46044 92044 46068 92044 46050 92044 46050 92045 46068 92045 46048 92045 46050 92046 46048 92046 46052 92046 46052 92047 46048 92047 45935 92047 46002 92048 46049 92048 46054 92048 46054 92049 46049 92049 46032 92049 46054 92050 46032 92050 46050 92050 46050 92051 46032 92051 45991 92051 46050 92052 45991 92052 45993 92052 46055 92053 45931 92053 46043 92053 46043 92054 45931 92054 46051 92054 46043 92055 46051 92055 46001 92055 45935 92056 45938 92056 46052 92056 46052 92057 45938 92057 46053 92057 46052 92058 46053 92058 46046 92058 46046 92059 46053 92059 45957 92059 46046 92060 45957 92060 45962 92060 46002 92061 46054 92061 46043 92061 46043 92062 46054 92062 46046 92062 46043 92063 46046 92063 46055 92063 46055 92064 46046 92064 45962 92064 46055 92065 45962 92065 45920 92065 46072 92066 46059 92066 46045 92066 46072 92067 46061 92067 46056 92067 46056 92068 46057 92068 46072 92068 46072 92069 46057 92069 46058 92069 46072 92070 46058 92070 46059 92070 45932 92071 45933 92071 46072 92071 46072 92072 45933 92072 46060 92072 46072 92073 46060 92073 46061 92073 46065 92074 45983 92074 46062 92074 46024 92075 45983 92075 45985 92075 45985 92076 45983 92076 46065 92076 45985 92077 46065 92077 46063 92077 46064 92078 45980 92078 46065 92078 46065 92079 45980 92079 45982 92079 45982 92080 46066 92080 46065 92080 46065 92081 46066 92081 46067 92081 46065 92082 46067 92082 46063 92082 46064 92083 46065 92083 46044 92083 46044 92084 46065 92084 46062 92084 46044 92085 46062 92085 46068 92085 46068 92086 46062 92086 46069 92086 46068 92087 46069 92087 46070 92087 46070 92088 46069 92088 46037 92088 46070 92089 46037 92089 46045 92089 46045 92090 46037 92090 46071 92090 46045 92091 46071 92091 46072 92091 46072 92092 46071 92092 46034 92092 46072 92093 46034 92093 45932 92093 45978 92094 46007 92094 46075 92094 46007 92095 46073 92095 46075 92095 46075 92096 46073 92096 46074 92096 46075 92097 46074 92097 45900 92097 45900 92098 46074 92098 46005 92098 45900 92099 46005 92099 45924 92099 46075 92100 46076 92100 45978 92100 45978 92101 46076 92101 46079 92101 45978 92102 46079 92102 46077 92102 45900 92103 46105 92103 46075 92103 46075 92104 46105 92104 46078 92104 46075 92105 46078 92105 46076 92105 46076 92106 46078 92106 46080 92106 46076 92107 46080 92107 46079 92107 46079 92108 46080 92108 46108 92108 46081 92109 46230 92109 46088 92109 46082 92110 46232 92110 46083 92110 46088 92111 46230 92111 46083 92111 46083 92112 46230 92112 46234 92112 46083 92113 46234 92113 46082 92113 46084 92114 46150 92114 46085 92114 46085 92115 46247 92115 46084 92115 46084 92116 46247 92116 46086 92116 46084 92117 46086 92117 46088 92117 46088 92118 46086 92118 46235 92118 46088 92119 46235 92119 46081 92119 46083 92120 46087 92120 46088 92120 46088 92121 46087 92121 46089 92121 46088 92122 46089 92122 46084 92122 46084 92123 46089 92123 46090 92123 46084 92124 46090 92124 46150 92124 46150 92125 46090 92125 46091 92125 46132 92126 46092 92126 46133 92126 46133 92127 46092 92127 46093 92127 46133 92128 46093 92128 46083 92128 46083 92129 46093 92129 46087 92129 46118 92130 46113 92130 46094 92130 46094 92131 46113 92131 45904 92131 46094 92132 45904 92132 46132 92132 46132 92133 45904 92133 45884 92133 46132 92134 45884 92134 46092 92134 46128 92135 46106 92135 46099 92135 45901 92136 46115 92136 46095 92136 46095 92137 46115 92137 46096 92137 46095 92138 46096 92138 46097 92138 46097 92139 46096 92139 46126 92139 46097 92140 46126 92140 46099 92140 46099 92141 46126 92141 46098 92141 46099 92142 46098 92142 46128 92142 46128 92143 46123 92143 46106 92143 46106 92144 46123 92144 46124 92144 46106 92145 46124 92145 46100 92145 46154 92146 46109 92146 46101 92146 46101 92147 46109 92147 46102 92147 46101 92148 46102 92148 46103 92148 46103 92149 46102 92149 46100 92149 46103 92150 46100 92150 46122 92150 46122 92151 46100 92151 46124 92151 46104 92152 46097 92152 46099 92152 46105 92153 46106 92153 46100 92153 46105 92154 45898 92154 46106 92154 46106 92155 45898 92155 45897 92155 46106 92156 45897 92156 46099 92156 46099 92157 45897 92157 46107 92157 46099 92158 46107 92158 46104 92158 46108 92159 46080 92159 46100 92159 46100 92160 46080 92160 46078 92160 46100 92161 46078 92161 46105 92161 46087 92162 45893 92162 46089 92162 46089 92163 45893 92163 45894 92163 46089 92164 45894 92164 46090 92164 46090 92165 45894 92165 45888 92165 46090 92166 45888 92166 46091 92166 46091 92167 45888 92167 45886 92167 46091 92168 45886 92168 46119 92168 46119 92169 45886 92169 45885 92169 46119 92170 45885 92170 46109 92170 46109 92171 45885 92171 46108 92171 46109 92172 46108 92172 46102 92172 46102 92173 46108 92173 46100 92173 45884 92174 46110 92174 46092 92174 46092 92175 46110 92175 46111 92175 46092 92176 46111 92176 46093 92176 46093 92177 46111 92177 46112 92177 46093 92178 46112 92178 46087 92178 46087 92179 46112 92179 45891 92179 46087 92180 45891 92180 45893 92180 46113 92181 46118 92181 46116 92181 46113 92182 46116 92182 45903 92182 45903 92183 46116 92183 46115 92183 45903 92184 46115 92184 45901 92184 46178 92185 46115 92185 46114 92185 46114 92186 46115 92186 46116 92186 46114 92187 46116 92187 46117 92187 46118 92188 46139 92188 46116 92188 46116 92189 46139 92189 46138 92189 46116 92190 46138 92190 46117 92190 46150 92191 46091 92191 46151 92191 46151 92192 46091 92192 46119 92192 46151 92193 46119 92193 46154 92193 46154 92194 46119 92194 46109 92194 46096 92195 46115 92195 46178 92195 46192 92196 46154 92196 46120 92196 46120 92197 46154 92197 46101 92197 46120 92198 46101 92198 46164 92198 46164 92199 46101 92199 46121 92199 46101 92200 46103 92200 46121 92200 46121 92201 46103 92201 46122 92201 46121 92202 46122 92202 46125 92202 46128 92203 46130 92203 46123 92203 46123 92204 46130 92204 46125 92204 46123 92205 46125 92205 46124 92205 46124 92206 46125 92206 46122 92206 46126 92207 46127 92207 46098 92207 46098 92208 46127 92208 46174 92208 46098 92209 46174 92209 46128 92209 46128 92210 46174 92210 46129 92210 46128 92211 46129 92211 46130 92211 46178 92212 46189 92212 46096 92212 46096 92213 46189 92213 46191 92213 46096 92214 46191 92214 46126 92214 46126 92215 46191 92215 46131 92215 46126 92216 46131 92216 46127 92216 46139 92217 46118 92217 46229 92217 46229 92218 46118 92218 46094 92218 46229 92219 46094 92219 46227 92219 46227 92220 46094 92220 46132 92220 46227 92221 46132 92221 46225 92221 46225 92222 46132 92222 46224 92222 46224 92223 46132 92223 46133 92223 46224 92224 46133 92224 46223 92224 46223 92225 46133 92225 46134 92225 46134 92226 46133 92226 46083 92226 46134 92227 46083 92227 46232 92227 46135 92228 46222 92228 46149 92228 46222 92229 46135 92229 46218 92229 46136 92230 46137 92230 46148 92230 46177 92231 46178 92231 46114 92231 46141 92232 46176 92232 46136 92232 46136 92233 46176 92233 46177 92233 46177 92234 46114 92234 46136 92234 46136 92235 46114 92235 46117 92235 46136 92236 46117 92236 46137 92236 46137 92237 46117 92237 46138 92237 46137 92238 46138 92238 46139 92238 46147 92239 46175 92239 46140 92239 46140 92240 46175 92240 46141 92240 46139 92241 46142 92241 46137 92241 46137 92242 46142 92242 46143 92242 46137 92243 46143 92243 46148 92243 46148 92244 46143 92244 46204 92244 46148 92245 46204 92245 46144 92245 46145 92246 46147 92246 46146 92246 46146 92247 46147 92247 46140 92247 46146 92248 46140 92248 46135 92248 46141 92249 46136 92249 46140 92249 46140 92250 46136 92250 46148 92250 46140 92251 46148 92251 46135 92251 46135 92252 46148 92252 46144 92252 46135 92253 46144 92253 46218 92253 45851 92254 46145 92254 45862 92254 45862 92255 46145 92255 46146 92255 45862 92256 46146 92256 45861 92256 45861 92257 46146 92257 46135 92257 45861 92258 46135 92258 45860 92258 45860 92259 46135 92259 46149 92259 45880 92260 46085 92260 46150 92260 45880 92261 46150 92261 46152 92261 46152 92262 46150 92262 46151 92262 46152 92263 46151 92263 46153 92263 46153 92264 46151 92264 46154 92264 46153 92265 46154 92265 46192 92265 46168 92266 46158 92266 46169 92266 46155 92267 45854 92267 46156 92267 46157 92268 45866 92268 46165 92268 46168 92269 46167 92269 46158 92269 46158 92270 46167 92270 46159 92270 46158 92271 46159 92271 46157 92271 46161 92272 45852 92272 46201 92272 46201 92273 45852 92273 45853 92273 46201 92274 45853 92274 46160 92274 46201 92275 46203 92275 46161 92275 46161 92276 46203 92276 46145 92276 46161 92277 46145 92277 45851 92277 45853 92278 46155 92278 46160 92278 46160 92279 46155 92279 46156 92279 46160 92280 46156 92280 46200 92280 46200 92281 46156 92281 46170 92281 46200 92282 46170 92282 46162 92282 46162 92283 46170 92283 46163 92283 46162 92284 46163 92284 46198 92284 46198 92285 46163 92285 46172 92285 46198 92286 46172 92286 46196 92286 46120 92287 46164 92287 46166 92287 46166 92288 46164 92288 46195 92288 46157 92289 46165 92289 46158 92289 46158 92290 46165 92290 46194 92290 46158 92291 46194 92291 46169 92291 46169 92292 46194 92292 46166 92292 46169 92293 46166 92293 46171 92293 46171 92294 46166 92294 46195 92294 46171 92295 46195 92295 46173 92295 45854 92296 46167 92296 46156 92296 46156 92297 46167 92297 46168 92297 46156 92298 46168 92298 46170 92298 46170 92299 46168 92299 46169 92299 46170 92300 46169 92300 46163 92300 46163 92301 46169 92301 46171 92301 46163 92302 46171 92302 46172 92302 46172 92303 46171 92303 46173 92303 46172 92304 46173 92304 46196 92304 46174 92305 46127 92305 46190 92305 46190 92306 46127 92306 46131 92306 46190 92307 46131 92307 46191 92307 46130 92308 46129 92308 46197 92308 46147 92309 46202 92309 46175 92309 46175 92310 46202 92310 46184 92310 46175 92311 46184 92311 46141 92311 46141 92312 46184 92312 46185 92312 46141 92313 46185 92313 46176 92313 46176 92314 46185 92314 46186 92314 46176 92315 46186 92315 46177 92315 46177 92316 46186 92316 46188 92316 46177 92317 46188 92317 46178 92317 46178 92318 46188 92318 46189 92318 46129 92319 46174 92319 46197 92319 46197 92320 46174 92320 46190 92320 46197 92321 46190 92321 46199 92321 46199 92322 46190 92322 46187 92322 46199 92323 46187 92323 46180 92323 46180 92324 46187 92324 46179 92324 46180 92325 46179 92325 46181 92325 46181 92326 46179 92326 46182 92326 46181 92327 46182 92327 46183 92327 46202 92328 46183 92328 46184 92328 46184 92329 46183 92329 46182 92329 46184 92330 46182 92330 46185 92330 46185 92331 46182 92331 46179 92331 46185 92332 46179 92332 46186 92332 46186 92333 46179 92333 46187 92333 46186 92334 46187 92334 46188 92334 46188 92335 46187 92335 46190 92335 46188 92336 46190 92336 46189 92336 46189 92337 46190 92337 46191 92337 46192 92338 46120 92338 45868 92338 45868 92339 46120 92339 46166 92339 45868 92340 46166 92340 46193 92340 46193 92341 46166 92341 46194 92341 46193 92342 46194 92342 45879 92342 45879 92343 46194 92343 46165 92343 45879 92344 46165 92344 45869 92344 45869 92345 46165 92345 45866 92345 45869 92346 45866 92346 45864 92346 46164 92347 46121 92347 46195 92347 46195 92348 46121 92348 46125 92348 46195 92349 46125 92349 46173 92349 46173 92350 46125 92350 46130 92350 46173 92351 46130 92351 46196 92351 46196 92352 46130 92352 46197 92352 46196 92353 46197 92353 46198 92353 46198 92354 46197 92354 46199 92354 46198 92355 46199 92355 46162 92355 46162 92356 46199 92356 46180 92356 46162 92357 46180 92357 46200 92357 46200 92358 46180 92358 46181 92358 46200 92359 46181 92359 46160 92359 46160 92360 46181 92360 46183 92360 46160 92361 46183 92361 46201 92361 46201 92362 46183 92362 46202 92362 46201 92363 46202 92363 46203 92363 46203 92364 46202 92364 46147 92364 46203 92365 46147 92365 46145 92365 45867 92366 45874 92366 46242 92366 46247 92367 46085 92367 46248 92367 46204 92368 46143 92368 46236 92368 46217 92369 46253 92369 46205 92369 45859 92370 45858 92370 46219 92370 46219 92371 45858 92371 46206 92371 46219 92372 46206 92372 46207 92372 46207 92373 46206 92373 46149 92373 46207 92374 46149 92374 46222 92374 46213 92375 46212 92375 46208 92375 46249 92376 45856 92376 46209 92376 46209 92377 45856 92377 46210 92377 46209 92378 46210 92378 46211 92378 46211 92379 46210 92379 45855 92379 46211 92380 45855 92380 46205 92380 45874 92381 46212 92381 46242 92381 46242 92382 46212 92382 46213 92382 46242 92383 46213 92383 46214 92383 46205 92384 46253 92384 46211 92384 46211 92385 46253 92385 46250 92385 46211 92386 46250 92386 46209 92386 45855 92387 46215 92387 46205 92387 46205 92388 46215 92388 46216 92388 46205 92389 46216 92389 46217 92389 46217 92390 46216 92390 46220 92390 46217 92391 46220 92391 46255 92391 46255 92392 46220 92392 46221 92392 46255 92393 46221 92393 46257 92393 46257 92394 46221 92394 46218 92394 46257 92395 46218 92395 46144 92395 46215 92396 45859 92396 46216 92396 46216 92397 45859 92397 46219 92397 46216 92398 46219 92398 46220 92398 46220 92399 46219 92399 46207 92399 46220 92400 46207 92400 46221 92400 46221 92401 46207 92401 46222 92401 46221 92402 46222 92402 46218 92402 46134 92403 46244 92403 46223 92403 46223 92404 46244 92404 46226 92404 46223 92405 46226 92405 46224 92405 46224 92406 46226 92406 46225 92406 46225 92407 46226 92407 46228 92407 46225 92408 46228 92408 46227 92408 46227 92409 46228 92409 46243 92409 46227 92410 46243 92410 46229 92410 46139 92411 46229 92411 46142 92411 46142 92412 46229 92412 46243 92412 46142 92413 46243 92413 46143 92413 46081 92414 46231 92414 46230 92414 46230 92415 46231 92415 46233 92415 46134 92416 46232 92416 46244 92416 46244 92417 46232 92417 46082 92417 46244 92418 46082 92418 46233 92418 46233 92419 46082 92419 46234 92419 46233 92420 46234 92420 46230 92420 46081 92421 46235 92421 46231 92421 46231 92422 46235 92422 46086 92422 46231 92423 46086 92423 46247 92423 46204 92424 46236 92424 46237 92424 46237 92425 46236 92425 46238 92425 46237 92426 46238 92426 46256 92426 46256 92427 46238 92427 46245 92427 46256 92428 46245 92428 46254 92428 46254 92429 46245 92429 46239 92429 46254 92430 46239 92430 46252 92430 46252 92431 46239 92431 46240 92431 46252 92432 46240 92432 46251 92432 46251 92433 46240 92433 46246 92433 46251 92434 46246 92434 46214 92434 46214 92435 46246 92435 46242 92435 46242 92436 46246 92436 46241 92436 46242 92437 46241 92437 45867 92437 46143 92438 46243 92438 46236 92438 46236 92439 46243 92439 46228 92439 46236 92440 46228 92440 46238 92440 46238 92441 46228 92441 46226 92441 46238 92442 46226 92442 46245 92442 46245 92443 46226 92443 46244 92443 46245 92444 46244 92444 46239 92444 46239 92445 46244 92445 46233 92445 46239 92446 46233 92446 46240 92446 46240 92447 46233 92447 46231 92447 46240 92448 46231 92448 46246 92448 46246 92449 46231 92449 46247 92449 46246 92450 46247 92450 46241 92450 46241 92451 46247 92451 46248 92451 46241 92452 46248 92452 45867 92452 46208 92453 46249 92453 46213 92453 46213 92454 46249 92454 46209 92454 46213 92455 46209 92455 46214 92455 46214 92456 46209 92456 46250 92456 46214 92457 46250 92457 46251 92457 46251 92458 46250 92458 46253 92458 46251 92459 46253 92459 46252 92459 46252 92460 46253 92460 46217 92460 46252 92461 46217 92461 46254 92461 46254 92462 46217 92462 46255 92462 46254 92463 46255 92463 46256 92463 46256 92464 46255 92464 46257 92464 46256 92465 46257 92465 46237 92465 46237 92466 46257 92466 46144 92466 46237 92467 46144 92467 46204 92467 46502 92468 46259 92468 46258 92468 46502 92469 46258 92469 46550 92469 46550 92470 46258 92470 46463 92470 46550 92471 46463 92471 46546 92471 46546 92472 46463 92472 46476 92472 46546 92473 46476 92473 46585 92473 46466 92474 46259 92474 46502 92474 46272 92475 46260 92475 46261 92475 46261 92476 46260 92476 46471 92476 46261 92477 46471 92477 46262 92477 46262 92478 46471 92478 46263 92478 46264 92479 46265 92479 46474 92479 46474 92480 46265 92480 46263 92480 46474 92481 46263 92481 46473 92481 46473 92482 46263 92482 46471 92482 46267 92483 46270 92483 46470 92483 46470 92484 46270 92484 46508 92484 46470 92485 46508 92485 46264 92485 46264 92486 46508 92486 46507 92486 46264 92487 46507 92487 46265 92487 46266 92488 46503 92488 46469 92488 46469 92489 46503 92489 46268 92489 46469 92490 46268 92490 46267 92490 46267 92491 46268 92491 46269 92491 46267 92492 46269 92492 46270 92492 46502 92493 46504 92493 46466 92493 46466 92494 46504 92494 46266 92494 46466 92495 46266 92495 46468 92495 46468 92496 46266 92496 46469 92496 46566 92497 46281 92497 46559 92497 46559 92498 46281 92498 46482 92498 46559 92499 46482 92499 46271 92499 46271 92500 46482 92500 46273 92500 46271 92501 46273 92501 46272 92501 46272 92502 46273 92502 46260 92502 46640 92503 46641 92503 46274 92503 46274 92504 46641 92504 46464 92504 46274 92505 46464 92505 46661 92505 46661 92506 46464 92506 46275 92506 46661 92507 46275 92507 46637 92507 46637 92508 46275 92508 46276 92508 46637 92509 46276 92509 46277 92509 46590 92510 46632 92510 46481 92510 46590 92511 46481 92511 46278 92511 46481 92512 46279 92512 46278 92512 46278 92513 46279 92513 46281 92513 46278 92514 46281 92514 46566 92514 46481 92515 46651 92515 46279 92515 46279 92516 46651 92516 46280 92516 46279 92517 46280 92517 46281 92517 46281 92518 46280 92518 46654 92518 46282 92519 46283 92519 46406 92519 46406 92520 46283 92520 46284 92520 46406 92521 46284 92521 46407 92521 46407 92522 46284 92522 46296 92522 46407 92523 46296 92523 46408 92523 46288 92524 46285 92524 46287 92524 46287 92525 46285 92525 46296 92525 46296 92526 46285 92526 46286 92526 46296 92527 46286 92527 46408 92527 46287 92528 46289 92528 46288 92528 46288 92529 46289 92529 46291 92529 46288 92530 46291 92530 46290 92530 46290 92531 46291 92531 46293 92531 46290 92532 46293 92532 46446 92532 46294 92533 46292 92533 46293 92533 46293 92534 46291 92534 46294 92534 46294 92535 46291 92535 46289 92535 46294 92536 46289 92536 46658 92536 46283 92537 46636 92537 46284 92537 46284 92538 46636 92538 46295 92538 46284 92539 46295 92539 46296 92539 46296 92540 46295 92540 46658 92540 46296 92541 46658 92541 46287 92541 46287 92542 46658 92542 46289 92542 46303 92543 46300 92543 46316 92543 46316 92544 46300 92544 46297 92544 46316 92545 46297 92545 46317 92545 46312 92546 46402 92546 46297 92546 46297 92547 46402 92547 46298 92547 46297 92548 46298 92548 46317 92548 46293 92549 46292 92549 46330 92549 46330 92550 46292 92550 46299 92550 46330 92551 46299 92551 46301 92551 46301 92552 46299 92552 46655 92552 46306 92553 46300 92553 46303 92553 46366 92554 46301 92554 46367 92554 46367 92555 46301 92555 46645 92555 46367 92556 46645 92556 46371 92556 46371 92557 46645 92557 46372 92557 46645 92558 46647 92558 46372 92558 46372 92559 46647 92559 46648 92559 46372 92560 46648 92560 46302 92560 46310 92561 46374 92561 46644 92561 46644 92562 46374 92562 46302 92562 46644 92563 46302 92563 46649 92563 46649 92564 46302 92564 46648 92564 46303 92565 46304 92565 46306 92565 46306 92566 46304 92566 46305 92566 46306 92567 46305 92567 46307 92567 46307 92568 46305 92568 46308 92568 46307 92569 46308 92569 46309 92569 46309 92570 46308 92570 46311 92570 46309 92571 46311 92571 46310 92571 46310 92572 46311 92572 46331 92572 46310 92573 46331 92573 46374 92573 46402 92574 46312 92574 46403 92574 46403 92575 46312 92575 46638 92575 46403 92576 46638 92576 46313 92576 46313 92577 46638 92577 46639 92577 46313 92578 46639 92578 46314 92578 46314 92579 46639 92579 46283 92579 46314 92580 46283 92580 46282 92580 46326 92581 46400 92581 46384 92581 46400 92582 46326 92582 46396 92582 46315 92583 46318 92583 46324 92583 46359 92584 46303 92584 46316 92584 46323 92585 46357 92585 46315 92585 46315 92586 46357 92586 46359 92586 46359 92587 46316 92587 46315 92587 46315 92588 46316 92588 46317 92588 46315 92589 46317 92589 46318 92589 46318 92590 46317 92590 46298 92590 46318 92591 46298 92591 46402 92591 46321 92592 46319 92592 46325 92592 46325 92593 46319 92593 46323 92593 46402 92594 46401 92594 46318 92594 46318 92595 46401 92595 46320 92595 46318 92596 46320 92596 46324 92596 46324 92597 46320 92597 46432 92597 46324 92598 46432 92598 46430 92598 46338 92599 46321 92599 46322 92599 46322 92600 46321 92600 46325 92600 46322 92601 46325 92601 46326 92601 46323 92602 46315 92602 46325 92602 46325 92603 46315 92603 46324 92603 46325 92604 46324 92604 46326 92604 46326 92605 46324 92605 46430 92605 46326 92606 46430 92606 46396 92606 46327 92607 46338 92607 46443 92607 46443 92608 46338 92608 46322 92608 46443 92609 46322 92609 46328 92609 46328 92610 46322 92610 46326 92610 46328 92611 46326 92611 46442 92611 46442 92612 46326 92612 46384 92612 46446 92613 46293 92613 46329 92613 46329 92614 46293 92614 46330 92614 46329 92615 46330 92615 46458 92615 46301 92616 46366 92616 46330 92616 46330 92617 46366 92617 46459 92617 46330 92618 46459 92618 46458 92618 46331 92619 46311 92619 46376 92619 46308 92620 46305 92620 46332 92620 46349 92621 46343 92621 46350 92621 46340 92622 46333 92622 46347 92622 46335 92623 46436 92623 46369 92623 46349 92624 46346 92624 46343 92624 46343 92625 46346 92625 46334 92625 46343 92626 46334 92626 46335 92626 46434 92627 46435 92627 46336 92627 46336 92628 46435 92628 46339 92628 46336 92629 46339 92629 46341 92629 46336 92630 46337 92630 46434 92630 46434 92631 46337 92631 46338 92631 46434 92632 46338 92632 46327 92632 46339 92633 46340 92633 46341 92633 46341 92634 46340 92634 46347 92634 46341 92635 46347 92635 46381 92635 46381 92636 46347 92636 46348 92636 46381 92637 46348 92637 46379 92637 46379 92638 46348 92638 46342 92638 46379 92639 46342 92639 46377 92639 46377 92640 46342 92640 46351 92640 46377 92641 46351 92641 46375 92641 46367 92642 46371 92642 46345 92642 46345 92643 46371 92643 46373 92643 46335 92644 46369 92644 46343 92644 46343 92645 46369 92645 46344 92645 46343 92646 46344 92646 46350 92646 46350 92647 46344 92647 46345 92647 46350 92648 46345 92648 46352 92648 46352 92649 46345 92649 46373 92649 46352 92650 46373 92650 46353 92650 46333 92651 46346 92651 46347 92651 46347 92652 46346 92652 46349 92652 46347 92653 46349 92653 46348 92653 46348 92654 46349 92654 46350 92654 46348 92655 46350 92655 46342 92655 46342 92656 46350 92656 46352 92656 46342 92657 46352 92657 46351 92657 46351 92658 46352 92658 46353 92658 46351 92659 46353 92659 46375 92659 46331 92660 46376 92660 46374 92660 46321 92661 46354 92661 46319 92661 46319 92662 46354 92662 46355 92662 46319 92663 46355 92663 46323 92663 46323 92664 46355 92664 46356 92664 46323 92665 46356 92665 46357 92665 46357 92666 46356 92666 46358 92666 46357 92667 46358 92667 46359 92667 46359 92668 46358 92668 46365 92668 46359 92669 46365 92669 46303 92669 46303 92670 46365 92670 46304 92670 46311 92671 46308 92671 46376 92671 46376 92672 46308 92672 46332 92672 46376 92673 46332 92673 46378 92673 46378 92674 46332 92674 46364 92674 46378 92675 46364 92675 46380 92675 46380 92676 46364 92676 46360 92676 46380 92677 46360 92677 46362 92677 46362 92678 46360 92678 46361 92678 46362 92679 46361 92679 46363 92679 46354 92680 46363 92680 46355 92680 46355 92681 46363 92681 46361 92681 46355 92682 46361 92682 46356 92682 46356 92683 46361 92683 46360 92683 46356 92684 46360 92684 46358 92684 46358 92685 46360 92685 46364 92685 46358 92686 46364 92686 46365 92686 46365 92687 46364 92687 46332 92687 46365 92688 46332 92688 46304 92688 46304 92689 46332 92689 46305 92689 46366 92690 46367 92690 46461 92690 46461 92691 46367 92691 46345 92691 46461 92692 46345 92692 46447 92692 46447 92693 46345 92693 46344 92693 46447 92694 46344 92694 46368 92694 46368 92695 46344 92695 46369 92695 46368 92696 46369 92696 46370 92696 46370 92697 46369 92697 46436 92697 46370 92698 46436 92698 46448 92698 46371 92699 46372 92699 46373 92699 46373 92700 46372 92700 46302 92700 46373 92701 46302 92701 46353 92701 46353 92702 46302 92702 46374 92702 46353 92703 46374 92703 46375 92703 46375 92704 46374 92704 46376 92704 46375 92705 46376 92705 46377 92705 46377 92706 46376 92706 46378 92706 46377 92707 46378 92707 46379 92707 46379 92708 46378 92708 46380 92708 46379 92709 46380 92709 46381 92709 46381 92710 46380 92710 46362 92710 46381 92711 46362 92711 46341 92711 46341 92712 46362 92712 46363 92712 46341 92713 46363 92713 46336 92713 46336 92714 46363 92714 46354 92714 46336 92715 46354 92715 46337 92715 46337 92716 46354 92716 46321 92716 46337 92717 46321 92717 46338 92717 46290 92718 46446 92718 46445 92718 46382 92719 46391 92719 46390 92719 46410 92720 46424 92720 46451 92720 46441 92721 46440 92721 46383 92721 46383 92722 46440 92722 46439 92722 46383 92723 46439 92723 46399 92723 46399 92724 46439 92724 46384 92724 46399 92725 46384 92725 46400 92725 46385 92726 46451 92726 46452 92726 46386 92727 46437 92727 46425 92727 46425 92728 46437 92728 46388 92728 46425 92729 46388 92729 46387 92729 46387 92730 46388 92730 46389 92730 46387 92731 46389 92731 46390 92731 46390 92732 46391 92732 46387 92732 46387 92733 46391 92733 46392 92733 46387 92734 46392 92734 46425 92734 46389 92735 46397 92735 46390 92735 46390 92736 46397 92736 46398 92736 46390 92737 46398 92737 46382 92737 46382 92738 46398 92738 46393 92738 46382 92739 46393 92739 46394 92739 46394 92740 46393 92740 46395 92740 46394 92741 46395 92741 46429 92741 46429 92742 46395 92742 46396 92742 46429 92743 46396 92743 46430 92743 46397 92744 46441 92744 46398 92744 46398 92745 46441 92745 46383 92745 46398 92746 46383 92746 46393 92746 46393 92747 46383 92747 46399 92747 46393 92748 46399 92748 46395 92748 46395 92749 46399 92749 46400 92749 46395 92750 46400 92750 46396 92750 46320 92751 46401 92751 46416 92751 46416 92752 46401 92752 46402 92752 46416 92753 46402 92753 46403 92753 46421 92754 46286 92754 46422 92754 46422 92755 46286 92755 46285 92755 46403 92756 46313 92756 46416 92756 46416 92757 46313 92757 46314 92757 46416 92758 46314 92758 46404 92758 46404 92759 46314 92759 46282 92759 46404 92760 46282 92760 46405 92760 46405 92761 46282 92761 46406 92761 46405 92762 46406 92762 46419 92762 46419 92763 46406 92763 46407 92763 46419 92764 46407 92764 46421 92764 46421 92765 46407 92765 46408 92765 46421 92766 46408 92766 46286 92766 46285 92767 46288 92767 46422 92767 46422 92768 46288 92768 46290 92768 46422 92769 46290 92769 46423 92769 46423 92770 46290 92770 46445 92770 46423 92771 46445 92771 46409 92771 46451 92772 46385 92772 46410 92772 46410 92773 46385 92773 46426 92773 46410 92774 46426 92774 46411 92774 46411 92775 46426 92775 46427 92775 46411 92776 46427 92776 46412 92776 46412 92777 46427 92777 46413 92777 46412 92778 46413 92778 46420 92778 46420 92779 46413 92779 46414 92779 46420 92780 46414 92780 46418 92780 46418 92781 46414 92781 46428 92781 46418 92782 46428 92782 46417 92782 46417 92783 46428 92783 46431 92783 46417 92784 46431 92784 46415 92784 46415 92785 46431 92785 46432 92785 46415 92786 46432 92786 46320 92786 46320 92787 46416 92787 46415 92787 46415 92788 46416 92788 46404 92788 46415 92789 46404 92789 46417 92789 46417 92790 46404 92790 46405 92790 46417 92791 46405 92791 46418 92791 46418 92792 46405 92792 46419 92792 46418 92793 46419 92793 46420 92793 46420 92794 46419 92794 46421 92794 46420 92795 46421 92795 46412 92795 46412 92796 46421 92796 46422 92796 46412 92797 46422 92797 46411 92797 46411 92798 46422 92798 46423 92798 46411 92799 46423 92799 46410 92799 46410 92800 46423 92800 46409 92800 46410 92801 46409 92801 46424 92801 46452 92802 46386 92802 46385 92802 46385 92803 46386 92803 46425 92803 46385 92804 46425 92804 46426 92804 46426 92805 46425 92805 46392 92805 46426 92806 46392 92806 46427 92806 46427 92807 46392 92807 46391 92807 46427 92808 46391 92808 46413 92808 46413 92809 46391 92809 46382 92809 46413 92810 46382 92810 46414 92810 46414 92811 46382 92811 46394 92811 46414 92812 46394 92812 46428 92812 46428 92813 46394 92813 46429 92813 46428 92814 46429 92814 46431 92814 46431 92815 46429 92815 46430 92815 46431 92816 46430 92816 46432 92816 46438 92817 46452 92817 46433 92817 46444 92818 46327 92818 46443 92818 46434 92819 46327 92819 46435 92819 46435 92820 46327 92820 46444 92820 46435 92821 46444 92821 46339 92821 46339 92822 46444 92822 46340 92822 46436 92823 46335 92823 46444 92823 46444 92824 46335 92824 46334 92824 46334 92825 46346 92825 46444 92825 46444 92826 46346 92826 46333 92826 46444 92827 46333 92827 46340 92827 46441 92828 46397 92828 46438 92828 46438 92829 46397 92829 46389 92829 46386 92830 46452 92830 46437 92830 46437 92831 46452 92831 46438 92831 46437 92832 46438 92832 46388 92832 46388 92833 46438 92833 46389 92833 46384 92834 46439 92834 46438 92834 46438 92835 46439 92835 46440 92835 46438 92836 46440 92836 46441 92836 46384 92837 46438 92837 46442 92837 46442 92838 46438 92838 46433 92838 46442 92839 46433 92839 46328 92839 46328 92840 46433 92840 46450 92840 46328 92841 46450 92841 46443 92841 46443 92842 46450 92842 46449 92842 46443 92843 46449 92843 46444 92843 46444 92844 46449 92844 46448 92844 46444 92845 46448 92845 46436 92845 46445 92846 46446 92846 46329 92846 46424 92847 46409 92847 46457 92847 46461 92848 46447 92848 46460 92848 46368 92849 46370 92849 46456 92849 46370 92850 46448 92850 46456 92850 46456 92851 46448 92851 46449 92851 46456 92852 46449 92852 46454 92852 46454 92853 46449 92853 46450 92853 46454 92854 46450 92854 46453 92854 46453 92855 46450 92855 46433 92855 46453 92856 46433 92856 46451 92856 46451 92857 46433 92857 46452 92857 46451 92858 46424 92858 46453 92858 46453 92859 46424 92859 46457 92859 46453 92860 46457 92860 46454 92860 46454 92861 46457 92861 46455 92861 46454 92862 46455 92862 46456 92862 46456 92863 46455 92863 46460 92863 46456 92864 46460 92864 46368 92864 46368 92865 46460 92865 46447 92865 46409 92866 46445 92866 46457 92866 46457 92867 46445 92867 46329 92867 46457 92868 46329 92868 46455 92868 46455 92869 46329 92869 46458 92869 46455 92870 46458 92870 46460 92870 46460 92871 46458 92871 46459 92871 46460 92872 46459 92872 46461 92872 46461 92873 46459 92873 46366 92873 46641 92874 46462 92874 46476 92874 46641 92875 46476 92875 46464 92875 46476 92876 46463 92876 46464 92876 46464 92877 46463 92877 46258 92877 46464 92878 46258 92878 46275 92878 46275 92879 46258 92879 46276 92879 46276 92880 46258 92880 46259 92880 46276 92881 46259 92881 46465 92881 46467 92882 46465 92882 46259 92882 46267 92883 46659 92883 46660 92883 46259 92884 46466 92884 46467 92884 46467 92885 46466 92885 46468 92885 46467 92886 46468 92886 46660 92886 46660 92887 46468 92887 46469 92887 46660 92888 46469 92888 46267 92888 46267 92889 46470 92889 46659 92889 46659 92890 46470 92890 46264 92890 46659 92891 46264 92891 46475 92891 46260 92892 46657 92892 46471 92892 46471 92893 46657 92893 46472 92893 46471 92894 46472 92894 46473 92894 46473 92895 46472 92895 46475 92895 46473 92896 46475 92896 46474 92896 46474 92897 46475 92897 46264 92897 46476 92898 46462 92898 46477 92898 46477 92899 46462 92899 46478 92899 46477 92900 46478 92900 46628 92900 46628 92901 46478 92901 46653 92901 46628 92902 46653 92902 46630 92902 46630 92903 46653 92903 46652 92903 46630 92904 46652 92904 46479 92904 46479 92905 46652 92905 46480 92905 46479 92906 46480 92906 46481 92906 46481 92907 46480 92907 46651 92907 46281 92908 46654 92908 46482 92908 46482 92909 46654 92909 46656 92909 46482 92910 46656 92910 46273 92910 46273 92911 46656 92911 46483 92911 46273 92912 46483 92912 46260 92912 46260 92913 46483 92913 46657 92913 46485 92914 46553 92914 46484 92914 46497 92915 46485 92915 46498 92915 46616 92916 46486 92916 46487 92916 46487 92917 46486 92917 46495 92917 46487 92918 46495 92918 46488 92918 46488 92919 46495 92919 46489 92919 46488 92920 46489 92920 46537 92920 46537 92921 46489 92921 46538 92921 46496 92922 46490 92922 46540 92922 46531 92923 46533 92923 46494 92923 46494 92924 46533 92924 46491 92924 46494 92925 46491 92925 46496 92925 46496 92926 46491 92926 46492 92926 46496 92927 46492 92927 46490 92927 46524 92928 46486 92928 46522 92928 46522 92929 46486 92929 46616 92929 46522 92930 46616 92930 46493 92930 46524 92931 46531 92931 46486 92931 46486 92932 46531 92932 46494 92932 46486 92933 46494 92933 46495 92933 46495 92934 46494 92934 46496 92934 46495 92935 46496 92935 46489 92935 46489 92936 46496 92936 46540 92936 46489 92937 46540 92937 46538 92937 46525 92938 46528 92938 46524 92938 46524 92939 46528 92939 46530 92939 46524 92940 46530 92940 46531 92940 46617 92941 46497 92941 46499 92941 46499 92942 46497 92942 46498 92942 46499 92943 46498 92943 46523 92943 46523 92944 46498 92944 46521 92944 46527 92945 46505 92945 46512 92945 46262 92946 46500 92946 46261 92946 46261 92947 46500 92947 46501 92947 46261 92948 46501 92948 46272 92948 46517 92949 46504 92949 46519 92949 46519 92950 46504 92950 46502 92950 46519 92951 46502 92951 46551 92951 46269 92952 46268 92952 46515 92952 46515 92953 46268 92953 46503 92953 46515 92954 46503 92954 46517 92954 46517 92955 46503 92955 46266 92955 46517 92956 46266 92956 46504 92956 46262 92957 46263 92957 46505 92957 46505 92958 46263 92958 46265 92958 46505 92959 46265 92959 46512 92959 46512 92960 46265 92960 46507 92960 46512 92961 46507 92961 46506 92961 46506 92962 46507 92962 46508 92962 46506 92963 46508 92963 46515 92963 46515 92964 46508 92964 46270 92964 46515 92965 46270 92965 46269 92965 46527 92966 46513 92966 46509 92966 46509 92967 46513 92967 46514 92967 46509 92968 46514 92968 46529 92968 46529 92969 46514 92969 46516 92969 46529 92970 46516 92970 46510 92970 46510 92971 46516 92971 46518 92971 46510 92972 46518 92972 46532 92972 46532 92973 46518 92973 46520 92973 46532 92974 46520 92974 46511 92974 46511 92975 46520 92975 46548 92975 46511 92976 46548 92976 46534 92976 46527 92977 46512 92977 46513 92977 46513 92978 46512 92978 46506 92978 46513 92979 46506 92979 46514 92979 46514 92980 46506 92980 46515 92980 46514 92981 46515 92981 46516 92981 46516 92982 46515 92982 46517 92982 46516 92983 46517 92983 46518 92983 46518 92984 46517 92984 46519 92984 46518 92985 46519 92985 46520 92985 46520 92986 46519 92986 46551 92986 46520 92987 46551 92987 46548 92987 46485 92988 46484 92988 46498 92988 46498 92989 46484 92989 46554 92989 46498 92990 46554 92990 46521 92990 46521 92991 46554 92991 46563 92991 46521 92992 46563 92992 46526 92992 46493 92993 46617 92993 46522 92993 46522 92994 46617 92994 46499 92994 46522 92995 46499 92995 46524 92995 46524 92996 46499 92996 46523 92996 46524 92997 46523 92997 46525 92997 46525 92998 46523 92998 46521 92998 46525 92999 46521 92999 46500 92999 46500 93000 46521 93000 46526 93000 46500 93001 46526 93001 46501 93001 46262 93002 46505 93002 46500 93002 46500 93003 46505 93003 46527 93003 46500 93004 46527 93004 46525 93004 46525 93005 46527 93005 46509 93005 46525 93006 46509 93006 46528 93006 46528 93007 46509 93007 46529 93007 46528 93008 46529 93008 46530 93008 46530 93009 46529 93009 46510 93009 46530 93010 46510 93010 46531 93010 46531 93011 46510 93011 46532 93011 46531 93012 46532 93012 46533 93012 46533 93013 46532 93013 46511 93013 46533 93014 46511 93014 46491 93014 46491 93015 46511 93015 46534 93015 46491 93016 46534 93016 46492 93016 46586 93017 46599 93017 46545 93017 46624 93018 46535 93018 46541 93018 46568 93019 46623 93019 46536 93019 46536 93020 46623 93020 46544 93020 46537 93021 46538 93021 46625 93021 46625 93022 46538 93022 46535 93022 46549 93023 46539 93023 46547 93023 46547 93024 46539 93024 46544 93024 46535 93025 46538 93025 46541 93025 46541 93026 46538 93026 46540 93026 46541 93027 46540 93027 46490 93027 46623 93028 46624 93028 46544 93028 46544 93029 46624 93029 46541 93029 46544 93030 46541 93030 46547 93030 46547 93031 46541 93031 46490 93031 46599 93032 46542 93032 46539 93032 46539 93033 46542 93033 46543 93033 46539 93034 46543 93034 46544 93034 46544 93035 46543 93035 46578 93035 46544 93036 46578 93036 46536 93036 46550 93037 46546 93037 46545 93037 46545 93038 46546 93038 46585 93038 46545 93039 46585 93039 46586 93039 46490 93040 46492 93040 46547 93040 46547 93041 46492 93041 46534 93041 46547 93042 46534 93042 46549 93042 46549 93043 46534 93043 46548 93043 46549 93044 46548 93044 46551 93044 46599 93045 46539 93045 46545 93045 46545 93046 46539 93046 46549 93046 46545 93047 46549 93047 46550 93047 46550 93048 46549 93048 46551 93048 46550 93049 46551 93049 46502 93049 46555 93050 46561 93050 46564 93050 46560 93051 46607 93051 46552 93051 46484 93052 46553 93052 46626 93052 46563 93053 46554 93053 46555 93053 46555 93054 46554 93054 46484 93054 46484 93055 46626 93055 46555 93055 46555 93056 46626 93056 46556 93056 46555 93057 46556 93057 46561 93057 46561 93058 46556 93058 46557 93058 46561 93059 46557 93059 46560 93059 46501 93060 46526 93060 46558 93060 46558 93061 46526 93061 46563 93061 46272 93062 46501 93062 46271 93062 46271 93063 46501 93063 46558 93063 46271 93064 46558 93064 46559 93064 46560 93065 46552 93065 46561 93065 46561 93066 46552 93066 46562 93066 46561 93067 46562 93067 46564 93067 46564 93068 46562 93068 46592 93068 46564 93069 46592 93069 46565 93069 46563 93070 46555 93070 46558 93070 46558 93071 46555 93071 46564 93071 46558 93072 46564 93072 46559 93072 46559 93073 46564 93073 46565 93073 46559 93074 46565 93074 46566 93074 46278 93075 46566 93075 46565 93075 46567 93076 46573 93076 46574 93076 46606 93077 46562 93077 46552 93077 46568 93078 46536 93078 46618 93078 46618 93079 46536 93079 46569 93079 46618 93080 46569 93080 46620 93080 46620 93081 46569 93081 46570 93081 46620 93082 46570 93082 46579 93082 46593 93083 46552 93083 46607 93083 46608 93084 46572 93084 46609 93084 46609 93085 46572 93085 46571 93085 46571 93086 46572 93086 46622 93086 46571 93087 46622 93087 46574 93087 46574 93088 46573 93088 46571 93088 46571 93089 46573 93089 46610 93089 46571 93090 46610 93090 46609 93090 46622 93091 46621 93091 46574 93091 46574 93092 46621 93092 46575 93092 46574 93093 46575 93093 46567 93093 46567 93094 46575 93094 46576 93094 46567 93095 46576 93095 46612 93095 46612 93096 46576 93096 46580 93096 46612 93097 46580 93097 46577 93097 46577 93098 46580 93098 46578 93098 46577 93099 46578 93099 46543 93099 46621 93100 46579 93100 46575 93100 46575 93101 46579 93101 46570 93101 46575 93102 46570 93102 46576 93102 46576 93103 46570 93103 46569 93103 46576 93104 46569 93104 46580 93104 46580 93105 46569 93105 46536 93105 46580 93106 46536 93106 46578 93106 46581 93107 46583 93107 46582 93107 46582 93108 46583 93108 46627 93108 46627 93109 46583 93109 46587 93109 46627 93110 46587 93110 46584 93110 46585 93111 46584 93111 46586 93111 46586 93112 46584 93112 46587 93112 46586 93113 46587 93113 46599 93113 46603 93114 46588 93114 46605 93114 46605 93115 46588 93115 46632 93115 46582 93116 46629 93116 46581 93116 46581 93117 46629 93117 46631 93117 46581 93118 46631 93118 46589 93118 46589 93119 46631 93119 46634 93119 46589 93120 46634 93120 46603 93120 46603 93121 46634 93121 46633 93121 46603 93122 46633 93122 46588 93122 46632 93123 46590 93123 46605 93123 46605 93124 46590 93124 46278 93124 46605 93125 46278 93125 46591 93125 46591 93126 46278 93126 46565 93126 46591 93127 46565 93127 46592 93127 46552 93128 46593 93128 46606 93128 46606 93129 46593 93129 46594 93129 46606 93130 46594 93130 46604 93130 46604 93131 46594 93131 46595 93131 46604 93132 46595 93132 46602 93132 46602 93133 46595 93133 46611 93133 46602 93134 46611 93134 46596 93134 46596 93135 46611 93135 46613 93135 46596 93136 46613 93136 46601 93136 46601 93137 46613 93137 46614 93137 46601 93138 46614 93138 46600 93138 46600 93139 46614 93139 46598 93139 46600 93140 46598 93140 46597 93140 46597 93141 46598 93141 46542 93141 46597 93142 46542 93142 46599 93142 46599 93143 46587 93143 46597 93143 46597 93144 46587 93144 46583 93144 46597 93145 46583 93145 46600 93145 46600 93146 46583 93146 46581 93146 46600 93147 46581 93147 46601 93147 46601 93148 46581 93148 46589 93148 46601 93149 46589 93149 46596 93149 46596 93150 46589 93150 46603 93150 46596 93151 46603 93151 46602 93151 46602 93152 46603 93152 46605 93152 46602 93153 46605 93153 46604 93153 46604 93154 46605 93154 46591 93154 46604 93155 46591 93155 46606 93155 46606 93156 46591 93156 46592 93156 46606 93157 46592 93157 46562 93157 46607 93158 46608 93158 46593 93158 46593 93159 46608 93159 46609 93159 46593 93160 46609 93160 46594 93160 46594 93161 46609 93161 46610 93161 46594 93162 46610 93162 46595 93162 46595 93163 46610 93163 46573 93163 46595 93164 46573 93164 46611 93164 46611 93165 46573 93165 46567 93165 46611 93166 46567 93166 46613 93166 46613 93167 46567 93167 46612 93167 46613 93168 46612 93168 46614 93168 46614 93169 46612 93169 46577 93169 46614 93170 46577 93170 46598 93170 46598 93171 46577 93171 46543 93171 46598 93172 46543 93172 46542 93172 46615 93173 46537 93173 46625 93173 46615 93174 46493 93174 46616 93174 46616 93175 46487 93175 46615 93175 46615 93176 46487 93176 46488 93176 46615 93177 46488 93177 46537 93177 46485 93178 46497 93178 46615 93178 46615 93179 46497 93179 46617 93179 46615 93180 46617 93180 46493 93180 46619 93181 46607 93181 46560 93181 46608 93182 46607 93182 46572 93182 46572 93183 46607 93183 46619 93183 46572 93184 46619 93184 46622 93184 46568 93185 46618 93185 46619 93185 46619 93186 46618 93186 46620 93186 46620 93187 46579 93187 46619 93187 46619 93188 46579 93188 46621 93188 46619 93189 46621 93189 46622 93189 46568 93190 46619 93190 46623 93190 46623 93191 46619 93191 46560 93191 46623 93192 46560 93192 46624 93192 46624 93193 46560 93193 46557 93193 46624 93194 46557 93194 46535 93194 46535 93195 46557 93195 46556 93195 46535 93196 46556 93196 46625 93196 46625 93197 46556 93197 46626 93197 46625 93198 46626 93198 46615 93198 46615 93199 46626 93199 46553 93199 46615 93200 46553 93200 46485 93200 46585 93201 46476 93201 46584 93201 46584 93202 46476 93202 46477 93202 46584 93203 46477 93203 46627 93203 46627 93204 46477 93204 46628 93204 46627 93205 46628 93205 46582 93205 46582 93206 46628 93206 46629 93206 46629 93207 46628 93207 46630 93207 46629 93208 46630 93208 46631 93208 46479 93209 46481 93209 46632 93209 46632 93210 46588 93210 46479 93210 46479 93211 46588 93211 46633 93211 46479 93212 46633 93212 46630 93212 46630 93213 46633 93213 46634 93213 46630 93214 46634 93214 46631 93214 46639 93215 46635 93215 46283 93215 46283 93216 46635 93216 46636 93216 46312 93217 46637 93217 46638 93217 46638 93218 46637 93218 46277 93218 46638 93219 46277 93219 46639 93219 46639 93220 46277 93220 46276 93220 46639 93221 46276 93221 46635 93221 46310 93222 46643 93222 46642 93222 46274 93223 46300 93223 46640 93223 46640 93224 46300 93224 46306 93224 46640 93225 46306 93225 46641 93225 46641 93226 46306 93226 46307 93226 46641 93227 46307 93227 46642 93227 46642 93228 46307 93228 46309 93228 46642 93229 46309 93229 46310 93229 46310 93230 46644 93230 46643 93230 46643 93231 46644 93231 46649 93231 46643 93232 46649 93232 46650 93232 46301 93233 46655 93233 46645 93233 46645 93234 46655 93234 46646 93234 46645 93235 46646 93235 46647 93235 46647 93236 46646 93236 46650 93236 46647 93237 46650 93237 46648 93237 46648 93238 46650 93238 46649 93238 46462 93239 46641 93239 46642 93239 46480 93240 46643 93240 46650 93240 46654 93241 46280 93241 46650 93241 46650 93242 46280 93242 46651 93242 46650 93243 46651 93243 46480 93243 46480 93244 46652 93244 46643 93244 46643 93245 46652 93245 46653 93245 46643 93246 46653 93246 46642 93246 46642 93247 46653 93247 46478 93247 46642 93248 46478 93248 46462 93248 46276 93249 46465 93249 46635 93249 46635 93250 46465 93250 46467 93250 46635 93251 46467 93251 46636 93251 46636 93252 46467 93252 46660 93252 46636 93253 46660 93253 46295 93253 46650 93254 46646 93254 46654 93254 46654 93255 46646 93255 46655 93255 46654 93256 46655 93256 46656 93256 46656 93257 46655 93257 46299 93257 46656 93258 46299 93258 46483 93258 46483 93259 46299 93259 46292 93259 46483 93260 46292 93260 46657 93260 46657 93261 46292 93261 46294 93261 46657 93262 46294 93262 46472 93262 46472 93263 46294 93263 46658 93263 46472 93264 46658 93264 46475 93264 46475 93265 46658 93265 46295 93265 46475 93266 46295 93266 46659 93266 46659 93267 46295 93267 46660 93267 46637 93268 46312 93268 46297 93268 46637 93269 46297 93269 46661 93269 46661 93270 46297 93270 46300 93270 46661 93271 46300 93271 46274 93271 46663 93272 47064 93272 46702 93272 46666 93273 46879 93273 46662 93273 46702 93274 46696 93274 46663 93274 46663 93275 46696 93275 46664 93275 46663 93276 46664 93276 46662 93276 46662 93277 46664 93277 46665 93277 46662 93278 46665 93278 46666 93278 46666 93279 46691 93279 46879 93279 46879 93280 46691 93280 46670 93280 46879 93281 46670 93281 46669 93281 46667 93282 46881 93282 46686 93282 46686 93283 46881 93283 46668 93283 46686 93284 46668 93284 46689 93284 46689 93285 46668 93285 46669 93285 46689 93286 46669 93286 46688 93286 46688 93287 46669 93287 46670 93287 46705 93288 46672 93288 46671 93288 46671 93289 46672 93289 46673 93289 46671 93290 46673 93290 46674 93290 46674 93291 46673 93291 46676 93291 46674 93292 46676 93292 46675 93292 46675 93293 46676 93293 46876 93293 46677 93294 47062 93294 46678 93294 46678 93295 47062 93295 47063 93295 46678 93296 47063 93296 46679 93296 46679 93297 47063 93297 46680 93297 46679 93298 46680 93298 46682 93298 46682 93299 46680 93299 46681 93299 46682 93300 46681 93300 46869 93300 46696 93301 46702 93301 46683 93301 46701 93302 46667 93302 46684 93302 46684 93303 46667 93303 46686 93303 46684 93304 46686 93304 46685 93304 46685 93305 46686 93305 46687 93305 46670 93306 46729 93306 46688 93306 46688 93307 46729 93307 46687 93307 46688 93308 46687 93308 46689 93308 46689 93309 46687 93309 46686 93309 46666 93310 46694 93310 46691 93310 46691 93311 46694 93311 46690 93311 46691 93312 46690 93312 46670 93312 46670 93313 46690 93313 46731 93313 46670 93314 46731 93314 46729 93314 46728 93315 46727 93315 46665 93315 46665 93316 46727 93316 46692 93316 46665 93317 46692 93317 46666 93317 46666 93318 46692 93318 46693 93318 46666 93319 46693 93319 46694 93319 46683 93320 46695 93320 46696 93320 46696 93321 46695 93321 46728 93321 46696 93322 46728 93322 46664 93322 46664 93323 46728 93323 46665 93323 46779 93324 46705 93324 46697 93324 46697 93325 46705 93325 46671 93325 46697 93326 46671 93326 46698 93326 46698 93327 46671 93327 46674 93327 46698 93328 46674 93328 46778 93328 46778 93329 46674 93329 46675 93329 46778 93330 46675 93330 46776 93330 46854 93331 46853 93331 46699 93331 46699 93332 46853 93332 47065 93332 46699 93333 47065 93333 46700 93333 46700 93334 47065 93334 47066 93334 46700 93335 47066 93335 46701 93335 46701 93336 47066 93336 46667 93336 46683 93337 46702 93337 46703 93337 46683 93338 46703 93338 46831 93338 46831 93339 46703 93339 46704 93339 46831 93340 46704 93340 46826 93340 46826 93341 46704 93341 46705 93341 46826 93342 46705 93342 46779 93342 46845 93343 46706 93343 46806 93343 46834 93344 46845 93344 46721 93344 46707 93345 46714 93345 46833 93345 46833 93346 46714 93346 46716 93346 46833 93347 46716 93347 46708 93347 46708 93348 46716 93348 46709 93348 46708 93349 46709 93349 46710 93349 46710 93350 46709 93350 46718 93350 46711 93351 46821 93351 46717 93351 46754 93352 46712 93352 46715 93352 46715 93353 46712 93353 46713 93353 46715 93354 46713 93354 46711 93354 46711 93355 46713 93355 46756 93355 46711 93356 46756 93356 46821 93356 46719 93357 46714 93357 46745 93357 46745 93358 46714 93358 46707 93358 46745 93359 46707 93359 46832 93359 46719 93360 46754 93360 46714 93360 46714 93361 46754 93361 46715 93361 46714 93362 46715 93362 46716 93362 46716 93363 46715 93363 46711 93363 46716 93364 46711 93364 46709 93364 46709 93365 46711 93365 46717 93365 46709 93366 46717 93366 46718 93366 46748 93367 46753 93367 46719 93367 46719 93368 46753 93368 46720 93368 46719 93369 46720 93369 46754 93369 46744 93370 46834 93370 46746 93370 46746 93371 46834 93371 46721 93371 46746 93372 46721 93372 46747 93372 46747 93373 46721 93373 46743 93373 46722 93374 46751 93374 46730 93374 46685 93375 46749 93375 46684 93375 46684 93376 46749 93376 46723 93376 46684 93377 46723 93377 46701 93377 46724 93378 46695 93378 46725 93378 46725 93379 46695 93379 46683 93379 46725 93380 46683 93380 46726 93380 46693 93381 46692 93381 46741 93381 46741 93382 46692 93382 46727 93382 46741 93383 46727 93383 46724 93383 46724 93384 46727 93384 46728 93384 46724 93385 46728 93385 46695 93385 46685 93386 46687 93386 46751 93386 46751 93387 46687 93387 46729 93387 46751 93388 46729 93388 46730 93388 46730 93389 46729 93389 46731 93389 46730 93390 46731 93390 46732 93390 46732 93391 46731 93391 46690 93391 46732 93392 46690 93392 46741 93392 46741 93393 46690 93393 46694 93393 46741 93394 46694 93394 46693 93394 46722 93395 46740 93395 46752 93395 46752 93396 46740 93396 46734 93396 46752 93397 46734 93397 46733 93397 46733 93398 46734 93398 46736 93398 46733 93399 46736 93399 46735 93399 46735 93400 46736 93400 46737 93400 46735 93401 46737 93401 46739 93401 46739 93402 46737 93402 46738 93402 46739 93403 46738 93403 46755 93403 46755 93404 46738 93404 46742 93404 46755 93405 46742 93405 46828 93405 46722 93406 46730 93406 46740 93406 46740 93407 46730 93407 46732 93407 46740 93408 46732 93408 46734 93408 46734 93409 46732 93409 46741 93409 46734 93410 46741 93410 46736 93410 46736 93411 46741 93411 46724 93411 46736 93412 46724 93412 46737 93412 46737 93413 46724 93413 46725 93413 46737 93414 46725 93414 46738 93414 46738 93415 46725 93415 46726 93415 46738 93416 46726 93416 46742 93416 46845 93417 46806 93417 46721 93417 46721 93418 46806 93418 46807 93418 46721 93419 46807 93419 46743 93419 46743 93420 46807 93420 46810 93420 46743 93421 46810 93421 46750 93421 46832 93422 46744 93422 46745 93422 46745 93423 46744 93423 46746 93423 46745 93424 46746 93424 46719 93424 46719 93425 46746 93425 46747 93425 46719 93426 46747 93426 46748 93426 46748 93427 46747 93427 46743 93427 46748 93428 46743 93428 46749 93428 46749 93429 46743 93429 46750 93429 46749 93430 46750 93430 46723 93430 46685 93431 46751 93431 46749 93431 46749 93432 46751 93432 46722 93432 46749 93433 46722 93433 46748 93433 46748 93434 46722 93434 46752 93434 46748 93435 46752 93435 46753 93435 46753 93436 46752 93436 46733 93436 46753 93437 46733 93437 46720 93437 46720 93438 46733 93438 46735 93438 46720 93439 46735 93439 46754 93439 46754 93440 46735 93440 46739 93440 46754 93441 46739 93441 46712 93441 46712 93442 46739 93442 46755 93442 46712 93443 46755 93443 46713 93443 46713 93444 46755 93444 46828 93444 46713 93445 46828 93445 46756 93445 46757 93446 46854 93446 46814 93446 46758 93447 46800 93447 46766 93447 46784 93448 46812 93448 46759 93448 46837 93449 46825 93449 46838 93449 46838 93450 46825 93450 46773 93450 46838 93451 46773 93451 46760 93451 46760 93452 46773 93452 46761 93452 46760 93453 46761 93453 46762 93453 46783 93454 46759 93454 46836 93454 46763 93455 46764 93455 46797 93455 46797 93456 46764 93456 46765 93456 46765 93457 46764 93457 46768 93457 46765 93458 46768 93458 46766 93458 46766 93459 46800 93459 46765 93459 46765 93460 46800 93460 46767 93460 46765 93461 46767 93461 46797 93461 46768 93462 46840 93462 46766 93462 46766 93463 46840 93463 46769 93463 46766 93464 46769 93464 46758 93464 46758 93465 46769 93465 46772 93465 46758 93466 46772 93466 46770 93466 46770 93467 46772 93467 46774 93467 46770 93468 46774 93468 46803 93468 46803 93469 46774 93469 46824 93469 46803 93470 46824 93470 46771 93470 46840 93471 46762 93471 46769 93471 46769 93472 46762 93472 46761 93472 46769 93473 46761 93473 46772 93473 46772 93474 46761 93474 46773 93474 46772 93475 46773 93475 46774 93475 46774 93476 46773 93476 46825 93476 46774 93477 46825 93477 46824 93477 46776 93478 46846 93478 46775 93478 46775 93479 46792 93479 46776 93479 46776 93480 46792 93480 46791 93480 46776 93481 46791 93481 46778 93481 46778 93482 46791 93482 46777 93482 46778 93483 46777 93483 46698 93483 46698 93484 46777 93484 46697 93484 46822 93485 46815 93485 46777 93485 46777 93486 46815 93486 46779 93486 46777 93487 46779 93487 46697 93487 46847 93488 46850 93488 46796 93488 46796 93489 46795 93489 46847 93489 46847 93490 46795 93490 46775 93490 46847 93491 46775 93491 46780 93491 46780 93492 46775 93492 46846 93492 46850 93493 46851 93493 46796 93493 46796 93494 46851 93494 46757 93494 46796 93495 46757 93495 46781 93495 46781 93496 46757 93496 46814 93496 46781 93497 46814 93497 46782 93497 46759 93498 46783 93498 46784 93498 46784 93499 46783 93499 46798 93499 46784 93500 46798 93500 46785 93500 46785 93501 46798 93501 46799 93501 46785 93502 46799 93502 46794 93502 46794 93503 46799 93503 46786 93503 46794 93504 46786 93504 46793 93504 46793 93505 46786 93505 46801 93505 46793 93506 46801 93506 46787 93506 46787 93507 46801 93507 46802 93507 46787 93508 46802 93508 46790 93508 46790 93509 46802 93509 46788 93509 46790 93510 46788 93510 46789 93510 46789 93511 46788 93511 46823 93511 46789 93512 46823 93512 46822 93512 46822 93513 46777 93513 46789 93513 46789 93514 46777 93514 46791 93514 46789 93515 46791 93515 46790 93515 46790 93516 46791 93516 46792 93516 46790 93517 46792 93517 46787 93517 46787 93518 46792 93518 46775 93518 46787 93519 46775 93519 46793 93519 46793 93520 46775 93520 46795 93520 46793 93521 46795 93521 46794 93521 46794 93522 46795 93522 46796 93522 46794 93523 46796 93523 46785 93523 46785 93524 46796 93524 46781 93524 46785 93525 46781 93525 46784 93525 46784 93526 46781 93526 46782 93526 46784 93527 46782 93527 46812 93527 46836 93528 46763 93528 46783 93528 46783 93529 46763 93529 46797 93529 46783 93530 46797 93530 46798 93530 46798 93531 46797 93531 46767 93531 46798 93532 46767 93532 46799 93532 46799 93533 46767 93533 46800 93533 46799 93534 46800 93534 46786 93534 46786 93535 46800 93535 46758 93535 46786 93536 46758 93536 46801 93536 46801 93537 46758 93537 46770 93537 46801 93538 46770 93538 46802 93538 46802 93539 46770 93539 46803 93539 46802 93540 46803 93540 46788 93540 46788 93541 46803 93541 46771 93541 46788 93542 46771 93542 46823 93542 46808 93543 46811 93543 46804 93543 46805 93544 46836 93544 46759 93544 46806 93545 46706 93545 46844 93545 46810 93546 46807 93546 46808 93546 46808 93547 46807 93547 46806 93547 46806 93548 46844 93548 46808 93548 46808 93549 46844 93549 46809 93549 46808 93550 46809 93550 46811 93550 46811 93551 46809 93551 46841 93551 46811 93552 46841 93552 46805 93552 46723 93553 46750 93553 46813 93553 46813 93554 46750 93554 46810 93554 46701 93555 46723 93555 46700 93555 46700 93556 46723 93556 46813 93556 46700 93557 46813 93557 46699 93557 46805 93558 46759 93558 46811 93558 46811 93559 46759 93559 46812 93559 46811 93560 46812 93560 46804 93560 46804 93561 46812 93561 46782 93561 46804 93562 46782 93562 46814 93562 46810 93563 46808 93563 46813 93563 46813 93564 46808 93564 46804 93564 46813 93565 46804 93565 46699 93565 46699 93566 46804 93566 46814 93566 46699 93567 46814 93567 46854 93567 46815 93568 46822 93568 46816 93568 46820 93569 46842 93569 46819 93569 46837 93570 46817 93570 46825 93570 46825 93571 46817 93571 46818 93571 46710 93572 46718 93572 46843 93572 46843 93573 46718 93573 46842 93573 46829 93574 46830 93574 46827 93574 46827 93575 46830 93575 46818 93575 46842 93576 46718 93576 46819 93576 46819 93577 46718 93577 46717 93577 46819 93578 46717 93578 46821 93578 46817 93579 46820 93579 46818 93579 46818 93580 46820 93580 46819 93580 46818 93581 46819 93581 46827 93581 46827 93582 46819 93582 46821 93582 46822 93583 46823 93583 46830 93583 46830 93584 46823 93584 46771 93584 46830 93585 46771 93585 46818 93585 46818 93586 46771 93586 46824 93586 46818 93587 46824 93587 46825 93587 46831 93588 46826 93588 46816 93588 46816 93589 46826 93589 46779 93589 46816 93590 46779 93590 46815 93590 46821 93591 46756 93591 46827 93591 46827 93592 46756 93592 46828 93592 46827 93593 46828 93593 46829 93593 46829 93594 46828 93594 46742 93594 46829 93595 46742 93595 46726 93595 46822 93596 46830 93596 46816 93596 46816 93597 46830 93597 46829 93597 46816 93598 46829 93598 46831 93598 46831 93599 46829 93599 46726 93599 46831 93600 46726 93600 46683 93600 46835 93601 46710 93601 46843 93601 46835 93602 46832 93602 46707 93602 46707 93603 46833 93603 46835 93603 46835 93604 46833 93604 46708 93604 46835 93605 46708 93605 46710 93605 46845 93606 46834 93606 46835 93606 46835 93607 46834 93607 46744 93607 46835 93608 46744 93608 46832 93608 46839 93609 46836 93609 46805 93609 46763 93610 46836 93610 46764 93610 46764 93611 46836 93611 46839 93611 46764 93612 46839 93612 46768 93612 46837 93613 46838 93613 46839 93613 46839 93614 46838 93614 46760 93614 46760 93615 46762 93615 46839 93615 46839 93616 46762 93616 46840 93616 46839 93617 46840 93617 46768 93617 46837 93618 46839 93618 46817 93618 46817 93619 46839 93619 46805 93619 46817 93620 46805 93620 46820 93620 46820 93621 46805 93621 46841 93621 46820 93622 46841 93622 46842 93622 46842 93623 46841 93623 46809 93623 46842 93624 46809 93624 46843 93624 46843 93625 46809 93625 46844 93625 46843 93626 46844 93626 46835 93626 46835 93627 46844 93627 46706 93627 46835 93628 46706 93628 46845 93628 46776 93629 46675 93629 46846 93629 46846 93630 46675 93630 46848 93630 46846 93631 46848 93631 46780 93631 46780 93632 46848 93632 46847 93632 46847 93633 46848 93633 46849 93633 46847 93634 46849 93634 46850 93634 46850 93635 46849 93635 46858 93635 46850 93636 46858 93636 46851 93636 46858 93637 46852 93637 46851 93637 46851 93638 46852 93638 46856 93638 46851 93639 46856 93639 46757 93639 46757 93640 46856 93640 46853 93640 46757 93641 46853 93641 46854 93641 46885 93642 46853 93642 46855 93642 46855 93643 46853 93643 46856 93643 46855 93644 46856 93644 46859 93644 46859 93645 46856 93645 46852 93645 46675 93646 46876 93646 46848 93646 46848 93647 46876 93647 46857 93647 46848 93648 46857 93648 46849 93648 46849 93649 46857 93649 46859 93649 46849 93650 46859 93650 46858 93650 46858 93651 46859 93651 46852 93651 46860 93652 46913 93652 46861 93652 46860 93653 46861 93653 46864 93653 46861 93654 46862 93654 46864 93654 46864 93655 46862 93655 46863 93655 46864 93656 46863 93656 46985 93656 46861 93657 46865 93657 46862 93657 46862 93658 46865 93658 46880 93658 46862 93659 46880 93659 46863 93659 46863 93660 46880 93660 46890 93660 46866 93661 46878 93661 46911 93661 46911 93662 46878 93662 46867 93662 46911 93663 46867 93663 46912 93663 46912 93664 46867 93664 46868 93664 46912 93665 46868 93665 46861 93665 46861 93666 46868 93666 46865 93666 46906 93667 46682 93667 46908 93667 46908 93668 46682 93668 46869 93668 46908 93669 46869 93669 46866 93669 46866 93670 46869 93670 46681 93670 46866 93671 46681 93671 46878 93671 46873 93672 46870 93672 46877 93672 46678 93673 46887 93673 46677 93673 46677 93674 46887 93674 46871 93674 46677 93675 46871 93675 47062 93675 47062 93676 46871 93676 46899 93676 47062 93677 46899 93677 46877 93677 46877 93678 46899 93678 46872 93678 46877 93679 46872 93679 46873 93679 46873 93680 46897 93680 46870 93680 46870 93681 46897 93681 46874 93681 46870 93682 46874 93682 46886 93682 46892 93683 46891 93683 46875 93683 46875 93684 46891 93684 46884 93684 46875 93685 46884 93685 46894 93685 46894 93686 46884 93686 46886 93686 46894 93687 46886 93687 46895 93687 46895 93688 46886 93688 46874 93688 46672 93689 47062 93689 46877 93689 46857 93690 46870 93690 46886 93690 46885 93691 46855 93691 46886 93691 46886 93692 46855 93692 46859 93692 46886 93693 46859 93693 46857 93693 46857 93694 46876 93694 46870 93694 46870 93695 46876 93695 46676 93695 46870 93696 46676 93696 46877 93696 46877 93697 46676 93697 46673 93697 46877 93698 46673 93698 46672 93698 46681 93699 47064 93699 46878 93699 46878 93700 47064 93700 46663 93700 46878 93701 46663 93701 46867 93701 46663 93702 46662 93702 46867 93702 46867 93703 46662 93703 46879 93703 46867 93704 46879 93704 46868 93704 46868 93705 46879 93705 46669 93705 46868 93706 46669 93706 46865 93706 46865 93707 46669 93707 46668 93707 46865 93708 46668 93708 46880 93708 46880 93709 46668 93709 46881 93709 46880 93710 46881 93710 46890 93710 46890 93711 46881 93711 46882 93711 46890 93712 46882 93712 46883 93712 46883 93713 46882 93713 47067 93713 46883 93714 47067 93714 46891 93714 46891 93715 47067 93715 46885 93715 46891 93716 46885 93716 46884 93716 46884 93717 46885 93717 46886 93717 46682 93718 46906 93718 46888 93718 46682 93719 46888 93719 46679 93719 46679 93720 46888 93720 46887 93720 46679 93721 46887 93721 46678 93721 46898 93722 46887 93722 46915 93722 46915 93723 46887 93723 46888 93723 46915 93724 46888 93724 46889 93724 46906 93725 46905 93725 46888 93725 46888 93726 46905 93726 46920 93726 46888 93727 46920 93727 46889 93727 46863 93728 46890 93728 46929 93728 46929 93729 46890 93729 46883 93729 46929 93730 46883 93730 46892 93730 46892 93731 46883 93731 46891 93731 46871 93732 46887 93732 46898 93732 46969 93733 46892 93733 46893 93733 46893 93734 46892 93734 46875 93734 46893 93735 46875 93735 46976 93735 46976 93736 46875 93736 46977 93736 46875 93737 46894 93737 46977 93737 46977 93738 46894 93738 46895 93738 46977 93739 46895 93739 46896 93739 46873 93740 46903 93740 46897 93740 46897 93741 46903 93741 46896 93741 46897 93742 46896 93742 46874 93742 46874 93743 46896 93743 46895 93743 46898 93744 46968 93744 46871 93744 46871 93745 46968 93745 46900 93745 46871 93746 46900 93746 46899 93746 46899 93747 46900 93747 46901 93747 46899 93748 46901 93748 46872 93748 46872 93749 46901 93749 46902 93749 46872 93750 46902 93750 46873 93750 46873 93751 46902 93751 46954 93751 46873 93752 46954 93752 46903 93752 46904 93753 47007 93753 46866 93753 46905 93754 46906 93754 47008 93754 47008 93755 46906 93755 46908 93755 47007 93756 46907 93756 46866 93756 46866 93757 46907 93757 47006 93757 46866 93758 47006 93758 46908 93758 46908 93759 47006 93759 46909 93759 46908 93760 46909 93760 47008 93760 46904 93761 46866 93761 46910 93761 46910 93762 46866 93762 46911 93762 46910 93763 46911 93763 47002 93763 47002 93764 46911 93764 47011 93764 47011 93765 46911 93765 46912 93765 47011 93766 46912 93766 46914 93766 46861 93767 46913 93767 46912 93767 46912 93768 46913 93768 47010 93768 46912 93769 47010 93769 46914 93769 46924 93770 46989 93770 46928 93770 46989 93771 46924 93771 47000 93771 46918 93772 46919 93772 46923 93772 46917 93773 46898 93773 46915 93773 46956 93774 46916 93774 46918 93774 46918 93775 46916 93775 46917 93775 46917 93776 46915 93776 46918 93776 46918 93777 46915 93777 46889 93777 46918 93778 46889 93778 46919 93778 46919 93779 46889 93779 46920 93779 46919 93780 46920 93780 46905 93780 46984 93781 46955 93781 46922 93781 46922 93782 46955 93782 46956 93782 46905 93783 47009 93783 46919 93783 46919 93784 47009 93784 47022 93784 46919 93785 47022 93785 46923 93785 46923 93786 47022 93786 47021 93786 46923 93787 47021 93787 46921 93787 46944 93788 46984 93788 46925 93788 46925 93789 46984 93789 46922 93789 46925 93790 46922 93790 46924 93790 46956 93791 46918 93791 46922 93791 46922 93792 46918 93792 46923 93792 46922 93793 46923 93793 46924 93793 46924 93794 46923 93794 46921 93794 46924 93795 46921 93795 47000 93795 47040 93796 46944 93796 47039 93796 47039 93797 46944 93797 46925 93797 47039 93798 46925 93798 46926 93798 46926 93799 46925 93799 46924 93799 46926 93800 46924 93800 46927 93800 46927 93801 46924 93801 46928 93801 46985 93802 46863 93802 47049 93802 47049 93803 46863 93803 46929 93803 47049 93804 46929 93804 46930 93804 46892 93805 46969 93805 46929 93805 46929 93806 46969 93806 47061 93806 46929 93807 47061 93807 46930 93807 46954 93808 46902 93808 46979 93808 46901 93809 46900 93809 46931 93809 46936 93810 46932 93810 46933 93810 46945 93811 47041 93811 46934 93811 46935 93812 46975 93812 46974 93812 46936 93813 46937 93813 46932 93813 46932 93814 46937 93814 46938 93814 46932 93815 46938 93815 46935 93815 46939 93816 46941 93816 46940 93816 46940 93817 46941 93817 46942 93817 46940 93818 46942 93818 46983 93818 46940 93819 46943 93819 46939 93819 46939 93820 46943 93820 46944 93820 46939 93821 46944 93821 47040 93821 46942 93822 46945 93822 46983 93822 46983 93823 46945 93823 46934 93823 46983 93824 46934 93824 46981 93824 46981 93825 46934 93825 46949 93825 46981 93826 46949 93826 46946 93826 46946 93827 46949 93827 46950 93827 46946 93828 46950 93828 46980 93828 46980 93829 46950 93829 46947 93829 46980 93830 46947 93830 46953 93830 46893 93831 46976 93831 46971 93831 46971 93832 46976 93832 46978 93832 46935 93833 46974 93833 46932 93833 46932 93834 46974 93834 46948 93834 46932 93835 46948 93835 46933 93835 46933 93836 46948 93836 46971 93836 46933 93837 46971 93837 46951 93837 46951 93838 46971 93838 46978 93838 46951 93839 46978 93839 46952 93839 47041 93840 46937 93840 46934 93840 46934 93841 46937 93841 46936 93841 46934 93842 46936 93842 46949 93842 46949 93843 46936 93843 46933 93843 46949 93844 46933 93844 46950 93844 46950 93845 46933 93845 46951 93845 46950 93846 46951 93846 46947 93846 46947 93847 46951 93847 46952 93847 46947 93848 46952 93848 46953 93848 46954 93849 46979 93849 46903 93849 46984 93850 46961 93850 46955 93850 46955 93851 46961 93851 46962 93851 46955 93852 46962 93852 46956 93852 46956 93853 46962 93853 46965 93853 46956 93854 46965 93854 46916 93854 46916 93855 46965 93855 46957 93855 46916 93856 46957 93856 46917 93856 46917 93857 46957 93857 46967 93857 46917 93858 46967 93858 46898 93858 46898 93859 46967 93859 46968 93859 46902 93860 46901 93860 46979 93860 46979 93861 46901 93861 46931 93861 46979 93862 46931 93862 46958 93862 46958 93863 46931 93863 46959 93863 46958 93864 46959 93864 46960 93864 46960 93865 46959 93865 46966 93865 46960 93866 46966 93866 46982 93866 46982 93867 46966 93867 46964 93867 46982 93868 46964 93868 46963 93868 46961 93869 46963 93869 46962 93869 46962 93870 46963 93870 46964 93870 46962 93871 46964 93871 46965 93871 46965 93872 46964 93872 46966 93872 46965 93873 46966 93873 46957 93873 46957 93874 46966 93874 46959 93874 46957 93875 46959 93875 46967 93875 46967 93876 46959 93876 46931 93876 46967 93877 46931 93877 46968 93877 46968 93878 46931 93878 46900 93878 46969 93879 46893 93879 46970 93879 46970 93880 46893 93880 46971 93880 46970 93881 46971 93881 46972 93881 46972 93882 46971 93882 46948 93882 46972 93883 46948 93883 46973 93883 46973 93884 46948 93884 46974 93884 46973 93885 46974 93885 47050 93885 47050 93886 46974 93886 46975 93886 47050 93887 46975 93887 47051 93887 46976 93888 46977 93888 46978 93888 46978 93889 46977 93889 46896 93889 46978 93890 46896 93890 46952 93890 46952 93891 46896 93891 46903 93891 46952 93892 46903 93892 46953 93892 46953 93893 46903 93893 46979 93893 46953 93894 46979 93894 46980 93894 46980 93895 46979 93895 46958 93895 46980 93896 46958 93896 46946 93896 46946 93897 46958 93897 46960 93897 46946 93898 46960 93898 46981 93898 46981 93899 46960 93899 46982 93899 46981 93900 46982 93900 46983 93900 46983 93901 46982 93901 46963 93901 46983 93902 46963 93902 46940 93902 46940 93903 46963 93903 46961 93903 46940 93904 46961 93904 46943 93904 46943 93905 46961 93905 46984 93905 46943 93906 46984 93906 46944 93906 46864 93907 46985 93907 47060 93907 47036 93908 47034 93908 46986 93908 47014 93909 47029 93909 46990 93909 46987 93910 47045 93910 46988 93910 46988 93911 47045 93911 47044 93911 46988 93912 47044 93912 47001 93912 47001 93913 47044 93913 46928 93913 47001 93914 46928 93914 46989 93914 47030 93915 46990 93915 46991 93915 47042 93916 46992 93916 47031 93916 47031 93917 46992 93917 47043 93917 47031 93918 47043 93918 46993 93918 46993 93919 47043 93919 46994 93919 46993 93920 46994 93920 46986 93920 46986 93921 47034 93921 46993 93921 46993 93922 47034 93922 47032 93922 46993 93923 47032 93923 47031 93923 46994 93924 46995 93924 46986 93924 46986 93925 46995 93925 46996 93925 46986 93926 46996 93926 47036 93926 47036 93927 46996 93927 46997 93927 47036 93928 46997 93928 46999 93928 46999 93929 46997 93929 46998 93929 46999 93930 46998 93930 47038 93930 47038 93931 46998 93931 47000 93931 47038 93932 47000 93932 46921 93932 46995 93933 46987 93933 46996 93933 46996 93934 46987 93934 46988 93934 46996 93935 46988 93935 46997 93935 46997 93936 46988 93936 47001 93936 46997 93937 47001 93937 46998 93937 46998 93938 47001 93938 46989 93938 46998 93939 46989 93939 47000 93939 47003 93940 46910 93940 47002 93940 47003 93941 47002 93941 47024 93941 46910 93942 47003 93942 46904 93942 46904 93943 47003 93943 47004 93943 46904 93944 47004 93944 47007 93944 47008 93945 46909 93945 47005 93945 47005 93946 46909 93946 47006 93946 47005 93947 47006 93947 47004 93947 47004 93948 47006 93948 46907 93948 47004 93949 46907 93949 47007 93949 46905 93950 47008 93950 47009 93950 47009 93951 47008 93951 47005 93951 47009 93952 47005 93952 47022 93952 46913 93953 47012 93953 47010 93953 47010 93954 47012 93954 47027 93954 47010 93955 47027 93955 46914 93955 46914 93956 47027 93956 47024 93956 46914 93957 47024 93957 47011 93957 47011 93958 47024 93958 47002 93958 46913 93959 46860 93959 47012 93959 47012 93960 46860 93960 46864 93960 47012 93961 46864 93961 47028 93961 47028 93962 46864 93962 47060 93962 47028 93963 47060 93963 47013 93963 46990 93964 47030 93964 47014 93964 47014 93965 47030 93965 47015 93965 47014 93966 47015 93966 47016 93966 47016 93967 47015 93967 47033 93967 47016 93968 47033 93968 47026 93968 47026 93969 47033 93969 47035 93969 47026 93970 47035 93970 47017 93970 47017 93971 47035 93971 47018 93971 47017 93972 47018 93972 47025 93972 47025 93973 47018 93973 47019 93973 47025 93974 47019 93974 47020 93974 47020 93975 47019 93975 47037 93975 47020 93976 47037 93976 47023 93976 47023 93977 47037 93977 47021 93977 47023 93978 47021 93978 47022 93978 47022 93979 47005 93979 47023 93979 47023 93980 47005 93980 47004 93980 47023 93981 47004 93981 47020 93981 47020 93982 47004 93982 47003 93982 47020 93983 47003 93983 47025 93983 47025 93984 47003 93984 47024 93984 47025 93985 47024 93985 47017 93985 47017 93986 47024 93986 47027 93986 47017 93987 47027 93987 47026 93987 47026 93988 47027 93988 47012 93988 47026 93989 47012 93989 47016 93989 47016 93990 47012 93990 47028 93990 47016 93991 47028 93991 47014 93991 47014 93992 47028 93992 47013 93992 47014 93993 47013 93993 47029 93993 46991 93994 47042 93994 47030 93994 47030 93995 47042 93995 47031 93995 47030 93996 47031 93996 47015 93996 47015 93997 47031 93997 47032 93997 47015 93998 47032 93998 47033 93998 47033 93999 47032 93999 47034 93999 47033 94000 47034 94000 47035 94000 47035 94001 47034 94001 47036 94001 47035 94002 47036 94002 47018 94002 47018 94003 47036 94003 46999 94003 47018 94004 46999 94004 47019 94004 47019 94005 46999 94005 47038 94005 47019 94006 47038 94006 47037 94006 47037 94007 47038 94007 46921 94007 47037 94008 46921 94008 47021 94008 47046 94009 46991 94009 47047 94009 47048 94010 47040 94010 47039 94010 46939 94011 47040 94011 46941 94011 46941 94012 47040 94012 47048 94012 46941 94013 47048 94013 46942 94013 46942 94014 47048 94014 46945 94014 46975 94015 46935 94015 47048 94015 47048 94016 46935 94016 46938 94016 46938 94017 46937 94017 47048 94017 47048 94018 46937 94018 47041 94018 47048 94019 47041 94019 46945 94019 46987 94020 46995 94020 47046 94020 47046 94021 46995 94021 46994 94021 47042 94022 46991 94022 46992 94022 46992 94023 46991 94023 47046 94023 46992 94024 47046 94024 47043 94024 47043 94025 47046 94025 46994 94025 46928 94026 47044 94026 47046 94026 47046 94027 47044 94027 47045 94027 47046 94028 47045 94028 46987 94028 46928 94029 47046 94029 46927 94029 46927 94030 47046 94030 47047 94030 46927 94031 47047 94031 46926 94031 46926 94032 47047 94032 47053 94032 46926 94033 47053 94033 47039 94033 47039 94034 47053 94034 47052 94034 47039 94035 47052 94035 47048 94035 47048 94036 47052 94036 47051 94036 47048 94037 47051 94037 46975 94037 47060 94038 46985 94038 47049 94038 47029 94039 47013 94039 47056 94039 46970 94040 46972 94040 47058 94040 46973 94041 47050 94041 47059 94041 47050 94042 47051 94042 47059 94042 47059 94043 47051 94043 47052 94043 47059 94044 47052 94044 47054 94044 47054 94045 47052 94045 47053 94045 47054 94046 47053 94046 47055 94046 47055 94047 47053 94047 47047 94047 47055 94048 47047 94048 46990 94048 46990 94049 47047 94049 46991 94049 46990 94050 47029 94050 47055 94050 47055 94051 47029 94051 47056 94051 47055 94052 47056 94052 47054 94052 47054 94053 47056 94053 47057 94053 47054 94054 47057 94054 47059 94054 47059 94055 47057 94055 47058 94055 47059 94056 47058 94056 46973 94056 46973 94057 47058 94057 46972 94057 47013 94058 47060 94058 47056 94058 47056 94059 47060 94059 47049 94059 47056 94060 47049 94060 47057 94060 47057 94061 47049 94061 46930 94061 47057 94062 46930 94062 47058 94062 47058 94063 46930 94063 47061 94063 47058 94064 47061 94064 46970 94064 46970 94065 47061 94065 46969 94065 47062 94066 46672 94066 46705 94066 47062 94067 46705 94067 47063 94067 46705 94068 46704 94068 47063 94068 47063 94069 46704 94069 46703 94069 47063 94070 46703 94070 46680 94070 46680 94071 46703 94071 46681 94071 46681 94072 46703 94072 46702 94072 46681 94073 46702 94073 47064 94073 46853 94074 46885 94074 47065 94074 47065 94075 46885 94075 47067 94075 47065 94076 47067 94076 47066 94076 47066 94077 47067 94077 46882 94077 47066 94078 46882 94078 46667 94078 46667 94079 46882 94079 46881 94079 47270 94080 47078 94080 47350 94080 47350 94081 47078 94081 47068 94081 47350 94082 47068 94082 47349 94082 47354 94083 47355 94083 47080 94083 47080 94084 47355 94084 47347 94084 47080 94085 47347 94085 47068 94085 47068 94086 47347 94086 47348 94086 47068 94087 47348 94087 47349 94087 47354 94088 47080 94088 47069 94088 47069 94089 47080 94089 47081 94089 47069 94090 47081 94090 47070 94090 47070 94091 47081 94091 47077 94091 47070 94092 47077 94092 47071 94092 47071 94093 47077 94093 47072 94093 47071 94094 47072 94094 47074 94094 47072 94095 47073 94095 47074 94095 47074 94096 47073 94096 47075 94096 47074 94097 47075 94097 47076 94097 47076 94098 47075 94098 47272 94098 47076 94099 47272 94099 47271 94099 47454 94100 47272 94100 47442 94100 47442 94101 47272 94101 47075 94101 47442 94102 47075 94102 47443 94102 47443 94103 47075 94103 47073 94103 47073 94104 47072 94104 47443 94104 47443 94105 47072 94105 47077 94105 47443 94106 47077 94106 47444 94106 47078 94107 47079 94107 47068 94107 47068 94108 47079 94108 47446 94108 47068 94109 47446 94109 47080 94109 47080 94110 47446 94110 47444 94110 47080 94111 47444 94111 47081 94111 47081 94112 47444 94112 47077 94112 47084 94113 47219 94113 47082 94113 47082 94114 47219 94114 47153 94114 47082 94115 47153 94115 47083 94115 47082 94116 47450 94116 47084 94116 47084 94117 47450 94117 47452 94117 47094 94118 47085 94118 47213 94118 47085 94119 47094 94119 47086 94119 47092 94120 47088 94120 47093 94120 47131 94121 47133 94121 47087 94121 47127 94122 47129 94122 47092 94122 47092 94123 47129 94123 47131 94123 47131 94124 47087 94124 47092 94124 47092 94125 47087 94125 47457 94125 47092 94126 47457 94126 47088 94126 47088 94127 47457 94127 47459 94127 47088 94128 47459 94128 47089 94128 47124 94129 47125 94129 47091 94129 47091 94130 47125 94130 47127 94130 47089 94131 47178 94131 47088 94131 47088 94132 47178 94132 47189 94132 47088 94133 47189 94133 47093 94133 47093 94134 47189 94134 47090 94134 47093 94135 47090 94135 47204 94135 47109 94136 47124 94136 47095 94136 47095 94137 47124 94137 47091 94137 47095 94138 47091 94138 47094 94138 47127 94139 47092 94139 47091 94139 47091 94140 47092 94140 47093 94140 47091 94141 47093 94141 47094 94141 47094 94142 47093 94142 47204 94142 47094 94143 47204 94143 47086 94143 47205 94144 47109 94144 47096 94144 47096 94145 47109 94145 47095 94145 47096 94146 47095 94146 47215 94146 47215 94147 47095 94147 47094 94147 47215 94148 47094 94148 47097 94148 47097 94149 47094 94149 47213 94149 47219 94150 47084 94150 47220 94150 47220 94151 47084 94151 47460 94151 47220 94152 47460 94152 47233 94152 47233 94153 47460 94153 47098 94153 47098 94154 47460 94154 47099 94154 47098 94155 47099 94155 47100 94155 47469 94156 47471 94156 47143 94156 47101 94157 47112 94157 47102 94157 47210 94158 47209 94158 47117 94158 47103 94159 47217 94159 47104 94159 47101 94160 47118 94160 47112 94160 47112 94161 47118 94161 47105 94161 47112 94162 47105 94162 47103 94162 47108 94163 47206 94163 47107 94163 47107 94164 47206 94164 47207 94164 47107 94165 47207 94165 47106 94165 47107 94166 47152 94166 47108 94166 47108 94167 47152 94167 47109 94167 47108 94168 47109 94168 47205 94168 47207 94169 47210 94169 47106 94169 47106 94170 47210 94170 47117 94170 47106 94171 47117 94171 47151 94171 47151 94172 47117 94172 47119 94172 47151 94173 47119 94173 47149 94173 47149 94174 47119 94174 47120 94174 47149 94175 47120 94175 47148 94175 47148 94176 47120 94176 47121 94176 47148 94177 47121 94177 47110 94177 47144 94178 47111 94178 47146 94178 47146 94179 47111 94179 47114 94179 47103 94180 47104 94180 47112 94180 47112 94181 47104 94181 47113 94181 47112 94182 47113 94182 47102 94182 47102 94183 47113 94183 47146 94183 47102 94184 47146 94184 47115 94184 47115 94185 47146 94185 47114 94185 47115 94186 47114 94186 47116 94186 47209 94187 47118 94187 47117 94187 47117 94188 47118 94188 47101 94188 47117 94189 47101 94189 47119 94189 47119 94190 47101 94190 47102 94190 47119 94191 47102 94191 47120 94191 47120 94192 47102 94192 47115 94192 47120 94193 47115 94193 47121 94193 47121 94194 47115 94194 47116 94194 47121 94195 47116 94195 47110 94195 47468 94196 47470 94196 47134 94196 47134 94197 47470 94197 47122 94197 47134 94198 47122 94198 47123 94198 47124 94199 47139 94199 47125 94199 47125 94200 47139 94200 47126 94200 47125 94201 47126 94201 47127 94201 47127 94202 47126 94202 47128 94202 47127 94203 47128 94203 47129 94203 47129 94204 47128 94204 47130 94204 47129 94205 47130 94205 47131 94205 47131 94206 47130 94206 47132 94206 47131 94207 47132 94207 47133 94207 47133 94208 47132 94208 47142 94208 47123 94209 47469 94209 47134 94209 47134 94210 47469 94210 47143 94210 47134 94211 47143 94211 47135 94211 47135 94212 47143 94212 47141 94212 47135 94213 47141 94213 47136 94213 47136 94214 47141 94214 47140 94214 47136 94215 47140 94215 47150 94215 47150 94216 47140 94216 47137 94216 47150 94217 47137 94217 47138 94217 47139 94218 47138 94218 47126 94218 47126 94219 47138 94219 47137 94219 47126 94220 47137 94220 47128 94220 47128 94221 47137 94221 47140 94221 47128 94222 47140 94222 47130 94222 47130 94223 47140 94223 47141 94223 47130 94224 47141 94224 47132 94224 47132 94225 47141 94225 47143 94225 47132 94226 47143 94226 47142 94226 47142 94227 47143 94227 47471 94227 47100 94228 47144 94228 47145 94228 47145 94229 47144 94229 47146 94229 47145 94230 47146 94230 47147 94230 47147 94231 47146 94231 47113 94231 47147 94232 47113 94232 47222 94232 47222 94233 47113 94233 47104 94233 47222 94234 47104 94234 47223 94234 47223 94235 47104 94235 47217 94235 47223 94236 47217 94236 47216 94236 47111 94237 47464 94237 47114 94237 47114 94238 47464 94238 47465 94238 47114 94239 47465 94239 47116 94239 47116 94240 47465 94240 47468 94240 47116 94241 47468 94241 47110 94241 47110 94242 47468 94242 47134 94242 47110 94243 47134 94243 47148 94243 47148 94244 47134 94244 47135 94244 47148 94245 47135 94245 47149 94245 47149 94246 47135 94246 47136 94246 47149 94247 47136 94247 47151 94247 47151 94248 47136 94248 47150 94248 47151 94249 47150 94249 47106 94249 47106 94250 47150 94250 47138 94250 47106 94251 47138 94251 47107 94251 47107 94252 47138 94252 47139 94252 47107 94253 47139 94253 47152 94253 47152 94254 47139 94254 47124 94254 47152 94255 47124 94255 47109 94255 47153 94256 47219 94256 47218 94256 47201 94257 47200 94257 47164 94257 47196 94258 47221 94258 47159 94258 47154 94259 47214 94259 47155 94259 47155 94260 47214 94260 47157 94260 47155 94261 47157 94261 47156 94261 47156 94262 47157 94262 47213 94262 47156 94263 47213 94263 47085 94263 47158 94264 47159 94264 47211 94264 47197 94265 47160 94265 47161 94265 47161 94266 47160 94266 47162 94266 47161 94267 47162 94267 47163 94267 47163 94268 47162 94268 47166 94268 47163 94269 47166 94269 47164 94269 47164 94270 47200 94270 47163 94270 47163 94271 47200 94271 47165 94271 47163 94272 47165 94272 47161 94272 47166 94273 47167 94273 47164 94273 47164 94274 47167 94274 47170 94274 47164 94275 47170 94275 47201 94275 47201 94276 47170 94276 47171 94276 47201 94277 47171 94277 47168 94277 47168 94278 47171 94278 47172 94278 47168 94279 47172 94279 47169 94279 47169 94280 47172 94280 47086 94280 47169 94281 47086 94281 47204 94281 47167 94282 47154 94282 47170 94282 47170 94283 47154 94283 47155 94283 47170 94284 47155 94284 47171 94284 47171 94285 47155 94285 47156 94285 47171 94286 47156 94286 47172 94286 47172 94287 47156 94287 47085 94287 47172 94288 47085 94288 47086 94288 47174 94289 47476 94289 47173 94289 47174 94290 47173 94290 47181 94290 47476 94291 47174 94291 47175 94291 47175 94292 47174 94292 47176 94292 47175 94293 47176 94293 47473 94293 47473 94294 47176 94294 47190 94294 47473 94295 47190 94295 47177 94295 47089 94296 47177 94296 47178 94296 47178 94297 47177 94297 47190 94297 47178 94298 47190 94298 47189 94298 47153 94299 47218 94299 47083 94299 47180 94300 47179 94300 47183 94300 47183 94301 47194 94301 47180 94301 47180 94302 47194 94302 47181 94302 47180 94303 47181 94303 47182 94303 47182 94304 47181 94304 47173 94304 47179 94305 47478 94305 47183 94305 47183 94306 47478 94306 47083 94306 47183 94307 47083 94307 47184 94307 47184 94308 47083 94308 47218 94308 47184 94309 47218 94309 47231 94309 47159 94310 47158 94310 47196 94310 47196 94311 47158 94311 47185 94311 47196 94312 47185 94312 47195 94312 47195 94313 47185 94313 47198 94313 47195 94314 47198 94314 47186 94314 47186 94315 47198 94315 47199 94315 47186 94316 47199 94316 47193 94316 47193 94317 47199 94317 47187 94317 47193 94318 47187 94318 47188 94318 47188 94319 47187 94319 47202 94319 47188 94320 47202 94320 47192 94320 47192 94321 47202 94321 47203 94321 47192 94322 47203 94322 47191 94322 47191 94323 47203 94323 47090 94323 47191 94324 47090 94324 47189 94324 47189 94325 47190 94325 47191 94325 47191 94326 47190 94326 47176 94326 47191 94327 47176 94327 47192 94327 47192 94328 47176 94328 47174 94328 47192 94329 47174 94329 47188 94329 47188 94330 47174 94330 47181 94330 47188 94331 47181 94331 47193 94331 47193 94332 47181 94332 47194 94332 47193 94333 47194 94333 47186 94333 47186 94334 47194 94334 47183 94334 47186 94335 47183 94335 47195 94335 47195 94336 47183 94336 47184 94336 47195 94337 47184 94337 47196 94337 47196 94338 47184 94338 47231 94338 47196 94339 47231 94339 47221 94339 47211 94340 47197 94340 47158 94340 47158 94341 47197 94341 47161 94341 47158 94342 47161 94342 47185 94342 47185 94343 47161 94343 47165 94343 47185 94344 47165 94344 47198 94344 47198 94345 47165 94345 47200 94345 47198 94346 47200 94346 47199 94346 47199 94347 47200 94347 47201 94347 47199 94348 47201 94348 47187 94348 47187 94349 47201 94349 47168 94349 47187 94350 47168 94350 47202 94350 47202 94351 47168 94351 47169 94351 47202 94352 47169 94352 47203 94352 47203 94353 47169 94353 47204 94353 47203 94354 47204 94354 47090 94354 47212 94355 47211 94355 47228 94355 47208 94356 47205 94356 47096 94356 47108 94357 47205 94357 47206 94357 47206 94358 47205 94358 47208 94358 47206 94359 47208 94359 47207 94359 47207 94360 47208 94360 47210 94360 47217 94361 47103 94361 47208 94361 47208 94362 47103 94362 47105 94362 47105 94363 47118 94363 47208 94363 47208 94364 47118 94364 47209 94364 47208 94365 47209 94365 47210 94365 47154 94366 47167 94366 47212 94366 47212 94367 47167 94367 47166 94367 47197 94368 47211 94368 47160 94368 47160 94369 47211 94369 47212 94369 47160 94370 47212 94370 47162 94370 47162 94371 47212 94371 47166 94371 47213 94372 47157 94372 47212 94372 47212 94373 47157 94373 47214 94373 47212 94374 47214 94374 47154 94374 47213 94375 47212 94375 47097 94375 47097 94376 47212 94376 47228 94376 47097 94377 47228 94377 47215 94377 47215 94378 47228 94378 47226 94378 47215 94379 47226 94379 47096 94379 47096 94380 47226 94380 47225 94380 47096 94381 47225 94381 47208 94381 47208 94382 47225 94382 47216 94382 47208 94383 47216 94383 47217 94383 47218 94384 47219 94384 47220 94384 47221 94385 47231 94385 47232 94385 47145 94386 47147 94386 47234 94386 47222 94387 47223 94387 47224 94387 47223 94388 47216 94388 47224 94388 47224 94389 47216 94389 47225 94389 47224 94390 47225 94390 47227 94390 47227 94391 47225 94391 47226 94391 47227 94392 47226 94392 47229 94392 47229 94393 47226 94393 47228 94393 47229 94394 47228 94394 47159 94394 47159 94395 47228 94395 47211 94395 47159 94396 47221 94396 47229 94396 47229 94397 47221 94397 47232 94397 47229 94398 47232 94398 47227 94398 47227 94399 47232 94399 47230 94399 47227 94400 47230 94400 47224 94400 47224 94401 47230 94401 47234 94401 47224 94402 47234 94402 47222 94402 47222 94403 47234 94403 47147 94403 47231 94404 47218 94404 47232 94404 47232 94405 47218 94405 47220 94405 47232 94406 47220 94406 47230 94406 47230 94407 47220 94407 47233 94407 47230 94408 47233 94408 47234 94408 47234 94409 47233 94409 47098 94409 47234 94410 47098 94410 47145 94410 47145 94411 47098 94411 47100 94411 47235 94412 47252 94412 47236 94412 47235 94413 47236 94413 47255 94413 47236 94414 47275 94414 47255 94414 47255 94415 47275 94415 47274 94415 47255 94416 47274 94416 47257 94416 47257 94417 47274 94417 47237 94417 47237 94418 47274 94418 47241 94418 47237 94419 47241 94419 47240 94419 47272 94420 47454 94420 47273 94420 47273 94421 47454 94421 47453 94421 47273 94422 47453 94422 47238 94422 47238 94423 47453 94423 47239 94423 47238 94424 47239 94424 47249 94424 47249 94425 47239 94425 47451 94425 47240 94426 47241 94426 47242 94426 47242 94427 47241 94427 47243 94427 47242 94428 47243 94428 47245 94428 47243 94429 47244 94429 47245 94429 47245 94430 47244 94430 47268 94430 47245 94431 47268 94431 47246 94431 47246 94432 47268 94432 47264 94432 47246 94433 47264 94433 47247 94433 47247 94434 47264 94434 47261 94434 47247 94435 47261 94435 47248 94435 47249 94436 47451 94436 47260 94436 47260 94437 47451 94437 47448 94437 47260 94438 47448 94438 47250 94438 47250 94439 47448 94439 47248 94439 47250 94440 47248 94440 47251 94440 47251 94441 47248 94441 47261 94441 47236 94442 47252 94442 47269 94442 47269 94443 47252 94443 47253 94443 47269 94444 47253 94444 47078 94444 47078 94445 47253 94445 47079 94445 47257 94446 47237 94446 47431 94446 47254 94447 47235 94447 47432 94447 47432 94448 47235 94448 47255 94448 47432 94449 47255 94449 47256 94449 47256 94450 47255 94450 47257 94450 47256 94451 47257 94451 47429 94451 47429 94452 47257 94452 47431 94452 47243 94453 47241 94453 47296 94453 47258 94454 47249 94454 47259 94454 47259 94455 47249 94455 47260 94455 47259 94456 47260 94456 47293 94456 47293 94457 47260 94457 47299 94457 47260 94458 47250 94458 47299 94458 47299 94459 47250 94459 47251 94459 47299 94460 47251 94460 47262 94460 47262 94461 47251 94461 47261 94461 47262 94462 47261 94462 47303 94462 47303 94463 47261 94463 47263 94463 47263 94464 47261 94464 47264 94464 47263 94465 47264 94465 47305 94465 47265 94466 47266 94466 47268 94466 47268 94467 47266 94467 47267 94467 47268 94468 47267 94468 47264 94468 47264 94469 47267 94469 47297 94469 47264 94470 47297 94470 47305 94470 47296 94471 47294 94471 47243 94471 47243 94472 47294 94472 47265 94472 47243 94473 47265 94473 47244 94473 47244 94474 47265 94474 47268 94474 47352 94475 47277 94475 47236 94475 47236 94476 47269 94476 47352 94476 47352 94477 47269 94477 47078 94477 47352 94478 47078 94478 47270 94478 47271 94479 47272 94479 47391 94479 47391 94480 47272 94480 47273 94480 47391 94481 47273 94481 47390 94481 47390 94482 47273 94482 47238 94482 47390 94483 47238 94483 47258 94483 47258 94484 47238 94484 47249 94484 47296 94485 47241 94485 47274 94485 47296 94486 47274 94486 47407 94486 47407 94487 47274 94487 47275 94487 47407 94488 47275 94488 47276 94488 47276 94489 47275 94489 47236 94489 47276 94490 47236 94490 47277 94490 47317 94491 47423 94491 47385 94491 47412 94492 47317 94492 47290 94492 47410 94493 47279 94493 47278 94493 47278 94494 47279 94494 47284 94494 47278 94495 47284 94495 47411 94495 47411 94496 47284 94496 47280 94496 47411 94497 47280 94497 47408 94497 47408 94498 47280 94498 47286 94498 47281 94499 47401 94499 47285 94499 47324 94500 47325 94500 47283 94500 47283 94501 47325 94501 47326 94501 47283 94502 47326 94502 47281 94502 47281 94503 47326 94503 47327 94503 47281 94504 47327 94504 47401 94504 47287 94505 47279 94505 47282 94505 47282 94506 47279 94506 47410 94506 47282 94507 47410 94507 47319 94507 47287 94508 47324 94508 47279 94508 47279 94509 47324 94509 47283 94509 47279 94510 47283 94510 47284 94510 47284 94511 47283 94511 47281 94511 47284 94512 47281 94512 47280 94512 47280 94513 47281 94513 47285 94513 47280 94514 47285 94514 47286 94514 47322 94515 47288 94515 47287 94515 47287 94516 47288 94516 47289 94516 47287 94517 47289 94517 47324 94517 47413 94518 47412 94518 47320 94518 47320 94519 47412 94519 47290 94519 47320 94520 47290 94520 47291 94520 47291 94521 47290 94521 47318 94521 47292 94522 47300 94522 47301 94522 47293 94523 47321 94523 47259 94523 47259 94524 47321 94524 47389 94524 47259 94525 47389 94525 47258 94525 47298 94526 47294 94526 47295 94526 47295 94527 47294 94527 47296 94527 47295 94528 47296 94528 47315 94528 47297 94529 47267 94529 47304 94529 47304 94530 47267 94530 47266 94530 47304 94531 47266 94531 47298 94531 47298 94532 47266 94532 47265 94532 47298 94533 47265 94533 47294 94533 47293 94534 47299 94534 47300 94534 47300 94535 47299 94535 47262 94535 47300 94536 47262 94536 47301 94536 47301 94537 47262 94537 47303 94537 47301 94538 47303 94538 47302 94538 47302 94539 47303 94539 47263 94539 47302 94540 47263 94540 47304 94540 47304 94541 47263 94541 47305 94541 47304 94542 47305 94542 47297 94542 47292 94543 47313 94543 47306 94543 47306 94544 47313 94544 47314 94544 47306 94545 47314 94545 47323 94545 47323 94546 47314 94546 47307 94546 47323 94547 47307 94547 47308 94547 47308 94548 47307 94548 47309 94548 47308 94549 47309 94549 47310 94549 47310 94550 47309 94550 47316 94550 47310 94551 47316 94551 47311 94551 47311 94552 47316 94552 47312 94552 47311 94553 47312 94553 47404 94553 47292 94554 47301 94554 47313 94554 47313 94555 47301 94555 47302 94555 47313 94556 47302 94556 47314 94556 47314 94557 47302 94557 47304 94557 47314 94558 47304 94558 47307 94558 47307 94559 47304 94559 47298 94559 47307 94560 47298 94560 47309 94560 47309 94561 47298 94561 47295 94561 47309 94562 47295 94562 47316 94562 47316 94563 47295 94563 47315 94563 47316 94564 47315 94564 47312 94564 47317 94565 47385 94565 47290 94565 47290 94566 47385 94566 47383 94566 47290 94567 47383 94567 47318 94567 47318 94568 47383 94568 47394 94568 47318 94569 47394 94569 47388 94569 47319 94570 47413 94570 47282 94570 47282 94571 47413 94571 47320 94571 47282 94572 47320 94572 47287 94572 47287 94573 47320 94573 47291 94573 47287 94574 47291 94574 47322 94574 47322 94575 47291 94575 47318 94575 47322 94576 47318 94576 47321 94576 47321 94577 47318 94577 47388 94577 47321 94578 47388 94578 47389 94578 47293 94579 47300 94579 47321 94579 47321 94580 47300 94580 47292 94580 47321 94581 47292 94581 47322 94581 47322 94582 47292 94582 47306 94582 47322 94583 47306 94583 47288 94583 47288 94584 47306 94584 47323 94584 47288 94585 47323 94585 47289 94585 47289 94586 47323 94586 47308 94586 47289 94587 47308 94587 47324 94587 47324 94588 47308 94588 47310 94588 47324 94589 47310 94589 47325 94589 47325 94590 47310 94590 47311 94590 47325 94591 47311 94591 47326 94591 47326 94592 47311 94592 47404 94592 47326 94593 47404 94593 47327 94593 47076 94594 47271 94594 47328 94594 47329 94595 47277 94595 47352 94595 47340 94596 47376 94596 47330 94596 47356 94597 47331 94597 47392 94597 47395 94598 47332 94598 47333 94598 47333 94599 47332 94599 47334 94599 47333 94600 47334 94600 47417 94600 47417 94601 47334 94601 47343 94601 47417 94602 47343 94602 47335 94602 47373 94603 47392 94603 47415 94603 47372 94604 47416 94604 47374 94604 47374 94605 47416 94605 47336 94605 47336 94606 47416 94606 47337 94606 47336 94607 47337 94607 47330 94607 47330 94608 47376 94608 47336 94608 47336 94609 47376 94609 47375 94609 47336 94610 47375 94610 47374 94610 47337 94611 47338 94611 47330 94611 47330 94612 47338 94612 47339 94612 47330 94613 47339 94613 47340 94613 47340 94614 47339 94614 47344 94614 47340 94615 47344 94615 47341 94615 47341 94616 47344 94616 47345 94616 47341 94617 47345 94617 47342 94617 47342 94618 47345 94618 47346 94618 47342 94619 47346 94619 47380 94619 47338 94620 47335 94620 47339 94620 47339 94621 47335 94621 47343 94621 47339 94622 47343 94622 47344 94622 47344 94623 47343 94623 47334 94623 47344 94624 47334 94624 47345 94624 47345 94625 47334 94625 47332 94625 47345 94626 47332 94626 47346 94626 47355 94627 47365 94627 47347 94627 47347 94628 47365 94628 47364 94628 47347 94629 47364 94629 47348 94629 47348 94630 47364 94630 47349 94630 47349 94631 47364 94631 47360 94631 47349 94632 47360 94632 47350 94632 47402 94633 47329 94633 47351 94633 47351 94634 47329 94634 47352 94634 47351 94635 47352 94635 47360 94635 47360 94636 47352 94636 47270 94636 47360 94637 47270 94637 47350 94637 47071 94638 47353 94638 47070 94638 47070 94639 47353 94639 47368 94639 47070 94640 47368 94640 47069 94640 47069 94641 47368 94641 47365 94641 47069 94642 47365 94642 47354 94642 47354 94643 47365 94643 47355 94643 47071 94644 47074 94644 47353 94644 47353 94645 47074 94645 47076 94645 47353 94646 47076 94646 47370 94646 47370 94647 47076 94647 47328 94647 47370 94648 47328 94648 47371 94648 47392 94649 47373 94649 47356 94649 47356 94650 47373 94650 47357 94650 47356 94651 47357 94651 47369 94651 47369 94652 47357 94652 47358 94652 47369 94653 47358 94653 47367 94653 47367 94654 47358 94654 47377 94654 47367 94655 47377 94655 47366 94655 47366 94656 47377 94656 47378 94656 47366 94657 47378 94657 47363 94657 47363 94658 47378 94658 47379 94658 47363 94659 47379 94659 47362 94659 47362 94660 47379 94660 47359 94660 47362 94661 47359 94661 47361 94661 47361 94662 47359 94662 47381 94662 47361 94663 47381 94663 47402 94663 47402 94664 47351 94664 47361 94664 47361 94665 47351 94665 47360 94665 47361 94666 47360 94666 47362 94666 47362 94667 47360 94667 47364 94667 47362 94668 47364 94668 47363 94668 47363 94669 47364 94669 47365 94669 47363 94670 47365 94670 47366 94670 47366 94671 47365 94671 47368 94671 47366 94672 47368 94672 47367 94672 47367 94673 47368 94673 47353 94673 47367 94674 47353 94674 47369 94674 47369 94675 47353 94675 47370 94675 47369 94676 47370 94676 47356 94676 47356 94677 47370 94677 47371 94677 47356 94678 47371 94678 47331 94678 47415 94679 47372 94679 47373 94679 47373 94680 47372 94680 47374 94680 47373 94681 47374 94681 47357 94681 47357 94682 47374 94682 47375 94682 47357 94683 47375 94683 47358 94683 47358 94684 47375 94684 47376 94684 47358 94685 47376 94685 47377 94685 47377 94686 47376 94686 47340 94686 47377 94687 47340 94687 47378 94687 47378 94688 47340 94688 47341 94688 47378 94689 47341 94689 47379 94689 47379 94690 47341 94690 47342 94690 47379 94691 47342 94691 47359 94691 47359 94692 47342 94692 47380 94692 47359 94693 47380 94693 47381 94693 47384 94694 47386 94694 47393 94694 47382 94695 47415 94695 47392 94695 47385 94696 47423 94696 47422 94696 47394 94697 47383 94697 47384 94697 47384 94698 47383 94698 47385 94698 47385 94699 47422 94699 47384 94699 47384 94700 47422 94700 47421 94700 47384 94701 47421 94701 47386 94701 47386 94702 47421 94702 47419 94702 47386 94703 47419 94703 47382 94703 47389 94704 47388 94704 47387 94704 47387 94705 47388 94705 47394 94705 47258 94706 47389 94706 47390 94706 47390 94707 47389 94707 47387 94707 47390 94708 47387 94708 47391 94708 47382 94709 47392 94709 47386 94709 47386 94710 47392 94710 47331 94710 47386 94711 47331 94711 47393 94711 47393 94712 47331 94712 47371 94712 47393 94713 47371 94713 47328 94713 47394 94714 47384 94714 47387 94714 47387 94715 47384 94715 47393 94715 47387 94716 47393 94716 47391 94716 47391 94717 47393 94717 47328 94717 47391 94718 47328 94718 47271 94718 47329 94719 47402 94719 47406 94719 47399 94720 47420 94720 47400 94720 47395 94721 47398 94721 47332 94721 47332 94722 47398 94722 47396 94722 47408 94723 47286 94723 47409 94723 47409 94724 47286 94724 47420 94724 47405 94725 47397 94725 47403 94725 47403 94726 47397 94726 47396 94726 47420 94727 47286 94727 47400 94727 47400 94728 47286 94728 47285 94728 47400 94729 47285 94729 47401 94729 47398 94730 47399 94730 47396 94730 47396 94731 47399 94731 47400 94731 47396 94732 47400 94732 47403 94732 47403 94733 47400 94733 47401 94733 47402 94734 47381 94734 47397 94734 47397 94735 47381 94735 47380 94735 47397 94736 47380 94736 47396 94736 47396 94737 47380 94737 47346 94737 47396 94738 47346 94738 47332 94738 47407 94739 47276 94739 47406 94739 47406 94740 47276 94740 47277 94740 47406 94741 47277 94741 47329 94741 47401 94742 47327 94742 47403 94742 47403 94743 47327 94743 47404 94743 47403 94744 47404 94744 47405 94744 47405 94745 47404 94745 47312 94745 47405 94746 47312 94746 47315 94746 47402 94747 47397 94747 47406 94747 47406 94748 47397 94748 47405 94748 47406 94749 47405 94749 47407 94749 47407 94750 47405 94750 47315 94750 47407 94751 47315 94751 47296 94751 47414 94752 47408 94752 47409 94752 47414 94753 47319 94753 47410 94753 47410 94754 47278 94754 47414 94754 47414 94755 47278 94755 47411 94755 47414 94756 47411 94756 47408 94756 47317 94757 47412 94757 47414 94757 47414 94758 47412 94758 47413 94758 47414 94759 47413 94759 47319 94759 47418 94760 47415 94760 47382 94760 47372 94761 47415 94761 47416 94761 47416 94762 47415 94762 47418 94762 47416 94763 47418 94763 47337 94763 47395 94764 47333 94764 47418 94764 47418 94765 47333 94765 47417 94765 47417 94766 47335 94766 47418 94766 47418 94767 47335 94767 47338 94767 47418 94768 47338 94768 47337 94768 47395 94769 47418 94769 47398 94769 47398 94770 47418 94770 47382 94770 47398 94771 47382 94771 47399 94771 47399 94772 47382 94772 47419 94772 47399 94773 47419 94773 47420 94773 47420 94774 47419 94774 47421 94774 47420 94775 47421 94775 47409 94775 47409 94776 47421 94776 47422 94776 47409 94777 47422 94777 47414 94777 47414 94778 47422 94778 47423 94778 47414 94779 47423 94779 47317 94779 47450 94780 47082 94780 47449 94780 47449 94781 47082 94781 47424 94781 47449 94782 47424 94782 47426 94782 47424 94783 47425 94783 47426 94783 47426 94784 47425 94784 47477 94784 47426 94785 47477 94785 47441 94785 47441 94786 47477 94786 47427 94786 47441 94787 47427 94787 47440 94787 47427 94788 47475 94788 47440 94788 47440 94789 47475 94789 47474 94789 47440 94790 47474 94790 47237 94790 47237 94791 47474 94791 47431 94791 47428 94792 47429 94792 47430 94792 47430 94793 47429 94793 47431 94793 47430 94794 47431 94794 47472 94794 47472 94795 47431 94795 47474 94795 47432 94796 47456 94796 47254 94796 47254 94797 47456 94797 47433 94797 47254 94798 47433 94798 47235 94798 47235 94799 47433 94799 47434 94799 47235 94800 47434 94800 47447 94800 47447 94801 47434 94801 47435 94801 47447 94802 47435 94802 47445 94802 47445 94803 47435 94803 47436 94803 47445 94804 47436 94804 47437 94804 47437 94805 47436 94805 47467 94805 47437 94806 47467 94806 47455 94806 47099 94807 47462 94807 47463 94807 47463 94808 47462 94808 47438 94808 47463 94809 47438 94809 47439 94809 47439 94810 47438 94810 47455 94810 47439 94811 47455 94811 47466 94811 47466 94812 47455 94812 47467 94812 47246 94813 47426 94813 47441 94813 47237 94814 47240 94814 47440 94814 47440 94815 47240 94815 47242 94815 47440 94816 47242 94816 47441 94816 47441 94817 47242 94817 47245 94817 47441 94818 47245 94818 47246 94818 47454 94819 47442 94819 47455 94819 47455 94820 47442 94820 47443 94820 47455 94821 47443 94821 47437 94821 47437 94822 47443 94822 47444 94822 47437 94823 47444 94823 47445 94823 47252 94824 47235 94824 47447 94824 47444 94825 47446 94825 47445 94825 47445 94826 47446 94826 47079 94826 47445 94827 47079 94827 47447 94827 47447 94828 47079 94828 47253 94828 47447 94829 47253 94829 47252 94829 47246 94830 47247 94830 47426 94830 47426 94831 47247 94831 47248 94831 47426 94832 47248 94832 47449 94832 47449 94833 47248 94833 47448 94833 47449 94834 47448 94834 47450 94834 47450 94835 47448 94835 47451 94835 47450 94836 47451 94836 47452 94836 47452 94837 47451 94837 47239 94837 47452 94838 47239 94838 47461 94838 47461 94839 47239 94839 47453 94839 47461 94840 47453 94840 47462 94840 47462 94841 47453 94841 47454 94841 47462 94842 47454 94842 47438 94842 47438 94843 47454 94843 47455 94843 47429 94844 47428 94844 47458 94844 47429 94845 47458 94845 47256 94845 47256 94846 47458 94846 47456 94846 47256 94847 47456 94847 47432 94847 47133 94848 47456 94848 47087 94848 47087 94849 47456 94849 47458 94849 47087 94850 47458 94850 47457 94850 47428 94851 47089 94851 47458 94851 47458 94852 47089 94852 47459 94852 47458 94853 47459 94853 47457 94853 47084 94854 47452 94854 47460 94854 47460 94855 47452 94855 47461 94855 47460 94856 47461 94856 47099 94856 47099 94857 47461 94857 47462 94857 47433 94858 47456 94858 47133 94858 47100 94859 47099 94859 47144 94859 47144 94860 47099 94860 47463 94860 47144 94861 47463 94861 47111 94861 47111 94862 47463 94862 47464 94862 47463 94863 47439 94863 47464 94863 47464 94864 47439 94864 47466 94864 47464 94865 47466 94865 47465 94865 47465 94866 47466 94866 47467 94866 47465 94867 47467 94867 47468 94867 47468 94868 47467 94868 47436 94868 47468 94869 47436 94869 47470 94869 47471 94870 47469 94870 47435 94870 47435 94871 47469 94871 47123 94871 47435 94872 47123 94872 47436 94872 47436 94873 47123 94873 47122 94873 47436 94874 47122 94874 47470 94874 47133 94875 47142 94875 47433 94875 47433 94876 47142 94876 47471 94876 47433 94877 47471 94877 47434 94877 47434 94878 47471 94878 47435 94878 47177 94879 47089 94879 47428 94879 47428 94880 47430 94880 47177 94880 47177 94881 47430 94881 47472 94881 47177 94882 47472 94882 47473 94882 47473 94883 47472 94883 47474 94883 47473 94884 47474 94884 47175 94884 47175 94885 47474 94885 47475 94885 47175 94886 47475 94886 47476 94886 47476 94887 47475 94887 47427 94887 47476 94888 47427 94888 47173 94888 47173 94889 47427 94889 47182 94889 47182 94890 47427 94890 47477 94890 47182 94891 47477 94891 47180 94891 47477 94892 47425 94892 47180 94892 47180 94893 47425 94893 47424 94893 47180 94894 47424 94894 47179 94894 47082 94895 47083 94895 47424 94895 47424 94896 47083 94896 47478 94896 47424 94897 47478 94897 47179 94897 47575 94898 47878 94898 47479 94898 47479 94899 47878 94899 47480 94899 47479 94900 47480 94900 47481 94900 47481 94901 47480 94901 47482 94901 47875 94902 47871 94902 47580 94902 47580 94903 47483 94903 47875 94903 47875 94904 47483 94904 47484 94904 47875 94905 47484 94905 47876 94905 47876 94906 47484 94906 47485 94906 47876 94907 47485 94907 47881 94907 47881 94908 47485 94908 47486 94908 47881 94909 47486 94909 47482 94909 47482 94910 47486 94910 47487 94910 47482 94911 47487 94911 47481 94911 47488 94912 47489 94912 47872 94912 47872 94913 47489 94913 47490 94913 47872 94914 47490 94914 47873 94914 47490 94915 47581 94915 47873 94915 47873 94916 47581 94916 47491 94916 47873 94917 47491 94917 47492 94917 47492 94918 47491 94918 47577 94918 47492 94919 47577 94919 47871 94919 47871 94920 47577 94920 47576 94920 47871 94921 47576 94921 47580 94921 47489 94922 47488 94922 47612 94922 47612 94923 47488 94923 47493 94923 47612 94924 47493 94924 47495 94924 47495 94925 47493 94925 47494 94925 47495 94926 47494 94926 47521 94926 47521 94927 47494 94927 47890 94927 47496 94928 47861 94928 47497 94928 47496 94929 47497 94929 47630 94929 47630 94930 47497 94930 47498 94930 47630 94931 47498 94931 47499 94931 47499 94932 47498 94932 47878 94932 47499 94933 47878 94933 47575 94933 47541 94934 47607 94934 47500 94934 47515 94935 47541 94935 47543 94935 47632 94936 47510 94936 47501 94936 47501 94937 47510 94937 47502 94937 47501 94938 47502 94938 47633 94938 47633 94939 47502 94939 47503 94939 47633 94940 47503 94940 47504 94940 47504 94941 47503 94941 47505 94941 47512 94942 47624 94942 47506 94942 47555 94943 47556 94943 47511 94943 47511 94944 47556 94944 47507 94944 47511 94945 47507 94945 47512 94945 47512 94946 47507 94946 47508 94946 47512 94947 47508 94947 47624 94947 47548 94948 47510 94948 47509 94948 47509 94949 47510 94949 47632 94949 47509 94950 47632 94950 47635 94950 47548 94951 47555 94951 47510 94951 47510 94952 47555 94952 47511 94952 47510 94953 47511 94953 47502 94953 47502 94954 47511 94954 47512 94954 47502 94955 47512 94955 47503 94955 47503 94956 47512 94956 47506 94956 47503 94957 47506 94957 47505 94957 47549 94958 47513 94958 47548 94958 47548 94959 47513 94959 47514 94959 47548 94960 47514 94960 47555 94960 47546 94961 47515 94961 47547 94961 47547 94962 47515 94962 47543 94962 47547 94963 47543 94963 47550 94963 47550 94964 47543 94964 47544 94964 47517 94965 47886 94965 47535 94965 47535 94966 47886 94966 47516 94966 47535 94967 47516 94967 47537 94967 47553 94968 47552 94968 47535 94968 47520 94969 47519 94969 47551 94969 47517 94970 47535 94970 47518 94970 47518 94971 47535 94971 47552 94971 47518 94972 47552 94972 47551 94972 47519 94973 47520 94973 47891 94973 47891 94974 47520 94974 47611 94974 47891 94975 47611 94975 47521 94975 47496 94976 47540 94976 47523 94976 47538 94977 47527 94977 47522 94977 47522 94978 47527 94978 47524 94978 47522 94979 47524 94979 47523 94979 47523 94980 47524 94980 47647 94980 47523 94981 47647 94981 47496 94981 47516 94982 47884 94982 47537 94982 47537 94983 47884 94983 47525 94983 47537 94984 47525 94984 47538 94984 47538 94985 47525 94985 47526 94985 47538 94986 47526 94986 47527 94986 47553 94987 47536 94987 47528 94987 47528 94988 47536 94988 47529 94988 47528 94989 47529 94989 47554 94989 47554 94990 47529 94990 47539 94990 47554 94991 47539 94991 47530 94991 47530 94992 47539 94992 47531 94992 47530 94993 47531 94993 47533 94993 47533 94994 47531 94994 47532 94994 47533 94995 47532 94995 47534 94995 47534 94996 47532 94996 47626 94996 47534 94997 47626 94997 47557 94997 47553 94998 47535 94998 47536 94998 47536 94999 47535 94999 47537 94999 47536 95000 47537 95000 47529 95000 47529 95001 47537 95001 47538 95001 47529 95002 47538 95002 47539 95002 47539 95003 47538 95003 47522 95003 47539 95004 47522 95004 47531 95004 47531 95005 47522 95005 47523 95005 47531 95006 47523 95006 47532 95006 47532 95007 47523 95007 47540 95007 47532 95008 47540 95008 47626 95008 47541 95009 47500 95009 47543 95009 47543 95010 47500 95010 47542 95010 47543 95011 47542 95011 47544 95011 47544 95012 47542 95012 47610 95012 47544 95013 47610 95013 47545 95013 47635 95014 47546 95014 47509 95014 47509 95015 47546 95015 47547 95015 47509 95016 47547 95016 47548 95016 47548 95017 47547 95017 47550 95017 47548 95018 47550 95018 47549 95018 47549 95019 47550 95019 47544 95019 47549 95020 47544 95020 47520 95020 47520 95021 47544 95021 47545 95021 47520 95022 47545 95022 47611 95022 47551 95023 47552 95023 47520 95023 47520 95024 47552 95024 47553 95024 47520 95025 47553 95025 47549 95025 47549 95026 47553 95026 47528 95026 47549 95027 47528 95027 47513 95027 47513 95028 47528 95028 47554 95028 47513 95029 47554 95029 47514 95029 47514 95030 47554 95030 47530 95030 47514 95031 47530 95031 47555 95031 47555 95032 47530 95032 47533 95032 47555 95033 47533 95033 47556 95033 47556 95034 47533 95034 47534 95034 47556 95035 47534 95035 47507 95035 47507 95036 47534 95036 47557 95036 47507 95037 47557 95037 47508 95037 47490 95038 47489 95038 47582 95038 47601 95039 47561 95039 47564 95039 47585 95040 47613 95040 47584 95040 47639 95041 47618 95041 47637 95041 47637 95042 47618 95042 47558 95042 47637 95043 47558 95043 47559 95043 47559 95044 47558 95044 47570 95044 47559 95045 47570 95045 47638 95045 47586 95046 47584 95046 47560 95046 47598 95047 47636 95047 47599 95047 47599 95048 47636 95048 47562 95048 47562 95049 47636 95049 47563 95049 47562 95050 47563 95050 47564 95050 47564 95051 47561 95051 47562 95051 47562 95052 47561 95052 47600 95052 47562 95053 47600 95053 47599 95053 47563 95054 47568 95054 47564 95054 47564 95055 47568 95055 47569 95055 47564 95056 47569 95056 47601 95056 47601 95057 47569 95057 47565 95057 47601 95058 47565 95058 47602 95058 47602 95059 47565 95059 47566 95059 47602 95060 47566 95060 47567 95060 47567 95061 47566 95061 47622 95061 47567 95062 47622 95062 47604 95062 47568 95063 47638 95063 47569 95063 47569 95064 47638 95064 47570 95064 47569 95065 47570 95065 47565 95065 47565 95066 47570 95066 47558 95066 47565 95067 47558 95067 47566 95067 47566 95068 47558 95068 47618 95068 47566 95069 47618 95069 47622 95069 47479 95070 47481 95070 47571 95070 47571 95071 47481 95071 47487 95071 47571 95072 47487 95072 47572 95072 47572 95073 47487 95073 47486 95073 47572 95074 47486 95074 47573 95074 47573 95075 47486 95075 47485 95075 47573 95076 47485 95076 47578 95076 47627 95077 47574 95077 47571 95077 47571 95078 47574 95078 47575 95078 47571 95079 47575 95079 47479 95079 47579 95080 47576 95080 47597 95080 47597 95081 47576 95081 47577 95081 47597 95082 47577 95082 47491 95082 47485 95083 47484 95083 47578 95083 47578 95084 47484 95084 47483 95084 47578 95085 47483 95085 47579 95085 47579 95086 47483 95086 47580 95086 47579 95087 47580 95087 47576 95087 47491 95088 47581 95088 47597 95088 47597 95089 47581 95089 47490 95089 47597 95090 47490 95090 47583 95090 47583 95091 47490 95091 47582 95091 47583 95092 47582 95092 47614 95092 47584 95093 47586 95093 47585 95093 47585 95094 47586 95094 47587 95094 47585 95095 47587 95095 47596 95095 47596 95096 47587 95096 47588 95096 47596 95097 47588 95097 47595 95097 47595 95098 47588 95098 47589 95098 47595 95099 47589 95099 47590 95099 47590 95100 47589 95100 47591 95100 47590 95101 47591 95101 47594 95101 47594 95102 47591 95102 47603 95102 47594 95103 47603 95103 47593 95103 47593 95104 47603 95104 47605 95104 47593 95105 47605 95105 47592 95105 47592 95106 47605 95106 47621 95106 47592 95107 47621 95107 47627 95107 47627 95108 47571 95108 47592 95108 47592 95109 47571 95109 47572 95109 47592 95110 47572 95110 47593 95110 47593 95111 47572 95111 47573 95111 47593 95112 47573 95112 47594 95112 47594 95113 47573 95113 47578 95113 47594 95114 47578 95114 47590 95114 47590 95115 47578 95115 47579 95115 47590 95116 47579 95116 47595 95116 47595 95117 47579 95117 47597 95117 47595 95118 47597 95118 47596 95118 47596 95119 47597 95119 47583 95119 47596 95120 47583 95120 47585 95120 47585 95121 47583 95121 47614 95121 47585 95122 47614 95122 47613 95122 47560 95123 47598 95123 47586 95123 47586 95124 47598 95124 47599 95124 47586 95125 47599 95125 47587 95125 47587 95126 47599 95126 47600 95126 47587 95127 47600 95127 47588 95127 47588 95128 47600 95128 47561 95128 47588 95129 47561 95129 47589 95129 47589 95130 47561 95130 47601 95130 47589 95131 47601 95131 47591 95131 47591 95132 47601 95132 47602 95132 47591 95133 47602 95133 47603 95133 47603 95134 47602 95134 47567 95134 47603 95135 47567 95135 47605 95135 47605 95136 47567 95136 47604 95136 47605 95137 47604 95137 47621 95137 47617 95138 47609 95138 47615 95138 47606 95139 47560 95139 47584 95139 47500 95140 47607 95140 47645 95140 47610 95141 47542 95141 47617 95141 47617 95142 47542 95142 47500 95142 47500 95143 47645 95143 47617 95143 47617 95144 47645 95144 47608 95144 47617 95145 47608 95145 47609 95145 47609 95146 47608 95146 47644 95146 47609 95147 47644 95147 47606 95147 47611 95148 47545 95148 47616 95148 47616 95149 47545 95149 47610 95149 47521 95150 47611 95150 47495 95150 47495 95151 47611 95151 47616 95151 47495 95152 47616 95152 47612 95152 47606 95153 47584 95153 47609 95153 47609 95154 47584 95154 47613 95154 47609 95155 47613 95155 47615 95155 47615 95156 47613 95156 47614 95156 47615 95157 47614 95157 47582 95157 47610 95158 47617 95158 47616 95158 47616 95159 47617 95159 47615 95159 47616 95160 47615 95160 47612 95160 47612 95161 47615 95161 47582 95161 47612 95162 47582 95162 47489 95162 47574 95163 47627 95163 47623 95163 47642 95164 47643 95164 47619 95164 47639 95165 47640 95165 47618 95165 47618 95166 47640 95166 47620 95166 47504 95167 47505 95167 47631 95167 47631 95168 47505 95168 47643 95168 47629 95169 47628 95169 47625 95169 47625 95170 47628 95170 47620 95170 47643 95171 47505 95171 47619 95171 47619 95172 47505 95172 47506 95172 47619 95173 47506 95173 47624 95173 47640 95174 47642 95174 47620 95174 47620 95175 47642 95175 47619 95175 47620 95176 47619 95176 47625 95176 47625 95177 47619 95177 47624 95177 47627 95178 47621 95178 47628 95178 47628 95179 47621 95179 47604 95179 47628 95180 47604 95180 47620 95180 47620 95181 47604 95181 47622 95181 47620 95182 47622 95182 47618 95182 47630 95183 47499 95183 47623 95183 47623 95184 47499 95184 47575 95184 47623 95185 47575 95185 47574 95185 47624 95186 47508 95186 47625 95186 47625 95187 47508 95187 47557 95187 47625 95188 47557 95188 47629 95188 47629 95189 47557 95189 47626 95189 47629 95190 47626 95190 47540 95190 47627 95191 47628 95191 47623 95191 47623 95192 47628 95192 47629 95192 47623 95193 47629 95193 47630 95193 47630 95194 47629 95194 47540 95194 47630 95195 47540 95195 47496 95195 47634 95196 47504 95196 47631 95196 47634 95197 47635 95197 47632 95197 47632 95198 47501 95198 47634 95198 47634 95199 47501 95199 47633 95199 47634 95200 47633 95200 47504 95200 47541 95201 47515 95201 47634 95201 47634 95202 47515 95202 47546 95202 47634 95203 47546 95203 47635 95203 47641 95204 47560 95204 47606 95204 47598 95205 47560 95205 47636 95205 47636 95206 47560 95206 47641 95206 47636 95207 47641 95207 47563 95207 47639 95208 47637 95208 47641 95208 47641 95209 47637 95209 47559 95209 47559 95210 47638 95210 47641 95210 47641 95211 47638 95211 47568 95211 47641 95212 47568 95212 47563 95212 47639 95213 47641 95213 47640 95213 47640 95214 47641 95214 47606 95214 47640 95215 47606 95215 47642 95215 47642 95216 47606 95216 47644 95216 47642 95217 47644 95217 47643 95217 47643 95218 47644 95218 47608 95218 47643 95219 47608 95219 47631 95219 47631 95220 47608 95220 47645 95220 47631 95221 47645 95221 47634 95221 47634 95222 47645 95222 47607 95222 47634 95223 47607 95223 47541 95223 47647 95224 47524 95224 47893 95224 47893 95225 47646 95225 47647 95225 47647 95226 47646 95226 47861 95226 47647 95227 47861 95227 47496 95227 47893 95228 47864 95228 47646 95228 47646 95229 47864 95229 47677 95229 47646 95230 47677 95230 47861 95230 47861 95231 47677 95231 47676 95231 47754 95232 47648 95232 47650 95232 47650 95233 47648 95233 47649 95233 47650 95234 47649 95234 47651 95234 47651 95235 47649 95235 47752 95235 47651 95236 47752 95236 47652 95236 47652 95237 47752 95237 47744 95237 47652 95238 47744 95238 47663 95238 47663 95239 47744 95239 47653 95239 47663 95240 47653 95240 47671 95240 47671 95241 47653 95241 47654 95241 47754 95242 47650 95242 47755 95242 47755 95243 47650 95243 47661 95243 47755 95244 47661 95244 47751 95244 47751 95245 47661 95245 47660 95245 47751 95246 47660 95246 47655 95246 47655 95247 47660 95247 47656 95247 47655 95248 47656 95248 47657 95248 47657 95249 47656 95249 47658 95249 47657 95250 47658 95250 47748 95250 47882 95251 47658 95251 47659 95251 47659 95252 47658 95252 47656 95252 47659 95253 47656 95253 47858 95253 47858 95254 47656 95254 47660 95254 47858 95255 47660 95255 47675 95255 47675 95256 47660 95256 47661 95256 47675 95257 47661 95257 47674 95257 47674 95258 47661 95258 47650 95258 47674 95259 47650 95259 47662 95259 47671 95260 47685 95260 47663 95260 47663 95261 47685 95261 47664 95261 47663 95262 47664 95262 47652 95262 47652 95263 47664 95263 47662 95263 47652 95264 47662 95264 47651 95264 47651 95265 47662 95265 47650 95265 47683 95266 47724 95266 47681 95266 47681 95267 47724 95267 47705 95267 47681 95268 47705 95268 47680 95268 47705 95269 47708 95269 47680 95269 47680 95270 47708 95270 47665 95270 47680 95271 47665 95271 47679 95271 47679 95272 47665 95272 47666 95272 47679 95273 47666 95273 47667 95273 47667 95274 47666 95274 47703 95274 47667 95275 47703 95275 47670 95275 47670 95276 47703 95276 47700 95276 47670 95277 47700 95277 47668 95277 47687 95278 47686 95278 47699 95278 47699 95279 47686 95279 47669 95279 47699 95280 47669 95280 47668 95280 47668 95281 47669 95281 47860 95281 47668 95282 47860 95282 47670 95282 47693 95283 47695 95283 47671 95283 47671 95284 47695 95284 47685 95284 47662 95285 47664 95285 47672 95285 47672 95286 47664 95286 47862 95286 47879 95287 47858 95287 47675 95287 47672 95288 47673 95288 47662 95288 47662 95289 47673 95289 47874 95289 47662 95290 47874 95290 47674 95290 47674 95291 47874 95291 47877 95291 47674 95292 47877 95292 47675 95292 47675 95293 47877 95293 47880 95293 47675 95294 47880 95294 47879 95294 47679 95295 47667 95295 47866 95295 47860 95296 47676 95296 47670 95296 47670 95297 47676 95297 47677 95297 47670 95298 47677 95298 47667 95298 47667 95299 47677 95299 47864 95299 47667 95300 47864 95300 47866 95300 47866 95301 47678 95301 47679 95301 47679 95302 47678 95302 47870 95302 47679 95303 47870 95303 47680 95303 47680 95304 47870 95304 47869 95304 47680 95305 47869 95305 47681 95305 47681 95306 47869 95306 47682 95306 47681 95307 47682 95307 47683 95307 47683 95308 47682 95308 47684 95308 47683 95309 47684 95309 47694 95309 47694 95310 47684 95310 47863 95310 47694 95311 47863 95311 47695 95311 47695 95312 47863 95312 47862 95312 47695 95313 47862 95313 47685 95313 47685 95314 47862 95314 47664 95314 47686 95315 47687 95315 47690 95315 47686 95316 47690 95316 47688 95316 47688 95317 47690 95317 47658 95317 47688 95318 47658 95318 47882 95318 47748 95319 47658 95319 47689 95319 47689 95320 47658 95320 47690 95320 47689 95321 47690 95321 47713 95321 47687 95322 47691 95322 47690 95322 47690 95323 47691 95323 47692 95323 47690 95324 47692 95324 47713 95324 47724 95325 47683 95325 47725 95325 47725 95326 47683 95326 47694 95326 47725 95327 47694 95327 47693 95327 47693 95328 47694 95328 47695 95328 47696 95329 47693 95329 47697 95329 47697 95330 47693 95330 47671 95330 47697 95331 47671 95331 47654 95331 47691 95332 47687 95332 47698 95332 47698 95333 47687 95333 47699 95333 47698 95334 47699 95334 47801 95334 47801 95335 47699 95335 47668 95335 47801 95336 47668 95336 47802 95336 47802 95337 47668 95337 47700 95337 47802 95338 47700 95338 47701 95338 47701 95339 47700 95339 47703 95339 47701 95340 47703 95340 47702 95340 47702 95341 47703 95341 47805 95341 47805 95342 47703 95342 47806 95342 47806 95343 47703 95343 47666 95343 47806 95344 47666 95344 47704 95344 47724 95345 47782 95345 47705 95345 47705 95346 47782 95346 47781 95346 47705 95347 47781 95347 47708 95347 47781 95348 47706 95348 47708 95348 47708 95349 47706 95349 47707 95349 47708 95350 47707 95350 47665 95350 47665 95351 47707 95351 47709 95351 47665 95352 47709 95352 47666 95352 47666 95353 47709 95353 47808 95353 47666 95354 47808 95354 47704 95354 47710 95355 47711 95355 47722 95355 47711 95356 47710 95356 47797 95356 47712 95357 47714 95357 47717 95357 47749 95358 47748 95358 47689 95358 47764 95359 47763 95359 47712 95359 47712 95360 47763 95360 47749 95360 47749 95361 47689 95361 47712 95361 47712 95362 47689 95362 47713 95362 47712 95363 47713 95363 47714 95363 47714 95364 47713 95364 47692 95364 47714 95365 47692 95365 47691 95365 47735 95366 47736 95366 47715 95366 47715 95367 47736 95367 47764 95367 47691 95368 47716 95368 47714 95368 47714 95369 47716 95369 47819 95369 47714 95370 47819 95370 47717 95370 47717 95371 47819 95371 47818 95371 47717 95372 47818 95372 47831 95372 47719 95373 47735 95373 47720 95373 47720 95374 47735 95374 47715 95374 47720 95375 47715 95375 47710 95375 47764 95376 47712 95376 47715 95376 47715 95377 47712 95377 47717 95377 47715 95378 47717 95378 47710 95378 47710 95379 47717 95379 47831 95379 47710 95380 47831 95380 47797 95380 47718 95381 47719 95381 47832 95381 47832 95382 47719 95382 47720 95382 47832 95383 47720 95383 47721 95383 47721 95384 47720 95384 47710 95384 47721 95385 47710 95385 47843 95385 47843 95386 47710 95386 47722 95386 47782 95387 47724 95387 47723 95387 47723 95388 47724 95388 47725 95388 47723 95389 47725 95389 47726 95389 47726 95390 47725 95390 47727 95390 47727 95391 47725 95391 47693 95391 47727 95392 47693 95392 47696 95392 47737 95393 47733 95393 47728 95393 47834 95394 47729 95394 47730 95394 47834 95395 47730 95395 47835 95395 47731 95396 47732 95396 47733 95396 47733 95397 47732 95397 47734 95397 47733 95398 47734 95398 47728 95398 47728 95399 47734 95399 47836 95399 47728 95400 47836 95400 47743 95400 47719 95401 47739 95401 47735 95401 47735 95402 47739 95402 47738 95402 47735 95403 47738 95403 47736 95403 47736 95404 47738 95404 47780 95404 47779 95405 47780 95405 47737 95405 47737 95406 47780 95406 47738 95406 47737 95407 47738 95407 47733 95407 47733 95408 47738 95408 47739 95408 47733 95409 47739 95409 47731 95409 47731 95410 47739 95410 47719 95410 47731 95411 47719 95411 47718 95411 47770 95412 47730 95412 47740 95412 47740 95413 47730 95413 47729 95413 47740 95414 47729 95414 47772 95414 47779 95415 47737 95415 47741 95415 47741 95416 47737 95416 47728 95416 47741 95417 47728 95417 47742 95417 47742 95418 47728 95418 47743 95418 47742 95419 47743 95419 47776 95419 47776 95420 47743 95420 47747 95420 47776 95421 47747 95421 47775 95421 47765 95422 47744 95422 47752 95422 47765 95423 47752 95423 47766 95423 47653 95424 47744 95424 47745 95424 47745 95425 47744 95425 47765 95425 47745 95426 47765 95426 47774 95426 47697 95427 47654 95427 47773 95427 47773 95428 47654 95428 47653 95428 47836 95429 47746 95429 47743 95429 47743 95430 47746 95430 47835 95430 47743 95431 47835 95431 47747 95431 47747 95432 47835 95432 47730 95432 47747 95433 47730 95433 47775 95433 47775 95434 47730 95434 47770 95434 47775 95435 47770 95435 47773 95435 47748 95436 47749 95436 47750 95436 47748 95437 47750 95437 47657 95437 47657 95438 47750 95438 47767 95438 47657 95439 47767 95439 47655 95439 47655 95440 47767 95440 47751 95440 47751 95441 47767 95441 47753 95441 47751 95442 47753 95442 47755 95442 47752 95443 47649 95443 47766 95443 47766 95444 47649 95444 47648 95444 47766 95445 47648 95445 47753 95445 47753 95446 47648 95446 47754 95446 47753 95447 47754 95447 47755 95447 47774 95448 47756 95448 47757 95448 47757 95449 47756 95449 47758 95449 47757 95450 47758 95450 47777 95450 47777 95451 47758 95451 47759 95451 47777 95452 47759 95452 47761 95452 47761 95453 47759 95453 47760 95453 47761 95454 47760 95454 47778 95454 47778 95455 47760 95455 47768 95455 47778 95456 47768 95456 47762 95456 47762 95457 47768 95457 47763 95457 47762 95458 47763 95458 47764 95458 47774 95459 47765 95459 47756 95459 47756 95460 47765 95460 47766 95460 47756 95461 47766 95461 47758 95461 47758 95462 47766 95462 47753 95462 47758 95463 47753 95463 47759 95463 47759 95464 47753 95464 47767 95464 47759 95465 47767 95465 47760 95465 47760 95466 47767 95466 47750 95466 47760 95467 47750 95467 47768 95467 47768 95468 47750 95468 47749 95468 47768 95469 47749 95469 47763 95469 47696 95470 47697 95470 47769 95470 47769 95471 47697 95471 47773 95471 47769 95472 47773 95472 47857 95472 47857 95473 47773 95473 47770 95473 47857 95474 47770 95474 47771 95474 47771 95475 47770 95475 47740 95475 47771 95476 47740 95476 47848 95476 47848 95477 47740 95477 47772 95477 47848 95478 47772 95478 47849 95478 47653 95479 47745 95479 47773 95479 47773 95480 47745 95480 47774 95480 47773 95481 47774 95481 47775 95481 47775 95482 47774 95482 47757 95482 47775 95483 47757 95483 47776 95483 47776 95484 47757 95484 47777 95484 47776 95485 47777 95485 47742 95485 47742 95486 47777 95486 47761 95486 47742 95487 47761 95487 47741 95487 47741 95488 47761 95488 47778 95488 47741 95489 47778 95489 47779 95489 47779 95490 47778 95490 47762 95490 47779 95491 47762 95491 47780 95491 47780 95492 47762 95492 47764 95492 47780 95493 47764 95493 47736 95493 47781 95494 47782 95494 47809 95494 47794 95495 47790 95495 47788 95495 47783 95496 47852 95496 47851 95496 47842 95497 47841 95497 47799 95497 47799 95498 47841 95498 47784 95498 47799 95499 47784 95499 47785 95499 47785 95500 47784 95500 47722 95500 47785 95501 47722 95501 47711 95501 47827 95502 47851 95502 47786 95502 47838 95503 47839 95503 47791 95503 47791 95504 47839 95504 47787 95504 47791 95505 47787 95505 47789 95505 47789 95506 47787 95506 47840 95506 47789 95507 47840 95507 47788 95507 47788 95508 47790 95508 47789 95508 47789 95509 47790 95509 47828 95509 47789 95510 47828 95510 47791 95510 47840 95511 47792 95511 47788 95511 47788 95512 47792 95512 47793 95512 47788 95513 47793 95513 47794 95513 47794 95514 47793 95514 47798 95514 47794 95515 47798 95515 47795 95515 47795 95516 47798 95516 47800 95516 47795 95517 47800 95517 47796 95517 47796 95518 47800 95518 47797 95518 47796 95519 47797 95519 47831 95519 47792 95520 47842 95520 47793 95520 47793 95521 47842 95521 47799 95521 47793 95522 47799 95522 47798 95522 47798 95523 47799 95523 47785 95523 47798 95524 47785 95524 47800 95524 47800 95525 47785 95525 47711 95525 47800 95526 47711 95526 47797 95526 47698 95527 47801 95527 47803 95527 47803 95528 47801 95528 47802 95528 47803 95529 47802 95529 47822 95529 47822 95530 47802 95530 47701 95530 47822 95531 47701 95531 47823 95531 47823 95532 47701 95532 47702 95532 47823 95533 47702 95533 47824 95533 47819 95534 47716 95534 47803 95534 47803 95535 47716 95535 47691 95535 47803 95536 47691 95536 47698 95536 47807 95537 47808 95537 47804 95537 47804 95538 47808 95538 47709 95538 47804 95539 47709 95539 47707 95539 47702 95540 47805 95540 47824 95540 47824 95541 47805 95541 47806 95541 47824 95542 47806 95542 47807 95542 47807 95543 47806 95543 47704 95543 47807 95544 47704 95544 47808 95544 47707 95545 47706 95545 47804 95545 47804 95546 47706 95546 47781 95546 47804 95547 47781 95547 47826 95547 47826 95548 47781 95548 47809 95548 47826 95549 47809 95549 47810 95549 47851 95550 47827 95550 47783 95550 47783 95551 47827 95551 47811 95551 47783 95552 47811 95552 47812 95552 47812 95553 47811 95553 47829 95553 47812 95554 47829 95554 47813 95554 47813 95555 47829 95555 47814 95555 47813 95556 47814 95556 47825 95556 47825 95557 47814 95557 47830 95557 47825 95558 47830 95558 47815 95558 47815 95559 47830 95559 47816 95559 47815 95560 47816 95560 47821 95560 47821 95561 47816 95561 47817 95561 47821 95562 47817 95562 47820 95562 47820 95563 47817 95563 47818 95563 47820 95564 47818 95564 47819 95564 47819 95565 47803 95565 47820 95565 47820 95566 47803 95566 47822 95566 47820 95567 47822 95567 47821 95567 47821 95568 47822 95568 47823 95568 47821 95569 47823 95569 47815 95569 47815 95570 47823 95570 47824 95570 47815 95571 47824 95571 47825 95571 47825 95572 47824 95572 47807 95572 47825 95573 47807 95573 47813 95573 47813 95574 47807 95574 47804 95574 47813 95575 47804 95575 47812 95575 47812 95576 47804 95576 47826 95576 47812 95577 47826 95577 47783 95577 47783 95578 47826 95578 47810 95578 47783 95579 47810 95579 47852 95579 47786 95580 47838 95580 47827 95580 47827 95581 47838 95581 47791 95581 47827 95582 47791 95582 47811 95582 47811 95583 47791 95583 47828 95583 47811 95584 47828 95584 47829 95584 47829 95585 47828 95585 47790 95585 47829 95586 47790 95586 47814 95586 47814 95587 47790 95587 47794 95587 47814 95588 47794 95588 47830 95588 47830 95589 47794 95589 47795 95589 47830 95590 47795 95590 47816 95590 47816 95591 47795 95591 47796 95591 47816 95592 47796 95592 47817 95592 47817 95593 47796 95593 47831 95593 47817 95594 47831 95594 47818 95594 47837 95595 47786 95595 47850 95595 47833 95596 47718 95596 47832 95596 47731 95597 47718 95597 47732 95597 47732 95598 47718 95598 47833 95598 47732 95599 47833 95599 47734 95599 47734 95600 47833 95600 47836 95600 47772 95601 47729 95601 47833 95601 47833 95602 47729 95602 47834 95602 47834 95603 47835 95603 47833 95603 47833 95604 47835 95604 47746 95604 47833 95605 47746 95605 47836 95605 47842 95606 47792 95606 47837 95606 47837 95607 47792 95607 47840 95607 47838 95608 47786 95608 47839 95608 47839 95609 47786 95609 47837 95609 47839 95610 47837 95610 47787 95610 47787 95611 47837 95611 47840 95611 47722 95612 47784 95612 47837 95612 47837 95613 47784 95613 47841 95613 47837 95614 47841 95614 47842 95614 47722 95615 47837 95615 47843 95615 47843 95616 47837 95616 47850 95616 47843 95617 47850 95617 47721 95617 47721 95618 47850 95618 47844 95618 47721 95619 47844 95619 47832 95619 47832 95620 47844 95620 47845 95620 47832 95621 47845 95621 47833 95621 47833 95622 47845 95622 47849 95622 47833 95623 47849 95623 47772 95623 47809 95624 47782 95624 47723 95624 47852 95625 47810 95625 47846 95625 47769 95626 47857 95626 47847 95626 47771 95627 47848 95627 47856 95627 47848 95628 47849 95628 47856 95628 47856 95629 47849 95629 47845 95629 47856 95630 47845 95630 47854 95630 47854 95631 47845 95631 47844 95631 47854 95632 47844 95632 47853 95632 47853 95633 47844 95633 47850 95633 47853 95634 47850 95634 47851 95634 47851 95635 47850 95635 47786 95635 47851 95636 47852 95636 47853 95636 47853 95637 47852 95637 47846 95637 47853 95638 47846 95638 47854 95638 47854 95639 47846 95639 47855 95639 47854 95640 47855 95640 47856 95640 47856 95641 47855 95641 47847 95641 47856 95642 47847 95642 47771 95642 47771 95643 47847 95643 47857 95643 47810 95644 47809 95644 47846 95644 47846 95645 47809 95645 47723 95645 47846 95646 47723 95646 47855 95646 47855 95647 47723 95647 47726 95647 47855 95648 47726 95648 47847 95648 47847 95649 47726 95649 47727 95649 47847 95650 47727 95650 47769 95650 47769 95651 47727 95651 47696 95651 47858 95652 47879 95652 47878 95652 47858 95653 47878 95653 47859 95653 47878 95654 47498 95654 47859 95654 47859 95655 47498 95655 47497 95655 47859 95656 47497 95656 47883 95656 47883 95657 47497 95657 47860 95657 47860 95658 47497 95658 47861 95658 47860 95659 47861 95659 47676 95659 47488 95660 47862 95660 47493 95660 47493 95661 47862 95661 47863 95661 47493 95662 47863 95662 47494 95662 47494 95663 47863 95663 47684 95663 47494 95664 47684 95664 47890 95664 47890 95665 47684 95665 47682 95665 47866 95666 47864 95666 47893 95666 47893 95667 47865 95667 47866 95667 47866 95668 47865 95668 47892 95668 47866 95669 47892 95669 47678 95669 47678 95670 47892 95670 47885 95670 47885 95671 47867 95671 47678 95671 47678 95672 47867 95672 47887 95672 47678 95673 47887 95673 47870 95673 47890 95674 47682 95674 47889 95674 47889 95675 47682 95675 47869 95675 47889 95676 47869 95676 47868 95676 47868 95677 47869 95677 47870 95677 47868 95678 47870 95678 47888 95678 47888 95679 47870 95679 47887 95679 47672 95680 47862 95680 47488 95680 47871 95681 47874 95681 47673 95681 47488 95682 47872 95682 47672 95682 47672 95683 47872 95683 47873 95683 47672 95684 47873 95684 47673 95684 47673 95685 47873 95685 47492 95685 47673 95686 47492 95686 47871 95686 47871 95687 47875 95687 47874 95687 47874 95688 47875 95688 47876 95688 47874 95689 47876 95689 47877 95689 47878 95690 47879 95690 47480 95690 47480 95691 47879 95691 47880 95691 47480 95692 47880 95692 47482 95692 47482 95693 47880 95693 47877 95693 47482 95694 47877 95694 47881 95694 47881 95695 47877 95695 47876 95695 47883 95696 47860 95696 47669 95696 47659 95697 47858 95697 47882 95697 47882 95698 47858 95698 47859 95698 47882 95699 47859 95699 47688 95699 47688 95700 47859 95700 47883 95700 47688 95701 47883 95701 47686 95701 47686 95702 47883 95702 47669 95702 47884 95703 47516 95703 47885 95703 47885 95704 47516 95704 47867 95704 47867 95705 47516 95705 47886 95705 47867 95706 47886 95706 47887 95706 47887 95707 47886 95707 47517 95707 47887 95708 47517 95708 47888 95708 47888 95709 47517 95709 47518 95709 47888 95710 47518 95710 47868 95710 47868 95711 47518 95711 47551 95711 47868 95712 47551 95712 47889 95712 47889 95713 47551 95713 47519 95713 47889 95714 47519 95714 47890 95714 47890 95715 47519 95715 47891 95715 47890 95716 47891 95716 47521 95716 47884 95717 47885 95717 47525 95717 47525 95718 47885 95718 47892 95718 47525 95719 47892 95719 47526 95719 47526 95720 47892 95720 47865 95720 47526 95721 47865 95721 47527 95721 47527 95722 47865 95722 47893 95722 47527 95723 47893 95723 47524 95723 47901 95724 47911 95724 47902 95724 47897 95725 48213 95725 48197 95725 47894 95726 48213 95726 47895 95726 47895 95727 48213 95727 47897 95727 47895 95728 47897 95728 48210 95728 48210 95729 47897 95729 48243 95729 48242 95730 47896 95730 47897 95730 47897 95731 47896 95731 48208 95731 48208 95732 48245 95732 47897 95732 47897 95733 48245 95733 48244 95733 47897 95734 48244 95734 48243 95734 47898 95735 47899 95735 47901 95735 47901 95736 47899 95736 48261 95736 48298 95737 47911 95737 47900 95737 47900 95738 47911 95738 47901 95738 47900 95739 47901 95739 48260 95739 48260 95740 47901 95740 48261 95740 48201 95741 48258 95741 47901 95741 47901 95742 48258 95742 48256 95742 47901 95743 48256 95743 47898 95743 48201 95744 47901 95744 48200 95744 48200 95745 47901 95745 47902 95745 48200 95746 47902 95746 48198 95746 48198 95747 47902 95747 47910 95747 48198 95748 47910 95748 48197 95748 48197 95749 47910 95749 47903 95749 48197 95750 47903 95750 47897 95750 47897 95751 47903 95751 47904 95751 47897 95752 47904 95752 48242 95752 47915 95753 48202 95753 48203 95753 47912 95754 48296 95754 47916 95754 47905 95755 48249 95755 47906 95755 47914 95756 47907 95756 47908 95756 47907 95757 47904 95757 47908 95757 47908 95758 47904 95758 47903 95758 47908 95759 47903 95759 47909 95759 47909 95760 47903 95760 47910 95760 47909 95761 47910 95761 47913 95761 47913 95762 47910 95762 47902 95762 47913 95763 47902 95763 48279 95763 48279 95764 47902 95764 47911 95764 48279 95765 47912 95765 47913 95765 47913 95766 47912 95766 47916 95766 47913 95767 47916 95767 47909 95767 47909 95768 47916 95768 47917 95768 47909 95769 47917 95769 47908 95769 47908 95770 47917 95770 47906 95770 47908 95771 47906 95771 47914 95771 47914 95772 47906 95772 48249 95772 48296 95773 47915 95773 47916 95773 47916 95774 47915 95774 48203 95774 47916 95775 48203 95775 47917 95775 47917 95776 48203 95776 48205 95776 47917 95777 48205 95777 47906 95777 47906 95778 48205 95778 48204 95778 47906 95779 48204 95779 47905 95779 47905 95780 48204 95780 48215 95780 48121 95781 48135 95781 47944 95781 48121 95782 47944 95782 47918 95782 47944 95783 47919 95783 47918 95783 47918 95784 47919 95784 47920 95784 47918 95785 47920 95785 47934 95785 47934 95786 47920 95786 48141 95786 48141 95787 47920 95787 47921 95787 48141 95788 47921 95788 48142 95788 47961 95789 47922 95789 47923 95789 47923 95790 47922 95790 48154 95790 47923 95791 48154 95791 47924 95791 47924 95792 48154 95792 47925 95792 47924 95793 47925 95793 47962 95793 47962 95794 47925 95794 47927 95794 48147 95795 48114 95795 48109 95795 48109 95796 47942 95796 48147 95796 48147 95797 47942 95797 47940 95797 48147 95798 47940 95798 48148 95798 48148 95799 47940 95799 47939 95799 47962 95800 47927 95800 47926 95800 47926 95801 47927 95801 48149 95801 47926 95802 48149 95802 47936 95802 47936 95803 48149 95803 48148 95803 47936 95804 48148 95804 47928 95804 47928 95805 48148 95805 47939 95805 47922 95806 47961 95806 48136 95806 48136 95807 47961 95807 47953 95807 48136 95808 47953 95808 48137 95808 47953 95809 47955 95809 48137 95809 48137 95810 47955 95810 47957 95810 48137 95811 47957 95811 48138 95811 48138 95812 47957 95812 47958 95812 48138 95813 47958 95813 48139 95813 48139 95814 47958 95814 47929 95814 48139 95815 47929 95815 47931 95815 47944 95816 48135 95816 47945 95816 47945 95817 48135 95817 47930 95817 47945 95818 47930 95818 47932 95818 47932 95819 47930 95819 47931 95819 47932 95820 47931 95820 47947 95820 47947 95821 47931 95821 47929 95821 47934 95822 48141 95822 47935 95822 47933 95823 48121 95823 48160 95823 48160 95824 48121 95824 47918 95824 48160 95825 47918 95825 48158 95825 48158 95826 47918 95826 47934 95826 48158 95827 47934 95827 48133 95827 48133 95828 47934 95828 47935 95828 47989 95829 47962 95829 48014 95829 48014 95830 47962 95830 47926 95830 48014 95831 47926 95831 47936 95831 47987 95832 47986 95832 47928 95832 47928 95833 47986 95833 47937 95833 47928 95834 47937 95834 47936 95834 47936 95835 47937 95835 47938 95835 47936 95836 47938 95836 48014 95836 47928 95837 47939 95837 47987 95837 47987 95838 47939 95838 47940 95838 47987 95839 47940 95839 47941 95839 47941 95840 47940 95840 47942 95840 47941 95841 47942 95841 47993 95841 47993 95842 47942 95842 48109 95842 47993 95843 48109 95843 47994 95843 47943 95844 47944 95844 48040 95844 48040 95845 47944 95845 47945 95845 48040 95846 47945 95846 48041 95846 48041 95847 47945 95847 47932 95847 48041 95848 47932 95848 47946 95848 47946 95849 47932 95849 47947 95849 47946 95850 47947 95850 48042 95850 48042 95851 47947 95851 47929 95851 48042 95852 47929 95852 47948 95852 47948 95853 47929 95853 47949 95853 47949 95854 47929 95854 47950 95854 47950 95855 47929 95855 47958 95855 47950 95856 47958 95856 47951 95856 47961 95857 47952 95857 47953 95857 47953 95858 47952 95858 47954 95858 47953 95859 47954 95859 47955 95859 47954 95860 48047 95860 47955 95860 47955 95861 48047 95861 48045 95861 47955 95862 48045 95862 47957 95862 47957 95863 48045 95863 47956 95863 47957 95864 47956 95864 47958 95864 47958 95865 47956 95865 47959 95865 47958 95866 47959 95866 47951 95866 47952 95867 47961 95867 47960 95867 47960 95868 47961 95868 47923 95868 47960 95869 47923 95869 48074 95869 48074 95870 47923 95870 47924 95870 48074 95871 47924 95871 47989 95871 47989 95872 47924 95872 47962 95872 47963 95873 47921 95873 47920 95873 47963 95874 47920 95874 47964 95874 47964 95875 47920 95875 47919 95875 47964 95876 47919 95876 47965 95876 47965 95877 47919 95877 47944 95877 47965 95878 47944 95878 47943 95878 48100 95879 48108 95879 47966 95879 47983 95880 48100 95880 47967 95880 48098 95881 47974 95881 48099 95881 48099 95882 47974 95882 47976 95882 48099 95883 47976 95883 47968 95883 47968 95884 47976 95884 47977 95884 47968 95885 47977 95885 47969 95885 47969 95886 47977 95886 47979 95886 47975 95887 48087 95887 47978 95887 48019 95888 47970 95888 47971 95888 47971 95889 47970 95889 48020 95889 47971 95890 48020 95890 47975 95890 47975 95891 48020 95891 47972 95891 47975 95892 47972 95892 48087 95892 47980 95893 47974 95893 47973 95893 47973 95894 47974 95894 48098 95894 47973 95895 48098 95895 48010 95895 47980 95896 48019 95896 47974 95896 47974 95897 48019 95897 47971 95897 47974 95898 47971 95898 47976 95898 47976 95899 47971 95899 47975 95899 47976 95900 47975 95900 47977 95900 47977 95901 47975 95901 47978 95901 47977 95902 47978 95902 47979 95902 48016 95903 48018 95903 47980 95903 47980 95904 48018 95904 47981 95904 47980 95905 47981 95905 48019 95905 47982 95906 47983 95906 48011 95906 48011 95907 47983 95907 47967 95907 48011 95908 47967 95908 47984 95908 47984 95909 47967 95909 48012 95909 47987 95910 47941 95910 47985 95910 47985 95911 47941 95911 48005 95911 47997 95912 48015 95912 47985 95912 48014 95913 47938 95913 48015 95913 48015 95914 47938 95914 47937 95914 48015 95915 47937 95915 47985 95915 47985 95916 47937 95916 47986 95916 47985 95917 47986 95917 47987 95917 47988 95918 47989 95918 48013 95918 48013 95919 47989 95919 48014 95919 47963 95920 47990 95920 48113 95920 48113 95921 47990 95921 47991 95921 48113 95922 47991 95922 48111 95922 48111 95923 47991 95923 47992 95923 47941 95924 47993 95924 48005 95924 48005 95925 47993 95925 47994 95925 48005 95926 47994 95926 48006 95926 48006 95927 47994 95927 47995 95927 48006 95928 47995 95928 47992 95928 47992 95929 47995 95929 47996 95929 47992 95930 47996 95930 48111 95930 47997 95931 48004 95931 47998 95931 47998 95932 48004 95932 48007 95932 47998 95933 48007 95933 48017 95933 48017 95934 48007 95934 47999 95934 48017 95935 47999 95935 48000 95935 48000 95936 47999 95936 48001 95936 48000 95937 48001 95937 48002 95937 48002 95938 48001 95938 48008 95938 48002 95939 48008 95939 48003 95939 48003 95940 48008 95940 48096 95940 48003 95941 48096 95941 48021 95941 47997 95942 47985 95942 48004 95942 48004 95943 47985 95943 48005 95943 48004 95944 48005 95944 48007 95944 48007 95945 48005 95945 48006 95945 48007 95946 48006 95946 47999 95946 47999 95947 48006 95947 47992 95947 47999 95948 47992 95948 48001 95948 48001 95949 47992 95949 47991 95949 48001 95950 47991 95950 48008 95950 48008 95951 47991 95951 47990 95951 48008 95952 47990 95952 48096 95952 48100 95953 47966 95953 47967 95953 47967 95954 47966 95954 48009 95954 47967 95955 48009 95955 48012 95955 48012 95956 48009 95956 48073 95956 48012 95957 48073 95957 48072 95957 48010 95958 47982 95958 47973 95958 47973 95959 47982 95959 48011 95959 47973 95960 48011 95960 47980 95960 47980 95961 48011 95961 47984 95961 47980 95962 47984 95962 48016 95962 48016 95963 47984 95963 48012 95963 48016 95964 48012 95964 48013 95964 48013 95965 48012 95965 48072 95965 48013 95966 48072 95966 47988 95966 48014 95967 48015 95967 48013 95967 48013 95968 48015 95968 47997 95968 48013 95969 47997 95969 48016 95969 48016 95970 47997 95970 47998 95970 48016 95971 47998 95971 48018 95971 48018 95972 47998 95972 48017 95972 48018 95973 48017 95973 47981 95973 47981 95974 48017 95974 48000 95974 47981 95975 48000 95975 48019 95975 48019 95976 48000 95976 48002 95976 48019 95977 48002 95977 47970 95977 47970 95978 48002 95978 48003 95978 47970 95979 48003 95979 48020 95979 48020 95980 48003 95980 48021 95980 48020 95981 48021 95981 47972 95981 47954 95982 47952 95982 48080 95982 48033 95983 48067 95983 48031 95983 48048 95984 48077 95984 48026 95984 48022 95985 48092 95985 48023 95985 48023 95986 48092 95986 48039 95986 48023 95987 48039 95987 48024 95987 48024 95988 48039 95988 48036 95988 48024 95989 48036 95989 48025 95989 48064 95990 48026 95990 48101 95990 48027 95991 48029 95991 48032 95991 48032 95992 48029 95992 48028 95992 48028 95993 48029 95993 48030 95993 48028 95994 48030 95994 48031 95994 48031 95995 48067 95995 48028 95995 48028 95996 48067 95996 48065 95996 48028 95997 48065 95997 48032 95997 48030 95998 48104 95998 48031 95998 48031 95999 48104 95999 48035 95999 48031 96000 48035 96000 48033 96000 48033 96001 48035 96001 48037 96001 48033 96002 48037 96002 48034 96002 48034 96003 48037 96003 48038 96003 48034 96004 48038 96004 48068 96004 48068 96005 48038 96005 48091 96005 48068 96006 48091 96006 48089 96006 48104 96007 48025 96007 48035 96007 48035 96008 48025 96008 48036 96008 48035 96009 48036 96009 48037 96009 48037 96010 48036 96010 48039 96010 48037 96011 48039 96011 48038 96011 48038 96012 48039 96012 48092 96012 48038 96013 48092 96013 48091 96013 48040 96014 48041 96014 48056 96014 48056 96015 48041 96015 47946 96015 48056 96016 47946 96016 48057 96016 48057 96017 47946 96017 48042 96017 48057 96018 48042 96018 48043 96018 48043 96019 48042 96019 47948 96019 48043 96020 47948 96020 48059 96020 48082 96021 48081 96021 48056 96021 48056 96022 48081 96022 47943 96022 48056 96023 47943 96023 48040 96023 48044 96024 47959 96024 48046 96024 48046 96025 47959 96025 47956 96025 48046 96026 47956 96026 48045 96026 47948 96027 47949 96027 48059 96027 48059 96028 47949 96028 47950 96028 48059 96029 47950 96029 48044 96029 48044 96030 47950 96030 47951 96030 48044 96031 47951 96031 47959 96031 48045 96032 48047 96032 48046 96032 48046 96033 48047 96033 47954 96033 48046 96034 47954 96034 48062 96034 48062 96035 47954 96035 48080 96035 48062 96036 48080 96036 48078 96036 48026 96037 48064 96037 48048 96037 48048 96038 48064 96038 48049 96038 48048 96039 48049 96039 48063 96039 48063 96040 48049 96040 48066 96040 48063 96041 48066 96041 48050 96041 48050 96042 48066 96042 48051 96042 48050 96043 48051 96043 48061 96043 48061 96044 48051 96044 48052 96044 48061 96045 48052 96045 48060 96045 48060 96046 48052 96046 48053 96046 48060 96047 48053 96047 48058 96047 48058 96048 48053 96048 48055 96048 48058 96049 48055 96049 48054 96049 48054 96050 48055 96050 48088 96050 48054 96051 48088 96051 48082 96051 48082 96052 48056 96052 48054 96052 48054 96053 48056 96053 48057 96053 48054 96054 48057 96054 48058 96054 48058 96055 48057 96055 48043 96055 48058 96056 48043 96056 48060 96056 48060 96057 48043 96057 48059 96057 48060 96058 48059 96058 48061 96058 48061 96059 48059 96059 48044 96059 48061 96060 48044 96060 48050 96060 48050 96061 48044 96061 48046 96061 48050 96062 48046 96062 48063 96062 48063 96063 48046 96063 48062 96063 48063 96064 48062 96064 48048 96064 48048 96065 48062 96065 48078 96065 48048 96066 48078 96066 48077 96066 48101 96067 48027 96067 48064 96067 48064 96068 48027 96068 48032 96068 48064 96069 48032 96069 48049 96069 48049 96070 48032 96070 48065 96070 48049 96071 48065 96071 48066 96071 48066 96072 48065 96072 48067 96072 48066 96073 48067 96073 48051 96073 48051 96074 48067 96074 48033 96074 48051 96075 48033 96075 48052 96075 48052 96076 48033 96076 48034 96076 48052 96077 48034 96077 48053 96077 48053 96078 48034 96078 48068 96078 48053 96079 48068 96079 48055 96079 48055 96080 48068 96080 48089 96080 48055 96081 48089 96081 48088 96081 48070 96082 48075 96082 48076 96082 48102 96083 48101 96083 48026 96083 47966 96084 48108 96084 48069 96084 48073 96085 48009 96085 48070 96085 48070 96086 48009 96086 47966 96086 47966 96087 48069 96087 48070 96087 48070 96088 48069 96088 48107 96088 48070 96089 48107 96089 48075 96089 48075 96090 48107 96090 48071 96090 48075 96091 48071 96091 48102 96091 47988 96092 48072 96092 48079 96092 48079 96093 48072 96093 48073 96093 47989 96094 47988 96094 48074 96094 48074 96095 47988 96095 48079 96095 48074 96096 48079 96096 47960 96096 48102 96097 48026 96097 48075 96097 48075 96098 48026 96098 48077 96098 48075 96099 48077 96099 48076 96099 48076 96100 48077 96100 48078 96100 48076 96101 48078 96101 48080 96101 48073 96102 48070 96102 48079 96102 48079 96103 48070 96103 48076 96103 48079 96104 48076 96104 47960 96104 47960 96105 48076 96105 48080 96105 47960 96106 48080 96106 47952 96106 48081 96107 48082 96107 48093 96107 48083 96108 48106 96108 48086 96108 48022 96109 48105 96109 48092 96109 48092 96110 48105 96110 48090 96110 47969 96111 47979 96111 48084 96111 48084 96112 47979 96112 48106 96112 48095 96113 48085 96113 48094 96113 48094 96114 48085 96114 48090 96114 48106 96115 47979 96115 48086 96115 48086 96116 47979 96116 47978 96116 48086 96117 47978 96117 48087 96117 48105 96118 48083 96118 48090 96118 48090 96119 48083 96119 48086 96119 48090 96120 48086 96120 48094 96120 48094 96121 48086 96121 48087 96121 48082 96122 48088 96122 48085 96122 48085 96123 48088 96123 48089 96123 48085 96124 48089 96124 48090 96124 48090 96125 48089 96125 48091 96125 48090 96126 48091 96126 48092 96126 47964 96127 47965 96127 48093 96127 48093 96128 47965 96128 47943 96128 48093 96129 47943 96129 48081 96129 48087 96130 47972 96130 48094 96130 48094 96131 47972 96131 48021 96131 48094 96132 48021 96132 48095 96132 48095 96133 48021 96133 48096 96133 48095 96134 48096 96134 47990 96134 48082 96135 48085 96135 48093 96135 48093 96136 48085 96136 48095 96136 48093 96137 48095 96137 47964 96137 47964 96138 48095 96138 47990 96138 47964 96139 47990 96139 47963 96139 48097 96140 47969 96140 48084 96140 48097 96141 48010 96141 48098 96141 48098 96142 48099 96142 48097 96142 48097 96143 48099 96143 47968 96143 48097 96144 47968 96144 47969 96144 48100 96145 47983 96145 48097 96145 48097 96146 47983 96146 47982 96146 48097 96147 47982 96147 48010 96147 48103 96148 48101 96148 48102 96148 48027 96149 48101 96149 48029 96149 48029 96150 48101 96150 48103 96150 48029 96151 48103 96151 48030 96151 48022 96152 48023 96152 48103 96152 48103 96153 48023 96153 48024 96153 48024 96154 48025 96154 48103 96154 48103 96155 48025 96155 48104 96155 48103 96156 48104 96156 48030 96156 48022 96157 48103 96157 48105 96157 48105 96158 48103 96158 48102 96158 48105 96159 48102 96159 48083 96159 48083 96160 48102 96160 48071 96160 48083 96161 48071 96161 48106 96161 48106 96162 48071 96162 48107 96162 48106 96163 48107 96163 48084 96163 48084 96164 48107 96164 48069 96164 48084 96165 48069 96165 48097 96165 48097 96166 48069 96166 48108 96166 48097 96167 48108 96167 48100 96167 47994 96168 48109 96168 47995 96168 47995 96169 48109 96169 48110 96169 47995 96170 48110 96170 47996 96170 47996 96171 48110 96171 48112 96171 47996 96172 48112 96172 48111 96172 48111 96173 48112 96173 48113 96173 48113 96174 48112 96174 47921 96174 48113 96175 47921 96175 47963 96175 48109 96176 48114 96176 48110 96176 48110 96177 48114 96177 48145 96177 48110 96178 48145 96178 48112 96178 48112 96179 48145 96179 48144 96179 48112 96180 48144 96180 47921 96180 47921 96181 48144 96181 48142 96181 48169 96182 48115 96182 48250 96182 48250 96183 48115 96183 48122 96183 48250 96184 48122 96184 48116 96184 48116 96185 48122 96185 48126 96185 48116 96186 48126 96186 48224 96186 48224 96187 48126 96187 48230 96187 48230 96188 48126 96188 48127 96188 48230 96189 48127 96189 48117 96189 48117 96190 48127 96190 48207 96190 48207 96191 48127 96191 48118 96191 48207 96192 48118 96192 48119 96192 48119 96193 48118 96193 48159 96193 48119 96194 48159 96194 48120 96194 48160 96195 48159 96195 47933 96195 47933 96196 48159 96196 48118 96196 47933 96197 48118 96197 48121 96197 48121 96198 48118 96198 48127 96198 48115 96199 48123 96199 48122 96199 48122 96200 48123 96200 48124 96200 48122 96201 48124 96201 48126 96201 48126 96202 48124 96202 48125 96202 48126 96203 48125 96203 48127 96203 48127 96204 48125 96204 48140 96204 48127 96205 48140 96205 48121 96205 48152 96206 48162 96206 48151 96206 48151 96207 48162 96207 48177 96207 48151 96208 48177 96208 48150 96208 48177 96209 48128 96209 48150 96209 48150 96210 48128 96210 48129 96210 48150 96211 48129 96211 48130 96211 48130 96212 48129 96212 48176 96212 48130 96213 48176 96213 48146 96213 48146 96214 48176 96214 48174 96214 48146 96215 48174 96215 48143 96215 48143 96216 48174 96216 48131 96216 48143 96217 48131 96217 48132 96217 48156 96218 48133 96218 48172 96218 48172 96219 48133 96219 47935 96219 48172 96220 47935 96220 48132 96220 48132 96221 47935 96221 48141 96221 48132 96222 48141 96222 48143 96222 48164 96223 48155 96223 48168 96223 48168 96224 48155 96224 48134 96224 48168 96225 48134 96225 48115 96225 48115 96226 48134 96226 48123 96226 48135 96227 48121 96227 48140 96227 48130 96228 48146 96228 48114 96228 47922 96229 48136 96229 48123 96229 48123 96230 48136 96230 48137 96230 48123 96231 48137 96231 48124 96231 48137 96232 48138 96232 48124 96232 48124 96233 48138 96233 48139 96233 48124 96234 48139 96234 48125 96234 48125 96235 48139 96235 47931 96235 48125 96236 47931 96236 48140 96236 48140 96237 47931 96237 47930 96237 48140 96238 47930 96238 48135 96238 48141 96239 48142 96239 48143 96239 48143 96240 48142 96240 48144 96240 48143 96241 48144 96241 48146 96241 48146 96242 48144 96242 48145 96242 48146 96243 48145 96243 48114 96243 48114 96244 48147 96244 48130 96244 48130 96245 48147 96245 48148 96245 48130 96246 48148 96246 48150 96246 48150 96247 48148 96247 48149 96247 48150 96248 48149 96248 48151 96248 48151 96249 48149 96249 47927 96249 48151 96250 47927 96250 48152 96250 48152 96251 47927 96251 47925 96251 48152 96252 47925 96252 48153 96252 48153 96253 47925 96253 48154 96253 48153 96254 48154 96254 48155 96254 48155 96255 48154 96255 47922 96255 48155 96256 47922 96256 48134 96256 48134 96257 47922 96257 48123 96257 48133 96258 48156 96258 48157 96258 48133 96259 48157 96259 48158 96259 48158 96260 48157 96260 48159 96260 48158 96261 48159 96261 48160 96261 48120 96262 48159 96262 48186 96262 48186 96263 48159 96263 48157 96263 48186 96264 48157 96264 48187 96264 48156 96265 48161 96265 48157 96265 48157 96266 48161 96266 48188 96266 48157 96267 48188 96267 48187 96267 48162 96268 48152 96268 48163 96268 48163 96269 48152 96269 48153 96269 48163 96270 48153 96270 48164 96270 48164 96271 48153 96271 48155 96271 48215 96272 48164 96272 48165 96272 48165 96273 48164 96273 48168 96273 48165 96274 48168 96274 48166 96274 48166 96275 48168 96275 48167 96275 48167 96276 48168 96276 48115 96276 48167 96277 48115 96277 48169 96277 48161 96278 48156 96278 48170 96278 48170 96279 48156 96279 48172 96279 48170 96280 48172 96280 48171 96280 48171 96281 48172 96281 48132 96281 48171 96282 48132 96282 48269 96282 48269 96283 48132 96283 48131 96283 48269 96284 48131 96284 48272 96284 48272 96285 48131 96285 48174 96285 48272 96286 48174 96286 48276 96286 48276 96287 48174 96287 48173 96287 48173 96288 48174 96288 48175 96288 48175 96289 48174 96289 48176 96289 48175 96290 48176 96290 48181 96290 48162 96291 48202 96291 48177 96291 48177 96292 48202 96292 48178 96292 48177 96293 48178 96293 48128 96293 48178 96294 48179 96294 48128 96294 48128 96295 48179 96295 48180 96295 48128 96296 48180 96296 48129 96296 48129 96297 48180 96297 48275 96297 48129 96298 48275 96298 48176 96298 48176 96299 48275 96299 48277 96299 48176 96300 48277 96300 48181 96300 48199 96301 48182 96301 48201 96301 48182 96302 48199 96302 48183 96302 48185 96303 48184 96303 48193 96303 48228 96304 48120 96304 48186 96304 48191 96305 48227 96305 48185 96305 48185 96306 48227 96306 48228 96306 48228 96307 48186 96307 48185 96307 48185 96308 48186 96308 48187 96308 48185 96309 48187 96309 48184 96309 48184 96310 48187 96310 48188 96310 48184 96311 48188 96311 48161 96311 48225 96312 48189 96312 48190 96312 48190 96313 48189 96313 48191 96313 48161 96314 48274 96314 48184 96314 48184 96315 48274 96315 48192 96315 48184 96316 48192 96316 48193 96316 48193 96317 48192 96317 48290 96317 48193 96318 48290 96318 48195 96318 48194 96319 48225 96319 48196 96319 48196 96320 48225 96320 48190 96320 48196 96321 48190 96321 48199 96321 48191 96322 48185 96322 48190 96322 48190 96323 48185 96323 48193 96323 48190 96324 48193 96324 48199 96324 48199 96325 48193 96325 48195 96325 48199 96326 48195 96326 48183 96326 48213 96327 48194 96327 48197 96327 48197 96328 48194 96328 48196 96328 48197 96329 48196 96329 48198 96329 48198 96330 48196 96330 48199 96330 48198 96331 48199 96331 48200 96331 48200 96332 48199 96332 48201 96332 48202 96333 48162 96333 48203 96333 48203 96334 48162 96334 48163 96334 48203 96335 48163 96335 48205 96335 48164 96336 48215 96336 48163 96336 48163 96337 48215 96337 48204 96337 48163 96338 48204 96338 48205 96338 48224 96339 48230 96339 48206 96339 48117 96340 48207 96340 48231 96340 48211 96341 48212 96341 48223 96341 48208 96342 47896 96342 48247 96342 48208 96343 48247 96343 48245 96343 47894 96344 47895 96344 48209 96344 48209 96345 47895 96345 48210 96345 48209 96346 48210 96346 48211 96346 48211 96347 48210 96347 48243 96347 48211 96348 48243 96348 48212 96348 48209 96349 48255 96349 47894 96349 47894 96350 48255 96350 48194 96350 47894 96351 48194 96351 48213 96351 48248 96352 48247 96352 48241 96352 48241 96353 48247 96353 47896 96353 48241 96354 47896 96354 48242 96354 48223 96355 48212 96355 48222 96355 48222 96356 48212 96356 48246 96356 48222 96357 48246 96357 48221 96357 48252 96358 48217 96358 48251 96358 48251 96359 48217 96359 48214 96359 48167 96360 48216 96360 48166 96360 48166 96361 48216 96361 48165 96361 47905 96362 48215 96362 48219 96362 48219 96363 48215 96363 48165 96363 48167 96364 48169 96364 48216 96364 48216 96365 48169 96365 48214 96365 48216 96366 48214 96366 48220 96366 48220 96367 48214 96367 48217 96367 48220 96368 48217 96368 48218 96368 48218 96369 48217 96369 48252 96369 48218 96370 48252 96370 48253 96370 48165 96371 48216 96371 48219 96371 48219 96372 48216 96372 48220 96372 48219 96373 48220 96373 48221 96373 48221 96374 48220 96374 48218 96374 48221 96375 48218 96375 48222 96375 48222 96376 48218 96376 48253 96376 48222 96377 48253 96377 48223 96377 48224 96378 48206 96378 48116 96378 48225 96379 48236 96379 48189 96379 48189 96380 48236 96380 48226 96380 48189 96381 48226 96381 48191 96381 48191 96382 48226 96382 48238 96382 48191 96383 48238 96383 48227 96383 48227 96384 48238 96384 48239 96384 48227 96385 48239 96385 48228 96385 48228 96386 48239 96386 48229 96386 48228 96387 48229 96387 48120 96387 48120 96388 48229 96388 48119 96388 48230 96389 48117 96389 48206 96389 48206 96390 48117 96390 48231 96390 48206 96391 48231 96391 48232 96391 48232 96392 48231 96392 48240 96392 48232 96393 48240 96393 48233 96393 48233 96394 48240 96394 48234 96394 48233 96395 48234 96395 48235 96395 48235 96396 48234 96396 48237 96396 48235 96397 48237 96397 48254 96397 48236 96398 48254 96398 48226 96398 48226 96399 48254 96399 48237 96399 48226 96400 48237 96400 48238 96400 48238 96401 48237 96401 48234 96401 48238 96402 48234 96402 48239 96402 48239 96403 48234 96403 48240 96403 48239 96404 48240 96404 48229 96404 48229 96405 48240 96405 48231 96405 48229 96406 48231 96406 48119 96406 48119 96407 48231 96407 48207 96407 48249 96408 48248 96408 47914 96408 47914 96409 48248 96409 48241 96409 47914 96410 48241 96410 47907 96410 47907 96411 48241 96411 48242 96411 47907 96412 48242 96412 47904 96412 48243 96413 48244 96413 48212 96413 48212 96414 48244 96414 48245 96414 48212 96415 48245 96415 48246 96415 48246 96416 48245 96416 48247 96416 48246 96417 48247 96417 48221 96417 48221 96418 48247 96418 48248 96418 48221 96419 48248 96419 48219 96419 48219 96420 48248 96420 48249 96420 48219 96421 48249 96421 47905 96421 48169 96422 48250 96422 48214 96422 48214 96423 48250 96423 48116 96423 48214 96424 48116 96424 48251 96424 48251 96425 48116 96425 48206 96425 48251 96426 48206 96426 48252 96426 48252 96427 48206 96427 48232 96427 48252 96428 48232 96428 48253 96428 48253 96429 48232 96429 48233 96429 48253 96430 48233 96430 48223 96430 48223 96431 48233 96431 48235 96431 48223 96432 48235 96432 48211 96432 48211 96433 48235 96433 48254 96433 48211 96434 48254 96434 48209 96434 48209 96435 48254 96435 48236 96435 48209 96436 48236 96436 48255 96436 48255 96437 48236 96437 48225 96437 48255 96438 48225 96438 48194 96438 48178 96439 48202 96439 47915 96439 48302 96440 48262 96440 48263 96440 48295 96441 47912 96441 48279 96441 47898 96442 48256 96442 48257 96442 48257 96443 48256 96443 48258 96443 48257 96444 48258 96444 48268 96444 48268 96445 48258 96445 48201 96445 48268 96446 48201 96446 48182 96446 48297 96447 48279 96447 47911 96447 48298 96448 47900 96448 48299 96448 48299 96449 47900 96449 48260 96449 48299 96450 48260 96450 48259 96450 48259 96451 48260 96451 48261 96451 48259 96452 48261 96452 48263 96452 48263 96453 48262 96453 48259 96453 48259 96454 48262 96454 48300 96454 48259 96455 48300 96455 48299 96455 48261 96456 47899 96456 48263 96456 48263 96457 47899 96457 48264 96457 48263 96458 48264 96458 48302 96458 48302 96459 48264 96459 48267 96459 48302 96460 48267 96460 48303 96460 48303 96461 48267 96461 48265 96461 48303 96462 48265 96462 48266 96462 48266 96463 48265 96463 48183 96463 48266 96464 48183 96464 48195 96464 47899 96465 47898 96465 48264 96465 48264 96466 47898 96466 48257 96466 48264 96467 48257 96467 48267 96467 48267 96468 48257 96468 48268 96468 48267 96469 48268 96469 48265 96469 48265 96470 48268 96470 48182 96470 48265 96471 48182 96471 48183 96471 48170 96472 48171 96472 48291 96472 48291 96473 48171 96473 48269 96473 48291 96474 48269 96474 48270 96474 48270 96475 48269 96475 48272 96475 48270 96476 48272 96476 48271 96476 48271 96477 48272 96477 48276 96477 48271 96478 48276 96478 48273 96478 48192 96479 48274 96479 48291 96479 48291 96480 48274 96480 48161 96480 48291 96481 48161 96481 48170 96481 48293 96482 48277 96482 48294 96482 48294 96483 48277 96483 48275 96483 48294 96484 48275 96484 48180 96484 48276 96485 48173 96485 48273 96485 48273 96486 48173 96486 48175 96486 48273 96487 48175 96487 48293 96487 48293 96488 48175 96488 48181 96488 48293 96489 48181 96489 48277 96489 48180 96490 48179 96490 48294 96490 48294 96491 48179 96491 48178 96491 48294 96492 48178 96492 48278 96492 48278 96493 48178 96493 47915 96493 48278 96494 47915 96494 48296 96494 48279 96495 48297 96495 48295 96495 48295 96496 48297 96496 48280 96496 48295 96497 48280 96497 48282 96497 48282 96498 48280 96498 48281 96498 48282 96499 48281 96499 48283 96499 48283 96500 48281 96500 48301 96500 48283 96501 48301 96501 48284 96501 48284 96502 48301 96502 48286 96502 48284 96503 48286 96503 48285 96503 48285 96504 48286 96504 48287 96504 48285 96505 48287 96505 48292 96505 48292 96506 48287 96506 48288 96506 48292 96507 48288 96507 48289 96507 48289 96508 48288 96508 48290 96508 48289 96509 48290 96509 48192 96509 48192 96510 48291 96510 48289 96510 48289 96511 48291 96511 48270 96511 48289 96512 48270 96512 48292 96512 48292 96513 48270 96513 48271 96513 48292 96514 48271 96514 48285 96514 48285 96515 48271 96515 48273 96515 48285 96516 48273 96516 48284 96516 48284 96517 48273 96517 48293 96517 48284 96518 48293 96518 48283 96518 48283 96519 48293 96519 48294 96519 48283 96520 48294 96520 48282 96520 48282 96521 48294 96521 48278 96521 48282 96522 48278 96522 48295 96522 48295 96523 48278 96523 48296 96523 48295 96524 48296 96524 47912 96524 47911 96525 48298 96525 48297 96525 48297 96526 48298 96526 48299 96526 48297 96527 48299 96527 48280 96527 48280 96528 48299 96528 48300 96528 48280 96529 48300 96529 48281 96529 48281 96530 48300 96530 48262 96530 48281 96531 48262 96531 48301 96531 48301 96532 48262 96532 48302 96532 48301 96533 48302 96533 48286 96533 48286 96534 48302 96534 48303 96534 48286 96535 48303 96535 48287 96535 48287 96536 48303 96536 48266 96536 48287 96537 48266 96537 48288 96537 48288 96538 48266 96538 48195 96538 48288 96539 48195 96539 48290 96539 48633 96540 48366 96540 48331 96540 48313 96541 48304 96541 48312 96541 48332 96542 48364 96542 48363 96542 48368 96543 48369 96543 48305 96543 48305 96544 48369 96544 48318 96544 48305 96545 48318 96545 48306 96545 48306 96546 48318 96546 48317 96546 48306 96547 48317 96547 48392 96547 48307 96548 48363 96548 48390 96548 48346 96549 48308 96549 48347 96549 48347 96550 48308 96550 48310 96550 48310 96551 48308 96551 48309 96551 48310 96552 48309 96552 48312 96552 48312 96553 48304 96553 48310 96553 48310 96554 48304 96554 48348 96554 48310 96555 48348 96555 48347 96555 48309 96556 48393 96556 48312 96556 48312 96557 48393 96557 48311 96557 48312 96558 48311 96558 48313 96558 48313 96559 48311 96559 48314 96559 48313 96560 48314 96560 48350 96560 48350 96561 48314 96561 48315 96561 48350 96562 48315 96562 48316 96562 48316 96563 48315 96563 48319 96563 48316 96564 48319 96564 48378 96564 48393 96565 48392 96565 48311 96565 48311 96566 48392 96566 48317 96566 48311 96567 48317 96567 48314 96567 48314 96568 48317 96568 48318 96568 48314 96569 48318 96569 48315 96569 48315 96570 48318 96570 48369 96570 48315 96571 48369 96571 48319 96571 48626 96572 48627 96572 48324 96572 48324 96573 48627 96573 48630 96573 48324 96574 48630 96574 48342 96574 48342 96575 48630 96575 48320 96575 48342 96576 48320 96576 48321 96576 48321 96577 48320 96577 48322 96577 48321 96578 48322 96578 48327 96578 48340 96579 48323 96579 48324 96579 48324 96580 48323 96580 48380 96580 48324 96581 48380 96581 48626 96581 48344 96582 48636 96582 48325 96582 48325 96583 48636 96583 48635 96583 48325 96584 48635 96584 48326 96584 48322 96585 48328 96585 48327 96585 48327 96586 48328 96586 48628 96586 48327 96587 48628 96587 48344 96587 48344 96588 48628 96588 48637 96588 48344 96589 48637 96589 48636 96589 48326 96590 48329 96590 48325 96590 48325 96591 48329 96591 48633 96591 48325 96592 48633 96592 48330 96592 48330 96593 48633 96593 48331 96593 48330 96594 48331 96594 48345 96594 48363 96595 48307 96595 48332 96595 48332 96596 48307 96596 48334 96596 48332 96597 48334 96597 48333 96597 48333 96598 48334 96598 48335 96598 48333 96599 48335 96599 48343 96599 48343 96600 48335 96600 48336 96600 48343 96601 48336 96601 48337 96601 48337 96602 48336 96602 48349 96602 48337 96603 48349 96603 48338 96603 48338 96604 48349 96604 48351 96604 48338 96605 48351 96605 48339 96605 48339 96606 48351 96606 48352 96606 48339 96607 48352 96607 48341 96607 48341 96608 48352 96608 48353 96608 48341 96609 48353 96609 48340 96609 48340 96610 48324 96610 48341 96610 48341 96611 48324 96611 48342 96611 48341 96612 48342 96612 48339 96612 48339 96613 48342 96613 48321 96613 48339 96614 48321 96614 48338 96614 48338 96615 48321 96615 48327 96615 48338 96616 48327 96616 48337 96616 48337 96617 48327 96617 48344 96617 48337 96618 48344 96618 48343 96618 48343 96619 48344 96619 48325 96619 48343 96620 48325 96620 48333 96620 48333 96621 48325 96621 48330 96621 48333 96622 48330 96622 48332 96622 48332 96623 48330 96623 48345 96623 48332 96624 48345 96624 48364 96624 48390 96625 48346 96625 48307 96625 48307 96626 48346 96626 48347 96626 48307 96627 48347 96627 48334 96627 48334 96628 48347 96628 48348 96628 48334 96629 48348 96629 48335 96629 48335 96630 48348 96630 48304 96630 48335 96631 48304 96631 48336 96631 48336 96632 48304 96632 48313 96632 48336 96633 48313 96633 48349 96633 48349 96634 48313 96634 48350 96634 48349 96635 48350 96635 48351 96635 48351 96636 48350 96636 48316 96636 48351 96637 48316 96637 48352 96637 48352 96638 48316 96638 48378 96638 48352 96639 48378 96639 48353 96639 48357 96640 48359 96640 48365 96640 48394 96641 48390 96641 48363 96641 48356 96642 48398 96642 48358 96642 48354 96643 48355 96643 48357 96643 48357 96644 48355 96644 48356 96644 48356 96645 48358 96645 48357 96645 48357 96646 48358 96646 48397 96646 48357 96647 48397 96647 48359 96647 48359 96648 48397 96648 48395 96648 48359 96649 48395 96649 48394 96649 48362 96650 48360 96650 48361 96650 48361 96651 48360 96651 48354 96651 48661 96652 48362 96652 48639 96652 48639 96653 48362 96653 48361 96653 48639 96654 48361 96654 48638 96654 48394 96655 48363 96655 48359 96655 48359 96656 48363 96656 48364 96656 48359 96657 48364 96657 48365 96657 48365 96658 48364 96658 48345 96658 48365 96659 48345 96659 48331 96659 48354 96660 48357 96660 48361 96660 48361 96661 48357 96661 48365 96661 48361 96662 48365 96662 48638 96662 48638 96663 48365 96663 48331 96663 48638 96664 48331 96664 48366 96664 48323 96665 48340 96665 48367 96665 48396 96666 48373 96666 48374 96666 48368 96667 48375 96667 48369 96667 48369 96668 48375 96668 48376 96668 48388 96669 48371 96669 48370 96669 48370 96670 48371 96670 48373 96670 48383 96671 48382 96671 48372 96671 48372 96672 48382 96672 48376 96672 48373 96673 48371 96673 48374 96673 48374 96674 48371 96674 48647 96674 48374 96675 48647 96675 48377 96675 48375 96676 48396 96676 48376 96676 48376 96677 48396 96677 48374 96677 48376 96678 48374 96678 48372 96678 48372 96679 48374 96679 48377 96679 48340 96680 48353 96680 48382 96680 48382 96681 48353 96681 48378 96681 48382 96682 48378 96682 48376 96682 48376 96683 48378 96683 48319 96683 48376 96684 48319 96684 48369 96684 48642 96685 48379 96685 48367 96685 48367 96686 48379 96686 48380 96686 48367 96687 48380 96687 48323 96687 48377 96688 48381 96688 48372 96688 48372 96689 48381 96689 48671 96689 48372 96690 48671 96690 48383 96690 48383 96691 48671 96691 48678 96691 48383 96692 48678 96692 48384 96692 48340 96693 48382 96693 48367 96693 48367 96694 48382 96694 48383 96694 48367 96695 48383 96695 48642 96695 48642 96696 48383 96696 48384 96696 48642 96697 48384 96697 48640 96697 48386 96698 48388 96698 48370 96698 48386 96699 48680 96699 48385 96699 48385 96700 48387 96700 48386 96700 48386 96701 48387 96701 48644 96701 48386 96702 48644 96702 48388 96702 48643 96703 48389 96703 48386 96703 48386 96704 48389 96704 48657 96704 48386 96705 48657 96705 48680 96705 48391 96706 48390 96706 48394 96706 48346 96707 48390 96707 48308 96707 48308 96708 48390 96708 48391 96708 48308 96709 48391 96709 48309 96709 48368 96710 48305 96710 48391 96710 48391 96711 48305 96711 48306 96711 48306 96712 48392 96712 48391 96712 48391 96713 48392 96713 48393 96713 48391 96714 48393 96714 48309 96714 48368 96715 48391 96715 48375 96715 48375 96716 48391 96716 48394 96716 48375 96717 48394 96717 48396 96717 48396 96718 48394 96718 48395 96718 48396 96719 48395 96719 48373 96719 48373 96720 48395 96720 48397 96720 48373 96721 48397 96721 48370 96721 48370 96722 48397 96722 48358 96722 48370 96723 48358 96723 48386 96723 48386 96724 48358 96724 48398 96724 48386 96725 48398 96725 48643 96725 48624 96726 48400 96726 48399 96726 48399 96727 48400 96727 48401 96727 48399 96728 48401 96728 48665 96728 48665 96729 48401 96729 48403 96729 48403 96730 48401 96730 48402 96730 48403 96731 48402 96731 48404 96731 48404 96732 48402 96732 48405 96732 48405 96733 48402 96733 48407 96733 48405 96734 48407 96734 48406 96734 48406 96735 48407 96735 48410 96735 48406 96736 48410 96736 48640 96736 48400 96737 48408 96737 48401 96737 48401 96738 48408 96738 48703 96738 48401 96739 48703 96739 48402 96739 48402 96740 48703 96740 48409 96740 48402 96741 48409 96741 48407 96741 48407 96742 48409 96742 48411 96742 48407 96743 48411 96743 48410 96743 48410 96744 48411 96744 48598 96744 48412 96745 48423 96745 48413 96745 48413 96746 48423 96746 48414 96746 48413 96747 48414 96747 48495 96747 48495 96748 48414 96748 48416 96748 48416 96749 48414 96749 48415 96749 48416 96750 48415 96750 48493 96750 48493 96751 48415 96751 48417 96751 48417 96752 48415 96752 48422 96752 48417 96753 48422 96753 48418 96753 48418 96754 48422 96754 48419 96754 48418 96755 48419 96755 48426 96755 48420 96756 48419 96756 48421 96756 48421 96757 48419 96757 48422 96757 48421 96758 48422 96758 48425 96758 48425 96759 48422 96759 48415 96759 48423 96760 48704 96760 48414 96760 48414 96761 48704 96761 48424 96761 48414 96762 48424 96762 48415 96762 48415 96763 48424 96763 48705 96763 48415 96764 48705 96764 48425 96764 48426 96765 48419 96765 48427 96765 48427 96766 48419 96766 48428 96766 48427 96767 48428 96767 48450 96767 48434 96768 48543 96768 48428 96768 48428 96769 48543 96769 48451 96769 48428 96770 48451 96770 48450 96770 48690 96771 48429 96771 48464 96771 48464 96772 48429 96772 48708 96772 48464 96773 48708 96773 48430 96773 48430 96774 48708 96774 48701 96774 48700 96775 48486 96775 48513 96775 48700 96776 48513 96776 48430 96776 48430 96777 48513 96777 48507 96777 48430 96778 48507 96778 48595 96778 48486 96779 48700 96779 48488 96779 48488 96780 48700 96780 48431 96780 48488 96781 48431 96781 48432 96781 48423 96782 48412 96782 48465 96782 48423 96783 48465 96783 48431 96783 48431 96784 48465 96784 48433 96784 48431 96785 48433 96785 48432 96785 48543 96786 48434 96786 48436 96786 48436 96787 48434 96787 48435 96787 48436 96788 48435 96788 48536 96788 48536 96789 48435 96789 48438 96789 48445 96790 48446 96790 48699 96790 48699 96791 48446 96791 48437 96791 48699 96792 48437 96792 48698 96792 48698 96793 48437 96793 48539 96793 48698 96794 48539 96794 48697 96794 48697 96795 48539 96795 48538 96795 48697 96796 48538 96796 48438 96796 48438 96797 48538 96797 48439 96797 48438 96798 48439 96798 48536 96798 48690 96799 48461 96799 48691 96799 48691 96800 48461 96800 48441 96800 48691 96801 48441 96801 48440 96801 48441 96802 48442 96802 48440 96802 48440 96803 48442 96803 48443 96803 48440 96804 48443 96804 48692 96804 48692 96805 48443 96805 48444 96805 48692 96806 48444 96806 48445 96806 48445 96807 48444 96807 48545 96807 48445 96808 48545 96808 48446 96808 48459 96809 48447 96809 48576 96809 48447 96810 48459 96810 48533 96810 48449 96811 48454 96811 48456 96811 48506 96812 48426 96812 48427 96812 48519 96813 48448 96813 48449 96813 48449 96814 48448 96814 48506 96814 48506 96815 48427 96815 48449 96815 48449 96816 48427 96816 48450 96816 48449 96817 48450 96817 48454 96817 48454 96818 48450 96818 48451 96818 48454 96819 48451 96819 48543 96819 48474 96820 48452 96820 48455 96820 48455 96821 48452 96821 48519 96821 48543 96822 48453 96822 48454 96822 48454 96823 48453 96823 48541 96823 48454 96824 48541 96824 48456 96824 48456 96825 48541 96825 48568 96825 48456 96826 48568 96826 48457 96826 48478 96827 48474 96827 48458 96827 48458 96828 48474 96828 48455 96828 48458 96829 48455 96829 48459 96829 48519 96830 48449 96830 48455 96830 48455 96831 48449 96831 48456 96831 48455 96832 48456 96832 48459 96832 48459 96833 48456 96833 48457 96833 48459 96834 48457 96834 48533 96834 48479 96835 48478 96835 48579 96835 48579 96836 48478 96836 48458 96836 48579 96837 48458 96837 48578 96837 48578 96838 48458 96838 48459 96838 48578 96839 48459 96839 48460 96839 48460 96840 48459 96840 48576 96840 48462 96841 48461 96841 48690 96841 48462 96842 48690 96842 48463 96842 48463 96843 48690 96843 48464 96843 48463 96844 48464 96844 48593 96844 48593 96845 48464 96845 48430 96845 48593 96846 48430 96846 48595 96846 48507 96847 48513 96847 48508 96847 48433 96848 48465 96848 48501 96848 48476 96849 48477 96849 48466 96849 48571 96850 48467 96850 48491 96850 48571 96851 48491 96851 48490 96851 48468 96852 48469 96852 48477 96852 48477 96853 48469 96853 48470 96853 48477 96854 48470 96854 48466 96854 48466 96855 48470 96855 48471 96855 48466 96856 48471 96856 48481 96856 48478 96857 48472 96857 48474 96857 48474 96858 48472 96858 48473 96858 48474 96859 48473 96859 48452 96859 48452 96860 48473 96860 48475 96860 48517 96861 48475 96861 48476 96861 48476 96862 48475 96862 48473 96862 48476 96863 48473 96863 48477 96863 48477 96864 48473 96864 48472 96864 48477 96865 48472 96865 48468 96865 48468 96866 48472 96866 48478 96866 48468 96867 48478 96867 48479 96867 48509 96868 48491 96868 48510 96868 48510 96869 48491 96869 48467 96869 48510 96870 48467 96870 48511 96870 48517 96871 48476 96871 48480 96871 48480 96872 48476 96872 48466 96872 48480 96873 48466 96873 48482 96873 48482 96874 48466 96874 48481 96874 48482 96875 48481 96875 48484 96875 48484 96876 48481 96876 48483 96876 48484 96877 48483 96877 48515 96877 48501 96878 48465 96878 48485 96878 48514 96879 48487 96879 48501 96879 48513 96880 48486 96880 48487 96880 48487 96881 48486 96881 48488 96881 48487 96882 48488 96882 48501 96882 48501 96883 48488 96883 48432 96883 48501 96884 48432 96884 48433 96884 48471 96885 48489 96885 48481 96885 48481 96886 48489 96886 48490 96886 48481 96887 48490 96887 48483 96887 48483 96888 48490 96888 48491 96888 48483 96889 48491 96889 48515 96889 48515 96890 48491 96890 48509 96890 48515 96891 48509 96891 48508 96891 48426 96892 48506 96892 48492 96892 48426 96893 48492 96893 48418 96893 48418 96894 48492 96894 48505 96894 48418 96895 48505 96895 48417 96895 48417 96896 48505 96896 48493 96896 48493 96897 48505 96897 48494 96897 48493 96898 48494 96898 48416 96898 48465 96899 48412 96899 48485 96899 48485 96900 48412 96900 48413 96900 48485 96901 48413 96901 48494 96901 48494 96902 48413 96902 48495 96902 48494 96903 48495 96903 48416 96903 48514 96904 48502 96904 48496 96904 48496 96905 48502 96905 48503 96905 48496 96906 48503 96906 48497 96906 48497 96907 48503 96907 48504 96907 48497 96908 48504 96908 48499 96908 48499 96909 48504 96909 48498 96909 48499 96910 48498 96910 48516 96910 48516 96911 48498 96911 48500 96911 48516 96912 48500 96912 48518 96912 48518 96913 48500 96913 48448 96913 48518 96914 48448 96914 48519 96914 48514 96915 48501 96915 48502 96915 48502 96916 48501 96916 48485 96916 48502 96917 48485 96917 48503 96917 48503 96918 48485 96918 48494 96918 48503 96919 48494 96919 48504 96919 48504 96920 48494 96920 48505 96920 48504 96921 48505 96921 48498 96921 48498 96922 48505 96922 48492 96922 48498 96923 48492 96923 48500 96923 48500 96924 48492 96924 48506 96924 48500 96925 48506 96925 48448 96925 48595 96926 48507 96926 48594 96926 48594 96927 48507 96927 48508 96927 48594 96928 48508 96928 48592 96928 48592 96929 48508 96929 48509 96929 48592 96930 48509 96930 48582 96930 48582 96931 48509 96931 48510 96931 48582 96932 48510 96932 48512 96932 48512 96933 48510 96933 48511 96933 48512 96934 48511 96934 48581 96934 48513 96935 48487 96935 48508 96935 48508 96936 48487 96936 48514 96936 48508 96937 48514 96937 48515 96937 48515 96938 48514 96938 48496 96938 48515 96939 48496 96939 48484 96939 48484 96940 48496 96940 48497 96940 48484 96941 48497 96941 48482 96941 48482 96942 48497 96942 48499 96942 48482 96943 48499 96943 48480 96943 48480 96944 48499 96944 48516 96944 48480 96945 48516 96945 48517 96945 48517 96946 48516 96946 48518 96946 48517 96947 48518 96947 48475 96947 48475 96948 48518 96948 48519 96948 48475 96949 48519 96949 48452 96949 48441 96950 48461 96950 48547 96950 48565 96951 48563 96951 48520 96951 48521 96952 48587 96952 48525 96952 48522 96953 48523 96953 48534 96953 48534 96954 48523 96954 48577 96954 48534 96955 48577 96955 48524 96955 48524 96956 48577 96956 48576 96956 48524 96957 48576 96957 48447 96957 48549 96958 48525 96958 48526 96958 48573 96959 48574 96959 48527 96959 48527 96960 48574 96960 48575 96960 48527 96961 48575 96961 48529 96961 48529 96962 48575 96962 48528 96962 48529 96963 48528 96963 48520 96963 48520 96964 48563 96964 48529 96964 48529 96965 48563 96965 48562 96965 48529 96966 48562 96966 48527 96966 48528 96967 48572 96967 48520 96967 48520 96968 48572 96968 48530 96968 48520 96969 48530 96969 48565 96969 48565 96970 48530 96970 48532 96970 48565 96971 48532 96971 48531 96971 48531 96972 48532 96972 48535 96972 48531 96973 48535 96973 48567 96973 48567 96974 48535 96974 48533 96974 48567 96975 48533 96975 48457 96975 48572 96976 48522 96976 48530 96976 48530 96977 48522 96977 48534 96977 48530 96978 48534 96978 48532 96978 48532 96979 48534 96979 48524 96979 48532 96980 48524 96980 48535 96980 48535 96981 48524 96981 48447 96981 48535 96982 48447 96982 48533 96982 48436 96983 48536 96983 48542 96983 48542 96984 48536 96984 48439 96984 48542 96985 48439 96985 48537 96985 48537 96986 48439 96986 48538 96986 48537 96987 48538 96987 48558 96987 48558 96988 48538 96988 48539 96988 48558 96989 48539 96989 48540 96989 48541 96990 48453 96990 48542 96990 48542 96991 48453 96991 48543 96991 48542 96992 48543 96992 48436 96992 48539 96993 48437 96993 48540 96993 48540 96994 48437 96994 48446 96994 48540 96995 48446 96995 48544 96995 48544 96996 48446 96996 48545 96996 48544 96997 48545 96997 48546 96997 48546 96998 48545 96998 48444 96998 48546 96999 48444 96999 48443 96999 48443 97000 48442 97000 48546 97000 48546 97001 48442 97001 48441 97001 48546 97002 48441 97002 48548 97002 48548 97003 48441 97003 48547 97003 48548 97004 48547 97004 48561 97004 48525 97005 48549 97005 48521 97005 48521 97006 48549 97006 48550 97006 48521 97007 48550 97007 48551 97007 48551 97008 48550 97008 48552 97008 48551 97009 48552 97009 48553 97009 48553 97010 48552 97010 48564 97010 48553 97011 48564 97011 48560 97011 48560 97012 48564 97012 48566 97012 48560 97013 48566 97013 48559 97013 48559 97014 48566 97014 48554 97014 48559 97015 48554 97015 48557 97015 48557 97016 48554 97016 48555 97016 48557 97017 48555 97017 48556 97017 48556 97018 48555 97018 48568 97018 48556 97019 48568 97019 48541 97019 48541 97020 48542 97020 48556 97020 48556 97021 48542 97021 48537 97021 48556 97022 48537 97022 48557 97022 48557 97023 48537 97023 48558 97023 48557 97024 48558 97024 48559 97024 48559 97025 48558 97025 48540 97025 48559 97026 48540 97026 48560 97026 48560 97027 48540 97027 48544 97027 48560 97028 48544 97028 48553 97028 48553 97029 48544 97029 48546 97029 48553 97030 48546 97030 48551 97030 48551 97031 48546 97031 48548 97031 48551 97032 48548 97032 48521 97032 48521 97033 48548 97033 48561 97033 48521 97034 48561 97034 48587 97034 48526 97035 48573 97035 48549 97035 48549 97036 48573 97036 48527 97036 48549 97037 48527 97037 48550 97037 48550 97038 48527 97038 48562 97038 48550 97039 48562 97039 48552 97039 48552 97040 48562 97040 48563 97040 48552 97041 48563 97041 48564 97041 48564 97042 48563 97042 48565 97042 48564 97043 48565 97043 48566 97043 48566 97044 48565 97044 48531 97044 48566 97045 48531 97045 48554 97045 48554 97046 48531 97046 48567 97046 48554 97047 48567 97047 48555 97047 48555 97048 48567 97048 48457 97048 48555 97049 48457 97049 48568 97049 48569 97050 48526 97050 48570 97050 48580 97051 48479 97051 48579 97051 48468 97052 48479 97052 48469 97052 48469 97053 48479 97053 48580 97053 48469 97054 48580 97054 48470 97054 48470 97055 48580 97055 48471 97055 48511 97056 48467 97056 48580 97056 48580 97057 48467 97057 48571 97057 48571 97058 48490 97058 48580 97058 48580 97059 48490 97059 48489 97059 48580 97060 48489 97060 48471 97060 48522 97061 48572 97061 48569 97061 48569 97062 48572 97062 48528 97062 48573 97063 48526 97063 48574 97063 48574 97064 48526 97064 48569 97064 48574 97065 48569 97065 48575 97065 48575 97066 48569 97066 48528 97066 48576 97067 48577 97067 48569 97067 48569 97068 48577 97068 48523 97068 48569 97069 48523 97069 48522 97069 48576 97070 48569 97070 48460 97070 48460 97071 48569 97071 48570 97071 48460 97072 48570 97072 48578 97072 48578 97073 48570 97073 48586 97073 48578 97074 48586 97074 48579 97074 48579 97075 48586 97075 48584 97075 48579 97076 48584 97076 48580 97076 48580 97077 48584 97077 48581 97077 48580 97078 48581 97078 48511 97078 48547 97079 48461 97079 48462 97079 48587 97080 48561 97080 48588 97080 48594 97081 48592 97081 48591 97081 48582 97082 48512 97082 48583 97082 48512 97083 48581 97083 48583 97083 48583 97084 48581 97084 48584 97084 48583 97085 48584 97085 48590 97085 48590 97086 48584 97086 48586 97086 48590 97087 48586 97087 48585 97087 48585 97088 48586 97088 48570 97088 48585 97089 48570 97089 48525 97089 48525 97090 48570 97090 48526 97090 48525 97091 48587 97091 48585 97091 48585 97092 48587 97092 48588 97092 48585 97093 48588 97093 48590 97093 48590 97094 48588 97094 48589 97094 48590 97095 48589 97095 48583 97095 48583 97096 48589 97096 48591 97096 48583 97097 48591 97097 48582 97097 48582 97098 48591 97098 48592 97098 48561 97099 48547 97099 48588 97099 48588 97100 48547 97100 48462 97100 48588 97101 48462 97101 48589 97101 48589 97102 48462 97102 48463 97102 48589 97103 48463 97103 48591 97103 48591 97104 48463 97104 48593 97104 48591 97105 48593 97105 48594 97105 48594 97106 48593 97106 48595 97106 48425 97107 48615 97107 48625 97107 48425 97108 48625 97108 48596 97108 48625 97109 48597 97109 48596 97109 48596 97110 48597 97110 48641 97110 48596 97111 48641 97111 48620 97111 48620 97112 48641 97112 48696 97112 48696 97113 48641 97113 48410 97113 48696 97114 48410 97114 48598 97114 48609 97115 48600 97115 48599 97115 48599 97116 48600 97116 48709 97116 48599 97117 48709 97117 48601 97117 48601 97118 48709 97118 48707 97118 48601 97119 48707 97119 48602 97119 48602 97120 48707 97120 48706 97120 48602 97121 48706 97121 48603 97121 48603 97122 48706 97122 48604 97122 48603 97123 48604 97123 48605 97123 48605 97124 48604 97124 48606 97124 48605 97125 48606 97125 48400 97125 48400 97126 48606 97126 48408 97126 48610 97127 48600 97127 48609 97127 48607 97128 48608 97128 48612 97128 48609 97129 48632 97129 48610 97129 48610 97130 48632 97130 48611 97130 48610 97131 48611 97131 48612 97131 48612 97132 48611 97132 48634 97132 48612 97133 48634 97133 48607 97133 48607 97134 48613 97134 48608 97134 48608 97135 48613 97135 48614 97135 48608 97136 48614 97136 48618 97136 48625 97137 48615 97137 48617 97137 48617 97138 48615 97138 48616 97138 48617 97139 48616 97139 48631 97139 48631 97140 48616 97140 48618 97140 48631 97141 48618 97141 48629 97141 48629 97142 48618 97142 48614 97142 48620 97143 48696 97143 48695 97143 48421 97144 48425 97144 48420 97144 48420 97145 48425 97145 48596 97145 48420 97146 48596 97146 48619 97146 48619 97147 48596 97147 48620 97147 48619 97148 48620 97148 48694 97148 48694 97149 48620 97149 48695 97149 48661 97150 48602 97150 48621 97150 48621 97151 48602 97151 48603 97151 48621 97152 48603 97152 48622 97152 48622 97153 48603 97153 48605 97153 48622 97154 48605 97154 48660 97154 48660 97155 48605 97155 48623 97155 48623 97156 48605 97156 48400 97156 48623 97157 48400 97157 48624 97157 48380 97158 48625 97158 48626 97158 48626 97159 48625 97159 48617 97159 48626 97160 48617 97160 48627 97160 48627 97161 48617 97161 48631 97161 48613 97162 48607 97162 48637 97162 48637 97163 48628 97163 48613 97163 48613 97164 48628 97164 48328 97164 48613 97165 48328 97165 48614 97165 48614 97166 48328 97166 48322 97166 48614 97167 48322 97167 48629 97167 48629 97168 48322 97168 48320 97168 48629 97169 48320 97169 48631 97169 48631 97170 48320 97170 48630 97170 48631 97171 48630 97171 48627 97171 48609 97172 48366 97172 48632 97172 48632 97173 48366 97173 48633 97173 48632 97174 48633 97174 48611 97174 48633 97175 48329 97175 48611 97175 48611 97176 48329 97176 48326 97176 48611 97177 48326 97177 48634 97177 48634 97178 48326 97178 48635 97178 48634 97179 48635 97179 48607 97179 48607 97180 48635 97180 48636 97180 48607 97181 48636 97181 48637 97181 48366 97182 48609 97182 48638 97182 48638 97183 48609 97183 48599 97183 48638 97184 48599 97184 48639 97184 48639 97185 48599 97185 48601 97185 48639 97186 48601 97186 48661 97186 48661 97187 48601 97187 48602 97187 48640 97188 48410 97188 48641 97188 48640 97189 48641 97189 48642 97189 48642 97190 48641 97190 48597 97190 48642 97191 48597 97191 48379 97191 48379 97192 48597 97192 48625 97192 48379 97193 48625 97193 48380 97193 48643 97194 48398 97194 48356 97194 48389 97195 48643 97195 48679 97195 48385 97196 48654 97196 48387 97196 48387 97197 48654 97197 48645 97197 48387 97198 48645 97198 48644 97198 48644 97199 48645 97199 48646 97199 48644 97200 48646 97200 48388 97200 48388 97201 48646 97201 48371 97201 48651 97202 48377 97202 48647 97202 48655 97203 48648 97203 48649 97203 48649 97204 48648 97204 48650 97204 48649 97205 48650 97205 48651 97205 48651 97206 48650 97206 48381 97206 48651 97207 48381 97207 48377 97207 48653 97208 48654 97208 48652 97208 48652 97209 48654 97209 48385 97209 48652 97210 48385 97210 48680 97210 48653 97211 48655 97211 48654 97211 48654 97212 48655 97212 48649 97212 48654 97213 48649 97213 48645 97213 48645 97214 48649 97214 48651 97214 48645 97215 48651 97215 48646 97215 48646 97216 48651 97216 48647 97216 48646 97217 48647 97217 48371 97217 48685 97218 48656 97218 48653 97218 48653 97219 48656 97219 48686 97219 48653 97220 48686 97220 48655 97220 48657 97221 48389 97221 48658 97221 48658 97222 48389 97222 48679 97222 48658 97223 48679 97223 48681 97223 48681 97224 48679 97224 48682 97224 48672 97225 48683 97225 48659 97225 48621 97226 48622 97226 48683 97226 48683 97227 48622 97227 48660 97227 48683 97228 48660 97228 48659 97228 48659 97229 48660 97229 48623 97229 48659 97230 48623 97230 48675 97230 48362 97231 48661 97231 48684 97231 48684 97232 48661 97232 48621 97232 48640 97233 48384 97233 48662 97233 48640 97234 48662 97234 48406 97234 48406 97235 48662 97235 48663 97235 48406 97236 48663 97236 48405 97236 48405 97237 48663 97237 48404 97237 48404 97238 48663 97238 48664 97238 48404 97239 48664 97239 48403 97239 48623 97240 48624 97240 48675 97240 48675 97241 48624 97241 48399 97241 48675 97242 48399 97242 48664 97242 48664 97243 48399 97243 48665 97243 48664 97244 48665 97244 48403 97244 48672 97245 48673 97245 48666 97245 48666 97246 48673 97246 48674 97246 48666 97247 48674 97247 48667 97247 48667 97248 48674 97248 48668 97248 48667 97249 48668 97249 48669 97249 48669 97250 48668 97250 48676 97250 48669 97251 48676 97251 48670 97251 48670 97252 48676 97252 48677 97252 48670 97253 48677 97253 48687 97253 48687 97254 48677 97254 48678 97254 48687 97255 48678 97255 48671 97255 48672 97256 48659 97256 48673 97256 48673 97257 48659 97257 48675 97257 48673 97258 48675 97258 48674 97258 48674 97259 48675 97259 48664 97259 48674 97260 48664 97260 48668 97260 48668 97261 48664 97261 48663 97261 48668 97262 48663 97262 48676 97262 48676 97263 48663 97263 48662 97263 48676 97264 48662 97264 48677 97264 48677 97265 48662 97265 48384 97265 48677 97266 48384 97266 48678 97266 48643 97267 48356 97267 48679 97267 48679 97268 48356 97268 48355 97268 48679 97269 48355 97269 48682 97269 48682 97270 48355 97270 48354 97270 48682 97271 48354 97271 48360 97271 48680 97272 48657 97272 48652 97272 48652 97273 48657 97273 48658 97273 48652 97274 48658 97274 48653 97274 48653 97275 48658 97275 48681 97275 48653 97276 48681 97276 48685 97276 48685 97277 48681 97277 48682 97277 48685 97278 48682 97278 48684 97278 48684 97279 48682 97279 48360 97279 48684 97280 48360 97280 48362 97280 48621 97281 48683 97281 48684 97281 48684 97282 48683 97282 48672 97282 48684 97283 48672 97283 48685 97283 48685 97284 48672 97284 48666 97284 48685 97285 48666 97285 48656 97285 48656 97286 48666 97286 48667 97286 48656 97287 48667 97287 48686 97287 48686 97288 48667 97288 48669 97288 48686 97289 48669 97289 48655 97289 48655 97290 48669 97290 48670 97290 48655 97291 48670 97291 48648 97291 48648 97292 48670 97292 48687 97292 48648 97293 48687 97293 48650 97293 48650 97294 48687 97294 48671 97294 48650 97295 48671 97295 48381 97295 48688 97296 48429 97296 48690 97296 48445 97297 48689 97297 48693 97297 48690 97298 48691 97298 48688 97298 48688 97299 48691 97299 48440 97299 48688 97300 48440 97300 48693 97300 48693 97301 48440 97301 48692 97301 48693 97302 48692 97302 48445 97302 48434 97303 48694 97303 48435 97303 48435 97304 48694 97304 48695 97304 48435 97305 48695 97305 48438 97305 48438 97306 48695 97306 48696 97306 48438 97307 48696 97307 48697 97307 48697 97308 48696 97308 48702 97308 48697 97309 48702 97309 48698 97309 48698 97310 48702 97310 48689 97310 48698 97311 48689 97311 48699 97311 48699 97312 48689 97312 48445 97312 48430 97313 48701 97313 48700 97313 48700 97314 48701 97314 48710 97314 48700 97315 48710 97315 48431 97315 48431 97316 48710 97316 48711 97316 48431 97317 48711 97317 48423 97317 48423 97318 48711 97318 48704 97318 48409 97319 48689 97319 48702 97319 48696 97320 48598 97320 48702 97320 48702 97321 48598 97321 48411 97321 48702 97322 48411 97322 48409 97322 48615 97323 48425 97323 48705 97323 48409 97324 48703 97324 48689 97324 48689 97325 48703 97325 48408 97325 48689 97326 48408 97326 48693 97326 48600 97327 48610 97327 48711 97327 48711 97328 48610 97328 48612 97328 48711 97329 48612 97329 48704 97329 48704 97330 48612 97330 48608 97330 48704 97331 48608 97331 48424 97331 48424 97332 48608 97332 48618 97332 48424 97333 48618 97333 48705 97333 48705 97334 48618 97334 48616 97334 48705 97335 48616 97335 48615 97335 48408 97336 48606 97336 48693 97336 48693 97337 48606 97337 48604 97337 48693 97338 48604 97338 48688 97338 48688 97339 48604 97339 48706 97339 48688 97340 48706 97340 48429 97340 48429 97341 48706 97341 48707 97341 48429 97342 48707 97342 48708 97342 48708 97343 48707 97343 48709 97343 48708 97344 48709 97344 48701 97344 48701 97345 48709 97345 48600 97345 48701 97346 48600 97346 48710 97346 48710 97347 48600 97347 48711 97347 48694 97348 48434 97348 48428 97348 48694 97349 48428 97349 48619 97349 48619 97350 48428 97350 48419 97350 48619 97351 48419 97351 48420 97351 48712 97352 48933 97352 48713 97352 48713 97353 48933 97353 48715 97353 48713 97354 48715 97354 48714 97354 48714 97355 48715 97355 48902 97355 48718 97356 49117 97356 48716 97356 48720 97357 48717 97357 48931 97357 48716 97358 48738 97358 48718 97358 48718 97359 48738 97359 48719 97359 48718 97360 48719 97360 48931 97360 48931 97361 48719 97361 48741 97361 48931 97362 48741 97362 48720 97362 48720 97363 48734 97363 48717 97363 48717 97364 48734 97364 48723 97364 48717 97365 48723 97365 48722 97365 49114 97366 48940 97366 48731 97366 48731 97367 48940 97367 48938 97367 48731 97368 48938 97368 48721 97368 48721 97369 48938 97369 48722 97369 48721 97370 48722 97370 48735 97370 48735 97371 48722 97371 48723 97371 48727 97372 49115 97372 48918 97372 48911 97373 48725 97373 48724 97373 48724 97374 48725 97374 48726 97374 48724 97375 48726 97375 48942 97375 48942 97376 48726 97376 48727 97376 48942 97377 48727 97377 48728 97377 48728 97378 48727 97378 48918 97378 48855 97379 48712 97379 48788 97379 48788 97380 48712 97380 48713 97380 48788 97381 48713 97381 48729 97381 48729 97382 48713 97382 48714 97382 48729 97383 48714 97383 48762 97383 48748 97384 49114 97384 48730 97384 48730 97385 49114 97385 48731 97385 48730 97386 48731 97386 48737 97386 48737 97387 48731 97387 48721 97387 48734 97388 48720 97388 48827 97388 48827 97389 48732 97389 48734 97389 48734 97390 48732 97390 48733 97390 48734 97391 48733 97391 48723 97391 48723 97392 48733 97392 48823 97392 48723 97393 48823 97393 48735 97393 48735 97394 48823 97394 48736 97394 48735 97395 48736 97395 48721 97395 48721 97396 48736 97396 48821 97396 48721 97397 48821 97397 48737 97397 48716 97398 48861 97398 48738 97398 48738 97399 48861 97399 48828 97399 48738 97400 48828 97400 48719 97400 48828 97401 48739 97401 48719 97401 48719 97402 48739 97402 48740 97402 48719 97403 48740 97403 48741 97403 48741 97404 48740 97404 48742 97404 48741 97405 48742 97405 48720 97405 48720 97406 48742 97406 48824 97406 48720 97407 48824 97407 48827 97407 48861 97408 48716 97408 48856 97408 48856 97409 48716 97409 49116 97409 48856 97410 49116 97410 48743 97410 48743 97411 49116 97411 48744 97411 48743 97412 48744 97412 48855 97412 48855 97413 48744 97413 48712 97413 48745 97414 48901 97414 48746 97414 48745 97415 48746 97415 48871 97415 48871 97416 48746 97416 48747 97416 48871 97417 48747 97417 48873 97417 48873 97418 48747 97418 49114 97418 48873 97419 49114 97419 48748 97419 48780 97420 48891 97420 48749 97420 48881 97421 48780 97421 48781 97421 48879 97422 48752 97422 48880 97422 48880 97423 48752 97423 48754 97423 48880 97424 48754 97424 48750 97424 48750 97425 48754 97425 48751 97425 48750 97426 48751 97426 48863 97426 48863 97427 48751 97427 48867 97427 48755 97428 48875 97428 48868 97428 48795 97429 48796 97429 48753 97429 48753 97430 48796 97430 48798 97430 48753 97431 48798 97431 48755 97431 48755 97432 48798 97432 48876 97432 48755 97433 48876 97433 48875 97433 48756 97434 48752 97434 48783 97434 48783 97435 48752 97435 48879 97435 48783 97436 48879 97436 48782 97436 48756 97437 48795 97437 48752 97437 48752 97438 48795 97438 48753 97438 48752 97439 48753 97439 48754 97439 48754 97440 48753 97440 48755 97440 48754 97441 48755 97441 48751 97441 48751 97442 48755 97442 48868 97442 48751 97443 48868 97443 48867 97443 48785 97444 48792 97444 48756 97444 48756 97445 48792 97445 48793 97445 48756 97446 48793 97446 48795 97446 48757 97447 48881 97447 48758 97447 48758 97448 48881 97448 48781 97448 48758 97449 48781 97449 48784 97449 48784 97450 48781 97450 48759 97450 48760 97451 48775 97451 48774 97451 48789 97452 48761 97452 48774 97452 48788 97453 48729 97453 48761 97453 48761 97454 48729 97454 48762 97454 48761 97455 48762 97455 48774 97455 48774 97456 48762 97456 48894 97456 48774 97457 48894 97457 48760 97457 48787 97458 48855 97458 48763 97458 48763 97459 48855 97459 48788 97459 48895 97460 48898 97460 48764 97460 48764 97461 48898 97461 48765 97461 48764 97462 48765 97462 48766 97462 48766 97463 48765 97463 48745 97463 48766 97464 48745 97464 48779 97464 48895 97465 48764 97465 48896 97465 48896 97466 48764 97466 48767 97466 48896 97467 48767 97467 48897 97467 48775 97468 48760 97468 48767 97468 48767 97469 48760 97469 48768 97469 48767 97470 48768 97470 48897 97470 48789 97471 48776 97471 48790 97471 48790 97472 48776 97472 48769 97472 48790 97473 48769 97473 48791 97473 48791 97474 48769 97474 48770 97474 48791 97475 48770 97475 48794 97475 48794 97476 48770 97476 48777 97476 48794 97477 48777 97477 48771 97477 48771 97478 48777 97478 48778 97478 48771 97479 48778 97479 48773 97479 48773 97480 48778 97480 48772 97480 48773 97481 48772 97481 48797 97481 48789 97482 48774 97482 48776 97482 48776 97483 48774 97483 48775 97483 48776 97484 48775 97484 48769 97484 48769 97485 48775 97485 48767 97485 48769 97486 48767 97486 48770 97486 48770 97487 48767 97487 48764 97487 48770 97488 48764 97488 48777 97488 48777 97489 48764 97489 48766 97489 48777 97490 48766 97490 48778 97490 48778 97491 48766 97491 48779 97491 48778 97492 48779 97492 48772 97492 48780 97493 48749 97493 48781 97493 48781 97494 48749 97494 48850 97494 48781 97495 48850 97495 48759 97495 48759 97496 48850 97496 48854 97496 48759 97497 48854 97497 48786 97497 48782 97498 48757 97498 48783 97498 48783 97499 48757 97499 48758 97499 48783 97500 48758 97500 48756 97500 48756 97501 48758 97501 48784 97501 48756 97502 48784 97502 48785 97502 48785 97503 48784 97503 48759 97503 48785 97504 48759 97504 48763 97504 48763 97505 48759 97505 48786 97505 48763 97506 48786 97506 48787 97506 48788 97507 48761 97507 48763 97507 48763 97508 48761 97508 48789 97508 48763 97509 48789 97509 48785 97509 48785 97510 48789 97510 48790 97510 48785 97511 48790 97511 48792 97511 48792 97512 48790 97512 48791 97512 48792 97513 48791 97513 48793 97513 48793 97514 48791 97514 48794 97514 48793 97515 48794 97515 48795 97515 48795 97516 48794 97516 48771 97516 48795 97517 48771 97517 48796 97517 48796 97518 48771 97518 48773 97518 48796 97519 48773 97519 48798 97519 48798 97520 48773 97520 48797 97520 48798 97521 48797 97521 48876 97521 48828 97522 48861 97522 48829 97522 48799 97523 48800 97523 48801 97523 48802 97524 48857 97524 48809 97524 48803 97525 48818 97525 48804 97525 48804 97526 48818 97526 48805 97526 48804 97527 48805 97527 48807 97527 48807 97528 48805 97528 48806 97528 48807 97529 48806 97529 48808 97529 48830 97530 48809 97530 48849 97530 48882 97531 48883 97531 48810 97531 48810 97532 48883 97532 48811 97532 48811 97533 48883 97533 48884 97533 48811 97534 48884 97534 48801 97534 48801 97535 48800 97535 48811 97535 48811 97536 48800 97536 48843 97536 48811 97537 48843 97537 48810 97537 48884 97538 48812 97538 48801 97538 48801 97539 48812 97539 48813 97539 48801 97540 48813 97540 48799 97540 48799 97541 48813 97541 48814 97541 48799 97542 48814 97542 48815 97542 48815 97543 48814 97543 48816 97543 48815 97544 48816 97544 48817 97544 48817 97545 48816 97545 48819 97545 48817 97546 48819 97546 48870 97546 48812 97547 48808 97547 48813 97547 48813 97548 48808 97548 48806 97548 48813 97549 48806 97549 48814 97549 48814 97550 48806 97550 48805 97550 48814 97551 48805 97551 48816 97551 48816 97552 48805 97552 48818 97552 48816 97553 48818 97553 48819 97553 48730 97554 48737 97554 48820 97554 48820 97555 48737 97555 48821 97555 48820 97556 48821 97556 48822 97556 48822 97557 48821 97557 48736 97557 48822 97558 48736 97558 48836 97558 48836 97559 48736 97559 48823 97559 48836 97560 48823 97560 48825 97560 48862 97561 48874 97561 48820 97561 48820 97562 48874 97562 48748 97562 48820 97563 48748 97563 48730 97563 48826 97564 48824 97564 48839 97564 48839 97565 48824 97565 48742 97565 48839 97566 48742 97566 48740 97566 48823 97567 48733 97567 48825 97567 48825 97568 48733 97568 48732 97568 48825 97569 48732 97569 48826 97569 48826 97570 48732 97570 48827 97570 48826 97571 48827 97571 48824 97571 48740 97572 48739 97572 48839 97572 48839 97573 48739 97573 48828 97573 48839 97574 48828 97574 48841 97574 48841 97575 48828 97575 48829 97575 48841 97576 48829 97576 48859 97576 48809 97577 48830 97577 48802 97577 48802 97578 48830 97578 48842 97578 48802 97579 48842 97579 48840 97579 48840 97580 48842 97580 48844 97580 48840 97581 48844 97581 48838 97581 48838 97582 48844 97582 48845 97582 48838 97583 48845 97583 48831 97583 48831 97584 48845 97584 48846 97584 48831 97585 48846 97585 48837 97585 48837 97586 48846 97586 48832 97586 48837 97587 48832 97587 48833 97587 48833 97588 48832 97588 48847 97588 48833 97589 48847 97589 48835 97589 48835 97590 48847 97590 48834 97590 48835 97591 48834 97591 48862 97591 48862 97592 48820 97592 48835 97592 48835 97593 48820 97593 48822 97593 48835 97594 48822 97594 48833 97594 48833 97595 48822 97595 48836 97595 48833 97596 48836 97596 48837 97596 48837 97597 48836 97597 48825 97597 48837 97598 48825 97598 48831 97598 48831 97599 48825 97599 48826 97599 48831 97600 48826 97600 48838 97600 48838 97601 48826 97601 48839 97601 48838 97602 48839 97602 48840 97602 48840 97603 48839 97603 48841 97603 48840 97604 48841 97604 48802 97604 48802 97605 48841 97605 48859 97605 48802 97606 48859 97606 48857 97606 48849 97607 48882 97607 48830 97607 48830 97608 48882 97608 48810 97608 48830 97609 48810 97609 48842 97609 48842 97610 48810 97610 48843 97610 48842 97611 48843 97611 48844 97611 48844 97612 48843 97612 48800 97612 48844 97613 48800 97613 48845 97613 48845 97614 48800 97614 48799 97614 48845 97615 48799 97615 48846 97615 48846 97616 48799 97616 48815 97616 48846 97617 48815 97617 48832 97617 48832 97618 48815 97618 48817 97618 48832 97619 48817 97619 48847 97619 48847 97620 48817 97620 48870 97620 48847 97621 48870 97621 48834 97621 48851 97622 48848 97622 48858 97622 48853 97623 48849 97623 48809 97623 48749 97624 48891 97624 48890 97624 48854 97625 48850 97625 48851 97625 48851 97626 48850 97626 48749 97626 48749 97627 48890 97627 48851 97627 48851 97628 48890 97628 48888 97628 48851 97629 48888 97629 48848 97629 48848 97630 48888 97630 48852 97630 48848 97631 48852 97631 48853 97631 48787 97632 48786 97632 48860 97632 48860 97633 48786 97633 48854 97633 48855 97634 48787 97634 48743 97634 48743 97635 48787 97635 48860 97635 48743 97636 48860 97636 48856 97636 48853 97637 48809 97637 48848 97637 48848 97638 48809 97638 48857 97638 48848 97639 48857 97639 48858 97639 48858 97640 48857 97640 48859 97640 48858 97641 48859 97641 48829 97641 48854 97642 48851 97642 48860 97642 48860 97643 48851 97643 48858 97643 48860 97644 48858 97644 48856 97644 48856 97645 48858 97645 48829 97645 48856 97646 48829 97646 48861 97646 48874 97647 48862 97647 48872 97647 48887 97648 48864 97648 48869 97648 48803 97649 48886 97649 48818 97649 48818 97650 48886 97650 48866 97650 48863 97651 48867 97651 48889 97651 48889 97652 48867 97652 48864 97652 48878 97653 48877 97653 48865 97653 48865 97654 48877 97654 48866 97654 48864 97655 48867 97655 48869 97655 48869 97656 48867 97656 48868 97656 48869 97657 48868 97657 48875 97657 48886 97658 48887 97658 48866 97658 48866 97659 48887 97659 48869 97659 48866 97660 48869 97660 48865 97660 48865 97661 48869 97661 48875 97661 48862 97662 48834 97662 48877 97662 48877 97663 48834 97663 48870 97663 48877 97664 48870 97664 48866 97664 48866 97665 48870 97665 48819 97665 48866 97666 48819 97666 48818 97666 48871 97667 48873 97667 48872 97667 48872 97668 48873 97668 48748 97668 48872 97669 48748 97669 48874 97669 48875 97670 48876 97670 48865 97670 48865 97671 48876 97671 48797 97671 48865 97672 48797 97672 48878 97672 48878 97673 48797 97673 48772 97673 48878 97674 48772 97674 48779 97674 48862 97675 48877 97675 48872 97675 48872 97676 48877 97676 48878 97676 48872 97677 48878 97677 48871 97677 48871 97678 48878 97678 48779 97678 48871 97679 48779 97679 48745 97679 48892 97680 48863 97680 48889 97680 48892 97681 48782 97681 48879 97681 48879 97682 48880 97682 48892 97682 48892 97683 48880 97683 48750 97683 48892 97684 48750 97684 48863 97684 48780 97685 48881 97685 48892 97685 48892 97686 48881 97686 48757 97686 48892 97687 48757 97687 48782 97687 48885 97688 48849 97688 48853 97688 48882 97689 48849 97689 48883 97689 48883 97690 48849 97690 48885 97690 48883 97691 48885 97691 48884 97691 48803 97692 48804 97692 48885 97692 48885 97693 48804 97693 48807 97693 48807 97694 48808 97694 48885 97694 48885 97695 48808 97695 48812 97695 48885 97696 48812 97696 48884 97696 48803 97697 48885 97697 48886 97697 48886 97698 48885 97698 48853 97698 48886 97699 48853 97699 48887 97699 48887 97700 48853 97700 48852 97700 48887 97701 48852 97701 48864 97701 48864 97702 48852 97702 48888 97702 48864 97703 48888 97703 48889 97703 48889 97704 48888 97704 48890 97704 48889 97705 48890 97705 48892 97705 48892 97706 48890 97706 48891 97706 48892 97707 48891 97707 48780 97707 48762 97708 48714 97708 48894 97708 48894 97709 48714 97709 48893 97709 48894 97710 48893 97710 48760 97710 48760 97711 48893 97711 48904 97711 48895 97712 48896 97712 48899 97712 48899 97713 48896 97713 48897 97713 48899 97714 48897 97714 48904 97714 48904 97715 48897 97715 48768 97715 48904 97716 48768 97716 48760 97716 48895 97717 48899 97717 48898 97717 48898 97718 48899 97718 48900 97718 48898 97719 48900 97719 48765 97719 48765 97720 48900 97720 48901 97720 48765 97721 48901 97721 48745 97721 48714 97722 48902 97722 48893 97722 48893 97723 48902 97723 48903 97723 48893 97724 48903 97724 48904 97724 48904 97725 48903 97725 48905 97725 48904 97726 48905 97726 48899 97726 48899 97727 48905 97727 48926 97727 48899 97728 48926 97728 48900 97728 48900 97729 48926 97729 48930 97729 48900 97730 48930 97730 48901 97730 48901 97731 48930 97731 48928 97731 49006 97732 48910 97732 49007 97732 49007 97733 48910 97733 48907 97733 49007 97734 48907 97734 48906 97734 48906 97735 48907 97735 48908 97735 48906 97736 48908 97736 49009 97736 49009 97737 48908 97737 48909 97737 48909 97738 48908 97738 48943 97738 48909 97739 48943 97739 49003 97739 48907 97740 48910 97740 48937 97740 48724 97741 48943 97741 48911 97741 48911 97742 48943 97742 48908 97742 48911 97743 48908 97743 48725 97743 48725 97744 48908 97744 48907 97744 48725 97745 48907 97745 48939 97745 48939 97746 48907 97746 48937 97746 48912 97747 48913 97747 48914 97747 48963 97748 48927 97748 48932 97748 48914 97749 48915 97749 48912 97749 48912 97750 48915 97750 48959 97750 48912 97751 48959 97751 48932 97751 48932 97752 48959 97752 48960 97752 48932 97753 48960 97753 48963 97753 48952 97754 48728 97754 48916 97754 48916 97755 48728 97755 48918 97755 48916 97756 48918 97756 48917 97756 48917 97757 48918 97757 49115 97757 48917 97758 49115 97758 48957 97758 48957 97759 49115 97759 48929 97759 48957 97760 48929 97760 48919 97760 48919 97761 48929 97761 48927 97761 48919 97762 48927 97762 48920 97762 48920 97763 48927 97763 48963 97763 48922 97764 48937 97764 48910 97764 48910 97765 48921 97765 48922 97765 48922 97766 48921 97766 48950 97766 48922 97767 48950 97767 48936 97767 48945 97768 48935 97768 48924 97768 48924 97769 48935 97769 48923 97769 48924 97770 48923 97770 48925 97770 48925 97771 48923 97771 48936 97771 48925 97772 48936 97772 48947 97772 48947 97773 48936 97773 48950 97773 48932 97774 48927 97774 48903 97774 48929 97775 48926 97775 48927 97775 48927 97776 48926 97776 48905 97776 48927 97777 48905 97777 48903 97777 49115 97778 48928 97778 48929 97778 48929 97779 48928 97779 48930 97779 48929 97780 48930 97780 48926 97780 49117 97781 48718 97781 48936 97781 48936 97782 48718 97782 48931 97782 48936 97783 48931 97783 48922 97783 48922 97784 48931 97784 48717 97784 48922 97785 48717 97785 48937 97785 48903 97786 48902 97786 48932 97786 48932 97787 48902 97787 48715 97787 48932 97788 48715 97788 48912 97788 48912 97789 48715 97789 48933 97789 48912 97790 48933 97790 48913 97790 48913 97791 48933 97791 49119 97791 48913 97792 49119 97792 48934 97792 48934 97793 49119 97793 49118 97793 48934 97794 49118 97794 48935 97794 48935 97795 49118 97795 49117 97795 48935 97796 49117 97796 48923 97796 48923 97797 49117 97797 48936 97797 48717 97798 48722 97798 48937 97798 48937 97799 48722 97799 48938 97799 48937 97800 48938 97800 48939 97800 48939 97801 48938 97801 48940 97801 48939 97802 48940 97802 48725 97802 48728 97803 48952 97803 48941 97803 48728 97804 48941 97804 48942 97804 48942 97805 48941 97805 48943 97805 48942 97806 48943 97806 48724 97806 49003 97807 48943 97807 48968 97807 48968 97808 48943 97808 48941 97808 48968 97809 48941 97809 48970 97809 48952 97810 49058 97810 48941 97810 48941 97811 49058 97811 48944 97811 48941 97812 48944 97812 48970 97812 48914 97813 48913 97813 48981 97813 48981 97814 48913 97814 48934 97814 48981 97815 48934 97815 48945 97815 48945 97816 48934 97816 48935 97816 49113 97817 48945 97817 49001 97817 49001 97818 48945 97818 48924 97818 49001 97819 48924 97819 48946 97819 48946 97820 48924 97820 48925 97820 48946 97821 48925 97821 49000 97821 49000 97822 48925 97822 48947 97822 49000 97823 48947 97823 48948 97823 48948 97824 48947 97824 48950 97824 48948 97825 48950 97825 48998 97825 48998 97826 48950 97826 48949 97826 48949 97827 48950 97827 48921 97827 48949 97828 48921 97828 48951 97828 48951 97829 48921 97829 48910 97829 48951 97830 48910 97830 49006 97830 49058 97831 48952 97831 49052 97831 49052 97832 48952 97832 48916 97832 49052 97833 48916 97833 48953 97833 48953 97834 48916 97834 48917 97834 48963 97835 48954 97835 48920 97835 48920 97836 48954 97836 48955 97836 48920 97837 48955 97837 48919 97837 48919 97838 48955 97838 48956 97838 48919 97839 48956 97839 48957 97839 48957 97840 48956 97840 49055 97840 48957 97841 49055 97841 48917 97841 48917 97842 49055 97842 49054 97842 48917 97843 49054 97843 48953 97843 48914 97844 48958 97844 48915 97844 48915 97845 48958 97845 49034 97845 48915 97846 49034 97846 48959 97846 49034 97847 49061 97847 48959 97847 48959 97848 49061 97848 49060 97848 48959 97849 49060 97849 48960 97849 48960 97850 49060 97850 48961 97850 48960 97851 48961 97851 48963 97851 48963 97852 48961 97852 48962 97852 48963 97853 48962 97853 48954 97853 48964 97854 48965 97854 49041 97854 48965 97855 48964 97855 48966 97855 48967 97856 48971 97856 48974 97856 49020 97857 49003 97857 48968 97857 49032 97858 48969 97858 48967 97858 48967 97859 48969 97859 49020 97859 49020 97860 48968 97860 48967 97860 48967 97861 48968 97861 48970 97861 48967 97862 48970 97862 48971 97862 48971 97863 48970 97863 48944 97863 48971 97864 48944 97864 49058 97864 48988 97865 48989 97865 48975 97865 48975 97866 48989 97866 49032 97866 49058 97867 49057 97867 48971 97867 48971 97868 49057 97868 49070 97868 48971 97869 49070 97869 48974 97869 48974 97870 49070 97870 48972 97870 48974 97871 48972 97871 49086 97871 48977 97872 48988 97872 48973 97872 48973 97873 48988 97873 48975 97873 48973 97874 48975 97874 48964 97874 49032 97875 48967 97875 48975 97875 48975 97876 48967 97876 48974 97876 48975 97877 48974 97877 48964 97877 48964 97878 48974 97878 49086 97878 48964 97879 49086 97879 48966 97879 48976 97880 48977 97880 48978 97880 48978 97881 48977 97881 48973 97881 48978 97882 48973 97882 48979 97882 48979 97883 48973 97883 48964 97883 48979 97884 48964 97884 48980 97884 48980 97885 48964 97885 49041 97885 48958 97886 48914 97886 49100 97886 49100 97887 48914 97887 48981 97887 49100 97888 48981 97888 48982 97888 48982 97889 48981 97889 49112 97889 49112 97890 48981 97890 48945 97890 49112 97891 48945 97891 49113 97891 48993 97892 48984 97892 48995 97892 49091 97893 48983 97893 49025 97893 49091 97894 49025 97894 49092 97894 49087 97895 49088 97895 48984 97895 48984 97896 49088 97896 49089 97896 48984 97897 49089 97897 48995 97897 48995 97898 49089 97898 48985 97898 48995 97899 48985 97899 48986 97899 48977 97900 48987 97900 48988 97900 48988 97901 48987 97901 48990 97901 48988 97902 48990 97902 48989 97902 48989 97903 48990 97903 49033 97903 48992 97904 49033 97904 48993 97904 48993 97905 49033 97905 48990 97905 48993 97906 48990 97906 48984 97906 48984 97907 48990 97907 48987 97907 48984 97908 48987 97908 49087 97908 49087 97909 48987 97909 48977 97909 49087 97910 48977 97910 48976 97910 49027 97911 49025 97911 48991 97911 48991 97912 49025 97912 48983 97912 48991 97913 48983 97913 49023 97913 48992 97914 48993 97914 48994 97914 48994 97915 48993 97915 48995 97915 48994 97916 48995 97916 48996 97916 48996 97917 48995 97917 48986 97917 48996 97918 48986 97918 49029 97918 49029 97919 48986 97919 48997 97919 49029 97920 48997 97920 49026 97920 48949 97921 49004 97921 48998 97921 48998 97922 49004 97922 49015 97922 48998 97923 49015 97923 48948 97923 49028 97924 48999 97924 49015 97924 48948 97925 49015 97925 49000 97925 49000 97926 49015 97926 48999 97926 49000 97927 48999 97927 48946 97927 49111 97928 49113 97928 49002 97928 49002 97929 49113 97929 49001 97929 49002 97930 49001 97930 48946 97930 49003 97931 49020 97931 48909 97931 48909 97932 49020 97932 49019 97932 48909 97933 49019 97933 49009 97933 49009 97934 49019 97934 49008 97934 48949 97935 48951 97935 49004 97935 49004 97936 48951 97936 49006 97936 49004 97937 49006 97937 49005 97937 49005 97938 49006 97938 49007 97938 49005 97939 49007 97939 49008 97939 49008 97940 49007 97940 48906 97940 49008 97941 48906 97941 49009 97941 49028 97942 49016 97942 49010 97942 49010 97943 49016 97943 49017 97943 49010 97944 49017 97944 49011 97944 49011 97945 49017 97945 49012 97945 49011 97946 49012 97946 49030 97946 49030 97947 49012 97947 49013 97947 49030 97948 49013 97948 49014 97948 49014 97949 49013 97949 49018 97949 49014 97950 49018 97950 49031 97950 49031 97951 49018 97951 48969 97951 49031 97952 48969 97952 49032 97952 49028 97953 49015 97953 49016 97953 49016 97954 49015 97954 49004 97954 49016 97955 49004 97955 49017 97955 49017 97956 49004 97956 49005 97956 49017 97957 49005 97957 49012 97957 49012 97958 49005 97958 49008 97958 49012 97959 49008 97959 49013 97959 49013 97960 49008 97960 49019 97960 49013 97961 49019 97961 49018 97961 49018 97962 49019 97962 49020 97962 49018 97963 49020 97963 48969 97963 49021 97964 49027 97964 49022 97964 49022 97965 49027 97965 48991 97965 49022 97966 48991 97966 49103 97966 49103 97967 48991 97967 49023 97967 49103 97968 49023 97968 49098 97968 48985 97969 49024 97969 48986 97969 48986 97970 49024 97970 49092 97970 48986 97971 49092 97971 48997 97971 48997 97972 49092 97972 49025 97972 48997 97973 49025 97973 49026 97973 49026 97974 49025 97974 49027 97974 49026 97975 49027 97975 49002 97975 49002 97976 49027 97976 49021 97976 49002 97977 49021 97977 49111 97977 48946 97978 48999 97978 49002 97978 49002 97979 48999 97979 49028 97979 49002 97980 49028 97980 49026 97980 49026 97981 49028 97981 49010 97981 49026 97982 49010 97982 49029 97982 49029 97983 49010 97983 49011 97983 49029 97984 49011 97984 48996 97984 48996 97985 49011 97985 49030 97985 48996 97986 49030 97986 48994 97986 48994 97987 49030 97987 49014 97987 48994 97988 49014 97988 48992 97988 48992 97989 49014 97989 49031 97989 48992 97990 49031 97990 49033 97990 49033 97991 49031 97991 49032 97991 49033 97992 49032 97992 48989 97992 49034 97993 48958 97993 49099 97993 49035 97994 49036 97994 49037 97994 49075 97995 49078 97995 49108 97995 49049 97996 49039 97996 49038 97996 49038 97997 49039 97997 49040 97997 49038 97998 49040 97998 49042 97998 49042 97999 49040 97999 49041 97999 49042 98000 49041 98000 48965 98000 49079 98001 49108 98001 49094 98001 49043 98002 49045 98002 49044 98002 49044 98003 49045 98003 49096 98003 49044 98004 49096 98004 49046 98004 49046 98005 49096 98005 49093 98005 49046 98006 49093 98006 49037 98006 49037 98007 49036 98007 49046 98007 49046 98008 49036 98008 49081 98008 49046 98009 49081 98009 49044 98009 49093 98010 49047 98010 49037 98010 49037 98011 49047 98011 49050 98011 49037 98012 49050 98012 49035 98012 49035 98013 49050 98013 49048 98013 49035 98014 49048 98014 49083 98014 49083 98015 49048 98015 49051 98015 49083 98016 49051 98016 49085 98016 49085 98017 49051 98017 48966 98017 49085 98018 48966 98018 49086 98018 49047 98019 49049 98019 49050 98019 49050 98020 49049 98020 49038 98020 49050 98021 49038 98021 49048 98021 49048 98022 49038 98022 49042 98022 49048 98023 49042 98023 49051 98023 49051 98024 49042 98024 48965 98024 49051 98025 48965 98025 48966 98025 49052 98026 48953 98026 49053 98026 49053 98027 48953 98027 49054 98027 49053 98028 49054 98028 49071 98028 49071 98029 49054 98029 49055 98029 49071 98030 49055 98030 49056 98030 49056 98031 49055 98031 48956 98031 49056 98032 48956 98032 49059 98032 49070 98033 49057 98033 49053 98033 49053 98034 49057 98034 49058 98034 49053 98035 49058 98035 49052 98035 48956 98036 48955 98036 49059 98036 49059 98037 48955 98037 48954 98037 49059 98038 48954 98038 49073 98038 49073 98039 48954 98039 48962 98039 49073 98040 48962 98040 49062 98040 49062 98041 48962 98041 48961 98041 49062 98042 48961 98042 49060 98042 49060 98043 49061 98043 49062 98043 49062 98044 49061 98044 49034 98044 49062 98045 49034 98045 49076 98045 49076 98046 49034 98046 49099 98046 49076 98047 49099 98047 49077 98047 49108 98048 49079 98048 49075 98048 49075 98049 49079 98049 49080 98049 49075 98050 49080 98050 49063 98050 49063 98051 49080 98051 49064 98051 49063 98052 49064 98052 49074 98052 49074 98053 49064 98053 49082 98053 49074 98054 49082 98054 49065 98054 49065 98055 49082 98055 49066 98055 49065 98056 49066 98056 49067 98056 49067 98057 49066 98057 49068 98057 49067 98058 49068 98058 49072 98058 49072 98059 49068 98059 49084 98059 49072 98060 49084 98060 49069 98060 49069 98061 49084 98061 48972 98061 49069 98062 48972 98062 49070 98062 49070 98063 49053 98063 49069 98063 49069 98064 49053 98064 49071 98064 49069 98065 49071 98065 49072 98065 49072 98066 49071 98066 49056 98066 49072 98067 49056 98067 49067 98067 49067 98068 49056 98068 49059 98068 49067 98069 49059 98069 49065 98069 49065 98070 49059 98070 49073 98070 49065 98071 49073 98071 49074 98071 49074 98072 49073 98072 49062 98072 49074 98073 49062 98073 49063 98073 49063 98074 49062 98074 49076 98074 49063 98075 49076 98075 49075 98075 49075 98076 49076 98076 49077 98076 49075 98077 49077 98077 49078 98077 49094 98078 49043 98078 49079 98078 49079 98079 49043 98079 49044 98079 49079 98080 49044 98080 49080 98080 49080 98081 49044 98081 49081 98081 49080 98082 49081 98082 49064 98082 49064 98083 49081 98083 49036 98083 49064 98084 49036 98084 49082 98084 49082 98085 49036 98085 49035 98085 49082 98086 49035 98086 49066 98086 49066 98087 49035 98087 49083 98087 49066 98088 49083 98088 49068 98088 49068 98089 49083 98089 49085 98089 49068 98090 49085 98090 49084 98090 49084 98091 49085 98091 49086 98091 49084 98092 49086 98092 48972 98092 49095 98093 49094 98093 49097 98093 49090 98094 48976 98094 48978 98094 49087 98095 48976 98095 49088 98095 49088 98096 48976 98096 49090 98096 49088 98097 49090 98097 49089 98097 49089 98098 49090 98098 48985 98098 49023 98099 48983 98099 49090 98099 49090 98100 48983 98100 49091 98100 49091 98101 49092 98101 49090 98101 49090 98102 49092 98102 49024 98102 49090 98103 49024 98103 48985 98103 49049 98104 49047 98104 49095 98104 49095 98105 49047 98105 49093 98105 49043 98106 49094 98106 49045 98106 49045 98107 49094 98107 49095 98107 49045 98108 49095 98108 49096 98108 49096 98109 49095 98109 49093 98109 49041 98110 49040 98110 49095 98110 49095 98111 49040 98111 49039 98111 49095 98112 49039 98112 49049 98112 49041 98113 49095 98113 48980 98113 48980 98114 49095 98114 49097 98114 48980 98115 49097 98115 48979 98115 48979 98116 49097 98116 49106 98116 48979 98117 49106 98117 48978 98117 48978 98118 49106 98118 49105 98118 48978 98119 49105 98119 49090 98119 49090 98120 49105 98120 49098 98120 49090 98121 49098 98121 49023 98121 49099 98122 48958 98122 49100 98122 49078 98123 49077 98123 49101 98123 49111 98124 49021 98124 49110 98124 49022 98125 49103 98125 49102 98125 49103 98126 49098 98126 49102 98126 49102 98127 49098 98127 49105 98127 49102 98128 49105 98128 49104 98128 49104 98129 49105 98129 49106 98129 49104 98130 49106 98130 49107 98130 49107 98131 49106 98131 49097 98131 49107 98132 49097 98132 49108 98132 49108 98133 49097 98133 49094 98133 49108 98134 49078 98134 49107 98134 49107 98135 49078 98135 49101 98135 49107 98136 49101 98136 49104 98136 49104 98137 49101 98137 49109 98137 49104 98138 49109 98138 49102 98138 49102 98139 49109 98139 49110 98139 49102 98140 49110 98140 49022 98140 49022 98141 49110 98141 49021 98141 49077 98142 49099 98142 49101 98142 49101 98143 49099 98143 49100 98143 49101 98144 49100 98144 49109 98144 49109 98145 49100 98145 48982 98145 49109 98146 48982 98146 49110 98146 49110 98147 48982 98147 49112 98147 49110 98148 49112 98148 49111 98148 49111 98149 49112 98149 49113 98149 48725 98150 48940 98150 49114 98150 48725 98151 49114 98151 48726 98151 49114 98152 48747 98152 48726 98152 48726 98153 48747 98153 48746 98153 48726 98154 48746 98154 48727 98154 48727 98155 48746 98155 49115 98155 49115 98156 48746 98156 48901 98156 49115 98157 48901 98157 48928 98157 48716 98158 49117 98158 49116 98158 49116 98159 49117 98159 49118 98159 49116 98160 49118 98160 48744 98160 48744 98161 49118 98161 49119 98161 48744 98162 49119 98162 48712 98162 48712 98163 49119 98163 48933 98163 49125 98164 49368 98164 49120 98164 49120 98165 49368 98165 49378 98165 49120 98166 49378 98166 49346 98166 49338 98167 49342 98167 49136 98167 49136 98168 49342 98168 49343 98168 49136 98169 49343 98169 49121 98169 49121 98170 49343 98170 49122 98170 49121 98171 49122 98171 49123 98171 49123 98172 49122 98172 49124 98172 49123 98173 49124 98173 49125 98173 49125 98174 49124 98174 49344 98174 49125 98175 49344 98175 49368 98175 49338 98176 49136 98176 49126 98176 49126 98177 49136 98177 49135 98177 49126 98178 49135 98178 49127 98178 49127 98179 49135 98179 49128 98179 49127 98180 49128 98180 49129 98180 49129 98181 49128 98181 49130 98181 49129 98182 49130 98182 49131 98182 49131 98183 49130 98183 49132 98183 49131 98184 49132 98184 49133 98184 49498 98185 49132 98185 49500 98185 49500 98186 49132 98186 49130 98186 49500 98187 49130 98187 49134 98187 49130 98188 49128 98188 49134 98188 49134 98189 49128 98189 49135 98189 49134 98190 49135 98190 49501 98190 49501 98191 49135 98191 49136 98191 49501 98192 49136 98192 49503 98192 49120 98193 49506 98193 49125 98193 49125 98194 49506 98194 49504 98194 49125 98195 49504 98195 49123 98195 49123 98196 49504 98196 49503 98196 49123 98197 49503 98197 49121 98197 49121 98198 49503 98198 49136 98198 49137 98199 49527 98199 49138 98199 49138 98200 49527 98200 49140 98200 49138 98201 49140 98201 49193 98201 49193 98202 49140 98202 49139 98202 49193 98203 49139 98203 49192 98203 49527 98204 49313 98204 49140 98204 49140 98205 49313 98205 49141 98205 49140 98206 49141 98206 49139 98206 49139 98207 49141 98207 49312 98207 49159 98208 49142 98208 49160 98208 49142 98209 49159 98209 49232 98209 49153 98210 49147 98210 49150 98210 49206 98211 49192 98211 49515 98211 49143 98212 49207 98212 49153 98212 49153 98213 49207 98213 49206 98213 49206 98214 49515 98214 49153 98214 49153 98215 49515 98215 49517 98215 49153 98216 49517 98216 49147 98216 49147 98217 49517 98217 49144 98217 49147 98218 49144 98218 49238 98218 49169 98219 49145 98219 49152 98219 49152 98220 49145 98220 49143 98220 49238 98221 49146 98221 49147 98221 49147 98222 49146 98222 49148 98222 49147 98223 49148 98223 49150 98223 49150 98224 49148 98224 49149 98224 49150 98225 49149 98225 49154 98225 49151 98226 49169 98226 49157 98226 49157 98227 49169 98227 49152 98227 49157 98228 49152 98228 49159 98228 49143 98229 49153 98229 49152 98229 49152 98230 49153 98230 49150 98230 49152 98231 49150 98231 49159 98231 49159 98232 49150 98232 49154 98232 49159 98233 49154 98233 49232 98233 49155 98234 49151 98234 49156 98234 49156 98235 49151 98235 49157 98235 49156 98236 49157 98236 49158 98236 49158 98237 49157 98237 49159 98237 49158 98238 49159 98238 49277 98238 49277 98239 49159 98239 49160 98239 49283 98240 49217 98240 49161 98240 49283 98241 49161 98241 49162 98241 49162 98242 49161 98242 49163 98242 49162 98243 49163 98243 49296 98243 49296 98244 49163 98244 49164 98244 49296 98245 49164 98245 49165 98245 49172 98246 49166 98246 49178 98246 49270 98247 49175 98247 49188 98247 49270 98248 49188 98248 49187 98248 49174 98249 49267 98249 49166 98249 49166 98250 49267 98250 49167 98250 49166 98251 49167 98251 49178 98251 49178 98252 49167 98252 49268 98252 49178 98253 49268 98253 49179 98253 49151 98254 49168 98254 49169 98254 49169 98255 49168 98255 49173 98255 49169 98256 49173 98256 49145 98256 49145 98257 49173 98257 49171 98257 49170 98258 49171 98258 49172 98258 49172 98259 49171 98259 49173 98259 49172 98260 49173 98260 49166 98260 49166 98261 49173 98261 49168 98261 49166 98262 49168 98262 49174 98262 49174 98263 49168 98263 49151 98263 49174 98264 49151 98264 49155 98264 49191 98265 49188 98265 49208 98265 49208 98266 49188 98266 49175 98266 49208 98267 49175 98267 49210 98267 49170 98268 49172 98268 49176 98268 49176 98269 49172 98269 49178 98269 49176 98270 49178 98270 49177 98270 49177 98271 49178 98271 49179 98271 49177 98272 49179 98272 49212 98272 49212 98273 49179 98273 49189 98273 49212 98274 49189 98274 49190 98274 49180 98275 49196 98275 49519 98275 49519 98276 49196 98276 49183 98276 49519 98277 49183 98277 49181 98277 49211 98278 49182 98278 49183 98278 49522 98279 49184 98279 49185 98279 49185 98280 49184 98280 49186 98280 49181 98281 49183 98281 49520 98281 49520 98282 49183 98282 49182 98282 49520 98283 49182 98283 49186 98283 49268 98284 49271 98284 49179 98284 49179 98285 49271 98285 49187 98285 49179 98286 49187 98286 49189 98286 49189 98287 49187 98287 49188 98287 49189 98288 49188 98288 49190 98288 49190 98289 49188 98289 49191 98289 49190 98290 49191 98290 49185 98290 49192 98291 49206 98291 49193 98291 49193 98292 49206 98292 49205 98292 49198 98293 49525 98293 49194 98293 49194 98294 49525 98294 49137 98294 49194 98295 49137 98295 49205 98295 49205 98296 49137 98296 49138 98296 49205 98297 49138 98297 49193 98297 49180 98298 49195 98298 49196 98298 49196 98299 49195 98299 49197 98299 49196 98300 49197 98300 49198 98300 49198 98301 49197 98301 49524 98301 49198 98302 49524 98302 49525 98302 49211 98303 49200 98303 49199 98303 49199 98304 49200 98304 49201 98304 49199 98305 49201 98305 49213 98305 49213 98306 49201 98306 49204 98306 49213 98307 49204 98307 49214 98307 49214 98308 49204 98308 49202 98308 49214 98309 49202 98309 49215 98309 49215 98310 49202 98310 49203 98310 49215 98311 49203 98311 49216 98311 49216 98312 49203 98312 49207 98312 49216 98313 49207 98313 49143 98313 49211 98314 49183 98314 49200 98314 49200 98315 49183 98315 49196 98315 49200 98316 49196 98316 49201 98316 49201 98317 49196 98317 49198 98317 49201 98318 49198 98318 49204 98318 49204 98319 49198 98319 49194 98319 49204 98320 49194 98320 49202 98320 49202 98321 49194 98321 49205 98321 49202 98322 49205 98322 49203 98322 49203 98323 49205 98323 49206 98323 49203 98324 49206 98324 49207 98324 49165 98325 49522 98325 49295 98325 49295 98326 49522 98326 49185 98326 49295 98327 49185 98327 49285 98327 49285 98328 49185 98328 49191 98328 49285 98329 49191 98329 49286 98329 49286 98330 49191 98330 49208 98330 49286 98331 49208 98331 49209 98331 49209 98332 49208 98332 49210 98332 49209 98333 49210 98333 49281 98333 49186 98334 49182 98334 49185 98334 49185 98335 49182 98335 49211 98335 49185 98336 49211 98336 49190 98336 49190 98337 49211 98337 49199 98337 49190 98338 49199 98338 49212 98338 49212 98339 49199 98339 49213 98339 49212 98340 49213 98340 49177 98340 49177 98341 49213 98341 49214 98341 49177 98342 49214 98342 49176 98342 49176 98343 49214 98343 49215 98343 49176 98344 49215 98344 49170 98344 49170 98345 49215 98345 49216 98345 49170 98346 49216 98346 49171 98346 49171 98347 49216 98347 49143 98347 49171 98348 49143 98348 49145 98348 49244 98349 49217 98349 49282 98349 49228 98350 49264 98350 49222 98350 49247 98351 49284 98351 49218 98351 49272 98352 49276 98352 49219 98352 49219 98353 49276 98353 49275 98353 49219 98354 49275 98354 49233 98354 49233 98355 49275 98355 49160 98355 49233 98356 49160 98356 49142 98356 49246 98357 49218 98357 49290 98357 49273 98358 49274 98358 49225 98358 49225 98359 49274 98359 49220 98359 49225 98360 49220 98360 49223 98360 49223 98361 49220 98361 49221 98361 49223 98362 49221 98362 49222 98362 49222 98363 49264 98363 49223 98363 49223 98364 49264 98364 49224 98364 49223 98365 49224 98365 49225 98365 49221 98366 49226 98366 49222 98366 49222 98367 49226 98367 49227 98367 49222 98368 49227 98368 49228 98368 49228 98369 49227 98369 49230 98369 49228 98370 49230 98370 49229 98370 49229 98371 49230 98371 49231 98371 49229 98372 49231 98372 49266 98372 49266 98373 49231 98373 49232 98373 49266 98374 49232 98374 49154 98374 49226 98375 49272 98375 49227 98375 49227 98376 49272 98376 49219 98376 49227 98377 49219 98377 49230 98377 49230 98378 49219 98378 49233 98378 49230 98379 49233 98379 49231 98379 49231 98380 49233 98380 49142 98380 49231 98381 49142 98381 49232 98381 49239 98382 49528 98382 49234 98382 49234 98383 49528 98383 49235 98383 49234 98384 49235 98384 49257 98384 49257 98385 49235 98385 49236 98385 49257 98386 49236 98386 49258 98386 49258 98387 49236 98387 49237 98387 49258 98388 49237 98388 49260 98388 49148 98389 49146 98389 49234 98389 49234 98390 49146 98390 49238 98390 49234 98391 49238 98391 49239 98391 49241 98392 49242 98392 49261 98392 49261 98393 49242 98393 49534 98393 49261 98394 49534 98394 49240 98394 49237 98395 49529 98395 49260 98395 49260 98396 49529 98396 49531 98396 49260 98397 49531 98397 49241 98397 49241 98398 49531 98398 49536 98398 49241 98399 49536 98399 49242 98399 49240 98400 49243 98400 49261 98400 49261 98401 49243 98401 49244 98401 49261 98402 49244 98402 49245 98402 49245 98403 49244 98403 49282 98403 49245 98404 49282 98404 49262 98404 49218 98405 49246 98405 49247 98405 49247 98406 49246 98406 49263 98406 49247 98407 49263 98407 49248 98407 49248 98408 49263 98408 49249 98408 49248 98409 49249 98409 49250 98409 49250 98410 49249 98410 49251 98410 49250 98411 49251 98411 49252 98411 49252 98412 49251 98412 49253 98412 49252 98413 49253 98413 49259 98413 49259 98414 49253 98414 49265 98414 49259 98415 49265 98415 49254 98415 49254 98416 49265 98416 49255 98416 49254 98417 49255 98417 49256 98417 49256 98418 49255 98418 49149 98418 49256 98419 49149 98419 49148 98419 49148 98420 49234 98420 49256 98420 49256 98421 49234 98421 49257 98421 49256 98422 49257 98422 49254 98422 49254 98423 49257 98423 49258 98423 49254 98424 49258 98424 49259 98424 49259 98425 49258 98425 49260 98425 49259 98426 49260 98426 49252 98426 49252 98427 49260 98427 49241 98427 49252 98428 49241 98428 49250 98428 49250 98429 49241 98429 49261 98429 49250 98430 49261 98430 49248 98430 49248 98431 49261 98431 49245 98431 49248 98432 49245 98432 49247 98432 49247 98433 49245 98433 49262 98433 49247 98434 49262 98434 49284 98434 49290 98435 49273 98435 49246 98435 49246 98436 49273 98436 49225 98436 49246 98437 49225 98437 49263 98437 49263 98438 49225 98438 49224 98438 49263 98439 49224 98439 49249 98439 49249 98440 49224 98440 49264 98440 49249 98441 49264 98441 49251 98441 49251 98442 49264 98442 49228 98442 49251 98443 49228 98443 49253 98443 49253 98444 49228 98444 49229 98444 49253 98445 49229 98445 49265 98445 49265 98446 49229 98446 49266 98446 49265 98447 49266 98447 49255 98447 49255 98448 49266 98448 49154 98448 49255 98449 49154 98449 49149 98449 49278 98450 49290 98450 49279 98450 49269 98451 49155 98451 49156 98451 49174 98452 49155 98452 49267 98452 49267 98453 49155 98453 49269 98453 49267 98454 49269 98454 49167 98454 49167 98455 49269 98455 49268 98455 49210 98456 49175 98456 49269 98456 49269 98457 49175 98457 49270 98457 49270 98458 49187 98458 49269 98458 49269 98459 49187 98459 49271 98459 49269 98460 49271 98460 49268 98460 49272 98461 49226 98461 49278 98461 49278 98462 49226 98462 49221 98462 49273 98463 49290 98463 49274 98463 49274 98464 49290 98464 49278 98464 49274 98465 49278 98465 49220 98465 49220 98466 49278 98466 49221 98466 49160 98467 49275 98467 49278 98467 49278 98468 49275 98468 49276 98468 49278 98469 49276 98469 49272 98469 49160 98470 49278 98470 49277 98470 49277 98471 49278 98471 49279 98471 49277 98472 49279 98472 49158 98472 49158 98473 49279 98473 49288 98473 49158 98474 49288 98474 49156 98474 49156 98475 49288 98475 49280 98475 49156 98476 49280 98476 49269 98476 49269 98477 49280 98477 49281 98477 49269 98478 49281 98478 49210 98478 49282 98479 49217 98479 49283 98479 49284 98480 49262 98480 49291 98480 49295 98481 49285 98481 49293 98481 49286 98482 49209 98482 49292 98482 49209 98483 49281 98483 49292 98483 49292 98484 49281 98484 49280 98484 49292 98485 49280 98485 49287 98485 49287 98486 49280 98486 49288 98486 49287 98487 49288 98487 49289 98487 49289 98488 49288 98488 49279 98488 49289 98489 49279 98489 49218 98489 49218 98490 49279 98490 49290 98490 49218 98491 49284 98491 49289 98491 49289 98492 49284 98492 49291 98492 49289 98493 49291 98493 49287 98493 49287 98494 49291 98494 49294 98494 49287 98495 49294 98495 49292 98495 49292 98496 49294 98496 49293 98496 49292 98497 49293 98497 49286 98497 49286 98498 49293 98498 49285 98498 49262 98499 49282 98499 49291 98499 49291 98500 49282 98500 49283 98500 49291 98501 49283 98501 49294 98501 49294 98502 49283 98502 49162 98502 49294 98503 49162 98503 49293 98503 49293 98504 49162 98504 49296 98504 49293 98505 49296 98505 49295 98505 49295 98506 49296 98506 49165 98506 49488 98507 49297 98507 49336 98507 49488 98508 49336 98508 49298 98508 49336 98509 49335 98509 49298 98509 49298 98510 49335 98510 49333 98510 49298 98511 49333 98511 49311 98511 49311 98512 49333 98512 49487 98512 49487 98513 49333 98513 49132 98513 49487 98514 49132 98514 49498 98514 49299 98515 49509 98515 49300 98515 49300 98516 49509 98516 49301 98516 49300 98517 49301 98517 49332 98517 49332 98518 49301 98518 49302 98518 49332 98519 49302 98519 49315 98519 49315 98520 49302 98520 49507 98520 49315 98521 49507 98521 49120 98521 49120 98522 49507 98522 49506 98522 49305 98523 49509 98523 49299 98523 49303 98524 49304 98524 49496 98524 49299 98525 49324 98525 49305 98525 49305 98526 49324 98526 49326 98526 49305 98527 49326 98527 49496 98527 49496 98528 49326 98528 49306 98528 49496 98529 49306 98529 49303 98529 49303 98530 49317 98530 49304 98530 49304 98531 49317 98531 49319 98531 49304 98532 49319 98532 49308 98532 49336 98533 49297 98533 49316 98533 49316 98534 49297 98534 49307 98534 49316 98535 49307 98535 49309 98535 49309 98536 49307 98536 49308 98536 49309 98537 49308 98537 49310 98537 49310 98538 49308 98538 49319 98538 49311 98539 49487 98539 49314 98539 49312 98540 49141 98540 49313 98540 49313 98541 49488 98541 49312 98541 49312 98542 49488 98542 49298 98542 49312 98543 49298 98543 49514 98543 49514 98544 49298 98544 49311 98544 49514 98545 49311 98545 49512 98545 49512 98546 49311 98546 49314 98546 49120 98547 49346 98547 49315 98547 49315 98548 49346 98548 49331 98548 49407 98549 49336 98549 49408 98549 49408 98550 49336 98550 49316 98550 49408 98551 49316 98551 49403 98551 49403 98552 49316 98552 49309 98552 49317 98553 49303 98553 49410 98553 49410 98554 49409 98554 49317 98554 49317 98555 49409 98555 49318 98555 49317 98556 49318 98556 49319 98556 49319 98557 49318 98557 49320 98557 49319 98558 49320 98558 49310 98558 49310 98559 49320 98559 49321 98559 49310 98560 49321 98560 49309 98560 49309 98561 49321 98561 49322 98561 49309 98562 49322 98562 49403 98562 49299 98563 49323 98563 49324 98563 49324 98564 49323 98564 49325 98564 49324 98565 49325 98565 49326 98565 49325 98566 49327 98566 49326 98566 49326 98567 49327 98567 49328 98567 49326 98568 49328 98568 49306 98568 49306 98569 49328 98569 49329 98569 49306 98570 49329 98570 49303 98570 49303 98571 49329 98571 49411 98571 49303 98572 49411 98572 49410 98572 49323 98573 49299 98573 49446 98573 49446 98574 49299 98574 49300 98574 49446 98575 49300 98575 49330 98575 49330 98576 49300 98576 49332 98576 49330 98577 49332 98577 49331 98577 49331 98578 49332 98578 49315 98578 49133 98579 49132 98579 49333 98579 49133 98580 49333 98580 49334 98580 49334 98581 49333 98581 49335 98581 49334 98582 49335 98582 49459 98582 49459 98583 49335 98583 49336 98583 49459 98584 49336 98584 49407 98584 49480 98585 49437 98585 49337 98585 49368 98586 49344 98586 49369 98586 49338 98587 49126 98587 49339 98587 49339 98588 49126 98588 49127 98588 49339 98589 49127 98589 49340 98589 49338 98590 49339 98590 49342 98590 49342 98591 49339 98591 49341 98591 49342 98592 49341 98592 49343 98592 49343 98593 49341 98593 49370 98593 49343 98594 49370 98594 49122 98594 49369 98595 49344 98595 49370 98595 49370 98596 49344 98596 49124 98596 49370 98597 49124 98597 49122 98597 49378 98598 49368 98598 49345 98598 49331 98599 49346 98599 49440 98599 49440 98600 49346 98600 49347 98600 49469 98601 49480 98601 49348 98601 49357 98602 49349 98602 49467 98602 49467 98603 49349 98603 49350 98603 49467 98604 49350 98604 49468 98604 49468 98605 49350 98605 49351 98605 49468 98606 49351 98606 49465 98606 49465 98607 49351 98607 49450 98607 49354 98608 49352 98608 49453 98608 49381 98609 49383 98609 49353 98609 49353 98610 49383 98610 49355 98610 49353 98611 49355 98611 49354 98611 49354 98612 49355 98612 49461 98612 49354 98613 49461 98613 49352 98613 49374 98614 49349 98614 49356 98614 49356 98615 49349 98615 49357 98615 49356 98616 49357 98616 49466 98616 49374 98617 49381 98617 49349 98617 49349 98618 49381 98618 49353 98618 49349 98619 49353 98619 49350 98619 49350 98620 49353 98620 49354 98620 49350 98621 49354 98621 49351 98621 49351 98622 49354 98622 49453 98622 49351 98623 49453 98623 49450 98623 49376 98624 49379 98624 49374 98624 49374 98625 49379 98625 49358 98625 49374 98626 49358 98626 49381 98626 49471 98627 49469 98627 49373 98627 49373 98628 49469 98628 49348 98628 49373 98629 49348 98629 49375 98629 49375 98630 49348 98630 49359 98630 49127 98631 49129 98631 49340 98631 49340 98632 49129 98632 49131 98632 49340 98633 49131 98633 49360 98633 49360 98634 49131 98634 49133 98634 49360 98635 49133 98635 49464 98635 49345 98636 49371 98636 49361 98636 49361 98637 49371 98637 49363 98637 49361 98638 49363 98638 49362 98638 49362 98639 49363 98639 49364 98639 49362 98640 49364 98640 49380 98640 49380 98641 49364 98641 49365 98641 49380 98642 49365 98642 49382 98642 49382 98643 49365 98643 49366 98643 49382 98644 49366 98644 49384 98644 49384 98645 49366 98645 49463 98645 49384 98646 49463 98646 49367 98646 49368 98647 49369 98647 49345 98647 49345 98648 49369 98648 49370 98648 49345 98649 49370 98649 49371 98649 49371 98650 49370 98650 49341 98650 49371 98651 49341 98651 49363 98651 49363 98652 49341 98652 49339 98652 49363 98653 49339 98653 49364 98653 49364 98654 49339 98654 49340 98654 49364 98655 49340 98655 49365 98655 49365 98656 49340 98656 49360 98656 49365 98657 49360 98657 49366 98657 49366 98658 49360 98658 49464 98658 49366 98659 49464 98659 49463 98659 49480 98660 49337 98660 49348 98660 49348 98661 49337 98661 49372 98661 49348 98662 49372 98662 49359 98662 49359 98663 49372 98663 49439 98663 49359 98664 49439 98664 49377 98664 49466 98665 49471 98665 49356 98665 49356 98666 49471 98666 49373 98666 49356 98667 49373 98667 49374 98667 49374 98668 49373 98668 49375 98668 49374 98669 49375 98669 49376 98669 49376 98670 49375 98670 49359 98670 49376 98671 49359 98671 49347 98671 49347 98672 49359 98672 49377 98672 49347 98673 49377 98673 49440 98673 49346 98674 49378 98674 49347 98674 49347 98675 49378 98675 49345 98675 49347 98676 49345 98676 49376 98676 49376 98677 49345 98677 49361 98677 49376 98678 49361 98678 49379 98678 49379 98679 49361 98679 49362 98679 49379 98680 49362 98680 49358 98680 49358 98681 49362 98681 49380 98681 49358 98682 49380 98682 49381 98682 49381 98683 49380 98683 49382 98683 49381 98684 49382 98684 49383 98684 49383 98685 49382 98685 49384 98685 49383 98686 49384 98686 49355 98686 49355 98687 49384 98687 49367 98687 49355 98688 49367 98688 49461 98688 49325 98689 49323 98689 49447 98689 49431 98690 49385 98690 49392 98690 49428 98691 49444 98691 49436 98691 49386 98692 49449 98692 49387 98692 49387 98693 49449 98693 49388 98693 49387 98694 49388 98694 49389 98694 49389 98695 49388 98695 49401 98695 49389 98696 49401 98696 49400 98696 49413 98697 49436 98697 49429 98697 49472 98698 49473 98698 49390 98698 49390 98699 49473 98699 49393 98699 49393 98700 49473 98700 49391 98700 49393 98701 49391 98701 49392 98701 49392 98702 49385 98702 49393 98702 49393 98703 49385 98703 49394 98703 49393 98704 49394 98704 49390 98704 49391 98705 49395 98705 49392 98705 49392 98706 49395 98706 49396 98706 49392 98707 49396 98707 49431 98707 49431 98708 49396 98708 49397 98708 49431 98709 49397 98709 49398 98709 49398 98710 49397 98710 49402 98710 49398 98711 49402 98711 49433 98711 49433 98712 49402 98712 49399 98712 49433 98713 49399 98713 49457 98713 49395 98714 49400 98714 49396 98714 49396 98715 49400 98715 49401 98715 49396 98716 49401 98716 49397 98716 49397 98717 49401 98717 49388 98717 49397 98718 49388 98718 49402 98718 49402 98719 49388 98719 49449 98719 49402 98720 49449 98720 49399 98720 49408 98721 49403 98721 49421 98721 49421 98722 49403 98722 49322 98722 49421 98723 49322 98723 49404 98723 49404 98724 49322 98724 49321 98724 49404 98725 49321 98725 49423 98725 49423 98726 49321 98726 49320 98726 49423 98727 49320 98727 49405 98727 49406 98728 49448 98728 49421 98728 49421 98729 49448 98729 49407 98729 49421 98730 49407 98730 49408 98730 49424 98731 49411 98731 49426 98731 49426 98732 49411 98732 49329 98732 49426 98733 49329 98733 49328 98733 49320 98734 49318 98734 49405 98734 49405 98735 49318 98735 49409 98735 49405 98736 49409 98736 49424 98736 49424 98737 49409 98737 49410 98737 49424 98738 49410 98738 49411 98738 49328 98739 49327 98739 49426 98739 49426 98740 49327 98740 49325 98740 49426 98741 49325 98741 49427 98741 49427 98742 49325 98742 49447 98742 49427 98743 49447 98743 49412 98743 49436 98744 49413 98744 49428 98744 49428 98745 49413 98745 49414 98745 49428 98746 49414 98746 49415 98746 49415 98747 49414 98747 49416 98747 49415 98748 49416 98748 49425 98748 49425 98749 49416 98749 49430 98749 49425 98750 49430 98750 49417 98750 49417 98751 49430 98751 49432 98751 49417 98752 49432 98752 49418 98752 49418 98753 49432 98753 49419 98753 49418 98754 49419 98754 49422 98754 49422 98755 49419 98755 49434 98755 49422 98756 49434 98756 49420 98756 49420 98757 49434 98757 49455 98757 49420 98758 49455 98758 49406 98758 49406 98759 49421 98759 49420 98759 49420 98760 49421 98760 49404 98760 49420 98761 49404 98761 49422 98761 49422 98762 49404 98762 49423 98762 49422 98763 49423 98763 49418 98763 49418 98764 49423 98764 49405 98764 49418 98765 49405 98765 49417 98765 49417 98766 49405 98766 49424 98766 49417 98767 49424 98767 49425 98767 49425 98768 49424 98768 49426 98768 49425 98769 49426 98769 49415 98769 49415 98770 49426 98770 49427 98770 49415 98771 49427 98771 49428 98771 49428 98772 49427 98772 49412 98772 49428 98773 49412 98773 49444 98773 49429 98774 49472 98774 49413 98774 49413 98775 49472 98775 49390 98775 49413 98776 49390 98776 49414 98776 49414 98777 49390 98777 49394 98777 49414 98778 49394 98778 49416 98778 49416 98779 49394 98779 49385 98779 49416 98780 49385 98780 49430 98780 49430 98781 49385 98781 49431 98781 49430 98782 49431 98782 49432 98782 49432 98783 49431 98783 49398 98783 49432 98784 49398 98784 49419 98784 49419 98785 49398 98785 49433 98785 49419 98786 49433 98786 49434 98786 49434 98787 49433 98787 49457 98787 49434 98788 49457 98788 49455 98788 49435 98789 49443 98789 49445 98789 49442 98790 49429 98790 49436 98790 49337 98791 49437 98791 49438 98791 49439 98792 49372 98792 49435 98792 49435 98793 49372 98793 49337 98793 49337 98794 49438 98794 49435 98794 49435 98795 49438 98795 49479 98795 49435 98796 49479 98796 49443 98796 49443 98797 49479 98797 49477 98797 49443 98798 49477 98798 49442 98798 49440 98799 49377 98799 49441 98799 49441 98800 49377 98800 49439 98800 49331 98801 49440 98801 49330 98801 49330 98802 49440 98802 49441 98802 49330 98803 49441 98803 49446 98803 49442 98804 49436 98804 49443 98804 49443 98805 49436 98805 49444 98805 49443 98806 49444 98806 49445 98806 49445 98807 49444 98807 49412 98807 49445 98808 49412 98808 49447 98808 49439 98809 49435 98809 49441 98809 49441 98810 49435 98810 49445 98810 49441 98811 49445 98811 49446 98811 49446 98812 49445 98812 49447 98812 49446 98813 49447 98813 49323 98813 49448 98814 49406 98814 49460 98814 49476 98815 49478 98815 49454 98815 49386 98816 49475 98816 49449 98816 49449 98817 49475 98817 49458 98817 49465 98818 49450 98818 49451 98818 49451 98819 49450 98819 49478 98819 49452 98820 49456 98820 49462 98820 49462 98821 49456 98821 49458 98821 49478 98822 49450 98822 49454 98822 49454 98823 49450 98823 49453 98823 49454 98824 49453 98824 49352 98824 49475 98825 49476 98825 49458 98825 49458 98826 49476 98826 49454 98826 49458 98827 49454 98827 49462 98827 49462 98828 49454 98828 49352 98828 49406 98829 49455 98829 49456 98829 49456 98830 49455 98830 49457 98830 49456 98831 49457 98831 49458 98831 49458 98832 49457 98832 49399 98832 49458 98833 49399 98833 49449 98833 49334 98834 49459 98834 49460 98834 49460 98835 49459 98835 49407 98835 49460 98836 49407 98836 49448 98836 49352 98837 49461 98837 49462 98837 49462 98838 49461 98838 49367 98838 49462 98839 49367 98839 49452 98839 49452 98840 49367 98840 49463 98840 49452 98841 49463 98841 49464 98841 49406 98842 49456 98842 49460 98842 49460 98843 49456 98843 49452 98843 49460 98844 49452 98844 49334 98844 49334 98845 49452 98845 49464 98845 49334 98846 49464 98846 49133 98846 49470 98847 49465 98847 49451 98847 49470 98848 49466 98848 49357 98848 49357 98849 49467 98849 49470 98849 49470 98850 49467 98850 49468 98850 49470 98851 49468 98851 49465 98851 49480 98852 49469 98852 49470 98852 49470 98853 49469 98853 49471 98853 49470 98854 49471 98854 49466 98854 49474 98855 49429 98855 49442 98855 49472 98856 49429 98856 49473 98856 49473 98857 49429 98857 49474 98857 49473 98858 49474 98858 49391 98858 49386 98859 49387 98859 49474 98859 49474 98860 49387 98860 49389 98860 49389 98861 49400 98861 49474 98861 49474 98862 49400 98862 49395 98862 49474 98863 49395 98863 49391 98863 49386 98864 49474 98864 49475 98864 49475 98865 49474 98865 49442 98865 49475 98866 49442 98866 49476 98866 49476 98867 49442 98867 49477 98867 49476 98868 49477 98868 49478 98868 49478 98869 49477 98869 49479 98869 49478 98870 49479 98870 49451 98870 49451 98871 49479 98871 49438 98871 49451 98872 49438 98872 49470 98872 49470 98873 49438 98873 49437 98873 49470 98874 49437 98874 49480 98874 49508 98875 49161 98875 49505 98875 49505 98876 49161 98876 49532 98876 49505 98877 49532 98877 49481 98877 49532 98878 49482 98878 49481 98878 49481 98879 49482 98879 49533 98879 49481 98880 49533 98880 49502 98880 49502 98881 49533 98881 49535 98881 49502 98882 49535 98882 49483 98882 49483 98883 49535 98883 49530 98883 49483 98884 49530 98884 49499 98884 49499 98885 49530 98885 49484 98885 49499 98886 49484 98886 49486 98886 49513 98887 49512 98887 49485 98887 49485 98888 49512 98888 49314 98888 49485 98889 49314 98889 49486 98889 49486 98890 49314 98890 49487 98890 49486 98891 49487 98891 49499 98891 49526 98892 49497 98892 49527 98892 49527 98893 49497 98893 49488 98893 49527 98894 49488 98894 49313 98894 49526 98895 49523 98895 49497 98895 49497 98896 49523 98896 49489 98896 49497 98897 49489 98897 49491 98897 49489 98898 49490 98898 49491 98898 49491 98899 49490 98899 49492 98899 49491 98900 49492 98900 49511 98900 49164 98901 49493 98901 49521 98901 49521 98902 49493 98902 49510 98902 49521 98903 49510 98903 49494 98903 49494 98904 49510 98904 49511 98904 49494 98905 49511 98905 49495 98905 49495 98906 49511 98906 49492 98906 49297 98907 49488 98907 49497 98907 49509 98908 49305 98908 49511 98908 49511 98909 49305 98909 49496 98909 49511 98910 49496 98910 49491 98910 49496 98911 49304 98911 49491 98911 49491 98912 49304 98912 49308 98912 49491 98913 49308 98913 49497 98913 49497 98914 49308 98914 49307 98914 49497 98915 49307 98915 49297 98915 49501 98916 49502 98916 49483 98916 49487 98917 49498 98917 49499 98917 49499 98918 49498 98918 49500 98918 49499 98919 49500 98919 49483 98919 49483 98920 49500 98920 49134 98920 49483 98921 49134 98921 49501 98921 49501 98922 49503 98922 49502 98922 49502 98923 49503 98923 49504 98923 49502 98924 49504 98924 49481 98924 49481 98925 49504 98925 49506 98925 49481 98926 49506 98926 49505 98926 49505 98927 49506 98927 49507 98927 49505 98928 49507 98928 49508 98928 49508 98929 49507 98929 49302 98929 49508 98930 49302 98930 49518 98930 49518 98931 49302 98931 49301 98931 49518 98932 49301 98932 49493 98932 49493 98933 49301 98933 49509 98933 49493 98934 49509 98934 49510 98934 49510 98935 49509 98935 49511 98935 49512 98936 49513 98936 49516 98936 49512 98937 49516 98937 49514 98937 49514 98938 49516 98938 49139 98938 49514 98939 49139 98939 49312 98939 49192 98940 49139 98940 49515 98940 49515 98941 49139 98941 49516 98941 49515 98942 49516 98942 49517 98942 49513 98943 49238 98943 49516 98943 49516 98944 49238 98944 49144 98944 49516 98945 49144 98945 49517 98945 49161 98946 49508 98946 49163 98946 49163 98947 49508 98947 49518 98947 49163 98948 49518 98948 49164 98948 49164 98949 49518 98949 49493 98949 49195 98950 49180 98950 49489 98950 49489 98951 49180 98951 49490 98951 49490 98952 49180 98952 49519 98952 49490 98953 49519 98953 49492 98953 49492 98954 49519 98954 49181 98954 49492 98955 49181 98955 49495 98955 49495 98956 49181 98956 49520 98956 49495 98957 49520 98957 49494 98957 49494 98958 49520 98958 49186 98958 49494 98959 49186 98959 49521 98959 49521 98960 49186 98960 49184 98960 49521 98961 49184 98961 49164 98961 49164 98962 49184 98962 49522 98962 49164 98963 49522 98963 49165 98963 49195 98964 49489 98964 49197 98964 49197 98965 49489 98965 49523 98965 49197 98966 49523 98966 49524 98966 49524 98967 49523 98967 49526 98967 49524 98968 49526 98968 49525 98968 49525 98969 49526 98969 49527 98969 49525 98970 49527 98970 49137 98970 49238 98971 49513 98971 49239 98971 49239 98972 49513 98972 49485 98972 49239 98973 49485 98973 49528 98973 49528 98974 49485 98974 49486 98974 49528 98975 49486 98975 49235 98975 49235 98976 49486 98976 49484 98976 49235 98977 49484 98977 49236 98977 49236 98978 49484 98978 49530 98978 49236 98979 49530 98979 49237 98979 49237 98980 49530 98980 49529 98980 49529 98981 49530 98981 49531 98981 49531 98982 49530 98982 49535 98982 49531 98983 49535 98983 49536 98983 49161 98984 49217 98984 49532 98984 49532 98985 49217 98985 49244 98985 49532 98986 49244 98986 49482 98986 49244 98987 49243 98987 49482 98987 49482 98988 49243 98988 49240 98988 49482 98989 49240 98989 49533 98989 49533 98990 49240 98990 49534 98990 49533 98991 49534 98991 49535 98991 49535 98992 49534 98992 49242 98992 49535 98993 49242 98993 49536 98993 49537 98994 49681 98994 49550 98994 49550 98995 49932 98995 49537 98995 49537 98996 49932 98996 49538 98996 49537 98997 49538 98997 49624 98997 49624 98998 49538 98998 49931 98998 49624 98999 49931 98999 49539 98999 49539 99000 49931 99000 49930 99000 49539 99001 49930 99001 49622 99001 49622 99002 49930 99002 49928 99002 49622 99003 49928 99003 49631 99003 49631 99004 49928 99004 49630 99004 49630 99005 49928 99005 49540 99005 49630 99006 49540 99006 49629 99006 49540 99007 49926 99007 49629 99007 49629 99008 49926 99008 49924 99008 49629 99009 49924 99009 49627 99009 49627 99010 49924 99010 49541 99010 49541 99011 49924 99011 49922 99011 49541 99012 49922 99012 49542 99012 49543 99013 49544 99013 49666 99013 49666 99014 49544 99014 49545 99014 49666 99015 49545 99015 49659 99015 49659 99016 49545 99016 49918 99016 49659 99017 49918 99017 49546 99017 49546 99018 49918 99018 49936 99018 49570 99019 49919 99019 49917 99019 49570 99020 49917 99020 49547 99020 49547 99021 49917 99021 49548 99021 49547 99022 49548 99022 49549 99022 49549 99023 49548 99023 49550 99023 49549 99024 49550 99024 49681 99024 49551 99025 49699 99025 49594 99025 49564 99026 49551 99026 49565 99026 49687 99027 49552 99027 49553 99027 49553 99028 49552 99028 49554 99028 49553 99029 49554 99029 49688 99029 49688 99030 49554 99030 49555 99030 49688 99031 49555 99031 49689 99031 49689 99032 49555 99032 49676 99032 49562 99033 49678 99033 49677 99033 49560 99034 49556 99034 49561 99034 49561 99035 49556 99035 49557 99035 49561 99036 49557 99036 49562 99036 49562 99037 49557 99037 49558 99037 49562 99038 49558 99038 49678 99038 49598 99039 49552 99039 49559 99039 49559 99040 49552 99040 49687 99040 49559 99041 49687 99041 49596 99041 49598 99042 49560 99042 49552 99042 49552 99043 49560 99043 49561 99043 49552 99044 49561 99044 49554 99044 49554 99045 49561 99045 49562 99045 49554 99046 49562 99046 49555 99046 49555 99047 49562 99047 49677 99047 49555 99048 49677 99048 49676 99048 49603 99049 49604 99049 49598 99049 49598 99050 49604 99050 49605 99050 49598 99051 49605 99051 49560 99051 49597 99052 49564 99052 49563 99052 49563 99053 49564 99053 49565 99053 49563 99054 49565 99054 49599 99054 49599 99055 49565 99055 49566 99055 49602 99056 49576 99056 49586 99056 49938 99057 49601 99057 49567 99057 49567 99058 49601 99058 49658 99058 49567 99059 49658 99059 49546 99059 49591 99060 49568 99060 49569 99060 49569 99061 49568 99061 49570 99061 49569 99062 49570 99062 49685 99062 49571 99063 49572 99063 49573 99063 49573 99064 49572 99064 49574 99064 49573 99065 49574 99065 49591 99065 49591 99066 49574 99066 49575 99066 49591 99067 49575 99067 49568 99067 49938 99068 49940 99068 49576 99068 49576 99069 49940 99069 49577 99069 49576 99070 49577 99070 49586 99070 49586 99071 49577 99071 49578 99071 49586 99072 49578 99072 49588 99072 49588 99073 49578 99073 49944 99073 49588 99074 49944 99074 49573 99074 49573 99075 49944 99075 49579 99075 49573 99076 49579 99076 49571 99076 49602 99077 49580 99077 49581 99077 49581 99078 49580 99078 49587 99078 49581 99079 49587 99079 49582 99079 49582 99080 49587 99080 49589 99080 49582 99081 49589 99081 49583 99081 49583 99082 49589 99082 49590 99082 49583 99083 49590 99083 49584 99083 49584 99084 49590 99084 49592 99084 49584 99085 49592 99085 49585 99085 49585 99086 49592 99086 49593 99086 49585 99087 49593 99087 49606 99087 49602 99088 49586 99088 49580 99088 49580 99089 49586 99089 49588 99089 49580 99090 49588 99090 49587 99090 49587 99091 49588 99091 49573 99091 49587 99092 49573 99092 49589 99092 49589 99093 49573 99093 49591 99093 49589 99094 49591 99094 49590 99094 49590 99095 49591 99095 49569 99095 49590 99096 49569 99096 49592 99096 49592 99097 49569 99097 49685 99097 49592 99098 49685 99098 49593 99098 49551 99099 49594 99099 49565 99099 49565 99100 49594 99100 49595 99100 49565 99101 49595 99101 49566 99101 49566 99102 49595 99102 49655 99102 49566 99103 49655 99103 49600 99103 49596 99104 49597 99104 49559 99104 49559 99105 49597 99105 49563 99105 49559 99106 49563 99106 49598 99106 49598 99107 49563 99107 49599 99107 49598 99108 49599 99108 49603 99108 49603 99109 49599 99109 49566 99109 49603 99110 49566 99110 49601 99110 49601 99111 49566 99111 49600 99111 49601 99112 49600 99112 49658 99112 49938 99113 49576 99113 49601 99113 49601 99114 49576 99114 49602 99114 49601 99115 49602 99115 49603 99115 49603 99116 49602 99116 49581 99116 49603 99117 49581 99117 49604 99117 49604 99118 49581 99118 49582 99118 49604 99119 49582 99119 49605 99119 49605 99120 49582 99120 49583 99120 49605 99121 49583 99121 49560 99121 49560 99122 49583 99122 49584 99122 49560 99123 49584 99123 49556 99123 49556 99124 49584 99124 49585 99124 49556 99125 49585 99125 49557 99125 49557 99126 49585 99126 49606 99126 49557 99127 49606 99127 49558 99127 49632 99128 49543 99128 49668 99128 49613 99129 49607 99129 49612 99129 49646 99130 49663 99130 49661 99130 49694 99131 49673 99131 49608 99131 49608 99132 49673 99132 49619 99132 49608 99133 49619 99133 49692 99133 49692 99134 49619 99134 49617 99134 49692 99135 49617 99135 49616 99135 49647 99136 49661 99136 49609 99136 49690 99137 49691 99137 49648 99137 49648 99138 49691 99138 49610 99138 49610 99139 49691 99139 49611 99139 49610 99140 49611 99140 49612 99140 49612 99141 49607 99141 49610 99141 49610 99142 49607 99142 49649 99142 49610 99143 49649 99143 49648 99143 49611 99144 49693 99144 49612 99144 49612 99145 49693 99145 49614 99145 49612 99146 49614 99146 49613 99146 49613 99147 49614 99147 49618 99147 49613 99148 49618 99148 49651 99148 49651 99149 49618 99149 49615 99149 49651 99150 49615 99150 49652 99150 49652 99151 49615 99151 49620 99151 49652 99152 49620 99152 49654 99152 49693 99153 49616 99153 49614 99153 49614 99154 49616 99154 49617 99154 49614 99155 49617 99155 49618 99155 49618 99156 49617 99156 49619 99156 49618 99157 49619 99157 49615 99157 49615 99158 49619 99158 49673 99158 49615 99159 49673 99159 49620 99159 49621 99160 49622 99160 49631 99160 49621 99161 49631 99161 49623 99161 49622 99162 49621 99162 49539 99162 49539 99163 49621 99163 49641 99163 49539 99164 49641 99164 49624 99164 49624 99165 49641 99165 49625 99165 49624 99166 49625 99166 49537 99166 49681 99167 49537 99167 49682 99167 49682 99168 49537 99168 49625 99168 49682 99169 49625 99169 49684 99169 49542 99170 49626 99170 49541 99170 49541 99171 49626 99171 49645 99171 49541 99172 49645 99172 49627 99172 49627 99173 49645 99173 49628 99173 49627 99174 49628 99174 49629 99174 49629 99175 49628 99175 49623 99175 49629 99176 49623 99176 49630 99176 49630 99177 49623 99177 49631 99177 49664 99178 49626 99178 49668 99178 49668 99179 49626 99179 49542 99179 49668 99180 49542 99180 49632 99180 49661 99181 49647 99181 49646 99181 49646 99182 49647 99182 49633 99182 49646 99183 49633 99183 49634 99183 49634 99184 49633 99184 49635 99184 49634 99185 49635 99185 49644 99185 49644 99186 49635 99186 49650 99186 49644 99187 49650 99187 49643 99187 49643 99188 49650 99188 49636 99188 49643 99189 49636 99189 49642 99189 49642 99190 49636 99190 49637 99190 49642 99191 49637 99191 49640 99191 49640 99192 49637 99192 49653 99192 49640 99193 49653 99193 49638 99193 49638 99194 49653 99194 49639 99194 49638 99195 49639 99195 49684 99195 49684 99196 49625 99196 49638 99196 49638 99197 49625 99197 49641 99197 49638 99198 49641 99198 49640 99198 49640 99199 49641 99199 49621 99199 49640 99200 49621 99200 49642 99200 49642 99201 49621 99201 49623 99201 49642 99202 49623 99202 49643 99202 49643 99203 49623 99203 49628 99203 49643 99204 49628 99204 49644 99204 49644 99205 49628 99205 49645 99205 49644 99206 49645 99206 49634 99206 49634 99207 49645 99207 49626 99207 49634 99208 49626 99208 49646 99208 49646 99209 49626 99209 49664 99209 49646 99210 49664 99210 49663 99210 49609 99211 49690 99211 49647 99211 49647 99212 49690 99212 49648 99212 49647 99213 49648 99213 49633 99213 49633 99214 49648 99214 49649 99214 49633 99215 49649 99215 49635 99215 49635 99216 49649 99216 49607 99216 49635 99217 49607 99217 49650 99217 49650 99218 49607 99218 49613 99218 49650 99219 49613 99219 49636 99219 49636 99220 49613 99220 49651 99220 49636 99221 49651 99221 49637 99221 49637 99222 49651 99222 49652 99222 49637 99223 49652 99223 49653 99223 49653 99224 49652 99224 49654 99224 49653 99225 49654 99225 49639 99225 49657 99226 49662 99226 49667 99226 49660 99227 49609 99227 49661 99227 49594 99228 49699 99228 49656 99228 49655 99229 49595 99229 49657 99229 49657 99230 49595 99230 49594 99230 49594 99231 49656 99231 49657 99231 49657 99232 49656 99232 49697 99232 49657 99233 49697 99233 49662 99233 49662 99234 49697 99234 49696 99234 49662 99235 49696 99235 49660 99235 49658 99236 49600 99236 49665 99236 49665 99237 49600 99237 49655 99237 49546 99238 49658 99238 49659 99238 49659 99239 49658 99239 49665 99239 49659 99240 49665 99240 49666 99240 49660 99241 49661 99241 49662 99241 49662 99242 49661 99242 49663 99242 49662 99243 49663 99243 49667 99243 49667 99244 49663 99244 49664 99244 49667 99245 49664 99245 49668 99245 49655 99246 49657 99246 49665 99246 49665 99247 49657 99247 49667 99247 49665 99248 49667 99248 49666 99248 49666 99249 49667 99249 49668 99249 49666 99250 49668 99250 49543 99250 49682 99251 49684 99251 49680 99251 49669 99252 49670 99252 49671 99252 49694 99253 49672 99253 49673 99253 49673 99254 49672 99254 49675 99254 49689 99255 49676 99255 49698 99255 49698 99256 49676 99256 49670 99256 49674 99257 49679 99257 49683 99257 49683 99258 49679 99258 49675 99258 49670 99259 49676 99259 49671 99259 49671 99260 49676 99260 49677 99260 49671 99261 49677 99261 49678 99261 49672 99262 49669 99262 49675 99262 49675 99263 49669 99263 49671 99263 49675 99264 49671 99264 49683 99264 49683 99265 49671 99265 49678 99265 49684 99266 49639 99266 49679 99266 49679 99267 49639 99267 49654 99267 49679 99268 49654 99268 49675 99268 49675 99269 49654 99269 49620 99269 49675 99270 49620 99270 49673 99270 49547 99271 49549 99271 49680 99271 49680 99272 49549 99272 49681 99272 49680 99273 49681 99273 49682 99273 49678 99274 49558 99274 49683 99274 49683 99275 49558 99275 49606 99275 49683 99276 49606 99276 49674 99276 49674 99277 49606 99277 49593 99277 49674 99278 49593 99278 49685 99278 49684 99279 49679 99279 49680 99279 49680 99280 49679 99280 49674 99280 49680 99281 49674 99281 49547 99281 49547 99282 49674 99282 49685 99282 49547 99283 49685 99283 49570 99283 49686 99284 49689 99284 49698 99284 49686 99285 49596 99285 49687 99285 49687 99286 49553 99286 49686 99286 49686 99287 49553 99287 49688 99287 49686 99288 49688 99288 49689 99288 49551 99289 49564 99289 49686 99289 49686 99290 49564 99290 49597 99290 49686 99291 49597 99291 49596 99291 49695 99292 49609 99292 49660 99292 49690 99293 49609 99293 49691 99293 49691 99294 49609 99294 49695 99294 49691 99295 49695 99295 49611 99295 49694 99296 49608 99296 49695 99296 49695 99297 49608 99297 49692 99297 49692 99298 49616 99298 49695 99298 49695 99299 49616 99299 49693 99299 49695 99300 49693 99300 49611 99300 49694 99301 49695 99301 49672 99301 49672 99302 49695 99302 49660 99302 49672 99303 49660 99303 49669 99303 49669 99304 49660 99304 49696 99304 49669 99305 49696 99305 49670 99305 49670 99306 49696 99306 49697 99306 49670 99307 49697 99307 49698 99307 49698 99308 49697 99308 49656 99308 49698 99309 49656 99309 49686 99309 49686 99310 49656 99310 49699 99310 49686 99311 49699 99311 49551 99311 49544 99312 49543 99312 49922 99312 49922 99313 49543 99313 49632 99313 49922 99314 49632 99314 49542 99314 49922 99315 49700 99315 49544 99315 49544 99316 49700 99316 49735 99316 49705 99317 49861 99317 49718 99317 49856 99318 49855 99318 49720 99318 49720 99319 49855 99319 49702 99319 49720 99320 49702 99320 49701 99320 49701 99321 49702 99321 49703 99321 49701 99322 49703 99322 49857 99322 49718 99323 49861 99323 49720 99323 49720 99324 49861 99324 49704 99324 49720 99325 49704 99325 49856 99325 49705 99326 49718 99326 49706 99326 49706 99327 49718 99327 49707 99327 49706 99328 49707 99328 49708 99328 49707 99329 49717 99329 49708 99329 49708 99330 49717 99330 49716 99330 49708 99331 49716 99331 49709 99331 49709 99332 49716 99332 49715 99332 49709 99333 49715 99333 49862 99333 49862 99334 49715 99334 49865 99334 49715 99335 49713 99335 49865 99335 49865 99336 49713 99336 49712 99336 49865 99337 49712 99337 49710 99337 49714 99338 49711 99338 49712 99338 49717 99339 49741 99339 49743 99339 49712 99340 49713 99340 49714 99340 49714 99341 49713 99341 49715 99341 49714 99342 49715 99342 49743 99342 49743 99343 49715 99343 49716 99343 49743 99344 49716 99344 49717 99344 49717 99345 49707 99345 49741 99345 49741 99346 49707 99346 49718 99346 49741 99347 49718 99347 49719 99347 49719 99348 49718 99348 49720 99348 49719 99349 49720 99349 49721 99349 49721 99350 49720 99350 49701 99350 49721 99351 49701 99351 49935 99351 49749 99352 49722 99352 49723 99352 49723 99353 49722 99353 49724 99353 49723 99354 49724 99354 49701 99354 49701 99355 49724 99355 49935 99355 49730 99356 49737 99356 49734 99356 49725 99357 49751 99357 49727 99357 49727 99358 49751 99358 49726 99358 49727 99359 49726 99359 49728 99359 49728 99360 49726 99360 49729 99360 49728 99361 49729 99361 49734 99361 49734 99362 49729 99362 49762 99362 49734 99363 49762 99363 49730 99363 49730 99364 49760 99364 49737 99364 49737 99365 49760 99365 49733 99365 49737 99366 49733 99366 49736 99366 49782 99367 49756 99367 49757 99367 49757 99368 49756 99368 49748 99368 49757 99369 49748 99369 49731 99369 49731 99370 49748 99370 49736 99370 49731 99371 49736 99371 49732 99371 49732 99372 49736 99372 49733 99372 49933 99373 49728 99373 49734 99373 49925 99374 49737 99374 49736 99374 49735 99375 49700 99375 49736 99375 49736 99376 49700 99376 49923 99376 49736 99377 49923 99377 49925 99377 49925 99378 49927 99378 49737 99378 49737 99379 49927 99379 49929 99379 49737 99380 49929 99380 49734 99380 49734 99381 49929 99381 49934 99381 49734 99382 49934 99382 49933 99382 49721 99383 49738 99383 49719 99383 49719 99384 49738 99384 49739 99384 49719 99385 49739 99385 49741 99385 49741 99386 49739 99386 49740 99386 49740 99387 49920 99387 49741 99387 49741 99388 49920 99388 49742 99388 49741 99389 49742 99389 49743 99389 49743 99390 49742 99390 49744 99390 49743 99391 49744 99391 49714 99391 49714 99392 49744 99392 49921 99392 49714 99393 49921 99393 49711 99393 49711 99394 49921 99394 49745 99394 49711 99395 49745 99395 49746 99395 49746 99396 49745 99396 49747 99396 49746 99397 49747 99397 49756 99397 49756 99398 49747 99398 49735 99398 49756 99399 49735 99399 49748 99399 49748 99400 49735 99400 49736 99400 49722 99401 49749 99401 49753 99401 49722 99402 49753 99402 49750 99402 49750 99403 49753 99403 49751 99403 49750 99404 49751 99404 49725 99404 49809 99405 49751 99405 49767 99405 49767 99406 49751 99406 49753 99406 49767 99407 49753 99407 49768 99407 49749 99408 49752 99408 49753 99408 49753 99409 49752 99409 49754 99409 49753 99410 49754 99410 49768 99410 49712 99411 49711 99411 49755 99411 49755 99412 49711 99412 49746 99412 49755 99413 49746 99413 49782 99413 49782 99414 49746 99414 49756 99414 49726 99415 49751 99415 49809 99415 49818 99416 49782 99416 49792 99416 49792 99417 49782 99417 49757 99417 49792 99418 49757 99418 49793 99418 49793 99419 49757 99419 49758 99419 49757 99420 49731 99420 49758 99420 49758 99421 49731 99421 49732 99421 49758 99422 49732 99422 49825 99422 49730 99423 49759 99423 49760 99423 49760 99424 49759 99424 49825 99424 49760 99425 49825 99425 49733 99425 49733 99426 49825 99426 49732 99426 49809 99427 49817 99427 49726 99427 49726 99428 49817 99428 49761 99428 49726 99429 49761 99429 49729 99429 49729 99430 49761 99430 49785 99430 49729 99431 49785 99431 49762 99431 49762 99432 49785 99432 49763 99432 49762 99433 49763 99433 49730 99433 49730 99434 49763 99434 49783 99434 49730 99435 49783 99435 49759 99435 49752 99436 49749 99436 49764 99436 49764 99437 49749 99437 49723 99437 49764 99438 49723 99438 49765 99438 49765 99439 49723 99439 49701 99439 49765 99440 49701 99440 49857 99440 49781 99441 49841 99441 49840 99441 49841 99442 49781 99442 49778 99442 49766 99443 49770 99443 49775 99443 49808 99444 49809 99444 49767 99444 49774 99445 49805 99445 49766 99445 49766 99446 49805 99446 49808 99446 49808 99447 49767 99447 49766 99447 49766 99448 49767 99448 49768 99448 49766 99449 49768 99449 49770 99449 49770 99450 49768 99450 49754 99450 49770 99451 49754 99451 49752 99451 49803 99452 49804 99452 49776 99452 49776 99453 49804 99453 49774 99453 49752 99454 49769 99454 49770 99454 49770 99455 49769 99455 49771 99455 49770 99456 49771 99456 49775 99456 49775 99457 49771 99457 49772 99457 49775 99458 49772 99458 49777 99458 49779 99459 49803 99459 49773 99459 49773 99460 49803 99460 49776 99460 49773 99461 49776 99461 49781 99461 49774 99462 49766 99462 49776 99462 49776 99463 49766 99463 49775 99463 49776 99464 49775 99464 49781 99464 49781 99465 49775 99465 49777 99465 49781 99466 49777 99466 49778 99466 49889 99467 49779 99467 49887 99467 49887 99468 49779 99468 49773 99468 49887 99469 49773 99469 49780 99469 49780 99470 49773 99470 49781 99470 49780 99471 49781 99471 49898 99471 49898 99472 49781 99472 49840 99472 49710 99473 49712 99473 49902 99473 49902 99474 49712 99474 49755 99474 49902 99475 49755 99475 49912 99475 49912 99476 49755 99476 49914 99476 49914 99477 49755 99477 49782 99477 49914 99478 49782 99478 49818 99478 49783 99479 49763 99479 49784 99479 49785 99480 49761 99480 49786 99480 49799 99481 49794 99481 49796 99481 49894 99482 49893 99482 49790 99482 49890 99483 49823 99483 49821 99483 49799 99484 49891 99484 49794 99484 49794 99485 49891 99485 49787 99485 49794 99486 49787 99486 49890 99486 49789 99487 49888 99487 49833 99487 49833 99488 49888 99488 49788 99488 49833 99489 49788 99489 49831 99489 49833 99490 49835 99490 49789 99490 49789 99491 49835 99491 49779 99491 49789 99492 49779 99492 49889 99492 49788 99493 49894 99493 49831 99493 49831 99494 49894 99494 49790 99494 49831 99495 49790 99495 49830 99495 49830 99496 49790 99496 49800 99496 49830 99497 49800 99497 49828 99497 49828 99498 49800 99498 49791 99498 49828 99499 49791 99499 49827 99499 49827 99500 49791 99500 49801 99500 49827 99501 49801 99501 49826 99501 49792 99502 49793 99502 49798 99502 49798 99503 49793 99503 49824 99503 49890 99504 49821 99504 49794 99504 49794 99505 49821 99505 49795 99505 49794 99506 49795 99506 49796 99506 49796 99507 49795 99507 49798 99507 49796 99508 49798 99508 49797 99508 49797 99509 49798 99509 49824 99509 49797 99510 49824 99510 49802 99510 49893 99511 49891 99511 49790 99511 49790 99512 49891 99512 49799 99512 49790 99513 49799 99513 49800 99513 49800 99514 49799 99514 49796 99514 49800 99515 49796 99515 49791 99515 49791 99516 49796 99516 49797 99516 49791 99517 49797 99517 49801 99517 49801 99518 49797 99518 49802 99518 49801 99519 49802 99519 49826 99519 49783 99520 49784 99520 49759 99520 49803 99521 49834 99521 49804 99521 49804 99522 49834 99522 49814 99522 49804 99523 49814 99523 49774 99523 49774 99524 49814 99524 49806 99524 49774 99525 49806 99525 49805 99525 49805 99526 49806 99526 49807 99526 49805 99527 49807 99527 49808 99527 49808 99528 49807 99528 49810 99528 49808 99529 49810 99529 49809 99529 49809 99530 49810 99530 49817 99530 49763 99531 49785 99531 49784 99531 49784 99532 49785 99532 49786 99532 49784 99533 49786 99533 49811 99533 49811 99534 49786 99534 49812 99534 49811 99535 49812 99535 49829 99535 49829 99536 49812 99536 49816 99536 49829 99537 49816 99537 49813 99537 49813 99538 49816 99538 49815 99538 49813 99539 49815 99539 49832 99539 49834 99540 49832 99540 49814 99540 49814 99541 49832 99541 49815 99541 49814 99542 49815 99542 49806 99542 49806 99543 49815 99543 49816 99543 49806 99544 49816 99544 49807 99544 49807 99545 49816 99545 49812 99545 49807 99546 49812 99546 49810 99546 49810 99547 49812 99547 49786 99547 49810 99548 49786 99548 49817 99548 49817 99549 49786 99549 49761 99549 49818 99550 49792 99550 49819 99550 49819 99551 49792 99551 49798 99551 49819 99552 49798 99552 49909 99552 49909 99553 49798 99553 49795 99553 49909 99554 49795 99554 49820 99554 49820 99555 49795 99555 49821 99555 49820 99556 49821 99556 49822 99556 49822 99557 49821 99557 49823 99557 49822 99558 49823 99558 49903 99558 49793 99559 49758 99559 49824 99559 49824 99560 49758 99560 49825 99560 49824 99561 49825 99561 49802 99561 49802 99562 49825 99562 49759 99562 49802 99563 49759 99563 49826 99563 49826 99564 49759 99564 49784 99564 49826 99565 49784 99565 49827 99565 49827 99566 49784 99566 49811 99566 49827 99567 49811 99567 49828 99567 49828 99568 49811 99568 49829 99568 49828 99569 49829 99569 49830 99569 49830 99570 49829 99570 49813 99570 49830 99571 49813 99571 49831 99571 49831 99572 49813 99572 49832 99572 49831 99573 49832 99573 49833 99573 49833 99574 49832 99574 49834 99574 49833 99575 49834 99575 49835 99575 49835 99576 49834 99576 49803 99576 49835 99577 49803 99577 49779 99577 49865 99578 49710 99578 49866 99578 49764 99579 49765 99579 49858 99579 49885 99580 49884 99580 49844 99580 49836 99581 49907 99581 49867 99581 49850 99582 49837 99582 49851 99582 49851 99583 49837 99583 49838 99583 49851 99584 49838 99584 49839 99584 49839 99585 49838 99585 49840 99585 49839 99586 49840 99586 49841 99586 49868 99587 49867 99587 49842 99587 49878 99588 49895 99588 49879 99588 49879 99589 49895 99589 49896 99589 49879 99590 49896 99590 49843 99590 49843 99591 49896 99591 49845 99591 49843 99592 49845 99592 49844 99592 49844 99593 49884 99593 49843 99593 49843 99594 49884 99594 49881 99594 49843 99595 49881 99595 49879 99595 49845 99596 49846 99596 49844 99596 49844 99597 49846 99597 49847 99597 49844 99598 49847 99598 49885 99598 49885 99599 49847 99599 49852 99599 49885 99600 49852 99600 49848 99600 49848 99601 49852 99601 49853 99601 49848 99602 49853 99602 49849 99602 49849 99603 49853 99603 49778 99603 49849 99604 49778 99604 49777 99604 49846 99605 49850 99605 49847 99605 49847 99606 49850 99606 49851 99606 49847 99607 49851 99607 49852 99607 49852 99608 49851 99608 49839 99608 49852 99609 49839 99609 49853 99609 49853 99610 49839 99610 49841 99610 49853 99611 49841 99611 49778 99611 49860 99612 49876 99612 49704 99612 49703 99613 49702 99613 49854 99613 49854 99614 49702 99614 49855 99614 49854 99615 49855 99615 49876 99615 49876 99616 49855 99616 49856 99616 49876 99617 49856 99617 49704 99617 49858 99618 49765 99618 49854 99618 49854 99619 49765 99619 49857 99619 49854 99620 49857 99620 49703 99620 49771 99621 49769 99621 49858 99621 49858 99622 49769 99622 49752 99622 49858 99623 49752 99623 49764 99623 49859 99624 49708 99624 49863 99624 49863 99625 49708 99625 49709 99625 49704 99626 49861 99626 49860 99626 49860 99627 49861 99627 49705 99627 49860 99628 49705 99628 49859 99628 49859 99629 49705 99629 49706 99629 49859 99630 49706 99630 49708 99630 49709 99631 49862 99631 49863 99631 49863 99632 49862 99632 49865 99632 49863 99633 49865 99633 49864 99633 49864 99634 49865 99634 49866 99634 49864 99635 49866 99635 49910 99635 49867 99636 49868 99636 49836 99636 49836 99637 49868 99637 49880 99637 49836 99638 49880 99638 49869 99638 49869 99639 49880 99639 49882 99639 49869 99640 49882 99640 49870 99640 49870 99641 49882 99641 49883 99641 49870 99642 49883 99642 49877 99642 49877 99643 49883 99643 49871 99643 49877 99644 49871 99644 49872 99644 49872 99645 49871 99645 49874 99645 49872 99646 49874 99646 49873 99646 49873 99647 49874 99647 49886 99647 49873 99648 49886 99648 49875 99648 49875 99649 49886 99649 49772 99649 49875 99650 49772 99650 49771 99650 49771 99651 49858 99651 49875 99651 49875 99652 49858 99652 49854 99652 49875 99653 49854 99653 49873 99653 49873 99654 49854 99654 49876 99654 49873 99655 49876 99655 49872 99655 49872 99656 49876 99656 49860 99656 49872 99657 49860 99657 49877 99657 49877 99658 49860 99658 49859 99658 49877 99659 49859 99659 49870 99659 49870 99660 49859 99660 49863 99660 49870 99661 49863 99661 49869 99661 49869 99662 49863 99662 49864 99662 49869 99663 49864 99663 49836 99663 49836 99664 49864 99664 49910 99664 49836 99665 49910 99665 49907 99665 49842 99666 49878 99666 49868 99666 49868 99667 49878 99667 49879 99667 49868 99668 49879 99668 49880 99668 49880 99669 49879 99669 49881 99669 49880 99670 49881 99670 49882 99670 49882 99671 49881 99671 49884 99671 49882 99672 49884 99672 49883 99672 49883 99673 49884 99673 49885 99673 49883 99674 49885 99674 49871 99674 49871 99675 49885 99675 49848 99675 49871 99676 49848 99676 49874 99676 49874 99677 49848 99677 49849 99677 49874 99678 49849 99678 49886 99678 49886 99679 49849 99679 49777 99679 49886 99680 49777 99680 49772 99680 49897 99681 49842 99681 49899 99681 49892 99682 49889 99682 49887 99682 49789 99683 49889 99683 49888 99683 49888 99684 49889 99684 49892 99684 49888 99685 49892 99685 49788 99685 49788 99686 49892 99686 49894 99686 49823 99687 49890 99687 49892 99687 49892 99688 49890 99688 49787 99688 49787 99689 49891 99689 49892 99689 49892 99690 49891 99690 49893 99690 49892 99691 49893 99691 49894 99691 49850 99692 49846 99692 49897 99692 49897 99693 49846 99693 49845 99693 49878 99694 49842 99694 49895 99694 49895 99695 49842 99695 49897 99695 49895 99696 49897 99696 49896 99696 49896 99697 49897 99697 49845 99697 49840 99698 49838 99698 49897 99698 49897 99699 49838 99699 49837 99699 49897 99700 49837 99700 49850 99700 49840 99701 49897 99701 49898 99701 49898 99702 49897 99702 49899 99702 49898 99703 49899 99703 49780 99703 49780 99704 49899 99704 49900 99704 49780 99705 49900 99705 49887 99705 49887 99706 49900 99706 49901 99706 49887 99707 49901 99707 49892 99707 49892 99708 49901 99708 49903 99708 49892 99709 49903 99709 49823 99709 49866 99710 49710 99710 49902 99710 49907 99711 49910 99711 49911 99711 49819 99712 49909 99712 49913 99712 49820 99713 49822 99713 49904 99713 49822 99714 49903 99714 49904 99714 49904 99715 49903 99715 49901 99715 49904 99716 49901 99716 49905 99716 49905 99717 49901 99717 49900 99717 49905 99718 49900 99718 49906 99718 49906 99719 49900 99719 49899 99719 49906 99720 49899 99720 49867 99720 49867 99721 49899 99721 49842 99721 49867 99722 49907 99722 49906 99722 49906 99723 49907 99723 49911 99723 49906 99724 49911 99724 49905 99724 49905 99725 49911 99725 49908 99725 49905 99726 49908 99726 49904 99726 49904 99727 49908 99727 49913 99727 49904 99728 49913 99728 49820 99728 49820 99729 49913 99729 49909 99729 49910 99730 49866 99730 49911 99730 49911 99731 49866 99731 49902 99731 49911 99732 49902 99732 49908 99732 49908 99733 49902 99733 49912 99733 49908 99734 49912 99734 49913 99734 49913 99735 49912 99735 49914 99735 49913 99736 49914 99736 49819 99736 49819 99737 49914 99737 49818 99737 49728 99738 49933 99738 49550 99738 49728 99739 49550 99739 49915 99739 49550 99740 49548 99740 49915 99740 49915 99741 49548 99741 49917 99741 49915 99742 49917 99742 49916 99742 49916 99743 49917 99743 49721 99743 49721 99744 49917 99744 49919 99744 49721 99745 49919 99745 49738 99745 49544 99746 49735 99746 49545 99746 49545 99747 49735 99747 49747 99747 49545 99748 49747 99748 49918 99748 49918 99749 49747 99749 49745 99749 49918 99750 49745 99750 49936 99750 49936 99751 49745 99751 49921 99751 49739 99752 49738 99752 49919 99752 49945 99753 49920 99753 49740 99753 49919 99754 49946 99754 49739 99754 49739 99755 49946 99755 49947 99755 49739 99756 49947 99756 49740 99756 49740 99757 49947 99757 49948 99757 49740 99758 49948 99758 49945 99758 49945 99759 49942 99759 49920 99759 49920 99760 49942 99760 49943 99760 49920 99761 49943 99761 49742 99761 49936 99762 49921 99762 49937 99762 49937 99763 49921 99763 49744 99763 49937 99764 49744 99764 49941 99764 49941 99765 49744 99765 49742 99765 49941 99766 49742 99766 49939 99766 49939 99767 49742 99767 49943 99767 49700 99768 49922 99768 49923 99768 49923 99769 49922 99769 49924 99769 49923 99770 49924 99770 49925 99770 49924 99771 49926 99771 49925 99771 49925 99772 49926 99772 49540 99772 49925 99773 49540 99773 49927 99773 49927 99774 49540 99774 49928 99774 49927 99775 49928 99775 49929 99775 49928 99776 49930 99776 49929 99776 49929 99777 49930 99777 49931 99777 49929 99778 49931 99778 49934 99778 49550 99779 49933 99779 49932 99779 49932 99780 49933 99780 49934 99780 49932 99781 49934 99781 49538 99781 49538 99782 49934 99782 49931 99782 49935 99783 49724 99783 49722 99783 49727 99784 49728 99784 49725 99784 49725 99785 49728 99785 49915 99785 49725 99786 49915 99786 49750 99786 49750 99787 49915 99787 49916 99787 49750 99788 49916 99788 49722 99788 49722 99789 49916 99789 49721 99789 49722 99790 49721 99790 49935 99790 49946 99791 49919 99791 49570 99791 49546 99792 49936 99792 49567 99792 49567 99793 49936 99793 49937 99793 49567 99794 49937 99794 49938 99794 49938 99795 49937 99795 49940 99795 49943 99796 49577 99796 49939 99796 49939 99797 49577 99797 49940 99797 49939 99798 49940 99798 49941 99798 49941 99799 49940 99799 49937 99799 49945 99800 49579 99800 49942 99800 49942 99801 49579 99801 49944 99801 49942 99802 49944 99802 49943 99802 49943 99803 49944 99803 49578 99803 49943 99804 49578 99804 49577 99804 49575 99805 49574 99805 49948 99805 49948 99806 49574 99806 49572 99806 49948 99807 49572 99807 49945 99807 49945 99808 49572 99808 49571 99808 49945 99809 49571 99809 49579 99809 49570 99810 49568 99810 49946 99810 49946 99811 49568 99811 49575 99811 49946 99812 49575 99812 49947 99812 49947 99813 49575 99813 49948 99813 54814 99814 49949 99814 54813 99814 54813 99815 49949 99815 51555 99815 54813 99816 51555 99816 49950 99816 49950 99817 51555 99817 51556 99817 49950 99818 51556 99818 54809 99818 54809 99819 51556 99819 49951 99819 54809 99820 49951 99820 54808 99820 54808 99821 49951 99821 49952 99821 54808 99822 49952 99822 54810 99822 54810 99823 49952 99823 51559 99823 54810 99824 51559 99824 54811 99824 54811 99825 51559 99825 49953 99825 54811 99826 49953 99826 54812 99826 54812 99827 49953 99827 49954 99827 54812 99828 49954 99828 49955 99828 49955 99829 49954 99829 49956 99829 49955 99830 49956 99830 49957 99830 49957 99831 49956 99831 54731 99831 49957 99832 54731 99832 49958 99832 49958 99833 54731 99833 54732 99833 49958 99834 54732 99834 54815 99834 54815 99835 54732 99835 54733 99835 54815 99836 54733 99836 54814 99836 54814 99837 54733 99837 49949 99837 54805 99838 54736 99838 54804 99838 54804 99839 54736 99839 49960 99839 54804 99840 49960 99840 49959 99840 49959 99841 49960 99841 49961 99841 49959 99842 49961 99842 54807 99842 54807 99843 49961 99843 51552 99843 54807 99844 51552 99844 49962 99844 49962 99845 51552 99845 49963 99845 49962 99846 49963 99846 54802 99846 54802 99847 49963 99847 51554 99847 54802 99848 51554 99848 54803 99848 54803 99849 51554 99849 49964 99849 54803 99850 49964 99850 49965 99850 49965 99851 49964 99851 54734 99851 49965 99852 54734 99852 54801 99852 54801 99853 54734 99853 49967 99853 54801 99854 49967 99854 49966 99854 49966 99855 49967 99855 49968 99855 49966 99856 49968 99856 49969 99856 49969 99857 49968 99857 54735 99857 49969 99858 54735 99858 54806 99858 54806 99859 54735 99859 49970 99859 54806 99860 49970 99860 54805 99860 54805 99861 49970 99861 54736 99861 49981 99862 49971 99862 49983 99862 49972 99863 53972 99863 54406 99863 49985 99864 49973 99864 51844 99864 51844 99865 49973 99865 51843 99865 49984 99866 49974 99866 49975 99866 49975 99867 49974 99867 49976 99867 49975 99868 49976 99868 51849 99868 51849 99869 49976 99869 49990 99869 51849 99870 49990 99870 51848 99870 49982 99871 49971 99871 49977 99871 49977 99872 49971 99872 49981 99872 49977 99873 49981 99873 49978 99873 49985 99874 49972 99874 49973 99874 49973 99875 49972 99875 54406 99875 49973 99876 54406 99876 49983 99876 49983 99877 54406 99877 49979 99877 49983 99878 49979 99878 49981 99878 49981 99879 49979 99879 49980 99879 49981 99880 49980 99880 49978 99880 49982 99881 49990 99881 49971 99881 49971 99882 49990 99882 49976 99882 49971 99883 49976 99883 49983 99883 49983 99884 49976 99884 49974 99884 49983 99885 49974 99885 49973 99885 49973 99886 49974 99886 49984 99886 49973 99887 49984 99887 51843 99887 51844 99888 49988 99888 49985 99888 49985 99889 49988 99889 49986 99889 49985 99890 49986 99890 49972 99890 49972 99891 49986 99891 49987 99891 49972 99892 49987 99892 53972 99892 49988 99893 49994 99893 49986 99893 49986 99894 49994 99894 49989 99894 49986 99895 49989 99895 49987 99895 49987 99896 49989 99896 49997 99896 49998 99897 51848 99897 49991 99897 49991 99898 51848 99898 49990 99898 49991 99899 49990 99899 49992 99899 49992 99900 49990 99900 49982 99900 49992 99901 49982 99901 49993 99901 49993 99902 49982 99902 49977 99902 49993 99903 49977 99903 54405 99903 54405 99904 49977 99904 49978 99904 49996 99905 49989 99905 49994 99905 50005 99906 50004 99906 49995 99906 49994 99907 51847 99907 49996 99907 49996 99908 51847 99908 51841 99908 49996 99909 51841 99909 50005 99909 50005 99910 49995 99910 49996 99910 49996 99911 49995 99911 49997 99911 49996 99912 49997 99912 49989 99912 51838 99913 49998 99913 50014 99913 50014 99914 49998 99914 49991 99914 50014 99915 49991 99915 50021 99915 50021 99916 49991 99916 49992 99916 50021 99917 49992 99917 49999 99917 49999 99918 49992 99918 49993 99918 49999 99919 49993 99919 54404 99919 54404 99920 49993 99920 54405 99920 54309 99921 50000 99921 50022 99921 50022 99922 50000 99922 50006 99922 50022 99923 50006 99923 51820 99923 51819 99924 50001 99924 50006 99924 50006 99925 50001 99925 50002 99925 50006 99926 50002 99926 51820 99926 50003 99927 54075 99927 54073 99927 50003 99928 54073 99928 50007 99928 50007 99929 54073 99929 50004 99929 50007 99930 50004 99930 50005 99930 50000 99931 54075 99931 50006 99931 50006 99932 54075 99932 50003 99932 50006 99933 50003 99933 51819 99933 51819 99934 50003 99934 50007 99934 51819 99935 50007 99935 50008 99935 50008 99936 50007 99936 50005 99936 50008 99937 50005 99937 51841 99937 50009 99938 49999 99938 54404 99938 54407 99939 50010 99939 50030 99939 50013 99940 50011 99940 50012 99940 50012 99941 50011 99941 51831 99941 50012 99942 51829 99942 50013 99942 50013 99943 51829 99943 51838 99943 50013 99944 51838 99944 50014 99944 51832 99945 50020 99945 50015 99945 50017 99946 54407 99946 50015 99946 50015 99947 54407 99947 50030 99947 50015 99948 50030 99948 51832 99948 54408 99949 54407 99949 50016 99949 50016 99950 54407 99950 50017 99950 50016 99951 50017 99951 50009 99951 50009 99952 50017 99952 50018 99952 50009 99953 50018 99953 49999 99953 49999 99954 50018 99954 50021 99954 54404 99955 50019 99955 50009 99955 50009 99956 50019 99956 54398 99956 50009 99957 54398 99957 50016 99957 50016 99958 54398 99958 54409 99958 50016 99959 54409 99959 54408 99959 50020 99960 51831 99960 50015 99960 50015 99961 51831 99961 50011 99961 50015 99962 50011 99962 50017 99962 50017 99963 50011 99963 50013 99963 50017 99964 50013 99964 50018 99964 50018 99965 50013 99965 50014 99965 50018 99966 50014 99966 50021 99966 54309 99967 50022 99967 50028 99967 54309 99968 50028 99968 54308 99968 54308 99969 50028 99969 50023 99969 54308 99970 50023 99970 50024 99970 54329 99971 50024 99971 50027 99971 50027 99972 50024 99972 50023 99972 50027 99973 50023 99973 50025 99973 50025 99974 50023 99974 51824 99974 50036 99975 54329 99975 50026 99975 50026 99976 54329 99976 50027 99976 50026 99977 50027 99977 50034 99977 50034 99978 50027 99978 50025 99978 50034 99979 50025 99979 50033 99979 50033 99980 50025 99980 51824 99980 50022 99981 51820 99981 50028 99981 50028 99982 51820 99982 50029 99982 50028 99983 50029 99983 50023 99983 50023 99984 50029 99984 51821 99984 50023 99985 51821 99985 51824 99985 51835 99986 51832 99986 50032 99986 50032 99987 51832 99987 50030 99987 50032 99988 50030 99988 54325 99988 54325 99989 50030 99989 50010 99989 51833 99990 51835 99990 50031 99990 50031 99991 51835 99991 50032 99991 50031 99992 50032 99992 54328 99992 54328 99993 50032 99993 54325 99993 50033 99994 51802 99994 50055 99994 50033 99995 50055 99995 50034 99995 50034 99996 50055 99996 50035 99996 50034 99997 50035 99997 50026 99997 50026 99998 50035 99998 54338 99998 50026 99999 54338 99999 50036 99999 50042 100000 51801 100000 50049 100000 50037 100001 50051 100001 54339 100001 54339 100002 50051 100002 50052 100002 54339 100003 50052 100003 54340 100003 54340 100004 50052 100004 50038 100004 54340 100005 50038 100005 54341 100005 54341 100006 50038 100006 50053 100006 54341 100007 50053 100007 50039 100007 50039 100008 50053 100008 50048 100008 50039 100009 50048 100009 50040 100009 50040 100010 50048 100010 50046 100010 50040 100011 50046 100011 50041 100011 50041 100012 50046 100012 50031 100012 50041 100013 50031 100013 54328 100013 50042 100014 50043 100014 50044 100014 50044 100015 50043 100015 50045 100015 50044 100016 50045 100016 50056 100016 50042 100017 50049 100017 50043 100017 50043 100018 50049 100018 50051 100018 50043 100019 50051 100019 50045 100019 50045 100020 50051 100020 50037 100020 50045 100021 50037 100021 50056 100021 51833 100022 50031 100022 51806 100022 51806 100023 50031 100023 50046 100023 51806 100024 50046 100024 50047 100024 50047 100025 50046 100025 50048 100025 50047 100026 50048 100026 50054 100026 50054 100027 50048 100027 50053 100027 50049 100028 50050 100028 50051 100028 50051 100029 50050 100029 51814 100029 50051 100030 51814 100030 50052 100030 50052 100031 51814 100031 51812 100031 50052 100032 51812 100032 50038 100032 50038 100033 51812 100033 51811 100033 50038 100034 51811 100034 50053 100034 50053 100035 51811 100035 51809 100035 50053 100036 51809 100036 50054 100036 51802 100037 51801 100037 50042 100037 51802 100038 50042 100038 50055 100038 50055 100039 50042 100039 50044 100039 50055 100040 50044 100040 50035 100040 50035 100041 50044 100041 50056 100041 50035 100042 50056 100042 54338 100042 54326 100043 50059 100043 50057 100043 54326 100044 50057 100044 54327 100044 54327 100045 50057 100045 50076 100045 54327 100046 50076 100046 50060 100046 51728 100047 50076 100047 51729 100047 51729 100048 50076 100048 50057 100048 51729 100049 50057 100049 50058 100049 50058 100050 50057 100050 50059 100050 50058 100051 50059 100051 51731 100051 50060 100052 50076 100052 50061 100052 50060 100053 50061 100053 54342 100053 54342 100054 50061 100054 50077 100054 54342 100055 50077 100055 50062 100055 50062 100056 50077 100056 50078 100056 50062 100057 50078 100057 50063 100057 50065 100058 50069 100058 54337 100058 54337 100059 50069 100059 50071 100059 54337 100060 50071 100060 50064 100060 50073 100061 54364 100061 50071 100061 50071 100062 54364 100062 54361 100062 50071 100063 54361 100063 50064 100063 50081 100064 50069 100064 50066 100064 50066 100065 50069 100065 50065 100065 50066 100066 50065 100066 50078 100066 50078 100067 50065 100067 54354 100067 50078 100068 54354 100068 50063 100068 50067 100069 50068 100069 50071 100069 50071 100070 50068 100070 50075 100070 50071 100071 50075 100071 50073 100071 50081 100072 51707 100072 50069 100072 50069 100073 51707 100073 51705 100073 50069 100074 51705 100074 50071 100074 50071 100075 51705 100075 50070 100075 50071 100076 50070 100076 50067 100076 54363 100077 54364 100077 50072 100077 50072 100078 54364 100078 50073 100078 50072 100079 50073 100079 50074 100079 50074 100080 50073 100080 50075 100080 50074 100081 50075 100081 51698 100081 51698 100082 50075 100082 50068 100082 50076 100083 51728 100083 50061 100083 50061 100084 51728 100084 51710 100084 50061 100085 51710 100085 50077 100085 50077 100086 51710 100086 50079 100086 50077 100087 50079 100087 50078 100087 50078 100088 50079 100088 51709 100088 50078 100089 51709 100089 50066 100089 50066 100090 51709 100090 50080 100090 50066 100091 50080 100091 50081 100091 50082 100092 50098 100092 50097 100092 50082 100093 50097 100093 54376 100093 54376 100094 50083 100094 50082 100094 50082 100095 50083 100095 50104 100095 50082 100096 50104 100096 50098 100096 50098 100097 50104 100097 50099 100097 50092 100098 50094 100098 50096 100098 50096 100099 50094 100099 50089 100099 50095 100100 50085 100100 50084 100100 50084 100101 50085 100101 50086 100101 50084 100102 50086 100102 51737 100102 51737 100103 50086 100103 50087 100103 51737 100104 50087 100104 51735 100104 51735 100105 50087 100105 50101 100105 51735 100106 50101 100106 51725 100106 50059 100107 54326 100107 50088 100107 50088 100108 54326 100108 54410 100108 50088 100109 54410 100109 50093 100109 50093 100110 54410 100110 54411 100110 50094 100111 50090 100111 50089 100111 50089 100112 50090 100112 50091 100112 50089 100113 50091 100113 50097 100113 50097 100114 50091 100114 54416 100114 50097 100115 54416 100115 54376 100115 51731 100116 50059 100116 51733 100116 51733 100117 50059 100117 50088 100117 51733 100118 50088 100118 50092 100118 50092 100119 50088 100119 50093 100119 50092 100120 50093 100120 50094 100120 50094 100121 50093 100121 54411 100121 50094 100122 54411 100122 50090 100122 50095 100123 50096 100123 50085 100123 50085 100124 50096 100124 50089 100124 50085 100125 50089 100125 50086 100125 50086 100126 50089 100126 50097 100126 50086 100127 50097 100127 50087 100127 50087 100128 50097 100128 50098 100128 50087 100129 50098 100129 50101 100129 50101 100130 50098 100130 50099 100130 51698 100131 50106 100131 50074 100131 50074 100132 50106 100132 50100 100132 50074 100133 50100 100133 50072 100133 50072 100134 50100 100134 54367 100134 50072 100135 54367 100135 54363 100135 51739 100136 51725 100136 50107 100136 50107 100137 51725 100137 50101 100137 50107 100138 50101 100138 50102 100138 50102 100139 50101 100139 50099 100139 50102 100140 50099 100140 50103 100140 50103 100141 50099 100141 50104 100141 50103 100142 50104 100142 50105 100142 50105 100143 50104 100143 50083 100143 50106 100144 51719 100144 50116 100144 50106 100145 50116 100145 50100 100145 50116 100146 50123 100146 50100 100146 50100 100147 50123 100147 54366 100147 50100 100148 54366 100148 54367 100148 50131 100149 51739 100149 50132 100149 50132 100150 51739 100150 50107 100150 50132 100151 50107 100151 50108 100151 50108 100152 50107 100152 50102 100152 50108 100153 50102 100153 50109 100153 50109 100154 50102 100154 50103 100154 50109 100155 50103 100155 50136 100155 50136 100156 50103 100156 50105 100156 50125 100157 51718 100157 50126 100157 50110 100158 54372 100158 50112 100158 54366 100159 50123 100159 50122 100159 54366 100160 50122 100160 50111 100160 50111 100161 50122 100161 50120 100161 50111 100162 50120 100162 50119 100162 50110 100163 50112 100163 54350 100163 50126 100164 51718 100164 50127 100164 51718 100165 51717 100165 50127 100165 50127 100166 51717 100166 50113 100166 50127 100167 50113 100167 50114 100167 50114 100168 50113 100168 50115 100168 50114 100169 50115 100169 50128 100169 51719 100170 50121 100170 50116 100170 50116 100171 50121 100171 50117 100171 51721 100172 50118 100172 50120 100172 50120 100173 50118 100173 50112 100173 50120 100174 50112 100174 50119 100174 50119 100175 50112 100175 54372 100175 51721 100176 50120 100176 50121 100176 50121 100177 50120 100177 50122 100177 50121 100178 50122 100178 50117 100178 50117 100179 50122 100179 50123 100179 50117 100180 50123 100180 50116 100180 51753 100181 50130 100181 50124 100181 50124 100182 50130 100182 50128 100182 50124 100183 50128 100183 51713 100183 51713 100184 50128 100184 50115 100184 50118 100185 50125 100185 50112 100185 50112 100186 50125 100186 50126 100186 50112 100187 50126 100187 54350 100187 54350 100188 50126 100188 50127 100188 54350 100189 50127 100189 54359 100189 54359 100190 50127 100190 50114 100190 54359 100191 50114 100191 54360 100191 54360 100192 50114 100192 50128 100192 54360 100193 50128 100193 50129 100193 50129 100194 50128 100194 50130 100194 50129 100195 50130 100195 50140 100195 51741 100196 50131 100196 50137 100196 50137 100197 50131 100197 50132 100197 50137 100198 50132 100198 50133 100198 50133 100199 50132 100199 50108 100199 50133 100200 50108 100200 50134 100200 50134 100201 50108 100201 50109 100201 50134 100202 50109 100202 50135 100202 50135 100203 50109 100203 50136 100203 51742 100204 51741 100204 50143 100204 50143 100205 51741 100205 50137 100205 50143 100206 50137 100206 50147 100206 50147 100207 50137 100207 50133 100207 50147 100208 50133 100208 50146 100208 50146 100209 50133 100209 50134 100209 50146 100210 50134 100210 54440 100210 54440 100211 50134 100211 50135 100211 51752 100212 51757 100212 50139 100212 50139 100213 51757 100213 50138 100213 50139 100214 50138 100214 54351 100214 54351 100215 50138 100215 54355 100215 51753 100216 51752 100216 50130 100216 50130 100217 51752 100217 50139 100217 50130 100218 50139 100218 50140 100218 50140 100219 50139 100219 54351 100219 50146 100220 54440 100220 54444 100220 51745 100221 51742 100221 50143 100221 50148 100222 50141 100222 50142 100222 50142 100223 50141 100223 54444 100223 51745 100224 50143 100224 51746 100224 50145 100225 50138 100225 51757 100225 54355 100226 50138 100226 54442 100226 54442 100227 50138 100227 50145 100227 54442 100228 50145 100228 50144 100228 50144 100229 50145 100229 50142 100229 50144 100230 50142 100230 54443 100230 54443 100231 50142 100231 54444 100231 50146 100232 54444 100232 50147 100232 50147 100233 54444 100233 50141 100233 50147 100234 50141 100234 50143 100234 50143 100235 50141 100235 50148 100235 50143 100236 50148 100236 51746 100236 51746 100237 50148 100237 50142 100237 51746 100238 50142 100238 50149 100238 51757 100239 51750 100239 50145 100239 50145 100240 51750 100240 51749 100240 50145 100241 51749 100241 50142 100241 50142 100242 51749 100242 51747 100242 50142 100243 51747 100243 50149 100243 50150 100244 50151 100244 50165 100244 50165 100245 50151 100245 50152 100245 50152 100246 50151 100246 54449 100246 54449 100247 50151 100247 50153 100247 54449 100248 50153 100248 54451 100248 51795 100249 50153 100249 51796 100249 51796 100250 50153 100250 50151 100250 51796 100251 50151 100251 50154 100251 50154 100252 50151 100252 50150 100252 50162 100253 50155 100253 50159 100253 50158 100254 54453 100254 54452 100254 54452 100255 54451 100255 50153 100255 50156 100256 54453 100256 50157 100256 50157 100257 54453 100257 50158 100257 50157 100258 50158 100258 50155 100258 50155 100259 50158 100259 54452 100259 50155 100260 54452 100260 50159 100260 50159 100261 54452 100261 50153 100261 50159 100262 50153 100262 51795 100262 50163 100263 51794 100263 50161 100263 50161 100264 51794 100264 50169 100264 50161 100265 50169 100265 50160 100265 50160 100266 50169 100266 50170 100266 50160 100267 50170 100267 50171 100267 50172 100268 50156 100268 50171 100268 50171 100269 50156 100269 50157 100269 50171 100270 50157 100270 50160 100270 50160 100271 50157 100271 50155 100271 50160 100272 50155 100272 50161 100272 50161 100273 50155 100273 50162 100273 50161 100274 50162 100274 50163 100274 50163 100275 50162 100275 50159 100275 50163 100276 50159 100276 50164 100276 50164 100277 50159 100277 51795 100277 50165 100278 54078 100278 50167 100278 50165 100279 50167 100279 50150 100279 50150 100280 50167 100280 51799 100280 50150 100281 51799 100281 50154 100281 51798 100282 51799 100282 50166 100282 50166 100283 51799 100283 50167 100283 50166 100284 50167 100284 54080 100284 54080 100285 50167 100285 54078 100285 51794 100286 50168 100286 50169 100286 50169 100287 50168 100287 50180 100287 50169 100288 50180 100288 50170 100288 50170 100289 50180 100289 50181 100289 50170 100290 50181 100290 50171 100290 50171 100291 50181 100291 50182 100291 50171 100292 50182 100292 50172 100292 50172 100293 50182 100293 54447 100293 50166 100294 54080 100294 50173 100294 51798 100295 50166 100295 50174 100295 50166 100296 50173 100296 50174 100296 50174 100297 50173 100297 50175 100297 50174 100298 50175 100298 50178 100298 50178 100299 50175 100299 54079 100299 50178 100300 54079 100300 50176 100300 50176 100301 54079 100301 50177 100301 50176 100302 50177 100302 50190 100302 51798 100303 50174 100303 51773 100303 51773 100304 50174 100304 50178 100304 51773 100305 50178 100305 50179 100305 50179 100306 50178 100306 50176 100306 50179 100307 50176 100307 51776 100307 51776 100308 50176 100308 50190 100308 51776 100309 50190 100309 51777 100309 50168 100310 51789 100310 50180 100310 50180 100311 51789 100311 50209 100311 50180 100312 50209 100312 50181 100312 50181 100313 50209 100313 50183 100313 50181 100314 50183 100314 50182 100314 50182 100315 50183 100315 50198 100315 50182 100316 50198 100316 54447 100316 54447 100317 50198 100317 50196 100317 54348 100318 50191 100318 50185 100318 50188 100319 50186 100319 54357 100319 54357 100320 50186 100320 54347 100320 54348 100321 50185 100321 50184 100321 50184 100322 50185 100322 50190 100322 50184 100323 50190 100323 50177 100323 54348 100324 54347 100324 50191 100324 50191 100325 54347 100325 50186 100325 50191 100326 50186 100326 50187 100326 50187 100327 50186 100327 50188 100327 50187 100328 50188 100328 50213 100328 51777 100329 50190 100329 50189 100329 50189 100330 50190 100330 50185 100330 50189 100331 50185 100331 50192 100331 50192 100332 50185 100332 50191 100332 50192 100333 50191 100333 50193 100333 50193 100334 50191 100334 50187 100334 50193 100335 50187 100335 50194 100335 50194 100336 50187 100336 50213 100336 50194 100337 50213 100337 50212 100337 50195 100338 50197 100338 50203 100338 50210 100339 50209 100339 51789 100339 50206 100340 50196 100340 50195 100340 50195 100341 50196 100341 50198 100341 50195 100342 50198 100342 50197 100342 50197 100343 50198 100343 50183 100343 51789 100344 51786 100344 50210 100344 50210 100345 51786 100345 50199 100345 50210 100346 50199 100346 50200 100346 50200 100347 50199 100347 50201 100347 50200 100348 50201 100348 50211 100348 54446 100349 54445 100349 50202 100349 50202 100350 54445 100350 50204 100350 50202 100351 50204 100351 50203 100351 50203 100352 50204 100352 50205 100352 50203 100353 50205 100353 50195 100353 50195 100354 50205 100354 54448 100354 50195 100355 54448 100355 50206 100355 50202 100356 51784 100356 50207 100356 54446 100357 50202 100357 50208 100357 50208 100358 50202 100358 50207 100358 50208 100359 50207 100359 50218 100359 50183 100360 50209 100360 50197 100360 50197 100361 50209 100361 50210 100361 50197 100362 50210 100362 50203 100362 50203 100363 50210 100363 50200 100363 50203 100364 50200 100364 50202 100364 50202 100365 50200 100365 50211 100365 50202 100366 50211 100366 51784 100366 51758 100367 50212 100367 50213 100367 51758 100368 50213 100368 50214 100368 50214 100369 50213 100369 50188 100369 50214 100370 50188 100370 50220 100370 50220 100371 50188 100371 54357 100371 50220 100372 54357 100372 50223 100372 51782 100373 50215 100373 50219 100373 50219 100374 50215 100374 50225 100374 50219 100375 50225 100375 50216 100375 50216 100376 50225 100376 50217 100376 50218 100377 51782 100377 50208 100377 50208 100378 51782 100378 50219 100378 50208 100379 50219 100379 54446 100379 54446 100380 50219 100380 50216 100380 50237 100381 51758 100381 50214 100381 50237 100382 50214 100382 50221 100382 50221 100383 50214 100383 50220 100383 50221 100384 50220 100384 50222 100384 50222 100385 50220 100385 50223 100385 50222 100386 50223 100386 50224 100386 54356 100387 50239 100387 50240 100387 50217 100388 50225 100388 50226 100388 50217 100389 50226 100389 50227 100389 50227 100390 50226 100390 50228 100390 50227 100391 50228 100391 50229 100391 50229 100392 50228 100392 50238 100392 50229 100393 50238 100393 50230 100393 54356 100394 50240 100394 50231 100394 50231 100395 50240 100395 50242 100395 50231 100396 50242 100396 50232 100396 50236 100397 50232 100397 50233 100397 50233 100398 50232 100398 50242 100398 50233 100399 50242 100399 50234 100399 50234 100400 50242 100400 51767 100400 51771 100401 50238 100401 50235 100401 50235 100402 50238 100402 50228 100402 50235 100403 50228 100403 51768 100403 51768 100404 50228 100404 50226 100404 51768 100405 50226 100405 50215 100405 50215 100406 50226 100406 50225 100406 50224 100407 50236 100407 50222 100407 50222 100408 50236 100408 50233 100408 50222 100409 50233 100409 50221 100409 50221 100410 50233 100410 50234 100410 50221 100411 50234 100411 50237 100411 50237 100412 50234 100412 51767 100412 51771 100413 51761 100413 50238 100413 50238 100414 51761 100414 50239 100414 50238 100415 50239 100415 50230 100415 50230 100416 50239 100416 54356 100416 51761 100417 51762 100417 50239 100417 50239 100418 51762 100418 51764 100418 50239 100419 51764 100419 50240 100419 50240 100420 51764 100420 50241 100420 50240 100421 50241 100421 50242 100421 50242 100422 50241 100422 51766 100422 50242 100423 51766 100423 51767 100423 52264 100424 52263 100424 50244 100424 52264 100425 50244 100425 52266 100425 50243 100426 50245 100426 50244 100426 50244 100427 50245 100427 54545 100427 50244 100428 54545 100428 52266 100428 50245 100429 50243 100429 50246 100429 50246 100430 50243 100430 50250 100430 51886 100431 50257 100431 51857 100431 51857 100432 50257 100432 54576 100432 51857 100433 54576 100433 51858 100433 51858 100434 54576 100434 54575 100434 51858 100435 54575 100435 50247 100435 50247 100436 54575 100436 50249 100436 50247 100437 50249 100437 50248 100437 50248 100438 50249 100438 54546 100438 50248 100439 54546 100439 50250 100439 50250 100440 54546 100440 50246 100440 50260 100441 54570 100441 54572 100441 51885 100442 50251 100442 54572 100442 54572 100443 50251 100443 51882 100443 54572 100444 51882 100444 50260 100444 54572 100445 54573 100445 51885 100445 51885 100446 54573 100446 50252 100446 51885 100447 50252 100447 50253 100447 50253 100448 50252 100448 50254 100448 50253 100449 50254 100449 50255 100449 50254 100450 54580 100450 50255 100450 50255 100451 54580 100451 54579 100451 50255 100452 54579 100452 50256 100452 50256 100453 54579 100453 50257 100453 50256 100454 50257 100454 51886 100454 50262 100455 50259 100455 50258 100455 50258 100456 50259 100456 54568 100456 50258 100457 54568 100457 51854 100457 51854 100458 54568 100458 50261 100458 51854 100459 50261 100459 50260 100459 50260 100460 50261 100460 54570 100460 50259 100461 50262 100461 54289 100461 54289 100462 50262 100462 53160 100462 53162 100463 50272 100463 54274 100463 53162 100464 54274 100464 53163 100464 53163 100465 54274 100465 50263 100465 53163 100466 50263 100466 53166 100466 53166 100467 50263 100467 54276 100467 53166 100468 54276 100468 53158 100468 54276 100469 54277 100469 53158 100469 53158 100470 54277 100470 50264 100470 53158 100471 50264 100471 50266 100471 50266 100472 50264 100472 50265 100472 50265 100473 54279 100473 50266 100473 50266 100474 54279 100474 54281 100474 50266 100475 54281 100475 50269 100475 50269 100476 54281 100476 50267 100476 50267 100477 50268 100477 50269 100477 50269 100478 50268 100478 50270 100478 50269 100479 50270 100479 53159 100479 53159 100480 50270 100480 53160 100480 53160 100481 50270 100481 50271 100481 53160 100482 50271 100482 54289 100482 50272 100483 53162 100483 52496 100483 50285 100484 54268 100484 52498 100484 52498 100485 54268 100485 50272 100485 52498 100486 50272 100486 52497 100486 52497 100487 50272 100487 52496 100487 50273 100488 50295 100488 52484 100488 52484 100489 50295 100489 50275 100489 52484 100490 50275 100490 50274 100490 50274 100491 50275 100491 54193 100491 50274 100492 54193 100492 52485 100492 52485 100493 54193 100493 54265 100493 50281 100494 50276 100494 50277 100494 50277 100495 50276 100495 50279 100495 50277 100496 50279 100496 50278 100496 50278 100497 50279 100497 50280 100497 50278 100498 50280 100498 54265 100498 54265 100499 50280 100499 52487 100499 54265 100500 52487 100500 52485 100500 50281 100501 50277 100501 52492 100501 52492 100502 50277 100502 50282 100502 52492 100503 50282 100503 52493 100503 52493 100504 50282 100504 54270 100504 52493 100505 54270 100505 50283 100505 50283 100506 54270 100506 52495 100506 52495 100507 54270 100507 50284 100507 52495 100508 50284 100508 52494 100508 52494 100509 50284 100509 54268 100509 52494 100510 54268 100510 50285 100510 52480 100511 52482 100511 50286 100511 50286 100512 50287 100512 52480 100512 52480 100513 50287 100513 52942 100513 52480 100514 52942 100514 52477 100514 52477 100515 52942 100515 50288 100515 52477 100516 50288 100516 52476 100516 52476 100517 50288 100517 54199 100517 52476 100518 54199 100518 50290 100518 50292 100519 50289 100519 50290 100519 50290 100520 50289 100520 52475 100520 50290 100521 52475 100521 52476 100521 50290 100522 50291 100522 50292 100522 50292 100523 50291 100523 50293 100523 50292 100524 50293 100524 50294 100524 50294 100525 50293 100525 54195 100525 50294 100526 54195 100526 52471 100526 50295 100527 50273 100527 54195 100527 54195 100528 50273 100528 52472 100528 54195 100529 52472 100529 52471 100529 50296 100530 52914 100530 52919 100530 52600 100531 50301 100531 50305 100531 52620 100532 50297 100532 50298 100532 52920 100533 52914 100533 50307 100533 52920 100534 50307 100534 52921 100534 52921 100535 50307 100535 50299 100535 52620 100536 50298 100536 52605 100536 52605 100537 50298 100537 50300 100537 52605 100538 50300 100538 52606 100538 52606 100539 50300 100539 50302 100539 52606 100540 50302 100540 52602 100540 50301 100541 52600 100541 50302 100541 50302 100542 52600 100542 52604 100542 50302 100543 52604 100543 52602 100543 50306 100544 50303 100544 50305 100544 50305 100545 50303 100545 50304 100545 50305 100546 50304 100546 52600 100546 50305 100547 54201 100547 50306 100547 50306 100548 54201 100548 50308 100548 50306 100549 50308 100549 50307 100549 50307 100550 50308 100550 52918 100550 50307 100551 52918 100551 50299 100551 52608 100552 54205 100552 50309 100552 50309 100553 54205 100553 54204 100553 50309 100554 54204 100554 52620 100554 52620 100555 54204 100555 50297 100555 52864 100556 52868 100556 50310 100556 50318 100557 52614 100557 50311 100557 50320 100558 52611 100558 50312 100558 50312 100559 52611 100559 50313 100559 50312 100560 50313 100560 54214 100560 54214 100561 50313 100561 50314 100561 54214 100562 50314 100562 54238 100562 54238 100563 50314 100563 50315 100563 54238 100564 50315 100564 50317 100564 50317 100565 50315 100565 50316 100565 50317 100566 50316 100566 50310 100566 50310 100567 50316 100567 50318 100567 50310 100568 50318 100568 52864 100568 52864 100569 50318 100569 50311 100569 52609 100570 50319 100570 50320 100570 50320 100571 50319 100571 52610 100571 50320 100572 52610 100572 52611 100572 50320 100573 54206 100573 52609 100573 52609 100574 54206 100574 54205 100574 52609 100575 54205 100575 52608 100575 52876 100576 50311 100576 50321 100576 50321 100577 50311 100577 52614 100577 52830 100578 50322 100578 50323 100578 50323 100579 50322 100579 50324 100579 50323 100580 50324 100580 52833 100580 52672 100581 50334 100581 50325 100581 52672 100582 50325 100582 52673 100582 52673 100583 50325 100583 54222 100583 52673 100584 54222 100584 50326 100584 50326 100585 54222 100585 50327 100585 50326 100586 50327 100586 52670 100586 52670 100587 50327 100587 50328 100587 50328 100588 50327 100588 50329 100588 50328 100589 50329 100589 50330 100589 50330 100590 50329 100590 54218 100590 50330 100591 54218 100591 52669 100591 52669 100592 54218 100592 54210 100592 52669 100593 54210 100593 50331 100593 50331 100594 54210 100594 54212 100594 50331 100595 54212 100595 52668 100595 50322 100596 52830 100596 50332 100596 50332 100597 52830 100597 52668 100597 50332 100598 52668 100598 50333 100598 50333 100599 52668 100599 54212 100599 50334 100600 52672 100600 50335 100600 50335 100601 52672 100601 50347 100601 50336 100602 54207 100602 50337 100602 50349 100603 50348 100603 52666 100603 52666 100604 50348 100604 50336 100604 50336 100605 50337 100605 52666 100605 52666 100606 50337 100606 54237 100606 52666 100607 54237 100607 50338 100607 50338 100608 54237 100608 54236 100608 50338 100609 54236 100609 50339 100609 50339 100610 54236 100610 52661 100610 52661 100611 54236 100611 50340 100611 52661 100612 50340 100612 50341 100612 50341 100613 50340 100613 50342 100613 50341 100614 50342 100614 50343 100614 50343 100615 50342 100615 50344 100615 50343 100616 50344 100616 50345 100616 50345 100617 50344 100617 54224 100617 50345 100618 54224 100618 50346 100618 50346 100619 54224 100619 50335 100619 50346 100620 50335 100620 50347 100620 50348 100621 50349 100621 52819 100621 52819 100622 50349 100622 52826 100622 52819 100623 52826 100623 52820 100623 52783 100624 50350 100624 52789 100624 52789 100625 50350 100625 50351 100625 52789 100626 50351 100626 50352 100626 50365 100627 50368 100627 54241 100627 50352 100628 50351 100628 52790 100628 52790 100629 50351 100629 52577 100629 52790 100630 52577 100630 50354 100630 50354 100631 52577 100631 50353 100631 50354 100632 50353 100632 54209 100632 54209 100633 50353 100633 50355 100633 54209 100634 50355 100634 54232 100634 54232 100635 50355 100635 50356 100635 54232 100636 50356 100636 50357 100636 50357 100637 50356 100637 52581 100637 50357 100638 52581 100638 50358 100638 50358 100639 52581 100639 50359 100639 50358 100640 50359 100640 50360 100640 50360 100641 50359 100641 50362 100641 50360 100642 50362 100642 50361 100642 50361 100643 50362 100643 50363 100643 50361 100644 50363 100644 54241 100644 54241 100645 50363 100645 50364 100645 54241 100646 50364 100646 50365 100646 52595 100647 50375 100647 50367 100647 50367 100648 50375 100648 50366 100648 50367 100649 50366 100649 50365 100649 50365 100650 50366 100650 50368 100650 50371 100651 54244 100651 50373 100651 52899 100652 52898 100652 54239 100652 50369 100653 50377 100653 52896 100653 50369 100654 52896 100654 52899 100654 52899 100655 54239 100655 50369 100655 50369 100656 54239 100656 54245 100656 50369 100657 54245 100657 52592 100657 52592 100658 54245 100658 50372 100658 52592 100659 50372 100659 50370 100659 54244 100660 50371 100660 50372 100660 50372 100661 50371 100661 52589 100661 50372 100662 52589 100662 50370 100662 52587 100663 52584 100663 50373 100663 50373 100664 52584 100664 52591 100664 50373 100665 52591 100665 50371 100665 50373 100666 50374 100666 52587 100666 52587 100667 50374 100667 54243 100667 52587 100668 54243 100668 52588 100668 52588 100669 54243 100669 50375 100669 52588 100670 50375 100670 52595 100670 50376 100671 50377 100671 50378 100671 52199 100672 52198 100672 54529 100672 50379 100673 52200 100673 52196 100673 52196 100674 52199 100674 50379 100674 50379 100675 52199 100675 54529 100675 50379 100676 54529 100676 50380 100676 50380 100677 54529 100677 54564 100677 50380 100678 54564 100678 51876 100678 51876 100679 54564 100679 54553 100679 51876 100680 54553 100680 51862 100680 51862 100681 54553 100681 54552 100681 51862 100682 54552 100682 51863 100682 51863 100683 54552 100683 50381 100683 51863 100684 50381 100684 51866 100684 51866 100685 50381 100685 50382 100685 51866 100686 50382 100686 51867 100686 51867 100687 50382 100687 50383 100687 51867 100688 50383 100688 51868 100688 51868 100689 50383 100689 50384 100689 51868 100690 50384 100690 54563 100690 51868 100691 54563 100691 51877 100691 51877 100692 54563 100692 54562 100692 51877 100693 54562 100693 50385 100693 50385 100694 54562 100694 50386 100694 50385 100695 50386 100695 51878 100695 51878 100696 50386 100696 50387 100696 51878 100697 50387 100697 50388 100697 50388 100698 50387 100698 54559 100698 50388 100699 54559 100699 50389 100699 50389 100700 54559 100700 51881 100700 51881 100701 54559 100701 54539 100701 51881 100702 54539 100702 51880 100702 51880 100703 54539 100703 54538 100703 51880 100704 54538 100704 50390 100704 50390 100705 54538 100705 50392 100705 50392 100706 54538 100706 50391 100706 50392 100707 50391 100707 50393 100707 50393 100708 50391 100708 50394 100708 50393 100709 50394 100709 53152 100709 53152 100710 50394 100710 54525 100710 53152 100711 54525 100711 50395 100711 50395 100712 54525 100712 54301 100712 54303 100713 54304 100713 50396 100713 50398 100714 53156 100714 54185 100714 54185 100715 53156 100715 54294 100715 54185 100716 50397 100716 50398 100716 50398 100717 50397 100717 54291 100717 50398 100718 54291 100718 50399 100718 50399 100719 54291 100719 54292 100719 50399 100720 54292 100720 50404 100720 54294 100721 53156 100721 50400 100721 50400 100722 53156 100722 53155 100722 50400 100723 53155 100723 50402 100723 50402 100724 53155 100724 50401 100724 50402 100725 50401 100725 54297 100725 50396 100726 54304 100726 53153 100726 53153 100727 54304 100727 54299 100727 53153 100728 54299 100728 50401 100728 50401 100729 54299 100729 54298 100729 50401 100730 54298 100730 54297 100730 54303 100731 50396 100731 50403 100731 50403 100732 50396 100732 50395 100732 50403 100733 50395 100733 54301 100733 52430 100734 52445 100734 50414 100734 50414 100735 52445 100735 52446 100735 50414 100736 52446 100736 50404 100736 50404 100737 52446 100737 52447 100737 50404 100738 52447 100738 50399 100738 52440 100739 50408 100739 50405 100739 50405 100740 50408 100740 50406 100740 50405 100741 50406 100741 52442 100741 52442 100742 50406 100742 54256 100742 52442 100743 54256 100743 52444 100743 52444 100744 54256 100744 50407 100744 52444 100745 50407 100745 52427 100745 52427 100746 50407 100746 54253 100746 52440 100747 52439 100747 50408 100747 50408 100748 52439 100748 52438 100748 50408 100749 52438 100749 50409 100749 50409 100750 52438 100750 54259 100750 52438 100751 50410 100751 54259 100751 54259 100752 50410 100752 50411 100752 54259 100753 50411 100753 54261 100753 54261 100754 50411 100754 50412 100754 54261 100755 50412 100755 54189 100755 50412 100756 52436 100756 54189 100756 54189 100757 52436 100757 52433 100757 54189 100758 52433 100758 54188 100758 52433 100759 52432 100759 54188 100759 54188 100760 52432 100760 52431 100760 54188 100761 52431 100761 54187 100761 54187 100762 52431 100762 50413 100762 50413 100763 52431 100763 52430 100763 50413 100764 52430 100764 50414 100764 50416 100765 50415 100765 50421 100765 50415 100766 50416 100766 50417 100766 50416 100767 52429 100767 50417 100767 50417 100768 52429 100768 50418 100768 50417 100769 50418 100769 50419 100769 50419 100770 50418 100770 52427 100770 50419 100771 52427 100771 54253 100771 50422 100772 50420 100772 50421 100772 50421 100773 50420 100773 52426 100773 50421 100774 52426 100774 50416 100774 50421 100775 54251 100775 50422 100775 50422 100776 54251 100776 54263 100776 50422 100777 54263 100777 50423 100777 50423 100778 54263 100778 52891 100778 52888 100779 50424 100779 52893 100779 52893 100780 50424 100780 50425 100780 52893 100781 50425 100781 52894 100781 52894 100782 50425 100782 50423 100782 52894 100783 50423 100783 52890 100783 52890 100784 50423 100784 52891 100784 50426 100785 53150 100785 52249 100785 54549 100786 50427 100786 52249 100786 52249 100787 50427 100787 52194 100787 52249 100788 52194 100788 50426 100788 53076 100789 50429 100789 53089 100789 53089 100790 50429 100790 50428 100790 50429 100791 53076 100791 50430 100791 50430 100792 53076 100792 53135 100792 50430 100793 53135 100793 52961 100793 52961 100794 53135 100794 53126 100794 52961 100795 53126 100795 50431 100795 50431 100796 53126 100796 53083 100796 50431 100797 53083 100797 50432 100797 50432 100798 53083 100798 53095 100798 50436 100799 53111 100799 50433 100799 50433 100800 53111 100800 53040 100800 50433 100801 53040 100801 52957 100801 52957 100802 53040 100802 50434 100802 52957 100803 50434 100803 50428 100803 50428 100804 50434 100804 53089 100804 50432 100805 53095 100805 50435 100805 50435 100806 53095 100806 53097 100806 53111 100807 50436 100807 50441 100807 50441 100808 50436 100808 52956 100808 50435 100809 53097 100809 50437 100809 50437 100810 53097 100810 50438 100810 50437 100811 50438 100811 52965 100811 52965 100812 50438 100812 50439 100812 52965 100813 50439 100813 50440 100813 50440 100814 50439 100814 53108 100814 50440 100815 53108 100815 52964 100815 52964 100816 53108 100816 53107 100816 53112 100817 50441 100817 52956 100817 52956 100818 52951 100818 53112 100818 53112 100819 52951 100819 50443 100819 53112 100820 50443 100820 50442 100820 50442 100821 50443 100821 52953 100821 50442 100822 52953 100822 53114 100822 52967 100823 53140 100823 50444 100823 50444 100824 53140 100824 53114 100824 50444 100825 53114 100825 50445 100825 50445 100826 53114 100826 52953 100826 53140 100827 52967 100827 53107 100827 53107 100828 52967 100828 52964 100828 52981 100829 52999 100829 50453 100829 50453 100830 52999 100830 53006 100830 52999 100831 52981 100831 53000 100831 53000 100832 52981 100832 52980 100832 53000 100833 52980 100833 50446 100833 50446 100834 52980 100834 50447 100834 50446 100835 50447 100835 53002 100835 53002 100836 50447 100836 52979 100836 53002 100837 52979 100837 50448 100837 50448 100838 52979 100838 52977 100838 52984 100839 50449 100839 53004 100839 53004 100840 50449 100840 50450 100840 53004 100841 50450 100841 53005 100841 53005 100842 50450 100842 50451 100842 53005 100843 50451 100843 50452 100843 50452 100844 50451 100844 52983 100844 50452 100845 52983 100845 53006 100845 53006 100846 52983 100846 50453 100846 50448 100847 52977 100847 52994 100847 52994 100848 52977 100848 50454 100848 50449 100849 52984 100849 52969 100849 52969 100850 52984 100850 52986 100850 52994 100851 50454 100851 50455 100851 50455 100852 50454 100852 50456 100852 50455 100853 50456 100853 50457 100853 50457 100854 50456 100854 52972 100854 50457 100855 52972 100855 52996 100855 52996 100856 52972 100856 50458 100856 52996 100857 50458 100857 52998 100857 52998 100858 50458 100858 52971 100858 50465 100859 50459 100859 50460 100859 50460 100860 50459 100860 50461 100860 50460 100861 50461 100861 52990 100861 52990 100862 50461 100862 50462 100862 52990 100863 50462 100863 50463 100863 50463 100864 50462 100864 50464 100864 50463 100865 50464 100865 52986 100865 52986 100866 50464 100866 52969 100866 50459 100867 50465 100867 52971 100867 52971 100868 50465 100868 52998 100868 50472 100869 53047 100869 52299 100869 52299 100870 53047 100870 53045 100870 52299 100871 53045 100871 52302 100871 52302 100872 53045 100872 50466 100872 52302 100873 50466 100873 52303 100873 52303 100874 50466 100874 50467 100874 52303 100875 50467 100875 52304 100875 52304 100876 50467 100876 50469 100876 52304 100877 50469 100877 50468 100877 50468 100878 50469 100878 50470 100878 50468 100879 50470 100879 52305 100879 52305 100880 50470 100880 53039 100880 52305 100881 53039 100881 50471 100881 50471 100882 53039 100882 53110 100882 53047 100883 50472 100883 50473 100883 50473 100884 50472 100884 52292 100884 50471 100885 53110 100885 50474 100885 50474 100886 53110 100886 50476 100886 52290 100887 50475 100887 52292 100887 52292 100888 50475 100888 50473 100888 50474 100889 50476 100889 50477 100889 50477 100890 50476 100890 50478 100890 50477 100891 50478 100891 52294 100891 52294 100892 50478 100892 53113 100892 52294 100893 53113 100893 52295 100893 52295 100894 53113 100894 50479 100894 52295 100895 50479 100895 50480 100895 50480 100896 50479 100896 50481 100896 50480 100897 50481 100897 52297 100897 52297 100898 50481 100898 53037 100898 52297 100899 53037 100899 52290 100899 52290 100900 53037 100900 50475 100900 52197 100901 52206 100901 50482 100901 50482 100902 52206 100902 50490 100902 52206 100903 52197 100903 50483 100903 52206 100904 50483 100904 52208 100904 52208 100905 50483 100905 52201 100905 52208 100906 52201 100906 50485 100906 50485 100907 52201 100907 50484 100907 50485 100908 50484 100908 50486 100908 50492 100909 52188 100909 52189 100909 50492 100910 52189 100910 52203 100910 52203 100911 52189 100911 50488 100911 52203 100912 50488 100912 50487 100912 50487 100913 50488 100913 50489 100913 50487 100914 50489 100914 52205 100914 52205 100915 50489 100915 50482 100915 52205 100916 50482 100916 50490 100916 50486 100917 50484 100917 50491 100917 50491 100918 50484 100918 52195 100918 52188 100919 50492 100919 52191 100919 52191 100920 50492 100920 52218 100920 50491 100921 52195 100921 50493 100921 50491 100922 50493 100922 52210 100922 52210 100923 50493 100923 50494 100923 52210 100924 50494 100924 50495 100924 50495 100925 50494 100925 53149 100925 50495 100926 53149 100926 52212 100926 52214 100927 52193 100927 50496 100927 52214 100928 50496 100928 52215 100928 52215 100929 50496 100929 50497 100929 52215 100930 50497 100930 50498 100930 50498 100931 50497 100931 52191 100931 50498 100932 52191 100932 52218 100932 52193 100933 52214 100933 53149 100933 53149 100934 52214 100934 52212 100934 52213 100935 50501 100935 50499 100935 50499 100936 50501 100936 50500 100936 50501 100937 52213 100937 52182 100937 52182 100938 52213 100938 52216 100938 52182 100939 52216 100939 50502 100939 50502 100940 52216 100940 52217 100940 50502 100941 52217 100941 52180 100941 52180 100942 52217 100942 50507 100942 52173 100943 50503 100943 50504 100943 50504 100944 50503 100944 50505 100944 50504 100945 50505 100945 52185 100945 52185 100946 50505 100946 52211 100946 52185 100947 52211 100947 50500 100947 50500 100948 52211 100948 50499 100948 52180 100949 50507 100949 50506 100949 50506 100950 50507 100950 52219 100950 50503 100951 52173 100951 52209 100951 52209 100952 52173 100952 52174 100952 50506 100953 52219 100953 50508 100953 50508 100954 52219 100954 52202 100954 50508 100955 52202 100955 50509 100955 50509 100956 52202 100956 50510 100956 50509 100957 50510 100957 50511 100957 50511 100958 50510 100958 52204 100958 50511 100959 52204 100959 50512 100959 50512 100960 52204 100960 50518 100960 50517 100961 50513 100961 50514 100961 50514 100962 50513 100962 52207 100962 50514 100963 52207 100963 50515 100963 50515 100964 52207 100964 50516 100964 50515 100965 50516 100965 52174 100965 52174 100966 50516 100966 52209 100966 50513 100967 50517 100967 50518 100967 50518 100968 50517 100968 50512 100968 52245 100969 52269 100969 52248 100969 52248 100970 52269 100970 52288 100970 52269 100971 52245 100971 50519 100971 52269 100972 50519 100972 52270 100972 52270 100973 50519 100973 52265 100973 52270 100974 52265 100974 52271 100974 52271 100975 52265 100975 50520 100975 52271 100976 50520 100976 52273 100976 52273 100977 50520 100977 52262 100977 52273 100978 52262 100978 52274 100978 52284 100979 50521 100979 50522 100979 52284 100980 50522 100980 50523 100980 50523 100981 50522 100981 52246 100981 50523 100982 52246 100982 50524 100982 50524 100983 52246 100983 50525 100983 50524 100984 50525 100984 52286 100984 52286 100985 50525 100985 52248 100985 52286 100986 52248 100986 52288 100986 52274 100987 52262 100987 52275 100987 52275 100988 52262 100988 52258 100988 50521 100989 52284 100989 50526 100989 50526 100990 52284 100990 50527 100990 52275 100991 52258 100991 52259 100991 52275 100992 52259 100992 50528 100992 50528 100993 52259 100993 50529 100993 50528 100994 50529 100994 50530 100994 50530 100995 50529 100995 52255 100995 50530 100996 52255 100996 52279 100996 52280 100997 50533 100997 50531 100997 52280 100998 50531 100998 50532 100998 50532 100999 50531 100999 52252 100999 50532 101000 52252 101000 52281 101000 52252 101001 52251 101001 52281 101001 52281 101002 52251 101002 50526 101002 52281 101003 50526 101003 50527 101003 50533 101004 52280 101004 52255 101004 52255 101005 52280 101005 52279 101005 50541 101006 50534 101006 50535 101006 50535 101007 50534 101007 50537 101007 50535 101008 50537 101008 50536 101008 50536 101009 50537 101009 50538 101009 50536 101010 50538 101010 52240 101010 52240 101011 50538 101011 52272 101011 52240 101012 52272 101012 50539 101012 50539 101013 52272 101013 50540 101013 50539 101014 50540 101014 50542 101014 50542 101015 50540 101015 52276 101015 50534 101016 50541 101016 52287 101016 52287 101017 50541 101017 52242 101017 50542 101018 52276 101018 52238 101018 52238 101019 52276 101019 52277 101019 52238 101020 52277 101020 50543 101020 50543 101021 52277 101021 50544 101021 50543 101022 50544 101022 52236 101022 52236 101023 50544 101023 50550 101023 50545 101024 50551 101024 50546 101024 50546 101025 50551 101025 52283 101025 50546 101026 52283 101026 52243 101026 52243 101027 52283 101027 50548 101027 52243 101028 50548 101028 50547 101028 50547 101029 50548 101029 52285 101029 50547 101030 52285 101030 52242 101030 52242 101031 52285 101031 52287 101031 52236 101032 50550 101032 50549 101032 50549 101033 50550 101033 52278 101033 50551 101034 50545 101034 52282 101034 52282 101035 50545 101035 50554 101035 50549 101036 52278 101036 52233 101036 52233 101037 52278 101037 50552 101037 52233 101038 50552 101038 52232 101038 52232 101039 50552 101039 50553 101039 52232 101040 50553 101040 50554 101040 50554 101041 50553 101041 52282 101041 50555 101042 52756 101042 52796 101042 52796 101043 52756 101043 50562 101043 52756 101044 50555 101044 50556 101044 50556 101045 50555 101045 50557 101045 50556 101046 50557 101046 52758 101046 52758 101047 50557 101047 52797 101047 52758 101048 52797 101048 52760 101048 52760 101049 52797 101049 52799 101049 52760 101050 52799 101050 50563 101050 50563 101051 52799 101051 50558 101051 52775 101052 52792 101052 50559 101052 50559 101053 52792 101053 50561 101053 50559 101054 50561 101054 50560 101054 50560 101055 50561 101055 52794 101055 50560 101056 52794 101056 50562 101056 50562 101057 52794 101057 52796 101057 50563 101058 50558 101058 50564 101058 50564 101059 50558 101059 52802 101059 52792 101060 52775 101060 50565 101060 50565 101061 52775 101061 52770 101061 50569 101062 50575 101062 50566 101062 50564 101063 52802 101063 52763 101063 52763 101064 52802 101064 52803 101064 52763 101065 52803 101065 50567 101065 50567 101066 52803 101066 50569 101066 50567 101067 50569 101067 50568 101067 50568 101068 50569 101068 50566 101068 50570 101069 50565 101069 52770 101069 52770 101070 52771 101070 50570 101070 50570 101071 52771 101071 52774 101071 50570 101072 52774 101072 52810 101072 52810 101073 52774 101073 50571 101073 52810 101074 50571 101074 50573 101074 52767 101075 52807 101075 50572 101075 50572 101076 52807 101076 50573 101076 50572 101077 50573 101077 50574 101077 50574 101078 50573 101078 50571 101078 52807 101079 52767 101079 50575 101079 50575 101080 52767 101080 50566 101080 50576 101081 52793 101081 52817 101081 52817 101082 52793 101082 52812 101082 52793 101083 50576 101083 52813 101083 50577 101084 52795 101084 52813 101084 52813 101085 52795 101085 50578 101085 52813 101086 50578 101086 52793 101086 50577 101087 52816 101087 52795 101087 52795 101088 52816 101088 52814 101088 52795 101089 52814 101089 50579 101089 50580 101090 50582 101090 52822 101090 50580 101091 52822 101091 52808 101091 52808 101092 52822 101092 52823 101092 52808 101093 52823 101093 52809 101093 52809 101094 52823 101094 52818 101094 52809 101095 52818 101095 52811 101095 52811 101096 52818 101096 52817 101096 52811 101097 52817 101097 52812 101097 50579 101098 52814 101098 50584 101098 50584 101099 52814 101099 50581 101099 50582 101100 50580 101100 50583 101100 50583 101101 50580 101101 52806 101101 50584 101102 50581 101102 52779 101102 50584 101103 52779 101103 50585 101103 50585 101104 52779 101104 50586 101104 50585 101105 50586 101105 52798 101105 52798 101106 50586 101106 52781 101106 52798 101107 52781 101107 52800 101107 52800 101108 52781 101108 50591 101108 52800 101109 50591 101109 52801 101109 52804 101110 50590 101110 52791 101110 52804 101111 52791 101111 50587 101111 50587 101112 52791 101112 50588 101112 50587 101113 50588 101113 52805 101113 50588 101114 50589 101114 52805 101114 52805 101115 50589 101115 50583 101115 52805 101116 50583 101116 52806 101116 50590 101117 52804 101117 50591 101117 50591 101118 52804 101118 52801 101118 52843 101119 50592 101119 52842 101119 52842 101120 50592 101120 50593 101120 50592 101121 52843 101121 50594 101121 50594 101122 52843 101122 52844 101122 50594 101123 52844 101123 50595 101123 50595 101124 52844 101124 50596 101124 50595 101125 50596 101125 52736 101125 52736 101126 50596 101126 52847 101126 52746 101127 52837 101127 52748 101127 52748 101128 52837 101128 50597 101128 52748 101129 50597 101129 52750 101129 52750 101130 50597 101130 52840 101130 52750 101131 52840 101131 50593 101131 50593 101132 52840 101132 52842 101132 52736 101133 52847 101133 52738 101133 52738 101134 52847 101134 50598 101134 52837 101135 52746 101135 52857 101135 52857 101136 52746 101136 50603 101136 52851 101137 50599 101137 52742 101137 52738 101138 50598 101138 52739 101138 52739 101139 50598 101139 52849 101139 52739 101140 52849 101140 52740 101140 52740 101141 52849 101141 52851 101141 52740 101142 52851 101142 50600 101142 50600 101143 52851 101143 52742 101143 50604 101144 50601 101144 52743 101144 52743 101145 50601 101145 52854 101145 52743 101146 52854 101146 50602 101146 50602 101147 52854 101147 52856 101147 50602 101148 52856 101148 50603 101148 50603 101149 52856 101149 52857 101149 50601 101150 50604 101150 50599 101150 50599 101151 50604 101151 52742 101151 52877 101152 52838 101152 50608 101152 50608 101153 52838 101153 50609 101153 52838 101154 52877 101154 52863 101154 52861 101155 50605 101155 52863 101155 52863 101156 50605 101156 52839 101156 52863 101157 52839 101157 52838 101157 52861 101158 52860 101158 50605 101158 50605 101159 52860 101159 52859 101159 50605 101160 52859 101160 52841 101160 52853 101161 52874 101161 52873 101161 52870 101162 50606 101162 52873 101162 52873 101163 50606 101163 52855 101163 52873 101164 52855 101164 52853 101164 52870 101165 50607 101165 50606 101165 50606 101166 50607 101166 50608 101166 50606 101167 50608 101167 50609 101167 52841 101168 52859 101168 50610 101168 50610 101169 52859 101169 50611 101169 52874 101170 52853 101170 52835 101170 52835 101171 52853 101171 52852 101171 50610 101172 50611 101172 50612 101172 52828 101173 52846 101173 50612 101173 50612 101174 52846 101174 52845 101174 50612 101175 52845 101175 50610 101175 52828 101176 50613 101176 52846 101176 52846 101177 50613 101177 50619 101177 52846 101178 50619 101178 52848 101178 50614 101179 52834 101179 50615 101179 50617 101180 50616 101180 50615 101180 50615 101181 50616 101181 52850 101181 50615 101182 52850 101182 50614 101182 50617 101183 50618 101183 50616 101183 50616 101184 50618 101184 52835 101184 50616 101185 52835 101185 52852 101185 52834 101186 50614 101186 50619 101186 50619 101187 50614 101187 52848 101187 50625 101188 50631 101188 51934 101188 50629 101189 50663 101189 50620 101189 50633 101190 50626 101190 50621 101190 50622 101191 50623 101191 51531 101191 51531 101192 50623 101192 50633 101192 51531 101193 50633 101193 50624 101193 50624 101194 50633 101194 50621 101194 50631 101195 50625 101195 50633 101195 50633 101196 50625 101196 51927 101196 50633 101197 51927 101197 50626 101197 50639 101198 50627 101198 50628 101198 50636 101199 50640 101199 51932 101199 51932 101200 50640 101200 50639 101200 51932 101201 50639 101201 51937 101201 51937 101202 50639 101202 50628 101202 51937 101203 50628 101203 51929 101203 51929 101204 50628 101204 50627 101204 51929 101205 50627 101205 51930 101205 51930 101206 50627 101206 50641 101206 51930 101207 50641 101207 50629 101207 51938 101208 51936 101208 50620 101208 50620 101209 51936 101209 51935 101209 50620 101210 51935 101210 50629 101210 50629 101211 51935 101211 50630 101211 50629 101212 50630 101212 51930 101212 51932 101213 51934 101213 50636 101213 50636 101214 51934 101214 50631 101214 50636 101215 50631 101215 50632 101215 50632 101216 50631 101216 50633 101216 50632 101217 50633 101217 50635 101217 50635 101218 50633 101218 50623 101218 50662 101219 50642 101219 50634 101219 50641 101220 50650 101220 50634 101220 50622 101221 50643 101221 50623 101221 50623 101222 50643 101222 50635 101222 50635 101223 50643 101223 50645 101223 50635 101224 50645 101224 50632 101224 50638 101225 50640 101225 50645 101225 50645 101226 50640 101226 50636 101226 50645 101227 50636 101227 50632 101227 50637 101228 50627 101228 50638 101228 50638 101229 50627 101229 50639 101229 50638 101230 50639 101230 50640 101230 50641 101231 50634 101231 50629 101231 50629 101232 50634 101232 50642 101232 50629 101233 50642 101233 50663 101233 50643 101234 50644 101234 50645 101234 50645 101235 50644 101235 51520 101235 50645 101236 51520 101236 50638 101236 50638 101237 51520 101237 51519 101237 50638 101238 51519 101238 50637 101238 50637 101239 51519 101239 50646 101239 50637 101240 50646 101240 50649 101240 50649 101241 50646 101241 50647 101241 50649 101242 50647 101242 50648 101242 50648 101243 50662 101243 50649 101243 50649 101244 50662 101244 50634 101244 50649 101245 50634 101245 50637 101245 50637 101246 50634 101246 50650 101246 50637 101247 50650 101247 50627 101247 50627 101248 50650 101248 50641 101248 50661 101249 54512 101249 54511 101249 50651 101250 50655 101250 50652 101250 50652 101251 50655 101251 50653 101251 50652 101252 50653 101252 50654 101252 50654 101253 50653 101253 50660 101253 50654 101254 50660 101254 50664 101254 50657 101255 50655 101255 50656 101255 50656 101256 50655 101256 50651 101256 50656 101257 50651 101257 51943 101257 50657 101258 50658 101258 50655 101258 50655 101259 50658 101259 50659 101259 50655 101260 50659 101260 50653 101260 50653 101261 50659 101261 50661 101261 50653 101262 50661 101262 50660 101262 50660 101263 50661 101263 54511 101263 50660 101264 54511 101264 50664 101264 50647 101265 54512 101265 50648 101265 50648 101266 54512 101266 50661 101266 50648 101267 50661 101267 50662 101267 50662 101268 50661 101268 50659 101268 50662 101269 50659 101269 50642 101269 50642 101270 50659 101270 50658 101270 50642 101271 50658 101271 50663 101271 50663 101272 50658 101272 50657 101272 50654 101273 50664 101273 51957 101273 50665 101274 50675 101274 50666 101274 50654 101275 51957 101275 50652 101275 50652 101276 51957 101276 50665 101276 50652 101277 50665 101277 50651 101277 50651 101278 50665 101278 50666 101278 50651 101279 50666 101279 51943 101279 50680 101280 50667 101280 50669 101280 50667 101281 50695 101281 50668 101281 51959 101282 51963 101282 50680 101282 50667 101283 50668 101283 50669 101283 50669 101284 50668 101284 51940 101284 50669 101285 51940 101285 50671 101285 50671 101286 51940 101286 50670 101286 50671 101287 50670 101287 50673 101287 50673 101288 50670 101288 51942 101288 50673 101289 51942 101289 50674 101289 50674 101290 51942 101290 51943 101290 50674 101291 51943 101291 50666 101291 50680 101292 50669 101292 51959 101292 51959 101293 50669 101293 50671 101293 51959 101294 50671 101294 51961 101294 51961 101295 50671 101295 50673 101295 51961 101296 50673 101296 50672 101296 50672 101297 50673 101297 50674 101297 50672 101298 50674 101298 51962 101298 51962 101299 50674 101299 50666 101299 51962 101300 50666 101300 50675 101300 50676 101301 50683 101301 50677 101301 50678 101302 50679 101302 50677 101302 51969 101303 50677 101303 51970 101303 50667 101304 50680 101304 50689 101304 50689 101305 50680 101305 51963 101305 50681 101306 50682 101306 51969 101306 51969 101307 50682 101307 50677 101307 50679 101308 51970 101308 50677 101308 50683 101309 50678 101309 50677 101309 51967 101310 50676 101310 50677 101310 50693 101311 50684 101311 50692 101311 50692 101312 50684 101312 51968 101312 50692 101313 51968 101313 50685 101313 50685 101314 51968 101314 51967 101314 50685 101315 51967 101315 50677 101315 51963 101316 50686 101316 50689 101316 50689 101317 50686 101317 50687 101317 50689 101318 50687 101318 50690 101318 50695 101319 50667 101319 50688 101319 50688 101320 50667 101320 50689 101320 50688 101321 50689 101321 50709 101321 50709 101322 50689 101322 50690 101322 50709 101323 50690 101323 50713 101323 50713 101324 50690 101324 50714 101324 50691 101325 50714 101325 50692 101325 50692 101326 50714 101326 50690 101326 50692 101327 50690 101327 50693 101327 50693 101328 50690 101328 50687 101328 50677 101329 50707 101329 50685 101329 50685 101330 50707 101330 50706 101330 50685 101331 50706 101331 50692 101331 50692 101332 50706 101332 50705 101332 50692 101333 50705 101333 50691 101333 50694 101334 50695 101334 50688 101334 51917 101335 50696 101335 50697 101335 50697 101336 50696 101336 50715 101336 50697 101337 50715 101337 51933 101337 51933 101338 50715 101338 51928 101338 50717 101339 50698 101339 51928 101339 50698 101340 50717 101340 50699 101340 50699 101341 50717 101341 50708 101341 50699 101342 50708 101342 50700 101342 51925 101343 50701 101343 50702 101343 50702 101344 50701 101344 50703 101344 50702 101345 50703 101345 50708 101345 50708 101346 50703 101346 50704 101346 50708 101347 50704 101347 50700 101347 50724 101348 50677 101348 50682 101348 50716 101349 50705 101349 50722 101349 50722 101350 50705 101350 50706 101350 50722 101351 50706 101351 50724 101351 50724 101352 50706 101352 50707 101352 50724 101353 50707 101353 50677 101353 50723 101354 50702 101354 50721 101354 50721 101355 50702 101355 50708 101355 50721 101356 50708 101356 50720 101356 50720 101357 50708 101357 50717 101357 50720 101358 50717 101358 50719 101358 50694 101359 50688 101359 50710 101359 50710 101360 50688 101360 50709 101360 50710 101361 50709 101361 50713 101361 50712 101362 50714 101362 50691 101362 51947 101363 50694 101363 50711 101363 50711 101364 50694 101364 50710 101364 50711 101365 50710 101365 50712 101365 50712 101366 50710 101366 50713 101366 50712 101367 50713 101367 50714 101367 50696 101368 51947 101368 50715 101368 50715 101369 51947 101369 50711 101369 50715 101370 50711 101370 50718 101370 50718 101371 50711 101371 50712 101371 50718 101372 50712 101372 50716 101372 50716 101373 50712 101373 50691 101373 50716 101374 50691 101374 50705 101374 51928 101375 50715 101375 50717 101375 50717 101376 50715 101376 50718 101376 50717 101377 50718 101377 50719 101377 50719 101378 50718 101378 50716 101378 50719 101379 50716 101379 50720 101379 50720 101380 50716 101380 50722 101380 50720 101381 50722 101381 50721 101381 50721 101382 50722 101382 50724 101382 50721 101383 50724 101383 50723 101383 50723 101384 50724 101384 50682 101384 50723 101385 50682 101385 50681 101385 50741 101386 50764 101386 50763 101386 50764 101387 50741 101387 50761 101387 50726 101388 50740 101388 50725 101388 51997 101389 50726 101389 50748 101389 50748 101390 50726 101390 50725 101390 50748 101391 50725 101391 50749 101391 50749 101392 50725 101392 50727 101392 50780 101393 52001 101393 50739 101393 50739 101394 52001 101394 50737 101394 50761 101395 50741 101395 50728 101395 50728 101396 50741 101396 50729 101396 50728 101397 50729 101397 50730 101397 52015 101398 50743 101398 52014 101398 52014 101399 50743 101399 51983 101399 52014 101400 51983 101400 52013 101400 50752 101401 50731 101401 50743 101401 50743 101402 50731 101402 50732 101402 50743 101403 50732 101403 51983 101403 51990 101404 50734 101404 50733 101404 50734 101405 50735 101405 50733 101405 50733 101406 50735 101406 51975 101406 50733 101407 51975 101407 51977 101407 50736 101408 50750 101408 50747 101408 50747 101409 50766 101409 50736 101409 50736 101410 50766 101410 50738 101410 50736 101411 50738 101411 50737 101411 50737 101412 50738 101412 50767 101412 50737 101413 50767 101413 50739 101413 50751 101414 50727 101414 50733 101414 50733 101415 50727 101415 50725 101415 50733 101416 50725 101416 51990 101416 51990 101417 50725 101417 50740 101417 50744 101418 50729 101418 50745 101418 50745 101419 50729 101419 50741 101419 50745 101420 50741 101420 50742 101420 50742 101421 50741 101421 50763 101421 50742 101422 50763 101422 50765 101422 52015 101423 50744 101423 50743 101423 50743 101424 50744 101424 50745 101424 50743 101425 50745 101425 50746 101425 50746 101426 50745 101426 50742 101426 50746 101427 50742 101427 50750 101427 50750 101428 50742 101428 50765 101428 50750 101429 50765 101429 50747 101429 52001 101430 50748 101430 50737 101430 50737 101431 50748 101431 50749 101431 50737 101432 50749 101432 50736 101432 50736 101433 50749 101433 50727 101433 50736 101434 50727 101434 50750 101434 50750 101435 50727 101435 50751 101435 50750 101436 50751 101436 50746 101436 50746 101437 50751 101437 50733 101437 50746 101438 50733 101438 50743 101438 50743 101439 50733 101439 51977 101439 50743 101440 51977 101440 50752 101440 50760 101441 50761 101441 52020 101441 50768 101442 50774 101442 50769 101442 50753 101443 50774 101443 52026 101443 52026 101444 50774 101444 50768 101444 52026 101445 50768 101445 50755 101445 50754 101446 50758 101446 50755 101446 50755 101447 50758 101447 52027 101447 50755 101448 52027 101448 52026 101448 50761 101449 50757 101449 50756 101449 50756 101450 50757 101450 52022 101450 50756 101451 52022 101451 50754 101451 50754 101452 52022 101452 52021 101452 50754 101453 52021 101453 50758 101453 50761 101454 50759 101454 52023 101454 52017 101455 50759 101455 50761 101455 50760 101456 52017 101456 50761 101456 50730 101457 50762 101457 50728 101457 50728 101458 50762 101458 50761 101458 52020 101459 50761 101459 50762 101459 50763 101460 50764 101460 50756 101460 50756 101461 50764 101461 50761 101461 52023 101462 50757 101462 50761 101462 50763 101463 50756 101463 50765 101463 50765 101464 50756 101464 50754 101464 50765 101465 50754 101465 50747 101465 50747 101466 50754 101466 50766 101466 50766 101467 50754 101467 50755 101467 50766 101468 50755 101468 50738 101468 50738 101469 50755 101469 50767 101469 50767 101470 50755 101470 50768 101470 50767 101471 50768 101471 50739 101471 50739 101472 50768 101472 50769 101472 50739 101473 50769 101473 50780 101473 52030 101474 50782 101474 50770 101474 50778 101475 50769 101475 50774 101475 52030 101476 50770 101476 50771 101476 50771 101477 50770 101477 50772 101477 50771 101478 50772 101478 52029 101478 52029 101479 50772 101479 50777 101479 52029 101480 50777 101480 52028 101480 52028 101481 50777 101481 50778 101481 52028 101482 50778 101482 50773 101482 50773 101483 50778 101483 50774 101483 50773 101484 50774 101484 50753 101484 50782 101485 50797 101485 50775 101485 50782 101486 50775 101486 50770 101486 50770 101487 50775 101487 50776 101487 50770 101488 50776 101488 50772 101488 50772 101489 50776 101489 51996 101489 50772 101490 51996 101490 50777 101490 50777 101491 51996 101491 50779 101491 50777 101492 50779 101492 50778 101492 50778 101493 50779 101493 50780 101493 50778 101494 50780 101494 50769 101494 50782 101495 52030 101495 50781 101495 50797 101496 50782 101496 50795 101496 50795 101497 50782 101497 50781 101497 50795 101498 50781 101498 50783 101498 50784 101499 50794 101499 50783 101499 50783 101500 50794 101500 50785 101500 50783 101501 50785 101501 50795 101501 50792 101502 54499 101502 50786 101502 50787 101503 50791 101503 50789 101503 50789 101504 50791 101504 50788 101504 50789 101505 50788 101505 50809 101505 50809 101506 50788 101506 50790 101506 50809 101507 50790 101507 50793 101507 51994 101508 50791 101508 52005 101508 52005 101509 50791 101509 50787 101509 52005 101510 50787 101510 50800 101510 51994 101511 50798 101511 50791 101511 50791 101512 50798 101512 50796 101512 50791 101513 50796 101513 50788 101513 50788 101514 50796 101514 50792 101514 50788 101515 50792 101515 50790 101515 50790 101516 50792 101516 50786 101516 50790 101517 50786 101517 50793 101517 50784 101518 54499 101518 50794 101518 50794 101519 54499 101519 50792 101519 50794 101520 50792 101520 50785 101520 50785 101521 50792 101521 50796 101521 50785 101522 50796 101522 50795 101522 50795 101523 50796 101523 50798 101523 50795 101524 50798 101524 50797 101524 50797 101525 50798 101525 51994 101525 50789 101526 50809 101526 50812 101526 50826 101527 51526 101527 51525 101527 50804 101528 50827 101528 50802 101528 50799 101529 50800 101529 50787 101529 50799 101530 50787 101530 50817 101530 50813 101531 50815 101531 50801 101531 50801 101532 50815 101532 50817 101532 50801 101533 50817 101533 50811 101533 50811 101534 50817 101534 50787 101534 50827 101535 50803 101535 50802 101535 50802 101536 50803 101536 50823 101536 50802 101537 50823 101537 50805 101537 50826 101538 50804 101538 51526 101538 51526 101539 50804 101539 50802 101539 51526 101540 50802 101540 51528 101540 51528 101541 50802 101541 50805 101541 51528 101542 50805 101542 50806 101542 50806 101543 50805 101543 50807 101543 50806 101544 50807 101544 50808 101544 50808 101545 50807 101545 50812 101545 50808 101546 50812 101546 50810 101546 50810 101547 50812 101547 50809 101547 50810 101548 50809 101548 50793 101548 50787 101549 50789 101549 50811 101549 50811 101550 50789 101550 50812 101550 50811 101551 50812 101551 50801 101551 50801 101552 50812 101552 50807 101552 50801 101553 50807 101553 50813 101553 50813 101554 50807 101554 50805 101554 50813 101555 50805 101555 50822 101555 50822 101556 50805 101556 50823 101556 50826 101557 51525 101557 51540 101557 50814 101558 51991 101558 51992 101558 50814 101559 50800 101559 51991 101559 51991 101560 50800 101560 50799 101560 51991 101561 50799 101561 50817 101561 50813 101562 50820 101562 50815 101562 50815 101563 50820 101563 50816 101563 50815 101564 50816 101564 50817 101564 50817 101565 50816 101565 50818 101565 50817 101566 50818 101566 51991 101566 50819 101567 50820 101567 50821 101567 50821 101568 50820 101568 50813 101568 50821 101569 50813 101569 50819 101569 50819 101570 50813 101570 50822 101570 50819 101571 50822 101571 51993 101571 51993 101572 50822 101572 50823 101572 50803 101573 51988 101573 50823 101573 50823 101574 51988 101574 51989 101574 50823 101575 51989 101575 51993 101575 51976 101576 50824 101576 51974 101576 51974 101577 50824 101577 50825 101577 51974 101578 50825 101578 51973 101578 51540 101579 51978 101579 51973 101579 51973 101580 50825 101580 51540 101580 51540 101581 50825 101581 50804 101581 51540 101582 50804 101582 50826 101582 51976 101583 51988 101583 50824 101583 50824 101584 51988 101584 50803 101584 50824 101585 50803 101585 50825 101585 50825 101586 50803 101586 50827 101586 50825 101587 50827 101587 50804 101587 50828 101588 50832 101588 50829 101588 50830 101589 50831 101589 50845 101589 50845 101590 50831 101590 54121 101590 50845 101591 54121 101591 50843 101591 50843 101592 54121 101592 50835 101592 50843 101593 50835 101593 50842 101593 50829 101594 50832 101594 50833 101594 50833 101595 50832 101595 54141 101595 50833 101596 54141 101596 50830 101596 50830 101597 54141 101597 50834 101597 50830 101598 50834 101598 50831 101598 50853 101599 50840 101599 50899 101599 50838 101600 53540 101600 50839 101600 50849 101601 50848 101601 50855 101601 50841 101602 50880 101602 50848 101602 50835 101603 54113 101603 50842 101603 50842 101604 54113 101604 50836 101604 50842 101605 50836 101605 50880 101605 50858 101606 53542 101606 50837 101606 50837 101607 53542 101607 50838 101607 50837 101608 50838 101608 50853 101608 50853 101609 50838 101609 50839 101609 50853 101610 50839 101610 50840 101610 50880 101611 50841 101611 50842 101611 50842 101612 50841 101612 50851 101612 50842 101613 50851 101613 50843 101613 50843 101614 50851 101614 50844 101614 50843 101615 50844 101615 50845 101615 50845 101616 50844 101616 50852 101616 50845 101617 50852 101617 50830 101617 50830 101618 50852 101618 50846 101618 50830 101619 50846 101619 50833 101619 50833 101620 50846 101620 50854 101620 50833 101621 50854 101621 50829 101621 50829 101622 50854 101622 50847 101622 50829 101623 50847 101623 50828 101623 50828 101624 50847 101624 54503 101624 50828 101625 54503 101625 54136 101625 50848 101626 50849 101626 50841 101626 50841 101627 50849 101627 50850 101627 50841 101628 50850 101628 50851 101628 50851 101629 50850 101629 50857 101629 50851 101630 50857 101630 50844 101630 50844 101631 50857 101631 50858 101631 50844 101632 50858 101632 50852 101632 50852 101633 50858 101633 50837 101633 50852 101634 50837 101634 50846 101634 50846 101635 50837 101635 50853 101635 50846 101636 50853 101636 50854 101636 50854 101637 50853 101637 50899 101637 50854 101638 50899 101638 50847 101638 50855 101639 50856 101639 50849 101639 50849 101640 50856 101640 53535 101640 50849 101641 53535 101641 50850 101641 50850 101642 53535 101642 53536 101642 50850 101643 53536 101643 50857 101643 50857 101644 53536 101644 50859 101644 50857 101645 50859 101645 50858 101645 50858 101646 50859 101646 50860 101646 50858 101647 50860 101647 53542 101647 54519 101648 54125 101648 54516 101648 54516 101649 54125 101649 54123 101649 54117 101650 50861 101650 50887 101650 50887 101651 50861 101651 54137 101651 50887 101652 54137 101652 50886 101652 50886 101653 54137 101653 54125 101653 50886 101654 54125 101654 50884 101654 50884 101655 54125 101655 54519 101655 50884 101656 54519 101656 50881 101656 50862 101657 54115 101657 50889 101657 50889 101658 54115 101658 54117 101658 50889 101659 54117 101659 50863 101659 50863 101660 54117 101660 50887 101660 50862 101661 50889 101661 50864 101661 50864 101662 50889 101662 50890 101662 50864 101663 50890 101663 54114 101663 54114 101664 50890 101664 50836 101664 54114 101665 50836 101665 54113 101665 50865 101666 50855 101666 50848 101666 50848 101667 50879 101667 50865 101667 50865 101668 50879 101668 50866 101668 50865 101669 50866 101669 53387 101669 53387 101670 50866 101670 50876 101670 53387 101671 50876 101671 53385 101671 53385 101672 50876 101672 50867 101672 50867 101673 50876 101673 50875 101673 50867 101674 50875 101674 50868 101674 50868 101675 50875 101675 50873 101675 50868 101676 50873 101676 50870 101676 50870 101677 50873 101677 50869 101677 50870 101678 50869 101678 50871 101678 50871 101679 50869 101679 53377 101679 53377 101680 50869 101680 50872 101680 53377 101681 50872 101681 53379 101681 50882 101682 50872 101682 50883 101682 50883 101683 50872 101683 50869 101683 50883 101684 50869 101684 50885 101684 50885 101685 50869 101685 50873 101685 50885 101686 50873 101686 50874 101686 50874 101687 50873 101687 50875 101687 50874 101688 50875 101688 50888 101688 50888 101689 50875 101689 50876 101689 50888 101690 50876 101690 50877 101690 50877 101691 50876 101691 50866 101691 50877 101692 50866 101692 50878 101692 50878 101693 50866 101693 50879 101693 50878 101694 50879 101694 50880 101694 50880 101695 50879 101695 50848 101695 50881 101696 50882 101696 50884 101696 50884 101697 50882 101697 50883 101697 50884 101698 50883 101698 50886 101698 50886 101699 50883 101699 50885 101699 50886 101700 50885 101700 50887 101700 50887 101701 50885 101701 50874 101701 50887 101702 50874 101702 50863 101702 50863 101703 50874 101703 50888 101703 50863 101704 50888 101704 50889 101704 50889 101705 50888 101705 50877 101705 50889 101706 50877 101706 50890 101706 50890 101707 50877 101707 50878 101707 50890 101708 50878 101708 50836 101708 50836 101709 50878 101709 50880 101709 50839 101710 53540 101710 53538 101710 50891 101711 50893 101711 50892 101711 53511 101712 54506 101712 50891 101712 50891 101713 54506 101713 54507 101713 50891 101714 54507 101714 50893 101714 54502 101715 50847 101715 50899 101715 50892 101716 50893 101716 50894 101716 50894 101717 50893 101717 50896 101717 50894 101718 50896 101718 50895 101718 50895 101719 50896 101719 50897 101719 50895 101720 50897 101720 50898 101720 50897 101721 54502 101721 50898 101721 50898 101722 54502 101722 50899 101722 50898 101723 50899 101723 53538 101723 53538 101724 50899 101724 50840 101724 53538 101725 50840 101725 50839 101725 53703 101726 53704 101726 50903 101726 50905 101727 54508 101727 50900 101727 50905 101728 50900 101728 50901 101728 50901 101729 50900 101729 50902 101729 50901 101730 50902 101730 53706 101730 50903 101731 53704 101731 50902 101731 50902 101732 53704 101732 53705 101732 50902 101733 53705 101733 53706 101733 54506 101734 53511 101734 50903 101734 50903 101735 53511 101735 50904 101735 50903 101736 50904 101736 53703 101736 54508 101737 50905 101737 54501 101737 54501 101738 50905 101738 50906 101738 50907 101739 50910 101739 50909 101739 54501 101740 50906 101740 53209 101740 53209 101741 50906 101741 50907 101741 53209 101742 50907 101742 53211 101742 53211 101743 50907 101743 50909 101743 54496 101744 54495 101744 50908 101744 50908 101745 53216 101745 54496 101745 54496 101746 53216 101746 50912 101746 54496 101747 50912 101747 54497 101747 50909 101748 50910 101748 50911 101748 50911 101749 50910 101749 50914 101749 50912 101750 50913 101750 54497 101750 54497 101751 50913 101751 53213 101751 54497 101752 53213 101752 50914 101752 50914 101753 53213 101753 50915 101753 50914 101754 50915 101754 50911 101754 50908 101755 54495 101755 53207 101755 53207 101756 54495 101756 50916 101756 53207 101757 50916 101757 50917 101757 50917 101758 50916 101758 50921 101758 50924 101759 53201 101759 50918 101759 50924 101760 50918 101760 54490 101760 50918 101761 53200 101761 54490 101761 54490 101762 53200 101762 53199 101762 54490 101763 53199 101763 50919 101763 50919 101764 53199 101764 50920 101764 50919 101765 50920 101765 54491 101765 50917 101766 50921 101766 50922 101766 50922 101767 50921 101767 54491 101767 50922 101768 54491 101768 53197 101768 53197 101769 54491 101769 50920 101769 50925 101770 53409 101770 50923 101770 53201 101771 50924 101771 53206 101771 53206 101772 50924 101772 50925 101772 53206 101773 50925 101773 53205 101773 53205 101774 50925 101774 50923 101774 50923 101775 53409 101775 50926 101775 50926 101776 53409 101776 50931 101776 50932 101777 54514 101777 50927 101777 50927 101778 54514 101778 50928 101778 50928 101779 54514 101779 53734 101779 53734 101780 54514 101780 50929 101780 53734 101781 50929 101781 50930 101781 50930 101782 50929 101782 54509 101782 50930 101783 54509 101783 53735 101783 53735 101784 54509 101784 53729 101784 53729 101785 54509 101785 50926 101785 53729 101786 50926 101786 50931 101786 50932 101787 50927 101787 50934 101787 50932 101788 50934 101788 50933 101788 50934 101789 53372 101789 50933 101789 50933 101790 53372 101790 53371 101790 50933 101791 53371 101791 50935 101791 50935 101792 53371 101792 53376 101792 50935 101793 53376 101793 54515 101793 54515 101794 53376 101794 50936 101794 54515 101795 50936 101795 54517 101795 54517 101796 50936 101796 50937 101796 54517 101797 50937 101797 54518 101797 54518 101798 50937 101798 53382 101798 54518 101799 53382 101799 54519 101799 53379 101800 50872 101800 53381 101800 53381 101801 50872 101801 50882 101801 53381 101802 50882 101802 53382 101802 53382 101803 50882 101803 50881 101803 53382 101804 50881 101804 54519 101804 50940 101805 51958 101805 54124 101805 54124 101806 51958 101806 50938 101806 54124 101807 50938 101807 54122 101807 54122 101808 50938 101808 50939 101808 54122 101809 50939 101809 51956 101809 51958 101810 50940 101810 51960 101810 51960 101811 50940 101811 50941 101811 51960 101812 50941 101812 51964 101812 51964 101813 50941 101813 54116 101813 51964 101814 54116 101814 51965 101814 51965 101815 54116 101815 50942 101815 51965 101816 50942 101816 51966 101816 51966 101817 50942 101817 50943 101817 51966 101818 50943 101818 50944 101818 50944 101819 50943 101819 54139 101819 50944 101820 54139 101820 51972 101820 51972 101821 54139 101821 54151 101821 50945 101822 50946 101822 50947 101822 50947 101823 51951 101823 50945 101823 50945 101824 51951 101824 50948 101824 50945 101825 50948 101825 54133 101825 54133 101826 50948 101826 51952 101826 54133 101827 51952 101827 54152 101827 51972 101828 54151 101828 51949 101828 51949 101829 54151 101829 54152 101829 51949 101830 54152 101830 50949 101830 50949 101831 54152 101831 51952 101831 50947 101832 50946 101832 51954 101832 51954 101833 50946 101833 54157 101833 53202 101834 51955 101834 50950 101834 53202 101835 50950 101835 54154 101835 51954 101836 54157 101836 50950 101836 50950 101837 54157 101837 54155 101837 50950 101838 54155 101838 54154 101838 50951 101839 50954 101839 50952 101839 54505 101840 50953 101840 54504 101840 54504 101841 50953 101841 50951 101841 54504 101842 50951 101842 54135 101842 54135 101843 50951 101843 50952 101843 50952 101844 50954 101844 54140 101844 54140 101845 50954 101845 50956 101845 52019 101846 54119 101846 52018 101846 52018 101847 54119 101847 54102 101847 52018 101848 54102 101848 52024 101848 52024 101849 54102 101849 54120 101849 52024 101850 54120 101850 52025 101850 52025 101851 54120 101851 50955 101851 52025 101852 50955 101852 50956 101852 50956 101853 50955 101853 54140 101853 54119 101854 52019 101854 50958 101854 50958 101855 52019 101855 52016 101855 50957 101856 50958 101856 52016 101856 52007 101857 54134 101857 50959 101857 50959 101858 54134 101858 50960 101858 50959 101859 50960 101859 52010 101859 52010 101860 50960 101860 50957 101860 52010 101861 50957 101861 52011 101861 52011 101862 50957 101862 52016 101862 54134 101863 52007 101863 54108 101863 54108 101864 52007 101864 50963 101864 50961 101865 54111 101865 54110 101865 53212 101866 50961 101866 50962 101866 50962 101867 50961 101867 54110 101867 50962 101868 54110 101868 50963 101868 50963 101869 54110 101869 54108 101869 50968 101870 54149 101870 51913 101870 51913 101871 54149 101871 50964 101871 51913 101872 50964 101872 51916 101872 51916 101873 50964 101873 50966 101873 51916 101874 50966 101874 50965 101874 50965 101875 50966 101875 54118 101875 50965 101876 54118 101876 51897 101876 51897 101877 54118 101877 50967 101877 54149 101878 50968 101878 50971 101878 50971 101879 50968 101879 51912 101879 54106 101880 50977 101880 51902 101880 51897 101881 50967 101881 50969 101881 50969 101882 50967 101882 54142 101882 50969 101883 54142 101883 51898 101883 51898 101884 54142 101884 54106 101884 51898 101885 54106 101885 51900 101885 51900 101886 54106 101886 51902 101886 50970 101887 50971 101887 51912 101887 51908 101888 50972 101888 50973 101888 50973 101889 50972 101889 50974 101889 50973 101890 50974 101890 50975 101890 50975 101891 50974 101891 50970 101891 50975 101892 50970 101892 50976 101892 50976 101893 50970 101893 51912 101893 51902 101894 50977 101894 51901 101894 51901 101895 50977 101895 50978 101895 50972 101896 51908 101896 50979 101896 50979 101897 51908 101897 51907 101897 51901 101898 50978 101898 51904 101898 51904 101899 50978 101899 50980 101899 51904 101900 50980 101900 50981 101900 50981 101901 50980 101901 54132 101901 50981 101902 54132 101902 50982 101902 50982 101903 54132 101903 54130 101903 50982 101904 54130 101904 51907 101904 51907 101905 54130 101905 50979 101905 51530 101906 51548 101906 51529 101906 51529 101907 51548 101907 51547 101907 51529 101908 51547 101908 51527 101908 51527 101909 51547 101909 50983 101909 51527 101910 50983 101910 51539 101910 51539 101911 50983 101911 51545 101911 50998 101912 50997 101912 50984 101912 50998 101913 50984 101913 50985 101913 50985 101914 50984 101914 50987 101914 50985 101915 50987 101915 50986 101915 50987 101916 50988 101916 50986 101916 50986 101917 50988 101917 50990 101917 50986 101918 50990 101918 50989 101918 50989 101919 50990 101919 51543 101919 50989 101920 51543 101920 50991 101920 50991 101921 51543 101921 51541 101921 50991 101922 51541 101922 50993 101922 51541 101923 50992 101923 50993 101923 50993 101924 50992 101924 51539 101924 50993 101925 51539 101925 51545 101925 50994 101926 54500 101926 50995 101926 50995 101927 54500 101927 53210 101927 50995 101928 53210 101928 50996 101928 50996 101929 53210 101929 53208 101929 50997 101930 50998 101930 54745 101930 54745 101931 50998 101931 51546 101931 54745 101932 51546 101932 50995 101932 50995 101933 51546 101933 50999 101933 50995 101934 50999 101934 50994 101934 54798 101935 51000 101935 53204 101935 53204 101936 51000 101936 51523 101936 51537 101937 51003 101937 51001 101937 51537 101938 51001 101938 51536 101938 51536 101939 51001 101939 51532 101939 51536 101940 51532 101940 51002 101940 51002 101941 51532 101941 54791 101941 51002 101942 54791 101942 54790 101942 51003 101943 51537 101943 51521 101943 51521 101944 51537 101944 51535 101944 51521 101945 51535 101945 51518 101945 51518 101946 51535 101946 51534 101946 51518 101947 51534 101947 51517 101947 51517 101948 51534 101948 54513 101948 51598 101949 54345 101949 51599 101949 51599 101950 54345 101950 54336 101950 51599 101951 54336 101951 51600 101951 51600 101952 54336 101952 51004 101952 51600 101953 51004 101953 51005 101953 51005 101954 51004 101954 54334 101954 51005 101955 54334 101955 51007 101955 51007 101956 54334 101956 51006 101956 51007 101957 51006 101957 51008 101957 51008 101958 51006 101958 54318 101958 51008 101959 54318 101959 54718 101959 54718 101960 54318 101960 54783 101960 51009 101961 54781 101961 51575 101961 51575 101962 54781 101962 54317 101962 51575 101963 54317 101963 51577 101963 51577 101964 54317 101964 51010 101964 51577 101965 51010 101965 51578 101965 51578 101966 51010 101966 54332 101966 51578 101967 54332 101967 51011 101967 51011 101968 54332 101968 54320 101968 51011 101969 54320 101969 51580 101969 51580 101970 54320 101970 54312 101970 51580 101971 54312 101971 51012 101971 51012 101972 54312 101972 54314 101972 51018 101973 51158 101973 53235 101973 51017 101974 51163 101974 51162 101974 51013 101975 51026 101975 51015 101975 51015 101976 51026 101976 51014 101976 51015 101977 51014 101977 53238 101977 53238 101978 51014 101978 53766 101978 53238 101979 53766 101979 51016 101979 51016 101980 53766 101980 53765 101980 51016 101981 53765 101981 53235 101981 53235 101982 53765 101982 51017 101982 53235 101983 51017 101983 51018 101983 51018 101984 51017 101984 51162 101984 51018 101985 51162 101985 51161 101985 51036 101986 51035 101986 53225 101986 53225 101987 51035 101987 54488 101987 53225 101988 54488 101988 51019 101988 51019 101989 54488 101989 51020 101989 51019 101990 51020 101990 53227 101990 53227 101991 51020 101991 51022 101991 53227 101992 51022 101992 51021 101992 51021 101993 51022 101993 51023 101993 51023 101994 51022 101994 54485 101994 51023 101995 54485 101995 53228 101995 53228 101996 54485 101996 54483 101996 53228 101997 54483 101997 53232 101997 53232 101998 54483 101998 54482 101998 53232 101999 54482 101999 51024 101999 54482 102000 54481 102000 51024 102000 51024 102001 54481 102001 51025 102001 51024 102002 51025 102002 53234 102002 53234 102003 51025 102003 51026 102003 53234 102004 51026 102004 51013 102004 51610 102005 51027 102005 51611 102005 51611 102006 51027 102006 51028 102006 51611 102007 51028 102007 53220 102007 51610 102008 51609 102008 51027 102008 51027 102009 51609 102009 51608 102009 51027 102010 51608 102010 53222 102010 53222 102011 51608 102011 51029 102011 51608 102012 51030 102012 51029 102012 51029 102013 51030 102013 51031 102013 51029 102014 51031 102014 53218 102014 53218 102015 51031 102015 51032 102015 53218 102016 51032 102016 51034 102016 51034 102017 51032 102017 51033 102017 51034 102018 51033 102018 53224 102018 53224 102019 51033 102019 51035 102019 53224 102020 51035 102020 51036 102020 51629 102021 51611 102021 51037 102021 51037 102022 51611 102022 53220 102022 51629 102023 51037 102023 51627 102023 51627 102024 51037 102024 53410 102024 51043 102025 51041 102025 51623 102025 51625 102026 53414 102026 53416 102026 51043 102027 51623 102027 53416 102027 53416 102028 51623 102028 51624 102028 53416 102029 51624 102029 51625 102029 51625 102030 51626 102030 53414 102030 53414 102031 51626 102031 51038 102031 53414 102032 51038 102032 53413 102032 51627 102033 53410 102033 51039 102033 51039 102034 53410 102034 53413 102034 51039 102035 53413 102035 51040 102035 51040 102036 53413 102036 51038 102036 51041 102037 51043 102037 51042 102037 51042 102038 51043 102038 54489 102038 51045 102039 51621 102039 51620 102039 51045 102040 51620 102040 51044 102040 51044 102041 51620 102041 51614 102041 51044 102042 51614 102042 54492 102042 54492 102043 51614 102043 51616 102043 54492 102044 51616 102044 54493 102044 54493 102045 51616 102045 51042 102045 54493 102046 51042 102046 54489 102046 51621 102047 51045 102047 54480 102047 54480 102048 51045 102048 51046 102048 54480 102049 51046 102049 51632 102049 51632 102050 51046 102050 51053 102050 54498 102051 51047 102051 51638 102051 54498 102052 51638 102052 51048 102052 51048 102053 51638 102053 51049 102053 51048 102054 51049 102054 51050 102054 51050 102055 51049 102055 51051 102055 51050 102056 51051 102056 51052 102056 51052 102057 51051 102057 51632 102057 51052 102058 51632 102058 51053 102058 51047 102059 54498 102059 51054 102059 51054 102060 54498 102060 51055 102060 53572 102061 51649 102061 51648 102061 51056 102062 51057 102062 51058 102062 53572 102063 51648 102063 51058 102063 51058 102064 51648 102064 51059 102064 51058 102065 51059 102065 51056 102065 51056 102066 51060 102066 51057 102066 51057 102067 51060 102067 51061 102067 51057 102068 51061 102068 53571 102068 51054 102069 51055 102069 51642 102069 51642 102070 51055 102070 53571 102070 51642 102071 53571 102071 51643 102071 51643 102072 53571 102072 51061 102072 51649 102073 53572 102073 51601 102073 51601 102074 53572 102074 53217 102074 51062 102075 51601 102075 51070 102075 51070 102076 51601 102076 53217 102076 51064 102077 53259 102077 51063 102077 51063 102078 53259 102078 53258 102078 51063 102079 53258 102079 53256 102079 51064 102080 51603 102080 53259 102080 53259 102081 51603 102081 51065 102081 53259 102082 51065 102082 53260 102082 53260 102083 51065 102083 51066 102083 53260 102084 51066 102084 53262 102084 53262 102085 51066 102085 53263 102085 53263 102086 51066 102086 51067 102086 53263 102087 51067 102087 51069 102087 51067 102088 51068 102088 51069 102088 51069 102089 51068 102089 51062 102089 51069 102090 51062 102090 51070 102090 53247 102091 53755 102091 53756 102091 53247 102092 53756 102092 51071 102092 51071 102093 53756 102093 51072 102093 51071 102094 51072 102094 51074 102094 51072 102095 53763 102095 51074 102095 51074 102096 53763 102096 51073 102096 51074 102097 51073 102097 51075 102097 51075 102098 51073 102098 51076 102098 51075 102099 51076 102099 53249 102099 53249 102100 51076 102100 53251 102100 53251 102101 51076 102101 51077 102101 53251 102102 51077 102102 51078 102102 51078 102103 51077 102103 53760 102103 51078 102104 53760 102104 53252 102104 53252 102105 53760 102105 53759 102105 53252 102106 53759 102106 53253 102106 53253 102107 53759 102107 53255 102107 53255 102108 53759 102108 51063 102108 53255 102109 51063 102109 53256 102109 51079 102110 51249 102110 53768 102110 53240 102111 53239 102111 51084 102111 53240 102112 51084 102112 53768 102112 53768 102113 51084 102113 51080 102113 53768 102114 51080 102114 51079 102114 53247 102115 51081 102115 53755 102115 53755 102116 51081 102116 53246 102116 53755 102117 53246 102117 53768 102117 53768 102118 53246 102118 51082 102118 53768 102119 51082 102119 53240 102119 51084 102120 53239 102120 51083 102120 51085 102121 51250 102121 51248 102121 51080 102122 51084 102122 51248 102122 51248 102123 51084 102123 51083 102123 51248 102124 51083 102124 51085 102124 51085 102125 51083 102125 53244 102125 51085 102126 53244 102126 51087 102126 51087 102127 53244 102127 51086 102127 51087 102128 51086 102128 51088 102128 51088 102129 51086 102129 53243 102129 54569 102130 51090 102130 51118 102130 51118 102131 51090 102131 51091 102131 51092 102132 51089 102132 51090 102132 51090 102133 51089 102133 53585 102133 51090 102134 53585 102134 51091 102134 51093 102135 53577 102135 51092 102135 51092 102136 53577 102136 53576 102136 51092 102137 53576 102137 51089 102137 51097 102138 51099 102138 51093 102138 51093 102139 51099 102139 51094 102139 51093 102140 51094 102140 53577 102140 53243 102141 51095 102141 51088 102141 51088 102142 51095 102142 51096 102142 51088 102143 51096 102143 51097 102143 51097 102144 51096 102144 51098 102144 51097 102145 51098 102145 51099 102145 51144 102146 51143 102146 53431 102146 53431 102147 51143 102147 54544 102147 53431 102148 54544 102148 53430 102148 53430 102149 54544 102149 53428 102149 53428 102150 54544 102150 51100 102150 53428 102151 51100 102151 53427 102151 53427 102152 51100 102152 51104 102152 53427 102153 51104 102153 53426 102153 51106 102154 51101 102154 54548 102154 54548 102155 51101 102155 51102 102155 54548 102156 51102 102156 51103 102156 51103 102157 51102 102157 53425 102157 51103 102158 53425 102158 54542 102158 54542 102159 53425 102159 53424 102159 54542 102160 53424 102160 51104 102160 51104 102161 53424 102161 51105 102161 51104 102162 51105 102162 53426 102162 51106 102163 54548 102163 51107 102163 51107 102164 54548 102164 51108 102164 51107 102165 51108 102165 51109 102165 51109 102166 51108 102166 54577 102166 51109 102167 54577 102167 51110 102167 51110 102168 54577 102168 54578 102168 51110 102169 54578 102169 51111 102169 51111 102170 54578 102170 51113 102170 51111 102171 51113 102171 53464 102171 53464 102172 51113 102172 51112 102172 51112 102173 51113 102173 54574 102173 51112 102174 54574 102174 51114 102174 51114 102175 54574 102175 51115 102175 51114 102176 51115 102176 53423 102176 53423 102177 51115 102177 51116 102177 51116 102178 51115 102178 51117 102178 51116 102179 51117 102179 53421 102179 53421 102180 51117 102180 53422 102180 53422 102181 51117 102181 54571 102181 53422 102182 54571 102182 53420 102182 53420 102183 54571 102183 54569 102183 53420 102184 54569 102184 51118 102184 51119 102185 53602 102185 51151 102185 51119 102186 51151 102186 51120 102186 51120 102187 51151 102187 51121 102187 51120 102188 51121 102188 53276 102188 53276 102189 51121 102189 51122 102189 53276 102190 51122 102190 51123 102190 54540 102191 51124 102191 51122 102191 51122 102192 51124 102192 53274 102192 51122 102193 53274 102193 51123 102193 51127 102194 51125 102194 54540 102194 54540 102195 51125 102195 51126 102195 54540 102196 51126 102196 51124 102196 54540 102197 54558 102197 51127 102197 51127 102198 54558 102198 51128 102198 51127 102199 51128 102199 51129 102199 51129 102200 51128 102200 51130 102200 51130 102201 51128 102201 54560 102201 51130 102202 54560 102202 53269 102202 53269 102203 54560 102203 53271 102203 53271 102204 54560 102204 54561 102204 53271 102205 54561 102205 51131 102205 51132 102206 53267 102206 51133 102206 51133 102207 53267 102207 53268 102207 51133 102208 53268 102208 54561 102208 54561 102209 53268 102209 53302 102209 54561 102210 53302 102210 51131 102210 51132 102211 51133 102211 53266 102211 53266 102212 51133 102212 51134 102212 53266 102213 51134 102213 51135 102213 51135 102214 51134 102214 54531 102214 51135 102215 54531 102215 51136 102215 51136 102216 54531 102216 51137 102216 51137 102217 54531 102217 51139 102217 51137 102218 51139 102218 51138 102218 51138 102219 51139 102219 51140 102219 51140 102220 51139 102220 54528 102220 51140 102221 54528 102221 53264 102221 53264 102222 54528 102222 51141 102222 51141 102223 54528 102223 54527 102223 51141 102224 54527 102224 51142 102224 51142 102225 54527 102225 51143 102225 51142 102226 51143 102226 51144 102226 53236 102227 51152 102227 53595 102227 53595 102228 51152 102228 54522 102228 53595 102229 54522 102229 51145 102229 51145 102230 54522 102230 51146 102230 51146 102231 54522 102231 51147 102231 51147 102232 54522 102232 54526 102232 51147 102233 54526 102233 51148 102233 51148 102234 54526 102234 51149 102234 51148 102235 51149 102235 53607 102235 53602 102236 51150 102236 51151 102236 51151 102237 51150 102237 53604 102237 51151 102238 53604 102238 54524 102238 54524 102239 53604 102239 53605 102239 54524 102240 53605 102240 51149 102240 51149 102241 53605 102241 53606 102241 51149 102242 53606 102242 53607 102242 51152 102243 53236 102243 54521 102243 54521 102244 53236 102244 51153 102244 51160 102245 51154 102245 51159 102245 51157 102246 54521 102246 51153 102246 51153 102247 51155 102247 51157 102247 51157 102248 51155 102248 51156 102248 51157 102249 51156 102249 51159 102249 51159 102250 51156 102250 51158 102250 51159 102251 51158 102251 51160 102251 51160 102252 51158 102252 51018 102252 51160 102253 51018 102253 51161 102253 54300 102254 51154 102254 53764 102254 53764 102255 51154 102255 51160 102255 51160 102256 51161 102256 53764 102256 53764 102257 51161 102257 51162 102257 53764 102258 51162 102258 51163 102258 51165 102259 51167 102259 51164 102259 51164 102260 51167 102260 51174 102260 51164 102261 51174 102261 54302 102261 51168 102262 51253 102262 51165 102262 51253 102263 51166 102263 51165 102263 51165 102264 51166 102264 51255 102264 51165 102265 51255 102265 51167 102265 51165 102266 51169 102266 51168 102266 51168 102267 51169 102267 54300 102267 51168 102268 54300 102268 53764 102268 54095 102269 51202 102269 54096 102269 54096 102270 51202 102270 51170 102270 54096 102271 51170 102271 54097 102271 54097 102272 51170 102272 54184 102272 54097 102273 54184 102273 51171 102273 51171 102274 54184 102274 54295 102274 51171 102275 54295 102275 51172 102275 51172 102276 54295 102276 54296 102276 51172 102277 54296 102277 54094 102277 54094 102278 54296 102278 54307 102278 54094 102279 54307 102279 51173 102279 54307 102280 54306 102280 51173 102280 51173 102281 54306 102281 54305 102281 51173 102282 54305 102282 51174 102282 51174 102283 54305 102283 51175 102283 51174 102284 51175 102284 54302 102284 54252 102285 53772 102285 51176 102285 51176 102286 53772 102286 53771 102286 51176 102287 53771 102287 54250 102287 54250 102288 53771 102288 51177 102288 54250 102289 51177 102289 54249 102289 54249 102290 51177 102290 54431 102290 53780 102291 51178 102291 54254 102291 54254 102292 51178 102292 51179 102292 54254 102293 51179 102293 54252 102293 54252 102294 51179 102294 51180 102294 54252 102295 51180 102295 53772 102295 54254 102296 54255 102296 53780 102296 53780 102297 54255 102297 51181 102297 53780 102298 51181 102298 53781 102298 53781 102299 51181 102299 54257 102299 53781 102300 54257 102300 53783 102300 53783 102301 54257 102301 53784 102301 53784 102302 54257 102302 51183 102302 53784 102303 51183 102303 51182 102303 51182 102304 51183 102304 54258 102304 51182 102305 54258 102305 53819 102305 54258 102306 54260 102306 53819 102306 53819 102307 54260 102307 51184 102307 53819 102308 51184 102308 53837 102308 51184 102309 54190 102309 53837 102309 53837 102310 54190 102310 51185 102310 53837 102311 51185 102311 51186 102311 51186 102312 51185 102312 51188 102312 51185 102313 51187 102313 51188 102313 51188 102314 51187 102314 51189 102314 51188 102315 51189 102315 53806 102315 53806 102316 51189 102316 54186 102316 53806 102317 54186 102317 51190 102317 51190 102318 54186 102318 51191 102318 51190 102319 51191 102319 53773 102319 53773 102320 51191 102320 51193 102320 53773 102321 51193 102321 51192 102321 51192 102322 51193 102322 51194 102322 51192 102323 51194 102323 53827 102323 53827 102324 51194 102324 51195 102324 53827 102325 51195 102325 51196 102325 51196 102326 51195 102326 53778 102326 53778 102327 51195 102327 51197 102327 53778 102328 51197 102328 51198 102328 51198 102329 51197 102329 54290 102329 51198 102330 54290 102330 51201 102330 54290 102331 51199 102331 51201 102331 51201 102332 51199 102332 51200 102332 51201 102333 51200 102333 54095 102333 54095 102334 51200 102334 54293 102334 54095 102335 54293 102335 51202 102335 51205 102336 51204 102336 54225 102336 51205 102337 54225 102337 54428 102337 54428 102338 54225 102338 54240 102338 54428 102339 54240 102339 51203 102339 51203 102340 54240 102340 54242 102340 51203 102341 54242 102341 54430 102341 54430 102342 54242 102342 54249 102342 54430 102343 54249 102343 54431 102343 54375 102344 54223 102344 54474 102344 54474 102345 54223 102345 51204 102345 54474 102346 51204 102346 51205 102346 54388 102347 51207 102347 51206 102347 51206 102348 51207 102348 54223 102348 51206 102349 54223 102349 54375 102349 51207 102350 54388 102350 51208 102350 51208 102351 54388 102351 54426 102351 51208 102352 54426 102352 54213 102352 54213 102353 54426 102353 51209 102353 54213 102354 51209 102354 54203 102354 54203 102355 51209 102355 51210 102355 54203 102356 51210 102356 54200 102356 54200 102357 51210 102357 51233 102357 51232 102358 54200 102358 51233 102358 54196 102359 54197 102359 53918 102359 51222 102360 51221 102360 53940 102360 54040 102361 53923 102361 51211 102361 54040 102362 51211 102362 54012 102362 51211 102363 54272 102363 54012 102363 54012 102364 54272 102364 51212 102364 54012 102365 51212 102365 53979 102365 53979 102366 51212 102366 54275 102366 53979 102367 54275 102367 51215 102367 51216 102368 51213 102368 51215 102368 51215 102369 51213 102369 51214 102369 51215 102370 51214 102370 53979 102370 51215 102371 54273 102371 51216 102371 51216 102372 54273 102372 51217 102372 51216 102373 51217 102373 54041 102373 54041 102374 51217 102374 53915 102374 53915 102375 51217 102375 54271 102375 53915 102376 54271 102376 51218 102376 51218 102377 54271 102377 51219 102377 51218 102378 51219 102378 51220 102378 51220 102379 51219 102379 53940 102379 53940 102380 51219 102380 54269 102380 53940 102381 54269 102381 51222 102381 51221 102382 51222 102382 51223 102382 51223 102383 51222 102383 51224 102383 51223 102384 51224 102384 51225 102384 51224 102385 54267 102385 51225 102385 51225 102386 54267 102386 54266 102386 51225 102387 54266 102387 53939 102387 53939 102388 54266 102388 51230 102388 54196 102389 53918 102389 54194 102389 54194 102390 53918 102390 51226 102390 54194 102391 51226 102391 51227 102391 51227 102392 51226 102392 53917 102392 51227 102393 53917 102393 54192 102393 54192 102394 53917 102394 51228 102394 54192 102395 51228 102395 54264 102395 54264 102396 51228 102396 51229 102396 54264 102397 51229 102397 51230 102397 51230 102398 51229 102398 51231 102398 51230 102399 51231 102399 53939 102399 51232 102400 51233 102400 54197 102400 54197 102401 51233 102401 53919 102401 54197 102402 53919 102402 53918 102402 54060 102403 51247 102403 51234 102403 54060 102404 51234 102404 51235 102404 51235 102405 51234 102405 54283 102405 51235 102406 54283 102406 54063 102406 54063 102407 54283 102407 54282 102407 54063 102408 54282 102408 51236 102408 54282 102409 54280 102409 51236 102409 51236 102410 54280 102410 51238 102410 51236 102411 51238 102411 51237 102411 51237 102412 51238 102412 54278 102412 51237 102413 54278 102413 54066 102413 54066 102414 54278 102414 51239 102414 54066 102415 51239 102415 53923 102415 53923 102416 51239 102416 51240 102416 53923 102417 51240 102417 51211 102417 54288 102418 54287 102418 53769 102418 53769 102419 54287 102419 51480 102419 54287 102420 54286 102420 51480 102420 51480 102421 54286 102421 51241 102421 51480 102422 51241 102422 51243 102422 51241 102423 51242 102423 51243 102423 51243 102424 51242 102424 54285 102424 51243 102425 54285 102425 51244 102425 54285 102426 54284 102426 51244 102426 51244 102427 54284 102427 51245 102427 51244 102428 51245 102428 51246 102428 51246 102429 51245 102429 51234 102429 51246 102430 51234 102430 51247 102430 51079 102431 51080 102431 51248 102431 51249 102432 51079 102432 53769 102432 53769 102433 51079 102433 51248 102433 53769 102434 51248 102434 54288 102434 54288 102435 51248 102435 51250 102435 51258 102436 54098 102436 51254 102436 54100 102437 51174 102437 51167 102437 51256 102438 51251 102438 51166 102438 53764 102439 51252 102439 51168 102439 51168 102440 51252 102440 51256 102440 51168 102441 51256 102441 51253 102441 51253 102442 51256 102442 51166 102442 54098 102443 54100 102443 51254 102443 51254 102444 54100 102444 51167 102444 51254 102445 51167 102445 51251 102445 51251 102446 51167 102446 51255 102446 51251 102447 51255 102447 51166 102447 51252 102448 53767 102448 51256 102448 51256 102449 53767 102449 51257 102449 51256 102450 51257 102450 51251 102450 51251 102451 51257 102451 51276 102451 51251 102452 51276 102452 51254 102452 51254 102453 51276 102453 51263 102453 51254 102454 51263 102454 51258 102454 51258 102455 51263 102455 51259 102455 54090 102456 51260 102456 51262 102456 54484 102457 54486 102457 51270 102457 51296 102458 51274 102458 51605 102458 51605 102459 51274 102459 51273 102459 53767 102460 51268 102460 51257 102460 51257 102461 51268 102461 51267 102461 51257 102462 51267 102462 51276 102462 54091 102463 51259 102463 51261 102463 51261 102464 51259 102464 51263 102464 51260 102465 54091 102465 51262 102465 51262 102466 54091 102466 51261 102466 51262 102467 51261 102467 51277 102467 51277 102468 51261 102468 51263 102468 51277 102469 51263 102469 51276 102469 51279 102470 51278 102470 51264 102470 51264 102471 51278 102471 51266 102471 51264 102472 51266 102472 51265 102472 51265 102473 51266 102473 51267 102473 51265 102474 51267 102474 51271 102474 51271 102475 51267 102475 51268 102475 51281 102476 51279 102476 51269 102476 51269 102477 51279 102477 51264 102477 51269 102478 51264 102478 51270 102478 51270 102479 51264 102479 51265 102479 51270 102480 51265 102480 54484 102480 54484 102481 51265 102481 51271 102481 54487 102482 51273 102482 51272 102482 51272 102483 51273 102483 51274 102483 51272 102484 51274 102484 51275 102484 51275 102485 51274 102485 51296 102485 51275 102486 51296 102486 51298 102486 54486 102487 54487 102487 51270 102487 51270 102488 54487 102488 51272 102488 51270 102489 51272 102489 51269 102489 51269 102490 51272 102490 51275 102490 51269 102491 51275 102491 51281 102491 51281 102492 51275 102492 51298 102492 51281 102493 51298 102493 51299 102493 51276 102494 51267 102494 51277 102494 51277 102495 51267 102495 51266 102495 51277 102496 51266 102496 51262 102496 51262 102497 51266 102497 51278 102497 51262 102498 51278 102498 54090 102498 54090 102499 51278 102499 51279 102499 54090 102500 51279 102500 51280 102500 51280 102501 51279 102501 51281 102501 51280 102502 51281 102502 54087 102502 54087 102503 51281 102503 51299 102503 54087 102504 51299 102504 54085 102504 54083 102505 54085 102505 51299 102505 51287 102506 51282 102506 51294 102506 51290 102507 51295 102507 51283 102507 51283 102508 51295 102508 54344 102508 51607 102509 51285 102509 51284 102509 51284 102510 51285 102510 51306 102510 51286 102511 51607 102511 51293 102511 51293 102512 51607 102512 51284 102512 51293 102513 51284 102513 51294 102513 51294 102514 51284 102514 51306 102514 51294 102515 51306 102515 51287 102515 54081 102516 51288 102516 51289 102516 51289 102517 51288 102517 51300 102517 51289 102518 51300 102518 51297 102518 51283 102519 54081 102519 51290 102519 51290 102520 54081 102520 51289 102520 51290 102521 51289 102521 51291 102521 51291 102522 51289 102522 51297 102522 51291 102523 51297 102523 51292 102523 51606 102524 51286 102524 51292 102524 51292 102525 51286 102525 51293 102525 51292 102526 51293 102526 51291 102526 51291 102527 51293 102527 51294 102527 51291 102528 51294 102528 51290 102528 51290 102529 51294 102529 51282 102529 51290 102530 51282 102530 51295 102530 51605 102531 51606 102531 51296 102531 51296 102532 51606 102532 51292 102532 51296 102533 51292 102533 51298 102533 51298 102534 51292 102534 51297 102534 51298 102535 51297 102535 51299 102535 51299 102536 51297 102536 51300 102536 51299 102537 51300 102537 54083 102537 54083 102538 51300 102538 51288 102538 51307 102539 51309 102539 51301 102539 51301 102540 51302 102540 51304 102540 51304 102541 51302 102541 51303 102541 51311 102542 51309 102542 51613 102542 51613 102543 51309 102543 51307 102543 51613 102544 51307 102544 51612 102544 51308 102545 51304 102545 51305 102545 51305 102546 51304 102546 51303 102546 51305 102547 51303 102547 54346 102547 54346 102548 54344 102548 51295 102548 54346 102549 51295 102549 51305 102549 51305 102550 51295 102550 51282 102550 51305 102551 51282 102551 51308 102551 51308 102552 51282 102552 51287 102552 51308 102553 51287 102553 51306 102553 51301 102554 51304 102554 51307 102554 51307 102555 51304 102555 51308 102555 51307 102556 51308 102556 51612 102556 51612 102557 51308 102557 51306 102557 51612 102558 51306 102558 51285 102558 51309 102559 51311 102559 51310 102559 51310 102560 51311 102560 51630 102560 51310 102561 51630 102561 51312 102561 51312 102562 51630 102562 51628 102562 51312 102563 51628 102563 51313 102563 51313 102564 51628 102564 51314 102564 51313 102565 51314 102565 51325 102565 51325 102566 51314 102566 51316 102566 51325 102567 51316 102567 51315 102567 51315 102568 51316 102568 51317 102568 51315 102569 51317 102569 51319 102569 51319 102570 51317 102570 51318 102570 51319 102571 51318 102571 51328 102571 51328 102572 51318 102572 51320 102572 51328 102573 51320 102573 51330 102573 51330 102574 51320 102574 51321 102574 51330 102575 51321 102575 51322 102575 51322 102576 51321 102576 51622 102576 51322 102577 51622 102577 51323 102577 51323 102578 51622 102578 51358 102578 51301 102579 51309 102579 51324 102579 51324 102580 51309 102580 51310 102580 51324 102581 51310 102581 51334 102581 51334 102582 51310 102582 51312 102582 51334 102583 51312 102583 51335 102583 51335 102584 51312 102584 51313 102584 51335 102585 51313 102585 51336 102585 51336 102586 51313 102586 51325 102586 51336 102587 51325 102587 51338 102587 51338 102588 51325 102588 51315 102588 51338 102589 51315 102589 51326 102589 51326 102590 51315 102590 51319 102590 51326 102591 51319 102591 51327 102591 51327 102592 51319 102592 51328 102592 51327 102593 51328 102593 51329 102593 51329 102594 51328 102594 51330 102594 51329 102595 51330 102595 51331 102595 51331 102596 51330 102596 51322 102596 51331 102597 51322 102597 51357 102597 51357 102598 51322 102598 51323 102598 51302 102599 51301 102599 51332 102599 51332 102600 51301 102600 51324 102600 51332 102601 51324 102601 51333 102601 51333 102602 51324 102602 51334 102602 51333 102603 51334 102603 54333 102603 54333 102604 51334 102604 51335 102604 54333 102605 51335 102605 54335 102605 54335 102606 51335 102606 51336 102606 54335 102607 51336 102607 51337 102607 51337 102608 51336 102608 51338 102608 51337 102609 51338 102609 54324 102609 54324 102610 51338 102610 51326 102610 54324 102611 51326 102611 51339 102611 51339 102612 51326 102612 51327 102612 51339 102613 51327 102613 51340 102613 51340 102614 51327 102614 51329 102614 51340 102615 51329 102615 51341 102615 51341 102616 51329 102616 51331 102616 51341 102617 51331 102617 54319 102617 54319 102618 51331 102618 51357 102618 51370 102619 51342 102619 51348 102619 51372 102620 51374 102620 51343 102620 51370 102621 51348 102621 51367 102621 51364 102622 51365 102622 51344 102622 51342 102623 51372 102623 51348 102623 51348 102624 51372 102624 51343 102624 51348 102625 51343 102625 51349 102625 51349 102626 51343 102626 54373 102626 51349 102627 54373 102627 51345 102627 51345 102628 54373 102628 51346 102628 51345 102629 51346 102629 51347 102629 51347 102630 51346 102630 54365 102630 51347 102631 54365 102631 51352 102631 51352 102632 54365 102632 54371 102632 51352 102633 54371 102633 51355 102633 51355 102634 54371 102634 54370 102634 51355 102635 54370 102635 51356 102635 51356 102636 54370 102636 54369 102636 51356 102637 54369 102637 51357 102637 51357 102638 54369 102638 54319 102638 51365 102639 51367 102639 51344 102639 51344 102640 51367 102640 51348 102640 51344 102641 51348 102641 51363 102641 51363 102642 51348 102642 51349 102642 51363 102643 51349 102643 51350 102643 51350 102644 51349 102644 51345 102644 51350 102645 51345 102645 51351 102645 51351 102646 51345 102646 51347 102646 51351 102647 51347 102647 51359 102647 51359 102648 51347 102648 51352 102648 51359 102649 51352 102649 51353 102649 51353 102650 51352 102650 51355 102650 51353 102651 51355 102651 51354 102651 51354 102652 51355 102652 51356 102652 51354 102653 51356 102653 51323 102653 51323 102654 51356 102654 51357 102654 51323 102655 51358 102655 51354 102655 51354 102656 51358 102656 51617 102656 51354 102657 51617 102657 51353 102657 51353 102658 51617 102658 51360 102658 51353 102659 51360 102659 51359 102659 51359 102660 51360 102660 51615 102660 51359 102661 51615 102661 51351 102661 51351 102662 51615 102662 51361 102662 51351 102663 51361 102663 51350 102663 51350 102664 51361 102664 51362 102664 51350 102665 51362 102665 51363 102665 51363 102666 51362 102666 51618 102666 51363 102667 51618 102667 51344 102667 51344 102668 51618 102668 51619 102668 51344 102669 51619 102669 51364 102669 51364 102670 51634 102670 51365 102670 51365 102671 51634 102671 51366 102671 51365 102672 51366 102672 51367 102672 51367 102673 51366 102673 51368 102673 51367 102674 51368 102674 51370 102674 51370 102675 51368 102675 51369 102675 51370 102676 51369 102676 51342 102676 51342 102677 51369 102677 51371 102677 51342 102678 51371 102678 51372 102678 51372 102679 51371 102679 51373 102679 51372 102680 51373 102680 51374 102680 51374 102681 51373 102681 54368 102681 51366 102682 51634 102682 51633 102682 51369 102683 51368 102683 51392 102683 51375 102684 51424 102684 51390 102684 51390 102685 51424 102685 54323 102685 51390 102686 54323 102686 51376 102686 51376 102687 54323 102687 51377 102687 51376 102688 51377 102688 51388 102688 51388 102689 51377 102689 51378 102689 51388 102690 51378 102690 51386 102690 51386 102691 51378 102691 54362 102691 51386 102692 54362 102692 51379 102692 51379 102693 54362 102693 51380 102693 51379 102694 51380 102694 51381 102694 51381 102695 51380 102695 51382 102695 51381 102696 51382 102696 51384 102696 51384 102697 51382 102697 51383 102697 51383 102698 54368 102698 51384 102698 51384 102699 54368 102699 51373 102699 51384 102700 51373 102700 51371 102700 51371 102701 51369 102701 51384 102701 51384 102702 51369 102702 51392 102702 51384 102703 51392 102703 51381 102703 51381 102704 51392 102704 51385 102704 51381 102705 51385 102705 51379 102705 51379 102706 51385 102706 51387 102706 51379 102707 51387 102707 51386 102707 51386 102708 51387 102708 51394 102708 51386 102709 51394 102709 51388 102709 51388 102710 51394 102710 51389 102710 51388 102711 51389 102711 51376 102711 51376 102712 51389 102712 51395 102712 51376 102713 51395 102713 51390 102713 51390 102714 51395 102714 51391 102714 51390 102715 51391 102715 51375 102715 51375 102716 51391 102716 51416 102716 51368 102717 51366 102717 51392 102717 51392 102718 51366 102718 51633 102718 51392 102719 51633 102719 51385 102719 51385 102720 51633 102720 51393 102720 51385 102721 51393 102721 51387 102721 51387 102722 51393 102722 51631 102722 51387 102723 51631 102723 51394 102723 51394 102724 51631 102724 51635 102724 51394 102725 51635 102725 51389 102725 51389 102726 51635 102726 51396 102726 51389 102727 51396 102727 51395 102727 51395 102728 51396 102728 51636 102728 51395 102729 51636 102729 51391 102729 51391 102730 51636 102730 51397 102730 51391 102731 51397 102731 51416 102731 51416 102732 51397 102732 51637 102732 51435 102733 54313 102733 54311 102733 51433 102734 51417 102734 51404 102734 51427 102735 51431 102735 51398 102735 51428 102736 51427 102736 51647 102736 51647 102737 51427 102737 51398 102737 51647 102738 51398 102738 51646 102738 51646 102739 51398 102739 51399 102739 51646 102740 51399 102740 51645 102740 51645 102741 51399 102741 51400 102741 51645 102742 51400 102742 51644 102742 51644 102743 51400 102743 51407 102743 51644 102744 51407 102744 51401 102744 51401 102745 51407 102745 51409 102745 51401 102746 51409 102746 51402 102746 51402 102747 51409 102747 51410 102747 51402 102748 51410 102748 51641 102748 51641 102749 51410 102749 51412 102749 51641 102750 51412 102750 51640 102750 51640 102751 51412 102751 51413 102751 51640 102752 51413 102752 51639 102752 51639 102753 51413 102753 51403 102753 51639 102754 51403 102754 51637 102754 51637 102755 51403 102755 51416 102755 51431 102756 51433 102756 51398 102756 51398 102757 51433 102757 51404 102757 51398 102758 51404 102758 51399 102758 51399 102759 51404 102759 51405 102759 51399 102760 51405 102760 51400 102760 51400 102761 51405 102761 51406 102761 51400 102762 51406 102762 51407 102762 51407 102763 51406 102763 51408 102763 51407 102764 51408 102764 51409 102764 51409 102765 51408 102765 51411 102765 51409 102766 51411 102766 51410 102766 51410 102767 51411 102767 51419 102767 51410 102768 51419 102768 51412 102768 51412 102769 51419 102769 51414 102769 51412 102770 51414 102770 51413 102770 51413 102771 51414 102771 51415 102771 51413 102772 51415 102772 51403 102772 51403 102773 51415 102773 51422 102773 51403 102774 51422 102774 51416 102774 51416 102775 51422 102775 51375 102775 51417 102776 51435 102776 51404 102776 51404 102777 51435 102777 54311 102777 51404 102778 54311 102778 51405 102778 51405 102779 54311 102779 54310 102779 51405 102780 54310 102780 51406 102780 51406 102781 54310 102781 51418 102781 51406 102782 51418 102782 51408 102782 51408 102783 51418 102783 54321 102783 51408 102784 54321 102784 51411 102784 51411 102785 54321 102785 54322 102785 51411 102786 54322 102786 51419 102786 51419 102787 54322 102787 51420 102787 51419 102788 51420 102788 51414 102788 51414 102789 51420 102789 54331 102789 51414 102790 54331 102790 51415 102790 51415 102791 54331 102791 51421 102791 51415 102792 51421 102792 51422 102792 51422 102793 51421 102793 51423 102793 51422 102794 51423 102794 51375 102794 51375 102795 51423 102795 51424 102795 51602 102796 51425 102796 51426 102796 51427 102797 51428 102797 51429 102797 51429 102798 51428 102798 51430 102798 51429 102799 51430 102799 51602 102799 51427 102800 51429 102800 51431 102800 51431 102801 51429 102801 51432 102801 51431 102802 51432 102802 51433 102802 51433 102803 51432 102803 51417 102803 51417 102804 51432 102804 51434 102804 51417 102805 51434 102805 51435 102805 51435 102806 51434 102806 54315 102806 51435 102807 54315 102807 54313 102807 51602 102808 51426 102808 51429 102808 51429 102809 51426 102809 51436 102809 51429 102810 51436 102810 51432 102810 51432 102811 51436 102811 51450 102811 51432 102812 51450 102812 51434 102812 51434 102813 51450 102813 51451 102813 51434 102814 51451 102814 54315 102814 54074 102815 54077 102815 51445 102815 51443 102816 51444 102816 54070 102816 54070 102817 51444 102817 51456 102817 54070 102818 51456 102818 54068 102818 51438 102819 53757 102819 51437 102819 51437 102820 53757 102820 51441 102820 51604 102821 51438 102821 51439 102821 51439 102822 51438 102822 51437 102822 51439 102823 51437 102823 51440 102823 51440 102824 51437 102824 51441 102824 51440 102825 51441 102825 51457 102825 54077 102826 54076 102826 51445 102826 51445 102827 54076 102827 51442 102827 51445 102828 51442 102828 51449 102828 51443 102829 54074 102829 51444 102829 51444 102830 54074 102830 51445 102830 51444 102831 51445 102831 51448 102831 51448 102832 51445 102832 51449 102832 51448 102833 51449 102833 51446 102833 51447 102834 51604 102834 51446 102834 51446 102835 51604 102835 51439 102835 51446 102836 51439 102836 51448 102836 51448 102837 51439 102837 51440 102837 51448 102838 51440 102838 51444 102838 51444 102839 51440 102839 51457 102839 51444 102840 51457 102840 51456 102840 51425 102841 51447 102841 51426 102841 51426 102842 51447 102842 51446 102842 51426 102843 51446 102843 51436 102843 51436 102844 51446 102844 51449 102844 51436 102845 51449 102845 51450 102845 51450 102846 51449 102846 51442 102846 51450 102847 51442 102847 51451 102847 51451 102848 51442 102848 54076 102848 51469 102849 54055 102849 54067 102849 51452 102850 51453 102850 51476 102850 51452 102851 51476 102851 53762 102851 51460 102852 53762 102852 51466 102852 51459 102853 53761 102853 51460 102853 51458 102854 53758 102854 51454 102854 51454 102855 53758 102855 53761 102855 51464 102856 51456 102856 51455 102856 51455 102857 51456 102857 51457 102857 51455 102858 51457 102858 51454 102858 51454 102859 51457 102859 51441 102859 51454 102860 51441 102860 51458 102860 51458 102861 51441 102861 53757 102861 53761 102862 51459 102862 51454 102862 51454 102863 51459 102863 51462 102863 51454 102864 51462 102864 51455 102864 51455 102865 51462 102865 51463 102865 51455 102866 51463 102866 51464 102866 51460 102867 51467 102867 51459 102867 51459 102868 51467 102868 51461 102868 51459 102869 51461 102869 51462 102869 51462 102870 51461 102870 51469 102870 51462 102871 51469 102871 51463 102871 51463 102872 51469 102872 54067 102872 51463 102873 54067 102873 51464 102873 51464 102874 54067 102874 54068 102874 51464 102875 54068 102875 51456 102875 51468 102876 51474 102876 51465 102876 51460 102877 51466 102877 51467 102877 51467 102878 51466 102878 51472 102878 51467 102879 51472 102879 51461 102879 51461 102880 51472 102880 51468 102880 51461 102881 51468 102881 51469 102881 51469 102882 51468 102882 51465 102882 51469 102883 51465 102883 54055 102883 51473 102884 54057 102884 51470 102884 53762 102885 51476 102885 51466 102885 51466 102886 51476 102886 51471 102886 51466 102887 51471 102887 51472 102887 51472 102888 51471 102888 51473 102888 51472 102889 51473 102889 51468 102889 51468 102890 51473 102890 51470 102890 51468 102891 51470 102891 51474 102891 54058 102892 54057 102892 51475 102892 51475 102893 54057 102893 51473 102893 51475 102894 51473 102894 51482 102894 51482 102895 51473 102895 51471 102895 51482 102896 51471 102896 51485 102896 51485 102897 51471 102897 51476 102897 51485 102898 51476 102898 51477 102898 51477 102899 51476 102899 51453 102899 54059 102900 51478 102900 51479 102900 51247 102901 54059 102901 51246 102901 51246 102902 54059 102902 51479 102902 51246 102903 51479 102903 51244 102903 51244 102904 51479 102904 51483 102904 51244 102905 51483 102905 51243 102905 51243 102906 51483 102906 51484 102906 51243 102907 51484 102907 51480 102907 51480 102908 51484 102908 51481 102908 51480 102909 51481 102909 53769 102909 51478 102910 54058 102910 51479 102910 51479 102911 54058 102911 51475 102911 51479 102912 51475 102912 51483 102912 51483 102913 51475 102913 51482 102913 51483 102914 51482 102914 51484 102914 51484 102915 51482 102915 51485 102915 51484 102916 51485 102916 51481 102916 51481 102917 51485 102917 51477 102917 54777 102918 54532 102918 51490 102918 51490 102919 54532 102919 51486 102919 51490 102920 51486 102920 51492 102920 51492 102921 51486 102921 54541 102921 51492 102922 54541 102922 51493 102922 51493 102923 54541 102923 51487 102923 51493 102924 51487 102924 51488 102924 51488 102925 51487 102925 51489 102925 51488 102926 51489 102926 51495 102926 51495 102927 51489 102927 54543 102927 51495 102928 54543 102928 54766 102928 54766 102929 54543 102929 54536 102929 54772 102930 54777 102930 51498 102930 51498 102931 54777 102931 51490 102931 51498 102932 51490 102932 51497 102932 51497 102933 51490 102933 51492 102933 51497 102934 51492 102934 51491 102934 51491 102935 51492 102935 51493 102935 51491 102936 51493 102936 51494 102936 51494 102937 51493 102937 51488 102937 51494 102938 51488 102938 51500 102938 51500 102939 51488 102939 51495 102939 51500 102940 51495 102940 51499 102940 51499 102941 51495 102941 54766 102941 51496 102942 51497 102942 51491 102942 51498 102943 51497 102943 51496 102943 54772 102944 51498 102944 51496 102944 51496 102945 51500 102945 51499 102945 51494 102946 51500 102946 51496 102946 51491 102947 51494 102947 51496 102947 54756 102948 51501 102948 51502 102948 51502 102949 51501 102949 51503 102949 51502 102950 51503 102950 51510 102950 51510 102951 51503 102951 51504 102951 51510 102952 51504 102952 51505 102952 51505 102953 51504 102953 54530 102953 51505 102954 54530 102954 51506 102954 51506 102955 54530 102955 51507 102955 51506 102956 51507 102956 51508 102956 51508 102957 51507 102957 54520 102957 51508 102958 54520 102958 51513 102958 51513 102959 54520 102959 54551 102959 54750 102960 54756 102960 51515 102960 51515 102961 54756 102961 51502 102961 51515 102962 51502 102962 51509 102962 51509 102963 51502 102963 51510 102963 51509 102964 51510 102964 51514 102964 51514 102965 51510 102965 51505 102965 51514 102966 51505 102966 51516 102966 51516 102967 51505 102967 51506 102967 51516 102968 51506 102968 51511 102968 51511 102969 51506 102969 51508 102969 51511 102970 51508 102970 51512 102970 51512 102971 51508 102971 51513 102971 54751 102972 51509 102972 51514 102972 51515 102973 51509 102973 54751 102973 54750 102974 51515 102974 54751 102974 54751 102975 51511 102975 51512 102975 51516 102976 51511 102976 54751 102976 51514 102977 51516 102977 54751 102977 51517 102978 50647 102978 50646 102978 51517 102979 50646 102979 51518 102979 51518 102980 50646 102980 51519 102980 51518 102981 51519 102981 51520 102981 51520 102982 50644 102982 51518 102982 51518 102983 50644 102983 50643 102983 51518 102984 50643 102984 51521 102984 51521 102985 50643 102985 50622 102985 51521 102986 50622 102986 51003 102986 51522 102987 51523 102987 51922 102987 51922 102988 51523 102988 51000 102988 53208 102989 51524 102989 50996 102989 50996 102990 51524 102990 54743 102990 51539 102991 51525 102991 51526 102991 51539 102992 51526 102992 51527 102992 51527 102993 51526 102993 51528 102993 51527 102994 51528 102994 51529 102994 51528 102995 50806 102995 51529 102995 51529 102996 50806 102996 50808 102996 51529 102997 50808 102997 51530 102997 51530 102998 50808 102998 50810 102998 51530 102999 50810 102999 50793 102999 51001 103000 51003 103000 50622 103000 50621 103001 51926 103001 50624 103001 50624 103002 51926 103002 51001 103002 50624 103003 51001 103003 51531 103003 51531 103004 51001 103004 50622 103004 54738 103005 54791 103005 51926 103005 51926 103006 54791 103006 51532 103006 51926 103007 51532 103007 51001 103007 51533 103008 51535 103008 51537 103008 54513 103009 51534 103009 54796 103009 54796 103010 51534 103010 51535 103010 54796 103011 51535 103011 54797 103011 54797 103012 51535 103012 51533 103012 54793 103013 54794 103013 51537 103013 51537 103014 54794 103014 54795 103014 51537 103015 54795 103015 51533 103015 51536 103016 51002 103016 51537 103016 51537 103017 51002 103017 54790 103017 51537 103018 54790 103018 54793 103018 51540 103019 51525 103019 51539 103019 51542 103020 51978 103020 51540 103020 50997 103021 51538 103021 50984 103021 50984 103022 51538 103022 51980 103022 50984 103023 51980 103023 51982 103023 51544 103024 50988 103024 51982 103024 51982 103025 50988 103025 50987 103025 51982 103026 50987 103026 50984 103026 51539 103027 50992 103027 51540 103027 51540 103028 50992 103028 51541 103028 51540 103029 51541 103029 51542 103029 51542 103030 51541 103030 51543 103030 51542 103031 51543 103031 51544 103031 51544 103032 51543 103032 50990 103032 51544 103033 50990 103033 50988 103033 51546 103034 51548 103034 50999 103034 50999 103035 51548 103035 50994 103035 50985 103036 51545 103036 50998 103036 50998 103037 51545 103037 50983 103037 50998 103038 50983 103038 51546 103038 51546 103039 50983 103039 51547 103039 51546 103040 51547 103040 51548 103040 50991 103041 50993 103041 50989 103041 50989 103042 50993 103042 51545 103042 50989 103043 51545 103043 50986 103043 50986 103044 51545 103044 50985 103044 54736 103045 51549 103045 49960 103045 49960 103046 51549 103046 51550 103046 49960 103047 51550 103047 49961 103047 49961 103048 51550 103048 51551 103048 49961 103049 51551 103049 51552 103049 51552 103050 51551 103050 51553 103050 51552 103051 51553 103051 49963 103051 49963 103052 51553 103052 51589 103052 49963 103053 51589 103053 51554 103053 51554 103054 51589 103054 51591 103054 51554 103055 51591 103055 49964 103055 49964 103056 51591 103056 51593 103056 49949 103057 51568 103057 51555 103057 51555 103058 51568 103058 51557 103058 51555 103059 51557 103059 51556 103059 51556 103060 51557 103060 51569 103060 51556 103061 51569 103061 49951 103061 49951 103062 51569 103062 51558 103062 49951 103063 51558 103063 49952 103063 49952 103064 51558 103064 51571 103064 49952 103065 51571 103065 51559 103065 51559 103066 51571 103066 51560 103066 51559 103067 51560 103067 49953 103067 49953 103068 51560 103068 54729 103068 54730 103069 51561 103069 51562 103069 51562 103070 51561 103070 51563 103070 51562 103071 51563 103071 51564 103071 51564 103072 51563 103072 54725 103072 51564 103073 54725 103073 51566 103073 51566 103074 54725 103074 51565 103074 51566 103075 51565 103075 51567 103075 51567 103076 51565 103076 54727 103076 51567 103077 54727 103077 51568 103077 51568 103078 54727 103078 54728 103078 51568 103079 54728 103079 51557 103079 51557 103080 54728 103080 51574 103080 51557 103081 51574 103081 51569 103081 51569 103082 51574 103082 51576 103082 51569 103083 51576 103083 51558 103083 51558 103084 51576 103084 51570 103084 51558 103085 51570 103085 51571 103085 51571 103086 51570 103086 51579 103086 51571 103087 51579 103087 51560 103087 51560 103088 51579 103088 51572 103088 51560 103089 51572 103089 54729 103089 54729 103090 51572 103090 51573 103090 54729 103091 51573 103091 54730 103091 54730 103092 51573 103092 51561 103092 54728 103093 51009 103093 51574 103093 51574 103094 51009 103094 51575 103094 51574 103095 51575 103095 51576 103095 51576 103096 51575 103096 51577 103096 51576 103097 51577 103097 51570 103097 51570 103098 51577 103098 51578 103098 51570 103099 51578 103099 51579 103099 51579 103100 51578 103100 51011 103100 51579 103101 51011 103101 51572 103101 51572 103102 51011 103102 51580 103102 51572 103103 51580 103103 51573 103103 51573 103104 51580 103104 51012 103104 54717 103105 51581 103105 51596 103105 51596 103106 51581 103106 54719 103106 51596 103107 54719 103107 51582 103107 51582 103108 54719 103108 54720 103108 51582 103109 54720 103109 51583 103109 51583 103110 54720 103110 51584 103110 51583 103111 51584 103111 54737 103111 54737 103112 51584 103112 51585 103112 54737 103113 51585 103113 51549 103113 51549 103114 51585 103114 51597 103114 51549 103115 51597 103115 51550 103115 51550 103116 51597 103116 51586 103116 51550 103117 51586 103117 51551 103117 51551 103118 51586 103118 51587 103118 51551 103119 51587 103119 51553 103119 51553 103120 51587 103120 51588 103120 51553 103121 51588 103121 51589 103121 51589 103122 51588 103122 51590 103122 51589 103123 51590 103123 51591 103123 51591 103124 51590 103124 51592 103124 51591 103125 51592 103125 51593 103125 51593 103126 51592 103126 51594 103126 51593 103127 51594 103127 51595 103127 51595 103128 51594 103128 54717 103128 51595 103129 54717 103129 51596 103129 51597 103130 51598 103130 51586 103130 51586 103131 51598 103131 51599 103131 51586 103132 51599 103132 51587 103132 51587 103133 51599 103133 51600 103133 51587 103134 51600 103134 51588 103134 51588 103135 51600 103135 51005 103135 51588 103136 51005 103136 51590 103136 51590 103137 51005 103137 51007 103137 51590 103138 51007 103138 51592 103138 51592 103139 51007 103139 51008 103139 51592 103140 51008 103140 51594 103140 51594 103141 51008 103141 54718 103141 51428 103142 51601 103142 51430 103142 51430 103143 51601 103143 51062 103143 51430 103144 51062 103144 51602 103144 51602 103145 51062 103145 51425 103145 51425 103146 51062 103146 51068 103146 51425 103147 51068 103147 51447 103147 51068 103148 51067 103148 51447 103148 51447 103149 51067 103149 51066 103149 51447 103150 51066 103150 51604 103150 51063 103151 53757 103151 51064 103151 51064 103152 53757 103152 51438 103152 51064 103153 51438 103153 51603 103153 51603 103154 51438 103154 51604 103154 51603 103155 51604 103155 51065 103155 51065 103156 51604 103156 51066 103156 51286 103157 51606 103157 51032 103157 51605 103158 51035 103158 51606 103158 51606 103159 51035 103159 51033 103159 51606 103160 51033 103160 51032 103160 51032 103161 51031 103161 51286 103161 51286 103162 51031 103162 51030 103162 51286 103163 51030 103163 51607 103163 51030 103164 51608 103164 51607 103164 51607 103165 51608 103165 51609 103165 51607 103166 51609 103166 51285 103166 51285 103167 51609 103167 51610 103167 51285 103168 51610 103168 51612 103168 51612 103169 51610 103169 51611 103169 51612 103170 51611 103170 51613 103170 51613 103171 51611 103171 51629 103171 51613 103172 51629 103172 51311 103172 51362 103173 51361 103173 51614 103173 51614 103174 51361 103174 51615 103174 51614 103175 51615 103175 51616 103175 51616 103176 51615 103176 51360 103176 51616 103177 51360 103177 51042 103177 51042 103178 51360 103178 51617 103178 51042 103179 51617 103179 51358 103179 51362 103180 51614 103180 51618 103180 51618 103181 51614 103181 51620 103181 51618 103182 51620 103182 51619 103182 51619 103183 51620 103183 51621 103183 51619 103184 51621 103184 51364 103184 51042 103185 51358 103185 51041 103185 51041 103186 51358 103186 51622 103186 51041 103187 51622 103187 51623 103187 51623 103188 51622 103188 51321 103188 51623 103189 51321 103189 51624 103189 51624 103190 51321 103190 51320 103190 51624 103191 51320 103191 51625 103191 51625 103192 51320 103192 51318 103192 51625 103193 51318 103193 51626 103193 51626 103194 51318 103194 51317 103194 51626 103195 51317 103195 51038 103195 51038 103196 51317 103196 51316 103196 51038 103197 51316 103197 51040 103197 51040 103198 51316 103198 51314 103198 51040 103199 51314 103199 51039 103199 51039 103200 51314 103200 51628 103200 51039 103201 51628 103201 51627 103201 51627 103202 51628 103202 51630 103202 51627 103203 51630 103203 51629 103203 51629 103204 51630 103204 51311 103204 51631 103205 51393 103205 51051 103205 51051 103206 51393 103206 51632 103206 51632 103207 51393 103207 51633 103207 51632 103208 51633 103208 51634 103208 51631 103209 51051 103209 51635 103209 51635 103210 51051 103210 51049 103210 51635 103211 51049 103211 51396 103211 51396 103212 51049 103212 51638 103212 51396 103213 51638 103213 51636 103213 51047 103214 51637 103214 51638 103214 51638 103215 51637 103215 51397 103215 51638 103216 51397 103216 51636 103216 51637 103217 51047 103217 51639 103217 51639 103218 51047 103218 51054 103218 51639 103219 51054 103219 51640 103219 51640 103220 51054 103220 51642 103220 51640 103221 51642 103221 51641 103221 51641 103222 51642 103222 51643 103222 51641 103223 51643 103223 51402 103223 51402 103224 51643 103224 51061 103224 51402 103225 51061 103225 51401 103225 51401 103226 51061 103226 51060 103226 51401 103227 51060 103227 51644 103227 51644 103228 51060 103228 51056 103228 51644 103229 51056 103229 51645 103229 51645 103230 51056 103230 51059 103230 51645 103231 51059 103231 51646 103231 51646 103232 51059 103232 51648 103232 51646 103233 51648 103233 51647 103233 51647 103234 51648 103234 51649 103234 51647 103235 51649 103235 51428 103235 51428 103236 51649 103236 51601 103236 53008 103237 51818 103237 51650 103237 53008 103238 51650 103238 53014 103238 53014 103239 51650 103239 51651 103239 53014 103240 51651 103240 51842 103240 51656 103241 51652 103241 51653 103241 51656 103242 51653 103242 53008 103242 53008 103243 51653 103243 51654 103243 53008 103244 51654 103244 51818 103244 51825 103245 51823 103245 51655 103245 51655 103246 51823 103246 51656 103246 51656 103247 51823 103247 51822 103247 51656 103248 51822 103248 51652 103248 51803 103249 51816 103249 51655 103249 51655 103250 51816 103250 51817 103250 51655 103251 51817 103251 51825 103251 51660 103252 51657 103252 51658 103252 51660 103253 51658 103253 51655 103253 51655 103254 51658 103254 51804 103254 51655 103255 51804 103255 51803 103255 51659 103256 51813 103256 51660 103256 51660 103257 51813 103257 51661 103257 51661 103258 51815 103258 51660 103258 51660 103259 51815 103259 51662 103259 51660 103260 51662 103260 51657 103260 51807 103261 51663 103261 51664 103261 51664 103262 51663 103262 51808 103262 51664 103263 51808 103263 51659 103263 51659 103264 51808 103264 51810 103264 51659 103265 51810 103265 51813 103265 51807 103266 51664 103266 51805 103266 51805 103267 51664 103267 54709 103267 51805 103268 54709 103268 51834 103268 51667 103269 51669 103269 51770 103269 51667 103270 51770 103270 53009 103270 53009 103271 51770 103271 51769 103271 53009 103272 51769 103272 51665 103272 51666 103273 51673 103273 51763 103273 51666 103274 51763 103274 51667 103274 51667 103275 51763 103275 51668 103275 51667 103276 51668 103276 51669 103276 51670 103277 51672 103277 51671 103277 51671 103278 51672 103278 51666 103278 51666 103279 51672 103279 51765 103279 51666 103280 51765 103280 51673 103280 51759 103281 51674 103281 51671 103281 51671 103282 51674 103282 51675 103282 51671 103283 51675 103283 51670 103283 53023 103284 51676 103284 51760 103284 53023 103285 51760 103285 51671 103285 51671 103286 51760 103286 51677 103286 51671 103287 51677 103287 51759 103287 51683 103288 51678 103288 53023 103288 53023 103289 51678 103289 51778 103289 51778 103290 51779 103290 53023 103290 53023 103291 51779 103291 51679 103291 53023 103292 51679 103292 51676 103292 51680 103293 51774 103293 51681 103293 51681 103294 51774 103294 51682 103294 51681 103295 51682 103295 51683 103295 51683 103296 51682 103296 51775 103296 51683 103297 51775 103297 51678 103297 51680 103298 51681 103298 51772 103298 51772 103299 51681 103299 53012 103299 51772 103300 53012 103300 54693 103300 51720 103301 51684 103301 51685 103301 51687 103302 51686 103302 51708 103302 51687 103303 51708 103303 53031 103303 53031 103304 51708 103304 51711 103304 53031 103305 51711 103305 51727 103305 53030 103306 51688 103306 51687 103306 51687 103307 51688 103307 51689 103307 51687 103308 51689 103308 51686 103308 51702 103309 51703 103309 51690 103309 51690 103310 51703 103310 51704 103310 51690 103311 51704 103311 53030 103311 53030 103312 51704 103312 51706 103312 53030 103313 51706 103313 51688 103313 51702 103314 51690 103314 51701 103314 51701 103315 51690 103315 51691 103315 51701 103316 51691 103316 51699 103316 51685 103317 51684 103317 51691 103317 51691 103318 51684 103318 51722 103318 51691 103319 51722 103319 51723 103319 51723 103320 51712 103320 51691 103320 51691 103321 51712 103321 51700 103321 51691 103322 51700 103322 51699 103322 51720 103323 51685 103323 51692 103323 51692 103324 51685 103324 53021 103324 51692 103325 53021 103325 51716 103325 51693 103326 51694 103326 51695 103326 51695 103327 51694 103327 51714 103327 51695 103328 51714 103328 53021 103328 53021 103329 51714 103329 51715 103329 53021 103330 51715 103330 51716 103330 51693 103331 51695 103331 51696 103331 51696 103332 51695 103332 51697 103332 51696 103333 51697 103333 51754 103333 51698 103334 51701 103334 50106 103334 50106 103335 51701 103335 51699 103335 50106 103336 51699 103336 51700 103336 51698 103337 50068 103337 51701 103337 51701 103338 50068 103338 51702 103338 50068 103339 50067 103339 51702 103339 51702 103340 50067 103340 50070 103340 51702 103341 50070 103341 51703 103341 51703 103342 50070 103342 51705 103342 51703 103343 51705 103343 51704 103343 51704 103344 51705 103344 51707 103344 51704 103345 51707 103345 51706 103345 51706 103346 51707 103346 50081 103346 50081 103347 50080 103347 51706 103347 51706 103348 50080 103348 51709 103348 51706 103349 51709 103349 51688 103349 51711 103350 51708 103350 50079 103350 50079 103351 51708 103351 51686 103351 50079 103352 51686 103352 51709 103352 51709 103353 51686 103353 51689 103353 51709 103354 51689 103354 51688 103354 50079 103355 51710 103355 51711 103355 51711 103356 51710 103356 51728 103356 51711 103357 51728 103357 51727 103357 51723 103358 51719 103358 51712 103358 51712 103359 51719 103359 50106 103359 51712 103360 50106 103360 51700 103360 51714 103361 51694 103361 50115 103361 50115 103362 51694 103362 51693 103362 50115 103363 51693 103363 51713 103363 51713 103364 51693 103364 51696 103364 51713 103365 51696 103365 50124 103365 50124 103366 51696 103366 51754 103366 50124 103367 51754 103367 51753 103367 50115 103368 50113 103368 51714 103368 51714 103369 50113 103369 51717 103369 51714 103370 51717 103370 51715 103370 51715 103371 51717 103371 51716 103371 51716 103372 51717 103372 51718 103372 51716 103373 51718 103373 51692 103373 50121 103374 51719 103374 51723 103374 51718 103375 50125 103375 51692 103375 51692 103376 50125 103376 50118 103376 51692 103377 50118 103377 51720 103377 51720 103378 50118 103378 51721 103378 51720 103379 51721 103379 51684 103379 51684 103380 51721 103380 50121 103380 51684 103381 50121 103381 51722 103381 51722 103382 50121 103382 51723 103382 51724 103383 51725 103383 51726 103383 51726 103384 51725 103384 51739 103384 51726 103385 51739 103385 54672 103385 51727 103386 51728 103386 51729 103386 51727 103387 51729 103387 51730 103387 51730 103388 51729 103388 50058 103388 51730 103389 50058 103389 54676 103389 54676 103390 50058 103390 51731 103390 54676 103391 51731 103391 54674 103391 54674 103392 51731 103392 51733 103392 54674 103393 51733 103393 51732 103393 51732 103394 51733 103394 51734 103394 51734 103395 51733 103395 50092 103395 51734 103396 50092 103396 54675 103396 54675 103397 50092 103397 50096 103397 54675 103398 50096 103398 54673 103398 54673 103399 50096 103399 50095 103399 54673 103400 50095 103400 51736 103400 51735 103401 51725 103401 51724 103401 50095 103402 50084 103402 51736 103402 51736 103403 50084 103403 51737 103403 51736 103404 51737 103404 54671 103404 54671 103405 51737 103405 51735 103405 54671 103406 51735 103406 51738 103406 51738 103407 51735 103407 51724 103407 50131 103408 51740 103408 51739 103408 51739 103409 51740 103409 54670 103409 51739 103410 54670 103410 54672 103410 51740 103411 50131 103411 51741 103411 51740 103412 51741 103412 51743 103412 51743 103413 51741 103413 51742 103413 51743 103414 51742 103414 51744 103414 51742 103415 51745 103415 51744 103415 51744 103416 51745 103416 51746 103416 51744 103417 51746 103417 54681 103417 51746 103418 50149 103418 54681 103418 54681 103419 50149 103419 51747 103419 54681 103420 51747 103420 51748 103420 51748 103421 51747 103421 51749 103421 51748 103422 51749 103422 51751 103422 51749 103423 51750 103423 51751 103423 51751 103424 51750 103424 51757 103424 51751 103425 51757 103425 54678 103425 51752 103426 51753 103426 51754 103426 51754 103427 51755 103427 51752 103427 51752 103428 51755 103428 51756 103428 51752 103429 51756 103429 51757 103429 51757 103430 51756 103430 54679 103430 51757 103431 54679 103431 54678 103431 50237 103432 51674 103432 51758 103432 51758 103433 51674 103433 51759 103433 51758 103434 51759 103434 51677 103434 51676 103435 50212 103435 51760 103435 51760 103436 50212 103436 51758 103436 51760 103437 51758 103437 51677 103437 51761 103438 51771 103438 51668 103438 51674 103439 50237 103439 51675 103439 51675 103440 50237 103440 51767 103440 51761 103441 51668 103441 51762 103441 51762 103442 51668 103442 51763 103442 51762 103443 51763 103443 51764 103443 51764 103444 51763 103444 51673 103444 51764 103445 51673 103445 50241 103445 50241 103446 51673 103446 51765 103446 50241 103447 51765 103447 51766 103447 51766 103448 51765 103448 51672 103448 51766 103449 51672 103449 51767 103449 51767 103450 51672 103450 51670 103450 51767 103451 51670 103451 51675 103451 50215 103452 51665 103452 51768 103452 51768 103453 51665 103453 51769 103453 51768 103454 51769 103454 50235 103454 50235 103455 51769 103455 51770 103455 50235 103456 51770 103456 51771 103456 51771 103457 51770 103457 51669 103457 51771 103458 51669 103458 51668 103458 54693 103459 51798 103459 51772 103459 51772 103460 51798 103460 51773 103460 51772 103461 51773 103461 51680 103461 51680 103462 51773 103462 50179 103462 51680 103463 50179 103463 51774 103463 51774 103464 50179 103464 51776 103464 51774 103465 51776 103465 51682 103465 51682 103466 51776 103466 51775 103466 51775 103467 51776 103467 51777 103467 51775 103468 51777 103468 51678 103468 51678 103469 51777 103469 50189 103469 51678 103470 50189 103470 51778 103470 50194 103471 50212 103471 51676 103471 51676 103472 51679 103472 50194 103472 50194 103473 51679 103473 51779 103473 50194 103474 51779 103474 50193 103474 50193 103475 51779 103475 51778 103475 50193 103476 51778 103476 50192 103476 50192 103477 51778 103477 50189 103477 51780 103478 51665 103478 50215 103478 51780 103479 50215 103479 51781 103479 51781 103480 50215 103480 51782 103480 51781 103481 51782 103481 54688 103481 54688 103482 51782 103482 50218 103482 54688 103483 50218 103483 51783 103483 51783 103484 50218 103484 50207 103484 51783 103485 50207 103485 54690 103485 54690 103486 50207 103486 51784 103486 54690 103487 51784 103487 51785 103487 51784 103488 50211 103488 51785 103488 51785 103489 50211 103489 50201 103489 51785 103490 50201 103490 54686 103490 54686 103491 50201 103491 50199 103491 54686 103492 50199 103492 54687 103492 54687 103493 50199 103493 51786 103493 54687 103494 51786 103494 51787 103494 51787 103495 51786 103495 51789 103495 51787 103496 51789 103496 51788 103496 51788 103497 51789 103497 54683 103497 54683 103498 51789 103498 50168 103498 54683 103499 50168 103499 54684 103499 51794 103500 51790 103500 50168 103500 50168 103501 51790 103501 54682 103501 50168 103502 54682 103502 54684 103502 51797 103503 51791 103503 51795 103503 51795 103504 51791 103504 50164 103504 50164 103505 51791 103505 51792 103505 50164 103506 51792 103506 50163 103506 51792 103507 54697 103507 50163 103507 50163 103508 54697 103508 51793 103508 50163 103509 51793 103509 51794 103509 51794 103510 51793 103510 54696 103510 51794 103511 54696 103511 51790 103511 51795 103512 51796 103512 51797 103512 51797 103513 51796 103513 50154 103513 51797 103514 50154 103514 54694 103514 51799 103515 51798 103515 54693 103515 54693 103516 51800 103516 51799 103516 51799 103517 51800 103517 54692 103517 51799 103518 54692 103518 50154 103518 50154 103519 54692 103519 54695 103519 50154 103520 54695 103520 54694 103520 51657 103521 51801 103521 51658 103521 51658 103522 51801 103522 51802 103522 51658 103523 51802 103523 51804 103523 50033 103524 51816 103524 51802 103524 51802 103525 51816 103525 51803 103525 51802 103526 51803 103526 51804 103526 51834 103527 51833 103527 51805 103527 51805 103528 51833 103528 51806 103528 51805 103529 51806 103529 51807 103529 51807 103530 51806 103530 50047 103530 51807 103531 50047 103531 51663 103531 51663 103532 50047 103532 50054 103532 51663 103533 50054 103533 51808 103533 51808 103534 50054 103534 51809 103534 51808 103535 51809 103535 51810 103535 51809 103536 51811 103536 51810 103536 51810 103537 51811 103537 51812 103537 51810 103538 51812 103538 51813 103538 51813 103539 51812 103539 51814 103539 51813 103540 51814 103540 51661 103540 51661 103541 51814 103541 50050 103541 51661 103542 50050 103542 51815 103542 51815 103543 50050 103543 50049 103543 51815 103544 50049 103544 51662 103544 51662 103545 50049 103545 51801 103545 51662 103546 51801 103546 51657 103546 51816 103547 50033 103547 51817 103547 51817 103548 50033 103548 51824 103548 50008 103549 51841 103549 51842 103549 51842 103550 51651 103550 50008 103550 50008 103551 51651 103551 51650 103551 50008 103552 51650 103552 51819 103552 51819 103553 51650 103553 51818 103553 51819 103554 51818 103554 50001 103554 50001 103555 51818 103555 51654 103555 50001 103556 51654 103556 50002 103556 50002 103557 51654 103557 51653 103557 50002 103558 51653 103558 51820 103558 51820 103559 51653 103559 51652 103559 51820 103560 51652 103560 50029 103560 50029 103561 51652 103561 51822 103561 50029 103562 51822 103562 51821 103562 51821 103563 51822 103563 51823 103563 51821 103564 51823 103564 51824 103564 51824 103565 51823 103565 51825 103565 51824 103566 51825 103566 51817 103566 54716 103567 51826 103567 51838 103567 54716 103568 51838 103568 51827 103568 51827 103569 51838 103569 51829 103569 51827 103570 51829 103570 51828 103570 51828 103571 51829 103571 50012 103571 51828 103572 50012 103572 51830 103572 51830 103573 50012 103573 51831 103573 51830 103574 51831 103574 54712 103574 54712 103575 51831 103575 50020 103575 54712 103576 50020 103576 54713 103576 54713 103577 50020 103577 51832 103577 54713 103578 51832 103578 54715 103578 51835 103579 51833 103579 51834 103579 51834 103580 54710 103580 51835 103580 51835 103581 54710 103581 51836 103581 51835 103582 51836 103582 51832 103582 51832 103583 51836 103583 51837 103583 51832 103584 51837 103584 54715 103584 51838 103585 51826 103585 49998 103585 49998 103586 51826 103586 51839 103586 49998 103587 51839 103587 54698 103587 51850 103588 51848 103588 51840 103588 51840 103589 51848 103589 49998 103589 51840 103590 49998 103590 54698 103590 54700 103591 51843 103591 49984 103591 51847 103592 54705 103592 51841 103592 51841 103593 54705 103593 54708 103593 51841 103594 54708 103594 51842 103594 51843 103595 54700 103595 51844 103595 51844 103596 54700 103596 54704 103596 51844 103597 54704 103597 49988 103597 49988 103598 54704 103598 54706 103598 49988 103599 54706 103599 49994 103599 49994 103600 54706 103600 51845 103600 49994 103601 51845 103601 51847 103601 51847 103602 51845 103602 51846 103602 51847 103603 51846 103603 54705 103603 51848 103604 51850 103604 51849 103604 51849 103605 51850 103605 51851 103605 51849 103606 51851 103606 49975 103606 49975 103607 51851 103607 51852 103607 49975 103608 51852 103608 49984 103608 49984 103609 51852 103609 54701 103609 49984 103610 54701 103610 54700 103610 53109 103611 50262 103611 51853 103611 51853 103612 50262 103612 50258 103612 51853 103613 50258 103613 53125 103613 53125 103614 50258 103614 51854 103614 53125 103615 51854 103615 53124 103615 53124 103616 51854 103616 50260 103616 53134 103617 51886 103617 51855 103617 51855 103618 51886 103618 51857 103618 51855 103619 51857 103619 51856 103619 51856 103620 51857 103620 51858 103620 51856 103621 51858 103621 51859 103621 51859 103622 51858 103622 50247 103622 51859 103623 50247 103623 53129 103623 53129 103624 50247 103624 50248 103624 53129 103625 50248 103625 51860 103625 51860 103626 50248 103626 50250 103626 53066 103627 51876 103627 51861 103627 51861 103628 51876 103628 51862 103628 51861 103629 51862 103629 53056 103629 53056 103630 51862 103630 51863 103630 53056 103631 51863 103631 51864 103631 51864 103632 51863 103632 51866 103632 51864 103633 51866 103633 51865 103633 51865 103634 51866 103634 51867 103634 51865 103635 51867 103635 53067 103635 53067 103636 51867 103636 51868 103636 51869 103637 50390 103637 53038 103637 53038 103638 50390 103638 50392 103638 53038 103639 50392 103639 51870 103639 51870 103640 50392 103640 50393 103640 51870 103641 50393 103641 53048 103641 53048 103642 50393 103642 53152 103642 52263 103643 51871 103643 51872 103643 52263 103644 51872 103644 50244 103644 50244 103645 51872 103645 51873 103645 50244 103646 51873 103646 50243 103646 50380 103647 51874 103647 51875 103647 50380 103648 51875 103648 50379 103648 50379 103649 51875 103649 53049 103649 50379 103650 53049 103650 52200 103650 50380 103651 51876 103651 51874 103651 51874 103652 51876 103652 53066 103652 53067 103653 51868 103653 51877 103653 53067 103654 51877 103654 53080 103654 51877 103655 50385 103655 53080 103655 53080 103656 50385 103656 51878 103656 53080 103657 51878 103657 51879 103657 51878 103658 50388 103658 51879 103658 51879 103659 50388 103659 50389 103659 51879 103660 50389 103660 53054 103660 53054 103661 50389 103661 53055 103661 50390 103662 51869 103662 51880 103662 51880 103663 51869 103663 53055 103663 51880 103664 53055 103664 51881 103664 51881 103665 53055 103665 50389 103665 51860 103666 50250 103666 51873 103666 51873 103667 50250 103667 50243 103667 50251 103668 53130 103668 51882 103668 51882 103669 53130 103669 53124 103669 51882 103670 53124 103670 50260 103670 51885 103671 51883 103671 50251 103671 50251 103672 51883 103672 51884 103672 50251 103673 51884 103673 53130 103673 51885 103674 50253 103674 51883 103674 51883 103675 50253 103675 50255 103675 51883 103676 50255 103676 53131 103676 53131 103677 50255 103677 53134 103677 53134 103678 50255 103678 50256 103678 53134 103679 50256 103679 51886 103679 51915 103680 51896 103680 51887 103680 51896 103681 51899 103681 51894 103681 51905 103682 51887 103682 51888 103682 51888 103683 51887 103683 51896 103683 51888 103684 51896 103684 51903 103684 51903 103685 51896 103685 51892 103685 51887 103686 51906 103686 51915 103686 51915 103687 51906 103687 51909 103687 51915 103688 51909 103688 51910 103688 51914 103689 51890 103689 51889 103689 51889 103690 51890 103690 51915 103690 51889 103691 51915 103691 51911 103691 51911 103692 51915 103692 51910 103692 51911 103693 51910 103693 51891 103693 51892 103694 51896 103694 51893 103694 51893 103695 51896 103695 51894 103695 51893 103696 51894 103696 51895 103696 51897 103697 51896 103697 50965 103697 50965 103698 51896 103698 51915 103698 51896 103699 51897 103699 50969 103699 51896 103700 50969 103700 51899 103700 51899 103701 50969 103701 51898 103701 51899 103702 51898 103702 51894 103702 51894 103703 51898 103703 51900 103703 51894 103704 51900 103704 51895 103704 51895 103705 51900 103705 51902 103705 51895 103706 51902 103706 51893 103706 51901 103707 51892 103707 51902 103707 51902 103708 51892 103708 51893 103708 51892 103709 51901 103709 51903 103709 51903 103710 51901 103710 51904 103710 51903 103711 51904 103711 51888 103711 51888 103712 51904 103712 50981 103712 51888 103713 50981 103713 51905 103713 51905 103714 50981 103714 50982 103714 51905 103715 50982 103715 51887 103715 51887 103716 50982 103716 51907 103716 51908 103717 51906 103717 51907 103717 51907 103718 51906 103718 51887 103718 51906 103719 51908 103719 50973 103719 51906 103720 50973 103720 51909 103720 51909 103721 50973 103721 50975 103721 51909 103722 50975 103722 51910 103722 51910 103723 50975 103723 50976 103723 51910 103724 50976 103724 51891 103724 51891 103725 50976 103725 51912 103725 51891 103726 51912 103726 51911 103726 50968 103727 51889 103727 51912 103727 51912 103728 51889 103728 51911 103728 51889 103729 50968 103729 51914 103729 51914 103730 50968 103730 51913 103730 51914 103731 51913 103731 51890 103731 51890 103732 51913 103732 51916 103732 51890 103733 51916 103733 51915 103733 51915 103734 51916 103734 50965 103734 51917 103735 50697 103735 51933 103735 51925 103736 51971 103736 54739 103736 51918 103737 51919 103737 54741 103737 54739 103738 51971 103738 51920 103738 51921 103739 53203 103739 51953 103739 51953 103740 53203 103740 53196 103740 51953 103741 53196 103741 51950 103741 51950 103742 53196 103742 51522 103742 51950 103743 51522 103743 51922 103743 51922 103744 51918 103744 51950 103744 51950 103745 51918 103745 54741 103745 51950 103746 54741 103746 51923 103746 51923 103747 54741 103747 51920 103747 51923 103748 51920 103748 51924 103748 51924 103749 51920 103749 51971 103749 54739 103750 54738 103750 51925 103750 51925 103751 54738 103751 51926 103751 51925 103752 51926 103752 50701 103752 50701 103753 51926 103753 50621 103753 50701 103754 50621 103754 50703 103754 50703 103755 50621 103755 50704 103755 50626 103756 51927 103756 51928 103756 51928 103757 51927 103757 50625 103757 51928 103758 50625 103758 51933 103758 51928 103759 50698 103759 50626 103759 50626 103760 50698 103760 50699 103760 50626 103761 50699 103761 50621 103761 50621 103762 50699 103762 50700 103762 50621 103763 50700 103763 50704 103763 51929 103764 51930 103764 50630 103764 51931 103765 51917 103765 51932 103765 51932 103766 51917 103766 51933 103766 51932 103767 51933 103767 51934 103767 51934 103768 51933 103768 50625 103768 50630 103769 51935 103769 51929 103769 51929 103770 51935 103770 51936 103770 51929 103771 51936 103771 51937 103771 51937 103772 51936 103772 51938 103772 51937 103773 51938 103773 51932 103773 51932 103774 51938 103774 51939 103774 51932 103775 51939 103775 51931 103775 51948 103776 51947 103776 50696 103776 50668 103777 50695 103777 50694 103777 50670 103778 51940 103778 51944 103778 51944 103779 51940 103779 50668 103779 51944 103780 50668 103780 51941 103780 51941 103781 50668 103781 50694 103781 50670 103782 50656 103782 51942 103782 51942 103783 50656 103783 51943 103783 50670 103784 51944 103784 50656 103784 50656 103785 51944 103785 51945 103785 50656 103786 51945 103786 50657 103786 50657 103787 51945 103787 50620 103787 50657 103788 50620 103788 50663 103788 51938 103789 51946 103789 51939 103789 51939 103790 51946 103790 51948 103790 51939 103791 51948 103791 51931 103791 51931 103792 51948 103792 50696 103792 51931 103793 50696 103793 51917 103793 50694 103794 51947 103794 51941 103794 51941 103795 51947 103795 51948 103795 51941 103796 51948 103796 51944 103796 51944 103797 51948 103797 51946 103797 51944 103798 51946 103798 51945 103798 51945 103799 51946 103799 51938 103799 51945 103800 51938 103800 50620 103800 51972 103801 51949 103801 51971 103801 51971 103802 51949 103802 51924 103802 51949 103803 50949 103803 51924 103803 51924 103804 50949 103804 51952 103804 51924 103805 51952 103805 51923 103805 50947 103806 51950 103806 51951 103806 51951 103807 51950 103807 51923 103807 51951 103808 51923 103808 50948 103808 50948 103809 51923 103809 51952 103809 51954 103810 51953 103810 50947 103810 50947 103811 51953 103811 51950 103811 51953 103812 51954 103812 50950 103812 51953 103813 50950 103813 51921 103813 51921 103814 50950 103814 51955 103814 51921 103815 51955 103815 53203 103815 50664 103816 51956 103816 51957 103816 51957 103817 51956 103817 50939 103817 51957 103818 50939 103818 50665 103818 50665 103819 50939 103819 50938 103819 50665 103820 50938 103820 50675 103820 50675 103821 50938 103821 51958 103821 51962 103822 50675 103822 51958 103822 51963 103823 51959 103823 51960 103823 51960 103824 51959 103824 51961 103824 51960 103825 51961 103825 51958 103825 51958 103826 51961 103826 50672 103826 51958 103827 50672 103827 51962 103827 51963 103828 51960 103828 50686 103828 50686 103829 51960 103829 51964 103829 50686 103830 51964 103830 50687 103830 50687 103831 51964 103831 51965 103831 50687 103832 51965 103832 50693 103832 50693 103833 51965 103833 50684 103833 51966 103834 51967 103834 51965 103834 51965 103835 51967 103835 51968 103835 51965 103836 51968 103836 50684 103836 50681 103837 51969 103837 50944 103837 50944 103838 51969 103838 51970 103838 50944 103839 51970 103839 50679 103839 50679 103840 50678 103840 50944 103840 50944 103841 50678 103841 50683 103841 50944 103842 50683 103842 51966 103842 51966 103843 50683 103843 50676 103843 51966 103844 50676 103844 51967 103844 51972 103845 51971 103845 51925 103845 50681 103846 50944 103846 50723 103846 50723 103847 50944 103847 51972 103847 50723 103848 51972 103848 50702 103848 50702 103849 51972 103849 51925 103849 51977 103850 51975 103850 51973 103850 51986 103851 51979 103851 51980 103851 51973 103852 51975 103852 51974 103852 51974 103853 51975 103853 50735 103853 51974 103854 50735 103854 51976 103854 51977 103855 51973 103855 50752 103855 50752 103856 51973 103856 51978 103856 50752 103857 51978 103857 50731 103857 51979 103858 52009 103858 51980 103858 51980 103859 52009 103859 51981 103859 51980 103860 51981 103860 51982 103860 51982 103861 51981 103861 52012 103861 51982 103862 52012 103862 51544 103862 51544 103863 52012 103863 52013 103863 51544 103864 52013 103864 51542 103864 51542 103865 52013 103865 51983 103865 51542 103866 51983 103866 51978 103866 51978 103867 51983 103867 50732 103867 51978 103868 50732 103868 50731 103868 51987 103869 51984 103869 52006 103869 54744 103870 54743 103870 51985 103870 51985 103871 54743 103871 51986 103871 51985 103872 51986 103872 51538 103872 51538 103873 51986 103873 51980 103873 54743 103874 51524 103874 51986 103874 51986 103875 51524 103875 51987 103875 51986 103876 51987 103876 52008 103876 52008 103877 51987 103877 52006 103877 50740 103878 50726 103878 51989 103878 51976 103879 50735 103879 51988 103879 51988 103880 50735 103880 50734 103880 51988 103881 50734 103881 51989 103881 51989 103882 50734 103882 51990 103882 51989 103883 51990 103883 50740 103883 50818 103884 50816 103884 51991 103884 51991 103885 50816 103885 50820 103885 51991 103886 50820 103886 51992 103886 51992 103887 50820 103887 50819 103887 51992 103888 50819 103888 51999 103888 51999 103889 50819 103889 51993 103889 51999 103890 51993 103890 51998 103890 51998 103891 51993 103891 51989 103891 51998 103892 51989 103892 51997 103892 51997 103893 51989 103893 50726 103893 51996 103894 50776 103894 51994 103894 51994 103895 50776 103895 50775 103895 51994 103896 50775 103896 50797 103896 52005 103897 51995 103897 51994 103897 51994 103898 51995 103898 52004 103898 51994 103899 52004 103899 51996 103899 51996 103900 52004 103900 52003 103900 51996 103901 52003 103901 50779 103901 52002 103902 50748 103902 52001 103902 51997 103903 50748 103903 51998 103903 51998 103904 50748 103904 52002 103904 51998 103905 52002 103905 51999 103905 51999 103906 52002 103906 52000 103906 51999 103907 52000 103907 51992 103907 51992 103908 52000 103908 50814 103908 50780 103909 50779 103909 52001 103909 52001 103910 50779 103910 52003 103910 52001 103911 52003 103911 52002 103911 52002 103912 52003 103912 52004 103912 52002 103913 52004 103913 52000 103913 52000 103914 52004 103914 51995 103914 52000 103915 51995 103915 50814 103915 50814 103916 51995 103916 52005 103916 50814 103917 52005 103917 50800 103917 51984 103918 53212 103918 50962 103918 51984 103919 50962 103919 52006 103919 52006 103920 50962 103920 50963 103920 52006 103921 50963 103921 52008 103921 52007 103922 51986 103922 50963 103922 50963 103923 51986 103923 52008 103923 51986 103924 52007 103924 50959 103924 51986 103925 50959 103925 51979 103925 51979 103926 50959 103926 52010 103926 51979 103927 52010 103927 52009 103927 52009 103928 52010 103928 52011 103928 52009 103929 52011 103929 51981 103929 51981 103930 52011 103930 52016 103930 51981 103931 52016 103931 52012 103931 52013 103932 52012 103932 52014 103932 52014 103933 52012 103933 52016 103933 52014 103934 52016 103934 52015 103934 52015 103935 52016 103935 50744 103935 52019 103936 50730 103936 52016 103936 52016 103937 50730 103937 50729 103937 52016 103938 50729 103938 50744 103938 50760 103939 52019 103939 52017 103939 52017 103940 52019 103940 52018 103940 52017 103941 52018 103941 50759 103941 50760 103942 52020 103942 52019 103942 52019 103943 52020 103943 50762 103943 52019 103944 50762 103944 50730 103944 52022 103945 52018 103945 52021 103945 52021 103946 52018 103946 52024 103946 52022 103947 50757 103947 52018 103947 52018 103948 50757 103948 52023 103948 52018 103949 52023 103949 50759 103949 52025 103950 52027 103950 52024 103950 52024 103951 52027 103951 50758 103951 52024 103952 50758 103952 52021 103952 50956 103953 50753 103953 52025 103953 52025 103954 50753 103954 52026 103954 52025 103955 52026 103955 52027 103955 52029 103956 50954 103956 50771 103956 50771 103957 50954 103957 52030 103957 50753 103958 50956 103958 50773 103958 50773 103959 50956 103959 50954 103959 50773 103960 50954 103960 52028 103960 52028 103961 50954 103961 52029 103961 52030 103962 50954 103962 50951 103962 52030 103963 50951 103963 50781 103963 50781 103964 50951 103964 50953 103964 50781 103965 50953 103965 50783 103965 50783 103966 50953 103966 54505 103966 50783 103967 54505 103967 50784 103967 52031 103968 52034 103968 52059 103968 54164 103969 52032 103969 54166 103969 54166 103970 52032 103970 52033 103970 54166 103971 52033 103971 54167 103971 54167 103972 52033 103972 52031 103972 54167 103973 52031 103973 54170 103973 54170 103974 52031 103974 52059 103974 52061 103975 52060 103975 52035 103975 52035 103976 52060 103976 52034 103976 52034 103977 52031 103977 52035 103977 52035 103978 52031 103978 52033 103978 52035 103979 52033 103979 52040 103979 52040 103980 52033 103980 52032 103980 52040 103981 52032 103981 52037 103981 52679 103982 52062 103982 52039 103982 52039 103983 52062 103983 52061 103983 54164 103984 52945 103984 52032 103984 52032 103985 52945 103985 52036 103985 52032 103986 52036 103986 52037 103986 52037 103987 52036 103987 52038 103987 52037 103988 52038 103988 52944 103988 52061 103989 52035 103989 52039 103989 52039 103990 52035 103990 52040 103990 52039 103991 52040 103991 52042 103991 52042 103992 52040 103992 52037 103992 52042 103993 52037 103993 52044 103993 52044 103994 52037 103994 52944 103994 52044 103995 52944 103995 52045 103995 52679 103996 52039 103996 52041 103996 52041 103997 52039 103997 52042 103997 52041 103998 52042 103998 52043 103998 52043 103999 52042 103999 52044 103999 52043 104000 52044 104000 52675 104000 52675 104001 52044 104001 52045 104001 52675 104002 52045 104002 52674 104002 52948 104003 52947 104003 52051 104003 52063 104004 52949 104004 52053 104004 52053 104005 52949 104005 52948 104005 52059 104006 52057 104006 54172 104006 54172 104007 52057 104007 52055 104007 54172 104008 52055 104008 52046 104008 52046 104009 52055 104009 52047 104009 52046 104010 52047 104010 52049 104010 52049 104011 52047 104011 52048 104011 52049 104012 52048 104012 52050 104012 52050 104013 52048 104013 52051 104013 52050 104014 52051 104014 52052 104014 52052 104015 52051 104015 52947 104015 52052 104016 52947 104016 52946 104016 52948 104017 52051 104017 52053 104017 52053 104018 52051 104018 52048 104018 52053 104019 52048 104019 52064 104019 52064 104020 52048 104020 52047 104020 52064 104021 52047 104021 52054 104021 52054 104022 52047 104022 52055 104022 52054 104023 52055 104023 52056 104023 52056 104024 52055 104024 52057 104024 52056 104025 52057 104025 52058 104025 52059 104026 52034 104026 52057 104026 52057 104027 52034 104027 52060 104027 52057 104028 52060 104028 52058 104028 52058 104029 52060 104029 52061 104029 52058 104030 52061 104030 52062 104030 52063 104031 52053 104031 52682 104031 52682 104032 52053 104032 52064 104032 52682 104033 52064 104033 52680 104033 52680 104034 52064 104034 52054 104034 52680 104035 52054 104035 52684 104035 52684 104036 52054 104036 52056 104036 52684 104037 52056 104037 52683 104037 52683 104038 52056 104038 52058 104038 52683 104039 52058 104039 52065 104039 52065 104040 52058 104040 52062 104040 52065 104041 52062 104041 52679 104041 52686 104042 52685 104042 52072 104042 52066 104043 52088 104043 52067 104043 52067 104044 52088 104044 52068 104044 52067 104045 52068 104045 52069 104045 52070 104046 52090 104046 52066 104046 52066 104047 52090 104047 52089 104047 52066 104048 52089 104048 52088 104048 52069 104049 52926 104049 52067 104049 52067 104050 52926 104050 52076 104050 52067 104051 52076 104051 52066 104051 52066 104052 52076 104052 52071 104052 52066 104053 52071 104053 52070 104053 52070 104054 52071 104054 52072 104054 52073 104055 52678 104055 52070 104055 52070 104056 52678 104056 52095 104056 52070 104057 52095 104057 52090 104057 52072 104058 52685 104058 52070 104058 52070 104059 52685 104059 52074 104059 52070 104060 52074 104060 52073 104060 52681 104061 52686 104061 52075 104061 52075 104062 52686 104062 52072 104062 52075 104063 52072 104063 52080 104063 52080 104064 52072 104064 52071 104064 52080 104065 52071 104065 52078 104065 52078 104066 52071 104066 52076 104066 52078 104067 52076 104067 52077 104067 52077 104068 52076 104068 52926 104068 52077 104069 52938 104069 52078 104069 52078 104070 52938 104070 52079 104070 52078 104071 52079 104071 52080 104071 52080 104072 52079 104072 52936 104072 52080 104073 52936 104073 52075 104073 52075 104074 52936 104074 52932 104074 52075 104075 52932 104075 52681 104075 52681 104076 52932 104076 52934 104076 52081 104077 52087 104077 52092 104077 52087 104078 52915 104078 52085 104078 52068 104079 52082 104079 52083 104079 52083 104080 52082 104080 52084 104080 52083 104081 52084 104081 52931 104081 52931 104082 52084 104082 52085 104082 52931 104083 52085 104083 52930 104083 52930 104084 52085 104084 52915 104084 52930 104085 52915 104085 52086 104085 52087 104086 52085 104086 52092 104086 52092 104087 52085 104087 52084 104087 52092 104088 52084 104088 52093 104088 52093 104089 52084 104089 52082 104089 52093 104090 52082 104090 52094 104090 52068 104091 52088 104091 52082 104091 52082 104092 52088 104092 52089 104092 52082 104093 52089 104093 52094 104093 52094 104094 52089 104094 52090 104094 52094 104095 52090 104095 52095 104095 52081 104096 52092 104096 52091 104096 52091 104097 52092 104097 52093 104097 52091 104098 52093 104098 52676 104098 52676 104099 52093 104099 52094 104099 52676 104100 52094 104100 52677 104100 52677 104101 52094 104101 52095 104101 52677 104102 52095 104102 52678 104102 52697 104103 52696 104103 52096 104103 52098 104104 52123 104104 52101 104104 52101 104105 52123 104105 52097 104105 52101 104106 52097 104106 52100 104106 52104 104107 52099 104107 52098 104107 52098 104108 52099 104108 52125 104108 52098 104109 52125 104109 52123 104109 52100 104110 52109 104110 52101 104110 52101 104111 52109 104111 52107 104111 52101 104112 52107 104112 52098 104112 52098 104113 52107 104113 52102 104113 52098 104114 52102 104114 52104 104114 52104 104115 52102 104115 52096 104115 52105 104116 52687 104116 52104 104116 52104 104117 52687 104117 52103 104117 52104 104118 52103 104118 52099 104118 52096 104119 52696 104119 52104 104119 52104 104120 52696 104120 52695 104120 52104 104121 52695 104121 52105 104121 52698 104122 52697 104122 52106 104122 52106 104123 52697 104123 52096 104123 52106 104124 52096 104124 52111 104124 52111 104125 52096 104125 52102 104125 52111 104126 52102 104126 52110 104126 52110 104127 52102 104127 52107 104127 52110 104128 52107 104128 52108 104128 52108 104129 52107 104129 52109 104129 52108 104130 52901 104130 52110 104130 52110 104131 52901 104131 52900 104131 52110 104132 52900 104132 52111 104132 52111 104133 52900 104133 52112 104133 52111 104134 52112 104134 52106 104134 52106 104135 52112 104135 52113 104135 52106 104136 52113 104136 52698 104136 52698 104137 52113 104137 52895 104137 52114 104138 52903 104138 52118 104138 52097 104139 52124 104139 52116 104139 52116 104140 52124 104140 52115 104140 52116 104141 52115 104141 52117 104141 52117 104142 52115 104142 52118 104142 52117 104143 52118 104143 52910 104143 52910 104144 52118 104144 52903 104144 52910 104145 52903 104145 52119 104145 52889 104146 52121 104146 52120 104146 52120 104147 52121 104147 52114 104147 52114 104148 52118 104148 52120 104148 52120 104149 52118 104149 52115 104149 52120 104150 52115 104150 52122 104150 52122 104151 52115 104151 52124 104151 52122 104152 52124 104152 52126 104152 52097 104153 52123 104153 52124 104153 52124 104154 52123 104154 52125 104154 52124 104155 52125 104155 52126 104155 52126 104156 52125 104156 52099 104156 52126 104157 52099 104157 52103 104157 52889 104158 52120 104158 52693 104158 52693 104159 52120 104159 52122 104159 52693 104160 52122 104160 52127 104160 52127 104161 52122 104161 52126 104161 52127 104162 52126 104162 52128 104162 52128 104163 52126 104163 52103 104163 52128 104164 52103 104164 52687 104164 52132 104165 52158 104165 52129 104165 52129 104166 52158 104166 52130 104166 52129 104167 52130 104167 54183 104167 52133 104168 52131 104168 52132 104168 52132 104169 52131 104169 52159 104169 52132 104170 52159 104170 52158 104170 52689 104171 52688 104171 52133 104171 52133 104172 52688 104172 52134 104172 52133 104173 52134 104173 52131 104173 54183 104174 54182 104174 52129 104174 52129 104175 54182 104175 52135 104175 52129 104176 52135 104176 52132 104176 52132 104177 52135 104177 52137 104177 52132 104178 52137 104178 52133 104178 52133 104179 52137 104179 52138 104179 52133 104180 52138 104180 52689 104180 52689 104181 52138 104181 52690 104181 54182 104182 54181 104182 52135 104182 52135 104183 54181 104183 52139 104183 52135 104184 52139 104184 52137 104184 52137 104185 52139 104185 52136 104185 52137 104186 52136 104186 52138 104186 52138 104187 52136 104187 52141 104187 52138 104188 52141 104188 52690 104188 52690 104189 52141 104189 52691 104189 54181 104190 54173 104190 52139 104190 52139 104191 54173 104191 52140 104191 52139 104192 52140 104192 52136 104192 52136 104193 52140 104193 52142 104193 52136 104194 52142 104194 52141 104194 52141 104195 52142 104195 52884 104195 52141 104196 52884 104196 52691 104196 52691 104197 52884 104197 52692 104197 52882 104198 52143 104198 52162 104198 52143 104199 52881 104199 52144 104199 52130 104200 52145 104200 52146 104200 52146 104201 52145 104201 52148 104201 52146 104202 52148 104202 52147 104202 52147 104203 52148 104203 52156 104203 52147 104204 52156 104204 52149 104204 52149 104205 52156 104205 52150 104205 52149 104206 52150 104206 52151 104206 52151 104207 52150 104207 52144 104207 52151 104208 52144 104208 52152 104208 52152 104209 52144 104209 52881 104209 52152 104210 52881 104210 52153 104210 52143 104211 52144 104211 52162 104211 52162 104212 52144 104212 52150 104212 52162 104213 52150 104213 52154 104213 52154 104214 52150 104214 52156 104214 52154 104215 52156 104215 52155 104215 52155 104216 52156 104216 52148 104216 52155 104217 52148 104217 52157 104217 52157 104218 52148 104218 52145 104218 52157 104219 52145 104219 52160 104219 52130 104220 52158 104220 52145 104220 52145 104221 52158 104221 52159 104221 52145 104222 52159 104222 52160 104222 52160 104223 52159 104223 52131 104223 52160 104224 52131 104224 52134 104224 52882 104225 52162 104225 52161 104225 52161 104226 52162 104226 52154 104226 52161 104227 52154 104227 52163 104227 52163 104228 52154 104228 52155 104228 52163 104229 52155 104229 52164 104229 52164 104230 52155 104230 52157 104230 52164 104231 52157 104231 52165 104231 52165 104232 52157 104232 52160 104232 52165 104233 52160 104233 52694 104233 52694 104234 52160 104234 52134 104234 52694 104235 52134 104235 52688 104235 52181 104236 52166 104236 52170 104236 52166 104237 52167 104237 52179 104237 52177 104238 52176 104238 52172 104238 52183 104239 52168 104239 52184 104239 52184 104240 52168 104240 52181 104240 52184 104241 52181 104241 52169 104241 52169 104242 52181 104242 52170 104242 52169 104243 52170 104243 52186 104243 52186 104244 52170 104244 52187 104244 52179 104245 52178 104245 52166 104245 52166 104246 52178 104246 52171 104246 52166 104247 52171 104247 52170 104247 52170 104248 52171 104248 52177 104248 52170 104249 52177 104249 52175 104249 52175 104250 52177 104250 52172 104250 52173 104251 52170 104251 52174 104251 52174 104252 52170 104252 52175 104252 52174 104253 52175 104253 50515 104253 50515 104254 52175 104254 52172 104254 50515 104255 52172 104255 50514 104255 50514 104256 52172 104256 52176 104256 50514 104257 52176 104257 50517 104257 50517 104258 52176 104258 52177 104258 50517 104259 52177 104259 50512 104259 50512 104260 52177 104260 52171 104260 50512 104261 52171 104261 50511 104261 50511 104262 52171 104262 52178 104262 50511 104263 52178 104263 50509 104263 50509 104264 52178 104264 52179 104264 50509 104265 52179 104265 50508 104265 50508 104266 52179 104266 52167 104266 50508 104267 52167 104267 50506 104267 50506 104268 52167 104268 52166 104268 50506 104269 52166 104269 52180 104269 52180 104270 52166 104270 52181 104270 52180 104271 52181 104271 50502 104271 50502 104272 52181 104272 52168 104272 50502 104273 52168 104273 52182 104273 52182 104274 52168 104274 52183 104274 52182 104275 52183 104275 50501 104275 50501 104276 52183 104276 52184 104276 50501 104277 52184 104277 50500 104277 50500 104278 52184 104278 52169 104278 50500 104279 52169 104279 52185 104279 52185 104280 52169 104280 52186 104280 52185 104281 52186 104281 50504 104281 50504 104282 52186 104282 52187 104282 50504 104283 52187 104283 52173 104283 52173 104284 52187 104284 52170 104284 50482 104285 54567 104285 52197 104285 52197 104286 54567 104286 54566 104286 52188 104287 54556 104287 54555 104287 52188 104288 54555 104288 52189 104288 52189 104289 54555 104289 54550 104289 52189 104290 54550 104290 50488 104290 50488 104291 54550 104291 52190 104291 50488 104292 52190 104292 50489 104292 50489 104293 52190 104293 54567 104293 50489 104294 54567 104294 50482 104294 52191 104295 52192 104295 52188 104295 52188 104296 52192 104296 54556 104296 50496 104297 54554 104297 50497 104297 50497 104298 54554 104298 52192 104298 50497 104299 52192 104299 52191 104299 50426 104300 52194 104300 52193 104300 52193 104301 52194 104301 50427 104301 52193 104302 50427 104302 50496 104302 50496 104303 50427 104303 54523 104303 50496 104304 54523 104304 54554 104304 52195 104305 53081 104305 53079 104305 52195 104306 53079 104306 50493 104306 50493 104307 53079 104307 53142 104307 50493 104308 53142 104308 50494 104308 50494 104309 53142 104309 53141 104309 50494 104310 53141 104310 53149 104310 53081 104311 52195 104311 53041 104311 53041 104312 52195 104312 50484 104312 52200 104313 53049 104313 53042 104313 52200 104314 52201 104314 52196 104314 52196 104315 52201 104315 50483 104315 52196 104316 50483 104316 52199 104316 52197 104317 54566 104317 50483 104317 50483 104318 54566 104318 52198 104318 50483 104319 52198 104319 52199 104319 52200 104320 53042 104320 52201 104320 52201 104321 53042 104321 53041 104321 52201 104322 53041 104322 50484 104322 52219 104323 50492 104323 52202 104323 52202 104324 50492 104324 52203 104324 52202 104325 52203 104325 50510 104325 50510 104326 52203 104326 50487 104326 50510 104327 50487 104327 52204 104327 52204 104328 50487 104328 52205 104328 52204 104329 52205 104329 50518 104329 50518 104330 52205 104330 50490 104330 50518 104331 50490 104331 50513 104331 50513 104332 50490 104332 52206 104332 50513 104333 52206 104333 52207 104333 52207 104334 52206 104334 52208 104334 52207 104335 52208 104335 50516 104335 50516 104336 52208 104336 50485 104336 50516 104337 50485 104337 52209 104337 52209 104338 50485 104338 50486 104338 52209 104339 50486 104339 50503 104339 50503 104340 50486 104340 50491 104340 50503 104341 50491 104341 50505 104341 50505 104342 50491 104342 52210 104342 50505 104343 52210 104343 52211 104343 52211 104344 52210 104344 50495 104344 52211 104345 50495 104345 50499 104345 50499 104346 50495 104346 52212 104346 50499 104347 52212 104347 52213 104347 52213 104348 52212 104348 52214 104348 52213 104349 52214 104349 52216 104349 52216 104350 52214 104350 52215 104350 52216 104351 52215 104351 52217 104351 52217 104352 52215 104352 50498 104352 52217 104353 50498 104353 50507 104353 50507 104354 50498 104354 52218 104354 50507 104355 52218 104355 52219 104355 52219 104356 52218 104356 50492 104356 52244 104357 52221 104357 52220 104357 52220 104358 52221 104358 52223 104358 52220 104359 52223 104359 52222 104359 52222 104360 52223 104360 52228 104360 52230 104361 52241 104361 52224 104361 52225 104362 52237 104362 52239 104362 52239 104363 52237 104363 52226 104363 52239 104364 52226 104364 52229 104364 52235 104365 52234 104365 52227 104365 52227 104366 52234 104366 52228 104366 52227 104367 52228 104367 52226 104367 52226 104368 52228 104368 52223 104368 52226 104369 52223 104369 52229 104369 52229 104370 52223 104370 52230 104370 52229 104371 52230 104371 52231 104371 52231 104372 52230 104372 52224 104372 50545 104373 52222 104373 50554 104373 50554 104374 52222 104374 52228 104374 50554 104375 52228 104375 52232 104375 52232 104376 52228 104376 52234 104376 52232 104377 52234 104377 52233 104377 52233 104378 52234 104378 52235 104378 52233 104379 52235 104379 50549 104379 50549 104380 52235 104380 52227 104380 50549 104381 52227 104381 52236 104381 52236 104382 52227 104382 52226 104382 52236 104383 52226 104383 50543 104383 50543 104384 52226 104384 52237 104384 50543 104385 52237 104385 52238 104385 52238 104386 52237 104386 52225 104386 52238 104387 52225 104387 50542 104387 50542 104388 52225 104388 52239 104388 50542 104389 52239 104389 50539 104389 50539 104390 52239 104390 52229 104390 50539 104391 52229 104391 52240 104391 52240 104392 52229 104392 52231 104392 52240 104393 52231 104393 50536 104393 50536 104394 52231 104394 52224 104394 50536 104395 52224 104395 50535 104395 50535 104396 52224 104396 52241 104396 50535 104397 52241 104397 50541 104397 50541 104398 52241 104398 52230 104398 50541 104399 52230 104399 52242 104399 52242 104400 52230 104400 52223 104400 52242 104401 52223 104401 50547 104401 50547 104402 52223 104402 52221 104402 50547 104403 52221 104403 52243 104403 52243 104404 52221 104404 52244 104404 52243 104405 52244 104405 50546 104405 50546 104406 52244 104406 52220 104406 50546 104407 52220 104407 50545 104407 50545 104408 52220 104408 52222 104408 52268 104409 52245 104409 52247 104409 52247 104410 52245 104410 52248 104410 50521 104411 53151 104411 53139 104411 50521 104412 53139 104412 50522 104412 50522 104413 53139 104413 53138 104413 50522 104414 53138 104414 52246 104414 52246 104415 53138 104415 53137 104415 52246 104416 53137 104416 50525 104416 50525 104417 53137 104417 52247 104417 50525 104418 52247 104418 52248 104418 52250 104419 54549 104419 50526 104419 50526 104420 54549 104420 52249 104420 50526 104421 52249 104421 53150 104421 50526 104422 52251 104422 52250 104422 52250 104423 52251 104423 52252 104423 52250 104424 52252 104424 52253 104424 52253 104425 52252 104425 50531 104425 52253 104426 50531 104426 52254 104426 52254 104427 50531 104427 50533 104427 52254 104428 50533 104428 52257 104428 52255 104429 52256 104429 50533 104429 50533 104430 52256 104430 52257 104430 52258 104431 52261 104431 54535 104431 52258 104432 54535 104432 52259 104432 52259 104433 54535 104433 52260 104433 52259 104434 52260 104434 50529 104434 50529 104435 52260 104435 52256 104435 50529 104436 52256 104436 52255 104436 52262 104437 52267 104437 52258 104437 52258 104438 52267 104438 52261 104438 52267 104439 52262 104439 50520 104439 53133 104440 51871 104440 52263 104440 52263 104441 52264 104441 52265 104441 52265 104442 52264 104442 52266 104442 52265 104443 52266 104443 50520 104443 50520 104444 52266 104444 54533 104444 50520 104445 54533 104445 52267 104445 52263 104446 52265 104446 53133 104446 53133 104447 52265 104447 50519 104447 53133 104448 50519 104448 53132 104448 53132 104449 50519 104449 52245 104449 53132 104450 52245 104450 52268 104450 52287 104451 52288 104451 50534 104451 50534 104452 52288 104452 52269 104452 50534 104453 52269 104453 50537 104453 50537 104454 52269 104454 52270 104454 50537 104455 52270 104455 50538 104455 50538 104456 52270 104456 52271 104456 50538 104457 52271 104457 52272 104457 52272 104458 52271 104458 52273 104458 52272 104459 52273 104459 50540 104459 50540 104460 52273 104460 52274 104460 50540 104461 52274 104461 52276 104461 52276 104462 52274 104462 52275 104462 52276 104463 52275 104463 52277 104463 52277 104464 52275 104464 50528 104464 52277 104465 50528 104465 50544 104465 50544 104466 50528 104466 50530 104466 50544 104467 50530 104467 50550 104467 50550 104468 50530 104468 52279 104468 50550 104469 52279 104469 52278 104469 52278 104470 52279 104470 52280 104470 52278 104471 52280 104471 50552 104471 50552 104472 52280 104472 50532 104472 50552 104473 50532 104473 50553 104473 50553 104474 50532 104474 52281 104474 50553 104475 52281 104475 52282 104475 52282 104476 52281 104476 50527 104476 52282 104477 50527 104477 50551 104477 50551 104478 50527 104478 52284 104478 50551 104479 52284 104479 52283 104479 52283 104480 52284 104480 50523 104480 52283 104481 50523 104481 50548 104481 50548 104482 50523 104482 50524 104482 50548 104483 50524 104483 52285 104483 52285 104484 50524 104484 52286 104484 52285 104485 52286 104485 52287 104485 52287 104486 52286 104486 52288 104486 52289 104487 50472 104487 52309 104487 52309 104488 50472 104488 52299 104488 50472 104489 52289 104489 52292 104489 52292 104490 52289 104490 52291 104490 52307 104491 52290 104491 52291 104491 52291 104492 52290 104492 52292 104492 52306 104493 50474 104493 52314 104493 52314 104494 50474 104494 50477 104494 52314 104495 50477 104495 52293 104495 52293 104496 50477 104496 52294 104496 52293 104497 52294 104497 52313 104497 52313 104498 52294 104498 52295 104498 52313 104499 52295 104499 52296 104499 52296 104500 52295 104500 50480 104500 52296 104501 50480 104501 52298 104501 52298 104502 50480 104502 52297 104502 52298 104503 52297 104503 52307 104503 52307 104504 52297 104504 52290 104504 50474 104505 52306 104505 50471 104505 50471 104506 52306 104506 52308 104506 52309 104507 52299 104507 52300 104507 52300 104508 52299 104508 52302 104508 52300 104509 52302 104509 52301 104509 52301 104510 52302 104510 52303 104510 52301 104511 52303 104511 52311 104511 52311 104512 52303 104512 52304 104512 52311 104513 52304 104513 52310 104513 52310 104514 52304 104514 50468 104514 52310 104515 50468 104515 52312 104515 52312 104516 50468 104516 52305 104516 52312 104517 52305 104517 52308 104517 52308 104518 52305 104518 50471 104518 52307 104519 52291 104519 52306 104519 52296 104520 52298 104520 52307 104520 52306 104521 52291 104521 52308 104521 52291 104522 52289 104522 52308 104522 52308 104523 52289 104523 52309 104523 52308 104524 52309 104524 52300 104524 52310 104525 52312 104525 52311 104525 52311 104526 52312 104526 52308 104526 52311 104527 52308 104527 52301 104527 52301 104528 52308 104528 52300 104528 52313 104529 52296 104529 52293 104529 52293 104530 52296 104530 52307 104530 52293 104531 52307 104531 52314 104531 52314 104532 52307 104532 52306 104532 53167 104533 52321 104533 53165 104533 53165 104534 52321 104534 52323 104534 53165 104535 52323 104535 53164 104535 53164 104536 52323 104536 52315 104536 53164 104537 52315 104537 52317 104537 52317 104538 52315 104538 52316 104538 52317 104539 52316 104539 53161 104539 53094 104540 52318 104540 52319 104540 52319 104541 52318 104541 52320 104541 53096 104542 53094 104542 53167 104542 53167 104543 53094 104543 52319 104543 53167 104544 52319 104544 52321 104544 52321 104545 52319 104545 52320 104545 52320 104546 52467 104546 52321 104546 52321 104547 52467 104547 52322 104547 52321 104548 52322 104548 52323 104548 52323 104549 52322 104549 52457 104549 52323 104550 52457 104550 52315 104550 52315 104551 52457 104551 52456 104551 52315 104552 52456 104552 52316 104552 52316 104553 52324 104553 53161 104553 52324 104554 52316 104554 52456 104554 52491 104555 52488 104555 52325 104555 52325 104556 52488 104556 52324 104556 52325 104557 52324 104557 52456 104557 52325 104558 52326 104558 52491 104558 52491 104559 52326 104559 52327 104559 52491 104560 52327 104560 52490 104560 52490 104561 52327 104561 52459 104561 52490 104562 52459 104562 52328 104562 52459 104563 52329 104563 52328 104563 52328 104564 52329 104564 52330 104564 52328 104565 52330 104565 52489 104565 52489 104566 52330 104566 52461 104566 52489 104567 52461 104567 52331 104567 52331 104568 52461 104568 52486 104568 52486 104569 52461 104569 52460 104569 52486 104570 52460 104570 52332 104570 52332 104571 52460 104571 52333 104571 52332 104572 52333 104572 52334 104572 52334 104573 52333 104573 52335 104573 52334 104574 52335 104574 52468 104574 52355 104575 52354 104575 52336 104575 52337 104576 52354 104576 52483 104576 52354 104577 52337 104577 52481 104577 52478 104578 52354 104578 52339 104578 52354 104579 52478 104579 52338 104579 52479 104580 52339 104580 52354 104580 52336 104581 52354 104581 52340 104581 52469 104582 52335 104582 52341 104582 52469 104583 52341 104583 52470 104583 52470 104584 52341 104584 52353 104584 52470 104585 52353 104585 52473 104585 52338 104586 52340 104586 52354 104586 52481 104587 52479 104587 52354 104587 52353 104588 52342 104588 52473 104588 52473 104589 52342 104589 52343 104589 52473 104590 52343 104590 52474 104590 52474 104591 52343 104591 52359 104591 52474 104592 52359 104592 52336 104592 52336 104593 52359 104593 52357 104593 52336 104594 52357 104594 52355 104594 52344 104595 53148 104595 52345 104595 52346 104596 53146 104596 53145 104596 52345 104597 53148 104597 52346 104597 52346 104598 53148 104598 53147 104598 52346 104599 53147 104599 53146 104599 52344 104600 52345 104600 52347 104600 52347 104601 52345 104601 52348 104601 52347 104602 52348 104602 52349 104602 52349 104603 52348 104603 52350 104603 52349 104604 52350 104604 52452 104604 52483 104605 52354 104605 52941 104605 52941 104606 52354 104606 52356 104606 52351 104607 52941 104607 52352 104607 52352 104608 52941 104608 52356 104608 52352 104609 52356 104609 53145 104609 53145 104610 52356 104610 52358 104610 53145 104611 52358 104611 52346 104611 52335 104612 52350 104612 52341 104612 52341 104613 52350 104613 52348 104613 52341 104614 52348 104614 52353 104614 52353 104615 52348 104615 52345 104615 52353 104616 52345 104616 52342 104616 52342 104617 52345 104617 52346 104617 52354 104618 52355 104618 52356 104618 52356 104619 52355 104619 52357 104619 52356 104620 52357 104620 52358 104620 52358 104621 52357 104621 52359 104621 52358 104622 52359 104622 52346 104622 52346 104623 52359 104623 52343 104623 52346 104624 52343 104624 52342 104624 53145 104625 52360 104625 52352 104625 52352 104626 52360 104626 53144 104626 52352 104627 53144 104627 52351 104627 53046 104628 52362 104628 52363 104628 53046 104629 53157 104629 52362 104629 52362 104630 53157 104630 52361 104630 52362 104631 52361 104631 52363 104631 52363 104632 52361 104632 53154 104632 52363 104633 53154 104633 52364 104633 52364 104634 53154 104634 52365 104634 52364 104635 52365 104635 52368 104635 52368 104636 52365 104636 52366 104636 52368 104637 52366 104637 52367 104637 52367 104638 52371 104638 52419 104638 52367 104639 52419 104639 52368 104639 52368 104640 52419 104640 52369 104640 52368 104641 52369 104641 52364 104641 52364 104642 52369 104642 52370 104642 52364 104643 52370 104643 52363 104643 52363 104644 52370 104644 53044 104644 52363 104645 53044 104645 53046 104645 52367 104646 52378 104646 52371 104646 52378 104647 52367 104647 52366 104647 52402 104648 52443 104648 52411 104648 52411 104649 52443 104649 52372 104649 52411 104650 52372 104650 52379 104650 52374 104651 52441 104651 52402 104651 52402 104652 52441 104652 52373 104652 52402 104653 52373 104653 52443 104653 52402 104654 52404 104654 52374 104654 52374 104655 52404 104655 52408 104655 52374 104656 52408 104656 52437 104656 52437 104657 52408 104657 52406 104657 52437 104658 52406 104658 52435 104658 52435 104659 52406 104659 52405 104659 52435 104660 52405 104660 52434 104660 52434 104661 52405 104661 52375 104661 52405 104662 52376 104662 52375 104662 52375 104663 52376 104663 52409 104663 52375 104664 52409 104664 52377 104664 52377 104665 52409 104665 52371 104665 52377 104666 52371 104666 52378 104666 54668 104667 52379 104667 52372 104667 52410 104668 52379 104668 52380 104668 52380 104669 52379 104669 52390 104669 52380 104670 52390 104670 52382 104670 53119 104671 52399 104671 52410 104671 52410 104672 52380 104672 53119 104672 53119 104673 52380 104673 52382 104673 53119 104674 52382 104674 52381 104674 52381 104675 52382 104675 52393 104675 52381 104676 52393 104676 53120 104676 53120 104677 52393 104677 52388 104677 53120 104678 52388 104678 53121 104678 52383 104679 52384 104679 52386 104679 52386 104680 52384 104680 53121 104680 52386 104681 54669 104681 52385 104681 52383 104682 52386 104682 52387 104682 52387 104683 52386 104683 52385 104683 52387 104684 52385 104684 52887 104684 53121 104685 52388 104685 52386 104685 52386 104686 52388 104686 52389 104686 52386 104687 52389 104687 54669 104687 52390 104688 52391 104688 52382 104688 52382 104689 52391 104689 52392 104689 52382 104690 52392 104690 52393 104690 52393 104691 52392 104691 54666 104691 52393 104692 54666 104692 52388 104692 52388 104693 54666 104693 54664 104693 52388 104694 54664 104694 52389 104694 53121 104695 52384 104695 52394 104695 52394 104696 52384 104696 52383 104696 52394 104697 52383 104697 52395 104697 52421 104698 52415 104698 52418 104698 52413 104699 52403 104699 52396 104699 52414 104700 52397 104700 53033 104700 52417 104701 52398 104701 52418 104701 53084 104702 52396 104702 52399 104702 52399 104703 52396 104703 52400 104703 52399 104704 52400 104704 52410 104704 52411 104705 52401 104705 52402 104705 52402 104706 52401 104706 52403 104706 52402 104707 52403 104707 52404 104707 52404 104708 52403 104708 52413 104708 52415 104709 52421 104709 52407 104709 52421 104710 52405 104710 52407 104710 52407 104711 52405 104711 52406 104711 52407 104712 52406 104712 52413 104712 52413 104713 52406 104713 52408 104713 52413 104714 52408 104714 52404 104714 52376 104715 52420 104715 52409 104715 52409 104716 52420 104716 52419 104716 52409 104717 52419 104717 52371 104717 53033 104718 52397 104718 52412 104718 52396 104719 52403 104719 52400 104719 52400 104720 52403 104720 52401 104720 52400 104721 52401 104721 52410 104721 52410 104722 52401 104722 52411 104722 52410 104723 52411 104723 52379 104723 53084 104724 52412 104724 52396 104724 52396 104725 52412 104725 52397 104725 52396 104726 52397 104726 52413 104726 52413 104727 52397 104727 52414 104727 52413 104728 52414 104728 52407 104728 52407 104729 52414 104729 53034 104729 52407 104730 53034 104730 52415 104730 52415 104731 53034 104731 53043 104731 52415 104732 53043 104732 52418 104732 52418 104733 53043 104733 52416 104733 52418 104734 52416 104734 52417 104734 53044 104735 52370 104735 52417 104735 52417 104736 52370 104736 52369 104736 52417 104737 52369 104737 52398 104737 52398 104738 52369 104738 52419 104738 52398 104739 52419 104739 52418 104739 52418 104740 52419 104740 52420 104740 52418 104741 52420 104741 52421 104741 52421 104742 52420 104742 52376 104742 52421 104743 52376 104743 52405 104743 52887 104744 52422 104744 52888 104744 52888 104745 52422 104745 50424 104745 52422 104746 52423 104746 50424 104746 50424 104747 52423 104747 54662 104747 50424 104748 54662 104748 50425 104748 50425 104749 54662 104749 54661 104749 54661 104750 54660 104750 50425 104750 50425 104751 54660 104751 52424 104751 50425 104752 52424 104752 50423 104752 50423 104753 52424 104753 52425 104753 50423 104754 52425 104754 50422 104754 50422 104755 52425 104755 54663 104755 50422 104756 54663 104756 50420 104756 50420 104757 54663 104757 54665 104757 50420 104758 54665 104758 52426 104758 52426 104759 54665 104759 54667 104759 52426 104760 54667 104760 50416 104760 50416 104761 54667 104761 52428 104761 52372 104762 52427 104762 54668 104762 54668 104763 52427 104763 50418 104763 54668 104764 50418 104764 52428 104764 52428 104765 50418 104765 52429 104765 52428 104766 52429 104766 50416 104766 52378 104767 52430 104767 52431 104767 52437 104768 52435 104768 50411 104768 52378 104769 52431 104769 52377 104769 52377 104770 52431 104770 52432 104770 52377 104771 52432 104771 52375 104771 52375 104772 52432 104772 52433 104772 52375 104773 52433 104773 52434 104773 52434 104774 52433 104774 52436 104774 52434 104775 52436 104775 52435 104775 52435 104776 52436 104776 50412 104776 52435 104777 50412 104777 50411 104777 50411 104778 50410 104778 52437 104778 52437 104779 50410 104779 52438 104779 52437 104780 52438 104780 52374 104780 52438 104781 52439 104781 52374 104781 52374 104782 52439 104782 52440 104782 52374 104783 52440 104783 52441 104783 52441 104784 52440 104784 50405 104784 52441 104785 50405 104785 52373 104785 52373 104786 50405 104786 52442 104786 52373 104787 52442 104787 52443 104787 52443 104788 52442 104788 52444 104788 52443 104789 52444 104789 52372 104789 52372 104790 52444 104790 52427 104790 52445 104791 52430 104791 52378 104791 52445 104792 52378 104792 52446 104792 52446 104793 52378 104793 52447 104793 52447 104794 52378 104794 52366 104794 52447 104795 52366 104795 50399 104795 52449 104796 52448 104796 52465 104796 52448 104797 52449 104797 52450 104797 52451 104798 52452 104798 52453 104798 52453 104799 52452 104799 52350 104799 52453 104800 52350 104800 52335 104800 52463 104801 52454 104801 52462 104801 52462 104802 52454 104802 53143 104802 52462 104803 53143 104803 52455 104803 52325 104804 52456 104804 52457 104804 52465 104805 52325 104805 52449 104805 52449 104806 52325 104806 52457 104806 52449 104807 52457 104807 52450 104807 52450 104808 52457 104808 52322 104808 52450 104809 52322 104809 52467 104809 52464 104810 52327 104810 52465 104810 52465 104811 52327 104811 52326 104811 52465 104812 52326 104812 52325 104812 52451 104813 52330 104813 52458 104813 52458 104814 52330 104814 52329 104814 52458 104815 52329 104815 52464 104815 52464 104816 52329 104816 52459 104816 52464 104817 52459 104817 52327 104817 52335 104818 52333 104818 52453 104818 52453 104819 52333 104819 52460 104819 52453 104820 52460 104820 52451 104820 52451 104821 52460 104821 52461 104821 52451 104822 52461 104822 52330 104822 53143 104823 52452 104823 52455 104823 52455 104824 52452 104824 52451 104824 52455 104825 52451 104825 52462 104825 52462 104826 52451 104826 52458 104826 52462 104827 52458 104827 52463 104827 52463 104828 52458 104828 52464 104828 52463 104829 52464 104829 53136 104829 53136 104830 52464 104830 52465 104830 53136 104831 52465 104831 53127 104831 53127 104832 52465 104832 52448 104832 53127 104833 52448 104833 53128 104833 53128 104834 52448 104834 52450 104834 53128 104835 52450 104835 53082 104835 53082 104836 52450 104836 52467 104836 53082 104837 52467 104837 52466 104837 52466 104838 52467 104838 52320 104838 52466 104839 52320 104839 52318 104839 50273 104840 52468 104840 52469 104840 50292 104841 50294 104841 52470 104841 52470 104842 50294 104842 52471 104842 52470 104843 52471 104843 52469 104843 52469 104844 52471 104844 52472 104844 52469 104845 52472 104845 50273 104845 50292 104846 52470 104846 50289 104846 50289 104847 52470 104847 52473 104847 50289 104848 52473 104848 52475 104848 52475 104849 52473 104849 52474 104849 52475 104850 52474 104850 52476 104850 52476 104851 52474 104851 52336 104851 52476 104852 52336 104852 52477 104852 52336 104853 52340 104853 52477 104853 52477 104854 52340 104854 52338 104854 52477 104855 52338 104855 52480 104855 52480 104856 52338 104856 52478 104856 52480 104857 52478 104857 52339 104857 52339 104858 52479 104858 52480 104858 52480 104859 52479 104859 52481 104859 52480 104860 52481 104860 52482 104860 52482 104861 52481 104861 52337 104861 52482 104862 52337 104862 52483 104862 52468 104863 50273 104863 52334 104863 52334 104864 50273 104864 52484 104864 52334 104865 52484 104865 52332 104865 52484 104866 50274 104866 52332 104866 52332 104867 50274 104867 52485 104867 52332 104868 52485 104868 52486 104868 52486 104869 52485 104869 52487 104869 52486 104870 52487 104870 52331 104870 52331 104871 52487 104871 50280 104871 52331 104872 50280 104872 52489 104872 52488 104873 52491 104873 50283 104873 50280 104874 50279 104874 52489 104874 52489 104875 50279 104875 50276 104875 52489 104876 50276 104876 52328 104876 52328 104877 50276 104877 50281 104877 52328 104878 50281 104878 52490 104878 52490 104879 50281 104879 52492 104879 52490 104880 52492 104880 52491 104880 52491 104881 52492 104881 52493 104881 52491 104882 52493 104882 50283 104882 50285 104883 52324 104883 52494 104883 52494 104884 52324 104884 52488 104884 52494 104885 52488 104885 52495 104885 52495 104886 52488 104886 50283 104886 52324 104887 50285 104887 52498 104887 53162 104888 53161 104888 52496 104888 52496 104889 53161 104889 52324 104889 52496 104890 52324 104890 52497 104890 52497 104891 52324 104891 52498 104891 53091 104892 52500 104892 52499 104892 52499 104893 52500 104893 52502 104893 52504 104894 52501 104894 52502 104894 52502 104895 52501 104895 53078 104895 52502 104896 53078 104896 52499 104896 52505 104897 52503 104897 52504 104897 52504 104898 52503 104898 53092 104898 52504 104899 53092 104899 52501 104899 53061 104900 53059 104900 52913 104900 52913 104901 53059 104901 53074 104901 52913 104902 53074 104902 52505 104902 52505 104903 53074 104903 53058 104903 52505 104904 53058 104904 52503 104904 52500 104905 52598 104905 52502 104905 52502 104906 52598 104906 52511 104906 52502 104907 52511 104907 52504 104907 52504 104908 52511 104908 52508 104908 52504 104909 52508 104909 52505 104909 52505 104910 52508 104910 52507 104910 52505 104911 52507 104911 52913 104911 52913 104912 52507 104912 52506 104912 52506 104913 52507 104913 52601 104913 52601 104914 52507 104914 52508 104914 52601 104915 52508 104915 52603 104915 52603 104916 52508 104916 52509 104916 52509 104917 52508 104917 52511 104917 52509 104918 52511 104918 52510 104918 52510 104919 52511 104919 52598 104919 52510 104920 52598 104920 52512 104920 52512 104921 52598 104921 52514 104921 52514 104922 52598 104922 52513 104922 52514 104923 52513 104923 52619 104923 52619 104924 52513 104924 52515 104924 52619 104925 52515 104925 52618 104925 52516 104926 52529 104926 52530 104926 52517 104927 52529 104927 52519 104927 52529 104928 52517 104928 52617 104928 52518 104929 52519 104929 52529 104929 52616 104930 52615 104930 52529 104930 52613 104931 52520 104931 52529 104931 52525 104932 52521 104932 52526 104932 52526 104933 52521 104933 52612 104933 52526 104934 52612 104934 52522 104934 52522 104935 52612 104935 52524 104935 52522 104936 52524 104936 52523 104936 52523 104937 52524 104937 52607 104937 52523 104938 52607 104938 52515 104938 52525 104939 52526 104939 52520 104939 52520 104940 52526 104940 52529 104940 52615 104941 52613 104941 52529 104941 52617 104942 52616 104942 52529 104942 52516 104943 52518 104943 52529 104943 52536 104944 52526 104944 52538 104944 52538 104945 52526 104945 52522 104945 52538 104946 52522 104946 52539 104946 52539 104947 52522 104947 52523 104947 52539 104948 52523 104948 52527 104948 52527 104949 52523 104949 52515 104949 52536 104950 52528 104950 52526 104950 52526 104951 52528 104951 52875 104951 52526 104952 52875 104952 52529 104952 52529 104953 52875 104953 52530 104953 52537 104954 52531 104954 52599 104954 52535 104955 52534 104955 53103 104955 53073 104956 52532 104956 52533 104956 52533 104957 52532 104957 52535 104957 52533 104958 52535 104958 53102 104958 53102 104959 52535 104959 53103 104959 52599 104960 53123 104960 52537 104960 52537 104961 53123 104961 53122 104961 52537 104962 53122 104962 52534 104962 52534 104963 53122 104963 53104 104963 52534 104964 53104 104964 53103 104964 52532 104965 52528 104965 52535 104965 52535 104966 52528 104966 52536 104966 52535 104967 52536 104967 52534 104967 52534 104968 52536 104968 52538 104968 52534 104969 52538 104969 52537 104969 52537 104970 52538 104970 52539 104970 52537 104971 52539 104971 52531 104971 52531 104972 52539 104972 52527 104972 52540 104973 52549 104973 52541 104973 52541 104974 52549 104974 52782 104974 52541 104975 52782 104975 53064 104975 53064 104976 52782 104976 53035 104976 53087 104977 52571 104977 52542 104977 52542 104978 52571 104978 52543 104978 52544 104979 53093 104979 52543 104979 52543 104980 53093 104980 53088 104980 52543 104981 53088 104981 52542 104981 52540 104982 53053 104982 52549 104982 52549 104983 53053 104983 52545 104983 52549 104984 52545 104984 52544 104984 52544 104985 52545 104985 52546 104985 52544 104986 52546 104986 53093 104986 52571 104987 52573 104987 52543 104987 52543 104988 52573 104988 52547 104988 52543 104989 52547 104989 52544 104989 52544 104990 52547 104990 52548 104990 52544 104991 52548 104991 52549 104991 52549 104992 52548 104992 52552 104992 52549 104993 52552 104993 52782 104993 52782 104994 52552 104994 52784 104994 52553 104995 52784 104995 52552 104995 52573 104996 52555 104996 52547 104996 52547 104997 52555 104997 52550 104997 52547 104998 52550 104998 52548 104998 52548 104999 52550 104999 52551 104999 52548 105000 52551 105000 52552 105000 52552 105001 52551 105001 54658 105001 52552 105002 54658 105002 52553 105002 52553 105003 54658 105003 54653 105003 52553 105004 54653 105004 52785 105004 52554 105005 52555 105005 52582 105005 52582 105006 52555 105006 52597 105006 52597 105007 52555 105007 52556 105007 52597 105008 52556 105008 52596 105008 52596 105009 52556 105009 52559 105009 52596 105010 52559 105010 52594 105010 52593 105011 52557 105011 52558 105011 52558 105012 52557 105012 52590 105012 52558 105013 52590 105013 52568 105013 52568 105014 52590 105014 52585 105014 52568 105015 52585 105015 52569 105015 52569 105016 52585 105016 52586 105016 52569 105017 52586 105017 52559 105017 52559 105018 52586 105018 52594 105018 52565 105019 52560 105019 52567 105019 52563 105020 52564 105020 52879 105020 52879 105021 52564 105021 52561 105021 52879 105022 52561 105022 53063 105022 52567 105023 52560 105023 52562 105023 52560 105024 53085 105024 52562 105024 52562 105025 53085 105025 53106 105025 52562 105026 53106 105026 52563 105026 52563 105027 53106 105027 53105 105027 52563 105028 53105 105028 52564 105028 52565 105029 52567 105029 52566 105029 52566 105030 52567 105030 52570 105030 52566 105031 52570 105031 52572 105031 52879 105032 52593 105032 52563 105032 52563 105033 52593 105033 52558 105033 52563 105034 52558 105034 52562 105034 52562 105035 52558 105035 52568 105035 52562 105036 52568 105036 52567 105036 52567 105037 52568 105037 52569 105037 52567 105038 52569 105038 52570 105038 52570 105039 52569 105039 52559 105039 52556 105040 52555 105040 52573 105040 52556 105041 52573 105041 52559 105041 53087 105042 53086 105042 52571 105042 52571 105043 53086 105043 52572 105043 52571 105044 52572 105044 52573 105044 52573 105045 52572 105045 52570 105045 52573 105046 52570 105046 52559 105046 52574 105047 52577 105047 52575 105047 52575 105048 52577 105048 50351 105048 52575 105049 50351 105049 52785 105049 52574 105050 54654 105050 52577 105050 52577 105051 54654 105051 54652 105051 52577 105052 54652 105052 54655 105052 54655 105053 52576 105053 52577 105053 52577 105054 52576 105054 52578 105054 52577 105055 52578 105055 52579 105055 52579 105056 54656 105056 52577 105056 52577 105057 54656 105057 54657 105057 52577 105058 54657 105058 50353 105058 50353 105059 54657 105059 52580 105059 50353 105060 52580 105060 50355 105060 50355 105061 52580 105061 50356 105061 50356 105062 52580 105062 54659 105062 50356 105063 54659 105063 52581 105063 52581 105064 54659 105064 50359 105064 50359 105065 54659 105065 52583 105065 50359 105066 52583 105066 50362 105066 52582 105067 50365 105067 52554 105067 52554 105068 50365 105068 50364 105068 52554 105069 50364 105069 52583 105069 52583 105070 50364 105070 50363 105070 52583 105071 50363 105071 50362 105071 52595 105072 52594 105072 52588 105072 52588 105073 52594 105073 52586 105073 52590 105074 52591 105074 52585 105074 52585 105075 52591 105075 52584 105075 52585 105076 52584 105076 52586 105076 52586 105077 52584 105077 52587 105077 52586 105078 52587 105078 52588 105078 52592 105079 50370 105079 52557 105079 52557 105080 50370 105080 52589 105080 52557 105081 52589 105081 52590 105081 52590 105082 52589 105082 50371 105082 52590 105083 50371 105083 52591 105083 52592 105084 52557 105084 50369 105084 50369 105085 52557 105085 52593 105085 50369 105086 52593 105086 50377 105086 52594 105087 52595 105087 52596 105087 52596 105088 52595 105088 50367 105088 52596 105089 50367 105089 52597 105089 52597 105090 50367 105090 50365 105090 52597 105091 50365 105091 52582 105091 52513 105092 52598 105092 52500 105092 52500 105093 53091 105093 53060 105093 52515 105094 52513 105094 52527 105094 52527 105095 52513 105095 52500 105095 52527 105096 52500 105096 52531 105096 52531 105097 52500 105097 53060 105097 52531 105098 53060 105098 52599 105098 52914 105099 52506 105099 50307 105099 50307 105100 52506 105100 52601 105100 50307 105101 52601 105101 50306 105101 50306 105102 52601 105102 50303 105102 52603 105103 52600 105103 52601 105103 52601 105104 52600 105104 50304 105104 52601 105105 50304 105105 50303 105105 52509 105106 52602 105106 52603 105106 52603 105107 52602 105107 52604 105107 52603 105108 52604 105108 52600 105108 52512 105109 52620 105109 52510 105109 52510 105110 52620 105110 52605 105110 52510 105111 52605 105111 52509 105111 52509 105112 52605 105112 52606 105112 52509 105113 52606 105113 52602 105113 52609 105114 52608 105114 52607 105114 52607 105115 52608 105115 52618 105115 52609 105116 52607 105116 50319 105116 50319 105117 52607 105117 52524 105117 50319 105118 52524 105118 52610 105118 52610 105119 52524 105119 52611 105119 52611 105120 52524 105120 52612 105120 52611 105121 52612 105121 50313 105121 50313 105122 52612 105122 50314 105122 50314 105123 52612 105123 52521 105123 50314 105124 52521 105124 50315 105124 50315 105125 52521 105125 50316 105125 50316 105126 52521 105126 52525 105126 50316 105127 52525 105127 50318 105127 50318 105128 52525 105128 52520 105128 50318 105129 52520 105129 52614 105129 52520 105130 52613 105130 52614 105130 52614 105131 52613 105131 52615 105131 52614 105132 52615 105132 52616 105132 52616 105133 52617 105133 52614 105133 52614 105134 52617 105134 52517 105134 52614 105135 52517 105135 52519 105135 52519 105136 52518 105136 52614 105136 52614 105137 52518 105137 52516 105137 52614 105138 52516 105138 52530 105138 52618 105139 52608 105139 52619 105139 52619 105140 52608 105140 50309 105140 52619 105141 50309 105141 52514 105141 52514 105142 50309 105142 52620 105142 52514 105143 52620 105143 52512 105143 52667 105144 52665 105144 52625 105144 52625 105145 52665 105145 52664 105145 52625 105146 52664 105146 52623 105146 52623 105147 52664 105147 52663 105147 52623 105148 52663 105148 52621 105148 52621 105149 52663 105149 52662 105149 52621 105150 52662 105150 52627 105150 52624 105151 52667 105151 52625 105151 52627 105152 52628 105152 52621 105152 52621 105153 52628 105153 52622 105153 52621 105154 52622 105154 52623 105154 52622 105155 52631 105155 52623 105155 52623 105156 52631 105156 52633 105156 52623 105157 52633 105157 52625 105157 52637 105158 52624 105158 52636 105158 52636 105159 52624 105159 52625 105159 52636 105160 52625 105160 52634 105160 52634 105161 52625 105161 52633 105161 52662 105162 52626 105162 52627 105162 52627 105163 52626 105163 52655 105163 52622 105164 52628 105164 52658 105164 52658 105165 52629 105165 52622 105165 52622 105166 52629 105166 52630 105166 52622 105167 52630 105167 52631 105167 52631 105168 52630 105168 52632 105168 52631 105169 52632 105169 52633 105169 52633 105170 52632 105170 53098 105170 52633 105171 53098 105171 52634 105171 52634 105172 53098 105172 52635 105172 52634 105173 52635 105173 52636 105173 52636 105174 52635 105174 53068 105174 52636 105175 53068 105175 52637 105175 52637 105176 53068 105176 53069 105176 52655 105177 52626 105177 52638 105177 52638 105178 52626 105178 52671 105178 52638 105179 52671 105179 54651 105179 52639 105180 52647 105180 52651 105180 52657 105181 54651 105181 52640 105181 52640 105182 54651 105182 52641 105182 52640 105183 52641 105183 52642 105183 52642 105184 52641 105184 52643 105184 52642 105185 52643 105185 52651 105185 52651 105186 52643 105186 52644 105186 52651 105187 52644 105187 52639 105187 52639 105188 52644 105188 54647 105188 52645 105189 52651 105189 53077 105189 53077 105190 52651 105190 52647 105190 53077 105191 52647 105191 52646 105191 52646 105192 52647 105192 52648 105192 52649 105193 52657 105193 53100 105193 53100 105194 52657 105194 52640 105194 52642 105195 53118 105195 52640 105195 52640 105196 53118 105196 53101 105196 52640 105197 53101 105197 53100 105197 52645 105198 53057 105198 52651 105198 52651 105199 53057 105199 52650 105199 52651 105200 52650 105200 52642 105200 52642 105201 52650 105201 52652 105201 52642 105202 52652 105202 53118 105202 52657 105203 52653 105203 54651 105203 54651 105204 52653 105204 52654 105204 54651 105205 52654 105205 52638 105205 52655 105206 52638 105206 52660 105206 52660 105207 52638 105207 52654 105207 52660 105208 52654 105208 52656 105208 52656 105209 52654 105209 52653 105209 52656 105210 52653 105210 53070 105210 53070 105211 52653 105211 52657 105211 53070 105212 52657 105212 52649 105212 52659 105213 52658 105213 52628 105213 52659 105214 52628 105214 52656 105214 52656 105215 52628 105215 52660 105215 52660 105216 52628 105216 52627 105216 52660 105217 52627 105217 52655 105217 50339 105218 52661 105218 52664 105218 50347 105219 52662 105219 50346 105219 50346 105220 52662 105220 50345 105220 50345 105221 52662 105221 52663 105221 50345 105222 52663 105222 50343 105222 50343 105223 52663 105223 52664 105223 50343 105224 52664 105224 50341 105224 50341 105225 52664 105225 52661 105225 50339 105226 52664 105226 50338 105226 50338 105227 52664 105227 52665 105227 50338 105228 52665 105228 52666 105228 52666 105229 52665 105229 52667 105229 52666 105230 52667 105230 50349 105230 52662 105231 50347 105231 52626 105231 52626 105232 50347 105232 52672 105232 52626 105233 52672 105233 52671 105233 52830 105234 54647 105234 52668 105234 52668 105235 54647 105235 54648 105235 52668 105236 54648 105236 50331 105236 50331 105237 54648 105237 52669 105237 52669 105238 54648 105238 54649 105238 52669 105239 54649 105239 50330 105239 54650 105240 52670 105240 54649 105240 54649 105241 52670 105241 50328 105241 54649 105242 50328 105242 50330 105242 52671 105243 52672 105243 52673 105243 52671 105244 52673 105244 54650 105244 54650 105245 52673 105245 50326 105245 54650 105246 50326 105246 52670 105246 52674 105247 52081 105247 52091 105247 52674 105248 52091 105248 52675 105248 52675 105249 52091 105249 52676 105249 52675 105250 52676 105250 52043 105250 52043 105251 52676 105251 52677 105251 52043 105252 52677 105252 52041 105252 52041 105253 52677 105253 52678 105253 52041 105254 52678 105254 52679 105254 52680 105255 52681 105255 52682 105255 52682 105256 52681 105256 52934 105256 52682 105257 52934 105257 52063 105257 52679 105258 52678 105258 52065 105258 52065 105259 52678 105259 52073 105259 52065 105260 52073 105260 52683 105260 52683 105261 52073 105261 52074 105261 52683 105262 52074 105262 52684 105262 52684 105263 52074 105263 52685 105263 52684 105264 52685 105264 52680 105264 52680 105265 52685 105265 52686 105265 52680 105266 52686 105266 52681 105266 52687 105267 52688 105267 52689 105267 52687 105268 52689 105268 52128 105268 52128 105269 52689 105269 52690 105269 52128 105270 52690 105270 52127 105270 52127 105271 52690 105271 52691 105271 52127 105272 52691 105272 52693 105272 52693 105273 52691 105273 52692 105273 52693 105274 52692 105274 52889 105274 52688 105275 52687 105275 52694 105275 52694 105276 52687 105276 52105 105276 52694 105277 52105 105277 52165 105277 52165 105278 52105 105278 52695 105278 52165 105279 52695 105279 52164 105279 52164 105280 52695 105280 52696 105280 52164 105281 52696 105281 52163 105281 52696 105282 52697 105282 52163 105282 52163 105283 52697 105283 52698 105283 52163 105284 52698 105284 52161 105284 52161 105285 52698 105285 52895 105285 52161 105286 52895 105286 52882 105286 52699 105287 54646 105287 52700 105287 52700 105288 54646 105288 52912 105288 52700 105289 52912 105289 52701 105289 52701 105290 52912 105290 52702 105290 52701 105291 52702 105291 52710 105291 52710 105292 52702 105292 52703 105292 52710 105293 52703 105293 52711 105293 52711 105294 52703 105294 52911 105294 52711 105295 52911 105295 52705 105295 52705 105296 52911 105296 52704 105296 52705 105297 52704 105297 52706 105297 52706 105298 52704 105298 54641 105298 54639 105299 52699 105299 52707 105299 52707 105300 52699 105300 52700 105300 52707 105301 52700 105301 54179 105301 54179 105302 52700 105302 52701 105302 54179 105303 52701 105303 52708 105303 52708 105304 52701 105304 52710 105304 52708 105305 52710 105305 52709 105305 52709 105306 52710 105306 52711 105306 52709 105307 52711 105307 54180 105307 54180 105308 52711 105308 52705 105308 54180 105309 52705 105309 54174 105309 54174 105310 52705 105310 52706 105310 54628 105311 52712 105311 52719 105311 52719 105312 52712 105312 52923 105312 52719 105313 52923 105313 52720 105313 52720 105314 52923 105314 52714 105314 52720 105315 52714 105315 52713 105315 52713 105316 52714 105316 52715 105316 52713 105317 52715 105317 52716 105317 52716 105318 52715 105318 52717 105318 52716 105319 52717 105319 52723 105319 52723 105320 52717 105320 52718 105320 52723 105321 52718 105321 52724 105321 52724 105322 52718 105322 52929 105322 54627 105323 54628 105323 54165 105323 54165 105324 54628 105324 52719 105324 54165 105325 52719 105325 54171 105325 54171 105326 52719 105326 52720 105326 54171 105327 52720 105327 52721 105327 52721 105328 52720 105328 52713 105328 52721 105329 52713 105329 52722 105329 52722 105330 52713 105330 52716 105330 52722 105331 52716 105331 54162 105331 54162 105332 52716 105332 52723 105332 54162 105333 52723 105333 54163 105333 54163 105334 52723 105334 52724 105334 52725 105335 52735 105335 52730 105335 52737 105336 52726 105336 52727 105336 52747 105337 52728 105337 52745 105337 52745 105338 52728 105338 52749 105338 52745 105339 52749 105339 52737 105339 52737 105340 52749 105340 52725 105340 52737 105341 52725 105341 52729 105341 52729 105342 52725 105342 52730 105342 52733 105343 52731 105343 52744 105343 52727 105344 52741 105344 52737 105344 52737 105345 52741 105345 52732 105345 52737 105346 52732 105346 52745 105346 52745 105347 52732 105347 52733 105347 52745 105348 52733 105348 52734 105348 52734 105349 52733 105349 52744 105349 50592 105350 52725 105350 50593 105350 50593 105351 52725 105351 52749 105351 52725 105352 50592 105352 52735 105352 52735 105353 50592 105353 50594 105353 52735 105354 50594 105354 52730 105354 52730 105355 50594 105355 50595 105355 52730 105356 50595 105356 52729 105356 52729 105357 50595 105357 52736 105357 52738 105358 52737 105358 52736 105358 52736 105359 52737 105359 52729 105359 52737 105360 52738 105360 52739 105360 52737 105361 52739 105361 52726 105361 52726 105362 52739 105362 52740 105362 52726 105363 52740 105363 52727 105363 52727 105364 52740 105364 50600 105364 52727 105365 50600 105365 52741 105365 52741 105366 50600 105366 52742 105366 52741 105367 52742 105367 52732 105367 50604 105368 52733 105368 52742 105368 52742 105369 52733 105369 52732 105369 52733 105370 50604 105370 52731 105370 52731 105371 50604 105371 52743 105371 52731 105372 52743 105372 52744 105372 52744 105373 52743 105373 50602 105373 52744 105374 50602 105374 52734 105374 52734 105375 50602 105375 50603 105375 52746 105376 52745 105376 50603 105376 50603 105377 52745 105377 52734 105377 52745 105378 52746 105378 52747 105378 52747 105379 52746 105379 52748 105379 52747 105380 52748 105380 52728 105380 52728 105381 52748 105381 52750 105381 52728 105382 52750 105382 52749 105382 52749 105383 52750 105383 50593 105383 52769 105384 52773 105384 52772 105384 52759 105385 52761 105385 52766 105385 52759 105386 52766 105386 52752 105386 52776 105387 52777 105387 52751 105387 52751 105388 52777 105388 52754 105388 52751 105389 52754 105389 52772 105389 52772 105390 52754 105390 52755 105390 52772 105391 52755 105391 52769 105391 52769 105392 52755 105392 52768 105392 52768 105393 52755 105393 52766 105393 52766 105394 52755 105394 52757 105394 52766 105395 52757 105395 52752 105395 52764 105396 52765 105396 52753 105396 52753 105397 52765 105397 52766 105397 52753 105398 52766 105398 52762 105398 52762 105399 52766 105399 52761 105399 52756 105400 52755 105400 50562 105400 50562 105401 52755 105401 52754 105401 52755 105402 52756 105402 52757 105402 52757 105403 52756 105403 50556 105403 52757 105404 50556 105404 52752 105404 52752 105405 50556 105405 52758 105405 52752 105406 52758 105406 52759 105406 52759 105407 52758 105407 52760 105407 52759 105408 52760 105408 52761 105408 52761 105409 52760 105409 50563 105409 50564 105410 52762 105410 50563 105410 50563 105411 52762 105411 52761 105411 52762 105412 50564 105412 52763 105412 52762 105413 52763 105413 52753 105413 52753 105414 52763 105414 50567 105414 52753 105415 50567 105415 52764 105415 52764 105416 50567 105416 50568 105416 52764 105417 50568 105417 52765 105417 52765 105418 50568 105418 50566 105418 52765 105419 50566 105419 52766 105419 52767 105420 52768 105420 50566 105420 50566 105421 52768 105421 52766 105421 52767 105422 50572 105422 52768 105422 52768 105423 50572 105423 52769 105423 50572 105424 50574 105424 52769 105424 52769 105425 50574 105425 50571 105425 52769 105426 50571 105426 52773 105426 52770 105427 52772 105427 52771 105427 52771 105428 52772 105428 52773 105428 52771 105429 52773 105429 52774 105429 52774 105430 52773 105430 50571 105430 52775 105431 52751 105431 52770 105431 52770 105432 52751 105432 52772 105432 52751 105433 52775 105433 52776 105433 52776 105434 52775 105434 50559 105434 52776 105435 50559 105435 52777 105435 52777 105436 50559 105436 50560 105436 52777 105437 50560 105437 52754 105437 52754 105438 50560 105438 50562 105438 52784 105439 50591 105439 52781 105439 52778 105440 53035 105440 52782 105440 52779 105441 50581 105441 54161 105441 54161 105442 53032 105442 52779 105442 52779 105443 53032 105443 52780 105443 52779 105444 52780 105444 50586 105444 50586 105445 52780 105445 52778 105445 50586 105446 52778 105446 52781 105446 52781 105447 52778 105447 52782 105447 52781 105448 52782 105448 52784 105448 52783 105449 50590 105449 50591 105449 50591 105450 52784 105450 52783 105450 52783 105451 52784 105451 52553 105451 52783 105452 52553 105452 50350 105452 50350 105453 52553 105453 52785 105453 50350 105454 52785 105454 50351 105454 54228 105455 52786 105455 50583 105455 54228 105456 50583 105456 54229 105456 54229 105457 50583 105457 50589 105457 54229 105458 50589 105458 52788 105458 50588 105459 54234 105459 50589 105459 50589 105460 54234 105460 52787 105460 50589 105461 52787 105461 52788 105461 52791 105462 54231 105462 50588 105462 50588 105463 54231 105463 54233 105463 50588 105464 54233 105464 54234 105464 50352 105465 50590 105465 52789 105465 52789 105466 50590 105466 52783 105466 50352 105467 52790 105467 50590 105467 50590 105468 52790 105468 50354 105468 50590 105469 50354 105469 52791 105469 52791 105470 50354 105470 54230 105470 52791 105471 54230 105471 54231 105471 50583 105472 52786 105472 50582 105472 50582 105473 52786 105473 52821 105473 50565 105474 52812 105474 52792 105474 52792 105475 52812 105475 52793 105475 52792 105476 52793 105476 50561 105476 50561 105477 52793 105477 50578 105477 50561 105478 50578 105478 52794 105478 52794 105479 50578 105479 52795 105479 52794 105480 52795 105480 52796 105480 52796 105481 52795 105481 50579 105481 52796 105482 50579 105482 50555 105482 50555 105483 50579 105483 50584 105483 50555 105484 50584 105484 50557 105484 50557 105485 50584 105485 50585 105485 50557 105486 50585 105486 52797 105486 52797 105487 50585 105487 52798 105487 52797 105488 52798 105488 52799 105488 52799 105489 52798 105489 52800 105489 52799 105490 52800 105490 50558 105490 50558 105491 52800 105491 52801 105491 50558 105492 52801 105492 52802 105492 52802 105493 52801 105493 52804 105493 52802 105494 52804 105494 52803 105494 52803 105495 52804 105495 50587 105495 52803 105496 50587 105496 50569 105496 50569 105497 50587 105497 52805 105497 50569 105498 52805 105498 50575 105498 50575 105499 52805 105499 52806 105499 50575 105500 52806 105500 52807 105500 52807 105501 52806 105501 50580 105501 52807 105502 50580 105502 50573 105502 50573 105503 50580 105503 52808 105503 50573 105504 52808 105504 52810 105504 52810 105505 52808 105505 52809 105505 52810 105506 52809 105506 50570 105506 50570 105507 52809 105507 52811 105507 50570 105508 52811 105508 50565 105508 50565 105509 52811 105509 52812 105509 52813 105510 50576 105510 52637 105510 52815 105511 54160 105511 52814 105511 52814 105512 52816 105512 52815 105512 52815 105513 52816 105513 50577 105513 52815 105514 50577 105514 53050 105514 53050 105515 50577 105515 52813 105515 53050 105516 52813 105516 53099 105516 53099 105517 52813 105517 52637 105517 53099 105518 52637 105518 53069 105518 50336 105519 52817 105519 54207 105519 54207 105520 52817 105520 52818 105520 54207 105521 52818 105521 54208 105521 50336 105522 50348 105522 52817 105522 52817 105523 50348 105523 52819 105523 52817 105524 52819 105524 52820 105524 52823 105525 52825 105525 52818 105525 52818 105526 52825 105526 54235 105526 52818 105527 54235 105527 54208 105527 52822 105528 50582 105528 52821 105528 52821 105529 54227 105529 52822 105529 52822 105530 54227 105530 54226 105530 52822 105531 54226 105531 52823 105531 52823 105532 54226 105532 52824 105532 52823 105533 52824 105533 52825 105533 52826 105534 50349 105534 52667 105534 52637 105535 50576 105535 52820 105535 52820 105536 50576 105536 52817 105536 52826 105537 52667 105537 52820 105537 52820 105538 52667 105538 52624 105538 52820 105539 52624 105539 52637 105539 52647 105540 50619 105540 50613 105540 50612 105541 50611 105541 52827 105541 52827 105542 53052 105542 50612 105542 50612 105543 53052 105543 53051 105543 50612 105544 53051 105544 52828 105544 52828 105545 53051 105545 52829 105545 52828 105546 52829 105546 50613 105546 50613 105547 52829 105547 52648 105547 50613 105548 52648 105548 52647 105548 52833 105549 52834 105549 50619 105549 50619 105550 52647 105550 52833 105550 52833 105551 52647 105551 52639 105551 52833 105552 52639 105552 50323 105552 50323 105553 52639 105553 54647 105553 50323 105554 54647 105554 52830 105554 50618 105555 54217 105555 52835 105555 52835 105556 54217 105556 52831 105556 52835 105557 52831 105557 54215 105557 50617 105558 54220 105558 50618 105558 50618 105559 54220 105559 54219 105559 50618 105560 54219 105560 54217 105560 50615 105561 52832 105561 50617 105561 50617 105562 52832 105562 54221 105562 50617 105563 54221 105563 54220 105563 50322 105564 52834 105564 50324 105564 50324 105565 52834 105565 52833 105565 50322 105566 50332 105566 52834 105566 52834 105567 50332 105567 50333 105567 52834 105568 50333 105568 50615 105568 50615 105569 50333 105569 54211 105569 50615 105570 54211 105570 52832 105570 52835 105571 54215 105571 52874 105571 52874 105572 54215 105572 52836 105572 52857 105573 50609 105573 52837 105573 52837 105574 50609 105574 52838 105574 52837 105575 52838 105575 50597 105575 50597 105576 52838 105576 52839 105576 50597 105577 52839 105577 52840 105577 52840 105578 52839 105578 50605 105578 52840 105579 50605 105579 52842 105579 52842 105580 50605 105580 52841 105580 52842 105581 52841 105581 52843 105581 52843 105582 52841 105582 50610 105582 52843 105583 50610 105583 52844 105583 52844 105584 50610 105584 52845 105584 52844 105585 52845 105585 50596 105585 50596 105586 52845 105586 52846 105586 50596 105587 52846 105587 52847 105587 52847 105588 52846 105588 52848 105588 52847 105589 52848 105589 50598 105589 50598 105590 52848 105590 50614 105590 50598 105591 50614 105591 52849 105591 52849 105592 50614 105592 52850 105592 52849 105593 52850 105593 52851 105593 52851 105594 52850 105594 50616 105594 52851 105595 50616 105595 50599 105595 50599 105596 50616 105596 52852 105596 50599 105597 52852 105597 50601 105597 50601 105598 52852 105598 52853 105598 50601 105599 52853 105599 52854 105599 52854 105600 52853 105600 52855 105600 52854 105601 52855 105601 52856 105601 52856 105602 52855 105602 50606 105602 52856 105603 50606 105603 52857 105603 52857 105604 50606 105604 50609 105604 52532 105605 52863 105605 52528 105605 52528 105606 52863 105606 52877 105606 53036 105607 52858 105607 52859 105607 52859 105608 52860 105608 53036 105608 53036 105609 52860 105609 52861 105609 53036 105610 52861 105610 52862 105610 52862 105611 52861 105611 52863 105611 52862 105612 52863 105612 53072 105612 53072 105613 52863 105613 52532 105613 53072 105614 52532 105614 53073 105614 52876 105615 50608 105615 50311 105615 50311 105616 50608 105616 52864 105616 52865 105617 52866 105617 50607 105617 50607 105618 52866 105618 52867 105618 50607 105619 52867 105619 50608 105619 50608 105620 52867 105620 52868 105620 50608 105621 52868 105621 52864 105621 52865 105622 50607 105622 52869 105622 52869 105623 50607 105623 52870 105623 52869 105624 52870 105624 52871 105624 52871 105625 52870 105625 52873 105625 52871 105626 52873 105626 52872 105626 52872 105627 52873 105627 54216 105627 54216 105628 52873 105628 52874 105628 54216 105629 52874 105629 52836 105629 52877 105630 50608 105630 52876 105630 52614 105631 52530 105631 50321 105631 50321 105632 52530 105632 52875 105632 50321 105633 52875 105633 52876 105633 52876 105634 52875 105634 52528 105634 52876 105635 52528 105635 52877 105635 52882 105636 52895 105636 52878 105636 52878 105637 52895 105637 50378 105637 53063 105638 52878 105638 52879 105638 52879 105639 52878 105639 50378 105639 52879 105640 50378 105640 52593 105640 52593 105641 50378 105641 50377 105641 52880 105642 52153 105642 52881 105642 52880 105643 52881 105643 53090 105643 53090 105644 52881 105644 52143 105644 53090 105645 52143 105645 52883 105645 52883 105646 52143 105646 52882 105646 52883 105647 52882 105647 52878 105647 52383 105648 52692 105648 52884 105648 53071 105649 52395 105649 52383 105649 52383 105650 52884 105650 53071 105650 53071 105651 52884 105651 52142 105651 53071 105652 52142 105652 52885 105652 52885 105653 52142 105653 52140 105653 52885 105654 52140 105654 52886 105654 52886 105655 52140 105655 54173 105655 52886 105656 54173 105656 54176 105656 52892 105657 54262 105657 52889 105657 52383 105658 52387 105658 52692 105658 52692 105659 52387 105659 52887 105659 52692 105660 52887 105660 52888 105660 52692 105661 52890 105661 52889 105661 52889 105662 52890 105662 52891 105662 52889 105663 52891 105663 52892 105663 52888 105664 52893 105664 52692 105664 52692 105665 52893 105665 52894 105665 52692 105666 52894 105666 52890 105666 50376 105667 50378 105667 52895 105667 50376 105668 52895 105668 50377 105668 50377 105669 52895 105669 52113 105669 50377 105670 52113 105670 52896 105670 54246 105671 52897 105671 52112 105671 52112 105672 52897 105672 52898 105672 52112 105673 52898 105673 52113 105673 52113 105674 52898 105674 52899 105674 52113 105675 52899 105675 52896 105675 52112 105676 52900 105676 54246 105676 54246 105677 52900 105677 52901 105677 54246 105678 52901 105678 54247 105678 54248 105679 52119 105679 52902 105679 52902 105680 52119 105680 52903 105680 52902 105681 52903 105681 52904 105681 52904 105682 52903 105682 52905 105682 52905 105683 52903 105683 52114 105683 52905 105684 52114 105684 52906 105684 52906 105685 52114 105685 52121 105685 52906 105686 52121 105686 52907 105686 52907 105687 52121 105687 52889 105687 52907 105688 52889 105688 54262 105688 52912 105689 54646 105689 52901 105689 52901 105690 54646 105690 54247 105690 54646 105691 52908 105691 54247 105691 54247 105692 52908 105692 54645 105692 54247 105693 54645 105693 54248 105693 54248 105694 54645 105694 52909 105694 52909 105695 54644 105695 54248 105695 54248 105696 54644 105696 54642 105696 54248 105697 54642 105697 52119 105697 52119 105698 54642 105698 54641 105698 52119 105699 54641 105699 52910 105699 52910 105700 54641 105700 52704 105700 52910 105701 52704 105701 52117 105701 52117 105702 52704 105702 52911 105702 52901 105703 52108 105703 52912 105703 52912 105704 52108 105704 52109 105704 52912 105705 52109 105705 52702 105705 52702 105706 52109 105706 52100 105706 52702 105707 52100 105707 52703 105707 52703 105708 52100 105708 52097 105708 52703 105709 52097 105709 52911 105709 52911 105710 52097 105710 52116 105710 52911 105711 52116 105711 52117 105711 53062 105712 53061 105712 52913 105712 52081 105713 52674 105713 50296 105713 50296 105714 52674 105714 53062 105714 53062 105715 52913 105715 50296 105715 50296 105716 52913 105716 52506 105716 50296 105717 52506 105717 52914 105717 52915 105718 52917 105718 54202 105718 52915 105719 54202 105719 52086 105719 52086 105720 54202 105720 52916 105720 52086 105721 52916 105721 52927 105721 52917 105722 52915 105722 52918 105722 52918 105723 52915 105723 52087 105723 52918 105724 52087 105724 50299 105724 52081 105725 50296 105725 52919 105725 52919 105726 52914 105726 52081 105726 52081 105727 52914 105727 52920 105727 52081 105728 52920 105728 52087 105728 52087 105729 52920 105729 52921 105729 52087 105730 52921 105730 50299 105730 54633 105731 52922 105731 52712 105731 52712 105732 52922 105732 52938 105732 52712 105733 52938 105733 52923 105733 54633 105734 52924 105734 52922 105734 52922 105735 52924 105735 52925 105735 52922 105736 52925 105736 52927 105736 52938 105737 52077 105737 52923 105737 52923 105738 52077 105738 52926 105738 52923 105739 52926 105739 52714 105739 52714 105740 52926 105740 52069 105740 52714 105741 52069 105741 52715 105741 52715 105742 52069 105742 52068 105742 52715 105743 52068 105743 52717 105743 52925 105744 54630 105744 52927 105744 52927 105745 54630 105745 52928 105745 52927 105746 52928 105746 52086 105746 52086 105747 52928 105747 52929 105747 52086 105748 52929 105748 52930 105748 52930 105749 52929 105749 52718 105749 52930 105750 52718 105750 52931 105750 52931 105751 52718 105751 52717 105751 52931 105752 52717 105752 52083 105752 52083 105753 52717 105753 52068 105753 52937 105754 54198 105754 52932 105754 52932 105755 54198 105755 52933 105755 52932 105756 52933 105756 52934 105756 52934 105757 52933 105757 52935 105757 52934 105758 52935 105758 54191 105758 52932 105759 52936 105759 52937 105759 52937 105760 52936 105760 52079 105760 52937 105761 52079 105761 52939 105761 52939 105762 52079 105762 52938 105762 52939 105763 52938 105763 52922 105763 52934 105764 54191 105764 52940 105764 52482 105765 52483 105765 52063 105765 52063 105766 52483 105766 52941 105766 52063 105767 52941 105767 52351 105767 52940 105768 52942 105768 52934 105768 52934 105769 52942 105769 50287 105769 52934 105770 50287 105770 52063 105770 52063 105771 50287 105771 50286 105771 52063 105772 50286 105772 52482 105772 52674 105773 52045 105773 53062 105773 53062 105774 52045 105774 52943 105774 52045 105775 52944 105775 52943 105775 52943 105776 52944 105776 52038 105776 52943 105777 52038 105777 53065 105777 54164 105778 53075 105778 52945 105778 52945 105779 53075 105779 53065 105779 52945 105780 53065 105780 52036 105780 52036 105781 53065 105781 52038 105781 52351 105782 53144 105782 53117 105782 54168 105783 52946 105783 52947 105783 54168 105784 52947 105784 53115 105784 53115 105785 52947 105785 52948 105785 53115 105786 52948 105786 53116 105786 53116 105787 52948 105787 52949 105787 53116 105788 52949 105788 53117 105788 53117 105789 52949 105789 52063 105789 53117 105790 52063 105790 52351 105790 52956 105791 52950 105791 52951 105791 52951 105792 52950 105792 52952 105792 52951 105793 52952 105793 50443 105793 50443 105794 52952 105794 52953 105794 52953 105795 52952 105795 52954 105795 52953 105796 52954 105796 50445 105796 50445 105797 52954 105797 50444 105797 50444 105798 52954 105798 52970 105798 50444 105799 52970 105799 52967 105799 50436 105800 52955 105800 52956 105800 52956 105801 52955 105801 52950 105801 50428 105802 52982 105802 52957 105802 52957 105803 52982 105803 52958 105803 52957 105804 52958 105804 50433 105804 50433 105805 52958 105805 52968 105805 50433 105806 52968 105806 50436 105806 50436 105807 52968 105807 52955 105807 50429 105808 52959 105808 50428 105808 50428 105809 52959 105809 52982 105809 50432 105810 52960 105810 50431 105810 50431 105811 52960 105811 52978 105811 50431 105812 52978 105812 52961 105812 52961 105813 52978 105813 52962 105813 52961 105814 52962 105814 50430 105814 50430 105815 52962 105815 52963 105815 50430 105816 52963 105816 50429 105816 50429 105817 52963 105817 52959 105817 50435 105818 52976 105818 50432 105818 50432 105819 52976 105819 52960 105819 52964 105820 52973 105820 50440 105820 50440 105821 52973 105821 52974 105821 50440 105822 52974 105822 52965 105822 52965 105823 52974 105823 52966 105823 52965 105824 52966 105824 50437 105824 50437 105825 52966 105825 52975 105825 50437 105826 52975 105826 50435 105826 50435 105827 52975 105827 52976 105827 52967 105828 52970 105828 52964 105828 52964 105829 52970 105829 52973 105829 50462 105830 50461 105830 52970 105830 52982 105831 52983 105831 52958 105831 52958 105832 52983 105832 50451 105832 52958 105833 50451 105833 52968 105833 52968 105834 50451 105834 50450 105834 52968 105835 50450 105835 52955 105835 52955 105836 50450 105836 50449 105836 52955 105837 50449 105837 52950 105837 50449 105838 52969 105838 52950 105838 52950 105839 52969 105839 50464 105839 52950 105840 50464 105840 52952 105840 52952 105841 50464 105841 50462 105841 52952 105842 50462 105842 52954 105842 52954 105843 50462 105843 52970 105843 50461 105844 50459 105844 52970 105844 52970 105845 50459 105845 52971 105845 52970 105846 52971 105846 52973 105846 52971 105847 50458 105847 52973 105847 52973 105848 50458 105848 52972 105848 52973 105849 52972 105849 52974 105849 52974 105850 52972 105850 50456 105850 52974 105851 50456 105851 52966 105851 52966 105852 50456 105852 52975 105852 52975 105853 50456 105853 50454 105853 52975 105854 50454 105854 52976 105854 52976 105855 50454 105855 52960 105855 52960 105856 50454 105856 52977 105856 52960 105857 52977 105857 52978 105857 52978 105858 52977 105858 52979 105858 52978 105859 52979 105859 52962 105859 50447 105860 52959 105860 52979 105860 52979 105861 52959 105861 52963 105861 52979 105862 52963 105862 52962 105862 50447 105863 52980 105863 52959 105863 52959 105864 52980 105864 52981 105864 52959 105865 52981 105865 52982 105865 52982 105866 52981 105866 50453 105866 52982 105867 50453 105867 52983 105867 52984 105868 52985 105868 52986 105868 52986 105869 52985 105869 52987 105869 53022 105870 50465 105870 52988 105870 52988 105871 50465 105871 50460 105871 52988 105872 50460 105872 52989 105872 52989 105873 50460 105873 52990 105873 52989 105874 52990 105874 52991 105874 52991 105875 52990 105875 50463 105875 52991 105876 50463 105876 52987 105876 52987 105877 50463 105877 52986 105877 50465 105878 53022 105878 52998 105878 52998 105879 53022 105879 52997 105879 52992 105880 52994 105880 52993 105880 52993 105881 52994 105881 50455 105881 52993 105882 50455 105882 52995 105882 52995 105883 50455 105883 50457 105883 52995 105884 50457 105884 53018 105884 53018 105885 50457 105885 52996 105885 53018 105886 52996 105886 52997 105886 52997 105887 52996 105887 52998 105887 52994 105888 52992 105888 50448 105888 50448 105889 52992 105889 53015 105889 53019 105890 52999 105890 53011 105890 53011 105891 52999 105891 53000 105891 53011 105892 53000 105892 53001 105892 53001 105893 53000 105893 50446 105893 53001 105894 50446 105894 53016 105894 53016 105895 50446 105895 53002 105895 53016 105896 53002 105896 53015 105896 53015 105897 53002 105897 50448 105897 52999 105898 53019 105898 53006 105898 53006 105899 53019 105899 53027 105899 52985 105900 52984 105900 53003 105900 53003 105901 52984 105901 53004 105901 53003 105902 53004 105902 53024 105902 53024 105903 53004 105903 53005 105903 53024 105904 53005 105904 53025 105904 53025 105905 53005 105905 50452 105905 53025 105906 50452 105906 53027 105906 53027 105907 50452 105907 53006 105907 53007 105908 53017 105908 54714 105908 53015 105909 52992 105909 53008 105909 53008 105910 52992 105910 52993 105910 53008 105911 52993 105911 51656 105911 51695 105912 51667 105912 51697 105912 51697 105913 51667 105913 53009 105913 51697 105914 53009 105914 53010 105914 53010 105915 53009 105915 53029 105915 53019 105916 53011 105916 54702 105916 54702 105917 53011 105917 54703 105917 51683 105918 52991 105918 51681 105918 51681 105919 52991 105919 52987 105919 51681 105920 52987 105920 53012 105920 53012 105921 52987 105921 52985 105921 53012 105922 52985 105922 54691 105922 54691 105923 52985 105923 53003 105923 54691 105924 53003 105924 53013 105924 53008 105925 53014 105925 53015 105925 53015 105926 53014 105926 54707 105926 53015 105927 54707 105927 53016 105927 53016 105928 54707 105928 54703 105928 53016 105929 54703 105929 53001 105929 53001 105930 54703 105930 53011 105930 51691 105931 52997 105931 53022 105931 54714 105932 53017 105932 54711 105932 54711 105933 53017 105933 53020 105933 54711 105934 53020 105934 54699 105934 51690 105935 51659 105935 51691 105935 51691 105936 51659 105936 51660 105936 51691 105937 51660 105937 52997 105937 52997 105938 51660 105938 51655 105938 52997 105939 51655 105939 53018 105939 53018 105940 51655 105940 51656 105940 53018 105941 51656 105941 52995 105941 52995 105942 51656 105942 52993 105942 54702 105943 54699 105943 53019 105943 53019 105944 54699 105944 53020 105944 53019 105945 53020 105945 53027 105945 51695 105946 53021 105946 51667 105946 51667 105947 53021 105947 51685 105947 51667 105948 51685 105948 51666 105948 51666 105949 51685 105949 51691 105949 51666 105950 51691 105950 51671 105950 51671 105951 51691 105951 53022 105951 51671 105952 53022 105952 53023 105952 53023 105953 53022 105953 52988 105953 53023 105954 52988 105954 51683 105954 51683 105955 52988 105955 52989 105955 51683 105956 52989 105956 52991 105956 53003 105957 53024 105957 53013 105957 53013 105958 53024 105958 53025 105958 53013 105959 53025 105959 53026 105959 53026 105960 53025 105960 53027 105960 53026 105961 53027 105961 54685 105961 54685 105962 53027 105962 53020 105962 54685 105963 53020 105963 54689 105963 54689 105964 53020 105964 54680 105964 54689 105965 54680 105965 53029 105965 53029 105966 54680 105966 53028 105966 53029 105967 53028 105967 53010 105967 53030 105968 54709 105968 51690 105968 51690 105969 54709 105969 51664 105969 51690 105970 51664 105970 51659 105970 53030 105971 51687 105971 54709 105971 54709 105972 51687 105972 53031 105972 54709 105973 53031 105973 54714 105973 54714 105974 53031 105974 54677 105974 54714 105975 54677 105975 53007 105975 53062 105976 52943 105976 52862 105976 52878 105977 52780 105977 52883 105977 52883 105978 52780 105978 53032 105978 52883 105979 53032 105979 54161 105979 50475 105980 53037 105980 53048 105980 52412 105981 50434 105981 53033 105981 53033 105982 50434 105982 53040 105982 53033 105983 53040 105983 52414 105983 52414 105984 53040 105984 53034 105984 53064 105985 53035 105985 52878 105985 52878 105986 53035 105986 52778 105986 52878 105987 52778 105987 52780 105987 52646 105988 52648 105988 53099 105988 52862 105989 52943 105989 53036 105989 52572 105990 53086 105990 52878 105990 53048 105991 53037 105991 51870 105991 51870 105992 53037 105992 50481 105992 51870 105993 50481 105993 53038 105993 53110 105994 53039 105994 53111 105994 53111 105995 53039 105995 50470 105995 53111 105996 50470 105996 53040 105996 53081 105997 53041 105997 53080 105997 53080 105998 53041 105998 53042 105998 53080 105999 53042 105999 53067 105999 53040 106000 50470 106000 53034 106000 53034 106001 50470 106001 50469 106001 53034 106002 50469 106002 53043 106002 53043 106003 50469 106003 50467 106003 53043 106004 50467 106004 52416 106004 52416 106005 50467 106005 50466 106005 52416 106006 50466 106006 52417 106006 52417 106007 50466 106007 53044 106007 53044 106008 50466 106008 53045 106008 53044 106009 53045 106009 53046 106009 53046 106010 53045 106010 53157 106010 53157 106011 53045 106011 53047 106011 53157 106012 53047 106012 53048 106012 53048 106013 53047 106013 50473 106013 53048 106014 50473 106014 50475 106014 53042 106015 53049 106015 53067 106015 53067 106016 53049 106016 51875 106016 53067 106017 51875 106017 51874 106017 52815 106018 53050 106018 52827 106018 52648 106019 52829 106019 53099 106019 53099 106020 52829 106020 53051 106020 53099 106021 53051 106021 53050 106021 53050 106022 53051 106022 53052 106022 53050 106023 53052 106023 52827 106023 52545 106024 53053 106024 52878 106024 53080 106025 51879 106025 53113 106025 53113 106026 51879 106026 53054 106026 53113 106027 53054 106027 50479 106027 50479 106028 53054 106028 53055 106028 50479 106029 53055 106029 50481 106029 50481 106030 53055 106030 51869 106030 50481 106031 51869 106031 53038 106031 51861 106032 53056 106032 51864 106032 52650 106033 53057 106033 53099 106033 52503 106034 53058 106034 53091 106034 53059 106035 53061 106035 53060 106035 53060 106036 53061 106036 53062 106036 53060 106037 53062 106037 52599 106037 52572 106038 52878 106038 52566 106038 52566 106039 52878 106039 53063 106039 52566 106040 53063 106040 52561 106040 53053 106041 52540 106041 52878 106041 52878 106042 52540 106042 52541 106042 52878 106043 52541 106043 53064 106043 52943 106044 53065 106044 53089 106044 53089 106045 53065 106045 53075 106045 53089 106046 53075 106046 53076 106046 51874 106047 53066 106047 53067 106047 53067 106048 53066 106048 51861 106048 53067 106049 51861 106049 51865 106049 51865 106050 51861 106050 51864 106050 53068 106051 52658 106051 53069 106051 53069 106052 52658 106052 52659 106052 53069 106053 52659 106053 53099 106053 53099 106054 52659 106054 52656 106054 53099 106055 52656 106055 53070 106055 52412 106056 52395 106056 50434 106056 50434 106057 52395 106057 53071 106057 50434 106058 53071 106058 53089 106058 53089 106059 53071 106059 52885 106059 53089 106060 52885 106060 52886 106060 52862 106061 53072 106061 53062 106061 53062 106062 53072 106062 53073 106062 53062 106063 53073 106063 52533 106063 53091 106064 53058 106064 53060 106064 53060 106065 53058 106065 53074 106065 53060 106066 53074 106066 53059 106066 53075 106067 54168 106067 53076 106067 53076 106068 54168 106068 53115 106068 53076 106069 53115 106069 53135 106069 53057 106070 52645 106070 53099 106070 53099 106071 52645 106071 53077 106071 53099 106072 53077 106072 52646 106072 54161 106073 54160 106073 53089 106073 53078 106074 52501 106074 53092 106074 53140 106075 53142 106075 53080 106075 53080 106076 53142 106076 53079 106076 53080 106077 53079 106077 53081 106077 52466 106078 53083 106078 53082 106078 53082 106079 53083 106079 53126 106079 52412 106080 53084 106080 52395 106080 52395 106081 53084 106081 52399 106081 52395 106082 52399 106082 52394 106082 52394 106083 52399 106083 53121 106083 53085 106084 52560 106084 52565 106084 53086 106085 53087 106085 52878 106085 52878 106086 53087 106086 52542 106086 52878 106087 52542 106087 53088 106087 52886 106088 54176 106088 53089 106088 53089 106089 54176 106089 52880 106089 53089 106090 52880 106090 54161 106090 54161 106091 52880 106091 53090 106091 54161 106092 53090 106092 52883 106092 52503 106093 53091 106093 53092 106093 53092 106094 53091 106094 52499 106094 53092 106095 52499 106095 53078 106095 53088 106096 53093 106096 52878 106096 52878 106097 53093 106097 52546 106097 52878 106098 52546 106098 52545 106098 51860 106099 51873 106099 53134 106099 52466 106100 52318 106100 53083 106100 53083 106101 52318 106101 53094 106101 53083 106102 53094 106102 53095 106102 53095 106103 53094 106103 53096 106103 53095 106104 53096 106104 53097 106104 53097 106105 53096 106105 53109 106105 53097 106106 53109 106106 50438 106106 53068 106107 52635 106107 52658 106107 52658 106108 52635 106108 53098 106108 52658 106109 53098 106109 52629 106109 52629 106110 53098 106110 52632 106110 52629 106111 52632 106111 52630 106111 53070 106112 52649 106112 53099 106112 53099 106113 52649 106113 53100 106113 53099 106114 53100 106114 53101 106114 53036 106115 52943 106115 52858 106115 52858 106116 52943 106116 53089 106116 52858 106117 53089 106117 52827 106117 52827 106118 53089 106118 54160 106118 52827 106119 54160 106119 52815 106119 52533 106120 53102 106120 53062 106120 53062 106121 53102 106121 53103 106121 53062 106122 53103 106122 53104 106122 52561 106123 52564 106123 52566 106123 52566 106124 52564 106124 53105 106124 52566 106125 53105 106125 52565 106125 52565 106126 53105 106126 53106 106126 52565 106127 53106 106127 53085 106127 53107 106128 53108 106128 53109 106128 53109 106129 53108 106129 50439 106129 53109 106130 50439 106130 50438 106130 53110 106131 53111 106131 50476 106131 50476 106132 53111 106132 50441 106132 50476 106133 50441 106133 50478 106133 50478 106134 50441 106134 53112 106134 50478 106135 53112 106135 53113 106135 53113 106136 53112 106136 50442 106136 53113 106137 50442 106137 53080 106137 53080 106138 50442 106138 53114 106138 53080 106139 53114 106139 53140 106139 53115 106140 53116 106140 53135 106140 53135 106141 53116 106141 53117 106141 53135 106142 53117 106142 53144 106142 53101 106143 53118 106143 53099 106143 53099 106144 53118 106144 52652 106144 53099 106145 52652 106145 52650 106145 53119 106146 52381 106146 52399 106146 52399 106147 52381 106147 53120 106147 52399 106148 53120 106148 53121 106148 53104 106149 53122 106149 53062 106149 53062 106150 53122 106150 53123 106150 53062 106151 53123 106151 52599 106151 52247 106152 53137 106152 53124 106152 53124 106153 53137 106153 53109 106153 53124 106154 53109 106154 53125 106154 53125 106155 53109 106155 51853 106155 53135 106156 53127 106156 53126 106156 53126 106157 53127 106157 53128 106157 53126 106158 53128 106158 53082 106158 51859 106159 53129 106159 51856 106159 51856 106160 53129 106160 51860 106160 51856 106161 51860 106161 51855 106161 51855 106162 51860 106162 53134 106162 53124 106163 53130 106163 52247 106163 52247 106164 53130 106164 51884 106164 52247 106165 51884 106165 52268 106165 52268 106166 51884 106166 51883 106166 52268 106167 51883 106167 53132 106167 53132 106168 51883 106168 53131 106168 53132 106169 53131 106169 53133 106169 53133 106170 53131 106170 53134 106170 53133 106171 53134 106171 51871 106171 51871 106172 53134 106172 51873 106172 51871 106173 51873 106173 51872 106173 52454 106174 52463 106174 53135 106174 53135 106175 52463 106175 53136 106175 53135 106176 53136 106176 53127 106176 53137 106177 53138 106177 53109 106177 53109 106178 53138 106178 53139 106178 53109 106179 53139 106179 53107 106179 53107 106180 53139 106180 53151 106180 53107 106181 53151 106181 53140 106181 53140 106182 53151 106182 53141 106182 53140 106183 53141 106183 53142 106183 52454 106184 53135 106184 53143 106184 53143 106185 53135 106185 53144 106185 53143 106186 53144 106186 52452 106186 52452 106187 53144 106187 52349 106187 52349 106188 53144 106188 52360 106188 52349 106189 52360 106189 53145 106189 53145 106190 53146 106190 52349 106190 52349 106191 53146 106191 53147 106191 52349 106192 53147 106192 52347 106192 52347 106193 53147 106193 53148 106193 52347 106194 53148 106194 52344 106194 52193 106195 53149 106195 50426 106195 50426 106196 53149 106196 53141 106196 50426 106197 53141 106197 53150 106197 53150 106198 53141 106198 53151 106198 53150 106199 53151 106199 50526 106199 50526 106200 53151 106200 50521 106200 53048 106201 53152 106201 50395 106201 50395 106202 50396 106202 53048 106202 53048 106203 50396 106203 53153 106203 53048 106204 53153 106204 53157 106204 53157 106205 53153 106205 50401 106205 53157 106206 50401 106206 53155 106206 50399 106207 52366 106207 50398 106207 50398 106208 52366 106208 52365 106208 50398 106209 52365 106209 53154 106209 53155 106210 53156 106210 53157 106210 53157 106211 53156 106211 50398 106211 53157 106212 50398 106212 52361 106212 52361 106213 50398 106213 53154 106213 53158 106214 50266 106214 53096 106214 53158 106215 53096 106215 53166 106215 50266 106216 50269 106216 53096 106216 53096 106217 50269 106217 53159 106217 53096 106218 53159 106218 53109 106218 53109 106219 53159 106219 53160 106219 53109 106220 53160 106220 50262 106220 53161 106221 53162 106221 52317 106221 52317 106222 53162 106222 53163 106222 52317 106223 53163 106223 53164 106223 53164 106224 53163 106224 53165 106224 53166 106225 53096 106225 53163 106225 53163 106226 53096 106226 53167 106226 53163 106227 53167 106227 53165 106227 52859 106228 52858 106228 50611 106228 50611 106229 52858 106229 52827 106229 53173 106230 54153 106230 53168 106230 53168 106231 54153 106231 54129 106231 53168 106232 54129 106232 53175 106232 53175 106233 54129 106233 54131 106233 53175 106234 54131 106234 53169 106234 53169 106235 54131 106235 54107 106235 53169 106236 54107 106236 53170 106236 53170 106237 54107 106237 54105 106237 53170 106238 54105 106238 53177 106238 53177 106239 54105 106239 54143 106239 53177 106240 54143 106240 53171 106240 53171 106241 54143 106241 54144 106241 53172 106242 53173 106242 53178 106242 53178 106243 53173 106243 53168 106243 53178 106244 53168 106244 53174 106244 53174 106245 53168 106245 53175 106245 53174 106246 53175 106246 53180 106246 53180 106247 53175 106247 53169 106247 53180 106248 53169 106248 53181 106248 53181 106249 53169 106249 53170 106249 53181 106250 53170 106250 53179 106250 53179 106251 53170 106251 53177 106251 53179 106252 53177 106252 53176 106252 53176 106253 53177 106253 53171 106253 54602 106254 53174 106254 53180 106254 53178 106255 53174 106255 54602 106255 53172 106256 53178 106256 54602 106256 54602 106257 53179 106257 53176 106257 53181 106258 53179 106258 54602 106258 53180 106259 53181 106259 54602 106259 54595 106260 54150 106260 53182 106260 53182 106261 54150 106261 54138 106261 53182 106262 54138 106262 53183 106262 53183 106263 54138 106263 53184 106263 53183 106264 53184 106264 53185 106264 53185 106265 53184 106265 53186 106265 53185 106266 53186 106266 53190 106266 53190 106267 53186 106267 54112 106267 53190 106268 54112 106268 53191 106268 53191 106269 54112 106269 54104 106269 53191 106270 54104 106270 53192 106270 53192 106271 54104 106271 54103 106271 54593 106272 54595 106272 53193 106272 53193 106273 54595 106273 53182 106273 53193 106274 53182 106274 53187 106274 53187 106275 53182 106275 53183 106275 53187 106276 53183 106276 53188 106276 53188 106277 53183 106277 53185 106277 53188 106278 53185 106278 53189 106278 53189 106279 53185 106279 53190 106279 53189 106280 53190 106280 53194 106280 53194 106281 53190 106281 53191 106281 53194 106282 53191 106282 54585 106282 54585 106283 53191 106283 53192 106283 53195 106284 53187 106284 53188 106284 53193 106285 53187 106285 53195 106285 54593 106286 53193 106286 53195 106286 53195 106287 53194 106287 54585 106287 53189 106288 53194 106288 53195 106288 53188 106289 53189 106289 53195 106289 51523 106290 51522 106290 53196 106290 50917 106291 50922 106291 54158 106291 54158 106292 50922 106292 54156 106292 50922 106293 53197 106293 54156 106293 54156 106294 53197 106294 50920 106294 54156 106295 50920 106295 53198 106295 50920 106296 53199 106296 53198 106296 53198 106297 53199 106297 53200 106297 53198 106298 53200 106298 54154 106298 54154 106299 53200 106299 50918 106299 54154 106300 50918 106300 53202 106300 53202 106301 50918 106301 53201 106301 53202 106302 53201 106302 51955 106302 51955 106303 53201 106303 53206 106303 51955 106304 53206 106304 53203 106304 54510 106305 54798 106305 50923 106305 50923 106306 54798 106306 53204 106306 50923 106307 53204 106307 53205 106307 53205 106308 53204 106308 51523 106308 53205 106309 51523 106309 53206 106309 53206 106310 51523 106310 53196 106310 53206 106311 53196 106311 53203 106311 50917 106312 54158 106312 53207 106312 53207 106313 54158 106313 53215 106313 53207 106314 53215 106314 50908 106314 53212 106315 51984 106315 51987 106315 53211 106316 53208 106316 53209 106316 53209 106317 53208 106317 53210 106317 53209 106318 53210 106318 54501 106318 51524 106319 53208 106319 51987 106319 51987 106320 53208 106320 53211 106320 51987 106321 53211 106321 53212 106321 53212 106322 53211 106322 50909 106322 53212 106323 50909 106323 50961 106323 50961 106324 50909 106324 50911 106324 50961 106325 50911 106325 54111 106325 54111 106326 50911 106326 50915 106326 54111 106327 50915 106327 54109 106327 50915 106328 53213 106328 54109 106328 54109 106329 53213 106329 50913 106329 54109 106330 50913 106330 53214 106330 50908 106331 53215 106331 53216 106331 53216 106332 53215 106332 53214 106332 53216 106333 53214 106333 50912 106333 50912 106334 53214 106334 50913 106334 53572 106335 53574 106335 53217 106335 53217 106336 53574 106336 51070 106336 53228 106337 53232 106337 53230 106337 53223 106338 53218 106338 53680 106338 53680 106339 53218 106339 51034 106339 53680 106340 51034 106340 53219 106340 54494 106341 53220 106341 53221 106341 53221 106342 53220 106342 51028 106342 53221 106343 51028 106343 53691 106343 51028 106344 51027 106344 53691 106344 53691 106345 51027 106345 53222 106345 53691 106346 53222 106346 53223 106346 53223 106347 53222 106347 51029 106347 53223 106348 51029 106348 53218 106348 51034 106349 53224 106349 53219 106349 53219 106350 53224 106350 51036 106350 53219 106351 51036 106351 53671 106351 53671 106352 51036 106352 53225 106352 53671 106353 53225 106353 53672 106353 53672 106354 53225 106354 51019 106354 53672 106355 51019 106355 53226 106355 53226 106356 51019 106356 53227 106356 53226 106357 53227 106357 53668 106357 53668 106358 53227 106358 51021 106358 53668 106359 51021 106359 53665 106359 53665 106360 51021 106360 51023 106360 53665 106361 51023 106361 53229 106361 53229 106362 51023 106362 53228 106362 53229 106363 53228 106363 53626 106363 53626 106364 53228 106364 53230 106364 53234 106365 53231 106365 51024 106365 51024 106366 53231 106366 53597 106366 51024 106367 53597 106367 53232 106367 53232 106368 53597 106368 53625 106368 53232 106369 53625 106369 53230 106369 53238 106370 53610 106370 51015 106370 51015 106371 53610 106371 53594 106371 51015 106372 53594 106372 51013 106372 51013 106373 53594 106373 53233 106373 51013 106374 53233 106374 53234 106374 53234 106375 53233 106375 53608 106375 53234 106376 53608 106376 53231 106376 51158 106377 51156 106377 53235 106377 53235 106378 51156 106378 51155 106378 51155 106379 51153 106379 53235 106379 53235 106380 51153 106380 53236 106380 53235 106381 53236 106381 51016 106381 51016 106382 53236 106382 53237 106382 51016 106383 53237 106383 53238 106383 53238 106384 53237 106384 53609 106384 53238 106385 53609 106385 53610 106385 51083 106386 53239 106386 53240 106386 53241 106387 53247 106387 53242 106387 53242 106388 53247 106388 51071 106388 53242 106389 51071 106389 53583 106389 51083 106390 53240 106390 53244 106390 53588 106391 53243 106391 51086 106391 51086 106392 53244 106392 53588 106392 53588 106393 53244 106393 53240 106393 53588 106394 53240 106394 53589 106394 53589 106395 53240 106395 51082 106395 53589 106396 51082 106396 53245 106396 53245 106397 51082 106397 53246 106397 53245 106398 53246 106398 53241 106398 53241 106399 53246 106399 51081 106399 53241 106400 51081 106400 53247 106400 51075 106401 53248 106401 53624 106401 51075 106402 53624 106402 51074 106402 51074 106403 53624 106403 53579 106403 51074 106404 53579 106404 51071 106404 51071 106405 53579 106405 53580 106405 51071 106406 53580 106406 53583 106406 53248 106407 51075 106407 53629 106407 53629 106408 51075 106408 53249 106408 53629 106409 53249 106409 53250 106409 53249 106410 53251 106410 53250 106410 53250 106411 53251 106411 51078 106411 53250 106412 51078 106412 53632 106412 51078 106413 53252 106413 53632 106413 53632 106414 53252 106414 53253 106414 53632 106415 53253 106415 53254 106415 53254 106416 53253 106416 53255 106416 53254 106417 53255 106417 53634 106417 53634 106418 53255 106418 53256 106418 53634 106419 53256 106419 53635 106419 53635 106420 53256 106420 53258 106420 53635 106421 53258 106421 53257 106421 53257 106422 53258 106422 53259 106422 53257 106423 53259 106423 53261 106423 53261 106424 53259 106424 53260 106424 53261 106425 53260 106425 53637 106425 51069 106426 51070 106426 53574 106426 53260 106427 53262 106427 53637 106427 53637 106428 53262 106428 53263 106428 53637 106429 53263 106429 53567 106429 53567 106430 53263 106430 51069 106430 53567 106431 51069 106431 53569 106431 53569 106432 51069 106432 53574 106432 51129 106433 53308 106433 53273 106433 53288 106434 51142 106434 51144 106434 51142 106435 53288 106435 51141 106435 51141 106436 53288 106436 53289 106436 51141 106437 53289 106437 53264 106437 53264 106438 53289 106438 53291 106438 53264 106439 53291 106439 51140 106439 53265 106440 51136 106440 51137 106440 53265 106441 51137 106441 53291 106441 53291 106442 51137 106442 51138 106442 53291 106443 51138 106443 51140 106443 51136 106444 53265 106444 51135 106444 51135 106445 53265 106445 53293 106445 51135 106446 53293 106446 53266 106446 53266 106447 53293 106447 53294 106447 53266 106448 53294 106448 51132 106448 51132 106449 53294 106449 53267 106449 53267 106450 53294 106450 53295 106450 53267 106451 53295 106451 53268 106451 51130 106452 53269 106452 53270 106452 53270 106453 53269 106453 53271 106453 53270 106454 53271 106454 53304 106454 53304 106455 53271 106455 51131 106455 53304 106456 51131 106456 53302 106456 53272 106457 51125 106457 53273 106457 53273 106458 51125 106458 51127 106458 53273 106459 51127 106459 51129 106459 51123 106460 53274 106460 53275 106460 53275 106461 53274 106461 51124 106461 53275 106462 51124 106462 53272 106462 53272 106463 51124 106463 51126 106463 53272 106464 51126 106464 51125 106464 51123 106465 53275 106465 53276 106465 53276 106466 53275 106466 53300 106466 53276 106467 53300 106467 51120 106467 51120 106468 53300 106468 51119 106468 51119 106469 53300 106469 53277 106469 51119 106470 53277 106470 53602 106470 53278 106471 53282 106471 53279 106471 53279 106472 53353 106472 53278 106472 53278 106473 53353 106473 53280 106473 53278 106474 53280 106474 53281 106474 53281 106475 53280 106475 53354 106475 53281 106476 53354 106476 53322 106476 53325 106477 53349 106477 53282 106477 53282 106478 53349 106478 53348 106478 53282 106479 53348 106479 53279 106479 53286 106480 53352 106480 53325 106480 53325 106481 53352 106481 53283 106481 53325 106482 53283 106482 53349 106482 53419 106483 53395 106483 53284 106483 53284 106484 53395 106484 53346 106484 53284 106485 53346 106485 53285 106485 53285 106486 53346 106486 53347 106486 53285 106487 53347 106487 53286 106487 53286 106488 53347 106488 53287 106488 53286 106489 53287 106489 53352 106489 51144 106490 53457 106490 53288 106490 53288 106491 53457 106491 53330 106491 53288 106492 53330 106492 53289 106492 53289 106493 53330 106493 53290 106493 53289 106494 53290 106494 53291 106494 53291 106495 53290 106495 53292 106495 53291 106496 53292 106496 53265 106496 53265 106497 53292 106497 53333 106497 53265 106498 53333 106498 53293 106498 53293 106499 53333 106499 53335 106499 53293 106500 53335 106500 53294 106500 53294 106501 53335 106501 53337 106501 53294 106502 53337 106502 53295 106502 53295 106503 53337 106503 53305 106503 53339 106504 53307 106504 53296 106504 53296 106505 53307 106505 53297 106505 53296 106506 53297 106506 53298 106506 53615 106507 53277 106507 53299 106507 53299 106508 53277 106508 53300 106508 53299 106509 53300 106509 53343 106509 53343 106510 53300 106510 53275 106510 53343 106511 53275 106511 53301 106511 53301 106512 53275 106512 53272 106512 53301 106513 53272 106513 53341 106513 53341 106514 53272 106514 53273 106514 53341 106515 53273 106515 53339 106515 53339 106516 53273 106516 53308 106516 53339 106517 53308 106517 53307 106517 53268 106518 53295 106518 53302 106518 53302 106519 53295 106519 53303 106519 53302 106520 53303 106520 53304 106520 53304 106521 53303 106521 53306 106521 53304 106522 53306 106522 53270 106522 53305 106523 53298 106523 53295 106523 53295 106524 53298 106524 53297 106524 53295 106525 53297 106525 53303 106525 53303 106526 53297 106526 53307 106526 53303 106527 53307 106527 53306 106527 53306 106528 53307 106528 53308 106528 53306 106529 53308 106529 53270 106529 53270 106530 53308 106530 51129 106530 53270 106531 51129 106531 51130 106531 53313 106532 53357 106532 53309 106532 53309 106533 53357 106533 53344 106533 53601 106534 53616 106534 53311 106534 53311 106535 53616 106535 53310 106535 53311 106536 53310 106536 53359 106536 53359 106537 53310 106537 53344 106537 53359 106538 53344 106538 53360 106538 53360 106539 53344 106539 53357 106539 53342 106540 53356 106540 53309 106540 53309 106541 53356 106541 53312 106541 53309 106542 53312 106542 53313 106542 53329 106543 53328 106543 53331 106543 53331 106544 53328 106544 53327 106544 53331 106545 53327 106545 53332 106545 53332 106546 53327 106546 53326 106546 53332 106547 53326 106547 53334 106547 53334 106548 53326 106548 53314 106548 53334 106549 53314 106549 53336 106549 53336 106550 53314 106550 53315 106550 53336 106551 53315 106551 53316 106551 53316 106552 53315 106552 53317 106552 53316 106553 53317 106553 53318 106553 53318 106554 53317 106554 53324 106554 53318 106555 53324 106555 53319 106555 53319 106556 53324 106556 53323 106556 53319 106557 53323 106557 53338 106557 53338 106558 53323 106558 53320 106558 53338 106559 53320 106559 53340 106559 53340 106560 53320 106560 53321 106560 53340 106561 53321 106561 53342 106561 53342 106562 53321 106562 53355 106562 53342 106563 53355 106563 53356 106563 53354 106564 53320 106564 53322 106564 53322 106565 53320 106565 53323 106565 53322 106566 53323 106566 53281 106566 53281 106567 53323 106567 53324 106567 53281 106568 53324 106568 53278 106568 53278 106569 53324 106569 53317 106569 53278 106570 53317 106570 53282 106570 53282 106571 53317 106571 53315 106571 53282 106572 53315 106572 53325 106572 53325 106573 53315 106573 53314 106573 53325 106574 53314 106574 53286 106574 53286 106575 53314 106575 53326 106575 53286 106576 53326 106576 53285 106576 53285 106577 53326 106577 53327 106577 53285 106578 53327 106578 53284 106578 53284 106579 53327 106579 53328 106579 53284 106580 53328 106580 53419 106580 53419 106581 53328 106581 53329 106581 53419 106582 53329 106582 53494 106582 53457 106583 53494 106583 53330 106583 53330 106584 53494 106584 53329 106584 53330 106585 53329 106585 53290 106585 53290 106586 53329 106586 53331 106586 53290 106587 53331 106587 53292 106587 53292 106588 53331 106588 53332 106588 53292 106589 53332 106589 53333 106589 53333 106590 53332 106590 53334 106590 53333 106591 53334 106591 53335 106591 53335 106592 53334 106592 53336 106592 53335 106593 53336 106593 53337 106593 53337 106594 53336 106594 53316 106594 53337 106595 53316 106595 53305 106595 53305 106596 53316 106596 53318 106596 53305 106597 53318 106597 53298 106597 53298 106598 53318 106598 53319 106598 53298 106599 53319 106599 53296 106599 53296 106600 53319 106600 53338 106600 53296 106601 53338 106601 53339 106601 53339 106602 53338 106602 53340 106602 53339 106603 53340 106603 53341 106603 53341 106604 53340 106604 53342 106604 53341 106605 53342 106605 53301 106605 53301 106606 53342 106606 53309 106606 53301 106607 53309 106607 53343 106607 53343 106608 53309 106608 53344 106608 53343 106609 53344 106609 53299 106609 53299 106610 53344 106610 53310 106610 53299 106611 53310 106611 53615 106611 53615 106612 53310 106612 53616 106612 50865 106613 53389 106613 50855 106613 53687 106614 53390 106614 53394 106614 53346 106615 53396 106615 53345 106615 53396 106616 53346 106616 53395 106616 53388 106617 53551 106617 53532 106617 53351 106618 53287 106618 53345 106618 53345 106619 53287 106619 53347 106619 53345 106620 53347 106620 53346 106620 53348 106621 53349 106621 53350 106621 53350 106622 53349 106622 53283 106622 53350 106623 53283 106623 53351 106623 53351 106624 53283 106624 53352 106624 53351 106625 53352 106625 53287 106625 53378 106626 53380 106626 53353 106626 53353 106627 53380 106627 53280 106627 53280 106628 53380 106628 53397 106628 53280 106629 53397 106629 53354 106629 53354 106630 53397 106630 53399 106630 53354 106631 53399 106631 53320 106631 53320 106632 53399 106632 53401 106632 53320 106633 53401 106633 53321 106633 53321 106634 53401 106634 53403 106634 53321 106635 53403 106635 53355 106635 53355 106636 53403 106636 53358 106636 53355 106637 53358 106637 53356 106637 53361 106638 53357 106638 53313 106638 53361 106639 53313 106639 53358 106639 53358 106640 53313 106640 53312 106640 53358 106641 53312 106641 53356 106641 53601 106642 53311 106642 53362 106642 53362 106643 53311 106643 53359 106643 53362 106644 53359 106644 53361 106644 53361 106645 53359 106645 53360 106645 53361 106646 53360 106646 53357 106646 53406 106647 53363 106647 53362 106647 53362 106648 53363 106648 53364 106648 53362 106649 53364 106649 53601 106649 53405 106650 53365 106650 53407 106650 53407 106651 53365 106651 53366 106651 53407 106652 53366 106652 53667 106652 53370 106653 53754 106653 53367 106653 53367 106654 53754 106654 53368 106654 53367 106655 53368 106655 53393 106655 53393 106656 53368 106656 53701 106656 53393 106657 53701 106657 53369 106657 53369 106658 53701 106658 53690 106658 53369 106659 53690 106659 53686 106659 53374 106660 53752 106660 53370 106660 53370 106661 53752 106661 53753 106661 53370 106662 53753 106662 53754 106662 53371 106663 53372 106663 53373 106663 53373 106664 53372 106664 50934 106664 53370 106665 53375 106665 53374 106665 53374 106666 53375 106666 53373 106666 53374 106667 53373 106667 53750 106667 53750 106668 53373 106668 50934 106668 53750 106669 50934 106669 50927 106669 50937 106670 50936 106670 53398 106670 53398 106671 50936 106671 53376 106671 50871 106672 53377 106672 53378 106672 53378 106673 53377 106673 53379 106673 53378 106674 53379 106674 53380 106674 53380 106675 53379 106675 53381 106675 53380 106676 53381 106676 53382 106676 53353 106677 53279 106677 53378 106677 53378 106678 53279 106678 53383 106678 53378 106679 53383 106679 50871 106679 50871 106680 53383 106680 50870 106680 50870 106681 53383 106681 50868 106681 50868 106682 53383 106682 53384 106682 50868 106683 53384 106683 50867 106683 50867 106684 53384 106684 53385 106684 53385 106685 53384 106685 53386 106685 53385 106686 53386 106686 53387 106686 53387 106687 53386 106687 50865 106687 50865 106688 53386 106688 53388 106688 50865 106689 53388 106689 53389 106689 53389 106690 53388 106690 53532 106690 53389 106691 53532 106691 50855 106691 53687 106692 53365 106692 53390 106692 53390 106693 53365 106693 53405 106693 53390 106694 53405 106694 53394 106694 53394 106695 53405 106695 53404 106695 53376 106696 53371 106696 53398 106696 53398 106697 53371 106697 53373 106697 53398 106698 53373 106698 53391 106698 53391 106699 53373 106699 53375 106699 53391 106700 53375 106700 53400 106700 53400 106701 53375 106701 53370 106701 53400 106702 53370 106702 53402 106702 53402 106703 53370 106703 53367 106703 53402 106704 53367 106704 53392 106704 53392 106705 53367 106705 53393 106705 53392 106706 53393 106706 53404 106706 53404 106707 53393 106707 53369 106707 53404 106708 53369 106708 53394 106708 53394 106709 53369 106709 53686 106709 53394 106710 53686 106710 53687 106710 53395 106711 53551 106711 53396 106711 53396 106712 53551 106712 53388 106712 53396 106713 53388 106713 53345 106713 53345 106714 53388 106714 53386 106714 53345 106715 53386 106715 53351 106715 53351 106716 53386 106716 53384 106716 53351 106717 53384 106717 53350 106717 53350 106718 53384 106718 53383 106718 53350 106719 53383 106719 53348 106719 53348 106720 53383 106720 53279 106720 53382 106721 50937 106721 53380 106721 53380 106722 50937 106722 53398 106722 53380 106723 53398 106723 53397 106723 53397 106724 53398 106724 53391 106724 53397 106725 53391 106725 53399 106725 53399 106726 53391 106726 53400 106726 53399 106727 53400 106727 53401 106727 53401 106728 53400 106728 53402 106728 53401 106729 53402 106729 53403 106729 53403 106730 53402 106730 53392 106730 53403 106731 53392 106731 53358 106731 53358 106732 53392 106732 53404 106732 53358 106733 53404 106733 53361 106733 53361 106734 53404 106734 53405 106734 53361 106735 53405 106735 53362 106735 53362 106736 53405 106736 53407 106736 53362 106737 53407 106737 53406 106737 53406 106738 53407 106738 53667 106738 53406 106739 53667 106739 53363 106739 53408 106740 54494 106740 53221 106740 54494 106741 53408 106741 53411 106741 53733 106742 50931 106742 53409 106742 53733 106743 53409 106743 53415 106743 50924 106744 51043 106744 50925 106744 50925 106745 51043 106745 53416 106745 54494 106746 53411 106746 53410 106746 53410 106747 53411 106747 53730 106747 53410 106748 53730 106748 53413 106748 53413 106749 53730 106749 53412 106749 53413 106750 53412 106750 53414 106750 53414 106751 53412 106751 53415 106751 53414 106752 53415 106752 53416 106752 53416 106753 53415 106753 53409 106753 53416 106754 53409 106754 50925 106754 53433 106755 53502 106755 53504 106755 53417 106756 53418 106756 53484 106756 53443 106757 53395 106757 53419 106757 51118 106758 53493 106758 53420 106758 53420 106759 53493 106759 53492 106759 53420 106760 53492 106760 53422 106760 53422 106761 53492 106761 53490 106761 53423 106762 51116 106762 53490 106762 53490 106763 51116 106763 53421 106763 53490 106764 53421 106764 53422 106764 53490 106765 53488 106765 53423 106765 53423 106766 53488 106766 53487 106766 53423 106767 53487 106767 51114 106767 53460 106768 51109 106768 51110 106768 51101 106769 51106 106769 53458 106769 53424 106770 53425 106770 53452 106770 53452 106771 53425 106771 51102 106771 53452 106772 51102 106772 53451 106772 53451 106773 51102 106773 51101 106773 53451 106774 51101 106774 53449 106774 53449 106775 51101 106775 53458 106775 53424 106776 53452 106776 51105 106776 51105 106777 53452 106777 53454 106777 51105 106778 53454 106778 53426 106778 53426 106779 53454 106779 53427 106779 53427 106780 53454 106780 53429 106780 53427 106781 53429 106781 53428 106781 53428 106782 53429 106782 53456 106782 53428 106783 53456 106783 53430 106783 53430 106784 53456 106784 53431 106784 53431 106785 53456 106785 53457 106785 53431 106786 53457 106786 51144 106786 53471 106787 53526 106787 53435 106787 53502 106788 53433 106788 53432 106788 53432 106789 53433 106789 53470 106789 53432 106790 53470 106790 53500 106790 53526 106791 53434 106791 53435 106791 53435 106792 53434 106792 53436 106792 53435 106793 53436 106793 53437 106793 53437 106794 53436 106794 53554 106794 53437 106795 53554 106795 53447 106795 53554 106796 53438 106796 53447 106796 53447 106797 53438 106797 53439 106797 53447 106798 53439 106798 53445 106798 53443 106799 53440 106799 53530 106799 53530 106800 53440 106800 53444 106800 53530 106801 53444 106801 53441 106801 53441 106802 53444 106802 53445 106802 53441 106803 53445 106803 53442 106803 53442 106804 53445 106804 53439 106804 53443 106805 53419 106805 53440 106805 53440 106806 53419 106806 53495 106806 53440 106807 53495 106807 53444 106807 53444 106808 53495 106808 53496 106808 53444 106809 53496 106809 53445 106809 53445 106810 53496 106810 53446 106810 53445 106811 53446 106811 53447 106811 53447 106812 53446 106812 53448 106812 53447 106813 53448 106813 53437 106813 53437 106814 53448 106814 53499 106814 53437 106815 53499 106815 53435 106815 51111 106816 53464 106816 53461 106816 53461 106817 53464 106817 53462 106817 53461 106818 53462 106818 53459 106818 53459 106819 53462 106819 53417 106819 53459 106820 53417 106820 53458 106820 53458 106821 53417 106821 53484 106821 53458 106822 53484 106822 53449 106822 53449 106823 53484 106823 53450 106823 53449 106824 53450 106824 53451 106824 53451 106825 53450 106825 53483 106825 53451 106826 53483 106826 53452 106826 53452 106827 53483 106827 53453 106827 53452 106828 53453 106828 53454 106828 53454 106829 53453 106829 53455 106829 53454 106830 53455 106830 53429 106830 53429 106831 53455 106831 53479 106831 53429 106832 53479 106832 53456 106832 53456 106833 53479 106833 53477 106833 53456 106834 53477 106834 53457 106834 51106 106835 51107 106835 53458 106835 53458 106836 51107 106836 51109 106836 53458 106837 51109 106837 53459 106837 53459 106838 51109 106838 53460 106838 53459 106839 53460 106839 53461 106839 53461 106840 53460 106840 51110 106840 53461 106841 51110 106841 51111 106841 53418 106842 53417 106842 53463 106842 53463 106843 53417 106843 53462 106843 53463 106844 53462 106844 53485 106844 53485 106845 53462 106845 53464 106845 53485 106846 53464 106846 53487 106846 53487 106847 53464 106847 51112 106847 53487 106848 51112 106848 51114 106848 53465 106849 53521 106849 53475 106849 53475 106850 53521 106850 53466 106850 53475 106851 53466 106851 53476 106851 53593 106852 53467 106852 53468 106852 53468 106853 53467 106853 53520 106853 53468 106854 53520 106854 53465 106854 53465 106855 53520 106855 53469 106855 53465 106856 53469 106856 53521 106856 53499 106857 53500 106857 53435 106857 53435 106858 53500 106858 53470 106858 53435 106859 53470 106859 53471 106859 53471 106860 53470 106860 53433 106860 53471 106861 53433 106861 53472 106861 53472 106862 53433 106862 53504 106862 53472 106863 53504 106863 53522 106863 53522 106864 53504 106864 53473 106864 53522 106865 53473 106865 53474 106865 53474 106866 53473 106866 53506 106866 53474 106867 53506 106867 53524 106867 53524 106868 53506 106868 53475 106868 53524 106869 53475 106869 53525 106869 53525 106870 53475 106870 53476 106870 53494 106871 53457 106871 53478 106871 53478 106872 53457 106872 53477 106872 53478 106873 53477 106873 53497 106873 53497 106874 53477 106874 53479 106874 53497 106875 53479 106875 53480 106875 53480 106876 53479 106876 53455 106876 53480 106877 53455 106877 53498 106877 53498 106878 53455 106878 53453 106878 53498 106879 53453 106879 53481 106879 53481 106880 53453 106880 53483 106880 53481 106881 53483 106881 53482 106881 53482 106882 53483 106882 53450 106882 53482 106883 53450 106883 53501 106883 53501 106884 53450 106884 53484 106884 53501 106885 53484 106885 53503 106885 53503 106886 53484 106886 53418 106886 53503 106887 53418 106887 53505 106887 53505 106888 53418 106888 53463 106888 53505 106889 53463 106889 53507 106889 53507 106890 53463 106890 53485 106890 53507 106891 53485 106891 53486 106891 53486 106892 53485 106892 53487 106892 53486 106893 53487 106893 53508 106893 53508 106894 53487 106894 53488 106894 53508 106895 53488 106895 53489 106895 53489 106896 53488 106896 53490 106896 53489 106897 53490 106897 53509 106897 53509 106898 53490 106898 53492 106898 53509 106899 53492 106899 53491 106899 53491 106900 53492 106900 53493 106900 53419 106901 53494 106901 53495 106901 53495 106902 53494 106902 53478 106902 53495 106903 53478 106903 53496 106903 53496 106904 53478 106904 53497 106904 53496 106905 53497 106905 53446 106905 53446 106906 53497 106906 53480 106906 53446 106907 53480 106907 53448 106907 53448 106908 53480 106908 53498 106908 53448 106909 53498 106909 53499 106909 53499 106910 53498 106910 53481 106910 53499 106911 53481 106911 53500 106911 53500 106912 53481 106912 53482 106912 53500 106913 53482 106913 53432 106913 53432 106914 53482 106914 53501 106914 53432 106915 53501 106915 53502 106915 53502 106916 53501 106916 53503 106916 53502 106917 53503 106917 53504 106917 53504 106918 53503 106918 53505 106918 53504 106919 53505 106919 53473 106919 53473 106920 53505 106920 53507 106920 53473 106921 53507 106921 53506 106921 53506 106922 53507 106922 53486 106922 53506 106923 53486 106923 53475 106923 53475 106924 53486 106924 53508 106924 53475 106925 53508 106925 53465 106925 53465 106926 53508 106926 53489 106926 53465 106927 53489 106927 53468 106927 53468 106928 53489 106928 53509 106928 53468 106929 53509 106929 53593 106929 53593 106930 53509 106930 53491 106930 53657 106931 53510 106931 53543 106931 53511 106932 50891 106932 53550 106932 53511 106933 53550 106933 53702 106933 53702 106934 53550 106934 53512 106934 53702 106935 53512 106935 53712 106935 53712 106936 53512 106936 53513 106936 53513 106937 53512 106937 53549 106937 53513 106938 53549 106938 53714 106938 53714 106939 53549 106939 53514 106939 53714 106940 53514 106940 53716 106940 53716 106941 53514 106941 53547 106941 53716 106942 53547 106942 53717 106942 53717 106943 53547 106943 53659 106943 53659 106944 53547 106944 53545 106944 53659 106945 53545 106945 53515 106945 53515 106946 53545 106946 53516 106946 53515 106947 53516 106947 53517 106947 53566 106948 53518 106948 53519 106948 53565 106949 53619 106949 53653 106949 53467 106950 53619 106950 53520 106950 53520 106951 53619 106951 53565 106951 53520 106952 53565 106952 53469 106952 53469 106953 53565 106953 53521 106953 53521 106954 53565 106954 53563 106954 53521 106955 53563 106955 53466 106955 53539 106956 53471 106956 53557 106956 53557 106957 53471 106957 53472 106957 53557 106958 53472 106958 53558 106958 53558 106959 53472 106959 53522 106959 53558 106960 53522 106960 53560 106960 53560 106961 53522 106961 53474 106961 53560 106962 53474 106962 53523 106962 53523 106963 53474 106963 53524 106963 53523 106964 53524 106964 53562 106964 53562 106965 53524 106965 53525 106965 53562 106966 53525 106966 53563 106966 53563 106967 53525 106967 53476 106967 53563 106968 53476 106968 53466 106968 53554 106969 53436 106969 53541 106969 53541 106970 53436 106970 53434 106970 53541 106971 53434 106971 53539 106971 53539 106972 53434 106972 53526 106972 53539 106973 53526 106973 53471 106973 53530 106974 53441 106974 53527 106974 53527 106975 53441 106975 53442 106975 53527 106976 53442 106976 53528 106976 53528 106977 53442 106977 53439 106977 53528 106978 53439 106978 53438 106978 53395 106979 53443 106979 53529 106979 53529 106980 53443 106980 53530 106980 53529 106981 53530 106981 53531 106981 53531 106982 53530 106982 53527 106982 50855 106983 53532 106983 53533 106983 53533 106984 53532 106984 53551 106984 53533 106985 53551 106985 53552 106985 50855 106986 53533 106986 50856 106986 50856 106987 53533 106987 53552 106987 50856 106988 53552 106988 53535 106988 53535 106989 53552 106989 53534 106989 53535 106990 53534 106990 53536 106990 53536 106991 53534 106991 53537 106991 53536 106992 53537 106992 50859 106992 53554 106993 53541 106993 53553 106993 53553 106994 53541 106994 53542 106994 53553 106995 53542 106995 53537 106995 53537 106996 53542 106996 50860 106996 53537 106997 50860 106997 50859 106997 50898 106998 53538 106998 53539 106998 53539 106999 53538 106999 53540 106999 53539 107000 53540 107000 53541 107000 53541 107001 53540 107001 50838 107001 53541 107002 50838 107002 53542 107002 50892 107003 50894 107003 53555 107003 53555 107004 50894 107004 50895 107004 53566 107005 53519 107005 53564 107005 53564 107006 53519 107006 53543 107006 53564 107007 53543 107007 53544 107007 53544 107008 53543 107008 53510 107008 53544 107009 53510 107009 53561 107009 53657 107010 53517 107010 53510 107010 53510 107011 53517 107011 53516 107011 53510 107012 53516 107012 53561 107012 53561 107013 53516 107013 53545 107013 53561 107014 53545 107014 53559 107014 53559 107015 53545 107015 53547 107015 53559 107016 53547 107016 53546 107016 53546 107017 53547 107017 53514 107017 53546 107018 53514 107018 53548 107018 53548 107019 53514 107019 53549 107019 53548 107020 53549 107020 53556 107020 53556 107021 53549 107021 53512 107021 53556 107022 53512 107022 53555 107022 53555 107023 53512 107023 53550 107023 53555 107024 53550 107024 50892 107024 50892 107025 53550 107025 50891 107025 53551 107026 53395 107026 53552 107026 53552 107027 53395 107027 53529 107027 53552 107028 53529 107028 53534 107028 53534 107029 53529 107029 53531 107029 53534 107030 53531 107030 53537 107030 53537 107031 53531 107031 53527 107031 53537 107032 53527 107032 53553 107032 53553 107033 53527 107033 53528 107033 53553 107034 53528 107034 53554 107034 53554 107035 53528 107035 53438 107035 50895 107036 50898 107036 53555 107036 53555 107037 50898 107037 53539 107037 53555 107038 53539 107038 53556 107038 53556 107039 53539 107039 53557 107039 53556 107040 53557 107040 53548 107040 53548 107041 53557 107041 53558 107041 53548 107042 53558 107042 53546 107042 53546 107043 53558 107043 53560 107043 53546 107044 53560 107044 53559 107044 53559 107045 53560 107045 53523 107045 53559 107046 53523 107046 53561 107046 53561 107047 53523 107047 53562 107047 53561 107048 53562 107048 53544 107048 53544 107049 53562 107049 53563 107049 53544 107050 53563 107050 53564 107050 53564 107051 53563 107051 53565 107051 53564 107052 53565 107052 53566 107052 53566 107053 53565 107053 53653 107053 53566 107054 53653 107054 53518 107054 53567 107055 53569 107055 53568 107055 53568 107056 53569 107056 53574 107056 53568 107057 53574 107057 53693 107057 50906 107058 50905 107058 53570 107058 53571 107059 51055 107059 50910 107059 53573 107060 53693 107060 53574 107060 50910 107061 50907 107061 53571 107061 53571 107062 50907 107062 50906 107062 53571 107063 50906 107063 51057 107063 51057 107064 50906 107064 53570 107064 51057 107065 53570 107065 51058 107065 53570 107066 53708 107066 51058 107066 51058 107067 53708 107067 53573 107067 51058 107068 53573 107068 53572 107068 53572 107069 53573 107069 53574 107069 53245 107070 53241 107070 53575 107070 53576 107071 53577 107071 53587 107071 53467 107072 53593 107072 53592 107072 53467 107073 53592 107073 53621 107073 53621 107074 53592 107074 53578 107074 53621 107075 53578 107075 53622 107075 53622 107076 53578 107076 53582 107076 53622 107077 53582 107077 53581 107077 53579 107078 53581 107078 53580 107078 53580 107079 53581 107079 53582 107079 53580 107080 53582 107080 53583 107080 53583 107081 53582 107081 53242 107081 51099 107082 51098 107082 53584 107082 53584 107083 51098 107083 51096 107083 53584 107084 51096 107084 53588 107084 53588 107085 51096 107085 51095 107085 53588 107086 51095 107086 53243 107086 53587 107087 53577 107087 53584 107087 53584 107088 53577 107088 51094 107088 53584 107089 51094 107089 51099 107089 53586 107090 53493 107090 51118 107090 51118 107091 51091 107091 53586 107091 53586 107092 51091 107092 53585 107092 53586 107093 53585 107093 53587 107093 53587 107094 53585 107094 51089 107094 53587 107095 51089 107095 53576 107095 53245 107096 53575 107096 53589 107096 53588 107097 53589 107097 53584 107097 53584 107098 53589 107098 53575 107098 53584 107099 53575 107099 53587 107099 53587 107100 53575 107100 53590 107100 53587 107101 53590 107101 53586 107101 53586 107102 53590 107102 53591 107102 53586 107103 53591 107103 53493 107103 53493 107104 53591 107104 53491 107104 53241 107105 53242 107105 53575 107105 53575 107106 53242 107106 53582 107106 53575 107107 53582 107107 53590 107107 53590 107108 53582 107108 53578 107108 53590 107109 53578 107109 53591 107109 53591 107110 53578 107110 53592 107110 53591 107111 53592 107111 53491 107111 53491 107112 53592 107112 53593 107112 53233 107113 53594 107113 53612 107113 53595 107114 51145 107114 53611 107114 53597 107115 53231 107115 53596 107115 53597 107116 53596 107116 53625 107116 53625 107117 53596 107117 53598 107117 53598 107118 53596 107118 53618 107118 53598 107119 53618 107119 53599 107119 53599 107120 53618 107120 53600 107120 53599 107121 53600 107121 53628 107121 53628 107122 53600 107122 53616 107122 53628 107123 53616 107123 53601 107123 53602 107124 53277 107124 51150 107124 51150 107125 53277 107125 53603 107125 51150 107126 53603 107126 53604 107126 53604 107127 53603 107127 53605 107127 53605 107128 53603 107128 53606 107128 53606 107129 53603 107129 53614 107129 53606 107130 53614 107130 53607 107130 51145 107131 51146 107131 53611 107131 53611 107132 51146 107132 51147 107132 53611 107133 51147 107133 53614 107133 53614 107134 51147 107134 51148 107134 53614 107135 51148 107135 53607 107135 53233 107136 53612 107136 53608 107136 53236 107137 53595 107137 53237 107137 53237 107138 53595 107138 53611 107138 53237 107139 53611 107139 53609 107139 53609 107140 53611 107140 53610 107140 53594 107141 53610 107141 53612 107141 53612 107142 53610 107142 53611 107142 53612 107143 53611 107143 53613 107143 53613 107144 53611 107144 53614 107144 53613 107145 53614 107145 53617 107145 53617 107146 53614 107146 53603 107146 53617 107147 53603 107147 53615 107147 53615 107148 53603 107148 53277 107148 53615 107149 53616 107149 53617 107149 53617 107150 53616 107150 53600 107150 53617 107151 53600 107151 53613 107151 53613 107152 53600 107152 53618 107152 53613 107153 53618 107153 53612 107153 53612 107154 53618 107154 53596 107154 53612 107155 53596 107155 53608 107155 53608 107156 53596 107156 53231 107156 53624 107157 53248 107157 53623 107157 53619 107158 53467 107158 53630 107158 53630 107159 53467 107159 53621 107159 53630 107160 53621 107160 53620 107160 53620 107161 53621 107161 53622 107161 53620 107162 53622 107162 53623 107162 53623 107163 53622 107163 53581 107163 53623 107164 53581 107164 53624 107164 53624 107165 53581 107165 53579 107165 53230 107166 53625 107166 53598 107166 53626 107167 53230 107167 53662 107167 53662 107168 53230 107168 53598 107168 53662 107169 53598 107169 53663 107169 53663 107170 53598 107170 53599 107170 53663 107171 53599 107171 53627 107171 53627 107172 53599 107172 53628 107172 53627 107173 53628 107173 53364 107173 53364 107174 53628 107174 53601 107174 53623 107175 53248 107175 53629 107175 53620 107176 53623 107176 53638 107176 53630 107177 53620 107177 53646 107177 53619 107178 53630 107178 53654 107178 53623 107179 53629 107179 53638 107179 53638 107180 53629 107180 53250 107180 53638 107181 53250 107181 53631 107181 53631 107182 53250 107182 53632 107182 53631 107183 53632 107183 53633 107183 53633 107184 53632 107184 53254 107184 53633 107185 53254 107185 53640 107185 53254 107186 53634 107186 53640 107186 53640 107187 53634 107187 53635 107187 53640 107188 53635 107188 53642 107188 53642 107189 53635 107189 53257 107189 53642 107190 53257 107190 53636 107190 53257 107191 53261 107191 53636 107191 53636 107192 53261 107192 53637 107192 53636 107193 53637 107193 53643 107193 53643 107194 53637 107194 53567 107194 53643 107195 53567 107195 53645 107195 53620 107196 53638 107196 53646 107196 53646 107197 53638 107197 53631 107197 53646 107198 53631 107198 53647 107198 53647 107199 53631 107199 53633 107199 53647 107200 53633 107200 53639 107200 53639 107201 53633 107201 53640 107201 53639 107202 53640 107202 53649 107202 53649 107203 53640 107203 53642 107203 53649 107204 53642 107204 53641 107204 53641 107205 53642 107205 53636 107205 53641 107206 53636 107206 53644 107206 53644 107207 53636 107207 53643 107207 53644 107208 53643 107208 53651 107208 53651 107209 53643 107209 53645 107209 53651 107210 53645 107210 53696 107210 53630 107211 53646 107211 53654 107211 53654 107212 53646 107212 53647 107212 53654 107213 53647 107213 53648 107213 53648 107214 53647 107214 53639 107214 53648 107215 53639 107215 53655 107215 53655 107216 53639 107216 53649 107216 53655 107217 53649 107217 53650 107217 53650 107218 53649 107218 53641 107218 53650 107219 53641 107219 53656 107219 53656 107220 53641 107220 53644 107220 53656 107221 53644 107221 53658 107221 53658 107222 53644 107222 53651 107222 53658 107223 53651 107223 53652 107223 53652 107224 53651 107224 53696 107224 53652 107225 53696 107225 53694 107225 53619 107226 53654 107226 53653 107226 53653 107227 53654 107227 53648 107227 53653 107228 53648 107228 53518 107228 53518 107229 53648 107229 53655 107229 53518 107230 53655 107230 53519 107230 53519 107231 53655 107231 53650 107231 53519 107232 53650 107232 53543 107232 53543 107233 53650 107233 53656 107233 53543 107234 53656 107234 53657 107234 53657 107235 53656 107235 53658 107235 53657 107236 53658 107236 53517 107236 53517 107237 53658 107237 53652 107237 53517 107238 53652 107238 53515 107238 53515 107239 53652 107239 53694 107239 53515 107240 53694 107240 53659 107240 53680 107241 53219 107241 53683 107241 53672 107242 53226 107242 53673 107242 53665 107243 53229 107243 53660 107243 53229 107244 53626 107244 53660 107244 53660 107245 53626 107245 53662 107245 53660 107246 53662 107246 53661 107246 53661 107247 53662 107247 53663 107247 53661 107248 53663 107248 53666 107248 53666 107249 53663 107249 53627 107249 53666 107250 53627 107250 53363 107250 53363 107251 53627 107251 53364 107251 53668 107252 53665 107252 53664 107252 53664 107253 53665 107253 53660 107253 53664 107254 53660 107254 53669 107254 53669 107255 53660 107255 53661 107255 53669 107256 53661 107256 53670 107256 53670 107257 53661 107257 53666 107257 53670 107258 53666 107258 53667 107258 53667 107259 53666 107259 53363 107259 53226 107260 53668 107260 53673 107260 53673 107261 53668 107261 53664 107261 53673 107262 53664 107262 53674 107262 53674 107263 53664 107263 53669 107263 53674 107264 53669 107264 53676 107264 53676 107265 53669 107265 53670 107265 53676 107266 53670 107266 53366 107266 53366 107267 53670 107267 53667 107267 53671 107268 53672 107268 53677 107268 53677 107269 53672 107269 53673 107269 53677 107270 53673 107270 53679 107270 53679 107271 53673 107271 53674 107271 53679 107272 53674 107272 53675 107272 53675 107273 53674 107273 53676 107273 53675 107274 53676 107274 53365 107274 53365 107275 53676 107275 53366 107275 53219 107276 53671 107276 53683 107276 53683 107277 53671 107277 53677 107277 53683 107278 53677 107278 53678 107278 53678 107279 53677 107279 53679 107279 53678 107280 53679 107280 53685 107280 53685 107281 53679 107281 53675 107281 53685 107282 53675 107282 53687 107282 53687 107283 53675 107283 53365 107283 53223 107284 53680 107284 53681 107284 53681 107285 53680 107285 53683 107285 53681 107286 53683 107286 53682 107286 53682 107287 53683 107287 53678 107287 53682 107288 53678 107288 53684 107288 53684 107289 53678 107289 53685 107289 53684 107290 53685 107290 53686 107290 53686 107291 53685 107291 53687 107291 53691 107292 53223 107292 53688 107292 53688 107293 53223 107293 53681 107293 53688 107294 53681 107294 53689 107294 53689 107295 53681 107295 53682 107295 53689 107296 53682 107296 53692 107296 53692 107297 53682 107297 53684 107297 53692 107298 53684 107298 53690 107298 53690 107299 53684 107299 53686 107299 53221 107300 53691 107300 53697 107300 53697 107301 53691 107301 53688 107301 53697 107302 53688 107302 53698 107302 53698 107303 53688 107303 53689 107303 53698 107304 53689 107304 53700 107304 53700 107305 53689 107305 53692 107305 53700 107306 53692 107306 53701 107306 53701 107307 53692 107307 53690 107307 53568 107308 53693 107308 53710 107308 53717 107309 53659 107309 53718 107309 53718 107310 53659 107310 53694 107310 53718 107311 53694 107311 53695 107311 53695 107312 53694 107312 53696 107312 53695 107313 53696 107313 53710 107313 53710 107314 53696 107314 53645 107314 53710 107315 53645 107315 53568 107315 53568 107316 53645 107316 53567 107316 53741 107317 53697 107317 53748 107317 53748 107318 53697 107318 53698 107318 53748 107319 53698 107319 53699 107319 53699 107320 53698 107320 53700 107320 53699 107321 53700 107321 53368 107321 53368 107322 53700 107322 53701 107322 53741 107323 53411 107323 53697 107323 53697 107324 53411 107324 53408 107324 53697 107325 53408 107325 53221 107325 53706 107326 53705 107326 53724 107326 53704 107327 53703 107327 53711 107327 50904 107328 53511 107328 53702 107328 50904 107329 53702 107329 53703 107329 53704 107330 53711 107330 53705 107330 53706 107331 53723 107331 50901 107331 50901 107332 53723 107332 53726 107332 50901 107333 53726 107333 50905 107333 50905 107334 53726 107334 53707 107334 50905 107335 53707 107335 53570 107335 53570 107336 53707 107336 53709 107336 53570 107337 53709 107337 53708 107337 53708 107338 53709 107338 53728 107338 53708 107339 53728 107339 53573 107339 53573 107340 53728 107340 53710 107340 53573 107341 53710 107341 53693 107341 53703 107342 53702 107342 53711 107342 53711 107343 53702 107343 53712 107343 53711 107344 53712 107344 53719 107344 53719 107345 53712 107345 53513 107345 53719 107346 53513 107346 53713 107346 53713 107347 53513 107347 53714 107347 53713 107348 53714 107348 53721 107348 53721 107349 53714 107349 53716 107349 53721 107350 53716 107350 53715 107350 53715 107351 53716 107351 53717 107351 53715 107352 53717 107352 53718 107352 53705 107353 53711 107353 53724 107353 53724 107354 53711 107354 53719 107354 53724 107355 53719 107355 53725 107355 53725 107356 53719 107356 53713 107356 53725 107357 53713 107357 53720 107357 53720 107358 53713 107358 53721 107358 53720 107359 53721 107359 53727 107359 53727 107360 53721 107360 53715 107360 53727 107361 53715 107361 53722 107361 53722 107362 53715 107362 53718 107362 53722 107363 53718 107363 53695 107363 53706 107364 53724 107364 53723 107364 53723 107365 53724 107365 53725 107365 53723 107366 53725 107366 53726 107366 53726 107367 53725 107367 53720 107367 53726 107368 53720 107368 53707 107368 53707 107369 53720 107369 53727 107369 53707 107370 53727 107370 53709 107370 53709 107371 53727 107371 53722 107371 53709 107372 53722 107372 53728 107372 53728 107373 53722 107373 53695 107373 53728 107374 53695 107374 53710 107374 53729 107375 53736 107375 53735 107375 53411 107376 53741 107376 53740 107376 53736 107377 53729 107377 53732 107377 53411 107378 53740 107378 53730 107378 53730 107379 53740 107379 53739 107379 53730 107380 53739 107380 53412 107380 53412 107381 53739 107381 53731 107381 53412 107382 53731 107382 53415 107382 53415 107383 53731 107383 53732 107383 53415 107384 53732 107384 53733 107384 53733 107385 53732 107385 53729 107385 53733 107386 53729 107386 50931 107386 53734 107387 50930 107387 53742 107387 53742 107388 50930 107388 53735 107388 53749 107389 50928 107389 53734 107389 53750 107390 50927 107390 50928 107390 53735 107391 53736 107391 53742 107391 53742 107392 53736 107392 53732 107392 53742 107393 53732 107393 53737 107393 53737 107394 53732 107394 53731 107394 53737 107395 53731 107395 53743 107395 53743 107396 53731 107396 53739 107396 53743 107397 53739 107397 53738 107397 53738 107398 53739 107398 53740 107398 53738 107399 53740 107399 53746 107399 53746 107400 53740 107400 53741 107400 53746 107401 53741 107401 53748 107401 53734 107402 53742 107402 53749 107402 53749 107403 53742 107403 53737 107403 53749 107404 53737 107404 53744 107404 53744 107405 53737 107405 53743 107405 53744 107406 53743 107406 53751 107406 53751 107407 53743 107407 53738 107407 53751 107408 53738 107408 53745 107408 53745 107409 53738 107409 53746 107409 53745 107410 53746 107410 53747 107410 53747 107411 53746 107411 53748 107411 53747 107412 53748 107412 53699 107412 50928 107413 53749 107413 53750 107413 53750 107414 53749 107414 53744 107414 53750 107415 53744 107415 53374 107415 53374 107416 53744 107416 53751 107416 53374 107417 53751 107417 53752 107417 53752 107418 53751 107418 53745 107418 53752 107419 53745 107419 53753 107419 53753 107420 53745 107420 53747 107420 53753 107421 53747 107421 53754 107421 53754 107422 53747 107422 53699 107422 53754 107423 53699 107423 53368 107423 53755 107424 51477 107424 53756 107424 53756 107425 51477 107425 51453 107425 53757 107426 51063 107426 51458 107426 51458 107427 51063 107427 53759 107427 51458 107428 53759 107428 53758 107428 53758 107429 53759 107429 53760 107429 53758 107430 53760 107430 53761 107430 53761 107431 53760 107431 51077 107431 53761 107432 51077 107432 51460 107432 51460 107433 51077 107433 51076 107433 51460 107434 51076 107434 53762 107434 53762 107435 51076 107435 51073 107435 53762 107436 51073 107436 51452 107436 51452 107437 51073 107437 53763 107437 51452 107438 53763 107438 51453 107438 51453 107439 53763 107439 51072 107439 51453 107440 51072 107440 53756 107440 53764 107441 51163 107441 51017 107441 53764 107442 51017 107442 51252 107442 51017 107443 53765 107443 51252 107443 51252 107444 53765 107444 53766 107444 51252 107445 53766 107445 53767 107445 53767 107446 53766 107446 51014 107446 53767 107447 51014 107447 51026 107447 51477 107448 53755 107448 53768 107448 51477 107449 53768 107449 51481 107449 51481 107450 53768 107450 51249 107450 51481 107451 51249 107451 53769 107451 54082 107452 53789 107452 53853 107452 54473 107453 53770 107453 53887 107453 53771 107454 53772 107454 53785 107454 51186 107455 51188 107455 53830 107455 53773 107456 51192 107456 53774 107456 54089 107457 116271 107457 53863 107457 53866 107458 53775 107458 53864 107458 53865 107459 54093 107459 54092 107459 53864 107460 53775 107460 54092 107460 53836 107461 54099 107461 53848 107461 51201 107462 53776 107462 51198 107462 51198 107463 53776 107463 53777 107463 51198 107464 53777 107464 53778 107464 53778 107465 53777 107465 51196 107465 51196 107466 53777 107466 53779 107466 51196 107467 53779 107467 53827 107467 53807 107468 53806 107468 51190 107468 53780 107469 53781 107469 53782 107469 53782 107470 53781 107470 53783 107470 53782 107471 53783 107471 53784 107471 53772 107472 51180 107472 53785 107472 53785 107473 51180 107473 51179 107473 53785 107474 51179 107474 53897 107474 53897 107475 51179 107475 51178 107475 54479 107476 54468 107476 53888 107476 53888 107477 54468 107477 54467 107477 53888 107478 54467 107478 54466 107478 53879 107479 54460 107479 53890 107479 53786 107480 54459 107480 53787 107480 53787 107481 54459 107481 54458 107481 53787 107482 54458 107482 54463 107482 54473 107483 53887 107483 53854 107483 53850 107484 53851 107484 54450 107484 54450 107485 53851 107485 53788 107485 54450 107486 53788 107486 54449 107486 53789 107487 54082 107487 53788 107487 54449 107488 53788 107488 50152 107488 50152 107489 53788 107489 54082 107489 50152 107490 54082 107490 50165 107490 54084 107491 53790 107491 53791 107491 53791 107492 53790 107492 53859 107492 53791 107493 53859 107493 54086 107493 116271 107494 54088 107494 53792 107494 53792 107495 54088 107495 53860 107495 53792 107496 53860 107496 53858 107496 53805 107497 53799 107497 53793 107497 53793 107498 53799 107498 53797 107498 53793 107499 53797 107499 53804 107499 53804 107500 53797 107500 53803 107500 53903 107501 53794 107501 53817 107501 53817 107502 53794 107502 53900 107502 53817 107503 53900 107503 53795 107503 53795 107504 53900 107504 53899 107504 53795 107505 53899 107505 53820 107505 53820 107506 53899 107506 53782 107506 53820 107507 53782 107507 51182 107507 51182 107508 53782 107508 53784 107508 53800 107509 53796 107509 53798 107509 53798 107510 53796 107510 53891 107510 53798 107511 53891 107511 53889 107511 53802 107512 53803 107512 53889 107512 53889 107513 53803 107513 53797 107513 53889 107514 53797 107514 53798 107514 53798 107515 53797 107515 53799 107515 53798 107516 53799 107516 53800 107516 53800 107517 53799 107517 53805 107517 53800 107518 53805 107518 53801 107518 51177 107519 53771 107519 53802 107519 53802 107520 53771 107520 53785 107520 53802 107521 53785 107521 53803 107521 53803 107522 53785 107522 53897 107522 53803 107523 53897 107523 53804 107523 53804 107524 53897 107524 53898 107524 53804 107525 53898 107525 53793 107525 53793 107526 53898 107526 53901 107526 53793 107527 53901 107527 53805 107527 53805 107528 53901 107528 53902 107528 53805 107529 53902 107529 53801 107529 51188 107530 53806 107530 53830 107530 53830 107531 53806 107531 53807 107531 53830 107532 53807 107532 53808 107532 53808 107533 53807 107533 53809 107533 53808 107534 53809 107534 53810 107534 53810 107535 53809 107535 53824 107535 53810 107536 53824 107536 53811 107536 53811 107537 53824 107537 53812 107537 53811 107538 53812 107538 53833 107538 53833 107539 53812 107539 53813 107539 53833 107540 53813 107540 53814 107540 53814 107541 53813 107541 53815 107541 53814 107542 53815 107542 53835 107542 53816 107543 53903 107543 53840 107543 53840 107544 53903 107544 53817 107544 53840 107545 53817 107545 53818 107545 53818 107546 53817 107546 53795 107546 53818 107547 53795 107547 53838 107547 53838 107548 53795 107548 53820 107548 53838 107549 53820 107549 53819 107549 53819 107550 53820 107550 51182 107550 54101 107551 53835 107551 53821 107551 53821 107552 53835 107552 53815 107552 53821 107553 53815 107553 53829 107553 53829 107554 53815 107554 53813 107554 53829 107555 53813 107555 53822 107555 53822 107556 53813 107556 53812 107556 53822 107557 53812 107557 53823 107557 53823 107558 53812 107558 53824 107558 53823 107559 53824 107559 53828 107559 53828 107560 53824 107560 53809 107560 53776 107561 53825 107561 53777 107561 53777 107562 53825 107562 53826 107562 53777 107563 53826 107563 53779 107563 53779 107564 53826 107564 53774 107564 53779 107565 53774 107565 53827 107565 53827 107566 53774 107566 51192 107566 51190 107567 53773 107567 53807 107567 53807 107568 53773 107568 53774 107568 53807 107569 53774 107569 53809 107569 53809 107570 53774 107570 53826 107570 53809 107571 53826 107571 53828 107571 53828 107572 53826 107572 53825 107572 53828 107573 53825 107573 53823 107573 53823 107574 53825 107574 53776 107574 53823 107575 53776 107575 53822 107575 53822 107576 53776 107576 51201 107576 53822 107577 51201 107577 53829 107577 53829 107578 51201 107578 54095 107578 53829 107579 54095 107579 53821 107579 53837 107580 51186 107580 53831 107580 53831 107581 51186 107581 53830 107581 53831 107582 53830 107582 53839 107582 53839 107583 53830 107583 53808 107583 53839 107584 53808 107584 53841 107584 53841 107585 53808 107585 53810 107585 53841 107586 53810 107586 53842 107586 53842 107587 53810 107587 53811 107587 53842 107588 53811 107588 53832 107588 53832 107589 53811 107589 53833 107589 53832 107590 53833 107590 53845 107590 53845 107591 53833 107591 53814 107591 53845 107592 53814 107592 53834 107592 53834 107593 53814 107593 53835 107593 53834 107594 53835 107594 53836 107594 53836 107595 53835 107595 54101 107595 53836 107596 54101 107596 54099 107596 53819 107597 53837 107597 53838 107597 53838 107598 53837 107598 53831 107598 53838 107599 53831 107599 53818 107599 53818 107600 53831 107600 53839 107600 53818 107601 53839 107601 53840 107601 53840 107602 53839 107602 53841 107602 53840 107603 53841 107603 53816 107603 53816 107604 53841 107604 53842 107604 53816 107605 53842 107605 53905 107605 53905 107606 53842 107606 53832 107606 53905 107607 53832 107607 53843 107607 53843 107608 53832 107608 53845 107608 53843 107609 53845 107609 53844 107609 53844 107610 53845 107610 53834 107610 53844 107611 53834 107611 53846 107611 53846 107612 53834 107612 53836 107612 53846 107613 53836 107613 53847 107613 53847 107614 53836 107614 53848 107614 53847 107615 53848 107615 53910 107615 53854 107616 53849 107616 54454 107616 54454 107617 53849 107617 53855 107617 54454 107618 53855 107618 53850 107618 53850 107619 53855 107619 53857 107619 53850 107620 53857 107620 53851 107620 53851 107621 53857 107621 53852 107621 53851 107622 53852 107622 53788 107622 53788 107623 53852 107623 53790 107623 53788 107624 53790 107624 53789 107624 53789 107625 53790 107625 54084 107625 53789 107626 54084 107626 53853 107626 53854 107627 53887 107627 53849 107627 53849 107628 53887 107628 53856 107628 53849 107629 53856 107629 53855 107629 53855 107630 53856 107630 53883 107630 53855 107631 53883 107631 53857 107631 53857 107632 53883 107632 53882 107632 53857 107633 53882 107633 53852 107633 53852 107634 53882 107634 53880 107634 53852 107635 53880 107635 53790 107635 53790 107636 53880 107636 53858 107636 53790 107637 53858 107637 53859 107637 53859 107638 53858 107638 53860 107638 53859 107639 53860 107639 54086 107639 54463 107640 53877 107640 53787 107640 53787 107641 53877 107641 53876 107641 53787 107642 53876 107642 53786 107642 53786 107643 53876 107643 53861 107643 53786 107644 53861 107644 53886 107644 53886 107645 53861 107645 53874 107645 53886 107646 53874 107646 53885 107646 53885 107647 53874 107647 53872 107647 53885 107648 53872 107648 53884 107648 53884 107649 53872 107649 53870 107649 53884 107650 53870 107650 53881 107650 53881 107651 53870 107651 53868 107651 53881 107652 53868 107652 53862 107652 53862 107653 53868 107653 53866 107653 53862 107654 53866 107654 53863 107654 53863 107655 53866 107655 53864 107655 53863 107656 53864 107656 54089 107656 54092 107657 53775 107657 53865 107657 53865 107658 53775 107658 53866 107658 53865 107659 53866 107659 53867 107659 53867 107660 53866 107660 53868 107660 53867 107661 53868 107661 53869 107661 53869 107662 53868 107662 53870 107662 53869 107663 53870 107663 53871 107663 53871 107664 53870 107664 53872 107664 53871 107665 53872 107665 53873 107665 53873 107666 53872 107666 53874 107666 53873 107667 53874 107667 53875 107667 53875 107668 53874 107668 53861 107668 53875 107669 53861 107669 53894 107669 53894 107670 53861 107670 53876 107670 53894 107671 53876 107671 53892 107671 53892 107672 53876 107672 53877 107672 53892 107673 53877 107673 53878 107673 53878 107674 53877 107674 54463 107674 53878 107675 54463 107675 53879 107675 53879 107676 54463 107676 54462 107676 53879 107677 54462 107677 54460 107677 116271 107678 53792 107678 53863 107678 53863 107679 53792 107679 53858 107679 53863 107680 53858 107680 53862 107680 53862 107681 53858 107681 53880 107681 53862 107682 53880 107682 53881 107682 53881 107683 53880 107683 53882 107683 53881 107684 53882 107684 53884 107684 53884 107685 53882 107685 53883 107685 53884 107686 53883 107686 53885 107686 53885 107687 53883 107687 53856 107687 53885 107688 53856 107688 53886 107688 53886 107689 53856 107689 53887 107689 53886 107690 53887 107690 53786 107690 53786 107691 53887 107691 53770 107691 53786 107692 53770 107692 54459 107692 54431 107693 51177 107693 54466 107693 54466 107694 51177 107694 53802 107694 54466 107695 53802 107695 53888 107695 53888 107696 53802 107696 53889 107696 53888 107697 53889 107697 54479 107697 54479 107698 53889 107698 53891 107698 54479 107699 53891 107699 53890 107699 53890 107700 53891 107700 53796 107700 53890 107701 53796 107701 53879 107701 53879 107702 53796 107702 53800 107702 53879 107703 53800 107703 53878 107703 53878 107704 53800 107704 53801 107704 53878 107705 53801 107705 53892 107705 53892 107706 53801 107706 53893 107706 53892 107707 53893 107707 53894 107707 53894 107708 53893 107708 53904 107708 53894 107709 53904 107709 53875 107709 53875 107710 53904 107710 53906 107710 53875 107711 53906 107711 53873 107711 53873 107712 53906 107712 53907 107712 53873 107713 53907 107713 53871 107713 53871 107714 53907 107714 53908 107714 53871 107715 53908 107715 53869 107715 53869 107716 53908 107716 53895 107716 53869 107717 53895 107717 53867 107717 53867 107718 53895 107718 53909 107718 53867 107719 53909 107719 53865 107719 53865 107720 53909 107720 53896 107720 53865 107721 53896 107721 54093 107721 51178 107722 53780 107722 53897 107722 53897 107723 53780 107723 53782 107723 53897 107724 53782 107724 53898 107724 53898 107725 53782 107725 53899 107725 53898 107726 53899 107726 53901 107726 53901 107727 53899 107727 53900 107727 53901 107728 53900 107728 53902 107728 53902 107729 53900 107729 53794 107729 53902 107730 53794 107730 53801 107730 53801 107731 53794 107731 53903 107731 53801 107732 53903 107732 53893 107732 53893 107733 53903 107733 53816 107733 53893 107734 53816 107734 53904 107734 53904 107735 53816 107735 53905 107735 53904 107736 53905 107736 53906 107736 53906 107737 53905 107737 53843 107737 53906 107738 53843 107738 53907 107738 53907 107739 53843 107739 53844 107739 53907 107740 53844 107740 53908 107740 53908 107741 53844 107741 53846 107741 53908 107742 53846 107742 53895 107742 53895 107743 53846 107743 53847 107743 53895 107744 53847 107744 53909 107744 53909 107745 53847 107745 53910 107745 53909 107746 53910 107746 53896 107746 53931 107747 53961 107747 53962 107747 53974 107748 53911 107748 53930 107748 53954 107749 53912 107749 53913 107749 53972 107750 49987 107750 53931 107750 54071 107751 54069 107751 53963 107751 53963 107752 54069 107752 53964 107752 53914 107753 53976 107753 53930 107753 53915 107754 51218 107754 53916 107754 53940 107755 51221 107755 53942 107755 53917 107756 51226 107756 53945 107756 53919 107757 51233 107757 54389 107757 51226 107758 53918 107758 53945 107758 53945 107759 53918 107759 53919 107759 53945 107760 53919 107760 53936 107760 53946 107761 51228 107761 53917 107761 53939 107762 51231 107762 53937 107762 53937 107763 51231 107763 51229 107763 53938 107764 51223 107764 51225 107764 53979 107765 51214 107765 53920 107765 53920 107766 51214 107766 51213 107766 53920 107767 51213 107767 53921 107767 53921 107768 51213 107768 51216 107768 53921 107769 51216 107769 53922 107769 53923 107770 53992 107770 54065 107770 54065 107771 53992 107771 53927 107771 54065 107772 53927 107772 54064 107772 54064 107773 53927 107773 53926 107773 53957 107774 54061 107774 53924 107774 53924 107775 54061 107775 54062 107775 53924 107776 54062 107776 53925 107776 53925 107777 54062 107777 53926 107777 53925 107778 53926 107778 53994 107778 53994 107779 53926 107779 53927 107779 53974 107780 53928 107780 53911 107780 53911 107781 53928 107781 53929 107781 53911 107782 53929 107782 53930 107782 53930 107783 53929 107783 115926 107783 53930 107784 115926 107784 53914 107784 49987 107785 49997 107785 53931 107785 53931 107786 49997 107786 53960 107786 53931 107787 53960 107787 53961 107787 53932 107788 54020 107788 53933 107788 53933 107789 54020 107789 54010 107789 53933 107790 54010 107790 54397 107790 54046 107791 54396 107791 53934 107791 54049 107792 54050 107792 54393 107792 54393 107793 54050 107793 53935 107793 53919 107794 54389 107794 53936 107794 53936 107795 54389 107795 54391 107795 53936 107796 54391 107796 53947 107796 53947 107797 54391 107797 54395 107797 53947 107798 54395 107798 53948 107798 54053 107799 53938 107799 53937 107799 53937 107800 53938 107800 51225 107800 53937 107801 51225 107801 53939 107801 51220 107802 53940 107802 53941 107802 53941 107803 53940 107803 53942 107803 53941 107804 53942 107804 53944 107804 53944 107805 53942 107805 54054 107805 53944 107806 54054 107806 53953 107806 53949 107807 54053 107807 53943 107807 53943 107808 54053 107808 53937 107808 53943 107809 53937 107809 53946 107809 53946 107810 53937 107810 51229 107810 53946 107811 51229 107811 51228 107811 51218 107812 51220 107812 53916 107812 53916 107813 51220 107813 53941 107813 53916 107814 53941 107814 54025 107814 54025 107815 53941 107815 53944 107815 54025 107816 53944 107816 54026 107816 54026 107817 53944 107817 53953 107817 54026 107818 53953 107818 53952 107818 54048 107819 54047 107819 54028 107819 54028 107820 54047 107820 54045 107820 54028 107821 54045 107821 54027 107821 53917 107822 53945 107822 53946 107822 53946 107823 53945 107823 53936 107823 53946 107824 53936 107824 53943 107824 53943 107825 53936 107825 53947 107825 53943 107826 53947 107826 53949 107826 53949 107827 53947 107827 53948 107827 53949 107828 53948 107828 54050 107828 54050 107829 53948 107829 54394 107829 54050 107830 54394 107830 53935 107830 54029 107831 53950 107831 53951 107831 53951 107832 53950 107832 53952 107832 53951 107833 53952 107833 54051 107833 54051 107834 53952 107834 53953 107834 54051 107835 53953 107835 54052 107835 54052 107836 53953 107836 54054 107836 54046 107837 54009 107837 53954 107837 53996 107838 53955 107838 53957 107838 53957 107839 53955 107839 53956 107839 53957 107840 53956 107840 54061 107840 53954 107841 54009 107841 53912 107841 53912 107842 54009 107842 53958 107842 53912 107843 53958 107843 53913 107843 53913 107844 53958 107844 53959 107844 53913 107845 53959 107845 54014 107845 53960 107846 54072 107846 53961 107846 53961 107847 54072 107847 54071 107847 53961 107848 54071 107848 53962 107848 53962 107849 54071 107849 53963 107849 53962 107850 53963 107850 53974 107850 53974 107851 53963 107851 53964 107851 53974 107852 53964 107852 53928 107852 54034 107853 54015 107853 53965 107853 53965 107854 54015 107854 53966 107854 53965 107855 53966 107855 54033 107855 54033 107856 53966 107856 53968 107856 54033 107857 53968 107857 53967 107857 53967 107858 53968 107858 53969 107858 53967 107859 53969 107859 54031 107859 54031 107860 53969 107860 54019 107860 54031 107861 54019 107861 53970 107861 53970 107862 54019 107862 54021 107862 53970 107863 54021 107863 54030 107863 54030 107864 54021 107864 54022 107864 53971 107865 53972 107865 53973 107865 53973 107866 53972 107866 53931 107866 53973 107867 53931 107867 54001 107867 54001 107868 53931 107868 53962 107868 54001 107869 53962 107869 53999 107869 53999 107870 53962 107870 53974 107870 53999 107871 53974 107871 53975 107871 53975 107872 53974 107872 53930 107872 53975 107873 53930 107873 53996 107873 53996 107874 53930 107874 53976 107874 53996 107875 53976 107875 53955 107875 53955 107876 53976 107876 54056 107876 53955 107877 54056 107877 53956 107877 53922 107878 53977 107878 53921 107878 53921 107879 53977 107879 53978 107879 53921 107880 53978 107880 53920 107880 53920 107881 53978 107881 54013 107881 53920 107882 54013 107882 53979 107882 53979 107883 54013 107883 54012 107883 53980 107884 54403 107884 53981 107884 53981 107885 54403 107885 54000 107885 53981 107886 54000 107886 54032 107886 54032 107887 54000 107887 53982 107887 54032 107888 53982 107888 53983 107888 53983 107889 53982 107889 53998 107889 53983 107890 53998 107890 53984 107890 53984 107891 53998 107891 53997 107891 53984 107892 53997 107892 53985 107892 53985 107893 53997 107893 53986 107893 53985 107894 53986 107894 53987 107894 53987 107895 53986 107895 53988 107895 53987 107896 53988 107896 54035 107896 54035 107897 53988 107897 53995 107897 54035 107898 53995 107898 54036 107898 54036 107899 53995 107899 53989 107899 54036 107900 53989 107900 53991 107900 53991 107901 53989 107901 53990 107901 53991 107902 53990 107902 54037 107902 54037 107903 53990 107903 53993 107903 53992 107904 53993 107904 53927 107904 53927 107905 53993 107905 53990 107905 53927 107906 53990 107906 53994 107906 53994 107907 53990 107907 53989 107907 53994 107908 53989 107908 53925 107908 53925 107909 53989 107909 53995 107909 53925 107910 53995 107910 53924 107910 53924 107911 53995 107911 53988 107911 53924 107912 53988 107912 53957 107912 53957 107913 53988 107913 53986 107913 53957 107914 53986 107914 53996 107914 53996 107915 53986 107915 53997 107915 53996 107916 53997 107916 53975 107916 53975 107917 53997 107917 53998 107917 53975 107918 53998 107918 53999 107918 53999 107919 53998 107919 53982 107919 53999 107920 53982 107920 54001 107920 54001 107921 53982 107921 54000 107921 54001 107922 54000 107922 53973 107922 53973 107923 54000 107923 54403 107923 53973 107924 54403 107924 53971 107924 54034 107925 54002 107925 54005 107925 54005 107926 54002 107926 54003 107926 54005 107927 54003 107927 54004 107927 54004 107928 54006 107928 54005 107928 54005 107929 54006 107929 54007 107929 54005 107930 54007 107930 54016 107930 54016 107931 54007 107931 54014 107931 54016 107932 54014 107932 54008 107932 54008 107933 54014 107933 53959 107933 54008 107934 53959 107934 54017 107934 54017 107935 53959 107935 53958 107935 54017 107936 53958 107936 54018 107936 54018 107937 53958 107937 54009 107937 54018 107938 54009 107938 54020 107938 54020 107939 54009 107939 54046 107939 54020 107940 54046 107940 54010 107940 54010 107941 54046 107941 53934 107941 54010 107942 53934 107942 54397 107942 54040 107943 54012 107943 54011 107943 54011 107944 54012 107944 54013 107944 54011 107945 54013 107945 54039 107945 54039 107946 54013 107946 53978 107946 54039 107947 53978 107947 54038 107947 54038 107948 53978 107948 53977 107948 54038 107949 53977 107949 54004 107949 54004 107950 53977 107950 53922 107950 54004 107951 53922 107951 54006 107951 54006 107952 53922 107952 54043 107952 54006 107953 54043 107953 54007 107953 54007 107954 54043 107954 54044 107954 54007 107955 54044 107955 54014 107955 54034 107956 54005 107956 54015 107956 54015 107957 54005 107957 54016 107957 54015 107958 54016 107958 53966 107958 53966 107959 54016 107959 54008 107959 53966 107960 54008 107960 53968 107960 53968 107961 54008 107961 54017 107961 53968 107962 54017 107962 53969 107962 53969 107963 54017 107963 54018 107963 53969 107964 54018 107964 54019 107964 54019 107965 54018 107965 54020 107965 54019 107966 54020 107966 54021 107966 54021 107967 54020 107967 53932 107967 54021 107968 53932 107968 54022 107968 54041 107969 53915 107969 54042 107969 54042 107970 53915 107970 53916 107970 54042 107971 53916 107971 54023 107971 54023 107972 53916 107972 54025 107972 54023 107973 54025 107973 54024 107973 54024 107974 54025 107974 54026 107974 54024 107975 54026 107975 54027 107975 54027 107976 54026 107976 53952 107976 54027 107977 53952 107977 54028 107977 54028 107978 53952 107978 53950 107978 54028 107979 53950 107979 54048 107979 54048 107980 53950 107980 54029 107980 54022 107981 53980 107981 54030 107981 54030 107982 53980 107982 53981 107982 54030 107983 53981 107983 53970 107983 53970 107984 53981 107984 54032 107984 53970 107985 54032 107985 54031 107985 54031 107986 54032 107986 53983 107986 54031 107987 53983 107987 53967 107987 53967 107988 53983 107988 53984 107988 53967 107989 53984 107989 54033 107989 54033 107990 53984 107990 53985 107990 54033 107991 53985 107991 53965 107991 53965 107992 53985 107992 53987 107992 53965 107993 53987 107993 54034 107993 54034 107994 53987 107994 54035 107994 54034 107995 54035 107995 54002 107995 54002 107996 54035 107996 54036 107996 54002 107997 54036 107997 54003 107997 54003 107998 54036 107998 53991 107998 54003 107999 53991 107999 54004 107999 54004 108000 53991 108000 54037 108000 54004 108001 54037 108001 54038 108001 54038 108002 54037 108002 53993 108002 54038 108003 53993 108003 54039 108003 54039 108004 53993 108004 53992 108004 54039 108005 53992 108005 54011 108005 54011 108006 53992 108006 53923 108006 54011 108007 53923 108007 54040 108007 51216 108008 54041 108008 53922 108008 53922 108009 54041 108009 54042 108009 53922 108010 54042 108010 54043 108010 54043 108011 54042 108011 54023 108011 54043 108012 54023 108012 54044 108012 54044 108013 54023 108013 54024 108013 54044 108014 54024 108014 54014 108014 54014 108015 54024 108015 54027 108015 54014 108016 54027 108016 53913 108016 53913 108017 54027 108017 54045 108017 53913 108018 54045 108018 53954 108018 53954 108019 54045 108019 54047 108019 53954 108020 54047 108020 54046 108020 54046 108021 54047 108021 54048 108021 54046 108022 54048 108022 54396 108022 54396 108023 54048 108023 54029 108023 54396 108024 54029 108024 54049 108024 54049 108025 54029 108025 53951 108025 54049 108026 53951 108026 54050 108026 54050 108027 53951 108027 54051 108027 54050 108028 54051 108028 53949 108028 53949 108029 54051 108029 54052 108029 53949 108030 54052 108030 54053 108030 54053 108031 54052 108031 54054 108031 54053 108032 54054 108032 53938 108032 53938 108033 54054 108033 53942 108033 53938 108034 53942 108034 51223 108034 51223 108035 53942 108035 51221 108035 115926 108036 53929 108036 54055 108036 54055 108037 53929 108037 54067 108037 115926 108038 54055 108038 53914 108038 53914 108039 54055 108039 51465 108039 53914 108040 51465 108040 53976 108040 53976 108041 51465 108041 51474 108041 53976 108042 51474 108042 54056 108042 51474 108043 51470 108043 54056 108043 54056 108044 51470 108044 54057 108044 54056 108045 54057 108045 53956 108045 53956 108046 54057 108046 54058 108046 53956 108047 54058 108047 54061 108047 51235 108048 54059 108048 54060 108048 54060 108049 54059 108049 51247 108049 54061 108050 54058 108050 54062 108050 54062 108051 54058 108051 51478 108051 54062 108052 51478 108052 53926 108052 53926 108053 51478 108053 54059 108053 53926 108054 54059 108054 54064 108054 54064 108055 54059 108055 51235 108055 54064 108056 51235 108056 54063 108056 54063 108057 51236 108057 54064 108057 54064 108058 51236 108058 51237 108058 54064 108059 51237 108059 54065 108059 54065 108060 51237 108060 54066 108060 54065 108061 54066 108061 53923 108061 53929 108062 53928 108062 54067 108062 54067 108063 53928 108063 53964 108063 54067 108064 53964 108064 54068 108064 54068 108065 53964 108065 54069 108065 54068 108066 54069 108066 54070 108066 54070 108067 54069 108067 54071 108067 54070 108068 54071 108068 51443 108068 51443 108069 54071 108069 54072 108069 51443 108070 54072 108070 54074 108070 49997 108071 49995 108071 53960 108071 53960 108072 49995 108072 54072 108072 49995 108073 50004 108073 54072 108073 54072 108074 50004 108074 54073 108074 54072 108075 54073 108075 54074 108075 54074 108076 54073 108076 54075 108076 54074 108077 54075 108077 50000 108077 54309 108078 51451 108078 54076 108078 54309 108079 54076 108079 50000 108079 50000 108080 54076 108080 54077 108080 50000 108081 54077 108081 54074 108081 51173 108082 51174 108082 54100 108082 54078 108083 50165 108083 54082 108083 54078 108084 54082 108084 54080 108084 51283 108085 54344 108085 50177 108085 51283 108086 50177 108086 54081 108086 50177 108087 54079 108087 54081 108087 54081 108088 54079 108088 50175 108088 54081 108089 50175 108089 50173 108089 50173 108090 54080 108090 54081 108090 54081 108091 54080 108091 54082 108091 54081 108092 54082 108092 51288 108092 51288 108093 54082 108093 53853 108093 51288 108094 53853 108094 54083 108094 54083 108095 53853 108095 54084 108095 54083 108096 54084 108096 54085 108096 54085 108097 54084 108097 53791 108097 54085 108098 53791 108098 54087 108098 53791 108099 54086 108099 54087 108099 54087 108100 54086 108100 53860 108100 54087 108101 53860 108101 51280 108101 53860 108102 54088 108102 51280 108102 51280 108103 54088 108103 116271 108103 51280 108104 116271 108104 54090 108104 54090 108105 116271 108105 54089 108105 54090 108106 54089 108106 51260 108106 51260 108107 54089 108107 53864 108107 51260 108108 53864 108108 54091 108108 54091 108109 53864 108109 54092 108109 54091 108110 54092 108110 51259 108110 54092 108111 54093 108111 51259 108111 51259 108112 54093 108112 53896 108112 51259 108113 53896 108113 51258 108113 51172 108114 54094 108114 54101 108114 54095 108115 54096 108115 53821 108115 53821 108116 54096 108116 54097 108116 53821 108117 54097 108117 54101 108117 54101 108118 54097 108118 51171 108118 54101 108119 51171 108119 51172 108119 53896 108120 53910 108120 51258 108120 51258 108121 53910 108121 53848 108121 51258 108122 53848 108122 54098 108122 54098 108123 53848 108123 54099 108123 54098 108124 54099 108124 54100 108124 54100 108125 54099 108125 54101 108125 54100 108126 54101 108126 51173 108126 51173 108127 54101 108127 54094 108127 54143 108128 54105 108128 54142 108128 54599 108129 54600 108129 50964 108129 54102 108130 54103 108130 54120 108130 54120 108131 54103 108131 54104 108131 50862 108132 50864 108132 50942 108132 54107 108133 50977 108133 54105 108133 54105 108134 50977 108134 54106 108134 54105 108135 54106 108135 54142 108135 54131 108136 50980 108136 54107 108136 54107 108137 50980 108137 50978 108137 54107 108138 50978 108138 50977 108138 54134 108139 54108 108139 54109 108139 54109 108140 54108 108140 54110 108140 54109 108141 54110 108141 54111 108141 50835 108142 54112 108142 54113 108142 54113 108143 54112 108143 53186 108143 54113 108144 53186 108144 54114 108144 54114 108145 53186 108145 53184 108145 54114 108146 53184 108146 50864 108146 50864 108147 53184 108147 54138 108147 50864 108148 54138 108148 50942 108148 50862 108149 50942 108149 54115 108149 54115 108150 50942 108150 54116 108150 54115 108151 54116 108151 54117 108151 54117 108152 54116 108152 50941 108152 54117 108153 50941 108153 50861 108153 54118 108154 54119 108154 50967 108154 50967 108155 54119 108155 50958 108155 54102 108156 54119 108156 54103 108156 54103 108157 54119 108157 54118 108157 54103 108158 54118 108158 54600 108158 54600 108159 54118 108159 50966 108159 54600 108160 50966 108160 50964 108160 54104 108161 54112 108161 54120 108161 54120 108162 54112 108162 50835 108162 54120 108163 50835 108163 50955 108163 50955 108164 50835 108164 54121 108164 50955 108165 54121 108165 54140 108165 54140 108166 54121 108166 50831 108166 54122 108167 54123 108167 54124 108167 54124 108168 54123 108168 54125 108168 54124 108169 54125 108169 50940 108169 54150 108170 54126 108170 50970 108170 50970 108171 54126 108171 54127 108171 50970 108172 54127 108172 54128 108172 54153 108173 50979 108173 54129 108173 54129 108174 50979 108174 54130 108174 54129 108175 54130 108175 54131 108175 54131 108176 54130 108176 54132 108176 54131 108177 54132 108177 50980 108177 54153 108178 54159 108178 54133 108178 54133 108179 54159 108179 50945 108179 54109 108180 53214 108180 54134 108180 54134 108181 53214 108181 53215 108181 54134 108182 53215 108182 50960 108182 50960 108183 53215 108183 50957 108183 50952 108184 50828 108184 54135 108184 54135 108185 50828 108185 54136 108185 54135 108186 54136 108186 54504 108186 50940 108187 54125 108187 50941 108187 50941 108188 54125 108188 54137 108188 50941 108189 54137 108189 50861 108189 54150 108190 54139 108190 54138 108190 54138 108191 54139 108191 50943 108191 54138 108192 50943 108192 50942 108192 50831 108193 50834 108193 54140 108193 54140 108194 50834 108194 54141 108194 54140 108195 54141 108195 50952 108195 50952 108196 54141 108196 50832 108196 50952 108197 50832 108197 50828 108197 54147 108198 53215 108198 54616 108198 54616 108199 53215 108199 54158 108199 54616 108200 54158 108200 54613 108200 54142 108201 50967 108201 54143 108201 54143 108202 50967 108202 50958 108202 54143 108203 50958 108203 54144 108203 54144 108204 50958 108204 50957 108204 54144 108205 50957 108205 54145 108205 54145 108206 50957 108206 53215 108206 54145 108207 53215 108207 54146 108207 54146 108208 53215 108208 54147 108208 54599 108209 50964 108209 54148 108209 54148 108210 50964 108210 54149 108210 54148 108211 54149 108211 54128 108211 54128 108212 54149 108212 50971 108212 54128 108213 50971 108213 50970 108213 50970 108214 50974 108214 54150 108214 54150 108215 50974 108215 50972 108215 54150 108216 50972 108216 54139 108216 54139 108217 50972 108217 50979 108217 54139 108218 50979 108218 54151 108218 54151 108219 50979 108219 54153 108219 54151 108220 54153 108220 54152 108220 54152 108221 54153 108221 54133 108221 54154 108222 54155 108222 53198 108222 53198 108223 54155 108223 54157 108223 53198 108224 54157 108224 54156 108224 54156 108225 54157 108225 50946 108225 54156 108226 50946 108226 54158 108226 54158 108227 50946 108227 50945 108227 54158 108228 50945 108228 54613 108228 54613 108229 50945 108229 54159 108229 52814 108230 54160 108230 50581 108230 50581 108231 54160 108231 54161 108231 54162 108232 54163 108232 54164 108232 54164 108233 54163 108233 53075 108233 54165 108234 52052 108234 54627 108234 54627 108235 52052 108235 52946 108235 54627 108236 52946 108236 54626 108236 54626 108237 52946 108237 54168 108237 54626 108238 54168 108238 54625 108238 54171 108239 52049 108239 54165 108239 54165 108240 52049 108240 52050 108240 54165 108241 52050 108241 52052 108241 54164 108242 54166 108242 54162 108242 54162 108243 54166 108243 54167 108243 54162 108244 54167 108244 52722 108244 52722 108245 54167 108245 54170 108245 52722 108246 54170 108246 52721 108246 54163 108247 54621 108247 53075 108247 53075 108248 54621 108248 54622 108248 53075 108249 54622 108249 54168 108249 54168 108250 54622 108250 54169 108250 54168 108251 54169 108251 54625 108251 54170 108252 52059 108252 52721 108252 52721 108253 52059 108253 54172 108253 52721 108254 54172 108254 54171 108254 54171 108255 54172 108255 52046 108255 54171 108256 52046 108256 52049 108256 54180 108257 54174 108257 54173 108257 54173 108258 54174 108258 54176 108258 54174 108259 54175 108259 54176 108259 54176 108260 54175 108260 54177 108260 54176 108261 54177 108261 52880 108261 52880 108262 54177 108262 54635 108262 52146 108263 54179 108263 52708 108263 54635 108264 54637 108264 52880 108264 52880 108265 54637 108265 54178 108265 52880 108266 54178 108266 52153 108266 52153 108267 54178 108267 54639 108267 52153 108268 54639 108268 52152 108268 52152 108269 54639 108269 52707 108269 52146 108270 52147 108270 54179 108270 54179 108271 52147 108271 52149 108271 54179 108272 52149 108272 52707 108272 52707 108273 52149 108273 52151 108273 52707 108274 52151 108274 52152 108274 54173 108275 54181 108275 54180 108275 54180 108276 54181 108276 54182 108276 54180 108277 54182 108277 52709 108277 52709 108278 54182 108278 54183 108278 52709 108279 54183 108279 52708 108279 52708 108280 54183 108280 52130 108280 52708 108281 52130 108281 52146 108281 54184 108282 51170 108282 54185 108282 54185 108283 51170 108283 50397 108283 52940 108284 50288 108284 52942 108284 50404 108285 51193 108285 50414 108285 50414 108286 51193 108286 51191 108286 50414 108287 51191 108287 50413 108287 50413 108288 51191 108288 54186 108288 50413 108289 54186 108289 54187 108289 54187 108290 54186 108290 51189 108290 54187 108291 51189 108291 54188 108291 51189 108292 51187 108292 54188 108292 54188 108293 51187 108293 51185 108293 54188 108294 51185 108294 54189 108294 54189 108295 51185 108295 54190 108295 54189 108296 54190 108296 51184 108296 50288 108297 52940 108297 54199 108297 54199 108298 52940 108298 54191 108298 54199 108299 54191 108299 52935 108299 54264 108300 54265 108300 54192 108300 54192 108301 54265 108301 54193 108301 54192 108302 54193 108302 51227 108302 51227 108303 54193 108303 50275 108303 51227 108304 50275 108304 54194 108304 54194 108305 50275 108305 50295 108305 54194 108306 50295 108306 54196 108306 50295 108307 54195 108307 54196 108307 54196 108308 54195 108308 50293 108308 54196 108309 50293 108309 54197 108309 54197 108310 50293 108310 50291 108310 54197 108311 50291 108311 50290 108311 52922 108312 52927 108312 54203 108312 54203 108313 52927 108313 52916 108313 54203 108314 52916 108314 54202 108314 52935 108315 52933 108315 54199 108315 54199 108316 52933 108316 54198 108316 54199 108317 54198 108317 50290 108317 50290 108318 54198 108318 52937 108318 50290 108319 52937 108319 54197 108319 54197 108320 52937 108320 52939 108320 54197 108321 52939 108321 51232 108321 51232 108322 52939 108322 52922 108322 51232 108323 52922 108323 54200 108323 54200 108324 52922 108324 54203 108324 50360 108325 50361 108325 54240 108325 52918 108326 50308 108326 52917 108326 52917 108327 50308 108327 54201 108327 52917 108328 54201 108328 54202 108328 54202 108329 54201 108329 50305 108329 54202 108330 50305 108330 54203 108330 54203 108331 50305 108331 50301 108331 54203 108332 50301 108332 50302 108332 50302 108333 50300 108333 54203 108333 54203 108334 50300 108334 50298 108334 54203 108335 50298 108335 50297 108335 50297 108336 54204 108336 54203 108336 54203 108337 54204 108337 54205 108337 54203 108338 54205 108338 54213 108338 54213 108339 54205 108339 54206 108339 54213 108340 54206 108340 50320 108340 50310 108341 52868 108341 52867 108341 50337 108342 54207 108342 54208 108342 54230 108343 50354 108343 54209 108343 54210 108344 54221 108344 52832 108344 54210 108345 52832 108345 54212 108345 54212 108346 52832 108346 54211 108346 54212 108347 54211 108347 50333 108347 50320 108348 50312 108348 54213 108348 54213 108349 50312 108349 54214 108349 54213 108350 54214 108350 54238 108350 54215 108351 51208 108351 52836 108351 52836 108352 51208 108352 54213 108352 52836 108353 54213 108353 54216 108353 54215 108354 52831 108354 51208 108354 51208 108355 52831 108355 54217 108355 51208 108356 54217 108356 54219 108356 50329 108357 51208 108357 54218 108357 54218 108358 51208 108358 54219 108358 54218 108359 54219 108359 54210 108359 54210 108360 54219 108360 54220 108360 54210 108361 54220 108361 54221 108361 50329 108362 50327 108362 51208 108362 51208 108363 50327 108363 54222 108363 51208 108364 54222 108364 51207 108364 54222 108365 50325 108365 51207 108365 51207 108366 50325 108366 50334 108366 51207 108367 50334 108367 54223 108367 54223 108368 50334 108368 50335 108368 54223 108369 50335 108369 51204 108369 51204 108370 50335 108370 54224 108370 51204 108371 54224 108371 54225 108371 54225 108372 54224 108372 50344 108372 54225 108373 50344 108373 50342 108373 50342 108374 50340 108374 54225 108374 54225 108375 50340 108375 54236 108375 54225 108376 54236 108376 54226 108376 54226 108377 54227 108377 54225 108377 54225 108378 54227 108378 52821 108378 54225 108379 52821 108379 54240 108379 52821 108380 52786 108380 54240 108380 54240 108381 52786 108381 54228 108381 54240 108382 54228 108382 54229 108382 54229 108383 52788 108383 54240 108383 54240 108384 52788 108384 52787 108384 54240 108385 52787 108385 54234 108385 54230 108386 54209 108386 54231 108386 54231 108387 54209 108387 54232 108387 54231 108388 54232 108388 54233 108388 54233 108389 54232 108389 50357 108389 54233 108390 50357 108390 54234 108390 54235 108391 52825 108391 54236 108391 54236 108392 52825 108392 52824 108392 54236 108393 52824 108393 54226 108393 54235 108394 54236 108394 54208 108394 54208 108395 54236 108395 54237 108395 54208 108396 54237 108396 50337 108396 54216 108397 54213 108397 52872 108397 52872 108398 54213 108398 54238 108398 52872 108399 54238 108399 52871 108399 50310 108400 52867 108400 50317 108400 52867 108401 52866 108401 50317 108401 50317 108402 52866 108402 52865 108402 50317 108403 52865 108403 54238 108403 54238 108404 52865 108404 52869 108404 54238 108405 52869 108405 52871 108405 54234 108406 50357 108406 54240 108406 54240 108407 50357 108407 50358 108407 54240 108408 50358 108408 50360 108408 54239 108409 52898 108409 52897 108409 50361 108410 54241 108410 54240 108410 54240 108411 54241 108411 50368 108411 54240 108412 50368 108412 54242 108412 54242 108413 50368 108413 50366 108413 50366 108414 50375 108414 54242 108414 54242 108415 50375 108415 54243 108415 54242 108416 54243 108416 50374 108416 50374 108417 50373 108417 54242 108417 54242 108418 50373 108418 54244 108418 54242 108419 54244 108419 50372 108419 54239 108420 52897 108420 54245 108420 54245 108421 52897 108421 54246 108421 54245 108422 54246 108422 50372 108422 50372 108423 54246 108423 54242 108423 54242 108424 54246 108424 54247 108424 54242 108425 54247 108425 54249 108425 54249 108426 54247 108426 54248 108426 54249 108427 54248 108427 54250 108427 54250 108428 54248 108428 52902 108428 54250 108429 52902 108429 51176 108429 50415 108430 50417 108430 54252 108430 50415 108431 54252 108431 50421 108431 52902 108432 52904 108432 51176 108432 51176 108433 52904 108433 52905 108433 51176 108434 52905 108434 54252 108434 54252 108435 52905 108435 52906 108435 54252 108436 52906 108436 50421 108436 50421 108437 52906 108437 54251 108437 50417 108438 50419 108438 54252 108438 54252 108439 50419 108439 54253 108439 54252 108440 54253 108440 54254 108440 54254 108441 54253 108441 50407 108441 54254 108442 50407 108442 54255 108442 54255 108443 50407 108443 54256 108443 54255 108444 54256 108444 51181 108444 51181 108445 54256 108445 54257 108445 54257 108446 54256 108446 50406 108446 54257 108447 50406 108447 51183 108447 51183 108448 50406 108448 50408 108448 51183 108449 50408 108449 54258 108449 54258 108450 50408 108450 50409 108450 54258 108451 50409 108451 54260 108451 54260 108452 50409 108452 54259 108452 54260 108453 54259 108453 51184 108453 51184 108454 54259 108454 54261 108454 51184 108455 54261 108455 54189 108455 52906 108456 52907 108456 54251 108456 54251 108457 52907 108457 54262 108457 54251 108458 54262 108458 54263 108458 54263 108459 54262 108459 52892 108459 54263 108460 52892 108460 52891 108460 50282 108461 50277 108461 51222 108461 54264 108462 51230 108462 54265 108462 54265 108463 51230 108463 54266 108463 54265 108464 54266 108464 50278 108464 50278 108465 54266 108465 54267 108465 50278 108466 54267 108466 50277 108466 50277 108467 54267 108467 51224 108467 50277 108468 51224 108468 51222 108468 50272 108469 54268 108469 51217 108469 51217 108470 54268 108470 54271 108470 51222 108471 54269 108471 50282 108471 50282 108472 54269 108472 51219 108472 50282 108473 51219 108473 54270 108473 54270 108474 51219 108474 54271 108474 54270 108475 54271 108475 50284 108475 50284 108476 54271 108476 54268 108476 54272 108477 50263 108477 51212 108477 51212 108478 50263 108478 54274 108478 51217 108479 54273 108479 50272 108479 50272 108480 54273 108480 51215 108480 50272 108481 51215 108481 54274 108481 54274 108482 51215 108482 54275 108482 54274 108483 54275 108483 51212 108483 54272 108484 51211 108484 50263 108484 50263 108485 51211 108485 51240 108485 50263 108486 51240 108486 54276 108486 54276 108487 51240 108487 51239 108487 54276 108488 51239 108488 54277 108488 54277 108489 51239 108489 54278 108489 54277 108490 54278 108490 50264 108490 50264 108491 54278 108491 51238 108491 50264 108492 51238 108492 50265 108492 50265 108493 51238 108493 54279 108493 54279 108494 51238 108494 54280 108494 54279 108495 54280 108495 54281 108495 54281 108496 54280 108496 54282 108496 54281 108497 54282 108497 50267 108497 50267 108498 54282 108498 50268 108498 50268 108499 54282 108499 54283 108499 50268 108500 54283 108500 50270 108500 50270 108501 54283 108501 50271 108501 50271 108502 54283 108502 51234 108502 50271 108503 51234 108503 51245 108503 51245 108504 54284 108504 50271 108504 50271 108505 54284 108505 54285 108505 50271 108506 54285 108506 54289 108506 54289 108507 54285 108507 51242 108507 54289 108508 51242 108508 51241 108508 51241 108509 54286 108509 54289 108509 54289 108510 54286 108510 54287 108510 54289 108511 54287 108511 54288 108511 54288 108512 51250 108512 54289 108512 54289 108513 51250 108513 51085 108513 54289 108514 51085 108514 51087 108514 51199 108515 54290 108515 54291 108515 54291 108516 54290 108516 51197 108516 54291 108517 51197 108517 54292 108517 54292 108518 51197 108518 51195 108518 54292 108519 51195 108519 50404 108519 50404 108520 51195 108520 51194 108520 50404 108521 51194 108521 51193 108521 51170 108522 51202 108522 50397 108522 50397 108523 51202 108523 54293 108523 50397 108524 54293 108524 54291 108524 54291 108525 54293 108525 51200 108525 54291 108526 51200 108526 51199 108526 54185 108527 54294 108527 54184 108527 54184 108528 54294 108528 50400 108528 54184 108529 50400 108529 54295 108529 54295 108530 50400 108530 50402 108530 54295 108531 50402 108531 54296 108531 54296 108532 50402 108532 54297 108532 54296 108533 54297 108533 54307 108533 54307 108534 54297 108534 54298 108534 54307 108535 54298 108535 54299 108535 51159 108536 51154 108536 54300 108536 51159 108537 54300 108537 51157 108537 51157 108538 54300 108538 54301 108538 51157 108539 54301 108539 54521 108539 54300 108540 51169 108540 54301 108540 54301 108541 51169 108541 51165 108541 54301 108542 51165 108542 50403 108542 51165 108543 51164 108543 50403 108543 50403 108544 51164 108544 54302 108544 50403 108545 54302 108545 54303 108545 54303 108546 54302 108546 51175 108546 54303 108547 51175 108547 54304 108547 54304 108548 51175 108548 54305 108548 54304 108549 54305 108549 54299 108549 54299 108550 54305 108550 54306 108550 54299 108551 54306 108551 54307 108551 54783 108552 54318 108552 54319 108552 54330 108553 50024 108553 54329 108553 50024 108554 54330 108554 54308 108554 54308 108555 54330 108555 54316 108555 54308 108556 54316 108556 54309 108556 54312 108557 54320 108557 54310 108557 54310 108558 54320 108558 51418 108558 51339 108559 51340 108559 51006 108559 54310 108560 54311 108560 54312 108560 54312 108561 54311 108561 54313 108561 54312 108562 54313 108562 54314 108562 54314 108563 54313 108563 54315 108563 54314 108564 54315 108564 54316 108564 54316 108565 54315 108565 51451 108565 54316 108566 51451 108566 54309 108566 54317 108567 51424 108567 51423 108567 51006 108568 51340 108568 54318 108568 54318 108569 51340 108569 51341 108569 54318 108570 51341 108570 54319 108570 54352 108571 54342 108571 50062 108571 51418 108572 54320 108572 54321 108572 54321 108573 54320 108573 54332 108573 54321 108574 54332 108574 54322 108574 54317 108575 51423 108575 51010 108575 51424 108576 54317 108576 54323 108576 54323 108577 54317 108577 54781 108577 54323 108578 54781 108578 51377 108578 51339 108579 51006 108579 54324 108579 54324 108580 51006 108580 54334 108580 54324 108581 54334 108581 51337 108581 51004 108582 54336 108582 51332 108582 50010 108583 54326 108583 54325 108583 54325 108584 54326 108584 54327 108584 54325 108585 54327 108585 54328 108585 54328 108586 54327 108586 50060 108586 54328 108587 50060 108587 50041 108587 50041 108588 50060 108588 54342 108588 54329 108589 50036 108589 54330 108589 54330 108590 50036 108590 54338 108590 54330 108591 54338 108591 54779 108591 51423 108592 51421 108592 51010 108592 51010 108593 51421 108593 54331 108593 51010 108594 54331 108594 54332 108594 54332 108595 54331 108595 51420 108595 54332 108596 51420 108596 54322 108596 51332 108597 51333 108597 51004 108597 51004 108598 51333 108598 54333 108598 51004 108599 54333 108599 54334 108599 54334 108600 54333 108600 54335 108600 54334 108601 54335 108601 51337 108601 54345 108602 51303 108602 54336 108602 54336 108603 51303 108603 51302 108603 54336 108604 51302 108604 51332 108604 54361 108605 54353 108605 50064 108605 50064 108606 54353 108606 54337 108606 54338 108607 50056 108607 54779 108607 54779 108608 50056 108608 50037 108608 54779 108609 50037 108609 54352 108609 54352 108610 50037 108610 54339 108610 54352 108611 54339 108611 54340 108611 54340 108612 54341 108612 54352 108612 54352 108613 54341 108613 50039 108613 54352 108614 50039 108614 54342 108614 54342 108615 50039 108615 50040 108615 54342 108616 50040 108616 50041 108616 54446 108617 50216 108617 54355 108617 54355 108618 50216 108618 50217 108618 54343 108619 50177 108619 54789 108619 54789 108620 50177 108620 54344 108620 54789 108621 54344 108621 54345 108621 54345 108622 54344 108622 54346 108622 54345 108623 54346 108623 51303 108623 54347 108624 54348 108624 54343 108624 54343 108625 54348 108625 50184 108625 54343 108626 50184 108626 50177 108626 50231 108627 50232 108627 54349 108627 54349 108628 50232 108628 50236 108628 54349 108629 50236 108629 54787 108629 54350 108630 54359 108630 54358 108630 50129 108631 50140 108631 54785 108631 54785 108632 50140 108632 54351 108632 50062 108633 50063 108633 54352 108633 54352 108634 50063 108634 54354 108634 54352 108635 54354 108635 54353 108635 54353 108636 54354 108636 50065 108636 54353 108637 50065 108637 54337 108637 50217 108638 50227 108638 54355 108638 54355 108639 50227 108639 50229 108639 54355 108640 50229 108640 50230 108640 54351 108641 54355 108641 54785 108641 54785 108642 54355 108642 50230 108642 54785 108643 50230 108643 54349 108643 54349 108644 50230 108644 54356 108644 54349 108645 54356 108645 50231 108645 50236 108646 50224 108646 54787 108646 54787 108647 50224 108647 50223 108647 54787 108648 50223 108648 54343 108648 54343 108649 50223 108649 54357 108649 54343 108650 54357 108650 54347 108650 54358 108651 54359 108651 54785 108651 54785 108652 54359 108652 54360 108652 54785 108653 54360 108653 50129 108653 54361 108654 51380 108654 54353 108654 54353 108655 51380 108655 54362 108655 54353 108656 54362 108656 54781 108656 54781 108657 54362 108657 51378 108657 54781 108658 51378 108658 51377 108658 54363 108659 54368 108659 54364 108659 54364 108660 54368 108660 51383 108660 54364 108661 51383 108661 54361 108661 54361 108662 51383 108662 51382 108662 54361 108663 51382 108663 51380 108663 54365 108664 51346 108664 54358 108664 54358 108665 51346 108665 50110 108665 54358 108666 50110 108666 54350 108666 50111 108667 51374 108667 54366 108667 54366 108668 51374 108668 54368 108668 54366 108669 54368 108669 54367 108669 54367 108670 54368 108670 54363 108670 54319 108671 54369 108671 54783 108671 54783 108672 54369 108672 54370 108672 54783 108673 54370 108673 54358 108673 54358 108674 54370 108674 54371 108674 54358 108675 54371 108675 54365 108675 50111 108676 50119 108676 51374 108676 51374 108677 50119 108677 54372 108677 51374 108678 54372 108678 51343 108678 51343 108679 54372 108679 50110 108679 51343 108680 50110 108680 54373 108680 54373 108681 50110 108681 51346 108681 54049 108682 54393 108682 54374 108682 51206 108683 54375 108683 54432 108683 50083 108684 54376 108684 54380 108684 54440 108685 50135 108685 54377 108685 54377 108686 50135 108686 50136 108686 54377 108687 50136 108687 50105 108687 54387 108688 54378 108688 54379 108688 54379 108689 54378 108689 54377 108689 54379 108690 54377 108690 54380 108690 54380 108691 54377 108691 50105 108691 54380 108692 50105 108692 50083 108692 54423 108693 54432 108693 54381 108693 54381 108694 54432 108694 54433 108694 54381 108695 54433 108695 54422 108695 54422 108696 54433 108696 54382 108696 54422 108697 54382 108697 54420 108697 54420 108698 54382 108698 54383 108698 54420 108699 54383 108699 54419 108699 54419 108700 54383 108700 54385 108700 54419 108701 54385 108701 54384 108701 54384 108702 54385 108702 54386 108702 54384 108703 54386 108703 54418 108703 54418 108704 54386 108704 54438 108704 54418 108705 54438 108705 54387 108705 54387 108706 54438 108706 54436 108706 54387 108707 54436 108707 54378 108707 54423 108708 54426 108708 54432 108708 54432 108709 54426 108709 54388 108709 54432 108710 54388 108710 51206 108710 51233 108711 51210 108711 54389 108711 54389 108712 51210 108712 54390 108712 54389 108713 54390 108713 54391 108713 54391 108714 54390 108714 54392 108714 54391 108715 54392 108715 54395 108715 54393 108716 53935 108716 54374 108716 54374 108717 53935 108717 54394 108717 54374 108718 54394 108718 54392 108718 54392 108719 54394 108719 53948 108719 54392 108720 53948 108720 54395 108720 54049 108721 54374 108721 54396 108721 54396 108722 54374 108722 54413 108722 54396 108723 54413 108723 53934 108723 54413 108724 54415 108724 53934 108724 53934 108725 54415 108725 54400 108725 53934 108726 54400 108726 54397 108726 54412 108727 54398 108727 54399 108727 54399 108728 54398 108728 50019 108728 54399 108729 50019 108729 54404 108729 54405 108730 49978 108730 54403 108730 54397 108731 54400 108731 53933 108731 53933 108732 54400 108732 54401 108732 53933 108733 54401 108733 53932 108733 53932 108734 54401 108734 54402 108734 53932 108735 54402 108735 54022 108735 54022 108736 54402 108736 54417 108736 54022 108737 54417 108737 53980 108737 53980 108738 54417 108738 54399 108738 53980 108739 54399 108739 54403 108739 54403 108740 54399 108740 54404 108740 54403 108741 54404 108741 54405 108741 49978 108742 49980 108742 54403 108742 54403 108743 49980 108743 49979 108743 54403 108744 49979 108744 53971 108744 53971 108745 49979 108745 54406 108745 53971 108746 54406 108746 53972 108746 54412 108747 50010 108747 54407 108747 54407 108748 54408 108748 54412 108748 54412 108749 54408 108749 54409 108749 54412 108750 54409 108750 54398 108750 54326 108751 50010 108751 54410 108751 54410 108752 50010 108752 54412 108752 54410 108753 54412 108753 54411 108753 54411 108754 54412 108754 50090 108754 50090 108755 54412 108755 50091 108755 50091 108756 54412 108756 54399 108756 50091 108757 54399 108757 54416 108757 51210 108758 51209 108758 54390 108758 54390 108759 51209 108759 54425 108759 54390 108760 54425 108760 54392 108760 54392 108761 54425 108761 54424 108761 54392 108762 54424 108762 54374 108762 54374 108763 54424 108763 54414 108763 54374 108764 54414 108764 54413 108764 54413 108765 54414 108765 54421 108765 54413 108766 54421 108766 54415 108766 54376 108767 54416 108767 54380 108767 54380 108768 54416 108768 54399 108768 54380 108769 54399 108769 54379 108769 54379 108770 54399 108770 54417 108770 54379 108771 54417 108771 54387 108771 54387 108772 54417 108772 54402 108772 54387 108773 54402 108773 54418 108773 54418 108774 54402 108774 54401 108774 54418 108775 54401 108775 54384 108775 54384 108776 54401 108776 54400 108776 54384 108777 54400 108777 54419 108777 54419 108778 54400 108778 54415 108778 54419 108779 54415 108779 54420 108779 54420 108780 54415 108780 54421 108780 54420 108781 54421 108781 54422 108781 54422 108782 54421 108782 54414 108782 54422 108783 54414 108783 54381 108783 54381 108784 54414 108784 54424 108784 54381 108785 54424 108785 54423 108785 54423 108786 54424 108786 54425 108786 54423 108787 54425 108787 54426 108787 54426 108788 54425 108788 51209 108788 53770 108789 54473 108789 54457 108789 54432 108790 54476 108790 54427 108790 51205 108791 54428 108791 54475 108791 54475 108792 54428 108792 51203 108792 54475 108793 51203 108793 54429 108793 54429 108794 51203 108794 54430 108794 54429 108795 54430 108795 54478 108795 54478 108796 54430 108796 54431 108796 54432 108797 54375 108797 54474 108797 54432 108798 54427 108798 54433 108798 54433 108799 54427 108799 54434 108799 54433 108800 54434 108800 54382 108800 54382 108801 54434 108801 54383 108801 54383 108802 54434 108802 54469 108802 54383 108803 54469 108803 54385 108803 54385 108804 54469 108804 54435 108804 54385 108805 54435 108805 54439 108805 54378 108806 54436 108806 54437 108806 54437 108807 54436 108807 54438 108807 54437 108808 54438 108808 54439 108808 54439 108809 54438 108809 54386 108809 54439 108810 54386 108810 54385 108810 54437 108811 54455 108811 54378 108811 54378 108812 54455 108812 54456 108812 54378 108813 54456 108813 54377 108813 54377 108814 54456 108814 54444 108814 54377 108815 54444 108815 54440 108815 54355 108816 54442 108816 54441 108816 54441 108817 54442 108817 50144 108817 54441 108818 50144 108818 54456 108818 54456 108819 50144 108819 54443 108819 54456 108820 54443 108820 54444 108820 50204 108821 54445 108821 54441 108821 54441 108822 54445 108822 54446 108822 54441 108823 54446 108823 54355 108823 50156 108824 50172 108824 53850 108824 53850 108825 50172 108825 54447 108825 50196 108826 50206 108826 54456 108826 54456 108827 50206 108827 54448 108827 54456 108828 54448 108828 54441 108828 54441 108829 54448 108829 50205 108829 54441 108830 50205 108830 50204 108830 54449 108831 54451 108831 54450 108831 54450 108832 54451 108832 54452 108832 54450 108833 54452 108833 53850 108833 53850 108834 54452 108834 54453 108834 53850 108835 54453 108835 50156 108835 53854 108836 54454 108836 54455 108836 54455 108837 54454 108837 53850 108837 54455 108838 53850 108838 54456 108838 54456 108839 53850 108839 54447 108839 54456 108840 54447 108840 50196 108840 53770 108841 54457 108841 54459 108841 54470 108842 54458 108842 54471 108842 54471 108843 54458 108843 54459 108843 54471 108844 54459 108844 54472 108844 54472 108845 54459 108845 54457 108845 54465 108846 54460 108846 54461 108846 54461 108847 54460 108847 54462 108847 54461 108848 54462 108848 54470 108848 54470 108849 54462 108849 54463 108849 54470 108850 54463 108850 54458 108850 54465 108851 54464 108851 54477 108851 54477 108852 54479 108852 54465 108852 54465 108853 54479 108853 53890 108853 54465 108854 53890 108854 54460 108854 54431 108855 54466 108855 54478 108855 54478 108856 54466 108856 54467 108856 54478 108857 54467 108857 54468 108857 54476 108858 54464 108858 54427 108858 54427 108859 54464 108859 54465 108859 54427 108860 54465 108860 54434 108860 54434 108861 54465 108861 54461 108861 54434 108862 54461 108862 54469 108862 54469 108863 54461 108863 54470 108863 54469 108864 54470 108864 54435 108864 54435 108865 54470 108865 54471 108865 54435 108866 54471 108866 54439 108866 54439 108867 54471 108867 54472 108867 54439 108868 54472 108868 54437 108868 54437 108869 54472 108869 54457 108869 54437 108870 54457 108870 54455 108870 54455 108871 54457 108871 54473 108871 54455 108872 54473 108872 53854 108872 54474 108873 51205 108873 54432 108873 54432 108874 51205 108874 54475 108874 54432 108875 54475 108875 54476 108875 54476 108876 54475 108876 54429 108876 54476 108877 54429 108877 54464 108877 54464 108878 54429 108878 54478 108878 54464 108879 54478 108879 54477 108879 54477 108880 54478 108880 54468 108880 54477 108881 54468 108881 54479 108881 51364 108882 51621 108882 51634 108882 51634 108883 51621 108883 54480 108883 51634 108884 54480 108884 51632 108884 51026 108885 51025 108885 53767 108885 53767 108886 51025 108886 54481 108886 53767 108887 54481 108887 51268 108887 51268 108888 54481 108888 54482 108888 51268 108889 54482 108889 51271 108889 51271 108890 54482 108890 54483 108890 51271 108891 54483 108891 54484 108891 54484 108892 54483 108892 54485 108892 54484 108893 54485 108893 54486 108893 54486 108894 54485 108894 51022 108894 54486 108895 51022 108895 54487 108895 54487 108896 51022 108896 51020 108896 54487 108897 51020 108897 51273 108897 51273 108898 51020 108898 54488 108898 51273 108899 54488 108899 51605 108899 51605 108900 54488 108900 51035 108900 51043 108901 50924 108901 54489 108901 54489 108902 50924 108902 54490 108902 50916 108903 51046 108903 50921 108903 50921 108904 51046 108904 51045 108904 50921 108905 51045 108905 54491 108905 54491 108906 51045 108906 51044 108906 54491 108907 51044 108907 50919 108907 50919 108908 51044 108908 54492 108908 50919 108909 54492 108909 54490 108909 54490 108910 54492 108910 54493 108910 54490 108911 54493 108911 54489 108911 53220 108912 54494 108912 51037 108912 51037 108913 54494 108913 53410 108913 51046 108914 50916 108914 51053 108914 51053 108915 50916 108915 54495 108915 51053 108916 54495 108916 51052 108916 51052 108917 54495 108917 54496 108917 51052 108918 54496 108918 51050 108918 51050 108919 54496 108919 54497 108919 51050 108920 54497 108920 51048 108920 51048 108921 54497 108921 50914 108921 51048 108922 50914 108922 54498 108922 54498 108923 50914 108923 50910 108923 54498 108924 50910 108924 51055 108924 54499 108925 50784 108925 54505 108925 51530 108926 50793 108926 50786 108926 50893 108927 54507 108927 54501 108927 54501 108928 53210 108928 54500 108928 50893 108929 54501 108929 50896 108929 54500 108930 50994 108930 54501 108930 54501 108931 50994 108931 51548 108931 54501 108932 51548 108932 51530 108932 50847 108933 54502 108933 54503 108933 54503 108934 54502 108934 50897 108934 54503 108935 50897 108935 54136 108935 54136 108936 50897 108936 54504 108936 50897 108937 50896 108937 54504 108937 54504 108938 50896 108938 54501 108938 54504 108939 54501 108939 54505 108939 54505 108940 54501 108940 51530 108940 54505 108941 51530 108941 54499 108941 54499 108942 51530 108942 50786 108942 50903 108943 50902 108943 54506 108943 54506 108944 50902 108944 50900 108944 54506 108945 50900 108945 54507 108945 54507 108946 50900 108946 54508 108946 54507 108947 54508 108947 54501 108947 54512 108948 50647 108948 51517 108948 54513 108949 54509 108949 50929 108949 54509 108950 54513 108950 50926 108950 50926 108951 54513 108951 54796 108951 50926 108952 54796 108952 50923 108952 50923 108953 54796 108953 54799 108953 50923 108954 54799 108954 54510 108954 51956 108955 50664 108955 51517 108955 51517 108956 50664 108956 54511 108956 51517 108957 54511 108957 54512 108957 54122 108958 51956 108958 50933 108958 50933 108959 51956 108959 51517 108959 50933 108960 51517 108960 50932 108960 50932 108961 51517 108961 54513 108961 50932 108962 54513 108962 54514 108962 54514 108963 54513 108963 50929 108963 50933 108964 50935 108964 54122 108964 54122 108965 50935 108965 54515 108965 54122 108966 54515 108966 54123 108966 54123 108967 54515 108967 54517 108967 54123 108968 54517 108968 54516 108968 54516 108969 54517 108969 54518 108969 54516 108970 54518 108970 54519 108970 50382 108971 54551 108971 54520 108971 51152 108972 54521 108972 54301 108972 54301 108973 54525 108973 51152 108973 51152 108974 54525 108974 54526 108974 51152 108975 54526 108975 54522 108975 50427 108976 54549 108976 54523 108976 54523 108977 54549 108977 54554 108977 51121 108978 51151 108978 50394 108978 50394 108979 51151 108979 54524 108979 50394 108980 54524 108980 54525 108980 54525 108981 54524 108981 51149 108981 54525 108982 51149 108982 54526 108982 54527 108983 54528 108983 54530 108983 54289 108984 51087 108984 50259 108984 50259 108985 51087 108985 51088 108985 50259 108986 51088 108986 51097 108986 54529 108987 52198 108987 54566 108987 54544 108988 51143 108988 54543 108988 54543 108989 51143 108989 54527 108989 54543 108990 54527 108990 54536 108990 54536 108991 54527 108991 54530 108991 54536 108992 54530 108992 51504 108992 54528 108993 51139 108993 54530 108993 54530 108994 51139 108994 54531 108994 54530 108995 54531 108995 51507 108995 51507 108996 54531 108996 51134 108996 51507 108997 51134 108997 54520 108997 54520 108998 51134 108998 51133 108998 54520 108999 51133 108999 50382 108999 54548 109000 51486 109000 54532 109000 54554 109001 52260 109001 54535 109001 52266 109002 54545 109002 54533 109002 54533 109003 54545 109003 54776 109003 54533 109004 54776 109004 52267 109004 52267 109005 54776 109005 54774 109005 52267 109006 54774 109006 52261 109006 52261 109007 54774 109007 54534 109007 52261 109008 54534 109008 54535 109008 54535 109009 54534 109009 54557 109009 54535 109010 54557 109010 54554 109010 51504 109011 51503 109011 54536 109011 54536 109012 51503 109012 51501 109012 54536 109013 51501 109013 54557 109013 54557 109014 51501 109014 54762 109014 54557 109015 54762 109015 54537 109015 50394 109016 50391 109016 51121 109016 51121 109017 50391 109017 54538 109017 51121 109018 54538 109018 51122 109018 51122 109019 54538 109019 54539 109019 51122 109020 54539 109020 54540 109020 54540 109021 54539 109021 54558 109021 51486 109022 54548 109022 54541 109022 54541 109023 54548 109023 51103 109023 54541 109024 51103 109024 51487 109024 51487 109025 51103 109025 54542 109025 51487 109026 54542 109026 51489 109026 51489 109027 54542 109027 51104 109027 51489 109028 51104 109028 54543 109028 54543 109029 51104 109029 51100 109029 54543 109030 51100 109030 54544 109030 54545 109031 50245 109031 54776 109031 54776 109032 50245 109032 50246 109032 54776 109033 50246 109033 54547 109033 54547 109034 50246 109034 54546 109034 54547 109035 54546 109035 54532 109035 54532 109036 54546 109036 50249 109036 54532 109037 50249 109037 54548 109037 54548 109038 50249 109038 54575 109038 54548 109039 54575 109039 51108 109039 51097 109040 51093 109040 50259 109040 50259 109041 51093 109041 51092 109041 50259 109042 51092 109042 54568 109042 54549 109043 52250 109043 54554 109043 54554 109044 52250 109044 52253 109044 54554 109045 52253 109045 52254 109045 54550 109046 54555 109046 54557 109046 54561 109047 50384 109047 51133 109047 51133 109048 50384 109048 50383 109048 51133 109049 50383 109049 50382 109049 50382 109050 50381 109050 54551 109050 54551 109051 50381 109051 54552 109051 54551 109052 54552 109052 54757 109052 54757 109053 54552 109053 54553 109053 54757 109054 54553 109054 54759 109054 52254 109055 52257 109055 54554 109055 54554 109056 52257 109056 52256 109056 54554 109057 52256 109057 52260 109057 54555 109058 54556 109058 54557 109058 54557 109059 54556 109059 52192 109059 54557 109060 52192 109060 54554 109060 54539 109061 54559 109061 54558 109061 54558 109062 54559 109062 50387 109062 54558 109063 50387 109063 51128 109063 51128 109064 50387 109064 50386 109064 51128 109065 50386 109065 54560 109065 54560 109066 50386 109066 54562 109066 54560 109067 54562 109067 54561 109067 54561 109068 54562 109068 54563 109068 54561 109069 54563 109069 50384 109069 54553 109070 54564 109070 54759 109070 54759 109071 54564 109071 54529 109071 54759 109072 54529 109072 54565 109072 54565 109073 54529 109073 54566 109073 54565 109074 54566 109074 54537 109074 54537 109075 54566 109075 54567 109075 54537 109076 54567 109076 54557 109076 54557 109077 54567 109077 52190 109077 54557 109078 52190 109078 54550 109078 51092 109079 51090 109079 54568 109079 54568 109080 51090 109080 54569 109080 54568 109081 54569 109081 50261 109081 50261 109082 54569 109082 54571 109082 50261 109083 54571 109083 54570 109083 54570 109084 54571 109084 51117 109084 54570 109085 51117 109085 54572 109085 54572 109086 51117 109086 51115 109086 54572 109087 51115 109087 54573 109087 54573 109088 51115 109088 54574 109088 54575 109089 54576 109089 51108 109089 51108 109090 54576 109090 50257 109090 51108 109091 50257 109091 54577 109091 54577 109092 50257 109092 54579 109092 54577 109093 54579 109093 54578 109093 54578 109094 54579 109094 54580 109094 54578 109095 54580 109095 51113 109095 51113 109096 54580 109096 50254 109096 51113 109097 50254 109097 54574 109097 54574 109098 50254 109098 50252 109098 54574 109099 50252 109099 54573 109099 53195 109100 54582 109100 54589 109100 54581 109101 54582 109101 53195 109101 54585 109102 54581 109102 53195 109102 53195 109103 54583 109103 54593 109103 54584 109104 54583 109104 53195 109104 54589 109105 54584 109105 53195 109105 53192 109106 54586 109106 54585 109106 54585 109107 54586 109107 54581 109107 54586 109108 54587 109108 54581 109108 54581 109109 54587 109109 54601 109109 54581 109110 54601 109110 54582 109110 54601 109111 54598 109111 54582 109111 54582 109112 54598 109112 54588 109112 54582 109113 54588 109113 54589 109113 54588 109114 54590 109114 54589 109114 54589 109115 54590 109115 54591 109115 54589 109116 54591 109116 54584 109116 54591 109117 54592 109117 54584 109117 54584 109118 54592 109118 54597 109118 54584 109119 54597 109119 54583 109119 54595 109120 54593 109120 54596 109120 54596 109121 54593 109121 54583 109121 54596 109122 54583 109122 54594 109122 54594 109123 54583 109123 54597 109123 54126 109124 54150 109124 54595 109124 54595 109125 54596 109125 54126 109125 54126 109126 54596 109126 54594 109126 54126 109127 54594 109127 54127 109127 54594 109128 54597 109128 54127 109128 54127 109129 54597 109129 54592 109129 54127 109130 54592 109130 54128 109130 54592 109131 54591 109131 54128 109131 54128 109132 54591 109132 54590 109132 54128 109133 54590 109133 54148 109133 54148 109134 54590 109134 54588 109134 54148 109135 54588 109135 54599 109135 54588 109136 54598 109136 54599 109136 54599 109137 54598 109137 54601 109137 54599 109138 54601 109138 54600 109138 53192 109139 54103 109139 54586 109139 54586 109140 54103 109140 54600 109140 54586 109141 54600 109141 54587 109141 54587 109142 54600 109142 54601 109142 54602 109143 54608 109143 54603 109143 54605 109144 54608 109144 54602 109144 53176 109145 54605 109145 54602 109145 54602 109146 54610 109146 53172 109146 54604 109147 54610 109147 54602 109147 54603 109148 54604 109148 54602 109148 53171 109149 54620 109149 53176 109149 53176 109150 54620 109150 54605 109150 54620 109151 54606 109151 54605 109151 54605 109152 54606 109152 54607 109152 54605 109153 54607 109153 54608 109153 54607 109154 54609 109154 54608 109154 54608 109155 54609 109155 54619 109155 54608 109156 54619 109156 54603 109156 54619 109157 54618 109157 54603 109157 54603 109158 54618 109158 54617 109158 54603 109159 54617 109159 54604 109159 54617 109160 54615 109160 54604 109160 54604 109161 54615 109161 54614 109161 54604 109162 54614 109162 54610 109162 53173 109163 53172 109163 54611 109163 54611 109164 53172 109164 54610 109164 54611 109165 54610 109165 54612 109165 54612 109166 54610 109166 54614 109166 54159 109167 54153 109167 53173 109167 53173 109168 54611 109168 54159 109168 54159 109169 54611 109169 54612 109169 54159 109170 54612 109170 54613 109170 54612 109171 54614 109171 54613 109171 54613 109172 54614 109172 54615 109172 54613 109173 54615 109173 54616 109173 54615 109174 54617 109174 54616 109174 54616 109175 54617 109175 54618 109175 54616 109176 54618 109176 54147 109176 54147 109177 54618 109177 54619 109177 54147 109178 54619 109178 54146 109178 54619 109179 54609 109179 54146 109179 54146 109180 54609 109180 54607 109180 54146 109181 54607 109181 54145 109181 53171 109182 54144 109182 54620 109182 54620 109183 54144 109183 54145 109183 54620 109184 54145 109184 54606 109184 54606 109185 54145 109185 54607 109185 54163 109186 52724 109186 54621 109186 54621 109187 52724 109187 54623 109187 54621 109188 54623 109188 54622 109188 54622 109189 54623 109189 54629 109189 54622 109190 54629 109190 54169 109190 54169 109191 54629 109191 54624 109191 54169 109192 54624 109192 54625 109192 54625 109193 54624 109193 54631 109193 54625 109194 54631 109194 54626 109194 54626 109195 54631 109195 54632 109195 54626 109196 54632 109196 54627 109196 54627 109197 54632 109197 54628 109197 52724 109198 52929 109198 54623 109198 54623 109199 52929 109199 52928 109199 54623 109200 52928 109200 54629 109200 54629 109201 52928 109201 54630 109201 54629 109202 54630 109202 54624 109202 54624 109203 54630 109203 52925 109203 54624 109204 52925 109204 54631 109204 54631 109205 52925 109205 52924 109205 54631 109206 52924 109206 54632 109206 54632 109207 52924 109207 54633 109207 54632 109208 54633 109208 54628 109208 54628 109209 54633 109209 52712 109209 54174 109210 52706 109210 54175 109210 54175 109211 52706 109211 54634 109211 54175 109212 54634 109212 54177 109212 54177 109213 54634 109213 54643 109213 54177 109214 54643 109214 54635 109214 54635 109215 54643 109215 54636 109215 54635 109216 54636 109216 54637 109216 54637 109217 54636 109217 54638 109217 54637 109218 54638 109218 54178 109218 54178 109219 54638 109219 54640 109219 54178 109220 54640 109220 54639 109220 54639 109221 54640 109221 52699 109221 52706 109222 54641 109222 54634 109222 54634 109223 54641 109223 54642 109223 54634 109224 54642 109224 54643 109224 54643 109225 54642 109225 54644 109225 54643 109226 54644 109226 54636 109226 54636 109227 54644 109227 52909 109227 54636 109228 52909 109228 54638 109228 54638 109229 52909 109229 54645 109229 54638 109230 54645 109230 54640 109230 54640 109231 54645 109231 52908 109231 54640 109232 52908 109232 52699 109232 52699 109233 52908 109233 54646 109233 54647 109234 52644 109234 54648 109234 54648 109235 52644 109235 52643 109235 54648 109236 52643 109236 54649 109236 54649 109237 52643 109237 52641 109237 54649 109238 52641 109238 54650 109238 54650 109239 52641 109239 54651 109239 54650 109240 54651 109240 52671 109240 52579 109241 52578 109241 54653 109241 54652 109242 54653 109242 54655 109242 54653 109243 54652 109243 54654 109243 52576 109244 54655 109244 54653 109244 52574 109245 52575 109245 54653 109245 54653 109246 52575 109246 52785 109246 54654 109247 52574 109247 54653 109247 52578 109248 52576 109248 54653 109248 54653 109249 54658 109249 54656 109249 54656 109250 54658 109250 54657 109250 52579 109251 54653 109251 54656 109251 54657 109252 54658 109252 52580 109252 52580 109253 54658 109253 52551 109253 52580 109254 52551 109254 54659 109254 54659 109255 52551 109255 52550 109255 54659 109256 52550 109256 52583 109256 52583 109257 52550 109257 52555 109257 52583 109258 52555 109258 52554 109258 52618 109259 52515 109259 52607 109259 54660 109260 52385 109260 52424 109260 52385 109261 54660 109261 54661 109261 52425 109262 52424 109262 52385 109262 52422 109263 52385 109263 52423 109263 52385 109264 52422 109264 52887 109264 54662 109265 52423 109265 52385 109265 54661 109266 54662 109266 52385 109266 54663 109267 54664 109267 54665 109267 54665 109268 54664 109268 54666 109268 54665 109269 54666 109269 54667 109269 54666 109270 52392 109270 54667 109270 54667 109271 52392 109271 52391 109271 54667 109272 52391 109272 52428 109272 52391 109273 52390 109273 52428 109273 52428 109274 52390 109274 52379 109274 52428 109275 52379 109275 54668 109275 52385 109276 54669 109276 54663 109276 54663 109277 54669 109277 52389 109277 54663 109278 52389 109278 54664 109278 52425 109279 52385 109279 54663 109279 52468 109280 52335 109280 52469 109280 51736 109281 54671 109281 53017 109281 51743 109282 54680 109282 51740 109282 51740 109283 54680 109283 53020 109283 51740 109284 53020 109284 54670 109284 53017 109285 54671 109285 53020 109285 53020 109286 54671 109286 51738 109286 53020 109287 51738 109287 51724 109287 51724 109288 51726 109288 53020 109288 53020 109289 51726 109289 54672 109289 53020 109290 54672 109290 54670 109290 51736 109291 53017 109291 54673 109291 54673 109292 53017 109292 53007 109292 54673 109293 53007 109293 54675 109293 54676 109294 54674 109294 54677 109294 54677 109295 54674 109295 51732 109295 54677 109296 51732 109296 53007 109296 53007 109297 51732 109297 51734 109297 53007 109298 51734 109298 54675 109298 54676 109299 54677 109299 51730 109299 51730 109300 54677 109300 53031 109300 51730 109301 53031 109301 51727 109301 53010 109302 54679 109302 51756 109302 53010 109303 51756 109303 51697 109303 51697 109304 51756 109304 51755 109304 51697 109305 51755 109305 51754 109305 53028 109306 51751 109306 53010 109306 53010 109307 51751 109307 54678 109307 53010 109308 54678 109308 54679 109308 51743 109309 51744 109309 54680 109309 54680 109310 51744 109310 54681 109310 54680 109311 54681 109311 53028 109311 53028 109312 54681 109312 51748 109312 53028 109313 51748 109313 51751 109313 51790 109314 54696 109314 53026 109314 51790 109315 53026 109315 54682 109315 54685 109316 51788 109316 54683 109316 54685 109317 54683 109317 53026 109317 53026 109318 54683 109318 54684 109318 53026 109319 54684 109319 54682 109319 54689 109320 51785 109320 54685 109320 54685 109321 51785 109321 54686 109321 54686 109322 54687 109322 54685 109322 54685 109323 54687 109323 51787 109323 54685 109324 51787 109324 51788 109324 51781 109325 54688 109325 53029 109325 53029 109326 54688 109326 51783 109326 53029 109327 51783 109327 54689 109327 54689 109328 51783 109328 54690 109328 54689 109329 54690 109329 51785 109329 51781 109330 53029 109330 51780 109330 51780 109331 53029 109331 53009 109331 51780 109332 53009 109332 51665 109332 54691 109333 54695 109333 54692 109333 54691 109334 54692 109334 53012 109334 53012 109335 54692 109335 51800 109335 53012 109336 51800 109336 54693 109336 53013 109337 51791 109337 51797 109337 53013 109338 51797 109338 54691 109338 54691 109339 51797 109339 54694 109339 54691 109340 54694 109340 54695 109340 54696 109341 51793 109341 53026 109341 53026 109342 51793 109342 54697 109342 53026 109343 54697 109343 53013 109343 53013 109344 54697 109344 51792 109344 53013 109345 51792 109345 51791 109345 51826 109346 54716 109346 54699 109346 51850 109347 51840 109347 54702 109347 54702 109348 51840 109348 54698 109348 54702 109349 54698 109349 54699 109349 54699 109350 54698 109350 51839 109350 54699 109351 51839 109351 51826 109351 54703 109352 54700 109352 54702 109352 54702 109353 54700 109353 54701 109353 54701 109354 51852 109354 54702 109354 54702 109355 51852 109355 51851 109355 54702 109356 51851 109356 51850 109356 54707 109357 54706 109357 54703 109357 54703 109358 54706 109358 54704 109358 54703 109359 54704 109359 54700 109359 54705 109360 51846 109360 54707 109360 54707 109361 51846 109361 51845 109361 54707 109362 51845 109362 54706 109362 54705 109363 54707 109363 54708 109363 54708 109364 54707 109364 53014 109364 54708 109365 53014 109365 51842 109365 54714 109366 51837 109366 51836 109366 54714 109367 51836 109367 54709 109367 54709 109368 51836 109368 54710 109368 54709 109369 54710 109369 51834 109369 54711 109370 54712 109370 54713 109370 54711 109371 54713 109371 54714 109371 54714 109372 54713 109372 54715 109372 54714 109373 54715 109373 51837 109373 54716 109374 51827 109374 54699 109374 54699 109375 51827 109375 51828 109375 54699 109376 51828 109376 54711 109376 54711 109377 51828 109377 51830 109377 54711 109378 51830 109378 54712 109378 51594 109379 54718 109379 54717 109379 54717 109380 54718 109380 54782 109380 54717 109381 54782 109381 51581 109381 51581 109382 54782 109382 54784 109382 51581 109383 54784 109383 54719 109383 54719 109384 54784 109384 54786 109384 54719 109385 54786 109385 54720 109385 54720 109386 54786 109386 54721 109386 54720 109387 54721 109387 51584 109387 51584 109388 54721 109388 54722 109388 51584 109389 54722 109389 51585 109389 51585 109390 54722 109390 54788 109390 51585 109391 54788 109391 51597 109391 51597 109392 54788 109392 51598 109392 51573 109393 51012 109393 51561 109393 51561 109394 51012 109394 54723 109394 51561 109395 54723 109395 51563 109395 51563 109396 54723 109396 54724 109396 51563 109397 54724 109397 54725 109397 54725 109398 54724 109398 54778 109398 54725 109399 54778 109399 51565 109399 51565 109400 54778 109400 54726 109400 51565 109401 54726 109401 54727 109401 54727 109402 54726 109402 54780 109402 54727 109403 54780 109403 54728 109403 54728 109404 54780 109404 51009 109404 49953 109405 54729 109405 49954 109405 49954 109406 54729 109406 54730 109406 49954 109407 54730 109407 49956 109407 49956 109408 54730 109408 51562 109408 49956 109409 51562 109409 54731 109409 54731 109410 51562 109410 51564 109410 54731 109411 51564 109411 54732 109411 54732 109412 51564 109412 51566 109412 54732 109413 51566 109413 54733 109413 54733 109414 51566 109414 51567 109414 54733 109415 51567 109415 49949 109415 49949 109416 51567 109416 51568 109416 49964 109417 51593 109417 54734 109417 54734 109418 51593 109418 51595 109418 54734 109419 51595 109419 49967 109419 49967 109420 51595 109420 51596 109420 49967 109421 51596 109421 49968 109421 49968 109422 51596 109422 51582 109422 49968 109423 51582 109423 54735 109423 54735 109424 51582 109424 51583 109424 54735 109425 51583 109425 49970 109425 49970 109426 51583 109426 54737 109426 49970 109427 54737 109427 54736 109427 54736 109428 54737 109428 51549 109428 54791 109429 54738 109429 54739 109429 54791 109430 54739 109430 54792 109430 54792 109431 54739 109431 51920 109431 54792 109432 51920 109432 54740 109432 54740 109433 51920 109433 54741 109433 54740 109434 54741 109434 54742 109434 50996 109435 54743 109435 54744 109435 50996 109436 54744 109436 50995 109436 50995 109437 54744 109437 51985 109437 50995 109438 51985 109438 54745 109438 54745 109439 51985 109439 51538 109439 54745 109440 51538 109440 50997 109440 51922 109441 51000 109441 51918 109441 51918 109442 51000 109442 54800 109442 51918 109443 54800 109443 51919 109443 51919 109444 54800 109444 54746 109444 51919 109445 54746 109445 54741 109445 54741 109446 54746 109446 54742 109446 54751 109447 54747 109447 54752 109447 54748 109448 54747 109448 54751 109448 51512 109449 54748 109449 54751 109449 54751 109450 54749 109450 54750 109450 54753 109451 54749 109451 54751 109451 54752 109452 54753 109452 54751 109452 51512 109453 51513 109453 54748 109453 54748 109454 51513 109454 54754 109454 54748 109455 54754 109455 54747 109455 54747 109456 54754 109456 54758 109456 54747 109457 54758 109457 54752 109457 54752 109458 54758 109458 54760 109458 54752 109459 54760 109459 54753 109459 54753 109460 54760 109460 54761 109460 54753 109461 54761 109461 54749 109461 54749 109462 54761 109462 54755 109462 54749 109463 54755 109463 54750 109463 54750 109464 54755 109464 54756 109464 51513 109465 54551 109465 54754 109465 54754 109466 54551 109466 54757 109466 54754 109467 54757 109467 54758 109467 54758 109468 54757 109468 54759 109468 54758 109469 54759 109469 54760 109469 54760 109470 54759 109470 54565 109470 54760 109471 54565 109471 54761 109471 54761 109472 54565 109472 54537 109472 54761 109473 54537 109473 54755 109473 54755 109474 54537 109474 54762 109474 54755 109475 54762 109475 54756 109475 54756 109476 54762 109476 51501 109476 51496 109477 54768 109477 54765 109477 54763 109478 54768 109478 51496 109478 51499 109479 54763 109479 51496 109479 51496 109480 54771 109480 54772 109480 54764 109481 54771 109481 51496 109481 54765 109482 54764 109482 51496 109482 51499 109483 54766 109483 54763 109483 54763 109484 54766 109484 54767 109484 54763 109485 54767 109485 54768 109485 54768 109486 54767 109486 54769 109486 54768 109487 54769 109487 54765 109487 54765 109488 54769 109488 54770 109488 54765 109489 54770 109489 54764 109489 54764 109490 54770 109490 54775 109490 54764 109491 54775 109491 54771 109491 54771 109492 54775 109492 54773 109492 54771 109493 54773 109493 54772 109493 54772 109494 54773 109494 54777 109494 54766 109495 54536 109495 54767 109495 54767 109496 54536 109496 54557 109496 54767 109497 54557 109497 54769 109497 54769 109498 54557 109498 54534 109498 54769 109499 54534 109499 54770 109499 54770 109500 54534 109500 54774 109500 54770 109501 54774 109501 54775 109501 54775 109502 54774 109502 54776 109502 54775 109503 54776 109503 54773 109503 54773 109504 54776 109504 54547 109504 54773 109505 54547 109505 54777 109505 54777 109506 54547 109506 54532 109506 51012 109507 54314 109507 54723 109507 54723 109508 54314 109508 54316 109508 54723 109509 54316 109509 54724 109509 54724 109510 54316 109510 54330 109510 54724 109511 54330 109511 54778 109511 54778 109512 54330 109512 54779 109512 54778 109513 54779 109513 54726 109513 54726 109514 54779 109514 54352 109514 54726 109515 54352 109515 54780 109515 54780 109516 54352 109516 54353 109516 54780 109517 54353 109517 51009 109517 51009 109518 54353 109518 54781 109518 54718 109519 54783 109519 54782 109519 54782 109520 54783 109520 54358 109520 54782 109521 54358 109521 54784 109521 54784 109522 54358 109522 54785 109522 54784 109523 54785 109523 54786 109523 54786 109524 54785 109524 54349 109524 54786 109525 54349 109525 54721 109525 54721 109526 54349 109526 54787 109526 54721 109527 54787 109527 54722 109527 54722 109528 54787 109528 54343 109528 54722 109529 54343 109529 54788 109529 54788 109530 54343 109530 54789 109530 54788 109531 54789 109531 51598 109531 51598 109532 54789 109532 54345 109532 54790 109533 54791 109533 54792 109533 54790 109534 54792 109534 54793 109534 54793 109535 54792 109535 54740 109535 54793 109536 54740 109536 54794 109536 54794 109537 54740 109537 54742 109537 54794 109538 54742 109538 54795 109538 54799 109539 54796 109539 54797 109539 51000 109540 54798 109540 54800 109540 54800 109541 54798 109541 54510 109541 54510 109542 54799 109542 54800 109542 54800 109543 54799 109543 54797 109543 54800 109544 54797 109544 54746 109544 54746 109545 54797 109545 51533 109545 54746 109546 51533 109546 54742 109546 54742 109547 51533 109547 54795 109547 49965 109548 54801 109548 49966 109548 49962 109549 54802 109549 54807 109549 54807 109550 54802 109550 54803 109550 54807 109551 54803 109551 49965 109551 54804 109552 49959 109552 54805 109552 54805 109553 49959 109553 54807 109553 54805 109554 54807 109554 54806 109554 49965 109555 49966 109555 54807 109555 54807 109556 49966 109556 49969 109556 54807 109557 49969 109557 54806 109557 54812 109558 49955 109558 49957 109558 54808 109559 54810 109559 54809 109559 54809 109560 54810 109560 54811 109560 54809 109561 54811 109561 54812 109561 54813 109562 49950 109562 54814 109562 54814 109563 49950 109563 54809 109563 54814 109564 54809 109564 54815 109564 54812 109565 49957 109565 54809 109565 54809 109566 49957 109566 49958 109566 54809 109567 49958 109567 54815 109567 56160 109568 54966 109568 56124 109568 56124 109569 54966 109569 54828 109569 54816 109570 54861 109570 55944 109570 55944 109571 54861 109571 54932 109571 54874 109572 54817 109572 55246 109572 55246 109573 54817 109573 54818 109573 54967 109574 54820 109574 54818 109574 54818 109575 54820 109575 55244 109575 54818 109576 55244 109576 55246 109576 54964 109577 54819 109577 54967 109577 54967 109578 54819 109578 55243 109578 54967 109579 55243 109579 54820 109579 54821 109580 56205 109580 54822 109580 54822 109581 56205 109581 56201 109581 54822 109582 56201 109582 56179 109582 56179 109583 56178 109583 54822 109583 54822 109584 56178 109584 56177 109584 54822 109585 56177 109585 54823 109585 54823 109586 56175 109586 54822 109586 54822 109587 56175 109587 56173 109587 54822 109588 56173 109588 54824 109588 54824 109589 54825 109589 54822 109589 54822 109590 54825 109590 54826 109590 54822 109591 54826 109591 54964 109591 54964 109592 54826 109592 55240 109592 54964 109593 55240 109593 54819 109593 54821 109594 54822 109594 54827 109594 54827 109595 54822 109595 54966 109595 54827 109596 54966 109596 56160 109596 56124 109597 54828 109597 56123 109597 56123 109598 54828 109598 54833 109598 56114 109599 54829 109599 54833 109599 56114 109600 54833 109600 54830 109600 56108 109601 54831 109601 54833 109601 54833 109602 54831 109602 56111 109602 54833 109603 56111 109603 54830 109603 56107 109604 56108 109604 56105 109604 56105 109605 56108 109605 54833 109605 56105 109606 54833 109606 54832 109606 54832 109607 54833 109607 55191 109607 54829 109608 54834 109608 54833 109608 54833 109609 54834 109609 54835 109609 54833 109610 54835 109610 56123 109610 55191 109611 54833 109611 55189 109611 55189 109612 54833 109612 54912 109612 55189 109613 54912 109613 54836 109613 54836 109614 54912 109614 54911 109614 54836 109615 54911 109615 55192 109615 55192 109616 54911 109616 55193 109616 55193 109617 54911 109617 54837 109617 55193 109618 54837 109618 55194 109618 55194 109619 54837 109619 55196 109619 55196 109620 54837 109620 54914 109620 55196 109621 54914 109621 54838 109621 54838 109622 54914 109622 54913 109622 54839 109623 54840 109623 55359 109623 55359 109624 54840 109624 54848 109624 54913 109625 54841 109625 54838 109625 54838 109626 54841 109626 54842 109626 54838 109627 54842 109627 55506 109627 54848 109628 55482 109628 54843 109628 55506 109629 54844 109629 54838 109629 54838 109630 54844 109630 55491 109630 54838 109631 55491 109631 54845 109631 54843 109632 54846 109632 54848 109632 54848 109633 54846 109633 55363 109633 54848 109634 55363 109634 55359 109634 55478 109635 54847 109635 54848 109635 54848 109636 54847 109636 55480 109636 54848 109637 55480 109637 55482 109637 54845 109638 55490 109638 54838 109638 54838 109639 55490 109639 55489 109639 54838 109640 55489 109640 55488 109640 55488 109641 54849 109641 54838 109641 54838 109642 54849 109642 55477 109642 54838 109643 55477 109643 54848 109643 54848 109644 55477 109644 54850 109644 54848 109645 54850 109645 55478 109645 54848 109646 54840 109646 55181 109646 55181 109647 54840 109647 54918 109647 54851 109648 55179 109648 54918 109648 54918 109649 55179 109649 54852 109649 54918 109650 54852 109650 55181 109650 54919 109651 55177 109651 54851 109651 54851 109652 55177 109652 54853 109652 54851 109653 54853 109653 55179 109653 55984 109654 55983 109654 54858 109654 54858 109655 55983 109655 54854 109655 54858 109656 54854 109656 55981 109656 55981 109657 54855 109657 54858 109657 54858 109658 54855 109658 54856 109658 54858 109659 54856 109659 55978 109659 55978 109660 55976 109660 54858 109660 54858 109661 55976 109661 54857 109661 54858 109662 54857 109662 55975 109662 55975 109663 55994 109663 54858 109663 54858 109664 55994 109664 54859 109664 54858 109665 54859 109665 54919 109665 54919 109666 54859 109666 55176 109666 54919 109667 55176 109667 55177 109667 55984 109668 54858 109668 54860 109668 54860 109669 54858 109669 54861 109669 54860 109670 54861 109670 54816 109670 55944 109671 54932 109671 54862 109671 54862 109672 54932 109672 54864 109672 55914 109673 55915 109673 54864 109673 55914 109674 54864 109674 55912 109674 55909 109675 54863 109675 54864 109675 54864 109676 54863 109676 55911 109676 54864 109677 55911 109677 55912 109677 55906 109678 55909 109678 55905 109678 55905 109679 55909 109679 54864 109679 55905 109680 54864 109680 55903 109680 55903 109681 54864 109681 55871 109681 55915 109682 55916 109682 54864 109682 54864 109683 55916 109683 55926 109683 54864 109684 55926 109684 54862 109684 55871 109685 54864 109685 55212 109685 55212 109686 54864 109686 54865 109686 55212 109687 54865 109687 54866 109687 54866 109688 54865 109688 54930 109688 54866 109689 54930 109689 55213 109689 55213 109690 54930 109690 55214 109690 55214 109691 54930 109691 54868 109691 55214 109692 54868 109692 54867 109692 54867 109693 54868 109693 55216 109693 55216 109694 54868 109694 54869 109694 55216 109695 54869 109695 54870 109695 54870 109696 54869 109696 54927 109696 54871 109697 54817 109697 55369 109697 55369 109698 54817 109698 54874 109698 54927 109699 54872 109699 54870 109699 54870 109700 54872 109700 54873 109700 54870 109701 54873 109701 55514 109701 54874 109702 55558 109702 54877 109702 55514 109703 54875 109703 54870 109703 54870 109704 54875 109704 55516 109704 54870 109705 55516 109705 54876 109705 54877 109706 55556 109706 54874 109706 54874 109707 55556 109707 55557 109707 54874 109708 55557 109708 55369 109708 55548 109709 55549 109709 54874 109709 54874 109710 55549 109710 55551 109710 54874 109711 55551 109711 55558 109711 54876 109712 55522 109712 54870 109712 54870 109713 55522 109713 54878 109713 54870 109714 54878 109714 54879 109714 54879 109715 55531 109715 54870 109715 54870 109716 55531 109716 55532 109716 54870 109717 55532 109717 54874 109717 54874 109718 55532 109718 55546 109718 54874 109719 55546 109719 55548 109719 54883 109720 54880 109720 54892 109720 55150 109721 55149 109721 54881 109721 54881 109722 55149 109722 54882 109722 54881 109723 54882 109723 55760 109723 54894 109724 55695 109724 54891 109724 54892 109725 55635 109725 54883 109725 54883 109726 55635 109726 54884 109726 54883 109727 54884 109727 54903 109727 54897 109728 55140 109728 55595 109728 55595 109729 55140 109729 55138 109729 55132 109730 55595 109730 54885 109730 54885 109731 55595 109731 54893 109731 54905 109732 55755 109732 54895 109732 54897 109733 55755 109733 55756 109733 54886 109734 54881 109734 55152 109734 55152 109735 54881 109735 54887 109735 54886 109736 54888 109736 54881 109736 54881 109737 54888 109737 54889 109737 54881 109738 54889 109738 55150 109738 54880 109739 55121 109739 54891 109739 54891 109740 55121 109740 54890 109740 54891 109741 54890 109741 55119 109741 54891 109742 55743 109742 54880 109742 54880 109743 55743 109743 55744 109743 54880 109744 55744 109744 54892 109744 54892 109745 55744 109745 55746 109745 54892 109746 55746 109746 54900 109746 55103 109747 55102 109747 54903 109747 55138 109748 55137 109748 55595 109748 55595 109749 55137 109749 55135 109749 55595 109750 55135 109750 54893 109750 55119 109751 55118 109751 54891 109751 54891 109752 55118 109752 55117 109752 54891 109753 55117 109753 54894 109753 55102 109754 55101 109754 54903 109754 54903 109755 55101 109755 55100 109755 54903 109756 55100 109756 54883 109756 54899 109757 55626 109757 55755 109757 55755 109758 55626 109758 55628 109758 55755 109759 55628 109759 54895 109759 55756 109760 55757 109760 54897 109760 54897 109761 55757 109761 54896 109761 54897 109762 54896 109762 54882 109762 54882 109763 54896 109763 55758 109763 54882 109764 55758 109764 55760 109764 55595 109765 55621 109765 54897 109765 54897 109766 55621 109766 54898 109766 54897 109767 54898 109767 55755 109767 55755 109768 54898 109768 55623 109768 55755 109769 55623 109769 54899 109769 54900 109770 55749 109770 54892 109770 54892 109771 55749 109771 55751 109771 54892 109772 55751 109772 55633 109772 55633 109773 55751 109773 54901 109773 54902 109774 55105 109774 54903 109774 54903 109775 55105 109775 54904 109775 54903 109776 54904 109776 55103 109776 54905 109777 54895 109777 54906 109777 54906 109778 54895 109778 54907 109778 54906 109779 54907 109779 54908 109779 54908 109780 54907 109780 54909 109780 54908 109781 54909 109781 55751 109781 55751 109782 54909 109782 54910 109782 55751 109783 54910 109783 54901 109783 54837 109784 54911 109784 54912 109784 54953 109785 54936 109785 55335 109785 54953 109786 55335 109786 54912 109786 55335 109787 55337 109787 54912 109787 54912 109788 55337 109788 55339 109788 54912 109789 55339 109789 55341 109789 55353 109790 54913 109790 55341 109790 55341 109791 54913 109791 54912 109791 54912 109792 54913 109792 54914 109792 54912 109793 54914 109793 54837 109793 55355 109794 54915 109794 55341 109794 55341 109795 54915 109795 54916 109795 55341 109796 54916 109796 55353 109796 54917 109797 55344 109797 54920 109797 54920 109798 55344 109798 55345 109798 54840 109799 54919 109799 54918 109799 54918 109800 54919 109800 54851 109800 54840 109801 54839 109801 54919 109801 54919 109802 54839 109802 55358 109802 54919 109803 55358 109803 55357 109803 55357 109804 55360 109804 54919 109804 54919 109805 55360 109805 55361 109805 54919 109806 55361 109806 54921 109806 54926 109807 54919 109807 54920 109807 54920 109808 54919 109808 54921 109808 54920 109809 54921 109809 54917 109809 54946 109810 54922 109810 54975 109810 54926 109811 54923 109811 54924 109811 54924 109812 54923 109812 54925 109812 54924 109813 54925 109813 54940 109813 54934 109814 54858 109814 56212 109814 56212 109815 54858 109815 54919 109815 56212 109816 54919 109816 56210 109816 56210 109817 54919 109817 54926 109817 56210 109818 54926 109818 56209 109818 56209 109819 54926 109819 54924 109819 54929 109820 56207 109820 54868 109820 54939 109821 54927 109821 56207 109821 56207 109822 54927 109822 54869 109822 56207 109823 54869 109823 54868 109823 54995 109824 54928 109824 54953 109824 54868 109825 54930 109825 54929 109825 54929 109826 54930 109826 54865 109826 54929 109827 54865 109827 54931 109827 54931 109828 54865 109828 54864 109828 54931 109829 54864 109829 54933 109829 54933 109830 54864 109830 54932 109830 54933 109831 54932 109831 54934 109831 54934 109832 54932 109832 54861 109832 54934 109833 54861 109833 54858 109833 55349 109834 55351 109834 54937 109834 54937 109835 55351 109835 54935 109835 54937 109836 54935 109836 54947 109836 54928 109837 54993 109837 54953 109837 54953 109838 54993 109838 54991 109838 54953 109839 54991 109839 54936 109839 54936 109840 54991 109840 54990 109840 54936 109841 54990 109841 55345 109841 55345 109842 54990 109842 54950 109842 55345 109843 54950 109843 54920 109843 54937 109844 54938 109844 54939 109844 54939 109845 54938 109845 55375 109845 54939 109846 55375 109846 54927 109846 55014 109847 54937 109847 54941 109847 54941 109848 54937 109848 54940 109848 54941 109849 54940 109849 54942 109849 54942 109850 54940 109850 54925 109850 54986 109851 54943 109851 55349 109851 55349 109852 54943 109852 54944 109852 55349 109853 54944 109853 54975 109853 54975 109854 54944 109854 54945 109854 54975 109855 54945 109855 54946 109855 54947 109856 55374 109856 54937 109856 54937 109857 55374 109857 54948 109857 54937 109858 54948 109858 54938 109858 54990 109859 54949 109859 54950 109859 54950 109860 54949 109860 54989 109860 54950 109861 54989 109861 55018 109861 55018 109862 54989 109862 54963 109862 55018 109863 54963 109863 55019 109863 55014 109864 55012 109864 54937 109864 54937 109865 55012 109865 54951 109865 54937 109866 54951 109866 55349 109866 55349 109867 54951 109867 54952 109867 54952 109868 55027 109868 55349 109868 55349 109869 55027 109869 55025 109869 55349 109870 55025 109870 54986 109870 54986 109871 55025 109871 54956 109871 54922 109872 54998 109872 54975 109872 54975 109873 54998 109873 54954 109873 54975 109874 54954 109874 54953 109874 54953 109875 54954 109875 54955 109875 54953 109876 54955 109876 54995 109876 55025 109877 54957 109877 54956 109877 54956 109878 54957 109878 55021 109878 54956 109879 55021 109879 54958 109879 54958 109880 55021 109880 54959 109880 54958 109881 54959 109881 54960 109881 54960 109882 54959 109882 54961 109882 54960 109883 54961 109883 54963 109883 54963 109884 54961 109884 54962 109884 54963 109885 54962 109885 55019 109885 54964 109886 54968 109886 54965 109886 56215 109887 54828 109887 56214 109887 56214 109888 54828 109888 54966 109888 56214 109889 54966 109889 54965 109889 54965 109890 54966 109890 54822 109890 54965 109891 54822 109891 54964 109891 54973 109892 54912 109892 56215 109892 56215 109893 54912 109893 54833 109893 56215 109894 54833 109894 54828 109894 54964 109895 54967 109895 54968 109895 54968 109896 54967 109896 54818 109896 54968 109897 54818 109897 54969 109897 54969 109898 54818 109898 54817 109898 54969 109899 54817 109899 54970 109899 54970 109900 54817 109900 54871 109900 54953 109901 55043 109901 55042 109901 54971 109902 55346 109902 54974 109902 55051 109903 55050 109903 56219 109903 56219 109904 55050 109904 54972 109904 56219 109905 54972 109905 56218 109905 56218 109906 54972 109906 54912 109906 56218 109907 54912 109907 56217 109907 56217 109908 54912 109908 54973 109908 54972 109909 55049 109909 54912 109909 54912 109910 55049 109910 55047 109910 54912 109911 55047 109911 54953 109911 54953 109912 55047 109912 55044 109912 54953 109913 55044 109913 55043 109913 54974 109914 55346 109914 55058 109914 55042 109915 55041 109915 54953 109915 54953 109916 55041 109916 54976 109916 54953 109917 54976 109917 54975 109917 54975 109918 54976 109918 55038 109918 54975 109919 55038 109919 55035 109919 55035 109920 55034 109920 54975 109920 54975 109921 55034 109921 54978 109921 54975 109922 54978 109922 54977 109922 54977 109923 54978 109923 55058 109923 54977 109924 55058 109924 54979 109924 54979 109925 55058 109925 55346 109925 55051 109926 56219 109926 55053 109926 55053 109927 56219 109927 54980 109927 55053 109928 54980 109928 55054 109928 55054 109929 54980 109929 54981 109929 55054 109930 54981 109930 55056 109930 55056 109931 54981 109931 54970 109931 55056 109932 54970 109932 54982 109932 54982 109933 54970 109933 54871 109933 54982 109934 54871 109934 54974 109934 54974 109935 54871 109935 55368 109935 54974 109936 55368 109936 55367 109936 55367 109937 55366 109937 54974 109937 54974 109938 55366 109938 54983 109938 54974 109939 54983 109939 54971 109939 54984 109940 54944 109940 54943 109940 54984 109941 54943 109941 56255 109941 56255 109942 54943 109942 54986 109942 56255 109943 54986 109943 54985 109943 54985 109944 54986 109944 54956 109944 54985 109945 54956 109945 56257 109945 56257 109946 54956 109946 54958 109946 56257 109947 54958 109947 54987 109947 54987 109948 54958 109948 54988 109948 54988 109949 54958 109949 54960 109949 54988 109950 54960 109950 54963 109950 54988 109951 54963 109951 56245 109951 56245 109952 54963 109952 54989 109952 56245 109953 54989 109953 56246 109953 56246 109954 54989 109954 54949 109954 56246 109955 54949 109955 56248 109955 56248 109956 54949 109956 54990 109956 56248 109957 54990 109957 56250 109957 56250 109958 54990 109958 54992 109958 54992 109959 54990 109959 54991 109959 54992 109960 54991 109960 54993 109960 54992 109961 54993 109961 54994 109961 54994 109962 54993 109962 54928 109962 54994 109963 54928 109963 56251 109963 56251 109964 54928 109964 54995 109964 56251 109965 54995 109965 54996 109965 54996 109966 54995 109966 54955 109966 54996 109967 54955 109967 56254 109967 56254 109968 54955 109968 56258 109968 56258 109969 54955 109969 54954 109969 56258 109970 54954 109970 54998 109970 56258 109971 54998 109971 54997 109971 54997 109972 54998 109972 54922 109972 54997 109973 54922 109973 56261 109973 56261 109974 54922 109974 54946 109974 56261 109975 54946 109975 54999 109975 54999 109976 54946 109976 54945 109976 54999 109977 54945 109977 56264 109977 56264 109978 54945 109978 54984 109978 54984 109979 54945 109979 54944 109979 55009 109980 55000 109980 55002 109980 55000 109981 56259 109981 56260 109981 56260 109982 56262 109982 55000 109982 55000 109983 56262 109983 56263 109983 55000 109984 56263 109984 55002 109984 55002 109985 56263 109985 55001 109985 55002 109986 55001 109986 55007 109986 55002 109987 55003 109987 56247 109987 56253 109988 55004 109988 56252 109988 56252 109989 55004 109989 55009 109989 56256 109990 55005 109990 55001 109990 55001 109991 55005 109991 55006 109991 55001 109992 55006 109992 55007 109992 56247 109993 56249 109993 55002 109993 55002 109994 56249 109994 55008 109994 55002 109995 55008 109995 55009 109995 55009 109996 55008 109996 56244 109996 55009 109997 56244 109997 56252 109997 55010 109998 54952 109998 54951 109998 55010 109999 54951 109999 55011 109999 55011 110000 54951 110000 55012 110000 55011 110001 55012 110001 55013 110001 55013 110002 55012 110002 55014 110002 55013 110003 55014 110003 55015 110003 55015 110004 55014 110004 54941 110004 55015 110005 54941 110005 55016 110005 55016 110006 54941 110006 56236 110006 56236 110007 54941 110007 54942 110007 56236 110008 54942 110008 54925 110008 56236 110009 54925 110009 55017 110009 55017 110010 54925 110010 54923 110010 55017 110011 54923 110011 56226 110011 56226 110012 54923 110012 54926 110012 56226 110013 54926 110013 56228 110013 56228 110014 54926 110014 54920 110014 56228 110015 54920 110015 56222 110015 56222 110016 54920 110016 56223 110016 56223 110017 54920 110017 54950 110017 56223 110018 54950 110018 55018 110018 56223 110019 55018 110019 56230 110019 56230 110020 55018 110020 55019 110020 56230 110021 55019 110021 55020 110021 55020 110022 55019 110022 54962 110022 55020 110023 54962 110023 56233 110023 56233 110024 54962 110024 54961 110024 56233 110025 54961 110025 56237 110025 56237 110026 54961 110026 55022 110026 55022 110027 54961 110027 54959 110027 55022 110028 54959 110028 55021 110028 55022 110029 55021 110029 55023 110029 55023 110030 55021 110030 54957 110030 55023 110031 54957 110031 55024 110031 55024 110032 54957 110032 55025 110032 55024 110033 55025 110033 55026 110033 55026 110034 55025 110034 55027 110034 55026 110035 55027 110035 56243 110035 56243 110036 55027 110036 55010 110036 55010 110037 55027 110037 54952 110037 56225 110038 56227 110038 56224 110038 56224 110039 56227 110039 56229 110039 55030 110040 56235 110040 56241 110040 56241 110041 56235 110041 56224 110041 56241 110042 56224 110042 55028 110042 55028 110043 56224 110043 56229 110043 55028 110044 56229 110044 56221 110044 56221 110045 56231 110045 55028 110045 55028 110046 56231 110046 56232 110046 55028 110047 56232 110047 56234 110047 55029 110048 56242 110048 55030 110048 55030 110049 56242 110049 55031 110049 55030 110050 55031 110050 56235 110050 56235 110051 55031 110051 56238 110051 56235 110052 56238 110052 55032 110052 56239 110053 55033 110053 56238 110053 56238 110054 55033 110054 56240 110054 56238 110055 56240 110055 55032 110055 55059 110056 54978 110056 55034 110056 55059 110057 55034 110057 56275 110057 56275 110058 55034 110058 55035 110058 56275 110059 55035 110059 55036 110059 55036 110060 55035 110060 55038 110060 55036 110061 55038 110061 55037 110061 55037 110062 55038 110062 54976 110062 55037 110063 54976 110063 55039 110063 55039 110064 54976 110064 55040 110064 55040 110065 54976 110065 55041 110065 55040 110066 55041 110066 55042 110066 55040 110067 55042 110067 56267 110067 56267 110068 55042 110068 55043 110068 56267 110069 55043 110069 55045 110069 55045 110070 55043 110070 55044 110070 55045 110071 55044 110071 55046 110071 55046 110072 55044 110072 55047 110072 55046 110073 55047 110073 56266 110073 56266 110074 55047 110074 55048 110074 55048 110075 55047 110075 55049 110075 55048 110076 55049 110076 54972 110076 55048 110077 54972 110077 56271 110077 56271 110078 54972 110078 55050 110078 56271 110079 55050 110079 56273 110079 56273 110080 55050 110080 55051 110080 56273 110081 55051 110081 55052 110081 55052 110082 55051 110082 55053 110082 55052 110083 55053 110083 56274 110083 56274 110084 55053 110084 55055 110084 55055 110085 55053 110085 55054 110085 55055 110086 55054 110086 55056 110086 55055 110087 55056 110087 56278 110087 56278 110088 55056 110088 54982 110088 56278 110089 54982 110089 56279 110089 56279 110090 54982 110090 54974 110090 56279 110091 54974 110091 55057 110091 55057 110092 54974 110092 55058 110092 55057 110093 55058 110093 56281 110093 56281 110094 55058 110094 55059 110094 55059 110095 55058 110095 54978 110095 56268 110096 56269 110096 56265 110096 56277 110097 55062 110097 56276 110097 56276 110098 55062 110098 55069 110098 56280 110099 55060 110099 56277 110099 56277 110100 55060 110100 55061 110100 56277 110101 55061 110101 55062 110101 55062 110102 55061 110102 56282 110102 55062 110103 56282 110103 55063 110103 55069 110104 55062 110104 56265 110104 56265 110105 55062 110105 55064 110105 56265 110106 55064 110106 56268 110106 55065 110107 55066 110107 56282 110107 56282 110108 55066 110108 55067 110108 56282 110109 55067 110109 55063 110109 56272 110110 55068 110110 55070 110110 55070 110111 55068 110111 55069 110111 55070 110112 55069 110112 56270 110112 56270 110113 55069 110113 56265 110113 55154 110114 55227 110114 55073 110114 55073 110115 55227 110115 55075 110115 55071 110116 55583 110116 55072 110116 55228 110117 55578 110117 55071 110117 55228 110118 55071 110118 55235 110118 55235 110119 55071 110119 55072 110119 55235 110120 55072 110120 55078 110120 55073 110121 55075 110121 55074 110121 55074 110122 55075 110122 55076 110122 55074 110123 55076 110123 55145 110123 55145 110124 55076 110124 55237 110124 55145 110125 55237 110125 55143 110125 55143 110126 55237 110126 55236 110126 55143 110127 55236 110127 55077 110127 55077 110128 55236 110128 55078 110128 55077 110129 55078 110129 55079 110129 55079 110130 55078 110130 55072 110130 55775 110131 55218 110131 55080 110131 55080 110132 55218 110132 55082 110132 55080 110133 55082 110133 55783 110133 55223 110134 55081 110134 55082 110134 55082 110135 55081 110135 55161 110135 55082 110136 55161 110136 55783 110136 55227 110137 55154 110137 55219 110137 55219 110138 55154 110138 55083 110138 55219 110139 55083 110139 55220 110139 55220 110140 55083 110140 55156 110140 55220 110141 55156 110141 55222 110141 55222 110142 55156 110142 55158 110142 55222 110143 55158 110143 55223 110143 55223 110144 55158 110144 55159 110144 55223 110145 55159 110145 55081 110145 55664 110146 55084 110146 55651 110146 55651 110147 55084 110147 55086 110147 55651 110148 55086 110148 55087 110148 55203 110149 55085 110149 55086 110149 55086 110150 55085 110150 55111 110150 55086 110151 55111 110151 55087 110151 55097 110152 55096 110152 55199 110152 55199 110153 55096 110153 55088 110153 55199 110154 55088 110154 55200 110154 55200 110155 55088 110155 55106 110155 55200 110156 55106 110156 55202 110156 55202 110157 55106 110157 55109 110157 55202 110158 55109 110158 55203 110158 55203 110159 55109 110159 55089 110159 55203 110160 55089 110160 55085 110160 55090 110161 55686 110161 55093 110161 55168 110162 55091 110162 55090 110162 55168 110163 55090 110163 55092 110163 55092 110164 55090 110164 55093 110164 55092 110165 55093 110165 55095 110165 55114 110166 55183 110166 55094 110166 55094 110167 55183 110167 55174 110167 55094 110168 55174 110168 55130 110168 55130 110169 55174 110169 55172 110169 55130 110170 55172 110170 55129 110170 55129 110171 55172 110171 55170 110171 55129 110172 55170 110172 55127 110172 55127 110173 55170 110173 55095 110173 55127 110174 55095 110174 55125 110174 55125 110175 55095 110175 55093 110175 55096 110176 55097 110176 55114 110176 55114 110177 55097 110177 55183 110177 55096 110178 55099 110178 55098 110178 55099 110179 54883 110179 55100 110179 55099 110180 55100 110180 55098 110180 55098 110181 55100 110181 55101 110181 55098 110182 55101 110182 55107 110182 55107 110183 55101 110183 55102 110183 55107 110184 55102 110184 55104 110184 55104 110185 55102 110185 55103 110185 55104 110186 55103 110186 55108 110186 55108 110187 55103 110187 54904 110187 55108 110188 54904 110188 55110 110188 55110 110189 54904 110189 55105 110189 55110 110190 55105 110190 55112 110190 55105 110191 54902 110191 55112 110191 55112 110192 54902 110192 55642 110192 55112 110193 55642 110193 55113 110193 55096 110194 55098 110194 55088 110194 55088 110195 55098 110195 55107 110195 55088 110196 55107 110196 55106 110196 55106 110197 55107 110197 55104 110197 55106 110198 55104 110198 55109 110198 55109 110199 55104 110199 55108 110199 55109 110200 55108 110200 55089 110200 55089 110201 55108 110201 55110 110201 55089 110202 55110 110202 55085 110202 55085 110203 55110 110203 55112 110203 55085 110204 55112 110204 55111 110204 55111 110205 55112 110205 55113 110205 55111 110206 55113 110206 55087 110206 55096 110207 55114 110207 55123 110207 55096 110208 55123 110208 55099 110208 55099 110209 55123 110209 54880 110209 55099 110210 54880 110210 54883 110210 55696 110211 55115 110211 55116 110211 55115 110212 55695 110212 54894 110212 55093 110213 55686 110213 55696 110213 55115 110214 54894 110214 55116 110214 55116 110215 54894 110215 55117 110215 55116 110216 55117 110216 55124 110216 55124 110217 55117 110217 55118 110217 55124 110218 55118 110218 55126 110218 55126 110219 55118 110219 55119 110219 55126 110220 55119 110220 55128 110220 55128 110221 55119 110221 54890 110221 55128 110222 54890 110222 55120 110222 55120 110223 54890 110223 55121 110223 55120 110224 55121 110224 55122 110224 55122 110225 55121 110225 54880 110225 55122 110226 54880 110226 55123 110226 55696 110227 55116 110227 55093 110227 55093 110228 55116 110228 55124 110228 55093 110229 55124 110229 55125 110229 55125 110230 55124 110230 55126 110230 55125 110231 55126 110231 55127 110231 55127 110232 55126 110232 55128 110232 55127 110233 55128 110233 55129 110233 55129 110234 55128 110234 55120 110234 55129 110235 55120 110235 55130 110235 55130 110236 55120 110236 55122 110236 55130 110237 55122 110237 55094 110237 55094 110238 55122 110238 55123 110238 55094 110239 55123 110239 55114 110239 55133 110240 55134 110240 55131 110240 55134 110241 55132 110241 54885 110241 55072 110242 55583 110242 55133 110242 55134 110243 54885 110243 55131 110243 55131 110244 54885 110244 54893 110244 55131 110245 54893 110245 55141 110245 55141 110246 54893 110246 55135 110246 55141 110247 55135 110247 55142 110247 55142 110248 55135 110248 55137 110248 55142 110249 55137 110249 55136 110249 55136 110250 55137 110250 55138 110250 55136 110251 55138 110251 55144 110251 55144 110252 55138 110252 55140 110252 55144 110253 55140 110253 55139 110253 55139 110254 55140 110254 54897 110254 55139 110255 54897 110255 55146 110255 55133 110256 55131 110256 55072 110256 55072 110257 55131 110257 55141 110257 55072 110258 55141 110258 55079 110258 55079 110259 55141 110259 55142 110259 55079 110260 55142 110260 55077 110260 55077 110261 55142 110261 55136 110261 55077 110262 55136 110262 55143 110262 55143 110263 55136 110263 55144 110263 55143 110264 55144 110264 55145 110264 55145 110265 55144 110265 55139 110265 55145 110266 55139 110266 55074 110266 55074 110267 55139 110267 55146 110267 55074 110268 55146 110268 55073 110268 55154 110269 55073 110269 55146 110269 55154 110270 55146 110270 55147 110270 55147 110271 55146 110271 54897 110271 55147 110272 54897 110272 54882 110272 55154 110273 55147 110273 55148 110273 55147 110274 54882 110274 55149 110274 55147 110275 55149 110275 55148 110275 55148 110276 55149 110276 55150 110276 55148 110277 55150 110277 55155 110277 55155 110278 55150 110278 54889 110278 55155 110279 54889 110279 55157 110279 55157 110280 54889 110280 54888 110280 55157 110281 54888 110281 55151 110281 55151 110282 54888 110282 54886 110282 55151 110283 54886 110283 55153 110283 55153 110284 54886 110284 55152 110284 55153 110285 55152 110285 55160 110285 55152 110286 54887 110286 55160 110286 55160 110287 54887 110287 55765 110287 55160 110288 55765 110288 55770 110288 55154 110289 55148 110289 55083 110289 55083 110290 55148 110290 55155 110290 55083 110291 55155 110291 55156 110291 55156 110292 55155 110292 55157 110292 55156 110293 55157 110293 55158 110293 55158 110294 55157 110294 55151 110294 55158 110295 55151 110295 55159 110295 55159 110296 55151 110296 55153 110296 55159 110297 55153 110297 55081 110297 55081 110298 55153 110298 55160 110298 55081 110299 55160 110299 55161 110299 55161 110300 55160 110300 55770 110300 55161 110301 55770 110301 55783 110301 55680 110302 55091 110302 55168 110302 55167 110303 55681 110303 55165 110303 55166 110304 55175 110304 55164 110304 54859 110305 55162 110305 55175 110305 55162 110306 55995 110306 55175 110306 55175 110307 55995 110307 55163 110307 55175 110308 55163 110308 55164 110308 55680 110309 55175 110309 55165 110309 55165 110310 55175 110310 55166 110310 55165 110311 55166 110311 55167 110311 55680 110312 55168 110312 55175 110312 55175 110313 55168 110313 55092 110313 55175 110314 55092 110314 55169 110314 55169 110315 55092 110315 55095 110315 55169 110316 55095 110316 55171 110316 55171 110317 55095 110317 55170 110317 55171 110318 55170 110318 55178 110318 55178 110319 55170 110319 55172 110319 55178 110320 55172 110320 55180 110320 55180 110321 55172 110321 55174 110321 55180 110322 55174 110322 55173 110322 55173 110323 55174 110323 55183 110323 55173 110324 55183 110324 55182 110324 54859 110325 55175 110325 55176 110325 55176 110326 55175 110326 55169 110326 55176 110327 55169 110327 55177 110327 55177 110328 55169 110328 55171 110328 55177 110329 55171 110329 54853 110329 54853 110330 55171 110330 55178 110330 54853 110331 55178 110331 55179 110331 55179 110332 55178 110332 55180 110332 55179 110333 55180 110333 54852 110333 54852 110334 55180 110334 55173 110334 54852 110335 55173 110335 55181 110335 55181 110336 55173 110336 55182 110336 55181 110337 55182 110337 54848 110337 54838 110338 54848 110338 55182 110338 54838 110339 55182 110339 55184 110339 55184 110340 55182 110340 55183 110340 55184 110341 55183 110341 55097 110341 55184 110342 55097 110342 55199 110342 55185 110343 55186 110343 56082 110343 56082 110344 55186 110344 55665 110344 56082 110345 55665 110345 55187 110345 55185 110346 55188 110346 55189 110346 55189 110347 55188 110347 56083 110347 56083 110348 56103 110348 55189 110348 55189 110349 56103 110349 55190 110349 55189 110350 55190 110350 55191 110350 55185 110351 55189 110351 55186 110351 55186 110352 55189 110352 54836 110352 55186 110353 54836 110353 55205 110353 55205 110354 54836 110354 55192 110354 55205 110355 55192 110355 55204 110355 55204 110356 55192 110356 55193 110356 55204 110357 55193 110357 55195 110357 55195 110358 55193 110358 55194 110358 55195 110359 55194 110359 55201 110359 55201 110360 55194 110360 55196 110360 55201 110361 55196 110361 55197 110361 55197 110362 55196 110362 54838 110362 55197 110363 54838 110363 55184 110363 55084 110364 55664 110364 55198 110364 55184 110365 55199 110365 55197 110365 55197 110366 55199 110366 55200 110366 55197 110367 55200 110367 55201 110367 55201 110368 55200 110368 55202 110368 55201 110369 55202 110369 55195 110369 55195 110370 55202 110370 55203 110370 55195 110371 55203 110371 55204 110371 55204 110372 55203 110372 55086 110372 55204 110373 55086 110373 55205 110373 55205 110374 55086 110374 55084 110374 55205 110375 55084 110375 55186 110375 55186 110376 55084 110376 55198 110376 55186 110377 55198 110377 55665 110377 55226 110378 55227 110378 55219 110378 55209 110379 55206 110379 55800 110379 55800 110380 55206 110380 55207 110380 55800 110381 55207 110381 55208 110381 55212 110382 55209 110382 55869 110382 55212 110383 55869 110383 55210 110383 55210 110384 55211 110384 55212 110384 55212 110385 55211 110385 55870 110385 55212 110386 55870 110386 55871 110386 55209 110387 55212 110387 55206 110387 55206 110388 55212 110388 54866 110388 55206 110389 54866 110389 55225 110389 55225 110390 54866 110390 55213 110390 55225 110391 55213 110391 55224 110391 55224 110392 55213 110392 55214 110392 55224 110393 55214 110393 55215 110393 55215 110394 55214 110394 54867 110394 55215 110395 54867 110395 55221 110395 55221 110396 54867 110396 55216 110396 55221 110397 55216 110397 55217 110397 55217 110398 55216 110398 54870 110398 55217 110399 54870 110399 55226 110399 55218 110400 55775 110400 55785 110400 55226 110401 55219 110401 55217 110401 55217 110402 55219 110402 55220 110402 55217 110403 55220 110403 55221 110403 55221 110404 55220 110404 55222 110404 55221 110405 55222 110405 55215 110405 55215 110406 55222 110406 55223 110406 55215 110407 55223 110407 55224 110407 55224 110408 55223 110408 55082 110408 55224 110409 55082 110409 55225 110409 55225 110410 55082 110410 55218 110410 55225 110411 55218 110411 55206 110411 55206 110412 55218 110412 55785 110412 55206 110413 55785 110413 55207 110413 54870 110414 54874 110414 55247 110414 54870 110415 55247 110415 55226 110415 55226 110416 55247 110416 55075 110416 55226 110417 55075 110417 55227 110417 55234 110418 55578 110418 55228 110418 56136 110419 56137 110419 55229 110419 56167 110420 55233 110420 55230 110420 54826 110421 55231 110421 55233 110421 55231 110422 56187 110422 55233 110422 55233 110423 56187 110423 55232 110423 55233 110424 55232 110424 55230 110424 55234 110425 55233 110425 55229 110425 55229 110426 55233 110426 56167 110426 55229 110427 56167 110427 56136 110427 55234 110428 55228 110428 55233 110428 55233 110429 55228 110429 55235 110429 55233 110430 55235 110430 55241 110430 55241 110431 55235 110431 55078 110431 55241 110432 55078 110432 55242 110432 55242 110433 55078 110433 55236 110433 55242 110434 55236 110434 55238 110434 55238 110435 55236 110435 55237 110435 55238 110436 55237 110436 55239 110436 55239 110437 55237 110437 55076 110437 55239 110438 55076 110438 55245 110438 55245 110439 55076 110439 55075 110439 55245 110440 55075 110440 55247 110440 54826 110441 55233 110441 55240 110441 55240 110442 55233 110442 55241 110442 55240 110443 55241 110443 54819 110443 54819 110444 55241 110444 55242 110444 54819 110445 55242 110445 55243 110445 55243 110446 55242 110446 55238 110446 55243 110447 55238 110447 54820 110447 54820 110448 55238 110448 55239 110448 54820 110449 55239 110449 55244 110449 55244 110450 55239 110450 55245 110450 55244 110451 55245 110451 55246 110451 55246 110452 55245 110452 55247 110452 55246 110453 55247 110453 54874 110453 55264 110454 55266 110454 56078 110454 56078 110455 55266 110455 55248 110455 56078 110456 55248 110456 55256 110456 55252 110457 55249 110457 55250 110457 55250 110458 55249 110458 55251 110458 55250 110459 55251 110459 56220 110459 55252 110460 55250 110460 55253 110460 55253 110461 55250 110461 55257 110461 55253 110462 55257 110462 56072 110462 55251 110463 56076 110463 56220 110463 56220 110464 56076 110464 55254 110464 56220 110465 55254 110465 55248 110465 55248 110466 55254 110466 55255 110466 55248 110467 55255 110467 55256 110467 56072 110468 55257 110468 56071 110468 56071 110469 55257 110469 55259 110469 56071 110470 55259 110470 55260 110470 56216 110471 55258 110471 55259 110471 55259 110472 55258 110472 56069 110472 55259 110473 56069 110473 55260 110473 55274 110474 55261 110474 55262 110474 55263 110475 56154 110475 56155 110475 56155 110476 56154 110476 56153 110476 56155 110477 56153 110477 56161 110477 55264 110478 55265 110478 55266 110478 55266 110479 55265 110479 55267 110479 55266 110480 55267 110480 55268 110480 55268 110481 55267 110481 55269 110481 55268 110482 55269 110482 55270 110482 55270 110483 55269 110483 55263 110483 55270 110484 55263 110484 55271 110484 55271 110485 55263 110485 56155 110485 55271 110486 56155 110486 55272 110486 55272 110487 56155 110487 56132 110487 55272 110488 56132 110488 55273 110488 55273 110489 56132 110489 56116 110489 55273 110490 56116 110490 55274 110490 56216 110491 55273 110491 55258 110491 55258 110492 55273 110492 55274 110492 55258 110493 55274 110493 56011 110493 56011 110494 55274 110494 55262 110494 56035 110495 55275 110495 56036 110495 56036 110496 55275 110496 55276 110496 56036 110497 55276 110497 56038 110497 56038 110498 55276 110498 55606 110498 56038 110499 55606 110499 55278 110499 55278 110500 55606 110500 55277 110500 55278 110501 55277 110501 55280 110501 55280 110502 55277 110502 55279 110502 55280 110503 55279 110503 55281 110503 55281 110504 55279 110504 55603 110504 55281 110505 55603 110505 55282 110505 55282 110506 55603 110506 55283 110506 55282 110507 55283 110507 56039 110507 56039 110508 55283 110508 55601 110508 56039 110509 55601 110509 56042 110509 56042 110510 55601 110510 55284 110510 56042 110511 55284 110511 56043 110511 56043 110512 55284 110512 55285 110512 56043 110513 55285 110513 56044 110513 56044 110514 55285 110514 55286 110514 56044 110515 55286 110515 56045 110515 56045 110516 55286 110516 55598 110516 56045 110517 55598 110517 56047 110517 56047 110518 55598 110518 55288 110518 56047 110519 55288 110519 55287 110519 55287 110520 55288 110520 55597 110520 55287 110521 55597 110521 56048 110521 56048 110522 55597 110522 55289 110522 56048 110523 55289 110523 55290 110523 55290 110524 55289 110524 55292 110524 55290 110525 55292 110525 55291 110525 55291 110526 55292 110526 55593 110526 55657 110527 55275 110527 55649 110527 55649 110528 55275 110528 56035 110528 55649 110529 56035 110529 55650 110529 55593 110530 55577 110530 55291 110530 55291 110531 55577 110531 55293 110531 55291 110532 55293 110532 55575 110532 55846 110533 55305 110533 55309 110533 55309 110534 55305 110534 56206 110534 55310 110535 55884 110535 55815 110535 55860 110536 55862 110536 56208 110536 56208 110537 55862 110537 55294 110537 55300 110538 55295 110538 55296 110538 55296 110539 55295 110539 55297 110539 55296 110540 55297 110540 55946 110540 55853 110541 55304 110541 55307 110541 55307 110542 55304 110542 55298 110542 56211 110543 55921 110543 55299 110543 55299 110544 55921 110544 55300 110544 55299 110545 55300 110545 56213 110545 56213 110546 55300 110546 55296 110546 56213 110547 55296 110547 55301 110547 55301 110548 55296 110548 55959 110548 55301 110549 55959 110549 55308 110549 55308 110550 55959 110550 55936 110550 55308 110551 55936 110551 55310 110551 55862 110552 55863 110552 55294 110552 55294 110553 55863 110553 55302 110553 55294 110554 55302 110554 56211 110554 56211 110555 55302 110555 55303 110555 56211 110556 55303 110556 55921 110556 55853 110557 55854 110557 55304 110557 55304 110558 55854 110558 55857 110558 55304 110559 55857 110559 55312 110559 55846 110560 55849 110560 55305 110560 55305 110561 55849 110561 55306 110561 55305 110562 55306 110562 55298 110562 55298 110563 55306 110563 55851 110563 55298 110564 55851 110564 55307 110564 56206 110565 55308 110565 55309 110565 55309 110566 55308 110566 55310 110566 55309 110567 55310 110567 55793 110567 55793 110568 55310 110568 55815 110568 55857 110569 55311 110569 55312 110569 55312 110570 55311 110570 55313 110570 55312 110571 55313 110571 56208 110571 56208 110572 55313 110572 55859 110572 56208 110573 55859 110573 55860 110573 55331 110574 55314 110574 55315 110574 55315 110575 55314 110575 55316 110575 55315 110576 55316 110576 55317 110576 55317 110577 55316 110577 55318 110577 55317 110578 55318 110578 55818 110578 55818 110579 55318 110579 55727 110579 55818 110580 55727 110580 55820 110580 55820 110581 55727 110581 55725 110581 55820 110582 55725 110582 55821 110582 55821 110583 55725 110583 55319 110583 55821 110584 55319 110584 55822 110584 55822 110585 55319 110585 55320 110585 55822 110586 55320 110586 55321 110586 55321 110587 55320 110587 55721 110587 55321 110588 55721 110588 55824 110588 55824 110589 55721 110589 55322 110589 55824 110590 55322 110590 55323 110590 55323 110591 55322 110591 55719 110591 55323 110592 55719 110592 55825 110592 55825 110593 55719 110593 55718 110593 55825 110594 55718 110594 55324 110594 55324 110595 55718 110595 55325 110595 55324 110596 55325 110596 55326 110596 55326 110597 55325 110597 55714 110597 55326 110598 55714 110598 55829 110598 55829 110599 55714 110599 55713 110599 55829 110600 55713 110600 55327 110600 55327 110601 55713 110601 55328 110601 55327 110602 55328 110602 55830 110602 55830 110603 55328 110603 55329 110603 55830 110604 55329 110604 55918 110604 55918 110605 55329 110605 55710 110605 55330 110606 55314 110606 55332 110606 55332 110607 55314 110607 55331 110607 55332 110608 55331 110608 55774 110608 55710 110609 55708 110609 55918 110609 55918 110610 55708 110610 55333 110610 55918 110611 55333 110611 55692 110611 54977 110612 55390 110612 54975 110612 54975 110613 55390 110613 55403 110613 54975 110614 55403 110614 55349 110614 55345 110615 55436 110615 54936 110615 54936 110616 55436 110616 55334 110616 54936 110617 55334 110617 55335 110617 55335 110618 55334 110618 55336 110618 55338 110619 55356 110619 55340 110619 55335 110620 55336 110620 55337 110620 55337 110621 55336 110621 55338 110621 55337 110622 55338 110622 55339 110622 55339 110623 55338 110623 55340 110623 55339 110624 55340 110624 55341 110624 55342 110625 55343 110625 55433 110625 54917 110626 54921 110626 55342 110626 55342 110627 55433 110627 54917 110627 54917 110628 55433 110628 55427 110628 54917 110629 55427 110629 55344 110629 55344 110630 55427 110630 55436 110630 55344 110631 55436 110631 55345 110631 55370 110632 55372 110632 55347 110632 55346 110633 54971 110633 55370 110633 55370 110634 55347 110634 55346 110634 55346 110635 55347 110635 55348 110635 55346 110636 55348 110636 54979 110636 54979 110637 55348 110637 55390 110637 54979 110638 55390 110638 54977 110638 55349 110639 55403 110639 55412 110639 55352 110640 55380 110640 55350 110640 55349 110641 55412 110641 55351 110641 55351 110642 55412 110642 55352 110642 55351 110643 55352 110643 54935 110643 54935 110644 55352 110644 55350 110644 54935 110645 55350 110645 54947 110645 55341 110646 55340 110646 55355 110646 55355 110647 55340 110647 55354 110647 54913 110648 55353 110648 54841 110648 54841 110649 55353 110649 54916 110649 54841 110650 54916 110650 55354 110650 55354 110651 54916 110651 54915 110651 55354 110652 54915 110652 55355 110652 54842 110653 54841 110653 55449 110653 55449 110654 54841 110654 55354 110654 55449 110655 55354 110655 55452 110655 55452 110656 55354 110656 55455 110656 55455 110657 55354 110657 55456 110657 55456 110658 55354 110658 55340 110658 55456 110659 55340 110659 55356 110659 55360 110660 55357 110660 55362 110660 55358 110661 54839 110661 55359 110661 55358 110662 55359 110662 55357 110662 55360 110663 55362 110663 55361 110663 55342 110664 54921 110664 55361 110664 55361 110665 55362 110665 55342 110665 55342 110666 55362 110666 55424 110666 55342 110667 55424 110667 55343 110667 55357 110668 55359 110668 55362 110668 55362 110669 55359 110669 55363 110669 55362 110670 55363 110670 55364 110670 55364 110671 55421 110671 55362 110671 55362 110672 55421 110672 55365 110672 55362 110673 55365 110673 55424 110673 55366 110674 55367 110674 55373 110674 55368 110675 54871 110675 55369 110675 55368 110676 55369 110676 55367 110676 55366 110677 55373 110677 54983 110677 55370 110678 54971 110678 54983 110678 54983 110679 55373 110679 55370 110679 55370 110680 55373 110680 55371 110680 55370 110681 55371 110681 55372 110681 55367 110682 55369 110682 55373 110682 55373 110683 55369 110683 55557 110683 55373 110684 55557 110684 55385 110684 55385 110685 55383 110685 55373 110685 55373 110686 55383 110686 55384 110686 55373 110687 55384 110687 55371 110687 54947 110688 55350 110688 55374 110688 55374 110689 55350 110689 55379 110689 54927 110690 55375 110690 54872 110690 54872 110691 55375 110691 54938 110691 54872 110692 54938 110692 55379 110692 55379 110693 54938 110693 54948 110693 55379 110694 54948 110694 55374 110694 54873 110695 54872 110695 55376 110695 55376 110696 54872 110696 55379 110696 55376 110697 55379 110697 55377 110697 55377 110698 55379 110698 55378 110698 55378 110699 55379 110699 55419 110699 55419 110700 55379 110700 55350 110700 55419 110701 55350 110701 55380 110701 55559 110702 55381 110702 55553 110702 55553 110703 55381 110703 55371 110703 55553 110704 55371 110704 55382 110704 55385 110705 55554 110705 55383 110705 55383 110706 55554 110706 55382 110706 55383 110707 55382 110707 55384 110707 55384 110708 55382 110708 55371 110708 55557 110709 55386 110709 55385 110709 55385 110710 55386 110710 55387 110710 55385 110711 55387 110711 55554 110711 55372 110712 55371 110712 55388 110712 55388 110713 55371 110713 55381 110713 55388 110714 55381 110714 55389 110714 55389 110715 55381 110715 55559 110715 55389 110716 55559 110716 55561 110716 55397 110717 55390 110717 55348 110717 55388 110718 55389 110718 55391 110718 55392 110719 55396 110719 55393 110719 55538 110720 55394 110720 55398 110720 55389 110721 55561 110721 55391 110721 55391 110722 55561 110722 55395 110722 55391 110723 55395 110723 55393 110723 55393 110724 55395 110724 55540 110724 55393 110725 55540 110725 55392 110725 55400 110726 55391 110726 55399 110726 55399 110727 55391 110727 55393 110727 55399 110728 55393 110728 55398 110728 55398 110729 55393 110729 55396 110729 55398 110730 55396 110730 55538 110730 55400 110731 55397 110731 55391 110731 55391 110732 55397 110732 55348 110732 55391 110733 55348 110733 55388 110733 55388 110734 55348 110734 55347 110734 55388 110735 55347 110735 55372 110735 55394 110736 55519 110736 55398 110736 55398 110737 55519 110737 55409 110737 55398 110738 55409 110738 55399 110738 55399 110739 55409 110739 55401 110739 55399 110740 55401 110740 55400 110740 55400 110741 55401 110741 55402 110741 55400 110742 55402 110742 55397 110742 55397 110743 55402 110743 55410 110743 55397 110744 55410 110744 55390 110744 55390 110745 55410 110745 55403 110745 55404 110746 55513 110746 55405 110746 55406 110747 55517 110747 55407 110747 55407 110748 55517 110748 55526 110748 55526 110749 55408 110749 55407 110749 55407 110750 55408 110750 55524 110750 55407 110751 55524 110751 55411 110751 55519 110752 55406 110752 55409 110752 55409 110753 55406 110753 55407 110753 55409 110754 55407 110754 55401 110754 55401 110755 55407 110755 55411 110755 55401 110756 55411 110756 55402 110756 55402 110757 55411 110757 55410 110757 55410 110758 55411 110758 55412 110758 55410 110759 55412 110759 55403 110759 55524 110760 55404 110760 55411 110760 55411 110761 55404 110761 55405 110761 55411 110762 55405 110762 55412 110762 55412 110763 55405 110763 55413 110763 55412 110764 55413 110764 55352 110764 55352 110765 55413 110765 55380 110765 55418 110766 55414 110766 55417 110766 55415 110767 54873 110767 55376 110767 55415 110768 55376 110768 55510 110768 55510 110769 55376 110769 55377 110769 55510 110770 55377 110770 55512 110770 55512 110771 55377 110771 55378 110771 55512 110772 55378 110772 55416 110772 55414 110773 55413 110773 55417 110773 55417 110774 55413 110774 55405 110774 55417 110775 55405 110775 55513 110775 55416 110776 55378 110776 55418 110776 55418 110777 55378 110777 55419 110777 55418 110778 55419 110778 55414 110778 55414 110779 55419 110779 55380 110779 55414 110780 55380 110780 55413 110780 55461 110781 55425 110781 55459 110781 55459 110782 55425 110782 55424 110782 55459 110783 55424 110783 55460 110783 55364 110784 55420 110784 55421 110784 55421 110785 55420 110785 55460 110785 55421 110786 55460 110786 55365 110786 55365 110787 55460 110787 55424 110787 55363 110788 55422 110788 55364 110788 55364 110789 55422 110789 55423 110789 55364 110790 55423 110790 55420 110790 55343 110791 55424 110791 55434 110791 55434 110792 55424 110792 55425 110792 55434 110793 55425 110793 55426 110793 55426 110794 55425 110794 55461 110794 55426 110795 55461 110795 55469 110795 55434 110796 55426 110796 55430 110796 55438 110797 55436 110797 55427 110797 55429 110798 55465 110798 55432 110798 55464 110799 55428 110799 55442 110799 55429 110800 55432 110800 55466 110800 55426 110801 55469 110801 55430 110801 55430 110802 55469 110802 55468 110802 55430 110803 55468 110803 55432 110803 55432 110804 55468 110804 55467 110804 55432 110805 55467 110805 55466 110805 55440 110806 55430 110806 55431 110806 55431 110807 55430 110807 55432 110807 55431 110808 55432 110808 55442 110808 55442 110809 55432 110809 55465 110809 55442 110810 55465 110810 55464 110810 55440 110811 55438 110811 55430 110811 55430 110812 55438 110812 55427 110812 55430 110813 55427 110813 55434 110813 55434 110814 55427 110814 55433 110814 55434 110815 55433 110815 55343 110815 55334 110816 55436 110816 55435 110816 55435 110817 55436 110817 55438 110817 55435 110818 55438 110818 55437 110818 55437 110819 55438 110819 55440 110819 55437 110820 55440 110820 55439 110820 55439 110821 55440 110821 55431 110821 55439 110822 55431 110822 55441 110822 55441 110823 55431 110823 55442 110823 55441 110824 55442 110824 55483 110824 55483 110825 55442 110825 55428 110825 55497 110826 55499 110826 55443 110826 55443 110827 55499 110827 55500 110827 55500 110828 55501 110828 55443 110828 55443 110829 55501 110829 55444 110829 55443 110830 55444 110830 55445 110830 55356 110831 55338 110831 55446 110831 55446 110832 55338 110832 55336 110832 55446 110833 55336 110833 55447 110833 55334 110834 55435 110834 55336 110834 55336 110835 55435 110835 55445 110835 55336 110836 55445 110836 55447 110836 55447 110837 55445 110837 55444 110837 55447 110838 55444 110838 55454 110838 55483 110839 55497 110839 55441 110839 55441 110840 55497 110840 55443 110840 55441 110841 55443 110841 55439 110841 55439 110842 55443 110842 55445 110842 55439 110843 55445 110843 55437 110843 55437 110844 55445 110844 55435 110844 55505 110845 55457 110845 55448 110845 55450 110846 54842 110846 55449 110846 55450 110847 55449 110847 55451 110847 55451 110848 55449 110848 55452 110848 55451 110849 55452 110849 55453 110849 55453 110850 55452 110850 55455 110850 55453 110851 55455 110851 55504 110851 55457 110852 55446 110852 55448 110852 55448 110853 55446 110853 55447 110853 55448 110854 55447 110854 55454 110854 55504 110855 55455 110855 55505 110855 55505 110856 55455 110856 55456 110856 55505 110857 55456 110857 55457 110857 55457 110858 55456 110858 55356 110858 55457 110859 55356 110859 55446 110859 55363 110860 54846 110860 55422 110860 55422 110861 54846 110861 54843 110861 55422 110862 54843 110862 55458 110862 55461 110863 55459 110863 55458 110863 55458 110864 55459 110864 55460 110864 55460 110865 55420 110865 55458 110865 55458 110866 55420 110866 55423 110866 55458 110867 55423 110867 55422 110867 54843 110868 55482 110868 55458 110868 55458 110869 55482 110869 55481 110869 55458 110870 55481 110870 55461 110870 55461 110871 55481 110871 55462 110871 55461 110872 55462 110872 55469 110872 55469 110873 55462 110873 55476 110873 55463 110874 55428 110874 55464 110874 55477 110875 55484 110875 55471 110875 55484 110876 55463 110876 55470 110876 55470 110877 55463 110877 55464 110877 55470 110878 55464 110878 55473 110878 55473 110879 55464 110879 55465 110879 55465 110880 55429 110880 55473 110880 55473 110881 55429 110881 55466 110881 55473 110882 55466 110882 55474 110882 55474 110883 55466 110883 55467 110883 55474 110884 55467 110884 55476 110884 55476 110885 55467 110885 55468 110885 55476 110886 55468 110886 55469 110886 55484 110887 55470 110887 55471 110887 55471 110888 55470 110888 55473 110888 55471 110889 55473 110889 55472 110889 55472 110890 55473 110890 55474 110890 55472 110891 55474 110891 55475 110891 55475 110892 55474 110892 55476 110892 55475 110893 55476 110893 55479 110893 55479 110894 55476 110894 55462 110894 55479 110895 55462 110895 55481 110895 55477 110896 55471 110896 54850 110896 54850 110897 55471 110897 55472 110897 54850 110898 55472 110898 55478 110898 55478 110899 55472 110899 55475 110899 55478 110900 55475 110900 54847 110900 54847 110901 55475 110901 55479 110901 54847 110902 55479 110902 55480 110902 55480 110903 55479 110903 55481 110903 55480 110904 55481 110904 55482 110904 55483 110905 55428 110905 55463 110905 55483 110906 55463 110906 55485 110906 55485 110907 55463 110907 55484 110907 55485 110908 55484 110908 55486 110908 55486 110909 55484 110909 55477 110909 55486 110910 55477 110910 54849 110910 55486 110911 54849 110911 55488 110911 55485 110912 55486 110912 55487 110912 55497 110913 55483 110913 55498 110913 55498 110914 55483 110914 55485 110914 55486 110915 55488 110915 55487 110915 55487 110916 55488 110916 55489 110916 55487 110917 55489 110917 55492 110917 55492 110918 55489 110918 55490 110918 55492 110919 55490 110919 55493 110919 55493 110920 55490 110920 54845 110920 55493 110921 54845 110921 55496 110921 54845 110922 55491 110922 55496 110922 55496 110923 55491 110923 55508 110923 55496 110924 55508 110924 55507 110924 55485 110925 55487 110925 55498 110925 55498 110926 55487 110926 55492 110926 55498 110927 55492 110927 55494 110927 55494 110928 55492 110928 55493 110928 55494 110929 55493 110929 55495 110929 55495 110930 55493 110930 55496 110930 55495 110931 55496 110931 55502 110931 55502 110932 55496 110932 55507 110932 55502 110933 55507 110933 55503 110933 55497 110934 55498 110934 55499 110934 55499 110935 55498 110935 55494 110935 55499 110936 55494 110936 55500 110936 55500 110937 55494 110937 55495 110937 55500 110938 55495 110938 55501 110938 55501 110939 55495 110939 55502 110939 55501 110940 55502 110940 55444 110940 55444 110941 55502 110941 55503 110941 55444 110942 55503 110942 55454 110942 55504 110943 55505 110943 55509 110943 54842 110944 55450 110944 55506 110944 55506 110945 55450 110945 55451 110945 55506 110946 55451 110946 55509 110946 55509 110947 55451 110947 55453 110947 55509 110948 55453 110948 55504 110948 55507 110949 55448 110949 55503 110949 55503 110950 55448 110950 55454 110950 55508 110951 55509 110951 55507 110951 55507 110952 55509 110952 55505 110952 55507 110953 55505 110953 55448 110953 55506 110954 55509 110954 54844 110954 54844 110955 55509 110955 55508 110955 54844 110956 55508 110956 55491 110956 55415 110957 55510 110957 55511 110957 55511 110958 55510 110958 55512 110958 55512 110959 55416 110959 55511 110959 55511 110960 55416 110960 55418 110960 55511 110961 55418 110961 55515 110961 55515 110962 55418 110962 55417 110962 55515 110963 55417 110963 55530 110963 55530 110964 55417 110964 55513 110964 54873 110965 55415 110965 55514 110965 55514 110966 55415 110966 55511 110966 55514 110967 55511 110967 54875 110967 54875 110968 55511 110968 55515 110968 54875 110969 55515 110969 55516 110969 55517 110970 55406 110970 55518 110970 55406 110971 55519 110971 55518 110971 55518 110972 55519 110972 55535 110972 55518 110973 55535 110973 55520 110973 55520 110974 55535 110974 55534 110974 55520 110975 55534 110975 54879 110975 54879 110976 55534 110976 55531 110976 55526 110977 55517 110977 55523 110977 55523 110978 55517 110978 55518 110978 55523 110979 55518 110979 55521 110979 55521 110980 55518 110980 55520 110980 55521 110981 55520 110981 54878 110981 54878 110982 55520 110982 54879 110982 54878 110983 55522 110983 55521 110983 55521 110984 55522 110984 55528 110984 55521 110985 55528 110985 55523 110985 55523 110986 55528 110986 55525 110986 55523 110987 55525 110987 55526 110987 55404 110988 55524 110988 55525 110988 55525 110989 55524 110989 55408 110989 55525 110990 55408 110990 55526 110990 55530 110991 55529 110991 55515 110991 55515 110992 55529 110992 55527 110992 55515 110993 55527 110993 55516 110993 55516 110994 55527 110994 54876 110994 55522 110995 54876 110995 55528 110995 55528 110996 54876 110996 55527 110996 55528 110997 55527 110997 55525 110997 55525 110998 55527 110998 55529 110998 55525 110999 55529 110999 55404 110999 55404 111000 55529 111000 55530 111000 55404 111001 55530 111001 55513 111001 55532 111002 55531 111002 55534 111002 55532 111003 55534 111003 55533 111003 55533 111004 55534 111004 55535 111004 55533 111005 55535 111005 55537 111005 55537 111006 55535 111006 55519 111006 55537 111007 55519 111007 55394 111007 55545 111008 55552 111008 55536 111008 55537 111009 55394 111009 55538 111009 55532 111010 55533 111010 55541 111010 55533 111011 55537 111011 55542 111011 55542 111012 55537 111012 55538 111012 55542 111013 55538 111013 55543 111013 55543 111014 55538 111014 55396 111014 55396 111015 55392 111015 55543 111015 55543 111016 55392 111016 55540 111016 55543 111017 55540 111017 55539 111017 55539 111018 55540 111018 55395 111018 55539 111019 55395 111019 55544 111019 55544 111020 55395 111020 55561 111020 55544 111021 55561 111021 55560 111021 55533 111022 55542 111022 55541 111022 55541 111023 55542 111023 55543 111023 55541 111024 55543 111024 55547 111024 55547 111025 55543 111025 55539 111025 55547 111026 55539 111026 55550 111026 55550 111027 55539 111027 55544 111027 55550 111028 55544 111028 55536 111028 55536 111029 55544 111029 55560 111029 55536 111030 55560 111030 55545 111030 55532 111031 55541 111031 55546 111031 55546 111032 55541 111032 55547 111032 55546 111033 55547 111033 55548 111033 55548 111034 55547 111034 55550 111034 55548 111035 55550 111035 55549 111035 55549 111036 55550 111036 55536 111036 55549 111037 55536 111037 55551 111037 55551 111038 55536 111038 55552 111038 55551 111039 55552 111039 55558 111039 55559 111040 55553 111040 55555 111040 55555 111041 55553 111041 55382 111041 55382 111042 55554 111042 55555 111042 55555 111043 55554 111043 55387 111043 55555 111044 55387 111044 55556 111044 55556 111045 55387 111045 55386 111045 55556 111046 55386 111046 55557 111046 55556 111047 54877 111047 55555 111047 55555 111048 54877 111048 55558 111048 55558 111049 55552 111049 55555 111049 55555 111050 55552 111050 55545 111050 55555 111051 55545 111051 55559 111051 55559 111052 55545 111052 55560 111052 55559 111053 55560 111053 55561 111053 56150 111054 55582 111054 56149 111054 56149 111055 55582 111055 55567 111055 56149 111056 55567 111056 56146 111056 56146 111057 55567 111057 55570 111057 56146 111058 55570 111058 56145 111058 56145 111059 55570 111059 55562 111059 56145 111060 55562 111060 55563 111060 55562 111061 55234 111061 55229 111061 55563 111062 55562 111062 55564 111062 55564 111063 55562 111063 55229 111063 55564 111064 55229 111064 56137 111064 55578 111065 55234 111065 55565 111065 55565 111066 55234 111066 55562 111066 55565 111067 55562 111067 55566 111067 55566 111068 55562 111068 55570 111068 55582 111069 55568 111069 55567 111069 55567 111070 55568 111070 55569 111070 55567 111071 55569 111071 55570 111071 55570 111072 55569 111072 55571 111072 55570 111073 55571 111073 55566 111073 55565 111074 55566 111074 55573 111074 55572 111075 55579 111075 55573 111075 55574 111076 55583 111076 55071 111076 55575 111077 55293 111077 55576 111077 55293 111078 55577 111078 55576 111078 55576 111079 55577 111079 55592 111079 55576 111080 55592 111080 55580 111080 55580 111081 55592 111081 55581 111081 55578 111082 55565 111082 55071 111082 55071 111083 55565 111083 55573 111083 55071 111084 55573 111084 55574 111084 55574 111085 55573 111085 55579 111085 55566 111086 55571 111086 55573 111086 55573 111087 55571 111087 55580 111087 55573 111088 55580 111088 55572 111088 55572 111089 55580 111089 55581 111089 56150 111090 55575 111090 55582 111090 55582 111091 55575 111091 55576 111091 55582 111092 55576 111092 55568 111092 55568 111093 55576 111093 55580 111093 55568 111094 55580 111094 55569 111094 55569 111095 55580 111095 55571 111095 55132 111096 55134 111096 55585 111096 55585 111097 55134 111097 55133 111097 55585 111098 55133 111098 55583 111098 55588 111099 55590 111099 55585 111099 55585 111100 55590 111100 55584 111100 55585 111101 55584 111101 55132 111101 55583 111102 55574 111102 55585 111102 55585 111103 55574 111103 55579 111103 55585 111104 55579 111104 55588 111104 55577 111105 55586 111105 55591 111105 55591 111106 55586 111106 55587 111106 55591 111107 55587 111107 55588 111107 55588 111108 55587 111108 55589 111108 55588 111109 55589 111109 55590 111109 55579 111110 55572 111110 55588 111110 55588 111111 55572 111111 55581 111111 55588 111112 55581 111112 55591 111112 55591 111113 55581 111113 55592 111113 55591 111114 55592 111114 55577 111114 55586 111115 55577 111115 55593 111115 55586 111116 55593 111116 55587 111116 55587 111117 55593 111117 55596 111117 55587 111118 55596 111118 55589 111118 55589 111119 55596 111119 55594 111119 55589 111120 55594 111120 55590 111120 55590 111121 55594 111121 55584 111121 55584 111122 55594 111122 55595 111122 55584 111123 55595 111123 55132 111123 55595 111124 55594 111124 55610 111124 55594 111125 55596 111125 55609 111125 55596 111126 55593 111126 55292 111126 55596 111127 55292 111127 55609 111127 55609 111128 55292 111128 55289 111128 55609 111129 55289 111129 55612 111129 55612 111130 55289 111130 55597 111130 55612 111131 55597 111131 55613 111131 55613 111132 55597 111132 55288 111132 55613 111133 55288 111133 55614 111133 55614 111134 55288 111134 55598 111134 55614 111135 55598 111135 55615 111135 55615 111136 55598 111136 55286 111136 55615 111137 55286 111137 55616 111137 55616 111138 55286 111138 55285 111138 55616 111139 55285 111139 55599 111139 55599 111140 55285 111140 55284 111140 55599 111141 55284 111141 55600 111141 55600 111142 55284 111142 55601 111142 55600 111143 55601 111143 55617 111143 55617 111144 55601 111144 55283 111144 55617 111145 55283 111145 55602 111145 55602 111146 55283 111146 55603 111146 55602 111147 55603 111147 55604 111147 55604 111148 55603 111148 55279 111148 55604 111149 55279 111149 55605 111149 55605 111150 55279 111150 55277 111150 55605 111151 55277 111151 55620 111151 55620 111152 55277 111152 55606 111152 55620 111153 55606 111153 55607 111153 55607 111154 55606 111154 55276 111154 55607 111155 55276 111155 55608 111155 55608 111156 55276 111156 55275 111156 55608 111157 55275 111157 55639 111157 55594 111158 55609 111158 55610 111158 55610 111159 55609 111159 55612 111159 55610 111160 55612 111160 55611 111160 55611 111161 55612 111161 55613 111161 55611 111162 55613 111162 55622 111162 55622 111163 55613 111163 55614 111163 55622 111164 55614 111164 55624 111164 55624 111165 55614 111165 55615 111165 55624 111166 55615 111166 55625 111166 55625 111167 55615 111167 55616 111167 55625 111168 55616 111168 55627 111168 55627 111169 55616 111169 55599 111169 55627 111170 55599 111170 55629 111170 55629 111171 55599 111171 55600 111171 55629 111172 55600 111172 55630 111172 55630 111173 55600 111173 55617 111173 55630 111174 55617 111174 55631 111174 55631 111175 55617 111175 55602 111175 55631 111176 55602 111176 55618 111176 55618 111177 55602 111177 55604 111177 55618 111178 55604 111178 55632 111178 55632 111179 55604 111179 55605 111179 55632 111180 55605 111180 55619 111180 55619 111181 55605 111181 55620 111181 55619 111182 55620 111182 55634 111182 55634 111183 55620 111183 55607 111183 55634 111184 55607 111184 55636 111184 55636 111185 55607 111185 55608 111185 55636 111186 55608 111186 55637 111186 55637 111187 55608 111187 55639 111187 55637 111188 55639 111188 55641 111188 55595 111189 55610 111189 55621 111189 55621 111190 55610 111190 55611 111190 55621 111191 55611 111191 54898 111191 54898 111192 55611 111192 55622 111192 54898 111193 55622 111193 55623 111193 55623 111194 55622 111194 55624 111194 55623 111195 55624 111195 54899 111195 54899 111196 55624 111196 55625 111196 54899 111197 55625 111197 55626 111197 55626 111198 55625 111198 55627 111198 55626 111199 55627 111199 55628 111199 55628 111200 55627 111200 55629 111200 55628 111201 55629 111201 54895 111201 54895 111202 55629 111202 55630 111202 54895 111203 55630 111203 54907 111203 54907 111204 55630 111204 55631 111204 54907 111205 55631 111205 54909 111205 54909 111206 55631 111206 55618 111206 54909 111207 55618 111207 54910 111207 54910 111208 55618 111208 55632 111208 54910 111209 55632 111209 54901 111209 54901 111210 55632 111210 55619 111210 54901 111211 55619 111211 55633 111211 55633 111212 55619 111212 55634 111212 55633 111213 55634 111213 54892 111213 54892 111214 55634 111214 55636 111214 54892 111215 55636 111215 55635 111215 55635 111216 55636 111216 55637 111216 55635 111217 55637 111217 54884 111217 54884 111218 55637 111218 55641 111218 54884 111219 55641 111219 54903 111219 55657 111220 55638 111220 55275 111220 55275 111221 55638 111221 55639 111221 55638 111222 55647 111222 55639 111222 55639 111223 55647 111223 55640 111223 55639 111224 55640 111224 55641 111224 54902 111225 54903 111225 55643 111225 55643 111226 54903 111226 55641 111226 55643 111227 55641 111227 55646 111227 55646 111228 55641 111228 55640 111228 55642 111229 54902 111229 55643 111229 55645 111230 55113 111230 55642 111230 55642 111231 55643 111231 55645 111231 55645 111232 55643 111232 55646 111232 55645 111233 55646 111233 55644 111233 55657 111234 55658 111234 55648 111234 55648 111235 55658 111235 55660 111235 55648 111236 55660 111236 55644 111236 55644 111237 55660 111237 55662 111237 55644 111238 55662 111238 55645 111238 55645 111239 55662 111239 55663 111239 55645 111240 55663 111240 55113 111240 55113 111241 55663 111241 55087 111241 55646 111242 55640 111242 55644 111242 55644 111243 55640 111243 55647 111243 55644 111244 55647 111244 55648 111244 55648 111245 55647 111245 55638 111245 55648 111246 55638 111246 55657 111246 55659 111247 55649 111247 55650 111247 55664 111248 55651 111248 55652 111248 55652 111249 55651 111249 55661 111249 55652 111250 55661 111250 55668 111250 55668 111251 55661 111251 55653 111251 55653 111252 55661 111252 55654 111252 55653 111253 55654 111253 55671 111253 55671 111254 55654 111254 55655 111254 55655 111255 55654 111255 55659 111255 55655 111256 55659 111256 55673 111256 55673 111257 55659 111257 55650 111257 55673 111258 55650 111258 55656 111258 55657 111259 55649 111259 55658 111259 55658 111260 55649 111260 55659 111260 55658 111261 55659 111261 55660 111261 55660 111262 55659 111262 55654 111262 55660 111263 55654 111263 55662 111263 55662 111264 55654 111264 55661 111264 55662 111265 55661 111265 55663 111265 55663 111266 55661 111266 55651 111266 55663 111267 55651 111267 55087 111267 55652 111268 55669 111268 55664 111268 55664 111269 55669 111269 55198 111269 55669 111270 56026 111270 56022 111270 55198 111271 55669 111271 55665 111271 55665 111272 55669 111272 56022 111272 55665 111273 56022 111273 55187 111273 55666 111274 55667 111274 55672 111274 55672 111275 55667 111275 56029 111275 55672 111276 56029 111276 55670 111276 55652 111277 55668 111277 55669 111277 55669 111278 55668 111278 55670 111278 55669 111279 55670 111279 56026 111279 56026 111280 55670 111280 56029 111280 55668 111281 55653 111281 55670 111281 55670 111282 55653 111282 55671 111282 55670 111283 55671 111283 55672 111283 55672 111284 55671 111284 55655 111284 55672 111285 55655 111285 55666 111285 55666 111286 55655 111286 55673 111286 55666 111287 55673 111287 55656 111287 55935 111288 55675 111288 55674 111288 55674 111289 55675 111289 55676 111289 55674 111290 55676 111290 55677 111290 55677 111291 55676 111291 55678 111291 55677 111292 55678 111292 55679 111292 55679 111293 55678 111293 55682 111293 55679 111294 55682 111294 55951 111294 55682 111295 55680 111295 55165 111295 55951 111296 55682 111296 55948 111296 55948 111297 55682 111297 55165 111297 55948 111298 55165 111298 55681 111298 55091 111299 55680 111299 55690 111299 55690 111300 55680 111300 55682 111300 55690 111301 55682 111301 55685 111301 55685 111302 55682 111302 55678 111302 55675 111303 55694 111303 55676 111303 55676 111304 55694 111304 55683 111304 55676 111305 55683 111305 55678 111305 55678 111306 55683 111306 55684 111306 55678 111307 55684 111307 55685 111307 55690 111308 55685 111308 55691 111308 55706 111309 55700 111309 55691 111309 55699 111310 55686 111310 55090 111310 55692 111311 55333 111311 55693 111311 55333 111312 55708 111312 55693 111312 55693 111313 55708 111313 55687 111313 55693 111314 55687 111314 55688 111314 55688 111315 55687 111315 55689 111315 55091 111316 55690 111316 55090 111316 55090 111317 55690 111317 55691 111317 55090 111318 55691 111318 55699 111318 55699 111319 55691 111319 55700 111319 55685 111320 55684 111320 55691 111320 55691 111321 55684 111321 55688 111321 55691 111322 55688 111322 55706 111322 55706 111323 55688 111323 55689 111323 55935 111324 55692 111324 55675 111324 55675 111325 55692 111325 55693 111325 55675 111326 55693 111326 55694 111326 55694 111327 55693 111327 55688 111327 55694 111328 55688 111328 55683 111328 55683 111329 55688 111329 55684 111329 55695 111330 55115 111330 55701 111330 55701 111331 55115 111331 55696 111331 55701 111332 55696 111332 55686 111332 55703 111333 55697 111333 55701 111333 55701 111334 55697 111334 55698 111334 55701 111335 55698 111335 55695 111335 55686 111336 55699 111336 55701 111336 55701 111337 55699 111337 55700 111337 55701 111338 55700 111338 55703 111338 55708 111339 55702 111339 55707 111339 55707 111340 55702 111340 55704 111340 55707 111341 55704 111341 55703 111341 55703 111342 55704 111342 55705 111342 55703 111343 55705 111343 55697 111343 55700 111344 55706 111344 55703 111344 55703 111345 55706 111345 55689 111345 55703 111346 55689 111346 55707 111346 55707 111347 55689 111347 55687 111347 55707 111348 55687 111348 55708 111348 55702 111349 55708 111349 55710 111349 55702 111350 55710 111350 55704 111350 55704 111351 55710 111351 55711 111351 55704 111352 55711 111352 55705 111352 55705 111353 55711 111353 55730 111353 55705 111354 55730 111354 55697 111354 55697 111355 55730 111355 55698 111355 55698 111356 55730 111356 54891 111356 55698 111357 54891 111357 55695 111357 54891 111358 55730 111358 55732 111358 55730 111359 55711 111359 55709 111359 55711 111360 55710 111360 55329 111360 55711 111361 55329 111361 55709 111361 55709 111362 55329 111362 55328 111362 55709 111363 55328 111363 55731 111363 55731 111364 55328 111364 55713 111364 55731 111365 55713 111365 55712 111365 55712 111366 55713 111366 55714 111366 55712 111367 55714 111367 55715 111367 55715 111368 55714 111368 55325 111368 55715 111369 55325 111369 55716 111369 55716 111370 55325 111370 55718 111370 55716 111371 55718 111371 55717 111371 55717 111372 55718 111372 55719 111372 55717 111373 55719 111373 55720 111373 55720 111374 55719 111374 55322 111374 55720 111375 55322 111375 55735 111375 55735 111376 55322 111376 55721 111376 55735 111377 55721 111377 55722 111377 55722 111378 55721 111378 55320 111378 55722 111379 55320 111379 55723 111379 55723 111380 55320 111380 55319 111380 55723 111381 55319 111381 55724 111381 55724 111382 55319 111382 55725 111382 55724 111383 55725 111383 55726 111383 55726 111384 55725 111384 55727 111384 55726 111385 55727 111385 55738 111385 55738 111386 55727 111386 55318 111386 55738 111387 55318 111387 55739 111387 55739 111388 55318 111388 55316 111388 55739 111389 55316 111389 55728 111389 55728 111390 55316 111390 55314 111390 55728 111391 55314 111391 55729 111391 55730 111392 55709 111392 55732 111392 55732 111393 55709 111393 55731 111393 55732 111394 55731 111394 55733 111394 55733 111395 55731 111395 55712 111395 55733 111396 55712 111396 55745 111396 55745 111397 55712 111397 55715 111397 55745 111398 55715 111398 55747 111398 55747 111399 55715 111399 55716 111399 55747 111400 55716 111400 55748 111400 55748 111401 55716 111401 55717 111401 55748 111402 55717 111402 55750 111402 55750 111403 55717 111403 55720 111403 55750 111404 55720 111404 55752 111404 55752 111405 55720 111405 55735 111405 55752 111406 55735 111406 55734 111406 55734 111407 55735 111407 55722 111407 55734 111408 55722 111408 55753 111408 55753 111409 55722 111409 55723 111409 55753 111410 55723 111410 55754 111410 55754 111411 55723 111411 55724 111411 55754 111412 55724 111412 55736 111412 55736 111413 55724 111413 55726 111413 55736 111414 55726 111414 55737 111414 55737 111415 55726 111415 55738 111415 55737 111416 55738 111416 55740 111416 55740 111417 55738 111417 55739 111417 55740 111418 55739 111418 55741 111418 55741 111419 55739 111419 55728 111419 55741 111420 55728 111420 55759 111420 55759 111421 55728 111421 55729 111421 55759 111422 55729 111422 55742 111422 54891 111423 55732 111423 55743 111423 55743 111424 55732 111424 55733 111424 55743 111425 55733 111425 55744 111425 55744 111426 55733 111426 55745 111426 55744 111427 55745 111427 55746 111427 55746 111428 55745 111428 55747 111428 55746 111429 55747 111429 54900 111429 54900 111430 55747 111430 55748 111430 54900 111431 55748 111431 55749 111431 55749 111432 55748 111432 55750 111432 55749 111433 55750 111433 55751 111433 55751 111434 55750 111434 55752 111434 55751 111435 55752 111435 54908 111435 54908 111436 55752 111436 55734 111436 54908 111437 55734 111437 54906 111437 54906 111438 55734 111438 55753 111438 54906 111439 55753 111439 54905 111439 54905 111440 55753 111440 55754 111440 54905 111441 55754 111441 55755 111441 55755 111442 55754 111442 55736 111442 55755 111443 55736 111443 55756 111443 55756 111444 55736 111444 55737 111444 55756 111445 55737 111445 55757 111445 55757 111446 55737 111446 55740 111446 55757 111447 55740 111447 54896 111447 54896 111448 55740 111448 55741 111448 54896 111449 55741 111449 55758 111449 55758 111450 55741 111450 55759 111450 55758 111451 55759 111451 55760 111451 55760 111452 55759 111452 55742 111452 55760 111453 55742 111453 54881 111453 55330 111454 55761 111454 55314 111454 55314 111455 55761 111455 55729 111455 55761 111456 55762 111456 55729 111456 55729 111457 55762 111457 55763 111457 55729 111458 55763 111458 55742 111458 54887 111459 54881 111459 55764 111459 55764 111460 54881 111460 55742 111460 55764 111461 55742 111461 55771 111461 55771 111462 55742 111462 55763 111462 55765 111463 54887 111463 55764 111463 55769 111464 55770 111464 55765 111464 55765 111465 55764 111465 55769 111465 55769 111466 55764 111466 55771 111466 55769 111467 55771 111467 55772 111467 55330 111468 55780 111468 55766 111468 55766 111469 55780 111469 55767 111469 55766 111470 55767 111470 55772 111470 55772 111471 55767 111471 55768 111471 55772 111472 55768 111472 55769 111472 55769 111473 55768 111473 55782 111473 55769 111474 55782 111474 55770 111474 55770 111475 55782 111475 55783 111475 55771 111476 55763 111476 55772 111476 55772 111477 55763 111477 55762 111477 55772 111478 55762 111478 55766 111478 55766 111479 55762 111479 55761 111479 55766 111480 55761 111480 55330 111480 55773 111481 55332 111481 55774 111481 55775 111482 55080 111482 55776 111482 55776 111483 55080 111483 55777 111483 55776 111484 55777 111484 55788 111484 55788 111485 55777 111485 55778 111485 55778 111486 55777 111486 55781 111486 55778 111487 55781 111487 55790 111487 55790 111488 55781 111488 55779 111488 55779 111489 55781 111489 55773 111489 55779 111490 55773 111490 55791 111490 55791 111491 55773 111491 55774 111491 55791 111492 55774 111492 55808 111492 55330 111493 55332 111493 55780 111493 55780 111494 55332 111494 55773 111494 55780 111495 55773 111495 55767 111495 55767 111496 55773 111496 55781 111496 55767 111497 55781 111497 55768 111497 55768 111498 55781 111498 55777 111498 55768 111499 55777 111499 55782 111499 55782 111500 55777 111500 55080 111500 55782 111501 55080 111501 55783 111501 55776 111502 55786 111502 55775 111502 55775 111503 55786 111503 55785 111503 55786 111504 55784 111504 55802 111504 55785 111505 55786 111505 55207 111505 55207 111506 55786 111506 55802 111506 55207 111507 55802 111507 55208 111507 55807 111508 55806 111508 55787 111508 55787 111509 55806 111509 55801 111509 55787 111510 55801 111510 55789 111510 55776 111511 55788 111511 55786 111511 55786 111512 55788 111512 55789 111512 55786 111513 55789 111513 55784 111513 55784 111514 55789 111514 55801 111514 55788 111515 55778 111515 55789 111515 55789 111516 55778 111516 55790 111516 55789 111517 55790 111517 55787 111517 55787 111518 55790 111518 55779 111518 55787 111519 55779 111519 55807 111519 55807 111520 55779 111520 55791 111520 55807 111521 55791 111521 55808 111521 55309 111522 55793 111522 55792 111522 55792 111523 55793 111523 55816 111523 55792 111524 55816 111524 55794 111524 55794 111525 55816 111525 55814 111525 55794 111526 55814 111526 55797 111526 55797 111527 55814 111527 55813 111527 55797 111528 55813 111528 55795 111528 55795 111529 55813 111529 55812 111529 55795 111530 55812 111530 55796 111530 55796 111531 55812 111531 55810 111531 55796 111532 55810 111532 55774 111532 55774 111533 55810 111533 55808 111533 55774 111534 55331 111534 55796 111534 55796 111535 55331 111535 55831 111535 55796 111536 55831 111536 55795 111536 55795 111537 55831 111537 55797 111537 55797 111538 55831 111538 55847 111538 55797 111539 55847 111539 55794 111539 55794 111540 55847 111540 55792 111540 55792 111541 55847 111541 55846 111541 55792 111542 55846 111542 55309 111542 55803 111543 55879 111543 55802 111543 55879 111544 55798 111544 55802 111544 55802 111545 55798 111545 55799 111545 55802 111546 55799 111546 55208 111546 55208 111547 55799 111547 55881 111547 55208 111548 55881 111548 55800 111548 55801 111549 55872 111549 55784 111549 55784 111550 55872 111550 55873 111550 55784 111551 55873 111551 55802 111551 55802 111552 55873 111552 55876 111552 55802 111553 55876 111553 55803 111553 55815 111554 55884 111554 55804 111554 55804 111555 55884 111555 55883 111555 55804 111556 55883 111556 55811 111556 55882 111557 55872 111557 55805 111557 55805 111558 55872 111558 55801 111558 55805 111559 55801 111559 55809 111559 55809 111560 55801 111560 55806 111560 55809 111561 55806 111561 55807 111561 55807 111562 55808 111562 55809 111562 55809 111563 55808 111563 55810 111563 55809 111564 55810 111564 55812 111564 55812 111565 55804 111565 55809 111565 55809 111566 55804 111566 55811 111566 55809 111567 55811 111567 55805 111567 55805 111568 55811 111568 55882 111568 55812 111569 55813 111569 55804 111569 55804 111570 55813 111570 55814 111570 55804 111571 55814 111571 55815 111571 55815 111572 55814 111572 55816 111572 55815 111573 55816 111573 55793 111573 55831 111574 55331 111574 55817 111574 55817 111575 55331 111575 55315 111575 55817 111576 55315 111576 55832 111576 55832 111577 55315 111577 55317 111577 55832 111578 55317 111578 55834 111578 55834 111579 55317 111579 55818 111579 55834 111580 55818 111580 55819 111580 55819 111581 55818 111581 55820 111581 55819 111582 55820 111582 55835 111582 55835 111583 55820 111583 55821 111583 55835 111584 55821 111584 55837 111584 55837 111585 55821 111585 55822 111585 55837 111586 55822 111586 55823 111586 55823 111587 55822 111587 55321 111587 55823 111588 55321 111588 55838 111588 55838 111589 55321 111589 55824 111589 55838 111590 55824 111590 55840 111590 55840 111591 55824 111591 55323 111591 55840 111592 55323 111592 55826 111592 55826 111593 55323 111593 55825 111593 55826 111594 55825 111594 55827 111594 55827 111595 55825 111595 55324 111595 55827 111596 55324 111596 55828 111596 55828 111597 55324 111597 55326 111597 55828 111598 55326 111598 55843 111598 55843 111599 55326 111599 55829 111599 55843 111600 55829 111600 55844 111600 55844 111601 55829 111601 55327 111601 55844 111602 55327 111602 55845 111602 55845 111603 55327 111603 55830 111603 55845 111604 55830 111604 55920 111604 55920 111605 55830 111605 55918 111605 55847 111606 55831 111606 55848 111606 55848 111607 55831 111607 55817 111607 55848 111608 55817 111608 55850 111608 55850 111609 55817 111609 55832 111609 55850 111610 55832 111610 55833 111610 55833 111611 55832 111611 55834 111611 55833 111612 55834 111612 55852 111612 55852 111613 55834 111613 55819 111613 55852 111614 55819 111614 55855 111614 55855 111615 55819 111615 55835 111615 55855 111616 55835 111616 55836 111616 55836 111617 55835 111617 55837 111617 55836 111618 55837 111618 55856 111618 55856 111619 55837 111619 55823 111619 55856 111620 55823 111620 55839 111620 55839 111621 55823 111621 55838 111621 55839 111622 55838 111622 55858 111622 55858 111623 55838 111623 55840 111623 55858 111624 55840 111624 55841 111624 55841 111625 55840 111625 55826 111625 55841 111626 55826 111626 55861 111626 55861 111627 55826 111627 55827 111627 55861 111628 55827 111628 55842 111628 55842 111629 55827 111629 55828 111629 55842 111630 55828 111630 55864 111630 55864 111631 55828 111631 55843 111631 55864 111632 55843 111632 55865 111632 55865 111633 55843 111633 55844 111633 55865 111634 55844 111634 55866 111634 55866 111635 55844 111635 55845 111635 55866 111636 55845 111636 55924 111636 55924 111637 55845 111637 55920 111637 55846 111638 55847 111638 55849 111638 55849 111639 55847 111639 55848 111639 55849 111640 55848 111640 55306 111640 55306 111641 55848 111641 55850 111641 55306 111642 55850 111642 55851 111642 55851 111643 55850 111643 55833 111643 55851 111644 55833 111644 55307 111644 55307 111645 55833 111645 55852 111645 55307 111646 55852 111646 55853 111646 55853 111647 55852 111647 55855 111647 55853 111648 55855 111648 55854 111648 55854 111649 55855 111649 55836 111649 55854 111650 55836 111650 55857 111650 55857 111651 55836 111651 55856 111651 55857 111652 55856 111652 55311 111652 55311 111653 55856 111653 55839 111653 55311 111654 55839 111654 55313 111654 55313 111655 55839 111655 55858 111655 55313 111656 55858 111656 55859 111656 55859 111657 55858 111657 55841 111657 55859 111658 55841 111658 55860 111658 55860 111659 55841 111659 55861 111659 55860 111660 55861 111660 55862 111660 55862 111661 55861 111661 55842 111661 55862 111662 55842 111662 55863 111662 55863 111663 55842 111663 55864 111663 55863 111664 55864 111664 55302 111664 55302 111665 55864 111665 55865 111665 55302 111666 55865 111666 55303 111666 55303 111667 55865 111667 55866 111667 55303 111668 55866 111668 55921 111668 55921 111669 55866 111669 55924 111669 55902 111670 55867 111670 55901 111670 55868 111671 55209 111671 55800 111671 55868 111672 55800 111672 55885 111672 55210 111673 55869 111673 55892 111673 55892 111674 55869 111674 55209 111674 55870 111675 55211 111675 55904 111675 55904 111676 55211 111676 55210 111676 55904 111677 55210 111677 55893 111677 55903 111678 55871 111678 55870 111678 55872 111679 55874 111679 55873 111679 55873 111680 55874 111680 55875 111680 55873 111681 55875 111681 55876 111681 55876 111682 55875 111682 55877 111682 55876 111683 55877 111683 55803 111683 55803 111684 55877 111684 55878 111684 55803 111685 55878 111685 55879 111685 55879 111686 55878 111686 55887 111686 55879 111687 55887 111687 55798 111687 55798 111688 55887 111688 55880 111688 55798 111689 55880 111689 55799 111689 55799 111690 55880 111690 55885 111690 55799 111691 55885 111691 55881 111691 55881 111692 55885 111692 55800 111692 55872 111693 55882 111693 55874 111693 55874 111694 55882 111694 55891 111694 55891 111695 55882 111695 55811 111695 55891 111696 55811 111696 55883 111696 55883 111697 55884 111697 55891 111697 55891 111698 55884 111698 55925 111698 55891 111699 55925 111699 55928 111699 55209 111700 55868 111700 55892 111700 55892 111701 55868 111701 55885 111701 55892 111702 55885 111702 55895 111702 55895 111703 55885 111703 55880 111703 55895 111704 55880 111704 55886 111704 55886 111705 55880 111705 55887 111705 55886 111706 55887 111706 55896 111706 55896 111707 55887 111707 55878 111707 55896 111708 55878 111708 55888 111708 55888 111709 55878 111709 55877 111709 55888 111710 55877 111710 55897 111710 55897 111711 55877 111711 55875 111711 55897 111712 55875 111712 55899 111712 55899 111713 55875 111713 55874 111713 55899 111714 55874 111714 55889 111714 55889 111715 55874 111715 55891 111715 55889 111716 55891 111716 55890 111716 55890 111717 55891 111717 55928 111717 55890 111718 55928 111718 55930 111718 55210 111719 55892 111719 55893 111719 55893 111720 55892 111720 55895 111720 55893 111721 55895 111721 55894 111721 55894 111722 55895 111722 55886 111722 55894 111723 55886 111723 55907 111723 55907 111724 55886 111724 55896 111724 55907 111725 55896 111725 55908 111725 55908 111726 55896 111726 55888 111726 55908 111727 55888 111727 55910 111727 55910 111728 55888 111728 55897 111728 55910 111729 55897 111729 55898 111729 55898 111730 55897 111730 55899 111730 55898 111731 55899 111731 55900 111731 55900 111732 55899 111732 55889 111732 55900 111733 55889 111733 55913 111733 55913 111734 55889 111734 55890 111734 55913 111735 55890 111735 55901 111735 55901 111736 55890 111736 55930 111736 55901 111737 55930 111737 55902 111737 55870 111738 55904 111738 55903 111738 55903 111739 55904 111739 55893 111739 55903 111740 55893 111740 55905 111740 55905 111741 55893 111741 55894 111741 55905 111742 55894 111742 55906 111742 55906 111743 55894 111743 55907 111743 55906 111744 55907 111744 55909 111744 55909 111745 55907 111745 55908 111745 55909 111746 55908 111746 54863 111746 54863 111747 55908 111747 55910 111747 54863 111748 55910 111748 55911 111748 55911 111749 55910 111749 55898 111749 55911 111750 55898 111750 55912 111750 55912 111751 55898 111751 55900 111751 55912 111752 55900 111752 55914 111752 55914 111753 55900 111753 55913 111753 55914 111754 55913 111754 55915 111754 55915 111755 55913 111755 55901 111755 55915 111756 55901 111756 55916 111756 55916 111757 55901 111757 55867 111757 55916 111758 55867 111758 55926 111758 55692 111759 55917 111759 55918 111759 55918 111760 55917 111760 55920 111760 55917 111761 55919 111761 55920 111761 55920 111762 55919 111762 55933 111762 55920 111763 55933 111763 55924 111763 55300 111764 55921 111764 55922 111764 55922 111765 55921 111765 55924 111765 55922 111766 55924 111766 55923 111766 55923 111767 55924 111767 55933 111767 55937 111768 55938 111768 55927 111768 55930 111769 55928 111769 55927 111769 55925 111770 55884 111770 55310 111770 55902 111771 55929 111771 55867 111771 55867 111772 55929 111772 54862 111772 55867 111773 54862 111773 55926 111773 55936 111774 55937 111774 55310 111774 55310 111775 55937 111775 55927 111775 55310 111776 55927 111776 55925 111776 55925 111777 55927 111777 55928 111777 55938 111778 55940 111778 55927 111778 55927 111779 55940 111779 55929 111779 55927 111780 55929 111780 55930 111780 55930 111781 55929 111781 55902 111781 55944 111782 54862 111782 55931 111782 55931 111783 54862 111783 55929 111783 55931 111784 55929 111784 55942 111784 55942 111785 55929 111785 55940 111785 55295 111786 55300 111786 55932 111786 55932 111787 55300 111787 55922 111787 55932 111788 55922 111788 55957 111788 55957 111789 55922 111789 55923 111789 55957 111790 55923 111790 55954 111790 55954 111791 55923 111791 55933 111791 55954 111792 55933 111792 55934 111792 55934 111793 55933 111793 55919 111793 55934 111794 55919 111794 55953 111794 55953 111795 55919 111795 55917 111795 55953 111796 55917 111796 55935 111796 55935 111797 55917 111797 55692 111797 55959 111798 55939 111798 55936 111798 55936 111799 55939 111799 55937 111799 55937 111800 55939 111800 55938 111800 55938 111801 55939 111801 55962 111801 55938 111802 55962 111802 55940 111802 55940 111803 55962 111803 55941 111803 55940 111804 55941 111804 55942 111804 55942 111805 55941 111805 55943 111805 55942 111806 55943 111806 55931 111806 55943 111807 55961 111807 55931 111807 55931 111808 55961 111808 54816 111808 55931 111809 54816 111809 55944 111809 55973 111810 56007 111810 55952 111810 55952 111811 56007 111811 55955 111811 55955 111812 56007 111812 55945 111812 55955 111813 55945 111813 55956 111813 55956 111814 55945 111814 56009 111814 55956 111815 56009 111815 55297 111815 55297 111816 56009 111816 55946 111816 55167 111817 55967 111817 55681 111817 55681 111818 55967 111818 55947 111818 55681 111819 55947 111819 55948 111819 55947 111820 55968 111820 55948 111820 55948 111821 55968 111821 55949 111821 55948 111822 55949 111822 55970 111822 55955 111823 55934 111823 55953 111823 55970 111824 55971 111824 55948 111824 55948 111825 55971 111825 55950 111825 55948 111826 55950 111826 55951 111826 55951 111827 55950 111827 55973 111827 55951 111828 55973 111828 55679 111828 55679 111829 55973 111829 55952 111829 55679 111830 55952 111830 55677 111830 55677 111831 55952 111831 55955 111831 55677 111832 55955 111832 55674 111832 55674 111833 55955 111833 55953 111833 55674 111834 55953 111834 55935 111834 55934 111835 55955 111835 55954 111835 55954 111836 55955 111836 55956 111836 55954 111837 55956 111837 55957 111837 55957 111838 55956 111838 55932 111838 55932 111839 55956 111839 55297 111839 55932 111840 55297 111840 55295 111840 56010 111841 56006 111841 55958 111841 55941 111842 55962 111842 55958 111842 55939 111843 55959 111843 55296 111843 55943 111844 55960 111844 55961 111844 55961 111845 55960 111845 54860 111845 55961 111846 54860 111846 54816 111846 55946 111847 56010 111847 55296 111847 55296 111848 56010 111848 55958 111848 55296 111849 55958 111849 55939 111849 55939 111850 55958 111850 55962 111850 56006 111851 55963 111851 55958 111851 55958 111852 55963 111852 55960 111852 55958 111853 55960 111853 55941 111853 55941 111854 55960 111854 55943 111854 55984 111855 54860 111855 55964 111855 55964 111856 54860 111856 55960 111856 55964 111857 55960 111857 55993 111857 55993 111858 55960 111858 55963 111858 56006 111859 56010 111859 56008 111859 55986 111860 55965 111860 55966 111860 55162 111861 54859 111861 55994 111861 55997 111862 55166 111862 55164 111862 55996 111863 55994 111863 55975 111863 55166 111864 55997 111864 55167 111864 55167 111865 55997 111865 55998 111865 55167 111866 55998 111866 55967 111866 55967 111867 55998 111867 55999 111867 55967 111868 55999 111868 55947 111868 55947 111869 55999 111869 56001 111869 55947 111870 56001 111870 55968 111870 55968 111871 56001 111871 56002 111871 55968 111872 56002 111872 55949 111872 55949 111873 56002 111873 55969 111873 55949 111874 55969 111874 55970 111874 55970 111875 55969 111875 55974 111875 55970 111876 55974 111876 55971 111876 55972 111877 56007 111877 55973 111877 55972 111878 55973 111878 55974 111878 55974 111879 55973 111879 55950 111879 55974 111880 55950 111880 55971 111880 55996 111881 55975 111881 55965 111881 55965 111882 55975 111882 54857 111882 55965 111883 54857 111883 55966 111883 55966 111884 54857 111884 55976 111884 55966 111885 55976 111885 55989 111885 55989 111886 55976 111886 55978 111886 55989 111887 55978 111887 55977 111887 55977 111888 55978 111888 54856 111888 55977 111889 54856 111889 55979 111889 55979 111890 54856 111890 54855 111890 55979 111891 54855 111891 55980 111891 55980 111892 54855 111892 55981 111892 55980 111893 55981 111893 55992 111893 55992 111894 55981 111894 54854 111894 55992 111895 54854 111895 55982 111895 55982 111896 54854 111896 55983 111896 55982 111897 55983 111897 55985 111897 55983 111898 55984 111898 55985 111898 55985 111899 55984 111899 55964 111899 55985 111900 55964 111900 55993 111900 55986 111901 55966 111901 55987 111901 55987 111902 55966 111902 55989 111902 55987 111903 55989 111903 55988 111903 55988 111904 55989 111904 55977 111904 55988 111905 55977 111905 56000 111905 56000 111906 55977 111906 55979 111906 56000 111907 55979 111907 55990 111907 55990 111908 55979 111908 55980 111908 55990 111909 55980 111909 55991 111909 55991 111910 55980 111910 55992 111910 55991 111911 55992 111911 56003 111911 56003 111912 55992 111912 55982 111912 56003 111913 55982 111913 56004 111913 56004 111914 55982 111914 55985 111914 56004 111915 55985 111915 56005 111915 56005 111916 55985 111916 55993 111916 56005 111917 55993 111917 55963 111917 55162 111918 55994 111918 55995 111918 55995 111919 55994 111919 55996 111919 55995 111920 55996 111920 55163 111920 55163 111921 55996 111921 55965 111921 55163 111922 55965 111922 55164 111922 55164 111923 55965 111923 55986 111923 55164 111924 55986 111924 55997 111924 55997 111925 55986 111925 55987 111925 55997 111926 55987 111926 55998 111926 55998 111927 55987 111927 55988 111927 55998 111928 55988 111928 55999 111928 55999 111929 55988 111929 56000 111929 55999 111930 56000 111930 56001 111930 56001 111931 56000 111931 55990 111931 56001 111932 55990 111932 56002 111932 56002 111933 55990 111933 55991 111933 56002 111934 55991 111934 55969 111934 55969 111935 55991 111935 56003 111935 55969 111936 56003 111936 55974 111936 55974 111937 56003 111937 56004 111937 55974 111938 56004 111938 55972 111938 55972 111939 56004 111939 56005 111939 55972 111940 56005 111940 56008 111940 56008 111941 56005 111941 55963 111941 56008 111942 55963 111942 56006 111942 56007 111943 55972 111943 55945 111943 55945 111944 55972 111944 56008 111944 55945 111945 56008 111945 56009 111945 56009 111946 56008 111946 56010 111946 56009 111947 56010 111947 55946 111947 55258 111948 56011 111948 56012 111948 56012 111949 56011 111949 56013 111949 56012 111950 56013 111950 56014 111950 56014 111951 56013 111951 56034 111951 56014 111952 56034 111952 56019 111952 56019 111953 56034 111953 56015 111953 56019 111954 56015 111954 56016 111954 56016 111955 56015 111955 56033 111955 56016 111956 56033 111956 56017 111956 56017 111957 56033 111957 56031 111957 56017 111958 56031 111958 55650 111958 55650 111959 56031 111959 55656 111959 55650 111960 56035 111960 56017 111960 56017 111961 56035 111961 56018 111961 56017 111962 56018 111962 56016 111962 56016 111963 56018 111963 56019 111963 56019 111964 56018 111964 56020 111964 56019 111965 56020 111965 56014 111965 56014 111966 56020 111966 56012 111966 56012 111967 56020 111967 56069 111967 56012 111968 56069 111968 55258 111968 56021 111969 56087 111969 56022 111969 56087 111970 56023 111970 56022 111970 56022 111971 56023 111971 56024 111971 56022 111972 56024 111972 55187 111972 55187 111973 56024 111973 56088 111973 55187 111974 56088 111974 56082 111974 56029 111975 56025 111975 56026 111975 56026 111976 56025 111976 56084 111976 56026 111977 56084 111977 56022 111977 56022 111978 56084 111978 56027 111978 56022 111979 56027 111979 56021 111979 55262 111980 55261 111980 56028 111980 56028 111981 55261 111981 56092 111981 56028 111982 56092 111982 56091 111982 56089 111983 56025 111983 56032 111983 56032 111984 56025 111984 56029 111984 56032 111985 56029 111985 56030 111985 56030 111986 56029 111986 55667 111986 56030 111987 55667 111987 55666 111987 55666 111988 55656 111988 56030 111988 56030 111989 55656 111989 56031 111989 56030 111990 56031 111990 56033 111990 56033 111991 56028 111991 56030 111991 56030 111992 56028 111992 56091 111992 56030 111993 56091 111993 56032 111993 56032 111994 56091 111994 56089 111994 56033 111995 56015 111995 56028 111995 56028 111996 56015 111996 56034 111996 56028 111997 56034 111997 55262 111997 55262 111998 56034 111998 56013 111998 55262 111999 56013 111999 56011 111999 56018 112000 56035 112000 56051 112000 56051 112001 56035 112001 56036 112001 56051 112002 56036 112002 56053 112002 56053 112003 56036 112003 56038 112003 56053 112004 56038 112004 56037 112004 56037 112005 56038 112005 55278 112005 56037 112006 55278 112006 56055 112006 56055 112007 55278 112007 55280 112007 56055 112008 55280 112008 56056 112008 56056 112009 55280 112009 55281 112009 56056 112010 55281 112010 56057 112010 56057 112011 55281 112011 55282 112011 56057 112012 55282 112012 56060 112012 56060 112013 55282 112013 56039 112013 56060 112014 56039 112014 56040 112014 56040 112015 56039 112015 56042 112015 56040 112016 56042 112016 56041 112016 56041 112017 56042 112017 56043 112017 56041 112018 56043 112018 56062 112018 56062 112019 56043 112019 56044 112019 56062 112020 56044 112020 56064 112020 56064 112021 56044 112021 56045 112021 56064 112022 56045 112022 56046 112022 56046 112023 56045 112023 56047 112023 56046 112024 56047 112024 56066 112024 56066 112025 56047 112025 55287 112025 56066 112026 55287 112026 56067 112026 56067 112027 55287 112027 56048 112027 56067 112028 56048 112028 56049 112028 56049 112029 56048 112029 55290 112029 56049 112030 55290 112030 56050 112030 56050 112031 55290 112031 55291 112031 56020 112032 56018 112032 56070 112032 56070 112033 56018 112033 56051 112033 56070 112034 56051 112034 56052 112034 56052 112035 56051 112035 56053 112035 56052 112036 56053 112036 56073 112036 56073 112037 56053 112037 56037 112037 56073 112038 56037 112038 56074 112038 56074 112039 56037 112039 56055 112039 56074 112040 56055 112040 56054 112040 56054 112041 56055 112041 56056 112041 56054 112042 56056 112042 56075 112042 56075 112043 56056 112043 56057 112043 56075 112044 56057 112044 56058 112044 56058 112045 56057 112045 56060 112045 56058 112046 56060 112046 56059 112046 56059 112047 56060 112047 56040 112047 56059 112048 56040 112048 56061 112048 56061 112049 56040 112049 56041 112049 56061 112050 56041 112050 56077 112050 56077 112051 56041 112051 56062 112051 56077 112052 56062 112052 56063 112052 56063 112053 56062 112053 56064 112053 56063 112054 56064 112054 56079 112054 56079 112055 56064 112055 56046 112055 56079 112056 56046 112056 56080 112056 56080 112057 56046 112057 56066 112057 56080 112058 56066 112058 56065 112058 56065 112059 56066 112059 56067 112059 56065 112060 56067 112060 56068 112060 56068 112061 56067 112061 56049 112061 56068 112062 56049 112062 56081 112062 56081 112063 56049 112063 56050 112063 56069 112064 56020 112064 55260 112064 55260 112065 56020 112065 56070 112065 55260 112066 56070 112066 56071 112066 56071 112067 56070 112067 56052 112067 56071 112068 56052 112068 56072 112068 56072 112069 56052 112069 56073 112069 56072 112070 56073 112070 55253 112070 55253 112071 56073 112071 56074 112071 55253 112072 56074 112072 55252 112072 55252 112073 56074 112073 56054 112073 55252 112074 56054 112074 55249 112074 55249 112075 56054 112075 56075 112075 55249 112076 56075 112076 55251 112076 55251 112077 56075 112077 56058 112077 55251 112078 56058 112078 56076 112078 56076 112079 56058 112079 56059 112079 56076 112080 56059 112080 55254 112080 55254 112081 56059 112081 56061 112081 55254 112082 56061 112082 55255 112082 55255 112083 56061 112083 56077 112083 55255 112084 56077 112084 55256 112084 55256 112085 56077 112085 56063 112085 55256 112086 56063 112086 56078 112086 56078 112087 56063 112087 56079 112087 56078 112088 56079 112088 55264 112088 55264 112089 56079 112089 56080 112089 55264 112090 56080 112090 55265 112090 55265 112091 56080 112091 56065 112091 55265 112092 56065 112092 55267 112092 55267 112093 56065 112093 56068 112093 55267 112094 56068 112094 55269 112094 55269 112095 56068 112095 56081 112095 56083 112096 55188 112096 56093 112096 55188 112097 55185 112097 56093 112097 56093 112098 55185 112098 56082 112098 56093 112099 56082 112099 56094 112099 56104 112100 56103 112100 56083 112100 54832 112101 55191 112101 55190 112101 56025 112102 56090 112102 56084 112102 56084 112103 56090 112103 56085 112103 56084 112104 56085 112104 56027 112104 56027 112105 56085 112105 56086 112105 56027 112106 56086 112106 56021 112106 56021 112107 56086 112107 56097 112107 56021 112108 56097 112108 56087 112108 56087 112109 56097 112109 56096 112109 56087 112110 56096 112110 56023 112110 56023 112111 56096 112111 56095 112111 56023 112112 56095 112112 56024 112112 56024 112113 56095 112113 56094 112113 56024 112114 56094 112114 56088 112114 56088 112115 56094 112115 56082 112115 56025 112116 56089 112116 56090 112116 56090 112117 56089 112117 56100 112117 56100 112118 56089 112118 56091 112118 56091 112119 56092 112119 56100 112119 56100 112120 56092 112120 55261 112120 56100 112121 55261 112121 56102 112121 56083 112122 56093 112122 56104 112122 56104 112123 56093 112123 56094 112123 56104 112124 56094 112124 56106 112124 56106 112125 56094 112125 56095 112125 56106 112126 56095 112126 56109 112126 56109 112127 56095 112127 56096 112127 56109 112128 56096 112128 56110 112128 56110 112129 56096 112129 56097 112129 56110 112130 56097 112130 56098 112130 56098 112131 56097 112131 56086 112131 56098 112132 56086 112132 56112 112132 56112 112133 56086 112133 56085 112133 56112 112134 56085 112134 56099 112134 56099 112135 56085 112135 56090 112135 56099 112136 56090 112136 56113 112136 56113 112137 56090 112137 56100 112137 56113 112138 56100 112138 56101 112138 56101 112139 56100 112139 56102 112139 56101 112140 56102 112140 56117 112140 55190 112141 56103 112141 54832 112141 54832 112142 56103 112142 56104 112142 54832 112143 56104 112143 56105 112143 56105 112144 56104 112144 56106 112144 56105 112145 56106 112145 56107 112145 56107 112146 56106 112146 56109 112146 56107 112147 56109 112147 56108 112147 56108 112148 56109 112148 56110 112148 56108 112149 56110 112149 54831 112149 54831 112150 56110 112150 56098 112150 54831 112151 56098 112151 56111 112151 56111 112152 56098 112152 56112 112152 56111 112153 56112 112153 54830 112153 54830 112154 56112 112154 56099 112154 54830 112155 56099 112155 56114 112155 56114 112156 56099 112156 56113 112156 56114 112157 56113 112157 54829 112157 54829 112158 56113 112158 56101 112158 54829 112159 56101 112159 54834 112159 54834 112160 56101 112160 56117 112160 54834 112161 56117 112161 54835 112161 55575 112162 56115 112162 55291 112162 55291 112163 56115 112163 56050 112163 56115 112164 56131 112164 56050 112164 56050 112165 56131 112165 56128 112165 56050 112166 56128 112166 56081 112166 55263 112167 55269 112167 56125 112167 56125 112168 55269 112168 56081 112168 56125 112169 56081 112169 56127 112169 56127 112170 56081 112170 56128 112170 56118 112171 55274 112171 56116 112171 55261 112172 55274 112172 56102 112172 56102 112173 55274 112173 56118 112173 56102 112174 56118 112174 56117 112174 56117 112175 56118 112175 56121 112175 56117 112176 56121 112176 54835 112176 54835 112177 56121 112177 56123 112177 56116 112178 56119 112178 56118 112178 56118 112179 56119 112179 56120 112179 56118 112180 56120 112180 56121 112180 56121 112181 56120 112181 56122 112181 56121 112182 56122 112182 56123 112182 56123 112183 56122 112183 56124 112183 56154 112184 55263 112184 56152 112184 56152 112185 55263 112185 56125 112185 56152 112186 56125 112186 56126 112186 56126 112187 56125 112187 56127 112187 56126 112188 56127 112188 56129 112188 56129 112189 56127 112189 56128 112189 56129 112190 56128 112190 56130 112190 56130 112191 56128 112191 56131 112191 56130 112192 56131 112192 56140 112192 56140 112193 56131 112193 56115 112193 56140 112194 56115 112194 56150 112194 56150 112195 56115 112195 55575 112195 56116 112196 56132 112196 56157 112196 56116 112197 56157 112197 56119 112197 56119 112198 56157 112198 56133 112198 56119 112199 56133 112199 56120 112199 56120 112200 56133 112200 56159 112200 56120 112201 56159 112201 56122 112201 56122 112202 56159 112202 56160 112202 56122 112203 56160 112203 56124 112203 56144 112204 56165 112204 56147 112204 56147 112205 56165 112205 56148 112205 56148 112206 56165 112206 56134 112206 56148 112207 56134 112207 56151 112207 56151 112208 56134 112208 56135 112208 56151 112209 56135 112209 56153 112209 56153 112210 56135 112210 56161 112210 56136 112211 56138 112211 56137 112211 56137 112212 56138 112212 56168 112212 56137 112213 56168 112213 55564 112213 56168 112214 56169 112214 55564 112214 55564 112215 56169 112215 56139 112215 55564 112216 56139 112216 56141 112216 56148 112217 56130 112217 56140 112217 56141 112218 56142 112218 55564 112218 55564 112219 56142 112219 56143 112219 55564 112220 56143 112220 55563 112220 55563 112221 56143 112221 56144 112221 55563 112222 56144 112222 56145 112222 56145 112223 56144 112223 56147 112223 56145 112224 56147 112224 56146 112224 56146 112225 56147 112225 56148 112225 56146 112226 56148 112226 56149 112226 56149 112227 56148 112227 56140 112227 56149 112228 56140 112228 56150 112228 56130 112229 56148 112229 56129 112229 56129 112230 56148 112230 56151 112230 56129 112231 56151 112231 56126 112231 56126 112232 56151 112232 56152 112232 56152 112233 56151 112233 56153 112233 56152 112234 56153 112234 56154 112234 56132 112235 56155 112235 56157 112235 56157 112236 56155 112236 56156 112236 56157 112237 56156 112237 56133 112237 56133 112238 56156 112238 56158 112238 56133 112239 56158 112239 56159 112239 56159 112240 56158 112240 56163 112240 56159 112241 56163 112241 56160 112241 56160 112242 56163 112242 54827 112242 56155 112243 56161 112243 56156 112243 56156 112244 56161 112244 56162 112244 56156 112245 56162 112245 56158 112245 56158 112246 56162 112246 56202 112246 56158 112247 56202 112247 56163 112247 56163 112248 56202 112248 56164 112248 56163 112249 56164 112249 54827 112249 54827 112250 56164 112250 54821 112250 56134 112251 56165 112251 56198 112251 56166 112252 56172 112252 56174 112252 55231 112253 54826 112253 54825 112253 56189 112254 56167 112254 55230 112254 56188 112255 54825 112255 54824 112255 56167 112256 56189 112256 56136 112256 56136 112257 56189 112257 56191 112257 56136 112258 56191 112258 56138 112258 56138 112259 56191 112259 56193 112259 56138 112260 56193 112260 56168 112260 56168 112261 56193 112261 56196 112261 56168 112262 56196 112262 56169 112262 56169 112263 56196 112263 56197 112263 56169 112264 56197 112264 56139 112264 56139 112265 56197 112265 56170 112265 56139 112266 56170 112266 56141 112266 56141 112267 56170 112267 56171 112267 56141 112268 56171 112268 56142 112268 56188 112269 54824 112269 56172 112269 56172 112270 54824 112270 56173 112270 56172 112271 56173 112271 56174 112271 56174 112272 56173 112272 56175 112272 56174 112273 56175 112273 56176 112273 56176 112274 56175 112274 54823 112274 56176 112275 54823 112275 56182 112275 56182 112276 54823 112276 56177 112276 56182 112277 56177 112277 56183 112277 56183 112278 56177 112278 56178 112278 56183 112279 56178 112279 56185 112279 56185 112280 56178 112280 56179 112280 56185 112281 56179 112281 56180 112281 56180 112282 56179 112282 56201 112282 56180 112283 56201 112283 56181 112283 56166 112284 56174 112284 56190 112284 56190 112285 56174 112285 56176 112285 56190 112286 56176 112286 56192 112286 56192 112287 56176 112287 56182 112287 56192 112288 56182 112288 56194 112288 56194 112289 56182 112289 56183 112289 56194 112290 56183 112290 56195 112290 56195 112291 56183 112291 56185 112291 56195 112292 56185 112292 56184 112292 56184 112293 56185 112293 56180 112293 56184 112294 56180 112294 56186 112294 56186 112295 56180 112295 56181 112295 56186 112296 56181 112296 56200 112296 55231 112297 54825 112297 56187 112297 56187 112298 54825 112298 56188 112298 56187 112299 56188 112299 55232 112299 55232 112300 56188 112300 56172 112300 55232 112301 56172 112301 55230 112301 55230 112302 56172 112302 56166 112302 55230 112303 56166 112303 56189 112303 56189 112304 56166 112304 56190 112304 56189 112305 56190 112305 56191 112305 56191 112306 56190 112306 56192 112306 56191 112307 56192 112307 56193 112307 56193 112308 56192 112308 56194 112308 56193 112309 56194 112309 56196 112309 56196 112310 56194 112310 56195 112310 56196 112311 56195 112311 56197 112311 56197 112312 56195 112312 56184 112312 56197 112313 56184 112313 56170 112313 56170 112314 56184 112314 56186 112314 56170 112315 56186 112315 56171 112315 56171 112316 56186 112316 56200 112316 56171 112317 56200 112317 56198 112317 56198 112318 56165 112318 56144 112318 56198 112319 56144 112319 56171 112319 56171 112320 56144 112320 56143 112320 56171 112321 56143 112321 56142 112321 56135 112322 56134 112322 56203 112322 56203 112323 56134 112323 56198 112323 56203 112324 56198 112324 56199 112324 56199 112325 56198 112325 56200 112325 56199 112326 56200 112326 56204 112326 56204 112327 56200 112327 56181 112327 56204 112328 56181 112328 56205 112328 56205 112329 56181 112329 56201 112329 56161 112330 56135 112330 56162 112330 56162 112331 56135 112331 56203 112331 56162 112332 56203 112332 56202 112332 56202 112333 56203 112333 56199 112333 56202 112334 56199 112334 56164 112334 56164 112335 56199 112335 56204 112335 56164 112336 56204 112336 54821 112336 54821 112337 56204 112337 56205 112337 54933 112338 55301 112338 54931 112338 54931 112339 55301 112339 55308 112339 54931 112340 55308 112340 54929 112340 54929 112341 55308 112341 56206 112341 54929 112342 56206 112342 56207 112342 56207 112343 56206 112343 55305 112343 56207 112344 55305 112344 54939 112344 54939 112345 55305 112345 55298 112345 54939 112346 55298 112346 54937 112346 54937 112347 55298 112347 55304 112347 54937 112348 55304 112348 54940 112348 54940 112349 55304 112349 55312 112349 54940 112350 55312 112350 54924 112350 54924 112351 55312 112351 56208 112351 54924 112352 56208 112352 56209 112352 56209 112353 56208 112353 55294 112353 56209 112354 55294 112354 56210 112354 56210 112355 55294 112355 56211 112355 56210 112356 56211 112356 56212 112356 56212 112357 56211 112357 55299 112357 56212 112358 55299 112358 54934 112358 54934 112359 55299 112359 56213 112359 54934 112360 56213 112360 54933 112360 54933 112361 56213 112361 55301 112361 54980 112362 56220 112362 54981 112362 54981 112363 56220 112363 55248 112363 54981 112364 55248 112364 54970 112364 54970 112365 55248 112365 55266 112365 54970 112366 55266 112366 54969 112366 54969 112367 55266 112367 55268 112367 54969 112368 55268 112368 54968 112368 54968 112369 55268 112369 55270 112369 54968 112370 55270 112370 54965 112370 54965 112371 55270 112371 55271 112371 54965 112372 55271 112372 56214 112372 56214 112373 55271 112373 55272 112373 56214 112374 55272 112374 56215 112374 56215 112375 55272 112375 55273 112375 56215 112376 55273 112376 54973 112376 54973 112377 55273 112377 56216 112377 54973 112378 56216 112378 56217 112378 56217 112379 56216 112379 55259 112379 56217 112380 55259 112380 56218 112380 56218 112381 55259 112381 55257 112381 56218 112382 55257 112382 56219 112382 56219 112383 55257 112383 55250 112383 56219 112384 55250 112384 54980 112384 54980 112385 55250 112385 56220 112385 56229 112386 56222 112386 56221 112386 56221 112387 56222 112387 56223 112387 56235 112388 56236 112388 55017 112388 56235 112389 55017 112389 56224 112389 56224 112390 55017 112390 56226 112390 56224 112391 56226 112391 56225 112391 56225 112392 56226 112392 56228 112392 56225 112393 56228 112393 56227 112393 56227 112394 56228 112394 56222 112394 56227 112395 56222 112395 56229 112395 56221 112396 56223 112396 56230 112396 56221 112397 56230 112397 56231 112397 56231 112398 56230 112398 55020 112398 56231 112399 55020 112399 56232 112399 56232 112400 55020 112400 56233 112400 56232 112401 56233 112401 56234 112401 56234 112402 56233 112402 56237 112402 56234 112403 56237 112403 55028 112403 55032 112404 55016 112404 56235 112404 56235 112405 55016 112405 56236 112405 55022 112406 56241 112406 56237 112406 56237 112407 56241 112407 55028 112407 56238 112408 55010 112408 55011 112408 56238 112409 55011 112409 56239 112409 56239 112410 55011 112410 55013 112410 56239 112411 55013 112411 55033 112411 55033 112412 55013 112412 55015 112412 55033 112413 55015 112413 56240 112413 56240 112414 55015 112414 55016 112414 56240 112415 55016 112415 55032 112415 56241 112416 55022 112416 55023 112416 56241 112417 55023 112417 55030 112417 55030 112418 55023 112418 55024 112418 55030 112419 55024 112419 55029 112419 55029 112420 55024 112420 55026 112420 55029 112421 55026 112421 56242 112421 56242 112422 55026 112422 56243 112422 56242 112423 56243 112423 55031 112423 55031 112424 56243 112424 56238 112424 56238 112425 56243 112425 55010 112425 55008 112426 56250 112426 56244 112426 56244 112427 56250 112427 54992 112427 55002 112428 54988 112428 56245 112428 55002 112429 56245 112429 55003 112429 55003 112430 56245 112430 56246 112430 55003 112431 56246 112431 56247 112431 56247 112432 56246 112432 56248 112432 56247 112433 56248 112433 56249 112433 56249 112434 56248 112434 56250 112434 56249 112435 56250 112435 55008 112435 56244 112436 54992 112436 54994 112436 56244 112437 54994 112437 56252 112437 56252 112438 54994 112438 56251 112438 56252 112439 56251 112439 56253 112439 56253 112440 56251 112440 54996 112440 56253 112441 54996 112441 55004 112441 55004 112442 54996 112442 56254 112442 55004 112443 56254 112443 55009 112443 55007 112444 54987 112444 55002 112444 55002 112445 54987 112445 54988 112445 56258 112446 55000 112446 56254 112446 56254 112447 55000 112447 55009 112447 55001 112448 54984 112448 56255 112448 55001 112449 56255 112449 56256 112449 56256 112450 56255 112450 54985 112450 56256 112451 54985 112451 55005 112451 55005 112452 54985 112452 56257 112452 55005 112453 56257 112453 55006 112453 55006 112454 56257 112454 54987 112454 55006 112455 54987 112455 55007 112455 55000 112456 56258 112456 54997 112456 55000 112457 54997 112457 56259 112457 56259 112458 54997 112458 56261 112458 56259 112459 56261 112459 56260 112459 56260 112460 56261 112460 54999 112460 56260 112461 54999 112461 56262 112461 56262 112462 54999 112462 56264 112462 56262 112463 56264 112463 56263 112463 56263 112464 56264 112464 55001 112464 55001 112465 56264 112465 54984 112465 56265 112466 56266 112466 56270 112466 56270 112467 56266 112467 55048 112467 55062 112468 55040 112468 56267 112468 55062 112469 56267 112469 55064 112469 55064 112470 56267 112470 55045 112470 55064 112471 55045 112471 56268 112471 56268 112472 55045 112472 55046 112472 56268 112473 55046 112473 56269 112473 56269 112474 55046 112474 56266 112474 56269 112475 56266 112475 56265 112475 56270 112476 55048 112476 56271 112476 56270 112477 56271 112477 55070 112477 55070 112478 56271 112478 56273 112478 55070 112479 56273 112479 56272 112479 56272 112480 56273 112480 55052 112480 56272 112481 55052 112481 55068 112481 55068 112482 55052 112482 56274 112482 55068 112483 56274 112483 55069 112483 55063 112484 55039 112484 55062 112484 55062 112485 55039 112485 55040 112485 55055 112486 56276 112486 56274 112486 56274 112487 56276 112487 55069 112487 56282 112488 55059 112488 56275 112488 56282 112489 56275 112489 55065 112489 55065 112490 56275 112490 55036 112490 55065 112491 55036 112491 55066 112491 55066 112492 55036 112492 55037 112492 55066 112493 55037 112493 55067 112493 55067 112494 55037 112494 55039 112494 55067 112495 55039 112495 55063 112495 56276 112496 55055 112496 56278 112496 56276 112497 56278 112497 56277 112497 56277 112498 56278 112498 56279 112498 56277 112499 56279 112499 56280 112499 56280 112500 56279 112500 55057 112500 56280 112501 55057 112501 55060 112501 55060 112502 55057 112502 56281 112502 55060 112503 56281 112503 55061 112503 55061 112504 56281 112504 56282 112504 56282 112505 56281 112505 55059 112505 56283 112506 56284 112506 56285 112506 56285 112507 56284 112507 56286 112507 56285 112508 56286 112508 56364 112508 56364 112509 56286 112509 56287 112509 56364 112510 56287 112510 56361 112510 56361 112511 56287 112511 56288 112511 56361 112512 56288 112512 56340 112512 56340 112513 56288 112513 56331 112513 56340 112514 56331 112514 56289 112514 56289 112515 56331 112515 56330 112515 56289 112516 56330 112516 56338 112516 56338 112517 56330 112517 56290 112517 56338 112518 56290 112518 56337 112518 56337 112519 56290 112519 56332 112519 56337 112520 56332 112520 56291 112520 56291 112521 56332 112521 56292 112521 56291 112522 56292 112522 56293 112522 56293 112523 56292 112523 56294 112523 56293 112524 56294 112524 56295 112524 56295 112525 56294 112525 56296 112525 56295 112526 56296 112526 56349 112526 56349 112527 56296 112527 56297 112527 56349 112528 56297 112528 56348 112528 56348 112529 56297 112529 56298 112529 56348 112530 56298 112530 56299 112530 56299 112531 56298 112531 56300 112531 56299 112532 56300 112532 56301 112532 56301 112533 56300 112533 56302 112533 56301 112534 56302 112534 56357 112534 56357 112535 56302 112535 56303 112535 56357 112536 56303 112536 56304 112536 56304 112537 56303 112537 56306 112537 56304 112538 56306 112538 56305 112538 56305 112539 56306 112539 56322 112539 56305 112540 56322 112540 56354 112540 56354 112541 56322 112541 56307 112541 56354 112542 56307 112542 56353 112542 56353 112543 56307 112543 56324 112543 56353 112544 56324 112544 56308 112544 56308 112545 56324 112545 56309 112545 56308 112546 56309 112546 56335 112546 56335 112547 56309 112547 56310 112547 56335 112548 56310 112548 56311 112548 56311 112549 56310 112549 56323 112549 56311 112550 56323 112550 56334 112550 56334 112551 56323 112551 56326 112551 56334 112552 56326 112552 56312 112552 56312 112553 56326 112553 56325 112553 56312 112554 56325 112554 56346 112554 56346 112555 56325 112555 56313 112555 56346 112556 56313 112556 56345 112556 56345 112557 56313 112557 56314 112557 56345 112558 56314 112558 56315 112558 56315 112559 56314 112559 56327 112559 56315 112560 56327 112560 56317 112560 56317 112561 56327 112561 56316 112561 56317 112562 56316 112562 56318 112562 56318 112563 56316 112563 56319 112563 56318 112564 56319 112564 56320 112564 56320 112565 56319 112565 56321 112565 56320 112566 56321 112566 56366 112566 56366 112567 56321 112567 56329 112567 56366 112568 56329 112568 56283 112568 56283 112569 56329 112569 56284 112569 56303 112570 56302 112570 56328 112570 56303 112571 56328 112571 56306 112571 56324 112572 56307 112572 56328 112572 56328 112573 56307 112573 56322 112573 56328 112574 56322 112574 56306 112574 56323 112575 56310 112575 56328 112575 56328 112576 56310 112576 56309 112576 56328 112577 56309 112577 56324 112577 56313 112578 56325 112578 56328 112578 56328 112579 56325 112579 56326 112579 56328 112580 56326 112580 56323 112580 56316 112581 56327 112581 56328 112581 56328 112582 56327 112582 56314 112582 56328 112583 56314 112583 56313 112583 56329 112584 56321 112584 56328 112584 56328 112585 56321 112585 56319 112585 56328 112586 56319 112586 56316 112586 56287 112587 56286 112587 56328 112587 56328 112588 56286 112588 56284 112588 56328 112589 56284 112589 56329 112589 56330 112590 56331 112590 56328 112590 56328 112591 56331 112591 56288 112591 56328 112592 56288 112592 56287 112592 56292 112593 56332 112593 56328 112593 56328 112594 56332 112594 56290 112594 56328 112595 56290 112595 56330 112595 56297 112596 56296 112596 56328 112596 56328 112597 56296 112597 56294 112597 56328 112598 56294 112598 56292 112598 56302 112599 56300 112599 56328 112599 56328 112600 56300 112600 56298 112600 56328 112601 56298 112601 56297 112601 56346 112602 56333 112602 56312 112602 56312 112603 56333 112603 56391 112603 56312 112604 56391 112604 56334 112604 56334 112605 56391 112605 56393 112605 56334 112606 56393 112606 56311 112606 56311 112607 56393 112607 56394 112607 56311 112608 56394 112608 56335 112608 56335 112609 56394 112609 56395 112609 56335 112610 56395 112610 56308 112610 56308 112611 56395 112611 56397 112611 56308 112612 56397 112612 56353 112612 56291 112613 56336 112613 56337 112613 56337 112614 56336 112614 56373 112614 56337 112615 56373 112615 56338 112615 56338 112616 56373 112616 56374 112616 56338 112617 56374 112617 56289 112617 56289 112618 56374 112618 56339 112618 56289 112619 56339 112619 56340 112619 56340 112620 56339 112620 56341 112620 56340 112621 56341 112621 56361 112621 56320 112622 56385 112622 56318 112622 56318 112623 56385 112623 56342 112623 56318 112624 56342 112624 56317 112624 56317 112625 56342 112625 56343 112625 56317 112626 56343 112626 56315 112626 56315 112627 56343 112627 56388 112627 56315 112628 56388 112628 56345 112628 56345 112629 56388 112629 56344 112629 56345 112630 56344 112630 56346 112630 56346 112631 56344 112631 56389 112631 56346 112632 56389 112632 56333 112632 56301 112633 56347 112633 56299 112633 56299 112634 56347 112634 56368 112634 56299 112635 56368 112635 56348 112635 56348 112636 56368 112636 56370 112636 56348 112637 56370 112637 56349 112637 56349 112638 56370 112638 56350 112638 56349 112639 56350 112639 56295 112639 56295 112640 56350 112640 56372 112640 56295 112641 56372 112641 56293 112641 56293 112642 56372 112642 56351 112642 56293 112643 56351 112643 56291 112643 56291 112644 56351 112644 56352 112644 56291 112645 56352 112645 56336 112645 56397 112646 56398 112646 56353 112646 56353 112647 56398 112647 56355 112647 56353 112648 56355 112648 56354 112648 56354 112649 56355 112649 56356 112649 56354 112650 56356 112650 56305 112650 56305 112651 56356 112651 56401 112651 56305 112652 56401 112652 56304 112652 56304 112653 56401 112653 56358 112653 56304 112654 56358 112654 56357 112654 56357 112655 56358 112655 56359 112655 56357 112656 56359 112656 56301 112656 56301 112657 56359 112657 56360 112657 56301 112658 56360 112658 56347 112658 56341 112659 56362 112659 56361 112659 56361 112660 56362 112660 56363 112660 56361 112661 56363 112661 56364 112661 56364 112662 56363 112662 56365 112662 56364 112663 56365 112663 56285 112663 56285 112664 56365 112664 56379 112664 56285 112665 56379 112665 56283 112665 56283 112666 56379 112666 56380 112666 56283 112667 56380 112667 56366 112667 56366 112668 56380 112668 56381 112668 56366 112669 56381 112669 56320 112669 56320 112670 56381 112670 56382 112670 56320 112671 56382 112671 56385 112671 56358 112672 56407 112672 56359 112672 56359 112673 56407 112673 56410 112673 56359 112674 56410 112674 56360 112674 56360 112675 56410 112675 56409 112675 56360 112676 56409 112676 56347 112676 56347 112677 56409 112677 56367 112677 56347 112678 56367 112678 56368 112678 56368 112679 56367 112679 56369 112679 56368 112680 56369 112680 56370 112680 56370 112681 56369 112681 56413 112681 56370 112682 56413 112682 56350 112682 56350 112683 56413 112683 56371 112683 56350 112684 56371 112684 56372 112684 56372 112685 56371 112685 56411 112685 56372 112686 56411 112686 56351 112686 56351 112687 56411 112687 56428 112687 56351 112688 56428 112688 56352 112688 56352 112689 56428 112689 56427 112689 56352 112690 56427 112690 56336 112690 56336 112691 56427 112691 56430 112691 56336 112692 56430 112692 56373 112692 56373 112693 56430 112693 56429 112693 56373 112694 56429 112694 56374 112694 56374 112695 56429 112695 56375 112695 56374 112696 56375 112696 56339 112696 56339 112697 56375 112697 56376 112697 56339 112698 56376 112698 56341 112698 56341 112699 56376 112699 56377 112699 56341 112700 56377 112700 56362 112700 56362 112701 56377 112701 56415 112701 56362 112702 56415 112702 56363 112702 56363 112703 56415 112703 56414 112703 56363 112704 56414 112704 56365 112704 56365 112705 56414 112705 56378 112705 56365 112706 56378 112706 56379 112706 56379 112707 56378 112707 56432 112707 56379 112708 56432 112708 56380 112708 56380 112709 56432 112709 56431 112709 56380 112710 56431 112710 56381 112710 56381 112711 56431 112711 56383 112711 56381 112712 56383 112712 56382 112712 56382 112713 56383 112713 56384 112713 56382 112714 56384 112714 56385 112714 56385 112715 56384 112715 56417 112715 56385 112716 56417 112716 56342 112716 56342 112717 56417 112717 56386 112717 56342 112718 56386 112718 56343 112718 56343 112719 56386 112719 56387 112719 56343 112720 56387 112720 56388 112720 56388 112721 56387 112721 56422 112721 56388 112722 56422 112722 56344 112722 56344 112723 56422 112723 56421 112723 56344 112724 56421 112724 56389 112724 56389 112725 56421 112725 56420 112725 56389 112726 56420 112726 56333 112726 56333 112727 56420 112727 56390 112727 56333 112728 56390 112728 56391 112728 56391 112729 56390 112729 56392 112729 56391 112730 56392 112730 56393 112730 56393 112731 56392 112731 56424 112731 56393 112732 56424 112732 56394 112732 56394 112733 56424 112733 56423 112733 56394 112734 56423 112734 56395 112734 56395 112735 56423 112735 56396 112735 56395 112736 56396 112736 56397 112736 56397 112737 56396 112737 56405 112737 56397 112738 56405 112738 56398 112738 56398 112739 56405 112739 56403 112739 56398 112740 56403 112740 56355 112740 56355 112741 56403 112741 56399 112741 56355 112742 56399 112742 56356 112742 56356 112743 56399 112743 56400 112743 56356 112744 56400 112744 56401 112744 56401 112745 56400 112745 56408 112745 56401 112746 56408 112746 56358 112746 56358 112747 56408 112747 56407 112747 56406 112748 56400 112748 56402 112748 56402 112749 56400 112749 56399 112749 56402 112750 56399 112750 56404 112750 56412 112751 56592 112751 56411 112751 56387 112752 56416 112752 56615 112752 56425 112753 56392 112753 56611 112753 56611 112754 56392 112754 56390 112754 56611 112755 56390 112755 56419 112755 56399 112756 56403 112756 56404 112756 56404 112757 56403 112757 56405 112757 56404 112758 56405 112758 56607 112758 56601 112759 56407 112759 56406 112759 56406 112760 56407 112760 56408 112760 56406 112761 56408 112761 56400 112761 56595 112762 56367 112762 56597 112762 56597 112763 56367 112763 56409 112763 56597 112764 56409 112764 56601 112764 56601 112765 56409 112765 56410 112765 56601 112766 56410 112766 56407 112766 56411 112767 56371 112767 56412 112767 56412 112768 56371 112768 56413 112768 56412 112769 56413 112769 56595 112769 56595 112770 56413 112770 56369 112770 56595 112771 56369 112771 56367 112771 56587 112772 56585 112772 56377 112772 56621 112773 56378 112773 56583 112773 56583 112774 56378 112774 56414 112774 56583 112775 56414 112775 56585 112775 56585 112776 56414 112776 56415 112776 56585 112777 56415 112777 56377 112777 56387 112778 56386 112778 56416 112778 56416 112779 56386 112779 56417 112779 56416 112780 56417 112780 56418 112780 56418 112781 56417 112781 56384 112781 56418 112782 56384 112782 56620 112782 56390 112783 56420 112783 56419 112783 56419 112784 56420 112784 56421 112784 56419 112785 56421 112785 56615 112785 56615 112786 56421 112786 56422 112786 56615 112787 56422 112787 56387 112787 56405 112788 56396 112788 56607 112788 56607 112789 56396 112789 56423 112789 56607 112790 56423 112790 56425 112790 56425 112791 56423 112791 56424 112791 56425 112792 56424 112792 56392 112792 56426 112793 56430 112793 56590 112793 56590 112794 56430 112794 56427 112794 56590 112795 56427 112795 56592 112795 56592 112796 56427 112796 56428 112796 56592 112797 56428 112797 56411 112797 56377 112798 56376 112798 56587 112798 56587 112799 56376 112799 56375 112799 56587 112800 56375 112800 56426 112800 56426 112801 56375 112801 56429 112801 56426 112802 56429 112802 56430 112802 56384 112803 56383 112803 56620 112803 56620 112804 56383 112804 56431 112804 56620 112805 56431 112805 56621 112805 56621 112806 56431 112806 56432 112806 56621 112807 56432 112807 56378 112807 56442 112808 56572 112808 56443 112808 56443 112809 56572 112809 56518 112809 56572 112810 56433 112810 56440 112810 56440 112811 56433 112811 56434 112811 56440 112812 56434 112812 56574 112812 56435 112813 56506 112813 56446 112813 56451 112814 56452 112814 56572 112814 56574 112815 56577 112815 56440 112815 56440 112816 56577 112816 56436 112816 56440 112817 56436 112817 56437 112817 56437 112818 56579 112818 56440 112818 56440 112819 56579 112819 56438 112819 56440 112820 56438 112820 56439 112820 56506 112821 56508 112821 56446 112821 56446 112822 56508 112822 56440 112822 56446 112823 56440 112823 56581 112823 56581 112824 56440 112824 56439 112824 56440 112825 56441 112825 56572 112825 56572 112826 56441 112826 56511 112826 56572 112827 56511 112827 56512 112827 56442 112828 56443 112828 56445 112828 56445 112829 56443 112829 56563 112829 56445 112830 56563 112830 56444 112830 56444 112831 56565 112831 56445 112831 56445 112832 56565 112832 56567 112832 56445 112833 56567 112833 56455 112833 56446 112834 56447 112834 56502 112834 56502 112835 56448 112835 56446 112835 56446 112836 56448 112836 56504 112836 56446 112837 56504 112837 56505 112837 56512 112838 56449 112838 56572 112838 56572 112839 56449 112839 56450 112839 56572 112840 56450 112840 56451 112840 56452 112841 56453 112841 56572 112841 56572 112842 56453 112842 56454 112842 56572 112843 56454 112843 56518 112843 56569 112844 56456 112844 56455 112844 56455 112845 56456 112845 56571 112845 56455 112846 56571 112846 56445 112846 56505 112847 56457 112847 56446 112847 56446 112848 56457 112848 56458 112848 56446 112849 56458 112849 56435 112849 56446 112850 56459 112850 56500 112850 56459 112851 56562 112851 56475 112851 56562 112852 56537 112852 56603 112852 56562 112853 56603 112853 56475 112853 56475 112854 56603 112854 56460 112854 56475 112855 56460 112855 56461 112855 56461 112856 56460 112856 56604 112856 56461 112857 56604 112857 56462 112857 56462 112858 56604 112858 56605 112858 56462 112859 56605 112859 56463 112859 56463 112860 56605 112860 56606 112860 56463 112861 56606 112861 56464 112861 56464 112862 56606 112862 56466 112862 56464 112863 56466 112863 56465 112863 56465 112864 56466 112864 56608 112864 56465 112865 56608 112865 56479 112865 56479 112866 56608 112866 56609 112866 56479 112867 56609 112867 56482 112867 56482 112868 56609 112868 56610 112868 56482 112869 56610 112869 56483 112869 56483 112870 56610 112870 56467 112870 56483 112871 56467 112871 56485 112871 56485 112872 56467 112872 56469 112872 56485 112873 56469 112873 56468 112873 56468 112874 56469 112874 56612 112874 56468 112875 56612 112875 56487 112875 56487 112876 56612 112876 56613 112876 56487 112877 56613 112877 56488 112877 56488 112878 56613 112878 56614 112878 56488 112879 56614 112879 56490 112879 56490 112880 56614 112880 56470 112880 56490 112881 56470 112881 56491 112881 56491 112882 56470 112882 56471 112882 56491 112883 56471 112883 56492 112883 56492 112884 56471 112884 56616 112884 56492 112885 56616 112885 56493 112885 56493 112886 56616 112886 56472 112886 56493 112887 56472 112887 56494 112887 56494 112888 56472 112888 56617 112888 56494 112889 56617 112889 56495 112889 56495 112890 56617 112890 56618 112890 56495 112891 56618 112891 56497 112891 56497 112892 56618 112892 56619 112892 56497 112893 56619 112893 56473 112893 56473 112894 56619 112894 56474 112894 56473 112895 56474 112895 56498 112895 56459 112896 56475 112896 56500 112896 56500 112897 56475 112897 56461 112897 56500 112898 56461 112898 56501 112898 56501 112899 56461 112899 56462 112899 56501 112900 56462 112900 56503 112900 56503 112901 56462 112901 56463 112901 56503 112902 56463 112902 56476 112902 56476 112903 56463 112903 56464 112903 56476 112904 56464 112904 56477 112904 56477 112905 56464 112905 56465 112905 56477 112906 56465 112906 56478 112906 56478 112907 56465 112907 56479 112907 56478 112908 56479 112908 56480 112908 56480 112909 56479 112909 56482 112909 56480 112910 56482 112910 56481 112910 56481 112911 56482 112911 56483 112911 56481 112912 56483 112912 56484 112912 56484 112913 56483 112913 56485 112913 56484 112914 56485 112914 56507 112914 56507 112915 56485 112915 56468 112915 56507 112916 56468 112916 56486 112916 56486 112917 56468 112917 56487 112917 56486 112918 56487 112918 56509 112918 56509 112919 56487 112919 56488 112919 56509 112920 56488 112920 56510 112920 56510 112921 56488 112921 56490 112921 56510 112922 56490 112922 56489 112922 56489 112923 56490 112923 56491 112923 56489 112924 56491 112924 56513 112924 56513 112925 56491 112925 56492 112925 56513 112926 56492 112926 56514 112926 56514 112927 56492 112927 56493 112927 56514 112928 56493 112928 56515 112928 56515 112929 56493 112929 56494 112929 56515 112930 56494 112930 56516 112930 56516 112931 56494 112931 56495 112931 56516 112932 56495 112932 56496 112932 56496 112933 56495 112933 56497 112933 56496 112934 56497 112934 56517 112934 56517 112935 56497 112935 56473 112935 56517 112936 56473 112936 56499 112936 56499 112937 56473 112937 56498 112937 56499 112938 56498 112938 56520 112938 56446 112939 56500 112939 56447 112939 56447 112940 56500 112940 56501 112940 56447 112941 56501 112941 56502 112941 56502 112942 56501 112942 56503 112942 56502 112943 56503 112943 56448 112943 56448 112944 56503 112944 56476 112944 56448 112945 56476 112945 56504 112945 56504 112946 56476 112946 56477 112946 56504 112947 56477 112947 56505 112947 56505 112948 56477 112948 56478 112948 56505 112949 56478 112949 56457 112949 56457 112950 56478 112950 56480 112950 56457 112951 56480 112951 56458 112951 56458 112952 56480 112952 56481 112952 56458 112953 56481 112953 56435 112953 56435 112954 56481 112954 56484 112954 56435 112955 56484 112955 56506 112955 56506 112956 56484 112956 56507 112956 56506 112957 56507 112957 56508 112957 56508 112958 56507 112958 56486 112958 56508 112959 56486 112959 56440 112959 56440 112960 56486 112960 56509 112960 56440 112961 56509 112961 56441 112961 56441 112962 56509 112962 56510 112962 56441 112963 56510 112963 56511 112963 56511 112964 56510 112964 56489 112964 56511 112965 56489 112965 56512 112965 56512 112966 56489 112966 56513 112966 56512 112967 56513 112967 56449 112967 56449 112968 56513 112968 56514 112968 56449 112969 56514 112969 56450 112969 56450 112970 56514 112970 56515 112970 56450 112971 56515 112971 56451 112971 56451 112972 56515 112972 56516 112972 56451 112973 56516 112973 56452 112973 56452 112974 56516 112974 56496 112974 56452 112975 56496 112975 56453 112975 56453 112976 56496 112976 56517 112976 56453 112977 56517 112977 56454 112977 56454 112978 56517 112978 56499 112978 56454 112979 56499 112979 56518 112979 56518 112980 56499 112980 56520 112980 56518 112981 56520 112981 56443 112981 56443 112982 56520 112982 56519 112982 56520 112983 56498 112983 56521 112983 56498 112984 56474 112984 56522 112984 56498 112985 56522 112985 56521 112985 56521 112986 56522 112986 56584 112986 56521 112987 56584 112987 56538 112987 56538 112988 56584 112988 56523 112988 56538 112989 56523 112989 56524 112989 56524 112990 56523 112990 56586 112990 56524 112991 56586 112991 56539 112991 56539 112992 56586 112992 56525 112992 56539 112993 56525 112993 56541 112993 56541 112994 56525 112994 56526 112994 56541 112995 56526 112995 56542 112995 56542 112996 56526 112996 56588 112996 56542 112997 56588 112997 56544 112997 56544 112998 56588 112998 56589 112998 56544 112999 56589 112999 56527 112999 56527 113000 56589 113000 56528 113000 56527 113001 56528 113001 56546 113001 56546 113002 56528 113002 56529 113002 56546 113003 56529 113003 56548 113003 56548 113004 56529 113004 56591 113004 56548 113005 56591 113005 56551 113005 56551 113006 56591 113006 56530 113006 56551 113007 56530 113007 56531 113007 56531 113008 56530 113008 56593 113008 56531 113009 56593 113009 56532 113009 56532 113010 56593 113010 56594 113010 56532 113011 56594 113011 56553 113011 56553 113012 56594 113012 56533 113012 56553 113013 56533 113013 56554 113013 56554 113014 56533 113014 56596 113014 56554 113015 56596 113015 56534 113015 56534 113016 56596 113016 56598 113016 56534 113017 56598 113017 56556 113017 56556 113018 56598 113018 56599 113018 56556 113019 56599 113019 56558 113019 56558 113020 56599 113020 56600 113020 56558 113021 56600 113021 56535 113021 56535 113022 56600 113022 56536 113022 56535 113023 56536 113023 56559 113023 56559 113024 56536 113024 56602 113024 56559 113025 56602 113025 56561 113025 56561 113026 56602 113026 56537 113026 56561 113027 56537 113027 56562 113027 56520 113028 56521 113028 56519 113028 56519 113029 56521 113029 56538 113029 56519 113030 56538 113030 56564 113030 56564 113031 56538 113031 56524 113031 56564 113032 56524 113032 56566 113032 56566 113033 56524 113033 56539 113033 56566 113034 56539 113034 56568 113034 56568 113035 56539 113035 56541 113035 56568 113036 56541 113036 56540 113036 56540 113037 56541 113037 56542 113037 56540 113038 56542 113038 56543 113038 56543 113039 56542 113039 56544 113039 56543 113040 56544 113040 56570 113040 56570 113041 56544 113041 56527 113041 56570 113042 56527 113042 56545 113042 56545 113043 56527 113043 56546 113043 56545 113044 56546 113044 56547 113044 56547 113045 56546 113045 56548 113045 56547 113046 56548 113046 56549 113046 56549 113047 56548 113047 56551 113047 56549 113048 56551 113048 56550 113048 56550 113049 56551 113049 56531 113049 56550 113050 56531 113050 56552 113050 56552 113051 56531 113051 56532 113051 56552 113052 56532 113052 56573 113052 56573 113053 56532 113053 56553 113053 56573 113054 56553 113054 56575 113054 56575 113055 56553 113055 56554 113055 56575 113056 56554 113056 56576 113056 56576 113057 56554 113057 56534 113057 56576 113058 56534 113058 56555 113058 56555 113059 56534 113059 56556 113059 56555 113060 56556 113060 56557 113060 56557 113061 56556 113061 56558 113061 56557 113062 56558 113062 56578 113062 56578 113063 56558 113063 56535 113063 56578 113064 56535 113064 56580 113064 56580 113065 56535 113065 56559 113065 56580 113066 56559 113066 56560 113066 56560 113067 56559 113067 56561 113067 56560 113068 56561 113068 56582 113068 56582 113069 56561 113069 56562 113069 56582 113070 56562 113070 56459 113070 56443 113071 56519 113071 56563 113071 56563 113072 56519 113072 56564 113072 56563 113073 56564 113073 56444 113073 56444 113074 56564 113074 56566 113074 56444 113075 56566 113075 56565 113075 56565 113076 56566 113076 56568 113076 56565 113077 56568 113077 56567 113077 56567 113078 56568 113078 56540 113078 56567 113079 56540 113079 56455 113079 56455 113080 56540 113080 56543 113080 56455 113081 56543 113081 56569 113081 56569 113082 56543 113082 56570 113082 56569 113083 56570 113083 56456 113083 56456 113084 56570 113084 56545 113084 56456 113085 56545 113085 56571 113085 56571 113086 56545 113086 56547 113086 56571 113087 56547 113087 56445 113087 56445 113088 56547 113088 56549 113088 56445 113089 56549 113089 56442 113089 56442 113090 56549 113090 56550 113090 56442 113091 56550 113091 56572 113091 56572 113092 56550 113092 56552 113092 56572 113093 56552 113093 56433 113093 56433 113094 56552 113094 56573 113094 56433 113095 56573 113095 56434 113095 56434 113096 56573 113096 56575 113096 56434 113097 56575 113097 56574 113097 56574 113098 56575 113098 56576 113098 56574 113099 56576 113099 56577 113099 56577 113100 56576 113100 56555 113100 56577 113101 56555 113101 56436 113101 56436 113102 56555 113102 56557 113102 56436 113103 56557 113103 56437 113103 56437 113104 56557 113104 56578 113104 56437 113105 56578 113105 56579 113105 56579 113106 56578 113106 56580 113106 56579 113107 56580 113107 56438 113107 56438 113108 56580 113108 56560 113108 56438 113109 56560 113109 56439 113109 56439 113110 56560 113110 56582 113110 56439 113111 56582 113111 56581 113111 56581 113112 56582 113112 56459 113112 56581 113113 56459 113113 56446 113113 56474 113114 56621 113114 56522 113114 56522 113115 56621 113115 56583 113115 56522 113116 56583 113116 56584 113116 56584 113117 56583 113117 56523 113117 56523 113118 56583 113118 56585 113118 56523 113119 56585 113119 56586 113119 56586 113120 56585 113120 56525 113120 56525 113121 56585 113121 56587 113121 56525 113122 56587 113122 56526 113122 56526 113123 56587 113123 56588 113123 56588 113124 56587 113124 56426 113124 56588 113125 56426 113125 56589 113125 56589 113126 56426 113126 56528 113126 56528 113127 56426 113127 56590 113127 56528 113128 56590 113128 56529 113128 56529 113129 56590 113129 56591 113129 56591 113130 56590 113130 56592 113130 56591 113131 56592 113131 56530 113131 56530 113132 56592 113132 56593 113132 56593 113133 56592 113133 56412 113133 56593 113134 56412 113134 56594 113134 56594 113135 56412 113135 56533 113135 56533 113136 56412 113136 56595 113136 56533 113137 56595 113137 56596 113137 56596 113138 56595 113138 56598 113138 56598 113139 56595 113139 56597 113139 56598 113140 56597 113140 56599 113140 56599 113141 56597 113141 56600 113141 56600 113142 56597 113142 56601 113142 56600 113143 56601 113143 56536 113143 56536 113144 56601 113144 56602 113144 56602 113145 56601 113145 56406 113145 56602 113146 56406 113146 56537 113146 56537 113147 56406 113147 56603 113147 56603 113148 56406 113148 56402 113148 56603 113149 56402 113149 56460 113149 56460 113150 56402 113150 56604 113150 56604 113151 56402 113151 56404 113151 56604 113152 56404 113152 56605 113152 56605 113153 56404 113153 56606 113153 56606 113154 56404 113154 56607 113154 56606 113155 56607 113155 56466 113155 56466 113156 56607 113156 56608 113156 56608 113157 56607 113157 56425 113157 56608 113158 56425 113158 56609 113158 56609 113159 56425 113159 56610 113159 56610 113160 56425 113160 56611 113160 56610 113161 56611 113161 56467 113161 56467 113162 56611 113162 56469 113162 56469 113163 56611 113163 56419 113163 56469 113164 56419 113164 56612 113164 56612 113165 56419 113165 56613 113165 56613 113166 56419 113166 56615 113166 56613 113167 56615 113167 56614 113167 56614 113168 56615 113168 56470 113168 56470 113169 56615 113169 56416 113169 56470 113170 56416 113170 56471 113170 56471 113171 56416 113171 56616 113171 56616 113172 56416 113172 56418 113172 56616 113173 56418 113173 56472 113173 56472 113174 56418 113174 56617 113174 56617 113175 56418 113175 56620 113175 56617 113176 56620 113176 56618 113176 56618 113177 56620 113177 56619 113177 56619 113178 56620 113178 56621 113178 56619 113179 56621 113179 56474 113179 57596 113180 57592 113180 56622 113180 56622 113181 57592 113181 57589 113181 56622 113182 57589 113182 56635 113182 56638 113183 56979 113183 56980 113183 56627 113184 56874 113184 56876 113184 56935 113185 56984 113185 57554 113185 57554 113186 56984 113186 56631 113186 56824 113187 56825 113187 56644 113187 56623 113188 56651 113188 57560 113188 57560 113189 56651 113189 56624 113189 57915 113190 57601 113190 56625 113190 56625 113191 57601 113191 57604 113191 56625 113192 57604 113192 57911 113192 57911 113193 57604 113193 56654 113193 56626 113194 56871 113194 56627 113194 56627 113195 56871 113195 56873 113195 56627 113196 56873 113196 56874 113196 56868 113197 56628 113197 56626 113197 56626 113198 56628 113198 56870 113198 56626 113199 56870 113199 56871 113199 56669 113200 56661 113200 57582 113200 57582 113201 56661 113201 56629 113201 56984 113202 56630 113202 56631 113202 56631 113203 56630 113203 56971 113203 56631 113204 56971 113204 56972 113204 56632 113205 56830 113205 56658 113205 56624 113206 56780 113206 57560 113206 57560 113207 56780 113207 56784 113207 57560 113208 56784 113208 56644 113208 56644 113209 56784 113209 56823 113209 56644 113210 56823 113210 56824 113210 57596 113211 56622 113211 56626 113211 56626 113212 56622 113212 56633 113212 56626 113213 56633 113213 56868 113213 57589 113214 56634 113214 56635 113214 56635 113215 56634 113215 57586 113215 56635 113216 57586 113216 56636 113216 56636 113217 57586 113217 56638 113217 56636 113218 56638 113218 56637 113218 56637 113219 56638 113219 56980 113219 56629 113220 56975 113220 57582 113220 57582 113221 56975 113221 56976 113221 57582 113222 56976 113222 56638 113222 56638 113223 56976 113223 56639 113223 56638 113224 56639 113224 56979 113224 56650 113225 56930 113225 57554 113225 57554 113226 56930 113226 56640 113226 57554 113227 56640 113227 56932 113227 56932 113228 56933 113228 57554 113228 57554 113229 56933 113229 56934 113229 57554 113230 56934 113230 56935 113230 56641 113231 56928 113231 56650 113231 56650 113232 56928 113232 56929 113232 56650 113233 56929 113233 56930 113233 56642 113234 57550 113234 56649 113234 56649 113235 57550 113235 57566 113235 56649 113236 57566 113236 56835 113236 56825 113237 56643 113237 56644 113237 56644 113238 56643 113238 56645 113238 56644 113239 56645 113239 56658 113239 56658 113240 56645 113240 56828 113240 56658 113241 56828 113241 56632 113241 56651 113242 57910 113242 56652 113242 57915 113243 56646 113243 57601 113243 57601 113244 56646 113244 56647 113244 57601 113245 56647 113245 57580 113245 57580 113246 56647 113246 56648 113246 57580 113247 56648 113247 56669 113247 56669 113248 56648 113248 57916 113248 56642 113249 56649 113249 56650 113249 56650 113250 56649 113250 56927 113250 56650 113251 56927 113251 56641 113251 56651 113252 57905 113252 57907 113252 56876 113253 56651 113253 56627 113253 56627 113254 56651 113254 56652 113254 56627 113255 56652 113255 56654 113255 56654 113256 56652 113256 56653 113256 56654 113257 56653 113257 57911 113257 57923 113258 56661 113258 56655 113258 56655 113259 56661 113259 57921 113259 57923 113260 56656 113260 56661 113260 56661 113261 56656 113261 57925 113261 56661 113262 57925 113262 56657 113262 57566 113263 57568 113263 56835 113263 56835 113264 57568 113264 57563 113264 56835 113265 57563 113265 56832 113265 56832 113266 57563 113266 56658 113266 56832 113267 56658 113267 56831 113267 56831 113268 56658 113268 56830 113268 57907 113269 56659 113269 56651 113269 56651 113270 56659 113270 56660 113270 56651 113271 56660 113271 57910 113271 56657 113272 56662 113272 56661 113272 56661 113273 56662 113273 57928 113273 56661 113274 57928 113274 56664 113274 56667 113275 57900 113275 56623 113275 56623 113276 57900 113276 57902 113276 56623 113277 57902 113277 56651 113277 56651 113278 57902 113278 57903 113278 56651 113279 57903 113279 57905 113279 56972 113280 56661 113280 56631 113280 56631 113281 56661 113281 56664 113281 56631 113282 56664 113282 56663 113282 56663 113283 56664 113283 57932 113283 56663 113284 57932 113284 57556 113284 57556 113285 57932 113285 57933 113285 57556 113286 57933 113286 57934 113286 57934 113287 56665 113287 57556 113287 57556 113288 56665 113288 56666 113288 57556 113289 56666 113289 56623 113289 56623 113290 56666 113290 57898 113290 56623 113291 57898 113291 56667 113291 57916 113292 56668 113292 56669 113292 56669 113293 56668 113293 57918 113293 56669 113294 57918 113294 56661 113294 56661 113295 57918 113295 56670 113295 56661 113296 56670 113296 57921 113296 56674 113297 57488 113297 56687 113297 57089 113298 57088 113298 56672 113298 56672 113299 57088 113299 56671 113299 56672 113300 56671 113300 57494 113300 57494 113301 56671 113301 56676 113301 57494 113302 56676 113302 56673 113302 56674 113303 56687 113303 57491 113303 57258 113304 57509 113304 56675 113304 56675 113305 57509 113305 57508 113305 56675 113306 57508 113306 57265 113306 57265 113307 57508 113307 56683 113307 57504 113308 57502 113308 57289 113308 56673 113309 56676 113309 56677 113309 56677 113310 56676 113310 56678 113310 56677 113311 56678 113311 56679 113311 56679 113312 56678 113312 56680 113312 56679 113313 56680 113313 56681 113313 56681 113314 56680 113314 57206 113314 56681 113315 57206 113315 56695 113315 57040 113316 56682 113316 57044 113316 57044 113317 56682 113317 57514 113317 57044 113318 57514 113318 57046 113318 57046 113319 57514 113319 57054 113319 57054 113320 57514 113320 57513 113320 57054 113321 57513 113321 57007 113321 56704 113322 57013 113322 57513 113322 57513 113323 57013 113323 57012 113323 57513 113324 57012 113324 57007 113324 56683 113325 57508 113325 57229 113325 57229 113326 57508 113326 56684 113326 57229 113327 56684 113327 57230 113327 57230 113328 56684 113328 57289 113328 57289 113329 56684 113329 57505 113329 57289 113330 57505 113330 57504 113330 57078 113331 57135 113331 56697 113331 56697 113332 57135 113332 56685 113332 56697 113333 56685 113333 56686 113333 56686 113334 56685 113334 57118 113334 56686 113335 57118 113335 56672 113335 56672 113336 57118 113336 57117 113336 56672 113337 57117 113337 57089 113337 57488 113338 57521 113338 56687 113338 56687 113339 57521 113339 57520 113339 56687 113340 57520 113340 56690 113340 56690 113341 57520 113341 56688 113341 56690 113342 56688 113342 56689 113342 56689 113343 57518 113343 56690 113343 56690 113344 57518 113344 57517 113344 56690 113345 57517 113345 56691 113345 56691 113346 57517 113346 56682 113346 56691 113347 56682 113347 56692 113347 56692 113348 56682 113348 57040 113348 56693 113349 56708 113349 56694 113349 56694 113350 56708 113350 56681 113350 56694 113351 56681 113351 57201 113351 57201 113352 56681 113352 56695 113352 57491 113353 56687 113353 56697 113353 56697 113354 56687 113354 56696 113354 56697 113355 56696 113355 57078 113355 57258 113356 57232 113356 57509 113356 57509 113357 57232 113357 56698 113357 57509 113358 56698 113358 57511 113358 57511 113359 56698 113359 56700 113359 57511 113360 56700 113360 56699 113360 56699 113361 56700 113361 56701 113361 56699 113362 56701 113362 56702 113362 56702 113363 56701 113363 56703 113363 56702 113364 56703 113364 56704 113364 56704 113365 56703 113365 57019 113365 56704 113366 57019 113366 57013 113366 57502 113367 57501 113367 57289 113367 57289 113368 57501 113368 56705 113368 57289 113369 56705 113369 57288 113369 57288 113370 56705 113370 57500 113370 56693 113371 56706 113371 56708 113371 56708 113372 56706 113372 56707 113372 56708 113373 56707 113373 56710 113373 56710 113374 56707 113374 56709 113374 56710 113375 56709 113375 56711 113375 56711 113376 56709 113376 57288 113376 56711 113377 57288 113377 57499 113377 57499 113378 57288 113378 57500 113378 56779 113379 56988 113379 56712 113379 56712 113380 56988 113380 56904 113380 56712 113381 56904 113381 57069 113381 57069 113382 56904 113382 56903 113382 57069 113383 56903 113383 57068 113383 57068 113384 56903 113384 56897 113384 57068 113385 56897 113385 57067 113385 57067 113386 56897 113386 56902 113386 57067 113387 56902 113387 57000 113387 57000 113388 56902 113388 56713 113388 57000 113389 56713 113389 56714 113389 56714 113390 56713 113390 56899 113390 56714 113391 56899 113391 57001 113391 57001 113392 56899 113392 56898 113392 57001 113393 56898 113393 57063 113393 57063 113394 56898 113394 56715 113394 57063 113395 56715 113395 57062 113395 56716 113396 56717 113396 56895 113396 56895 113397 56717 113397 57062 113397 56895 113398 57062 113398 56896 113398 56896 113399 57062 113399 56715 113399 56718 113400 56719 113400 56892 113400 56892 113401 56719 113401 56720 113401 56892 113402 56720 113402 56891 113402 56891 113403 56720 113403 57029 113403 56891 113404 57029 113404 56721 113404 56721 113405 57029 113405 57002 113405 56721 113406 57002 113406 56722 113406 56722 113407 57002 113407 57035 113407 56722 113408 57035 113408 56893 113408 56893 113409 57035 113409 57034 113409 56893 113410 57034 113410 56716 113410 56716 113411 57034 113411 56723 113411 56716 113412 56723 113412 56717 113412 56719 113413 56718 113413 56992 113413 56992 113414 56718 113414 56803 113414 56992 113415 56803 113415 56724 113415 56724 113416 56803 113416 56802 113416 56724 113417 56802 113417 56725 113417 56725 113418 56802 113418 56727 113418 56725 113419 56727 113419 56726 113419 56726 113420 56727 113420 56801 113420 56726 113421 56801 113421 56728 113421 56728 113422 56801 113422 56799 113422 56728 113423 56799 113423 56729 113423 56729 113424 56799 113424 56730 113424 56729 113425 56730 113425 57130 113425 57130 113426 56730 113426 56731 113426 57130 113427 56731 113427 57071 113427 57071 113428 56731 113428 56797 113428 57071 113429 56797 113429 57129 113429 56793 113430 57122 113430 56732 113430 56732 113431 57122 113431 57129 113431 56732 113432 57129 113432 56733 113432 56733 113433 57129 113433 56797 113433 56791 113434 57103 113434 56734 113434 56734 113435 57103 113435 57102 113435 56734 113436 57102 113436 56789 113436 56789 113437 57102 113437 57105 113437 56789 113438 57105 113438 56735 113438 56735 113439 57105 113439 56736 113439 56735 113440 56736 113440 56787 113440 56787 113441 56736 113441 56738 113441 56787 113442 56738 113442 56737 113442 56737 113443 56738 113443 57072 113443 56737 113444 57072 113444 56793 113444 56793 113445 57072 113445 57109 113445 56793 113446 57109 113446 57122 113446 57103 113447 56791 113447 56739 113447 56739 113448 56791 113448 56740 113448 56739 113449 56740 113449 57216 113449 57216 113450 56740 113450 56741 113450 57216 113451 56741 113451 57156 113451 57156 113452 56741 113452 56742 113452 57156 113453 56742 113453 57157 113453 57157 113454 56742 113454 56743 113454 57157 113455 56743 113455 57202 113455 57202 113456 56743 113456 56847 113456 57202 113457 56847 113457 56744 113457 56744 113458 56847 113458 56846 113458 56744 113459 56846 113459 56745 113459 56745 113460 56846 113460 56746 113460 56745 113461 56746 113461 57159 113461 57159 113462 56746 113462 56747 113462 57159 113463 56747 113463 56749 113463 56758 113464 57190 113464 56844 113464 56844 113465 57190 113465 56749 113465 56844 113466 56749 113466 56748 113466 56748 113467 56749 113467 56747 113467 56885 113468 56759 113468 56750 113468 56750 113469 56759 113469 56751 113469 56750 113470 56751 113470 56752 113470 56752 113471 56751 113471 56754 113471 56752 113472 56754 113472 56753 113472 56753 113473 56754 113473 57162 113473 56753 113474 57162 113474 56756 113474 56756 113475 57162 113475 56755 113475 56756 113476 56755 113476 56843 113476 56843 113477 56755 113477 56757 113477 56843 113478 56757 113478 56758 113478 56758 113479 56757 113479 57161 113479 56758 113480 57161 113480 57190 113480 56759 113481 56885 113481 56760 113481 56760 113482 56885 113482 56761 113482 56760 113483 56761 113483 56762 113483 56762 113484 56761 113484 56953 113484 56762 113485 56953 113485 57277 113485 57277 113486 56953 113486 56763 113486 57277 113487 56763 113487 57276 113487 57276 113488 56763 113488 56764 113488 57276 113489 56764 113489 57217 113489 57217 113490 56764 113490 56765 113490 57217 113491 56765 113491 56766 113491 56766 113492 56765 113492 56767 113492 56766 113493 56767 113493 56768 113493 56768 113494 56767 113494 56949 113494 56768 113495 56949 113495 57271 113495 57271 113496 56949 113496 56769 113496 57271 113497 56769 113497 57264 113497 56945 113498 56770 113498 56771 113498 56771 113499 56770 113499 57264 113499 56771 113500 57264 113500 56947 113500 56947 113501 57264 113501 56769 113501 56944 113502 56772 113502 56942 113502 56942 113503 56772 113503 57245 113503 56942 113504 57245 113504 56773 113504 56773 113505 57245 113505 56774 113505 56773 113506 56774 113506 56941 113506 56941 113507 56774 113507 56775 113507 56941 113508 56775 113508 56939 113508 56939 113509 56775 113509 57252 113509 56939 113510 57252 113510 56776 113510 56776 113511 57252 113511 56777 113511 56776 113512 56777 113512 56945 113512 56945 113513 56777 113513 56778 113513 56945 113514 56778 113514 56770 113514 56772 113515 56944 113515 56779 113515 56779 113516 56944 113516 56988 113516 56784 113517 56780 113517 56879 113517 56784 113518 56879 113518 56782 113518 56782 113519 56879 113519 56781 113519 56782 113520 56781 113520 56785 113520 56785 113521 56781 113521 56783 113521 56785 113522 56783 113522 56790 113522 56790 113523 56783 113523 56740 113523 56790 113524 56740 113524 56791 113524 56784 113525 56782 113525 56813 113525 56782 113526 56785 113526 56804 113526 56785 113527 56790 113527 56786 113527 56787 113528 56792 113528 56735 113528 56735 113529 56792 113529 56788 113529 56735 113530 56788 113530 56789 113530 56789 113531 56788 113531 56786 113531 56789 113532 56786 113532 56734 113532 56734 113533 56786 113533 56790 113533 56734 113534 56790 113534 56791 113534 56787 113535 56737 113535 56792 113535 56792 113536 56737 113536 56793 113536 56792 113537 56793 113537 56807 113537 56807 113538 56793 113538 56732 113538 56807 113539 56732 113539 56794 113539 56794 113540 56732 113540 56733 113540 56794 113541 56733 113541 56796 113541 56727 113542 56795 113542 56800 113542 56733 113543 56797 113543 56796 113543 56796 113544 56797 113544 56731 113544 56796 113545 56731 113545 56811 113545 56811 113546 56731 113546 56730 113546 56811 113547 56730 113547 56798 113547 56798 113548 56730 113548 56799 113548 56798 113549 56799 113549 56800 113549 56800 113550 56799 113550 56801 113550 56800 113551 56801 113551 56727 113551 56727 113552 56802 113552 56795 113552 56795 113553 56802 113553 56803 113553 56795 113554 56803 113554 56812 113554 56785 113555 56786 113555 56804 113555 56804 113556 56786 113556 56788 113556 56804 113557 56788 113557 56814 113557 56814 113558 56788 113558 56792 113558 56814 113559 56792 113559 56805 113559 56805 113560 56792 113560 56807 113560 56805 113561 56807 113561 56806 113561 56806 113562 56807 113562 56794 113562 56806 113563 56794 113563 56808 113563 56808 113564 56794 113564 56796 113564 56808 113565 56796 113565 56809 113565 56809 113566 56796 113566 56811 113566 56809 113567 56811 113567 56810 113567 56810 113568 56811 113568 56798 113568 56810 113569 56798 113569 56819 113569 56819 113570 56798 113570 56800 113570 56819 113571 56800 113571 56820 113571 56820 113572 56800 113572 56795 113572 56820 113573 56795 113573 56822 113573 56822 113574 56795 113574 56812 113574 56822 113575 56812 113575 56882 113575 56782 113576 56804 113576 56813 113576 56813 113577 56804 113577 56814 113577 56813 113578 56814 113578 56815 113578 56815 113579 56814 113579 56805 113579 56815 113580 56805 113580 56816 113580 56816 113581 56805 113581 56806 113581 56816 113582 56806 113582 56826 113582 56826 113583 56806 113583 56808 113583 56826 113584 56808 113584 56827 113584 56827 113585 56808 113585 56809 113585 56827 113586 56809 113586 56817 113586 56817 113587 56809 113587 56810 113587 56817 113588 56810 113588 56818 113588 56818 113589 56810 113589 56819 113589 56818 113590 56819 113590 56829 113590 56829 113591 56819 113591 56820 113591 56829 113592 56820 113592 56821 113592 56821 113593 56820 113593 56822 113593 56821 113594 56822 113594 56833 113594 56833 113595 56822 113595 56882 113595 56833 113596 56882 113596 56834 113596 56784 113597 56813 113597 56823 113597 56823 113598 56813 113598 56815 113598 56823 113599 56815 113599 56824 113599 56824 113600 56815 113600 56816 113600 56824 113601 56816 113601 56825 113601 56825 113602 56816 113602 56826 113602 56825 113603 56826 113603 56643 113603 56643 113604 56826 113604 56827 113604 56643 113605 56827 113605 56645 113605 56645 113606 56827 113606 56817 113606 56645 113607 56817 113607 56828 113607 56828 113608 56817 113608 56818 113608 56828 113609 56818 113609 56632 113609 56632 113610 56818 113610 56829 113610 56632 113611 56829 113611 56830 113611 56830 113612 56829 113612 56821 113612 56830 113613 56821 113613 56831 113613 56831 113614 56821 113614 56833 113614 56831 113615 56833 113615 56832 113615 56832 113616 56833 113616 56834 113616 56832 113617 56834 113617 56835 113617 56622 113618 56836 113618 56866 113618 56836 113619 56838 113619 56837 113619 56838 113620 56839 113620 56842 113620 56756 113621 56840 113621 56753 113621 56753 113622 56840 113622 56841 113622 56753 113623 56841 113623 56752 113623 56752 113624 56841 113624 56842 113624 56752 113625 56842 113625 56750 113625 56750 113626 56842 113626 56839 113626 56750 113627 56839 113627 56885 113627 56756 113628 56843 113628 56840 113628 56840 113629 56843 113629 56758 113629 56840 113630 56758 113630 56849 113630 56849 113631 56758 113631 56844 113631 56849 113632 56844 113632 56851 113632 56851 113633 56844 113633 56748 113633 56851 113634 56748 113634 56852 113634 56742 113635 56857 113635 56845 113635 56748 113636 56747 113636 56852 113636 56852 113637 56747 113637 56746 113637 56852 113638 56746 113638 56853 113638 56853 113639 56746 113639 56846 113639 56853 113640 56846 113640 56855 113640 56855 113641 56846 113641 56847 113641 56855 113642 56847 113642 56845 113642 56845 113643 56847 113643 56743 113643 56845 113644 56743 113644 56742 113644 56742 113645 56741 113645 56857 113645 56857 113646 56741 113646 56740 113646 56857 113647 56740 113647 56783 113647 56838 113648 56842 113648 56837 113648 56837 113649 56842 113649 56841 113649 56837 113650 56841 113650 56858 113650 56858 113651 56841 113651 56840 113651 56858 113652 56840 113652 56848 113652 56848 113653 56840 113653 56849 113653 56848 113654 56849 113654 56850 113654 56850 113655 56849 113655 56851 113655 56850 113656 56851 113656 56860 113656 56860 113657 56851 113657 56852 113657 56860 113658 56852 113658 56862 113658 56862 113659 56852 113659 56853 113659 56862 113660 56853 113660 56854 113660 56854 113661 56853 113661 56855 113661 56854 113662 56855 113662 56864 113662 56864 113663 56855 113663 56845 113663 56864 113664 56845 113664 56856 113664 56856 113665 56845 113665 56857 113665 56856 113666 56857 113666 56865 113666 56865 113667 56857 113667 56783 113667 56865 113668 56783 113668 56781 113668 56836 113669 56837 113669 56866 113669 56866 113670 56837 113670 56858 113670 56866 113671 56858 113671 56867 113671 56867 113672 56858 113672 56848 113672 56867 113673 56848 113673 56859 113673 56859 113674 56848 113674 56850 113674 56859 113675 56850 113675 56869 113675 56869 113676 56850 113676 56860 113676 56869 113677 56860 113677 56861 113677 56861 113678 56860 113678 56862 113678 56861 113679 56862 113679 56872 113679 56872 113680 56862 113680 56854 113680 56872 113681 56854 113681 56863 113681 56863 113682 56854 113682 56864 113682 56863 113683 56864 113683 56875 113683 56875 113684 56864 113684 56856 113684 56875 113685 56856 113685 56877 113685 56877 113686 56856 113686 56865 113686 56877 113687 56865 113687 56878 113687 56878 113688 56865 113688 56781 113688 56878 113689 56781 113689 56879 113689 56622 113690 56866 113690 56633 113690 56633 113691 56866 113691 56867 113691 56633 113692 56867 113692 56868 113692 56868 113693 56867 113693 56859 113693 56868 113694 56859 113694 56628 113694 56628 113695 56859 113695 56869 113695 56628 113696 56869 113696 56870 113696 56870 113697 56869 113697 56861 113697 56870 113698 56861 113698 56871 113698 56871 113699 56861 113699 56872 113699 56871 113700 56872 113700 56873 113700 56873 113701 56872 113701 56863 113701 56873 113702 56863 113702 56874 113702 56874 113703 56863 113703 56875 113703 56874 113704 56875 113704 56876 113704 56876 113705 56875 113705 56877 113705 56876 113706 56877 113706 56651 113706 56651 113707 56877 113707 56878 113707 56651 113708 56878 113708 56624 113708 56624 113709 56878 113709 56879 113709 56624 113710 56879 113710 56780 113710 56649 113711 56835 113711 56834 113711 56649 113712 56834 113712 56880 113712 56880 113713 56834 113713 56882 113713 56880 113714 56882 113714 56881 113714 56881 113715 56882 113715 56812 113715 56881 113716 56812 113716 56883 113716 56883 113717 56812 113717 56803 113717 56883 113718 56803 113718 56718 113718 56622 113719 56635 113719 56983 113719 56622 113720 56983 113720 56836 113720 56836 113721 56983 113721 56884 113721 56836 113722 56884 113722 56838 113722 56838 113723 56884 113723 56965 113723 56838 113724 56965 113724 56839 113724 56839 113725 56965 113725 56761 113725 56839 113726 56761 113726 56885 113726 56649 113727 56880 113727 56886 113727 56880 113728 56881 113728 56887 113728 56881 113729 56883 113729 56888 113729 56722 113730 56889 113730 56721 113730 56721 113731 56889 113731 56890 113731 56721 113732 56890 113732 56891 113732 56891 113733 56890 113733 56888 113733 56891 113734 56888 113734 56892 113734 56892 113735 56888 113735 56883 113735 56892 113736 56883 113736 56718 113736 56722 113737 56893 113737 56889 113737 56889 113738 56893 113738 56716 113738 56889 113739 56716 113739 56907 113739 56907 113740 56716 113740 56895 113740 56907 113741 56895 113741 56894 113741 56894 113742 56895 113742 56896 113742 56894 113743 56896 113743 56909 113743 56897 113744 56912 113744 56901 113744 56896 113745 56715 113745 56909 113745 56909 113746 56715 113746 56898 113746 56909 113747 56898 113747 56910 113747 56910 113748 56898 113748 56899 113748 56910 113749 56899 113749 56900 113749 56900 113750 56899 113750 56713 113750 56900 113751 56713 113751 56901 113751 56901 113752 56713 113752 56902 113752 56901 113753 56902 113753 56897 113753 56897 113754 56903 113754 56912 113754 56912 113755 56903 113755 56904 113755 56912 113756 56904 113756 56987 113756 56881 113757 56888 113757 56887 113757 56887 113758 56888 113758 56890 113758 56887 113759 56890 113759 56905 113759 56905 113760 56890 113760 56889 113760 56905 113761 56889 113761 56906 113761 56906 113762 56889 113762 56907 113762 56906 113763 56907 113763 56916 113763 56916 113764 56907 113764 56894 113764 56916 113765 56894 113765 56919 113765 56919 113766 56894 113766 56909 113766 56919 113767 56909 113767 56908 113767 56908 113768 56909 113768 56910 113768 56908 113769 56910 113769 56920 113769 56920 113770 56910 113770 56900 113770 56920 113771 56900 113771 56911 113771 56911 113772 56900 113772 56901 113772 56911 113773 56901 113773 56923 113773 56923 113774 56901 113774 56912 113774 56923 113775 56912 113775 56925 113775 56925 113776 56912 113776 56987 113776 56925 113777 56987 113777 56913 113777 56880 113778 56887 113778 56886 113778 56886 113779 56887 113779 56905 113779 56886 113780 56905 113780 56914 113780 56914 113781 56905 113781 56906 113781 56914 113782 56906 113782 56915 113782 56915 113783 56906 113783 56916 113783 56915 113784 56916 113784 56917 113784 56917 113785 56916 113785 56919 113785 56917 113786 56919 113786 56918 113786 56918 113787 56919 113787 56908 113787 56918 113788 56908 113788 56921 113788 56921 113789 56908 113789 56920 113789 56921 113790 56920 113790 56931 113790 56931 113791 56920 113791 56911 113791 56931 113792 56911 113792 56922 113792 56922 113793 56911 113793 56923 113793 56922 113794 56923 113794 56924 113794 56924 113795 56923 113795 56925 113795 56924 113796 56925 113796 56926 113796 56926 113797 56925 113797 56913 113797 56926 113798 56913 113798 56986 113798 56649 113799 56886 113799 56927 113799 56927 113800 56886 113800 56914 113800 56927 113801 56914 113801 56641 113801 56641 113802 56914 113802 56915 113802 56641 113803 56915 113803 56928 113803 56928 113804 56915 113804 56917 113804 56928 113805 56917 113805 56929 113805 56929 113806 56917 113806 56918 113806 56929 113807 56918 113807 56930 113807 56930 113808 56918 113808 56921 113808 56930 113809 56921 113809 56640 113809 56640 113810 56921 113810 56931 113810 56640 113811 56931 113811 56932 113811 56932 113812 56931 113812 56922 113812 56932 113813 56922 113813 56933 113813 56933 113814 56922 113814 56924 113814 56933 113815 56924 113815 56934 113815 56934 113816 56924 113816 56926 113816 56934 113817 56926 113817 56935 113817 56935 113818 56926 113818 56986 113818 56935 113819 56986 113819 56984 113819 56971 113820 56937 113820 56936 113820 56937 113821 56990 113821 56955 113821 56990 113822 56938 113822 56943 113822 56939 113823 56957 113823 56941 113823 56941 113824 56957 113824 56940 113824 56941 113825 56940 113825 56773 113825 56773 113826 56940 113826 56943 113826 56773 113827 56943 113827 56942 113827 56942 113828 56943 113828 56938 113828 56942 113829 56938 113829 56944 113829 56939 113830 56776 113830 56957 113830 56957 113831 56776 113831 56945 113831 56957 113832 56945 113832 56946 113832 56946 113833 56945 113833 56771 113833 56946 113834 56771 113834 56960 113834 56960 113835 56771 113835 56947 113835 56960 113836 56947 113836 56948 113836 56763 113837 56954 113837 56952 113837 56947 113838 56769 113838 56948 113838 56948 113839 56769 113839 56949 113839 56948 113840 56949 113840 56950 113840 56950 113841 56949 113841 56767 113841 56950 113842 56767 113842 56951 113842 56951 113843 56767 113843 56765 113843 56951 113844 56765 113844 56952 113844 56952 113845 56765 113845 56764 113845 56952 113846 56764 113846 56763 113846 56763 113847 56953 113847 56954 113847 56954 113848 56953 113848 56761 113848 56954 113849 56761 113849 56965 113849 56990 113850 56943 113850 56955 113850 56955 113851 56943 113851 56940 113851 56955 113852 56940 113852 56956 113852 56956 113853 56940 113853 56957 113853 56956 113854 56957 113854 56958 113854 56958 113855 56957 113855 56946 113855 56958 113856 56946 113856 56959 113856 56959 113857 56946 113857 56960 113857 56959 113858 56960 113858 56967 113858 56967 113859 56960 113859 56948 113859 56967 113860 56948 113860 56968 113860 56968 113861 56948 113861 56950 113861 56968 113862 56950 113862 56961 113862 56961 113863 56950 113863 56951 113863 56961 113864 56951 113864 56962 113864 56962 113865 56951 113865 56952 113865 56962 113866 56952 113866 56963 113866 56963 113867 56952 113867 56954 113867 56963 113868 56954 113868 56964 113868 56964 113869 56954 113869 56965 113869 56964 113870 56965 113870 56884 113870 56937 113871 56955 113871 56936 113871 56936 113872 56955 113872 56956 113872 56936 113873 56956 113873 56973 113873 56973 113874 56956 113874 56958 113874 56973 113875 56958 113875 56974 113875 56974 113876 56958 113876 56959 113876 56974 113877 56959 113877 56966 113877 56966 113878 56959 113878 56967 113878 56966 113879 56967 113879 56977 113879 56977 113880 56967 113880 56968 113880 56977 113881 56968 113881 56969 113881 56969 113882 56968 113882 56961 113882 56969 113883 56961 113883 56978 113883 56978 113884 56961 113884 56962 113884 56978 113885 56962 113885 56970 113885 56970 113886 56962 113886 56963 113886 56970 113887 56963 113887 56981 113887 56981 113888 56963 113888 56964 113888 56981 113889 56964 113889 56982 113889 56982 113890 56964 113890 56884 113890 56982 113891 56884 113891 56983 113891 56971 113892 56936 113892 56972 113892 56972 113893 56936 113893 56973 113893 56972 113894 56973 113894 56661 113894 56661 113895 56973 113895 56974 113895 56661 113896 56974 113896 56629 113896 56629 113897 56974 113897 56966 113897 56629 113898 56966 113898 56975 113898 56975 113899 56966 113899 56977 113899 56975 113900 56977 113900 56976 113900 56976 113901 56977 113901 56969 113901 56976 113902 56969 113902 56639 113902 56639 113903 56969 113903 56978 113903 56639 113904 56978 113904 56979 113904 56979 113905 56978 113905 56970 113905 56979 113906 56970 113906 56980 113906 56980 113907 56970 113907 56981 113907 56980 113908 56981 113908 56637 113908 56637 113909 56981 113909 56982 113909 56637 113910 56982 113910 56636 113910 56636 113911 56982 113911 56983 113911 56636 113912 56983 113912 56635 113912 56630 113913 56984 113913 56986 113913 56630 113914 56986 113914 56985 113914 56985 113915 56986 113915 56913 113915 56985 113916 56913 113916 56989 113916 56989 113917 56913 113917 56987 113917 56989 113918 56987 113918 56991 113918 56991 113919 56987 113919 56904 113919 56991 113920 56904 113920 56988 113920 56971 113921 56630 113921 56985 113921 56971 113922 56985 113922 56937 113922 56937 113923 56985 113923 56989 113923 56937 113924 56989 113924 56990 113924 56990 113925 56989 113925 56991 113925 56990 113926 56991 113926 56938 113926 56938 113927 56991 113927 56988 113927 56938 113928 56988 113928 56944 113928 56719 113929 56992 113929 56993 113929 56993 113930 56992 113930 57101 113930 56993 113931 57101 113931 56994 113931 56994 113932 57101 113932 56995 113932 56994 113933 56995 113933 56996 113933 56996 113934 56995 113934 57097 113934 56996 113935 57097 113935 56998 113935 56998 113936 57097 113936 56997 113936 56998 113937 56997 113937 57018 113937 57018 113938 56997 113938 57095 113938 57018 113939 57095 113939 57005 113939 57005 113940 57095 113940 56999 113940 57005 113941 56999 113941 57004 113941 57004 113942 56999 113942 57093 113942 57004 113943 57093 113943 56690 113943 56690 113944 57093 113944 56687 113944 57000 113945 56714 113945 57024 113945 57001 113946 57063 113946 57061 113946 56723 113947 57034 113947 57041 113947 57035 113948 57002 113948 57028 113948 57029 113949 56720 113949 57003 113949 57014 113950 57013 113950 57019 113950 56690 113951 56691 113951 57004 113951 57004 113952 56691 113952 57033 113952 57004 113953 57033 113953 57005 113953 57005 113954 57033 113954 57006 113954 57007 113955 57012 113955 57066 113955 57066 113956 57012 113956 57008 113956 57066 113957 57008 113957 57065 113957 57065 113958 57008 113958 57009 113958 57065 113959 57009 113959 57064 113959 57064 113960 57009 113960 57010 113960 57064 113961 57010 113961 57011 113961 57011 113962 57010 113962 57026 113962 57011 113963 57026 113963 57024 113963 57012 113964 57013 113964 57008 113964 57008 113965 57013 113965 57014 113965 57008 113966 57014 113966 57009 113966 57009 113967 57014 113967 57015 113967 57009 113968 57015 113968 57010 113968 57010 113969 57015 113969 57016 113969 57010 113970 57016 113970 57026 113970 57026 113971 57016 113971 57022 113971 57003 113972 56994 113972 57017 113972 57017 113973 56994 113973 56996 113973 57017 113974 56996 113974 57030 113974 57030 113975 56996 113975 56998 113975 57030 113976 56998 113976 57006 113976 57006 113977 56998 113977 57018 113977 57006 113978 57018 113978 57005 113978 57019 113979 57137 113979 57014 113979 57014 113980 57137 113980 57020 113980 57014 113981 57020 113981 57015 113981 57015 113982 57020 113982 57138 113982 57015 113983 57138 113983 57016 113983 57016 113984 57138 113984 57021 113984 57016 113985 57021 113985 57022 113985 57022 113986 57021 113986 57023 113986 57022 113987 57023 113987 57141 113987 57024 113988 57026 113988 57025 113988 57025 113989 57026 113989 57022 113989 57025 113990 57022 113990 57027 113990 57027 113991 57022 113991 57141 113991 57027 113992 57141 113992 57070 113992 56720 113993 56719 113993 57003 113993 57003 113994 56719 113994 56993 113994 57003 113995 56993 113995 56994 113995 57002 113996 57029 113996 57028 113996 57028 113997 57029 113997 57003 113997 57028 113998 57003 113998 57037 113998 57037 113999 57003 113999 57017 113999 57037 114000 57017 114000 57039 114000 57039 114001 57017 114001 57030 114001 57039 114002 57030 114002 57031 114002 57031 114003 57030 114003 57006 114003 57031 114004 57006 114004 57032 114004 57032 114005 57006 114005 57033 114005 57032 114006 57033 114006 56692 114006 56692 114007 57033 114007 56691 114007 57034 114008 57035 114008 57041 114008 57041 114009 57035 114009 57028 114009 57041 114010 57028 114010 57036 114010 57036 114011 57028 114011 57037 114011 57036 114012 57037 114012 57038 114012 57038 114013 57037 114013 57039 114013 57038 114014 57039 114014 57042 114014 57042 114015 57039 114015 57031 114015 57042 114016 57031 114016 57043 114016 57043 114017 57031 114017 57032 114017 57043 114018 57032 114018 57040 114018 57040 114019 57032 114019 56692 114019 56717 114020 56723 114020 57052 114020 57052 114021 56723 114021 57041 114021 57052 114022 57041 114022 57051 114022 57051 114023 57041 114023 57036 114023 57051 114024 57036 114024 57050 114024 57050 114025 57036 114025 57038 114025 57050 114026 57038 114026 57047 114026 57047 114027 57038 114027 57042 114027 57047 114028 57042 114028 57045 114028 57045 114029 57042 114029 57043 114029 57045 114030 57043 114030 57044 114030 57044 114031 57043 114031 57040 114031 57044 114032 57046 114032 57045 114032 57045 114033 57046 114033 57048 114033 57045 114034 57048 114034 57047 114034 57047 114035 57048 114035 57056 114035 57047 114036 57056 114036 57050 114036 57050 114037 57056 114037 57049 114037 57050 114038 57049 114038 57051 114038 57051 114039 57049 114039 57060 114039 57051 114040 57060 114040 57052 114040 57052 114041 57060 114041 57053 114041 57052 114042 57053 114042 56717 114042 56717 114043 57053 114043 57062 114043 57046 114044 57054 114044 57048 114044 57048 114045 57054 114045 57055 114045 57048 114046 57055 114046 57056 114046 57056 114047 57055 114047 57057 114047 57056 114048 57057 114048 57049 114048 57049 114049 57057 114049 57058 114049 57049 114050 57058 114050 57060 114050 57060 114051 57058 114051 57059 114051 57060 114052 57059 114052 57053 114052 57053 114053 57059 114053 57061 114053 57053 114054 57061 114054 57062 114054 57062 114055 57061 114055 57063 114055 56714 114056 57001 114056 57024 114056 57024 114057 57001 114057 57061 114057 57024 114058 57061 114058 57011 114058 57011 114059 57061 114059 57059 114059 57011 114060 57059 114060 57064 114060 57064 114061 57059 114061 57058 114061 57064 114062 57058 114062 57065 114062 57065 114063 57058 114063 57057 114063 57065 114064 57057 114064 57066 114064 57066 114065 57057 114065 57055 114065 57066 114066 57055 114066 57007 114066 57007 114067 57055 114067 57054 114067 57000 114068 57024 114068 57067 114068 57067 114069 57024 114069 57025 114069 57067 114070 57025 114070 57068 114070 57068 114071 57025 114071 57027 114071 57068 114072 57027 114072 57069 114072 57069 114073 57027 114073 57070 114073 57069 114074 57070 114074 56712 114074 56728 114075 56729 114075 57098 114075 57130 114076 57071 114076 57128 114076 57109 114077 57072 114077 57111 114077 57105 114078 57102 114078 57083 114078 57073 114079 56696 114079 56687 114079 56676 114080 56671 114080 57074 114080 57074 114081 56671 114081 57075 114081 57074 114082 57075 114082 57144 114082 57144 114083 57075 114083 57087 114083 57135 114084 57078 114084 57076 114084 57076 114085 57078 114085 57079 114085 57076 114086 57079 114086 57133 114086 57133 114087 57079 114087 57080 114087 57133 114088 57080 114088 57131 114088 57131 114089 57080 114089 57082 114089 57131 114090 57082 114090 57077 114090 57077 114091 57082 114091 57099 114091 57077 114092 57099 114092 57098 114092 57078 114093 56696 114093 57079 114093 57079 114094 56696 114094 57073 114094 57079 114095 57073 114095 57080 114095 57080 114096 57073 114096 57081 114096 57080 114097 57081 114097 57082 114097 57082 114098 57081 114098 57094 114098 57082 114099 57094 114099 57099 114099 57099 114100 57094 114100 57096 114100 57083 114101 57149 114101 57084 114101 57084 114102 57149 114102 57147 114102 57084 114103 57147 114103 57085 114103 57085 114104 57147 114104 57086 114104 57085 114105 57086 114105 57087 114105 57087 114106 57086 114106 57146 114106 57087 114107 57146 114107 57144 114107 57088 114108 57089 114108 57108 114108 57108 114109 57089 114109 57090 114109 57108 114110 57090 114110 57107 114110 57107 114111 57090 114111 57116 114111 57107 114112 57116 114112 57091 114112 57091 114113 57116 114113 57114 114113 57091 114114 57114 114114 57106 114114 57106 114115 57114 114115 57092 114115 57106 114116 57092 114116 57104 114116 57104 114117 57092 114117 57111 114117 56687 114118 57093 114118 57073 114118 57073 114119 57093 114119 56999 114119 57073 114120 56999 114120 57081 114120 57081 114121 56999 114121 57095 114121 57081 114122 57095 114122 57094 114122 57094 114123 57095 114123 56997 114123 57094 114124 56997 114124 57096 114124 57096 114125 56997 114125 57097 114125 57096 114126 57097 114126 56995 114126 57098 114127 57099 114127 57136 114127 57136 114128 57099 114128 57096 114128 57136 114129 57096 114129 57100 114129 57100 114130 57096 114130 56995 114130 57100 114131 56995 114131 57101 114131 57102 114132 57103 114132 57083 114132 57083 114133 57103 114133 57150 114133 57083 114134 57150 114134 57149 114134 56736 114135 57105 114135 57104 114135 57104 114136 57105 114136 57083 114136 57104 114137 57083 114137 57106 114137 57106 114138 57083 114138 57084 114138 57106 114139 57084 114139 57091 114139 57091 114140 57084 114140 57085 114140 57091 114141 57085 114141 57107 114141 57107 114142 57085 114142 57087 114142 57107 114143 57087 114143 57108 114143 57108 114144 57087 114144 57075 114144 57108 114145 57075 114145 57088 114145 57088 114146 57075 114146 56671 114146 57111 114147 57072 114147 57104 114147 57104 114148 57072 114148 56738 114148 57104 114149 56738 114149 56736 114149 57122 114150 57109 114150 57110 114150 57110 114151 57109 114151 57111 114151 57110 114152 57111 114152 57112 114152 57112 114153 57111 114153 57092 114153 57112 114154 57092 114154 57113 114154 57113 114155 57092 114155 57114 114155 57113 114156 57114 114156 57115 114156 57115 114157 57114 114157 57116 114157 57115 114158 57116 114158 57119 114158 57119 114159 57116 114159 57090 114159 57119 114160 57090 114160 57117 114160 57117 114161 57090 114161 57089 114161 57117 114162 57118 114162 57119 114162 57119 114163 57118 114163 57120 114163 57119 114164 57120 114164 57115 114164 57115 114165 57120 114165 57121 114165 57115 114166 57121 114166 57113 114166 57113 114167 57121 114167 57123 114167 57113 114168 57123 114168 57112 114168 57112 114169 57123 114169 57124 114169 57112 114170 57124 114170 57110 114170 57110 114171 57124 114171 57126 114171 57110 114172 57126 114172 57122 114172 57122 114173 57126 114173 57129 114173 57118 114174 56685 114174 57120 114174 57120 114175 56685 114175 57134 114175 57120 114176 57134 114176 57121 114176 57121 114177 57134 114177 57132 114177 57121 114178 57132 114178 57123 114178 57123 114179 57132 114179 57125 114179 57123 114180 57125 114180 57124 114180 57124 114181 57125 114181 57127 114181 57124 114182 57127 114182 57126 114182 57126 114183 57127 114183 57128 114183 57126 114184 57128 114184 57129 114184 57129 114185 57128 114185 57071 114185 56729 114186 57130 114186 57098 114186 57098 114187 57130 114187 57128 114187 57098 114188 57128 114188 57077 114188 57077 114189 57128 114189 57127 114189 57077 114190 57127 114190 57131 114190 57131 114191 57127 114191 57125 114191 57131 114192 57125 114192 57133 114192 57133 114193 57125 114193 57132 114193 57133 114194 57132 114194 57076 114194 57076 114195 57132 114195 57134 114195 57076 114196 57134 114196 57135 114196 57135 114197 57134 114197 56685 114197 56728 114198 57098 114198 56726 114198 56726 114199 57098 114199 57136 114199 56726 114200 57136 114200 56725 114200 56725 114201 57136 114201 57100 114201 56725 114202 57100 114202 56724 114202 56724 114203 57100 114203 57101 114203 56724 114204 57101 114204 56992 114204 57019 114205 56703 114205 57137 114205 57137 114206 56703 114206 57151 114206 57137 114207 57151 114207 57020 114207 57020 114208 57151 114208 57138 114208 57138 114209 57151 114209 57139 114209 57138 114210 57139 114210 57021 114210 57021 114211 57139 114211 57023 114211 57023 114212 57139 114212 57140 114212 57023 114213 57140 114213 57141 114213 57141 114214 57140 114214 57070 114214 57070 114215 57140 114215 56779 114215 57070 114216 56779 114216 56712 114216 56678 114217 56676 114217 57166 114217 57166 114218 56676 114218 57074 114218 57166 114219 57074 114219 57142 114219 57142 114220 57074 114220 57144 114220 57142 114221 57144 114221 57143 114221 57143 114222 57144 114222 57146 114222 57143 114223 57146 114223 57145 114223 57145 114224 57146 114224 57086 114224 57145 114225 57086 114225 57214 114225 57214 114226 57086 114226 57147 114226 57214 114227 57147 114227 57215 114227 57215 114228 57147 114228 57149 114228 57215 114229 57149 114229 57148 114229 57148 114230 57149 114230 57150 114230 57148 114231 57150 114231 56739 114231 56739 114232 57150 114232 57103 114232 56701 114233 57219 114233 56703 114233 56703 114234 57219 114234 57151 114234 57219 114235 57221 114235 57151 114235 57151 114236 57221 114236 57152 114236 57151 114237 57152 114237 57139 114237 57152 114238 57153 114238 57139 114238 57139 114239 57153 114239 57155 114239 57139 114240 57155 114240 57140 114240 56772 114241 56779 114241 57154 114241 57154 114242 56779 114242 57140 114242 57154 114243 57140 114243 57247 114243 57247 114244 57140 114244 57155 114244 57156 114245 57157 114245 57158 114245 57202 114246 56744 114246 57197 114246 56745 114247 57159 114247 57160 114247 57161 114248 56757 114248 57181 114248 56755 114249 57162 114249 57176 114249 56754 114250 56751 114250 57172 114250 57163 114251 56680 114251 56678 114251 57288 114252 56709 114252 57165 114252 57165 114253 56709 114253 57164 114253 57165 114254 57164 114254 57285 114254 57285 114255 57164 114255 57169 114255 56678 114256 57166 114256 57163 114256 57163 114257 57166 114257 57142 114257 57163 114258 57142 114258 57167 114258 57167 114259 57142 114259 57143 114259 57167 114260 57143 114260 57211 114260 57211 114261 57143 114261 57145 114261 57211 114262 57145 114262 57209 114262 57172 114263 57280 114263 57168 114263 57168 114264 57280 114264 57282 114264 57168 114265 57282 114265 57173 114265 57173 114266 57282 114266 57283 114266 57173 114267 57283 114267 57169 114267 57169 114268 57283 114268 57170 114268 57169 114269 57170 114269 57285 114269 56751 114270 56759 114270 57172 114270 57172 114271 56759 114271 57171 114271 57172 114272 57171 114272 57280 114272 57162 114273 56754 114273 57176 114273 57176 114274 56754 114274 57172 114274 57176 114275 57172 114275 57177 114275 57177 114276 57172 114276 57168 114276 57177 114277 57168 114277 57179 114277 57179 114278 57168 114278 57173 114278 57179 114279 57173 114279 57174 114279 57174 114280 57173 114280 57169 114280 57174 114281 57169 114281 57175 114281 57175 114282 57169 114282 57164 114282 57175 114283 57164 114283 56707 114283 56707 114284 57164 114284 56709 114284 56757 114285 56755 114285 57181 114285 57181 114286 56755 114286 57176 114286 57181 114287 57176 114287 57183 114287 57183 114288 57176 114288 57177 114288 57183 114289 57177 114289 57178 114289 57178 114290 57177 114290 57179 114290 57178 114291 57179 114291 57185 114291 57185 114292 57179 114292 57174 114292 57185 114293 57174 114293 57180 114293 57180 114294 57174 114294 57175 114294 57180 114295 57175 114295 56706 114295 56706 114296 57175 114296 56707 114296 57190 114297 57161 114297 57189 114297 57189 114298 57161 114298 57181 114298 57189 114299 57181 114299 57182 114299 57182 114300 57181 114300 57183 114300 57182 114301 57183 114301 57188 114301 57188 114302 57183 114302 57178 114302 57188 114303 57178 114303 57184 114303 57184 114304 57178 114304 57185 114304 57184 114305 57185 114305 57186 114305 57186 114306 57185 114306 57180 114306 57186 114307 57180 114307 56693 114307 56693 114308 57180 114308 56706 114308 56693 114309 56694 114309 57186 114309 57186 114310 56694 114310 57192 114310 57186 114311 57192 114311 57184 114311 57184 114312 57192 114312 57187 114312 57184 114313 57187 114313 57188 114313 57188 114314 57187 114314 57194 114314 57188 114315 57194 114315 57182 114315 57182 114316 57194 114316 57195 114316 57182 114317 57195 114317 57189 114317 57189 114318 57195 114318 57191 114318 57189 114319 57191 114319 57190 114319 57190 114320 57191 114320 56749 114320 56694 114321 57201 114321 57192 114321 57192 114322 57201 114322 57193 114322 57192 114323 57193 114323 57187 114323 57187 114324 57193 114324 57200 114324 57187 114325 57200 114325 57194 114325 57194 114326 57200 114326 57199 114326 57194 114327 57199 114327 57195 114327 57195 114328 57199 114328 57196 114328 57195 114329 57196 114329 57191 114329 57191 114330 57196 114330 57160 114330 57191 114331 57160 114331 56749 114331 56749 114332 57160 114332 57159 114332 56744 114333 56745 114333 57197 114333 57197 114334 56745 114334 57160 114334 57197 114335 57160 114335 57198 114335 57198 114336 57160 114336 57196 114336 57198 114337 57196 114337 57204 114337 57204 114338 57196 114338 57199 114338 57204 114339 57199 114339 57205 114339 57205 114340 57199 114340 57200 114340 57205 114341 57200 114341 57207 114341 57207 114342 57200 114342 57193 114342 57207 114343 57193 114343 56695 114343 56695 114344 57193 114344 57201 114344 57157 114345 57202 114345 57158 114345 57158 114346 57202 114346 57197 114346 57158 114347 57197 114347 57210 114347 57210 114348 57197 114348 57198 114348 57210 114349 57198 114349 57212 114349 57212 114350 57198 114350 57204 114350 57212 114351 57204 114351 57203 114351 57203 114352 57204 114352 57205 114352 57203 114353 57205 114353 57213 114353 57213 114354 57205 114354 57207 114354 57213 114355 57207 114355 57206 114355 57206 114356 57207 114356 56695 114356 57216 114357 57156 114357 57208 114357 57208 114358 57156 114358 57158 114358 57208 114359 57158 114359 57209 114359 57209 114360 57158 114360 57210 114360 57209 114361 57210 114361 57211 114361 57211 114362 57210 114362 57212 114362 57211 114363 57212 114363 57167 114363 57167 114364 57212 114364 57203 114364 57167 114365 57203 114365 57163 114365 57163 114366 57203 114366 57213 114366 57163 114367 57213 114367 56680 114367 56680 114368 57213 114368 57206 114368 57145 114369 57214 114369 57209 114369 57209 114370 57214 114370 57215 114370 57209 114371 57215 114371 57208 114371 57208 114372 57215 114372 57148 114372 57208 114373 57148 114373 57216 114373 57216 114374 57148 114374 56739 114374 57217 114375 56766 114375 57228 114375 56768 114376 57271 114376 57269 114376 56778 114377 56777 114377 57218 114377 56774 114378 57245 114378 57246 114378 57237 114379 57230 114379 57289 114379 56701 114380 56700 114380 57219 114380 57219 114381 56700 114381 57220 114381 57219 114382 57220 114382 57221 114382 57221 114383 57220 114383 57231 114383 56683 114384 57229 114384 57222 114384 57222 114385 57229 114385 57223 114385 57222 114386 57223 114386 57224 114386 57224 114387 57223 114387 57225 114387 57224 114388 57225 114388 57226 114388 57226 114389 57225 114389 57227 114389 57226 114390 57227 114390 57272 114390 57272 114391 57227 114391 57242 114391 57272 114392 57242 114392 57228 114392 57229 114393 57230 114393 57223 114393 57223 114394 57230 114394 57237 114394 57223 114395 57237 114395 57225 114395 57225 114396 57237 114396 57238 114396 57225 114397 57238 114397 57227 114397 57227 114398 57238 114398 57239 114398 57227 114399 57239 114399 57242 114399 57242 114400 57239 114400 57244 114400 57246 114401 57247 114401 57248 114401 57248 114402 57247 114402 57155 114402 57248 114403 57155 114403 57249 114403 57249 114404 57155 114404 57153 114404 57249 114405 57153 114405 57231 114405 57231 114406 57153 114406 57152 114406 57231 114407 57152 114407 57221 114407 56698 114408 57232 114408 57251 114408 57251 114409 57232 114409 57233 114409 57251 114410 57233 114410 57250 114410 57250 114411 57233 114411 57234 114411 57250 114412 57234 114412 57235 114412 57235 114413 57234 114413 57256 114413 57235 114414 57256 114414 57236 114414 57236 114415 57256 114415 57255 114415 57236 114416 57255 114416 57253 114416 57253 114417 57255 114417 57218 114417 57289 114418 57287 114418 57237 114418 57237 114419 57287 114419 57286 114419 57237 114420 57286 114420 57238 114420 57238 114421 57286 114421 57284 114421 57238 114422 57284 114422 57239 114422 57239 114423 57284 114423 57240 114423 57239 114424 57240 114424 57244 114424 57244 114425 57240 114425 57241 114425 57244 114426 57241 114426 57281 114426 57228 114427 57242 114427 57278 114427 57278 114428 57242 114428 57244 114428 57278 114429 57244 114429 57243 114429 57243 114430 57244 114430 57281 114430 57243 114431 57281 114431 57279 114431 57245 114432 56772 114432 57246 114432 57246 114433 56772 114433 57154 114433 57246 114434 57154 114434 57247 114434 56775 114435 56774 114435 57253 114435 57253 114436 56774 114436 57246 114436 57253 114437 57246 114437 57236 114437 57236 114438 57246 114438 57248 114438 57236 114439 57248 114439 57235 114439 57235 114440 57248 114440 57249 114440 57235 114441 57249 114441 57250 114441 57250 114442 57249 114442 57231 114442 57250 114443 57231 114443 57251 114443 57251 114444 57231 114444 57220 114444 57251 114445 57220 114445 56698 114445 56698 114446 57220 114446 56700 114446 57218 114447 56777 114447 57253 114447 57253 114448 56777 114448 57252 114448 57253 114449 57252 114449 56775 114449 56770 114450 56778 114450 57262 114450 57262 114451 56778 114451 57218 114451 57262 114452 57218 114452 57254 114452 57254 114453 57218 114453 57255 114453 57254 114454 57255 114454 57257 114454 57257 114455 57255 114455 57256 114455 57257 114456 57256 114456 57261 114456 57261 114457 57256 114457 57234 114457 57261 114458 57234 114458 57259 114458 57259 114459 57234 114459 57233 114459 57259 114460 57233 114460 57258 114460 57258 114461 57233 114461 57232 114461 57258 114462 56675 114462 57259 114462 57259 114463 56675 114463 57260 114463 57259 114464 57260 114464 57261 114464 57261 114465 57260 114465 57266 114465 57261 114466 57266 114466 57257 114466 57257 114467 57266 114467 57267 114467 57257 114468 57267 114468 57254 114468 57254 114469 57267 114469 57263 114469 57254 114470 57263 114470 57262 114470 57262 114471 57263 114471 57270 114471 57262 114472 57270 114472 56770 114472 56770 114473 57270 114473 57264 114473 56675 114474 57265 114474 57260 114474 57260 114475 57265 114475 57275 114475 57260 114476 57275 114476 57266 114476 57266 114477 57275 114477 57274 114477 57266 114478 57274 114478 57267 114478 57267 114479 57274 114479 57268 114479 57267 114480 57268 114480 57263 114480 57263 114481 57268 114481 57273 114481 57263 114482 57273 114482 57270 114482 57270 114483 57273 114483 57269 114483 57270 114484 57269 114484 57264 114484 57264 114485 57269 114485 57271 114485 56766 114486 56768 114486 57228 114486 57228 114487 56768 114487 57269 114487 57228 114488 57269 114488 57272 114488 57272 114489 57269 114489 57273 114489 57272 114490 57273 114490 57226 114490 57226 114491 57273 114491 57268 114491 57226 114492 57268 114492 57224 114492 57224 114493 57268 114493 57274 114493 57224 114494 57274 114494 57222 114494 57222 114495 57274 114495 57275 114495 57222 114496 57275 114496 56683 114496 56683 114497 57275 114497 57265 114497 57217 114498 57228 114498 57276 114498 57276 114499 57228 114499 57278 114499 57276 114500 57278 114500 57277 114500 57277 114501 57278 114501 57243 114501 57277 114502 57243 114502 56762 114502 56762 114503 57243 114503 57279 114503 56762 114504 57279 114504 56760 114504 56759 114505 56760 114505 57171 114505 57171 114506 56760 114506 57279 114506 57171 114507 57279 114507 57280 114507 57280 114508 57279 114508 57281 114508 57280 114509 57281 114509 57282 114509 57282 114510 57281 114510 57241 114510 57282 114511 57241 114511 57283 114511 57283 114512 57241 114512 57240 114512 57283 114513 57240 114513 57170 114513 57170 114514 57240 114514 57284 114514 57170 114515 57284 114515 57285 114515 57285 114516 57284 114516 57286 114516 57285 114517 57286 114517 57165 114517 57165 114518 57286 114518 57287 114518 57165 114519 57287 114519 57288 114519 57288 114520 57287 114520 57289 114520 57290 114521 57336 114521 57291 114521 57294 114522 57397 114522 57291 114522 57291 114523 57397 114523 57292 114523 57291 114524 57292 114524 57290 114524 57399 114525 57398 114525 57296 114525 57296 114526 57398 114526 57293 114526 57296 114527 57293 114527 57294 114527 57294 114528 57293 114528 57395 114528 57294 114529 57395 114529 57397 114529 57399 114530 57296 114530 57295 114530 57295 114531 57296 114531 57298 114531 57295 114532 57298 114532 57297 114532 57297 114533 57298 114533 57299 114533 57299 114534 57298 114534 57360 114534 57299 114535 57360 114535 57301 114535 57341 114536 57306 114536 57360 114536 57360 114537 57306 114537 57300 114537 57360 114538 57300 114538 57301 114538 57401 114539 57302 114539 57303 114539 57303 114540 57302 114540 57304 114540 57303 114541 57304 114541 57341 114541 57341 114542 57304 114542 57305 114542 57341 114543 57305 114543 57306 114543 57401 114544 57303 114544 57307 114544 57307 114545 57303 114545 57354 114545 57307 114546 57354 114546 57402 114546 57402 114547 57354 114547 57403 114547 57403 114548 57354 114548 57309 114548 57403 114549 57309 114549 57311 114549 57308 114550 57406 114550 57309 114550 57309 114551 57406 114551 57310 114551 57309 114552 57310 114552 57311 114552 57410 114553 57312 114553 57315 114553 57315 114554 57312 114554 57313 114554 57315 114555 57313 114555 57308 114555 57308 114556 57313 114556 57408 114556 57308 114557 57408 114557 57406 114557 57410 114558 57315 114558 57314 114558 57314 114559 57315 114559 57316 114559 57314 114560 57316 114560 57412 114560 57412 114561 57316 114561 57366 114561 57366 114562 57316 114562 57318 114562 57366 114563 57318 114563 57317 114563 57345 114564 57319 114564 57318 114564 57318 114565 57319 114565 57368 114565 57318 114566 57368 114566 57317 114566 57323 114567 57320 114567 57345 114567 57345 114568 57320 114568 57321 114568 57345 114569 57321 114569 57319 114569 57372 114570 57371 114570 57348 114570 57348 114571 57371 114571 57322 114571 57348 114572 57322 114572 57323 114572 57323 114573 57322 114573 57369 114573 57323 114574 57369 114574 57320 114574 57372 114575 57348 114575 57375 114575 57375 114576 57348 114576 57324 114576 57375 114577 57324 114577 57328 114577 57325 114578 57326 114578 57324 114578 57324 114579 57326 114579 57327 114579 57324 114580 57327 114580 57328 114580 57331 114581 57329 114581 57325 114581 57325 114582 57329 114582 57378 114582 57325 114583 57378 114583 57326 114583 57382 114584 57381 114584 57330 114584 57330 114585 57381 114585 57380 114585 57330 114586 57380 114586 57331 114586 57331 114587 57380 114587 57332 114587 57331 114588 57332 114588 57329 114588 57382 114589 57330 114589 57384 114589 57384 114590 57330 114590 57333 114590 57384 114591 57333 114591 57385 114591 57362 114592 57387 114592 57333 114592 57333 114593 57387 114593 57386 114593 57333 114594 57386 114594 57385 114594 57338 114595 57334 114595 57362 114595 57362 114596 57334 114596 57335 114596 57362 114597 57335 114597 57387 114597 57290 114598 57337 114598 57336 114598 57336 114599 57337 114599 57390 114599 57336 114600 57390 114600 57338 114600 57338 114601 57390 114601 57391 114601 57338 114602 57391 114602 57334 114602 57315 114603 57802 114603 57316 114603 57316 114604 57802 114604 57339 114604 57316 114605 57339 114605 57318 114605 57324 114606 57340 114606 57325 114606 57325 114607 57340 114607 57813 114607 57325 114608 57813 114608 57331 114608 57360 114609 57342 114609 57341 114609 57341 114610 57342 114610 57343 114610 57341 114611 57343 114611 57303 114611 57309 114612 57344 114612 57308 114612 57308 114613 57344 114613 57798 114613 57308 114614 57798 114614 57315 114614 57315 114615 57798 114615 57800 114615 57315 114616 57800 114616 57802 114616 57339 114617 57805 114617 57318 114617 57318 114618 57805 114618 57346 114618 57318 114619 57346 114619 57345 114619 57345 114620 57346 114620 57347 114620 57345 114621 57347 114621 57323 114621 57347 114622 57808 114622 57323 114622 57323 114623 57808 114623 57349 114623 57323 114624 57349 114624 57348 114624 57348 114625 57349 114625 57350 114625 57348 114626 57350 114626 57324 114626 57324 114627 57350 114627 57811 114627 57324 114628 57811 114628 57340 114628 57813 114629 57351 114629 57331 114629 57331 114630 57351 114630 57814 114630 57331 114631 57814 114631 57330 114631 57330 114632 57814 114632 57361 114632 57330 114633 57361 114633 57333 114633 57343 114634 57352 114634 57303 114634 57303 114635 57352 114635 57353 114635 57303 114636 57353 114636 57354 114636 57354 114637 57353 114637 57355 114637 57354 114638 57355 114638 57309 114638 57309 114639 57355 114639 57796 114639 57309 114640 57796 114640 57344 114640 57338 114641 57363 114641 57336 114641 57336 114642 57363 114642 57356 114642 57336 114643 57356 114643 57291 114643 57296 114644 57357 114644 57298 114644 57298 114645 57357 114645 57358 114645 57298 114646 57358 114646 57360 114646 57360 114647 57358 114647 57359 114647 57360 114648 57359 114648 57342 114648 57361 114649 57816 114649 57333 114649 57333 114650 57816 114650 57817 114650 57333 114651 57817 114651 57362 114651 57362 114652 57817 114652 57818 114652 57362 114653 57818 114653 57338 114653 57338 114654 57818 114654 57821 114654 57338 114655 57821 114655 57363 114655 57356 114656 57364 114656 57291 114656 57291 114657 57364 114657 57789 114657 57291 114658 57789 114658 57294 114658 57294 114659 57789 114659 57365 114659 57294 114660 57365 114660 57296 114660 57296 114661 57365 114661 57791 114661 57296 114662 57791 114662 57357 114662 57366 114663 57317 114663 57367 114663 57317 114664 57368 114664 57367 114664 57367 114665 57368 114665 57319 114665 57367 114666 57319 114666 57444 114666 57444 114667 57319 114667 57321 114667 57444 114668 57321 114668 57443 114668 57443 114669 57321 114669 57320 114669 57443 114670 57320 114670 57370 114670 57370 114671 57320 114671 57369 114671 57369 114672 57322 114672 57370 114672 57370 114673 57322 114673 57371 114673 57370 114674 57371 114674 57373 114674 57373 114675 57371 114675 57372 114675 57373 114676 57372 114676 57374 114676 57374 114677 57372 114677 57375 114677 57374 114678 57375 114678 57376 114678 57376 114679 57375 114679 57328 114679 57328 114680 57327 114680 57376 114680 57376 114681 57327 114681 57326 114681 57376 114682 57326 114682 57377 114682 57377 114683 57326 114683 57378 114683 57377 114684 57378 114684 57438 114684 57438 114685 57378 114685 57329 114685 57438 114686 57329 114686 57379 114686 57379 114687 57329 114687 57332 114687 57332 114688 57380 114688 57379 114688 57379 114689 57380 114689 57381 114689 57379 114690 57381 114690 57436 114690 57436 114691 57381 114691 57382 114691 57436 114692 57382 114692 57383 114692 57383 114693 57382 114693 57384 114693 57383 114694 57384 114694 57433 114694 57433 114695 57384 114695 57385 114695 57385 114696 57386 114696 57433 114696 57433 114697 57386 114697 57387 114697 57433 114698 57387 114698 57388 114698 57388 114699 57387 114699 57335 114699 57388 114700 57335 114700 57389 114700 57390 114701 57393 114701 57391 114701 57391 114702 57393 114702 57389 114702 57391 114703 57389 114703 57334 114703 57334 114704 57389 114704 57335 114704 57337 114705 57429 114705 57390 114705 57390 114706 57429 114706 57392 114706 57390 114707 57392 114707 57393 114707 57397 114708 57394 114708 57292 114708 57292 114709 57394 114709 57429 114709 57292 114710 57429 114710 57290 114710 57290 114711 57429 114711 57337 114711 57395 114712 57396 114712 57397 114712 57397 114713 57396 114713 57427 114713 57397 114714 57427 114714 57394 114714 57395 114715 57293 114715 57396 114715 57396 114716 57293 114716 57398 114716 57396 114717 57398 114717 57425 114717 57425 114718 57398 114718 57399 114718 57425 114719 57399 114719 57424 114719 57424 114720 57399 114720 57295 114720 57424 114721 57295 114721 57423 114721 57423 114722 57295 114722 57297 114722 57297 114723 57299 114723 57423 114723 57423 114724 57299 114724 57301 114724 57423 114725 57301 114725 57422 114725 57422 114726 57301 114726 57300 114726 57422 114727 57300 114727 57400 114727 57400 114728 57300 114728 57306 114728 57400 114729 57306 114729 57421 114729 57421 114730 57306 114730 57305 114730 57305 114731 57304 114731 57421 114731 57421 114732 57304 114732 57302 114732 57421 114733 57302 114733 57418 114733 57418 114734 57302 114734 57401 114734 57418 114735 57401 114735 57417 114735 57417 114736 57401 114736 57307 114736 57417 114737 57307 114737 57404 114737 57404 114738 57307 114738 57402 114738 57402 114739 57403 114739 57404 114739 57404 114740 57403 114740 57311 114740 57404 114741 57311 114741 57415 114741 57415 114742 57311 114742 57310 114742 57415 114743 57310 114743 57405 114743 57405 114744 57310 114744 57406 114744 57405 114745 57406 114745 57407 114745 57407 114746 57406 114746 57408 114746 57408 114747 57313 114747 57407 114747 57407 114748 57313 114748 57312 114748 57407 114749 57312 114749 57409 114749 57409 114750 57312 114750 57410 114750 57409 114751 57410 114751 57413 114751 57367 114752 57411 114752 57366 114752 57366 114753 57411 114753 57445 114753 57366 114754 57445 114754 57412 114754 57412 114755 57445 114755 57413 114755 57412 114756 57413 114756 57314 114756 57314 114757 57413 114757 57410 114757 57445 114758 57448 114758 57413 114758 57413 114759 57448 114759 57449 114759 57413 114760 57449 114760 57409 114760 57409 114761 57449 114761 57450 114761 57409 114762 57450 114762 57407 114762 57407 114763 57450 114763 57451 114763 57407 114764 57451 114764 57405 114764 57405 114765 57451 114765 57414 114765 57405 114766 57414 114766 57415 114766 57415 114767 57414 114767 57416 114767 57415 114768 57416 114768 57404 114768 57404 114769 57416 114769 57453 114769 57404 114770 57453 114770 57417 114770 57417 114771 57453 114771 57419 114771 57417 114772 57419 114772 57418 114772 57418 114773 57419 114773 57420 114773 57418 114774 57420 114774 57421 114774 57421 114775 57420 114775 57457 114775 57421 114776 57457 114776 57400 114776 57400 114777 57457 114777 57458 114777 57400 114778 57458 114778 57422 114778 57422 114779 57458 114779 57459 114779 57422 114780 57459 114780 57423 114780 57423 114781 57459 114781 57461 114781 57423 114782 57461 114782 57424 114782 57424 114783 57461 114783 57462 114783 57424 114784 57462 114784 57425 114784 57425 114785 57462 114785 57426 114785 57425 114786 57426 114786 57396 114786 57396 114787 57426 114787 57464 114787 57396 114788 57464 114788 57427 114788 57427 114789 57464 114789 57467 114789 57427 114790 57467 114790 57394 114790 57394 114791 57467 114791 57428 114791 57394 114792 57428 114792 57429 114792 57429 114793 57428 114793 57471 114793 57429 114794 57471 114794 57392 114794 57392 114795 57471 114795 57430 114795 57392 114796 57430 114796 57393 114796 57393 114797 57430 114797 57472 114797 57393 114798 57472 114798 57389 114798 57389 114799 57472 114799 57431 114799 57389 114800 57431 114800 57388 114800 57388 114801 57431 114801 57432 114801 57388 114802 57432 114802 57433 114802 57433 114803 57432 114803 57434 114803 57433 114804 57434 114804 57383 114804 57383 114805 57434 114805 57435 114805 57383 114806 57435 114806 57436 114806 57436 114807 57435 114807 57476 114807 57436 114808 57476 114808 57379 114808 57379 114809 57476 114809 57437 114809 57379 114810 57437 114810 57438 114810 57438 114811 57437 114811 57478 114811 57438 114812 57478 114812 57377 114812 57377 114813 57478 114813 57439 114813 57377 114814 57439 114814 57376 114814 57376 114815 57439 114815 57440 114815 57376 114816 57440 114816 57374 114816 57374 114817 57440 114817 57441 114817 57374 114818 57441 114818 57373 114818 57373 114819 57441 114819 57442 114819 57373 114820 57442 114820 57370 114820 57370 114821 57442 114821 57481 114821 57370 114822 57481 114822 57443 114822 57443 114823 57481 114823 57482 114823 57443 114824 57482 114824 57444 114824 57444 114825 57482 114825 57483 114825 57444 114826 57483 114826 57367 114826 57367 114827 57483 114827 57486 114827 57367 114828 57486 114828 57411 114828 57411 114829 57486 114829 57446 114829 57411 114830 57446 114830 57445 114830 57445 114831 57446 114831 57448 114831 57446 114832 57447 114832 57448 114832 57448 114833 57447 114833 57489 114833 57448 114834 57489 114834 57449 114834 57449 114835 57489 114835 57490 114835 57449 114836 57490 114836 57450 114836 57450 114837 57490 114837 57492 114837 57450 114838 57492 114838 57451 114838 57451 114839 57492 114839 57493 114839 57451 114840 57493 114840 57414 114840 57414 114841 57493 114841 57452 114841 57414 114842 57452 114842 57416 114842 57416 114843 57452 114843 57454 114843 57416 114844 57454 114844 57453 114844 57453 114845 57454 114845 57455 114845 57453 114846 57455 114846 57419 114846 57419 114847 57455 114847 57456 114847 57419 114848 57456 114848 57420 114848 57420 114849 57456 114849 57495 114849 57420 114850 57495 114850 57457 114850 57457 114851 57495 114851 57496 114851 57457 114852 57496 114852 57458 114852 57458 114853 57496 114853 57460 114853 57458 114854 57460 114854 57459 114854 57459 114855 57460 114855 57497 114855 57459 114856 57497 114856 57461 114856 57461 114857 57497 114857 57498 114857 57461 114858 57498 114858 57462 114858 57462 114859 57498 114859 57463 114859 57462 114860 57463 114860 57426 114860 57426 114861 57463 114861 57465 114861 57426 114862 57465 114862 57464 114862 57464 114863 57465 114863 57466 114863 57464 114864 57466 114864 57467 114864 57467 114865 57466 114865 57468 114865 57467 114866 57468 114866 57428 114866 57428 114867 57468 114867 57469 114867 57428 114868 57469 114868 57471 114868 57471 114869 57469 114869 57470 114869 57471 114870 57470 114870 57430 114870 57430 114871 57470 114871 57503 114871 57430 114872 57503 114872 57472 114872 57472 114873 57503 114873 57473 114873 57472 114874 57473 114874 57431 114874 57431 114875 57473 114875 57506 114875 57431 114876 57506 114876 57432 114876 57432 114877 57506 114877 57507 114877 57432 114878 57507 114878 57434 114878 57434 114879 57507 114879 57510 114879 57434 114880 57510 114880 57435 114880 57435 114881 57510 114881 57474 114881 57435 114882 57474 114882 57476 114882 57476 114883 57474 114883 57475 114883 57476 114884 57475 114884 57437 114884 57437 114885 57475 114885 57477 114885 57437 114886 57477 114886 57478 114886 57478 114887 57477 114887 57512 114887 57478 114888 57512 114888 57439 114888 57439 114889 57512 114889 57479 114889 57439 114890 57479 114890 57440 114890 57440 114891 57479 114891 57515 114891 57440 114892 57515 114892 57441 114892 57441 114893 57515 114893 57480 114893 57441 114894 57480 114894 57442 114894 57442 114895 57480 114895 57516 114895 57442 114896 57516 114896 57481 114896 57481 114897 57516 114897 57519 114897 57481 114898 57519 114898 57482 114898 57482 114899 57519 114899 57484 114899 57482 114900 57484 114900 57483 114900 57483 114901 57484 114901 57485 114901 57483 114902 57485 114902 57486 114902 57486 114903 57485 114903 57487 114903 57486 114904 57487 114904 57446 114904 57446 114905 57487 114905 57447 114905 57487 114906 57521 114906 57447 114906 57447 114907 57521 114907 57488 114907 57447 114908 57488 114908 57489 114908 57489 114909 57488 114909 56674 114909 57489 114910 56674 114910 57490 114910 57490 114911 56674 114911 57491 114911 57490 114912 57491 114912 57492 114912 57492 114913 57491 114913 56697 114913 57492 114914 56697 114914 57493 114914 57493 114915 56697 114915 56686 114915 57493 114916 56686 114916 57452 114916 57452 114917 56686 114917 56672 114917 57452 114918 56672 114918 57454 114918 57454 114919 56672 114919 57494 114919 57454 114920 57494 114920 57455 114920 57455 114921 57494 114921 56673 114921 57455 114922 56673 114922 57456 114922 57456 114923 56673 114923 56677 114923 57456 114924 56677 114924 57495 114924 57495 114925 56677 114925 56679 114925 57495 114926 56679 114926 57496 114926 57496 114927 56679 114927 56681 114927 57496 114928 56681 114928 57460 114928 57460 114929 56681 114929 56708 114929 57460 114930 56708 114930 57497 114930 57497 114931 56708 114931 56710 114931 57497 114932 56710 114932 57498 114932 57498 114933 56710 114933 56711 114933 57498 114934 56711 114934 57463 114934 57463 114935 56711 114935 57499 114935 57463 114936 57499 114936 57465 114936 57465 114937 57499 114937 57500 114937 57465 114938 57500 114938 57466 114938 57466 114939 57500 114939 56705 114939 57466 114940 56705 114940 57468 114940 57468 114941 56705 114941 57501 114941 57468 114942 57501 114942 57469 114942 57469 114943 57501 114943 57502 114943 57469 114944 57502 114944 57470 114944 57470 114945 57502 114945 57504 114945 57470 114946 57504 114946 57503 114946 57503 114947 57504 114947 57505 114947 57503 114948 57505 114948 57473 114948 57473 114949 57505 114949 56684 114949 57473 114950 56684 114950 57506 114950 57506 114951 56684 114951 57508 114951 57506 114952 57508 114952 57507 114952 57507 114953 57508 114953 57509 114953 57507 114954 57509 114954 57510 114954 57510 114955 57509 114955 57511 114955 57510 114956 57511 114956 57474 114956 57474 114957 57511 114957 56699 114957 57474 114958 56699 114958 57475 114958 57475 114959 56699 114959 56702 114959 57475 114960 56702 114960 57477 114960 57477 114961 56702 114961 56704 114961 57477 114962 56704 114962 57512 114962 57512 114963 56704 114963 57513 114963 57512 114964 57513 114964 57479 114964 57479 114965 57513 114965 57514 114965 57479 114966 57514 114966 57515 114966 57515 114967 57514 114967 56682 114967 57515 114968 56682 114968 57480 114968 57480 114969 56682 114969 57517 114969 57480 114970 57517 114970 57516 114970 57516 114971 57517 114971 57518 114971 57516 114972 57518 114972 57519 114972 57519 114973 57518 114973 56689 114973 57519 114974 56689 114974 57484 114974 57484 114975 56689 114975 56688 114975 57484 114976 56688 114976 57485 114976 57485 114977 56688 114977 57520 114977 57485 114978 57520 114978 57487 114978 57487 114979 57520 114979 57521 114979 57993 114980 57522 114980 57523 114980 57523 114981 57522 114981 57895 114981 57523 114982 57895 114982 57524 114982 57524 114983 57895 114983 57893 114983 57524 114984 57893 114984 57525 114984 57525 114985 57893 114985 57891 114985 57525 114986 57891 114986 57995 114986 57995 114987 57891 114987 57890 114987 57995 114988 57890 114988 57526 114988 57526 114989 57890 114989 57889 114989 57526 114990 57889 114990 57527 114990 57527 114991 57889 114991 57887 114991 57527 114992 57887 114992 57528 114992 57528 114993 57887 114993 57529 114993 57528 114994 57529 114994 57998 114994 57998 114995 57529 114995 57530 114995 57998 114996 57530 114996 58000 114996 58000 114997 57530 114997 57531 114997 58000 114998 57531 114998 58002 114998 58002 114999 57531 114999 57883 114999 58002 115000 57883 115000 58004 115000 58004 115001 57883 115001 57532 115001 58004 115002 57532 115002 57533 115002 57533 115003 57532 115003 57881 115003 57533 115004 57881 115004 58005 115004 58005 115005 57881 115005 57880 115005 58005 115006 57880 115006 58008 115006 58008 115007 57880 115007 57878 115007 58008 115008 57878 115008 58010 115008 58010 115009 57878 115009 57875 115009 58010 115010 57875 115010 57534 115010 57534 115011 57875 115011 57874 115011 57534 115012 57874 115012 57535 115012 57535 115013 57874 115013 57536 115013 57535 115014 57536 115014 57969 115014 57969 115015 57536 115015 57873 115015 57969 115016 57873 115016 57971 115016 57971 115017 57873 115017 57537 115017 57971 115018 57537 115018 57972 115018 57972 115019 57537 115019 57872 115019 57972 115020 57872 115020 57973 115020 57973 115021 57872 115021 57538 115021 57973 115022 57538 115022 57974 115022 57974 115023 57538 115023 57870 115023 57974 115024 57870 115024 57539 115024 57539 115025 57870 115025 57869 115025 57539 115026 57869 115026 57540 115026 57540 115027 57869 115027 57868 115027 57540 115028 57868 115028 57976 115028 57976 115029 57868 115029 57867 115029 57976 115030 57867 115030 57978 115030 57978 115031 57867 115031 57541 115031 57978 115032 57541 115032 57980 115032 57980 115033 57541 115033 57866 115033 57980 115034 57866 115034 57981 115034 57981 115035 57866 115035 57864 115035 57981 115036 57864 115036 57982 115036 57982 115037 57864 115037 57542 115037 57982 115038 57542 115038 57984 115038 57984 115039 57542 115039 57543 115039 57984 115040 57543 115040 57985 115040 57985 115041 57543 115041 57544 115041 57985 115042 57544 115042 57545 115042 57545 115043 57544 115043 57862 115043 57545 115044 57862 115044 57987 115044 57987 115045 57862 115045 57860 115045 57987 115046 57860 115046 57990 115046 57990 115047 57860 115047 57546 115047 57990 115048 57546 115048 57991 115048 57991 115049 57546 115049 57547 115049 57991 115050 57547 115050 57993 115050 57993 115051 57547 115051 57522 115051 57566 115052 57550 115052 57548 115052 56642 115053 57549 115053 57550 115053 57550 115054 57549 115054 57551 115054 57550 115055 57551 115055 57548 115055 56650 115056 57552 115056 56642 115056 56642 115057 57552 115057 57776 115057 56642 115058 57776 115058 57549 115058 57554 115059 57553 115059 56650 115059 56650 115060 57553 115060 57778 115060 56650 115061 57778 115061 57552 115061 56631 115062 57782 115062 57554 115062 57554 115063 57782 115063 57555 115063 57554 115064 57555 115064 57553 115064 56663 115065 57784 115065 56631 115065 56631 115066 57784 115066 57783 115066 56631 115067 57783 115067 57782 115067 57556 115068 57787 115068 56663 115068 56663 115069 57787 115069 57786 115069 56663 115070 57786 115070 57784 115070 56623 115071 57559 115071 57556 115071 57556 115072 57559 115072 57557 115072 57556 115073 57557 115073 57787 115073 57560 115074 57558 115074 56623 115074 56623 115075 57558 115075 57766 115075 56623 115076 57766 115076 57559 115076 56644 115077 57562 115077 57560 115077 57560 115078 57562 115078 57767 115078 57560 115079 57767 115079 57558 115079 56658 115080 57561 115080 56644 115080 56644 115081 57561 115081 57769 115081 56644 115082 57769 115082 57562 115082 57563 115083 57564 115083 56658 115083 56658 115084 57564 115084 57565 115084 56658 115085 57565 115085 57561 115085 57568 115086 57771 115086 57563 115086 57563 115087 57771 115087 57770 115087 57563 115088 57770 115088 57564 115088 57548 115089 57774 115089 57566 115089 57566 115090 57774 115090 57567 115090 57566 115091 57567 115091 57568 115091 57568 115092 57567 115092 57569 115092 57568 115093 57569 115093 57771 115093 57733 115094 57702 115094 57577 115094 57570 115095 57571 115095 57577 115095 57577 115096 57571 115096 57572 115096 57577 115097 57572 115097 57733 115097 57573 115098 57574 115098 57577 115098 57577 115099 57574 115099 57729 115099 57577 115100 57729 115100 57570 115100 57725 115101 57726 115101 57577 115101 57577 115102 57726 115102 57727 115102 57577 115103 57727 115103 57573 115103 57722 115104 57723 115104 57577 115104 57577 115105 57723 115105 57575 115105 57577 115106 57575 115106 57725 115106 57719 115107 57720 115107 57577 115107 57577 115108 57720 115108 57721 115108 57577 115109 57721 115109 57722 115109 57715 115110 57717 115110 57577 115110 57577 115111 57717 115111 57576 115111 57577 115112 57576 115112 57719 115112 57711 115113 57712 115113 57577 115113 57577 115114 57712 115114 57714 115114 57577 115115 57714 115115 57715 115115 57705 115116 57578 115116 57577 115116 57577 115117 57578 115117 57579 115117 57577 115118 57579 115118 57711 115118 57702 115119 57703 115119 57577 115119 57577 115120 57703 115120 57704 115120 57577 115121 57704 115121 57705 115121 57601 115122 57580 115122 57688 115122 56669 115123 57692 115123 57580 115123 57580 115124 57692 115124 57689 115124 57580 115125 57689 115125 57688 115125 57582 115126 57693 115126 56669 115126 56669 115127 57693 115127 57581 115127 56669 115128 57581 115128 57692 115128 56638 115129 57584 115129 57582 115129 57582 115130 57584 115130 57694 115130 57582 115131 57694 115131 57693 115131 57586 115132 57587 115132 56638 115132 56638 115133 57587 115133 57583 115133 56638 115134 57583 115134 57584 115134 56634 115135 57585 115135 57586 115135 57586 115136 57585 115136 57696 115136 57586 115137 57696 115137 57587 115137 57589 115138 57591 115138 56634 115138 56634 115139 57591 115139 57588 115139 56634 115140 57588 115140 57585 115140 57592 115141 57595 115141 57589 115141 57589 115142 57595 115142 57590 115142 57589 115143 57590 115143 57591 115143 57596 115144 57593 115144 57592 115144 57592 115145 57593 115145 57594 115145 57592 115146 57594 115146 57595 115146 56626 115147 57679 115147 57596 115147 57596 115148 57679 115148 57597 115148 57596 115149 57597 115149 57593 115149 56627 115150 57681 115150 56626 115150 56626 115151 57681 115151 57598 115151 56626 115152 57598 115152 57679 115152 56654 115153 57599 115153 56627 115153 56627 115154 57599 115154 57600 115154 56627 115155 57600 115155 57681 115155 57604 115156 57685 115156 56654 115156 56654 115157 57685 115157 57684 115157 56654 115158 57684 115158 57599 115158 57688 115159 57602 115159 57601 115159 57601 115160 57602 115160 57687 115160 57601 115161 57687 115161 57604 115161 57604 115162 57687 115162 57603 115162 57604 115163 57603 115163 57685 115163 57605 115164 57618 115164 57613 115164 57642 115165 57643 115165 57613 115165 57613 115166 57643 115166 57645 115166 57613 115167 57645 115167 57605 115167 57608 115168 57606 115168 57613 115168 57613 115169 57606 115169 57640 115169 57613 115170 57640 115170 57642 115170 57610 115171 57639 115171 57613 115171 57613 115172 57639 115172 57607 115172 57613 115173 57607 115173 57608 115173 57612 115174 57609 115174 57613 115174 57613 115175 57609 115175 57636 115175 57613 115176 57636 115176 57610 115176 57614 115177 57633 115177 57613 115177 57613 115178 57633 115178 57611 115178 57613 115179 57611 115179 57612 115179 57615 115180 57629 115180 57613 115180 57613 115181 57629 115181 57630 115181 57613 115182 57630 115182 57614 115182 57626 115183 57627 115183 57613 115183 57613 115184 57627 115184 57628 115184 57613 115185 57628 115185 57615 115185 57622 115186 57616 115186 57613 115186 57613 115187 57616 115187 57624 115187 57613 115188 57624 115188 57626 115188 57618 115189 57619 115189 57613 115189 57613 115190 57619 115190 57620 115190 57613 115191 57620 115191 57622 115191 57605 115192 57617 115192 57618 115192 57618 115193 57617 115193 57647 115193 57618 115194 57647 115194 57619 115194 57619 115195 57647 115195 57621 115195 57619 115196 57621 115196 57620 115196 57620 115197 57621 115197 57650 115197 57620 115198 57650 115198 57622 115198 57622 115199 57650 115199 57623 115199 57622 115200 57623 115200 57616 115200 57616 115201 57623 115201 57652 115201 57616 115202 57652 115202 57624 115202 57624 115203 57652 115203 57653 115203 57624 115204 57653 115204 57626 115204 57626 115205 57653 115205 57625 115205 57626 115206 57625 115206 57627 115206 57627 115207 57625 115207 57655 115207 57627 115208 57655 115208 57628 115208 57628 115209 57655 115209 57657 115209 57628 115210 57657 115210 57615 115210 57615 115211 57657 115211 57659 115211 57615 115212 57659 115212 57629 115212 57629 115213 57659 115213 57631 115213 57629 115214 57631 115214 57630 115214 57630 115215 57631 115215 57632 115215 57630 115216 57632 115216 57614 115216 57614 115217 57632 115217 57634 115217 57614 115218 57634 115218 57633 115218 57633 115219 57634 115219 57663 115219 57633 115220 57663 115220 57611 115220 57611 115221 57663 115221 57664 115221 57611 115222 57664 115222 57612 115222 57612 115223 57664 115223 57635 115223 57612 115224 57635 115224 57609 115224 57609 115225 57635 115225 57637 115225 57609 115226 57637 115226 57636 115226 57636 115227 57637 115227 57638 115227 57636 115228 57638 115228 57610 115228 57610 115229 57638 115229 57668 115229 57610 115230 57668 115230 57639 115230 57639 115231 57668 115231 57669 115231 57639 115232 57669 115232 57607 115232 57607 115233 57669 115233 57671 115233 57607 115234 57671 115234 57608 115234 57608 115235 57671 115235 57673 115235 57608 115236 57673 115236 57606 115236 57606 115237 57673 115237 57674 115237 57606 115238 57674 115238 57640 115238 57640 115239 57674 115239 57641 115239 57640 115240 57641 115240 57642 115240 57642 115241 57641 115241 57676 115241 57642 115242 57676 115242 57643 115242 57643 115243 57676 115243 57644 115243 57643 115244 57644 115244 57645 115244 57645 115245 57644 115245 57646 115245 57645 115246 57646 115246 57605 115246 57605 115247 57646 115247 57617 115247 57646 115248 57677 115248 57617 115248 57617 115249 57677 115249 57678 115249 57617 115250 57678 115250 57647 115250 57647 115251 57678 115251 57648 115251 57647 115252 57648 115252 57621 115252 57621 115253 57648 115253 57649 115253 57621 115254 57649 115254 57650 115254 57650 115255 57649 115255 57651 115255 57650 115256 57651 115256 57623 115256 57623 115257 57651 115257 57680 115257 57623 115258 57680 115258 57652 115258 57652 115259 57680 115259 57682 115259 57652 115260 57682 115260 57653 115260 57653 115261 57682 115261 57683 115261 57653 115262 57683 115262 57625 115262 57625 115263 57683 115263 57654 115263 57625 115264 57654 115264 57655 115264 57655 115265 57654 115265 57656 115265 57655 115266 57656 115266 57657 115266 57657 115267 57656 115267 57658 115267 57657 115268 57658 115268 57659 115268 57659 115269 57658 115269 57686 115269 57659 115270 57686 115270 57631 115270 57631 115271 57686 115271 57660 115271 57631 115272 57660 115272 57632 115272 57632 115273 57660 115273 57661 115273 57632 115274 57661 115274 57634 115274 57634 115275 57661 115275 57662 115275 57634 115276 57662 115276 57663 115276 57663 115277 57662 115277 57690 115277 57663 115278 57690 115278 57664 115278 57664 115279 57690 115279 57691 115279 57664 115280 57691 115280 57635 115280 57635 115281 57691 115281 57665 115281 57635 115282 57665 115282 57637 115282 57637 115283 57665 115283 57666 115283 57637 115284 57666 115284 57638 115284 57638 115285 57666 115285 57667 115285 57638 115286 57667 115286 57668 115286 57668 115287 57667 115287 57695 115287 57668 115288 57695 115288 57669 115288 57669 115289 57695 115289 57670 115289 57669 115290 57670 115290 57671 115290 57671 115291 57670 115291 57672 115291 57671 115292 57672 115292 57673 115292 57673 115293 57672 115293 57697 115293 57673 115294 57697 115294 57674 115294 57674 115295 57697 115295 57675 115295 57674 115296 57675 115296 57641 115296 57641 115297 57675 115297 57698 115297 57641 115298 57698 115298 57676 115298 57676 115299 57698 115299 57699 115299 57676 115300 57699 115300 57644 115300 57644 115301 57699 115301 57700 115301 57644 115302 57700 115302 57646 115302 57646 115303 57700 115303 57677 115303 57700 115304 57595 115304 57677 115304 57677 115305 57595 115305 57594 115305 57677 115306 57594 115306 57678 115306 57678 115307 57594 115307 57593 115307 57678 115308 57593 115308 57648 115308 57648 115309 57593 115309 57597 115309 57648 115310 57597 115310 57649 115310 57649 115311 57597 115311 57679 115311 57649 115312 57679 115312 57651 115312 57651 115313 57679 115313 57598 115313 57651 115314 57598 115314 57680 115314 57680 115315 57598 115315 57681 115315 57680 115316 57681 115316 57682 115316 57682 115317 57681 115317 57600 115317 57682 115318 57600 115318 57683 115318 57683 115319 57600 115319 57599 115319 57683 115320 57599 115320 57654 115320 57654 115321 57599 115321 57684 115321 57654 115322 57684 115322 57656 115322 57656 115323 57684 115323 57685 115323 57656 115324 57685 115324 57658 115324 57658 115325 57685 115325 57603 115325 57658 115326 57603 115326 57686 115326 57686 115327 57603 115327 57687 115327 57686 115328 57687 115328 57660 115328 57660 115329 57687 115329 57602 115329 57660 115330 57602 115330 57661 115330 57661 115331 57602 115331 57688 115331 57661 115332 57688 115332 57662 115332 57662 115333 57688 115333 57689 115333 57662 115334 57689 115334 57690 115334 57690 115335 57689 115335 57692 115335 57690 115336 57692 115336 57691 115336 57691 115337 57692 115337 57581 115337 57691 115338 57581 115338 57665 115338 57665 115339 57581 115339 57693 115339 57665 115340 57693 115340 57666 115340 57666 115341 57693 115341 57694 115341 57666 115342 57694 115342 57667 115342 57667 115343 57694 115343 57584 115343 57667 115344 57584 115344 57695 115344 57695 115345 57584 115345 57583 115345 57695 115346 57583 115346 57670 115346 57670 115347 57583 115347 57587 115347 57670 115348 57587 115348 57672 115348 57672 115349 57587 115349 57696 115349 57672 115350 57696 115350 57697 115350 57697 115351 57696 115351 57585 115351 57697 115352 57585 115352 57675 115352 57675 115353 57585 115353 57588 115353 57675 115354 57588 115354 57698 115354 57698 115355 57588 115355 57591 115355 57698 115356 57591 115356 57699 115356 57699 115357 57591 115357 57590 115357 57699 115358 57590 115358 57700 115358 57700 115359 57590 115359 57595 115359 57733 115360 57701 115360 57702 115360 57702 115361 57701 115361 57734 115361 57702 115362 57734 115362 57703 115362 57703 115363 57734 115363 57736 115363 57703 115364 57736 115364 57704 115364 57704 115365 57736 115365 57706 115365 57704 115366 57706 115366 57705 115366 57705 115367 57706 115367 57707 115367 57705 115368 57707 115368 57578 115368 57578 115369 57707 115369 57708 115369 57578 115370 57708 115370 57579 115370 57579 115371 57708 115371 57709 115371 57579 115372 57709 115372 57711 115372 57711 115373 57709 115373 57710 115373 57711 115374 57710 115374 57712 115374 57712 115375 57710 115375 57713 115375 57712 115376 57713 115376 57714 115376 57714 115377 57713 115377 57743 115377 57714 115378 57743 115378 57715 115378 57715 115379 57743 115379 57716 115379 57715 115380 57716 115380 57717 115380 57717 115381 57716 115381 57744 115381 57717 115382 57744 115382 57576 115382 57576 115383 57744 115383 57718 115383 57576 115384 57718 115384 57719 115384 57719 115385 57718 115385 57747 115385 57719 115386 57747 115386 57720 115386 57720 115387 57747 115387 57748 115387 57720 115388 57748 115388 57721 115388 57721 115389 57748 115389 57750 115389 57721 115390 57750 115390 57722 115390 57722 115391 57750 115391 57724 115391 57722 115392 57724 115392 57723 115392 57723 115393 57724 115393 57752 115393 57723 115394 57752 115394 57575 115394 57575 115395 57752 115395 57754 115395 57575 115396 57754 115396 57725 115396 57725 115397 57754 115397 57756 115397 57725 115398 57756 115398 57726 115398 57726 115399 57756 115399 57757 115399 57726 115400 57757 115400 57727 115400 57727 115401 57757 115401 57758 115401 57727 115402 57758 115402 57573 115402 57573 115403 57758 115403 57759 115403 57573 115404 57759 115404 57574 115404 57574 115405 57759 115405 57728 115405 57574 115406 57728 115406 57729 115406 57729 115407 57728 115407 57730 115407 57729 115408 57730 115408 57570 115408 57570 115409 57730 115409 57731 115409 57570 115410 57731 115410 57571 115410 57571 115411 57731 115411 57732 115411 57571 115412 57732 115412 57572 115412 57572 115413 57732 115413 57763 115413 57572 115414 57763 115414 57733 115414 57733 115415 57763 115415 57701 115415 57763 115416 57764 115416 57701 115416 57701 115417 57764 115417 57765 115417 57701 115418 57765 115418 57734 115418 57734 115419 57765 115419 57735 115419 57734 115420 57735 115420 57736 115420 57736 115421 57735 115421 57737 115421 57736 115422 57737 115422 57706 115422 57706 115423 57737 115423 57738 115423 57706 115424 57738 115424 57707 115424 57707 115425 57738 115425 57768 115425 57707 115426 57768 115426 57708 115426 57708 115427 57768 115427 57739 115427 57708 115428 57739 115428 57709 115428 57709 115429 57739 115429 57740 115429 57709 115430 57740 115430 57710 115430 57710 115431 57740 115431 57741 115431 57710 115432 57741 115432 57713 115432 57713 115433 57741 115433 57742 115433 57713 115434 57742 115434 57743 115434 57743 115435 57742 115435 57772 115435 57743 115436 57772 115436 57716 115436 57716 115437 57772 115437 57773 115437 57716 115438 57773 115438 57744 115438 57744 115439 57773 115439 57775 115439 57744 115440 57775 115440 57718 115440 57718 115441 57775 115441 57745 115441 57718 115442 57745 115442 57747 115442 57747 115443 57745 115443 57746 115443 57747 115444 57746 115444 57748 115444 57748 115445 57746 115445 57749 115445 57748 115446 57749 115446 57750 115446 57750 115447 57749 115447 57751 115447 57750 115448 57751 115448 57724 115448 57724 115449 57751 115449 57753 115449 57724 115450 57753 115450 57752 115450 57752 115451 57753 115451 57777 115451 57752 115452 57777 115452 57754 115452 57754 115453 57777 115453 57755 115453 57754 115454 57755 115454 57756 115454 57756 115455 57755 115455 57779 115455 57756 115456 57779 115456 57757 115456 57757 115457 57779 115457 57780 115457 57757 115458 57780 115458 57758 115458 57758 115459 57780 115459 57781 115459 57758 115460 57781 115460 57759 115460 57759 115461 57781 115461 57760 115461 57759 115462 57760 115462 57728 115462 57728 115463 57760 115463 57761 115463 57728 115464 57761 115464 57730 115464 57730 115465 57761 115465 57785 115465 57730 115466 57785 115466 57731 115466 57731 115467 57785 115467 57762 115467 57731 115468 57762 115468 57732 115468 57732 115469 57762 115469 57788 115469 57732 115470 57788 115470 57763 115470 57763 115471 57788 115471 57764 115471 57788 115472 57559 115472 57764 115472 57764 115473 57559 115473 57766 115473 57764 115474 57766 115474 57765 115474 57765 115475 57766 115475 57558 115475 57765 115476 57558 115476 57735 115476 57735 115477 57558 115477 57767 115477 57735 115478 57767 115478 57737 115478 57737 115479 57767 115479 57562 115479 57737 115480 57562 115480 57738 115480 57738 115481 57562 115481 57769 115481 57738 115482 57769 115482 57768 115482 57768 115483 57769 115483 57561 115483 57768 115484 57561 115484 57739 115484 57739 115485 57561 115485 57565 115485 57739 115486 57565 115486 57740 115486 57740 115487 57565 115487 57564 115487 57740 115488 57564 115488 57741 115488 57741 115489 57564 115489 57770 115489 57741 115490 57770 115490 57742 115490 57742 115491 57770 115491 57771 115491 57742 115492 57771 115492 57772 115492 57772 115493 57771 115493 57569 115493 57772 115494 57569 115494 57773 115494 57773 115495 57569 115495 57567 115495 57773 115496 57567 115496 57775 115496 57775 115497 57567 115497 57774 115497 57775 115498 57774 115498 57745 115498 57745 115499 57774 115499 57548 115499 57745 115500 57548 115500 57746 115500 57746 115501 57548 115501 57551 115501 57746 115502 57551 115502 57749 115502 57749 115503 57551 115503 57549 115503 57749 115504 57549 115504 57751 115504 57751 115505 57549 115505 57776 115505 57751 115506 57776 115506 57753 115506 57753 115507 57776 115507 57552 115507 57753 115508 57552 115508 57777 115508 57777 115509 57552 115509 57778 115509 57777 115510 57778 115510 57755 115510 57755 115511 57778 115511 57553 115511 57755 115512 57553 115512 57779 115512 57779 115513 57553 115513 57555 115513 57779 115514 57555 115514 57780 115514 57780 115515 57555 115515 57782 115515 57780 115516 57782 115516 57781 115516 57781 115517 57782 115517 57783 115517 57781 115518 57783 115518 57760 115518 57760 115519 57783 115519 57784 115519 57760 115520 57784 115520 57761 115520 57761 115521 57784 115521 57786 115521 57761 115522 57786 115522 57785 115522 57785 115523 57786 115523 57787 115523 57785 115524 57787 115524 57762 115524 57762 115525 57787 115525 57557 115525 57762 115526 57557 115526 57788 115526 57788 115527 57557 115527 57559 115527 57356 115528 57825 115528 57364 115528 57364 115529 57825 115529 57827 115529 57364 115530 57827 115530 57789 115530 57789 115531 57827 115531 57790 115531 57789 115532 57790 115532 57365 115532 57365 115533 57790 115533 57792 115533 57365 115534 57792 115534 57791 115534 57791 115535 57792 115535 57793 115535 57791 115536 57793 115536 57357 115536 57357 115537 57793 115537 57829 115537 57357 115538 57829 115538 57358 115538 57358 115539 57829 115539 57831 115539 57358 115540 57831 115540 57359 115540 57359 115541 57831 115541 57794 115541 57359 115542 57794 115542 57342 115542 57342 115543 57794 115543 57834 115543 57342 115544 57834 115544 57343 115544 57343 115545 57834 115545 57837 115545 57343 115546 57837 115546 57352 115546 57352 115547 57837 115547 57795 115547 57352 115548 57795 115548 57353 115548 57353 115549 57795 115549 57839 115549 57353 115550 57839 115550 57355 115550 57355 115551 57839 115551 57841 115551 57355 115552 57841 115552 57796 115552 57796 115553 57841 115553 57842 115553 57796 115554 57842 115554 57344 115554 57344 115555 57842 115555 57797 115555 57344 115556 57797 115556 57798 115556 57798 115557 57797 115557 57799 115557 57798 115558 57799 115558 57800 115558 57800 115559 57799 115559 57801 115559 57800 115560 57801 115560 57802 115560 57802 115561 57801 115561 57803 115561 57802 115562 57803 115562 57339 115562 57339 115563 57803 115563 57804 115563 57339 115564 57804 115564 57805 115564 57805 115565 57804 115565 57806 115565 57805 115566 57806 115566 57346 115566 57346 115567 57806 115567 57847 115567 57346 115568 57847 115568 57347 115568 57347 115569 57847 115569 57849 115569 57347 115570 57849 115570 57808 115570 57808 115571 57849 115571 57807 115571 57808 115572 57807 115572 57349 115572 57349 115573 57807 115573 57809 115573 57349 115574 57809 115574 57350 115574 57350 115575 57809 115575 57810 115575 57350 115576 57810 115576 57811 115576 57811 115577 57810 115577 57852 115577 57811 115578 57852 115578 57340 115578 57340 115579 57852 115579 57853 115579 57340 115580 57853 115580 57813 115580 57813 115581 57853 115581 57812 115581 57813 115582 57812 115582 57351 115582 57351 115583 57812 115583 57815 115583 57351 115584 57815 115584 57814 115584 57814 115585 57815 115585 57856 115585 57814 115586 57856 115586 57361 115586 57361 115587 57856 115587 57857 115587 57361 115588 57857 115588 57816 115588 57816 115589 57857 115589 57858 115589 57816 115590 57858 115590 57817 115590 57817 115591 57858 115591 57819 115591 57817 115592 57819 115592 57818 115592 57818 115593 57819 115593 57820 115593 57818 115594 57820 115594 57821 115594 57821 115595 57820 115595 57822 115595 57821 115596 57822 115596 57363 115596 57363 115597 57822 115597 57823 115597 57363 115598 57823 115598 57356 115598 57356 115599 57823 115599 57825 115599 57823 115600 57824 115600 57825 115600 57825 115601 57824 115601 57826 115601 57825 115602 57826 115602 57827 115602 57827 115603 57826 115603 57861 115603 57827 115604 57861 115604 57790 115604 57790 115605 57861 115605 57863 115605 57790 115606 57863 115606 57792 115606 57792 115607 57863 115607 57828 115607 57792 115608 57828 115608 57793 115608 57793 115609 57828 115609 57830 115609 57793 115610 57830 115610 57829 115610 57829 115611 57830 115611 57865 115611 57829 115612 57865 115612 57831 115612 57831 115613 57865 115613 57832 115613 57831 115614 57832 115614 57794 115614 57794 115615 57832 115615 57833 115615 57794 115616 57833 115616 57834 115616 57834 115617 57833 115617 57835 115617 57834 115618 57835 115618 57837 115618 57837 115619 57835 115619 57836 115619 57837 115620 57836 115620 57795 115620 57795 115621 57836 115621 57838 115621 57795 115622 57838 115622 57839 115622 57839 115623 57838 115623 57840 115623 57839 115624 57840 115624 57841 115624 57841 115625 57840 115625 57843 115625 57841 115626 57843 115626 57842 115626 57842 115627 57843 115627 57871 115627 57842 115628 57871 115628 57797 115628 57797 115629 57871 115629 57844 115629 57797 115630 57844 115630 57799 115630 57799 115631 57844 115631 57845 115631 57799 115632 57845 115632 57801 115632 57801 115633 57845 115633 57846 115633 57801 115634 57846 115634 57803 115634 57803 115635 57846 115635 57876 115635 57803 115636 57876 115636 57804 115636 57804 115637 57876 115637 57877 115637 57804 115638 57877 115638 57806 115638 57806 115639 57877 115639 57879 115639 57806 115640 57879 115640 57847 115640 57847 115641 57879 115641 57848 115641 57847 115642 57848 115642 57849 115642 57849 115643 57848 115643 57850 115643 57849 115644 57850 115644 57807 115644 57807 115645 57850 115645 57882 115645 57807 115646 57882 115646 57809 115646 57809 115647 57882 115647 57851 115647 57809 115648 57851 115648 57810 115648 57810 115649 57851 115649 57884 115649 57810 115650 57884 115650 57852 115650 57852 115651 57884 115651 57885 115651 57852 115652 57885 115652 57853 115652 57853 115653 57885 115653 57854 115653 57853 115654 57854 115654 57812 115654 57812 115655 57854 115655 57886 115655 57812 115656 57886 115656 57815 115656 57815 115657 57886 115657 57888 115657 57815 115658 57888 115658 57856 115658 57856 115659 57888 115659 57855 115659 57856 115660 57855 115660 57857 115660 57857 115661 57855 115661 57892 115661 57857 115662 57892 115662 57858 115662 57858 115663 57892 115663 57894 115663 57858 115664 57894 115664 57819 115664 57819 115665 57894 115665 57896 115665 57819 115666 57896 115666 57820 115666 57820 115667 57896 115667 57897 115667 57820 115668 57897 115668 57822 115668 57822 115669 57897 115669 57859 115669 57822 115670 57859 115670 57823 115670 57823 115671 57859 115671 57824 115671 57859 115672 57546 115672 57824 115672 57824 115673 57546 115673 57860 115673 57824 115674 57860 115674 57826 115674 57826 115675 57860 115675 57862 115675 57826 115676 57862 115676 57861 115676 57861 115677 57862 115677 57544 115677 57861 115678 57544 115678 57863 115678 57863 115679 57544 115679 57543 115679 57863 115680 57543 115680 57828 115680 57828 115681 57543 115681 57542 115681 57828 115682 57542 115682 57830 115682 57830 115683 57542 115683 57864 115683 57830 115684 57864 115684 57865 115684 57865 115685 57864 115685 57866 115685 57865 115686 57866 115686 57832 115686 57832 115687 57866 115687 57541 115687 57832 115688 57541 115688 57833 115688 57833 115689 57541 115689 57867 115689 57833 115690 57867 115690 57835 115690 57835 115691 57867 115691 57868 115691 57835 115692 57868 115692 57836 115692 57836 115693 57868 115693 57869 115693 57836 115694 57869 115694 57838 115694 57838 115695 57869 115695 57870 115695 57838 115696 57870 115696 57840 115696 57840 115697 57870 115697 57538 115697 57840 115698 57538 115698 57843 115698 57843 115699 57538 115699 57872 115699 57843 115700 57872 115700 57871 115700 57871 115701 57872 115701 57537 115701 57871 115702 57537 115702 57844 115702 57844 115703 57537 115703 57873 115703 57844 115704 57873 115704 57845 115704 57845 115705 57873 115705 57536 115705 57845 115706 57536 115706 57846 115706 57846 115707 57536 115707 57874 115707 57846 115708 57874 115708 57876 115708 57876 115709 57874 115709 57875 115709 57876 115710 57875 115710 57877 115710 57877 115711 57875 115711 57878 115711 57877 115712 57878 115712 57879 115712 57879 115713 57878 115713 57880 115713 57879 115714 57880 115714 57848 115714 57848 115715 57880 115715 57881 115715 57848 115716 57881 115716 57850 115716 57850 115717 57881 115717 57532 115717 57850 115718 57532 115718 57882 115718 57882 115719 57532 115719 57883 115719 57882 115720 57883 115720 57851 115720 57851 115721 57883 115721 57531 115721 57851 115722 57531 115722 57884 115722 57884 115723 57531 115723 57530 115723 57884 115724 57530 115724 57885 115724 57885 115725 57530 115725 57529 115725 57885 115726 57529 115726 57854 115726 57854 115727 57529 115727 57887 115727 57854 115728 57887 115728 57886 115728 57886 115729 57887 115729 57889 115729 57886 115730 57889 115730 57888 115730 57888 115731 57889 115731 57890 115731 57888 115732 57890 115732 57855 115732 57855 115733 57890 115733 57891 115733 57855 115734 57891 115734 57892 115734 57892 115735 57891 115735 57893 115735 57892 115736 57893 115736 57894 115736 57894 115737 57893 115737 57895 115737 57894 115738 57895 115738 57896 115738 57896 115739 57895 115739 57522 115739 57896 115740 57522 115740 57897 115740 57897 115741 57522 115741 57547 115741 57897 115742 57547 115742 57859 115742 57859 115743 57547 115743 57546 115743 56666 115744 57899 115744 57898 115744 57898 115745 57899 115745 57938 115745 57898 115746 57938 115746 56667 115746 56667 115747 57938 115747 57939 115747 56667 115748 57939 115748 57900 115748 57900 115749 57939 115749 57901 115749 57900 115750 57901 115750 57902 115750 57902 115751 57901 115751 57942 115751 57902 115752 57942 115752 57903 115752 57903 115753 57942 115753 57904 115753 57903 115754 57904 115754 57905 115754 57905 115755 57904 115755 57906 115755 57905 115756 57906 115756 57907 115756 57907 115757 57906 115757 57944 115757 57907 115758 57944 115758 56659 115758 56659 115759 57944 115759 57945 115759 56659 115760 57945 115760 56660 115760 56660 115761 57945 115761 57908 115761 56660 115762 57908 115762 57910 115762 57910 115763 57908 115763 57909 115763 57910 115764 57909 115764 56652 115764 56652 115765 57909 115765 57949 115765 56652 115766 57949 115766 56653 115766 56653 115767 57949 115767 57912 115767 56653 115768 57912 115768 57911 115768 57911 115769 57912 115769 57913 115769 57911 115770 57913 115770 56625 115770 56625 115771 57913 115771 57914 115771 56625 115772 57914 115772 57915 115772 57915 115773 57914 115773 57951 115773 57915 115774 57951 115774 56646 115774 56646 115775 57951 115775 57952 115775 56646 115776 57952 115776 56647 115776 56647 115777 57952 115777 57953 115777 56647 115778 57953 115778 56648 115778 56648 115779 57953 115779 57955 115779 56648 115780 57955 115780 57916 115780 57916 115781 57955 115781 57957 115781 57916 115782 57957 115782 56668 115782 56668 115783 57957 115783 57917 115783 56668 115784 57917 115784 57918 115784 57918 115785 57917 115785 57919 115785 57918 115786 57919 115786 56670 115786 56670 115787 57919 115787 57961 115787 56670 115788 57961 115788 57921 115788 57921 115789 57961 115789 57920 115789 57921 115790 57920 115790 56655 115790 56655 115791 57920 115791 57922 115791 56655 115792 57922 115792 57923 115792 57923 115793 57922 115793 57962 115793 57923 115794 57962 115794 56656 115794 56656 115795 57962 115795 57924 115795 56656 115796 57924 115796 57925 115796 57925 115797 57924 115797 57926 115797 57925 115798 57926 115798 56657 115798 56657 115799 57926 115799 57927 115799 56657 115800 57927 115800 56662 115800 56662 115801 57927 115801 57929 115801 56662 115802 57929 115802 57928 115802 57928 115803 57929 115803 57930 115803 57928 115804 57930 115804 56664 115804 56664 115805 57930 115805 57931 115805 56664 115806 57931 115806 57932 115806 57932 115807 57931 115807 57964 115807 57932 115808 57964 115808 57933 115808 57933 115809 57964 115809 57935 115809 57933 115810 57935 115810 57934 115810 57934 115811 57935 115811 57936 115811 57934 115812 57936 115812 56665 115812 56665 115813 57936 115813 57967 115813 56665 115814 57967 115814 56666 115814 56666 115815 57967 115815 57899 115815 57967 115816 57968 115816 57899 115816 57899 115817 57968 115817 57970 115817 57899 115818 57970 115818 57938 115818 57938 115819 57970 115819 57937 115819 57938 115820 57937 115820 57939 115820 57939 115821 57937 115821 57940 115821 57939 115822 57940 115822 57901 115822 57901 115823 57940 115823 57975 115823 57901 115824 57975 115824 57942 115824 57942 115825 57975 115825 57941 115825 57942 115826 57941 115826 57904 115826 57904 115827 57941 115827 57943 115827 57904 115828 57943 115828 57906 115828 57906 115829 57943 115829 57977 115829 57906 115830 57977 115830 57944 115830 57944 115831 57977 115831 57946 115831 57944 115832 57946 115832 57945 115832 57945 115833 57946 115833 57979 115833 57945 115834 57979 115834 57908 115834 57908 115835 57979 115835 57947 115835 57908 115836 57947 115836 57909 115836 57909 115837 57947 115837 57983 115837 57909 115838 57983 115838 57949 115838 57949 115839 57983 115839 57948 115839 57949 115840 57948 115840 57912 115840 57912 115841 57948 115841 57950 115841 57912 115842 57950 115842 57913 115842 57913 115843 57950 115843 57986 115843 57913 115844 57986 115844 57914 115844 57914 115845 57986 115845 57988 115845 57914 115846 57988 115846 57951 115846 57951 115847 57988 115847 57989 115847 57951 115848 57989 115848 57952 115848 57952 115849 57989 115849 57992 115849 57952 115850 57992 115850 57953 115850 57953 115851 57992 115851 57954 115851 57953 115852 57954 115852 57955 115852 57955 115853 57954 115853 57956 115853 57955 115854 57956 115854 57957 115854 57957 115855 57956 115855 57958 115855 57957 115856 57958 115856 57917 115856 57917 115857 57958 115857 57994 115857 57917 115858 57994 115858 57919 115858 57919 115859 57994 115859 57959 115859 57919 115860 57959 115860 57961 115860 57961 115861 57959 115861 57960 115861 57961 115862 57960 115862 57920 115862 57920 115863 57960 115863 57996 115863 57920 115864 57996 115864 57922 115864 57922 115865 57996 115865 57997 115865 57922 115866 57997 115866 57962 115866 57962 115867 57997 115867 57999 115867 57962 115868 57999 115868 57924 115868 57924 115869 57999 115869 58001 115869 57924 115870 58001 115870 57926 115870 57926 115871 58001 115871 57963 115871 57926 115872 57963 115872 57927 115872 57927 115873 57963 115873 58003 115873 57927 115874 58003 115874 57929 115874 57929 115875 58003 115875 58006 115875 57929 115876 58006 115876 57930 115876 57930 115877 58006 115877 58007 115877 57930 115878 58007 115878 57931 115878 57931 115879 58007 115879 58009 115879 57931 115880 58009 115880 57964 115880 57964 115881 58009 115881 57965 115881 57964 115882 57965 115882 57935 115882 57935 115883 57965 115883 57966 115883 57935 115884 57966 115884 57936 115884 57936 115885 57966 115885 58011 115885 57936 115886 58011 115886 57967 115886 57967 115887 58011 115887 57968 115887 58011 115888 57969 115888 57968 115888 57968 115889 57969 115889 57971 115889 57968 115890 57971 115890 57970 115890 57970 115891 57971 115891 57972 115891 57970 115892 57972 115892 57937 115892 57937 115893 57972 115893 57973 115893 57937 115894 57973 115894 57940 115894 57940 115895 57973 115895 57974 115895 57940 115896 57974 115896 57975 115896 57975 115897 57974 115897 57539 115897 57975 115898 57539 115898 57941 115898 57941 115899 57539 115899 57540 115899 57941 115900 57540 115900 57943 115900 57943 115901 57540 115901 57976 115901 57943 115902 57976 115902 57977 115902 57977 115903 57976 115903 57978 115903 57977 115904 57978 115904 57946 115904 57946 115905 57978 115905 57980 115905 57946 115906 57980 115906 57979 115906 57979 115907 57980 115907 57981 115907 57979 115908 57981 115908 57947 115908 57947 115909 57981 115909 57982 115909 57947 115910 57982 115910 57983 115910 57983 115911 57982 115911 57984 115911 57983 115912 57984 115912 57948 115912 57948 115913 57984 115913 57985 115913 57948 115914 57985 115914 57950 115914 57950 115915 57985 115915 57545 115915 57950 115916 57545 115916 57986 115916 57986 115917 57545 115917 57987 115917 57986 115918 57987 115918 57988 115918 57988 115919 57987 115919 57990 115919 57988 115920 57990 115920 57989 115920 57989 115921 57990 115921 57991 115921 57989 115922 57991 115922 57992 115922 57992 115923 57991 115923 57993 115923 57992 115924 57993 115924 57954 115924 57954 115925 57993 115925 57523 115925 57954 115926 57523 115926 57956 115926 57956 115927 57523 115927 57524 115927 57956 115928 57524 115928 57958 115928 57958 115929 57524 115929 57525 115929 57958 115930 57525 115930 57994 115930 57994 115931 57525 115931 57995 115931 57994 115932 57995 115932 57959 115932 57959 115933 57995 115933 57526 115933 57959 115934 57526 115934 57960 115934 57960 115935 57526 115935 57527 115935 57960 115936 57527 115936 57996 115936 57996 115937 57527 115937 57528 115937 57996 115938 57528 115938 57997 115938 57997 115939 57528 115939 57998 115939 57997 115940 57998 115940 57999 115940 57999 115941 57998 115941 58000 115941 57999 115942 58000 115942 58001 115942 58001 115943 58000 115943 58002 115943 58001 115944 58002 115944 57963 115944 57963 115945 58002 115945 58004 115945 57963 115946 58004 115946 58003 115946 58003 115947 58004 115947 57533 115947 58003 115948 57533 115948 58006 115948 58006 115949 57533 115949 58005 115949 58006 115950 58005 115950 58007 115950 58007 115951 58005 115951 58008 115951 58007 115952 58008 115952 58009 115952 58009 115953 58008 115953 58010 115953 58009 115954 58010 115954 57965 115954 57965 115955 58010 115955 57534 115955 57965 115956 57534 115956 57966 115956 57966 115957 57534 115957 57535 115957 57966 115958 57535 115958 58011 115958 58011 115959 57535 115959 57969 115959 58042 115960 58968 115960 58038 115960 58271 115961 58051 115961 58052 115961 59006 115962 58012 115962 58013 115962 58013 115963 58012 115963 59002 115963 58013 115964 59002 115964 58044 115964 58271 115965 58052 115965 58270 115965 58264 115966 58267 115966 58014 115966 58047 115967 58323 115967 58015 115967 58016 115968 58224 115968 58034 115968 58217 115969 58017 115969 58032 115969 59007 115970 58054 115970 59009 115970 59009 115971 58054 115971 59310 115971 59009 115972 59310 115972 58018 115972 58267 115973 58268 115973 58014 115973 58014 115974 58268 115974 58019 115974 58014 115975 58019 115975 58052 115975 58052 115976 58019 115976 58269 115976 58052 115977 58269 115977 58270 115977 59006 115978 58013 115978 58014 115978 58014 115979 58013 115979 58263 115979 58014 115980 58263 115980 58264 115980 58372 115981 58020 115981 58021 115981 58021 115982 58020 115982 58370 115982 58376 115983 58022 115983 58015 115983 58323 115984 58325 115984 58015 115984 58015 115985 58325 115985 58023 115985 58015 115986 58023 115986 58376 115986 58049 115987 58319 115987 58046 115987 58959 115988 58958 115988 58317 115988 58317 115989 58958 115989 58024 115989 58317 115990 58024 115990 58025 115990 58024 115991 58973 115991 58025 115991 58025 115992 58973 115992 58974 115992 58025 115993 58974 115993 58225 115993 58225 115994 58974 115994 58034 115994 58225 115995 58034 115995 58026 115995 58026 115996 58034 115996 58224 115996 58018 115997 58027 115997 59009 115997 59009 115998 58027 115998 58028 115998 59009 115999 58028 115999 58996 115999 58996 116000 58028 116000 58029 116000 58996 116001 58029 116001 58059 116001 58370 116002 58020 116002 58030 116002 58030 116003 58020 116003 58031 116003 58030 116004 58031 116004 58067 116004 58376 116005 58379 116005 58022 116005 58022 116006 58379 116006 58378 116006 58022 116007 58378 116007 58367 116007 58017 116008 58033 116008 58032 116008 58032 116009 58033 116009 58219 116009 58032 116010 58219 116010 58034 116010 58034 116011 58219 116011 58035 116011 58034 116012 58035 116012 58016 116012 58042 116013 58036 116013 58968 116013 58968 116014 58036 116014 58179 116014 58968 116015 58179 116015 58032 116015 58032 116016 58179 116016 58037 116016 58032 116017 58037 116017 58217 116017 59299 116018 59301 116018 58038 116018 58038 116019 59301 116019 59303 116019 58038 116020 59303 116020 58042 116020 58042 116021 59303 116021 58039 116021 58042 116022 58039 116022 58040 116022 59307 116023 58041 116023 58042 116023 58042 116024 58041 116024 58053 116024 59002 116025 58043 116025 58044 116025 58044 116026 58043 116026 59001 116026 58044 116027 59001 116027 58375 116027 58375 116028 59001 116028 58020 116028 58375 116029 58020 116029 58373 116029 58373 116030 58020 116030 58372 116030 58319 116031 58045 116031 58046 116031 58046 116032 58045 116032 58321 116032 58046 116033 58321 116033 58015 116033 58015 116034 58321 116034 58322 116034 58015 116035 58322 116035 58047 116035 58959 116036 58317 116036 58046 116036 58046 116037 58317 116037 58048 116037 58046 116038 58048 116038 58049 116038 58040 116039 59304 116039 58042 116039 58042 116040 59304 116040 58050 116040 58042 116041 58050 116041 59307 116041 58051 116042 58042 116042 58052 116042 58052 116043 58042 116043 58053 116043 58052 116044 58053 116044 59007 116044 59007 116045 58053 116045 59309 116045 59007 116046 59309 116046 58054 116046 58055 116047 59323 116047 59324 116047 59330 116048 58056 116048 58966 116048 58966 116049 58056 116049 58057 116049 58966 116050 58057 116050 58038 116050 58038 116051 58057 116051 58058 116051 58038 116052 58058 116052 59299 116052 58059 116053 58029 116053 58997 116053 58997 116054 58029 116054 59315 116054 58997 116055 59315 116055 58060 116055 59324 116056 58061 116056 58055 116056 58055 116057 58061 116057 59325 116057 58055 116058 59325 116058 58062 116058 58367 116059 58055 116059 58022 116059 58022 116060 58055 116060 58062 116060 58022 116061 58062 116061 58063 116061 58063 116062 58062 116062 58064 116062 58063 116063 58064 116063 58966 116063 58966 116064 58064 116064 58065 116064 58966 116065 58065 116065 59330 116065 58060 116066 58066 116066 58997 116066 58997 116067 58066 116067 58055 116067 58997 116068 58055 116068 58031 116068 58031 116069 58055 116069 58368 116069 58031 116070 58368 116070 58067 116070 58066 116071 59319 116071 58055 116071 58055 116072 59319 116072 58068 116072 58055 116073 58068 116073 59320 116073 59320 116074 59322 116074 58055 116074 58055 116075 59322 116075 58069 116075 58055 116076 58069 116076 59323 116076 58461 116077 58883 116077 58881 116077 58461 116078 58913 116078 58090 116078 58090 116079 58913 116079 58911 116079 58090 116080 58911 116080 58910 116080 58102 116081 58905 116081 58452 116081 58452 116082 58905 116082 58904 116082 58070 116083 58071 116083 58085 116083 58085 116084 58071 116084 58072 116084 58576 116085 58101 116085 58577 116085 58577 116086 58101 116086 58074 116086 58577 116087 58074 116087 58073 116087 58073 116088 58074 116088 58075 116088 58075 116089 58074 116089 58076 116089 58076 116090 58074 116090 58077 116090 58076 116091 58077 116091 58604 116091 58604 116092 58077 116092 58078 116092 58078 116093 58077 116093 58079 116093 58078 116094 58079 116094 58086 116094 58520 116095 58081 116095 58080 116095 58080 116096 58081 116096 58082 116096 58080 116097 58082 116097 58886 116097 58886 116098 58082 116098 58083 116098 58886 116099 58083 116099 58887 116099 58887 116100 58083 116100 58084 116100 58887 116101 58084 116101 58471 116101 58881 116102 58880 116102 58461 116102 58461 116103 58880 116103 58915 116103 58461 116104 58915 116104 58913 116104 58663 116105 58664 116105 58072 116105 58072 116106 58664 116106 58648 116106 58072 116107 58648 116107 58085 116107 58079 116108 58087 116108 58086 116108 58086 116109 58087 116109 58088 116109 58086 116110 58088 116110 58463 116110 58463 116111 58088 116111 58887 116111 58463 116112 58887 116112 58480 116112 58480 116113 58887 116113 58471 116113 58910 116114 58089 116114 58090 116114 58090 116115 58089 116115 58091 116115 58090 116116 58091 116116 58399 116116 58399 116117 58091 116117 58906 116117 58399 116118 58906 116118 58092 116118 58104 116119 58105 116119 58906 116119 58906 116120 58105 116120 58419 116120 58906 116121 58419 116121 58092 116121 58070 116122 58093 116122 58071 116122 58071 116123 58093 116123 58632 116123 58071 116124 58632 116124 58094 116124 58094 116125 58632 116125 58610 116125 58094 116126 58610 116126 58095 116126 58095 116127 58610 116127 58609 116127 58095 116128 58609 116128 58903 116128 58903 116129 58609 116129 58096 116129 58903 116130 58096 116130 58904 116130 58904 116131 58096 116131 58523 116131 58904 116132 58523 116132 58452 116132 58893 116133 58892 116133 58097 116133 58097 116134 58892 116134 58098 116134 58097 116135 58098 116135 58099 116135 58099 116136 58098 116136 58100 116136 58099 116137 58100 116137 58561 116137 58561 116138 58100 116138 58101 116138 58561 116139 58101 116139 58569 116139 58569 116140 58101 116140 58576 116140 58883 116141 58461 116141 58080 116141 58080 116142 58461 116142 58519 116142 58080 116143 58519 116143 58520 116143 58102 116144 58103 116144 58905 116144 58905 116145 58103 116145 58442 116145 58905 116146 58442 116146 58104 116146 58104 116147 58442 116147 58426 116147 58104 116148 58426 116148 58105 116148 58663 116149 58072 116149 58106 116149 58106 116150 58072 116150 58901 116150 58106 116151 58901 116151 58107 116151 58107 116152 58901 116152 58898 116152 58107 116153 58898 116153 58897 116153 58897 116154 58108 116154 58107 116154 58107 116155 58108 116155 58895 116155 58107 116156 58895 116156 58097 116156 58097 116157 58895 116157 58894 116157 58097 116158 58894 116158 58893 116158 58545 116159 58178 116159 58109 116159 58109 116160 58178 116160 58377 116160 58109 116161 58377 116161 58456 116161 58456 116162 58377 116162 58110 116162 58456 116163 58110 116163 58111 116163 58111 116164 58110 116164 58112 116164 58111 116165 58112 116165 58113 116165 58113 116166 58112 116166 58293 116166 58113 116167 58293 116167 58396 116167 58396 116168 58293 116168 58114 116168 58396 116169 58114 116169 58436 116169 58436 116170 58114 116170 58115 116170 58436 116171 58115 116171 58116 116171 58116 116172 58115 116172 58117 116172 58116 116173 58117 116173 58435 116173 58435 116174 58117 116174 58120 116174 58435 116175 58120 116175 58118 116175 58127 116176 58128 116176 58119 116176 58119 116177 58128 116177 58118 116177 58119 116178 58118 116178 58290 116178 58290 116179 58118 116179 58120 116179 58121 116180 58385 116180 58122 116180 58122 116181 58385 116181 58123 116181 58122 116182 58123 116182 58287 116182 58287 116183 58123 116183 58408 116183 58287 116184 58408 116184 58124 116184 58124 116185 58408 116185 58125 116185 58124 116186 58125 116186 58126 116186 58126 116187 58125 116187 58398 116187 58126 116188 58398 116188 58289 116188 58289 116189 58398 116189 58413 116189 58289 116190 58413 116190 58127 116190 58127 116191 58413 116191 58420 116191 58127 116192 58420 116192 58128 116192 58385 116193 58121 116193 58129 116193 58129 116194 58121 116194 58278 116194 58129 116195 58278 116195 58513 116195 58513 116196 58278 116196 58130 116196 58513 116197 58130 116197 58514 116197 58514 116198 58130 116198 58191 116198 58514 116199 58191 116199 58131 116199 58131 116200 58191 116200 58132 116200 58131 116201 58132 116201 58506 116201 58506 116202 58132 116202 58195 116202 58506 116203 58195 116203 58133 116203 58133 116204 58195 116204 58193 116204 58133 116205 58193 116205 58134 116205 58134 116206 58193 116206 58135 116206 58134 116207 58135 116207 58458 116207 58458 116208 58135 116208 58136 116208 58458 116209 58136 116209 58138 116209 58188 116210 58495 116210 58137 116210 58137 116211 58495 116211 58138 116211 58137 116212 58138 116212 58139 116212 58139 116213 58138 116213 58136 116213 58185 116214 58141 116214 58140 116214 58140 116215 58141 116215 58142 116215 58140 116216 58142 116216 58183 116216 58183 116217 58142 116217 58143 116217 58183 116218 58143 116218 58144 116218 58144 116219 58143 116219 58483 116219 58144 116220 58483 116220 58186 116220 58186 116221 58483 116221 58482 116221 58186 116222 58482 116222 58187 116222 58187 116223 58482 116223 58459 116223 58187 116224 58459 116224 58188 116224 58188 116225 58459 116225 58145 116225 58188 116226 58145 116226 58495 116226 58141 116227 58185 116227 58537 116227 58537 116228 58185 116228 58146 116228 58537 116229 58146 116229 58147 116229 58147 116230 58146 116230 58148 116230 58147 116231 58148 116231 58149 116231 58149 116232 58148 116232 58237 116232 58149 116233 58237 116233 58150 116233 58150 116234 58237 116234 58152 116234 58150 116235 58152 116235 58151 116235 58151 116236 58152 116236 58153 116236 58151 116237 58153 116237 58590 116237 58590 116238 58153 116238 58154 116238 58590 116239 58154 116239 58155 116239 58155 116240 58154 116240 58239 116240 58155 116241 58239 116241 58546 116241 58546 116242 58239 116242 58159 116242 58546 116243 58159 116243 58156 116243 58236 116244 58570 116244 58157 116244 58157 116245 58570 116245 58156 116245 58157 116246 58156 116246 58158 116246 58158 116247 58156 116247 58159 116247 58233 116248 58166 116248 58160 116248 58160 116249 58166 116249 58161 116249 58160 116250 58161 116250 58231 116250 58231 116251 58161 116251 58559 116251 58231 116252 58559 116252 58229 116252 58229 116253 58559 116253 58162 116253 58229 116254 58162 116254 58228 116254 58228 116255 58162 116255 58163 116255 58228 116256 58163 116256 58164 116256 58164 116257 58163 116257 58165 116257 58164 116258 58165 116258 58236 116258 58236 116259 58165 116259 58572 116259 58236 116260 58572 116260 58570 116260 58166 116261 58233 116261 58677 116261 58677 116262 58233 116262 58167 116262 58677 116263 58167 116263 58675 116263 58675 116264 58167 116264 58343 116264 58675 116265 58343 116265 58665 116265 58665 116266 58343 116266 58342 116266 58665 116267 58342 116267 58607 116267 58607 116268 58342 116268 58168 116268 58607 116269 58168 116269 58658 116269 58658 116270 58168 116270 58169 116270 58658 116271 58169 116271 58170 116271 58170 116272 58169 116272 58340 116272 58170 116273 58340 116273 58171 116273 58171 116274 58340 116274 58338 116274 58171 116275 58338 116275 58653 116275 58653 116276 58338 116276 58172 116276 58653 116277 58172 116277 58175 116277 58173 116278 58647 116278 58174 116278 58174 116279 58647 116279 58175 116279 58174 116280 58175 116280 58337 116280 58337 116281 58175 116281 58172 116281 58333 116282 58176 116282 58332 116282 58332 116283 58176 116283 58619 116283 58332 116284 58619 116284 58330 116284 58330 116285 58619 116285 58623 116285 58330 116286 58623 116286 58328 116286 58328 116287 58623 116287 58621 116287 58328 116288 58621 116288 58334 116288 58334 116289 58621 116289 58177 116289 58334 116290 58177 116290 58335 116290 58335 116291 58177 116291 58608 116291 58335 116292 58608 116292 58173 116292 58173 116293 58608 116293 58633 116293 58173 116294 58633 116294 58647 116294 58176 116295 58333 116295 58545 116295 58545 116296 58333 116296 58178 116296 58179 116297 58036 116297 58262 116297 58179 116298 58262 116298 58208 116298 58208 116299 58262 116299 58261 116299 58208 116300 58261 116300 58197 116300 58197 116301 58261 116301 58181 116301 58197 116302 58181 116302 58180 116302 58180 116303 58181 116303 58146 116303 58180 116304 58146 116304 58185 116304 58179 116305 58208 116305 58215 116305 58208 116306 58197 116306 58209 116306 58197 116307 58180 116307 58184 116307 58186 116308 58198 116308 58144 116308 58144 116309 58198 116309 58182 116309 58144 116310 58182 116310 58183 116310 58183 116311 58182 116311 58184 116311 58183 116312 58184 116312 58140 116312 58140 116313 58184 116313 58180 116313 58140 116314 58180 116314 58185 116314 58186 116315 58187 116315 58198 116315 58198 116316 58187 116316 58188 116316 58198 116317 58188 116317 58200 116317 58200 116318 58188 116318 58137 116318 58200 116319 58137 116319 58189 116319 58189 116320 58137 116320 58139 116320 58189 116321 58139 116321 58190 116321 58191 116322 58196 116322 58205 116322 58139 116323 58136 116323 58190 116323 58190 116324 58136 116324 58135 116324 58190 116325 58135 116325 58192 116325 58192 116326 58135 116326 58193 116326 58192 116327 58193 116327 58194 116327 58194 116328 58193 116328 58195 116328 58194 116329 58195 116329 58205 116329 58205 116330 58195 116330 58132 116330 58205 116331 58132 116331 58191 116331 58191 116332 58130 116332 58196 116332 58196 116333 58130 116333 58278 116333 58196 116334 58278 116334 58277 116334 58197 116335 58184 116335 58209 116335 58209 116336 58184 116336 58182 116336 58209 116337 58182 116337 58210 116337 58210 116338 58182 116338 58198 116338 58210 116339 58198 116339 58199 116339 58199 116340 58198 116340 58200 116340 58199 116341 58200 116341 58201 116341 58201 116342 58200 116342 58189 116342 58201 116343 58189 116343 58212 116343 58212 116344 58189 116344 58190 116344 58212 116345 58190 116345 58202 116345 58202 116346 58190 116346 58192 116346 58202 116347 58192 116347 58203 116347 58203 116348 58192 116348 58194 116348 58203 116349 58194 116349 58204 116349 58204 116350 58194 116350 58205 116350 58204 116351 58205 116351 58206 116351 58206 116352 58205 116352 58196 116352 58206 116353 58196 116353 58207 116353 58207 116354 58196 116354 58277 116354 58207 116355 58277 116355 58275 116355 58208 116356 58209 116356 58215 116356 58215 116357 58209 116357 58210 116357 58215 116358 58210 116358 58216 116358 58216 116359 58210 116359 58199 116359 58216 116360 58199 116360 58218 116360 58218 116361 58199 116361 58201 116361 58218 116362 58201 116362 58211 116362 58211 116363 58201 116363 58212 116363 58211 116364 58212 116364 58220 116364 58220 116365 58212 116365 58202 116365 58220 116366 58202 116366 58221 116366 58221 116367 58202 116367 58203 116367 58221 116368 58203 116368 58222 116368 58222 116369 58203 116369 58204 116369 58222 116370 58204 116370 58213 116370 58213 116371 58204 116371 58206 116371 58213 116372 58206 116372 58223 116372 58223 116373 58206 116373 58207 116373 58223 116374 58207 116374 58214 116374 58214 116375 58207 116375 58275 116375 58214 116376 58275 116376 58274 116376 58179 116377 58215 116377 58037 116377 58037 116378 58215 116378 58216 116378 58037 116379 58216 116379 58217 116379 58217 116380 58216 116380 58218 116380 58217 116381 58218 116381 58017 116381 58017 116382 58218 116382 58211 116382 58017 116383 58211 116383 58033 116383 58033 116384 58211 116384 58220 116384 58033 116385 58220 116385 58219 116385 58219 116386 58220 116386 58221 116386 58219 116387 58221 116387 58035 116387 58035 116388 58221 116388 58222 116388 58035 116389 58222 116389 58016 116389 58016 116390 58222 116390 58213 116390 58016 116391 58213 116391 58224 116391 58224 116392 58213 116392 58223 116392 58224 116393 58223 116393 58026 116393 58026 116394 58223 116394 58214 116394 58026 116395 58214 116395 58225 116395 58225 116396 58214 116396 58274 116396 58225 116397 58274 116397 58025 116397 58013 116398 58226 116398 58249 116398 58226 116399 58280 116399 58248 116399 58280 116400 58232 116400 58227 116400 58228 116401 58234 116401 58229 116401 58229 116402 58234 116402 58230 116402 58229 116403 58230 116403 58231 116403 58231 116404 58230 116404 58227 116404 58231 116405 58227 116405 58160 116405 58160 116406 58227 116406 58232 116406 58160 116407 58232 116407 58233 116407 58228 116408 58164 116408 58234 116408 58234 116409 58164 116409 58236 116409 58234 116410 58236 116410 58235 116410 58235 116411 58236 116411 58157 116411 58235 116412 58157 116412 58242 116412 58242 116413 58157 116413 58158 116413 58242 116414 58158 116414 58238 116414 58237 116415 58247 116415 58245 116415 58158 116416 58159 116416 58238 116416 58238 116417 58159 116417 58239 116417 58238 116418 58239 116418 58243 116418 58243 116419 58239 116419 58154 116419 58243 116420 58154 116420 58244 116420 58244 116421 58154 116421 58153 116421 58244 116422 58153 116422 58245 116422 58245 116423 58153 116423 58152 116423 58245 116424 58152 116424 58237 116424 58237 116425 58148 116425 58247 116425 58247 116426 58148 116426 58146 116426 58247 116427 58146 116427 58181 116427 58280 116428 58227 116428 58248 116428 58248 116429 58227 116429 58230 116429 58248 116430 58230 116430 58240 116430 58240 116431 58230 116431 58234 116431 58240 116432 58234 116432 58251 116432 58251 116433 58234 116433 58235 116433 58251 116434 58235 116434 58241 116434 58241 116435 58235 116435 58242 116435 58241 116436 58242 116436 58252 116436 58252 116437 58242 116437 58238 116437 58252 116438 58238 116438 58254 116438 58254 116439 58238 116439 58243 116439 58254 116440 58243 116440 58256 116440 58256 116441 58243 116441 58244 116441 58256 116442 58244 116442 58258 116442 58258 116443 58244 116443 58245 116443 58258 116444 58245 116444 58246 116444 58246 116445 58245 116445 58247 116445 58246 116446 58247 116446 58260 116446 58260 116447 58247 116447 58181 116447 58260 116448 58181 116448 58261 116448 58226 116449 58248 116449 58249 116449 58249 116450 58248 116450 58240 116450 58249 116451 58240 116451 58250 116451 58250 116452 58240 116452 58251 116452 58250 116453 58251 116453 58265 116453 58265 116454 58251 116454 58241 116454 58265 116455 58241 116455 58266 116455 58266 116456 58241 116456 58252 116456 58266 116457 58252 116457 58253 116457 58253 116458 58252 116458 58254 116458 58253 116459 58254 116459 58255 116459 58255 116460 58254 116460 58256 116460 58255 116461 58256 116461 58257 116461 58257 116462 58256 116462 58258 116462 58257 116463 58258 116463 58259 116463 58259 116464 58258 116464 58246 116464 58259 116465 58246 116465 58272 116465 58272 116466 58246 116466 58260 116466 58272 116467 58260 116467 58273 116467 58273 116468 58260 116468 58261 116468 58273 116469 58261 116469 58262 116469 58013 116470 58249 116470 58263 116470 58263 116471 58249 116471 58250 116471 58263 116472 58250 116472 58264 116472 58264 116473 58250 116473 58265 116473 58264 116474 58265 116474 58267 116474 58267 116475 58265 116475 58266 116475 58267 116476 58266 116476 58268 116476 58268 116477 58266 116477 58253 116477 58268 116478 58253 116478 58019 116478 58019 116479 58253 116479 58255 116479 58019 116480 58255 116480 58269 116480 58269 116481 58255 116481 58257 116481 58269 116482 58257 116482 58270 116482 58270 116483 58257 116483 58259 116483 58270 116484 58259 116484 58271 116484 58271 116485 58259 116485 58272 116485 58271 116486 58272 116486 58051 116486 58051 116487 58272 116487 58273 116487 58051 116488 58273 116488 58042 116488 58042 116489 58273 116489 58262 116489 58042 116490 58262 116490 58036 116490 58317 116491 58025 116491 58274 116491 58317 116492 58274 116492 58276 116492 58276 116493 58274 116493 58275 116493 58276 116494 58275 116494 58282 116494 58282 116495 58275 116495 58277 116495 58282 116496 58277 116496 58288 116496 58288 116497 58277 116497 58278 116497 58288 116498 58278 116498 58121 116498 58013 116499 58044 116499 58279 116499 58013 116500 58279 116500 58226 116500 58226 116501 58279 116501 58281 116501 58226 116502 58281 116502 58280 116502 58280 116503 58281 116503 58354 116503 58280 116504 58354 116504 58232 116504 58232 116505 58354 116505 58167 116505 58232 116506 58167 116506 58233 116506 58317 116507 58276 116507 58318 116507 58276 116508 58282 116508 58283 116508 58282 116509 58288 116509 58284 116509 58126 116510 58285 116510 58124 116510 58124 116511 58285 116511 58286 116511 58124 116512 58286 116512 58287 116512 58287 116513 58286 116513 58284 116513 58287 116514 58284 116514 58122 116514 58122 116515 58284 116515 58288 116515 58122 116516 58288 116516 58121 116516 58126 116517 58289 116517 58285 116517 58285 116518 58289 116518 58127 116518 58285 116519 58127 116519 58295 116519 58295 116520 58127 116520 58119 116520 58295 116521 58119 116521 58298 116521 58298 116522 58119 116522 58290 116522 58298 116523 58290 116523 58299 116523 58112 116524 58294 116524 58292 116524 58290 116525 58120 116525 58299 116525 58299 116526 58120 116526 58117 116526 58299 116527 58117 116527 58291 116527 58291 116528 58117 116528 58115 116528 58291 116529 58115 116529 58301 116529 58301 116530 58115 116530 58114 116530 58301 116531 58114 116531 58292 116531 58292 116532 58114 116532 58293 116532 58292 116533 58293 116533 58112 116533 58112 116534 58110 116534 58294 116534 58294 116535 58110 116535 58377 116535 58294 116536 58377 116536 58304 116536 58282 116537 58284 116537 58283 116537 58283 116538 58284 116538 58286 116538 58283 116539 58286 116539 58305 116539 58305 116540 58286 116540 58285 116540 58305 116541 58285 116541 58296 116541 58296 116542 58285 116542 58295 116542 58296 116543 58295 116543 58297 116543 58297 116544 58295 116544 58298 116544 58297 116545 58298 116545 58309 116545 58309 116546 58298 116546 58299 116546 58309 116547 58299 116547 58300 116547 58300 116548 58299 116548 58291 116548 58300 116549 58291 116549 58311 116549 58311 116550 58291 116550 58301 116550 58311 116551 58301 116551 58302 116551 58302 116552 58301 116552 58292 116552 58302 116553 58292 116553 58314 116553 58314 116554 58292 116554 58294 116554 58314 116555 58294 116555 58303 116555 58303 116556 58294 116556 58304 116556 58303 116557 58304 116557 58315 116557 58276 116558 58283 116558 58318 116558 58318 116559 58283 116559 58305 116559 58318 116560 58305 116560 58306 116560 58306 116561 58305 116561 58296 116561 58306 116562 58296 116562 58307 116562 58307 116563 58296 116563 58297 116563 58307 116564 58297 116564 58308 116564 58308 116565 58297 116565 58309 116565 58308 116566 58309 116566 58320 116566 58320 116567 58309 116567 58300 116567 58320 116568 58300 116568 58310 116568 58310 116569 58300 116569 58311 116569 58310 116570 58311 116570 58312 116570 58312 116571 58311 116571 58302 116571 58312 116572 58302 116572 58313 116572 58313 116573 58302 116573 58314 116573 58313 116574 58314 116574 58324 116574 58324 116575 58314 116575 58303 116575 58324 116576 58303 116576 58316 116576 58316 116577 58303 116577 58315 116577 58316 116578 58315 116578 58326 116578 58317 116579 58318 116579 58048 116579 58048 116580 58318 116580 58306 116580 58048 116581 58306 116581 58049 116581 58049 116582 58306 116582 58307 116582 58049 116583 58307 116583 58319 116583 58319 116584 58307 116584 58308 116584 58319 116585 58308 116585 58045 116585 58045 116586 58308 116586 58320 116586 58045 116587 58320 116587 58321 116587 58321 116588 58320 116588 58310 116588 58321 116589 58310 116589 58322 116589 58322 116590 58310 116590 58312 116590 58322 116591 58312 116591 58047 116591 58047 116592 58312 116592 58313 116592 58047 116593 58313 116593 58323 116593 58323 116594 58313 116594 58324 116594 58323 116595 58324 116595 58325 116595 58325 116596 58324 116596 58316 116596 58325 116597 58316 116597 58023 116597 58023 116598 58316 116598 58326 116598 58023 116599 58326 116599 58376 116599 58378 116600 58381 116600 58365 116600 58381 116601 58383 116601 58356 116601 58383 116602 58331 116602 58329 116602 58334 116603 58327 116603 58328 116603 58328 116604 58327 116604 58345 116604 58328 116605 58345 116605 58330 116605 58330 116606 58345 116606 58329 116606 58330 116607 58329 116607 58332 116607 58332 116608 58329 116608 58331 116608 58332 116609 58331 116609 58333 116609 58334 116610 58335 116610 58327 116610 58327 116611 58335 116611 58173 116611 58327 116612 58173 116612 58347 116612 58347 116613 58173 116613 58174 116613 58347 116614 58174 116614 58336 116614 58336 116615 58174 116615 58337 116615 58336 116616 58337 116616 58350 116616 58342 116617 58344 116617 58341 116617 58337 116618 58172 116618 58350 116618 58350 116619 58172 116619 58338 116619 58350 116620 58338 116620 58339 116620 58339 116621 58338 116621 58340 116621 58339 116622 58340 116622 58351 116622 58351 116623 58340 116623 58169 116623 58351 116624 58169 116624 58341 116624 58341 116625 58169 116625 58168 116625 58341 116626 58168 116626 58342 116626 58342 116627 58343 116627 58344 116627 58344 116628 58343 116628 58167 116628 58344 116629 58167 116629 58354 116629 58383 116630 58329 116630 58356 116630 58356 116631 58329 116631 58345 116631 58356 116632 58345 116632 58357 116632 58357 116633 58345 116633 58327 116633 58357 116634 58327 116634 58346 116634 58346 116635 58327 116635 58347 116635 58346 116636 58347 116636 58348 116636 58348 116637 58347 116637 58336 116637 58348 116638 58336 116638 58349 116638 58349 116639 58336 116639 58350 116639 58349 116640 58350 116640 58360 116640 58360 116641 58350 116641 58339 116641 58360 116642 58339 116642 58362 116642 58362 116643 58339 116643 58351 116643 58362 116644 58351 116644 58352 116644 58352 116645 58351 116645 58341 116645 58352 116646 58341 116646 58353 116646 58353 116647 58341 116647 58344 116647 58353 116648 58344 116648 58355 116648 58355 116649 58344 116649 58354 116649 58355 116650 58354 116650 58281 116650 58381 116651 58356 116651 58365 116651 58365 116652 58356 116652 58357 116652 58365 116653 58357 116653 58366 116653 58366 116654 58357 116654 58346 116654 58366 116655 58346 116655 58358 116655 58358 116656 58346 116656 58348 116656 58358 116657 58348 116657 58359 116657 58359 116658 58348 116658 58349 116658 58359 116659 58349 116659 58369 116659 58369 116660 58349 116660 58360 116660 58369 116661 58360 116661 58361 116661 58361 116662 58360 116662 58362 116662 58361 116663 58362 116663 58371 116663 58371 116664 58362 116664 58352 116664 58371 116665 58352 116665 58363 116665 58363 116666 58352 116666 58353 116666 58363 116667 58353 116667 58364 116667 58364 116668 58353 116668 58355 116668 58364 116669 58355 116669 58374 116669 58374 116670 58355 116670 58281 116670 58374 116671 58281 116671 58279 116671 58378 116672 58365 116672 58367 116672 58367 116673 58365 116673 58366 116673 58367 116674 58366 116674 58055 116674 58055 116675 58366 116675 58358 116675 58055 116676 58358 116676 58368 116676 58368 116677 58358 116677 58359 116677 58368 116678 58359 116678 58067 116678 58067 116679 58359 116679 58369 116679 58067 116680 58369 116680 58030 116680 58030 116681 58369 116681 58361 116681 58030 116682 58361 116682 58370 116682 58370 116683 58361 116683 58371 116683 58370 116684 58371 116684 58021 116684 58021 116685 58371 116685 58363 116685 58021 116686 58363 116686 58372 116686 58372 116687 58363 116687 58364 116687 58372 116688 58364 116688 58373 116688 58373 116689 58364 116689 58374 116689 58373 116690 58374 116690 58375 116690 58375 116691 58374 116691 58279 116691 58375 116692 58279 116692 58044 116692 58379 116693 58376 116693 58326 116693 58379 116694 58326 116694 58380 116694 58380 116695 58326 116695 58315 116695 58380 116696 58315 116696 58382 116696 58382 116697 58315 116697 58304 116697 58382 116698 58304 116698 58384 116698 58384 116699 58304 116699 58377 116699 58384 116700 58377 116700 58178 116700 58378 116701 58379 116701 58380 116701 58378 116702 58380 116702 58381 116702 58381 116703 58380 116703 58382 116703 58381 116704 58382 116704 58383 116704 58383 116705 58382 116705 58384 116705 58383 116706 58384 116706 58331 116706 58331 116707 58384 116707 58178 116707 58331 116708 58178 116708 58333 116708 58385 116709 58129 116709 58406 116709 58406 116710 58129 116710 58386 116710 58406 116711 58386 116711 58387 116711 58387 116712 58386 116712 58521 116712 58387 116713 58521 116713 58389 116713 58389 116714 58521 116714 58388 116714 58389 116715 58388 116715 58390 116715 58390 116716 58388 116716 58392 116716 58390 116717 58392 116717 58391 116717 58391 116718 58392 116718 58393 116718 58391 116719 58393 116719 58394 116719 58394 116720 58393 116720 58468 116720 58394 116721 58468 116721 58395 116721 58395 116722 58468 116722 58467 116722 58395 116723 58467 116723 58090 116723 58090 116724 58467 116724 58461 116724 58111 116725 58113 116725 58449 116725 58396 116726 58436 116726 58437 116726 58116 116727 58435 116727 58397 116727 58420 116728 58413 116728 58421 116728 58398 116729 58125 116729 58407 116729 58408 116730 58123 116730 58410 116730 58451 116731 58452 116731 58523 116731 58090 116732 58399 116732 58395 116732 58395 116733 58399 116733 58412 116733 58395 116734 58412 116734 58394 116734 58394 116735 58412 116735 58405 116735 58523 116736 58524 116736 58451 116736 58451 116737 58524 116737 58525 116737 58451 116738 58525 116738 58400 116738 58400 116739 58525 116739 58401 116739 58400 116740 58401 116740 58402 116740 58402 116741 58401 116741 58526 116741 58402 116742 58526 116742 58455 116742 58410 116743 58387 116743 58403 116743 58403 116744 58387 116744 58389 116744 58403 116745 58389 116745 58404 116745 58404 116746 58389 116746 58390 116746 58404 116747 58390 116747 58405 116747 58405 116748 58390 116748 58391 116748 58405 116749 58391 116749 58394 116749 58123 116750 58385 116750 58410 116750 58410 116751 58385 116751 58406 116751 58410 116752 58406 116752 58387 116752 58125 116753 58408 116753 58407 116753 58407 116754 58408 116754 58410 116754 58407 116755 58410 116755 58409 116755 58409 116756 58410 116756 58403 116756 58409 116757 58403 116757 58411 116757 58411 116758 58403 116758 58404 116758 58411 116759 58404 116759 58416 116759 58416 116760 58404 116760 58405 116760 58416 116761 58405 116761 58417 116761 58417 116762 58405 116762 58412 116762 58417 116763 58412 116763 58092 116763 58092 116764 58412 116764 58399 116764 58413 116765 58398 116765 58421 116765 58421 116766 58398 116766 58407 116766 58421 116767 58407 116767 58414 116767 58414 116768 58407 116768 58409 116768 58414 116769 58409 116769 58415 116769 58415 116770 58409 116770 58411 116770 58415 116771 58411 116771 58424 116771 58424 116772 58411 116772 58416 116772 58424 116773 58416 116773 58418 116773 58418 116774 58416 116774 58417 116774 58418 116775 58417 116775 58419 116775 58419 116776 58417 116776 58092 116776 58128 116777 58420 116777 58429 116777 58429 116778 58420 116778 58421 116778 58429 116779 58421 116779 58422 116779 58422 116780 58421 116780 58414 116780 58422 116781 58414 116781 58423 116781 58423 116782 58414 116782 58415 116782 58423 116783 58415 116783 58427 116783 58427 116784 58415 116784 58424 116784 58427 116785 58424 116785 58425 116785 58425 116786 58424 116786 58418 116786 58425 116787 58418 116787 58105 116787 58105 116788 58418 116788 58419 116788 58105 116789 58426 116789 58425 116789 58425 116790 58426 116790 58431 116790 58425 116791 58431 116791 58427 116791 58427 116792 58431 116792 58432 116792 58427 116793 58432 116793 58423 116793 58423 116794 58432 116794 58428 116794 58423 116795 58428 116795 58422 116795 58422 116796 58428 116796 58433 116796 58422 116797 58433 116797 58429 116797 58429 116798 58433 116798 58430 116798 58429 116799 58430 116799 58128 116799 58128 116800 58430 116800 58118 116800 58426 116801 58442 116801 58431 116801 58431 116802 58442 116802 58441 116802 58431 116803 58441 116803 58432 116803 58432 116804 58441 116804 58440 116804 58432 116805 58440 116805 58428 116805 58428 116806 58440 116806 58434 116806 58428 116807 58434 116807 58433 116807 58433 116808 58434 116808 58438 116808 58433 116809 58438 116809 58430 116809 58430 116810 58438 116810 58397 116810 58430 116811 58397 116811 58118 116811 58118 116812 58397 116812 58435 116812 58436 116813 58116 116813 58437 116813 58437 116814 58116 116814 58397 116814 58437 116815 58397 116815 58443 116815 58443 116816 58397 116816 58438 116816 58443 116817 58438 116817 58445 116817 58445 116818 58438 116818 58434 116818 58445 116819 58434 116819 58447 116819 58447 116820 58434 116820 58440 116820 58447 116821 58440 116821 58439 116821 58439 116822 58440 116822 58441 116822 58439 116823 58441 116823 58103 116823 58103 116824 58441 116824 58442 116824 58113 116825 58396 116825 58449 116825 58449 116826 58396 116826 58437 116826 58449 116827 58437 116827 58444 116827 58444 116828 58437 116828 58443 116828 58444 116829 58443 116829 58450 116829 58450 116830 58443 116830 58445 116830 58450 116831 58445 116831 58446 116831 58446 116832 58445 116832 58447 116832 58446 116833 58447 116833 58453 116833 58453 116834 58447 116834 58439 116834 58453 116835 58439 116835 58102 116835 58102 116836 58439 116836 58103 116836 58456 116837 58111 116837 58448 116837 58448 116838 58111 116838 58449 116838 58448 116839 58449 116839 58455 116839 58455 116840 58449 116840 58444 116840 58455 116841 58444 116841 58402 116841 58402 116842 58444 116842 58450 116842 58402 116843 58450 116843 58400 116843 58400 116844 58450 116844 58446 116844 58400 116845 58446 116845 58451 116845 58451 116846 58446 116846 58453 116846 58451 116847 58453 116847 58452 116847 58452 116848 58453 116848 58102 116848 58526 116849 58454 116849 58455 116849 58455 116850 58454 116850 58528 116850 58455 116851 58528 116851 58448 116851 58448 116852 58528 116852 58457 116852 58448 116853 58457 116853 58456 116853 58456 116854 58457 116854 58109 116854 58514 116855 58131 116855 58507 116855 58506 116856 58133 116856 58508 116856 58134 116857 58458 116857 58501 116857 58145 116858 58459 116858 58484 116858 58143 116859 58142 116859 58460 116859 58466 116860 58519 116860 58461 116860 58086 116861 58463 116861 58462 116861 58462 116862 58463 116862 58464 116862 58462 116863 58464 116863 58465 116863 58465 116864 58464 116864 58479 116864 58461 116865 58467 116865 58466 116865 58466 116866 58467 116866 58468 116866 58466 116867 58468 116867 58517 116867 58517 116868 58468 116868 58393 116868 58517 116869 58393 116869 58469 116869 58469 116870 58393 116870 58392 116870 58469 116871 58392 116871 58515 116871 58460 116872 58476 116872 58477 116872 58477 116873 58476 116873 58533 116873 58477 116874 58533 116874 58470 116874 58470 116875 58533 116875 58532 116875 58470 116876 58532 116876 58479 116876 58479 116877 58532 116877 58530 116877 58479 116878 58530 116878 58465 116878 58480 116879 58471 116879 58472 116879 58472 116880 58471 116880 58489 116880 58472 116881 58489 116881 58478 116881 58478 116882 58489 116882 58488 116882 58478 116883 58488 116883 58473 116883 58473 116884 58488 116884 58475 116884 58473 116885 58475 116885 58474 116885 58474 116886 58475 116886 58486 116886 58474 116887 58486 116887 58481 116887 58481 116888 58486 116888 58484 116888 58142 116889 58141 116889 58460 116889 58460 116890 58141 116890 58538 116890 58460 116891 58538 116891 58476 116891 58483 116892 58143 116892 58481 116892 58481 116893 58143 116893 58460 116893 58481 116894 58460 116894 58474 116894 58474 116895 58460 116895 58477 116895 58474 116896 58477 116896 58473 116896 58473 116897 58477 116897 58470 116897 58473 116898 58470 116898 58478 116898 58478 116899 58470 116899 58479 116899 58478 116900 58479 116900 58472 116900 58472 116901 58479 116901 58464 116901 58472 116902 58464 116902 58480 116902 58480 116903 58464 116903 58463 116903 58484 116904 58459 116904 58481 116904 58481 116905 58459 116905 58482 116905 58481 116906 58482 116906 58483 116906 58495 116907 58145 116907 58494 116907 58494 116908 58145 116908 58484 116908 58494 116909 58484 116909 58485 116909 58485 116910 58484 116910 58486 116910 58485 116911 58486 116911 58487 116911 58487 116912 58486 116912 58475 116912 58487 116913 58475 116913 58492 116913 58492 116914 58475 116914 58488 116914 58492 116915 58488 116915 58490 116915 58490 116916 58488 116916 58489 116916 58490 116917 58489 116917 58084 116917 58084 116918 58489 116918 58471 116918 58084 116919 58083 116919 58490 116919 58490 116920 58083 116920 58491 116920 58490 116921 58491 116921 58492 116921 58492 116922 58491 116922 58493 116922 58492 116923 58493 116923 58487 116923 58487 116924 58493 116924 58498 116924 58487 116925 58498 116925 58485 116925 58485 116926 58498 116926 58499 116926 58485 116927 58499 116927 58494 116927 58494 116928 58499 116928 58500 116928 58494 116929 58500 116929 58495 116929 58495 116930 58500 116930 58138 116930 58083 116931 58082 116931 58491 116931 58491 116932 58082 116932 58496 116932 58491 116933 58496 116933 58493 116933 58493 116934 58496 116934 58504 116934 58493 116935 58504 116935 58498 116935 58498 116936 58504 116936 58497 116936 58498 116937 58497 116937 58499 116937 58499 116938 58497 116938 58502 116938 58499 116939 58502 116939 58500 116939 58500 116940 58502 116940 58501 116940 58500 116941 58501 116941 58138 116941 58138 116942 58501 116942 58458 116942 58133 116943 58134 116943 58508 116943 58508 116944 58134 116944 58501 116944 58508 116945 58501 116945 58510 116945 58510 116946 58501 116946 58502 116946 58510 116947 58502 116947 58503 116947 58503 116948 58502 116948 58497 116948 58503 116949 58497 116949 58512 116949 58512 116950 58497 116950 58504 116950 58512 116951 58504 116951 58505 116951 58505 116952 58504 116952 58496 116952 58505 116953 58496 116953 58081 116953 58081 116954 58496 116954 58082 116954 58131 116955 58506 116955 58507 116955 58507 116956 58506 116956 58508 116956 58507 116957 58508 116957 58509 116957 58509 116958 58508 116958 58510 116958 58509 116959 58510 116959 58516 116959 58516 116960 58510 116960 58503 116960 58516 116961 58503 116961 58511 116961 58511 116962 58503 116962 58512 116962 58511 116963 58512 116963 58518 116963 58518 116964 58512 116964 58505 116964 58518 116965 58505 116965 58520 116965 58520 116966 58505 116966 58081 116966 58513 116967 58514 116967 58522 116967 58522 116968 58514 116968 58507 116968 58522 116969 58507 116969 58515 116969 58515 116970 58507 116970 58509 116970 58515 116971 58509 116971 58469 116971 58469 116972 58509 116972 58516 116972 58469 116973 58516 116973 58517 116973 58517 116974 58516 116974 58511 116974 58517 116975 58511 116975 58466 116975 58466 116976 58511 116976 58518 116976 58466 116977 58518 116977 58519 116977 58519 116978 58518 116978 58520 116978 58392 116979 58388 116979 58515 116979 58515 116980 58388 116980 58521 116980 58515 116981 58521 116981 58522 116981 58522 116982 58521 116982 58386 116982 58522 116983 58386 116983 58513 116983 58513 116984 58386 116984 58129 116984 58523 116985 58096 116985 58524 116985 58524 116986 58096 116986 58541 116986 58524 116987 58541 116987 58525 116987 58525 116988 58541 116988 58401 116988 58401 116989 58541 116989 58542 116989 58401 116990 58542 116990 58526 116990 58526 116991 58542 116991 58454 116991 58454 116992 58542 116992 58527 116992 58454 116993 58527 116993 58528 116993 58528 116994 58527 116994 58457 116994 58457 116995 58527 116995 58545 116995 58457 116996 58545 116996 58109 116996 58078 116997 58086 116997 58550 116997 58550 116998 58086 116998 58462 116998 58550 116999 58462 116999 58529 116999 58529 117000 58462 117000 58465 117000 58529 117001 58465 117001 58531 117001 58531 117002 58465 117002 58530 117002 58531 117003 58530 117003 58552 117003 58552 117004 58530 117004 58532 117004 58552 117005 58532 117005 58534 117005 58534 117006 58532 117006 58533 117006 58534 117007 58533 117007 58535 117007 58535 117008 58533 117008 58476 117008 58535 117009 58476 117009 58536 117009 58536 117010 58476 117010 58538 117010 58536 117011 58538 117011 58537 117011 58537 117012 58538 117012 58141 117012 58609 117013 58539 117013 58096 117013 58096 117014 58539 117014 58541 117014 58539 117015 58618 117015 58541 117015 58541 117016 58618 117016 58540 117016 58541 117017 58540 117017 58542 117017 58540 117018 58543 117018 58542 117018 58542 117019 58543 117019 58544 117019 58542 117020 58544 117020 58527 117020 58176 117021 58545 117021 58620 117021 58620 117022 58545 117022 58527 117022 58620 117023 58527 117023 58616 117023 58616 117024 58527 117024 58544 117024 58149 117025 58150 117025 58596 117025 58151 117026 58590 117026 58591 117026 58155 117027 58546 117027 58589 117027 58572 117028 58165 117028 58573 117028 58163 117029 58162 117029 58563 117029 58559 117030 58161 117030 58558 117030 58547 117031 58604 117031 58078 117031 58097 117032 58099 117032 58548 117032 58548 117033 58099 117033 58562 117033 58548 117034 58562 117034 58681 117034 58681 117035 58562 117035 58549 117035 58078 117036 58550 117036 58547 117036 58547 117037 58550 117037 58529 117037 58547 117038 58529 117038 58603 117038 58603 117039 58529 117039 58531 117039 58603 117040 58531 117040 58551 117040 58551 117041 58531 117041 58552 117041 58551 117042 58552 117042 58605 117042 58558 117043 58554 117043 58553 117043 58553 117044 58554 117044 58556 117044 58553 117045 58556 117045 58555 117045 58555 117046 58556 117046 58557 117046 58555 117047 58557 117047 58549 117047 58549 117048 58557 117048 58680 117048 58549 117049 58680 117049 58681 117049 58161 117050 58166 117050 58558 117050 58558 117051 58166 117051 58676 117051 58558 117052 58676 117052 58554 117052 58162 117053 58559 117053 58563 117053 58563 117054 58559 117054 58558 117054 58563 117055 58558 117055 58560 117055 58560 117056 58558 117056 58553 117056 58560 117057 58553 117057 58566 117057 58566 117058 58553 117058 58555 117058 58566 117059 58555 117059 58567 117059 58567 117060 58555 117060 58549 117060 58567 117061 58549 117061 58568 117061 58568 117062 58549 117062 58562 117062 58568 117063 58562 117063 58561 117063 58561 117064 58562 117064 58099 117064 58165 117065 58163 117065 58573 117065 58573 117066 58163 117066 58563 117066 58573 117067 58563 117067 58574 117067 58574 117068 58563 117068 58560 117068 58574 117069 58560 117069 58564 117069 58564 117070 58560 117070 58566 117070 58564 117071 58566 117071 58565 117071 58565 117072 58566 117072 58567 117072 58565 117073 58567 117073 58575 117073 58575 117074 58567 117074 58568 117074 58575 117075 58568 117075 58569 117075 58569 117076 58568 117076 58561 117076 58570 117077 58572 117077 58571 117077 58571 117078 58572 117078 58573 117078 58571 117079 58573 117079 58581 117079 58581 117080 58573 117080 58574 117080 58581 117081 58574 117081 58580 117081 58580 117082 58574 117082 58564 117082 58580 117083 58564 117083 58579 117083 58579 117084 58564 117084 58565 117084 58579 117085 58565 117085 58578 117085 58578 117086 58565 117086 58575 117086 58578 117087 58575 117087 58576 117087 58576 117088 58575 117088 58569 117088 58576 117089 58577 117089 58578 117089 58578 117090 58577 117090 58584 117090 58578 117091 58584 117091 58579 117091 58579 117092 58584 117092 58585 117092 58579 117093 58585 117093 58580 117093 58580 117094 58585 117094 58586 117094 58580 117095 58586 117095 58581 117095 58581 117096 58586 117096 58582 117096 58581 117097 58582 117097 58571 117097 58571 117098 58582 117098 58583 117098 58571 117099 58583 117099 58570 117099 58570 117100 58583 117100 58156 117100 58577 117101 58073 117101 58584 117101 58584 117102 58073 117102 58595 117102 58584 117103 58595 117103 58585 117103 58585 117104 58595 117104 58587 117104 58585 117105 58587 117105 58586 117105 58586 117106 58587 117106 58592 117106 58586 117107 58592 117107 58582 117107 58582 117108 58592 117108 58588 117108 58582 117109 58588 117109 58583 117109 58583 117110 58588 117110 58589 117110 58583 117111 58589 117111 58156 117111 58156 117112 58589 117112 58546 117112 58590 117113 58155 117113 58591 117113 58591 117114 58155 117114 58589 117114 58591 117115 58589 117115 58598 117115 58598 117116 58589 117116 58588 117116 58598 117117 58588 117117 58599 117117 58599 117118 58588 117118 58592 117118 58599 117119 58592 117119 58593 117119 58593 117120 58592 117120 58587 117120 58593 117121 58587 117121 58594 117121 58594 117122 58587 117122 58595 117122 58594 117123 58595 117123 58075 117123 58075 117124 58595 117124 58073 117124 58150 117125 58151 117125 58596 117125 58596 117126 58151 117126 58591 117126 58596 117127 58591 117127 58597 117127 58597 117128 58591 117128 58598 117128 58597 117129 58598 117129 58602 117129 58602 117130 58598 117130 58599 117130 58602 117131 58599 117131 58600 117131 58600 117132 58599 117132 58593 117132 58600 117133 58593 117133 58601 117133 58601 117134 58593 117134 58594 117134 58601 117135 58594 117135 58076 117135 58076 117136 58594 117136 58075 117136 58147 117137 58149 117137 58606 117137 58606 117138 58149 117138 58596 117138 58606 117139 58596 117139 58605 117139 58605 117140 58596 117140 58597 117140 58605 117141 58597 117141 58551 117141 58551 117142 58597 117142 58602 117142 58551 117143 58602 117143 58603 117143 58603 117144 58602 117144 58600 117144 58603 117145 58600 117145 58547 117145 58547 117146 58600 117146 58601 117146 58547 117147 58601 117147 58604 117147 58604 117148 58601 117148 58076 117148 58552 117149 58534 117149 58605 117149 58605 117150 58534 117150 58535 117150 58605 117151 58535 117151 58606 117151 58606 117152 58535 117152 58536 117152 58606 117153 58536 117153 58147 117153 58147 117154 58536 117154 58537 117154 58665 117155 58607 117155 58666 117155 58658 117156 58170 117156 58659 117156 58171 117157 58653 117157 58652 117157 58633 117158 58608 117158 58629 117158 58177 117159 58621 117159 58622 117159 58623 117160 58619 117160 58615 117160 58670 117161 58106 117161 58107 117161 58609 117162 58610 117162 58539 117162 58539 117163 58610 117163 58628 117163 58539 117164 58628 117164 58618 117164 58618 117165 58628 117165 58626 117165 58107 117166 58611 117166 58670 117166 58670 117167 58611 117167 58612 117167 58670 117168 58612 117168 58613 117168 58613 117169 58612 117169 58682 117169 58613 117170 58682 117170 58614 117170 58614 117171 58682 117171 58671 117171 58614 117172 58671 117172 58673 117172 58615 117173 58616 117173 58624 117173 58624 117174 58616 117174 58544 117174 58624 117175 58544 117175 58617 117175 58617 117176 58544 117176 58543 117176 58617 117177 58543 117177 58626 117177 58626 117178 58543 117178 58540 117178 58626 117179 58540 117179 58618 117179 58619 117180 58176 117180 58615 117180 58615 117181 58176 117181 58620 117181 58615 117182 58620 117182 58616 117182 58621 117183 58623 117183 58622 117183 58622 117184 58623 117184 58615 117184 58622 117185 58615 117185 58630 117185 58630 117186 58615 117186 58624 117186 58630 117187 58624 117187 58625 117187 58625 117188 58624 117188 58617 117188 58625 117189 58617 117189 58631 117189 58631 117190 58617 117190 58626 117190 58631 117191 58626 117191 58627 117191 58627 117192 58626 117192 58628 117192 58627 117193 58628 117193 58632 117193 58632 117194 58628 117194 58610 117194 58608 117195 58177 117195 58629 117195 58629 117196 58177 117196 58622 117196 58629 117197 58622 117197 58635 117197 58635 117198 58622 117198 58630 117198 58635 117199 58630 117199 58636 117199 58636 117200 58630 117200 58625 117200 58636 117201 58625 117201 58638 117201 58638 117202 58625 117202 58631 117202 58638 117203 58631 117203 58639 117203 58639 117204 58631 117204 58627 117204 58639 117205 58627 117205 58093 117205 58093 117206 58627 117206 58632 117206 58647 117207 58633 117207 58634 117207 58634 117208 58633 117208 58629 117208 58634 117209 58629 117209 58644 117209 58644 117210 58629 117210 58635 117210 58644 117211 58635 117211 58637 117211 58637 117212 58635 117212 58636 117212 58637 117213 58636 117213 58642 117213 58642 117214 58636 117214 58638 117214 58642 117215 58638 117215 58640 117215 58640 117216 58638 117216 58639 117216 58640 117217 58639 117217 58070 117217 58070 117218 58639 117218 58093 117218 58070 117219 58085 117219 58640 117219 58640 117220 58085 117220 58641 117220 58640 117221 58641 117221 58642 117221 58642 117222 58641 117222 58649 117222 58642 117223 58649 117223 58637 117223 58637 117224 58649 117224 58643 117224 58637 117225 58643 117225 58644 117225 58644 117226 58643 117226 58645 117226 58644 117227 58645 117227 58634 117227 58634 117228 58645 117228 58646 117228 58634 117229 58646 117229 58647 117229 58647 117230 58646 117230 58175 117230 58085 117231 58648 117231 58641 117231 58641 117232 58648 117232 58657 117232 58641 117233 58657 117233 58649 117233 58649 117234 58657 117234 58655 117234 58649 117235 58655 117235 58643 117235 58643 117236 58655 117236 58650 117236 58643 117237 58650 117237 58645 117237 58645 117238 58650 117238 58651 117238 58645 117239 58651 117239 58646 117239 58646 117240 58651 117240 58652 117240 58646 117241 58652 117241 58175 117241 58175 117242 58652 117242 58653 117242 58170 117243 58171 117243 58659 117243 58659 117244 58171 117244 58652 117244 58659 117245 58652 117245 58660 117245 58660 117246 58652 117246 58651 117246 58660 117247 58651 117247 58654 117247 58654 117248 58651 117248 58650 117248 58654 117249 58650 117249 58661 117249 58661 117250 58650 117250 58655 117250 58661 117251 58655 117251 58656 117251 58656 117252 58655 117252 58657 117252 58656 117253 58657 117253 58664 117253 58664 117254 58657 117254 58648 117254 58607 117255 58658 117255 58666 117255 58666 117256 58658 117256 58659 117256 58666 117257 58659 117257 58667 117257 58667 117258 58659 117258 58660 117258 58667 117259 58660 117259 58668 117259 58668 117260 58660 117260 58654 117260 58668 117261 58654 117261 58662 117261 58662 117262 58654 117262 58661 117262 58662 117263 58661 117263 58669 117263 58669 117264 58661 117264 58656 117264 58669 117265 58656 117265 58663 117265 58663 117266 58656 117266 58664 117266 58675 117267 58665 117267 58674 117267 58674 117268 58665 117268 58666 117268 58674 117269 58666 117269 58673 117269 58673 117270 58666 117270 58667 117270 58673 117271 58667 117271 58614 117271 58614 117272 58667 117272 58668 117272 58614 117273 58668 117273 58613 117273 58613 117274 58668 117274 58662 117274 58613 117275 58662 117275 58670 117275 58670 117276 58662 117276 58669 117276 58670 117277 58669 117277 58106 117277 58106 117278 58669 117278 58663 117278 58671 117279 58672 117279 58673 117279 58673 117280 58672 117280 58679 117280 58673 117281 58679 117281 58674 117281 58674 117282 58679 117282 58678 117282 58674 117283 58678 117283 58675 117283 58675 117284 58678 117284 58677 117284 58166 117285 58677 117285 58676 117285 58676 117286 58677 117286 58678 117286 58676 117287 58678 117287 58554 117287 58554 117288 58678 117288 58679 117288 58554 117289 58679 117289 58556 117289 58556 117290 58679 117290 58672 117290 58556 117291 58672 117291 58557 117291 58557 117292 58672 117292 58671 117292 58557 117293 58671 117293 58680 117293 58680 117294 58671 117294 58682 117294 58680 117295 58682 117295 58681 117295 58681 117296 58682 117296 58612 117296 58681 117297 58612 117297 58548 117297 58548 117298 58612 117298 58611 117298 58548 117299 58611 117299 58097 117299 58097 117300 58611 117300 58107 117300 58683 117301 58715 117301 58737 117301 58730 117302 58779 117302 58737 117302 58737 117303 58779 117303 58781 117303 58737 117304 58781 117304 58683 117304 58685 117305 58784 117305 58731 117305 58731 117306 58784 117306 58684 117306 58731 117307 58684 117307 58730 117307 58730 117308 58684 117308 58783 117308 58730 117309 58783 117309 58779 117309 58685 117310 58731 117310 58686 117310 58686 117311 58731 117311 58687 117311 58686 117312 58687 117312 58787 117312 58787 117313 58687 117313 58788 117313 58788 117314 58687 117314 58740 117314 58788 117315 58740 117315 58789 117315 58688 117316 58689 117316 58740 117316 58740 117317 58689 117317 58690 117317 58740 117318 58690 117318 58789 117318 58691 117319 58791 117319 58745 117319 58745 117320 58791 117320 58790 117320 58745 117321 58790 117321 58688 117321 58688 117322 58790 117322 58692 117322 58688 117323 58692 117323 58689 117323 58691 117324 58745 117324 58693 117324 58693 117325 58745 117325 58747 117325 58693 117326 58747 117326 58694 117326 58694 117327 58747 117327 58792 117327 58792 117328 58747 117328 58750 117328 58792 117329 58750 117329 58696 117329 58751 117330 58695 117330 58750 117330 58750 117331 58695 117331 58793 117331 58750 117332 58793 117332 58696 117332 58797 117333 58698 117333 58697 117333 58697 117334 58698 117334 58699 117334 58697 117335 58699 117335 58751 117335 58751 117336 58699 117336 58794 117336 58751 117337 58794 117337 58695 117337 58797 117338 58697 117338 58801 117338 58801 117339 58697 117339 58726 117339 58801 117340 58726 117340 58700 117340 58700 117341 58726 117341 58798 117341 58798 117342 58726 117342 58701 117342 58798 117343 58701 117343 58753 117343 58702 117344 58757 117344 58701 117344 58701 117345 58757 117345 58754 117345 58701 117346 58754 117346 58753 117346 58720 117347 58759 117347 58702 117347 58702 117348 58759 117348 58758 117348 58702 117349 58758 117349 58757 117349 58764 117350 58762 117350 58704 117350 58704 117351 58762 117351 58703 117351 58704 117352 58703 117352 58720 117352 58720 117353 58703 117353 58760 117353 58720 117354 58760 117354 58759 117354 58764 117355 58704 117355 58766 117355 58766 117356 58704 117356 58706 117356 58766 117357 58706 117357 58767 117357 58723 117358 58768 117358 58706 117358 58706 117359 58768 117359 58705 117359 58706 117360 58705 117360 58767 117360 58724 117361 58772 117361 58723 117361 58723 117362 58772 117362 58771 117362 58723 117363 58771 117363 58768 117363 58773 117364 58707 117364 58735 117364 58735 117365 58707 117365 58708 117365 58735 117366 58708 117366 58724 117366 58724 117367 58708 117367 58709 117367 58724 117368 58709 117368 58772 117368 58773 117369 58735 117369 58710 117369 58710 117370 58735 117370 58712 117370 58710 117371 58712 117371 58711 117371 58711 117372 58712 117372 58713 117372 58713 117373 58712 117373 58738 117373 58713 117374 58738 117374 58774 117374 58717 117375 58714 117375 58738 117375 58738 117376 58714 117376 58775 117376 58738 117377 58775 117377 58774 117377 58683 117378 58777 117378 58715 117378 58715 117379 58777 117379 58716 117379 58715 117380 58716 117380 58717 117380 58717 117381 58716 117381 58718 117381 58717 117382 58718 117382 58714 117382 58701 117383 58728 117383 58702 117383 58702 117384 58728 117384 59216 117384 58702 117385 59216 117385 58720 117385 58740 117386 58742 117386 58688 117386 58688 117387 58742 117387 58743 117387 58688 117388 58743 117388 58745 117388 59216 117389 58719 117389 58720 117389 58720 117390 58719 117390 58721 117390 58720 117391 58721 117391 58704 117391 58704 117392 58721 117392 59218 117392 58704 117393 59218 117393 58706 117393 59218 117394 59220 117394 58706 117394 58706 117395 59220 117395 58722 117395 58706 117396 58722 117396 58723 117396 58723 117397 58722 117397 58732 117397 58723 117398 58732 117398 58724 117398 58697 117399 58725 117399 58726 117399 58726 117400 58725 117400 59215 117400 58726 117401 59215 117401 58701 117401 58701 117402 59215 117402 58727 117402 58701 117403 58727 117403 58728 117403 58737 117404 58729 117404 58730 117404 58730 117405 58729 117405 59201 117405 58730 117406 59201 117406 58731 117406 58732 117407 58733 117407 58724 117407 58724 117408 58733 117408 58734 117408 58724 117409 58734 117409 58735 117409 58735 117410 58734 117410 59225 117410 58735 117411 59225 117411 58712 117411 58717 117412 58736 117412 58715 117412 58715 117413 58736 117413 59196 117413 58715 117414 59196 117414 58737 117414 58737 117415 59196 117415 59198 117415 58737 117416 59198 117416 58729 117416 59225 117417 59226 117417 58712 117417 58712 117418 59226 117418 58739 117418 58712 117419 58739 117419 58738 117419 58738 117420 58739 117420 59227 117420 58738 117421 59227 117421 58717 117421 58717 117422 59227 117422 59228 117422 58717 117423 59228 117423 58736 117423 59201 117424 59202 117424 58731 117424 58731 117425 59202 117425 59204 117425 58731 117426 59204 117426 58687 117426 58687 117427 59204 117427 59206 117427 58687 117428 59206 117428 58740 117428 58740 117429 59206 117429 58741 117429 58740 117430 58741 117430 58742 117430 58743 117431 58744 117431 58745 117431 58745 117432 58744 117432 58746 117432 58745 117433 58746 117433 58747 117433 58747 117434 58746 117434 58748 117434 58747 117435 58748 117435 58750 117435 58748 117436 58749 117436 58750 117436 58750 117437 58749 117437 59210 117437 58750 117438 59210 117438 58751 117438 58751 117439 59210 117439 58752 117439 58751 117440 58752 117440 58697 117440 58697 117441 58752 117441 59213 117441 58697 117442 59213 117442 58725 117442 58798 117443 58753 117443 58755 117443 58753 117444 58754 117444 58755 117444 58755 117445 58754 117445 58757 117445 58755 117446 58757 117446 58756 117446 58756 117447 58757 117447 58758 117447 58756 117448 58758 117448 58838 117448 58838 117449 58758 117449 58759 117449 58838 117450 58759 117450 58761 117450 58761 117451 58759 117451 58760 117451 58760 117452 58703 117452 58761 117452 58761 117453 58703 117453 58762 117453 58761 117454 58762 117454 58763 117454 58763 117455 58762 117455 58764 117455 58763 117456 58764 117456 58765 117456 58765 117457 58764 117457 58766 117457 58765 117458 58766 117458 58769 117458 58769 117459 58766 117459 58767 117459 58767 117460 58705 117460 58769 117460 58769 117461 58705 117461 58768 117461 58769 117462 58768 117462 58770 117462 58770 117463 58768 117463 58771 117463 58770 117464 58771 117464 58834 117464 58834 117465 58771 117465 58772 117465 58834 117466 58772 117466 58833 117466 58833 117467 58772 117467 58709 117467 58709 117468 58708 117468 58833 117468 58833 117469 58708 117469 58707 117469 58833 117470 58707 117470 58831 117470 58831 117471 58707 117471 58773 117471 58831 117472 58773 117472 58830 117472 58830 117473 58773 117473 58710 117473 58830 117474 58710 117474 58828 117474 58828 117475 58710 117475 58711 117475 58711 117476 58713 117476 58828 117476 58828 117477 58713 117477 58774 117477 58828 117478 58774 117478 58827 117478 58827 117479 58774 117479 58775 117479 58827 117480 58775 117480 58776 117480 58716 117481 58823 117481 58718 117481 58718 117482 58823 117482 58776 117482 58718 117483 58776 117483 58714 117483 58714 117484 58776 117484 58775 117484 58777 117485 58778 117485 58716 117485 58716 117486 58778 117486 58822 117486 58716 117487 58822 117487 58823 117487 58779 117488 58780 117488 58781 117488 58781 117489 58780 117489 58778 117489 58781 117490 58778 117490 58683 117490 58683 117491 58778 117491 58777 117491 58783 117492 58782 117492 58779 117492 58779 117493 58782 117493 58820 117493 58779 117494 58820 117494 58780 117494 58783 117495 58684 117495 58782 117495 58782 117496 58684 117496 58784 117496 58782 117497 58784 117497 58785 117497 58785 117498 58784 117498 58685 117498 58785 117499 58685 117499 58786 117499 58786 117500 58685 117500 58686 117500 58786 117501 58686 117501 58816 117501 58816 117502 58686 117502 58787 117502 58787 117503 58788 117503 58816 117503 58816 117504 58788 117504 58789 117504 58816 117505 58789 117505 58815 117505 58815 117506 58789 117506 58690 117506 58815 117507 58690 117507 58814 117507 58814 117508 58690 117508 58689 117508 58814 117509 58689 117509 58813 117509 58813 117510 58689 117510 58692 117510 58692 117511 58790 117511 58813 117511 58813 117512 58790 117512 58791 117512 58813 117513 58791 117513 58810 117513 58810 117514 58791 117514 58691 117514 58810 117515 58691 117515 58808 117515 58808 117516 58691 117516 58693 117516 58808 117517 58693 117517 58807 117517 58807 117518 58693 117518 58694 117518 58694 117519 58792 117519 58807 117519 58807 117520 58792 117520 58696 117520 58807 117521 58696 117521 58806 117521 58806 117522 58696 117522 58793 117522 58806 117523 58793 117523 58804 117523 58804 117524 58793 117524 58695 117524 58804 117525 58695 117525 58795 117525 58795 117526 58695 117526 58794 117526 58794 117527 58699 117527 58795 117527 58795 117528 58699 117528 58698 117528 58795 117529 58698 117529 58796 117529 58796 117530 58698 117530 58797 117530 58796 117531 58797 117531 58802 117531 58755 117532 58799 117532 58798 117532 58798 117533 58799 117533 58800 117533 58798 117534 58800 117534 58700 117534 58700 117535 58800 117535 58802 117535 58700 117536 58802 117536 58801 117536 58801 117537 58802 117537 58797 117537 58800 117538 58840 117538 58802 117538 58802 117539 58840 117539 58803 117539 58802 117540 58803 117540 58796 117540 58796 117541 58803 117541 58842 117541 58796 117542 58842 117542 58795 117542 58795 117543 58842 117543 58843 117543 58795 117544 58843 117544 58804 117544 58804 117545 58843 117545 58805 117545 58804 117546 58805 117546 58806 117546 58806 117547 58805 117547 58845 117547 58806 117548 58845 117548 58807 117548 58807 117549 58845 117549 58809 117549 58807 117550 58809 117550 58808 117550 58808 117551 58809 117551 58811 117551 58808 117552 58811 117552 58810 117552 58810 117553 58811 117553 58812 117553 58810 117554 58812 117554 58813 117554 58813 117555 58812 117555 58848 117555 58813 117556 58848 117556 58814 117556 58814 117557 58848 117557 58850 117557 58814 117558 58850 117558 58815 117558 58815 117559 58850 117559 58852 117559 58815 117560 58852 117560 58816 117560 58816 117561 58852 117561 58817 117561 58816 117562 58817 117562 58786 117562 58786 117563 58817 117563 58818 117563 58786 117564 58818 117564 58785 117564 58785 117565 58818 117565 58819 117565 58785 117566 58819 117566 58782 117566 58782 117567 58819 117567 58855 117567 58782 117568 58855 117568 58820 117568 58820 117569 58855 117569 58858 117569 58820 117570 58858 117570 58780 117570 58780 117571 58858 117571 58821 117571 58780 117572 58821 117572 58778 117572 58778 117573 58821 117573 58859 117573 58778 117574 58859 117574 58822 117574 58822 117575 58859 117575 58860 117575 58822 117576 58860 117576 58823 117576 58823 117577 58860 117577 58824 117577 58823 117578 58824 117578 58776 117578 58776 117579 58824 117579 58825 117579 58776 117580 58825 117580 58827 117580 58827 117581 58825 117581 58826 117581 58827 117582 58826 117582 58828 117582 58828 117583 58826 117583 58829 117583 58828 117584 58829 117584 58830 117584 58830 117585 58829 117585 58832 117585 58830 117586 58832 117586 58831 117586 58831 117587 58832 117587 58864 117587 58831 117588 58864 117588 58833 117588 58833 117589 58864 117589 58868 117589 58833 117590 58868 117590 58834 117590 58834 117591 58868 117591 58869 117591 58834 117592 58869 117592 58770 117592 58770 117593 58869 117593 58835 117593 58770 117594 58835 117594 58769 117594 58769 117595 58835 117595 58872 117595 58769 117596 58872 117596 58765 117596 58765 117597 58872 117597 58836 117597 58765 117598 58836 117598 58763 117598 58763 117599 58836 117599 58874 117599 58763 117600 58874 117600 58761 117600 58761 117601 58874 117601 58837 117601 58761 117602 58837 117602 58838 117602 58838 117603 58837 117603 58875 117603 58838 117604 58875 117604 58756 117604 58756 117605 58875 117605 58839 117605 58756 117606 58839 117606 58755 117606 58755 117607 58839 117607 58876 117607 58755 117608 58876 117608 58799 117608 58799 117609 58876 117609 58878 117609 58799 117610 58878 117610 58800 117610 58800 117611 58878 117611 58840 117611 58878 117612 58879 117612 58840 117612 58840 117613 58879 117613 58841 117613 58840 117614 58841 117614 58803 117614 58803 117615 58841 117615 58882 117615 58803 117616 58882 117616 58842 117616 58842 117617 58882 117617 58884 117617 58842 117618 58884 117618 58843 117618 58843 117619 58884 117619 58885 117619 58843 117620 58885 117620 58805 117620 58805 117621 58885 117621 58844 117621 58805 117622 58844 117622 58845 117622 58845 117623 58844 117623 58888 117623 58845 117624 58888 117624 58809 117624 58809 117625 58888 117625 58846 117625 58809 117626 58846 117626 58811 117626 58811 117627 58846 117627 58847 117627 58811 117628 58847 117628 58812 117628 58812 117629 58847 117629 58889 117629 58812 117630 58889 117630 58848 117630 58848 117631 58889 117631 58849 117631 58848 117632 58849 117632 58850 117632 58850 117633 58849 117633 58851 117633 58850 117634 58851 117634 58852 117634 58852 117635 58851 117635 58890 117635 58852 117636 58890 117636 58817 117636 58817 117637 58890 117637 58853 117637 58817 117638 58853 117638 58818 117638 58818 117639 58853 117639 58854 117639 58818 117640 58854 117640 58819 117640 58819 117641 58854 117641 58891 117641 58819 117642 58891 117642 58855 117642 58855 117643 58891 117643 58856 117643 58855 117644 58856 117644 58858 117644 58858 117645 58856 117645 58857 117645 58858 117646 58857 117646 58821 117646 58821 117647 58857 117647 58896 117647 58821 117648 58896 117648 58859 117648 58859 117649 58896 117649 58861 117649 58859 117650 58861 117650 58860 117650 58860 117651 58861 117651 58862 117651 58860 117652 58862 117652 58824 117652 58824 117653 58862 117653 58899 117653 58824 117654 58899 117654 58825 117654 58825 117655 58899 117655 58900 117655 58825 117656 58900 117656 58826 117656 58826 117657 58900 117657 58863 117657 58826 117658 58863 117658 58829 117658 58829 117659 58863 117659 58902 117659 58829 117660 58902 117660 58832 117660 58832 117661 58902 117661 58865 117661 58832 117662 58865 117662 58864 117662 58864 117663 58865 117663 58866 117663 58864 117664 58866 117664 58868 117664 58868 117665 58866 117665 58867 117665 58868 117666 58867 117666 58869 117666 58869 117667 58867 117667 58870 117667 58869 117668 58870 117668 58835 117668 58835 117669 58870 117669 58871 117669 58835 117670 58871 117670 58872 117670 58872 117671 58871 117671 58873 117671 58872 117672 58873 117672 58836 117672 58836 117673 58873 117673 58907 117673 58836 117674 58907 117674 58874 117674 58874 117675 58907 117675 58908 117675 58874 117676 58908 117676 58837 117676 58837 117677 58908 117677 58909 117677 58837 117678 58909 117678 58875 117678 58875 117679 58909 117679 58912 117679 58875 117680 58912 117680 58839 117680 58839 117681 58912 117681 58877 117681 58839 117682 58877 117682 58876 117682 58876 117683 58877 117683 58914 117683 58876 117684 58914 117684 58878 117684 58878 117685 58914 117685 58879 117685 58914 117686 58915 117686 58879 117686 58879 117687 58915 117687 58880 117687 58879 117688 58880 117688 58841 117688 58841 117689 58880 117689 58881 117689 58841 117690 58881 117690 58882 117690 58882 117691 58881 117691 58883 117691 58882 117692 58883 117692 58884 117692 58884 117693 58883 117693 58080 117693 58884 117694 58080 117694 58885 117694 58885 117695 58080 117695 58886 117695 58885 117696 58886 117696 58844 117696 58844 117697 58886 117697 58887 117697 58844 117698 58887 117698 58888 117698 58888 117699 58887 117699 58088 117699 58888 117700 58088 117700 58846 117700 58846 117701 58088 117701 58087 117701 58846 117702 58087 117702 58847 117702 58847 117703 58087 117703 58079 117703 58847 117704 58079 117704 58889 117704 58889 117705 58079 117705 58077 117705 58889 117706 58077 117706 58849 117706 58849 117707 58077 117707 58074 117707 58849 117708 58074 117708 58851 117708 58851 117709 58074 117709 58101 117709 58851 117710 58101 117710 58890 117710 58890 117711 58101 117711 58100 117711 58890 117712 58100 117712 58853 117712 58853 117713 58100 117713 58098 117713 58853 117714 58098 117714 58854 117714 58854 117715 58098 117715 58892 117715 58854 117716 58892 117716 58891 117716 58891 117717 58892 117717 58893 117717 58891 117718 58893 117718 58856 117718 58856 117719 58893 117719 58894 117719 58856 117720 58894 117720 58857 117720 58857 117721 58894 117721 58895 117721 58857 117722 58895 117722 58896 117722 58896 117723 58895 117723 58108 117723 58896 117724 58108 117724 58861 117724 58861 117725 58108 117725 58897 117725 58861 117726 58897 117726 58862 117726 58862 117727 58897 117727 58898 117727 58862 117728 58898 117728 58899 117728 58899 117729 58898 117729 58901 117729 58899 117730 58901 117730 58900 117730 58900 117731 58901 117731 58072 117731 58900 117732 58072 117732 58863 117732 58863 117733 58072 117733 58071 117733 58863 117734 58071 117734 58902 117734 58902 117735 58071 117735 58094 117735 58902 117736 58094 117736 58865 117736 58865 117737 58094 117737 58095 117737 58865 117738 58095 117738 58866 117738 58866 117739 58095 117739 58903 117739 58866 117740 58903 117740 58867 117740 58867 117741 58903 117741 58904 117741 58867 117742 58904 117742 58870 117742 58870 117743 58904 117743 58905 117743 58870 117744 58905 117744 58871 117744 58871 117745 58905 117745 58104 117745 58871 117746 58104 117746 58873 117746 58873 117747 58104 117747 58906 117747 58873 117748 58906 117748 58907 117748 58907 117749 58906 117749 58091 117749 58907 117750 58091 117750 58908 117750 58908 117751 58091 117751 58089 117751 58908 117752 58089 117752 58909 117752 58909 117753 58089 117753 58910 117753 58909 117754 58910 117754 58912 117754 58912 117755 58910 117755 58911 117755 58912 117756 58911 117756 58877 117756 58877 117757 58911 117757 58913 117757 58877 117758 58913 117758 58914 117758 58914 117759 58913 117759 58915 117759 59385 117760 58916 117760 59388 117760 59388 117761 58916 117761 58917 117761 59388 117762 58917 117762 59389 117762 59389 117763 58917 117763 59292 117763 59389 117764 59292 117764 59390 117764 59390 117765 59292 117765 59289 117765 59390 117766 59289 117766 58918 117766 58918 117767 59289 117767 59287 117767 58918 117768 59287 117768 58920 117768 58920 117769 59287 117769 58919 117769 58920 117770 58919 117770 58921 117770 58921 117771 58919 117771 59286 117771 58921 117772 59286 117772 59392 117772 59392 117773 59286 117773 58922 117773 59392 117774 58922 117774 58923 117774 58923 117775 58922 117775 58924 117775 58923 117776 58924 117776 58925 117776 58925 117777 58924 117777 58927 117777 58925 117778 58927 117778 58926 117778 58926 117779 58927 117779 58928 117779 58926 117780 58928 117780 59396 117780 59396 117781 58928 117781 58929 117781 59396 117782 58929 117782 58930 117782 58930 117783 58929 117783 58931 117783 58930 117784 58931 117784 59398 117784 59398 117785 58931 117785 59283 117785 59398 117786 59283 117786 59399 117786 59399 117787 59283 117787 58932 117787 59399 117788 58932 117788 58933 117788 58933 117789 58932 117789 59281 117789 58933 117790 59281 117790 58934 117790 58934 117791 59281 117791 59280 117791 58934 117792 59280 117792 58935 117792 58935 117793 59280 117793 58936 117793 58935 117794 58936 117794 58937 117794 58937 117795 58936 117795 59279 117795 58937 117796 59279 117796 58938 117796 58938 117797 59279 117797 59278 117797 58938 117798 59278 117798 58939 117798 58939 117799 59278 117799 58940 117799 58939 117800 58940 117800 58941 117800 58941 117801 58940 117801 59276 117801 58941 117802 59276 117802 58942 117802 58942 117803 59276 117803 58943 117803 58942 117804 58943 117804 59371 117804 59371 117805 58943 117805 58944 117805 59371 117806 58944 117806 59372 117806 59372 117807 58944 117807 59275 117807 59372 117808 59275 117808 58945 117808 58945 117809 59275 117809 58946 117809 58945 117810 58946 117810 58947 117810 58947 117811 58946 117811 58948 117811 58947 117812 58948 117812 59374 117812 59374 117813 58948 117813 58949 117813 59374 117814 58949 117814 59375 117814 59375 117815 58949 117815 59273 117815 59375 117816 59273 117816 59376 117816 59376 117817 59273 117817 58950 117817 59376 117818 58950 117818 59378 117818 59378 117819 58950 117819 58951 117819 59378 117820 58951 117820 59380 117820 59380 117821 58951 117821 58952 117821 59380 117822 58952 117822 59381 117822 59381 117823 58952 117823 58953 117823 59381 117824 58953 117824 58954 117824 58954 117825 58953 117825 59269 117825 58954 117826 59269 117826 59384 117826 59384 117827 59269 117827 59297 117827 59384 117828 59297 117828 58955 117828 58955 117829 59297 117829 58956 117829 58955 117830 58956 117830 59385 117830 59385 117831 58956 117831 58916 117831 58024 117832 58958 117832 58977 117832 58959 117833 58957 117833 58958 117833 58958 117834 58957 117834 59185 117834 58958 117835 59185 117835 58977 117835 58046 117836 59187 117836 58959 117836 58959 117837 59187 117837 59186 117837 58959 117838 59186 117838 58957 117838 58015 117839 59190 117839 58046 117839 58046 117840 59190 117840 58960 117840 58046 117841 58960 117841 59187 117841 58022 117842 58961 117842 58015 117842 58015 117843 58961 117843 58962 117843 58015 117844 58962 117844 59190 117844 58063 117845 59193 117845 58022 117845 58022 117846 59193 117846 58963 117846 58022 117847 58963 117847 58961 117847 58966 117848 58964 117848 58063 117848 58063 117849 58964 117849 58965 117849 58063 117850 58965 117850 59193 117850 58038 117851 59172 117851 58966 117851 58966 117852 59172 117852 58967 117852 58966 117853 58967 117853 58964 117853 58968 117854 58969 117854 58038 117854 58038 117855 58969 117855 59173 117855 58038 117856 59173 117856 59172 117856 58032 117857 59175 117857 58968 117857 58968 117858 59175 117858 58970 117858 58968 117859 58970 117859 58969 117859 58034 117860 59177 117860 58032 117860 58032 117861 59177 117861 58971 117861 58032 117862 58971 117862 59175 117862 58974 117863 58976 117863 58034 117863 58034 117864 58976 117864 58972 117864 58034 117865 58972 117865 59177 117865 58973 117866 59179 117866 58974 117866 58974 117867 59179 117867 58975 117867 58974 117868 58975 117868 58976 117868 58977 117869 59182 117869 58024 117869 58024 117870 59182 117870 58978 117870 58024 117871 58978 117871 58973 117871 58973 117872 58978 117872 58979 117872 58973 117873 58979 117873 59179 117873 59140 117874 58994 117874 58985 117874 59137 117875 59138 117875 58985 117875 58985 117876 59138 117876 58980 117876 58985 117877 58980 117877 59140 117877 58981 117878 58982 117878 58985 117878 58985 117879 58982 117879 59136 117879 58985 117880 59136 117880 59137 117880 58983 117881 58984 117881 58985 117881 58985 117882 58984 117882 58986 117882 58985 117883 58986 117883 58981 117883 58990 117884 58987 117884 58985 117884 58985 117885 58987 117885 59133 117885 58985 117886 59133 117886 58983 117886 58988 117887 59130 117887 58985 117887 58985 117888 59130 117888 58989 117888 58985 117889 58989 117889 58990 117889 58992 117890 59126 117890 58985 117890 58985 117891 59126 117891 59128 117891 58985 117892 59128 117892 58988 117892 59124 117893 59125 117893 58985 117893 58985 117894 59125 117894 58991 117894 58985 117895 58991 117895 58992 117895 59121 117896 58993 117896 58985 117896 58985 117897 58993 117897 59122 117897 58985 117898 59122 117898 59124 117898 58994 117899 58995 117899 58985 117899 58985 117900 58995 117900 59119 117900 58985 117901 59119 117901 59121 117901 58996 117902 58059 117902 59098 117902 58997 117903 59102 117903 58059 117903 58059 117904 59102 117904 59101 117904 58059 117905 59101 117905 59098 117905 58031 117906 59104 117906 58997 117906 58997 117907 59104 117907 59103 117907 58997 117908 59103 117908 59102 117908 58020 117909 58998 117909 58031 117909 58031 117910 58998 117910 58999 117910 58031 117911 58999 117911 59104 117911 59001 117912 59000 117912 58020 117912 58020 117913 59000 117913 59108 117913 58020 117914 59108 117914 58998 117914 58043 117915 59112 117915 59001 117915 59001 117916 59112 117916 59111 117916 59001 117917 59111 117917 59000 117917 59002 117918 59114 117918 58043 117918 58043 117919 59114 117919 59003 117919 58043 117920 59003 117920 59112 117920 58012 117921 59005 117921 59002 117921 59002 117922 59005 117922 59115 117922 59002 117923 59115 117923 59114 117923 59006 117924 59004 117924 58012 117924 58012 117925 59004 117925 59083 117925 58012 117926 59083 117926 59005 117926 58014 117927 59087 117927 59006 117927 59006 117928 59087 117928 59085 117928 59006 117929 59085 117929 59004 117929 58052 117930 59008 117930 58014 117930 58014 117931 59008 117931 59089 117931 58014 117932 59089 117932 59087 117932 59007 117933 59092 117933 58052 117933 58052 117934 59092 117934 59090 117934 58052 117935 59090 117935 59008 117935 59009 117936 59013 117936 59007 117936 59007 117937 59013 117937 59010 117937 59007 117938 59010 117938 59092 117938 59098 117939 59011 117939 58996 117939 58996 117940 59011 117940 59012 117940 58996 117941 59012 117941 59009 117941 59009 117942 59012 117942 59095 117942 59009 117943 59095 117943 59013 117943 59030 117944 59014 117944 59015 117944 59018 117945 59052 117945 59015 117945 59015 117946 59052 117946 59055 117946 59015 117947 59055 117947 59030 117947 59048 117948 59016 117948 59015 117948 59015 117949 59016 117949 59017 117949 59015 117950 59017 117950 59018 117950 59022 117951 59046 117951 59015 117951 59015 117952 59046 117952 59019 117952 59015 117953 59019 117953 59048 117953 59044 117954 59020 117954 59015 117954 59015 117955 59020 117955 59021 117955 59015 117956 59021 117956 59022 117956 59023 117957 59024 117957 59015 117957 59015 117958 59024 117958 59043 117958 59015 117959 59043 117959 59044 117959 59025 117960 59039 117960 59015 117960 59015 117961 59039 117961 59040 117961 59015 117962 59040 117962 59023 117962 59026 117963 59034 117963 59015 117963 59015 117964 59034 117964 59036 117964 59015 117965 59036 117965 59025 117965 59029 117966 59032 117966 59015 117966 59015 117967 59032 117967 59033 117967 59015 117968 59033 117968 59026 117968 59014 117969 59027 117969 59015 117969 59015 117970 59027 117970 59028 117970 59015 117971 59028 117971 59029 117971 59030 117972 59056 117972 59014 117972 59014 117973 59056 117973 59057 117973 59014 117974 59057 117974 59027 117974 59027 117975 59057 117975 59059 117975 59027 117976 59059 117976 59028 117976 59028 117977 59059 117977 59060 117977 59028 117978 59060 117978 59029 117978 59029 117979 59060 117979 59031 117979 59029 117980 59031 117980 59032 117980 59032 117981 59031 117981 59062 117981 59032 117982 59062 117982 59033 117982 59033 117983 59062 117983 59063 117983 59033 117984 59063 117984 59026 117984 59026 117985 59063 117985 59035 117985 59026 117986 59035 117986 59034 117986 59034 117987 59035 117987 59064 117987 59034 117988 59064 117988 59036 117988 59036 117989 59064 117989 59037 117989 59036 117990 59037 117990 59025 117990 59025 117991 59037 117991 59038 117991 59025 117992 59038 117992 59039 117992 59039 117993 59038 117993 59068 117993 59039 117994 59068 117994 59040 117994 59040 117995 59068 117995 59069 117995 59040 117996 59069 117996 59023 117996 59023 117997 59069 117997 59041 117997 59023 117998 59041 117998 59024 117998 59024 117999 59041 117999 59042 117999 59024 118000 59042 118000 59043 118000 59043 118001 59042 118001 59071 118001 59043 118002 59071 118002 59044 118002 59044 118003 59071 118003 59045 118003 59044 118004 59045 118004 59020 118004 59020 118005 59045 118005 59073 118005 59020 118006 59073 118006 59021 118006 59021 118007 59073 118007 59074 118007 59021 118008 59074 118008 59022 118008 59022 118009 59074 118009 59075 118009 59022 118010 59075 118010 59046 118010 59046 118011 59075 118011 59047 118011 59046 118012 59047 118012 59019 118012 59019 118013 59047 118013 59077 118013 59019 118014 59077 118014 59048 118014 59048 118015 59077 118015 59049 118015 59048 118016 59049 118016 59016 118016 59016 118017 59049 118017 59050 118017 59016 118018 59050 118018 59017 118018 59017 118019 59050 118019 59051 118019 59017 118020 59051 118020 59018 118020 59018 118021 59051 118021 59080 118021 59018 118022 59080 118022 59052 118022 59052 118023 59080 118023 59053 118023 59052 118024 59053 118024 59055 118024 59055 118025 59053 118025 59054 118025 59055 118026 59054 118026 59030 118026 59030 118027 59054 118027 59056 118027 59054 118028 59082 118028 59056 118028 59056 118029 59082 118029 59084 118029 59056 118030 59084 118030 59057 118030 59057 118031 59084 118031 59058 118031 59057 118032 59058 118032 59059 118032 59059 118033 59058 118033 59086 118033 59059 118034 59086 118034 59060 118034 59060 118035 59086 118035 59061 118035 59060 118036 59061 118036 59031 118036 59031 118037 59061 118037 59088 118037 59031 118038 59088 118038 59062 118038 59062 118039 59088 118039 59091 118039 59062 118040 59091 118040 59063 118040 59063 118041 59091 118041 59093 118041 59063 118042 59093 118042 59035 118042 59035 118043 59093 118043 59094 118043 59035 118044 59094 118044 59064 118044 59064 118045 59094 118045 59065 118045 59064 118046 59065 118046 59037 118046 59037 118047 59065 118047 59066 118047 59037 118048 59066 118048 59038 118048 59038 118049 59066 118049 59067 118049 59038 118050 59067 118050 59068 118050 59068 118051 59067 118051 59096 118051 59068 118052 59096 118052 59069 118052 59069 118053 59096 118053 59097 118053 59069 118054 59097 118054 59041 118054 59041 118055 59097 118055 59099 118055 59041 118056 59099 118056 59042 118056 59042 118057 59099 118057 59100 118057 59042 118058 59100 118058 59071 118058 59071 118059 59100 118059 59070 118059 59071 118060 59070 118060 59045 118060 59045 118061 59070 118061 59105 118061 59045 118062 59105 118062 59073 118062 59073 118063 59105 118063 59072 118063 59073 118064 59072 118064 59074 118064 59074 118065 59072 118065 59106 118065 59074 118066 59106 118066 59075 118066 59075 118067 59106 118067 59076 118067 59075 118068 59076 118068 59047 118068 59047 118069 59076 118069 59107 118069 59047 118070 59107 118070 59077 118070 59077 118071 59107 118071 59109 118071 59077 118072 59109 118072 59049 118072 59049 118073 59109 118073 59110 118073 59049 118074 59110 118074 59050 118074 59050 118075 59110 118075 59078 118075 59050 118076 59078 118076 59051 118076 59051 118077 59078 118077 59079 118077 59051 118078 59079 118078 59080 118078 59080 118079 59079 118079 59113 118079 59080 118080 59113 118080 59053 118080 59053 118081 59113 118081 59081 118081 59053 118082 59081 118082 59054 118082 59054 118083 59081 118083 59082 118083 59081 118084 59005 118084 59082 118084 59082 118085 59005 118085 59083 118085 59082 118086 59083 118086 59084 118086 59084 118087 59083 118087 59004 118087 59084 118088 59004 118088 59058 118088 59058 118089 59004 118089 59085 118089 59058 118090 59085 118090 59086 118090 59086 118091 59085 118091 59087 118091 59086 118092 59087 118092 59061 118092 59061 118093 59087 118093 59089 118093 59061 118094 59089 118094 59088 118094 59088 118095 59089 118095 59008 118095 59088 118096 59008 118096 59091 118096 59091 118097 59008 118097 59090 118097 59091 118098 59090 118098 59093 118098 59093 118099 59090 118099 59092 118099 59093 118100 59092 118100 59094 118100 59094 118101 59092 118101 59010 118101 59094 118102 59010 118102 59065 118102 59065 118103 59010 118103 59013 118103 59065 118104 59013 118104 59066 118104 59066 118105 59013 118105 59095 118105 59066 118106 59095 118106 59067 118106 59067 118107 59095 118107 59012 118107 59067 118108 59012 118108 59096 118108 59096 118109 59012 118109 59011 118109 59096 118110 59011 118110 59097 118110 59097 118111 59011 118111 59098 118111 59097 118112 59098 118112 59099 118112 59099 118113 59098 118113 59101 118113 59099 118114 59101 118114 59100 118114 59100 118115 59101 118115 59102 118115 59100 118116 59102 118116 59070 118116 59070 118117 59102 118117 59103 118117 59070 118118 59103 118118 59105 118118 59105 118119 59103 118119 59104 118119 59105 118120 59104 118120 59072 118120 59072 118121 59104 118121 58999 118121 59072 118122 58999 118122 59106 118122 59106 118123 58999 118123 58998 118123 59106 118124 58998 118124 59076 118124 59076 118125 58998 118125 59108 118125 59076 118126 59108 118126 59107 118126 59107 118127 59108 118127 59000 118127 59107 118128 59000 118128 59109 118128 59109 118129 59000 118129 59111 118129 59109 118130 59111 118130 59110 118130 59110 118131 59111 118131 59112 118131 59110 118132 59112 118132 59078 118132 59078 118133 59112 118133 59003 118133 59078 118134 59003 118134 59079 118134 59079 118135 59003 118135 59114 118135 59079 118136 59114 118136 59113 118136 59113 118137 59114 118137 59115 118137 59113 118138 59115 118138 59081 118138 59081 118139 59115 118139 59005 118139 59140 118140 59116 118140 58994 118140 58994 118141 59116 118141 59117 118141 58994 118142 59117 118142 58995 118142 58995 118143 59117 118143 59118 118143 58995 118144 59118 118144 59119 118144 59119 118145 59118 118145 59120 118145 59119 118146 59120 118146 59121 118146 59121 118147 59120 118147 59144 118147 59121 118148 59144 118148 58993 118148 58993 118149 59144 118149 59123 118149 58993 118150 59123 118150 59122 118150 59122 118151 59123 118151 59147 118151 59122 118152 59147 118152 59124 118152 59124 118153 59147 118153 59148 118153 59124 118154 59148 118154 59125 118154 59125 118155 59148 118155 59150 118155 59125 118156 59150 118156 58991 118156 58991 118157 59150 118157 59152 118157 58991 118158 59152 118158 58992 118158 58992 118159 59152 118159 59154 118159 58992 118160 59154 118160 59126 118160 59126 118161 59154 118161 59127 118161 59126 118162 59127 118162 59128 118162 59128 118163 59127 118163 59129 118163 59128 118164 59129 118164 58988 118164 58988 118165 59129 118165 59155 118165 58988 118166 59155 118166 59130 118166 59130 118167 59155 118167 59157 118167 59130 118168 59157 118168 58989 118168 58989 118169 59157 118169 59131 118169 58989 118170 59131 118170 58990 118170 58990 118171 59131 118171 59159 118171 58990 118172 59159 118172 58987 118172 58987 118173 59159 118173 59132 118173 58987 118174 59132 118174 59133 118174 59133 118175 59132 118175 59161 118175 59133 118176 59161 118176 58983 118176 58983 118177 59161 118177 59134 118177 58983 118178 59134 118178 58984 118178 58984 118179 59134 118179 59163 118179 58984 118180 59163 118180 58986 118180 58986 118181 59163 118181 59164 118181 58986 118182 59164 118182 58981 118182 58981 118183 59164 118183 59135 118183 58981 118184 59135 118184 58982 118184 58982 118185 59135 118185 59166 118185 58982 118186 59166 118186 59136 118186 59136 118187 59166 118187 59167 118187 59136 118188 59167 118188 59137 118188 59137 118189 59167 118189 59169 118189 59137 118190 59169 118190 59138 118190 59138 118191 59169 118191 59170 118191 59138 118192 59170 118192 58980 118192 58980 118193 59170 118193 59139 118193 58980 118194 59139 118194 59140 118194 59140 118195 59139 118195 59116 118195 59139 118196 59141 118196 59116 118196 59116 118197 59141 118197 59142 118197 59116 118198 59142 118198 59117 118198 59117 118199 59142 118199 59174 118199 59117 118200 59174 118200 59118 118200 59118 118201 59174 118201 59143 118201 59118 118202 59143 118202 59120 118202 59120 118203 59143 118203 59176 118203 59120 118204 59176 118204 59144 118204 59144 118205 59176 118205 59145 118205 59144 118206 59145 118206 59123 118206 59123 118207 59145 118207 59146 118207 59123 118208 59146 118208 59147 118208 59147 118209 59146 118209 59149 118209 59147 118210 59149 118210 59148 118210 59148 118211 59149 118211 59178 118211 59148 118212 59178 118212 59150 118212 59150 118213 59178 118213 59151 118213 59150 118214 59151 118214 59152 118214 59152 118215 59151 118215 59180 118215 59152 118216 59180 118216 59154 118216 59154 118217 59180 118217 59153 118217 59154 118218 59153 118218 59127 118218 59127 118219 59153 118219 59181 118219 59127 118220 59181 118220 59129 118220 59129 118221 59181 118221 59183 118221 59129 118222 59183 118222 59155 118222 59155 118223 59183 118223 59156 118223 59155 118224 59156 118224 59157 118224 59157 118225 59156 118225 59184 118225 59157 118226 59184 118226 59131 118226 59131 118227 59184 118227 59158 118227 59131 118228 59158 118228 59159 118228 59159 118229 59158 118229 59160 118229 59159 118230 59160 118230 59132 118230 59132 118231 59160 118231 59188 118231 59132 118232 59188 118232 59161 118232 59161 118233 59188 118233 59189 118233 59161 118234 59189 118234 59134 118234 59134 118235 59189 118235 59162 118235 59134 118236 59162 118236 59163 118236 59163 118237 59162 118237 59191 118237 59163 118238 59191 118238 59164 118238 59164 118239 59191 118239 59192 118239 59164 118240 59192 118240 59135 118240 59135 118241 59192 118241 59165 118241 59135 118242 59165 118242 59166 118242 59166 118243 59165 118243 59194 118243 59166 118244 59194 118244 59167 118244 59167 118245 59194 118245 59168 118245 59167 118246 59168 118246 59169 118246 59169 118247 59168 118247 59195 118247 59169 118248 59195 118248 59170 118248 59170 118249 59195 118249 59171 118249 59170 118250 59171 118250 59139 118250 59139 118251 59171 118251 59141 118251 59171 118252 59172 118252 59141 118252 59141 118253 59172 118253 59173 118253 59141 118254 59173 118254 59142 118254 59142 118255 59173 118255 58969 118255 59142 118256 58969 118256 59174 118256 59174 118257 58969 118257 58970 118257 59174 118258 58970 118258 59143 118258 59143 118259 58970 118259 59175 118259 59143 118260 59175 118260 59176 118260 59176 118261 59175 118261 58971 118261 59176 118262 58971 118262 59145 118262 59145 118263 58971 118263 59177 118263 59145 118264 59177 118264 59146 118264 59146 118265 59177 118265 58972 118265 59146 118266 58972 118266 59149 118266 59149 118267 58972 118267 58976 118267 59149 118268 58976 118268 59178 118268 59178 118269 58976 118269 58975 118269 59178 118270 58975 118270 59151 118270 59151 118271 58975 118271 59179 118271 59151 118272 59179 118272 59180 118272 59180 118273 59179 118273 58979 118273 59180 118274 58979 118274 59153 118274 59153 118275 58979 118275 58978 118275 59153 118276 58978 118276 59181 118276 59181 118277 58978 118277 59182 118277 59181 118278 59182 118278 59183 118278 59183 118279 59182 118279 58977 118279 59183 118280 58977 118280 59156 118280 59156 118281 58977 118281 59185 118281 59156 118282 59185 118282 59184 118282 59184 118283 59185 118283 58957 118283 59184 118284 58957 118284 59158 118284 59158 118285 58957 118285 59186 118285 59158 118286 59186 118286 59160 118286 59160 118287 59186 118287 59187 118287 59160 118288 59187 118288 59188 118288 59188 118289 59187 118289 58960 118289 59188 118290 58960 118290 59189 118290 59189 118291 58960 118291 59190 118291 59189 118292 59190 118292 59162 118292 59162 118293 59190 118293 58962 118293 59162 118294 58962 118294 59191 118294 59191 118295 58962 118295 58961 118295 59191 118296 58961 118296 59192 118296 59192 118297 58961 118297 58963 118297 59192 118298 58963 118298 59165 118298 59165 118299 58963 118299 59193 118299 59165 118300 59193 118300 59194 118300 59194 118301 59193 118301 58965 118301 59194 118302 58965 118302 59168 118302 59168 118303 58965 118303 58964 118303 59168 118304 58964 118304 59195 118304 59195 118305 58964 118305 58967 118305 59195 118306 58967 118306 59171 118306 59171 118307 58967 118307 59172 118307 59196 118308 59197 118308 59198 118308 59198 118309 59197 118309 59199 118309 59198 118310 59199 118310 58729 118310 58729 118311 59199 118311 59200 118311 58729 118312 59200 118312 59201 118312 59201 118313 59200 118313 59233 118313 59201 118314 59233 118314 59202 118314 59202 118315 59233 118315 59203 118315 59202 118316 59203 118316 59204 118316 59204 118317 59203 118317 59205 118317 59204 118318 59205 118318 59206 118318 59206 118319 59205 118319 59235 118319 59206 118320 59235 118320 58741 118320 58741 118321 59235 118321 59238 118321 58741 118322 59238 118322 58742 118322 58742 118323 59238 118323 59207 118323 58742 118324 59207 118324 58743 118324 58743 118325 59207 118325 59208 118325 58743 118326 59208 118326 58744 118326 58744 118327 59208 118327 59240 118327 58744 118328 59240 118328 58746 118328 58746 118329 59240 118329 59209 118329 58746 118330 59209 118330 58748 118330 58748 118331 59209 118331 59245 118331 58748 118332 59245 118332 58749 118332 58749 118333 59245 118333 59211 118333 58749 118334 59211 118334 59210 118334 59210 118335 59211 118335 59212 118335 59210 118336 59212 118336 58752 118336 58752 118337 59212 118337 59247 118337 58752 118338 59247 118338 59213 118338 59213 118339 59247 118339 59214 118339 59213 118340 59214 118340 58725 118340 58725 118341 59214 118341 59250 118341 58725 118342 59250 118342 59215 118342 59215 118343 59250 118343 59252 118343 59215 118344 59252 118344 58727 118344 58727 118345 59252 118345 59253 118345 58727 118346 59253 118346 58728 118346 58728 118347 59253 118347 59217 118347 58728 118348 59217 118348 59216 118348 59216 118349 59217 118349 59255 118349 59216 118350 59255 118350 58719 118350 58719 118351 59255 118351 59256 118351 58719 118352 59256 118352 58721 118352 58721 118353 59256 118353 59258 118353 58721 118354 59258 118354 59218 118354 59218 118355 59258 118355 59219 118355 59218 118356 59219 118356 59220 118356 59220 118357 59219 118357 59221 118357 59220 118358 59221 118358 58722 118358 58722 118359 59221 118359 59262 118359 58722 118360 59262 118360 58732 118360 58732 118361 59262 118361 59222 118361 58732 118362 59222 118362 58733 118362 58733 118363 59222 118363 59223 118363 58733 118364 59223 118364 58734 118364 58734 118365 59223 118365 59224 118365 58734 118366 59224 118366 59225 118366 59225 118367 59224 118367 59265 118367 59225 118368 59265 118368 59226 118368 59226 118369 59265 118369 59266 118369 59226 118370 59266 118370 58739 118370 58739 118371 59266 118371 59267 118371 58739 118372 59267 118372 59227 118372 59227 118373 59267 118373 59268 118373 59227 118374 59268 118374 59228 118374 59228 118375 59268 118375 59229 118375 59228 118376 59229 118376 58736 118376 58736 118377 59229 118377 59230 118377 58736 118378 59230 118378 59196 118378 59196 118379 59230 118379 59197 118379 59230 118380 59231 118380 59197 118380 59197 118381 59231 118381 59270 118381 59197 118382 59270 118382 59199 118382 59199 118383 59270 118383 59271 118383 59199 118384 59271 118384 59200 118384 59200 118385 59271 118385 59232 118385 59200 118386 59232 118386 59233 118386 59233 118387 59232 118387 59272 118387 59233 118388 59272 118388 59203 118388 59203 118389 59272 118389 59234 118389 59203 118390 59234 118390 59205 118390 59205 118391 59234 118391 59274 118391 59205 118392 59274 118392 59235 118392 59235 118393 59274 118393 59236 118393 59235 118394 59236 118394 59238 118394 59238 118395 59236 118395 59237 118395 59238 118396 59237 118396 59207 118396 59207 118397 59237 118397 59239 118397 59207 118398 59239 118398 59208 118398 59208 118399 59239 118399 59241 118399 59208 118400 59241 118400 59240 118400 59240 118401 59241 118401 59242 118401 59240 118402 59242 118402 59209 118402 59209 118403 59242 118403 59243 118403 59209 118404 59243 118404 59245 118404 59245 118405 59243 118405 59244 118405 59245 118406 59244 118406 59211 118406 59211 118407 59244 118407 59277 118407 59211 118408 59277 118408 59212 118408 59212 118409 59277 118409 59246 118409 59212 118410 59246 118410 59247 118410 59247 118411 59246 118411 59248 118411 59247 118412 59248 118412 59214 118412 59214 118413 59248 118413 59249 118413 59214 118414 59249 118414 59250 118414 59250 118415 59249 118415 59251 118415 59250 118416 59251 118416 59252 118416 59252 118417 59251 118417 59282 118417 59252 118418 59282 118418 59253 118418 59253 118419 59282 118419 59284 118419 59253 118420 59284 118420 59217 118420 59217 118421 59284 118421 59254 118421 59217 118422 59254 118422 59255 118422 59255 118423 59254 118423 59285 118423 59255 118424 59285 118424 59256 118424 59256 118425 59285 118425 59257 118425 59256 118426 59257 118426 59258 118426 59258 118427 59257 118427 59259 118427 59258 118428 59259 118428 59219 118428 59219 118429 59259 118429 59260 118429 59219 118430 59260 118430 59221 118430 59221 118431 59260 118431 59261 118431 59221 118432 59261 118432 59262 118432 59262 118433 59261 118433 59263 118433 59262 118434 59263 118434 59222 118434 59222 118435 59263 118435 59264 118435 59222 118436 59264 118436 59223 118436 59223 118437 59264 118437 59288 118437 59223 118438 59288 118438 59224 118438 59224 118439 59288 118439 59290 118439 59224 118440 59290 118440 59265 118440 59265 118441 59290 118441 59291 118441 59265 118442 59291 118442 59266 118442 59266 118443 59291 118443 59293 118443 59266 118444 59293 118444 59267 118444 59267 118445 59293 118445 59294 118445 59267 118446 59294 118446 59268 118446 59268 118447 59294 118447 59295 118447 59268 118448 59295 118448 59229 118448 59229 118449 59295 118449 59296 118449 59229 118450 59296 118450 59230 118450 59230 118451 59296 118451 59231 118451 59296 118452 59297 118452 59231 118452 59231 118453 59297 118453 59269 118453 59231 118454 59269 118454 59270 118454 59270 118455 59269 118455 58953 118455 59270 118456 58953 118456 59271 118456 59271 118457 58953 118457 58952 118457 59271 118458 58952 118458 59232 118458 59232 118459 58952 118459 58951 118459 59232 118460 58951 118460 59272 118460 59272 118461 58951 118461 58950 118461 59272 118462 58950 118462 59234 118462 59234 118463 58950 118463 59273 118463 59234 118464 59273 118464 59274 118464 59274 118465 59273 118465 58949 118465 59274 118466 58949 118466 59236 118466 59236 118467 58949 118467 58948 118467 59236 118468 58948 118468 59237 118468 59237 118469 58948 118469 58946 118469 59237 118470 58946 118470 59239 118470 59239 118471 58946 118471 59275 118471 59239 118472 59275 118472 59241 118472 59241 118473 59275 118473 58944 118473 59241 118474 58944 118474 59242 118474 59242 118475 58944 118475 58943 118475 59242 118476 58943 118476 59243 118476 59243 118477 58943 118477 59276 118477 59243 118478 59276 118478 59244 118478 59244 118479 59276 118479 58940 118479 59244 118480 58940 118480 59277 118480 59277 118481 58940 118481 59278 118481 59277 118482 59278 118482 59246 118482 59246 118483 59278 118483 59279 118483 59246 118484 59279 118484 59248 118484 59248 118485 59279 118485 58936 118485 59248 118486 58936 118486 59249 118486 59249 118487 58936 118487 59280 118487 59249 118488 59280 118488 59251 118488 59251 118489 59280 118489 59281 118489 59251 118490 59281 118490 59282 118490 59282 118491 59281 118491 58932 118491 59282 118492 58932 118492 59284 118492 59284 118493 58932 118493 59283 118493 59284 118494 59283 118494 59254 118494 59254 118495 59283 118495 58931 118495 59254 118496 58931 118496 59285 118496 59285 118497 58931 118497 58929 118497 59285 118498 58929 118498 59257 118498 59257 118499 58929 118499 58928 118499 59257 118500 58928 118500 59259 118500 59259 118501 58928 118501 58927 118501 59259 118502 58927 118502 59260 118502 59260 118503 58927 118503 58924 118503 59260 118504 58924 118504 59261 118504 59261 118505 58924 118505 58922 118505 59261 118506 58922 118506 59263 118506 59263 118507 58922 118507 59286 118507 59263 118508 59286 118508 59264 118508 59264 118509 59286 118509 58919 118509 59264 118510 58919 118510 59288 118510 59288 118511 58919 118511 59287 118511 59288 118512 59287 118512 59290 118512 59290 118513 59287 118513 59289 118513 59290 118514 59289 118514 59291 118514 59291 118515 59289 118515 59292 118515 59291 118516 59292 118516 59293 118516 59293 118517 59292 118517 58917 118517 59293 118518 58917 118518 59294 118518 59294 118519 58917 118519 58916 118519 59294 118520 58916 118520 59295 118520 59295 118521 58916 118521 58956 118521 59295 118522 58956 118522 59296 118522 59296 118523 58956 118523 59297 118523 58057 118524 59334 118524 58058 118524 58058 118525 59334 118525 59298 118525 58058 118526 59298 118526 59299 118526 59299 118527 59298 118527 59300 118527 59299 118528 59300 118528 59301 118528 59301 118529 59300 118529 59302 118529 59301 118530 59302 118530 59303 118530 59303 118531 59302 118531 59338 118531 59303 118532 59338 118532 58039 118532 58039 118533 59338 118533 59339 118533 58039 118534 59339 118534 58040 118534 58040 118535 59339 118535 59342 118535 58040 118536 59342 118536 59304 118536 59304 118537 59342 118537 59305 118537 59304 118538 59305 118538 58050 118538 58050 118539 59305 118539 59306 118539 58050 118540 59306 118540 59307 118540 59307 118541 59306 118541 59308 118541 59307 118542 59308 118542 58041 118542 58041 118543 59308 118543 59345 118543 58041 118544 59345 118544 58053 118544 58053 118545 59345 118545 59347 118545 58053 118546 59347 118546 59309 118546 59309 118547 59347 118547 59348 118547 59309 118548 59348 118548 58054 118548 58054 118549 59348 118549 59350 118549 58054 118550 59350 118550 59310 118550 59310 118551 59350 118551 59351 118551 59310 118552 59351 118552 58018 118552 58018 118553 59351 118553 59311 118553 58018 118554 59311 118554 58027 118554 58027 118555 59311 118555 59312 118555 58027 118556 59312 118556 58028 118556 58028 118557 59312 118557 59313 118557 58028 118558 59313 118558 58029 118558 58029 118559 59313 118559 59314 118559 58029 118560 59314 118560 59315 118560 59315 118561 59314 118561 59316 118561 59315 118562 59316 118562 58060 118562 58060 118563 59316 118563 59317 118563 58060 118564 59317 118564 58066 118564 58066 118565 59317 118565 59318 118565 58066 118566 59318 118566 59319 118566 59319 118567 59318 118567 59357 118567 59319 118568 59357 118568 58068 118568 58068 118569 59357 118569 59321 118569 58068 118570 59321 118570 59320 118570 59320 118571 59321 118571 59359 118571 59320 118572 59359 118572 59322 118572 59322 118573 59359 118573 59360 118573 59322 118574 59360 118574 58069 118574 58069 118575 59360 118575 59361 118575 58069 118576 59361 118576 59323 118576 59323 118577 59361 118577 59363 118577 59323 118578 59363 118578 59324 118578 59324 118579 59363 118579 59364 118579 59324 118580 59364 118580 58061 118580 58061 118581 59364 118581 59326 118581 58061 118582 59326 118582 59325 118582 59325 118583 59326 118583 59327 118583 59325 118584 59327 118584 58062 118584 58062 118585 59327 118585 59328 118585 58062 118586 59328 118586 58064 118586 58064 118587 59328 118587 59329 118587 58064 118588 59329 118588 58065 118588 58065 118589 59329 118589 59331 118589 58065 118590 59331 118590 59330 118590 59330 118591 59331 118591 59332 118591 59330 118592 59332 118592 58056 118592 58056 118593 59332 118593 59333 118593 58056 118594 59333 118594 58057 118594 58057 118595 59333 118595 59334 118595 59333 118596 59369 118596 59334 118596 59334 118597 59369 118597 59370 118597 59334 118598 59370 118598 59298 118598 59298 118599 59370 118599 59335 118599 59298 118600 59335 118600 59300 118600 59300 118601 59335 118601 59336 118601 59300 118602 59336 118602 59302 118602 59302 118603 59336 118603 59337 118603 59302 118604 59337 118604 59338 118604 59338 118605 59337 118605 59340 118605 59338 118606 59340 118606 59339 118606 59339 118607 59340 118607 59341 118607 59339 118608 59341 118608 59342 118608 59342 118609 59341 118609 59343 118609 59342 118610 59343 118610 59305 118610 59305 118611 59343 118611 59373 118611 59305 118612 59373 118612 59306 118612 59306 118613 59373 118613 59344 118613 59306 118614 59344 118614 59308 118614 59308 118615 59344 118615 59346 118615 59308 118616 59346 118616 59345 118616 59345 118617 59346 118617 59377 118617 59345 118618 59377 118618 59347 118618 59347 118619 59377 118619 59349 118619 59347 118620 59349 118620 59348 118620 59348 118621 59349 118621 59379 118621 59348 118622 59379 118622 59350 118622 59350 118623 59379 118623 59352 118623 59350 118624 59352 118624 59351 118624 59351 118625 59352 118625 59382 118625 59351 118626 59382 118626 59311 118626 59311 118627 59382 118627 59383 118627 59311 118628 59383 118628 59312 118628 59312 118629 59383 118629 59386 118629 59312 118630 59386 118630 59313 118630 59313 118631 59386 118631 59387 118631 59313 118632 59387 118632 59314 118632 59314 118633 59387 118633 59353 118633 59314 118634 59353 118634 59316 118634 59316 118635 59353 118635 59354 118635 59316 118636 59354 118636 59317 118636 59317 118637 59354 118637 59355 118637 59317 118638 59355 118638 59318 118638 59318 118639 59355 118639 59356 118639 59318 118640 59356 118640 59357 118640 59357 118641 59356 118641 59391 118641 59357 118642 59391 118642 59321 118642 59321 118643 59391 118643 59358 118643 59321 118644 59358 118644 59359 118644 59359 118645 59358 118645 59393 118645 59359 118646 59393 118646 59360 118646 59360 118647 59393 118647 59394 118647 59360 118648 59394 118648 59361 118648 59361 118649 59394 118649 59395 118649 59361 118650 59395 118650 59363 118650 59363 118651 59395 118651 59362 118651 59363 118652 59362 118652 59364 118652 59364 118653 59362 118653 59365 118653 59364 118654 59365 118654 59326 118654 59326 118655 59365 118655 59397 118655 59326 118656 59397 118656 59327 118656 59327 118657 59397 118657 59366 118657 59327 118658 59366 118658 59328 118658 59328 118659 59366 118659 59367 118659 59328 118660 59367 118660 59329 118660 59329 118661 59367 118661 59368 118661 59329 118662 59368 118662 59331 118662 59331 118663 59368 118663 59400 118663 59331 118664 59400 118664 59332 118664 59332 118665 59400 118665 59401 118665 59332 118666 59401 118666 59333 118666 59333 118667 59401 118667 59369 118667 59401 118668 58937 118668 59369 118668 59369 118669 58937 118669 58938 118669 59369 118670 58938 118670 59370 118670 59370 118671 58938 118671 58939 118671 59370 118672 58939 118672 59335 118672 59335 118673 58939 118673 58941 118673 59335 118674 58941 118674 59336 118674 59336 118675 58941 118675 58942 118675 59336 118676 58942 118676 59337 118676 59337 118677 58942 118677 59371 118677 59337 118678 59371 118678 59340 118678 59340 118679 59371 118679 59372 118679 59340 118680 59372 118680 59341 118680 59341 118681 59372 118681 58945 118681 59341 118682 58945 118682 59343 118682 59343 118683 58945 118683 58947 118683 59343 118684 58947 118684 59373 118684 59373 118685 58947 118685 59374 118685 59373 118686 59374 118686 59344 118686 59344 118687 59374 118687 59375 118687 59344 118688 59375 118688 59346 118688 59346 118689 59375 118689 59376 118689 59346 118690 59376 118690 59377 118690 59377 118691 59376 118691 59378 118691 59377 118692 59378 118692 59349 118692 59349 118693 59378 118693 59380 118693 59349 118694 59380 118694 59379 118694 59379 118695 59380 118695 59381 118695 59379 118696 59381 118696 59352 118696 59352 118697 59381 118697 58954 118697 59352 118698 58954 118698 59382 118698 59382 118699 58954 118699 59384 118699 59382 118700 59384 118700 59383 118700 59383 118701 59384 118701 58955 118701 59383 118702 58955 118702 59386 118702 59386 118703 58955 118703 59385 118703 59386 118704 59385 118704 59387 118704 59387 118705 59385 118705 59388 118705 59387 118706 59388 118706 59353 118706 59353 118707 59388 118707 59389 118707 59353 118708 59389 118708 59354 118708 59354 118709 59389 118709 59390 118709 59354 118710 59390 118710 59355 118710 59355 118711 59390 118711 58918 118711 59355 118712 58918 118712 59356 118712 59356 118713 58918 118713 58920 118713 59356 118714 58920 118714 59391 118714 59391 118715 58920 118715 58921 118715 59391 118716 58921 118716 59358 118716 59358 118717 58921 118717 59392 118717 59358 118718 59392 118718 59393 118718 59393 118719 59392 118719 58923 118719 59393 118720 58923 118720 59394 118720 59394 118721 58923 118721 58925 118721 59394 118722 58925 118722 59395 118722 59395 118723 58925 118723 58926 118723 59395 118724 58926 118724 59362 118724 59362 118725 58926 118725 59396 118725 59362 118726 59396 118726 59365 118726 59365 118727 59396 118727 58930 118727 59365 118728 58930 118728 59397 118728 59397 118729 58930 118729 59398 118729 59397 118730 59398 118730 59366 118730 59366 118731 59398 118731 59399 118731 59366 118732 59399 118732 59367 118732 59367 118733 59399 118733 58933 118733 59367 118734 58933 118734 59368 118734 59368 118735 58933 118735 58934 118735 59368 118736 58934 118736 59400 118736 59400 118737 58934 118737 58935 118737 59400 118738 58935 118738 59401 118738 59401 118739 58935 118739 58937 118739 59402 118740 59403 118740 59474 118740 59474 118741 59403 118741 59404 118741 59405 118742 59406 118742 64628 118742 62936 118743 62937 118743 59506 118743 59506 118744 64630 118744 62936 118744 62936 118745 64630 118745 59914 118745 62936 118746 59914 118746 59407 118746 59407 118747 59914 118747 59405 118747 59407 118748 59405 118748 59408 118748 59408 118749 59405 118749 64628 118749 62943 118750 59410 118750 59409 118750 59409 118751 59410 118751 59412 118751 59409 118752 59412 118752 59411 118752 59412 118753 59538 118753 64631 118753 64631 118754 64632 118754 59412 118754 59412 118755 64632 118755 64634 118755 59412 118756 64634 118756 59411 118756 59502 118757 64670 118757 59413 118757 59413 118758 64670 118758 59416 118758 59413 118759 59416 118759 59414 118759 59414 118760 59416 118760 59418 118760 59415 118761 64672 118761 59416 118761 59416 118762 64672 118762 59417 118762 59416 118763 59417 118763 59418 118763 59499 118764 59419 118764 59420 118764 59420 118765 59419 118765 59536 118765 59420 118766 59536 118766 62933 118766 62933 118767 59536 118767 59421 118767 59535 118768 59422 118768 59536 118768 59536 118769 59422 118769 59478 118769 59536 118770 59478 118770 59421 118770 59498 118771 59423 118771 59424 118771 59424 118772 59423 118772 59425 118772 59424 118773 59425 118773 59902 118773 59902 118774 59425 118774 62934 118774 64665 118775 64666 118775 59425 118775 59425 118776 64666 118776 59900 118776 59425 118777 59900 118777 62934 118777 64664 118778 59426 118778 59427 118778 59427 118779 59426 118779 59428 118779 59427 118780 59428 118780 62928 118780 62928 118781 59428 118781 62929 118781 59531 118782 59480 118782 59428 118782 59428 118783 59480 118783 59429 118783 59428 118784 59429 118784 62929 118784 59430 118785 59494 118785 59899 118785 59899 118786 59494 118786 59492 118786 59492 118787 59431 118787 59432 118787 62925 118788 59899 118788 62927 118788 62927 118789 59899 118789 59492 118789 62927 118790 59492 118790 59898 118790 59898 118791 59492 118791 59432 118791 59488 118792 62916 118792 59433 118792 59434 118793 59488 118793 59435 118793 59435 118794 59488 118794 59433 118794 59435 118795 59433 118795 59436 118795 59437 118796 59438 118796 59488 118796 59488 118797 59438 118797 59439 118797 59488 118798 59439 118798 62916 118798 59897 118799 59441 118799 59440 118799 59440 118800 59441 118800 62920 118800 59440 118801 62920 118801 62921 118801 59442 118802 64627 118802 59440 118802 59440 118803 64627 118803 59443 118803 59440 118804 59443 118804 59897 118804 59444 118805 59445 118805 59510 118805 59446 118806 59511 118806 59510 118806 59510 118807 59511 118807 59909 118807 59510 118808 59909 118808 59444 118808 59448 118809 59447 118809 59449 118809 62971 118810 59448 118810 59909 118810 59909 118811 59448 118811 59449 118811 59909 118812 59449 118812 59444 118812 59516 118813 59541 118813 59450 118813 59450 118814 59541 118814 59451 118814 59450 118815 59451 118815 62949 118815 62949 118816 59451 118816 59452 118816 59452 118817 59451 118817 59453 118817 59453 118818 59451 118818 59449 118818 59453 118819 59449 118819 59917 118819 59917 118820 59449 118820 59447 118820 59917 118821 59447 118821 59454 118821 64700 118822 59455 118822 59457 118822 59457 118823 59455 118823 59552 118823 59552 118824 59551 118824 59457 118824 59457 118825 59551 118825 59456 118825 59457 118826 59456 118826 59458 118826 59459 118827 59461 118827 59460 118827 59460 118828 59461 118828 63198 118828 63198 118829 63197 118829 59460 118829 59460 118830 63197 118830 63189 118830 59460 118831 63189 118831 63183 118831 59462 118832 59518 118832 59463 118832 59463 118833 59518 118833 63166 118833 63166 118834 63169 118834 59463 118834 59463 118835 63169 118835 63164 118835 59463 118836 63164 118836 63152 118836 59521 118837 59464 118837 59520 118837 59520 118838 59464 118838 63130 118838 63130 118839 59465 118839 59520 118839 59520 118840 59465 118840 59466 118840 59520 118841 59466 118841 63117 118841 59524 118842 64699 118842 59469 118842 59469 118843 64699 118843 59467 118843 59467 118844 59468 118844 59469 118844 59469 118845 59468 118845 63095 118845 59469 118846 63095 118846 59470 118846 59471 118847 59528 118847 63059 118847 63059 118848 59528 118848 59472 118848 63059 118849 59472 118849 63057 118849 63057 118850 59472 118850 59473 118850 60302 118851 59403 118851 60299 118851 60299 118852 59403 118852 59402 118852 59474 118853 59404 118853 60305 118853 60305 118854 59404 118854 62970 118854 59914 118855 64630 118855 59915 118855 59915 118856 64630 118856 60342 118856 59915 118857 60342 118857 60343 118857 62922 118858 60316 118858 59475 118858 59475 118859 60316 118859 59442 118859 59475 118860 59442 118860 59440 118860 62932 118861 59417 118861 59476 118861 59476 118862 59417 118862 64672 118862 59476 118863 64672 118863 60326 118863 59477 118864 59478 118864 62931 118864 62931 118865 59478 118865 59422 118865 62931 118866 59422 118866 64669 118866 59901 118867 59900 118867 60331 118867 60331 118868 59900 118868 64666 118868 60331 118869 64666 118869 59479 118869 62926 118870 59429 118870 60335 118870 60335 118871 59429 118871 59480 118871 60335 118872 59480 118872 59481 118872 59482 118873 59898 118873 59483 118873 59483 118874 59898 118874 59432 118874 59483 118875 59432 118875 60337 118875 64663 118876 59484 118876 59438 118876 59438 118877 59484 118877 59485 118877 59438 118878 59485 118878 59439 118878 59433 118879 59486 118879 59436 118879 59436 118880 59486 118880 60323 118880 59436 118881 60323 118881 60322 118881 62914 118882 59488 118882 59487 118882 59487 118883 59488 118883 59434 118883 59487 118884 59434 118884 60321 118884 60320 118885 59437 118885 59489 118885 59489 118886 59437 118886 59488 118886 59489 118887 59488 118887 62914 118887 60318 118888 59430 118888 59490 118888 59490 118889 59430 118889 59899 118889 59490 118890 59899 118890 59491 118890 62915 118891 59492 118891 59493 118891 59493 118892 59492 118892 59494 118892 59493 118893 59494 118893 59495 118893 60338 118894 59431 118894 60339 118894 60339 118895 59431 118895 59492 118895 60339 118896 59492 118896 62915 118896 59496 118897 64664 118897 62924 118897 62924 118898 64664 118898 59427 118898 62924 118899 59427 118899 59497 118899 60327 118900 59498 118900 60336 118900 60336 118901 59498 118901 59424 118901 60336 118902 59424 118902 59903 118902 64667 118903 59499 118903 59500 118903 59500 118904 59499 118904 59420 118904 59500 118905 59420 118905 59904 118905 59501 118906 59502 118906 62930 118906 62930 118907 59502 118907 59413 118907 62930 118908 59413 118908 59503 118908 59504 118909 59897 118909 59998 118909 59998 118910 59897 118910 59443 118910 59998 118911 59443 118911 59505 118911 59506 118912 62937 118912 60340 118912 60340 118913 62937 118913 59507 118913 60312 118914 59509 118914 59508 118914 59508 118915 59509 118915 59446 118915 59508 118916 59446 118916 59510 118916 59909 118917 59511 118917 59908 118917 59908 118918 59511 118918 60311 118918 59908 118919 60311 118919 62972 118919 59512 118920 59408 118920 64629 118920 64629 118921 59408 118921 64628 118921 60346 118922 59513 118922 59912 118922 59912 118923 59513 118923 59406 118923 59912 118924 59406 118924 59405 118924 59445 118925 59514 118925 59510 118925 59510 118926 59514 118926 60313 118926 59510 118927 60313 118927 59508 118927 59515 118928 60307 118928 59516 118928 63238 118929 59515 118929 63231 118929 63231 118930 59515 118930 59516 118930 63231 118931 59516 118931 63230 118931 63230 118932 59516 118932 59450 118932 64700 118933 59457 118933 64701 118933 59455 118934 59553 118934 59552 118934 59460 118935 59517 118935 59459 118935 59459 118936 59517 118936 60288 118936 59461 118937 64697 118937 63198 118937 59463 118938 63151 118938 59462 118938 59462 118939 63151 118939 60294 118939 60287 118940 59519 118940 59518 118940 59518 118941 59519 118941 63166 118941 59520 118942 59522 118942 59521 118942 59521 118943 59522 118943 59523 118943 64698 118944 60289 118944 59464 118944 59464 118945 60289 118945 63130 118945 59469 118946 63089 118946 59524 118946 59524 118947 63089 118947 60368 118947 60291 118948 63101 118948 64699 118948 64699 118949 63101 118949 59467 118949 60296 118950 59471 118950 59525 118950 59525 118951 59471 118951 63059 118951 59525 118952 63059 118952 59526 118952 59526 118953 63059 118953 63060 118953 59526 118954 63060 118954 63061 118954 63061 118955 59527 118955 59526 118955 59526 118956 59527 118956 63062 118956 59526 118957 63062 118957 62965 118957 60367 118958 63068 118958 59528 118958 59528 118959 63068 118959 59472 118959 59905 118960 59409 118960 59529 118960 59529 118961 59409 118961 59411 118961 60334 118962 59530 118962 59426 118962 59426 118963 59530 118963 59428 118963 59531 118964 59428 118964 60333 118964 60333 118965 59428 118965 59530 118965 59532 118966 60332 118966 59423 118966 59423 118967 60332 118967 59425 118967 64665 118968 59425 118968 59533 118968 59533 118969 59425 118969 60332 118969 60330 118970 59534 118970 59419 118970 59419 118971 59534 118971 59536 118971 59535 118972 59536 118972 64668 118972 64668 118973 59536 118973 59534 118973 60328 118974 59537 118974 64670 118974 64670 118975 59537 118975 59416 118975 59415 118976 59416 118976 64671 118976 64671 118977 59416 118977 59537 118977 59412 118978 59907 118978 59538 118978 59538 118979 59907 118979 60379 118979 59451 118980 59540 118980 59449 118980 59449 118981 59540 118981 64702 118981 59539 118982 59540 118982 59541 118982 59541 118983 59540 118983 59451 118983 59542 118984 59543 118984 59549 118984 59544 118985 59550 118985 63208 118985 64701 118986 59457 118986 59458 118986 59545 118987 59546 118987 64701 118987 64701 118988 59458 118988 59545 118988 59545 118989 59458 118989 59547 118989 59545 118990 59547 118990 63211 118990 59544 118991 63208 118991 59547 118991 59547 118992 63208 118992 59548 118992 59547 118993 59548 118993 63211 118993 59542 118994 59549 118994 59550 118994 59550 118995 59549 118995 63206 118995 59550 118996 63206 118996 63208 118996 59551 118997 59552 118997 60310 118997 60310 118998 59552 118998 59553 118998 60310 118999 59553 118999 59554 118999 63226 119000 59556 119000 63222 119000 63222 119001 59556 119001 59551 119001 63222 119002 59551 119002 63220 119002 63220 119003 59551 119003 60310 119003 63224 119004 63215 119004 59555 119004 59555 119005 63215 119005 59556 119005 59555 119006 59556 119006 63225 119006 63225 119007 59556 119007 63226 119007 63223 119008 59558 119008 59557 119008 59557 119009 59558 119009 63218 119009 59557 119010 63218 119010 63224 119010 63224 119011 63218 119011 63217 119011 63224 119012 63217 119012 63215 119012 59835 119013 59559 119013 59719 119013 63640 119014 59560 119014 59764 119014 59561 119015 59563 119015 59562 119015 59562 119016 59563 119016 62860 119016 59566 119017 61094 119017 59848 119017 60783 119018 60782 119018 63730 119018 59649 119019 64012 119019 59648 119019 59564 119020 59565 119020 59856 119020 61134 119021 61136 119021 59566 119021 61134 119022 59566 119022 61156 119022 60920 119023 59567 119023 59566 119023 59566 119024 59567 119024 59568 119024 59566 119025 59568 119025 61156 119025 61156 119026 59568 119026 59569 119026 61156 119027 59569 119027 61159 119027 61159 119028 59569 119028 59570 119028 61136 119029 61121 119029 59566 119029 59566 119030 61121 119030 61122 119030 59566 119031 61122 119031 59571 119031 59571 119032 61099 119032 59566 119032 59566 119033 61099 119033 61093 119033 59566 119034 61093 119034 61094 119034 59842 119035 59576 119035 59572 119035 64152 119036 64149 119036 59842 119036 59842 119037 64149 119037 59573 119037 59842 119038 59573 119038 59574 119038 59574 119039 64142 119039 59842 119039 59842 119040 64142 119040 59575 119040 59842 119041 59575 119041 59576 119041 59576 119042 59575 119042 59577 119042 59577 119043 59578 119043 59576 119043 59576 119044 59578 119044 64273 119044 59576 119045 64273 119045 64263 119045 64263 119046 64256 119046 59576 119046 59576 119047 64256 119047 59579 119047 59576 119048 59579 119048 59580 119048 59580 119049 59579 119049 59582 119049 59580 119050 59582 119050 59581 119050 59581 119051 59582 119051 59583 119051 59583 119052 64227 119052 59581 119052 59581 119053 64227 119053 59584 119053 59581 119054 59584 119054 59585 119054 59585 119055 59584 119055 59586 119055 59585 119056 59586 119056 59587 119056 59587 119057 59586 119057 59588 119057 59592 119058 60923 119058 64317 119058 64317 119059 60923 119059 59588 119059 64317 119060 59588 119060 64318 119060 64318 119061 59588 119061 59586 119061 59594 119062 60924 119062 59589 119062 59589 119063 60924 119063 59590 119063 59589 119064 59590 119064 59592 119064 59592 119065 59590 119065 59591 119065 59592 119066 59591 119066 60923 119066 59595 119067 60927 119067 64308 119067 64308 119068 60927 119068 60926 119068 64308 119069 60926 119069 59593 119069 59593 119070 60926 119070 59594 119070 59593 119071 59594 119071 64310 119071 64310 119072 59594 119072 59589 119072 59595 119073 64373 119073 60927 119073 60927 119074 64373 119074 59596 119074 60927 119075 59596 119075 60928 119075 60928 119076 59596 119076 64356 119076 60928 119077 64356 119077 60930 119077 60930 119078 64356 119078 64354 119078 60930 119079 64354 119079 59597 119079 59603 119080 64295 119080 59601 119080 59597 119081 64352 119081 60930 119081 60930 119082 64352 119082 64349 119082 60930 119083 64349 119083 59602 119083 64295 119084 59598 119084 59601 119084 59601 119085 59598 119085 64290 119085 59601 119086 64290 119086 59599 119086 59798 119087 64393 119087 59601 119087 59601 119088 64393 119088 59600 119088 59600 119089 64388 119089 59601 119089 59601 119090 64388 119090 64387 119090 59601 119091 64387 119091 64427 119091 59602 119092 59603 119092 60930 119092 60930 119093 59603 119093 59601 119093 60930 119094 59601 119094 64487 119094 64487 119095 59601 119095 64427 119095 64487 119096 64476 119096 60930 119096 60930 119097 64476 119097 59604 119097 60930 119098 59604 119098 64475 119098 64475 119099 64474 119099 60930 119099 60930 119100 64474 119100 64472 119100 60930 119101 64472 119101 59605 119101 59605 119102 64472 119102 64471 119102 59605 119103 64471 119103 64469 119103 64469 119104 64468 119104 59605 119104 59605 119105 64468 119105 59606 119105 59605 119106 59606 119106 60931 119106 60931 119107 59606 119107 64556 119107 60931 119108 64556 119108 59607 119108 59607 119109 64556 119109 64555 119109 59607 119110 64555 119110 60932 119110 60932 119111 64555 119111 59608 119111 60932 119112 59608 119112 60934 119112 60934 119113 59608 119113 59609 119113 60934 119114 59609 119114 59617 119114 59617 119115 59609 119115 64552 119115 64607 119116 59610 119116 60941 119116 64607 119117 60941 119117 59611 119117 59611 119118 60941 119118 59613 119118 59611 119119 59613 119119 59612 119119 59612 119120 59613 119120 60940 119120 59612 119121 60940 119121 64612 119121 64612 119122 60940 119122 59614 119122 64612 119123 59614 119123 64613 119123 64613 119124 59614 119124 60938 119124 64613 119125 60938 119125 59616 119125 59616 119126 60938 119126 59615 119126 59616 119127 59615 119127 64552 119127 64552 119128 59615 119128 60936 119128 64552 119129 60936 119129 59617 119129 59610 119130 64605 119130 60941 119130 60941 119131 64605 119131 64582 119131 60941 119132 64582 119132 64577 119132 59618 119133 59619 119133 59855 119133 59855 119134 59619 119134 59620 119134 59855 119135 59620 119135 64517 119135 64517 119136 59621 119136 59855 119136 59855 119137 59621 119137 59622 119137 59855 119138 59622 119138 59854 119138 64577 119139 59618 119139 60941 119139 60941 119140 59618 119140 59855 119140 60941 119141 59855 119141 59623 119141 59623 119142 59855 119142 59856 119142 59623 119143 59856 119143 60943 119143 60943 119144 59856 119144 59565 119144 61452 119145 59624 119145 59856 119145 61497 119146 59625 119146 59856 119146 59856 119147 59625 119147 61474 119147 59856 119148 61474 119148 61452 119148 59624 119149 61454 119149 59856 119149 59856 119150 61454 119150 59626 119150 59856 119151 59626 119151 59564 119151 59564 119152 59626 119152 61436 119152 59564 119153 61436 119153 61417 119153 59859 119154 59627 119154 59856 119154 59856 119155 59627 119155 61507 119155 59856 119156 61507 119156 61497 119156 61482 119157 59628 119157 59629 119157 60865 119158 61471 119158 61467 119158 60804 119159 60864 119159 59629 119159 59629 119160 60864 119160 60865 119160 59629 119161 60865 119161 61482 119161 61482 119162 60865 119162 61467 119162 59628 119163 61490 119163 59629 119163 59629 119164 61490 119164 61516 119164 59629 119165 61516 119165 61512 119165 61512 119166 61533 119166 59629 119166 59629 119167 61533 119167 59630 119167 59629 119168 59630 119168 59631 119168 64061 119169 64054 119169 59636 119169 59559 119170 64128 119170 59632 119170 59632 119171 64128 119171 64126 119171 59632 119172 64126 119172 59633 119172 64061 119173 59636 119173 64098 119173 59633 119174 59634 119174 59632 119174 59632 119175 59634 119175 64125 119175 59632 119176 64125 119176 64097 119176 60804 119177 59629 119177 59635 119177 59635 119178 59629 119178 59632 119178 59635 119179 59632 119179 59636 119179 59636 119180 59632 119180 64097 119180 59636 119181 64097 119181 64098 119181 64054 119182 64055 119182 59636 119182 59636 119183 64055 119183 59637 119183 59636 119184 59637 119184 59638 119184 64012 119185 59649 119185 64013 119185 64013 119186 59649 119186 59640 119186 64013 119187 59640 119187 59639 119187 59639 119188 59640 119188 59641 119188 59639 119189 59641 119189 64029 119189 64029 119190 59641 119190 60801 119190 64029 119191 60801 119191 59638 119191 59638 119192 60801 119192 60802 119192 59638 119193 60802 119193 59636 119193 59642 119194 60793 119194 60796 119194 59642 119195 60796 119195 59643 119195 59643 119196 60796 119196 59644 119196 59643 119197 59644 119197 59645 119197 59645 119198 59644 119198 60797 119198 59645 119199 60797 119199 59646 119199 59646 119200 60797 119200 60799 119200 59646 119201 60799 119201 59648 119201 59648 119202 60799 119202 59647 119202 59648 119203 59647 119203 59649 119203 60793 119204 59642 119204 59650 119204 59650 119205 59642 119205 63953 119205 59650 119206 63953 119206 59651 119206 59651 119207 63953 119207 63944 119207 59651 119208 63944 119208 63939 119208 63939 119209 63940 119209 59651 119209 59651 119210 63940 119210 63930 119210 59651 119211 63930 119211 59653 119211 59653 119212 63930 119212 63926 119212 63926 119213 63909 119213 59653 119213 59653 119214 63909 119214 59652 119214 59653 119215 59652 119215 63907 119215 63907 119216 63906 119216 59653 119216 59653 119217 63906 119217 59654 119217 59653 119218 59654 119218 59659 119218 59659 119219 59654 119219 59655 119219 59659 119220 59655 119220 63998 119220 63998 119221 63989 119221 59659 119221 59659 119222 63989 119222 59656 119222 59659 119223 59656 119223 63988 119223 59787 119224 63890 119224 59659 119224 59659 119225 63890 119225 63887 119225 63887 119226 63888 119226 59659 119226 59659 119227 63888 119227 63870 119227 59659 119228 63870 119228 59657 119228 59657 119229 59658 119229 59659 119229 59659 119230 59658 119230 63867 119230 59659 119231 63867 119231 59653 119231 59653 119232 63867 119232 63862 119232 63862 119233 59660 119233 59653 119233 59653 119234 59660 119234 59661 119234 59653 119235 59661 119235 63813 119235 63816 119236 59662 119236 59663 119236 59663 119237 59662 119237 60789 119237 59663 119238 60789 119238 59664 119238 59664 119239 60789 119239 59653 119239 59664 119240 59653 119240 63814 119240 63814 119241 59653 119241 63813 119241 63816 119242 63819 119242 59662 119242 59662 119243 63819 119243 59665 119243 59662 119244 59665 119244 60786 119244 63730 119245 60782 119245 63731 119245 59665 119246 59666 119246 60786 119246 60786 119247 59666 119247 59667 119247 60786 119248 59667 119248 59668 119248 59668 119249 59667 119249 63732 119249 59668 119250 63732 119250 60784 119250 60784 119251 63732 119251 63731 119251 60784 119252 63731 119252 59669 119252 59669 119253 63731 119253 60782 119253 60783 119254 63730 119254 59670 119254 59670 119255 63730 119255 59671 119255 59670 119256 59671 119256 60774 119256 60774 119257 59671 119257 63728 119257 60774 119258 63728 119258 60775 119258 60775 119259 63728 119259 63679 119259 60775 119260 63679 119260 59674 119260 63679 119261 59672 119261 59674 119261 59674 119262 59672 119262 59673 119262 59674 119263 59673 119263 60779 119263 59673 119264 63677 119264 60779 119264 60779 119265 63677 119265 63675 119265 60779 119266 63675 119266 59675 119266 59675 119267 63675 119267 63674 119267 59675 119268 63674 119268 63672 119268 63672 119269 63671 119269 59675 119269 59675 119270 63671 119270 63723 119270 59675 119271 63723 119271 63716 119271 59679 119272 59676 119272 59850 119272 59850 119273 59676 119273 59677 119273 59677 119274 59678 119274 59850 119274 59850 119275 59678 119275 63778 119275 59850 119276 63778 119276 59844 119276 63716 119277 59679 119277 59675 119277 59675 119278 59679 119278 59850 119278 59675 119279 59850 119279 60780 119279 60780 119280 59850 119280 60769 119280 59680 119281 59681 119281 59685 119281 59849 119282 61125 119282 59685 119282 59685 119283 61125 119283 61148 119283 59685 119284 61148 119284 59680 119284 59681 119285 59682 119285 59685 119285 59685 119286 59682 119286 59683 119286 59685 119287 59683 119287 59684 119287 60771 119288 59685 119288 59686 119288 59686 119289 59685 119289 59684 119289 59686 119290 59684 119290 60772 119290 60772 119291 59684 119291 59687 119291 60772 119292 59687 119292 61219 119292 62478 119293 62479 119293 59782 119293 62479 119294 62480 119294 59782 119294 59782 119295 62480 119295 62481 119295 59782 119296 62481 119296 59845 119296 59845 119297 62481 119297 62487 119297 59688 119298 62430 119298 59779 119298 59779 119299 62430 119299 62434 119299 59779 119300 62434 119300 59689 119300 62434 119301 62438 119301 59689 119301 59689 119302 62438 119302 59690 119302 59689 119303 59690 119303 59691 119303 59691 119304 59692 119304 59689 119304 59689 119305 59692 119305 62456 119305 59689 119306 62456 119306 59782 119306 59782 119307 62456 119307 59693 119307 59782 119308 59693 119308 62478 119308 59700 119309 59694 119309 59779 119309 59779 119310 59694 119310 62628 119310 59779 119311 62628 119311 59688 119311 59688 119312 62628 119312 59695 119312 59688 119313 59695 119313 59696 119313 59696 119314 62568 119314 59698 119314 62563 119315 62559 119315 59698 119315 59698 119316 62559 119316 59697 119316 59698 119317 59697 119317 59696 119317 59696 119318 59697 119318 62501 119318 59696 119319 62501 119319 59688 119319 62568 119320 59699 119320 59698 119320 59698 119321 59699 119321 62562 119321 59698 119322 62562 119322 62563 119322 59700 119323 59779 119323 59701 119323 59701 119324 59779 119324 59703 119324 59701 119325 59703 119325 59702 119325 59702 119326 59703 119326 59831 119326 59702 119327 59831 119327 59704 119327 59707 119328 62769 119328 59705 119328 62769 119329 62750 119329 59705 119329 59705 119330 62750 119330 62743 119330 59705 119331 62743 119331 59706 119331 59706 119332 62735 119332 59705 119332 59705 119333 62735 119333 62736 119333 59705 119334 62736 119334 59707 119334 59707 119335 62736 119335 59708 119335 59707 119336 59708 119336 59709 119336 59709 119337 59708 119337 59710 119337 59709 119338 59710 119338 59718 119338 59718 119339 59710 119339 62686 119339 59718 119340 62686 119340 59711 119340 59711 119341 59712 119341 59718 119341 59718 119342 59712 119342 59713 119342 59718 119343 59713 119343 59714 119343 59714 119344 59713 119344 62642 119344 59714 119345 62642 119345 59831 119345 59831 119346 62642 119346 62643 119346 59831 119347 62643 119347 59704 119347 62834 119348 59715 119348 59717 119348 59717 119349 59715 119349 59716 119349 59717 119350 59716 119350 59718 119350 59718 119351 59716 119351 62837 119351 59718 119352 62837 119352 59709 119352 62831 119353 59720 119353 59719 119353 62831 119354 59719 119354 62858 119354 59720 119355 59721 119355 59719 119355 59719 119356 59721 119356 59722 119356 59719 119357 59722 119357 59717 119357 59717 119358 59722 119358 62833 119358 59717 119359 62833 119359 62834 119359 62860 119360 59563 119360 62852 119360 62852 119361 59563 119361 59723 119361 62852 119362 59723 119362 62913 119362 62909 119363 62910 119363 59723 119363 59723 119364 62910 119364 62912 119364 59723 119365 62912 119365 62913 119365 59724 119366 59725 119366 59853 119366 59726 119367 59727 119367 59802 119367 59726 119368 59802 119368 62866 119368 59727 119369 62905 119369 59802 119369 59802 119370 62905 119370 59728 119370 59802 119371 59728 119371 59724 119371 62726 119372 62727 119372 59729 119372 59729 119373 62727 119373 62728 119373 59729 119374 62728 119374 62838 119374 59730 119375 62788 119375 59731 119375 62728 119376 62730 119376 62838 119376 62838 119377 62730 119377 62754 119377 62838 119378 62754 119378 59732 119378 59732 119379 62754 119379 59730 119379 59732 119380 59730 119380 62845 119380 62845 119381 59730 119381 59731 119381 62845 119382 59731 119382 62778 119382 62778 119383 59731 119383 62779 119383 62788 119384 59733 119384 59731 119384 59731 119385 59733 119385 62789 119385 59731 119386 62789 119386 62779 119386 59735 119387 59734 119387 59736 119387 59736 119388 59734 119388 63395 119388 59736 119389 63395 119389 63397 119389 59735 119390 59736 119390 59737 119390 59737 119391 59736 119391 59601 119391 59737 119392 59601 119392 59738 119392 62726 119393 59729 119393 62697 119393 62697 119394 59729 119394 59736 119394 62697 119395 59736 119395 59740 119395 59740 119396 59736 119396 63397 119396 59740 119397 63397 119397 59739 119397 59739 119398 59741 119398 59740 119398 59740 119399 59741 119399 63365 119399 59740 119400 63365 119400 59742 119400 59742 119401 63365 119401 59743 119401 59742 119402 59743 119402 62693 119402 63384 119403 63386 119403 62690 119403 59743 119404 59744 119404 62693 119404 62693 119405 59744 119405 59745 119405 62693 119406 59745 119406 62690 119406 62690 119407 59745 119407 63383 119407 62690 119408 63383 119408 63384 119408 59746 119409 63388 119409 59749 119409 63388 119410 59747 119410 59749 119410 59749 119411 59747 119411 59748 119411 59749 119412 59748 119412 59601 119412 59601 119413 59748 119413 63391 119413 59601 119414 63391 119414 59738 119414 59750 119415 59753 119415 59754 119415 62601 119416 59751 119416 59754 119416 59754 119417 59751 119417 59752 119417 59754 119418 59752 119418 59750 119418 59753 119419 62603 119419 59754 119419 59754 119420 62603 119420 62602 119420 59754 119421 62602 119421 62601 119421 62665 119422 59817 119422 59755 119422 59755 119423 59817 119423 62573 119423 59755 119424 62573 119424 62633 119424 62633 119425 62573 119425 59750 119425 62633 119426 59750 119426 62634 119426 62634 119427 59750 119427 59752 119427 63386 119428 59746 119428 62690 119428 62690 119429 59746 119429 59749 119429 62690 119430 59749 119430 59756 119430 59756 119431 59749 119431 59817 119431 59756 119432 59817 119432 62666 119432 62666 119433 59817 119433 62665 119433 59809 119434 62543 119434 59812 119434 59812 119435 62543 119435 62544 119435 59812 119436 62544 119436 62546 119436 62546 119437 59757 119437 59812 119437 59812 119438 59757 119438 62548 119438 59812 119439 62548 119439 59817 119439 59817 119440 62548 119440 62549 119440 59817 119441 62549 119441 62573 119441 62509 119442 62512 119442 59758 119442 62509 119443 59758 119443 59759 119443 59759 119444 59758 119444 59852 119444 59759 119445 59852 119445 62487 119445 59760 119446 59761 119446 59787 119446 59787 119447 59761 119447 63315 119447 59787 119448 63315 119448 63316 119448 59760 119449 59787 119449 63312 119449 63312 119450 59787 119450 59659 119450 63312 119451 59659 119451 59773 119451 59764 119452 59786 119452 59762 119452 59763 119453 63324 119453 59768 119453 59762 119454 59765 119454 59764 119454 59764 119455 59765 119455 59766 119455 59764 119456 59766 119456 59767 119456 59767 119457 59766 119457 63320 119457 59767 119458 63320 119458 59768 119458 59768 119459 63320 119459 63322 119459 59768 119460 63322 119460 59763 119460 59830 119461 59769 119461 59818 119461 59818 119462 59769 119462 63287 119462 63287 119463 59770 119463 59818 119463 59818 119464 59770 119464 59771 119464 59818 119465 59771 119465 59659 119465 59659 119466 59771 119466 59772 119466 59659 119467 59772 119467 59773 119467 63572 119468 63621 119468 59779 119468 59779 119469 63621 119469 63622 119469 59779 119470 63622 119470 59703 119470 59703 119471 63622 119471 59774 119471 59703 119472 59774 119472 63623 119472 63623 119473 63624 119473 59703 119473 59703 119474 63624 119474 63627 119474 59703 119475 63627 119475 59775 119475 59775 119476 63629 119476 59703 119476 59703 119477 63629 119477 59776 119477 59703 119478 59776 119478 63637 119478 59777 119479 59778 119479 59689 119479 59689 119480 59778 119480 63559 119480 63559 119481 63561 119481 59689 119481 59689 119482 63561 119482 63562 119482 59689 119483 63562 119483 59779 119483 59779 119484 63562 119484 59780 119484 59779 119485 59780 119485 63572 119485 63564 119486 63537 119486 59782 119486 63600 119487 63565 119487 59837 119487 59837 119488 63565 119488 63564 119488 63537 119489 59781 119489 59782 119489 59782 119490 59781 119490 63556 119490 59782 119491 63556 119491 59689 119491 59689 119492 63556 119492 63557 119492 59689 119493 63557 119493 59777 119493 63600 119494 59837 119494 59783 119494 59783 119495 59837 119495 59840 119495 59783 119496 59840 119496 63598 119496 63594 119497 63595 119497 59784 119497 63595 119498 63596 119498 59784 119498 59784 119499 63596 119499 59785 119499 59784 119500 59785 119500 59824 119500 63316 119501 59786 119501 59787 119501 59787 119502 59786 119502 59764 119502 59787 119503 59764 119503 59788 119503 59788 119504 59764 119504 59560 119504 59788 119505 59789 119505 59787 119505 59787 119506 59789 119506 59790 119506 59787 119507 59790 119507 59791 119507 59791 119508 63664 119508 59787 119508 59787 119509 63664 119509 59792 119509 59787 119510 59792 119510 63666 119510 59793 119511 59795 119511 59794 119511 59794 119512 59795 119512 59796 119512 59794 119513 59796 119513 59784 119513 59784 119514 59796 119514 59797 119514 59784 119515 59797 119515 63594 119515 59800 119516 64417 119516 59736 119516 59736 119517 64417 119517 64418 119517 59736 119518 64418 119518 59601 119518 59601 119519 64418 119519 64410 119519 59601 119520 64410 119520 59798 119520 59801 119521 64435 119521 59729 119521 59729 119522 64435 119522 64434 119522 59729 119523 64434 119523 59736 119523 59736 119524 64434 119524 59799 119524 59736 119525 59799 119525 59800 119525 62838 119526 62866 119526 59729 119526 59729 119527 62866 119527 59802 119527 59729 119528 59802 119528 59801 119528 59801 119529 59802 119529 64436 119529 59724 119530 59853 119530 59802 119530 59802 119531 59853 119531 59803 119531 59802 119532 59803 119532 64436 119532 59622 119533 64523 119533 59854 119533 59854 119534 64523 119534 64502 119534 59854 119535 64502 119535 59804 119535 59804 119536 64502 119536 64440 119536 59804 119537 64440 119537 59853 119537 59853 119538 64440 119538 64438 119538 59853 119539 64438 119539 59803 119539 59807 119540 59841 119540 59805 119540 59805 119541 59806 119541 59807 119541 59807 119542 59806 119542 59810 119542 59807 119543 59810 119543 64201 119543 64201 119544 59810 119544 59811 119544 59808 119545 59809 119545 59810 119545 59810 119546 59809 119546 59812 119546 59810 119547 59812 119547 59811 119547 59811 119548 59812 119548 59813 119548 59813 119549 59812 119549 64203 119549 64203 119550 59812 119550 59817 119550 64203 119551 59817 119551 64204 119551 59599 119552 64291 119552 59601 119552 59601 119553 64291 119553 59814 119553 59601 119554 59814 119554 59749 119554 59749 119555 59814 119555 59815 119555 59749 119556 59815 119556 64294 119556 64294 119557 59816 119557 59749 119557 59749 119558 59816 119558 64197 119558 59749 119559 64197 119559 59817 119559 59817 119560 64197 119560 64206 119560 59817 119561 64206 119561 64204 119561 63988 119562 63986 119562 59659 119562 59659 119563 63986 119563 63985 119563 59659 119564 63985 119564 59818 119564 59818 119565 63985 119565 63984 119565 59818 119566 63984 119566 63982 119566 63982 119567 63980 119567 59818 119567 59818 119568 63980 119568 64072 119568 59818 119569 64072 119569 59829 119569 59829 119570 64072 119570 59820 119570 59828 119571 64066 119571 59819 119571 59819 119572 64066 119572 59826 119572 59820 119573 59821 119573 59829 119573 59829 119574 59821 119574 64070 119574 59829 119575 64070 119575 59828 119575 59828 119576 64070 119576 64068 119576 59828 119577 64068 119577 64066 119577 59847 119578 59822 119578 63755 119578 59823 119579 63901 119579 59787 119579 59787 119580 63901 119580 63895 119580 59787 119581 63895 119581 63890 119581 63666 119582 59793 119582 59787 119582 59787 119583 59793 119583 59794 119583 59787 119584 59794 119584 59823 119584 59823 119585 59794 119585 63835 119585 63846 119586 63845 119586 59784 119586 59784 119587 63845 119587 63842 119587 59784 119588 63842 119588 59794 119588 59794 119589 63842 119589 63836 119589 59794 119590 63836 119590 63835 119590 59824 119591 63598 119591 59784 119591 59784 119592 63598 119592 59840 119592 59784 119593 59840 119593 63846 119593 63846 119594 59840 119594 59825 119594 59629 119595 59858 119595 59632 119595 59632 119596 59858 119596 59857 119596 59632 119597 59857 119597 59559 119597 59559 119598 59857 119598 59561 119598 59559 119599 59561 119599 59719 119599 59719 119600 59561 119600 59562 119600 59719 119601 59562 119601 62858 119601 62858 119602 59562 119602 62860 119602 59826 119603 59834 119603 59819 119603 59819 119604 59834 119604 59827 119604 59819 119605 59827 119605 59828 119605 59828 119606 59827 119606 59833 119606 59828 119607 59833 119607 59829 119607 59829 119608 59833 119608 59832 119608 59829 119609 59832 119609 59818 119609 59818 119610 59832 119610 59768 119610 59818 119611 59768 119611 59830 119611 59830 119612 59768 119612 63324 119612 63637 119613 63640 119613 59703 119613 59703 119614 63640 119614 59764 119614 59703 119615 59764 119615 59831 119615 59831 119616 59764 119616 59767 119616 59831 119617 59767 119617 59714 119617 59714 119618 59767 119618 59768 119618 59714 119619 59768 119619 59718 119619 59718 119620 59768 119620 59832 119620 59718 119621 59832 119621 59717 119621 59717 119622 59832 119622 59833 119622 59717 119623 59833 119623 59719 119623 59719 119624 59833 119624 59827 119624 59719 119625 59827 119625 59835 119625 59835 119626 59827 119626 59834 119626 59835 119627 59834 119627 59559 119627 59559 119628 59834 119628 59836 119628 59559 119629 59836 119629 64128 119629 63564 119630 59782 119630 59837 119630 59837 119631 59782 119631 59838 119631 59837 119632 59838 119632 59840 119632 59840 119633 59838 119633 59839 119633 59840 119634 59839 119634 59825 119634 59841 119635 64152 119635 59805 119635 59805 119636 64152 119636 59842 119636 59805 119637 59842 119637 59851 119637 59851 119638 59842 119638 59843 119638 59851 119639 59843 119639 59685 119639 59846 119640 59850 119640 59847 119640 59847 119641 59850 119641 59844 119641 59847 119642 59844 119642 59822 119642 62487 119643 59852 119643 59845 119643 59845 119644 59852 119644 59846 119644 59845 119645 59846 119645 59782 119645 59782 119646 59846 119646 59847 119646 59782 119647 59847 119647 59838 119647 59838 119648 59847 119648 63755 119648 59838 119649 63755 119649 59839 119649 59572 119650 60920 119650 59842 119650 59842 119651 60920 119651 59566 119651 59842 119652 59566 119652 59843 119652 59843 119653 59566 119653 59848 119653 59843 119654 59848 119654 59685 119654 59685 119655 59848 119655 61108 119655 59685 119656 61108 119656 59849 119656 60771 119657 60769 119657 59685 119657 59685 119658 60769 119658 59850 119658 59685 119659 59850 119659 59851 119659 59851 119660 59850 119660 59846 119660 59851 119661 59846 119661 59805 119661 59805 119662 59846 119662 59852 119662 59805 119663 59852 119663 59806 119663 59806 119664 59852 119664 59758 119664 59806 119665 59758 119665 59810 119665 59810 119666 59758 119666 62512 119666 59810 119667 62512 119667 59808 119667 59725 119668 62909 119668 59853 119668 59853 119669 62909 119669 59723 119669 59853 119670 59723 119670 59804 119670 59804 119671 59723 119671 59563 119671 59804 119672 59563 119672 59854 119672 59854 119673 59563 119673 59561 119673 59854 119674 59561 119674 59855 119674 59855 119675 59561 119675 59857 119675 59855 119676 59857 119676 59856 119676 59856 119677 59857 119677 59858 119677 59856 119678 59858 119678 59859 119678 59859 119679 59858 119679 59629 119679 59859 119680 59629 119680 59860 119680 59860 119681 59629 119681 59631 119681 63632 119682 59861 119682 59862 119682 59862 119683 59861 119683 59863 119683 59862 119684 59863 119684 59864 119684 59864 119685 59863 119685 59865 119685 59865 119686 59863 119686 63492 119686 59865 119687 63492 119687 59866 119687 59866 119688 63492 119688 59867 119688 59866 119689 59867 119689 59868 119689 59868 119690 59867 119690 63581 119690 63581 119691 59867 119691 63494 119691 63581 119692 63494 119692 59869 119692 59869 119693 63494 119693 59870 119693 59869 119694 59870 119694 63582 119694 63582 119695 59870 119695 59872 119695 63582 119696 59872 119696 59871 119696 59871 119697 59872 119697 63569 119697 63569 119698 59872 119698 63446 119698 63569 119699 63446 119699 63536 119699 63536 119700 63446 119700 59873 119700 59873 119701 63446 119701 63459 119701 59873 119702 63459 119702 63539 119702 63539 119703 63459 119703 59874 119703 63460 119704 59879 119704 63459 119704 63459 119705 59879 119705 59875 119705 63459 119706 59875 119706 59874 119706 59881 119707 59876 119707 59877 119707 59877 119708 59876 119708 63543 119708 59877 119709 63543 119709 63460 119709 63460 119710 63543 119710 59878 119710 63460 119711 59878 119711 59879 119711 59880 119712 59889 119712 63633 119712 63633 119713 59889 119713 59861 119713 63633 119714 59861 119714 63632 119714 59881 119715 59877 119715 59882 119715 59882 119716 59877 119716 63502 119716 59882 119717 63502 119717 63576 119717 63644 119718 59896 119718 59883 119718 59883 119719 59896 119719 59886 119719 59883 119720 59886 119720 59884 119720 59884 119721 59886 119721 59885 119721 59885 119722 59886 119722 59887 119722 59887 119723 59886 119723 63535 119723 59887 119724 63535 119724 63648 119724 59880 119725 59888 119725 59889 119725 59889 119726 59888 119726 63652 119726 59889 119727 63652 119727 63535 119727 63535 119728 63652 119728 63649 119728 63535 119729 63649 119729 63648 119729 63604 119730 63603 119730 63505 119730 63505 119731 63603 119731 59890 119731 63505 119732 59890 119732 63502 119732 63502 119733 59890 119733 59891 119733 63502 119734 59891 119734 63576 119734 59895 119735 63639 119735 59893 119735 59893 119736 63639 119736 63608 119736 63608 119737 59892 119737 59893 119737 59893 119738 59892 119738 59894 119738 59893 119739 59894 119739 63505 119739 63505 119740 59894 119740 63606 119740 63505 119741 63606 119741 63604 119741 63639 119742 59895 119742 63638 119742 63638 119743 59895 119743 59896 119743 63638 119744 59896 119744 63644 119744 63230 119745 59450 119745 63234 119745 63234 119746 59450 119746 62949 119746 59475 119747 59440 119747 62921 119747 59504 119748 59441 119748 59897 119748 62916 119749 59486 119749 59433 119749 62927 119750 59898 119750 59482 119750 62925 119751 59491 119751 59899 119751 62929 119752 59429 119752 62926 119752 62928 119753 59497 119753 59427 119753 62934 119754 59900 119754 59901 119754 59902 119755 59903 119755 59424 119755 59421 119756 59478 119756 59477 119756 62933 119757 59904 119757 59420 119757 59418 119758 59417 119758 62932 119758 59414 119759 59503 119759 59413 119759 59905 119760 62945 119760 59409 119760 59409 119761 62945 119761 59906 119761 59409 119762 59906 119762 62943 119762 62946 119763 59907 119763 62941 119763 62941 119764 59907 119764 59412 119764 62941 119765 59412 119765 59410 119765 59908 119766 62971 119766 59909 119766 59910 119767 59916 119767 59911 119767 59911 119768 59916 119768 62948 119768 59912 119769 59405 119769 59913 119769 59913 119770 59405 119770 59914 119770 59913 119771 59914 119771 59915 119771 59916 119772 59917 119772 62948 119772 62948 119773 59917 119773 59454 119773 59453 119774 59917 119774 59910 119774 59910 119775 59917 119775 59916 119775 59918 119776 62409 119776 60017 119776 60017 119777 62409 119777 59919 119777 60017 119778 59919 119778 60191 119778 60191 119779 59919 119779 59938 119779 60058 119780 62763 119780 59920 119780 59920 119781 62763 119781 62764 119781 59920 119782 62764 119782 59921 119782 59921 119783 62764 119783 62807 119783 62421 119784 59922 119784 62839 119784 62839 119785 59922 119785 59923 119785 62839 119786 59923 119786 59978 119786 59978 119787 59923 119787 60044 119787 59978 119788 60044 119788 60041 119788 59936 119789 60191 119789 59938 119789 59924 119790 59925 119790 59926 119790 59926 119791 59925 119791 59934 119791 59926 119792 59934 119792 59933 119792 62492 119793 59939 119793 62505 119793 62505 119794 59939 119794 59927 119794 62505 119795 59927 119795 62506 119795 62506 119796 59927 119796 59928 119796 62506 119797 59928 119797 59930 119797 59930 119798 59928 119798 59929 119798 59930 119799 59929 119799 59931 119799 59931 119800 59929 119800 60013 119800 59931 119801 60013 119801 62513 119801 62513 119802 60013 119802 60012 119802 62513 119803 60012 119803 59924 119803 59924 119804 60012 119804 59932 119804 59924 119805 59932 119805 59925 119805 59933 119806 59934 119806 59935 119806 59935 119807 59934 119807 60014 119807 59935 119808 60014 119808 59937 119808 59936 119809 59938 119809 59937 119809 59937 119810 59938 119810 62515 119810 59937 119811 62515 119811 59935 119811 59939 119812 62492 119812 60411 119812 60411 119813 62492 119813 62493 119813 60411 119814 62493 119814 59940 119814 59940 119815 62493 119815 59942 119815 59940 119816 59942 119816 59941 119816 59941 119817 59942 119817 59943 119817 59943 119818 59942 119818 62464 119818 59943 119819 62464 119819 59944 119819 59944 119820 62464 119820 59945 119820 59944 119821 59945 119821 59946 119821 59946 119822 59945 119822 59947 119822 59946 119823 59947 119823 59948 119823 59948 119824 59947 119824 59949 119824 59948 119825 59949 119825 60010 119825 60010 119826 59949 119826 62451 119826 60010 119827 62451 119827 59950 119827 59950 119828 62451 119828 62450 119828 59950 119829 62450 119829 59951 119829 59951 119830 62450 119830 62444 119830 59951 119831 62444 119831 60068 119831 60068 119832 62444 119832 62446 119832 60068 119833 62446 119833 59952 119833 59952 119834 62446 119834 62437 119834 59952 119835 62437 119835 62498 119835 59952 119836 62498 119836 60069 119836 60069 119837 62498 119837 62495 119837 60069 119838 62495 119838 62407 119838 62407 119839 62495 119839 62408 119839 59953 119840 59921 119840 62807 119840 59967 119841 59966 119841 59954 119841 59954 119842 59966 119842 59955 119842 59954 119843 59955 119843 59956 119843 59956 119844 59955 119844 60048 119844 59956 119845 60048 119845 62799 119845 62799 119846 60048 119846 59957 119846 62799 119847 59957 119847 62798 119847 62798 119848 59957 119848 59959 119848 62798 119849 59959 119849 59958 119849 59958 119850 59959 119850 59960 119850 59958 119851 59960 119851 59961 119851 59961 119852 59960 119852 60050 119852 59961 119853 60050 119853 59962 119853 59962 119854 60050 119854 60049 119854 59962 119855 60049 119855 62805 119855 62805 119856 60049 119856 60007 119856 62805 119857 60007 119857 59963 119857 59953 119858 62807 119858 59963 119858 59963 119859 62807 119859 59964 119859 59963 119860 59964 119860 62805 119860 59965 119861 59968 119861 62851 119861 62851 119862 59968 119862 60414 119862 62851 119863 60414 119863 62857 119863 62857 119864 60414 119864 59966 119864 62857 119865 59966 119865 59967 119865 59968 119866 59965 119866 59969 119866 59969 119867 59965 119867 59970 119867 59969 119868 59970 119868 59971 119868 59971 119869 59970 119869 59972 119869 59971 119870 59972 119870 59974 119870 59974 119871 59972 119871 59973 119871 59974 119872 59973 119872 60045 119872 60045 119873 59973 119873 59975 119873 60045 119874 59975 119874 60046 119874 60046 119875 59975 119875 62872 119875 60046 119876 62872 119876 59976 119876 59976 119877 62872 119877 62871 119877 59976 119878 62871 119878 60047 119878 60047 119879 62871 119879 59977 119879 60047 119880 59977 119880 60040 119880 60040 119881 59977 119881 62868 119881 60040 119882 62868 119882 60041 119882 60041 119883 62868 119883 62867 119883 60041 119884 62867 119884 59978 119884 59979 119885 62390 119885 62389 119885 62389 119886 59980 119886 59979 119886 59979 119887 59980 119887 60059 119887 59979 119888 60059 119888 62637 119888 62637 119889 60059 119889 60066 119889 62637 119890 60066 119890 59981 119890 59981 119891 60066 119891 59982 119891 62732 119892 62392 119892 62705 119892 62705 119893 62392 119893 60055 119893 62705 119894 60055 119894 62707 119894 60063 119895 59983 119895 60064 119895 60064 119896 59983 119896 59984 119896 60064 119897 59984 119897 59985 119897 59989 119898 62655 119898 62367 119898 60032 119899 62708 119899 59986 119899 59986 119900 62708 119900 59987 119900 59986 119901 59987 119901 59988 119901 59988 119902 59987 119902 59989 119902 59988 119903 59989 119903 59990 119903 59990 119904 59989 119904 62367 119904 62417 119905 59991 119905 59992 119905 59992 119906 59991 119906 59993 119906 59992 119907 59993 119907 59994 119907 62416 119908 62415 119908 59995 119908 59995 119909 62415 119909 59996 119909 59995 119910 59996 119910 59997 119910 59505 119911 62918 119911 59998 119911 60316 119912 62922 119912 60315 119912 62968 119913 60349 119913 59999 119913 61904 119914 60000 119914 60257 119914 60235 119915 60569 119915 60570 119915 60229 119916 62226 119916 60547 119916 61935 119917 61934 119917 60419 119917 60214 119918 60207 119918 60429 119918 64688 119919 60001 119919 60176 119919 62243 119920 60002 119920 62329 119920 60147 119921 60003 119921 60004 119921 60133 119922 62163 119922 60467 119922 60005 119923 62172 119923 60434 119923 60006 119924 62173 119924 62350 119924 60069 119925 59999 119925 60348 119925 59963 119926 60007 119926 60052 119926 62368 119927 60032 119927 60036 119927 59927 119928 59939 119928 60008 119928 59941 119929 59943 119929 60009 119929 60009 119930 59943 119930 59944 119930 60009 119931 59944 119931 59946 119931 59950 119932 60341 119932 60010 119932 60010 119933 60341 119933 60009 119933 60010 119934 60009 119934 59948 119934 59948 119935 60009 119935 59946 119935 60188 119936 59925 119936 60011 119936 60011 119937 59925 119937 59932 119937 60011 119938 59932 119938 60012 119938 60012 119939 60013 119939 60011 119939 60011 119940 60013 119940 59929 119940 60011 119941 59929 119941 59928 119941 59936 119942 59937 119942 60188 119942 59936 119943 60188 119943 60191 119943 59937 119944 60014 119944 60188 119944 60188 119945 60014 119945 59934 119945 60188 119946 59934 119946 59925 119946 62367 119947 60015 119947 60192 119947 60015 119948 60016 119948 60192 119948 60192 119949 60016 119949 62364 119949 60192 119950 62364 119950 60193 119950 59918 119951 60017 119951 59996 119951 59996 119952 60017 119952 62365 119952 59996 119953 62415 119953 60020 119953 60020 119954 62415 119954 60018 119954 60020 119955 60018 119955 60019 119955 60019 119956 62412 119956 60020 119956 60020 119957 62412 119957 60021 119957 60020 119958 60021 119958 59996 119958 59996 119959 60021 119959 62410 119959 59996 119960 62410 119960 59918 119960 60022 119961 62990 119961 60025 119961 62984 119962 60023 119962 60185 119962 60185 119963 60023 119963 60024 119963 60185 119964 60024 119964 60025 119964 60025 119965 60024 119965 62988 119965 60025 119966 62988 119966 60022 119966 62990 119967 62993 119967 60025 119967 60025 119968 62993 119968 62994 119968 60025 119969 62994 119969 60026 119969 62367 119970 60027 119970 62978 119970 62978 119971 60028 119971 62367 119971 62367 119972 60028 119972 62980 119972 62367 119973 62980 119973 59990 119973 59990 119974 62980 119974 63003 119974 59990 119975 63003 119975 59988 119975 59988 119976 63003 119976 60029 119976 59988 119977 60029 119977 59986 119977 59986 119978 60029 119978 60030 119978 59986 119979 60030 119979 60032 119979 60030 119980 60031 119980 60032 119980 60032 119981 60031 119981 60033 119981 60032 119982 60033 119982 60034 119982 60034 119983 63006 119983 60032 119983 60032 119984 63006 119984 60035 119984 60032 119985 60035 119985 60036 119985 60036 119986 60035 119986 62999 119986 62999 119987 62998 119987 60036 119987 60036 119988 62998 119988 62997 119988 60036 119989 62997 119989 62974 119989 62974 119990 60037 119990 60036 119990 60036 119991 60037 119991 62981 119991 60036 119992 62981 119992 60185 119992 60185 119993 62981 119993 62983 119993 60185 119994 62983 119994 62984 119994 60038 119995 62417 119995 60039 119995 60038 119996 60039 119996 62419 119996 62420 119997 62422 119997 60039 119997 60039 119998 62422 119998 62424 119998 60039 119999 62424 119999 62419 119999 62417 120000 59992 120000 60039 120000 60039 120001 59992 120001 59922 120001 60039 120002 59922 120002 62420 120002 62371 120003 62373 120003 60215 120003 60215 120004 62373 120004 62374 120004 59992 120005 62371 120005 59922 120005 59922 120006 62371 120006 60215 120006 59922 120007 60215 120007 59923 120007 59923 120008 60215 120008 60043 120008 60047 120009 60040 120009 60042 120009 60042 120010 60040 120010 60041 120010 60042 120011 60041 120011 60043 120011 60043 120012 60041 120012 60044 120012 60043 120013 60044 120013 59923 120013 59969 120014 59971 120014 60421 120014 60421 120015 59971 120015 59974 120015 59974 120016 60045 120016 60421 120016 60421 120017 60045 120017 60046 120017 60421 120018 60046 120018 60042 120018 60042 120019 60046 120019 59976 120019 60042 120020 59976 120020 60047 120020 60048 120021 59955 120021 60051 120021 60050 120022 59960 120022 60051 120022 60052 120023 60007 120023 60051 120023 60051 120024 60007 120024 60049 120024 60051 120025 60049 120025 60050 120025 59960 120026 59959 120026 60051 120026 60051 120027 59959 120027 59957 120027 60051 120028 59957 120028 60048 120028 59963 120029 60052 120029 59953 120029 59953 120030 60052 120030 60053 120030 59953 120031 60053 120031 59921 120031 59921 120032 60053 120032 60056 120032 59921 120033 60056 120033 59920 120033 60054 120034 60056 120034 62385 120034 62385 120035 60056 120035 60366 120035 62385 120036 60366 120036 62388 120036 62388 120037 60366 120037 62389 120037 60054 120038 62383 120038 60056 120038 60056 120039 62383 120039 62382 120039 60056 120040 62382 120040 60055 120040 60055 120041 62392 120041 60056 120041 60056 120042 62392 120042 62394 120042 60056 120043 62394 120043 62395 120043 62395 120044 62396 120044 60056 120044 60056 120045 62396 120045 62397 120045 60056 120046 62397 120046 62399 120046 62399 120047 60057 120047 60056 120047 60056 120048 60057 120048 60058 120048 60056 120049 60058 120049 59920 120049 62389 120050 60366 120050 59980 120050 59980 120051 60366 120051 60067 120051 59980 120052 60067 120052 60059 120052 60065 120053 62380 120053 59999 120053 60069 120054 62407 120054 60061 120054 62407 120055 62405 120055 60061 120055 60061 120056 62405 120056 62404 120056 60061 120057 62404 120057 60060 120057 60060 120058 60062 120058 60061 120058 60061 120059 60062 120059 60063 120059 60061 120060 60063 120060 60069 120060 60069 120061 60063 120061 60064 120061 60069 120062 60064 120062 59999 120062 59999 120063 60064 120063 62378 120063 59999 120064 62378 120064 60065 120064 60303 120065 62375 120065 60300 120065 60300 120066 62375 120066 59982 120066 60300 120067 59982 120067 60067 120067 60067 120068 59982 120068 60066 120068 60067 120069 60066 120069 60059 120069 59950 120070 59951 120070 60341 120070 60341 120071 59951 120071 60068 120071 60341 120072 60068 120072 60348 120072 60348 120073 60068 120073 59952 120073 60348 120074 59952 120074 60069 120074 63013 120075 60293 120075 63012 120075 63012 120076 60293 120076 60079 120076 63013 120077 63015 120077 60293 120077 60293 120078 63015 120078 63017 120078 60293 120079 63017 120079 63018 120079 63018 120080 63019 120080 60293 120080 60293 120081 63019 120081 60070 120081 60293 120082 60070 120082 60162 120082 60070 120083 63020 120083 60162 120083 60162 120084 63020 120084 63007 120084 60162 120085 63007 120085 60071 120085 60071 120086 60072 120086 60162 120086 60162 120087 60072 120087 60073 120087 60162 120088 60073 120088 60112 120088 60112 120089 60073 120089 63030 120089 63030 120090 63032 120090 60112 120090 60112 120091 63032 120091 63033 120091 60112 120092 63033 120092 60076 120092 63033 120093 63036 120093 60076 120093 60076 120094 63036 120094 60074 120094 60076 120095 60074 120095 63039 120095 63039 120096 60075 120096 60076 120096 60076 120097 60075 120097 63028 120097 60076 120098 63028 120098 60352 120098 63026 120099 63024 120099 60353 120099 60353 120100 63024 120100 63023 120100 60353 120101 63023 120101 60077 120101 60077 120102 63010 120102 60353 120102 60353 120103 63010 120103 60078 120103 60353 120104 60078 120104 60079 120104 60079 120105 60078 120105 60080 120105 60079 120106 60080 120106 63012 120106 60083 120107 60081 120107 60124 120107 60484 120108 60437 120108 60082 120108 60484 120109 60082 120109 61974 120109 60083 120110 60124 120110 61977 120110 60088 120111 61980 120111 64660 120111 64660 120112 61980 120112 60084 120112 64660 120113 60084 120113 60437 120113 60437 120114 60084 120114 60085 120114 60437 120115 60085 120115 60082 120115 60086 120116 61983 120116 60087 120116 60087 120117 61983 120117 60088 120117 60087 120118 60088 120118 64660 120118 60086 120119 62342 120119 61983 120119 61983 120120 62342 120120 60089 120120 60089 120121 62342 120121 60453 120121 60089 120122 60453 120122 60090 120122 60449 120123 60091 120123 64658 120123 62348 120124 62347 120124 60092 120124 60092 120125 62347 120125 60093 120125 60092 120126 60093 120126 64658 120126 64658 120127 60093 120127 62104 120127 64658 120128 62104 120128 60449 120128 60449 120129 62104 120129 60090 120129 60449 120130 60090 120130 60094 120130 60094 120131 60090 120131 60453 120131 62347 120132 62345 120132 60093 120132 60093 120133 62345 120133 60096 120133 60093 120134 60096 120134 60095 120134 60095 120135 60096 120135 60098 120135 60436 120136 60435 120136 64654 120136 62350 120137 62105 120137 60006 120137 60006 120138 62105 120138 60097 120138 60006 120139 60097 120139 64654 120139 64654 120140 60097 120140 60095 120140 64654 120141 60095 120141 60436 120141 60436 120142 60095 120142 60098 120142 60436 120143 60098 120143 60099 120143 60101 120144 60103 120144 60100 120144 60100 120145 62114 120145 60101 120145 60101 120146 62114 120146 62107 120146 60101 120147 62107 120147 62109 120147 62350 120148 62175 120148 62105 120148 62105 120149 62175 120149 62177 120149 62105 120150 62177 120150 62110 120150 62110 120151 62177 120151 60005 120151 62110 120152 60005 120152 62109 120152 62109 120153 60005 120153 60434 120153 62109 120154 60434 120154 60101 120154 60101 120155 60434 120155 62135 120155 62353 120156 60108 120156 60102 120156 60102 120157 60108 120157 60103 120157 60102 120158 60103 120158 64652 120158 64652 120159 60103 120159 60101 120159 60128 120160 60104 120160 60105 120160 60106 120161 60107 120161 60112 120161 60112 120162 60107 120162 62119 120162 60108 120163 62171 120163 60103 120163 60103 120164 62171 120164 60109 120164 60103 120165 60109 120165 62115 120165 62115 120166 60109 120166 60114 120166 62115 120167 60114 120167 60110 120167 60110 120168 60114 120168 60113 120168 60114 120169 60458 120169 60111 120169 64647 120170 60128 120170 60112 120170 62119 120171 60113 120171 60112 120171 60112 120172 60113 120172 60114 120172 60112 120173 60114 120173 64647 120173 64647 120174 60114 120174 60111 120174 64647 120175 60111 120175 60115 120175 62094 120176 60116 120176 60076 120176 60076 120177 60116 120177 60117 120177 60076 120178 60117 120178 60112 120178 60112 120179 60117 120179 62121 120179 60112 120180 62121 120180 60106 120180 60076 120181 60354 120181 62094 120181 62094 120182 60354 120182 60355 120182 62094 120183 60355 120183 60118 120183 60118 120184 60355 120184 62102 120184 62102 120185 60355 120185 60119 120185 62102 120186 60119 120186 62101 120186 62101 120187 60119 120187 62099 120187 62099 120188 60119 120188 60120 120188 62099 120189 60120 120189 62098 120189 62098 120190 60120 120190 60121 120190 62098 120191 60121 120191 62096 120191 62096 120192 60121 120192 60122 120192 62096 120193 60122 120193 60123 120193 60081 120194 61972 120194 60124 120194 60124 120195 61972 120195 61970 120195 60124 120196 61970 120196 60126 120196 60126 120197 61970 120197 60125 120197 60126 120198 60125 120198 61969 120198 61969 120199 61967 120199 60126 120199 60126 120200 61967 120200 61966 120200 60126 120201 61966 120201 60127 120201 64643 120202 62165 120202 62357 120202 60128 120203 60105 120203 60112 120203 60112 120204 60105 120204 62169 120204 60112 120205 62169 120205 60129 120205 64646 120206 62070 120206 60129 120206 60129 120207 62070 120207 62071 120207 60129 120208 62071 120208 62068 120208 62062 120209 60112 120209 62055 120209 62055 120210 60112 120210 60129 120210 62055 120211 60129 120211 62067 120211 62067 120212 60129 120212 62068 120212 64646 120213 60130 120213 60462 120213 60462 120214 62137 120214 60131 120214 64646 120215 60462 120215 62070 120215 62070 120216 60462 120216 60131 120216 62070 120217 60131 120217 64643 120217 64643 120218 62357 120218 62070 120218 62070 120219 62357 120219 62356 120219 62070 120220 62356 120220 60136 120220 62141 120221 60138 120221 60467 120221 60467 120222 60138 120222 60132 120222 60467 120223 60132 120223 60133 120223 60133 120224 60132 120224 60134 120224 60133 120225 60134 120225 60136 120225 60136 120226 60134 120226 60135 120226 60136 120227 60135 120227 62070 120227 60137 120228 60139 120228 62158 120228 62158 120229 60139 120229 62087 120229 62158 120230 62087 120230 60138 120230 60138 120231 62087 120231 62088 120231 60138 120232 62088 120232 60132 120232 60478 120233 62156 120233 60479 120233 60479 120234 62156 120234 60481 120234 60143 120235 62092 120235 60141 120235 60141 120236 62092 120236 62090 120236 60139 120237 62160 120237 62087 120237 62087 120238 62160 120238 62161 120238 62087 120239 62161 120239 60140 120239 60140 120240 62161 120240 62156 120240 60140 120241 62156 120241 62090 120241 62090 120242 62156 120242 60478 120242 62090 120243 60478 120243 60141 120243 60141 120244 60478 120244 62144 120244 62360 120245 62358 120245 60145 120245 60141 120246 64638 120246 60143 120246 60143 120247 64638 120247 60142 120247 60143 120248 60142 120248 60144 120248 60142 120249 62360 120249 60144 120249 60144 120250 62360 120250 60145 120250 60144 120251 60145 120251 60146 120251 60146 120252 60145 120252 60147 120252 60146 120253 60147 120253 62084 120253 62084 120254 60147 120254 60004 120254 62084 120255 60004 120255 62086 120255 62086 120256 60004 120256 60477 120256 62086 120257 60477 120257 60439 120257 64635 120258 61959 120258 60439 120258 60439 120259 61959 120259 61958 120259 60439 120260 61958 120260 62086 120260 64635 120261 60148 120261 61959 120261 61959 120262 60148 120262 60149 120262 61959 120263 60149 120263 61961 120263 61961 120264 60149 120264 60155 120264 61961 120265 60155 120265 60150 120265 60150 120266 60155 120266 60151 120266 61949 120267 60152 120267 60281 120267 60281 120268 60152 120268 61952 120268 60281 120269 61952 120269 60153 120269 60153 120270 60154 120270 60157 120270 60157 120271 60154 120271 60156 120271 60151 120272 60155 120272 61964 120272 61964 120273 60155 120273 60475 120273 61964 120274 60475 120274 60156 120274 60156 120275 60475 120275 60474 120275 60156 120276 60474 120276 60157 120276 60376 120277 60406 120277 60158 120277 60158 120278 60406 120278 60159 120278 60159 120279 61954 120279 60158 120279 60158 120280 61954 120280 60160 120280 60158 120281 60160 120281 60281 120281 60281 120282 60160 120282 61953 120282 60281 120283 61953 120283 61949 120283 62062 120284 60161 120284 60112 120284 60112 120285 60161 120285 62064 120285 60112 120286 62064 120286 60162 120286 60162 120287 62064 120287 60163 120287 60162 120288 60163 120288 60398 120288 62248 120289 64692 120289 60583 120289 60583 120290 64692 120290 62022 120290 60583 120291 62022 120291 60164 120291 64691 120292 60165 120292 64692 120292 64692 120293 60165 120293 62024 120293 64692 120294 62024 120294 62022 120294 64691 120295 62326 120295 60165 120295 60165 120296 62326 120296 62327 120296 60165 120297 62327 120297 60166 120297 62327 120298 60167 120298 60166 120298 60166 120299 60167 120299 64690 120299 60166 120300 64690 120300 60170 120300 60170 120301 64690 120301 60168 120301 60170 120302 60168 120302 60587 120302 60587 120303 60168 120303 60169 120303 60171 120304 60589 120304 60172 120304 60587 120305 60171 120305 60170 120305 60170 120306 60171 120306 60172 120306 60170 120307 60172 120307 62025 120307 62025 120308 60172 120308 62243 120308 62025 120309 62243 120309 62026 120309 62026 120310 62243 120310 62329 120310 64685 120311 60181 120311 60173 120311 60173 120312 62030 120312 64685 120312 64685 120313 62030 120313 60174 120313 64685 120314 60174 120314 62027 120314 62329 120315 62242 120315 62026 120315 62026 120316 62242 120316 60175 120316 62026 120317 60175 120317 62028 120317 62028 120318 60175 120318 64688 120318 62028 120319 64688 120319 62027 120319 62027 120320 64688 120320 60176 120320 62027 120321 60176 120321 64685 120321 64685 120322 60176 120322 60177 120322 62236 120323 62331 120323 60178 120323 60178 120324 62331 120324 60181 120324 60178 120325 60181 120325 60179 120325 60179 120326 60181 120326 64685 120326 60180 120327 62039 120327 60185 120327 60185 120328 62039 120328 62038 120328 62038 120329 62033 120329 60185 120329 60185 120330 62033 120330 62034 120330 60185 120331 62034 120331 64684 120331 62331 120332 60182 120332 60181 120332 60181 120333 60182 120333 62235 120333 60181 120334 62235 120334 62031 120334 62031 120335 62235 120335 64684 120335 62031 120336 64684 120336 60183 120336 60183 120337 64684 120337 62034 120337 64680 120338 62333 120338 62334 120338 64684 120339 60184 120339 60565 120339 60565 120340 62233 120340 64681 120340 64684 120341 60565 120341 60185 120341 60185 120342 60565 120342 64681 120342 60185 120343 64681 120343 64680 120343 60186 120344 62047 120344 60025 120344 60025 120345 62047 120345 62046 120345 60025 120346 62046 120346 60185 120346 60185 120347 62046 120347 62043 120347 60185 120348 62043 120348 60180 120348 60189 120349 62050 120349 60190 120349 60190 120350 62050 120350 60186 120350 60190 120351 60186 120351 60192 120351 60192 120352 60186 120352 60025 120352 60192 120353 60025 120353 62367 120353 62367 120354 60025 120354 60026 120354 62367 120355 60026 120355 60027 120355 60187 120356 60189 120356 60188 120356 60188 120357 60189 120357 60190 120357 60188 120358 60190 120358 60191 120358 60191 120359 60190 120359 60192 120359 60191 120360 60192 120360 60017 120360 60017 120361 60192 120361 60193 120361 60017 120362 60193 120362 62365 120362 60187 120363 60188 120363 62051 120363 62051 120364 60188 120364 60011 120364 62051 120365 60011 120365 60194 120365 60194 120366 60011 120366 60383 120366 60194 120367 60383 120367 60195 120367 60195 120368 60383 120368 60196 120368 60195 120369 60196 120369 60197 120369 60388 120370 61943 120370 61942 120370 60388 120371 61942 120371 60386 120371 62254 120372 60198 120372 61936 120372 60266 120373 60200 120373 60201 120373 60582 120374 62254 120374 61936 120374 60582 120375 61936 120375 60267 120375 60267 120376 61936 120376 60199 120376 60267 120377 60199 120377 60266 120377 60200 120378 61944 120378 60201 120378 60201 120379 61944 120379 61945 120379 60201 120380 61945 120380 60388 120380 60388 120381 61945 120381 61946 120381 60388 120382 61946 120382 61943 120382 62362 120383 60202 120383 64695 120383 64695 120384 60202 120384 60203 120384 64695 120385 60203 120385 62254 120385 62254 120386 60203 120386 61938 120386 62254 120387 61938 120387 60198 120387 60204 120388 60164 120388 62022 120388 60204 120389 62022 120389 64694 120389 64694 120390 62022 120390 62021 120390 64694 120391 62021 120391 60205 120391 64694 120392 60205 120392 60206 120392 60206 120393 60205 120393 60202 120393 60206 120394 60202 120394 62362 120394 60429 120395 60207 120395 60426 120395 60426 120396 60207 120396 60208 120396 60426 120397 60208 120397 60210 120397 61918 120398 60209 120398 60657 120398 60210 120399 60211 120399 60426 120399 60426 120400 60211 120400 61930 120400 60426 120401 61930 120401 61929 120401 60209 120402 61927 120402 60657 120402 60657 120403 61927 120403 60212 120403 60657 120404 60212 120404 60656 120404 60656 120405 60212 120405 61925 120405 60656 120406 61925 120406 60213 120406 60419 120407 61934 120407 60429 120407 60429 120408 61934 120408 61933 120408 60429 120409 61933 120409 60214 120409 62017 120410 62014 120410 60036 120410 62014 120411 62012 120411 60036 120411 60036 120412 62012 120412 60215 120412 60036 120413 60215 120413 62368 120413 62368 120414 60215 120414 62374 120414 60218 120415 60216 120415 60228 120415 60222 120416 62231 120416 60223 120416 64680 120417 62334 120417 60185 120417 60185 120418 62334 120418 60217 120418 60185 120419 60217 120419 60225 120419 60218 120420 60219 120420 60220 120420 60220 120421 60219 120421 60221 120421 61992 120422 60225 120422 60221 120422 60221 120423 60225 120423 60222 120423 60221 120424 60222 120424 60220 120424 60220 120425 60222 120425 60223 120425 60220 120426 60223 120426 60548 120426 62007 120427 60185 120427 60224 120427 60224 120428 60185 120428 60225 120428 60224 120429 60225 120429 60226 120429 60226 120430 60225 120430 61992 120430 62007 120431 62019 120431 60185 120431 60185 120432 62019 120432 60227 120432 60185 120433 60227 120433 60036 120433 60036 120434 60227 120434 62015 120434 60036 120435 62015 120435 62017 120435 61993 120436 60219 120436 64679 120436 60218 120437 60228 120437 60219 120437 60219 120438 60228 120438 62228 120438 60219 120439 62228 120439 64679 120439 62219 120440 60232 120440 60547 120440 60547 120441 60232 120441 60233 120441 60547 120442 60233 120442 60229 120442 60229 120443 60233 120443 60230 120443 60229 120444 60230 120444 64679 120444 64679 120445 60230 120445 61995 120445 64679 120446 61995 120446 61993 120446 62224 120447 62339 120447 60231 120447 60231 120448 62339 120448 62006 120448 60231 120449 62006 120449 60232 120449 60232 120450 62006 120450 62005 120450 60232 120451 62005 120451 60233 120451 62339 120452 60234 120452 62006 120452 62006 120453 60234 120453 62222 120453 62006 120454 62222 120454 62003 120454 62003 120455 62222 120455 60235 120455 62003 120456 60235 120456 60237 120456 60237 120457 60235 120457 60570 120457 60237 120458 60570 120458 64676 120458 64676 120459 60570 120459 62212 120459 62215 120460 60238 120460 62214 120460 62214 120461 60238 120461 62001 120461 62214 120462 62001 120462 64676 120462 64676 120463 62001 120463 60236 120463 64676 120464 60236 120464 60237 120464 60238 120465 60239 120465 62001 120465 62001 120466 60239 120466 62213 120466 62001 120467 62213 120467 60240 120467 60240 120468 62213 120468 60243 120468 60241 120469 62207 120469 60240 120469 60241 120470 60240 120470 60242 120470 60242 120471 60240 120471 60243 120471 60242 120472 60243 120472 60574 120472 60244 120473 61921 120473 62207 120473 62207 120474 61921 120474 61998 120474 62207 120475 61998 120475 60240 120475 60244 120476 62208 120476 61921 120476 61921 120477 62208 120477 60246 120477 61921 120478 60246 120478 60245 120478 60245 120479 60246 120479 60213 120479 60245 120480 60213 120480 61922 120480 61922 120481 60213 120481 60247 120481 60247 120482 60213 120482 61925 120482 60257 120483 60000 120483 60359 120483 60000 120484 61893 120484 60359 120484 60359 120485 61893 120485 60248 120485 60359 120486 60248 120486 60252 120486 61974 120487 61977 120487 60484 120487 60484 120488 61977 120488 60124 120488 60484 120489 60124 120489 60249 120489 60249 120490 60124 120490 60360 120490 60249 120491 60360 120491 60250 120491 60250 120492 60360 120492 60359 120492 60250 120493 60359 120493 60251 120493 60251 120494 60359 120494 60252 120494 60251 120495 60252 120495 61877 120495 61877 120496 60253 120496 60251 120496 60251 120497 60253 120497 60254 120497 60251 120498 60254 120498 60446 120498 61914 120499 60255 120499 61915 120499 61915 120500 60255 120500 61909 120500 60256 120501 61902 120501 60257 120501 60257 120502 61902 120502 61909 120502 60257 120503 61909 120503 61904 120503 61904 120504 61909 120504 60255 120504 60258 120505 61847 120505 60424 120505 60424 120506 61847 120506 61874 120506 61874 120507 60259 120507 60424 120507 60424 120508 60259 120508 60260 120508 60424 120509 60260 120509 60261 120509 60261 120510 60260 120510 61885 120510 61797 120511 61826 120511 60262 120511 60262 120512 61826 120512 61835 120512 60262 120513 61835 120513 61833 120513 60258 120514 60424 120514 60263 120514 60263 120515 60424 120515 60264 120515 60263 120516 60264 120516 61833 120516 61833 120517 60264 120517 60262 120517 60262 120518 60264 120518 60265 120518 60262 120519 60265 120519 60660 120519 60660 120520 60265 120520 60659 120520 60659 120521 60265 120521 60426 120521 60659 120522 60426 120522 60657 120522 60657 120523 60426 120523 61929 120523 60657 120524 61929 120524 61918 120524 61576 120525 61578 120525 60270 120525 60266 120526 60201 120526 60267 120526 60267 120527 60201 120527 60268 120527 60267 120528 60268 120528 60579 120528 60579 120529 60268 120529 60391 120529 60579 120530 60391 120530 60269 120530 60269 120531 60391 120531 60271 120531 60269 120532 60271 120532 60270 120532 60270 120533 60271 120533 61574 120533 60270 120534 61574 120534 61576 120534 61549 120535 60272 120535 60392 120535 60392 120536 60272 120536 61564 120536 60392 120537 61564 120537 60391 120537 60391 120538 61564 120538 61558 120538 60391 120539 61558 120539 60271 120539 60273 120540 61548 120540 61537 120540 61537 120541 61548 120541 61554 120541 61548 120542 61549 120542 61554 120542 61554 120543 61549 120543 60392 120543 61554 120544 60392 120544 61553 120544 60394 120545 61604 120545 60274 120545 60274 120546 61585 120546 60394 120546 60394 120547 61585 120547 61565 120547 60394 120548 61565 120548 60396 120548 60438 120549 60275 120549 60276 120549 60276 120550 60275 120550 60278 120550 60276 120551 60278 120551 60277 120551 60277 120552 60278 120552 60284 120552 61604 120553 60394 120553 60279 120553 60279 120554 60394 120554 60372 120554 60279 120555 60372 120555 60280 120555 60153 120556 60157 120556 60281 120556 60281 120557 60157 120557 60282 120557 60281 120558 60282 120558 60283 120558 60283 120559 60282 120559 60277 120559 60283 120560 60277 120560 60372 120560 60372 120561 60277 120561 60284 120561 60372 120562 60284 120562 60280 120562 60293 120563 60285 120563 60286 120563 60286 120564 64697 120564 60293 120564 60293 120565 64697 120565 60288 120565 60287 120566 63177 120566 59519 120566 59519 120567 63177 120567 63165 120567 60294 120568 60293 120568 60287 120568 60287 120569 60293 120569 60288 120569 60287 120570 60288 120570 63177 120570 63177 120571 60288 120571 59517 120571 63177 120572 59517 120572 63184 120572 64698 120573 60295 120573 60289 120573 60289 120574 60295 120574 63131 120574 63118 120575 60290 120575 59522 120575 59522 120576 60290 120576 59523 120576 60291 120577 60368 120577 60293 120577 60292 120578 63101 120578 60290 120578 60290 120579 63101 120579 60291 120579 60290 120580 60291 120580 59523 120580 59523 120581 60291 120581 60293 120581 59523 120582 60293 120582 64698 120582 64698 120583 60293 120583 60294 120583 64698 120584 60294 120584 60295 120584 60295 120585 60294 120585 63151 120585 60295 120586 63151 120586 63145 120586 60367 120587 63082 120587 63068 120587 63068 120588 63082 120588 63079 120588 60367 120589 60296 120589 60300 120589 60297 120590 60301 120590 60300 120590 60297 120591 60300 120591 60298 120591 60298 120592 60300 120592 60296 120592 60298 120593 60296 120593 59525 120593 60304 120594 60300 120594 60299 120594 60299 120595 60300 120595 60301 120595 60299 120596 60301 120596 60302 120596 62380 120597 60303 120597 59999 120597 59999 120598 60303 120598 60300 120598 59999 120599 60300 120599 60305 120599 60305 120600 60300 120600 60304 120600 60305 120601 62970 120601 62969 120601 60305 120602 62969 120602 59999 120602 59999 120603 62969 120603 60306 120603 59999 120604 60306 120604 62968 120604 59539 120605 60307 120605 60162 120605 60162 120606 60307 120606 59554 120606 60162 120607 59554 120607 60293 120607 60293 120608 59554 120608 59546 120608 60293 120609 59546 120609 60285 120609 60285 120610 59546 120610 59545 120610 60307 120611 59515 120611 63237 120611 63237 120612 60308 120612 60307 120612 60307 120613 60308 120613 60309 120613 60307 120614 60309 120614 59554 120614 59554 120615 60309 120615 63229 120615 59554 120616 63229 120616 60310 120616 60314 120617 60311 120617 60400 120617 60400 120618 60311 120618 59509 120618 60400 120619 59509 120619 60312 120619 59540 120620 59539 120620 64702 120620 64702 120621 59539 120621 60162 120621 64702 120622 60162 120622 59514 120622 59514 120623 60162 120623 60400 120623 59514 120624 60400 120624 60313 120624 60313 120625 60400 120625 60312 120625 62972 120626 60311 120626 60315 120626 60315 120627 60311 120627 60314 120627 60315 120628 60314 120628 60316 120628 60316 120629 60314 120629 60317 120629 60316 120630 60317 120630 60324 120630 60339 120631 59493 120631 60319 120631 60319 120632 59493 120632 59495 120632 60319 120633 59495 120633 60318 120633 60320 120634 59489 120634 59487 120634 59490 120635 59484 120635 60318 120635 60318 120636 59484 120636 64663 120636 60318 120637 64663 120637 60319 120637 60319 120638 64663 120638 60320 120638 60319 120639 60320 120639 60321 120639 60321 120640 60320 120640 59487 120640 64662 120641 64626 120641 60381 120641 60381 120642 64626 120642 60322 120642 60381 120643 60322 120643 60323 120643 60323 120644 62917 120644 60381 120644 60381 120645 62917 120645 62918 120645 60381 120646 62918 120646 60317 120646 60317 120647 62918 120647 59505 120647 60317 120648 59505 120648 60324 120648 62944 120649 62945 120649 59905 120649 60009 120650 59529 120650 64633 120650 60325 120651 59476 120651 60326 120651 60379 120652 59907 120652 60329 120652 60329 120653 59907 120653 62946 120653 59532 120654 60327 120654 60319 120654 60330 120655 64667 120655 60319 120655 60328 120656 59501 120656 60319 120656 59537 120657 60328 120657 64671 120657 64671 120658 60328 120658 60319 120658 64671 120659 60319 120659 60326 120659 60326 120660 60319 120660 60379 120660 60326 120661 60379 120661 60325 120661 60325 120662 60379 120662 60329 120662 62930 120663 62931 120663 59501 120663 59501 120664 62931 120664 64669 120664 59501 120665 64669 120665 60319 120665 60319 120666 64669 120666 64668 120666 60319 120667 64668 120667 60330 120667 60330 120668 64668 120668 59534 120668 59500 120669 60331 120669 64667 120669 64667 120670 60331 120670 59479 120670 64667 120671 59479 120671 60319 120671 60319 120672 59479 120672 59533 120672 60319 120673 59533 120673 59532 120673 59532 120674 59533 120674 60332 120674 60334 120675 59496 120675 60319 120675 59530 120676 60334 120676 60333 120676 60333 120677 60334 120677 60319 120677 60333 120678 60319 120678 59481 120678 59481 120679 60319 120679 60327 120679 59481 120680 60327 120680 60335 120680 60335 120681 60327 120681 60336 120681 62924 120682 59483 120682 59496 120682 59496 120683 59483 120683 60337 120683 59496 120684 60337 120684 60319 120684 60319 120685 60337 120685 60338 120685 60319 120686 60338 120686 60339 120686 60340 120687 60341 120687 60342 120687 60342 120688 60341 120688 60348 120688 60342 120689 60348 120689 60343 120689 60343 120690 60348 120690 60347 120690 59905 120691 59529 120691 62944 120691 62944 120692 59529 120692 60009 120692 62944 120693 60009 120693 60344 120693 60344 120694 60009 120694 60341 120694 60344 120695 60341 120695 62938 120695 62938 120696 60341 120696 60340 120696 62938 120697 60340 120697 59507 120697 60345 120698 59512 120698 64629 120698 60346 120699 60347 120699 59513 120699 59513 120700 60347 120700 60348 120700 59513 120701 60348 120701 64629 120701 64629 120702 60348 120702 59999 120702 64629 120703 59999 120703 60345 120703 60345 120704 59999 120704 60349 120704 59955 120705 59966 120705 60051 120705 60051 120706 59966 120706 60433 120706 60051 120707 60433 120707 60350 120707 60350 120708 60433 120708 60432 120708 60350 120709 60432 120709 60351 120709 60351 120710 60432 120710 60431 120710 60351 120711 60431 120711 60362 120711 60352 120712 63026 120712 60076 120712 60076 120713 63026 120713 60353 120713 60076 120714 60353 120714 60354 120714 60354 120715 60353 120715 60365 120715 60354 120716 60365 120716 60355 120716 60355 120717 60365 120717 60364 120717 60355 120718 60364 120718 60119 120718 60119 120719 60364 120719 60356 120719 60119 120720 60356 120720 60120 120720 60120 120721 60356 120721 60357 120721 60120 120722 60357 120722 60121 120722 60121 120723 60357 120723 60358 120723 60121 120724 60358 120724 60122 120724 60122 120725 60358 120725 60363 120725 60122 120726 60363 120726 60123 120726 60123 120727 60363 120727 60127 120727 60123 120728 60127 120728 61965 120728 61965 120729 60127 120729 61966 120729 60256 120730 60257 120730 60425 120730 60425 120731 60257 120731 60359 120731 60425 120732 60359 120732 60427 120732 60427 120733 60359 120733 60360 120733 60427 120734 60360 120734 60428 120734 60428 120735 60360 120735 60124 120735 60428 120736 60124 120736 60361 120736 60361 120737 60124 120737 60126 120737 60361 120738 60126 120738 60362 120738 60362 120739 60126 120739 60127 120739 60362 120740 60127 120740 60351 120740 60351 120741 60127 120741 60363 120741 60351 120742 60363 120742 60350 120742 60350 120743 60363 120743 60358 120743 60350 120744 60358 120744 60051 120744 60051 120745 60358 120745 60357 120745 60051 120746 60357 120746 60052 120746 60052 120747 60357 120747 60356 120747 60052 120748 60356 120748 60053 120748 60053 120749 60356 120749 60364 120749 60053 120750 60364 120750 60056 120750 60056 120751 60364 120751 60365 120751 60056 120752 60365 120752 60366 120752 60366 120753 60365 120753 60353 120753 60366 120754 60353 120754 60067 120754 60067 120755 60353 120755 60079 120755 60067 120756 60079 120756 60300 120756 60300 120757 60079 120757 60293 120757 60300 120758 60293 120758 60367 120758 60367 120759 60293 120759 60368 120759 60367 120760 60368 120760 63082 120760 63082 120761 60368 120761 63089 120761 63082 120762 63089 120762 60369 120762 60370 120763 60408 120763 60378 120763 60378 120764 60408 120764 60371 120764 60378 120765 60371 120765 60009 120765 60009 120766 60371 120766 60410 120766 60009 120767 60410 120767 59941 120767 59941 120768 60410 120768 59940 120768 60394 120769 60393 120769 60372 120769 60372 120770 60393 120770 60373 120770 60372 120771 60373 120771 60283 120771 60283 120772 60373 120772 60390 120772 60283 120773 60390 120773 60281 120773 60281 120774 60390 120774 60374 120774 60281 120775 60374 120775 60158 120775 60158 120776 60374 120776 60375 120776 60158 120777 60375 120777 60376 120777 60376 120778 60375 120778 60389 120778 60407 120779 60370 120779 60377 120779 60377 120780 60370 120780 60378 120780 60377 120781 60378 120781 60319 120781 60319 120782 60378 120782 60009 120782 60319 120783 60009 120783 60379 120783 60379 120784 60009 120784 64633 120784 60405 120785 60407 120785 60380 120785 60380 120786 60407 120786 60377 120786 60380 120787 60377 120787 60381 120787 60381 120788 60377 120788 60319 120788 60381 120789 60319 120789 64662 120789 64662 120790 60319 120790 60321 120790 61942 120791 61941 120791 60386 120791 60386 120792 61941 120792 60197 120792 60386 120793 60197 120793 60382 120793 60382 120794 60197 120794 60196 120794 60382 120795 60196 120795 60385 120795 60385 120796 60196 120796 60383 120796 60385 120797 60383 120797 60008 120797 60008 120798 60383 120798 60011 120798 60008 120799 60011 120799 59927 120799 59927 120800 60011 120800 59928 120800 59939 120801 60411 120801 60008 120801 60008 120802 60411 120802 60384 120802 60008 120803 60384 120803 60385 120803 60385 120804 60384 120804 60409 120804 60385 120805 60409 120805 60382 120805 60382 120806 60409 120806 60387 120806 60382 120807 60387 120807 60386 120807 60386 120808 60387 120808 60389 120808 60386 120809 60389 120809 60388 120809 60388 120810 60389 120810 60375 120810 60388 120811 60375 120811 60201 120811 60201 120812 60375 120812 60374 120812 60201 120813 60374 120813 60268 120813 60268 120814 60374 120814 60390 120814 60268 120815 60390 120815 60391 120815 60391 120816 60390 120816 60373 120816 60391 120817 60373 120817 60392 120817 60392 120818 60373 120818 60393 120818 60392 120819 60393 120819 61553 120819 61553 120820 60393 120820 60394 120820 61553 120821 60394 120821 60395 120821 60395 120822 60394 120822 60396 120822 60395 120823 60396 120823 60397 120823 60398 120824 60399 120824 60162 120824 60162 120825 60399 120825 60401 120825 60162 120826 60401 120826 60400 120826 60400 120827 60401 120827 62076 120827 60400 120828 62076 120828 60314 120828 60314 120829 62076 120829 60402 120829 60314 120830 60402 120830 60317 120830 60317 120831 60402 120831 60403 120831 60317 120832 60403 120832 60381 120832 60381 120833 60403 120833 62080 120833 60381 120834 62080 120834 60380 120834 60380 120835 62080 120835 60404 120835 60380 120836 60404 120836 60405 120836 60405 120837 60404 120837 60406 120837 60405 120838 60406 120838 60407 120838 60407 120839 60406 120839 60376 120839 60407 120840 60376 120840 60370 120840 60370 120841 60376 120841 60389 120841 60370 120842 60389 120842 60408 120842 60408 120843 60389 120843 60387 120843 60408 120844 60387 120844 60371 120844 60371 120845 60387 120845 60409 120845 60371 120846 60409 120846 60410 120846 60410 120847 60409 120847 60384 120847 60410 120848 60384 120848 59940 120848 59940 120849 60384 120849 60411 120849 59968 120850 59969 120850 60416 120850 60416 120851 59969 120851 60421 120851 60416 120852 60421 120852 60412 120852 60412 120853 60421 120853 60420 120853 60412 120854 60420 120854 60413 120854 60413 120855 60420 120855 60418 120855 60414 120856 59968 120856 60415 120856 60415 120857 59968 120857 60416 120857 60415 120858 60416 120858 60417 120858 60417 120859 60416 120859 60412 120859 60417 120860 60412 120860 60430 120860 60430 120861 60412 120861 60413 120861 60430 120862 60413 120862 60419 120862 60419 120863 60413 120863 60418 120863 60419 120864 60418 120864 61935 120864 61935 120865 60418 120865 60420 120865 61935 120866 60420 120866 61988 120866 61988 120867 60420 120867 60421 120867 61988 120868 60421 120868 60422 120868 60422 120869 60421 120869 60042 120869 60422 120870 60042 120870 61986 120870 61986 120871 60042 120871 60043 120871 61986 120872 60043 120872 61984 120872 61984 120873 60043 120873 60215 120873 61984 120874 60215 120874 60423 120874 60423 120875 60215 120875 62012 120875 60261 120876 61902 120876 60424 120876 60424 120877 61902 120877 60256 120877 60424 120878 60256 120878 60264 120878 60264 120879 60256 120879 60425 120879 60264 120880 60425 120880 60265 120880 60265 120881 60425 120881 60427 120881 60265 120882 60427 120882 60426 120882 60426 120883 60427 120883 60428 120883 60426 120884 60428 120884 60429 120884 60429 120885 60428 120885 60361 120885 60429 120886 60361 120886 60419 120886 60419 120887 60361 120887 60362 120887 60419 120888 60362 120888 60430 120888 60430 120889 60362 120889 60431 120889 60430 120890 60431 120890 60417 120890 60417 120891 60431 120891 60432 120891 60417 120892 60432 120892 60415 120892 60415 120893 60432 120893 60433 120893 60415 120894 60433 120894 60414 120894 60414 120895 60433 120895 59966 120895 62139 120896 62141 120896 60467 120896 60463 120897 62137 120897 60462 120897 62196 120898 62135 120898 60434 120898 60454 120899 60435 120899 60436 120899 62130 120900 60437 120900 60484 120900 61632 120901 60438 120901 60276 120901 62147 120902 60439 120902 60477 120902 62148 120903 62149 120903 60512 120903 60512 120904 62149 120904 62186 120904 60512 120905 62186 120905 60440 120905 60440 120906 62186 120906 62185 120906 60440 120907 62185 120907 60476 120907 60476 120908 62185 120908 62147 120908 60518 120909 61636 120909 60516 120909 60516 120910 61636 120910 60441 120910 60516 120911 60441 120911 61632 120911 60442 120912 60721 120912 61707 120912 60444 120913 61838 120913 60443 120913 61855 120914 61854 120914 60444 120914 60444 120915 61854 120915 60445 120915 60444 120916 60445 120916 61838 120916 60251 120917 60446 120917 61858 120917 62130 120918 60483 120918 62203 120918 62203 120919 60483 120919 60447 120919 62203 120920 60447 120920 60491 120920 60453 120921 62182 120921 60448 120921 60448 120922 62182 120922 62181 120922 60448 120923 62181 120923 60491 120923 60491 120924 62181 120924 62205 120924 60491 120925 62205 120925 62203 120925 60091 120926 60449 120926 62131 120926 62131 120927 60449 120927 60452 120927 60436 120928 60099 120928 60493 120928 60493 120929 60099 120929 60450 120929 60493 120930 60450 120930 60451 120930 60451 120931 60450 120931 60452 120931 60451 120932 60452 120932 60492 120932 60492 120933 60452 120933 60449 120933 60492 120934 60449 120934 60448 120934 60448 120935 60449 120935 60094 120935 60448 120936 60094 120936 60453 120936 60436 120937 60493 120937 60454 120937 60454 120938 60493 120938 60456 120938 60454 120939 60456 120939 60455 120939 60455 120940 60456 120940 60495 120940 60455 120941 60495 120941 62172 120941 60111 120942 60458 120942 60457 120942 60457 120943 60458 120943 60459 120943 60457 120944 60459 120944 60497 120944 60497 120945 60459 120945 62196 120945 60497 120946 62196 120946 60495 120946 60495 120947 62196 120947 60434 120947 60495 120948 60434 120948 62172 120948 60115 120949 60111 120949 60460 120949 60460 120950 60111 120950 60457 120950 60460 120951 60457 120951 60461 120951 60461 120952 60457 120952 60500 120952 60461 120953 60500 120953 60130 120953 60130 120954 60500 120954 60462 120954 60462 120955 60500 120955 60463 120955 60463 120956 60500 120956 60464 120956 60463 120957 60464 120957 60466 120957 60466 120958 60464 120958 60465 120958 60466 120959 60465 120959 62163 120959 60480 120960 60482 120960 60502 120960 60502 120961 60482 120961 62139 120961 60502 120962 62139 120962 60465 120962 60465 120963 62139 120963 60467 120963 60465 120964 60467 120964 62163 120964 62144 120965 60505 120965 60468 120965 60468 120966 60505 120966 60469 120966 60468 120967 60469 120967 60508 120967 60509 120968 60470 120968 60508 120968 60508 120969 60470 120969 60471 120969 60508 120970 60471 120970 60468 120970 61632 120971 60276 120971 60516 120971 60516 120972 60276 120972 60277 120972 60516 120973 60277 120973 60515 120973 60515 120974 60277 120974 60282 120974 60515 120975 60282 120975 60472 120975 60472 120976 60282 120976 60157 120976 60472 120977 60157 120977 60473 120977 60473 120978 60157 120978 60474 120978 60473 120979 60474 120979 60512 120979 60512 120980 60474 120980 60475 120980 60512 120981 60475 120981 62148 120981 62147 120982 60477 120982 60476 120982 60476 120983 60477 120983 60004 120983 60476 120984 60004 120984 60509 120984 60509 120985 60004 120985 60003 120985 60509 120986 60003 120986 60470 120986 62144 120987 60478 120987 60505 120987 60505 120988 60478 120988 60479 120988 60505 120989 60479 120989 60480 120989 60480 120990 60479 120990 60481 120990 60480 120991 60481 120991 60482 120991 62130 120992 60484 120992 60483 120992 60483 120993 60484 120993 60249 120993 60483 120994 60249 120994 60485 120994 60485 120995 60249 120995 60250 120995 60485 120996 60250 120996 60488 120996 60488 120997 60250 120997 60251 120997 60488 120998 60251 120998 60486 120998 60486 120999 60251 120999 61858 120999 60486 121000 61858 121000 60487 121000 60487 121001 61855 121001 60486 121001 60486 121002 61855 121002 60444 121002 60486 121003 60444 121003 60488 121003 60488 121004 60444 121004 60543 121004 60488 121005 60543 121005 60485 121005 60485 121006 60543 121006 60489 121006 60485 121007 60489 121007 60483 121007 60483 121008 60489 121008 60540 121008 60483 121009 60540 121009 60447 121009 60447 121010 60540 121010 60490 121010 60447 121011 60490 121011 60491 121011 60491 121012 60490 121012 60539 121012 60491 121013 60539 121013 60448 121013 60448 121014 60539 121014 60538 121014 60448 121015 60538 121015 60492 121015 60492 121016 60538 121016 60536 121016 60492 121017 60536 121017 60451 121017 60451 121018 60536 121018 60535 121018 60451 121019 60535 121019 60493 121019 60493 121020 60535 121020 60494 121020 60493 121021 60494 121021 60456 121021 60456 121022 60494 121022 60533 121022 60456 121023 60533 121023 60495 121023 60495 121024 60533 121024 60496 121024 60495 121025 60496 121025 60497 121025 60497 121026 60496 121026 60498 121026 60497 121027 60498 121027 60457 121027 60457 121028 60498 121028 60530 121028 60457 121029 60530 121029 60500 121029 60500 121030 60530 121030 60499 121030 60500 121031 60499 121031 60464 121031 60464 121032 60499 121032 60501 121032 60464 121033 60501 121033 60465 121033 60465 121034 60501 121034 60503 121034 60465 121035 60503 121035 60502 121035 60502 121036 60503 121036 60504 121036 60502 121037 60504 121037 60480 121037 60480 121038 60504 121038 60506 121038 60480 121039 60506 121039 60505 121039 60505 121040 60506 121040 60507 121040 60505 121041 60507 121041 60469 121041 60469 121042 60507 121042 60527 121042 60469 121043 60527 121043 60508 121043 60508 121044 60527 121044 60526 121044 60508 121045 60526 121045 60509 121045 60509 121046 60526 121046 60525 121046 60509 121047 60525 121047 60476 121047 60476 121048 60525 121048 60510 121048 60476 121049 60510 121049 60440 121049 60440 121050 60510 121050 60511 121050 60440 121051 60511 121051 60512 121051 60512 121052 60511 121052 60521 121052 60512 121053 60521 121053 60473 121053 60473 121054 60521 121054 60520 121054 60473 121055 60520 121055 60472 121055 60472 121056 60520 121056 60513 121056 60472 121057 60513 121057 60515 121057 60515 121058 60513 121058 60514 121058 60515 121059 60514 121059 60516 121059 60516 121060 60514 121060 60517 121060 60516 121061 60517 121061 60518 121061 60518 121062 60517 121062 60519 121062 60519 121063 60517 121063 61707 121063 61707 121064 60517 121064 60514 121064 61707 121065 60514 121065 60442 121065 60442 121066 60514 121066 60513 121066 60442 121067 60513 121067 60723 121067 60723 121068 60513 121068 60520 121068 60723 121069 60520 121069 60522 121069 60522 121070 60520 121070 60521 121070 60522 121071 60521 121071 60523 121071 60523 121072 60521 121072 60511 121072 60523 121073 60511 121073 60524 121073 60524 121074 60511 121074 60510 121074 60524 121075 60510 121075 60718 121075 60718 121076 60510 121076 60525 121076 60718 121077 60525 121077 60719 121077 60719 121078 60525 121078 60526 121078 60719 121079 60526 121079 60720 121079 60720 121080 60526 121080 60527 121080 60720 121081 60527 121081 60715 121081 60715 121082 60527 121082 60507 121082 60715 121083 60507 121083 60716 121083 60716 121084 60507 121084 60506 121084 60716 121085 60506 121085 60528 121085 60528 121086 60506 121086 60504 121086 60528 121087 60504 121087 60714 121087 60714 121088 60504 121088 60503 121088 60714 121089 60503 121089 60529 121089 60529 121090 60503 121090 60501 121090 60529 121091 60501 121091 60730 121091 60730 121092 60501 121092 60499 121092 60730 121093 60499 121093 60731 121093 60731 121094 60499 121094 60530 121094 60731 121095 60530 121095 60531 121095 60531 121096 60530 121096 60498 121096 60531 121097 60498 121097 60532 121097 60532 121098 60498 121098 60496 121098 60532 121099 60496 121099 60733 121099 60733 121100 60496 121100 60533 121100 60733 121101 60533 121101 60534 121101 60534 121102 60533 121102 60494 121102 60534 121103 60494 121103 60713 121103 60713 121104 60494 121104 60535 121104 60713 121105 60535 121105 60537 121105 60537 121106 60535 121106 60536 121106 60537 121107 60536 121107 60728 121107 60728 121108 60536 121108 60538 121108 60728 121109 60538 121109 60729 121109 60729 121110 60538 121110 60539 121110 60729 121111 60539 121111 60725 121111 60725 121112 60539 121112 60490 121112 60725 121113 60490 121113 60727 121113 60727 121114 60490 121114 60540 121114 60727 121115 60540 121115 60541 121115 60541 121116 60540 121116 60489 121116 60541 121117 60489 121117 60542 121117 60542 121118 60489 121118 60543 121118 60542 121119 60543 121119 60544 121119 60544 121120 60543 121120 60444 121120 60544 121121 60444 121121 60711 121121 60711 121122 60444 121122 60443 121122 60711 121123 60443 121123 61843 121123 60545 121124 60632 121124 60546 121124 60576 121125 62207 121125 60241 121125 62261 121126 62219 121126 60547 121126 62227 121127 60548 121127 60223 121127 60549 121128 62233 121128 60565 121128 62269 121129 62247 121129 60584 121129 61590 121130 60655 121130 60653 121130 60654 121131 60554 121131 60555 121131 61606 121132 61622 121132 60590 121132 60627 121133 60550 121133 60661 121133 60661 121134 60550 121134 60662 121134 61801 121135 61803 121135 60551 121135 60551 121136 61803 121136 61805 121136 60552 121137 61723 121137 60553 121137 60554 121138 61607 121138 60555 121138 60555 121139 61607 121139 61606 121139 60555 121140 61606 121140 60650 121140 61590 121141 60653 121141 61578 121141 60204 121142 62253 121142 60648 121142 60648 121143 62253 121143 62273 121143 60648 121144 62273 121144 60649 121144 60649 121145 62273 121145 60556 121145 60649 121146 60556 121146 60581 121146 60581 121147 60556 121147 60557 121147 60581 121148 60557 121148 60558 121148 60584 121149 62247 121149 60646 121149 60560 121150 60559 121150 60588 121150 60588 121151 60642 121151 60560 121151 60560 121152 60642 121152 60561 121152 60560 121153 60561 121153 60001 121153 62265 121154 60562 121154 60561 121154 60001 121155 60561 121155 60176 121155 60176 121156 60561 121156 60562 121156 60176 121157 60562 121157 60177 121157 60561 121158 60641 121158 62265 121158 62265 121159 60641 121159 60564 121159 62265 121160 60564 121160 60184 121160 62231 121161 60563 121161 60639 121161 60639 121162 60563 121162 60549 121162 60639 121163 60549 121163 60564 121163 60564 121164 60549 121164 60565 121164 60564 121165 60565 121165 60184 121165 60547 121166 62226 121166 60566 121166 60566 121167 62226 121167 62262 121167 60566 121168 62262 121168 60567 121168 60567 121169 62262 121169 62227 121169 60567 121170 62227 121170 60639 121170 60639 121171 62227 121171 60223 121171 60639 121172 60223 121172 62231 121172 60547 121173 60566 121173 62261 121173 62261 121174 60566 121174 60636 121174 62261 121175 60636 121175 60568 121175 60568 121176 60636 121176 60635 121176 60568 121177 60635 121177 60569 121177 60569 121178 60635 121178 60570 121178 60570 121179 60635 121179 60571 121179 60570 121180 60571 121180 62212 121180 60635 121181 60572 121181 60571 121181 60571 121182 60572 121182 60634 121182 60571 121183 60634 121183 60573 121183 60242 121184 60574 121184 62210 121184 60632 121185 60545 121185 60575 121185 60545 121186 60576 121186 60575 121186 60575 121187 60576 121187 60241 121187 60575 121188 60241 121188 60634 121188 60634 121189 60241 121189 60242 121189 60634 121190 60242 121190 60573 121190 60573 121191 60242 121191 62210 121191 60656 121192 60577 121192 60631 121192 60631 121193 60577 121193 60578 121193 60631 121194 60578 121194 60546 121194 60546 121195 60578 121195 62257 121195 60546 121196 62257 121196 60545 121196 61578 121197 60653 121197 60270 121197 60270 121198 60653 121198 60652 121198 60270 121199 60652 121199 60269 121199 60269 121200 60652 121200 60651 121200 60269 121201 60651 121201 60579 121201 60579 121202 60651 121202 60580 121202 60579 121203 60580 121203 60267 121203 60267 121204 60580 121204 60581 121204 60267 121205 60581 121205 60582 121205 60582 121206 60581 121206 60558 121206 60582 121207 60558 121207 62254 121207 60204 121208 60648 121208 60164 121208 60164 121209 60648 121209 60646 121209 60164 121210 60646 121210 60583 121210 60583 121211 60646 121211 62247 121211 60583 121212 62247 121212 62248 121212 62269 121213 60584 121213 62268 121213 62268 121214 60584 121214 60585 121214 62268 121215 60585 121215 60169 121215 60169 121216 60585 121216 60586 121216 60169 121217 60586 121217 60587 121217 60587 121218 60586 121218 60588 121218 60587 121219 60588 121219 60171 121219 60171 121220 60588 121220 60559 121220 60171 121221 60559 121221 60589 121221 61606 121222 60590 121222 60650 121222 60650 121223 60590 121223 60591 121223 60650 121224 60591 121224 60592 121224 60592 121225 60591 121225 60878 121225 60592 121226 60878 121226 60593 121226 60593 121227 60878 121227 60879 121227 60593 121228 60879 121228 60594 121228 60594 121229 60879 121229 60881 121229 60594 121230 60881 121230 60647 121230 60647 121231 60881 121231 60596 121231 60647 121232 60596 121232 60595 121232 60595 121233 60596 121233 60598 121233 60595 121234 60598 121234 60597 121234 60597 121235 60598 121235 60599 121235 60597 121236 60599 121236 60645 121236 60645 121237 60599 121237 60600 121237 60645 121238 60600 121238 60644 121238 60644 121239 60600 121239 60601 121239 60644 121240 60601 121240 60602 121240 60602 121241 60601 121241 60603 121241 60602 121242 60603 121242 60643 121242 60643 121243 60603 121243 60605 121243 60643 121244 60605 121244 60604 121244 60604 121245 60605 121245 60607 121245 60604 121246 60607 121246 60606 121246 60606 121247 60607 121247 60871 121247 60606 121248 60871 121248 60640 121248 60640 121249 60871 121249 60608 121249 60640 121250 60608 121250 60609 121250 60609 121251 60608 121251 60873 121251 60609 121252 60873 121252 60610 121252 60610 121253 60873 121253 60611 121253 60610 121254 60611 121254 60638 121254 60638 121255 60611 121255 60612 121255 60638 121256 60612 121256 60637 121256 60637 121257 60612 121257 60614 121257 60637 121258 60614 121258 60613 121258 60613 121259 60614 121259 60875 121259 60613 121260 60875 121260 60615 121260 60615 121261 60875 121261 60874 121261 60615 121262 60874 121262 60616 121262 60616 121263 60874 121263 60617 121263 60616 121264 60617 121264 60633 121264 60633 121265 60617 121265 60618 121265 60633 121266 60618 121266 60619 121266 60619 121267 60618 121267 60620 121267 60619 121268 60620 121268 60621 121268 60621 121269 60620 121269 60622 121269 60621 121270 60622 121270 60623 121270 60623 121271 60622 121271 60624 121271 60623 121272 60624 121272 60625 121272 60625 121273 60624 121273 60626 121273 60625 121274 60626 121274 60629 121274 60629 121275 60626 121275 60868 121275 60629 121276 60868 121276 60628 121276 60628 121277 60868 121277 60552 121277 60628 121278 60552 121278 60551 121278 60551 121279 60552 121279 60553 121279 60551 121280 60553 121280 61801 121280 61805 121281 60627 121281 60551 121281 60551 121282 60627 121282 60661 121282 60551 121283 60661 121283 60628 121283 60628 121284 60661 121284 60658 121284 60628 121285 60658 121285 60629 121285 60629 121286 60658 121286 60630 121286 60629 121287 60630 121287 60625 121287 60625 121288 60630 121288 60631 121288 60625 121289 60631 121289 60623 121289 60623 121290 60631 121290 60546 121290 60623 121291 60546 121291 60621 121291 60621 121292 60546 121292 60632 121292 60621 121293 60632 121293 60619 121293 60619 121294 60632 121294 60575 121294 60619 121295 60575 121295 60633 121295 60633 121296 60575 121296 60634 121296 60633 121297 60634 121297 60616 121297 60616 121298 60634 121298 60572 121298 60616 121299 60572 121299 60615 121299 60615 121300 60572 121300 60635 121300 60615 121301 60635 121301 60613 121301 60613 121302 60635 121302 60636 121302 60613 121303 60636 121303 60637 121303 60637 121304 60636 121304 60566 121304 60637 121305 60566 121305 60638 121305 60638 121306 60566 121306 60567 121306 60638 121307 60567 121307 60610 121307 60610 121308 60567 121308 60639 121308 60610 121309 60639 121309 60609 121309 60609 121310 60639 121310 60564 121310 60609 121311 60564 121311 60640 121311 60640 121312 60564 121312 60641 121312 60640 121313 60641 121313 60606 121313 60606 121314 60641 121314 60561 121314 60606 121315 60561 121315 60604 121315 60604 121316 60561 121316 60642 121316 60604 121317 60642 121317 60643 121317 60643 121318 60642 121318 60588 121318 60643 121319 60588 121319 60602 121319 60602 121320 60588 121320 60586 121320 60602 121321 60586 121321 60644 121321 60644 121322 60586 121322 60585 121322 60644 121323 60585 121323 60645 121323 60645 121324 60585 121324 60584 121324 60645 121325 60584 121325 60597 121325 60597 121326 60584 121326 60646 121326 60597 121327 60646 121327 60595 121327 60595 121328 60646 121328 60648 121328 60595 121329 60648 121329 60647 121329 60647 121330 60648 121330 60649 121330 60647 121331 60649 121331 60594 121331 60594 121332 60649 121332 60581 121332 60594 121333 60581 121333 60593 121333 60593 121334 60581 121334 60580 121334 60593 121335 60580 121335 60592 121335 60592 121336 60580 121336 60651 121336 60592 121337 60651 121337 60650 121337 60650 121338 60651 121338 60652 121338 60650 121339 60652 121339 60555 121339 60555 121340 60652 121340 60653 121340 60555 121341 60653 121341 60654 121341 60654 121342 60653 121342 60655 121342 60656 121343 60631 121343 60657 121343 60657 121344 60631 121344 60630 121344 60657 121345 60630 121345 60659 121345 60659 121346 60630 121346 60658 121346 60659 121347 60658 121347 60660 121347 60660 121348 60658 121348 60661 121348 60660 121349 60661 121349 60262 121349 60262 121350 60661 121350 60662 121350 60262 121351 60662 121351 61797 121351 61816 121352 61082 121352 60663 121352 60663 121353 61082 121353 61340 121353 60663 121354 61340 121354 61742 121354 61742 121355 61340 121355 61346 121355 61742 121356 61346 121356 61744 121356 61744 121357 61346 121357 60664 121357 61744 121358 60664 121358 61741 121358 61741 121359 60664 121359 60665 121359 61741 121360 60665 121360 60666 121360 60666 121361 60665 121361 61347 121361 60666 121362 61347 121362 60667 121362 60667 121363 61347 121363 60668 121363 60667 121364 60668 121364 61747 121364 61747 121365 60668 121365 61360 121365 61747 121366 61360 121366 60670 121366 60670 121367 61360 121367 60669 121367 60670 121368 60669 121368 61750 121368 61750 121369 60669 121369 61359 121369 61750 121370 61359 121370 61751 121370 61751 121371 61359 121371 61358 121371 61751 121372 61358 121372 60671 121372 60671 121373 61358 121373 60672 121373 60671 121374 60672 121374 60673 121374 60673 121375 60672 121375 60675 121375 60673 121376 60675 121376 60674 121376 60674 121377 60675 121377 60676 121377 60674 121378 60676 121378 60677 121378 60677 121379 60676 121379 60678 121379 60677 121380 60678 121380 61748 121380 61748 121381 60678 121381 60679 121381 61748 121382 60679 121382 61754 121382 61754 121383 60679 121383 60681 121383 61754 121384 60681 121384 60680 121384 60680 121385 60681 121385 61325 121385 60680 121386 61325 121386 61757 121386 61757 121387 61325 121387 61324 121387 61757 121388 61324 121388 60682 121388 60682 121389 61324 121389 60683 121389 60682 121390 60683 121390 61753 121390 61753 121391 60683 121391 60684 121391 61753 121392 60684 121392 60685 121392 60685 121393 60684 121393 60686 121393 60685 121394 60686 121394 61062 121394 61062 121395 60686 121395 61378 121395 61084 121396 60687 121396 61244 121396 61244 121397 60687 121397 60688 121397 61244 121398 60688 121398 60689 121398 60689 121399 60688 121399 60690 121399 60689 121400 60690 121400 60691 121400 60691 121401 60690 121401 61646 121401 60691 121402 61646 121402 60692 121402 60692 121403 61646 121403 60693 121403 60692 121404 60693 121404 61247 121404 61247 121405 60693 121405 61673 121405 61247 121406 61673 121406 61249 121406 61249 121407 61673 121407 60694 121407 61249 121408 60694 121408 61251 121408 61251 121409 60694 121409 61681 121409 61251 121410 61681 121410 60695 121410 60695 121411 61681 121411 60696 121411 60695 121412 60696 121412 61246 121412 61246 121413 60696 121413 60697 121413 61246 121414 60697 121414 60698 121414 60698 121415 60697 121415 61680 121415 60698 121416 61680 121416 60699 121416 60699 121417 61680 121417 61679 121417 60699 121418 61679 121418 61253 121418 61253 121419 61679 121419 61678 121419 61253 121420 61678 121420 60700 121420 60700 121421 61678 121421 61687 121421 60700 121422 61687 121422 61255 121422 61255 121423 61687 121423 61688 121423 61255 121424 61688 121424 60701 121424 60701 121425 61688 121425 60703 121425 60701 121426 60703 121426 60702 121426 60702 121427 60703 121427 61694 121427 60702 121428 61694 121428 60704 121428 60704 121429 61694 121429 61696 121429 60704 121430 61696 121430 60705 121430 60705 121431 61696 121431 61645 121431 60705 121432 61645 121432 61258 121432 61258 121433 61645 121433 61644 121433 61258 121434 61644 121434 60706 121434 60706 121435 61644 121435 61700 121435 60706 121436 61700 121436 60708 121436 60708 121437 61700 121437 60707 121437 60708 121438 60707 121438 60709 121438 60709 121439 60707 121439 60710 121439 61843 121440 61818 121440 60711 121440 60711 121441 61818 121441 60712 121441 60711 121442 60712 121442 60544 121442 60544 121443 60712 121443 61811 121443 60524 121444 60717 121444 60523 121444 60523 121445 60717 121445 60724 121445 60726 121446 61795 121446 60725 121446 61793 121447 61791 121447 60713 121447 61787 121448 61785 121448 60529 121448 61784 121449 60528 121449 61785 121449 61785 121450 60528 121450 60714 121450 61785 121451 60714 121451 60529 121451 61782 121452 60715 121452 61784 121452 61784 121453 60715 121453 60716 121453 61784 121454 60716 121454 60528 121454 60524 121455 60718 121455 60717 121455 60717 121456 60718 121456 60719 121456 60717 121457 60719 121457 61782 121457 61782 121458 60719 121458 60720 121458 61782 121459 60720 121459 60715 121459 61726 121460 60721 121460 61727 121460 61727 121461 60721 121461 60442 121461 61727 121462 60442 121462 60722 121462 60722 121463 60442 121463 60723 121463 60722 121464 60723 121464 60724 121464 60724 121465 60723 121465 60522 121465 60724 121466 60522 121466 60523 121466 60725 121467 60727 121467 60726 121467 60726 121468 60727 121468 60541 121468 60726 121469 60541 121469 61811 121469 61811 121470 60541 121470 60542 121470 61811 121471 60542 121471 60544 121471 60713 121472 60537 121472 61793 121472 61793 121473 60537 121473 60728 121473 61793 121474 60728 121474 61795 121474 61795 121475 60728 121475 60729 121475 61795 121476 60729 121476 60725 121476 60529 121477 60730 121477 61787 121477 61787 121478 60730 121478 60731 121478 61787 121479 60731 121479 61789 121479 61789 121480 60731 121480 60531 121480 61789 121481 60531 121481 60732 121481 60732 121482 60531 121482 60532 121482 60732 121483 60532 121483 60734 121483 60734 121484 60532 121484 60733 121484 60734 121485 60733 121485 61791 121485 61791 121486 60733 121486 60534 121486 61791 121487 60534 121487 60713 121487 61400 121488 60735 121488 60736 121488 60736 121489 60735 121489 60737 121489 60736 121490 60737 121490 60738 121490 60737 121491 60835 121491 60738 121491 60738 121492 60835 121492 60748 121492 60738 121493 60748 121493 60739 121493 61368 121494 60763 121494 60815 121494 60740 121495 60823 121495 60741 121495 60741 121496 60823 121496 60822 121496 60741 121497 60822 121497 61329 121497 60747 121498 60826 121498 60740 121498 60740 121499 60826 121499 60742 121499 60740 121500 60742 121500 60823 121500 60744 121501 60811 121501 60743 121501 60743 121502 60811 121502 60808 121502 60743 121503 60808 121503 60758 121503 60815 121504 60814 121504 61368 121504 61368 121505 60814 121505 60813 121505 61368 121506 60813 121506 60744 121506 60744 121507 60813 121507 60745 121507 60744 121508 60745 121508 60811 121508 60746 121509 60828 121509 60747 121509 60747 121510 60828 121510 60827 121510 60747 121511 60827 121511 60826 121511 60748 121512 60749 121512 60739 121512 60739 121513 60749 121513 60831 121513 60739 121514 60831 121514 60746 121514 60746 121515 60831 121515 60750 121515 60746 121516 60750 121516 60828 121516 61304 121517 60751 121517 60752 121517 60752 121518 60751 121518 61312 121518 60752 121519 61312 121519 60754 121519 60754 121520 61312 121520 60753 121520 60754 121521 60753 121521 60755 121521 60755 121522 60753 121522 60756 121522 60755 121523 60756 121523 60757 121523 60757 121524 60756 121524 60743 121524 60757 121525 60743 121525 60805 121525 60805 121526 60743 121526 60758 121526 60822 121527 60820 121527 61329 121527 61329 121528 60820 121528 60759 121528 61329 121529 60759 121529 61328 121529 61328 121530 60759 121530 60760 121530 61328 121531 60760 121531 60761 121531 60761 121532 60760 121532 60762 121532 60761 121533 60762 121533 60763 121533 60763 121534 60762 121534 60817 121534 60763 121535 60817 121535 60815 121535 60764 121536 61304 121536 60752 121536 60737 121537 60735 121537 60765 121537 61208 121538 61240 121538 60862 121538 60862 121539 61240 121539 60764 121539 60862 121540 60764 121540 60861 121540 60768 121541 61215 121541 60766 121541 60766 121542 61215 121542 60863 121542 61437 121543 60767 121543 60838 121543 60838 121544 60767 121544 61441 121544 60836 121545 61447 121545 60837 121545 60837 121546 61447 121546 61437 121546 60860 121547 60772 121547 60766 121547 60766 121548 60772 121548 61219 121548 60766 121549 61219 121549 60768 121549 60781 121550 60769 121550 60770 121550 60770 121551 60769 121551 60771 121551 60770 121552 60771 121552 60860 121552 60860 121553 60771 121553 59686 121553 60860 121554 59686 121554 60772 121554 60855 121555 59670 121555 60773 121555 60773 121556 59670 121556 60774 121556 60773 121557 60774 121557 60856 121557 60856 121558 60774 121558 60775 121558 60856 121559 60775 121559 60776 121559 60776 121560 60775 121560 59674 121560 60776 121561 59674 121561 60777 121561 60777 121562 59674 121562 60779 121562 60777 121563 60779 121563 60778 121563 60778 121564 60779 121564 59675 121564 60778 121565 59675 121565 60781 121565 60781 121566 59675 121566 60780 121566 60781 121567 60780 121567 60769 121567 59669 121568 60782 121568 60855 121568 60855 121569 60782 121569 60783 121569 60855 121570 60783 121570 59670 121570 60855 121571 60854 121571 59669 121571 59669 121572 60854 121572 60852 121572 59669 121573 60852 121573 60784 121573 60784 121574 60852 121574 60785 121574 60784 121575 60785 121575 59668 121575 59668 121576 60785 121576 60787 121576 59668 121577 60787 121577 60786 121577 60786 121578 60787 121578 60849 121578 60786 121579 60849 121579 59662 121579 59662 121580 60849 121580 60788 121580 59662 121581 60788 121581 60789 121581 60789 121582 60788 121582 60790 121582 60789 121583 60790 121583 59653 121583 59653 121584 60790 121584 60791 121584 59653 121585 60791 121585 59651 121585 59651 121586 60791 121586 60792 121586 59651 121587 60792 121587 59650 121587 59650 121588 60792 121588 60793 121588 60793 121589 60792 121589 60794 121589 60793 121590 60794 121590 60796 121590 60796 121591 60794 121591 60795 121591 60796 121592 60795 121592 59644 121592 59644 121593 60795 121593 60797 121593 60797 121594 60795 121594 60798 121594 60797 121595 60798 121595 60799 121595 60799 121596 60798 121596 60844 121596 60799 121597 60844 121597 59647 121597 59647 121598 60844 121598 60843 121598 59647 121599 60843 121599 59649 121599 59649 121600 60843 121600 60800 121600 59649 121601 60800 121601 59640 121601 59640 121602 60800 121602 59641 121602 59641 121603 60800 121603 60842 121603 59641 121604 60842 121604 60801 121604 60801 121605 60842 121605 60841 121605 60801 121606 60841 121606 60802 121606 60802 121607 60841 121607 59636 121607 59636 121608 60841 121608 60839 121608 59636 121609 60839 121609 59635 121609 59635 121610 60839 121610 60803 121610 59635 121611 60803 121611 60804 121611 60764 121612 60752 121612 60861 121612 60861 121613 60752 121613 60754 121613 60861 121614 60754 121614 60859 121614 60859 121615 60754 121615 60755 121615 60859 121616 60755 121616 60858 121616 60858 121617 60755 121617 60757 121617 60858 121618 60757 121618 60857 121618 60857 121619 60757 121619 60805 121619 60857 121620 60805 121620 60806 121620 60806 121621 60805 121621 60758 121621 60806 121622 60758 121622 60807 121622 60807 121623 60758 121623 60808 121623 60807 121624 60808 121624 60809 121624 60809 121625 60808 121625 60811 121625 60809 121626 60811 121626 60810 121626 60810 121627 60811 121627 60745 121627 60810 121628 60745 121628 60812 121628 60812 121629 60745 121629 60813 121629 60812 121630 60813 121630 60853 121630 60853 121631 60813 121631 60814 121631 60853 121632 60814 121632 60816 121632 60816 121633 60814 121633 60815 121633 60816 121634 60815 121634 60851 121634 60851 121635 60815 121635 60817 121635 60851 121636 60817 121636 60850 121636 60850 121637 60817 121637 60762 121637 60850 121638 60762 121638 60818 121638 60818 121639 60762 121639 60760 121639 60818 121640 60760 121640 60819 121640 60819 121641 60760 121641 60759 121641 60819 121642 60759 121642 60848 121642 60848 121643 60759 121643 60820 121643 60848 121644 60820 121644 60821 121644 60821 121645 60820 121645 60822 121645 60821 121646 60822 121646 60847 121646 60847 121647 60822 121647 60823 121647 60847 121648 60823 121648 60824 121648 60824 121649 60823 121649 60742 121649 60824 121650 60742 121650 60825 121650 60825 121651 60742 121651 60826 121651 60825 121652 60826 121652 60846 121652 60846 121653 60826 121653 60827 121653 60846 121654 60827 121654 60845 121654 60845 121655 60827 121655 60828 121655 60845 121656 60828 121656 60829 121656 60829 121657 60828 121657 60750 121657 60829 121658 60750 121658 60830 121658 60830 121659 60750 121659 60831 121659 60830 121660 60831 121660 60832 121660 60832 121661 60831 121661 60749 121661 60832 121662 60749 121662 60840 121662 60840 121663 60749 121663 60748 121663 60840 121664 60748 121664 60833 121664 60833 121665 60748 121665 60835 121665 60833 121666 60835 121666 60834 121666 60834 121667 60835 121667 60737 121667 60834 121668 60737 121668 60837 121668 60837 121669 60737 121669 60765 121669 60837 121670 60765 121670 60836 121670 61437 121671 60838 121671 60837 121671 60837 121672 60838 121672 60803 121672 60837 121673 60803 121673 60834 121673 60834 121674 60803 121674 60839 121674 60834 121675 60839 121675 60833 121675 60833 121676 60839 121676 60841 121676 60833 121677 60841 121677 60840 121677 60840 121678 60841 121678 60842 121678 60840 121679 60842 121679 60832 121679 60832 121680 60842 121680 60800 121680 60832 121681 60800 121681 60830 121681 60830 121682 60800 121682 60843 121682 60830 121683 60843 121683 60829 121683 60829 121684 60843 121684 60844 121684 60829 121685 60844 121685 60845 121685 60845 121686 60844 121686 60798 121686 60845 121687 60798 121687 60846 121687 60846 121688 60798 121688 60795 121688 60846 121689 60795 121689 60825 121689 60825 121690 60795 121690 60794 121690 60825 121691 60794 121691 60824 121691 60824 121692 60794 121692 60792 121692 60824 121693 60792 121693 60847 121693 60847 121694 60792 121694 60791 121694 60847 121695 60791 121695 60821 121695 60821 121696 60791 121696 60790 121696 60821 121697 60790 121697 60848 121697 60848 121698 60790 121698 60788 121698 60848 121699 60788 121699 60819 121699 60819 121700 60788 121700 60849 121700 60819 121701 60849 121701 60818 121701 60818 121702 60849 121702 60787 121702 60818 121703 60787 121703 60850 121703 60850 121704 60787 121704 60785 121704 60850 121705 60785 121705 60851 121705 60851 121706 60785 121706 60852 121706 60851 121707 60852 121707 60816 121707 60816 121708 60852 121708 60854 121708 60816 121709 60854 121709 60853 121709 60853 121710 60854 121710 60855 121710 60853 121711 60855 121711 60812 121711 60812 121712 60855 121712 60773 121712 60812 121713 60773 121713 60810 121713 60810 121714 60773 121714 60856 121714 60810 121715 60856 121715 60809 121715 60809 121716 60856 121716 60776 121716 60809 121717 60776 121717 60807 121717 60807 121718 60776 121718 60777 121718 60807 121719 60777 121719 60806 121719 60806 121720 60777 121720 60778 121720 60806 121721 60778 121721 60857 121721 60857 121722 60778 121722 60781 121722 60857 121723 60781 121723 60858 121723 60858 121724 60781 121724 60770 121724 60858 121725 60770 121725 60859 121725 60859 121726 60770 121726 60860 121726 60859 121727 60860 121727 60861 121727 60861 121728 60860 121728 60766 121728 60861 121729 60766 121729 60862 121729 60862 121730 60766 121730 60863 121730 60862 121731 60863 121731 61208 121731 60804 121732 60803 121732 60864 121732 60864 121733 60803 121733 60838 121733 60864 121734 60838 121734 60865 121734 60865 121735 60838 121735 61441 121735 60865 121736 61441 121736 61471 121736 60866 121737 61551 121737 60867 121737 60867 121738 61551 121738 61550 121738 60867 121739 61550 121739 61103 121739 61103 121740 61550 121740 61572 121740 61718 121741 61723 121741 61715 121741 61715 121742 61723 121742 60552 121742 61715 121743 60552 121743 60869 121743 60552 121744 60868 121744 60869 121744 60869 121745 60868 121745 60626 121745 60869 121746 60626 121746 60870 121746 61647 121747 60873 121747 61648 121747 61648 121748 60873 121748 60608 121748 61648 121749 60608 121749 61682 121749 61682 121750 60608 121750 60871 121750 61682 121751 60871 121751 61683 121751 61653 121752 60614 121752 60872 121752 60872 121753 60614 121753 60612 121753 60872 121754 60612 121754 61647 121754 61647 121755 60612 121755 60611 121755 61647 121756 60611 121756 60873 121756 60626 121757 60624 121757 60870 121757 60870 121758 60624 121758 60622 121758 60870 121759 60622 121759 60876 121759 60882 121760 60884 121760 60601 121760 61671 121761 60874 121761 61653 121761 61653 121762 60874 121762 60875 121762 61653 121763 60875 121763 60614 121763 60622 121764 60620 121764 60876 121764 60876 121765 60620 121765 60618 121765 60876 121766 60618 121766 61671 121766 61671 121767 60618 121767 60617 121767 61671 121768 60617 121768 60874 121768 61622 121769 61627 121769 60590 121769 60590 121770 61627 121770 61631 121770 60590 121771 61631 121771 60591 121771 60591 121772 61631 121772 60877 121772 60591 121773 60877 121773 60878 121773 60878 121774 60877 121774 60880 121774 60878 121775 60880 121775 60879 121775 60879 121776 60880 121776 60883 121776 60879 121777 60883 121777 60881 121777 60881 121778 60883 121778 60596 121778 60601 121779 60600 121779 60882 121779 60882 121780 60600 121780 60599 121780 60882 121781 60599 121781 60883 121781 60883 121782 60599 121782 60598 121782 60883 121783 60598 121783 60596 121783 60871 121784 60607 121784 61683 121784 61683 121785 60607 121785 60605 121785 61683 121786 60605 121786 60884 121786 60884 121787 60605 121787 60603 121787 60884 121788 60603 121788 60601 121788 61052 121789 61913 121789 61522 121789 61522 121790 61913 121790 60886 121790 61522 121791 60886 121791 60885 121791 60885 121792 60886 121792 60887 121792 60888 121793 60889 121793 61004 121793 61004 121794 60889 121794 60890 121794 61004 121795 60890 121795 60891 121795 60891 121796 60890 121796 61289 121796 60892 121797 60893 121797 60895 121797 60894 121798 61299 121798 60984 121798 60984 121799 61299 121799 61300 121799 60895 121800 61001 121800 60892 121800 60892 121801 61001 121801 61002 121801 60892 121802 61002 121802 61289 121802 61289 121803 61002 121803 60896 121803 61289 121804 60896 121804 60891 121804 61223 121805 61201 121805 61228 121805 61228 121806 61201 121806 60981 121806 61228 121807 60981 121807 60897 121807 60897 121808 60981 121808 60982 121808 60897 121809 60982 121809 61300 121809 61300 121810 60982 121810 60983 121810 61300 121811 60983 121811 60984 121811 60898 121812 61292 121812 60997 121812 60997 121813 60999 121813 60898 121813 60898 121814 60999 121814 60899 121814 60898 121815 60899 121815 60893 121815 60893 121816 60899 121816 61000 121816 60893 121817 61000 121817 60895 121817 61296 121818 60900 121818 60901 121818 60901 121819 60900 121819 60993 121819 60901 121820 60993 121820 60902 121820 60902 121821 60993 121821 60903 121821 60902 121822 60903 121822 61293 121822 61293 121823 60903 121823 60904 121823 61293 121824 60904 121824 61292 121824 61292 121825 60904 121825 60905 121825 61292 121826 60905 121826 60997 121826 61297 121827 60906 121827 61296 121827 61296 121828 60906 121828 60907 121828 61296 121829 60907 121829 60900 121829 61298 121830 60990 121830 61297 121830 61297 121831 60990 121831 60908 121831 61297 121832 60908 121832 60906 121832 60912 121833 60909 121833 61298 121833 61298 121834 60909 121834 60989 121834 61298 121835 60989 121835 60990 121835 60894 121836 60910 121836 61299 121836 61299 121837 60910 121837 60911 121837 61299 121838 60911 121838 60912 121838 60912 121839 60911 121839 60987 121839 60912 121840 60987 121840 60909 121840 60943 121841 60945 121841 60913 121841 61175 121842 59570 121842 59569 121842 61187 121843 61188 121843 60979 121843 60981 121844 61201 121844 61202 121844 60915 121845 61403 121845 61381 121845 60914 121846 61410 121846 60915 121846 60915 121847 61410 121847 61402 121847 60915 121848 61402 121848 61403 121848 60944 121849 60916 121849 60914 121849 60916 121850 60944 121850 61401 121850 61401 121851 60944 121851 59564 121851 61401 121852 59564 121852 61417 121852 61181 121853 60917 121853 60918 121853 60918 121854 60917 121854 61175 121854 61175 121855 59569 121855 60918 121855 60918 121856 59569 121856 59568 121856 60918 121857 59568 121857 60919 121857 60919 121858 59568 121858 59567 121858 60919 121859 59567 121859 60978 121859 59567 121860 60920 121860 60978 121860 60978 121861 60920 121861 59572 121861 60978 121862 59572 121862 60976 121862 60976 121863 59572 121863 59576 121863 60976 121864 59576 121864 60973 121864 59576 121865 59580 121865 60973 121865 60973 121866 59580 121866 59581 121866 60973 121867 59581 121867 60972 121867 60972 121868 59581 121868 59585 121868 60972 121869 59585 121869 60921 121869 60921 121870 59585 121870 59587 121870 60921 121871 59587 121871 60970 121871 60970 121872 59587 121872 59588 121872 60970 121873 59588 121873 60922 121873 60922 121874 59588 121874 60923 121874 60922 121875 60923 121875 60968 121875 60968 121876 60923 121876 59591 121876 60968 121877 59591 121877 60967 121877 59591 121878 59590 121878 60967 121878 60967 121879 59590 121879 60924 121879 60967 121880 60924 121880 60925 121880 60925 121881 60924 121881 59594 121881 60925 121882 59594 121882 60964 121882 60964 121883 59594 121883 60926 121883 60964 121884 60926 121884 60963 121884 60963 121885 60926 121885 60927 121885 60963 121886 60927 121886 60961 121886 60961 121887 60927 121887 60928 121887 60961 121888 60928 121888 60929 121888 60929 121889 60928 121889 60930 121889 60929 121890 60930 121890 60959 121890 60959 121891 60930 121891 59605 121891 60959 121892 59605 121892 60957 121892 60957 121893 59605 121893 60931 121893 59607 121894 60933 121894 60931 121894 60931 121895 60933 121895 60956 121895 60931 121896 60956 121896 60957 121896 59607 121897 60932 121897 60933 121897 60933 121898 60932 121898 60934 121898 60933 121899 60934 121899 60935 121899 60935 121900 60934 121900 59617 121900 60935 121901 59617 121901 60954 121901 60954 121902 59617 121902 60936 121902 60954 121903 60936 121903 60937 121903 60937 121904 60936 121904 59615 121904 60937 121905 59615 121905 60939 121905 60939 121906 59615 121906 60938 121906 60939 121907 60938 121907 60951 121907 60938 121908 59614 121908 60951 121908 60951 121909 59614 121909 60940 121909 60951 121910 60940 121910 60949 121910 60949 121911 60940 121911 59613 121911 60949 121912 59613 121912 60942 121912 60942 121913 59613 121913 60941 121913 60942 121914 60941 121914 60913 121914 60913 121915 60941 121915 59623 121915 60913 121916 59623 121916 60943 121916 60945 121917 60943 121917 60944 121917 60944 121918 60943 121918 59565 121918 60944 121919 59565 121919 59564 121919 60914 121920 60915 121920 60944 121920 60944 121921 60915 121921 61003 121921 60944 121922 61003 121922 60945 121922 60945 121923 61003 121923 60946 121923 60945 121924 60946 121924 60913 121924 60913 121925 60946 121925 60947 121925 60913 121926 60947 121926 60942 121926 60942 121927 60947 121927 60948 121927 60942 121928 60948 121928 60949 121928 60949 121929 60948 121929 60950 121929 60949 121930 60950 121930 60951 121930 60951 121931 60950 121931 60952 121931 60951 121932 60952 121932 60939 121932 60939 121933 60952 121933 60953 121933 60939 121934 60953 121934 60937 121934 60937 121935 60953 121935 60998 121935 60937 121936 60998 121936 60954 121936 60954 121937 60998 121937 60996 121937 60954 121938 60996 121938 60935 121938 60935 121939 60996 121939 60955 121939 60935 121940 60955 121940 60933 121940 60933 121941 60955 121941 60995 121941 60933 121942 60995 121942 60956 121942 60956 121943 60995 121943 60994 121943 60956 121944 60994 121944 60957 121944 60957 121945 60994 121945 60958 121945 60957 121946 60958 121946 60959 121946 60959 121947 60958 121947 60960 121947 60959 121948 60960 121948 60929 121948 60929 121949 60960 121949 60992 121949 60929 121950 60992 121950 60961 121950 60961 121951 60992 121951 60962 121951 60961 121952 60962 121952 60963 121952 60963 121953 60962 121953 60991 121953 60963 121954 60991 121954 60964 121954 60964 121955 60991 121955 60965 121955 60964 121956 60965 121956 60925 121956 60925 121957 60965 121957 60988 121957 60925 121958 60988 121958 60967 121958 60967 121959 60988 121959 60966 121959 60967 121960 60966 121960 60968 121960 60968 121961 60966 121961 60986 121961 60968 121962 60986 121962 60922 121962 60922 121963 60986 121963 60969 121963 60922 121964 60969 121964 60970 121964 60970 121965 60969 121965 60985 121965 60970 121966 60985 121966 60921 121966 60921 121967 60985 121967 60971 121967 60921 121968 60971 121968 60972 121968 60972 121969 60971 121969 60974 121969 60972 121970 60974 121970 60973 121970 60973 121971 60974 121971 60975 121971 60973 121972 60975 121972 60976 121972 60976 121973 60975 121973 60977 121973 60976 121974 60977 121974 60978 121974 60978 121975 60977 121975 60980 121975 60978 121976 60980 121976 60919 121976 60919 121977 60980 121977 60979 121977 60919 121978 60979 121978 60918 121978 60918 121979 60979 121979 61188 121979 60918 121980 61188 121980 61181 121980 61187 121981 60979 121981 61202 121981 61202 121982 60979 121982 60980 121982 61202 121983 60980 121983 60981 121983 60981 121984 60980 121984 60977 121984 60981 121985 60977 121985 60982 121985 60982 121986 60977 121986 60975 121986 60982 121987 60975 121987 60983 121987 60983 121988 60975 121988 60974 121988 60983 121989 60974 121989 60984 121989 60984 121990 60974 121990 60971 121990 60984 121991 60971 121991 60894 121991 60894 121992 60971 121992 60985 121992 60894 121993 60985 121993 60910 121993 60910 121994 60985 121994 60969 121994 60910 121995 60969 121995 60911 121995 60911 121996 60969 121996 60986 121996 60911 121997 60986 121997 60987 121997 60987 121998 60986 121998 60966 121998 60987 121999 60966 121999 60909 121999 60909 122000 60966 122000 60988 122000 60909 122001 60988 122001 60989 122001 60989 122002 60988 122002 60965 122002 60989 122003 60965 122003 60990 122003 60990 122004 60965 122004 60991 122004 60990 122005 60991 122005 60908 122005 60908 122006 60991 122006 60962 122006 60908 122007 60962 122007 60906 122007 60906 122008 60962 122008 60992 122008 60906 122009 60992 122009 60907 122009 60907 122010 60992 122010 60960 122010 60907 122011 60960 122011 60900 122011 60900 122012 60960 122012 60958 122012 60900 122013 60958 122013 60993 122013 60993 122014 60958 122014 60994 122014 60993 122015 60994 122015 60903 122015 60903 122016 60994 122016 60995 122016 60903 122017 60995 122017 60904 122017 60904 122018 60995 122018 60955 122018 60904 122019 60955 122019 60905 122019 60905 122020 60955 122020 60996 122020 60905 122021 60996 122021 60997 122021 60997 122022 60996 122022 60998 122022 60997 122023 60998 122023 60999 122023 60999 122024 60998 122024 60953 122024 60999 122025 60953 122025 60899 122025 60899 122026 60953 122026 60952 122026 60899 122027 60952 122027 61000 122027 61000 122028 60952 122028 60950 122028 61000 122029 60950 122029 60895 122029 60895 122030 60950 122030 60948 122030 60895 122031 60948 122031 61001 122031 61001 122032 60948 122032 60947 122032 61001 122033 60947 122033 61002 122033 61002 122034 60947 122034 60946 122034 61002 122035 60946 122035 60896 122035 60896 122036 60946 122036 61003 122036 60896 122037 61003 122037 60891 122037 60891 122038 61003 122038 60915 122038 60891 122039 60915 122039 61004 122039 61004 122040 60915 122040 61381 122040 61004 122041 61381 122041 60888 122041 61005 122042 61006 122042 61547 122042 61547 122043 61006 122043 61117 122043 61547 122044 61117 122044 61544 122044 61544 122045 61117 122045 61139 122045 61007 122046 61009 122046 61008 122046 61008 122047 61009 122047 61157 122047 61008 122048 61157 122048 61010 122048 61010 122049 61157 122049 61011 122049 61010 122050 61011 122050 61012 122050 61012 122051 61011 122051 61176 122051 61012 122052 61176 122052 61014 122052 61014 122053 61176 122053 61013 122053 61014 122054 61013 122054 61015 122054 61015 122055 61013 122055 61183 122055 61015 122056 61183 122056 61613 122056 61613 122057 61183 122057 61068 122057 61846 122058 61016 122058 61869 122058 61869 122059 61016 122059 61477 122059 61869 122060 61477 122060 61017 122060 61017 122061 61477 122061 61476 122061 61086 122062 61404 122062 61018 122062 61018 122063 61404 122063 61019 122063 61018 122064 61019 122064 61020 122064 61020 122065 61019 122065 61412 122065 61020 122066 61412 122066 61808 122066 61808 122067 61412 122067 61021 122067 61808 122068 61021 122068 61798 122068 61798 122069 61021 122069 61426 122069 61798 122070 61426 122070 61834 122070 61834 122071 61426 122071 61434 122071 61834 122072 61434 122072 61829 122072 61829 122073 61434 122073 61432 122073 61022 122074 61023 122074 61586 122074 61586 122075 61023 122075 61140 122075 61586 122076 61140 122076 61057 122076 61057 122077 61140 122077 61058 122077 61643 122078 61235 122078 61024 122078 61024 122079 61235 122079 61209 122079 61024 122080 61209 122080 61025 122080 61025 122081 61209 122081 61026 122081 61025 122082 61026 122082 61027 122082 61027 122083 61026 122083 61216 122083 61027 122084 61216 122084 61028 122084 61028 122085 61216 122085 61029 122085 61028 122086 61029 122086 61030 122086 61030 122087 61029 122087 61193 122087 61030 122088 61193 122088 61031 122088 61031 122089 61193 122089 61192 122089 61045 122090 61044 122090 61032 122090 61032 122091 61044 122091 61033 122091 61032 122092 61033 122092 61034 122092 61034 122093 61033 122093 61438 122093 61034 122094 61438 122094 61867 122094 61867 122095 61438 122095 61035 122095 61867 122096 61035 122096 61865 122096 61865 122097 61035 122097 61036 122097 61865 122098 61036 122098 61863 122098 61863 122099 61036 122099 61037 122099 61863 122100 61037 122100 61836 122100 61836 122101 61037 122101 61077 122101 61038 122102 61508 122102 61039 122102 61039 122103 61508 122103 61513 122103 61039 122104 61513 122104 61894 122104 61894 122105 61513 122105 61043 122105 61031 122106 61192 122106 61040 122106 61023 122107 61022 122107 61041 122107 61041 122108 61022 122108 61597 122108 61041 122109 61597 122109 61040 122109 61040 122110 61597 122110 61042 122110 61040 122111 61042 122111 61031 122111 61894 122112 61043 122112 61494 122112 61044 122113 61045 122113 61046 122113 61046 122114 61045 122114 61890 122114 61046 122115 61890 122115 61494 122115 61494 122116 61890 122116 61047 122116 61494 122117 61047 122117 61894 122117 61829 122118 61432 122118 61457 122118 61016 122119 61846 122119 61459 122119 61459 122120 61846 122120 61048 122120 61459 122121 61048 122121 61457 122121 61457 122122 61048 122122 61851 122122 61457 122123 61851 122123 61829 122123 61544 122124 61139 122124 61049 122124 61009 122125 61007 122125 61133 122125 61133 122126 61007 122126 61559 122126 61133 122127 61559 122127 61049 122127 61049 122128 61559 122128 61050 122128 61049 122129 61050 122129 61544 122129 61551 122130 60866 122130 61051 122130 61051 122131 60866 122131 61089 122131 61051 122132 61089 122132 61540 122132 61089 122133 61100 122133 61540 122133 61540 122134 61100 122134 61006 122134 61540 122135 61006 122135 61005 122135 61017 122136 61476 122136 61881 122136 61881 122137 61476 122137 61498 122137 61881 122138 61498 122138 61884 122138 61498 122139 61503 122139 61884 122139 61884 122140 61503 122140 60885 122140 61884 122141 60885 122141 60887 122141 61913 122142 61052 122142 61053 122142 61053 122143 61052 122143 61054 122143 61053 122144 61054 122144 61056 122144 61054 122145 61055 122145 61056 122145 61056 122146 61055 122146 61508 122146 61056 122147 61508 122147 61038 122147 61057 122148 61058 122148 61569 122148 61569 122149 61058 122149 61059 122149 61569 122150 61059 122150 61060 122150 61059 122151 61061 122151 61060 122151 61060 122152 61061 122152 61103 122152 61060 122153 61103 122153 61572 122153 61067 122154 61732 122154 61063 122154 61063 122155 61732 122155 61062 122155 61063 122156 61062 122156 61378 122156 61235 122157 61643 122157 61236 122157 61236 122158 61643 122158 61064 122158 61236 122159 61064 122159 61066 122159 61066 122160 61064 122160 61065 122160 61066 122161 61065 122161 61067 122161 61067 122162 61065 122162 61730 122162 61067 122163 61730 122163 61732 122163 61613 122164 61068 122164 61612 122164 61612 122165 61068 122165 61195 122165 61612 122166 61195 122166 61069 122166 61069 122167 61195 122167 61070 122167 61069 122168 61070 122168 61621 122168 61621 122169 61070 122169 61072 122169 61621 122170 61072 122170 61071 122170 61071 122171 61072 122171 61073 122171 61071 122172 61073 122172 61074 122172 61074 122173 61073 122173 61075 122173 61074 122174 61075 122174 61076 122174 61076 122175 61075 122175 61231 122175 61076 122176 61231 122176 60710 122176 60710 122177 61231 122177 60709 122177 61836 122178 61077 122178 61078 122178 61078 122179 61077 122179 61424 122179 61078 122180 61424 122180 61845 122180 61845 122181 61424 122181 61391 122181 61845 122182 61391 122182 61080 122182 61391 122183 61079 122183 61080 122183 61080 122184 61079 122184 61389 122184 61080 122185 61389 122185 61081 122185 61081 122186 61389 122186 61082 122186 61081 122187 61082 122187 61816 122187 61323 122188 61083 122188 61322 122188 61322 122189 61083 122189 60687 122189 61322 122190 60687 122190 61084 122190 61404 122191 61086 122191 61085 122191 61085 122192 61086 122192 61087 122192 61085 122193 61087 122193 61379 122193 61379 122194 61087 122194 61719 122194 61379 122195 61719 122195 61323 122195 61323 122196 61719 122196 61088 122196 61323 122197 61088 122197 61083 122197 61089 122198 60866 122198 61095 122198 61095 122199 60866 122199 61090 122199 61095 122200 61090 122200 61097 122200 61097 122201 61090 122201 61111 122201 61097 122202 61111 122202 61091 122202 61091 122203 61111 122203 61092 122203 61091 122204 61092 122204 61093 122204 61093 122205 61092 122205 61094 122205 61100 122206 61089 122206 61096 122206 61096 122207 61089 122207 61095 122207 61096 122208 61095 122208 61102 122208 61102 122209 61095 122209 61097 122209 61102 122210 61097 122210 61098 122210 61098 122211 61097 122211 61091 122211 61098 122212 61091 122212 61099 122212 61099 122213 61091 122213 61093 122213 61006 122214 61100 122214 61101 122214 61101 122215 61100 122215 61096 122215 61101 122216 61096 122216 61114 122216 61114 122217 61096 122217 61102 122217 61114 122218 61102 122218 61115 122218 61115 122219 61102 122219 61098 122219 61115 122220 61098 122220 59571 122220 59571 122221 61098 122221 61099 122221 60867 122222 61103 122222 61109 122222 61109 122223 61103 122223 61104 122223 61109 122224 61104 122224 61110 122224 61110 122225 61104 122225 61105 122225 61110 122226 61105 122226 61107 122226 61107 122227 61105 122227 61106 122227 61107 122228 61106 122228 59848 122228 59848 122229 61106 122229 61108 122229 60866 122230 60867 122230 61090 122230 61090 122231 60867 122231 61109 122231 61090 122232 61109 122232 61111 122232 61111 122233 61109 122233 61110 122233 61111 122234 61110 122234 61092 122234 61092 122235 61110 122235 61107 122235 61092 122236 61107 122236 61094 122236 61094 122237 61107 122237 59848 122237 61117 122238 61006 122238 61112 122238 61112 122239 61006 122239 61101 122239 61112 122240 61101 122240 61113 122240 61113 122241 61101 122241 61114 122241 61113 122242 61114 122242 61119 122242 61119 122243 61114 122243 61115 122243 61119 122244 61115 122244 61122 122244 61122 122245 61115 122245 59571 122245 61139 122246 61117 122246 61116 122246 61116 122247 61117 122247 61112 122247 61116 122248 61112 122248 61118 122248 61118 122249 61112 122249 61113 122249 61118 122250 61113 122250 61120 122250 61120 122251 61113 122251 61119 122251 61120 122252 61119 122252 61121 122252 61121 122253 61119 122253 61122 122253 61059 122254 61058 122254 61123 122254 61123 122255 61058 122255 61143 122255 61123 122256 61143 122256 61126 122256 61126 122257 61143 122257 61145 122257 61126 122258 61145 122258 61124 122258 61124 122259 61145 122259 61146 122259 61124 122260 61146 122260 61125 122260 61125 122261 61146 122261 61148 122261 61061 122262 61059 122262 61127 122262 61127 122263 61059 122263 61123 122263 61127 122264 61123 122264 61128 122264 61128 122265 61123 122265 61126 122265 61128 122266 61126 122266 61129 122266 61129 122267 61126 122267 61124 122267 61129 122268 61124 122268 59849 122268 59849 122269 61124 122269 61125 122269 61103 122270 61061 122270 61104 122270 61104 122271 61061 122271 61127 122271 61104 122272 61127 122272 61105 122272 61105 122273 61127 122273 61128 122273 61105 122274 61128 122274 61106 122274 61106 122275 61128 122275 61129 122275 61106 122276 61129 122276 61108 122276 61108 122277 61129 122277 59849 122277 61134 122278 61156 122278 61130 122278 61130 122279 61156 122279 61155 122279 61130 122280 61155 122280 61131 122280 61131 122281 61155 122281 61153 122281 61131 122282 61153 122282 61132 122282 61132 122283 61153 122283 61150 122283 61132 122284 61150 122284 61133 122284 61133 122285 61150 122285 61009 122285 61136 122286 61134 122286 61137 122286 61137 122287 61134 122287 61130 122287 61137 122288 61130 122288 61138 122288 61138 122289 61130 122289 61131 122289 61138 122290 61131 122290 61135 122290 61135 122291 61131 122291 61132 122291 61135 122292 61132 122292 61049 122292 61049 122293 61132 122293 61133 122293 61121 122294 61136 122294 61120 122294 61120 122295 61136 122295 61137 122295 61120 122296 61137 122296 61118 122296 61118 122297 61137 122297 61138 122297 61118 122298 61138 122298 61116 122298 61116 122299 61138 122299 61135 122299 61116 122300 61135 122300 61139 122300 61139 122301 61135 122301 61049 122301 61140 122302 61023 122302 61144 122302 61144 122303 61023 122303 61141 122303 61144 122304 61141 122304 61147 122304 61147 122305 61141 122305 61161 122305 61147 122306 61161 122306 61149 122306 61149 122307 61161 122307 61142 122307 61149 122308 61142 122308 59680 122308 59680 122309 61142 122309 59681 122309 61058 122310 61140 122310 61143 122310 61143 122311 61140 122311 61144 122311 61143 122312 61144 122312 61145 122312 61145 122313 61144 122313 61147 122313 61145 122314 61147 122314 61146 122314 61146 122315 61147 122315 61149 122315 61146 122316 61149 122316 61148 122316 61148 122317 61149 122317 59680 122317 61157 122318 61009 122318 61151 122318 61151 122319 61009 122319 61150 122319 61151 122320 61150 122320 61152 122320 61152 122321 61150 122321 61153 122321 61152 122322 61153 122322 61154 122322 61154 122323 61153 122323 61155 122323 61154 122324 61155 122324 61159 122324 61159 122325 61155 122325 61156 122325 61011 122326 61157 122326 61172 122326 61172 122327 61157 122327 61151 122327 61172 122328 61151 122328 61173 122328 61173 122329 61151 122329 61152 122329 61173 122330 61152 122330 61158 122330 61158 122331 61152 122331 61154 122331 61158 122332 61154 122332 59570 122332 59570 122333 61154 122333 61159 122333 59682 122334 59681 122334 61163 122334 61163 122335 59681 122335 61142 122335 61163 122336 61142 122336 61160 122336 61160 122337 61142 122337 61161 122337 61160 122338 61161 122338 61162 122338 61162 122339 61161 122339 61141 122339 61162 122340 61141 122340 61041 122340 61041 122341 61141 122341 61023 122341 59683 122342 59682 122342 61166 122342 61166 122343 59682 122343 61163 122343 61166 122344 61163 122344 61168 122344 61168 122345 61163 122345 61160 122345 61168 122346 61160 122346 61164 122346 61164 122347 61160 122347 61162 122347 61164 122348 61162 122348 61040 122348 61040 122349 61162 122349 61041 122349 59684 122350 59683 122350 61165 122350 61165 122351 59683 122351 61166 122351 61165 122352 61166 122352 61167 122352 61167 122353 61166 122353 61168 122353 61167 122354 61168 122354 61169 122354 61169 122355 61168 122355 61164 122355 61169 122356 61164 122356 61192 122356 61192 122357 61164 122357 61040 122357 60917 122358 61181 122358 61178 122358 61176 122359 61011 122359 61170 122359 61170 122360 61011 122360 61172 122360 61170 122361 61172 122361 61171 122361 61171 122362 61172 122362 61173 122362 61171 122363 61173 122363 61174 122363 61174 122364 61173 122364 61158 122364 61174 122365 61158 122365 61175 122365 61175 122366 61158 122366 59570 122366 61013 122367 61176 122367 61179 122367 61179 122368 61176 122368 61170 122368 61179 122369 61170 122369 61177 122369 61177 122370 61170 122370 61171 122370 61177 122371 61171 122371 61178 122371 61178 122372 61171 122372 61174 122372 61178 122373 61174 122373 60917 122373 60917 122374 61174 122374 61175 122374 61183 122375 61013 122375 61184 122375 61184 122376 61013 122376 61179 122376 61184 122377 61179 122377 61185 122377 61185 122378 61179 122378 61177 122378 61185 122379 61177 122379 61180 122379 61180 122380 61177 122380 61178 122380 61180 122381 61178 122381 61188 122381 61188 122382 61178 122382 61181 122382 61068 122383 61183 122383 61182 122383 61182 122384 61183 122384 61184 122384 61182 122385 61184 122385 61197 122385 61197 122386 61184 122386 61185 122386 61197 122387 61185 122387 61186 122387 61186 122388 61185 122388 61180 122388 61186 122389 61180 122389 61187 122389 61187 122390 61180 122390 61188 122390 61193 122391 61029 122391 61190 122391 61190 122392 61029 122392 61189 122392 61190 122393 61189 122393 61191 122393 61191 122394 61189 122394 61217 122394 61191 122395 61217 122395 61194 122395 61194 122396 61217 122396 61218 122396 61194 122397 61218 122397 59687 122397 59687 122398 61218 122398 61219 122398 61192 122399 61193 122399 61169 122399 61169 122400 61193 122400 61190 122400 61169 122401 61190 122401 61167 122401 61167 122402 61190 122402 61191 122402 61167 122403 61191 122403 61165 122403 61165 122404 61191 122404 61194 122404 61165 122405 61194 122405 59684 122405 59684 122406 61194 122406 59687 122406 61195 122407 61068 122407 61196 122407 61196 122408 61068 122408 61182 122408 61196 122409 61182 122409 61198 122409 61198 122410 61182 122410 61197 122410 61198 122411 61197 122411 61199 122411 61199 122412 61197 122412 61186 122412 61199 122413 61186 122413 61202 122413 61202 122414 61186 122414 61187 122414 61070 122415 61195 122415 61220 122415 61220 122416 61195 122416 61196 122416 61220 122417 61196 122417 61222 122417 61222 122418 61196 122418 61198 122418 61222 122419 61198 122419 61200 122419 61200 122420 61198 122420 61199 122420 61200 122421 61199 122421 61201 122421 61201 122422 61199 122422 61202 122422 61215 122423 60768 122423 61203 122423 61209 122424 61235 122424 61204 122424 61204 122425 61235 122425 61237 122425 61204 122426 61237 122426 61205 122426 61205 122427 61237 122427 61238 122427 61205 122428 61238 122428 61206 122428 61206 122429 61238 122429 61207 122429 61206 122430 61207 122430 61208 122430 61208 122431 61207 122431 61240 122431 61026 122432 61209 122432 61210 122432 61210 122433 61209 122433 61204 122433 61210 122434 61204 122434 61214 122434 61214 122435 61204 122435 61205 122435 61214 122436 61205 122436 61211 122436 61211 122437 61205 122437 61206 122437 61211 122438 61206 122438 60863 122438 60863 122439 61206 122439 61208 122439 61216 122440 61026 122440 61212 122440 61212 122441 61026 122441 61210 122441 61212 122442 61210 122442 61213 122442 61213 122443 61210 122443 61214 122443 61213 122444 61214 122444 61203 122444 61203 122445 61214 122445 61211 122445 61203 122446 61211 122446 61215 122446 61215 122447 61211 122447 60863 122447 61029 122448 61216 122448 61189 122448 61189 122449 61216 122449 61212 122449 61189 122450 61212 122450 61217 122450 61217 122451 61212 122451 61213 122451 61217 122452 61213 122452 61218 122452 61218 122453 61213 122453 61203 122453 61218 122454 61203 122454 61219 122454 61219 122455 61203 122455 60768 122455 61075 122456 61073 122456 61224 122456 61072 122457 61070 122457 61220 122457 61073 122458 61072 122458 61224 122458 61224 122459 61072 122459 61220 122459 61224 122460 61220 122460 61221 122460 61221 122461 61220 122461 61222 122461 61221 122462 61222 122462 61227 122462 61227 122463 61222 122463 61200 122463 61227 122464 61200 122464 61223 122464 61223 122465 61200 122465 61201 122465 61231 122466 61075 122466 61225 122466 61225 122467 61075 122467 61224 122467 61225 122468 61224 122468 61230 122468 61230 122469 61224 122469 61221 122469 61230 122470 61221 122470 61226 122470 61226 122471 61221 122471 61227 122471 61226 122472 61227 122472 61228 122472 61228 122473 61227 122473 61223 122473 61228 122474 60897 122474 61226 122474 61226 122475 60897 122475 61229 122475 61226 122476 61229 122476 61230 122476 61230 122477 61229 122477 61272 122477 61230 122478 61272 122478 61225 122478 61225 122479 61272 122479 61271 122479 61225 122480 61271 122480 61231 122480 61231 122481 61271 122481 60709 122481 61236 122482 61066 122482 61233 122482 61233 122483 61066 122483 61232 122483 61233 122484 61232 122484 61239 122484 61239 122485 61232 122485 61301 122485 61239 122486 61301 122486 61234 122486 61234 122487 61301 122487 61303 122487 61234 122488 61303 122488 60764 122488 60764 122489 61303 122489 61304 122489 61235 122490 61236 122490 61237 122490 61237 122491 61236 122491 61233 122491 61237 122492 61233 122492 61238 122492 61238 122493 61233 122493 61239 122493 61238 122494 61239 122494 61207 122494 61207 122495 61239 122495 61234 122495 61207 122496 61234 122496 61240 122496 61240 122497 61234 122497 60764 122497 61241 122498 61243 122498 61242 122498 61243 122499 61084 122499 61244 122499 60692 122500 61248 122500 61245 122500 61243 122501 61244 122501 61242 122501 61242 122502 61244 122502 60689 122502 61242 122503 60689 122503 61245 122503 61245 122504 60689 122504 60691 122504 61245 122505 60691 122505 60692 122505 61246 122506 61252 122506 61262 122506 60692 122507 61247 122507 61248 122507 61248 122508 61247 122508 61249 122508 61248 122509 61249 122509 61250 122509 61250 122510 61249 122510 61251 122510 61250 122511 61251 122511 61262 122511 61262 122512 61251 122512 60695 122512 61262 122513 60695 122513 61246 122513 60701 122514 61256 122514 61265 122514 61246 122515 60698 122515 61252 122515 61252 122516 60698 122516 60699 122516 61252 122517 60699 122517 61254 122517 61254 122518 60699 122518 61253 122518 61254 122519 61253 122519 61264 122519 61264 122520 61253 122520 60700 122520 61264 122521 60700 122521 61265 122521 61265 122522 60700 122522 61255 122522 61265 122523 61255 122523 60701 122523 60706 122524 61270 122524 61257 122524 60701 122525 60702 122525 61256 122525 61256 122526 60702 122526 60704 122526 61256 122527 60704 122527 61268 122527 61268 122528 60704 122528 60705 122528 61268 122529 60705 122529 61257 122529 61257 122530 60705 122530 61258 122530 61257 122531 61258 122531 60706 122531 60706 122532 60708 122532 61270 122532 61270 122533 60708 122533 60709 122533 61270 122534 60709 122534 61271 122534 61259 122535 61317 122535 61260 122535 61260 122536 61317 122536 61241 122536 61241 122537 61242 122537 61260 122537 61260 122538 61242 122538 61245 122538 61260 122539 61245 122539 61274 122539 61274 122540 61245 122540 61248 122540 61274 122541 61248 122541 61276 122541 61276 122542 61248 122542 61250 122542 61276 122543 61250 122543 61261 122543 61261 122544 61250 122544 61262 122544 61261 122545 61262 122545 61277 122545 61277 122546 61262 122546 61252 122546 61277 122547 61252 122547 61263 122547 61263 122548 61252 122548 61254 122548 61263 122549 61254 122549 61279 122549 61279 122550 61254 122550 61264 122550 61279 122551 61264 122551 61280 122551 61280 122552 61264 122552 61265 122552 61280 122553 61265 122553 61266 122553 61266 122554 61265 122554 61256 122554 61266 122555 61256 122555 61267 122555 61267 122556 61256 122556 61268 122556 61267 122557 61268 122557 61269 122557 61269 122558 61268 122558 61257 122558 61269 122559 61257 122559 61286 122559 61286 122560 61257 122560 61270 122560 61286 122561 61270 122561 61287 122561 61287 122562 61270 122562 61271 122562 61287 122563 61271 122563 61272 122563 61289 122564 61315 122564 61273 122564 61273 122565 61315 122565 61259 122565 61259 122566 61260 122566 61273 122566 61273 122567 61260 122567 61274 122567 61273 122568 61274 122568 61275 122568 61275 122569 61274 122569 61276 122569 61275 122570 61276 122570 61290 122570 61290 122571 61276 122571 61261 122571 61290 122572 61261 122572 61291 122572 61291 122573 61261 122573 61277 122573 61291 122574 61277 122574 61278 122574 61278 122575 61277 122575 61263 122575 61278 122576 61263 122576 61294 122576 61294 122577 61263 122577 61279 122577 61294 122578 61279 122578 61295 122578 61295 122579 61279 122579 61280 122579 61295 122580 61280 122580 61281 122580 61281 122581 61280 122581 61266 122581 61281 122582 61266 122582 61282 122582 61282 122583 61266 122583 61267 122583 61282 122584 61267 122584 61283 122584 61283 122585 61267 122585 61269 122585 61283 122586 61269 122586 61284 122586 61284 122587 61269 122587 61286 122587 61284 122588 61286 122588 61285 122588 61285 122589 61286 122589 61287 122589 61285 122590 61287 122590 61288 122590 61288 122591 61287 122591 61272 122591 61288 122592 61272 122592 61229 122592 61289 122593 61273 122593 60892 122593 60892 122594 61273 122594 61275 122594 60892 122595 61275 122595 60893 122595 60893 122596 61275 122596 61290 122596 60893 122597 61290 122597 60898 122597 60898 122598 61290 122598 61291 122598 60898 122599 61291 122599 61292 122599 61292 122600 61291 122600 61278 122600 61292 122601 61278 122601 61293 122601 61293 122602 61278 122602 61294 122602 61293 122603 61294 122603 60902 122603 60902 122604 61294 122604 61295 122604 60902 122605 61295 122605 60901 122605 60901 122606 61295 122606 61281 122606 60901 122607 61281 122607 61296 122607 61296 122608 61281 122608 61282 122608 61296 122609 61282 122609 61297 122609 61297 122610 61282 122610 61283 122610 61297 122611 61283 122611 61298 122611 61298 122612 61283 122612 61284 122612 61298 122613 61284 122613 60912 122613 60912 122614 61284 122614 61285 122614 60912 122615 61285 122615 61299 122615 61299 122616 61285 122616 61288 122616 61299 122617 61288 122617 61300 122617 61300 122618 61288 122618 61229 122618 61300 122619 61229 122619 60897 122619 61066 122620 61067 122620 61232 122620 61232 122621 61067 122621 61305 122621 61232 122622 61305 122622 61301 122622 61301 122623 61305 122623 61302 122623 61301 122624 61302 122624 61303 122624 61303 122625 61302 122625 61306 122625 61303 122626 61306 122626 61304 122626 61304 122627 61306 122627 60751 122627 61067 122628 61063 122628 61305 122628 61305 122629 61063 122629 61308 122629 61305 122630 61308 122630 61302 122630 61302 122631 61308 122631 61311 122631 61302 122632 61311 122632 61306 122632 61306 122633 61311 122633 61307 122633 61306 122634 61307 122634 60751 122634 60751 122635 61307 122635 61312 122635 61063 122636 61378 122636 61308 122636 61308 122637 61378 122637 61309 122637 61308 122638 61309 122638 61311 122638 61311 122639 61309 122639 61310 122639 61311 122640 61310 122640 61307 122640 61307 122641 61310 122641 61376 122641 61307 122642 61376 122642 61312 122642 61312 122643 61376 122643 60753 122643 61313 122644 60890 122644 60889 122644 61243 122645 61241 122645 61314 122645 61289 122646 60890 122646 61315 122646 61315 122647 60890 122647 61313 122647 61315 122648 61313 122648 61259 122648 61259 122649 61313 122649 61317 122649 61322 122650 61084 122650 61243 122650 61316 122651 61319 122651 61314 122651 60888 122652 61380 122652 60889 122652 60889 122653 61380 122653 61316 122653 60889 122654 61316 122654 61313 122654 61313 122655 61316 122655 61314 122655 61313 122656 61314 122656 61317 122656 61317 122657 61314 122657 61241 122657 61380 122658 61318 122658 61316 122658 61316 122659 61318 122659 61383 122659 61316 122660 61383 122660 61319 122660 61319 122661 61383 122661 61320 122661 61319 122662 61320 122662 61321 122662 61243 122663 61314 122663 61322 122663 61322 122664 61314 122664 61319 122664 61322 122665 61319 122665 61323 122665 61323 122666 61319 122666 61321 122666 61323 122667 61321 122667 61379 122667 60684 122668 60683 122668 61372 122668 61324 122669 61325 122669 61326 122669 60679 122670 60678 122670 61363 122670 60665 122671 60664 122671 61350 122671 61346 122672 61340 122672 61345 122672 61327 122673 61329 122673 61328 122673 60741 122674 61329 122674 61333 122674 61333 122675 61329 122675 61327 122675 61333 122676 61327 122676 61354 122676 61343 122677 61342 122677 61394 122677 60738 122678 60739 122678 61330 122678 61330 122679 60739 122679 61343 122679 61330 122680 61343 122680 61331 122680 61331 122681 61343 122681 61394 122681 60740 122682 60741 122682 61332 122682 61332 122683 60741 122683 61333 122683 61332 122684 61333 122684 61353 122684 61353 122685 61333 122685 61354 122685 61353 122686 61354 122686 61355 122686 61336 122687 61334 122687 61335 122687 61357 122688 61334 122688 61339 122688 61339 122689 61334 122689 61336 122689 61339 122690 61336 122690 61338 122690 61328 122691 60761 122691 61338 122691 61338 122692 60761 122692 61337 122692 61338 122693 61337 122693 61339 122693 61339 122694 61337 122694 61362 122694 61339 122695 61362 122695 61357 122695 61357 122696 61362 122696 61356 122696 61340 122697 61082 122697 61345 122697 61345 122698 61082 122698 61341 122698 61345 122699 61341 122699 61342 122699 61342 122700 61341 122700 61390 122700 61342 122701 61390 122701 61394 122701 60739 122702 60746 122702 61343 122702 61343 122703 60746 122703 61344 122703 61343 122704 61344 122704 61342 122704 61342 122705 61344 122705 61351 122705 61342 122706 61351 122706 61345 122706 61345 122707 61351 122707 61350 122707 61345 122708 61350 122708 61346 122708 61346 122709 61350 122709 60664 122709 61347 122710 60665 122710 61348 122710 61348 122711 60665 122711 61350 122711 61348 122712 61350 122712 61349 122712 61349 122713 61350 122713 61351 122713 61349 122714 61351 122714 61352 122714 61352 122715 61351 122715 61344 122715 61352 122716 61344 122716 60747 122716 60747 122717 61344 122717 60746 122717 60747 122718 60740 122718 61352 122718 61352 122719 60740 122719 61332 122719 61352 122720 61332 122720 61349 122720 61349 122721 61332 122721 61353 122721 61349 122722 61353 122722 61348 122722 61348 122723 61353 122723 61355 122723 61348 122724 61355 122724 61347 122724 61347 122725 61355 122725 60668 122725 61328 122726 61338 122726 61327 122726 61327 122727 61338 122727 61336 122727 61327 122728 61336 122728 61354 122728 61354 122729 61336 122729 61335 122729 61354 122730 61335 122730 61355 122730 61355 122731 61335 122731 61360 122731 61355 122732 61360 122732 60668 122732 60676 122733 60675 122733 61356 122733 61356 122734 60675 122734 60672 122734 61356 122735 60672 122735 61357 122735 61357 122736 60672 122736 61358 122736 61357 122737 61358 122737 61334 122737 61334 122738 61358 122738 61359 122738 61334 122739 61359 122739 61335 122739 61335 122740 61359 122740 60669 122740 61335 122741 60669 122741 61360 122741 60761 122742 60763 122742 61337 122742 61337 122743 60763 122743 61361 122743 61337 122744 61361 122744 61362 122744 61362 122745 61361 122745 61366 122745 61362 122746 61366 122746 61356 122746 61356 122747 61366 122747 61363 122747 61356 122748 61363 122748 60676 122748 60676 122749 61363 122749 60678 122749 60681 122750 60679 122750 61364 122750 61364 122751 60679 122751 61363 122751 61364 122752 61363 122752 61365 122752 61365 122753 61363 122753 61366 122753 61365 122754 61366 122754 61367 122754 61367 122755 61366 122755 61361 122755 61367 122756 61361 122756 61368 122756 61368 122757 61361 122757 60763 122757 61368 122758 60744 122758 61367 122758 61367 122759 60744 122759 61369 122759 61367 122760 61369 122760 61365 122760 61365 122761 61369 122761 61370 122761 61365 122762 61370 122762 61364 122762 61364 122763 61370 122763 61326 122763 61364 122764 61326 122764 60681 122764 60681 122765 61326 122765 61325 122765 60744 122766 60743 122766 61369 122766 61369 122767 60743 122767 61371 122767 61369 122768 61371 122768 61370 122768 61370 122769 61371 122769 61373 122769 61370 122770 61373 122770 61326 122770 61326 122771 61373 122771 61372 122771 61326 122772 61372 122772 61324 122772 61324 122773 61372 122773 60683 122773 60686 122774 60684 122774 61377 122774 61377 122775 60684 122775 61372 122775 61377 122776 61372 122776 61375 122776 61375 122777 61372 122777 61373 122777 61375 122778 61373 122778 61374 122778 61374 122779 61373 122779 61371 122779 61374 122780 61371 122780 60756 122780 60756 122781 61371 122781 60743 122781 60756 122782 60753 122782 61374 122782 61374 122783 60753 122783 61376 122783 61374 122784 61376 122784 61375 122784 61375 122785 61376 122785 61310 122785 61375 122786 61310 122786 61377 122786 61377 122787 61310 122787 61309 122787 61377 122788 61309 122788 60686 122788 60686 122789 61309 122789 61378 122789 61385 122790 61085 122790 61379 122790 60888 122791 61381 122791 61380 122791 61380 122792 61381 122792 61388 122792 61380 122793 61388 122793 61318 122793 61318 122794 61388 122794 61382 122794 61379 122795 61321 122795 61385 122795 61385 122796 61321 122796 61320 122796 61385 122797 61320 122797 61382 122797 61382 122798 61320 122798 61383 122798 61382 122799 61383 122799 61318 122799 61404 122800 61085 122800 61384 122800 61384 122801 61085 122801 61385 122801 61384 122802 61385 122802 61386 122802 61386 122803 61385 122803 61382 122803 61386 122804 61382 122804 61387 122804 61387 122805 61382 122805 61388 122805 61387 122806 61388 122806 61403 122806 61403 122807 61388 122807 61381 122807 61393 122808 61389 122808 61079 122808 61330 122809 61331 122809 61399 122809 61082 122810 61389 122810 61341 122810 61341 122811 61389 122811 61393 122811 61341 122812 61393 122812 61390 122812 61390 122813 61393 122813 61394 122813 60736 122814 60738 122814 61330 122814 61392 122815 61397 122815 61399 122815 61391 122816 61425 122816 61079 122816 61079 122817 61425 122817 61392 122817 61079 122818 61392 122818 61393 122818 61393 122819 61392 122819 61399 122819 61393 122820 61399 122820 61394 122820 61394 122821 61399 122821 61331 122821 61425 122822 61395 122822 61392 122822 61392 122823 61395 122823 61396 122823 61392 122824 61396 122824 61397 122824 61397 122825 61396 122825 61423 122825 61397 122826 61423 122826 61398 122826 61330 122827 61399 122827 60736 122827 60736 122828 61399 122828 61397 122828 60736 122829 61397 122829 61400 122829 61400 122830 61397 122830 61398 122830 61400 122831 61398 122831 60735 122831 60916 122832 61401 122832 61414 122832 61402 122833 61410 122833 61406 122833 61402 122834 61406 122834 61403 122834 61019 122835 61404 122835 61408 122835 61408 122836 61404 122836 61384 122836 61408 122837 61384 122837 61405 122837 61405 122838 61384 122838 61386 122838 61405 122839 61386 122839 61406 122839 61406 122840 61386 122840 61387 122840 61406 122841 61387 122841 61403 122841 61412 122842 61019 122842 61407 122842 61407 122843 61019 122843 61408 122843 61407 122844 61408 122844 61413 122844 61413 122845 61408 122845 61405 122845 61413 122846 61405 122846 61409 122846 61409 122847 61405 122847 61406 122847 61409 122848 61406 122848 60914 122848 60914 122849 61406 122849 61410 122849 61021 122850 61412 122850 61411 122850 61411 122851 61412 122851 61407 122851 61411 122852 61407 122852 61416 122852 61416 122853 61407 122853 61413 122853 61416 122854 61413 122854 61414 122854 61414 122855 61413 122855 61409 122855 61414 122856 61409 122856 60916 122856 60916 122857 61409 122857 60914 122857 61426 122858 61021 122858 61428 122858 61428 122859 61021 122859 61411 122859 61428 122860 61411 122860 61415 122860 61415 122861 61411 122861 61416 122861 61415 122862 61416 122862 61431 122862 61431 122863 61416 122863 61414 122863 61431 122864 61414 122864 61417 122864 61417 122865 61414 122865 61401 122865 61422 122866 60836 122866 60765 122866 61418 122867 61422 122867 61419 122867 61424 122868 61077 122868 61420 122868 61420 122869 61077 122869 61449 122869 61420 122870 61449 122870 61421 122870 61422 122871 60765 122871 61419 122871 61419 122872 60765 122872 60735 122872 61419 122873 60735 122873 61398 122873 61398 122874 61423 122874 61419 122874 61419 122875 61423 122875 61421 122875 61419 122876 61421 122876 61418 122876 61418 122877 61421 122877 61449 122877 61391 122878 61424 122878 61425 122878 61425 122879 61424 122879 61420 122879 61425 122880 61420 122880 61395 122880 61395 122881 61420 122881 61421 122881 61395 122882 61421 122882 61396 122882 61396 122883 61421 122883 61423 122883 61434 122884 61426 122884 61427 122884 61427 122885 61426 122885 61428 122885 61427 122886 61428 122886 61429 122886 61429 122887 61428 122887 61415 122887 61429 122888 61415 122888 61430 122888 61430 122889 61415 122889 61431 122889 61430 122890 61431 122890 61436 122890 61436 122891 61431 122891 61417 122891 61432 122892 61434 122892 61433 122892 61433 122893 61434 122893 61427 122893 61433 122894 61427 122894 61435 122894 61435 122895 61427 122895 61429 122895 61435 122896 61429 122896 61460 122896 61460 122897 61429 122897 61430 122897 61460 122898 61430 122898 59626 122898 59626 122899 61430 122899 61436 122899 60767 122900 61437 122900 61448 122900 61035 122901 61438 122901 61442 122901 61442 122902 61438 122902 61440 122902 61442 122903 61440 122903 61439 122903 61439 122904 61440 122904 61468 122904 61439 122905 61468 122905 61443 122905 61443 122906 61468 122906 61470 122906 61443 122907 61470 122907 61441 122907 61441 122908 61470 122908 61471 122908 61036 122909 61035 122909 61445 122909 61445 122910 61035 122910 61442 122910 61445 122911 61442 122911 61446 122911 61446 122912 61442 122912 61439 122912 61446 122913 61439 122913 61448 122913 61448 122914 61439 122914 61443 122914 61448 122915 61443 122915 60767 122915 60767 122916 61443 122916 61441 122916 61037 122917 61036 122917 61444 122917 61444 122918 61036 122918 61445 122918 61444 122919 61445 122919 61450 122919 61450 122920 61445 122920 61446 122920 61450 122921 61446 122921 61451 122921 61451 122922 61446 122922 61448 122922 61451 122923 61448 122923 61447 122923 61447 122924 61448 122924 61437 122924 61077 122925 61037 122925 61449 122925 61449 122926 61037 122926 61444 122926 61449 122927 61444 122927 61418 122927 61418 122928 61444 122928 61450 122928 61418 122929 61450 122929 61422 122929 61422 122930 61450 122930 61451 122930 61422 122931 61451 122931 60836 122931 60836 122932 61451 122932 61447 122932 59624 122933 61452 122933 61455 122933 61455 122934 61452 122934 61475 122934 61455 122935 61475 122935 61456 122935 61456 122936 61475 122936 61473 122936 61456 122937 61473 122937 61458 122937 61458 122938 61473 122938 61453 122938 61458 122939 61453 122939 61459 122939 61459 122940 61453 122940 61016 122940 61454 122941 59624 122941 61461 122941 61461 122942 59624 122942 61455 122942 61461 122943 61455 122943 61462 122943 61462 122944 61455 122944 61456 122944 61462 122945 61456 122945 61463 122945 61463 122946 61456 122946 61458 122946 61463 122947 61458 122947 61457 122947 61457 122948 61458 122948 61459 122948 59626 122949 61454 122949 61460 122949 61460 122950 61454 122950 61461 122950 61460 122951 61461 122951 61435 122951 61435 122952 61461 122952 61462 122952 61435 122953 61462 122953 61433 122953 61433 122954 61462 122954 61463 122954 61433 122955 61463 122955 61432 122955 61432 122956 61463 122956 61457 122956 61033 122957 61044 122957 61464 122957 61464 122958 61044 122958 61486 122958 61464 122959 61486 122959 61469 122959 61469 122960 61486 122960 61483 122960 61469 122961 61483 122961 61465 122961 61465 122962 61483 122962 61466 122962 61465 122963 61466 122963 61467 122963 61467 122964 61466 122964 61482 122964 61438 122965 61033 122965 61440 122965 61440 122966 61033 122966 61464 122966 61440 122967 61464 122967 61468 122967 61468 122968 61464 122968 61469 122968 61468 122969 61469 122969 61470 122969 61470 122970 61469 122970 61465 122970 61470 122971 61465 122971 61471 122971 61471 122972 61465 122972 61467 122972 61477 122973 61016 122973 61479 122973 61479 122974 61016 122974 61453 122974 61479 122975 61453 122975 61472 122975 61472 122976 61453 122976 61473 122976 61472 122977 61473 122977 61481 122977 61481 122978 61473 122978 61475 122978 61481 122979 61475 122979 61474 122979 61474 122980 61475 122980 61452 122980 61476 122981 61477 122981 61478 122981 61478 122982 61477 122982 61479 122982 61478 122983 61479 122983 61496 122983 61496 122984 61479 122984 61472 122984 61496 122985 61472 122985 61480 122985 61480 122986 61472 122986 61481 122986 61480 122987 61481 122987 59625 122987 59625 122988 61481 122988 61474 122988 59628 122989 61482 122989 61488 122989 61488 122990 61482 122990 61466 122990 61488 122991 61466 122991 61484 122991 61484 122992 61466 122992 61483 122992 61484 122993 61483 122993 61485 122993 61485 122994 61483 122994 61486 122994 61485 122995 61486 122995 61046 122995 61046 122996 61486 122996 61044 122996 61490 122997 59628 122997 61487 122997 61487 122998 59628 122998 61488 122998 61487 122999 61488 122999 61492 122999 61492 123000 61488 123000 61484 123000 61492 123001 61484 123001 61489 123001 61489 123002 61484 123002 61485 123002 61489 123003 61485 123003 61494 123003 61494 123004 61485 123004 61046 123004 61516 123005 61490 123005 61491 123005 61491 123006 61490 123006 61487 123006 61491 123007 61487 123007 61515 123007 61515 123008 61487 123008 61492 123008 61515 123009 61492 123009 61493 123009 61493 123010 61492 123010 61489 123010 61493 123011 61489 123011 61043 123011 61043 123012 61489 123012 61494 123012 61498 123013 61476 123013 61495 123013 61495 123014 61476 123014 61478 123014 61495 123015 61478 123015 61501 123015 61501 123016 61478 123016 61496 123016 61501 123017 61496 123017 61502 123017 61502 123018 61496 123018 61480 123018 61502 123019 61480 123019 61497 123019 61497 123020 61480 123020 59625 123020 61503 123021 61498 123021 61504 123021 61504 123022 61498 123022 61495 123022 61504 123023 61495 123023 61499 123023 61499 123024 61495 123024 61501 123024 61499 123025 61501 123025 61500 123025 61500 123026 61501 123026 61502 123026 61500 123027 61502 123027 61507 123027 61507 123028 61502 123028 61497 123028 60885 123029 61503 123029 61505 123029 61505 123030 61503 123030 61504 123030 61505 123031 61504 123031 61520 123031 61520 123032 61504 123032 61499 123032 61520 123033 61499 123033 61506 123033 61506 123034 61499 123034 61500 123034 61506 123035 61500 123035 59627 123035 59627 123036 61500 123036 61507 123036 61513 123037 61508 123037 61509 123037 61509 123038 61508 123038 61510 123038 61509 123039 61510 123039 61514 123039 61514 123040 61510 123040 61511 123040 61514 123041 61511 123041 61517 123041 61517 123042 61511 123042 61532 123042 61517 123043 61532 123043 61512 123043 61512 123044 61532 123044 61533 123044 61043 123045 61513 123045 61493 123045 61493 123046 61513 123046 61509 123046 61493 123047 61509 123047 61515 123047 61515 123048 61509 123048 61514 123048 61515 123049 61514 123049 61491 123049 61491 123050 61514 123050 61517 123050 61491 123051 61517 123051 61516 123051 61516 123052 61517 123052 61512 123052 61522 123053 60885 123053 61518 123053 61518 123054 60885 123054 61505 123054 61518 123055 61505 123055 61519 123055 61519 123056 61505 123056 61520 123056 61519 123057 61520 123057 61524 123057 61524 123058 61520 123058 61506 123058 61524 123059 61506 123059 59859 123059 59859 123060 61506 123060 59627 123060 61052 123061 61522 123061 61521 123061 61521 123062 61522 123062 61518 123062 61521 123063 61518 123063 61523 123063 61523 123064 61518 123064 61519 123064 61523 123065 61519 123065 61526 123065 61526 123066 61519 123066 61524 123066 61526 123067 61524 123067 59860 123067 59860 123068 61524 123068 59859 123068 61054 123069 61052 123069 61525 123069 61525 123070 61052 123070 61521 123070 61525 123071 61521 123071 61528 123071 61528 123072 61521 123072 61523 123072 61528 123073 61523 123073 61530 123073 61530 123074 61523 123074 61526 123074 61530 123075 61526 123075 59631 123075 59631 123076 61526 123076 59860 123076 61055 123077 61054 123077 61531 123077 61531 123078 61054 123078 61525 123078 61531 123079 61525 123079 61527 123079 61527 123080 61525 123080 61528 123080 61527 123081 61528 123081 61529 123081 61529 123082 61528 123082 61530 123082 61529 123083 61530 123083 59630 123083 59630 123084 61530 123084 59631 123084 61508 123085 61055 123085 61510 123085 61510 123086 61055 123086 61531 123086 61510 123087 61531 123087 61511 123087 61511 123088 61531 123088 61527 123088 61511 123089 61527 123089 61532 123089 61532 123090 61527 123090 61529 123090 61532 123091 61529 123091 61533 123091 61533 123092 61529 123092 59630 123092 61537 123093 61554 123093 61538 123093 61538 123094 61554 123094 61534 123094 61538 123095 61534 123095 61541 123095 61541 123096 61534 123096 61535 123096 61541 123097 61535 123097 61051 123097 61051 123098 61535 123098 61551 123098 60273 123099 61537 123099 61536 123099 61536 123100 61537 123100 61538 123100 61536 123101 61538 123101 61539 123101 61539 123102 61538 123102 61541 123102 61539 123103 61541 123103 61540 123103 61540 123104 61541 123104 61051 123104 61548 123105 60273 123105 61542 123105 61542 123106 60273 123106 61536 123106 61542 123107 61536 123107 61543 123107 61543 123108 61536 123108 61539 123108 61543 123109 61539 123109 61005 123109 61005 123110 61539 123110 61540 123110 61547 123111 61544 123111 61545 123111 61545 123112 61544 123112 61561 123112 61545 123113 61561 123113 61546 123113 61546 123114 61561 123114 61562 123114 61546 123115 61562 123115 61549 123115 61549 123116 61562 123116 60272 123116 61005 123117 61547 123117 61543 123117 61543 123118 61547 123118 61545 123118 61543 123119 61545 123119 61542 123119 61542 123120 61545 123120 61546 123120 61542 123121 61546 123121 61548 123121 61548 123122 61546 123122 61549 123122 61550 123123 61551 123123 61555 123123 61555 123124 61551 123124 61535 123124 61555 123125 61535 123125 61552 123125 61552 123126 61535 123126 61534 123126 61552 123127 61534 123127 61553 123127 61553 123128 61534 123128 61554 123128 61572 123129 61550 123129 61571 123129 61571 123130 61550 123130 61555 123130 61571 123131 61555 123131 61570 123131 61570 123132 61555 123132 61552 123132 61570 123133 61552 123133 60395 123133 60395 123134 61552 123134 61553 123134 61559 123135 61007 123135 61556 123135 61556 123136 61007 123136 61579 123136 61556 123137 61579 123137 61557 123137 61557 123138 61579 123138 61581 123138 61557 123139 61581 123139 61558 123139 61558 123140 61581 123140 60271 123140 61050 123141 61559 123141 61560 123141 61560 123142 61559 123142 61556 123142 61560 123143 61556 123143 61563 123143 61563 123144 61556 123144 61557 123144 61563 123145 61557 123145 61564 123145 61564 123146 61557 123146 61558 123146 61544 123147 61050 123147 61561 123147 61561 123148 61050 123148 61560 123148 61561 123149 61560 123149 61562 123149 61562 123150 61560 123150 61563 123150 61562 123151 61563 123151 60272 123151 60272 123152 61563 123152 61564 123152 60396 123153 61565 123153 61566 123153 61566 123154 61565 123154 61584 123154 61566 123155 61584 123155 61567 123155 61567 123156 61584 123156 61583 123156 61567 123157 61583 123157 61569 123157 61569 123158 61583 123158 61057 123158 60397 123159 60396 123159 61568 123159 61568 123160 60396 123160 61566 123160 61568 123161 61566 123161 61573 123161 61573 123162 61566 123162 61567 123162 61573 123163 61567 123163 61060 123163 61060 123164 61567 123164 61569 123164 60395 123165 60397 123165 61570 123165 61570 123166 60397 123166 61568 123166 61570 123167 61568 123167 61571 123167 61571 123168 61568 123168 61573 123168 61571 123169 61573 123169 61572 123169 61572 123170 61573 123170 61060 123170 61576 123171 61574 123171 61575 123171 61008 123172 61010 123172 61580 123172 61580 123173 61010 123173 61596 123173 61580 123174 61596 123174 61575 123174 61575 123175 61596 123175 61577 123175 61575 123176 61577 123176 61576 123176 61576 123177 61577 123177 61578 123177 61007 123178 61008 123178 61579 123178 61579 123179 61008 123179 61580 123179 61579 123180 61580 123180 61581 123180 61581 123181 61580 123181 61575 123181 61581 123182 61575 123182 60271 123182 60271 123183 61575 123183 61574 123183 61586 123184 61057 123184 61582 123184 61582 123185 61057 123185 61583 123185 61582 123186 61583 123186 61587 123186 61587 123187 61583 123187 61584 123187 61587 123188 61584 123188 61585 123188 61585 123189 61584 123189 61565 123189 61022 123190 61586 123190 61599 123190 61599 123191 61586 123191 61582 123191 61599 123192 61582 123192 61601 123192 61601 123193 61582 123193 61587 123193 61601 123194 61587 123194 60274 123194 60274 123195 61587 123195 61585 123195 61578 123196 61577 123196 61592 123196 61610 123197 61608 123197 61589 123197 61608 123198 61607 123198 60554 123198 61594 123199 61588 123199 61610 123199 61588 123200 61594 123200 61613 123200 61608 123201 60554 123201 61589 123201 61589 123202 60554 123202 60654 123202 61589 123203 60654 123203 61591 123203 61591 123204 60654 123204 60655 123204 61591 123205 60655 123205 61592 123205 61592 123206 60655 123206 61590 123206 61592 123207 61590 123207 61578 123207 61610 123208 61589 123208 61594 123208 61594 123209 61589 123209 61591 123209 61594 123210 61591 123210 61595 123210 61595 123211 61591 123211 61592 123211 61595 123212 61592 123212 61593 123212 61593 123213 61592 123213 61577 123213 61593 123214 61577 123214 61596 123214 61613 123215 61594 123215 61015 123215 61015 123216 61594 123216 61595 123216 61015 123217 61595 123217 61014 123217 61014 123218 61595 123218 61593 123218 61014 123219 61593 123219 61012 123219 61012 123220 61593 123220 61596 123220 61012 123221 61596 123221 61010 123221 60280 123222 60284 123222 61618 123222 61597 123223 61022 123223 61598 123223 61598 123224 61022 123224 61599 123224 61598 123225 61599 123225 61600 123225 61600 123226 61599 123226 61601 123226 61600 123227 61601 123227 61604 123227 61604 123228 61601 123228 60274 123228 61042 123229 61597 123229 61602 123229 61602 123230 61597 123230 61598 123230 61602 123231 61598 123231 61603 123231 61603 123232 61598 123232 61600 123232 61603 123233 61600 123233 60279 123233 60279 123234 61600 123234 61604 123234 61031 123235 61042 123235 61605 123235 61605 123236 61042 123236 61602 123236 61605 123237 61602 123237 61618 123237 61618 123238 61602 123238 61603 123238 61618 123239 61603 123239 60280 123239 60280 123240 61603 123240 60279 123240 61606 123241 61607 123241 61615 123241 61615 123242 61607 123242 61608 123242 61615 123243 61608 123243 61609 123243 61609 123244 61608 123244 61610 123244 61609 123245 61610 123245 61611 123245 61611 123246 61610 123246 61588 123246 61611 123247 61588 123247 61612 123247 61612 123248 61588 123248 61613 123248 61622 123249 61606 123249 61614 123249 61614 123250 61606 123250 61615 123250 61614 123251 61615 123251 61616 123251 61616 123252 61615 123252 61609 123252 61616 123253 61609 123253 61623 123253 61623 123254 61609 123254 61611 123254 61623 123255 61611 123255 61069 123255 61069 123256 61611 123256 61612 123256 60275 123257 60438 123257 61634 123257 61030 123258 61031 123258 61617 123258 61617 123259 61031 123259 61605 123259 61617 123260 61605 123260 61619 123260 61619 123261 61605 123261 61618 123261 61619 123262 61618 123262 60278 123262 60278 123263 61618 123263 60284 123263 61028 123264 61030 123264 61633 123264 61633 123265 61030 123265 61617 123265 61633 123266 61617 123266 61634 123266 61634 123267 61617 123267 61619 123267 61634 123268 61619 123268 60275 123268 60275 123269 61619 123269 60278 123269 61074 123270 61076 123270 61620 123270 61069 123271 61621 123271 61624 123271 61074 123272 61620 123272 61071 123272 61627 123273 61622 123273 61626 123273 61626 123274 61622 123274 61614 123274 61626 123275 61614 123275 61625 123275 61625 123276 61614 123276 61616 123276 61625 123277 61616 123277 61624 123277 61624 123278 61616 123278 61623 123278 61624 123279 61623 123279 61069 123279 61621 123280 61071 123280 61624 123280 61624 123281 61071 123281 61620 123281 61624 123282 61620 123282 61625 123282 61625 123283 61620 123283 61628 123283 61625 123284 61628 123284 61626 123284 61626 123285 61628 123285 61629 123285 61626 123286 61629 123286 61627 123286 61627 123287 61629 123287 61631 123287 61076 123288 60710 123288 61620 123288 61620 123289 60710 123289 61706 123289 61620 123290 61706 123290 61628 123290 61628 123291 61706 123291 61705 123291 61628 123292 61705 123292 61629 123292 61629 123293 61705 123293 61630 123293 61629 123294 61630 123294 61631 123294 61631 123295 61630 123295 60877 123295 61634 123296 60438 123296 61632 123296 61028 123297 61633 123297 61639 123297 61633 123298 61634 123298 61635 123298 61635 123299 61634 123299 61632 123299 61635 123300 61632 123300 61637 123300 61637 123301 61632 123301 60441 123301 60441 123302 61636 123302 61637 123302 61637 123303 61636 123303 60518 123303 61637 123304 60518 123304 61638 123304 61638 123305 60518 123305 60519 123305 61638 123306 60519 123306 61641 123306 61633 123307 61635 123307 61639 123307 61639 123308 61635 123308 61637 123308 61639 123309 61637 123309 61640 123309 61640 123310 61637 123310 61638 123310 61640 123311 61638 123311 61642 123311 61642 123312 61638 123312 61641 123312 61642 123313 61641 123313 61712 123313 61028 123314 61639 123314 61027 123314 61027 123315 61639 123315 61640 123315 61027 123316 61640 123316 61025 123316 61025 123317 61640 123317 61642 123317 61025 123318 61642 123318 61024 123318 61024 123319 61642 123319 61712 123319 61024 123320 61712 123320 61643 123320 61700 123321 61644 123321 61698 123321 61645 123322 61696 123322 61695 123322 60703 123323 61688 123323 61686 123323 60693 123324 61646 123324 61669 123324 60690 123325 60688 123325 61665 123325 61650 123326 61647 123326 61648 123326 60872 123327 61647 123327 61649 123327 61649 123328 61647 123328 61650 123328 61649 123329 61650 123329 61651 123329 61663 123330 61664 123330 61652 123330 60869 123331 60870 123331 61716 123331 61716 123332 60870 123332 61663 123332 61716 123333 61663 123333 61714 123333 61714 123334 61663 123334 61652 123334 61653 123335 60872 123335 61654 123335 61654 123336 60872 123336 61649 123336 61654 123337 61649 123337 61655 123337 61655 123338 61649 123338 61651 123338 61655 123339 61651 123339 61675 123339 61674 123340 61656 123340 61676 123340 61660 123341 61656 123341 61658 123341 61658 123342 61656 123342 61674 123342 61658 123343 61674 123343 61657 123343 61648 123344 61682 123344 61657 123344 61657 123345 61682 123345 61684 123345 61657 123346 61684 123346 61658 123346 61658 123347 61684 123347 61659 123347 61658 123348 61659 123348 61660 123348 61660 123349 61659 123349 61677 123349 60688 123350 60687 123350 61665 123350 61665 123351 60687 123351 61661 123351 61665 123352 61661 123352 61664 123352 61664 123353 61661 123353 61662 123353 61664 123354 61662 123354 61652 123354 60870 123355 60876 123355 61663 123355 61663 123356 60876 123356 61670 123356 61663 123357 61670 123357 61664 123357 61664 123358 61670 123358 61666 123358 61664 123359 61666 123359 61665 123359 61665 123360 61666 123360 61669 123360 61665 123361 61669 123361 60690 123361 60690 123362 61669 123362 61646 123362 61673 123363 60693 123363 61667 123363 61667 123364 60693 123364 61669 123364 61667 123365 61669 123365 61668 123365 61668 123366 61669 123366 61666 123366 61668 123367 61666 123367 61672 123367 61672 123368 61666 123368 61670 123368 61672 123369 61670 123369 61671 123369 61671 123370 61670 123370 60876 123370 61671 123371 61653 123371 61672 123371 61672 123372 61653 123372 61654 123372 61672 123373 61654 123373 61668 123373 61668 123374 61654 123374 61655 123374 61668 123375 61655 123375 61667 123375 61667 123376 61655 123376 61675 123376 61667 123377 61675 123377 61673 123377 61673 123378 61675 123378 60694 123378 61648 123379 61657 123379 61650 123379 61650 123380 61657 123380 61674 123380 61650 123381 61674 123381 61651 123381 61651 123382 61674 123382 61676 123382 61651 123383 61676 123383 61675 123383 61675 123384 61676 123384 61681 123384 61675 123385 61681 123385 60694 123385 61687 123386 61678 123386 61677 123386 61677 123387 61678 123387 61679 123387 61677 123388 61679 123388 61660 123388 61660 123389 61679 123389 61680 123389 61660 123390 61680 123390 61656 123390 61656 123391 61680 123391 60697 123391 61656 123392 60697 123392 61676 123392 61676 123393 60697 123393 60696 123393 61676 123394 60696 123394 61681 123394 61682 123395 61683 123395 61684 123395 61684 123396 61683 123396 61691 123396 61684 123397 61691 123397 61659 123397 61659 123398 61691 123398 61685 123398 61659 123399 61685 123399 61677 123399 61677 123400 61685 123400 61686 123400 61677 123401 61686 123401 61687 123401 61687 123402 61686 123402 61688 123402 61694 123403 60703 123403 61693 123403 61693 123404 60703 123404 61686 123404 61693 123405 61686 123405 61689 123405 61689 123406 61686 123406 61685 123406 61689 123407 61685 123407 61690 123407 61690 123408 61685 123408 61691 123408 61690 123409 61691 123409 60884 123409 60884 123410 61691 123410 61683 123410 60884 123411 60882 123411 61690 123411 61690 123412 60882 123412 61692 123412 61690 123413 61692 123413 61689 123413 61689 123414 61692 123414 61697 123414 61689 123415 61697 123415 61693 123415 61693 123416 61697 123416 61695 123416 61693 123417 61695 123417 61694 123417 61694 123418 61695 123418 61696 123418 60882 123419 60883 123419 61692 123419 61692 123420 60883 123420 61703 123420 61692 123421 61703 123421 61697 123421 61697 123422 61703 123422 61702 123422 61697 123423 61702 123423 61695 123423 61695 123424 61702 123424 61698 123424 61695 123425 61698 123425 61645 123425 61645 123426 61698 123426 61644 123426 60707 123427 61700 123427 61699 123427 61699 123428 61700 123428 61698 123428 61699 123429 61698 123429 61701 123429 61701 123430 61698 123430 61702 123430 61701 123431 61702 123431 61704 123431 61704 123432 61702 123432 61703 123432 61704 123433 61703 123433 60880 123433 60880 123434 61703 123434 60883 123434 60880 123435 60877 123435 61704 123435 61704 123436 60877 123436 61630 123436 61704 123437 61630 123437 61701 123437 61701 123438 61630 123438 61705 123438 61701 123439 61705 123439 61699 123439 61699 123440 61705 123440 61706 123440 61699 123441 61706 123441 60707 123441 60707 123442 61706 123442 60710 123442 61707 123443 60721 123443 61709 123443 61709 123444 60721 123444 61708 123444 61709 123445 61708 123445 61710 123445 61710 123446 61708 123446 61711 123446 61710 123447 61711 123447 61064 123447 61064 123448 61711 123448 61065 123448 60519 123449 61707 123449 61641 123449 61641 123450 61707 123450 61709 123450 61641 123451 61709 123451 61712 123451 61712 123452 61709 123452 61710 123452 61712 123453 61710 123453 61643 123453 61643 123454 61710 123454 61064 123454 60687 123455 61083 123455 61661 123455 61661 123456 61083 123456 61713 123456 61661 123457 61713 123457 61662 123457 61662 123458 61713 123458 61652 123458 61652 123459 61713 123459 61717 123459 61652 123460 61717 123460 61714 123460 61714 123461 61717 123461 61716 123461 61716 123462 61717 123462 61715 123462 61716 123463 61715 123463 60869 123463 61083 123464 61088 123464 61713 123464 61713 123465 61088 123465 61721 123465 61713 123466 61721 123466 61717 123466 61717 123467 61721 123467 61722 123467 61717 123468 61722 123468 61715 123468 61715 123469 61722 123469 61718 123469 61088 123470 61719 123470 61721 123470 61721 123471 61719 123471 61720 123471 61721 123472 61720 123472 61722 123472 61722 123473 61720 123473 61735 123473 61722 123474 61735 123474 61718 123474 61718 123475 61735 123475 61723 123475 61728 123476 61727 123476 60722 123476 60721 123477 61726 123477 61708 123477 61708 123478 61726 123478 61724 123478 61708 123479 61724 123479 61711 123479 61711 123480 61724 123480 61725 123480 61711 123481 61725 123481 61065 123481 61726 123482 61727 123482 61724 123482 61724 123483 61727 123483 61728 123483 61724 123484 61728 123484 61725 123484 61725 123485 61728 123485 61731 123485 60722 123486 61739 123486 61728 123486 61728 123487 61739 123487 61738 123487 61728 123488 61738 123488 61731 123488 61731 123489 61738 123489 61729 123489 61731 123490 61729 123490 61733 123490 61065 123491 61725 123491 61730 123491 61730 123492 61725 123492 61731 123492 61730 123493 61731 123493 61732 123493 61732 123494 61731 123494 61733 123494 61732 123495 61733 123495 61062 123495 60553 123496 61723 123496 61734 123496 61734 123497 61723 123497 61735 123497 61734 123498 61735 123498 61736 123498 61736 123499 61735 123499 61720 123499 61736 123500 61720 123500 61087 123500 61087 123501 61720 123501 61719 123501 61801 123502 60553 123502 61802 123502 61802 123503 60553 123503 61734 123503 61802 123504 61734 123504 61737 123504 61737 123505 61734 123505 61736 123505 61737 123506 61736 123506 61086 123506 61086 123507 61736 123507 61087 123507 61768 123508 61738 123508 61739 123508 61812 123509 61814 123509 61740 123509 61738 123510 61768 123510 61729 123510 61814 123511 61815 123511 61743 123511 61815 123512 61816 123512 60663 123512 61741 123513 61745 123513 61759 123513 61815 123514 60663 123514 61743 123514 61743 123515 60663 123515 61742 123515 61743 123516 61742 123516 61759 123516 61759 123517 61742 123517 61744 123517 61759 123518 61744 123518 61741 123518 61750 123519 61763 123519 61761 123519 61741 123520 60666 123520 61745 123520 61745 123521 60666 123521 60667 123521 61745 123522 60667 123522 61746 123522 61746 123523 60667 123523 61747 123523 61746 123524 61747 123524 61761 123524 61761 123525 61747 123525 60670 123525 61761 123526 60670 123526 61750 123526 61748 123527 61755 123527 61749 123527 61750 123528 61751 123528 61763 123528 61763 123529 61751 123529 60671 123529 61763 123530 60671 123530 61752 123530 61752 123531 60671 123531 60673 123531 61752 123532 60673 123532 61765 123532 61765 123533 60673 123533 60674 123533 61765 123534 60674 123534 61749 123534 61749 123535 60674 123535 60677 123535 61749 123536 60677 123536 61748 123536 61753 123537 61767 123537 61758 123537 61748 123538 61754 123538 61755 123538 61755 123539 61754 123539 60680 123539 61755 123540 60680 123540 61756 123540 61756 123541 60680 123541 61757 123541 61756 123542 61757 123542 61758 123542 61758 123543 61757 123543 60682 123543 61758 123544 60682 123544 61753 123544 61753 123545 60685 123545 61767 123545 61767 123546 60685 123546 61062 123546 61767 123547 61062 123547 61733 123547 61814 123548 61743 123548 61740 123548 61740 123549 61743 123549 61759 123549 61740 123550 61759 123550 61760 123550 61760 123551 61759 123551 61745 123551 61760 123552 61745 123552 61770 123552 61770 123553 61745 123553 61746 123553 61770 123554 61746 123554 61771 123554 61771 123555 61746 123555 61761 123555 61771 123556 61761 123556 61772 123556 61772 123557 61761 123557 61763 123557 61772 123558 61763 123558 61762 123558 61762 123559 61763 123559 61752 123559 61762 123560 61752 123560 61764 123560 61764 123561 61752 123561 61765 123561 61764 123562 61765 123562 61766 123562 61766 123563 61765 123563 61749 123563 61766 123564 61749 123564 61775 123564 61775 123565 61749 123565 61755 123565 61775 123566 61755 123566 61776 123566 61776 123567 61755 123567 61756 123567 61776 123568 61756 123568 61778 123568 61778 123569 61756 123569 61758 123569 61778 123570 61758 123570 61779 123570 61779 123571 61758 123571 61767 123571 61779 123572 61767 123572 61768 123572 61768 123573 61767 123573 61733 123573 61768 123574 61733 123574 61729 123574 61812 123575 61740 123575 61796 123575 61796 123576 61740 123576 61760 123576 61796 123577 61760 123577 61769 123577 61769 123578 61760 123578 61770 123578 61769 123579 61770 123579 61794 123579 61794 123580 61770 123580 61771 123580 61794 123581 61771 123581 61792 123581 61792 123582 61771 123582 61772 123582 61792 123583 61772 123583 61790 123583 61790 123584 61772 123584 61762 123584 61790 123585 61762 123585 61773 123585 61773 123586 61762 123586 61764 123586 61773 123587 61764 123587 61788 123587 61788 123588 61764 123588 61766 123588 61788 123589 61766 123589 61774 123589 61774 123590 61766 123590 61775 123590 61774 123591 61775 123591 61786 123591 61786 123592 61775 123592 61776 123592 61786 123593 61776 123593 61777 123593 61777 123594 61776 123594 61778 123594 61777 123595 61778 123595 61783 123595 61783 123596 61778 123596 61779 123596 61783 123597 61779 123597 61780 123597 61780 123598 61779 123598 61768 123598 61780 123599 61768 123599 61781 123599 61781 123600 61768 123600 61739 123600 61781 123601 61739 123601 60722 123601 60722 123602 60724 123602 61781 123602 61781 123603 60724 123603 60717 123603 61781 123604 60717 123604 61780 123604 61780 123605 60717 123605 61782 123605 61780 123606 61782 123606 61783 123606 61783 123607 61782 123607 61784 123607 61783 123608 61784 123608 61777 123608 61777 123609 61784 123609 61785 123609 61777 123610 61785 123610 61786 123610 61786 123611 61785 123611 61787 123611 61786 123612 61787 123612 61774 123612 61774 123613 61787 123613 61789 123613 61774 123614 61789 123614 61788 123614 61788 123615 61789 123615 60732 123615 61788 123616 60732 123616 61773 123616 61773 123617 60732 123617 60734 123617 61773 123618 60734 123618 61790 123618 61790 123619 60734 123619 61791 123619 61790 123620 61791 123620 61792 123620 61792 123621 61791 123621 61793 123621 61792 123622 61793 123622 61794 123622 61794 123623 61793 123623 61795 123623 61794 123624 61795 123624 61769 123624 61769 123625 61795 123625 60726 123625 61769 123626 60726 123626 61796 123626 61796 123627 60726 123627 61811 123627 61796 123628 61811 123628 61812 123628 61827 123629 61797 123629 60662 123629 61798 123630 61806 123630 61807 123630 61806 123631 61827 123631 61799 123631 61799 123632 61827 123632 60662 123632 61799 123633 60662 123633 61800 123633 61800 123634 60662 123634 60550 123634 61801 123635 61802 123635 61803 123635 61803 123636 61802 123636 61804 123636 61803 123637 61804 123637 61805 123637 61805 123638 61804 123638 61800 123638 61805 123639 61800 123639 60627 123639 60627 123640 61800 123640 60550 123640 61806 123641 61799 123641 61807 123641 61807 123642 61799 123642 61800 123642 61807 123643 61800 123643 61809 123643 61809 123644 61800 123644 61804 123644 61809 123645 61804 123645 61810 123645 61810 123646 61804 123646 61802 123646 61810 123647 61802 123647 61737 123647 61798 123648 61807 123648 61808 123648 61808 123649 61807 123649 61809 123649 61808 123650 61809 123650 61020 123650 61020 123651 61809 123651 61810 123651 61020 123652 61810 123652 61018 123652 61018 123653 61810 123653 61737 123653 61018 123654 61737 123654 61086 123654 61811 123655 60712 123655 61812 123655 61812 123656 60712 123656 61813 123656 61812 123657 61813 123657 61814 123657 61814 123658 61813 123658 61819 123658 61814 123659 61819 123659 61815 123659 61815 123660 61819 123660 61817 123660 61815 123661 61817 123661 61816 123661 61816 123662 61817 123662 61081 123662 60712 123663 61818 123663 61813 123663 61813 123664 61818 123664 61822 123664 61813 123665 61822 123665 61819 123665 61819 123666 61822 123666 61820 123666 61819 123667 61820 123667 61817 123667 61817 123668 61820 123668 61821 123668 61817 123669 61821 123669 61081 123669 61081 123670 61821 123670 61080 123670 61818 123671 61843 123671 61822 123671 61822 123672 61843 123672 61823 123672 61822 123673 61823 123673 61820 123673 61820 123674 61823 123674 61824 123674 61820 123675 61824 123675 61821 123675 61821 123676 61824 123676 61825 123676 61821 123677 61825 123677 61080 123677 61080 123678 61825 123678 61845 123678 61826 123679 61797 123679 61827 123679 61834 123680 61829 123680 61828 123680 61828 123681 61829 123681 61830 123681 61828 123682 61830 123682 61831 123682 61831 123683 61830 123683 61832 123683 61831 123684 61832 123684 61835 123684 61835 123685 61832 123685 61833 123685 61798 123686 61834 123686 61806 123686 61806 123687 61834 123687 61828 123687 61806 123688 61828 123688 61827 123688 61827 123689 61828 123689 61831 123689 61827 123690 61831 123690 61826 123690 61826 123691 61831 123691 61835 123691 61837 123692 61839 123692 61842 123692 61836 123693 61078 123693 61862 123693 61862 123694 61078 123694 61837 123694 61862 123695 61837 123695 61853 123695 61853 123696 61837 123696 61842 123696 60443 123697 61838 123697 61844 123697 61844 123698 61838 123698 61840 123698 61844 123699 61840 123699 61839 123699 61839 123700 61840 123700 61841 123700 61839 123701 61841 123701 61842 123701 61843 123702 60443 123702 61823 123702 61823 123703 60443 123703 61844 123703 61823 123704 61844 123704 61824 123704 61824 123705 61844 123705 61839 123705 61824 123706 61839 123706 61825 123706 61825 123707 61839 123707 61837 123707 61825 123708 61837 123708 61845 123708 61845 123709 61837 123709 61078 123709 61048 123710 61846 123710 61849 123710 61849 123711 61846 123711 61870 123711 61849 123712 61870 123712 61850 123712 61850 123713 61870 123713 61872 123713 61850 123714 61872 123714 60258 123714 60258 123715 61872 123715 61847 123715 61851 123716 61048 123716 61848 123716 61848 123717 61048 123717 61849 123717 61848 123718 61849 123718 61852 123718 61852 123719 61849 123719 61850 123719 61852 123720 61850 123720 60263 123720 60263 123721 61850 123721 60258 123721 61829 123722 61851 123722 61830 123722 61830 123723 61851 123723 61848 123723 61830 123724 61848 123724 61832 123724 61832 123725 61848 123725 61852 123725 61832 123726 61852 123726 61833 123726 61833 123727 61852 123727 60263 123727 60446 123728 61861 123728 61860 123728 61838 123729 60445 123729 61840 123729 61840 123730 60445 123730 61856 123730 61840 123731 61856 123731 61841 123731 61841 123732 61856 123732 61842 123732 61862 123733 61853 123733 61864 123733 61864 123734 61853 123734 61842 123734 61863 123735 61836 123735 61862 123735 60445 123736 61854 123736 61856 123736 61856 123737 61854 123737 61855 123737 61856 123738 61855 123738 61857 123738 61857 123739 61855 123739 60487 123739 61857 123740 60487 123740 61860 123740 61860 123741 60487 123741 61858 123741 61860 123742 61858 123742 60446 123742 61842 123743 61856 123743 61864 123743 61864 123744 61856 123744 61857 123744 61864 123745 61857 123745 61859 123745 61859 123746 61857 123746 61860 123746 61859 123747 61860 123747 61866 123747 61866 123748 61860 123748 61861 123748 61866 123749 61861 123749 61868 123749 61862 123750 61864 123750 61863 123750 61863 123751 61864 123751 61859 123751 61863 123752 61859 123752 61865 123752 61865 123753 61859 123753 61866 123753 61865 123754 61866 123754 61867 123754 61867 123755 61866 123755 61868 123755 61867 123756 61868 123756 61034 123756 61869 123757 61017 123757 61871 123757 61871 123758 61017 123758 61880 123758 61871 123759 61880 123759 61873 123759 61873 123760 61880 123760 61878 123760 61873 123761 61878 123761 61874 123761 61874 123762 61878 123762 60259 123762 61846 123763 61869 123763 61870 123763 61870 123764 61869 123764 61871 123764 61870 123765 61871 123765 61872 123765 61872 123766 61871 123766 61873 123766 61872 123767 61873 123767 61847 123767 61847 123768 61873 123768 61874 123768 60254 123769 60253 123769 61876 123769 61032 123770 61034 123770 61875 123770 61875 123771 61034 123771 61868 123771 61875 123772 61868 123772 61876 123772 61876 123773 61868 123773 61861 123773 61876 123774 61861 123774 60254 123774 60254 123775 61861 123775 60446 123775 61045 123776 61032 123776 61888 123776 61888 123777 61032 123777 61875 123777 61888 123778 61875 123778 61889 123778 61889 123779 61875 123779 61876 123779 61889 123780 61876 123780 61877 123780 61877 123781 61876 123781 60253 123781 60260 123782 60259 123782 61882 123782 61882 123783 60259 123783 61878 123783 61882 123784 61878 123784 61879 123784 61879 123785 61878 123785 61880 123785 61879 123786 61880 123786 61881 123786 61881 123787 61880 123787 61017 123787 61885 123788 60260 123788 61886 123788 61886 123789 60260 123789 61882 123789 61886 123790 61882 123790 61883 123790 61883 123791 61882 123791 61879 123791 61883 123792 61879 123792 61884 123792 61884 123793 61879 123793 61881 123793 60261 123794 61885 123794 61901 123794 61901 123795 61885 123795 61886 123795 61901 123796 61886 123796 61900 123796 61900 123797 61886 123797 61883 123797 61900 123798 61883 123798 60887 123798 60887 123799 61883 123799 61884 123799 60252 123800 60248 123800 61887 123800 61890 123801 61045 123801 61892 123801 61892 123802 61045 123802 61888 123802 61892 123803 61888 123803 61887 123803 61887 123804 61888 123804 61889 123804 61887 123805 61889 123805 60252 123805 60252 123806 61889 123806 61877 123806 61047 123807 61890 123807 61891 123807 61891 123808 61890 123808 61892 123808 61891 123809 61892 123809 61896 123809 61896 123810 61892 123810 61887 123810 61896 123811 61887 123811 61893 123811 61893 123812 61887 123812 60248 123812 61894 123813 61047 123813 61895 123813 61895 123814 61047 123814 61891 123814 61895 123815 61891 123815 61903 123815 61903 123816 61891 123816 61896 123816 61903 123817 61896 123817 60000 123817 60000 123818 61896 123818 61893 123818 60886 123819 61913 123819 61897 123819 61897 123820 61913 123820 61912 123820 61897 123821 61912 123821 61898 123821 61898 123822 61912 123822 61899 123822 61898 123823 61899 123823 61902 123823 61902 123824 61899 123824 61909 123824 60887 123825 60886 123825 61900 123825 61900 123826 60886 123826 61897 123826 61900 123827 61897 123827 61901 123827 61901 123828 61897 123828 61898 123828 61901 123829 61898 123829 60261 123829 60261 123830 61898 123830 61902 123830 61039 123831 61894 123831 61905 123831 61905 123832 61894 123832 61895 123832 61905 123833 61895 123833 61908 123833 61908 123834 61895 123834 61903 123834 61908 123835 61903 123835 61904 123835 61904 123836 61903 123836 60000 123836 61038 123837 61039 123837 61906 123837 61906 123838 61039 123838 61905 123838 61906 123839 61905 123839 61907 123839 61907 123840 61905 123840 61908 123840 61907 123841 61908 123841 60255 123841 60255 123842 61908 123842 61904 123842 61915 123843 61909 123843 61910 123843 61910 123844 61909 123844 61899 123844 61910 123845 61899 123845 61911 123845 61911 123846 61899 123846 61912 123846 61911 123847 61912 123847 61053 123847 61053 123848 61912 123848 61913 123848 61914 123849 61915 123849 61917 123849 61917 123850 61915 123850 61910 123850 61917 123851 61910 123851 61916 123851 61916 123852 61910 123852 61911 123852 61916 123853 61911 123853 61056 123853 61056 123854 61911 123854 61053 123854 60255 123855 61914 123855 61907 123855 61907 123856 61914 123856 61917 123856 61907 123857 61917 123857 61906 123857 61906 123858 61917 123858 61916 123858 61906 123859 61916 123859 61038 123859 61038 123860 61916 123860 61056 123860 64599 123861 61918 123861 61919 123861 61919 123862 61918 123862 61929 123862 61919 123863 61929 123863 61920 123863 61999 123864 61998 123864 64614 123864 64614 123865 61998 123865 61921 123865 64614 123866 61921 123866 64604 123866 61921 123867 60245 123867 64604 123867 64604 123868 60245 123868 61922 123868 64604 123869 61922 123869 61923 123869 61923 123870 61922 123870 60247 123870 61923 123871 60247 123871 61924 123871 60247 123872 61925 123872 61924 123872 61924 123873 61925 123873 60212 123873 61924 123874 60212 123874 61926 123874 61926 123875 60212 123875 61927 123875 61926 123876 61927 123876 61928 123876 61928 123877 61927 123877 60209 123877 61928 123878 60209 123878 64599 123878 64599 123879 60209 123879 61918 123879 61920 123880 61929 123880 61930 123880 61920 123881 61930 123881 64547 123881 64547 123882 61930 123882 60211 123882 64547 123883 60211 123883 61931 123883 61931 123884 60211 123884 60210 123884 61931 123885 60210 123885 61932 123885 61932 123886 60210 123886 60208 123886 61932 123887 60208 123887 64531 123887 64531 123888 60208 123888 60207 123888 64531 123889 60207 123889 64532 123889 64532 123890 60207 123890 60214 123890 64532 123891 60214 123891 64529 123891 64529 123892 60214 123892 61933 123892 64529 123893 61933 123893 64512 123893 64512 123894 61933 123894 64513 123894 64513 123895 61933 123895 61934 123895 64513 123896 61934 123896 64505 123896 64505 123897 61934 123897 61935 123897 64505 123898 61935 123898 64458 123898 60198 123899 64225 123899 64265 123899 60198 123900 64265 123900 61936 123900 61936 123901 64265 123901 61937 123901 61936 123902 61937 123902 60199 123902 60199 123903 61937 123903 64186 123903 60199 123904 64186 123904 60266 123904 64225 123905 60198 123905 64226 123905 64226 123906 60198 123906 61938 123906 64226 123907 61938 123907 64251 123907 64251 123908 61938 123908 60203 123908 64251 123909 60203 123909 64247 123909 64247 123910 60203 123910 60202 123910 64247 123911 60202 123911 61939 123911 61939 123912 60202 123912 60205 123912 61939 123913 60205 123913 64236 123913 64236 123914 60205 123914 62021 123914 64236 123915 62021 123915 64230 123915 64146 123916 60200 123916 64191 123916 64191 123917 60200 123917 60266 123917 64191 123918 60266 123918 64186 123918 64200 123919 60197 123919 61940 123919 61940 123920 60197 123920 61941 123920 61940 123921 61941 123921 64185 123921 64185 123922 61941 123922 61942 123922 64185 123923 61942 123923 64184 123923 64184 123924 61942 123924 61943 123924 64184 123925 61943 123925 61946 123925 60200 123926 64146 123926 61944 123926 61944 123927 64146 123927 64182 123927 61944 123928 64182 123928 61945 123928 61945 123929 64182 123929 61947 123929 61945 123930 61947 123930 61946 123930 61946 123931 61947 123931 61948 123931 61946 123932 61948 123932 64184 123932 61949 123933 61950 123933 63779 123933 61949 123934 63779 123934 60152 123934 60152 123935 63779 123935 61951 123935 60152 123936 61951 123936 61952 123936 61952 123937 61951 123937 63713 123937 61952 123938 63713 123938 60153 123938 61950 123939 61949 123939 63749 123939 63749 123940 61949 123940 61953 123940 63749 123941 61953 123941 63772 123941 63772 123942 61953 123942 60160 123942 63772 123943 60160 123943 63766 123943 63766 123944 60160 123944 61954 123944 63766 123945 61954 123945 61955 123945 61955 123946 61954 123946 60159 123946 61955 123947 60159 123947 61956 123947 61956 123948 60159 123948 60406 123948 61956 123949 60406 123949 63859 123949 63708 123950 60154 123950 61957 123950 61957 123951 60154 123951 60153 123951 61957 123952 60153 123952 63713 123952 62085 123953 61958 123953 61960 123953 61960 123954 61958 123954 61959 123954 61960 123955 61959 123955 63712 123955 63712 123956 61959 123956 61961 123956 63712 123957 61961 123957 61962 123957 61962 123958 61961 123958 60150 123958 61962 123959 60150 123959 60151 123959 60154 123960 63708 123960 60156 123960 60156 123961 63708 123961 63709 123961 60156 123962 63709 123962 61964 123962 61964 123963 63709 123963 61963 123963 61964 123964 61963 123964 60151 123964 60151 123965 61963 123965 63710 123965 60151 123966 63710 123966 61962 123966 64101 123967 60083 123967 64093 123967 64093 123968 60083 123968 61977 123968 64093 123969 61977 123969 61976 123969 64064 123970 60123 123970 64129 123970 64129 123971 60123 123971 61965 123971 64129 123972 61965 123972 64123 123972 61965 123973 61966 123973 64123 123973 64123 123974 61966 123974 61967 123974 64123 123975 61967 123975 61968 123975 61968 123976 61967 123976 61969 123976 61968 123977 61969 123977 61971 123977 61969 123978 60125 123978 61971 123978 61971 123979 60125 123979 61970 123979 61971 123980 61970 123980 64121 123980 64121 123981 61970 123981 61972 123981 64121 123982 61972 123982 61973 123982 61973 123983 61972 123983 60081 123983 61973 123984 60081 123984 64101 123984 64101 123985 60081 123985 60083 123985 60085 123986 61978 123986 64041 123986 60085 123987 64041 123987 60082 123987 60082 123988 64041 123988 61975 123988 60082 123989 61975 123989 61974 123989 61974 123990 61975 123990 61976 123990 61974 123991 61976 123991 61977 123991 61978 123992 60085 123992 61979 123992 61979 123993 60085 123993 60084 123993 61979 123994 60084 123994 61981 123994 61981 123995 60084 123995 61980 123995 61981 123996 61980 123996 64030 123996 64030 123997 61980 123997 60088 123997 64030 123998 60088 123998 61982 123998 61982 123999 60088 123999 61983 123999 61982 124000 61983 124000 64018 124000 64018 124001 61983 124001 60089 124001 64018 124002 60089 124002 64019 124002 62012 124003 64422 124003 60423 124003 60423 124004 64422 124004 64453 124004 60423 124005 64453 124005 61984 124005 61984 124006 64453 124006 61985 124006 61984 124007 61985 124007 61986 124007 61986 124008 61985 124008 61987 124008 61986 124009 61987 124009 60422 124009 60422 124010 61987 124010 64456 124010 60422 124011 64456 124011 61988 124011 61988 124012 64456 124012 61989 124012 61988 124013 61989 124013 61935 124013 61935 124014 61989 124014 64458 124014 62009 124015 60224 124015 61990 124015 61990 124016 60224 124016 60226 124016 61990 124017 60226 124017 61991 124017 61991 124018 60226 124018 64499 124018 60226 124019 61992 124019 64499 124019 64499 124020 61992 124020 60221 124020 64499 124021 60221 124021 64467 124021 64467 124022 60221 124022 64466 124022 64466 124023 60221 124023 64465 124023 64465 124024 60221 124024 60219 124024 64465 124025 60219 124025 64464 124025 64464 124026 60219 124026 61993 124026 64464 124027 61993 124027 64463 124027 64463 124028 61993 124028 61994 124028 61994 124029 61993 124029 61995 124029 61994 124030 61995 124030 61996 124030 61996 124031 61995 124031 60230 124031 61996 124032 60230 124032 61997 124032 61998 124033 61999 124033 60240 124033 60240 124034 61999 124034 62000 124034 60240 124035 62000 124035 62001 124035 62001 124036 62000 124036 64569 124036 62001 124037 64569 124037 60236 124037 60236 124038 64569 124038 62004 124038 62002 124039 61997 124039 60230 124039 64570 124040 62003 124040 62004 124040 62004 124041 62003 124041 60237 124041 62004 124042 60237 124042 60236 124042 60230 124043 60233 124043 62002 124043 62002 124044 60233 124044 62005 124044 62002 124045 62005 124045 64570 124045 64570 124046 62005 124046 62006 124046 64570 124047 62006 124047 62003 124047 62018 124048 62007 124048 62008 124048 62008 124049 62007 124049 60224 124049 62008 124050 60224 124050 62009 124050 62010 124051 62011 124051 60227 124051 64422 124052 62012 124052 62013 124052 62013 124053 62012 124053 62014 124053 62013 124054 62014 124054 64413 124054 64413 124055 62014 124055 62017 124055 60227 124056 62011 124056 62015 124056 62011 124057 62016 124057 62015 124057 62015 124058 62016 124058 64386 124058 62015 124059 64386 124059 62017 124059 62017 124060 64386 124060 64385 124060 62017 124061 64385 124061 64413 124061 62019 124062 62007 124062 62018 124062 62018 124063 64405 124063 62019 124063 62019 124064 64405 124064 62020 124064 62019 124065 62020 124065 60227 124065 60227 124066 62020 124066 64403 124066 60227 124067 64403 124067 62010 124067 64230 124068 62021 124068 62022 124068 64230 124069 62022 124069 62023 124069 62023 124070 62022 124070 62024 124070 62023 124071 62024 124071 64334 124071 62024 124072 60165 124072 64334 124072 64334 124073 60165 124073 60166 124073 64334 124074 60166 124074 64333 124074 64333 124075 60166 124075 60170 124075 64333 124076 60170 124076 64331 124076 60170 124077 62025 124077 64331 124077 64331 124078 62025 124078 62026 124078 64331 124079 62026 124079 64329 124079 60174 124080 64328 124080 62027 124080 62027 124081 64328 124081 64329 124081 62027 124082 64329 124082 62028 124082 62028 124083 64329 124083 62026 124083 64328 124084 60174 124084 62029 124084 62029 124085 60174 124085 62030 124085 62029 124086 62030 124086 64380 124086 64368 124087 64378 124087 60181 124087 64380 124088 62030 124088 64378 124088 64378 124089 62030 124089 60173 124089 64378 124090 60173 124090 60181 124090 60183 124091 64371 124091 62031 124091 62031 124092 64371 124092 64370 124092 62031 124093 64370 124093 60181 124093 60181 124094 64370 124094 62032 124094 60181 124095 62032 124095 64368 124095 62034 124096 62033 124096 64347 124096 64347 124097 64346 124097 62034 124097 62034 124098 64346 124098 64372 124098 62034 124099 64372 124099 60183 124099 60183 124100 64372 124100 62035 124100 60183 124101 62035 124101 64371 124101 64347 124102 62033 124102 62036 124102 62036 124103 62033 124103 62038 124103 62036 124104 62038 124104 64343 124104 64343 124105 62038 124105 62037 124105 62037 124106 62038 124106 62039 124106 62037 124107 62039 124107 64306 124107 64306 124108 62039 124108 60180 124108 62043 124109 62040 124109 60180 124109 60180 124110 62040 124110 62041 124110 60180 124111 62041 124111 64306 124111 64278 124112 62042 124112 62046 124112 62046 124113 62042 124113 62044 124113 62046 124114 62044 124114 62043 124114 62043 124115 62044 124115 64280 124115 62043 124116 64280 124116 62040 124116 64278 124117 62046 124117 62045 124117 62045 124118 62046 124118 62047 124118 62045 124119 62047 124119 64277 124119 64277 124120 62047 124120 60186 124120 64277 124121 60186 124121 64224 124121 64224 124122 60186 124122 62048 124122 62048 124123 60186 124123 62050 124123 62048 124124 62050 124124 62049 124124 62049 124125 62050 124125 60189 124125 62049 124126 60189 124126 64223 124126 60197 124127 64200 124127 60195 124127 60195 124128 64200 124128 64221 124128 60195 124129 64221 124129 60194 124129 60194 124130 64221 124130 62052 124130 60194 124131 62052 124131 62051 124131 62051 124132 62052 124132 64223 124132 62051 124133 64223 124133 60187 124133 60187 124134 64223 124134 60189 124134 62053 124135 62062 124135 62054 124135 62054 124136 62062 124136 62055 124136 62054 124137 62055 124137 63861 124137 62056 124138 62059 124138 62064 124138 63854 124139 60401 124139 62057 124139 62057 124140 60401 124140 60399 124140 62057 124141 60399 124141 62058 124141 62058 124142 60399 124142 60398 124142 62064 124143 62059 124143 60163 124143 62059 124144 62060 124144 60163 124144 60163 124145 62060 124145 62061 124145 60163 124146 62061 124146 60398 124146 60398 124147 62061 124147 63868 124147 60398 124148 63868 124148 62058 124148 60161 124149 62062 124149 62053 124149 62053 124150 62063 124150 60161 124150 60161 124151 62063 124151 62065 124151 60161 124152 62065 124152 62064 124152 62064 124153 62065 124153 63880 124153 62064 124154 63880 124154 62056 124154 63861 124155 62055 124155 62066 124155 62066 124156 62055 124156 62067 124156 62066 124157 62067 124157 63833 124157 63833 124158 62067 124158 62068 124158 62071 124159 62069 124159 62068 124159 62068 124160 62069 124160 63832 124160 62068 124161 63832 124161 63833 124161 62073 124162 63801 124162 62070 124162 62070 124163 63801 124163 63802 124163 62070 124164 63802 124164 62071 124164 62071 124165 63802 124165 62072 124165 62071 124166 62072 124166 62069 124166 62073 124167 62070 124167 63799 124167 63799 124168 62070 124168 60135 124168 63799 124169 60135 124169 62074 124169 62074 124170 60135 124170 60134 124170 62074 124171 60134 124171 62075 124171 60401 124172 63854 124172 62076 124172 62076 124173 63854 124173 62077 124173 62076 124174 62077 124174 60402 124174 60402 124175 62077 124175 62078 124175 60402 124176 62078 124176 60403 124176 60403 124177 62078 124177 62079 124177 60403 124178 62079 124178 62080 124178 62080 124179 62079 124179 62081 124179 62080 124180 62081 124180 60404 124180 60404 124181 62081 124181 62082 124181 60404 124182 62082 124182 60406 124182 60406 124183 62082 124183 63859 124183 62083 124184 62087 124184 60140 124184 62083 124185 60140 124185 62091 124185 63747 124186 62084 124186 62085 124186 62085 124187 62084 124187 62086 124187 62085 124188 62086 124188 61958 124188 62087 124189 62083 124189 62088 124189 62088 124190 62083 124190 62089 124190 62088 124191 62089 124191 60132 124191 60132 124192 62089 124192 62075 124192 60132 124193 62075 124193 60134 124193 60140 124194 62090 124194 62091 124194 62091 124195 62090 124195 62092 124195 62091 124196 62092 124196 62093 124196 62092 124197 60143 124197 62093 124197 62093 124198 60143 124198 60144 124198 62093 124199 60144 124199 63747 124199 63747 124200 60144 124200 60146 124200 63747 124201 60146 124201 62084 124201 64088 124202 62094 124202 62095 124202 62095 124203 62094 124203 60118 124203 62095 124204 60118 124204 64086 124204 64086 124205 60118 124205 62102 124205 64086 124206 62102 124206 62100 124206 60123 124207 64064 124207 62096 124207 62096 124208 64064 124208 64084 124208 62096 124209 64084 124209 62098 124209 62098 124210 64084 124210 62097 124210 62098 124211 62097 124211 62099 124211 62099 124212 62097 124212 62100 124212 62099 124213 62100 124213 62101 124213 62101 124214 62100 124214 62102 124214 62106 124215 62103 124215 60095 124215 60095 124216 62103 124216 60093 124216 60093 124217 62103 124217 63972 124217 60093 124218 63972 124218 62104 124218 62104 124219 63972 124219 63973 124219 62104 124220 63973 124220 60090 124220 60090 124221 63973 124221 64019 124221 60090 124222 64019 124222 60089 124222 60095 124223 60097 124223 62106 124223 62106 124224 60097 124224 62105 124224 62106 124225 62105 124225 62111 124225 62107 124226 62108 124226 62109 124226 62109 124227 62108 124227 62111 124227 62109 124228 62111 124228 62110 124228 62110 124229 62111 124229 62105 124229 63917 124230 62116 124230 62115 124230 62108 124231 62107 124231 62112 124231 62112 124232 62107 124232 62114 124232 62112 124233 62114 124233 62113 124233 62113 124234 62114 124234 60100 124234 62115 124235 62116 124235 60103 124235 62116 124236 63927 124236 60103 124236 60103 124237 63927 124237 62117 124237 60103 124238 62117 124238 60100 124238 60100 124239 62117 124239 63902 124239 60100 124240 63902 124240 62113 124240 60110 124241 60113 124241 63922 124241 63922 124242 63921 124242 60110 124242 60110 124243 63921 124243 63920 124243 60110 124244 63920 124244 62115 124244 62115 124245 63920 124245 62118 124245 62115 124246 62118 124246 63917 124246 63949 124247 62119 124247 62120 124247 62120 124248 62119 124248 60107 124248 62120 124249 60107 124249 62123 124249 62123 124250 60107 124250 60106 124250 62121 124251 62127 124251 60106 124251 60106 124252 62127 124252 62122 124252 60106 124253 62122 124253 62123 124253 63977 124254 62124 124254 60117 124254 60117 124255 62124 124255 62125 124255 60117 124256 62125 124256 62121 124256 62121 124257 62125 124257 62126 124257 62121 124258 62126 124258 62127 124258 63977 124259 60117 124259 63975 124259 63975 124260 60117 124260 60116 124260 63975 124261 60116 124261 62128 124261 62128 124262 60116 124262 62094 124262 62128 124263 62094 124263 64088 124263 63922 124264 60113 124264 63947 124264 63947 124265 60113 124265 62119 124265 63947 124266 62119 124266 63949 124266 62292 124267 60437 124267 62129 124267 62129 124268 60437 124268 62130 124268 62129 124269 62130 124269 62203 124269 60452 124270 62291 124270 62131 124270 62131 124271 62291 124271 62132 124271 62131 124272 62132 124272 60091 124272 60091 124273 62132 124273 64658 124273 60454 124274 62133 124274 60435 124274 60435 124275 62133 124275 62134 124275 60435 124276 62134 124276 64654 124276 62196 124277 62197 124277 62135 124277 62135 124278 62197 124278 64651 124278 62135 124279 64651 124279 60101 124279 60460 124280 62285 124280 60115 124280 60115 124281 62285 124281 62284 124281 60115 124282 62284 124282 64647 124282 60463 124283 62136 124283 62137 124283 62137 124284 62136 124284 62138 124284 62137 124285 62138 124285 60131 124285 62139 124286 62140 124286 62141 124286 62141 124287 62140 124287 62142 124287 62141 124288 62142 124288 60138 124288 60468 124289 62143 124289 62144 124289 62144 124290 62143 124290 64639 124290 62144 124291 64639 124291 60141 124291 62185 124292 62145 124292 62147 124292 62147 124293 62145 124293 62146 124293 62147 124294 62146 124294 60439 124294 60475 124295 62276 124295 62148 124295 62148 124296 62276 124296 62187 124296 62148 124297 62187 124297 62149 124297 62279 124298 62151 124298 62150 124298 62150 124299 62151 124299 60148 124299 62277 124300 60155 124300 62152 124300 62152 124301 60155 124301 62153 124301 60003 124302 60147 124302 64637 124302 60003 124303 64637 124303 60470 124303 60470 124304 64637 124304 62280 124304 60470 124305 62280 124305 60471 124305 64638 124306 62154 124306 60142 124306 60142 124307 62154 124307 62155 124307 60142 124308 62155 124308 62359 124308 62189 124309 62188 124309 62358 124309 62358 124310 62188 124310 64636 124310 62358 124311 64636 124311 60145 124311 62156 124312 64641 124312 60481 124312 60481 124313 64641 124313 62157 124313 60481 124314 62157 124314 60482 124314 62158 124315 64642 124315 60137 124315 60137 124316 64642 124316 62281 124316 60137 124317 62281 124317 62190 124317 62159 124318 62282 124318 62160 124318 62160 124319 62282 124319 64640 124319 62160 124320 64640 124320 62161 124320 60133 124321 62162 124321 62163 124321 62163 124322 62162 124322 62164 124322 62163 124323 62164 124323 60466 124323 64643 124324 64644 124324 62165 124324 62165 124325 64644 124325 62191 124325 62165 124326 62191 124326 62355 124326 62193 124327 62192 124327 62356 124327 62356 124328 62192 124328 62166 124328 62356 124329 62166 124329 60136 124329 64646 124330 62167 124330 60130 124330 60130 124331 62167 124331 62194 124331 60130 124332 62194 124332 60461 124332 60128 124333 62283 124333 60104 124333 60104 124334 62283 124334 62286 124334 60104 124335 62286 124335 62354 124335 62195 124336 62168 124336 62169 124336 62169 124337 62168 124337 64645 124337 62169 124338 64645 124338 60129 124338 60114 124339 64648 124339 60458 124339 60458 124340 64648 124340 62287 124340 60458 124341 62287 124341 60459 124341 60102 124342 64649 124342 62353 124342 62353 124343 64649 124343 62198 124343 62353 124344 62198 124344 62170 124344 62352 124345 62199 124345 62171 124345 62171 124346 62199 124346 62288 124346 62171 124347 62288 124347 60109 124347 60005 124348 64653 124348 62172 124348 62172 124349 64653 124349 62290 124349 62172 124350 62290 124350 60455 124350 60006 124351 64655 124351 62173 124351 62173 124352 64655 124352 62174 124352 62173 124353 62174 124353 62200 124353 62351 124354 62289 124354 62175 124354 62175 124355 62289 124355 62176 124355 62175 124356 62176 124356 62177 124356 60098 124357 64657 124357 60099 124357 60099 124358 64657 124358 62178 124358 60099 124359 62178 124359 60450 124359 60092 124360 64659 124360 62348 124360 62348 124361 64659 124361 62179 124361 62348 124362 62179 124362 62349 124362 62346 124363 62201 124363 62345 124363 62345 124364 62201 124364 64656 124364 62345 124365 64656 124365 60096 124365 62204 124366 62181 124366 62180 124366 62180 124367 62181 124367 62182 124367 62180 124368 62182 124368 60453 124368 60087 124369 64661 124369 62183 124369 60087 124370 62183 124370 62344 124370 62343 124371 62184 124371 62342 124371 62342 124372 62184 124372 62293 124372 62145 124373 62185 124373 62278 124373 62278 124374 62185 124374 62186 124374 62278 124375 62186 124375 62187 124375 62187 124376 62186 124376 62149 124376 62279 124377 62152 124377 62151 124377 62151 124378 62152 124378 62153 124378 60471 124379 62280 124379 60468 124379 60468 124380 62280 124380 62143 124380 62155 124381 62188 124381 62359 124381 62359 124382 62188 124382 62189 124382 60482 124383 62157 124383 62139 124383 62139 124384 62157 124384 62140 124384 62281 124385 62282 124385 62190 124385 62190 124386 62282 124386 62159 124386 60466 124387 62164 124387 60463 124387 60463 124388 62164 124388 62136 124388 62191 124389 62192 124389 62355 124389 62355 124390 62192 124390 62193 124390 60461 124391 62194 124391 60460 124391 60460 124392 62194 124392 62285 124392 62286 124393 62168 124393 62354 124393 62354 124394 62168 124394 62195 124394 60459 124395 62287 124395 62196 124395 62196 124396 62287 124396 62197 124396 62198 124397 62199 124397 62170 124397 62170 124398 62199 124398 62352 124398 60455 124399 62290 124399 60454 124399 60454 124400 62290 124400 62133 124400 62174 124401 62289 124401 62200 124401 62200 124402 62289 124402 62351 124402 60450 124403 62178 124403 60452 124403 60452 124404 62178 124404 62291 124404 62179 124405 62201 124405 62349 124405 62349 124406 62201 124406 62346 124406 62202 124407 62129 124407 62203 124407 62202 124408 62203 124408 62204 124408 62204 124409 62203 124409 62205 124409 62204 124410 62205 124410 62181 124410 62183 124411 62184 124411 62344 124411 62344 124412 62184 124412 62343 124412 60656 124413 62206 124413 60577 124413 60577 124414 62206 124414 62258 124414 60577 124415 62258 124415 60578 124415 60545 124416 62298 124416 60576 124416 60576 124417 62298 124417 62295 124417 60576 124418 62295 124418 62207 124418 64673 124419 60213 124419 62296 124419 62296 124420 60213 124420 62340 124420 62294 124421 62341 124421 64674 124421 64674 124422 62341 124422 62208 124422 60574 124423 60243 124423 62209 124423 60574 124424 62209 124424 62210 124424 62210 124425 62209 124425 62259 124425 62210 124426 62259 124426 60573 124426 60571 124427 62211 124427 62212 124427 62212 124428 62211 124428 62299 124428 62212 124429 62299 124429 64676 124429 62260 124430 62301 124430 60239 124430 60239 124431 62301 124431 62302 124431 60239 124432 62302 124432 62213 124432 62214 124433 64675 124433 62215 124433 62215 124434 64675 124434 62300 124434 62215 124435 62300 124435 62216 124435 60235 124436 62217 124436 60569 124436 60569 124437 62217 124437 62218 124437 60569 124438 62218 124438 60568 124438 62261 124439 62304 124439 62219 124439 62219 124440 62304 124440 64677 124440 62219 124441 64677 124441 60232 124441 62337 124442 62220 124442 60234 124442 60234 124443 62220 124443 62221 124443 60234 124444 62221 124444 62222 124444 60231 124445 62223 124445 62224 124445 62224 124446 62223 124446 62303 124446 62224 124447 62303 124447 62338 124447 60229 124448 62225 124448 62226 124448 62226 124449 62225 124449 62307 124449 62226 124450 62307 124450 62262 124450 62227 124451 62306 124451 60548 124451 60548 124452 62306 124452 62305 124452 60548 124453 62305 124453 60220 124453 62264 124454 62263 124454 62228 124454 62228 124455 62263 124455 64678 124455 62228 124456 64678 124456 64679 124456 60218 124457 62229 124457 60216 124457 60216 124458 62229 124458 62230 124458 60216 124459 62230 124459 62336 124459 60222 124460 62312 124460 62231 124460 62231 124461 62312 124461 62232 124461 62231 124462 62232 124462 60563 124462 60549 124463 62309 124463 62233 124463 62233 124464 62309 124464 64683 124464 62233 124465 64683 124465 64681 124465 62335 124466 62310 124466 60217 124466 60217 124467 62310 124467 62311 124467 60217 124468 62311 124468 60225 124468 64680 124469 64682 124469 62333 124469 62333 124470 64682 124470 62308 124470 62333 124471 62308 124471 62234 124471 64684 124472 62316 124472 60184 124472 60184 124473 62316 124473 62266 124473 60184 124474 62266 124474 62265 124474 60562 124475 62313 124475 60177 124475 60177 124476 62313 124476 64686 124476 60177 124477 64686 124477 64685 124477 62332 124478 62314 124478 60182 124478 60182 124479 62314 124479 62315 124479 60182 124480 62315 124480 62235 124480 60178 124481 62237 124481 62236 124481 62236 124482 62237 124482 62238 124482 62236 124483 62238 124483 62239 124483 64688 124484 64687 124484 60001 124484 60001 124485 64687 124485 62267 124485 60001 124486 62267 124486 60560 124486 60559 124487 62240 124487 60589 124487 60589 124488 62240 124488 62241 124488 60589 124489 62241 124489 60172 124489 62330 124490 62317 124490 62242 124490 62242 124491 62317 124491 62318 124491 62242 124492 62318 124492 60175 124492 62243 124493 62244 124493 60002 124493 60002 124494 62244 124494 62245 124494 60002 124495 62245 124495 62328 124495 60168 124496 62320 124496 60169 124496 60169 124497 62320 124497 62321 124497 60169 124498 62321 124498 62268 124498 62249 124499 64693 124499 64692 124499 62269 124500 62246 124500 62247 124500 62247 124501 62246 124501 62249 124501 62247 124502 62249 124502 62248 124502 62248 124503 62249 124503 64692 124503 62271 124504 62319 124504 60167 124504 60167 124505 62319 124505 64689 124505 60167 124506 64689 124506 64690 124506 64691 124507 62250 124507 62326 124507 62326 124508 62250 124508 62251 124508 62326 124509 62251 124509 62270 124509 62325 124510 62273 124510 62252 124510 62252 124511 62273 124511 62253 124511 62252 124512 62253 124512 60204 124512 62323 124513 62254 124513 62255 124513 62255 124514 62254 124514 60558 124514 62255 124515 60558 124515 60557 124515 62361 124516 62275 124516 64694 124516 64694 124517 62275 124517 62324 124517 62362 124518 64696 124518 62274 124518 62362 124519 62274 124519 62256 124519 62298 124520 60545 124520 62297 124520 62297 124521 60545 124521 62257 124521 62297 124522 62257 124522 62258 124522 62258 124523 62257 124523 60578 124523 62294 124524 62296 124524 62341 124524 62341 124525 62296 124525 62340 124525 60573 124526 62259 124526 60571 124526 60571 124527 62259 124527 62211 124527 62300 124528 62301 124528 62216 124528 62216 124529 62301 124529 62260 124529 60568 124530 62218 124530 62261 124530 62261 124531 62218 124531 62304 124531 62303 124532 62220 124532 62338 124532 62338 124533 62220 124533 62337 124533 62262 124534 62307 124534 62227 124534 62227 124535 62307 124535 62306 124535 62230 124536 62263 124536 62336 124536 62336 124537 62263 124537 62264 124537 60563 124538 62232 124538 60549 124538 60549 124539 62232 124539 62309 124539 62308 124540 62310 124540 62234 124540 62234 124541 62310 124541 62335 124541 62265 124542 62266 124542 60562 124542 60562 124543 62266 124543 62313 124543 62238 124544 62314 124544 62239 124544 62239 124545 62314 124545 62332 124545 60560 124546 62267 124546 60559 124546 60559 124547 62267 124547 62240 124547 62245 124548 62317 124548 62328 124548 62328 124549 62317 124549 62330 124549 62268 124550 62321 124550 62269 124550 62269 124551 62321 124551 62246 124551 62251 124552 62319 124552 62270 124552 62270 124553 62319 124553 62271 124553 62272 124554 62255 124554 60557 124554 62272 124555 60557 124555 62325 124555 62325 124556 60557 124556 60556 124556 62325 124557 60556 124557 62273 124557 62274 124558 62275 124558 62256 124558 62256 124559 62275 124559 62361 124559 62279 124560 62150 124560 62146 124560 62276 124561 62277 124561 62187 124561 62187 124562 62277 124562 62152 124562 62187 124563 62152 124563 62278 124563 62278 124564 62152 124564 62279 124564 62278 124565 62279 124565 62145 124565 62145 124566 62279 124566 62146 124566 62154 124567 64639 124567 62155 124567 62155 124568 64639 124568 62143 124568 62155 124569 62143 124569 62188 124569 62188 124570 62143 124570 62280 124570 62188 124571 62280 124571 64636 124571 64636 124572 62280 124572 64637 124572 64642 124573 62142 124573 62281 124573 62281 124574 62142 124574 62140 124574 62281 124575 62140 124575 62282 124575 62282 124576 62140 124576 62157 124576 62282 124577 62157 124577 64640 124577 64640 124578 62157 124578 64641 124578 64644 124579 62138 124579 62191 124579 62191 124580 62138 124580 62136 124580 62191 124581 62136 124581 62192 124581 62192 124582 62136 124582 62164 124582 62192 124583 62164 124583 62166 124583 62166 124584 62164 124584 62162 124584 62283 124585 62284 124585 62286 124585 62286 124586 62284 124586 62285 124586 62286 124587 62285 124587 62168 124587 62168 124588 62285 124588 62194 124588 62168 124589 62194 124589 64645 124589 64645 124590 62194 124590 62167 124590 64648 124591 62288 124591 62287 124591 62287 124592 62288 124592 62199 124592 62287 124593 62199 124593 62197 124593 62197 124594 62199 124594 62198 124594 62198 124595 64649 124595 62197 124595 62197 124596 64649 124596 64650 124596 62197 124597 64650 124597 64651 124597 64655 124598 62134 124598 62174 124598 62174 124599 62134 124599 62133 124599 62174 124600 62133 124600 62289 124600 62289 124601 62133 124601 62290 124601 62289 124602 62290 124602 62176 124602 62176 124603 62290 124603 64653 124603 64659 124604 62132 124604 62179 124604 62179 124605 62132 124605 62291 124605 62179 124606 62291 124606 62201 124606 62201 124607 62291 124607 62178 124607 62201 124608 62178 124608 64656 124608 64656 124609 62178 124609 64657 124609 62183 124610 64661 124610 62292 124610 62292 124611 62129 124611 62183 124611 62183 124612 62129 124612 62202 124612 62183 124613 62202 124613 62184 124613 62184 124614 62202 124614 62204 124614 62184 124615 62204 124615 62293 124615 62293 124616 62204 124616 62180 124616 62294 124617 64674 124617 62295 124617 62206 124618 64673 124618 62258 124618 62258 124619 64673 124619 62296 124619 62258 124620 62296 124620 62297 124620 62297 124621 62296 124621 62294 124621 62297 124622 62294 124622 62298 124622 62298 124623 62294 124623 62295 124623 64675 124624 62299 124624 62300 124624 62300 124625 62299 124625 62211 124625 62300 124626 62211 124626 62301 124626 62301 124627 62211 124627 62259 124627 62301 124628 62259 124628 62302 124628 62302 124629 62259 124629 62209 124629 62223 124630 64677 124630 62303 124630 62303 124631 64677 124631 62304 124631 62303 124632 62304 124632 62220 124632 62220 124633 62304 124633 62218 124633 62220 124634 62218 124634 62221 124634 62221 124635 62218 124635 62217 124635 62229 124636 62305 124636 62230 124636 62230 124637 62305 124637 62306 124637 62230 124638 62306 124638 62263 124638 62263 124639 62306 124639 62307 124639 62263 124640 62307 124640 64678 124640 64678 124641 62307 124641 62225 124641 64682 124642 64683 124642 62308 124642 62308 124643 64683 124643 62309 124643 62308 124644 62309 124644 62310 124644 62310 124645 62309 124645 62232 124645 62310 124646 62232 124646 62311 124646 62311 124647 62232 124647 62312 124647 62237 124648 64686 124648 62238 124648 62238 124649 64686 124649 62313 124649 62238 124650 62313 124650 62314 124650 62314 124651 62313 124651 62266 124651 62314 124652 62266 124652 62315 124652 62315 124653 62266 124653 62316 124653 62244 124654 62241 124654 62245 124654 62245 124655 62241 124655 62240 124655 62245 124656 62240 124656 62317 124656 62317 124657 62240 124657 62267 124657 62317 124658 62267 124658 62318 124658 62318 124659 62267 124659 64687 124659 62249 124660 62322 124660 64693 124660 64689 124661 62319 124661 62320 124661 62320 124662 62319 124662 62321 124662 62321 124663 62319 124663 62246 124663 62246 124664 62319 124664 62251 124664 62246 124665 62251 124665 62249 124665 62249 124666 62251 124666 62250 124666 62249 124667 62250 124667 62322 124667 62274 124668 64696 124668 62323 124668 62252 124669 62324 124669 62325 124669 62325 124670 62324 124670 62275 124670 62325 124671 62275 124671 62272 124671 62272 124672 62275 124672 62274 124672 62272 124673 62274 124673 62255 124673 62255 124674 62274 124674 62323 124674 62326 124675 62270 124675 62327 124675 62327 124676 62270 124676 62271 124676 62327 124677 62271 124677 60167 124677 60002 124678 62328 124678 62329 124678 62329 124679 62328 124679 62330 124679 62329 124680 62330 124680 62242 124680 62236 124681 62239 124681 62331 124681 62331 124682 62239 124682 62332 124682 62331 124683 62332 124683 60182 124683 62333 124684 62234 124684 62334 124684 62334 124685 62234 124685 62335 124685 62334 124686 62335 124686 60217 124686 62264 124687 62228 124687 62336 124687 62336 124688 62228 124688 60228 124688 62336 124689 60228 124689 60216 124689 62337 124690 60234 124690 62338 124690 62338 124691 60234 124691 62339 124691 62338 124692 62339 124692 62224 124692 62260 124693 60239 124693 62216 124693 62216 124694 60239 124694 60238 124694 62216 124695 60238 124695 62215 124695 62340 124696 60213 124696 62341 124696 62341 124697 60213 124697 60246 124697 62341 124698 60246 124698 62208 124698 62342 124699 60086 124699 62343 124699 62343 124700 60086 124700 60087 124700 62343 124701 60087 124701 62344 124701 62345 124702 62347 124702 62346 124702 62346 124703 62347 124703 62348 124703 62346 124704 62348 124704 62349 124704 62175 124705 62350 124705 62351 124705 62351 124706 62350 124706 62173 124706 62351 124707 62173 124707 62200 124707 62171 124708 60108 124708 62352 124708 62352 124709 60108 124709 62353 124709 62352 124710 62353 124710 62170 124710 62195 124711 62169 124711 62354 124711 62354 124712 62169 124712 60105 124712 62354 124713 60105 124713 60104 124713 62193 124714 62356 124714 62355 124714 62355 124715 62356 124715 62357 124715 62355 124716 62357 124716 62165 124716 62159 124717 62160 124717 62190 124717 62190 124718 62160 124718 60139 124718 62190 124719 60139 124719 60137 124719 62189 124720 62358 124720 62359 124720 62359 124721 62358 124721 62360 124721 62359 124722 62360 124722 60142 124722 60155 124723 60149 124723 62153 124723 62153 124724 60149 124724 60148 124724 62153 124725 60148 124725 62151 124725 62361 124726 64694 124726 62256 124726 62256 124727 64694 124727 60206 124727 62256 124728 60206 124728 62362 124728 60016 124729 62363 124729 62364 124729 62364 124730 62363 124730 62652 124730 62364 124731 62652 124731 60193 124731 60193 124732 62652 124732 62653 124732 60193 124733 62653 124733 62365 124733 62365 124734 62653 124734 62366 124734 62365 124735 62366 124735 59996 124735 59996 124736 62366 124736 59997 124736 62367 124737 62655 124737 60015 124737 60015 124738 62655 124738 62654 124738 60015 124739 62654 124739 60016 124739 60016 124740 62654 124740 62649 124740 60016 124741 62649 124741 62363 124741 62708 124742 60032 124742 62712 124742 62712 124743 60032 124743 62368 124743 62712 124744 62368 124744 62713 124744 62374 124745 62369 124745 62368 124745 62368 124746 62369 124746 62370 124746 62368 124747 62370 124747 62713 124747 59992 124748 59994 124748 62371 124748 62371 124749 59994 124749 62372 124749 62371 124750 62372 124750 62373 124750 62373 124751 62372 124751 62716 124751 62373 124752 62716 124752 62374 124752 62374 124753 62716 124753 62715 124753 62374 124754 62715 124754 62369 124754 62375 124755 62376 124755 59982 124755 59982 124756 62376 124756 62377 124756 59982 124757 62377 124757 59981 124757 60064 124758 59985 124758 62378 124758 62378 124759 59985 124759 62620 124759 62378 124760 62620 124760 60065 124760 60065 124761 62620 124761 62379 124761 60065 124762 62379 124762 62380 124762 62380 124763 62379 124763 62618 124763 62380 124764 62618 124764 60303 124764 60303 124765 62618 124765 62616 124765 60303 124766 62616 124766 62375 124766 62375 124767 62616 124767 62615 124767 62375 124768 62615 124768 62376 124768 62707 124769 60055 124769 62381 124769 62381 124770 60055 124770 62382 124770 62381 124771 62382 124771 62670 124771 62670 124772 62382 124772 62383 124772 62670 124773 62383 124773 62669 124773 62669 124774 62383 124774 60054 124774 62669 124775 60054 124775 62384 124775 62384 124776 60054 124776 62385 124776 62384 124777 62385 124777 62386 124777 62386 124778 62385 124778 62388 124778 62386 124779 62388 124779 62387 124779 62387 124780 62388 124780 62389 124780 62387 124781 62389 124781 62390 124781 62763 124782 60058 124782 62391 124782 62391 124783 60058 124783 60057 124783 62391 124784 60057 124784 62746 124784 62392 124785 62732 124785 62394 124785 62394 124786 62732 124786 62393 124786 62394 124787 62393 124787 62395 124787 62395 124788 62393 124788 62737 124788 62395 124789 62737 124789 62396 124789 62396 124790 62737 124790 62398 124790 62396 124791 62398 124791 62397 124791 62397 124792 62398 124792 62746 124792 62397 124793 62746 124793 62399 124793 62399 124794 62746 124794 60057 124794 59983 124795 60063 124795 62400 124795 62400 124796 60063 124796 60062 124796 62400 124797 60062 124797 62564 124797 62564 124798 60062 124798 60060 124798 62564 124799 60060 124799 62401 124799 62401 124800 60060 124800 62404 124800 62401 124801 62404 124801 62402 124801 62402 124802 62404 124802 62403 124802 62403 124803 62404 124803 62405 124803 62403 124804 62405 124804 62406 124804 62406 124805 62405 124805 62550 124805 62550 124806 62405 124806 62407 124806 62550 124807 62407 124807 62408 124807 62409 124808 59918 124808 62410 124808 62409 124809 62410 124809 62411 124809 62411 124810 62410 124810 60021 124810 62411 124811 60021 124811 62598 124811 62598 124812 60021 124812 62412 124812 62598 124813 62412 124813 62596 124813 62596 124814 62412 124814 60019 124814 62596 124815 60019 124815 62589 124815 62589 124816 60019 124816 60018 124816 62589 124817 60018 124817 62413 124817 62413 124818 60018 124818 62414 124818 62414 124819 60018 124819 62415 124819 62414 124820 62415 124820 62416 124820 59991 124821 62417 124821 62783 124821 62783 124822 62417 124822 60038 124822 62783 124823 60038 124823 62418 124823 62418 124824 60038 124824 62419 124824 62418 124825 62419 124825 62785 124825 62785 124826 62419 124826 62424 124826 59922 124827 62421 124827 62420 124827 62420 124828 62421 124828 62772 124828 62420 124829 62772 124829 62422 124829 62422 124830 62772 124830 62423 124830 62422 124831 62423 124831 62424 124831 62424 124832 62423 124832 62782 124832 62424 124833 62782 124833 62785 124833 62427 124834 62433 124834 62429 124834 62498 124835 62437 124835 62425 124835 62425 124836 62437 124836 62436 124836 62425 124837 62436 124837 62426 124837 62426 124838 62436 124838 62427 124838 62426 124839 62427 124839 62428 124839 62428 124840 62427 124840 62429 124840 62434 124841 62430 124841 62432 124841 62432 124842 62430 124842 62431 124842 62432 124843 62431 124843 62433 124843 62433 124844 62431 124844 62500 124844 62433 124845 62500 124845 62429 124845 62438 124846 62434 124846 62440 124846 62440 124847 62434 124847 62432 124847 62440 124848 62432 124848 62435 124848 62435 124849 62432 124849 62433 124849 62435 124850 62433 124850 62442 124850 62442 124851 62433 124851 62427 124851 62442 124852 62427 124852 62445 124852 62445 124853 62427 124853 62436 124853 62445 124854 62436 124854 62446 124854 62446 124855 62436 124855 62437 124855 59690 124856 62438 124856 62439 124856 62439 124857 62438 124857 62440 124857 62439 124858 62440 124858 62441 124858 62441 124859 62440 124859 62435 124859 62441 124860 62435 124860 62449 124860 62449 124861 62435 124861 62442 124861 62449 124862 62442 124862 62443 124862 62443 124863 62442 124863 62445 124863 62443 124864 62445 124864 62444 124864 62444 124865 62445 124865 62446 124865 59691 124866 59690 124866 62447 124866 62447 124867 59690 124867 62439 124867 62447 124868 62439 124868 62455 124868 62455 124869 62439 124869 62441 124869 62455 124870 62441 124870 62453 124870 62453 124871 62441 124871 62449 124871 62453 124872 62449 124872 62448 124872 62448 124873 62449 124873 62443 124873 62448 124874 62443 124874 62450 124874 62450 124875 62443 124875 62444 124875 62450 124876 62451 124876 62448 124876 62448 124877 62451 124877 62452 124877 62448 124878 62452 124878 62453 124878 62453 124879 62452 124879 62474 124879 62453 124880 62474 124880 62455 124880 62455 124881 62474 124881 62454 124881 62455 124882 62454 124882 62447 124882 62447 124883 62454 124883 62477 124883 62447 124884 62477 124884 59691 124884 59693 124885 62456 124885 62477 124885 62477 124886 62456 124886 59692 124886 62477 124887 59692 124887 59691 124887 59949 124888 59947 124888 62473 124888 62473 124889 59947 124889 62457 124889 62473 124890 62457 124890 62475 124890 62475 124891 62457 124891 62458 124891 62475 124892 62458 124892 62476 124892 62476 124893 62458 124893 62462 124893 62476 124894 62462 124894 62459 124894 62459 124895 62462 124895 62463 124895 59947 124896 59945 124896 62457 124896 62457 124897 59945 124897 62460 124897 62457 124898 62460 124898 62458 124898 62458 124899 62460 124899 62461 124899 62458 124900 62461 124900 62462 124900 62462 124901 62461 124901 62465 124901 62462 124902 62465 124902 62463 124902 62463 124903 62465 124903 62466 124903 59945 124904 62464 124904 62460 124904 62460 124905 62464 124905 62472 124905 62460 124906 62472 124906 62461 124906 62461 124907 62472 124907 62471 124907 62461 124908 62471 124908 62465 124908 62465 124909 62471 124909 62469 124909 62465 124910 62469 124910 62466 124910 62466 124911 62469 124911 62467 124911 62483 124912 62467 124912 62468 124912 62468 124913 62467 124913 62469 124913 62468 124914 62469 124914 62485 124914 62485 124915 62469 124915 62471 124915 62485 124916 62471 124916 62470 124916 62470 124917 62471 124917 62472 124917 62470 124918 62472 124918 59942 124918 59942 124919 62472 124919 62464 124919 62451 124920 59949 124920 62452 124920 62452 124921 59949 124921 62473 124921 62452 124922 62473 124922 62474 124922 62474 124923 62473 124923 62475 124923 62474 124924 62475 124924 62454 124924 62454 124925 62475 124925 62476 124925 62454 124926 62476 124926 62477 124926 62477 124927 62476 124927 62459 124927 62477 124928 62459 124928 59693 124928 59693 124929 62459 124929 62463 124929 59693 124930 62463 124930 62478 124930 62478 124931 62463 124931 62466 124931 62478 124932 62466 124932 62479 124932 62479 124933 62466 124933 62467 124933 62479 124934 62467 124934 62480 124934 62480 124935 62467 124935 62483 124935 62480 124936 62483 124936 62481 124936 62487 124937 62481 124937 62482 124937 62482 124938 62481 124938 62483 124938 62482 124939 62483 124939 62489 124939 62489 124940 62483 124940 62468 124940 62489 124941 62468 124941 62484 124941 62484 124942 62468 124942 62485 124942 62484 124943 62485 124943 62486 124943 62486 124944 62485 124944 62470 124944 62486 124945 62470 124945 62493 124945 62493 124946 62470 124946 59942 124946 59759 124947 62487 124947 62488 124947 62488 124948 62487 124948 62482 124948 62488 124949 62482 124949 62503 124949 62503 124950 62482 124950 62489 124950 62503 124951 62489 124951 62490 124951 62490 124952 62489 124952 62484 124952 62490 124953 62484 124953 62491 124953 62491 124954 62484 124954 62486 124954 62491 124955 62486 124955 62492 124955 62492 124956 62486 124956 62493 124956 62499 124957 62501 124957 59697 124957 62408 124958 62495 124958 62494 124958 62494 124959 62495 124959 62497 124959 59697 124960 62551 124960 62499 124960 62499 124961 62551 124961 62496 124961 62499 124962 62496 124962 62497 124962 62497 124963 62496 124963 62554 124963 62497 124964 62554 124964 62494 124964 62428 124965 62499 124965 62426 124965 62426 124966 62499 124966 62497 124966 62426 124967 62497 124967 62425 124967 62425 124968 62497 124968 62495 124968 62425 124969 62495 124969 62498 124969 62428 124970 62429 124970 62499 124970 62499 124971 62429 124971 62500 124971 62499 124972 62500 124972 62501 124972 62501 124973 62500 124973 62431 124973 62501 124974 62431 124974 59688 124974 59688 124975 62431 124975 62430 124975 62502 124976 62572 124976 62547 124976 62527 124977 62570 124977 62525 124977 62491 124978 62492 124978 62505 124978 62490 124979 62491 124979 62516 124979 62503 124980 62490 124980 62517 124980 62488 124981 62503 124981 62504 124981 59759 124982 62488 124982 62510 124982 62491 124983 62505 124983 62516 124983 62516 124984 62505 124984 62506 124984 62516 124985 62506 124985 62507 124985 62507 124986 62506 124986 59930 124986 62507 124987 59930 124987 62508 124987 62508 124988 59930 124988 59931 124988 62508 124989 59931 124989 62519 124989 59759 124990 62510 124990 62509 124990 62509 124991 62510 124991 62511 124991 62509 124992 62511 124992 62512 124992 62512 124993 62511 124993 62534 124993 62512 124994 62534 124994 59808 124994 59808 124995 62534 124995 62536 124995 59808 124996 62536 124996 59809 124996 59931 124997 62513 124997 62519 124997 62519 124998 62513 124998 59924 124998 62519 124999 59924 124999 62520 124999 62520 125000 59924 125000 59926 125000 62520 125001 59926 125001 62514 125001 62514 125002 59926 125002 59933 125002 62514 125003 59933 125003 62523 125003 59933 125004 59935 125004 62523 125004 62523 125005 59935 125005 62515 125005 62523 125006 62515 125006 62524 125006 62524 125007 62515 125007 59938 125007 62524 125008 59938 125008 62526 125008 62490 125009 62516 125009 62517 125009 62517 125010 62516 125010 62507 125010 62517 125011 62507 125011 62518 125011 62518 125012 62507 125012 62508 125012 62518 125013 62508 125013 62528 125013 62528 125014 62508 125014 62519 125014 62528 125015 62519 125015 62530 125015 62530 125016 62519 125016 62520 125016 62530 125017 62520 125017 62531 125017 62531 125018 62520 125018 62514 125018 62531 125019 62514 125019 62521 125019 62521 125020 62514 125020 62523 125020 62521 125021 62523 125021 62522 125021 62522 125022 62523 125022 62524 125022 62522 125023 62524 125023 62525 125023 62525 125024 62524 125024 62526 125024 62525 125025 62526 125025 62527 125025 62503 125026 62517 125026 62504 125026 62504 125027 62517 125027 62518 125027 62504 125028 62518 125028 62532 125028 62532 125029 62518 125029 62528 125029 62532 125030 62528 125030 62533 125030 62533 125031 62528 125031 62530 125031 62533 125032 62530 125032 62529 125032 62529 125033 62530 125033 62531 125033 62529 125034 62531 125034 62535 125034 62535 125035 62531 125035 62521 125035 62535 125036 62521 125036 62538 125036 62538 125037 62521 125037 62522 125037 62538 125038 62522 125038 62540 125038 62540 125039 62522 125039 62525 125039 62540 125040 62525 125040 62541 125040 62541 125041 62525 125041 62570 125041 62541 125042 62570 125042 62542 125042 62488 125043 62504 125043 62510 125043 62510 125044 62504 125044 62532 125044 62510 125045 62532 125045 62511 125045 62511 125046 62532 125046 62533 125046 62511 125047 62533 125047 62534 125047 62534 125048 62533 125048 62529 125048 62534 125049 62529 125049 62536 125049 62536 125050 62529 125050 62535 125050 62536 125051 62535 125051 62537 125051 62537 125052 62535 125052 62538 125052 62537 125053 62538 125053 62545 125053 62545 125054 62538 125054 62540 125054 62545 125055 62540 125055 62539 125055 62539 125056 62540 125056 62541 125056 62539 125057 62541 125057 62547 125057 62547 125058 62541 125058 62542 125058 62547 125059 62542 125059 62502 125059 59809 125060 62536 125060 62543 125060 62543 125061 62536 125061 62537 125061 62543 125062 62537 125062 62544 125062 62544 125063 62537 125063 62545 125063 62544 125064 62545 125064 62546 125064 62546 125065 62545 125065 62539 125065 62546 125066 62539 125066 59757 125066 59757 125067 62539 125067 62547 125067 59757 125068 62547 125068 62548 125068 62548 125069 62547 125069 62572 125069 62548 125070 62572 125070 62549 125070 62564 125071 62401 125071 62566 125071 62402 125072 62403 125072 62555 125072 62406 125073 62550 125073 62557 125073 62557 125074 62550 125074 62408 125074 59697 125075 62559 125075 62551 125075 62551 125076 62559 125076 62552 125076 62551 125077 62552 125077 62496 125077 62496 125078 62552 125078 62553 125078 62496 125079 62553 125079 62554 125079 62554 125080 62553 125080 62557 125080 62554 125081 62557 125081 62494 125081 62494 125082 62557 125082 62408 125082 62403 125083 62406 125083 62555 125083 62555 125084 62406 125084 62557 125084 62555 125085 62557 125085 62556 125085 62556 125086 62557 125086 62553 125086 62556 125087 62553 125087 62558 125087 62558 125088 62553 125088 62552 125088 62558 125089 62552 125089 62563 125089 62563 125090 62552 125090 62559 125090 62401 125091 62402 125091 62566 125091 62566 125092 62402 125092 62555 125092 62566 125093 62555 125093 62560 125093 62560 125094 62555 125094 62556 125094 62560 125095 62556 125095 62561 125095 62561 125096 62556 125096 62558 125096 62561 125097 62558 125097 62562 125097 62562 125098 62558 125098 62563 125098 62400 125099 62564 125099 62565 125099 62565 125100 62564 125100 62566 125100 62565 125101 62566 125101 62567 125101 62567 125102 62566 125102 62560 125102 62567 125103 62560 125103 62569 125103 62569 125104 62560 125104 62561 125104 62569 125105 62561 125105 59699 125105 59699 125106 62561 125106 62562 125106 59983 125107 62400 125107 62587 125107 62587 125108 62400 125108 62565 125108 62587 125109 62565 125109 62586 125109 62586 125110 62565 125110 62567 125110 62586 125111 62567 125111 62584 125111 62584 125112 62567 125112 62569 125112 62584 125113 62569 125113 62568 125113 62568 125114 62569 125114 59699 125114 62570 125115 62527 125115 62575 125115 62526 125116 59938 125116 59919 125116 62570 125117 62575 125117 62542 125117 62542 125118 62575 125118 62571 125118 62542 125119 62571 125119 62502 125119 62571 125120 59750 125120 62573 125120 62502 125121 62571 125121 62572 125121 62572 125122 62571 125122 62573 125122 62572 125123 62573 125123 62549 125123 62409 125124 62574 125124 59919 125124 59919 125125 62574 125125 62575 125125 59919 125126 62575 125126 62526 125126 62526 125127 62575 125127 62527 125127 59753 125128 59750 125128 62576 125128 62576 125129 59750 125129 62571 125129 62576 125130 62571 125130 62577 125130 62577 125131 62571 125131 62575 125131 62577 125132 62575 125132 62578 125132 62578 125133 62575 125133 62574 125133 59696 125134 59695 125134 62585 125134 62585 125135 59695 125135 62579 125135 62585 125136 62579 125136 62580 125136 62580 125137 62579 125137 62581 125137 62580 125138 62581 125138 62582 125138 62582 125139 62581 125139 62583 125139 62582 125140 62583 125140 59984 125140 59984 125141 62583 125141 59985 125141 62568 125142 59696 125142 62584 125142 62584 125143 59696 125143 62585 125143 62584 125144 62585 125144 62586 125144 62586 125145 62585 125145 62580 125145 62586 125146 62580 125146 62587 125146 62587 125147 62580 125147 62582 125147 62587 125148 62582 125148 59983 125148 59983 125149 62582 125149 59984 125149 62599 125150 59752 125150 59751 125150 62590 125151 62631 125151 62607 125151 62416 125152 62590 125152 62588 125152 62416 125153 62588 125153 62414 125153 62414 125154 62588 125154 62592 125154 62414 125155 62592 125155 62413 125155 62413 125156 62592 125156 62589 125156 62589 125157 62592 125157 62594 125157 62589 125158 62594 125158 62596 125158 62590 125159 62607 125159 62588 125159 62588 125160 62607 125160 62591 125160 62588 125161 62591 125161 62592 125161 62592 125162 62591 125162 62593 125162 62592 125163 62593 125163 62594 125163 62594 125164 62593 125164 62595 125164 62594 125165 62595 125165 62597 125165 62596 125166 62594 125166 62598 125166 62598 125167 62594 125167 62597 125167 62598 125168 62597 125168 62411 125168 62599 125169 59751 125169 62600 125169 62600 125170 59751 125170 62601 125170 62600 125171 62601 125171 62606 125171 62606 125172 62601 125172 62602 125172 62606 125173 62602 125173 62605 125173 62605 125174 62602 125174 62603 125174 62605 125175 62603 125175 62604 125175 62604 125176 62603 125176 59753 125176 62604 125177 59753 125177 62576 125177 62576 125178 62595 125178 62604 125178 62604 125179 62595 125179 62593 125179 62604 125180 62593 125180 62605 125180 62605 125181 62593 125181 62591 125181 62605 125182 62591 125182 62606 125182 62606 125183 62591 125183 62607 125183 62606 125184 62607 125184 62600 125184 62600 125185 62607 125185 62631 125185 62600 125186 62631 125186 62599 125186 62409 125187 62411 125187 62574 125187 62574 125188 62411 125188 62597 125188 62574 125189 62597 125189 62578 125189 62578 125190 62597 125190 62595 125190 62578 125191 62595 125191 62577 125191 62577 125192 62595 125192 62576 125192 59985 125193 62583 125193 62619 125193 62608 125194 62609 125194 62610 125194 62611 125195 59981 125195 62377 125195 62609 125196 62613 125196 62621 125196 62625 125197 62612 125197 62608 125197 62612 125198 62625 125198 59702 125198 62613 125199 62611 125199 62621 125199 62621 125200 62611 125200 62377 125200 62621 125201 62377 125201 62614 125201 62614 125202 62377 125202 62376 125202 62376 125203 62615 125203 62614 125203 62614 125204 62615 125204 62616 125204 62614 125205 62616 125205 62617 125205 62616 125206 62618 125206 62617 125206 62617 125207 62618 125207 62379 125207 62617 125208 62379 125208 62619 125208 62619 125209 62379 125209 62620 125209 62619 125210 62620 125210 59985 125210 62609 125211 62621 125211 62610 125211 62610 125212 62621 125212 62614 125212 62610 125213 62614 125213 62622 125213 62622 125214 62614 125214 62617 125214 62622 125215 62617 125215 62623 125215 62623 125216 62617 125216 62619 125216 62623 125217 62619 125217 62624 125217 62624 125218 62619 125218 62583 125218 62624 125219 62583 125219 62581 125219 62608 125220 62610 125220 62625 125220 62625 125221 62610 125221 62622 125221 62625 125222 62622 125222 62627 125222 62627 125223 62622 125223 62623 125223 62627 125224 62623 125224 62626 125224 62626 125225 62623 125225 62624 125225 62626 125226 62624 125226 62629 125226 62629 125227 62624 125227 62581 125227 62629 125228 62581 125228 62579 125228 59702 125229 62625 125229 59701 125229 59701 125230 62625 125230 62627 125230 59701 125231 62627 125231 59700 125231 59700 125232 62627 125232 62626 125232 59700 125233 62626 125233 59694 125233 59694 125234 62626 125234 62629 125234 59694 125235 62629 125235 62628 125235 62628 125236 62629 125236 62579 125236 62628 125237 62579 125237 59695 125237 62634 125238 59752 125238 62635 125238 62635 125239 59752 125239 62599 125239 62635 125240 62599 125240 62630 125240 62630 125241 62599 125241 62631 125241 62630 125242 62631 125242 62632 125242 62632 125243 62631 125243 62590 125243 62632 125244 62590 125244 59995 125244 59995 125245 62590 125245 62416 125245 62633 125246 62634 125246 62647 125246 62647 125247 62634 125247 62635 125247 62647 125248 62635 125248 62645 125248 62645 125249 62635 125249 62630 125249 62645 125250 62630 125250 62636 125250 62636 125251 62630 125251 62632 125251 62636 125252 62632 125252 59997 125252 59997 125253 62632 125253 59995 125253 62685 125254 62667 125254 62638 125254 62638 125255 62667 125255 62681 125255 62642 125256 62688 125256 62640 125256 62637 125257 62638 125257 59979 125257 59979 125258 62638 125258 62681 125258 59979 125259 62681 125259 62390 125259 62639 125260 62641 125260 62640 125260 59981 125261 62611 125261 62637 125261 62637 125262 62611 125262 62639 125262 62637 125263 62639 125263 62638 125263 62638 125264 62639 125264 62640 125264 62638 125265 62640 125265 62685 125265 62685 125266 62640 125266 62688 125266 62611 125267 62613 125267 62639 125267 62639 125268 62613 125268 62609 125268 62639 125269 62609 125269 62641 125269 62641 125270 62609 125270 62608 125270 62641 125271 62608 125271 62612 125271 62642 125272 62640 125272 62643 125272 62643 125273 62640 125273 62641 125273 62643 125274 62641 125274 59704 125274 59704 125275 62641 125275 62612 125275 59704 125276 62612 125276 59702 125276 62664 125277 62694 125277 62644 125277 62660 125278 62696 125278 62659 125278 62645 125279 62636 125279 62646 125279 62647 125280 62645 125280 62648 125280 62633 125281 62647 125281 62661 125281 62649 125282 62650 125282 62363 125282 62363 125283 62650 125283 62651 125283 62363 125284 62651 125284 62652 125284 62652 125285 62651 125285 62657 125285 62652 125286 62657 125286 62653 125286 62653 125287 62657 125287 62646 125287 62653 125288 62646 125288 62366 125288 62366 125289 62646 125289 62636 125289 62366 125290 62636 125290 59997 125290 62649 125291 62654 125291 62650 125291 62650 125292 62654 125292 62655 125292 62650 125293 62655 125293 62689 125293 62645 125294 62646 125294 62648 125294 62648 125295 62646 125295 62657 125295 62648 125296 62657 125296 62656 125296 62656 125297 62657 125297 62651 125297 62656 125298 62651 125298 62658 125298 62658 125299 62651 125299 62650 125299 62658 125300 62650 125300 62659 125300 62659 125301 62650 125301 62689 125301 62659 125302 62689 125302 62660 125302 62647 125303 62648 125303 62661 125303 62661 125304 62648 125304 62656 125304 62661 125305 62656 125305 62662 125305 62662 125306 62656 125306 62658 125306 62662 125307 62658 125307 62663 125307 62663 125308 62658 125308 62659 125308 62663 125309 62659 125309 62644 125309 62644 125310 62659 125310 62696 125310 62644 125311 62696 125311 62664 125311 62633 125312 62661 125312 59755 125312 59755 125313 62661 125313 62662 125313 59755 125314 62662 125314 62665 125314 62665 125315 62662 125315 62663 125315 62665 125316 62663 125316 62666 125316 62666 125317 62663 125317 62644 125317 62666 125318 62644 125318 59756 125318 59756 125319 62644 125319 62694 125319 59756 125320 62694 125320 62690 125320 62667 125321 62685 125321 62680 125321 62673 125322 62672 125322 62671 125322 62668 125323 62673 125323 62674 125323 59710 125324 62668 125324 62682 125324 62386 125325 62679 125325 62384 125325 62384 125326 62679 125326 62677 125326 62384 125327 62677 125327 62669 125327 62669 125328 62677 125328 62675 125328 62669 125329 62675 125329 62670 125329 62670 125330 62675 125330 62671 125330 62670 125331 62671 125331 62381 125331 62381 125332 62671 125332 62672 125332 62381 125333 62672 125333 62707 125333 62386 125334 62387 125334 62679 125334 62679 125335 62387 125335 62390 125335 62679 125336 62390 125336 62681 125336 62673 125337 62671 125337 62674 125337 62674 125338 62671 125338 62675 125338 62674 125339 62675 125339 62676 125339 62676 125340 62675 125340 62677 125340 62676 125341 62677 125341 62678 125341 62678 125342 62677 125342 62679 125342 62678 125343 62679 125343 62680 125343 62680 125344 62679 125344 62681 125344 62680 125345 62681 125345 62667 125345 62668 125346 62674 125346 62682 125346 62682 125347 62674 125347 62676 125347 62682 125348 62676 125348 62687 125348 62687 125349 62676 125349 62678 125349 62687 125350 62678 125350 62683 125350 62683 125351 62678 125351 62680 125351 62683 125352 62680 125352 62684 125352 62684 125353 62680 125353 62685 125353 62684 125354 62685 125354 62688 125354 59710 125355 62682 125355 62686 125355 62686 125356 62682 125356 62687 125356 62686 125357 62687 125357 59711 125357 59711 125358 62687 125358 62683 125358 59711 125359 62683 125359 59712 125359 59712 125360 62683 125360 62684 125360 59712 125361 62684 125361 59713 125361 59713 125362 62684 125362 62688 125362 59713 125363 62688 125363 62642 125363 62696 125364 62660 125364 62695 125364 62695 125365 62660 125365 62689 125365 62693 125366 62690 125366 62694 125366 59987 125367 62695 125367 59989 125367 59989 125368 62695 125368 62689 125368 59989 125369 62689 125369 62655 125369 62700 125370 62692 125370 62691 125370 59740 125371 59742 125371 62692 125371 62692 125372 59742 125372 62693 125372 62692 125373 62693 125373 62691 125373 62691 125374 62693 125374 62694 125374 62691 125375 62694 125375 62664 125375 62708 125376 62710 125376 59987 125376 59987 125377 62710 125377 62700 125377 59987 125378 62700 125378 62695 125378 62695 125379 62700 125379 62691 125379 62695 125380 62691 125380 62696 125380 62696 125381 62691 125381 62664 125381 62697 125382 59740 125382 62698 125382 62698 125383 59740 125383 62692 125383 62698 125384 62692 125384 62699 125384 62699 125385 62692 125385 62700 125385 62699 125386 62700 125386 62709 125386 62709 125387 62700 125387 62710 125387 59708 125388 62736 125388 62706 125388 62706 125389 62736 125389 62701 125389 62706 125390 62701 125390 62702 125390 62702 125391 62701 125391 62734 125391 62702 125392 62734 125392 62703 125392 62703 125393 62734 125393 62704 125393 62703 125394 62704 125394 62705 125394 62705 125395 62704 125395 62732 125395 59710 125396 59708 125396 62668 125396 62668 125397 59708 125397 62706 125397 62668 125398 62706 125398 62673 125398 62673 125399 62706 125399 62702 125399 62673 125400 62702 125400 62672 125400 62672 125401 62702 125401 62703 125401 62672 125402 62703 125402 62707 125402 62707 125403 62703 125403 62705 125403 59994 125404 62757 125404 62720 125404 62710 125405 62708 125405 62712 125405 62699 125406 62709 125406 62711 125406 62698 125407 62699 125407 62717 125407 62697 125408 62698 125408 62725 125408 62709 125409 62710 125409 62711 125409 62711 125410 62710 125410 62712 125410 62711 125411 62712 125411 62714 125411 62712 125412 62713 125412 62714 125412 62714 125413 62713 125413 62370 125413 62714 125414 62370 125414 62719 125414 62719 125415 62370 125415 62369 125415 62369 125416 62715 125416 62719 125416 62719 125417 62715 125417 62716 125417 62719 125418 62716 125418 62720 125418 62720 125419 62716 125419 62372 125419 62720 125420 62372 125420 59994 125420 62699 125421 62711 125421 62717 125421 62717 125422 62711 125422 62714 125422 62717 125423 62714 125423 62718 125423 62718 125424 62714 125424 62719 125424 62718 125425 62719 125425 62721 125425 62721 125426 62719 125426 62720 125426 62721 125427 62720 125427 62722 125427 62722 125428 62720 125428 62757 125428 62722 125429 62757 125429 62756 125429 62698 125430 62717 125430 62725 125430 62725 125431 62717 125431 62718 125431 62725 125432 62718 125432 62723 125432 62723 125433 62718 125433 62721 125433 62723 125434 62721 125434 62729 125434 62729 125435 62721 125435 62722 125435 62729 125436 62722 125436 62724 125436 62724 125437 62722 125437 62756 125437 62724 125438 62756 125438 62731 125438 62697 125439 62725 125439 62726 125439 62726 125440 62725 125440 62723 125440 62726 125441 62723 125441 62727 125441 62727 125442 62723 125442 62729 125442 62727 125443 62729 125443 62728 125443 62728 125444 62729 125444 62724 125444 62728 125445 62724 125445 62730 125445 62730 125446 62724 125446 62731 125446 62730 125447 62731 125447 62754 125447 62393 125448 62732 125448 62739 125448 62739 125449 62732 125449 62704 125449 62739 125450 62704 125450 62733 125450 62733 125451 62704 125451 62734 125451 62733 125452 62734 125452 62742 125452 62742 125453 62734 125453 62701 125453 62742 125454 62701 125454 62735 125454 62735 125455 62701 125455 62736 125455 62737 125456 62393 125456 62738 125456 62738 125457 62393 125457 62739 125457 62738 125458 62739 125458 62740 125458 62740 125459 62739 125459 62733 125459 62740 125460 62733 125460 62741 125460 62741 125461 62733 125461 62742 125461 62741 125462 62742 125462 59706 125462 59706 125463 62742 125463 62735 125463 59706 125464 62743 125464 62741 125464 62741 125465 62743 125465 62744 125465 62741 125466 62744 125466 62740 125466 62740 125467 62744 125467 62745 125467 62740 125468 62745 125468 62738 125468 62738 125469 62745 125469 62751 125469 62738 125470 62751 125470 62737 125470 62391 125471 62746 125471 62751 125471 62751 125472 62746 125472 62398 125472 62751 125473 62398 125473 62737 125473 62748 125474 62750 125474 62769 125474 62769 125475 62770 125475 62748 125475 62748 125476 62770 125476 62747 125476 62748 125477 62747 125477 62749 125477 62753 125478 62752 125478 62766 125478 62766 125479 62752 125479 62749 125479 62766 125480 62749 125480 62767 125480 62767 125481 62749 125481 62747 125481 62743 125482 62750 125482 62744 125482 62744 125483 62750 125483 62748 125483 62744 125484 62748 125484 62745 125484 62745 125485 62748 125485 62749 125485 62745 125486 62749 125486 62751 125486 62751 125487 62749 125487 62752 125487 62751 125488 62752 125488 62391 125488 62391 125489 62752 125489 62753 125489 62391 125490 62753 125490 62763 125490 59730 125491 62754 125491 62759 125491 62759 125492 62754 125492 62731 125492 62759 125493 62731 125493 62755 125493 62755 125494 62731 125494 62756 125494 62755 125495 62756 125495 62761 125495 62761 125496 62756 125496 62757 125496 62761 125497 62757 125497 59993 125497 59993 125498 62757 125498 59994 125498 62788 125499 59730 125499 62758 125499 62758 125500 59730 125500 62759 125500 62758 125501 62759 125501 62760 125501 62760 125502 62759 125502 62755 125502 62760 125503 62755 125503 62786 125503 62786 125504 62755 125504 62761 125504 62786 125505 62761 125505 59991 125505 59991 125506 62761 125506 59993 125506 62753 125507 62766 125507 62768 125507 62765 125508 62807 125508 62764 125508 62822 125509 62762 125509 62768 125509 59707 125510 59709 125510 62771 125510 62771 125511 59709 125511 62837 125511 62771 125512 62837 125512 62830 125512 62763 125513 62753 125513 62764 125513 62764 125514 62753 125514 62768 125514 62764 125515 62768 125515 62765 125515 62765 125516 62768 125516 62762 125516 62766 125517 62767 125517 62768 125517 62768 125518 62767 125518 62771 125518 62768 125519 62771 125519 62822 125519 62822 125520 62771 125520 62830 125520 62769 125521 59707 125521 62770 125521 62770 125522 59707 125522 62771 125522 62770 125523 62771 125523 62747 125523 62747 125524 62771 125524 62767 125524 62423 125525 62772 125525 62774 125525 62774 125526 62772 125526 62421 125526 62845 125527 62778 125527 62844 125527 62844 125528 62778 125528 62773 125528 62844 125529 62773 125529 62775 125529 62775 125530 62773 125530 62777 125530 62421 125531 62840 125531 62774 125531 62774 125532 62840 125532 62842 125532 62774 125533 62842 125533 62777 125533 62777 125534 62842 125534 62843 125534 62777 125535 62843 125535 62775 125535 62782 125536 62423 125536 62776 125536 62776 125537 62423 125537 62774 125537 62776 125538 62774 125538 62781 125538 62781 125539 62774 125539 62777 125539 62781 125540 62777 125540 62780 125540 62780 125541 62777 125541 62773 125541 62780 125542 62773 125542 62779 125542 62779 125543 62773 125543 62778 125543 62779 125544 62789 125544 62780 125544 62780 125545 62789 125545 62790 125545 62780 125546 62790 125546 62781 125546 62781 125547 62790 125547 62791 125547 62781 125548 62791 125548 62776 125548 62776 125549 62791 125549 62784 125549 62776 125550 62784 125550 62782 125550 62783 125551 62418 125551 62784 125551 62784 125552 62418 125552 62785 125552 62784 125553 62785 125553 62782 125553 62786 125554 62793 125554 62760 125554 62760 125555 62793 125555 62787 125555 62760 125556 62787 125556 62758 125556 62758 125557 62787 125557 62792 125557 62758 125558 62792 125558 62788 125558 62788 125559 62792 125559 59733 125559 62789 125560 59733 125560 62790 125560 62790 125561 59733 125561 62792 125561 62790 125562 62792 125562 62791 125562 62791 125563 62792 125563 62787 125563 62791 125564 62787 125564 62784 125564 62784 125565 62787 125565 62793 125565 62784 125566 62793 125566 62783 125566 62783 125567 62793 125567 62786 125567 62783 125568 62786 125568 59991 125568 62862 125569 62802 125569 62801 125569 62795 125570 62862 125570 62794 125570 62859 125571 62795 125571 62796 125571 62858 125572 62859 125572 62797 125572 62798 125573 62803 125573 62799 125573 62799 125574 62803 125574 62800 125574 62799 125575 62800 125575 59956 125575 59956 125576 62800 125576 62801 125576 59956 125577 62801 125577 59954 125577 59954 125578 62801 125578 62802 125578 59954 125579 62802 125579 59967 125579 59958 125580 62811 125580 62798 125580 62798 125581 62811 125581 62810 125581 62798 125582 62810 125582 62803 125582 59958 125583 59961 125583 62811 125583 62811 125584 59961 125584 59962 125584 62811 125585 59962 125585 62804 125585 62804 125586 59962 125586 62805 125586 62804 125587 62805 125587 62813 125587 62813 125588 62805 125588 59964 125588 62813 125589 59964 125589 62806 125589 62806 125590 59964 125590 62807 125590 62806 125591 62807 125591 62765 125591 62862 125592 62801 125592 62794 125592 62794 125593 62801 125593 62800 125593 62794 125594 62800 125594 62808 125594 62808 125595 62800 125595 62803 125595 62808 125596 62803 125596 62809 125596 62809 125597 62803 125597 62810 125597 62809 125598 62810 125598 62815 125598 62815 125599 62810 125599 62811 125599 62815 125600 62811 125600 62817 125600 62817 125601 62811 125601 62804 125601 62817 125602 62804 125602 62812 125602 62812 125603 62804 125603 62813 125603 62812 125604 62813 125604 62819 125604 62819 125605 62813 125605 62806 125605 62819 125606 62806 125606 62820 125606 62820 125607 62806 125607 62765 125607 62820 125608 62765 125608 62762 125608 62795 125609 62794 125609 62796 125609 62796 125610 62794 125610 62808 125610 62796 125611 62808 125611 62814 125611 62814 125612 62808 125612 62809 125612 62814 125613 62809 125613 62824 125613 62824 125614 62809 125614 62815 125614 62824 125615 62815 125615 62816 125615 62816 125616 62815 125616 62817 125616 62816 125617 62817 125617 62825 125617 62825 125618 62817 125618 62812 125618 62825 125619 62812 125619 62818 125619 62818 125620 62812 125620 62819 125620 62818 125621 62819 125621 62829 125621 62829 125622 62819 125622 62820 125622 62829 125623 62820 125623 62821 125623 62821 125624 62820 125624 62762 125624 62821 125625 62762 125625 62822 125625 62859 125626 62796 125626 62797 125626 62797 125627 62796 125627 62814 125627 62797 125628 62814 125628 62823 125628 62823 125629 62814 125629 62824 125629 62823 125630 62824 125630 62832 125630 62832 125631 62824 125631 62816 125631 62832 125632 62816 125632 62826 125632 62826 125633 62816 125633 62825 125633 62826 125634 62825 125634 62827 125634 62827 125635 62825 125635 62818 125635 62827 125636 62818 125636 62828 125636 62828 125637 62818 125637 62829 125637 62828 125638 62829 125638 62835 125638 62835 125639 62829 125639 62821 125639 62835 125640 62821 125640 62836 125640 62836 125641 62821 125641 62822 125641 62836 125642 62822 125642 62830 125642 62858 125643 62797 125643 62831 125643 62831 125644 62797 125644 62823 125644 62831 125645 62823 125645 59720 125645 59720 125646 62823 125646 62832 125646 59720 125647 62832 125647 59721 125647 59721 125648 62832 125648 62826 125648 59721 125649 62826 125649 59722 125649 59722 125650 62826 125650 62827 125650 59722 125651 62827 125651 62833 125651 62833 125652 62827 125652 62828 125652 62833 125653 62828 125653 62834 125653 62834 125654 62828 125654 62835 125654 62834 125655 62835 125655 59715 125655 59715 125656 62835 125656 62836 125656 59715 125657 62836 125657 59716 125657 59716 125658 62836 125658 62830 125658 59716 125659 62830 125659 62837 125659 62838 125660 59732 125660 62846 125660 62421 125661 62839 125661 62840 125661 62840 125662 62839 125662 62841 125662 62840 125663 62841 125663 62842 125663 62842 125664 62841 125664 62843 125664 62843 125665 62841 125665 62846 125665 62843 125666 62846 125666 62775 125666 62775 125667 62846 125667 62844 125667 62844 125668 62846 125668 59732 125668 62844 125669 59732 125669 62845 125669 62866 125670 62838 125670 62891 125670 62891 125671 62838 125671 62846 125671 62891 125672 62846 125672 62847 125672 62847 125673 62846 125673 62841 125673 62847 125674 62841 125674 59978 125674 59978 125675 62841 125675 62839 125675 62852 125676 62913 125676 62853 125676 62853 125677 62913 125677 62849 125677 62853 125678 62849 125678 62848 125678 62848 125679 62849 125679 62903 125679 62848 125680 62903 125680 62850 125680 62850 125681 62903 125681 62881 125681 62850 125682 62881 125682 62856 125682 62856 125683 62881 125683 62880 125683 62856 125684 62880 125684 62851 125684 62851 125685 62880 125685 59965 125685 62860 125686 62852 125686 62861 125686 62861 125687 62852 125687 62853 125687 62861 125688 62853 125688 62863 125688 62863 125689 62853 125689 62848 125689 62863 125690 62848 125690 62854 125690 62854 125691 62848 125691 62850 125691 62854 125692 62850 125692 62855 125692 62855 125693 62850 125693 62856 125693 62855 125694 62856 125694 62857 125694 62857 125695 62856 125695 62851 125695 62858 125696 62860 125696 62859 125696 62859 125697 62860 125697 62861 125697 62859 125698 62861 125698 62795 125698 62795 125699 62861 125699 62863 125699 62795 125700 62863 125700 62862 125700 62862 125701 62863 125701 62854 125701 62862 125702 62854 125702 62802 125702 62802 125703 62854 125703 62855 125703 62802 125704 62855 125704 59967 125704 59967 125705 62855 125705 62857 125705 62892 125706 62864 125706 62882 125706 62864 125707 62865 125707 62869 125707 62847 125708 59978 125708 62867 125708 62866 125709 62891 125709 62893 125709 62865 125710 62867 125710 62868 125710 62865 125711 62868 125711 62869 125711 62869 125712 62868 125712 59977 125712 62869 125713 59977 125713 62870 125713 62870 125714 59977 125714 62871 125714 62870 125715 62871 125715 62876 125715 62876 125716 62871 125716 62872 125716 62876 125717 62872 125717 62877 125717 62877 125718 62872 125718 59975 125718 62877 125719 59975 125719 62873 125719 62873 125720 59975 125720 59973 125720 62873 125721 59973 125721 62878 125721 62878 125722 59973 125722 59972 125722 62878 125723 59972 125723 62874 125723 62874 125724 59972 125724 59970 125724 62874 125725 59970 125725 62875 125725 62875 125726 59970 125726 59965 125726 62875 125727 59965 125727 62880 125727 62864 125728 62869 125728 62882 125728 62882 125729 62869 125729 62870 125729 62882 125730 62870 125730 62883 125730 62883 125731 62870 125731 62876 125731 62883 125732 62876 125732 62885 125732 62885 125733 62876 125733 62877 125733 62885 125734 62877 125734 62886 125734 62886 125735 62877 125735 62873 125735 62886 125736 62873 125736 62888 125736 62888 125737 62873 125737 62878 125737 62888 125738 62878 125738 62889 125738 62889 125739 62878 125739 62874 125739 62889 125740 62874 125740 62879 125740 62879 125741 62874 125741 62875 125741 62879 125742 62875 125742 62890 125742 62890 125743 62875 125743 62880 125743 62890 125744 62880 125744 62881 125744 62892 125745 62882 125745 62894 125745 62894 125746 62882 125746 62883 125746 62894 125747 62883 125747 62884 125747 62884 125748 62883 125748 62885 125748 62884 125749 62885 125749 62895 125749 62895 125750 62885 125750 62886 125750 62895 125751 62886 125751 62897 125751 62897 125752 62886 125752 62888 125752 62897 125753 62888 125753 62887 125753 62887 125754 62888 125754 62889 125754 62887 125755 62889 125755 62900 125755 62900 125756 62889 125756 62879 125756 62900 125757 62879 125757 62901 125757 62901 125758 62879 125758 62890 125758 62901 125759 62890 125759 62902 125759 62902 125760 62890 125760 62881 125760 62902 125761 62881 125761 62903 125761 62867 125762 62865 125762 62847 125762 62847 125763 62865 125763 62864 125763 62847 125764 62864 125764 62891 125764 62891 125765 62864 125765 62892 125765 62891 125766 62892 125766 62893 125766 62893 125767 62892 125767 62894 125767 62893 125768 62894 125768 62904 125768 62904 125769 62894 125769 62884 125769 62904 125770 62884 125770 62906 125770 62906 125771 62884 125771 62895 125771 62906 125772 62895 125772 62896 125772 62896 125773 62895 125773 62897 125773 62896 125774 62897 125774 62898 125774 62898 125775 62897 125775 62887 125775 62898 125776 62887 125776 62899 125776 62899 125777 62887 125777 62900 125777 62899 125778 62900 125778 62907 125778 62907 125779 62900 125779 62901 125779 62907 125780 62901 125780 62908 125780 62908 125781 62901 125781 62902 125781 62908 125782 62902 125782 62911 125782 62911 125783 62902 125783 62903 125783 62911 125784 62903 125784 62849 125784 62866 125785 62893 125785 59726 125785 59726 125786 62893 125786 62904 125786 59726 125787 62904 125787 59727 125787 59727 125788 62904 125788 62906 125788 59727 125789 62906 125789 62905 125789 62905 125790 62906 125790 62896 125790 62905 125791 62896 125791 59728 125791 59728 125792 62896 125792 62898 125792 59728 125793 62898 125793 59724 125793 59724 125794 62898 125794 62899 125794 59724 125795 62899 125795 59725 125795 59725 125796 62899 125796 62907 125796 59725 125797 62907 125797 62909 125797 62909 125798 62907 125798 62908 125798 62909 125799 62908 125799 62910 125799 62910 125800 62908 125800 62911 125800 62910 125801 62911 125801 62912 125801 62912 125802 62911 125802 62849 125802 62912 125803 62849 125803 62913 125803 62914 125804 59487 125804 59489 125804 59493 125805 60339 125805 62915 125805 59913 125806 60347 125806 59912 125806 59912 125807 60347 125807 60346 125807 59913 125808 59915 125808 60347 125808 60347 125809 59915 125809 60343 125809 60313 125810 60312 125810 59508 125810 62917 125811 60323 125811 59486 125811 63258 125812 62916 125812 63260 125812 63260 125813 62916 125813 59439 125813 63260 125814 59439 125814 59485 125814 59486 125815 62916 125815 62917 125815 62917 125816 62916 125816 63258 125816 62917 125817 63258 125817 62918 125817 62918 125818 63258 125818 62919 125818 62918 125819 62919 125819 59998 125819 59504 125820 59998 125820 59441 125820 59441 125821 59998 125821 62919 125821 59441 125822 62919 125822 62920 125822 62920 125823 62919 125823 62973 125823 62920 125824 62973 125824 62921 125824 62921 125825 62973 125825 60315 125825 62921 125826 60315 125826 59475 125826 59475 125827 60315 125827 62922 125827 62923 125828 63260 125828 62927 125828 62927 125829 63260 125829 62925 125829 62924 125830 59497 125830 62928 125830 59902 125831 62934 125831 62923 125831 59491 125832 62925 125832 59490 125832 59490 125833 62925 125833 63260 125833 59490 125834 63260 125834 59484 125834 59484 125835 63260 125835 59485 125835 62927 125836 59482 125836 59483 125836 59500 125837 59904 125837 62933 125837 59414 125838 59418 125838 62923 125838 62926 125839 60335 125839 62929 125839 62929 125840 60335 125840 60336 125840 59483 125841 62924 125841 62927 125841 62927 125842 62924 125842 62928 125842 62927 125843 62928 125843 62923 125843 62923 125844 62928 125844 62929 125844 62923 125845 62929 125845 59902 125845 59902 125846 62929 125846 60336 125846 59902 125847 60336 125847 59903 125847 62934 125848 59901 125848 60331 125848 62930 125849 59503 125849 59414 125849 62930 125850 59414 125850 62931 125850 59418 125851 62932 125851 62923 125851 62923 125852 62932 125852 59476 125852 62923 125853 59476 125853 60325 125853 60331 125854 59500 125854 62934 125854 62934 125855 59500 125855 62933 125855 62934 125856 62933 125856 62923 125856 62923 125857 62933 125857 59421 125857 62923 125858 59421 125858 59414 125858 59414 125859 59421 125859 59477 125859 59414 125860 59477 125860 62931 125860 59512 125861 60345 125861 59408 125861 59408 125862 60345 125862 63264 125862 59408 125863 63264 125863 59407 125863 59407 125864 63264 125864 62935 125864 59407 125865 62935 125865 62936 125865 62936 125866 62935 125866 62939 125866 62936 125867 62939 125867 62937 125867 59507 125868 62937 125868 62938 125868 62938 125869 62937 125869 62939 125869 62938 125870 62939 125870 60344 125870 60344 125871 62939 125871 62942 125871 60344 125872 62942 125872 62944 125872 62946 125873 62941 125873 62940 125873 62940 125874 62941 125874 59410 125874 62940 125875 59410 125875 62942 125875 62942 125876 59410 125876 62943 125876 62942 125877 62943 125877 62944 125877 62944 125878 62943 125878 59906 125878 62944 125879 59906 125879 62945 125879 62946 125880 62940 125880 60329 125880 60329 125881 62940 125881 62923 125881 60329 125882 62923 125882 60325 125882 59448 125883 62947 125883 59447 125883 59447 125884 62947 125884 63282 125884 59447 125885 63282 125885 59454 125885 59454 125886 63282 125886 62948 125886 59453 125887 59910 125887 59911 125887 63281 125888 63233 125888 63234 125888 63234 125889 62949 125889 63281 125889 63281 125890 62949 125890 59452 125890 63281 125891 59452 125891 62950 125891 62950 125892 59452 125892 59453 125892 62950 125893 59453 125893 63282 125893 63282 125894 59453 125894 59911 125894 63282 125895 59911 125895 62948 125895 63233 125896 63281 125896 62951 125896 62951 125897 63281 125897 63278 125897 62951 125898 63278 125898 63227 125898 63207 125899 59549 125899 59543 125899 62957 125900 63174 125900 63190 125900 63146 125901 63155 125901 62955 125901 63113 125902 63109 125902 62962 125902 63277 125903 59543 125903 63278 125903 63278 125904 59543 125904 62952 125904 63278 125905 62952 125905 59558 125905 59558 125906 63223 125906 63278 125906 63278 125907 63223 125907 62953 125907 63278 125908 62953 125908 63227 125908 63083 125909 63088 125909 62959 125909 63190 125910 63194 125910 63277 125910 63277 125911 63194 125911 62954 125911 63277 125912 62954 125912 59543 125912 59543 125913 62954 125913 63212 125913 59543 125914 63212 125914 63207 125914 62955 125915 63160 125915 63277 125915 63277 125916 63160 125916 63163 125916 63277 125917 63163 125917 63190 125917 63190 125918 63163 125918 62956 125918 63190 125919 62956 125919 62957 125919 62962 125920 63127 125920 63277 125920 63277 125921 63127 125921 63133 125921 63277 125922 63133 125922 62955 125922 62955 125923 63133 125923 62958 125923 62955 125924 62958 125924 63146 125924 62964 125925 63065 125925 63277 125925 63277 125926 63065 125926 63075 125926 63277 125927 63075 125927 62959 125927 62959 125928 63075 125928 62960 125928 62959 125929 62960 125929 63083 125929 62959 125930 62961 125930 63277 125930 63277 125931 62961 125931 62963 125931 63277 125932 62963 125932 62962 125932 62962 125933 62963 125933 63105 125933 62962 125934 63105 125934 63113 125934 59403 125935 60302 125935 60301 125935 60298 125936 59525 125936 59526 125936 62964 125937 63277 125937 62965 125937 62965 125938 63277 125938 62967 125938 62965 125939 62967 125939 59526 125939 62967 125940 62966 125940 59404 125940 59404 125941 59403 125941 62967 125941 62967 125942 59403 125942 60301 125942 62967 125943 60301 125943 59526 125943 59526 125944 60301 125944 60297 125944 59526 125945 60297 125945 60298 125945 60345 125946 60349 125946 63264 125946 63264 125947 60349 125947 62968 125947 63264 125948 62968 125948 62966 125948 62966 125949 62968 125949 60306 125949 62966 125950 60306 125950 59404 125950 59404 125951 60306 125951 62969 125951 59404 125952 62969 125952 62970 125952 62971 125953 59908 125953 62972 125953 62947 125954 59448 125954 62973 125954 62973 125955 59448 125955 62971 125955 62973 125956 62971 125956 60315 125956 60315 125957 62971 125957 62972 125957 62996 125958 63371 125958 62974 125958 62974 125959 63371 125959 60037 125959 60026 125960 62975 125960 60027 125960 60027 125961 62975 125961 62976 125961 60027 125962 62976 125962 62978 125962 62978 125963 62976 125963 62977 125963 62978 125964 62977 125964 60028 125964 60028 125965 62977 125965 62979 125965 60028 125966 62979 125966 62980 125966 63371 125967 63369 125967 60037 125967 60037 125968 63369 125968 62982 125968 60037 125969 62982 125969 62981 125969 62981 125970 62982 125970 63372 125970 62981 125971 63372 125971 62983 125971 62983 125972 63372 125972 62985 125972 62983 125973 62985 125973 62984 125973 62984 125974 62985 125974 63373 125974 62984 125975 63373 125975 60023 125975 60023 125976 63373 125976 62986 125976 60023 125977 62986 125977 60024 125977 60024 125978 62986 125978 62987 125978 60024 125979 62987 125979 62988 125979 62988 125980 62987 125980 62989 125980 62988 125981 62989 125981 60022 125981 60022 125982 62989 125982 62991 125982 60022 125983 62991 125983 62990 125983 62990 125984 62991 125984 62992 125984 62990 125985 62992 125985 62993 125985 62993 125986 62992 125986 63379 125986 62993 125987 63379 125987 62994 125987 62994 125988 63379 125988 63378 125988 62994 125989 63378 125989 60026 125989 60026 125990 63378 125990 62995 125990 60026 125991 62995 125991 62975 125991 62974 125992 62997 125992 62996 125992 62996 125993 62997 125993 62998 125993 62996 125994 62998 125994 63368 125994 63368 125995 62998 125995 62999 125995 63368 125996 62999 125996 63000 125996 63000 125997 62999 125997 60035 125997 63000 125998 60035 125998 63001 125998 63001 125999 60035 125999 63006 125999 63001 126000 63006 126000 63002 126000 62979 126001 63380 126001 62980 126001 62980 126002 63380 126002 63381 126002 62980 126003 63381 126003 63003 126003 63003 126004 63381 126004 63439 126004 63003 126005 63439 126005 60029 126005 60029 126006 63439 126006 63004 126006 60029 126007 63004 126007 60030 126007 60030 126008 63004 126008 63438 126008 60030 126009 63438 126009 60031 126009 60031 126010 63438 126010 63005 126010 60031 126011 63005 126011 60033 126011 60033 126012 63005 126012 63002 126012 60033 126013 63002 126013 60034 126013 60034 126014 63002 126014 63006 126014 63025 126015 63009 126015 63023 126015 63020 126016 63022 126016 63007 126016 63007 126017 63022 126017 63303 126017 63007 126018 63303 126018 60071 126018 60071 126019 63303 126019 63008 126019 60071 126020 63008 126020 60072 126020 60072 126021 63008 126021 63308 126021 60072 126022 63308 126022 60073 126022 63023 126023 63009 126023 60077 126023 60077 126024 63009 126024 63295 126024 60077 126025 63295 126025 63010 126025 63295 126026 63293 126026 63010 126026 63010 126027 63293 126027 63296 126027 63010 126028 63296 126028 60078 126028 60078 126029 63296 126029 63297 126029 60078 126030 63297 126030 60080 126030 60080 126031 63297 126031 63011 126031 60080 126032 63011 126032 63012 126032 63012 126033 63011 126033 63014 126033 63012 126034 63014 126034 63013 126034 63013 126035 63014 126035 63299 126035 63013 126036 63299 126036 63015 126036 63015 126037 63299 126037 63016 126037 63015 126038 63016 126038 63017 126038 63017 126039 63016 126039 63300 126039 63017 126040 63300 126040 63018 126040 63018 126041 63300 126041 63301 126041 63018 126042 63301 126042 63019 126042 63019 126043 63301 126043 63307 126043 63019 126044 63307 126044 60070 126044 60070 126045 63307 126045 63305 126045 60070 126046 63305 126046 63020 126046 63020 126047 63305 126047 63021 126047 63020 126048 63021 126048 63022 126048 63023 126049 63024 126049 63025 126049 63025 126050 63024 126050 63026 126050 63025 126051 63026 126051 63291 126051 63291 126052 63026 126052 60352 126052 63291 126053 60352 126053 63027 126053 63027 126054 60352 126054 63028 126054 63027 126055 63028 126055 63290 126055 63308 126056 63309 126056 60073 126056 60073 126057 63309 126057 63029 126057 60073 126058 63029 126058 63030 126058 63030 126059 63029 126059 63031 126059 63030 126060 63031 126060 63032 126060 63032 126061 63031 126061 63034 126061 63032 126062 63034 126062 63033 126062 63033 126063 63034 126063 63035 126063 63033 126064 63035 126064 63036 126064 63036 126065 63035 126065 63037 126065 63036 126066 63037 126066 60074 126066 60074 126067 63037 126067 63038 126067 60074 126068 63038 126068 63039 126068 63039 126069 63038 126069 63290 126069 63039 126070 63290 126070 60075 126070 60075 126071 63290 126071 63028 126071 63450 126072 63441 126072 63247 126072 63247 126073 63441 126073 63242 126073 63242 126074 63441 126074 63040 126074 63242 126075 63040 126075 63041 126075 63041 126076 63040 126076 63042 126076 63041 126077 63042 126077 63050 126077 63530 126078 63043 126078 63520 126078 63520 126079 63043 126079 63045 126079 63520 126080 63045 126080 63044 126080 63044 126081 63045 126081 63046 126081 63044 126082 63046 126082 63482 126082 63482 126083 63046 126083 63047 126083 63482 126084 63047 126084 63048 126084 63048 126085 63047 126085 63050 126085 63048 126086 63050 126086 63049 126086 63049 126087 63050 126087 63042 126087 63247 126088 63248 126088 63450 126088 63450 126089 63248 126089 63249 126089 63450 126090 63249 126090 63443 126090 63443 126091 63249 126091 63051 126091 63443 126092 63051 126092 63052 126092 63052 126093 63051 126093 63251 126093 63052 126094 63251 126094 63498 126094 63498 126095 63251 126095 63268 126095 63498 126096 63268 126096 63053 126096 63053 126097 63268 126097 63269 126097 63053 126098 63269 126098 63054 126098 63054 126099 63269 126099 63272 126099 63054 126100 63272 126100 63512 126100 63512 126101 63272 126101 63280 126101 63512 126102 63280 126102 63524 126102 63524 126103 63280 126103 63055 126103 63524 126104 63055 126104 63530 126104 63530 126105 63055 126105 63056 126105 63530 126106 63056 126106 63043 126106 63057 126107 63058 126107 63059 126107 63059 126108 63058 126108 63060 126108 63060 126109 63058 126109 63061 126109 63061 126110 63058 126110 63066 126110 63061 126111 63066 126111 59527 126111 59527 126112 63066 126112 63062 126112 63062 126113 63066 126113 62964 126113 63062 126114 62964 126114 62965 126114 63073 126115 63067 126115 59473 126115 63067 126116 63073 126116 63063 126116 63073 126117 63078 126117 63063 126117 63063 126118 63078 126118 63064 126118 63063 126119 63064 126119 63065 126119 63065 126120 63064 126120 63076 126120 63065 126121 63076 126121 63075 126121 63057 126122 59473 126122 63058 126122 63058 126123 59473 126123 63067 126123 63058 126124 63067 126124 63066 126124 63066 126125 63067 126125 63063 126125 63066 126126 63063 126126 62964 126126 62964 126127 63063 126127 63065 126127 59472 126128 63068 126128 63079 126128 59472 126129 63079 126129 59473 126129 63074 126130 63073 126130 63069 126130 63069 126131 63073 126131 59473 126131 63069 126132 59473 126132 63070 126132 63070 126133 59473 126133 63079 126133 63077 126134 63078 126134 63071 126134 63071 126135 63078 126135 63073 126135 63071 126136 63073 126136 63072 126136 63072 126137 63073 126137 63074 126137 62960 126138 63075 126138 63085 126138 63085 126139 63075 126139 63076 126139 63085 126140 63076 126140 63077 126140 63077 126141 63076 126141 63064 126141 63077 126142 63064 126142 63078 126142 63074 126143 63069 126143 63086 126143 63070 126144 63079 126144 63082 126144 63080 126145 63088 126145 63083 126145 63084 126146 63081 126146 63080 126146 63081 126147 63084 126147 63093 126147 63093 126148 63084 126148 63086 126148 63093 126149 63086 126149 63090 126149 63069 126150 63070 126150 63086 126150 63086 126151 63070 126151 63082 126151 63086 126152 63082 126152 63090 126152 63090 126153 63082 126153 60369 126153 63080 126154 63083 126154 63084 126154 63084 126155 63083 126155 62960 126155 63084 126156 62960 126156 63085 126156 63085 126157 63077 126157 63084 126157 63084 126158 63077 126158 63071 126158 63084 126159 63071 126159 63086 126159 63086 126160 63071 126160 63072 126160 63086 126161 63072 126161 63074 126161 63087 126162 62959 126162 63088 126162 63091 126163 63094 126163 63081 126163 63089 126164 59469 126164 59470 126164 63089 126165 59470 126165 60369 126165 60369 126166 59470 126166 63092 126166 60369 126167 63092 126167 63090 126167 63091 126168 63081 126168 63092 126168 63092 126169 63081 126169 63093 126169 63092 126170 63093 126170 63090 126170 63087 126171 63088 126171 63094 126171 63094 126172 63088 126172 63080 126172 63094 126173 63080 126173 63081 126173 63091 126174 63092 126174 63100 126174 63100 126175 63092 126175 59470 126175 63100 126176 59470 126176 63095 126176 62961 126177 62959 126177 63096 126177 63096 126178 62959 126178 63087 126178 63096 126179 63087 126179 63094 126179 63099 126180 63097 126180 63096 126180 63096 126181 63097 126181 63098 126181 63096 126182 63098 126182 62961 126182 62961 126183 63098 126183 63106 126183 62961 126184 63106 126184 62963 126184 63094 126185 63091 126185 63096 126185 63096 126186 63091 126186 63100 126186 63096 126187 63100 126187 63099 126187 63099 126188 63100 126188 63095 126188 63099 126189 63095 126189 59468 126189 59467 126190 63101 126190 60292 126190 59467 126191 60292 126191 59468 126191 63107 126192 63099 126192 63102 126192 63102 126193 63099 126193 59468 126193 63102 126194 59468 126194 63103 126194 63103 126195 59468 126195 60292 126195 63115 126196 63097 126196 63104 126196 63104 126197 63097 126197 63099 126197 63104 126198 63099 126198 63116 126198 63116 126199 63099 126199 63107 126199 63105 126200 62963 126200 63114 126200 63114 126201 62963 126201 63106 126201 63114 126202 63106 126202 63115 126202 63115 126203 63106 126203 63098 126203 63115 126204 63098 126204 63097 126204 63107 126205 63102 126205 63112 126205 63103 126206 60292 126206 60290 126206 63108 126207 63109 126207 63113 126207 63110 126208 63120 126208 63108 126208 63120 126209 63110 126209 63122 126209 63122 126210 63110 126210 63112 126210 63122 126211 63112 126211 63111 126211 63102 126212 63103 126212 63112 126212 63112 126213 63103 126213 60290 126213 63112 126214 60290 126214 63111 126214 63111 126215 60290 126215 63118 126215 63108 126216 63113 126216 63110 126216 63110 126217 63113 126217 63105 126217 63110 126218 63105 126218 63114 126218 63114 126219 63115 126219 63110 126219 63110 126220 63115 126220 63104 126220 63110 126221 63104 126221 63112 126221 63112 126222 63104 126222 63116 126222 63112 126223 63116 126223 63107 126223 63123 126224 62962 126224 63109 126224 63119 126225 63124 126225 63120 126225 59522 126226 59520 126226 63117 126226 59522 126227 63117 126227 63118 126227 63118 126228 63117 126228 63121 126228 63118 126229 63121 126229 63111 126229 63119 126230 63120 126230 63121 126230 63121 126231 63120 126231 63122 126231 63121 126232 63122 126232 63111 126232 63123 126233 63109 126233 63124 126233 63124 126234 63109 126234 63108 126234 63124 126235 63108 126235 63120 126235 63119 126236 63121 126236 63125 126236 63125 126237 63121 126237 63117 126237 63125 126238 63117 126238 59466 126238 63127 126239 62962 126239 63126 126239 63126 126240 62962 126240 63123 126240 63126 126241 63123 126241 63124 126241 63129 126242 63136 126242 63126 126242 63126 126243 63136 126243 63135 126243 63126 126244 63135 126244 63127 126244 63127 126245 63135 126245 63128 126245 63127 126246 63128 126246 63133 126246 63124 126247 63119 126247 63126 126247 63126 126248 63119 126248 63125 126248 63126 126249 63125 126249 63129 126249 63129 126250 63125 126250 59466 126250 63129 126251 59466 126251 59465 126251 63130 126252 60289 126252 63131 126252 63130 126253 63131 126253 59465 126253 63137 126254 63129 126254 63144 126254 63144 126255 63129 126255 59465 126255 63144 126256 59465 126256 63138 126256 63138 126257 59465 126257 63131 126257 63134 126258 63136 126258 63132 126258 63132 126259 63136 126259 63129 126259 63132 126260 63129 126260 63148 126260 63148 126261 63129 126261 63137 126261 62958 126262 63133 126262 63147 126262 63147 126263 63133 126263 63128 126263 63147 126264 63128 126264 63134 126264 63134 126265 63128 126265 63135 126265 63134 126266 63135 126266 63136 126266 63137 126267 63144 126267 63142 126267 63138 126268 63131 126268 60295 126268 63140 126269 63155 126269 63146 126269 63141 126270 63139 126270 63140 126270 63139 126271 63141 126271 63154 126271 63154 126272 63141 126272 63142 126272 63154 126273 63142 126273 63143 126273 63144 126274 63138 126274 63142 126274 63142 126275 63138 126275 60295 126275 63142 126276 60295 126276 63143 126276 63143 126277 60295 126277 63145 126277 63140 126278 63146 126278 63141 126278 63141 126279 63146 126279 62958 126279 63141 126280 62958 126280 63147 126280 63147 126281 63134 126281 63141 126281 63141 126282 63134 126282 63132 126282 63141 126283 63132 126283 63142 126283 63142 126284 63132 126284 63148 126284 63142 126285 63148 126285 63137 126285 63157 126286 62955 126286 63155 126286 63149 126287 63150 126287 63139 126287 63151 126288 59463 126288 63152 126288 63151 126289 63152 126289 63145 126289 63145 126290 63152 126290 63153 126290 63145 126291 63153 126291 63143 126291 63149 126292 63139 126292 63153 126292 63153 126293 63139 126293 63154 126293 63153 126294 63154 126294 63143 126294 63157 126295 63155 126295 63150 126295 63150 126296 63155 126296 63140 126296 63150 126297 63140 126297 63139 126297 63149 126298 63153 126298 63156 126298 63156 126299 63153 126299 63152 126299 63156 126300 63152 126300 63164 126300 63160 126301 62955 126301 63159 126301 63159 126302 62955 126302 63157 126302 63159 126303 63157 126303 63150 126303 63167 126304 63158 126304 63159 126304 63159 126305 63158 126305 63161 126305 63159 126306 63161 126306 63160 126306 63160 126307 63161 126307 63162 126307 63160 126308 63162 126308 63163 126308 63150 126309 63149 126309 63159 126309 63159 126310 63149 126310 63156 126310 63159 126311 63156 126311 63167 126311 63167 126312 63156 126312 63164 126312 63167 126313 63164 126313 63169 126313 63166 126314 59519 126314 63165 126314 63166 126315 63165 126315 63169 126315 63182 126316 63167 126316 63168 126316 63168 126317 63167 126317 63169 126317 63168 126318 63169 126318 63170 126318 63170 126319 63169 126319 63165 126319 63171 126320 63158 126320 63180 126320 63180 126321 63158 126321 63167 126321 63180 126322 63167 126322 63181 126322 63181 126323 63167 126323 63182 126323 62956 126324 63163 126324 63172 126324 63172 126325 63163 126325 63162 126325 63172 126326 63162 126326 63171 126326 63171 126327 63162 126327 63161 126327 63171 126328 63161 126328 63158 126328 63182 126329 63168 126329 63173 126329 63170 126330 63165 126330 63177 126330 63178 126331 63174 126331 62957 126331 63179 126332 63175 126332 63178 126332 63175 126333 63179 126333 63185 126333 63185 126334 63179 126334 63173 126334 63185 126335 63173 126335 63176 126335 63168 126336 63170 126336 63173 126336 63173 126337 63170 126337 63177 126337 63173 126338 63177 126338 63176 126338 63176 126339 63177 126339 63184 126339 63178 126340 62957 126340 63179 126340 63179 126341 62957 126341 62956 126341 63179 126342 62956 126342 63172 126342 63172 126343 63171 126343 63179 126343 63179 126344 63171 126344 63180 126344 63179 126345 63180 126345 63173 126345 63173 126346 63180 126346 63181 126346 63173 126347 63181 126347 63182 126347 63186 126348 63190 126348 63174 126348 63187 126349 63192 126349 63175 126349 59517 126350 59460 126350 63183 126350 59517 126351 63183 126351 63184 126351 63184 126352 63183 126352 63188 126352 63184 126353 63188 126353 63176 126353 63187 126354 63175 126354 63188 126354 63188 126355 63175 126355 63185 126355 63188 126356 63185 126356 63176 126356 63186 126357 63174 126357 63192 126357 63192 126358 63174 126358 63178 126358 63192 126359 63178 126359 63175 126359 63187 126360 63188 126360 63196 126360 63196 126361 63188 126361 63183 126361 63196 126362 63183 126362 63189 126362 63194 126363 63190 126363 63191 126363 63191 126364 63190 126364 63186 126364 63191 126365 63186 126365 63192 126365 63203 126366 63201 126366 63191 126366 63191 126367 63201 126367 63193 126367 63191 126368 63193 126368 63194 126368 63194 126369 63193 126369 63195 126369 63194 126370 63195 126370 62954 126370 63192 126371 63187 126371 63191 126371 63191 126372 63187 126372 63196 126372 63191 126373 63196 126373 63203 126373 63203 126374 63196 126374 63189 126374 63203 126375 63189 126375 63197 126375 63198 126376 64697 126376 60286 126376 63198 126377 60286 126377 63197 126377 63199 126378 63203 126378 63209 126378 63209 126379 63203 126379 63197 126379 63209 126380 63197 126380 63210 126380 63210 126381 63197 126381 60286 126381 63213 126382 63201 126382 63200 126382 63200 126383 63201 126383 63203 126383 63200 126384 63203 126384 63202 126384 63202 126385 63203 126385 63199 126385 63212 126386 62954 126386 63204 126386 63204 126387 62954 126387 63195 126387 63204 126388 63195 126388 63213 126388 63213 126389 63195 126389 63193 126389 63213 126390 63193 126390 63201 126390 63199 126391 63209 126391 63205 126391 63210 126392 60286 126392 60285 126392 63206 126393 59549 126393 63207 126393 63214 126394 63208 126394 63206 126394 63208 126395 63214 126395 59548 126395 59548 126396 63214 126396 63205 126396 59548 126397 63205 126397 63211 126397 63209 126398 63210 126398 63205 126398 63205 126399 63210 126399 60285 126399 63205 126400 60285 126400 63211 126400 63211 126401 60285 126401 59545 126401 63206 126402 63207 126402 63214 126402 63214 126403 63207 126403 63212 126403 63214 126404 63212 126404 63204 126404 63204 126405 63213 126405 63214 126405 63214 126406 63213 126406 63200 126406 63214 126407 63200 126407 63205 126407 63205 126408 63200 126408 63202 126408 63205 126409 63202 126409 63199 126409 59544 126410 59547 126410 63219 126410 63219 126411 59547 126411 59458 126411 63219 126412 59458 126412 59456 126412 62952 126413 59543 126413 63216 126413 63216 126414 59543 126414 59542 126414 63216 126415 59542 126415 59550 126415 59556 126416 63215 126416 63216 126416 63216 126417 63215 126417 63217 126417 63216 126418 63217 126418 62952 126418 62952 126419 63217 126419 63218 126419 62952 126420 63218 126420 59558 126420 59550 126421 59544 126421 63216 126421 63216 126422 59544 126422 63219 126422 63216 126423 63219 126423 59556 126423 59556 126424 63219 126424 59456 126424 59556 126425 59456 126425 59551 126425 60310 126426 63229 126426 63220 126426 63220 126427 63229 126427 63221 126427 63220 126428 63221 126428 63222 126428 63222 126429 63221 126429 63226 126429 62953 126430 63223 126430 63228 126430 63228 126431 63223 126431 59557 126431 59557 126432 63224 126432 63228 126432 63228 126433 63224 126433 59555 126433 63228 126434 59555 126434 63221 126434 63221 126435 59555 126435 63225 126435 63221 126436 63225 126436 63226 126436 63227 126437 62953 126437 63240 126437 63240 126438 62953 126438 63228 126438 63240 126439 63228 126439 63239 126439 63239 126440 63228 126440 63221 126440 63239 126441 63221 126441 60309 126441 60309 126442 63221 126442 63229 126442 63236 126443 60308 126443 63237 126443 63230 126444 63235 126444 63231 126444 63231 126445 63235 126445 63232 126445 63231 126446 63232 126446 63238 126446 62951 126447 63235 126447 63233 126447 63233 126448 63235 126448 63230 126448 63233 126449 63230 126449 63234 126449 62951 126450 63241 126450 63235 126450 63235 126451 63241 126451 63236 126451 63235 126452 63236 126452 63232 126452 63232 126453 63236 126453 63237 126453 63232 126454 63237 126454 63238 126454 63238 126455 63237 126455 59515 126455 60309 126456 60308 126456 63239 126456 63239 126457 60308 126457 63236 126457 63239 126458 63236 126458 63240 126458 63240 126459 63236 126459 63241 126459 63240 126460 63241 126460 63227 126460 63227 126461 63241 126461 62951 126461 63242 126462 63243 126462 63246 126462 63243 126463 62923 126463 62940 126463 63243 126464 62940 126464 63246 126464 63246 126465 62940 126465 62942 126465 63246 126466 62942 126466 63244 126466 63244 126467 62942 126467 62939 126467 63244 126468 62939 126468 63245 126468 63245 126469 62939 126469 62935 126469 63245 126470 62935 126470 63252 126470 63242 126471 63246 126471 63247 126471 63247 126472 63246 126472 63244 126472 63247 126473 63244 126473 63248 126473 63248 126474 63244 126474 63245 126474 63248 126475 63245 126475 63249 126475 63249 126476 63245 126476 63252 126476 63249 126477 63252 126477 63051 126477 63242 126478 63041 126478 63263 126478 63242 126479 63263 126479 63243 126479 63243 126480 63263 126480 63250 126480 63243 126481 63250 126481 62923 126481 62923 126482 63250 126482 63261 126482 62923 126483 63261 126483 63260 126483 63251 126484 63051 126484 63252 126484 63251 126485 63252 126485 63253 126485 63253 126486 63252 126486 62935 126486 63253 126487 62935 126487 63264 126487 63259 126488 63258 126488 63260 126488 62973 126489 62919 126489 63254 126489 63254 126490 62919 126490 63257 126490 63254 126491 63257 126491 63255 126491 63255 126492 63257 126492 63256 126492 63047 126493 63046 126493 63256 126493 63256 126494 63046 126494 63270 126494 63256 126495 63270 126495 63255 126495 62919 126496 63258 126496 63257 126496 63257 126497 63258 126497 63259 126497 63257 126498 63259 126498 63256 126498 63256 126499 63259 126499 63262 126499 63256 126500 63262 126500 63047 126500 63047 126501 63262 126501 63050 126501 63260 126502 63261 126502 63259 126502 63259 126503 63261 126503 63250 126503 63259 126504 63250 126504 63262 126504 63262 126505 63250 126505 63263 126505 63262 126506 63263 126506 63050 126506 63050 126507 63263 126507 63041 126507 63251 126508 63253 126508 63265 126508 63253 126509 63264 126509 62966 126509 63253 126510 62966 126510 63265 126510 63265 126511 62966 126511 62967 126511 63265 126512 62967 126512 63267 126512 62967 126513 63277 126513 63266 126513 62967 126514 63266 126514 63267 126514 63267 126515 63266 126515 63275 126515 63267 126516 63275 126516 63273 126516 63251 126517 63265 126517 63268 126517 63268 126518 63265 126518 63267 126518 63268 126519 63267 126519 63269 126519 63269 126520 63267 126520 63273 126520 63269 126521 63273 126521 63272 126521 63046 126522 63045 126522 63270 126522 63270 126523 63045 126523 63271 126523 63270 126524 63271 126524 63255 126524 63255 126525 63271 126525 63254 126525 63254 126526 63271 126526 62947 126526 63254 126527 62947 126527 62973 126527 63272 126528 63273 126528 63280 126528 63280 126529 63273 126529 63279 126529 63279 126530 63273 126530 63274 126530 63274 126531 63273 126531 63275 126531 63274 126532 63275 126532 63276 126532 63275 126533 63266 126533 63276 126533 63276 126534 63266 126534 63277 126534 63276 126535 63277 126535 63278 126535 63276 126536 63278 126536 63281 126536 63279 126537 63274 126537 63284 126537 63284 126538 63274 126538 63276 126538 63055 126539 63280 126539 63279 126539 63276 126540 63281 126540 63284 126540 63284 126541 63281 126541 62950 126541 63284 126542 62950 126542 63285 126542 63285 126543 62950 126543 63282 126543 63285 126544 63282 126544 63283 126544 63283 126545 63282 126545 62947 126545 63283 126546 62947 126546 63271 126546 63279 126547 63284 126547 63055 126547 63055 126548 63284 126548 63285 126548 63055 126549 63285 126549 63056 126549 63056 126550 63285 126550 63283 126550 63056 126551 63283 126551 63043 126551 63043 126552 63283 126552 63271 126552 63043 126553 63271 126553 63045 126553 63035 126554 63286 126554 63037 126554 63037 126555 63286 126555 63360 126555 63287 126556 63288 126556 59770 126556 59770 126557 63288 126557 63327 126557 59770 126558 63327 126558 59771 126558 59771 126559 63327 126559 63289 126559 59771 126560 63289 126560 59772 126560 63027 126561 63290 126561 63360 126561 63360 126562 63290 126562 63038 126562 63360 126563 63038 126563 63037 126563 63360 126564 63359 126564 63027 126564 63027 126565 63359 126565 63358 126565 63027 126566 63358 126566 63291 126566 63291 126567 63358 126567 63357 126567 63296 126568 63293 126568 63292 126568 63292 126569 63293 126569 63295 126569 63292 126570 63295 126570 63294 126570 63294 126571 63295 126571 63009 126571 63294 126572 63009 126572 63357 126572 63357 126573 63009 126573 63025 126573 63357 126574 63025 126574 63291 126574 63296 126575 63292 126575 63297 126575 63297 126576 63292 126576 63298 126576 63297 126577 63298 126577 63011 126577 63011 126578 63298 126578 63354 126578 63011 126579 63354 126579 63014 126579 63014 126580 63354 126580 63352 126580 63014 126581 63352 126581 63299 126581 63299 126582 63352 126582 63016 126582 63016 126583 63352 126583 63351 126583 63016 126584 63351 126584 63300 126584 63300 126585 63351 126585 63306 126585 63300 126586 63306 126586 63301 126586 63008 126587 63303 126587 63302 126587 63302 126588 63303 126588 63022 126588 63302 126589 63022 126589 63349 126589 63349 126590 63022 126590 63021 126590 63349 126591 63021 126591 63304 126591 63304 126592 63021 126592 63305 126592 63304 126593 63305 126593 63306 126593 63306 126594 63305 126594 63307 126594 63306 126595 63307 126595 63301 126595 63008 126596 63302 126596 63308 126596 63308 126597 63302 126597 63346 126597 63308 126598 63346 126598 63309 126598 63309 126599 63346 126599 63310 126599 63309 126600 63310 126600 63029 126600 63029 126601 63310 126601 63363 126601 63029 126602 63363 126602 63031 126602 59772 126603 63289 126603 59773 126603 59773 126604 63289 126604 63311 126604 59773 126605 63311 126605 63312 126605 63312 126606 63311 126606 63313 126606 63312 126607 63313 126607 59760 126607 59760 126608 63313 126608 63314 126608 59760 126609 63314 126609 59761 126609 59761 126610 63314 126610 63330 126610 59761 126611 63330 126611 63315 126611 63315 126612 63330 126612 63332 126612 63315 126613 63332 126613 63316 126613 63316 126614 63332 126614 63333 126614 63316 126615 63333 126615 59786 126615 59786 126616 63333 126616 63317 126616 59786 126617 63317 126617 59762 126617 59762 126618 63317 126618 63336 126618 59762 126619 63336 126619 59765 126619 59765 126620 63336 126620 63318 126620 59765 126621 63318 126621 59766 126621 59766 126622 63318 126622 63319 126622 59766 126623 63319 126623 63320 126623 63320 126624 63319 126624 63321 126624 63320 126625 63321 126625 63322 126625 63322 126626 63321 126626 63323 126626 63322 126627 63323 126627 59763 126627 59763 126628 63323 126628 63339 126628 59763 126629 63339 126629 63324 126629 63324 126630 63339 126630 63325 126630 63324 126631 63325 126631 59830 126631 59830 126632 63325 126632 63326 126632 59830 126633 63326 126633 59769 126633 59769 126634 63326 126634 63361 126634 59769 126635 63361 126635 63287 126635 63288 126636 63328 126636 63327 126636 63327 126637 63328 126637 63329 126637 63327 126638 63329 126638 63289 126638 63289 126639 63329 126639 63344 126639 63289 126640 63344 126640 63311 126640 63311 126641 63344 126641 63345 126641 63311 126642 63345 126642 63313 126642 63313 126643 63345 126643 63347 126643 63313 126644 63347 126644 63314 126644 63314 126645 63347 126645 63348 126645 63314 126646 63348 126646 63330 126646 63330 126647 63348 126647 63350 126647 63330 126648 63350 126648 63332 126648 63332 126649 63350 126649 63331 126649 63332 126650 63331 126650 63333 126650 63333 126651 63331 126651 63334 126651 63333 126652 63334 126652 63317 126652 63317 126653 63334 126653 63335 126653 63317 126654 63335 126654 63336 126654 63336 126655 63335 126655 63353 126655 63336 126656 63353 126656 63318 126656 63318 126657 63353 126657 63337 126657 63318 126658 63337 126658 63319 126658 63319 126659 63337 126659 63355 126659 63319 126660 63355 126660 63321 126660 63321 126661 63355 126661 63338 126661 63321 126662 63338 126662 63323 126662 63323 126663 63338 126663 63356 126663 63323 126664 63356 126664 63339 126664 63339 126665 63356 126665 63340 126665 63339 126666 63340 126666 63325 126666 63325 126667 63340 126667 63341 126667 63325 126668 63341 126668 63326 126668 63326 126669 63341 126669 63342 126669 63326 126670 63342 126670 63361 126670 63361 126671 63342 126671 63362 126671 63328 126672 63343 126672 63329 126672 63329 126673 63343 126673 63363 126673 63329 126674 63363 126674 63344 126674 63344 126675 63363 126675 63310 126675 63344 126676 63310 126676 63345 126676 63345 126677 63310 126677 63346 126677 63345 126678 63346 126678 63347 126678 63347 126679 63346 126679 63302 126679 63347 126680 63302 126680 63348 126680 63348 126681 63302 126681 63349 126681 63348 126682 63349 126682 63350 126682 63350 126683 63349 126683 63304 126683 63350 126684 63304 126684 63331 126684 63331 126685 63304 126685 63306 126685 63331 126686 63306 126686 63334 126686 63334 126687 63306 126687 63351 126687 63334 126688 63351 126688 63335 126688 63335 126689 63351 126689 63352 126689 63335 126690 63352 126690 63353 126690 63353 126691 63352 126691 63354 126691 63353 126692 63354 126692 63337 126692 63337 126693 63354 126693 63298 126693 63337 126694 63298 126694 63355 126694 63355 126695 63298 126695 63292 126695 63355 126696 63292 126696 63338 126696 63338 126697 63292 126697 63294 126697 63338 126698 63294 126698 63356 126698 63356 126699 63294 126699 63357 126699 63356 126700 63357 126700 63340 126700 63340 126701 63357 126701 63358 126701 63340 126702 63358 126702 63341 126702 63341 126703 63358 126703 63359 126703 63341 126704 63359 126704 63342 126704 63342 126705 63359 126705 63360 126705 63342 126706 63360 126706 63362 126706 63362 126707 63360 126707 63286 126707 63287 126708 63361 126708 63288 126708 63288 126709 63361 126709 63362 126709 63288 126710 63362 126710 63328 126710 63328 126711 63362 126711 63286 126711 63328 126712 63286 126712 63343 126712 63343 126713 63286 126713 63035 126713 63343 126714 63035 126714 63363 126714 63363 126715 63035 126715 63034 126715 63363 126716 63034 126716 63031 126716 63438 126717 63364 126717 63005 126717 63005 126718 63364 126718 63367 126718 59739 126719 63436 126719 59741 126719 59741 126720 63436 126720 63366 126720 59741 126721 63366 126721 63365 126721 63365 126722 63366 126722 63382 126722 63365 126723 63382 126723 59743 126723 63000 126724 63001 126724 63367 126724 63367 126725 63001 126725 63002 126725 63367 126726 63002 126726 63005 126726 63367 126727 63432 126727 63000 126727 63000 126728 63432 126728 63431 126728 63000 126729 63431 126729 63368 126729 63368 126730 63431 126730 63430 126730 63372 126731 62982 126731 63428 126731 63428 126732 62982 126732 63369 126732 63428 126733 63369 126733 63370 126733 63370 126734 63369 126734 63371 126734 63370 126735 63371 126735 63430 126735 63430 126736 63371 126736 62996 126736 63430 126737 62996 126737 63368 126737 63372 126738 63428 126738 62985 126738 62985 126739 63428 126739 63426 126739 62985 126740 63426 126740 63373 126740 63373 126741 63426 126741 63374 126741 63373 126742 63374 126742 62986 126742 62986 126743 63374 126743 63375 126743 62986 126744 63375 126744 62987 126744 62987 126745 63375 126745 62989 126745 62989 126746 63375 126746 63423 126746 62989 126747 63423 126747 62991 126747 62991 126748 63423 126748 63422 126748 62991 126749 63422 126749 62992 126749 62977 126750 62976 126750 63419 126750 63419 126751 62976 126751 62975 126751 63419 126752 62975 126752 63376 126752 63376 126753 62975 126753 62995 126753 63376 126754 62995 126754 63377 126754 63377 126755 62995 126755 63378 126755 63377 126756 63378 126756 63422 126756 63422 126757 63378 126757 63379 126757 63422 126758 63379 126758 62992 126758 62977 126759 63419 126759 62979 126759 62979 126760 63419 126760 63418 126760 62979 126761 63418 126761 63380 126761 63380 126762 63418 126762 63417 126762 63380 126763 63417 126763 63381 126763 63381 126764 63417 126764 63416 126764 63381 126765 63416 126765 63439 126765 59743 126766 63382 126766 59744 126766 59744 126767 63382 126767 63399 126767 59744 126768 63399 126768 59745 126768 59745 126769 63399 126769 63401 126769 59745 126770 63401 126770 63383 126770 63383 126771 63401 126771 63385 126771 63383 126772 63385 126772 63384 126772 63384 126773 63385 126773 63387 126773 63384 126774 63387 126774 63386 126774 63386 126775 63387 126775 63404 126775 63386 126776 63404 126776 59746 126776 59746 126777 63404 126777 63405 126777 59746 126778 63405 126778 63388 126778 63388 126779 63405 126779 63406 126779 63388 126780 63406 126780 59747 126780 59747 126781 63406 126781 63389 126781 59747 126782 63389 126782 59748 126782 59748 126783 63389 126783 63390 126783 59748 126784 63390 126784 63391 126784 63391 126785 63390 126785 63408 126785 63391 126786 63408 126786 59738 126786 59738 126787 63408 126787 63410 126787 59738 126788 63410 126788 59737 126788 59737 126789 63410 126789 63392 126789 59737 126790 63392 126790 59735 126790 59735 126791 63392 126791 63393 126791 59735 126792 63393 126792 59734 126792 59734 126793 63393 126793 63394 126793 59734 126794 63394 126794 63395 126794 63395 126795 63394 126795 63396 126795 63395 126796 63396 126796 63397 126796 63397 126797 63396 126797 63435 126797 63397 126798 63435 126798 59739 126798 63436 126799 63437 126799 63366 126799 63366 126800 63437 126800 63415 126800 63366 126801 63415 126801 63382 126801 63382 126802 63415 126802 63398 126802 63382 126803 63398 126803 63399 126803 63399 126804 63398 126804 63400 126804 63399 126805 63400 126805 63401 126805 63401 126806 63400 126806 63402 126806 63401 126807 63402 126807 63385 126807 63385 126808 63402 126808 63403 126808 63385 126809 63403 126809 63387 126809 63387 126810 63403 126810 63420 126810 63387 126811 63420 126811 63404 126811 63404 126812 63420 126812 63421 126812 63404 126813 63421 126813 63405 126813 63405 126814 63421 126814 63407 126814 63405 126815 63407 126815 63406 126815 63406 126816 63407 126816 63424 126816 63406 126817 63424 126817 63389 126817 63389 126818 63424 126818 63425 126818 63389 126819 63425 126819 63390 126819 63390 126820 63425 126820 63409 126820 63390 126821 63409 126821 63408 126821 63408 126822 63409 126822 63427 126822 63408 126823 63427 126823 63410 126823 63410 126824 63427 126824 63411 126824 63410 126825 63411 126825 63392 126825 63392 126826 63411 126826 63429 126826 63392 126827 63429 126827 63393 126827 63393 126828 63429 126828 63412 126828 63393 126829 63412 126829 63394 126829 63394 126830 63412 126830 63413 126830 63394 126831 63413 126831 63396 126831 63396 126832 63413 126832 63433 126832 63396 126833 63433 126833 63435 126833 63435 126834 63433 126834 63434 126834 63437 126835 63414 126835 63415 126835 63415 126836 63414 126836 63416 126836 63415 126837 63416 126837 63398 126837 63398 126838 63416 126838 63417 126838 63398 126839 63417 126839 63400 126839 63400 126840 63417 126840 63418 126840 63400 126841 63418 126841 63402 126841 63402 126842 63418 126842 63419 126842 63402 126843 63419 126843 63403 126843 63403 126844 63419 126844 63376 126844 63403 126845 63376 126845 63420 126845 63420 126846 63376 126846 63377 126846 63420 126847 63377 126847 63421 126847 63421 126848 63377 126848 63422 126848 63421 126849 63422 126849 63407 126849 63407 126850 63422 126850 63423 126850 63407 126851 63423 126851 63424 126851 63424 126852 63423 126852 63375 126852 63424 126853 63375 126853 63425 126853 63425 126854 63375 126854 63374 126854 63425 126855 63374 126855 63409 126855 63409 126856 63374 126856 63426 126856 63409 126857 63426 126857 63427 126857 63427 126858 63426 126858 63428 126858 63427 126859 63428 126859 63411 126859 63411 126860 63428 126860 63370 126860 63411 126861 63370 126861 63429 126861 63429 126862 63370 126862 63430 126862 63429 126863 63430 126863 63412 126863 63412 126864 63430 126864 63431 126864 63412 126865 63431 126865 63413 126865 63413 126866 63431 126866 63432 126866 63413 126867 63432 126867 63433 126867 63433 126868 63432 126868 63367 126868 63433 126869 63367 126869 63434 126869 63434 126870 63367 126870 63364 126870 59739 126871 63435 126871 63436 126871 63436 126872 63435 126872 63434 126872 63436 126873 63434 126873 63437 126873 63437 126874 63434 126874 63364 126874 63437 126875 63364 126875 63414 126875 63414 126876 63364 126876 63438 126876 63414 126877 63438 126877 63416 126877 63416 126878 63438 126878 63004 126878 63416 126879 63004 126879 63439 126879 63440 126880 63450 126880 63443 126880 63451 126881 63452 126881 63442 126881 63040 126882 63441 126882 63462 126882 63462 126883 63441 126883 63451 126883 63462 126884 63451 126884 63464 126884 63464 126885 63451 126885 63442 126885 63443 126886 63444 126886 63440 126886 63440 126887 63444 126887 63455 126887 63440 126888 63455 126888 63445 126888 63446 126889 63469 126889 63454 126889 63454 126890 63469 126890 63447 126890 63454 126891 63447 126891 63448 126891 63448 126892 63447 126892 63449 126892 63448 126893 63449 126893 63452 126893 63452 126894 63449 126894 63466 126894 63452 126895 63466 126895 63442 126895 63441 126896 63450 126896 63451 126896 63451 126897 63450 126897 63440 126897 63451 126898 63440 126898 63452 126898 63452 126899 63440 126899 63445 126899 63452 126900 63445 126900 63448 126900 63448 126901 63445 126901 63453 126901 63448 126902 63453 126902 63454 126902 63454 126903 63453 126903 63458 126903 63455 126904 63470 126904 63445 126904 63445 126905 63470 126905 63456 126905 63445 126906 63456 126906 63453 126906 63453 126907 63456 126907 63457 126907 63453 126908 63457 126908 63458 126908 63458 126909 63457 126909 63473 126909 63458 126910 63473 126910 63474 126910 63446 126911 63454 126911 63459 126911 63459 126912 63454 126912 63458 126912 63459 126913 63458 126913 63460 126913 63460 126914 63458 126914 63474 126914 63460 126915 63474 126915 59877 126915 63042 126916 63040 126916 63461 126916 63461 126917 63040 126917 63462 126917 63461 126918 63462 126918 63475 126918 63475 126919 63462 126919 63464 126919 63475 126920 63464 126920 63463 126920 63463 126921 63464 126921 63442 126921 63463 126922 63442 126922 63465 126922 63465 126923 63442 126923 63466 126923 63465 126924 63466 126924 63467 126924 63467 126925 63466 126925 63449 126925 63467 126926 63449 126926 63481 126926 63481 126927 63449 126927 63447 126927 63481 126928 63447 126928 63468 126928 63468 126929 63447 126929 63469 126929 63468 126930 63469 126930 59872 126930 59872 126931 63469 126931 63446 126931 63443 126932 63052 126932 63444 126932 63444 126933 63052 126933 63500 126933 63444 126934 63500 126934 63455 126934 63455 126935 63500 126935 63470 126935 63470 126936 63500 126936 63471 126936 63470 126937 63471 126937 63456 126937 63456 126938 63471 126938 63457 126938 63457 126939 63471 126939 63472 126939 63457 126940 63472 126940 63473 126940 63473 126941 63472 126941 63474 126941 63474 126942 63472 126942 63502 126942 63474 126943 63502 126943 59877 126943 63492 126944 59863 126944 63490 126944 63476 126945 63049 126945 63042 126945 63042 126946 63461 126946 63476 126946 63476 126947 63461 126947 63475 126947 63476 126948 63475 126948 63479 126948 63048 126949 63049 126949 63489 126949 63489 126950 63049 126950 63476 126950 63489 126951 63476 126951 63477 126951 63477 126952 63476 126952 63479 126952 63477 126953 63479 126953 63478 126953 63478 126954 63479 126954 63480 126954 63478 126955 63480 126955 63491 126955 63491 126956 63480 126956 63493 126956 63475 126957 63463 126957 63479 126957 63479 126958 63463 126958 63465 126958 63479 126959 63465 126959 63480 126959 63480 126960 63465 126960 63467 126960 63480 126961 63467 126961 63493 126961 63493 126962 63467 126962 63481 126962 63493 126963 63481 126963 63468 126963 63044 126964 63482 126964 63483 126964 63483 126965 63482 126965 63484 126965 63483 126966 63484 126966 63485 126966 63485 126967 63484 126967 63488 126967 63485 126968 63488 126968 63509 126968 63509 126969 63488 126969 63486 126969 63509 126970 63486 126970 63487 126970 63487 126971 63486 126971 63490 126971 63487 126972 63490 126972 59861 126972 59861 126973 63490 126973 59863 126973 63482 126974 63048 126974 63484 126974 63484 126975 63048 126975 63489 126975 63484 126976 63489 126976 63488 126976 63488 126977 63489 126977 63477 126977 63488 126978 63477 126978 63486 126978 63486 126979 63477 126979 63478 126979 63486 126980 63478 126980 63490 126980 63490 126981 63478 126981 63491 126981 63490 126982 63491 126982 63492 126982 63492 126983 63491 126983 59867 126983 59867 126984 63491 126984 63494 126984 63494 126985 63491 126985 63493 126985 63494 126986 63493 126986 59870 126986 59870 126987 63493 126987 63468 126987 59870 126988 63468 126988 59872 126988 63053 126989 63054 126989 63496 126989 63053 126990 63496 126990 63495 126990 63496 126991 63497 126991 63495 126991 63495 126992 63497 126992 63513 126992 63495 126993 63513 126993 63506 126993 63052 126994 63498 126994 63500 126994 63500 126995 63498 126995 63499 126995 63500 126996 63499 126996 63471 126996 63471 126997 63499 126997 63503 126997 63471 126998 63503 126998 63472 126998 63472 126999 63503 126999 63501 126999 63472 127000 63501 127000 63502 127000 63502 127001 63501 127001 63505 127001 63498 127002 63053 127002 63499 127002 63499 127003 63053 127003 63495 127003 63499 127004 63495 127004 63503 127004 63503 127005 63495 127005 63506 127005 63503 127006 63506 127006 63501 127006 63501 127007 63506 127007 63504 127007 63501 127008 63504 127008 63505 127008 63505 127009 63504 127009 59893 127009 63513 127010 63515 127010 63506 127010 63506 127011 63515 127011 63516 127011 63506 127012 63516 127012 63504 127012 63504 127013 63516 127013 63507 127013 63504 127014 63507 127014 59893 127014 59893 127015 63507 127015 63519 127015 59893 127016 63519 127016 59895 127016 63520 127017 63044 127017 63483 127017 63520 127018 63483 127018 63508 127018 63508 127019 63483 127019 63485 127019 63508 127020 63485 127020 63527 127020 63527 127021 63485 127021 63510 127021 63510 127022 63485 127022 63509 127022 63510 127023 63509 127023 63511 127023 63511 127024 63509 127024 63487 127024 63511 127025 63487 127025 63533 127025 63533 127026 63487 127026 59861 127026 63533 127027 59861 127027 59889 127027 63512 127028 63526 127028 63054 127028 63054 127029 63526 127029 63496 127029 63496 127030 63526 127030 63497 127030 63497 127031 63526 127031 63525 127031 63497 127032 63525 127032 63513 127032 63513 127033 63525 127033 63514 127033 63513 127034 63514 127034 63515 127034 63515 127035 63514 127035 63522 127035 63515 127036 63522 127036 63516 127036 63516 127037 63522 127037 63517 127037 63516 127038 63517 127038 63507 127038 63507 127039 63517 127039 63518 127039 63507 127040 63518 127040 63519 127040 63518 127041 63529 127041 63519 127041 63519 127042 63529 127042 59896 127042 63519 127043 59896 127043 59895 127043 63517 127044 63522 127044 63521 127044 63531 127045 63530 127045 63520 127045 63521 127046 63522 127046 63523 127046 63522 127047 63514 127047 63523 127047 63523 127048 63514 127048 63525 127048 63523 127049 63525 127049 63524 127049 63524 127050 63525 127050 63526 127050 63524 127051 63526 127051 63512 127051 63520 127052 63508 127052 63531 127052 63531 127053 63508 127053 63527 127053 63531 127054 63527 127054 63532 127054 63517 127055 63521 127055 63518 127055 63518 127056 63521 127056 63528 127056 63518 127057 63528 127057 63529 127057 63529 127058 63528 127058 59886 127058 63529 127059 59886 127059 59896 127059 63524 127060 63530 127060 63523 127060 63523 127061 63530 127061 63531 127061 63523 127062 63531 127062 63521 127062 63521 127063 63531 127063 63532 127063 63521 127064 63532 127064 63528 127064 63528 127065 63532 127065 63534 127065 63528 127066 63534 127066 59886 127066 59886 127067 63534 127067 63535 127067 63527 127068 63510 127068 63532 127068 63532 127069 63510 127069 63511 127069 63532 127070 63511 127070 63534 127070 63534 127071 63511 127071 63533 127071 63534 127072 63533 127072 63535 127072 63535 127073 63533 127073 59889 127073 63570 127074 63536 127074 59873 127074 63538 127075 63570 127075 63546 127075 63537 127076 63538 127076 63547 127076 63570 127077 59873 127077 63546 127077 63546 127078 59873 127078 63539 127078 63546 127079 63539 127079 63540 127079 63540 127080 63539 127080 59874 127080 63540 127081 59874 127081 63541 127081 63541 127082 59874 127082 59875 127082 63541 127083 59875 127083 63549 127083 63549 127084 59875 127084 59879 127084 63549 127085 59879 127085 63551 127085 63551 127086 59879 127086 59878 127086 63551 127087 59878 127087 63542 127087 63542 127088 59878 127088 63543 127088 63542 127089 63543 127089 63544 127089 63544 127090 63543 127090 59876 127090 63544 127091 59876 127091 63553 127091 63553 127092 59876 127092 59881 127092 63553 127093 59881 127093 63545 127093 63538 127094 63546 127094 63547 127094 63547 127095 63546 127095 63540 127095 63547 127096 63540 127096 63555 127096 63555 127097 63540 127097 63541 127097 63555 127098 63541 127098 63548 127098 63548 127099 63541 127099 63549 127099 63548 127100 63549 127100 63550 127100 63550 127101 63549 127101 63551 127101 63550 127102 63551 127102 63558 127102 63558 127103 63551 127103 63542 127103 63558 127104 63542 127104 63560 127104 63560 127105 63542 127105 63544 127105 63560 127106 63544 127106 63552 127106 63552 127107 63544 127107 63553 127107 63552 127108 63553 127108 63554 127108 63554 127109 63553 127109 63545 127109 63554 127110 63545 127110 63563 127110 63537 127111 63547 127111 59781 127111 59781 127112 63547 127112 63555 127112 59781 127113 63555 127113 63556 127113 63556 127114 63555 127114 63548 127114 63556 127115 63548 127115 63557 127115 63557 127116 63548 127116 63550 127116 63557 127117 63550 127117 59777 127117 59777 127118 63550 127118 63558 127118 59777 127119 63558 127119 59778 127119 59778 127120 63558 127120 63560 127120 59778 127121 63560 127121 63559 127121 63559 127122 63560 127122 63552 127122 63559 127123 63552 127123 63561 127123 63561 127124 63552 127124 63554 127124 63561 127125 63554 127125 63562 127125 63562 127126 63554 127126 63563 127126 63562 127127 63563 127127 59780 127127 63564 127128 63565 127128 63566 127128 63566 127129 63565 127129 63567 127129 63566 127130 63567 127130 63571 127130 63571 127131 63567 127131 63568 127131 63571 127132 63568 127132 63569 127132 63569 127133 63568 127133 59871 127133 63537 127134 63564 127134 63538 127134 63538 127135 63564 127135 63566 127135 63538 127136 63566 127136 63570 127136 63570 127137 63566 127137 63571 127137 63570 127138 63571 127138 63536 127138 63536 127139 63571 127139 63569 127139 63572 127140 59780 127140 63573 127140 63573 127141 59780 127141 63563 127141 63573 127142 63563 127142 63575 127142 63575 127143 63563 127143 63545 127143 63575 127144 63545 127144 59882 127144 59882 127145 63545 127145 59881 127145 63621 127146 63572 127146 63601 127146 63601 127147 63572 127147 63573 127147 63601 127148 63573 127148 63574 127148 63574 127149 63573 127149 63575 127149 63574 127150 63575 127150 63576 127150 63576 127151 63575 127151 59882 127151 63636 127152 63578 127152 63577 127152 63578 127153 63632 127153 59862 127153 63585 127154 63635 127154 63636 127154 63635 127155 63585 127155 59797 127155 63578 127156 59862 127156 63577 127156 63577 127157 59862 127157 59864 127157 63577 127158 59864 127158 63579 127158 63579 127159 59864 127159 59865 127159 63579 127160 59865 127160 63587 127160 63587 127161 59865 127161 59866 127161 63587 127162 59866 127162 63589 127162 63589 127163 59866 127163 59868 127163 63589 127164 59868 127164 63580 127164 63580 127165 59868 127165 63581 127165 63580 127166 63581 127166 63590 127166 63590 127167 63581 127167 59869 127167 63590 127168 59869 127168 63583 127168 63583 127169 59869 127169 63582 127169 63583 127170 63582 127170 63584 127170 63584 127171 63582 127171 59871 127171 63584 127172 59871 127172 63568 127172 63636 127173 63577 127173 63585 127173 63585 127174 63577 127174 63579 127174 63585 127175 63579 127175 63586 127175 63586 127176 63579 127176 63587 127176 63586 127177 63587 127177 63588 127177 63588 127178 63587 127178 63589 127178 63588 127179 63589 127179 63597 127179 63597 127180 63589 127180 63580 127180 63597 127181 63580 127181 63591 127181 63591 127182 63580 127182 63590 127182 63591 127183 63590 127183 63592 127183 63592 127184 63590 127184 63583 127184 63592 127185 63583 127185 63599 127185 63599 127186 63583 127186 63584 127186 63599 127187 63584 127187 63593 127187 63593 127188 63584 127188 63568 127188 63593 127189 63568 127189 63567 127189 59797 127190 63585 127190 63594 127190 63594 127191 63585 127191 63586 127191 63594 127192 63586 127192 63595 127192 63595 127193 63586 127193 63588 127193 63595 127194 63588 127194 63596 127194 63596 127195 63588 127195 63597 127195 63596 127196 63597 127196 59785 127196 59785 127197 63597 127197 63591 127197 59785 127198 63591 127198 59824 127198 59824 127199 63591 127199 63592 127199 59824 127200 63592 127200 63598 127200 63598 127201 63592 127201 63599 127201 63598 127202 63599 127202 59783 127202 59783 127203 63599 127203 63593 127203 59783 127204 63593 127204 63600 127204 63600 127205 63593 127205 63567 127205 63600 127206 63567 127206 63565 127206 63574 127207 63576 127207 59891 127207 63601 127208 63574 127208 63602 127208 63621 127209 63601 127209 63610 127209 63574 127210 59891 127210 63602 127210 63602 127211 59891 127211 59890 127211 63602 127212 59890 127212 63611 127212 63611 127213 59890 127213 63603 127213 63611 127214 63603 127214 63613 127214 63613 127215 63603 127215 63604 127215 63613 127216 63604 127216 63605 127216 63605 127217 63604 127217 63606 127217 63605 127218 63606 127218 63615 127218 63615 127219 63606 127219 59894 127219 63615 127220 59894 127220 63617 127220 63617 127221 59894 127221 59892 127221 63617 127222 59892 127222 63607 127222 63607 127223 59892 127223 63608 127223 63607 127224 63608 127224 63618 127224 63618 127225 63608 127225 63639 127225 63618 127226 63639 127226 63609 127226 63601 127227 63602 127227 63610 127227 63610 127228 63602 127228 63611 127228 63610 127229 63611 127229 63612 127229 63612 127230 63611 127230 63613 127230 63612 127231 63613 127231 63614 127231 63614 127232 63613 127232 63605 127232 63614 127233 63605 127233 63625 127233 63625 127234 63605 127234 63615 127234 63625 127235 63615 127235 63626 127235 63626 127236 63615 127236 63617 127236 63626 127237 63617 127237 63616 127237 63616 127238 63617 127238 63607 127238 63616 127239 63607 127239 63628 127239 63628 127240 63607 127240 63618 127240 63628 127241 63618 127241 63619 127241 63619 127242 63618 127242 63609 127242 63619 127243 63609 127243 63620 127243 63621 127244 63610 127244 63622 127244 63622 127245 63610 127245 63612 127245 63622 127246 63612 127246 59774 127246 59774 127247 63612 127247 63614 127247 59774 127248 63614 127248 63623 127248 63623 127249 63614 127249 63625 127249 63623 127250 63625 127250 63624 127250 63624 127251 63625 127251 63626 127251 63624 127252 63626 127252 63627 127252 63627 127253 63626 127253 63616 127253 63627 127254 63616 127254 59775 127254 59775 127255 63616 127255 63628 127255 59775 127256 63628 127256 63629 127256 63629 127257 63628 127257 63619 127257 63629 127258 63619 127258 59776 127258 59776 127259 63619 127259 63620 127259 59776 127260 63620 127260 63637 127260 63634 127261 59880 127261 63633 127261 59796 127262 59795 127262 63630 127262 63630 127263 59795 127263 63631 127263 63632 127264 63578 127264 63633 127264 63633 127265 63578 127265 63630 127265 63633 127266 63630 127266 63634 127266 63634 127267 63630 127267 63631 127267 59797 127268 59796 127268 63635 127268 63635 127269 59796 127269 63630 127269 63635 127270 63630 127270 63636 127270 63636 127271 63630 127271 63578 127271 63640 127272 63637 127272 63642 127272 63642 127273 63637 127273 63620 127273 63642 127274 63620 127274 63643 127274 63643 127275 63620 127275 63609 127275 63643 127276 63609 127276 63638 127276 63638 127277 63609 127277 63639 127277 59560 127278 63640 127278 63645 127278 63645 127279 63640 127279 63642 127279 63645 127280 63642 127280 63641 127280 63641 127281 63642 127281 63643 127281 63641 127282 63643 127282 63644 127282 63644 127283 63643 127283 63638 127283 63641 127284 63644 127284 59883 127284 63645 127285 63641 127285 63646 127285 59560 127286 63645 127286 63653 127286 63641 127287 59883 127287 63646 127287 63646 127288 59883 127288 59884 127288 63646 127289 59884 127289 63647 127289 63647 127290 59884 127290 59885 127290 63647 127291 59885 127291 63654 127291 63654 127292 59885 127292 59887 127292 63654 127293 59887 127293 63657 127293 63657 127294 59887 127294 63648 127294 63657 127295 63648 127295 63658 127295 63658 127296 63648 127296 63649 127296 63658 127297 63649 127297 63650 127297 63650 127298 63649 127298 63652 127298 63650 127299 63652 127299 63651 127299 63651 127300 63652 127300 59888 127300 63651 127301 59888 127301 63661 127301 63661 127302 59888 127302 59880 127302 63661 127303 59880 127303 63634 127303 63645 127304 63646 127304 63653 127304 63653 127305 63646 127305 63647 127305 63653 127306 63647 127306 63663 127306 63663 127307 63647 127307 63654 127307 63663 127308 63654 127308 63655 127308 63655 127309 63654 127309 63657 127309 63655 127310 63657 127310 63656 127310 63656 127311 63657 127311 63658 127311 63656 127312 63658 127312 63659 127312 63659 127313 63658 127313 63650 127313 63659 127314 63650 127314 63665 127314 63665 127315 63650 127315 63651 127315 63665 127316 63651 127316 63660 127316 63660 127317 63651 127317 63661 127317 63660 127318 63661 127318 63662 127318 63662 127319 63661 127319 63634 127319 63662 127320 63634 127320 63631 127320 59560 127321 63653 127321 59788 127321 59788 127322 63653 127322 63663 127322 59788 127323 63663 127323 59789 127323 59789 127324 63663 127324 63655 127324 59789 127325 63655 127325 59790 127325 59790 127326 63655 127326 63656 127326 59790 127327 63656 127327 59791 127327 59791 127328 63656 127328 63659 127328 59791 127329 63659 127329 63664 127329 63664 127330 63659 127330 63665 127330 63664 127331 63665 127331 59792 127331 59792 127332 63665 127332 63660 127332 59792 127333 63660 127333 63666 127333 63666 127334 63660 127334 63662 127334 63666 127335 63662 127335 59793 127335 59793 127336 63662 127336 63631 127336 59793 127337 63631 127337 59795 127337 63679 127338 63686 127338 63684 127338 63667 127339 63723 127339 63671 127339 63668 127340 63667 127340 63680 127340 63669 127341 63668 127341 63681 127341 63718 127342 63669 127342 63695 127342 63717 127343 63718 127343 63696 127343 63708 127344 63717 127344 63670 127344 63667 127345 63671 127345 63680 127345 63680 127346 63671 127346 63672 127346 63680 127347 63672 127347 63673 127347 63673 127348 63672 127348 63674 127348 63673 127349 63674 127349 63683 127349 63683 127350 63674 127350 63675 127350 63683 127351 63675 127351 63676 127351 63676 127352 63675 127352 63677 127352 63676 127353 63677 127353 63678 127353 63678 127354 63677 127354 59673 127354 63678 127355 59673 127355 63684 127355 63684 127356 59673 127356 59672 127356 63684 127357 59672 127357 63679 127357 63668 127358 63680 127358 63681 127358 63681 127359 63680 127359 63673 127359 63681 127360 63673 127360 63682 127360 63682 127361 63673 127361 63683 127361 63682 127362 63683 127362 63687 127362 63687 127363 63683 127363 63676 127363 63687 127364 63676 127364 63690 127364 63690 127365 63676 127365 63678 127365 63690 127366 63678 127366 63691 127366 63691 127367 63678 127367 63684 127367 63691 127368 63684 127368 63685 127368 63685 127369 63684 127369 63686 127369 63685 127370 63686 127370 63726 127370 63669 127371 63681 127371 63695 127371 63695 127372 63681 127372 63682 127372 63695 127373 63682 127373 63688 127373 63688 127374 63682 127374 63687 127374 63688 127375 63687 127375 63689 127375 63689 127376 63687 127376 63690 127376 63689 127377 63690 127377 63698 127377 63698 127378 63690 127378 63691 127378 63698 127379 63691 127379 63692 127379 63692 127380 63691 127380 63685 127380 63692 127381 63685 127381 63693 127381 63693 127382 63685 127382 63726 127382 63693 127383 63726 127383 63694 127383 63718 127384 63695 127384 63696 127384 63696 127385 63695 127385 63688 127385 63696 127386 63688 127386 63697 127386 63697 127387 63688 127387 63689 127387 63697 127388 63689 127388 63703 127388 63703 127389 63689 127389 63698 127389 63703 127390 63698 127390 63699 127390 63699 127391 63698 127391 63692 127391 63699 127392 63692 127392 63704 127392 63704 127393 63692 127393 63693 127393 63704 127394 63693 127394 63700 127394 63700 127395 63693 127395 63694 127395 63700 127396 63694 127396 63706 127396 63717 127397 63696 127397 63670 127397 63670 127398 63696 127398 63697 127398 63670 127399 63697 127399 63701 127399 63701 127400 63697 127400 63703 127400 63701 127401 63703 127401 63702 127401 63702 127402 63703 127402 63699 127402 63702 127403 63699 127403 63711 127403 63711 127404 63699 127404 63704 127404 63711 127405 63704 127405 63705 127405 63705 127406 63704 127406 63700 127406 63705 127407 63700 127407 63707 127407 63707 127408 63700 127408 63706 127408 63707 127409 63706 127409 63727 127409 63708 127410 63670 127410 63709 127410 63709 127411 63670 127411 63701 127411 63709 127412 63701 127412 61963 127412 61963 127413 63701 127413 63702 127413 61963 127414 63702 127414 63710 127414 63710 127415 63702 127415 63711 127415 63710 127416 63711 127416 61962 127416 61962 127417 63711 127417 63705 127417 61962 127418 63705 127418 63712 127418 63712 127419 63705 127419 63707 127419 63712 127420 63707 127420 61960 127420 61960 127421 63707 127421 63727 127421 61960 127422 63727 127422 62085 127422 61957 127423 63713 127423 63719 127423 63719 127424 63713 127424 63791 127424 63719 127425 63791 127425 63720 127425 63720 127426 63791 127426 63793 127426 63720 127427 63793 127427 63721 127427 63721 127428 63793 127428 63714 127428 63721 127429 63714 127429 63722 127429 63722 127430 63714 127430 63794 127430 63722 127431 63794 127431 63715 127431 63715 127432 63794 127432 63795 127432 63715 127433 63795 127433 63716 127433 63716 127434 63795 127434 59679 127434 63708 127435 61957 127435 63717 127435 63717 127436 61957 127436 63719 127436 63717 127437 63719 127437 63718 127437 63718 127438 63719 127438 63720 127438 63718 127439 63720 127439 63669 127439 63669 127440 63720 127440 63721 127440 63669 127441 63721 127441 63668 127441 63668 127442 63721 127442 63722 127442 63668 127443 63722 127443 63667 127443 63667 127444 63722 127444 63715 127444 63667 127445 63715 127445 63723 127445 63723 127446 63715 127446 63716 127446 59666 127447 63739 127447 63724 127447 63727 127448 63706 127448 63741 127448 63726 127449 63686 127449 63725 127449 63686 127450 63679 127450 63728 127450 63734 127451 63694 127451 63726 127451 63694 127452 63734 127452 63706 127452 63747 127453 62085 127453 63727 127453 63686 127454 63728 127454 63725 127454 63725 127455 63728 127455 59671 127455 63725 127456 59671 127456 63736 127456 63736 127457 59671 127457 63730 127457 63736 127458 63730 127458 63729 127458 63729 127459 63730 127459 63731 127459 63729 127460 63731 127460 63733 127460 63733 127461 63731 127461 63732 127461 63733 127462 63732 127462 63724 127462 63724 127463 63732 127463 59667 127463 63724 127464 59667 127464 59666 127464 63726 127465 63725 127465 63734 127465 63734 127466 63725 127466 63736 127466 63734 127467 63736 127467 63735 127467 63735 127468 63736 127468 63729 127468 63735 127469 63729 127469 63737 127469 63737 127470 63729 127470 63733 127470 63737 127471 63733 127471 63738 127471 63738 127472 63733 127472 63724 127472 63738 127473 63724 127473 63745 127473 63745 127474 63724 127474 63739 127474 63745 127475 63739 127475 63740 127475 63706 127476 63734 127476 63741 127476 63741 127477 63734 127477 63735 127477 63741 127478 63735 127478 63748 127478 63748 127479 63735 127479 63737 127479 63748 127480 63737 127480 63742 127480 63742 127481 63737 127481 63738 127481 63742 127482 63738 127482 63743 127482 63743 127483 63738 127483 63745 127483 63743 127484 63745 127484 63744 127484 63744 127485 63745 127485 63740 127485 63744 127486 63740 127486 63746 127486 63727 127487 63741 127487 63747 127487 63747 127488 63741 127488 63748 127488 63747 127489 63748 127489 62093 127489 62093 127490 63748 127490 63742 127490 62093 127491 63742 127491 62091 127491 62091 127492 63742 127492 63743 127492 62091 127493 63743 127493 62083 127493 62083 127494 63743 127494 63744 127494 62083 127495 63744 127495 62089 127495 62089 127496 63744 127496 63746 127496 62089 127497 63746 127497 62075 127497 61950 127498 63749 127498 63780 127498 61956 127499 63859 127499 63750 127499 63750 127500 63859 127500 63858 127500 63750 127501 63858 127501 63758 127501 63758 127502 63858 127502 63751 127502 63758 127503 63751 127503 63752 127503 63752 127504 63751 127504 63753 127504 63752 127505 63753 127505 63760 127505 63760 127506 63753 127506 63848 127506 63760 127507 63848 127507 63754 127507 63754 127508 63848 127508 63756 127508 63754 127509 63756 127509 63755 127509 63755 127510 63756 127510 59839 127510 61955 127511 61956 127511 63761 127511 63761 127512 61956 127512 63750 127512 63761 127513 63750 127513 63757 127513 63757 127514 63750 127514 63758 127514 63757 127515 63758 127515 63763 127515 63763 127516 63758 127516 63752 127516 63763 127517 63752 127517 63759 127517 63759 127518 63752 127518 63760 127518 63759 127519 63760 127519 63764 127519 63764 127520 63760 127520 63754 127520 63764 127521 63754 127521 59822 127521 59822 127522 63754 127522 63755 127522 63766 127523 61955 127523 63767 127523 63767 127524 61955 127524 63761 127524 63767 127525 63761 127525 63762 127525 63762 127526 63761 127526 63757 127526 63762 127527 63757 127527 63769 127527 63769 127528 63757 127528 63763 127528 63769 127529 63763 127529 63770 127529 63770 127530 63763 127530 63759 127530 63770 127531 63759 127531 63771 127531 63771 127532 63759 127532 63764 127532 63771 127533 63764 127533 59844 127533 59844 127534 63764 127534 59822 127534 63772 127535 63766 127535 63765 127535 63765 127536 63766 127536 63767 127536 63765 127537 63767 127537 63774 127537 63774 127538 63767 127538 63762 127538 63774 127539 63762 127539 63768 127539 63768 127540 63762 127540 63769 127540 63768 127541 63769 127541 63776 127541 63776 127542 63769 127542 63770 127542 63776 127543 63770 127543 63777 127543 63777 127544 63770 127544 63771 127544 63777 127545 63771 127545 63778 127545 63778 127546 63771 127546 59844 127546 63749 127547 63772 127547 63780 127547 63780 127548 63772 127548 63765 127548 63780 127549 63765 127549 63773 127549 63773 127550 63765 127550 63774 127550 63773 127551 63774 127551 63782 127551 63782 127552 63774 127552 63768 127552 63782 127553 63768 127553 63783 127553 63783 127554 63768 127554 63776 127554 63783 127555 63776 127555 63775 127555 63775 127556 63776 127556 63777 127556 63775 127557 63777 127557 59678 127557 59678 127558 63777 127558 63778 127558 63779 127559 61950 127559 63785 127559 63785 127560 61950 127560 63780 127560 63785 127561 63780 127561 63781 127561 63781 127562 63780 127562 63773 127562 63781 127563 63773 127563 63787 127563 63787 127564 63773 127564 63782 127564 63787 127565 63782 127565 63789 127565 63789 127566 63782 127566 63783 127566 63789 127567 63783 127567 63790 127567 63790 127568 63783 127568 63775 127568 63790 127569 63775 127569 59677 127569 59677 127570 63775 127570 59678 127570 61951 127571 63779 127571 63784 127571 63784 127572 63779 127572 63785 127572 63784 127573 63785 127573 63792 127573 63792 127574 63785 127574 63781 127574 63792 127575 63781 127575 63786 127575 63786 127576 63781 127576 63787 127576 63786 127577 63787 127577 63788 127577 63788 127578 63787 127578 63789 127578 63788 127579 63789 127579 63796 127579 63796 127580 63789 127580 63790 127580 63796 127581 63790 127581 59676 127581 59676 127582 63790 127582 59677 127582 63713 127583 61951 127583 63791 127583 63791 127584 61951 127584 63784 127584 63791 127585 63784 127585 63793 127585 63793 127586 63784 127586 63792 127586 63793 127587 63792 127587 63714 127587 63714 127588 63792 127588 63786 127588 63714 127589 63786 127589 63794 127589 63794 127590 63786 127590 63788 127590 63794 127591 63788 127591 63795 127591 63795 127592 63788 127592 63796 127592 63795 127593 63796 127593 59679 127593 59679 127594 63796 127594 59676 127594 63740 127595 63739 127595 63804 127595 63746 127596 63740 127596 63797 127596 62075 127597 63746 127597 63823 127597 62075 127598 63823 127598 62074 127598 62074 127599 63823 127599 63798 127599 62074 127600 63798 127600 63799 127600 63799 127601 63798 127601 63824 127601 63799 127602 63824 127602 62073 127602 62073 127603 63824 127603 63800 127603 62073 127604 63800 127604 63801 127604 63801 127605 63800 127605 63802 127605 63802 127606 63800 127606 63803 127606 63802 127607 63803 127607 62072 127607 62072 127608 63803 127608 63827 127608 62072 127609 63827 127609 62069 127609 63740 127610 63804 127610 63797 127610 63797 127611 63804 127611 63818 127611 63797 127612 63818 127612 63805 127612 63805 127613 63818 127613 63817 127613 63805 127614 63817 127614 63806 127614 63806 127615 63817 127615 63815 127615 63806 127616 63815 127616 63825 127616 63825 127617 63815 127617 63807 127617 63825 127618 63807 127618 63826 127618 63826 127619 63807 127619 63808 127619 63826 127620 63808 127620 63810 127620 63810 127621 63808 127621 63809 127621 63810 127622 63809 127622 63811 127622 63811 127623 63809 127623 63812 127623 63811 127624 63812 127624 63821 127624 59660 127625 63812 127625 59661 127625 59661 127626 63812 127626 63809 127626 59661 127627 63809 127627 63813 127627 63813 127628 63809 127628 63808 127628 63813 127629 63808 127629 63814 127629 63814 127630 63808 127630 63807 127630 63814 127631 63807 127631 59664 127631 59664 127632 63807 127632 63815 127632 59664 127633 63815 127633 59663 127633 59663 127634 63815 127634 63817 127634 59663 127635 63817 127635 63816 127635 63816 127636 63817 127636 63818 127636 63816 127637 63818 127637 63819 127637 63819 127638 63818 127638 63804 127638 63819 127639 63804 127639 59665 127639 59665 127640 63804 127640 63739 127640 59665 127641 63739 127641 59666 127641 59660 127642 63820 127642 63812 127642 63812 127643 63820 127643 63860 127643 63812 127644 63860 127644 63821 127644 63821 127645 63860 127645 63822 127645 63821 127646 63822 127646 63830 127646 63746 127647 63797 127647 63823 127647 63823 127648 63797 127648 63805 127648 63823 127649 63805 127649 63798 127649 63798 127650 63805 127650 63806 127650 63798 127651 63806 127651 63824 127651 63824 127652 63806 127652 63825 127652 63824 127653 63825 127653 63800 127653 63800 127654 63825 127654 63826 127654 63800 127655 63826 127655 63803 127655 63803 127656 63826 127656 63810 127656 63803 127657 63810 127657 63827 127657 63827 127658 63810 127658 63811 127658 63827 127659 63811 127659 63828 127659 63828 127660 63811 127660 63821 127660 63828 127661 63821 127661 63829 127661 63829 127662 63821 127662 63830 127662 63829 127663 63830 127663 63831 127663 62069 127664 63827 127664 63832 127664 63832 127665 63827 127665 63828 127665 63832 127666 63828 127666 63833 127666 63833 127667 63828 127667 63829 127667 63833 127668 63829 127668 62066 127668 62066 127669 63829 127669 63831 127669 62066 127670 63831 127670 63861 127670 63834 127671 59823 127671 63835 127671 63898 127672 63834 127672 63837 127672 63849 127673 63898 127673 63850 127673 63854 127674 63849 127674 63851 127674 63834 127675 63835 127675 63837 127675 63837 127676 63835 127676 63836 127676 63837 127677 63836 127677 63843 127677 63898 127678 63837 127678 63850 127678 63850 127679 63837 127679 63843 127679 63850 127680 63843 127680 63838 127680 63838 127681 63843 127681 63844 127681 63838 127682 63844 127682 63840 127682 63840 127683 63844 127683 63839 127683 63840 127684 63839 127684 63841 127684 63841 127685 63839 127685 63847 127685 63841 127686 63847 127686 63853 127686 63836 127687 63842 127687 63843 127687 63843 127688 63842 127688 63845 127688 63843 127689 63845 127689 63844 127689 63844 127690 63845 127690 63846 127690 63844 127691 63846 127691 63839 127691 63839 127692 63846 127692 59825 127692 63839 127693 59825 127693 63847 127693 63847 127694 59825 127694 59839 127694 59839 127695 63756 127695 63847 127695 63847 127696 63756 127696 63848 127696 63847 127697 63848 127697 63853 127697 63853 127698 63848 127698 63753 127698 63853 127699 63753 127699 63751 127699 63849 127700 63850 127700 63851 127700 63851 127701 63850 127701 63838 127701 63851 127702 63838 127702 63852 127702 63852 127703 63838 127703 63840 127703 63852 127704 63840 127704 63855 127704 63855 127705 63840 127705 63841 127705 63855 127706 63841 127706 63856 127706 63856 127707 63841 127707 63853 127707 63856 127708 63853 127708 63857 127708 63857 127709 63853 127709 63751 127709 63857 127710 63751 127710 63858 127710 63854 127711 63851 127711 62077 127711 62077 127712 63851 127712 63852 127712 62077 127713 63852 127713 62078 127713 62078 127714 63852 127714 63855 127714 62078 127715 63855 127715 62079 127715 62079 127716 63855 127716 63856 127716 62079 127717 63856 127717 62081 127717 62081 127718 63856 127718 63857 127718 62081 127719 63857 127719 62082 127719 62082 127720 63857 127720 63858 127720 62082 127721 63858 127721 63859 127721 63866 127722 63860 127722 63820 127722 63860 127723 63866 127723 63822 127723 63822 127724 63866 127724 63865 127724 63822 127725 63865 127725 63830 127725 63830 127726 63865 127726 63831 127726 63831 127727 63865 127727 62054 127727 63831 127728 62054 127728 63861 127728 63867 127729 63866 127729 63862 127729 63862 127730 63866 127730 63820 127730 63862 127731 63820 127731 59660 127731 62053 127732 62054 127732 63863 127732 63863 127733 62054 127733 63865 127733 63863 127734 63865 127734 63864 127734 63864 127735 63865 127735 63866 127735 63864 127736 63866 127736 63869 127736 63869 127737 63866 127737 63867 127737 63868 127738 62061 127738 63892 127738 63869 127739 63867 127739 59658 127739 63864 127740 63869 127740 63871 127740 63863 127741 63864 127741 63872 127741 63869 127742 59658 127742 63871 127742 63871 127743 59658 127743 59657 127743 63871 127744 59657 127744 63873 127744 63873 127745 59657 127745 63870 127745 63873 127746 63870 127746 63874 127746 63874 127747 63870 127747 63888 127747 63874 127748 63888 127748 63875 127748 63864 127749 63871 127749 63872 127749 63872 127750 63871 127750 63873 127750 63872 127751 63873 127751 63877 127751 63877 127752 63873 127752 63874 127752 63877 127753 63874 127753 63878 127753 63878 127754 63874 127754 63875 127754 63878 127755 63875 127755 63886 127755 63863 127756 63872 127756 63876 127756 63876 127757 63872 127757 63877 127757 63876 127758 63877 127758 63882 127758 63882 127759 63877 127759 63878 127759 63882 127760 63878 127760 63881 127760 63881 127761 63878 127761 63886 127761 63881 127762 63886 127762 63879 127762 62059 127763 62056 127763 63879 127763 63879 127764 62056 127764 63880 127764 63879 127765 63880 127765 63881 127765 63881 127766 63880 127766 62065 127766 63881 127767 62065 127767 63882 127767 63882 127768 62065 127768 62063 127768 63882 127769 62063 127769 63876 127769 63876 127770 62063 127770 62053 127770 63876 127771 62053 127771 63863 127771 62060 127772 62059 127772 63883 127772 63883 127773 62059 127773 63879 127773 63883 127774 63879 127774 63884 127774 63884 127775 63879 127775 63886 127775 63884 127776 63886 127776 63885 127776 63885 127777 63886 127777 63875 127777 63885 127778 63875 127778 63887 127778 63887 127779 63875 127779 63888 127779 62061 127780 62060 127780 63892 127780 63892 127781 62060 127781 63883 127781 63892 127782 63883 127782 63889 127782 63889 127783 63883 127783 63884 127783 63889 127784 63884 127784 63894 127784 63894 127785 63884 127785 63885 127785 63894 127786 63885 127786 63890 127786 63890 127787 63885 127787 63887 127787 62058 127788 63868 127788 63891 127788 63891 127789 63868 127789 63892 127789 63891 127790 63892 127790 63897 127790 63897 127791 63892 127791 63889 127791 63897 127792 63889 127792 63893 127792 63893 127793 63889 127793 63894 127793 63893 127794 63894 127794 63895 127794 63895 127795 63894 127795 63890 127795 62057 127796 62058 127796 63896 127796 63896 127797 62058 127797 63891 127797 63896 127798 63891 127798 63899 127798 63899 127799 63891 127799 63897 127799 63899 127800 63897 127800 63900 127800 63900 127801 63897 127801 63893 127801 63900 127802 63893 127802 63901 127802 63901 127803 63893 127803 63895 127803 63854 127804 62057 127804 63849 127804 63849 127805 62057 127805 63896 127805 63849 127806 63896 127806 63898 127806 63898 127807 63896 127807 63899 127807 63898 127808 63899 127808 63834 127808 63834 127809 63899 127809 63900 127809 63834 127810 63900 127810 59823 127810 59823 127811 63900 127811 63901 127811 63902 127812 62117 127812 63931 127812 63905 127813 63952 127813 63914 127813 63945 127814 63903 127814 63904 127814 63903 127815 59654 127815 63906 127815 63945 127816 63904 127816 63952 127816 63905 127817 63914 127817 63923 127817 63903 127818 63906 127818 63904 127818 63904 127819 63906 127819 63907 127819 63904 127820 63907 127820 63911 127820 63911 127821 63907 127821 59652 127821 63911 127822 59652 127822 63908 127822 63908 127823 59652 127823 63909 127823 63908 127824 63909 127824 63913 127824 63952 127825 63904 127825 63914 127825 63914 127826 63904 127826 63911 127826 63914 127827 63911 127827 63910 127827 63910 127828 63911 127828 63908 127828 63910 127829 63908 127829 63912 127829 63912 127830 63908 127830 63913 127830 63912 127831 63913 127831 63924 127831 63923 127832 63914 127832 63915 127832 63915 127833 63914 127833 63910 127833 63915 127834 63910 127834 63919 127834 63919 127835 63910 127835 63912 127835 63919 127836 63912 127836 63916 127836 63916 127837 63912 127837 63924 127837 63916 127838 63924 127838 63918 127838 62116 127839 63917 127839 63918 127839 63918 127840 63917 127840 62118 127840 63918 127841 62118 127841 63916 127841 63916 127842 62118 127842 63920 127842 63916 127843 63920 127843 63919 127843 63919 127844 63920 127844 63921 127844 63919 127845 63921 127845 63915 127845 63915 127846 63921 127846 63922 127846 63915 127847 63922 127847 63923 127847 63927 127848 62116 127848 63928 127848 63928 127849 62116 127849 63918 127849 63928 127850 63918 127850 63929 127850 63929 127851 63918 127851 63924 127851 63929 127852 63924 127852 63925 127852 63925 127853 63924 127853 63913 127853 63925 127854 63913 127854 63926 127854 63926 127855 63913 127855 63909 127855 62117 127856 63927 127856 63931 127856 63931 127857 63927 127857 63928 127857 63931 127858 63928 127858 63932 127858 63932 127859 63928 127859 63929 127859 63932 127860 63929 127860 63934 127860 63934 127861 63929 127861 63925 127861 63934 127862 63925 127862 63930 127862 63930 127863 63925 127863 63926 127863 62113 127864 63902 127864 63935 127864 63935 127865 63902 127865 63931 127865 63935 127866 63931 127866 63938 127866 63938 127867 63931 127867 63932 127867 63938 127868 63932 127868 63933 127868 63933 127869 63932 127869 63934 127869 63933 127870 63934 127870 63940 127870 63940 127871 63934 127871 63930 127871 62112 127872 62113 127872 63942 127872 63942 127873 62113 127873 63935 127873 63942 127874 63935 127874 63936 127874 63936 127875 63935 127875 63938 127875 63936 127876 63938 127876 63937 127876 63937 127877 63938 127877 63933 127877 63937 127878 63933 127878 63939 127878 63939 127879 63933 127879 63940 127879 62108 127880 62112 127880 63954 127880 63954 127881 62112 127881 63942 127881 63954 127882 63942 127882 63941 127882 63941 127883 63942 127883 63936 127883 63941 127884 63936 127884 63943 127884 63943 127885 63936 127885 63937 127885 63943 127886 63937 127886 63944 127886 63944 127887 63937 127887 63939 127887 63903 127888 63945 127888 63951 127888 63950 127889 63998 127889 59655 127889 64000 127890 63946 127890 63948 127890 63948 127891 63946 127891 63947 127891 63948 127892 63947 127892 63949 127892 59654 127893 63903 127893 59655 127893 59655 127894 63903 127894 63951 127894 59655 127895 63951 127895 63950 127895 63950 127896 63951 127896 63999 127896 63945 127897 63952 127897 63951 127897 63951 127898 63952 127898 63946 127898 63951 127899 63946 127899 63999 127899 63999 127900 63946 127900 64000 127900 63922 127901 63947 127901 63923 127901 63923 127902 63947 127902 63946 127902 63923 127903 63946 127903 63905 127903 63905 127904 63946 127904 63952 127904 63943 127905 63944 127905 63953 127905 63941 127906 63943 127906 63957 127906 63954 127907 63941 127907 63962 127907 62108 127908 63954 127908 63969 127908 63943 127909 63953 127909 63957 127909 63957 127910 63953 127910 59642 127910 63957 127911 59642 127911 63958 127911 59642 127912 59643 127912 63958 127912 63958 127913 59643 127913 59645 127913 63958 127914 59645 127914 63955 127914 63955 127915 59645 127915 59646 127915 63955 127916 59646 127916 63956 127916 63956 127917 59646 127917 59648 127917 63956 127918 59648 127918 63960 127918 63960 127919 59648 127919 64012 127919 63960 127920 64012 127920 64014 127920 63941 127921 63957 127921 63962 127921 63962 127922 63957 127922 63958 127922 63962 127923 63958 127923 63963 127923 63963 127924 63958 127924 63955 127924 63963 127925 63955 127925 63965 127925 63965 127926 63955 127926 63956 127926 63965 127927 63956 127927 63959 127927 63959 127928 63956 127928 63960 127928 63959 127929 63960 127929 63967 127929 63967 127930 63960 127930 64014 127930 63967 127931 64014 127931 63961 127931 63954 127932 63962 127932 63969 127932 63969 127933 63962 127933 63963 127933 63969 127934 63963 127934 63970 127934 63970 127935 63963 127935 63965 127935 63970 127936 63965 127936 63964 127936 63964 127937 63965 127937 63959 127937 63964 127938 63959 127938 63966 127938 63966 127939 63959 127939 63967 127939 63966 127940 63967 127940 63971 127940 63971 127941 63967 127941 63961 127941 63971 127942 63961 127942 63968 127942 62108 127943 63969 127943 62111 127943 62111 127944 63969 127944 63970 127944 62111 127945 63970 127945 62106 127945 62106 127946 63970 127946 63964 127946 62106 127947 63964 127947 62103 127947 62103 127948 63964 127948 63966 127948 62103 127949 63966 127949 63972 127949 63972 127950 63966 127950 63971 127950 63972 127951 63971 127951 63973 127951 63973 127952 63971 127952 63968 127952 63973 127953 63968 127953 64019 127953 63974 127954 64072 127954 63980 127954 63990 127955 63974 127955 63991 127955 64087 127956 63990 127956 64001 127956 64088 127957 64087 127957 64002 127957 64088 127958 64002 127958 62128 127958 62128 127959 64002 127959 64003 127959 62128 127960 64003 127960 63975 127960 63975 127961 64003 127961 63976 127961 63975 127962 63976 127962 63977 127962 63977 127963 63976 127963 64006 127963 63977 127964 64006 127964 62124 127964 62124 127965 64006 127965 62125 127965 62125 127966 64006 127966 63978 127966 62125 127967 63978 127967 62126 127967 62126 127968 63978 127968 63979 127968 62126 127969 63979 127969 62127 127969 63974 127970 63980 127970 63991 127970 63991 127971 63980 127971 63982 127971 63991 127972 63982 127972 63981 127972 63981 127973 63982 127973 63984 127973 63981 127974 63984 127974 63983 127974 63983 127975 63984 127975 63985 127975 63983 127976 63985 127976 63987 127976 63987 127977 63985 127977 63986 127977 63987 127978 63986 127978 63993 127978 63993 127979 63986 127979 63988 127979 63993 127980 63988 127980 63994 127980 63994 127981 63988 127981 59656 127981 63994 127982 59656 127982 63996 127982 63996 127983 59656 127983 63989 127983 63996 127984 63989 127984 63997 127984 63990 127985 63991 127985 64001 127985 64001 127986 63991 127986 63981 127986 64001 127987 63981 127987 64004 127987 64004 127988 63981 127988 63983 127988 64004 127989 63983 127989 63992 127989 63992 127990 63983 127990 63987 127990 63992 127991 63987 127991 64005 127991 64005 127992 63987 127992 63993 127992 64005 127993 63993 127993 64007 127993 64007 127994 63993 127994 63994 127994 64007 127995 63994 127995 63995 127995 63995 127996 63994 127996 63996 127996 63995 127997 63996 127997 64008 127997 64008 127998 63996 127998 63997 127998 64008 127999 63997 127999 64009 127999 63989 128000 63998 128000 63997 128000 63997 128001 63998 128001 63950 128001 63997 128002 63950 128002 64009 128002 64009 128003 63950 128003 63999 128003 64009 128004 63999 128004 64000 128004 64087 128005 64001 128005 64002 128005 64002 128006 64001 128006 64004 128006 64002 128007 64004 128007 64003 128007 64003 128008 64004 128008 63992 128008 64003 128009 63992 128009 63976 128009 63976 128010 63992 128010 64005 128010 63976 128011 64005 128011 64006 128011 64006 128012 64005 128012 64007 128012 64006 128013 64007 128013 63978 128013 63978 128014 64007 128014 63995 128014 63978 128015 63995 128015 63979 128015 63979 128016 63995 128016 64008 128016 63979 128017 64008 128017 64011 128017 64011 128018 64008 128018 64009 128018 64011 128019 64009 128019 64010 128019 64010 128020 64009 128020 64000 128020 64010 128021 64000 128021 63948 128021 62127 128022 63979 128022 62122 128022 62122 128023 63979 128023 64011 128023 62122 128024 64011 128024 62123 128024 62123 128025 64011 128025 64010 128025 62123 128026 64010 128026 62120 128026 62120 128027 64010 128027 63948 128027 62120 128028 63948 128028 63949 128028 61978 128029 61979 128029 64043 128029 64014 128030 64012 128030 64013 128030 64013 128031 64015 128031 64014 128031 64014 128032 64015 128032 64016 128032 64014 128033 64016 128033 63961 128033 63961 128034 64016 128034 64017 128034 63961 128035 64017 128035 63968 128035 64018 128036 64019 128036 64021 128036 64021 128037 64019 128037 63968 128037 64021 128038 63968 128038 64022 128038 64022 128039 63968 128039 64017 128039 61982 128040 64018 128040 64020 128040 64020 128041 64018 128041 64021 128041 64020 128042 64021 128042 64024 128042 64024 128043 64021 128043 64022 128043 64024 128044 64022 128044 64026 128044 64026 128045 64022 128045 64017 128045 64026 128046 64017 128046 64028 128046 64028 128047 64017 128047 64016 128047 64028 128048 64016 128048 64023 128048 64023 128049 64016 128049 64015 128049 64023 128050 64015 128050 59639 128050 59639 128051 64015 128051 64013 128051 64030 128052 61982 128052 64031 128052 64031 128053 61982 128053 64020 128053 64031 128054 64020 128054 64033 128054 64033 128055 64020 128055 64024 128055 64033 128056 64024 128056 64025 128056 64025 128057 64024 128057 64026 128057 64025 128058 64026 128058 64027 128058 64027 128059 64026 128059 64028 128059 64027 128060 64028 128060 64035 128060 64035 128061 64028 128061 64023 128061 64035 128062 64023 128062 64029 128062 64029 128063 64023 128063 59639 128063 61981 128064 64030 128064 64037 128064 64037 128065 64030 128065 64031 128065 64037 128066 64031 128066 64032 128066 64032 128067 64031 128067 64033 128067 64032 128068 64033 128068 64034 128068 64034 128069 64033 128069 64025 128069 64034 128070 64025 128070 64039 128070 64039 128071 64025 128071 64027 128071 64039 128072 64027 128072 64040 128072 64040 128073 64027 128073 64035 128073 64040 128074 64035 128074 59638 128074 59638 128075 64035 128075 64029 128075 61979 128076 61981 128076 64043 128076 64043 128077 61981 128077 64037 128077 64043 128078 64037 128078 64036 128078 64036 128079 64037 128079 64032 128079 64036 128080 64032 128080 64038 128080 64038 128081 64032 128081 64034 128081 64038 128082 64034 128082 64048 128082 64048 128083 64034 128083 64039 128083 64048 128084 64039 128084 64049 128084 64049 128085 64039 128085 64040 128085 64049 128086 64040 128086 59637 128086 59637 128087 64040 128087 59638 128087 64041 128088 61978 128088 64042 128088 64042 128089 61978 128089 64043 128089 64042 128090 64043 128090 64044 128090 64044 128091 64043 128091 64036 128091 64044 128092 64036 128092 64045 128092 64045 128093 64036 128093 64038 128093 64045 128094 64038 128094 64046 128094 64046 128095 64038 128095 64048 128095 64046 128096 64048 128096 64047 128096 64047 128097 64048 128097 64049 128097 64047 128098 64049 128098 64055 128098 64055 128099 64049 128099 59637 128099 61975 128100 64041 128100 64050 128100 64050 128101 64041 128101 64042 128101 64050 128102 64042 128102 64057 128102 64057 128103 64042 128103 64044 128103 64057 128104 64044 128104 64051 128104 64051 128105 64044 128105 64045 128105 64051 128106 64045 128106 64052 128106 64052 128107 64045 128107 64046 128107 64052 128108 64046 128108 64053 128108 64053 128109 64046 128109 64047 128109 64053 128110 64047 128110 64054 128110 64054 128111 64047 128111 64055 128111 61976 128112 61975 128112 64089 128112 64089 128113 61975 128113 64050 128113 64089 128114 64050 128114 64056 128114 64056 128115 64050 128115 64057 128115 64056 128116 64057 128116 64058 128116 64058 128117 64057 128117 64051 128117 64058 128118 64051 128118 64059 128118 64059 128119 64051 128119 64052 128119 64059 128120 64052 128120 64060 128120 64060 128121 64052 128121 64053 128121 64060 128122 64053 128122 64061 128122 64061 128123 64053 128123 64054 128123 64072 128124 63974 128124 64071 128124 64065 128125 64062 128125 64082 128125 64131 128126 59834 128126 59826 128126 64063 128127 64131 128127 64074 128127 64062 128128 64063 128128 64073 128128 64084 128129 64064 128129 64065 128129 64131 128130 59826 128130 64074 128130 64074 128131 59826 128131 64066 128131 64074 128132 64066 128132 64067 128132 64067 128133 64066 128133 64068 128133 64067 128134 64068 128134 64077 128134 64077 128135 64068 128135 64070 128135 64077 128136 64070 128136 64069 128136 64069 128137 64070 128137 59821 128137 64069 128138 59821 128138 64071 128138 64071 128139 59821 128139 59820 128139 64071 128140 59820 128140 64072 128140 64063 128141 64074 128141 64073 128141 64073 128142 64074 128142 64067 128142 64073 128143 64067 128143 64075 128143 64075 128144 64067 128144 64077 128144 64075 128145 64077 128145 64076 128145 64076 128146 64077 128146 64069 128146 64076 128147 64069 128147 64079 128147 64079 128148 64069 128148 64071 128148 64079 128149 64071 128149 64080 128149 64080 128150 64071 128150 63974 128150 64080 128151 63974 128151 63990 128151 64062 128152 64073 128152 64082 128152 64082 128153 64073 128153 64075 128153 64082 128154 64075 128154 64083 128154 64083 128155 64075 128155 64076 128155 64083 128156 64076 128156 64078 128156 64078 128157 64076 128157 64079 128157 64078 128158 64079 128158 64085 128158 64085 128159 64079 128159 64080 128159 64085 128160 64080 128160 64081 128160 64081 128161 64080 128161 63990 128161 64081 128162 63990 128162 64087 128162 64065 128163 64082 128163 64084 128163 64084 128164 64082 128164 64083 128164 64084 128165 64083 128165 62097 128165 62097 128166 64083 128166 64078 128166 62097 128167 64078 128167 62100 128167 62100 128168 64078 128168 64085 128168 62100 128169 64085 128169 64086 128169 64086 128170 64085 128170 64081 128170 64086 128171 64081 128171 62095 128171 62095 128172 64081 128172 64087 128172 62095 128173 64087 128173 64088 128173 64093 128174 61976 128174 64094 128174 64094 128175 61976 128175 64089 128175 64094 128176 64089 128176 64090 128176 64090 128177 64089 128177 64056 128177 64090 128178 64056 128178 64091 128178 64091 128179 64056 128179 64058 128179 64091 128180 64058 128180 64092 128180 64092 128181 64058 128181 64059 128181 64092 128182 64059 128182 64096 128182 64096 128183 64059 128183 64060 128183 64096 128184 64060 128184 64098 128184 64098 128185 64060 128185 64061 128185 64101 128186 64093 128186 64114 128186 64114 128187 64093 128187 64094 128187 64114 128188 64094 128188 64099 128188 64099 128189 64094 128189 64090 128189 64099 128190 64090 128190 64100 128190 64100 128191 64090 128191 64091 128191 64100 128192 64091 128192 64095 128192 64095 128193 64091 128193 64092 128193 64095 128194 64092 128194 64124 128194 64124 128195 64092 128195 64096 128195 64124 128196 64096 128196 64097 128196 64097 128197 64096 128197 64098 128197 64124 128198 64097 128198 64125 128198 64100 128199 64095 128199 64139 128199 64099 128200 64100 128200 64102 128200 64114 128201 64099 128201 64109 128201 64101 128202 64114 128202 64115 128202 64100 128203 64139 128203 64102 128203 64102 128204 64139 128204 64137 128204 64102 128205 64137 128205 64108 128205 64108 128206 64137 128206 64135 128206 64108 128207 64135 128207 64103 128207 64103 128208 64135 128208 64134 128208 64103 128209 64134 128209 64111 128209 64111 128210 64134 128210 64104 128210 64111 128211 64104 128211 64106 128211 64106 128212 64104 128212 64105 128212 64106 128213 64105 128213 64107 128213 64099 128214 64102 128214 64109 128214 64109 128215 64102 128215 64108 128215 64109 128216 64108 128216 64110 128216 64110 128217 64108 128217 64103 128217 64110 128218 64103 128218 64117 128218 64117 128219 64103 128219 64111 128219 64117 128220 64111 128220 64112 128220 64112 128221 64111 128221 64106 128221 64112 128222 64106 128222 64113 128222 64113 128223 64106 128223 64107 128223 64113 128224 64107 128224 64130 128224 64114 128225 64109 128225 64115 128225 64115 128226 64109 128226 64110 128226 64115 128227 64110 128227 64116 128227 64116 128228 64110 128228 64117 128228 64116 128229 64117 128229 64118 128229 64118 128230 64117 128230 64112 128230 64118 128231 64112 128231 64122 128231 64122 128232 64112 128232 64113 128232 64122 128233 64113 128233 64119 128233 64119 128234 64113 128234 64130 128234 64119 128235 64130 128235 64120 128235 64101 128236 64115 128236 61973 128236 61973 128237 64115 128237 64116 128237 61973 128238 64116 128238 64121 128238 64121 128239 64116 128239 64118 128239 64121 128240 64118 128240 61971 128240 61971 128241 64118 128241 64122 128241 61971 128242 64122 128242 61968 128242 61968 128243 64122 128243 64119 128243 61968 128244 64119 128244 64123 128244 64123 128245 64119 128245 64120 128245 64123 128246 64120 128246 64129 128246 64124 128247 64125 128247 64140 128247 64140 128248 64125 128248 59634 128248 64140 128249 59634 128249 64138 128249 64138 128250 59634 128250 59633 128250 64138 128251 59633 128251 64136 128251 64136 128252 59633 128252 64126 128252 64136 128253 64126 128253 64127 128253 64127 128254 64126 128254 64128 128254 64127 128255 64128 128255 64133 128255 64133 128256 64128 128256 59836 128256 64133 128257 59836 128257 64132 128257 64132 128258 59836 128258 59834 128258 64132 128259 59834 128259 64131 128259 64064 128260 64129 128260 64065 128260 64065 128261 64129 128261 64120 128261 64065 128262 64120 128262 64062 128262 64062 128263 64120 128263 64130 128263 64062 128264 64130 128264 64063 128264 64063 128265 64130 128265 64107 128265 64063 128266 64107 128266 64131 128266 64131 128267 64107 128267 64105 128267 64131 128268 64105 128268 64132 128268 64132 128269 64105 128269 64104 128269 64132 128270 64104 128270 64133 128270 64133 128271 64104 128271 64134 128271 64133 128272 64134 128272 64127 128272 64127 128273 64134 128273 64135 128273 64127 128274 64135 128274 64136 128274 64136 128275 64135 128275 64137 128275 64136 128276 64137 128276 64138 128276 64138 128277 64137 128277 64139 128277 64138 128278 64139 128278 64140 128278 64140 128279 64139 128279 64095 128279 64140 128280 64095 128280 64124 128280 64141 128281 59575 128281 64142 128281 64143 128282 64141 128282 64153 128282 64144 128283 64143 128283 64159 128283 64145 128284 64144 128284 64167 128284 64173 128285 64145 128285 64174 128285 64146 128286 64173 128286 64147 128286 64141 128287 64142 128287 64153 128287 64153 128288 64142 128288 59574 128288 64153 128289 59574 128289 64154 128289 64154 128290 59574 128290 59573 128290 64154 128291 59573 128291 64148 128291 64148 128292 59573 128292 64149 128292 64148 128293 64149 128293 64150 128293 64150 128294 64149 128294 64152 128294 64150 128295 64152 128295 64151 128295 64151 128296 64152 128296 59841 128296 64151 128297 59841 128297 64156 128297 64156 128298 59841 128298 59807 128298 64156 128299 59807 128299 64158 128299 64143 128300 64153 128300 64159 128300 64159 128301 64153 128301 64154 128301 64159 128302 64154 128302 64160 128302 64160 128303 64154 128303 64148 128303 64160 128304 64148 128304 64161 128304 64161 128305 64148 128305 64150 128305 64161 128306 64150 128306 64155 128306 64155 128307 64150 128307 64151 128307 64155 128308 64151 128308 64164 128308 64164 128309 64151 128309 64156 128309 64164 128310 64156 128310 64157 128310 64157 128311 64156 128311 64158 128311 64157 128312 64158 128312 64207 128312 64144 128313 64159 128313 64167 128313 64167 128314 64159 128314 64160 128314 64167 128315 64160 128315 64162 128315 64162 128316 64160 128316 64161 128316 64162 128317 64161 128317 64170 128317 64170 128318 64161 128318 64155 128318 64170 128319 64155 128319 64171 128319 64171 128320 64155 128320 64164 128320 64171 128321 64164 128321 64163 128321 64163 128322 64164 128322 64157 128322 64163 128323 64157 128323 64165 128323 64165 128324 64157 128324 64207 128324 64165 128325 64207 128325 64166 128325 64145 128326 64167 128326 64174 128326 64174 128327 64167 128327 64162 128327 64174 128328 64162 128328 64168 128328 64168 128329 64162 128329 64170 128329 64168 128330 64170 128330 64169 128330 64169 128331 64170 128331 64171 128331 64169 128332 64171 128332 64176 128332 64176 128333 64171 128333 64163 128333 64176 128334 64163 128334 64178 128334 64178 128335 64163 128335 64165 128335 64178 128336 64165 128336 64181 128336 64181 128337 64165 128337 64166 128337 64181 128338 64166 128338 64172 128338 64173 128339 64174 128339 64147 128339 64147 128340 64174 128340 64168 128340 64147 128341 64168 128341 64183 128341 64183 128342 64168 128342 64169 128342 64183 128343 64169 128343 64175 128343 64175 128344 64169 128344 64176 128344 64175 128345 64176 128345 64177 128345 64177 128346 64176 128346 64178 128346 64177 128347 64178 128347 64179 128347 64179 128348 64178 128348 64181 128348 64179 128349 64181 128349 64180 128349 64180 128350 64181 128350 64172 128350 64180 128351 64172 128351 64199 128351 64146 128352 64147 128352 64182 128352 64182 128353 64147 128353 64183 128353 64182 128354 64183 128354 61947 128354 61947 128355 64183 128355 64175 128355 61947 128356 64175 128356 61948 128356 61948 128357 64175 128357 64177 128357 61948 128358 64177 128358 64184 128358 64184 128359 64177 128359 64179 128359 64184 128360 64179 128360 64185 128360 64185 128361 64179 128361 64180 128361 64185 128362 64180 128362 61940 128362 61940 128363 64180 128363 64199 128363 61940 128364 64199 128364 64200 128364 64191 128365 64186 128365 64192 128365 64192 128366 64186 128366 64187 128366 64192 128367 64187 128367 64193 128367 64193 128368 64187 128368 64188 128368 64193 128369 64188 128369 64194 128369 64194 128370 64188 128370 64189 128370 64194 128371 64189 128371 64195 128371 64195 128372 64189 128372 64190 128372 64195 128373 64190 128373 64196 128373 64196 128374 64190 128374 64271 128374 64196 128375 64271 128375 59577 128375 59577 128376 64271 128376 59578 128376 64146 128377 64191 128377 64173 128377 64173 128378 64191 128378 64192 128378 64173 128379 64192 128379 64145 128379 64145 128380 64192 128380 64193 128380 64145 128381 64193 128381 64144 128381 64144 128382 64193 128382 64194 128382 64144 128383 64194 128383 64143 128383 64143 128384 64194 128384 64195 128384 64143 128385 64195 128385 64141 128385 64141 128386 64195 128386 64196 128386 64141 128387 64196 128387 59575 128387 59575 128388 64196 128388 59577 128388 64197 128389 64212 128389 64205 128389 64207 128390 64158 128390 64198 128390 64158 128391 59807 128391 64201 128391 64172 128392 64166 128392 64208 128392 64208 128393 64166 128393 64207 128393 64214 128394 64199 128394 64172 128394 64199 128395 64214 128395 64200 128395 64158 128396 64201 128396 64198 128396 64198 128397 64201 128397 59811 128397 64198 128398 59811 128398 64202 128398 64202 128399 59811 128399 59813 128399 64202 128400 59813 128400 64210 128400 64210 128401 59813 128401 64203 128401 64210 128402 64203 128402 64211 128402 64211 128403 64203 128403 64204 128403 64211 128404 64204 128404 64205 128404 64205 128405 64204 128405 64206 128405 64205 128406 64206 128406 64197 128406 64207 128407 64198 128407 64208 128407 64208 128408 64198 128408 64202 128408 64208 128409 64202 128409 64215 128409 64215 128410 64202 128410 64210 128410 64215 128411 64210 128411 64209 128411 64209 128412 64210 128412 64211 128412 64209 128413 64211 128413 64217 128413 64217 128414 64211 128414 64205 128414 64217 128415 64205 128415 64213 128415 64213 128416 64205 128416 64212 128416 64213 128417 64212 128417 64274 128417 64172 128418 64208 128418 64214 128418 64214 128419 64208 128419 64215 128419 64214 128420 64215 128420 64222 128420 64222 128421 64215 128421 64209 128421 64222 128422 64209 128422 64216 128422 64216 128423 64209 128423 64217 128423 64216 128424 64217 128424 64218 128424 64218 128425 64217 128425 64213 128425 64218 128426 64213 128426 64219 128426 64219 128427 64213 128427 64274 128427 64219 128428 64274 128428 64220 128428 64200 128429 64214 128429 64221 128429 64221 128430 64214 128430 64222 128430 64221 128431 64222 128431 62052 128431 62052 128432 64222 128432 64216 128432 62052 128433 64216 128433 64223 128433 64223 128434 64216 128434 64218 128434 64223 128435 64218 128435 62049 128435 62049 128436 64218 128436 64219 128436 62049 128437 64219 128437 62048 128437 62048 128438 64219 128438 64220 128438 62048 128439 64220 128439 64224 128439 64225 128440 64226 128440 64250 128440 64227 128441 59583 128441 64228 128441 64236 128442 64230 128442 64229 128442 64229 128443 64230 128443 64231 128443 64229 128444 64231 128444 64237 128444 64237 128445 64231 128445 64232 128445 64237 128446 64232 128446 64233 128446 64233 128447 64232 128447 64323 128447 64233 128448 64323 128448 64234 128448 64234 128449 64323 128449 64321 128449 64234 128450 64321 128450 64235 128450 64235 128451 64321 128451 64320 128451 64227 128452 64228 128452 59584 128452 61939 128453 64236 128453 64239 128453 64239 128454 64236 128454 64229 128454 64239 128455 64229 128455 64243 128455 64243 128456 64229 128456 64237 128456 64243 128457 64237 128457 64244 128457 64244 128458 64237 128458 64233 128458 64244 128459 64233 128459 64238 128459 64238 128460 64233 128460 64234 128460 64238 128461 64234 128461 64228 128461 64228 128462 64234 128462 64235 128462 64228 128463 64235 128463 59584 128463 59584 128464 64235 128464 64320 128464 59584 128465 64320 128465 59586 128465 64247 128466 61939 128466 64240 128466 64240 128467 61939 128467 64239 128467 64240 128468 64239 128468 64241 128468 64241 128469 64239 128469 64243 128469 64241 128470 64243 128470 64242 128470 64242 128471 64243 128471 64244 128471 64242 128472 64244 128472 64245 128472 64245 128473 64244 128473 64238 128473 64245 128474 64238 128474 64246 128474 64246 128475 64238 128475 64228 128475 64246 128476 64228 128476 59582 128476 59582 128477 64228 128477 59583 128477 64251 128478 64247 128478 64248 128478 64248 128479 64247 128479 64240 128479 64248 128480 64240 128480 64252 128480 64252 128481 64240 128481 64241 128481 64252 128482 64241 128482 64254 128482 64254 128483 64241 128483 64242 128483 64254 128484 64242 128484 64255 128484 64255 128485 64242 128485 64245 128485 64255 128486 64245 128486 64249 128486 64249 128487 64245 128487 64246 128487 64249 128488 64246 128488 59579 128488 59579 128489 64246 128489 59582 128489 64226 128490 64251 128490 64250 128490 64250 128491 64251 128491 64248 128491 64250 128492 64248 128492 64258 128492 64258 128493 64248 128493 64252 128493 64258 128494 64252 128494 64253 128494 64253 128495 64252 128495 64254 128495 64253 128496 64254 128496 64261 128496 64261 128497 64254 128497 64255 128497 64261 128498 64255 128498 64262 128498 64262 128499 64255 128499 64249 128499 64262 128500 64249 128500 64256 128500 64256 128501 64249 128501 59579 128501 64265 128502 64225 128502 64267 128502 64267 128503 64225 128503 64250 128503 64267 128504 64250 128504 64257 128504 64257 128505 64250 128505 64258 128505 64257 128506 64258 128506 64259 128506 64259 128507 64258 128507 64253 128507 64259 128508 64253 128508 64260 128508 64260 128509 64253 128509 64261 128509 64260 128510 64261 128510 64269 128510 64269 128511 64261 128511 64262 128511 64269 128512 64262 128512 64263 128512 64263 128513 64262 128513 64256 128513 61937 128514 64265 128514 64264 128514 64264 128515 64265 128515 64267 128515 64264 128516 64267 128516 64266 128516 64266 128517 64267 128517 64257 128517 64266 128518 64257 128518 64270 128518 64270 128519 64257 128519 64259 128519 64270 128520 64259 128520 64268 128520 64268 128521 64259 128521 64260 128521 64268 128522 64260 128522 64272 128522 64272 128523 64260 128523 64269 128523 64272 128524 64269 128524 64273 128524 64273 128525 64269 128525 64263 128525 64186 128526 61937 128526 64187 128526 64187 128527 61937 128527 64264 128527 64187 128528 64264 128528 64188 128528 64188 128529 64264 128529 64266 128529 64188 128530 64266 128530 64189 128530 64189 128531 64266 128531 64270 128531 64189 128532 64270 128532 64190 128532 64190 128533 64270 128533 64268 128533 64190 128534 64268 128534 64271 128534 64271 128535 64268 128535 64272 128535 64271 128536 64272 128536 59578 128536 59578 128537 64272 128537 64273 128537 64274 128538 64212 128538 64275 128538 64220 128539 64274 128539 64298 128539 64224 128540 64220 128540 64276 128540 64224 128541 64276 128541 64277 128541 64277 128542 64276 128542 64299 128542 64277 128543 64299 128543 62045 128543 62045 128544 64299 128544 64300 128544 62045 128545 64300 128545 64278 128545 64278 128546 64300 128546 64302 128546 64278 128547 64302 128547 62042 128547 62042 128548 64302 128548 62044 128548 62044 128549 64302 128549 64279 128549 62044 128550 64279 128550 64280 128550 64280 128551 64279 128551 64281 128551 64280 128552 64281 128552 62040 128552 64274 128553 64275 128553 64298 128553 64298 128554 64275 128554 64293 128554 64298 128555 64293 128555 64282 128555 64282 128556 64293 128556 64283 128556 64282 128557 64283 128557 64284 128557 64284 128558 64283 128558 64292 128558 64284 128559 64292 128559 64285 128559 64285 128560 64292 128560 64286 128560 64285 128561 64286 128561 64301 128561 64301 128562 64286 128562 64287 128562 64301 128563 64287 128563 64288 128563 64288 128564 64287 128564 64289 128564 64288 128565 64289 128565 64303 128565 64303 128566 64289 128566 64296 128566 64303 128567 64296 128567 64297 128567 64295 128568 64296 128568 59598 128568 59598 128569 64296 128569 64289 128569 59598 128570 64289 128570 64290 128570 64290 128571 64289 128571 64287 128571 64290 128572 64287 128572 59599 128572 59599 128573 64287 128573 64286 128573 59599 128574 64286 128574 64291 128574 64291 128575 64286 128575 64292 128575 64291 128576 64292 128576 59814 128576 59814 128577 64292 128577 64283 128577 59814 128578 64283 128578 59815 128578 59815 128579 64283 128579 64293 128579 59815 128580 64293 128580 64294 128580 64294 128581 64293 128581 64275 128581 64294 128582 64275 128582 59816 128582 59816 128583 64275 128583 64212 128583 59816 128584 64212 128584 64197 128584 64295 128585 64337 128585 64296 128585 64296 128586 64337 128586 64336 128586 64296 128587 64336 128587 64297 128587 64297 128588 64336 128588 64340 128588 64297 128589 64340 128589 64341 128589 64220 128590 64298 128590 64276 128590 64276 128591 64298 128591 64282 128591 64276 128592 64282 128592 64299 128592 64299 128593 64282 128593 64284 128593 64299 128594 64284 128594 64300 128594 64300 128595 64284 128595 64285 128595 64300 128596 64285 128596 64302 128596 64302 128597 64285 128597 64301 128597 64302 128598 64301 128598 64279 128598 64279 128599 64301 128599 64288 128599 64279 128600 64288 128600 64281 128600 64281 128601 64288 128601 64303 128601 64281 128602 64303 128602 64305 128602 64305 128603 64303 128603 64297 128603 64305 128604 64297 128604 64304 128604 64304 128605 64297 128605 64341 128605 64304 128606 64341 128606 64342 128606 62040 128607 64281 128607 62041 128607 62041 128608 64281 128608 64305 128608 62041 128609 64305 128609 64306 128609 64306 128610 64305 128610 64304 128610 64306 128611 64304 128611 62037 128611 62037 128612 64304 128612 64342 128612 62037 128613 64342 128613 64343 128613 64307 128614 64308 128614 59593 128614 64312 128615 64307 128615 64309 128615 64384 128616 64312 128616 64324 128616 64328 128617 64384 128617 64325 128617 64307 128618 59593 128618 64309 128618 64309 128619 59593 128619 64310 128619 64309 128620 64310 128620 64311 128620 64312 128621 64309 128621 64324 128621 64324 128622 64309 128622 64311 128622 64324 128623 64311 128623 64313 128623 64313 128624 64311 128624 64314 128624 64313 128625 64314 128625 64326 128625 64326 128626 64314 128626 64315 128626 64326 128627 64315 128627 64316 128627 64316 128628 64315 128628 64319 128628 64316 128629 64319 128629 64322 128629 64310 128630 59589 128630 64311 128630 64311 128631 59589 128631 59592 128631 64311 128632 59592 128632 64314 128632 64314 128633 59592 128633 64317 128633 64314 128634 64317 128634 64315 128634 64315 128635 64317 128635 64318 128635 64315 128636 64318 128636 64319 128636 64319 128637 64318 128637 59586 128637 59586 128638 64320 128638 64319 128638 64319 128639 64320 128639 64321 128639 64319 128640 64321 128640 64322 128640 64322 128641 64321 128641 64323 128641 64322 128642 64323 128642 64232 128642 64384 128643 64324 128643 64325 128643 64325 128644 64324 128644 64313 128644 64325 128645 64313 128645 64330 128645 64330 128646 64313 128646 64326 128646 64330 128647 64326 128647 64332 128647 64332 128648 64326 128648 64316 128648 64332 128649 64316 128649 64327 128649 64327 128650 64316 128650 64322 128650 64327 128651 64322 128651 64335 128651 64335 128652 64322 128652 64232 128652 64335 128653 64232 128653 64231 128653 64328 128654 64325 128654 64329 128654 64329 128655 64325 128655 64330 128655 64329 128656 64330 128656 64331 128656 64331 128657 64330 128657 64332 128657 64331 128658 64332 128658 64333 128658 64333 128659 64332 128659 64327 128659 64333 128660 64327 128660 64334 128660 64334 128661 64327 128661 64335 128661 64334 128662 64335 128662 62023 128662 62023 128663 64335 128663 64231 128663 62023 128664 64231 128664 64230 128664 64338 128665 64336 128665 64337 128665 64336 128666 64338 128666 64340 128666 64340 128667 64338 128667 64339 128667 64340 128668 64339 128668 64341 128668 64341 128669 64339 128669 64342 128669 64342 128670 64339 128670 62036 128670 64342 128671 62036 128671 64343 128671 59602 128672 64338 128672 59603 128672 59603 128673 64338 128673 64337 128673 59603 128674 64337 128674 64295 128674 64347 128675 62036 128675 64344 128675 64344 128676 62036 128676 64339 128676 64344 128677 64339 128677 64345 128677 64345 128678 64339 128678 64338 128678 64345 128679 64338 128679 64348 128679 64348 128680 64338 128680 59602 128680 64348 128681 59602 128681 64349 128681 64345 128682 64348 128682 64350 128682 64344 128683 64345 128683 64359 128683 64362 128684 64346 128684 64360 128684 64360 128685 64346 128685 64347 128685 64360 128686 64347 128686 64344 128686 64348 128687 64349 128687 64350 128687 64350 128688 64349 128688 64352 128688 64350 128689 64352 128689 64351 128689 64351 128690 64352 128690 59597 128690 64351 128691 59597 128691 64353 128691 64353 128692 59597 128692 64354 128692 64353 128693 64354 128693 64357 128693 64357 128694 64354 128694 64356 128694 64357 128695 64356 128695 64355 128695 64355 128696 64356 128696 59596 128696 64355 128697 59596 128697 64374 128697 64345 128698 64350 128698 64359 128698 64359 128699 64350 128699 64351 128699 64359 128700 64351 128700 64361 128700 64361 128701 64351 128701 64353 128701 64361 128702 64353 128702 64363 128702 64363 128703 64353 128703 64357 128703 64363 128704 64357 128704 64365 128704 64365 128705 64357 128705 64355 128705 64365 128706 64355 128706 64358 128706 64358 128707 64355 128707 64374 128707 64358 128708 64374 128708 64375 128708 64344 128709 64359 128709 64360 128709 64360 128710 64359 128710 64361 128710 64360 128711 64361 128711 64362 128711 64362 128712 64361 128712 64363 128712 64362 128713 64363 128713 64364 128713 64364 128714 64363 128714 64365 128714 64364 128715 64365 128715 64366 128715 64366 128716 64365 128716 64358 128716 64366 128717 64358 128717 64367 128717 64367 128718 64358 128718 64375 128718 64367 128719 64375 128719 64369 128719 64378 128720 64368 128720 64369 128720 64369 128721 64368 128721 62032 128721 64369 128722 62032 128722 64367 128722 64367 128723 62032 128723 64370 128723 64367 128724 64370 128724 64366 128724 64366 128725 64370 128725 64371 128725 64366 128726 64371 128726 64364 128726 64364 128727 64371 128727 62035 128727 64364 128728 62035 128728 64362 128728 64362 128729 62035 128729 64372 128729 64362 128730 64372 128730 64346 128730 59596 128731 64373 128731 64374 128731 64374 128732 64373 128732 64376 128732 64374 128733 64376 128733 64375 128733 64375 128734 64376 128734 64377 128734 64375 128735 64377 128735 64369 128735 64369 128736 64377 128736 64379 128736 64369 128737 64379 128737 64378 128737 64378 128738 64379 128738 64380 128738 62029 128739 64380 128739 64383 128739 64383 128740 64380 128740 64379 128740 64383 128741 64379 128741 64381 128741 64381 128742 64379 128742 64377 128742 64381 128743 64377 128743 64382 128743 64382 128744 64377 128744 64376 128744 64382 128745 64376 128745 59595 128745 59595 128746 64376 128746 64373 128746 64328 128747 62029 128747 64384 128747 64384 128748 62029 128748 64383 128748 64384 128749 64383 128749 64312 128749 64312 128750 64383 128750 64381 128750 64312 128751 64381 128751 64307 128751 64307 128752 64381 128752 64382 128752 64307 128753 64382 128753 64308 128753 64308 128754 64382 128754 59595 128754 64385 128755 64386 128755 64415 128755 64390 128756 64429 128756 64398 128756 64389 128757 64391 128757 64395 128757 64391 128758 64387 128758 64388 128758 64389 128759 64395 128759 64429 128759 64390 128760 64398 128760 64430 128760 64391 128761 64388 128761 64395 128761 64395 128762 64388 128762 59600 128762 64395 128763 59600 128763 64396 128763 64396 128764 59600 128764 64393 128764 64396 128765 64393 128765 64392 128765 64392 128766 64393 128766 59798 128766 64392 128767 59798 128767 64394 128767 64429 128768 64395 128768 64398 128768 64398 128769 64395 128769 64396 128769 64398 128770 64396 128770 64401 128770 64401 128771 64396 128771 64392 128771 64401 128772 64392 128772 64402 128772 64402 128773 64392 128773 64394 128773 64402 128774 64394 128774 64397 128774 64430 128775 64398 128775 64399 128775 64399 128776 64398 128776 64401 128776 64399 128777 64401 128777 64400 128777 64400 128778 64401 128778 64402 128778 64400 128779 64402 128779 64404 128779 64404 128780 64402 128780 64397 128780 64404 128781 64397 128781 64408 128781 62011 128782 62010 128782 64408 128782 64408 128783 62010 128783 64403 128783 64408 128784 64403 128784 64404 128784 64404 128785 64403 128785 62020 128785 64404 128786 62020 128786 64400 128786 64400 128787 62020 128787 64405 128787 64400 128788 64405 128788 64399 128788 64399 128789 64405 128789 62018 128789 64399 128790 62018 128790 64430 128790 62016 128791 62011 128791 64406 128791 64406 128792 62011 128792 64408 128792 64406 128793 64408 128793 64407 128793 64407 128794 64408 128794 64397 128794 64407 128795 64397 128795 64409 128795 64409 128796 64397 128796 64394 128796 64409 128797 64394 128797 64410 128797 64410 128798 64394 128798 59798 128798 64386 128799 62016 128799 64415 128799 64415 128800 62016 128800 64406 128800 64415 128801 64406 128801 64411 128801 64411 128802 64406 128802 64407 128802 64411 128803 64407 128803 64412 128803 64412 128804 64407 128804 64409 128804 64412 128805 64409 128805 64418 128805 64418 128806 64409 128806 64410 128806 64413 128807 64385 128807 64414 128807 64414 128808 64385 128808 64415 128808 64414 128809 64415 128809 64421 128809 64421 128810 64415 128810 64411 128810 64421 128811 64411 128811 64416 128811 64416 128812 64411 128812 64412 128812 64416 128813 64412 128813 64417 128813 64417 128814 64412 128814 64418 128814 62013 128815 64413 128815 64419 128815 64419 128816 64413 128816 64414 128816 64419 128817 64414 128817 64420 128817 64420 128818 64414 128818 64421 128818 64420 128819 64421 128819 64425 128819 64425 128820 64421 128820 64416 128820 64425 128821 64416 128821 59800 128821 59800 128822 64416 128822 64417 128822 64422 128823 62013 128823 64423 128823 64423 128824 62013 128824 64419 128824 64423 128825 64419 128825 64432 128825 64432 128826 64419 128826 64420 128826 64432 128827 64420 128827 64424 128827 64424 128828 64420 128828 64425 128828 64424 128829 64425 128829 59799 128829 59799 128830 64425 128830 59800 128830 64391 128831 64389 128831 64428 128831 64488 128832 64487 128832 64427 128832 64498 128833 64431 128833 64426 128833 64426 128834 64431 128834 62008 128834 64426 128835 62008 128835 62009 128835 64387 128836 64391 128836 64427 128836 64427 128837 64391 128837 64428 128837 64427 128838 64428 128838 64488 128838 64488 128839 64428 128839 64489 128839 64389 128840 64429 128840 64428 128840 64428 128841 64429 128841 64431 128841 64428 128842 64431 128842 64489 128842 64489 128843 64431 128843 64498 128843 62018 128844 62008 128844 64430 128844 64430 128845 62008 128845 64431 128845 64430 128846 64431 128846 64390 128846 64390 128847 64431 128847 64429 128847 64424 128848 59799 128848 64434 128848 64432 128849 64424 128849 64433 128849 64423 128850 64432 128850 64442 128850 64422 128851 64423 128851 64452 128851 64424 128852 64434 128852 64433 128852 64433 128853 64434 128853 64435 128853 64433 128854 64435 128854 64443 128854 64435 128855 59801 128855 64443 128855 64443 128856 59801 128856 64436 128856 64443 128857 64436 128857 64437 128857 64437 128858 64436 128858 59803 128858 64437 128859 59803 128859 64445 128859 64445 128860 59803 128860 64438 128860 64445 128861 64438 128861 64439 128861 64439 128862 64438 128862 64440 128862 64439 128863 64440 128863 64441 128863 64432 128864 64433 128864 64442 128864 64442 128865 64433 128865 64443 128865 64442 128866 64443 128866 64449 128866 64449 128867 64443 128867 64437 128867 64449 128868 64437 128868 64444 128868 64444 128869 64437 128869 64445 128869 64444 128870 64445 128870 64446 128870 64446 128871 64445 128871 64439 128871 64446 128872 64439 128872 64447 128872 64447 128873 64439 128873 64441 128873 64447 128874 64441 128874 64448 128874 64423 128875 64442 128875 64452 128875 64452 128876 64442 128876 64449 128876 64452 128877 64449 128877 64454 128877 64454 128878 64449 128878 64444 128878 64454 128879 64444 128879 64450 128879 64450 128880 64444 128880 64446 128880 64450 128881 64446 128881 64451 128881 64451 128882 64446 128882 64447 128882 64451 128883 64447 128883 64455 128883 64455 128884 64447 128884 64448 128884 64455 128885 64448 128885 64457 128885 64422 128886 64452 128886 64453 128886 64453 128887 64452 128887 64454 128887 64453 128888 64454 128888 61985 128888 61985 128889 64454 128889 64450 128889 61985 128890 64450 128890 61987 128890 61987 128891 64450 128891 64451 128891 61987 128892 64451 128892 64456 128892 64456 128893 64451 128893 64455 128893 64456 128894 64455 128894 61989 128894 61989 128895 64455 128895 64457 128895 61989 128896 64457 128896 64458 128896 64459 128897 59606 128897 64468 128897 64560 128898 64459 128898 64477 128898 64460 128899 64560 128899 64490 128899 61997 128900 64460 128900 64461 128900 61997 128901 64461 128901 61996 128901 61996 128902 64461 128902 64462 128902 61996 128903 64462 128903 61994 128903 61994 128904 64462 128904 64463 128904 64463 128905 64462 128905 64492 128905 64463 128906 64492 128906 64464 128906 64464 128907 64492 128907 64493 128907 64464 128908 64493 128908 64465 128908 64465 128909 64493 128909 64495 128909 64465 128910 64495 128910 64466 128910 64466 128911 64495 128911 64500 128911 64466 128912 64500 128912 64467 128912 64459 128913 64468 128913 64477 128913 64477 128914 64468 128914 64469 128914 64477 128915 64469 128915 64470 128915 64470 128916 64469 128916 64471 128916 64470 128917 64471 128917 64478 128917 64478 128918 64471 128918 64472 128918 64478 128919 64472 128919 64473 128919 64473 128920 64472 128920 64474 128920 64473 128921 64474 128921 64481 128921 64481 128922 64474 128922 64475 128922 64481 128923 64475 128923 64482 128923 64482 128924 64475 128924 59604 128924 64482 128925 59604 128925 64484 128925 64484 128926 59604 128926 64476 128926 64484 128927 64476 128927 64486 128927 64560 128928 64477 128928 64490 128928 64490 128929 64477 128929 64470 128929 64490 128930 64470 128930 64491 128930 64491 128931 64470 128931 64478 128931 64491 128932 64478 128932 64479 128932 64479 128933 64478 128933 64473 128933 64479 128934 64473 128934 64480 128934 64480 128935 64473 128935 64481 128935 64480 128936 64481 128936 64494 128936 64494 128937 64481 128937 64482 128937 64494 128938 64482 128938 64483 128938 64483 128939 64482 128939 64484 128939 64483 128940 64484 128940 64485 128940 64485 128941 64484 128941 64486 128941 64485 128942 64486 128942 64497 128942 64476 128943 64487 128943 64486 128943 64486 128944 64487 128944 64488 128944 64486 128945 64488 128945 64497 128945 64497 128946 64488 128946 64489 128946 64497 128947 64489 128947 64498 128947 64460 128948 64490 128948 64461 128948 64461 128949 64490 128949 64491 128949 64461 128950 64491 128950 64462 128950 64462 128951 64491 128951 64479 128951 64462 128952 64479 128952 64492 128952 64492 128953 64479 128953 64480 128953 64492 128954 64480 128954 64493 128954 64493 128955 64480 128955 64494 128955 64493 128956 64494 128956 64495 128956 64495 128957 64494 128957 64483 128957 64495 128958 64483 128958 64500 128958 64500 128959 64483 128959 64485 128959 64500 128960 64485 128960 64496 128960 64496 128961 64485 128961 64497 128961 64496 128962 64497 128962 64501 128962 64501 128963 64497 128963 64498 128963 64501 128964 64498 128964 64426 128964 64467 128965 64500 128965 64499 128965 64499 128966 64500 128966 64496 128966 64499 128967 64496 128967 61991 128967 61991 128968 64496 128968 64501 128968 61991 128969 64501 128969 61990 128969 61990 128970 64501 128970 64426 128970 61990 128971 64426 128971 62009 128971 64441 128972 64440 128972 64502 128972 64502 128973 64503 128973 64441 128973 64441 128974 64503 128974 64507 128974 64441 128975 64507 128975 64448 128975 64448 128976 64507 128976 64504 128976 64448 128977 64504 128977 64457 128977 64505 128978 64458 128978 64511 128978 64511 128979 64458 128979 64457 128979 64511 128980 64457 128980 64509 128980 64509 128981 64457 128981 64504 128981 64502 128982 64523 128982 64503 128982 64503 128983 64523 128983 64506 128983 64503 128984 64506 128984 64507 128984 64507 128985 64506 128985 64508 128985 64507 128986 64508 128986 64504 128986 64504 128987 64508 128987 64526 128987 64504 128988 64526 128988 64509 128988 64509 128989 64526 128989 64510 128989 64509 128990 64510 128990 64511 128990 64511 128991 64510 128991 64528 128991 64511 128992 64528 128992 64505 128992 64529 128993 64512 128993 64528 128993 64528 128994 64512 128994 64513 128994 64528 128995 64513 128995 64505 128995 59622 128996 59621 128996 64524 128996 64524 128997 59621 128997 64518 128997 64524 128998 64518 128998 64525 128998 64525 128999 64518 128999 64520 128999 64525 129000 64520 129000 64527 129000 64527 129001 64520 129001 64514 129001 64527 129002 64514 129002 64515 129002 64515 129003 64514 129003 64521 129003 64515 129004 64521 129004 64516 129004 64516 129005 64521 129005 64530 129005 59621 129006 64517 129006 64518 129006 64518 129007 64517 129007 64539 129007 64518 129008 64539 129008 64520 129008 64520 129009 64539 129009 64519 129009 64520 129010 64519 129010 64514 129010 64514 129011 64519 129011 64522 129011 64514 129012 64522 129012 64521 129012 64521 129013 64522 129013 64543 129013 64521 129014 64543 129014 64530 129014 64530 129015 64543 129015 64545 129015 64523 129016 59622 129016 64506 129016 64506 129017 59622 129017 64524 129017 64506 129018 64524 129018 64508 129018 64508 129019 64524 129019 64525 129019 64508 129020 64525 129020 64526 129020 64526 129021 64525 129021 64527 129021 64526 129022 64527 129022 64510 129022 64510 129023 64527 129023 64515 129023 64510 129024 64515 129024 64528 129024 64528 129025 64515 129025 64516 129025 64528 129026 64516 129026 64529 129026 64529 129027 64516 129027 64530 129027 64529 129028 64530 129028 64532 129028 64532 129029 64530 129029 64545 129029 61931 129030 61932 129030 64545 129030 64545 129031 61932 129031 64531 129031 64545 129032 64531 129032 64532 129032 59620 129033 59619 129033 64540 129033 64540 129034 59619 129034 64538 129034 64540 129035 64538 129035 64541 129035 64541 129036 64538 129036 64537 129036 64541 129037 64537 129037 64542 129037 64542 129038 64537 129038 64535 129038 64542 129039 64535 129039 64544 129039 64544 129040 64535 129040 64534 129040 64544 129041 64534 129041 64533 129041 64533 129042 64534 129042 64546 129042 64572 129043 64546 129043 64574 129043 64574 129044 64546 129044 64534 129044 64574 129045 64534 129045 64575 129045 64575 129046 64534 129046 64535 129046 64575 129047 64535 129047 64536 129047 64536 129048 64535 129048 64537 129048 64536 129049 64537 129049 64576 129049 64576 129050 64537 129050 64538 129050 64576 129051 64538 129051 59618 129051 59618 129052 64538 129052 59619 129052 64517 129053 59620 129053 64539 129053 64539 129054 59620 129054 64540 129054 64539 129055 64540 129055 64519 129055 64519 129056 64540 129056 64541 129056 64519 129057 64541 129057 64522 129057 64522 129058 64541 129058 64542 129058 64522 129059 64542 129059 64543 129059 64543 129060 64542 129060 64544 129060 64543 129061 64544 129061 64545 129061 64545 129062 64544 129062 64533 129062 64545 129063 64533 129063 61931 129063 61931 129064 64533 129064 64546 129064 61931 129065 64546 129065 64547 129065 64547 129066 64546 129066 64572 129066 64547 129067 64572 129067 61920 129067 59606 129068 64459 129068 64548 129068 64550 129069 64615 129069 64561 129069 64549 129070 64613 129070 59616 129070 64618 129071 64549 129071 64551 129071 64615 129072 64618 129072 64557 129072 62000 129073 61999 129073 64550 129073 64549 129074 59616 129074 64551 129074 64551 129075 59616 129075 64552 129075 64551 129076 64552 129076 64553 129076 64553 129077 64552 129077 59609 129077 64553 129078 59609 129078 64554 129078 64554 129079 59609 129079 59608 129079 64554 129080 59608 129080 64559 129080 64559 129081 59608 129081 64555 129081 64559 129082 64555 129082 64548 129082 64548 129083 64555 129083 64556 129083 64548 129084 64556 129084 59606 129084 64618 129085 64551 129085 64557 129085 64557 129086 64551 129086 64553 129086 64557 129087 64553 129087 64558 129087 64558 129088 64553 129088 64554 129088 64558 129089 64554 129089 64562 129089 64562 129090 64554 129090 64559 129090 64562 129091 64559 129091 64565 129091 64565 129092 64559 129092 64548 129092 64565 129093 64548 129093 64566 129093 64566 129094 64548 129094 64459 129094 64566 129095 64459 129095 64560 129095 64615 129096 64557 129096 64561 129096 64561 129097 64557 129097 64558 129097 64561 129098 64558 129098 64568 129098 64568 129099 64558 129099 64562 129099 64568 129100 64562 129100 64563 129100 64563 129101 64562 129101 64565 129101 64563 129102 64565 129102 64564 129102 64564 129103 64565 129103 64566 129103 64564 129104 64566 129104 64567 129104 64567 129105 64566 129105 64560 129105 64567 129106 64560 129106 64460 129106 64550 129107 64561 129107 62000 129107 62000 129108 64561 129108 64568 129108 62000 129109 64568 129109 64569 129109 64569 129110 64568 129110 64563 129110 64569 129111 64563 129111 62004 129111 62004 129112 64563 129112 64564 129112 62004 129113 64564 129113 64570 129113 64570 129114 64564 129114 64567 129114 64570 129115 64567 129115 62002 129115 62002 129116 64567 129116 64460 129116 62002 129117 64460 129117 61997 129117 61919 129118 61920 129118 64571 129118 64571 129119 61920 129119 64572 129119 64571 129120 64572 129120 64573 129120 64573 129121 64572 129121 64574 129121 64573 129122 64574 129122 64579 129122 64579 129123 64574 129123 64575 129123 64579 129124 64575 129124 64580 129124 64580 129125 64575 129125 64536 129125 64580 129126 64536 129126 64581 129126 64581 129127 64536 129127 64576 129127 64581 129128 64576 129128 64577 129128 64577 129129 64576 129129 59618 129129 64599 129130 61919 129130 64583 129130 64583 129131 61919 129131 64571 129131 64583 129132 64571 129132 64591 129132 64591 129133 64571 129133 64573 129133 64591 129134 64573 129134 64584 129134 64584 129135 64573 129135 64579 129135 64584 129136 64579 129136 64578 129136 64578 129137 64579 129137 64580 129137 64578 129138 64580 129138 64625 129138 64625 129139 64580 129139 64581 129139 64625 129140 64581 129140 64582 129140 64582 129141 64581 129141 64577 129141 64625 129142 64582 129142 64605 129142 64584 129143 64578 129143 64623 129143 64591 129144 64584 129144 64585 129144 64583 129145 64591 129145 64594 129145 64599 129146 64583 129146 64600 129146 64584 129147 64623 129147 64585 129147 64585 129148 64623 129148 64622 129148 64585 129149 64622 129149 64586 129149 64586 129150 64622 129150 64587 129150 64586 129151 64587 129151 64588 129151 64588 129152 64587 129152 64621 129152 64588 129153 64621 129153 64589 129153 64589 129154 64621 129154 64620 129154 64589 129155 64620 129155 64593 129155 64593 129156 64620 129156 64619 129156 64593 129157 64619 129157 64590 129157 64591 129158 64585 129158 64594 129158 64594 129159 64585 129159 64586 129159 64594 129160 64586 129160 64595 129160 64595 129161 64586 129161 64588 129161 64595 129162 64588 129162 64596 129162 64596 129163 64588 129163 64589 129163 64596 129164 64589 129164 64592 129164 64592 129165 64589 129165 64593 129165 64592 129166 64593 129166 64598 129166 64598 129167 64593 129167 64590 129167 64598 129168 64590 129168 64617 129168 64583 129169 64594 129169 64600 129169 64600 129170 64594 129170 64595 129170 64600 129171 64595 129171 64601 129171 64601 129172 64595 129172 64596 129172 64601 129173 64596 129173 64602 129173 64602 129174 64596 129174 64592 129174 64602 129175 64592 129175 64597 129175 64597 129176 64592 129176 64598 129176 64597 129177 64598 129177 64603 129177 64603 129178 64598 129178 64617 129178 64603 129179 64617 129179 64616 129179 64599 129180 64600 129180 61928 129180 61928 129181 64600 129181 64601 129181 61928 129182 64601 129182 61926 129182 61926 129183 64601 129183 64602 129183 61926 129184 64602 129184 61924 129184 61924 129185 64602 129185 64597 129185 61924 129186 64597 129186 61923 129186 61923 129187 64597 129187 64603 129187 61923 129188 64603 129188 64604 129188 64604 129189 64603 129189 64616 129189 64604 129190 64616 129190 64614 129190 64625 129191 64605 129191 64624 129191 64624 129192 64605 129192 59610 129192 64624 129193 59610 129193 64606 129193 64606 129194 59610 129194 64607 129194 64606 129195 64607 129195 64608 129195 64608 129196 64607 129196 59611 129196 64608 129197 59611 129197 64609 129197 64609 129198 59611 129198 59612 129198 64609 129199 59612 129199 64610 129199 64610 129200 59612 129200 64612 129200 64610 129201 64612 129201 64611 129201 64611 129202 64612 129202 64613 129202 64611 129203 64613 129203 64549 129203 61999 129204 64614 129204 64550 129204 64550 129205 64614 129205 64616 129205 64550 129206 64616 129206 64615 129206 64615 129207 64616 129207 64617 129207 64615 129208 64617 129208 64618 129208 64618 129209 64617 129209 64590 129209 64618 129210 64590 129210 64549 129210 64549 129211 64590 129211 64619 129211 64549 129212 64619 129212 64611 129212 64611 129213 64619 129213 64620 129213 64611 129214 64620 129214 64610 129214 64610 129215 64620 129215 64621 129215 64610 129216 64621 129216 64609 129216 64609 129217 64621 129217 64587 129217 64609 129218 64587 129218 64608 129218 64608 129219 64587 129219 64622 129219 64608 129220 64622 129220 64606 129220 64606 129221 64622 129221 64623 129221 64606 129222 64623 129222 64624 129222 64624 129223 64623 129223 64578 129223 64624 129224 64578 129224 64625 129224 60299 129225 59402 129225 60304 129225 60304 129226 59402 129226 59474 129226 60304 129227 59474 129227 60305 129227 64662 129228 59435 129228 64626 129228 64626 129229 59435 129229 59436 129229 64626 129230 59436 129230 60322 129230 59442 129231 60316 129231 64627 129231 64627 129232 60316 129232 60324 129232 64627 129233 60324 129233 59443 129233 59443 129234 60324 129234 59505 129234 60311 129235 59511 129235 59509 129235 59509 129236 59511 129236 59446 129236 59406 129237 59513 129237 64628 129237 64628 129238 59513 129238 64629 129238 64630 129239 59506 129239 60342 129239 60342 129240 59506 129240 60340 129240 64631 129241 59538 129241 60379 129241 64631 129242 60379 129242 64632 129242 64632 129243 60379 129243 64633 129243 64632 129244 64633 129244 64634 129244 64634 129245 64633 129245 59529 129245 64634 129246 59529 129246 59411 129246 62277 129247 62276 129247 60155 129247 60155 129248 62276 129248 60475 129248 62150 129249 60148 129249 62146 129249 62146 129250 60148 129250 64635 129250 62146 129251 64635 129251 60439 129251 64636 129252 64637 129252 60145 129252 60145 129253 64637 129253 60147 129253 64638 129254 60141 129254 62154 129254 62154 129255 60141 129255 64639 129255 64640 129256 64641 129256 62161 129256 62161 129257 64641 129257 62156 129257 62158 129258 60138 129258 64642 129258 64642 129259 60138 129259 62142 129259 62166 129260 62162 129260 60136 129260 60136 129261 62162 129261 60133 129261 64643 129262 60131 129262 64644 129262 64644 129263 60131 129263 62138 129263 64645 129264 62167 129264 60129 129264 60129 129265 62167 129265 64646 129265 60128 129266 64647 129266 62283 129266 62283 129267 64647 129267 62284 129267 62288 129268 64648 129268 60109 129268 60109 129269 64648 129269 60114 129269 64649 129270 60102 129270 64650 129270 64650 129271 60102 129271 64652 129271 64650 129272 64652 129272 64651 129272 64651 129273 64652 129273 60101 129273 62176 129274 64653 129274 62177 129274 62177 129275 64653 129275 60005 129275 60006 129276 64654 129276 64655 129276 64655 129277 64654 129277 62134 129277 64656 129278 64657 129278 60096 129278 60096 129279 64657 129279 60098 129279 60092 129280 64658 129280 64659 129280 64659 129281 64658 129281 62132 129281 62293 129282 62180 129282 62342 129282 62342 129283 62180 129283 60453 129283 60437 129284 62292 129284 64660 129284 64660 129285 62292 129285 64661 129285 64660 129286 64661 129286 60087 129286 60307 129287 59539 129287 59516 129287 59516 129288 59539 129288 59541 129288 64662 129289 60321 129289 59435 129289 59435 129290 60321 129290 59434 129290 59437 129291 60320 129291 59438 129291 59438 129292 60320 129292 64663 129292 59495 129293 59494 129293 60318 129293 60318 129294 59494 129294 59430 129294 59431 129295 60338 129295 59432 129295 59432 129296 60338 129296 60337 129296 60334 129297 59426 129297 59496 129297 59496 129298 59426 129298 64664 129298 59531 129299 60333 129299 59480 129299 59480 129300 60333 129300 59481 129300 59532 129301 59423 129301 60327 129301 60327 129302 59423 129302 59498 129302 64665 129303 59533 129303 64666 129303 64666 129304 59533 129304 59479 129304 60330 129305 59419 129305 64667 129305 64667 129306 59419 129306 59499 129306 59535 129307 64668 129307 59422 129307 59422 129308 64668 129308 64669 129308 60328 129309 64670 129309 59501 129309 59501 129310 64670 129310 59502 129310 59415 129311 64671 129311 64672 129311 64672 129312 64671 129312 60326 129312 64673 129313 62206 129313 60213 129313 60213 129314 62206 129314 60656 129314 64674 129315 62208 129315 62295 129315 62295 129316 62208 129316 60244 129316 62295 129317 60244 129317 62207 129317 62302 129318 62209 129318 62213 129318 62213 129319 62209 129319 60243 129319 62214 129320 64676 129320 64675 129320 64675 129321 64676 129321 62299 129321 62221 129322 62217 129322 62222 129322 62222 129323 62217 129323 60235 129323 60231 129324 60232 129324 62223 129324 62223 129325 60232 129325 64677 129325 64678 129326 62225 129326 64679 129326 64679 129327 62225 129327 60229 129327 60218 129328 60220 129328 62229 129328 62229 129329 60220 129329 62305 129329 62311 129330 62312 129330 60225 129330 60225 129331 62312 129331 60222 129331 64680 129332 64681 129332 64682 129332 64682 129333 64681 129333 64683 129333 62315 129334 62316 129334 62235 129334 62235 129335 62316 129335 64684 129335 64685 129336 64686 129336 60179 129336 60179 129337 64686 129337 62237 129337 60179 129338 62237 129338 60178 129338 62318 129339 64687 129339 60175 129339 60175 129340 64687 129340 64688 129340 62243 129341 60172 129341 62244 129341 62244 129342 60172 129342 62241 129342 64689 129343 62320 129343 64690 129343 64690 129344 62320 129344 60168 129344 62250 129345 64691 129345 62322 129345 62322 129346 64691 129346 64692 129346 62322 129347 64692 129347 64693 129347 62324 129348 62252 129348 64694 129348 64694 129349 62252 129349 60204 129349 62254 129350 62323 129350 64695 129350 64695 129351 62323 129351 64696 129351 64695 129352 64696 129352 62362 129352 64697 129353 59461 129353 60288 129353 60288 129354 59461 129354 59459 129354 60287 129355 59518 129355 60294 129355 60294 129356 59518 129356 59462 129356 64698 129357 59464 129357 59523 129357 59523 129358 59464 129358 59521 129358 60291 129359 64699 129359 60368 129359 60368 129360 64699 129360 59524 129360 60367 129361 59528 129361 60296 129361 60296 129362 59528 129362 59471 129362 59455 129363 64700 129363 59553 129363 59553 129364 64700 129364 64701 129364 59553 129365 64701 129365 59554 129365 59554 129366 64701 129366 59546 129366 59449 129367 64702 129367 59444 129367 59444 129368 64702 129368 59514 129368 59444 129369 59514 129369 59445 129369 68601 129370 64703 129370 68600 129370 68600 129371 64703 129371 72205 129371 68600 129372 72205 129372 64704 129372 72205 129373 72206 129373 64704 129373 64704 129374 72206 129374 72207 129374 64704 129375 72207 129375 64705 129375 64705 129376 72207 129376 72208 129376 64705 129377 72208 129377 68604 129377 68604 129378 72208 129378 72209 129378 68604 129379 72209 129379 68603 129379 68603 129380 72209 129380 64706 129380 68603 129381 64706 129381 64707 129381 64707 129382 64706 129382 72164 129382 64707 129383 72164 129383 64709 129383 72164 129384 64708 129384 64709 129384 64709 129385 64708 129385 64710 129385 64709 129386 64710 129386 64711 129386 64711 129387 64710 129387 72225 129387 64711 129388 72225 129388 68611 129388 68611 129389 72225 129389 72177 129389 68611 129390 72177 129390 64713 129390 64713 129391 72177 129391 64712 129391 64713 129392 64712 129392 68609 129392 68609 129393 64712 129393 72126 129393 68609 129394 72126 129394 64714 129394 72126 129395 64715 129395 64714 129395 64714 129396 64715 129396 72215 129396 64714 129397 72215 129397 64716 129397 64716 129398 72215 129398 72214 129398 64716 129399 72214 129399 64717 129399 64717 129400 72214 129400 72213 129400 64717 129401 72213 129401 68626 129401 68626 129402 72213 129402 64718 129402 68626 129403 64718 129403 68625 129403 68625 129404 64718 129404 72194 129404 68625 129405 72194 129405 64719 129405 64719 129406 72194 129406 72195 129406 64719 129407 72195 129407 68618 129407 72195 129408 72198 129408 68618 129408 68618 129409 72198 129409 64720 129409 68618 129410 64720 129410 68617 129410 68617 129411 64720 129411 72217 129411 68617 129412 72217 129412 64721 129412 64721 129413 72217 129413 64722 129413 64721 129414 64722 129414 68623 129414 68623 129415 64722 129415 64723 129415 68623 129416 64723 129416 64725 129416 64725 129417 64723 129417 64724 129417 64725 129418 64724 129418 68620 129418 68620 129419 64724 129419 72139 129419 68620 129420 72139 129420 68602 129420 68602 129421 72139 129421 72141 129421 68602 129422 72141 129422 68601 129422 68601 129423 72141 129423 64726 129423 68601 129424 64726 129424 64703 129424 71121 129425 64729 129425 64730 129425 64727 129426 64729 129426 71121 129426 71118 129427 64727 129427 71121 129427 71121 129428 64734 129428 64735 129428 64731 129429 64734 129429 71121 129429 64730 129430 64731 129430 71121 129430 71118 129431 71106 129431 64727 129431 64727 129432 71106 129432 71107 129432 64727 129433 71107 129433 64729 129433 64729 129434 71107 129434 64728 129434 64729 129435 64728 129435 64730 129435 64730 129436 64728 129436 64732 129436 64730 129437 64732 129437 64731 129437 64731 129438 64732 129438 64733 129438 64731 129439 64733 129439 64734 129439 64734 129440 64733 129440 71109 129440 64734 129441 71109 129441 64735 129441 64735 129442 71109 129442 71113 129442 64736 129443 71092 129443 64737 129443 64737 129444 71092 129444 64739 129444 64737 129445 64739 129445 64738 129445 64738 129446 64739 129446 64740 129446 64738 129447 64740 129447 64745 129447 64745 129448 64740 129448 71095 129448 64745 129449 71095 129449 64741 129449 64741 129450 71095 129450 64742 129450 64741 129451 64742 129451 64743 129451 64743 129452 64742 129452 64744 129452 64743 129453 64744 129453 71080 129453 71080 129454 64744 129454 71097 129454 71078 129455 64738 129455 64745 129455 64737 129456 64738 129456 71078 129456 64736 129457 64737 129457 71078 129457 71078 129458 64743 129458 71080 129458 64741 129459 64743 129459 71078 129459 64745 129460 64741 129460 71078 129460 64755 129461 71073 129461 64746 129461 64746 129462 71073 129462 71075 129462 64746 129463 71075 129463 64747 129463 64747 129464 71075 129464 64748 129464 64747 129465 64748 129465 64749 129465 64749 129466 64748 129466 64750 129466 64749 129467 64750 129467 64756 129467 64756 129468 64750 129468 71063 129468 64756 129469 71063 129469 64751 129469 64751 129470 71063 129470 64752 129470 64751 129471 64752 129471 64753 129471 64753 129472 64752 129472 71066 129472 64754 129473 64747 129473 64749 129473 64746 129474 64747 129474 64754 129474 64755 129475 64746 129475 64754 129475 64754 129476 64751 129476 64753 129476 64756 129477 64751 129477 64754 129477 64749 129478 64756 129478 64754 129478 71038 129479 71054 129479 64765 129479 64765 129480 71054 129480 64757 129480 64765 129481 64757 129481 64764 129481 64764 129482 64757 129482 71047 129482 64764 129483 71047 129483 64758 129483 64758 129484 71047 129484 71048 129484 64758 129485 71048 129485 64759 129485 64759 129486 71048 129486 64760 129486 64759 129487 64760 129487 64766 129487 64766 129488 64760 129488 71050 129488 64766 129489 71050 129489 64761 129489 64761 129490 71050 129490 64762 129490 64763 129491 64764 129491 64758 129491 64765 129492 64764 129492 64763 129492 71038 129493 64765 129493 64763 129493 64763 129494 64766 129494 64761 129494 64759 129495 64766 129495 64763 129495 64758 129496 64759 129496 64763 129496 64767 129497 71021 129497 64772 129497 64772 129498 71021 129498 64768 129498 64772 129499 64768 129499 64771 129499 64771 129500 64768 129500 71025 129500 64771 129501 71025 129501 64769 129501 64769 129502 71025 129502 71027 129502 64769 129503 71027 129503 64775 129503 64775 129504 71027 129504 64770 129504 64775 129505 64770 129505 64774 129505 64774 129506 64770 129506 71030 129506 64774 129507 71030 129507 71013 129507 71013 129508 71030 129508 71032 129508 64773 129509 64771 129509 64769 129509 64772 129510 64771 129510 64773 129510 64767 129511 64772 129511 64773 129511 64773 129512 64774 129512 71013 129512 64775 129513 64774 129513 64773 129513 64769 129514 64775 129514 64773 129514 70999 129515 71001 129515 64777 129515 64777 129516 71001 129516 64776 129516 64777 129517 64776 129517 64783 129517 64783 129518 64776 129518 71009 129518 64783 129519 71009 129519 64778 129519 64778 129520 71009 129520 71011 129520 64778 129521 71011 129521 64779 129521 64779 129522 71011 129522 64780 129522 64779 129523 64780 129523 64781 129523 64781 129524 64780 129524 71003 129524 64781 129525 71003 129525 64784 129525 64784 129526 71003 129526 70994 129526 64782 129527 64783 129527 64778 129527 64777 129528 64783 129528 64782 129528 70999 129529 64777 129529 64782 129529 64782 129530 64781 129530 64784 129530 64779 129531 64781 129531 64782 129531 64778 129532 64779 129532 64782 129532 64785 129533 70985 129533 64786 129533 64786 129534 70985 129534 70986 129534 64786 129535 70986 129535 64787 129535 64787 129536 70986 129536 70988 129536 64787 129537 70988 129537 64788 129537 64788 129538 70988 129538 64789 129538 64788 129539 64789 129539 64792 129539 64792 129540 64789 129540 70976 129540 64792 129541 70976 129541 64791 129541 64791 129542 70976 129542 70977 129542 64791 129543 70977 129543 70969 129543 70969 129544 70977 129544 70970 129544 64790 129545 64787 129545 64788 129545 64786 129546 64787 129546 64790 129546 64785 129547 64786 129547 64790 129547 64790 129548 64791 129548 70969 129548 64792 129549 64791 129549 64790 129549 64788 129550 64792 129550 64790 129550 70959 129551 64793 129551 64802 129551 64802 129552 64793 129552 64794 129552 64802 129553 64794 129553 64795 129553 64795 129554 64794 129554 64796 129554 64795 129555 64796 129555 64801 129555 64801 129556 64796 129556 64797 129556 64801 129557 64797 129557 64798 129557 64798 129558 64797 129558 70960 129558 64798 129559 70960 129559 64799 129559 64799 129560 70960 129560 64800 129560 64799 129561 64800 129561 70949 129561 70949 129562 64800 129562 70951 129562 70948 129563 64795 129563 64801 129563 64802 129564 64795 129564 70948 129564 70959 129565 64802 129565 70948 129565 70948 129566 64799 129566 70949 129566 64798 129567 64799 129567 70948 129567 64801 129568 64798 129568 70948 129568 70930 129569 70931 129569 64808 129569 64808 129570 70931 129570 70936 129570 64808 129571 70936 129571 64803 129571 64803 129572 70936 129572 64804 129572 64803 129573 64804 129573 64805 129573 64805 129574 64804 129574 70939 129574 64805 129575 70939 129575 64806 129575 64806 129576 70939 129576 64807 129576 64806 129577 64807 129577 64809 129577 64809 129578 64807 129578 70941 129578 64809 129579 70941 129579 64810 129579 64810 129580 70941 129580 70942 129580 70923 129581 64803 129581 64805 129581 64808 129582 64803 129582 70923 129582 70930 129583 64808 129583 70923 129583 70923 129584 64809 129584 64810 129584 64806 129585 64809 129585 70923 129585 64805 129586 64806 129586 70923 129586 70907 129587 70914 129587 64817 129587 64817 129588 70914 129588 64811 129588 64817 129589 64811 129589 64812 129589 64812 129590 64811 129590 64813 129590 64812 129591 64813 129591 64820 129591 64820 129592 64813 129592 64815 129592 64820 129593 64815 129593 64814 129593 64814 129594 64815 129594 70919 129594 64814 129595 70919 129595 64819 129595 64819 129596 70919 129596 70920 129596 64819 129597 70920 129597 64816 129597 64816 129598 70920 129598 70922 129598 64818 129599 64812 129599 64820 129599 64817 129600 64812 129600 64818 129600 70907 129601 64817 129601 64818 129601 64818 129602 64819 129602 64816 129602 64814 129603 64819 129603 64818 129603 64820 129604 64814 129604 64818 129604 64824 129605 64827 129605 64828 129605 64826 129606 68677 129606 64821 129606 64821 129607 68677 129607 64822 129607 64821 129608 64822 129608 64823 129608 64824 129609 64828 129609 64823 129609 64823 129610 64828 129610 64845 129610 64823 129611 64845 129611 64821 129611 64821 129612 64845 129612 64825 129612 64821 129613 64825 129613 64826 129613 64827 129614 68667 129614 64828 129614 64828 129615 68667 129615 68671 129615 64828 129616 68671 129616 64830 129616 65812 129617 64829 129617 68669 129617 68669 129618 64829 129618 64830 129618 68669 129619 64830 129619 68670 129619 68670 129620 64830 129620 68671 129620 64960 129621 64831 129621 64832 129621 64832 129622 64831 129622 69064 129622 69064 129623 69061 129623 64832 129623 64832 129624 69061 129624 64833 129624 64832 129625 64833 129625 64960 129625 64960 129626 64833 129626 64834 129626 69044 129627 69045 129627 64959 129627 64959 129628 69045 129628 64835 129628 64835 129629 64836 129629 64959 129629 64959 129630 64836 129630 69048 129630 64959 129631 69048 129631 64837 129631 64837 129632 64838 129632 64959 129632 64959 129633 64838 129633 64842 129633 64959 129634 64842 129634 64841 129634 64839 129635 64828 129635 64840 129635 64840 129636 64828 129636 64841 129636 64840 129637 64841 129637 69051 129637 69051 129638 64841 129638 64842 129638 64839 129639 64843 129639 64828 129639 64828 129640 64843 129640 64844 129640 64828 129641 64844 129641 64845 129641 64845 129642 64844 129642 64846 129642 64845 129643 64846 129643 64847 129643 69027 129644 69026 129644 64848 129644 64848 129645 69026 129645 69025 129645 64847 129646 69027 129646 64845 129646 64845 129647 69027 129647 64848 129647 64845 129648 64848 129648 70669 129648 70669 129649 64848 129649 69025 129649 70669 129650 69025 129650 69024 129650 64849 129651 64850 129651 64851 129651 64851 129652 64850 129652 69107 129652 64849 129653 69110 129653 64850 129653 64850 129654 69110 129654 69112 129654 64850 129655 69112 129655 64854 129655 69112 129656 64852 129656 64854 129656 64854 129657 64852 129657 64853 129657 64854 129658 64853 129658 70231 129658 70231 129659 64853 129659 69115 129659 69116 129660 64855 129660 64858 129660 64858 129661 64855 129661 64856 129661 69085 129662 69084 129662 64857 129662 64857 129663 69084 129663 69083 129663 64856 129664 69085 129664 64858 129664 64858 129665 69085 129665 64857 129665 64858 129666 64857 129666 64859 129666 64859 129667 64857 129667 69083 129667 64859 129668 69083 129668 69082 129668 64860 129669 69126 129669 69124 129669 69126 129670 64860 129670 64954 129670 69122 129671 69123 129671 64955 129671 69102 129672 69103 129672 64952 129672 64952 129673 69103 129673 69104 129673 64952 129674 69104 129674 64861 129674 64861 129675 69104 129675 64862 129675 64861 129676 64862 129676 64850 129676 64850 129677 64862 129677 69106 129677 64850 129678 69106 129678 69107 129678 64863 129679 64864 129679 64865 129679 64865 129680 64864 129680 64866 129680 64865 129681 64866 129681 69170 129681 69170 129682 64866 129682 70227 129682 69170 129683 70227 129683 64867 129683 64950 129684 69173 129684 69127 129684 69127 129685 69173 129685 69174 129685 69138 129686 69135 129686 64868 129686 64868 129687 69135 129687 64869 129687 69174 129688 69138 129688 69127 129688 69127 129689 69138 129689 64868 129689 69127 129690 64868 129690 69134 129690 69134 129691 64868 129691 64869 129691 69134 129692 64869 129692 64870 129692 64874 129693 69193 129693 69183 129693 69193 129694 64874 129694 64873 129694 64871 129695 69181 129695 69175 129695 69160 129696 64949 129696 64872 129696 64872 129697 64949 129697 64873 129697 64872 129698 64873 129698 69175 129698 69175 129699 64873 129699 64874 129699 69175 129700 64874 129700 64871 129700 64871 129701 64874 129701 69183 129701 69163 129702 64876 129702 64875 129702 64875 129703 64876 129703 64949 129703 64875 129704 64949 129704 64877 129704 64877 129705 64949 129705 69160 129705 69163 129706 64878 129706 64876 129706 64876 129707 64878 129707 69165 129707 64876 129708 69165 129708 70227 129708 70227 129709 69165 129709 69166 129709 70227 129710 69166 129710 64867 129710 64944 129711 64879 129711 69244 129711 64945 129712 64880 129712 64946 129712 64946 129713 64880 129713 64881 129713 69207 129714 69205 129714 64882 129714 64882 129715 69205 129715 69204 129715 64881 129716 69207 129716 64946 129716 64946 129717 69207 129717 64882 129717 64946 129718 64882 129718 64883 129718 64883 129719 64882 129719 69204 129719 64883 129720 69204 129720 69201 129720 69249 129721 69258 129721 64884 129721 64884 129722 69258 129722 64885 129722 64885 129723 69253 129723 64884 129723 64884 129724 69253 129724 64886 129724 64884 129725 64886 129725 69249 129725 69249 129726 64886 129726 64887 129726 64888 129727 69230 129727 70221 129727 70221 129728 69230 129728 69231 129728 69231 129729 64889 129729 70221 129729 70221 129730 64889 129730 69234 129730 70221 129731 69234 129731 64890 129731 64890 129732 69234 129732 64891 129732 64890 129733 64891 129733 69236 129733 69236 129734 69237 129734 64890 129734 64890 129735 69237 129735 69239 129735 64890 129736 69239 129736 64892 129736 64892 129737 69239 129737 64893 129737 64893 129738 69241 129738 64892 129738 64892 129739 69241 129739 69242 129739 64892 129740 69242 129740 64879 129740 64879 129741 69242 129741 64894 129741 64879 129742 64894 129742 69244 129742 64898 129743 64895 129743 69261 129743 69261 129744 64895 129744 69250 129744 69261 129745 69250 129745 64896 129745 64941 129746 64897 129746 69260 129746 69260 129747 64897 129747 69209 129747 69260 129748 69209 129748 64898 129748 64898 129749 69209 129749 69248 129749 64898 129750 69248 129750 64895 129750 64895 129751 69248 129751 64899 129751 64895 129752 64899 129752 69250 129752 64903 129753 69190 129753 64901 129753 64901 129754 69190 129754 64900 129754 64900 129755 69196 129755 64901 129755 64901 129756 69196 129756 64902 129756 64901 129757 64902 129757 64903 129757 64903 129758 64902 129758 69199 129758 69208 129759 69225 129759 70214 129759 70214 129760 69225 129760 64904 129760 64904 129761 69222 129761 70214 129761 70214 129762 69222 129762 69220 129762 70214 129763 69220 129763 70216 129763 70216 129764 69220 129764 69218 129764 70216 129765 69218 129765 64907 129765 64910 129766 64905 129766 70217 129766 70217 129767 64905 129767 69213 129767 70217 129768 69213 129768 64906 129768 64906 129769 69213 129769 69212 129769 64906 129770 69212 129770 70219 129770 64907 129771 64908 129771 70216 129771 70216 129772 64908 129772 64909 129772 70216 129773 64909 129773 70217 129773 70217 129774 64909 129774 69216 129774 70217 129775 69216 129775 64910 129775 69150 129776 69142 129776 64911 129776 69150 129777 64911 129777 69148 129777 64912 129778 70672 129778 64913 129778 70672 129779 64912 129779 64931 129779 69132 129780 69133 129780 64914 129780 64913 129781 69132 129781 64912 129781 64912 129782 69132 129782 64914 129782 64912 129783 64914 129783 64931 129783 64931 129784 64914 129784 64915 129784 64931 129785 64915 129785 70208 129785 70208 129786 64915 129786 64916 129786 70208 129787 64916 129787 64917 129787 64917 129788 69156 129788 70208 129788 70208 129789 69156 129789 69155 129789 70208 129790 69155 129790 64920 129790 64921 129791 64918 129791 69151 129791 69151 129792 64918 129792 70208 129792 69151 129793 70208 129793 64919 129793 64919 129794 70208 129794 64920 129794 64921 129795 64922 129795 64918 129795 64918 129796 64922 129796 69144 129796 64918 129797 69144 129797 64911 129797 64911 129798 69144 129798 69145 129798 64911 129799 69145 129799 69148 129799 64936 129800 64924 129800 64937 129800 64925 129801 69177 129801 64927 129801 64927 129802 69177 129802 64923 129802 64924 129803 64925 129803 64937 129803 64937 129804 64925 129804 64927 129804 64937 129805 64927 129805 64926 129805 64926 129806 64927 129806 64923 129806 64926 129807 64923 129807 69176 129807 65236 129808 68645 129808 64928 129808 64928 129809 68645 129809 64929 129809 64928 129810 64929 129810 70208 129810 64929 129811 68639 129811 70208 129811 70208 129812 68639 129812 64930 129812 70208 129813 64930 129813 64932 129813 64931 129814 64934 129814 68629 129814 68629 129815 64934 129815 68632 129815 68629 129816 68632 129816 68630 129816 64932 129817 68642 129817 70208 129817 70208 129818 68642 129818 64933 129818 70208 129819 64933 129819 64931 129819 64931 129820 64933 129820 68635 129820 64931 129821 68635 129821 64934 129821 64934 129822 68635 129822 64935 129822 64934 129823 64935 129823 68632 129823 69142 129824 64936 129824 64911 129824 64911 129825 64936 129825 64937 129825 64911 129826 64937 129826 64938 129826 64938 129827 64937 129827 64939 129827 64938 129828 64939 129828 70212 129828 70212 129829 64939 129829 69187 129829 70212 129830 69187 129830 64940 129830 64940 129831 69187 129831 69189 129831 64940 129832 69189 129832 70214 129832 70214 129833 69189 129833 69190 129833 70214 129834 69190 129834 69208 129834 69208 129835 69190 129835 64903 129835 69212 129836 64941 129836 70219 129836 70219 129837 64941 129837 69260 129837 70219 129838 69260 129838 64942 129838 64942 129839 69260 129839 64943 129839 64942 129840 64943 129840 70221 129840 70221 129841 64943 129841 69258 129841 70221 129842 69258 129842 64888 129842 64888 129843 69258 129843 69249 129843 69244 129844 64945 129844 64944 129844 64944 129845 64945 129845 64946 129845 64944 129846 64946 129846 64947 129846 64947 129847 64946 129847 69191 129847 64947 129848 69191 129848 64949 129848 64949 129849 69191 129849 64948 129849 64949 129850 64948 129850 64873 129850 64863 129851 64950 129851 64864 129851 64864 129852 64950 129852 69127 129852 64864 129853 69127 129853 64951 129853 64951 129854 69127 129854 69129 129854 64951 129855 69129 129855 64952 129855 64952 129856 69129 129856 64953 129856 64952 129857 64953 129857 69102 129857 69102 129858 64953 129858 64954 129858 69102 129859 64954 129859 64955 129859 64955 129860 64954 129860 64860 129860 64955 129861 64860 129861 69122 129861 69122 129862 64860 129862 69124 129862 69115 129863 69116 129863 70231 129863 70231 129864 69116 129864 64858 129864 70231 129865 64858 129865 70232 129865 70232 129866 64858 129866 64956 129866 70232 129867 64956 129867 64957 129867 64957 129868 64956 129868 64958 129868 64957 129869 64958 129869 70234 129869 70234 129870 64958 129870 69073 129870 70234 129871 69073 129871 64959 129871 64959 129872 69073 129872 64831 129872 64959 129873 64831 129873 69044 129873 69044 129874 64831 129874 64960 129874 70619 129875 70620 129875 64961 129875 64961 129876 70620 129876 64962 129876 64961 129877 64962 129877 64963 129877 64963 129878 64962 129878 65525 129878 64963 129879 65525 129879 64964 129879 64964 129880 65525 129880 64966 129880 64964 129881 64966 129881 64965 129881 64965 129882 64966 129882 64967 129882 64965 129883 64967 129883 64968 129883 64968 129884 64967 129884 65526 129884 64968 129885 65526 129885 64969 129885 64969 129886 65526 129886 64970 129886 64969 129887 64970 129887 70437 129887 70437 129888 64970 129888 64972 129888 70437 129889 64972 129889 64971 129889 64971 129890 64972 129890 65527 129890 64971 129891 65527 129891 64973 129891 64973 129892 65527 129892 65528 129892 64973 129893 65528 129893 70441 129893 70441 129894 65528 129894 64974 129894 70441 129895 64974 129895 70442 129895 70442 129896 64974 129896 64975 129896 70442 129897 64975 129897 70443 129897 70443 129898 64975 129898 65531 129898 70443 129899 65531 129899 70444 129899 70444 129900 65531 129900 65532 129900 70444 129901 65532 129901 64976 129901 64976 129902 65532 129902 64977 129902 64976 129903 64977 129903 70446 129903 70446 129904 64977 129904 64978 129904 70446 129905 64978 129905 64979 129905 64979 129906 64978 129906 65534 129906 64979 129907 65534 129907 70448 129907 70448 129908 65534 129908 70604 129908 70601 129909 70602 129909 65523 129909 65523 129910 70602 129910 65680 129910 65523 129911 65680 129911 65522 129911 65522 129912 65680 129912 64980 129912 65522 129913 64980 129913 65520 129913 65520 129914 64980 129914 64981 129914 65520 129915 64981 129915 65518 129915 65518 129916 64981 129916 64983 129916 65518 129917 64983 129917 64982 129917 64982 129918 64983 129918 64984 129918 64982 129919 64984 129919 65516 129919 65516 129920 64984 129920 64985 129920 65516 129921 64985 129921 65514 129921 65514 129922 64985 129922 65683 129922 65514 129923 65683 129923 65513 129923 65513 129924 65683 129924 64986 129924 65513 129925 64986 129925 64987 129925 64987 129926 64986 129926 64988 129926 64987 129927 64988 129927 64989 129927 64989 129928 64988 129928 65686 129928 64989 129929 65686 129929 64990 129929 64990 129930 65686 129930 64991 129930 64990 129931 64991 129931 65511 129931 65511 129932 64991 129932 65689 129932 65511 129933 65689 129933 65510 129933 65510 129934 65689 129934 65690 129934 65510 129935 65690 129935 65508 129935 65508 129936 65690 129936 65692 129936 65508 129937 65692 129937 65507 129937 65507 129938 65692 129938 64992 129938 65507 129939 64992 129939 64993 129939 64993 129940 64992 129940 64994 129940 64993 129941 64994 129941 69807 129941 69807 129942 64994 129942 70586 129942 64995 129943 68779 129943 65743 129943 65743 129944 68779 129944 65746 129944 65743 129945 65746 129945 64996 129945 64996 129946 65746 129946 65747 129946 64996 129947 65747 129947 64998 129947 64998 129948 65747 129948 64997 129948 64998 129949 64997 129949 65741 129949 65741 129950 64997 129950 64999 129950 65741 129951 64999 129951 65000 129951 65000 129952 64999 129952 65001 129952 65000 129953 65001 129953 65740 129953 65740 129954 65001 129954 65002 129954 65740 129955 65002 129955 65003 129955 65003 129956 65002 129956 65005 129956 65003 129957 65005 129957 65004 129957 65004 129958 65005 129958 65006 129958 65004 129959 65006 129959 65738 129959 65738 129960 65006 129960 65007 129960 65738 129961 65007 129961 65736 129961 65736 129962 65007 129962 65008 129962 65736 129963 65008 129963 65009 129963 65009 129964 65008 129964 65756 129964 65009 129965 65756 129965 65010 129965 65010 129966 65756 129966 65011 129966 65010 129967 65011 129967 65734 129967 65734 129968 65011 129968 65757 129968 65734 129969 65757 129969 65733 129969 65733 129970 65757 129970 65012 129970 65733 129971 65012 129971 65013 129971 65013 129972 65012 129972 65758 129972 65013 129973 65758 129973 65731 129973 65731 129974 65758 129974 65014 129974 65015 129975 65019 129975 70274 129975 65015 129976 70274 129976 70568 129976 70568 129977 70274 129977 70276 129977 70568 129978 70276 129978 65016 129978 70203 129979 65018 129979 65017 129979 65017 129980 65018 129980 70204 129980 65017 129981 70204 129981 65015 129981 65015 129982 70204 129982 70273 129982 65015 129983 70273 129983 65019 129983 70203 129984 65017 129984 70200 129984 70200 129985 65017 129985 65020 129985 70200 129986 65020 129986 70199 129986 65021 129987 65023 129987 65022 129987 65022 129988 65023 129988 70196 129988 65022 129989 70196 129989 65020 129989 65020 129990 70196 129990 70197 129990 65020 129991 70197 129991 70199 129991 65021 129992 65022 129992 70194 129992 70194 129993 65022 129993 65727 129993 70194 129994 65727 129994 70191 129994 65029 129995 70189 129995 65024 129995 65029 129996 65024 129996 65727 129996 65727 129997 65024 129997 65025 129997 65727 129998 65025 129998 70191 129998 65026 129999 70188 129999 65726 129999 65726 130000 70188 130000 65027 130000 65726 130001 65027 130001 65029 130001 65029 130002 65027 130002 65028 130002 65029 130003 65028 130003 70189 130003 65026 130004 65726 130004 65030 130004 65030 130005 65726 130005 65725 130005 65030 130006 65725 130006 65033 130006 65031 130007 70184 130007 70186 130007 65031 130008 70186 130008 65725 130008 65725 130009 70186 130009 65032 130009 65725 130010 65032 130010 65033 130010 65724 130011 70181 130011 65034 130011 65724 130012 65034 130012 65031 130012 65031 130013 65034 130013 70183 130013 65031 130014 70183 130014 70184 130014 70176 130015 70178 130015 65035 130015 65035 130016 70178 130016 70179 130016 65035 130017 70179 130017 65724 130017 65724 130018 70179 130018 70180 130018 65724 130019 70180 130019 70181 130019 70176 130020 65035 130020 70175 130020 70175 130021 65035 130021 65036 130021 70175 130022 65036 130022 70173 130022 70169 130023 70170 130023 65038 130023 65038 130024 70170 130024 70171 130024 65038 130025 70171 130025 65036 130025 65036 130026 70171 130026 65037 130026 65036 130027 65037 130027 70173 130027 70169 130028 65038 130028 70168 130028 70168 130029 65038 130029 65040 130029 70168 130030 65040 130030 70167 130030 70162 130031 70164 130031 65720 130031 65720 130032 70164 130032 65039 130032 65720 130033 65039 130033 65040 130033 65040 130034 65039 130034 70166 130034 65040 130035 70166 130035 70167 130035 70162 130036 65720 130036 70161 130036 70161 130037 65720 130037 65042 130037 70161 130038 65042 130038 70160 130038 65043 130039 65041 130039 70157 130039 65043 130040 70157 130040 65042 130040 65042 130041 70157 130041 70158 130041 65042 130042 70158 130042 70160 130042 65718 130043 65238 130043 70155 130043 65718 130044 70155 130044 65043 130044 65043 130045 70155 130045 70156 130045 65043 130046 70156 130046 65041 130046 70482 130047 70504 130047 70483 130047 70483 130048 70504 130048 65696 130048 70483 130049 65696 130049 70485 130049 70485 130050 65696 130050 65698 130050 70485 130051 65698 130051 65044 130051 65044 130052 65698 130052 65700 130052 65044 130053 65700 130053 65045 130053 65045 130054 65700 130054 65046 130054 65045 130055 65046 130055 70487 130055 70487 130056 65046 130056 65702 130056 70487 130057 65702 130057 65047 130057 65047 130058 65702 130058 65704 130058 65047 130059 65704 130059 65048 130059 65048 130060 65704 130060 65049 130060 65048 130061 65049 130061 70458 130061 70458 130062 65049 130062 65707 130062 70458 130063 65707 130063 70459 130063 70459 130064 65707 130064 65050 130064 70459 130065 65050 130065 65051 130065 65051 130066 65050 130066 65052 130066 65051 130067 65052 130067 70460 130067 70460 130068 65052 130068 65709 130068 70460 130069 65709 130069 70461 130069 70461 130070 65709 130070 65053 130070 70461 130071 65053 130071 70463 130071 70463 130072 65053 130072 65711 130072 70463 130073 65711 130073 65054 130073 65054 130074 65711 130074 65056 130074 65054 130075 65056 130075 65055 130075 65055 130076 65056 130076 65712 130076 65055 130077 65712 130077 65058 130077 65058 130078 65712 130078 65057 130078 65058 130079 65057 130079 70464 130079 70464 130080 65057 130080 65059 130080 70464 130081 65059 130081 70465 130081 70465 130082 65059 130082 68810 130082 70433 130083 68739 130083 65793 130083 70433 130084 65793 130084 65060 130084 65060 130085 65793 130085 65061 130085 65060 130086 65061 130086 65062 130086 65062 130087 65061 130087 65790 130087 65062 130088 65790 130088 70430 130088 70430 130089 65790 130089 65788 130089 70430 130090 65788 130090 65063 130090 65063 130091 65788 130091 65787 130091 65063 130092 65787 130092 70428 130092 70428 130093 65787 130093 65786 130093 70428 130094 65786 130094 65064 130094 65064 130095 65786 130095 65065 130095 65064 130096 65065 130096 65066 130096 65066 130097 65065 130097 65067 130097 65066 130098 65067 130098 65068 130098 65068 130099 65067 130099 65782 130099 65068 130100 65782 130100 65069 130100 65069 130101 65782 130101 65781 130101 65069 130102 65781 130102 70423 130102 70423 130103 65781 130103 65780 130103 70423 130104 65780 130104 70422 130104 70422 130105 65780 130105 65070 130105 70422 130106 65070 130106 70455 130106 70455 130107 65070 130107 65071 130107 70455 130108 65071 130108 70453 130108 70453 130109 65071 130109 65777 130109 70453 130110 65777 130110 70452 130110 70452 130111 65777 130111 65072 130111 70452 130112 65072 130112 70450 130112 70450 130113 65072 130113 65073 130113 70450 130114 65073 130114 70449 130114 70449 130115 65073 130115 65074 130115 70449 130116 65074 130116 70402 130116 65075 130117 65076 130117 65078 130117 65075 130118 65078 130118 65077 130118 65077 130119 65078 130119 65678 130119 65077 130120 65678 130120 65079 130120 65079 130121 65678 130121 65080 130121 65079 130122 65080 130122 65082 130122 65082 130123 65080 130123 65081 130123 65082 130124 65081 130124 70396 130124 70396 130125 65081 130125 65676 130125 70396 130126 65676 130126 70394 130126 70394 130127 65676 130127 65083 130127 70394 130128 65083 130128 70393 130128 70393 130129 65083 130129 65084 130129 70393 130130 65084 130130 65085 130130 65085 130131 65084 130131 65086 130131 65085 130132 65086 130132 65087 130132 65087 130133 65086 130133 65672 130133 65087 130134 65672 130134 70392 130134 70392 130135 65672 130135 65671 130135 70392 130136 65671 130136 65088 130136 65088 130137 65671 130137 65089 130137 65088 130138 65089 130138 70389 130138 70389 130139 65089 130139 65667 130139 70389 130140 65667 130140 70388 130140 70388 130141 65667 130141 65091 130141 70388 130142 65091 130142 65090 130142 65090 130143 65091 130143 65093 130143 65090 130144 65093 130144 65092 130144 65092 130145 65093 130145 65663 130145 65092 130146 65663 130146 65094 130146 65094 130147 65663 130147 65662 130147 65094 130148 65662 130148 70384 130148 65095 130149 65096 130149 65097 130149 65097 130150 65096 130150 65098 130150 65097 130151 65098 130151 70307 130151 70307 130152 65098 130152 65099 130152 70307 130153 65099 130153 65100 130153 65100 130154 65099 130154 65760 130154 65100 130155 65760 130155 65101 130155 65101 130156 65760 130156 65761 130156 65101 130157 65761 130157 70308 130157 70308 130158 65761 130158 65103 130158 70308 130159 65103 130159 65102 130159 65102 130160 65103 130160 65764 130160 65102 130161 65764 130161 70279 130161 70279 130162 65764 130162 65767 130162 70279 130163 65767 130163 70280 130163 70280 130164 65767 130164 65104 130164 70280 130165 65104 130165 70281 130165 70281 130166 65104 130166 65769 130166 70281 130167 65769 130167 65105 130167 65105 130168 65769 130168 65106 130168 65105 130169 65106 130169 70283 130169 70283 130170 65106 130170 65771 130170 70283 130171 65771 130171 70285 130171 70285 130172 65771 130172 65774 130172 70285 130173 65774 130173 65107 130173 65107 130174 65774 130174 65108 130174 65107 130175 65108 130175 70288 130175 70288 130176 65108 130176 65775 130176 70288 130177 65775 130177 65109 130177 65109 130178 65775 130178 65776 130178 65109 130179 65776 130179 70290 130179 70290 130180 65776 130180 65110 130180 65016 130181 65194 130181 65111 130181 65111 130182 65194 130182 65195 130182 65111 130183 65195 130183 65112 130183 65112 130184 65195 130184 65196 130184 65112 130185 65196 130185 65113 130185 65113 130186 65196 130186 65114 130186 65114 130187 65196 130187 65115 130187 65114 130188 65115 130188 65116 130188 65116 130189 65115 130189 65199 130189 65116 130190 65199 130190 65117 130190 65117 130191 65199 130191 65118 130191 65118 130192 65199 130192 65200 130192 65118 130193 65200 130193 65119 130193 65119 130194 65200 130194 65201 130194 65119 130195 65201 130195 65120 130195 65120 130196 65201 130196 65203 130196 65120 130197 65203 130197 70565 130197 70565 130198 65203 130198 70564 130198 70564 130199 65203 130199 65205 130199 70564 130200 65205 130200 70562 130200 70562 130201 65205 130201 65206 130201 70562 130202 65206 130202 65121 130202 65121 130203 65206 130203 70563 130203 70563 130204 65206 130204 65208 130204 70563 130205 65208 130205 65122 130205 65122 130206 65208 130206 65124 130206 65122 130207 65124 130207 65123 130207 65123 130208 65124 130208 70560 130208 70560 130209 65124 130209 65209 130209 70560 130210 65209 130210 65125 130210 65125 130211 65209 130211 65211 130211 65125 130212 65211 130212 65126 130212 65126 130213 65211 130213 65127 130213 65127 130214 65211 130214 65128 130214 65127 130215 65128 130215 65129 130215 65129 130216 65128 130216 65213 130216 65129 130217 65213 130217 70558 130217 70558 130218 65213 130218 70559 130218 70559 130219 65213 130219 65131 130219 70559 130220 65131 130220 65130 130220 65130 130221 65131 130221 65133 130221 65130 130222 65133 130222 65132 130222 65132 130223 65133 130223 65134 130223 65134 130224 65133 130224 65216 130224 65134 130225 65216 130225 65135 130225 65135 130226 65216 130226 65218 130226 65135 130227 65218 130227 70556 130227 70556 130228 65218 130228 65220 130228 70556 130229 65220 130229 65136 130229 65136 130230 65220 130230 65137 130230 65136 130231 65137 130231 70554 130231 70554 130232 65137 130232 70555 130232 70555 130233 65137 130233 65139 130233 70555 130234 65139 130234 65138 130234 65138 130235 65139 130235 65140 130235 65138 130236 65140 130236 65141 130236 65141 130237 65140 130237 70551 130237 70551 130238 65140 130238 65142 130238 70551 130239 65142 130239 65143 130239 65143 130240 65142 130240 65144 130240 65143 130241 65144 130241 65145 130241 65145 130242 65144 130242 65221 130242 65145 130243 65221 130243 70550 130243 70550 130244 65221 130244 65146 130244 65146 130245 65221 130245 65223 130245 65146 130246 65223 130246 70549 130246 70549 130247 65223 130247 65147 130247 70549 130248 65147 130248 65148 130248 65148 130249 65147 130249 65149 130249 65149 130250 65147 130250 65224 130250 65149 130251 65224 130251 65150 130251 65150 130252 65224 130252 65226 130252 65150 130253 65226 130253 65151 130253 65151 130254 65226 130254 65152 130254 65152 130255 65226 130255 65153 130255 65152 130256 65153 130256 65155 130256 65155 130257 65153 130257 65154 130257 65155 130258 65154 130258 65156 130258 65156 130259 65154 130259 70545 130259 70545 130260 65154 130260 65157 130260 70545 130261 65157 130261 70544 130261 70544 130262 65157 130262 65228 130262 70544 130263 65228 130263 65230 130263 65158 130264 64829 130264 65159 130264 65159 130265 64829 130265 70775 130265 65159 130266 70775 130266 65197 130266 65197 130267 70775 130267 70766 130267 65197 130268 70766 130268 65198 130268 65198 130269 70766 130269 70767 130269 65198 130270 70767 130270 65160 130270 65160 130271 70767 130271 70769 130271 65160 130272 70769 130272 65161 130272 65161 130273 70769 130273 70781 130273 65161 130274 70781 130274 65202 130274 65202 130275 70781 130275 70783 130275 65202 130276 70783 130276 65204 130276 65204 130277 70783 130277 65162 130277 65204 130278 65162 130278 65163 130278 65163 130279 65162 130279 70786 130279 65163 130280 70786 130280 65207 130280 65207 130281 70786 130281 65164 130281 65207 130282 65164 130282 65165 130282 65165 130283 65164 130283 70756 130283 65165 130284 70756 130284 65166 130284 65166 130285 70756 130285 65167 130285 65166 130286 65167 130286 65168 130286 65168 130287 65167 130287 70789 130287 65168 130288 70789 130288 65210 130288 65210 130289 70789 130289 70790 130289 65210 130290 70790 130290 65212 130290 65212 130291 70790 130291 65169 130291 65212 130292 65169 130292 65214 130292 65214 130293 65169 130293 70741 130293 65214 130294 70741 130294 65171 130294 65171 130295 70741 130295 65170 130295 65171 130296 65170 130296 65215 130296 65215 130297 65170 130297 70743 130297 65215 130298 70743 130298 65217 130298 65217 130299 70743 130299 70732 130299 65217 130300 70732 130300 65219 130300 65219 130301 70732 130301 65172 130301 65219 130302 65172 130302 65173 130302 65173 130303 65172 130303 70726 130303 65173 130304 70726 130304 65174 130304 65174 130305 70726 130305 70730 130305 65174 130306 70730 130306 65175 130306 65175 130307 70730 130307 65176 130307 65175 130308 65176 130308 65177 130308 65177 130309 65176 130309 70718 130309 65177 130310 70718 130310 65178 130310 65178 130311 70718 130311 70795 130311 65178 130312 70795 130312 65179 130312 65179 130313 70795 130313 65180 130313 65179 130314 65180 130314 65222 130314 65222 130315 65180 130315 70715 130315 65222 130316 70715 130316 65181 130316 65181 130317 70715 130317 65182 130317 65181 130318 65182 130318 65183 130318 65183 130319 65182 130319 70704 130319 65183 130320 70704 130320 65184 130320 65184 130321 70704 130321 70708 130321 65184 130322 70708 130322 65225 130322 65225 130323 70708 130323 65185 130323 65225 130324 65185 130324 65186 130324 65186 130325 65185 130325 65187 130325 65186 130326 65187 130326 65227 130326 65227 130327 65187 130327 65188 130327 65227 130328 65188 130328 65190 130328 65190 130329 65188 130329 65189 130329 65190 130330 65189 130330 65191 130330 65191 130331 65189 130331 70804 130331 65191 130332 70804 130332 65192 130332 65192 130333 70804 130333 65193 130333 65192 130334 65193 130334 65233 130334 65233 130335 65193 130335 70679 130335 65194 130336 65158 130336 65195 130336 65195 130337 65158 130337 65159 130337 65195 130338 65159 130338 65196 130338 65196 130339 65159 130339 65197 130339 65196 130340 65197 130340 65115 130340 65115 130341 65197 130341 65198 130341 65115 130342 65198 130342 65199 130342 65199 130343 65198 130343 65160 130343 65199 130344 65160 130344 65200 130344 65200 130345 65160 130345 65161 130345 65200 130346 65161 130346 65201 130346 65201 130347 65161 130347 65202 130347 65201 130348 65202 130348 65203 130348 65203 130349 65202 130349 65204 130349 65203 130350 65204 130350 65205 130350 65205 130351 65204 130351 65163 130351 65205 130352 65163 130352 65206 130352 65206 130353 65163 130353 65207 130353 65206 130354 65207 130354 65208 130354 65208 130355 65207 130355 65165 130355 65208 130356 65165 130356 65124 130356 65124 130357 65165 130357 65166 130357 65124 130358 65166 130358 65209 130358 65209 130359 65166 130359 65168 130359 65209 130360 65168 130360 65211 130360 65211 130361 65168 130361 65210 130361 65211 130362 65210 130362 65128 130362 65128 130363 65210 130363 65212 130363 65128 130364 65212 130364 65213 130364 65213 130365 65212 130365 65214 130365 65213 130366 65214 130366 65131 130366 65131 130367 65214 130367 65171 130367 65131 130368 65171 130368 65133 130368 65133 130369 65171 130369 65215 130369 65133 130370 65215 130370 65216 130370 65216 130371 65215 130371 65217 130371 65216 130372 65217 130372 65218 130372 65218 130373 65217 130373 65219 130373 65218 130374 65219 130374 65220 130374 65220 130375 65219 130375 65173 130375 65220 130376 65173 130376 65137 130376 65137 130377 65173 130377 65174 130377 65137 130378 65174 130378 65139 130378 65139 130379 65174 130379 65175 130379 65139 130380 65175 130380 65140 130380 65140 130381 65175 130381 65177 130381 65140 130382 65177 130382 65142 130382 65142 130383 65177 130383 65178 130383 65142 130384 65178 130384 65144 130384 65144 130385 65178 130385 65179 130385 65144 130386 65179 130386 65221 130386 65221 130387 65179 130387 65222 130387 65221 130388 65222 130388 65223 130388 65223 130389 65222 130389 65181 130389 65223 130390 65181 130390 65147 130390 65147 130391 65181 130391 65183 130391 65147 130392 65183 130392 65224 130392 65224 130393 65183 130393 65184 130393 65224 130394 65184 130394 65226 130394 65226 130395 65184 130395 65225 130395 65226 130396 65225 130396 65153 130396 65153 130397 65225 130397 65186 130397 65153 130398 65186 130398 65154 130398 65154 130399 65186 130399 65227 130399 65154 130400 65227 130400 65157 130400 65157 130401 65227 130401 65190 130401 65157 130402 65190 130402 65228 130402 65228 130403 65190 130403 65191 130403 65228 130404 65191 130404 65229 130404 65229 130405 65191 130405 65192 130405 65229 130406 65192 130406 65232 130406 65232 130407 65192 130407 65233 130407 65230 130408 65228 130408 70542 130408 70542 130409 65228 130409 65229 130409 70542 130410 65229 130410 65231 130410 65231 130411 65229 130411 65232 130411 65231 130412 65232 130412 70540 130412 70679 130413 65235 130413 65237 130413 70679 130414 65237 130414 65233 130414 65233 130415 65237 130415 65234 130415 65233 130416 65234 130416 65232 130416 65232 130417 65234 130417 70541 130417 65232 130418 70541 130418 70540 130418 65235 130419 65236 130419 70205 130419 65235 130420 70205 130420 65237 130420 65237 130421 70205 130421 70236 130421 65237 130422 70236 130422 65234 130422 65234 130423 70236 130423 65238 130423 65234 130424 65238 130424 70541 130424 69841 130425 69920 130425 65497 130425 65497 130426 69920 130426 65331 130426 65497 130427 65331 130427 65239 130427 65239 130428 65331 130428 65240 130428 65239 130429 65240 130429 65501 130429 65501 130430 65240 130430 65241 130430 65501 130431 65241 130431 65242 130431 65242 130432 65241 130432 65333 130432 65242 130433 65333 130433 65243 130433 65243 130434 65333 130434 65244 130434 65243 130435 65244 130435 65486 130435 65486 130436 65244 130436 65301 130436 65486 130437 65301 130437 65488 130437 65488 130438 65301 130438 65338 130438 65488 130439 65338 130439 65490 130439 65490 130440 65338 130440 65245 130440 65490 130441 65245 130441 65246 130441 65246 130442 65245 130442 65247 130442 65246 130443 65247 130443 65248 130443 65248 130444 65247 130444 65249 130444 65248 130445 65249 130445 65434 130445 65434 130446 65249 130446 65250 130446 65434 130447 65250 130447 65433 130447 65433 130448 65250 130448 65251 130448 65433 130449 65251 130449 65476 130449 65476 130450 65251 130450 65252 130450 65476 130451 65252 130451 65478 130451 65478 130452 65252 130452 65253 130452 65478 130453 65253 130453 65479 130453 65479 130454 65253 130454 65254 130454 65479 130455 65254 130455 65255 130455 65255 130456 65254 130456 65352 130456 65255 130457 65352 130457 65256 130457 65256 130458 65352 130458 65258 130458 65256 130459 65258 130459 65257 130459 65257 130460 65258 130460 65259 130460 65257 130461 65259 130461 65470 130461 65470 130462 65259 130462 65310 130462 65470 130463 65310 130463 65471 130463 65471 130464 65310 130464 65261 130464 65471 130465 65261 130465 65260 130465 65260 130466 65261 130466 65262 130466 65260 130467 65262 130467 65391 130467 65391 130468 65262 130468 65361 130468 65391 130469 65361 130469 65263 130469 65263 130470 65361 130470 65264 130470 65263 130471 65264 130471 65417 130471 65417 130472 65264 130472 65359 130472 65417 130473 65359 130473 65265 130473 65265 130474 65359 130474 65266 130474 65265 130475 65266 130475 65267 130475 65267 130476 65266 130476 65369 130476 65267 130477 65369 130477 65268 130477 65268 130478 65369 130478 65368 130478 65268 130479 65368 130479 65461 130479 65461 130480 65368 130480 65269 130480 65461 130481 65269 130481 65407 130481 65407 130482 65269 130482 65366 130482 65407 130483 65366 130483 65456 130483 65456 130484 65366 130484 65318 130484 65456 130485 65318 130485 65270 130485 65270 130486 65318 130486 65272 130486 65270 130487 65272 130487 65271 130487 65271 130488 65272 130488 65273 130488 65271 130489 65273 130489 65274 130489 65274 130490 65273 130490 65275 130490 65274 130491 65275 130491 65452 130491 65452 130492 65275 130492 65276 130492 65452 130493 65276 130493 65450 130493 65450 130494 65276 130494 65378 130494 65450 130495 65378 130495 65277 130495 65277 130496 65378 130496 65278 130496 65277 130497 65278 130497 65280 130497 65280 130498 65278 130498 65279 130498 65280 130499 65279 130499 65281 130499 65281 130500 65279 130500 65326 130500 65281 130501 65326 130501 65282 130501 65282 130502 65326 130502 65283 130502 65282 130503 65283 130503 65445 130503 65445 130504 65283 130504 65384 130504 65445 130505 65384 130505 65443 130505 65443 130506 65384 130506 65285 130506 65443 130507 65285 130507 65284 130507 65284 130508 65285 130508 65390 130508 65275 130509 65273 130509 65373 130509 65381 130510 65299 130510 65286 130510 65355 130511 65289 130511 65294 130511 65335 130512 65292 130512 65291 130512 70049 130513 70048 130513 65387 130513 65300 130514 70049 130514 65388 130514 70026 130515 65329 130515 65287 130515 65287 130516 65329 130516 65288 130516 65293 130517 65292 130517 70032 130517 70032 130518 65292 130518 65335 130518 70032 130519 65335 130519 70035 130519 70044 130520 65289 130520 70037 130520 70037 130521 65289 130521 65355 130521 70037 130522 65355 130522 65353 130522 70051 130523 65299 130523 70052 130523 70052 130524 65299 130524 65381 130524 70052 130525 65381 130525 65380 130525 65288 130526 65329 130526 65290 130526 65290 130527 65329 130527 65330 130527 65290 130528 65330 130528 69987 130528 65342 130529 65291 130529 65341 130529 65341 130530 65291 130530 65292 130530 65341 130531 65292 130531 65339 130531 65339 130532 65292 130532 65293 130532 65339 130533 65293 130533 65344 130533 65358 130534 65294 130534 65295 130534 65295 130535 65294 130535 65289 130535 65295 130536 65289 130536 65357 130536 65357 130537 65289 130537 70044 130537 65357 130538 70044 130538 65296 130538 65297 130539 65286 130539 65386 130539 65386 130540 65286 130540 65299 130540 65386 130541 65299 130541 65298 130541 65298 130542 65299 130542 70051 130542 65298 130543 70051 130543 65300 130543 65332 130544 65334 130544 65302 130544 65338 130545 65301 130545 65337 130545 65337 130546 65301 130546 65332 130546 65337 130547 65332 130547 65336 130547 65336 130548 65332 130548 65302 130548 65336 130549 65302 130549 65303 130549 65343 130550 65304 130550 65340 130550 65253 130551 65252 130551 65349 130551 65349 130552 65252 130552 65343 130552 65349 130553 65343 130553 65346 130553 65346 130554 65343 130554 65340 130554 65346 130555 65340 130555 65345 130555 70036 130556 65305 130556 65347 130556 65347 130557 65305 130557 65307 130557 65347 130558 65307 130558 65348 130558 65348 130559 65307 130559 65308 130559 65348 130560 65308 130560 65350 130560 65350 130561 65308 130561 65351 130561 65305 130562 65306 130562 65307 130562 65307 130563 65306 130563 65354 130563 65307 130564 65354 130564 65308 130564 65308 130565 65354 130565 65309 130565 65308 130566 65309 130566 65351 130566 65351 130567 65309 130567 65356 130567 65351 130568 65356 130568 65259 130568 65259 130569 65356 130569 65310 130569 65312 130570 65360 130570 65313 130570 65369 130571 65266 130571 65311 130571 65311 130572 65266 130572 65312 130572 65311 130573 65312 130573 65365 130573 65365 130574 65312 130574 65313 130574 65365 130575 65313 130575 65363 130575 65362 130576 70041 130576 65314 130576 65314 130577 70041 130577 65316 130577 65314 130578 65316 130578 65364 130578 65364 130579 65316 130579 65317 130579 65364 130580 65317 130580 65367 130580 65367 130581 65317 130581 65315 130581 70041 130582 70039 130582 65316 130582 65316 130583 70039 130583 65370 130583 65316 130584 65370 130584 65317 130584 65317 130585 65370 130585 65371 130585 65317 130586 65371 130586 65315 130586 65315 130587 65371 130587 65374 130587 65315 130588 65374 130588 65318 130588 65318 130589 65374 130589 65272 130589 70047 130590 65319 130590 65376 130590 65376 130591 65319 130591 65320 130591 65376 130592 65320 130592 65321 130592 65321 130593 65320 130593 65324 130593 65321 130594 65324 130594 65322 130594 65322 130595 65324 130595 65377 130595 65319 130596 65323 130596 65320 130596 65320 130597 65323 130597 65379 130597 65320 130598 65379 130598 65324 130598 65324 130599 65379 130599 65382 130599 65324 130600 65382 130600 65377 130600 65377 130601 65382 130601 65325 130601 65377 130602 65325 130602 65279 130602 65279 130603 65325 130603 65326 130603 69987 130604 65330 130604 69922 130604 69922 130605 65330 130605 65327 130605 69922 130606 65327 130606 65328 130606 65328 130607 65327 130607 65331 130607 65328 130608 65331 130608 69920 130608 70026 130609 65303 130609 65329 130609 65329 130610 65303 130610 65302 130610 65329 130611 65302 130611 65330 130611 65330 130612 65302 130612 65334 130612 65330 130613 65334 130613 65327 130613 65327 130614 65334 130614 65240 130614 65327 130615 65240 130615 65331 130615 65301 130616 65244 130616 65332 130616 65332 130617 65244 130617 65333 130617 65332 130618 65333 130618 65334 130618 65334 130619 65333 130619 65241 130619 65334 130620 65241 130620 65240 130620 70026 130621 70035 130621 65303 130621 65303 130622 70035 130622 65335 130622 65303 130623 65335 130623 65336 130623 65336 130624 65335 130624 65291 130624 65336 130625 65291 130625 65337 130625 65337 130626 65291 130626 65342 130626 65337 130627 65342 130627 65338 130627 65338 130628 65342 130628 65245 130628 65344 130629 65345 130629 65339 130629 65339 130630 65345 130630 65340 130630 65339 130631 65340 130631 65341 130631 65341 130632 65340 130632 65304 130632 65341 130633 65304 130633 65342 130633 65342 130634 65304 130634 65247 130634 65342 130635 65247 130635 65245 130635 65252 130636 65251 130636 65343 130636 65343 130637 65251 130637 65250 130637 65343 130638 65250 130638 65304 130638 65304 130639 65250 130639 65249 130639 65304 130640 65249 130640 65247 130640 65344 130641 70036 130641 65345 130641 65345 130642 70036 130642 65347 130642 65345 130643 65347 130643 65346 130643 65346 130644 65347 130644 65348 130644 65346 130645 65348 130645 65349 130645 65349 130646 65348 130646 65350 130646 65349 130647 65350 130647 65253 130647 65259 130648 65258 130648 65351 130648 65351 130649 65258 130649 65352 130649 65351 130650 65352 130650 65350 130650 65350 130651 65352 130651 65254 130651 65350 130652 65254 130652 65253 130652 65306 130653 65353 130653 65354 130653 65354 130654 65353 130654 65355 130654 65354 130655 65355 130655 65309 130655 65309 130656 65355 130656 65294 130656 65309 130657 65294 130657 65356 130657 65356 130658 65294 130658 65358 130658 65356 130659 65358 130659 65310 130659 65310 130660 65358 130660 65261 130660 65296 130661 65363 130661 65357 130661 65357 130662 65363 130662 65313 130662 65357 130663 65313 130663 65295 130663 65295 130664 65313 130664 65360 130664 65295 130665 65360 130665 65358 130665 65358 130666 65360 130666 65262 130666 65358 130667 65262 130667 65261 130667 65266 130668 65359 130668 65312 130668 65312 130669 65359 130669 65264 130669 65312 130670 65264 130670 65360 130670 65360 130671 65264 130671 65361 130671 65360 130672 65361 130672 65262 130672 65296 130673 65362 130673 65363 130673 65363 130674 65362 130674 65314 130674 65363 130675 65314 130675 65365 130675 65365 130676 65314 130676 65364 130676 65365 130677 65364 130677 65311 130677 65311 130678 65364 130678 65367 130678 65311 130679 65367 130679 65369 130679 65318 130680 65366 130680 65315 130680 65315 130681 65366 130681 65269 130681 65315 130682 65269 130682 65367 130682 65367 130683 65269 130683 65368 130683 65367 130684 65368 130684 65369 130684 70039 130685 70027 130685 65370 130685 65370 130686 70027 130686 65375 130686 65370 130687 65375 130687 65371 130687 65371 130688 65375 130688 65372 130688 65371 130689 65372 130689 65374 130689 65374 130690 65372 130690 65373 130690 65374 130691 65373 130691 65272 130691 65272 130692 65373 130692 65273 130692 70027 130693 70047 130693 65375 130693 65375 130694 70047 130694 65376 130694 65375 130695 65376 130695 65372 130695 65372 130696 65376 130696 65321 130696 65372 130697 65321 130697 65373 130697 65373 130698 65321 130698 65322 130698 65373 130699 65322 130699 65275 130699 65279 130700 65278 130700 65377 130700 65377 130701 65278 130701 65378 130701 65377 130702 65378 130702 65322 130702 65322 130703 65378 130703 65276 130703 65322 130704 65276 130704 65275 130704 65323 130705 65380 130705 65379 130705 65379 130706 65380 130706 65381 130706 65379 130707 65381 130707 65382 130707 65382 130708 65381 130708 65286 130708 65382 130709 65286 130709 65325 130709 65325 130710 65286 130710 65297 130710 65325 130711 65297 130711 65326 130711 65326 130712 65297 130712 65283 130712 65383 130713 65285 130713 65384 130713 65300 130714 65388 130714 65298 130714 65298 130715 65388 130715 65385 130715 65298 130716 65385 130716 65386 130716 65386 130717 65385 130717 65383 130717 65386 130718 65383 130718 65297 130718 65297 130719 65383 130719 65384 130719 65297 130720 65384 130720 65283 130720 70049 130721 65387 130721 65388 130721 65388 130722 65387 130722 65389 130722 65388 130723 65389 130723 65385 130723 65385 130724 65389 130724 69957 130724 65385 130725 69957 130725 65383 130725 65383 130726 69957 130726 65390 130726 65383 130727 65390 130727 65285 130727 65246 130728 65248 130728 65482 130728 65260 130729 65391 130729 65466 130729 65493 130730 65392 130730 65404 130730 65393 130731 65394 130731 65449 130731 65502 130732 69918 130732 69808 130732 70094 130733 65502 130733 65498 130733 70074 130734 65401 130734 70075 130734 70075 130735 65401 130735 65395 130735 70080 130736 65394 130736 65396 130736 65396 130737 65394 130737 65393 130737 65396 130738 65393 130738 65397 130738 65398 130739 65392 130739 65399 130739 65399 130740 65392 130740 65493 130740 65399 130741 65493 130741 65492 130741 65395 130742 65401 130742 65400 130742 65400 130743 65401 130743 65441 130743 65400 130744 65441 130744 69883 130744 65451 130745 65449 130745 65402 130745 65402 130746 65449 130746 65394 130746 65402 130747 65394 130747 65453 130747 65453 130748 65394 130748 70080 130748 65453 130749 70080 130749 70079 130749 65403 130750 65404 130750 65500 130750 65500 130751 65404 130751 65392 130751 65500 130752 65392 130752 65499 130752 65499 130753 65392 130753 65398 130753 65499 130754 65398 130754 70094 130754 65446 130755 65405 130755 65444 130755 65450 130756 65277 130756 65406 130756 65406 130757 65277 130757 65446 130757 65406 130758 65446 130758 65448 130758 65448 130759 65446 130759 65444 130759 65448 130760 65444 130760 65447 130760 65408 130761 65457 130761 65455 130761 65461 130762 65407 130762 65460 130762 65460 130763 65407 130763 65408 130763 65460 130764 65408 130764 65459 130764 65459 130765 65408 130765 65455 130765 65459 130766 65455 130766 65454 130766 65458 130767 65409 130767 65410 130767 65410 130768 65409 130768 65415 130768 65410 130769 65415 130769 65411 130769 65411 130770 65415 130770 65413 130770 65411 130771 65413 130771 65412 130771 65412 130772 65413 130772 65462 130772 65409 130773 65414 130773 65415 130773 65415 130774 65414 130774 65464 130774 65415 130775 65464 130775 65413 130775 65413 130776 65464 130776 65416 130776 65413 130777 65416 130777 65462 130777 65462 130778 65416 130778 65418 130778 65462 130779 65418 130779 65417 130779 65417 130780 65418 130780 65263 130780 65467 130781 70086 130781 65419 130781 65419 130782 70086 130782 65420 130782 65419 130783 65420 130783 65469 130783 65469 130784 65420 130784 65421 130784 65469 130785 65421 130785 65472 130785 65472 130786 65421 130786 65424 130786 70086 130787 65422 130787 65420 130787 65420 130788 65422 130788 65474 130788 65420 130789 65474 130789 65421 130789 65421 130790 65474 130790 65423 130790 65421 130791 65423 130791 65424 130791 65424 130792 65423 130792 65475 130792 65424 130793 65475 130793 65256 130793 65256 130794 65475 130794 65255 130794 65473 130795 65426 130795 65425 130795 65425 130796 65426 130796 65427 130796 65425 130797 65427 130797 65428 130797 65428 130798 65427 130798 65429 130798 65428 130799 65429 130799 65477 130799 65477 130800 65429 130800 65431 130800 65426 130801 65480 130801 65427 130801 65427 130802 65480 130802 65430 130802 65427 130803 65430 130803 65429 130803 65429 130804 65430 130804 65432 130804 65429 130805 65432 130805 65431 130805 65431 130806 65432 130806 65481 130806 65431 130807 65481 130807 65433 130807 65433 130808 65481 130808 65434 130808 65435 130809 70093 130809 65436 130809 65436 130810 70093 130810 65437 130810 65436 130811 65437 130811 65438 130811 65438 130812 65437 130812 65439 130812 65438 130813 65439 130813 65489 130813 65489 130814 65439 130814 65487 130814 70093 130815 65491 130815 65437 130815 65437 130816 65491 130816 65494 130816 65437 130817 65494 130817 65439 130817 65439 130818 65494 130818 65440 130818 65439 130819 65440 130819 65487 130819 65487 130820 65440 130820 65495 130820 65487 130821 65495 130821 65243 130821 65243 130822 65495 130822 65242 130822 69883 130823 65441 130823 69809 130823 69809 130824 65441 130824 65442 130824 69809 130825 65442 130825 69810 130825 69810 130826 65442 130826 65443 130826 69810 130827 65443 130827 65284 130827 70074 130828 65447 130828 65401 130828 65401 130829 65447 130829 65444 130829 65401 130830 65444 130830 65441 130830 65441 130831 65444 130831 65405 130831 65441 130832 65405 130832 65442 130832 65442 130833 65405 130833 65445 130833 65442 130834 65445 130834 65443 130834 65277 130835 65280 130835 65446 130835 65446 130836 65280 130836 65281 130836 65446 130837 65281 130837 65405 130837 65405 130838 65281 130838 65282 130838 65405 130839 65282 130839 65445 130839 70074 130840 65397 130840 65447 130840 65447 130841 65397 130841 65393 130841 65447 130842 65393 130842 65448 130842 65448 130843 65393 130843 65449 130843 65448 130844 65449 130844 65406 130844 65406 130845 65449 130845 65451 130845 65406 130846 65451 130846 65450 130846 65450 130847 65451 130847 65452 130847 70079 130848 65454 130848 65453 130848 65453 130849 65454 130849 65455 130849 65453 130850 65455 130850 65402 130850 65402 130851 65455 130851 65457 130851 65402 130852 65457 130852 65451 130852 65451 130853 65457 130853 65274 130853 65451 130854 65274 130854 65452 130854 65407 130855 65456 130855 65408 130855 65408 130856 65456 130856 65270 130856 65408 130857 65270 130857 65457 130857 65457 130858 65270 130858 65271 130858 65457 130859 65271 130859 65274 130859 70079 130860 65458 130860 65454 130860 65454 130861 65458 130861 65410 130861 65454 130862 65410 130862 65459 130862 65459 130863 65410 130863 65411 130863 65459 130864 65411 130864 65460 130864 65460 130865 65411 130865 65412 130865 65460 130866 65412 130866 65461 130866 65417 130867 65265 130867 65462 130867 65462 130868 65265 130868 65267 130868 65462 130869 65267 130869 65412 130869 65412 130870 65267 130870 65268 130870 65412 130871 65268 130871 65461 130871 65414 130872 65463 130872 65464 130872 65464 130873 65463 130873 65465 130873 65464 130874 65465 130874 65416 130874 65416 130875 65465 130875 65468 130875 65416 130876 65468 130876 65418 130876 65418 130877 65468 130877 65466 130877 65418 130878 65466 130878 65263 130878 65263 130879 65466 130879 65391 130879 65463 130880 65467 130880 65465 130880 65465 130881 65467 130881 65419 130881 65465 130882 65419 130882 65468 130882 65468 130883 65419 130883 65469 130883 65468 130884 65469 130884 65466 130884 65466 130885 65469 130885 65472 130885 65466 130886 65472 130886 65260 130886 65256 130887 65257 130887 65424 130887 65424 130888 65257 130888 65470 130888 65424 130889 65470 130889 65472 130889 65472 130890 65470 130890 65471 130890 65472 130891 65471 130891 65260 130891 65422 130892 65473 130892 65474 130892 65474 130893 65473 130893 65425 130893 65474 130894 65425 130894 65423 130894 65423 130895 65425 130895 65428 130895 65423 130896 65428 130896 65475 130896 65475 130897 65428 130897 65477 130897 65475 130898 65477 130898 65255 130898 65433 130899 65476 130899 65431 130899 65431 130900 65476 130900 65478 130900 65431 130901 65478 130901 65477 130901 65477 130902 65478 130902 65479 130902 65477 130903 65479 130903 65255 130903 65480 130904 65483 130904 65430 130904 65430 130905 65483 130905 65484 130905 65430 130906 65484 130906 65432 130906 65432 130907 65484 130907 65485 130907 65432 130908 65485 130908 65481 130908 65481 130909 65485 130909 65482 130909 65481 130910 65482 130910 65434 130910 65434 130911 65482 130911 65248 130911 65483 130912 65435 130912 65484 130912 65484 130913 65435 130913 65436 130913 65484 130914 65436 130914 65485 130914 65485 130915 65436 130915 65438 130915 65485 130916 65438 130916 65482 130916 65482 130917 65438 130917 65489 130917 65482 130918 65489 130918 65246 130918 65243 130919 65486 130919 65487 130919 65487 130920 65486 130920 65488 130920 65487 130921 65488 130921 65489 130921 65489 130922 65488 130922 65490 130922 65489 130923 65490 130923 65246 130923 65491 130924 65492 130924 65494 130924 65494 130925 65492 130925 65493 130925 65494 130926 65493 130926 65440 130926 65440 130927 65493 130927 65404 130927 65440 130928 65404 130928 65495 130928 65495 130929 65404 130929 65403 130929 65495 130930 65403 130930 65242 130930 65242 130931 65403 130931 65501 130931 65496 130932 65497 130932 65239 130932 70094 130933 65498 130933 65499 130933 65499 130934 65498 130934 65504 130934 65499 130935 65504 130935 65500 130935 65500 130936 65504 130936 65496 130936 65500 130937 65496 130937 65403 130937 65403 130938 65496 130938 65239 130938 65403 130939 65239 130939 65501 130939 65502 130940 69808 130940 65498 130940 65498 130941 69808 130941 65503 130941 65498 130942 65503 130942 65504 130942 65504 130943 65503 130943 69842 130943 65504 130944 69842 130944 65496 130944 65496 130945 69842 130945 69841 130945 65496 130946 69841 130946 65497 130946 69807 130947 65505 130947 64993 130947 64993 130948 65505 130948 65506 130948 64993 130949 65506 130949 65507 130949 65507 130950 65506 130950 65509 130950 65507 130951 65509 130951 65508 130951 65508 130952 65509 130952 70050 130952 65508 130953 70050 130953 65510 130953 65510 130954 70050 130954 70045 130954 65510 130955 70045 130955 65511 130955 65511 130956 70045 130956 70046 130956 65511 130957 70046 130957 64990 130957 64990 130958 70046 130958 65512 130958 64990 130959 65512 130959 64989 130959 64989 130960 65512 130960 70040 130960 64989 130961 70040 130961 64987 130961 64987 130962 70040 130962 70042 130962 64987 130963 70042 130963 65513 130963 65513 130964 70042 130964 70043 130964 65513 130965 70043 130965 65514 130965 65514 130966 70043 130966 65515 130966 65514 130967 65515 130967 65516 130967 65516 130968 65515 130968 65517 130968 65516 130969 65517 130969 64982 130969 64982 130970 65517 130970 70038 130970 64982 130971 70038 130971 65518 130971 65518 130972 70038 130972 65519 130972 65518 130973 65519 130973 65520 130973 65520 130974 65519 130974 65521 130974 65520 130975 65521 130975 65522 130975 65522 130976 65521 130976 70033 130976 65522 130977 70033 130977 65523 130977 65523 130978 70033 130978 70034 130978 65523 130979 70034 130979 70601 130979 70601 130980 70034 130980 69787 130980 70620 130981 70082 130981 64962 130981 64962 130982 70082 130982 65524 130982 64962 130983 65524 130983 65525 130983 65525 130984 65524 130984 70095 130984 65525 130985 70095 130985 64966 130985 64966 130986 70095 130986 70096 130986 64966 130987 70096 130987 64967 130987 64967 130988 70096 130988 70091 130988 64967 130989 70091 130989 65526 130989 65526 130990 70091 130990 70092 130990 65526 130991 70092 130991 64970 130991 64970 130992 70092 130992 70089 130992 64970 130993 70089 130993 64972 130993 64972 130994 70089 130994 70090 130994 64972 130995 70090 130995 65527 130995 65527 130996 70090 130996 70101 130996 65527 130997 70101 130997 65528 130997 65528 130998 70101 130998 65529 130998 65528 130999 65529 130999 64974 130999 64974 131000 65529 131000 65530 131000 64974 131001 65530 131001 64975 131001 64975 131002 65530 131002 70087 131002 64975 131003 70087 131003 65531 131003 65531 131004 70087 131004 70088 131004 65531 131005 70088 131005 65532 131005 65532 131006 70088 131006 70070 131006 65532 131007 70070 131007 64977 131007 64977 131008 70070 131008 65533 131008 64977 131009 65533 131009 64978 131009 64978 131010 65533 131010 65535 131010 64978 131011 65535 131011 65534 131011 65534 131012 65535 131012 70081 131012 65534 131013 70081 131013 70604 131013 70604 131014 70081 131014 69772 131014 69755 131015 69771 131015 65536 131015 65536 131016 69771 131016 69743 131016 69742 131017 65537 131017 65538 131017 65538 131018 65537 131018 65539 131018 65538 131019 65539 131019 67824 131019 67824 131020 65539 131020 69761 131020 67824 131021 69761 131021 65541 131021 65541 131022 69761 131022 65540 131022 65541 131023 65540 131023 67822 131023 67822 131024 65540 131024 69763 131024 67822 131025 69763 131025 65542 131025 65542 131026 69763 131026 69764 131026 65542 131027 69764 131027 67819 131027 67819 131028 69764 131028 69765 131028 69745 131029 69770 131029 69744 131029 69744 131030 69770 131030 69206 131030 69603 131031 69602 131031 65544 131031 65544 131032 69602 131032 65543 131032 65547 131033 68977 131033 65543 131033 65543 131034 68977 131034 68980 131034 65543 131035 68980 131035 65544 131035 68971 131036 68973 131036 65545 131036 65545 131037 68973 131037 68974 131037 65545 131038 68974 131038 65547 131038 65547 131039 68974 131039 65546 131039 65547 131040 65546 131040 68977 131040 68971 131041 65545 131041 68966 131041 68966 131042 65545 131042 65548 131042 68966 131043 65548 131043 65549 131043 65549 131044 65548 131044 68967 131044 68967 131045 65548 131045 65550 131045 68967 131046 65550 131046 68969 131046 68969 131047 65550 131047 68963 131047 68963 131048 65550 131048 69608 131048 68963 131049 69608 131049 68965 131049 69582 131050 69581 131050 65551 131050 65551 131051 69581 131051 69592 131051 65551 131052 69592 131052 65552 131052 69037 131053 65553 131053 69590 131053 69590 131054 65553 131054 65554 131054 69590 131055 65554 131055 69592 131055 69592 131056 65554 131056 69038 131056 69592 131057 69038 131057 65552 131057 69037 131058 69590 131058 65555 131058 65555 131059 69590 131059 65557 131059 65555 131060 65557 131060 65556 131060 65556 131061 65557 131061 69035 131061 69035 131062 65557 131062 69588 131062 69035 131063 69588 131063 69030 131063 69030 131064 69588 131064 65558 131064 65558 131065 69588 131065 69599 131065 65558 131066 69599 131066 69031 131066 69090 131067 65559 131067 69563 131067 69090 131068 69563 131068 65560 131068 65560 131069 69563 131069 65561 131069 65560 131070 65561 131070 69091 131070 69091 131071 65561 131071 69093 131071 69093 131072 65561 131072 65562 131072 69093 131073 65562 131073 65563 131073 65563 131074 65562 131074 65564 131074 65564 131075 65562 131075 69565 131075 65564 131076 69565 131076 69088 131076 69088 131077 69565 131077 65565 131077 69088 131078 65565 131078 69556 131078 69146 131079 69548 131079 69147 131079 69147 131080 69548 131080 65567 131080 69147 131081 65567 131081 69149 131081 69149 131082 65567 131082 65566 131082 65566 131083 65567 131083 69546 131083 65566 131084 69546 131084 69141 131084 69141 131085 69546 131085 65568 131085 69141 131086 65568 131086 65569 131086 69522 131087 65570 131087 69211 131087 69211 131088 65570 131088 69527 131088 69211 131089 69527 131089 69210 131089 69210 131090 69527 131090 69526 131090 69210 131091 69526 131091 69514 131091 65571 131092 69505 131092 67832 131092 67832 131093 69505 131093 65572 131093 67832 131094 65572 131094 65573 131094 65573 131095 65572 131095 69507 131095 65573 131096 69507 131096 65574 131096 65574 131097 69507 131097 65575 131097 65574 131098 65575 131098 65576 131098 65576 131099 65575 131099 69508 131099 65576 131100 69508 131100 67835 131100 67835 131101 69508 131101 65577 131101 67835 131102 65577 131102 65578 131102 65578 131103 65577 131103 65579 131103 67838 131104 65580 131104 65581 131104 65581 131105 65580 131105 70633 131105 65581 131106 70633 131106 65582 131106 65582 131107 70633 131107 70623 131107 65582 131108 70623 131108 65583 131108 65583 131109 70623 131109 70624 131109 65583 131110 70624 131110 65584 131110 65584 131111 70624 131111 70625 131111 65584 131112 70625 131112 65585 131112 65585 131113 70625 131113 65586 131113 65585 131114 65586 131114 67843 131114 67843 131115 65586 131115 70629 131115 67849 131116 69699 131116 65587 131116 65587 131117 69699 131117 69698 131117 65587 131118 69698 131118 67847 131118 67847 131119 69698 131119 65588 131119 67847 131120 65588 131120 65589 131120 65589 131121 65588 131121 69702 131121 65589 131122 69702 131122 65590 131122 65590 131123 69702 131123 69704 131123 65590 131124 69704 131124 67855 131124 67855 131125 69704 131125 69705 131125 67855 131126 69705 131126 65591 131126 65591 131127 69705 131127 69707 131127 65592 131128 65593 131128 67857 131128 67857 131129 65593 131129 65595 131129 67857 131130 65595 131130 65594 131130 65594 131131 65595 131131 65596 131131 65594 131132 65596 131132 65597 131132 65597 131133 65596 131133 65598 131133 65597 131134 65598 131134 67862 131134 67862 131135 65598 131135 69673 131135 67862 131136 69673 131136 65599 131136 65599 131137 69673 131137 69675 131137 65599 131138 69675 131138 67861 131138 67861 131139 69675 131139 69677 131139 67872 131140 69658 131140 67873 131140 67873 131141 69658 131141 69655 131141 67873 131142 69655 131142 67874 131142 67874 131143 69655 131143 69656 131143 67874 131144 69656 131144 65600 131144 65600 131145 69656 131145 65601 131145 65600 131146 65601 131146 67875 131146 67875 131147 65601 131147 69661 131147 67875 131148 69661 131148 65602 131148 65602 131149 69661 131149 65603 131149 65602 131150 65603 131150 67865 131150 67865 131151 65603 131151 69663 131151 67882 131152 65604 131152 67883 131152 67883 131153 65604 131153 65605 131153 67883 131154 65605 131154 67885 131154 67885 131155 65605 131155 65606 131155 67885 131156 65606 131156 67886 131156 67886 131157 65606 131157 69630 131157 67886 131158 69630 131158 65607 131158 65607 131159 69630 131159 65608 131159 65607 131160 65608 131160 65609 131160 65609 131161 65608 131161 69633 131161 65609 131162 69633 131162 65610 131162 65610 131163 69633 131163 69635 131163 67892 131164 69452 131164 67891 131164 67891 131165 69452 131165 69606 131165 67891 131166 69606 131166 67890 131166 67890 131167 69606 131167 65612 131167 67890 131168 65612 131168 65611 131168 65611 131169 65612 131169 65613 131169 65611 131170 65613 131170 67898 131170 67898 131171 65613 131171 65614 131171 67898 131172 65614 131172 65615 131172 65615 131173 65614 131173 69605 131173 65615 131174 69605 131174 67897 131174 67897 131175 69605 131175 65616 131175 67903 131176 69593 131176 65617 131176 65617 131177 69593 131177 69594 131177 65617 131178 69594 131178 65618 131178 65618 131179 69594 131179 69595 131179 65618 131180 69595 131180 65619 131180 65619 131181 69595 131181 69584 131181 65619 131182 69584 131182 65620 131182 65620 131183 69584 131183 65621 131183 65620 131184 65621 131184 65622 131184 65622 131185 65621 131185 65623 131185 65622 131186 65623 131186 67902 131186 67902 131187 65623 131187 69597 131187 69441 131188 69442 131188 65624 131188 65624 131189 69442 131189 69568 131189 65624 131190 69568 131190 67911 131190 67911 131191 69568 131191 65625 131191 67911 131192 65625 131192 67910 131192 67910 131193 65625 131193 69570 131193 67910 131194 69570 131194 67918 131194 67918 131195 69570 131195 65626 131195 67918 131196 65626 131196 67917 131196 67917 131197 65626 131197 65627 131197 67917 131198 65627 131198 65628 131198 65628 131199 65627 131199 69569 131199 67927 131200 65629 131200 67925 131200 67925 131201 65629 131201 65630 131201 67925 131202 65630 131202 67924 131202 67924 131203 65630 131203 69549 131203 67924 131204 69549 131204 67921 131204 67921 131205 69549 131205 69551 131205 67921 131206 69551 131206 65631 131206 65631 131207 69551 131207 69542 131207 65631 131208 69542 131208 67936 131208 67936 131209 69542 131209 69544 131209 67936 131210 69544 131210 65632 131210 65632 131211 69544 131211 69555 131211 67941 131212 69529 131212 65633 131212 65633 131213 69529 131213 69530 131213 65633 131214 69530 131214 65634 131214 65634 131215 69530 131215 65635 131215 65634 131216 65635 131216 67937 131216 67937 131217 65635 131217 65636 131217 67937 131218 65636 131218 65637 131218 65637 131219 65636 131219 65638 131219 65637 131220 65638 131220 67948 131220 67948 131221 65638 131221 65639 131221 67948 131222 65639 131222 69429 131222 69429 131223 65639 131223 69523 131223 65645 131224 65648 131224 69279 131224 69279 131225 65648 131225 65640 131225 69279 131226 65640 131226 69281 131226 69281 131227 65640 131227 65641 131227 69281 131228 65641 131228 70851 131228 68952 131229 65642 131229 65643 131229 65643 131230 65642 131230 65644 131230 65643 131231 65644 131231 69607 131231 69607 131232 65644 131232 65646 131232 69607 131233 65646 131233 65645 131233 65645 131234 65646 131234 65647 131234 65645 131235 65647 131235 65648 131235 69586 131236 69020 131236 69585 131236 69585 131237 69020 131237 69021 131237 69585 131238 69021 131238 65649 131238 65649 131239 69021 131239 69274 131239 69274 131240 69021 131240 70853 131240 69274 131241 70853 131241 65650 131241 69268 131242 65651 131242 69071 131242 69071 131243 65651 131243 69081 131243 65652 131244 65657 131244 65653 131244 65652 131245 65653 131245 65654 131245 65654 131246 65653 131246 65655 131246 65654 131247 65655 131247 65656 131247 65656 131248 65655 131248 69178 131248 65656 131249 69178 131249 69537 131249 65652 131250 65658 131250 65657 131250 65657 131251 65658 131251 69265 131251 65657 131252 69265 131252 69319 131252 69252 131253 69515 131253 65659 131253 69252 131254 65659 131254 65661 131254 65659 131255 65660 131255 65661 131255 65661 131256 65660 131256 69535 131256 65661 131257 69535 131257 69251 131257 68870 131258 65662 131258 65663 131258 68870 131259 65663 131259 65664 131259 65664 131260 65663 131260 65093 131260 65664 131261 65093 131261 65665 131261 65665 131262 65093 131262 65091 131262 65665 131263 65091 131263 65666 131263 65666 131264 65091 131264 65667 131264 65666 131265 65667 131265 65668 131265 65668 131266 65667 131266 65089 131266 65668 131267 65089 131267 65669 131267 65669 131268 65089 131268 65671 131268 65669 131269 65671 131269 65670 131269 65670 131270 65671 131270 65672 131270 65670 131271 65672 131271 70352 131271 70352 131272 65672 131272 65086 131272 70352 131273 65086 131273 65673 131273 65673 131274 65086 131274 65084 131274 65673 131275 65084 131275 65674 131275 65674 131276 65084 131276 65083 131276 65674 131277 65083 131277 65675 131277 65675 131278 65083 131278 65676 131278 65675 131279 65676 131279 70328 131279 70328 131280 65676 131280 65081 131280 70328 131281 65081 131281 70331 131281 70331 131282 65081 131282 65080 131282 70331 131283 65080 131283 65677 131283 65677 131284 65080 131284 65678 131284 65677 131285 65678 131285 70333 131285 70333 131286 65678 131286 65078 131286 70333 131287 65078 131287 65679 131287 65679 131288 65078 131288 65076 131288 65679 131289 65076 131289 68850 131289 70602 131290 70480 131290 65680 131290 65680 131291 70480 131291 70481 131291 65680 131292 70481 131292 64980 131292 64980 131293 70481 131293 70484 131293 64980 131294 70484 131294 64981 131294 64981 131295 70484 131295 65681 131295 64981 131296 65681 131296 64983 131296 64983 131297 65681 131297 70486 131297 64983 131298 70486 131298 64984 131298 64984 131299 70486 131299 70456 131299 64984 131300 70456 131300 64985 131300 64985 131301 70456 131301 65682 131301 64985 131302 65682 131302 65683 131302 65683 131303 65682 131303 70457 131303 65683 131304 70457 131304 64986 131304 64986 131305 70457 131305 65684 131305 64986 131306 65684 131306 64988 131306 64988 131307 65684 131307 65685 131307 64988 131308 65685 131308 65686 131308 65686 131309 65685 131309 65687 131309 65686 131310 65687 131310 64991 131310 64991 131311 65687 131311 65688 131311 64991 131312 65688 131312 65689 131312 65689 131313 65688 131313 70462 131313 65689 131314 70462 131314 65690 131314 65690 131315 70462 131315 65691 131315 65690 131316 65691 131316 65692 131316 65692 131317 65691 131317 65693 131317 65692 131318 65693 131318 64992 131318 64992 131319 65693 131319 65694 131319 64992 131320 65694 131320 64994 131320 64994 131321 65694 131321 65695 131321 64994 131322 65695 131322 70586 131322 70586 131323 65695 131323 68829 131323 70504 131324 65697 131324 65696 131324 65696 131325 65697 131325 70521 131325 65696 131326 70521 131326 65698 131326 65698 131327 70521 131327 65699 131327 65698 131328 65699 131328 65700 131328 65700 131329 65699 131329 65701 131329 65700 131330 65701 131330 65046 131330 65046 131331 65701 131331 70524 131331 65046 131332 70524 131332 65702 131332 65702 131333 70524 131333 65703 131333 65702 131334 65703 131334 65704 131334 65704 131335 65703 131335 65705 131335 65704 131336 65705 131336 65049 131336 65049 131337 65705 131337 65706 131337 65049 131338 65706 131338 65707 131338 65707 131339 65706 131339 70527 131339 65707 131340 70527 131340 65050 131340 65050 131341 70527 131341 65708 131341 65050 131342 65708 131342 65052 131342 65052 131343 65708 131343 70528 131343 65052 131344 70528 131344 65709 131344 65709 131345 70528 131345 65710 131345 65709 131346 65710 131346 65053 131346 65053 131347 65710 131347 70530 131347 65053 131348 70530 131348 65711 131348 65711 131349 70530 131349 70531 131349 65711 131350 70531 131350 65056 131350 65056 131351 70531 131351 65713 131351 65056 131352 65713 131352 65712 131352 65712 131353 65713 131353 65714 131353 65712 131354 65714 131354 65057 131354 65057 131355 65714 131355 65715 131355 65057 131356 65715 131356 65059 131356 65059 131357 65715 131357 65716 131357 65059 131358 65716 131358 68810 131358 68810 131359 65716 131359 68811 131359 65717 131360 65718 131360 65043 131360 65717 131361 65043 131361 65719 131361 65719 131362 65043 131362 65042 131362 65719 131363 65042 131363 70537 131363 70537 131364 65042 131364 65720 131364 70537 131365 65720 131365 70539 131365 70539 131366 65720 131366 65040 131366 70539 131367 65040 131367 65721 131367 65721 131368 65040 131368 65038 131368 65721 131369 65038 131369 65722 131369 65722 131370 65038 131370 65036 131370 65722 131371 65036 131371 70506 131371 70506 131372 65036 131372 65035 131372 70506 131373 65035 131373 65723 131373 65723 131374 65035 131374 65724 131374 65723 131375 65724 131375 70508 131375 70508 131376 65724 131376 65031 131376 70508 131377 65031 131377 70511 131377 70511 131378 65031 131378 65725 131378 70511 131379 65725 131379 70512 131379 70512 131380 65725 131380 65726 131380 70512 131381 65726 131381 70514 131381 70514 131382 65726 131382 65029 131382 70514 131383 65029 131383 70515 131383 70515 131384 65029 131384 65727 131384 70515 131385 65727 131385 65728 131385 65728 131386 65727 131386 65022 131386 65728 131387 65022 131387 70516 131387 70516 131388 65022 131388 65020 131388 70516 131389 65020 131389 65729 131389 65729 131390 65020 131390 65017 131390 65729 131391 65017 131391 70519 131391 70519 131392 65017 131392 65015 131392 70519 131393 65015 131393 70520 131393 70520 131394 65015 131394 70568 131394 70520 131395 70568 131395 65730 131395 65731 131396 68793 131396 65013 131396 65013 131397 68793 131397 65732 131397 65013 131398 65732 131398 65733 131398 65733 131399 65732 131399 68622 131399 65733 131400 68622 131400 65734 131400 65734 131401 68622 131401 68621 131401 65734 131402 68621 131402 65010 131402 65010 131403 68621 131403 68619 131403 65010 131404 68619 131404 65009 131404 65009 131405 68619 131405 65735 131405 65009 131406 65735 131406 65736 131406 65736 131407 65735 131407 65737 131407 65736 131408 65737 131408 65738 131408 65738 131409 65737 131409 68599 131409 65738 131410 68599 131410 65004 131410 65004 131411 68599 131411 68606 131411 65004 131412 68606 131412 65003 131412 65003 131413 68606 131413 65739 131413 65003 131414 65739 131414 65740 131414 65740 131415 65739 131415 68605 131415 65740 131416 68605 131416 65000 131416 65000 131417 68605 131417 68616 131417 65000 131418 68616 131418 65741 131418 65741 131419 68616 131419 68615 131419 65741 131420 68615 131420 64998 131420 64998 131421 68615 131421 68614 131421 64998 131422 68614 131422 64996 131422 64996 131423 68614 131423 65742 131423 64996 131424 65742 131424 65743 131424 65743 131425 65742 131425 65744 131425 65743 131426 65744 131426 64995 131426 64995 131427 65744 131427 68613 131427 68779 131428 70305 131428 65746 131428 65746 131429 70305 131429 65745 131429 65746 131430 65745 131430 65747 131430 65747 131431 65745 131431 70306 131431 65747 131432 70306 131432 64997 131432 64997 131433 70306 131433 65748 131433 64997 131434 65748 131434 64999 131434 64999 131435 65748 131435 65749 131435 64999 131436 65749 131436 65001 131436 65001 131437 65749 131437 65750 131437 65001 131438 65750 131438 65002 131438 65002 131439 65750 131439 65751 131439 65002 131440 65751 131440 65005 131440 65005 131441 65751 131441 65752 131441 65005 131442 65752 131442 65006 131442 65006 131443 65752 131443 65753 131443 65006 131444 65753 131444 65007 131444 65007 131445 65753 131445 65754 131445 65007 131446 65754 131446 65008 131446 65008 131447 65754 131447 65755 131447 65008 131448 65755 131448 65756 131448 65756 131449 65755 131449 70282 131449 65756 131450 70282 131450 65011 131450 65011 131451 70282 131451 70284 131451 65011 131452 70284 131452 65757 131452 65757 131453 70284 131453 70286 131453 65757 131454 70286 131454 65012 131454 65012 131455 70286 131455 70287 131455 65012 131456 70287 131456 65758 131456 65758 131457 70287 131457 70289 131457 65758 131458 70289 131458 65014 131458 65014 131459 70289 131459 68762 131459 65096 131460 70335 131460 65098 131460 65098 131461 70335 131461 65759 131461 65098 131462 65759 131462 65099 131462 65099 131463 65759 131463 70336 131463 65099 131464 70336 131464 65760 131464 65760 131465 70336 131465 65762 131465 65760 131466 65762 131466 65761 131466 65761 131467 65762 131467 65763 131467 65761 131468 65763 131468 65103 131468 65103 131469 65763 131469 65765 131469 65103 131470 65765 131470 65764 131470 65764 131471 65765 131471 65766 131471 65764 131472 65766 131472 65767 131472 65767 131473 65766 131473 70340 131473 65767 131474 70340 131474 65104 131474 65104 131475 70340 131475 65768 131475 65104 131476 65768 131476 65769 131476 65769 131477 65768 131477 65770 131477 65769 131478 65770 131478 65106 131478 65106 131479 65770 131479 65772 131479 65106 131480 65772 131480 65771 131480 65771 131481 65772 131481 65773 131481 65771 131482 65773 131482 65774 131482 65774 131483 65773 131483 70341 131483 65774 131484 70341 131484 65108 131484 65108 131485 70341 131485 70342 131485 65108 131486 70342 131486 65775 131486 65775 131487 70342 131487 70344 131487 65775 131488 70344 131488 65776 131488 65776 131489 70344 131489 70345 131489 65776 131490 70345 131490 65110 131490 65110 131491 70345 131491 70346 131491 68751 131492 65074 131492 65073 131492 68751 131493 65073 131493 70385 131493 70385 131494 65073 131494 65072 131494 70385 131495 65072 131495 70386 131495 70386 131496 65072 131496 65777 131496 70386 131497 65777 131497 65778 131497 65778 131498 65777 131498 65071 131498 65778 131499 65071 131499 70387 131499 70387 131500 65071 131500 65070 131500 70387 131501 65070 131501 65779 131501 65779 131502 65070 131502 65780 131502 65779 131503 65780 131503 70390 131503 70390 131504 65780 131504 65781 131504 70390 131505 65781 131505 70391 131505 70391 131506 65781 131506 65782 131506 70391 131507 65782 131507 65783 131507 65783 131508 65782 131508 65067 131508 65783 131509 65067 131509 65784 131509 65784 131510 65067 131510 65065 131510 65784 131511 65065 131511 65785 131511 65785 131512 65065 131512 65786 131512 65785 131513 65786 131513 70395 131513 70395 131514 65786 131514 65787 131514 70395 131515 65787 131515 70397 131515 70397 131516 65787 131516 65788 131516 70397 131517 65788 131517 65789 131517 65789 131518 65788 131518 65790 131518 65789 131519 65790 131519 65791 131519 65791 131520 65790 131520 65061 131520 65791 131521 65061 131521 65792 131521 65792 131522 65061 131522 65793 131522 65792 131523 65793 131523 70398 131523 70398 131524 65793 131524 68739 131524 70398 131525 68739 131525 70399 131525 68691 131526 68693 131526 65794 131526 65794 131527 68693 131527 68662 131527 65795 131528 65796 131528 68674 131528 68674 131529 65796 131529 65799 131529 68687 131530 68668 131530 65797 131530 65797 131531 68668 131531 68672 131531 65797 131532 68672 131532 68689 131532 68689 131533 68672 131533 65798 131533 68689 131534 65798 131534 65799 131534 65799 131535 65798 131535 68673 131535 65799 131536 68673 131536 68674 131536 68727 131537 68729 131537 65800 131537 65800 131538 68729 131538 65809 131538 65810 131539 68702 131539 70855 131539 70855 131540 68702 131540 68652 131540 68636 131541 68723 131541 65802 131541 68636 131542 65802 131542 68634 131542 68634 131543 65802 131543 65801 131543 68634 131544 65801 131544 68633 131544 68633 131545 65801 131545 68710 131545 68633 131546 68710 131546 68631 131546 68723 131547 68546 131547 65802 131547 65802 131548 68546 131548 65803 131548 65802 131549 65803 131549 65801 131549 65801 131550 65803 131550 68708 131550 65801 131551 68708 131551 68710 131551 65804 131552 65805 131552 68722 131552 68725 131553 68543 131553 65806 131553 65806 131554 68543 131554 65804 131554 65806 131555 65804 131555 65807 131555 65807 131556 65804 131556 68722 131556 65800 131557 65809 131557 68542 131557 68542 131558 65809 131558 68541 131558 65808 131559 68540 131559 65809 131559 65809 131560 68540 131560 68541 131560 68702 131561 65810 131561 68533 131561 68533 131562 65810 131562 65811 131562 68736 131563 65794 131563 65812 131563 65812 131564 65794 131564 68661 131564 65829 131565 68588 131565 66137 131565 66137 131566 68588 131566 66138 131566 65813 131567 68085 131567 68696 131567 68696 131568 68085 131568 65814 131568 65815 131569 68552 131569 65837 131569 65837 131570 68552 131570 68690 131570 68495 131571 65837 131571 68692 131571 68692 131572 65837 131572 68690 131572 68501 131573 65817 131573 65816 131573 65816 131574 65817 131574 65818 131574 65816 131575 65818 131575 65832 131575 65832 131576 65818 131576 68688 131576 65832 131577 68688 131577 65834 131577 65834 131578 68688 131578 68684 131578 68549 131579 65819 131579 65820 131579 65820 131580 65819 131580 68681 131580 65820 131581 68681 131581 65822 131581 65822 131582 68681 131582 65821 131582 65822 131583 65821 131583 68530 131583 68530 131584 65821 131584 68682 131584 65823 131585 68063 131585 68125 131585 68125 131586 68063 131586 65824 131586 68547 131587 65825 131587 68598 131587 68598 131588 65825 131588 68597 131588 68597 131589 65825 131589 65826 131589 68597 131590 65826 131590 68593 131590 65827 131591 68518 131591 68161 131591 68161 131592 68518 131592 68547 131592 68161 131593 68547 131593 68162 131593 68162 131594 68547 131594 68598 131594 65828 131595 68505 131595 65829 131595 65829 131596 68505 131596 68588 131596 65830 131597 68564 131597 68501 131597 65830 131598 68501 131598 68561 131598 68561 131599 68501 131599 65816 131599 68561 131600 65816 131600 65831 131600 65831 131601 65816 131601 68560 131601 68560 131602 65816 131602 65832 131602 68560 131603 65832 131603 65833 131603 65833 131604 65832 131604 65834 131604 65833 131605 65834 131605 68559 131605 65835 131606 65815 131606 65836 131606 65836 131607 65815 131607 65837 131607 65836 131608 65837 131608 68567 131608 65838 131609 68494 131609 67940 131609 65838 131610 67940 131610 68038 131610 68038 131611 67940 131611 67939 131611 68038 131612 67939 131612 65839 131612 65839 131613 67939 131613 67938 131613 65839 131614 67938 131614 65840 131614 65840 131615 67938 131615 65841 131615 65840 131616 65841 131616 65842 131616 65842 131617 65841 131617 67949 131617 65842 131618 67949 131618 68040 131618 68040 131619 67949 131619 65843 131619 68040 131620 65843 131620 65844 131620 65844 131621 65843 131621 67947 131621 65844 131622 67947 131622 68042 131622 68061 131623 67928 131623 67926 131623 68061 131624 67926 131624 68062 131624 68062 131625 67926 131625 65846 131625 68062 131626 65846 131626 65845 131626 65845 131627 65846 131627 67923 131627 65845 131628 67923 131628 65847 131628 65847 131629 67923 131629 67922 131629 65847 131630 67922 131630 68054 131630 68054 131631 67922 131631 65848 131631 68054 131632 65848 131632 68053 131632 68053 131633 65848 131633 65849 131633 68053 131634 65849 131634 65850 131634 65850 131635 65849 131635 65851 131635 65850 131636 65851 131636 65852 131636 66148 131637 68477 131637 67912 131637 66148 131638 67912 131638 65853 131638 65853 131639 67912 131639 65854 131639 65853 131640 65854 131640 65855 131640 65855 131641 65854 131641 65856 131641 65855 131642 65856 131642 66141 131642 66141 131643 65856 131643 67909 131643 66141 131644 67909 131644 66140 131644 66140 131645 67909 131645 67920 131645 66140 131646 67920 131646 65857 131646 65857 131647 67920 131647 67919 131647 65857 131648 67919 131648 65858 131648 65858 131649 67919 131649 67916 131649 65858 131650 67916 131650 66143 131650 65859 131651 65860 131651 65866 131651 65861 131652 67905 131652 67904 131652 65861 131653 67904 131653 65862 131653 65862 131654 67904 131654 65863 131654 65862 131655 65863 131655 66155 131655 66155 131656 65863 131656 65864 131656 66155 131657 65864 131657 65865 131657 65866 131658 65860 131658 65864 131658 65864 131659 65860 131659 66157 131659 65864 131660 66157 131660 65865 131660 65859 131661 65866 131661 65868 131661 65868 131662 65866 131662 65867 131662 65868 131663 65867 131663 66158 131663 66158 131664 65867 131664 68461 131664 66158 131665 68461 131665 65869 131665 68460 131666 67893 131666 65870 131666 68460 131667 65870 131667 66172 131667 66172 131668 65870 131668 65871 131668 66172 131669 65871 131669 66173 131669 66173 131670 65871 131670 65872 131670 66173 131671 65872 131671 66175 131671 66175 131672 65872 131672 65873 131672 66175 131673 65873 131673 66176 131673 66176 131674 65873 131674 65874 131674 66176 131675 65874 131675 65875 131675 65875 131676 65874 131676 65876 131676 65875 131677 65876 131677 66177 131677 66177 131678 65876 131678 68450 131678 66177 131679 68450 131679 68449 131679 65880 131680 65877 131680 67884 131680 67881 131681 65878 131681 66186 131681 66186 131682 65878 131682 65879 131682 67884 131683 65877 131683 65878 131683 65878 131684 65877 131684 66188 131684 65878 131685 66188 131685 65879 131685 65880 131686 67884 131686 65881 131686 65881 131687 67884 131687 65882 131687 65881 131688 65882 131688 66190 131688 66190 131689 65882 131689 67887 131689 66190 131690 67887 131690 65883 131690 65883 131691 67887 131691 67888 131691 65883 131692 67888 131692 65884 131692 65884 131693 67888 131693 67889 131693 65884 131694 67889 131694 66191 131694 65885 131695 66200 131695 67869 131695 65885 131696 67869 131696 66201 131696 66201 131697 67869 131697 67871 131697 66201 131698 67871 131698 66202 131698 66202 131699 67871 131699 65886 131699 66202 131700 65886 131700 66204 131700 66204 131701 65886 131701 65887 131701 65887 131702 65886 131702 65889 131702 65887 131703 65889 131703 65888 131703 65888 131704 65889 131704 65890 131704 65888 131705 65890 131705 65891 131705 65891 131706 65890 131706 67863 131706 65891 131707 67863 131707 65892 131707 65892 131708 67863 131708 67864 131708 65892 131709 67864 131709 66207 131709 66124 131710 65893 131710 65894 131710 66124 131711 65894 131711 66125 131711 66125 131712 65894 131712 65895 131712 66125 131713 65895 131713 65896 131713 65896 131714 65895 131714 65897 131714 65896 131715 65897 131715 65898 131715 65898 131716 65897 131716 65899 131716 65898 131717 65899 131717 66216 131717 66216 131718 65899 131718 67856 131718 66216 131719 67856 131719 66217 131719 66217 131720 67856 131720 65900 131720 66217 131721 65900 131721 65901 131721 65901 131722 65900 131722 65902 131722 65901 131723 65902 131723 66126 131723 68426 131724 65903 131724 67848 131724 68426 131725 67848 131725 65904 131725 65904 131726 67848 131726 65905 131726 65904 131727 65905 131727 67974 131727 67974 131728 65905 131728 67846 131728 67974 131729 67846 131729 67979 131729 67979 131730 67846 131730 65906 131730 67979 131731 65906 131731 67969 131731 67969 131732 65906 131732 65907 131732 67969 131733 65907 131733 65908 131733 65908 131734 65907 131734 65909 131734 65908 131735 65909 131735 65910 131735 65910 131736 65909 131736 65911 131736 65910 131737 65911 131737 68419 131737 65912 131738 65913 131738 65914 131738 65912 131739 65914 131739 68000 131739 68000 131740 65914 131740 67837 131740 68000 131741 67837 131741 68001 131741 68001 131742 67837 131742 65916 131742 68001 131743 65916 131743 65915 131743 65915 131744 65916 131744 67845 131744 65915 131745 67845 131745 68004 131745 68004 131746 67845 131746 67844 131746 68004 131747 67844 131747 68002 131747 68002 131748 67844 131748 65918 131748 68002 131749 65918 131749 65917 131749 65917 131750 65918 131750 65919 131750 65917 131751 65919 131751 68412 131751 68009 131752 65920 131752 65921 131752 68009 131753 65921 131753 65922 131753 65922 131754 65921 131754 67831 131754 65922 131755 67831 131755 68010 131755 68010 131756 67831 131756 67830 131756 68010 131757 67830 131757 68012 131757 68012 131758 67830 131758 65924 131758 68012 131759 65924 131759 65923 131759 65923 131760 65924 131760 67829 131760 65923 131761 67829 131761 65925 131761 65925 131762 67829 131762 65926 131762 65925 131763 65926 131763 68014 131763 68014 131764 65926 131764 67836 131764 68014 131765 67836 131765 68022 131765 65928 131766 65927 131766 65929 131766 65928 131767 65929 131767 68023 131767 68023 131768 65929 131768 67825 131768 68023 131769 67825 131769 68024 131769 68024 131770 67825 131770 67823 131770 68024 131771 67823 131771 68026 131771 68026 131772 67823 131772 65930 131772 68026 131773 65930 131773 68027 131773 68027 131774 65930 131774 65931 131774 68027 131775 65931 131775 68028 131775 68028 131776 65931 131776 67821 131776 68028 131777 67821 131777 68031 131777 68031 131778 67821 131778 68392 131778 68031 131779 68392 131779 68029 131779 65932 131780 66710 131780 65933 131780 65933 131781 66710 131781 65934 131781 65933 131782 65934 131782 66235 131782 66235 131783 65934 131783 66708 131783 66235 131784 66708 131784 66233 131784 66233 131785 66708 131785 65935 131785 66233 131786 65935 131786 65936 131786 65936 131787 65935 131787 65937 131787 65936 131788 65937 131788 66229 131788 66229 131789 65937 131789 66706 131789 66229 131790 66706 131790 65938 131790 65938 131791 66706 131791 65939 131791 65938 131792 65939 131792 66228 131792 66228 131793 65939 131793 66704 131793 66228 131794 66704 131794 66226 131794 66226 131795 66704 131795 66703 131795 66226 131796 66703 131796 65941 131796 65941 131797 66703 131797 65940 131797 65941 131798 65940 131798 65942 131798 65942 131799 65940 131799 65943 131799 65942 131800 65943 131800 66224 131800 66224 131801 65943 131801 66700 131801 66224 131802 66700 131802 65944 131802 65944 131803 66700 131803 66698 131803 65944 131804 66698 131804 66221 131804 66221 131805 66698 131805 65945 131805 66221 131806 65945 131806 66220 131806 66220 131807 65945 131807 66695 131807 66220 131808 66695 131808 66218 131808 66218 131809 66695 131809 66694 131809 70884 131810 65946 131810 65947 131810 70884 131811 65947 131811 70885 131811 70885 131812 65947 131812 66095 131812 70885 131813 66095 131813 65948 131813 65948 131814 66095 131814 66097 131814 65948 131815 66097 131815 65949 131815 65949 131816 66097 131816 66098 131816 65949 131817 66098 131817 70889 131817 70889 131818 66098 131818 66099 131818 70889 131819 66099 131819 65950 131819 65950 131820 66099 131820 66104 131820 65950 131821 66104 131821 65951 131821 65951 131822 66104 131822 66106 131822 65951 131823 66106 131823 70868 131823 70868 131824 66106 131824 65952 131824 70868 131825 65952 131825 65953 131825 65953 131826 65952 131826 66108 131826 65953 131827 66108 131827 65954 131827 65954 131828 66108 131828 65955 131828 65954 131829 65955 131829 70867 131829 70867 131830 65955 131830 65956 131830 70867 131831 65956 131831 70898 131831 70898 131832 65956 131832 66110 131832 70898 131833 66110 131833 70897 131833 70897 131834 66110 131834 65957 131834 70897 131835 65957 131835 70896 131835 70896 131836 65957 131836 66112 131836 70896 131837 66112 131837 65958 131837 65958 131838 66112 131838 66114 131838 65958 131839 66114 131839 70894 131839 70894 131840 66114 131840 65959 131840 70894 131841 65959 131841 65960 131841 65960 131842 65959 131842 66120 131842 65960 131843 66120 131843 70892 131843 70892 131844 66120 131844 66118 131844 70892 131845 66118 131845 68353 131845 65965 131846 65964 131846 68254 131846 65961 131847 65962 131847 66092 131847 66092 131848 65962 131848 68566 131848 66092 131849 68566 131849 68296 131849 68293 131850 68254 131850 65963 131850 65963 131851 68254 131851 65964 131851 65963 131852 65964 131852 66012 131852 68254 131853 65966 131853 65965 131853 65965 131854 65966 131854 68255 131854 65965 131855 68255 131855 66014 131855 66014 131856 68255 131856 68253 131856 66014 131857 68253 131857 65967 131857 68253 131858 68251 131858 65967 131858 65967 131859 68251 131859 65968 131859 65967 131860 65968 131860 65969 131860 65969 131861 65968 131861 68250 131861 65969 131862 68250 131862 65970 131862 68250 131863 68248 131863 65970 131863 65970 131864 68248 131864 65971 131864 65970 131865 65971 131865 65972 131865 65972 131866 65971 131866 65973 131866 65972 131867 65973 131867 65974 131867 65973 131868 68246 131868 65974 131868 65974 131869 68246 131869 68245 131869 65974 131870 68245 131870 66020 131870 66020 131871 68245 131871 65975 131871 66020 131872 65975 131872 66022 131872 66022 131873 65975 131873 65976 131873 66022 131874 65976 131874 65978 131874 65976 131875 68243 131875 65978 131875 65978 131876 68243 131876 65977 131876 65978 131877 65977 131877 65979 131877 65979 131878 65977 131878 68242 131878 65979 131879 68242 131879 66024 131879 68242 131880 65980 131880 66024 131880 66024 131881 65980 131881 68241 131881 66024 131882 68241 131882 66025 131882 66025 131883 68241 131883 65981 131883 66025 131884 65981 131884 65983 131884 65981 131885 65982 131885 65983 131885 65983 131886 65982 131886 68240 131886 65983 131887 68240 131887 65985 131887 65985 131888 68240 131888 65984 131888 65985 131889 65984 131889 66026 131889 65984 131890 65986 131890 66026 131890 66026 131891 65986 131891 68238 131891 66026 131892 68238 131892 65987 131892 65987 131893 68238 131893 68237 131893 65987 131894 68237 131894 66028 131894 68237 131895 68236 131895 66028 131895 66028 131896 68236 131896 65988 131896 66028 131897 65988 131897 65989 131897 65989 131898 65988 131898 68235 131898 65989 131899 68235 131899 66030 131899 68235 131900 65990 131900 66030 131900 66030 131901 65990 131901 65991 131901 66030 131902 65991 131902 66032 131902 66032 131903 65991 131903 65992 131903 66032 131904 65992 131904 66033 131904 66033 131905 65992 131905 65994 131905 66033 131906 65994 131906 65993 131906 65994 131907 68234 131907 65993 131907 65993 131908 68234 131908 65995 131908 65993 131909 65995 131909 65996 131909 65996 131910 65995 131910 68233 131910 65996 131911 68233 131911 66035 131911 68233 131912 68232 131912 66035 131912 66035 131913 68232 131913 68231 131913 66035 131914 68231 131914 66036 131914 66036 131915 68231 131915 68230 131915 66036 131916 68230 131916 65998 131916 68230 131917 65997 131917 65998 131917 65998 131918 65997 131918 68228 131918 65998 131919 68228 131919 66038 131919 66038 131920 68228 131920 65999 131920 66038 131921 65999 131921 66002 131921 65999 131922 66000 131922 66002 131922 66002 131923 66000 131923 66001 131923 66002 131924 66001 131924 66042 131924 66042 131925 66001 131925 66003 131925 66042 131926 66003 131926 66043 131926 66003 131927 66004 131927 66043 131927 66043 131928 66004 131928 68226 131928 66043 131929 68226 131929 66045 131929 66045 131930 68226 131930 66005 131930 66045 131931 66005 131931 66006 131931 66005 131932 68225 131932 66006 131932 66006 131933 68225 131933 66007 131933 66006 131934 66007 131934 66047 131934 66047 131935 66007 131935 68224 131935 66047 131936 68224 131936 66048 131936 66048 131937 68224 131937 68222 131937 66048 131938 68222 131938 66009 131938 68222 131939 66008 131939 66009 131939 66009 131940 66008 131940 66010 131940 66009 131941 66010 131941 66011 131941 66011 131942 66010 131942 68221 131942 66011 131943 68221 131943 68256 131943 68256 131944 68221 131944 68257 131944 68296 131945 66012 131945 66092 131945 66092 131946 66012 131946 65964 131946 66092 131947 65964 131947 66090 131947 66090 131948 65964 131948 65965 131948 66090 131949 65965 131949 66013 131949 66013 131950 65965 131950 66014 131950 66013 131951 66014 131951 66015 131951 66015 131952 66014 131952 65967 131952 66015 131953 65967 131953 66088 131953 66088 131954 65967 131954 65969 131954 66088 131955 65969 131955 66016 131955 66016 131956 65969 131956 65970 131956 66016 131957 65970 131957 66017 131957 66017 131958 65970 131958 65972 131958 66017 131959 65972 131959 66018 131959 66018 131960 65972 131960 65974 131960 66018 131961 65974 131961 66084 131961 66084 131962 65974 131962 66020 131962 66084 131963 66020 131963 66019 131963 66019 131964 66020 131964 66022 131964 66019 131965 66022 131965 66021 131965 66021 131966 66022 131966 65978 131966 66021 131967 65978 131967 66082 131967 66082 131968 65978 131968 65979 131968 66082 131969 65979 131969 66023 131969 66023 131970 65979 131970 66024 131970 66023 131971 66024 131971 66080 131971 66080 131972 66024 131972 66025 131972 66080 131973 66025 131973 66076 131973 66076 131974 66025 131974 65983 131974 66076 131975 65983 131975 66075 131975 66075 131976 65983 131976 65985 131976 66075 131977 65985 131977 66073 131977 66073 131978 65985 131978 66026 131978 66073 131979 66026 131979 66071 131979 66071 131980 66026 131980 65987 131980 66071 131981 65987 131981 66027 131981 66027 131982 65987 131982 66028 131982 66027 131983 66028 131983 66029 131983 66029 131984 66028 131984 65989 131984 66029 131985 65989 131985 66069 131985 66069 131986 65989 131986 66030 131986 66069 131987 66030 131987 66031 131987 66031 131988 66030 131988 66032 131988 66031 131989 66032 131989 66067 131989 66067 131990 66032 131990 66033 131990 66067 131991 66033 131991 66065 131991 66065 131992 66033 131992 65993 131992 66065 131993 65993 131993 66063 131993 66063 131994 65993 131994 65996 131994 66063 131995 65996 131995 66034 131995 66034 131996 65996 131996 66035 131996 66034 131997 66035 131997 66061 131997 66061 131998 66035 131998 66036 131998 66061 131999 66036 131999 66060 131999 66060 132000 66036 132000 65998 132000 66060 132001 65998 132001 66037 132001 66037 132002 65998 132002 66038 132002 66037 132003 66038 132003 66039 132003 66039 132004 66038 132004 66002 132004 66039 132005 66002 132005 66040 132005 66040 132006 66002 132006 66042 132006 66040 132007 66042 132007 66041 132007 66041 132008 66042 132008 66043 132008 66041 132009 66043 132009 66044 132009 66044 132010 66043 132010 66045 132010 66044 132011 66045 132011 66056 132011 66056 132012 66045 132012 66006 132012 66056 132013 66006 132013 66046 132013 66046 132014 66006 132014 66047 132014 66046 132015 66047 132015 66049 132015 66049 132016 66047 132016 66048 132016 66049 132017 66048 132017 66053 132017 66053 132018 66048 132018 66009 132018 66053 132019 66009 132019 66050 132019 66050 132020 66009 132020 66011 132020 66050 132021 66011 132021 68260 132021 68260 132022 66011 132022 68256 132022 68260 132023 66051 132023 66050 132023 66050 132024 66051 132024 66052 132024 66050 132025 66052 132025 66053 132025 66053 132026 66052 132026 66054 132026 66053 132027 66054 132027 66049 132027 66049 132028 66054 132028 66055 132028 66049 132029 66055 132029 66046 132029 66046 132030 66055 132030 66149 132030 66046 132031 66149 132031 66056 132031 66056 132032 66149 132032 66150 132032 66056 132033 66150 132033 66044 132033 66044 132034 66150 132034 66057 132034 66044 132035 66057 132035 66041 132035 66041 132036 66057 132036 66058 132036 66041 132037 66058 132037 66040 132037 66040 132038 66058 132038 66159 132038 66040 132039 66159 132039 66039 132039 66039 132040 66159 132040 66163 132040 66039 132041 66163 132041 66037 132041 66037 132042 66163 132042 66059 132042 66037 132043 66059 132043 66060 132043 66060 132044 66059 132044 66165 132044 66060 132045 66165 132045 66061 132045 66061 132046 66165 132046 66167 132046 66061 132047 66167 132047 66034 132047 66034 132048 66167 132048 66062 132048 66034 132049 66062 132049 66063 132049 66063 132050 66062 132050 66064 132050 66063 132051 66064 132051 66065 132051 66065 132052 66064 132052 66066 132052 66065 132053 66066 132053 66067 132053 66067 132054 66066 132054 66068 132054 66067 132055 66068 132055 66031 132055 66031 132056 66068 132056 66180 132056 66031 132057 66180 132057 66069 132057 66069 132058 66180 132058 66181 132058 66069 132059 66181 132059 66029 132059 66029 132060 66181 132060 66070 132060 66029 132061 66070 132061 66027 132061 66027 132062 66070 132062 66183 132062 66027 132063 66183 132063 66071 132063 66071 132064 66183 132064 66072 132064 66071 132065 66072 132065 66073 132065 66073 132066 66072 132066 66074 132066 66073 132067 66074 132067 66075 132067 66075 132068 66074 132068 66077 132068 66075 132069 66077 132069 66076 132069 66076 132070 66077 132070 66078 132070 66076 132071 66078 132071 66080 132071 66080 132072 66078 132072 66079 132072 66080 132073 66079 132073 66023 132073 66023 132074 66079 132074 66198 132074 66023 132075 66198 132075 66082 132075 66082 132076 66198 132076 66081 132076 66082 132077 66081 132077 66021 132077 66021 132078 66081 132078 66206 132078 66021 132079 66206 132079 66019 132079 66019 132080 66206 132080 66083 132080 66019 132081 66083 132081 66084 132081 66084 132082 66083 132082 66085 132082 66084 132083 66085 132083 66018 132083 66018 132084 66085 132084 66212 132084 66018 132085 66212 132085 66017 132085 66017 132086 66212 132086 66086 132086 66017 132087 66086 132087 66016 132087 66016 132088 66086 132088 66087 132088 66016 132089 66087 132089 66088 132089 66088 132090 66087 132090 66214 132090 66088 132091 66214 132091 66015 132091 66015 132092 66214 132092 66089 132092 66015 132093 66089 132093 66013 132093 66013 132094 66089 132094 66128 132094 66013 132095 66128 132095 66090 132095 66090 132096 66128 132096 66091 132096 66090 132097 66091 132097 66092 132097 66092 132098 66091 132098 66122 132098 66092 132099 66122 132099 65961 132099 68293 132100 66093 132100 65946 132100 65946 132101 66093 132101 65947 132101 66093 132102 68295 132102 65947 132102 65947 132103 68295 132103 66096 132103 65947 132104 66096 132104 66095 132104 68304 132105 66097 132105 66094 132105 66094 132106 66097 132106 66095 132106 66094 132107 66095 132107 68298 132107 68298 132108 66095 132108 66096 132108 68304 132109 68309 132109 66097 132109 66097 132110 68309 132110 68308 132110 66097 132111 68308 132111 66098 132111 66102 132112 66099 132112 68306 132112 68306 132113 66099 132113 66098 132113 68306 132114 66098 132114 66100 132114 66100 132115 66098 132115 68308 132115 68316 132116 66104 132116 66101 132116 66101 132117 66104 132117 66099 132117 66101 132118 66099 132118 68312 132118 68312 132119 66099 132119 66102 132119 68316 132120 66103 132120 66104 132120 66104 132121 66103 132121 66105 132121 66104 132122 66105 132122 66106 132122 66105 132123 68258 132123 66106 132123 66106 132124 68258 132124 66107 132124 66106 132125 66107 132125 65952 132125 66107 132126 68320 132126 65952 132126 65952 132127 68320 132127 68321 132127 65952 132128 68321 132128 66108 132128 68321 132129 68323 132129 66108 132129 66108 132130 68323 132130 68325 132130 66108 132131 68325 132131 65955 132131 68328 132132 65956 132132 66109 132132 66109 132133 65956 132133 65955 132133 66109 132134 65955 132134 68326 132134 68326 132135 65955 132135 68325 132135 68328 132136 68332 132136 65956 132136 65956 132137 68332 132137 68335 132137 65956 132138 68335 132138 66110 132138 68335 132139 68339 132139 66110 132139 66110 132140 68339 132140 68338 132140 66110 132141 68338 132141 65957 132141 66111 132142 66112 132142 68336 132142 68336 132143 66112 132143 65957 132143 68336 132144 65957 132144 68337 132144 68337 132145 65957 132145 68338 132145 66111 132146 66113 132146 66112 132146 66112 132147 66113 132147 66116 132147 66112 132148 66116 132148 66114 132148 66117 132149 65959 132149 68342 132149 68342 132150 65959 132150 66114 132150 68342 132151 66114 132151 66115 132151 66115 132152 66114 132152 66116 132152 66117 132153 68351 132153 65959 132153 65959 132154 68351 132154 66121 132154 65959 132155 66121 132155 66120 132155 68257 132156 66118 132156 66119 132156 66119 132157 66118 132157 66120 132157 66119 132158 66120 132158 68349 132158 68349 132159 66120 132159 66121 132159 66210 132160 68439 132160 66085 132160 68570 132161 66122 132161 66091 132161 66123 132162 68436 132162 66131 132162 66131 132163 68436 132163 66124 132163 66131 132164 66124 132164 68157 132164 66124 132165 66125 132165 68157 132165 68157 132166 66125 132166 65896 132166 68157 132167 65896 132167 66215 132167 66215 132168 65896 132168 65898 132168 66215 132169 65898 132169 66216 132169 66217 132170 65901 132170 66089 132170 66089 132171 65901 132171 66126 132171 66089 132172 66126 132172 66128 132172 66128 132173 66126 132173 66127 132173 66127 132174 68429 132174 66128 132174 66128 132175 68429 132175 68431 132175 66128 132176 68431 132176 68432 132176 68570 132177 66091 132177 66136 132177 66135 132178 66129 132178 66130 132178 66130 132179 66129 132179 66132 132179 66130 132180 66132 132180 68577 132180 68577 132181 66132 132181 66134 132181 66123 132182 66131 132182 66132 132182 66132 132183 66131 132183 66133 132183 66132 132184 66133 132184 66134 132184 68432 132185 66129 132185 66128 132185 66128 132186 66129 132186 66135 132186 66128 132187 66135 132187 66091 132187 66091 132188 66135 132188 68573 132188 66091 132189 68573 132189 66136 132189 66051 132190 66137 132190 66052 132190 66052 132191 66137 132191 66138 132191 66052 132192 66138 132192 66054 132192 66054 132193 66138 132193 68587 132193 68587 132194 66139 132194 66054 132194 66054 132195 66139 132195 68586 132195 66054 132196 68586 132196 66146 132196 68583 132197 68581 132197 66144 132197 66144 132198 68581 132198 68580 132198 66144 132199 68580 132199 68152 132199 65857 132200 68151 132200 66140 132200 66140 132201 68151 132201 66142 132201 66140 132202 66142 132202 66141 132202 66141 132203 66142 132203 65855 132203 65857 132204 65858 132204 68151 132204 68151 132205 65858 132205 66143 132205 68151 132206 66143 132206 66144 132206 66144 132207 66143 132207 68468 132207 66144 132208 68468 132208 68470 132208 68470 132209 66145 132209 66144 132209 66144 132210 66145 132210 66054 132210 66144 132211 66054 132211 68583 132211 68583 132212 66054 132212 66146 132212 66145 132213 68471 132213 66054 132213 66054 132214 68471 132214 68473 132214 66054 132215 68473 132215 66055 132215 66055 132216 68473 132216 68474 132216 68474 132217 66147 132217 66055 132217 66055 132218 66147 132218 68475 132218 66055 132219 68475 132219 66149 132219 66149 132220 68475 132220 66148 132220 66149 132221 66148 132221 65853 132221 65853 132222 65855 132222 66149 132222 66149 132223 65855 132223 66142 132223 66149 132224 66142 132224 66150 132224 66150 132225 66142 132225 66152 132225 66150 132226 66152 132226 66151 132226 66151 132227 66152 132227 66153 132227 66151 132228 66153 132228 66058 132228 66058 132229 66153 132229 66154 132229 66058 132230 66154 132230 66159 132230 66159 132231 66154 132231 68147 132231 65862 132232 66155 132232 66156 132232 66156 132233 66155 132233 65865 132233 65859 132234 68146 132234 65860 132234 65860 132235 68146 132235 66156 132235 65860 132236 66156 132236 66157 132236 66157 132237 66156 132237 65865 132237 65859 132238 65868 132238 68146 132238 68146 132239 65868 132239 66158 132239 68146 132240 66158 132240 68147 132240 66162 132241 66163 132241 66160 132241 66160 132242 66163 132242 66159 132242 66160 132243 66159 132243 66161 132243 66161 132244 66159 132244 68147 132244 66161 132245 68147 132245 65869 132245 65869 132246 68147 132246 66158 132246 66162 132247 66164 132247 66163 132247 66163 132248 66164 132248 68466 132248 66163 132249 68466 132249 66059 132249 66059 132250 68466 132250 68467 132250 66059 132251 68467 132251 65861 132251 65861 132252 65862 132252 66059 132252 66059 132253 65862 132253 66156 132253 66059 132254 66156 132254 66165 132254 66165 132255 66156 132255 66166 132255 66165 132256 66166 132256 66167 132256 66167 132257 66166 132257 68141 132257 66167 132258 68141 132258 66062 132258 66062 132259 68141 132259 66168 132259 66062 132260 66168 132260 66064 132260 66064 132261 66168 132261 66169 132261 66064 132262 66169 132262 66066 132262 66066 132263 66169 132263 66170 132263 66066 132264 66170 132264 66068 132264 66068 132265 66170 132265 68137 132265 68454 132266 66171 132266 66068 132266 66068 132267 66171 132267 68455 132267 66068 132268 68455 132268 66180 132268 66180 132269 68455 132269 68456 132269 66180 132270 68456 132270 68458 132270 68460 132271 66172 132271 68135 132271 68135 132272 66172 132272 66174 132272 66172 132273 66173 132273 66174 132273 66174 132274 66173 132274 66175 132274 66174 132275 66175 132275 68137 132275 66175 132276 66176 132276 68137 132276 68137 132277 66176 132277 65875 132277 68137 132278 65875 132278 66177 132278 66177 132279 68449 132279 68137 132279 68137 132280 68449 132280 66178 132280 68137 132281 66178 132281 66068 132281 66068 132282 66178 132282 68453 132282 66068 132283 68453 132283 68454 132283 68458 132284 66179 132284 66180 132284 66180 132285 66179 132285 68460 132285 66180 132286 68460 132286 66181 132286 66181 132287 68460 132287 68135 132287 66181 132288 68135 132288 66070 132288 66070 132289 68135 132289 66182 132289 66070 132290 66182 132290 66183 132290 66183 132291 66182 132291 68132 132291 66183 132292 68132 132292 66072 132292 66072 132293 68132 132293 66184 132293 66072 132294 66184 132294 66185 132294 66185 132295 66184 132295 66189 132295 68448 132296 66186 132296 66197 132296 66197 132297 66186 132297 66187 132297 66187 132298 66186 132298 65879 132298 66187 132299 65879 132299 66188 132299 66188 132300 65877 132300 66187 132300 66187 132301 65877 132301 65880 132301 66187 132302 65880 132302 66189 132302 66189 132303 65880 132303 65881 132303 66189 132304 65881 132304 66190 132304 66190 132305 65883 132305 66189 132305 66189 132306 65883 132306 65884 132306 66189 132307 65884 132307 66185 132307 66185 132308 65884 132308 66191 132308 66185 132309 66191 132309 66192 132309 66192 132310 66193 132310 66185 132310 66185 132311 66193 132311 66194 132311 66185 132312 66194 132312 66077 132312 66077 132313 66194 132313 66195 132313 66077 132314 66195 132314 66078 132314 66078 132315 66195 132315 66196 132315 66196 132316 68448 132316 66078 132316 66078 132317 68448 132317 66197 132317 66078 132318 66197 132318 66079 132318 66079 132319 66197 132319 68129 132319 66079 132320 68129 132320 66198 132320 66198 132321 68129 132321 68127 132321 66198 132322 68127 132322 66081 132322 66081 132323 68127 132323 66199 132323 66081 132324 66199 132324 66206 132324 66206 132325 66199 132325 66205 132325 68442 132326 68443 132326 68155 132326 68155 132327 68443 132327 66200 132327 68155 132328 66200 132328 66203 132328 66203 132329 66200 132329 65885 132329 66203 132330 65885 132330 66201 132330 66201 132331 66202 132331 66203 132331 66203 132332 66202 132332 66204 132332 66203 132333 66204 132333 66205 132333 66205 132334 66204 132334 65887 132334 65887 132335 65888 132335 66205 132335 66205 132336 65888 132336 65891 132336 66205 132337 65891 132337 66206 132337 66206 132338 65891 132338 65892 132338 66206 132339 65892 132339 66083 132339 66083 132340 65892 132340 66207 132340 66083 132341 66207 132341 66208 132341 66208 132342 68437 132342 66083 132342 66083 132343 68437 132343 66209 132343 66083 132344 66209 132344 66085 132344 66085 132345 66209 132345 68438 132345 66085 132346 68438 132346 66210 132346 68439 132347 68442 132347 66085 132347 66085 132348 68442 132348 68155 132348 66085 132349 68155 132349 66212 132349 66212 132350 68155 132350 66211 132350 66212 132351 66211 132351 66086 132351 66086 132352 66211 132352 66213 132352 66086 132353 66213 132353 66087 132353 66087 132354 66213 132354 68156 132354 66087 132355 68156 132355 66214 132355 66214 132356 68156 132356 66215 132356 66214 132357 66215 132357 66089 132357 66089 132358 66215 132358 66216 132358 66089 132359 66216 132359 66217 132359 66218 132360 66219 132360 66220 132360 66220 132361 66219 132361 67811 132361 66220 132362 67811 132362 66221 132362 66221 132363 67811 132363 67815 132363 66221 132364 67815 132364 65944 132364 65944 132365 67815 132365 66222 132365 65944 132366 66222 132366 66224 132366 66224 132367 66222 132367 66223 132367 66224 132368 66223 132368 65942 132368 65942 132369 66223 132369 66225 132369 65942 132370 66225 132370 65941 132370 65941 132371 66225 132371 67812 132371 65941 132372 67812 132372 66226 132372 66226 132373 67812 132373 66227 132373 66226 132374 66227 132374 66228 132374 66228 132375 66227 132375 67813 132375 66228 132376 67813 132376 65938 132376 65938 132377 67813 132377 66230 132377 65938 132378 66230 132378 66229 132378 66229 132379 66230 132379 67814 132379 66229 132380 67814 132380 65936 132380 65936 132381 67814 132381 66231 132381 65936 132382 66231 132382 66233 132382 66233 132383 66231 132383 66232 132383 66233 132384 66232 132384 66235 132384 66235 132385 66232 132385 66234 132385 66235 132386 66234 132386 65933 132386 65933 132387 66234 132387 67810 132387 65933 132388 67810 132388 65932 132388 65932 132389 67810 132389 67809 132389 66238 132390 66237 132390 66236 132390 66897 132391 66237 132391 66238 132391 66896 132392 66897 132392 66238 132392 66238 132393 66870 132393 66879 132393 66872 132394 66870 132394 66238 132394 66236 132395 66872 132395 66238 132395 67788 132396 66239 132396 66893 132396 66875 132397 66239 132397 67788 132397 67789 132398 66875 132398 67788 132398 67788 132399 66891 132399 66240 132399 66241 132400 66891 132400 67788 132400 66893 132401 66241 132401 67788 132401 67786 132402 66242 132402 66899 132402 66244 132403 66242 132403 67786 132403 66243 132404 66244 132404 67786 132404 67786 132405 66869 132405 66868 132405 66245 132406 66869 132406 67786 132406 66899 132407 66245 132407 67786 132407 67780 132408 66904 132408 66246 132408 66871 132409 66904 132409 67780 132409 66880 132410 66871 132410 67780 132410 67780 132411 66247 132411 66886 132411 66908 132412 66247 132412 67780 132412 66246 132413 66908 132413 67780 132413 66248 132414 66916 132414 66915 132414 66248 132415 66915 132415 70893 132415 70893 132416 66915 132416 66914 132416 70893 132417 66914 132417 66249 132417 66249 132418 66914 132418 66912 132418 66249 132419 66912 132419 70895 132419 70895 132420 66912 132420 66910 132420 70895 132421 66910 132421 66250 132421 66250 132422 66910 132422 67765 132422 66250 132423 67765 132423 67764 132423 70883 132424 66658 132424 66251 132424 70883 132425 66251 132425 70882 132425 70882 132426 66251 132426 66656 132426 70882 132427 66656 132427 66252 132427 66252 132428 66656 132428 66253 132428 66252 132429 66253 132429 70879 132429 70879 132430 66253 132430 66655 132430 70879 132431 66655 132431 66254 132431 66254 132432 66655 132432 66255 132432 66254 132433 66255 132433 66256 132433 66256 132434 66255 132434 66652 132434 66256 132435 66652 132435 66257 132435 66257 132436 66652 132436 66258 132436 66257 132437 66258 132437 66259 132437 66259 132438 66258 132438 66649 132438 66259 132439 66649 132439 66260 132439 66260 132440 66649 132440 66261 132440 66260 132441 66261 132441 66262 132441 66262 132442 66261 132442 66263 132442 66262 132443 66263 132443 70875 132443 70875 132444 66263 132444 66264 132444 70875 132445 66264 132445 66265 132445 66265 132446 66264 132446 66646 132446 66265 132447 66646 132447 70874 132447 70874 132448 66646 132448 66266 132448 70874 132449 66266 132449 66267 132449 66267 132450 66266 132450 66268 132450 66267 132451 66268 132451 66269 132451 66269 132452 66268 132452 66270 132452 66269 132453 66270 132453 70891 132453 70891 132454 66270 132454 66916 132454 70891 132455 66916 132455 66248 132455 66271 132456 67703 132456 66272 132456 66271 132457 66272 132457 66747 132457 66747 132458 66272 132458 66273 132458 66747 132459 66273 132459 66769 132459 66769 132460 66273 132460 66274 132460 66769 132461 66274 132461 66275 132461 66274 132462 66920 132462 66275 132462 66275 132463 66920 132463 66276 132463 66275 132464 66276 132464 66766 132464 66766 132465 66276 132465 66277 132465 66766 132466 66277 132466 66765 132466 66765 132467 66277 132467 66924 132467 66765 132468 66924 132468 66922 132468 66296 132469 66659 132469 66639 132469 66296 132470 66639 132470 66763 132470 66763 132471 66639 132471 66640 132471 66763 132472 66640 132472 66278 132472 66278 132473 66640 132473 66279 132473 66278 132474 66279 132474 66772 132474 66772 132475 66279 132475 66643 132475 66772 132476 66643 132476 66746 132476 66746 132477 66643 132477 66280 132477 66746 132478 66280 132478 66757 132478 66645 132479 66835 132479 66644 132479 66644 132480 66835 132480 66282 132480 66644 132481 66282 132481 66281 132481 66281 132482 66282 132482 66283 132482 66281 132483 66283 132483 66917 132483 66291 132484 66816 132484 66648 132484 66648 132485 66816 132485 66284 132485 66648 132486 66284 132486 66647 132486 66647 132487 66284 132487 66820 132487 66647 132488 66820 132488 66645 132488 66645 132489 66820 132489 66285 132489 66645 132490 66285 132490 66835 132490 66286 132491 66287 132491 66651 132491 66651 132492 66287 132492 66288 132492 66651 132493 66288 132493 66650 132493 66650 132494 66288 132494 66289 132494 66650 132495 66289 132495 66290 132495 66290 132496 66289 132496 66743 132496 66290 132497 66743 132497 66291 132497 66291 132498 66743 132498 66827 132498 66291 132499 66827 132499 66816 132499 66292 132500 66788 132500 66654 132500 66654 132501 66788 132501 66796 132501 66654 132502 66796 132502 66653 132502 66653 132503 66796 132503 66797 132503 66653 132504 66797 132504 66286 132504 66286 132505 66797 132505 66293 132505 66286 132506 66293 132506 66287 132506 66295 132507 66784 132507 66292 132507 66292 132508 66784 132508 66745 132508 66292 132509 66745 132509 66788 132509 66292 132510 66294 132510 66295 132510 66295 132511 66294 132511 66657 132511 66295 132512 66657 132512 66780 132512 66780 132513 66657 132513 66659 132513 66780 132514 66659 132514 66296 132514 67081 132515 67659 132515 66297 132515 66297 132516 67659 132516 67083 132516 67635 132517 67042 132517 66298 132517 66298 132518 67042 132518 67043 132518 66298 132519 67043 132519 66306 132519 66306 132520 67043 132520 66299 132520 66306 132521 66299 132521 66308 132521 66308 132522 66299 132522 66300 132522 66308 132523 66300 132523 66309 132523 66309 132524 66300 132524 67034 132524 66309 132525 67034 132525 66311 132525 66311 132526 67034 132526 66302 132526 66311 132527 66302 132527 66301 132527 66301 132528 66302 132528 67636 132528 66303 132529 67635 132529 66304 132529 66304 132530 67635 132530 66298 132530 66304 132531 66298 132531 66305 132531 66305 132532 66298 132532 66306 132532 66305 132533 66306 132533 66307 132533 66307 132534 66306 132534 66308 132534 66307 132535 66308 132535 66312 132535 66312 132536 66308 132536 66309 132536 66312 132537 66309 132537 66310 132537 66310 132538 66309 132538 66311 132538 66310 132539 66311 132539 67624 132539 67624 132540 66311 132540 66301 132540 67630 132541 66305 132541 66307 132541 66304 132542 66305 132542 67630 132542 66303 132543 66304 132543 67630 132543 67630 132544 66310 132544 67624 132544 66312 132545 66310 132545 67630 132545 66307 132546 66312 132546 67630 132546 66322 132547 67623 132547 66323 132547 66323 132548 67623 132548 66313 132548 66323 132549 66313 132549 66314 132549 66314 132550 66313 132550 67073 132550 66314 132551 67073 132551 66315 132551 66315 132552 67073 132552 66317 132552 66315 132553 66317 132553 66316 132553 66316 132554 66317 132554 66318 132554 66316 132555 66318 132555 66326 132555 66326 132556 66318 132556 66319 132556 66326 132557 66319 132557 66320 132557 66320 132558 66319 132558 67067 132558 66320 132559 67067 132559 67610 132559 67610 132560 67067 132560 67066 132560 66328 132561 66322 132561 66321 132561 66321 132562 66322 132562 66323 132562 66321 132563 66323 132563 66324 132563 66324 132564 66323 132564 66314 132564 66324 132565 66314 132565 66329 132565 66329 132566 66314 132566 66315 132566 66329 132567 66315 132567 66332 132567 66332 132568 66315 132568 66316 132568 66332 132569 66316 132569 66325 132569 66325 132570 66316 132570 66326 132570 66325 132571 66326 132571 66327 132571 66327 132572 66326 132572 66320 132572 66327 132573 66320 132573 66330 132573 66330 132574 66320 132574 67610 132574 66331 132575 66328 132575 66321 132575 66331 132576 66329 132576 66332 132576 66324 132577 66329 132577 66331 132577 66321 132578 66324 132578 66331 132578 66331 132579 66327 132579 66330 132579 66325 132580 66327 132580 66331 132580 66332 132581 66325 132581 66331 132581 67602 132582 67052 132582 66333 132582 66333 132583 67052 132583 66334 132583 66333 132584 66334 132584 66335 132584 66335 132585 66334 132585 67051 132585 66335 132586 67051 132586 66336 132586 66336 132587 67051 132587 66337 132587 66336 132588 66337 132588 66345 132588 66345 132589 66337 132589 67038 132589 66345 132590 67038 132590 66338 132590 66338 132591 67038 132591 66339 132591 66338 132592 66339 132592 66347 132592 66347 132593 66339 132593 67040 132593 66347 132594 67040 132594 67603 132594 67603 132595 67040 132595 67037 132595 66340 132596 67602 132596 66341 132596 66341 132597 67602 132597 66333 132597 66341 132598 66333 132598 66342 132598 66342 132599 66333 132599 66335 132599 66342 132600 66335 132600 66343 132600 66343 132601 66335 132601 66336 132601 66343 132602 66336 132602 66344 132602 66344 132603 66336 132603 66345 132603 66344 132604 66345 132604 66346 132604 66346 132605 66345 132605 66338 132605 66346 132606 66338 132606 66348 132606 66348 132607 66338 132607 66347 132607 66348 132608 66347 132608 66349 132608 66349 132609 66347 132609 67603 132609 66350 132610 66340 132610 66341 132610 66350 132611 66343 132611 66344 132611 66342 132612 66343 132612 66350 132612 66341 132613 66342 132613 66350 132613 66350 132614 66348 132614 66349 132614 66346 132615 66348 132615 66350 132615 66344 132616 66346 132616 66350 132616 66351 132617 66413 132617 66352 132617 66352 132618 66413 132618 66414 132618 66353 132619 66728 132619 66405 132619 66405 132620 66728 132620 66402 132620 66418 132621 66421 132621 66422 132621 66354 132622 66407 132622 66404 132622 66396 132623 66359 132623 66397 132623 66993 132624 67562 132624 67563 132624 66355 132625 66993 132625 66420 132625 67000 132626 66998 132626 66367 132626 66357 132627 66360 132627 66378 132627 66356 132628 67004 132628 66387 132628 66357 132629 66359 132629 66358 132629 66358 132630 66359 132630 66396 132630 66358 132631 66396 132631 67002 132631 66378 132632 66360 132632 66361 132632 66361 132633 66360 132633 66362 132633 66361 132634 66362 132634 66363 132634 66363 132635 66362 132635 66364 132635 66363 132636 66364 132636 66381 132636 66381 132637 66364 132637 67001 132637 66381 132638 67001 132638 66382 132638 67000 132639 66407 132639 66365 132639 66365 132640 66407 132640 66354 132640 66365 132641 66354 132641 66366 132641 66367 132642 66998 132642 66368 132642 66368 132643 66998 132643 66997 132643 66368 132644 66997 132644 66384 132644 66384 132645 66997 132645 66369 132645 66384 132646 66369 132646 66370 132646 66370 132647 66369 132647 66371 132647 66370 132648 66371 132648 66417 132648 66355 132649 66421 132649 66372 132649 66372 132650 66421 132650 66418 132650 66372 132651 66418 132651 66996 132651 66373 132652 66390 132652 66375 132652 67004 132653 66374 132653 66375 132653 66375 132654 66374 132654 66395 132654 66375 132655 66395 132655 66373 132655 66373 132656 66395 132656 66376 132656 66373 132657 66376 132657 66393 132657 66393 132658 66376 132658 66735 132658 66377 132659 66378 132659 66379 132659 66379 132660 66378 132660 66361 132660 66379 132661 66361 132661 66400 132661 66400 132662 66361 132662 66363 132662 66400 132663 66363 132663 66380 132663 66380 132664 66363 132664 66381 132664 66380 132665 66381 132665 66402 132665 66402 132666 66381 132666 66382 132666 66402 132667 66382 132667 66405 132667 66412 132668 66367 132668 66383 132668 66383 132669 66367 132669 66368 132669 66383 132670 66368 132670 66409 132670 66409 132671 66368 132671 66384 132671 66409 132672 66384 132672 66385 132672 66385 132673 66384 132673 66370 132673 66385 132674 66370 132674 66414 132674 66414 132675 66370 132675 66417 132675 66414 132676 66417 132676 66352 132676 66356 132677 66387 132677 66386 132677 66386 132678 66387 132678 66388 132678 66386 132679 66388 132679 67594 132679 67594 132680 66388 132680 66392 132680 67594 132681 66392 132681 66389 132681 67004 132682 66375 132682 66387 132682 66387 132683 66375 132683 66390 132683 66387 132684 66390 132684 66388 132684 66388 132685 66390 132685 66391 132685 66388 132686 66391 132686 66392 132686 66393 132687 66737 132687 66373 132687 66373 132688 66737 132688 66394 132688 66373 132689 66394 132689 66390 132689 66390 132690 66394 132690 66738 132690 66390 132691 66738 132691 66391 132691 66374 132692 67002 132692 66395 132692 66395 132693 67002 132693 66396 132693 66395 132694 66396 132694 66376 132694 66376 132695 66396 132695 66397 132695 66376 132696 66397 132696 66735 132696 66735 132697 66397 132697 66398 132697 66357 132698 66378 132698 66359 132698 66359 132699 66378 132699 66377 132699 66359 132700 66377 132700 66397 132700 66397 132701 66377 132701 66736 132701 66397 132702 66736 132702 66398 132702 66380 132703 66399 132703 66400 132703 66400 132704 66399 132704 66732 132704 66400 132705 66732 132705 66379 132705 66379 132706 66732 132706 66734 132706 66379 132707 66734 132707 66377 132707 66377 132708 66734 132708 66733 132708 66377 132709 66733 132709 66736 132709 66728 132710 66401 132710 66402 132710 66402 132711 66401 132711 66403 132711 66402 132712 66403 132712 66380 132712 66380 132713 66403 132713 66729 132713 66380 132714 66729 132714 66399 132714 67001 132715 66366 132715 66382 132715 66382 132716 66366 132716 66354 132716 66382 132717 66354 132717 66405 132717 66405 132718 66354 132718 66404 132718 66405 132719 66404 132719 66353 132719 66353 132720 66404 132720 66406 132720 67000 132721 66367 132721 66407 132721 66407 132722 66367 132722 66412 132722 66407 132723 66412 132723 66404 132723 66404 132724 66412 132724 66726 132724 66404 132725 66726 132725 66406 132725 66385 132726 66408 132726 66409 132726 66409 132727 66408 132727 66410 132727 66409 132728 66410 132728 66383 132728 66383 132729 66410 132729 66411 132729 66383 132730 66411 132730 66412 132730 66412 132731 66411 132731 66725 132731 66412 132732 66725 132732 66726 132732 66413 132733 66415 132733 66414 132733 66414 132734 66415 132734 66416 132734 66414 132735 66416 132735 66385 132735 66385 132736 66416 132736 66723 132736 66385 132737 66723 132737 66408 132737 66371 132738 66996 132738 66417 132738 66417 132739 66996 132739 66418 132739 66417 132740 66418 132740 66352 132740 66352 132741 66418 132741 66422 132741 66352 132742 66422 132742 66351 132742 66351 132743 66422 132743 66721 132743 66419 132744 66722 132744 66423 132744 66355 132745 66420 132745 66421 132745 66421 132746 66420 132746 66419 132746 66421 132747 66419 132747 66422 132747 66422 132748 66419 132748 66423 132748 66422 132749 66423 132749 66721 132749 66993 132750 67563 132750 66420 132750 66420 132751 67563 132751 67565 132751 66420 132752 67565 132752 66419 132752 66419 132753 67565 132753 66719 132753 66419 132754 66719 132754 66722 132754 67008 132755 66622 132755 66621 132755 67008 132756 66621 132756 67006 132756 67006 132757 66621 132757 66619 132757 67006 132758 66619 132758 67017 132758 67017 132759 66619 132759 66425 132759 67017 132760 66425 132760 66424 132760 66424 132761 66425 132761 66426 132761 66424 132762 66426 132762 67014 132762 67014 132763 66426 132763 66618 132763 67014 132764 66618 132764 67011 132764 67011 132765 66618 132765 66617 132765 67011 132766 66617 132766 67010 132766 67010 132767 66617 132767 66611 132767 67010 132768 66611 132768 66427 132768 66427 132769 66611 132769 66429 132769 66427 132770 66429 132770 66428 132770 66428 132771 66429 132771 66430 132771 66428 132772 66430 132772 67025 132772 67025 132773 66430 132773 66625 132773 67025 132774 66625 132774 66431 132774 66431 132775 66625 132775 66627 132775 66431 132776 66627 132776 66432 132776 66432 132777 66627 132777 66433 132777 66432 132778 66433 132778 67020 132778 67020 132779 66433 132779 66630 132779 67020 132780 66630 132780 67019 132780 67019 132781 66630 132781 66434 132781 67019 132782 66434 132782 67018 132782 67018 132783 66434 132783 66435 132783 67018 132784 66435 132784 67005 132784 66436 132785 67510 132785 66437 132785 66437 132786 67510 132786 66974 132786 67457 132787 66438 132787 66446 132787 66446 132788 66438 132788 66844 132788 66446 132789 66844 132789 66447 132789 66447 132790 66844 132790 66849 132790 66447 132791 66849 132791 66439 132791 66439 132792 66849 132792 66440 132792 66439 132793 66440 132793 66441 132793 66441 132794 66440 132794 66442 132794 66441 132795 66442 132795 66450 132795 66450 132796 66442 132796 66443 132796 66450 132797 66443 132797 67458 132797 67458 132798 66443 132798 66850 132798 66444 132799 67457 132799 66445 132799 66445 132800 67457 132800 66446 132800 66445 132801 66446 132801 66453 132801 66453 132802 66446 132802 66447 132802 66453 132803 66447 132803 66448 132803 66448 132804 66447 132804 66439 132804 66448 132805 66439 132805 66449 132805 66449 132806 66439 132806 66441 132806 66449 132807 66441 132807 66451 132807 66451 132808 66441 132808 66450 132808 66451 132809 66450 132809 67451 132809 67451 132810 66450 132810 67458 132810 67451 132811 67450 132811 66451 132811 66451 132812 67450 132812 66452 132812 66451 132813 66452 132813 66449 132813 66449 132814 66452 132814 70921 132814 66449 132815 70921 132815 66448 132815 66448 132816 70921 132816 70918 132816 66448 132817 70918 132817 66453 132817 66453 132818 70918 132818 70917 132818 66453 132819 70917 132819 66445 132819 66445 132820 70917 132820 70916 132820 66445 132821 70916 132821 66444 132821 66444 132822 70916 132822 70915 132822 67445 132823 66454 132823 66459 132823 66459 132824 66454 132824 66838 132824 66459 132825 66838 132825 66461 132825 66461 132826 66838 132826 66834 132826 66461 132827 66834 132827 66462 132827 66462 132828 66834 132828 66455 132828 66462 132829 66455 132829 66464 132829 66464 132830 66455 132830 66836 132830 66464 132831 66836 132831 66456 132831 66456 132832 66836 132832 66457 132832 66456 132833 66457 132833 66466 132833 66466 132834 66457 132834 66832 132834 67440 132835 67445 132835 66458 132835 66458 132836 67445 132836 66459 132836 66458 132837 66459 132837 66468 132837 66468 132838 66459 132838 66461 132838 66468 132839 66461 132839 66460 132839 66460 132840 66461 132840 66462 132840 66460 132841 66462 132841 66463 132841 66463 132842 66462 132842 66464 132842 66463 132843 66464 132843 66465 132843 66465 132844 66464 132844 66456 132844 66465 132845 66456 132845 67433 132845 67433 132846 66456 132846 66466 132846 67433 132847 70944 132847 66465 132847 66465 132848 70944 132848 70943 132848 66465 132849 70943 132849 66463 132849 66463 132850 70943 132850 66467 132850 66463 132851 66467 132851 66460 132851 66460 132852 66467 132852 70940 132852 66460 132853 70940 132853 66468 132853 66468 132854 70940 132854 70938 132854 66468 132855 70938 132855 66458 132855 66458 132856 70938 132856 70937 132856 66458 132857 70937 132857 67440 132857 67440 132858 70937 132858 70935 132858 66473 132859 66819 132859 66475 132859 66475 132860 66819 132860 66818 132860 66475 132861 66818 132861 66469 132861 66469 132862 66818 132862 66817 132862 66469 132863 66817 132863 66470 132863 66470 132864 66817 132864 66825 132864 66470 132865 66825 132865 66476 132865 66476 132866 66825 132866 66826 132866 66476 132867 66826 132867 66471 132867 66471 132868 66826 132868 66814 132868 66471 132869 66814 132869 66472 132869 66472 132870 66814 132870 67422 132870 67421 132871 66473 132871 66484 132871 66484 132872 66473 132872 66475 132872 66484 132873 66475 132873 66474 132873 66474 132874 66475 132874 66469 132874 66474 132875 66469 132875 66481 132875 66481 132876 66469 132876 66470 132876 66481 132877 66470 132877 66477 132877 66477 132878 66470 132878 66476 132878 66477 132879 66476 132879 66478 132879 66478 132880 66476 132880 66471 132880 66478 132881 66471 132881 67415 132881 67415 132882 66471 132882 66472 132882 67415 132883 70962 132883 66478 132883 66478 132884 70962 132884 66479 132884 66478 132885 66479 132885 66477 132885 66477 132886 66479 132886 66480 132886 66477 132887 66480 132887 66481 132887 66481 132888 66480 132888 66482 132888 66481 132889 66482 132889 66474 132889 66474 132890 66482 132890 66483 132890 66474 132891 66483 132891 66484 132891 66484 132892 66483 132892 70966 132892 66484 132893 70966 132893 67421 132893 67421 132894 70966 132894 67409 132894 67404 132895 66485 132895 66492 132895 66492 132896 66485 132896 66811 132896 66492 132897 66811 132897 66493 132897 66493 132898 66811 132898 66810 132898 66493 132899 66810 132899 66486 132899 66486 132900 66810 132900 66809 132900 66486 132901 66809 132901 66487 132901 66487 132902 66809 132902 66808 132902 66487 132903 66808 132903 66488 132903 66488 132904 66808 132904 66489 132904 66488 132905 66489 132905 66490 132905 66490 132906 66489 132906 66807 132906 66491 132907 67404 132907 66499 132907 66499 132908 67404 132908 66492 132908 66499 132909 66492 132909 66494 132909 66494 132910 66492 132910 66493 132910 66494 132911 66493 132911 66495 132911 66495 132912 66493 132912 66486 132912 66495 132913 66486 132913 66497 132913 66497 132914 66486 132914 66487 132914 66497 132915 66487 132915 66496 132915 66496 132916 66487 132916 66488 132916 66496 132917 66488 132917 67397 132917 67397 132918 66488 132918 66490 132918 67397 132919 70980 132919 66496 132919 66496 132920 70980 132920 70978 132920 66496 132921 70978 132921 66497 132921 66497 132922 70978 132922 66498 132922 66497 132923 66498 132923 66495 132923 66495 132924 66498 132924 70990 132924 66495 132925 70990 132925 66494 132925 66494 132926 70990 132926 70989 132926 66494 132927 70989 132927 66499 132927 66499 132928 70989 132928 70987 132928 66499 132929 70987 132929 66491 132929 66491 132930 70987 132930 66500 132930 66501 132931 66502 132931 66509 132931 66509 132932 66502 132932 66801 132932 66509 132933 66801 132933 66503 132933 66503 132934 66801 132934 66504 132934 66503 132935 66504 132935 66512 132935 66512 132936 66504 132936 66505 132936 66512 132937 66505 132937 66513 132937 66513 132938 66505 132938 66507 132938 66513 132939 66507 132939 66506 132939 66506 132940 66507 132940 66795 132940 66506 132941 66795 132941 67389 132941 67389 132942 66795 132942 66508 132942 67376 132943 66501 132943 66518 132943 66518 132944 66501 132944 66509 132944 66518 132945 66509 132945 66510 132945 66510 132946 66509 132946 66503 132946 66510 132947 66503 132947 66511 132947 66511 132948 66503 132948 66512 132948 66511 132949 66512 132949 66516 132949 66516 132950 66512 132950 66513 132950 66516 132951 66513 132951 66514 132951 66514 132952 66513 132952 66506 132952 66514 132953 66506 132953 67382 132953 67382 132954 66506 132954 67389 132954 67382 132955 67383 132955 66514 132955 66514 132956 67383 132956 66515 132956 66514 132957 66515 132957 66516 132957 66516 132958 66515 132958 71002 132958 66516 132959 71002 132959 66511 132959 66511 132960 71002 132960 66517 132960 66511 132961 66517 132961 66510 132961 66510 132962 66517 132962 71010 132962 66510 132963 71010 132963 66518 132963 66518 132964 71010 132964 66519 132964 66518 132965 66519 132965 67376 132965 67376 132966 66519 132966 67378 132966 66520 132967 66521 132967 66522 132967 66522 132968 66521 132968 66775 132968 66522 132969 66775 132969 66523 132969 66523 132970 66775 132970 66786 132970 66523 132971 66786 132971 66524 132971 66524 132972 66786 132972 66785 132972 66524 132973 66785 132973 66525 132973 66525 132974 66785 132974 66783 132974 66525 132975 66783 132975 66526 132975 66526 132976 66783 132976 66782 132976 66526 132977 66782 132977 66527 132977 66527 132978 66782 132978 66781 132978 66533 132979 66520 132979 66532 132979 66532 132980 66520 132980 66522 132980 66532 132981 66522 132981 66528 132981 66528 132982 66522 132982 66523 132982 66528 132983 66523 132983 66531 132983 66531 132984 66523 132984 66524 132984 66531 132985 66524 132985 66530 132985 66530 132986 66524 132986 66525 132986 66530 132987 66525 132987 66529 132987 66529 132988 66525 132988 66526 132988 66529 132989 66526 132989 67367 132989 67367 132990 66526 132990 66527 132990 67367 132991 71033 132991 66529 132991 66529 132992 71033 132992 71031 132992 66529 132993 71031 132993 66530 132993 66530 132994 71031 132994 71029 132994 66530 132995 71029 132995 66531 132995 66531 132996 71029 132996 71028 132996 66531 132997 71028 132997 66528 132997 66528 132998 71028 132998 71026 132998 66528 132999 71026 132999 66532 132999 66532 133000 71026 133000 71024 133000 66532 133001 71024 133001 66533 133001 66533 133002 71024 133002 71023 133002 66540 133003 66768 133003 66542 133003 66542 133004 66768 133004 66534 133004 66542 133005 66534 133005 66535 133005 66535 133006 66534 133006 66767 133006 66535 133007 66767 133007 66544 133007 66544 133008 66767 133008 66537 133008 66544 133009 66537 133009 66536 133009 66536 133010 66537 133010 66538 133010 66536 133011 66538 133011 66546 133011 66546 133012 66538 133012 66539 133012 66546 133013 66539 133013 66547 133013 66547 133014 66539 133014 67354 133014 66552 133015 66540 133015 66541 133015 66541 133016 66540 133016 66542 133016 66541 133017 66542 133017 66550 133017 66550 133018 66542 133018 66535 133018 66550 133019 66535 133019 66543 133019 66543 133020 66535 133020 66544 133020 66543 133021 66544 133021 66549 133021 66549 133022 66544 133022 66536 133022 66549 133023 66536 133023 66545 133023 66545 133024 66536 133024 66546 133024 66545 133025 66546 133025 67348 133025 67348 133026 66546 133026 66547 133026 67348 133027 67349 133027 66545 133027 66545 133028 67349 133028 71051 133028 66545 133029 71051 133029 66549 133029 66549 133030 71051 133030 66548 133030 66549 133031 66548 133031 66543 133031 66543 133032 66548 133032 71049 133032 66543 133033 71049 133033 66550 133033 66550 133034 71049 133034 66551 133034 66550 133035 66551 133035 66541 133035 66541 133036 66551 133036 71046 133036 66541 133037 71046 133037 66552 133037 66552 133038 71046 133038 71055 133038 66553 133039 66555 133039 66554 133039 66554 133040 66555 133040 66750 133040 66554 133041 66750 133041 66556 133041 66556 133042 66750 133042 66759 133042 66556 133043 66759 133043 66557 133043 66557 133044 66759 133044 66558 133044 66557 133045 66558 133045 66563 133045 66563 133046 66558 133046 66762 133046 66563 133047 66762 133047 66564 133047 66564 133048 66762 133048 66754 133048 66564 133049 66754 133049 66565 133049 66565 133050 66754 133050 66753 133050 66559 133051 66553 133051 66560 133051 66560 133052 66553 133052 66554 133052 66560 133053 66554 133053 66561 133053 66561 133054 66554 133054 66556 133054 66561 133055 66556 133055 66562 133055 66562 133056 66556 133056 66557 133056 66562 133057 66557 133057 66568 133057 66568 133058 66557 133058 66563 133058 66568 133059 66563 133059 66567 133059 66567 133060 66563 133060 66564 133060 66567 133061 66564 133061 67330 133061 67330 133062 66564 133062 66565 133062 67330 133063 71065 133063 66567 133063 66567 133064 71065 133064 66566 133064 66567 133065 66566 133065 66568 133065 66568 133066 66566 133066 71064 133066 66568 133067 71064 133067 66562 133067 66562 133068 71064 133068 71077 133068 66562 133069 71077 133069 66561 133069 66561 133070 71077 133070 71076 133070 66561 133071 71076 133071 66560 133071 66560 133072 71076 133072 66569 133072 66560 133073 66569 133073 66559 133073 66559 133074 66569 133074 71074 133074 67324 133075 66947 133075 66574 133075 66574 133076 66947 133076 66945 133076 66574 133077 66945 133077 66576 133077 66576 133078 66945 133078 66570 133078 66576 133079 66570 133079 66571 133079 66571 133080 66570 133080 66941 133080 66571 133081 66941 133081 66572 133081 66572 133082 66941 133082 66940 133082 66572 133083 66940 133083 66578 133083 66578 133084 66940 133084 66573 133084 66578 133085 66573 133085 67311 133085 67311 133086 66573 133086 66936 133086 67308 133087 67324 133087 66584 133087 66584 133088 67324 133088 66574 133088 66584 133089 66574 133089 66575 133089 66575 133090 66574 133090 66576 133090 66575 133091 66576 133091 66577 133091 66577 133092 66576 133092 66571 133092 66577 133093 66571 133093 66581 133093 66581 133094 66571 133094 66572 133094 66581 133095 66572 133095 66580 133095 66580 133096 66572 133096 66578 133096 66580 133097 66578 133097 66579 133097 66579 133098 66578 133098 67311 133098 66579 133099 71098 133099 66580 133099 66580 133100 71098 133100 71096 133100 66580 133101 71096 133101 66581 133101 66581 133102 71096 133102 66582 133102 66581 133103 66582 133103 66577 133103 66577 133104 66582 133104 66583 133104 66577 133105 66583 133105 66575 133105 66575 133106 66583 133106 71094 133106 66575 133107 71094 133107 66584 133107 66584 133108 71094 133108 71093 133108 66584 133109 71093 133109 67308 133109 67308 133110 71093 133110 66585 133110 66593 133111 66856 133111 66594 133111 66594 133112 66856 133112 66587 133112 66594 133113 66587 133113 66586 133113 66586 133114 66587 133114 66588 133114 66586 133115 66588 133115 66589 133115 66589 133116 66588 133116 66855 133116 66589 133117 66855 133117 66598 133117 66598 133118 66855 133118 66590 133118 66598 133119 66590 133119 66591 133119 66591 133120 66590 133120 66864 133120 66591 133121 66864 133121 66592 133121 66592 133122 66864 133122 67303 133122 67302 133123 66593 133123 66595 133123 66595 133124 66593 133124 66594 133124 66595 133125 66594 133125 66602 133125 66602 133126 66594 133126 66586 133126 66602 133127 66586 133127 66596 133127 66596 133128 66586 133128 66589 133128 66596 133129 66589 133129 66600 133129 66600 133130 66589 133130 66598 133130 66600 133131 66598 133131 66597 133131 66597 133132 66598 133132 66591 133132 66597 133133 66591 133133 67295 133133 67295 133134 66591 133134 66592 133134 67295 133135 71110 133135 66597 133135 66597 133136 71110 133136 66599 133136 66597 133137 66599 133137 66600 133137 66600 133138 66599 133138 66601 133138 66600 133139 66601 133139 66596 133139 66596 133140 66601 133140 66603 133140 66596 133141 66603 133141 66602 133141 66602 133142 66603 133142 71108 133142 66602 133143 71108 133143 66595 133143 66595 133144 71108 133144 66604 133144 66595 133145 66604 133145 67302 133145 67302 133146 66604 133146 67290 133146 67750 133147 66609 133147 66429 133147 66625 133148 66430 133148 66608 133148 66608 133149 66430 133149 66605 133149 67778 133150 66606 133150 66608 133150 66608 133151 66606 133151 66607 133151 66608 133152 66607 133152 66625 133152 66609 133153 67109 133153 66429 133153 66429 133154 67109 133154 66610 133154 66429 133155 66610 133155 66430 133155 66430 133156 66610 133156 67730 133156 66430 133157 67730 133157 66605 133157 66613 133158 66611 133158 66612 133158 66612 133159 66611 133159 66617 133159 66612 133160 66617 133160 67734 133160 67750 133161 66429 133161 66718 133161 66718 133162 66429 133162 66611 133162 66718 133163 66611 133163 67760 133163 67760 133164 66611 133164 66613 133164 67760 133165 66613 133165 67115 133165 66716 133166 66614 133166 67183 133166 67183 133167 66614 133167 66615 133167 67183 133168 66615 133168 66616 133168 67734 133169 66617 133169 67183 133169 67183 133170 66617 133170 66618 133170 67183 133171 66618 133171 66716 133171 66716 133172 66618 133172 66426 133172 66716 133173 66426 133173 66715 133173 66715 133174 66426 133174 66425 133174 66715 133175 66425 133175 66713 133175 66713 133176 66425 133176 66619 133176 66713 133177 66619 133177 66620 133177 66620 133178 66619 133178 66621 133178 66620 133179 66621 133179 66711 133179 66711 133180 66621 133180 66622 133180 66711 133181 66622 133181 66623 133181 66607 133182 66624 133182 66625 133182 66625 133183 66624 133183 66626 133183 66625 133184 66626 133184 66627 133184 66627 133185 66626 133185 66628 133185 66627 133186 66628 133186 66433 133186 66433 133187 66628 133187 66629 133187 66433 133188 66629 133188 66630 133188 66630 133189 66629 133189 66692 133189 66630 133190 66692 133190 66434 133190 66434 133191 66692 133191 66631 133191 66434 133192 66631 133192 66435 133192 66632 133193 67675 133193 66634 133193 66632 133194 66634 133194 66633 133194 66633 133195 66634 133195 66636 133195 66633 133196 66636 133196 66635 133196 66635 133197 66636 133197 66954 133197 66635 133198 66954 133198 67678 133198 67678 133199 66954 133199 66966 133199 67678 133200 66966 133200 66637 133200 66637 133201 66966 133201 66638 133201 66637 133202 66638 133202 67503 133202 66659 133203 66658 133203 67772 133203 66659 133204 67772 133204 66639 133204 66639 133205 67772 133205 66641 133205 66639 133206 66641 133206 66640 133206 66640 133207 66641 133207 66642 133207 66640 133208 66642 133208 66279 133208 66279 133209 66642 133209 67770 133209 66279 133210 67770 133210 66643 133210 66643 133211 67770 133211 67775 133211 66643 133212 67775 133212 66280 133212 66917 133213 66916 133213 66270 133213 66917 133214 66270 133214 66281 133214 66281 133215 66270 133215 66268 133215 66281 133216 66268 133216 66644 133216 66644 133217 66268 133217 66266 133217 66644 133218 66266 133218 66645 133218 66645 133219 66266 133219 66646 133219 66645 133220 66646 133220 66647 133220 66647 133221 66646 133221 66264 133221 66647 133222 66264 133222 66648 133222 66648 133223 66264 133223 66263 133223 66648 133224 66263 133224 66291 133224 66291 133225 66263 133225 66261 133225 66291 133226 66261 133226 66290 133226 66290 133227 66261 133227 66649 133227 66290 133228 66649 133228 66650 133228 66650 133229 66649 133229 66258 133229 66650 133230 66258 133230 66651 133230 66651 133231 66258 133231 66652 133231 66651 133232 66652 133232 66286 133232 66286 133233 66652 133233 66255 133233 66286 133234 66255 133234 66653 133234 66653 133235 66255 133235 66655 133235 66653 133236 66655 133236 66654 133236 66654 133237 66655 133237 66253 133237 66654 133238 66253 133238 66292 133238 66292 133239 66253 133239 66656 133239 66292 133240 66656 133240 66294 133240 66294 133241 66656 133241 66251 133241 66294 133242 66251 133242 66657 133242 66657 133243 66251 133243 66658 133243 66657 133244 66658 133244 66659 133244 66389 133245 66740 133245 66660 133245 66660 133246 66740 133246 66898 133246 66660 133247 66898 133247 66661 133247 66661 133248 66898 133248 66662 133248 66662 133249 66898 133249 66663 133249 66662 133250 66663 133250 66664 133250 66665 133251 67588 133251 66663 133251 66663 133252 67588 133252 67533 133252 66663 133253 67533 133253 66664 133253 66878 133254 66666 133254 66665 133254 66665 133255 66666 133255 67589 133255 66665 133256 67589 133256 67588 133256 66877 133257 66667 133257 66878 133257 66878 133258 66667 133258 66668 133258 66878 133259 66668 133259 66666 133259 66673 133260 66674 133260 66877 133260 66877 133261 66674 133261 66669 133261 66877 133262 66669 133262 66667 133262 66670 133263 67534 133263 66671 133263 66671 133264 67534 133264 66672 133264 66671 133265 66672 133265 66673 133265 66673 133266 66672 133266 67585 133266 66673 133267 67585 133267 66674 133267 66670 133268 66671 133268 66675 133268 66675 133269 66671 133269 66881 133269 66675 133270 66881 133270 66676 133270 66676 133271 66881 133271 66677 133271 66677 133272 66881 133272 66680 133272 66677 133273 66680 133273 66678 133273 66678 133274 66680 133274 66679 133274 66679 133275 66680 133275 66681 133275 66679 133276 66681 133276 66682 133276 66682 133277 66681 133277 66683 133277 66683 133278 66681 133278 66884 133278 66683 133279 66884 133279 66684 133279 66684 133280 66884 133280 66685 133280 66685 133281 66884 133281 66686 133281 66685 133282 66686 133282 66687 133282 66887 133283 67571 133283 67570 133283 66887 133284 67570 133284 66686 133284 66686 133285 67570 133285 66688 133285 66686 133286 66688 133286 66687 133286 67571 133287 66887 133287 66689 133287 66689 133288 66887 133288 66909 133288 66689 133289 66909 133289 67569 133289 67569 133290 66909 133290 67566 133290 67566 133291 66909 133291 66890 133291 67566 133292 66890 133292 66719 133292 66607 133293 66690 133293 66624 133293 66624 133294 66690 133294 66691 133294 66624 133295 66691 133295 66626 133295 66626 133296 66691 133296 68390 133296 66626 133297 68390 133297 66628 133297 66628 133298 68390 133298 68388 133298 66628 133299 68388 133299 66629 133299 66629 133300 68388 133300 68387 133300 66629 133301 68387 133301 66692 133301 66692 133302 68387 133302 66693 133302 66692 133303 66693 133303 66631 133303 66631 133304 66693 133304 66694 133304 66631 133305 66694 133305 66990 133305 66990 133306 66694 133306 66695 133306 66990 133307 66695 133307 66696 133307 66696 133308 66695 133308 65945 133308 66696 133309 65945 133309 66697 133309 66697 133310 65945 133310 66698 133310 66697 133311 66698 133311 66699 133311 66699 133312 66698 133312 66700 133312 66699 133313 66700 133313 66701 133313 66701 133314 66700 133314 65943 133314 66701 133315 65943 133315 66702 133315 66702 133316 65943 133316 65940 133316 66702 133317 65940 133317 66988 133317 66988 133318 65940 133318 66703 133318 66988 133319 66703 133319 66986 133319 66986 133320 66703 133320 66704 133320 66986 133321 66704 133321 66705 133321 66705 133322 66704 133322 65939 133322 66705 133323 65939 133323 66985 133323 66985 133324 65939 133324 66706 133324 66985 133325 66706 133325 66982 133325 66982 133326 66706 133326 65937 133326 66982 133327 65937 133327 66707 133327 66707 133328 65937 133328 65935 133328 66707 133329 65935 133329 66709 133329 66709 133330 65935 133330 66708 133330 66709 133331 66708 133331 66980 133331 66980 133332 66708 133332 65934 133332 66980 133333 65934 133333 66623 133333 66623 133334 65934 133334 66710 133334 66623 133335 66710 133335 66711 133335 66711 133336 66710 133336 66712 133336 66711 133337 66712 133337 66620 133337 66620 133338 66712 133338 68379 133338 66620 133339 68379 133339 66713 133339 66713 133340 68379 133340 66714 133340 66713 133341 66714 133341 66715 133341 66715 133342 66714 133342 68375 133342 66715 133343 68375 133343 66716 133343 66716 133344 68375 133344 68382 133344 66716 133345 68382 133345 66614 133345 66614 133346 68382 133346 67761 133346 66717 133347 67750 133347 70866 133347 70866 133348 67750 133348 66718 133348 66719 133349 66890 133349 66722 133349 66722 133350 66890 133350 66889 133350 66413 133351 66351 133351 66720 133351 66720 133352 66351 133352 66721 133352 66720 133353 66721 133353 66889 133353 66889 133354 66721 133354 66423 133354 66889 133355 66423 133355 66722 133355 66413 133356 66720 133356 66415 133356 66415 133357 66720 133357 66888 133357 66415 133358 66888 133358 66416 133358 66416 133359 66888 133359 66723 133359 66723 133360 66888 133360 66724 133360 66723 133361 66724 133361 66408 133361 66408 133362 66724 133362 66410 133362 66410 133363 66724 133363 66892 133363 66410 133364 66892 133364 66411 133364 66411 133365 66892 133365 66725 133365 66725 133366 66892 133366 66894 133366 66725 133367 66894 133367 66726 133367 66726 133368 66894 133368 66406 133368 66406 133369 66894 133369 66727 133369 66406 133370 66727 133370 66353 133370 66730 133371 66401 133371 66727 133371 66727 133372 66401 133372 66728 133372 66727 133373 66728 133373 66353 133373 66731 133374 66729 133374 66730 133374 66730 133375 66729 133375 66403 133375 66730 133376 66403 133376 66401 133376 66882 133377 66732 133377 66731 133377 66731 133378 66732 133378 66399 133378 66731 133379 66399 133379 66729 133379 66900 133380 66733 133380 66882 133380 66882 133381 66733 133381 66734 133381 66882 133382 66734 133382 66732 133382 66393 133383 66735 133383 66901 133383 66901 133384 66735 133384 66398 133384 66901 133385 66398 133385 66900 133385 66900 133386 66398 133386 66736 133386 66900 133387 66736 133387 66733 133387 66393 133388 66901 133388 66737 133388 66737 133389 66901 133389 66902 133389 66737 133390 66902 133390 66394 133390 66394 133391 66902 133391 66738 133391 66738 133392 66902 133392 66739 133392 66738 133393 66739 133393 66391 133393 66391 133394 66739 133394 66392 133394 66392 133395 66739 133395 66740 133395 66392 133396 66740 133396 66389 133396 67709 133397 66793 133397 66741 133397 66854 133398 66742 133398 67679 133398 66743 133399 66828 133399 66827 133399 66797 133400 66744 133400 66293 133400 66784 133401 66793 133401 66745 133401 66746 133402 66757 133402 67336 133402 66772 133403 66746 133403 66771 133403 66771 133404 66746 133404 66271 133404 66771 133405 66271 133405 66747 133405 66749 133406 66748 133406 66750 133406 66750 133407 66748 133407 66759 133407 66749 133408 66750 133408 67701 133408 67701 133409 66750 133409 66555 133409 67701 133410 66555 133410 66751 133410 66751 133411 66555 133411 67700 133411 67700 133412 66555 133412 66752 133412 67700 133413 66752 133413 67699 133413 67336 133414 66753 133414 66746 133414 66746 133415 66753 133415 66754 133415 66746 133416 66754 133416 66271 133416 66271 133417 66754 133417 66762 133417 66271 133418 66762 133418 67703 133418 67699 133419 66752 133419 66755 133419 66755 133420 66752 133420 67340 133420 66755 133421 67340 133421 67696 133421 67696 133422 67340 133422 66756 133422 67696 133423 66756 133423 66757 133423 66757 133424 66756 133424 67338 133424 66757 133425 67338 133425 67336 133425 66748 133426 66758 133426 66759 133426 66759 133427 66758 133427 66760 133427 66759 133428 66760 133428 66558 133428 66558 133429 66760 133429 66761 133429 66558 133430 66761 133430 66762 133430 66762 133431 66761 133431 67704 133431 66762 133432 67704 133432 67703 133432 66539 133433 66763 133433 67354 133433 67354 133434 66763 133434 66278 133434 67354 133435 66278 133435 66764 133435 66765 133436 66779 133436 66763 133436 66766 133437 66765 133437 66537 133437 66537 133438 66765 133438 66763 133438 66537 133439 66763 133439 66538 133439 66538 133440 66763 133440 66539 133440 66537 133441 66767 133441 66766 133441 66766 133442 66767 133442 66534 133442 66766 133443 66534 133443 66275 133443 66275 133444 66534 133444 66768 133444 66275 133445 66768 133445 66769 133445 66769 133446 66768 133446 66770 133446 66769 133447 66770 133447 67358 133447 66747 133448 66769 133448 66771 133448 66771 133449 66769 133449 67358 133449 66771 133450 67358 133450 66772 133450 66772 133451 67358 133451 67357 133451 66772 133452 67357 133452 66278 133452 66278 133453 67357 133453 66773 133453 66278 133454 66773 133454 66764 133454 67375 133455 66774 133455 66780 133455 66780 133456 66774 133456 66781 133456 66780 133457 66781 133457 66295 133457 66741 133458 66793 133458 67710 133458 67706 133459 66777 133459 66765 133459 66765 133460 66777 133460 66778 133460 66786 133461 66775 133461 67707 133461 67707 133462 66775 133462 66521 133462 67707 133463 66521 133463 67706 133463 67706 133464 66521 133464 66776 133464 67706 133465 66776 133465 66777 133465 66778 133466 67375 133466 66765 133466 66765 133467 67375 133467 66780 133467 66765 133468 66780 133468 66779 133468 66779 133469 66780 133469 66296 133469 66779 133470 66296 133470 66763 133470 66781 133471 66782 133471 66295 133471 66295 133472 66782 133472 66783 133472 66295 133473 66783 133473 66784 133473 66784 133474 66783 133474 66785 133474 66784 133475 66785 133475 66793 133475 66793 133476 66785 133476 66786 133476 66793 133477 66786 133477 67710 133477 67710 133478 66786 133478 67707 133478 66787 133479 66508 133479 66788 133479 66788 133480 66508 133480 66795 133480 66788 133481 66795 133481 66796 133481 66789 133482 66798 133482 66802 133482 66502 133483 66790 133483 67714 133483 67714 133484 66790 133484 66791 133484 67714 133485 66791 133485 67713 133485 67713 133486 66791 133486 66792 133486 67713 133487 66792 133487 66794 133487 66788 133488 66745 133488 66787 133488 66787 133489 66745 133489 66793 133489 66787 133490 66793 133490 66794 133490 66794 133491 66793 133491 67709 133491 66794 133492 67709 133492 67713 133492 66795 133493 66507 133493 66796 133493 66796 133494 66507 133494 66505 133494 66796 133495 66505 133495 66797 133495 66797 133496 66505 133496 66504 133496 66797 133497 66504 133497 66744 133497 66744 133498 66504 133498 66801 133498 66802 133499 66798 133499 66799 133499 66799 133500 66798 133500 66800 133500 66799 133501 66800 133501 67086 133501 67714 133502 66789 133502 66502 133502 66502 133503 66789 133503 66802 133503 66502 133504 66802 133504 66801 133504 66801 133505 66802 133505 66803 133505 66801 133506 66803 133506 66744 133506 66744 133507 66803 133507 67031 133507 66744 133508 66828 133508 66804 133508 66804 133509 66828 133509 67407 133509 66804 133510 66805 133510 66744 133510 66744 133511 66805 133511 66806 133511 66744 133512 66806 133512 66293 133512 66293 133513 66806 133513 66807 133513 66293 133514 66807 133514 66287 133514 66807 133515 66489 133515 66287 133515 66287 133516 66489 133516 66808 133516 66287 133517 66808 133517 66288 133517 66808 133518 66809 133518 66288 133518 66288 133519 66809 133519 66810 133519 66288 133520 66810 133520 66289 133520 66289 133521 66810 133521 66811 133521 66289 133522 66811 133522 66743 133522 66743 133523 66811 133523 66485 133523 66743 133524 66485 133524 66828 133524 66828 133525 66485 133525 66812 133525 66828 133526 66812 133526 67407 133526 66285 133527 66820 133527 66837 133527 66837 133528 66820 133528 67669 133528 66837 133529 67669 133529 66813 133529 66830 133530 67422 133530 67172 133530 67172 133531 67422 133531 66814 133531 67172 133532 66814 133532 66815 133532 66825 133533 66817 133533 66816 133533 66816 133534 66817 133534 66818 133534 66816 133535 66818 133535 66284 133535 66284 133536 66818 133536 66819 133536 66284 133537 66819 133537 66820 133537 66820 133538 66819 133538 67427 133538 66820 133539 67427 133539 67669 133539 67669 133540 67427 133540 66821 133540 67669 133541 66821 133541 66822 133541 66822 133542 66821 133542 66823 133542 66822 133543 66823 133543 66824 133543 66825 133544 66816 133544 66826 133544 66826 133545 66816 133545 66827 133545 66826 133546 66827 133546 66814 133546 66814 133547 66827 133547 66828 133547 66814 133548 66828 133548 66815 133548 66823 133549 67425 133549 66824 133549 66824 133550 67425 133550 66829 133550 66824 133551 66829 133551 67662 133551 67662 133552 66829 133552 67422 133552 67662 133553 67422 133553 67664 133553 67664 133554 67422 133554 66830 133554 67664 133555 66830 133555 67665 133555 67665 133556 66830 133556 66831 133556 67665 133557 66831 133557 67085 133557 66842 133558 66832 133558 66833 133558 66833 133559 66832 133559 66457 133559 66833 133560 66457 133560 66836 133560 66834 133561 66835 133561 66455 133561 66455 133562 66835 133562 66285 133562 66455 133563 66285 133563 66836 133563 66836 133564 66285 133564 66837 133564 66836 133565 66837 133565 66833 133565 66833 133566 66837 133566 66813 133566 66834 133567 66838 133567 66835 133567 66835 133568 66838 133568 66454 133568 66835 133569 66454 133569 66282 133569 66282 133570 66454 133570 66839 133570 66282 133571 66839 133571 66283 133571 66283 133572 66839 133572 67444 133572 66283 133573 67444 133573 66840 133573 66840 133574 67444 133574 66841 133574 66840 133575 66841 133575 67673 133575 67673 133576 66841 133576 67443 133576 67673 133577 67443 133577 66842 133577 66842 133578 67443 133578 66843 133578 66842 133579 66843 133579 66832 133579 66845 133580 66844 133580 66438 133580 66845 133581 66438 133581 67694 133581 66438 133582 67464 133582 67694 133582 67694 133583 67464 133583 66846 133583 67694 133584 66846 133584 66847 133584 67679 133585 66742 133585 66848 133585 66844 133586 66845 133586 66849 133586 66849 133587 66845 133587 66283 133587 66849 133588 66283 133588 66440 133588 66440 133589 66283 133589 66840 133589 66440 133590 66840 133590 67676 133590 67462 133591 67460 133591 66742 133591 66742 133592 67460 133592 67459 133592 66742 133593 67459 133593 66848 133593 66848 133594 67459 133594 66850 133594 66848 133595 66850 133595 67677 133595 67677 133596 66850 133596 66443 133596 67677 133597 66443 133597 67676 133597 67676 133598 66443 133598 66442 133598 67676 133599 66442 133599 66440 133599 66588 133600 66587 133600 66854 133600 66854 133601 66587 133601 66851 133601 66854 133602 66851 133602 66742 133602 66742 133603 66851 133603 66847 133603 66742 133604 66847 133604 67462 133604 67462 133605 66847 133605 66846 133605 66852 133606 66590 133606 66853 133606 66853 133607 66590 133607 66855 133607 66854 133608 67682 133608 66588 133608 66588 133609 67682 133609 67681 133609 66588 133610 67681 133610 66855 133610 66855 133611 67681 133611 67680 133611 66855 133612 67680 133612 66853 133612 66587 133613 66856 133613 66851 133613 66851 133614 66856 133614 67307 133614 66851 133615 67307 133615 67691 133615 67691 133616 67307 133616 67306 133616 67691 133617 67306 133617 66857 133617 66857 133618 67306 133618 66858 133618 66857 133619 66858 133619 67689 133619 67689 133620 66858 133620 66859 133620 67689 133621 66859 133621 66860 133621 66860 133622 66859 133622 66861 133622 66860 133623 66861 133623 67688 133623 67688 133624 66861 133624 67303 133624 66864 133625 67685 133625 67303 133625 67303 133626 67685 133626 67687 133626 67303 133627 67687 133627 67688 133627 66852 133628 66862 133628 66590 133628 66590 133629 66862 133629 66863 133629 66590 133630 66863 133630 66864 133630 66864 133631 66863 133631 66865 133631 66864 133632 66865 133632 67685 133632 67031 133633 66866 133633 66744 133633 66744 133634 66866 133634 66867 133634 66744 133635 66867 133635 66828 133635 66828 133636 66867 133636 67028 133636 66828 133637 67028 133637 66815 133637 66903 133638 67789 133638 67790 133638 66874 133639 67783 133639 66239 133639 66239 133640 67783 133640 66868 133640 66239 133641 66868 133641 66893 133641 66724 133642 66888 133642 66240 133642 66904 133643 66871 133643 66739 133643 66869 133644 66245 133644 66731 133644 66879 133645 66870 133645 66871 133645 66871 133646 66870 133646 66872 133646 66871 133647 66872 133647 66739 133647 66881 133648 66873 133648 66680 133648 66680 133649 66873 133649 67781 133649 66680 133650 67781 133650 66681 133650 66681 133651 67781 133651 66883 133651 66681 133652 66883 133652 66884 133652 66874 133653 66239 133653 66903 133653 66903 133654 66239 133654 66875 133654 66903 133655 66875 133655 67789 133655 66872 133656 66236 133656 66739 133656 66739 133657 66236 133657 66237 133657 66739 133658 66237 133658 66740 133658 67791 133659 66671 133659 66876 133659 66876 133660 66671 133660 66673 133660 66876 133661 66673 133661 67792 133661 67792 133662 66673 133662 66877 133662 67792 133663 66877 133663 67793 133663 67793 133664 66877 133664 66878 133664 67793 133665 66878 133665 66895 133665 66871 133666 66880 133666 66879 133666 66879 133667 66880 133667 66873 133667 66879 133668 66873 133668 67791 133668 67791 133669 66873 133669 66881 133669 67791 133670 66881 133670 66671 133670 66731 133671 66245 133671 66882 133671 66882 133672 66245 133672 66899 133672 66882 133673 66899 133673 66900 133673 66883 133674 67779 133674 66884 133674 66884 133675 67779 133675 66885 133675 66884 133676 66885 133676 66686 133676 66686 133677 66885 133677 66886 133677 66686 133678 66886 133678 66887 133678 66887 133679 66886 133679 66247 133679 66887 133680 66247 133680 66909 133680 66909 133681 66247 133681 66908 133681 66240 133682 66888 133682 67787 133682 67787 133683 66888 133683 66720 133683 67787 133684 66720 133684 66907 133684 66907 133685 66720 133685 66889 133685 66907 133686 66889 133686 66890 133686 66240 133687 66891 133687 66724 133687 66724 133688 66891 133688 66241 133688 66724 133689 66241 133689 66892 133689 66892 133690 66241 133690 66893 133690 66892 133691 66893 133691 66894 133691 66894 133692 66893 133692 66868 133692 66894 133693 66868 133693 66727 133693 66727 133694 66868 133694 66869 133694 66727 133695 66869 133695 66730 133695 66730 133696 66869 133696 66731 133696 66895 133697 66878 133697 66896 133697 66896 133698 66878 133698 66665 133698 66896 133699 66665 133699 66897 133699 66897 133700 66665 133700 66663 133700 66897 133701 66663 133701 66237 133701 66237 133702 66663 133702 66898 133702 66237 133703 66898 133703 66740 133703 66899 133704 66242 133704 66900 133704 66900 133705 66242 133705 66244 133705 66900 133706 66244 133706 66901 133706 66901 133707 66244 133707 66243 133707 66901 133708 66243 133708 66902 133708 66902 133709 66243 133709 67784 133709 66902 133710 67784 133710 66739 133710 66739 133711 67784 133711 67785 133711 66739 133712 67785 133712 67782 133712 67782 133713 66903 133713 66739 133713 66739 133714 66903 133714 67790 133714 66739 133715 67790 133715 66904 133715 66904 133716 67790 133716 66905 133716 66904 133717 66905 133717 66246 133717 66246 133718 66905 133718 66906 133718 66246 133719 66906 133719 66908 133719 66908 133720 66906 133720 66907 133720 66908 133721 66907 133721 66909 133721 66909 133722 66907 133722 66890 133722 67692 133723 67765 133723 66910 133723 67692 133724 66910 133724 66911 133724 66911 133725 66910 133725 66912 133725 66911 133726 66912 133726 66913 133726 66913 133727 66912 133727 66914 133727 66913 133728 66914 133728 67693 133728 67693 133729 66914 133729 66915 133729 67693 133730 66915 133730 67695 133730 67695 133731 66915 133731 66916 133731 67695 133732 66916 133732 66917 133732 67708 133733 66925 133733 66964 133733 66272 133734 66918 133734 66273 133734 66273 133735 66918 133735 66919 133735 66273 133736 66919 133736 66274 133736 66274 133737 66919 133737 66920 133737 66920 133738 66919 133738 66921 133738 66920 133739 66921 133739 66276 133739 66276 133740 66921 133740 66277 133740 66277 133741 66921 133741 66923 133741 66277 133742 66923 133742 66924 133742 66928 133743 67705 133743 66923 133743 66923 133744 67705 133744 66922 133744 66923 133745 66922 133745 66924 133745 66964 133746 66925 133746 66969 133746 66925 133747 66926 133747 66969 133747 66969 133748 66926 133748 66927 133748 66969 133749 66927 133749 66928 133749 66928 133750 66927 133750 66929 133750 66928 133751 66929 133751 67705 133751 67708 133752 66964 133752 67712 133752 67712 133753 66964 133753 66965 133753 67712 133754 66965 133754 67711 133754 67711 133755 66965 133755 66973 133755 67711 133756 66973 133756 66930 133756 67667 133757 66953 133757 66955 133757 67667 133758 66955 133758 67668 133758 67668 133759 66955 133759 66931 133759 67668 133760 66931 133760 67670 133760 66963 133761 66934 133761 66931 133761 66931 133762 66934 133762 67671 133762 66931 133763 67671 133763 67670 133763 66932 133764 66634 133764 67675 133764 67675 133765 67674 133765 66932 133765 66932 133766 67674 133766 67672 133766 66932 133767 67672 133767 66963 133767 66963 133768 67672 133768 66933 133768 66963 133769 66933 133769 66934 133769 66935 133770 66936 133770 67652 133770 67652 133771 66936 133771 66939 133771 66942 133772 66941 133772 66944 133772 66944 133773 66941 133773 66570 133773 66937 133774 67322 133774 67658 133774 67658 133775 67322 133775 67321 133775 67658 133776 67321 133776 67657 133776 67657 133777 67321 133777 66935 133777 67657 133778 66935 133778 66938 133778 66938 133779 66935 133779 67652 133779 66936 133780 66573 133780 66939 133780 66939 133781 66573 133781 66940 133781 66939 133782 66940 133782 67650 133782 67650 133783 66940 133783 66941 133783 67650 133784 66941 133784 67648 133784 67648 133785 66941 133785 66942 133785 66943 133786 66944 133786 67644 133786 67644 133787 66944 133787 66570 133787 67644 133788 66570 133788 67651 133788 67651 133789 66570 133789 66945 133789 67651 133790 66945 133790 66946 133790 66946 133791 66945 133791 66947 133791 66946 133792 66947 133792 66948 133792 66948 133793 66947 133793 67323 133793 66948 133794 67323 133794 67654 133794 67654 133795 67323 133795 66937 133795 67654 133796 66937 133796 66949 133796 66949 133797 66937 133797 67658 133797 66956 133798 66950 133798 66955 133798 66955 133799 66950 133799 66951 133799 66955 133800 66951 133800 66931 133800 66966 133801 67173 133801 66958 133801 66952 133802 66955 133802 67080 133802 67080 133803 66955 133803 66953 133803 67080 133804 66953 133804 67511 133804 67173 133805 66966 133805 67175 133805 67175 133806 66966 133806 66954 133806 67175 133807 66954 133807 67177 133807 67177 133808 66954 133808 66636 133808 67177 133809 66636 133809 66634 133809 67146 133810 67195 133810 67196 133810 66952 133811 67157 133811 66955 133811 66955 133812 67157 133812 67159 133812 66955 133813 67159 133813 66956 133813 67186 133814 66958 133814 67189 133814 67189 133815 66958 133815 67078 133815 67189 133816 67078 133816 66957 133816 66957 133817 67078 133817 67058 133817 66957 133818 67058 133818 67500 133818 66976 133819 67151 133819 67186 133819 67151 133820 67152 133820 67186 133820 67186 133821 67152 133821 67153 133821 67186 133822 67153 133822 66958 133822 66958 133823 67153 133823 67155 133823 66958 133824 67155 133824 66959 133824 66959 133825 67147 133825 66958 133825 66958 133826 67147 133826 67146 133826 66958 133827 67146 133827 66966 133827 66966 133828 67146 133828 67196 133828 66960 133829 67514 133829 66953 133829 66953 133830 67514 133830 66961 133830 66953 133831 66961 133831 67511 133831 66951 133832 67165 133832 66931 133832 66931 133833 67165 133833 66962 133833 66931 133834 66962 133834 66963 133834 66963 133835 66962 133835 67177 133835 66963 133836 67177 133836 66932 133836 66932 133837 67177 133837 66634 133837 66964 133838 67168 133838 66965 133838 66965 133839 67168 133839 67166 133839 66965 133840 67166 133840 66973 133840 66973 133841 67166 133841 67091 133841 66973 133842 67091 133842 67090 133842 67196 133843 67108 133843 66966 133843 66966 133844 67108 133844 67106 133844 66966 133845 67106 133845 66638 133845 66638 133846 67106 133846 67505 133846 66975 133847 66967 133847 67144 133847 67144 133848 66967 133848 67202 133848 66969 133849 66968 133849 66964 133849 66964 133850 66968 133850 67032 133850 66964 133851 67032 133851 67168 133851 67502 133852 67500 133852 66918 133852 66918 133853 67500 133853 67058 133853 66918 133854 67058 133854 66919 133854 66919 133855 67058 133855 67180 133855 66919 133856 67180 133856 66921 133856 66921 133857 67180 133857 67178 133857 66921 133858 67178 133858 66923 133858 66923 133859 67178 133859 66968 133859 66923 133860 66968 133860 66928 133860 66928 133861 66968 133861 66969 133861 67195 133862 67146 133862 67193 133862 67193 133863 67146 133863 67144 133863 67193 133864 67144 133864 66970 133864 66970 133865 67144 133865 67202 133865 66970 133866 67202 133866 67200 133866 67090 133867 67161 133867 66973 133867 66973 133868 67161 133868 67162 133868 66973 133869 67162 133869 67163 133869 67508 133870 67507 133870 66971 133870 66971 133871 67507 133871 66972 133871 66971 133872 66972 133872 67510 133872 67510 133873 66972 133873 66973 133873 67510 133874 66973 133874 66974 133874 66974 133875 66973 133875 67163 133875 67186 133876 67199 133876 66976 133876 66976 133877 67199 133877 67198 133877 66976 133878 67198 133878 67197 133878 66977 133879 67213 133879 67212 133879 67207 133880 67206 133880 67144 133880 67144 133881 67206 133881 67203 133881 67144 133882 67203 133882 66975 133882 67197 133883 67156 133883 66976 133883 66976 133884 67156 133884 66977 133884 66976 133885 66977 133885 67209 133885 67209 133886 66977 133886 67212 133886 67753 133887 66978 133887 67143 133887 67143 133888 66978 133888 66979 133888 66623 133889 66622 133889 67531 133889 66623 133890 67531 133890 66980 133890 66980 133891 67531 133891 67530 133891 66980 133892 67530 133892 66709 133892 66709 133893 67530 133893 67529 133893 66709 133894 67529 133894 66707 133894 66707 133895 67529 133895 66981 133895 66707 133896 66981 133896 66982 133896 66982 133897 66981 133897 66983 133897 66982 133898 66983 133898 66985 133898 66985 133899 66983 133899 66984 133899 66985 133900 66984 133900 66705 133900 66705 133901 66984 133901 67526 133901 66705 133902 67526 133902 66986 133902 66986 133903 67526 133903 66987 133903 66986 133904 66987 133904 66988 133904 66988 133905 66987 133905 66989 133905 66988 133906 66989 133906 66702 133906 66702 133907 66989 133907 67522 133907 66702 133908 67522 133908 66701 133908 66701 133909 67522 133909 67521 133909 66701 133910 67521 133910 66699 133910 66699 133911 67521 133911 67518 133911 66699 133912 67518 133912 66697 133912 66697 133913 67518 133913 67517 133913 66697 133914 67517 133914 66696 133914 66696 133915 67517 133915 66991 133915 66696 133916 66991 133916 66990 133916 66990 133917 66991 133917 66435 133917 66990 133918 66435 133918 66631 133918 66995 133919 66371 133919 66992 133919 66992 133920 66371 133920 66369 133920 66992 133921 66369 133921 67528 133921 67008 133922 66993 133922 67532 133922 67532 133923 66993 133923 66355 133923 67532 133924 66355 133924 66994 133924 66994 133925 66355 133925 66372 133925 66994 133926 66372 133926 66995 133926 66995 133927 66372 133927 66996 133927 66995 133928 66996 133928 66371 133928 66369 133929 66997 133929 67528 133929 67528 133930 66997 133930 66998 133930 67528 133931 66998 133931 66999 133931 66999 133932 66998 133932 67000 133932 66999 133933 67000 133933 67527 133933 67000 133934 66365 133934 67527 133934 67527 133935 66365 133935 66366 133935 67527 133936 66366 133936 67525 133936 67525 133937 66366 133937 67001 133937 67525 133938 67001 133938 67524 133938 67524 133939 67001 133939 66364 133939 67524 133940 66364 133940 67523 133940 66364 133941 66362 133941 67523 133941 67523 133942 66362 133942 66360 133942 67523 133943 66360 133943 67520 133943 67520 133944 66360 133944 66357 133944 67520 133945 66357 133945 67519 133945 66357 133946 66358 133946 67519 133946 67519 133947 66358 133947 67002 133947 67519 133948 67002 133948 67003 133948 67003 133949 67002 133949 66374 133949 67003 133950 66374 133950 67516 133950 67516 133951 66374 133951 67004 133951 67516 133952 67004 133952 67005 133952 67017 133953 67007 133953 67006 133953 67006 133954 67007 133954 67009 133954 67006 133955 67009 133955 67008 133955 67008 133956 67009 133956 67562 133956 67008 133957 67562 133957 66993 133957 67020 133958 67021 133958 66432 133958 66432 133959 67021 133959 67022 133959 66432 133960 67022 133960 66431 133960 66428 133961 67026 133961 66427 133961 66427 133962 67026 133962 67541 133962 66427 133963 67541 133963 67010 133963 67010 133964 67541 133964 67012 133964 67010 133965 67012 133965 67011 133965 67012 133966 67013 133966 67011 133966 67011 133967 67013 133967 67540 133967 67011 133968 67540 133968 67014 133968 67014 133969 67540 133969 67015 133969 67014 133970 67015 133970 66424 133970 66424 133971 67015 133971 67538 133971 66424 133972 67538 133972 67017 133972 67017 133973 67538 133973 67016 133973 67017 133974 67016 133974 67007 133974 67004 133975 66356 133975 67005 133975 67005 133976 66356 133976 67592 133976 67005 133977 67592 133977 67018 133977 67018 133978 67592 133978 67537 133978 67018 133979 67537 133979 67019 133979 67019 133980 67537 133980 67547 133980 67019 133981 67547 133981 67020 133981 67020 133982 67547 133982 67549 133982 67020 133983 67549 133983 67021 133983 67022 133984 67023 133984 66431 133984 66431 133985 67023 133985 67544 133985 66431 133986 67544 133986 67025 133986 67025 133987 67544 133987 67024 133987 67025 133988 67024 133988 66428 133988 66428 133989 67024 133989 67542 133989 66428 133990 67542 133990 67026 133990 67027 133991 66815 133991 67028 133991 67027 133992 67028 133992 67279 133992 67279 133993 67028 133993 66867 133993 67279 133994 66867 133994 67029 133994 67029 133995 66867 133995 66866 133995 67029 133996 66866 133996 67030 133996 67030 133997 66866 133997 67031 133997 67030 133998 67031 133998 67170 133998 67277 133999 67032 133999 67033 133999 67033 134000 67032 134000 66968 134000 67046 134001 66302 134001 67034 134001 67058 134002 66300 134002 66299 134002 67035 134003 67036 134003 67037 134003 66339 134004 67038 134004 67059 134004 67059 134005 67038 134005 67485 134005 66300 134006 67058 134006 67034 134006 67034 134007 67058 134007 67039 134007 67034 134008 67039 134008 67046 134008 67035 134009 67037 134009 67059 134009 67059 134010 67037 134010 67040 134010 67059 134011 67040 134011 66339 134011 67041 134012 67044 134012 67042 134012 67042 134013 67044 134013 67058 134013 67042 134014 67058 134014 67043 134014 67043 134015 67058 134015 66299 134015 67041 134016 67045 134016 67044 134016 67044 134017 67045 134017 67640 134017 67044 134018 67640 134018 67053 134018 67488 134019 67637 134019 67046 134019 67046 134020 67637 134020 67636 134020 67046 134021 67636 134021 66302 134021 67049 134022 67035 134022 67056 134022 67056 134023 67035 134023 67044 134023 67052 134024 67608 134024 67047 134024 67047 134025 67608 134025 67048 134025 67047 134026 67048 134026 67049 134026 67049 134027 67048 134027 67050 134027 67049 134028 67050 134028 67035 134028 67035 134029 67050 134029 67605 134029 67035 134030 67605 134030 67036 134030 67038 134031 66337 134031 67485 134031 67485 134032 66337 134032 67051 134032 67485 134033 67051 134033 67487 134033 67487 134034 67051 134034 66334 134034 67487 134035 66334 134035 67491 134035 67491 134036 66334 134036 67052 134036 67491 134037 67052 134037 67490 134037 67490 134038 67052 134038 67047 134038 67488 134039 67497 134039 67637 134039 67637 134040 67497 134040 67496 134040 67637 134041 67496 134041 67639 134041 67639 134042 67496 134042 67054 134042 67639 134043 67054 134043 67053 134043 67053 134044 67054 134044 67055 134044 67053 134045 67055 134045 67044 134045 67044 134046 67055 134046 67498 134046 67044 134047 67498 134047 67056 134047 67485 134048 67057 134048 67078 134048 67078 134049 67057 134049 67483 134049 67078 134050 67483 134050 67058 134050 67058 134051 67483 134051 67484 134051 67058 134052 67484 134052 67039 134052 67621 134053 67620 134053 67070 134053 67485 134054 67078 134054 67059 134054 67059 134055 67078 134055 67060 134055 67059 134056 67060 134056 67061 134056 67622 134057 67071 134057 67062 134057 67062 134058 67071 134058 67476 134058 67063 134059 67064 134059 67035 134059 67620 134060 67065 134060 67070 134060 67070 134061 67065 134061 67066 134061 67070 134062 67066 134062 66958 134062 66958 134063 67066 134063 67067 134063 66958 134064 67067 134064 66319 134064 67061 134065 67068 134065 67059 134065 67059 134066 67068 134066 67472 134066 67059 134067 67472 134067 67035 134067 67035 134068 67472 134068 67479 134068 67035 134069 67479 134069 67063 134069 67064 134070 67482 134070 67035 134070 67035 134071 67482 134071 67069 134071 67035 134072 67069 134072 67070 134072 67070 134073 67069 134073 67476 134073 67070 134074 67476 134074 67621 134074 67621 134075 67476 134075 67071 134075 67473 134076 66313 134076 67062 134076 67062 134077 66313 134077 67623 134077 67062 134078 67623 134078 67622 134078 66319 134079 66318 134079 66958 134079 66958 134080 66318 134080 66317 134080 66958 134081 66317 134081 67072 134081 67072 134082 66317 134082 67073 134082 67072 134083 67073 134083 67074 134083 67074 134084 67073 134084 66313 134084 67074 134085 66313 134085 67075 134085 67075 134086 66313 134086 67473 134086 67072 134087 67076 134087 66958 134087 66958 134088 67076 134088 67077 134088 66958 134089 67077 134089 67078 134089 67078 134090 67077 134090 67465 134090 67078 134091 67465 134091 67060 134091 67255 134092 67177 134092 67079 134092 67079 134093 67177 134093 66962 134093 67259 134094 66950 134094 67266 134094 67266 134095 66950 134095 66956 134095 66952 134096 67080 134096 67084 134096 67084 134097 67080 134097 67081 134097 67084 134098 67081 134098 67082 134098 66831 134099 67270 134099 67085 134099 67085 134100 67270 134100 67084 134100 67082 134101 67083 134101 67084 134101 67084 134102 67083 134102 67660 134102 67084 134103 67660 134103 67085 134103 67286 134104 66799 134104 67289 134104 67289 134105 66799 134105 67086 134105 66974 134106 67163 134106 66437 134106 66437 134107 67163 134107 67289 134107 66437 134108 67289 134108 67087 134108 67087 134109 67289 134109 67086 134109 67088 134110 67090 134110 67089 134110 67089 134111 67090 134111 67091 134111 67264 134112 67096 134112 67265 134112 67265 134113 67096 134113 67092 134113 67265 134114 67092 134114 67267 134114 67267 134115 67092 134115 67093 134115 67267 134116 67093 134116 67094 134116 67094 134117 67093 134117 67269 134117 67269 134118 67288 134118 67095 134118 67254 134119 67256 134119 67260 134119 67261 134120 67262 134120 67264 134120 67264 134121 67262 134121 67097 134121 67264 134122 67097 134122 67096 134122 67096 134123 67097 134123 67254 134123 67096 134124 67254 134124 67263 134124 67263 134125 67254 134125 67260 134125 67275 134126 67276 134126 67095 134126 67095 134127 67276 134127 67278 134127 67095 134128 67278 134128 67269 134128 67284 134129 67285 134129 67283 134129 67283 134130 67285 134130 67098 134130 67283 134131 67098 134131 67281 134131 67281 134132 67098 134132 67100 134132 67281 134133 67100 134133 67099 134133 67099 134134 67100 134134 67280 134134 67101 134135 67272 134135 67102 134135 67102 134136 67274 134136 67101 134136 67101 134137 67274 134137 67280 134137 67101 134138 67280 134138 67103 134138 67103 134139 67280 134139 67100 134139 67103 134140 67100 134140 67093 134140 67093 134141 67100 134141 67104 134141 67093 134142 67104 134142 67269 134142 67269 134143 67104 134143 67105 134143 67269 134144 67105 134144 67288 134144 67684 134145 67129 134145 67686 134145 67686 134146 67129 134146 67132 134146 67506 134147 67106 134147 67107 134147 67107 134148 67106 134148 67108 134148 67749 134149 67110 134149 67109 134149 67109 134150 67110 134150 67148 134150 67149 134151 67735 134151 67148 134151 67148 134152 67735 134152 67111 134152 67148 134153 67111 134153 67109 134153 67109 134154 67111 134154 67112 134154 67109 134155 67112 134155 66610 134155 67646 134156 66959 134156 67154 134156 67154 134157 66959 134157 67155 134157 67726 134158 67113 134158 67118 134158 67118 134159 67655 134159 67115 134159 67115 134160 67655 134160 67114 134160 67115 134161 66613 134161 67116 134161 67115 134162 67116 134162 67118 134162 67118 134163 67116 134163 67117 134163 67118 134164 67117 134164 67726 134164 67191 134165 66957 134165 67499 134165 67499 134166 66957 134166 67500 134166 67119 134167 67124 134167 67702 134167 67702 134168 67124 134168 67123 134168 67777 134169 67120 134169 67773 134169 67773 134170 67120 134170 67698 134170 67112 134171 67111 134171 67121 134171 67748 134172 67746 134172 67731 134172 67748 134173 67731 134173 67743 134173 67121 134174 67740 134174 67112 134174 67112 134175 67740 134175 67739 134175 67112 134176 67739 134176 67731 134176 67731 134177 67739 134177 67122 134177 67731 134178 67122 134178 67743 134178 67744 134179 67123 134179 67746 134179 67746 134180 67123 134180 67124 134180 67746 134181 67124 134181 67731 134181 67731 134182 67124 134182 67182 134182 67731 134183 67182 134183 67125 134183 67138 134184 67126 134184 67762 134184 67762 134185 67126 134185 67184 134185 67117 134186 67116 134186 67727 134186 67727 134187 67116 134187 67127 134187 67721 134188 67128 134188 67129 134188 67129 134189 67128 134189 67132 134189 67130 134190 67131 134190 67134 134190 67134 134191 67131 134191 67132 134191 67128 134192 67719 134192 67132 134192 67132 134193 67719 134193 67724 134193 67132 134194 67724 134194 67134 134194 67134 134195 67724 134195 67133 134195 67134 134196 67133 134196 67116 134196 67116 134197 67133 134197 67728 134197 67116 134198 67728 134198 67127 134198 66280 134199 67775 134199 67135 134199 66280 134200 67135 134200 67697 134200 67697 134201 67135 134201 67136 134201 67697 134202 67136 134202 67137 134202 67137 134203 67136 134203 67773 134203 67137 134204 67773 134204 67698 134204 67126 134205 67138 134205 67768 134205 67126 134206 67768 134206 67139 134206 67139 134207 67768 134207 67767 134207 67139 134208 67767 134208 67690 134208 67690 134209 67767 134209 67765 134209 67690 134210 67765 134210 67692 134210 66979 134211 66978 134211 67759 134211 66979 134212 67759 134212 67653 134212 67653 134213 67759 134213 67756 134213 67653 134214 67756 134214 67140 134214 67140 134215 67756 134215 67114 134215 67140 134216 67114 134216 67655 134216 67110 134217 67749 134217 67752 134217 67110 134218 67752 134218 67656 134218 67656 134219 67752 134219 67141 134219 67656 134220 67141 134220 67142 134220 67142 134221 67141 134221 67753 134221 67142 134222 67753 134222 67143 134222 67725 134223 67144 134223 67146 134223 67725 134224 67643 134224 67145 134224 67145 134225 67643 134225 67118 134225 67145 134226 67118 134226 67113 134226 67725 134227 67146 134227 67643 134227 67643 134228 67146 134228 67147 134228 67643 134229 67147 134229 67645 134229 67645 134230 67147 134230 66959 134230 67645 134231 66959 134231 67646 134231 66976 134232 67210 134232 67150 134232 67150 134233 67210 134233 67148 134233 67148 134234 67210 134234 67736 134234 67148 134235 67736 134235 67149 134235 66976 134236 67150 134236 67151 134236 67151 134237 67150 134237 67649 134237 67151 134238 67649 134238 67152 134238 67152 134239 67649 134239 67647 134239 67152 134240 67647 134240 67153 134240 67153 134241 67647 134241 67154 134241 67153 134242 67154 134242 67155 134242 67723 134243 67202 134243 67722 134243 67722 134244 67202 134244 66967 134244 67722 134245 66967 134245 67729 134245 67729 134246 66967 134246 66975 134246 67742 134247 66977 134247 67741 134247 67741 134248 66977 134248 67156 134248 67741 134249 67156 134249 67747 134249 67747 134250 67156 134250 67197 134250 66952 134251 67084 134251 67157 134251 67157 134252 67084 134252 67158 134252 67157 134253 67158 134253 67159 134253 67159 134254 67158 134254 67160 134254 67159 134255 67160 134255 66956 134255 66956 134256 67160 134256 67266 134256 67090 134257 67088 134257 67161 134257 67161 134258 67088 134258 67287 134258 67161 134259 67287 134259 67162 134259 67162 134260 67287 134260 67164 134260 67162 134261 67164 134261 67163 134261 67163 134262 67164 134262 67289 134262 67079 134263 66962 134263 67165 134263 67079 134264 67165 134264 67257 134264 67257 134265 67165 134265 66951 134265 67257 134266 66951 134266 67258 134266 67258 134267 66951 134267 66950 134267 67258 134268 66950 134268 67259 134268 67089 134269 67091 134269 67166 134269 67089 134270 67166 134270 67167 134270 67167 134271 67166 134271 67168 134271 67167 134272 67168 134272 67169 134272 67169 134273 67168 134273 67032 134273 67169 134274 67032 134274 67277 134274 67170 134275 67031 134275 66803 134275 67170 134276 66803 134276 67282 134276 67282 134277 66803 134277 66802 134277 67282 134278 66802 134278 67171 134278 67171 134279 66802 134279 66799 134279 67171 134280 66799 134280 67286 134280 67270 134281 66831 134281 66830 134281 67270 134282 66830 134282 67271 134282 67271 134283 66830 134283 67172 134283 67271 134284 67172 134284 67273 134284 67273 134285 67172 134285 66815 134285 67273 134286 66815 134286 67027 134286 67070 134287 66958 134287 67173 134287 67070 134288 67173 134288 67174 134288 67174 134289 67173 134289 67175 134289 67174 134290 67175 134290 67176 134290 67176 134291 67175 134291 67177 134291 67176 134292 67177 134292 67255 134292 67033 134293 66968 134293 67178 134293 67033 134294 67178 134294 67179 134294 67179 134295 67178 134295 67180 134295 67179 134296 67180 134296 67268 134296 67268 134297 67180 134297 67058 134297 67268 134298 67058 134298 67044 134298 67124 134299 67119 134299 67181 134299 67120 134300 67777 134300 67181 134300 67181 134301 67777 134301 67778 134301 66608 134302 67732 134302 67778 134302 67778 134303 67732 134303 67125 134303 67778 134304 67125 134304 67181 134304 67181 134305 67125 134305 67182 134305 67181 134306 67182 134306 67124 134306 67131 134307 67130 134307 66616 134307 66616 134308 67130 134308 67733 134308 66616 134309 67733 134309 67183 134309 67762 134310 67184 134310 66616 134310 66616 134311 67184 134311 67185 134311 66616 134312 67185 134312 67131 134312 67131 134313 67185 134313 67686 134313 67131 134314 67686 134314 67132 134314 67187 134315 67199 134315 67186 134315 67187 134316 67188 134316 67744 134316 67744 134317 67188 134317 67702 134317 67744 134318 67702 134318 67123 134318 67187 134319 67186 134319 67188 134319 67188 134320 67186 134320 67189 134320 67188 134321 67189 134321 67190 134321 67190 134322 67189 134322 66957 134322 67190 134323 66957 134323 67191 134323 66970 134324 67720 134324 67192 134324 67192 134325 67720 134325 67684 134325 67684 134326 67720 134326 67721 134326 67684 134327 67721 134327 67129 134327 66970 134328 67192 134328 67193 134328 67193 134329 67192 134329 67194 134329 67193 134330 67194 134330 67195 134330 67195 134331 67194 134331 67683 134331 67195 134332 67683 134332 67196 134332 67196 134333 67683 134333 67107 134333 67196 134334 67107 134334 67108 134334 67747 134335 67197 134335 67198 134335 67747 134336 67198 134336 67745 134336 67745 134337 67198 134337 67199 134337 67745 134338 67199 134338 67187 134338 67720 134339 66970 134339 67200 134339 67720 134340 67200 134340 67201 134340 67201 134341 67200 134341 67202 134341 67201 134342 67202 134342 67723 134342 67729 134343 66975 134343 67203 134343 67729 134344 67203 134344 67204 134344 67204 134345 67203 134345 67206 134345 67204 134346 67206 134346 67205 134346 67205 134347 67206 134347 67207 134347 67205 134348 67207 134348 67208 134348 67208 134349 67207 134349 67144 134349 67208 134350 67144 134350 67725 134350 67210 134351 66976 134351 67209 134351 67210 134352 67209 134352 67211 134352 67211 134353 67209 134353 67212 134353 67211 134354 67212 134354 67738 134354 67738 134355 67212 134355 67213 134355 67738 134356 67213 134356 67737 134356 67737 134357 67213 134357 66977 134357 67737 134358 66977 134358 67742 134358 67214 134359 67481 134359 67215 134359 67215 134360 67481 134360 67226 134360 67805 134361 67220 134361 67216 134361 67216 134362 67220 134362 67217 134362 67216 134363 67217 134363 67218 134363 67218 134364 67217 134364 67474 134364 67218 134365 67474 134365 67804 134365 67804 134366 67474 134366 67475 134366 67219 134367 67469 134367 67805 134367 67805 134368 67469 134368 67220 134368 67802 134369 67467 134369 67221 134369 67221 134370 67467 134370 67468 134370 67221 134371 67468 134371 67222 134371 67222 134372 67468 134372 67223 134372 67222 134373 67223 134373 67807 134373 67807 134374 67223 134374 67224 134374 67807 134375 67224 134375 67219 134375 67219 134376 67224 134376 67469 134376 67803 134377 67466 134377 67802 134377 67802 134378 67466 134378 67467 134378 67215 134379 67226 134379 67225 134379 67225 134380 67226 134380 67470 134380 67225 134381 67470 134381 67227 134381 67227 134382 67470 134382 67471 134382 67227 134383 67471 134383 67803 134383 67803 134384 67471 134384 67466 134384 67228 134385 67231 134385 67229 134385 67229 134386 67231 134386 67477 134386 67229 134387 67477 134387 67230 134387 67230 134388 67477 134388 67478 134388 67230 134389 67478 134389 67806 134389 67806 134390 67478 134390 67480 134390 67806 134391 67480 134391 67214 134391 67214 134392 67480 134392 67481 134392 67804 134393 67475 134393 67228 134393 67228 134394 67475 134394 67231 134394 67799 134395 67486 134395 67798 134395 67798 134396 67486 134396 67232 134396 67798 134397 67232 134397 67233 134397 67233 134398 67232 134398 67492 134398 67233 134399 67492 134399 67235 134399 67235 134400 67492 134400 67234 134400 67235 134401 67234 134401 67800 134401 67800 134402 67234 134402 67493 134402 67796 134403 67237 134403 67236 134403 67236 134404 67237 134404 67238 134404 67236 134405 67238 134405 67797 134405 67797 134406 67238 134406 67239 134406 67797 134407 67239 134407 67240 134407 67240 134408 67239 134408 67241 134408 67240 134409 67241 134409 67799 134409 67799 134410 67241 134410 67486 134410 67247 134411 67242 134411 67796 134411 67796 134412 67242 134412 67237 134412 67801 134413 67243 134413 67244 134413 67244 134414 67243 134414 67489 134414 67244 134415 67489 134415 67245 134415 67245 134416 67489 134416 67246 134416 67245 134417 67246 134417 67247 134417 67247 134418 67246 134418 67242 134418 67251 134419 67252 134419 67801 134419 67801 134420 67252 134420 67243 134420 67794 134421 67253 134421 67248 134421 67248 134422 67253 134422 67494 134422 67248 134423 67494 134423 67249 134423 67249 134424 67494 134424 67250 134424 67249 134425 67250 134425 67795 134425 67795 134426 67250 134426 67495 134426 67795 134427 67495 134427 67251 134427 67251 134428 67495 134428 67252 134428 67800 134429 67493 134429 67794 134429 67794 134430 67493 134430 67253 134430 67079 134431 67254 134431 67255 134431 67255 134432 67254 134432 67097 134432 67254 134433 67079 134433 67257 134433 67254 134434 67257 134434 67256 134434 67256 134435 67257 134435 67258 134435 67256 134436 67258 134436 67260 134436 67260 134437 67258 134437 67259 134437 67260 134438 67259 134438 67263 134438 67264 134439 67070 134439 67174 134439 67264 134440 67174 134440 67261 134440 67261 134441 67174 134441 67176 134441 67261 134442 67176 134442 67262 134442 67262 134443 67176 134443 67255 134443 67262 134444 67255 134444 67097 134444 67266 134445 67096 134445 67259 134445 67259 134446 67096 134446 67263 134446 67070 134447 67264 134447 67035 134447 67035 134448 67264 134448 67265 134448 67035 134449 67265 134449 67044 134449 67084 134450 67103 134450 67158 134450 67158 134451 67103 134451 67093 134451 67158 134452 67093 134452 67160 134452 67160 134453 67093 134453 67092 134453 67160 134454 67092 134454 67266 134454 67266 134455 67092 134455 67096 134455 67269 134456 67033 134456 67179 134456 67269 134457 67179 134457 67094 134457 67094 134458 67179 134458 67268 134458 67094 134459 67268 134459 67267 134459 67267 134460 67268 134460 67044 134460 67267 134461 67044 134461 67265 134461 67270 134462 67101 134462 67084 134462 67084 134463 67101 134463 67103 134463 67278 134464 67277 134464 67269 134464 67269 134465 67277 134465 67033 134465 67101 134466 67270 134466 67271 134466 67101 134467 67271 134467 67272 134467 67272 134468 67271 134468 67273 134468 67272 134469 67273 134469 67102 134469 67102 134470 67273 134470 67027 134470 67102 134471 67027 134471 67274 134471 67095 134472 67089 134472 67167 134472 67095 134473 67167 134473 67275 134473 67275 134474 67167 134474 67169 134474 67275 134475 67169 134475 67276 134475 67276 134476 67169 134476 67277 134476 67276 134477 67277 134477 67278 134477 67274 134478 67027 134478 67279 134478 67274 134479 67279 134479 67280 134479 67280 134480 67279 134480 67029 134480 67280 134481 67029 134481 67099 134481 67099 134482 67029 134482 67030 134482 67099 134483 67030 134483 67281 134483 67281 134484 67030 134484 67170 134484 67281 134485 67170 134485 67283 134485 67288 134486 67088 134486 67095 134486 67095 134487 67088 134487 67089 134487 67283 134488 67170 134488 67282 134488 67283 134489 67282 134489 67284 134489 67284 134490 67282 134490 67171 134490 67284 134491 67171 134491 67285 134491 67285 134492 67171 134492 67286 134492 67285 134493 67286 134493 67098 134493 67088 134494 67288 134494 67287 134494 67287 134495 67288 134495 67105 134495 67287 134496 67105 134496 67164 134496 67164 134497 67105 134497 67104 134497 67164 134498 67104 134498 67289 134498 67289 134499 67104 134499 67100 134499 67289 134500 67100 134500 67286 134500 67286 134501 67100 134501 67098 134501 67302 134502 67290 134502 67291 134502 67291 134503 67290 134503 67292 134503 67291 134504 67292 134504 67300 134504 67300 134505 67292 134505 67293 134505 67300 134506 67293 134506 67294 134506 67294 134507 67293 134507 71103 134507 67294 134508 71103 134508 67298 134508 67298 134509 71103 134509 71102 134509 67298 134510 71102 134510 67297 134510 67297 134511 71102 134511 71112 134511 67297 134512 71112 134512 67295 134512 67295 134513 71112 134513 71110 134513 67295 134514 66592 134514 67297 134514 67297 134515 66592 134515 67296 134515 67297 134516 67296 134516 67298 134516 67298 134517 67296 134517 67299 134517 67298 134518 67299 134518 67294 134518 67294 134519 67299 134519 67304 134519 67294 134520 67304 134520 67300 134520 67300 134521 67304 134521 67305 134521 67300 134522 67305 134522 67291 134522 67291 134523 67305 134523 67301 134523 67291 134524 67301 134524 67302 134524 67302 134525 67301 134525 66593 134525 66592 134526 67303 134526 67296 134526 67296 134527 67303 134527 66861 134527 67296 134528 66861 134528 67299 134528 67299 134529 66861 134529 66859 134529 67299 134530 66859 134530 67304 134530 67304 134531 66859 134531 66858 134531 67304 134532 66858 134532 67305 134532 67305 134533 66858 134533 67306 134533 67305 134534 67306 134534 67301 134534 67301 134535 67306 134535 67307 134535 67301 134536 67307 134536 66593 134536 66593 134537 67307 134537 66856 134537 67308 134538 66585 134538 67319 134538 67319 134539 66585 134539 71091 134539 67319 134540 71091 134540 67309 134540 67309 134541 71091 134541 71089 134541 67309 134542 71089 134542 67315 134542 67315 134543 71089 134543 71088 134543 67315 134544 71088 134544 67314 134544 67314 134545 71088 134545 71100 134545 67314 134546 71100 134546 67312 134546 67312 134547 71100 134547 67310 134547 67312 134548 67310 134548 66579 134548 66579 134549 67310 134549 71098 134549 66579 134550 67311 134550 67312 134550 67312 134551 67311 134551 67320 134551 67312 134552 67320 134552 67314 134552 67314 134553 67320 134553 67313 134553 67314 134554 67313 134554 67315 134554 67315 134555 67313 134555 67316 134555 67315 134556 67316 134556 67309 134556 67309 134557 67316 134557 67317 134557 67309 134558 67317 134558 67319 134558 67319 134559 67317 134559 67318 134559 67319 134560 67318 134560 67308 134560 67308 134561 67318 134561 67324 134561 67311 134562 66936 134562 67320 134562 67320 134563 66936 134563 66935 134563 67320 134564 66935 134564 67313 134564 67313 134565 66935 134565 67321 134565 67313 134566 67321 134566 67316 134566 67316 134567 67321 134567 67322 134567 67316 134568 67322 134568 67317 134568 67317 134569 67322 134569 66937 134569 67317 134570 66937 134570 67318 134570 67318 134571 66937 134571 67323 134571 67318 134572 67323 134572 67324 134572 67324 134573 67323 134573 66947 134573 66559 134574 71074 134574 67332 134574 67332 134575 71074 134575 71071 134575 67332 134576 71071 134576 67331 134576 67331 134577 71071 134577 67325 134577 67331 134578 67325 134578 67326 134578 67326 134579 67325 134579 71070 134579 67326 134580 71070 134580 67327 134580 67327 134581 71070 134581 67328 134581 67327 134582 67328 134582 67329 134582 67329 134583 67328 134583 71067 134583 67329 134584 71067 134584 67330 134584 67330 134585 71067 134585 71065 134585 67330 134586 66565 134586 67329 134586 67329 134587 66565 134587 67335 134587 67329 134588 67335 134588 67327 134588 67327 134589 67335 134589 67337 134589 67327 134590 67337 134590 67326 134590 67326 134591 67337 134591 67339 134591 67326 134592 67339 134592 67331 134592 67331 134593 67339 134593 67333 134593 67331 134594 67333 134594 67332 134594 67332 134595 67333 134595 67334 134595 67332 134596 67334 134596 66559 134596 66559 134597 67334 134597 66553 134597 66565 134598 66753 134598 67335 134598 67335 134599 66753 134599 67336 134599 67335 134600 67336 134600 67337 134600 67337 134601 67336 134601 67338 134601 67337 134602 67338 134602 67339 134602 67339 134603 67338 134603 66756 134603 67339 134604 66756 134604 67333 134604 67333 134605 66756 134605 67340 134605 67333 134606 67340 134606 67334 134606 67334 134607 67340 134607 66752 134607 67334 134608 66752 134608 66553 134608 66553 134609 66752 134609 66555 134609 66552 134610 71055 134610 67342 134610 67342 134611 71055 134611 67341 134611 67342 134612 67341 134612 67353 134612 67353 134613 67341 134613 67344 134613 67353 134614 67344 134614 67343 134614 67343 134615 67344 134615 67345 134615 67343 134616 67345 134616 67351 134616 67351 134617 67345 134617 67346 134617 67351 134618 67346 134618 67350 134618 67350 134619 67346 134619 67347 134619 67350 134620 67347 134620 67348 134620 67348 134621 67347 134621 67349 134621 67348 134622 66547 134622 67350 134622 67350 134623 66547 134623 67352 134623 67350 134624 67352 134624 67351 134624 67351 134625 67352 134625 67355 134625 67351 134626 67355 134626 67343 134626 67343 134627 67355 134627 67356 134627 67343 134628 67356 134628 67353 134628 67353 134629 67356 134629 67359 134629 67353 134630 67359 134630 67342 134630 67342 134631 67359 134631 67360 134631 67342 134632 67360 134632 66552 134632 66552 134633 67360 134633 66540 134633 66547 134634 67354 134634 67352 134634 67352 134635 67354 134635 66764 134635 67352 134636 66764 134636 67355 134636 67355 134637 66764 134637 66773 134637 67355 134638 66773 134638 67356 134638 67356 134639 66773 134639 67357 134639 67356 134640 67357 134640 67359 134640 67359 134641 67357 134641 67358 134641 67359 134642 67358 134642 67360 134642 67360 134643 67358 134643 66770 134643 67360 134644 66770 134644 66540 134644 66540 134645 66770 134645 66768 134645 66533 134646 71023 134646 67372 134646 67372 134647 71023 134647 67361 134647 67372 134648 67361 134648 67370 134648 67370 134649 67361 134649 71022 134649 67370 134650 71022 134650 67362 134650 67362 134651 71022 134651 71036 134651 67362 134652 71036 134652 67363 134652 67363 134653 71036 134653 67365 134653 67363 134654 67365 134654 67364 134654 67364 134655 67365 134655 67366 134655 67364 134656 67366 134656 67367 134656 67367 134657 67366 134657 71033 134657 67367 134658 66527 134658 67364 134658 67364 134659 66527 134659 67368 134659 67364 134660 67368 134660 67363 134660 67363 134661 67368 134661 67374 134661 67363 134662 67374 134662 67362 134662 67362 134663 67374 134663 67369 134663 67362 134664 67369 134664 67370 134664 67370 134665 67369 134665 67371 134665 67370 134666 67371 134666 67372 134666 67372 134667 67371 134667 67373 134667 67372 134668 67373 134668 66533 134668 66533 134669 67373 134669 66520 134669 66527 134670 66781 134670 67368 134670 67368 134671 66781 134671 66774 134671 67368 134672 66774 134672 67374 134672 67374 134673 66774 134673 67375 134673 67374 134674 67375 134674 67369 134674 67369 134675 67375 134675 66778 134675 67369 134676 66778 134676 67371 134676 67371 134677 66778 134677 66777 134677 67371 134678 66777 134678 67373 134678 67373 134679 66777 134679 66776 134679 67373 134680 66776 134680 66520 134680 66520 134681 66776 134681 66521 134681 67376 134682 67378 134682 67377 134682 67377 134683 67378 134683 71008 134683 67377 134684 71008 134684 67388 134684 67388 134685 71008 134685 67379 134685 67388 134686 67379 134686 67387 134686 67387 134687 67379 134687 71006 134687 67387 134688 71006 134688 67380 134688 67380 134689 71006 134689 71005 134689 67380 134690 71005 134690 67384 134690 67384 134691 71005 134691 67381 134691 67384 134692 67381 134692 67382 134692 67382 134693 67381 134693 67383 134693 67382 134694 67389 134694 67384 134694 67384 134695 67389 134695 67385 134695 67384 134696 67385 134696 67380 134696 67380 134697 67385 134697 67386 134697 67380 134698 67386 134698 67387 134698 67387 134699 67386 134699 67390 134699 67387 134700 67390 134700 67388 134700 67388 134701 67390 134701 67391 134701 67388 134702 67391 134702 67377 134702 67377 134703 67391 134703 67392 134703 67377 134704 67392 134704 67376 134704 67376 134705 67392 134705 66501 134705 67389 134706 66508 134706 67385 134706 67385 134707 66508 134707 66787 134707 67385 134708 66787 134708 67386 134708 67386 134709 66787 134709 66794 134709 67386 134710 66794 134710 67390 134710 67390 134711 66794 134711 66792 134711 67390 134712 66792 134712 67391 134712 67391 134713 66792 134713 66791 134713 67391 134714 66791 134714 67392 134714 67392 134715 66791 134715 66790 134715 67392 134716 66790 134716 66501 134716 66501 134717 66790 134717 66502 134717 66491 134718 66500 134718 67403 134718 67403 134719 66500 134719 67393 134719 67403 134720 67393 134720 67401 134720 67401 134721 67393 134721 70983 134721 67401 134722 70983 134722 67394 134722 67394 134723 70983 134723 67395 134723 67394 134724 67395 134724 67399 134724 67399 134725 67395 134725 67396 134725 67399 134726 67396 134726 67398 134726 67398 134727 67396 134727 70981 134727 67398 134728 70981 134728 67397 134728 67397 134729 70981 134729 70980 134729 67397 134730 66490 134730 67398 134730 67398 134731 66490 134731 67405 134731 67398 134732 67405 134732 67399 134732 67399 134733 67405 134733 67406 134733 67399 134734 67406 134734 67394 134734 67394 134735 67406 134735 67400 134735 67394 134736 67400 134736 67401 134736 67401 134737 67400 134737 67402 134737 67401 134738 67402 134738 67403 134738 67403 134739 67402 134739 67408 134739 67403 134740 67408 134740 66491 134740 66491 134741 67408 134741 67404 134741 66490 134742 66807 134742 67405 134742 67405 134743 66807 134743 66806 134743 67405 134744 66806 134744 67406 134744 67406 134745 66806 134745 66805 134745 67406 134746 66805 134746 67400 134746 67400 134747 66805 134747 66804 134747 67400 134748 66804 134748 67402 134748 67402 134749 66804 134749 67407 134749 67402 134750 67407 134750 67408 134750 67408 134751 67407 134751 66812 134751 67408 134752 66812 134752 67404 134752 67404 134753 66812 134753 66485 134753 67421 134754 67409 134754 67420 134754 67420 134755 67409 134755 70965 134755 67420 134756 70965 134756 67410 134756 67410 134757 70965 134757 67411 134757 67410 134758 67411 134758 67412 134758 67412 134759 67411 134759 67413 134759 67412 134760 67413 134760 67417 134760 67417 134761 67413 134761 67414 134761 67417 134762 67414 134762 67416 134762 67416 134763 67414 134763 70963 134763 67416 134764 70963 134764 67415 134764 67415 134765 70963 134765 70962 134765 67415 134766 66472 134766 67416 134766 67416 134767 66472 134767 67423 134767 67416 134768 67423 134768 67417 134768 67417 134769 67423 134769 67418 134769 67417 134770 67418 134770 67412 134770 67412 134771 67418 134771 67424 134771 67412 134772 67424 134772 67410 134772 67410 134773 67424 134773 67419 134773 67410 134774 67419 134774 67420 134774 67420 134775 67419 134775 67426 134775 67420 134776 67426 134776 67421 134776 67421 134777 67426 134777 66473 134777 66472 134778 67422 134778 67423 134778 67423 134779 67422 134779 66829 134779 67423 134780 66829 134780 67418 134780 67418 134781 66829 134781 67425 134781 67418 134782 67425 134782 67424 134782 67424 134783 67425 134783 66823 134783 67424 134784 66823 134784 67419 134784 67419 134785 66823 134785 66821 134785 67419 134786 66821 134786 67426 134786 67426 134787 66821 134787 67427 134787 67426 134788 67427 134788 66473 134788 66473 134789 67427 134789 66819 134789 67440 134790 70935 134790 67439 134790 67439 134791 70935 134791 67428 134791 67439 134792 67428 134792 67429 134792 67429 134793 67428 134793 67430 134793 67429 134794 67430 134794 67436 134794 67436 134795 67430 134795 70932 134795 67436 134796 70932 134796 67431 134796 67431 134797 70932 134797 67432 134797 67431 134798 67432 134798 67434 134798 67434 134799 67432 134799 70947 134799 67434 134800 70947 134800 67433 134800 67433 134801 70947 134801 70944 134801 67433 134802 66466 134802 67434 134802 67434 134803 66466 134803 67435 134803 67434 134804 67435 134804 67431 134804 67431 134805 67435 134805 67442 134805 67431 134806 67442 134806 67436 134806 67436 134807 67442 134807 67437 134807 67436 134808 67437 134808 67429 134808 67429 134809 67437 134809 67438 134809 67429 134810 67438 134810 67439 134810 67439 134811 67438 134811 67441 134811 67439 134812 67441 134812 67440 134812 67440 134813 67441 134813 67445 134813 66466 134814 66832 134814 67435 134814 67435 134815 66832 134815 66843 134815 67435 134816 66843 134816 67442 134816 67442 134817 66843 134817 67443 134817 67442 134818 67443 134818 67437 134818 67437 134819 67443 134819 66841 134819 67437 134820 66841 134820 67438 134820 67438 134821 66841 134821 67444 134821 67438 134822 67444 134822 67441 134822 67441 134823 67444 134823 66839 134823 67441 134824 66839 134824 67445 134824 67445 134825 66839 134825 66454 134825 66444 134826 70915 134826 67456 134826 67456 134827 70915 134827 70913 134827 67456 134828 70913 134828 67446 134828 67446 134829 70913 134829 70912 134829 67446 134830 70912 134830 67454 134830 67454 134831 70912 134831 70911 134831 67454 134832 70911 134832 67447 134832 67447 134833 70911 134833 70908 134833 67447 134834 70908 134834 67448 134834 67448 134835 70908 134835 67449 134835 67448 134836 67449 134836 67451 134836 67451 134837 67449 134837 67450 134837 67451 134838 67458 134838 67448 134838 67448 134839 67458 134839 67452 134839 67448 134840 67452 134840 67447 134840 67447 134841 67452 134841 67453 134841 67447 134842 67453 134842 67454 134842 67454 134843 67453 134843 67461 134843 67454 134844 67461 134844 67446 134844 67446 134845 67461 134845 67455 134845 67446 134846 67455 134846 67456 134846 67456 134847 67455 134847 67463 134847 67456 134848 67463 134848 66444 134848 66444 134849 67463 134849 67457 134849 67458 134850 66850 134850 67452 134850 67452 134851 66850 134851 67459 134851 67452 134852 67459 134852 67453 134852 67453 134853 67459 134853 67460 134853 67453 134854 67460 134854 67461 134854 67461 134855 67460 134855 67462 134855 67461 134856 67462 134856 67455 134856 67455 134857 67462 134857 66846 134857 67455 134858 66846 134858 67463 134858 67463 134859 66846 134859 67464 134859 67463 134860 67464 134860 67457 134860 67457 134861 67464 134861 66438 134861 67077 134862 67467 134862 67465 134862 67465 134863 67467 134863 67466 134863 67467 134864 67077 134864 67468 134864 67468 134865 67077 134865 67076 134865 67468 134866 67076 134866 67223 134866 67223 134867 67076 134867 67072 134867 67223 134868 67072 134868 67224 134868 67224 134869 67072 134869 67074 134869 67224 134870 67074 134870 67469 134870 67469 134871 67074 134871 67075 134871 67226 134872 67068 134872 67470 134872 67470 134873 67068 134873 67061 134873 67470 134874 67061 134874 67471 134874 67471 134875 67061 134875 67060 134875 67471 134876 67060 134876 67466 134876 67466 134877 67060 134877 67465 134877 67473 134878 67220 134878 67075 134878 67075 134879 67220 134879 67469 134879 67481 134880 67472 134880 67226 134880 67226 134881 67472 134881 67068 134881 67220 134882 67473 134882 67217 134882 67217 134883 67473 134883 67062 134883 67217 134884 67062 134884 67474 134884 67474 134885 67062 134885 67476 134885 67474 134886 67476 134886 67475 134886 67475 134887 67476 134887 67069 134887 67231 134888 67482 134888 67477 134888 67477 134889 67482 134889 67064 134889 67477 134890 67064 134890 67478 134890 67478 134891 67064 134891 67063 134891 67478 134892 67063 134892 67480 134892 67480 134893 67063 134893 67479 134893 67480 134894 67479 134894 67481 134894 67481 134895 67479 134895 67472 134895 67482 134896 67231 134896 67069 134896 67069 134897 67231 134897 67475 134897 67483 134898 67237 134898 67484 134898 67484 134899 67237 134899 67242 134899 67237 134900 67483 134900 67238 134900 67238 134901 67483 134901 67057 134901 67238 134902 67057 134902 67239 134902 67239 134903 67057 134903 67485 134903 67239 134904 67485 134904 67241 134904 67241 134905 67485 134905 67487 134905 67241 134906 67487 134906 67486 134906 67486 134907 67487 134907 67491 134907 67243 134908 67488 134908 67489 134908 67489 134909 67488 134909 67046 134909 67489 134910 67046 134910 67246 134910 67246 134911 67046 134911 67039 134911 67246 134912 67039 134912 67242 134912 67242 134913 67039 134913 67484 134913 67490 134914 67232 134914 67491 134914 67491 134915 67232 134915 67486 134915 67252 134916 67497 134916 67243 134916 67243 134917 67497 134917 67488 134917 67232 134918 67490 134918 67492 134918 67492 134919 67490 134919 67047 134919 67492 134920 67047 134920 67234 134920 67234 134921 67047 134921 67049 134921 67234 134922 67049 134922 67493 134922 67493 134923 67049 134923 67056 134923 67253 134924 67498 134924 67494 134924 67494 134925 67498 134925 67055 134925 67494 134926 67055 134926 67250 134926 67250 134927 67055 134927 67054 134927 67250 134928 67054 134928 67495 134928 67495 134929 67054 134929 67496 134929 67495 134930 67496 134930 67252 134930 67252 134931 67496 134931 67497 134931 67498 134932 67253 134932 67056 134932 67056 134933 67253 134933 67493 134933 67499 134934 67500 134934 67501 134934 67501 134935 67500 134935 67502 134935 67501 134936 67502 134936 66272 134936 66272 134937 67502 134937 66918 134937 67503 134938 66638 134938 67504 134938 67504 134939 66638 134939 67505 134939 67504 134940 67505 134940 67506 134940 67506 134941 67505 134941 67106 134941 66930 134942 66973 134942 66972 134942 66930 134943 66972 134943 67715 134943 67715 134944 66972 134944 67507 134944 67715 134945 67507 134945 67716 134945 67716 134946 67507 134946 67508 134946 67716 134947 67508 134947 67509 134947 67509 134948 67508 134948 66971 134948 67509 134949 66971 134949 67717 134949 67717 134950 66971 134950 67718 134950 67718 134951 66971 134951 67510 134951 67718 134952 67510 134952 66436 134952 67081 134953 67080 134953 67659 134953 67659 134954 67080 134954 67511 134954 67659 134955 67511 134955 67512 134955 67512 134956 67511 134956 67661 134956 67661 134957 67511 134957 66961 134957 67661 134958 66961 134958 67666 134958 67666 134959 66961 134959 67513 134959 67513 134960 66961 134960 67514 134960 67513 134961 67514 134961 67515 134961 67515 134962 67514 134962 66960 134962 67515 134963 66960 134963 67663 134963 67663 134964 66960 134964 66953 134964 67663 134965 66953 134965 67667 134965 67005 134966 66435 134966 66991 134966 67005 134967 66991 134967 67516 134967 67516 134968 66991 134968 67517 134968 67516 134969 67517 134969 67003 134969 67003 134970 67517 134970 67518 134970 67003 134971 67518 134971 67519 134971 67519 134972 67518 134972 67521 134972 67519 134973 67521 134973 67520 134973 67520 134974 67521 134974 67522 134974 67520 134975 67522 134975 67523 134975 67523 134976 67522 134976 66989 134976 67523 134977 66989 134977 67524 134977 67524 134978 66989 134978 66987 134978 67524 134979 66987 134979 67525 134979 67525 134980 66987 134980 67526 134980 67525 134981 67526 134981 67527 134981 67527 134982 67526 134982 66984 134982 67527 134983 66984 134983 66999 134983 66999 134984 66984 134984 66983 134984 66999 134985 66983 134985 67528 134985 67528 134986 66983 134986 66981 134986 67528 134987 66981 134987 66992 134987 66992 134988 66981 134988 67529 134988 66992 134989 67529 134989 66995 134989 66995 134990 67529 134990 67530 134990 66995 134991 67530 134991 66994 134991 66994 134992 67530 134992 67531 134992 66994 134993 67531 134993 67532 134993 67532 134994 67531 134994 66622 134994 67532 134995 66622 134995 67008 134995 66664 134996 67533 134996 67590 134996 67590 134997 67533 134997 67560 134997 67534 134998 66670 134998 67582 134998 67582 134999 66670 134999 67554 134999 67548 135000 67546 135000 67535 135000 67543 135001 67583 135001 67586 135001 67536 135002 67576 135002 67574 135002 67592 135003 66356 135003 66386 135003 67537 135004 67592 135004 67593 135004 67024 135005 67544 135005 67555 135005 67015 135006 67540 135006 67575 135006 67562 135007 67009 135007 67568 135007 67015 135008 67576 135008 67538 135008 67538 135009 67576 135009 67536 135009 67538 135010 67536 135010 67016 135010 67575 135011 67540 135011 67539 135011 67539 135012 67540 135012 67013 135012 67539 135013 67013 135013 67552 135013 67552 135014 67013 135014 67012 135014 67552 135015 67012 135015 67553 135015 67553 135016 67012 135016 67541 135016 67553 135017 67541 135017 67581 135017 67024 135018 67583 135018 67542 135018 67542 135019 67583 135019 67543 135019 67542 135020 67543 135020 67026 135020 67555 135021 67544 135021 67557 135021 67557 135022 67544 135022 67023 135022 67557 135023 67023 135023 67545 135023 67545 135024 67023 135024 67022 135024 67545 135025 67022 135025 67558 135025 67558 135026 67022 135026 67021 135026 67558 135027 67021 135027 67561 135027 67537 135028 67546 135028 67547 135028 67547 135029 67546 135029 67548 135029 67547 135030 67548 135030 67549 135030 67551 135031 67550 135031 67567 135031 67009 135032 67007 135032 67567 135032 67567 135033 67007 135033 67572 135033 67567 135034 67572 135034 67551 135034 67551 135035 67572 135035 67573 135035 67551 135036 67573 135036 66688 135036 66688 135037 67573 135037 66687 135037 67580 135038 67575 135038 67579 135038 67579 135039 67575 135039 67539 135039 67579 135040 67539 135040 67578 135040 67578 135041 67539 135041 67552 135041 67578 135042 67552 135042 67577 135042 67577 135043 67552 135043 67553 135043 67577 135044 67553 135044 67554 135044 67554 135045 67553 135045 67581 135045 67554 135046 67581 135046 67582 135046 67584 135047 67555 135047 67556 135047 67556 135048 67555 135048 67557 135048 67556 135049 67557 135049 67587 135049 67587 135050 67557 135050 67545 135050 67587 135051 67545 135051 67559 135051 67559 135052 67545 135052 67558 135052 67559 135053 67558 135053 67560 135053 67560 135054 67558 135054 67561 135054 67560 135055 67561 135055 67590 135055 67562 135056 67568 135056 67563 135056 67563 135057 67568 135057 67564 135057 67563 135058 67564 135058 67565 135058 67565 135059 67564 135059 67566 135059 67565 135060 67566 135060 66719 135060 67009 135061 67567 135061 67568 135061 67568 135062 67567 135062 67550 135062 67568 135063 67550 135063 67564 135063 67564 135064 67550 135064 67569 135064 67564 135065 67569 135065 67566 135065 66688 135066 67570 135066 67551 135066 67551 135067 67570 135067 67571 135067 67551 135068 67571 135068 67550 135068 67550 135069 67571 135069 66689 135069 67550 135070 66689 135070 67569 135070 67007 135071 67016 135071 67572 135071 67572 135072 67016 135072 67536 135072 67572 135073 67536 135073 67573 135073 67573 135074 67536 135074 67574 135074 67573 135075 67574 135075 66687 135075 66687 135076 67574 135076 66685 135076 67015 135077 67575 135077 67576 135077 67576 135078 67575 135078 67580 135078 67576 135079 67580 135079 67574 135079 67574 135080 67580 135080 66684 135080 67574 135081 66684 135081 66685 135081 67577 135082 66678 135082 67578 135082 67578 135083 66678 135083 66679 135083 67578 135084 66679 135084 67579 135084 67579 135085 66679 135085 66682 135085 67579 135086 66682 135086 67580 135086 67580 135087 66682 135087 66683 135087 67580 135088 66683 135088 66684 135088 66670 135089 66675 135089 67554 135089 67554 135090 66675 135090 66676 135090 67554 135091 66676 135091 67577 135091 67577 135092 66676 135092 66677 135092 67577 135093 66677 135093 66678 135093 67541 135094 67026 135094 67581 135094 67581 135095 67026 135095 67543 135095 67581 135096 67543 135096 67582 135096 67582 135097 67543 135097 67586 135097 67582 135098 67586 135098 67534 135098 67534 135099 67586 135099 66672 135099 67024 135100 67555 135100 67583 135100 67583 135101 67555 135101 67584 135101 67583 135102 67584 135102 67586 135102 67586 135103 67584 135103 67585 135103 67586 135104 67585 135104 66672 135104 67559 135105 66668 135105 67587 135105 67587 135106 66668 135106 66667 135106 67587 135107 66667 135107 67556 135107 67556 135108 66667 135108 66669 135108 67556 135109 66669 135109 67584 135109 67584 135110 66669 135110 66674 135110 67584 135111 66674 135111 67585 135111 67533 135112 67588 135112 67560 135112 67560 135113 67588 135113 67589 135113 67560 135114 67589 135114 67559 135114 67559 135115 67589 135115 66666 135115 67559 135116 66666 135116 66668 135116 67021 135117 67549 135117 67561 135117 67561 135118 67549 135118 67548 135118 67561 135119 67548 135119 67590 135119 67590 135120 67548 135120 67535 135120 67590 135121 67535 135121 66664 135121 66664 135122 67535 135122 66662 135122 67591 135123 66660 135123 66661 135123 67537 135124 67593 135124 67546 135124 67546 135125 67593 135125 67591 135125 67546 135126 67591 135126 67535 135126 67535 135127 67591 135127 66661 135127 67535 135128 66661 135128 66662 135128 67592 135129 66386 135129 67593 135129 67593 135130 66386 135130 67594 135130 67593 135131 67594 135131 67591 135131 67591 135132 67594 135132 66389 135132 67591 135133 66389 135133 66660 135133 66350 135134 67599 135134 67597 135134 67595 135135 67599 135135 66350 135135 66349 135136 67595 135136 66350 135136 66350 135137 67596 135137 66340 135137 67598 135138 67596 135138 66350 135138 67597 135139 67598 135139 66350 135139 66349 135140 67603 135140 67595 135140 67595 135141 67603 135141 67604 135141 67595 135142 67604 135142 67599 135142 67599 135143 67604 135143 67600 135143 67599 135144 67600 135144 67597 135144 67597 135145 67600 135145 67606 135145 67597 135146 67606 135146 67598 135146 67598 135147 67606 135147 67601 135147 67598 135148 67601 135148 67596 135148 67596 135149 67601 135149 67607 135149 67596 135150 67607 135150 66340 135150 66340 135151 67607 135151 67602 135151 67603 135152 67037 135152 67604 135152 67604 135153 67037 135153 67036 135153 67604 135154 67036 135154 67600 135154 67600 135155 67036 135155 67605 135155 67600 135156 67605 135156 67606 135156 67606 135157 67605 135157 67050 135157 67606 135158 67050 135158 67601 135158 67601 135159 67050 135159 67048 135159 67601 135160 67048 135160 67607 135160 67607 135161 67048 135161 67608 135161 67607 135162 67608 135162 67602 135162 67602 135163 67608 135163 67052 135163 66331 135164 67612 135164 67614 135164 67611 135165 67612 135165 66331 135165 66330 135166 67611 135166 66331 135166 66331 135167 67617 135167 66328 135167 67609 135168 67617 135168 66331 135168 67614 135169 67609 135169 66331 135169 66330 135170 67610 135170 67611 135170 67611 135171 67610 135171 67613 135171 67611 135172 67613 135172 67612 135172 67612 135173 67613 135173 67619 135173 67612 135174 67619 135174 67614 135174 67614 135175 67619 135175 67615 135175 67614 135176 67615 135176 67609 135176 67609 135177 67615 135177 67616 135177 67609 135178 67616 135178 67617 135178 67617 135179 67616 135179 67618 135179 67617 135180 67618 135180 66328 135180 66328 135181 67618 135181 66322 135181 67610 135182 67066 135182 67613 135182 67613 135183 67066 135183 67065 135183 67613 135184 67065 135184 67619 135184 67619 135185 67065 135185 67620 135185 67619 135186 67620 135186 67615 135186 67615 135187 67620 135187 67621 135187 67615 135188 67621 135188 67616 135188 67616 135189 67621 135189 67071 135189 67616 135190 67071 135190 67618 135190 67618 135191 67071 135191 67622 135191 67618 135192 67622 135192 66322 135192 66322 135193 67622 135193 67623 135193 67630 135194 67624 135194 67626 135194 67630 135195 67625 135195 67629 135195 67627 135196 67625 135196 67630 135196 67626 135197 67627 135197 67630 135197 67630 135198 67634 135198 66303 135198 67628 135199 67634 135199 67630 135199 67629 135200 67628 135200 67630 135200 67624 135201 66301 135201 67626 135201 67626 135202 66301 135202 67638 135202 67626 135203 67638 135203 67627 135203 67627 135204 67638 135204 67631 135204 67627 135205 67631 135205 67625 135205 67625 135206 67631 135206 67632 135206 67625 135207 67632 135207 67629 135207 67629 135208 67632 135208 67633 135208 67629 135209 67633 135209 67628 135209 67628 135210 67633 135210 67641 135210 67628 135211 67641 135211 67634 135211 67634 135212 67641 135212 67642 135212 67634 135213 67642 135213 66303 135213 66303 135214 67642 135214 67635 135214 66301 135215 67636 135215 67638 135215 67638 135216 67636 135216 67637 135216 67638 135217 67637 135217 67631 135217 67631 135218 67637 135218 67639 135218 67631 135219 67639 135219 67632 135219 67632 135220 67639 135220 67053 135220 67632 135221 67053 135221 67633 135221 67633 135222 67053 135222 67640 135222 67633 135223 67640 135223 67641 135223 67641 135224 67640 135224 67045 135224 67641 135225 67045 135225 67642 135225 67642 135226 67045 135226 67041 135226 67642 135227 67041 135227 67635 135227 67635 135228 67041 135228 67042 135228 66944 135229 67646 135229 66942 135229 66942 135230 67646 135230 67154 135230 67651 135231 67118 135231 67643 135231 67651 135232 67643 135232 67644 135232 67644 135233 67643 135233 67645 135233 67644 135234 67645 135234 66943 135234 66943 135235 67645 135235 67646 135235 66943 135236 67646 135236 66944 135236 66942 135237 67154 135237 67647 135237 66942 135238 67647 135238 67648 135238 67648 135239 67647 135239 67649 135239 67648 135240 67649 135240 67650 135240 67649 135241 67150 135241 67650 135241 67650 135242 67150 135242 67148 135242 67650 135243 67148 135243 66939 135243 66946 135244 67655 135244 67651 135244 67651 135245 67655 135245 67118 135245 67110 135246 67652 135246 67148 135246 67148 135247 67652 135247 66939 135247 66949 135248 66979 135248 67653 135248 66949 135249 67653 135249 67654 135249 67654 135250 67653 135250 67140 135250 67654 135251 67140 135251 66948 135251 66948 135252 67140 135252 67655 135252 66948 135253 67655 135253 66946 135253 67652 135254 67110 135254 67656 135254 67652 135255 67656 135255 66938 135255 66938 135256 67656 135256 67142 135256 66938 135257 67142 135257 67657 135257 67657 135258 67142 135258 67143 135258 67657 135259 67143 135259 67658 135259 67143 135260 66979 135260 67658 135260 67658 135261 66979 135261 66949 135261 67660 135262 67083 135262 67659 135262 67659 135263 67512 135263 67660 135263 67660 135264 67512 135264 67661 135264 67660 135265 67661 135265 67666 135265 67667 135266 66824 135266 67663 135266 67663 135267 66824 135267 67662 135267 67663 135268 67662 135268 67515 135268 67515 135269 67662 135269 67664 135269 67515 135270 67664 135270 67513 135270 67513 135271 67664 135271 67665 135271 67513 135272 67665 135272 67666 135272 67666 135273 67665 135273 67085 135273 67666 135274 67085 135274 67660 135274 66824 135275 67667 135275 66822 135275 66822 135276 67667 135276 67668 135276 66822 135277 67668 135277 67669 135277 67669 135278 67668 135278 67670 135278 67669 135279 67670 135279 66813 135279 66813 135280 67670 135280 66833 135280 66833 135281 67670 135281 67671 135281 66833 135282 67671 135282 66842 135282 67671 135283 66934 135283 66842 135283 66842 135284 66934 135284 66933 135284 66842 135285 66933 135285 67673 135285 66933 135286 67672 135286 67673 135286 67673 135287 67672 135287 67674 135287 67673 135288 67674 135288 66840 135288 66840 135289 67674 135289 67675 135289 66840 135290 67675 135290 67676 135290 67675 135291 66632 135291 67676 135291 67676 135292 66632 135292 66633 135292 67676 135293 66633 135293 67677 135293 67503 135294 67682 135294 66854 135294 67503 135295 66854 135295 66637 135295 66633 135296 66635 135296 67677 135296 67677 135297 66635 135297 67678 135297 67677 135298 67678 135298 66848 135298 66848 135299 67678 135299 66637 135299 66848 135300 66637 135300 67679 135300 67679 135301 66637 135301 66854 135301 67506 135302 67680 135302 67504 135302 67504 135303 67680 135303 67681 135303 67504 135304 67681 135304 67503 135304 67503 135305 67681 135305 67682 135305 67107 135306 66853 135306 67506 135306 67506 135307 66853 135307 67680 135307 66853 135308 67107 135308 67683 135308 66853 135309 67683 135309 66852 135309 66852 135310 67683 135310 67194 135310 66852 135311 67194 135311 66862 135311 66862 135312 67194 135312 67192 135312 66862 135313 67192 135313 66863 135313 66863 135314 67192 135314 67684 135314 66863 135315 67684 135315 66865 135315 67686 135316 67685 135316 67684 135316 67684 135317 67685 135317 66865 135317 67685 135318 67686 135318 67185 135318 67685 135319 67185 135319 67687 135319 67687 135320 67185 135320 67184 135320 67687 135321 67184 135321 67688 135321 67126 135322 66860 135322 67184 135322 67184 135323 66860 135323 67688 135323 66860 135324 67126 135324 67139 135324 66860 135325 67139 135325 67689 135325 67689 135326 67139 135326 67690 135326 67689 135327 67690 135327 66857 135327 66857 135328 67690 135328 67692 135328 66857 135329 67692 135329 67691 135329 67691 135330 67692 135330 66911 135330 67691 135331 66911 135331 66851 135331 66851 135332 66911 135332 66913 135332 66851 135333 66913 135333 66847 135333 66847 135334 66913 135334 67693 135334 66847 135335 67693 135335 67694 135335 67694 135336 67693 135336 67695 135336 67694 135337 67695 135337 66845 135337 66845 135338 67695 135338 66917 135338 66845 135339 66917 135339 66283 135339 66757 135340 66280 135340 67697 135340 66757 135341 67697 135341 67696 135341 67696 135342 67697 135342 67137 135342 67696 135343 67137 135343 66755 135343 66755 135344 67137 135344 67698 135344 66755 135345 67698 135345 67699 135345 67120 135346 67700 135346 67698 135346 67698 135347 67700 135347 67699 135347 67700 135348 67120 135348 67181 135348 67700 135349 67181 135349 66751 135349 66751 135350 67181 135350 67119 135350 66751 135351 67119 135351 67701 135351 67702 135352 66749 135352 67119 135352 67119 135353 66749 135353 67701 135353 66749 135354 67702 135354 67188 135354 66749 135355 67188 135355 66748 135355 66748 135356 67188 135356 67190 135356 66748 135357 67190 135357 66758 135357 66758 135358 67190 135358 67191 135358 66758 135359 67191 135359 66760 135359 67499 135360 66761 135360 67191 135360 67191 135361 66761 135361 66760 135361 66272 135362 67703 135362 67501 135362 67501 135363 67703 135363 67704 135363 67501 135364 67704 135364 67499 135364 67499 135365 67704 135365 66761 135365 67706 135366 66765 135366 66922 135366 66922 135367 67705 135367 67706 135367 67706 135368 67705 135368 66929 135368 67706 135369 66929 135369 67707 135369 66929 135370 66927 135370 67707 135370 67707 135371 66927 135371 66926 135371 67707 135372 66926 135372 67710 135372 67710 135373 66926 135373 66925 135373 67710 135374 66925 135374 67708 135374 67713 135375 67709 135375 67708 135375 67708 135376 67709 135376 66741 135376 67708 135377 66741 135377 67710 135377 66930 135378 67714 135378 67711 135378 67711 135379 67714 135379 67713 135379 67711 135380 67713 135380 67712 135380 67712 135381 67713 135381 67708 135381 66436 135382 66437 135382 67087 135382 67714 135383 66930 135383 66789 135383 66789 135384 66930 135384 67715 135384 66789 135385 67715 135385 66798 135385 66798 135386 67715 135386 67716 135386 66798 135387 67716 135387 66800 135387 66800 135388 67716 135388 67509 135388 66800 135389 67509 135389 67086 135389 67086 135390 67509 135390 67717 135390 67086 135391 67717 135391 67087 135391 67087 135392 67717 135392 67718 135392 67087 135393 67718 135393 66436 135393 67723 135394 67719 135394 67201 135394 67201 135395 67719 135395 67128 135395 67201 135396 67128 135396 67720 135396 67720 135397 67128 135397 67721 135397 67729 135398 67133 135398 67722 135398 67722 135399 67133 135399 67724 135399 67722 135400 67724 135400 67723 135400 67723 135401 67724 135401 67719 135401 67726 135402 67117 135402 67727 135402 67113 135403 67208 135403 67145 135403 67145 135404 67208 135404 67725 135404 67113 135405 67726 135405 67208 135405 67208 135406 67726 135406 67727 135406 67208 135407 67727 135407 67205 135407 67205 135408 67727 135408 67127 135408 67205 135409 67127 135409 67204 135409 67204 135410 67127 135410 67728 135410 67204 135411 67728 135411 67729 135411 67729 135412 67728 135412 67133 135412 67731 135413 67125 135413 67732 135413 66610 135414 67112 135414 67730 135414 67730 135415 67112 135415 67731 135415 67730 135416 67731 135416 66605 135416 66605 135417 67731 135417 67732 135417 66605 135418 67732 135418 66608 135418 67183 135419 67733 135419 67734 135419 67734 135420 67733 135420 67130 135420 67734 135421 67130 135421 67134 135421 67116 135422 66613 135422 67134 135422 67134 135423 66613 135423 66612 135423 67134 135424 66612 135424 67734 135424 67111 135425 67735 135425 67211 135425 67735 135426 67149 135426 67211 135426 67211 135427 67149 135427 67736 135427 67211 135428 67736 135428 67210 135428 67742 135429 67122 135429 67737 135429 67737 135430 67122 135430 67739 135430 67737 135431 67739 135431 67738 135431 67738 135432 67739 135432 67740 135432 67738 135433 67740 135433 67211 135433 67211 135434 67740 135434 67121 135434 67211 135435 67121 135435 67111 135435 67747 135436 67748 135436 67741 135436 67741 135437 67748 135437 67743 135437 67741 135438 67743 135438 67742 135438 67742 135439 67743 135439 67122 135439 67187 135440 67744 135440 67745 135440 67745 135441 67744 135441 67746 135441 67745 135442 67746 135442 67747 135442 67747 135443 67746 135443 67748 135443 67749 135444 67109 135444 66609 135444 70870 135445 67749 135445 66717 135445 66717 135446 67749 135446 66609 135446 66717 135447 66609 135447 67750 135447 67755 135448 67753 135448 67141 135448 67755 135449 67141 135449 67751 135449 67751 135450 67141 135450 67752 135450 67751 135451 67752 135451 70869 135451 70869 135452 67752 135452 67749 135452 70869 135453 67749 135453 70870 135453 66978 135454 67753 135454 67754 135454 67754 135455 67753 135455 67755 135455 70872 135456 67114 135456 67756 135456 70872 135457 67756 135457 67757 135457 67757 135458 67756 135458 67759 135458 67757 135459 67759 135459 67758 135459 67758 135460 67759 135460 66978 135460 67758 135461 66978 135461 67754 135461 70866 135462 66718 135462 67760 135462 70872 135463 70866 135463 67114 135463 67114 135464 70866 135464 67760 135464 67114 135465 67760 135465 67115 135465 67761 135466 70873 135466 67762 135466 66614 135467 67761 135467 66615 135467 66615 135468 67761 135468 67762 135468 66615 135469 67762 135469 66616 135469 67763 135470 67138 135470 70873 135470 70873 135471 67138 135471 67762 135471 67764 135472 67765 135472 67767 135472 67764 135473 67767 135473 67766 135473 67766 135474 67767 135474 67768 135474 67766 135475 67768 135475 67769 135475 67769 135476 67768 135476 67138 135476 67769 135477 67138 135477 67763 135477 70878 135478 67775 135478 67770 135478 70878 135479 67770 135479 70888 135479 70888 135480 67770 135480 66642 135480 70888 135481 66642 135481 70887 135481 70887 135482 66642 135482 66641 135482 70887 135483 66641 135483 70886 135483 70886 135484 66641 135484 67772 135484 70886 135485 67772 135485 67771 135485 67771 135486 67772 135486 66658 135486 67771 135487 66658 135487 70883 135487 70871 135488 67773 135488 67136 135488 70871 135489 67136 135489 70877 135489 70877 135490 67136 135490 67135 135490 70877 135491 67135 135491 67774 135491 67774 135492 67135 135492 67775 135492 67774 135493 67775 135493 70878 135493 67776 135494 67777 135494 70871 135494 70871 135495 67777 135495 67773 135495 67777 135496 67776 135496 66690 135496 66690 135497 66607 135497 67777 135497 67777 135498 66607 135498 66606 135498 67777 135499 66606 135499 67778 135499 67780 135500 67779 135500 66883 135500 66885 135501 67779 135501 67780 135501 66886 135502 66885 135502 67780 135502 67780 135503 66873 135503 66880 135503 67781 135504 66873 135504 67780 135504 66883 135505 67781 135505 67780 135505 67786 135506 66868 135506 67783 135506 67786 135507 66903 135507 67782 135507 66874 135508 66903 135508 67786 135508 67783 135509 66874 135509 67786 135509 67786 135510 67784 135510 66243 135510 67785 135511 67784 135511 67786 135511 67782 135512 67785 135512 67786 135512 67788 135513 66907 135513 66906 135513 67787 135514 66907 135514 67788 135514 66240 135515 67787 135515 67788 135515 67788 135516 67790 135516 67789 135516 66905 135517 67790 135517 67788 135517 66906 135518 66905 135518 67788 135518 66238 135519 66876 135519 67792 135519 67791 135520 66876 135520 66238 135520 66879 135521 67791 135521 66238 135521 66238 135522 66895 135522 66896 135522 67793 135523 66895 135523 66238 135523 67792 135524 67793 135524 66238 135524 67248 135525 67249 135525 67794 135525 67794 135526 67249 135526 67795 135526 67794 135527 67795 135527 67800 135527 67236 135528 67797 135528 67796 135528 67796 135529 67797 135529 67240 135529 67796 135530 67240 135530 67247 135530 67247 135531 67240 135531 67801 135531 67247 135532 67801 135532 67245 135532 67245 135533 67801 135533 67244 135533 67233 135534 67235 135534 67798 135534 67798 135535 67235 135535 67800 135535 67798 135536 67800 135536 67799 135536 67799 135537 67800 135537 67795 135537 67799 135538 67795 135538 67240 135538 67240 135539 67795 135539 67251 135539 67240 135540 67251 135540 67801 135540 67229 135541 67230 135541 67228 135541 67228 135542 67230 135542 67806 135542 67228 135543 67806 135543 67804 135543 67221 135544 67222 135544 67802 135544 67802 135545 67222 135545 67807 135545 67802 135546 67807 135546 67803 135546 67803 135547 67807 135547 67215 135547 67803 135548 67215 135548 67227 135548 67227 135549 67215 135549 67225 135549 67216 135550 67218 135550 67805 135550 67805 135551 67218 135551 67804 135551 67805 135552 67804 135552 67219 135552 67219 135553 67804 135553 67806 135553 67219 135554 67806 135554 67807 135554 67807 135555 67806 135555 67214 135555 67807 135556 67214 135556 67215 135556 67965 135557 67964 135557 67950 135557 67808 135558 67809 135558 67968 135558 67968 135559 67809 135559 67810 135559 67968 135560 67810 135560 66219 135560 66219 135561 67810 135561 67811 135561 67811 135562 67810 135562 66234 135562 67811 135563 66234 135563 66232 135563 67808 135564 67968 135564 67950 135564 67950 135565 67968 135565 67966 135565 67950 135566 67966 135566 67965 135566 67964 135567 67963 135567 67950 135567 67950 135568 67963 135568 67961 135568 67950 135569 67961 135569 67952 135569 66227 135570 67812 135570 67813 135570 67813 135571 67812 135571 66225 135571 67813 135572 66225 135572 66230 135572 66230 135573 66225 135573 67814 135573 67814 135574 66225 135574 66223 135574 67814 135575 66223 135575 66222 135575 66232 135576 66231 135576 67811 135576 67811 135577 66231 135577 67814 135577 67811 135578 67814 135578 67815 135578 67815 135579 67814 135579 66222 135579 67952 135580 67961 135580 67953 135580 67953 135581 67961 135581 67959 135581 67953 135582 67959 135582 67816 135582 67816 135583 67959 135583 67958 135583 67816 135584 67958 135584 67955 135584 69738 135585 68395 135585 69737 135585 69737 135586 68395 135586 67817 135586 69737 135587 67817 135587 67818 135587 67818 135588 67817 135588 67820 135588 67818 135589 67820 135589 67819 135589 67819 135590 67820 135590 68392 135590 67819 135591 68392 135591 65542 135591 65542 135592 68392 135592 67821 135592 65542 135593 67821 135593 67822 135593 67822 135594 67821 135594 65931 135594 67822 135595 65931 135595 65541 135595 65931 135596 65930 135596 65541 135596 65541 135597 65930 135597 67823 135597 65541 135598 67823 135598 67824 135598 67824 135599 67823 135599 67825 135599 67824 135600 67825 135600 65538 135600 65538 135601 67825 135601 65929 135601 65538 135602 65929 135602 69742 135602 69742 135603 65929 135603 65927 135603 69742 135604 65927 135604 69741 135604 69741 135605 65927 135605 67827 135605 69741 135606 67827 135606 67826 135606 67826 135607 67827 135607 68398 135607 67826 135608 68398 135608 69738 135608 69738 135609 68398 135609 67828 135609 69738 135610 67828 135610 68395 135610 67829 135611 65924 135611 65574 135611 65574 135612 65924 135612 67830 135612 65574 135613 67830 135613 65573 135613 65573 135614 67830 135614 67831 135614 65573 135615 67831 135615 67832 135615 67832 135616 67831 135616 65921 135616 67832 135617 65921 135617 65571 135617 65571 135618 65921 135618 65920 135618 65571 135619 65920 135619 67833 135619 67833 135620 65920 135620 68411 135620 67833 135621 68411 135621 67834 135621 67834 135622 68411 135622 68408 135622 67834 135623 68408 135623 69487 135623 69487 135624 68408 135624 68405 135624 69487 135625 68405 135625 69486 135625 69486 135626 68405 135626 68403 135626 69486 135627 68403 135627 69485 135627 69485 135628 68403 135628 68402 135628 69485 135629 68402 135629 65578 135629 65578 135630 68402 135630 67836 135630 65578 135631 67836 135631 67835 135631 67835 135632 67836 135632 65926 135632 67835 135633 65926 135633 65576 135633 65576 135634 65926 135634 67829 135634 65576 135635 67829 135635 65574 135635 65583 135636 65916 135636 65582 135636 65582 135637 65916 135637 67837 135637 65582 135638 67837 135638 65581 135638 65581 135639 67837 135639 65914 135639 65581 135640 65914 135640 67838 135640 67838 135641 65914 135641 65913 135641 67838 135642 65913 135642 69483 135642 69483 135643 65913 135643 68418 135643 69483 135644 68418 135644 67839 135644 67839 135645 68418 135645 68417 135645 67839 135646 68417 135646 69481 135646 69481 135647 68417 135647 67841 135647 69481 135648 67841 135648 67840 135648 67840 135649 67841 135649 68413 135649 67840 135650 68413 135650 69478 135650 69478 135651 68413 135651 67842 135651 69478 135652 67842 135652 67843 135652 67843 135653 67842 135653 65919 135653 67843 135654 65919 135654 65585 135654 65585 135655 65919 135655 65918 135655 65585 135656 65918 135656 65584 135656 65584 135657 65918 135657 67844 135657 65584 135658 67844 135658 65583 135658 65583 135659 67844 135659 67845 135659 65583 135660 67845 135660 65916 135660 65907 135661 65906 135661 65589 135661 65589 135662 65906 135662 67846 135662 65589 135663 67846 135663 67847 135663 67847 135664 67846 135664 65905 135664 67847 135665 65905 135665 65587 135665 65587 135666 65905 135666 67848 135666 65587 135667 67848 135667 67849 135667 67849 135668 67848 135668 65903 135668 67849 135669 65903 135669 67850 135669 67850 135670 65903 135670 67851 135670 67850 135671 67851 135671 69476 135671 69476 135672 67851 135672 68424 135672 69476 135673 68424 135673 69474 135673 69474 135674 68424 135674 68422 135674 69474 135675 68422 135675 69472 135675 69472 135676 68422 135676 67852 135676 69472 135677 67852 135677 67853 135677 67853 135678 67852 135678 67854 135678 67853 135679 67854 135679 65591 135679 65591 135680 67854 135680 65911 135680 65591 135681 65911 135681 67855 135681 67855 135682 65911 135682 65909 135682 67855 135683 65909 135683 65590 135683 65590 135684 65909 135684 65907 135684 65590 135685 65907 135685 65589 135685 67856 135686 65899 135686 65597 135686 65597 135687 65899 135687 65897 135687 65597 135688 65897 135688 65594 135688 65594 135689 65897 135689 65895 135689 65594 135690 65895 135690 67857 135690 67857 135691 65895 135691 65894 135691 67857 135692 65894 135692 65592 135692 65592 135693 65894 135693 65893 135693 65592 135694 65893 135694 69471 135694 69471 135695 65893 135695 68435 135695 69471 135696 68435 135696 67858 135696 67858 135697 68435 135697 68434 135697 67858 135698 68434 135698 69468 135698 69468 135699 68434 135699 68433 135699 69468 135700 68433 135700 67859 135700 67859 135701 68433 135701 67860 135701 67859 135702 67860 135702 69466 135702 69466 135703 67860 135703 68430 135703 69466 135704 68430 135704 67861 135704 67861 135705 68430 135705 65902 135705 67861 135706 65902 135706 65599 135706 65599 135707 65902 135707 65900 135707 65599 135708 65900 135708 67862 135708 67862 135709 65900 135709 67856 135709 67862 135710 67856 135710 65597 135710 67863 135711 65602 135711 67864 135711 67864 135712 65602 135712 67865 135712 67864 135713 67865 135713 67866 135713 67866 135714 67865 135714 69457 135714 67866 135715 69457 135715 67867 135715 67867 135716 69457 135716 69458 135716 67867 135717 69458 135717 68440 135717 68440 135718 69458 135718 69462 135718 68440 135719 69462 135719 68441 135719 68441 135720 69462 135720 69463 135720 68441 135721 69463 135721 67868 135721 67868 135722 69463 135722 67870 135722 67868 135723 67870 135723 67869 135723 67869 135724 67870 135724 67872 135724 67869 135725 67872 135725 67871 135725 67871 135726 67872 135726 67873 135726 67871 135727 67873 135727 65886 135727 65886 135728 67873 135728 67874 135728 65886 135729 67874 135729 65889 135729 65889 135730 67874 135730 65600 135730 65889 135731 65600 135731 65890 135731 65890 135732 65600 135732 67875 135732 65890 135733 67875 135733 67863 135733 67863 135734 67875 135734 65602 135734 68444 135735 67876 135735 68445 135735 68445 135736 67876 135736 69453 135736 68445 135737 69453 135737 67877 135737 67877 135738 69453 135738 67878 135738 67877 135739 67878 135739 68446 135739 68446 135740 67878 135740 69454 135740 68446 135741 69454 135741 68447 135741 68447 135742 69454 135742 67880 135742 68447 135743 67880 135743 67879 135743 67879 135744 67880 135744 69456 135744 67879 135745 69456 135745 67881 135745 67881 135746 69456 135746 67882 135746 67881 135747 67882 135747 65878 135747 65878 135748 67882 135748 67883 135748 65878 135749 67883 135749 67884 135749 67884 135750 67883 135750 67885 135750 67884 135751 67885 135751 65882 135751 65882 135752 67885 135752 67886 135752 65882 135753 67886 135753 67887 135753 67887 135754 67886 135754 65607 135754 67887 135755 65607 135755 67888 135755 67888 135756 65607 135756 65609 135756 67888 135757 65609 135757 67889 135757 67889 135758 65609 135758 65610 135758 67889 135759 65610 135759 68444 135759 68444 135760 65610 135760 67876 135760 65874 135761 65873 135761 65611 135761 65611 135762 65873 135762 65872 135762 65611 135763 65872 135763 67890 135763 67890 135764 65872 135764 65871 135764 67890 135765 65871 135765 67891 135765 67891 135766 65871 135766 65870 135766 67891 135767 65870 135767 67892 135767 67892 135768 65870 135768 67893 135768 67892 135769 67893 135769 67894 135769 67894 135770 67893 135770 68459 135770 67894 135771 68459 135771 69449 135771 69449 135772 68459 135772 68457 135772 69449 135773 68457 135773 67895 135773 67895 135774 68457 135774 67896 135774 67895 135775 67896 135775 69448 135775 69448 135776 67896 135776 68452 135776 69448 135777 68452 135777 69446 135777 69446 135778 68452 135778 68451 135778 69446 135779 68451 135779 67897 135779 67897 135780 68451 135780 68450 135780 67897 135781 68450 135781 65615 135781 65615 135782 68450 135782 65876 135782 65615 135783 65876 135783 67898 135783 67898 135784 65876 135784 65874 135784 67898 135785 65874 135785 65611 135785 68465 135786 68464 135786 67899 135786 67899 135787 68464 135787 68463 135787 67899 135788 68463 135788 67900 135788 67900 135789 68463 135789 68462 135789 67900 135790 68462 135790 69443 135790 69443 135791 68462 135791 67901 135791 69443 135792 67901 135792 67902 135792 67902 135793 67901 135793 68461 135793 67902 135794 68461 135794 65622 135794 65622 135795 68461 135795 65867 135795 65622 135796 65867 135796 65620 135796 65620 135797 65867 135797 65866 135797 65620 135798 65866 135798 65619 135798 65619 135799 65866 135799 65864 135799 65619 135800 65864 135800 65618 135800 65618 135801 65864 135801 65863 135801 65618 135802 65863 135802 65617 135802 65617 135803 65863 135803 67904 135803 65617 135804 67904 135804 67903 135804 67903 135805 67904 135805 67905 135805 67903 135806 67905 135806 67906 135806 67906 135807 67905 135807 67907 135807 67906 135808 67907 135808 67908 135808 67908 135809 67907 135809 68465 135809 67908 135810 68465 135810 67899 135810 67920 135811 67909 135811 67910 135811 67910 135812 67909 135812 65856 135812 67910 135813 65856 135813 67911 135813 67911 135814 65856 135814 65854 135814 67911 135815 65854 135815 65624 135815 65624 135816 65854 135816 67912 135816 65624 135817 67912 135817 69441 135817 69441 135818 67912 135818 68477 135818 69441 135819 68477 135819 69440 135819 69440 135820 68477 135820 68476 135820 69440 135821 68476 135821 69439 135821 69439 135822 68476 135822 68472 135822 69439 135823 68472 135823 69438 135823 69438 135824 68472 135824 67913 135824 69438 135825 67913 135825 69437 135825 69437 135826 67913 135826 67914 135826 69437 135827 67914 135827 67915 135827 67915 135828 67914 135828 68469 135828 67915 135829 68469 135829 65628 135829 65628 135830 68469 135830 67916 135830 65628 135831 67916 135831 67917 135831 67917 135832 67916 135832 67919 135832 67917 135833 67919 135833 67918 135833 67918 135834 67919 135834 67920 135834 67918 135835 67920 135835 67910 135835 65848 135836 67922 135836 67921 135836 67921 135837 67922 135837 67923 135837 67921 135838 67923 135838 67924 135838 67924 135839 67923 135839 65846 135839 67924 135840 65846 135840 67925 135840 67925 135841 65846 135841 67926 135841 67925 135842 67926 135842 67927 135842 67927 135843 67926 135843 67928 135843 67927 135844 67928 135844 67929 135844 67929 135845 67928 135845 68485 135845 67929 135846 68485 135846 67930 135846 67930 135847 68485 135847 68481 135847 67930 135848 68481 135848 67931 135848 67931 135849 68481 135849 67932 135849 67931 135850 67932 135850 69435 135850 69435 135851 67932 135851 67934 135851 69435 135852 67934 135852 67933 135852 67933 135853 67934 135853 67935 135853 67933 135854 67935 135854 65632 135854 65632 135855 67935 135855 65851 135855 65632 135856 65851 135856 67936 135856 67936 135857 65851 135857 65849 135857 67936 135858 65849 135858 65631 135858 65631 135859 65849 135859 65848 135859 65631 135860 65848 135860 67921 135860 67949 135861 65841 135861 67937 135861 67937 135862 65841 135862 67938 135862 67937 135863 67938 135863 65634 135863 65634 135864 67938 135864 67939 135864 65634 135865 67939 135865 65633 135865 65633 135866 67939 135866 67940 135866 65633 135867 67940 135867 67941 135867 67941 135868 67940 135868 68494 135868 67941 135869 68494 135869 69433 135869 69433 135870 68494 135870 67942 135870 69433 135871 67942 135871 67943 135871 67943 135872 67942 135872 68493 135872 67943 135873 68493 135873 67944 135873 67944 135874 68493 135874 68491 135874 67944 135875 68491 135875 67945 135875 67945 135876 68491 135876 68489 135876 67945 135877 68489 135877 69430 135877 69430 135878 68489 135878 67946 135878 69430 135879 67946 135879 69429 135879 69429 135880 67946 135880 67947 135880 69429 135881 67947 135881 67948 135881 67948 135882 67947 135882 65843 135882 67948 135883 65843 135883 65637 135883 65637 135884 65843 135884 67949 135884 65637 135885 67949 135885 67937 135885 65932 135886 67809 135886 68378 135886 68378 135887 67809 135887 67808 135887 68378 135888 67808 135888 68377 135888 68377 135889 67808 135889 67950 135889 68377 135890 67950 135890 68376 135890 68376 135891 67950 135891 67952 135891 68376 135892 67952 135892 67951 135892 67951 135893 67952 135893 67953 135893 67951 135894 67953 135894 67954 135894 67954 135895 67953 135895 67816 135895 67954 135896 67816 135896 68380 135896 68380 135897 67816 135897 67955 135897 68380 135898 67955 135898 67956 135898 67956 135899 67955 135899 67958 135899 67956 135900 67958 135900 67957 135900 67957 135901 67958 135901 67959 135901 67957 135902 67959 135902 67960 135902 67960 135903 67959 135903 67961 135903 67960 135904 67961 135904 68391 135904 68391 135905 67961 135905 67963 135905 68391 135906 67963 135906 67962 135906 67962 135907 67963 135907 67964 135907 67962 135908 67964 135908 68389 135908 68389 135909 67964 135909 67965 135909 68389 135910 67965 135910 67967 135910 67967 135911 67965 135911 67966 135911 67967 135912 67966 135912 68386 135912 68386 135913 67966 135913 67968 135913 68386 135914 67968 135914 66218 135914 66218 135915 67968 135915 66219 135915 68394 135916 68396 135916 68030 135916 65904 135917 67974 135917 67972 135917 67976 135918 67969 135918 65908 135918 65908 135919 65910 135919 67976 135919 67976 135920 65910 135920 68419 135920 67976 135921 68419 135921 67987 135921 67987 135922 68419 135922 68420 135922 65904 135923 67972 135923 68426 135923 68425 135924 67971 135924 68423 135924 68423 135925 67971 135925 68164 135925 68423 135926 68164 135926 67988 135926 68425 135927 67970 135927 67971 135927 67971 135928 67970 135928 68428 135928 67971 135929 68428 135929 67972 135929 67972 135930 68428 135930 68427 135930 67972 135931 68427 135931 68426 135931 68558 135932 67972 135932 67973 135932 67973 135933 67972 135933 67974 135933 67973 135934 67974 135934 67981 135934 67981 135935 67974 135935 67979 135935 68274 135936 68563 135936 68562 135936 68274 135937 68562 135937 67976 135937 68562 135938 67975 135938 67976 135938 67976 135939 67975 135939 67977 135939 67976 135940 67977 135940 67969 135940 67969 135941 67977 135941 67978 135941 67969 135942 67978 135942 67979 135942 67979 135943 67978 135943 67980 135943 67979 135944 67980 135944 67981 135944 68594 135945 68055 135945 68595 135945 68595 135946 68055 135946 68056 135946 68595 135947 68056 135947 68596 135947 68596 135948 68056 135948 67982 135948 67983 135949 67984 135949 68590 135949 68590 135950 67984 135950 68055 135950 68590 135951 68055 135951 67985 135951 67985 135952 68055 135952 68594 135952 66137 135953 66051 135953 68589 135953 68589 135954 66051 135954 67984 135954 68589 135955 67984 135955 67986 135955 67986 135956 67984 135956 67983 135956 68420 135957 68421 135957 67987 135957 67987 135958 68421 135958 67988 135958 67987 135959 67988 135959 68301 135959 68301 135960 67988 135960 68164 135960 68301 135961 68164 135961 67989 135961 67989 135962 68164 135962 67990 135962 67989 135963 67990 135963 67991 135963 67991 135964 67990 135964 67992 135964 67991 135965 67992 135965 68278 135965 68278 135966 67992 135966 68166 135966 68278 135967 68166 135967 68003 135967 68003 135968 68166 135968 67993 135968 67994 135969 67995 135969 68169 135969 67995 135970 68415 135970 68169 135970 68169 135971 68415 135971 68414 135971 68169 135972 68414 135972 67997 135972 67997 135973 68414 135973 67996 135973 67997 135974 67996 135974 67998 135974 67998 135975 68416 135975 67997 135975 67997 135976 68416 135976 67999 135976 67997 135977 67999 135977 67993 135977 67999 135978 65912 135978 67993 135978 67993 135979 65912 135979 68000 135979 67993 135980 68000 135980 68003 135980 68003 135981 68000 135981 68001 135981 68003 135982 68001 135982 65915 135982 65917 135983 68271 135983 68002 135983 68002 135984 68271 135984 68003 135984 68002 135985 68003 135985 68004 135985 68004 135986 68003 135986 65915 135986 65917 135987 68412 135987 68271 135987 68271 135988 68412 135988 67994 135988 68271 135989 67994 135989 68272 135989 68272 135990 67994 135990 68169 135990 68272 135991 68169 135991 68005 135991 68005 135992 68169 135992 68006 135992 68005 135993 68006 135993 68259 135993 68259 135994 68006 135994 68007 135994 68259 135995 68007 135995 68317 135995 68317 135996 68007 135996 68171 135996 68317 135997 68171 135997 68011 135997 68011 135998 68171 135998 68172 135998 68015 135999 68406 135999 68008 135999 68008 136000 68406 136000 68407 136000 68407 136001 68409 136001 68008 136001 68008 136002 68409 136002 68410 136002 68008 136003 68410 136003 68172 136003 68172 136004 68410 136004 68009 136004 68172 136005 68009 136005 68011 136005 68011 136006 68009 136006 65922 136006 68011 136007 65922 136007 68010 136007 68010 136008 68012 136008 68011 136008 68011 136009 68012 136009 65923 136009 68011 136010 65923 136010 68013 136010 68013 136011 65923 136011 65925 136011 68013 136012 65925 136012 68021 136012 68021 136013 65925 136013 68014 136013 68022 136014 68401 136014 68015 136014 68015 136015 68401 136015 68400 136015 68400 136016 68016 136016 68015 136016 68015 136017 68016 136017 68404 136017 68015 136018 68404 136018 68406 136018 68030 136019 68396 136019 68017 136019 68396 136020 68397 136020 68017 136020 68017 136021 68397 136021 68018 136021 68017 136022 68018 136022 68176 136022 68018 136023 68399 136023 68176 136023 68176 136024 68399 136024 68019 136024 68176 136025 68019 136025 68020 136025 68020 136026 68019 136026 68268 136026 68020 136027 68268 136027 68175 136027 68175 136028 68268 136028 68269 136028 68175 136029 68269 136029 68174 136029 68174 136030 68269 136030 68270 136030 68174 136031 68270 136031 68015 136031 68015 136032 68270 136032 68021 136032 68015 136033 68021 136033 68022 136033 68022 136034 68021 136034 68014 136034 68399 136035 65928 136035 68019 136035 68019 136036 65928 136036 68023 136036 68019 136037 68023 136037 68266 136037 68023 136038 68024 136038 68266 136038 68266 136039 68024 136039 68026 136039 68266 136040 68026 136040 68025 136040 68025 136041 68026 136041 68027 136041 68025 136042 68027 136042 68028 136042 68031 136043 68029 136043 68030 136043 68030 136044 68029 136044 68393 136044 68030 136045 68393 136045 68394 136045 68028 136046 68031 136046 68025 136046 68025 136047 68031 136047 68030 136047 68025 136048 68030 136048 68033 136048 68033 136049 68030 136049 68032 136049 68033 136050 68032 136050 68034 136050 68034 136051 68032 136051 68035 136051 68034 136052 68035 136052 68333 136052 68333 136053 68035 136053 68179 136053 68333 136054 68179 136054 68287 136054 68179 136055 68036 136055 68287 136055 68287 136056 68036 136056 68181 136056 68287 136057 68181 136057 68037 136057 68037 136058 68181 136058 68046 136058 68037 136059 68046 136059 68048 136059 68039 136060 68048 136060 65839 136060 65839 136061 68048 136061 68038 136061 65839 136062 65840 136062 68039 136062 68039 136063 65840 136063 65842 136063 68039 136064 65842 136064 68049 136064 68490 136065 68045 136065 68046 136065 68040 136066 65844 136066 68050 136066 68050 136067 65844 136067 68042 136067 68050 136068 68042 136068 68041 136068 68041 136069 68042 136069 68487 136069 68487 136070 68488 136070 68041 136070 68041 136071 68488 136071 68043 136071 68041 136072 68043 136072 68046 136072 68046 136073 68043 136073 68044 136073 68046 136074 68044 136074 68490 136074 68045 136075 68492 136075 68046 136075 68046 136076 68492 136076 68047 136076 68046 136077 68047 136077 68048 136077 68048 136078 68047 136078 65838 136078 68048 136079 65838 136079 68038 136079 65842 136080 68040 136080 68049 136080 68049 136081 68040 136081 68050 136081 68049 136082 68050 136082 68264 136082 68264 136083 68050 136083 68184 136083 68264 136084 68184 136084 68051 136084 68184 136085 68185 136085 68051 136085 68051 136086 68185 136086 68052 136086 68051 136087 68052 136087 68262 136087 68262 136088 68052 136088 68059 136088 68262 136089 68059 136089 68060 136089 68055 136090 68263 136090 65845 136090 68053 136091 68056 136091 68054 136091 68054 136092 68056 136092 68055 136092 68054 136093 68055 136093 65847 136093 65847 136094 68055 136094 65845 136094 68478 136095 68057 136095 65852 136095 65852 136096 68057 136096 68056 136096 65852 136097 68056 136097 65850 136097 65850 136098 68056 136098 68053 136098 68478 136099 68479 136099 68057 136099 68057 136100 68479 136100 68058 136100 68057 136101 68058 136101 68059 136101 68058 136102 68480 136102 68059 136102 68059 136103 68480 136103 68482 136103 68059 136104 68482 136104 68060 136104 68060 136105 68482 136105 68483 136105 68060 136106 68483 136106 68484 136106 68484 136107 68486 136107 68060 136107 68060 136108 68486 136108 68061 136108 68060 136109 68061 136109 68263 136109 68263 136110 68061 136110 68062 136110 68263 136111 68062 136111 65845 136111 65824 136112 68063 136112 68150 136112 68150 136113 68063 136113 68064 136113 68150 136114 68064 136114 68149 136114 68149 136115 68064 136115 68065 136115 68065 136116 68064 136116 68066 136116 68065 136117 68066 136117 68148 136117 68148 136118 68066 136118 68067 136118 68067 136119 68066 136119 68068 136119 68067 136120 68068 136120 68145 136120 68145 136121 68068 136121 68144 136121 68144 136122 68068 136122 68203 136122 68144 136123 68203 136123 68143 136123 68143 136124 68203 136124 68142 136124 68142 136125 68203 136125 68069 136125 68142 136126 68069 136126 68140 136126 68140 136127 68069 136127 68139 136127 68139 136128 68069 136128 68070 136128 68139 136129 68070 136129 68138 136129 68138 136130 68070 136130 68136 136130 68136 136131 68070 136131 68072 136131 68136 136132 68072 136132 68071 136132 68071 136133 68072 136133 68073 136133 68073 136134 68072 136134 68076 136134 68073 136135 68076 136135 68134 136135 68074 136136 68075 136136 68076 136136 68076 136137 68075 136137 68133 136137 68076 136138 68133 136138 68134 136138 68197 136139 68195 136139 68080 136139 68080 136140 68077 136140 68197 136140 68197 136141 68077 136141 68130 136141 68197 136142 68130 136142 68074 136142 68074 136143 68130 136143 68131 136143 68074 136144 68131 136144 68075 136144 68078 136145 68193 136145 68154 136145 68154 136146 68153 136146 68078 136146 68078 136147 68153 136147 68079 136147 68078 136148 68079 136148 68195 136148 68195 136149 68079 136149 68128 136149 68195 136150 68128 136150 68080 136150 68081 136151 68192 136151 68089 136151 68089 136152 68082 136152 68081 136152 68081 136153 68082 136153 68083 136153 68081 136154 68083 136154 68193 136154 68193 136155 68083 136155 68084 136155 68193 136156 68084 136156 68154 136156 68191 136157 68085 136157 68123 136157 68123 136158 68086 136158 68191 136158 68191 136159 68086 136159 68087 136159 68191 136160 68087 136160 68192 136160 68192 136161 68087 136161 68088 136161 68192 136162 68088 136162 68089 136162 68090 136163 68091 136163 68092 136163 68092 136164 68091 136164 68220 136164 68092 136165 68220 136165 68093 136165 68093 136166 68220 136166 68165 136166 68165 136167 68220 136167 68094 136167 68165 136168 68094 136168 68095 136168 68095 136169 68094 136169 68096 136169 68096 136170 68094 136170 68218 136170 68096 136171 68218 136171 68097 136171 68097 136172 68218 136172 68167 136172 68167 136173 68218 136173 68098 136173 68167 136174 68098 136174 68168 136174 68168 136175 68098 136175 68170 136175 68170 136176 68098 136176 68216 136176 68170 136177 68216 136177 68099 136177 68099 136178 68216 136178 68100 136178 68100 136179 68216 136179 68214 136179 68100 136180 68214 136180 68101 136180 68101 136181 68214 136181 68102 136181 68102 136182 68214 136182 68212 136182 68102 136183 68212 136183 68173 136183 68173 136184 68212 136184 68103 136184 68103 136185 68212 136185 68105 136185 68103 136186 68105 136186 68104 136186 68104 136187 68105 136187 68106 136187 68106 136188 68105 136188 68107 136188 68106 136189 68107 136189 68177 136189 68209 136190 68108 136190 68112 136190 68112 136191 68109 136191 68209 136191 68209 136192 68109 136192 68178 136192 68209 136193 68178 136193 68107 136193 68107 136194 68178 136194 68110 136194 68107 136195 68110 136195 68177 136195 68207 136196 68206 136196 68183 136196 68183 136197 68182 136197 68207 136197 68207 136198 68182 136198 68111 136198 68207 136199 68111 136199 68108 136199 68108 136200 68111 136200 68180 136200 68108 136201 68180 136201 68112 136201 68114 136202 68119 136202 68186 136202 68186 136203 68113 136203 68114 136203 68114 136204 68113 136204 68115 136204 68114 136205 68115 136205 68206 136205 68206 136206 68115 136206 68116 136206 68206 136207 68116 136207 68183 136207 68204 136208 68117 136208 68118 136208 68118 136209 68189 136209 68204 136209 68204 136210 68189 136210 68188 136210 68204 136211 68188 136211 68119 136211 68119 136212 68188 136212 68187 136212 68119 136213 68187 136213 68186 136213 68120 136214 68121 136214 68122 136214 68526 136215 68120 136215 68123 136215 68123 136216 68120 136216 68122 136216 68123 136217 68122 136217 68086 136217 68152 136218 68124 136218 65824 136218 68125 136219 65824 136219 68126 136219 68126 136220 65824 136220 68124 136220 68126 136221 68124 136221 68525 136221 68525 136222 68124 136222 68582 136222 66203 136223 66205 136223 68153 136223 68153 136224 66205 136224 66199 136224 68153 136225 66199 136225 68079 136225 68079 136226 66199 136226 68127 136226 68079 136227 68127 136227 68128 136227 68128 136228 68127 136228 68129 136228 68128 136229 68129 136229 68080 136229 68080 136230 68129 136230 66197 136230 68080 136231 66197 136231 68077 136231 68077 136232 66197 136232 66187 136232 68077 136233 66187 136233 68130 136233 68130 136234 66187 136234 66189 136234 68130 136235 66189 136235 68131 136235 68131 136236 66189 136236 66184 136236 68131 136237 66184 136237 68075 136237 68075 136238 66184 136238 68132 136238 68075 136239 68132 136239 68133 136239 68133 136240 68132 136240 66182 136240 68133 136241 66182 136241 68134 136241 68134 136242 66182 136242 68135 136242 68134 136243 68135 136243 68073 136243 68073 136244 68135 136244 66174 136244 68073 136245 66174 136245 68071 136245 68071 136246 66174 136246 68137 136246 68071 136247 68137 136247 68136 136247 68136 136248 68137 136248 66170 136248 68136 136249 66170 136249 68138 136249 68138 136250 66170 136250 66169 136250 68138 136251 66169 136251 68139 136251 68139 136252 66169 136252 66168 136252 68139 136253 66168 136253 68140 136253 68140 136254 66168 136254 68141 136254 68140 136255 68141 136255 68142 136255 68142 136256 68141 136256 66166 136256 68142 136257 66166 136257 68143 136257 68143 136258 66166 136258 66156 136258 68143 136259 66156 136259 68144 136259 68144 136260 66156 136260 68146 136260 68144 136261 68146 136261 68145 136261 68145 136262 68146 136262 68147 136262 68145 136263 68147 136263 68067 136263 68067 136264 68147 136264 66154 136264 68067 136265 66154 136265 68148 136265 68148 136266 66154 136266 66153 136266 68148 136267 66153 136267 68065 136267 68065 136268 66153 136268 66152 136268 68065 136269 66152 136269 68149 136269 68149 136270 66152 136270 66142 136270 68149 136271 66142 136271 68150 136271 68150 136272 66142 136272 68151 136272 68150 136273 68151 136273 65824 136273 65824 136274 68151 136274 66144 136274 65824 136275 66144 136275 68152 136275 68153 136276 68154 136276 66203 136276 66203 136277 68154 136277 68084 136277 66203 136278 68084 136278 68155 136278 68155 136279 68084 136279 66211 136279 68084 136280 68083 136280 66211 136280 66211 136281 68083 136281 68082 136281 66211 136282 68082 136282 66213 136282 66213 136283 68082 136283 68156 136283 68082 136284 68089 136284 68156 136284 68156 136285 68089 136285 68088 136285 68156 136286 68088 136286 66215 136286 66215 136287 68088 136287 68087 136287 66215 136288 68087 136288 68157 136288 68157 136289 68087 136289 68086 136289 68157 136290 68086 136290 66131 136290 66131 136291 68086 136291 68122 136291 66131 136292 68122 136292 66133 136292 68163 136293 68158 136293 68092 136293 68092 136294 68158 136294 68159 136294 68092 136295 68159 136295 68090 136295 68090 136296 68159 136296 68531 136296 68160 136297 67982 136297 68056 136297 65827 136298 68161 136298 68160 136298 68160 136299 68161 136299 68162 136299 68160 136300 68162 136300 68598 136300 68558 136301 68163 136301 67972 136301 67972 136302 68163 136302 68092 136302 67972 136303 68092 136303 67971 136303 67971 136304 68092 136304 68093 136304 67971 136305 68093 136305 68164 136305 68164 136306 68093 136306 68165 136306 68164 136307 68165 136307 67990 136307 67990 136308 68165 136308 68095 136308 67990 136309 68095 136309 67992 136309 67992 136310 68095 136310 68096 136310 67992 136311 68096 136311 68166 136311 68166 136312 68096 136312 68097 136312 68166 136313 68097 136313 67993 136313 67993 136314 68097 136314 68167 136314 67993 136315 68167 136315 67997 136315 67997 136316 68167 136316 68168 136316 67997 136317 68168 136317 68169 136317 68169 136318 68168 136318 68170 136318 68169 136319 68170 136319 68006 136319 68006 136320 68170 136320 68099 136320 68006 136321 68099 136321 68007 136321 68007 136322 68099 136322 68100 136322 68007 136323 68100 136323 68171 136323 68171 136324 68100 136324 68101 136324 68171 136325 68101 136325 68172 136325 68172 136326 68101 136326 68102 136326 68172 136327 68102 136327 68008 136327 68103 136328 68174 136328 68015 136328 68008 136329 68102 136329 68015 136329 68015 136330 68102 136330 68173 136330 68015 136331 68173 136331 68103 136331 68106 136332 68020 136332 68175 136332 68174 136333 68103 136333 68175 136333 68175 136334 68103 136334 68104 136334 68175 136335 68104 136335 68106 136335 68020 136336 68106 136336 68176 136336 68176 136337 68106 136337 68177 136337 68176 136338 68177 136338 68017 136338 68017 136339 68177 136339 68110 136339 68017 136340 68110 136340 68030 136340 68030 136341 68110 136341 68178 136341 68030 136342 68178 136342 68032 136342 68032 136343 68178 136343 68109 136343 68032 136344 68109 136344 68035 136344 68035 136345 68109 136345 68112 136345 68035 136346 68112 136346 68179 136346 68179 136347 68112 136347 68180 136347 68179 136348 68180 136348 68036 136348 68036 136349 68180 136349 68111 136349 68036 136350 68111 136350 68181 136350 68181 136351 68111 136351 68182 136351 68181 136352 68182 136352 68046 136352 68046 136353 68182 136353 68183 136353 68046 136354 68183 136354 68041 136354 68041 136355 68183 136355 68116 136355 68041 136356 68116 136356 68050 136356 68050 136357 68116 136357 68115 136357 68050 136358 68115 136358 68184 136358 68184 136359 68115 136359 68113 136359 68184 136360 68113 136360 68185 136360 68185 136361 68113 136361 68186 136361 68185 136362 68186 136362 68052 136362 68052 136363 68186 136363 68187 136363 68052 136364 68187 136364 68059 136364 68059 136365 68187 136365 68188 136365 68059 136366 68188 136366 68057 136366 68057 136367 68188 136367 68189 136367 68057 136368 68189 136368 68056 136368 68056 136369 68189 136369 68118 136369 68056 136370 68118 136370 68160 136370 68160 136371 68118 136371 68190 136371 68160 136372 68190 136372 65827 136372 65814 136373 68085 136373 68191 136373 65814 136374 68191 136374 70667 136374 70667 136375 68191 136375 68192 136375 70667 136376 68192 136376 70666 136376 70666 136377 68192 136377 68081 136377 70666 136378 68081 136378 70664 136378 70664 136379 68081 136379 68193 136379 70664 136380 68193 136380 70661 136380 70661 136381 68193 136381 68078 136381 70661 136382 68078 136382 68194 136382 68194 136383 68078 136383 68195 136383 68194 136384 68195 136384 68196 136384 68196 136385 68195 136385 68197 136385 68196 136386 68197 136386 68198 136386 68198 136387 68197 136387 68074 136387 68198 136388 68074 136388 68199 136388 68199 136389 68074 136389 68076 136389 68199 136390 68076 136390 70657 136390 70657 136391 68076 136391 68072 136391 70657 136392 68072 136392 68200 136392 68200 136393 68072 136393 68070 136393 68200 136394 68070 136394 68201 136394 68201 136395 68070 136395 68069 136395 68201 136396 68069 136396 68202 136396 68202 136397 68069 136397 68203 136397 68202 136398 68203 136398 70655 136398 70655 136399 68203 136399 68068 136399 70655 136400 68068 136400 70654 136400 70654 136401 68068 136401 68066 136401 70654 136402 68066 136402 70653 136402 70653 136403 68066 136403 68064 136403 70653 136404 68064 136404 70652 136404 70652 136405 68064 136405 68063 136405 70652 136406 68063 136406 65811 136406 68548 136407 68117 136407 68204 136407 68548 136408 68204 136408 70650 136408 70650 136409 68204 136409 68119 136409 70650 136410 68119 136410 70647 136410 70647 136411 68119 136411 68114 136411 70647 136412 68114 136412 68205 136412 68205 136413 68114 136413 68206 136413 68205 136414 68206 136414 68208 136414 68208 136415 68206 136415 68207 136415 68208 136416 68207 136416 70645 136416 70645 136417 68207 136417 68108 136417 70645 136418 68108 136418 70644 136418 70644 136419 68108 136419 68209 136419 70644 136420 68209 136420 70643 136420 70643 136421 68209 136421 68107 136421 70643 136422 68107 136422 68210 136422 68210 136423 68107 136423 68105 136423 68210 136424 68105 136424 68211 136424 68211 136425 68105 136425 68212 136425 68211 136426 68212 136426 68213 136426 68213 136427 68212 136427 68214 136427 68213 136428 68214 136428 70641 136428 70641 136429 68214 136429 68216 136429 70641 136430 68216 136430 68215 136430 68215 136431 68216 136431 68098 136431 68215 136432 68098 136432 68217 136432 68217 136433 68098 136433 68218 136433 68217 136434 68218 136434 70640 136434 70640 136435 68218 136435 68094 136435 70640 136436 68094 136436 68219 136436 68219 136437 68094 136437 68220 136437 68219 136438 68220 136438 70639 136438 70639 136439 68220 136439 68091 136439 70639 136440 68091 136440 68683 136440 68241 136441 65980 136441 68368 136441 66010 136442 68352 136442 68221 136442 68221 136443 68352 136443 66118 136443 68221 136444 66118 136444 68257 136444 66010 136445 66008 136445 68352 136445 68352 136446 66008 136446 68222 136446 68352 136447 68222 136447 68223 136447 68223 136448 68222 136448 68224 136448 68223 136449 68224 136449 66007 136449 66007 136450 68225 136450 68223 136450 68223 136451 68225 136451 66005 136451 68223 136452 66005 136452 68355 136452 66005 136453 68226 136453 68355 136453 68355 136454 68226 136454 66004 136454 68355 136455 66004 136455 68227 136455 68227 136456 66004 136456 66003 136456 68227 136457 66003 136457 66001 136457 66001 136458 66000 136458 68227 136458 68227 136459 66000 136459 65999 136459 68227 136460 65999 136460 68358 136460 65999 136461 68228 136461 68358 136461 68358 136462 68228 136462 65997 136462 68358 136463 65997 136463 68229 136463 68229 136464 65997 136464 68230 136464 68229 136465 68230 136465 68231 136465 68231 136466 68232 136466 68229 136466 68229 136467 68232 136467 68233 136467 68229 136468 68233 136468 68362 136468 68362 136469 68233 136469 65995 136469 68362 136470 65995 136470 68234 136470 68234 136471 65994 136471 68362 136471 68362 136472 65994 136472 65992 136472 68362 136473 65992 136473 68363 136473 68235 136474 68364 136474 65990 136474 65990 136475 68364 136475 68363 136475 65990 136476 68363 136476 65991 136476 65991 136477 68363 136477 65992 136477 68235 136478 65988 136478 68364 136478 68364 136479 65988 136479 68236 136479 68364 136480 68236 136480 68366 136480 68366 136481 68236 136481 68237 136481 68366 136482 68237 136482 68238 136482 68238 136483 65986 136483 68366 136483 68366 136484 65986 136484 65984 136484 68366 136485 65984 136485 68239 136485 65984 136486 68240 136486 68239 136486 68239 136487 68240 136487 65982 136487 68239 136488 65982 136488 68368 136488 68368 136489 65982 136489 65981 136489 68368 136490 65981 136490 68241 136490 68243 136491 68371 136491 65977 136491 65977 136492 68371 136492 68368 136492 65977 136493 68368 136493 68242 136493 68242 136494 68368 136494 65980 136494 68243 136495 65976 136495 68371 136495 68371 136496 65976 136496 65975 136496 68371 136497 65975 136497 68244 136497 65975 136498 68245 136498 68244 136498 68244 136499 68245 136499 68246 136499 68244 136500 68246 136500 68247 136500 68247 136501 68246 136501 65973 136501 68247 136502 65973 136502 65971 136502 65971 136503 68248 136503 68247 136503 68247 136504 68248 136504 68250 136504 68247 136505 68250 136505 68249 136505 68250 136506 65968 136506 68249 136506 68249 136507 65968 136507 68251 136507 68249 136508 68251 136508 68252 136508 68252 136509 68251 136509 68253 136509 68252 136510 68253 136510 68255 136510 68293 136511 65946 136511 68254 136511 68254 136512 65946 136512 68252 136512 68254 136513 68252 136513 65966 136513 65966 136514 68252 136514 68255 136514 68348 136515 68256 136515 68257 136515 68258 136516 66105 136516 68286 136516 68340 136517 68343 136517 68345 136517 68311 136518 68313 136518 68315 136518 68275 136519 68299 136519 68297 136519 68259 136520 68317 136520 68318 136520 68034 136521 68333 136521 68329 136521 68287 136522 68037 136522 68289 136522 68264 136523 68051 136523 68346 136523 66051 136524 68260 136524 68261 136524 68291 136525 68055 136525 68261 136525 68261 136526 68055 136526 67984 136526 68261 136527 67984 136527 66051 136527 68051 136528 68262 136528 68292 136528 68292 136529 68262 136529 68060 136529 68292 136530 68060 136530 68291 136530 68291 136531 68060 136531 68263 136531 68291 136532 68263 136532 68055 136532 68048 136533 68039 136533 68340 136533 68340 136534 68039 136534 68049 136534 68340 136535 68049 136535 68343 136535 68343 136536 68049 136536 68264 136536 68025 136537 68033 136537 68265 136537 68265 136538 68033 136538 68034 136538 68327 136539 68266 136539 68025 136539 68266 136540 68327 136540 68019 136540 68019 136541 68327 136541 68267 136541 68019 136542 68267 136542 68268 136542 68268 136543 68267 136543 68281 136543 68268 136544 68281 136544 68269 136544 68269 136545 68281 136545 68282 136545 68269 136546 68282 136546 68270 136546 68270 136547 68282 136547 68021 136547 68021 136548 68282 136548 68284 136548 68021 136549 68284 136549 68013 136549 68013 136550 68284 136550 68011 136550 68011 136551 68284 136551 68319 136551 68011 136552 68319 136552 68317 136552 68003 136553 68271 136553 68311 136553 68311 136554 68271 136554 68272 136554 68311 136555 68272 136555 68313 136555 68313 136556 68272 136556 68005 136556 68313 136557 68005 136557 68259 136557 68301 136558 67989 136558 68305 136558 68305 136559 67989 136559 67991 136559 67976 136560 67987 136560 68302 136560 68302 136561 67987 136561 68301 136561 68273 136562 68565 136562 68275 136562 67976 136563 68299 136563 68274 136563 68274 136564 68299 136564 68275 136564 68274 136565 68275 136565 68563 136565 68563 136566 68275 136566 68565 136566 68294 136567 65963 136567 66012 136567 68307 136568 68276 136568 68277 136568 67991 136569 68278 136569 68277 136569 68277 136570 68278 136570 68310 136570 68277 136571 68310 136571 68307 136571 68307 136572 68310 136572 68279 136572 68307 136573 68279 136573 66102 136573 66102 136574 68279 136574 68312 136574 68327 136575 68280 136575 68267 136575 68267 136576 68280 136576 68324 136576 68267 136577 68324 136577 68281 136577 68281 136578 68324 136578 68322 136578 68281 136579 68322 136579 68282 136579 68282 136580 68322 136580 68283 136580 68282 136581 68283 136581 68284 136581 68284 136582 68283 136582 68285 136582 68284 136583 68285 136583 68319 136583 68319 136584 68285 136584 68286 136584 68290 136585 68334 136585 68288 136585 68333 136586 68287 136586 68288 136586 68288 136587 68287 136587 68289 136587 68288 136588 68289 136588 68290 136588 68290 136589 68289 136589 68341 136589 68290 136590 68341 136590 66111 136590 66111 136591 68341 136591 66113 136591 68260 136592 68256 136592 68261 136592 68261 136593 68256 136593 68348 136593 68261 136594 68348 136594 68291 136594 68291 136595 68348 136595 68350 136595 68291 136596 68350 136596 68292 136596 68292 136597 68350 136597 68347 136597 68293 136598 65963 136598 66093 136598 66093 136599 65963 136599 68294 136599 66093 136600 68294 136600 68295 136600 68296 136601 68273 136601 66012 136601 66012 136602 68273 136602 68275 136602 66012 136603 68275 136603 68294 136603 68294 136604 68275 136604 68297 136604 68294 136605 68297 136605 68295 136605 68295 136606 68297 136606 66096 136606 68300 136607 66094 136607 68298 136607 67976 136608 68302 136608 68299 136608 68299 136609 68302 136609 68300 136609 68299 136610 68300 136610 68297 136610 68297 136611 68300 136611 68298 136611 68297 136612 68298 136612 66096 136612 68301 136613 68305 136613 68302 136613 68302 136614 68305 136614 68303 136614 68302 136615 68303 136615 68300 136615 68300 136616 68303 136616 68304 136616 68300 136617 68304 136617 66094 136617 67991 136618 68277 136618 68305 136618 68305 136619 68277 136619 68276 136619 68305 136620 68276 136620 68303 136620 68303 136621 68276 136621 68309 136621 68303 136622 68309 136622 68304 136622 66102 136623 68306 136623 68307 136623 68307 136624 68306 136624 66100 136624 68307 136625 66100 136625 68276 136625 68276 136626 66100 136626 68308 136626 68276 136627 68308 136627 68309 136627 68278 136628 68003 136628 68310 136628 68310 136629 68003 136629 68311 136629 68310 136630 68311 136630 68279 136630 68279 136631 68311 136631 68315 136631 68279 136632 68315 136632 68312 136632 68312 136633 68315 136633 66101 136633 68314 136634 66103 136634 68316 136634 68259 136635 68318 136635 68313 136635 68313 136636 68318 136636 68314 136636 68313 136637 68314 136637 68315 136637 68315 136638 68314 136638 68316 136638 68315 136639 68316 136639 66101 136639 68317 136640 68319 136640 68318 136640 68318 136641 68319 136641 68286 136641 68318 136642 68286 136642 68314 136642 68314 136643 68286 136643 66105 136643 68314 136644 66105 136644 66103 136644 68258 136645 68286 136645 66107 136645 66107 136646 68286 136646 68285 136646 66107 136647 68285 136647 68320 136647 68320 136648 68285 136648 68283 136648 68320 136649 68283 136649 68321 136649 68321 136650 68283 136650 68323 136650 68323 136651 68283 136651 68322 136651 68323 136652 68322 136652 68325 136652 68325 136653 68322 136653 68324 136653 68325 136654 68324 136654 68326 136654 68326 136655 68324 136655 68280 136655 68326 136656 68280 136656 66109 136656 68331 136657 68332 136657 68328 136657 68025 136658 68265 136658 68327 136658 68327 136659 68265 136659 68331 136659 68327 136660 68331 136660 68280 136660 68280 136661 68331 136661 68328 136661 68280 136662 68328 136662 66109 136662 68034 136663 68329 136663 68265 136663 68265 136664 68329 136664 68330 136664 68265 136665 68330 136665 68331 136665 68331 136666 68330 136666 68335 136666 68331 136667 68335 136667 68332 136667 68333 136668 68288 136668 68329 136668 68329 136669 68288 136669 68334 136669 68329 136670 68334 136670 68330 136670 68330 136671 68334 136671 68339 136671 68330 136672 68339 136672 68335 136672 66111 136673 68336 136673 68290 136673 68290 136674 68336 136674 68337 136674 68290 136675 68337 136675 68334 136675 68334 136676 68337 136676 68338 136676 68334 136677 68338 136677 68339 136677 68037 136678 68048 136678 68289 136678 68289 136679 68048 136679 68340 136679 68289 136680 68340 136680 68341 136680 68341 136681 68340 136681 68345 136681 68341 136682 68345 136682 66113 136682 66113 136683 68345 136683 66116 136683 68344 136684 68342 136684 66115 136684 68264 136685 68346 136685 68343 136685 68343 136686 68346 136686 68344 136686 68343 136687 68344 136687 68345 136687 68345 136688 68344 136688 66115 136688 68345 136689 66115 136689 66116 136689 68051 136690 68292 136690 68346 136690 68346 136691 68292 136691 68347 136691 68346 136692 68347 136692 68344 136692 68344 136693 68347 136693 66117 136693 68344 136694 66117 136694 68342 136694 68257 136695 66119 136695 68348 136695 68348 136696 66119 136696 68349 136696 68348 136697 68349 136697 68350 136697 68350 136698 68349 136698 66121 136698 68350 136699 66121 136699 68347 136699 68347 136700 66121 136700 68351 136700 68347 136701 68351 136701 66117 136701 68353 136702 66118 136702 68352 136702 68353 136703 68352 136703 68354 136703 68354 136704 68352 136704 68223 136704 68354 136705 68223 136705 68356 136705 68356 136706 68223 136706 68355 136706 68356 136707 68355 136707 70890 136707 70890 136708 68355 136708 68227 136708 70890 136709 68227 136709 68357 136709 68357 136710 68227 136710 68358 136710 68357 136711 68358 136711 68359 136711 68359 136712 68358 136712 68229 136712 68359 136713 68229 136713 68360 136713 68360 136714 68229 136714 68362 136714 68360 136715 68362 136715 68361 136715 68361 136716 68362 136716 68363 136716 68361 136717 68363 136717 70876 136717 70876 136718 68363 136718 68364 136718 70876 136719 68364 136719 68365 136719 68365 136720 68364 136720 68366 136720 68365 136721 68366 136721 68367 136721 68367 136722 68366 136722 68239 136722 68367 136723 68239 136723 68369 136723 68369 136724 68239 136724 68368 136724 68369 136725 68368 136725 68370 136725 68370 136726 68368 136726 68371 136726 68370 136727 68371 136727 68372 136727 68372 136728 68371 136728 68244 136728 68372 136729 68244 136729 68373 136729 68373 136730 68244 136730 68247 136730 68373 136731 68247 136731 70880 136731 70880 136732 68247 136732 68249 136732 70880 136733 68249 136733 70881 136733 70881 136734 68249 136734 68252 136734 70881 136735 68252 136735 68374 136735 68374 136736 68252 136736 65946 136736 68374 136737 65946 136737 70884 136737 67954 136738 68382 136738 67951 136738 67951 136739 68382 136739 68375 136739 67951 136740 68375 136740 68376 136740 68376 136741 68375 136741 66714 136741 68376 136742 66714 136742 68377 136742 68377 136743 66714 136743 68379 136743 68377 136744 68379 136744 68378 136744 68378 136745 68379 136745 66712 136745 68378 136746 66712 136746 65932 136746 65932 136747 66712 136747 66710 136747 67956 136748 68383 136748 68380 136748 68380 136749 68383 136749 68381 136749 68380 136750 68381 136750 67954 136750 67954 136751 68381 136751 67761 136751 67954 136752 67761 136752 68382 136752 67957 136753 66717 136753 67956 136753 67956 136754 66717 136754 70866 136754 67956 136755 70866 136755 68383 136755 68391 136756 66690 136756 67960 136756 67960 136757 66690 136757 68384 136757 67960 136758 68384 136758 67957 136758 67957 136759 68384 136759 68385 136759 67957 136760 68385 136760 66717 136760 66218 136761 66694 136761 68386 136761 68386 136762 66694 136762 66693 136762 68386 136763 66693 136763 67967 136763 67967 136764 66693 136764 68387 136764 67967 136765 68387 136765 68389 136765 68389 136766 68387 136766 68388 136766 68389 136767 68388 136767 67962 136767 67962 136768 68388 136768 68390 136768 67962 136769 68390 136769 68391 136769 68391 136770 68390 136770 66691 136770 68391 136771 66691 136771 66690 136771 68029 136772 68392 136772 67820 136772 68029 136773 67820 136773 68393 136773 68393 136774 67820 136774 67817 136774 68393 136775 67817 136775 68394 136775 68394 136776 67817 136776 68395 136776 68394 136777 68395 136777 68396 136777 68396 136778 68395 136778 67828 136778 68396 136779 67828 136779 68397 136779 68397 136780 67828 136780 68398 136780 68397 136781 68398 136781 68018 136781 68018 136782 68398 136782 67827 136782 68018 136783 67827 136783 68399 136783 68399 136784 67827 136784 65927 136784 68399 136785 65927 136785 65928 136785 68016 136786 68400 136786 68403 136786 68403 136787 68400 136787 68401 136787 68403 136788 68401 136788 68402 136788 68402 136789 68401 136789 68022 136789 68402 136790 68022 136790 67836 136790 68016 136791 68403 136791 68404 136791 68404 136792 68403 136792 68405 136792 68404 136793 68405 136793 68406 136793 68406 136794 68405 136794 68408 136794 68406 136795 68408 136795 68407 136795 68407 136796 68408 136796 68409 136796 68409 136797 68408 136797 68411 136797 68409 136798 68411 136798 68410 136798 68410 136799 68411 136799 65920 136799 68410 136800 65920 136800 68009 136800 67998 136801 67996 136801 68417 136801 68412 136802 65919 136802 67842 136802 68412 136803 67842 136803 67994 136803 67994 136804 67842 136804 68413 136804 67994 136805 68413 136805 67995 136805 67995 136806 68413 136806 67841 136806 67995 136807 67841 136807 68415 136807 68417 136808 67996 136808 67841 136808 67841 136809 67996 136809 68414 136809 67841 136810 68414 136810 68415 136810 67998 136811 68417 136811 68416 136811 68416 136812 68417 136812 68418 136812 68416 136813 68418 136813 67999 136813 67999 136814 68418 136814 65913 136814 67999 136815 65913 136815 65912 136815 68419 136816 65911 136816 68420 136816 68420 136817 65911 136817 67854 136817 68420 136818 67854 136818 68421 136818 68421 136819 67854 136819 67852 136819 68421 136820 67852 136820 67988 136820 67988 136821 67852 136821 68422 136821 67988 136822 68422 136822 68423 136822 68423 136823 68422 136823 68424 136823 68423 136824 68424 136824 68425 136824 67851 136825 65903 136825 68426 136825 68426 136826 68427 136826 67851 136826 67851 136827 68427 136827 68428 136827 67851 136828 68428 136828 68424 136828 68424 136829 68428 136829 67970 136829 68424 136830 67970 136830 68425 136830 66126 136831 65902 136831 66127 136831 66127 136832 65902 136832 68430 136832 66127 136833 68430 136833 68429 136833 68429 136834 68430 136834 68431 136834 68431 136835 68430 136835 67860 136835 68431 136836 67860 136836 68432 136836 68432 136837 67860 136837 68433 136837 68432 136838 68433 136838 66129 136838 66129 136839 68433 136839 68434 136839 66129 136840 68434 136840 66132 136840 66132 136841 68434 136841 68435 136841 66132 136842 68435 136842 66123 136842 65893 136843 66124 136843 68435 136843 68435 136844 66124 136844 68436 136844 68435 136845 68436 136845 66123 136845 66207 136846 67864 136846 66208 136846 66208 136847 67864 136847 67866 136847 66208 136848 67866 136848 68437 136848 68437 136849 67866 136849 66209 136849 66209 136850 67866 136850 67867 136850 66209 136851 67867 136851 68438 136851 68438 136852 67867 136852 66210 136852 66210 136853 67867 136853 68440 136853 66210 136854 68440 136854 68439 136854 68439 136855 68440 136855 68441 136855 68439 136856 68441 136856 68442 136856 68442 136857 68441 136857 67868 136857 68442 136858 67868 136858 68443 136858 68443 136859 67868 136859 67869 136859 68443 136860 67869 136860 66200 136860 66191 136861 67889 136861 68444 136861 66191 136862 68444 136862 66192 136862 66192 136863 68444 136863 68445 136863 66192 136864 68445 136864 66193 136864 66193 136865 68445 136865 67877 136865 66193 136866 67877 136866 66194 136866 66194 136867 67877 136867 68446 136867 66194 136868 68446 136868 66195 136868 66195 136869 68446 136869 68447 136869 66195 136870 68447 136870 66196 136870 66196 136871 68447 136871 67879 136871 66196 136872 67879 136872 68448 136872 68448 136873 67879 136873 67881 136873 68448 136874 67881 136874 66186 136874 68449 136875 68450 136875 68451 136875 68449 136876 68451 136876 66178 136876 66178 136877 68451 136877 68452 136877 66178 136878 68452 136878 68453 136878 68453 136879 68452 136879 68454 136879 68454 136880 68452 136880 67896 136880 68454 136881 67896 136881 66171 136881 66171 136882 67896 136882 68455 136882 68455 136883 67896 136883 68457 136883 68455 136884 68457 136884 68456 136884 68456 136885 68457 136885 68458 136885 68458 136886 68457 136886 68459 136886 68458 136887 68459 136887 66179 136887 66179 136888 68459 136888 67893 136888 66179 136889 67893 136889 68460 136889 65869 136890 68461 136890 67901 136890 65869 136891 67901 136891 66161 136891 66161 136892 67901 136892 68462 136892 66161 136893 68462 136893 66160 136893 66160 136894 68462 136894 68463 136894 66160 136895 68463 136895 66162 136895 66162 136896 68463 136896 68464 136896 66162 136897 68464 136897 66164 136897 66164 136898 68464 136898 68465 136898 66164 136899 68465 136899 68466 136899 68466 136900 68465 136900 67907 136900 68466 136901 67907 136901 68467 136901 68467 136902 67907 136902 67905 136902 68467 136903 67905 136903 65861 136903 66143 136904 67916 136904 68468 136904 68468 136905 67916 136905 68469 136905 68468 136906 68469 136906 68470 136906 68470 136907 68469 136907 67914 136907 68470 136908 67914 136908 66145 136908 66145 136909 67914 136909 67913 136909 66145 136910 67913 136910 68471 136910 68471 136911 67913 136911 68472 136911 68471 136912 68472 136912 68473 136912 68473 136913 68472 136913 68474 136913 68474 136914 68472 136914 68476 136914 68474 136915 68476 136915 66147 136915 66147 136916 68476 136916 68475 136916 68475 136917 68476 136917 68477 136917 68475 136918 68477 136918 66148 136918 68478 136919 65852 136919 65851 136919 68478 136920 65851 136920 68479 136920 68479 136921 65851 136921 67935 136921 68479 136922 67935 136922 68058 136922 68058 136923 67935 136923 67934 136923 68058 136924 67934 136924 68480 136924 68480 136925 67934 136925 67932 136925 68480 136926 67932 136926 68482 136926 68482 136927 67932 136927 68481 136927 68482 136928 68481 136928 68483 136928 68483 136929 68481 136929 68485 136929 68483 136930 68485 136930 68484 136930 68484 136931 68485 136931 68486 136931 68486 136932 68485 136932 67928 136932 68486 136933 67928 136933 68061 136933 68487 136934 68042 136934 67947 136934 68487 136935 67947 136935 68488 136935 68488 136936 67947 136936 67946 136936 68488 136937 67946 136937 68043 136937 68043 136938 67946 136938 68489 136938 68043 136939 68489 136939 68044 136939 68044 136940 68489 136940 68490 136940 68490 136941 68489 136941 68491 136941 68490 136942 68491 136942 68045 136942 68045 136943 68491 136943 68493 136943 68045 136944 68493 136944 68492 136944 68492 136945 68493 136945 67942 136945 68492 136946 67942 136946 68047 136946 68047 136947 67942 136947 68494 136947 68047 136948 68494 136948 65838 136948 68567 136949 65837 136949 68495 136949 68567 136950 68495 136950 68496 136950 68496 136951 68495 136951 68500 136951 68496 136952 68500 136952 68502 136952 68497 136953 68555 136953 68574 136953 68574 136954 68555 136954 68550 136954 65815 136955 65835 136955 68498 136955 68498 136956 68499 136956 65815 136956 65815 136957 68499 136957 68571 136957 65815 136958 68571 136958 68550 136958 68550 136959 68571 136959 68572 136959 68550 136960 68572 136960 68574 136960 68500 136961 68501 136961 68502 136961 68502 136962 68501 136962 68564 136962 68576 136963 68504 136963 68503 136963 68503 136964 68504 136964 68555 136964 68503 136965 68555 136965 68497 136965 68559 136966 65834 136966 68529 136966 68529 136967 65834 136967 68549 136967 68588 136968 68505 136968 68506 136968 68506 136969 68505 136969 68539 136969 68506 136970 68539 136970 68507 136970 68507 136971 68539 136971 68538 136971 68507 136972 68538 136972 68508 136972 68508 136973 68538 136973 68516 136973 68508 136974 68516 136974 68585 136974 68513 136975 65828 136975 68514 136975 68514 136976 65828 136976 65829 136976 68591 136977 68510 136977 68509 136977 68509 136978 68510 136978 68544 136978 68509 136979 68544 136979 68511 136979 68511 136980 68544 136980 68545 136980 68511 136981 68545 136981 68512 136981 68512 136982 68545 136982 68513 136982 68512 136983 68513 136983 68514 136983 68585 136984 68516 136984 68515 136984 68515 136985 68516 136985 68517 136985 68515 136986 68517 136986 68522 136986 68593 136987 65826 136987 68592 136987 68592 136988 65826 136988 68510 136988 68592 136989 68510 136989 68591 136989 68118 136990 68117 136990 68519 136990 68519 136991 68117 136991 68518 136991 68519 136992 68518 136992 65827 136992 68524 136993 68521 136993 68520 136993 68520 136994 68521 136994 68522 136994 68520 136995 68522 136995 68517 136995 65823 136996 68125 136996 68523 136996 68523 136997 68125 136997 68126 136997 68523 136998 68126 136998 68524 136998 68524 136999 68126 136999 68525 136999 68524 137000 68525 137000 68521 137000 68521 137001 68525 137001 68582 137001 68556 137002 68120 137002 68526 137002 68556 137003 68526 137003 65813 137003 65813 137004 68526 137004 68123 137004 65813 137005 68123 137005 68085 137005 68120 137006 68556 137006 68121 137006 68121 137007 68556 137007 68528 137007 68121 137008 68528 137008 68527 137008 68527 137009 68528 137009 68579 137009 68579 137010 68528 137010 68504 137010 68579 137011 68504 137011 68576 137011 65820 137012 68532 137012 68549 137012 68549 137013 68532 137013 68529 137013 68091 137014 68090 137014 68530 137014 68530 137015 68090 137015 68531 137015 68530 137016 68531 137016 65822 137016 65822 137017 68531 137017 68159 137017 65822 137018 68159 137018 65820 137018 65820 137019 68159 137019 68158 137019 65820 137020 68158 137020 68532 137020 65811 137021 68063 137021 68533 137021 68533 137022 68063 137022 65823 137022 68533 137023 65823 137023 68534 137023 68517 137024 68535 137024 68520 137024 68520 137025 68535 137025 68700 137025 68520 137026 68700 137026 68524 137026 68524 137027 68700 137027 68534 137027 68524 137028 68534 137028 68523 137028 68523 137029 68534 137029 65823 137029 68516 137030 68536 137030 68517 137030 68517 137031 68536 137031 68535 137031 68537 137032 68536 137032 68516 137032 68516 137033 68538 137033 68537 137033 68537 137034 68538 137034 68539 137034 68537 137035 68539 137035 68540 137035 68540 137036 68539 137036 68505 137036 68540 137037 68505 137037 68541 137037 68541 137038 68505 137038 65828 137038 68541 137039 65828 137039 68542 137039 68542 137040 65828 137040 68513 137040 68542 137041 68513 137041 68706 137041 68543 137042 68706 137042 68513 137042 68543 137043 68513 137043 65804 137043 68510 137044 65805 137044 68544 137044 68544 137045 65805 137045 65804 137045 68544 137046 65804 137046 68545 137046 68545 137047 65804 137047 68513 137047 65826 137048 68546 137048 68510 137048 68510 137049 68546 137049 65805 137049 65803 137050 68546 137050 65826 137050 65826 137051 65825 137051 65803 137051 65803 137052 65825 137052 68547 137052 65803 137053 68547 137053 68708 137053 68708 137054 68547 137054 68518 137054 68708 137055 68518 137055 68548 137055 68548 137056 68518 137056 68117 137056 68091 137057 68530 137057 68683 137057 68683 137058 68530 137058 68682 137058 65834 137059 68684 137059 68549 137059 68549 137060 68684 137060 65819 137060 68500 137061 68685 137061 68501 137061 68501 137062 68685 137062 65817 137062 68500 137063 68495 137063 68685 137063 68685 137064 68495 137064 68692 137064 68550 137065 68555 137065 68551 137065 68552 137066 65815 137066 68553 137066 68553 137067 65815 137067 68550 137067 68553 137068 68550 137068 68554 137068 68554 137069 68550 137069 68551 137069 68504 137070 68698 137070 68555 137070 68555 137071 68698 137071 68551 137071 65813 137072 68696 137072 68556 137072 68556 137073 68696 137073 68697 137073 68556 137074 68697 137074 68528 137074 68528 137075 68697 137075 68557 137075 68528 137076 68557 137076 68504 137076 68504 137077 68557 137077 68698 137077 68532 137078 68158 137078 68163 137078 67981 137079 68529 137079 67973 137079 67973 137080 68529 137080 68532 137080 67973 137081 68532 137081 68558 137081 68558 137082 68532 137082 68163 137082 68529 137083 67981 137083 68559 137083 68559 137084 67981 137084 67980 137084 68559 137085 67980 137085 67978 137085 68559 137086 67978 137086 65833 137086 65833 137087 67978 137087 67977 137087 65833 137088 67977 137088 68560 137088 68560 137089 67977 137089 67975 137089 68560 137090 67975 137090 65831 137090 65831 137091 67975 137091 68562 137091 65831 137092 68562 137092 68561 137092 68561 137093 68562 137093 68563 137093 68565 137094 68273 137094 68502 137094 68561 137095 68563 137095 65830 137095 65830 137096 68563 137096 68565 137096 65830 137097 68565 137097 68564 137097 68564 137098 68565 137098 68502 137098 68566 137099 65962 137099 68567 137099 68566 137100 68567 137100 68296 137100 68567 137101 68496 137101 68296 137101 68296 137102 68496 137102 68502 137102 68296 137103 68502 137103 68273 137103 65961 137104 66122 137104 68499 137104 68499 137105 68568 137105 65961 137105 65961 137106 68568 137106 65835 137106 65961 137107 65835 137107 65962 137107 65962 137108 65835 137108 68569 137108 65962 137109 68569 137109 68567 137109 68499 137110 66122 137110 68571 137110 68571 137111 66122 137111 68570 137111 68571 137112 68570 137112 68572 137112 68572 137113 68570 137113 66136 137113 68572 137114 66136 137114 68574 137114 68574 137115 66136 137115 68573 137115 68574 137116 68573 137116 68497 137116 68497 137117 68573 137117 66135 137117 68497 137118 66135 137118 68575 137118 68575 137119 66135 137119 66130 137119 68575 137120 66130 137120 68576 137120 68576 137121 66130 137121 68577 137121 68576 137122 68577 137122 68579 137122 68579 137123 68577 137123 68578 137123 68578 137124 66133 137124 68579 137124 68579 137125 66133 137125 68122 137125 68579 137126 68122 137126 68527 137126 68527 137127 68122 137127 68121 137127 68124 137128 68152 137128 68580 137128 68581 137129 68522 137129 68580 137129 68580 137130 68522 137130 68521 137130 68580 137131 68521 137131 68124 137131 68124 137132 68521 137132 68582 137132 68522 137133 68581 137133 68584 137133 68584 137134 68581 137134 68583 137134 68584 137135 68583 137135 68585 137135 68585 137136 68583 137136 66146 137136 68585 137137 66146 137137 68586 137137 68585 137138 68586 137138 68508 137138 68586 137139 66139 137139 68508 137139 68508 137140 66139 137140 68587 137140 68508 137141 68587 137141 68507 137141 68507 137142 68587 137142 68506 137142 68506 137143 68587 137143 66138 137143 68506 137144 66138 137144 68588 137144 68514 137145 65829 137145 68589 137145 68589 137146 65829 137146 66137 137146 68514 137147 68589 137147 67986 137147 68514 137148 67986 137148 68512 137148 68512 137149 67986 137149 67983 137149 68512 137150 67983 137150 68511 137150 68511 137151 67983 137151 68590 137151 68511 137152 68590 137152 68509 137152 68509 137153 68590 137153 67985 137153 68509 137154 67985 137154 68591 137154 68591 137155 67985 137155 68592 137155 68592 137156 67985 137156 68594 137156 68592 137157 68594 137157 68593 137157 68593 137158 68594 137158 68595 137158 68593 137159 68595 137159 68597 137159 68597 137160 68595 137160 68596 137160 68596 137161 67982 137161 68597 137161 68597 137162 67982 137162 68160 137162 68597 137163 68160 137163 68598 137163 64704 137164 68599 137164 68600 137164 68600 137165 68599 137165 65737 137165 68600 137166 65737 137166 68601 137166 68601 137167 65737 137167 65735 137167 68601 137168 65735 137168 68602 137168 68602 137169 65735 137169 68619 137169 68602 137170 68619 137170 68620 137170 68603 137171 68616 137171 68604 137171 68604 137172 68616 137172 68605 137172 68604 137173 68605 137173 64705 137173 64705 137174 68605 137174 65739 137174 64705 137175 65739 137175 64704 137175 64704 137176 65739 137176 68606 137176 64704 137177 68606 137177 68599 137177 64716 137178 68780 137178 64714 137178 64714 137179 68780 137179 68607 137179 64714 137180 68607 137180 68609 137180 68609 137181 68607 137181 68608 137181 68609 137182 68608 137182 64713 137182 64713 137183 68608 137183 68610 137183 64713 137184 68610 137184 68611 137184 68610 137185 68612 137185 68611 137185 68611 137186 68612 137186 68613 137186 68611 137187 68613 137187 64711 137187 64711 137188 68613 137188 65744 137188 64711 137189 65744 137189 64709 137189 64709 137190 65744 137190 65742 137190 64709 137191 65742 137191 64707 137191 64707 137192 65742 137192 68614 137192 64707 137193 68614 137193 68603 137193 68603 137194 68614 137194 68615 137194 68603 137195 68615 137195 68616 137195 64721 137196 68792 137196 68617 137196 68617 137197 68792 137197 68790 137197 68617 137198 68790 137198 68618 137198 68618 137199 68790 137199 68789 137199 68618 137200 68789 137200 64719 137200 64719 137201 68789 137201 68788 137201 64719 137202 68788 137202 68625 137202 68619 137203 68621 137203 68620 137203 68620 137204 68621 137204 68622 137204 68620 137205 68622 137205 64725 137205 64725 137206 68622 137206 65732 137206 64725 137207 65732 137207 68623 137207 68623 137208 65732 137208 68793 137208 68623 137209 68793 137209 64721 137209 64721 137210 68793 137210 68624 137210 64721 137211 68624 137211 68792 137211 68788 137212 68786 137212 68625 137212 68625 137213 68786 137213 68627 137213 68625 137214 68627 137214 68626 137214 68626 137215 68627 137215 68784 137215 68626 137216 68784 137216 64717 137216 64717 137217 68784 137217 68783 137217 64717 137218 68783 137218 64716 137218 64716 137219 68783 137219 68628 137219 64716 137220 68628 137220 68780 137220 70673 137221 68629 137221 68709 137221 68709 137222 68629 137222 68630 137222 68709 137223 68630 137223 68631 137223 68631 137224 68630 137224 68632 137224 68631 137225 68632 137225 68633 137225 68633 137226 68632 137226 64935 137226 68633 137227 64935 137227 68634 137227 68634 137228 64935 137228 68635 137228 68634 137229 68635 137229 68636 137229 68636 137230 68635 137230 68637 137230 68637 137231 68635 137231 64933 137231 68637 137232 64933 137232 68641 137232 68641 137233 64933 137233 68642 137233 64929 137234 68644 137234 68638 137234 64929 137235 68638 137235 68639 137235 68639 137236 68638 137236 68726 137236 68639 137237 68726 137237 64930 137237 64930 137238 68726 137238 68640 137238 64930 137239 68640 137239 64932 137239 64932 137240 68640 137240 68641 137240 64932 137241 68641 137241 68642 137241 68643 137242 68729 137242 68727 137242 68643 137243 68727 137243 68645 137243 68645 137244 68727 137244 68644 137244 68645 137245 68644 137245 64929 137245 68646 137246 68650 137246 68728 137246 68646 137247 68728 137247 70682 137247 70682 137248 68728 137248 68730 137248 70682 137249 68730 137249 70683 137249 68730 137250 68647 137250 70683 137250 70683 137251 68647 137251 68648 137251 70683 137252 68648 137252 68649 137252 68649 137253 68648 137253 68729 137253 68649 137254 68729 137254 68643 137254 68650 137255 68646 137255 68724 137255 68724 137256 68646 137256 70678 137256 68724 137257 70678 137257 68713 137257 68713 137258 70678 137258 70680 137258 70680 137259 70677 137259 68713 137259 68713 137260 70677 137260 68651 137260 70677 137261 70676 137261 68651 137261 68651 137262 70676 137262 70681 137262 68651 137263 70681 137263 68711 137263 68711 137264 70681 137264 68652 137264 68652 137265 70681 137265 68653 137265 68652 137266 68653 137266 70855 137266 68654 137267 70776 137267 68655 137267 68654 137268 68655 137268 68656 137268 68656 137269 68655 137269 70777 137269 68656 137270 70777 137270 68719 137270 68719 137271 70777 137271 68657 137271 68719 137272 68657 137272 68658 137272 68658 137273 68657 137273 68659 137273 68658 137274 68659 137274 68717 137274 68717 137275 68659 137275 68733 137275 68733 137276 68659 137276 70779 137276 68733 137277 70779 137277 68660 137277 68660 137278 70779 137278 70778 137278 68661 137279 65794 137279 68662 137279 68661 137280 68662 137280 68663 137280 68663 137281 68662 137281 68665 137281 68663 137282 68665 137282 68664 137282 68664 137283 68665 137283 68735 137283 68664 137284 68735 137284 68666 137284 68666 137285 68735 137285 68660 137285 68666 137286 68660 137286 70778 137286 68738 137287 68736 137287 68669 137287 68669 137288 68736 137288 65812 137288 65795 137289 68674 137289 64827 137289 64827 137290 68674 137290 68667 137290 68738 137291 68669 137291 68668 137291 68668 137292 68669 137292 68670 137292 68668 137293 68670 137293 68672 137293 68672 137294 68670 137294 68671 137294 68672 137295 68671 137295 65798 137295 65798 137296 68671 137296 68667 137296 65798 137297 68667 137297 68673 137297 68673 137298 68667 137298 68674 137298 65795 137299 64827 137299 68732 137299 68732 137300 64827 137300 64824 137300 68732 137301 64824 137301 68731 137301 68731 137302 64824 137302 64823 137302 68731 137303 64823 137303 64822 137303 68731 137304 64822 137304 68675 137304 68675 137305 64822 137305 68677 137305 68675 137306 68677 137306 68676 137306 68676 137307 68677 137307 64826 137307 68676 137308 64826 137308 68678 137308 68678 137309 64826 137309 64825 137309 68678 137310 64825 137310 68679 137310 65819 137311 68716 137311 68680 137311 65819 137312 68680 137312 68681 137312 68681 137313 68680 137313 68715 137313 68681 137314 68715 137314 65821 137314 65821 137315 68715 137315 68682 137315 68682 137316 68715 137316 68714 137316 68682 137317 68714 137317 68683 137317 68716 137318 65819 137318 65796 137318 65796 137319 65819 137319 68684 137319 68685 137320 68686 137320 65817 137320 65817 137321 68686 137321 68687 137321 65817 137322 68687 137322 65818 137322 65818 137323 68687 137323 65797 137323 65818 137324 65797 137324 68688 137324 65796 137325 68684 137325 65799 137325 65799 137326 68684 137326 68688 137326 65799 137327 68688 137327 68689 137327 68689 137328 68688 137328 65797 137328 68690 137329 68691 137329 68737 137329 68690 137330 68737 137330 68692 137330 68692 137331 68737 137331 68686 137331 68692 137332 68686 137332 68685 137332 68691 137333 68690 137333 68693 137333 68693 137334 68690 137334 68552 137334 68693 137335 68552 137335 68694 137335 68694 137336 68552 137336 68553 137336 68694 137337 68553 137337 68734 137337 68734 137338 68553 137338 68554 137338 68734 137339 68554 137339 68695 137339 68695 137340 68554 137340 68551 137340 68695 137341 68551 137341 68718 137341 68718 137342 68551 137342 68698 137342 68696 137343 65814 137343 70845 137343 68696 137344 70845 137344 68697 137344 70845 137345 68721 137345 68697 137345 68697 137346 68721 137346 68720 137346 68697 137347 68720 137347 68557 137347 68557 137348 68720 137348 68718 137348 68557 137349 68718 137349 68698 137349 68535 137350 68712 137350 68699 137350 68535 137351 68699 137351 68700 137351 68700 137352 68699 137352 68701 137352 68700 137353 68701 137353 68534 137353 68534 137354 68701 137354 68702 137354 68534 137355 68702 137355 68533 137355 68712 137356 68535 137356 68703 137356 68703 137357 68535 137357 68536 137357 68537 137358 68540 137358 65808 137358 68703 137359 68536 137359 68704 137359 68704 137360 68536 137360 68537 137360 68704 137361 68537 137361 68705 137361 68705 137362 68537 137362 65808 137362 68707 137363 65800 137363 68706 137363 68706 137364 65800 137364 68542 137364 68707 137365 68706 137365 68725 137365 68725 137366 68706 137366 68543 137366 68722 137367 65805 137367 68723 137367 68723 137368 65805 137368 68546 137368 70649 137369 68710 137369 68548 137369 68548 137370 68710 137370 68708 137370 70649 137371 70673 137371 68710 137371 68710 137372 70673 137372 68709 137372 68710 137373 68709 137373 68631 137373 68652 137374 68702 137374 68701 137374 68652 137375 68701 137375 68711 137375 68711 137376 68701 137376 68699 137376 68711 137377 68699 137377 68651 137377 68651 137378 68699 137378 68712 137378 68651 137379 68712 137379 68713 137379 68679 137380 68714 137380 68678 137380 68678 137381 68714 137381 68715 137381 68678 137382 68715 137382 68676 137382 68676 137383 68715 137383 68680 137383 68676 137384 68680 137384 68675 137384 68675 137385 68680 137385 68716 137385 68675 137386 68716 137386 68731 137386 68658 137387 68717 137387 68718 137387 68658 137388 68718 137388 68719 137388 68718 137389 68720 137389 68719 137389 68719 137390 68720 137390 68721 137390 68719 137391 68721 137391 68656 137391 68656 137392 68721 137392 70845 137392 68656 137393 70845 137393 68654 137393 68641 137394 68722 137394 68637 137394 68637 137395 68722 137395 68723 137395 68637 137396 68723 137396 68636 137396 68713 137397 68712 137397 68724 137397 68724 137398 68712 137398 68703 137398 68724 137399 68703 137399 68650 137399 68644 137400 68707 137400 68638 137400 68638 137401 68707 137401 68725 137401 68638 137402 68725 137402 68726 137402 68725 137403 65806 137403 68726 137403 68726 137404 65806 137404 65807 137404 68726 137405 65807 137405 68640 137405 68640 137406 65807 137406 68722 137406 68640 137407 68722 137407 68641 137407 68644 137408 68727 137408 68707 137408 68707 137409 68727 137409 65800 137409 68650 137410 68703 137410 68728 137410 68728 137411 68703 137411 68704 137411 65809 137412 68729 137412 65808 137412 65808 137413 68729 137413 68648 137413 65808 137414 68648 137414 68705 137414 68705 137415 68648 137415 68647 137415 68705 137416 68647 137416 68704 137416 68704 137417 68647 137417 68730 137417 68704 137418 68730 137418 68728 137418 68731 137419 68716 137419 68732 137419 68732 137420 68716 137420 65796 137420 68732 137421 65796 137421 65795 137421 68660 137422 68695 137422 68733 137422 68733 137423 68695 137423 68718 137423 68733 137424 68718 137424 68717 137424 68687 137425 68686 137425 68668 137425 68668 137426 68686 137426 68738 137426 68662 137427 68693 137427 68694 137427 68662 137428 68694 137428 68665 137428 68665 137429 68694 137429 68734 137429 68665 137430 68734 137430 68735 137430 68735 137431 68734 137431 68695 137431 68735 137432 68695 137432 68660 137432 68691 137433 65794 137433 68736 137433 68691 137434 68736 137434 68737 137434 68737 137435 68736 137435 68738 137435 68737 137436 68738 137436 68686 137436 70399 137437 68739 137437 70419 137437 70399 137438 70419 137438 70400 137438 70400 137439 70419 137439 68741 137439 70400 137440 68741 137440 68740 137440 68740 137441 68741 137441 70416 137441 68740 137442 70416 137442 70367 137442 70367 137443 70416 137443 70415 137443 70367 137444 70415 137444 68742 137444 68742 137445 70415 137445 68743 137445 68742 137446 68743 137446 70368 137446 70368 137447 68743 137447 70413 137447 70368 137448 70413 137448 68744 137448 68744 137449 70413 137449 68745 137449 68744 137450 68745 137450 68746 137450 68746 137451 68745 137451 70412 137451 68746 137452 70412 137452 70372 137452 70372 137453 70412 137453 68747 137453 70372 137454 68747 137454 70373 137454 70373 137455 68747 137455 70411 137455 70373 137456 70411 137456 70376 137456 70376 137457 70411 137457 68748 137457 70376 137458 68748 137458 70378 137458 70378 137459 68748 137459 70409 137459 70378 137460 70409 137460 68749 137460 68749 137461 70409 137461 68750 137461 68749 137462 68750 137462 70379 137462 70379 137463 68750 137463 70407 137463 70379 137464 70407 137464 70381 137464 70381 137465 70407 137465 70404 137465 70381 137466 70404 137466 70382 137466 70382 137467 70404 137467 70403 137467 70382 137468 70403 137468 70383 137468 70383 137469 70403 137469 65074 137469 70383 137470 65074 137470 68751 137470 65110 137471 70346 137471 70310 137471 70310 137472 70346 137472 68752 137472 70310 137473 68752 137473 68753 137473 68753 137474 68752 137474 70347 137474 68753 137475 70347 137475 70311 137475 70311 137476 70347 137476 70348 137476 70311 137477 70348 137477 68754 137477 68754 137478 70348 137478 70349 137478 68754 137479 70349 137479 68755 137479 68755 137480 70349 137480 70350 137480 68755 137481 70350 137481 70314 137481 70314 137482 70350 137482 68756 137482 70314 137483 68756 137483 68757 137483 68757 137484 68756 137484 68758 137484 68757 137485 68758 137485 70316 137485 70316 137486 68758 137486 70351 137486 70316 137487 70351 137487 70318 137487 70318 137488 70351 137488 70325 137488 70318 137489 70325 137489 70319 137489 70319 137490 70325 137490 70326 137490 70319 137491 70326 137491 70320 137491 70320 137492 70326 137492 70327 137492 70320 137493 70327 137493 70321 137493 70321 137494 70327 137494 70329 137494 70321 137495 70329 137495 68759 137495 68759 137496 70329 137496 70330 137496 68759 137497 70330 137497 68760 137497 68760 137498 70330 137498 70332 137498 68760 137499 70332 137499 68761 137499 68761 137500 70332 137500 70334 137500 68761 137501 70334 137501 65096 137501 65096 137502 70334 137502 70335 137502 65014 137503 68762 137503 70569 137503 70569 137504 68762 137504 70291 137504 70569 137505 70291 137505 70571 137505 70571 137506 70291 137506 68763 137506 70571 137507 68763 137507 70573 137507 70573 137508 68763 137508 68764 137508 70573 137509 68764 137509 70574 137509 70574 137510 68764 137510 68765 137510 70574 137511 68765 137511 70575 137511 70575 137512 68765 137512 70294 137512 70575 137513 70294 137513 70578 137513 70578 137514 70294 137514 68766 137514 70578 137515 68766 137515 68767 137515 68767 137516 68766 137516 70296 137516 68767 137517 70296 137517 68768 137517 68768 137518 70296 137518 70297 137518 68768 137519 70297 137519 68769 137519 68769 137520 70297 137520 68770 137520 68769 137521 68770 137521 68771 137521 68771 137522 68770 137522 68772 137522 68771 137523 68772 137523 68773 137523 68773 137524 68772 137524 70300 137524 68773 137525 70300 137525 68774 137525 68774 137526 70300 137526 68775 137526 68774 137527 68775 137527 70584 137527 70584 137528 68775 137528 70303 137528 70584 137529 70303 137529 68776 137529 68776 137530 70303 137530 68777 137530 68776 137531 68777 137531 68778 137531 68778 137532 68777 137532 70304 137532 68778 137533 70304 137533 68779 137533 68779 137534 70304 137534 70305 137534 64995 137535 68613 137535 70585 137535 70585 137536 68613 137536 68612 137536 70585 137537 68612 137537 70583 137537 70583 137538 68612 137538 68610 137538 70583 137539 68610 137539 70582 137539 70582 137540 68610 137540 68608 137540 70582 137541 68608 137541 70581 137541 70581 137542 68608 137542 68607 137542 70581 137543 68607 137543 70580 137543 70580 137544 68607 137544 68780 137544 70580 137545 68780 137545 70579 137545 70579 137546 68780 137546 68628 137546 70579 137547 68628 137547 68781 137547 68781 137548 68628 137548 68783 137548 68781 137549 68783 137549 68782 137549 68782 137550 68783 137550 68784 137550 68782 137551 68784 137551 70577 137551 70577 137552 68784 137552 68627 137552 70577 137553 68627 137553 70576 137553 70576 137554 68627 137554 68786 137554 70576 137555 68786 137555 68785 137555 68785 137556 68786 137556 68788 137556 68785 137557 68788 137557 68787 137557 68787 137558 68788 137558 68789 137558 68787 137559 68789 137559 70572 137559 70572 137560 68789 137560 68790 137560 70572 137561 68790 137561 68791 137561 68791 137562 68790 137562 68792 137562 68791 137563 68792 137563 70570 137563 70570 137564 68792 137564 68624 137564 70570 137565 68624 137565 65731 137565 65731 137566 68624 137566 68793 137566 65730 137567 70568 137567 70567 137567 65730 137568 70567 137568 70522 137568 70522 137569 70567 137569 68794 137569 70522 137570 68794 137570 70523 137570 70523 137571 68794 137571 70566 137571 70523 137572 70566 137572 68795 137572 68795 137573 70566 137573 68796 137573 68795 137574 68796 137574 70525 137574 70525 137575 68796 137575 68797 137575 70525 137576 68797 137576 70526 137576 70526 137577 68797 137577 70561 137577 70526 137578 70561 137578 68798 137578 68798 137579 70561 137579 70557 137579 68798 137580 70557 137580 68799 137580 68799 137581 70557 137581 68800 137581 68799 137582 68800 137582 68801 137582 68801 137583 68800 137583 68802 137583 68801 137584 68802 137584 68803 137584 68803 137585 68802 137585 70553 137585 68803 137586 70553 137586 68804 137586 68804 137587 70553 137587 68805 137587 68804 137588 68805 137588 70529 137588 70529 137589 68805 137589 70552 137589 70529 137590 70552 137590 68806 137590 68806 137591 70552 137591 70548 137591 68806 137592 70548 137592 70532 137592 70532 137593 70548 137593 70547 137593 70532 137594 70547 137594 70533 137594 70533 137595 70547 137595 70546 137595 70533 137596 70546 137596 68807 137596 68807 137597 70546 137597 70543 137597 68807 137598 70543 137598 70534 137598 70534 137599 70543 137599 68808 137599 70534 137600 68808 137600 68809 137600 68809 137601 68808 137601 65718 137601 68809 137602 65718 137602 65717 137602 68810 137603 68811 137603 68812 137603 68812 137604 68811 137604 70535 137604 68812 137605 70535 137605 70490 137605 70490 137606 70535 137606 70536 137606 70490 137607 70536 137607 70492 137607 70492 137608 70536 137608 68813 137608 70492 137609 68813 137609 70493 137609 70493 137610 68813 137610 70538 137610 70493 137611 70538 137611 68814 137611 68814 137612 70538 137612 68816 137612 68814 137613 68816 137613 68815 137613 68815 137614 68816 137614 68817 137614 68815 137615 68817 137615 68818 137615 68818 137616 68817 137616 70505 137616 68818 137617 70505 137617 70496 137617 70496 137618 70505 137618 70507 137618 70496 137619 70507 137619 68819 137619 68819 137620 70507 137620 70509 137620 68819 137621 70509 137621 68820 137621 68820 137622 70509 137622 70510 137622 68820 137623 70510 137623 68821 137623 68821 137624 70510 137624 70513 137624 68821 137625 70513 137625 68823 137625 68823 137626 70513 137626 68822 137626 68823 137627 68822 137627 70499 137627 70499 137628 68822 137628 68824 137628 70499 137629 68824 137629 68825 137629 68825 137630 68824 137630 70517 137630 68825 137631 70517 137631 70502 137631 70502 137632 70517 137632 70518 137632 70502 137633 70518 137633 70503 137633 70503 137634 70518 137634 68826 137634 70503 137635 68826 137635 68828 137635 68828 137636 68826 137636 68827 137636 68828 137637 68827 137637 70504 137637 70504 137638 68827 137638 65697 137638 70586 137639 68829 137639 68830 137639 68830 137640 68829 137640 68831 137640 68830 137641 68831 137641 68833 137641 68833 137642 68831 137642 68832 137642 68833 137643 68832 137643 70588 137643 70588 137644 68832 137644 68835 137644 70588 137645 68835 137645 68834 137645 68834 137646 68835 137646 68836 137646 68834 137647 68836 137647 70589 137647 70589 137648 68836 137648 68837 137648 70589 137649 68837 137649 70591 137649 70591 137650 68837 137650 68838 137650 70591 137651 68838 137651 70593 137651 70593 137652 68838 137652 70468 137652 70593 137653 70468 137653 68840 137653 68840 137654 70468 137654 68839 137654 68840 137655 68839 137655 70595 137655 70595 137656 68839 137656 68841 137656 70595 137657 68841 137657 70597 137657 70597 137658 68841 137658 70470 137658 70597 137659 70470 137659 68842 137659 68842 137660 70470 137660 70472 137660 68842 137661 70472 137661 68843 137661 68843 137662 70472 137662 68844 137662 68843 137663 68844 137663 68845 137663 68845 137664 68844 137664 70475 137664 68845 137665 70475 137665 68846 137665 68846 137666 70475 137666 70476 137666 68846 137667 70476 137667 68847 137667 68847 137668 70476 137668 70478 137668 68847 137669 70478 137669 68848 137669 68848 137670 70478 137670 68849 137670 68848 137671 68849 137671 70602 137671 70602 137672 68849 137672 70480 137672 68850 137673 65076 137673 68851 137673 68850 137674 68851 137674 68852 137674 68852 137675 68851 137675 70364 137675 68852 137676 70364 137676 70337 137676 70337 137677 70364 137677 68853 137677 70337 137678 68853 137678 70338 137678 70338 137679 68853 137679 70362 137679 70338 137680 70362 137680 68854 137680 68854 137681 70362 137681 68855 137681 68854 137682 68855 137682 70339 137682 70339 137683 68855 137683 70361 137683 70339 137684 70361 137684 68856 137684 68856 137685 70361 137685 70360 137685 68856 137686 70360 137686 68857 137686 68857 137687 70360 137687 70358 137687 68857 137688 70358 137688 68858 137688 68858 137689 70358 137689 68859 137689 68858 137690 68859 137690 68860 137690 68860 137691 68859 137691 70357 137691 68860 137692 70357 137692 68862 137692 68862 137693 70357 137693 68861 137693 68862 137694 68861 137694 68863 137694 68863 137695 68861 137695 68865 137695 68863 137696 68865 137696 68864 137696 68864 137697 68865 137697 68866 137697 68864 137698 68866 137698 70343 137698 70343 137699 68866 137699 70355 137699 70343 137700 70355 137700 68868 137700 68868 137701 70355 137701 68867 137701 68868 137702 68867 137702 68869 137702 68869 137703 68867 137703 65662 137703 68869 137704 65662 137704 68870 137704 70744 137705 68884 137705 68876 137705 68871 137706 70739 137706 68872 137706 68872 137707 70739 137707 68873 137707 68872 137708 68873 137708 68874 137708 68874 137709 68873 137709 70792 137709 68874 137710 70792 137710 68875 137710 68875 137711 70792 137711 70791 137711 68875 137712 70791 137712 68876 137712 68876 137713 70791 137713 68877 137713 68876 137714 68877 137714 70744 137714 69363 137715 69362 137715 68883 137715 68883 137716 69362 137716 68878 137716 68883 137717 68878 137717 68880 137717 68880 137718 68878 137718 68879 137718 68880 137719 68879 137719 68881 137719 68881 137720 68879 137720 68882 137720 68881 137721 68882 137721 70737 137721 69363 137722 68883 137722 69364 137722 69364 137723 68883 137723 70739 137723 69364 137724 70739 137724 68871 137724 70744 137725 68887 137725 68884 137725 68884 137726 68887 137726 68885 137726 68885 137727 68887 137727 68886 137727 68886 137728 68887 137728 70745 137728 68886 137729 70745 137729 68888 137729 68888 137730 70745 137730 68889 137730 68889 137731 70745 137731 68891 137731 68889 137732 68891 137732 68890 137732 68890 137733 68891 137733 70746 137733 68890 137734 70746 137734 68892 137734 68912 137735 70737 137735 69614 137735 69614 137736 70737 137736 68882 137736 68893 137737 68894 137737 70746 137737 70746 137738 68894 137738 68892 137738 69627 137739 68895 137739 70793 137739 70793 137740 68895 137740 70733 137740 70733 137741 68895 137741 68929 137741 70733 137742 68929 137742 70734 137742 69627 137743 70793 137743 69626 137743 69626 137744 70793 137744 68896 137744 69626 137745 68896 137745 69625 137745 69625 137746 68896 137746 68897 137746 69625 137747 68897 137747 69622 137747 69618 137748 69620 137748 68898 137748 68897 137749 70742 137749 69622 137749 69622 137750 70742 137750 68900 137750 69622 137751 68900 137751 68899 137751 68899 137752 68900 137752 68901 137752 68899 137753 68901 137753 68902 137753 68902 137754 68901 137754 68903 137754 68902 137755 68903 137755 69624 137755 69624 137756 68903 137756 68904 137756 69624 137757 68904 137757 69621 137757 69621 137758 68904 137758 70740 137758 69621 137759 70740 137759 69620 137759 69620 137760 70740 137760 68905 137760 69620 137761 68905 137761 68898 137761 68898 137762 68906 137762 69618 137762 69618 137763 68906 137763 68907 137763 69618 137764 68907 137764 68908 137764 68908 137765 68907 137765 68909 137765 68908 137766 68909 137766 69617 137766 69617 137767 68909 137767 68910 137767 69617 137768 68910 137768 68911 137768 68911 137769 68910 137769 68912 137769 68911 137770 68912 137770 69614 137770 70787 137771 68913 137771 68914 137771 70787 137772 68914 137772 70752 137772 70752 137773 68914 137773 69644 137773 70752 137774 69644 137774 68915 137774 68915 137775 69644 137775 68916 137775 68915 137776 68916 137776 70753 137776 70753 137777 68916 137777 68917 137777 70753 137778 68917 137778 70754 137778 70754 137779 68917 137779 69646 137779 70754 137780 69646 137780 70755 137780 70755 137781 69646 137781 70759 137781 70759 137782 69646 137782 68918 137782 70759 137783 68918 137783 70758 137783 70758 137784 68918 137784 68919 137784 70758 137785 68919 137785 70757 137785 70757 137786 68919 137786 69649 137786 70757 137787 69649 137787 68920 137787 68920 137788 69649 137788 68921 137788 68920 137789 68921 137789 68922 137789 68921 137790 68923 137790 68922 137790 68922 137791 68923 137791 69650 137791 68922 137792 69650 137792 68924 137792 68924 137793 69650 137793 68925 137793 68924 137794 68925 137794 70788 137794 68925 137795 68926 137795 70788 137795 70788 137796 68926 137796 69653 137796 70788 137797 69653 137797 68927 137797 68927 137798 69653 137798 68894 137798 68927 137799 68894 137799 68893 137799 70734 137800 68929 137800 68928 137800 68928 137801 68929 137801 68930 137801 70787 137802 70750 137802 68913 137802 68913 137803 70750 137803 68937 137803 68931 137804 68932 137804 70850 137804 70850 137805 68932 137805 69354 137805 69354 137806 68932 137806 69356 137806 69356 137807 68932 137807 68933 137807 69356 137808 68933 137808 69355 137808 69355 137809 68933 137809 68935 137809 68935 137810 68933 137810 68934 137810 68935 137811 68934 137811 69358 137811 69358 137812 68934 137812 68928 137812 69358 137813 68928 137813 68930 137813 68936 137814 69372 137814 68938 137814 68938 137815 69372 137815 69370 137815 68938 137816 69370 137816 70749 137816 70749 137817 69370 137817 69371 137817 70749 137818 69371 137818 70751 137818 70751 137819 69371 137819 68937 137819 70751 137820 68937 137820 70750 137820 68936 137821 68938 137821 69374 137821 69374 137822 68938 137822 68950 137822 69374 137823 68950 137823 70843 137823 68931 137824 70850 137824 70735 137824 70735 137825 70850 137825 68939 137825 70735 137826 68939 137826 70794 137826 70794 137827 68939 137827 70861 137827 70794 137828 70861 137828 68942 137828 65641 137829 68940 137829 68941 137829 68941 137830 68940 137830 68943 137830 68941 137831 68943 137831 68942 137831 68942 137832 68943 137832 68944 137832 68942 137833 68944 137833 70794 137833 70773 137834 70864 137834 68945 137834 68945 137835 70864 137835 68946 137835 68945 137836 68946 137836 70782 137836 70782 137837 68946 137837 70865 137837 70782 137838 70865 137838 70784 137838 70784 137839 70865 137839 68947 137839 70784 137840 68947 137840 68948 137840 68948 137841 68947 137841 68949 137841 68948 137842 68949 137842 70785 137842 70785 137843 68949 137843 68951 137843 70785 137844 68951 137844 68950 137844 68950 137845 68951 137845 70843 137845 69352 137846 68959 137846 68952 137846 68952 137847 68959 137847 68953 137847 68952 137848 68953 137848 65642 137848 65642 137849 68953 137849 65644 137849 65644 137850 68953 137850 65646 137850 65646 137851 68953 137851 68954 137851 65646 137852 68954 137852 65647 137852 65647 137853 68954 137853 65648 137853 65648 137854 68954 137854 68955 137854 65648 137855 68955 137855 65640 137855 65640 137856 68955 137856 68940 137856 65640 137857 68940 137857 65641 137857 70773 137858 70774 137858 70864 137858 70864 137859 70774 137859 69379 137859 69379 137860 70774 137860 69377 137860 69377 137861 70774 137861 68956 137861 69377 137862 68956 137862 69375 137862 69375 137863 68956 137863 68958 137863 68958 137864 68956 137864 68957 137864 68958 137865 68957 137865 69380 137865 69380 137866 68957 137866 68961 137866 69380 137867 68961 137867 68962 137867 68979 137868 68959 137868 68960 137868 68960 137869 68959 137869 69352 137869 69001 137870 69000 137870 68961 137870 68961 137871 69000 137871 68962 137871 68968 137872 68963 137872 68964 137872 68964 137873 68963 137873 68965 137873 68964 137874 68965 137874 70719 137874 68966 137875 65549 137875 70716 137875 70716 137876 65549 137876 68967 137876 70716 137877 68967 137877 68968 137877 68968 137878 68967 137878 68969 137878 68968 137879 68969 137879 68963 137879 70728 137880 68980 137880 68978 137880 68978 137881 68980 137881 68977 137881 70716 137882 70717 137882 68966 137882 68966 137883 70717 137883 68970 137883 68966 137884 68970 137884 68971 137884 68971 137885 68970 137885 68972 137885 68971 137886 68972 137886 68973 137886 68973 137887 68972 137887 70731 137887 68973 137888 70731 137888 68974 137888 68974 137889 70731 137889 68975 137889 68974 137890 68975 137890 65546 137890 65546 137891 68975 137891 68976 137891 65546 137892 68976 137892 68977 137892 68977 137893 68976 137893 70729 137893 68977 137894 70729 137894 68978 137894 68982 137895 68979 137895 68960 137895 70728 137896 68981 137896 68980 137896 68980 137897 68981 137897 70727 137897 68980 137898 70727 137898 65544 137898 65544 137899 70727 137899 68982 137899 65544 137900 68982 137900 69603 137900 69603 137901 68982 137901 68960 137901 70764 137902 69664 137902 69665 137902 70764 137903 69665 137903 70765 137903 70765 137904 69665 137904 69666 137904 70765 137905 69666 137905 68983 137905 68983 137906 69666 137906 68984 137906 68983 137907 68984 137907 70761 137907 70761 137908 68984 137908 69668 137908 70761 137909 69668 137909 68985 137909 68985 137910 69668 137910 68986 137910 68985 137911 68986 137911 68987 137911 68987 137912 68986 137912 68988 137912 68988 137913 68986 137913 68989 137913 68988 137914 68989 137914 70770 137914 70770 137915 68989 137915 68990 137915 70770 137916 68990 137916 68991 137916 68991 137917 68990 137917 68992 137917 68991 137918 68992 137918 70768 137918 70768 137919 68992 137919 68993 137919 70768 137920 68993 137920 68995 137920 68993 137921 68994 137921 68995 137921 68995 137922 68994 137922 69670 137922 68995 137923 69670 137923 70771 137923 70771 137924 69670 137924 68996 137924 70771 137925 68996 137925 68997 137925 68996 137926 69672 137926 68997 137926 68997 137927 69672 137927 68998 137927 68997 137928 68998 137928 68999 137928 68999 137929 68998 137929 69000 137929 68999 137930 69000 137930 69001 137930 70719 137931 68965 137931 69007 137931 69007 137932 68965 137932 69002 137932 70764 137933 70762 137933 69664 137933 69664 137934 70762 137934 69011 137934 70724 137935 69003 137935 69349 137935 69349 137936 69003 137936 69351 137936 69351 137937 69003 137937 69350 137937 69350 137938 69003 137938 70723 137938 69350 137939 70723 137939 69004 137939 69004 137940 70723 137940 69005 137940 69005 137941 70723 137941 70720 137941 69005 137942 70720 137942 69006 137942 69006 137943 70720 137943 69007 137943 69006 137944 69007 137944 69002 137944 69387 137945 69008 137945 69009 137945 69009 137946 69008 137946 69384 137946 69009 137947 69384 137947 69010 137947 69010 137948 69384 137948 69385 137948 69010 137949 69385 137949 70760 137949 70760 137950 69385 137950 69011 137950 70760 137951 69011 137951 70762 137951 69387 137952 69009 137952 69389 137952 69389 137953 69009 137953 70670 137953 69389 137954 70670 137954 69012 137954 70724 137955 69349 137955 70722 137955 70722 137956 69349 137956 69013 137956 70722 137957 69013 137957 69014 137957 69014 137958 69013 137958 70860 137958 69014 137959 70860 137959 69015 137959 69015 137960 70860 137960 70858 137960 69015 137961 70858 137961 70797 137961 70858 137962 69016 137962 70797 137962 70797 137963 69016 137963 70853 137963 70797 137964 70853 137964 69022 137964 69028 137965 69017 137965 69018 137965 69018 137966 69017 137966 69346 137966 69346 137967 69017 137967 69345 137967 69345 137968 69017 137968 69019 137968 69345 137969 69019 137969 69020 137969 69020 137970 69019 137970 70713 137970 69020 137971 70713 137971 69021 137971 69021 137972 70713 137972 69022 137972 69021 137973 69022 137973 70853 137973 70669 137974 69024 137974 70826 137974 70826 137975 69024 137975 69023 137975 69023 137976 69024 137976 69393 137976 69393 137977 69024 137977 69025 137977 69393 137978 69025 137978 69392 137978 69392 137979 69025 137979 69390 137979 69390 137980 69025 137980 69026 137980 69390 137981 69026 137981 69394 137981 69394 137982 69026 137982 69027 137982 69394 137983 69027 137983 69029 137983 70796 137984 69028 137984 69576 137984 69576 137985 69028 137985 69018 137985 64847 137986 69684 137986 69027 137986 69027 137987 69684 137987 69029 137987 69030 137988 65558 137988 69034 137988 69034 137989 65558 137989 69032 137989 69032 137990 65558 137990 69031 137990 69032 137991 69031 137991 69033 137991 69030 137992 69034 137992 69035 137992 69035 137993 69034 137993 69036 137993 69035 137994 69036 137994 65556 137994 65556 137995 69036 137995 70707 137995 65556 137996 70707 137996 65555 137996 65555 137997 70707 137997 70709 137997 65555 137998 70709 137998 69037 137998 69037 137999 70709 137999 70710 137999 69037 138000 70710 138000 65553 138000 65553 138001 70710 138001 70705 138001 65553 138002 70705 138002 65554 138002 65554 138003 70705 138003 70706 138003 65554 138004 70706 138004 69038 138004 69038 138005 70706 138005 69039 138005 69038 138006 69039 138006 65552 138006 69582 138007 65551 138007 70703 138007 65552 138008 69039 138008 65551 138008 65551 138009 69039 138009 69040 138009 65551 138010 69040 138010 70703 138010 70714 138011 70796 138011 69576 138011 70703 138012 69041 138012 69582 138012 69582 138013 69041 138013 69042 138013 69582 138014 69042 138014 69580 138014 69580 138015 69042 138015 69043 138015 69580 138016 69043 138016 69579 138016 69579 138017 69043 138017 70714 138017 69579 138018 70714 138018 69577 138018 69577 138019 70714 138019 69576 138019 69044 138020 69686 138020 69687 138020 69044 138021 69687 138021 69045 138021 69045 138022 69687 138022 69688 138022 69045 138023 69688 138023 64835 138023 64835 138024 69688 138024 69046 138024 64835 138025 69046 138025 64836 138025 64836 138026 69046 138026 69047 138026 64836 138027 69047 138027 69048 138027 69048 138028 69047 138028 69049 138028 69048 138029 69049 138029 64837 138029 64837 138030 69049 138030 64838 138030 64838 138031 69049 138031 69050 138031 64838 138032 69050 138032 64842 138032 64842 138033 69050 138033 69690 138033 64842 138034 69690 138034 69051 138034 69051 138035 69690 138035 69691 138035 69051 138036 69691 138036 64840 138036 64840 138037 69691 138037 69052 138037 64840 138038 69052 138038 64839 138038 69052 138039 69693 138039 64839 138039 64839 138040 69693 138040 69694 138040 64839 138041 69694 138041 64843 138041 64843 138042 69694 138042 69696 138042 64843 138043 69696 138043 64844 138043 69696 138044 69053 138044 64844 138044 64844 138045 69053 138045 69054 138045 64844 138046 69054 138046 64846 138046 64846 138047 69054 138047 69684 138047 64846 138048 69684 138048 64847 138048 69033 138049 69031 138049 70712 138049 70712 138050 69031 138050 69344 138050 69044 138051 64960 138051 69686 138051 69686 138052 64960 138052 69055 138052 69065 138053 69057 138053 69336 138053 69336 138054 69057 138054 69056 138054 69056 138055 69057 138055 69340 138055 69340 138056 69057 138056 69058 138056 69340 138057 69058 138057 69339 138057 69339 138058 69058 138058 69342 138058 69342 138059 69058 138059 69059 138059 69342 138060 69059 138060 69060 138060 69060 138061 69059 138061 70712 138061 69060 138062 70712 138062 69344 138062 69063 138063 69398 138063 69061 138063 69061 138064 69398 138064 69062 138064 69061 138065 69062 138065 64833 138065 64833 138066 69062 138066 69396 138066 64833 138067 69396 138067 64834 138067 64834 138068 69396 138068 69055 138068 64834 138069 69055 138069 64960 138069 69063 138070 69061 138070 69400 138070 69400 138071 69061 138071 69064 138071 69400 138072 69064 138072 69401 138072 69065 138073 69336 138073 70799 138073 70799 138074 69336 138074 69066 138074 70799 138075 69066 138075 70800 138075 70800 138076 69066 138076 69067 138076 70800 138077 69067 138077 70801 138077 70801 138078 69067 138078 69068 138078 70801 138079 69068 138079 70802 138079 70802 138080 69068 138080 69069 138080 70802 138081 69069 138081 70803 138081 70803 138082 69069 138082 69070 138082 70803 138083 69070 138083 70686 138083 70686 138084 69070 138084 69071 138084 64859 138085 70823 138085 64858 138085 64858 138086 70823 138086 70830 138086 64858 138087 70830 138087 64956 138087 64956 138088 70830 138088 70829 138088 64956 138089 70829 138089 64958 138089 64958 138090 70829 138090 69072 138090 64958 138091 69072 138091 69073 138091 69073 138092 69072 138092 69074 138092 69073 138093 69074 138093 64831 138093 64831 138094 69074 138094 69075 138094 64831 138095 69075 138095 69064 138095 69064 138096 69075 138096 69401 138096 69077 138097 70684 138097 69076 138097 69077 138098 69076 138098 69078 138098 69078 138099 69076 138099 69079 138099 69078 138100 69079 138100 69334 138100 69334 138101 69079 138101 69080 138101 69080 138102 69079 138102 70687 138102 69080 138103 70687 138103 69333 138103 69333 138104 70687 138104 69081 138104 69081 138105 70687 138105 70686 138105 69081 138106 70686 138106 69071 138106 64859 138107 69082 138107 70823 138107 70823 138108 69082 138108 69406 138108 69406 138109 69082 138109 69405 138109 69405 138110 69082 138110 69083 138110 69405 138111 69083 138111 69404 138111 69404 138112 69083 138112 69402 138112 69402 138113 69083 138113 69084 138113 69402 138114 69084 138114 69086 138114 69086 138115 69084 138115 69085 138115 69086 138116 69085 138116 69407 138116 69101 138117 70684 138117 69558 138117 69558 138118 70684 138118 69077 138118 64856 138119 69087 138119 69085 138119 69085 138120 69087 138120 69407 138120 69088 138121 70694 138121 70693 138121 70694 138122 69088 138122 70695 138122 70695 138123 69088 138123 69556 138123 70695 138124 69556 138124 70698 138124 69089 138125 70689 138125 69095 138125 69095 138126 65559 138126 69089 138126 69089 138127 65559 138127 69090 138127 69089 138128 69090 138128 70690 138128 70690 138129 69090 138129 65560 138129 70690 138130 65560 138130 70691 138130 70691 138131 65560 138131 69091 138131 70691 138132 69091 138132 69092 138132 69092 138133 69091 138133 69093 138133 69092 138134 69093 138134 70692 138134 70692 138135 69093 138135 65563 138135 70692 138136 65563 138136 70693 138136 70693 138137 65563 138137 65564 138137 70693 138138 65564 138138 69088 138138 70689 138139 69094 138139 69095 138139 69095 138140 69094 138140 69096 138140 69095 138141 69096 138141 69562 138141 69562 138142 69096 138142 69097 138142 69562 138143 69097 138143 69098 138143 69098 138144 69097 138144 70688 138144 69098 138145 70688 138145 69560 138145 69560 138146 70688 138146 69099 138146 69560 138147 69099 138147 69100 138147 69100 138148 69099 138148 69101 138148 69100 138149 69101 138149 69558 138149 69102 138150 69713 138150 69715 138150 69102 138151 69715 138151 69103 138151 69103 138152 69715 138152 69716 138152 69103 138153 69716 138153 69104 138153 69104 138154 69716 138154 69105 138154 69104 138155 69105 138155 64862 138155 64862 138156 69105 138156 69106 138156 69106 138157 69105 138157 69718 138157 69106 138158 69718 138158 69107 138158 69107 138159 69718 138159 69108 138159 69107 138160 69108 138160 64851 138160 64851 138161 69108 138161 64849 138161 64849 138162 69108 138162 69109 138162 64849 138163 69109 138163 69110 138163 69110 138164 69109 138164 69111 138164 69110 138165 69111 138165 69112 138165 69112 138166 69111 138166 69720 138166 69112 138167 69720 138167 64852 138167 69720 138168 69113 138168 64852 138168 64852 138169 69113 138169 69719 138169 64852 138170 69719 138170 64853 138170 64853 138171 69719 138171 69114 138171 64853 138172 69114 138172 69115 138172 69115 138173 69114 138173 69721 138173 69721 138174 69722 138174 69115 138174 69115 138175 69722 138175 69117 138175 69115 138176 69117 138176 69116 138176 69116 138177 69117 138177 64855 138177 64855 138178 69117 138178 69087 138178 64855 138179 69087 138179 64856 138179 70698 138180 69556 138180 70696 138180 70696 138181 69556 138181 69332 138181 69102 138182 64955 138182 69713 138182 69713 138183 64955 138183 69712 138183 69118 138184 70702 138184 70674 138184 70674 138185 70702 138185 69330 138185 69330 138186 70702 138186 69119 138186 69119 138187 70702 138187 70701 138187 69119 138188 70701 138188 69329 138188 69329 138189 70701 138189 69120 138189 69120 138190 70701 138190 70697 138190 69120 138191 70697 138191 69121 138191 69121 138192 70697 138192 70696 138192 69121 138193 70696 138193 69332 138193 69412 138194 69411 138194 69124 138194 69124 138195 69411 138195 69408 138195 69124 138196 69408 138196 69122 138196 69122 138197 69408 138197 69410 138197 69122 138198 69410 138198 69123 138198 69123 138199 69410 138199 69712 138199 69123 138200 69712 138200 64955 138200 69412 138201 69124 138201 69125 138201 69125 138202 69124 138202 69126 138202 69125 138203 69126 138203 70822 138203 69134 138204 69414 138204 69127 138204 69127 138205 69414 138205 69128 138205 69127 138206 69128 138206 69129 138206 69129 138207 69128 138207 69130 138207 69129 138208 69130 138208 64953 138208 64953 138209 69130 138209 69131 138209 64953 138210 69131 138210 64954 138210 69131 138211 70831 138211 64954 138211 64954 138212 70831 138212 70822 138212 64954 138213 70822 138213 69126 138213 69325 138214 69324 138214 64913 138214 64913 138215 69324 138215 69320 138215 64913 138216 69320 138216 69132 138216 69132 138217 69320 138217 69322 138217 69132 138218 69322 138218 69133 138218 69133 138219 69322 138219 69137 138219 69133 138220 69137 138220 64914 138220 69325 138221 64913 138221 69326 138221 69326 138222 64913 138222 70672 138222 69326 138223 70672 138223 69327 138223 69134 138224 64870 138224 69414 138224 69414 138225 64870 138225 69415 138225 69415 138226 64870 138226 69418 138226 69418 138227 64870 138227 64869 138227 69418 138228 64869 138228 69417 138228 69417 138229 64869 138229 69421 138229 69421 138230 64869 138230 69135 138230 69421 138231 69135 138231 69422 138231 69422 138232 69135 138232 69138 138232 69422 138233 69138 138233 69140 138233 64915 138234 64914 138234 69136 138234 69136 138235 64914 138235 69137 138235 69174 138236 69139 138236 69138 138236 69138 138237 69139 138237 69140 138237 69141 138238 69142 138238 69150 138238 69142 138239 69141 138239 64936 138239 64936 138240 69141 138240 65569 138240 64936 138241 65569 138241 64924 138241 69152 138242 69538 138242 64921 138242 64921 138243 69538 138243 64922 138243 69538 138244 69540 138244 64922 138244 64922 138245 69540 138245 69143 138245 64922 138246 69143 138246 69144 138246 69144 138247 69143 138247 69146 138247 69144 138248 69146 138248 69145 138248 69145 138249 69146 138249 69147 138249 69145 138250 69147 138250 69148 138250 69148 138251 69147 138251 69149 138251 69148 138252 69149 138252 69150 138252 69150 138253 69149 138253 65566 138253 69150 138254 65566 138254 69141 138254 64921 138255 69151 138255 69152 138255 69152 138256 69151 138256 64919 138256 69152 138257 64919 138257 69153 138257 69153 138258 64919 138258 64920 138258 69153 138259 64920 138259 69154 138259 64920 138260 69155 138260 69154 138260 69154 138261 69155 138261 69156 138261 69154 138262 69156 138262 69157 138262 69157 138263 69156 138263 64917 138263 69157 138264 64917 138264 69158 138264 69158 138265 64917 138265 64916 138265 69158 138266 64916 138266 69159 138266 69159 138267 64916 138267 64915 138267 69159 138268 64915 138268 69136 138268 64872 138269 69491 138269 69492 138269 64872 138270 69492 138270 69160 138270 69160 138271 69492 138271 69161 138271 69160 138272 69161 138272 64877 138272 64877 138273 69161 138273 69162 138273 64877 138274 69162 138274 64875 138274 64875 138275 69162 138275 69163 138275 69163 138276 69162 138276 69164 138276 69163 138277 69164 138277 64878 138277 64878 138278 69164 138278 69493 138278 64878 138279 69493 138279 69165 138279 69165 138280 69493 138280 69495 138280 69165 138281 69495 138281 69166 138281 69166 138282 69495 138282 69167 138282 69166 138283 69167 138283 64867 138283 64867 138284 69167 138284 69496 138284 64867 138285 69496 138285 69170 138285 69496 138286 69168 138286 69170 138286 69170 138287 69168 138287 69169 138287 69170 138288 69169 138288 64865 138288 64865 138289 69169 138289 69498 138289 64865 138290 69498 138290 64863 138290 64863 138291 69498 138291 69500 138291 69500 138292 69171 138292 64863 138292 64863 138293 69171 138293 69172 138293 64863 138294 69172 138294 64950 138294 64950 138295 69172 138295 69173 138295 69173 138296 69172 138296 69139 138296 69173 138297 69139 138297 69174 138297 64924 138298 65569 138298 64925 138298 64925 138299 65569 138299 69537 138299 64872 138300 69175 138300 69491 138300 69491 138301 69175 138301 69182 138301 64926 138302 69176 138302 69184 138302 69184 138303 69176 138303 69319 138303 69319 138304 69176 138304 65657 138304 65657 138305 69176 138305 64923 138305 65657 138306 64923 138306 65653 138306 65653 138307 64923 138307 69177 138307 65653 138308 69177 138308 65655 138308 65655 138309 69177 138309 69178 138309 69178 138310 69177 138310 64925 138310 69178 138311 64925 138311 69537 138311 69427 138312 69425 138312 69183 138312 69183 138313 69425 138313 69179 138313 69183 138314 69179 138314 64871 138314 64871 138315 69179 138315 69180 138315 64871 138316 69180 138316 69181 138316 69181 138317 69180 138317 69182 138317 69181 138318 69182 138318 69175 138318 69427 138319 69183 138319 69428 138319 69428 138320 69183 138320 69193 138320 69428 138321 69193 138321 70835 138321 64926 138322 69184 138322 64937 138322 64937 138323 69184 138323 69185 138323 64937 138324 69185 138324 64939 138324 64939 138325 69185 138325 69186 138325 64939 138326 69186 138326 69187 138326 69187 138327 69186 138327 70842 138327 69187 138328 70842 138328 69189 138328 69189 138329 70842 138329 69188 138329 69189 138330 69188 138330 69190 138330 69190 138331 69188 138331 70807 138331 69190 138332 70807 138332 64900 138332 64900 138333 70807 138333 70806 138333 64883 138334 69727 138334 64946 138334 64946 138335 69727 138335 69192 138335 64946 138336 69192 138336 69191 138336 69191 138337 69192 138337 70805 138337 69191 138338 70805 138338 69194 138338 70835 138339 69193 138339 70833 138339 70833 138340 69193 138340 64873 138340 70833 138341 64873 138341 69194 138341 69194 138342 64873 138342 64948 138342 69194 138343 64948 138343 69191 138343 69195 138344 69314 138344 69196 138344 69196 138345 69314 138345 69312 138345 69196 138346 69312 138346 64902 138346 64902 138347 69312 138347 69197 138347 64902 138348 69197 138348 69199 138348 69199 138349 69197 138349 69198 138349 69199 138350 69198 138350 64903 138350 69195 138351 69196 138351 69200 138351 69200 138352 69196 138352 64900 138352 69200 138353 64900 138353 70806 138353 64883 138354 69201 138354 69727 138354 69727 138355 69201 138355 69202 138355 69202 138356 69201 138356 69203 138356 69203 138357 69201 138357 69204 138357 69203 138358 69204 138358 69728 138358 69728 138359 69204 138359 69730 138359 69730 138360 69204 138360 69205 138360 69730 138361 69205 138361 69731 138361 69731 138362 69205 138362 69206 138362 69206 138363 69205 138363 69207 138363 69206 138364 69207 138364 69744 138364 69208 138365 64903 138365 69517 138365 69517 138366 64903 138366 69198 138366 64881 138367 69743 138367 69207 138367 69207 138368 69743 138368 69744 138368 69514 138369 69209 138369 64897 138369 69514 138370 64897 138370 69210 138370 69210 138371 64897 138371 64941 138371 69210 138372 64941 138372 69211 138372 69211 138373 64941 138373 69212 138373 69211 138374 69212 138374 69522 138374 69212 138375 69213 138375 69522 138375 69522 138376 69213 138376 64905 138376 69522 138377 64905 138377 69214 138377 69214 138378 64905 138378 64910 138378 69214 138379 64910 138379 69215 138379 69215 138380 64910 138380 69216 138380 69215 138381 69216 138381 69521 138381 69521 138382 69216 138382 64909 138382 69521 138383 64909 138383 69519 138383 69519 138384 64909 138384 64908 138384 69519 138385 64908 138385 69217 138385 69217 138386 64908 138386 64907 138386 69217 138387 64907 138387 69520 138387 69520 138388 64907 138388 69218 138388 69520 138389 69218 138389 69219 138389 69219 138390 69218 138390 69220 138390 69219 138391 69220 138391 69221 138391 69221 138392 69220 138392 69222 138392 69221 138393 69222 138393 69223 138393 69223 138394 69222 138394 64904 138394 69223 138395 64904 138395 69224 138395 69224 138396 64904 138396 69225 138396 69224 138397 69225 138397 69226 138397 69226 138398 69225 138398 69208 138398 69226 138399 69208 138399 69517 138399 69229 138400 69230 138400 69227 138400 69227 138401 69230 138401 64888 138401 69227 138402 64888 138402 69228 138402 69229 138403 69747 138403 69230 138403 69230 138404 69747 138404 69750 138404 69230 138405 69750 138405 69231 138405 69231 138406 69750 138406 69749 138406 69231 138407 69749 138407 64889 138407 64889 138408 69749 138408 69232 138408 64889 138409 69232 138409 69234 138409 69234 138410 69232 138410 69233 138410 69234 138411 69233 138411 64891 138411 64891 138412 69233 138412 69235 138412 64891 138413 69235 138413 69236 138413 69236 138414 69235 138414 69752 138414 69236 138415 69752 138415 69237 138415 69237 138416 69752 138416 69238 138416 69237 138417 69238 138417 69239 138417 69239 138418 69238 138418 69751 138418 69239 138419 69751 138419 64893 138419 64893 138420 69751 138420 69240 138420 64893 138421 69240 138421 69241 138421 69241 138422 69240 138422 69754 138422 69241 138423 69754 138423 69242 138423 69242 138424 69754 138424 64894 138424 69754 138425 69243 138425 64894 138425 64894 138426 69243 138426 69756 138426 64894 138427 69756 138427 69244 138427 69244 138428 69756 138428 69245 138428 69244 138429 69245 138429 64945 138429 69743 138430 64881 138430 65536 138430 65536 138431 64881 138431 64880 138431 65536 138432 64880 138432 69246 138432 69246 138433 64880 138433 64945 138433 69246 138434 64945 138434 69247 138434 69247 138435 64945 138435 69245 138435 69209 138436 69514 138436 69248 138436 69248 138437 69514 138437 69515 138437 64888 138438 69249 138438 69228 138438 69228 138439 69249 138439 69256 138439 69261 138440 64896 138440 69308 138440 69308 138441 64896 138441 69309 138441 69309 138442 64896 138442 69306 138442 69306 138443 64896 138443 69250 138443 69306 138444 69250 138444 69251 138444 69251 138445 69250 138445 64899 138445 69251 138446 64899 138446 65661 138446 65661 138447 64899 138447 69252 138447 69252 138448 64899 138448 69248 138448 69252 138449 69248 138449 69515 138449 69257 138450 69734 138450 69253 138450 69253 138451 69734 138451 69254 138451 69253 138452 69254 138452 64886 138452 64886 138453 69254 138453 69255 138453 64886 138454 69255 138454 64887 138454 64887 138455 69255 138455 69256 138455 64887 138456 69256 138456 69249 138456 69257 138457 69253 138457 69736 138457 69736 138458 69253 138458 64885 138458 69736 138459 64885 138459 70839 138459 69261 138460 69308 138460 70810 138460 70839 138461 64885 138461 70838 138461 70838 138462 64885 138462 69258 138462 70838 138463 69258 138463 69259 138463 69259 138464 69258 138464 64943 138464 69259 138465 64943 138465 70809 138465 70809 138466 64943 138466 69260 138466 70809 138467 69260 138467 70810 138467 70810 138468 69260 138468 64898 138468 70810 138469 64898 138469 69261 138469 70811 138470 69307 138470 69262 138470 69262 138471 69307 138471 69310 138471 69262 138472 69310 138472 69525 138472 69525 138473 69315 138473 69316 138473 69525 138474 69316 138474 69262 138474 69262 138475 69316 138475 69317 138475 69262 138476 69317 138476 70808 138476 69267 138477 69318 138477 69265 138477 65652 138478 69263 138478 65658 138478 65658 138479 69263 138479 69264 138479 65658 138480 69264 138480 69265 138480 69265 138481 69264 138481 69266 138481 69265 138482 69266 138482 69267 138482 65651 138483 69268 138483 69269 138483 69271 138484 69331 138484 69573 138484 69269 138485 69270 138485 65651 138485 65651 138486 69270 138486 69271 138486 65651 138487 69271 138487 69272 138487 69272 138488 69271 138488 69573 138488 69275 138489 69273 138489 69337 138489 69337 138490 69341 138490 69275 138490 69275 138491 69341 138491 69583 138491 69275 138492 69583 138492 69585 138492 69585 138493 65649 138493 69275 138493 69275 138494 65649 138494 69274 138494 69275 138495 69274 138495 65650 138495 69280 138496 69276 138496 69277 138496 69277 138497 69278 138497 69280 138497 69280 138498 69278 138498 69604 138498 69280 138499 69604 138499 65645 138499 65645 138500 69279 138500 69280 138500 69280 138501 69279 138501 69281 138501 69280 138502 69281 138502 70851 138502 69284 138503 70849 138503 69353 138503 69353 138504 69282 138504 69284 138504 69284 138505 69282 138505 69357 138505 69284 138506 69357 138506 69359 138506 69359 138507 69365 138507 69284 138507 69284 138508 69365 138508 69283 138508 69284 138509 69283 138509 70863 138509 70846 138510 69285 138510 69286 138510 69286 138511 69285 138511 69367 138511 69286 138512 69367 138512 69659 138512 69659 138513 69287 138513 69373 138513 69659 138514 69373 138514 69286 138514 69286 138515 69373 138515 69288 138515 69286 138516 69288 138516 70847 138516 69378 138517 69383 138517 69290 138517 69290 138518 69383 138518 69289 138518 69290 138519 69289 138519 69291 138519 69291 138520 69289 138520 70844 138520 70844 138521 69289 138521 69388 138521 70844 138522 69388 138522 69292 138522 69697 138523 69399 138523 69293 138523 69293 138524 69399 138524 69294 138524 69293 138525 69294 138525 69295 138525 69295 138526 69294 138526 69296 138526 69296 138527 69294 138527 69297 138527 69296 138528 69297 138528 70827 138528 69300 138529 70825 138529 69298 138529 69298 138530 69299 138530 69300 138530 69300 138531 69299 138531 70630 138531 69300 138532 70630 138532 70621 138532 70621 138533 69301 138533 69300 138533 69300 138534 69301 138534 69413 138534 69300 138535 69413 138535 70820 138535 69303 138536 70818 138536 69302 138536 69302 138537 69420 138537 69303 138537 69303 138538 69420 138538 69502 138538 69303 138539 69502 138539 69426 138539 69426 138540 69304 138540 69303 138540 69303 138541 69304 138541 69305 138541 69303 138542 69305 138542 70834 138542 69525 138543 69309 138543 69535 138543 69535 138544 69309 138544 69306 138544 69535 138545 69306 138545 69251 138545 70811 138546 69308 138546 69307 138546 69307 138547 69308 138547 69309 138547 69307 138548 69309 138548 69310 138548 69310 138549 69309 138549 69525 138549 69315 138550 69311 138550 69312 138550 69312 138551 69311 138551 69313 138551 69312 138552 69313 138552 69197 138552 69197 138553 69313 138553 69534 138553 69197 138554 69534 138554 69198 138554 69312 138555 69314 138555 69315 138555 69315 138556 69314 138556 69195 138556 69315 138557 69195 138557 69316 138557 69316 138558 69195 138558 69200 138558 69316 138559 69200 138559 69317 138559 69317 138560 69200 138560 70806 138560 69317 138561 70806 138561 70808 138561 69265 138562 69318 138562 69319 138562 69319 138563 69318 138563 69184 138563 69263 138564 69321 138564 69320 138564 69320 138565 69321 138565 69543 138565 69320 138566 69543 138566 69322 138566 69322 138567 69543 138567 69323 138567 69322 138568 69323 138568 69137 138568 69320 138569 69324 138569 69263 138569 69263 138570 69324 138570 69325 138570 69263 138571 69325 138571 69264 138571 69264 138572 69325 138572 69326 138572 69264 138573 69326 138573 69266 138573 69266 138574 69326 138574 69327 138574 69266 138575 69327 138575 69267 138575 69269 138576 70674 138576 69270 138576 69270 138577 70674 138577 69330 138577 69120 138578 69575 138578 69329 138578 69329 138579 69575 138579 69328 138579 69329 138580 69328 138580 69119 138580 69119 138581 69328 138581 69331 138581 69119 138582 69331 138582 69330 138582 69330 138583 69331 138583 69271 138583 69330 138584 69271 138584 69270 138584 69120 138585 69121 138585 69575 138585 69575 138586 69121 138586 69332 138586 69575 138587 69332 138587 69557 138587 69081 138588 65651 138588 69333 138588 69333 138589 65651 138589 69272 138589 69333 138590 69272 138590 69080 138590 69080 138591 69272 138591 69573 138591 69080 138592 69573 138592 69334 138592 69334 138593 69573 138593 69335 138593 69334 138594 69335 138594 69078 138594 69078 138595 69335 138595 69572 138595 69078 138596 69572 138596 69077 138596 69273 138597 69336 138597 69337 138597 69337 138598 69336 138598 69056 138598 69342 138599 69343 138599 69339 138599 69339 138600 69343 138600 69338 138600 69339 138601 69338 138601 69340 138601 69340 138602 69338 138602 69583 138602 69340 138603 69583 138603 69056 138603 69056 138604 69583 138604 69341 138604 69056 138605 69341 138605 69337 138605 69342 138606 69060 138606 69343 138606 69343 138607 69060 138607 69344 138607 69343 138608 69344 138608 69598 138608 69020 138609 69586 138609 69345 138609 69345 138610 69586 138610 69347 138610 69345 138611 69347 138611 69346 138611 69346 138612 69347 138612 69348 138612 69346 138613 69348 138613 69018 138613 69276 138614 69349 138614 69277 138614 69277 138615 69349 138615 69351 138615 69005 138616 69612 138616 69004 138616 69004 138617 69612 138617 69611 138617 69004 138618 69611 138618 69350 138618 69350 138619 69611 138619 69604 138619 69350 138620 69604 138620 69351 138620 69351 138621 69604 138621 69278 138621 69351 138622 69278 138622 69277 138622 69005 138623 69006 138623 69612 138623 69612 138624 69006 138624 69002 138624 69612 138625 69002 138625 69613 138625 65643 138626 69600 138626 68952 138626 68952 138627 69600 138627 69352 138627 70849 138628 70850 138628 69353 138628 69353 138629 70850 138629 69354 138629 68935 138630 69632 138630 69355 138630 69355 138631 69632 138631 69631 138631 69355 138632 69631 138632 69356 138632 69356 138633 69631 138633 69357 138633 69356 138634 69357 138634 69354 138634 69354 138635 69357 138635 69282 138635 69354 138636 69282 138636 69353 138636 68935 138637 69358 138637 69632 138637 69632 138638 69358 138638 68930 138638 69632 138639 68930 138639 69634 138639 69359 138640 69360 138640 68878 138640 68878 138641 69360 138641 69642 138641 68878 138642 69642 138642 68879 138642 68879 138643 69642 138643 69361 138643 68879 138644 69361 138644 68882 138644 68878 138645 69362 138645 69359 138645 69359 138646 69362 138646 69363 138646 69359 138647 69363 138647 69365 138647 69365 138648 69363 138648 69364 138648 69365 138649 69364 138649 69283 138649 69283 138650 69364 138650 68871 138650 69283 138651 68871 138651 70863 138651 70846 138652 68884 138652 69285 138652 69285 138653 68884 138653 68885 138653 68889 138654 69366 138654 68888 138654 68888 138655 69366 138655 69660 138655 68888 138656 69660 138656 68886 138656 68886 138657 69660 138657 69659 138657 68886 138658 69659 138658 68885 138658 68885 138659 69659 138659 69367 138659 68885 138660 69367 138660 69285 138660 68889 138661 68890 138661 69366 138661 69366 138662 68890 138662 68892 138662 69366 138663 68892 138663 69662 138663 69287 138664 69368 138664 69370 138664 69370 138665 69368 138665 69369 138665 69370 138666 69369 138666 69371 138666 69371 138667 69369 138667 69657 138667 69371 138668 69657 138668 68937 138668 69370 138669 69372 138669 69287 138669 69287 138670 69372 138670 68936 138670 69287 138671 68936 138671 69373 138671 69373 138672 68936 138672 69374 138672 69373 138673 69374 138673 69288 138673 69288 138674 69374 138674 70843 138674 69288 138675 70843 138675 70847 138675 70844 138676 70864 138676 69291 138676 69291 138677 70864 138677 69379 138677 68958 138678 69381 138678 69375 138678 69375 138679 69381 138679 69376 138679 69375 138680 69376 138680 69377 138680 69377 138681 69376 138681 69378 138681 69377 138682 69378 138682 69379 138682 69379 138683 69378 138683 69290 138683 69379 138684 69290 138684 69291 138684 68958 138685 69380 138685 69381 138685 69381 138686 69380 138686 68962 138686 69381 138687 68962 138687 69382 138687 69383 138688 69683 138688 69384 138688 69384 138689 69683 138689 69682 138689 69384 138690 69682 138690 69385 138690 69385 138691 69682 138691 69386 138691 69385 138692 69386 138692 69011 138692 69384 138693 69008 138693 69383 138693 69383 138694 69008 138694 69387 138694 69383 138695 69387 138695 69289 138695 69289 138696 69387 138696 69389 138696 69289 138697 69389 138697 69388 138697 69388 138698 69389 138698 69012 138698 69388 138699 69012 138699 69292 138699 69296 138700 70826 138700 69295 138700 69295 138701 70826 138701 69023 138701 69390 138702 69700 138702 69392 138702 69392 138703 69700 138703 69391 138703 69392 138704 69391 138704 69393 138704 69393 138705 69391 138705 69697 138705 69393 138706 69697 138706 69023 138706 69023 138707 69697 138707 69293 138707 69023 138708 69293 138708 69295 138708 69390 138709 69394 138709 69700 138709 69700 138710 69394 138710 69029 138710 69700 138711 69029 138711 69701 138711 69399 138712 69395 138712 69062 138712 69062 138713 69395 138713 69397 138713 69062 138714 69397 138714 69396 138714 69396 138715 69397 138715 69711 138715 69396 138716 69711 138716 69055 138716 69062 138717 69398 138717 69399 138717 69399 138718 69398 138718 69063 138718 69399 138719 69063 138719 69294 138719 69294 138720 69063 138720 69400 138720 69294 138721 69400 138721 69297 138721 69297 138722 69400 138722 69401 138722 69297 138723 69401 138723 70827 138723 70825 138724 70823 138724 69298 138724 69298 138725 70823 138725 69406 138725 69402 138726 69403 138726 69404 138726 69404 138727 69403 138727 70631 138727 69404 138728 70631 138728 69405 138728 69405 138729 70631 138729 70630 138729 69405 138730 70630 138730 69406 138730 69406 138731 70630 138731 69299 138731 69406 138732 69299 138732 69298 138732 69402 138733 69086 138733 69403 138733 69403 138734 69086 138734 69407 138734 69403 138735 69407 138735 70632 138735 70621 138736 70637 138736 69408 138736 69408 138737 70637 138737 69409 138737 69408 138738 69409 138738 69410 138738 69410 138739 69409 138739 70636 138739 69410 138740 70636 138740 69712 138740 69408 138741 69411 138741 70621 138741 70621 138742 69411 138742 69412 138742 70621 138743 69412 138743 69301 138743 69301 138744 69412 138744 69125 138744 69301 138745 69125 138745 69413 138745 69413 138746 69125 138746 70822 138746 69413 138747 70822 138747 70820 138747 70818 138748 69414 138748 69302 138748 69302 138749 69414 138749 69415 138749 69421 138750 69416 138750 69417 138750 69417 138751 69416 138751 69419 138751 69417 138752 69419 138752 69418 138752 69418 138753 69419 138753 69502 138753 69418 138754 69502 138754 69415 138754 69415 138755 69502 138755 69420 138755 69415 138756 69420 138756 69302 138756 69421 138757 69422 138757 69416 138757 69416 138758 69422 138758 69140 138758 69416 138759 69140 138759 69490 138759 69426 138760 69423 138760 69179 138760 69179 138761 69423 138761 69424 138761 69179 138762 69424 138762 69180 138762 69180 138763 69424 138763 69513 138763 69180 138764 69513 138764 69182 138764 69179 138765 69425 138765 69426 138765 69426 138766 69425 138766 69427 138766 69426 138767 69427 138767 69304 138767 69304 138768 69427 138768 69428 138768 69304 138769 69428 138769 69305 138769 69305 138770 69428 138770 70835 138770 69305 138771 70835 138771 70834 138771 69429 138772 69523 138772 69430 138772 69430 138773 69523 138773 69524 138773 69430 138774 69524 138774 67945 138774 67945 138775 69524 138775 69431 138775 67945 138776 69431 138776 67944 138776 67944 138777 69431 138777 69536 138777 67944 138778 69536 138778 67943 138778 67943 138779 69536 138779 69432 138779 67943 138780 69432 138780 69433 138780 69433 138781 69432 138781 69528 138781 69433 138782 69528 138782 67941 138782 67941 138783 69528 138783 69529 138783 65632 138784 69555 138784 67933 138784 67933 138785 69555 138785 69434 138785 67933 138786 69434 138786 69435 138786 69435 138787 69434 138787 69554 138787 69435 138788 69554 138788 67931 138788 67931 138789 69554 138789 69541 138789 67931 138790 69541 138790 67930 138790 67930 138791 69541 138791 69545 138791 67930 138792 69545 138792 67929 138792 67929 138793 69545 138793 69547 138793 67929 138794 69547 138794 67927 138794 67927 138795 69547 138795 65629 138795 65628 138796 69569 138796 67915 138796 67915 138797 69569 138797 69436 138797 67915 138798 69436 138798 69437 138798 69437 138799 69436 138799 69574 138799 69437 138800 69574 138800 69438 138800 69438 138801 69574 138801 69564 138801 69438 138802 69564 138802 69439 138802 69439 138803 69564 138803 69566 138803 69439 138804 69566 138804 69440 138804 69440 138805 69566 138805 69567 138805 69440 138806 69567 138806 69441 138806 69441 138807 69567 138807 69442 138807 67902 138808 69597 138808 69443 138808 69443 138809 69597 138809 69444 138809 69443 138810 69444 138810 67900 138810 67900 138811 69444 138811 69587 138811 67900 138812 69587 138812 67899 138812 67899 138813 69587 138813 69589 138813 67899 138814 69589 138814 67908 138814 67908 138815 69589 138815 69445 138815 67908 138816 69445 138816 67906 138816 67906 138817 69445 138817 69591 138817 67906 138818 69591 138818 67903 138818 67903 138819 69591 138819 69593 138819 67897 138820 65616 138820 69446 138820 69446 138821 65616 138821 69447 138821 69446 138822 69447 138822 69448 138822 69448 138823 69447 138823 69609 138823 69448 138824 69609 138824 67895 138824 67895 138825 69609 138825 69610 138825 67895 138826 69610 138826 69449 138826 69449 138827 69610 138827 69450 138827 69449 138828 69450 138828 67894 138828 67894 138829 69450 138829 69451 138829 67894 138830 69451 138830 67892 138830 67892 138831 69451 138831 69452 138831 65610 138832 69635 138832 67876 138832 67876 138833 69635 138833 69636 138833 67876 138834 69636 138834 69453 138834 69453 138835 69636 138835 69637 138835 69453 138836 69637 138836 67878 138836 67878 138837 69637 138837 69639 138837 67878 138838 69639 138838 69454 138838 69454 138839 69639 138839 69455 138839 69454 138840 69455 138840 67880 138840 67880 138841 69455 138841 69640 138841 67880 138842 69640 138842 69456 138842 69456 138843 69640 138843 69641 138843 69456 138844 69641 138844 67882 138844 67882 138845 69641 138845 65604 138845 67865 138846 69663 138846 69457 138846 69457 138847 69663 138847 69459 138847 69457 138848 69459 138848 69458 138848 69458 138849 69459 138849 69460 138849 69458 138850 69460 138850 69462 138850 69462 138851 69460 138851 69461 138851 69462 138852 69461 138852 69463 138852 69463 138853 69461 138853 69464 138853 69463 138854 69464 138854 67870 138854 67870 138855 69464 138855 69465 138855 67870 138856 69465 138856 67872 138856 67872 138857 69465 138857 69658 138857 67861 138858 69677 138858 69466 138858 69466 138859 69677 138859 69467 138859 69466 138860 69467 138860 67859 138860 67859 138861 69467 138861 69679 138861 67859 138862 69679 138862 69468 138862 69468 138863 69679 138863 69680 138863 69468 138864 69680 138864 67858 138864 67858 138865 69680 138865 69469 138865 67858 138866 69469 138866 69471 138866 69471 138867 69469 138867 69470 138867 69471 138868 69470 138868 65592 138868 65592 138869 69470 138869 65593 138869 65591 138870 69707 138870 67853 138870 67853 138871 69707 138871 69709 138871 67853 138872 69709 138872 69472 138872 69472 138873 69709 138873 69473 138873 69472 138874 69473 138874 69474 138874 69474 138875 69473 138875 69475 138875 69474 138876 69475 138876 69476 138876 69476 138877 69475 138877 69706 138877 69476 138878 69706 138878 67850 138878 67850 138879 69706 138879 69477 138879 67850 138880 69477 138880 67849 138880 67849 138881 69477 138881 69699 138881 67843 138882 70629 138882 69478 138882 69478 138883 70629 138883 69479 138883 69478 138884 69479 138884 67840 138884 67840 138885 69479 138885 69480 138885 67840 138886 69480 138886 69481 138886 69481 138887 69480 138887 69482 138887 69481 138888 69482 138888 67839 138888 67839 138889 69482 138889 70622 138889 67839 138890 70622 138890 69483 138890 69483 138891 70622 138891 69484 138891 69483 138892 69484 138892 67838 138892 67838 138893 69484 138893 65580 138893 65578 138894 65579 138894 69485 138894 69485 138895 65579 138895 69511 138895 69485 138896 69511 138896 69486 138896 69486 138897 69511 138897 69504 138897 69486 138898 69504 138898 69487 138898 69487 138899 69504 138899 69488 138899 69487 138900 69488 138900 67834 138900 67834 138901 69488 138901 69489 138901 67834 138902 69489 138902 67833 138902 67833 138903 69489 138903 69503 138903 67833 138904 69503 138904 65571 138904 65571 138905 69503 138905 69505 138905 69139 138906 69506 138906 69140 138906 69140 138907 69506 138907 69490 138907 69182 138908 69513 138908 69491 138908 69491 138909 69513 138909 69512 138909 69491 138910 69512 138910 69492 138910 69492 138911 69512 138911 69510 138911 69492 138912 69510 138912 69161 138912 69161 138913 69510 138913 69162 138913 69162 138914 69510 138914 69509 138914 69162 138915 69509 138915 69164 138915 69164 138916 69509 138916 69493 138916 69493 138917 69509 138917 69494 138917 69493 138918 69494 138918 69495 138918 69169 138919 69168 138919 69497 138919 69497 138920 69168 138920 69496 138920 69497 138921 69496 138921 69494 138921 69494 138922 69496 138922 69167 138922 69494 138923 69167 138923 69495 138923 69169 138924 69497 138924 69498 138924 69498 138925 69497 138925 69499 138925 69498 138926 69499 138926 69500 138926 69500 138927 69499 138927 69171 138927 69171 138928 69499 138928 69501 138928 69171 138929 69501 138929 69172 138929 69172 138930 69501 138930 69506 138930 69172 138931 69506 138931 69139 138931 69503 138932 69489 138932 69502 138932 69502 138933 69489 138933 69426 138933 69502 138934 69419 138934 69503 138934 69503 138935 69419 138935 69416 138935 69503 138936 69416 138936 69505 138936 69511 138937 69513 138937 69504 138937 69504 138938 69513 138938 69424 138938 69489 138939 69488 138939 69426 138939 69426 138940 69488 138940 69504 138940 69426 138941 69504 138941 69423 138941 69423 138942 69504 138942 69424 138942 69416 138943 69490 138943 69505 138943 69505 138944 69490 138944 69506 138944 69505 138945 69506 138945 65572 138945 65572 138946 69506 138946 69501 138946 65572 138947 69501 138947 69507 138947 69507 138948 69501 138948 69499 138948 69507 138949 69499 138949 65575 138949 65575 138950 69499 138950 69497 138950 65575 138951 69497 138951 69508 138951 69508 138952 69497 138952 69494 138952 69508 138953 69494 138953 65577 138953 65577 138954 69494 138954 69509 138954 65577 138955 69509 138955 65579 138955 65579 138956 69509 138956 69510 138956 65579 138957 69510 138957 69511 138957 69511 138958 69510 138958 69512 138958 69511 138959 69512 138959 69513 138959 69514 138960 69526 138960 69515 138960 69515 138961 69526 138961 65659 138961 69198 138962 69534 138962 69517 138962 69517 138963 69534 138963 69516 138963 69517 138964 69516 138964 69226 138964 69226 138965 69516 138965 69533 138965 69226 138966 69533 138966 69224 138966 69224 138967 69533 138967 69223 138967 69223 138968 69533 138968 69518 138968 69223 138969 69518 138969 69221 138969 69519 138970 69217 138970 69532 138970 69532 138971 69217 138971 69520 138971 69532 138972 69520 138972 69518 138972 69518 138973 69520 138973 69219 138973 69518 138974 69219 138974 69221 138974 69519 138975 69532 138975 69521 138975 69521 138976 69532 138976 69531 138976 69521 138977 69531 138977 69215 138977 69215 138978 69531 138978 69214 138978 69214 138979 69531 138979 65570 138979 69214 138980 65570 138980 69522 138980 65639 138981 69534 138981 69523 138981 69523 138982 69534 138982 69313 138982 69313 138983 69311 138983 69523 138983 69523 138984 69311 138984 69315 138984 69523 138985 69315 138985 69524 138985 69524 138986 69315 138986 69431 138986 69431 138987 69315 138987 69525 138987 69431 138988 69525 138988 69536 138988 69432 138989 69526 138989 69528 138989 69528 138990 69526 138990 69527 138990 69528 138991 69527 138991 69529 138991 69529 138992 69527 138992 65570 138992 69529 138993 65570 138993 69530 138993 69530 138994 65570 138994 69531 138994 69530 138995 69531 138995 65635 138995 65635 138996 69531 138996 69532 138996 65635 138997 69532 138997 65636 138997 65636 138998 69532 138998 69518 138998 65636 138999 69518 138999 65638 138999 65638 139000 69518 139000 69533 139000 65638 139001 69533 139001 65639 139001 65639 139002 69533 139002 69516 139002 65639 139003 69516 139003 69534 139003 69525 139004 69535 139004 69536 139004 69536 139005 69535 139005 65660 139005 69536 139006 65660 139006 69432 139006 69432 139007 65660 139007 65659 139007 69432 139008 65659 139008 69526 139008 65569 139009 65568 139009 69537 139009 69537 139010 65568 139010 65656 139010 69137 139011 69323 139011 69136 139011 69136 139012 69323 139012 69553 139012 69136 139013 69553 139013 69159 139013 69159 139014 69553 139014 69552 139014 69159 139015 69552 139015 69158 139015 69158 139016 69552 139016 69157 139016 69157 139017 69552 139017 69550 139017 69157 139018 69550 139018 69154 139018 69540 139019 69538 139019 69539 139019 69539 139020 69538 139020 69152 139020 69539 139021 69152 139021 69550 139021 69550 139022 69152 139022 69153 139022 69550 139023 69153 139023 69154 139023 69540 139024 69539 139024 69143 139024 69143 139025 69539 139025 69548 139025 69143 139026 69548 139026 69146 139026 69541 139027 65656 139027 65568 139027 69544 139028 69542 139028 69323 139028 69323 139029 69543 139029 69544 139029 69544 139030 69543 139030 69321 139030 69544 139031 69321 139031 69263 139031 69541 139032 65568 139032 69545 139032 69545 139033 65568 139033 69546 139033 69545 139034 69546 139034 69547 139034 69547 139035 69546 139035 65567 139035 69547 139036 65567 139036 65629 139036 65629 139037 65567 139037 69548 139037 65629 139038 69548 139038 65630 139038 65630 139039 69548 139039 69539 139039 65630 139040 69539 139040 69549 139040 69549 139041 69539 139041 69550 139041 69549 139042 69550 139042 69551 139042 69551 139043 69550 139043 69552 139043 69551 139044 69552 139044 69542 139044 69542 139045 69552 139045 69553 139045 69542 139046 69553 139046 69323 139046 65656 139047 69541 139047 65654 139047 65654 139048 69541 139048 69554 139048 65654 139049 69554 139049 65652 139049 65652 139050 69554 139050 69434 139050 65652 139051 69434 139051 69263 139051 69263 139052 69434 139052 69555 139052 69263 139053 69555 139053 69544 139053 69556 139054 65565 139054 69332 139054 69332 139055 65565 139055 69557 139055 69077 139056 69572 139056 69558 139056 69558 139057 69572 139057 69571 139057 69558 139058 69571 139058 69100 139058 69100 139059 69571 139059 69559 139059 69100 139060 69559 139060 69560 139060 69560 139061 69559 139061 69098 139061 69098 139062 69559 139062 69561 139062 69098 139063 69561 139063 69562 139063 69562 139064 69561 139064 69095 139064 69095 139065 69561 139065 69563 139065 69095 139066 69563 139066 65559 139066 69436 139067 69569 139067 69331 139067 69574 139068 65565 139068 69564 139068 69564 139069 65565 139069 69565 139069 69564 139070 69565 139070 69566 139070 69566 139071 69565 139071 65562 139071 69566 139072 65562 139072 69567 139072 69567 139073 65562 139073 65561 139073 69567 139074 65561 139074 69442 139074 69442 139075 65561 139075 69563 139075 69442 139076 69563 139076 69568 139076 69568 139077 69563 139077 69561 139077 69568 139078 69561 139078 65625 139078 65625 139079 69561 139079 69559 139079 65625 139080 69559 139080 69570 139080 69331 139081 69569 139081 69573 139081 69573 139082 69569 139082 65627 139082 69573 139083 65627 139083 65626 139083 69559 139084 69571 139084 69570 139084 69570 139085 69571 139085 69572 139085 69570 139086 69572 139086 65626 139086 65626 139087 69572 139087 69335 139087 65626 139088 69335 139088 69573 139088 69331 139089 69328 139089 69436 139089 69436 139090 69328 139090 69575 139090 69436 139091 69575 139091 69574 139091 69574 139092 69575 139092 69557 139092 69574 139093 69557 139093 65565 139093 69031 139094 69599 139094 69344 139094 69344 139095 69599 139095 69598 139095 69018 139096 69348 139096 69576 139096 69576 139097 69348 139097 69596 139097 69576 139098 69596 139098 69577 139098 69577 139099 69596 139099 69578 139099 69577 139100 69578 139100 69579 139100 69579 139101 69578 139101 69580 139101 69580 139102 69578 139102 69581 139102 69580 139103 69581 139103 69582 139103 69583 139104 69597 139104 65623 139104 69583 139105 65623 139105 69585 139105 69595 139106 69348 139106 69584 139106 69584 139107 69348 139107 69347 139107 65623 139108 65621 139108 69585 139108 69585 139109 65621 139109 69584 139109 69585 139110 69584 139110 69586 139110 69586 139111 69584 139111 69347 139111 69444 139112 69599 139112 69587 139112 69587 139113 69599 139113 69588 139113 69587 139114 69588 139114 69589 139114 69589 139115 69588 139115 65557 139115 69589 139116 65557 139116 69445 139116 69445 139117 65557 139117 69590 139117 69445 139118 69590 139118 69591 139118 69591 139119 69590 139119 69592 139119 69591 139120 69592 139120 69593 139120 69593 139121 69592 139121 69581 139121 69593 139122 69581 139122 69594 139122 69594 139123 69581 139123 69578 139123 69594 139124 69578 139124 69595 139124 69595 139125 69578 139125 69596 139125 69595 139126 69596 139126 69348 139126 69583 139127 69338 139127 69597 139127 69597 139128 69338 139128 69343 139128 69597 139129 69343 139129 69444 139129 69444 139130 69343 139130 69598 139130 69444 139131 69598 139131 69599 139131 68965 139132 69608 139132 69002 139132 69002 139133 69608 139133 69613 139133 69352 139134 69600 139134 68960 139134 68960 139135 69600 139135 69601 139135 69601 139136 69602 139136 68960 139136 68960 139137 69602 139137 69603 139137 69607 139138 65645 139138 65612 139138 65612 139139 65645 139139 65613 139139 65613 139140 65645 139140 65614 139140 65614 139141 65645 139141 69604 139141 65614 139142 69604 139142 69605 139142 69452 139143 69601 139143 69606 139143 69606 139144 69601 139144 69600 139144 69606 139145 69600 139145 65612 139145 65612 139146 69600 139146 65643 139146 65612 139147 65643 139147 69607 139147 65616 139148 69608 139148 69447 139148 69447 139149 69608 139149 65550 139149 69447 139150 65550 139150 69609 139150 69609 139151 65550 139151 65548 139151 69609 139152 65548 139152 69610 139152 69610 139153 65548 139153 65545 139153 69610 139154 65545 139154 69450 139154 69450 139155 65545 139155 65547 139155 69450 139156 65547 139156 69451 139156 69451 139157 65547 139157 65543 139157 69451 139158 65543 139158 69452 139158 69452 139159 65543 139159 69602 139159 69452 139160 69602 139160 69601 139160 69604 139161 69611 139161 69605 139161 69605 139162 69611 139162 69612 139162 69605 139163 69612 139163 65616 139163 65616 139164 69612 139164 69613 139164 65616 139165 69613 139165 69608 139165 68929 139166 69629 139166 68930 139166 68930 139167 69629 139167 69634 139167 68882 139168 69361 139168 69614 139168 69614 139169 69361 139169 69615 139169 69614 139170 69615 139170 68911 139170 68911 139171 69615 139171 69616 139171 68911 139172 69616 139172 69617 139172 69617 139173 69616 139173 68908 139173 68908 139174 69616 139174 69618 139174 69618 139175 69616 139175 69619 139175 69618 139176 69619 139176 69620 139176 69620 139177 69619 139177 69621 139177 69621 139178 69619 139178 69623 139178 69621 139179 69623 139179 69624 139179 69622 139180 68899 139180 69623 139180 69623 139181 68899 139181 68902 139181 69623 139182 68902 139182 69624 139182 69622 139183 69623 139183 69625 139183 69625 139184 69623 139184 69638 139184 69625 139185 69638 139185 69626 139185 69626 139186 69638 139186 69628 139186 69626 139187 69628 139187 69627 139187 69627 139188 69628 139188 68895 139188 68895 139189 69628 139189 69629 139189 68895 139190 69629 139190 68929 139190 65608 139191 69630 139191 69357 139191 69360 139192 69359 139192 65605 139192 69357 139193 69630 139193 69359 139193 69359 139194 69630 139194 65606 139194 69359 139195 65606 139195 65605 139195 69357 139196 69631 139196 65608 139196 65608 139197 69631 139197 69632 139197 65608 139198 69632 139198 69633 139198 69633 139199 69632 139199 69634 139199 69633 139200 69634 139200 69635 139200 69635 139201 69634 139201 69629 139201 69635 139202 69629 139202 69636 139202 69636 139203 69629 139203 69628 139203 69636 139204 69628 139204 69637 139204 69637 139205 69628 139205 69638 139205 69637 139206 69638 139206 69639 139206 69639 139207 69638 139207 69623 139207 69639 139208 69623 139208 69455 139208 69455 139209 69623 139209 69619 139209 69455 139210 69619 139210 69640 139210 69640 139211 69619 139211 69616 139211 69640 139212 69616 139212 69641 139212 69641 139213 69616 139213 69615 139213 69641 139214 69615 139214 65604 139214 65604 139215 69615 139215 69361 139215 65604 139216 69361 139216 65605 139216 65605 139217 69361 139217 69642 139217 65605 139218 69642 139218 69360 139218 68894 139219 69654 139219 68892 139219 68892 139220 69654 139220 69662 139220 68937 139221 69657 139221 68913 139221 68913 139222 69657 139222 69643 139222 68913 139223 69643 139223 68914 139223 68914 139224 69643 139224 69645 139224 68914 139225 69645 139225 69644 139225 69644 139226 69645 139226 68916 139226 68916 139227 69645 139227 68917 139227 68917 139228 69645 139228 69647 139228 68917 139229 69647 139229 69646 139229 69646 139230 69647 139230 68918 139230 68918 139231 69647 139231 69648 139231 68918 139232 69648 139232 68919 139232 68923 139233 68921 139233 69648 139233 69648 139234 68921 139234 69649 139234 69648 139235 69649 139235 68919 139235 68923 139236 69648 139236 69650 139236 69650 139237 69648 139237 69651 139237 69650 139238 69651 139238 68925 139238 68925 139239 69651 139239 69652 139239 68925 139240 69652 139240 68926 139240 68926 139241 69652 139241 69653 139241 69653 139242 69652 139242 69654 139242 69653 139243 69654 139243 68894 139243 69368 139244 69287 139244 69658 139244 69658 139245 69287 139245 69655 139245 69655 139246 69287 139246 69656 139246 69656 139247 69287 139247 69659 139247 69656 139248 69659 139248 65601 139248 69648 139249 69460 139249 69459 139249 69460 139250 69648 139250 69461 139250 69461 139251 69648 139251 69647 139251 69461 139252 69647 139252 69464 139252 69647 139253 69645 139253 69464 139253 69464 139254 69645 139254 69643 139254 69464 139255 69643 139255 69465 139255 69465 139256 69643 139256 69657 139256 69465 139257 69657 139257 69658 139257 69658 139258 69657 139258 69369 139258 69658 139259 69369 139259 69368 139259 69659 139260 69660 139260 65601 139260 65601 139261 69660 139261 69366 139261 65601 139262 69366 139262 69661 139262 69661 139263 69366 139263 69662 139263 69661 139264 69662 139264 65603 139264 65603 139265 69662 139265 69654 139265 65603 139266 69654 139266 69663 139266 69663 139267 69654 139267 69652 139267 69663 139268 69652 139268 69459 139268 69459 139269 69652 139269 69651 139269 69459 139270 69651 139270 69648 139270 69000 139271 69674 139271 68962 139271 68962 139272 69674 139272 69382 139272 69011 139273 69386 139273 69664 139273 69664 139274 69386 139274 69681 139274 69664 139275 69681 139275 69665 139275 69665 139276 69681 139276 69667 139276 69665 139277 69667 139277 69666 139277 69666 139278 69667 139278 68984 139278 68984 139279 69667 139279 69668 139279 69668 139280 69667 139280 69678 139280 69668 139281 69678 139281 68986 139281 68986 139282 69678 139282 68989 139282 68989 139283 69678 139283 69669 139283 68989 139284 69669 139284 68990 139284 68994 139285 68993 139285 69669 139285 69669 139286 68993 139286 68992 139286 69669 139287 68992 139287 68990 139287 68994 139288 69669 139288 69670 139288 69670 139289 69669 139289 69671 139289 69670 139290 69671 139290 68996 139290 68996 139291 69671 139291 69676 139291 68996 139292 69676 139292 69672 139292 69672 139293 69676 139293 68998 139293 68998 139294 69676 139294 69674 139294 68998 139295 69674 139295 69000 139295 65596 139296 65595 139296 69378 139296 69378 139297 65595 139297 69383 139297 65595 139298 65593 139298 69383 139298 69383 139299 65593 139299 69470 139299 69383 139300 69470 139300 69683 139300 69378 139301 69376 139301 65596 139301 65596 139302 69376 139302 69381 139302 65596 139303 69381 139303 65598 139303 65598 139304 69381 139304 69382 139304 65598 139305 69382 139305 69673 139305 69673 139306 69382 139306 69674 139306 69673 139307 69674 139307 69675 139307 69674 139308 69676 139308 69675 139308 69675 139309 69676 139309 69671 139309 69675 139310 69671 139310 69677 139310 69677 139311 69671 139311 69669 139311 69677 139312 69669 139312 69467 139312 69467 139313 69669 139313 69678 139313 69467 139314 69678 139314 69679 139314 69679 139315 69678 139315 69667 139315 69679 139316 69667 139316 69680 139316 69680 139317 69667 139317 69681 139317 69680 139318 69681 139318 69469 139318 69469 139319 69681 139319 69386 139319 69469 139320 69386 139320 69470 139320 69470 139321 69386 139321 69682 139321 69470 139322 69682 139322 69683 139322 69684 139323 69685 139323 69029 139323 69029 139324 69685 139324 69701 139324 69055 139325 69711 139325 69686 139325 69686 139326 69711 139326 69710 139326 69686 139327 69710 139327 69687 139327 69687 139328 69710 139328 69689 139328 69687 139329 69689 139329 69688 139329 69688 139330 69689 139330 69046 139330 69046 139331 69689 139331 69047 139331 69047 139332 69689 139332 69708 139332 69047 139333 69708 139333 69049 139333 69049 139334 69708 139334 69050 139334 69050 139335 69708 139335 69692 139335 69050 139336 69692 139336 69690 139336 69693 139337 69052 139337 69692 139337 69692 139338 69052 139338 69691 139338 69692 139339 69691 139339 69690 139339 69693 139340 69692 139340 69694 139340 69694 139341 69692 139341 69695 139341 69694 139342 69695 139342 69696 139342 69696 139343 69695 139343 69703 139343 69696 139344 69703 139344 69053 139344 69053 139345 69703 139345 69054 139345 69054 139346 69703 139346 69685 139346 69054 139347 69685 139347 69684 139347 69697 139348 69698 139348 69699 139348 69697 139349 69699 139349 69399 139349 69697 139350 69391 139350 69698 139350 69698 139351 69391 139351 69700 139351 69698 139352 69700 139352 65588 139352 65588 139353 69700 139353 69701 139353 65588 139354 69701 139354 69702 139354 69702 139355 69701 139355 69685 139355 69702 139356 69685 139356 69704 139356 69704 139357 69685 139357 69703 139357 69704 139358 69703 139358 69705 139358 69699 139359 69477 139359 69399 139359 69399 139360 69477 139360 69706 139360 69399 139361 69706 139361 69395 139361 69703 139362 69695 139362 69705 139362 69705 139363 69695 139363 69692 139363 69705 139364 69692 139364 69707 139364 69707 139365 69692 139365 69708 139365 69707 139366 69708 139366 69709 139366 69709 139367 69708 139367 69689 139367 69709 139368 69689 139368 69473 139368 69473 139369 69689 139369 69710 139369 69473 139370 69710 139370 69475 139370 69475 139371 69710 139371 69711 139371 69475 139372 69711 139372 69706 139372 69706 139373 69711 139373 69397 139373 69706 139374 69397 139374 69395 139374 69087 139375 70634 139375 69407 139375 69407 139376 70634 139376 70632 139376 69712 139377 70636 139377 69713 139377 69713 139378 70636 139378 69714 139378 69713 139379 69714 139379 69715 139379 69715 139380 69714 139380 70635 139380 69715 139381 70635 139381 69716 139381 69716 139382 70635 139382 69105 139382 69105 139383 70635 139383 69717 139383 69105 139384 69717 139384 69718 139384 69718 139385 69717 139385 69108 139385 69108 139386 69717 139386 70628 139386 69108 139387 70628 139387 69109 139387 69719 139388 69113 139388 70627 139388 70627 139389 69113 139389 69720 139389 70627 139390 69720 139390 70628 139390 70628 139391 69720 139391 69111 139391 70628 139392 69111 139392 69109 139392 69719 139393 70627 139393 69114 139393 69114 139394 70627 139394 70626 139394 69114 139395 70626 139395 69721 139395 69721 139396 70626 139396 69722 139396 69722 139397 70626 139397 69723 139397 69722 139398 69723 139398 69117 139398 69117 139399 69723 139399 70634 139399 69117 139400 70634 139400 69087 139400 70816 139401 70813 139401 69724 139401 69724 139402 69725 139402 70816 139402 70816 139403 69725 139403 69767 139403 70816 139404 69767 139404 69759 139404 69759 139405 69735 139405 70816 139405 70816 139406 69735 139406 69726 139406 70816 139407 69726 139407 70812 139407 70813 139408 69727 139408 69724 139408 69724 139409 69727 139409 69202 139409 69724 139410 69202 139410 69725 139410 69725 139411 69202 139411 69203 139411 69725 139412 69203 139412 69767 139412 69767 139413 69203 139413 69728 139413 69767 139414 69728 139414 69729 139414 69729 139415 69728 139415 69730 139415 69729 139416 69730 139416 69770 139416 69770 139417 69730 139417 69731 139417 69770 139418 69731 139418 69206 139418 69759 139419 69758 139419 69254 139419 69254 139420 69758 139420 69732 139420 69254 139421 69732 139421 69255 139421 69255 139422 69732 139422 69733 139422 69255 139423 69733 139423 69256 139423 69254 139424 69734 139424 69759 139424 69759 139425 69734 139425 69257 139425 69759 139426 69257 139426 69735 139426 69735 139427 69257 139427 69736 139427 69735 139428 69736 139428 69726 139428 69726 139429 69736 139429 70839 139429 69726 139430 70839 139430 70812 139430 67819 139431 69765 139431 67818 139431 67818 139432 69765 139432 69757 139432 67818 139433 69757 139433 69737 139433 69737 139434 69757 139434 69739 139434 69737 139435 69739 139435 69738 139435 69738 139436 69739 139436 69740 139436 69738 139437 69740 139437 67826 139437 67826 139438 69740 139438 69768 139438 67826 139439 69768 139439 69741 139439 69741 139440 69768 139440 69769 139440 69741 139441 69769 139441 69742 139441 69742 139442 69769 139442 65537 139442 69743 139443 69771 139443 69744 139443 69744 139444 69771 139444 69745 139444 69256 139445 69733 139445 69228 139445 69228 139446 69733 139446 69766 139446 69240 139447 69751 139447 69753 139447 69228 139448 69766 139448 69227 139448 69227 139449 69766 139449 69746 139449 69227 139450 69746 139450 69229 139450 69229 139451 69746 139451 69747 139451 69233 139452 69232 139452 69748 139452 69748 139453 69232 139453 69749 139453 69748 139454 69749 139454 69746 139454 69746 139455 69749 139455 69750 139455 69746 139456 69750 139456 69747 139456 69751 139457 69238 139457 69753 139457 69753 139458 69238 139458 69752 139458 69753 139459 69752 139459 69748 139459 69748 139460 69752 139460 69235 139460 69748 139461 69235 139461 69233 139461 69760 139462 69756 139462 69762 139462 69762 139463 69756 139463 69243 139463 69762 139464 69243 139464 69753 139464 69753 139465 69243 139465 69754 139465 69753 139466 69754 139466 69240 139466 69755 139467 65536 139467 69760 139467 69760 139468 65536 139468 69246 139468 69246 139469 69247 139469 69760 139469 69760 139470 69247 139470 69245 139470 69760 139471 69245 139471 69756 139471 69768 139472 69740 139472 69767 139472 69757 139473 69765 139473 69733 139473 69733 139474 69732 139474 69757 139474 69757 139475 69732 139475 69758 139475 69757 139476 69758 139476 69759 139476 69767 139477 69740 139477 69759 139477 69759 139478 69740 139478 69739 139478 69759 139479 69739 139479 69757 139479 69769 139480 69771 139480 65537 139480 65537 139481 69771 139481 69755 139481 65537 139482 69755 139482 65539 139482 65539 139483 69755 139483 69760 139483 65539 139484 69760 139484 69761 139484 69761 139485 69760 139485 69762 139485 69761 139486 69762 139486 65540 139486 65540 139487 69762 139487 69753 139487 65540 139488 69753 139488 69763 139488 69763 139489 69753 139489 69748 139489 69763 139490 69748 139490 69764 139490 69764 139491 69748 139491 69746 139491 69764 139492 69746 139492 69765 139492 69765 139493 69746 139493 69766 139493 69765 139494 69766 139494 69733 139494 69767 139495 69729 139495 69768 139495 69768 139496 69729 139496 69770 139496 69768 139497 69770 139497 69769 139497 69769 139498 69770 139498 69745 139498 69769 139499 69745 139499 69771 139499 70604 139500 69772 139500 70605 139500 70605 139501 69772 139501 70071 139501 70605 139502 70071 139502 70606 139502 70606 139503 70071 139503 70076 139503 70606 139504 70076 139504 70607 139504 70607 139505 70076 139505 69773 139505 70607 139506 69773 139506 70609 139506 70609 139507 69773 139507 70099 139507 70609 139508 70099 139508 69774 139508 69774 139509 70099 139509 70084 139509 69774 139510 70084 139510 70611 139510 70611 139511 70084 139511 69775 139511 70611 139512 69775 139512 69776 139512 69776 139513 69775 139513 69777 139513 69776 139514 69777 139514 70613 139514 70613 139515 69777 139515 70104 139515 70613 139516 70104 139516 69778 139516 69778 139517 70104 139517 70103 139517 69778 139518 70103 139518 69779 139518 69779 139519 70103 139519 70097 139519 69779 139520 70097 139520 69781 139520 69781 139521 70097 139521 69780 139521 69781 139522 69780 139522 70615 139522 70615 139523 69780 139523 69783 139523 70615 139524 69783 139524 69782 139524 69782 139525 69783 139525 69784 139525 69782 139526 69784 139526 69785 139526 69785 139527 69784 139527 70109 139527 69785 139528 70109 139528 70616 139528 70616 139529 70109 139529 69786 139529 70616 139530 69786 139530 70618 139530 70618 139531 69786 139531 70083 139531 70618 139532 70083 139532 70620 139532 70620 139533 70083 139533 70082 139533 70601 139534 69787 139534 69788 139534 69788 139535 69787 139535 69789 139535 69788 139536 69789 139536 70600 139536 70600 139537 69789 139537 69790 139537 70600 139538 69790 139538 69791 139538 69791 139539 69790 139539 69792 139539 69791 139540 69792 139540 70599 139540 70599 139541 69792 139541 69793 139541 70599 139542 69793 139542 70598 139542 70598 139543 69793 139543 69794 139543 70598 139544 69794 139544 70596 139544 70596 139545 69794 139545 70065 139545 70596 139546 70065 139546 70594 139546 70594 139547 70065 139547 70066 139547 70594 139548 70066 139548 69795 139548 69795 139549 70066 139549 70062 139549 69795 139550 70062 139550 70592 139550 70592 139551 70062 139551 70063 139551 70592 139552 70063 139552 69796 139552 69796 139553 70063 139553 69797 139553 69796 139554 69797 139554 70590 139554 70590 139555 69797 139555 69799 139555 70590 139556 69799 139556 69798 139556 69798 139557 69799 139557 69800 139557 69798 139558 69800 139558 69801 139558 69801 139559 69800 139559 70053 139559 69801 139560 70053 139560 69802 139560 69802 139561 70053 139561 69804 139561 69802 139562 69804 139562 69803 139562 69803 139563 69804 139563 69805 139563 69803 139564 69805 139564 70587 139564 70587 139565 69805 139565 69806 139565 70587 139566 69806 139566 69807 139566 69807 139567 69806 139567 65505 139567 65503 139568 69808 139568 69917 139568 65395 139569 65400 139569 69884 139569 69883 139570 69809 139570 69811 139570 69810 139571 65284 139571 70154 139571 69809 139572 69810 139572 69811 139572 69811 139573 69810 139573 70154 139573 69811 139574 70154 139574 69812 139574 69812 139575 70154 139575 70153 139575 69812 139576 70153 139576 69813 139576 69813 139577 70153 139577 69814 139577 69813 139578 69814 139578 69880 139578 69880 139579 69814 139579 69815 139579 69880 139580 69815 139580 69878 139580 69878 139581 69815 139581 69816 139581 69878 139582 69816 139582 69817 139582 69817 139583 69816 139583 70151 139583 69817 139584 70151 139584 69818 139584 69818 139585 70151 139585 70149 139585 69818 139586 70149 139586 69874 139586 69874 139587 70149 139587 70148 139587 69874 139588 70148 139588 69819 139588 69819 139589 70148 139589 70147 139589 69819 139590 70147 139590 69820 139590 69820 139591 70147 139591 70146 139591 69820 139592 70146 139592 69871 139592 69871 139593 70146 139593 70143 139593 69871 139594 70143 139594 69870 139594 69870 139595 70143 139595 70142 139595 69870 139596 70142 139596 69869 139596 69869 139597 70142 139597 69821 139597 69869 139598 69821 139598 69822 139598 69822 139599 69821 139599 69823 139599 69822 139600 69823 139600 69867 139600 69867 139601 69823 139601 70137 139601 69867 139602 70137 139602 69824 139602 69824 139603 70137 139603 69825 139603 69824 139604 69825 139604 69826 139604 69826 139605 69825 139605 70136 139605 69826 139606 70136 139606 69865 139606 69865 139607 70136 139607 70134 139607 69865 139608 70134 139608 69864 139608 69864 139609 70134 139609 70133 139609 69864 139610 70133 139610 69862 139610 69862 139611 70133 139611 69827 139611 69862 139612 69827 139612 69861 139612 69861 139613 69827 139613 70131 139613 69861 139614 70131 139614 69828 139614 69828 139615 70131 139615 69829 139615 69828 139616 69829 139616 69858 139616 69858 139617 69829 139617 69830 139617 69858 139618 69830 139618 69857 139618 69857 139619 69830 139619 70127 139619 69857 139620 70127 139620 69854 139620 69854 139621 70127 139621 70126 139621 69854 139622 70126 139622 69831 139622 69831 139623 70126 139623 69832 139623 69831 139624 69832 139624 69853 139624 69853 139625 69832 139625 70124 139625 69853 139626 70124 139626 69852 139626 69852 139627 70124 139627 69833 139627 69852 139628 69833 139628 69849 139628 69849 139629 69833 139629 70121 139629 69849 139630 70121 139630 69847 139630 69847 139631 70121 139631 69834 139631 69847 139632 69834 139632 69836 139632 69836 139633 69834 139633 69835 139633 69836 139634 69835 139634 69845 139634 69845 139635 69835 139635 70117 139635 69845 139636 70117 139636 69837 139636 69837 139637 70117 139637 70116 139637 69837 139638 70116 139638 69838 139638 69838 139639 70116 139639 69839 139639 69838 139640 69839 139640 69843 139640 69843 139641 69839 139641 69840 139641 69843 139642 69840 139642 69842 139642 69842 139643 69840 139643 69841 139643 69842 139644 65503 139644 69843 139644 69843 139645 65503 139645 69917 139645 69843 139646 69917 139646 69838 139646 69838 139647 69917 139647 69844 139647 69838 139648 69844 139648 69837 139648 69837 139649 69844 139649 69915 139649 69837 139650 69915 139650 69845 139650 69845 139651 69915 139651 69846 139651 69845 139652 69846 139652 69836 139652 69836 139653 69846 139653 69848 139653 69836 139654 69848 139654 69847 139654 69847 139655 69848 139655 69850 139655 69847 139656 69850 139656 69849 139656 69849 139657 69850 139657 69851 139657 69849 139658 69851 139658 69852 139658 69852 139659 69851 139659 69909 139659 69852 139660 69909 139660 69853 139660 69853 139661 69909 139661 69908 139661 69853 139662 69908 139662 69831 139662 69831 139663 69908 139663 69855 139663 69831 139664 69855 139664 69854 139664 69854 139665 69855 139665 69856 139665 69854 139666 69856 139666 69857 139666 69857 139667 69856 139667 69859 139667 69857 139668 69859 139668 69858 139668 69858 139669 69859 139669 69905 139669 69858 139670 69905 139670 69828 139670 69828 139671 69905 139671 69860 139671 69828 139672 69860 139672 69861 139672 69861 139673 69860 139673 69901 139673 69861 139674 69901 139674 69862 139674 69862 139675 69901 139675 69863 139675 69862 139676 69863 139676 69864 139676 69864 139677 69863 139677 69900 139677 69864 139678 69900 139678 69865 139678 69865 139679 69900 139679 69866 139679 69865 139680 69866 139680 69826 139680 69826 139681 69866 139681 69897 139681 69826 139682 69897 139682 69824 139682 69824 139683 69897 139683 69896 139683 69824 139684 69896 139684 69867 139684 69867 139685 69896 139685 69893 139685 69867 139686 69893 139686 69822 139686 69822 139687 69893 139687 69868 139687 69822 139688 69868 139688 69869 139688 69869 139689 69868 139689 69892 139689 69869 139690 69892 139690 69870 139690 69870 139691 69892 139691 69891 139691 69870 139692 69891 139692 69871 139692 69871 139693 69891 139693 69872 139693 69871 139694 69872 139694 69820 139694 69820 139695 69872 139695 69890 139695 69820 139696 69890 139696 69819 139696 69819 139697 69890 139697 69873 139697 69819 139698 69873 139698 69874 139698 69874 139699 69873 139699 69875 139699 69874 139700 69875 139700 69818 139700 69818 139701 69875 139701 69876 139701 69818 139702 69876 139702 69817 139702 69817 139703 69876 139703 69877 139703 69817 139704 69877 139704 69878 139704 69878 139705 69877 139705 69879 139705 69878 139706 69879 139706 69880 139706 69880 139707 69879 139707 69881 139707 69880 139708 69881 139708 69813 139708 69813 139709 69881 139709 69882 139709 69813 139710 69882 139710 69812 139710 69812 139711 69882 139711 69886 139711 69812 139712 69886 139712 69811 139712 69811 139713 69886 139713 69884 139713 69811 139714 69884 139714 69883 139714 69883 139715 69884 139715 65400 139715 70075 139716 65395 139716 70072 139716 70072 139717 65395 139717 69884 139717 70072 139718 69884 139718 70073 139718 70073 139719 69884 139719 69886 139719 70073 139720 69886 139720 69885 139720 69885 139721 69886 139721 69882 139721 69885 139722 69882 139722 69887 139722 69887 139723 69882 139723 69881 139723 69887 139724 69881 139724 70077 139724 70077 139725 69881 139725 69879 139725 70077 139726 69879 139726 70078 139726 70078 139727 69879 139727 69877 139727 70078 139728 69877 139728 69888 139728 69888 139729 69877 139729 69876 139729 69888 139730 69876 139730 69889 139730 69889 139731 69876 139731 69875 139731 69889 139732 69875 139732 70098 139732 70098 139733 69875 139733 69873 139733 70098 139734 69873 139734 70100 139734 70100 139735 69873 139735 69890 139735 70100 139736 69890 139736 70085 139736 70085 139737 69890 139737 69872 139737 70085 139738 69872 139738 70106 139738 70106 139739 69872 139739 69891 139739 70106 139740 69891 139740 70107 139740 70107 139741 69891 139741 69892 139741 70107 139742 69892 139742 70108 139742 70108 139743 69892 139743 69868 139743 70108 139744 69868 139744 70105 139744 70105 139745 69868 139745 69893 139745 70105 139746 69893 139746 69894 139746 69894 139747 69893 139747 69896 139747 69894 139748 69896 139748 69895 139748 69895 139749 69896 139749 69897 139749 69895 139750 69897 139750 69898 139750 69898 139751 69897 139751 69866 139751 69898 139752 69866 139752 69899 139752 69899 139753 69866 139753 69900 139753 69899 139754 69900 139754 70102 139754 70102 139755 69900 139755 69863 139755 70102 139756 69863 139756 69902 139756 69902 139757 69863 139757 69901 139757 69902 139758 69901 139758 69903 139758 69903 139759 69901 139759 69860 139759 69903 139760 69860 139760 69904 139760 69904 139761 69860 139761 69905 139761 69904 139762 69905 139762 70111 139762 70111 139763 69905 139763 69859 139763 70111 139764 69859 139764 69906 139764 69906 139765 69859 139765 69856 139765 69906 139766 69856 139766 69907 139766 69907 139767 69856 139767 69855 139767 69907 139768 69855 139768 70112 139768 70112 139769 69855 139769 69908 139769 70112 139770 69908 139770 70113 139770 70113 139771 69908 139771 69909 139771 70113 139772 69909 139772 69910 139772 69910 139773 69909 139773 69851 139773 69910 139774 69851 139774 70110 139774 70110 139775 69851 139775 69850 139775 70110 139776 69850 139776 69911 139776 69911 139777 69850 139777 69848 139777 69911 139778 69848 139778 69912 139778 69912 139779 69848 139779 69846 139779 69912 139780 69846 139780 69913 139780 69913 139781 69846 139781 69915 139781 69913 139782 69915 139782 69914 139782 69914 139783 69915 139783 69844 139783 69914 139784 69844 139784 69916 139784 69916 139785 69844 139785 69917 139785 69916 139786 69917 139786 69918 139786 69918 139787 69917 139787 69808 139787 65389 139788 65387 139788 70024 139788 65288 139789 65290 139789 69919 139789 69987 139790 69922 139790 69923 139790 65328 139791 69920 139791 69921 139791 69922 139792 65328 139792 69923 139792 69923 139793 65328 139793 69921 139793 69923 139794 69921 139794 69924 139794 69924 139795 69921 139795 69925 139795 69924 139796 69925 139796 69926 139796 69926 139797 69925 139797 70114 139797 69926 139798 70114 139798 69927 139798 69927 139799 70114 139799 70115 139799 69927 139800 70115 139800 69984 139800 69984 139801 70115 139801 70118 139801 69984 139802 70118 139802 69928 139802 69928 139803 70118 139803 70119 139803 69928 139804 70119 139804 69929 139804 69929 139805 70119 139805 70120 139805 69929 139806 70120 139806 69982 139806 69982 139807 70120 139807 70122 139807 69982 139808 70122 139808 69980 139808 69980 139809 70122 139809 70123 139809 69980 139810 70123 139810 69930 139810 69930 139811 70123 139811 70125 139811 69930 139812 70125 139812 69931 139812 69931 139813 70125 139813 69932 139813 69931 139814 69932 139814 69934 139814 69934 139815 69932 139815 69933 139815 69934 139816 69933 139816 69977 139816 69977 139817 69933 139817 69935 139817 69977 139818 69935 139818 69976 139818 69976 139819 69935 139819 70128 139819 69976 139820 70128 139820 69936 139820 69936 139821 70128 139821 70129 139821 69936 139822 70129 139822 69937 139822 69937 139823 70129 139823 70130 139823 69937 139824 70130 139824 69938 139824 69938 139825 70130 139825 70132 139825 69938 139826 70132 139826 69971 139826 69971 139827 70132 139827 69939 139827 69971 139828 69939 139828 69970 139828 69970 139829 69939 139829 69940 139829 69970 139830 69940 139830 69941 139830 69941 139831 69940 139831 70135 139831 69941 139832 70135 139832 69942 139832 69942 139833 70135 139833 70138 139833 69942 139834 70138 139834 69943 139834 69943 139835 70138 139835 70139 139835 69943 139836 70139 139836 69944 139836 69944 139837 70139 139837 70140 139837 69944 139838 70140 139838 69945 139838 69945 139839 70140 139839 70141 139839 69945 139840 70141 139840 69946 139840 69946 139841 70141 139841 70144 139841 69946 139842 70144 139842 69966 139842 69966 139843 70144 139843 70145 139843 69966 139844 70145 139844 69964 139844 69964 139845 70145 139845 69947 139845 69964 139846 69947 139846 69948 139846 69948 139847 69947 139847 69949 139847 69948 139848 69949 139848 69963 139848 69963 139849 69949 139849 69950 139849 69963 139850 69950 139850 69951 139850 69951 139851 69950 139851 70150 139851 69951 139852 70150 139852 69962 139852 69962 139853 70150 139853 70152 139853 69962 139854 70152 139854 69952 139854 69952 139855 70152 139855 69953 139855 69952 139856 69953 139856 69960 139856 69960 139857 69953 139857 69955 139857 69960 139858 69955 139858 69954 139858 69954 139859 69955 139859 69956 139859 69954 139860 69956 139860 69959 139860 69959 139861 69956 139861 69958 139861 69959 139862 69958 139862 69957 139862 69957 139863 69958 139863 65390 139863 69957 139864 65389 139864 69959 139864 69959 139865 65389 139865 70024 139865 69959 139866 70024 139866 69954 139866 69954 139867 70024 139867 70023 139867 69954 139868 70023 139868 69960 139868 69960 139869 70023 139869 70021 139869 69960 139870 70021 139870 69952 139870 69952 139871 70021 139871 69961 139871 69952 139872 69961 139872 69962 139872 69962 139873 69961 139873 70019 139873 69962 139874 70019 139874 69951 139874 69951 139875 70019 139875 70018 139875 69951 139876 70018 139876 69963 139876 69963 139877 70018 139877 70017 139877 69963 139878 70017 139878 69948 139878 69948 139879 70017 139879 70015 139879 69948 139880 70015 139880 69964 139880 69964 139881 70015 139881 69965 139881 69964 139882 69965 139882 69966 139882 69966 139883 69965 139883 70014 139883 69966 139884 70014 139884 69946 139884 69946 139885 70014 139885 70012 139885 69946 139886 70012 139886 69945 139886 69945 139887 70012 139887 69967 139887 69945 139888 69967 139888 69944 139888 69944 139889 69967 139889 70009 139889 69944 139890 70009 139890 69943 139890 69943 139891 70009 139891 69968 139891 69943 139892 69968 139892 69942 139892 69942 139893 69968 139893 70008 139893 69942 139894 70008 139894 69941 139894 69941 139895 70008 139895 69969 139895 69941 139896 69969 139896 69970 139896 69970 139897 69969 139897 70007 139897 69970 139898 70007 139898 69971 139898 69971 139899 70007 139899 69972 139899 69971 139900 69972 139900 69938 139900 69938 139901 69972 139901 69973 139901 69938 139902 69973 139902 69937 139902 69937 139903 69973 139903 69974 139903 69937 139904 69974 139904 69936 139904 69936 139905 69974 139905 69975 139905 69936 139906 69975 139906 69976 139906 69976 139907 69975 139907 69978 139907 69976 139908 69978 139908 69977 139908 69977 139909 69978 139909 69999 139909 69977 139910 69999 139910 69934 139910 69934 139911 69999 139911 69998 139911 69934 139912 69998 139912 69931 139912 69931 139913 69998 139913 69997 139913 69931 139914 69997 139914 69930 139914 69930 139915 69997 139915 69979 139915 69930 139916 69979 139916 69980 139916 69980 139917 69979 139917 69981 139917 69980 139918 69981 139918 69982 139918 69982 139919 69981 139919 69996 139919 69982 139920 69996 139920 69929 139920 69929 139921 69996 139921 69993 139921 69929 139922 69993 139922 69928 139922 69928 139923 69993 139923 69983 139923 69928 139924 69983 139924 69984 139924 69984 139925 69983 139925 69992 139925 69984 139926 69992 139926 69927 139926 69927 139927 69992 139927 69989 139927 69927 139928 69989 139928 69926 139928 69926 139929 69989 139929 69985 139929 69926 139930 69985 139930 69924 139930 69924 139931 69985 139931 69986 139931 69924 139932 69986 139932 69923 139932 69923 139933 69986 139933 69919 139933 69923 139934 69919 139934 69987 139934 69987 139935 69919 139935 65290 139935 65287 139936 65288 139936 69988 139936 69988 139937 65288 139937 69919 139937 69988 139938 69919 139938 70060 139938 70060 139939 69919 139939 69986 139939 70060 139940 69986 139940 70059 139940 70059 139941 69986 139941 69985 139941 70059 139942 69985 139942 69990 139942 69990 139943 69985 139943 69989 139943 69990 139944 69989 139944 69991 139944 69991 139945 69989 139945 69992 139945 69991 139946 69992 139946 70058 139946 70058 139947 69992 139947 69983 139947 70058 139948 69983 139948 70068 139948 70068 139949 69983 139949 69993 139949 70068 139950 69993 139950 69994 139950 69994 139951 69993 139951 69996 139951 69994 139952 69996 139952 69995 139952 69995 139953 69996 139953 69981 139953 69995 139954 69981 139954 70069 139954 70069 139955 69981 139955 69979 139955 70069 139956 69979 139956 70057 139956 70057 139957 69979 139957 69997 139957 70057 139958 69997 139958 70064 139958 70064 139959 69997 139959 69998 139959 70064 139960 69998 139960 70067 139960 70067 139961 69998 139961 69999 139961 70067 139962 69999 139962 70000 139962 70000 139963 69999 139963 69978 139963 70000 139964 69978 139964 70001 139964 70001 139965 69978 139965 69975 139965 70001 139966 69975 139966 70002 139966 70002 139967 69975 139967 69974 139967 70002 139968 69974 139968 70003 139968 70003 139969 69974 139969 69973 139969 70003 139970 69973 139970 70004 139970 70004 139971 69973 139971 69972 139971 70004 139972 69972 139972 70005 139972 70005 139973 69972 139973 70007 139973 70005 139974 70007 139974 70006 139974 70006 139975 70007 139975 69969 139975 70006 139976 69969 139976 70061 139976 70061 139977 69969 139977 70008 139977 70061 139978 70008 139978 70055 139978 70055 139979 70008 139979 69968 139979 70055 139980 69968 139980 70056 139980 70056 139981 69968 139981 70009 139981 70056 139982 70009 139982 70010 139982 70010 139983 70009 139983 69967 139983 70010 139984 69967 139984 70011 139984 70011 139985 69967 139985 70012 139985 70011 139986 70012 139986 70054 139986 70054 139987 70012 139987 70014 139987 70054 139988 70014 139988 70013 139988 70013 139989 70014 139989 69965 139989 70013 139990 69965 139990 70028 139990 70028 139991 69965 139991 70015 139991 70028 139992 70015 139992 70016 139992 70016 139993 70015 139993 70017 139993 70016 139994 70017 139994 70029 139994 70029 139995 70017 139995 70018 139995 70029 139996 70018 139996 70030 139996 70030 139997 70018 139997 70019 139997 70030 139998 70019 139998 70031 139998 70031 139999 70019 139999 69961 139999 70031 140000 69961 140000 70020 140000 70020 140001 69961 140001 70021 140001 70020 140002 70021 140002 70022 140002 70022 140003 70021 140003 70023 140003 70022 140004 70023 140004 70025 140004 70025 140005 70023 140005 70024 140005 70025 140006 70024 140006 70048 140006 70048 140007 70024 140007 65387 140007 69787 140008 70034 140008 70026 140008 69806 140009 69805 140009 70020 140009 70020 140010 69805 140010 70031 140010 69804 140011 70053 140011 70028 140011 70046 140012 70047 140012 65512 140012 65512 140013 70047 140013 70027 140013 65512 140014 70027 140014 70040 140014 70028 140015 70016 140015 69804 140015 69804 140016 70016 140016 70029 140016 69804 140017 70029 140017 69805 140017 69805 140018 70029 140018 70030 140018 69805 140019 70030 140019 70031 140019 65521 140020 65293 140020 70033 140020 70033 140021 65293 140021 70032 140021 70033 140022 70032 140022 70034 140022 70034 140023 70032 140023 70035 140023 70034 140024 70035 140024 70026 140024 70038 140025 65305 140025 65519 140025 65519 140026 65305 140026 70036 140026 65519 140027 70036 140027 65521 140027 65521 140028 70036 140028 65344 140028 65521 140029 65344 140029 65293 140029 70020 140030 70022 140030 69806 140030 69806 140031 70022 140031 70025 140031 69806 140032 70025 140032 65505 140032 65505 140033 70025 140033 70048 140033 65505 140034 70048 140034 65506 140034 70043 140035 70044 140035 65515 140035 65515 140036 70044 140036 70037 140036 65515 140037 70037 140037 65517 140037 65517 140038 70037 140038 65353 140038 65517 140039 65353 140039 70038 140039 70038 140040 65353 140040 65306 140040 70038 140041 65306 140041 65305 140041 70027 140042 70039 140042 70040 140042 70040 140043 70039 140043 70041 140043 70040 140044 70041 140044 70042 140044 70042 140045 70041 140045 65362 140045 70042 140046 65362 140046 70043 140046 70043 140047 65362 140047 65296 140047 70043 140048 65296 140048 70044 140048 70050 140049 65380 140049 70045 140049 70045 140050 65380 140050 65323 140050 70045 140051 65323 140051 70046 140051 70046 140052 65323 140052 65319 140052 70046 140053 65319 140053 70047 140053 70048 140054 70049 140054 65506 140054 65506 140055 70049 140055 65300 140055 65506 140056 65300 140056 65509 140056 65509 140057 65300 140057 70051 140057 65509 140058 70051 140058 70050 140058 70050 140059 70051 140059 70052 140059 70050 140060 70052 140060 65380 140060 69800 140061 70054 140061 70053 140061 70053 140062 70054 140062 70013 140062 70053 140063 70013 140063 70028 140063 69799 140064 70010 140064 69800 140064 69800 140065 70010 140065 70011 140065 69800 140066 70011 140066 70054 140066 69797 140067 70055 140067 69799 140067 69799 140068 70055 140068 70056 140068 69799 140069 70056 140069 70010 140069 70062 140070 70066 140070 70002 140070 70002 140071 70066 140071 70001 140071 70065 140072 69794 140072 70057 140072 69793 140073 69792 140073 70068 140073 69790 140074 69991 140074 69792 140074 69792 140075 69991 140075 70058 140075 69792 140076 70058 140076 70068 140076 69789 140077 70059 140077 69790 140077 69790 140078 70059 140078 69990 140078 69790 140079 69990 140079 69991 140079 70026 140080 65287 140080 69787 140080 69787 140081 65287 140081 69988 140081 69787 140082 69988 140082 69789 140082 69789 140083 69988 140083 70060 140083 69789 140084 70060 140084 70059 140084 70063 140085 70006 140085 69797 140085 69797 140086 70006 140086 70061 140086 69797 140087 70061 140087 70055 140087 70002 140088 70003 140088 70062 140088 70062 140089 70003 140089 70004 140089 70062 140090 70004 140090 70063 140090 70063 140091 70004 140091 70005 140091 70063 140092 70005 140092 70006 140092 70057 140093 70064 140093 70065 140093 70065 140094 70064 140094 70067 140094 70065 140095 70067 140095 70066 140095 70066 140096 70067 140096 70000 140096 70066 140097 70000 140097 70001 140097 70068 140098 69994 140098 69793 140098 69793 140099 69994 140099 69995 140099 69793 140100 69995 140100 69794 140100 69794 140101 69995 140101 70069 140101 69794 140102 70069 140102 70057 140102 65524 140103 70082 140103 69918 140103 70088 140104 65409 140104 70070 140104 70070 140105 65409 140105 65458 140105 70070 140106 65458 140106 65533 140106 70076 140107 70071 140107 69885 140107 69772 140108 70072 140108 70071 140108 70071 140109 70072 140109 70073 140109 70071 140110 70073 140110 69885 140110 70081 140111 70074 140111 69772 140111 69772 140112 70074 140112 70075 140112 69772 140113 70075 140113 70072 140113 70099 140114 69773 140114 69888 140114 69885 140115 69887 140115 70076 140115 70076 140116 69887 140116 70077 140116 70076 140117 70077 140117 69773 140117 69773 140118 70077 140118 70078 140118 69773 140119 70078 140119 69888 140119 65458 140120 70079 140120 65533 140120 65533 140121 70079 140121 70080 140121 65533 140122 70080 140122 65535 140122 65535 140123 70080 140123 65396 140123 65535 140124 65396 140124 70081 140124 70081 140125 65396 140125 65397 140125 70081 140126 65397 140126 70074 140126 69918 140127 70082 140127 69916 140127 69916 140128 70082 140128 70083 140128 69916 140129 70083 140129 69914 140129 69914 140130 70083 140130 69913 140130 69913 140131 70083 140131 69786 140131 69913 140132 69786 140132 69912 140132 69775 140133 70084 140133 70085 140133 65529 140134 70086 140134 65530 140134 65530 140135 70086 140135 65467 140135 65530 140136 65467 140136 70087 140136 70087 140137 65467 140137 65463 140137 70087 140138 65463 140138 70088 140138 70088 140139 65463 140139 65414 140139 70088 140140 65414 140140 65409 140140 70092 140141 65435 140141 70089 140141 70089 140142 65435 140142 65483 140142 70089 140143 65483 140143 70090 140143 70096 140144 65492 140144 70091 140144 70091 140145 65492 140145 65491 140145 70091 140146 65491 140146 70092 140146 70092 140147 65491 140147 70093 140147 70092 140148 70093 140148 65435 140148 69918 140149 65502 140149 65524 140149 65524 140150 65502 140150 70094 140150 65524 140151 70094 140151 70095 140151 70095 140152 70094 140152 65398 140152 70095 140153 65398 140153 70096 140153 70096 140154 65398 140154 65399 140154 70096 140155 65399 140155 65492 140155 70097 140156 69902 140156 69903 140156 69888 140157 69889 140157 70099 140157 70099 140158 69889 140158 70098 140158 70099 140159 70098 140159 70084 140159 70084 140160 70098 140160 70100 140160 70084 140161 70100 140161 70085 140161 65483 140162 65480 140162 70090 140162 70090 140163 65480 140163 65426 140163 70090 140164 65426 140164 70101 140164 70101 140165 65426 140165 65473 140165 70101 140166 65473 140166 65529 140166 65529 140167 65473 140167 65422 140167 65529 140168 65422 140168 70086 140168 70097 140169 69903 140169 69780 140169 70109 140170 69784 140170 70113 140170 69903 140171 69904 140171 69780 140171 69780 140172 69904 140172 70111 140172 69780 140173 70111 140173 69783 140173 69902 140174 70097 140174 70102 140174 70102 140175 70097 140175 70103 140175 70102 140176 70103 140176 69899 140176 69899 140177 70103 140177 69898 140177 69898 140178 70103 140178 70104 140178 69898 140179 70104 140179 69895 140179 69895 140180 70104 140180 69894 140180 69894 140181 70104 140181 69777 140181 69894 140182 69777 140182 70105 140182 70085 140183 70106 140183 69775 140183 69775 140184 70106 140184 70107 140184 69775 140185 70107 140185 69777 140185 69777 140186 70107 140186 70108 140186 69777 140187 70108 140187 70105 140187 70113 140188 69910 140188 70109 140188 70109 140189 69910 140189 70110 140189 70109 140190 70110 140190 69786 140190 69786 140191 70110 140191 69911 140191 69786 140192 69911 140192 69912 140192 70111 140193 69906 140193 69783 140193 69783 140194 69906 140194 69907 140194 69783 140195 69907 140195 69784 140195 69784 140196 69907 140196 70112 140196 69784 140197 70112 140197 70113 140197 69920 140198 69841 140198 69921 140198 69921 140199 69841 140199 69840 140199 69921 140200 69840 140200 69925 140200 69925 140201 69840 140201 69839 140201 69925 140202 69839 140202 70114 140202 70114 140203 69839 140203 70116 140203 70114 140204 70116 140204 70115 140204 70115 140205 70116 140205 70117 140205 70115 140206 70117 140206 70118 140206 70118 140207 70117 140207 69835 140207 70118 140208 69835 140208 70119 140208 70119 140209 69835 140209 69834 140209 70119 140210 69834 140210 70120 140210 70120 140211 69834 140211 70121 140211 70120 140212 70121 140212 70122 140212 70122 140213 70121 140213 69833 140213 70122 140214 69833 140214 70123 140214 70123 140215 69833 140215 70124 140215 70123 140216 70124 140216 70125 140216 70125 140217 70124 140217 69832 140217 70125 140218 69832 140218 69932 140218 69932 140219 69832 140219 70126 140219 69932 140220 70126 140220 69933 140220 69933 140221 70126 140221 70127 140221 69933 140222 70127 140222 69935 140222 69935 140223 70127 140223 69830 140223 69935 140224 69830 140224 70128 140224 70128 140225 69830 140225 69829 140225 70128 140226 69829 140226 70129 140226 70129 140227 69829 140227 70131 140227 70129 140228 70131 140228 70130 140228 70130 140229 70131 140229 69827 140229 70130 140230 69827 140230 70132 140230 70132 140231 69827 140231 70133 140231 70132 140232 70133 140232 69939 140232 69939 140233 70133 140233 70134 140233 69939 140234 70134 140234 69940 140234 69940 140235 70134 140235 70136 140235 69940 140236 70136 140236 70135 140236 70135 140237 70136 140237 69825 140237 70135 140238 69825 140238 70138 140238 70138 140239 69825 140239 70137 140239 70138 140240 70137 140240 70139 140240 70139 140241 70137 140241 69823 140241 70139 140242 69823 140242 70140 140242 70140 140243 69823 140243 69821 140243 70140 140244 69821 140244 70141 140244 70141 140245 69821 140245 70142 140245 70141 140246 70142 140246 70144 140246 70144 140247 70142 140247 70143 140247 70144 140248 70143 140248 70145 140248 70145 140249 70143 140249 70146 140249 70145 140250 70146 140250 69947 140250 69947 140251 70146 140251 70147 140251 69947 140252 70147 140252 69949 140252 69949 140253 70147 140253 70148 140253 69949 140254 70148 140254 69950 140254 69950 140255 70148 140255 70149 140255 69950 140256 70149 140256 70150 140256 70150 140257 70149 140257 70151 140257 70150 140258 70151 140258 70152 140258 70152 140259 70151 140259 69816 140259 70152 140260 69816 140260 69953 140260 69953 140261 69816 140261 69815 140261 69953 140262 69815 140262 69955 140262 69955 140263 69815 140263 69814 140263 69955 140264 69814 140264 69956 140264 69956 140265 69814 140265 70153 140265 69956 140266 70153 140266 69958 140266 69958 140267 70153 140267 70154 140267 69958 140268 70154 140268 65390 140268 65390 140269 70154 140269 65284 140269 65238 140270 70236 140270 70155 140270 70155 140271 70236 140271 70237 140271 70155 140272 70237 140272 70156 140272 70156 140273 70237 140273 70238 140273 70156 140274 70238 140274 65041 140274 65041 140275 70238 140275 70157 140275 70157 140276 70238 140276 70159 140276 70157 140277 70159 140277 70158 140277 70158 140278 70159 140278 70239 140278 70158 140279 70239 140279 70160 140279 70160 140280 70239 140280 70161 140280 70161 140281 70239 140281 70163 140281 70161 140282 70163 140282 70162 140282 70162 140283 70163 140283 70240 140283 70162 140284 70240 140284 70164 140284 70164 140285 70240 140285 70241 140285 70164 140286 70241 140286 65039 140286 65039 140287 70241 140287 70166 140287 70166 140288 70241 140288 70165 140288 70166 140289 70165 140289 70167 140289 70167 140290 70165 140290 70244 140290 70167 140291 70244 140291 70168 140291 70168 140292 70244 140292 70169 140292 70169 140293 70244 140293 70246 140293 70169 140294 70246 140294 70170 140294 70170 140295 70246 140295 70172 140295 70170 140296 70172 140296 70171 140296 70171 140297 70172 140297 65037 140297 65037 140298 70172 140298 70248 140298 65037 140299 70248 140299 70173 140299 70173 140300 70248 140300 70174 140300 70173 140301 70174 140301 70175 140301 70175 140302 70174 140302 70176 140302 70176 140303 70174 140303 70250 140303 70176 140304 70250 140304 70178 140304 70178 140305 70250 140305 70177 140305 70178 140306 70177 140306 70179 140306 70179 140307 70177 140307 70180 140307 70180 140308 70177 140308 70251 140308 70180 140309 70251 140309 70181 140309 70181 140310 70251 140310 70182 140310 70181 140311 70182 140311 65034 140311 65034 140312 70182 140312 70183 140312 70183 140313 70182 140313 70253 140313 70183 140314 70253 140314 70184 140314 70184 140315 70253 140315 70185 140315 70184 140316 70185 140316 70186 140316 70186 140317 70185 140317 70256 140317 70186 140318 70256 140318 65032 140318 65032 140319 70256 140319 70187 140319 65032 140320 70187 140320 65033 140320 65033 140321 70187 140321 65030 140321 65030 140322 70187 140322 70257 140322 65030 140323 70257 140323 65026 140323 65026 140324 70257 140324 70258 140324 65026 140325 70258 140325 70188 140325 70188 140326 70258 140326 65027 140326 65027 140327 70258 140327 70261 140327 65027 140328 70261 140328 65028 140328 65028 140329 70261 140329 70262 140329 65028 140330 70262 140330 70189 140330 70189 140331 70262 140331 70190 140331 70189 140332 70190 140332 65024 140332 65024 140333 70190 140333 65025 140333 65025 140334 70190 140334 70192 140334 65025 140335 70192 140335 70191 140335 70191 140336 70192 140336 70193 140336 70191 140337 70193 140337 70194 140337 70194 140338 70193 140338 65021 140338 65021 140339 70193 140339 70195 140339 65021 140340 70195 140340 65023 140340 65023 140341 70195 140341 70266 140341 65023 140342 70266 140342 70196 140342 70196 140343 70266 140343 70197 140343 70197 140344 70266 140344 70198 140344 70197 140345 70198 140345 70199 140345 70199 140346 70198 140346 70201 140346 70199 140347 70201 140347 70200 140347 70200 140348 70201 140348 70203 140348 70203 140349 70201 140349 70202 140349 70203 140350 70202 140350 65018 140350 65018 140351 70202 140351 70269 140351 65018 140352 70269 140352 70204 140352 70205 140353 65236 140353 70206 140353 70206 140354 65236 140354 64928 140354 70206 140355 64928 140355 70207 140355 70207 140356 64928 140356 70208 140356 70207 140357 70208 140357 70209 140357 70209 140358 70208 140358 64918 140358 70209 140359 64918 140359 70210 140359 70210 140360 64918 140360 64911 140360 70210 140361 64911 140361 70211 140361 70211 140362 64911 140362 64938 140362 70211 140363 64938 140363 70242 140363 70242 140364 64938 140364 70212 140364 70242 140365 70212 140365 70213 140365 70213 140366 70212 140366 64940 140366 70213 140367 64940 140367 70243 140367 70243 140368 64940 140368 70214 140368 70243 140369 70214 140369 70245 140369 70245 140370 70214 140370 70216 140370 70245 140371 70216 140371 70215 140371 70215 140372 70216 140372 70217 140372 70215 140373 70217 140373 70247 140373 70247 140374 70217 140374 64906 140374 70247 140375 64906 140375 70249 140375 70249 140376 64906 140376 70219 140376 70249 140377 70219 140377 70218 140377 70218 140378 70219 140378 64942 140378 70218 140379 64942 140379 70220 140379 70220 140380 64942 140380 70221 140380 70220 140381 70221 140381 70252 140381 70252 140382 70221 140382 64890 140382 70252 140383 64890 140383 70222 140383 70222 140384 64890 140384 64892 140384 70222 140385 64892 140385 70223 140385 70223 140386 64892 140386 64879 140386 70223 140387 64879 140387 70254 140387 70254 140388 64879 140388 64944 140388 70254 140389 64944 140389 70255 140389 70255 140390 64944 140390 64947 140390 70255 140391 64947 140391 70224 140391 70224 140392 64947 140392 64949 140392 70224 140393 64949 140393 70225 140393 70225 140394 64949 140394 64876 140394 70225 140395 64876 140395 70226 140395 70226 140396 64876 140396 70227 140396 70226 140397 70227 140397 70259 140397 70259 140398 70227 140398 64866 140398 70259 140399 64866 140399 70260 140399 70260 140400 64866 140400 64864 140400 70260 140401 64864 140401 70228 140401 70228 140402 64864 140402 64951 140402 70228 140403 64951 140403 70263 140403 70263 140404 64951 140404 64952 140404 70263 140405 64952 140405 70264 140405 70264 140406 64952 140406 64861 140406 70264 140407 64861 140407 70265 140407 70265 140408 64861 140408 64850 140408 70265 140409 64850 140409 70229 140409 70229 140410 64850 140410 64854 140410 70229 140411 64854 140411 70230 140411 70230 140412 64854 140412 70231 140412 70230 140413 70231 140413 70267 140413 70267 140414 70231 140414 70232 140414 70267 140415 70232 140415 70268 140415 70268 140416 70232 140416 64957 140416 70268 140417 64957 140417 70233 140417 70233 140418 64957 140418 70234 140418 70233 140419 70234 140419 70235 140419 70235 140420 70234 140420 64959 140420 70235 140421 64959 140421 70271 140421 70271 140422 64959 140422 64841 140422 70271 140423 64841 140423 70275 140423 70275 140424 64841 140424 64828 140424 70236 140425 70205 140425 70237 140425 70237 140426 70205 140426 70206 140426 70237 140427 70206 140427 70238 140427 70238 140428 70206 140428 70207 140428 70238 140429 70207 140429 70159 140429 70159 140430 70207 140430 70209 140430 70159 140431 70209 140431 70239 140431 70239 140432 70209 140432 70210 140432 70239 140433 70210 140433 70163 140433 70163 140434 70210 140434 70211 140434 70163 140435 70211 140435 70240 140435 70240 140436 70211 140436 70242 140436 70240 140437 70242 140437 70241 140437 70241 140438 70242 140438 70213 140438 70241 140439 70213 140439 70165 140439 70165 140440 70213 140440 70243 140440 70165 140441 70243 140441 70244 140441 70244 140442 70243 140442 70245 140442 70244 140443 70245 140443 70246 140443 70246 140444 70245 140444 70215 140444 70246 140445 70215 140445 70172 140445 70172 140446 70215 140446 70247 140446 70172 140447 70247 140447 70248 140447 70248 140448 70247 140448 70249 140448 70248 140449 70249 140449 70174 140449 70174 140450 70249 140450 70218 140450 70174 140451 70218 140451 70250 140451 70250 140452 70218 140452 70220 140452 70250 140453 70220 140453 70177 140453 70177 140454 70220 140454 70252 140454 70177 140455 70252 140455 70251 140455 70251 140456 70252 140456 70222 140456 70251 140457 70222 140457 70182 140457 70182 140458 70222 140458 70223 140458 70182 140459 70223 140459 70253 140459 70253 140460 70223 140460 70254 140460 70253 140461 70254 140461 70185 140461 70185 140462 70254 140462 70255 140462 70185 140463 70255 140463 70256 140463 70256 140464 70255 140464 70224 140464 70256 140465 70224 140465 70187 140465 70187 140466 70224 140466 70225 140466 70187 140467 70225 140467 70257 140467 70257 140468 70225 140468 70226 140468 70257 140469 70226 140469 70258 140469 70258 140470 70226 140470 70259 140470 70258 140471 70259 140471 70261 140471 70261 140472 70259 140472 70260 140472 70261 140473 70260 140473 70262 140473 70262 140474 70260 140474 70228 140474 70262 140475 70228 140475 70190 140475 70190 140476 70228 140476 70263 140476 70190 140477 70263 140477 70192 140477 70192 140478 70263 140478 70264 140478 70192 140479 70264 140479 70193 140479 70193 140480 70264 140480 70265 140480 70193 140481 70265 140481 70195 140481 70195 140482 70265 140482 70229 140482 70195 140483 70229 140483 70266 140483 70266 140484 70229 140484 70230 140484 70266 140485 70230 140485 70198 140485 70198 140486 70230 140486 70267 140486 70198 140487 70267 140487 70201 140487 70201 140488 70267 140488 70268 140488 70201 140489 70268 140489 70202 140489 70202 140490 70268 140490 70233 140490 70202 140491 70233 140491 70269 140491 70269 140492 70233 140492 70235 140492 70269 140493 70235 140493 70270 140493 70270 140494 70235 140494 70271 140494 70270 140495 70271 140495 70272 140495 70272 140496 70271 140496 70275 140496 70204 140497 70269 140497 70273 140497 70273 140498 70269 140498 70270 140498 70273 140499 70270 140499 65019 140499 65019 140500 70270 140500 70272 140500 65019 140501 70272 140501 70274 140501 64828 140502 64830 140502 70277 140502 64828 140503 70277 140503 70275 140503 70275 140504 70277 140504 70278 140504 70275 140505 70278 140505 70272 140505 70272 140506 70278 140506 70276 140506 70272 140507 70276 140507 70274 140507 64830 140508 64829 140508 65158 140508 64830 140509 65158 140509 70277 140509 70277 140510 65158 140510 65194 140510 70277 140511 65194 140511 70278 140511 70278 140512 65194 140512 65016 140512 70278 140513 65016 140513 70276 140513 65750 140514 70308 140514 65751 140514 65751 140515 70308 140515 65102 140515 65751 140516 65102 140516 65752 140516 65752 140517 65102 140517 70279 140517 65752 140518 70279 140518 65753 140518 65753 140519 70279 140519 70280 140519 65753 140520 70280 140520 65754 140520 65754 140521 70280 140521 70281 140521 65754 140522 70281 140522 65755 140522 65755 140523 70281 140523 65105 140523 65755 140524 65105 140524 70282 140524 70282 140525 65105 140525 70283 140525 70282 140526 70283 140526 70284 140526 70284 140527 70283 140527 70285 140527 70284 140528 70285 140528 70286 140528 70286 140529 70285 140529 65107 140529 70286 140530 65107 140530 70287 140530 70287 140531 65107 140531 70288 140531 70287 140532 70288 140532 70289 140532 70289 140533 70288 140533 65109 140533 70289 140534 65109 140534 68762 140534 68762 140535 65109 140535 70290 140535 68762 140536 70290 140536 70291 140536 70291 140537 70290 140537 70292 140537 70291 140538 70292 140538 68763 140538 68763 140539 70292 140539 70309 140539 68763 140540 70309 140540 68764 140540 68764 140541 70309 140541 70293 140541 68764 140542 70293 140542 68765 140542 68765 140543 70293 140543 70312 140543 68765 140544 70312 140544 70294 140544 70294 140545 70312 140545 70295 140545 70294 140546 70295 140546 68766 140546 68766 140547 70295 140547 70313 140547 68766 140548 70313 140548 70296 140548 70296 140549 70313 140549 70315 140549 70296 140550 70315 140550 70297 140550 70297 140551 70315 140551 70298 140551 70297 140552 70298 140552 68770 140552 68770 140553 70298 140553 70317 140553 68770 140554 70317 140554 68772 140554 68772 140555 70317 140555 70299 140555 68772 140556 70299 140556 70300 140556 70300 140557 70299 140557 70301 140557 70300 140558 70301 140558 68775 140558 68775 140559 70301 140559 70302 140559 68775 140560 70302 140560 70303 140560 70303 140561 70302 140561 70322 140561 70303 140562 70322 140562 68777 140562 68777 140563 70322 140563 70323 140563 68777 140564 70323 140564 70304 140564 70304 140565 70323 140565 70324 140565 70304 140566 70324 140566 70305 140566 70305 140567 70324 140567 65095 140567 70305 140568 65095 140568 65745 140568 65745 140569 65095 140569 65097 140569 65745 140570 65097 140570 70306 140570 70306 140571 65097 140571 70307 140571 70306 140572 70307 140572 65748 140572 65748 140573 70307 140573 65100 140573 65748 140574 65100 140574 65749 140574 65749 140575 65100 140575 65101 140575 65749 140576 65101 140576 65750 140576 65750 140577 65101 140577 70308 140577 70290 140578 65110 140578 70292 140578 70292 140579 65110 140579 70310 140579 70292 140580 70310 140580 70309 140580 70309 140581 70310 140581 68753 140581 70309 140582 68753 140582 70293 140582 70293 140583 68753 140583 70311 140583 70293 140584 70311 140584 70312 140584 70312 140585 70311 140585 68754 140585 70312 140586 68754 140586 70295 140586 70295 140587 68754 140587 68755 140587 70295 140588 68755 140588 70313 140588 70313 140589 68755 140589 70314 140589 70313 140590 70314 140590 70315 140590 70315 140591 70314 140591 68757 140591 70315 140592 68757 140592 70298 140592 70298 140593 68757 140593 70316 140593 70298 140594 70316 140594 70317 140594 70317 140595 70316 140595 70318 140595 70317 140596 70318 140596 70299 140596 70299 140597 70318 140597 70319 140597 70299 140598 70319 140598 70301 140598 70301 140599 70319 140599 70320 140599 70301 140600 70320 140600 70302 140600 70302 140601 70320 140601 70321 140601 70302 140602 70321 140602 70322 140602 70322 140603 70321 140603 68759 140603 70322 140604 68759 140604 70323 140604 70323 140605 68759 140605 68760 140605 70323 140606 68760 140606 70324 140606 70324 140607 68760 140607 68761 140607 70324 140608 68761 140608 65095 140608 65095 140609 68761 140609 65096 140609 70351 140610 65673 140610 70325 140610 70325 140611 65673 140611 65674 140611 70325 140612 65674 140612 70326 140612 70326 140613 65674 140613 65675 140613 70326 140614 65675 140614 70327 140614 70327 140615 65675 140615 70328 140615 70327 140616 70328 140616 70329 140616 70329 140617 70328 140617 70331 140617 70329 140618 70331 140618 70330 140618 70330 140619 70331 140619 65677 140619 70330 140620 65677 140620 70332 140620 70332 140621 65677 140621 70333 140621 70332 140622 70333 140622 70334 140622 70334 140623 70333 140623 65679 140623 70334 140624 65679 140624 70335 140624 70335 140625 65679 140625 68850 140625 70335 140626 68850 140626 65759 140626 65759 140627 68850 140627 68852 140627 65759 140628 68852 140628 70336 140628 70336 140629 68852 140629 70337 140629 70336 140630 70337 140630 65762 140630 65762 140631 70337 140631 70338 140631 65762 140632 70338 140632 65763 140632 65763 140633 70338 140633 68854 140633 65763 140634 68854 140634 65765 140634 65765 140635 68854 140635 70339 140635 65765 140636 70339 140636 65766 140636 65766 140637 70339 140637 68856 140637 65766 140638 68856 140638 70340 140638 70340 140639 68856 140639 68857 140639 70340 140640 68857 140640 65768 140640 65768 140641 68857 140641 68858 140641 65768 140642 68858 140642 65770 140642 65770 140643 68858 140643 68860 140643 65770 140644 68860 140644 65772 140644 65772 140645 68860 140645 68862 140645 65772 140646 68862 140646 65773 140646 65773 140647 68862 140647 68863 140647 65773 140648 68863 140648 70341 140648 70341 140649 68863 140649 68864 140649 70341 140650 68864 140650 70342 140650 70342 140651 68864 140651 70343 140651 70342 140652 70343 140652 70344 140652 70344 140653 70343 140653 68868 140653 70344 140654 68868 140654 70345 140654 70345 140655 68868 140655 68869 140655 70345 140656 68869 140656 70346 140656 70346 140657 68869 140657 68870 140657 70346 140658 68870 140658 68752 140658 68752 140659 68870 140659 65664 140659 68752 140660 65664 140660 70347 140660 70347 140661 65664 140661 65665 140661 70347 140662 65665 140662 70348 140662 70348 140663 65665 140663 65666 140663 70348 140664 65666 140664 70349 140664 70349 140665 65666 140665 65668 140665 70349 140666 65668 140666 70350 140666 70350 140667 65668 140667 65669 140667 70350 140668 65669 140668 68756 140668 68756 140669 65669 140669 65670 140669 68756 140670 65670 140670 68758 140670 68758 140671 65670 140671 70352 140671 68758 140672 70352 140672 70351 140672 70351 140673 70352 140673 65673 140673 70384 140674 65662 140674 68867 140674 70384 140675 68867 140675 70353 140675 70353 140676 68867 140676 70355 140676 70353 140677 70355 140677 70354 140677 70354 140678 70355 140678 68866 140678 70354 140679 68866 140679 70380 140679 70380 140680 68866 140680 68865 140680 70380 140681 68865 140681 70356 140681 70356 140682 68865 140682 68861 140682 70356 140683 68861 140683 70377 140683 70377 140684 68861 140684 70357 140684 70377 140685 70357 140685 70375 140685 70375 140686 70357 140686 68859 140686 70375 140687 68859 140687 70374 140687 70374 140688 68859 140688 70358 140688 70374 140689 70358 140689 70359 140689 70359 140690 70358 140690 70360 140690 70359 140691 70360 140691 70371 140691 70371 140692 70360 140692 70361 140692 70371 140693 70361 140693 70370 140693 70370 140694 70361 140694 68855 140694 70370 140695 68855 140695 70369 140695 70369 140696 68855 140696 70362 140696 70369 140697 70362 140697 70363 140697 70363 140698 70362 140698 68853 140698 70363 140699 68853 140699 70365 140699 70365 140700 68853 140700 70364 140700 70365 140701 70364 140701 70366 140701 70366 140702 70364 140702 68851 140702 70366 140703 68851 140703 70401 140703 70401 140704 68851 140704 65076 140704 70401 140705 65076 140705 65075 140705 70366 140706 70367 140706 70365 140706 70365 140707 70367 140707 68742 140707 70365 140708 68742 140708 70363 140708 70363 140709 68742 140709 70368 140709 70363 140710 70368 140710 70369 140710 70369 140711 70368 140711 68744 140711 70369 140712 68744 140712 70370 140712 70370 140713 68744 140713 68746 140713 70370 140714 68746 140714 70371 140714 70371 140715 68746 140715 70372 140715 70371 140716 70372 140716 70359 140716 70359 140717 70372 140717 70373 140717 70359 140718 70373 140718 70374 140718 70374 140719 70373 140719 70376 140719 70374 140720 70376 140720 70375 140720 70375 140721 70376 140721 70378 140721 70375 140722 70378 140722 70377 140722 70377 140723 70378 140723 68749 140723 70377 140724 68749 140724 70356 140724 70356 140725 68749 140725 70379 140725 70356 140726 70379 140726 70380 140726 70380 140727 70379 140727 70381 140727 70380 140728 70381 140728 70354 140728 70354 140729 70381 140729 70382 140729 70354 140730 70382 140730 70353 140730 70353 140731 70382 140731 70383 140731 70353 140732 70383 140732 70384 140732 70384 140733 70383 140733 68751 140733 70384 140734 68751 140734 65094 140734 65094 140735 68751 140735 70385 140735 65094 140736 70385 140736 65092 140736 70385 140737 70386 140737 65092 140737 65092 140738 70386 140738 65778 140738 65092 140739 65778 140739 65090 140739 65090 140740 65778 140740 70387 140740 65090 140741 70387 140741 70388 140741 70388 140742 70387 140742 65779 140742 70388 140743 65779 140743 70389 140743 70389 140744 65779 140744 70390 140744 70389 140745 70390 140745 65088 140745 65088 140746 70390 140746 70391 140746 65088 140747 70391 140747 70392 140747 70392 140748 70391 140748 65783 140748 70392 140749 65783 140749 65087 140749 65087 140750 65783 140750 65784 140750 65087 140751 65784 140751 65085 140751 65085 140752 65784 140752 65785 140752 65085 140753 65785 140753 70393 140753 70393 140754 65785 140754 70395 140754 70393 140755 70395 140755 70394 140755 70394 140756 70395 140756 70397 140756 70394 140757 70397 140757 70396 140757 70396 140758 70397 140758 65789 140758 70396 140759 65789 140759 65082 140759 65082 140760 65789 140760 65791 140760 65082 140761 65791 140761 65079 140761 65079 140762 65791 140762 65792 140762 65079 140763 65792 140763 65077 140763 65077 140764 65792 140764 70398 140764 65077 140765 70398 140765 65075 140765 65075 140766 70398 140766 70399 140766 65075 140767 70399 140767 70401 140767 70401 140768 70399 140768 70400 140768 70401 140769 70400 140769 70366 140769 70366 140770 70400 140770 68740 140770 70366 140771 68740 140771 70367 140771 70402 140772 65074 140772 70403 140772 70402 140773 70403 140773 70447 140773 70447 140774 70403 140774 70404 140774 70447 140775 70404 140775 70405 140775 70405 140776 70404 140776 70407 140776 70405 140777 70407 140777 70406 140777 70406 140778 70407 140778 68750 140778 70406 140779 68750 140779 70445 140779 70445 140780 68750 140780 70409 140780 70445 140781 70409 140781 70408 140781 70408 140782 70409 140782 68748 140782 70408 140783 68748 140783 70410 140783 70410 140784 68748 140784 70411 140784 70410 140785 70411 140785 70440 140785 70440 140786 70411 140786 68747 140786 70440 140787 68747 140787 70439 140787 70439 140788 68747 140788 70412 140788 70439 140789 70412 140789 70438 140789 70438 140790 70412 140790 68745 140790 70438 140791 68745 140791 70436 140791 70436 140792 68745 140792 70413 140792 70436 140793 70413 140793 70435 140793 70435 140794 70413 140794 68743 140794 70435 140795 68743 140795 70414 140795 70414 140796 68743 140796 70415 140796 70414 140797 70415 140797 70434 140797 70434 140798 70415 140798 70416 140798 70434 140799 70416 140799 70417 140799 70417 140800 70416 140800 68741 140800 70417 140801 68741 140801 70418 140801 70418 140802 68741 140802 70419 140802 70418 140803 70419 140803 70420 140803 70420 140804 70419 140804 68739 140804 70420 140805 68739 140805 70433 140805 70455 140806 70421 140806 70422 140806 70422 140807 70421 140807 70610 140807 70422 140808 70610 140808 70423 140808 70423 140809 70610 140809 70424 140809 70423 140810 70424 140810 65069 140810 65069 140811 70424 140811 70612 140811 65069 140812 70612 140812 65068 140812 65068 140813 70612 140813 70425 140813 65068 140814 70425 140814 65066 140814 65066 140815 70425 140815 70426 140815 65066 140816 70426 140816 65064 140816 65064 140817 70426 140817 70427 140817 65064 140818 70427 140818 70428 140818 70428 140819 70427 140819 70614 140819 70428 140820 70614 140820 65063 140820 65063 140821 70614 140821 70429 140821 65063 140822 70429 140822 70430 140822 70430 140823 70429 140823 70431 140823 70430 140824 70431 140824 65062 140824 65062 140825 70431 140825 70617 140825 65062 140826 70617 140826 65060 140826 65060 140827 70617 140827 70432 140827 65060 140828 70432 140828 70433 140828 70433 140829 70432 140829 70619 140829 70433 140830 70619 140830 70420 140830 70420 140831 70619 140831 64961 140831 70420 140832 64961 140832 70418 140832 70418 140833 64961 140833 64963 140833 70418 140834 64963 140834 70417 140834 70417 140835 64963 140835 64964 140835 70417 140836 64964 140836 70434 140836 70434 140837 64964 140837 64965 140837 70434 140838 64965 140838 70414 140838 70414 140839 64965 140839 64968 140839 70414 140840 64968 140840 70435 140840 70435 140841 64968 140841 64969 140841 70435 140842 64969 140842 70436 140842 70436 140843 64969 140843 70437 140843 70436 140844 70437 140844 70438 140844 70438 140845 70437 140845 64971 140845 70438 140846 64971 140846 70439 140846 70439 140847 64971 140847 64973 140847 70439 140848 64973 140848 70440 140848 70440 140849 64973 140849 70441 140849 70440 140850 70441 140850 70410 140850 70410 140851 70441 140851 70442 140851 70410 140852 70442 140852 70408 140852 70408 140853 70442 140853 70443 140853 70408 140854 70443 140854 70445 140854 70445 140855 70443 140855 70444 140855 70445 140856 70444 140856 70406 140856 70406 140857 70444 140857 64976 140857 70406 140858 64976 140858 70405 140858 70405 140859 64976 140859 70446 140859 70405 140860 70446 140860 70447 140860 70447 140861 70446 140861 64979 140861 70447 140862 64979 140862 70402 140862 70402 140863 64979 140863 70448 140863 70402 140864 70448 140864 70449 140864 70449 140865 70448 140865 70603 140865 70449 140866 70603 140866 70450 140866 70450 140867 70603 140867 70451 140867 70450 140868 70451 140868 70452 140868 70452 140869 70451 140869 70454 140869 70452 140870 70454 140870 70453 140870 70453 140871 70454 140871 70608 140871 70453 140872 70608 140872 70455 140872 70455 140873 70608 140873 70421 140873 70456 140874 65047 140874 65682 140874 65682 140875 65047 140875 65048 140875 65682 140876 65048 140876 70457 140876 70457 140877 65048 140877 70458 140877 70457 140878 70458 140878 65684 140878 65684 140879 70458 140879 70459 140879 65684 140880 70459 140880 65685 140880 65685 140881 70459 140881 65051 140881 65685 140882 65051 140882 65687 140882 65687 140883 65051 140883 70460 140883 65687 140884 70460 140884 65688 140884 65688 140885 70460 140885 70461 140885 65688 140886 70461 140886 70462 140886 70462 140887 70461 140887 70463 140887 70462 140888 70463 140888 65691 140888 65691 140889 70463 140889 65054 140889 65691 140890 65054 140890 65693 140890 65693 140891 65054 140891 65055 140891 65693 140892 65055 140892 65694 140892 65694 140893 65055 140893 65058 140893 65694 140894 65058 140894 65695 140894 65695 140895 65058 140895 70464 140895 65695 140896 70464 140896 68829 140896 68829 140897 70464 140897 70465 140897 68829 140898 70465 140898 68831 140898 68831 140899 70465 140899 70488 140899 68831 140900 70488 140900 68832 140900 68832 140901 70488 140901 70489 140901 68832 140902 70489 140902 68835 140902 68835 140903 70489 140903 70491 140903 68835 140904 70491 140904 68836 140904 68836 140905 70491 140905 70466 140905 68836 140906 70466 140906 68837 140906 70466 140907 70467 140907 68837 140907 68837 140908 70467 140908 70494 140908 68837 140909 70494 140909 68838 140909 68838 140910 70494 140910 70495 140910 68838 140911 70495 140911 70468 140911 70468 140912 70495 140912 70469 140912 70468 140913 70469 140913 68839 140913 68839 140914 70469 140914 70497 140914 68839 140915 70497 140915 68841 140915 68841 140916 70497 140916 70471 140916 68841 140917 70471 140917 70470 140917 70470 140918 70471 140918 70473 140918 70470 140919 70473 140919 70472 140919 70472 140920 70473 140920 70498 140920 70472 140921 70498 140921 68844 140921 68844 140922 70498 140922 70474 140922 68844 140923 70474 140923 70475 140923 70475 140924 70474 140924 70477 140924 70475 140925 70477 140925 70476 140925 70476 140926 70477 140926 70500 140926 70476 140927 70500 140927 70478 140927 70478 140928 70500 140928 70501 140928 70478 140929 70501 140929 68849 140929 68849 140930 70501 140930 70479 140930 68849 140931 70479 140931 70480 140931 70480 140932 70479 140932 70482 140932 70480 140933 70482 140933 70481 140933 70481 140934 70482 140934 70483 140934 70481 140935 70483 140935 70484 140935 70484 140936 70483 140936 70485 140936 70484 140937 70485 140937 65681 140937 65681 140938 70485 140938 65044 140938 65681 140939 65044 140939 70486 140939 70486 140940 65044 140940 65045 140940 70486 140941 65045 140941 70456 140941 70456 140942 65045 140942 70487 140942 70456 140943 70487 140943 65047 140943 70465 140944 68810 140944 70488 140944 70488 140945 68810 140945 68812 140945 70488 140946 68812 140946 70489 140946 70489 140947 68812 140947 70490 140947 70489 140948 70490 140948 70491 140948 70491 140949 70490 140949 70492 140949 70491 140950 70492 140950 70466 140950 70466 140951 70492 140951 70493 140951 70466 140952 70493 140952 70467 140952 70467 140953 70493 140953 68814 140953 70467 140954 68814 140954 70494 140954 70494 140955 68814 140955 68815 140955 70494 140956 68815 140956 70495 140956 70495 140957 68815 140957 68818 140957 70495 140958 68818 140958 70469 140958 70469 140959 68818 140959 70496 140959 70469 140960 70496 140960 70497 140960 70497 140961 70496 140961 68819 140961 70497 140962 68819 140962 70471 140962 70471 140963 68819 140963 68820 140963 70471 140964 68820 140964 70473 140964 70473 140965 68820 140965 68821 140965 70473 140966 68821 140966 70498 140966 70498 140967 68821 140967 68823 140967 70498 140968 68823 140968 70474 140968 70474 140969 68823 140969 70499 140969 70474 140970 70499 140970 70477 140970 70477 140971 70499 140971 68825 140971 70477 140972 68825 140972 70500 140972 70500 140973 68825 140973 70502 140973 70500 140974 70502 140974 70501 140974 70501 140975 70502 140975 70503 140975 70501 140976 70503 140976 70479 140976 70479 140977 70503 140977 68828 140977 70479 140978 68828 140978 70482 140978 70482 140979 68828 140979 70504 140979 70538 140980 65721 140980 68816 140980 68816 140981 65721 140981 65722 140981 68816 140982 65722 140982 68817 140982 68817 140983 65722 140983 70506 140983 68817 140984 70506 140984 70505 140984 70505 140985 70506 140985 65723 140985 70505 140986 65723 140986 70507 140986 70507 140987 65723 140987 70508 140987 70507 140988 70508 140988 70509 140988 70509 140989 70508 140989 70511 140989 70509 140990 70511 140990 70510 140990 70510 140991 70511 140991 70512 140991 70510 140992 70512 140992 70513 140992 70513 140993 70512 140993 70514 140993 70513 140994 70514 140994 68822 140994 68822 140995 70514 140995 70515 140995 68822 140996 70515 140996 68824 140996 68824 140997 70515 140997 65728 140997 68824 140998 65728 140998 70517 140998 70517 140999 65728 140999 70516 140999 70517 141000 70516 141000 70518 141000 70518 141001 70516 141001 65729 141001 70518 141002 65729 141002 68826 141002 68826 141003 65729 141003 70519 141003 68826 141004 70519 141004 68827 141004 68827 141005 70519 141005 70520 141005 68827 141006 70520 141006 65697 141006 65697 141007 70520 141007 65730 141007 65697 141008 65730 141008 70521 141008 70521 141009 65730 141009 70522 141009 70521 141010 70522 141010 65699 141010 65699 141011 70522 141011 70523 141011 65699 141012 70523 141012 65701 141012 65701 141013 70523 141013 68795 141013 65701 141014 68795 141014 70524 141014 70524 141015 68795 141015 70525 141015 70524 141016 70525 141016 65703 141016 65703 141017 70525 141017 70526 141017 65703 141018 70526 141018 65705 141018 65705 141019 70526 141019 68798 141019 65705 141020 68798 141020 65706 141020 65706 141021 68798 141021 68799 141021 65706 141022 68799 141022 70527 141022 70527 141023 68799 141023 68801 141023 70527 141024 68801 141024 65708 141024 65708 141025 68801 141025 68803 141025 65708 141026 68803 141026 70528 141026 70528 141027 68803 141027 68804 141027 70528 141028 68804 141028 65710 141028 65710 141029 68804 141029 70529 141029 65710 141030 70529 141030 70530 141030 70530 141031 70529 141031 68806 141031 70530 141032 68806 141032 70531 141032 70531 141033 68806 141033 70532 141033 70531 141034 70532 141034 65713 141034 65713 141035 70532 141035 70533 141035 65713 141036 70533 141036 65714 141036 65714 141037 70533 141037 68807 141037 65714 141038 68807 141038 65715 141038 65715 141039 68807 141039 70534 141039 65715 141040 70534 141040 65716 141040 65716 141041 70534 141041 68809 141041 65716 141042 68809 141042 68811 141042 68811 141043 68809 141043 65717 141043 68811 141044 65717 141044 70535 141044 70535 141045 65717 141045 65719 141045 70535 141046 65719 141046 70536 141046 70536 141047 65719 141047 70537 141047 70536 141048 70537 141048 68813 141048 68813 141049 70537 141049 70539 141049 68813 141050 70539 141050 70538 141050 70538 141051 70539 141051 65721 141051 70542 141052 65231 141052 68808 141052 68808 141053 65231 141053 70540 141053 68808 141054 70540 141054 65718 141054 65718 141055 70540 141055 70541 141055 65718 141056 70541 141056 65238 141056 70542 141057 68808 141057 65230 141057 65230 141058 68808 141058 70543 141058 65230 141059 70543 141059 70544 141059 65152 141060 65155 141060 70546 141060 70546 141061 65155 141061 65156 141061 70546 141062 65156 141062 70543 141062 70543 141063 65156 141063 70545 141063 70543 141064 70545 141064 70544 141064 65152 141065 70546 141065 65151 141065 65151 141066 70546 141066 70547 141066 65151 141067 70547 141067 65150 141067 65146 141068 70549 141068 70548 141068 70548 141069 70549 141069 65148 141069 70548 141070 65148 141070 70547 141070 70547 141071 65148 141071 65149 141071 70547 141072 65149 141072 65150 141072 65146 141073 70548 141073 70550 141073 70550 141074 70548 141074 70552 141074 70550 141075 70552 141075 65145 141075 68805 141076 65141 141076 70551 141076 68805 141077 70551 141077 70552 141077 70552 141078 70551 141078 65143 141078 70552 141079 65143 141079 65145 141079 70553 141080 70554 141080 70555 141080 70553 141081 70555 141081 68805 141081 68805 141082 70555 141082 65138 141082 68805 141083 65138 141083 65141 141083 65134 141084 65135 141084 68802 141084 68802 141085 65135 141085 70556 141085 68802 141086 70556 141086 70553 141086 70553 141087 70556 141087 65136 141087 70553 141088 65136 141088 70554 141088 65134 141089 68802 141089 65132 141089 65132 141090 68802 141090 68800 141090 65132 141091 68800 141091 65130 141091 70557 141092 65129 141092 70558 141092 70557 141093 70558 141093 68800 141093 68800 141094 70558 141094 70559 141094 68800 141095 70559 141095 65130 141095 70560 141096 65125 141096 70561 141096 70561 141097 65125 141097 65126 141097 70561 141098 65126 141098 70557 141098 70557 141099 65126 141099 65127 141099 70557 141100 65127 141100 65129 141100 70560 141101 70561 141101 65123 141101 65123 141102 70561 141102 68797 141102 65123 141103 68797 141103 65122 141103 70564 141104 70562 141104 68796 141104 68796 141105 70562 141105 65121 141105 68796 141106 65121 141106 68797 141106 68797 141107 65121 141107 70563 141107 68797 141108 70563 141108 65122 141108 70564 141109 68796 141109 70565 141109 70565 141110 68796 141110 70566 141110 70565 141111 70566 141111 65120 141111 68794 141112 65117 141112 65118 141112 68794 141113 65118 141113 70566 141113 70566 141114 65118 141114 65119 141114 70566 141115 65119 141115 65120 141115 65112 141116 65113 141116 70567 141116 70567 141117 65113 141117 65114 141117 70567 141118 65114 141118 68794 141118 68794 141119 65114 141119 65116 141119 68794 141120 65116 141120 65117 141120 65112 141121 70567 141121 65111 141121 65111 141122 70567 141122 70568 141122 65111 141123 70568 141123 65016 141123 65731 141124 65014 141124 70570 141124 70570 141125 65014 141125 70569 141125 70570 141126 70569 141126 68791 141126 68791 141127 70569 141127 70571 141127 68791 141128 70571 141128 70572 141128 70572 141129 70571 141129 70573 141129 70572 141130 70573 141130 68787 141130 68787 141131 70573 141131 70574 141131 68787 141132 70574 141132 68785 141132 68785 141133 70574 141133 70575 141133 68785 141134 70575 141134 70576 141134 70576 141135 70575 141135 70578 141135 70576 141136 70578 141136 70577 141136 70577 141137 70578 141137 68767 141137 70577 141138 68767 141138 68782 141138 68782 141139 68767 141139 68768 141139 68782 141140 68768 141140 68781 141140 68781 141141 68768 141141 68769 141141 68781 141142 68769 141142 70579 141142 70579 141143 68769 141143 68771 141143 70579 141144 68771 141144 70580 141144 70580 141145 68771 141145 68773 141145 70580 141146 68773 141146 70581 141146 70581 141147 68773 141147 68774 141147 70581 141148 68774 141148 70582 141148 70582 141149 68774 141149 70584 141149 70582 141150 70584 141150 70583 141150 70583 141151 70584 141151 68776 141151 70583 141152 68776 141152 70585 141152 70585 141153 68776 141153 68778 141153 70585 141154 68778 141154 64995 141154 64995 141155 68778 141155 68779 141155 69807 141156 70586 141156 70587 141156 70587 141157 70586 141157 68830 141157 70587 141158 68830 141158 69803 141158 69803 141159 68830 141159 68833 141159 69803 141160 68833 141160 69802 141160 69802 141161 68833 141161 70588 141161 69802 141162 70588 141162 69801 141162 69801 141163 70588 141163 68834 141163 69801 141164 68834 141164 69798 141164 69798 141165 68834 141165 70589 141165 69798 141166 70589 141166 70590 141166 70590 141167 70589 141167 70591 141167 70590 141168 70591 141168 69796 141168 69796 141169 70591 141169 70593 141169 69796 141170 70593 141170 70592 141170 70592 141171 70593 141171 68840 141171 70592 141172 68840 141172 69795 141172 69795 141173 68840 141173 70595 141173 69795 141174 70595 141174 70594 141174 70594 141175 70595 141175 70597 141175 70594 141176 70597 141176 70596 141176 70596 141177 70597 141177 68842 141177 70596 141178 68842 141178 70598 141178 70598 141179 68842 141179 68843 141179 70598 141180 68843 141180 70599 141180 70599 141181 68843 141181 68845 141181 70599 141182 68845 141182 69791 141182 69791 141183 68845 141183 68846 141183 69791 141184 68846 141184 70600 141184 70600 141185 68846 141185 68847 141185 70600 141186 68847 141186 69788 141186 69788 141187 68847 141187 68848 141187 69788 141188 68848 141188 70601 141188 70601 141189 68848 141189 70602 141189 70448 141190 70604 141190 70603 141190 70603 141191 70604 141191 70605 141191 70603 141192 70605 141192 70451 141192 70451 141193 70605 141193 70606 141193 70451 141194 70606 141194 70454 141194 70454 141195 70606 141195 70607 141195 70454 141196 70607 141196 70608 141196 70608 141197 70607 141197 70609 141197 70608 141198 70609 141198 70421 141198 70421 141199 70609 141199 69774 141199 70421 141200 69774 141200 70610 141200 70610 141201 69774 141201 70611 141201 70610 141202 70611 141202 70424 141202 70424 141203 70611 141203 69776 141203 70424 141204 69776 141204 70612 141204 70612 141205 69776 141205 70613 141205 70612 141206 70613 141206 70425 141206 70425 141207 70613 141207 69778 141207 70425 141208 69778 141208 70426 141208 70426 141209 69778 141209 69779 141209 70426 141210 69779 141210 70427 141210 70427 141211 69779 141211 69781 141211 70427 141212 69781 141212 70614 141212 70614 141213 69781 141213 70615 141213 70614 141214 70615 141214 70429 141214 70429 141215 70615 141215 69782 141215 70429 141216 69782 141216 70431 141216 70431 141217 69782 141217 69785 141217 70431 141218 69785 141218 70617 141218 70617 141219 69785 141219 70616 141219 70617 141220 70616 141220 70432 141220 70432 141221 70616 141221 70618 141221 70432 141222 70618 141222 70619 141222 70619 141223 70618 141223 70620 141223 70630 141224 65580 141224 69484 141224 70637 141225 70621 141225 69482 141225 70630 141226 69484 141226 70621 141226 70621 141227 69484 141227 70622 141227 70621 141228 70622 141228 69482 141228 70633 141229 70634 141229 70623 141229 70623 141230 70634 141230 69723 141230 70623 141231 69723 141231 70624 141231 70624 141232 69723 141232 70626 141232 70624 141233 70626 141233 70625 141233 70625 141234 70626 141234 70627 141234 70625 141235 70627 141235 65586 141235 65586 141236 70627 141236 70628 141236 65586 141237 70628 141237 70629 141237 70629 141238 70628 141238 69717 141238 70629 141239 69717 141239 69479 141239 69479 141240 69717 141240 70635 141240 69479 141241 70635 141241 69480 141241 70630 141242 70631 141242 65580 141242 65580 141243 70631 141243 69403 141243 65580 141244 69403 141244 70633 141244 70633 141245 69403 141245 70632 141245 70633 141246 70632 141246 70634 141246 70635 141247 69714 141247 69480 141247 69480 141248 69714 141248 70636 141248 69480 141249 70636 141249 69482 141249 69482 141250 70636 141250 69409 141250 69482 141251 69409 141251 70637 141251 68683 141252 68714 141252 70638 141252 68683 141253 70638 141253 70639 141253 70639 141254 70638 141254 70828 141254 70639 141255 70828 141255 68219 141255 68219 141256 70828 141256 70824 141256 68219 141257 70824 141257 70640 141257 70640 141258 70824 141258 70821 141258 70640 141259 70821 141259 68217 141259 68217 141260 70821 141260 70832 141260 68217 141261 70832 141261 68215 141261 68215 141262 70832 141262 70817 141262 68215 141263 70817 141263 70641 141263 70641 141264 70817 141264 70819 141264 70641 141265 70819 141265 68213 141265 68213 141266 70819 141266 70642 141266 68213 141267 70642 141267 68211 141267 68211 141268 70642 141268 70814 141268 68211 141269 70814 141269 68210 141269 68210 141270 70814 141270 70815 141270 68210 141271 70815 141271 70643 141271 70643 141272 70815 141272 70837 141272 70643 141273 70837 141273 70644 141273 70644 141274 70837 141274 70836 141274 70644 141275 70836 141275 70645 141275 70645 141276 70836 141276 70646 141276 70645 141277 70646 141277 68208 141277 68208 141278 70646 141278 70840 141278 68208 141279 70840 141279 68205 141279 68205 141280 70840 141280 70841 141280 68205 141281 70841 141281 70647 141281 70647 141282 70841 141282 70648 141282 70647 141283 70648 141283 70650 141283 70650 141284 70648 141284 70649 141284 70650 141285 70649 141285 68548 141285 65811 141286 65810 141286 70651 141286 65811 141287 70651 141287 70652 141287 70652 141288 70651 141288 70856 141288 70652 141289 70856 141289 70653 141289 70653 141290 70856 141290 70854 141290 70653 141291 70854 141291 70654 141291 70654 141292 70854 141292 70852 141292 70654 141293 70852 141293 70655 141293 70655 141294 70852 141294 70857 141294 70655 141295 70857 141295 68202 141295 68202 141296 70857 141296 70859 141296 68202 141297 70859 141297 68201 141297 68201 141298 70859 141298 70656 141298 68201 141299 70656 141299 68200 141299 68200 141300 70656 141300 70658 141300 68200 141301 70658 141301 70657 141301 70657 141302 70658 141302 70659 141302 70657 141303 70659 141303 68199 141303 68199 141304 70659 141304 70660 141304 68199 141305 70660 141305 68198 141305 68198 141306 70660 141306 70848 141306 68198 141307 70848 141307 68196 141307 68196 141308 70848 141308 70862 141308 68196 141309 70862 141309 68194 141309 68194 141310 70862 141310 70662 141310 68194 141311 70662 141311 70661 141311 70661 141312 70662 141312 70663 141312 70661 141313 70663 141313 70664 141313 70664 141314 70663 141314 70665 141314 70664 141315 70665 141315 70666 141315 70666 141316 70665 141316 70668 141316 70666 141317 70668 141317 70667 141317 70667 141318 70668 141318 70845 141318 70667 141319 70845 141319 65814 141319 70669 141320 70826 141320 64845 141320 64845 141321 70826 141321 68679 141321 64845 141322 68679 141322 64825 141322 69012 141323 70670 141323 68654 141323 68654 141324 70670 141324 70671 141324 68654 141325 70671 141325 70776 141325 69327 141326 70672 141326 70673 141326 70673 141327 70672 141327 64931 141327 70673 141328 64931 141328 68629 141328 69118 141329 70674 141329 70699 141329 70699 141330 70674 141330 70855 141330 70699 141331 70855 141331 68653 141331 70678 141332 68646 141332 70679 141332 70681 141333 70676 141333 70675 141333 70675 141334 70676 141334 70677 141334 70675 141335 70677 141335 70680 141335 70678 141336 70679 141336 70680 141336 70680 141337 70679 141337 70699 141337 70680 141338 70699 141338 70675 141338 70675 141339 70699 141339 68653 141339 70675 141340 68653 141340 70681 141340 68646 141341 70682 141341 70679 141341 70679 141342 70682 141342 70683 141342 70679 141343 70683 141343 65235 141343 68645 141344 65236 141344 68643 141344 68643 141345 65236 141345 65235 141345 68643 141346 65235 141346 68649 141346 68649 141347 65235 141347 70683 141347 70684 141348 70803 141348 70685 141348 70685 141349 70803 141349 70686 141349 70686 141350 70687 141350 70685 141350 70685 141351 70687 141351 69079 141351 70685 141352 69079 141352 70684 141352 70684 141353 69079 141353 69076 141353 69101 141354 69099 141354 70804 141354 70804 141355 69099 141355 70688 141355 70688 141356 69097 141356 70804 141356 70804 141357 69097 141357 69096 141357 70804 141358 69096 141358 69094 141358 69094 141359 70689 141359 70804 141359 70804 141360 70689 141360 69089 141360 70804 141361 69089 141361 65193 141361 69089 141362 70690 141362 65193 141362 65193 141363 70690 141363 70691 141363 65193 141364 70691 141364 70679 141364 70679 141365 70691 141365 69092 141365 70679 141366 69092 141366 70692 141366 70692 141367 70693 141367 70679 141367 70679 141368 70693 141368 70694 141368 70679 141369 70694 141369 70699 141369 70699 141370 70694 141370 70695 141370 70699 141371 70695 141371 70698 141371 70696 141372 70697 141372 70700 141372 70700 141373 70697 141373 70701 141373 70698 141374 70696 141374 70699 141374 70699 141375 70696 141375 70700 141375 70699 141376 70700 141376 69118 141376 69118 141377 70700 141377 70701 141377 69118 141378 70701 141378 70702 141378 69039 141379 70704 141379 69040 141379 69040 141380 70704 141380 70703 141380 70710 141381 70708 141381 70705 141381 70705 141382 70708 141382 70704 141382 70705 141383 70704 141383 70706 141383 70706 141384 70704 141384 69039 141384 69036 141385 65185 141385 70707 141385 70707 141386 65185 141386 70708 141386 70707 141387 70708 141387 70709 141387 70709 141388 70708 141388 70710 141388 69034 141389 69032 141389 70799 141389 70799 141390 69032 141390 69033 141390 70712 141391 69059 141391 70711 141391 70711 141392 69059 141392 69058 141392 69033 141393 70712 141393 70799 141393 70799 141394 70712 141394 70711 141394 70799 141395 70711 141395 69065 141395 69065 141396 70711 141396 69058 141396 69065 141397 69058 141397 69057 141397 70798 141398 69022 141398 70713 141398 69022 141399 70798 141399 70797 141399 69019 141400 69017 141400 69028 141400 70796 141401 70714 141401 70715 141401 70715 141402 70714 141402 69043 141402 70715 141403 69043 141403 65182 141403 65182 141404 69043 141404 69042 141404 65182 141405 69042 141405 70704 141405 70704 141406 69042 141406 69041 141406 70704 141407 69041 141407 70703 141407 70731 141408 68972 141408 65176 141408 65176 141409 68972 141409 70718 141409 70716 141410 70795 141410 70717 141410 70717 141411 70795 141411 70718 141411 70717 141412 70718 141412 68970 141412 68970 141413 70718 141413 68972 141413 68968 141414 68964 141414 70722 141414 70722 141415 68964 141415 70719 141415 69007 141416 70720 141416 70721 141416 70721 141417 70720 141417 70723 141417 70719 141418 69007 141418 70722 141418 70722 141419 69007 141419 70721 141419 70722 141420 70721 141420 70724 141420 70724 141421 70721 141421 70723 141421 70724 141422 70723 141422 69003 141422 70725 141423 68940 141423 68955 141423 68940 141424 70725 141424 68943 141424 68954 141425 68953 141425 68959 141425 68982 141426 70726 141426 68979 141426 68979 141427 70726 141427 68943 141427 68979 141428 68943 141428 68959 141428 68959 141429 68943 141429 70725 141429 68959 141430 70725 141430 68954 141430 68954 141431 70725 141431 68955 141431 68982 141432 70727 141432 70726 141432 70726 141433 70727 141433 68981 141433 70726 141434 68981 141434 70730 141434 70730 141435 68981 141435 70728 141435 70730 141436 70728 141436 68978 141436 68978 141437 70729 141437 70730 141437 70730 141438 70729 141438 68976 141438 70730 141439 68976 141439 65176 141439 65176 141440 68976 141440 68975 141440 65176 141441 68975 141441 70731 141441 68897 141442 68896 141442 70743 141442 70743 141443 68896 141443 70732 141443 70793 141444 70733 141444 70735 141444 70735 141445 70733 141445 70734 141445 68928 141446 68934 141446 70736 141446 70736 141447 68934 141447 68933 141447 70734 141448 68928 141448 70735 141448 70735 141449 68928 141449 70736 141449 70735 141450 70736 141450 68931 141450 68931 141451 70736 141451 68933 141451 68931 141452 68933 141452 68932 141452 70737 141453 68873 141453 70738 141453 70738 141454 68873 141454 70739 141454 70739 141455 68883 141455 70738 141455 70738 141456 68883 141456 68880 141456 70738 141457 68880 141457 70737 141457 70737 141458 68880 141458 68881 141458 68912 141459 68910 141459 65169 141459 65169 141460 68910 141460 68909 141460 68909 141461 68907 141461 65169 141461 65169 141462 68907 141462 68906 141462 65169 141463 68906 141463 70741 141463 70741 141464 68906 141464 68898 141464 70741 141465 68898 141465 68905 141465 68905 141466 70740 141466 70741 141466 70741 141467 70740 141467 68904 141467 70741 141468 68904 141468 65170 141468 65170 141469 68904 141469 68903 141469 68903 141470 68901 141470 65170 141470 65170 141471 68901 141471 68900 141471 65170 141472 68900 141472 70743 141472 70743 141473 68900 141473 70742 141473 70743 141474 70742 141474 68897 141474 68877 141475 70747 141475 70744 141475 70744 141476 70747 141476 70745 141476 70744 141477 70745 141477 68887 141477 70788 141478 68927 141478 70791 141478 70791 141479 68927 141479 68893 141479 70791 141480 68893 141480 68877 141480 68877 141481 68893 141481 70746 141481 68877 141482 70746 141482 70747 141482 70747 141483 70746 141483 68891 141483 70747 141484 68891 141484 70745 141484 70750 141485 70785 141485 70748 141485 70748 141486 70785 141486 68950 141486 68950 141487 68938 141487 70748 141487 70748 141488 68938 141488 70749 141488 70748 141489 70749 141489 70750 141489 70750 141490 70749 141490 70751 141490 70787 141491 70752 141491 70786 141491 70786 141492 70752 141492 68915 141492 68915 141493 70753 141493 70786 141493 70786 141494 70753 141494 70754 141494 70786 141495 70754 141495 65164 141495 65164 141496 70754 141496 70755 141496 65164 141497 70755 141497 70759 141497 68920 141498 70756 141498 70757 141498 70757 141499 70756 141499 65164 141499 70757 141500 65164 141500 70758 141500 70758 141501 65164 141501 70759 141501 70763 141502 70670 141502 69009 141502 70670 141503 70763 141503 70671 141503 69010 141504 70760 141504 70762 141504 70761 141505 68985 141505 70766 141505 70761 141506 70766 141506 68983 141506 69009 141507 69010 141507 70763 141507 70763 141508 69010 141508 70762 141508 70763 141509 70762 141509 70671 141509 70671 141510 70762 141510 70764 141510 70671 141511 70764 141511 70766 141511 70766 141512 70764 141512 70765 141512 70766 141513 70765 141513 68983 141513 68985 141514 68987 141514 70766 141514 70766 141515 68987 141515 68988 141515 70766 141516 68988 141516 70767 141516 70768 141517 70769 141517 68991 141517 68991 141518 70769 141518 70767 141518 68991 141519 70767 141519 70770 141519 70770 141520 70767 141520 68988 141520 70768 141521 68995 141521 70769 141521 70769 141522 68995 141522 70771 141522 70769 141523 70771 141523 68997 141523 68999 141524 69001 141524 68945 141524 68961 141525 68957 141525 70772 141525 70772 141526 68957 141526 68956 141526 69001 141527 68961 141527 68945 141527 68945 141528 68961 141528 70772 141528 68945 141529 70772 141529 70773 141529 70773 141530 70772 141530 68956 141530 70773 141531 68956 141531 70774 141531 64829 141532 65812 141532 70775 141532 70775 141533 65812 141533 68661 141533 70775 141534 68661 141534 70766 141534 68661 141535 68663 141535 70766 141535 70766 141536 68663 141536 68664 141536 70766 141537 68664 141537 68666 141537 70671 141538 70780 141538 70776 141538 70776 141539 70780 141539 70777 141539 70776 141540 70777 141540 68655 141540 68666 141541 70778 141541 70766 141541 70766 141542 70778 141542 70779 141542 70766 141543 70779 141543 70671 141543 70671 141544 70779 141544 68659 141544 70671 141545 68659 141545 70780 141545 70780 141546 68659 141546 68657 141546 70780 141547 68657 141547 70777 141547 68997 141548 68999 141548 70769 141548 70769 141549 68999 141549 68945 141549 70769 141550 68945 141550 70781 141550 70781 141551 68945 141551 70782 141551 70781 141552 70782 141552 70783 141552 70783 141553 70782 141553 70784 141553 70783 141554 70784 141554 65162 141554 65162 141555 70784 141555 68948 141555 65162 141556 68948 141556 70786 141556 70786 141557 68948 141557 70785 141557 70786 141558 70785 141558 70787 141558 70787 141559 70785 141559 70750 141559 68920 141560 68922 141560 70756 141560 70756 141561 68922 141561 68924 141561 70756 141562 68924 141562 65167 141562 65167 141563 68924 141563 70788 141563 65167 141564 70788 141564 70789 141564 70789 141565 70788 141565 70791 141565 70789 141566 70791 141566 70790 141566 70790 141567 70791 141567 70792 141567 70790 141568 70792 141568 65169 141568 65169 141569 70792 141569 68873 141569 65169 141570 68873 141570 68912 141570 68912 141571 68873 141571 70737 141571 68896 141572 70793 141572 70732 141572 70732 141573 70793 141573 70735 141573 70732 141574 70735 141574 65172 141574 65172 141575 70735 141575 70794 141575 65172 141576 70794 141576 70726 141576 70726 141577 70794 141577 68944 141577 70726 141578 68944 141578 68943 141578 70716 141579 68968 141579 70795 141579 70795 141580 68968 141580 70722 141580 70795 141581 70722 141581 65180 141581 65180 141582 70722 141582 69014 141582 65180 141583 69014 141583 70715 141583 70715 141584 69014 141584 69015 141584 70715 141585 69015 141585 70796 141585 70796 141586 69015 141586 70797 141586 70796 141587 70797 141587 69028 141587 69028 141588 70797 141588 70798 141588 69028 141589 70798 141589 69019 141589 69019 141590 70798 141590 70713 141590 69036 141591 69034 141591 65185 141591 65185 141592 69034 141592 70799 141592 65185 141593 70799 141593 65187 141593 65187 141594 70799 141594 70800 141594 65187 141595 70800 141595 65188 141595 65188 141596 70800 141596 70801 141596 65188 141597 70801 141597 65189 141597 65189 141598 70801 141598 70802 141598 65189 141599 70802 141599 70804 141599 70804 141600 70802 141600 70803 141600 70804 141601 70803 141601 69101 141601 69101 141602 70803 141602 70684 141602 70805 141603 69192 141603 70814 141603 70827 141604 69401 141604 69075 141604 70808 141605 70806 141605 70807 141605 69327 141606 70673 141606 69267 141606 69267 141607 70673 141607 70649 141607 69267 141608 70649 141608 69318 141608 69318 141609 70649 141609 70648 141609 70808 141610 70840 141610 70646 141610 70810 141611 69308 141611 70811 141611 70809 141612 70810 141612 70836 141612 70836 141613 70810 141613 70811 141613 70836 141614 70811 141614 70646 141614 70646 141615 70811 141615 69262 141615 70646 141616 69262 141616 70808 141616 70812 141617 70837 141617 70815 141617 69192 141618 69727 141618 70814 141618 70814 141619 69727 141619 70813 141619 70814 141620 70813 141620 70815 141620 70815 141621 70813 141621 70816 141621 70815 141622 70816 141622 70812 141622 70834 141623 70642 141623 70819 141623 69128 141624 69414 141624 70817 141624 70817 141625 69414 141625 70818 141625 70817 141626 70818 141626 70819 141626 70819 141627 70818 141627 69303 141627 70819 141628 69303 141628 70834 141628 70820 141629 70832 141629 70821 141629 70820 141630 70822 141630 70831 141630 70830 141631 70823 141631 70824 141631 70824 141632 70823 141632 70825 141632 70824 141633 70825 141633 70821 141633 70821 141634 70825 141634 69300 141634 70821 141635 69300 141635 70820 141635 68679 141636 70826 141636 68714 141636 68714 141637 70826 141637 69296 141637 68714 141638 69296 141638 70638 141638 69296 141639 70827 141639 70638 141639 70638 141640 70827 141640 69075 141640 70638 141641 69075 141641 70828 141641 69075 141642 69074 141642 70828 141642 70828 141643 69074 141643 69072 141643 70828 141644 69072 141644 70824 141644 70824 141645 69072 141645 70829 141645 70824 141646 70829 141646 70830 141646 70820 141647 70831 141647 70832 141647 70832 141648 70831 141648 69131 141648 70832 141649 69131 141649 70817 141649 70817 141650 69131 141650 69130 141650 70817 141651 69130 141651 69128 141651 70805 141652 70814 141652 69194 141652 69194 141653 70814 141653 70642 141653 69194 141654 70642 141654 70833 141654 70833 141655 70642 141655 70834 141655 70833 141656 70834 141656 70835 141656 70809 141657 70836 141657 69259 141657 69259 141658 70836 141658 70837 141658 69259 141659 70837 141659 70838 141659 70838 141660 70837 141660 70812 141660 70838 141661 70812 141661 70839 141661 70808 141662 70807 141662 70840 141662 70840 141663 70807 141663 69188 141663 70840 141664 69188 141664 70841 141664 69184 141665 69318 141665 69185 141665 69185 141666 69318 141666 70648 141666 69185 141667 70648 141667 69186 141667 69186 141668 70648 141668 70841 141668 69186 141669 70841 141669 70842 141669 70842 141670 70841 141670 69188 141670 69268 141671 69071 141671 69070 141671 70847 141672 70843 141672 68951 141672 69012 141673 68654 141673 69292 141673 69292 141674 68654 141674 70845 141674 69292 141675 70845 141675 70844 141675 70844 141676 70845 141676 70668 141676 70847 141677 70663 141677 70662 141677 68876 141678 68884 141678 70846 141678 68875 141679 68876 141679 70862 141679 70862 141680 68876 141680 70846 141680 70862 141681 70846 141681 70662 141681 70662 141682 70846 141682 69286 141682 70662 141683 69286 141683 70847 141683 70848 141684 70660 141684 70863 141684 70863 141685 70660 141685 69284 141685 69284 141686 70660 141686 70849 141686 70849 141687 70660 141687 70659 141687 70849 141688 70659 141688 70850 141688 65641 141689 68941 141689 70851 141689 70851 141690 68941 141690 70658 141690 70851 141691 70658 141691 70656 141691 69013 141692 69349 141692 70859 141692 70859 141693 69349 141693 69276 141693 70859 141694 69276 141694 70656 141694 70656 141695 69276 141695 69280 141695 70656 141696 69280 141696 70851 141696 65650 141697 70857 141697 70852 141697 65650 141698 70853 141698 69016 141698 69066 141699 69336 141699 70854 141699 70854 141700 69336 141700 69273 141700 70854 141701 69273 141701 70852 141701 70852 141702 69273 141702 69275 141702 70852 141703 69275 141703 65650 141703 70855 141704 70674 141704 65810 141704 65810 141705 70674 141705 69269 141705 65810 141706 69269 141706 70651 141706 69269 141707 69268 141707 70651 141707 70651 141708 69268 141708 69070 141708 70651 141709 69070 141709 70856 141709 69070 141710 69069 141710 70856 141710 70856 141711 69069 141711 69068 141711 70856 141712 69068 141712 70854 141712 70854 141713 69068 141713 69067 141713 70854 141714 69067 141714 69066 141714 65650 141715 69016 141715 70857 141715 70857 141716 69016 141716 70858 141716 70857 141717 70858 141717 70859 141717 70859 141718 70858 141718 70860 141718 70859 141719 70860 141719 69013 141719 68941 141720 68942 141720 70658 141720 70658 141721 68942 141721 70861 141721 70658 141722 70861 141722 70659 141722 70659 141723 70861 141723 68939 141723 70659 141724 68939 141724 70850 141724 68875 141725 70862 141725 68874 141725 68874 141726 70862 141726 70848 141726 68874 141727 70848 141727 68872 141727 68872 141728 70848 141728 70863 141728 68872 141729 70863 141729 68871 141729 70847 141730 68951 141730 70663 141730 70663 141731 68951 141731 68949 141731 70663 141732 68949 141732 70665 141732 70864 141733 70844 141733 68946 141733 68946 141734 70844 141734 70668 141734 68946 141735 70668 141735 70865 141735 70865 141736 70668 141736 70665 141736 70865 141737 70665 141737 68947 141737 68947 141738 70665 141738 68949 141738 70872 141739 67757 141739 70898 141739 68383 141740 70866 141740 70872 141740 70898 141741 67757 141741 70867 141741 70867 141742 67757 141742 67758 141742 70867 141743 67758 141743 65954 141743 65951 141744 70868 141744 70877 141744 70874 141745 68357 141745 68359 141745 67758 141746 67754 141746 65954 141746 65954 141747 67754 141747 67755 141747 65954 141748 67755 141748 65953 141748 65953 141749 67755 141749 67751 141749 65953 141750 67751 141750 70868 141750 70868 141751 67751 141751 70869 141751 70868 141752 70869 141752 70877 141752 70877 141753 70869 141753 70870 141753 70877 141754 70870 141754 70871 141754 70871 141755 70870 141755 67776 141755 68383 141756 70872 141756 68381 141756 68381 141757 70872 141757 70873 141757 68381 141758 70873 141758 67761 141758 70874 141759 68359 141759 66265 141759 66265 141760 68359 141760 68360 141760 66265 141761 68360 141761 70875 141761 70875 141762 68360 141762 68361 141762 70875 141763 68361 141763 66262 141763 66262 141764 68361 141764 70876 141764 66262 141765 70876 141765 66260 141765 66260 141766 70876 141766 68365 141766 66260 141767 68365 141767 66259 141767 66259 141768 68365 141768 68367 141768 66259 141769 68367 141769 66257 141769 66257 141770 68367 141770 68369 141770 66257 141771 68369 141771 66256 141771 66690 141772 67776 141772 68384 141772 68384 141773 67776 141773 70870 141773 68384 141774 70870 141774 68385 141774 68385 141775 70870 141775 66717 141775 70877 141776 67774 141776 65951 141776 65951 141777 67774 141777 70878 141777 65951 141778 70878 141778 65950 141778 65950 141779 70878 141779 70888 141779 68369 141780 68370 141780 66256 141780 66256 141781 68370 141781 68372 141781 66256 141782 68372 141782 66254 141782 66254 141783 68372 141783 68373 141783 66254 141784 68373 141784 70879 141784 70879 141785 68373 141785 70880 141785 70879 141786 70880 141786 66252 141786 66252 141787 70880 141787 70881 141787 66252 141788 70881 141788 70882 141788 70882 141789 70881 141789 68374 141789 70882 141790 68374 141790 70883 141790 70883 141791 68374 141791 70884 141791 70883 141792 70884 141792 67771 141792 67771 141793 70884 141793 70885 141793 67771 141794 70885 141794 70886 141794 70886 141795 70885 141795 65948 141795 70886 141796 65948 141796 70887 141796 70887 141797 65948 141797 65949 141797 70887 141798 65949 141798 70888 141798 70888 141799 65949 141799 70889 141799 70888 141800 70889 141800 65950 141800 68357 141801 70874 141801 70890 141801 70890 141802 70874 141802 66267 141802 70890 141803 66267 141803 68356 141803 68356 141804 66267 141804 66269 141804 68356 141805 66269 141805 68354 141805 68354 141806 66269 141806 70891 141806 68354 141807 70891 141807 68353 141807 68353 141808 70891 141808 66248 141808 68353 141809 66248 141809 70892 141809 70892 141810 66248 141810 70893 141810 70892 141811 70893 141811 65960 141811 65960 141812 70893 141812 66249 141812 65960 141813 66249 141813 70894 141813 70894 141814 66249 141814 70895 141814 70894 141815 70895 141815 65958 141815 65958 141816 70895 141816 66250 141816 65958 141817 66250 141817 70896 141817 70896 141818 66250 141818 67764 141818 70896 141819 67764 141819 70897 141819 70897 141820 67764 141820 67766 141820 70897 141821 67766 141821 70898 141821 70898 141822 67766 141822 67769 141822 70898 141823 67769 141823 70872 141823 70872 141824 67769 141824 67763 141824 70872 141825 67763 141825 70873 141825 64818 141826 70900 141826 70899 141826 70902 141827 70900 141827 64818 141827 64816 141828 70902 141828 64818 141828 64818 141829 70905 141829 70907 141829 70901 141830 70905 141830 64818 141830 70899 141831 70901 141831 64818 141831 64816 141832 70922 141832 70902 141832 70902 141833 70922 141833 70903 141833 70902 141834 70903 141834 70900 141834 70900 141835 70903 141835 70904 141835 70900 141836 70904 141836 70899 141836 70899 141837 70904 141837 70909 141837 70899 141838 70909 141838 70901 141838 70901 141839 70909 141839 70910 141839 70901 141840 70910 141840 70905 141840 70905 141841 70910 141841 70906 141841 70905 141842 70906 141842 70907 141842 70907 141843 70906 141843 70914 141843 70904 141844 70908 141844 70909 141844 70909 141845 70908 141845 70911 141845 70909 141846 70911 141846 70910 141846 70910 141847 70911 141847 70912 141847 70910 141848 70912 141848 70906 141848 70906 141849 70912 141849 70913 141849 70906 141850 70913 141850 70914 141850 70914 141851 70913 141851 70915 141851 70914 141852 70915 141852 64811 141852 64811 141853 70915 141853 70916 141853 64811 141854 70916 141854 64813 141854 64813 141855 70916 141855 70917 141855 64813 141856 70917 141856 64815 141856 64815 141857 70917 141857 70918 141857 64815 141858 70918 141858 70919 141858 70919 141859 70918 141859 70921 141859 70919 141860 70921 141860 70920 141860 70920 141861 70921 141861 66452 141861 70920 141862 66452 141862 70922 141862 70922 141863 66452 141863 67450 141863 70922 141864 67450 141864 70903 141864 70903 141865 67450 141865 67449 141865 70903 141866 67449 141866 70904 141866 70904 141867 67449 141867 70908 141867 70923 141868 70927 141868 70924 141868 70926 141869 70927 141869 70923 141869 64810 141870 70926 141870 70923 141870 70923 141871 70929 141871 70930 141871 70925 141872 70929 141872 70923 141872 70924 141873 70925 141873 70923 141873 64810 141874 70942 141874 70926 141874 70926 141875 70942 141875 70945 141875 70926 141876 70945 141876 70927 141876 70927 141877 70945 141877 70946 141877 70927 141878 70946 141878 70924 141878 70924 141879 70946 141879 70928 141879 70924 141880 70928 141880 70925 141880 70925 141881 70928 141881 70933 141881 70925 141882 70933 141882 70929 141882 70929 141883 70933 141883 70934 141883 70929 141884 70934 141884 70930 141884 70930 141885 70934 141885 70931 141885 70928 141886 70932 141886 70933 141886 70933 141887 70932 141887 67430 141887 70933 141888 67430 141888 70934 141888 70934 141889 67430 141889 67428 141889 70934 141890 67428 141890 70931 141890 70931 141891 67428 141891 70935 141891 70931 141892 70935 141892 70936 141892 70936 141893 70935 141893 70937 141893 70936 141894 70937 141894 64804 141894 64804 141895 70937 141895 70938 141895 64804 141896 70938 141896 70939 141896 70939 141897 70938 141897 70940 141897 70939 141898 70940 141898 64807 141898 64807 141899 70940 141899 66467 141899 64807 141900 66467 141900 70941 141900 70941 141901 66467 141901 70943 141901 70941 141902 70943 141902 70942 141902 70942 141903 70943 141903 70944 141903 70942 141904 70944 141904 70945 141904 70945 141905 70944 141905 70947 141905 70945 141906 70947 141906 70946 141906 70946 141907 70947 141907 67432 141907 70946 141908 67432 141908 70928 141908 70928 141909 67432 141909 70932 141909 70948 141910 70952 141910 70953 141910 70950 141911 70952 141911 70948 141911 70949 141912 70950 141912 70948 141912 70948 141913 70957 141913 70959 141913 70955 141914 70957 141914 70948 141914 70953 141915 70955 141915 70948 141915 70949 141916 70951 141916 70950 141916 70950 141917 70951 141917 70961 141917 70950 141918 70961 141918 70952 141918 70952 141919 70961 141919 70964 141919 70952 141920 70964 141920 70953 141920 70953 141921 70964 141921 70954 141921 70953 141922 70954 141922 70955 141922 70955 141923 70954 141923 70956 141923 70955 141924 70956 141924 70957 141924 70957 141925 70956 141925 70958 141925 70957 141926 70958 141926 70959 141926 70959 141927 70958 141927 64793 141927 64797 141928 66482 141928 70960 141928 70960 141929 66482 141929 66480 141929 70960 141930 66480 141930 64800 141930 64800 141931 66480 141931 66479 141931 64800 141932 66479 141932 70951 141932 70951 141933 66479 141933 70962 141933 70951 141934 70962 141934 70961 141934 70961 141935 70962 141935 70963 141935 70961 141936 70963 141936 70964 141936 70964 141937 70963 141937 67414 141937 70964 141938 67414 141938 70954 141938 70954 141939 67414 141939 67413 141939 70954 141940 67413 141940 70956 141940 70956 141941 67413 141941 67411 141941 70956 141942 67411 141942 70958 141942 70958 141943 67411 141943 70965 141943 70958 141944 70965 141944 64793 141944 64793 141945 70965 141945 67409 141945 64793 141946 67409 141946 64794 141946 64794 141947 67409 141947 70966 141947 64794 141948 70966 141948 64796 141948 64796 141949 70966 141949 66483 141949 64796 141950 66483 141950 64797 141950 64797 141951 66483 141951 66482 141951 64790 141952 70967 141952 70971 141952 70968 141953 70967 141953 64790 141953 70969 141954 70968 141954 64790 141954 64790 141955 70975 141955 64785 141955 70974 141956 70975 141956 64790 141956 70971 141957 70974 141957 64790 141957 70969 141958 70970 141958 70968 141958 70968 141959 70970 141959 70979 141959 70968 141960 70979 141960 70967 141960 70967 141961 70979 141961 70982 141961 70967 141962 70982 141962 70971 141962 70971 141963 70982 141963 70972 141963 70971 141964 70972 141964 70974 141964 70974 141965 70972 141965 70973 141965 70974 141966 70973 141966 70975 141966 70975 141967 70973 141967 70984 141967 70975 141968 70984 141968 64785 141968 64785 141969 70984 141969 70985 141969 64789 141970 70990 141970 70976 141970 70976 141971 70990 141971 66498 141971 70976 141972 66498 141972 70977 141972 70977 141973 66498 141973 70978 141973 70977 141974 70978 141974 70970 141974 70970 141975 70978 141975 70980 141975 70970 141976 70980 141976 70979 141976 70979 141977 70980 141977 70981 141977 70979 141978 70981 141978 70982 141978 70982 141979 70981 141979 67396 141979 70982 141980 67396 141980 70972 141980 70972 141981 67396 141981 67395 141981 70972 141982 67395 141982 70973 141982 70973 141983 67395 141983 70983 141983 70973 141984 70983 141984 70984 141984 70984 141985 70983 141985 67393 141985 70984 141986 67393 141986 70985 141986 70985 141987 67393 141987 66500 141987 70985 141988 66500 141988 70986 141988 70986 141989 66500 141989 70987 141989 70986 141990 70987 141990 70988 141990 70988 141991 70987 141991 70989 141991 70988 141992 70989 141992 64789 141992 64789 141993 70989 141993 70990 141993 64782 141994 70991 141994 70997 141994 70992 141995 70991 141995 64782 141995 64784 141996 70992 141996 64782 141996 64782 141997 70993 141997 70999 141997 70998 141998 70993 141998 64782 141998 70997 141999 70998 141999 64782 141999 64784 142000 70994 142000 70992 142000 70992 142001 70994 142001 71004 142001 70992 142002 71004 142002 70991 142002 70991 142003 71004 142003 70995 142003 70991 142004 70995 142004 70997 142004 70997 142005 70995 142005 70996 142005 70997 142006 70996 142006 70998 142006 70998 142007 70996 142007 71007 142007 70998 142008 71007 142008 70993 142008 70993 142009 71007 142009 71000 142009 70993 142010 71000 142010 70999 142010 70999 142011 71000 142011 71001 142011 71011 142012 66517 142012 64780 142012 64780 142013 66517 142013 71002 142013 64780 142014 71002 142014 71003 142014 71003 142015 71002 142015 66515 142015 71003 142016 66515 142016 70994 142016 70994 142017 66515 142017 67383 142017 70994 142018 67383 142018 71004 142018 71004 142019 67383 142019 67381 142019 71004 142020 67381 142020 70995 142020 70995 142021 67381 142021 71005 142021 70995 142022 71005 142022 70996 142022 70996 142023 71005 142023 71006 142023 70996 142024 71006 142024 71007 142024 71007 142025 71006 142025 67379 142025 71007 142026 67379 142026 71000 142026 71000 142027 67379 142027 71008 142027 71000 142028 71008 142028 71001 142028 71001 142029 71008 142029 67378 142029 71001 142030 67378 142030 64776 142030 64776 142031 67378 142031 66519 142031 64776 142032 66519 142032 71009 142032 71009 142033 66519 142033 71010 142033 71009 142034 71010 142034 71011 142034 71011 142035 71010 142035 66517 142035 64773 142036 71015 142036 71016 142036 71014 142037 71015 142037 64773 142037 71013 142038 71014 142038 64773 142038 64773 142039 71019 142039 64767 142039 71012 142040 71019 142040 64773 142040 71016 142041 71012 142041 64773 142041 71013 142042 71032 142042 71014 142042 71014 142043 71032 142043 71034 142043 71014 142044 71034 142044 71015 142044 71015 142045 71034 142045 71035 142045 71015 142046 71035 142046 71016 142046 71016 142047 71035 142047 71017 142047 71016 142048 71017 142048 71012 142048 71012 142049 71017 142049 71018 142049 71012 142050 71018 142050 71019 142050 71019 142051 71018 142051 71020 142051 71019 142052 71020 142052 64767 142052 64767 142053 71020 142053 71021 142053 71017 142054 71036 142054 71018 142054 71018 142055 71036 142055 71022 142055 71018 142056 71022 142056 71020 142056 71020 142057 71022 142057 67361 142057 71020 142058 67361 142058 71021 142058 71021 142059 67361 142059 71023 142059 71021 142060 71023 142060 64768 142060 64768 142061 71023 142061 71024 142061 64768 142062 71024 142062 71025 142062 71025 142063 71024 142063 71026 142063 71025 142064 71026 142064 71027 142064 71027 142065 71026 142065 71028 142065 71027 142066 71028 142066 64770 142066 64770 142067 71028 142067 71029 142067 64770 142068 71029 142068 71030 142068 71030 142069 71029 142069 71031 142069 71030 142070 71031 142070 71032 142070 71032 142071 71031 142071 71033 142071 71032 142072 71033 142072 71034 142072 71034 142073 71033 142073 67366 142073 71034 142074 67366 142074 71035 142074 71035 142075 67366 142075 67365 142075 71035 142076 67365 142076 71017 142076 71017 142077 67365 142077 71036 142077 64763 142078 71037 142078 71041 142078 71039 142079 71037 142079 64763 142079 64761 142080 71039 142080 64763 142080 64763 142081 71044 142081 71038 142081 71043 142082 71044 142082 64763 142082 71041 142083 71043 142083 64763 142083 64761 142084 64762 142084 71039 142084 71039 142085 64762 142085 71052 142085 71039 142086 71052 142086 71037 142086 71037 142087 71052 142087 71040 142087 71037 142088 71040 142088 71041 142088 71041 142089 71040 142089 71042 142089 71041 142090 71042 142090 71043 142090 71043 142091 71042 142091 71053 142091 71043 142092 71053 142092 71044 142092 71044 142093 71053 142093 71045 142093 71044 142094 71045 142094 71038 142094 71038 142095 71045 142095 71054 142095 64757 142096 71046 142096 71047 142096 71047 142097 71046 142097 66551 142097 71047 142098 66551 142098 71048 142098 71048 142099 66551 142099 71049 142099 71048 142100 71049 142100 64760 142100 64760 142101 71049 142101 66548 142101 64760 142102 66548 142102 71050 142102 71050 142103 66548 142103 71051 142103 71050 142104 71051 142104 64762 142104 64762 142105 71051 142105 67349 142105 64762 142106 67349 142106 71052 142106 71052 142107 67349 142107 67347 142107 71052 142108 67347 142108 71040 142108 71040 142109 67347 142109 67346 142109 71040 142110 67346 142110 71042 142110 71042 142111 67346 142111 67345 142111 71042 142112 67345 142112 71053 142112 71053 142113 67345 142113 67344 142113 71053 142114 67344 142114 71045 142114 71045 142115 67344 142115 67341 142115 71045 142116 67341 142116 71054 142116 71054 142117 67341 142117 71055 142117 71054 142118 71055 142118 64757 142118 64757 142119 71055 142119 71046 142119 64754 142120 71056 142120 71059 142120 71057 142121 71056 142121 64754 142121 64753 142122 71057 142122 64754 142122 64754 142123 71061 142123 64755 142123 71058 142124 71061 142124 64754 142124 71059 142125 71058 142125 64754 142125 64753 142126 71066 142126 71057 142126 71057 142127 71066 142127 71068 142127 71057 142128 71068 142128 71056 142128 71056 142129 71068 142129 71069 142129 71056 142130 71069 142130 71059 142130 71059 142131 71069 142131 71060 142131 71059 142132 71060 142132 71058 142132 71058 142133 71060 142133 71062 142133 71058 142134 71062 142134 71061 142134 71061 142135 71062 142135 71072 142135 71061 142136 71072 142136 64755 142136 64755 142137 71072 142137 71073 142137 64750 142138 71077 142138 71063 142138 71063 142139 71077 142139 71064 142139 71063 142140 71064 142140 64752 142140 64752 142141 71064 142141 66566 142141 64752 142142 66566 142142 71066 142142 71066 142143 66566 142143 71065 142143 71066 142144 71065 142144 71068 142144 71068 142145 71065 142145 71067 142145 71068 142146 71067 142146 71069 142146 71069 142147 71067 142147 67328 142147 71069 142148 67328 142148 71060 142148 71060 142149 67328 142149 71070 142149 71060 142150 71070 142150 71062 142150 71062 142151 71070 142151 67325 142151 71062 142152 67325 142152 71072 142152 71072 142153 67325 142153 71071 142153 71072 142154 71071 142154 71073 142154 71073 142155 71071 142155 71074 142155 71073 142156 71074 142156 71075 142156 71075 142157 71074 142157 66569 142157 71075 142158 66569 142158 64748 142158 64748 142159 66569 142159 71076 142159 64748 142160 71076 142160 64750 142160 64750 142161 71076 142161 71077 142161 71078 142162 71083 142162 71079 142162 71081 142163 71083 142163 71078 142163 71080 142164 71081 142164 71078 142164 71078 142165 71087 142165 64736 142165 71085 142166 71087 142166 71078 142166 71079 142167 71085 142167 71078 142167 71080 142168 71097 142168 71081 142168 71081 142169 71097 142169 71082 142169 71081 142170 71082 142170 71083 142170 71083 142171 71082 142171 71099 142171 71083 142172 71099 142172 71079 142172 71079 142173 71099 142173 71084 142173 71079 142174 71084 142174 71085 142174 71085 142175 71084 142175 71090 142175 71085 142176 71090 142176 71087 142176 71087 142177 71090 142177 71086 142177 71087 142178 71086 142178 64736 142178 64736 142179 71086 142179 71092 142179 71099 142180 71100 142180 71084 142180 71084 142181 71100 142181 71088 142181 71084 142182 71088 142182 71090 142182 71090 142183 71088 142183 71089 142183 71090 142184 71089 142184 71086 142184 71086 142185 71089 142185 71091 142185 71086 142186 71091 142186 71092 142186 71092 142187 71091 142187 66585 142187 71092 142188 66585 142188 64739 142188 64739 142189 66585 142189 71093 142189 64739 142190 71093 142190 64740 142190 64740 142191 71093 142191 71094 142191 64740 142192 71094 142192 71095 142192 71095 142193 71094 142193 66583 142193 71095 142194 66583 142194 64742 142194 64742 142195 66583 142195 66582 142195 64742 142196 66582 142196 64744 142196 64744 142197 66582 142197 71096 142197 64744 142198 71096 142198 71097 142198 71097 142199 71096 142199 71098 142199 71097 142200 71098 142200 71082 142200 71082 142201 71098 142201 67310 142201 71082 142202 67310 142202 71099 142202 71099 142203 67310 142203 71100 142203 71111 142204 71102 142204 71101 142204 71101 142205 71102 142205 71103 142205 71101 142206 71103 142206 71104 142206 71104 142207 71103 142207 67293 142207 71104 142208 67293 142208 71105 142208 71105 142209 67293 142209 67292 142209 71105 142210 67292 142210 71106 142210 71106 142211 67292 142211 67290 142211 71106 142212 67290 142212 71107 142212 71107 142213 67290 142213 66604 142213 71107 142214 66604 142214 64728 142214 64728 142215 66604 142215 71108 142215 64728 142216 71108 142216 64732 142216 64732 142217 71108 142217 66603 142217 64732 142218 66603 142218 64733 142218 64733 142219 66603 142219 66601 142219 64733 142220 66601 142220 71109 142220 71109 142221 66601 142221 66599 142221 71109 142222 66599 142222 71113 142222 71113 142223 66599 142223 71110 142223 71113 142224 71110 142224 71115 142224 71115 142225 71110 142225 71112 142225 71115 142226 71112 142226 71111 142226 71111 142227 71112 142227 71102 142227 64735 142228 71113 142228 71116 142228 71116 142229 71113 142229 71115 142229 71116 142230 71115 142230 71114 142230 71114 142231 71115 142231 71111 142231 71114 142232 71111 142232 71119 142232 71119 142233 71111 142233 71101 142233 71119 142234 71101 142234 71120 142234 71120 142235 71101 142235 71104 142235 71120 142236 71104 142236 71117 142236 71117 142237 71104 142237 71105 142237 71117 142238 71105 142238 71118 142238 71118 142239 71105 142239 71106 142239 71121 142240 71114 142240 71119 142240 71116 142241 71114 142241 71121 142241 64735 142242 71116 142242 71121 142242 71121 142243 71117 142243 71118 142243 71120 142244 71117 142244 71121 142244 71119 142245 71120 142245 71121 142245 71759 142246 71123 142246 71122 142246 71122 142247 71123 142247 71795 142247 71122 142248 71795 142248 71758 142248 71758 142249 71795 142249 71762 142249 71758 142250 71762 142250 71124 142250 71124 142251 71762 142251 71126 142251 71124 142252 71126 142252 71125 142252 71125 142253 71126 142253 71127 142253 71125 142254 71127 142254 71128 142254 71128 142255 71127 142255 71129 142255 71128 142256 71129 142256 71754 142256 71754 142257 71129 142257 71130 142257 71754 142258 71130 142258 71131 142258 71131 142259 71130 142259 71766 142259 71131 142260 71766 142260 71752 142260 71752 142261 71766 142261 71132 142261 71752 142262 71132 142262 71751 142262 71751 142263 71132 142263 71133 142263 71751 142264 71133 142264 71134 142264 71134 142265 71133 142265 71769 142265 71134 142266 71769 142266 71747 142266 71747 142267 71769 142267 71771 142267 71747 142268 71771 142268 71136 142268 71136 142269 71771 142269 71135 142269 71136 142270 71135 142270 71137 142270 71137 142271 71135 142271 71772 142271 71137 142272 71772 142272 71745 142272 71745 142273 71772 142273 71773 142273 71745 142274 71773 142274 71743 142274 71743 142275 71773 142275 71138 142275 71743 142276 71138 142276 71742 142276 71742 142277 71138 142277 71139 142277 71742 142278 71139 142278 72886 142278 72886 142279 71139 142279 72888 142279 71140 142280 71827 142280 71812 142280 71812 142281 71827 142281 71830 142281 71812 142282 71830 142282 71141 142282 71141 142283 71830 142283 71831 142283 71141 142284 71831 142284 71810 142284 71810 142285 71831 142285 71832 142285 71810 142286 71832 142286 71809 142286 71809 142287 71832 142287 71142 142287 71809 142288 71142 142288 71143 142288 71143 142289 71142 142289 71144 142289 71143 142290 71144 142290 71807 142290 71807 142291 71144 142291 71145 142291 71807 142292 71145 142292 71806 142292 71806 142293 71145 142293 71834 142293 71806 142294 71834 142294 71804 142294 71804 142295 71834 142295 71146 142295 71804 142296 71146 142296 71147 142296 71147 142297 71146 142297 71836 142297 71147 142298 71836 142298 71148 142298 71148 142299 71836 142299 71149 142299 71148 142300 71149 142300 71802 142300 71802 142301 71149 142301 71838 142301 71802 142302 71838 142302 71150 142302 71150 142303 71838 142303 71839 142303 71150 142304 71839 142304 71798 142304 71798 142305 71839 142305 71841 142305 71798 142306 71841 142306 71151 142306 71151 142307 71841 142307 71842 142307 71151 142308 71842 142308 71797 142308 71797 142309 71842 142309 71152 142309 71797 142310 71152 142310 71153 142310 71153 142311 71152 142311 71844 142311 71153 142312 71844 142312 72360 142312 72360 142313 71844 142313 71845 142313 72873 142314 72872 142314 71154 142314 72873 142315 71154 142315 71848 142315 71848 142316 71154 142316 71155 142316 71848 142317 71155 142317 71850 142317 71850 142318 71155 142318 71157 142318 71850 142319 71157 142319 71156 142319 71156 142320 71157 142320 71851 142320 71156 142321 71851 142321 71813 142321 71813 142322 71851 142322 71853 142322 71813 142323 71853 142323 71815 142323 71815 142324 71853 142324 71854 142324 71815 142325 71854 142325 71817 142325 71817 142326 71854 142326 71159 142326 71817 142327 71159 142327 71158 142327 71158 142328 71159 142328 71855 142328 71158 142329 71855 142329 71160 142329 71160 142330 71855 142330 71856 142330 71160 142331 71856 142331 71818 142331 71818 142332 71856 142332 71161 142332 71818 142333 71161 142333 71819 142333 71819 142334 71161 142334 71857 142334 71819 142335 71857 142335 71162 142335 71162 142336 71857 142336 71163 142336 71162 142337 71163 142337 71822 142337 71822 142338 71163 142338 71860 142338 71822 142339 71860 142339 71823 142339 71823 142340 71860 142340 71862 142340 71823 142341 71862 142341 71164 142341 71164 142342 71862 142342 71864 142342 71164 142343 71864 142343 71165 142343 71165 142344 71864 142344 71865 142344 71165 142345 71865 142345 71826 142345 71826 142346 71865 142346 71866 142346 71826 142347 71866 142347 71828 142347 71828 142348 71866 142348 72320 142348 71828 142349 72320 142349 71829 142349 71662 142350 72394 142350 71166 142350 71662 142351 71166 142351 71663 142351 71663 142352 71166 142352 71700 142352 71663 142353 71700 142353 71167 142353 71167 142354 71700 142354 71702 142354 71167 142355 71702 142355 71665 142355 71665 142356 71702 142356 71168 142356 71665 142357 71168 142357 71667 142357 71667 142358 71168 142358 71705 142358 71667 142359 71705 142359 71669 142359 71669 142360 71705 142360 71169 142360 71669 142361 71169 142361 71672 142361 71672 142362 71169 142362 71170 142362 71672 142363 71170 142363 71673 142363 71673 142364 71170 142364 71171 142364 71673 142365 71171 142365 71674 142365 71674 142366 71171 142366 71706 142366 71674 142367 71706 142367 71676 142367 71676 142368 71706 142368 71707 142368 71676 142369 71707 142369 71678 142369 71678 142370 71707 142370 71172 142370 71678 142371 71172 142371 71173 142371 71173 142372 71172 142372 71709 142372 71173 142373 71709 142373 71174 142373 71174 142374 71709 142374 71175 142374 71174 142375 71175 142375 71680 142375 71680 142376 71175 142376 71712 142376 71680 142377 71712 142377 71681 142377 71681 142378 71712 142378 71714 142378 71681 142379 71714 142379 71684 142379 71684 142380 71714 142380 71177 142380 71684 142381 71177 142381 71176 142381 71176 142382 71177 142382 72830 142382 71176 142383 72830 142383 71178 142383 72395 142384 71686 142384 71179 142384 71179 142385 71686 142385 71180 142385 71179 142386 71180 142386 71181 142386 71181 142387 71180 142387 71689 142387 71181 142388 71689 142388 71182 142388 71182 142389 71689 142389 71690 142389 71182 142390 71690 142390 71183 142390 71183 142391 71690 142391 71691 142391 71183 142392 71691 142392 71184 142392 71184 142393 71691 142393 71694 142393 71184 142394 71694 142394 71648 142394 71648 142395 71694 142395 71696 142395 71648 142396 71696 142396 71647 142396 71647 142397 71696 142397 71697 142397 71647 142398 71697 142398 71185 142398 71185 142399 71697 142399 71698 142399 71185 142400 71698 142400 71646 142400 71646 142401 71698 142401 71187 142401 71646 142402 71187 142402 71186 142402 71186 142403 71187 142403 71655 142403 71186 142404 71655 142404 71188 142404 71188 142405 71655 142405 71656 142405 71188 142406 71656 142406 71644 142406 71644 142407 71656 142407 71658 142407 71644 142408 71658 142408 71642 142408 71642 142409 71658 142409 71189 142409 71642 142410 71189 142410 71190 142410 71190 142411 71189 142411 71191 142411 71190 142412 71191 142412 71192 142412 71192 142413 71191 142413 71660 142413 71192 142414 71660 142414 71640 142414 71640 142415 71660 142415 71661 142415 71640 142416 71661 142416 72817 142416 72817 142417 71661 142417 71193 142417 72816 142418 71194 142418 71904 142418 72816 142419 71904 142419 71876 142419 71876 142420 71904 142420 71195 142420 71876 142421 71195 142421 71197 142421 71197 142422 71195 142422 71196 142422 71197 142423 71196 142423 71879 142423 71879 142424 71196 142424 71198 142424 71879 142425 71198 142425 71199 142425 71199 142426 71198 142426 71907 142426 71199 142427 71907 142427 71881 142427 71881 142428 71907 142428 71200 142428 71881 142429 71200 142429 71883 142429 71883 142430 71200 142430 71909 142430 71883 142431 71909 142431 71201 142431 71201 142432 71909 142432 71911 142432 71201 142433 71911 142433 71887 142433 71887 142434 71911 142434 71202 142434 71887 142435 71202 142435 71203 142435 71203 142436 71202 142436 71912 142436 71203 142437 71912 142437 71889 142437 71889 142438 71912 142438 71913 142438 71889 142439 71913 142439 71891 142439 71891 142440 71913 142440 71205 142440 71891 142441 71205 142441 71204 142441 71204 142442 71205 142442 71206 142442 71204 142443 71206 142443 71892 142443 71892 142444 71206 142444 71917 142444 71892 142445 71917 142445 71893 142445 71893 142446 71917 142446 71919 142446 71893 142447 71919 142447 71207 142447 71207 142448 71919 142448 71920 142448 71207 142449 71920 142449 71896 142449 71896 142450 71920 142450 71209 142450 71896 142451 71209 142451 71208 142451 71208 142452 71209 142452 72303 142452 71208 142453 72303 142453 71210 142453 71412 142454 72154 142454 71211 142454 71211 142455 72154 142455 72160 142455 71211 142456 72160 142456 71212 142456 71212 142457 72160 142457 72159 142457 71212 142458 72159 142458 71213 142458 71213 142459 72159 142459 72157 142459 71213 142460 72157 142460 71214 142460 71214 142461 72157 142461 71215 142461 71214 142462 71215 142462 71216 142462 71216 142463 71215 142463 72155 142463 71216 142464 72155 142464 72620 142464 72620 142465 72155 142465 72156 142465 71406 142466 71217 142466 71405 142466 71405 142467 71217 142467 71218 142467 71405 142468 71218 142468 71219 142468 71219 142469 71218 142469 72140 142469 71219 142470 72140 142470 71402 142470 71402 142471 72140 142471 71221 142471 71402 142472 71221 142472 71220 142472 71220 142473 71221 142473 71222 142473 71220 142474 71222 142474 71399 142474 71399 142475 71222 142475 71223 142475 71399 142476 71223 142476 71224 142476 71224 142477 71223 142477 72070 142477 71225 142478 72079 142478 71226 142478 71226 142479 72079 142479 72081 142479 71226 142480 72081 142480 71227 142480 71227 142481 72081 142481 71228 142481 71227 142482 71228 142482 71229 142482 71229 142483 71228 142483 71230 142483 71229 142484 71230 142484 71395 142484 71395 142485 71230 142485 71231 142485 71395 142486 71231 142486 71394 142486 71394 142487 71231 142487 71232 142487 71394 142488 71232 142488 72632 142488 72632 142489 71232 142489 72078 142489 72552 142490 71233 142490 71469 142490 71469 142491 71233 142491 71234 142491 71469 142492 71234 142492 71235 142492 71235 142493 71234 142493 72021 142493 71235 142494 72021 142494 71237 142494 71237 142495 72021 142495 71236 142495 71237 142496 71236 142496 71467 142496 71467 142497 71236 142497 71238 142497 71467 142498 71238 142498 71466 142498 71466 142499 71238 142499 71239 142499 71466 142500 71239 142500 71465 142500 71465 142501 71239 142501 72023 142501 72560 142502 72780 142502 71463 142502 71463 142503 72780 142503 71240 142503 71463 142504 71240 142504 71462 142504 71462 142505 71240 142505 72244 142505 71462 142506 72244 142506 71461 142506 71461 142507 72244 142507 72243 142507 71461 142508 72243 142508 71459 142508 71459 142509 72243 142509 71241 142509 71459 142510 71241 142510 71458 142510 71458 142511 71241 142511 72027 142511 71458 142512 72027 142512 71457 142512 71457 142513 72027 142513 72028 142513 72778 142514 72133 142514 71242 142514 71242 142515 72133 142515 72039 142515 71242 142516 72039 142516 71243 142516 71243 142517 72039 142517 71244 142517 71243 142518 71244 142518 71454 142518 71454 142519 71244 142519 72043 142519 71454 142520 72043 142520 71453 142520 71453 142521 72043 142521 72042 142521 71453 142522 72042 142522 71451 142522 71451 142523 72042 142523 71245 142523 71451 142524 71245 142524 72572 142524 72572 142525 71245 142525 72771 142525 71450 142526 71246 142526 71449 142526 71449 142527 71246 142527 72053 142527 71449 142528 72053 142528 71447 142528 71447 142529 72053 142529 72054 142529 71447 142530 72054 142530 71247 142530 71247 142531 72054 142531 71248 142531 71247 142532 71248 142532 71445 142532 71445 142533 71248 142533 71249 142533 71445 142534 71249 142534 71251 142534 71251 142535 71249 142535 71250 142535 71251 142536 71250 142536 71444 142536 71444 142537 71250 142537 72045 142537 72585 142538 71252 142538 71253 142538 71253 142539 71252 142539 71254 142539 71253 142540 71254 142540 71440 142540 71440 142541 71254 142541 72122 142541 71440 142542 72122 142542 71439 142542 71439 142543 72122 142543 71255 142543 71439 142544 71255 142544 71256 142544 71256 142545 71255 142545 71257 142545 71256 142546 71257 142546 71436 142546 71436 142547 71257 142547 71258 142547 71436 142548 71258 142548 72762 142548 72762 142549 71258 142549 71259 142549 72593 142550 72231 142550 71435 142550 71435 142551 72231 142551 71261 142551 71435 142552 71261 142552 71260 142552 71260 142553 71261 142553 72230 142553 71260 142554 72230 142554 71262 142554 71262 142555 72230 142555 72112 142555 71262 142556 72112 142556 71263 142556 71263 142557 72112 142557 71265 142557 71263 142558 71265 142558 71264 142558 71264 142559 71265 142559 72013 142559 71264 142560 72013 142560 71266 142560 71266 142561 72013 142561 72113 142561 71432 142562 72055 142562 71431 142562 71431 142563 72055 142563 72056 142563 71431 142564 72056 142564 71267 142564 71267 142565 72056 142565 72107 142565 71267 142566 72107 142566 71428 142566 71428 142567 72107 142567 71268 142567 71428 142568 71268 142568 71269 142568 71269 142569 71268 142569 71270 142569 71269 142570 71270 142570 71426 142570 71426 142571 71270 142571 72106 142571 71426 142572 72106 142572 71271 142572 71271 142573 72106 142573 71272 142573 71271 142574 71272 142574 72603 142574 72603 142575 71272 142575 72751 142575 71424 142576 72102 142576 71273 142576 71273 142577 72102 142577 72103 142577 71273 142578 72103 142578 71422 142578 71422 142579 72103 142579 71274 142579 71422 142580 71274 142580 71275 142580 71275 142581 71274 142581 71276 142581 71275 142582 71276 142582 71277 142582 71277 142583 71276 142583 71278 142583 71277 142584 71278 142584 71418 142584 71418 142585 71278 142585 71279 142585 71418 142586 71279 142586 71280 142586 71280 142587 71279 142587 72741 142587 72740 142588 71281 142588 71282 142588 71282 142589 71281 142589 71283 142589 71282 142590 71283 142590 71415 142590 71415 142591 71283 142591 72098 142591 71415 142592 72098 142592 71413 142592 71413 142593 72098 142593 72093 142593 71413 142594 72093 142594 71284 142594 71284 142595 72093 142595 72094 142595 71284 142596 72094 142596 71285 142596 71285 142597 72094 142597 71286 142597 71285 142598 71286 142598 72738 142598 72738 142599 71286 142599 71287 142599 72573 142600 73061 142600 71452 142600 71452 142601 73061 142601 73063 142601 71452 142602 73063 142602 71288 142602 71288 142603 73063 142603 72930 142603 71288 142604 72930 142604 71455 142604 71455 142605 72930 142605 72929 142605 71455 142606 72929 142606 71289 142606 71289 142607 72929 142607 71290 142607 71289 142608 71290 142608 71456 142608 71456 142609 71290 142609 72926 142609 71456 142610 72926 142610 71291 142610 71291 142611 72926 142611 72927 142611 71292 142612 71293 142612 71294 142612 71294 142613 71293 142613 73024 142613 71294 142614 73024 142614 71460 142614 71460 142615 73024 142615 71295 142615 71460 142616 71295 142616 71296 142616 71296 142617 71295 142617 73019 142617 71296 142618 73019 142618 71297 142618 71297 142619 73019 142619 71298 142619 71297 142620 71298 142620 71299 142620 71299 142621 71298 142621 73021 142621 71299 142622 73021 142622 71464 142622 71464 142623 73021 142623 72727 142623 71300 142624 71301 142624 71303 142624 71303 142625 71301 142625 71302 142625 71303 142626 71302 142626 71304 142626 71304 142627 71302 142627 71305 142627 71304 142628 71305 142628 71468 142628 71468 142629 71305 142629 72939 142629 71468 142630 72939 142630 71470 142630 71470 142631 72939 142631 72937 142631 71470 142632 72937 142632 71307 142632 71307 142633 72937 142633 71306 142633 71307 142634 71306 142634 72553 142634 72553 142635 71306 142635 73091 142635 72718 142636 72719 142636 71308 142636 71308 142637 72719 142637 71309 142637 71308 142638 71309 142638 71310 142638 71310 142639 71309 142639 72945 142639 71310 142640 72945 142640 71396 142640 71396 142641 72945 142641 71311 142641 71396 142642 71311 142642 71397 142642 71397 142643 71311 142643 71312 142643 71397 142644 71312 142644 71398 142644 71398 142645 71312 142645 72950 142645 71398 142646 72950 142646 72626 142646 72626 142647 72950 142647 72714 142647 72624 142648 71313 142648 71400 142648 71400 142649 71313 142649 73079 142649 71400 142650 73079 142650 71401 142650 71401 142651 73079 142651 71314 142651 71401 142652 71314 142652 71403 142652 71403 142653 71314 142653 71315 142653 71403 142654 71315 142654 71404 142654 71404 142655 71315 142655 71317 142655 71404 142656 71317 142656 71316 142656 71316 142657 71317 142657 71318 142657 71316 142658 71318 142658 71407 142658 71407 142659 71318 142659 73015 142659 71408 142660 71319 142660 71320 142660 71320 142661 71319 142661 71321 142661 71320 142662 71321 142662 71409 142662 71409 142663 71321 142663 71322 142663 71409 142664 71322 142664 71323 142664 71323 142665 71322 142665 73008 142665 71323 142666 73008 142666 71410 142666 71410 142667 73008 142667 73007 142667 71410 142668 73007 142668 71411 142668 71411 142669 73007 142669 71324 142669 71411 142670 71324 142670 72699 142670 72699 142671 71324 142671 72700 142671 72616 142672 71326 142672 71325 142672 71325 142673 71326 142673 73000 142673 71325 142674 73000 142674 71327 142674 71327 142675 73000 142675 72999 142675 71327 142676 72999 142676 71414 142676 71414 142677 72999 142677 71328 142677 71414 142678 71328 142678 71329 142678 71329 142679 71328 142679 71330 142679 71329 142680 71330 142680 71416 142680 71416 142681 71330 142681 72993 142681 71416 142682 72993 142682 71417 142682 71417 142683 72993 142683 73006 142683 71419 142684 72989 142684 71420 142684 71420 142685 72989 142685 72991 142685 71420 142686 72991 142686 71331 142686 71331 142687 72991 142687 71332 142687 71331 142688 71332 142688 71421 142688 71421 142689 71332 142689 71333 142689 71421 142690 71333 142690 71423 142690 71423 142691 71333 142691 73041 142691 71423 142692 73041 142692 71334 142692 71334 142693 73041 142693 73040 142693 71334 142694 73040 142694 72604 142694 72604 142695 73040 142695 72690 142695 71335 142696 71336 142696 71425 142696 71425 142697 71336 142697 72987 142697 71425 142698 72987 142698 71337 142698 71337 142699 72987 142699 71338 142699 71337 142700 71338 142700 71427 142700 71427 142701 71338 142701 71339 142701 71427 142702 71339 142702 71429 142702 71429 142703 71339 142703 72986 142703 71429 142704 72986 142704 71430 142704 71430 142705 72986 142705 71340 142705 71430 142706 71340 142706 71341 142706 71341 142707 71340 142707 72962 142707 71341 142708 72962 142708 72599 142708 72599 142709 72962 142709 72963 142709 72685 142710 72973 142710 71342 142710 71342 142711 72973 142711 72975 142711 71342 142712 72975 142712 71433 142712 71433 142713 72975 142713 71344 142713 71433 142714 71344 142714 71343 142714 71343 142715 71344 142715 72971 142715 71343 142716 72971 142716 71434 142716 71434 142717 72971 142717 72970 142717 71434 142718 72970 142718 71345 142718 71345 142719 72970 142719 71347 142719 71345 142720 71347 142720 71346 142720 71346 142721 71347 142721 71348 142721 72592 142722 71349 142722 71437 142722 71437 142723 71349 142723 71350 142723 71437 142724 71350 142724 71438 142724 71438 142725 71350 142725 71351 142725 71438 142726 71351 142726 71352 142726 71352 142727 71351 142727 71353 142727 71352 142728 71353 142728 71441 142728 71441 142729 71353 142729 71354 142729 71441 142730 71354 142730 71442 142730 71442 142731 71354 142731 71355 142731 71442 142732 71355 142732 71443 142732 71443 142733 71355 142733 71356 142733 72676 142734 72916 142734 71446 142734 71446 142735 72916 142735 71358 142735 71446 142736 71358 142736 71357 142736 71357 142737 71358 142737 71359 142737 71357 142738 71359 142738 71361 142738 71361 142739 71359 142739 71360 142739 71361 142740 71360 142740 71448 142740 71448 142741 71360 142741 71362 142741 71448 142742 71362 142742 71363 142742 71363 142743 71362 142743 72920 142743 71363 142744 72920 142744 72574 142744 72574 142745 72920 142745 72919 142745 72905 142746 72910 142746 71365 142746 71365 142747 72910 142747 73046 142747 71365 142748 73046 142748 71364 142748 72905 142749 71365 142749 72906 142749 72906 142750 71365 142750 71981 142750 72906 142751 71981 142751 72980 142751 72980 142752 71981 142752 71367 142752 72980 142753 71367 142753 71366 142753 71366 142754 71367 142754 71978 142754 71366 142755 71978 142755 71368 142755 71368 142756 71978 142756 71976 142756 71368 142757 71976 142757 71369 142757 71369 142758 71976 142758 71371 142758 71369 142759 71371 142759 71370 142759 71370 142760 71371 142760 71974 142760 71370 142761 71974 142761 71372 142761 71372 142762 71974 142762 71373 142762 71372 142763 71373 142763 72958 142763 72958 142764 71373 142764 71374 142764 72958 142765 71374 142765 71376 142765 71376 142766 71374 142766 71375 142766 71376 142767 71375 142767 73030 142767 73030 142768 71375 142768 71972 142768 73030 142769 71972 142769 73009 142769 73009 142770 71972 142770 71377 142770 73009 142771 71377 142771 72908 142771 72908 142772 71377 142772 71378 142772 72908 142773 71378 142773 72952 142773 72952 142774 71378 142774 71379 142774 72952 142775 71379 142775 72946 142775 72946 142776 71379 142776 71380 142776 72946 142777 71380 142777 72951 142777 72080 142778 71984 142778 71986 142778 71381 142779 72073 142779 71989 142779 71989 142780 72073 142780 72074 142780 71989 142781 72074 142781 71986 142781 71986 142782 72074 142782 71382 142782 71986 142783 71382 142783 72080 142783 71992 142784 72014 142784 71384 142784 71384 142785 72014 142785 71383 142785 71383 142786 72143 142786 71384 142786 71384 142787 72143 142787 71385 142787 71384 142788 71385 142788 71381 142788 71381 142789 71385 142789 72071 142789 71381 142790 72071 142790 72073 142790 72150 142791 71992 142791 71386 142791 72150 142792 72064 142792 71992 142792 71992 142793 72064 142793 72068 142793 71992 142794 72068 142794 72014 142794 72223 142795 72061 142795 71387 142795 71387 142796 72061 142796 72062 142796 71387 142797 72062 142797 71388 142797 71388 142798 72062 142798 71389 142798 71388 142799 71389 142799 71999 142799 71999 142800 71389 142800 71390 142800 71999 142801 71390 142801 71391 142801 71391 142802 71390 142802 72146 142802 71391 142803 72146 142803 71996 142803 71996 142804 72146 142804 72147 142804 71996 142805 72147 142805 71386 142805 71386 142806 72147 142806 72148 142806 71386 142807 72148 142807 72150 142807 72003 142808 71392 142808 72100 142808 72003 142809 72100 142809 71387 142809 71387 142810 72100 142810 72059 142810 71387 142811 72059 142811 72223 142811 71392 142812 72003 142812 71393 142812 71393 142813 72003 142813 72005 142813 71393 142814 72005 142814 72172 142814 72172 142815 72005 142815 72110 142815 72110 142816 72005 142816 72006 142816 72110 142817 72006 142817 72111 142817 72111 142818 72006 142818 72008 142818 72111 142819 72008 142819 72234 142819 72632 142820 72718 142820 71394 142820 71394 142821 72718 142821 71308 142821 71394 142822 71308 142822 71395 142822 71395 142823 71308 142823 71310 142823 71395 142824 71310 142824 71229 142824 71229 142825 71310 142825 71396 142825 71229 142826 71396 142826 71227 142826 71227 142827 71396 142827 71397 142827 71227 142828 71397 142828 71226 142828 71226 142829 71397 142829 71398 142829 71226 142830 71398 142830 71225 142830 71225 142831 71398 142831 72626 142831 71224 142832 72624 142832 71399 142832 71399 142833 72624 142833 71400 142833 71399 142834 71400 142834 71220 142834 71220 142835 71400 142835 71401 142835 71220 142836 71401 142836 71402 142836 71402 142837 71401 142837 71403 142837 71402 142838 71403 142838 71219 142838 71219 142839 71403 142839 71404 142839 71219 142840 71404 142840 71405 142840 71405 142841 71404 142841 71316 142841 71405 142842 71316 142842 71406 142842 71406 142843 71316 142843 71407 142843 72620 142844 71408 142844 71216 142844 71216 142845 71408 142845 71320 142845 71216 142846 71320 142846 71214 142846 71214 142847 71320 142847 71409 142847 71214 142848 71409 142848 71213 142848 71213 142849 71409 142849 71323 142849 71213 142850 71323 142850 71212 142850 71212 142851 71323 142851 71410 142851 71212 142852 71410 142852 71211 142852 71211 142853 71410 142853 71411 142853 71211 142854 71411 142854 71412 142854 71412 142855 71411 142855 72699 142855 72738 142856 72616 142856 71285 142856 71285 142857 72616 142857 71325 142857 71285 142858 71325 142858 71284 142858 71284 142859 71325 142859 71327 142859 71284 142860 71327 142860 71413 142860 71413 142861 71327 142861 71414 142861 71413 142862 71414 142862 71415 142862 71415 142863 71414 142863 71329 142863 71415 142864 71329 142864 71282 142864 71282 142865 71329 142865 71416 142865 71282 142866 71416 142866 72740 142866 72740 142867 71416 142867 71417 142867 71280 142868 71419 142868 71418 142868 71418 142869 71419 142869 71420 142869 71418 142870 71420 142870 71277 142870 71277 142871 71420 142871 71331 142871 71277 142872 71331 142872 71275 142872 71275 142873 71331 142873 71421 142873 71275 142874 71421 142874 71422 142874 71422 142875 71421 142875 71423 142875 71422 142876 71423 142876 71273 142876 71273 142877 71423 142877 71334 142877 71273 142878 71334 142878 71424 142878 71424 142879 71334 142879 72604 142879 72603 142880 71335 142880 71271 142880 71271 142881 71335 142881 71425 142881 71271 142882 71425 142882 71426 142882 71426 142883 71425 142883 71337 142883 71426 142884 71337 142884 71269 142884 71269 142885 71337 142885 71427 142885 71269 142886 71427 142886 71428 142886 71428 142887 71427 142887 71429 142887 71428 142888 71429 142888 71267 142888 71267 142889 71429 142889 71430 142889 71267 142890 71430 142890 71431 142890 71431 142891 71430 142891 71341 142891 71431 142892 71341 142892 71432 142892 71432 142893 71341 142893 72599 142893 71266 142894 72685 142894 71264 142894 71264 142895 72685 142895 71342 142895 71264 142896 71342 142896 71263 142896 71263 142897 71342 142897 71433 142897 71263 142898 71433 142898 71262 142898 71262 142899 71433 142899 71343 142899 71262 142900 71343 142900 71260 142900 71260 142901 71343 142901 71434 142901 71260 142902 71434 142902 71435 142902 71435 142903 71434 142903 71345 142903 71435 142904 71345 142904 72593 142904 72593 142905 71345 142905 71346 142905 72762 142906 72592 142906 71436 142906 71436 142907 72592 142907 71437 142907 71436 142908 71437 142908 71256 142908 71256 142909 71437 142909 71438 142909 71256 142910 71438 142910 71439 142910 71439 142911 71438 142911 71352 142911 71439 142912 71352 142912 71440 142912 71440 142913 71352 142913 71441 142913 71440 142914 71441 142914 71253 142914 71253 142915 71441 142915 71442 142915 71253 142916 71442 142916 72585 142916 72585 142917 71442 142917 71443 142917 71444 142918 72676 142918 71251 142918 71251 142919 72676 142919 71446 142919 71251 142920 71446 142920 71445 142920 71445 142921 71446 142921 71357 142921 71445 142922 71357 142922 71247 142922 71247 142923 71357 142923 71361 142923 71247 142924 71361 142924 71447 142924 71447 142925 71361 142925 71448 142925 71447 142926 71448 142926 71449 142926 71449 142927 71448 142927 71363 142927 71449 142928 71363 142928 71450 142928 71450 142929 71363 142929 72574 142929 72572 142930 72573 142930 71451 142930 71451 142931 72573 142931 71452 142931 71451 142932 71452 142932 71453 142932 71453 142933 71452 142933 71288 142933 71453 142934 71288 142934 71454 142934 71454 142935 71288 142935 71455 142935 71454 142936 71455 142936 71243 142936 71243 142937 71455 142937 71289 142937 71243 142938 71289 142938 71242 142938 71242 142939 71289 142939 71456 142939 71242 142940 71456 142940 72778 142940 72778 142941 71456 142941 71291 142941 71457 142942 71292 142942 71458 142942 71458 142943 71292 142943 71294 142943 71458 142944 71294 142944 71459 142944 71459 142945 71294 142945 71460 142945 71459 142946 71460 142946 71461 142946 71461 142947 71460 142947 71296 142947 71461 142948 71296 142948 71462 142948 71462 142949 71296 142949 71297 142949 71462 142950 71297 142950 71463 142950 71463 142951 71297 142951 71299 142951 71463 142952 71299 142952 72560 142952 72560 142953 71299 142953 71464 142953 71465 142954 71300 142954 71466 142954 71466 142955 71300 142955 71303 142955 71466 142956 71303 142956 71467 142956 71467 142957 71303 142957 71304 142957 71467 142958 71304 142958 71237 142958 71237 142959 71304 142959 71468 142959 71237 142960 71468 142960 71235 142960 71235 142961 71468 142961 71470 142961 71235 142962 71470 142962 71469 142962 71469 142963 71470 142963 71307 142963 71469 142964 71307 142964 72552 142964 72552 142965 71307 142965 72553 142965 73083 142966 72547 142966 73086 142966 73086 142967 72547 142967 71482 142967 73086 142968 71482 142968 72948 142968 72948 142969 71482 142969 71471 142969 72948 142970 71471 142970 71472 142970 71472 142971 71471 142971 71481 142971 71472 142972 71481 142972 71473 142972 71473 142973 71481 142973 71479 142973 71473 142974 71479 142974 71475 142974 71475 142975 71479 142975 71474 142975 71475 142976 71474 142976 71477 142976 71477 142977 71474 142977 71476 142977 71477 142978 71476 142978 73077 142978 72072 142979 71476 142979 72075 142979 72075 142980 71476 142980 71474 142980 72075 142981 71474 142981 72076 142981 72076 142982 71474 142982 71479 142982 72076 142983 71479 142983 71478 142983 71478 142984 71479 142984 71481 142984 71478 142985 71481 142985 71480 142985 71480 142986 71481 142986 71471 142986 71480 142987 71471 142987 71483 142987 71483 142988 71471 142988 71482 142988 71483 142989 71482 142989 71484 142989 71484 142990 71482 142990 72547 142990 71490 142991 73028 142991 71491 142991 71491 142992 73028 142992 71485 142992 71491 142993 71485 142993 71493 142993 71493 142994 71485 142994 73014 142994 71493 142995 73014 142995 71494 142995 71494 142996 73014 142996 71486 142996 71494 142997 71486 142997 71496 142997 71496 142998 71486 142998 71487 142998 71496 142999 71487 142999 71498 142999 71498 143000 71487 143000 73035 143000 71498 143001 73035 143001 72530 143001 72530 143002 73035 143002 71488 143002 71489 143003 71490 143003 72219 143003 72219 143004 71490 143004 71491 143004 72219 143005 71491 143005 71492 143005 71492 143006 71491 143006 71493 143006 71492 143007 71493 143007 72203 143007 72203 143008 71493 143008 71494 143008 72203 143009 71494 143009 71495 143009 71495 143010 71494 143010 71496 143010 71495 143011 71496 143011 71497 143011 71497 143012 71496 143012 71498 143012 71497 143013 71498 143013 71499 143013 71499 143014 71498 143014 72530 143014 72522 143015 72996 143015 71500 143015 71500 143016 72996 143016 72995 143016 71500 143017 72995 143017 71501 143017 71501 143018 72995 143018 72994 143018 71501 143019 72994 143019 71505 143019 71505 143020 72994 143020 72998 143020 71505 143021 72998 143021 71507 143021 71507 143022 72998 143022 71503 143022 71507 143023 71503 143023 71502 143023 71502 143024 71503 143024 73001 143024 71502 143025 73001 143025 71508 143025 71508 143026 73001 143026 72523 143026 72152 143027 72522 143027 72091 143027 72091 143028 72522 143028 71500 143028 72091 143029 71500 143029 71504 143029 71504 143030 71500 143030 71501 143030 71504 143031 71501 143031 72092 143031 72092 143032 71501 143032 71505 143032 72092 143033 71505 143033 71506 143033 71506 143034 71505 143034 71507 143034 71506 143035 71507 143035 72095 143035 72095 143036 71507 143036 71502 143036 72095 143037 71502 143037 72517 143037 72517 143038 71502 143038 71508 143038 71516 143039 71509 143039 71510 143039 71510 143040 71509 143040 73043 143040 71510 143041 73043 143041 71518 143041 71518 143042 73043 143042 73095 143042 71518 143043 73095 143043 71511 143043 71511 143044 73095 143044 71512 143044 71511 143045 71512 143045 71520 143045 71520 143046 71512 143046 72985 143046 71520 143047 72985 143047 71513 143047 71513 143048 72985 143048 72984 143048 71513 143049 72984 143049 71514 143049 71514 143050 72984 143050 72516 143050 71515 143051 71516 143051 71517 143051 71517 143052 71516 143052 71510 143052 71517 143053 71510 143053 72166 143053 72166 143054 71510 143054 71518 143054 72166 143055 71518 143055 72168 143055 72168 143056 71518 143056 71511 143056 72168 143057 71511 143057 71519 143057 71519 143058 71511 143058 71520 143058 71519 143059 71520 143059 72169 143059 72169 143060 71520 143060 71513 143060 72169 143061 71513 143061 72165 143061 72165 143062 71513 143062 71514 143062 71525 143063 73053 143063 71526 143063 71526 143064 73053 143064 73054 143064 71526 143065 73054 143065 71527 143065 71527 143066 73054 143066 71521 143066 71527 143067 71521 143067 71530 143067 71530 143068 71521 143068 71522 143068 71530 143069 71522 143069 71523 143069 71523 143070 71522 143070 73049 143070 71523 143071 73049 143071 71531 143071 71531 143072 73049 143072 73051 143072 71531 143073 73051 143073 71533 143073 71533 143074 73051 143074 72493 143074 72492 143075 71525 143075 71524 143075 71524 143076 71525 143076 71526 143076 71524 143077 71526 143077 71528 143077 71528 143078 71526 143078 71527 143078 71528 143079 71527 143079 71529 143079 71529 143080 71527 143080 71530 143080 71529 143081 71530 143081 72228 143081 72228 143082 71530 143082 71523 143082 72228 143083 71523 143083 72229 143083 72229 143084 71523 143084 71531 143084 72229 143085 71531 143085 71532 143085 71532 143086 71531 143086 71533 143086 72486 143087 73076 143087 71540 143087 71540 143088 73076 143088 71534 143088 71540 143089 71534 143089 71541 143089 71541 143090 71534 143090 71535 143090 71541 143091 71535 143091 71543 143091 71543 143092 71535 143092 71537 143092 71543 143093 71537 143093 71536 143093 71536 143094 71537 143094 73073 143094 71536 143095 73073 143095 71547 143095 71547 143096 73073 143096 73071 143096 71547 143097 73071 143097 71538 143097 71538 143098 73071 143098 73070 143098 72179 143099 72486 143099 71539 143099 71539 143100 72486 143100 71540 143100 71539 143101 71540 143101 71542 143101 71542 143102 71540 143102 71541 143102 71542 143103 71541 143103 71544 143103 71544 143104 71541 143104 71543 143104 71544 143105 71543 143105 71545 143105 71545 143106 71543 143106 71536 143106 71545 143107 71536 143107 71546 143107 71546 143108 71536 143108 71547 143108 71546 143109 71547 143109 72183 143109 72183 143110 71547 143110 71538 143110 72474 143111 71548 143111 71549 143111 71549 143112 71548 143112 71550 143112 71549 143113 71550 143113 71551 143113 71551 143114 71550 143114 71552 143114 71551 143115 71552 143115 71557 143115 71557 143116 71552 143116 71553 143116 71557 143117 71553 143117 71559 143117 71559 143118 71553 143118 71554 143118 71559 143119 71554 143119 71560 143119 71560 143120 71554 143120 71555 143120 71560 143121 71555 143121 71562 143121 71562 143122 71555 143122 72913 143122 72049 143123 72474 143123 72050 143123 72050 143124 72474 143124 71549 143124 72050 143125 71549 143125 71556 143125 71556 143126 71549 143126 71551 143126 71556 143127 71551 143127 72052 143127 72052 143128 71551 143128 71557 143128 72052 143129 71557 143129 71558 143129 71558 143130 71557 143130 71559 143130 71558 143131 71559 143131 72051 143131 72051 143132 71559 143132 71560 143132 72051 143133 71560 143133 71561 143133 71561 143134 71560 143134 71562 143134 72460 143135 73068 143135 71568 143135 71568 143136 73068 143136 73066 143136 71568 143137 73066 143137 71569 143137 71569 143138 73066 143138 73065 143138 71569 143139 73065 143139 71571 143139 71571 143140 73065 143140 71563 143140 71571 143141 71563 143141 71564 143141 71564 143142 71563 143142 73062 143142 71564 143143 73062 143143 71572 143143 71572 143144 73062 143144 71565 143144 71572 143145 71565 143145 71566 143145 71566 143146 71565 143146 73060 143146 72189 143147 72460 143147 71567 143147 71567 143148 72460 143148 71568 143148 71567 143149 71568 143149 72191 143149 72191 143150 71568 143150 71569 143150 72191 143151 71569 143151 71570 143151 71570 143152 71569 143152 71571 143152 71570 143153 71571 143153 72188 143153 72188 143154 71571 143154 71564 143154 72188 143155 71564 143155 72187 143155 72187 143156 71564 143156 71572 143156 72187 143157 71572 143157 71573 143157 71573 143158 71572 143158 71566 143158 71582 143159 72941 143159 71584 143159 71584 143160 72941 143160 72942 143160 71584 143161 72942 143161 71574 143161 71574 143162 72942 143162 71575 143162 71574 143163 71575 143163 71585 143163 71585 143164 71575 143164 71576 143164 71585 143165 71576 143165 71578 143165 71578 143166 71576 143166 71577 143166 71578 143167 71577 143167 71589 143167 71589 143168 71577 143168 73025 143168 71589 143169 73025 143169 71579 143169 71579 143170 73025 143170 71580 143170 71579 143171 71580 143171 72449 143171 72449 143172 71580 143172 72451 143172 71581 143173 71582 143173 71583 143173 71583 143174 71582 143174 71584 143174 71583 143175 71584 143175 72201 143175 72201 143176 71584 143176 71574 143176 72201 143177 71574 143177 71586 143177 71586 143178 71574 143178 71585 143178 71586 143179 71585 143179 71587 143179 71587 143180 71585 143180 71578 143180 71587 143181 71578 143181 71588 143181 71588 143182 71578 143182 71589 143182 71588 143183 71589 143183 72197 143183 72197 143184 71589 143184 71579 143184 72197 143185 71579 143185 72200 143185 72200 143186 71579 143186 72449 143186 71601 143187 71995 143187 71590 143187 72440 143188 71591 143188 72442 143188 72442 143189 71591 143189 71985 143189 71620 143190 71592 143190 71988 143190 71988 143191 71987 143191 71620 143191 71620 143192 71987 143192 71593 143192 71620 143193 71593 143193 71591 143193 71591 143194 71593 143194 71594 143194 71591 143195 71594 143195 71985 143195 71596 143196 71599 143196 71595 143196 71595 143197 71597 143197 71596 143197 71596 143198 71597 143198 71991 143198 71596 143199 71991 143199 71592 143199 71592 143200 71991 143200 71990 143200 71592 143201 71990 143201 71988 143201 71590 143202 71995 143202 71598 143202 71995 143203 71994 143203 71598 143203 71598 143204 71994 143204 71993 143204 71598 143205 71993 143205 71599 143205 71599 143206 71993 143206 71600 143206 71599 143207 71600 143207 71595 143207 71601 143208 71590 143208 71602 143208 71602 143209 71590 143209 71603 143209 71602 143210 71603 143210 71997 143210 71997 143211 71603 143211 71625 143211 71997 143212 71625 143212 71998 143212 71998 143213 71625 143213 71604 143213 71604 143214 71625 143214 71626 143214 71604 143215 71626 143215 72000 143215 72000 143216 71626 143216 71606 143216 71606 143217 71626 143217 71605 143217 71606 143218 71605 143218 71607 143218 71607 143219 71605 143219 72001 143219 72001 143220 71605 143220 71628 143220 72001 143221 71628 143221 72002 143221 72002 143222 71628 143222 72004 143222 72004 143223 71628 143223 71631 143223 72004 143224 71631 143224 71608 143224 71608 143225 71631 143225 71609 143225 71609 143226 71631 143226 71632 143226 71609 143227 71632 143227 72009 143227 72009 143228 71632 143228 71610 143228 71610 143229 71632 143229 71633 143229 71610 143230 71633 143230 71611 143230 71611 143231 71633 143231 71612 143231 71611 143232 71612 143232 72007 143232 72424 143233 71613 143233 72426 143233 72426 143234 71613 143234 71614 143234 72426 143235 71614 143235 72430 143235 72430 143236 71614 143236 71615 143236 72430 143237 71615 143237 72432 143237 72432 143238 71615 143238 71645 143238 72432 143239 71645 143239 72433 143239 72433 143240 71645 143240 71643 143240 72433 143241 71643 143241 72436 143241 72436 143242 71643 143242 71616 143242 72436 143243 71616 143243 71617 143243 71617 143244 71616 143244 71618 143244 71617 143245 71618 143245 72439 143245 72439 143246 71618 143246 71641 143246 72439 143247 71641 143247 72440 143247 72440 143248 71641 143248 71619 143248 72440 143249 71619 143249 71591 143249 71591 143250 71619 143250 72413 143250 71591 143251 72413 143251 71620 143251 71620 143252 72413 143252 71621 143252 71620 143253 71621 143253 71592 143253 71592 143254 71621 143254 72410 143254 71592 143255 72410 143255 71596 143255 71596 143256 72410 143256 72408 143256 71596 143257 72408 143257 71599 143257 71599 143258 72408 143258 71622 143258 71599 143259 71622 143259 71598 143259 71598 143260 71622 143260 71623 143260 71598 143261 71623 143261 71590 143261 71590 143262 71623 143262 72406 143262 71590 143263 72406 143263 71603 143263 72406 143264 72405 143264 71603 143264 71603 143265 72405 143265 71624 143265 71603 143266 71624 143266 71625 143266 71625 143267 71624 143267 72404 143267 71625 143268 72404 143268 71626 143268 71626 143269 72404 143269 71627 143269 71626 143270 71627 143270 71605 143270 71605 143271 71627 143271 71629 143271 71605 143272 71629 143272 71628 143272 71628 143273 71629 143273 71630 143273 71628 143274 71630 143274 71631 143274 71631 143275 71630 143275 72400 143275 71631 143276 72400 143276 71632 143276 71632 143277 72400 143277 72398 143277 71632 143278 72398 143278 71633 143278 71633 143279 72398 143279 71634 143279 71633 143280 71634 143280 71612 143280 71612 143281 71634 143281 72396 143281 71612 143282 72396 143282 72414 143282 72414 143283 72396 143283 71653 143283 72414 143284 71653 143284 72416 143284 72416 143285 71653 143285 71635 143285 72416 143286 71635 143286 72422 143286 72422 143287 71635 143287 71652 143287 72422 143288 71652 143288 72421 143288 72421 143289 71652 143289 71651 143289 72421 143290 71651 143290 72423 143290 72423 143291 71651 143291 71650 143291 72423 143292 71650 143292 71636 143292 71636 143293 71650 143293 71637 143293 71636 143294 71637 143294 71638 143294 71638 143295 71637 143295 71649 143295 71638 143296 71649 143296 72424 143296 72424 143297 71649 143297 71639 143297 72424 143298 71639 143298 71613 143298 72817 143299 71619 143299 71640 143299 71640 143300 71619 143300 71641 143300 71640 143301 71641 143301 71192 143301 71192 143302 71641 143302 71618 143302 71192 143303 71618 143303 71190 143303 71190 143304 71618 143304 71616 143304 71190 143305 71616 143305 71642 143305 71642 143306 71616 143306 71643 143306 71642 143307 71643 143307 71644 143307 71644 143308 71643 143308 71645 143308 71644 143309 71645 143309 71188 143309 71188 143310 71645 143310 71615 143310 71188 143311 71615 143311 71186 143311 71186 143312 71615 143312 71614 143312 71186 143313 71614 143313 71646 143313 71646 143314 71614 143314 71613 143314 71646 143315 71613 143315 71185 143315 71185 143316 71613 143316 71639 143316 71185 143317 71639 143317 71647 143317 71647 143318 71639 143318 71649 143318 71647 143319 71649 143319 71648 143319 71648 143320 71649 143320 71637 143320 71648 143321 71637 143321 71184 143321 71184 143322 71637 143322 71650 143322 71184 143323 71650 143323 71183 143323 71183 143324 71650 143324 71651 143324 71183 143325 71651 143325 71182 143325 71182 143326 71651 143326 71652 143326 71182 143327 71652 143327 71181 143327 71181 143328 71652 143328 71635 143328 71181 143329 71635 143329 71179 143329 71179 143330 71635 143330 71653 143330 71179 143331 71653 143331 72395 143331 72395 143332 71653 143332 72396 143332 71187 143333 71654 143333 71655 143333 71655 143334 71654 143334 71657 143334 71655 143335 71657 143335 71656 143335 71656 143336 71657 143336 72843 143336 71656 143337 72843 143337 71658 143337 71658 143338 72843 143338 72846 143338 71658 143339 72846 143339 71189 143339 71189 143340 72846 143340 72847 143340 71189 143341 72847 143341 71191 143341 71191 143342 72847 143342 71659 143342 71191 143343 71659 143343 71660 143343 71660 143344 71659 143344 72850 143344 71660 143345 72850 143345 71661 143345 71661 143346 72850 143346 72851 143346 71661 143347 72851 143347 71193 143347 71193 143348 72851 143348 71662 143348 71193 143349 71662 143349 72818 143349 72818 143350 71662 143350 71663 143350 72818 143351 71663 143351 71664 143351 71664 143352 71663 143352 71167 143352 71664 143353 71167 143353 72819 143353 72819 143354 71167 143354 71665 143354 72819 143355 71665 143355 71666 143355 71666 143356 71665 143356 71667 143356 71666 143357 71667 143357 71668 143357 71668 143358 71667 143358 71669 143358 71668 143359 71669 143359 71670 143359 71670 143360 71669 143360 71672 143360 71670 143361 71672 143361 71671 143361 71671 143362 71672 143362 71673 143362 71671 143363 71673 143363 72824 143363 72824 143364 71673 143364 71674 143364 72824 143365 71674 143365 71675 143365 71675 143366 71674 143366 71676 143366 71675 143367 71676 143367 71677 143367 71677 143368 71676 143368 71678 143368 71677 143369 71678 143369 72826 143369 72826 143370 71678 143370 71173 143370 72826 143371 71173 143371 72828 143371 72828 143372 71173 143372 71174 143372 72828 143373 71174 143373 71679 143373 71679 143374 71174 143374 71680 143374 71679 143375 71680 143375 71682 143375 71682 143376 71680 143376 71681 143376 71682 143377 71681 143377 71683 143377 71683 143378 71681 143378 71684 143378 71683 143379 71684 143379 71685 143379 71685 143380 71684 143380 71176 143380 71685 143381 71176 143381 71686 143381 71686 143382 71176 143382 71178 143382 71686 143383 71178 143383 71180 143383 71180 143384 71178 143384 71687 143384 71180 143385 71687 143385 71689 143385 71689 143386 71687 143386 71688 143386 71689 143387 71688 143387 71690 143387 71690 143388 71688 143388 71692 143388 71690 143389 71692 143389 71691 143389 71691 143390 71692 143390 71693 143390 71691 143391 71693 143391 71694 143391 71694 143392 71693 143392 71695 143392 71694 143393 71695 143393 71696 143393 71696 143394 71695 143394 72836 143394 71696 143395 72836 143395 71697 143395 71697 143396 72836 143396 72837 143396 71697 143397 72837 143397 71698 143397 71698 143398 72837 143398 72840 143398 71698 143399 72840 143399 71187 143399 71187 143400 72840 143400 71654 143400 72394 143401 71725 143401 71699 143401 72394 143402 71699 143402 71166 143402 71166 143403 71699 143403 71727 143403 71166 143404 71727 143404 71700 143404 71700 143405 71727 143405 71701 143405 71700 143406 71701 143406 71702 143406 71702 143407 71701 143407 71728 143407 71702 143408 71728 143408 71168 143408 71168 143409 71728 143409 71703 143409 71168 143410 71703 143410 71705 143410 71705 143411 71703 143411 71704 143411 71705 143412 71704 143412 71169 143412 71169 143413 71704 143413 71731 143413 71169 143414 71731 143414 71170 143414 71170 143415 71731 143415 71733 143415 71170 143416 71733 143416 71171 143416 71171 143417 71733 143417 71734 143417 71171 143418 71734 143418 71706 143418 71706 143419 71734 143419 71735 143419 71706 143420 71735 143420 71707 143420 71707 143421 71735 143421 71736 143421 71707 143422 71736 143422 71172 143422 71172 143423 71736 143423 71708 143423 71172 143424 71708 143424 71709 143424 71709 143425 71708 143425 71710 143425 71709 143426 71710 143426 71175 143426 71175 143427 71710 143427 71711 143427 71175 143428 71711 143428 71712 143428 71712 143429 71711 143429 71713 143429 71712 143430 71713 143430 71714 143430 71714 143431 71713 143431 71715 143431 71714 143432 71715 143432 71177 143432 71177 143433 71715 143433 72379 143433 71177 143434 72379 143434 72830 143434 72382 143435 71757 143435 72383 143435 72383 143436 71757 143436 71716 143436 72383 143437 71716 143437 72384 143437 72384 143438 71716 143438 71756 143438 72384 143439 71756 143439 72386 143439 72386 143440 71756 143440 71755 143440 72386 143441 71755 143441 71718 143441 71718 143442 71755 143442 71717 143442 71718 143443 71717 143443 71719 143443 71719 143444 71717 143444 71753 143444 71719 143445 71753 143445 72387 143445 72387 143446 71753 143446 71750 143446 72387 143447 71750 143447 72388 143447 72388 143448 71750 143448 71749 143448 72388 143449 71749 143449 72389 143449 72389 143450 71749 143450 71748 143450 72389 143451 71748 143451 71720 143451 71720 143452 71748 143452 71721 143452 71720 143453 71721 143453 72390 143453 72390 143454 71721 143454 71746 143454 72390 143455 71746 143455 71722 143455 71722 143456 71746 143456 71723 143456 71722 143457 71723 143457 72392 143457 72392 143458 71723 143458 71744 143458 72392 143459 71744 143459 71724 143459 71724 143460 71744 143460 71741 143460 71724 143461 71741 143461 71725 143461 71725 143462 71741 143462 72378 143462 71725 143463 72378 143463 71699 143463 71699 143464 72378 143464 71726 143464 71699 143465 71726 143465 71727 143465 71727 143466 71726 143466 72377 143466 71727 143467 72377 143467 71701 143467 71701 143468 72377 143468 72375 143468 71701 143469 72375 143469 71728 143469 71728 143470 72375 143470 71729 143470 71728 143471 71729 143471 71703 143471 71703 143472 71729 143472 71730 143472 71703 143473 71730 143473 71704 143473 71704 143474 71730 143474 72373 143474 71704 143475 72373 143475 71731 143475 71731 143476 72373 143476 72371 143476 71731 143477 72371 143477 71733 143477 71733 143478 72371 143478 71732 143478 71733 143479 71732 143479 71734 143479 71734 143480 71732 143480 72368 143480 71734 143481 72368 143481 71735 143481 71735 143482 72368 143482 72367 143482 71735 143483 72367 143483 71736 143483 71736 143484 72367 143484 72365 143484 71736 143485 72365 143485 71708 143485 71708 143486 72365 143486 72364 143486 71708 143487 72364 143487 71710 143487 71710 143488 72364 143488 72363 143488 71710 143489 72363 143489 71711 143489 71711 143490 72363 143490 71737 143490 71711 143491 71737 143491 71713 143491 71713 143492 71737 143492 72361 143492 71713 143493 72361 143493 71715 143493 71715 143494 72361 143494 71738 143494 71715 143495 71738 143495 72379 143495 72379 143496 71738 143496 71760 143496 72379 143497 71760 143497 72380 143497 72380 143498 71760 143498 71739 143498 72380 143499 71739 143499 72381 143499 72381 143500 71739 143500 71740 143500 72381 143501 71740 143501 72382 143501 72382 143502 71740 143502 71757 143502 72886 143503 72378 143503 71742 143503 71742 143504 72378 143504 71741 143504 71742 143505 71741 143505 71743 143505 71743 143506 71741 143506 71744 143506 71743 143507 71744 143507 71745 143507 71745 143508 71744 143508 71723 143508 71745 143509 71723 143509 71137 143509 71137 143510 71723 143510 71746 143510 71137 143511 71746 143511 71136 143511 71136 143512 71746 143512 71721 143512 71136 143513 71721 143513 71747 143513 71747 143514 71721 143514 71748 143514 71747 143515 71748 143515 71134 143515 71134 143516 71748 143516 71749 143516 71134 143517 71749 143517 71751 143517 71751 143518 71749 143518 71750 143518 71751 143519 71750 143519 71752 143519 71752 143520 71750 143520 71753 143520 71752 143521 71753 143521 71131 143521 71131 143522 71753 143522 71717 143522 71131 143523 71717 143523 71754 143523 71754 143524 71717 143524 71755 143524 71754 143525 71755 143525 71128 143525 71128 143526 71755 143526 71756 143526 71128 143527 71756 143527 71125 143527 71125 143528 71756 143528 71716 143528 71125 143529 71716 143529 71124 143529 71124 143530 71716 143530 71757 143530 71124 143531 71757 143531 71758 143531 71758 143532 71757 143532 71740 143532 71758 143533 71740 143533 71122 143533 71122 143534 71740 143534 71739 143534 71122 143535 71739 143535 71759 143535 71759 143536 71739 143536 71760 143536 71795 143537 71761 143537 71762 143537 71762 143538 71761 143538 71763 143538 71762 143539 71763 143539 71126 143539 71126 143540 71763 143540 71811 143540 71126 143541 71811 143541 71127 143541 71127 143542 71811 143542 71764 143542 71127 143543 71764 143543 71129 143543 71129 143544 71764 143544 71765 143544 71129 143545 71765 143545 71130 143545 71130 143546 71765 143546 71808 143546 71130 143547 71808 143547 71766 143547 71766 143548 71808 143548 71767 143548 71766 143549 71767 143549 71132 143549 71132 143550 71767 143550 71805 143550 71132 143551 71805 143551 71133 143551 71133 143552 71805 143552 71768 143552 71133 143553 71768 143553 71769 143553 71769 143554 71768 143554 71770 143554 71769 143555 71770 143555 71771 143555 71771 143556 71770 143556 71803 143556 71771 143557 71803 143557 71135 143557 71135 143558 71803 143558 71801 143558 71135 143559 71801 143559 71772 143559 71772 143560 71801 143560 71800 143560 71772 143561 71800 143561 71773 143561 71773 143562 71800 143562 71799 143562 71773 143563 71799 143563 71138 143563 71138 143564 71799 143564 71796 143564 71138 143565 71796 143565 71139 143565 71139 143566 71796 143566 71774 143566 71139 143567 71774 143567 72888 143567 72888 143568 71774 143568 71775 143568 72888 143569 71775 143569 71776 143569 71776 143570 71775 143570 71777 143570 71776 143571 71777 143571 72889 143571 72889 143572 71777 143572 71778 143572 72889 143573 71778 143573 72891 143573 72891 143574 71778 143574 72357 143574 72891 143575 72357 143575 71779 143575 71779 143576 72357 143576 71781 143576 71779 143577 71781 143577 71780 143577 71780 143578 71781 143578 72355 143578 71780 143579 72355 143579 71782 143579 71782 143580 72355 143580 71783 143580 71782 143581 71783 143581 72893 143581 72893 143582 71783 143582 71784 143582 72893 143583 71784 143583 72894 143583 72894 143584 71784 143584 71785 143584 72894 143585 71785 143585 72896 143585 72896 143586 71785 143586 72353 143586 72896 143587 72353 143587 71786 143587 71786 143588 72353 143588 71787 143588 71786 143589 71787 143589 71788 143589 71788 143590 71787 143590 72351 143590 71788 143591 72351 143591 71789 143591 71789 143592 72351 143592 72348 143592 71789 143593 72348 143593 71790 143593 71790 143594 72348 143594 72346 143594 71790 143595 72346 143595 71791 143595 71791 143596 72346 143596 71792 143596 71791 143597 71792 143597 72901 143597 72901 143598 71792 143598 72344 143598 72901 143599 72344 143599 72903 143599 72903 143600 72344 143600 71793 143600 72903 143601 71793 143601 71123 143601 71123 143602 71793 143602 71794 143602 71123 143603 71794 143603 71795 143603 71795 143604 71794 143604 71761 143604 72360 143605 71775 143605 71153 143605 71153 143606 71775 143606 71774 143606 71153 143607 71774 143607 71797 143607 71797 143608 71774 143608 71796 143608 71797 143609 71796 143609 71151 143609 71151 143610 71796 143610 71799 143610 71151 143611 71799 143611 71798 143611 71798 143612 71799 143612 71800 143612 71798 143613 71800 143613 71150 143613 71150 143614 71800 143614 71801 143614 71150 143615 71801 143615 71802 143615 71802 143616 71801 143616 71803 143616 71802 143617 71803 143617 71148 143617 71148 143618 71803 143618 71770 143618 71148 143619 71770 143619 71147 143619 71147 143620 71770 143620 71768 143620 71147 143621 71768 143621 71804 143621 71804 143622 71768 143622 71805 143622 71804 143623 71805 143623 71806 143623 71806 143624 71805 143624 71767 143624 71806 143625 71767 143625 71807 143625 71807 143626 71767 143626 71808 143626 71807 143627 71808 143627 71143 143627 71143 143628 71808 143628 71765 143628 71143 143629 71765 143629 71809 143629 71809 143630 71765 143630 71764 143630 71809 143631 71764 143631 71810 143631 71810 143632 71764 143632 71811 143632 71810 143633 71811 143633 71141 143633 71141 143634 71811 143634 71763 143634 71141 143635 71763 143635 71812 143635 71812 143636 71763 143636 71761 143636 71812 143637 71761 143637 71140 143637 71140 143638 71761 143638 71794 143638 71849 143639 71813 143639 71814 143639 71814 143640 71813 143640 71815 143640 71814 143641 71815 143641 71816 143641 71816 143642 71815 143642 71817 143642 71816 143643 71817 143643 72877 143643 72877 143644 71817 143644 71158 143644 72877 143645 71158 143645 72878 143645 72878 143646 71158 143646 71160 143646 72878 143647 71160 143647 72880 143647 72880 143648 71160 143648 71818 143648 72880 143649 71818 143649 71820 143649 71820 143650 71818 143650 71819 143650 71820 143651 71819 143651 71821 143651 71821 143652 71819 143652 71162 143652 71821 143653 71162 143653 72881 143653 72881 143654 71162 143654 71822 143654 72881 143655 71822 143655 72882 143655 72882 143656 71822 143656 71823 143656 72882 143657 71823 143657 72884 143657 72884 143658 71823 143658 71164 143658 72884 143659 71164 143659 71824 143659 71824 143660 71164 143660 71165 143660 71824 143661 71165 143661 71825 143661 71825 143662 71165 143662 71826 143662 71825 143663 71826 143663 72885 143663 72885 143664 71826 143664 71828 143664 72885 143665 71828 143665 71827 143665 71827 143666 71828 143666 71829 143666 71827 143667 71829 143667 71830 143667 71830 143668 71829 143668 72853 143668 71830 143669 72853 143669 71831 143669 71831 143670 72853 143670 72854 143670 71831 143671 72854 143671 71832 143671 72854 143672 72855 143672 71832 143672 71832 143673 72855 143673 72857 143673 71832 143674 72857 143674 71142 143674 71142 143675 72857 143675 72858 143675 71142 143676 72858 143676 71144 143676 71144 143677 72858 143677 71833 143677 71144 143678 71833 143678 71145 143678 71145 143679 71833 143679 72860 143679 71145 143680 72860 143680 71834 143680 71834 143681 72860 143681 72862 143681 71834 143682 72862 143682 71146 143682 71146 143683 72862 143683 71835 143683 71146 143684 71835 143684 71836 143684 71836 143685 71835 143685 72864 143685 71836 143686 72864 143686 71149 143686 71149 143687 72864 143687 71837 143687 71149 143688 71837 143688 71838 143688 71838 143689 71837 143689 72865 143689 71838 143690 72865 143690 71839 143690 71839 143691 72865 143691 71840 143691 71839 143692 71840 143692 71841 143692 71841 143693 71840 143693 72866 143693 71841 143694 72866 143694 71842 143694 71842 143695 72866 143695 72868 143695 71842 143696 72868 143696 71152 143696 71152 143697 72868 143697 71843 143697 71152 143698 71843 143698 71844 143698 71844 143699 71843 143699 72871 143699 71844 143700 72871 143700 71845 143700 71845 143701 72871 143701 72873 143701 71845 143702 72873 143702 71846 143702 71846 143703 72873 143703 71848 143703 71846 143704 71848 143704 71847 143704 71847 143705 71848 143705 71850 143705 71847 143706 71850 143706 71849 143706 71849 143707 71850 143707 71156 143707 71849 143708 71156 143708 71813 143708 72872 143709 72341 143709 71875 143709 72872 143710 71875 143710 71154 143710 71154 143711 71875 143711 71877 143711 71154 143712 71877 143712 71155 143712 71155 143713 71877 143713 71878 143713 71155 143714 71878 143714 71157 143714 71157 143715 71878 143715 71852 143715 71157 143716 71852 143716 71851 143716 71851 143717 71852 143717 71880 143717 71851 143718 71880 143718 71853 143718 71853 143719 71880 143719 71882 143719 71853 143720 71882 143720 71854 143720 71854 143721 71882 143721 71884 143721 71854 143722 71884 143722 71159 143722 71159 143723 71884 143723 71885 143723 71159 143724 71885 143724 71855 143724 71855 143725 71885 143725 71886 143725 71855 143726 71886 143726 71856 143726 71856 143727 71886 143727 71888 143727 71856 143728 71888 143728 71161 143728 71161 143729 71888 143729 71890 143729 71161 143730 71890 143730 71857 143730 71857 143731 71890 143731 71858 143731 71857 143732 71858 143732 71163 143732 71163 143733 71858 143733 71859 143733 71163 143734 71859 143734 71860 143734 71860 143735 71859 143735 71861 143735 71860 143736 71861 143736 71862 143736 71862 143737 71861 143737 71863 143737 71862 143738 71863 143738 71864 143738 71864 143739 71863 143739 71894 143739 71864 143740 71894 143740 71865 143740 71865 143741 71894 143741 71895 143741 71865 143742 71895 143742 71866 143742 71866 143743 71895 143743 71897 143743 71866 143744 71897 143744 72320 143744 72329 143745 71867 143745 71868 143745 71868 143746 71867 143746 72807 143746 71868 143747 72807 143747 72332 143747 72332 143748 72807 143748 71869 143748 72332 143749 71869 143749 71870 143749 71870 143750 71869 143750 71871 143750 71870 143751 71871 143751 72334 143751 72334 143752 71871 143752 72809 143752 72334 143753 72809 143753 72337 143753 72337 143754 72809 143754 72810 143754 72337 143755 72810 143755 72339 143755 72339 143756 72810 143756 71872 143756 72339 143757 71872 143757 71873 143757 71873 143758 71872 143758 72812 143758 71873 143759 72812 143759 72340 143759 72340 143760 72812 143760 72813 143760 72340 143761 72813 143761 71874 143761 71874 143762 72813 143762 72815 143762 71874 143763 72815 143763 72341 143763 72341 143764 72815 143764 72816 143764 72341 143765 72816 143765 71875 143765 71875 143766 72816 143766 71876 143766 71875 143767 71876 143767 71877 143767 71877 143768 71876 143768 71197 143768 71877 143769 71197 143769 71878 143769 71878 143770 71197 143770 71879 143770 71878 143771 71879 143771 71852 143771 71852 143772 71879 143772 71199 143772 71852 143773 71199 143773 71880 143773 71880 143774 71199 143774 71881 143774 71880 143775 71881 143775 71882 143775 71882 143776 71881 143776 71883 143776 71882 143777 71883 143777 71884 143777 71884 143778 71883 143778 71201 143778 71884 143779 71201 143779 71885 143779 71885 143780 71201 143780 71887 143780 71885 143781 71887 143781 71886 143781 71886 143782 71887 143782 71203 143782 71886 143783 71203 143783 71888 143783 71888 143784 71203 143784 71889 143784 71888 143785 71889 143785 71890 143785 71890 143786 71889 143786 71891 143786 71890 143787 71891 143787 71858 143787 71858 143788 71891 143788 71204 143788 71858 143789 71204 143789 71859 143789 71859 143790 71204 143790 71892 143790 71859 143791 71892 143791 71861 143791 71861 143792 71892 143792 71893 143792 71861 143793 71893 143793 71863 143793 71863 143794 71893 143794 71207 143794 71863 143795 71207 143795 71894 143795 71894 143796 71207 143796 71896 143796 71894 143797 71896 143797 71895 143797 71895 143798 71896 143798 71208 143798 71895 143799 71208 143799 71897 143799 71897 143800 71208 143800 71210 143800 71897 143801 71210 143801 72321 143801 72321 143802 71210 143802 72799 143802 72321 143803 72799 143803 72323 143803 72323 143804 72799 143804 72800 143804 72323 143805 72800 143805 71898 143805 71898 143806 72800 143806 71899 143806 71898 143807 71899 143807 72325 143807 72325 143808 71899 143808 72803 143808 72325 143809 72803 143809 72327 143809 72327 143810 72803 143810 71900 143810 72327 143811 71900 143811 72328 143811 72328 143812 71900 143812 71902 143812 72328 143813 71902 143813 71901 143813 71901 143814 71902 143814 71903 143814 71901 143815 71903 143815 72329 143815 72329 143816 71903 143816 71867 143816 71194 143817 71938 143817 71936 143817 71194 143818 71936 143818 71904 143818 71904 143819 71936 143819 71935 143819 71904 143820 71935 143820 71195 143820 71195 143821 71935 143821 71905 143821 71195 143822 71905 143822 71196 143822 71196 143823 71905 143823 71906 143823 71196 143824 71906 143824 71198 143824 71198 143825 71906 143825 71932 143825 71198 143826 71932 143826 71907 143826 71907 143827 71932 143827 71931 143827 71907 143828 71931 143828 71200 143828 71200 143829 71931 143829 71908 143829 71200 143830 71908 143830 71909 143830 71909 143831 71908 143831 71910 143831 71909 143832 71910 143832 71911 143832 71911 143833 71910 143833 71929 143833 71911 143834 71929 143834 71202 143834 71202 143835 71929 143835 71927 143835 71202 143836 71927 143836 71912 143836 71912 143837 71927 143837 71926 143837 71912 143838 71926 143838 71913 143838 71913 143839 71926 143839 71914 143839 71913 143840 71914 143840 71205 143840 71205 143841 71914 143841 71915 143841 71205 143842 71915 143842 71206 143842 71206 143843 71915 143843 71916 143843 71206 143844 71916 143844 71917 143844 71917 143845 71916 143845 71918 143845 71917 143846 71918 143846 71919 143846 71919 143847 71918 143847 71923 143847 71919 143848 71923 143848 71920 143848 71920 143849 71923 143849 71922 143849 71920 143850 71922 143850 71209 143850 71209 143851 71922 143851 72301 143851 71209 143852 72301 143852 72303 143852 71921 143853 72301 143853 71922 143853 71921 143854 71922 143854 71964 143854 71964 143855 71922 143855 71923 143855 71964 143856 71923 143856 71965 143856 71965 143857 71923 143857 71918 143857 71965 143858 71918 143858 71966 143858 71966 143859 71918 143859 71916 143859 71966 143860 71916 143860 71967 143860 71967 143861 71916 143861 71915 143861 71967 143862 71915 143862 71924 143862 71924 143863 71915 143863 71914 143863 71924 143864 71914 143864 71925 143864 71925 143865 71914 143865 71926 143865 71925 143866 71926 143866 71969 143866 71969 143867 71926 143867 71927 143867 71969 143868 71927 143868 71928 143868 71928 143869 71927 143869 71929 143869 71928 143870 71929 143870 71956 143870 71956 143871 71929 143871 71910 143871 71956 143872 71910 143872 71958 143872 71958 143873 71910 143873 71908 143873 71958 143874 71908 143874 71930 143874 71930 143875 71908 143875 71931 143875 71930 143876 71931 143876 71960 143876 71960 143877 71931 143877 71932 143877 71960 143878 71932 143878 71933 143878 71933 143879 71932 143879 71906 143879 71933 143880 71906 143880 71934 143880 71934 143881 71906 143881 71905 143881 71934 143882 71905 143882 71963 143882 71963 143883 71905 143883 71935 143883 71963 143884 71935 143884 71944 143884 71944 143885 71935 143885 71936 143885 71944 143886 71936 143886 71937 143886 71937 143887 71936 143887 71938 143887 71937 143888 71938 143888 72282 143888 72271 143889 72297 143889 72270 143889 72270 143890 72297 143890 72300 143890 72270 143891 72300 143891 71939 143891 71939 143892 72300 143892 72302 143892 71939 143893 72302 143893 72266 143893 72266 143894 72302 143894 71921 143894 72266 143895 71921 143895 71983 143895 71983 143896 71921 143896 71964 143896 71983 143897 71964 143897 71982 143897 71954 143898 71955 143898 72276 143898 72276 143899 71955 143899 71940 143899 72276 143900 71940 143900 72274 143900 72274 143901 71940 143901 71942 143901 72274 143902 71942 143902 71941 143902 71941 143903 71942 143903 71943 143903 71941 143904 71943 143904 72273 143904 72273 143905 71943 143905 72294 143905 72273 143906 72294 143906 72271 143906 72271 143907 72294 143907 72295 143907 72271 143908 72295 143908 72297 143908 71962 143909 71963 143909 71971 143909 71971 143910 71963 143910 71944 143910 71971 143911 71944 143911 71970 143911 71970 143912 71944 143912 71937 143912 71970 143913 71937 143913 71945 143913 71945 143914 71937 143914 72282 143914 71945 143915 72282 143915 71946 143915 71946 143916 72282 143916 72283 143916 71946 143917 72283 143917 71947 143917 72283 143918 72284 143918 71947 143918 71947 143919 72284 143919 71949 143919 71947 143920 71949 143920 71948 143920 71948 143921 71949 143921 71950 143921 71948 143922 71950 143922 72280 143922 72280 143923 71950 143923 71951 143923 72280 143924 71951 143924 71952 143924 71952 143925 71951 143925 71953 143925 71952 143926 71953 143926 72278 143926 72278 143927 71953 143927 72289 143927 72278 143928 72289 143928 71954 143928 71954 143929 72289 143929 72290 143929 71954 143930 72290 143930 71955 143930 71968 143931 71956 143931 71957 143931 71957 143932 71956 143932 71958 143932 71957 143933 71958 143933 71959 143933 71959 143934 71958 143934 71930 143934 71959 143935 71930 143935 71973 143935 71973 143936 71930 143936 71960 143936 71973 143937 71960 143937 71961 143937 71961 143938 71960 143938 71933 143938 71961 143939 71933 143939 71962 143939 71962 143940 71933 143940 71934 143940 71962 143941 71934 143941 71963 143941 71964 143942 71965 143942 71982 143942 71982 143943 71965 143943 71966 143943 71982 143944 71966 143944 71980 143944 71980 143945 71966 143945 71967 143945 71980 143946 71967 143946 71979 143946 71979 143947 71967 143947 71924 143947 71979 143948 71924 143948 71977 143948 71977 143949 71924 143949 71925 143949 71977 143950 71925 143950 71975 143950 71975 143951 71925 143951 71969 143951 71975 143952 71969 143952 71968 143952 71968 143953 71969 143953 71928 143953 71968 143954 71928 143954 71956 143954 71945 143955 71380 143955 71379 143955 71945 143956 71379 143956 71970 143956 71970 143957 71379 143957 71378 143957 71970 143958 71378 143958 71971 143958 71971 143959 71378 143959 71377 143959 71971 143960 71377 143960 71962 143960 71962 143961 71377 143961 71972 143961 71962 143962 71972 143962 71961 143962 71961 143963 71972 143963 71375 143963 71961 143964 71375 143964 71973 143964 71973 143965 71375 143965 71374 143965 71973 143966 71374 143966 71959 143966 71959 143967 71374 143967 71373 143967 71959 143968 71373 143968 71957 143968 71957 143969 71373 143969 71974 143969 71957 143970 71974 143970 71968 143970 71968 143971 71974 143971 71371 143971 71968 143972 71371 143972 71975 143972 71975 143973 71371 143973 71976 143973 71975 143974 71976 143974 71977 143974 71977 143975 71976 143975 71978 143975 71977 143976 71978 143976 71979 143976 71979 143977 71978 143977 71367 143977 71979 143978 71367 143978 71980 143978 71980 143979 71367 143979 71981 143979 71980 143980 71981 143980 71982 143980 71982 143981 71981 143981 71365 143981 71982 143982 71365 143982 71983 143982 71983 143983 71365 143983 71364 143983 71983 143984 71364 143984 72266 143984 71986 143985 71984 143985 72442 143985 72442 143986 71985 143986 71986 143986 71986 143987 71985 143987 71594 143987 71986 143988 71594 143988 71989 143988 71989 143989 71594 143989 71593 143989 71593 143990 71987 143990 71989 143990 71989 143991 71987 143991 71988 143991 71989 143992 71988 143992 71381 143992 71595 143993 71992 143993 71384 143993 71988 143994 71990 143994 71381 143994 71381 143995 71990 143995 71991 143995 71381 143996 71991 143996 71384 143996 71384 143997 71991 143997 71597 143997 71384 143998 71597 143998 71595 143998 71995 143999 71996 143999 71386 143999 71595 144000 71600 144000 71992 144000 71992 144001 71600 144001 71993 144001 71992 144002 71993 144002 71386 144002 71386 144003 71993 144003 71994 144003 71386 144004 71994 144004 71995 144004 71995 144005 71601 144005 71996 144005 71996 144006 71601 144006 71602 144006 71996 144007 71602 144007 71391 144007 71602 144008 71997 144008 71391 144008 71391 144009 71997 144009 71998 144009 71391 144010 71998 144010 71999 144010 71998 144011 71604 144011 71999 144011 71999 144012 71604 144012 72000 144012 71999 144013 72000 144013 71388 144013 72000 144014 71606 144014 71388 144014 71388 144015 71606 144015 71607 144015 71388 144016 71607 144016 71387 144016 71607 144017 72001 144017 71387 144017 71387 144018 72001 144018 72002 144018 71387 144019 72002 144019 72003 144019 72002 144020 72004 144020 72003 144020 72003 144021 72004 144021 71608 144021 72003 144022 71608 144022 72005 144022 71608 144023 71609 144023 72005 144023 72005 144024 71609 144024 72009 144024 72005 144025 72009 144025 72006 144025 72007 144026 72008 144026 71611 144026 71611 144027 72008 144027 72006 144027 71611 144028 72006 144028 71610 144028 71610 144029 72006 144029 72009 144029 72229 144030 71532 144030 72010 144030 72213 144031 72212 144031 64718 144031 64712 144032 72123 144032 72126 144032 64706 144033 72174 144033 72164 144033 64724 144034 72011 144034 72139 144034 64710 144035 64708 144035 72167 144035 72167 144036 64708 144036 72164 144036 72205 144037 64703 144037 72204 144037 72204 144038 64703 144038 64726 144038 72135 144039 72012 144039 72038 144039 72013 144040 71265 144040 72184 144040 72754 144041 72105 144041 72170 144041 72014 144042 72220 144042 71383 144042 72062 144043 72086 144043 71389 144043 72058 144044 71393 144044 72172 144044 72636 144045 72232 144045 72015 144045 72016 144046 72182 144046 72634 144046 71241 144047 72243 144047 72241 144047 72202 144048 72032 144048 72017 144048 72018 144049 72019 144049 72020 144049 72020 144050 72019 144050 72080 144050 72020 144051 72080 144051 72218 144051 72021 144052 71234 144052 72216 144052 72216 144053 71234 144053 71233 144053 72216 144054 71233 144054 72020 144054 72020 144055 71233 144055 72783 144055 72020 144056 72783 144056 72018 144056 72021 144057 72216 144057 71236 144057 71236 144058 72216 144058 72024 144058 71236 144059 72024 144059 71238 144059 72019 144060 72022 144060 72080 144060 72080 144061 72022 144061 72781 144061 72080 144062 72781 144062 72653 144062 72653 144063 72781 144063 72023 144063 72653 144064 72023 144064 72024 144064 72024 144065 72023 144065 71239 144065 72024 144066 71239 144066 71238 144066 72026 144067 72024 144067 72446 144067 72443 144068 72444 144068 72216 144068 72216 144069 72444 144069 72445 144069 72216 144070 72445 144070 72024 144070 72024 144071 72445 144071 72025 144071 72024 144072 72025 144072 72446 144072 72446 144073 71581 144073 72026 144073 72026 144074 71581 144074 71583 144074 72026 144075 71583 144075 72202 144075 71241 144076 72034 144076 72027 144076 72027 144077 72034 144077 72017 144077 72027 144078 72017 144078 72028 144078 72028 144079 72017 144079 72032 144079 72028 144080 72032 144080 72029 144080 72199 144081 72030 144081 72031 144081 72031 144082 72030 144082 72779 144082 72031 144083 72779 144083 72032 144083 72032 144084 72779 144084 72033 144084 72032 144085 72033 144085 72029 144085 71241 144086 72241 144086 72034 144086 72034 144087 72241 144087 72035 144087 72034 144088 72035 144088 72649 144088 72649 144089 72035 144089 72037 144089 72037 144090 72035 144090 72036 144090 72037 144091 72036 144091 72239 144091 72133 144092 72038 144092 72039 144092 72039 144093 72038 144093 72040 144093 72039 144094 72040 144094 71244 144094 72186 144095 72771 144095 72041 144095 72041 144096 72771 144096 71245 144096 72041 144097 71245 144097 72648 144097 72648 144098 71245 144098 72042 144098 72648 144099 72042 144099 72040 144099 72040 144100 72042 144100 72043 144100 72040 144101 72043 144101 71244 144101 72044 144102 72012 144102 72045 144102 72044 144103 72045 144103 71561 144103 71561 144104 72045 144104 71250 144104 71561 144105 71250 144105 72051 144105 72046 144106 72038 144106 72470 144106 72470 144107 72038 144107 72012 144107 72470 144108 72012 144108 72047 144108 72047 144109 72012 144109 72044 144109 72640 144110 72040 144110 71556 144110 72046 144111 72048 144111 72038 144111 72038 144112 72048 144112 72049 144112 72038 144113 72049 144113 72040 144113 72040 144114 72049 144114 72050 144114 72040 144115 72050 144115 71556 144115 71250 144116 71249 144116 72051 144116 72051 144117 71249 144117 72641 144117 72051 144118 72641 144118 71558 144118 71558 144119 72641 144119 72640 144119 71558 144120 72640 144120 72052 144120 72052 144121 72640 144121 71556 144121 72053 144122 72642 144122 72054 144122 72054 144123 72642 144123 72641 144123 72054 144124 72641 144124 71248 144124 71248 144125 72641 144125 71249 144125 72638 144126 72645 144126 72120 144126 72120 144127 72645 144127 72644 144127 72015 144128 72232 144128 72233 144128 72111 144129 72234 144129 72057 144129 72111 144130 72055 144130 72109 144130 72055 144131 72111 144131 72056 144131 72056 144132 72111 144132 72057 144132 72056 144133 72057 144133 72107 144133 71393 144134 72058 144134 71392 144134 71392 144135 72058 144135 72101 144135 71392 144136 72101 144136 72100 144136 72059 144137 72060 144137 72223 144137 72223 144138 72060 144138 72104 144138 72061 144139 72222 144139 72062 144139 72062 144140 72222 144140 72097 144140 72062 144141 72097 144141 72086 144141 72158 144142 71497 144142 71499 144142 72158 144143 71499 144143 72063 144143 72063 144144 71499 144144 72529 144144 72063 144145 72529 144145 72531 144145 72064 144146 72150 144146 72065 144146 71489 144147 72067 144147 72534 144147 72534 144148 72067 144148 72064 144148 72534 144149 72064 144149 72066 144149 72066 144150 72064 144150 72065 144150 72220 144151 72014 144151 72067 144151 72067 144152 72014 144152 72068 144152 72067 144153 72068 144153 72064 144153 72069 144154 72070 144154 71385 144154 71385 144155 72070 144155 72161 144155 71385 144156 72161 144156 72071 144156 72545 144157 72072 144157 72073 144157 72073 144158 72072 144158 72074 144158 72072 144159 72075 144159 72074 144159 72074 144160 72075 144160 72076 144160 72074 144161 72076 144161 72077 144161 72077 144162 72076 144162 71478 144162 72077 144163 71478 144163 71480 144163 71232 144164 72080 144164 72078 144164 72078 144165 72080 144165 71382 144165 72078 144166 71382 144166 72084 144166 72084 144167 71382 144167 72074 144167 72082 144168 72077 144168 72079 144168 72079 144169 72077 144169 72218 144169 72079 144170 72218 144170 72081 144170 71232 144171 71231 144171 72080 144171 72080 144172 71231 144172 71230 144172 72080 144173 71230 144173 72218 144173 72218 144174 71230 144174 71228 144174 72218 144175 71228 144175 72081 144175 72082 144176 72786 144176 72077 144176 72077 144177 72786 144177 72083 144177 72077 144178 72083 144178 72074 144178 72074 144179 72083 144179 72784 144179 72074 144180 72784 144180 72084 144180 72152 144181 72091 144181 72153 144181 72151 144182 72090 144182 72085 144182 72085 144183 72090 144183 72088 144183 71390 144184 71389 144184 72739 144184 72739 144185 71389 144185 72086 144185 72739 144186 72086 144186 72087 144186 72087 144187 72086 144187 72099 144187 72519 144188 72089 144188 72096 144188 72519 144189 72088 144189 72089 144189 72089 144190 72088 144190 72090 144190 72089 144191 72090 144191 72739 144191 72739 144192 72090 144192 72146 144192 72739 144193 72146 144193 71390 144193 72093 144194 72097 144194 72153 144194 72091 144195 71504 144195 72153 144195 72153 144196 71504 144196 72092 144196 72153 144197 72092 144197 71506 144197 72093 144198 72153 144198 72094 144198 72094 144199 72153 144199 71506 144199 72094 144200 71506 144200 71286 144200 71286 144201 71506 144201 72095 144201 71286 144202 72095 144202 71287 144202 71287 144203 72095 144203 72517 144203 71287 144204 72517 144204 72096 144204 72096 144205 72517 144205 72518 144205 72096 144206 72518 144206 72519 144206 72093 144207 72098 144207 72097 144207 72097 144208 72098 144208 71283 144208 72097 144209 71283 144209 72086 144209 72086 144210 71283 144210 71281 144210 72086 144211 71281 144211 72099 144211 72059 144212 72100 144212 72060 144212 72060 144213 72100 144213 72101 144213 72060 144214 72101 144214 72102 144214 72102 144215 72101 144215 72103 144215 72741 144216 71279 144216 72209 144216 72209 144217 71279 144217 64706 144217 64706 144218 71279 144218 71278 144218 64706 144219 71278 144219 72174 144219 72174 144220 71278 144220 71276 144220 72174 144221 71276 144221 72101 144221 72101 144222 71276 144222 71274 144222 72101 144223 71274 144223 72103 144223 72102 144224 72750 144224 72060 144224 72060 144225 72750 144225 72748 144225 72060 144226 72748 144226 72104 144226 72104 144227 72748 144227 72747 144227 72104 144228 72747 144228 72224 144228 72224 144229 72747 144229 72744 144229 72224 144230 72744 144230 72210 144230 72170 144231 72105 144231 72167 144231 64710 144232 72106 144232 72226 144232 72226 144233 72106 144233 71270 144233 72226 144234 71270 144234 72057 144234 72057 144235 71270 144235 71268 144235 72057 144236 71268 144236 72107 144236 72105 144237 72108 144237 72167 144237 72167 144238 72108 144238 72751 144238 72167 144239 72751 144239 64710 144239 64710 144240 72751 144240 71272 144240 64710 144241 71272 144241 72106 144241 72754 144242 72170 144242 72755 144242 72755 144243 72170 144243 72171 144243 72755 144244 72171 144244 72109 144244 72109 144245 72171 144245 72110 144245 72109 144246 72110 144246 72111 144246 72112 144247 72230 144247 72232 144247 71265 144248 72112 144248 72184 144248 72184 144249 72112 144249 72232 144249 72184 144250 72232 144250 72182 144250 72182 144251 72232 144251 72636 144251 72182 144252 72636 144252 72634 144252 72176 144253 72113 144253 72013 144253 72116 144254 72114 144254 72225 144254 72225 144255 72114 144255 72115 144255 72010 144256 72761 144256 72117 144256 72010 144257 72117 144257 72116 144257 72116 144258 72117 144258 72118 144258 72116 144259 72118 144259 72114 144259 72642 144260 72245 144260 72643 144260 72643 144261 72245 144261 72119 144261 72643 144262 72119 144262 72644 144262 72644 144263 72119 144263 72121 144263 72644 144264 72121 144264 72120 144264 72120 144265 72121 144265 71255 144265 72120 144266 71255 144266 72122 144266 72122 144267 71254 144267 72120 144267 72120 144268 71254 144268 71252 144268 72120 144269 71252 144269 72180 144269 71252 144270 72767 144270 72180 144270 72180 144271 72767 144271 72124 144271 72180 144272 72124 144272 72123 144272 72123 144273 72124 144273 72125 144273 72123 144274 72125 144274 72126 144274 72126 144275 72125 144275 72127 144275 72126 144276 72127 144276 64715 144276 72127 144277 72764 144277 64715 144277 64715 144278 72764 144278 71259 144278 64715 144279 71259 144279 72128 144279 72128 144280 71259 144280 71258 144280 72128 144281 71258 144281 71257 144281 72770 144282 72246 144282 72130 144282 72130 144283 72246 144283 72129 144283 72130 144284 72129 144284 71246 144284 72770 144285 72131 144285 72246 144285 72246 144286 72131 144286 72769 144286 72246 144287 72769 144287 72132 144287 72133 144288 72134 144288 72038 144288 72038 144289 72134 144289 72132 144289 72038 144290 72132 144290 72135 144290 72135 144291 72132 144291 72769 144291 72134 144292 72136 144292 72132 144292 72132 144293 72136 144293 72776 144293 72132 144294 72776 144294 72211 144294 72211 144295 72776 144295 72773 144295 72211 144296 72773 144296 72186 144296 72186 144297 72773 144297 72137 144297 72186 144298 72137 144298 72771 144298 72244 144299 71240 144299 72242 144299 72242 144300 71240 144300 72780 144300 72242 144301 72780 144301 72195 144301 72195 144302 72780 144302 72138 144302 72195 144303 72138 144303 72198 144303 72070 144304 71223 144304 72161 144304 72161 144305 71223 144305 71222 144305 72161 144306 71222 144306 72011 144306 72011 144307 71222 144307 71221 144307 72011 144308 71221 144308 72139 144308 72139 144309 71221 144309 72140 144309 72139 144310 72140 144310 72141 144310 72141 144311 72140 144311 71218 144311 72141 144312 71218 144312 71217 144312 72069 144313 71385 144313 72142 144313 72142 144314 71385 144314 72143 144314 72142 144315 72143 144315 72790 144315 72790 144316 72143 144316 72221 144316 72790 144317 72221 144317 72144 144317 72144 144318 72221 144318 72145 144318 72144 144319 72145 144319 72163 144319 72154 144320 72798 144320 72090 144320 72090 144321 72798 144321 72796 144321 72090 144322 72796 144322 72146 144322 72146 144323 72796 144323 72795 144323 72146 144324 72795 144324 72147 144324 72147 144325 72795 144325 72149 144325 72147 144326 72149 144326 72148 144326 72148 144327 72149 144327 72063 144327 72148 144328 72063 144328 72150 144328 72150 144329 72063 144329 72531 144329 72150 144330 72531 144330 72065 144330 72151 144331 72152 144331 72090 144331 72090 144332 72152 144332 72153 144332 72090 144333 72153 144333 72154 144333 72154 144334 72153 144334 72160 144334 72155 144335 72158 144335 72156 144335 72156 144336 72158 144336 72063 144336 72156 144337 72063 144337 72793 144337 72793 144338 72063 144338 72149 144338 72155 144339 71215 144339 72158 144339 72158 144340 71215 144340 72157 144340 72158 144341 72157 144341 72153 144341 72153 144342 72157 144342 72159 144342 72153 144343 72159 144343 72160 144343 72545 144344 72073 144344 72543 144344 72543 144345 72073 144345 72071 144345 72543 144346 72071 144346 72542 144346 72542 144347 72071 144347 72161 144347 72542 144348 72161 144348 72162 144348 72162 144349 72161 144349 72011 144349 72162 144350 72011 144350 72540 144350 64724 144351 71483 144351 72011 144351 72011 144352 71483 144352 71484 144352 72011 144353 71484 144353 72540 144353 72219 144354 72141 144354 72145 144354 72145 144355 72141 144355 71217 144355 72145 144356 71217 144356 72163 144356 72219 144357 71492 144357 72141 144357 72141 144358 71492 144358 72203 144358 72141 144359 72203 144359 64726 144359 72164 144360 71517 144360 72166 144360 72165 144361 72500 144361 72058 144361 72164 144362 72166 144362 72167 144362 72167 144363 72166 144363 72168 144363 72167 144364 72168 144364 72170 144364 72170 144365 72168 144365 71519 144365 72170 144366 71519 144366 72169 144366 72169 144367 72165 144367 72170 144367 72170 144368 72165 144368 72058 144368 72170 144369 72058 144369 72171 144369 72171 144370 72058 144370 72172 144370 72171 144371 72172 144371 72110 144371 72500 144372 72502 144372 72058 144372 72058 144373 72502 144373 72173 144373 72058 144374 72173 144374 72101 144374 72101 144375 72173 144375 72175 144375 72101 144376 72175 144376 72174 144376 72174 144377 72175 144377 72507 144377 72174 144378 72507 144378 72164 144378 72164 144379 72507 144379 71515 144379 72164 144380 71515 144380 71517 144380 72115 144381 72113 144381 72225 144381 72225 144382 72113 144382 72176 144382 72225 144383 72176 144383 72177 144383 72177 144384 72176 144384 64712 144384 72181 144385 72178 144385 72176 144385 72176 144386 72178 144386 72478 144386 72176 144387 72478 144387 64712 144387 64712 144388 72478 144388 72179 144388 64712 144389 72179 144389 72123 144389 72123 144390 72179 144390 71539 144390 72123 144391 71539 144391 72180 144391 72180 144392 71539 144392 71542 144392 72180 144393 71542 144393 71544 144393 72638 144394 72120 144394 72016 144394 72016 144395 72120 144395 72180 144395 72016 144396 72180 144396 72182 144396 72182 144397 72180 144397 71544 144397 72182 144398 71544 144398 71545 144398 72013 144399 72184 144399 72176 144399 72176 144400 72184 144400 72476 144400 72176 144401 72476 144401 72181 144401 71545 144402 71546 144402 72182 144402 72182 144403 71546 144403 72183 144403 72182 144404 72183 144404 72184 144404 72184 144405 72183 144405 72185 144405 72184 144406 72185 144406 72476 144406 72191 144407 71570 144407 72190 144407 72190 144408 71570 144408 72186 144408 72190 144409 72186 144409 72239 144409 72239 144410 72186 144410 72041 144410 71573 144411 72211 144411 72187 144411 72187 144412 72211 144412 72186 144412 72187 144413 72186 144413 72188 144413 72188 144414 72186 144414 71570 144414 72195 144415 72458 144415 72242 144415 72242 144416 72458 144416 72459 144416 72242 144417 72459 144417 72240 144417 72240 144418 72459 144418 72189 144418 72240 144419 72189 144419 72190 144419 72190 144420 72189 144420 71567 144420 72190 144421 71567 144421 72191 144421 72212 144422 72192 144422 72193 144422 64718 144423 72212 144423 72194 144423 72194 144424 72212 144424 72193 144424 72194 144425 72193 144425 72195 144425 72195 144426 72193 144426 72196 144426 72195 144427 72196 144427 72458 144427 72197 144428 72200 144428 72031 144428 72138 144429 72199 144429 72198 144429 72198 144430 72199 144430 72031 144430 72198 144431 72031 144431 64720 144431 64720 144432 72031 144432 72200 144432 71583 144433 72201 144433 72202 144433 72202 144434 72201 144434 71586 144434 72202 144435 71586 144435 72032 144435 72032 144436 71586 144436 71587 144436 72032 144437 71587 144437 72031 144437 72031 144438 71587 144438 71588 144438 72031 144439 71588 144439 72197 144439 72203 144440 71495 144440 64726 144440 64726 144441 71495 144441 71497 144441 64726 144442 71497 144442 72204 144442 72204 144443 71497 144443 72158 144443 72204 144444 72158 144444 72205 144444 72205 144445 72158 144445 72153 144445 72205 144446 72153 144446 72206 144446 72206 144447 72153 144447 72097 144447 72206 144448 72097 144448 72207 144448 72208 144449 72224 144449 72209 144449 72209 144450 72224 144450 72210 144450 72209 144451 72210 144451 72741 144451 71573 144452 72192 144452 72211 144452 72211 144453 72192 144453 72212 144453 72211 144454 72212 144454 72132 144454 72132 144455 72212 144455 72213 144455 72132 144456 72213 144456 72246 144456 72246 144457 72213 144457 72214 144457 72246 144458 72214 144458 72128 144458 72128 144459 72214 144459 72215 144459 72128 144460 72215 144460 64715 144460 72200 144461 72443 144461 64720 144461 64720 144462 72443 144462 72216 144462 64720 144463 72216 144463 72217 144463 72217 144464 72216 144464 72020 144464 72217 144465 72020 144465 64722 144465 64722 144466 72020 144466 72218 144466 64722 144467 72218 144467 64723 144467 64723 144468 72218 144468 72077 144468 64723 144469 72077 144469 64724 144469 64724 144470 72077 144470 71480 144470 64724 144471 71480 144471 71483 144471 71489 144472 72219 144472 72067 144472 72067 144473 72219 144473 72145 144473 72067 144474 72145 144474 72220 144474 72220 144475 72145 144475 72221 144475 72220 144476 72221 144476 71383 144476 71383 144477 72221 144477 72143 144477 72061 144478 72223 144478 72222 144478 72222 144479 72223 144479 72104 144479 72222 144480 72104 144480 72097 144480 72097 144481 72104 144481 72224 144481 72097 144482 72224 144482 72207 144482 72207 144483 72224 144483 72208 144483 72492 144484 71524 144484 72116 144484 72238 144485 72227 144485 72226 144485 72225 144486 64710 144486 72116 144486 72116 144487 64710 144487 72226 144487 72116 144488 72226 144488 72492 144488 72492 144489 72226 144489 72227 144489 71524 144490 71528 144490 72116 144490 72116 144491 71528 144491 71529 144491 72116 144492 71529 144492 72010 144492 72010 144493 71529 144493 72228 144493 72010 144494 72228 144494 72229 144494 72230 144495 71261 144495 72232 144495 72232 144496 71261 144496 72231 144496 72232 144497 72231 144497 72233 144497 72233 144498 72231 144498 72761 144498 72233 144499 72761 144499 72234 144499 72234 144500 72761 144500 72010 144500 72234 144501 72010 144501 72057 144501 72057 144502 72010 144502 71532 144502 72057 144503 71532 144503 72235 144503 72235 144504 72236 144504 72057 144504 72057 144505 72236 144505 72237 144505 72057 144506 72237 144506 72226 144506 72226 144507 72237 144507 72490 144507 72226 144508 72490 144508 72238 144508 72239 144509 72036 144509 72190 144509 72190 144510 72036 144510 72035 144510 72190 144511 72035 144511 72240 144511 72240 144512 72035 144512 72241 144512 72240 144513 72241 144513 72242 144513 72242 144514 72241 144514 72243 144514 72242 144515 72243 144515 72244 144515 72053 144516 71246 144516 72642 144516 72642 144517 71246 144517 72129 144517 72642 144518 72129 144518 72245 144518 72245 144519 72129 144519 72246 144519 72245 144520 72246 144520 72119 144520 72119 144521 72246 144521 72128 144521 72119 144522 72128 144522 72121 144522 72121 144523 72128 144523 71257 144523 72121 144524 71257 144524 71255 144524 72247 144525 72008 144525 72007 144525 72007 144526 72248 144526 72247 144526 72247 144527 72248 144527 72418 144527 72247 144528 72418 144528 72637 144528 72637 144529 72418 144529 72417 144529 72417 144530 72249 144530 72637 144530 72637 144531 72249 144531 72415 144531 72637 144532 72415 144532 72635 144532 72419 144533 72250 144533 72252 144533 72415 144534 72251 144534 72635 144534 72635 144535 72251 144535 72253 144535 72635 144536 72253 144536 72252 144536 72252 144537 72253 144537 72420 144537 72252 144538 72420 144538 72419 144538 72258 144539 72259 144539 72256 144539 72419 144540 72254 144540 72250 144540 72250 144541 72254 144541 72255 144541 72250 144542 72255 144542 72256 144542 72256 144543 72255 144543 72257 144543 72256 144544 72257 144544 72258 144544 72258 144545 72260 144545 72259 144545 72259 144546 72260 144546 72261 144546 72259 144547 72261 144547 72639 144547 72261 144548 72425 144548 72639 144548 72639 144549 72425 144549 72262 144549 72639 144550 72262 144550 72647 144550 72262 144551 72427 144551 72647 144551 72647 144552 72427 144552 72428 144552 72647 144553 72428 144553 72646 144553 72428 144554 72429 144554 72646 144554 72646 144555 72429 144555 72431 144555 72646 144556 72431 144556 72650 144556 72431 144557 72263 144557 72650 144557 72650 144558 72263 144558 72434 144558 72650 144559 72434 144559 72651 144559 72434 144560 72435 144560 72651 144560 72651 144561 72435 144561 72264 144561 72651 144562 72264 144562 72652 144562 72264 144563 72265 144563 72652 144563 72652 144564 72265 144564 72437 144564 72652 144565 72437 144565 72654 144565 72442 144566 71984 144566 72441 144566 72441 144567 71984 144567 72654 144567 72441 144568 72654 144568 72438 144568 72438 144569 72654 144569 72437 144569 72266 144570 71364 144570 72267 144570 72266 144571 72267 144571 71939 144571 71939 144572 72267 144572 72268 144572 71939 144573 72268 144573 72270 144573 72270 144574 72268 144574 72269 144574 72270 144575 72269 144575 72271 144575 72271 144576 72269 144576 72272 144576 72271 144577 72272 144577 72273 144577 72273 144578 72272 144578 72662 144578 72273 144579 72662 144579 71941 144579 71941 144580 72662 144580 72665 144580 71941 144581 72665 144581 72274 144581 72274 144582 72665 144582 72275 144582 72274 144583 72275 144583 72276 144583 72276 144584 72275 144584 72277 144584 72276 144585 72277 144585 71954 144585 71954 144586 72277 144586 72666 144586 71954 144587 72666 144587 72278 144587 72278 144588 72666 144588 72279 144588 72278 144589 72279 144589 71952 144589 71952 144590 72279 144590 72659 144590 71952 144591 72659 144591 72280 144591 72280 144592 72659 144592 72657 144592 72280 144593 72657 144593 71948 144593 71948 144594 72657 144594 72655 144594 71948 144595 72655 144595 71947 144595 71947 144596 72655 144596 72281 144596 71947 144597 72281 144597 71946 144597 71946 144598 72281 144598 71380 144598 71946 144599 71380 144599 71945 144599 72282 144600 71938 144600 72319 144600 72282 144601 72319 144601 72283 144601 72283 144602 72319 144602 72285 144602 72283 144603 72285 144603 72284 144603 72284 144604 72285 144604 72286 144604 72284 144605 72286 144605 71949 144605 71949 144606 72286 144606 72315 144606 71949 144607 72315 144607 71950 144607 71950 144608 72315 144608 72287 144608 71950 144609 72287 144609 71951 144609 71951 144610 72287 144610 72288 144610 71951 144611 72288 144611 71953 144611 71953 144612 72288 144612 72312 144612 71953 144613 72312 144613 72289 144613 72289 144614 72312 144614 72291 144614 72289 144615 72291 144615 72290 144615 72290 144616 72291 144616 72311 144616 72290 144617 72311 144617 71955 144617 71955 144618 72311 144618 72292 144618 71955 144619 72292 144619 71940 144619 71940 144620 72292 144620 72293 144620 71940 144621 72293 144621 71942 144621 71942 144622 72293 144622 72309 144622 71942 144623 72309 144623 71943 144623 71943 144624 72309 144624 72307 144624 71943 144625 72307 144625 72294 144625 72294 144626 72307 144626 72306 144626 72294 144627 72306 144627 72295 144627 72295 144628 72306 144628 72296 144628 72295 144629 72296 144629 72297 144629 72297 144630 72296 144630 72298 144630 72297 144631 72298 144631 72300 144631 72300 144632 72298 144632 72299 144632 72300 144633 72299 144633 72302 144633 72302 144634 72299 144634 72301 144634 72302 144635 72301 144635 71921 144635 72303 144636 72301 144636 72299 144636 72303 144637 72299 144637 72304 144637 72304 144638 72299 144638 72298 144638 72304 144639 72298 144639 72305 144639 72305 144640 72298 144640 72296 144640 72305 144641 72296 144641 72801 144641 72801 144642 72296 144642 72306 144642 72801 144643 72306 144643 72802 144643 72802 144644 72306 144644 72307 144644 72802 144645 72307 144645 72804 144645 72804 144646 72307 144646 72309 144646 72804 144647 72309 144647 72308 144647 72308 144648 72309 144648 72293 144648 72308 144649 72293 144649 72310 144649 72310 144650 72293 144650 72292 144650 72310 144651 72292 144651 72805 144651 72805 144652 72292 144652 72311 144652 72805 144653 72311 144653 72806 144653 72806 144654 72311 144654 72291 144654 72806 144655 72291 144655 72808 144655 72808 144656 72291 144656 72312 144656 72808 144657 72312 144657 72313 144657 72313 144658 72312 144658 72288 144658 72313 144659 72288 144659 72314 144659 72314 144660 72288 144660 72287 144660 72314 144661 72287 144661 72811 144661 72811 144662 72287 144662 72315 144662 72811 144663 72315 144663 72316 144663 72316 144664 72315 144664 72286 144664 72316 144665 72286 144665 72317 144665 72317 144666 72286 144666 72285 144666 72317 144667 72285 144667 72318 144667 72318 144668 72285 144668 72319 144668 72318 144669 72319 144669 72814 144669 72814 144670 72319 144670 71938 144670 72814 144671 71938 144671 71194 144671 72320 144672 71897 144672 72321 144672 72320 144673 72321 144673 72322 144673 72322 144674 72321 144674 72323 144674 72322 144675 72323 144675 72852 144675 72852 144676 72323 144676 71898 144676 72852 144677 71898 144677 72324 144677 72324 144678 71898 144678 72325 144678 72324 144679 72325 144679 72856 144679 72856 144680 72325 144680 72327 144680 72856 144681 72327 144681 72326 144681 72326 144682 72327 144682 72328 144682 72326 144683 72328 144683 72859 144683 72859 144684 72328 144684 71901 144684 72859 144685 71901 144685 72330 144685 72330 144686 71901 144686 72329 144686 72330 144687 72329 144687 72331 144687 72331 144688 72329 144688 71868 144688 72331 144689 71868 144689 72861 144689 72861 144690 71868 144690 72332 144690 72861 144691 72332 144691 72863 144691 72863 144692 72332 144692 71870 144692 72863 144693 71870 144693 72333 144693 72333 144694 71870 144694 72334 144694 72333 144695 72334 144695 72335 144695 72335 144696 72334 144696 72337 144696 72335 144697 72337 144697 72336 144697 72336 144698 72337 144698 72339 144698 72336 144699 72339 144699 72338 144699 72338 144700 72339 144700 71873 144700 72338 144701 71873 144701 72867 144701 72867 144702 71873 144702 72340 144702 72867 144703 72340 144703 72869 144703 72869 144704 72340 144704 71874 144704 72869 144705 71874 144705 72870 144705 72870 144706 71874 144706 72341 144706 72870 144707 72341 144707 72872 144707 71140 144708 71794 144708 72342 144708 72342 144709 71794 144709 71793 144709 72342 144710 71793 144710 72343 144710 72343 144711 71793 144711 72344 144711 72343 144712 72344 144712 72883 144712 72883 144713 72344 144713 71792 144713 72883 144714 71792 144714 72345 144714 72345 144715 71792 144715 72346 144715 72345 144716 72346 144716 72347 144716 72347 144717 72346 144717 72348 144717 72347 144718 72348 144718 72349 144718 72349 144719 72348 144719 72351 144719 72349 144720 72351 144720 72350 144720 72350 144721 72351 144721 71787 144721 72350 144722 71787 144722 72352 144722 72352 144723 71787 144723 72353 144723 72352 144724 72353 144724 72354 144724 72354 144725 72353 144725 71785 144725 72354 144726 71785 144726 72879 144726 72879 144727 71785 144727 71784 144727 72879 144728 71784 144728 72876 144728 72876 144729 71784 144729 71783 144729 72876 144730 71783 144730 72875 144730 72875 144731 71783 144731 72355 144731 72875 144732 72355 144732 72356 144732 72356 144733 72355 144733 71781 144733 72356 144734 71781 144734 72874 144734 72874 144735 71781 144735 72357 144735 72874 144736 72357 144736 72358 144736 72358 144737 72357 144737 71778 144737 72358 144738 71778 144738 72359 144738 72359 144739 71778 144739 71777 144739 72359 144740 71777 144740 72360 144740 72360 144741 71777 144741 71775 144741 71759 144742 71760 144742 72902 144742 72902 144743 71760 144743 71738 144743 72902 144744 71738 144744 72900 144744 72900 144745 71738 144745 72361 144745 72900 144746 72361 144746 72899 144746 72899 144747 72361 144747 71737 144747 72899 144748 71737 144748 72898 144748 72898 144749 71737 144749 72363 144749 72898 144750 72363 144750 72362 144750 72362 144751 72363 144751 72364 144751 72362 144752 72364 144752 72897 144752 72897 144753 72364 144753 72365 144753 72897 144754 72365 144754 72366 144754 72366 144755 72365 144755 72367 144755 72366 144756 72367 144756 72895 144756 72895 144757 72367 144757 72368 144757 72895 144758 72368 144758 72369 144758 72369 144759 72368 144759 71732 144759 72369 144760 71732 144760 72370 144760 72370 144761 71732 144761 72371 144761 72370 144762 72371 144762 72372 144762 72372 144763 72371 144763 72373 144763 72372 144764 72373 144764 72374 144764 72374 144765 72373 144765 71730 144765 72374 144766 71730 144766 72892 144766 72892 144767 71730 144767 71729 144767 72892 144768 71729 144768 72890 144768 72890 144769 71729 144769 72375 144769 72890 144770 72375 144770 72376 144770 72376 144771 72375 144771 72377 144771 72376 144772 72377 144772 72887 144772 72887 144773 72377 144773 71726 144773 72887 144774 71726 144774 72886 144774 72886 144775 71726 144775 72378 144775 72830 144776 72379 144776 72380 144776 72830 144777 72380 144777 72831 144777 72831 144778 72380 144778 72381 144778 72831 144779 72381 144779 72832 144779 72832 144780 72381 144780 72382 144780 72832 144781 72382 144781 72833 144781 72833 144782 72382 144782 72383 144782 72833 144783 72383 144783 72834 144783 72834 144784 72383 144784 72384 144784 72834 144785 72384 144785 72385 144785 72385 144786 72384 144786 72386 144786 72385 144787 72386 144787 72835 144787 72835 144788 72386 144788 71718 144788 72835 144789 71718 144789 72838 144789 72838 144790 71718 144790 71719 144790 72838 144791 71719 144791 72839 144791 72839 144792 71719 144792 72387 144792 72839 144793 72387 144793 72841 144793 72841 144794 72387 144794 72388 144794 72841 144795 72388 144795 72842 144795 72842 144796 72388 144796 72389 144796 72842 144797 72389 144797 72844 144797 72844 144798 72389 144798 71720 144798 72844 144799 71720 144799 72845 144799 72845 144800 71720 144800 72390 144800 72845 144801 72390 144801 72391 144801 72391 144802 72390 144802 71722 144802 72391 144803 71722 144803 72848 144803 72848 144804 71722 144804 72392 144804 72848 144805 72392 144805 72849 144805 72849 144806 72392 144806 71724 144806 72849 144807 71724 144807 72393 144807 72393 144808 71724 144808 71725 144808 72393 144809 71725 144809 72394 144809 72395 144810 72396 144810 72397 144810 72397 144811 72396 144811 71634 144811 72397 144812 71634 144812 72829 144812 72829 144813 71634 144813 72398 144813 72829 144814 72398 144814 72399 144814 72399 144815 72398 144815 72400 144815 72399 144816 72400 144816 72827 144816 72827 144817 72400 144817 71630 144817 72827 144818 71630 144818 72401 144818 72401 144819 71630 144819 71629 144819 72401 144820 71629 144820 72402 144820 72402 144821 71629 144821 71627 144821 72402 144822 71627 144822 72403 144822 72403 144823 71627 144823 72404 144823 72403 144824 72404 144824 72825 144824 72825 144825 72404 144825 71624 144825 72825 144826 71624 144826 72823 144826 72823 144827 71624 144827 72405 144827 72823 144828 72405 144828 72822 144828 72822 144829 72405 144829 72406 144829 72822 144830 72406 144830 72407 144830 72407 144831 72406 144831 71623 144831 72407 144832 71623 144832 72821 144832 72821 144833 71623 144833 71622 144833 72821 144834 71622 144834 72820 144834 72820 144835 71622 144835 72408 144835 72820 144836 72408 144836 72409 144836 72409 144837 72408 144837 72410 144837 72409 144838 72410 144838 72411 144838 72411 144839 72410 144839 71621 144839 72411 144840 71621 144840 72412 144840 72412 144841 71621 144841 72413 144841 72412 144842 72413 144842 72817 144842 72817 144843 72413 144843 71619 144843 72260 144844 72258 144844 71638 144844 71612 144845 72414 144845 72007 144845 72007 144846 72414 144846 72248 144846 72416 144847 72422 144847 72415 144847 72415 144848 72249 144848 72416 144848 72416 144849 72249 144849 72417 144849 72416 144850 72417 144850 72414 144850 72414 144851 72417 144851 72418 144851 72414 144852 72418 144852 72248 144852 72421 144853 72423 144853 72419 144853 72419 144854 72420 144854 72421 144854 72421 144855 72420 144855 72253 144855 72421 144856 72253 144856 72422 144856 72422 144857 72253 144857 72251 144857 72422 144858 72251 144858 72415 144858 71638 144859 72258 144859 71636 144859 72258 144860 72257 144860 71636 144860 71636 144861 72257 144861 72255 144861 71636 144862 72255 144862 72423 144862 72423 144863 72255 144863 72254 144863 72423 144864 72254 144864 72419 144864 72260 144865 71638 144865 72261 144865 72261 144866 71638 144866 72424 144866 72261 144867 72424 144867 72425 144867 72425 144868 72424 144868 72426 144868 72425 144869 72426 144869 72262 144869 72262 144870 72426 144870 72427 144870 72427 144871 72426 144871 72430 144871 72427 144872 72430 144872 72428 144872 72428 144873 72430 144873 72429 144873 72429 144874 72430 144874 72432 144874 72429 144875 72432 144875 72431 144875 72431 144876 72432 144876 72263 144876 72263 144877 72432 144877 72433 144877 72263 144878 72433 144878 72434 144878 72434 144879 72433 144879 72435 144879 72435 144880 72433 144880 72436 144880 72435 144881 72436 144881 72264 144881 72264 144882 72436 144882 72265 144882 72265 144883 72436 144883 71617 144883 72265 144884 71617 144884 72437 144884 72437 144885 71617 144885 72438 144885 72438 144886 71617 144886 72439 144886 72438 144887 72439 144887 72441 144887 72441 144888 72439 144888 72440 144888 72441 144889 72440 144889 72442 144889 72200 144890 72449 144890 72443 144890 72443 144891 72449 144891 72450 144891 72443 144892 72450 144892 72444 144892 72444 144893 72450 144893 72454 144893 72444 144894 72454 144894 72445 144894 72445 144895 72454 144895 72455 144895 72445 144896 72455 144896 72025 144896 72025 144897 72455 144897 72447 144897 72025 144898 72447 144898 72446 144898 72446 144899 72447 144899 72448 144899 72446 144900 72448 144900 71581 144900 71581 144901 72448 144901 71582 144901 72449 144902 72451 144902 72450 144902 72450 144903 72451 144903 72452 144903 72450 144904 72452 144904 72454 144904 72454 144905 72452 144905 72453 144905 72454 144906 72453 144906 72455 144906 72455 144907 72453 144907 72456 144907 72455 144908 72456 144908 72447 144908 72447 144909 72456 144909 72938 144909 72447 144910 72938 144910 72448 144910 72448 144911 72938 144911 72940 144911 72448 144912 72940 144912 71582 144912 71582 144913 72940 144913 72941 144913 71573 144914 71566 144914 72192 144914 72192 144915 71566 144915 72461 144915 72192 144916 72461 144916 72193 144916 72193 144917 72461 144917 72462 144917 72193 144918 72462 144918 72196 144918 72196 144919 72462 144919 72457 144919 72196 144920 72457 144920 72458 144920 72458 144921 72457 144921 72464 144921 72458 144922 72464 144922 72459 144922 72459 144923 72464 144923 72465 144923 72459 144924 72465 144924 72189 144924 72189 144925 72465 144925 72460 144925 73068 144926 72460 144926 73022 144926 73022 144927 72460 144927 72465 144927 71566 144928 73060 144928 72461 144928 72461 144929 73060 144929 73123 144929 72461 144930 73123 144930 72462 144930 72462 144931 73123 144931 73059 144931 72462 144932 73059 144932 72457 144932 72457 144933 73059 144933 72463 144933 72457 144934 72463 144934 72464 144934 72464 144935 72463 144935 72466 144935 72464 144936 72466 144936 72465 144936 72465 144937 72466 144937 72467 144937 72465 144938 72467 144938 73022 144938 71561 144939 71562 144939 72044 144939 72044 144940 71562 144940 72468 144940 72044 144941 72468 144941 72047 144941 72047 144942 72468 144942 72469 144942 72047 144943 72469 144943 72470 144943 72470 144944 72469 144944 72473 144944 72470 144945 72473 144945 72046 144945 72046 144946 72473 144946 72471 144946 72046 144947 72471 144947 72048 144947 72048 144948 72471 144948 72472 144948 72048 144949 72472 144949 72049 144949 72049 144950 72472 144950 72474 144950 71562 144951 72913 144951 72468 144951 72468 144952 72913 144952 72917 144952 72468 144953 72917 144953 72469 144953 72469 144954 72917 144954 72912 144954 72469 144955 72912 144955 72473 144955 72473 144956 72912 144956 73124 144956 72473 144957 73124 144957 72471 144957 72471 144958 73124 144958 72911 144958 72471 144959 72911 144959 72472 144959 72472 144960 72911 144960 72475 144960 72472 144961 72475 144961 72474 144961 72474 144962 72475 144962 71548 144962 72183 144963 71538 144963 72185 144963 72185 144964 71538 144964 72480 144964 72185 144965 72480 144965 72476 144965 72476 144966 72480 144966 72482 144966 72476 144967 72482 144967 72181 144967 72181 144968 72482 144968 72484 144968 72181 144969 72484 144969 72178 144969 72178 144970 72484 144970 72477 144970 72178 144971 72477 144971 72478 144971 72478 144972 72477 144972 72479 144972 72478 144973 72479 144973 72179 144973 72179 144974 72479 144974 72486 144974 71538 144975 73070 144975 72480 144975 72480 144976 73070 144976 72481 144976 72480 144977 72481 144977 72482 144977 72482 144978 72481 144978 72483 144978 72482 144979 72483 144979 72484 144979 72484 144980 72483 144980 72485 144980 72484 144981 72485 144981 72477 144981 72477 144982 72485 144982 72974 144982 72477 144983 72974 144983 72479 144983 72479 144984 72974 144984 72904 144984 72479 144985 72904 144985 72486 144985 72486 144986 72904 144986 73076 144986 71532 144987 71533 144987 72235 144987 72235 144988 71533 144988 72487 144988 72235 144989 72487 144989 72236 144989 72236 144990 72487 144990 72488 144990 72236 144991 72488 144991 72237 144991 72237 144992 72488 144992 72489 144992 72237 144993 72489 144993 72490 144993 72490 144994 72489 144994 72495 144994 72490 144995 72495 144995 72238 144995 72238 144996 72495 144996 72498 144996 72238 144997 72498 144997 72227 144997 72227 144998 72498 144998 72491 144998 72227 144999 72491 144999 72492 144999 72492 145000 72491 145000 71525 145000 71533 145001 72493 145001 72487 145001 72487 145002 72493 145002 72494 145002 72487 145003 72494 145003 72488 145003 72488 145004 72494 145004 73057 145004 72488 145005 73057 145005 72489 145005 72489 145006 73057 145006 72496 145006 72489 145007 72496 145007 72495 145007 72495 145008 72496 145008 72497 145008 72495 145009 72497 145009 72498 145009 72498 145010 72497 145010 73055 145010 72498 145011 73055 145011 72491 145011 72491 145012 73055 145012 73052 145012 72491 145013 73052 145013 71525 145013 71525 145014 73052 145014 73053 145014 72165 145015 71514 145015 72499 145015 72165 145016 72499 145016 72500 145016 72500 145017 72499 145017 72501 145017 72500 145018 72501 145018 72502 145018 72501 145019 72515 145019 72502 145019 72502 145020 72515 145020 72503 145020 72502 145021 72503 145021 72173 145021 72173 145022 72503 145022 72504 145022 72504 145023 72513 145023 72173 145023 72173 145024 72513 145024 72505 145024 72173 145025 72505 145025 72175 145025 72505 145026 72512 145026 72175 145026 72175 145027 72512 145027 72510 145027 72175 145028 72510 145028 72507 145028 71516 145029 71515 145029 72509 145029 72509 145030 71515 145030 72507 145030 72509 145031 72507 145031 72506 145031 72506 145032 72507 145032 72510 145032 72508 145033 71509 145033 71516 145033 71516 145034 72509 145034 72508 145034 72508 145035 72509 145035 72506 145035 72508 145036 72506 145036 72511 145036 72506 145037 72510 145037 72511 145037 72511 145038 72510 145038 72512 145038 72511 145039 72512 145039 72978 145039 72512 145040 72505 145040 72978 145040 72978 145041 72505 145041 72513 145041 72978 145042 72513 145042 72514 145042 72514 145043 72513 145043 72504 145043 72514 145044 72504 145044 72979 145044 72504 145045 72503 145045 72979 145045 72979 145046 72503 145046 72515 145046 72979 145047 72515 145047 72981 145047 71514 145048 72516 145048 72499 145048 72499 145049 72516 145049 72981 145049 72499 145050 72981 145050 72501 145050 72501 145051 72981 145051 72515 145051 72517 145052 71508 145052 72518 145052 72518 145053 71508 145053 72524 145053 72518 145054 72524 145054 72519 145054 72519 145055 72524 145055 72525 145055 72519 145056 72525 145056 72088 145056 72088 145057 72525 145057 72520 145057 72088 145058 72520 145058 72085 145058 72085 145059 72520 145059 72521 145059 72085 145060 72521 145060 72151 145060 72151 145061 72521 145061 72528 145061 72151 145062 72528 145062 72152 145062 72152 145063 72528 145063 72522 145063 71508 145064 72523 145064 72524 145064 72524 145065 72523 145065 73002 145065 72524 145066 73002 145066 72525 145066 72525 145067 73002 145067 72526 145067 72525 145068 72526 145068 72520 145068 72520 145069 72526 145069 72960 145069 72520 145070 72960 145070 72521 145070 72521 145071 72960 145071 72527 145071 72521 145072 72527 145072 72528 145072 72528 145073 72527 145073 72997 145073 72528 145074 72997 145074 72522 145074 72522 145075 72997 145075 72996 145075 71499 145076 72530 145076 72529 145076 72529 145077 72530 145077 72536 145077 72529 145078 72536 145078 72531 145078 72531 145079 72536 145079 72532 145079 72531 145080 72532 145080 72065 145080 72065 145081 72532 145081 72537 145081 72065 145082 72537 145082 72066 145082 72066 145083 72537 145083 72533 145083 72066 145084 72533 145084 72534 145084 72534 145085 72533 145085 72535 145085 72534 145086 72535 145086 71489 145086 71489 145087 72535 145087 71490 145087 72530 145088 71488 145088 72536 145088 72536 145089 71488 145089 73034 145089 72536 145090 73034 145090 72532 145090 72532 145091 73034 145091 73033 145091 72532 145092 73033 145092 72537 145092 72537 145093 73033 145093 73032 145093 72537 145094 73032 145094 72533 145094 72533 145095 73032 145095 72538 145095 72533 145096 72538 145096 72535 145096 72535 145097 72538 145097 72539 145097 72535 145098 72539 145098 71490 145098 71490 145099 72539 145099 73028 145099 71484 145100 72547 145100 72540 145100 72540 145101 72547 145101 72548 145101 72540 145102 72548 145102 72162 145102 72162 145103 72548 145103 72541 145103 72162 145104 72541 145104 72542 145104 72542 145105 72541 145105 72549 145105 72542 145106 72549 145106 72543 145106 72543 145107 72549 145107 72544 145107 72543 145108 72544 145108 72545 145108 72545 145109 72544 145109 72546 145109 72545 145110 72546 145110 72072 145110 72072 145111 72546 145111 71476 145111 72547 145112 73083 145112 72548 145112 72548 145113 73083 145113 73081 145113 72548 145114 73081 145114 72541 145114 72541 145115 73081 145115 73080 145115 72541 145116 73080 145116 72549 145116 72549 145117 73080 145117 73078 145117 72549 145118 73078 145118 72544 145118 72544 145119 73078 145119 72550 145119 72544 145120 72550 145120 72546 145120 72546 145121 72550 145121 72551 145121 72546 145122 72551 145122 71476 145122 71476 145123 72551 145123 73077 145123 72552 145124 72553 145124 72554 145124 72554 145125 72553 145125 72720 145125 72554 145126 72720 145126 72782 145126 72782 145127 72720 145127 72555 145127 72782 145128 72555 145128 72557 145128 72557 145129 72555 145129 72556 145129 72557 145130 72556 145130 72558 145130 72558 145131 72556 145131 72723 145131 72558 145132 72723 145132 72559 145132 72559 145133 72723 145133 72725 145133 72559 145134 72725 145134 71465 145134 71465 145135 72725 145135 71300 145135 72560 145136 71464 145136 72561 145136 72561 145137 71464 145137 72562 145137 72561 145138 72562 145138 72563 145138 72563 145139 72562 145139 72729 145139 72563 145140 72729 145140 72564 145140 72564 145141 72729 145141 72730 145141 72564 145142 72730 145142 72565 145142 72565 145143 72730 145143 72731 145143 72565 145144 72731 145144 72566 145144 72566 145145 72731 145145 72732 145145 72566 145146 72732 145146 72567 145146 72567 145147 72732 145147 72568 145147 72567 145148 72568 145148 71457 145148 71457 145149 72568 145149 71292 145149 72778 145150 71291 145150 72777 145150 72777 145151 71291 145151 72734 145151 72777 145152 72734 145152 72775 145152 72775 145153 72734 145153 72569 145153 72775 145154 72569 145154 72774 145154 72774 145155 72569 145155 72735 145155 72774 145156 72735 145156 72772 145156 72772 145157 72735 145157 72570 145157 72772 145158 72570 145158 72571 145158 72571 145159 72570 145159 72737 145159 72571 145160 72737 145160 72572 145160 72572 145161 72737 145161 72573 145161 71450 145162 72574 145162 72575 145162 72575 145163 72574 145163 72577 145163 72575 145164 72577 145164 72576 145164 72576 145165 72577 145165 72578 145165 72576 145166 72578 145166 72579 145166 72579 145167 72578 145167 72580 145167 72579 145168 72580 145168 72581 145168 72581 145169 72580 145169 72582 145169 72581 145170 72582 145170 72583 145170 72583 145171 72582 145171 72674 145171 72583 145172 72674 145172 72768 145172 72768 145173 72674 145173 72584 145173 72768 145174 72584 145174 71444 145174 71444 145175 72584 145175 72676 145175 72585 145176 71443 145176 72586 145176 72586 145177 71443 145177 72587 145177 72586 145178 72587 145178 72766 145178 72766 145179 72587 145179 72588 145179 72766 145180 72588 145180 72589 145180 72589 145181 72588 145181 72677 145181 72589 145182 72677 145182 72765 145182 72765 145183 72677 145183 72590 145183 72765 145184 72590 145184 72763 145184 72763 145185 72590 145185 72591 145185 72763 145186 72591 145186 72762 145186 72762 145187 72591 145187 72592 145187 72593 145188 71346 145188 72760 145188 72760 145189 71346 145189 72594 145189 72760 145190 72594 145190 72595 145190 72595 145191 72594 145191 72596 145191 72595 145192 72596 145192 72597 145192 72597 145193 72596 145193 72681 145193 72597 145194 72681 145194 72759 145194 72759 145195 72681 145195 72598 145195 72759 145196 72598 145196 72758 145196 72758 145197 72598 145197 72683 145197 72758 145198 72683 145198 71266 145198 71266 145199 72683 145199 72685 145199 71432 145200 72599 145200 72757 145200 72757 145201 72599 145201 72600 145201 72757 145202 72600 145202 72756 145202 72756 145203 72600 145203 72601 145203 72756 145204 72601 145204 72753 145204 72753 145205 72601 145205 72686 145205 72753 145206 72686 145206 72752 145206 72752 145207 72686 145207 72687 145207 72752 145208 72687 145208 72602 145208 72602 145209 72687 145209 72688 145209 72602 145210 72688 145210 72603 145210 72603 145211 72688 145211 71335 145211 71424 145212 72604 145212 72749 145212 72749 145213 72604 145213 72605 145213 72749 145214 72605 145214 72746 145214 72746 145215 72605 145215 72606 145215 72746 145216 72606 145216 72745 145216 72745 145217 72606 145217 72692 145217 72745 145218 72692 145218 72743 145218 72743 145219 72692 145219 72607 145219 72743 145220 72607 145220 72742 145220 72742 145221 72607 145221 72608 145221 72742 145222 72608 145222 71280 145222 71280 145223 72608 145223 71419 145223 72740 145224 71417 145224 72609 145224 72609 145225 71417 145225 72694 145225 72609 145226 72694 145226 72610 145226 72610 145227 72694 145227 72695 145227 72610 145228 72695 145228 72611 145228 72611 145229 72695 145229 72612 145229 72611 145230 72612 145230 72613 145230 72613 145231 72612 145231 72615 145231 72613 145232 72615 145232 72614 145232 72614 145233 72615 145233 72697 145233 72614 145234 72697 145234 72738 145234 72738 145235 72697 145235 72616 145235 71412 145236 72699 145236 72797 145236 72797 145237 72699 145237 72701 145237 72797 145238 72701 145238 72617 145238 72617 145239 72701 145239 72702 145239 72617 145240 72702 145240 72794 145240 72794 145241 72702 145241 72705 145241 72794 145242 72705 145242 72792 145242 72792 145243 72705 145243 72618 145243 72792 145244 72618 145244 72619 145244 72619 145245 72618 145245 72707 145245 72619 145246 72707 145246 72620 145246 72620 145247 72707 145247 71408 145247 71406 145248 71407 145248 72791 145248 72791 145249 71407 145249 72621 145249 72791 145250 72621 145250 72789 145250 72789 145251 72621 145251 72622 145251 72789 145252 72622 145252 72623 145252 72623 145253 72622 145253 72708 145253 72623 145254 72708 145254 72788 145254 72788 145255 72708 145255 72709 145255 72788 145256 72709 145256 72787 145256 72787 145257 72709 145257 72712 145257 72787 145258 72712 145258 71224 145258 71224 145259 72712 145259 72624 145259 71225 145260 72626 145260 72625 145260 72625 145261 72626 145261 72715 145261 72625 145262 72715 145262 72785 145262 72785 145263 72715 145263 72627 145263 72785 145264 72627 145264 72628 145264 72628 145265 72627 145265 72629 145265 72628 145266 72629 145266 72630 145266 72630 145267 72629 145267 72716 145267 72630 145268 72716 145268 72631 145268 72631 145269 72716 145269 72633 145269 72631 145270 72633 145270 72632 145270 72632 145271 72633 145271 72718 145271 72637 145272 72233 145272 72247 145272 72247 145273 72233 145273 72234 145273 72247 145274 72234 145274 72008 145274 72016 145275 72634 145275 72635 145275 72635 145276 72634 145276 72636 145276 72635 145277 72636 145277 72637 145277 72637 145278 72636 145278 72015 145278 72637 145279 72015 145279 72233 145279 72016 145280 72635 145280 72638 145280 72638 145281 72635 145281 72252 145281 72638 145282 72252 145282 72645 145282 72647 145283 72040 145283 72639 145283 72639 145284 72040 145284 72640 145284 72639 145285 72640 145285 72259 145285 72259 145286 72640 145286 72641 145286 72259 145287 72641 145287 72256 145287 72256 145288 72641 145288 72642 145288 72256 145289 72642 145289 72250 145289 72250 145290 72642 145290 72643 145290 72250 145291 72643 145291 72252 145291 72252 145292 72643 145292 72644 145292 72252 145293 72644 145293 72645 145293 72650 145294 72239 145294 72646 145294 72646 145295 72239 145295 72041 145295 72646 145296 72041 145296 72647 145296 72647 145297 72041 145297 72648 145297 72647 145298 72648 145298 72040 145298 72034 145299 72649 145299 72650 145299 72650 145300 72649 145300 72037 145300 72650 145301 72037 145301 72239 145301 72034 145302 72650 145302 72017 145302 72017 145303 72650 145303 72651 145303 72017 145304 72651 145304 72202 145304 72202 145305 72651 145305 72652 145305 72202 145306 72652 145306 72026 145306 72026 145307 72652 145307 72024 145307 72024 145308 72652 145308 72654 145308 72024 145309 72654 145309 72653 145309 72653 145310 72654 145310 71984 145310 72653 145311 71984 145311 72080 145311 72951 145312 71380 145312 72281 145312 72951 145313 72281 145313 72943 145313 72943 145314 72281 145314 72655 145314 72943 145315 72655 145315 72656 145315 72656 145316 72655 145316 72657 145316 72656 145317 72657 145317 72936 145317 72936 145318 72657 145318 72935 145318 72935 145319 72657 145319 72659 145319 72935 145320 72659 145320 72661 145320 72666 145321 73064 145321 72279 145321 72279 145322 73064 145322 72658 145322 72279 145323 72658 145323 72659 145323 72659 145324 72658 145324 72660 145324 72659 145325 72660 145325 72661 145325 72272 145326 72663 145326 72662 145326 72662 145327 72663 145327 72664 145327 72662 145328 72664 145328 72665 145328 72665 145329 72664 145329 72914 145329 72665 145330 72914 145330 72275 145330 72275 145331 72914 145331 72915 145331 72275 145332 72915 145332 72277 145332 72277 145333 72915 145333 72667 145333 72277 145334 72667 145334 72666 145334 72666 145335 72667 145335 72668 145335 72666 145336 72668 145336 73064 145336 72669 145337 73084 145337 72272 145337 72272 145338 73084 145338 72924 145338 72272 145339 72924 145339 72663 145339 72669 145340 72272 145340 72670 145340 72670 145341 72272 145341 72269 145341 72670 145342 72269 145342 73072 145342 73072 145343 72269 145343 72268 145343 73072 145344 72268 145344 72909 145344 72976 145345 72977 145345 72267 145345 72267 145346 72977 145346 72268 145346 72268 145347 72977 145347 72969 145347 72268 145348 72969 145348 72909 145348 72976 145349 72267 145349 72671 145349 72671 145350 72267 145350 71364 145350 72671 145351 71364 145351 73046 145351 72574 145352 72919 145352 72577 145352 72577 145353 72919 145353 72921 145353 72577 145354 72921 145354 72578 145354 72578 145355 72921 145355 72672 145355 72578 145356 72672 145356 72580 145356 72580 145357 72672 145357 72673 145357 72580 145358 72673 145358 72582 145358 72582 145359 72673 145359 73125 145359 72582 145360 73125 145360 72674 145360 72674 145361 73125 145361 72675 145361 72674 145362 72675 145362 72584 145362 72584 145363 72675 145363 72918 145363 72584 145364 72918 145364 72676 145364 72676 145365 72918 145365 72916 145365 71443 145366 71356 145366 72587 145366 72587 145367 71356 145367 73074 145367 72587 145368 73074 145368 72588 145368 72588 145369 73074 145369 73075 145369 72588 145370 73075 145370 72677 145370 72677 145371 73075 145371 72966 145371 72677 145372 72966 145372 72590 145372 72590 145373 72966 145373 72678 145373 72590 145374 72678 145374 72591 145374 72591 145375 72678 145375 73103 145375 72591 145376 73103 145376 72592 145376 72592 145377 73103 145377 71349 145377 71346 145378 71348 145378 72594 145378 72594 145379 71348 145379 72679 145379 72594 145380 72679 145380 72596 145380 72596 145381 72679 145381 72680 145381 72596 145382 72680 145382 72681 145382 72681 145383 72680 145383 72682 145383 72681 145384 72682 145384 72598 145384 72598 145385 72682 145385 72684 145385 72598 145386 72684 145386 72683 145386 72683 145387 72684 145387 72972 145387 72683 145388 72972 145388 72685 145388 72685 145389 72972 145389 72973 145389 72599 145390 72963 145390 72600 145390 72600 145391 72963 145391 72964 145391 72600 145392 72964 145392 72601 145392 72601 145393 72964 145393 72982 145393 72601 145394 72982 145394 72686 145394 72686 145395 72982 145395 72983 145395 72686 145396 72983 145396 72687 145396 72687 145397 72983 145397 73096 145397 72687 145398 73096 145398 72688 145398 72688 145399 73096 145399 72689 145399 72688 145400 72689 145400 71335 145400 71335 145401 72689 145401 71336 145401 72604 145402 72690 145402 72605 145402 72605 145403 72690 145403 72691 145403 72605 145404 72691 145404 72606 145404 72606 145405 72691 145405 73038 145405 72606 145406 73038 145406 72692 145406 72692 145407 73038 145407 73037 145407 72692 145408 73037 145408 72607 145408 72607 145409 73037 145409 72693 145409 72607 145410 72693 145410 72608 145410 72608 145411 72693 145411 72988 145411 72608 145412 72988 145412 71419 145412 71419 145413 72988 145413 72989 145413 71417 145414 73006 145414 72694 145414 72694 145415 73006 145415 73005 145415 72694 145416 73005 145416 72695 145416 72695 145417 73005 145417 73004 145417 72695 145418 73004 145418 72612 145418 72612 145419 73004 145419 72696 145419 72612 145420 72696 145420 72615 145420 72615 145421 72696 145421 73003 145421 72615 145422 73003 145422 72697 145422 72697 145423 73003 145423 72698 145423 72697 145424 72698 145424 72616 145424 72616 145425 72698 145425 71326 145425 72699 145426 72700 145426 72701 145426 72701 145427 72700 145427 72703 145427 72701 145428 72703 145428 72702 145428 72702 145429 72703 145429 72704 145429 72702 145430 72704 145430 72705 145430 72705 145431 72704 145431 72957 145431 72705 145432 72957 145432 72618 145432 72618 145433 72957 145433 72706 145433 72618 145434 72706 145434 72707 145434 72707 145435 72706 145435 72956 145435 72707 145436 72956 145436 71408 145436 71408 145437 72956 145437 71319 145437 71407 145438 73015 145438 72621 145438 72621 145439 73015 145439 73013 145439 72621 145440 73013 145440 72622 145440 72622 145441 73013 145441 73012 145441 72622 145442 73012 145442 72708 145442 72708 145443 73012 145443 72710 145443 72708 145444 72710 145444 72709 145444 72709 145445 72710 145445 72711 145445 72709 145446 72711 145446 72712 145446 72712 145447 72711 145447 72713 145447 72712 145448 72713 145448 72624 145448 72624 145449 72713 145449 71313 145449 72626 145450 72714 145450 72715 145450 72715 145451 72714 145451 72955 145451 72715 145452 72955 145452 72627 145452 72627 145453 72955 145453 72954 145453 72627 145454 72954 145454 72629 145454 72629 145455 72954 145455 72717 145455 72629 145456 72717 145456 72716 145456 72716 145457 72717 145457 72953 145457 72716 145458 72953 145458 72633 145458 72633 145459 72953 145459 72947 145459 72633 145460 72947 145460 72718 145460 72718 145461 72947 145461 72719 145461 72553 145462 73091 145462 72720 145462 72720 145463 73091 145463 72944 145463 72720 145464 72944 145464 72555 145464 72555 145465 72944 145465 72721 145465 72555 145466 72721 145466 72556 145466 72556 145467 72721 145467 72722 145467 72556 145468 72722 145468 72723 145468 72723 145469 72722 145469 72724 145469 72723 145470 72724 145470 72725 145470 72725 145471 72724 145471 72726 145471 72725 145472 72726 145472 71300 145472 71300 145473 72726 145473 71301 145473 71464 145474 72727 145474 72562 145474 72562 145475 72727 145475 73023 145475 72562 145476 73023 145476 72729 145476 72729 145477 73023 145477 72728 145477 72729 145478 72728 145478 72730 145478 72730 145479 72728 145479 73102 145479 72730 145480 73102 145480 72731 145480 72731 145481 73102 145481 73027 145481 72731 145482 73027 145482 72732 145482 72732 145483 73027 145483 73026 145483 72732 145484 73026 145484 72568 145484 72568 145485 73026 145485 72733 145485 72568 145486 72733 145486 71292 145486 71292 145487 72733 145487 71293 145487 71291 145488 72927 145488 72734 145488 72734 145489 72927 145489 72928 145489 72734 145490 72928 145490 72569 145490 72569 145491 72928 145491 72736 145491 72569 145492 72736 145492 72735 145492 72735 145493 72736 145493 72933 145493 72735 145494 72933 145494 72570 145494 72570 145495 72933 145495 72932 145495 72570 145496 72932 145496 72737 145496 72737 145497 72932 145497 72931 145497 72737 145498 72931 145498 72573 145498 72573 145499 72931 145499 73061 145499 72738 145500 71287 145500 72614 145500 72614 145501 71287 145501 72096 145501 72614 145502 72096 145502 72613 145502 72613 145503 72096 145503 72089 145503 72613 145504 72089 145504 72611 145504 72611 145505 72089 145505 72739 145505 72611 145506 72739 145506 72610 145506 72610 145507 72739 145507 72087 145507 72610 145508 72087 145508 72609 145508 72609 145509 72087 145509 72099 145509 72609 145510 72099 145510 72740 145510 72740 145511 72099 145511 71281 145511 71280 145512 72741 145512 72742 145512 72742 145513 72741 145513 72210 145513 72742 145514 72210 145514 72743 145514 72743 145515 72210 145515 72744 145515 72743 145516 72744 145516 72745 145516 72745 145517 72744 145517 72747 145517 72745 145518 72747 145518 72746 145518 72746 145519 72747 145519 72748 145519 72746 145520 72748 145520 72749 145520 72749 145521 72748 145521 72750 145521 72749 145522 72750 145522 71424 145522 71424 145523 72750 145523 72102 145523 72603 145524 72751 145524 72602 145524 72602 145525 72751 145525 72108 145525 72602 145526 72108 145526 72752 145526 72752 145527 72108 145527 72105 145527 72752 145528 72105 145528 72753 145528 72753 145529 72105 145529 72754 145529 72753 145530 72754 145530 72756 145530 72756 145531 72754 145531 72755 145531 72756 145532 72755 145532 72757 145532 72757 145533 72755 145533 72109 145533 72757 145534 72109 145534 71432 145534 71432 145535 72109 145535 72055 145535 71266 145536 72113 145536 72758 145536 72758 145537 72113 145537 72115 145537 72758 145538 72115 145538 72759 145538 72759 145539 72115 145539 72114 145539 72759 145540 72114 145540 72597 145540 72597 145541 72114 145541 72118 145541 72597 145542 72118 145542 72595 145542 72595 145543 72118 145543 72117 145543 72595 145544 72117 145544 72760 145544 72760 145545 72117 145545 72761 145545 72760 145546 72761 145546 72593 145546 72593 145547 72761 145547 72231 145547 72762 145548 71259 145548 72763 145548 72763 145549 71259 145549 72764 145549 72763 145550 72764 145550 72765 145550 72765 145551 72764 145551 72127 145551 72765 145552 72127 145552 72589 145552 72589 145553 72127 145553 72125 145553 72589 145554 72125 145554 72766 145554 72766 145555 72125 145555 72124 145555 72766 145556 72124 145556 72586 145556 72586 145557 72124 145557 72767 145557 72586 145558 72767 145558 72585 145558 72585 145559 72767 145559 71252 145559 71444 145560 72045 145560 72768 145560 72768 145561 72045 145561 72012 145561 72768 145562 72012 145562 72583 145562 72583 145563 72012 145563 72135 145563 72583 145564 72135 145564 72581 145564 72581 145565 72135 145565 72769 145565 72581 145566 72769 145566 72579 145566 72579 145567 72769 145567 72131 145567 72579 145568 72131 145568 72576 145568 72576 145569 72131 145569 72770 145569 72576 145570 72770 145570 72575 145570 72575 145571 72770 145571 72130 145571 72575 145572 72130 145572 71450 145572 71450 145573 72130 145573 71246 145573 72572 145574 72771 145574 72571 145574 72571 145575 72771 145575 72137 145575 72571 145576 72137 145576 72772 145576 72772 145577 72137 145577 72773 145577 72772 145578 72773 145578 72774 145578 72774 145579 72773 145579 72776 145579 72774 145580 72776 145580 72775 145580 72775 145581 72776 145581 72136 145581 72775 145582 72136 145582 72777 145582 72777 145583 72136 145583 72134 145583 72777 145584 72134 145584 72778 145584 72778 145585 72134 145585 72133 145585 71457 145586 72028 145586 72567 145586 72567 145587 72028 145587 72029 145587 72567 145588 72029 145588 72566 145588 72566 145589 72029 145589 72033 145589 72566 145590 72033 145590 72565 145590 72565 145591 72033 145591 72779 145591 72565 145592 72779 145592 72564 145592 72564 145593 72779 145593 72030 145593 72564 145594 72030 145594 72563 145594 72563 145595 72030 145595 72199 145595 72563 145596 72199 145596 72561 145596 72561 145597 72199 145597 72138 145597 72561 145598 72138 145598 72560 145598 72560 145599 72138 145599 72780 145599 71465 145600 72023 145600 72559 145600 72559 145601 72023 145601 72781 145601 72559 145602 72781 145602 72558 145602 72558 145603 72781 145603 72022 145603 72558 145604 72022 145604 72557 145604 72557 145605 72022 145605 72019 145605 72557 145606 72019 145606 72782 145606 72782 145607 72019 145607 72018 145607 72782 145608 72018 145608 72554 145608 72554 145609 72018 145609 72783 145609 72554 145610 72783 145610 72552 145610 72552 145611 72783 145611 71233 145611 72632 145612 72078 145612 72631 145612 72631 145613 72078 145613 72084 145613 72631 145614 72084 145614 72630 145614 72630 145615 72084 145615 72784 145615 72630 145616 72784 145616 72628 145616 72628 145617 72784 145617 72083 145617 72628 145618 72083 145618 72785 145618 72785 145619 72083 145619 72786 145619 72785 145620 72786 145620 72625 145620 72625 145621 72786 145621 72082 145621 72625 145622 72082 145622 71225 145622 71225 145623 72082 145623 72079 145623 71224 145624 72070 145624 72787 145624 72787 145625 72070 145625 72069 145625 72787 145626 72069 145626 72788 145626 72788 145627 72069 145627 72142 145627 72788 145628 72142 145628 72623 145628 72623 145629 72142 145629 72790 145629 72623 145630 72790 145630 72789 145630 72789 145631 72790 145631 72144 145631 72789 145632 72144 145632 72791 145632 72791 145633 72144 145633 72163 145633 72791 145634 72163 145634 71406 145634 71406 145635 72163 145635 71217 145635 72620 145636 72156 145636 72619 145636 72619 145637 72156 145637 72793 145637 72619 145638 72793 145638 72792 145638 72792 145639 72793 145639 72149 145639 72792 145640 72149 145640 72794 145640 72794 145641 72149 145641 72795 145641 72794 145642 72795 145642 72617 145642 72617 145643 72795 145643 72796 145643 72617 145644 72796 145644 72797 145644 72797 145645 72796 145645 72798 145645 72797 145646 72798 145646 71412 145646 71412 145647 72798 145647 72154 145647 71210 145648 72303 145648 72304 145648 71210 145649 72304 145649 72799 145649 72799 145650 72304 145650 72305 145650 72799 145651 72305 145651 72800 145651 72800 145652 72305 145652 72801 145652 72800 145653 72801 145653 71899 145653 71899 145654 72801 145654 72802 145654 71899 145655 72802 145655 72803 145655 72803 145656 72802 145656 72804 145656 72803 145657 72804 145657 71900 145657 71900 145658 72804 145658 72308 145658 71900 145659 72308 145659 71902 145659 71902 145660 72308 145660 72310 145660 71902 145661 72310 145661 71903 145661 71903 145662 72310 145662 72805 145662 71903 145663 72805 145663 71867 145663 71867 145664 72805 145664 72806 145664 71867 145665 72806 145665 72807 145665 72807 145666 72806 145666 72808 145666 72807 145667 72808 145667 71869 145667 71869 145668 72808 145668 72313 145668 71869 145669 72313 145669 71871 145669 71871 145670 72313 145670 72314 145670 71871 145671 72314 145671 72809 145671 72809 145672 72314 145672 72811 145672 72809 145673 72811 145673 72810 145673 72810 145674 72811 145674 72316 145674 72810 145675 72316 145675 71872 145675 71872 145676 72316 145676 72317 145676 71872 145677 72317 145677 72812 145677 72812 145678 72317 145678 72318 145678 72812 145679 72318 145679 72813 145679 72813 145680 72318 145680 72814 145680 72813 145681 72814 145681 72815 145681 72815 145682 72814 145682 71194 145682 72815 145683 71194 145683 72816 145683 72817 145684 71193 145684 72412 145684 72412 145685 71193 145685 72818 145685 72412 145686 72818 145686 72411 145686 72411 145687 72818 145687 71664 145687 72411 145688 71664 145688 72409 145688 72409 145689 71664 145689 72819 145689 72409 145690 72819 145690 72820 145690 72820 145691 72819 145691 71666 145691 72820 145692 71666 145692 72821 145692 72821 145693 71666 145693 71668 145693 72821 145694 71668 145694 72407 145694 72407 145695 71668 145695 71670 145695 72407 145696 71670 145696 72822 145696 72822 145697 71670 145697 71671 145697 72822 145698 71671 145698 72823 145698 72823 145699 71671 145699 72824 145699 72823 145700 72824 145700 72825 145700 72825 145701 72824 145701 71675 145701 72825 145702 71675 145702 72403 145702 72403 145703 71675 145703 71677 145703 72403 145704 71677 145704 72402 145704 72402 145705 71677 145705 72826 145705 72402 145706 72826 145706 72401 145706 72401 145707 72826 145707 72828 145707 72401 145708 72828 145708 72827 145708 72827 145709 72828 145709 71679 145709 72827 145710 71679 145710 72399 145710 72399 145711 71679 145711 71682 145711 72399 145712 71682 145712 72829 145712 72829 145713 71682 145713 71683 145713 72829 145714 71683 145714 72397 145714 72397 145715 71683 145715 71685 145715 72397 145716 71685 145716 72395 145716 72395 145717 71685 145717 71686 145717 71178 145718 72830 145718 72831 145718 71178 145719 72831 145719 71687 145719 71687 145720 72831 145720 72832 145720 71687 145721 72832 145721 71688 145721 71688 145722 72832 145722 72833 145722 71688 145723 72833 145723 71692 145723 71692 145724 72833 145724 72834 145724 71692 145725 72834 145725 71693 145725 71693 145726 72834 145726 72385 145726 71693 145727 72385 145727 71695 145727 71695 145728 72385 145728 72835 145728 71695 145729 72835 145729 72836 145729 72836 145730 72835 145730 72838 145730 72836 145731 72838 145731 72837 145731 72837 145732 72838 145732 72839 145732 72837 145733 72839 145733 72840 145733 72840 145734 72839 145734 72841 145734 72840 145735 72841 145735 71654 145735 71654 145736 72841 145736 72842 145736 71654 145737 72842 145737 71657 145737 71657 145738 72842 145738 72844 145738 71657 145739 72844 145739 72843 145739 72843 145740 72844 145740 72845 145740 72843 145741 72845 145741 72846 145741 72846 145742 72845 145742 72391 145742 72846 145743 72391 145743 72847 145743 72847 145744 72391 145744 72848 145744 72847 145745 72848 145745 71659 145745 71659 145746 72848 145746 72849 145746 71659 145747 72849 145747 72850 145747 72850 145748 72849 145748 72393 145748 72850 145749 72393 145749 72851 145749 72851 145750 72393 145750 72394 145750 72851 145751 72394 145751 71662 145751 71829 145752 72320 145752 72322 145752 71829 145753 72322 145753 72853 145753 72853 145754 72322 145754 72852 145754 72853 145755 72852 145755 72854 145755 72854 145756 72852 145756 72324 145756 72854 145757 72324 145757 72855 145757 72855 145758 72324 145758 72856 145758 72855 145759 72856 145759 72857 145759 72857 145760 72856 145760 72326 145760 72857 145761 72326 145761 72858 145761 72858 145762 72326 145762 72859 145762 72858 145763 72859 145763 71833 145763 71833 145764 72859 145764 72330 145764 71833 145765 72330 145765 72860 145765 72860 145766 72330 145766 72331 145766 72860 145767 72331 145767 72862 145767 72862 145768 72331 145768 72861 145768 72862 145769 72861 145769 71835 145769 71835 145770 72861 145770 72863 145770 71835 145771 72863 145771 72864 145771 72864 145772 72863 145772 72333 145772 72864 145773 72333 145773 71837 145773 71837 145774 72333 145774 72335 145774 71837 145775 72335 145775 72865 145775 72865 145776 72335 145776 72336 145776 72865 145777 72336 145777 71840 145777 71840 145778 72336 145778 72338 145778 71840 145779 72338 145779 72866 145779 72866 145780 72338 145780 72867 145780 72866 145781 72867 145781 72868 145781 72868 145782 72867 145782 72869 145782 72868 145783 72869 145783 71843 145783 71843 145784 72869 145784 72870 145784 71843 145785 72870 145785 72871 145785 72871 145786 72870 145786 72872 145786 72871 145787 72872 145787 72873 145787 72360 145788 71845 145788 72359 145788 72359 145789 71845 145789 71846 145789 72359 145790 71846 145790 72358 145790 72358 145791 71846 145791 71847 145791 72358 145792 71847 145792 72874 145792 72874 145793 71847 145793 71849 145793 72874 145794 71849 145794 72356 145794 72356 145795 71849 145795 71814 145795 72356 145796 71814 145796 72875 145796 72875 145797 71814 145797 71816 145797 72875 145798 71816 145798 72876 145798 72876 145799 71816 145799 72877 145799 72876 145800 72877 145800 72879 145800 72879 145801 72877 145801 72878 145801 72879 145802 72878 145802 72354 145802 72354 145803 72878 145803 72880 145803 72354 145804 72880 145804 72352 145804 72352 145805 72880 145805 71820 145805 72352 145806 71820 145806 72350 145806 72350 145807 71820 145807 71821 145807 72350 145808 71821 145808 72349 145808 72349 145809 71821 145809 72881 145809 72349 145810 72881 145810 72347 145810 72347 145811 72881 145811 72882 145811 72347 145812 72882 145812 72345 145812 72345 145813 72882 145813 72884 145813 72345 145814 72884 145814 72883 145814 72883 145815 72884 145815 71824 145815 72883 145816 71824 145816 72343 145816 72343 145817 71824 145817 71825 145817 72343 145818 71825 145818 72342 145818 72342 145819 71825 145819 72885 145819 72342 145820 72885 145820 71140 145820 71140 145821 72885 145821 71827 145821 72886 145822 72888 145822 72887 145822 72887 145823 72888 145823 71776 145823 72887 145824 71776 145824 72376 145824 72376 145825 71776 145825 72889 145825 72376 145826 72889 145826 72890 145826 72890 145827 72889 145827 72891 145827 72890 145828 72891 145828 72892 145828 72892 145829 72891 145829 71779 145829 72892 145830 71779 145830 72374 145830 72374 145831 71779 145831 71780 145831 72374 145832 71780 145832 72372 145832 72372 145833 71780 145833 71782 145833 72372 145834 71782 145834 72370 145834 72370 145835 71782 145835 72893 145835 72370 145836 72893 145836 72369 145836 72369 145837 72893 145837 72894 145837 72369 145838 72894 145838 72895 145838 72895 145839 72894 145839 72896 145839 72895 145840 72896 145840 72366 145840 72366 145841 72896 145841 71786 145841 72366 145842 71786 145842 72897 145842 72897 145843 71786 145843 71788 145843 72897 145844 71788 145844 72362 145844 72362 145845 71788 145845 71789 145845 72362 145846 71789 145846 72898 145846 72898 145847 71789 145847 71790 145847 72898 145848 71790 145848 72899 145848 72899 145849 71790 145849 71791 145849 72899 145850 71791 145850 72900 145850 72900 145851 71791 145851 72901 145851 72900 145852 72901 145852 72902 145852 72902 145853 72901 145853 72903 145853 72902 145854 72903 145854 71759 145854 71759 145855 72903 145855 71123 145855 73086 145856 72948 145856 72949 145856 72904 145857 72974 145857 73092 145857 72905 145858 73047 145858 72910 145858 72980 145859 72965 145859 72906 145859 71368 145860 71369 145860 72992 145860 71370 145861 72907 145861 71369 145861 73009 145862 72908 145862 73010 145862 73010 145863 72908 145863 73011 145863 72670 145864 72967 145864 72669 145864 72969 145865 73069 145865 72909 145865 72671 145866 73045 145866 72976 145866 72910 145867 73047 145867 73046 145867 71348 145868 71347 145868 72969 145868 72667 145869 71548 145869 72925 145869 72925 145870 71548 145870 72475 145870 72925 145871 72475 145871 72911 145871 73124 145872 72912 145872 73125 145872 72914 145873 72664 145873 71555 145873 71555 145874 72664 145874 71360 145874 71360 145875 71359 145875 71555 145875 71555 145876 71359 145876 71358 145876 71555 145877 71358 145877 72913 145877 72913 145878 71358 145878 72917 145878 71555 145879 71554 145879 72914 145879 72914 145880 71554 145880 71553 145880 72914 145881 71553 145881 72915 145881 72915 145882 71553 145882 71552 145882 72915 145883 71552 145883 72667 145883 72667 145884 71552 145884 71550 145884 72667 145885 71550 145885 71548 145885 71358 145886 72916 145886 72917 145886 72917 145887 72916 145887 72918 145887 72917 145888 72918 145888 72912 145888 72912 145889 72918 145889 72675 145889 72912 145890 72675 145890 73125 145890 72921 145891 72919 145891 72663 145891 72663 145892 72919 145892 72920 145892 72663 145893 72920 145893 72664 145893 72664 145894 72920 145894 71362 145894 72664 145895 71362 145895 71360 145895 72672 145896 72921 145896 72922 145896 72922 145897 72921 145897 72663 145897 72922 145898 72663 145898 72923 145898 72923 145899 72663 145899 72924 145899 72923 145900 72924 145900 73084 145900 73121 145901 72933 145901 72925 145901 72925 145902 72933 145902 72736 145902 72926 145903 72667 145903 72927 145903 72927 145904 72667 145904 72925 145904 72927 145905 72925 145905 72928 145905 72928 145906 72925 145906 72736 145906 72926 145907 71290 145907 72667 145907 72667 145908 71290 145908 72929 145908 72667 145909 72929 145909 72668 145909 72668 145910 72929 145910 72930 145910 72668 145911 72930 145911 73064 145911 73064 145912 72930 145912 73063 145912 73061 145913 72931 145913 73060 145913 73060 145914 72931 145914 72932 145914 73060 145915 72932 145915 72933 145915 72661 145916 73017 145916 72935 145916 72935 145917 73017 145917 72934 145917 72935 145918 72934 145918 72936 145918 72936 145919 72934 145919 71577 145919 72936 145920 71577 145920 71576 145920 71576 145921 71575 145921 72936 145921 72936 145922 71575 145922 72942 145922 72936 145923 72942 145923 72656 145923 72453 145924 71306 145924 72456 145924 72456 145925 71306 145925 72937 145925 72456 145926 72937 145926 72938 145926 72938 145927 72937 145927 72939 145927 72938 145928 72939 145928 72940 145928 72940 145929 72939 145929 72656 145929 72940 145930 72656 145930 72941 145930 72941 145931 72656 145931 72942 145931 72724 145932 72722 145932 72951 145932 72939 145933 71305 145933 72656 145933 72656 145934 71305 145934 71302 145934 72656 145935 71302 145935 72943 145935 72943 145936 71302 145936 71301 145936 72943 145937 71301 145937 72951 145937 72951 145938 71301 145938 72726 145938 72951 145939 72726 145939 72724 145939 73091 145940 73090 145940 72944 145940 72944 145941 73090 145941 73088 145941 72944 145942 73088 145942 72721 145942 71311 145943 72945 145943 72951 145943 72951 145944 72945 145944 71309 145944 72951 145945 71309 145945 72946 145945 72946 145946 71309 145946 72719 145946 72946 145947 72719 145947 72952 145947 72952 145948 72719 145948 72947 145948 72952 145949 72947 145949 72953 145949 71472 145950 72955 145950 72948 145950 72948 145951 72955 145951 72714 145951 72948 145952 72714 145952 72949 145952 72949 145953 72714 145953 72950 145953 72949 145954 72950 145954 71312 145954 71312 145955 71311 145955 72949 145955 72949 145956 71311 145956 72951 145956 72949 145957 72951 145957 73088 145957 73088 145958 72951 145958 72722 145958 73088 145959 72722 145959 72721 145959 71477 145960 72952 145960 71475 145960 71475 145961 72952 145961 72953 145961 71475 145962 72953 145962 71473 145962 71473 145963 72953 145963 72717 145963 71473 145964 72717 145964 71472 145964 71472 145965 72717 145965 72954 145965 71472 145966 72954 145966 72955 145966 73030 145967 73031 145967 71376 145967 71376 145968 73031 145968 72956 145968 72956 145969 72706 145969 71376 145969 71376 145970 72706 145970 72957 145970 71376 145971 72957 145971 72958 145971 72958 145972 72957 145972 72704 145972 72958 145973 72704 145973 72959 145973 72958 145974 72960 145974 71372 145974 71372 145975 72960 145975 72526 145975 71372 145976 72526 145976 73002 145976 72992 145977 71369 145977 73134 145977 73039 145978 72961 145978 71366 145978 71366 145979 72961 145979 72978 145979 71340 145980 73056 145980 72962 145980 72962 145981 73056 145981 73047 145981 72962 145982 73047 145982 72963 145982 72963 145983 73047 145983 72905 145983 72963 145984 72905 145984 72964 145984 72964 145985 72905 145985 72906 145985 72964 145986 72906 145986 72982 145986 72982 145987 72906 145987 72965 145987 73125 145988 72673 145988 73126 145988 71356 145989 71355 145989 72967 145989 73103 145990 72678 145990 73104 145990 73104 145991 72678 145991 72966 145991 72670 145992 73072 145992 72967 145992 72967 145993 73072 145993 72968 145993 72967 145994 72968 145994 71356 145994 71356 145995 72968 145995 73074 145995 71355 145996 71354 145996 72967 145996 72967 145997 71354 145997 71353 145997 72967 145998 71353 145998 73085 145998 73085 145999 71353 145999 71351 145999 73085 146000 71351 146000 73126 146000 73126 146001 71351 146001 71350 146001 73126 146002 71350 146002 73127 146002 73127 146003 71350 146003 71349 146003 73127 146004 71349 146004 73129 146004 72969 146005 71347 146005 73069 146005 73069 146006 71347 146006 72970 146006 73069 146007 72970 146007 72971 146007 72485 146008 71344 146008 72975 146008 71344 146009 72485 146009 72971 146009 72972 146010 73048 146010 72973 146010 72973 146011 73048 146011 73092 146011 72973 146012 73092 146012 72975 146012 72975 146013 73092 146013 72974 146013 72975 146014 72974 146014 72485 146014 72972 146015 72684 146015 73048 146015 73048 146016 72684 146016 72682 146016 73048 146017 72682 146017 73050 146017 73050 146018 72682 146018 72680 146018 73050 146019 72680 146019 73045 146019 73045 146020 72680 146020 72679 146020 73045 146021 72679 146021 72976 146021 72976 146022 72679 146022 71348 146022 72976 146023 71348 146023 72977 146023 72977 146024 71348 146024 72969 146024 72978 146025 72514 146025 71366 146025 71366 146026 72514 146026 72979 146026 71366 146027 72979 146027 72980 146027 72980 146028 72979 146028 72981 146028 72980 146029 72981 146029 72965 146029 72965 146030 72981 146030 72516 146030 72965 146031 72516 146031 72982 146031 72982 146032 72516 146032 72984 146032 72982 146033 72984 146033 72983 146033 72983 146034 72984 146034 72985 146034 72983 146035 72985 146035 73096 146035 73096 146036 72985 146036 71512 146036 71340 146037 72986 146037 73056 146037 73056 146038 72986 146038 71339 146038 73056 146039 71339 146039 73094 146039 71339 146040 71338 146040 73094 146040 73094 146041 71338 146041 72987 146041 73094 146042 72987 146042 71336 146042 72693 146043 72992 146043 72988 146043 72988 146044 72992 146044 73134 146044 72988 146045 73134 146045 72989 146045 72989 146046 73134 146046 73133 146046 72989 146047 73133 146047 72991 146047 72991 146048 73133 146048 72990 146048 72991 146049 72990 146049 71332 146049 72693 146050 73037 146050 72992 146050 72992 146051 73037 146051 73039 146051 72992 146052 73039 146052 71368 146052 71368 146053 73039 146053 71366 146053 71328 146054 72999 146054 73110 146054 72993 146055 71330 146055 73134 146055 72994 146056 72995 146056 73110 146056 73110 146057 72995 146057 72996 146057 73110 146058 72996 146058 72959 146058 72959 146059 72996 146059 72997 146059 72959 146060 72997 146060 72958 146060 72958 146061 72997 146061 72527 146061 72958 146062 72527 146062 72960 146062 71369 146063 72907 146063 73134 146063 73134 146064 72907 146064 73006 146064 73134 146065 73006 146065 72993 146065 72994 146066 73110 146066 72998 146066 72998 146067 73110 146067 72999 146067 72998 146068 72999 146068 71503 146068 71503 146069 72999 146069 73000 146069 71503 146070 73000 146070 73001 146070 73001 146071 73000 146071 71326 146071 73001 146072 71326 146072 72523 146072 72523 146073 71326 146073 72698 146073 72523 146074 72698 146074 73002 146074 73002 146075 72698 146075 73003 146075 73002 146076 73003 146076 71372 146076 71372 146077 73003 146077 72696 146077 71372 146078 72696 146078 71370 146078 71370 146079 72696 146079 73004 146079 71370 146080 73004 146080 72907 146080 72907 146081 73004 146081 73005 146081 72907 146082 73005 146082 73006 146082 73007 146083 73008 146083 73036 146083 73036 146084 73008 146084 71322 146084 71324 146085 73110 146085 72700 146085 72700 146086 73110 146086 72959 146086 72700 146087 72959 146087 72703 146087 72703 146088 72959 146088 72704 146088 73010 146089 72713 146089 72711 146089 73009 146090 73010 146090 73029 146090 73029 146091 73010 146091 72711 146091 73029 146092 72711 146092 72710 146092 71317 146093 71315 146093 73082 146093 73082 146094 71315 146094 71314 146094 72713 146095 73010 146095 71313 146095 71313 146096 73010 146096 73011 146096 71313 146097 73011 146097 73079 146097 73016 146098 73015 146098 73097 146098 73097 146099 73015 146099 71318 146099 73012 146100 71485 146100 73028 146100 71485 146101 73012 146101 73014 146101 73012 146102 73013 146102 73014 146102 73014 146103 73013 146103 73015 146103 73014 146104 73015 146104 71486 146104 71486 146105 73015 146105 73016 146105 71486 146106 73016 146106 71487 146106 72661 146107 72660 146107 73017 146107 73017 146108 72660 146108 73018 146108 73017 146109 73018 146109 73019 146109 73019 146110 73018 146110 71298 146110 73020 146111 73021 146111 72466 146111 72466 146112 73021 146112 72467 146112 72467 146113 73021 146113 71298 146113 72467 146114 71298 146114 73022 146114 73022 146115 71298 146115 73018 146115 73022 146116 73018 146116 73067 146116 73067 146117 73018 146117 72660 146117 73067 146118 72660 146118 72658 146118 73102 146119 72728 146119 73101 146119 73101 146120 72728 146120 73023 146120 73101 146121 73023 146121 73020 146121 73020 146122 73023 146122 72727 146122 73020 146123 72727 146123 73021 146123 73019 146124 71295 146124 73017 146124 73017 146125 71295 146125 73024 146125 73017 146126 73024 146126 72934 146126 72934 146127 73024 146127 71293 146127 72934 146128 71293 146128 71577 146128 71577 146129 71293 146129 72733 146129 71577 146130 72733 146130 73025 146130 73025 146131 72733 146131 73026 146131 73025 146132 73026 146132 71580 146132 71580 146133 73026 146133 73027 146133 71580 146134 73027 146134 73102 146134 72710 146135 73012 146135 73029 146135 73029 146136 73012 146136 73028 146136 73029 146137 73028 146137 73009 146137 73009 146138 73028 146138 72539 146138 73009 146139 72539 146139 73030 146139 73030 146140 72539 146140 72538 146140 73030 146141 72538 146141 73031 146141 73031 146142 72538 146142 73032 146142 73031 146143 73032 146143 72956 146143 72956 146144 73032 146144 73033 146144 72956 146145 73033 146145 71319 146145 71319 146146 73033 146146 73034 146146 71319 146147 73034 146147 71321 146147 71321 146148 73034 146148 71488 146148 71321 146149 71488 146149 71322 146149 71322 146150 71488 146150 73035 146150 71322 146151 73035 146151 73036 146151 73036 146152 73035 146152 73112 146152 73037 146153 73038 146153 73039 146153 73039 146154 73038 146154 72691 146154 73039 146155 72691 146155 72961 146155 72961 146156 72691 146156 72690 146156 72961 146157 72690 146157 72978 146157 72978 146158 72690 146158 73040 146158 72978 146159 73040 146159 72511 146159 72511 146160 73040 146160 73041 146160 72511 146161 73041 146161 72508 146161 72508 146162 73041 146162 71333 146162 72508 146163 71333 146163 71509 146163 71509 146164 71333 146164 73042 146164 71509 146165 73042 146165 73043 146165 73043 146166 73042 146166 73044 146166 73043 146167 73044 146167 73095 146167 72671 146168 73046 146168 73045 146168 73045 146169 73046 146169 73047 146169 73045 146170 73047 146170 72493 146170 72493 146171 73047 146171 72494 146171 71521 146172 73048 146172 71522 146172 71522 146173 73048 146173 73050 146173 71522 146174 73050 146174 73049 146174 73049 146175 73050 146175 73045 146175 73049 146176 73045 146176 73051 146176 73051 146177 73045 146177 72493 146177 73052 146178 73094 146178 73053 146178 73053 146179 73094 146179 73048 146179 73053 146180 73048 146180 73054 146180 73054 146181 73048 146181 71521 146181 73052 146182 73055 146182 73094 146182 73094 146183 73055 146183 72497 146183 73094 146184 72497 146184 73056 146184 73056 146185 72497 146185 72496 146185 73056 146186 72496 146186 73047 146186 73047 146187 72496 146187 73057 146187 73047 146188 73057 146188 72494 146188 72451 146189 73058 146189 72452 146189 72452 146190 73058 146190 73089 146190 72452 146191 73089 146191 72453 146191 73123 146192 73122 146192 73059 146192 73059 146193 73122 146193 73120 146193 73059 146194 73120 146194 72463 146194 73060 146195 71565 146195 73061 146195 73061 146196 71565 146196 73062 146196 73061 146197 73062 146197 73063 146197 73063 146198 73062 146198 71563 146198 73063 146199 71563 146199 73064 146199 73064 146200 71563 146200 73065 146200 73064 146201 73065 146201 72658 146201 72658 146202 73065 146202 73066 146202 72658 146203 73066 146203 73067 146203 73067 146204 73066 146204 73068 146204 73067 146205 73068 146205 73022 146205 72485 146206 72483 146206 72971 146206 72971 146207 72483 146207 72481 146207 72971 146208 72481 146208 73069 146208 73069 146209 72481 146209 73070 146209 73069 146210 73070 146210 72909 146210 72909 146211 73070 146211 73071 146211 72909 146212 73071 146212 73072 146212 73072 146213 73071 146213 73073 146213 73072 146214 73073 146214 72968 146214 72968 146215 73073 146215 71537 146215 72968 146216 71537 146216 73074 146216 73074 146217 71537 146217 71535 146217 73074 146218 71535 146218 73075 146218 73075 146219 71535 146219 71534 146219 73075 146220 71534 146220 72966 146220 72966 146221 71534 146221 73076 146221 72966 146222 73076 146222 73104 146222 73104 146223 73076 146223 73107 146223 71477 146224 73077 146224 72952 146224 72952 146225 73077 146225 72551 146225 72952 146226 72551 146226 72908 146226 72908 146227 72551 146227 72550 146227 72908 146228 72550 146228 73011 146228 73011 146229 72550 146229 73078 146229 73011 146230 73078 146230 73079 146230 73079 146231 73078 146231 73080 146231 73079 146232 73080 146232 71314 146232 71314 146233 73080 146233 73081 146233 71314 146234 73081 146234 73082 146234 73082 146235 73081 146235 73083 146235 73082 146236 73083 146236 73100 146236 72669 146237 72967 146237 73084 146237 73084 146238 72967 146238 73085 146238 73084 146239 73085 146239 72923 146239 72923 146240 73085 146240 73126 146240 72923 146241 73126 146241 72922 146241 72922 146242 73126 146242 72673 146242 72922 146243 72673 146243 72672 146243 73083 146244 73086 146244 73100 146244 73100 146245 73086 146245 72949 146245 73100 146246 72949 146246 73087 146246 73087 146247 72949 146247 73088 146247 73087 146248 73088 146248 73089 146248 73089 146249 73088 146249 73090 146249 73089 146250 73090 146250 72453 146250 72453 146251 73090 146251 73091 146251 72453 146252 73091 146252 71306 146252 73076 146253 72904 146253 73107 146253 73107 146254 72904 146254 73092 146254 73107 146255 73092 146255 73093 146255 73093 146256 73092 146256 73048 146256 73093 146257 73048 146257 73044 146257 73044 146258 73048 146258 73094 146258 73044 146259 73094 146259 73095 146259 73095 146260 73094 146260 71336 146260 73095 146261 71336 146261 71512 146261 71512 146262 71336 146262 72689 146262 71512 146263 72689 146263 73096 146263 71318 146264 71317 146264 73097 146264 73097 146265 71317 146265 73082 146265 73097 146266 73082 146266 73098 146266 73098 146267 73082 146267 73100 146267 73098 146268 73100 146268 73099 146268 73099 146269 73100 146269 73087 146269 73099 146270 73087 146270 73108 146270 73108 146271 73087 146271 73089 146271 73108 146272 73089 146272 73101 146272 73101 146273 73089 146273 73058 146273 73101 146274 73058 146274 73102 146274 73102 146275 73058 146275 72451 146275 73102 146276 72451 146276 71580 146276 71349 146277 73103 146277 73129 146277 73129 146278 73103 146278 73104 146278 73129 146279 73104 146279 73105 146279 73105 146280 73104 146280 73107 146280 73105 146281 73107 146281 73106 146281 73106 146282 73107 146282 73093 146282 73106 146283 73093 146283 73131 146283 73131 146284 73093 146284 73044 146284 73131 146285 73044 146285 72990 146285 72990 146286 73044 146286 73042 146286 72990 146287 73042 146287 71332 146287 71332 146288 73042 146288 71333 146288 72466 146289 72463 146289 73020 146289 73020 146290 72463 146290 73120 146290 73020 146291 73120 146291 73101 146291 73101 146292 73120 146292 73118 146292 73101 146293 73118 146293 73108 146293 73108 146294 73118 146294 73117 146294 73108 146295 73117 146295 73099 146295 73099 146296 73117 146296 73115 146296 73099 146297 73115 146297 73098 146297 73098 146298 73115 146298 73109 146298 73098 146299 73109 146299 73097 146299 73097 146300 73109 146300 73113 146300 73097 146301 73113 146301 73016 146301 73016 146302 73113 146302 73112 146302 73016 146303 73112 146303 71487 146303 71487 146304 73112 146304 73035 146304 71324 146305 73007 146305 73110 146305 73110 146306 73007 146306 73036 146306 73110 146307 73036 146307 73111 146307 73111 146308 73036 146308 73112 146308 73111 146309 73112 146309 73132 146309 73132 146310 73112 146310 73113 146310 73132 146311 73113 146311 73130 146311 73130 146312 73113 146312 73109 146312 73130 146313 73109 146313 73114 146313 73114 146314 73109 146314 73115 146314 73114 146315 73115 146315 73128 146315 73128 146316 73115 146316 73117 146316 73128 146317 73117 146317 73116 146317 73116 146318 73117 146318 73118 146318 73116 146319 73118 146319 73119 146319 73119 146320 73118 146320 73120 146320 73119 146321 73120 146321 73121 146321 73121 146322 73120 146322 73122 146322 73121 146323 73122 146323 72933 146323 72933 146324 73122 146324 73123 146324 72933 146325 73123 146325 73060 146325 72911 146326 73124 146326 72925 146326 72925 146327 73124 146327 73125 146327 72925 146328 73125 146328 73121 146328 73121 146329 73125 146329 73126 146329 73121 146330 73126 146330 73119 146330 73119 146331 73126 146331 73127 146331 73119 146332 73127 146332 73116 146332 73116 146333 73127 146333 73129 146333 73116 146334 73129 146334 73128 146334 73128 146335 73129 146335 73105 146335 73128 146336 73105 146336 73114 146336 73114 146337 73105 146337 73106 146337 73114 146338 73106 146338 73130 146338 73130 146339 73106 146339 73131 146339 73130 146340 73131 146340 73132 146340 73132 146341 73131 146341 72990 146341 73132 146342 72990 146342 73111 146342 73111 146343 72990 146343 73133 146343 73111 146344 73133 146344 73110 146344 73110 146345 73133 146345 73134 146345 73110 146346 73134 146346 71328 146346 71328 146347 73134 146347 71330 146347 73142 146348 73536 146348 73135 146348 73138 146349 73429 146349 73136 146349 73444 146350 73429 146350 73442 146350 73442 146351 73429 146351 73138 146351 73442 146352 73138 146352 73445 146352 73445 146353 73138 146353 73439 146353 73480 146354 73441 146354 73138 146354 73138 146355 73441 146355 73137 146355 73137 146356 73459 146356 73138 146356 73138 146357 73459 146357 73458 146357 73138 146358 73458 146358 73439 146358 73504 146359 73498 146359 73142 146359 73142 146360 73498 146360 73497 146360 73537 146361 73536 146361 73139 146361 73139 146362 73536 146362 73142 146362 73139 146363 73142 146363 73494 146363 73494 146364 73142 146364 73497 146364 73432 146365 73140 146365 73142 146365 73142 146366 73140 146366 73141 146366 73142 146367 73141 146367 73504 146367 73432 146368 73142 146368 73143 146368 73143 146369 73142 146369 73135 146369 73143 146370 73135 146370 73144 146370 73144 146371 73135 146371 73145 146371 73144 146372 73145 146372 73136 146372 73136 146373 73145 146373 73152 146373 73136 146374 73152 146374 73138 146374 73138 146375 73152 146375 73151 146375 73138 146376 73151 146376 73480 146376 73146 146377 73491 146377 73160 146377 73147 146378 73157 146378 73158 146378 73148 146379 73156 146379 73162 146379 73479 146380 73149 146380 73150 146380 73149 146381 73151 146381 73150 146381 73150 146382 73151 146382 73152 146382 73150 146383 73152 146383 73155 146383 73155 146384 73152 146384 73145 146384 73155 146385 73145 146385 73153 146385 73153 146386 73145 146386 73135 146386 73153 146387 73135 146387 73154 146387 73154 146388 73135 146388 73536 146388 73154 146389 73147 146389 73153 146389 73153 146390 73147 146390 73158 146390 73153 146391 73158 146391 73155 146391 73155 146392 73158 146392 73159 146392 73155 146393 73159 146393 73150 146393 73150 146394 73159 146394 73162 146394 73150 146395 73162 146395 73479 146395 73479 146396 73162 146396 73156 146396 73157 146397 73146 146397 73158 146397 73158 146398 73146 146398 73160 146398 73158 146399 73160 146399 73159 146399 73159 146400 73160 146400 73161 146400 73159 146401 73161 146401 73162 146401 73162 146402 73161 146402 73435 146402 73162 146403 73435 146403 73148 146403 73148 146404 73435 146404 73434 146404 73385 146405 73384 146405 73163 146405 73385 146406 73163 146406 73183 146406 73163 146407 73206 146407 73183 146407 73183 146408 73206 146408 73204 146408 73183 146409 73204 146409 73184 146409 73184 146410 73204 146410 73164 146410 73164 146411 73204 146411 73165 146411 73164 146412 73165 146412 73166 146412 73201 146413 73167 146413 73202 146413 73202 146414 73167 146414 73393 146414 73202 146415 73393 146415 73168 146415 73168 146416 73393 146416 73170 146416 73168 146417 73170 146417 73169 146417 73169 146418 73170 146418 73171 146418 73166 146419 73165 146419 73172 146419 73172 146420 73165 146420 73173 146420 73172 146421 73173 146421 73396 146421 73173 146422 73196 146422 73396 146422 73396 146423 73196 146423 73191 146423 73396 146424 73191 146424 73389 146424 73389 146425 73191 146425 73193 146425 73389 146426 73193 146426 73390 146426 73390 146427 73193 146427 73174 146427 73390 146428 73174 146428 73178 146428 73169 146429 73171 146429 73175 146429 73175 146430 73171 146430 73177 146430 73175 146431 73177 146431 73176 146431 73176 146432 73177 146432 73178 146432 73176 146433 73178 146433 73187 146433 73187 146434 73178 146434 73174 146434 73163 146435 73384 146435 73197 146435 73197 146436 73384 146436 73179 146436 73197 146437 73179 146437 73199 146437 73199 146438 73179 146438 73180 146438 73199 146439 73180 146439 73200 146439 73200 146440 73180 146440 73181 146440 73200 146441 73181 146441 73363 146441 73363 146442 73181 146442 73387 146442 73377 146443 73385 146443 73182 146443 73182 146444 73385 146444 73183 146444 73182 146445 73183 146445 73185 146445 73185 146446 73183 146446 73184 146446 73185 146447 73184 146447 73186 146447 73186 146448 73184 146448 73164 146448 73186 146449 73164 146449 73376 146449 73173 146450 73165 146450 73194 146450 73322 146451 73169 146451 73223 146451 73223 146452 73169 146452 73175 146452 73223 146453 73175 146453 73226 146453 73226 146454 73175 146454 73227 146454 73175 146455 73176 146455 73227 146455 73227 146456 73176 146456 73187 146456 73227 146457 73187 146457 73229 146457 73229 146458 73187 146458 73174 146458 73229 146459 73174 146459 73231 146459 73231 146460 73174 146460 73188 146460 73188 146461 73174 146461 73193 146461 73188 146462 73193 146462 73189 146462 73190 146463 73225 146463 73191 146463 73191 146464 73225 146464 73192 146464 73191 146465 73192 146465 73193 146465 73193 146466 73192 146466 73232 146466 73193 146467 73232 146467 73189 146467 73194 146468 73195 146468 73173 146468 73173 146469 73195 146469 73190 146469 73173 146470 73190 146470 73196 146470 73196 146471 73190 146471 73191 146471 73208 146472 73163 146472 73284 146472 73284 146473 73163 146473 73197 146473 73284 146474 73197 146474 73198 146474 73198 146475 73197 146475 73199 146475 73198 146476 73199 146476 73282 146476 73282 146477 73199 146477 73280 146477 73280 146478 73199 146478 73200 146478 73280 146479 73200 146479 73281 146479 73281 146480 73200 146480 73287 146480 73287 146481 73200 146481 73363 146481 73287 146482 73363 146482 73289 146482 73329 146483 73201 146483 73323 146483 73323 146484 73201 146484 73202 146484 73323 146485 73202 146485 73203 146485 73203 146486 73202 146486 73168 146486 73203 146487 73168 146487 73322 146487 73322 146488 73168 146488 73169 146488 73194 146489 73165 146489 73204 146489 73194 146490 73204 146490 73205 146490 73205 146491 73204 146491 73206 146491 73205 146492 73206 146492 73207 146492 73207 146493 73206 146493 73163 146493 73207 146494 73163 146494 73208 146494 73209 146495 73358 146495 73320 146495 73344 146496 73209 146496 73222 146496 73342 146497 73210 146497 73343 146497 73343 146498 73210 146498 73211 146498 73343 146499 73211 146499 73212 146499 73212 146500 73211 146500 73217 146500 73212 146501 73217 146501 73213 146501 73213 146502 73217 146502 73219 146502 73215 146503 73216 146503 73218 146503 73256 146504 73258 146504 73214 146504 73214 146505 73258 146505 73259 146505 73214 146506 73259 146506 73215 146506 73215 146507 73259 146507 73334 146507 73215 146508 73334 146508 73216 146508 73250 146509 73210 146509 73247 146509 73247 146510 73210 146510 73342 146510 73247 146511 73342 146511 73346 146511 73250 146512 73256 146512 73210 146512 73210 146513 73256 146513 73214 146513 73210 146514 73214 146514 73211 146514 73211 146515 73214 146515 73215 146515 73211 146516 73215 146516 73217 146516 73217 146517 73215 146517 73218 146517 73217 146518 73218 146518 73219 146518 73251 146519 73254 146519 73250 146519 73250 146520 73254 146520 73220 146520 73250 146521 73220 146521 73256 146521 73221 146522 73344 146522 73248 146522 73248 146523 73344 146523 73222 146523 73248 146524 73222 146524 73249 146524 73249 146525 73222 146525 73245 146525 73233 146526 73228 146526 73230 146526 73226 146527 73253 146527 73223 146527 73223 146528 73253 146528 73252 146528 73223 146529 73252 146529 73322 146529 73244 146530 73195 146530 73224 146530 73224 146531 73195 146531 73194 146531 73224 146532 73194 146532 73340 146532 73232 146533 73192 146533 73241 146533 73241 146534 73192 146534 73225 146534 73241 146535 73225 146535 73244 146535 73244 146536 73225 146536 73190 146536 73244 146537 73190 146537 73195 146537 73226 146538 73227 146538 73228 146538 73228 146539 73227 146539 73229 146539 73228 146540 73229 146540 73230 146540 73230 146541 73229 146541 73231 146541 73230 146542 73231 146542 73239 146542 73239 146543 73231 146543 73188 146543 73239 146544 73188 146544 73241 146544 73241 146545 73188 146545 73189 146545 73241 146546 73189 146546 73232 146546 73233 146547 73235 146547 73234 146547 73234 146548 73235 146548 73240 146548 73234 146549 73240 146549 73236 146549 73236 146550 73240 146550 73242 146550 73236 146551 73242 146551 73255 146551 73255 146552 73242 146552 73243 146552 73255 146553 73243 146553 73257 146553 73257 146554 73243 146554 73237 146554 73257 146555 73237 146555 73260 146555 73260 146556 73237 146556 73238 146556 73260 146557 73238 146557 73336 146557 73233 146558 73230 146558 73235 146558 73235 146559 73230 146559 73239 146559 73235 146560 73239 146560 73240 146560 73240 146561 73239 146561 73241 146561 73240 146562 73241 146562 73242 146562 73242 146563 73241 146563 73244 146563 73242 146564 73244 146564 73243 146564 73243 146565 73244 146565 73224 146565 73243 146566 73224 146566 73237 146566 73237 146567 73224 146567 73340 146567 73237 146568 73340 146568 73238 146568 73209 146569 73320 146569 73222 146569 73222 146570 73320 146570 73319 146570 73222 146571 73319 146571 73245 146571 73245 146572 73319 146572 73326 146572 73245 146573 73326 146573 73246 146573 73346 146574 73221 146574 73247 146574 73247 146575 73221 146575 73248 146575 73247 146576 73248 146576 73250 146576 73250 146577 73248 146577 73249 146577 73250 146578 73249 146578 73251 146578 73251 146579 73249 146579 73245 146579 73251 146580 73245 146580 73253 146580 73253 146581 73245 146581 73246 146581 73253 146582 73246 146582 73252 146582 73226 146583 73228 146583 73253 146583 73253 146584 73228 146584 73233 146584 73253 146585 73233 146585 73251 146585 73251 146586 73233 146586 73234 146586 73251 146587 73234 146587 73254 146587 73254 146588 73234 146588 73236 146588 73254 146589 73236 146589 73220 146589 73220 146590 73236 146590 73255 146590 73220 146591 73255 146591 73256 146591 73256 146592 73255 146592 73257 146592 73256 146593 73257 146593 73258 146593 73258 146594 73257 146594 73260 146594 73258 146595 73260 146595 73259 146595 73259 146596 73260 146596 73336 146596 73259 146597 73336 146597 73334 146597 73293 146598 73329 146598 73328 146598 73315 146599 73269 146599 73267 146599 73295 146600 73311 146600 73266 146600 73349 146601 73348 146601 73270 146601 73261 146602 73279 146602 73262 146602 73262 146603 73279 146603 73263 146603 73262 146604 73263 146604 73350 146604 73350 146605 73263 146605 73264 146605 73350 146606 73264 146606 73265 146606 73265 146607 73264 146607 73276 146607 73270 146608 73348 146608 73268 146608 73268 146609 73348 146609 73271 146609 73268 146610 73271 146610 73267 146610 73312 146611 73266 146611 73347 146611 73267 146612 73269 146612 73268 146612 73268 146613 73269 146613 73314 146613 73268 146614 73314 146614 73270 146614 73271 146615 73272 146615 73267 146615 73267 146616 73272 146616 73277 146616 73267 146617 73277 146617 73315 146617 73315 146618 73277 146618 73278 146618 73315 146619 73278 146619 73274 146619 73274 146620 73278 146620 73273 146620 73274 146621 73273 146621 73316 146621 73316 146622 73273 146622 73333 146622 73316 146623 73333 146623 73275 146623 73272 146624 73276 146624 73277 146624 73277 146625 73276 146625 73264 146625 73277 146626 73264 146626 73278 146626 73278 146627 73264 146627 73263 146627 73278 146628 73263 146628 73273 146628 73273 146629 73263 146629 73279 146629 73273 146630 73279 146630 73333 146630 73306 146631 73280 146631 73281 146631 73306 146632 73281 146632 73288 146632 73280 146633 73306 146633 73282 146633 73282 146634 73306 146634 73283 146634 73282 146635 73283 146635 73198 146635 73198 146636 73283 146636 73286 146636 73198 146637 73286 146637 73284 146637 73208 146638 73284 146638 73285 146638 73285 146639 73284 146639 73286 146639 73285 146640 73286 146640 73337 146640 73281 146641 73287 146641 73288 146641 73288 146642 73287 146642 73289 146642 73288 146643 73289 146643 73308 146643 73308 146644 73289 146644 73290 146644 73308 146645 73290 146645 73291 146645 73291 146646 73290 146646 73362 146646 73291 146647 73362 146647 73292 146647 73292 146648 73360 146648 73291 146648 73291 146649 73360 146649 73293 146649 73291 146650 73293 146650 73310 146650 73310 146651 73293 146651 73328 146651 73310 146652 73328 146652 73294 146652 73266 146653 73312 146653 73295 146653 73295 146654 73312 146654 73313 146654 73295 146655 73313 146655 73296 146655 73296 146656 73313 146656 73297 146656 73296 146657 73297 146657 73309 146657 73309 146658 73297 146658 73299 146658 73309 146659 73299 146659 73298 146659 73298 146660 73299 146660 73300 146660 73298 146661 73300 146661 73307 146661 73307 146662 73300 146662 73301 146662 73307 146663 73301 146663 73305 146663 73305 146664 73301 146664 73302 146664 73305 146665 73302 146665 73304 146665 73304 146666 73302 146666 73303 146666 73304 146667 73303 146667 73337 146667 73337 146668 73286 146668 73304 146668 73304 146669 73286 146669 73283 146669 73304 146670 73283 146670 73305 146670 73305 146671 73283 146671 73306 146671 73305 146672 73306 146672 73307 146672 73307 146673 73306 146673 73288 146673 73307 146674 73288 146674 73298 146674 73298 146675 73288 146675 73308 146675 73298 146676 73308 146676 73309 146676 73309 146677 73308 146677 73291 146677 73309 146678 73291 146678 73296 146678 73296 146679 73291 146679 73310 146679 73296 146680 73310 146680 73295 146680 73295 146681 73310 146681 73294 146681 73295 146682 73294 146682 73311 146682 73347 146683 73349 146683 73312 146683 73312 146684 73349 146684 73270 146684 73312 146685 73270 146685 73313 146685 73313 146686 73270 146686 73314 146686 73313 146687 73314 146687 73297 146687 73297 146688 73314 146688 73269 146688 73297 146689 73269 146689 73299 146689 73299 146690 73269 146690 73315 146690 73299 146691 73315 146691 73300 146691 73300 146692 73315 146692 73274 146692 73300 146693 73274 146693 73301 146693 73301 146694 73274 146694 73316 146694 73301 146695 73316 146695 73302 146695 73302 146696 73316 146696 73275 146696 73302 146697 73275 146697 73303 146697 73317 146698 73324 146698 73325 146698 73353 146699 73347 146699 73266 146699 73320 146700 73358 146700 73318 146700 73326 146701 73319 146701 73317 146701 73317 146702 73319 146702 73320 146702 73320 146703 73318 146703 73317 146703 73317 146704 73318 146704 73357 146704 73317 146705 73357 146705 73324 146705 73324 146706 73357 146706 73321 146706 73324 146707 73321 146707 73353 146707 73252 146708 73246 146708 73327 146708 73327 146709 73246 146709 73326 146709 73322 146710 73252 146710 73203 146710 73203 146711 73252 146711 73327 146711 73203 146712 73327 146712 73323 146712 73353 146713 73266 146713 73324 146713 73324 146714 73266 146714 73311 146714 73324 146715 73311 146715 73325 146715 73325 146716 73311 146716 73294 146716 73325 146717 73294 146717 73328 146717 73326 146718 73317 146718 73327 146718 73327 146719 73317 146719 73325 146719 73327 146720 73325 146720 73323 146720 73323 146721 73325 146721 73328 146721 73323 146722 73328 146722 73329 146722 73285 146723 73337 146723 73338 146723 73354 146724 73355 146724 73330 146724 73261 146725 73352 146725 73279 146725 73279 146726 73352 146726 73332 146726 73213 146727 73219 146727 73356 146727 73356 146728 73219 146728 73355 146728 73339 146729 73331 146729 73335 146729 73335 146730 73331 146730 73332 146730 73355 146731 73219 146731 73330 146731 73330 146732 73219 146732 73218 146732 73330 146733 73218 146733 73216 146733 73352 146734 73354 146734 73332 146734 73332 146735 73354 146735 73330 146735 73332 146736 73330 146736 73335 146736 73335 146737 73330 146737 73216 146737 73337 146738 73303 146738 73331 146738 73331 146739 73303 146739 73275 146739 73331 146740 73275 146740 73332 146740 73332 146741 73275 146741 73333 146741 73332 146742 73333 146742 73279 146742 73205 146743 73207 146743 73338 146743 73338 146744 73207 146744 73208 146744 73338 146745 73208 146745 73285 146745 73216 146746 73334 146746 73335 146746 73335 146747 73334 146747 73336 146747 73335 146748 73336 146748 73339 146748 73339 146749 73336 146749 73238 146749 73339 146750 73238 146750 73340 146750 73337 146751 73331 146751 73338 146751 73338 146752 73331 146752 73339 146752 73338 146753 73339 146753 73205 146753 73205 146754 73339 146754 73340 146754 73205 146755 73340 146755 73194 146755 73341 146756 73213 146756 73356 146756 73341 146757 73346 146757 73342 146757 73342 146758 73343 146758 73341 146758 73341 146759 73343 146759 73212 146759 73341 146760 73212 146760 73213 146760 73359 146761 73344 146761 73341 146761 73341 146762 73344 146762 73345 146762 73341 146763 73345 146763 73346 146763 73351 146764 73347 146764 73353 146764 73271 146765 73348 146765 73351 146765 73351 146766 73348 146766 73349 146766 73351 146767 73349 146767 73347 146767 73261 146768 73262 146768 73351 146768 73351 146769 73262 146769 73350 146769 73351 146770 73350 146770 73265 146770 73265 146771 73276 146771 73351 146771 73351 146772 73276 146772 73272 146772 73351 146773 73272 146773 73271 146773 73261 146774 73351 146774 73352 146774 73352 146775 73351 146775 73353 146775 73352 146776 73353 146776 73354 146776 73354 146777 73353 146777 73321 146777 73354 146778 73321 146778 73355 146778 73355 146779 73321 146779 73357 146779 73355 146780 73357 146780 73356 146780 73356 146781 73357 146781 73318 146781 73356 146782 73318 146782 73341 146782 73341 146783 73318 146783 73358 146783 73341 146784 73358 146784 73359 146784 73293 146785 73360 146785 73361 146785 73360 146786 73292 146786 73361 146786 73361 146787 73292 146787 73362 146787 73361 146788 73362 146788 73363 146788 73363 146789 73362 146789 73290 146789 73363 146790 73290 146790 73289 146790 73361 146791 73364 146791 73293 146791 73293 146792 73364 146792 73201 146792 73293 146793 73201 146793 73329 146793 73363 146794 73387 146794 73361 146794 73361 146795 73387 146795 73365 146795 73361 146796 73365 146796 73364 146796 73364 146797 73365 146797 73366 146797 73364 146798 73366 146798 73201 146798 73201 146799 73366 146799 73167 146799 73518 146800 73367 146800 73371 146800 73515 146801 73513 146801 73368 146801 73371 146802 73367 146802 73368 146802 73368 146803 73367 146803 73516 146803 73368 146804 73516 146804 73515 146804 73372 146805 73437 146805 73491 146805 73491 146806 73369 146806 73372 146806 73372 146807 73369 146807 73521 146807 73372 146808 73521 146808 73371 146808 73371 146809 73521 146809 73519 146809 73371 146810 73519 146810 73518 146810 73368 146811 73370 146811 73371 146811 73371 146812 73370 146812 73391 146812 73371 146813 73391 146813 73372 146813 73372 146814 73391 146814 73373 146814 73372 146815 73373 146815 73437 146815 73437 146816 73373 146816 73403 146816 73374 146817 73395 146817 73375 146817 73375 146818 73395 146818 73397 146818 73375 146819 73397 146819 73368 146819 73368 146820 73397 146820 73370 146820 73400 146821 73186 146821 73415 146821 73415 146822 73186 146822 73376 146822 73415 146823 73376 146823 73374 146823 73374 146824 73376 146824 73164 146824 73374 146825 73164 146825 73395 146825 73407 146826 73380 146826 73388 146826 73182 146827 73399 146827 73377 146827 73377 146828 73399 146828 73412 146828 73377 146829 73412 146829 73385 146829 73385 146830 73412 146830 73378 146830 73385 146831 73378 146831 73388 146831 73388 146832 73378 146832 73379 146832 73388 146833 73379 146833 73407 146833 73407 146834 73408 146834 73380 146834 73380 146835 73408 146835 73383 146835 73380 146836 73383 146836 73386 146836 73433 146837 73404 146837 73405 146837 73405 146838 73404 146838 73394 146838 73405 146839 73394 146839 73381 146839 73381 146840 73394 146840 73386 146840 73381 146841 73386 146841 73382 146841 73382 146842 73386 146842 73383 146842 73384 146843 73385 146843 73388 146843 73387 146844 73380 146844 73386 146844 73167 146845 73366 146845 73386 146845 73386 146846 73366 146846 73365 146846 73386 146847 73365 146847 73387 146847 73387 146848 73181 146848 73380 146848 73380 146849 73181 146849 73180 146849 73380 146850 73180 146850 73388 146850 73388 146851 73180 146851 73179 146851 73388 146852 73179 146852 73384 146852 73389 146853 73370 146853 73397 146853 73389 146854 73390 146854 73370 146854 73370 146855 73390 146855 73178 146855 73370 146856 73178 146856 73391 146856 73391 146857 73178 146857 73177 146857 73391 146858 73177 146858 73373 146858 73373 146859 73177 146859 73171 146859 73373 146860 73171 146860 73403 146860 73403 146861 73171 146861 73170 146861 73403 146862 73170 146862 73392 146862 73392 146863 73170 146863 73393 146863 73392 146864 73393 146864 73404 146864 73404 146865 73393 146865 73167 146865 73404 146866 73167 146866 73394 146866 73394 146867 73167 146867 73386 146867 73164 146868 73166 146868 73395 146868 73395 146869 73166 146869 73172 146869 73395 146870 73172 146870 73397 146870 73397 146871 73172 146871 73396 146871 73397 146872 73396 146872 73389 146872 73186 146873 73400 146873 73398 146873 73186 146874 73398 146874 73185 146874 73185 146875 73398 146875 73399 146875 73185 146876 73399 146876 73182 146876 73469 146877 73399 146877 73421 146877 73421 146878 73399 146878 73398 146878 73421 146879 73398 146879 73402 146879 73400 146880 73413 146880 73398 146880 73398 146881 73413 146881 73401 146881 73398 146882 73401 146882 73402 146882 73437 146883 73403 146883 73436 146883 73436 146884 73403 146884 73392 146884 73436 146885 73392 146885 73433 146885 73433 146886 73392 146886 73404 146886 73412 146887 73399 146887 73469 146887 73434 146888 73433 146888 73451 146888 73451 146889 73433 146889 73405 146889 73451 146890 73405 146890 73452 146890 73452 146891 73405 146891 73406 146891 73405 146892 73381 146892 73406 146892 73406 146893 73381 146893 73382 146893 73406 146894 73382 146894 73483 146894 73407 146895 73484 146895 73408 146895 73408 146896 73484 146896 73483 146896 73408 146897 73483 146897 73383 146897 73383 146898 73483 146898 73382 146898 73378 146899 73409 146899 73379 146899 73379 146900 73409 146900 73471 146900 73379 146901 73471 146901 73407 146901 73407 146902 73471 146902 73410 146902 73407 146903 73410 146903 73484 146903 73469 146904 73411 146904 73412 146904 73412 146905 73411 146905 73463 146905 73412 146906 73463 146906 73378 146906 73378 146907 73463 146907 73462 146907 73378 146908 73462 146908 73409 146908 73413 146909 73400 146909 73414 146909 73414 146910 73400 146910 73415 146910 73414 146911 73415 146911 73510 146911 73510 146912 73415 146912 73374 146912 73510 146913 73374 146913 73508 146913 73508 146914 73374 146914 73416 146914 73416 146915 73374 146915 73375 146915 73416 146916 73375 146916 73417 146916 73417 146917 73375 146917 73507 146917 73507 146918 73375 146918 73368 146918 73507 146919 73368 146919 73513 146919 73428 146920 73418 146920 73432 146920 73418 146921 73428 146921 73503 146921 73422 146922 73424 146922 73419 146922 73420 146923 73469 146923 73421 146923 73467 146924 73423 146924 73422 146924 73422 146925 73423 146925 73420 146925 73420 146926 73421 146926 73422 146926 73422 146927 73421 146927 73402 146927 73422 146928 73402 146928 73424 146928 73424 146929 73402 146929 73401 146929 73424 146930 73401 146930 73413 146930 73426 146931 73465 146931 73427 146931 73427 146932 73465 146932 73467 146932 73413 146933 73425 146933 73424 146933 73424 146934 73425 146934 73512 146934 73424 146935 73512 146935 73419 146935 73419 146936 73512 146936 73522 146936 73419 146937 73522 146937 73544 146937 73430 146938 73426 146938 73431 146938 73431 146939 73426 146939 73427 146939 73431 146940 73427 146940 73428 146940 73467 146941 73422 146941 73427 146941 73427 146942 73422 146942 73419 146942 73427 146943 73419 146943 73428 146943 73428 146944 73419 146944 73544 146944 73428 146945 73544 146945 73503 146945 73429 146946 73430 146946 73136 146946 73136 146947 73430 146947 73431 146947 73136 146948 73431 146948 73144 146948 73144 146949 73431 146949 73428 146949 73144 146950 73428 146950 73143 146950 73143 146951 73428 146951 73432 146951 73436 146952 73433 146952 73434 146952 73434 146953 73435 146953 73436 146953 73436 146954 73435 146954 73161 146954 73436 146955 73161 146955 73437 146955 73437 146956 73161 146956 73160 146956 73437 146957 73160 146957 73491 146957 73438 146958 73440 146958 73455 146958 73439 146959 73458 146959 73446 146959 73441 146960 73480 146960 73453 146960 73438 146961 73459 146961 73440 146961 73440 146962 73459 146962 73137 146962 73440 146963 73137 146963 73441 146963 73444 146964 73442 146964 73489 146964 73489 146965 73442 146965 73445 146965 73489 146966 73445 146966 73488 146966 73489 146967 73443 146967 73444 146967 73444 146968 73443 146968 73430 146968 73444 146969 73430 146969 73429 146969 73445 146970 73439 146970 73488 146970 73488 146971 73439 146971 73446 146971 73488 146972 73446 146972 73447 146972 73447 146973 73446 146973 73448 146973 73447 146974 73448 146974 73487 146974 73487 146975 73448 146975 73460 146975 73487 146976 73460 146976 73449 146976 73449 146977 73460 146977 73461 146977 73449 146978 73461 146978 73450 146978 73451 146979 73452 146979 73456 146979 73456 146980 73452 146980 73481 146980 73441 146981 73453 146981 73440 146981 73440 146982 73453 146982 73454 146982 73440 146983 73454 146983 73455 146983 73455 146984 73454 146984 73456 146984 73455 146985 73456 146985 73457 146985 73457 146986 73456 146986 73481 146986 73457 146987 73481 146987 73482 146987 73458 146988 73459 146988 73446 146988 73446 146989 73459 146989 73438 146989 73446 146990 73438 146990 73448 146990 73448 146991 73438 146991 73455 146991 73448 146992 73455 146992 73460 146992 73460 146993 73455 146993 73457 146993 73460 146994 73457 146994 73461 146994 73461 146995 73457 146995 73482 146995 73461 146996 73482 146996 73450 146996 73471 146997 73409 146997 73472 146997 73472 146998 73409 146998 73462 146998 73472 146999 73462 146999 73463 146999 73484 147000 73410 147000 73485 147000 73426 147001 73464 147001 73465 147001 73465 147002 73464 147002 73466 147002 73465 147003 73466 147003 73467 147003 73467 147004 73466 147004 73468 147004 73467 147005 73468 147005 73423 147005 73423 147006 73468 147006 73478 147006 73423 147007 73478 147007 73420 147007 73420 147008 73478 147008 73470 147008 73420 147009 73470 147009 73469 147009 73469 147010 73470 147010 73411 147010 73410 147011 73471 147011 73485 147011 73485 147012 73471 147012 73472 147012 73485 147013 73472 147013 73486 147013 73486 147014 73472 147014 73474 147014 73486 147015 73474 147015 73473 147015 73473 147016 73474 147016 73477 147016 73473 147017 73477 147017 73475 147017 73475 147018 73477 147018 73476 147018 73475 147019 73476 147019 73490 147019 73464 147020 73490 147020 73466 147020 73466 147021 73490 147021 73476 147021 73466 147022 73476 147022 73468 147022 73468 147023 73476 147023 73477 147023 73468 147024 73477 147024 73478 147024 73478 147025 73477 147025 73474 147025 73478 147026 73474 147026 73470 147026 73470 147027 73474 147027 73472 147027 73470 147028 73472 147028 73411 147028 73411 147029 73472 147029 73463 147029 73434 147030 73451 147030 73148 147030 73148 147031 73451 147031 73456 147031 73148 147032 73456 147032 73156 147032 73156 147033 73456 147033 73454 147033 73156 147034 73454 147034 73479 147034 73479 147035 73454 147035 73453 147035 73479 147036 73453 147036 73149 147036 73149 147037 73453 147037 73480 147037 73149 147038 73480 147038 73151 147038 73452 147039 73406 147039 73481 147039 73481 147040 73406 147040 73483 147040 73481 147041 73483 147041 73482 147041 73482 147042 73483 147042 73484 147042 73482 147043 73484 147043 73450 147043 73450 147044 73484 147044 73485 147044 73450 147045 73485 147045 73449 147045 73449 147046 73485 147046 73486 147046 73449 147047 73486 147047 73487 147047 73487 147048 73486 147048 73473 147048 73487 147049 73473 147049 73447 147049 73447 147050 73473 147050 73475 147050 73447 147051 73475 147051 73488 147051 73488 147052 73475 147052 73490 147052 73488 147053 73490 147053 73489 147053 73489 147054 73490 147054 73464 147054 73489 147055 73464 147055 73443 147055 73443 147056 73464 147056 73426 147056 73443 147057 73426 147057 73430 147057 73157 147058 73147 147058 73529 147058 73369 147059 73491 147059 73146 147059 73522 147060 73512 147060 73530 147060 73542 147061 73540 147061 73499 147061 73504 147062 73141 147062 73505 147062 73505 147063 73141 147063 73140 147063 73505 147064 73140 147064 73492 147064 73492 147065 73140 147065 73432 147065 73492 147066 73432 147066 73418 147066 73493 147067 73154 147067 73536 147067 73537 147068 73139 147068 73496 147068 73496 147069 73139 147069 73494 147069 73496 147070 73494 147070 73495 147070 73495 147071 73494 147071 73497 147071 73495 147072 73497 147072 73499 147072 73147 147073 73154 147073 73529 147073 73529 147074 73154 147074 73493 147074 73529 147075 73493 147075 73528 147075 73499 147076 73540 147076 73495 147076 73495 147077 73540 147077 73539 147077 73495 147078 73539 147078 73496 147078 73497 147079 73498 147079 73499 147079 73499 147080 73498 147080 73500 147080 73499 147081 73500 147081 73542 147081 73542 147082 73500 147082 73501 147082 73542 147083 73501 147083 73543 147083 73543 147084 73501 147084 73506 147084 73543 147085 73506 147085 73502 147085 73502 147086 73506 147086 73503 147086 73502 147087 73503 147087 73544 147087 73498 147088 73504 147088 73500 147088 73500 147089 73504 147089 73505 147089 73500 147090 73505 147090 73501 147090 73501 147091 73505 147091 73492 147091 73501 147092 73492 147092 73506 147092 73506 147093 73492 147093 73418 147093 73506 147094 73418 147094 73503 147094 73507 147095 73514 147095 73417 147095 73417 147096 73514 147096 73532 147096 73417 147097 73532 147097 73416 147097 73416 147098 73532 147098 73508 147098 73508 147099 73532 147099 73509 147099 73508 147100 73509 147100 73510 147100 73510 147101 73509 147101 73511 147101 73510 147102 73511 147102 73414 147102 73413 147103 73414 147103 73425 147103 73425 147104 73414 147104 73511 147104 73425 147105 73511 147105 73512 147105 73518 147106 73520 147106 73367 147106 73367 147107 73520 147107 73517 147107 73507 147108 73513 147108 73514 147108 73514 147109 73513 147109 73515 147109 73514 147110 73515 147110 73517 147110 73517 147111 73515 147111 73516 147111 73517 147112 73516 147112 73367 147112 73518 147113 73519 147113 73520 147113 73520 147114 73519 147114 73521 147114 73520 147115 73521 147115 73369 147115 73522 147116 73530 147116 73523 147116 73523 147117 73530 147117 73524 147117 73523 147118 73524 147118 73525 147118 73525 147119 73524 147119 73531 147119 73525 147120 73531 147120 73526 147120 73526 147121 73531 147121 73533 147121 73526 147122 73533 147122 73541 147122 73541 147123 73533 147123 73534 147123 73541 147124 73534 147124 73538 147124 73538 147125 73534 147125 73527 147125 73538 147126 73527 147126 73528 147126 73528 147127 73527 147127 73529 147127 73529 147128 73527 147128 73535 147128 73529 147129 73535 147129 73157 147129 73512 147130 73511 147130 73530 147130 73530 147131 73511 147131 73509 147131 73530 147132 73509 147132 73524 147132 73524 147133 73509 147133 73532 147133 73524 147134 73532 147134 73531 147134 73531 147135 73532 147135 73514 147135 73531 147136 73514 147136 73533 147136 73533 147137 73514 147137 73517 147137 73533 147138 73517 147138 73534 147138 73534 147139 73517 147139 73520 147139 73534 147140 73520 147140 73527 147140 73527 147141 73520 147141 73369 147141 73527 147142 73369 147142 73535 147142 73535 147143 73369 147143 73146 147143 73535 147144 73146 147144 73157 147144 73536 147145 73537 147145 73493 147145 73493 147146 73537 147146 73496 147146 73493 147147 73496 147147 73528 147147 73528 147148 73496 147148 73539 147148 73528 147149 73539 147149 73538 147149 73538 147150 73539 147150 73540 147150 73538 147151 73540 147151 73541 147151 73541 147152 73540 147152 73542 147152 73541 147153 73542 147153 73526 147153 73526 147154 73542 147154 73543 147154 73526 147155 73543 147155 73525 147155 73525 147156 73543 147156 73502 147156 73525 147157 73502 147157 73523 147157 73523 147158 73502 147158 73544 147158 73523 147159 73544 147159 73522 147159 73545 147160 73753 147160 73546 147160 73545 147161 73546 147161 73836 147161 73836 147162 73546 147162 73547 147162 73836 147163 73547 147163 73827 147163 73827 147164 73547 147164 73751 147164 73827 147165 73751 147165 73829 147165 73554 147166 73753 147166 73545 147166 73560 147167 73561 147167 73787 147167 73787 147168 73561 147168 73548 147168 73787 147169 73548 147169 73792 147169 73792 147170 73548 147170 73549 147170 73548 147171 73759 147171 73549 147171 73549 147172 73759 147172 73550 147172 73549 147173 73550 147173 73794 147173 73794 147174 73550 147174 73551 147174 73794 147175 73551 147175 73796 147175 73796 147176 73551 147176 73797 147176 73797 147177 73551 147177 73758 147177 73797 147178 73758 147178 73798 147178 73556 147179 73790 147179 73552 147179 73552 147180 73790 147180 73789 147180 73552 147181 73789 147181 73758 147181 73758 147182 73789 147182 73553 147182 73758 147183 73553 147183 73798 147183 73545 147184 73555 147184 73554 147184 73554 147185 73555 147185 73556 147185 73554 147186 73556 147186 73755 147186 73755 147187 73556 147187 73552 147187 73557 147188 73766 147188 73558 147188 73558 147189 73766 147189 73559 147189 73558 147190 73559 147190 73844 147190 73844 147191 73559 147191 73768 147191 73844 147192 73768 147192 73560 147192 73560 147193 73768 147193 73561 147193 73562 147194 73928 147194 73926 147194 73926 147195 73928 147195 73752 147195 73926 147196 73752 147196 73563 147196 73563 147197 73752 147197 73564 147197 73563 147198 73564 147198 73949 147198 73949 147199 73564 147199 73925 147199 73949 147200 73925 147200 73565 147200 73880 147201 73874 147201 73764 147201 73880 147202 73764 147202 73566 147202 73764 147203 73567 147203 73566 147203 73566 147204 73567 147204 73766 147204 73566 147205 73766 147205 73557 147205 73764 147206 73765 147206 73567 147206 73567 147207 73765 147207 73568 147207 73567 147208 73568 147208 73766 147208 73766 147209 73568 147209 73939 147209 73692 147210 73699 147210 73579 147210 73579 147211 73699 147211 73697 147211 73579 147212 73697 147212 73578 147212 73578 147213 73697 147213 73696 147213 73578 147214 73696 147214 73569 147214 73569 147215 73696 147215 73695 147215 73692 147216 73579 147216 73570 147216 73570 147217 73579 147217 73571 147217 73570 147218 73571 147218 73572 147218 73571 147219 73573 147219 73572 147219 73572 147220 73573 147220 73576 147220 73572 147221 73576 147221 73575 147221 73575 147222 73576 147222 73574 147222 73575 147223 73574 147223 73618 147223 73943 147224 73582 147224 73574 147224 73574 147225 73576 147225 73943 147225 73943 147226 73576 147226 73573 147226 73943 147227 73573 147227 73946 147227 73569 147228 73577 147228 73578 147228 73578 147229 73577 147229 73948 147229 73578 147230 73948 147230 73579 147230 73579 147231 73948 147231 73946 147231 73579 147232 73946 147232 73571 147232 73571 147233 73946 147233 73573 147233 73592 147234 73950 147234 73580 147234 73580 147235 73950 147235 73581 147235 73580 147236 73581 147236 73605 147236 73924 147237 73607 147237 73581 147237 73581 147238 73607 147238 73606 147238 73581 147239 73606 147239 73605 147239 73574 147240 73582 147240 73621 147240 73621 147241 73582 147241 73583 147241 73621 147242 73583 147242 73584 147242 73584 147243 73583 147243 73940 147243 73927 147244 73950 147244 73592 147244 73661 147245 73584 147245 73663 147245 73663 147246 73584 147246 73930 147246 73663 147247 73930 147247 73585 147247 73585 147248 73930 147248 73586 147248 73930 147249 73587 147249 73586 147249 73586 147250 73587 147250 73591 147250 73586 147251 73591 147251 73670 147251 73596 147252 73589 147252 73588 147252 73588 147253 73589 147253 73670 147253 73588 147254 73670 147254 73590 147254 73590 147255 73670 147255 73591 147255 73592 147256 73660 147256 73927 147256 73927 147257 73660 147257 73623 147257 73927 147258 73623 147258 73929 147258 73929 147259 73623 147259 73593 147259 73929 147260 73593 147260 73594 147260 73594 147261 73593 147261 73622 147261 73594 147262 73622 147262 73596 147262 73596 147263 73622 147263 73595 147263 73596 147264 73595 147264 73589 147264 73607 147265 73924 147265 73597 147265 73597 147266 73924 147266 73599 147266 73597 147267 73599 147267 73598 147267 73598 147268 73599 147268 73600 147268 73598 147269 73600 147269 73694 147269 73694 147270 73600 147270 73569 147270 73694 147271 73569 147271 73695 147271 73613 147272 73689 147272 73675 147272 73689 147273 73613 147273 73690 147273 73604 147274 73609 147274 73611 147274 73603 147275 73592 147275 73580 147275 73601 147276 73602 147276 73604 147276 73604 147277 73602 147277 73603 147277 73603 147278 73580 147278 73604 147278 73604 147279 73580 147279 73605 147279 73604 147280 73605 147280 73609 147280 73609 147281 73605 147281 73606 147281 73609 147282 73606 147282 73607 147282 73647 147283 73608 147283 73612 147283 73612 147284 73608 147284 73601 147284 73607 147285 73691 147285 73609 147285 73609 147286 73691 147286 73610 147286 73609 147287 73610 147287 73611 147287 73611 147288 73610 147288 73724 147288 73611 147289 73724 147289 73614 147289 73630 147290 73647 147290 73615 147290 73615 147291 73647 147291 73612 147291 73615 147292 73612 147292 73613 147292 73601 147293 73604 147293 73612 147293 73612 147294 73604 147294 73611 147294 73612 147295 73611 147295 73613 147295 73613 147296 73611 147296 73614 147296 73613 147297 73614 147297 73690 147297 73632 147298 73630 147298 73738 147298 73738 147299 73630 147299 73615 147299 73738 147300 73615 147300 73737 147300 73737 147301 73615 147301 73613 147301 73737 147302 73613 147302 73616 147302 73616 147303 73613 147303 73675 147303 73617 147304 73618 147304 73574 147304 73617 147305 73574 147305 73619 147305 73619 147306 73574 147306 73621 147306 73619 147307 73621 147307 73620 147307 73620 147308 73621 147308 73584 147308 73620 147309 73584 147309 73661 147309 73595 147310 73622 147310 73672 147310 73593 147311 73623 147311 73659 147311 73624 147312 73639 147312 73640 147312 73625 147313 73729 147313 73635 147313 73728 147314 73727 147314 73667 147314 73624 147315 73626 147315 73639 147315 73639 147316 73626 147316 73627 147316 73639 147317 73627 147317 73728 147317 73631 147318 73629 147318 73628 147318 73628 147319 73629 147319 73726 147319 73628 147320 73726 147320 73633 147320 73628 147321 73674 147321 73631 147321 73631 147322 73674 147322 73630 147322 73631 147323 73630 147323 73632 147323 73726 147324 73625 147324 73633 147324 73633 147325 73625 147325 73635 147325 73633 147326 73635 147326 73634 147326 73634 147327 73635 147327 73643 147327 73634 147328 73643 147328 73636 147328 73636 147329 73643 147329 73637 147329 73636 147330 73637 147330 73638 147330 73638 147331 73637 147331 73644 147331 73638 147332 73644 147332 73671 147332 73663 147333 73585 147333 73641 147333 73641 147334 73585 147334 73642 147334 73728 147335 73667 147335 73639 147335 73639 147336 73667 147336 73664 147336 73639 147337 73664 147337 73640 147337 73640 147338 73664 147338 73641 147338 73640 147339 73641 147339 73645 147339 73645 147340 73641 147340 73642 147340 73645 147341 73642 147341 73646 147341 73729 147342 73626 147342 73635 147342 73635 147343 73626 147343 73624 147343 73635 147344 73624 147344 73643 147344 73643 147345 73624 147345 73640 147345 73643 147346 73640 147346 73637 147346 73637 147347 73640 147347 73645 147347 73637 147348 73645 147348 73644 147348 73644 147349 73645 147349 73646 147349 73644 147350 73646 147350 73671 147350 73595 147351 73672 147351 73589 147351 73647 147352 73673 147352 73608 147352 73608 147353 73673 147353 73655 147353 73608 147354 73655 147354 73601 147354 73601 147355 73655 147355 73648 147355 73601 147356 73648 147356 73602 147356 73602 147357 73648 147357 73658 147357 73602 147358 73658 147358 73603 147358 73603 147359 73658 147359 73649 147359 73603 147360 73649 147360 73592 147360 73592 147361 73649 147361 73660 147361 73622 147362 73593 147362 73672 147362 73672 147363 73593 147363 73659 147363 73672 147364 73659 147364 73650 147364 73650 147365 73659 147365 73651 147365 73650 147366 73651 147366 73652 147366 73652 147367 73651 147367 73657 147367 73652 147368 73657 147368 73653 147368 73653 147369 73657 147369 73654 147369 73653 147370 73654 147370 73656 147370 73673 147371 73656 147371 73655 147371 73655 147372 73656 147372 73654 147372 73655 147373 73654 147373 73648 147373 73648 147374 73654 147374 73657 147374 73648 147375 73657 147375 73658 147375 73658 147376 73657 147376 73651 147376 73658 147377 73651 147377 73649 147377 73649 147378 73651 147378 73659 147378 73649 147379 73659 147379 73660 147379 73660 147380 73659 147380 73623 147380 73661 147381 73663 147381 73662 147381 73662 147382 73663 147382 73641 147382 73662 147383 73641 147383 73665 147383 73665 147384 73641 147384 73664 147384 73665 147385 73664 147385 73666 147385 73666 147386 73664 147386 73667 147386 73666 147387 73667 147387 73668 147387 73668 147388 73667 147388 73727 147388 73668 147389 73727 147389 73669 147389 73585 147390 73586 147390 73642 147390 73642 147391 73586 147391 73670 147391 73642 147392 73670 147392 73646 147392 73646 147393 73670 147393 73589 147393 73646 147394 73589 147394 73671 147394 73671 147395 73589 147395 73672 147395 73671 147396 73672 147396 73638 147396 73638 147397 73672 147397 73650 147397 73638 147398 73650 147398 73636 147398 73636 147399 73650 147399 73652 147399 73636 147400 73652 147400 73634 147400 73634 147401 73652 147401 73653 147401 73634 147402 73653 147402 73633 147402 73633 147403 73653 147403 73656 147403 73633 147404 73656 147404 73628 147404 73628 147405 73656 147405 73673 147405 73628 147406 73673 147406 73674 147406 73674 147407 73673 147407 73647 147407 73674 147408 73647 147408 73630 147408 73575 147409 73618 147409 73747 147409 73719 147410 73679 147410 73682 147410 73702 147411 73741 147411 73677 147411 73730 147412 73735 147412 73688 147412 73688 147413 73735 147413 73734 147413 73688 147414 73734 147414 73676 147414 73676 147415 73734 147415 73675 147415 73676 147416 73675 147416 73689 147416 73701 147417 73677 147417 73731 147417 73716 147418 73732 147418 73717 147418 73717 147419 73732 147419 73678 147419 73717 147420 73678 147420 73680 147420 73680 147421 73678 147421 73681 147421 73680 147422 73681 147422 73682 147422 73682 147423 73679 147423 73680 147423 73680 147424 73679 147424 73718 147424 73680 147425 73718 147425 73717 147425 73681 147426 73683 147426 73682 147426 73682 147427 73683 147427 73687 147427 73682 147428 73687 147428 73719 147428 73719 147429 73687 147429 73685 147429 73719 147430 73685 147430 73684 147430 73684 147431 73685 147431 73686 147431 73684 147432 73686 147432 73722 147432 73722 147433 73686 147433 73690 147433 73722 147434 73690 147434 73614 147434 73683 147435 73730 147435 73687 147435 73687 147436 73730 147436 73688 147436 73687 147437 73688 147437 73685 147437 73685 147438 73688 147438 73676 147438 73685 147439 73676 147439 73686 147439 73686 147440 73676 147440 73689 147440 73686 147441 73689 147441 73690 147441 73610 147442 73691 147442 73693 147442 73693 147443 73691 147443 73607 147443 73693 147444 73607 147444 73597 147444 73698 147445 73692 147445 73715 147445 73715 147446 73692 147446 73570 147446 73597 147447 73598 147447 73693 147447 73693 147448 73598 147448 73694 147448 73693 147449 73694 147449 73708 147449 73708 147450 73694 147450 73695 147450 73708 147451 73695 147451 73709 147451 73709 147452 73695 147452 73696 147452 73709 147453 73696 147453 73711 147453 73711 147454 73696 147454 73697 147454 73711 147455 73697 147455 73698 147455 73698 147456 73697 147456 73699 147456 73698 147457 73699 147457 73692 147457 73570 147458 73572 147458 73715 147458 73715 147459 73572 147459 73575 147459 73715 147460 73575 147460 73700 147460 73700 147461 73575 147461 73747 147461 73700 147462 73747 147462 73746 147462 73677 147463 73701 147463 73702 147463 73702 147464 73701 147464 73703 147464 73702 147465 73703 147465 73714 147465 73714 147466 73703 147466 73704 147466 73714 147467 73704 147467 73713 147467 73713 147468 73704 147468 73705 147468 73713 147469 73705 147469 73712 147469 73712 147470 73705 147470 73720 147470 73712 147471 73720 147471 73710 147471 73710 147472 73720 147472 73721 147472 73710 147473 73721 147473 73706 147473 73706 147474 73721 147474 73723 147474 73706 147475 73723 147475 73707 147475 73707 147476 73723 147476 73724 147476 73707 147477 73724 147477 73610 147477 73610 147478 73693 147478 73707 147478 73707 147479 73693 147479 73708 147479 73707 147480 73708 147480 73706 147480 73706 147481 73708 147481 73709 147481 73706 147482 73709 147482 73710 147482 73710 147483 73709 147483 73711 147483 73710 147484 73711 147484 73712 147484 73712 147485 73711 147485 73698 147485 73712 147486 73698 147486 73713 147486 73713 147487 73698 147487 73715 147487 73713 147488 73715 147488 73714 147488 73714 147489 73715 147489 73700 147489 73714 147490 73700 147490 73702 147490 73702 147491 73700 147491 73746 147491 73702 147492 73746 147492 73741 147492 73731 147493 73716 147493 73701 147493 73701 147494 73716 147494 73717 147494 73701 147495 73717 147495 73703 147495 73703 147496 73717 147496 73718 147496 73703 147497 73718 147497 73704 147497 73704 147498 73718 147498 73679 147498 73704 147499 73679 147499 73705 147499 73705 147500 73679 147500 73719 147500 73705 147501 73719 147501 73720 147501 73720 147502 73719 147502 73684 147502 73720 147503 73684 147503 73721 147503 73721 147504 73684 147504 73722 147504 73721 147505 73722 147505 73723 147505 73723 147506 73722 147506 73614 147506 73723 147507 73614 147507 73724 147507 73733 147508 73731 147508 73743 147508 73740 147509 73632 147509 73738 147509 73725 147510 73632 147510 73629 147510 73629 147511 73632 147511 73740 147511 73629 147512 73740 147512 73726 147512 73726 147513 73740 147513 73625 147513 73727 147514 73728 147514 73740 147514 73740 147515 73728 147515 73627 147515 73627 147516 73626 147516 73740 147516 73740 147517 73626 147517 73729 147517 73740 147518 73729 147518 73625 147518 73730 147519 73683 147519 73733 147519 73733 147520 73683 147520 73681 147520 73716 147521 73731 147521 73732 147521 73732 147522 73731 147522 73733 147522 73732 147523 73733 147523 73678 147523 73678 147524 73733 147524 73681 147524 73675 147525 73734 147525 73733 147525 73733 147526 73734 147526 73735 147526 73733 147527 73735 147527 73730 147527 73675 147528 73733 147528 73616 147528 73616 147529 73733 147529 73743 147529 73616 147530 73743 147530 73737 147530 73737 147531 73743 147531 73736 147531 73737 147532 73736 147532 73738 147532 73738 147533 73736 147533 73739 147533 73738 147534 73739 147534 73740 147534 73740 147535 73739 147535 73669 147535 73740 147536 73669 147536 73727 147536 73747 147537 73618 147537 73617 147537 73741 147538 73746 147538 73748 147538 73662 147539 73665 147539 73750 147539 73666 147540 73668 147540 73745 147540 73668 147541 73669 147541 73745 147541 73745 147542 73669 147542 73739 147542 73745 147543 73739 147543 73744 147543 73744 147544 73739 147544 73736 147544 73744 147545 73736 147545 73742 147545 73742 147546 73736 147546 73743 147546 73742 147547 73743 147547 73677 147547 73677 147548 73743 147548 73731 147548 73677 147549 73741 147549 73742 147549 73742 147550 73741 147550 73748 147550 73742 147551 73748 147551 73744 147551 73744 147552 73748 147552 73749 147552 73744 147553 73749 147553 73745 147553 73745 147554 73749 147554 73750 147554 73745 147555 73750 147555 73666 147555 73666 147556 73750 147556 73665 147556 73746 147557 73747 147557 73748 147557 73748 147558 73747 147558 73617 147558 73748 147559 73617 147559 73749 147559 73749 147560 73617 147560 73619 147560 73749 147561 73619 147561 73750 147561 73750 147562 73619 147562 73620 147562 73750 147563 73620 147563 73662 147563 73662 147564 73620 147564 73661 147564 73928 147565 73931 147565 73751 147565 73928 147566 73751 147566 73752 147566 73751 147567 73547 147567 73752 147567 73752 147568 73547 147568 73546 147568 73752 147569 73546 147569 73564 147569 73564 147570 73546 147570 73925 147570 73925 147571 73546 147571 73753 147571 73925 147572 73753 147572 73936 147572 73936 147573 73753 147573 73754 147573 73754 147574 73753 147574 73554 147574 73754 147575 73554 147575 73756 147575 73554 147576 73755 147576 73756 147576 73756 147577 73755 147577 73552 147577 73756 147578 73552 147578 73757 147578 73757 147579 73552 147579 73758 147579 73757 147580 73758 147580 73947 147580 73947 147581 73758 147581 73551 147581 73947 147582 73551 147582 73945 147582 73561 147583 73942 147583 73548 147583 73548 147584 73942 147584 73944 147584 73548 147585 73944 147585 73759 147585 73759 147586 73944 147586 73945 147586 73759 147587 73945 147587 73550 147587 73550 147588 73945 147588 73551 147588 73751 147589 73931 147589 73920 147589 73920 147590 73931 147590 73760 147590 73920 147591 73760 147591 73761 147591 73761 147592 73760 147592 73762 147592 73761 147593 73762 147593 73922 147593 73922 147594 73762 147594 73763 147594 73922 147595 73763 147595 73923 147595 73923 147596 73763 147596 73934 147596 73923 147597 73934 147597 73764 147597 73764 147598 73934 147598 73765 147598 73766 147599 73939 147599 73559 147599 73559 147600 73939 147600 73767 147600 73559 147601 73767 147601 73768 147601 73768 147602 73767 147602 73941 147602 73768 147603 73941 147603 73561 147603 73561 147604 73941 147604 73942 147604 73905 147605 73919 147605 73841 147605 73769 147606 73905 147606 73810 147606 73778 147607 73770 147607 73772 147607 73772 147608 73770 147608 73771 147608 73772 147609 73771 147609 73773 147609 73773 147610 73771 147610 73774 147610 73773 147611 73774 147611 73902 147611 73902 147612 73774 147612 73781 147612 73775 147613 73823 147613 73780 147613 73784 147614 73819 147614 73779 147614 73779 147615 73819 147615 73776 147615 73779 147616 73776 147616 73775 147616 73775 147617 73776 147617 73830 147617 73775 147618 73830 147618 73823 147618 73777 147619 73770 147619 73812 147619 73812 147620 73770 147620 73778 147620 73812 147621 73778 147621 73907 147621 73777 147622 73784 147622 73770 147622 73770 147623 73784 147623 73779 147623 73770 147624 73779 147624 73771 147624 73771 147625 73779 147625 73775 147625 73771 147626 73775 147626 73774 147626 73774 147627 73775 147627 73780 147627 73774 147628 73780 147628 73781 147628 73782 147629 73815 147629 73777 147629 73777 147630 73815 147630 73783 147630 73777 147631 73783 147631 73784 147631 73906 147632 73769 147632 73813 147632 73813 147633 73769 147633 73810 147633 73813 147634 73810 147634 73785 147634 73785 147635 73810 147635 73814 147635 73799 147636 73793 147636 73802 147636 73792 147637 73786 147637 73787 147637 73787 147638 73786 147638 73788 147638 73787 147639 73788 147639 73560 147639 73791 147640 73555 147640 73808 147640 73808 147641 73555 147641 73545 147641 73808 147642 73545 147642 73809 147642 73553 147643 73789 147643 73804 147643 73804 147644 73789 147644 73790 147644 73804 147645 73790 147645 73791 147645 73791 147646 73790 147646 73556 147646 73791 147647 73556 147647 73555 147647 73792 147648 73549 147648 73793 147648 73793 147649 73549 147649 73794 147649 73793 147650 73794 147650 73802 147650 73802 147651 73794 147651 73796 147651 73802 147652 73796 147652 73795 147652 73795 147653 73796 147653 73797 147653 73795 147654 73797 147654 73804 147654 73804 147655 73797 147655 73798 147655 73804 147656 73798 147656 73553 147656 73799 147657 73803 147657 73816 147657 73816 147658 73803 147658 73805 147658 73816 147659 73805 147659 73817 147659 73817 147660 73805 147660 73806 147660 73817 147661 73806 147661 73818 147661 73818 147662 73806 147662 73807 147662 73818 147663 73807 147663 73800 147663 73800 147664 73807 147664 73801 147664 73800 147665 73801 147665 73820 147665 73820 147666 73801 147666 73833 147666 73820 147667 73833 147667 73832 147667 73799 147668 73802 147668 73803 147668 73803 147669 73802 147669 73795 147669 73803 147670 73795 147670 73805 147670 73805 147671 73795 147671 73804 147671 73805 147672 73804 147672 73806 147672 73806 147673 73804 147673 73791 147673 73806 147674 73791 147674 73807 147674 73807 147675 73791 147675 73808 147675 73807 147676 73808 147676 73801 147676 73801 147677 73808 147677 73809 147677 73801 147678 73809 147678 73833 147678 73905 147679 73841 147679 73810 147679 73810 147680 73841 147680 73839 147680 73810 147681 73839 147681 73814 147681 73814 147682 73839 147682 73811 147682 73814 147683 73811 147683 73843 147683 73907 147684 73906 147684 73812 147684 73812 147685 73906 147685 73813 147685 73812 147686 73813 147686 73777 147686 73777 147687 73813 147687 73785 147687 73777 147688 73785 147688 73782 147688 73782 147689 73785 147689 73814 147689 73782 147690 73814 147690 73786 147690 73786 147691 73814 147691 73843 147691 73786 147692 73843 147692 73788 147692 73792 147693 73793 147693 73786 147693 73786 147694 73793 147694 73799 147694 73786 147695 73799 147695 73782 147695 73782 147696 73799 147696 73816 147696 73782 147697 73816 147697 73815 147697 73815 147698 73816 147698 73817 147698 73815 147699 73817 147699 73783 147699 73783 147700 73817 147700 73818 147700 73783 147701 73818 147701 73784 147701 73784 147702 73818 147702 73800 147702 73784 147703 73800 147703 73819 147703 73819 147704 73800 147704 73820 147704 73819 147705 73820 147705 73776 147705 73776 147706 73820 147706 73832 147706 73776 147707 73832 147707 73830 147707 73870 147708 73834 147708 73828 147708 73821 147709 73917 147709 73822 147709 73913 147710 73914 147710 73866 147710 73866 147711 73914 147711 73824 147711 73902 147712 73781 147712 73903 147712 73903 147713 73781 147713 73917 147713 73835 147714 73826 147714 73831 147714 73831 147715 73826 147715 73824 147715 73917 147716 73781 147716 73822 147716 73822 147717 73781 147717 73780 147717 73822 147718 73780 147718 73823 147718 73914 147719 73821 147719 73824 147719 73824 147720 73821 147720 73822 147720 73824 147721 73822 147721 73831 147721 73831 147722 73822 147722 73823 147722 73834 147723 73825 147723 73826 147723 73826 147724 73825 147724 73863 147724 73826 147725 73863 147725 73824 147725 73824 147726 73863 147726 73867 147726 73824 147727 73867 147727 73866 147727 73836 147728 73827 147728 73828 147728 73828 147729 73827 147729 73829 147729 73828 147730 73829 147730 73870 147730 73823 147731 73830 147731 73831 147731 73831 147732 73830 147732 73832 147732 73831 147733 73832 147733 73835 147733 73835 147734 73832 147734 73833 147734 73835 147735 73833 147735 73809 147735 73834 147736 73826 147736 73828 147736 73828 147737 73826 147737 73835 147737 73828 147738 73835 147738 73836 147738 73836 147739 73835 147739 73809 147739 73836 147740 73809 147740 73545 147740 73840 147741 73837 147741 73847 147741 73915 147742 73838 147742 73855 147742 73841 147743 73919 147743 73918 147743 73811 147744 73839 147744 73840 147744 73840 147745 73839 147745 73841 147745 73841 147746 73918 147746 73840 147746 73840 147747 73918 147747 73842 147747 73840 147748 73842 147748 73837 147748 73837 147749 73842 147749 73916 147749 73837 147750 73916 147750 73915 147750 73788 147751 73843 147751 73845 147751 73845 147752 73843 147752 73811 147752 73560 147753 73788 147753 73844 147753 73844 147754 73788 147754 73845 147754 73844 147755 73845 147755 73558 147755 73915 147756 73855 147756 73837 147756 73837 147757 73855 147757 73846 147757 73837 147758 73846 147758 73847 147758 73847 147759 73846 147759 73848 147759 73847 147760 73848 147760 73849 147760 73811 147761 73840 147761 73845 147761 73845 147762 73840 147762 73847 147762 73845 147763 73847 147763 73558 147763 73558 147764 73847 147764 73849 147764 73558 147765 73849 147765 73557 147765 73566 147766 73557 147766 73849 147766 73860 147767 73857 147767 73856 147767 73893 147768 73846 147768 73855 147768 73894 147769 73852 147769 73895 147769 73913 147770 73866 147770 73908 147770 73908 147771 73866 147771 73850 147771 73908 147772 73850 147772 73909 147772 73909 147773 73850 147773 73851 147773 73909 147774 73851 147774 73910 147774 73910 147775 73851 147775 73864 147775 73895 147776 73852 147776 73853 147776 73853 147777 73852 147777 73912 147777 73853 147778 73912 147778 73856 147778 73854 147779 73855 147779 73838 147779 73856 147780 73857 147780 73853 147780 73853 147781 73857 147781 73896 147781 73853 147782 73896 147782 73895 147782 73912 147783 73858 147783 73856 147783 73856 147784 73858 147784 73859 147784 73856 147785 73859 147785 73860 147785 73860 147786 73859 147786 73865 147786 73860 147787 73865 147787 73899 147787 73899 147788 73865 147788 73861 147788 73899 147789 73861 147789 73862 147789 73862 147790 73861 147790 73867 147790 73862 147791 73867 147791 73863 147791 73858 147792 73864 147792 73859 147792 73859 147793 73864 147793 73851 147793 73859 147794 73851 147794 73865 147794 73865 147795 73851 147795 73850 147795 73865 147796 73850 147796 73861 147796 73861 147797 73850 147797 73866 147797 73861 147798 73866 147798 73867 147798 73876 147799 73869 147799 73868 147799 73868 147800 73869 147800 73921 147800 73921 147801 73869 147801 73872 147801 73921 147802 73872 147802 73871 147802 73829 147803 73871 147803 73870 147803 73870 147804 73871 147804 73872 147804 73870 147805 73872 147805 73834 147805 73890 147806 73873 147806 73891 147806 73891 147807 73873 147807 73874 147807 73868 147808 73875 147808 73876 147808 73876 147809 73875 147809 73877 147809 73876 147810 73877 147810 73888 147810 73888 147811 73877 147811 73878 147811 73888 147812 73878 147812 73890 147812 73890 147813 73878 147813 73879 147813 73890 147814 73879 147814 73873 147814 73874 147815 73880 147815 73891 147815 73891 147816 73880 147816 73566 147816 73891 147817 73566 147817 73881 147817 73881 147818 73566 147818 73849 147818 73881 147819 73849 147819 73848 147819 73855 147820 73854 147820 73893 147820 73893 147821 73854 147821 73882 147821 73893 147822 73882 147822 73892 147822 73892 147823 73882 147823 73883 147823 73892 147824 73883 147824 73884 147824 73884 147825 73883 147825 73897 147825 73884 147826 73897 147826 73889 147826 73889 147827 73897 147827 73898 147827 73889 147828 73898 147828 73885 147828 73885 147829 73898 147829 73900 147829 73885 147830 73900 147830 73887 147830 73887 147831 73900 147831 73901 147831 73887 147832 73901 147832 73886 147832 73886 147833 73901 147833 73825 147833 73886 147834 73825 147834 73834 147834 73834 147835 73872 147835 73886 147835 73886 147836 73872 147836 73869 147836 73886 147837 73869 147837 73887 147837 73887 147838 73869 147838 73876 147838 73887 147839 73876 147839 73885 147839 73885 147840 73876 147840 73888 147840 73885 147841 73888 147841 73889 147841 73889 147842 73888 147842 73890 147842 73889 147843 73890 147843 73884 147843 73884 147844 73890 147844 73891 147844 73884 147845 73891 147845 73892 147845 73892 147846 73891 147846 73881 147846 73892 147847 73881 147847 73893 147847 73893 147848 73881 147848 73848 147848 73893 147849 73848 147849 73846 147849 73838 147850 73894 147850 73854 147850 73854 147851 73894 147851 73895 147851 73854 147852 73895 147852 73882 147852 73882 147853 73895 147853 73896 147853 73882 147854 73896 147854 73883 147854 73883 147855 73896 147855 73857 147855 73883 147856 73857 147856 73897 147856 73897 147857 73857 147857 73860 147857 73897 147858 73860 147858 73898 147858 73898 147859 73860 147859 73899 147859 73898 147860 73899 147860 73900 147860 73900 147861 73899 147861 73862 147861 73900 147862 73862 147862 73901 147862 73901 147863 73862 147863 73863 147863 73901 147864 73863 147864 73825 147864 73904 147865 73902 147865 73903 147865 73904 147866 73907 147866 73778 147866 73778 147867 73772 147867 73904 147867 73904 147868 73772 147868 73773 147868 73904 147869 73773 147869 73902 147869 73905 147870 73769 147870 73904 147870 73904 147871 73769 147871 73906 147871 73904 147872 73906 147872 73907 147872 73911 147873 73838 147873 73915 147873 73912 147874 73852 147874 73911 147874 73911 147875 73852 147875 73894 147875 73911 147876 73894 147876 73838 147876 73913 147877 73908 147877 73911 147877 73911 147878 73908 147878 73909 147878 73911 147879 73909 147879 73910 147879 73910 147880 73864 147880 73911 147880 73911 147881 73864 147881 73858 147881 73911 147882 73858 147882 73912 147882 73913 147883 73911 147883 73914 147883 73914 147884 73911 147884 73915 147884 73914 147885 73915 147885 73821 147885 73821 147886 73915 147886 73916 147886 73821 147887 73916 147887 73917 147887 73917 147888 73916 147888 73842 147888 73917 147889 73842 147889 73903 147889 73903 147890 73842 147890 73918 147890 73903 147891 73918 147891 73904 147891 73904 147892 73918 147892 73919 147892 73904 147893 73919 147893 73905 147893 73829 147894 73751 147894 73871 147894 73871 147895 73751 147895 73920 147895 73871 147896 73920 147896 73921 147896 73921 147897 73920 147897 73761 147897 73921 147898 73761 147898 73868 147898 73868 147899 73761 147899 73875 147899 73875 147900 73761 147900 73922 147900 73875 147901 73922 147901 73877 147901 73923 147902 73764 147902 73874 147902 73874 147903 73873 147903 73923 147903 73923 147904 73873 147904 73879 147904 73923 147905 73879 147905 73922 147905 73922 147906 73879 147906 73878 147906 73922 147907 73878 147907 73877 147907 73600 147908 73937 147908 73569 147908 73569 147909 73937 147909 73577 147909 73924 147910 73949 147910 73599 147910 73599 147911 73949 147911 73565 147911 73599 147912 73565 147912 73600 147912 73600 147913 73565 147913 73925 147913 73600 147914 73925 147914 73937 147914 73596 147915 73932 147915 73935 147915 73926 147916 73950 147916 73562 147916 73562 147917 73950 147917 73927 147917 73562 147918 73927 147918 73928 147918 73928 147919 73927 147919 73929 147919 73928 147920 73929 147920 73935 147920 73935 147921 73929 147921 73594 147921 73935 147922 73594 147922 73596 147922 73596 147923 73588 147923 73932 147923 73932 147924 73588 147924 73590 147924 73932 147925 73590 147925 73933 147925 73584 147926 73940 147926 73930 147926 73930 147927 73940 147927 73938 147927 73930 147928 73938 147928 73587 147928 73587 147929 73938 147929 73933 147929 73587 147930 73933 147930 73591 147930 73591 147931 73933 147931 73590 147931 73931 147932 73928 147932 73935 147932 73934 147933 73932 147933 73933 147933 73934 147934 73763 147934 73932 147934 73932 147935 73763 147935 73762 147935 73932 147936 73762 147936 73935 147936 73935 147937 73762 147937 73760 147937 73935 147938 73760 147938 73931 147938 73939 147939 73568 147939 73933 147939 73933 147940 73568 147940 73765 147940 73933 147941 73765 147941 73934 147941 73757 147942 73948 147942 73577 147942 73925 147943 73936 147943 73937 147943 73937 147944 73936 147944 73754 147944 73937 147945 73754 147945 73577 147945 73577 147946 73754 147946 73756 147946 73577 147947 73756 147947 73757 147947 73933 147948 73938 147948 73939 147948 73939 147949 73938 147949 73940 147949 73939 147950 73940 147950 73767 147950 73767 147951 73940 147951 73583 147951 73767 147952 73583 147952 73941 147952 73941 147953 73583 147953 73582 147953 73941 147954 73582 147954 73942 147954 73942 147955 73582 147955 73943 147955 73942 147956 73943 147956 73944 147956 73944 147957 73943 147957 73946 147957 73944 147958 73946 147958 73945 147958 73945 147959 73946 147959 73948 147959 73945 147960 73948 147960 73947 147960 73947 147961 73948 147961 73757 147961 73949 147962 73924 147962 73581 147962 73949 147963 73581 147963 73563 147963 73563 147964 73581 147964 73950 147964 73563 147965 73950 147965 73926 147965 73951 147966 74171 147966 74356 147966 73952 147967 73957 147967 73953 147967 74356 147968 73954 147968 73951 147968 73951 147969 73954 147969 73955 147969 73951 147970 73955 147970 73953 147970 73953 147971 73955 147971 73956 147971 73953 147972 73956 147972 73952 147972 73952 147973 73958 147973 73957 147973 73957 147974 73958 147974 73971 147974 73957 147975 73971 147975 74177 147975 73970 147976 74361 147976 73959 147976 73959 147977 74361 147977 74175 147977 73959 147978 74175 147978 73960 147978 73960 147979 74175 147979 74177 147979 73960 147980 74177 147980 73961 147980 73961 147981 74177 147981 73971 147981 74352 147982 74351 147982 73962 147982 73962 147983 74351 147983 74170 147983 73962 147984 74170 147984 73963 147984 73963 147985 74170 147985 73964 147985 73963 147986 73964 147986 74130 147986 74130 147987 73964 147987 73965 147987 74156 147988 74158 147988 73966 147988 73966 147989 74158 147989 74355 147989 73966 147990 74355 147990 74180 147990 74180 147991 74355 147991 73967 147991 74180 147992 73967 147992 74152 147992 74152 147993 73967 147993 74154 147993 74152 147994 74154 147994 73968 147994 73954 147995 74356 147995 73982 147995 73981 147996 73970 147996 73969 147996 73969 147997 73970 147997 73959 147997 73969 147998 73959 147998 74004 147998 74004 147999 73959 147999 73972 147999 73971 148000 73973 148000 73961 148000 73961 148001 73973 148001 73972 148001 73961 148002 73972 148002 73960 148002 73960 148003 73972 148003 73959 148003 73952 148004 74009 148004 73958 148004 73958 148005 74009 148005 74008 148005 73958 148006 74008 148006 73971 148006 73971 148007 74008 148007 74007 148007 73971 148008 74007 148008 73973 148008 73974 148009 73975 148009 73956 148009 73956 148010 73975 148010 74000 148010 73956 148011 74000 148011 73952 148011 73952 148012 74000 148012 73976 148012 73952 148013 73976 148013 74009 148013 73982 148014 74003 148014 73954 148014 73954 148015 74003 148015 73974 148015 73954 148016 73974 148016 73955 148016 73955 148017 73974 148017 73956 148017 73984 148018 74352 148018 73977 148018 73977 148019 74352 148019 73962 148019 73977 148020 73962 148020 74053 148020 74053 148021 73962 148021 73963 148021 74053 148022 73963 148022 73978 148022 73978 148023 73963 148023 74130 148023 73978 148024 74130 148024 73979 148024 74092 148025 74357 148025 74084 148025 74084 148026 74357 148026 74358 148026 74084 148027 74358 148027 74082 148027 74082 148028 74358 148028 73980 148028 74082 148029 73980 148029 73981 148029 73981 148030 73980 148030 73970 148030 73982 148031 74356 148031 74354 148031 73982 148032 74354 148032 74107 148032 74107 148033 74354 148033 74353 148033 74107 148034 74353 148034 73983 148034 73983 148035 74353 148035 74352 148035 73983 148036 74352 148036 73984 148036 74113 148037 74129 148037 74079 148037 73997 148038 74113 148038 73985 148038 73993 148039 73986 148039 74111 148039 74111 148040 73986 148040 73995 148040 74111 148041 73995 148041 74112 148041 74112 148042 73995 148042 73987 148042 74112 148043 73987 148043 74108 148043 74108 148044 73987 148044 74097 148044 73991 148045 74103 148045 74098 148045 73994 148046 73988 148046 73989 148046 73989 148047 73988 148047 74032 148047 73989 148048 74032 148048 73991 148048 73991 148049 74032 148049 73990 148049 73991 148050 73990 148050 74103 148050 74022 148051 73986 148051 73992 148051 73992 148052 73986 148052 73993 148052 73992 148053 73993 148053 74115 148053 74022 148054 73994 148054 73986 148054 73986 148055 73994 148055 73989 148055 73986 148056 73989 148056 73995 148056 73995 148057 73989 148057 73991 148057 73995 148058 73991 148058 73987 148058 73987 148059 73991 148059 74098 148059 73987 148060 74098 148060 74097 148060 74025 148061 73996 148061 74022 148061 74022 148062 73996 148062 74028 148062 74022 148063 74028 148063 73994 148063 74114 148064 73997 148064 74021 148064 74021 148065 73997 148065 73985 148065 74021 148066 73985 148066 74023 148066 74023 148067 73985 148067 74018 148067 74024 148068 74005 148068 74006 148068 74004 148069 73998 148069 73969 148069 73969 148070 73998 148070 74083 148070 73969 148071 74083 148071 73981 148071 74002 148072 74003 148072 73999 148072 73999 148073 74003 148073 73982 148073 73999 148074 73982 148074 74016 148074 73976 148075 74000 148075 74001 148075 74001 148076 74000 148076 73975 148076 74001 148077 73975 148077 74002 148077 74002 148078 73975 148078 73974 148078 74002 148079 73974 148079 74003 148079 74004 148080 73972 148080 74005 148080 74005 148081 73972 148081 73973 148081 74005 148082 73973 148082 74006 148082 74006 148083 73973 148083 74007 148083 74006 148084 74007 148084 74013 148084 74013 148085 74007 148085 74008 148085 74013 148086 74008 148086 74001 148086 74001 148087 74008 148087 74009 148087 74001 148088 74009 148088 73976 148088 74024 148089 74012 148089 74026 148089 74026 148090 74012 148090 74014 148090 74026 148091 74014 148091 74027 148091 74027 148092 74014 148092 74010 148092 74027 148093 74010 148093 74029 148093 74029 148094 74010 148094 74011 148094 74029 148095 74011 148095 74030 148095 74030 148096 74011 148096 74015 148096 74030 148097 74015 148097 74031 148097 74031 148098 74015 148098 74017 148098 74031 148099 74017 148099 74105 148099 74024 148100 74006 148100 74012 148100 74012 148101 74006 148101 74013 148101 74012 148102 74013 148102 74014 148102 74014 148103 74013 148103 74001 148103 74014 148104 74001 148104 74010 148104 74010 148105 74001 148105 74002 148105 74010 148106 74002 148106 74011 148106 74011 148107 74002 148107 73999 148107 74011 148108 73999 148108 74015 148108 74015 148109 73999 148109 74016 148109 74015 148110 74016 148110 74017 148110 74113 148111 74079 148111 73985 148111 73985 148112 74079 148112 74019 148112 73985 148113 74019 148113 74018 148113 74018 148114 74019 148114 74088 148114 74018 148115 74088 148115 74020 148115 74115 148116 74114 148116 73992 148116 73992 148117 74114 148117 74021 148117 73992 148118 74021 148118 74022 148118 74022 148119 74021 148119 74023 148119 74022 148120 74023 148120 74025 148120 74025 148121 74023 148121 74018 148121 74025 148122 74018 148122 73998 148122 73998 148123 74018 148123 74020 148123 73998 148124 74020 148124 74083 148124 74004 148125 74005 148125 73998 148125 73998 148126 74005 148126 74024 148126 73998 148127 74024 148127 74025 148127 74025 148128 74024 148128 74026 148128 74025 148129 74026 148129 73996 148129 73996 148130 74026 148130 74027 148130 73996 148131 74027 148131 74028 148131 74028 148132 74027 148132 74029 148132 74028 148133 74029 148133 73994 148133 73994 148134 74029 148134 74030 148134 73994 148135 74030 148135 73988 148135 73988 148136 74030 148136 74031 148136 73988 148137 74031 148137 74032 148137 74032 148138 74031 148138 74105 148138 74032 148139 74105 148139 73990 148139 74139 148140 74092 148140 74091 148140 74076 148141 74074 148141 74045 148141 74059 148142 74086 148142 74041 148142 74119 148143 74118 148143 74033 148143 74034 148144 74035 148144 74120 148144 74120 148145 74035 148145 74036 148145 74120 148146 74036 148146 74038 148146 74038 148147 74036 148147 74037 148147 74038 148148 74037 148148 74039 148148 74039 148149 74037 148149 74049 148149 74033 148150 74118 148150 74040 148150 74040 148151 74118 148151 74044 148151 74040 148152 74044 148152 74045 148152 74060 148153 74041 148153 74042 148153 74045 148154 74074 148154 74040 148154 74040 148155 74074 148155 74043 148155 74040 148156 74043 148156 74033 148156 74044 148157 74123 148157 74045 148157 74045 148158 74123 148158 74048 148158 74045 148159 74048 148159 74076 148159 74076 148160 74048 148160 74050 148160 74076 148161 74050 148161 74046 148161 74046 148162 74050 148162 74051 148162 74046 148163 74051 148163 74047 148163 74047 148164 74051 148164 74102 148164 74047 148165 74102 148165 74101 148165 74123 148166 74049 148166 74048 148166 74048 148167 74049 148167 74037 148167 74048 148168 74037 148168 74050 148168 74050 148169 74037 148169 74036 148169 74050 148170 74036 148170 74051 148170 74051 148171 74036 148171 74035 148171 74051 148172 74035 148172 74102 148172 73979 148173 74131 148173 74069 148173 74069 148174 74052 148174 73979 148174 73979 148175 74052 148175 74067 148175 73979 148176 74067 148176 73978 148176 73978 148177 74067 148177 74055 148177 73978 148178 74055 148178 74053 148178 74053 148179 74055 148179 73977 148179 74054 148180 74093 148180 74055 148180 74055 148181 74093 148181 73984 148181 74055 148182 73984 148182 73977 148182 74134 148183 74135 148183 74056 148183 74056 148184 74071 148184 74134 148184 74134 148185 74071 148185 74069 148185 74134 148186 74069 148186 74133 148186 74133 148187 74069 148187 74131 148187 74135 148188 74136 148188 74056 148188 74056 148189 74136 148189 74139 148189 74056 148190 74139 148190 74057 148190 74057 148191 74139 148191 74091 148191 74057 148192 74091 148192 74058 148192 74041 148193 74060 148193 74059 148193 74059 148194 74060 148194 74061 148194 74059 148195 74061 148195 74072 148195 74072 148196 74061 148196 74073 148196 74072 148197 74073 148197 74062 148197 74062 148198 74073 148198 74075 148198 74062 148199 74075 148199 74070 148199 74070 148200 74075 148200 74063 148200 74070 148201 74063 148201 74068 148201 74068 148202 74063 148202 74064 148202 74068 148203 74064 148203 74065 148203 74065 148204 74064 148204 74077 148204 74065 148205 74077 148205 74066 148205 74066 148206 74077 148206 74078 148206 74066 148207 74078 148207 74054 148207 74054 148208 74055 148208 74066 148208 74066 148209 74055 148209 74067 148209 74066 148210 74067 148210 74065 148210 74065 148211 74067 148211 74052 148211 74065 148212 74052 148212 74068 148212 74068 148213 74052 148213 74069 148213 74068 148214 74069 148214 74070 148214 74070 148215 74069 148215 74071 148215 74070 148216 74071 148216 74062 148216 74062 148217 74071 148217 74056 148217 74062 148218 74056 148218 74072 148218 74072 148219 74056 148219 74057 148219 74072 148220 74057 148220 74059 148220 74059 148221 74057 148221 74058 148221 74059 148222 74058 148222 74086 148222 74042 148223 74119 148223 74060 148223 74060 148224 74119 148224 74033 148224 74060 148225 74033 148225 74061 148225 74061 148226 74033 148226 74043 148226 74061 148227 74043 148227 74073 148227 74073 148228 74043 148228 74074 148228 74073 148229 74074 148229 74075 148229 74075 148230 74074 148230 74076 148230 74075 148231 74076 148231 74063 148231 74063 148232 74076 148232 74046 148232 74063 148233 74046 148233 74064 148233 74064 148234 74046 148234 74047 148234 74064 148235 74047 148235 74077 148235 74077 148236 74047 148236 74101 148236 74077 148237 74101 148237 74078 148237 74089 148238 74085 148238 74087 148238 74116 148239 74042 148239 74041 148239 74079 148240 74129 148240 74080 148240 74088 148241 74019 148241 74089 148241 74089 148242 74019 148242 74079 148242 74079 148243 74080 148243 74089 148243 74089 148244 74080 148244 74081 148244 74089 148245 74081 148245 74085 148245 74085 148246 74081 148246 74126 148246 74085 148247 74126 148247 74116 148247 74083 148248 74020 148248 74090 148248 74090 148249 74020 148249 74088 148249 73981 148250 74083 148250 74082 148250 74082 148251 74083 148251 74090 148251 74082 148252 74090 148252 74084 148252 74116 148253 74041 148253 74085 148253 74085 148254 74041 148254 74086 148254 74085 148255 74086 148255 74087 148255 74087 148256 74086 148256 74058 148256 74087 148257 74058 148257 74091 148257 74088 148258 74089 148258 74090 148258 74090 148259 74089 148259 74087 148259 74090 148260 74087 148260 74084 148260 74084 148261 74087 148261 74091 148261 74084 148262 74091 148262 74092 148262 74093 148263 74054 148263 74106 148263 74125 148264 74127 148264 74100 148264 74034 148265 74094 148265 74035 148265 74035 148266 74094 148266 74099 148266 74108 148267 74097 148267 74128 148267 74128 148268 74097 148268 74127 148268 74095 148269 74096 148269 74104 148269 74104 148270 74096 148270 74099 148270 74127 148271 74097 148271 74100 148271 74100 148272 74097 148272 74098 148272 74100 148273 74098 148273 74103 148273 74094 148274 74125 148274 74099 148274 74099 148275 74125 148275 74100 148275 74099 148276 74100 148276 74104 148276 74104 148277 74100 148277 74103 148277 74054 148278 74078 148278 74096 148278 74096 148279 74078 148279 74101 148279 74096 148280 74101 148280 74099 148280 74099 148281 74101 148281 74102 148281 74099 148282 74102 148282 74035 148282 74107 148283 73983 148283 74106 148283 74106 148284 73983 148284 73984 148284 74106 148285 73984 148285 74093 148285 74103 148286 73990 148286 74104 148286 74104 148287 73990 148287 74105 148287 74104 148288 74105 148288 74095 148288 74095 148289 74105 148289 74017 148289 74095 148290 74017 148290 74016 148290 74054 148291 74096 148291 74106 148291 74106 148292 74096 148292 74095 148292 74106 148293 74095 148293 74107 148293 74107 148294 74095 148294 74016 148294 74107 148295 74016 148295 73982 148295 74109 148296 74108 148296 74128 148296 74109 148297 74115 148297 74110 148297 74110 148298 74111 148298 74109 148298 74109 148299 74111 148299 74112 148299 74109 148300 74112 148300 74108 148300 74113 148301 73997 148301 74109 148301 74109 148302 73997 148302 74114 148302 74109 148303 74114 148303 74115 148303 74124 148304 74042 148304 74116 148304 74117 148305 74118 148305 74124 148305 74124 148306 74118 148306 74119 148306 74124 148307 74119 148307 74042 148307 74034 148308 74120 148308 74124 148308 74124 148309 74120 148309 74038 148309 74124 148310 74038 148310 74121 148310 74121 148311 74122 148311 74124 148311 74124 148312 74122 148312 74123 148312 74124 148313 74123 148313 74117 148313 74034 148314 74124 148314 74094 148314 74094 148315 74124 148315 74116 148315 74094 148316 74116 148316 74125 148316 74125 148317 74116 148317 74126 148317 74125 148318 74126 148318 74127 148318 74127 148319 74126 148319 74081 148319 74127 148320 74081 148320 74128 148320 74128 148321 74081 148321 74080 148321 74128 148322 74080 148322 74109 148322 74109 148323 74080 148323 74129 148323 74109 148324 74129 148324 74113 148324 73979 148325 74130 148325 74131 148325 74131 148326 74130 148326 74132 148326 74131 148327 74132 148327 74133 148327 74133 148328 74132 148328 74134 148328 74134 148329 74132 148329 74141 148329 74134 148330 74141 148330 74135 148330 74135 148331 74141 148331 74142 148331 74135 148332 74142 148332 74136 148332 74142 148333 74137 148333 74136 148333 74136 148334 74137 148334 74138 148334 74136 148335 74138 148335 74139 148335 74139 148336 74138 148336 74357 148336 74139 148337 74357 148337 74092 148337 74166 148338 74357 148338 74140 148338 74140 148339 74357 148339 74138 148339 74140 148340 74138 148340 74167 148340 74167 148341 74138 148341 74137 148341 74130 148342 73965 148342 74132 148342 74132 148343 73965 148343 74168 148343 74132 148344 74168 148344 74141 148344 74141 148345 74168 148345 74167 148345 74141 148346 74167 148346 74142 148346 74142 148347 74167 148347 74137 148347 74143 148348 74201 148348 74150 148348 74143 148349 74150 148349 74300 148349 74150 148350 74146 148350 74300 148350 74300 148351 74146 148351 74147 148351 74300 148352 74147 148352 74144 148352 74150 148353 74145 148353 74146 148353 74146 148354 74145 148354 74176 148354 74146 148355 74176 148355 74147 148355 74147 148356 74176 148356 74174 148356 74153 148357 74149 148357 74148 148357 74148 148358 74149 148358 74179 148358 74148 148359 74179 148359 74203 148359 74203 148360 74179 148360 74178 148360 74203 148361 74178 148361 74150 148361 74150 148362 74178 148362 74145 148362 74151 148363 74152 148363 74198 148363 74198 148364 74152 148364 73968 148364 74198 148365 73968 148365 74153 148365 74153 148366 73968 148366 74154 148366 74153 148367 74154 148367 74149 148367 74155 148368 74169 148368 74159 148368 73966 148369 74181 148369 74156 148369 74156 148370 74181 148370 74157 148370 74156 148371 74157 148371 74158 148371 74158 148372 74157 148372 74189 148372 74158 148373 74189 148373 74159 148373 74159 148374 74189 148374 74191 148374 74159 148375 74191 148375 74155 148375 74155 148376 74187 148376 74169 148376 74169 148377 74187 148377 74160 148377 74169 148378 74160 148378 74164 148378 74161 148379 74172 148379 74163 148379 74163 148380 74172 148380 74162 148380 74163 148381 74162 148381 74185 148381 74185 148382 74162 148382 74164 148382 74185 148383 74164 148383 74165 148383 74165 148384 74164 148384 74160 148384 74351 148385 74158 148385 74159 148385 74168 148386 74169 148386 74164 148386 74166 148387 74140 148387 74164 148387 74164 148388 74140 148388 74167 148388 74164 148389 74167 148389 74168 148389 74168 148390 73965 148390 74169 148390 74169 148391 73965 148391 73964 148391 74169 148392 73964 148392 74159 148392 74159 148393 73964 148393 74170 148393 74159 148394 74170 148394 74351 148394 74154 148395 74171 148395 74149 148395 74149 148396 74171 148396 73951 148396 74149 148397 73951 148397 74179 148397 74164 148398 74162 148398 74166 148398 74166 148399 74162 148399 74172 148399 74166 148400 74172 148400 74359 148400 74359 148401 74172 148401 74173 148401 74359 148402 74173 148402 74360 148402 74360 148403 74173 148403 74174 148403 74360 148404 74174 148404 74361 148404 74361 148405 74174 148405 74176 148405 74361 148406 74176 148406 74175 148406 74175 148407 74176 148407 74145 148407 74175 148408 74145 148408 74177 148408 74177 148409 74145 148409 74178 148409 74177 148410 74178 148410 73957 148410 73957 148411 74178 148411 74179 148411 73957 148412 74179 148412 73953 148412 73953 148413 74179 148413 73951 148413 74152 148414 74151 148414 74182 148414 74152 148415 74182 148415 74180 148415 74180 148416 74182 148416 74181 148416 74180 148417 74181 148417 73966 148417 74246 148418 74181 148418 74207 148418 74207 148419 74181 148419 74182 148419 74207 148420 74182 148420 74208 148420 74151 148421 74195 148421 74182 148421 74182 148422 74195 148422 74209 148422 74182 148423 74209 148423 74208 148423 74147 148424 74174 148424 74183 148424 74183 148425 74174 148425 74173 148425 74183 148426 74173 148426 74161 148426 74161 148427 74173 148427 74172 148427 74157 148428 74181 148428 74246 148428 74219 148429 74161 148429 74260 148429 74260 148430 74161 148430 74163 148430 74260 148431 74163 148431 74232 148431 74232 148432 74163 148432 74184 148432 74163 148433 74185 148433 74184 148433 74184 148434 74185 148434 74165 148434 74184 148435 74165 148435 74186 148435 74155 148436 74265 148436 74187 148436 74187 148437 74265 148437 74186 148437 74187 148438 74186 148438 74160 148438 74160 148439 74186 148439 74165 148439 74246 148440 74247 148440 74157 148440 74157 148441 74247 148441 74188 148441 74157 148442 74188 148442 74189 148442 74189 148443 74188 148443 74248 148443 74189 148444 74248 148444 74191 148444 74191 148445 74248 148445 74190 148445 74191 148446 74190 148446 74155 148446 74155 148447 74190 148447 74192 148447 74155 148448 74192 148448 74265 148448 74193 148449 74194 148449 74153 148449 74195 148450 74151 148450 74296 148450 74296 148451 74151 148451 74198 148451 74194 148452 74295 148452 74153 148452 74153 148453 74295 148453 74196 148453 74153 148454 74196 148454 74198 148454 74198 148455 74196 148455 74197 148455 74198 148456 74197 148456 74296 148456 74193 148457 74153 148457 74199 148457 74199 148458 74153 148458 74148 148458 74199 148459 74148 148459 74292 148459 74292 148460 74148 148460 74200 148460 74200 148461 74148 148461 74203 148461 74200 148462 74203 148462 74299 148462 74150 148463 74201 148463 74203 148463 74203 148464 74201 148464 74202 148464 74203 148465 74202 148465 74299 148465 74218 148466 74204 148466 74334 148466 74204 148467 74218 148467 74288 148467 74205 148468 74212 148468 74213 148468 74206 148469 74246 148469 74207 148469 74241 148470 74243 148470 74205 148470 74205 148471 74243 148471 74206 148471 74206 148472 74207 148472 74205 148472 74205 148473 74207 148473 74208 148473 74205 148474 74208 148474 74212 148474 74212 148475 74208 148475 74209 148475 74212 148476 74209 148476 74195 148476 74269 148477 74210 148477 74211 148477 74211 148478 74210 148478 74241 148478 74195 148479 74297 148479 74212 148479 74212 148480 74297 148480 74306 148480 74212 148481 74306 148481 74213 148481 74213 148482 74306 148482 74305 148482 74213 148483 74305 148483 74215 148483 74216 148484 74269 148484 74214 148484 74214 148485 74269 148485 74211 148485 74214 148486 74211 148486 74218 148486 74241 148487 74205 148487 74211 148487 74211 148488 74205 148488 74213 148488 74211 148489 74213 148489 74218 148489 74218 148490 74213 148490 74215 148490 74218 148491 74215 148491 74288 148491 74323 148492 74216 148492 74324 148492 74324 148493 74216 148493 74214 148493 74324 148494 74214 148494 74217 148494 74217 148495 74214 148495 74218 148495 74217 148496 74218 148496 74335 148496 74335 148497 74218 148497 74334 148497 74183 148498 74161 148498 74219 148498 74219 148499 74350 148499 74183 148499 74183 148500 74350 148500 74348 148500 74183 148501 74348 148501 74147 148501 74147 148502 74348 148502 74346 148502 74147 148503 74346 148503 74144 148503 74192 148504 74190 148504 74249 148504 74248 148505 74188 148505 74250 148505 74220 148506 74233 148506 74240 148506 74328 148507 74238 148507 74227 148507 74329 148508 74338 148508 74221 148508 74220 148509 74330 148509 74233 148509 74233 148510 74330 148510 74222 148510 74233 148511 74222 148511 74329 148511 74325 148512 74326 148512 74223 148512 74223 148513 74326 148513 74224 148513 74223 148514 74224 148514 74226 148514 74223 148515 74225 148515 74325 148515 74325 148516 74225 148516 74216 148516 74325 148517 74216 148517 74323 148517 74224 148518 74328 148518 74226 148518 74226 148519 74328 148519 74227 148519 74226 148520 74227 148520 74228 148520 74228 148521 74227 148521 74239 148521 74228 148522 74239 148522 74267 148522 74267 148523 74239 148523 74229 148523 74267 148524 74229 148524 74266 148524 74266 148525 74229 148525 74230 148525 74266 148526 74230 148526 74231 148526 74260 148527 74232 148527 74234 148527 74234 148528 74232 148528 74236 148528 74329 148529 74221 148529 74233 148529 74233 148530 74221 148530 74262 148530 74233 148531 74262 148531 74240 148531 74240 148532 74262 148532 74234 148532 74240 148533 74234 148533 74235 148533 74235 148534 74234 148534 74236 148534 74235 148535 74236 148535 74237 148535 74238 148536 74330 148536 74227 148536 74227 148537 74330 148537 74220 148537 74227 148538 74220 148538 74239 148538 74239 148539 74220 148539 74240 148539 74239 148540 74240 148540 74229 148540 74229 148541 74240 148541 74235 148541 74229 148542 74235 148542 74230 148542 74230 148543 74235 148543 74237 148543 74230 148544 74237 148544 74231 148544 74192 148545 74249 148545 74265 148545 74269 148546 74255 148546 74210 148546 74210 148547 74255 148547 74242 148547 74210 148548 74242 148548 74241 148548 74241 148549 74242 148549 74256 148549 74241 148550 74256 148550 74243 148550 74243 148551 74256 148551 74244 148551 74243 148552 74244 148552 74206 148552 74206 148553 74244 148553 74245 148553 74206 148554 74245 148554 74246 148554 74246 148555 74245 148555 74247 148555 74190 148556 74248 148556 74249 148556 74249 148557 74248 148557 74250 148557 74249 148558 74250 148558 74251 148558 74251 148559 74250 148559 74258 148559 74251 148560 74258 148560 74268 148560 74268 148561 74258 148561 74257 148561 74268 148562 74257 148562 74252 148562 74252 148563 74257 148563 74253 148563 74252 148564 74253 148564 74254 148564 74255 148565 74254 148565 74242 148565 74242 148566 74254 148566 74253 148566 74242 148567 74253 148567 74256 148567 74256 148568 74253 148568 74257 148568 74256 148569 74257 148569 74244 148569 74244 148570 74257 148570 74258 148570 74244 148571 74258 148571 74245 148571 74245 148572 74258 148572 74250 148572 74245 148573 74250 148573 74247 148573 74247 148574 74250 148574 74188 148574 74219 148575 74260 148575 74259 148575 74259 148576 74260 148576 74234 148576 74259 148577 74234 148577 74261 148577 74261 148578 74234 148578 74262 148578 74261 148579 74262 148579 74263 148579 74263 148580 74262 148580 74221 148580 74263 148581 74221 148581 74264 148581 74264 148582 74221 148582 74338 148582 74264 148583 74338 148583 74337 148583 74232 148584 74184 148584 74236 148584 74236 148585 74184 148585 74186 148585 74236 148586 74186 148586 74237 148586 74237 148587 74186 148587 74265 148587 74237 148588 74265 148588 74231 148588 74231 148589 74265 148589 74249 148589 74231 148590 74249 148590 74266 148590 74266 148591 74249 148591 74251 148591 74266 148592 74251 148592 74267 148592 74267 148593 74251 148593 74268 148593 74267 148594 74268 148594 74228 148594 74228 148595 74268 148595 74252 148595 74228 148596 74252 148596 74226 148596 74226 148597 74252 148597 74254 148597 74226 148598 74254 148598 74223 148598 74223 148599 74254 148599 74255 148599 74223 148600 74255 148600 74225 148600 74225 148601 74255 148601 74269 148601 74225 148602 74269 148602 74216 148602 74300 148603 74144 148603 74270 148603 74283 148604 74271 148604 74279 148604 74316 148605 74342 148605 74340 148605 74272 148606 74273 148606 74290 148606 74290 148607 74273 148607 74333 148607 74290 148608 74333 148608 74291 148608 74291 148609 74333 148609 74334 148609 74291 148610 74334 148610 74204 148610 74301 148611 74340 148611 74274 148611 74275 148612 74332 148612 74276 148612 74276 148613 74332 148613 74278 148613 74276 148614 74278 148614 74277 148614 74277 148615 74278 148615 74281 148615 74277 148616 74281 148616 74279 148616 74279 148617 74271 148617 74277 148617 74277 148618 74271 148618 74280 148618 74277 148619 74280 148619 74276 148619 74281 148620 74282 148620 74279 148620 74279 148621 74282 148621 74289 148621 74279 148622 74289 148622 74283 148622 74283 148623 74289 148623 74284 148623 74283 148624 74284 148624 74285 148624 74285 148625 74284 148625 74287 148625 74285 148626 74287 148626 74286 148626 74286 148627 74287 148627 74288 148627 74286 148628 74288 148628 74215 148628 74282 148629 74272 148629 74289 148629 74289 148630 74272 148630 74290 148630 74289 148631 74290 148631 74284 148631 74284 148632 74290 148632 74291 148632 74284 148633 74291 148633 74287 148633 74287 148634 74291 148634 74204 148634 74287 148635 74204 148635 74288 148635 74293 148636 74199 148636 74292 148636 74293 148637 74292 148637 74310 148637 74199 148638 74293 148638 74193 148638 74193 148639 74293 148639 74294 148639 74193 148640 74294 148640 74194 148640 74296 148641 74197 148641 74307 148641 74307 148642 74197 148642 74196 148642 74307 148643 74196 148643 74294 148643 74294 148644 74196 148644 74295 148644 74294 148645 74295 148645 74194 148645 74195 148646 74296 148646 74297 148646 74297 148647 74296 148647 74307 148647 74297 148648 74307 148648 74306 148648 74201 148649 74313 148649 74202 148649 74202 148650 74313 148650 74298 148650 74202 148651 74298 148651 74299 148651 74299 148652 74298 148652 74310 148652 74299 148653 74310 148653 74200 148653 74200 148654 74310 148654 74292 148654 74201 148655 74143 148655 74313 148655 74313 148656 74143 148656 74300 148656 74313 148657 74300 148657 74314 148657 74314 148658 74300 148658 74270 148658 74314 148659 74270 148659 74315 148659 74340 148660 74301 148660 74316 148660 74316 148661 74301 148661 74317 148661 74316 148662 74317 148662 74312 148662 74312 148663 74317 148663 74318 148663 74312 148664 74318 148664 74311 148664 74311 148665 74318 148665 74319 148665 74311 148666 74319 148666 74302 148666 74302 148667 74319 148667 74303 148667 74302 148668 74303 148668 74304 148668 74304 148669 74303 148669 74320 148669 74304 148670 74320 148670 74309 148670 74309 148671 74320 148671 74321 148671 74309 148672 74321 148672 74308 148672 74308 148673 74321 148673 74305 148673 74308 148674 74305 148674 74306 148674 74306 148675 74307 148675 74308 148675 74308 148676 74307 148676 74294 148676 74308 148677 74294 148677 74309 148677 74309 148678 74294 148678 74293 148678 74309 148679 74293 148679 74304 148679 74304 148680 74293 148680 74310 148680 74304 148681 74310 148681 74302 148681 74302 148682 74310 148682 74298 148682 74302 148683 74298 148683 74311 148683 74311 148684 74298 148684 74313 148684 74311 148685 74313 148685 74312 148685 74312 148686 74313 148686 74314 148686 74312 148687 74314 148687 74316 148687 74316 148688 74314 148688 74315 148688 74316 148689 74315 148689 74342 148689 74274 148690 74275 148690 74301 148690 74301 148691 74275 148691 74276 148691 74301 148692 74276 148692 74317 148692 74317 148693 74276 148693 74280 148693 74317 148694 74280 148694 74318 148694 74318 148695 74280 148695 74271 148695 74318 148696 74271 148696 74319 148696 74319 148697 74271 148697 74283 148697 74319 148698 74283 148698 74303 148698 74303 148699 74283 148699 74285 148699 74303 148700 74285 148700 74320 148700 74320 148701 74285 148701 74286 148701 74320 148702 74286 148702 74321 148702 74321 148703 74286 148703 74215 148703 74321 148704 74215 148704 74305 148704 74331 148705 74274 148705 74322 148705 74327 148706 74323 148706 74324 148706 74325 148707 74323 148707 74326 148707 74326 148708 74323 148708 74327 148708 74326 148709 74327 148709 74224 148709 74224 148710 74327 148710 74328 148710 74338 148711 74329 148711 74327 148711 74327 148712 74329 148712 74222 148712 74222 148713 74330 148713 74327 148713 74327 148714 74330 148714 74238 148714 74327 148715 74238 148715 74328 148715 74272 148716 74282 148716 74331 148716 74331 148717 74282 148717 74281 148717 74275 148718 74274 148718 74332 148718 74332 148719 74274 148719 74331 148719 74332 148720 74331 148720 74278 148720 74278 148721 74331 148721 74281 148721 74334 148722 74333 148722 74331 148722 74331 148723 74333 148723 74273 148723 74331 148724 74273 148724 74272 148724 74334 148725 74331 148725 74335 148725 74335 148726 74331 148726 74322 148726 74335 148727 74322 148727 74217 148727 74217 148728 74322 148728 74336 148728 74217 148729 74336 148729 74324 148729 74324 148730 74336 148730 74339 148730 74324 148731 74339 148731 74327 148731 74327 148732 74339 148732 74337 148732 74327 148733 74337 148733 74338 148733 74270 148734 74144 148734 74346 148734 74342 148735 74315 148735 74347 148735 74259 148736 74261 148736 74349 148736 74263 148737 74264 148737 74345 148737 74264 148738 74337 148738 74345 148738 74345 148739 74337 148739 74339 148739 74345 148740 74339 148740 74343 148740 74343 148741 74339 148741 74336 148741 74343 148742 74336 148742 74341 148742 74341 148743 74336 148743 74322 148743 74341 148744 74322 148744 74340 148744 74340 148745 74322 148745 74274 148745 74340 148746 74342 148746 74341 148746 74341 148747 74342 148747 74347 148747 74341 148748 74347 148748 74343 148748 74343 148749 74347 148749 74344 148749 74343 148750 74344 148750 74345 148750 74345 148751 74344 148751 74349 148751 74345 148752 74349 148752 74263 148752 74263 148753 74349 148753 74261 148753 74315 148754 74270 148754 74347 148754 74347 148755 74270 148755 74346 148755 74347 148756 74346 148756 74344 148756 74344 148757 74346 148757 74348 148757 74344 148758 74348 148758 74349 148758 74349 148759 74348 148759 74350 148759 74349 148760 74350 148760 74259 148760 74259 148761 74350 148761 74219 148761 74158 148762 74351 148762 74352 148762 74158 148763 74352 148763 74355 148763 74352 148764 74353 148764 74355 148764 74355 148765 74353 148765 74354 148765 74355 148766 74354 148766 73967 148766 73967 148767 74354 148767 74154 148767 74154 148768 74354 148768 74356 148768 74154 148769 74356 148769 74171 148769 74357 148770 74166 148770 74358 148770 74358 148771 74166 148771 74359 148771 74358 148772 74359 148772 73980 148772 73980 148773 74359 148773 74360 148773 73980 148774 74360 148774 73970 148774 73970 148775 74360 148775 74361 148775 74649 148776 74362 148776 74363 148776 74363 148777 74362 148777 74365 148777 74363 148778 74365 148778 74646 148778 74364 148779 74642 148779 74375 148779 74375 148780 74642 148780 74366 148780 74375 148781 74366 148781 74365 148781 74365 148782 74366 148782 74644 148782 74365 148783 74644 148783 74646 148783 74364 148784 74375 148784 74367 148784 74367 148785 74375 148785 74368 148785 74367 148786 74368 148786 74650 148786 74650 148787 74368 148787 74373 148787 74650 148788 74373 148788 74369 148788 74369 148789 74373 148789 74370 148789 74369 148790 74370 148790 74652 148790 74370 148791 74371 148791 74652 148791 74652 148792 74371 148792 74372 148792 74652 148793 74372 148793 74653 148793 74653 148794 74372 148794 74532 148794 74653 148795 74532 148795 74621 148795 74742 148796 74532 148796 74741 148796 74741 148797 74532 148797 74372 148797 74741 148798 74372 148798 74374 148798 74374 148799 74372 148799 74371 148799 74371 148800 74370 148800 74374 148800 74374 148801 74370 148801 74373 148801 74374 148802 74373 148802 74743 148802 74362 148803 74745 148803 74365 148803 74365 148804 74745 148804 74744 148804 74365 148805 74744 148805 74375 148805 74375 148806 74744 148806 74743 148806 74375 148807 74743 148807 74368 148807 74368 148808 74743 148808 74373 148808 74376 148809 74445 148809 74776 148809 74776 148810 74445 148810 74444 148810 74776 148811 74444 148811 74777 148811 74776 148812 74753 148812 74376 148812 74376 148813 74753 148813 74751 148813 74386 148814 74377 148814 74449 148814 74377 148815 74386 148815 74457 148815 74378 148816 74381 148816 74387 148816 74379 148817 74420 148817 74760 148817 74416 148818 74417 148818 74378 148818 74378 148819 74417 148819 74379 148819 74379 148820 74760 148820 74378 148820 74378 148821 74760 148821 74380 148821 74378 148822 74380 148822 74381 148822 74381 148823 74380 148823 74761 148823 74381 148824 74761 148824 74382 148824 74384 148825 74413 148825 74385 148825 74385 148826 74413 148826 74416 148826 74382 148827 74383 148827 74381 148827 74381 148828 74383 148828 74482 148828 74381 148829 74482 148829 74387 148829 74387 148830 74482 148830 74496 148830 74387 148831 74496 148831 74388 148831 74389 148832 74384 148832 74390 148832 74390 148833 74384 148833 74385 148833 74390 148834 74385 148834 74386 148834 74416 148835 74378 148835 74385 148835 74385 148836 74378 148836 74387 148836 74385 148837 74387 148837 74386 148837 74386 148838 74387 148838 74388 148838 74386 148839 74388 148839 74457 148839 74398 148840 74389 148840 74511 148840 74511 148841 74389 148841 74390 148841 74511 148842 74390 148842 74510 148842 74510 148843 74390 148843 74386 148843 74510 148844 74386 148844 74509 148844 74509 148845 74386 148845 74449 148845 74445 148846 74376 148846 74391 148846 74391 148847 74376 148847 74762 148847 74391 148848 74762 148848 74527 148848 74765 148849 74392 148849 74762 148849 74762 148850 74392 148850 74528 148850 74762 148851 74528 148851 74527 148851 74771 148852 74770 148852 74393 148852 74768 148853 74428 148853 74421 148853 74407 148854 74404 148854 74408 148854 74499 148855 74503 148855 74394 148855 74501 148856 74513 148856 74405 148856 74407 148857 74406 148857 74404 148857 74404 148858 74406 148858 74395 148858 74404 148859 74395 148859 74501 148859 74396 148860 74497 148860 74397 148860 74397 148861 74497 148861 74498 148861 74397 148862 74498 148862 74442 148862 74397 148863 74443 148863 74396 148863 74396 148864 74443 148864 74389 148864 74396 148865 74389 148865 74398 148865 74498 148866 74499 148866 74442 148866 74442 148867 74499 148867 74394 148867 74442 148868 74394 148868 74441 148868 74441 148869 74394 148869 74399 148869 74441 148870 74399 148870 74400 148870 74400 148871 74399 148871 74409 148871 74400 148872 74409 148872 74437 148872 74437 148873 74409 148873 74410 148873 74437 148874 74410 148874 74412 148874 74401 148875 74432 148875 74402 148875 74402 148876 74432 148876 74403 148876 74501 148877 74405 148877 74404 148877 74404 148878 74405 148878 74430 148878 74404 148879 74430 148879 74408 148879 74408 148880 74430 148880 74402 148880 74408 148881 74402 148881 74411 148881 74411 148882 74402 148882 74403 148882 74411 148883 74403 148883 74435 148883 74503 148884 74406 148884 74394 148884 74394 148885 74406 148885 74407 148885 74394 148886 74407 148886 74399 148886 74399 148887 74407 148887 74408 148887 74399 148888 74408 148888 74409 148888 74409 148889 74408 148889 74411 148889 74409 148890 74411 148890 74410 148890 74410 148891 74411 148891 74435 148891 74410 148892 74435 148892 74412 148892 74771 148893 74393 148893 74436 148893 74384 148894 74414 148894 74413 148894 74413 148895 74414 148895 74415 148895 74413 148896 74415 148896 74416 148896 74416 148897 74415 148897 74425 148897 74416 148898 74425 148898 74417 148898 74417 148899 74425 148899 74418 148899 74417 148900 74418 148900 74379 148900 74379 148901 74418 148901 74419 148901 74379 148902 74419 148902 74420 148902 74420 148903 74419 148903 74427 148903 74770 148904 74768 148904 74393 148904 74393 148905 74768 148905 74421 148905 74393 148906 74421 148906 74438 148906 74438 148907 74421 148907 74422 148907 74438 148908 74422 148908 74439 148908 74439 148909 74422 148909 74423 148909 74439 148910 74423 148910 74440 148910 74440 148911 74423 148911 74426 148911 74440 148912 74426 148912 74424 148912 74414 148913 74424 148913 74415 148913 74415 148914 74424 148914 74426 148914 74415 148915 74426 148915 74425 148915 74425 148916 74426 148916 74423 148916 74425 148917 74423 148917 74418 148917 74418 148918 74423 148918 74422 148918 74418 148919 74422 148919 74419 148919 74419 148920 74422 148920 74421 148920 74419 148921 74421 148921 74427 148921 74427 148922 74421 148922 74428 148922 74392 148923 74401 148923 74514 148923 74514 148924 74401 148924 74402 148924 74514 148925 74402 148925 74515 148925 74515 148926 74402 148926 74430 148926 74515 148927 74430 148927 74429 148927 74429 148928 74430 148928 74405 148928 74429 148929 74405 148929 74516 148929 74516 148930 74405 148930 74513 148930 74516 148931 74513 148931 74431 148931 74432 148932 74433 148932 74403 148932 74403 148933 74433 148933 74434 148933 74403 148934 74434 148934 74435 148934 74435 148935 74434 148935 74436 148935 74435 148936 74436 148936 74412 148936 74412 148937 74436 148937 74393 148937 74412 148938 74393 148938 74437 148938 74437 148939 74393 148939 74438 148939 74437 148940 74438 148940 74400 148940 74400 148941 74438 148941 74439 148941 74400 148942 74439 148942 74441 148942 74441 148943 74439 148943 74440 148943 74441 148944 74440 148944 74442 148944 74442 148945 74440 148945 74424 148945 74442 148946 74424 148946 74397 148946 74397 148947 74424 148947 74414 148947 74397 148948 74414 148948 74443 148948 74443 148949 74414 148949 74384 148949 74443 148950 74384 148950 74389 148950 74444 148951 74445 148951 74525 148951 74492 148952 74491 148952 74453 148952 74470 148953 74489 148953 74520 148953 74446 148954 74448 148954 74447 148954 74447 148955 74448 148955 74508 148955 74447 148956 74508 148956 74460 148956 74460 148957 74508 148957 74449 148957 74460 148958 74449 148958 74377 148958 74471 148959 74520 148959 74450 148959 74505 148960 74451 148960 74454 148960 74454 148961 74451 148961 74506 148961 74454 148962 74506 148962 74452 148962 74452 148963 74506 148963 74455 148963 74452 148964 74455 148964 74453 148964 74453 148965 74491 148965 74452 148965 74452 148966 74491 148966 74490 148966 74452 148967 74490 148967 74454 148967 74455 148968 74504 148968 74453 148968 74453 148969 74504 148969 74458 148969 74453 148970 74458 148970 74492 148970 74492 148971 74458 148971 74456 148971 74492 148972 74456 148972 74493 148972 74493 148973 74456 148973 74459 148973 74493 148974 74459 148974 74495 148974 74495 148975 74459 148975 74457 148975 74495 148976 74457 148976 74388 148976 74504 148977 74446 148977 74458 148977 74458 148978 74446 148978 74447 148978 74458 148979 74447 148979 74456 148979 74456 148980 74447 148980 74460 148980 74456 148981 74460 148981 74459 148981 74459 148982 74460 148982 74377 148982 74459 148983 74377 148983 74457 148983 74463 148984 74461 148984 74462 148984 74463 148985 74462 148985 74466 148985 74461 148986 74463 148986 74464 148986 74464 148987 74463 148987 74484 148987 74464 148988 74484 148988 74773 148988 74773 148989 74484 148989 74483 148989 74773 148990 74483 148990 74465 148990 74382 148991 74465 148991 74383 148991 74383 148992 74465 148992 74483 148992 74383 148993 74483 148993 74482 148993 74444 148994 74525 148994 74777 148994 74467 148995 74780 148995 74487 148995 74487 148996 74486 148996 74467 148996 74467 148997 74486 148997 74466 148997 74467 148998 74466 148998 74468 148998 74468 148999 74466 148999 74462 148999 74780 149000 74778 149000 74487 149000 74487 149001 74778 149001 74777 149001 74487 149002 74777 149002 74469 149002 74469 149003 74777 149003 74525 149003 74469 149004 74525 149004 74488 149004 74520 149005 74471 149005 74470 149005 74470 149006 74471 149006 74472 149006 74470 149007 74472 149007 74473 149007 74473 149008 74472 149008 74475 149008 74473 149009 74475 149009 74474 149009 74474 149010 74475 149010 74476 149010 74474 149011 74476 149011 74477 149011 74477 149012 74476 149012 74478 149012 74477 149013 74478 149013 74479 149013 74479 149014 74478 149014 74494 149014 74479 149015 74494 149015 74485 149015 74485 149016 74494 149016 74480 149016 74485 149017 74480 149017 74481 149017 74481 149018 74480 149018 74496 149018 74481 149019 74496 149019 74482 149019 74482 149020 74483 149020 74481 149020 74481 149021 74483 149021 74484 149021 74481 149022 74484 149022 74485 149022 74485 149023 74484 149023 74463 149023 74485 149024 74463 149024 74479 149024 74479 149025 74463 149025 74466 149025 74479 149026 74466 149026 74477 149026 74477 149027 74466 149027 74486 149027 74477 149028 74486 149028 74474 149028 74474 149029 74486 149029 74487 149029 74474 149030 74487 149030 74473 149030 74473 149031 74487 149031 74469 149031 74473 149032 74469 149032 74470 149032 74470 149033 74469 149033 74488 149033 74470 149034 74488 149034 74489 149034 74450 149035 74505 149035 74471 149035 74471 149036 74505 149036 74454 149036 74471 149037 74454 149037 74472 149037 74472 149038 74454 149038 74490 149038 74472 149039 74490 149039 74475 149039 74475 149040 74490 149040 74491 149040 74475 149041 74491 149041 74476 149041 74476 149042 74491 149042 74492 149042 74476 149043 74492 149043 74478 149043 74478 149044 74492 149044 74493 149044 74478 149045 74493 149045 74494 149045 74494 149046 74493 149046 74495 149046 74494 149047 74495 149047 74480 149047 74480 149048 74495 149048 74388 149048 74480 149049 74388 149049 74496 149049 74507 149050 74450 149050 74519 149050 74500 149051 74398 149051 74511 149051 74396 149052 74398 149052 74497 149052 74497 149053 74398 149053 74500 149053 74497 149054 74500 149054 74498 149054 74498 149055 74500 149055 74499 149055 74513 149056 74501 149056 74500 149056 74500 149057 74501 149057 74395 149057 74395 149058 74502 149058 74500 149058 74500 149059 74502 149059 74503 149059 74500 149060 74503 149060 74499 149060 74446 149061 74504 149061 74507 149061 74507 149062 74504 149062 74455 149062 74505 149063 74450 149063 74451 149063 74451 149064 74450 149064 74507 149064 74451 149065 74507 149065 74506 149065 74506 149066 74507 149066 74455 149066 74449 149067 74508 149067 74507 149067 74507 149068 74508 149068 74448 149068 74507 149069 74448 149069 74446 149069 74449 149070 74507 149070 74509 149070 74509 149071 74507 149071 74519 149071 74509 149072 74519 149072 74510 149072 74510 149073 74519 149073 74518 149073 74510 149074 74518 149074 74511 149074 74511 149075 74518 149075 74512 149075 74511 149076 74512 149076 74500 149076 74500 149077 74512 149077 74431 149077 74500 149078 74431 149078 74513 149078 74525 149079 74445 149079 74391 149079 74489 149080 74488 149080 74522 149080 74514 149081 74515 149081 74526 149081 74429 149082 74516 149082 74524 149082 74516 149083 74431 149083 74524 149083 74524 149084 74431 149084 74512 149084 74524 149085 74512 149085 74517 149085 74517 149086 74512 149086 74518 149086 74517 149087 74518 149087 74521 149087 74521 149088 74518 149088 74519 149088 74521 149089 74519 149089 74520 149089 74520 149090 74519 149090 74450 149090 74520 149091 74489 149091 74521 149091 74521 149092 74489 149092 74522 149092 74521 149093 74522 149093 74517 149093 74517 149094 74522 149094 74523 149094 74517 149095 74523 149095 74524 149095 74524 149096 74523 149096 74526 149096 74524 149097 74526 149097 74429 149097 74429 149098 74526 149098 74515 149098 74488 149099 74525 149099 74522 149099 74522 149100 74525 149100 74391 149100 74522 149101 74391 149101 74523 149101 74523 149102 74391 149102 74527 149102 74523 149103 74527 149103 74526 149103 74526 149104 74527 149104 74528 149104 74526 149105 74528 149105 74514 149105 74514 149106 74528 149106 74392 149106 74546 149107 74740 149107 74571 149107 74546 149108 74571 149108 74529 149108 74571 149109 74570 149109 74529 149109 74529 149110 74570 149110 74531 149110 74529 149111 74531 149111 74548 149111 74548 149112 74531 149112 74530 149112 74530 149113 74531 149113 74536 149113 74530 149114 74536 149114 74535 149114 74532 149115 74742 149115 74564 149115 74564 149116 74742 149116 74534 149116 74564 149117 74534 149117 74533 149117 74533 149118 74534 149118 74750 149118 74533 149119 74750 149119 74567 149119 74567 149120 74750 149120 74752 149120 74535 149121 74536 149121 74747 149121 74747 149122 74536 149122 74560 149122 74747 149123 74560 149123 74748 149123 74560 149124 74561 149124 74748 149124 74748 149125 74561 149125 74537 149125 74748 149126 74537 149126 74756 149126 74756 149127 74537 149127 74538 149127 74756 149128 74538 149128 74539 149128 74539 149129 74538 149129 74543 149129 74539 149130 74543 149130 74754 149130 74567 149131 74752 149131 74540 149131 74540 149132 74752 149132 74541 149132 74540 149133 74541 149133 74542 149133 74542 149134 74541 149134 74754 149134 74542 149135 74754 149135 74551 149135 74551 149136 74754 149136 74543 149136 74571 149137 74740 149137 74544 149137 74544 149138 74740 149138 74545 149138 74544 149139 74545 149139 74362 149139 74362 149140 74545 149140 74745 149140 74548 149141 74530 149141 74549 149141 74733 149142 74546 149142 74759 149142 74759 149143 74546 149143 74529 149143 74759 149144 74529 149144 74547 149144 74547 149145 74529 149145 74548 149145 74547 149146 74548 149146 74727 149146 74727 149147 74548 149147 74549 149147 74560 149148 74536 149148 74558 149148 74566 149149 74567 149149 74590 149149 74590 149150 74567 149150 74540 149150 74590 149151 74540 149151 74588 149151 74588 149152 74540 149152 74550 149152 74540 149153 74542 149153 74550 149153 74550 149154 74542 149154 74551 149154 74550 149155 74551 149155 74552 149155 74552 149156 74551 149156 74543 149156 74552 149157 74543 149157 74593 149157 74593 149158 74543 149158 74553 149158 74553 149159 74543 149159 74538 149159 74553 149160 74538 149160 74557 149160 74562 149161 74554 149161 74537 149161 74537 149162 74554 149162 74555 149162 74537 149163 74555 149163 74538 149163 74538 149164 74555 149164 74556 149164 74538 149165 74556 149165 74557 149165 74558 149166 74559 149166 74560 149166 74560 149167 74559 149167 74562 149167 74560 149168 74562 149168 74561 149168 74561 149169 74562 149169 74537 149169 74563 149170 74622 149170 74571 149170 74571 149171 74544 149171 74563 149171 74563 149172 74544 149172 74362 149172 74563 149173 74362 149173 74649 149173 74621 149174 74532 149174 74689 149174 74689 149175 74532 149175 74564 149175 74689 149176 74564 149176 74565 149176 74565 149177 74564 149177 74533 149177 74565 149178 74533 149178 74566 149178 74566 149179 74533 149179 74567 149179 74558 149180 74536 149180 74531 149180 74558 149181 74531 149181 74568 149181 74568 149182 74531 149182 74570 149182 74568 149183 74570 149183 74569 149183 74569 149184 74570 149184 74571 149184 74569 149185 74571 149185 74622 149185 74572 149186 74721 149186 74679 149186 74710 149187 74572 149187 74585 149187 74580 149188 74579 149188 74706 149188 74706 149189 74579 149189 74573 149189 74706 149190 74573 149190 74574 149190 74574 149191 74573 149191 74575 149191 74574 149192 74575 149192 74708 149192 74708 149193 74575 149193 74692 149193 74581 149194 74578 149194 74696 149194 74618 149195 74576 149195 74577 149195 74577 149196 74576 149196 74619 149196 74577 149197 74619 149197 74581 149197 74581 149198 74619 149198 74620 149198 74581 149199 74620 149199 74578 149199 74612 149200 74579 149200 74611 149200 74611 149201 74579 149201 74580 149201 74611 149202 74580 149202 74610 149202 74612 149203 74618 149203 74579 149203 74579 149204 74618 149204 74577 149204 74579 149205 74577 149205 74573 149205 74573 149206 74577 149206 74581 149206 74573 149207 74581 149207 74575 149207 74575 149208 74581 149208 74696 149208 74575 149209 74696 149209 74692 149209 74582 149210 74616 149210 74612 149210 74612 149211 74616 149211 74583 149211 74612 149212 74583 149212 74618 149212 74584 149213 74710 149213 74586 149213 74586 149214 74710 149214 74585 149214 74586 149215 74585 149215 74587 149215 74587 149216 74585 149216 74613 149216 74615 149217 74591 149217 74592 149217 74588 149218 74589 149218 74590 149218 74590 149219 74589 149219 74614 149219 74590 149220 74614 149220 74566 149220 74607 149221 74559 149221 74608 149221 74608 149222 74559 149222 74558 149222 74608 149223 74558 149223 74703 149223 74556 149224 74555 149224 74594 149224 74594 149225 74555 149225 74554 149225 74594 149226 74554 149226 74607 149226 74607 149227 74554 149227 74562 149227 74607 149228 74562 149228 74559 149228 74588 149229 74550 149229 74591 149229 74591 149230 74550 149230 74552 149230 74591 149231 74552 149231 74592 149231 74592 149232 74552 149232 74593 149232 74592 149233 74593 149233 74604 149233 74604 149234 74593 149234 74553 149234 74604 149235 74553 149235 74594 149235 74594 149236 74553 149236 74557 149236 74594 149237 74557 149237 74556 149237 74615 149238 74603 149238 74595 149238 74595 149239 74603 149239 74605 149239 74595 149240 74605 149240 74596 149240 74596 149241 74605 149241 74597 149241 74596 149242 74597 149242 74617 149242 74617 149243 74597 149243 74606 149243 74617 149244 74606 149244 74598 149244 74598 149245 74606 149245 74600 149245 74598 149246 74600 149246 74599 149246 74599 149247 74600 149247 74601 149247 74599 149248 74601 149248 74602 149248 74615 149249 74592 149249 74603 149249 74603 149250 74592 149250 74604 149250 74603 149251 74604 149251 74605 149251 74605 149252 74604 149252 74594 149252 74605 149253 74594 149253 74597 149253 74597 149254 74594 149254 74607 149254 74597 149255 74607 149255 74606 149255 74606 149256 74607 149256 74608 149256 74606 149257 74608 149257 74600 149257 74600 149258 74608 149258 74703 149258 74600 149259 74703 149259 74601 149259 74572 149260 74679 149260 74585 149260 74585 149261 74679 149261 74609 149261 74585 149262 74609 149262 74613 149262 74613 149263 74609 149263 74681 149263 74613 149264 74681 149264 74686 149264 74610 149265 74584 149265 74611 149265 74611 149266 74584 149266 74586 149266 74611 149267 74586 149267 74612 149267 74612 149268 74586 149268 74587 149268 74612 149269 74587 149269 74582 149269 74582 149270 74587 149270 74613 149270 74582 149271 74613 149271 74589 149271 74589 149272 74613 149272 74686 149272 74589 149273 74686 149273 74614 149273 74588 149274 74591 149274 74589 149274 74589 149275 74591 149275 74615 149275 74589 149276 74615 149276 74582 149276 74582 149277 74615 149277 74595 149277 74582 149278 74595 149278 74616 149278 74616 149279 74595 149279 74596 149279 74616 149280 74596 149280 74583 149280 74583 149281 74596 149281 74617 149281 74583 149282 74617 149282 74618 149282 74618 149283 74617 149283 74598 149283 74618 149284 74598 149284 74576 149284 74576 149285 74598 149285 74599 149285 74576 149286 74599 149286 74619 149286 74619 149287 74599 149287 74602 149287 74619 149288 74602 149288 74620 149288 74653 149289 74621 149289 74654 149289 74647 149290 74622 149290 74563 149290 74672 149291 74670 149291 74632 149291 74668 149292 74687 149292 74678 149292 74714 149293 74623 149293 74630 149293 74715 149294 74641 149294 74624 149294 74624 149295 74641 149295 74640 149295 74624 149296 74640 149296 74625 149296 74625 149297 74640 149297 74638 149297 74625 149298 74638 149298 74626 149298 74626 149299 74638 149299 74637 149299 74630 149300 74623 149300 74627 149300 74627 149301 74623 149301 74628 149301 74627 149302 74628 149302 74632 149302 74655 149303 74678 149303 74677 149303 74632 149304 74670 149304 74627 149304 74627 149305 74670 149305 74629 149305 74627 149306 74629 149306 74630 149306 74628 149307 74631 149307 74632 149307 74632 149308 74631 149308 74633 149308 74632 149309 74633 149309 74672 149309 74672 149310 74633 149310 74639 149310 74672 149311 74639 149311 74635 149311 74635 149312 74639 149312 74634 149312 74635 149313 74634 149313 74675 149313 74675 149314 74634 149314 74636 149314 74675 149315 74636 149315 74700 149315 74631 149316 74637 149316 74633 149316 74633 149317 74637 149317 74638 149317 74633 149318 74638 149318 74639 149318 74639 149319 74638 149319 74640 149319 74639 149320 74640 149320 74634 149320 74634 149321 74640 149321 74641 149321 74634 149322 74641 149322 74636 149322 74642 149323 74643 149323 74366 149323 74366 149324 74643 149324 74645 149324 74366 149325 74645 149325 74644 149325 74644 149326 74645 149326 74646 149326 74646 149327 74645 149327 74664 149327 74646 149328 74664 149328 74363 149328 74690 149329 74647 149329 74648 149329 74648 149330 74647 149330 74563 149330 74648 149331 74563 149331 74664 149331 74664 149332 74563 149332 74649 149332 74664 149333 74649 149333 74363 149333 74369 149334 74651 149334 74650 149334 74650 149335 74651 149335 74666 149335 74650 149336 74666 149336 74367 149336 74367 149337 74666 149337 74643 149337 74367 149338 74643 149338 74364 149338 74364 149339 74643 149339 74642 149339 74369 149340 74652 149340 74651 149340 74651 149341 74652 149341 74653 149341 74651 149342 74653 149342 74667 149342 74667 149343 74653 149343 74654 149343 74667 149344 74654 149344 74669 149344 74678 149345 74655 149345 74668 149345 74668 149346 74655 149346 74656 149346 74668 149347 74656 149347 74657 149347 74657 149348 74656 149348 74658 149348 74657 149349 74658 149349 74659 149349 74659 149350 74658 149350 74671 149350 74659 149351 74671 149351 74660 149351 74660 149352 74671 149352 74673 149352 74660 149353 74673 149353 74665 149353 74665 149354 74673 149354 74674 149354 74665 149355 74674 149355 74661 149355 74661 149356 74674 149356 74662 149356 74661 149357 74662 149357 74663 149357 74663 149358 74662 149358 74676 149358 74663 149359 74676 149359 74690 149359 74690 149360 74648 149360 74663 149360 74663 149361 74648 149361 74664 149361 74663 149362 74664 149362 74661 149362 74661 149363 74664 149363 74645 149363 74661 149364 74645 149364 74665 149364 74665 149365 74645 149365 74643 149365 74665 149366 74643 149366 74660 149366 74660 149367 74643 149367 74666 149367 74660 149368 74666 149368 74659 149368 74659 149369 74666 149369 74651 149369 74659 149370 74651 149370 74657 149370 74657 149371 74651 149371 74667 149371 74657 149372 74667 149372 74668 149372 74668 149373 74667 149373 74669 149373 74668 149374 74669 149374 74687 149374 74677 149375 74714 149375 74655 149375 74655 149376 74714 149376 74630 149376 74655 149377 74630 149377 74656 149377 74656 149378 74630 149378 74629 149378 74656 149379 74629 149379 74658 149379 74658 149380 74629 149380 74670 149380 74658 149381 74670 149381 74671 149381 74671 149382 74670 149382 74672 149382 74671 149383 74672 149383 74673 149383 74673 149384 74672 149384 74635 149384 74673 149385 74635 149385 74674 149385 74674 149386 74635 149386 74675 149386 74674 149387 74675 149387 74662 149387 74662 149388 74675 149388 74700 149388 74662 149389 74700 149389 74676 149389 74682 149390 74683 149390 74688 149390 74712 149391 74677 149391 74678 149391 74679 149392 74721 149392 74680 149392 74681 149393 74609 149393 74682 149393 74682 149394 74609 149394 74679 149394 74679 149395 74680 149395 74682 149395 74682 149396 74680 149396 74720 149396 74682 149397 74720 149397 74683 149397 74683 149398 74720 149398 74684 149398 74683 149399 74684 149399 74712 149399 74614 149400 74686 149400 74685 149400 74685 149401 74686 149401 74681 149401 74566 149402 74614 149402 74565 149402 74565 149403 74614 149403 74685 149403 74565 149404 74685 149404 74689 149404 74712 149405 74678 149405 74683 149405 74683 149406 74678 149406 74687 149406 74683 149407 74687 149407 74688 149407 74688 149408 74687 149408 74669 149408 74688 149409 74669 149409 74654 149409 74681 149410 74682 149410 74685 149410 74685 149411 74682 149411 74688 149411 74685 149412 74688 149412 74689 149412 74689 149413 74688 149413 74654 149413 74689 149414 74654 149414 74621 149414 74647 149415 74690 149415 74701 149415 74697 149416 74693 149416 74699 149416 74715 149417 74691 149417 74641 149417 74641 149418 74691 149418 74698 149418 74708 149419 74692 149419 74704 149419 74704 149420 74692 149420 74693 149420 74694 149421 74695 149421 74702 149421 74702 149422 74695 149422 74698 149422 74693 149423 74692 149423 74699 149423 74699 149424 74692 149424 74696 149424 74699 149425 74696 149425 74578 149425 74691 149426 74697 149426 74698 149426 74698 149427 74697 149427 74699 149427 74698 149428 74699 149428 74702 149428 74702 149429 74699 149429 74578 149429 74690 149430 74676 149430 74695 149430 74695 149431 74676 149431 74700 149431 74695 149432 74700 149432 74698 149432 74698 149433 74700 149433 74636 149433 74698 149434 74636 149434 74641 149434 74568 149435 74569 149435 74701 149435 74701 149436 74569 149436 74622 149436 74701 149437 74622 149437 74647 149437 74578 149438 74620 149438 74702 149438 74702 149439 74620 149439 74602 149439 74702 149440 74602 149440 74694 149440 74694 149441 74602 149441 74601 149441 74694 149442 74601 149442 74703 149442 74690 149443 74695 149443 74701 149443 74701 149444 74695 149444 74694 149444 74701 149445 74694 149445 74568 149445 74568 149446 74694 149446 74703 149446 74568 149447 74703 149447 74558 149447 74707 149448 74708 149448 74704 149448 74707 149449 74610 149449 74705 149449 74705 149450 74706 149450 74707 149450 74707 149451 74706 149451 74574 149451 74707 149452 74574 149452 74708 149452 74709 149453 74710 149453 74707 149453 74707 149454 74710 149454 74711 149454 74707 149455 74711 149455 74610 149455 74713 149456 74677 149456 74712 149456 74719 149457 74623 149457 74713 149457 74713 149458 74623 149458 74714 149458 74713 149459 74714 149459 74677 149459 74715 149460 74716 149460 74713 149460 74713 149461 74716 149461 74625 149461 74713 149462 74625 149462 74717 149462 74717 149463 74718 149463 74713 149463 74713 149464 74718 149464 74631 149464 74713 149465 74631 149465 74719 149465 74715 149466 74713 149466 74691 149466 74691 149467 74713 149467 74712 149467 74691 149468 74712 149468 74697 149468 74697 149469 74712 149469 74684 149469 74697 149470 74684 149470 74693 149470 74693 149471 74684 149471 74720 149471 74693 149472 74720 149472 74704 149472 74704 149473 74720 149473 74680 149473 74704 149474 74680 149474 74707 149474 74707 149475 74680 149475 74721 149475 74707 149476 74721 149476 74709 149476 74753 149477 74776 149477 74722 149477 74722 149478 74776 149478 74779 149478 74722 149479 74779 149479 74755 149479 74779 149480 74775 149480 74755 149480 74755 149481 74775 149481 74774 149481 74755 149482 74774 149482 74746 149482 74746 149483 74774 149483 74723 149483 74746 149484 74723 149484 74725 149484 74723 149485 74724 149485 74725 149485 74725 149486 74724 149486 74726 149486 74725 149487 74726 149487 74530 149487 74530 149488 74726 149488 74549 149488 74772 149489 74727 149489 74728 149489 74728 149490 74727 149490 74549 149490 74728 149491 74549 149491 74729 149491 74729 149492 74549 149492 74726 149492 74730 149493 74735 149493 74731 149493 74759 149494 74758 149494 74733 149494 74733 149495 74758 149495 74732 149495 74733 149496 74732 149496 74546 149496 74546 149497 74732 149497 74734 149497 74546 149498 74734 149498 74731 149498 74731 149499 74734 149499 74769 149499 74731 149500 74769 149500 74730 149500 74730 149501 74766 149501 74735 149501 74735 149502 74766 149502 74767 149502 74735 149503 74767 149503 74736 149503 74765 149504 74764 149504 74737 149504 74737 149505 74764 149505 74749 149505 74737 149506 74749 149506 74738 149506 74738 149507 74749 149507 74736 149507 74738 149508 74736 149508 74739 149508 74739 149509 74736 149509 74767 149509 74740 149510 74546 149510 74731 149510 74374 149511 74735 149511 74741 149511 74741 149512 74735 149512 74736 149512 74741 149513 74736 149513 74742 149513 74740 149514 74731 149514 74545 149514 74374 149515 74743 149515 74735 149515 74735 149516 74743 149516 74744 149516 74735 149517 74744 149517 74731 149517 74731 149518 74744 149518 74745 149518 74731 149519 74745 149519 74545 149519 74756 149520 74755 149520 74746 149520 74530 149521 74535 149521 74725 149521 74725 149522 74535 149522 74747 149522 74725 149523 74747 149523 74746 149523 74746 149524 74747 149524 74748 149524 74746 149525 74748 149525 74756 149525 74736 149526 74749 149526 74742 149526 74742 149527 74749 149527 74764 149527 74742 149528 74764 149528 74534 149528 74534 149529 74764 149529 74763 149529 74534 149530 74763 149530 74750 149530 74750 149531 74763 149531 74751 149531 74750 149532 74751 149532 74752 149532 74752 149533 74751 149533 74753 149533 74752 149534 74753 149534 74541 149534 74541 149535 74753 149535 74722 149535 74541 149536 74722 149536 74754 149536 74754 149537 74722 149537 74755 149537 74754 149538 74755 149538 74539 149538 74539 149539 74755 149539 74756 149539 74727 149540 74772 149540 74757 149540 74727 149541 74757 149541 74547 149541 74547 149542 74757 149542 74758 149542 74547 149543 74758 149543 74759 149543 74420 149544 74758 149544 74760 149544 74760 149545 74758 149545 74757 149545 74760 149546 74757 149546 74380 149546 74772 149547 74382 149547 74757 149547 74757 149548 74382 149548 74761 149548 74757 149549 74761 149549 74380 149549 74376 149550 74751 149550 74762 149550 74762 149551 74751 149551 74763 149551 74762 149552 74763 149552 74765 149552 74765 149553 74763 149553 74764 149553 74732 149554 74758 149554 74420 149554 74392 149555 74765 149555 74401 149555 74401 149556 74765 149556 74737 149556 74401 149557 74737 149557 74432 149557 74432 149558 74737 149558 74433 149558 74737 149559 74738 149559 74433 149559 74433 149560 74738 149560 74739 149560 74433 149561 74739 149561 74434 149561 74730 149562 74436 149562 74766 149562 74766 149563 74436 149563 74434 149563 74766 149564 74434 149564 74767 149564 74767 149565 74434 149565 74739 149565 74420 149566 74427 149566 74732 149566 74732 149567 74427 149567 74428 149567 74732 149568 74428 149568 74734 149568 74734 149569 74428 149569 74768 149569 74734 149570 74768 149570 74769 149570 74769 149571 74768 149571 74770 149571 74769 149572 74770 149572 74730 149572 74730 149573 74770 149573 74771 149573 74730 149574 74771 149574 74436 149574 74465 149575 74382 149575 74772 149575 74772 149576 74728 149576 74465 149576 74465 149577 74728 149577 74729 149577 74465 149578 74729 149578 74773 149578 74773 149579 74729 149579 74726 149579 74773 149580 74726 149580 74464 149580 74464 149581 74726 149581 74724 149581 74464 149582 74724 149582 74461 149582 74461 149583 74724 149583 74723 149583 74461 149584 74723 149584 74462 149584 74462 149585 74723 149585 74468 149585 74468 149586 74723 149586 74774 149586 74468 149587 74774 149587 74467 149587 74774 149588 74775 149588 74467 149588 74467 149589 74775 149589 74779 149589 74467 149590 74779 149590 74780 149590 74776 149591 74777 149591 74779 149591 74779 149592 74777 149592 74778 149592 74779 149593 74778 149593 74780 149593 74781 149594 74782 149594 74872 149594 74872 149595 74782 149595 75182 149595 74872 149596 75182 149596 74783 149596 74783 149597 75182 149597 74784 149597 75180 149598 74792 149598 74881 149598 74881 149599 74880 149599 75180 149599 75180 149600 74880 149600 74785 149600 75180 149601 74785 149601 74787 149601 74787 149602 74785 149602 74786 149602 74787 149603 74786 149603 74788 149603 74788 149604 74786 149604 74874 149604 74788 149605 74874 149605 74784 149605 74784 149606 74874 149606 74789 149606 74784 149607 74789 149607 74783 149607 75175 149608 74793 149608 75177 149608 75177 149609 74793 149609 74855 149609 75177 149610 74855 149610 74790 149610 74855 149611 74882 149611 74790 149611 74790 149612 74882 149612 74791 149612 74790 149613 74791 149613 75179 149613 75179 149614 74791 149614 74877 149614 75179 149615 74877 149615 74792 149615 74792 149616 74877 149616 74876 149616 74792 149617 74876 149617 74881 149617 74793 149618 75175 149618 74918 149618 74918 149619 75175 149619 75165 149619 74918 149620 75165 149620 74794 149620 74794 149621 75165 149621 74795 149621 74794 149622 74795 149622 74825 149622 74825 149623 74795 149623 75194 149623 74796 149624 75164 149624 74797 149624 74796 149625 74797 149625 74929 149625 74929 149626 74797 149626 74799 149626 74929 149627 74799 149627 74798 149627 74798 149628 74799 149628 74782 149628 74798 149629 74782 149629 74781 149629 74800 149630 74911 149630 74910 149630 74814 149631 74800 149631 74844 149631 74804 149632 74801 149632 74937 149632 74937 149633 74801 149633 74807 149633 74937 149634 74807 149634 74938 149634 74938 149635 74807 149635 74802 149635 74938 149636 74802 149636 74939 149636 74939 149637 74802 149637 74925 149637 74806 149638 74803 149638 74808 149638 74812 149639 74853 149639 74805 149639 74805 149640 74853 149640 74854 149640 74805 149641 74854 149641 74806 149641 74806 149642 74854 149642 74931 149642 74806 149643 74931 149643 74803 149643 74810 149644 74801 149644 74846 149644 74846 149645 74801 149645 74804 149645 74846 149646 74804 149646 74942 149646 74810 149647 74812 149647 74801 149647 74801 149648 74812 149648 74805 149648 74801 149649 74805 149649 74807 149649 74807 149650 74805 149650 74806 149650 74807 149651 74806 149651 74802 149651 74802 149652 74806 149652 74808 149652 74802 149653 74808 149653 74925 149653 74809 149654 74852 149654 74810 149654 74810 149655 74852 149655 74811 149655 74810 149656 74811 149656 74812 149656 74813 149657 74814 149657 74847 149657 74847 149658 74814 149658 74844 149658 74847 149659 74844 149659 74815 149659 74815 149660 74844 149660 74848 149660 74820 149661 74816 149661 74821 149661 74821 149662 74816 149662 74817 149662 74821 149663 74817 149663 74829 149663 74850 149664 74849 149664 74821 149664 74822 149665 74818 149665 74819 149665 74820 149666 74821 149666 75192 149666 75192 149667 74821 149667 74849 149667 75192 149668 74849 149668 74819 149668 74818 149669 74822 149669 74824 149669 74824 149670 74822 149670 74823 149670 74824 149671 74823 149671 74825 149671 74796 149672 74843 149672 74842 149672 74826 149673 74827 149673 74840 149673 74840 149674 74827 149674 75199 149674 74840 149675 75199 149675 74842 149675 74842 149676 75199 149676 74828 149676 74842 149677 74828 149677 74796 149677 74817 149678 75188 149678 74829 149678 74829 149679 75188 149679 74830 149679 74829 149680 74830 149680 74826 149680 74826 149681 74830 149681 75197 149681 74826 149682 75197 149682 74827 149682 74850 149683 74839 149683 74851 149683 74851 149684 74839 149684 74831 149684 74851 149685 74831 149685 74833 149685 74833 149686 74831 149686 74832 149686 74833 149687 74832 149687 74834 149687 74834 149688 74832 149688 74841 149688 74834 149689 74841 149689 74836 149689 74836 149690 74841 149690 74835 149690 74836 149691 74835 149691 74837 149691 74837 149692 74835 149692 74838 149692 74837 149693 74838 149693 74932 149693 74850 149694 74821 149694 74839 149694 74839 149695 74821 149695 74829 149695 74839 149696 74829 149696 74831 149696 74831 149697 74829 149697 74826 149697 74831 149698 74826 149698 74832 149698 74832 149699 74826 149699 74840 149699 74832 149700 74840 149700 74841 149700 74841 149701 74840 149701 74842 149701 74841 149702 74842 149702 74835 149702 74835 149703 74842 149703 74843 149703 74835 149704 74843 149704 74838 149704 74800 149705 74910 149705 74844 149705 74844 149706 74910 149706 74912 149706 74844 149707 74912 149707 74848 149707 74848 149708 74912 149708 74917 149708 74848 149709 74917 149709 74845 149709 74942 149710 74813 149710 74846 149710 74846 149711 74813 149711 74847 149711 74846 149712 74847 149712 74810 149712 74810 149713 74847 149713 74815 149713 74810 149714 74815 149714 74809 149714 74809 149715 74815 149715 74848 149715 74809 149716 74848 149716 74822 149716 74822 149717 74848 149717 74845 149717 74822 149718 74845 149718 74823 149718 74819 149719 74849 149719 74822 149719 74822 149720 74849 149720 74850 149720 74822 149721 74850 149721 74809 149721 74809 149722 74850 149722 74851 149722 74809 149723 74851 149723 74852 149723 74852 149724 74851 149724 74833 149724 74852 149725 74833 149725 74811 149725 74811 149726 74833 149726 74834 149726 74811 149727 74834 149727 74812 149727 74812 149728 74834 149728 74836 149728 74812 149729 74836 149729 74853 149729 74853 149730 74836 149730 74837 149730 74853 149731 74837 149731 74854 149731 74854 149732 74837 149732 74932 149732 74854 149733 74932 149733 74931 149733 74855 149734 74793 149734 74856 149734 74867 149735 74904 149735 74857 149735 74883 149736 74858 149736 74919 149736 74944 149737 74863 149737 74901 149737 74950 149738 74922 149738 74859 149738 74859 149739 74922 149739 74860 149739 74859 149740 74860 149740 74861 149740 74861 149741 74860 149741 74870 149741 74861 149742 74870 149742 74862 149742 74862 149743 74870 149743 74947 149743 74901 149744 74863 149744 74865 149744 74865 149745 74863 149745 74864 149745 74865 149746 74864 149746 74857 149746 74900 149747 74919 149747 74899 149747 74857 149748 74904 149748 74865 149748 74865 149749 74904 149749 74903 149749 74865 149750 74903 149750 74901 149750 74864 149751 74948 149751 74857 149751 74857 149752 74948 149752 74866 149752 74857 149753 74866 149753 74867 149753 74867 149754 74866 149754 74868 149754 74867 149755 74868 149755 74905 149755 74905 149756 74868 149756 74869 149756 74905 149757 74869 149757 74907 149757 74907 149758 74869 149758 74871 149758 74907 149759 74871 149759 74908 149759 74948 149760 74947 149760 74866 149760 74866 149761 74947 149761 74870 149761 74866 149762 74870 149762 74868 149762 74868 149763 74870 149763 74860 149763 74868 149764 74860 149764 74869 149764 74869 149765 74860 149765 74922 149765 74869 149766 74922 149766 74871 149766 74872 149767 74783 149767 74893 149767 74893 149768 74783 149768 74789 149768 74893 149769 74789 149769 74873 149769 74873 149770 74789 149770 74874 149770 74873 149771 74874 149771 74875 149771 74875 149772 74874 149772 74786 149772 74875 149773 74786 149773 74878 149773 74892 149774 74930 149774 74893 149774 74893 149775 74930 149775 74781 149775 74893 149776 74781 149776 74872 149776 74879 149777 74876 149777 74896 149777 74896 149778 74876 149778 74877 149778 74896 149779 74877 149779 74791 149779 74786 149780 74785 149780 74878 149780 74878 149781 74785 149781 74880 149781 74878 149782 74880 149782 74879 149782 74879 149783 74880 149783 74881 149783 74879 149784 74881 149784 74876 149784 74791 149785 74882 149785 74896 149785 74896 149786 74882 149786 74855 149786 74896 149787 74855 149787 74898 149787 74898 149788 74855 149788 74856 149788 74898 149789 74856 149789 74920 149789 74919 149790 74900 149790 74883 149790 74883 149791 74900 149791 74902 149791 74883 149792 74902 149792 74897 149792 74897 149793 74902 149793 74884 149793 74897 149794 74884 149794 74885 149794 74885 149795 74884 149795 74886 149795 74885 149796 74886 149796 74895 149796 74895 149797 74886 149797 74887 149797 74895 149798 74887 149798 74894 149798 74894 149799 74887 149799 74906 149799 74894 149800 74906 149800 74888 149800 74888 149801 74906 149801 74890 149801 74888 149802 74890 149802 74889 149802 74889 149803 74890 149803 74891 149803 74889 149804 74891 149804 74892 149804 74892 149805 74893 149805 74889 149805 74889 149806 74893 149806 74873 149806 74889 149807 74873 149807 74888 149807 74888 149808 74873 149808 74875 149808 74888 149809 74875 149809 74894 149809 74894 149810 74875 149810 74878 149810 74894 149811 74878 149811 74895 149811 74895 149812 74878 149812 74879 149812 74895 149813 74879 149813 74885 149813 74885 149814 74879 149814 74896 149814 74885 149815 74896 149815 74897 149815 74897 149816 74896 149816 74898 149816 74897 149817 74898 149817 74883 149817 74883 149818 74898 149818 74920 149818 74883 149819 74920 149819 74858 149819 74899 149820 74944 149820 74900 149820 74900 149821 74944 149821 74901 149821 74900 149822 74901 149822 74902 149822 74902 149823 74901 149823 74903 149823 74902 149824 74903 149824 74884 149824 74884 149825 74903 149825 74904 149825 74884 149826 74904 149826 74886 149826 74886 149827 74904 149827 74867 149827 74886 149828 74867 149828 74887 149828 74887 149829 74867 149829 74905 149829 74887 149830 74905 149830 74906 149830 74906 149831 74905 149831 74907 149831 74906 149832 74907 149832 74890 149832 74890 149833 74907 149833 74908 149833 74890 149834 74908 149834 74891 149834 74913 149835 74909 149835 74921 149835 74943 149836 74899 149836 74919 149836 74910 149837 74911 149837 74953 149837 74917 149838 74912 149838 74913 149838 74913 149839 74912 149839 74910 149839 74910 149840 74953 149840 74913 149840 74913 149841 74953 149841 74914 149841 74913 149842 74914 149842 74909 149842 74909 149843 74914 149843 74915 149843 74909 149844 74915 149844 74943 149844 74823 149845 74845 149845 74916 149845 74916 149846 74845 149846 74917 149846 74825 149847 74823 149847 74794 149847 74794 149848 74823 149848 74916 149848 74794 149849 74916 149849 74918 149849 74943 149850 74919 149850 74909 149850 74909 149851 74919 149851 74858 149851 74909 149852 74858 149852 74921 149852 74921 149853 74858 149853 74920 149853 74921 149854 74920 149854 74856 149854 74917 149855 74913 149855 74916 149855 74916 149856 74913 149856 74921 149856 74916 149857 74921 149857 74918 149857 74918 149858 74921 149858 74856 149858 74918 149859 74856 149859 74793 149859 74930 149860 74892 149860 74934 149860 74951 149861 74952 149861 74927 149861 74950 149862 74923 149862 74922 149862 74922 149863 74923 149863 74926 149863 74939 149864 74925 149864 74935 149864 74935 149865 74925 149865 74952 149865 74924 149866 74933 149866 74928 149866 74928 149867 74933 149867 74926 149867 74952 149868 74925 149868 74927 149868 74927 149869 74925 149869 74808 149869 74927 149870 74808 149870 74803 149870 74923 149871 74951 149871 74926 149871 74926 149872 74951 149872 74927 149872 74926 149873 74927 149873 74928 149873 74928 149874 74927 149874 74803 149874 74892 149875 74891 149875 74933 149875 74933 149876 74891 149876 74908 149876 74933 149877 74908 149877 74926 149877 74926 149878 74908 149878 74871 149878 74926 149879 74871 149879 74922 149879 74929 149880 74798 149880 74934 149880 74934 149881 74798 149881 74781 149881 74934 149882 74781 149882 74930 149882 74803 149883 74931 149883 74928 149883 74928 149884 74931 149884 74932 149884 74928 149885 74932 149885 74924 149885 74924 149886 74932 149886 74838 149886 74924 149887 74838 149887 74843 149887 74892 149888 74933 149888 74934 149888 74934 149889 74933 149889 74924 149889 74934 149890 74924 149890 74929 149890 74929 149891 74924 149891 74843 149891 74929 149892 74843 149892 74796 149892 74936 149893 74939 149893 74935 149893 74936 149894 74942 149894 74804 149894 74804 149895 74937 149895 74936 149895 74936 149896 74937 149896 74938 149896 74936 149897 74938 149897 74939 149897 74940 149898 74814 149898 74936 149898 74936 149899 74814 149899 74941 149899 74936 149900 74941 149900 74942 149900 74946 149901 74899 149901 74943 149901 74949 149902 74863 149902 74946 149902 74946 149903 74863 149903 74944 149903 74946 149904 74944 149904 74899 149904 74950 149905 74945 149905 74946 149905 74946 149906 74945 149906 74861 149906 74946 149907 74861 149907 74862 149907 74862 149908 74947 149908 74946 149908 74946 149909 74947 149909 74948 149909 74946 149910 74948 149910 74949 149910 74950 149911 74946 149911 74923 149911 74923 149912 74946 149912 74943 149912 74923 149913 74943 149913 74951 149913 74951 149914 74943 149914 74915 149914 74951 149915 74915 149915 74952 149915 74952 149916 74915 149916 74914 149916 74952 149917 74914 149917 74935 149917 74935 149918 74914 149918 74953 149918 74935 149919 74953 149919 74936 149919 74936 149920 74953 149920 74911 149920 74936 149921 74911 149921 74940 149921 74828 149922 75199 149922 75198 149922 75198 149923 74954 149923 74828 149923 74828 149924 74954 149924 75164 149924 74828 149925 75164 149925 74796 149925 75198 149926 75169 149926 74954 149926 74954 149927 75169 149927 74955 149927 74954 149928 74955 149928 75164 149928 75164 149929 74955 149929 74982 149929 74963 149930 75061 149930 74956 149930 74956 149931 75061 149931 75060 149931 74956 149932 75060 149932 74957 149932 74957 149933 75060 149933 74958 149933 74957 149934 74958 149934 74959 149934 74959 149935 74958 149935 74961 149935 74959 149936 74961 149936 74960 149936 74960 149937 74961 149937 75049 149937 74960 149938 75049 149938 74962 149938 74962 149939 75049 149939 75048 149939 74963 149940 74956 149940 75059 149940 75059 149941 74956 149941 74969 149941 75059 149942 74969 149942 74964 149942 74964 149943 74969 149943 74965 149943 74964 149944 74965 149944 75057 149944 75057 149945 74965 149945 74966 149945 75057 149946 74966 149946 75056 149946 75056 149947 74966 149947 74989 149947 75056 149948 74989 149948 75054 149948 75184 149949 74989 149949 74967 149949 74967 149950 74989 149950 74966 149950 74967 149951 74966 149951 74976 149951 74976 149952 74966 149952 74965 149952 74976 149953 74965 149953 74968 149953 74968 149954 74965 149954 74969 149954 74968 149955 74969 149955 74979 149955 74979 149956 74969 149956 74956 149956 74979 149957 74956 149957 74977 149957 74962 149958 74988 149958 74960 149958 74960 149959 74988 149959 74970 149959 74960 149960 74970 149960 74959 149960 74959 149961 74970 149961 74977 149961 74959 149962 74977 149962 74957 149962 74957 149963 74977 149963 74956 149963 74985 149964 74991 149964 75028 149964 74997 149965 74971 149965 74984 149965 75028 149966 75005 149966 74985 149966 74985 149967 75005 149967 75006 149967 74985 149968 75006 149968 74984 149968 74984 149969 75006 149969 74972 149969 74984 149970 74972 149970 74997 149970 74995 149971 74973 149971 74996 149971 74996 149972 74973 149972 75187 149972 74996 149973 75187 149973 75003 149973 75003 149974 75187 149974 74974 149974 75003 149975 74974 149975 75002 149975 75002 149976 74974 149976 74981 149976 75002 149977 74981 149977 75000 149977 75000 149978 74981 149978 74971 149978 75000 149979 74971 149979 74999 149979 74999 149980 74971 149980 74997 149980 74992 149981 74987 149981 74962 149981 74962 149982 74987 149982 74988 149982 74977 149983 74970 149983 75176 149983 75176 149984 74970 149984 74975 149984 75181 149985 74976 149985 74968 149985 75168 149986 74971 149986 74981 149986 74981 149987 74974 149987 74982 149987 75176 149988 75178 149988 74977 149988 74977 149989 75178 149989 74978 149989 74977 149990 74978 149990 74979 149990 74979 149991 74978 149991 74980 149991 74979 149992 74980 149992 74968 149992 74968 149993 74980 149993 75183 149993 74968 149994 75183 149994 75181 149994 75168 149995 74981 149995 75169 149995 75169 149996 74981 149996 74982 149996 75169 149997 74982 149997 74955 149997 75168 149998 75171 149998 74971 149998 74971 149999 75171 149999 75174 149999 74971 150000 75174 150000 74984 150000 74984 150001 75174 150001 74983 150001 74984 150002 74983 150002 74985 150002 74985 150003 74983 150003 75172 150003 74985 150004 75172 150004 74991 150004 74991 150005 75172 150005 75167 150005 74991 150006 75167 150006 74986 150006 74986 150007 75167 150007 75166 150007 74986 150008 75166 150008 74987 150008 74987 150009 75166 150009 74975 150009 74987 150010 74975 150010 74988 150010 74988 150011 74975 150011 74970 150011 74973 150012 74995 150012 74990 150012 74973 150013 74990 150013 75185 150013 75185 150014 74990 150014 74989 150014 75185 150015 74989 150015 75184 150015 75054 150016 74989 150016 75010 150016 75010 150017 74989 150017 74990 150017 75010 150018 74990 150018 75011 150018 74995 150019 75017 150019 74990 150019 74990 150020 75017 150020 75014 150020 74990 150021 75014 150021 75011 150021 75028 150022 74991 150022 75031 150022 75031 150023 74991 150023 74986 150023 75031 150024 74986 150024 74992 150024 74992 150025 74986 150025 74987 150025 74993 150026 74992 150026 75073 150026 75073 150027 74992 150027 74962 150027 75073 150028 74962 150028 75048 150028 75017 150029 74995 150029 74994 150029 74994 150030 74995 150030 74996 150030 74994 150031 74996 150031 75099 150031 75099 150032 74996 150032 75003 150032 74997 150033 74998 150033 74999 150033 74999 150034 74998 150034 75001 150034 74999 150035 75001 150035 75000 150035 75000 150036 75001 150036 75101 150036 75000 150037 75101 150037 75002 150037 75002 150038 75101 150038 75100 150038 75002 150039 75100 150039 75003 150039 75003 150040 75100 150040 75004 150040 75003 150041 75004 150041 75099 150041 75028 150042 75081 150042 75005 150042 75005 150043 75081 150043 75109 150043 75005 150044 75109 150044 75006 150044 75109 150045 75107 150045 75006 150045 75006 150046 75107 150046 75106 150046 75006 150047 75106 150047 74972 150047 74972 150048 75106 150048 75007 150048 74972 150049 75007 150049 74997 150049 74997 150050 75007 150050 75105 150050 74997 150051 75105 150051 74998 150051 75024 150052 75085 150052 75027 150052 75085 150053 75024 150053 75095 150053 75012 150054 75013 150054 75019 150054 75009 150055 75054 150055 75010 150055 75008 150056 75066 150056 75012 150056 75012 150057 75066 150057 75009 150057 75009 150058 75010 150058 75012 150058 75012 150059 75010 150059 75011 150059 75012 150060 75011 150060 75013 150060 75013 150061 75011 150061 75014 150061 75013 150062 75014 150062 75017 150062 75034 150063 75016 150063 75015 150063 75015 150064 75016 150064 75008 150064 75017 150065 75103 150065 75013 150065 75013 150066 75103 150066 75018 150066 75013 150067 75018 150067 75019 150067 75019 150068 75018 150068 75020 150068 75019 150069 75020 150069 75021 150069 75022 150070 75034 150070 75023 150070 75023 150071 75034 150071 75015 150071 75023 150072 75015 150072 75024 150072 75008 150073 75012 150073 75015 150073 75015 150074 75012 150074 75019 150074 75015 150075 75019 150075 75024 150075 75024 150076 75019 150076 75021 150076 75024 150077 75021 150077 75095 150077 75039 150078 75022 150078 75025 150078 75025 150079 75022 150079 75023 150079 75025 150080 75023 150080 75147 150080 75147 150081 75023 150081 75024 150081 75147 150082 75024 150082 75026 150082 75026 150083 75024 150083 75027 150083 75161 150084 75081 150084 75028 150084 75161 150085 75028 150085 75029 150085 75029 150086 75028 150086 75031 150086 75029 150087 75031 150087 75030 150087 75030 150088 75031 150088 74992 150088 75030 150089 74992 150089 74993 150089 75037 150090 75032 150090 75044 150090 75138 150091 75137 150091 75051 150091 75138 150092 75051 150092 75139 150092 75038 150093 75134 150093 75032 150093 75032 150094 75134 150094 75135 150094 75032 150095 75135 150095 75044 150095 75044 150096 75135 150096 75141 150096 75044 150097 75141 150097 75050 150097 75022 150098 75033 150098 75034 150098 75034 150099 75033 150099 75035 150099 75034 150100 75035 150100 75016 150100 75016 150101 75035 150101 75036 150101 75042 150102 75036 150102 75037 150102 75037 150103 75036 150103 75035 150103 75037 150104 75035 150104 75032 150104 75032 150105 75035 150105 75033 150105 75032 150106 75033 150106 75038 150106 75038 150107 75033 150107 75022 150107 75038 150108 75022 150108 75039 150108 75040 150109 75051 150109 75041 150109 75041 150110 75051 150110 75137 150110 75041 150111 75137 150111 75136 150111 75042 150112 75037 150112 75043 150112 75043 150113 75037 150113 75044 150113 75043 150114 75044 150114 75045 150114 75045 150115 75044 150115 75050 150115 75045 150116 75050 150116 75078 150116 75078 150117 75050 150117 75052 150117 75078 150118 75052 150118 75053 150118 75046 150119 74961 150119 74958 150119 75046 150120 74958 150120 75070 150120 75049 150121 74961 150121 75077 150121 75077 150122 74961 150122 75046 150122 75077 150123 75046 150123 75047 150123 75073 150124 75048 150124 75074 150124 75074 150125 75048 150125 75049 150125 75141 150126 75140 150126 75050 150126 75050 150127 75140 150127 75139 150127 75050 150128 75139 150128 75052 150128 75052 150129 75139 150129 75051 150129 75052 150130 75051 150130 75053 150130 75053 150131 75051 150131 75040 150131 75053 150132 75040 150132 75074 150132 75054 150133 75009 150133 75055 150133 75054 150134 75055 150134 75056 150134 75056 150135 75055 150135 75058 150135 75056 150136 75058 150136 75057 150136 75057 150137 75058 150137 74964 150137 74964 150138 75058 150138 75071 150138 74964 150139 75071 150139 75059 150139 74958 150140 75060 150140 75070 150140 75070 150141 75060 150141 75061 150141 75070 150142 75061 150142 75071 150142 75071 150143 75061 150143 74963 150143 75071 150144 74963 150144 75059 150144 75047 150145 75068 150145 75062 150145 75062 150146 75068 150146 75069 150146 75062 150147 75069 150147 75079 150147 75079 150148 75069 150148 75063 150148 75079 150149 75063 150149 75080 150149 75080 150150 75063 150150 75072 150150 75080 150151 75072 150151 75064 150151 75064 150152 75072 150152 75065 150152 75064 150153 75065 150153 75067 150153 75067 150154 75065 150154 75066 150154 75067 150155 75066 150155 75008 150155 75047 150156 75046 150156 75068 150156 75068 150157 75046 150157 75070 150157 75068 150158 75070 150158 75069 150158 75069 150159 75070 150159 75071 150159 75069 150160 75071 150160 75063 150160 75063 150161 75071 150161 75058 150161 75063 150162 75058 150162 75072 150162 75072 150163 75058 150163 75055 150163 75072 150164 75055 150164 75065 150164 75065 150165 75055 150165 75009 150165 75065 150166 75009 150166 75066 150166 74993 150167 75073 150167 75162 150167 75162 150168 75073 150168 75074 150168 75162 150169 75074 150169 75075 150169 75075 150170 75074 150170 75040 150170 75075 150171 75040 150171 75076 150171 75076 150172 75040 150172 75041 150172 75076 150173 75041 150173 75150 150173 75150 150174 75041 150174 75136 150174 75150 150175 75136 150175 75149 150175 75049 150176 75077 150176 75074 150176 75074 150177 75077 150177 75047 150177 75074 150178 75047 150178 75053 150178 75053 150179 75047 150179 75062 150179 75053 150180 75062 150180 75078 150180 75078 150181 75062 150181 75079 150181 75078 150182 75079 150182 75045 150182 75045 150183 75079 150183 75080 150183 75045 150184 75080 150184 75043 150184 75043 150185 75080 150185 75064 150185 75043 150186 75064 150186 75042 150186 75042 150187 75064 150187 75067 150187 75042 150188 75067 150188 75036 150188 75036 150189 75067 150189 75008 150189 75036 150190 75008 150190 75016 150190 75109 150191 75081 150191 75110 150191 75130 150192 75127 150192 75090 150192 75112 150193 75082 150193 75153 150193 75142 150194 75083 150194 75096 150194 75096 150195 75083 150195 75084 150195 75096 150196 75084 150196 75098 150196 75098 150197 75084 150197 75027 150197 75098 150198 75027 150198 75085 150198 75111 150199 75153 150199 75126 150199 75143 150200 75144 150200 75086 150200 75086 150201 75144 150201 75087 150201 75086 150202 75087 150202 75088 150202 75088 150203 75087 150203 75145 150203 75088 150204 75145 150204 75090 150204 75090 150205 75127 150205 75088 150205 75088 150206 75127 150206 75089 150206 75088 150207 75089 150207 75086 150207 75145 150208 75091 150208 75090 150208 75090 150209 75091 150209 75092 150209 75090 150210 75092 150210 75130 150210 75130 150211 75092 150211 75097 150211 75130 150212 75097 150212 75093 150212 75093 150213 75097 150213 75094 150213 75093 150214 75094 150214 75132 150214 75132 150215 75094 150215 75095 150215 75132 150216 75095 150216 75021 150216 75091 150217 75142 150217 75092 150217 75092 150218 75142 150218 75096 150218 75092 150219 75096 150219 75097 150219 75097 150220 75096 150220 75098 150220 75097 150221 75098 150221 75094 150221 75094 150222 75098 150222 75085 150222 75094 150223 75085 150223 75095 150223 74994 150224 75099 150224 75102 150224 75102 150225 75099 150225 75004 150225 75102 150226 75004 150226 75119 150226 75119 150227 75004 150227 75100 150227 75119 150228 75100 150228 75120 150228 75120 150229 75100 150229 75101 150229 75120 150230 75101 150230 75104 150230 75018 150231 75103 150231 75102 150231 75102 150232 75103 150232 75017 150232 75102 150233 75017 150233 74994 150233 75101 150234 75001 150234 75104 150234 75104 150235 75001 150235 74998 150235 75104 150236 74998 150236 75122 150236 75122 150237 74998 150237 75105 150237 75122 150238 75105 150238 75125 150238 75125 150239 75105 150239 75007 150239 75125 150240 75007 150240 75106 150240 75106 150241 75107 150241 75125 150241 75125 150242 75107 150242 75109 150242 75125 150243 75109 150243 75108 150243 75108 150244 75109 150244 75110 150244 75108 150245 75110 150245 75160 150245 75153 150246 75111 150246 75112 150246 75112 150247 75111 150247 75113 150247 75112 150248 75113 150248 75114 150248 75114 150249 75113 150249 75115 150249 75114 150250 75115 150250 75124 150250 75124 150251 75115 150251 75128 150251 75124 150252 75128 150252 75123 150252 75123 150253 75128 150253 75129 150253 75123 150254 75129 150254 75121 150254 75121 150255 75129 150255 75131 150255 75121 150256 75131 150256 75118 150256 75118 150257 75131 150257 75116 150257 75118 150258 75116 150258 75117 150258 75117 150259 75116 150259 75020 150259 75117 150260 75020 150260 75018 150260 75018 150261 75102 150261 75117 150261 75117 150262 75102 150262 75119 150262 75117 150263 75119 150263 75118 150263 75118 150264 75119 150264 75120 150264 75118 150265 75120 150265 75121 150265 75121 150266 75120 150266 75104 150266 75121 150267 75104 150267 75123 150267 75123 150268 75104 150268 75122 150268 75123 150269 75122 150269 75124 150269 75124 150270 75122 150270 75125 150270 75124 150271 75125 150271 75114 150271 75114 150272 75125 150272 75108 150272 75114 150273 75108 150273 75112 150273 75112 150274 75108 150274 75160 150274 75112 150275 75160 150275 75082 150275 75126 150276 75143 150276 75111 150276 75111 150277 75143 150277 75086 150277 75111 150278 75086 150278 75113 150278 75113 150279 75086 150279 75089 150279 75113 150280 75089 150280 75115 150280 75115 150281 75089 150281 75127 150281 75115 150282 75127 150282 75128 150282 75128 150283 75127 150283 75130 150283 75128 150284 75130 150284 75129 150284 75129 150285 75130 150285 75093 150285 75129 150286 75093 150286 75131 150286 75131 150287 75093 150287 75132 150287 75131 150288 75132 150288 75116 150288 75116 150289 75132 150289 75021 150289 75116 150290 75021 150290 75020 150290 75146 150291 75126 150291 75154 150291 75133 150292 75039 150292 75025 150292 75038 150293 75039 150293 75134 150293 75134 150294 75039 150294 75133 150294 75134 150295 75133 150295 75135 150295 75135 150296 75133 150296 75141 150296 75136 150297 75137 150297 75133 150297 75133 150298 75137 150298 75138 150298 75138 150299 75139 150299 75133 150299 75133 150300 75139 150300 75140 150300 75133 150301 75140 150301 75141 150301 75142 150302 75091 150302 75146 150302 75146 150303 75091 150303 75145 150303 75143 150304 75126 150304 75144 150304 75144 150305 75126 150305 75146 150305 75144 150306 75146 150306 75087 150306 75087 150307 75146 150307 75145 150307 75027 150308 75084 150308 75146 150308 75146 150309 75084 150309 75083 150309 75146 150310 75083 150310 75142 150310 75027 150311 75146 150311 75026 150311 75026 150312 75146 150312 75154 150312 75026 150313 75154 150313 75147 150313 75147 150314 75154 150314 75151 150314 75147 150315 75151 150315 75025 150315 75025 150316 75151 150316 75148 150316 75025 150317 75148 150317 75133 150317 75133 150318 75148 150318 75149 150318 75133 150319 75149 150319 75136 150319 75110 150320 75081 150320 75161 150320 75082 150321 75160 150321 75156 150321 75162 150322 75075 150322 75159 150322 75076 150323 75150 150323 75157 150323 75150 150324 75149 150324 75157 150324 75157 150325 75149 150325 75148 150325 75157 150326 75148 150326 75155 150326 75155 150327 75148 150327 75151 150327 75155 150328 75151 150328 75152 150328 75152 150329 75151 150329 75154 150329 75152 150330 75154 150330 75153 150330 75153 150331 75154 150331 75126 150331 75153 150332 75082 150332 75152 150332 75152 150333 75082 150333 75156 150333 75152 150334 75156 150334 75155 150334 75155 150335 75156 150335 75158 150335 75155 150336 75158 150336 75157 150336 75157 150337 75158 150337 75159 150337 75157 150338 75159 150338 75076 150338 75076 150339 75159 150339 75075 150339 75160 150340 75110 150340 75156 150340 75156 150341 75110 150341 75161 150341 75156 150342 75161 150342 75158 150342 75158 150343 75161 150343 75029 150343 75158 150344 75029 150344 75159 150344 75159 150345 75029 150345 75030 150345 75159 150346 75030 150346 75162 150346 75162 150347 75030 150347 74993 150347 74976 150348 75181 150348 74782 150348 74976 150349 74782 150349 75163 150349 74782 150350 74799 150350 75163 150350 75163 150351 74799 150351 74797 150351 75163 150352 74797 150352 75186 150352 75186 150353 74797 150353 74974 150353 74974 150354 74797 150354 75164 150354 74974 150355 75164 150355 74982 150355 75175 150356 74975 150356 75165 150356 75165 150357 74975 150357 75166 150357 75165 150358 75166 150358 74795 150358 74795 150359 75166 150359 75167 150359 74795 150360 75167 150360 75194 150360 75194 150361 75167 150361 75172 150361 75168 150362 75169 150362 75198 150362 75198 150363 75170 150363 75168 150363 75168 150364 75170 150364 75196 150364 75168 150365 75196 150365 75171 150365 75171 150366 75196 150366 75195 150366 75195 150367 75189 150367 75171 150367 75171 150368 75189 150368 75190 150368 75171 150369 75190 150369 75174 150369 75194 150370 75172 150370 75193 150370 75193 150371 75172 150371 74983 150371 75193 150372 74983 150372 75173 150372 75173 150373 74983 150373 75174 150373 75173 150374 75174 150374 75191 150374 75191 150375 75174 150375 75190 150375 75176 150376 74975 150376 75175 150376 74792 150377 74978 150377 75178 150377 75175 150378 75177 150378 75176 150378 75176 150379 75177 150379 74790 150379 75176 150380 74790 150380 75178 150380 75178 150381 74790 150381 75179 150381 75178 150382 75179 150382 74792 150382 74792 150383 75180 150383 74978 150383 74978 150384 75180 150384 74787 150384 74978 150385 74787 150385 74980 150385 74782 150386 75181 150386 75182 150386 75182 150387 75181 150387 75183 150387 75182 150388 75183 150388 74784 150388 74784 150389 75183 150389 74980 150389 74784 150390 74980 150390 74788 150390 74788 150391 74980 150391 74787 150391 75186 150392 74974 150392 75187 150392 74967 150393 74976 150393 75184 150393 75184 150394 74976 150394 75163 150394 75184 150395 75163 150395 75185 150395 75185 150396 75163 150396 75186 150396 75185 150397 75186 150397 74973 150397 74973 150398 75186 150398 75187 150398 75188 150399 74817 150399 75195 150399 75195 150400 74817 150400 75189 150400 75189 150401 74817 150401 74816 150401 75189 150402 74816 150402 75190 150402 75190 150403 74816 150403 74820 150403 75190 150404 74820 150404 75191 150404 75191 150405 74820 150405 75192 150405 75191 150406 75192 150406 75173 150406 75173 150407 75192 150407 74819 150407 75173 150408 74819 150408 75193 150408 75193 150409 74819 150409 74818 150409 75193 150410 74818 150410 75194 150410 75194 150411 74818 150411 74824 150411 75194 150412 74824 150412 74825 150412 75188 150413 75195 150413 74830 150413 74830 150414 75195 150414 75196 150414 74830 150415 75196 150415 75197 150415 75197 150416 75196 150416 75170 150416 75197 150417 75170 150417 74827 150417 74827 150418 75170 150418 75198 150418 74827 150419 75198 150419 75199 150419 75208 150420 75205 150420 75220 150420 75203 150421 75200 150421 75211 150421 75517 150422 75200 150422 75201 150422 75201 150423 75200 150423 75203 150423 75201 150424 75203 150424 75515 150424 75515 150425 75203 150425 75548 150425 75519 150426 75513 150426 75203 150426 75203 150427 75513 150427 75202 150427 75202 150428 75549 150428 75203 150428 75203 150429 75549 150429 75204 150429 75203 150430 75204 150430 75548 150430 75563 150431 75571 150431 75208 150431 75208 150432 75571 150432 75569 150432 75605 150433 75205 150433 75206 150433 75206 150434 75205 150434 75208 150434 75206 150435 75208 150435 75207 150435 75207 150436 75208 150436 75569 150436 75495 150437 75209 150437 75208 150437 75208 150438 75209 150438 75210 150438 75208 150439 75210 150439 75563 150439 75495 150440 75208 150440 75509 150440 75509 150441 75208 150441 75220 150441 75509 150442 75220 150442 75508 150442 75508 150443 75220 150443 75218 150443 75508 150444 75218 150444 75211 150444 75211 150445 75218 150445 75217 150445 75211 150446 75217 150446 75203 150446 75203 150447 75217 150447 75216 150447 75203 150448 75216 150448 75519 150448 75212 150449 75213 150449 75229 150449 75214 150450 75604 150450 75228 150450 75215 150451 75227 150451 75224 150451 75226 150452 75547 150452 75225 150452 75547 150453 75216 150453 75225 150453 75225 150454 75216 150454 75217 150454 75225 150455 75217 150455 75222 150455 75222 150456 75217 150456 75218 150456 75222 150457 75218 150457 75221 150457 75221 150458 75218 150458 75220 150458 75221 150459 75220 150459 75219 150459 75219 150460 75220 150460 75205 150460 75219 150461 75214 150461 75221 150461 75221 150462 75214 150462 75228 150462 75221 150463 75228 150463 75222 150463 75222 150464 75228 150464 75223 150464 75222 150465 75223 150465 75225 150465 75225 150466 75223 150466 75224 150466 75225 150467 75224 150467 75226 150467 75226 150468 75224 150468 75227 150468 75604 150469 75212 150469 75228 150469 75228 150470 75212 150470 75229 150470 75228 150471 75229 150471 75223 150471 75223 150472 75229 150472 75230 150472 75223 150473 75230 150473 75224 150473 75224 150474 75230 150474 75510 150474 75224 150475 75510 150475 75215 150475 75215 150476 75510 150476 75483 150476 75231 150477 75464 150477 75232 150477 75231 150478 75232 150478 75250 150478 75232 150479 75279 150479 75250 150479 75250 150480 75279 150480 75278 150480 75250 150481 75278 150481 75247 150481 75247 150482 75278 150482 75458 150482 75458 150483 75278 150483 75434 150483 75458 150484 75434 150484 75473 150484 75275 150485 75472 150485 75233 150485 75233 150486 75472 150486 75471 150486 75233 150487 75471 150487 75234 150487 75234 150488 75471 150488 75468 150488 75234 150489 75468 150489 75235 150489 75235 150490 75468 150490 75238 150490 75236 150491 75433 150491 75429 150491 75429 150492 75258 150492 75236 150492 75236 150493 75258 150493 75256 150493 75236 150494 75256 150494 75241 150494 75241 150495 75256 150495 75255 150495 75235 150496 75238 150496 75237 150496 75237 150497 75238 150497 75239 150497 75237 150498 75239 150498 75240 150498 75240 150499 75239 150499 75241 150499 75240 150500 75241 150500 75252 150500 75252 150501 75241 150501 75255 150501 75472 150502 75275 150502 75461 150502 75461 150503 75275 150503 75242 150503 75461 150504 75242 150504 75462 150504 75242 150505 75270 150505 75462 150505 75462 150506 75270 150506 75271 150506 75462 150507 75271 150507 75243 150507 75243 150508 75271 150508 75274 150508 75243 150509 75274 150509 75463 150509 75463 150510 75274 150510 75264 150510 75463 150511 75264 150511 75244 150511 75232 150512 75464 150512 75245 150512 75245 150513 75464 150513 75246 150513 75245 150514 75246 150514 75260 150514 75260 150515 75246 150515 75244 150515 75260 150516 75244 150516 75261 150516 75261 150517 75244 150517 75264 150517 75247 150518 75458 150518 75251 150518 75248 150519 75231 150519 75249 150519 75249 150520 75231 150520 75250 150520 75249 150521 75250 150521 75478 150521 75478 150522 75250 150522 75247 150522 75478 150523 75247 150523 75476 150523 75476 150524 75247 150524 75251 150524 75277 150525 75235 150525 75326 150525 75326 150526 75235 150526 75237 150526 75326 150527 75237 150527 75240 150527 75254 150528 75253 150528 75252 150528 75252 150529 75253 150529 75296 150529 75252 150530 75296 150530 75240 150530 75240 150531 75296 150531 75295 150531 75240 150532 75295 150532 75326 150532 75252 150533 75255 150533 75254 150533 75254 150534 75255 150534 75256 150534 75254 150535 75256 150535 75301 150535 75301 150536 75256 150536 75258 150536 75301 150537 75258 150537 75257 150537 75257 150538 75258 150538 75429 150538 75257 150539 75429 150539 75303 150539 75407 150540 75232 150540 75362 150540 75362 150541 75232 150541 75245 150541 75362 150542 75245 150542 75259 150542 75259 150543 75245 150543 75260 150543 75259 150544 75260 150544 75356 150544 75356 150545 75260 150545 75261 150545 75356 150546 75261 150546 75262 150546 75262 150547 75261 150547 75264 150547 75262 150548 75264 150548 75263 150548 75263 150549 75264 150549 75265 150549 75265 150550 75264 150550 75266 150550 75266 150551 75264 150551 75274 150551 75266 150552 75274 150552 75267 150552 75275 150553 75336 150553 75242 150553 75242 150554 75336 150554 75364 150554 75242 150555 75364 150555 75270 150555 75364 150556 75268 150556 75270 150556 75270 150557 75268 150557 75269 150557 75270 150558 75269 150558 75271 150558 75271 150559 75269 150559 75272 150559 75271 150560 75272 150560 75274 150560 75274 150561 75272 150561 75273 150561 75274 150562 75273 150562 75267 150562 75336 150563 75275 150563 75397 150563 75397 150564 75275 150564 75233 150564 75397 150565 75233 150565 75276 150565 75276 150566 75233 150566 75234 150566 75276 150567 75234 150567 75277 150567 75277 150568 75234 150568 75235 150568 75414 150569 75434 150569 75278 150569 75414 150570 75278 150570 75413 150570 75413 150571 75278 150571 75279 150571 75413 150572 75279 150572 75280 150572 75280 150573 75279 150573 75232 150573 75280 150574 75232 150574 75407 150574 75428 150575 75281 150575 75316 150575 75417 150576 75428 150576 75294 150576 75289 150577 75288 150577 75415 150577 75415 150578 75288 150578 75282 150578 75415 150579 75282 150579 75283 150579 75283 150580 75282 150580 75291 150580 75283 150581 75291 150581 75284 150581 75284 150582 75291 150582 75400 150582 75290 150583 75404 150583 75285 150583 75293 150584 75286 150584 75287 150584 75287 150585 75286 150585 75335 150585 75287 150586 75335 150586 75290 150586 75290 150587 75335 150587 75408 150587 75290 150588 75408 150588 75404 150588 75322 150589 75288 150589 75321 150589 75321 150590 75288 150590 75289 150590 75321 150591 75289 150591 75418 150591 75322 150592 75293 150592 75288 150592 75288 150593 75293 150593 75287 150593 75288 150594 75287 150594 75282 150594 75282 150595 75287 150595 75290 150595 75282 150596 75290 150596 75291 150596 75291 150597 75290 150597 75285 150597 75291 150598 75285 150598 75400 150598 75329 150599 75292 150599 75322 150599 75322 150600 75292 150600 75332 150600 75322 150601 75332 150601 75293 150601 75320 150602 75417 150602 75323 150602 75323 150603 75417 150603 75294 150603 75323 150604 75294 150604 75324 150604 75324 150605 75294 150605 75318 150605 75254 150606 75301 150606 75313 150606 75313 150607 75301 150607 75302 150607 75328 150608 75327 150608 75313 150608 75326 150609 75295 150609 75327 150609 75327 150610 75295 150610 75296 150610 75327 150611 75296 150611 75313 150611 75313 150612 75296 150612 75253 150612 75313 150613 75253 150613 75254 150613 75297 150614 75277 150614 75325 150614 75325 150615 75277 150615 75326 150615 75414 150616 75298 150616 75299 150616 75299 150617 75298 150617 75300 150617 75299 150618 75300 150618 75306 150618 75306 150619 75300 150619 75305 150619 75301 150620 75257 150620 75302 150620 75302 150621 75257 150621 75303 150621 75302 150622 75303 150622 75314 150622 75314 150623 75303 150623 75304 150623 75314 150624 75304 150624 75305 150624 75305 150625 75304 150625 75430 150625 75305 150626 75430 150626 75306 150626 75328 150627 75307 150627 75330 150627 75330 150628 75307 150628 75308 150628 75330 150629 75308 150629 75331 150629 75331 150630 75308 150630 75315 150630 75331 150631 75315 150631 75333 150631 75333 150632 75315 150632 75309 150632 75333 150633 75309 150633 75334 150633 75334 150634 75309 150634 75310 150634 75334 150635 75310 150635 75312 150635 75312 150636 75310 150636 75311 150636 75312 150637 75311 150637 75409 150637 75328 150638 75313 150638 75307 150638 75307 150639 75313 150639 75302 150639 75307 150640 75302 150640 75308 150640 75308 150641 75302 150641 75314 150641 75308 150642 75314 150642 75315 150642 75315 150643 75314 150643 75305 150643 75315 150644 75305 150644 75309 150644 75309 150645 75305 150645 75300 150645 75309 150646 75300 150646 75310 150646 75310 150647 75300 150647 75298 150647 75310 150648 75298 150648 75311 150648 75428 150649 75316 150649 75294 150649 75294 150650 75316 150650 75317 150650 75294 150651 75317 150651 75318 150651 75318 150652 75317 150652 75319 150652 75318 150653 75319 150653 75394 150653 75418 150654 75320 150654 75321 150654 75321 150655 75320 150655 75323 150655 75321 150656 75323 150656 75322 150656 75322 150657 75323 150657 75324 150657 75322 150658 75324 150658 75329 150658 75329 150659 75324 150659 75318 150659 75329 150660 75318 150660 75325 150660 75325 150661 75318 150661 75394 150661 75325 150662 75394 150662 75297 150662 75326 150663 75327 150663 75325 150663 75325 150664 75327 150664 75328 150664 75325 150665 75328 150665 75329 150665 75329 150666 75328 150666 75330 150666 75329 150667 75330 150667 75292 150667 75292 150668 75330 150668 75331 150668 75292 150669 75331 150669 75332 150669 75332 150670 75331 150670 75333 150670 75332 150671 75333 150671 75293 150671 75293 150672 75333 150672 75334 150672 75293 150673 75334 150673 75286 150673 75286 150674 75334 150674 75312 150674 75286 150675 75312 150675 75335 150675 75335 150676 75312 150676 75409 150676 75335 150677 75409 150677 75408 150677 75364 150678 75336 150678 75337 150678 75347 150679 75344 150679 75338 150679 75378 150680 75380 150680 75388 150680 75381 150681 75420 150681 75345 150681 75398 150682 75399 150682 75339 150682 75339 150683 75399 150683 75354 150683 75339 150684 75354 150684 75340 150684 75340 150685 75354 150685 75353 150685 75340 150686 75353 150686 75341 150686 75341 150687 75353 150687 75351 150687 75345 150688 75420 150688 75342 150688 75342 150689 75420 150689 75343 150689 75342 150690 75343 150690 75338 150690 75382 150691 75388 150691 75419 150691 75338 150692 75344 150692 75342 150692 75342 150693 75344 150693 75383 150693 75342 150694 75383 150694 75345 150694 75343 150695 75346 150695 75338 150695 75338 150696 75346 150696 75350 150696 75338 150697 75350 150697 75347 150697 75347 150698 75350 150698 75352 150698 75347 150699 75352 150699 75348 150699 75348 150700 75352 150700 75355 150700 75348 150701 75355 150701 75386 150701 75386 150702 75355 150702 75349 150702 75386 150703 75349 150703 75406 150703 75346 150704 75351 150704 75350 150704 75350 150705 75351 150705 75353 150705 75350 150706 75353 150706 75352 150706 75352 150707 75353 150707 75354 150707 75352 150708 75354 150708 75355 150708 75355 150709 75354 150709 75399 150709 75355 150710 75399 150710 75349 150710 75362 150711 75259 150711 75360 150711 75360 150712 75259 150712 75356 150712 75360 150713 75356 150713 75357 150713 75357 150714 75356 150714 75262 150714 75357 150715 75262 150715 75373 150715 75373 150716 75262 150716 75263 150716 75373 150717 75263 150717 75358 150717 75359 150718 75361 150718 75360 150718 75360 150719 75361 150719 75407 150719 75360 150720 75407 150720 75362 150720 75375 150721 75273 150721 75363 150721 75363 150722 75273 150722 75272 150722 75363 150723 75272 150723 75269 150723 75263 150724 75265 150724 75358 150724 75358 150725 75265 150725 75266 150725 75358 150726 75266 150726 75375 150726 75375 150727 75266 150727 75267 150727 75375 150728 75267 150728 75273 150728 75269 150729 75268 150729 75363 150729 75363 150730 75268 150730 75364 150730 75363 150731 75364 150731 75377 150731 75377 150732 75364 150732 75337 150732 75377 150733 75337 150733 75379 150733 75388 150734 75382 150734 75378 150734 75378 150735 75382 150735 75365 150735 75378 150736 75365 150736 75366 150736 75366 150737 75365 150737 75384 150737 75366 150738 75384 150738 75376 150738 75376 150739 75384 150739 75385 150739 75376 150740 75385 150740 75367 150740 75367 150741 75385 150741 75368 150741 75367 150742 75368 150742 75374 150742 75374 150743 75368 150743 75369 150743 75374 150744 75369 150744 75372 150744 75372 150745 75369 150745 75387 150745 75372 150746 75387 150746 75370 150746 75370 150747 75387 150747 75371 150747 75370 150748 75371 150748 75359 150748 75359 150749 75360 150749 75370 150749 75370 150750 75360 150750 75357 150750 75370 150751 75357 150751 75372 150751 75372 150752 75357 150752 75373 150752 75372 150753 75373 150753 75374 150753 75374 150754 75373 150754 75358 150754 75374 150755 75358 150755 75367 150755 75367 150756 75358 150756 75375 150756 75367 150757 75375 150757 75376 150757 75376 150758 75375 150758 75363 150758 75376 150759 75363 150759 75366 150759 75366 150760 75363 150760 75377 150760 75366 150761 75377 150761 75378 150761 75378 150762 75377 150762 75379 150762 75378 150763 75379 150763 75380 150763 75419 150764 75381 150764 75382 150764 75382 150765 75381 150765 75345 150765 75382 150766 75345 150766 75365 150766 75365 150767 75345 150767 75383 150767 75365 150768 75383 150768 75384 150768 75384 150769 75383 150769 75344 150769 75384 150770 75344 150770 75385 150770 75385 150771 75344 150771 75347 150771 75385 150772 75347 150772 75368 150772 75368 150773 75347 150773 75348 150773 75368 150774 75348 150774 75369 150774 75369 150775 75348 150775 75386 150775 75369 150776 75386 150776 75387 150776 75387 150777 75386 150777 75406 150777 75387 150778 75406 150778 75371 150778 75390 150779 75392 150779 75396 150779 75395 150780 75419 150780 75388 150780 75316 150781 75281 150781 75389 150781 75319 150782 75317 150782 75390 150782 75390 150783 75317 150783 75316 150783 75316 150784 75389 150784 75390 150784 75390 150785 75389 150785 75391 150785 75390 150786 75391 150786 75392 150786 75392 150787 75391 150787 75425 150787 75392 150788 75425 150788 75395 150788 75297 150789 75394 150789 75393 150789 75393 150790 75394 150790 75319 150790 75277 150791 75297 150791 75276 150791 75276 150792 75297 150792 75393 150792 75276 150793 75393 150793 75397 150793 75395 150794 75388 150794 75392 150794 75392 150795 75388 150795 75380 150795 75392 150796 75380 150796 75396 150796 75396 150797 75380 150797 75379 150797 75396 150798 75379 150798 75337 150798 75319 150799 75390 150799 75393 150799 75393 150800 75390 150800 75396 150800 75393 150801 75396 150801 75397 150801 75397 150802 75396 150802 75337 150802 75397 150803 75337 150803 75336 150803 75361 150804 75359 150804 75411 150804 75402 150805 75426 150805 75403 150805 75398 150806 75424 150806 75399 150806 75399 150807 75424 150807 75401 150807 75284 150808 75400 150808 75427 150808 75427 150809 75400 150809 75426 150809 75412 150810 75405 150810 75410 150810 75410 150811 75405 150811 75401 150811 75426 150812 75400 150812 75403 150812 75403 150813 75400 150813 75285 150813 75403 150814 75285 150814 75404 150814 75424 150815 75402 150815 75401 150815 75401 150816 75402 150816 75403 150816 75401 150817 75403 150817 75410 150817 75410 150818 75403 150818 75404 150818 75359 150819 75371 150819 75405 150819 75405 150820 75371 150820 75406 150820 75405 150821 75406 150821 75401 150821 75401 150822 75406 150822 75349 150822 75401 150823 75349 150823 75399 150823 75413 150824 75280 150824 75411 150824 75411 150825 75280 150825 75407 150825 75411 150826 75407 150826 75361 150826 75404 150827 75408 150827 75410 150827 75410 150828 75408 150828 75409 150828 75410 150829 75409 150829 75412 150829 75412 150830 75409 150830 75311 150830 75412 150831 75311 150831 75298 150831 75359 150832 75405 150832 75411 150832 75411 150833 75405 150833 75412 150833 75411 150834 75412 150834 75413 150834 75413 150835 75412 150835 75298 150835 75413 150836 75298 150836 75414 150836 75416 150837 75284 150837 75427 150837 75416 150838 75418 150838 75289 150838 75289 150839 75415 150839 75416 150839 75416 150840 75415 150840 75283 150840 75416 150841 75283 150841 75284 150841 75428 150842 75417 150842 75416 150842 75416 150843 75417 150843 75320 150843 75416 150844 75320 150844 75418 150844 75421 150845 75419 150845 75395 150845 75423 150846 75420 150846 75421 150846 75421 150847 75420 150847 75381 150847 75421 150848 75381 150848 75419 150848 75398 150849 75422 150849 75421 150849 75421 150850 75422 150850 75340 150850 75421 150851 75340 150851 75341 150851 75341 150852 75351 150852 75421 150852 75421 150853 75351 150853 75346 150853 75421 150854 75346 150854 75423 150854 75398 150855 75421 150855 75424 150855 75424 150856 75421 150856 75395 150856 75424 150857 75395 150857 75402 150857 75402 150858 75395 150858 75425 150858 75402 150859 75425 150859 75426 150859 75426 150860 75425 150860 75391 150860 75426 150861 75391 150861 75427 150861 75427 150862 75391 150862 75389 150862 75427 150863 75389 150863 75416 150863 75416 150864 75389 150864 75281 150864 75416 150865 75281 150865 75428 150865 75303 150866 75429 150866 75304 150866 75304 150867 75429 150867 75431 150867 75304 150868 75431 150868 75430 150868 75430 150869 75431 150869 75432 150869 75430 150870 75432 150870 75306 150870 75306 150871 75432 150871 75299 150871 75299 150872 75432 150872 75434 150872 75299 150873 75434 150873 75414 150873 75429 150874 75433 150874 75431 150874 75431 150875 75433 150875 75475 150875 75431 150876 75475 150876 75432 150876 75432 150877 75475 150877 75435 150877 75432 150878 75435 150878 75434 150878 75434 150879 75435 150879 75473 150879 75486 150880 75436 150880 75437 150880 75437 150881 75436 150881 75438 150881 75437 150882 75438 150882 75533 150882 75533 150883 75438 150883 75441 150883 75533 150884 75441 150884 75439 150884 75439 150885 75441 150885 75440 150885 75440 150886 75441 150886 75442 150886 75440 150887 75442 150887 75443 150887 75443 150888 75442 150888 75546 150888 75546 150889 75442 150889 75446 150889 75546 150890 75446 150890 75545 150890 75545 150891 75446 150891 75445 150891 75545 150892 75445 150892 75444 150892 75249 150893 75445 150893 75248 150893 75248 150894 75445 150894 75446 150894 75248 150895 75446 150895 75231 150895 75231 150896 75446 150896 75442 150896 75436 150897 75447 150897 75438 150897 75438 150898 75447 150898 75448 150898 75438 150899 75448 150899 75441 150899 75441 150900 75448 150900 75449 150900 75441 150901 75449 150901 75442 150901 75442 150902 75449 150902 75450 150902 75442 150903 75450 150903 75231 150903 75469 150904 75451 150904 75452 150904 75452 150905 75451 150905 75453 150905 75452 150906 75453 150906 75467 150906 75453 150907 75454 150907 75467 150907 75467 150908 75454 150908 75455 150908 75467 150909 75455 150909 75466 150909 75466 150910 75455 150910 75493 150910 75466 150911 75493 150911 75465 150911 75465 150912 75493 150912 75456 150912 75465 150913 75456 150913 75474 150913 75474 150914 75456 150914 75489 150914 75474 150915 75489 150915 75457 150915 75479 150916 75476 150916 75487 150916 75487 150917 75476 150917 75251 150917 75487 150918 75251 150918 75457 150918 75457 150919 75251 150919 75458 150919 75457 150920 75458 150920 75474 150920 75511 150921 75482 150921 75459 150921 75459 150922 75482 150922 75460 150922 75459 150923 75460 150923 75436 150923 75436 150924 75460 150924 75447 150924 75472 150925 75461 150925 75447 150925 75447 150926 75461 150926 75462 150926 75447 150927 75462 150927 75448 150927 75464 150928 75231 150928 75450 150928 75462 150929 75243 150929 75448 150929 75448 150930 75243 150930 75463 150930 75448 150931 75463 150931 75449 150931 75449 150932 75463 150932 75244 150932 75449 150933 75244 150933 75450 150933 75450 150934 75244 150934 75246 150934 75450 150935 75246 150935 75464 150935 75466 150936 75465 150936 75433 150936 75433 150937 75236 150937 75466 150937 75466 150938 75236 150938 75241 150938 75466 150939 75241 150939 75467 150939 75467 150940 75241 150940 75239 150940 75467 150941 75239 150941 75452 150941 75452 150942 75239 150942 75238 150942 75452 150943 75238 150943 75469 150943 75469 150944 75238 150944 75468 150944 75469 150945 75468 150945 75470 150945 75470 150946 75468 150946 75471 150946 75470 150947 75471 150947 75482 150947 75482 150948 75471 150948 75472 150948 75482 150949 75472 150949 75460 150949 75460 150950 75472 150950 75447 150950 75458 150951 75473 150951 75474 150951 75474 150952 75473 150952 75435 150952 75474 150953 75435 150953 75465 150953 75465 150954 75435 150954 75475 150954 75465 150955 75475 150955 75433 150955 75476 150956 75479 150956 75477 150956 75476 150957 75477 150957 75478 150957 75478 150958 75477 150958 75445 150958 75478 150959 75445 150959 75249 150959 75444 150960 75445 150960 75499 150960 75499 150961 75445 150961 75477 150961 75499 150962 75477 150962 75500 150962 75479 150963 75501 150963 75477 150963 75477 150964 75501 150964 75480 150964 75477 150965 75480 150965 75500 150965 75451 150966 75469 150966 75481 150966 75481 150967 75469 150967 75470 150967 75481 150968 75470 150968 75511 150968 75511 150969 75470 150969 75482 150969 75483 150970 75511 150970 75484 150970 75484 150971 75511 150971 75459 150971 75484 150972 75459 150972 75524 150972 75524 150973 75459 150973 75485 150973 75485 150974 75459 150974 75436 150974 75485 150975 75436 150975 75486 150975 75501 150976 75479 150976 75579 150976 75579 150977 75479 150977 75487 150977 75579 150978 75487 150978 75488 150978 75488 150979 75487 150979 75457 150979 75488 150980 75457 150980 75580 150980 75580 150981 75457 150981 75489 150981 75580 150982 75489 150982 75582 150982 75582 150983 75489 150983 75456 150983 75582 150984 75456 150984 75583 150984 75583 150985 75456 150985 75586 150985 75586 150986 75456 150986 75490 150986 75490 150987 75456 150987 75493 150987 75490 150988 75493 150988 75588 150988 75451 150989 75213 150989 75453 150989 75453 150990 75213 150990 75561 150990 75453 150991 75561 150991 75454 150991 75561 150992 75491 150992 75454 150992 75454 150993 75491 150993 75585 150993 75454 150994 75585 150994 75455 150994 75455 150995 75585 150995 75492 150995 75455 150996 75492 150996 75493 150996 75493 150997 75492 150997 75584 150997 75493 150998 75584 150998 75588 150998 75494 150999 75567 150999 75495 150999 75567 151000 75494 151000 75506 151000 75497 151001 75504 151001 75496 151001 75498 151002 75444 151002 75499 151002 75536 151003 75537 151003 75497 151003 75497 151004 75537 151004 75498 151004 75498 151005 75499 151005 75497 151005 75497 151006 75499 151006 75500 151006 75497 151007 75500 151007 75504 151007 75504 151008 75500 151008 75480 151008 75504 151009 75480 151009 75501 151009 75505 151010 75534 151010 75502 151010 75502 151011 75534 151011 75536 151011 75501 151012 75503 151012 75504 151012 75504 151013 75503 151013 75597 151013 75504 151014 75597 151014 75496 151014 75496 151015 75597 151015 75613 151015 75496 151016 75613 151016 75612 151016 75560 151017 75505 151017 75507 151017 75507 151018 75505 151018 75502 151018 75507 151019 75502 151019 75494 151019 75536 151020 75497 151020 75502 151020 75502 151021 75497 151021 75496 151021 75502 151022 75496 151022 75494 151022 75494 151023 75496 151023 75612 151023 75494 151024 75612 151024 75506 151024 75200 151025 75560 151025 75211 151025 75211 151026 75560 151026 75507 151026 75211 151027 75507 151027 75508 151027 75508 151028 75507 151028 75494 151028 75508 151029 75494 151029 75509 151029 75509 151030 75494 151030 75495 151030 75213 151031 75451 151031 75229 151031 75229 151032 75451 151032 75481 151032 75229 151033 75481 151033 75230 151033 75230 151034 75481 151034 75510 151034 75510 151035 75481 151035 75511 151035 75510 151036 75511 151036 75483 151036 75439 151037 75440 151037 75532 151037 75443 151038 75546 151038 75512 151038 75516 151039 75520 151039 75531 151039 75202 151040 75513 151040 75550 151040 75202 151041 75550 151041 75549 151041 75517 151042 75201 151042 75514 151042 75514 151043 75201 151043 75515 151043 75514 151044 75515 151044 75516 151044 75516 151045 75515 151045 75548 151045 75516 151046 75548 151046 75520 151046 75514 151047 75559 151047 75517 151047 75517 151048 75559 151048 75560 151048 75517 151049 75560 151049 75200 151049 75551 151050 75550 151050 75518 151050 75518 151051 75550 151051 75513 151051 75518 151052 75513 151052 75519 151052 75531 151053 75520 151053 75521 151053 75521 151054 75520 151054 75522 151054 75521 151055 75522 151055 75523 151055 75528 151056 75526 151056 75553 151056 75553 151057 75526 151057 75552 151057 75485 151058 75529 151058 75524 151058 75524 151059 75529 151059 75484 151059 75215 151060 75483 151060 75530 151060 75530 151061 75483 151061 75484 151061 75485 151062 75486 151062 75529 151062 75529 151063 75486 151063 75552 151063 75529 151064 75552 151064 75525 151064 75525 151065 75552 151065 75526 151065 75525 151066 75526 151066 75527 151066 75527 151067 75526 151067 75528 151067 75527 151068 75528 151068 75555 151068 75484 151069 75529 151069 75530 151069 75530 151070 75529 151070 75525 151070 75530 151071 75525 151071 75523 151071 75523 151072 75525 151072 75527 151072 75523 151073 75527 151073 75521 151073 75521 151074 75527 151074 75555 151074 75521 151075 75555 151075 75531 151075 75439 151076 75532 151076 75533 151076 75505 151077 75558 151077 75534 151077 75534 151078 75558 151078 75535 151078 75534 151079 75535 151079 75536 151079 75536 151080 75535 151080 75543 151080 75536 151081 75543 151081 75537 151081 75537 151082 75543 151082 75538 151082 75537 151083 75538 151083 75498 151083 75498 151084 75538 151084 75539 151084 75498 151085 75539 151085 75444 151085 75444 151086 75539 151086 75545 151086 75440 151087 75443 151087 75532 151087 75532 151088 75443 151088 75512 151088 75532 151089 75512 151089 75554 151089 75554 151090 75512 151090 75540 151090 75554 151091 75540 151091 75556 151091 75556 151092 75540 151092 75541 151092 75556 151093 75541 151093 75542 151093 75542 151094 75541 151094 75544 151094 75542 151095 75544 151095 75557 151095 75558 151096 75557 151096 75535 151096 75535 151097 75557 151097 75544 151097 75535 151098 75544 151098 75543 151098 75543 151099 75544 151099 75541 151099 75543 151100 75541 151100 75538 151100 75538 151101 75541 151101 75540 151101 75538 151102 75540 151102 75539 151102 75539 151103 75540 151103 75512 151103 75539 151104 75512 151104 75545 151104 75545 151105 75512 151105 75546 151105 75227 151106 75551 151106 75226 151106 75226 151107 75551 151107 75518 151107 75226 151108 75518 151108 75547 151108 75547 151109 75518 151109 75519 151109 75547 151110 75519 151110 75216 151110 75548 151111 75204 151111 75520 151111 75520 151112 75204 151112 75549 151112 75520 151113 75549 151113 75522 151113 75522 151114 75549 151114 75550 151114 75522 151115 75550 151115 75523 151115 75523 151116 75550 151116 75551 151116 75523 151117 75551 151117 75530 151117 75530 151118 75551 151118 75227 151118 75530 151119 75227 151119 75215 151119 75486 151120 75437 151120 75552 151120 75552 151121 75437 151121 75533 151121 75552 151122 75533 151122 75553 151122 75553 151123 75533 151123 75532 151123 75553 151124 75532 151124 75528 151124 75528 151125 75532 151125 75554 151125 75528 151126 75554 151126 75555 151126 75555 151127 75554 151127 75556 151127 75555 151128 75556 151128 75531 151128 75531 151129 75556 151129 75542 151129 75531 151130 75542 151130 75516 151130 75516 151131 75542 151131 75557 151131 75516 151132 75557 151132 75514 151132 75514 151133 75557 151133 75558 151133 75514 151134 75558 151134 75559 151134 75559 151135 75558 151135 75505 151135 75559 151136 75505 151136 75560 151136 75561 151137 75213 151137 75212 151137 75574 151138 75609 151138 75573 151138 75562 151139 75214 151139 75219 151139 75563 151140 75565 151140 75564 151140 75564 151141 75565 151141 75209 151141 75564 151142 75209 151142 75566 151142 75566 151143 75209 151143 75495 151143 75566 151144 75495 151144 75567 151144 75606 151145 75219 151145 75205 151145 75605 151146 75206 151146 75607 151146 75607 151147 75206 151147 75207 151147 75607 151148 75207 151148 75568 151148 75568 151149 75207 151149 75569 151149 75568 151150 75569 151150 75573 151150 75573 151151 75609 151151 75568 151151 75568 151152 75609 151152 75570 151152 75568 151153 75570 151153 75607 151153 75569 151154 75571 151154 75573 151154 75573 151155 75571 151155 75572 151155 75573 151156 75572 151156 75574 151156 75574 151157 75572 151157 75575 151157 75574 151158 75575 151158 75576 151158 75576 151159 75575 151159 75578 151159 75576 151160 75578 151160 75577 151160 75577 151161 75578 151161 75506 151161 75577 151162 75506 151162 75612 151162 75571 151163 75563 151163 75572 151163 75572 151164 75563 151164 75564 151164 75572 151165 75564 151165 75575 151165 75575 151166 75564 151166 75566 151166 75575 151167 75566 151167 75578 151167 75578 151168 75566 151168 75567 151168 75578 151169 75567 151169 75506 151169 75579 151170 75488 151170 75598 151170 75598 151171 75488 151171 75580 151171 75598 151172 75580 151172 75581 151172 75581 151173 75580 151173 75582 151173 75581 151174 75582 151174 75600 151174 75600 151175 75582 151175 75583 151175 75600 151176 75583 151176 75602 151176 75597 151177 75503 151177 75598 151177 75598 151178 75503 151178 75501 151178 75598 151179 75501 151179 75579 151179 75587 151180 75584 151180 75589 151180 75589 151181 75584 151181 75492 151181 75589 151182 75492 151182 75585 151182 75583 151183 75586 151183 75602 151183 75602 151184 75586 151184 75490 151184 75602 151185 75490 151185 75587 151185 75587 151186 75490 151186 75588 151186 75587 151187 75588 151187 75584 151187 75585 151188 75491 151188 75589 151188 75589 151189 75491 151189 75561 151189 75589 151190 75561 151190 75590 151190 75590 151191 75561 151191 75212 151191 75590 151192 75212 151192 75604 151192 75219 151193 75606 151193 75562 151193 75562 151194 75606 151194 75608 151194 75562 151195 75608 151195 75591 151195 75591 151196 75608 151196 75592 151196 75591 151197 75592 151197 75593 151197 75593 151198 75592 151198 75594 151198 75593 151199 75594 151199 75603 151199 75603 151200 75594 151200 75610 151200 75603 151201 75610 151201 75601 151201 75601 151202 75610 151202 75595 151202 75601 151203 75595 151203 75599 151203 75599 151204 75595 151204 75611 151204 75599 151205 75611 151205 75596 151205 75596 151206 75611 151206 75613 151206 75596 151207 75613 151207 75597 151207 75597 151208 75598 151208 75596 151208 75596 151209 75598 151209 75581 151209 75596 151210 75581 151210 75599 151210 75599 151211 75581 151211 75600 151211 75599 151212 75600 151212 75601 151212 75601 151213 75600 151213 75602 151213 75601 151214 75602 151214 75603 151214 75603 151215 75602 151215 75587 151215 75603 151216 75587 151216 75593 151216 75593 151217 75587 151217 75589 151217 75593 151218 75589 151218 75591 151218 75591 151219 75589 151219 75590 151219 75591 151220 75590 151220 75562 151220 75562 151221 75590 151221 75604 151221 75562 151222 75604 151222 75214 151222 75205 151223 75605 151223 75606 151223 75606 151224 75605 151224 75607 151224 75606 151225 75607 151225 75608 151225 75608 151226 75607 151226 75570 151226 75608 151227 75570 151227 75592 151227 75592 151228 75570 151228 75609 151228 75592 151229 75609 151229 75594 151229 75594 151230 75609 151230 75574 151230 75594 151231 75574 151231 75610 151231 75610 151232 75574 151232 75576 151232 75610 151233 75576 151233 75595 151233 75595 151234 75576 151234 75577 151234 75595 151235 75577 151235 75611 151235 75611 151236 75577 151236 75612 151236 75611 151237 75612 151237 75613 151237 75931 151238 75934 151238 75674 151238 75661 151239 75614 151239 75623 151239 75643 151240 75669 151240 75641 151240 75615 151241 75620 151241 75659 151241 75703 151242 75616 151242 75700 151242 75700 151243 75616 151243 75630 151243 75700 151244 75630 151244 75617 151244 75617 151245 75630 151245 75629 151245 75617 151246 75629 151246 75618 151246 75618 151247 75629 151247 75619 151247 75659 151248 75620 151248 75621 151248 75621 151249 75620 151249 75622 151249 75621 151250 75622 151250 75623 151250 75642 151251 75641 151251 75699 151251 75623 151252 75614 151252 75621 151252 75621 151253 75614 151253 75660 151253 75621 151254 75660 151254 75659 151254 75622 151255 75701 151255 75623 151255 75623 151256 75701 151256 75628 151256 75623 151257 75628 151257 75661 151257 75661 151258 75628 151258 75624 151258 75661 151259 75624 151259 75626 151259 75626 151260 75624 151260 75625 151260 75626 151261 75625 151261 75627 151261 75627 151262 75625 151262 75683 151262 75627 151263 75683 151263 75682 151263 75701 151264 75619 151264 75628 151264 75628 151265 75619 151265 75629 151265 75628 151266 75629 151266 75624 151266 75624 151267 75629 151267 75630 151267 75624 151268 75630 151268 75625 151268 75625 151269 75630 151269 75616 151269 75625 151270 75616 151270 75683 151270 75923 151271 75924 151271 75635 151271 75635 151272 75924 151272 75631 151272 75635 151273 75631 151273 75632 151273 75632 151274 75631 151274 75929 151274 75632 151275 75929 151275 75633 151275 75633 151276 75929 151276 75634 151276 75633 151277 75634 151277 75653 151277 75675 151278 75636 151278 75635 151278 75635 151279 75636 151279 75684 151279 75635 151280 75684 151280 75923 151280 75654 151281 75637 151281 75655 151281 75655 151282 75637 151282 75933 151282 75655 151283 75933 151283 75638 151283 75634 151284 75639 151284 75653 151284 75653 151285 75639 151285 75928 151285 75653 151286 75928 151286 75654 151286 75654 151287 75928 151287 75640 151287 75654 151288 75640 151288 75637 151288 75638 151289 75932 151289 75655 151289 75655 151290 75932 151290 75931 151290 75655 151291 75931 151291 75657 151291 75657 151292 75931 151292 75674 151292 75657 151293 75674 151293 75671 151293 75641 151294 75642 151294 75643 151294 75643 151295 75642 151295 75658 151295 75643 151296 75658 151296 75656 151296 75656 151297 75658 151297 75644 151297 75656 151298 75644 151298 75645 151298 75645 151299 75644 151299 75647 151299 75645 151300 75647 151300 75646 151300 75646 151301 75647 151301 75662 151301 75646 151302 75662 151302 75652 151302 75652 151303 75662 151303 75649 151303 75652 151304 75649 151304 75648 151304 75648 151305 75649 151305 75651 151305 75648 151306 75651 151306 75650 151306 75650 151307 75651 151307 75681 151307 75650 151308 75681 151308 75675 151308 75675 151309 75635 151309 75650 151309 75650 151310 75635 151310 75632 151310 75650 151311 75632 151311 75648 151311 75648 151312 75632 151312 75633 151312 75648 151313 75633 151313 75652 151313 75652 151314 75633 151314 75653 151314 75652 151315 75653 151315 75646 151315 75646 151316 75653 151316 75654 151316 75646 151317 75654 151317 75645 151317 75645 151318 75654 151318 75655 151318 75645 151319 75655 151319 75656 151319 75656 151320 75655 151320 75657 151320 75656 151321 75657 151321 75643 151321 75643 151322 75657 151322 75671 151322 75643 151323 75671 151323 75669 151323 75699 151324 75615 151324 75642 151324 75642 151325 75615 151325 75659 151325 75642 151326 75659 151326 75658 151326 75658 151327 75659 151327 75660 151327 75658 151328 75660 151328 75644 151328 75644 151329 75660 151329 75614 151329 75644 151330 75614 151330 75647 151330 75647 151331 75614 151331 75661 151331 75647 151332 75661 151332 75662 151332 75662 151333 75661 151333 75626 151333 75662 151334 75626 151334 75649 151334 75649 151335 75626 151335 75627 151335 75649 151336 75627 151336 75651 151336 75651 151337 75627 151337 75682 151337 75651 151338 75682 151338 75681 151338 75664 151339 75665 151339 75670 151339 75704 151340 75699 151340 75641 151340 75663 151341 75942 151341 75707 151341 75983 151342 75982 151342 75664 151342 75664 151343 75982 151343 75663 151343 75663 151344 75707 151344 75664 151344 75664 151345 75707 151345 75666 151345 75664 151346 75666 151346 75665 151346 75665 151347 75666 151347 75705 151347 75665 151348 75705 151348 75704 151348 75667 151349 75988 151349 75672 151349 75672 151350 75988 151350 75983 151350 75937 151351 75667 151351 75668 151351 75668 151352 75667 151352 75672 151352 75668 151353 75672 151353 75673 151353 75704 151354 75641 151354 75665 151354 75665 151355 75641 151355 75669 151355 75665 151356 75669 151356 75670 151356 75670 151357 75669 151357 75671 151357 75670 151358 75671 151358 75674 151358 75983 151359 75664 151359 75672 151359 75672 151360 75664 151360 75670 151360 75672 151361 75670 151361 75673 151361 75673 151362 75670 151362 75674 151362 75673 151363 75674 151363 75934 151363 75636 151364 75675 151364 75689 151364 75706 151365 75676 151365 75680 151365 75703 151366 75678 151366 75616 151366 75616 151367 75678 151367 75679 151367 75946 151368 75677 151368 75692 151368 75692 151369 75677 151369 75676 151369 75690 151370 75688 151370 75686 151370 75686 151371 75688 151371 75679 151371 75676 151372 75677 151372 75680 151372 75680 151373 75677 151373 75955 151373 75680 151374 75955 151374 75685 151374 75678 151375 75706 151375 75679 151375 75679 151376 75706 151376 75680 151376 75679 151377 75680 151377 75686 151377 75686 151378 75680 151378 75685 151378 75675 151379 75681 151379 75688 151379 75688 151380 75681 151380 75682 151380 75688 151381 75682 151381 75679 151381 75679 151382 75682 151382 75683 151382 75679 151383 75683 151383 75616 151383 75939 151384 75940 151384 75689 151384 75689 151385 75940 151385 75684 151385 75689 151386 75684 151386 75636 151386 75685 151387 75999 151387 75686 151387 75686 151388 75999 151388 75998 151388 75686 151389 75998 151389 75690 151389 75690 151390 75998 151390 75687 151390 75690 151391 75687 151391 75979 151391 75675 151392 75688 151392 75689 151392 75689 151393 75688 151393 75690 151393 75689 151394 75690 151394 75939 151394 75939 151395 75690 151395 75979 151395 75939 151396 75979 151396 75691 151396 75696 151397 75946 151397 75692 151397 75696 151398 75693 151398 75694 151398 75694 151399 75943 151399 75696 151399 75696 151400 75943 151400 75945 151400 75696 151401 75945 151401 75946 151401 75695 151402 75697 151402 75696 151402 75696 151403 75697 151403 75698 151403 75696 151404 75698 151404 75693 151404 75702 151405 75699 151405 75704 151405 75622 151406 75620 151406 75702 151406 75702 151407 75620 151407 75615 151407 75702 151408 75615 151408 75699 151408 75703 151409 75700 151409 75702 151409 75702 151410 75700 151410 75617 151410 75702 151411 75617 151411 75618 151411 75618 151412 75619 151412 75702 151412 75702 151413 75619 151413 75701 151413 75702 151414 75701 151414 75622 151414 75703 151415 75702 151415 75678 151415 75678 151416 75702 151416 75704 151416 75678 151417 75704 151417 75706 151417 75706 151418 75704 151418 75705 151418 75706 151419 75705 151419 75676 151419 75676 151420 75705 151420 75666 151420 75676 151421 75666 151421 75692 151421 75692 151422 75666 151422 75707 151422 75692 151423 75707 151423 75696 151423 75696 151424 75707 151424 75942 151424 75696 151425 75942 151425 75695 151425 75969 151426 75710 151426 75971 151426 75971 151427 75710 151427 75711 151427 75971 151428 75711 151428 75972 151428 75972 151429 75711 151429 75708 151429 75708 151430 75711 151430 75713 151430 75708 151431 75713 151431 75968 151431 75968 151432 75713 151432 75965 151432 75965 151433 75713 151433 75714 151433 75965 151434 75714 151434 75964 151434 75964 151435 75714 151435 75709 151435 75964 151436 75709 151436 75691 151436 75710 151437 75908 151437 75711 151437 75711 151438 75908 151438 75712 151438 75711 151439 75712 151439 75713 151439 75713 151440 75712 151440 76021 151440 75713 151441 76021 151441 75714 151441 75714 151442 76021 151442 75715 151442 75714 151443 75715 151443 75709 151443 75709 151444 75715 151444 76018 151444 75732 151445 76011 151445 75799 151445 75799 151446 76011 151446 75721 151446 75799 151447 75721 151447 75800 151447 75800 151448 75721 151448 75801 151448 75801 151449 75721 151449 75722 151449 75801 151450 75722 151450 75716 151450 75716 151451 75722 151451 75796 151451 75796 151452 75722 151452 75719 151452 75796 151453 75719 151453 75794 151453 75794 151454 75719 151454 75717 151454 75794 151455 75717 151455 75724 151455 75916 151456 75717 151456 75718 151456 75718 151457 75717 151457 75719 151457 75718 151458 75719 151458 75900 151458 75900 151459 75719 151459 75722 151459 76011 151460 76012 151460 75721 151460 75721 151461 76012 151461 75720 151461 75721 151462 75720 151462 75722 151462 75722 151463 75720 151463 75723 151463 75722 151464 75723 151464 75900 151464 75724 151465 75717 151465 75725 151465 75725 151466 75717 151466 75726 151466 75725 151467 75726 151467 75748 151467 75734 151468 75840 151468 75726 151468 75726 151469 75840 151469 75749 151469 75726 151470 75749 151470 75748 151470 75763 151471 75727 151471 75764 151471 75764 151472 75727 151472 76024 151472 75764 151473 76024 151473 75728 151473 75728 151474 76024 151474 76008 151474 76009 151475 75783 151475 75729 151475 76009 151476 75729 151476 75728 151476 75728 151477 75729 151477 75768 151477 75728 151478 75768 151478 75765 151478 75783 151479 76009 151479 75785 151479 75785 151480 76009 151480 75730 151480 75785 151481 75730 151481 75731 151481 76011 151482 75732 151482 75798 151482 76011 151483 75798 151483 75730 151483 75730 151484 75798 151484 75733 151484 75730 151485 75733 151485 75731 151485 75840 151486 75734 151486 75735 151486 75735 151487 75734 151487 75736 151487 75735 151488 75736 151488 75835 151488 75835 151489 75736 151489 76006 151489 75835 151490 76006 151490 75836 151490 75836 151491 76006 151491 76005 151491 75836 151492 76005 151492 75737 151492 75737 151493 76005 151493 75739 151493 75737 151494 75739 151494 75837 151494 75837 151495 75739 151495 75738 151495 75738 151496 75739 151496 75845 151496 75845 151497 75739 151497 75742 151497 75845 151498 75742 151498 75743 151498 75763 151499 75740 151499 76000 151499 76000 151500 75740 151500 75847 151500 76000 151501 75847 151501 76002 151501 75847 151502 75741 151502 76002 151502 76002 151503 75741 151503 75843 151503 76002 151504 75843 151504 76003 151504 76003 151505 75843 151505 75842 151505 76003 151506 75842 151506 75742 151506 75742 151507 75842 151507 75846 151507 75742 151508 75846 151508 75743 151508 75756 151509 75744 151509 75762 151509 75744 151510 75756 151510 75758 151510 75746 151511 75747 151511 75757 151511 75792 151512 75724 151512 75725 151512 75750 151513 75745 151513 75746 151513 75746 151514 75745 151514 75792 151514 75792 151515 75725 151515 75746 151515 75746 151516 75725 151516 75748 151516 75746 151517 75748 151517 75747 151517 75747 151518 75748 151518 75749 151518 75747 151519 75749 151519 75840 151519 75753 151520 75821 151520 75755 151520 75755 151521 75821 151521 75750 151521 75840 151522 75751 151522 75747 151522 75747 151523 75751 151523 75849 151523 75747 151524 75849 151524 75757 151524 75757 151525 75849 151525 75870 151525 75757 151526 75870 151526 75752 151526 75759 151527 75753 151527 75754 151527 75754 151528 75753 151528 75755 151528 75754 151529 75755 151529 75756 151529 75750 151530 75746 151530 75755 151530 75755 151531 75746 151531 75757 151531 75755 151532 75757 151532 75756 151532 75756 151533 75757 151533 75752 151533 75756 151534 75752 151534 75758 151534 75779 151535 75759 151535 75760 151535 75760 151536 75759 151536 75754 151536 75760 151537 75754 151537 75881 151537 75881 151538 75754 151538 75756 151538 75881 151539 75756 151539 75761 151539 75761 151540 75756 151540 75762 151540 75740 151541 75763 151541 75896 151541 75896 151542 75763 151542 75764 151542 75896 151543 75764 151543 75767 151543 75728 151544 75765 151544 75764 151544 75764 151545 75765 151545 75766 151545 75764 151546 75766 151546 75767 151546 75768 151547 75729 151547 75811 151547 75733 151548 75798 151548 75786 151548 75774 151549 75775 151549 75772 151549 75769 151550 75873 151550 75770 151550 75769 151551 75770 151551 75790 151551 75778 151552 75771 151552 75775 151552 75775 151553 75771 151553 75872 151553 75775 151554 75872 151554 75772 151554 75772 151555 75872 151555 75874 151555 75772 151556 75874 151556 75788 151556 75759 151557 75777 151557 75753 151557 75753 151558 75777 151558 75776 151558 75753 151559 75776 151559 75821 151559 75821 151560 75776 151560 75773 151560 75819 151561 75773 151561 75774 151561 75774 151562 75773 151562 75776 151562 75774 151563 75776 151563 75775 151563 75775 151564 75776 151564 75777 151564 75775 151565 75777 151565 75778 151565 75778 151566 75777 151566 75759 151566 75778 151567 75759 151567 75779 151567 75791 151568 75770 151568 75780 151568 75780 151569 75770 151569 75873 151569 75780 151570 75873 151570 75781 151570 75819 151571 75774 151571 75818 151571 75818 151572 75774 151572 75772 151572 75818 151573 75772 151573 75817 151573 75817 151574 75772 151574 75788 151574 75817 151575 75788 151575 75815 151575 75815 151576 75788 151576 75789 151576 75815 151577 75789 151577 75814 151577 75786 151578 75798 151578 75782 151578 75808 151579 75784 151579 75786 151579 75729 151580 75783 151580 75784 151580 75784 151581 75783 151581 75785 151581 75784 151582 75785 151582 75786 151582 75786 151583 75785 151583 75731 151583 75786 151584 75731 151584 75733 151584 75874 151585 75787 151585 75788 151585 75788 151586 75787 151586 75790 151586 75788 151587 75790 151587 75789 151587 75789 151588 75790 151588 75770 151588 75789 151589 75770 151589 75814 151589 75814 151590 75770 151590 75791 151590 75814 151591 75791 151591 75811 151591 75724 151592 75792 151592 75793 151592 75724 151593 75793 151593 75794 151593 75794 151594 75793 151594 75795 151594 75794 151595 75795 151595 75796 151595 75796 151596 75795 151596 75716 151596 75716 151597 75795 151597 75797 151597 75716 151598 75797 151598 75801 151598 75798 151599 75732 151599 75782 151599 75782 151600 75732 151600 75799 151600 75782 151601 75799 151601 75797 151601 75797 151602 75799 151602 75800 151602 75797 151603 75800 151603 75801 151603 75808 151604 75802 151604 75813 151604 75813 151605 75802 151605 75803 151605 75813 151606 75803 151606 75816 151606 75816 151607 75803 151607 75804 151607 75816 151608 75804 151608 75805 151608 75805 151609 75804 151609 75807 151609 75805 151610 75807 151610 75806 151610 75806 151611 75807 151611 75809 151611 75806 151612 75809 151612 75820 151612 75820 151613 75809 151613 75745 151613 75820 151614 75745 151614 75750 151614 75808 151615 75786 151615 75802 151615 75802 151616 75786 151616 75782 151616 75802 151617 75782 151617 75803 151617 75803 151618 75782 151618 75797 151618 75803 151619 75797 151619 75804 151619 75804 151620 75797 151620 75795 151620 75804 151621 75795 151621 75807 151621 75807 151622 75795 151622 75793 151622 75807 151623 75793 151623 75809 151623 75809 151624 75793 151624 75792 151624 75809 151625 75792 151625 75745 151625 75765 151626 75768 151626 75810 151626 75810 151627 75768 151627 75811 151627 75810 151628 75811 151628 75885 151628 75885 151629 75811 151629 75791 151629 75885 151630 75791 151630 75886 151630 75886 151631 75791 151631 75780 151631 75886 151632 75780 151632 75812 151632 75812 151633 75780 151633 75781 151633 75812 151634 75781 151634 75887 151634 75729 151635 75784 151635 75811 151635 75811 151636 75784 151636 75808 151636 75811 151637 75808 151637 75814 151637 75814 151638 75808 151638 75813 151638 75814 151639 75813 151639 75815 151639 75815 151640 75813 151640 75816 151640 75815 151641 75816 151641 75817 151641 75817 151642 75816 151642 75805 151642 75817 151643 75805 151643 75818 151643 75818 151644 75805 151644 75806 151644 75818 151645 75806 151645 75819 151645 75819 151646 75806 151646 75820 151646 75819 151647 75820 151647 75773 151647 75773 151648 75820 151648 75750 151648 75773 151649 75750 151649 75821 151649 75847 151650 75740 151650 75895 151650 75830 151651 75827 151651 75822 151651 75859 151652 75892 151652 75890 151652 75875 151653 75824 151653 75823 151653 75823 151654 75824 151654 75825 151654 75823 151655 75825 151655 75834 151655 75834 151656 75825 151656 75762 151656 75834 151657 75762 151657 75744 151657 75861 151658 75890 151658 75871 151658 75860 151659 75878 151659 75862 151659 75862 151660 75878 151660 75879 151660 75862 151661 75879 151661 75826 151661 75826 151662 75879 151662 75880 151662 75826 151663 75880 151663 75822 151663 75822 151664 75827 151664 75826 151664 75826 151665 75827 151665 75863 151665 75826 151666 75863 151666 75862 151666 75880 151667 75877 151667 75822 151667 75822 151668 75877 151668 75828 151668 75822 151669 75828 151669 75830 151669 75830 151670 75828 151670 75829 151670 75830 151671 75829 151671 75831 151671 75831 151672 75829 151672 75832 151672 75831 151673 75832 151673 75833 151673 75833 151674 75832 151674 75758 151674 75833 151675 75758 151675 75752 151675 75877 151676 75875 151676 75828 151676 75828 151677 75875 151677 75823 151677 75828 151678 75823 151678 75829 151678 75829 151679 75823 151679 75834 151679 75829 151680 75834 151680 75832 151680 75832 151681 75834 151681 75744 151681 75832 151682 75744 151682 75758 151682 75735 151683 75835 151683 75839 151683 75839 151684 75835 151684 75836 151684 75839 151685 75836 151685 75851 151685 75851 151686 75836 151686 75737 151686 75851 151687 75737 151687 75838 151687 75838 151688 75737 151688 75837 151688 75838 151689 75837 151689 75844 151689 75849 151690 75751 151690 75839 151690 75839 151691 75751 151691 75840 151691 75839 151692 75840 151692 75735 151692 75841 151693 75846 151693 75855 151693 75855 151694 75846 151694 75842 151694 75855 151695 75842 151695 75843 151695 75837 151696 75738 151696 75844 151696 75844 151697 75738 151697 75845 151697 75844 151698 75845 151698 75841 151698 75841 151699 75845 151699 75743 151699 75841 151700 75743 151700 75846 151700 75843 151701 75741 151701 75855 151701 75855 151702 75741 151702 75847 151702 75855 151703 75847 151703 75857 151703 75857 151704 75847 151704 75895 151704 75857 151705 75895 151705 75858 151705 75890 151706 75861 151706 75859 151706 75859 151707 75861 151707 75864 151707 75859 151708 75864 151708 75856 151708 75856 151709 75864 151709 75865 151709 75856 151710 75865 151710 75854 151710 75854 151711 75865 151711 75866 151711 75854 151712 75866 151712 75848 151712 75848 151713 75866 151713 75867 151713 75848 151714 75867 151714 75853 151714 75853 151715 75867 151715 75868 151715 75853 151716 75868 151716 75852 151716 75852 151717 75868 151717 75869 151717 75852 151718 75869 151718 75850 151718 75850 151719 75869 151719 75870 151719 75850 151720 75870 151720 75849 151720 75849 151721 75839 151721 75850 151721 75850 151722 75839 151722 75851 151722 75850 151723 75851 151723 75852 151723 75852 151724 75851 151724 75838 151724 75852 151725 75838 151725 75853 151725 75853 151726 75838 151726 75844 151726 75853 151727 75844 151727 75848 151727 75848 151728 75844 151728 75841 151728 75848 151729 75841 151729 75854 151729 75854 151730 75841 151730 75855 151730 75854 151731 75855 151731 75856 151731 75856 151732 75855 151732 75857 151732 75856 151733 75857 151733 75859 151733 75859 151734 75857 151734 75858 151734 75859 151735 75858 151735 75892 151735 75871 151736 75860 151736 75861 151736 75861 151737 75860 151737 75862 151737 75861 151738 75862 151738 75864 151738 75864 151739 75862 151739 75863 151739 75864 151740 75863 151740 75865 151740 75865 151741 75863 151741 75827 151741 75865 151742 75827 151742 75866 151742 75866 151743 75827 151743 75830 151743 75866 151744 75830 151744 75867 151744 75867 151745 75830 151745 75831 151745 75867 151746 75831 151746 75868 151746 75868 151747 75831 151747 75833 151747 75868 151748 75833 151748 75869 151748 75869 151749 75833 151749 75752 151749 75869 151750 75752 151750 75870 151750 75876 151751 75871 151751 75891 151751 75884 151752 75779 151752 75760 151752 75778 151753 75779 151753 75771 151753 75771 151754 75779 151754 75884 151754 75771 151755 75884 151755 75872 151755 75872 151756 75884 151756 75874 151756 75781 151757 75873 151757 75884 151757 75884 151758 75873 151758 75769 151758 75769 151759 75790 151759 75884 151759 75884 151760 75790 151760 75787 151760 75884 151761 75787 151761 75874 151761 75875 151762 75877 151762 75876 151762 75876 151763 75877 151763 75880 151763 75860 151764 75871 151764 75878 151764 75878 151765 75871 151765 75876 151765 75878 151766 75876 151766 75879 151766 75879 151767 75876 151767 75880 151767 75762 151768 75825 151768 75876 151768 75876 151769 75825 151769 75824 151769 75876 151770 75824 151770 75875 151770 75762 151771 75876 151771 75761 151771 75761 151772 75876 151772 75891 151772 75761 151773 75891 151773 75881 151773 75881 151774 75891 151774 75882 151774 75881 151775 75882 151775 75760 151775 75760 151776 75882 151776 75883 151776 75760 151777 75883 151777 75884 151777 75884 151778 75883 151778 75887 151778 75884 151779 75887 151779 75781 151779 75895 151780 75740 151780 75896 151780 75892 151781 75858 151781 75893 151781 75810 151782 75885 151782 75898 151782 75886 151783 75812 151783 75888 151783 75812 151784 75887 151784 75888 151784 75888 151785 75887 151785 75883 151785 75888 151786 75883 151786 75894 151786 75894 151787 75883 151787 75882 151787 75894 151788 75882 151788 75889 151788 75889 151789 75882 151789 75891 151789 75889 151790 75891 151790 75890 151790 75890 151791 75891 151791 75871 151791 75890 151792 75892 151792 75889 151792 75889 151793 75892 151793 75893 151793 75889 151794 75893 151794 75894 151794 75894 151795 75893 151795 75897 151795 75894 151796 75897 151796 75888 151796 75888 151797 75897 151797 75898 151797 75888 151798 75898 151798 75886 151798 75886 151799 75898 151799 75885 151799 75858 151800 75895 151800 75893 151800 75893 151801 75895 151801 75896 151801 75893 151802 75896 151802 75897 151802 75897 151803 75896 151803 75767 151803 75897 151804 75767 151804 75898 151804 75898 151805 75767 151805 75766 151805 75898 151806 75766 151806 75810 151806 75810 151807 75766 151807 75765 151807 75900 151808 76017 151808 75899 151808 75900 151809 75899 151809 75902 151809 75899 151810 75901 151810 75902 151810 75902 151811 75901 151811 75938 151811 75902 151812 75938 151812 75919 151812 75919 151813 75938 151813 76007 151813 76007 151814 75938 151814 75709 151814 76007 151815 75709 151815 76018 151815 75935 151816 76022 151816 75936 151816 75936 151817 76022 151817 76023 151817 75936 151818 76023 151818 75903 151818 75903 151819 76023 151819 75905 151819 75903 151820 75905 151820 75904 151820 75904 151821 75905 151821 76025 151821 75904 151822 76025 151822 75921 151822 75921 151823 76025 151823 76027 151823 75921 151824 76027 151824 75906 151824 75906 151825 76027 151825 75907 151825 75906 151826 75907 151826 75710 151826 75710 151827 75907 151827 75908 151827 76013 151828 76022 151828 75935 151828 75927 151829 76015 151829 75911 151829 75935 151830 75930 151830 76013 151830 76013 151831 75930 151831 75909 151831 76013 151832 75909 151832 75911 151832 75911 151833 75909 151833 75910 151833 75911 151834 75910 151834 75927 151834 75927 151835 75912 151835 76015 151835 76015 151836 75912 151836 75913 151836 76015 151837 75913 151837 76016 151837 75899 151838 76017 151838 75925 151838 75925 151839 76017 151839 75914 151839 75925 151840 75914 151840 75926 151840 75926 151841 75914 151841 76016 151841 75926 151842 76016 151842 75915 151842 75915 151843 76016 151843 75913 151843 75919 151844 76007 151844 75920 151844 75718 151845 75900 151845 75916 151845 75916 151846 75900 151846 75902 151846 75916 151847 75902 151847 75917 151847 75917 151848 75902 151848 75919 151848 75917 151849 75919 151849 75918 151849 75918 151850 75919 151850 75920 151850 75937 151851 75904 151851 75959 151851 75959 151852 75904 151852 75921 151852 75959 151853 75921 151853 75961 151853 75961 151854 75921 151854 75962 151854 75962 151855 75921 151855 75906 151855 75962 151856 75906 151856 75922 151856 75922 151857 75906 151857 75957 151857 75957 151858 75906 151858 75710 151858 75957 151859 75710 151859 75969 151859 75684 151860 75899 151860 75923 151860 75923 151861 75899 151861 75925 151861 75923 151862 75925 151862 75924 151862 75924 151863 75925 151863 75926 151863 75912 151864 75927 151864 75640 151864 75640 151865 75928 151865 75912 151865 75912 151866 75928 151866 75639 151866 75912 151867 75639 151867 75913 151867 75913 151868 75639 151868 75634 151868 75913 151869 75634 151869 75915 151869 75915 151870 75634 151870 75929 151870 75915 151871 75929 151871 75926 151871 75926 151872 75929 151872 75631 151872 75926 151873 75631 151873 75924 151873 75935 151874 75934 151874 75930 151874 75930 151875 75934 151875 75931 151875 75930 151876 75931 151876 75909 151876 75931 151877 75932 151877 75909 151877 75909 151878 75932 151878 75638 151878 75909 151879 75638 151879 75910 151879 75910 151880 75638 151880 75933 151880 75910 151881 75933 151881 75927 151881 75927 151882 75933 151882 75637 151882 75927 151883 75637 151883 75640 151883 75934 151884 75935 151884 75673 151884 75673 151885 75935 151885 75936 151885 75673 151886 75936 151886 75668 151886 75668 151887 75936 151887 75903 151887 75668 151888 75903 151888 75937 151888 75937 151889 75903 151889 75904 151889 75691 151890 75709 151890 75938 151890 75691 151891 75938 151891 75939 151891 75939 151892 75938 151892 75901 151892 75939 151893 75901 151893 75940 151893 75940 151894 75901 151894 75899 151894 75940 151895 75899 151895 75684 151895 75941 151896 75942 151896 75663 151896 75697 151897 75941 151897 75981 151897 75950 151898 75944 151898 75943 151898 75943 151899 75944 151899 75953 151899 75943 151900 75953 151900 75945 151900 75945 151901 75953 151901 75954 151901 75945 151902 75954 151902 75946 151902 75946 151903 75954 151903 75677 151903 75952 151904 75685 151904 75955 151904 75951 151905 75994 151905 75947 151905 75947 151906 75994 151906 75997 151906 75947 151907 75997 151907 75952 151907 75952 151908 75997 151908 75999 151908 75952 151909 75999 151909 75685 151909 75948 151910 75944 151910 75949 151910 75949 151911 75944 151911 75950 151911 75949 151912 75950 151912 75693 151912 75948 151913 75951 151913 75944 151913 75944 151914 75951 151914 75947 151914 75944 151915 75947 151915 75953 151915 75953 151916 75947 151916 75952 151916 75953 151917 75952 151917 75954 151917 75954 151918 75952 151918 75955 151918 75954 151919 75955 151919 75677 151919 75956 151920 75990 151920 75948 151920 75948 151921 75990 151921 75992 151921 75948 151922 75992 151922 75951 151922 75984 151923 75697 151923 75985 151923 75985 151924 75697 151924 75981 151924 75985 151925 75981 151925 75986 151925 75986 151926 75981 151926 75987 151926 75970 151927 75958 151927 75957 151927 75973 151928 75960 151928 75958 151928 75958 151929 75960 151929 75922 151929 75958 151930 75922 151930 75957 151930 75959 151931 75961 151931 75960 151931 75960 151932 75961 151932 75962 151932 75960 151933 75962 151933 75922 151933 75667 151934 75937 151934 75989 151934 75989 151935 75937 151935 75959 151935 75691 151936 75979 151936 75963 151936 75691 151937 75963 151937 75964 151937 75964 151938 75963 151938 75966 151938 75964 151939 75966 151939 75965 151939 75965 151940 75966 151940 75968 151940 75968 151941 75966 151941 75967 151941 75968 151942 75967 151942 75708 151942 75957 151943 75969 151943 75970 151943 75970 151944 75969 151944 75971 151944 75970 151945 75971 151945 75967 151945 75967 151946 75971 151946 75972 151946 75967 151947 75972 151947 75708 151947 75973 151948 75974 151948 75975 151948 75975 151949 75974 151949 75976 151949 75975 151950 75976 151950 75991 151950 75991 151951 75976 151951 75978 151951 75991 151952 75978 151952 75993 151952 75993 151953 75978 151953 75977 151953 75993 151954 75977 151954 75995 151954 75995 151955 75977 151955 75980 151955 75995 151956 75980 151956 75996 151956 75996 151957 75980 151957 75687 151957 75996 151958 75687 151958 75998 151958 75973 151959 75958 151959 75974 151959 75974 151960 75958 151960 75970 151960 75974 151961 75970 151961 75976 151961 75976 151962 75970 151962 75967 151962 75976 151963 75967 151963 75978 151963 75978 151964 75967 151964 75966 151964 75978 151965 75966 151965 75977 151965 75977 151966 75966 151966 75963 151966 75977 151967 75963 151967 75980 151967 75980 151968 75963 151968 75979 151968 75980 151969 75979 151969 75687 151969 75941 151970 75663 151970 75981 151970 75981 151971 75663 151971 75982 151971 75981 151972 75982 151972 75987 151972 75987 151973 75982 151973 75983 151973 75987 151974 75983 151974 75988 151974 75693 151975 75984 151975 75949 151975 75949 151976 75984 151976 75985 151976 75949 151977 75985 151977 75948 151977 75948 151978 75985 151978 75986 151978 75948 151979 75986 151979 75956 151979 75956 151980 75986 151980 75987 151980 75956 151981 75987 151981 75989 151981 75989 151982 75987 151982 75988 151982 75989 151983 75988 151983 75667 151983 75959 151984 75960 151984 75989 151984 75989 151985 75960 151985 75973 151985 75989 151986 75973 151986 75956 151986 75956 151987 75973 151987 75975 151987 75956 151988 75975 151988 75990 151988 75990 151989 75975 151989 75991 151989 75990 151990 75991 151990 75992 151990 75992 151991 75991 151991 75993 151991 75992 151992 75993 151992 75951 151992 75951 151993 75993 151993 75995 151993 75951 151994 75995 151994 75994 151994 75994 151995 75995 151995 75996 151995 75994 151996 75996 151996 75997 151996 75997 151997 75996 151997 75998 151997 75997 151998 75998 151998 75999 151998 75727 151999 75763 151999 76001 151999 76001 152000 75763 152000 76000 152000 76001 152001 76000 152001 76026 152001 76000 152002 76002 152002 76026 152002 76026 152003 76002 152003 76003 152003 76026 152004 76003 152004 76004 152004 76004 152005 76003 152005 75742 152005 76004 152006 75742 152006 76020 152006 76020 152007 75742 152007 75739 152007 76020 152008 75739 152008 76019 152008 76019 152009 75739 152009 76005 152009 76019 152010 76005 152010 76006 152010 75734 152011 75918 152011 75736 152011 75736 152012 75918 152012 75920 152012 75736 152013 75920 152013 76006 152013 76006 152014 75920 152014 76007 152014 76006 152015 76007 152015 76019 152015 75728 152016 76008 152016 76009 152016 76009 152017 76008 152017 76010 152017 76009 152018 76010 152018 75730 152018 75730 152019 76010 152019 76014 152019 75730 152020 76014 152020 76011 152020 76011 152021 76014 152021 76012 152021 76017 152022 75900 152022 75723 152022 76022 152023 76013 152023 76014 152023 76014 152024 76013 152024 75911 152024 76014 152025 75911 152025 76012 152025 76012 152026 75911 152026 76015 152026 76012 152027 76015 152027 75720 152027 75720 152028 76015 152028 76016 152028 75720 152029 76016 152029 75723 152029 75723 152030 76016 152030 75914 152030 75723 152031 75914 152031 76017 152031 75712 152032 76004 152032 76020 152032 76007 152033 76018 152033 76019 152033 76019 152034 76018 152034 75715 152034 76019 152035 75715 152035 76020 152035 76020 152036 75715 152036 76021 152036 76020 152037 76021 152037 75712 152037 76014 152038 76010 152038 76022 152038 76022 152039 76010 152039 76008 152039 76022 152040 76008 152040 76023 152040 76023 152041 76008 152041 76024 152041 76023 152042 76024 152042 75905 152042 75905 152043 76024 152043 75727 152043 75905 152044 75727 152044 76025 152044 76025 152045 75727 152045 76001 152045 76025 152046 76001 152046 76027 152046 76027 152047 76001 152047 76026 152047 76027 152048 76026 152048 75907 152048 75907 152049 76026 152049 76004 152049 75907 152050 76004 152050 75908 152050 75908 152051 76004 152051 75712 152051 75918 152052 75734 152052 75726 152052 75918 152053 75726 152053 75917 152053 75917 152054 75726 152054 75717 152054 75917 152055 75717 152055 75916 152055 76041 152056 76028 152056 76042 152056 76042 152057 76028 152057 76253 152057 76042 152058 76253 152058 76029 152058 76029 152059 76253 152059 76250 152059 76258 152060 76055 152060 76030 152060 76030 152061 76055 152061 76048 152061 76030 152062 76048 152062 76242 152062 76048 152063 76049 152063 76242 152063 76242 152064 76049 152064 76051 152064 76242 152065 76051 152065 76243 152065 76243 152066 76051 152066 76053 152066 76243 152067 76053 152067 76031 152067 76031 152068 76053 152068 76036 152068 76031 152069 76036 152069 76245 152069 76045 152070 76032 152070 76033 152070 76033 152071 76032 152071 76246 152071 76033 152072 76246 152072 76034 152072 76034 152073 76246 152073 76245 152073 76034 152074 76245 152074 76035 152074 76035 152075 76245 152075 76036 152075 76438 152076 76235 152076 76037 152076 76228 152077 76436 152077 76038 152077 76038 152078 76436 152078 76039 152078 76038 152079 76039 152079 76040 152079 76040 152080 76039 152080 76438 152080 76040 152081 76438 152081 76260 152081 76260 152082 76438 152082 76037 152082 76058 152083 76041 152083 76043 152083 76043 152084 76041 152084 76042 152084 76043 152085 76042 152085 76044 152085 76044 152086 76042 152086 76029 152086 76044 152087 76029 152087 76210 152087 76061 152088 76045 152088 76136 152088 76136 152089 76045 152089 76033 152089 76136 152090 76033 152090 76046 152090 76046 152091 76033 152091 76034 152091 76046 152092 76034 152092 76131 152092 76131 152093 76034 152093 76035 152093 76131 152094 76035 152094 76132 152094 76132 152095 76035 152095 76036 152095 76132 152096 76036 152096 76134 152096 76134 152097 76036 152097 76140 152097 76140 152098 76036 152098 76047 152098 76047 152099 76036 152099 76053 152099 76047 152100 76053 152100 76142 152100 76055 152101 76111 152101 76048 152101 76048 152102 76111 152102 76144 152102 76048 152103 76144 152103 76049 152103 76144 152104 76050 152104 76049 152104 76049 152105 76050 152105 76052 152105 76049 152106 76052 152106 76051 152106 76051 152107 76052 152107 76138 152107 76051 152108 76138 152108 76053 152108 76053 152109 76138 152109 76054 152109 76053 152110 76054 152110 76142 152110 76111 152111 76055 152111 76176 152111 76176 152112 76055 152112 76056 152112 76176 152113 76056 152113 76171 152113 76171 152114 76056 152114 76057 152114 76171 152115 76057 152115 76058 152115 76058 152116 76057 152116 76041 152116 76059 152117 76222 152117 76060 152117 76059 152118 76060 152118 76193 152118 76193 152119 76060 152119 76437 152119 76193 152120 76437 152120 76189 152120 76189 152121 76437 152121 76045 152121 76189 152122 76045 152122 76061 152122 76097 152123 76209 152123 76167 152123 76197 152124 76097 152124 76075 152124 76067 152125 76062 152125 76196 152125 76196 152126 76062 152126 76063 152126 76196 152127 76063 152127 76064 152127 76064 152128 76063 152128 76070 152128 76064 152129 76070 152129 76065 152129 76065 152130 76070 152130 76181 152130 76069 152131 76186 152131 76183 152131 76071 152132 76108 152132 76068 152132 76068 152133 76108 152133 76110 152133 76068 152134 76110 152134 76069 152134 76069 152135 76110 152135 76066 152135 76069 152136 76066 152136 76186 152136 76100 152137 76062 152137 76099 152137 76099 152138 76062 152138 76067 152138 76099 152139 76067 152139 76098 152139 76100 152140 76071 152140 76062 152140 76062 152141 76071 152141 76068 152141 76062 152142 76068 152142 76063 152142 76063 152143 76068 152143 76069 152143 76063 152144 76069 152144 76070 152144 76070 152145 76069 152145 76183 152145 76070 152146 76183 152146 76181 152146 76101 152147 76104 152147 76100 152147 76100 152148 76104 152148 76106 152148 76100 152149 76106 152149 76071 152149 76072 152150 76197 152150 76073 152150 76073 152151 76197 152151 76075 152151 76073 152152 76075 152152 76074 152152 76074 152153 76075 152153 76103 152153 76079 152154 76076 152154 76092 152154 76077 152155 76078 152155 76092 152155 76043 152156 76044 152156 76078 152156 76078 152157 76044 152157 76210 152157 76078 152158 76210 152158 76092 152158 76092 152159 76210 152159 76211 152159 76092 152160 76211 152160 76079 152160 76169 152161 76058 152161 76102 152161 76102 152162 76058 152162 76043 152162 76080 152163 76214 152163 76094 152163 76094 152164 76214 152164 76215 152164 76094 152165 76215 152165 76095 152165 76095 152166 76215 152166 76059 152166 76095 152167 76059 152167 76096 152167 76080 152168 76094 152168 76081 152168 76081 152169 76094 152169 76082 152169 76081 152170 76082 152170 76083 152170 76076 152171 76079 152171 76082 152171 76082 152172 76079 152172 76213 152172 76082 152173 76213 152173 76083 152173 76077 152174 76093 152174 76105 152174 76105 152175 76093 152175 76084 152175 76105 152176 76084 152176 76085 152176 76085 152177 76084 152177 76086 152177 76085 152178 76086 152178 76107 152178 76107 152179 76086 152179 76088 152179 76107 152180 76088 152180 76087 152180 76087 152181 76088 152181 76089 152181 76087 152182 76089 152182 76090 152182 76090 152183 76089 152183 76091 152183 76090 152184 76091 152184 76109 152184 76077 152185 76092 152185 76093 152185 76093 152186 76092 152186 76076 152186 76093 152187 76076 152187 76084 152187 76084 152188 76076 152188 76082 152188 76084 152189 76082 152189 76086 152189 76086 152190 76082 152190 76094 152190 76086 152191 76094 152191 76088 152191 76088 152192 76094 152192 76095 152192 76088 152193 76095 152193 76089 152193 76089 152194 76095 152194 76096 152194 76089 152195 76096 152195 76091 152195 76097 152196 76167 152196 76075 152196 76075 152197 76167 152197 76166 152197 76075 152198 76166 152198 76103 152198 76103 152199 76166 152199 76175 152199 76103 152200 76175 152200 76170 152200 76098 152201 76072 152201 76099 152201 76099 152202 76072 152202 76073 152202 76099 152203 76073 152203 76100 152203 76100 152204 76073 152204 76074 152204 76100 152205 76074 152205 76101 152205 76101 152206 76074 152206 76103 152206 76101 152207 76103 152207 76102 152207 76102 152208 76103 152208 76170 152208 76102 152209 76170 152209 76169 152209 76043 152210 76078 152210 76102 152210 76102 152211 76078 152211 76077 152211 76102 152212 76077 152212 76101 152212 76101 152213 76077 152213 76105 152213 76101 152214 76105 152214 76104 152214 76104 152215 76105 152215 76085 152215 76104 152216 76085 152216 76106 152216 76106 152217 76085 152217 76107 152217 76106 152218 76107 152218 76071 152218 76071 152219 76107 152219 76087 152219 76071 152220 76087 152220 76108 152220 76108 152221 76087 152221 76090 152221 76108 152222 76090 152222 76110 152222 76110 152223 76090 152223 76109 152223 76110 152224 76109 152224 76066 152224 76144 152225 76111 152225 76145 152225 76123 152226 76160 152226 76120 152226 76158 152227 76112 152227 76113 152227 76114 152228 76201 152228 76122 152228 76202 152229 76180 152229 76203 152229 76203 152230 76180 152230 76115 152230 76203 152231 76115 152231 76204 152231 76204 152232 76115 152232 76128 152232 76204 152233 76128 152233 76116 152233 76116 152234 76128 152234 76125 152234 76122 152235 76201 152235 76117 152235 76117 152236 76201 152236 76118 152236 76117 152237 76118 152237 76120 152237 76119 152238 76113 152238 76199 152238 76120 152239 76160 152239 76117 152239 76117 152240 76160 152240 76121 152240 76117 152241 76121 152241 76122 152241 76118 152242 76206 152242 76120 152242 76120 152243 76206 152243 76126 152243 76120 152244 76126 152244 76123 152244 76123 152245 76126 152245 76127 152245 76123 152246 76127 152246 76161 152246 76161 152247 76127 152247 76124 152247 76161 152248 76124 152248 76164 152248 76164 152249 76124 152249 76129 152249 76164 152250 76129 152250 76188 152250 76206 152251 76125 152251 76126 152251 76126 152252 76125 152252 76128 152252 76126 152253 76128 152253 76127 152253 76127 152254 76128 152254 76115 152254 76127 152255 76115 152255 76124 152255 76124 152256 76115 152256 76180 152256 76124 152257 76180 152257 76129 152257 76136 152258 76046 152258 76130 152258 76130 152259 76046 152259 76131 152259 76130 152260 76131 152260 76155 152260 76155 152261 76131 152261 76132 152261 76155 152262 76132 152262 76133 152262 76133 152263 76132 152263 76134 152263 76133 152264 76134 152264 76139 152264 76153 152265 76135 152265 76130 152265 76130 152266 76135 152266 76061 152266 76130 152267 76061 152267 76136 152267 76141 152268 76054 152268 76137 152268 76137 152269 76054 152269 76138 152269 76137 152270 76138 152270 76052 152270 76134 152271 76140 152271 76139 152271 76139 152272 76140 152272 76047 152272 76139 152273 76047 152273 76141 152273 76141 152274 76047 152274 76142 152274 76141 152275 76142 152275 76054 152275 76052 152276 76050 152276 76137 152276 76137 152277 76050 152277 76144 152277 76137 152278 76144 152278 76143 152278 76143 152279 76144 152279 76145 152279 76143 152280 76145 152280 76146 152280 76113 152281 76119 152281 76158 152281 76158 152282 76119 152282 76148 152282 76158 152283 76148 152283 76147 152283 76147 152284 76148 152284 76159 152284 76147 152285 76159 152285 76149 152285 76149 152286 76159 152286 76150 152286 76149 152287 76150 152287 76157 152287 76157 152288 76150 152288 76162 152288 76157 152289 76162 152289 76156 152289 76156 152290 76162 152290 76151 152290 76156 152291 76151 152291 76152 152291 76152 152292 76151 152292 76163 152292 76152 152293 76163 152293 76154 152293 76154 152294 76163 152294 76187 152294 76154 152295 76187 152295 76153 152295 76153 152296 76130 152296 76154 152296 76154 152297 76130 152297 76155 152297 76154 152298 76155 152298 76152 152298 76152 152299 76155 152299 76133 152299 76152 152300 76133 152300 76156 152300 76156 152301 76133 152301 76139 152301 76156 152302 76139 152302 76157 152302 76157 152303 76139 152303 76141 152303 76157 152304 76141 152304 76149 152304 76149 152305 76141 152305 76137 152305 76149 152306 76137 152306 76147 152306 76147 152307 76137 152307 76143 152307 76147 152308 76143 152308 76158 152308 76158 152309 76143 152309 76146 152309 76158 152310 76146 152310 76112 152310 76199 152311 76114 152311 76119 152311 76119 152312 76114 152312 76122 152312 76119 152313 76122 152313 76148 152313 76148 152314 76122 152314 76121 152314 76148 152315 76121 152315 76159 152315 76159 152316 76121 152316 76160 152316 76159 152317 76160 152317 76150 152317 76150 152318 76160 152318 76123 152318 76150 152319 76123 152319 76162 152319 76162 152320 76123 152320 76161 152320 76162 152321 76161 152321 76151 152321 76151 152322 76161 152322 76164 152322 76151 152323 76164 152323 76163 152323 76163 152324 76164 152324 76188 152324 76163 152325 76188 152325 76187 152325 76165 152326 76173 152326 76174 152326 76200 152327 76199 152327 76113 152327 76167 152328 76209 152328 76208 152328 76175 152329 76166 152329 76165 152329 76165 152330 76166 152330 76167 152330 76167 152331 76208 152331 76165 152331 76165 152332 76208 152332 76168 152332 76165 152333 76168 152333 76173 152333 76173 152334 76168 152334 76207 152334 76173 152335 76207 152335 76200 152335 76169 152336 76170 152336 76172 152336 76172 152337 76170 152337 76175 152337 76058 152338 76169 152338 76171 152338 76171 152339 76169 152339 76172 152339 76171 152340 76172 152340 76176 152340 76200 152341 76113 152341 76173 152341 76173 152342 76113 152342 76112 152342 76173 152343 76112 152343 76174 152343 76174 152344 76112 152344 76146 152344 76174 152345 76146 152345 76145 152345 76175 152346 76165 152346 76172 152346 76172 152347 76165 152347 76174 152347 76172 152348 76174 152348 76176 152348 76176 152349 76174 152349 76145 152349 76176 152350 76145 152350 76111 152350 76135 152351 76153 152351 76190 152351 76185 152352 76177 152352 76178 152352 76202 152353 76179 152353 76180 152353 76180 152354 76179 152354 76184 152354 76065 152355 76181 152355 76194 152355 76194 152356 76181 152356 76177 152356 76192 152357 76182 152357 76191 152357 76191 152358 76182 152358 76184 152358 76177 152359 76181 152359 76178 152359 76178 152360 76181 152360 76183 152360 76178 152361 76183 152361 76186 152361 76179 152362 76185 152362 76184 152362 76184 152363 76185 152363 76178 152363 76184 152364 76178 152364 76191 152364 76191 152365 76178 152365 76186 152365 76153 152366 76187 152366 76182 152366 76182 152367 76187 152367 76188 152367 76182 152368 76188 152368 76184 152368 76184 152369 76188 152369 76129 152369 76184 152370 76129 152370 76180 152370 76193 152371 76189 152371 76190 152371 76190 152372 76189 152372 76061 152372 76190 152373 76061 152373 76135 152373 76186 152374 76066 152374 76191 152374 76191 152375 76066 152375 76109 152375 76191 152376 76109 152376 76192 152376 76192 152377 76109 152377 76091 152377 76192 152378 76091 152378 76096 152378 76153 152379 76182 152379 76190 152379 76190 152380 76182 152380 76192 152380 76190 152381 76192 152381 76193 152381 76193 152382 76192 152382 76096 152382 76193 152383 76096 152383 76059 152383 76195 152384 76065 152384 76194 152384 76195 152385 76098 152385 76067 152385 76067 152386 76196 152386 76195 152386 76195 152387 76196 152387 76064 152387 76195 152388 76064 152388 76065 152388 76097 152389 76197 152389 76195 152389 76195 152390 76197 152390 76072 152390 76195 152391 76072 152391 76098 152391 76198 152392 76199 152392 76200 152392 76118 152393 76201 152393 76198 152393 76198 152394 76201 152394 76114 152394 76198 152395 76114 152395 76199 152395 76202 152396 76203 152396 76198 152396 76198 152397 76203 152397 76204 152397 76198 152398 76204 152398 76116 152398 76116 152399 76205 152399 76198 152399 76198 152400 76205 152400 76206 152400 76198 152401 76206 152401 76118 152401 76202 152402 76198 152402 76179 152402 76179 152403 76198 152403 76200 152403 76179 152404 76200 152404 76185 152404 76185 152405 76200 152405 76207 152405 76185 152406 76207 152406 76177 152406 76177 152407 76207 152407 76168 152407 76177 152408 76168 152408 76194 152408 76194 152409 76168 152409 76208 152409 76194 152410 76208 152410 76195 152410 76195 152411 76208 152411 76209 152411 76195 152412 76209 152412 76097 152412 76210 152413 76029 152413 76211 152413 76211 152414 76029 152414 76216 152414 76211 152415 76216 152415 76079 152415 76079 152416 76216 152416 76217 152416 76080 152417 76081 152417 76212 152417 76212 152418 76081 152418 76083 152418 76212 152419 76083 152419 76217 152419 76217 152420 76083 152420 76213 152420 76217 152421 76213 152421 76079 152421 76080 152422 76212 152422 76214 152422 76214 152423 76212 152423 76219 152423 76214 152424 76219 152424 76215 152424 76215 152425 76219 152425 76222 152425 76215 152426 76222 152426 76059 152426 76029 152427 76250 152427 76216 152427 76216 152428 76250 152428 76249 152428 76216 152429 76249 152429 76217 152429 76217 152430 76249 152430 76218 152430 76217 152431 76218 152431 76212 152431 76212 152432 76218 152432 76220 152432 76212 152433 76220 152433 76219 152433 76219 152434 76220 152434 76221 152434 76219 152435 76221 152435 76222 152435 76222 152436 76221 152436 76223 152436 76332 152437 76236 152437 76333 152437 76333 152438 76236 152438 76230 152438 76333 152439 76230 152439 76224 152439 76224 152440 76230 152440 76225 152440 76224 152441 76225 152441 76329 152441 76329 152442 76225 152442 76226 152442 76226 152443 76225 152443 76227 152443 76226 152444 76227 152444 76283 152444 76230 152445 76236 152445 76247 152445 76038 152446 76227 152446 76228 152446 76228 152447 76227 152447 76225 152447 76228 152448 76225 152448 76436 152448 76436 152449 76225 152449 76230 152449 76436 152450 76230 152450 76229 152450 76229 152451 76230 152451 76247 152451 76254 152452 76303 152452 76252 152452 76252 152453 76303 152453 76278 152453 76252 152454 76278 152454 76231 152454 76278 152455 76279 152455 76231 152455 76231 152456 76279 152456 76232 152456 76231 152457 76232 152457 76251 152457 76251 152458 76232 152458 76281 152458 76251 152459 76281 152459 76248 152459 76248 152460 76281 152460 76275 152460 76248 152461 76275 152461 76244 152461 76244 152462 76275 152462 76274 152462 76244 152463 76274 152463 76234 152463 76233 152464 76260 152464 76272 152464 76272 152465 76260 152465 76037 152465 76272 152466 76037 152466 76234 152466 76234 152467 76037 152467 76235 152467 76234 152468 76235 152468 76244 152468 76237 152469 76247 152469 76236 152469 76236 152470 76270 152470 76237 152470 76237 152471 76270 152471 76240 152471 76237 152472 76240 152472 76241 152472 76264 152473 76238 152473 76266 152473 76266 152474 76238 152474 76259 152474 76266 152475 76259 152475 76239 152475 76239 152476 76259 152476 76241 152476 76239 152477 76241 152477 76268 152477 76268 152478 76241 152478 76240 152478 76258 152479 76030 152479 76241 152479 76241 152480 76030 152480 76242 152480 76241 152481 76242 152481 76237 152481 76242 152482 76243 152482 76237 152482 76237 152483 76243 152483 76031 152483 76237 152484 76031 152484 76247 152484 76235 152485 76223 152485 76244 152485 76244 152486 76223 152486 76221 152486 76244 152487 76221 152487 76248 152487 76031 152488 76245 152488 76247 152488 76247 152489 76245 152489 76246 152489 76247 152490 76246 152490 76229 152490 76229 152491 76246 152491 76032 152491 76229 152492 76032 152492 76436 152492 76221 152493 76220 152493 76248 152493 76248 152494 76220 152494 76218 152494 76248 152495 76218 152495 76251 152495 76218 152496 76249 152496 76251 152496 76251 152497 76249 152497 76250 152497 76251 152498 76250 152498 76231 152498 76231 152499 76250 152499 76253 152499 76231 152500 76253 152500 76252 152500 76252 152501 76253 152501 76028 152501 76252 152502 76028 152502 76254 152502 76254 152503 76028 152503 76256 152503 76254 152504 76256 152504 76255 152504 76255 152505 76256 152505 76257 152505 76255 152506 76257 152506 76238 152506 76238 152507 76257 152507 76258 152507 76238 152508 76258 152508 76259 152508 76259 152509 76258 152509 76241 152509 76260 152510 76233 152510 76261 152510 76260 152511 76261 152511 76040 152511 76040 152512 76261 152512 76227 152512 76040 152513 76227 152513 76038 152513 76283 152514 76227 152514 76286 152514 76286 152515 76227 152515 76261 152515 76286 152516 76261 152516 76262 152516 76233 152517 76291 152517 76261 152517 76261 152518 76291 152518 76288 152518 76261 152519 76288 152519 76262 152519 76303 152520 76254 152520 76263 152520 76263 152521 76254 152521 76255 152521 76263 152522 76255 152522 76264 152522 76264 152523 76255 152523 76238 152523 76326 152524 76264 152524 76265 152524 76265 152525 76264 152525 76266 152525 76265 152526 76266 152526 76267 152526 76267 152527 76266 152527 76239 152527 76267 152528 76239 152528 76325 152528 76325 152529 76239 152529 76268 152529 76325 152530 76268 152530 76323 152530 76323 152531 76268 152531 76240 152531 76323 152532 76240 152532 76269 152532 76269 152533 76240 152533 76330 152533 76330 152534 76240 152534 76270 152534 76330 152535 76270 152535 76331 152535 76331 152536 76270 152536 76236 152536 76331 152537 76236 152537 76332 152537 76291 152538 76233 152538 76271 152538 76271 152539 76233 152539 76272 152539 76271 152540 76272 152540 76273 152540 76273 152541 76272 152541 76234 152541 76273 152542 76234 152542 76379 152542 76379 152543 76234 152543 76274 152543 76379 152544 76274 152544 76381 152544 76381 152545 76274 152545 76275 152545 76381 152546 76275 152546 76382 152546 76382 152547 76275 152547 76276 152547 76276 152548 76275 152548 76387 152548 76387 152549 76275 152549 76281 152549 76387 152550 76281 152550 76277 152550 76303 152551 76305 152551 76278 152551 76278 152552 76305 152552 76390 152552 76278 152553 76390 152553 76279 152553 76390 152554 76389 152554 76279 152554 76279 152555 76389 152555 76280 152555 76279 152556 76280 152556 76232 152556 76232 152557 76280 152557 76282 152557 76232 152558 76282 152558 76281 152558 76281 152559 76282 152559 76385 152559 76281 152560 76385 152560 76277 152560 76300 152561 76361 152561 76301 152561 76361 152562 76300 152562 76374 152562 76295 152563 76287 152563 76293 152563 76328 152564 76283 152564 76286 152564 76284 152565 76285 152565 76295 152565 76295 152566 76285 152566 76328 152566 76328 152567 76286 152567 76295 152567 76295 152568 76286 152568 76262 152568 76295 152569 76262 152569 76287 152569 76287 152570 76262 152570 76288 152570 76287 152571 76288 152571 76291 152571 76294 152572 76290 152572 76289 152572 76289 152573 76290 152573 76284 152573 76291 152574 76384 152574 76287 152574 76287 152575 76384 152575 76292 152575 76287 152576 76292 152576 76293 152576 76293 152577 76292 152577 76409 152577 76293 152578 76409 152578 76296 152578 76316 152579 76294 152579 76299 152579 76299 152580 76294 152580 76289 152580 76299 152581 76289 152581 76300 152581 76284 152582 76295 152582 76289 152582 76289 152583 76295 152583 76293 152583 76289 152584 76293 152584 76300 152584 76300 152585 76293 152585 76296 152585 76300 152586 76296 152586 76374 152586 76297 152587 76316 152587 76298 152587 76298 152588 76316 152588 76299 152588 76298 152589 76299 152589 76420 152589 76420 152590 76299 152590 76300 152590 76420 152591 76300 152591 76419 152591 76419 152592 76300 152592 76301 152592 76263 152593 76264 152593 76326 152593 76326 152594 76435 152594 76263 152594 76263 152595 76435 152595 76302 152595 76263 152596 76302 152596 76303 152596 76303 152597 76302 152597 76304 152597 76303 152598 76304 152598 76305 152598 76314 152599 76309 152599 76318 152599 76412 152600 76306 152600 76307 152600 76412 152601 76307 152601 76349 152601 76315 152602 76308 152602 76309 152602 76309 152603 76308 152603 76410 152603 76309 152604 76410 152604 76318 152604 76318 152605 76410 152605 76347 152605 76318 152606 76347 152606 76310 152606 76316 152607 76311 152607 76294 152607 76294 152608 76311 152608 76312 152608 76294 152609 76312 152609 76290 152609 76290 152610 76312 152610 76313 152610 76357 152611 76313 152611 76314 152611 76314 152612 76313 152612 76312 152612 76314 152613 76312 152613 76309 152613 76309 152614 76312 152614 76311 152614 76309 152615 76311 152615 76315 152615 76315 152616 76311 152616 76316 152616 76315 152617 76316 152617 76297 152617 76350 152618 76307 152618 76317 152618 76317 152619 76307 152619 76306 152619 76317 152620 76306 152620 76345 152620 76357 152621 76314 152621 76356 152621 76356 152622 76314 152622 76318 152622 76356 152623 76318 152623 76319 152623 76319 152624 76318 152624 76310 152624 76319 152625 76310 152625 76321 152625 76321 152626 76310 152626 76320 152626 76321 152627 76320 152627 76352 152627 76330 152628 76339 152628 76269 152628 76269 152629 76339 152629 76324 152629 76269 152630 76324 152630 76323 152630 76334 152631 76322 152631 76324 152631 76323 152632 76324 152632 76325 152632 76325 152633 76324 152633 76322 152633 76325 152634 76322 152634 76267 152634 76351 152635 76326 152635 76327 152635 76327 152636 76326 152636 76265 152636 76327 152637 76265 152637 76267 152637 76283 152638 76328 152638 76226 152638 76226 152639 76328 152639 76342 152639 76226 152640 76342 152640 76329 152640 76329 152641 76342 152641 76341 152641 76330 152642 76331 152642 76339 152642 76339 152643 76331 152643 76332 152643 76339 152644 76332 152644 76340 152644 76340 152645 76332 152645 76333 152645 76340 152646 76333 152646 76341 152646 76341 152647 76333 152647 76224 152647 76341 152648 76224 152648 76329 152648 76334 152649 76338 152649 76353 152649 76353 152650 76338 152650 76335 152650 76353 152651 76335 152651 76354 152651 76354 152652 76335 152652 76336 152652 76354 152653 76336 152653 76355 152653 76355 152654 76336 152654 76337 152654 76355 152655 76337 152655 76358 152655 76358 152656 76337 152656 76343 152656 76358 152657 76343 152657 76359 152657 76359 152658 76343 152658 76285 152658 76359 152659 76285 152659 76284 152659 76334 152660 76324 152660 76338 152660 76338 152661 76324 152661 76339 152661 76338 152662 76339 152662 76335 152662 76335 152663 76339 152663 76340 152663 76335 152664 76340 152664 76336 152664 76336 152665 76340 152665 76341 152665 76336 152666 76341 152666 76337 152666 76337 152667 76341 152667 76342 152667 76337 152668 76342 152668 76343 152668 76343 152669 76342 152669 76328 152669 76343 152670 76328 152670 76285 152670 76344 152671 76350 152671 76431 152671 76431 152672 76350 152672 76317 152672 76431 152673 76317 152673 76423 152673 76423 152674 76317 152674 76345 152674 76423 152675 76345 152675 76346 152675 76347 152676 76348 152676 76310 152676 76310 152677 76348 152677 76349 152677 76310 152678 76349 152678 76320 152678 76320 152679 76349 152679 76307 152679 76320 152680 76307 152680 76352 152680 76352 152681 76307 152681 76350 152681 76352 152682 76350 152682 76327 152682 76327 152683 76350 152683 76344 152683 76327 152684 76344 152684 76351 152684 76267 152685 76322 152685 76327 152685 76327 152686 76322 152686 76334 152686 76327 152687 76334 152687 76352 152687 76352 152688 76334 152688 76353 152688 76352 152689 76353 152689 76321 152689 76321 152690 76353 152690 76354 152690 76321 152691 76354 152691 76319 152691 76319 152692 76354 152692 76355 152692 76319 152693 76355 152693 76356 152693 76356 152694 76355 152694 76358 152694 76356 152695 76358 152695 76357 152695 76357 152696 76358 152696 76359 152696 76357 152697 76359 152697 76313 152697 76313 152698 76359 152698 76284 152698 76313 152699 76284 152699 76290 152699 76390 152700 76305 152700 76391 152700 76370 152701 76364 152701 76368 152701 76403 152702 76428 152702 76427 152702 76413 152703 76418 152703 76375 152703 76375 152704 76418 152704 76360 152704 76375 152705 76360 152705 76376 152705 76376 152706 76360 152706 76301 152706 76376 152707 76301 152707 76361 152707 76405 152708 76427 152708 76415 152708 76404 152709 76414 152709 76362 152709 76362 152710 76414 152710 76416 152710 76362 152711 76416 152711 76365 152711 76365 152712 76416 152712 76363 152712 76365 152713 76363 152713 76368 152713 76368 152714 76364 152714 76365 152714 76365 152715 76364 152715 76366 152715 76365 152716 76366 152716 76362 152716 76363 152717 76367 152717 76368 152717 76368 152718 76367 152718 76369 152718 76368 152719 76369 152719 76370 152719 76370 152720 76369 152720 76371 152720 76370 152721 76371 152721 76372 152721 76372 152722 76371 152722 76377 152722 76372 152723 76377 152723 76373 152723 76373 152724 76377 152724 76374 152724 76373 152725 76374 152725 76296 152725 76367 152726 76413 152726 76369 152726 76369 152727 76413 152727 76375 152727 76369 152728 76375 152728 76371 152728 76371 152729 76375 152729 76376 152729 76371 152730 76376 152730 76377 152730 76377 152731 76376 152731 76361 152731 76377 152732 76361 152732 76374 152732 76271 152733 76273 152733 76378 152733 76378 152734 76273 152734 76379 152734 76378 152735 76379 152735 76380 152735 76380 152736 76379 152736 76381 152736 76380 152737 76381 152737 76399 152737 76399 152738 76381 152738 76382 152738 76399 152739 76382 152739 76383 152739 76292 152740 76384 152740 76378 152740 76378 152741 76384 152741 76291 152741 76378 152742 76291 152742 76271 152742 76388 152743 76385 152743 76386 152743 76386 152744 76385 152744 76282 152744 76386 152745 76282 152745 76280 152745 76382 152746 76276 152746 76383 152746 76383 152747 76276 152747 76387 152747 76383 152748 76387 152748 76388 152748 76388 152749 76387 152749 76277 152749 76388 152750 76277 152750 76385 152750 76280 152751 76389 152751 76386 152751 76386 152752 76389 152752 76390 152752 76386 152753 76390 152753 76402 152753 76402 152754 76390 152754 76391 152754 76402 152755 76391 152755 76432 152755 76427 152756 76405 152756 76403 152756 76403 152757 76405 152757 76392 152757 76403 152758 76392 152758 76394 152758 76394 152759 76392 152759 76393 152759 76394 152760 76393 152760 76401 152760 76401 152761 76393 152761 76406 152761 76401 152762 76406 152762 76400 152762 76400 152763 76406 152763 76407 152763 76400 152764 76407 152764 76395 152764 76395 152765 76407 152765 76408 152765 76395 152766 76408 152766 76398 152766 76398 152767 76408 152767 76397 152767 76398 152768 76397 152768 76396 152768 76396 152769 76397 152769 76409 152769 76396 152770 76409 152770 76292 152770 76292 152771 76378 152771 76396 152771 76396 152772 76378 152772 76380 152772 76396 152773 76380 152773 76398 152773 76398 152774 76380 152774 76399 152774 76398 152775 76399 152775 76395 152775 76395 152776 76399 152776 76383 152776 76395 152777 76383 152777 76400 152777 76400 152778 76383 152778 76388 152778 76400 152779 76388 152779 76401 152779 76401 152780 76388 152780 76386 152780 76401 152781 76386 152781 76394 152781 76394 152782 76386 152782 76402 152782 76394 152783 76402 152783 76403 152783 76403 152784 76402 152784 76432 152784 76403 152785 76432 152785 76428 152785 76415 152786 76404 152786 76405 152786 76405 152787 76404 152787 76362 152787 76405 152788 76362 152788 76392 152788 76392 152789 76362 152789 76366 152789 76392 152790 76366 152790 76393 152790 76393 152791 76366 152791 76364 152791 76393 152792 76364 152792 76406 152792 76406 152793 76364 152793 76370 152793 76406 152794 76370 152794 76407 152794 76407 152795 76370 152795 76372 152795 76407 152796 76372 152796 76408 152796 76408 152797 76372 152797 76373 152797 76408 152798 76373 152798 76397 152798 76397 152799 76373 152799 76296 152799 76397 152800 76296 152800 76409 152800 76417 152801 76415 152801 76426 152801 76411 152802 76297 152802 76298 152802 76315 152803 76297 152803 76308 152803 76308 152804 76297 152804 76411 152804 76308 152805 76411 152805 76410 152805 76410 152806 76411 152806 76347 152806 76345 152807 76306 152807 76411 152807 76411 152808 76306 152808 76412 152808 76412 152809 76349 152809 76411 152809 76411 152810 76349 152810 76348 152810 76411 152811 76348 152811 76347 152811 76413 152812 76367 152812 76417 152812 76417 152813 76367 152813 76363 152813 76404 152814 76415 152814 76414 152814 76414 152815 76415 152815 76417 152815 76414 152816 76417 152816 76416 152816 76416 152817 76417 152817 76363 152817 76301 152818 76360 152818 76417 152818 76417 152819 76360 152819 76418 152819 76417 152820 76418 152820 76413 152820 76301 152821 76417 152821 76419 152821 76419 152822 76417 152822 76426 152822 76419 152823 76426 152823 76420 152823 76420 152824 76426 152824 76425 152824 76420 152825 76425 152825 76298 152825 76298 152826 76425 152826 76421 152826 76298 152827 76421 152827 76411 152827 76411 152828 76421 152828 76346 152828 76411 152829 76346 152829 76345 152829 76391 152830 76305 152830 76304 152830 76428 152831 76432 152831 76433 152831 76351 152832 76344 152832 76422 152832 76431 152833 76423 152833 76424 152833 76423 152834 76346 152834 76424 152834 76424 152835 76346 152835 76421 152835 76424 152836 76421 152836 76430 152836 76430 152837 76421 152837 76425 152837 76430 152838 76425 152838 76429 152838 76429 152839 76425 152839 76426 152839 76429 152840 76426 152840 76427 152840 76427 152841 76426 152841 76415 152841 76427 152842 76428 152842 76429 152842 76429 152843 76428 152843 76433 152843 76429 152844 76433 152844 76430 152844 76430 152845 76433 152845 76434 152845 76430 152846 76434 152846 76424 152846 76424 152847 76434 152847 76422 152847 76424 152848 76422 152848 76431 152848 76431 152849 76422 152849 76344 152849 76432 152850 76391 152850 76433 152850 76433 152851 76391 152851 76304 152851 76433 152852 76304 152852 76434 152852 76434 152853 76304 152853 76302 152853 76434 152854 76302 152854 76422 152854 76422 152855 76302 152855 76435 152855 76422 152856 76435 152856 76351 152856 76351 152857 76435 152857 76326 152857 76436 152858 76032 152858 76045 152858 76436 152859 76045 152859 76039 152859 76045 152860 76437 152860 76039 152860 76039 152861 76437 152861 76060 152861 76039 152862 76060 152862 76438 152862 76438 152863 76060 152863 76235 152863 76235 152864 76060 152864 76222 152864 76235 152865 76222 152865 76223 152865 76055 152866 76258 152866 76056 152866 76056 152867 76258 152867 76257 152867 76056 152868 76257 152868 76057 152868 76057 152869 76257 152869 76256 152869 76057 152870 76256 152870 76041 152870 76041 152871 76256 152871 76028 152871 76439 152872 76649 152872 76630 152872 76630 152873 76649 152873 76697 152873 76630 152874 76697 152874 76440 152874 76444 152875 76441 152875 76452 152875 76452 152876 76441 152876 76653 152876 76452 152877 76653 152877 76442 152877 76442 152878 76653 152878 76657 152878 76442 152879 76657 152879 76443 152879 76443 152880 76657 152880 76656 152880 76443 152881 76656 152881 76439 152881 76439 152882 76656 152882 76655 152882 76439 152883 76655 152883 76649 152883 76444 152884 76452 152884 76650 152884 76650 152885 76452 152885 76445 152885 76650 152886 76445 152886 76447 152886 76447 152887 76445 152887 76446 152887 76447 152888 76446 152888 76448 152888 76448 152889 76446 152889 76449 152889 76448 152890 76449 152890 76680 152890 76680 152891 76449 152891 76645 152891 76680 152892 76645 152892 76787 152892 76816 152893 76645 152893 76818 152893 76818 152894 76645 152894 76449 152894 76818 152895 76449 152895 76450 152895 76449 152896 76446 152896 76450 152896 76450 152897 76446 152897 76445 152897 76450 152898 76445 152898 76451 152898 76451 152899 76445 152899 76452 152899 76451 152900 76452 152900 76454 152900 76630 152901 76620 152901 76439 152901 76439 152902 76620 152902 76453 152902 76439 152903 76453 152903 76443 152903 76443 152904 76453 152904 76454 152904 76443 152905 76454 152905 76442 152905 76442 152906 76454 152906 76452 152906 76502 152907 76844 152907 76503 152907 76503 152908 76844 152908 76458 152908 76503 152909 76458 152909 76455 152909 76455 152910 76458 152910 76459 152910 76455 152911 76459 152911 76463 152911 76844 152912 76456 152912 76458 152912 76458 152913 76456 152913 76457 152913 76458 152914 76457 152914 76459 152914 76459 152915 76457 152915 76460 152915 76476 152916 76461 152916 76593 152916 76461 152917 76476 152917 76474 152917 76465 152918 76462 152918 76473 152918 76501 152919 76463 152919 76464 152919 76531 152920 76517 152920 76465 152920 76465 152921 76517 152921 76501 152921 76501 152922 76464 152922 76465 152922 76465 152923 76464 152923 76827 152923 76465 152924 76827 152924 76462 152924 76462 152925 76827 152925 76466 152925 76462 152926 76466 152926 76845 152926 76472 152927 76485 152927 76467 152927 76467 152928 76485 152928 76531 152928 76845 152929 76468 152929 76462 152929 76462 152930 76468 152930 76469 152930 76462 152931 76469 152931 76473 152931 76473 152932 76469 152932 76470 152932 76473 152933 76470 152933 76548 152933 76475 152934 76472 152934 76471 152934 76471 152935 76472 152935 76467 152935 76471 152936 76467 152936 76476 152936 76531 152937 76465 152937 76467 152937 76467 152938 76465 152938 76473 152938 76467 152939 76473 152939 76476 152939 76476 152940 76473 152940 76548 152940 76476 152941 76548 152941 76474 152941 76582 152942 76475 152942 76581 152942 76581 152943 76475 152943 76471 152943 76581 152944 76471 152944 76596 152944 76596 152945 76471 152945 76476 152945 76596 152946 76476 152946 76594 152946 76594 152947 76476 152947 76593 152947 76477 152948 76837 152948 76839 152948 76839 152949 76478 152949 76477 152949 76477 152950 76478 152950 76611 152950 76477 152951 76611 152951 76479 152951 76479 152952 76611 152952 76600 152952 76479 152953 76600 152953 76532 152953 76490 152954 76488 152954 76491 152954 76480 152955 76585 152955 76489 152955 76480 152956 76489 152956 76498 152956 76481 152957 76583 152957 76488 152957 76488 152958 76583 152958 76482 152958 76488 152959 76482 152959 76491 152959 76491 152960 76482 152960 76497 152960 76491 152961 76497 152961 76483 152961 76475 152962 76484 152962 76472 152962 76472 152963 76484 152963 76486 152963 76472 152964 76486 152964 76485 152964 76485 152965 76486 152965 76487 152965 76530 152966 76487 152966 76490 152966 76490 152967 76487 152967 76486 152967 76490 152968 76486 152968 76488 152968 76488 152969 76486 152969 76484 152969 76488 152970 76484 152970 76481 152970 76481 152971 76484 152971 76475 152971 76481 152972 76475 152972 76582 152972 76499 152973 76489 152973 76521 152973 76521 152974 76489 152974 76585 152974 76521 152975 76585 152975 76599 152975 76530 152976 76490 152976 76529 152976 76529 152977 76490 152977 76491 152977 76529 152978 76491 152978 76526 152978 76526 152979 76491 152979 76483 152979 76526 152980 76483 152980 76525 152980 76525 152981 76483 152981 76492 152981 76525 152982 76492 152982 76500 152982 76493 152983 76512 152983 76833 152983 76833 152984 76512 152984 76494 152984 76833 152985 76494 152985 76834 152985 76524 152986 76523 152986 76494 152986 76518 152987 76838 152987 76495 152987 76495 152988 76838 152988 76836 152988 76834 152989 76494 152989 76496 152989 76496 152990 76494 152990 76523 152990 76496 152991 76523 152991 76836 152991 76497 152992 76586 152992 76483 152992 76483 152993 76586 152993 76498 152993 76483 152994 76498 152994 76492 152994 76492 152995 76498 152995 76489 152995 76492 152996 76489 152996 76500 152996 76500 152997 76489 152997 76499 152997 76500 152998 76499 152998 76495 152998 76463 152999 76501 152999 76455 152999 76455 153000 76501 153000 76516 153000 76504 153001 76843 153001 76515 153001 76515 153002 76843 153002 76502 153002 76515 153003 76502 153003 76516 153003 76516 153004 76502 153004 76503 153004 76516 153005 76503 153005 76455 153005 76493 153006 76830 153006 76512 153006 76512 153007 76830 153007 76840 153007 76512 153008 76840 153008 76504 153008 76504 153009 76840 153009 76505 153009 76504 153010 76505 153010 76843 153010 76524 153011 76506 153011 76507 153011 76507 153012 76506 153012 76508 153012 76507 153013 76508 153013 76527 153013 76527 153014 76508 153014 76513 153014 76527 153015 76513 153015 76528 153015 76528 153016 76513 153016 76514 153016 76528 153017 76514 153017 76509 153017 76509 153018 76514 153018 76510 153018 76509 153019 76510 153019 76511 153019 76511 153020 76510 153020 76517 153020 76511 153021 76517 153021 76531 153021 76524 153022 76494 153022 76506 153022 76506 153023 76494 153023 76512 153023 76506 153024 76512 153024 76508 153024 76508 153025 76512 153025 76504 153025 76508 153026 76504 153026 76513 153026 76513 153027 76504 153027 76515 153027 76513 153028 76515 153028 76514 153028 76514 153029 76515 153029 76516 153029 76514 153030 76516 153030 76510 153030 76510 153031 76516 153031 76501 153031 76510 153032 76501 153032 76517 153032 76839 153033 76518 153033 76602 153033 76602 153034 76518 153034 76495 153034 76602 153035 76495 153035 76519 153035 76519 153036 76495 153036 76499 153036 76519 153037 76499 153037 76520 153037 76520 153038 76499 153038 76521 153038 76520 153039 76521 153039 76522 153039 76522 153040 76521 153040 76599 153040 76522 153041 76599 153041 76604 153041 76836 153042 76523 153042 76495 153042 76495 153043 76523 153043 76524 153043 76495 153044 76524 153044 76500 153044 76500 153045 76524 153045 76507 153045 76500 153046 76507 153046 76525 153046 76525 153047 76507 153047 76527 153047 76525 153048 76527 153048 76526 153048 76526 153049 76527 153049 76528 153049 76526 153050 76528 153050 76529 153050 76529 153051 76528 153051 76509 153051 76529 153052 76509 153052 76530 153052 76530 153053 76509 153053 76511 153053 76530 153054 76511 153054 76487 153054 76487 153055 76511 153055 76531 153055 76487 153056 76531 153056 76485 153056 76854 153057 76532 153057 76562 153057 76544 153058 76577 153058 76542 153058 76563 153059 76533 153059 76607 153059 76592 153060 76591 153060 76549 153060 76549 153061 76591 153061 76534 153061 76549 153062 76534 153062 76535 153062 76535 153063 76534 153063 76593 153063 76535 153064 76593 153064 76461 153064 76564 153065 76607 153065 76608 153065 76536 153066 76537 153066 76541 153066 76541 153067 76537 153067 76538 153067 76541 153068 76538 153068 76539 153068 76539 153069 76538 153069 76588 153069 76539 153070 76588 153070 76542 153070 76542 153071 76577 153071 76539 153071 76539 153072 76577 153072 76540 153072 76539 153073 76540 153073 76541 153073 76588 153074 76587 153074 76542 153074 76542 153075 76587 153075 76543 153075 76542 153076 76543 153076 76544 153076 76544 153077 76543 153077 76545 153077 76544 153078 76545 153078 76579 153078 76579 153079 76545 153079 76547 153079 76579 153080 76547 153080 76546 153080 76546 153081 76547 153081 76474 153081 76546 153082 76474 153082 76548 153082 76587 153083 76592 153083 76543 153083 76543 153084 76592 153084 76549 153084 76543 153085 76549 153085 76545 153085 76545 153086 76549 153086 76535 153086 76545 153087 76535 153087 76547 153087 76547 153088 76535 153088 76461 153088 76547 153089 76461 153089 76474 153089 76553 153090 76848 153090 76550 153090 76550 153091 76848 153091 76850 153091 76550 153092 76850 153092 76551 153092 76551 153093 76850 153093 76552 153093 76551 153094 76552 153094 76573 153094 76573 153095 76552 153095 76852 153095 76573 153096 76852 153096 76557 153096 76469 153097 76468 153097 76550 153097 76550 153098 76468 153098 76845 153098 76550 153099 76845 153099 76553 153099 76559 153100 76857 153100 76554 153100 76554 153101 76857 153101 76555 153101 76554 153102 76555 153102 76855 153102 76852 153103 76556 153103 76557 153103 76557 153104 76556 153104 76558 153104 76557 153105 76558 153105 76559 153105 76559 153106 76558 153106 76560 153106 76559 153107 76560 153107 76857 153107 76855 153108 76561 153108 76554 153108 76554 153109 76561 153109 76854 153109 76554 153110 76854 153110 76575 153110 76575 153111 76854 153111 76562 153111 76575 153112 76562 153112 76601 153112 76607 153113 76564 153113 76563 153113 76563 153114 76564 153114 76565 153114 76563 153115 76565 153115 76574 153115 76574 153116 76565 153116 76576 153116 76574 153117 76576 153117 76566 153117 76566 153118 76576 153118 76578 153118 76566 153119 76578 153119 76568 153119 76568 153120 76578 153120 76567 153120 76568 153121 76567 153121 76569 153121 76569 153122 76567 153122 76570 153122 76569 153123 76570 153123 76571 153123 76571 153124 76570 153124 76580 153124 76571 153125 76580 153125 76572 153125 76572 153126 76580 153126 76470 153126 76572 153127 76470 153127 76469 153127 76469 153128 76550 153128 76572 153128 76572 153129 76550 153129 76551 153129 76572 153130 76551 153130 76571 153130 76571 153131 76551 153131 76573 153131 76571 153132 76573 153132 76569 153132 76569 153133 76573 153133 76557 153133 76569 153134 76557 153134 76568 153134 76568 153135 76557 153135 76559 153135 76568 153136 76559 153136 76566 153136 76566 153137 76559 153137 76554 153137 76566 153138 76554 153138 76574 153138 76574 153139 76554 153139 76575 153139 76574 153140 76575 153140 76563 153140 76563 153141 76575 153141 76601 153141 76563 153142 76601 153142 76533 153142 76608 153143 76536 153143 76564 153143 76564 153144 76536 153144 76541 153144 76564 153145 76541 153145 76565 153145 76565 153146 76541 153146 76540 153146 76565 153147 76540 153147 76576 153147 76576 153148 76540 153148 76577 153148 76576 153149 76577 153149 76578 153149 76578 153150 76577 153150 76544 153150 76578 153151 76544 153151 76567 153151 76567 153152 76544 153152 76579 153152 76567 153153 76579 153153 76570 153153 76570 153154 76579 153154 76546 153154 76570 153155 76546 153155 76580 153155 76580 153156 76546 153156 76548 153156 76580 153157 76548 153157 76470 153157 76590 153158 76608 153158 76595 153158 76584 153159 76582 153159 76581 153159 76481 153160 76582 153160 76583 153160 76583 153161 76582 153161 76584 153161 76583 153162 76584 153162 76482 153162 76482 153163 76584 153163 76497 153163 76599 153164 76585 153164 76584 153164 76584 153165 76585 153165 76480 153165 76480 153166 76498 153166 76584 153166 76584 153167 76498 153167 76586 153167 76584 153168 76586 153168 76497 153168 76592 153169 76587 153169 76590 153169 76590 153170 76587 153170 76588 153170 76589 153171 76608 153171 76537 153171 76537 153172 76608 153172 76590 153172 76537 153173 76590 153173 76538 153173 76538 153174 76590 153174 76588 153174 76593 153175 76534 153175 76590 153175 76590 153176 76534 153176 76591 153176 76590 153177 76591 153177 76592 153177 76593 153178 76590 153178 76594 153178 76594 153179 76590 153179 76595 153179 76594 153180 76595 153180 76596 153180 76596 153181 76595 153181 76597 153181 76596 153182 76597 153182 76581 153182 76581 153183 76597 153183 76598 153183 76581 153184 76598 153184 76584 153184 76584 153185 76598 153185 76604 153185 76584 153186 76604 153186 76599 153186 76562 153187 76532 153187 76600 153187 76533 153188 76601 153188 76610 153188 76602 153189 76519 153189 76612 153189 76520 153190 76522 153190 76603 153190 76522 153191 76604 153191 76603 153191 76603 153192 76604 153192 76598 153192 76603 153193 76598 153193 76605 153193 76605 153194 76598 153194 76597 153194 76605 153195 76597 153195 76606 153195 76606 153196 76597 153196 76595 153196 76606 153197 76595 153197 76607 153197 76607 153198 76595 153198 76608 153198 76607 153199 76533 153199 76606 153199 76606 153200 76533 153200 76610 153200 76606 153201 76610 153201 76605 153201 76605 153202 76610 153202 76609 153202 76605 153203 76609 153203 76603 153203 76603 153204 76609 153204 76612 153204 76603 153205 76612 153205 76520 153205 76520 153206 76612 153206 76519 153206 76601 153207 76562 153207 76610 153207 76610 153208 76562 153208 76600 153208 76610 153209 76600 153209 76609 153209 76609 153210 76600 153210 76611 153210 76609 153211 76611 153211 76612 153211 76612 153212 76611 153212 76478 153212 76612 153213 76478 153213 76602 153213 76602 153214 76478 153214 76839 153214 76613 153215 76625 153215 76632 153215 76613 153216 76632 153216 76614 153216 76632 153217 76615 153217 76614 153217 76614 153218 76615 153218 76616 153218 76614 153219 76616 153219 76617 153219 76617 153220 76616 153220 76804 153220 76804 153221 76616 153221 76645 153221 76804 153222 76645 153222 76816 153222 76643 153223 76824 153223 76644 153223 76644 153224 76824 153224 76822 153224 76644 153225 76822 153225 76619 153225 76619 153226 76822 153226 76618 153226 76619 153227 76618 153227 76631 153227 76631 153228 76618 153228 76821 153228 76631 153229 76821 153229 76630 153229 76630 153230 76821 153230 76620 153230 76824 153231 76643 153231 76810 153231 76810 153232 76643 153232 76621 153232 76810 153233 76621 153233 76623 153233 76621 153234 76622 153234 76623 153234 76623 153235 76622 153235 76639 153235 76623 153236 76639 153236 76813 153236 76813 153237 76639 153237 76638 153237 76813 153238 76638 153238 76624 153238 76624 153239 76638 153239 76627 153239 76624 153240 76627 153240 76815 153240 76632 153241 76625 153241 76634 153241 76634 153242 76625 153242 76812 153242 76634 153243 76812 153243 76635 153243 76635 153244 76812 153244 76815 153244 76635 153245 76815 153245 76626 153245 76626 153246 76815 153246 76627 153246 76617 153247 76804 153247 76628 153247 76460 153248 76457 153248 76456 153248 76456 153249 76613 153249 76460 153249 76460 153250 76613 153250 76614 153250 76460 153251 76614 153251 76629 153251 76629 153252 76614 153252 76617 153252 76629 153253 76617 153253 76825 153253 76825 153254 76617 153254 76628 153254 76630 153255 76440 153255 76631 153255 76631 153256 76440 153256 76762 153256 76780 153257 76632 153257 76633 153257 76633 153258 76632 153258 76634 153258 76633 153259 76634 153259 76724 153259 76724 153260 76634 153260 76635 153260 76724 153261 76635 153261 76726 153261 76726 153262 76635 153262 76626 153262 76726 153263 76626 153263 76636 153263 76636 153264 76626 153264 76627 153264 76636 153265 76627 153265 76730 153265 76730 153266 76627 153266 76637 153266 76637 153267 76627 153267 76732 153267 76732 153268 76627 153268 76638 153268 76732 153269 76638 153269 76733 153269 76643 153270 76769 153270 76621 153270 76621 153271 76769 153271 76736 153271 76621 153272 76736 153272 76622 153272 76736 153273 76734 153273 76622 153273 76622 153274 76734 153274 76640 153274 76622 153275 76640 153275 76639 153275 76639 153276 76640 153276 76641 153276 76639 153277 76641 153277 76638 153277 76638 153278 76641 153278 76729 153278 76638 153279 76729 153279 76733 153279 76769 153280 76643 153280 76642 153280 76642 153281 76643 153281 76644 153281 76642 153282 76644 153282 76763 153282 76763 153283 76644 153283 76619 153283 76763 153284 76619 153284 76762 153284 76762 153285 76619 153285 76631 153285 76787 153286 76645 153286 76616 153286 76787 153287 76616 153287 76786 153287 76786 153288 76616 153288 76615 153288 76786 153289 76615 153289 76646 153289 76646 153290 76615 153290 76632 153290 76646 153291 76632 153291 76780 153291 76647 153292 76755 153292 76648 153292 76649 153293 76655 153293 76654 153293 76444 153294 76650 153294 76651 153294 76651 153295 76650 153295 76447 153295 76651 153296 76447 153296 76689 153296 76444 153297 76651 153297 76441 153297 76441 153298 76651 153298 76652 153298 76441 153299 76652 153299 76653 153299 76653 153300 76652 153300 76686 153300 76653 153301 76686 153301 76657 153301 76654 153302 76655 153302 76686 153302 76686 153303 76655 153303 76656 153303 76686 153304 76656 153304 76657 153304 76697 153305 76649 153305 76658 153305 76762 153306 76440 153306 76760 153306 76760 153307 76440 153307 76659 153307 76678 153308 76647 153308 76660 153308 76668 153309 76670 153309 76661 153309 76661 153310 76670 153310 76671 153310 76661 153311 76671 153311 76662 153311 76662 153312 76671 153312 76673 153312 76662 153313 76673 153313 76771 153313 76771 153314 76673 153314 76663 153314 76666 153315 76664 153315 76774 153315 76701 153316 76703 153316 76672 153316 76672 153317 76703 153317 76665 153317 76672 153318 76665 153318 76666 153318 76666 153319 76665 153319 76781 153319 76666 153320 76781 153320 76664 153320 76676 153321 76670 153321 76667 153321 76667 153322 76670 153322 76668 153322 76667 153323 76668 153323 76669 153323 76676 153324 76701 153324 76670 153324 76670 153325 76701 153325 76672 153325 76670 153326 76672 153326 76671 153326 76671 153327 76672 153327 76666 153327 76671 153328 76666 153328 76673 153328 76673 153329 76666 153329 76774 153329 76673 153330 76774 153330 76663 153330 76674 153331 76675 153331 76676 153331 76676 153332 76675 153332 76700 153332 76676 153333 76700 153333 76701 153333 76695 153334 76678 153334 76677 153334 76677 153335 76678 153335 76660 153335 76677 153336 76660 153336 76679 153336 76679 153337 76660 153337 76693 153337 76447 153338 76448 153338 76689 153338 76689 153339 76448 153339 76680 153339 76689 153340 76680 153340 76690 153340 76690 153341 76680 153341 76787 153341 76690 153342 76787 153342 76692 153342 76658 153343 76687 153343 76698 153343 76698 153344 76687 153344 76681 153344 76698 153345 76681 153345 76699 153345 76699 153346 76681 153346 76688 153346 76699 153347 76688 153347 76702 153347 76702 153348 76688 153348 76682 153348 76702 153349 76682 153349 76683 153349 76683 153350 76682 153350 76691 153350 76683 153351 76691 153351 76684 153351 76684 153352 76691 153352 76685 153352 76684 153353 76685 153353 76782 153353 76649 153354 76654 153354 76658 153354 76658 153355 76654 153355 76686 153355 76658 153356 76686 153356 76687 153356 76687 153357 76686 153357 76652 153357 76687 153358 76652 153358 76681 153358 76681 153359 76652 153359 76651 153359 76681 153360 76651 153360 76688 153360 76688 153361 76651 153361 76689 153361 76688 153362 76689 153362 76682 153362 76682 153363 76689 153363 76690 153363 76682 153364 76690 153364 76691 153364 76691 153365 76690 153365 76692 153365 76691 153366 76692 153366 76685 153366 76647 153367 76648 153367 76660 153367 76660 153368 76648 153368 76756 153368 76660 153369 76756 153369 76693 153369 76693 153370 76756 153370 76694 153370 76693 153371 76694 153371 76696 153371 76669 153372 76695 153372 76667 153372 76667 153373 76695 153373 76677 153373 76667 153374 76677 153374 76676 153374 76676 153375 76677 153375 76679 153375 76676 153376 76679 153376 76674 153376 76674 153377 76679 153377 76693 153377 76674 153378 76693 153378 76659 153378 76659 153379 76693 153379 76696 153379 76659 153380 76696 153380 76760 153380 76440 153381 76697 153381 76659 153381 76659 153382 76697 153382 76658 153382 76659 153383 76658 153383 76674 153383 76674 153384 76658 153384 76698 153384 76674 153385 76698 153385 76675 153385 76675 153386 76698 153386 76699 153386 76675 153387 76699 153387 76700 153387 76700 153388 76699 153388 76702 153388 76700 153389 76702 153389 76701 153389 76701 153390 76702 153390 76683 153390 76701 153391 76683 153391 76703 153391 76703 153392 76683 153392 76684 153392 76703 153393 76684 153393 76665 153393 76665 153394 76684 153394 76782 153394 76665 153395 76782 153395 76781 153395 76736 153396 76769 153396 76766 153396 76714 153397 76711 153397 76704 153397 76705 153398 76706 153398 76708 153398 76791 153399 76790 153399 76712 153399 76770 153400 76723 153400 76792 153400 76792 153401 76723 153401 76722 153401 76792 153402 76722 153402 76794 153402 76794 153403 76722 153403 76719 153403 76794 153404 76719 153404 76795 153404 76795 153405 76719 153405 76707 153405 76712 153406 76790 153406 76710 153406 76710 153407 76790 153407 76796 153407 76710 153408 76796 153408 76704 153408 76737 153409 76708 153409 76709 153409 76704 153410 76711 153410 76710 153410 76710 153411 76711 153411 76751 153411 76710 153412 76751 153412 76712 153412 76796 153413 76713 153413 76704 153413 76704 153414 76713 153414 76718 153414 76704 153415 76718 153415 76714 153415 76714 153416 76718 153416 76720 153416 76714 153417 76720 153417 76715 153417 76715 153418 76720 153418 76721 153418 76715 153419 76721 153419 76716 153419 76716 153420 76721 153420 76717 153420 76716 153421 76717 153421 76778 153421 76713 153422 76707 153422 76718 153422 76718 153423 76707 153423 76719 153423 76718 153424 76719 153424 76720 153424 76720 153425 76719 153425 76722 153425 76720 153426 76722 153426 76721 153426 76721 153427 76722 153427 76723 153427 76721 153428 76723 153428 76717 153428 76633 153429 76724 153429 76725 153429 76725 153430 76724 153430 76726 153430 76725 153431 76726 153431 76727 153431 76727 153432 76726 153432 76636 153432 76727 153433 76636 153433 76748 153433 76748 153434 76636 153434 76730 153434 76748 153435 76730 153435 76731 153435 76777 153436 76728 153436 76725 153436 76725 153437 76728 153437 76780 153437 76725 153438 76780 153438 76633 153438 76749 153439 76729 153439 76735 153439 76735 153440 76729 153440 76641 153440 76735 153441 76641 153441 76640 153441 76730 153442 76637 153442 76731 153442 76731 153443 76637 153443 76732 153443 76731 153444 76732 153444 76749 153444 76749 153445 76732 153445 76733 153445 76749 153446 76733 153446 76729 153446 76640 153447 76734 153447 76735 153447 76735 153448 76734 153448 76736 153448 76735 153449 76736 153449 76750 153449 76750 153450 76736 153450 76766 153450 76750 153451 76766 153451 76765 153451 76708 153452 76737 153452 76705 153452 76705 153453 76737 153453 76738 153453 76705 153454 76738 153454 76739 153454 76739 153455 76738 153455 76752 153455 76739 153456 76752 153456 76740 153456 76740 153457 76752 153457 76753 153457 76740 153458 76753 153458 76741 153458 76741 153459 76753 153459 76743 153459 76741 153460 76743 153460 76742 153460 76742 153461 76743 153461 76745 153461 76742 153462 76745 153462 76744 153462 76744 153463 76745 153463 76746 153463 76744 153464 76746 153464 76747 153464 76747 153465 76746 153465 76754 153465 76747 153466 76754 153466 76777 153466 76777 153467 76725 153467 76747 153467 76747 153468 76725 153468 76727 153468 76747 153469 76727 153469 76744 153469 76744 153470 76727 153470 76748 153470 76744 153471 76748 153471 76742 153471 76742 153472 76748 153472 76731 153472 76742 153473 76731 153473 76741 153473 76741 153474 76731 153474 76749 153474 76741 153475 76749 153475 76740 153475 76740 153476 76749 153476 76735 153476 76740 153477 76735 153477 76739 153477 76739 153478 76735 153478 76750 153478 76739 153479 76750 153479 76705 153479 76705 153480 76750 153480 76765 153480 76705 153481 76765 153481 76706 153481 76709 153482 76791 153482 76737 153482 76737 153483 76791 153483 76712 153483 76737 153484 76712 153484 76738 153484 76738 153485 76712 153485 76751 153485 76738 153486 76751 153486 76752 153486 76752 153487 76751 153487 76711 153487 76752 153488 76711 153488 76753 153488 76753 153489 76711 153489 76714 153489 76753 153490 76714 153490 76743 153490 76743 153491 76714 153491 76715 153491 76743 153492 76715 153492 76745 153492 76745 153493 76715 153493 76716 153493 76745 153494 76716 153494 76746 153494 76746 153495 76716 153495 76778 153495 76746 153496 76778 153496 76754 153496 76767 153497 76764 153497 76768 153497 76797 153498 76709 153498 76708 153498 76648 153499 76755 153499 76757 153499 76694 153500 76756 153500 76767 153500 76767 153501 76756 153501 76648 153501 76648 153502 76757 153502 76767 153502 76767 153503 76757 153503 76758 153503 76767 153504 76758 153504 76764 153504 76764 153505 76758 153505 76759 153505 76764 153506 76759 153506 76797 153506 76760 153507 76696 153507 76761 153507 76761 153508 76696 153508 76694 153508 76762 153509 76760 153509 76763 153509 76763 153510 76760 153510 76761 153510 76763 153511 76761 153511 76642 153511 76797 153512 76708 153512 76764 153512 76764 153513 76708 153513 76706 153513 76764 153514 76706 153514 76768 153514 76768 153515 76706 153515 76765 153515 76768 153516 76765 153516 76766 153516 76694 153517 76767 153517 76761 153517 76761 153518 76767 153518 76768 153518 76761 153519 76768 153519 76642 153519 76642 153520 76768 153520 76766 153520 76642 153521 76766 153521 76769 153521 76728 153522 76777 153522 76785 153522 76798 153523 76773 153523 76776 153523 76770 153524 76775 153524 76723 153524 76723 153525 76775 153525 76779 153525 76771 153526 76663 153526 76788 153526 76788 153527 76663 153527 76773 153527 76783 153528 76784 153528 76772 153528 76772 153529 76784 153529 76779 153529 76773 153530 76663 153530 76776 153530 76776 153531 76663 153531 76774 153531 76776 153532 76774 153532 76664 153532 76775 153533 76798 153533 76779 153533 76779 153534 76798 153534 76776 153534 76779 153535 76776 153535 76772 153535 76772 153536 76776 153536 76664 153536 76777 153537 76754 153537 76784 153537 76784 153538 76754 153538 76778 153538 76784 153539 76778 153539 76779 153539 76779 153540 76778 153540 76717 153540 76779 153541 76717 153541 76723 153541 76786 153542 76646 153542 76785 153542 76785 153543 76646 153543 76780 153543 76785 153544 76780 153544 76728 153544 76664 153545 76781 153545 76772 153545 76772 153546 76781 153546 76782 153546 76772 153547 76782 153547 76783 153547 76783 153548 76782 153548 76685 153548 76783 153549 76685 153549 76692 153549 76777 153550 76784 153550 76785 153550 76785 153551 76784 153551 76783 153551 76785 153552 76783 153552 76786 153552 76786 153553 76783 153553 76692 153553 76786 153554 76692 153554 76787 153554 76789 153555 76771 153555 76788 153555 76789 153556 76669 153556 76668 153556 76668 153557 76661 153557 76789 153557 76789 153558 76661 153558 76662 153558 76789 153559 76662 153559 76771 153559 76647 153560 76678 153560 76789 153560 76789 153561 76678 153561 76695 153561 76789 153562 76695 153562 76669 153562 76793 153563 76709 153563 76797 153563 76796 153564 76790 153564 76793 153564 76793 153565 76790 153565 76791 153565 76793 153566 76791 153566 76709 153566 76770 153567 76792 153567 76793 153567 76793 153568 76792 153568 76794 153568 76793 153569 76794 153569 76795 153569 76795 153570 76707 153570 76793 153570 76793 153571 76707 153571 76713 153571 76793 153572 76713 153572 76796 153572 76770 153573 76793 153573 76775 153573 76775 153574 76793 153574 76797 153574 76775 153575 76797 153575 76798 153575 76798 153576 76797 153576 76759 153576 76798 153577 76759 153577 76773 153577 76773 153578 76759 153578 76758 153578 76773 153579 76758 153579 76788 153579 76788 153580 76758 153580 76757 153580 76788 153581 76757 153581 76789 153581 76789 153582 76757 153582 76755 153582 76789 153583 76755 153583 76647 153583 76828 153584 76479 153584 76799 153584 76799 153585 76479 153585 76800 153585 76799 153586 76800 153586 76820 153586 76800 153587 76856 153587 76820 153587 76820 153588 76856 153588 76801 153588 76820 153589 76801 153589 76802 153589 76802 153590 76801 153590 76803 153590 76802 153591 76803 153591 76819 153591 76819 153592 76803 153592 76853 153592 76819 153593 76853 153593 76817 153593 76817 153594 76853 153594 76851 153594 76817 153595 76851 153595 76849 153595 76846 153596 76825 153596 76847 153596 76847 153597 76825 153597 76628 153597 76847 153598 76628 153598 76849 153598 76849 153599 76628 153599 76804 153599 76849 153600 76804 153600 76817 153600 76842 153601 76811 153601 76844 153601 76844 153602 76811 153602 76613 153602 76844 153603 76613 153603 76456 153603 76842 153604 76841 153604 76811 153604 76811 153605 76841 153605 76831 153605 76811 153606 76831 153606 76814 153606 76831 153607 76832 153607 76814 153607 76814 153608 76832 153608 76809 153608 76814 153609 76809 153609 76805 153609 76837 153610 76823 153610 76807 153610 76807 153611 76823 153611 76806 153611 76807 153612 76806 153612 76808 153612 76808 153613 76806 153613 76805 153613 76808 153614 76805 153614 76835 153614 76835 153615 76805 153615 76809 153615 76625 153616 76613 153616 76811 153616 76824 153617 76810 153617 76805 153617 76805 153618 76810 153618 76623 153618 76805 153619 76623 153619 76814 153619 76625 153620 76811 153620 76812 153620 76623 153621 76813 153621 76814 153621 76814 153622 76813 153622 76624 153622 76814 153623 76624 153623 76811 153623 76811 153624 76624 153624 76815 153624 76811 153625 76815 153625 76812 153625 76451 153626 76802 153626 76819 153626 76804 153627 76816 153627 76817 153627 76817 153628 76816 153628 76818 153628 76817 153629 76818 153629 76819 153629 76819 153630 76818 153630 76450 153630 76819 153631 76450 153631 76451 153631 76451 153632 76454 153632 76802 153632 76802 153633 76454 153633 76453 153633 76802 153634 76453 153634 76820 153634 76820 153635 76453 153635 76620 153635 76820 153636 76620 153636 76799 153636 76799 153637 76620 153637 76821 153637 76799 153638 76821 153638 76828 153638 76828 153639 76821 153639 76618 153639 76828 153640 76618 153640 76829 153640 76829 153641 76618 153641 76822 153641 76829 153642 76822 153642 76823 153642 76823 153643 76822 153643 76824 153643 76823 153644 76824 153644 76806 153644 76806 153645 76824 153645 76805 153645 76825 153646 76846 153646 76826 153646 76825 153647 76826 153647 76629 153647 76629 153648 76826 153648 76459 153648 76629 153649 76459 153649 76460 153649 76463 153650 76459 153650 76464 153650 76464 153651 76459 153651 76826 153651 76464 153652 76826 153652 76827 153652 76846 153653 76845 153653 76826 153653 76826 153654 76845 153654 76466 153654 76826 153655 76466 153655 76827 153655 76479 153656 76828 153656 76477 153656 76477 153657 76828 153657 76829 153657 76477 153658 76829 153658 76837 153658 76837 153659 76829 153659 76823 153659 76830 153660 76493 153660 76831 153660 76831 153661 76493 153661 76832 153661 76832 153662 76493 153662 76833 153662 76832 153663 76833 153663 76809 153663 76809 153664 76833 153664 76834 153664 76809 153665 76834 153665 76835 153665 76835 153666 76834 153666 76496 153666 76835 153667 76496 153667 76808 153667 76808 153668 76496 153668 76836 153668 76808 153669 76836 153669 76807 153669 76807 153670 76836 153670 76838 153670 76807 153671 76838 153671 76837 153671 76837 153672 76838 153672 76518 153672 76837 153673 76518 153673 76839 153673 76830 153674 76831 153674 76840 153674 76840 153675 76831 153675 76841 153675 76840 153676 76841 153676 76505 153676 76505 153677 76841 153677 76842 153677 76505 153678 76842 153678 76843 153678 76843 153679 76842 153679 76844 153679 76843 153680 76844 153680 76502 153680 76845 153681 76846 153681 76553 153681 76553 153682 76846 153682 76847 153682 76553 153683 76847 153683 76848 153683 76848 153684 76847 153684 76849 153684 76848 153685 76849 153685 76850 153685 76850 153686 76849 153686 76851 153686 76850 153687 76851 153687 76552 153687 76552 153688 76851 153688 76853 153688 76552 153689 76853 153689 76852 153689 76852 153690 76853 153690 76556 153690 76556 153691 76853 153691 76558 153691 76558 153692 76853 153692 76803 153692 76558 153693 76803 153693 76560 153693 76479 153694 76532 153694 76800 153694 76800 153695 76532 153695 76854 153695 76800 153696 76854 153696 76856 153696 76854 153697 76561 153697 76856 153697 76856 153698 76561 153698 76855 153698 76856 153699 76855 153699 76801 153699 76801 153700 76855 153700 76555 153700 76801 153701 76555 153701 76803 153701 76803 153702 76555 153702 76857 153702 76803 153703 76857 153703 76560 153703 76948 153704 76858 153704 77227 153704 77227 153705 77257 153705 76948 153705 76948 153706 77257 153706 77258 153706 76948 153707 77258 153707 76859 153707 76859 153708 77258 153708 76860 153708 76859 153709 76860 153709 76861 153709 76861 153710 76860 153710 77254 153710 76861 153711 77254 153711 76862 153711 76862 153712 77254 153712 76863 153712 76862 153713 76863 153713 76953 153713 76953 153714 76863 153714 76952 153714 76952 153715 76863 153715 76865 153715 76952 153716 76865 153716 76864 153716 76865 153717 76866 153717 76864 153717 76864 153718 76866 153718 77251 153718 76864 153719 77251 153719 76867 153719 76867 153720 77251 153720 76868 153720 76868 153721 77251 153721 77249 153721 76868 153722 77249 153722 76949 153722 76869 153723 76870 153723 76989 153723 76989 153724 76870 153724 77232 153724 76989 153725 77232 153725 76988 153725 76988 153726 77232 153726 76871 153726 76988 153727 76871 153727 76986 153727 76986 153728 76871 153728 76872 153728 77270 153729 77236 153729 76873 153729 77270 153730 76873 153730 76874 153730 76874 153731 76873 153731 77228 153731 76874 153732 77228 153732 76875 153732 76875 153733 77228 153733 77227 153733 76875 153734 77227 153734 76858 153734 76877 153735 76876 153735 76915 153735 77009 153736 76877 153736 76914 153736 76886 153737 76878 153737 77005 153737 77005 153738 76878 153738 76888 153738 77005 153739 76888 153739 77007 153739 77007 153740 76888 153740 76889 153740 77007 153741 76889 153741 76879 153741 76879 153742 76889 153742 76995 153742 76882 153743 76884 153743 76880 153743 76926 153744 76927 153744 76881 153744 76881 153745 76927 153745 76928 153745 76881 153746 76928 153746 76882 153746 76882 153747 76928 153747 76883 153747 76882 153748 76883 153748 76884 153748 76885 153749 76878 153749 76918 153749 76918 153750 76878 153750 76886 153750 76918 153751 76886 153751 76887 153751 76885 153752 76926 153752 76878 153752 76878 153753 76926 153753 76881 153753 76878 153754 76881 153754 76888 153754 76888 153755 76881 153755 76882 153755 76888 153756 76882 153756 76889 153756 76889 153757 76882 153757 76880 153757 76889 153758 76880 153758 76995 153758 76920 153759 76925 153759 76885 153759 76885 153760 76925 153760 76890 153760 76885 153761 76890 153761 76926 153761 76919 153762 77009 153762 76891 153762 76891 153763 77009 153763 76914 153763 76891 153764 76914 153764 76921 153764 76921 153765 76914 153765 76922 153765 76923 153766 76897 153766 76898 153766 77263 153767 76892 153767 76893 153767 76893 153768 76892 153768 76894 153768 76893 153769 76894 153769 76986 153769 76895 153770 77271 153770 76911 153770 76911 153771 77271 153771 77270 153771 76911 153772 77270 153772 76913 153772 76901 153773 76896 153773 76900 153773 76900 153774 76896 153774 77268 153774 76900 153775 77268 153775 76895 153775 76895 153776 77268 153776 77272 153776 76895 153777 77272 153777 77271 153777 77263 153778 77264 153778 76897 153778 76897 153779 77264 153779 77267 153779 76897 153780 77267 153780 76898 153780 76898 153781 77267 153781 76899 153781 76898 153782 76899 153782 76909 153782 76909 153783 76899 153783 77266 153783 76909 153784 77266 153784 76900 153784 76900 153785 77266 153785 77265 153785 76900 153786 77265 153786 76901 153786 76923 153787 76902 153787 76924 153787 76924 153788 76902 153788 76903 153788 76924 153789 76903 153789 76904 153789 76904 153790 76903 153790 76910 153790 76904 153791 76910 153791 76905 153791 76905 153792 76910 153792 76906 153792 76905 153793 76906 153793 76907 153793 76907 153794 76906 153794 76912 153794 76907 153795 76912 153795 76929 153795 76929 153796 76912 153796 76908 153796 76929 153797 76908 153797 76930 153797 76923 153798 76898 153798 76902 153798 76902 153799 76898 153799 76909 153799 76902 153800 76909 153800 76903 153800 76903 153801 76909 153801 76900 153801 76903 153802 76900 153802 76910 153802 76910 153803 76900 153803 76895 153803 76910 153804 76895 153804 76906 153804 76906 153805 76895 153805 76911 153805 76906 153806 76911 153806 76912 153806 76912 153807 76911 153807 76913 153807 76912 153808 76913 153808 76908 153808 76877 153809 76915 153809 76914 153809 76914 153810 76915 153810 76916 153810 76914 153811 76916 153811 76922 153811 76922 153812 76916 153812 76917 153812 76922 153813 76917 153813 76985 153813 76887 153814 76919 153814 76918 153814 76918 153815 76919 153815 76891 153815 76918 153816 76891 153816 76885 153816 76885 153817 76891 153817 76921 153817 76885 153818 76921 153818 76920 153818 76920 153819 76921 153819 76922 153819 76920 153820 76922 153820 76892 153820 76892 153821 76922 153821 76985 153821 76892 153822 76985 153822 76894 153822 77263 153823 76897 153823 76892 153823 76892 153824 76897 153824 76923 153824 76892 153825 76923 153825 76920 153825 76920 153826 76923 153826 76924 153826 76920 153827 76924 153827 76925 153827 76925 153828 76924 153828 76904 153828 76925 153829 76904 153829 76890 153829 76890 153830 76904 153830 76905 153830 76890 153831 76905 153831 76926 153831 76926 153832 76905 153832 76907 153832 76926 153833 76907 153833 76927 153833 76927 153834 76907 153834 76929 153834 76927 153835 76929 153835 76928 153835 76928 153836 76929 153836 76930 153836 76928 153837 76930 153837 76883 153837 76954 153838 76869 153838 76992 153838 76939 153839 76976 153839 76937 153839 76969 153840 76970 153840 76982 153840 76971 153841 76933 153841 76972 153841 76993 153842 76945 153842 76931 153842 76931 153843 76945 153843 76944 153843 76931 153844 76944 153844 77013 153844 77013 153845 76944 153845 76943 153845 77013 153846 76943 153846 76932 153846 76932 153847 76943 153847 76942 153847 76972 153848 76933 153848 76934 153848 76934 153849 76933 153849 77012 153849 76934 153850 77012 153850 76937 153850 76955 153851 76982 153851 76935 153851 76937 153852 76976 153852 76934 153852 76934 153853 76976 153853 76974 153853 76934 153854 76974 153854 76972 153854 77012 153855 76936 153855 76937 153855 76937 153856 76936 153856 76938 153856 76937 153857 76938 153857 76939 153857 76939 153858 76938 153858 76940 153858 76939 153859 76940 153859 76977 153859 76977 153860 76940 153860 76946 153860 76977 153861 76946 153861 76978 153861 76978 153862 76946 153862 76941 153862 76978 153863 76941 153863 76998 153863 76936 153864 76942 153864 76938 153864 76938 153865 76942 153865 76943 153865 76938 153866 76943 153866 76940 153866 76940 153867 76943 153867 76944 153867 76940 153868 76944 153868 76946 153868 76946 153869 76944 153869 76945 153869 76946 153870 76945 153870 76941 153870 76965 153871 76862 153871 76953 153871 76965 153872 76953 153872 76966 153872 76862 153873 76965 153873 76861 153873 76861 153874 76965 153874 76947 153874 76861 153875 76947 153875 76859 153875 76859 153876 76947 153876 76964 153876 76859 153877 76964 153877 76948 153877 76858 153878 76948 153878 77000 153878 77000 153879 76948 153879 76964 153879 77000 153880 76964 153880 77002 153880 76949 153881 76950 153881 76868 153881 76868 153882 76950 153882 76951 153882 76868 153883 76951 153883 76867 153883 76867 153884 76951 153884 76968 153884 76867 153885 76968 153885 76864 153885 76864 153886 76968 153886 76966 153886 76864 153887 76966 153887 76952 153887 76952 153888 76966 153888 76953 153888 76991 153889 76950 153889 76992 153889 76992 153890 76950 153890 76949 153890 76992 153891 76949 153891 76954 153891 76982 153892 76955 153892 76969 153892 76969 153893 76955 153893 76973 153893 76969 153894 76973 153894 76956 153894 76956 153895 76973 153895 76975 153895 76956 153896 76975 153896 76967 153896 76967 153897 76975 153897 76957 153897 76967 153898 76957 153898 76958 153898 76958 153899 76957 153899 76960 153899 76958 153900 76960 153900 76959 153900 76959 153901 76960 153901 76961 153901 76959 153902 76961 153902 76962 153902 76962 153903 76961 153903 76979 153903 76962 153904 76979 153904 76963 153904 76963 153905 76979 153905 76980 153905 76963 153906 76980 153906 77002 153906 77002 153907 76964 153907 76963 153907 76963 153908 76964 153908 76947 153908 76963 153909 76947 153909 76962 153909 76962 153910 76947 153910 76965 153910 76962 153911 76965 153911 76959 153911 76959 153912 76965 153912 76966 153912 76959 153913 76966 153913 76958 153913 76958 153914 76966 153914 76968 153914 76958 153915 76968 153915 76967 153915 76967 153916 76968 153916 76951 153916 76967 153917 76951 153917 76956 153917 76956 153918 76951 153918 76950 153918 76956 153919 76950 153919 76969 153919 76969 153920 76950 153920 76991 153920 76969 153921 76991 153921 76970 153921 76935 153922 76971 153922 76955 153922 76955 153923 76971 153923 76972 153923 76955 153924 76972 153924 76973 153924 76973 153925 76972 153925 76974 153925 76973 153926 76974 153926 76975 153926 76975 153927 76974 153927 76976 153927 76975 153928 76976 153928 76957 153928 76957 153929 76976 153929 76939 153929 76957 153930 76939 153930 76960 153930 76960 153931 76939 153931 76977 153931 76960 153932 76977 153932 76961 153932 76961 153933 76977 153933 76978 153933 76961 153934 76978 153934 76979 153934 76979 153935 76978 153935 76998 153935 76979 153936 76998 153936 76980 153936 76983 153937 76990 153937 76981 153937 77011 153938 76935 153938 76982 153938 76915 153939 76876 153939 77019 153939 76917 153940 76916 153940 76983 153940 76983 153941 76916 153941 76915 153941 76915 153942 77019 153942 76983 153942 76983 153943 77019 153943 77017 153943 76983 153944 77017 153944 76990 153944 76990 153945 77017 153945 76984 153945 76990 153946 76984 153946 77011 153946 76894 153947 76985 153947 76987 153947 76987 153948 76985 153948 76917 153948 76986 153949 76894 153949 76988 153949 76988 153950 76894 153950 76987 153950 76988 153951 76987 153951 76989 153951 77011 153952 76982 153952 76990 153952 76990 153953 76982 153953 76970 153953 76990 153954 76970 153954 76981 153954 76981 153955 76970 153955 76991 153955 76981 153956 76991 153956 76992 153956 76917 153957 76983 153957 76987 153957 76987 153958 76983 153958 76981 153958 76987 153959 76981 153959 76989 153959 76989 153960 76981 153960 76992 153960 76989 153961 76992 153961 76869 153961 77000 153962 77002 153962 77004 153962 77016 153963 76994 153963 76996 153963 76993 153964 77014 153964 76945 153964 76945 153965 77014 153965 76999 153965 76879 153966 76995 153966 77018 153966 77018 153967 76995 153967 76994 153967 77001 153968 77003 153968 76997 153968 76997 153969 77003 153969 76999 153969 76994 153970 76995 153970 76996 153970 76996 153971 76995 153971 76880 153971 76996 153972 76880 153972 76884 153972 77014 153973 77016 153973 76999 153973 76999 153974 77016 153974 76996 153974 76999 153975 76996 153975 76997 153975 76997 153976 76996 153976 76884 153976 77002 153977 76980 153977 77003 153977 77003 153978 76980 153978 76998 153978 77003 153979 76998 153979 76999 153979 76999 153980 76998 153980 76941 153980 76999 153981 76941 153981 76945 153981 76874 153982 76875 153982 77004 153982 77004 153983 76875 153983 76858 153983 77004 153984 76858 153984 77000 153984 76884 153985 76883 153985 76997 153985 76997 153986 76883 153986 76930 153986 76997 153987 76930 153987 77001 153987 77001 153988 76930 153988 76908 153988 77001 153989 76908 153989 76913 153989 77002 153990 77003 153990 77004 153990 77004 153991 77003 153991 77001 153991 77004 153992 77001 153992 76874 153992 76874 153993 77001 153993 76913 153993 76874 153994 76913 153994 77270 153994 77006 153995 76879 153995 77018 153995 77006 153996 76887 153996 76886 153996 76886 153997 77005 153997 77006 153997 77006 153998 77005 153998 77007 153998 77006 153999 77007 153999 76879 153999 77008 154000 77009 154000 77006 154000 77006 154001 77009 154001 77010 154001 77006 154002 77010 154002 76887 154002 77015 154003 76935 154003 77011 154003 77012 154004 76933 154004 77015 154004 77015 154005 76933 154005 76971 154005 77015 154006 76971 154006 76935 154006 76993 154007 76931 154007 77015 154007 77015 154008 76931 154008 77013 154008 77015 154009 77013 154009 76932 154009 76932 154010 76942 154010 77015 154010 77015 154011 76942 154011 76936 154011 77015 154012 76936 154012 77012 154012 76993 154013 77015 154013 77014 154013 77014 154014 77015 154014 77011 154014 77014 154015 77011 154015 77016 154015 77016 154016 77011 154016 76984 154016 77016 154017 76984 154017 76994 154017 76994 154018 76984 154018 77017 154018 76994 154019 77017 154019 77018 154019 77018 154020 77017 154020 77019 154020 77018 154021 77019 154021 77006 154021 77006 154022 77019 154022 76876 154022 77006 154023 76876 154023 77008 154023 76870 154024 76869 154024 77249 154024 77249 154025 76869 154025 76954 154025 77249 154026 76954 154026 76949 154026 77249 154027 77248 154027 76870 154027 76870 154028 77248 154028 77231 154028 77174 154029 77020 154029 77021 154029 77023 154030 77166 154030 77022 154030 77022 154031 77166 154031 77163 154031 77022 154032 77163 154032 77039 154032 77039 154033 77163 154033 77169 154033 77039 154034 77169 154034 77168 154034 77021 154035 77020 154035 77022 154035 77022 154036 77020 154036 77162 154036 77022 154037 77162 154037 77023 154037 77174 154038 77021 154038 77024 154038 77024 154039 77021 154039 77025 154039 77024 154040 77025 154040 77175 154040 77025 154041 77026 154041 77175 154041 77175 154042 77026 154042 77027 154042 77175 154043 77027 154043 77176 154043 77176 154044 77027 154044 77034 154044 77176 154045 77034 154045 77028 154045 77028 154046 77034 154046 77029 154046 77034 154047 77033 154047 77029 154047 77029 154048 77033 154048 77031 154048 77029 154049 77031 154049 77217 154049 77030 154050 77053 154050 77031 154050 77026 154051 77035 154051 77032 154051 77031 154052 77033 154052 77030 154052 77030 154053 77033 154053 77034 154053 77030 154054 77034 154054 77032 154054 77032 154055 77034 154055 77027 154055 77032 154056 77027 154056 77026 154056 77026 154057 77025 154057 77035 154057 77035 154058 77025 154058 77021 154058 77035 154059 77021 154059 77036 154059 77036 154060 77021 154060 77022 154060 77036 154061 77022 154061 77230 154061 77230 154062 77022 154062 77039 154062 77230 154063 77039 154063 77037 154063 77038 154064 77055 154064 77079 154064 77079 154065 77055 154065 77040 154065 77079 154066 77040 154066 77039 154066 77039 154067 77040 154067 77037 154067 77041 154068 77049 154068 77051 154068 77260 154069 77058 154069 77042 154069 77042 154070 77058 154070 77043 154070 77042 154071 77043 154071 77044 154071 77044 154072 77043 154072 77072 154072 77044 154073 77072 154073 77051 154073 77051 154074 77072 154074 77073 154074 77051 154075 77073 154075 77041 154075 77041 154076 77068 154076 77049 154076 77049 154077 77068 154077 77069 154077 77049 154078 77069 154078 77050 154078 77063 154079 77045 154079 77046 154079 77046 154080 77045 154080 77047 154080 77046 154081 77047 154081 77065 154081 77065 154082 77047 154082 77050 154082 77065 154083 77050 154083 77048 154083 77048 154084 77050 154084 77069 154084 77256 154085 77044 154085 77051 154085 77252 154086 77049 154086 77050 154086 77231 154087 77248 154087 77050 154087 77050 154088 77248 154088 77250 154088 77050 154089 77250 154089 77252 154089 77252 154090 77253 154090 77049 154090 77049 154091 77253 154091 77255 154091 77049 154092 77255 154092 77051 154092 77051 154093 77255 154093 77259 154093 77051 154094 77259 154094 77256 154094 77230 154095 77234 154095 77036 154095 77036 154096 77234 154096 77237 154096 77036 154097 77237 154097 77035 154097 77035 154098 77237 154098 77235 154098 77050 154099 77047 154099 77231 154099 77231 154100 77047 154100 77045 154100 77231 154101 77045 154101 77233 154101 77233 154102 77045 154102 77062 154102 77233 154103 77062 154103 77052 154103 77052 154104 77062 154104 77053 154104 77052 154105 77053 154105 77245 154105 77245 154106 77053 154106 77030 154106 77245 154107 77030 154107 77054 154107 77054 154108 77030 154108 77032 154108 77054 154109 77032 154109 77244 154109 77244 154110 77032 154110 77035 154110 77244 154111 77035 154111 77242 154111 77242 154112 77035 154112 77235 154112 77055 154113 77038 154113 77056 154113 77055 154114 77056 154114 77057 154114 77057 154115 77056 154115 77058 154115 77057 154116 77058 154116 77260 154116 77059 154117 77058 154117 77060 154117 77060 154118 77058 154118 77056 154118 77060 154119 77056 154119 77061 154119 77038 154120 77172 154120 77056 154120 77056 154121 77172 154121 77083 154121 77056 154122 77083 154122 77061 154122 77031 154123 77053 154123 77096 154123 77096 154124 77053 154124 77062 154124 77096 154125 77062 154125 77063 154125 77063 154126 77062 154126 77045 154126 77043 154127 77058 154127 77059 154127 77064 154128 77063 154128 77126 154128 77126 154129 77063 154129 77046 154129 77126 154130 77046 154130 77132 154130 77132 154131 77046 154131 77066 154131 77046 154132 77065 154132 77066 154132 77066 154133 77065 154133 77048 154133 77066 154134 77048 154134 77067 154134 77041 154135 77077 154135 77068 154135 77068 154136 77077 154136 77067 154136 77068 154137 77067 154137 77069 154137 77069 154138 77067 154138 77048 154138 77059 154139 77070 154139 77043 154139 77043 154140 77070 154140 77071 154140 77043 154141 77071 154141 77072 154141 77072 154142 77071 154142 77074 154142 77072 154143 77074 154143 77073 154143 77073 154144 77074 154144 77075 154144 77073 154145 77075 154145 77041 154145 77041 154146 77075 154146 77076 154146 77041 154147 77076 154147 77077 154147 77172 154148 77038 154148 77078 154148 77078 154149 77038 154149 77079 154149 77078 154150 77079 154150 77167 154150 77167 154151 77079 154151 77039 154151 77167 154152 77039 154152 77168 154152 77093 154153 77160 154153 77080 154153 77160 154154 77093 154154 77092 154154 77090 154155 77086 154155 77087 154155 77082 154156 77059 154156 77060 154156 77089 154157 77081 154157 77090 154157 77090 154158 77081 154158 77082 154158 77082 154159 77060 154159 77090 154159 77090 154160 77060 154160 77061 154160 77090 154161 77061 154161 77086 154161 77086 154162 77061 154162 77083 154162 77086 154163 77083 154163 77172 154163 77140 154164 77085 154164 77084 154164 77084 154165 77085 154165 77089 154165 77172 154166 77171 154166 77086 154166 77086 154167 77171 154167 77170 154167 77086 154168 77170 154168 77087 154168 77087 154169 77170 154169 77198 154169 77087 154170 77198 154170 77091 154170 77142 154171 77140 154171 77088 154171 77088 154172 77140 154172 77084 154172 77088 154173 77084 154173 77093 154173 77089 154174 77090 154174 77084 154174 77084 154175 77090 154175 77087 154175 77084 154176 77087 154176 77093 154176 77093 154177 77087 154177 77091 154177 77093 154178 77091 154178 77092 154178 77102 154179 77142 154179 77213 154179 77213 154180 77142 154180 77088 154180 77213 154181 77088 154181 77211 154181 77211 154182 77088 154182 77093 154182 77211 154183 77093 154183 77210 154183 77210 154184 77093 154184 77080 154184 77217 154185 77031 154185 77094 154185 77094 154186 77031 154186 77096 154186 77094 154187 77096 154187 77095 154187 77063 154188 77064 154188 77096 154188 77096 154189 77064 154189 77097 154189 77096 154190 77097 154190 77095 154190 77076 154191 77075 154191 77119 154191 77074 154192 77071 154192 77120 154192 77111 154193 77098 154193 77106 154193 77204 154194 77203 154194 77103 154194 77200 154195 77216 154195 77130 154195 77111 154196 77110 154196 77098 154196 77098 154197 77110 154197 77201 154197 77098 154198 77201 154198 77200 154198 77101 154199 77199 154199 77100 154199 77100 154200 77199 154200 77099 154200 77100 154201 77099 154201 77137 154201 77100 154202 77141 154202 77101 154202 77101 154203 77141 154203 77142 154203 77101 154204 77142 154204 77102 154204 77099 154205 77204 154205 77137 154205 77137 154206 77204 154206 77103 154206 77137 154207 77103 154207 77104 154207 77104 154208 77103 154208 77112 154208 77104 154209 77112 154209 77105 154209 77105 154210 77112 154210 77113 154210 77105 154211 77113 154211 77134 154211 77134 154212 77113 154212 77114 154212 77134 154213 77114 154213 77115 154213 77126 154214 77132 154214 77107 154214 77107 154215 77132 154215 77133 154215 77200 154216 77130 154216 77098 154216 77098 154217 77130 154217 77129 154217 77098 154218 77129 154218 77106 154218 77106 154219 77129 154219 77107 154219 77106 154220 77107 154220 77108 154220 77108 154221 77107 154221 77133 154221 77108 154222 77133 154222 77109 154222 77203 154223 77110 154223 77103 154223 77103 154224 77110 154224 77111 154224 77103 154225 77111 154225 77112 154225 77112 154226 77111 154226 77106 154226 77112 154227 77106 154227 77113 154227 77113 154228 77106 154228 77108 154228 77113 154229 77108 154229 77114 154229 77114 154230 77108 154230 77109 154230 77114 154231 77109 154231 77115 154231 77076 154232 77119 154232 77077 154232 77140 154233 77139 154233 77085 154233 77085 154234 77139 154234 77116 154234 77085 154235 77116 154235 77089 154235 77089 154236 77116 154236 77124 154236 77089 154237 77124 154237 77081 154237 77081 154238 77124 154238 77117 154238 77081 154239 77117 154239 77082 154239 77082 154240 77117 154240 77118 154240 77082 154241 77118 154241 77059 154241 77059 154242 77118 154242 77070 154242 77075 154243 77074 154243 77119 154243 77119 154244 77074 154244 77120 154244 77119 154245 77120 154245 77135 154245 77135 154246 77120 154246 77121 154246 77135 154247 77121 154247 77136 154247 77136 154248 77121 154248 77125 154248 77136 154249 77125 154249 77122 154249 77122 154250 77125 154250 77123 154250 77122 154251 77123 154251 77138 154251 77139 154252 77138 154252 77116 154252 77116 154253 77138 154253 77123 154253 77116 154254 77123 154254 77124 154254 77124 154255 77123 154255 77125 154255 77124 154256 77125 154256 77117 154256 77117 154257 77125 154257 77121 154257 77117 154258 77121 154258 77118 154258 77118 154259 77121 154259 77120 154259 77118 154260 77120 154260 77070 154260 77070 154261 77120 154261 77071 154261 77064 154262 77126 154262 77127 154262 77127 154263 77126 154263 77107 154263 77127 154264 77107 154264 77225 154264 77225 154265 77107 154265 77129 154265 77225 154266 77129 154266 77128 154266 77128 154267 77129 154267 77130 154267 77128 154268 77130 154268 77131 154268 77131 154269 77130 154269 77216 154269 77131 154270 77216 154270 77215 154270 77132 154271 77066 154271 77133 154271 77133 154272 77066 154272 77067 154272 77133 154273 77067 154273 77109 154273 77109 154274 77067 154274 77077 154274 77109 154275 77077 154275 77115 154275 77115 154276 77077 154276 77119 154276 77115 154277 77119 154277 77134 154277 77134 154278 77119 154278 77135 154278 77134 154279 77135 154279 77105 154279 77105 154280 77135 154280 77136 154280 77105 154281 77136 154281 77104 154281 77104 154282 77136 154282 77122 154282 77104 154283 77122 154283 77137 154283 77137 154284 77122 154284 77138 154284 77137 154285 77138 154285 77100 154285 77100 154286 77138 154286 77139 154286 77100 154287 77139 154287 77141 154287 77141 154288 77139 154288 77140 154288 77141 154289 77140 154289 77142 154289 77029 154290 77217 154290 77143 154290 77078 154291 77167 154291 77144 154291 77145 154292 77152 154292 77151 154292 77178 154293 77188 154293 77221 154293 77146 154294 77209 154294 77155 154294 77155 154295 77209 154295 77147 154295 77155 154296 77147 154296 77158 154296 77158 154297 77147 154297 77080 154297 77158 154298 77080 154298 77160 154298 77190 154299 77221 154299 77189 154299 77206 154300 77149 154300 77148 154300 77148 154301 77149 154301 77150 154301 77148 154302 77150 154302 77153 154302 77153 154303 77150 154303 77207 154303 77153 154304 77207 154304 77151 154304 77151 154305 77152 154305 77153 154305 77153 154306 77152 154306 77191 154306 77153 154307 77191 154307 77148 154307 77207 154308 77205 154308 77151 154308 77151 154309 77205 154309 77156 154309 77151 154310 77156 154310 77145 154310 77145 154311 77156 154311 77157 154311 77145 154312 77157 154312 77154 154312 77154 154313 77157 154313 77159 154313 77154 154314 77159 154314 77197 154314 77197 154315 77159 154315 77092 154315 77197 154316 77092 154316 77091 154316 77205 154317 77146 154317 77156 154317 77156 154318 77146 154318 77155 154318 77156 154319 77155 154319 77157 154319 77157 154320 77155 154320 77158 154320 77157 154321 77158 154321 77159 154321 77159 154322 77158 154322 77160 154322 77159 154323 77160 154323 77092 154323 77161 154324 77165 154324 77162 154324 77169 154325 77163 154325 77164 154325 77164 154326 77163 154326 77166 154326 77164 154327 77166 154327 77165 154327 77165 154328 77166 154328 77023 154328 77165 154329 77023 154329 77162 154329 77144 154330 77167 154330 77164 154330 77164 154331 77167 154331 77168 154331 77164 154332 77168 154332 77169 154332 77170 154333 77171 154333 77144 154333 77144 154334 77171 154334 77172 154334 77144 154335 77172 154335 77078 154335 77173 154336 77175 154336 77185 154336 77185 154337 77175 154337 77176 154337 77162 154338 77020 154338 77161 154338 77161 154339 77020 154339 77174 154339 77161 154340 77174 154340 77173 154340 77173 154341 77174 154341 77024 154341 77173 154342 77024 154342 77175 154342 77176 154343 77028 154343 77185 154343 77185 154344 77028 154344 77029 154344 77185 154345 77029 154345 77187 154345 77187 154346 77029 154346 77143 154346 77187 154347 77143 154347 77177 154347 77221 154348 77190 154348 77178 154348 77178 154349 77190 154349 77192 154349 77178 154350 77192 154350 77186 154350 77186 154351 77192 154351 77193 154351 77186 154352 77193 154352 77179 154352 77179 154353 77193 154353 77194 154353 77179 154354 77194 154354 77180 154354 77180 154355 77194 154355 77195 154355 77180 154356 77195 154356 77181 154356 77181 154357 77195 154357 77196 154357 77181 154358 77196 154358 77184 154358 77184 154359 77196 154359 77182 154359 77184 154360 77182 154360 77183 154360 77183 154361 77182 154361 77198 154361 77183 154362 77198 154362 77170 154362 77170 154363 77144 154363 77183 154363 77183 154364 77144 154364 77164 154364 77183 154365 77164 154365 77184 154365 77184 154366 77164 154366 77165 154366 77184 154367 77165 154367 77181 154367 77181 154368 77165 154368 77161 154368 77181 154369 77161 154369 77180 154369 77180 154370 77161 154370 77173 154370 77180 154371 77173 154371 77179 154371 77179 154372 77173 154372 77185 154372 77179 154373 77185 154373 77186 154373 77186 154374 77185 154374 77187 154374 77186 154375 77187 154375 77178 154375 77178 154376 77187 154376 77177 154376 77178 154377 77177 154377 77188 154377 77189 154378 77206 154378 77190 154378 77190 154379 77206 154379 77148 154379 77190 154380 77148 154380 77192 154380 77192 154381 77148 154381 77191 154381 77192 154382 77191 154382 77193 154382 77193 154383 77191 154383 77152 154383 77193 154384 77152 154384 77194 154384 77194 154385 77152 154385 77145 154385 77194 154386 77145 154386 77195 154386 77195 154387 77145 154387 77154 154387 77195 154388 77154 154388 77196 154388 77196 154389 77154 154389 77197 154389 77196 154390 77197 154390 77182 154390 77182 154391 77197 154391 77091 154391 77182 154392 77091 154392 77198 154392 77208 154393 77189 154393 77220 154393 77202 154394 77102 154394 77213 154394 77101 154395 77102 154395 77199 154395 77199 154396 77102 154396 77202 154396 77199 154397 77202 154397 77099 154397 77099 154398 77202 154398 77204 154398 77216 154399 77200 154399 77202 154399 77202 154400 77200 154400 77201 154400 77201 154401 77110 154401 77202 154401 77202 154402 77110 154402 77203 154402 77202 154403 77203 154403 77204 154403 77146 154404 77205 154404 77208 154404 77208 154405 77205 154405 77207 154405 77206 154406 77189 154406 77149 154406 77149 154407 77189 154407 77208 154407 77149 154408 77208 154408 77150 154408 77150 154409 77208 154409 77207 154409 77080 154410 77147 154410 77208 154410 77208 154411 77147 154411 77209 154411 77208 154412 77209 154412 77146 154412 77080 154413 77208 154413 77210 154413 77210 154414 77208 154414 77220 154414 77210 154415 77220 154415 77211 154415 77211 154416 77220 154416 77212 154416 77211 154417 77212 154417 77213 154417 77213 154418 77212 154418 77214 154418 77213 154419 77214 154419 77202 154419 77202 154420 77214 154420 77215 154420 77202 154421 77215 154421 77216 154421 77143 154422 77217 154422 77094 154422 77188 154423 77177 154423 77222 154423 77127 154424 77225 154424 77226 154424 77128 154425 77131 154425 77218 154425 77131 154426 77215 154426 77218 154426 77218 154427 77215 154427 77214 154427 77218 154428 77214 154428 77223 154428 77223 154429 77214 154429 77212 154429 77223 154430 77212 154430 77219 154430 77219 154431 77212 154431 77220 154431 77219 154432 77220 154432 77221 154432 77221 154433 77220 154433 77189 154433 77221 154434 77188 154434 77219 154434 77219 154435 77188 154435 77222 154435 77219 154436 77222 154436 77223 154436 77223 154437 77222 154437 77224 154437 77223 154438 77224 154438 77218 154438 77218 154439 77224 154439 77226 154439 77218 154440 77226 154440 77128 154440 77128 154441 77226 154441 77225 154441 77177 154442 77143 154442 77222 154442 77222 154443 77143 154443 77094 154443 77222 154444 77094 154444 77224 154444 77224 154445 77094 154445 77095 154445 77224 154446 77095 154446 77226 154446 77226 154447 77095 154447 77097 154447 77226 154448 77097 154448 77127 154448 77127 154449 77097 154449 77064 154449 77044 154450 77256 154450 77227 154450 77044 154451 77227 154451 77261 154451 77227 154452 77228 154452 77261 154452 77261 154453 77228 154453 76873 154453 77261 154454 76873 154454 77229 154454 77229 154455 76873 154455 77230 154455 77230 154456 76873 154456 77236 154456 77230 154457 77236 154457 77234 154457 76870 154458 77231 154458 77232 154458 77232 154459 77231 154459 77233 154459 77232 154460 77233 154460 76871 154460 76871 154461 77233 154461 77052 154461 76871 154462 77052 154462 76872 154462 76872 154463 77052 154463 77245 154463 77237 154464 77234 154464 77236 154464 77240 154465 77242 154465 77235 154465 77236 154466 77238 154466 77237 154466 77237 154467 77238 154467 77239 154467 77237 154468 77239 154468 77235 154468 77235 154469 77239 154469 77269 154469 77235 154470 77269 154470 77240 154470 77240 154471 77241 154471 77242 154471 77242 154472 77241 154472 77243 154472 77242 154473 77243 154473 77244 154473 76872 154474 77245 154474 77262 154474 77262 154475 77245 154475 77054 154475 77262 154476 77054 154476 77246 154476 77246 154477 77054 154477 77244 154477 77246 154478 77244 154478 77247 154478 77247 154479 77244 154479 77243 154479 77248 154480 77249 154480 77250 154480 77250 154481 77249 154481 77251 154481 77250 154482 77251 154482 77252 154482 77251 154483 76866 154483 77252 154483 77252 154484 76866 154484 76865 154484 77252 154485 76865 154485 77253 154485 77253 154486 76865 154486 76863 154486 77253 154487 76863 154487 77255 154487 76863 154488 77254 154488 77255 154488 77255 154489 77254 154489 76860 154489 77255 154490 76860 154490 77259 154490 77227 154491 77256 154491 77257 154491 77257 154492 77256 154492 77259 154492 77257 154493 77259 154493 77258 154493 77258 154494 77259 154494 76860 154494 77037 154495 77040 154495 77055 154495 77042 154496 77044 154496 77260 154496 77260 154497 77044 154497 77261 154497 77260 154498 77261 154498 77057 154498 77057 154499 77261 154499 77229 154499 77057 154500 77229 154500 77055 154500 77055 154501 77229 154501 77230 154501 77055 154502 77230 154502 77037 154502 77238 154503 77236 154503 77270 154503 76986 154504 76872 154504 76893 154504 76893 154505 76872 154505 77262 154505 76893 154506 77262 154506 77263 154506 77263 154507 77262 154507 77264 154507 77243 154508 77267 154508 77247 154508 77247 154509 77267 154509 77264 154509 77247 154510 77264 154510 77246 154510 77246 154511 77264 154511 77262 154511 77240 154512 77265 154512 77241 154512 77241 154513 77265 154513 77266 154513 77241 154514 77266 154514 77243 154514 77243 154515 77266 154515 76899 154515 77243 154516 76899 154516 77267 154516 77272 154517 77268 154517 77269 154517 77269 154518 77268 154518 76896 154518 77269 154519 76896 154519 77240 154519 77240 154520 76896 154520 76901 154520 77240 154521 76901 154521 77265 154521 77270 154522 77271 154522 77238 154522 77238 154523 77271 154523 77272 154523 77238 154524 77272 154524 77239 154524 77239 154525 77272 154525 77269 154525 77273 154526 77275 154526 77274 154526 77650 154527 77276 154527 77652 154527 77273 154528 77652 154528 77275 154528 77275 154529 77652 154529 77276 154529 77275 154530 77276 154530 77274 154530 77274 154531 77276 154531 77650 154531 78407 154532 78201 154532 77279 154532 77293 154533 79748 154533 77280 154533 78201 154534 78202 154534 77279 154534 77279 154535 78202 154535 78792 154535 77279 154536 78792 154536 78797 154536 77280 154537 79411 154537 77277 154537 78797 154538 77278 154538 77279 154538 77279 154539 77278 154539 78796 154539 77279 154540 78796 154540 78794 154540 79748 154541 79746 154541 77280 154541 77280 154542 79746 154542 79745 154542 77280 154543 79745 154543 77286 154543 79350 154544 79467 154544 77303 154544 77283 154545 79161 154545 79160 154545 77279 154546 77281 154546 78407 154546 78407 154547 77281 154547 77282 154547 78407 154548 77282 154548 79158 154548 79158 154549 77282 154549 77283 154549 79158 154550 77283 154550 79159 154550 79159 154551 77283 154551 79160 154551 80053 154552 77284 154552 80054 154552 80054 154553 77284 154553 80056 154553 80054 154554 80056 154554 80055 154554 80055 154555 80056 154555 80052 154555 80055 154556 80052 154556 77285 154556 77285 154557 80052 154557 77660 154557 77285 154558 77660 154558 79382 154558 79382 154559 77660 154559 77280 154559 79382 154560 77280 154560 79743 154560 79743 154561 77280 154561 77286 154561 78424 154562 77289 154562 77302 154562 77291 154563 77287 154563 77288 154563 77316 154564 77321 154564 77315 154564 77302 154565 77289 154565 77277 154565 77277 154566 77289 154566 79470 154566 77277 154567 79470 154567 77295 154567 77288 154568 77290 154568 77291 154568 77291 154569 77290 154569 77292 154569 77291 154570 77292 154570 80028 154570 80028 154571 77292 154571 77326 154571 80028 154572 77326 154572 77565 154572 77293 154573 77280 154573 77294 154573 77294 154574 77280 154574 77277 154574 77294 154575 77277 154575 77733 154575 77733 154576 77277 154576 77295 154576 77733 154577 77295 154577 79351 154577 79351 154578 77295 154578 77299 154578 79351 154579 77299 154579 79354 154579 77351 154580 78556 154580 77352 154580 77296 154581 77297 154581 77298 154581 77298 154582 77297 154582 77300 154582 77298 154583 77300 154583 77299 154583 77299 154584 77300 154584 79353 154584 77299 154585 79353 154585 79354 154585 77336 154586 77338 154586 78458 154586 78458 154587 77338 154587 77301 154587 78458 154588 77301 154588 78457 154588 78457 154589 77301 154589 78506 154589 78457 154590 78506 154590 78456 154590 78456 154591 78506 154591 78424 154591 78456 154592 78424 154592 78455 154592 78455 154593 78424 154593 77302 154593 77303 154594 79467 154594 77564 154594 77564 154595 79467 154595 79466 154595 77564 154596 79466 154596 77562 154596 77562 154597 79466 154597 79465 154597 77562 154598 79465 154598 77554 154598 77554 154599 79465 154599 78503 154599 77554 154600 78503 154600 77308 154600 77304 154601 78733 154601 77305 154601 77305 154602 78733 154602 77311 154602 78927 154603 77306 154603 77320 154603 77320 154604 77306 154604 78193 154604 79666 154605 79665 154605 77354 154605 77354 154606 79665 154606 77344 154606 78503 154607 78501 154607 77308 154607 77308 154608 78501 154608 77307 154608 77308 154609 77307 154609 77352 154609 77352 154610 77307 154610 77309 154610 77352 154611 77309 154611 77330 154611 77310 154612 77323 154612 79403 154612 77311 154613 77312 154613 77305 154613 77305 154614 77312 154614 77313 154614 77305 154615 77313 154615 77315 154615 77315 154616 77313 154616 77314 154616 77315 154617 77314 154617 77316 154617 78095 154618 77336 154618 78794 154618 78794 154619 77336 154619 78452 154619 78794 154620 78452 154620 77279 154620 77317 154621 78100 154621 78427 154621 78427 154622 78100 154622 77318 154622 78427 154623 77318 154623 78103 154623 77319 154624 78927 154624 77321 154624 77321 154625 78927 154625 77320 154625 77321 154626 77320 154626 77315 154626 77315 154627 77320 154627 77322 154627 77315 154628 77322 154628 77310 154628 77310 154629 77322 154629 78437 154629 77310 154630 78437 154630 77323 154630 77346 154631 77347 154631 79374 154631 79374 154632 77347 154632 77325 154632 79374 154633 77325 154633 77324 154633 77324 154634 77325 154634 79350 154634 77324 154635 79350 154635 77326 154635 77326 154636 79350 154636 77303 154636 77326 154637 77303 154637 77565 154637 77327 154638 79891 154638 77328 154638 77328 154639 79891 154639 77357 154639 77309 154640 77329 154640 77330 154640 77330 154641 77329 154641 77331 154641 77330 154642 77331 154642 77333 154642 77331 154643 77332 154643 77333 154643 77333 154644 77332 154644 78443 154644 77333 154645 78443 154645 78192 154645 78192 154646 78443 154646 78442 154646 78192 154647 78442 154647 78193 154647 78193 154648 78442 154648 78440 154648 78193 154649 78440 154649 77320 154649 79673 154650 77353 154650 77334 154650 77334 154651 77353 154651 79671 154651 79403 154652 79405 154652 77310 154652 77310 154653 79405 154653 77335 154653 77310 154654 77335 154654 77347 154654 78095 154655 77337 154655 77336 154655 77336 154656 77337 154656 78106 154656 77336 154657 78106 154657 77338 154657 77338 154658 78106 154658 77339 154658 77338 154659 77339 154659 77317 154659 77317 154660 77339 154660 78099 154660 77317 154661 78099 154661 78100 154661 77321 154662 77340 154662 77319 154662 77319 154663 77340 154663 78943 154663 77319 154664 78943 154664 78948 154664 78948 154665 78943 154665 78944 154665 78948 154666 78944 154666 78941 154666 77341 154667 77342 154667 77353 154667 77353 154668 77342 154668 77343 154668 77353 154669 77343 154669 79671 154669 77359 154670 79462 154670 77344 154670 77344 154671 79462 154671 77345 154671 77344 154672 77345 154672 77354 154672 77346 154673 79370 154673 77347 154673 77347 154674 79370 154674 79881 154674 77347 154675 79881 154675 77310 154675 77310 154676 79881 154676 77348 154676 77310 154677 77348 154677 77328 154677 77349 154678 79135 154678 77350 154678 77350 154679 79135 154679 79134 154679 77350 154680 79134 154680 78403 154680 78403 154681 79134 154681 77351 154681 78403 154682 77351 154682 78188 154682 78188 154683 77351 154683 77352 154683 78188 154684 77352 154684 78189 154684 78189 154685 77352 154685 77330 154685 79673 154686 79666 154686 77353 154686 77353 154687 79666 154687 77354 154687 77353 154688 77354 154688 77355 154688 77355 154689 77354 154689 77310 154689 77355 154690 77310 154690 77356 154690 77356 154691 77310 154691 77328 154691 77356 154692 77328 154692 79894 154692 79894 154693 77328 154693 77357 154693 78103 154694 78097 154694 78427 154694 78427 154695 78097 154695 78567 154695 78427 154696 78567 154696 77358 154696 77359 154697 79686 154697 79462 154697 79462 154698 79686 154698 79687 154698 79462 154699 79687 154699 77364 154699 77304 154700 77305 154700 78196 154700 78196 154701 77305 154701 78435 154701 78196 154702 78435 154702 78198 154702 78198 154703 78435 154703 78500 154703 78198 154704 78500 154704 77360 154704 77360 154705 78500 154705 78427 154705 77360 154706 78427 154706 77361 154706 77361 154707 78427 154707 77358 154707 77361 154708 77358 154708 78748 154708 77296 154709 77298 154709 77362 154709 77362 154710 77298 154710 79462 154710 77362 154711 79462 154711 77363 154711 77363 154712 79462 154712 77364 154712 77363 154713 77364 154713 79682 154713 81368 154714 81369 154714 77373 154714 77365 154715 77424 154715 77425 154715 77440 154716 77366 154716 77367 154716 81369 154717 77368 154717 77373 154717 77373 154718 77368 154718 77369 154718 77373 154719 77369 154719 81736 154719 77639 154720 77370 154720 77421 154720 77403 154721 80357 154721 77402 154721 80509 154722 80508 154722 77371 154722 81736 154723 77372 154723 77373 154723 77373 154724 77372 154724 77374 154724 77373 154725 77374 154725 81739 154725 80807 154726 77375 154726 77639 154726 77639 154727 77375 154727 77376 154727 77639 154728 77376 154728 77388 154728 77371 154729 80508 154729 77421 154729 77421 154730 80508 154730 77377 154730 77421 154731 77377 154731 80507 154731 77380 154732 77378 154732 77382 154732 80234 154733 77379 154733 81739 154733 81739 154734 77379 154734 77767 154734 81739 154735 77767 154735 77373 154735 77373 154736 81509 154736 81368 154736 81368 154737 81509 154737 82057 154737 81368 154738 82057 154738 81377 154738 81377 154739 82057 154739 77380 154739 81377 154740 77380 154740 77381 154740 77381 154741 77380 154741 77382 154741 81152 154742 81151 154742 77383 154742 77383 154743 81151 154743 77384 154743 77383 154744 77384 154744 77385 154744 77385 154745 77384 154745 77386 154745 77385 154746 77386 154746 80365 154746 80365 154747 77386 154747 80400 154747 80365 154748 80400 154748 77387 154748 77387 154749 80400 154749 77639 154749 77387 154750 77639 154750 80366 154750 80366 154751 77639 154751 77388 154751 77367 154752 77366 154752 80409 154752 80409 154753 77366 154753 77611 154753 80409 154754 77611 154754 80407 154754 80407 154755 77611 154755 77389 154755 80407 154756 77389 154756 77390 154756 77390 154757 77389 154757 77490 154757 77390 154758 77490 154758 80504 154758 81660 154759 77391 154759 77428 154759 80940 154760 80943 154760 80948 154760 77379 154761 81459 154761 77392 154761 77392 154762 81459 154762 77393 154762 77392 154763 77393 154763 77394 154763 77394 154764 77393 154764 81457 154764 77394 154765 81457 154765 80434 154765 80434 154766 81457 154766 80509 154766 80434 154767 80509 154767 80435 154767 80435 154768 80509 154768 77371 154768 77405 154769 81129 154769 77395 154769 80234 154770 81340 154770 77379 154770 77379 154771 81340 154771 81342 154771 77379 154772 81342 154772 81459 154772 81459 154773 81342 154773 77396 154773 81459 154774 77396 154774 81460 154774 81460 154775 77396 154775 81343 154775 77397 154776 80410 154776 80259 154776 80504 154777 77490 154777 80505 154777 80505 154778 77490 154778 77402 154778 80505 154779 77402 154779 77398 154779 77398 154780 77402 154780 80357 154780 77398 154781 80357 154781 77399 154781 77399 154782 80357 154782 77400 154782 77399 154783 77400 154783 77401 154783 77401 154784 77400 154784 80355 154784 77401 154785 80355 154785 80424 154785 77411 154786 81683 154786 81689 154786 77402 154787 80405 154787 77403 154787 77403 154788 80405 154788 81123 154788 77403 154789 81123 154789 77404 154789 77404 154790 81123 154790 77405 154790 77404 154791 77405 154791 81127 154791 81127 154792 77405 154792 77395 154792 77414 154793 77406 154793 77413 154793 77413 154794 77406 154794 77432 154794 81396 154795 77415 154795 80416 154795 81881 154796 77407 154796 80416 154796 80416 154797 77407 154797 77408 154797 80416 154798 77408 154798 81364 154798 80943 154799 80942 154799 80948 154799 80948 154800 80942 154800 77409 154800 80948 154801 77409 154801 77410 154801 77425 154802 81517 154802 77365 154802 77365 154803 81517 154803 77411 154803 77365 154804 77411 154804 81678 154804 81678 154805 77411 154805 81689 154805 80259 154806 80410 154806 80258 154806 80259 154807 80261 154807 77397 154807 77397 154808 80261 154808 80262 154808 77397 154809 80262 154809 80264 154809 80948 154810 80371 154810 80414 154810 80414 154811 80371 154811 77412 154811 80414 154812 77412 154812 77413 154812 77413 154813 77412 154813 77431 154813 77413 154814 77431 154814 77414 154814 77415 154815 80417 154815 80416 154815 80416 154816 80417 154816 80419 154816 80416 154817 80419 154817 80414 154817 80414 154818 80419 154818 80420 154818 80414 154819 80420 154819 80948 154819 80948 154820 80420 154820 80423 154820 80948 154821 80423 154821 80940 154821 81364 154822 77435 154822 81449 154822 81344 154823 77423 154823 81343 154823 81343 154824 77423 154824 81391 154824 81343 154825 81391 154825 81460 154825 80424 154826 80355 154826 77416 154826 77416 154827 80355 154827 80351 154827 77416 154828 80351 154828 77417 154828 77417 154829 80351 154829 80349 154829 77417 154830 80349 154830 80423 154830 80423 154831 80349 154831 77418 154831 80423 154832 77418 154832 80940 154832 80264 154833 77419 154833 77397 154833 77397 154834 77419 154834 80255 154834 77397 154835 80255 154835 80507 154835 80507 154836 80255 154836 77420 154836 80507 154837 77420 154837 77421 154837 77421 154838 77420 154838 80805 154838 77421 154839 80805 154839 77639 154839 77639 154840 80805 154840 80808 154840 77639 154841 80808 154841 80807 154841 81364 154842 81449 154842 80416 154842 80416 154843 81449 154843 81394 154843 80416 154844 81394 154844 81396 154844 77428 154845 77422 154845 81660 154845 81660 154846 77422 154846 77423 154846 81660 154847 77423 154847 77424 154847 77424 154848 77423 154848 81344 154848 77424 154849 81344 154849 77425 154849 77391 154850 77426 154850 77428 154850 77428 154851 77426 154851 81674 154851 77428 154852 81674 154852 77427 154852 80734 154853 80735 154853 77431 154853 77431 154854 80735 154854 80726 154854 77431 154855 80726 154855 77414 154855 77427 154856 81677 154856 77428 154856 77428 154857 81677 154857 77429 154857 77428 154858 77429 154858 80416 154858 80416 154859 77429 154859 81373 154859 80416 154860 81373 154860 81372 154860 81359 154861 77439 154861 81454 154861 81454 154862 77439 154862 77440 154862 81454 154863 77440 154863 77430 154863 77430 154864 77440 154864 77367 154864 80732 154865 80731 154865 77431 154865 77431 154866 80731 154866 80730 154866 77431 154867 80730 154867 80734 154867 77441 154868 77442 154868 77432 154868 77432 154869 77442 154869 80412 154869 77432 154870 80412 154870 77413 154870 81372 154871 77433 154871 80416 154871 80416 154872 77433 154872 77434 154872 80416 154873 77434 154873 81892 154873 81364 154874 77436 154874 77435 154874 77435 154875 77436 154875 81361 154875 77435 154876 81361 154876 81454 154876 81454 154877 81361 154877 81360 154877 81454 154878 81360 154878 81359 154878 81892 154879 77437 154879 80416 154879 80416 154880 77437 154880 81896 154880 80416 154881 81896 154881 81881 154881 82035 154882 82038 154882 77438 154882 77438 154883 82038 154883 82037 154883 77438 154884 82037 154884 82036 154884 82036 154885 82037 154885 82029 154885 82036 154886 82029 154886 77439 154886 77439 154887 82029 154887 81505 154887 77439 154888 81505 154888 77440 154888 77441 154889 80360 154889 77442 154889 77442 154890 80360 154890 77443 154890 77442 154891 77443 154891 80742 154891 80258 154892 80410 154892 77444 154892 77444 154893 80410 154893 77442 154893 77444 154894 77442 154894 77445 154894 77445 154895 77442 154895 80742 154895 77445 154896 80742 154896 80743 154896 77554 154897 77308 154897 77572 154897 77446 154898 77793 154898 77447 154898 77480 154899 77590 154899 77591 154899 77590 154900 77609 154900 77608 154900 77448 154901 77449 154901 77450 154901 77461 154902 77462 154902 77471 154902 78494 154903 77452 154903 77451 154903 77451 154904 77452 154904 77460 154904 78489 154905 77453 154905 77456 154905 77456 154906 77453 154906 77454 154906 77456 154907 77454 154907 77487 154907 78494 154908 78496 154908 77566 154908 77566 154909 78496 154909 77455 154909 77566 154910 77455 154910 77456 154910 77456 154911 77455 154911 77457 154911 77456 154912 77457 154912 78489 154912 77454 154913 78490 154913 77487 154913 77487 154914 78490 154914 77459 154914 77487 154915 77459 154915 77458 154915 77459 154916 78492 154916 77458 154916 77458 154917 78492 154917 77460 154917 77458 154918 77460 154918 77599 154918 80214 154919 77614 154919 77465 154919 77461 154920 77463 154920 77462 154920 77462 154921 77463 154921 77464 154921 77462 154922 77464 154922 77465 154922 77465 154923 77464 154923 77466 154923 77465 154924 77466 154924 80214 154924 77614 154925 77467 154925 77474 154925 77474 154926 77467 154926 77468 154926 77474 154927 77468 154927 77469 154927 77469 154928 77468 154928 77470 154928 77469 154929 77470 154929 80217 154929 77478 154930 77584 154930 77471 154930 77471 154931 77584 154931 80220 154931 77471 154932 80220 154932 77461 154932 77448 154933 77450 154933 80489 154933 80496 154934 77469 154934 77473 154934 77473 154935 77469 154935 77472 154935 77473 154936 77472 154936 80494 154936 80494 154937 77472 154937 77618 154937 80496 154938 80497 154938 77469 154938 77469 154939 80497 154939 80499 154939 77469 154940 80499 154940 77474 154940 77474 154941 80499 154941 80486 154941 77474 154942 80486 154942 80488 154942 82257 154943 77595 154943 77475 154943 77475 154944 77595 154944 82254 154944 82257 154945 82259 154945 77595 154945 77595 154946 82259 154946 77476 154946 77595 154947 77476 154947 77458 154947 77458 154948 77476 154948 77477 154948 77458 154949 77477 154949 77485 154949 77471 154950 82238 154950 77478 154950 77478 154951 82238 154951 82237 154951 77478 154952 82237 154952 77479 154952 77479 154953 82237 154953 82236 154953 77479 154954 82236 154954 77595 154954 77595 154955 82236 154955 82235 154955 77595 154956 82235 154956 82254 154956 77516 154957 77482 154957 79522 154957 77480 154958 77591 154958 77481 154958 79522 154959 77482 154959 77483 154959 77482 154960 77484 154960 77483 154960 77483 154961 77484 154961 82222 154961 77483 154962 82222 154962 77531 154962 77531 154963 82222 154963 82225 154963 77531 154964 82225 154964 82991 154964 77578 154965 77583 154965 77515 154965 77515 154966 77583 154966 77514 154966 77447 154967 77793 154967 82231 154967 82231 154968 77793 154968 77795 154968 82231 154969 77795 154969 82232 154969 77485 154970 82265 154970 77458 154970 77458 154971 82265 154971 77486 154971 77458 154972 77486 154972 77487 154972 77487 154973 77486 154973 77488 154973 77487 154974 77488 154974 77456 154974 77456 154975 77488 154975 82232 154975 77456 154976 82232 154976 77797 154976 77797 154977 82232 154977 77795 154977 77604 154978 77725 154978 77722 154978 77615 154979 77611 154979 77366 154979 77621 154980 77622 154980 77720 154980 77720 154981 77622 154981 77710 154981 77710 154982 77622 154982 77489 154982 77489 154983 77622 154983 77490 154983 77489 154984 77490 154984 77491 154984 77491 154985 77490 154985 77389 154985 77491 154986 77389 154986 77714 154986 77714 154987 77389 154987 77492 154987 77714 154988 77492 154988 77712 154988 77712 154989 77492 154989 77610 154989 77712 154990 77610 154990 77720 154990 77493 154991 77707 154991 77504 154991 77690 154992 77572 154992 77570 154992 77582 154993 77494 154993 77495 154993 77568 154994 77569 154994 77570 154994 77570 154995 77569 154995 77496 154995 77570 154996 77496 154996 77690 154996 77692 154997 77497 154997 77567 154997 77498 154998 77500 154998 77499 154998 77499 154999 77500 154999 77571 154999 77499 155000 77571 155000 78413 155000 78413 155001 77571 155001 77573 155001 78413 155002 77573 155002 78416 155002 78416 155003 77573 155003 77352 155003 78416 155004 77352 155004 78556 155004 77509 155005 79395 155005 77506 155005 77506 155006 79395 155006 77501 155006 77506 155007 77501 155007 77507 155007 77507 155008 77501 155008 77503 155008 77507 155009 77503 155009 77502 155009 77502 155010 77503 155010 77563 155010 77502 155011 77563 155011 77702 155011 77702 155012 77563 155012 77550 155012 77702 155013 77550 155013 77708 155013 77708 155014 77550 155014 77580 155014 77708 155015 77580 155015 77707 155015 77518 155016 79444 155016 77504 155016 79396 155017 79441 155017 79443 155017 79444 155018 77505 155018 77504 155018 77504 155019 77505 155019 77506 155019 77504 155020 77506 155020 77493 155020 77493 155021 77506 155021 77507 155021 77505 155022 77508 155022 77506 155022 77506 155023 77508 155023 79431 155023 77506 155024 79431 155024 77509 155024 79431 155025 79434 155025 77509 155025 77509 155026 79434 155026 79437 155026 77509 155027 79437 155027 77510 155027 77510 155028 79437 155028 79438 155028 77510 155029 79438 155029 77511 155029 77511 155030 79438 155030 77512 155030 77511 155031 77512 155031 79396 155031 79396 155032 77512 155032 77513 155032 79396 155033 77513 155033 79441 155033 77514 155034 77516 155034 77515 155034 77515 155035 77516 155035 79522 155035 77515 155036 79522 155036 77517 155036 77517 155037 79522 155037 79396 155037 77517 155038 79396 155038 77504 155038 77504 155039 79396 155039 79443 155039 77504 155040 79443 155040 77518 155040 81417 155041 77519 155041 81513 155041 77519 155042 81419 155042 81513 155042 81513 155043 81419 155043 77520 155043 81513 155044 77520 155044 81514 155044 81514 155045 77520 155045 77521 155045 81514 155046 77521 155046 81388 155046 81388 155047 77521 155047 77522 155047 81388 155048 77522 155048 77523 155048 77523 155049 77522 155049 81424 155049 77523 155050 81424 155050 77524 155050 77524 155051 81427 155051 77525 155051 81427 155052 77526 155052 77525 155052 77525 155053 77526 155053 77527 155053 77525 155054 77527 155054 77528 155054 77528 155055 77527 155055 81416 155055 81416 155056 81417 155056 77528 155056 77528 155057 81417 155057 81513 155057 77528 155058 81513 155058 77529 155058 77529 155059 81513 155059 77530 155059 77529 155060 77530 155060 77591 155060 77591 155061 77530 155061 77531 155061 77591 155062 77531 155062 77481 155062 77481 155063 77531 155063 82991 155063 77524 155064 77525 155064 77523 155064 77523 155065 77525 155065 77603 155065 77523 155066 77603 155066 81386 155066 81386 155067 77603 155067 77440 155067 81386 155068 77440 155068 81505 155068 80405 155069 77402 155069 77533 155069 80405 155070 77533 155070 77532 155070 77532 155071 77533 155071 77620 155071 77532 155072 77620 155072 77534 155072 77535 155073 77536 155073 77594 155073 77535 155074 77594 155074 80482 155074 77543 155075 80481 155075 80482 155075 77536 155076 80483 155076 77594 155076 77594 155077 80483 155077 80472 155077 77594 155078 80472 155078 77620 155078 77620 155079 80472 155079 77537 155079 77537 155080 80474 155080 77620 155080 77620 155081 80474 155081 77538 155081 77620 155082 77538 155082 77534 155082 77534 155083 77538 155083 80476 155083 77534 155084 80476 155084 77539 155084 77539 155085 80476 155085 80479 155085 77539 155086 80479 155086 77541 155086 77541 155087 80479 155087 77540 155087 77541 155088 77540 155088 77542 155088 77540 155089 80481 155089 77542 155089 77542 155090 80481 155090 77543 155090 77542 155091 77543 155091 80406 155091 80406 155092 77543 155092 77596 155092 80406 155093 77596 155093 77544 155093 77544 155094 77596 155094 77597 155094 78422 155095 78420 155095 77546 155095 77546 155096 78420 155096 77545 155096 77546 155097 77545 155097 77600 155097 77600 155098 77545 155098 78419 155098 77600 155099 78419 155099 77598 155099 77598 155100 78419 155100 77547 155100 77598 155101 77547 155101 77597 155101 77597 155102 77547 155102 82266 155102 77597 155103 82266 155103 77544 155103 77806 155104 77550 155104 77548 155104 77548 155105 77550 155105 77563 155105 77548 155106 77563 155106 77549 155106 77549 155107 77563 155107 77818 155107 77806 155108 77551 155108 77550 155108 77550 155109 77551 155109 77809 155109 77550 155110 77809 155110 77582 155110 77809 155111 77552 155111 77582 155111 77582 155112 77552 155112 77553 155112 77582 155113 77553 155113 77494 155113 77494 155114 77553 155114 77812 155114 77494 155115 77812 155115 77813 155115 77554 155116 77815 155116 77555 155116 77554 155117 77555 155117 77562 155117 77566 155118 77801 155118 77567 155118 77567 155119 77801 155119 77556 155119 77567 155120 77556 155120 77557 155120 77557 155121 77556 155121 77804 155121 77557 155122 77804 155122 77558 155122 77558 155123 77804 155123 77559 155123 77558 155124 77559 155124 77447 155124 77447 155125 77559 155125 77790 155125 77447 155126 77790 155126 77446 155126 77797 155127 77799 155127 77456 155127 77456 155128 77799 155128 77560 155128 77456 155129 77560 155129 77566 155129 77566 155130 77560 155130 77561 155130 77566 155131 77561 155131 77801 155131 77555 155132 77818 155132 77562 155132 77562 155133 77818 155133 77563 155133 77562 155134 77563 155134 77564 155134 77564 155135 77563 155135 77503 155135 77564 155136 77503 155136 77303 155136 77303 155137 77503 155137 77501 155137 77303 155138 77501 155138 77565 155138 77565 155139 77501 155139 79395 155139 77690 155140 77495 155140 77572 155140 77572 155141 77495 155141 77494 155141 77572 155142 77494 155142 77554 155142 77554 155143 77494 155143 77813 155143 77554 155144 77813 155144 77815 155144 78494 155145 77566 155145 77452 155145 77452 155146 77566 155146 77567 155146 77452 155147 77567 155147 77568 155147 77568 155148 77567 155148 77497 155148 77568 155149 77497 155149 77569 155149 77460 155150 77452 155150 77599 155150 77599 155151 77452 155151 77568 155151 77599 155152 77568 155152 77500 155152 77500 155153 77568 155153 77570 155153 77500 155154 77570 155154 77571 155154 77571 155155 77570 155155 77572 155155 77571 155156 77572 155156 77573 155156 77573 155157 77572 155157 77308 155157 77573 155158 77308 155158 77352 155158 79446 155159 77574 155159 77581 155159 79450 155160 77515 155160 77575 155160 77575 155161 77515 155161 77517 155161 77575 155162 77517 155162 79449 155162 79449 155163 77517 155163 79447 155163 79450 155164 77576 155164 77515 155164 77515 155165 77576 155165 77577 155165 77515 155166 77577 155166 77578 155166 77578 155167 77577 155167 79451 155167 79451 155168 79453 155168 77578 155168 77578 155169 79453 155169 79445 155169 77578 155170 79445 155170 77581 155170 77581 155171 79445 155171 77579 155171 77581 155172 77579 155172 79446 155172 77707 155173 77580 155173 77504 155173 77504 155174 77580 155174 77581 155174 77504 155175 77581 155175 77517 155175 77517 155176 77581 155176 77574 155176 77517 155177 77574 155177 79447 155177 77495 155178 77692 155178 77582 155178 77582 155179 77692 155179 77567 155179 77582 155180 77567 155180 77550 155180 77550 155181 77567 155181 77557 155181 77550 155182 77557 155182 77580 155182 77580 155183 77557 155183 77558 155183 77580 155184 77558 155184 77581 155184 77581 155185 77558 155185 77447 155185 77581 155186 77447 155186 77578 155186 77578 155187 77447 155187 82231 155187 77578 155188 82231 155188 77583 155188 77595 155189 77619 155189 77479 155189 77479 155190 77619 155190 77472 155190 77479 155191 77472 155191 77478 155191 77478 155192 77472 155192 77469 155192 77478 155193 77469 155193 77584 155193 77584 155194 77469 155194 80217 155194 77607 155195 77589 155195 77592 155195 77593 155196 77585 155196 77529 155196 77529 155197 77585 155197 77586 155197 77529 155198 77586 155198 77528 155198 77528 155199 77586 155199 81434 155199 77528 155200 81434 155200 81436 155200 77605 155201 81437 155201 81439 155201 81439 155202 77587 155202 77605 155202 77605 155203 77587 155203 81440 155203 77605 155204 81440 155204 77607 155204 77607 155205 81440 155205 77588 155205 77607 155206 77588 155206 77589 155206 77590 155207 77608 155207 77591 155207 77591 155208 77608 155208 77607 155208 77591 155209 77607 155209 77529 155209 77529 155210 77607 155210 77592 155210 77529 155211 77592 155211 77593 155211 80482 155212 77594 155212 77543 155212 77543 155213 77594 155213 77619 155213 77543 155214 77619 155214 77596 155214 77596 155215 77619 155215 77595 155215 77596 155216 77595 155216 77597 155216 77597 155217 77595 155217 77458 155217 77597 155218 77458 155218 77598 155218 77598 155219 77458 155219 77599 155219 77598 155220 77599 155220 77600 155220 77600 155221 77599 155221 77500 155221 77600 155222 77500 155222 77546 155222 77546 155223 77500 155223 77498 155223 77546 155224 77498 155224 78422 155224 77725 155225 77606 155225 77724 155225 77724 155226 77606 155226 77615 155226 77724 155227 77615 155227 77601 155227 77601 155228 77615 155228 77366 155228 77601 155229 77366 155229 77721 155229 77721 155230 77366 155230 77440 155230 77721 155231 77440 155231 77602 155231 77602 155232 77440 155232 77603 155232 77602 155233 77603 155233 77722 155233 77722 155234 77603 155234 77525 155234 77722 155235 77525 155235 77604 155235 77604 155236 77525 155236 77528 155236 77604 155237 77528 155237 77605 155237 77605 155238 77528 155238 81436 155238 77605 155239 81436 155239 81437 155239 77725 155240 77604 155240 77606 155240 77606 155241 77604 155241 77605 155241 77606 155242 77605 155242 77465 155242 77465 155243 77605 155243 77607 155243 77465 155244 77607 155244 77462 155244 77462 155245 77607 155245 77608 155245 77462 155246 77608 155246 77471 155246 77471 155247 77608 155247 77609 155247 77471 155248 77609 155248 82238 155248 77720 155249 77610 155249 77621 155249 77621 155250 77610 155250 77474 155250 77621 155251 77474 155251 77450 155251 77450 155252 77474 155252 80488 155252 77450 155253 80488 155253 80489 155253 80224 155254 77612 155254 77611 155254 77611 155255 77612 155255 77389 155255 80230 155256 77492 155256 80229 155256 80229 155257 77492 155257 77613 155257 77614 155258 77474 155258 77465 155258 77465 155259 77474 155259 77610 155259 77465 155260 77610 155260 77606 155260 77606 155261 77610 155261 77492 155261 77606 155262 77492 155262 77615 155262 77615 155263 77492 155263 80230 155263 77615 155264 80230 155264 80232 155264 80232 155265 77616 155265 77615 155265 77615 155266 77616 155266 80233 155266 77615 155267 80233 155267 77611 155267 77611 155268 80233 155268 80223 155268 77611 155269 80223 155269 80224 155269 77612 155270 80226 155270 77389 155270 77389 155271 80226 155271 80228 155271 77389 155272 80228 155272 77492 155272 77492 155273 80228 155273 77617 155273 77492 155274 77617 155274 77613 155274 77618 155275 77472 155275 80491 155275 80491 155276 77472 155276 77619 155276 80491 155277 77619 155277 77449 155277 77449 155278 77619 155278 77594 155278 77449 155279 77594 155279 77450 155279 77450 155280 77594 155280 77620 155280 77450 155281 77620 155281 77621 155281 77621 155282 77620 155282 77533 155282 77621 155283 77533 155283 77622 155283 77622 155284 77533 155284 77402 155284 77622 155285 77402 155285 77490 155285 77623 155286 79524 155286 77658 155286 77624 155287 77645 155287 77638 155287 77281 155288 77279 155288 77629 155288 78447 155289 77625 155289 77626 155289 77626 155290 77625 155290 77627 155290 77626 155291 77627 155291 78449 155291 77630 155292 77631 155292 77686 155292 77686 155293 77631 155293 78453 155293 77686 155294 78453 155294 77687 155294 77687 155295 78453 155295 77628 155295 77687 155296 77628 155296 77683 155296 77683 155297 77628 155297 77629 155297 77683 155298 77629 155298 77630 155298 77630 155299 77629 155299 77631 155299 77631 155300 77629 155300 77279 155300 77631 155301 77279 155301 78452 155301 77633 155302 78566 155302 77628 155302 77628 155303 78566 155303 78565 155303 77628 155304 78565 155304 77629 155304 77629 155305 78565 155305 77632 155305 77629 155306 77632 155306 77281 155306 77671 155307 77633 155307 77670 155307 77670 155308 77633 155308 82260 155308 82260 155309 77633 155309 77628 155309 82260 155310 77628 155310 77627 155310 77627 155311 77628 155311 78453 155311 77627 155312 78453 155312 78449 155312 82240 155313 77736 155313 77634 155313 77736 155314 82240 155314 77735 155314 77624 155315 77638 155315 77635 155315 82240 155316 82239 155316 77735 155316 77735 155317 82239 155317 82252 155317 77735 155318 82252 155318 77637 155318 77637 155319 82252 155319 82250 155319 77639 155320 80400 155320 77638 155320 77638 155321 80400 155321 77636 155321 82250 155322 77635 155322 77637 155322 77637 155323 77635 155323 77638 155323 77637 155324 77638 155324 80398 155324 80398 155325 77638 155325 77636 155325 77644 155326 77640 155326 77638 155326 77638 155327 77640 155327 77639 155327 77639 155328 77640 155328 77641 155328 77639 155329 77641 155329 77370 155329 77370 155330 77641 155330 77642 155330 77370 155331 77642 155331 77643 155331 82234 155332 80253 155332 80254 155332 82234 155333 80254 155333 77645 155333 77642 155334 77644 155334 77643 155334 77643 155335 77644 155335 77638 155335 77643 155336 77638 155336 80428 155336 80428 155337 77638 155337 77645 155337 80428 155338 77645 155338 80430 155338 80430 155339 77645 155339 80254 155339 77646 155340 77648 155340 77647 155340 77647 155341 77648 155341 82234 155341 82234 155342 77648 155342 77649 155342 82234 155343 77649 155343 80253 155343 77769 155344 77650 155344 77652 155344 77650 155345 77769 155345 77274 155345 77274 155346 77769 155346 77651 155346 77274 155347 77651 155347 77273 155347 77273 155348 77651 155348 77373 155348 77273 155349 77373 155349 77652 155349 77652 155350 77373 155350 77767 155350 77652 155351 77767 155351 77769 155351 81509 155352 77373 155352 81381 155352 81381 155353 77373 155353 77651 155353 81381 155354 77651 155354 77653 155354 77653 155355 77651 155355 81516 155355 81515 155356 81516 155356 82990 155356 82990 155357 81516 155357 77654 155357 77654 155358 81516 155358 77651 155358 77654 155359 77651 155359 77647 155359 77647 155360 77651 155360 77769 155360 77647 155361 77769 155361 77646 155361 82243 155362 77739 155362 77676 155362 77739 155363 82243 155363 79526 155363 82243 155364 82248 155364 79526 155364 79526 155365 82248 155365 77655 155365 79526 155366 77655 155366 79524 155366 79524 155367 77655 155367 82996 155367 79524 155368 82996 155368 77658 155368 77658 155369 82996 155369 77656 155369 77658 155370 77656 155370 77657 155370 77661 155371 79389 155371 77658 155371 77658 155372 79389 155372 77659 155372 77658 155373 77659 155373 77623 155373 77660 155374 79389 155374 77280 155374 77280 155375 79389 155375 77661 155375 77280 155376 77661 155376 79411 155376 79411 155377 77661 155377 79410 155377 79409 155378 79410 155378 77665 155378 77665 155379 79410 155379 77662 155379 77662 155380 79410 155380 77661 155380 77662 155381 77661 155381 77663 155381 77663 155382 77661 155382 77658 155382 77663 155383 77658 155383 77666 155383 78447 155384 77664 155384 77625 155384 77625 155385 77664 155385 77669 155385 77625 155386 77669 155386 77657 155386 77665 155387 77666 155387 79409 155387 79409 155388 77666 155388 77658 155388 79409 155389 77658 155389 77667 155389 77667 155390 77658 155390 77657 155390 77667 155391 77657 155391 77668 155391 77668 155392 77657 155392 77669 155392 77670 155393 82263 155393 77671 155393 77671 155394 82263 155394 82261 155394 77671 155395 82261 155395 77736 155395 77736 155396 82261 155396 77672 155396 77736 155397 77672 155397 77634 155397 77634 155398 77672 155398 77674 155398 77634 155399 77674 155399 77673 155399 77673 155400 77674 155400 83688 155400 77673 155401 83688 155401 77676 155401 77676 155402 83688 155402 83687 155402 77676 155403 83687 155403 82243 155403 82990 155404 82989 155404 81515 155404 81515 155405 82989 155405 82986 155405 81515 155406 82986 155406 77739 155406 77739 155407 82986 155407 77675 155407 77739 155408 77675 155408 77676 155408 77676 155409 77675 155409 77677 155409 77676 155410 77677 155410 77673 155410 77673 155411 77677 155411 83686 155411 77673 155412 83686 155412 77634 155412 77634 155413 83686 155413 77678 155413 77634 155414 77678 155414 82240 155414 77640 155415 77680 155415 77641 155415 77642 155416 77679 155416 77644 155416 77642 155417 77641 155417 77679 155417 77679 155418 77641 155418 77680 155418 77679 155419 77680 155419 77644 155419 77644 155420 77680 155420 77640 155420 77663 155421 77681 155421 77662 155421 77665 155422 77682 155422 77666 155422 77663 155423 77666 155423 77681 155423 77681 155424 77666 155424 77682 155424 77681 155425 77682 155425 77662 155425 77662 155426 77682 155426 77665 155426 77683 155427 77684 155427 77687 155427 77686 155428 77685 155428 77630 155428 77686 155429 77687 155429 77685 155429 77685 155430 77687 155430 77684 155430 77685 155431 77684 155431 77630 155431 77630 155432 77684 155432 77683 155432 77695 155433 77688 155433 77689 155433 77689 155434 77688 155434 77690 155434 77689 155435 77690 155435 77693 155435 77693 155436 77690 155436 77496 155436 77693 155437 77496 155437 77569 155437 77697 155438 77696 155438 77495 155438 77495 155439 77696 155439 77691 155439 77495 155440 77691 155440 77692 155440 77692 155441 77691 155441 77694 155441 77692 155442 77694 155442 77497 155442 77569 155443 77497 155443 77693 155443 77693 155444 77497 155444 77694 155444 77693 155445 77694 155445 77689 155445 77689 155446 77694 155446 77691 155446 77689 155447 77691 155447 77695 155447 77695 155448 77691 155448 77696 155448 77695 155449 77696 155449 77688 155449 77688 155450 77696 155450 77697 155450 77688 155451 77697 155451 77690 155451 77690 155452 77697 155452 77495 155452 77698 155453 77707 155453 77493 155453 77699 155454 77698 155454 77700 155454 77700 155455 77698 155455 77493 155455 77700 155456 77493 155456 77701 155456 77701 155457 77493 155457 77507 155457 77702 155458 77708 155458 77704 155458 77705 155459 77502 155459 77703 155459 77703 155460 77502 155460 77702 155460 77703 155461 77702 155461 77706 155461 77706 155462 77702 155462 77704 155462 77507 155463 77502 155463 77701 155463 77701 155464 77502 155464 77705 155464 77701 155465 77705 155465 77700 155465 77700 155466 77705 155466 77703 155466 77700 155467 77703 155467 77699 155467 77699 155468 77703 155468 77706 155468 77699 155469 77706 155469 77698 155469 77698 155470 77706 155470 77704 155470 77698 155471 77704 155471 77707 155471 77707 155472 77704 155472 77708 155472 77719 155473 77720 155473 77710 155473 77717 155474 77719 155474 77709 155474 77709 155475 77719 155475 77710 155475 77709 155476 77710 155476 77711 155476 77711 155477 77710 155477 77489 155477 77714 155478 77712 155478 77715 155478 77716 155479 77491 155479 77713 155479 77713 155480 77491 155480 77714 155480 77713 155481 77714 155481 77718 155481 77718 155482 77714 155482 77715 155482 77489 155483 77491 155483 77711 155483 77711 155484 77491 155484 77716 155484 77711 155485 77716 155485 77709 155485 77709 155486 77716 155486 77713 155486 77709 155487 77713 155487 77717 155487 77717 155488 77713 155488 77718 155488 77717 155489 77718 155489 77719 155489 77719 155490 77718 155490 77715 155490 77719 155491 77715 155491 77720 155491 77720 155492 77715 155492 77712 155492 77729 155493 77732 155493 77728 155493 77728 155494 77732 155494 77721 155494 77728 155495 77721 155495 77726 155495 77726 155496 77721 155496 77602 155496 77726 155497 77602 155497 77722 155497 77731 155498 77730 155498 77601 155498 77601 155499 77730 155499 77723 155499 77601 155500 77723 155500 77724 155500 77724 155501 77723 155501 77727 155501 77724 155502 77727 155502 77725 155502 77722 155503 77725 155503 77726 155503 77726 155504 77725 155504 77727 155504 77726 155505 77727 155505 77728 155505 77728 155506 77727 155506 77723 155506 77728 155507 77723 155507 77729 155507 77729 155508 77723 155508 77730 155508 77729 155509 77730 155509 77732 155509 77732 155510 77730 155510 77731 155510 77732 155511 77731 155511 77721 155511 77721 155512 77731 155512 77601 155512 79731 155513 79741 155513 77734 155513 79727 155514 79731 155514 77733 155514 77733 155515 79731 155515 77734 155515 77733 155516 77734 155516 77294 155516 80786 155517 80796 155517 80793 155517 80787 155518 80786 155518 77420 155518 77420 155519 80786 155519 80793 155519 77420 155520 80793 155520 80805 155520 77735 155521 77737 155521 77736 155521 77736 155522 77737 155522 77738 155522 77736 155523 77738 155523 77671 155523 79526 155524 79525 155524 77739 155524 77739 155525 79525 155525 83839 155525 77739 155526 83839 155526 81515 155526 77741 155527 81404 155527 77740 155527 77741 155528 77740 155528 83901 155528 83901 155529 77740 155529 82148 155529 83901 155530 82148 155530 77742 155530 77742 155531 82148 155531 81385 155531 77742 155532 81385 155532 81382 155532 83897 155533 81157 155533 81238 155533 83897 155534 81238 155534 83898 155534 83898 155535 81238 155535 77744 155535 83898 155536 77744 155536 77743 155536 77743 155537 77744 155537 77745 155537 77743 155538 77745 155538 80444 155538 77746 155539 83892 155539 83891 155539 77746 155540 83891 155540 80124 155540 80124 155541 83891 155541 83890 155541 80124 155542 83890 155542 80126 155542 80126 155543 83890 155543 83889 155543 80126 155544 83889 155544 80127 155544 78461 155545 77747 155545 78460 155545 78460 155546 77747 155546 77748 155546 77747 155547 77749 155547 77748 155547 77748 155548 77749 155548 77750 155548 77748 155549 77750 155549 77752 155549 79250 155550 83887 155550 77751 155550 77751 155551 83887 155551 77752 155551 77751 155552 77752 155552 77753 155552 77753 155553 77752 155553 77750 155553 79294 155554 78410 155554 77754 155554 79294 155555 77754 155555 79292 155555 79292 155556 77754 155556 77756 155556 79292 155557 77756 155557 77755 155557 77755 155558 77756 155558 78084 155558 77755 155559 78084 155559 78083 155559 79337 155560 79343 155560 80144 155560 79337 155561 80144 155561 77758 155561 77758 155562 80144 155562 77757 155562 77758 155563 77757 155563 77759 155563 77759 155564 77757 155564 79392 155564 77759 155565 79392 155565 79391 155565 80245 155566 80241 155566 81249 155566 80245 155567 81249 155567 83876 155567 83876 155568 81249 155568 81252 155568 83876 155569 81252 155569 77760 155569 77760 155570 81252 155570 81250 155570 77760 155571 81250 155571 83875 155571 83875 155572 81250 155572 81182 155572 83875 155573 81182 155573 80401 155573 81507 155574 81379 155574 77761 155574 81507 155575 77761 155575 77762 155575 77762 155576 77761 155576 83870 155576 77762 155577 83870 155577 82193 155577 82193 155578 83870 155578 77763 155578 82193 155579 77763 155579 77764 155579 77764 155580 77763 155580 81329 155580 77764 155581 81329 155581 81335 155581 80431 155582 77421 155582 77370 155582 77370 155583 77643 155583 77765 155583 77765 155584 77643 155584 78225 155584 80431 155585 77370 155585 81169 155585 81169 155586 77370 155586 77765 155586 81169 155587 77765 155587 77766 155587 77379 155588 77768 155588 77767 155588 77767 155589 77768 155589 82202 155589 78222 155590 77769 155590 77770 155590 77770 155591 77769 155591 77767 155591 77770 155592 77767 155592 82086 155592 82086 155593 77767 155593 82202 155593 78283 155594 79290 155594 77771 155594 77771 155595 79290 155595 79272 155595 77771 155596 79272 155596 77772 155596 80171 155597 80071 155597 77773 155597 77773 155598 80071 155598 77774 155598 77773 155599 77774 155599 77775 155599 81281 155600 78229 155600 77776 155600 77776 155601 78229 155601 78268 155601 77776 155602 78268 155602 78269 155602 78224 155603 82172 155603 77777 155603 77777 155604 82172 155604 82089 155604 77777 155605 82089 155605 77778 155605 81191 155606 77779 155606 77780 155606 77780 155607 77779 155607 77856 155607 77780 155608 77856 155608 77781 155608 77781 155609 77856 155609 77867 155609 77781 155610 77867 155610 80249 155610 77784 155611 82113 155611 82107 155611 77782 155612 77783 155612 80387 155612 80387 155613 77783 155613 77784 155613 80387 155614 77784 155614 80389 155614 80389 155615 77784 155615 82107 155615 77785 155616 79166 155616 77786 155616 77785 155617 77786 155617 77787 155617 77787 155618 77786 155618 79169 155618 77787 155619 79169 155619 77844 155619 77824 155620 77788 155620 77887 155620 77887 155621 77788 155621 80140 155621 77887 155622 80140 155622 77889 155622 81153 155623 77850 155623 81244 155623 81244 155624 77850 155624 77855 155624 81244 155625 77855 155625 81203 155625 81203 155626 77855 155626 77857 155626 82134 155627 82068 155627 77789 155627 77789 155628 82068 155628 77881 155628 77789 155629 77881 155629 77882 155629 77790 155630 77791 155630 77446 155630 77446 155631 77791 155631 77792 155631 77446 155632 77792 155632 77793 155632 77793 155633 77792 155633 77794 155633 77793 155634 77794 155634 77795 155634 77795 155635 77794 155635 77796 155635 77795 155636 77796 155636 77797 155636 77797 155637 77796 155637 78394 155637 77797 155638 78394 155638 77799 155638 77799 155639 78394 155639 77798 155639 77799 155640 77798 155640 77560 155640 77560 155641 77798 155641 77800 155641 77560 155642 77800 155642 77561 155642 77561 155643 77800 155643 78397 155643 77561 155644 78397 155644 77801 155644 77801 155645 78397 155645 77802 155645 77801 155646 77802 155646 77556 155646 77556 155647 77802 155647 77803 155647 77556 155648 77803 155648 77804 155648 77804 155649 77803 155649 78401 155649 77804 155650 78401 155650 77559 155650 77559 155651 78401 155651 78402 155651 77559 155652 78402 155652 77790 155652 77790 155653 78402 155653 77791 155653 77548 155654 77805 155654 77806 155654 77806 155655 77805 155655 77807 155655 77806 155656 77807 155656 77551 155656 77551 155657 77807 155657 77808 155657 77551 155658 77808 155658 77809 155658 77809 155659 77808 155659 78400 155659 77809 155660 78400 155660 77552 155660 77552 155661 78400 155661 78390 155661 77552 155662 78390 155662 77553 155662 77553 155663 78390 155663 77810 155663 77553 155664 77810 155664 77812 155664 77812 155665 77810 155665 77811 155665 77812 155666 77811 155666 77813 155666 77813 155667 77811 155667 77814 155667 77813 155668 77814 155668 77815 155668 77815 155669 77814 155669 77816 155669 77815 155670 77816 155670 77555 155670 77555 155671 77816 155671 77817 155671 77555 155672 77817 155672 77818 155672 77818 155673 77817 155673 77819 155673 77818 155674 77819 155674 77549 155674 77549 155675 77819 155675 77820 155675 77549 155676 77820 155676 77548 155676 77548 155677 77820 155677 77805 155677 78095 155678 78794 155678 77821 155678 78096 155679 78095 155679 77822 155679 77822 155680 78095 155680 77821 155680 77822 155681 77821 155681 78787 155681 77823 155682 83421 155682 77901 155682 79432 155683 77895 155683 77824 155683 77870 155684 77832 155684 78063 155684 77920 155685 77900 155685 77825 155685 77825 155686 77900 155686 77826 155686 77827 155687 77828 155687 77901 155687 77901 155688 77828 155688 82997 155688 77901 155689 82997 155689 77902 155689 78035 155690 78048 155690 77829 155690 77829 155691 78048 155691 82226 155691 82226 155692 78048 155692 77830 155692 77830 155693 78048 155693 77832 155693 77830 155694 77832 155694 82992 155694 77831 155695 82994 155695 77832 155695 77832 155696 82994 155696 82993 155696 77832 155697 82993 155697 82992 155697 77834 155698 77833 155698 77845 155698 77834 155699 77845 155699 82228 155699 77833 155700 82258 155700 77845 155700 77845 155701 82258 155701 82256 155701 77845 155702 82256 155702 77835 155702 77835 155703 82256 155703 82255 155703 77836 155704 82264 155704 77842 155704 77842 155705 82264 155705 82227 155705 77842 155706 82227 155706 77935 155706 77825 155707 82233 155707 77920 155707 77920 155708 82233 155708 77837 155708 77920 155709 77837 155709 77842 155709 77842 155710 77837 155710 77838 155710 77842 155711 77838 155711 77836 155711 79171 155712 77839 155712 77919 155712 77919 155713 77839 155713 79173 155713 77919 155714 79173 155714 77840 155714 79168 155715 79166 155715 77841 155715 77841 155716 79166 155716 77785 155716 77841 155717 77785 155717 83775 155717 77842 155718 77925 155718 83771 155718 83770 155719 83775 155719 77924 155719 77924 155720 83775 155720 77785 155720 77924 155721 77785 155721 77843 155721 77843 155722 77785 155722 77787 155722 77843 155723 77787 155723 77919 155723 77919 155724 77787 155724 77844 155724 77919 155725 77844 155725 79171 155725 78052 155726 77845 155726 83755 155726 83755 155727 77845 155727 83756 155727 81153 155728 83746 155728 83745 155728 77846 155729 77847 155729 83745 155729 83745 155730 77847 155730 77850 155730 83745 155731 77850 155731 81153 155731 77854 155732 77848 155732 77847 155732 77847 155733 77848 155733 77849 155733 77847 155734 77849 155734 77850 155734 77850 155735 77849 155735 80480 155735 80484 155736 77851 155736 78073 155736 78073 155737 77851 155737 77852 155737 78073 155738 77852 155738 77847 155738 77847 155739 77852 155739 77853 155739 77847 155740 77853 155740 77854 155740 80480 155741 80478 155741 77850 155741 77850 155742 80478 155742 80477 155742 77850 155743 80477 155743 77855 155743 77855 155744 80477 155744 80475 155744 77855 155745 80475 155745 80473 155745 77859 155746 77867 155746 81160 155746 81160 155747 77867 155747 77856 155747 80473 155748 80484 155748 77855 155748 77855 155749 80484 155749 78073 155749 77855 155750 78073 155750 77857 155750 77857 155751 78073 155751 77867 155751 77857 155752 77867 155752 77858 155752 77858 155753 77867 155753 77859 155753 80493 155754 77860 155754 78073 155754 78073 155755 77860 155755 80492 155755 80495 155756 77861 155756 77835 155756 77865 155757 80498 155757 77862 155757 77867 155758 80487 155758 80249 155758 80249 155759 80487 155759 80485 155759 80249 155760 80485 155760 80247 155760 80247 155761 80485 155761 80498 155761 80247 155762 80498 155762 77863 155762 77863 155763 80498 155763 77865 155763 77863 155764 77865 155764 77864 155764 77864 155765 77865 155765 80250 155765 82255 155766 77873 155766 77835 155766 77835 155767 77873 155767 77865 155767 77835 155768 77865 155768 80495 155768 80495 155769 77865 155769 77862 155769 80492 155770 80490 155770 78073 155770 78073 155771 80490 155771 77866 155771 78073 155772 77866 155772 77867 155772 77867 155773 77866 155773 77868 155773 77867 155774 77868 155774 80487 155774 77874 155775 77869 155775 77865 155775 77865 155776 77869 155776 81431 155776 81438 155777 77870 155777 77871 155777 77871 155778 77870 155778 77783 155778 77871 155779 77783 155779 77872 155779 77872 155780 77783 155780 81441 155780 77873 155781 77831 155781 77865 155781 77865 155782 77831 155782 77832 155782 77865 155783 77832 155783 77874 155783 77874 155784 77832 155784 81432 155784 81438 155785 81435 155785 77870 155785 77870 155786 81435 155786 81433 155786 77870 155787 81433 155787 77832 155787 77832 155788 81433 155788 77875 155788 77832 155789 77875 155789 81432 155789 81441 155790 77783 155790 81430 155790 81430 155791 77783 155791 77782 155791 81430 155792 77782 155792 81431 155792 77782 155793 77876 155793 81431 155793 81431 155794 77876 155794 77877 155794 81431 155795 77877 155795 77865 155795 77865 155796 77877 155796 81338 155796 77865 155797 81338 155797 80250 155797 81421 155798 77870 155798 81422 155798 81422 155799 77870 155799 77881 155799 81422 155800 77881 155800 81423 155800 81423 155801 77881 155801 81425 155801 81421 155802 81420 155802 77870 155802 77870 155803 81420 155803 77878 155803 77870 155804 77878 155804 77783 155804 77783 155805 77878 155805 77879 155805 77783 155806 77879 155806 81418 155806 81418 155807 81429 155807 77783 155807 77783 155808 81429 155808 82068 155808 77783 155809 82068 155809 82069 155809 82069 155810 82070 155810 77783 155810 77783 155811 82070 155811 82071 155811 77783 155812 82071 155812 77784 155812 81429 155813 77880 155813 82068 155813 82068 155814 77880 155814 81428 155814 82068 155815 81428 155815 77881 155815 77881 155816 81428 155816 81426 155816 77881 155817 81426 155817 81425 155817 82066 155818 77882 155818 83693 155818 83693 155819 77882 155819 77881 155819 83693 155820 77881 155820 77883 155820 77883 155821 77881 155821 77870 155821 77883 155822 77870 155822 77884 155822 77884 155823 77870 155823 78063 155823 77946 155824 77885 155824 77886 155824 79440 155825 79439 155825 77887 155825 77892 155826 79440 155826 77903 155826 77903 155827 79440 155827 77887 155827 77903 155828 77887 155828 77888 155828 77888 155829 77887 155829 77889 155829 77888 155830 77889 155830 80057 155830 79439 155831 79436 155831 77887 155831 77887 155832 79436 155832 79435 155832 77887 155833 79435 155833 77824 155833 77824 155834 79435 155834 79433 155834 77824 155835 79433 155835 79432 155835 77890 155836 77891 155836 77903 155836 77903 155837 77891 155837 79442 155837 77903 155838 79442 155838 77892 155838 77893 155839 79347 155839 77894 155839 77894 155840 79347 155840 79346 155840 77895 155841 77896 155841 77824 155841 77824 155842 77896 155842 79347 155842 77824 155843 79347 155843 77897 155843 77897 155844 79347 155844 77893 155844 77898 155845 79448 155845 77903 155845 77900 155846 79454 155846 77899 155846 77899 155847 79452 155847 77900 155847 77900 155848 79452 155848 77901 155848 77900 155849 77901 155849 77826 155849 77826 155850 77901 155850 77902 155850 77896 155851 77890 155851 79347 155851 79347 155852 77890 155852 77903 155852 79347 155853 77903 155853 77908 155853 77908 155854 77903 155854 79448 155854 78092 155855 78093 155855 77900 155855 77900 155856 78093 155856 77904 155856 77900 155857 77904 155857 79454 155857 79454 155858 77904 155858 79348 155858 79454 155859 79348 155859 77905 155859 77905 155860 79348 155860 79349 155860 77905 155861 79349 155861 77906 155861 77906 155862 79349 155862 79347 155862 77906 155863 79347 155863 77907 155863 77907 155864 79347 155864 77908 155864 79452 155865 77909 155865 77901 155865 77901 155866 77909 155866 77910 155866 77901 155867 77910 155867 77903 155867 77903 155868 77910 155868 77911 155868 77903 155869 77911 155869 77898 155869 77912 155870 77913 155870 77920 155870 77917 155871 77919 155871 78488 155871 78488 155872 77919 155872 78088 155872 78488 155873 78088 155873 77914 155873 78088 155874 78089 155874 77914 155874 77914 155875 78089 155875 77915 155875 77914 155876 77915 155876 77900 155876 77900 155877 77915 155877 77916 155877 77900 155878 77916 155878 78092 155878 77917 155879 77918 155879 77919 155879 77919 155880 77918 155880 78495 155880 77919 155881 78495 155881 77843 155881 77843 155882 78495 155882 78493 155882 77843 155883 78493 155883 77923 155883 77913 155884 78491 155884 77920 155884 77920 155885 78491 155885 77921 155885 77920 155886 77921 155886 77900 155886 77900 155887 77921 155887 77922 155887 77900 155888 77922 155888 77914 155888 77923 155889 77912 155889 77843 155889 77843 155890 77912 155890 77920 155890 77843 155891 77920 155891 77924 155891 77924 155892 77920 155892 77842 155892 77924 155893 77842 155893 83770 155893 83770 155894 77842 155894 83771 155894 82826 155895 83759 155895 82827 155895 82827 155896 83759 155896 77925 155896 77926 155897 77927 155897 77925 155897 82821 155898 77933 155898 77935 155898 77927 155899 77928 155899 77925 155899 77925 155900 77928 155900 82830 155900 77925 155901 82830 155901 82827 155901 77929 155902 77930 155902 77842 155902 77842 155903 77930 155903 77931 155903 77842 155904 77931 155904 77925 155904 77925 155905 77931 155905 82706 155905 77925 155906 82706 155906 77926 155906 82826 155907 82825 155907 83759 155907 83759 155908 82825 155908 77932 155908 83759 155909 77932 155909 77935 155909 77935 155910 77932 155910 82709 155910 77935 155911 82709 155911 82821 155911 77933 155912 77934 155912 77935 155912 77935 155913 77934 155913 77936 155913 77935 155914 77936 155914 77842 155914 77842 155915 77936 155915 82824 155915 77842 155916 82824 155916 77929 155916 83422 155917 83538 155917 77961 155917 83421 155918 83422 155918 77901 155918 77901 155919 83422 155919 77961 155919 77901 155920 77961 155920 77827 155920 77827 155921 77961 155921 77967 155921 77827 155922 77967 155922 77937 155922 77937 155923 77967 155923 78016 155923 77937 155924 78016 155924 82223 155924 83547 155925 77938 155925 77946 155925 77946 155926 77938 155926 77939 155926 83538 155927 77940 155927 77961 155927 77961 155928 77940 155928 77941 155928 77961 155929 77941 155929 78070 155929 78070 155930 77941 155930 83424 155930 78070 155931 83424 155931 77942 155931 77947 155932 77943 155932 77901 155932 77901 155933 77943 155933 83542 155933 77901 155934 83542 155934 77823 155934 77942 155935 77944 155935 78070 155935 78070 155936 77944 155936 77945 155936 78070 155937 77945 155937 77946 155937 77946 155938 77945 155938 83419 155938 77946 155939 83419 155939 83547 155939 77939 155940 77947 155940 77946 155940 77946 155941 77947 155941 77901 155941 77946 155942 77901 155942 77885 155942 77885 155943 77901 155943 77903 155943 77885 155944 77903 155944 77948 155944 77948 155945 77903 155945 77888 155945 77949 155946 82819 155946 83759 155946 77972 155947 82812 155947 77953 155947 82819 155948 82816 155948 83759 155948 83759 155949 82816 155949 77950 155949 83759 155950 77950 155950 77979 155950 77979 155951 77950 155951 77951 155951 77951 155952 82810 155952 77979 155952 77979 155953 82810 155953 77952 155953 77979 155954 77952 155954 77972 155954 77972 155955 77952 155955 82698 155955 77972 155956 82698 155956 82812 155956 77953 155957 77954 155957 77972 155957 77972 155958 77954 155958 77955 155958 77972 155959 77955 155959 77935 155959 77935 155960 77955 155960 77956 155960 77956 155961 82814 155961 77935 155961 77935 155962 82814 155962 82697 155962 77935 155963 82697 155963 83759 155963 83759 155964 82697 155964 77957 155964 83759 155965 77957 155965 77949 155965 77961 155966 77959 155966 77960 155966 77965 155967 83536 155967 78070 155967 78070 155968 83536 155968 77958 155968 78070 155969 77958 155969 77961 155969 77961 155970 77958 155970 83410 155970 77961 155971 83410 155971 77959 155971 77960 155972 83532 155972 77961 155972 77961 155973 83532 155973 83531 155973 77961 155974 83531 155974 77967 155974 77967 155975 83531 155975 77962 155975 77967 155976 77962 155976 77963 155976 77969 155977 83523 155977 78002 155977 78002 155978 83523 155978 77964 155978 78002 155979 77964 155979 78070 155979 78070 155980 77964 155980 83414 155980 78070 155981 83414 155981 77965 155981 77963 155982 77966 155982 77967 155982 77967 155983 77966 155983 77968 155983 77967 155984 77968 155984 78002 155984 78002 155985 77968 155985 83526 155985 78002 155986 83526 155986 77969 155986 77975 155987 77970 155987 77972 155987 77972 155988 77970 155988 77971 155988 77972 155989 77971 155989 82803 155989 77973 155990 82806 155990 77979 155990 82795 155991 77974 155991 77979 155991 77979 155992 77974 155992 82681 155992 77979 155993 82681 155993 78008 155993 78008 155994 82681 155994 82679 155994 78008 155995 82679 155995 77982 155995 77989 155996 77976 155996 77975 155996 77975 155997 77976 155997 82801 155997 77975 155998 82801 155998 77970 155998 82803 155999 77977 155999 77972 155999 77972 156000 77977 156000 77978 156000 77972 156001 77978 156001 77979 156001 77979 156002 77978 156002 82808 156002 77979 156003 82808 156003 77973 156003 82806 156004 77980 156004 77979 156004 77979 156005 77980 156005 77981 156005 77979 156006 77981 156006 77985 156006 82787 156007 82786 156007 77975 156007 77975 156008 82786 156008 82785 156008 77984 156009 82790 156009 77985 156009 77985 156010 82790 156010 82676 156010 77985 156011 82676 156011 77979 156011 77979 156012 82676 156012 82796 156012 77979 156013 82796 156013 82795 156013 77982 156014 82784 156014 78008 156014 78008 156015 82784 156015 82783 156015 78008 156016 82783 156016 77975 156016 77975 156017 82783 156017 77983 156017 77975 156018 77983 156018 82787 156018 77984 156019 77985 156019 82792 156019 82792 156020 77985 156020 82800 156020 82792 156021 82800 156021 77986 156021 77986 156022 82800 156022 82799 156022 77986 156023 82799 156023 77987 156023 82785 156024 77988 156024 77975 156024 77975 156025 77988 156025 77986 156025 77975 156026 77986 156026 77989 156026 77989 156027 77986 156027 77987 156027 77967 156028 77990 156028 77996 156028 83502 156029 77991 156029 77967 156029 77967 156030 77991 156030 77992 156030 77967 156031 77992 156031 78016 156031 78016 156032 77992 156032 77993 156032 78016 156033 77993 156033 83500 156033 78003 156034 83520 156034 78002 156034 78002 156035 83520 156035 77994 156035 78002 156036 77994 156036 77967 156036 77967 156037 77994 156037 77995 156037 77967 156038 77995 156038 77990 156038 77996 156039 83517 156039 77967 156039 77967 156040 83517 156040 83396 156040 77967 156041 83396 156041 83502 156041 83502 156042 83396 156042 77998 156042 77997 156043 78022 156043 83493 156043 83493 156044 78022 156044 78001 156044 78006 156045 83508 156045 83515 156045 83515 156046 83508 156046 83507 156046 83515 156047 83507 156047 83506 156047 78005 156048 83513 156048 78022 156048 78022 156049 83513 156049 83512 156049 83506 156050 83504 156050 83515 156050 83515 156051 83504 156051 77999 156051 83515 156052 77999 156052 77998 156052 77998 156053 77999 156053 78000 156053 77998 156054 78000 156054 83502 156054 83500 156055 83499 156055 78016 156055 78016 156056 83499 156056 83498 156056 78016 156057 83498 156057 78022 156057 78022 156058 83498 156058 83495 156058 78022 156059 83495 156059 78001 156059 83512 156060 83511 156060 78022 156060 78022 156061 83511 156061 83398 156061 78022 156062 83398 156062 78002 156062 78002 156063 83398 156063 83521 156063 78002 156064 83521 156064 78003 156064 77997 156065 78004 156065 78022 156065 78022 156066 78004 156066 83508 156066 78022 156067 83508 156067 78005 156067 78005 156068 83508 156068 78006 156068 82767 156069 78011 156069 78029 156069 78007 156070 78023 156070 82641 156070 82641 156071 78023 156071 78008 156071 82641 156072 78008 156072 82642 156072 78013 156073 82780 156073 78008 156073 78008 156074 82780 156074 78009 156074 78008 156075 78009 156075 82642 156075 78007 156076 82774 156076 78023 156076 78023 156077 82774 156077 78010 156077 78023 156078 78010 156078 78029 156078 78029 156079 78010 156079 82646 156079 78029 156080 82646 156080 82767 156080 78011 156081 82766 156081 78029 156081 78029 156082 82766 156082 82645 156082 78029 156083 82645 156083 77975 156083 77975 156084 82645 156084 82772 156084 77975 156085 82772 156085 82771 156085 82771 156086 82769 156086 77975 156086 77975 156087 82769 156087 78012 156087 77975 156088 78012 156088 78008 156088 78008 156089 78012 156089 82782 156089 78008 156090 82782 156090 78013 156090 78015 156091 78014 156091 78034 156091 82224 156092 82223 156092 78034 156092 78034 156093 82223 156093 78016 156093 78034 156094 78016 156094 78015 156094 78015 156095 78016 156095 78017 156095 78021 156096 83480 156096 78016 156096 78016 156097 83480 156097 83479 156097 78016 156098 83479 156098 78017 156098 78014 156099 83476 156099 78034 156099 78034 156100 83476 156100 78018 156100 78034 156101 78018 156101 78039 156101 78039 156102 78018 156102 83487 156102 78039 156103 83487 156103 78019 156103 83490 156104 83489 156104 78022 156104 78022 156105 83489 156105 83488 156105 78022 156106 83488 156106 78016 156106 78016 156107 83488 156107 78020 156107 78016 156108 78020 156108 78021 156108 78019 156109 83485 156109 78039 156109 78039 156110 83485 156110 83484 156110 78039 156111 83484 156111 78022 156111 78022 156112 83484 156112 83491 156112 78022 156113 83491 156113 83490 156113 78032 156114 82764 156114 78023 156114 82764 156115 78024 156115 78023 156115 78023 156116 78024 156116 82652 156116 78023 156117 82652 156117 78045 156117 78045 156118 82652 156118 82762 156118 82762 156119 82761 156119 78045 156119 78045 156120 82761 156120 78026 156120 78045 156121 78026 156121 78025 156121 78026 156122 82654 156122 78025 156122 78025 156123 82654 156123 78027 156123 78025 156124 78027 156124 78028 156124 78028 156125 82653 156125 78025 156125 78025 156126 82653 156126 82759 156126 78025 156127 82759 156127 78029 156127 78029 156128 82759 156128 78030 156128 78030 156129 82757 156129 78029 156129 78029 156130 82757 156130 78031 156130 78029 156131 78031 156131 78023 156131 78023 156132 78031 156132 82765 156132 78023 156133 82765 156133 78032 156133 78033 156134 83467 156134 78049 156134 83363 156135 83463 156135 78035 156135 83362 156136 78034 156136 83464 156136 83464 156137 78034 156137 83466 156137 77829 156138 82224 156138 78035 156138 78035 156139 82224 156139 78034 156139 78035 156140 78034 156140 83363 156140 83363 156141 78034 156141 83362 156141 83463 156142 83461 156142 78035 156142 78035 156143 83461 156143 78036 156143 78035 156144 78036 156144 78049 156144 78049 156145 78036 156145 83365 156145 78049 156146 83365 156146 78033 156146 83467 156147 83358 156147 78049 156147 78049 156148 83358 156148 78037 156148 78049 156149 78037 156149 78039 156149 78039 156150 78037 156150 78038 156150 78039 156151 78038 156151 83474 156151 83474 156152 83473 156152 78039 156152 78039 156153 83473 156153 83471 156153 78039 156154 83471 156154 78034 156154 78034 156155 83471 156155 83360 156155 78034 156156 83360 156156 83466 156156 82754 156157 78040 156157 78045 156157 78040 156158 82663 156158 78045 156158 78045 156159 82663 156159 82662 156159 78045 156160 82662 156160 78056 156160 78056 156161 82662 156161 82752 156161 82740 156162 78044 156162 78041 156162 78041 156163 78044 156163 82743 156163 82752 156164 78042 156164 78056 156164 78056 156165 78042 156165 78043 156165 78056 156166 78043 156166 78044 156166 78044 156167 78043 156167 82744 156167 78044 156168 82744 156168 82743 156168 82740 156169 82739 156169 78044 156169 78044 156170 82739 156170 82750 156170 78044 156171 82750 156171 78025 156171 78025 156172 82750 156172 82749 156172 82749 156173 82748 156173 78025 156173 78025 156174 82748 156174 82746 156174 78025 156175 82746 156175 78045 156175 78045 156176 82746 156176 82664 156176 78045 156177 82664 156177 82754 156177 83446 156178 78046 156178 78035 156178 78035 156179 78046 156179 78047 156179 78035 156180 78047 156180 78048 156180 78048 156181 78047 156181 83375 156181 78048 156182 83375 156182 83444 156182 83444 156183 83442 156183 78048 156183 78048 156184 83442 156184 83376 156184 78048 156185 83376 156185 78067 156185 78067 156186 83376 156186 83453 156186 78067 156187 83453 156187 83451 156187 83451 156188 83450 156188 78067 156188 78067 156189 83450 156189 83449 156189 78067 156190 83449 156190 78049 156190 78049 156191 83449 156191 83459 156191 78049 156192 83459 156192 83458 156192 83458 156193 83456 156193 78049 156193 78049 156194 83456 156194 83455 156194 78049 156195 83455 156195 78035 156195 78035 156196 83455 156196 78050 156196 78035 156197 78050 156197 83446 156197 82729 156198 82727 156198 78044 156198 78051 156199 82738 156199 78056 156199 82738 156200 82737 156200 78056 156200 78056 156201 82737 156201 82630 156201 78056 156202 82630 156202 78052 156202 78052 156203 82630 156203 82736 156203 78052 156204 82736 156204 82735 156204 78053 156205 82721 156205 77845 156205 77845 156206 82721 156206 78054 156206 77845 156207 78054 156207 78055 156207 82727 156208 82725 156208 78044 156208 78044 156209 82725 156209 82724 156209 78044 156210 82724 156210 78056 156210 78056 156211 82724 156211 82631 156211 78056 156212 82631 156212 78051 156212 82735 156213 82732 156213 78052 156213 78052 156214 82732 156214 82731 156214 78052 156215 82731 156215 77845 156215 77845 156216 82731 156216 82723 156216 77845 156217 82723 156217 78053 156217 82227 156218 82230 156218 77935 156218 77935 156219 82230 156219 78057 156219 77935 156220 78057 156220 77972 156220 77972 156221 78057 156221 78058 156221 77972 156222 78058 156222 77975 156222 77975 156223 78058 156223 78059 156223 77975 156224 78059 156224 78029 156224 78029 156225 78059 156225 82229 156225 78029 156226 82229 156226 78025 156226 78025 156227 82229 156227 82228 156227 78025 156228 82228 156228 78044 156228 78044 156229 82228 156229 77845 156229 78044 156230 77845 156230 82729 156230 82729 156231 77845 156231 78055 156231 83434 156232 78060 156232 78048 156232 78048 156233 78060 156233 83341 156233 78048 156234 83341 156234 77832 156234 77832 156235 83341 156235 83433 156235 77832 156236 83433 156236 78061 156236 78063 156237 83437 156237 83436 156237 78061 156238 83431 156238 77832 156238 77832 156239 83431 156239 78062 156239 77832 156240 78062 156240 78063 156240 78063 156241 78062 156241 83438 156241 78063 156242 83438 156242 83437 156242 83436 156243 78064 156243 78063 156243 78063 156244 78064 156244 83339 156244 78063 156245 83339 156245 78067 156245 78067 156246 83339 156246 78065 156246 78065 156247 78066 156247 78067 156247 78067 156248 78066 156248 83340 156248 78067 156249 83340 156249 78048 156249 78048 156250 83340 156250 78068 156250 78048 156251 78068 156251 83434 156251 77886 156252 83718 156252 77946 156252 77946 156253 83718 156253 78069 156253 77946 156254 78069 156254 78070 156254 78070 156255 78069 156255 78071 156255 78070 156256 78071 156256 78002 156256 78002 156257 78071 156257 83714 156257 78002 156258 83714 156258 78022 156258 78022 156259 83714 156259 83713 156259 78022 156260 83713 156260 78039 156260 78039 156261 83713 156261 78072 156261 78039 156262 78072 156262 78049 156262 78049 156263 78072 156263 83712 156263 78049 156264 83712 156264 78067 156264 78067 156265 83712 156265 83710 156265 78067 156266 83710 156266 78063 156266 78063 156267 83710 156267 83709 156267 78063 156268 83709 156268 77884 156268 77861 156269 80493 156269 77835 156269 77835 156270 80493 156270 78073 156270 77835 156271 78073 156271 77845 156271 77845 156272 78073 156272 77847 156272 77845 156273 77847 156273 83756 156273 83756 156274 77847 156274 77846 156274 78076 156275 78084 156275 78085 156275 78074 156276 78075 156276 78085 156276 78085 156277 78075 156277 79282 156277 78085 156278 79282 156278 78076 156278 79308 156279 78078 156279 78077 156279 78077 156280 78078 156280 78079 156280 79306 156281 78080 156281 78082 156281 79275 156282 78081 156282 79267 156282 78082 156283 78083 156283 79306 156283 79306 156284 78083 156284 78084 156284 79306 156285 78084 156285 78079 156285 78079 156286 78084 156286 78076 156286 78079 156287 78076 156287 78077 156287 78409 156288 83883 156288 78084 156288 78084 156289 83883 156289 79281 156289 78084 156290 79281 156290 78085 156290 78085 156291 79281 156291 79275 156291 78085 156292 79275 156292 79278 156292 79278 156293 79275 156293 79267 156293 77840 156294 79218 156294 78087 156294 78088 156295 77919 156295 78398 156295 78398 156296 77919 156296 77840 156296 78398 156297 77840 156297 78086 156297 78086 156298 77840 156298 78087 156298 78088 156299 78398 156299 78089 156299 78089 156300 78398 156300 78396 156300 78089 156301 78396 156301 77915 156301 77915 156302 78396 156302 78395 156302 77915 156303 78395 156303 77916 156303 77916 156304 78395 156304 78090 156304 77916 156305 78090 156305 78092 156305 78092 156306 78090 156306 78091 156306 78092 156307 78091 156307 78093 156307 78447 156308 78094 156308 77664 156308 77664 156309 78094 156309 3415 156309 77664 156310 3415 156310 77669 156310 77329 156311 79110 156311 77331 156311 77331 156312 79110 156312 79092 156312 78095 156313 78096 156313 77337 156313 77337 156314 78096 156314 78775 156314 77337 156315 78775 156315 78106 156315 78106 156316 78775 156316 78105 156316 78750 156317 78097 156317 78756 156317 78756 156318 78097 156318 78103 156318 78756 156319 78103 156319 78098 156319 77339 156320 78763 156320 78099 156320 78099 156321 78763 156321 78101 156321 78099 156322 78101 156322 78100 156322 78100 156323 78101 156323 78102 156323 78100 156324 78102 156324 77318 156324 77318 156325 78102 156325 78104 156325 77318 156326 78104 156326 78103 156326 78103 156327 78104 156327 78098 156327 78105 156328 78763 156328 78106 156328 78106 156329 78763 156329 77339 156329 78521 156330 78522 156330 78110 156330 78110 156331 78522 156331 78108 156331 78108 156332 78522 156332 78107 156332 78108 156333 78107 156333 79137 156333 78521 156334 78110 156334 78109 156334 78109 156335 78110 156335 78126 156335 78109 156336 78126 156336 78780 156336 79517 156337 80034 156337 78111 156337 79517 156338 78111 156338 78112 156338 79736 156339 78113 156339 78114 156339 78114 156340 78113 156340 78112 156340 78114 156341 78112 156341 79484 156341 79484 156342 78112 156342 78111 156342 78126 156343 78960 156343 78140 156343 79601 156344 78115 156344 78116 156344 78116 156345 78115 156345 79599 156345 79626 156346 79607 156346 78117 156346 78117 156347 79607 156347 78118 156347 78120 156348 78119 156348 78133 156348 79601 156349 78116 156349 79613 156349 79613 156350 78116 156350 79501 156350 79613 156351 79501 156351 78118 156351 78118 156352 79501 156352 79499 156352 78118 156353 79499 156353 78117 156353 78133 156354 79715 156354 78120 156354 78120 156355 79715 156355 78121 156355 78120 156356 78121 156356 79592 156356 79592 156357 78121 156357 78116 156357 79592 156358 78116 156358 79593 156358 79593 156359 78116 156359 79599 156359 78123 156360 78760 156360 78645 156360 78645 156361 78760 156361 78122 156361 78645 156362 78122 156362 78128 156362 78130 156363 78537 156363 78543 156363 78123 156364 78647 156364 78760 156364 78760 156365 78647 156365 78124 156365 78760 156366 78124 156366 78539 156366 78539 156367 78124 156367 78648 156367 78539 156368 78648 156368 78540 156368 78540 156369 78648 156369 78649 156369 78540 156370 78649 156370 78541 156370 78541 156371 78649 156371 78668 156371 78541 156372 78668 156372 78543 156372 78125 156373 79906 156373 78113 156373 78113 156374 79906 156374 78127 156374 78113 156375 78127 156375 78126 156375 78126 156376 78127 156376 78952 156376 78126 156377 78952 156377 78960 156377 78122 156378 78769 156378 78128 156378 78128 156379 78769 156379 78770 156379 78128 156380 78770 156380 78129 156380 78130 156381 78543 156381 78142 156381 79736 156382 79735 156382 78113 156382 78113 156383 79735 156383 79730 156383 78113 156384 79730 156384 78125 156384 78125 156385 79730 156385 78131 156385 78125 156386 78131 156386 78119 156386 78119 156387 78131 156387 78132 156387 78119 156388 78132 156388 78133 156388 78134 156389 79626 156389 78135 156389 78135 156390 79626 156390 78117 156390 78135 156391 78117 156391 79640 156391 79640 156392 78117 156392 78136 156392 78770 156393 78137 156393 78129 156393 78129 156394 78137 156394 78138 156394 78129 156395 78138 156395 78140 156395 78140 156396 78138 156396 78139 156396 78140 156397 78139 156397 78126 156397 78126 156398 78139 156398 78141 156398 78126 156399 78141 156399 78780 156399 78680 156400 78142 156400 78679 156400 78679 156401 78142 156401 78543 156401 78679 156402 78543 156402 78143 156402 78143 156403 78543 156403 78668 156403 78692 156404 78660 156404 78144 156404 78145 156405 78148 156405 78146 156405 78146 156406 78148 156406 78150 156406 78734 156407 78724 156407 78708 156407 78708 156408 78724 156408 78719 156408 78708 156409 78719 156409 78147 156409 78147 156410 78719 156410 78148 156410 78147 156411 78148 156411 78703 156411 78703 156412 78148 156412 78145 156412 78144 156413 78670 156413 78692 156413 78692 156414 78670 156414 78149 156414 78692 156415 78149 156415 78150 156415 78150 156416 78149 156416 78693 156416 78150 156417 78693 156417 78146 156417 80062 156418 78163 156418 78174 156418 78174 156419 79494 156419 80062 156419 80062 156420 79494 156420 79495 156420 80062 156421 79495 156421 78151 156421 78151 156422 79495 156422 79496 156422 78151 156423 79496 156423 80012 156423 78552 156424 79119 156424 78152 156424 79491 156425 78164 156425 78166 156425 78552 156426 78152 156426 79200 156426 78533 156427 78153 156427 78154 156427 78154 156428 78153 156428 79200 156428 78154 156429 79200 156429 78534 156429 78534 156430 79200 156430 78152 156430 78167 156431 78155 156431 79490 156431 79490 156432 78155 156432 79489 156432 78864 156433 78527 156433 78526 156433 78530 156434 78156 156434 78169 156434 78169 156435 78156 156435 78840 156435 78173 156436 78157 156436 78172 156436 78527 156437 78864 156437 78530 156437 78530 156438 78864 156438 78867 156438 78530 156439 78867 156439 78156 156439 78155 156440 79797 156440 79489 156440 79489 156441 79797 156441 79799 156441 79489 156442 79799 156442 78158 156442 78158 156443 79799 156443 78159 156443 78158 156444 78159 156444 79488 156444 79488 156445 78159 156445 78160 156445 79488 156446 78160 156446 79867 156446 78157 156447 79097 156447 78172 156447 78172 156448 79097 156448 79106 156448 78172 156449 79106 156449 78533 156449 78533 156450 79106 156450 78161 156450 78533 156451 78161 156451 78153 156451 78161 156452 79113 156452 78153 156452 78153 156453 79113 156453 78162 156453 78153 156454 78162 156454 78163 156454 79538 156455 78166 156455 79984 156455 79984 156456 78166 156456 78164 156456 79984 156457 78164 156457 78165 156457 78165 156458 78164 156458 78177 156458 79491 156459 78166 156459 79490 156459 79490 156460 78166 156460 79794 156460 79490 156461 79794 156461 78167 156461 78181 156462 78875 156462 78168 156462 78840 156463 78836 156463 78169 156463 78169 156464 78836 156464 78170 156464 78169 156465 78170 156465 78171 156465 78171 156466 78170 156466 78582 156466 78171 156467 78582 156467 78172 156467 78172 156468 78582 156468 79088 156468 78172 156469 79088 156469 78173 156469 78162 156470 80005 156470 78163 156470 78163 156471 80005 156471 80010 156471 78163 156472 80010 156472 78174 156472 78174 156473 80010 156473 78175 156473 78174 156474 78175 156474 78164 156474 78164 156475 78175 156475 78176 156475 78164 156476 78176 156476 78177 156476 78178 156477 79825 156477 78179 156477 78179 156478 79825 156478 78160 156478 78179 156479 78160 156479 78180 156479 78180 156480 78160 156480 78159 156480 78526 156481 78912 156481 78864 156481 78864 156482 78912 156482 78181 156482 78864 156483 78181 156483 78879 156483 78879 156484 78181 156484 78168 156484 78879 156485 78168 156485 78877 156485 78935 156486 78949 156486 78917 156486 78873 156487 78858 156487 78884 156487 78184 156488 78915 156488 78899 156488 78920 156489 78899 156489 78916 156489 78916 156490 78899 156490 78915 156490 78916 156491 78915 156491 78917 156491 78917 156492 78915 156492 78934 156492 78917 156493 78934 156493 78935 156493 78182 156494 78873 156494 78893 156494 78893 156495 78873 156495 78884 156495 78893 156496 78884 156496 78183 156496 78183 156497 78884 156497 78184 156497 78183 156498 78184 156498 78902 156498 78902 156499 78184 156499 78899 156499 78186 156500 78405 156500 78188 156500 78528 156501 78194 156501 78185 156501 78185 156502 78194 156502 78909 156502 78186 156503 78188 156503 78187 156503 78187 156504 78188 156504 78189 156504 78187 156505 78189 156505 78532 156505 78532 156506 78189 156506 77330 156506 78532 156507 77330 156507 78190 156507 78190 156508 77330 156508 78191 156508 78191 156509 77330 156509 77333 156509 78191 156510 77333 156510 78531 156510 78531 156511 77333 156511 78529 156511 78529 156512 77333 156512 78192 156512 78529 156513 78192 156513 78528 156513 78528 156514 78192 156514 78193 156514 78528 156515 78193 156515 78194 156515 78195 156516 78196 156516 78198 156516 78544 156517 78731 156517 78195 156517 78743 156518 78197 156518 78199 156518 78199 156519 78197 156519 78746 156519 78199 156520 78746 156520 78538 156520 78544 156521 78195 156521 78542 156521 78542 156522 78195 156522 78198 156522 78542 156523 78198 156523 78199 156523 78199 156524 78198 156524 77360 156524 78199 156525 77360 156525 78743 156525 78523 156526 78520 156526 78200 156526 78407 156527 78408 156527 78201 156527 78201 156528 78408 156528 78523 156528 78201 156529 78523 156529 78202 156529 78202 156530 78523 156530 78200 156530 78951 156531 77321 156531 77316 156531 78512 156532 78919 156532 77316 156532 77316 156533 78919 156533 78936 156533 77316 156534 78936 156534 78951 156534 78513 156535 78512 156535 78741 156535 78741 156536 78512 156536 77316 156536 78741 156537 77316 156537 78203 156537 78203 156538 77316 156538 77314 156538 78284 156539 78279 156539 78204 156539 83837 156540 78205 156540 78206 156540 78212 156541 78204 156541 82241 156541 82241 156542 78204 156542 78371 156542 82241 156543 78371 156543 82242 156543 78210 156544 78207 156544 78208 156544 78239 156545 78209 156545 78210 156545 78211 156546 78446 156546 78448 156546 78209 156547 79407 156547 78210 156547 78210 156548 79407 156548 3415 156548 78210 156549 3415 156549 78211 156549 78211 156550 3415 156550 78094 156550 78211 156551 78094 156551 78446 156551 78448 156552 78282 156552 78211 156552 78211 156553 78282 156553 78204 156553 78211 156554 78204 156554 82262 156554 82262 156555 78204 156555 78212 156555 82242 156556 78371 156556 78213 156556 78213 156557 78371 156557 78373 156557 78213 156558 78373 156558 78215 156558 78215 156559 78373 156559 78214 156559 78215 156560 78214 156560 78216 156560 78216 156561 78214 156561 78334 156561 78216 156562 78334 156562 78217 156562 78217 156563 78334 156563 78319 156563 78217 156564 78319 156564 78218 156564 78218 156565 78319 156565 78219 156565 78218 156566 78219 156566 78230 156566 82985 156567 77777 156567 78236 156567 81179 156568 77765 156568 78225 156568 78225 156569 3420 156569 78226 156569 82088 156570 78222 156570 82087 156570 82087 156571 78222 156571 77770 156571 78220 156572 78221 156572 78268 156572 82088 156573 78223 156573 78222 156573 78222 156574 78223 156574 78224 156574 78222 156575 78224 156575 77777 156575 81179 156576 78225 156576 81177 156576 81177 156577 78225 156577 78226 156577 81177 156578 78226 156578 81176 156578 3420 156579 80429 156579 78226 156579 78226 156580 80429 156580 3090 156580 78226 156581 3090 156581 78228 156581 78228 156582 3090 156582 80252 156582 78228 156583 80252 156583 81400 156583 81400 156584 78227 156584 78228 156584 78228 156585 78227 156585 78222 156585 78228 156586 78222 156586 82988 156586 82988 156587 78222 156587 77777 156587 82988 156588 77777 156588 82987 156588 82987 156589 77777 156589 82985 156589 78220 156590 78268 156590 78226 156590 78226 156591 78268 156591 78229 156591 78226 156592 78229 156592 81176 156592 78230 156593 78286 156593 82253 156593 82253 156594 78286 156594 78268 156594 82253 156595 78268 156595 82251 156595 82251 156596 78268 156596 78221 156596 78207 156597 82995 156597 78208 156597 78208 156598 82995 156598 78231 156598 78208 156599 78231 156599 78249 156599 78249 156600 78231 156600 78232 156600 78249 156601 78232 156601 78364 156601 78364 156602 78232 156602 78233 156602 78364 156603 78233 156603 78363 156603 78363 156604 78233 156604 82247 156604 78363 156605 82247 156605 78330 156605 78330 156606 82247 156606 78234 156606 78330 156607 78234 156607 78328 156607 78328 156608 78234 156608 82249 156608 78328 156609 82249 156609 78297 156609 78297 156610 82249 156610 78235 156610 78297 156611 78235 156611 78236 156611 78236 156612 78235 156612 82245 156612 78236 156613 82245 156613 82985 156613 79189 156614 78282 156614 78237 156614 78237 156615 78282 156615 79186 156615 80071 156616 78238 156616 78239 156616 78238 156617 80075 156617 78239 156617 78239 156618 80075 156618 80076 156618 78239 156619 80076 156619 79408 156619 78210 156620 78208 156620 78239 156620 78239 156621 78208 156621 77774 156621 78239 156622 77774 156622 80071 156622 78208 156623 78240 156623 77774 156623 77774 156624 78240 156624 78241 156624 77774 156625 78241 156625 77775 156625 77775 156626 78241 156626 80082 156626 83194 156627 78242 156627 78205 156627 78242 156628 83193 156628 78205 156628 78205 156629 83193 156629 78243 156629 78205 156630 78243 156630 78206 156630 78206 156631 78243 156631 83192 156631 78249 156632 78244 156632 78248 156632 83192 156633 83190 156633 78206 156633 78206 156634 83190 156634 78245 156634 78206 156635 78245 156635 78249 156635 78249 156636 78245 156636 83185 156636 78249 156637 83185 156637 78244 156637 78208 156638 83186 156638 78240 156638 78240 156639 83186 156639 78246 156639 78240 156640 78246 156640 78205 156640 78205 156641 78246 156641 78247 156641 78205 156642 78247 156642 83194 156642 78248 156643 78250 156643 78249 156643 78249 156644 78250 156644 83188 156644 78249 156645 83188 156645 78208 156645 78208 156646 83188 156646 78251 156646 78208 156647 78251 156647 83186 156647 78253 156648 78255 156648 78256 156648 83104 156649 83103 156649 78294 156649 78294 156650 83103 156650 78252 156650 78294 156651 78252 156651 78256 156651 78256 156652 78252 156652 82998 156652 78256 156653 82998 156653 78253 156653 77777 156654 78258 156654 83000 156654 77777 156655 83000 156655 78236 156655 78236 156656 83000 156656 83001 156656 78236 156657 83001 156657 83101 156657 83101 156658 78254 156658 78236 156658 78236 156659 78254 156659 83099 156659 78236 156660 83099 156660 78294 156660 78294 156661 83099 156661 83002 156661 78294 156662 83002 156662 83104 156662 77777 156663 83860 156663 78256 156663 83860 156664 77777 156664 83858 156664 83858 156665 77777 156665 77778 156665 83858 156666 77778 156666 83863 156666 78255 156667 78257 156667 78256 156667 78256 156668 78257 156668 83098 156668 78256 156669 83098 156669 77777 156669 77777 156670 83098 156670 83097 156670 77777 156671 83097 156671 78258 156671 78286 156672 82270 156672 78268 156672 78268 156673 82270 156673 82359 156673 78268 156674 82359 156674 82357 156674 82361 156675 82360 156675 78286 156675 78286 156676 82360 156676 82271 156676 78286 156677 82271 156677 82270 156677 82367 156678 78259 156678 78264 156678 82364 156679 78260 156679 78261 156679 82364 156680 78261 156680 82269 156680 78259 156681 78262 156681 78264 156681 78264 156682 78262 156682 82365 156682 78264 156683 82365 156683 78286 156683 78286 156684 82365 156684 82272 156684 78286 156685 82272 156685 82361 156685 78260 156686 78263 156686 78261 156686 78261 156687 78263 156687 82363 156687 78261 156688 82363 156688 78264 156688 78264 156689 82363 156689 82267 156689 78264 156690 82267 156690 82367 156690 78261 156691 78265 156691 82269 156691 82269 156692 78265 156692 78268 156692 82269 156693 78268 156693 78266 156693 78266 156694 78268 156694 82357 156694 78265 156695 78267 156695 78268 156695 78268 156696 78267 156696 83792 156696 78268 156697 83792 156697 78269 156697 78269 156698 83792 156698 81183 156698 78273 156699 82473 156699 78379 156699 82470 156700 78271 156700 78371 156700 82470 156701 78371 156701 82347 156701 82347 156702 78371 156702 78270 156702 78270 156703 78371 156703 78204 156703 78270 156704 78204 156704 78281 156704 78271 156705 82468 156705 78371 156705 78371 156706 82468 156706 78272 156706 78371 156707 78272 156707 78379 156707 78379 156708 78272 156708 82474 156708 78379 156709 82474 156709 78273 156709 82473 156710 78274 156710 78379 156710 78379 156711 78274 156711 78275 156711 78379 156712 78275 156712 78276 156712 78276 156713 78275 156713 82477 156713 82477 156714 82476 156714 78276 156714 78276 156715 82476 156715 78277 156715 78276 156716 78277 156716 83807 156716 83807 156717 78277 156717 78278 156717 83807 156718 78278 156718 78279 156718 78279 156719 78278 156719 78280 156719 78279 156720 78280 156720 78204 156720 78204 156721 78280 156721 82472 156721 78204 156722 82472 156722 78281 156722 79189 156723 79191 156723 78282 156723 78282 156724 79191 156724 78283 156724 78282 156725 78283 156725 78204 156725 78204 156726 78283 156726 77771 156726 78204 156727 77771 156727 78284 156727 78284 156728 77771 156728 77772 156728 78284 156729 77772 156729 79192 156729 78264 156730 78288 156730 78285 156730 82301 156731 82371 156731 78286 156731 78286 156732 82371 156732 82370 156732 78230 156733 78219 156733 78286 156733 78286 156734 78219 156734 82373 156734 78286 156735 82373 156735 82301 156735 82370 156736 82369 156736 78286 156736 78286 156737 82369 156737 78287 156737 78286 156738 78287 156738 78264 156738 78264 156739 78287 156739 82381 156739 78264 156740 82381 156740 78288 156740 82379 156741 82377 156741 78219 156741 78219 156742 82377 156742 82376 156742 78219 156743 82376 156743 82373 156743 78285 156744 82299 156744 78264 156744 78264 156745 82299 156745 82385 156745 78264 156746 82385 156746 78289 156746 78289 156747 82385 156747 82383 156747 82383 156748 78290 156748 78289 156748 78289 156749 78290 156749 78291 156749 78289 156750 78291 156750 78219 156750 78219 156751 78291 156751 82302 156751 78219 156752 82302 156752 82379 156752 83117 156753 78292 156753 78299 156753 78299 156754 78292 156754 78293 156754 78299 156755 78293 156755 78294 156755 78294 156756 78293 156756 83037 156756 78294 156757 83037 156757 83115 156757 83115 156758 83114 156758 78294 156758 78294 156759 83114 156759 83112 156759 78294 156760 83112 156760 78236 156760 78236 156761 83112 156761 83109 156761 78236 156762 83109 156762 83108 156762 83108 156763 78295 156763 78236 156763 78236 156764 78295 156764 78296 156764 78236 156765 78296 156765 78297 156765 78297 156766 78296 156766 83111 156766 78297 156767 83111 156767 78298 156767 78298 156768 83110 156768 78297 156768 78297 156769 83110 156769 78300 156769 78297 156770 78300 156770 78299 156770 78299 156771 78300 156771 78301 156771 78299 156772 78301 156772 83117 156772 82391 156773 82390 156773 78319 156773 78319 156774 82390 156774 78302 156774 78319 156775 78302 156775 78219 156775 78219 156776 78302 156776 82292 156776 78219 156777 82292 156777 82387 156777 78289 156778 82394 156778 78305 156778 82387 156779 78303 156779 78219 156779 78219 156780 78303 156780 78304 156780 78219 156781 78304 156781 78289 156781 78289 156782 78304 156782 82395 156782 78289 156783 82395 156783 82394 156783 78305 156784 82291 156784 78289 156784 78289 156785 82291 156785 78306 156785 78289 156786 78306 156786 78321 156786 78321 156787 78306 156787 78307 156787 78307 156788 82397 156788 78321 156788 78321 156789 82397 156789 78308 156789 78321 156790 78308 156790 78319 156790 78319 156791 78308 156791 82393 156791 78319 156792 82393 156792 82391 156792 83133 156793 83131 156793 78327 156793 78327 156794 83131 156794 83026 156794 78327 156795 83026 156795 78299 156795 78299 156796 83026 156796 83129 156796 78299 156797 83129 156797 83128 156797 83128 156798 83127 156798 78299 156798 78299 156799 83127 156799 78309 156799 78299 156800 78309 156800 78297 156800 78297 156801 78309 156801 83122 156801 78297 156802 83122 156802 83120 156802 83120 156803 83118 156803 78297 156803 78297 156804 83118 156804 78310 156804 78297 156805 78310 156805 78328 156805 78328 156806 78310 156806 78311 156806 78328 156807 78311 156807 78312 156807 78312 156808 83124 156808 78328 156808 78328 156809 83124 156809 78313 156809 78328 156810 78313 156810 78327 156810 78327 156811 78313 156811 83134 156811 78327 156812 83134 156812 83133 156812 78314 156813 82401 156813 78319 156813 78316 156814 82415 156814 82412 156814 82412 156815 78315 156815 78316 156815 78316 156816 78315 156816 82411 156816 78316 156817 82411 156817 78334 156817 78334 156818 82411 156818 78317 156818 78334 156819 78317 156819 78318 156819 82401 156820 82400 156820 78319 156820 78319 156821 82400 156821 78320 156821 78319 156822 78320 156822 78321 156822 78321 156823 78320 156823 82283 156823 78321 156824 82283 156824 82409 156824 82409 156825 82408 156825 78321 156825 78321 156826 82408 156826 78322 156826 78321 156827 78322 156827 78316 156827 78316 156828 78322 156828 82416 156828 78316 156829 82416 156829 82415 156829 78318 156830 82405 156830 78334 156830 78334 156831 82405 156831 78323 156831 78334 156832 78323 156832 78319 156832 78319 156833 78323 156833 82402 156833 78319 156834 82402 156834 78314 156834 78325 156835 78324 156835 78345 156835 78325 156836 78345 156836 78326 156836 78324 156837 83014 156837 78345 156837 78345 156838 83014 156838 83016 156838 78345 156839 83016 156839 78327 156839 78327 156840 83016 156840 83144 156840 83144 156841 83143 156841 78327 156841 78327 156842 83143 156842 83017 156842 78327 156843 83017 156843 78328 156843 78328 156844 83017 156844 83019 156844 78328 156845 83019 156845 78329 156845 78329 156846 83135 156846 78328 156846 78328 156847 83135 156847 83020 156847 78328 156848 83020 156848 78330 156848 78330 156849 83020 156849 83141 156849 78330 156850 83141 156850 83139 156850 83139 156851 83138 156851 78330 156851 78330 156852 83138 156852 78331 156852 78330 156853 78331 156853 78345 156853 78345 156854 78331 156854 78332 156854 78345 156855 78332 156855 78326 156855 78333 156856 82418 156856 78316 156856 78334 156857 78337 156857 82424 156857 78342 156858 82432 156858 78341 156858 78341 156859 82432 156859 82431 156859 78341 156860 82431 156860 78214 156860 78214 156861 82431 156861 82428 156861 78214 156862 82428 156862 78335 156862 78335 156863 82427 156863 78214 156863 78214 156864 82427 156864 82316 156864 78214 156865 82316 156865 78334 156865 78334 156866 82316 156866 78336 156866 78334 156867 78336 156867 78337 156867 82424 156868 82423 156868 78334 156868 78334 156869 82423 156869 78338 156869 78334 156870 78338 156870 78316 156870 78316 156871 78338 156871 78339 156871 78316 156872 78339 156872 78333 156872 82418 156873 78340 156873 78316 156873 78316 156874 78340 156874 82437 156874 78316 156875 82437 156875 78341 156875 78341 156876 82437 156876 82436 156876 78341 156877 82436 156877 78342 156877 78343 156878 78344 156878 78363 156878 78345 156879 83147 156879 83146 156879 83157 156880 78346 156880 78353 156880 78353 156881 78346 156881 83154 156881 78353 156882 83154 156882 78345 156882 78345 156883 83154 156883 83048 156883 78345 156884 83048 156884 83147 156884 83146 156885 78347 156885 78345 156885 78345 156886 78347 156886 78348 156886 78345 156887 78348 156887 78330 156887 78330 156888 78348 156888 78349 156888 78330 156889 78349 156889 78350 156889 78350 156890 78351 156890 78330 156890 78330 156891 78351 156891 78352 156891 78330 156892 78352 156892 78363 156892 78363 156893 78352 156893 83050 156893 78363 156894 83050 156894 78343 156894 78344 156895 83151 156895 78363 156895 78363 156896 83151 156896 83150 156896 78363 156897 83150 156897 78353 156897 78353 156898 83150 156898 83158 156898 78353 156899 83158 156899 83157 156899 78359 156900 82446 156900 78373 156900 78373 156901 82446 156901 82329 156901 78373 156902 82329 156902 78214 156902 78214 156903 82329 156903 82328 156903 78214 156904 82328 156904 78356 156904 78354 156905 78355 156905 78341 156905 82453 156906 82452 156906 78374 156906 78356 156907 78357 156907 78214 156907 78214 156908 78357 156908 82444 156908 78214 156909 82444 156909 78341 156909 78341 156910 82444 156910 82443 156910 78341 156911 82443 156911 78354 156911 78355 156912 82440 156912 78341 156912 78341 156913 82440 156913 78358 156913 78341 156914 78358 156914 78374 156914 78374 156915 78358 156915 82326 156915 78374 156916 82326 156916 82453 156916 82452 156917 82451 156917 78374 156917 78374 156918 82451 156918 82449 156918 78374 156919 82449 156919 78373 156919 78373 156920 82449 156920 82324 156920 78373 156921 82324 156921 78359 156921 83163 156922 83161 156922 78353 156922 83169 156923 78360 156923 78364 156923 78364 156924 78360 156924 83168 156924 78364 156925 83168 156925 78361 156925 78361 156926 83168 156926 83173 156926 78361 156927 83173 156927 78366 156927 83161 156928 83160 156928 78353 156928 78353 156929 83160 156929 78362 156929 78353 156930 78362 156930 78363 156930 78363 156931 78362 156931 83059 156931 78363 156932 83059 156932 83167 156932 83167 156933 83165 156933 78363 156933 78363 156934 83165 156934 78365 156934 78363 156935 78365 156935 78364 156935 78364 156936 78365 156936 83061 156936 78364 156937 83061 156937 83169 156937 78366 156938 78367 156938 78361 156938 78361 156939 78367 156939 78368 156939 78361 156940 78368 156940 78353 156940 78353 156941 78368 156941 83164 156941 78353 156942 83164 156942 83163 156942 78374 156943 78376 156943 78369 156943 82464 156944 78370 156944 78371 156944 78371 156945 78370 156945 78372 156945 78371 156946 78372 156946 78373 156946 78373 156947 78372 156947 82463 156947 78373 156948 82463 156948 82462 156948 82462 156949 82461 156949 78373 156949 78373 156950 82461 156950 82459 156950 78373 156951 82459 156951 78374 156951 78374 156952 82459 156952 78375 156952 78374 156953 78375 156953 78376 156953 78369 156954 78377 156954 78374 156954 78374 156955 78377 156955 82334 156955 78374 156956 82334 156956 78379 156956 78379 156957 82334 156957 78378 156957 78378 156958 82467 156958 78379 156958 78379 156959 82467 156959 78380 156959 78379 156960 78380 156960 78371 156960 78371 156961 78380 156961 82466 156961 78371 156962 82466 156962 82464 156962 83184 156963 83183 156963 78206 156963 78206 156964 83183 156964 78381 156964 78206 156965 78381 156965 78361 156965 78361 156966 78381 156966 83071 156966 78361 156967 83071 156967 83175 156967 78382 156968 83179 156968 78249 156968 78249 156969 83179 156969 83178 156969 78249 156970 83178 156970 78206 156970 78206 156971 83178 156971 83070 156971 78206 156972 83070 156972 83184 156972 83175 156973 78383 156973 78361 156973 78361 156974 78383 156974 78384 156974 78361 156975 78384 156975 78364 156975 78364 156976 78384 156976 83072 156976 78364 156977 83072 156977 78385 156977 78385 156978 78386 156978 78364 156978 78364 156979 78386 156979 78387 156979 78364 156980 78387 156980 78249 156980 78249 156981 78387 156981 83074 156981 78249 156982 83074 156982 78382 156982 78256 156983 83845 156983 78294 156983 78294 156984 83845 156984 83844 156984 78294 156985 83844 156985 78299 156985 78299 156986 83844 156986 83843 156986 78299 156987 83843 156987 78327 156987 78327 156988 83843 156988 83842 156988 78327 156989 83842 156989 78345 156989 78345 156990 83842 156990 83841 156990 78345 156991 83841 156991 78353 156991 78353 156992 83841 156992 78388 156992 78353 156993 78388 156993 78361 156993 78361 156994 78388 156994 83838 156994 78361 156995 83838 156995 78206 156995 78206 156996 83838 156996 78389 156996 78206 156997 78389 156997 83837 156997 77802 156998 78397 156998 78390 156998 78390 156999 78397 156999 77810 156999 78402 157000 79345 157000 77791 157000 77791 157001 79345 157001 78391 157001 77791 157002 78391 157002 77792 157002 77792 157003 78391 157003 78392 157003 77792 157004 78392 157004 77794 157004 77794 157005 78392 157005 78393 157005 77794 157006 78393 157006 77796 157006 78393 157007 78091 157007 77796 157007 77796 157008 78091 157008 78090 157008 77796 157009 78090 157009 78394 157009 78394 157010 78090 157010 78395 157010 78394 157011 78395 157011 77798 157011 77798 157012 78395 157012 78396 157012 77798 157013 78396 157013 77800 157013 77800 157014 78396 157014 78398 157014 77800 157015 78398 157015 78397 157015 78397 157016 78398 157016 78086 157016 78397 157017 78086 157017 77810 157017 77810 157018 78086 157018 77811 157018 77811 157019 78086 157019 77814 157019 77814 157020 78086 157020 78399 157020 77814 157021 78399 157021 77816 157021 77816 157022 78399 157022 77817 157022 77817 157023 78399 157023 80063 157023 77817 157024 80063 157024 77819 157024 77802 157025 78390 157025 77803 157025 77803 157026 78390 157026 78400 157026 77803 157027 78400 157027 78401 157027 78401 157028 78400 157028 77808 157028 78401 157029 77808 157029 78402 157029 78402 157030 77808 157030 77807 157030 78402 157031 77807 157031 79345 157031 79345 157032 77807 157032 77805 157032 79345 157033 77805 157033 80063 157033 80063 157034 77805 157034 77820 157034 80063 157035 77820 157035 77819 157035 78403 157036 78188 157036 79136 157036 79136 157037 78188 157037 78405 157037 79136 157038 78405 157038 78404 157038 78404 157039 78405 157039 78406 157039 78408 157040 78407 157040 79158 157040 79158 157041 79157 157041 78408 157041 78408 157042 79157 157042 79152 157042 78408 157043 79152 157043 79153 157043 77633 157044 78563 157044 78566 157044 78566 157045 78563 157045 78564 157045 78412 157046 77632 157046 79197 157046 79197 157047 77632 157047 78565 157047 79197 157048 78565 157048 83817 157048 83883 157049 78409 157049 78411 157049 78411 157050 78409 157050 78410 157050 79294 157051 77281 157051 78410 157051 78410 157052 77281 157052 77632 157052 78410 157053 77632 157053 78411 157053 78411 157054 77632 157054 78412 157054 78562 157055 77499 157055 78414 157055 78414 157056 77499 157056 78413 157056 78414 157057 78413 157057 79250 157057 79250 157058 78413 157058 83887 157058 78556 157059 78415 157059 78416 157059 78416 157060 78415 157060 78417 157060 78416 157061 78417 157061 78413 157061 78413 157062 78417 157062 83887 157062 83887 157063 78417 157063 78418 157063 83887 157064 78418 157064 83886 157064 78419 157065 77545 157065 78561 157065 78561 157066 77545 157066 78420 157066 78561 157067 78420 157067 78421 157067 78421 157068 78420 157068 78422 157068 78421 157069 78422 157069 77498 157069 79465 157070 79464 157070 78503 157070 78503 157071 79464 157071 78423 157071 78506 157072 78425 157072 78424 157072 78424 157073 78425 157073 79901 157073 78427 157074 78426 157074 78978 157074 78956 157075 77317 157075 78969 157075 78969 157076 77317 157076 78427 157076 78969 157077 78427 157077 78968 157077 78968 157078 78427 157078 78978 157078 78500 157079 78435 157079 78428 157079 78428 157080 78429 157080 78500 157080 78500 157081 78429 157081 78430 157081 78500 157082 78430 157082 78992 157082 77345 157083 79023 157083 77354 157083 77354 157084 79023 157084 78431 157084 77354 157085 78431 157085 77310 157085 77310 157086 78431 157086 78432 157086 77310 157087 78432 157087 77315 157087 77315 157088 78432 157088 78433 157088 77315 157089 78433 157089 77305 157089 77305 157090 78433 157090 78434 157090 77305 157091 78434 157091 78435 157091 78435 157092 78434 157092 78428 157092 78440 157093 79025 157093 77320 157093 77320 157094 79025 157094 78436 157094 77320 157095 78436 157095 77322 157095 77322 157096 78436 157096 79043 157096 77322 157097 79043 157097 78437 157097 78437 157098 79043 157098 79044 157098 78437 157099 79044 157099 77323 157099 77323 157100 79044 157100 78438 157100 77323 157101 78438 157101 79403 157101 79403 157102 78438 157102 79402 157102 79061 157103 78439 157103 78440 157103 78440 157104 78439 157104 79067 157104 78440 157105 79067 157105 79025 157105 78441 157106 79082 157106 78442 157106 78441 157107 78442 157107 78444 157107 78444 157108 78442 157108 78443 157108 78444 157109 78443 157109 79091 157109 79082 157110 79076 157110 78442 157110 78442 157111 79076 157111 79069 157111 78442 157112 79069 157112 78440 157112 78440 157113 79069 157113 78445 157113 78440 157114 78445 157114 79061 157114 78094 157115 78447 157115 78446 157115 78446 157116 78447 157116 77626 157116 78446 157117 77626 157117 78448 157117 78448 157118 77626 157118 78449 157118 78448 157119 78449 157119 78282 157119 78282 157120 78449 157120 78453 157120 78450 157121 79300 157121 79186 157121 77336 157122 78451 157122 78452 157122 78452 157123 78451 157123 78450 157123 78452 157124 78450 157124 77631 157124 77631 157125 78450 157125 79186 157125 77631 157126 79186 157126 78453 157126 78453 157127 79186 157127 78282 157127 80067 157128 80068 157128 79320 157128 78451 157129 77336 157129 78458 157129 80067 157130 79320 157130 77277 157130 77277 157131 79320 157131 77302 157131 77302 157132 79320 157132 78454 157132 77302 157133 78454 157133 78455 157133 78455 157134 78454 157134 79324 157134 78455 157135 79324 157135 78456 157135 78456 157136 79324 157136 79319 157136 78456 157137 79319 157137 78457 157137 78457 157138 79319 157138 79317 157138 78457 157139 79317 157139 78458 157139 78458 157140 79317 157140 79181 157140 78458 157141 79181 157141 78451 157141 78459 157142 83885 157142 79212 157142 83886 157143 78418 157143 78460 157143 78460 157144 78418 157144 83885 157144 83885 157145 78459 157145 78460 157145 78460 157146 78459 157146 78462 157146 78460 157147 78462 157147 78461 157147 79208 157148 79209 157148 79206 157148 79206 157149 79209 157149 79211 157149 79206 157150 79211 157150 79219 157150 79212 157151 79229 157151 78459 157151 78459 157152 79229 157152 79230 157152 78459 157153 79230 157153 79232 157153 79264 157154 79265 157154 78462 157154 78462 157155 79265 157155 79266 157155 78462 157156 79266 157156 78461 157156 78463 157157 79243 157157 79247 157157 79247 157158 79243 157158 79219 157158 79247 157159 79219 157159 83885 157159 83885 157160 79219 157160 79211 157160 83885 157161 79211 157161 79212 157161 78466 157162 78851 157162 78849 157162 78604 157163 78575 157163 79009 157163 79047 157164 78464 157164 79048 157164 79048 157165 78464 157165 78825 157165 79048 157166 78825 157166 78465 157166 78849 157167 78846 157167 78466 157167 78466 157168 78846 157168 78467 157168 78466 157169 78467 157169 78868 157169 78466 157170 78514 157170 78632 157170 78632 157171 78626 157171 78466 157171 78466 157172 78626 157172 78625 157172 78466 157173 78625 157173 78468 157173 78477 157174 78476 157174 79783 157174 79605 157175 78474 157175 79583 157175 79583 157176 78474 157176 79584 157176 78825 157177 78851 157177 78465 157177 78465 157178 78851 157178 78466 157178 78465 157179 78466 157179 79028 157179 79028 157180 78466 157180 78474 157180 79028 157181 78474 157181 78475 157181 78480 157182 78474 157182 79012 157182 79012 157183 78474 157183 78466 157183 79012 157184 78466 157184 78469 157184 78469 157185 78466 157185 78468 157185 78469 157186 78468 157186 78470 157186 78470 157187 78468 157187 78604 157187 78470 157188 78604 157188 78471 157188 78471 157189 78604 157189 79009 157189 79529 157190 79531 157190 79783 157190 79783 157191 79531 157191 78472 157191 79783 157192 78472 157192 78477 157192 79803 157193 78474 157193 79823 157193 79823 157194 78474 157194 78473 157194 79803 157195 79804 157195 78474 157195 78474 157196 79804 157196 78476 157196 78474 157197 78476 157197 78475 157197 78475 157198 78476 157198 78477 157198 79942 157199 78478 157199 79952 157199 79952 157200 78478 157200 78479 157200 79952 157201 78479 157201 78480 157201 78480 157202 78479 157202 78481 157202 78480 157203 78481 157203 78474 157203 78474 157204 78481 157204 79587 157204 78474 157205 79587 157205 79584 157205 78482 157206 78841 157206 78484 157206 78808 157207 78483 157207 78484 157207 78484 157208 78483 157208 78798 157208 78484 157209 78798 157209 78482 157209 78808 157210 78484 157210 78828 157210 78828 157211 78484 157211 78485 157211 78828 157212 78485 157212 78547 157212 78661 157213 78642 157213 78599 157213 78599 157214 78486 157214 78661 157214 78661 157215 78486 157215 78487 157215 78661 157216 78487 157216 78595 157216 78595 157217 78608 157217 78661 157217 78661 157218 78608 157218 78609 157218 78661 157219 78609 157219 78688 157219 77457 157220 78488 157220 78489 157220 78489 157221 78488 157221 77914 157221 78489 157222 77914 157222 77453 157222 77453 157223 77914 157223 77922 157223 77453 157224 77922 157224 77454 157224 77454 157225 77922 157225 77921 157225 77454 157226 77921 157226 78490 157226 78490 157227 77921 157227 78491 157227 78490 157228 78491 157228 77459 157228 77459 157229 78491 157229 77913 157229 77459 157230 77913 157230 78492 157230 78492 157231 77913 157231 77912 157231 78492 157232 77912 157232 77460 157232 77460 157233 77912 157233 77923 157233 77460 157234 77923 157234 77451 157234 77451 157235 77923 157235 78493 157235 77451 157236 78493 157236 78494 157236 78494 157237 78493 157237 78495 157237 78494 157238 78495 157238 78496 157238 78496 157239 78495 157239 77918 157239 78496 157240 77918 157240 77455 157240 77455 157241 77918 157241 77917 157241 77455 157242 77917 157242 77457 157242 77457 157243 77917 157243 78488 157243 78571 157244 79058 157244 78497 157244 78497 157245 79058 157245 79073 157245 78497 157246 79073 157246 78822 157246 78822 157247 79073 157247 79078 157247 78598 157248 78586 157248 78498 157248 78498 157249 78586 157249 78986 157249 78498 157250 78986 157250 78572 157250 78572 157251 78986 157251 78988 157251 78572 157252 78988 157252 78983 157252 77331 157253 79092 157253 77332 157253 77332 157254 79092 157254 78499 157254 77332 157255 78499 157255 78443 157255 78443 157256 78499 157256 79091 157256 78500 157257 78992 157257 78991 157257 78426 157258 78427 157258 78979 157258 78979 157259 78427 157259 78500 157259 78979 157260 78500 157260 78980 157260 78980 157261 78500 157261 78991 157261 79110 157262 77329 157262 77309 157262 79110 157263 77309 157263 79109 157263 79109 157264 77309 157264 77307 157264 79109 157265 77307 157265 78502 157265 78502 157266 77307 157266 78501 157266 78502 157267 78501 157267 78504 157267 78504 157268 78501 157268 78503 157268 78504 157269 78503 157269 78423 157269 78425 157270 78506 157270 78505 157270 78505 157271 78506 157271 77301 157271 78505 157272 77301 157272 78507 157272 78507 157273 77301 157273 77338 157273 78507 157274 77338 157274 78956 157274 78956 157275 77338 157275 77317 157275 78695 157276 78678 157276 78508 157276 78695 157277 78508 157277 78698 157277 78508 157278 78515 157278 78906 157278 78698 157279 78508 157279 78510 157279 78510 157280 78508 157280 78906 157280 78510 157281 78906 157281 78509 157281 78707 157282 78698 157282 78510 157282 78707 157283 78510 157283 78711 157283 78511 157284 78923 157284 78512 157284 78512 157285 78923 157285 78918 157285 78512 157286 78918 157286 78919 157286 78509 157287 78923 157287 78510 157287 78510 157288 78923 157288 78511 157288 78510 157289 78511 157289 78711 157289 78711 157290 78511 157290 78512 157290 78711 157291 78512 157291 78513 157291 78669 157292 78514 157292 78466 157292 78669 157293 78466 157293 78518 157293 78515 157294 78508 157294 78516 157294 78516 157295 78508 157295 78517 157295 78516 157296 78517 157296 78888 157296 78868 157297 78888 157297 78466 157297 78466 157298 78888 157298 78517 157298 78466 157299 78517 157299 78518 157299 78518 157300 78517 157300 78508 157300 78518 157301 78508 157301 78678 157301 78109 157302 78519 157302 78521 157302 78521 157303 78519 157303 78520 157303 78521 157304 78520 157304 78522 157304 78520 157305 78523 157305 78522 157305 78522 157306 78523 157306 78408 157306 78522 157307 78408 157307 78107 157307 78408 157308 79153 157308 79147 157308 79137 157309 78107 157309 78524 157309 78524 157310 78107 157310 78408 157310 78524 157311 78408 157311 78525 157311 78525 157312 78408 157312 79147 157312 78907 157313 78912 157313 78526 157313 78907 157314 78526 157314 78909 157314 78909 157315 78526 157315 78185 157315 78185 157316 78526 157316 78527 157316 78185 157317 78527 157317 78528 157317 78528 157318 78527 157318 78530 157318 78528 157319 78530 157319 78529 157319 78529 157320 78530 157320 78169 157320 78529 157321 78169 157321 78531 157321 78531 157322 78169 157322 78171 157322 78531 157323 78171 157323 78191 157323 78191 157324 78171 157324 78172 157324 78191 157325 78172 157325 78190 157325 78190 157326 78172 157326 78533 157326 78190 157327 78533 157327 78532 157327 78532 157328 78533 157328 78154 157328 78532 157329 78154 157329 78187 157329 78187 157330 78154 157330 78534 157330 78187 157331 78534 157331 78186 157331 78186 157332 78534 157332 78152 157332 78186 157333 78152 157333 78405 157333 78152 157334 79119 157334 78405 157334 78405 157335 79119 157335 79120 157335 79120 157336 78535 157336 78405 157336 78405 157337 78535 157337 78536 157337 78405 157338 78536 157338 78406 157338 78543 157339 78537 157339 78712 157339 78199 157340 78538 157340 78752 157340 78760 157341 78539 157341 78752 157341 78752 157342 78539 157342 78540 157342 78752 157343 78540 157343 78199 157343 78199 157344 78540 157344 78541 157344 78199 157345 78541 157345 78542 157345 78542 157346 78541 157346 78543 157346 78542 157347 78543 157347 78544 157347 78544 157348 78543 157348 78712 157348 78544 157349 78712 157349 78731 157349 78884 157350 78858 157350 78885 157350 78885 157351 78858 157351 78545 157351 78885 157352 78545 157352 78546 157352 78546 157353 78545 157353 78859 157353 78546 157354 78859 157354 78886 157354 78886 157355 78859 157355 78860 157355 78886 157356 78860 157356 78485 157356 78485 157357 78860 157357 78547 157357 78688 157358 78609 157358 78689 157358 78689 157359 78609 157359 78548 157359 78689 157360 78548 157360 78549 157360 78549 157361 78548 157361 78550 157361 78549 157362 78550 157362 78691 157362 78691 157363 78550 157363 78631 157363 78691 157364 78631 157364 78692 157364 78692 157365 78631 157365 78660 157365 78556 157366 77351 157366 78551 157366 79236 157367 78415 157367 78556 157367 79119 157368 78552 157368 79127 157368 79127 157369 78552 157369 79240 157369 79127 157370 79240 157370 79126 157370 79126 157371 79240 157371 78554 157371 79126 157372 78554 157372 78553 157372 78553 157373 78554 157373 79236 157373 78553 157374 79236 157374 78555 157374 78555 157375 79236 157375 78556 157375 78555 157376 78556 157376 79117 157376 79117 157377 78556 157377 78551 157377 77281 157378 79294 157378 79291 157378 78557 157379 79148 157379 77281 157379 77281 157380 79148 157380 79154 157380 77281 157381 79154 157381 77282 157381 77281 157382 79291 157382 78557 157382 78557 157383 79291 157383 78558 157383 78557 157384 78558 157384 79143 157384 79143 157385 78558 157385 78559 157385 79143 157386 78559 157386 79144 157386 78108 157387 79137 157387 78559 157387 78559 157388 79137 157388 78560 157388 78559 157389 78560 157389 79144 157389 77547 157390 78419 157390 83767 157390 83767 157391 78419 157391 78561 157391 77499 157392 78562 157392 77498 157392 77498 157393 78562 157393 78421 157393 77738 157394 78563 157394 77671 157394 77671 157395 78563 157395 77633 157395 83817 157396 78565 157396 78564 157396 78564 157397 78565 157397 78566 157397 78567 157398 78097 157398 78749 157398 78749 157399 78097 157399 78750 157399 78464 157400 79047 157400 78568 157400 78568 157401 79047 157401 79063 157401 78568 157402 79063 157402 78807 157402 78807 157403 79063 157403 78570 157403 78807 157404 78570 157404 78569 157404 78569 157405 78570 157405 79059 157405 78569 157406 79059 157406 78571 157406 78571 157407 79059 157407 79058 157407 78572 157408 78983 157408 78590 157408 78590 157409 78983 157409 78989 157409 78590 157410 78989 157410 78573 157410 78573 157411 78989 157411 78574 157411 78573 157412 78574 157412 78576 157412 79009 157413 78575 157413 78998 157413 78998 157414 78575 157414 78576 157414 78998 157415 78576 157415 78577 157415 78577 157416 78576 157416 78574 157416 78822 157417 79078 157417 78579 157417 78822 157418 78579 157418 78578 157418 78578 157419 78579 157419 79085 157419 78578 157420 79085 157420 78580 157420 78580 157421 79085 157421 78581 157421 78581 157422 79085 157422 79088 157422 78581 157423 79088 157423 78582 157423 78583 157424 78645 157424 78128 157424 78583 157425 78128 157425 78584 157425 78128 157426 78967 157426 78584 157426 78584 157427 78967 157427 78585 157427 78584 157428 78585 157428 78615 157428 78615 157429 78585 157429 78586 157429 78615 157430 78586 157430 78598 157430 78573 157431 78576 157431 78593 157431 78487 157432 78486 157432 78587 157432 78587 157433 78486 157433 78601 157433 78587 157434 78601 157434 78588 157434 78588 157435 78601 157435 78602 157435 78588 157436 78602 157436 78592 157436 78592 157437 78602 157437 78589 157437 78592 157438 78589 157438 78590 157438 78590 157439 78589 157439 78572 157439 78595 157440 78487 157440 78596 157440 78596 157441 78487 157441 78587 157441 78596 157442 78587 157442 78591 157442 78591 157443 78587 157443 78588 157443 78591 157444 78588 157444 78593 157444 78593 157445 78588 157445 78592 157445 78593 157446 78592 157446 78573 157446 78573 157447 78592 157447 78590 157447 78608 157448 78595 157448 78594 157448 78594 157449 78595 157449 78596 157449 78594 157450 78596 157450 78607 157450 78607 157451 78596 157451 78591 157451 78607 157452 78591 157452 78605 157452 78605 157453 78591 157453 78593 157453 78605 157454 78593 157454 78575 157454 78575 157455 78593 157455 78576 157455 78599 157456 78642 157456 78600 157456 78600 157457 78642 157457 78618 157457 78600 157458 78618 157458 78597 157458 78597 157459 78618 157459 78617 157459 78597 157460 78617 157460 78603 157460 78603 157461 78617 157461 78616 157461 78603 157462 78616 157462 78498 157462 78498 157463 78616 157463 78598 157463 78486 157464 78599 157464 78601 157464 78601 157465 78599 157465 78600 157465 78601 157466 78600 157466 78602 157466 78602 157467 78600 157467 78597 157467 78602 157468 78597 157468 78589 157468 78589 157469 78597 157469 78603 157469 78589 157470 78603 157470 78572 157470 78572 157471 78603 157471 78498 157471 78575 157472 78604 157472 78605 157472 78605 157473 78604 157473 78606 157473 78605 157474 78606 157474 78607 157474 78607 157475 78606 157475 78619 157475 78607 157476 78619 157476 78594 157476 78594 157477 78619 157477 78620 157477 78594 157478 78620 157478 78608 157478 78608 157479 78620 157479 78609 157479 78645 157480 78583 157480 78653 157480 78653 157481 78583 157481 78636 157481 78583 157482 78584 157482 78636 157482 78636 157483 78584 157483 78611 157483 78636 157484 78611 157484 78610 157484 78610 157485 78611 157485 78637 157485 78612 157486 78638 157486 78613 157486 78613 157487 78638 157487 78637 157487 78613 157488 78637 157488 78614 157488 78614 157489 78637 157489 78611 157489 78614 157490 78611 157490 78615 157490 78615 157491 78611 157491 78584 157491 78615 157492 78598 157492 78614 157492 78614 157493 78598 157493 78616 157493 78614 157494 78616 157494 78613 157494 78613 157495 78616 157495 78617 157495 78613 157496 78617 157496 78612 157496 78612 157497 78617 157497 78618 157497 78612 157498 78618 157498 78642 157498 78604 157499 78468 157499 78606 157499 78606 157500 78468 157500 78622 157500 78606 157501 78622 157501 78619 157501 78619 157502 78622 157502 78621 157502 78619 157503 78621 157503 78620 157503 78620 157504 78621 157504 78623 157504 78620 157505 78623 157505 78609 157505 78609 157506 78623 157506 78548 157506 78468 157507 78625 157507 78622 157507 78622 157508 78625 157508 78627 157508 78622 157509 78627 157509 78621 157509 78621 157510 78627 157510 78628 157510 78621 157511 78628 157511 78623 157511 78623 157512 78628 157512 78624 157512 78623 157513 78624 157513 78548 157513 78548 157514 78624 157514 78550 157514 78625 157515 78626 157515 78627 157515 78627 157516 78626 157516 78633 157516 78627 157517 78633 157517 78628 157517 78628 157518 78633 157518 78629 157518 78628 157519 78629 157519 78624 157519 78624 157520 78629 157520 78630 157520 78624 157521 78630 157521 78550 157521 78550 157522 78630 157522 78631 157522 78626 157523 78632 157523 78633 157523 78633 157524 78632 157524 78655 157524 78633 157525 78655 157525 78629 157525 78629 157526 78655 157526 78657 157526 78629 157527 78657 157527 78630 157527 78630 157528 78657 157528 78659 157528 78630 157529 78659 157529 78631 157529 78631 157530 78659 157530 78660 157530 78662 157531 78634 157531 78651 157531 78653 157532 78636 157532 78635 157532 78635 157533 78636 157533 78652 157533 78636 157534 78610 157534 78652 157534 78652 157535 78610 157535 78637 157535 78652 157536 78637 157536 78650 157536 78650 157537 78637 157537 78638 157537 78651 157538 78644 157538 78639 157538 78639 157539 78644 157539 78640 157539 78639 157540 78640 157540 78641 157540 78641 157541 78640 157541 78646 157541 78641 157542 78646 157542 78654 157542 78638 157543 78612 157543 78650 157543 78650 157544 78612 157544 78642 157544 78650 157545 78642 157545 78643 157545 78651 157546 78634 157546 78644 157546 78644 157547 78634 157547 78664 157547 78644 157548 78664 157548 78665 157548 78645 157549 78654 157549 78123 157549 78123 157550 78654 157550 78646 157550 78123 157551 78646 157551 78647 157551 78647 157552 78646 157552 78640 157552 78647 157553 78640 157553 78124 157553 78124 157554 78640 157554 78644 157554 78124 157555 78644 157555 78648 157555 78648 157556 78644 157556 78665 157556 78648 157557 78665 157557 78649 157557 78643 157558 78662 157558 78650 157558 78650 157559 78662 157559 78651 157559 78650 157560 78651 157560 78652 157560 78652 157561 78651 157561 78639 157561 78652 157562 78639 157562 78635 157562 78635 157563 78639 157563 78641 157563 78635 157564 78641 157564 78653 157564 78653 157565 78641 157565 78654 157565 78653 157566 78654 157566 78645 157566 78632 157567 78514 157567 78656 157567 78632 157568 78656 157568 78655 157568 78655 157569 78656 157569 78672 157569 78655 157570 78672 157570 78657 157570 78657 157571 78672 157571 78658 157571 78657 157572 78658 157572 78659 157572 78659 157573 78658 157573 78144 157573 78659 157574 78144 157574 78660 157574 78642 157575 78661 157575 78643 157575 78643 157576 78661 157576 78663 157576 78643 157577 78663 157577 78662 157577 78662 157578 78663 157578 78634 157578 78634 157579 78663 157579 78667 157579 78634 157580 78667 157580 78664 157580 78664 157581 78667 157581 78665 157581 78665 157582 78667 157582 78668 157582 78665 157583 78668 157583 78649 157583 78661 157584 78688 157584 78666 157584 78661 157585 78666 157585 78663 157585 78663 157586 78666 157586 78683 157586 78663 157587 78683 157587 78667 157587 78667 157588 78683 157588 78143 157588 78667 157589 78143 157589 78668 157589 78675 157590 78656 157590 78669 157590 78669 157591 78656 157591 78514 157591 78670 157592 78144 157592 78671 157592 78671 157593 78144 157593 78658 157593 78671 157594 78658 157594 78675 157594 78675 157595 78658 157595 78672 157595 78675 157596 78672 157596 78656 157596 78149 157597 78670 157597 78673 157597 78673 157598 78670 157598 78671 157598 78673 157599 78671 157599 78674 157599 78674 157600 78671 157600 78675 157600 78674 157601 78675 157601 78518 157601 78518 157602 78675 157602 78669 157602 78693 157603 78149 157603 78676 157603 78676 157604 78149 157604 78673 157604 78676 157605 78673 157605 78677 157605 78677 157606 78673 157606 78674 157606 78677 157607 78674 157607 78678 157607 78678 157608 78674 157608 78518 157608 78143 157609 78683 157609 78679 157609 78679 157610 78683 157610 78681 157610 78679 157611 78681 157611 78680 157611 78680 157612 78681 157612 78685 157612 78680 157613 78685 157613 78142 157613 78142 157614 78685 157614 78682 157614 78142 157615 78682 157615 78130 157615 78130 157616 78682 157616 78700 157616 78683 157617 78666 157617 78681 157617 78681 157618 78666 157618 78684 157618 78681 157619 78684 157619 78685 157619 78685 157620 78684 157620 78690 157620 78685 157621 78690 157621 78682 157621 78682 157622 78690 157622 78686 157622 78682 157623 78686 157623 78700 157623 78700 157624 78686 157624 78687 157624 78666 157625 78688 157625 78684 157625 78684 157626 78688 157626 78689 157626 78684 157627 78689 157627 78690 157627 78690 157628 78689 157628 78549 157628 78690 157629 78549 157629 78686 157629 78686 157630 78549 157630 78691 157630 78686 157631 78691 157631 78687 157631 78687 157632 78691 157632 78692 157632 78146 157633 78693 157633 78697 157633 78697 157634 78693 157634 78676 157634 78697 157635 78676 157635 78694 157635 78694 157636 78676 157636 78677 157636 78694 157637 78677 157637 78695 157637 78695 157638 78677 157638 78678 157638 78145 157639 78146 157639 78696 157639 78696 157640 78146 157640 78697 157640 78696 157641 78697 157641 78705 157641 78705 157642 78697 157642 78694 157642 78705 157643 78694 157643 78698 157643 78698 157644 78694 157644 78695 157644 78537 157645 78130 157645 78699 157645 78699 157646 78130 157646 78700 157646 78699 157647 78700 157647 78714 157647 78714 157648 78700 157648 78715 157648 78715 157649 78700 157649 78687 157649 78715 157650 78687 157650 78701 157650 78701 157651 78687 157651 78702 157651 78702 157652 78687 157652 78692 157652 78702 157653 78692 157653 78150 157653 78703 157654 78145 157654 78706 157654 78706 157655 78145 157655 78696 157655 78706 157656 78696 157656 78704 157656 78704 157657 78696 157657 78705 157657 78704 157658 78705 157658 78707 157658 78707 157659 78705 157659 78698 157659 78147 157660 78703 157660 78709 157660 78709 157661 78703 157661 78706 157661 78709 157662 78706 157662 78710 157662 78710 157663 78706 157663 78704 157663 78710 157664 78704 157664 78711 157664 78711 157665 78704 157665 78707 157665 78708 157666 78147 157666 78720 157666 78720 157667 78147 157667 78709 157667 78720 157668 78709 157668 78722 157668 78722 157669 78709 157669 78710 157669 78722 157670 78710 157670 78513 157670 78513 157671 78710 157671 78711 157671 78717 157672 78712 157672 78537 157672 78713 157673 78702 157673 78148 157673 78148 157674 78702 157674 78150 157674 78537 157675 78699 157675 78717 157675 78717 157676 78699 157676 78714 157676 78717 157677 78714 157677 78716 157677 78716 157678 78714 157678 78715 157678 78716 157679 78715 157679 78713 157679 78713 157680 78715 157680 78701 157680 78713 157681 78701 157681 78702 157681 78731 157682 78712 157682 78730 157682 78730 157683 78712 157683 78717 157683 78730 157684 78717 157684 78729 157684 78729 157685 78717 157685 78716 157685 78729 157686 78716 157686 78718 157686 78718 157687 78716 157687 78713 157687 78718 157688 78713 157688 78719 157688 78719 157689 78713 157689 78148 157689 78734 157690 78708 157690 78720 157690 78734 157691 78720 157691 78721 157691 78721 157692 78720 157692 78722 157692 78721 157693 78722 157693 78740 157693 78740 157694 78722 157694 78513 157694 78740 157695 78513 157695 78741 157695 78196 157696 78195 157696 77304 157696 77304 157697 78195 157697 78732 157697 77304 157698 78732 157698 78733 157698 78733 157699 78732 157699 78723 157699 78733 157700 78723 157700 78727 157700 78728 157701 78724 157701 78734 157701 78734 157702 78738 157702 78728 157702 78728 157703 78738 157703 78725 157703 78728 157704 78725 157704 78723 157704 78723 157705 78725 157705 78726 157705 78723 157706 78726 157706 78727 157706 78719 157707 78724 157707 78718 157707 78718 157708 78724 157708 78728 157708 78718 157709 78728 157709 78729 157709 78729 157710 78728 157710 78723 157710 78729 157711 78723 157711 78730 157711 78730 157712 78723 157712 78732 157712 78730 157713 78732 157713 78731 157713 78731 157714 78732 157714 78195 157714 78733 157715 78727 157715 77311 157715 78203 157716 77314 157716 77313 157716 78721 157717 78740 157717 78739 157717 78738 157718 78734 157718 78737 157718 78737 157719 78734 157719 78721 157719 78721 157720 78739 157720 78737 157720 78737 157721 78739 157721 78735 157721 78737 157722 78735 157722 78736 157722 78736 157723 78726 157723 78737 157723 78737 157724 78726 157724 78725 157724 78737 157725 78725 157725 78738 157725 78727 157726 78726 157726 77311 157726 77311 157727 78726 157727 78736 157727 77311 157728 78736 157728 77312 157728 77312 157729 78736 157729 78735 157729 77312 157730 78735 157730 77313 157730 77313 157731 78735 157731 78739 157731 77313 157732 78739 157732 78203 157732 78203 157733 78739 157733 78740 157733 78203 157734 78740 157734 78741 157734 77361 157735 78743 157735 77360 157735 78749 157736 78744 157736 78567 157736 78567 157737 78744 157737 77358 157737 78745 157738 78747 157738 78748 157738 78748 157739 78747 157739 78742 157739 78743 157740 77361 157740 78197 157740 78751 157741 78538 157741 78746 157741 78748 157742 77358 157742 78745 157742 78745 157743 77358 157743 78744 157743 78745 157744 78744 157744 78747 157744 78747 157745 78744 157745 78751 157745 78751 157746 78746 157746 78747 157746 78747 157747 78746 157747 78197 157747 78747 157748 78197 157748 78742 157748 78742 157749 78197 157749 77361 157749 78742 157750 77361 157750 78748 157750 78749 157751 78750 157751 78744 157751 78744 157752 78750 157752 78755 157752 78744 157753 78755 157753 78751 157753 78751 157754 78755 157754 78753 157754 78751 157755 78753 157755 78538 157755 78538 157756 78753 157756 78752 157756 78760 157757 78752 157757 78758 157757 78758 157758 78752 157758 78753 157758 78758 157759 78753 157759 78754 157759 78754 157760 78753 157760 78755 157760 78754 157761 78755 157761 78756 157761 78756 157762 78755 157762 78750 157762 78756 157763 78098 157763 78757 157763 78756 157764 78757 157764 78754 157764 78754 157765 78757 157765 78759 157765 78754 157766 78759 157766 78758 157766 78758 157767 78759 157767 78122 157767 78758 157768 78122 157768 78760 157768 78122 157769 78759 157769 78761 157769 78759 157770 78757 157770 78762 157770 78757 157771 78098 157771 78104 157771 78757 157772 78104 157772 78762 157772 78762 157773 78104 157773 78102 157773 78762 157774 78102 157774 78765 157774 78765 157775 78102 157775 78101 157775 78765 157776 78101 157776 78764 157776 78764 157777 78101 157777 78763 157777 78764 157778 78763 157778 78772 157778 78759 157779 78762 157779 78761 157779 78761 157780 78762 157780 78765 157780 78761 157781 78765 157781 78766 157781 78766 157782 78765 157782 78764 157782 78766 157783 78764 157783 78767 157783 78767 157784 78764 157784 78772 157784 78767 157785 78772 157785 78768 157785 78122 157786 78761 157786 78769 157786 78769 157787 78761 157787 78766 157787 78769 157788 78766 157788 78770 157788 78770 157789 78766 157789 78767 157789 78770 157790 78767 157790 78137 157790 78137 157791 78767 157791 78768 157791 78137 157792 78768 157792 78138 157792 78763 157793 78105 157793 78771 157793 78763 157794 78771 157794 78772 157794 78772 157795 78771 157795 78776 157795 78772 157796 78776 157796 78768 157796 78768 157797 78776 157797 78139 157797 78768 157798 78139 157798 78138 157798 78774 157799 78775 157799 78096 157799 78096 157800 78773 157800 78774 157800 78774 157801 78773 157801 78786 157801 78774 157802 78786 157802 78777 157802 78105 157803 78775 157803 78771 157803 78771 157804 78775 157804 78774 157804 78771 157805 78774 157805 78776 157805 78776 157806 78774 157806 78777 157806 78776 157807 78777 157807 78139 157807 78139 157808 78777 157808 78141 157808 78786 157809 78778 157809 78777 157809 78777 157810 78778 157810 78779 157810 78777 157811 78779 157811 78141 157811 78141 157812 78779 157812 78782 157812 78141 157813 78782 157813 78780 157813 78780 157814 78782 157814 78109 157814 78109 157815 78782 157815 78781 157815 78781 157816 78782 157816 78783 157816 78783 157817 78782 157817 78779 157817 78783 157818 78779 157818 78784 157818 78784 157819 78779 157819 78778 157819 78784 157820 78778 157820 78785 157820 78785 157821 78778 157821 78786 157821 78785 157822 78786 157822 78790 157822 78786 157823 78773 157823 78790 157823 78790 157824 78773 157824 78096 157824 78790 157825 78096 157825 77822 157825 78791 157826 78787 157826 77821 157826 78788 157827 78520 157827 78519 157827 78795 157828 78788 157828 78789 157828 78519 157829 78109 157829 78781 157829 78788 157830 78519 157830 78789 157830 78789 157831 78519 157831 78781 157831 78789 157832 78781 157832 78783 157832 78783 157833 78784 157833 78789 157833 78789 157834 78784 157834 78791 157834 78789 157835 78791 157835 78795 157835 78795 157836 78791 157836 77821 157836 77822 157837 78787 157837 78790 157837 78790 157838 78787 157838 78791 157838 78790 157839 78791 157839 78785 157839 78785 157840 78791 157840 78784 157840 78792 157841 78202 157841 78200 157841 78792 157842 78200 157842 78797 157842 78793 157843 78788 157843 78795 157843 77821 157844 78794 157844 78795 157844 78795 157845 78794 157845 78796 157845 78795 157846 78796 157846 78793 157846 78793 157847 78796 157847 77278 157847 78793 157848 77278 157848 78797 157848 78797 157849 78200 157849 78793 157849 78793 157850 78200 157850 78520 157850 78793 157851 78520 157851 78788 157851 78482 157852 78798 157852 78799 157852 78799 157853 78798 157853 78800 157853 78799 157854 78800 157854 78801 157854 78801 157855 78800 157855 78817 157855 78801 157856 78817 157856 78806 157856 78806 157857 78817 157857 78802 157857 78806 157858 78802 157858 78497 157858 78497 157859 78802 157859 78571 157859 78841 157860 78482 157860 78803 157860 78803 157861 78482 157861 78799 157861 78803 157862 78799 157862 78804 157862 78804 157863 78799 157863 78801 157863 78804 157864 78801 157864 78805 157864 78805 157865 78801 157865 78806 157865 78805 157866 78806 157866 78822 157866 78822 157867 78806 157867 78497 157867 78807 157868 78569 157868 78814 157868 78810 157869 78808 157869 78828 157869 78464 157870 78568 157870 78826 157870 78826 157871 78568 157871 78809 157871 78826 157872 78809 157872 78813 157872 78813 157873 78809 157873 78811 157873 78828 157874 78829 157874 78810 157874 78810 157875 78829 157875 78830 157875 78810 157876 78830 157876 78811 157876 78811 157877 78830 157877 78812 157877 78811 157878 78812 157878 78813 157878 78483 157879 78808 157879 78815 157879 78815 157880 78808 157880 78810 157880 78815 157881 78810 157881 78816 157881 78816 157882 78810 157882 78811 157882 78816 157883 78811 157883 78814 157883 78814 157884 78811 157884 78809 157884 78814 157885 78809 157885 78807 157885 78807 157886 78809 157886 78568 157886 78798 157887 78483 157887 78800 157887 78800 157888 78483 157888 78815 157888 78800 157889 78815 157889 78817 157889 78817 157890 78815 157890 78816 157890 78817 157891 78816 157891 78802 157891 78802 157892 78816 157892 78814 157892 78802 157893 78814 157893 78571 157893 78571 157894 78814 157894 78569 157894 78818 157895 78578 157895 78580 157895 78820 157896 78833 157896 78819 157896 78819 157897 78833 157897 78832 157897 78824 157898 78803 157898 78804 157898 78803 157899 78824 157899 78841 157899 78838 157900 78823 157900 78832 157900 78832 157901 78823 157901 78818 157901 78832 157902 78818 157902 78819 157902 78819 157903 78818 157903 78580 157903 78819 157904 78580 157904 78820 157904 78820 157905 78580 157905 78581 157905 78820 157906 78581 157906 78821 157906 78821 157907 78581 157907 78582 157907 78822 157908 78578 157908 78805 157908 78805 157909 78578 157909 78818 157909 78805 157910 78818 157910 78804 157910 78804 157911 78818 157911 78823 157911 78804 157912 78823 157912 78824 157912 78824 157913 78823 157913 78838 157913 78825 157914 78464 157914 78826 157914 78825 157915 78826 157915 78827 157915 78826 157916 78813 157916 78827 157916 78827 157917 78813 157917 78812 157917 78827 157918 78812 157918 78831 157918 78828 157919 78547 157919 78829 157919 78829 157920 78547 157920 78831 157920 78829 157921 78831 157921 78830 157921 78830 157922 78831 157922 78812 157922 78838 157923 78832 157923 78839 157923 78170 157924 78821 157924 78582 157924 78821 157925 78170 157925 78835 157925 78833 157926 78820 157926 78835 157926 78835 157927 78820 157927 78821 157927 78832 157928 78833 157928 78839 157928 78839 157929 78833 157929 78835 157929 78839 157930 78835 157930 78834 157930 78834 157931 78835 157931 78170 157931 78834 157932 78170 157932 78836 157932 78840 157933 78156 157933 78837 157933 78837 157934 78156 157934 78845 157934 78837 157935 78845 157935 78844 157935 78824 157936 78838 157936 78844 157936 78844 157937 78838 157937 78839 157937 78844 157938 78839 157938 78837 157938 78837 157939 78839 157939 78834 157939 78837 157940 78834 157940 78840 157940 78840 157941 78834 157941 78836 157941 78841 157942 78824 157942 78842 157942 78842 157943 78824 157943 78844 157943 78842 157944 78844 157944 78843 157944 78843 157945 78844 157945 78845 157945 78843 157946 78845 157946 78867 157946 78867 157947 78845 157947 78156 157947 78855 157948 78848 157948 78852 157948 78847 157949 78467 157949 78846 157949 78847 157950 78846 157950 78857 157950 78857 157951 78846 157951 78848 157951 78848 157952 78846 157952 78849 157952 78848 157953 78849 157953 78852 157953 78852 157954 78849 157954 78851 157954 78852 157955 78851 157955 78850 157955 78850 157956 78851 157956 78825 157956 78850 157957 78825 157957 78827 157957 78855 157958 78852 157958 78853 157958 78853 157959 78852 157959 78850 157959 78853 157960 78850 157960 78861 157960 78861 157961 78850 157961 78827 157961 78861 157962 78827 157962 78831 157962 78858 157963 78854 157963 78855 157963 78855 157964 78854 157964 78856 157964 78855 157965 78856 157965 78848 157965 78848 157966 78856 157966 78870 157966 78848 157967 78870 157967 78857 157967 78858 157968 78855 157968 78545 157968 78545 157969 78855 157969 78853 157969 78545 157970 78853 157970 78859 157970 78859 157971 78853 157971 78861 157971 78859 157972 78861 157972 78860 157972 78860 157973 78861 157973 78831 157973 78860 157974 78831 157974 78547 157974 78485 157975 78484 157975 78865 157975 78485 157976 78865 157976 78862 157976 78862 157977 78865 157977 78866 157977 78862 157978 78866 157978 78863 157978 78863 157979 78866 157979 78864 157979 78863 157980 78864 157980 78879 157980 78484 157981 78841 157981 78842 157981 78484 157982 78842 157982 78865 157982 78865 157983 78842 157983 78843 157983 78865 157984 78843 157984 78866 157984 78866 157985 78843 157985 78867 157985 78866 157986 78867 157986 78864 157986 78467 157987 78847 157987 78868 157987 78868 157988 78847 157988 78869 157988 78869 157989 78847 157989 78891 157989 78891 157990 78847 157990 78857 157990 78891 157991 78857 157991 78892 157991 78892 157992 78857 157992 78870 157992 78892 157993 78870 157993 78871 157993 78871 157994 78870 157994 78856 157994 78871 157995 78856 157995 78872 157995 78856 157996 78854 157996 78872 157996 78872 157997 78854 157997 78858 157997 78872 157998 78858 157998 78873 157998 78874 157999 78898 157999 78881 157999 78181 158000 78896 158000 78875 158000 78875 158001 78896 158001 78876 158001 78875 158002 78876 158002 78168 158002 78168 158003 78876 158003 78878 158003 78168 158004 78878 158004 78877 158004 78877 158005 78878 158005 78880 158005 78877 158006 78880 158006 78879 158006 78879 158007 78880 158007 78863 158007 78896 158008 78874 158008 78876 158008 78876 158009 78874 158009 78881 158009 78876 158010 78881 158010 78878 158010 78878 158011 78881 158011 78882 158011 78878 158012 78882 158012 78880 158012 78880 158013 78882 158013 78883 158013 78880 158014 78883 158014 78863 158014 78863 158015 78883 158015 78862 158015 78898 158016 78884 158016 78881 158016 78881 158017 78884 158017 78885 158017 78881 158018 78885 158018 78882 158018 78882 158019 78885 158019 78546 158019 78882 158020 78546 158020 78883 158020 78883 158021 78546 158021 78886 158021 78883 158022 78886 158022 78862 158022 78862 158023 78886 158023 78485 158023 78903 158024 78887 158024 78890 158024 78888 158025 78890 158025 78516 158025 78516 158026 78890 158026 78887 158026 78516 158027 78887 158027 78515 158027 78889 158028 78895 158028 78894 158028 78868 158029 78869 158029 78888 158029 78888 158030 78869 158030 78889 158030 78888 158031 78889 158031 78890 158031 78890 158032 78889 158032 78894 158032 78890 158033 78894 158033 78903 158033 78903 158034 78894 158034 78183 158034 78869 158035 78891 158035 78889 158035 78889 158036 78891 158036 78892 158036 78889 158037 78892 158037 78895 158037 78895 158038 78892 158038 78871 158038 78895 158039 78871 158039 78872 158039 78183 158040 78894 158040 78893 158040 78893 158041 78894 158041 78895 158041 78893 158042 78895 158042 78182 158042 78182 158043 78895 158043 78872 158043 78182 158044 78872 158044 78873 158044 78181 158045 78912 158045 78913 158045 78181 158046 78913 158046 78896 158046 78896 158047 78913 158047 78914 158047 78896 158048 78914 158048 78874 158048 78874 158049 78914 158049 78897 158049 78874 158050 78897 158050 78898 158050 78898 158051 78897 158051 78184 158051 78898 158052 78184 158052 78884 158052 78902 158053 78899 158053 78904 158053 78904 158054 78899 158054 78900 158054 78904 158055 78900 158055 78905 158055 78905 158056 78900 158056 78901 158056 78905 158057 78901 158057 78906 158057 78906 158058 78901 158058 78509 158058 78183 158059 78902 158059 78903 158059 78903 158060 78902 158060 78904 158060 78903 158061 78904 158061 78887 158061 78887 158062 78904 158062 78905 158062 78887 158063 78905 158063 78515 158063 78515 158064 78905 158064 78906 158064 78907 158065 78909 158065 78908 158065 78908 158066 78909 158066 78928 158066 78908 158067 78928 158067 78910 158067 78910 158068 78928 158068 78930 158068 78910 158069 78930 158069 78911 158069 78911 158070 78930 158070 78932 158070 78911 158071 78932 158071 78915 158071 78915 158072 78932 158072 78934 158072 78912 158073 78907 158073 78913 158073 78913 158074 78907 158074 78908 158074 78913 158075 78908 158075 78914 158075 78914 158076 78908 158076 78910 158076 78914 158077 78910 158077 78897 158077 78897 158078 78910 158078 78911 158078 78897 158079 78911 158079 78184 158079 78184 158080 78911 158080 78915 158080 78916 158081 78917 158081 78921 158081 78921 158082 78917 158082 78939 158082 78921 158083 78939 158083 78924 158083 78924 158084 78939 158084 78937 158084 78924 158085 78937 158085 78918 158085 78918 158086 78937 158086 78919 158086 78920 158087 78916 158087 78925 158087 78925 158088 78916 158088 78921 158088 78925 158089 78921 158089 78922 158089 78922 158090 78921 158090 78924 158090 78922 158091 78924 158091 78923 158091 78923 158092 78924 158092 78918 158092 78899 158093 78920 158093 78900 158093 78900 158094 78920 158094 78925 158094 78900 158095 78925 158095 78901 158095 78901 158096 78925 158096 78922 158096 78901 158097 78922 158097 78509 158097 78509 158098 78922 158098 78923 158098 78931 158099 78950 158099 78933 158099 78933 158100 78950 158100 78949 158100 78933 158101 78949 158101 78935 158101 78929 158102 78926 158102 78931 158102 78931 158103 78926 158103 78947 158103 78931 158104 78947 158104 78950 158104 78194 158105 78193 158105 78929 158105 78929 158106 78193 158106 77306 158106 77306 158107 78927 158107 78929 158107 78929 158108 78927 158108 77319 158108 78929 158109 77319 158109 78926 158109 78909 158110 78194 158110 78928 158110 78928 158111 78194 158111 78929 158111 78928 158112 78929 158112 78930 158112 78930 158113 78929 158113 78931 158113 78930 158114 78931 158114 78932 158114 78932 158115 78931 158115 78933 158115 78932 158116 78933 158116 78934 158116 78934 158117 78933 158117 78935 158117 78936 158118 78919 158118 78937 158118 78936 158119 78937 158119 78938 158119 78938 158120 78937 158120 78939 158120 78938 158121 78939 158121 78940 158121 78940 158122 78939 158122 78917 158122 78940 158123 78917 158123 78949 158123 78946 158124 78950 158124 78947 158124 78948 158125 78941 158125 78945 158125 78945 158126 78941 158126 78944 158126 77321 158127 78951 158127 77340 158127 77340 158128 78951 158128 78942 158128 77340 158129 78942 158129 78943 158129 78943 158130 78942 158130 78944 158130 78944 158131 78942 158131 78946 158131 78944 158132 78946 158132 78945 158132 78945 158133 78946 158133 78947 158133 78945 158134 78947 158134 78948 158134 78948 158135 78947 158135 78926 158135 78948 158136 78926 158136 77319 158136 78949 158137 78950 158137 78940 158137 78940 158138 78950 158138 78946 158138 78940 158139 78946 158139 78938 158139 78938 158140 78946 158140 78942 158140 78938 158141 78942 158141 78936 158141 78936 158142 78942 158142 78951 158142 79901 158143 78425 158143 78955 158143 79901 158144 78955 158144 79903 158144 79903 158145 78955 158145 78953 158145 79903 158146 78953 158146 79905 158146 79905 158147 78953 158147 78952 158147 79905 158148 78952 158148 78127 158148 78952 158149 78953 158149 78954 158149 78965 158150 78962 158150 78961 158150 78953 158151 78955 158151 78958 158151 78955 158152 78425 158152 78505 158152 78955 158153 78505 158153 78958 158153 78958 158154 78505 158154 78507 158154 78958 158155 78507 158155 78959 158155 78959 158156 78507 158156 78956 158156 78959 158157 78956 158157 78957 158157 78953 158158 78958 158158 78954 158158 78954 158159 78958 158159 78959 158159 78954 158160 78959 158160 78961 158160 78961 158161 78959 158161 78957 158161 78961 158162 78957 158162 78965 158162 78952 158163 78954 158163 78960 158163 78960 158164 78954 158164 78961 158164 78960 158165 78961 158165 78140 158165 78140 158166 78961 158166 78962 158166 78140 158167 78962 158167 78129 158167 78956 158168 78969 158168 78963 158168 78956 158169 78963 158169 78957 158169 78957 158170 78963 158170 78964 158170 78957 158171 78964 158171 78965 158171 78965 158172 78964 158172 78966 158172 78965 158173 78966 158173 78962 158173 78962 158174 78966 158174 78128 158174 78962 158175 78128 158175 78129 158175 78967 158176 78128 158176 78966 158176 78585 158177 78967 158177 78970 158177 78970 158178 78967 158178 78966 158178 78970 158179 78966 158179 78972 158179 78972 158180 78966 158180 78964 158180 78972 158181 78964 158181 78973 158181 78973 158182 78964 158182 78963 158182 78973 158183 78963 158183 78968 158183 78968 158184 78963 158184 78969 158184 78586 158185 78585 158185 78974 158185 78974 158186 78585 158186 78970 158186 78974 158187 78970 158187 78975 158187 78975 158188 78970 158188 78972 158188 78975 158189 78972 158189 78971 158189 78971 158190 78972 158190 78973 158190 78971 158191 78973 158191 78978 158191 78978 158192 78973 158192 78968 158192 78986 158193 78586 158193 78974 158193 78986 158194 78974 158194 78985 158194 78985 158195 78974 158195 78975 158195 78985 158196 78975 158196 78976 158196 78976 158197 78975 158197 78971 158197 78976 158198 78971 158198 78977 158198 78977 158199 78971 158199 78978 158199 78977 158200 78978 158200 78426 158200 78979 158201 78980 158201 78984 158201 78984 158202 78980 158202 78995 158202 78984 158203 78995 158203 78981 158203 78981 158204 78995 158204 78982 158204 78981 158205 78982 158205 78987 158205 78987 158206 78982 158206 78997 158206 78987 158207 78997 158207 78988 158207 78988 158208 78997 158208 78983 158208 78426 158209 78979 158209 78977 158209 78977 158210 78979 158210 78984 158210 78977 158211 78984 158211 78976 158211 78976 158212 78984 158212 78981 158212 78976 158213 78981 158213 78985 158213 78985 158214 78981 158214 78987 158214 78985 158215 78987 158215 78986 158215 78986 158216 78987 158216 78988 158216 78574 158217 78989 158217 78990 158217 78991 158218 78992 158218 78996 158218 78996 158219 78992 158219 79004 158219 78996 158220 79004 158220 78993 158220 78993 158221 79004 158221 78994 158221 78993 158222 78994 158222 78990 158222 78990 158223 78994 158223 79005 158223 78990 158224 79005 158224 78574 158224 78574 158225 79005 158225 78577 158225 78980 158226 78991 158226 78995 158226 78995 158227 78991 158227 78996 158227 78995 158228 78996 158228 78982 158228 78982 158229 78996 158229 78993 158229 78982 158230 78993 158230 78997 158230 78997 158231 78993 158231 78990 158231 78997 158232 78990 158232 78983 158232 78983 158233 78990 158233 78989 158233 79000 158234 78430 158234 78429 158234 79009 158235 78998 158235 78999 158235 78999 158236 78998 158236 79007 158236 78999 158237 79007 158237 79003 158237 79003 158238 79007 158238 79006 158238 78429 158239 79008 158239 79000 158239 79000 158240 79008 158240 79001 158240 79000 158241 79001 158241 79006 158241 79006 158242 79001 158242 79002 158242 79006 158243 79002 158243 79003 158243 78992 158244 78430 158244 79004 158244 79004 158245 78430 158245 79000 158245 79004 158246 79000 158246 78994 158246 78994 158247 79000 158247 79006 158247 78994 158248 79006 158248 79005 158248 79005 158249 79006 158249 79007 158249 79005 158250 79007 158250 78577 158250 78577 158251 79007 158251 78998 158251 78429 158252 78428 158252 79008 158252 79008 158253 78428 158253 79024 158253 79008 158254 79024 158254 79001 158254 79001 158255 79024 158255 79002 158255 79002 158256 79024 158256 79015 158256 79002 158257 79015 158257 79003 158257 79003 158258 79015 158258 78999 158258 78999 158259 79015 158259 78471 158259 78999 158260 78471 158260 79009 158260 79023 158261 79010 158261 79011 158261 79018 158262 78480 158262 79012 158262 79018 158263 79012 158263 79013 158263 79013 158264 79012 158264 78469 158264 79013 158265 78469 158265 79021 158265 79021 158266 78469 158266 78470 158266 79021 158267 78470 158267 79014 158267 79014 158268 78470 158268 78471 158268 79014 158269 78471 158269 79015 158269 79952 158270 78480 158270 79016 158270 79016 158271 78480 158271 79018 158271 79016 158272 79018 158272 79017 158272 79017 158273 79018 158273 79010 158273 79010 158274 79018 158274 79011 158274 79011 158275 79018 158275 79013 158275 79011 158276 79013 158276 79019 158276 79019 158277 79013 158277 79021 158277 79019 158278 79021 158278 79020 158278 79020 158279 79021 158279 79014 158279 79020 158280 79014 158280 79022 158280 79022 158281 79014 158281 79015 158281 79022 158282 79015 158282 79024 158282 79023 158283 79011 158283 78431 158283 78431 158284 79011 158284 79019 158284 78431 158285 79019 158285 78432 158285 78432 158286 79019 158286 79020 158286 78432 158287 79020 158287 78433 158287 78433 158288 79020 158288 79022 158288 78433 158289 79022 158289 78434 158289 78434 158290 79022 158290 79024 158290 78434 158291 79024 158291 78428 158291 79025 158292 79038 158292 79039 158292 79029 158293 79027 158293 79026 158293 79050 158294 79048 158294 78465 158294 79050 158295 78465 158295 79027 158295 79027 158296 78465 158296 79028 158296 79027 158297 79028 158297 79026 158297 79026 158298 79028 158298 78475 158298 79026 158299 78475 158299 79031 158299 79031 158300 78475 158300 78477 158300 79031 158301 78477 158301 79033 158301 79033 158302 78477 158302 78472 158302 79033 158303 78472 158303 79034 158303 79029 158304 79026 158304 79030 158304 79030 158305 79026 158305 79031 158305 79030 158306 79031 158306 79040 158306 79040 158307 79031 158307 79033 158307 79040 158308 79033 158308 79032 158308 79032 158309 79033 158309 79034 158309 79032 158310 79034 158310 79035 158310 79038 158311 79036 158311 79029 158311 79029 158312 79036 158312 79053 158312 79029 158313 79053 158313 79027 158313 79027 158314 79053 158314 79037 158314 79027 158315 79037 158315 79050 158315 79038 158316 79029 158316 79039 158316 79039 158317 79029 158317 79030 158317 79039 158318 79030 158318 79042 158318 79042 158319 79030 158319 79040 158319 79042 158320 79040 158320 79041 158320 79041 158321 79040 158321 79032 158321 79041 158322 79032 158322 79045 158322 79045 158323 79032 158323 79035 158323 79045 158324 79035 158324 79046 158324 79025 158325 79039 158325 78436 158325 78436 158326 79039 158326 79042 158326 78436 158327 79042 158327 79043 158327 79043 158328 79042 158328 79041 158328 79043 158329 79041 158329 79044 158329 79044 158330 79041 158330 79045 158330 79044 158331 79045 158331 78438 158331 78438 158332 79045 158332 79046 158332 78438 158333 79046 158333 79402 158333 79047 158334 79048 158334 79049 158334 79049 158335 79048 158335 79050 158335 79049 158336 79050 158336 79051 158336 79051 158337 79050 158337 79037 158337 79051 158338 79037 158338 79052 158338 79052 158339 79037 158339 79053 158339 79052 158340 79053 158340 79054 158340 79054 158341 79053 158341 79036 158341 79054 158342 79036 158342 79068 158342 79068 158343 79036 158343 79038 158343 79068 158344 79038 158344 79067 158344 79067 158345 79038 158345 79025 158345 79047 158346 79049 158346 79056 158346 79065 158347 79055 158347 79056 158347 79057 158348 79058 158348 79059 158348 79057 158349 79055 158349 79060 158349 79060 158350 79055 158350 79065 158350 79060 158351 79065 158351 79072 158351 79072 158352 79065 158352 79071 158352 78445 158353 79070 158353 79066 158353 79064 158354 79062 158354 79066 158354 78445 158355 79066 158355 79061 158355 79061 158356 79066 158356 79062 158356 79061 158357 79062 158357 78439 158357 79057 158358 79059 158358 79055 158358 79055 158359 79059 158359 78570 158359 79055 158360 78570 158360 79056 158360 79056 158361 78570 158361 79063 158361 79056 158362 79063 158362 79047 158362 79049 158363 79051 158363 79056 158363 79056 158364 79051 158364 79064 158364 79056 158365 79064 158365 79065 158365 79065 158366 79064 158366 79066 158366 79065 158367 79066 158367 79071 158367 79071 158368 79066 158368 79070 158368 79067 158369 78439 158369 79068 158369 79068 158370 78439 158370 79062 158370 79068 158371 79062 158371 79054 158371 79054 158372 79062 158372 79064 158372 79054 158373 79064 158373 79052 158373 79052 158374 79064 158374 79051 158374 78445 158375 79069 158375 79070 158375 79070 158376 79069 158376 79077 158376 79070 158377 79077 158377 79071 158377 79071 158378 79077 158378 79072 158378 79072 158379 79077 158379 79075 158379 79072 158380 79075 158380 79060 158380 79060 158381 79075 158381 79057 158381 79057 158382 79075 158382 79073 158382 79057 158383 79073 158383 79058 158383 79078 158384 79073 158384 79074 158384 79074 158385 79073 158385 79075 158385 79074 158386 79075 158386 79081 158386 79081 158387 79075 158387 79077 158387 79081 158388 79077 158388 79076 158388 79076 158389 79077 158389 79069 158389 78579 158390 79078 158390 79079 158390 79079 158391 79078 158391 79074 158391 79079 158392 79074 158392 79080 158392 79080 158393 79074 158393 79081 158393 79080 158394 79081 158394 79082 158394 79082 158395 79081 158395 79076 158395 79085 158396 78579 158396 79086 158396 79086 158397 78579 158397 79079 158397 79086 158398 79079 158398 79083 158398 79083 158399 79079 158399 79080 158399 79083 158400 79080 158400 78441 158400 78441 158401 79080 158401 79082 158401 79088 158402 79085 158402 79084 158402 79084 158403 79085 158403 79086 158403 79084 158404 79086 158404 79087 158404 79087 158405 79086 158405 79083 158405 79087 158406 79083 158406 78444 158406 78444 158407 79083 158407 78441 158407 78173 158408 79088 158408 79089 158408 79089 158409 79088 158409 79084 158409 79089 158410 79084 158410 79090 158410 79090 158411 79084 158411 79087 158411 79090 158412 79087 158412 79091 158412 79091 158413 79087 158413 78444 158413 79095 158414 78499 158414 79092 158414 79092 158415 79099 158415 79095 158415 79095 158416 79099 158416 79093 158416 79095 158417 79093 158417 79094 158417 79091 158418 78499 158418 79090 158418 79090 158419 78499 158419 79095 158419 79090 158420 79095 158420 79089 158420 79089 158421 79095 158421 79094 158421 79089 158422 79094 158422 78173 158422 78173 158423 79094 158423 78157 158423 79093 158424 79096 158424 79094 158424 79094 158425 79096 158425 79101 158425 79094 158426 79101 158426 78157 158426 78157 158427 79101 158427 79105 158427 78157 158428 79105 158428 79097 158428 79110 158429 79098 158429 79092 158429 79092 158430 79098 158430 79099 158430 79099 158431 79098 158431 79093 158431 79093 158432 79098 158432 79100 158432 79093 158433 79100 158433 79096 158433 79096 158434 79100 158434 79102 158434 79096 158435 79102 158435 79101 158435 79101 158436 79102 158436 79103 158436 79101 158437 79103 158437 79105 158437 79103 158438 79104 158438 79105 158438 79105 158439 79104 158439 79106 158439 79105 158440 79106 158440 79097 158440 78502 158441 78504 158441 79111 158441 79107 158442 79100 158442 79098 158442 78502 158443 79111 158443 79109 158443 79100 158444 79107 158444 79102 158444 79102 158445 79107 158445 79108 158445 79102 158446 79108 158446 79103 158446 79103 158447 79108 158447 79104 158447 79104 158448 79108 158448 78161 158448 79104 158449 78161 158449 79106 158449 79113 158450 78161 158450 79112 158450 79112 158451 78161 158451 79108 158451 79112 158452 79108 158452 79111 158452 79111 158453 79108 158453 79107 158453 79111 158454 79107 158454 79109 158454 79109 158455 79107 158455 79098 158455 79109 158456 79098 158456 79110 158456 78504 158457 78423 158457 79111 158457 79111 158458 78423 158458 79115 158458 79111 158459 79115 158459 79112 158459 79112 158460 79115 158460 79116 158460 79112 158461 79116 158461 79113 158461 79113 158462 79116 158462 78162 158462 78423 158463 79464 158463 79114 158463 78423 158464 79114 158464 79115 158464 79115 158465 79114 158465 80004 158465 79115 158466 80004 158466 79116 158466 79116 158467 80004 158467 80005 158467 79116 158468 80005 158468 78162 158468 78555 158469 79117 158469 79123 158469 79119 158470 79128 158470 79121 158470 79121 158471 79128 158471 79125 158471 79121 158472 79125 158472 79118 158472 79118 158473 79125 158473 79124 158473 79118 158474 79124 158474 79122 158474 79119 158475 79121 158475 79120 158475 79120 158476 79121 158476 79118 158476 79120 158477 79118 158477 78535 158477 78535 158478 79118 158478 79122 158478 78535 158479 79122 158479 78536 158479 78555 158480 79123 158480 78553 158480 78406 158481 78536 158481 79132 158481 79132 158482 78536 158482 79122 158482 79132 158483 79122 158483 79123 158483 79123 158484 79122 158484 79124 158484 79123 158485 79124 158485 78553 158485 78553 158486 79124 158486 79125 158486 78553 158487 79125 158487 79126 158487 79126 158488 79125 158488 79128 158488 79126 158489 79128 158489 79127 158489 79127 158490 79128 158490 79119 158490 78551 158491 77351 158491 79131 158491 79131 158492 77351 158492 79129 158492 79131 158493 79129 158493 79133 158493 79133 158494 79129 158494 79130 158494 79133 158495 79130 158495 78404 158495 78404 158496 79130 158496 79136 158496 79117 158497 78551 158497 79123 158497 79123 158498 78551 158498 79131 158498 79123 158499 79131 158499 79132 158499 79132 158500 79131 158500 79133 158500 79132 158501 79133 158501 78406 158501 78406 158502 79133 158502 78404 158502 79135 158503 77349 158503 79136 158503 79136 158504 77349 158504 77350 158504 79136 158505 77350 158505 78403 158505 77351 158506 79134 158506 79129 158506 79129 158507 79134 158507 79135 158507 79129 158508 79135 158508 79130 158508 79130 158509 79135 158509 79136 158509 79137 158510 78524 158510 79138 158510 79138 158511 78524 158511 78525 158511 79138 158512 78525 158512 79140 158512 79140 158513 78525 158513 79147 158513 79140 158514 79147 158514 79142 158514 79137 158515 79138 158515 79139 158515 79139 158516 79138 158516 79140 158516 79139 158517 79140 158517 79141 158517 79141 158518 79140 158518 79142 158518 79141 158519 79142 158519 79146 158519 78557 158520 79143 158520 79146 158520 79146 158521 79143 158521 79144 158521 79146 158522 79144 158522 79141 158522 79141 158523 79144 158523 78560 158523 79141 158524 78560 158524 79139 158524 79139 158525 78560 158525 79137 158525 79148 158526 78557 158526 79145 158526 79145 158527 78557 158527 79146 158527 79145 158528 79146 158528 79151 158528 79151 158529 79146 158529 79142 158529 79151 158530 79142 158530 79153 158530 79153 158531 79142 158531 79147 158531 79154 158532 79148 158532 79149 158532 79149 158533 79148 158533 79145 158533 79149 158534 79145 158534 79150 158534 79150 158535 79145 158535 79151 158535 79150 158536 79151 158536 79152 158536 79152 158537 79151 158537 79153 158537 77282 158538 79154 158538 79155 158538 79155 158539 79154 158539 79149 158539 79155 158540 79149 158540 79156 158540 79156 158541 79149 158541 79150 158541 79156 158542 79150 158542 79157 158542 79157 158543 79150 158543 79152 158543 77283 158544 79155 158544 79156 158544 79155 158545 77283 158545 77282 158545 79158 158546 79159 158546 79157 158546 79157 158547 79159 158547 79160 158547 79157 158548 79160 158548 79156 158548 79156 158549 79160 158549 79161 158549 79156 158550 79161 158550 77283 158550 79164 158551 78414 158551 79250 158551 83777 158552 79162 158552 79251 158552 79251 158553 79162 158553 79163 158553 79251 158554 79163 158554 79250 158554 79250 158555 79163 158555 83780 158555 79250 158556 83780 158556 79164 158556 79251 158557 79252 158557 83777 158557 83777 158558 79252 158558 79167 158558 83777 158559 79167 158559 79165 158559 77786 158560 79166 158560 79167 158560 79167 158561 79166 158561 79168 158561 79167 158562 79168 158562 79165 158562 77844 158563 79169 158563 79170 158563 77844 158564 79170 158564 79171 158564 79171 158565 79170 158565 79172 158565 79171 158566 79172 158566 77839 158566 77839 158567 79172 158567 79174 158567 77839 158568 79174 158568 79173 158568 79173 158569 79174 158569 79218 158569 79173 158570 79218 158570 77840 158570 79332 158571 79175 158571 79176 158571 79176 158572 79175 158572 78087 158572 78087 158573 79175 158573 78399 158573 78087 158574 78399 158574 78086 158574 79179 158575 79334 158575 79176 158575 79176 158576 79334 158576 79177 158576 79176 158577 79177 158577 79332 158577 78153 158578 79327 158578 79200 158578 79200 158579 79327 158579 79178 158579 79200 158580 79178 158580 79179 158580 79179 158581 79178 158581 79328 158581 79179 158582 79328 158582 79334 158582 78110 158583 79180 158583 79185 158583 79185 158584 79316 158584 78110 158584 78110 158585 79316 158585 79326 158585 78110 158586 79326 158586 78126 158586 78450 158587 78451 158587 79182 158587 79182 158588 78451 158588 79181 158588 79182 158589 79181 158589 79183 158589 79183 158590 79318 158590 79182 158590 79182 158591 79318 158591 79184 158591 79182 158592 79184 158592 79180 158592 79180 158593 79184 158593 79321 158593 79180 158594 79321 158594 79185 158594 79186 158595 79300 158595 79187 158595 79186 158596 79187 158596 78237 158596 78237 158597 79187 158597 79188 158597 78237 158598 79188 158598 79189 158598 79189 158599 79188 158599 79190 158599 79189 158600 79190 158600 79191 158600 79191 158601 79190 158601 79290 158601 79191 158602 79290 158602 78283 158602 77772 158603 79272 158603 79192 158603 79192 158604 79272 158604 79193 158604 79192 158605 79193 158605 79194 158605 79194 158606 79193 158606 83820 158606 83820 158607 79193 158607 79273 158607 83820 158608 79273 158608 79195 158608 79195 158609 79273 158609 83822 158609 83822 158610 79273 158610 79196 158610 83822 158611 79196 158611 83816 158611 78412 158612 79197 158612 79196 158612 79196 158613 79197 158613 79198 158613 79196 158614 79198 158614 83816 158614 78087 158615 79199 158615 79176 158615 79176 158616 79199 158616 79203 158616 79200 158617 79179 158617 79201 158617 79201 158618 79179 158618 79202 158618 79201 158619 79202 158619 79220 158619 79220 158620 79202 158620 79207 158620 79220 158621 79207 158621 79206 158621 79179 158622 79176 158622 79202 158622 79202 158623 79176 158623 79203 158623 79202 158624 79203 158624 79207 158624 79207 158625 79203 158625 79204 158625 79199 158626 79216 158626 79203 158626 79203 158627 79216 158627 79214 158627 79203 158628 79214 158628 79204 158628 79204 158629 79214 158629 79205 158629 79204 158630 79205 158630 79210 158630 79206 158631 79207 158631 79208 158631 79208 158632 79207 158632 79204 158632 79208 158633 79204 158633 79209 158633 79209 158634 79204 158634 79210 158634 79209 158635 79210 158635 79211 158635 79211 158636 79210 158636 79212 158636 79212 158637 79210 158637 79227 158637 79227 158638 79210 158638 79213 158638 79213 158639 79210 158639 79205 158639 79213 158640 79205 158640 79221 158640 79221 158641 79205 158641 79214 158641 79221 158642 79214 158642 79215 158642 79215 158643 79214 158643 79216 158643 79215 158644 79216 158644 79217 158644 79216 158645 79199 158645 79217 158645 79217 158646 79199 158646 78087 158646 79217 158647 78087 158647 79218 158647 79206 158648 79219 158648 79242 158648 79206 158649 79242 158649 79220 158649 79220 158650 79242 158650 79241 158650 79220 158651 79241 158651 79201 158651 79201 158652 79241 158652 78552 158652 79201 158653 78552 158653 79200 158653 79217 158654 79218 158654 79174 158654 79221 158655 79215 158655 79222 158655 79222 158656 79215 158656 79217 158656 79217 158657 79174 158657 79222 158657 79222 158658 79174 158658 79172 158658 79222 158659 79172 158659 79224 158659 79224 158660 79172 158660 79170 158660 79224 158661 79170 158661 79223 158661 79223 158662 79170 158662 79169 158662 79223 158663 79169 158663 79226 158663 79227 158664 79213 158664 79228 158664 79228 158665 79213 158665 79221 158665 79221 158666 79222 158666 79228 158666 79228 158667 79222 158667 79224 158667 79228 158668 79224 158668 79225 158668 79225 158669 79224 158669 79223 158669 79225 158670 79223 158670 79231 158670 79231 158671 79223 158671 79226 158671 79231 158672 79226 158672 79233 158672 79229 158673 79212 158673 79227 158673 79227 158674 79228 158674 79229 158674 79229 158675 79228 158675 79225 158675 79229 158676 79225 158676 79230 158676 79230 158677 79225 158677 79231 158677 79230 158678 79231 158678 79232 158678 79232 158679 79231 158679 79233 158679 79232 158680 79233 158680 78459 158680 78554 158681 79240 158681 79234 158681 78415 158682 79236 158682 79235 158682 79235 158683 79236 158683 79237 158683 79235 158684 79237 158684 79248 158684 79248 158685 79237 158685 79239 158685 79248 158686 79239 158686 79247 158686 79247 158687 79239 158687 78463 158687 79236 158688 78554 158688 79237 158688 79237 158689 78554 158689 79234 158689 79237 158690 79234 158690 79239 158690 79239 158691 79234 158691 79238 158691 79239 158692 79238 158692 78463 158692 78463 158693 79238 158693 79243 158693 79240 158694 78552 158694 79234 158694 79234 158695 78552 158695 79241 158695 79234 158696 79241 158696 79238 158696 79238 158697 79241 158697 79242 158697 79238 158698 79242 158698 79243 158698 79243 158699 79242 158699 79219 158699 77786 158700 79253 158700 79169 158700 79169 158701 79253 158701 79226 158701 79253 158702 79254 158702 79226 158702 79226 158703 79254 158703 79244 158703 79226 158704 79244 158704 79233 158704 79233 158705 79244 158705 79245 158705 79233 158706 79245 158706 78459 158706 78459 158707 79245 158707 79246 158707 78459 158708 79246 158708 78462 158708 79247 158709 83885 158709 79249 158709 79247 158710 79249 158710 79248 158710 79248 158711 79249 158711 83884 158711 79248 158712 83884 158712 79235 158712 79235 158713 83884 158713 78417 158713 79235 158714 78417 158714 78415 158714 79254 158715 79253 158715 79255 158715 79250 158716 79258 158716 79251 158716 79251 158717 79258 158717 79257 158717 79251 158718 79257 158718 79252 158718 79252 158719 79257 158719 79255 158719 79252 158720 79255 158720 79167 158720 79167 158721 79255 158721 79253 158721 79167 158722 79253 158722 77786 158722 79245 158723 79244 158723 79256 158723 79256 158724 79244 158724 79254 158724 79254 158725 79255 158725 79256 158725 79256 158726 79255 158726 79257 158726 79256 158727 79257 158727 79260 158727 79260 158728 79257 158728 79258 158728 79260 158729 79258 158729 79262 158729 78462 158730 79246 158730 79259 158730 79259 158731 79246 158731 79245 158731 79250 158732 77751 158732 79258 158732 79258 158733 77751 158733 77753 158733 79258 158734 77753 158734 79262 158734 79262 158735 77753 158735 77750 158735 79262 158736 77750 158736 77749 158736 79245 158737 79256 158737 79259 158737 79259 158738 79256 158738 79260 158738 79259 158739 79260 158739 79261 158739 79261 158740 79260 158740 79262 158740 79261 158741 79262 158741 79263 158741 79263 158742 79262 158742 77749 158742 79263 158743 77749 158743 77747 158743 78462 158744 79259 158744 79264 158744 79264 158745 79259 158745 79261 158745 79264 158746 79261 158746 79265 158746 79265 158747 79261 158747 79263 158747 79265 158748 79263 158748 79266 158748 79266 158749 79263 158749 77747 158749 79266 158750 77747 158750 78461 158750 79273 158751 79193 158751 79271 158751 79278 158752 79267 158752 79268 158752 79268 158753 79267 158753 79269 158753 79268 158754 79269 158754 79270 158754 79270 158755 79269 158755 79271 158755 79270 158756 79271 158756 79272 158756 79272 158757 79271 158757 79193 158757 79196 158758 79273 158758 79276 158758 79276 158759 79273 158759 79271 158759 79276 158760 79271 158760 79274 158760 79274 158761 79271 158761 79269 158761 79274 158762 79269 158762 78081 158762 78081 158763 79269 158763 79267 158763 78081 158764 79275 158764 79274 158764 79274 158765 79275 158765 79280 158765 79274 158766 79280 158766 79276 158766 79276 158767 79280 158767 79277 158767 79276 158768 79277 158768 79196 158768 79196 158769 79277 158769 78412 158769 78085 158770 79278 158770 79268 158770 78085 158771 79268 158771 79288 158771 79288 158772 79268 158772 79270 158772 79288 158773 79270 158773 79279 158773 79279 158774 79270 158774 79272 158774 79279 158775 79272 158775 79290 158775 78411 158776 78412 158776 79277 158776 78411 158777 79277 158777 83881 158777 83881 158778 79277 158778 79280 158778 83881 158779 79280 158779 83882 158779 83882 158780 79280 158780 79275 158780 83882 158781 79275 158781 79281 158781 79300 158782 79302 158782 79284 158782 79302 158783 79304 158783 79283 158783 79304 158784 78076 158784 79282 158784 79304 158785 79282 158785 79283 158785 79283 158786 79282 158786 78075 158786 79283 158787 78075 158787 79286 158787 79286 158788 78075 158788 78074 158788 79286 158789 78074 158789 79287 158789 79287 158790 78074 158790 78085 158790 79287 158791 78085 158791 79288 158791 79302 158792 79283 158792 79284 158792 79284 158793 79283 158793 79286 158793 79284 158794 79286 158794 79285 158794 79285 158795 79286 158795 79287 158795 79285 158796 79287 158796 79289 158796 79289 158797 79287 158797 79288 158797 79289 158798 79288 158798 79279 158798 79300 158799 79284 158799 79187 158799 79187 158800 79284 158800 79285 158800 79187 158801 79285 158801 79188 158801 79188 158802 79285 158802 79289 158802 79188 158803 79289 158803 79190 158803 79190 158804 79289 158804 79279 158804 79190 158805 79279 158805 79290 158805 78558 158806 79291 158806 79293 158806 78083 158807 78082 158807 77755 158807 77755 158808 78082 158808 79296 158808 77755 158809 79296 158809 79292 158809 79292 158810 79296 158810 79293 158810 79292 158811 79293 158811 79294 158811 79294 158812 79293 158812 79291 158812 78559 158813 78558 158813 79298 158813 79298 158814 78558 158814 79293 158814 79298 158815 79293 158815 79295 158815 79295 158816 79293 158816 79296 158816 79295 158817 79296 158817 78080 158817 78080 158818 79296 158818 78082 158818 78080 158819 79306 158819 79295 158819 79295 158820 79306 158820 79297 158820 79295 158821 79297 158821 79298 158821 79298 158822 79297 158822 79299 158822 79298 158823 79299 158823 78559 158823 78559 158824 79299 158824 78108 158824 79300 158825 78450 158825 79301 158825 79300 158826 79301 158826 79302 158826 79302 158827 79301 158827 79303 158827 79302 158828 79303 158828 79304 158828 79304 158829 79303 158829 78077 158829 79304 158830 78077 158830 78076 158830 78110 158831 78108 158831 79299 158831 78110 158832 79299 158832 79305 158832 79305 158833 79299 158833 79297 158833 79305 158834 79297 158834 79307 158834 79307 158835 79297 158835 79306 158835 79307 158836 79306 158836 78079 158836 78079 158837 78078 158837 79307 158837 79307 158838 78078 158838 79309 158838 79307 158839 79309 158839 79305 158839 79305 158840 79309 158840 79310 158840 79305 158841 79310 158841 78110 158841 78110 158842 79310 158842 79180 158842 78078 158843 79308 158843 79309 158843 79309 158844 79308 158844 79311 158844 79309 158845 79311 158845 79310 158845 79310 158846 79311 158846 79312 158846 79310 158847 79312 158847 79180 158847 79180 158848 79312 158848 79182 158848 79308 158849 78077 158849 79311 158849 79311 158850 78077 158850 79303 158850 79311 158851 79303 158851 79312 158851 79312 158852 79303 158852 79301 158852 79312 158853 79301 158853 79182 158853 79182 158854 79301 158854 78450 158854 79313 158855 78113 158855 78126 158855 79314 158856 79315 158856 79316 158856 80070 158857 79325 158857 79321 158857 79183 158858 79181 158858 79317 158858 79183 158859 79317 158859 79318 158859 79318 158860 79317 158860 79319 158860 79318 158861 79319 158861 79324 158861 80068 158862 79323 158862 79320 158862 79320 158863 79323 158863 78454 158863 80070 158864 79321 158864 79322 158864 79321 158865 79184 158865 79322 158865 79322 158866 79184 158866 79318 158866 79322 158867 79318 158867 79323 158867 79323 158868 79318 158868 79324 158868 79323 158869 79324 158869 78454 158869 79314 158870 79316 158870 79325 158870 79325 158871 79316 158871 79185 158871 79325 158872 79185 158872 79321 158872 79313 158873 78126 158873 79315 158873 79315 158874 78126 158874 79326 158874 79315 158875 79326 158875 79316 158875 79327 158876 78153 158876 78163 158876 79328 158877 79178 158877 79333 158877 79177 158878 79334 158878 79329 158878 79175 158879 79332 158879 79330 158879 79175 158880 79330 158880 78399 158880 78399 158881 79330 158881 79331 158881 78399 158882 79331 158882 80063 158882 79177 158883 79329 158883 79332 158883 79332 158884 79329 158884 80064 158884 79332 158885 80064 158885 79330 158885 79328 158886 79333 158886 79334 158886 79334 158887 79333 158887 79335 158887 79334 158888 79335 158888 79329 158888 79327 158889 78163 158889 79178 158889 79178 158890 78163 158890 79336 158890 79178 158891 79336 158891 79333 158891 83880 158892 83879 158892 79337 158892 79337 158893 83879 158893 79339 158893 79342 158894 80149 158894 80145 158894 79337 158895 80193 158895 79343 158895 79343 158896 80193 158896 80172 158896 80204 158897 80193 158897 80205 158897 80205 158898 80193 158898 79337 158898 80205 158899 79337 158899 79338 158899 79338 158900 79337 158900 79339 158900 79338 158901 79339 158901 79340 158901 79340 158902 79339 158902 80157 158902 80163 158903 80165 158903 80161 158903 80161 158904 80165 158904 79341 158904 80161 158905 79341 158905 80172 158905 80172 158906 79341 158906 79342 158906 80172 158907 79342 158907 79343 158907 79343 158908 79342 158908 80145 158908 80157 158909 80187 158909 79340 158909 79340 158910 80187 158910 79344 158910 79340 158911 79344 158911 80184 158911 80093 158912 80101 158912 79345 158912 79345 158913 80101 158913 79346 158913 79345 158914 79346 158914 78391 158914 78391 158915 79346 158915 79347 158915 78391 158916 79347 158916 79349 158916 78093 158917 78091 158917 77904 158917 77904 158918 78091 158918 78393 158918 77904 158919 78393 158919 79348 158919 79348 158920 78393 158920 78392 158920 79348 158921 78392 158921 79349 158921 79349 158922 78392 158922 78391 158922 77325 158923 79460 158923 79350 158923 79350 158924 79460 158924 80001 158924 79354 158925 79723 158925 79351 158925 79351 158926 79723 158926 79728 158926 79351 158927 79728 158927 77733 158927 77733 158928 79728 158928 79727 158928 79352 158929 77296 158929 79698 158929 79698 158930 77296 158930 77362 158930 79698 158931 77362 158931 79692 158931 77296 158932 79352 158932 77297 158932 77297 158933 79352 158933 79710 158933 77297 158934 79710 158934 77300 158934 77300 158935 79710 158935 79708 158935 77300 158936 79708 158936 79353 158936 79353 158937 79708 158937 79724 158937 79724 158938 79723 158938 79353 158938 79353 158939 79723 158939 79354 158939 79356 158940 79580 158940 79357 158940 79642 158941 79355 158941 79361 158941 79356 158942 79357 158942 79615 158942 79361 158943 79355 158943 79649 158943 79662 158944 79648 158944 79358 158944 79358 158945 79648 158945 79359 158945 79359 158946 79648 158946 79361 158946 79361 158947 79648 158947 79360 158947 79361 158948 79360 158948 79642 158948 79355 158949 79635 158949 79649 158949 79649 158950 79635 158950 79624 158950 79649 158951 79624 158951 79357 158951 79357 158952 79624 158952 79619 158952 79357 158953 79619 158953 79615 158953 79872 158954 79362 158954 79364 158954 79365 158955 79816 158955 79835 158955 79875 158956 79363 158956 79864 158956 79864 158957 79363 158957 79872 158957 79864 158958 79872 158958 79858 158958 79858 158959 79872 158959 79364 158959 79367 158960 79854 158960 79864 158960 79864 158961 79854 158961 79880 158961 79864 158962 79880 158962 79875 158962 79835 158963 79836 158963 79365 158963 79365 158964 79836 158964 79833 158964 79365 158965 79833 158965 79367 158965 79367 158966 79833 158966 79366 158966 79367 158967 79366 158967 79854 158967 79882 158968 79881 158968 79370 158968 79487 158969 79863 158969 79882 158969 79487 158970 79882 158970 79368 158970 79368 158971 79882 158971 79370 158971 79368 158972 79370 158972 79369 158972 79369 158973 79370 158973 77346 158973 79369 158974 77346 158974 79371 158974 79371 158975 77346 158975 79372 158975 79372 158976 77346 158976 79374 158976 79372 158977 79374 158977 79373 158977 79373 158978 79374 158978 79492 158978 79492 158979 79374 158979 77324 158979 79492 158980 77324 158980 79493 158980 79493 158981 77324 158981 79375 158981 79375 158982 77324 158982 77326 158982 79375 158983 77326 158983 79386 158983 79502 158984 79691 158984 79690 158984 77359 158985 79376 158985 79686 158985 79686 158986 79376 158986 79502 158986 79686 158987 79502 158987 79377 158987 79377 158988 79502 158988 79690 158988 79377 158989 79690 158989 79688 158989 77359 158990 77344 158990 79376 158990 79376 158991 77344 158991 79378 158991 79376 158992 79378 158992 79500 158992 79500 158993 79378 158993 79379 158993 79744 158994 79380 158994 79381 158994 79744 158995 79381 158995 79743 158995 79485 158996 77285 158996 79381 158996 79381 158997 77285 158997 79382 158997 79381 158998 79382 158998 79743 158998 79383 158999 77353 158999 77355 158999 79477 159000 79384 159000 77355 159000 77355 159001 79384 159001 79674 159001 77355 159002 79674 159002 79383 159002 79385 159003 79477 159003 79888 159003 79888 159004 79477 159004 77355 159004 79888 159005 77355 159005 79892 159005 79892 159006 77355 159006 77356 159006 79386 159007 77326 159007 77292 159007 77292 159008 80029 159008 79386 159008 79386 159009 80029 159009 80025 159009 79386 159010 80025 159010 79387 159010 80055 159011 77285 159011 80048 159011 80048 159012 77285 159012 79485 159012 80048 159013 79485 159013 80042 159013 80042 159014 79485 159014 80043 159014 77623 159015 83832 159015 79524 159015 79524 159016 83832 159016 83831 159016 79527 159017 77659 159017 79390 159017 79390 159018 77659 159018 79389 159018 83879 159019 83880 159019 79388 159019 79388 159020 83880 159020 79391 159020 77660 159021 80160 159021 79389 159021 79389 159022 80160 159022 79388 159022 79389 159023 79388 159023 79390 159023 79390 159024 79388 159024 79391 159024 79390 159025 79391 159025 79392 159025 79393 159026 77509 159026 83735 159026 83735 159027 77509 159027 77510 159027 83735 159028 77510 159028 83733 159028 79414 159029 79413 159029 79394 159029 79394 159030 79413 159030 83892 159030 79393 159031 79394 159031 77509 159031 77509 159032 79394 159032 83892 159032 77509 159033 83892 159033 79395 159033 79395 159034 83892 159034 77746 159034 79395 159035 77746 159035 77565 159035 79522 159036 83727 159036 79396 159036 79396 159037 83727 159037 79523 159037 79396 159038 79523 159038 77511 159038 79463 159039 77298 159039 79397 159039 79397 159040 77298 159040 79918 159040 79918 159041 77298 159041 79398 159041 79398 159042 77298 159042 77299 159042 79398 159043 77299 159043 79468 159043 79023 159044 77345 159044 79949 159044 79949 159045 77345 159045 79462 159045 79949 159046 79462 159046 79948 159046 79948 159047 79462 159047 79399 159047 79406 159048 79400 159048 79405 159048 79459 159049 77335 159049 79982 159049 79982 159050 77335 159050 79405 159050 79982 159051 79405 159051 79401 159051 79401 159052 79405 159052 79400 159052 79403 159053 79402 159053 79966 159053 79959 159054 79961 159054 79404 159054 79966 159055 79959 159055 79403 159055 79403 159056 79959 159056 79404 159056 79403 159057 79404 159057 79405 159057 79405 159058 79404 159058 79973 159058 79405 159059 79973 159059 79406 159059 78239 159060 79409 159060 78209 159060 78209 159061 79409 159061 77667 159061 78209 159062 77667 159062 79407 159062 79407 159063 77667 159063 77668 159063 79407 159064 77668 159064 3415 159064 3415 159065 77668 159065 77669 159065 79410 159066 79409 159066 79408 159066 79408 159067 79409 159067 78239 159067 79408 159068 80182 159068 79410 159068 79410 159069 80182 159069 80203 159069 79410 159070 80203 159070 79411 159070 79411 159071 80203 159071 80067 159071 79411 159072 80067 159072 77277 159072 80116 159073 80096 159073 79412 159073 83889 159074 79413 159074 79414 159074 79412 159075 80096 159075 80128 159075 80090 159076 79415 159076 80089 159076 80089 159077 79415 159077 79422 159077 79416 159078 80114 159078 79412 159078 79412 159079 80114 159079 79417 159079 79412 159080 79417 159080 80116 159080 80121 159081 79419 159081 79418 159081 79418 159082 79419 159082 80127 159082 79418 159083 80127 159083 79415 159083 79415 159084 80127 159084 83889 159084 79415 159085 83889 159085 79422 159085 79422 159086 83889 159086 79414 159086 80139 159087 79420 159087 79421 159087 79421 159088 79420 159088 80128 159088 79421 159089 80128 159089 79422 159089 79422 159090 80128 159090 80096 159090 79422 159091 80096 159091 80089 159091 79424 159092 79423 159092 79785 159092 79781 159093 79757 159093 79817 159093 79817 159094 79757 159094 79753 159094 79817 159095 79753 159095 79424 159095 79424 159096 79785 159096 79817 159096 79817 159097 79785 159097 79425 159097 79817 159098 79425 159098 79426 159098 79427 159099 79555 159099 79608 159099 79427 159100 79608 159100 79561 159100 79547 159101 79561 159101 79548 159101 79548 159102 79561 159102 79608 159102 79548 159103 79608 159103 79428 159103 79428 159104 79608 159104 79429 159104 79428 159105 79429 159105 79430 159105 77505 159106 77895 159106 77508 159106 77508 159107 77895 159107 79432 159107 77508 159108 79432 159108 79431 159108 79431 159109 79432 159109 79433 159109 79431 159110 79433 159110 79434 159110 79434 159111 79433 159111 79435 159111 79434 159112 79435 159112 79437 159112 79437 159113 79435 159113 79436 159113 79437 159114 79436 159114 79438 159114 79438 159115 79436 159115 79439 159115 79438 159116 79439 159116 77512 159116 77512 159117 79439 159117 79440 159117 77512 159118 79440 159118 77513 159118 77513 159119 79440 159119 77892 159119 77513 159120 77892 159120 79441 159120 79441 159121 77892 159121 79442 159121 79441 159122 79442 159122 79443 159122 79443 159123 79442 159123 77891 159123 79443 159124 77891 159124 77518 159124 77518 159125 77891 159125 77890 159125 77518 159126 77890 159126 79444 159126 79444 159127 77890 159127 77896 159127 79444 159128 77896 159128 77505 159128 77505 159129 77896 159129 77895 159129 79445 159130 77905 159130 77579 159130 77579 159131 77905 159131 77906 159131 77579 159132 77906 159132 79446 159132 79446 159133 77906 159133 77907 159133 79446 159134 77907 159134 77574 159134 77574 159135 77907 159135 77908 159135 77574 159136 77908 159136 79447 159136 79447 159137 77908 159137 79448 159137 79447 159138 79448 159138 79449 159138 79449 159139 79448 159139 77898 159139 79449 159140 77898 159140 77575 159140 77575 159141 77898 159141 77911 159141 77575 159142 77911 159142 79450 159142 79450 159143 77911 159143 77910 159143 79450 159144 77910 159144 77576 159144 77576 159145 77910 159145 77909 159145 77576 159146 77909 159146 77577 159146 77577 159147 77909 159147 79452 159147 77577 159148 79452 159148 79451 159148 79451 159149 79452 159149 77899 159149 79451 159150 77899 159150 79453 159150 79453 159151 77899 159151 79454 159151 79453 159152 79454 159152 79445 159152 79445 159153 79454 159153 77905 159153 79535 159154 79978 159154 79455 159154 79455 159155 79978 159155 79456 159155 79455 159156 79456 159156 79764 159156 79764 159157 79456 159157 79955 159157 79458 159158 79938 159158 79457 159158 79921 159159 79553 159159 79556 159159 79458 159160 79457 159160 79556 159160 79556 159161 79457 159161 79925 159161 79556 159162 79925 159162 79921 159162 77335 159163 79459 159163 77347 159163 77347 159164 79459 159164 79990 159164 77347 159165 79990 159165 77325 159165 77325 159166 79990 159166 79460 159166 79462 159167 77298 159167 79463 159167 79937 159168 79399 159168 79461 159168 79461 159169 79399 159169 79462 159169 79461 159170 79462 159170 79932 159170 79932 159171 79462 159171 79463 159171 79464 159172 79465 159172 80002 159172 80002 159173 79465 159173 79466 159173 80002 159174 79466 159174 80006 159174 80006 159175 79466 159175 79467 159175 80006 159176 79467 159176 80001 159176 80001 159177 79467 159177 79350 159177 79468 159178 77299 159178 77295 159178 79468 159179 77295 159179 79898 159179 79898 159180 77295 159180 79470 159180 79898 159181 79470 159181 79469 159181 79469 159182 79470 159182 77289 159182 79469 159183 77289 159183 79471 159183 79471 159184 77289 159184 78424 159184 79471 159185 78424 159185 79901 159185 79472 159186 79855 159186 79482 159186 79472 159187 79482 159187 79476 159187 79482 159188 79620 159188 79474 159188 79476 159189 79482 159189 79473 159189 79473 159190 79482 159190 79474 159190 79473 159191 79474 159191 79475 159191 79868 159192 79877 159192 79478 159192 79478 159193 79877 159193 79476 159193 79478 159194 79476 159194 79473 159194 79385 159195 79868 159195 79477 159195 79477 159196 79868 159196 79478 159196 79477 159197 79478 159197 79384 159197 79384 159198 79478 159198 79479 159198 79479 159199 79478 159199 79480 159199 79480 159200 79478 159200 79473 159200 79480 159201 79473 159201 79475 159201 78473 159202 78474 159202 79481 159202 79855 159203 79846 159203 79481 159203 79481 159204 79846 159204 79847 159204 79481 159205 79847 159205 78473 159205 79616 159206 79620 159206 79481 159206 79481 159207 79620 159207 79482 159207 79481 159208 79482 159208 79855 159208 79616 159209 79481 159209 79483 159209 79483 159210 79481 159210 78474 159210 79483 159211 78474 159211 79605 159211 79738 159212 79736 159212 78114 159212 79738 159213 78114 159213 79380 159213 79380 159214 78114 159214 79484 159214 79380 159215 79484 159215 79381 159215 79381 159216 79484 159216 78111 159216 79381 159217 78111 159217 79485 159217 78111 159218 80034 159218 79485 159218 79485 159219 80034 159219 80035 159219 80035 159220 80036 159220 79485 159220 79485 159221 80036 159221 80037 159221 79485 159222 80037 159222 80043 159222 79486 159223 79863 159223 79487 159223 79488 159224 79867 159224 79486 159224 79486 159225 79487 159225 79488 159225 79488 159226 79487 159226 79368 159226 79488 159227 79368 159227 78158 159227 78158 159228 79368 159228 79369 159228 78158 159229 79369 159229 79489 159229 79489 159230 79369 159230 79371 159230 79489 159231 79371 159231 79490 159231 79490 159232 79371 159232 79372 159232 79490 159233 79372 159233 79491 159233 79491 159234 79372 159234 79373 159234 79491 159235 79373 159235 78164 159235 78164 159236 79373 159236 79492 159236 78164 159237 79492 159237 78174 159237 78174 159238 79492 159238 79493 159238 78174 159239 79493 159239 79494 159239 79494 159240 79493 159240 79375 159240 79494 159241 79375 159241 79495 159241 79495 159242 79375 159242 79386 159242 79495 159243 79386 159243 79496 159243 79386 159244 79387 159244 80014 159244 80012 159245 79496 159245 79497 159245 79497 159246 79496 159246 79386 159246 79497 159247 79386 159247 79498 159247 79498 159248 79386 159248 80014 159248 79650 159249 78136 159249 78117 159249 79501 159250 78116 159250 79699 159250 79650 159251 78117 159251 79379 159251 79379 159252 78117 159252 79500 159252 79500 159253 78117 159253 79499 159253 79500 159254 79499 159254 79376 159254 79376 159255 79499 159255 79501 159255 79376 159256 79501 159256 79502 159256 79502 159257 79501 159257 79699 159257 79502 159258 79699 159258 79691 159258 79426 159259 79425 159259 79832 159259 79832 159260 79425 159260 79811 159260 79832 159261 79811 159261 79503 159261 79503 159262 79811 159262 79813 159262 79503 159263 79813 159263 79504 159263 79504 159264 79813 159264 79814 159264 79504 159265 79814 159265 79365 159265 79365 159266 79814 159266 79816 159266 79357 159267 79580 159267 79505 159267 79505 159268 79580 159268 79506 159268 79505 159269 79506 159269 79632 159269 79632 159270 79506 159270 79507 159270 79632 159271 79507 159271 79509 159271 79509 159272 79507 159272 79508 159272 79509 159273 79508 159273 79429 159273 79429 159274 79508 159274 79430 159274 77565 159275 77746 159275 80122 159275 79511 159276 80027 159276 77565 159276 77565 159277 80027 159277 79510 159277 77565 159278 79510 159278 80028 159278 77565 159279 80122 159279 79511 159279 79511 159280 80122 159280 80119 159280 79511 159281 80119 159281 79512 159281 79512 159282 80119 159282 79513 159282 79512 159283 79513 159283 80018 159283 78151 159284 80012 159284 79513 159284 79513 159285 80012 159285 79514 159285 79513 159286 79514 159286 80018 159286 77660 159287 80052 159287 79515 159287 80192 159288 80160 159288 77660 159288 80034 159289 79517 159289 79516 159289 79516 159290 79517 159290 79518 159290 79516 159291 79518 159291 80040 159291 80040 159292 79518 159292 79519 159292 80040 159293 79519 159293 79520 159293 79520 159294 79519 159294 80192 159294 79520 159295 80192 159295 79521 159295 79521 159296 80192 159296 77660 159296 79521 159297 77660 159297 80047 159297 80047 159298 77660 159298 79515 159298 79522 159299 77483 159299 83727 159299 83727 159300 77483 159300 83721 159300 77511 159301 79523 159301 77510 159301 77510 159302 79523 159302 83733 159302 83831 159303 79525 159303 79524 159303 79524 159304 79525 159304 79526 159304 83832 159305 77623 159305 79527 159305 79527 159306 77623 159306 77659 159306 79692 159307 77362 159307 79528 159307 79528 159308 77362 159308 77363 159308 79531 159309 79529 159309 79530 159309 79531 159310 79530 159310 79962 159310 79962 159311 79530 159311 79765 159311 79962 159312 79765 159312 79532 159312 79532 159313 79765 159313 79764 159313 79532 159314 79764 159314 79955 159314 79545 159315 79550 159315 79533 159315 79533 159316 79550 159316 79946 159316 79946 159317 79550 159317 78478 159317 79946 159318 78478 159318 79942 159318 79533 159319 79534 159319 79545 159319 79545 159320 79534 159320 79938 159320 79545 159321 79938 159321 79458 159321 79978 159322 79535 159322 79536 159322 79978 159323 79536 159323 79976 159323 79976 159324 79536 159324 79773 159324 79976 159325 79773 159325 79537 159325 79537 159326 79773 159326 79538 159326 79538 159327 79773 159327 79776 159327 79538 159328 79776 159328 78166 159328 79539 159329 79912 159329 79574 159329 79574 159330 79912 159330 78120 159330 79574 159331 78120 159331 79592 159331 79539 159332 79540 159332 79912 159332 79912 159333 79540 159333 79553 159333 79912 159334 79553 159334 79921 159334 79543 159335 79542 159335 79549 159335 79541 159336 79545 159336 79458 159336 79559 159337 79561 159337 79547 159337 79559 159338 79542 159338 79558 159338 79558 159339 79542 159339 79543 159339 79558 159340 79543 159340 79544 159340 79550 159341 79545 159341 79546 159341 79546 159342 79545 159342 79541 159342 79546 159343 79541 159343 79551 159343 79559 159344 79547 159344 79542 159344 79542 159345 79547 159345 79548 159345 79542 159346 79548 159346 79549 159346 79549 159347 79548 159347 79428 159347 79549 159348 79428 159348 79565 159348 79565 159349 79552 159349 79549 159349 79549 159350 79552 159350 79551 159350 79549 159351 79551 159351 79543 159351 79543 159352 79551 159352 79541 159352 79543 159353 79541 159353 79544 159353 79544 159354 79541 159354 79458 159354 78478 159355 79550 159355 79562 159355 79562 159356 79550 159356 79546 159356 79562 159357 79546 159357 79564 159357 79564 159358 79546 159358 79551 159358 79564 159359 79551 159359 79567 159359 79567 159360 79551 159360 79552 159360 79556 159361 79553 159361 79557 159361 79557 159362 79553 159362 79577 159362 79557 159363 79577 159363 79560 159363 79560 159364 79577 159364 79572 159364 79560 159365 79572 159365 79554 159365 79554 159366 79572 159366 79571 159366 79554 159367 79571 159367 79427 159367 79427 159368 79571 159368 79555 159368 79458 159369 79556 159369 79544 159369 79544 159370 79556 159370 79557 159370 79544 159371 79557 159371 79558 159371 79558 159372 79557 159372 79560 159372 79558 159373 79560 159373 79559 159373 79559 159374 79560 159374 79554 159374 79559 159375 79554 159375 79561 159375 79561 159376 79554 159376 79427 159376 78479 159377 78478 159377 79562 159377 78479 159378 79562 159378 79563 159378 79562 159379 79564 159379 79563 159379 79563 159380 79564 159380 79567 159380 79563 159381 79567 159381 79566 159381 79428 159382 79430 159382 79565 159382 79565 159383 79430 159383 79566 159383 79565 159384 79566 159384 79552 159384 79552 159385 79566 159385 79567 159385 79570 159386 79540 159386 79539 159386 79576 159387 79568 159387 79575 159387 79569 159388 79578 159388 79570 159388 79555 159389 79571 159389 79595 159389 79595 159390 79571 159390 79572 159390 79595 159391 79572 159391 79579 159391 79592 159392 79573 159392 79574 159392 79574 159393 79573 159393 79575 159393 79574 159394 79575 159394 79539 159394 79539 159395 79575 159395 79568 159395 79539 159396 79568 159396 79570 159396 79570 159397 79568 159397 79576 159397 79570 159398 79576 159398 79569 159398 79553 159399 79540 159399 79577 159399 79577 159400 79540 159400 79570 159400 79577 159401 79570 159401 79572 159401 79572 159402 79570 159402 79578 159402 79572 159403 79578 159403 79579 159403 79579 159404 79578 159404 79569 159404 79580 159405 79582 159405 79581 159405 79582 159406 79604 159406 79585 159406 79604 159407 79583 159407 79584 159407 79604 159408 79584 159408 79585 159408 79585 159409 79584 159409 79587 159409 79585 159410 79587 159410 79586 159410 79586 159411 79587 159411 78481 159411 79586 159412 78481 159412 79588 159412 79588 159413 78481 159413 78479 159413 79588 159414 78479 159414 79563 159414 79582 159415 79585 159415 79581 159415 79581 159416 79585 159416 79586 159416 79581 159417 79586 159417 79589 159417 79589 159418 79586 159418 79588 159418 79589 159419 79588 159419 79590 159419 79590 159420 79588 159420 79563 159420 79590 159421 79563 159421 79566 159421 79580 159422 79581 159422 79506 159422 79506 159423 79581 159423 79589 159423 79506 159424 79589 159424 79507 159424 79507 159425 79589 159425 79590 159425 79507 159426 79590 159426 79508 159426 79508 159427 79590 159427 79566 159427 79508 159428 79566 159428 79430 159428 79579 159429 79569 159429 79591 159429 79593 159430 79573 159430 79592 159430 79573 159431 79593 159431 79594 159431 79576 159432 79575 159432 79594 159432 79594 159433 79575 159433 79573 159433 79569 159434 79576 159434 79591 159434 79591 159435 79576 159435 79594 159435 79591 159436 79594 159436 79598 159436 79598 159437 79594 159437 79593 159437 79598 159438 79593 159438 79599 159438 78115 159439 79601 159439 79597 159439 79597 159440 79601 159440 79600 159440 79597 159441 79600 159441 79596 159441 79595 159442 79579 159442 79596 159442 79596 159443 79579 159443 79591 159443 79596 159444 79591 159444 79597 159444 79597 159445 79591 159445 79598 159445 79597 159446 79598 159446 78115 159446 78115 159447 79598 159447 79599 159447 79555 159448 79595 159448 79610 159448 79610 159449 79595 159449 79596 159449 79610 159450 79596 159450 79612 159450 79612 159451 79596 159451 79600 159451 79612 159452 79600 159452 79613 159452 79613 159453 79600 159453 79601 159453 79580 159454 79356 159454 79602 159454 79580 159455 79602 159455 79582 159455 79582 159456 79602 159456 79603 159456 79582 159457 79603 159457 79604 159457 79604 159458 79603 159458 79605 159458 79604 159459 79605 159459 79583 159459 79429 159460 79608 159460 79609 159460 79429 159461 79609 159461 79633 159461 79633 159462 79609 159462 79611 159462 79633 159463 79611 159463 79606 159463 79606 159464 79611 159464 78118 159464 79606 159465 78118 159465 79607 159465 79608 159466 79555 159466 79610 159466 79608 159467 79610 159467 79609 159467 79609 159468 79610 159468 79612 159468 79609 159469 79612 159469 79611 159469 79611 159470 79612 159470 79613 159470 79611 159471 79613 159471 78118 159471 79483 159472 79605 159472 79617 159472 79617 159473 79605 159473 79603 159473 79617 159474 79603 159474 79614 159474 79614 159475 79603 159475 79602 159475 79614 159476 79602 159476 79615 159476 79615 159477 79602 159477 79356 159477 79616 159478 79483 159478 79622 159478 79622 159479 79483 159479 79617 159479 79622 159480 79617 159480 79618 159480 79618 159481 79617 159481 79614 159481 79618 159482 79614 159482 79619 159482 79619 159483 79614 159483 79615 159483 79620 159484 79616 159484 79621 159484 79621 159485 79616 159485 79622 159485 79621 159486 79622 159486 79623 159486 79623 159487 79622 159487 79618 159487 79623 159488 79618 159488 79624 159488 79624 159489 79618 159489 79619 159489 79640 159490 79639 159490 78135 159490 78135 159491 79639 159491 79625 159491 78135 159492 79625 159492 78134 159492 78134 159493 79625 159493 79628 159493 78134 159494 79628 159494 79626 159494 79626 159495 79628 159495 79629 159495 79626 159496 79629 159496 79607 159496 79607 159497 79629 159497 79606 159497 79639 159498 79638 159498 79625 159498 79625 159499 79638 159499 79627 159499 79625 159500 79627 159500 79628 159500 79628 159501 79627 159501 79630 159501 79628 159502 79630 159502 79629 159502 79629 159503 79630 159503 79631 159503 79629 159504 79631 159504 79606 159504 79606 159505 79631 159505 79633 159505 79638 159506 79357 159506 79627 159506 79627 159507 79357 159507 79505 159507 79627 159508 79505 159508 79630 159508 79630 159509 79505 159509 79632 159509 79630 159510 79632 159510 79631 159510 79631 159511 79632 159511 79509 159511 79631 159512 79509 159512 79633 159512 79633 159513 79509 159513 79429 159513 79474 159514 79620 159514 79636 159514 79636 159515 79620 159515 79621 159515 79636 159516 79621 159516 79634 159516 79634 159517 79621 159517 79623 159517 79634 159518 79623 159518 79635 159518 79635 159519 79623 159519 79624 159519 79475 159520 79474 159520 79641 159520 79641 159521 79474 159521 79636 159521 79641 159522 79636 159522 79637 159522 79637 159523 79636 159523 79634 159523 79637 159524 79634 159524 79355 159524 79355 159525 79634 159525 79635 159525 79649 159526 79357 159526 79652 159526 79652 159527 79357 159527 79638 159527 79652 159528 79638 159528 79653 159528 79653 159529 79638 159529 79656 159529 79656 159530 79638 159530 79639 159530 79656 159531 79639 159531 79658 159531 79658 159532 79639 159532 79651 159532 79651 159533 79639 159533 79640 159533 79651 159534 79640 159534 78136 159534 79480 159535 79475 159535 79643 159535 79643 159536 79475 159536 79641 159536 79643 159537 79641 159537 79645 159537 79645 159538 79641 159538 79637 159538 79645 159539 79637 159539 79642 159539 79642 159540 79637 159540 79355 159540 79479 159541 79480 159541 79647 159541 79647 159542 79480 159542 79643 159542 79647 159543 79643 159543 79644 159543 79644 159544 79643 159544 79645 159544 79644 159545 79645 159545 79360 159545 79360 159546 79645 159546 79642 159546 79384 159547 79479 159547 79646 159547 79646 159548 79479 159548 79647 159548 79646 159549 79647 159549 79661 159549 79661 159550 79647 159550 79644 159550 79661 159551 79644 159551 79648 159551 79648 159552 79644 159552 79360 159552 79654 159553 79361 159553 79649 159553 79657 159554 79651 159554 79650 159554 79650 159555 79651 159555 78136 159555 79649 159556 79652 159556 79654 159556 79654 159557 79652 159557 79653 159557 79654 159558 79653 159558 79655 159558 79655 159559 79653 159559 79656 159559 79655 159560 79656 159560 79657 159560 79657 159561 79656 159561 79658 159561 79657 159562 79658 159562 79651 159562 79359 159563 79361 159563 79668 159563 79668 159564 79361 159564 79654 159564 79668 159565 79654 159565 79659 159565 79659 159566 79654 159566 79655 159566 79659 159567 79655 159567 79660 159567 79660 159568 79655 159568 79657 159568 79660 159569 79657 159569 79379 159569 79379 159570 79657 159570 79650 159570 79674 159571 79384 159571 79646 159571 79674 159572 79646 159572 79675 159572 79675 159573 79646 159573 79661 159573 79675 159574 79661 159574 79677 159574 79677 159575 79661 159575 79648 159575 79677 159576 79648 159576 79662 159576 79662 159577 79358 159577 79678 159577 79678 159578 79358 159578 79664 159578 79667 159579 79672 159579 79663 159579 79663 159580 79672 159580 79681 159580 79663 159581 79681 159581 79664 159581 79664 159582 79681 159582 79680 159582 79664 159583 79680 159583 79678 159583 79378 159584 77344 159584 79667 159584 79667 159585 77344 159585 79665 159585 79665 159586 79666 159586 79667 159586 79667 159587 79666 159587 79673 159587 79667 159588 79673 159588 79672 159588 79379 159589 79378 159589 79660 159589 79660 159590 79378 159590 79667 159590 79660 159591 79667 159591 79659 159591 79659 159592 79667 159592 79663 159592 79659 159593 79663 159593 79668 159593 79668 159594 79663 159594 79664 159594 79668 159595 79664 159595 79359 159595 79359 159596 79664 159596 79358 159596 77343 159597 77342 159597 79669 159597 77342 159598 77341 159598 79669 159598 79669 159599 77341 159599 77353 159599 79669 159600 77353 159600 79670 159600 77343 159601 79676 159601 79671 159601 79671 159602 79676 159602 79672 159602 79671 159603 79672 159603 77334 159603 77334 159604 79672 159604 79673 159604 79677 159605 79662 159605 79678 159605 77353 159606 79383 159606 79670 159606 79670 159607 79383 159607 79674 159607 79670 159608 79674 159608 79675 159608 77343 159609 79669 159609 79676 159609 79676 159610 79669 159610 79670 159610 79676 159611 79670 159611 79679 159611 79679 159612 79670 159612 79675 159612 79679 159613 79675 159613 79677 159613 79677 159614 79678 159614 79679 159614 79679 159615 79678 159615 79680 159615 79679 159616 79680 159616 79676 159616 79676 159617 79680 159617 79681 159617 79676 159618 79681 159618 79672 159618 77364 159619 79683 159619 79682 159619 79682 159620 79683 159620 77363 159620 77363 159621 79683 159621 79685 159621 77363 159622 79685 159622 79528 159622 79687 159623 79684 159623 77364 159623 77364 159624 79684 159624 79689 159624 77364 159625 79689 159625 79683 159625 79683 159626 79689 159626 79696 159626 79683 159627 79696 159627 79685 159627 79686 159628 79377 159628 79687 159628 79687 159629 79377 159629 79688 159629 79687 159630 79688 159630 79684 159630 79684 159631 79688 159631 79690 159631 79684 159632 79690 159632 79689 159632 79689 159633 79690 159633 79691 159633 79689 159634 79691 159634 79696 159634 79692 159635 79528 159635 79693 159635 79693 159636 79528 159636 79685 159636 79693 159637 79685 159637 79694 159637 79694 159638 79685 159638 79695 159638 79695 159639 79685 159639 79696 159639 79695 159640 79696 159640 79701 159640 79701 159641 79696 159641 79700 159641 79700 159642 79696 159642 79691 159642 79700 159643 79691 159643 79699 159643 79697 159644 79698 159644 79692 159644 79699 159645 78116 159645 79700 159645 79700 159646 78116 159646 79704 159646 79700 159647 79704 159647 79701 159647 79701 159648 79704 159648 79705 159648 79692 159649 79693 159649 79697 159649 79697 159650 79693 159650 79694 159650 79697 159651 79694 159651 79705 159651 79705 159652 79694 159652 79695 159652 79705 159653 79695 159653 79701 159653 78116 159654 78121 159654 79702 159654 78116 159655 79702 159655 79704 159655 79704 159656 79702 159656 79703 159656 79704 159657 79703 159657 79705 159657 79705 159658 79703 159658 79711 159658 79705 159659 79711 159659 79697 159659 79697 159660 79711 159660 79352 159660 79697 159661 79352 159661 79698 159661 79703 159662 79702 159662 79714 159662 79721 159663 79724 159663 79708 159663 79719 159664 79706 159664 79707 159664 79707 159665 79706 159665 79721 159665 79721 159666 79708 159666 79707 159666 79707 159667 79708 159667 79710 159667 79707 159668 79710 159668 79709 159668 79709 159669 79710 159669 79352 159669 79709 159670 79352 159670 79711 159670 79713 159671 79716 159671 79712 159671 79712 159672 79716 159672 79719 159672 79719 159673 79707 159673 79712 159673 79712 159674 79707 159674 79709 159674 79712 159675 79709 159675 79714 159675 79714 159676 79709 159676 79711 159676 79714 159677 79711 159677 79703 159677 78133 159678 78132 159678 79713 159678 79713 159679 79712 159679 78133 159679 78133 159680 79712 159680 79714 159680 78133 159681 79714 159681 79715 159681 79715 159682 79714 159682 79702 159682 79715 159683 79702 159683 78121 159683 78131 159684 79717 159684 78132 159684 78132 159685 79717 159685 79713 159685 79713 159686 79717 159686 79716 159686 79716 159687 79717 159687 79718 159687 79716 159688 79718 159688 79719 159688 79719 159689 79718 159689 79720 159689 79719 159690 79720 159690 79706 159690 79706 159691 79720 159691 79729 159691 79706 159692 79729 159692 79721 159692 79729 159693 79722 159693 79721 159693 79721 159694 79722 159694 79723 159694 79721 159695 79723 159695 79724 159695 79725 159696 79728 159696 79723 159696 79723 159697 79722 159697 79725 159697 79725 159698 79722 159698 79729 159698 79725 159699 79729 159699 79726 159699 79727 159700 79728 159700 79732 159700 79732 159701 79728 159701 79725 159701 79732 159702 79725 159702 79733 159702 79733 159703 79725 159703 79726 159703 79733 159704 79726 159704 79735 159704 79735 159705 79726 159705 79730 159705 79729 159706 79720 159706 79726 159706 79726 159707 79720 159707 79718 159707 79726 159708 79718 159708 79730 159708 79730 159709 79718 159709 79717 159709 79730 159710 79717 159710 78131 159710 79731 159711 79727 159711 79732 159711 79731 159712 79732 159712 79734 159712 79734 159713 79732 159713 79733 159713 79734 159714 79733 159714 79737 159714 79737 159715 79733 159715 79735 159715 79737 159716 79735 159716 79736 159716 79738 159717 79380 159717 79739 159717 79739 159718 79380 159718 79749 159718 79739 159719 79749 159719 79740 159719 79740 159720 79749 159720 79742 159720 79740 159721 79742 159721 79741 159721 79741 159722 79742 159722 77734 159722 79736 159723 79738 159723 79737 159723 79737 159724 79738 159724 79739 159724 79737 159725 79739 159725 79734 159725 79734 159726 79739 159726 79740 159726 79734 159727 79740 159727 79731 159727 79731 159728 79740 159728 79741 159728 79748 159729 79742 159729 79749 159729 79748 159730 77293 159730 79742 159730 79742 159731 77293 159731 77294 159731 79742 159732 77294 159732 77734 159732 79743 159733 77286 159733 79744 159733 79744 159734 77286 159734 79745 159734 79744 159735 79745 159735 79747 159735 79747 159736 79745 159736 79746 159736 79746 159737 79748 159737 79747 159737 79747 159738 79748 159738 79749 159738 79747 159739 79749 159739 79744 159739 79744 159740 79749 159740 79380 159740 79455 159741 79764 159741 79750 159741 79750 159742 79764 159742 79766 159742 79750 159743 79766 159743 79751 159743 79751 159744 79766 159744 79767 159744 79751 159745 79767 159745 79756 159745 79756 159746 79767 159746 79752 159746 79756 159747 79752 159747 79757 159747 79757 159748 79752 159748 79753 159748 79535 159749 79455 159749 79754 159749 79754 159750 79455 159750 79750 159750 79754 159751 79750 159751 79755 159751 79755 159752 79750 159752 79751 159752 79755 159753 79751 159753 79780 159753 79780 159754 79751 159754 79756 159754 79780 159755 79756 159755 79781 159755 79781 159756 79756 159756 79757 159756 79760 159757 79530 159757 79529 159757 79785 159758 79423 159758 79758 159758 79758 159759 79423 159759 79763 159759 79758 159760 79763 159760 79759 159760 79759 159761 79763 159761 79762 159761 79529 159762 79784 159762 79760 159762 79760 159763 79784 159763 79786 159763 79760 159764 79786 159764 79762 159764 79762 159765 79786 159765 79761 159765 79762 159766 79761 159766 79759 159766 79765 159767 79530 159767 79768 159767 79768 159768 79530 159768 79760 159768 79768 159769 79760 159769 79769 159769 79769 159770 79760 159770 79762 159770 79769 159771 79762 159771 79770 159771 79770 159772 79762 159772 79763 159772 79770 159773 79763 159773 79424 159773 79424 159774 79763 159774 79423 159774 79764 159775 79765 159775 79766 159775 79766 159776 79765 159776 79768 159776 79766 159777 79768 159777 79767 159777 79767 159778 79768 159778 79769 159778 79767 159779 79769 159779 79752 159779 79752 159780 79769 159780 79770 159780 79752 159781 79770 159781 79753 159781 79753 159782 79770 159782 79424 159782 79771 159783 79778 159783 79779 159783 79774 159784 79772 159784 79788 159784 79772 159785 79774 159785 79773 159785 79773 159786 79774 159786 79775 159786 79773 159787 79775 159787 79776 159787 79776 159788 79775 159788 79787 159788 79776 159789 79787 159789 78166 159789 79778 159790 79771 159790 79777 159790 79771 159791 79788 159791 79777 159791 79777 159792 79788 159792 79772 159792 79777 159793 79772 159793 79536 159793 79536 159794 79772 159794 79773 159794 79536 159795 79535 159795 79777 159795 79777 159796 79535 159796 79754 159796 79777 159797 79754 159797 79778 159797 79778 159798 79754 159798 79755 159798 79778 159799 79755 159799 79779 159799 79779 159800 79755 159800 79780 159800 79779 159801 79780 159801 79781 159801 79782 159802 79786 159802 79783 159802 79783 159803 79786 159803 79784 159803 79783 159804 79784 159804 79529 159804 79800 159805 79425 159805 79785 159805 79785 159806 79758 159806 79800 159806 79800 159807 79758 159807 79759 159807 79800 159808 79759 159808 79782 159808 79782 159809 79759 159809 79761 159809 79782 159810 79761 159810 79786 159810 79790 159811 79798 159811 79796 159811 79791 159812 79793 159812 79775 159812 79775 159813 79793 159813 79787 159813 79775 159814 79774 159814 79791 159814 79791 159815 79774 159815 79788 159815 79791 159816 79788 159816 79789 159816 79788 159817 79771 159817 79789 159817 79789 159818 79771 159818 79779 159818 79789 159819 79779 159819 79781 159819 79781 159820 79790 159820 79789 159820 79789 159821 79790 159821 79796 159821 79789 159822 79796 159822 79791 159822 79791 159823 79796 159823 79795 159823 79791 159824 79795 159824 79793 159824 79793 159825 79795 159825 79792 159825 79793 159826 79792 159826 79787 159826 79787 159827 79792 159827 79794 159827 79787 159828 79794 159828 78166 159828 79794 159829 79792 159829 78167 159829 78167 159830 79792 159830 79795 159830 78167 159831 79795 159831 78155 159831 78155 159832 79795 159832 79796 159832 78155 159833 79796 159833 79797 159833 79797 159834 79796 159834 79798 159834 79797 159835 79798 159835 79799 159835 79425 159836 79800 159836 79805 159836 79800 159837 79782 159837 79806 159837 79803 159838 79823 159838 79801 159838 79801 159839 79807 159839 79803 159839 79803 159840 79807 159840 79802 159840 79803 159841 79802 159841 79804 159841 79804 159842 79802 159842 79806 159842 79804 159843 79806 159843 78476 159843 78476 159844 79806 159844 79782 159844 78476 159845 79782 159845 79783 159845 79800 159846 79806 159846 79805 159846 79805 159847 79806 159847 79802 159847 79805 159848 79802 159848 79812 159848 79812 159849 79802 159849 79807 159849 79812 159850 79807 159850 79809 159850 79801 159851 79821 159851 79807 159851 79807 159852 79821 159852 79808 159852 79807 159853 79808 159853 79809 159853 79809 159854 79808 159854 79810 159854 79809 159855 79810 159855 79815 159855 79425 159856 79805 159856 79811 159856 79811 159857 79805 159857 79812 159857 79811 159858 79812 159858 79813 159858 79813 159859 79812 159859 79809 159859 79813 159860 79809 159860 79814 159860 79814 159861 79809 159861 79815 159861 79814 159862 79815 159862 79816 159862 79781 159863 79817 159863 79818 159863 79781 159864 79818 159864 79790 159864 79790 159865 79818 159865 79819 159865 79790 159866 79819 159866 79798 159866 79798 159867 79819 159867 78159 159867 79798 159868 78159 159868 79799 159868 79817 159869 79426 159869 79826 159869 79817 159870 79826 159870 79818 159870 79818 159871 79826 159871 79820 159871 79818 159872 79820 159872 79819 159872 79819 159873 79820 159873 78180 159873 79819 159874 78180 159874 78159 159874 79816 159875 79815 159875 79835 159875 79835 159876 79815 159876 79840 159876 79840 159877 79815 159877 79842 159877 79842 159878 79815 159878 79810 159878 79842 159879 79810 159879 79843 159879 79843 159880 79810 159880 79808 159880 79843 159881 79808 159881 79845 159881 79845 159882 79808 159882 79821 159882 79845 159883 79821 159883 79822 159883 79821 159884 79801 159884 79822 159884 79822 159885 79801 159885 79823 159885 79822 159886 79823 159886 78473 159886 79851 159887 79852 159887 79830 159887 78180 159888 79820 159888 78179 159888 78179 159889 79820 159889 79824 159889 78179 159890 79824 159890 78178 159890 78178 159891 79824 159891 79827 159891 78178 159892 79827 159892 79825 159892 79825 159893 79827 159893 79830 159893 79825 159894 79830 159894 78160 159894 78160 159895 79830 159895 79852 159895 79820 159896 79826 159896 79824 159896 79824 159897 79826 159897 79831 159897 79824 159898 79831 159898 79827 159898 79827 159899 79831 159899 79828 159899 79827 159900 79828 159900 79830 159900 79830 159901 79828 159901 79829 159901 79830 159902 79829 159902 79851 159902 79851 159903 79829 159903 79849 159903 79826 159904 79426 159904 79831 159904 79831 159905 79426 159905 79832 159905 79831 159906 79832 159906 79828 159906 79828 159907 79832 159907 79503 159907 79828 159908 79503 159908 79829 159908 79829 159909 79503 159909 79504 159909 79829 159910 79504 159910 79849 159910 79849 159911 79504 159911 79365 159911 79839 159912 79834 159912 79837 159912 79836 159913 79837 159913 79833 159913 79833 159914 79837 159914 79834 159914 79833 159915 79834 159915 79366 159915 79841 159916 79844 159916 79838 159916 79835 159917 79840 159917 79836 159917 79836 159918 79840 159918 79841 159918 79836 159919 79841 159919 79837 159919 79837 159920 79841 159920 79838 159920 79837 159921 79838 159921 79839 159921 79839 159922 79838 159922 79855 159922 79840 159923 79842 159923 79841 159923 79841 159924 79842 159924 79843 159924 79841 159925 79843 159925 79844 159925 79844 159926 79843 159926 79845 159926 79844 159927 79845 159927 79822 159927 79855 159928 79838 159928 79846 159928 79846 159929 79838 159929 79844 159929 79846 159930 79844 159930 79847 159930 79847 159931 79844 159931 79822 159931 79847 159932 79822 159932 78473 159932 79365 159933 79367 159933 79848 159933 79365 159934 79848 159934 79849 159934 79849 159935 79848 159935 79850 159935 79849 159936 79850 159936 79851 159936 79851 159937 79850 159937 79853 159937 79851 159938 79853 159938 79852 159938 79852 159939 79853 159939 79867 159939 79852 159940 79867 159940 78160 159940 79472 159941 79476 159941 79856 159941 79856 159942 79476 159942 79876 159942 79856 159943 79876 159943 79857 159943 79857 159944 79876 159944 79879 159944 79857 159945 79879 159945 79854 159945 79854 159946 79879 159946 79880 159946 79855 159947 79472 159947 79839 159947 79839 159948 79472 159948 79856 159948 79839 159949 79856 159949 79834 159949 79834 159950 79856 159950 79857 159950 79834 159951 79857 159951 79366 159951 79366 159952 79857 159952 79854 159952 79864 159953 79858 159953 79865 159953 79865 159954 79858 159954 79859 159954 79865 159955 79859 159955 79866 159955 79866 159956 79859 159956 79860 159956 79866 159957 79860 159957 79861 159957 79861 159958 79860 159958 79862 159958 79861 159959 79862 159959 79486 159959 79486 159960 79862 159960 79863 159960 79367 159961 79864 159961 79848 159961 79848 159962 79864 159962 79865 159962 79848 159963 79865 159963 79850 159963 79850 159964 79865 159964 79866 159964 79850 159965 79866 159965 79853 159965 79853 159966 79866 159966 79861 159966 79853 159967 79861 159967 79867 159967 79867 159968 79861 159968 79486 159968 79868 159969 79385 159969 79874 159969 79874 159970 79385 159970 79869 159970 79874 159971 79869 159971 79870 159971 79870 159972 79869 159972 79871 159972 79870 159973 79871 159973 79363 159973 79363 159974 79871 159974 79872 159974 79877 159975 79868 159975 79878 159975 79878 159976 79868 159976 79874 159976 79878 159977 79874 159977 79873 159977 79873 159978 79874 159978 79870 159978 79873 159979 79870 159979 79875 159979 79875 159980 79870 159980 79363 159980 79476 159981 79877 159981 79876 159981 79876 159982 79877 159982 79878 159982 79876 159983 79878 159983 79879 159983 79879 159984 79878 159984 79873 159984 79879 159985 79873 159985 79880 159985 79880 159986 79873 159986 79875 159986 79881 159987 79882 159987 77348 159987 77348 159988 79882 159988 79883 159988 77348 159989 79883 159989 77328 159989 77328 159990 79883 159990 79884 159990 79884 159991 79883 159991 79885 159991 79884 159992 79885 159992 79889 159992 79889 159993 79885 159993 79887 159993 79889 159994 79887 159994 79886 159994 79886 159995 79887 159995 79364 159995 79886 159996 79364 159996 79362 159996 79858 159997 79364 159997 79859 159997 79859 159998 79364 159998 79887 159998 79859 159999 79887 159999 79860 159999 79860 160000 79887 160000 79885 160000 79860 160001 79885 160001 79862 160001 79862 160002 79885 160002 79883 160002 79862 160003 79883 160003 79863 160003 79863 160004 79883 160004 79882 160004 79362 160005 79872 160005 79871 160005 79362 160006 79871 160006 79897 160006 79897 160007 79871 160007 79869 160007 79897 160008 79869 160008 79896 160008 79896 160009 79869 160009 79385 160009 79896 160010 79385 160010 79888 160010 77328 160011 79884 160011 77327 160011 77327 160012 79884 160012 79889 160012 77327 160013 79889 160013 79890 160013 79894 160014 77357 160014 79890 160014 79890 160015 77357 160015 79891 160015 79890 160016 79891 160016 77327 160016 79892 160017 77356 160017 79893 160017 79893 160018 77356 160018 79894 160018 79893 160019 79894 160019 79895 160019 79895 160020 79894 160020 79890 160020 79895 160021 79890 160021 79886 160021 79886 160022 79890 160022 79889 160022 79888 160023 79892 160023 79896 160023 79896 160024 79892 160024 79893 160024 79896 160025 79893 160025 79897 160025 79897 160026 79893 160026 79895 160026 79897 160027 79895 160027 79362 160027 79362 160028 79895 160028 79886 160028 79469 160029 79471 160029 79902 160029 79468 160030 79898 160030 79910 160030 79910 160031 79898 160031 79899 160031 79910 160032 79899 160032 79907 160032 79907 160033 79899 160033 79900 160033 79907 160034 79900 160034 78119 160034 78119 160035 79900 160035 78125 160035 79898 160036 79469 160036 79899 160036 79899 160037 79469 160037 79902 160037 79899 160038 79902 160038 79900 160038 79900 160039 79902 160039 79904 160039 79900 160040 79904 160040 78125 160040 78125 160041 79904 160041 79906 160041 79471 160042 79901 160042 79902 160042 79902 160043 79901 160043 79903 160043 79902 160044 79903 160044 79904 160044 79904 160045 79903 160045 79905 160045 79904 160046 79905 160046 79906 160046 79906 160047 79905 160047 78127 160047 78120 160048 79908 160048 78119 160048 78119 160049 79908 160049 79907 160049 79908 160050 79917 160050 79907 160050 79907 160051 79917 160051 79909 160051 79907 160052 79909 160052 79910 160052 79398 160053 79468 160053 79915 160053 79915 160054 79468 160054 79910 160054 79915 160055 79910 160055 79916 160055 79916 160056 79910 160056 79909 160056 79911 160057 79918 160057 79398 160057 78120 160058 79912 160058 79908 160058 79908 160059 79912 160059 79913 160059 79908 160060 79913 160060 79917 160060 79917 160061 79913 160061 79914 160061 79398 160062 79915 160062 79911 160062 79911 160063 79915 160063 79916 160063 79911 160064 79916 160064 79914 160064 79914 160065 79916 160065 79909 160065 79914 160066 79909 160066 79917 160066 79397 160067 79918 160067 79919 160067 79919 160068 79918 160068 79911 160068 79919 160069 79911 160069 79920 160069 79920 160070 79911 160070 79914 160070 79920 160071 79914 160071 79924 160071 79924 160072 79914 160072 79913 160072 79924 160073 79913 160073 79921 160073 79921 160074 79913 160074 79912 160074 79463 160075 79397 160075 79919 160075 79463 160076 79919 160076 79922 160076 79922 160077 79919 160077 79920 160077 79922 160078 79920 160078 79923 160078 79923 160079 79920 160079 79924 160079 79923 160080 79924 160080 79930 160080 79930 160081 79924 160081 79921 160081 79930 160082 79921 160082 79925 160082 79457 160083 79938 160083 79931 160083 79931 160084 79938 160084 79939 160084 79931 160085 79939 160085 79926 160085 79926 160086 79939 160086 79928 160086 79926 160087 79928 160087 79927 160087 79927 160088 79928 160088 79929 160088 79927 160089 79929 160089 79932 160089 79932 160090 79929 160090 79461 160090 79925 160091 79457 160091 79930 160091 79930 160092 79457 160092 79931 160092 79930 160093 79931 160093 79923 160093 79923 160094 79931 160094 79926 160094 79923 160095 79926 160095 79922 160095 79922 160096 79926 160096 79927 160096 79922 160097 79927 160097 79463 160097 79463 160098 79927 160098 79932 160098 79534 160099 79533 160099 79933 160099 79933 160100 79533 160100 79934 160100 79933 160101 79934 160101 79940 160101 79940 160102 79934 160102 79935 160102 79940 160103 79935 160103 79936 160103 79936 160104 79935 160104 79947 160104 79936 160105 79947 160105 79937 160105 79937 160106 79947 160106 79399 160106 79938 160107 79534 160107 79939 160107 79939 160108 79534 160108 79933 160108 79939 160109 79933 160109 79928 160109 79928 160110 79933 160110 79940 160110 79928 160111 79940 160111 79929 160111 79929 160112 79940 160112 79936 160112 79929 160113 79936 160113 79461 160113 79461 160114 79936 160114 79937 160114 79946 160115 79942 160115 79941 160115 79941 160116 79942 160116 79951 160116 79941 160117 79951 160117 79943 160117 79943 160118 79951 160118 79944 160118 79943 160119 79944 160119 79945 160119 79945 160120 79944 160120 79950 160120 79945 160121 79950 160121 79948 160121 79948 160122 79950 160122 79949 160122 79533 160123 79946 160123 79934 160123 79934 160124 79946 160124 79941 160124 79934 160125 79941 160125 79935 160125 79935 160126 79941 160126 79943 160126 79935 160127 79943 160127 79947 160127 79947 160128 79943 160128 79945 160128 79947 160129 79945 160129 79399 160129 79399 160130 79945 160130 79948 160130 79023 160131 79949 160131 79950 160131 79023 160132 79950 160132 79010 160132 79010 160133 79950 160133 79944 160133 79010 160134 79944 160134 79017 160134 79017 160135 79944 160135 79951 160135 79017 160136 79951 160136 79016 160136 79016 160137 79951 160137 79942 160137 79016 160138 79942 160138 79952 160138 79966 160139 79402 160139 79953 160139 79953 160140 79402 160140 79046 160140 79953 160141 79046 160141 79954 160141 79954 160142 79046 160142 79035 160142 79954 160143 79035 160143 79963 160143 79963 160144 79035 160144 79034 160144 79963 160145 79034 160145 79531 160145 79531 160146 79034 160146 78472 160146 79957 160147 79532 160147 79955 160147 79404 160148 79961 160148 79970 160148 79970 160149 79961 160149 79960 160149 79970 160150 79960 160150 79971 160150 79971 160151 79960 160151 79956 160151 79971 160152 79956 160152 79972 160152 79972 160153 79956 160153 79957 160153 79972 160154 79957 160154 79968 160154 79968 160155 79957 160155 79955 160155 79962 160156 79532 160156 79964 160156 79964 160157 79532 160157 79957 160157 79964 160158 79957 160158 79965 160158 79965 160159 79957 160159 79956 160159 79965 160160 79956 160160 79958 160160 79958 160161 79956 160161 79960 160161 79958 160162 79960 160162 79959 160162 79959 160163 79960 160163 79961 160163 79531 160164 79962 160164 79963 160164 79963 160165 79962 160165 79964 160165 79963 160166 79964 160166 79954 160166 79954 160167 79964 160167 79965 160167 79954 160168 79965 160168 79953 160168 79953 160169 79965 160169 79958 160169 79953 160170 79958 160170 79966 160170 79966 160171 79958 160171 79959 160171 79967 160172 79973 160172 79404 160172 79955 160173 79456 160173 79968 160173 79968 160174 79456 160174 79969 160174 79404 160175 79970 160175 79967 160175 79967 160176 79970 160176 79971 160176 79967 160177 79971 160177 79969 160177 79969 160178 79971 160178 79972 160178 79969 160179 79972 160179 79968 160179 79406 160180 79973 160180 79974 160180 79974 160181 79973 160181 79967 160181 79974 160182 79967 160182 79977 160182 79977 160183 79967 160183 79969 160183 79977 160184 79969 160184 79978 160184 79978 160185 79969 160185 79456 160185 79400 160186 79406 160186 79980 160186 79980 160187 79406 160187 79974 160187 79980 160188 79974 160188 79975 160188 79975 160189 79974 160189 79977 160189 79975 160190 79977 160190 79976 160190 79976 160191 79977 160191 79978 160191 79401 160192 79400 160192 79979 160192 79979 160193 79400 160193 79980 160193 79979 160194 79980 160194 79981 160194 79981 160195 79980 160195 79975 160195 79981 160196 79975 160196 79537 160196 79537 160197 79975 160197 79976 160197 79982 160198 79401 160198 79987 160198 79987 160199 79401 160199 79979 160199 79987 160200 79979 160200 79983 160200 79983 160201 79979 160201 79981 160201 79983 160202 79981 160202 79538 160202 79538 160203 79981 160203 79537 160203 79984 160204 79998 160204 79538 160204 79538 160205 79998 160205 79983 160205 79998 160206 79985 160206 79983 160206 79983 160207 79985 160207 79997 160207 79983 160208 79997 160208 79987 160208 79459 160209 79982 160209 79986 160209 79986 160210 79982 160210 79987 160210 79986 160211 79987 160211 79988 160211 79988 160212 79987 160212 79997 160212 79460 160213 79990 160213 79989 160213 79989 160214 79990 160214 79991 160214 79989 160215 79991 160215 79992 160215 79992 160216 79991 160216 79995 160216 79990 160217 79459 160217 79991 160217 79991 160218 79459 160218 79986 160218 79991 160219 79986 160219 79995 160219 79996 160220 79993 160220 79995 160220 79995 160221 79993 160221 79994 160221 79995 160222 79994 160222 79992 160222 79986 160223 79988 160223 79995 160223 79995 160224 79988 160224 79997 160224 79995 160225 79997 160225 79996 160225 78165 160226 78177 160226 79996 160226 79996 160227 78177 160227 79999 160227 79996 160228 79999 160228 79993 160228 79997 160229 79985 160229 79996 160229 79996 160230 79985 160230 79998 160230 79996 160231 79998 160231 78165 160231 78165 160232 79998 160232 79984 160232 78177 160233 78176 160233 79999 160233 79999 160234 78176 160234 80000 160234 79999 160235 80000 160235 79993 160235 79993 160236 80000 160236 79994 160236 79994 160237 80000 160237 80011 160237 79994 160238 80011 160238 79992 160238 79992 160239 80011 160239 79989 160239 79989 160240 80011 160240 80001 160240 79989 160241 80001 160241 79460 160241 79464 160242 80002 160242 79114 160242 79114 160243 80002 160243 80003 160243 79114 160244 80003 160244 80004 160244 80004 160245 80003 160245 80008 160245 80004 160246 80008 160246 80005 160246 80005 160247 80008 160247 80010 160247 80002 160248 80006 160248 80003 160248 80003 160249 80006 160249 80007 160249 80003 160250 80007 160250 80008 160250 80008 160251 80007 160251 80009 160251 80008 160252 80009 160252 80010 160252 80010 160253 80009 160253 78175 160253 80006 160254 80001 160254 80007 160254 80007 160255 80001 160255 80011 160255 80007 160256 80011 160256 80009 160256 80009 160257 80011 160257 80000 160257 80009 160258 80000 160258 78175 160258 78175 160259 80000 160259 78176 160259 80012 160260 79497 160260 80013 160260 80013 160261 79497 160261 79498 160261 80013 160262 79498 160262 80015 160262 80015 160263 79498 160263 80014 160263 80015 160264 80014 160264 80016 160264 80012 160265 80013 160265 80020 160265 80020 160266 80013 160266 80015 160266 80020 160267 80015 160267 80019 160267 80019 160268 80015 160268 80016 160268 80019 160269 80016 160269 80017 160269 79511 160270 79512 160270 80017 160270 80017 160271 79512 160271 80018 160271 80017 160272 80018 160272 80019 160272 80019 160273 80018 160273 79514 160273 80019 160274 79514 160274 80020 160274 80020 160275 79514 160275 80012 160275 80027 160276 79511 160276 80021 160276 80021 160277 79511 160277 80017 160277 80021 160278 80017 160278 80024 160278 80024 160279 80017 160279 80016 160279 80024 160280 80016 160280 79387 160280 79387 160281 80016 160281 80014 160281 80025 160282 80029 160282 80022 160282 80022 160283 80029 160283 80030 160283 80022 160284 80030 160284 80026 160284 80026 160285 80030 160285 80023 160285 80026 160286 80023 160286 79510 160286 79510 160287 80023 160287 80028 160287 79387 160288 80025 160288 80024 160288 80024 160289 80025 160289 80022 160289 80024 160290 80022 160290 80021 160290 80021 160291 80022 160291 80026 160291 80021 160292 80026 160292 80027 160292 80027 160293 80026 160293 79510 160293 77291 160294 80023 160294 80030 160294 80023 160295 77291 160295 80028 160295 77292 160296 77290 160296 80029 160296 80029 160297 77290 160297 77288 160297 80029 160298 77288 160298 80030 160298 80030 160299 77288 160299 77287 160299 80030 160300 77287 160300 77291 160300 79521 160301 80047 160301 80046 160301 80034 160302 80041 160302 80032 160302 80032 160303 80041 160303 80031 160303 80032 160304 80031 160304 80033 160304 80033 160305 80031 160305 80039 160305 80033 160306 80039 160306 80038 160306 80034 160307 80032 160307 80035 160307 80035 160308 80032 160308 80033 160308 80035 160309 80033 160309 80036 160309 80036 160310 80033 160310 80038 160310 80036 160311 80038 160311 80037 160311 79521 160312 80046 160312 79520 160312 80043 160313 80037 160313 80044 160313 80044 160314 80037 160314 80038 160314 80044 160315 80038 160315 80046 160315 80046 160316 80038 160316 80039 160316 80046 160317 80039 160317 79520 160317 79520 160318 80039 160318 80031 160318 79520 160319 80031 160319 80040 160319 80040 160320 80031 160320 80041 160320 80040 160321 80041 160321 79516 160321 79516 160322 80041 160322 80034 160322 80042 160323 80043 160323 80050 160323 80050 160324 80043 160324 80044 160324 80050 160325 80044 160325 80045 160325 80045 160326 80044 160326 80046 160326 80045 160327 80046 160327 79515 160327 79515 160328 80046 160328 80047 160328 80048 160329 80042 160329 80049 160329 80049 160330 80042 160330 80050 160330 80049 160331 80050 160331 80051 160331 80051 160332 80050 160332 80045 160332 80051 160333 80045 160333 80052 160333 80052 160334 80045 160334 79515 160334 77284 160335 80053 160335 80048 160335 80048 160336 80053 160336 80054 160336 80048 160337 80054 160337 80055 160337 80052 160338 80056 160338 80051 160338 80051 160339 80056 160339 77284 160339 80051 160340 77284 160340 80049 160340 80049 160341 77284 160341 80048 160341 77889 160342 80140 160342 80057 160342 80057 160343 80140 160343 80133 160343 80057 160344 80133 160344 83736 160344 83736 160345 80133 160345 80058 160345 80060 160346 83739 160346 80137 160346 80137 160347 83739 160347 83738 160347 80137 160348 83738 160348 80058 160348 80058 160349 83738 160349 80059 160349 80058 160350 80059 160350 83736 160350 79393 160351 83735 160351 80137 160351 80137 160352 83735 160352 83734 160352 80137 160353 83734 160353 80060 160353 79346 160354 80101 160354 80102 160354 79346 160355 80102 160355 77894 160355 77894 160356 80102 160356 80061 160356 77894 160357 80061 160357 77893 160357 77893 160358 80061 160358 80104 160358 77893 160359 80104 160359 77897 160359 77897 160360 80104 160360 77788 160360 77897 160361 77788 160361 77824 160361 80062 160362 80066 160362 79335 160362 79335 160363 79333 160363 80062 160363 80062 160364 79333 160364 79336 160364 80062 160365 79336 160365 78163 160365 79331 160366 80065 160366 80063 160366 80063 160367 80065 160367 80093 160367 80063 160368 80093 160368 79345 160368 79331 160369 79330 160369 80065 160369 80065 160370 79330 160370 80064 160370 80065 160371 80064 160371 80066 160371 80066 160372 80064 160372 79329 160372 80066 160373 79329 160373 79335 160373 80067 160374 80203 160374 80068 160374 80068 160375 80203 160375 80069 160375 80068 160376 80069 160376 79323 160376 79323 160377 80069 160377 79322 160377 80211 160378 79325 160378 80069 160378 80069 160379 79325 160379 80070 160379 80069 160380 80070 160380 79322 160380 78113 160381 79313 160381 78112 160381 78112 160382 79313 160382 79315 160382 78112 160383 79315 160383 80211 160383 80211 160384 79315 160384 79314 160384 80211 160385 79314 160385 79325 160385 80071 160386 80171 160386 80072 160386 80071 160387 80072 160387 78238 160387 78238 160388 80072 160388 80073 160388 78238 160389 80073 160389 80075 160389 80075 160390 80073 160390 80074 160390 80075 160391 80074 160391 80076 160391 80076 160392 80074 160392 80182 160392 80076 160393 80182 160393 79408 160393 80080 160394 80077 160394 80078 160394 80077 160395 83826 160395 80078 160395 80078 160396 83826 160396 80079 160396 80078 160397 80079 160397 79392 160397 79392 160398 80079 160398 83827 160398 79392 160399 83827 160399 79390 160399 80078 160400 80147 160400 80080 160400 80080 160401 80147 160401 80081 160401 80080 160402 80081 160402 83824 160402 77773 160403 77775 160403 80081 160403 80081 160404 77775 160404 80082 160404 80081 160405 80082 160405 83824 160405 80093 160406 80065 160406 80083 160406 80083 160407 80065 160407 80084 160407 80083 160408 80084 160408 80085 160408 80085 160409 80084 160409 80087 160409 80085 160410 80087 160410 80096 160410 80096 160411 80087 160411 80089 160411 80065 160412 80066 160412 80084 160412 80084 160413 80066 160413 80086 160413 80084 160414 80086 160414 80087 160414 80087 160415 80086 160415 80088 160415 80087 160416 80088 160416 80089 160416 80089 160417 80088 160417 80090 160417 80066 160418 80062 160418 80086 160418 80086 160419 80062 160419 80091 160419 80086 160420 80091 160420 80088 160420 80088 160421 80091 160421 80099 160421 80088 160422 80099 160422 80090 160422 80090 160423 80099 160423 79415 160423 80101 160424 80093 160424 80092 160424 80092 160425 80093 160425 80083 160425 80092 160426 80083 160426 80094 160426 80094 160427 80083 160427 80109 160427 80109 160428 80083 160428 80085 160428 80109 160429 80085 160429 80095 160429 80095 160430 80085 160430 80097 160430 80097 160431 80085 160431 80096 160431 80097 160432 80096 160432 80116 160432 80062 160433 78151 160433 80098 160433 80062 160434 80098 160434 80091 160434 80091 160435 80098 160435 80117 160435 80091 160436 80117 160436 80099 160436 80099 160437 80117 160437 79418 160437 80099 160438 79418 160438 79415 160438 79412 160439 80100 160439 80111 160439 80100 160440 80130 160440 80106 160440 80130 160441 80105 160441 80103 160441 80101 160442 80108 160442 80102 160442 80102 160443 80108 160443 80107 160443 80102 160444 80107 160444 80061 160444 80061 160445 80107 160445 80103 160445 80061 160446 80103 160446 80104 160446 80104 160447 80103 160447 80105 160447 80104 160448 80105 160448 77788 160448 80130 160449 80103 160449 80106 160449 80106 160450 80103 160450 80107 160450 80106 160451 80107 160451 80112 160451 80112 160452 80107 160452 80108 160452 80112 160453 80108 160453 80110 160453 80101 160454 80092 160454 80108 160454 80108 160455 80092 160455 80094 160455 80108 160456 80094 160456 80110 160456 80110 160457 80094 160457 80109 160457 80110 160458 80109 160458 80095 160458 80100 160459 80106 160459 80111 160459 80111 160460 80106 160460 80112 160460 80111 160461 80112 160461 80115 160461 80115 160462 80112 160462 80110 160462 80115 160463 80110 160463 80113 160463 80113 160464 80110 160464 80095 160464 80113 160465 80095 160465 80097 160465 79412 160466 80111 160466 79416 160466 79416 160467 80111 160467 80115 160467 79416 160468 80115 160468 80114 160468 80114 160469 80115 160469 80113 160469 80114 160470 80113 160470 79417 160470 79417 160471 80113 160471 80097 160471 79417 160472 80097 160472 80116 160472 80119 160473 80122 160473 80123 160473 78151 160474 79513 160474 80098 160474 80098 160475 79513 160475 80120 160475 80098 160476 80120 160476 80117 160476 80117 160477 80120 160477 80118 160477 80117 160478 80118 160478 79418 160478 79418 160479 80118 160479 80121 160479 79513 160480 80119 160480 80120 160480 80120 160481 80119 160481 80123 160481 80120 160482 80123 160482 80118 160482 80118 160483 80123 160483 80125 160483 80118 160484 80125 160484 80121 160484 80121 160485 80125 160485 79419 160485 80122 160486 77746 160486 80123 160486 80123 160487 77746 160487 80124 160487 80123 160488 80124 160488 80125 160488 80125 160489 80124 160489 80126 160489 80125 160490 80126 160490 79419 160490 79419 160491 80126 160491 80127 160491 79412 160492 80128 160492 80143 160492 79412 160493 80143 160493 80100 160493 80100 160494 80143 160494 80129 160494 80100 160495 80129 160495 80130 160495 80130 160496 80129 160496 80131 160496 80130 160497 80131 160497 80105 160497 80105 160498 80131 160498 80140 160498 80105 160499 80140 160499 77788 160499 79394 160500 79393 160500 80134 160500 79394 160501 80134 160501 83888 160501 83888 160502 80134 160502 80135 160502 83888 160503 80135 160503 80132 160503 80132 160504 80135 160504 79421 160504 80132 160505 79421 160505 79422 160505 80141 160506 80133 160506 80140 160506 80133 160507 80141 160507 80058 160507 79393 160508 80137 160508 80134 160508 80134 160509 80137 160509 80138 160509 80134 160510 80138 160510 80135 160510 80135 160511 80138 160511 80136 160511 80135 160512 80136 160512 79421 160512 79421 160513 80136 160513 80139 160513 80137 160514 80058 160514 80138 160514 80138 160515 80058 160515 80141 160515 80138 160516 80141 160516 80136 160516 80136 160517 80141 160517 80142 160517 80136 160518 80142 160518 80139 160518 80139 160519 80142 160519 79420 160519 80140 160520 80131 160520 80141 160520 80141 160521 80131 160521 80129 160521 80141 160522 80129 160522 80142 160522 80142 160523 80129 160523 80143 160523 80142 160524 80143 160524 79420 160524 79420 160525 80143 160525 80128 160525 80147 160526 80078 160526 80148 160526 79343 160527 80145 160527 80144 160527 80144 160528 80145 160528 80146 160528 80144 160529 80146 160529 77757 160529 77757 160530 80146 160530 80148 160530 77757 160531 80148 160531 79392 160531 79392 160532 80148 160532 80078 160532 80081 160533 80147 160533 80151 160533 80151 160534 80147 160534 80148 160534 80151 160535 80148 160535 80150 160535 80150 160536 80148 160536 80146 160536 80150 160537 80146 160537 80149 160537 80149 160538 80146 160538 80145 160538 80149 160539 79342 160539 80150 160539 80150 160540 79342 160540 80156 160540 80150 160541 80156 160541 80151 160541 80151 160542 80156 160542 80155 160542 80151 160543 80155 160543 80081 160543 80081 160544 80155 160544 77773 160544 80152 160545 80171 160545 77773 160545 80152 160546 77773 160546 80153 160546 80153 160547 77773 160547 80155 160547 80153 160548 80155 160548 80154 160548 80154 160549 80155 160549 80156 160549 80154 160550 80156 160550 80167 160550 80167 160551 80156 160551 80164 160551 80164 160552 80156 160552 79342 160552 80164 160553 79342 160553 79341 160553 80157 160554 79339 160554 83878 160554 80157 160555 83878 160555 80158 160555 80158 160556 83878 160556 83877 160556 80158 160557 83877 160557 80159 160557 80159 160558 83877 160558 79388 160558 80159 160559 79388 160559 80160 160559 80167 160560 80164 160560 80168 160560 80172 160561 80174 160561 80161 160561 80161 160562 80174 160562 80162 160562 80161 160563 80162 160563 80163 160563 80163 160564 80162 160564 80168 160564 80163 160565 80168 160565 80165 160565 80165 160566 80168 160566 80164 160566 80165 160567 80164 160567 79341 160567 80153 160568 80154 160568 80166 160568 80166 160569 80154 160569 80167 160569 80167 160570 80168 160570 80166 160570 80166 160571 80168 160571 80162 160571 80166 160572 80162 160572 80169 160572 80169 160573 80162 160573 80174 160573 80169 160574 80174 160574 80170 160574 80171 160575 80152 160575 80178 160575 80178 160576 80152 160576 80153 160576 80172 160577 80173 160577 80174 160577 80174 160578 80173 160578 80175 160578 80174 160579 80175 160579 80170 160579 80170 160580 80175 160580 80176 160580 80170 160581 80176 160581 80177 160581 80153 160582 80166 160582 80178 160582 80178 160583 80166 160583 80169 160583 80178 160584 80169 160584 80179 160584 80179 160585 80169 160585 80170 160585 80179 160586 80170 160586 80180 160586 80180 160587 80170 160587 80177 160587 80180 160588 80177 160588 80181 160588 80171 160589 80178 160589 80072 160589 80072 160590 80178 160590 80179 160590 80072 160591 80179 160591 80073 160591 80073 160592 80179 160592 80180 160592 80073 160593 80180 160593 80074 160593 80074 160594 80180 160594 80181 160594 80074 160595 80181 160595 80182 160595 80195 160596 79340 160596 80184 160596 80197 160597 80183 160597 80185 160597 80185 160598 80183 160598 80195 160598 80195 160599 80184 160599 80185 160599 80185 160600 80184 160600 79344 160600 80185 160601 79344 160601 80186 160601 80186 160602 79344 160602 80187 160602 80186 160603 80187 160603 80188 160603 80188 160604 80187 160604 80157 160604 80188 160605 80157 160605 80158 160605 80200 160606 80199 160606 80190 160606 80190 160607 80199 160607 80197 160607 80197 160608 80185 160608 80190 160608 80190 160609 80185 160609 80186 160609 80190 160610 80186 160610 80191 160610 80191 160611 80186 160611 80188 160611 80191 160612 80188 160612 80189 160612 80189 160613 80188 160613 80158 160613 80189 160614 80158 160614 80159 160614 79518 160615 79517 160615 80200 160615 80200 160616 80190 160616 79518 160616 79518 160617 80190 160617 80191 160617 79518 160618 80191 160618 79519 160618 79519 160619 80191 160619 80189 160619 79519 160620 80189 160620 80192 160620 80192 160621 80189 160621 80159 160621 80192 160622 80159 160622 80160 160622 80172 160623 80193 160623 80173 160623 80173 160624 80193 160624 80201 160624 80173 160625 80201 160625 80175 160625 80175 160626 80201 160626 80176 160626 80176 160627 80201 160627 80194 160627 80176 160628 80194 160628 80177 160628 80177 160629 80194 160629 80181 160629 80181 160630 80194 160630 80203 160630 80181 160631 80203 160631 80182 160631 79340 160632 80195 160632 79338 160632 79338 160633 80195 160633 80208 160633 80208 160634 80195 160634 80196 160634 80196 160635 80195 160635 80183 160635 80196 160636 80183 160636 80209 160636 80209 160637 80183 160637 80197 160637 80209 160638 80197 160638 80198 160638 80198 160639 80197 160639 80199 160639 80198 160640 80199 160640 80212 160640 80199 160641 80200 160641 80212 160641 80212 160642 80200 160642 79517 160642 80212 160643 79517 160643 78112 160643 79338 160644 80208 160644 80205 160644 80205 160645 80208 160645 80206 160645 80193 160646 80204 160646 80201 160646 80201 160647 80204 160647 80202 160647 80201 160648 80202 160648 80194 160648 80194 160649 80202 160649 80207 160649 80194 160650 80207 160650 80203 160650 80204 160651 80205 160651 80202 160651 80202 160652 80205 160652 80206 160652 80202 160653 80206 160653 80207 160653 80207 160654 80206 160654 80210 160654 80208 160655 80196 160655 80206 160655 80206 160656 80196 160656 80209 160656 80206 160657 80209 160657 80210 160657 80210 160658 80209 160658 80198 160658 80210 160659 80198 160659 80212 160659 80203 160660 80207 160660 80069 160660 80069 160661 80207 160661 80210 160661 80069 160662 80210 160662 80211 160662 80211 160663 80210 160663 80212 160663 80211 160664 80212 160664 78112 160664 77464 160665 80213 160665 77466 160665 77466 160666 80213 160666 80388 160666 77466 160667 80388 160667 80214 160667 80214 160668 80388 160668 80390 160668 80214 160669 80390 160669 77614 160669 77614 160670 80390 160670 80215 160670 77614 160671 80215 160671 77467 160671 77467 160672 80215 160672 80373 160672 77467 160673 80373 160673 77468 160673 77468 160674 80373 160674 80216 160674 77468 160675 80216 160675 77470 160675 77470 160676 80216 160676 80372 160676 77470 160677 80372 160677 80217 160677 80217 160678 80372 160678 80218 160678 80217 160679 80218 160679 77584 160679 77584 160680 80218 160680 80219 160680 77584 160681 80219 160681 80220 160681 80220 160682 80219 160682 80382 160682 80220 160683 80382 160683 77461 160683 77461 160684 80382 160684 80221 160684 77461 160685 80221 160685 77463 160685 77463 160686 80221 160686 80385 160686 77463 160687 80385 160687 77464 160687 77464 160688 80385 160688 80213 160688 80233 160689 80222 160689 80223 160689 80223 160690 80222 160690 80380 160690 80223 160691 80380 160691 80224 160691 80224 160692 80380 160692 80225 160692 80224 160693 80225 160693 77612 160693 77612 160694 80225 160694 80378 160694 77612 160695 80378 160695 80226 160695 80226 160696 80378 160696 80227 160696 80226 160697 80227 160697 80228 160697 80228 160698 80227 160698 80377 160698 80228 160699 80377 160699 77617 160699 77617 160700 80377 160700 80374 160700 77617 160701 80374 160701 77613 160701 77613 160702 80374 160702 80375 160702 77613 160703 80375 160703 80229 160703 80229 160704 80375 160704 80376 160704 80229 160705 80376 160705 80230 160705 80230 160706 80376 160706 80231 160706 80230 160707 80231 160707 80232 160707 80232 160708 80231 160708 80392 160708 80232 160709 80392 160709 77616 160709 77616 160710 80392 160710 80391 160710 77616 160711 80391 160711 80233 160711 80233 160712 80391 160712 80222 160712 80234 160713 81739 160713 81730 160713 81729 160714 80234 160714 80235 160714 80235 160715 80234 160715 81730 160715 80235 160716 81730 160716 81734 160716 80245 160717 81309 160717 81306 160717 80236 160718 80237 160718 80243 160718 80238 160719 80239 160719 81267 160719 81306 160720 80240 160720 80245 160720 80245 160721 80240 160721 81303 160721 80245 160722 81303 160722 80241 160722 80241 160723 81303 160723 80238 160723 81290 160724 81284 160724 80242 160724 80243 160725 80241 160725 80236 160725 80236 160726 80241 160726 80238 160726 80236 160727 80238 160727 80244 160727 80244 160728 80238 160728 81267 160728 80244 160729 81267 160729 81268 160729 80402 160730 83873 160730 80245 160730 80245 160731 83873 160731 81262 160731 80245 160732 81262 160732 81309 160732 81309 160733 81262 160733 81290 160733 81309 160734 81290 160734 80246 160734 80246 160735 81290 160735 80242 160735 77864 160736 80251 160736 77863 160736 77863 160737 80251 160737 80381 160737 77863 160738 80381 160738 80247 160738 80247 160739 80381 160739 80248 160739 80247 160740 80248 160740 80249 160740 80249 160741 80248 160741 77781 160741 81338 160742 80383 160742 80250 160742 80250 160743 80383 160743 80251 160743 80250 160744 80251 160744 77864 160744 77649 160745 80252 160745 80253 160745 80253 160746 80252 160746 3090 160746 80253 160747 3090 160747 80254 160747 77399 160748 81096 160748 77398 160748 77398 160749 81096 160749 81103 160749 77419 160750 80782 160750 80255 160750 80255 160751 80782 160751 80256 160751 80255 160752 80256 160752 77420 160752 77420 160753 80256 160753 80787 160753 80761 160754 80258 160754 80257 160754 80257 160755 80258 160755 77444 160755 80257 160756 77444 160756 80753 160756 80258 160757 80761 160757 80259 160757 80259 160758 80761 160758 80260 160758 80259 160759 80260 160759 80261 160759 80261 160760 80260 160760 80765 160760 80261 160761 80765 160761 80262 160761 80262 160762 80765 160762 80263 160762 80262 160763 80263 160763 80264 160763 80264 160764 80263 160764 80265 160764 80265 160765 80782 160765 80264 160765 80264 160766 80782 160766 77419 160766 80284 160767 80266 160767 82082 160767 81302 160768 80526 160768 80270 160768 82082 160769 80266 160769 82079 160769 81302 160770 80270 160770 80268 160770 80791 160771 80288 160771 80267 160771 80267 160772 80288 160772 80268 160772 80267 160773 80268 160773 80269 160773 80269 160774 80268 160774 80270 160774 80266 160775 81474 160775 82079 160775 82079 160776 81474 160776 81476 160776 82079 160777 81476 160777 82201 160777 82201 160778 81476 160778 80271 160778 82201 160779 80271 160779 82040 160779 81903 160780 81905 160780 82082 160780 80654 160781 80287 160781 80697 160781 80757 160782 80636 160782 80272 160782 80636 160783 80757 160783 80655 160783 80655 160784 80757 160784 80543 160784 80655 160785 80543 160785 80287 160785 80279 160786 80960 160786 80290 160786 81589 160787 81703 160787 80273 160787 80273 160788 81703 160788 80274 160788 80273 160789 80274 160789 81916 160789 81916 160790 80274 160790 81712 160790 81916 160791 81712 160791 81906 160791 81589 160792 81590 160792 81703 160792 81703 160793 81590 160793 81591 160793 81703 160794 81591 160794 80275 160794 80275 160795 81591 160795 80276 160795 80275 160796 80276 160796 81493 160796 81493 160797 80276 160797 81596 160797 81493 160798 81596 160798 80277 160798 80277 160799 81596 160799 80278 160799 80272 160800 80639 160800 80757 160800 80757 160801 80639 160801 80644 160801 80757 160802 80644 160802 80631 160802 80290 160803 80770 160803 80279 160803 80279 160804 80770 160804 80280 160804 80279 160805 80280 160805 80631 160805 80631 160806 80280 160806 80281 160806 80631 160807 80281 160807 80757 160807 81616 160808 81632 160808 81491 160808 81712 160809 81713 160809 81906 160809 81906 160810 81713 160810 80282 160810 81906 160811 80282 160811 81905 160811 81905 160812 80282 160812 81724 160812 81905 160813 81724 160813 82082 160813 82082 160814 81724 160814 80283 160814 82082 160815 80283 160815 80284 160815 80294 160816 81612 160816 81613 160816 80698 160817 80697 160817 80285 160817 80285 160818 80697 160818 80287 160818 80285 160819 80287 160819 80286 160819 80286 160820 80287 160820 80543 160820 80791 160821 80792 160821 80288 160821 80288 160822 80792 160822 80779 160822 80288 160823 80779 160823 80289 160823 80289 160824 80779 160824 80771 160824 80289 160825 80771 160825 80960 160825 80960 160826 80771 160826 80762 160826 80960 160827 80762 160827 80290 160827 80289 160828 80291 160828 80288 160828 80288 160829 80291 160829 80292 160829 80288 160830 80292 160830 82082 160830 82082 160831 80292 160831 80293 160831 82082 160832 80293 160832 81903 160832 81613 160833 81615 160833 80294 160833 80294 160834 81615 160834 81616 160834 80294 160835 81616 160835 80278 160835 80278 160836 81616 160836 81491 160836 80278 160837 81491 160837 80277 160837 80677 160838 80678 160838 80697 160838 80697 160839 80678 160839 80679 160839 80697 160840 80679 160840 80654 160840 80297 160841 80295 160841 80296 160841 80300 160842 80702 160842 80299 160842 80297 160843 80296 160843 80662 160843 80299 160844 80702 160844 80709 160844 80721 160845 80720 160845 80298 160845 80298 160846 80720 160846 80712 160846 80712 160847 80720 160847 80299 160847 80299 160848 80720 160848 80704 160848 80299 160849 80704 160849 80300 160849 80702 160850 80301 160850 80709 160850 80709 160851 80301 160851 80302 160851 80709 160852 80302 160852 80296 160852 80296 160853 80302 160853 80675 160853 80296 160854 80675 160854 80662 160854 81163 160855 80315 160855 80535 160855 80303 160856 81323 160856 80304 160856 80304 160857 81323 160857 80305 160857 80304 160858 80305 160858 81488 160858 81488 160859 80305 160859 80306 160859 80306 160860 80305 160860 80307 160860 80306 160861 80307 160861 81501 160861 80535 160862 80537 160862 81163 160862 81163 160863 80537 160863 80308 160863 81163 160864 80308 160864 81195 160864 81195 160865 80308 160865 80538 160865 81195 160866 80538 160866 81115 160866 81808 160867 81481 160867 81480 160867 81483 160868 81781 160868 80326 160868 80326 160869 81781 160869 80325 160869 80532 160870 80533 160870 80332 160870 81481 160871 81808 160871 81483 160871 81483 160872 81808 160872 80309 160872 81483 160873 80309 160873 81781 160873 80857 160874 80858 160874 80333 160874 80333 160875 80858 160875 80531 160875 80337 160876 80924 160876 80529 160876 81990 160877 82003 160877 80310 160877 80315 160878 81323 160878 80311 160878 80336 160879 80889 160879 80337 160879 80312 160880 80313 160880 80314 160880 80314 160881 80313 160881 80531 160881 80314 160882 80531 160882 80859 160882 80859 160883 80531 160883 80858 160883 80311 160884 81106 160884 80315 160884 80315 160885 81106 160885 80316 160885 80315 160886 80316 160886 80535 160886 80535 160887 80316 160887 81107 160887 80535 160888 81107 160888 80533 160888 80533 160889 81107 160889 80317 160889 80533 160890 80317 160890 80318 160890 80580 160891 80332 160891 80319 160891 80319 160892 80332 160892 80533 160892 80319 160893 80533 160893 80320 160893 80320 160894 80533 160894 80318 160894 80321 160895 80322 160895 81817 160895 81817 160896 80322 160896 81803 160896 81817 160897 81803 160897 80323 160897 80323 160898 81803 160898 81808 160898 80323 160899 81808 160899 80324 160899 80324 160900 81808 160900 81480 160900 80325 160901 81786 160901 80326 160901 80326 160902 81786 160902 80328 160902 80326 160903 80328 160903 80327 160903 80327 160904 80328 160904 80329 160904 80327 160905 80329 160905 80310 160905 80310 160906 80329 160906 80330 160906 80310 160907 80330 160907 81990 160907 82003 160908 82008 160908 80310 160908 80310 160909 82008 160909 82011 160909 80310 160910 82011 160910 80303 160910 80303 160911 82011 160911 80331 160911 80303 160912 80331 160912 81323 160912 81323 160913 80331 160913 82015 160913 81323 160914 82015 160914 80311 160914 80532 160915 80332 160915 80333 160915 80333 160916 80332 160916 80334 160916 80333 160917 80334 160917 80857 160917 80335 160918 80336 160918 80873 160918 80873 160919 80336 160919 80337 160919 80873 160920 80337 160920 80312 160920 80312 160921 80337 160921 80529 160921 80312 160922 80529 160922 80313 160922 80338 160923 80938 160923 80933 160923 80550 160924 80339 160924 80898 160924 80931 160925 80340 160925 80341 160925 80341 160926 80340 160926 80338 160926 80341 160927 80338 160927 80917 160927 80917 160928 80338 160928 80933 160928 80346 160929 80342 160929 80341 160929 80341 160930 80342 160930 80343 160930 80341 160931 80343 160931 80931 160931 80898 160932 80344 160932 80550 160932 80550 160933 80344 160933 80345 160933 80550 160934 80345 160934 80346 160934 80346 160935 80345 160935 80347 160935 80346 160936 80347 160936 80342 160936 80348 160937 80349 160937 80351 160937 80354 160938 80350 160938 80355 160938 80355 160939 80350 160939 80352 160939 80355 160940 80352 160940 80351 160940 80351 160941 80352 160941 80530 160941 80351 160942 80530 160942 80348 160942 80348 160943 80530 160943 80528 160943 80348 160944 80528 160944 80353 160944 80354 160945 80355 160945 80356 160945 80356 160946 80355 160946 77400 160946 80356 160947 77400 160947 80534 160947 80534 160948 77400 160948 80357 160948 80534 160949 80357 160949 80536 160949 80536 160950 80357 160950 80358 160950 80358 160951 80357 160951 77403 160951 80358 160952 77403 160952 80393 160952 80544 160953 80359 160953 80749 160953 77441 160954 80362 160954 80360 160954 80360 160955 80362 160955 80544 160955 80360 160956 80544 160956 80361 160956 80361 160957 80544 160957 80749 160957 80361 160958 80749 160958 80748 160958 77441 160959 77432 160959 80362 160959 80362 160960 77432 160960 80363 160960 80362 160961 80363 160961 80542 160961 80542 160962 80363 160962 80727 160962 80364 160963 80524 160963 80525 160963 80364 160964 80525 160964 80366 160964 80397 160965 80365 160965 80525 160965 80525 160966 80365 160966 77387 160966 80525 160967 77387 160967 80366 160967 80367 160968 77431 160968 77412 160968 80516 160969 80368 160969 77412 160969 77412 160970 80368 160970 80369 160970 77412 160971 80369 160971 80367 160971 80370 160972 80516 160972 80949 160972 80949 160973 80516 160973 77412 160973 80949 160974 77412 160974 80950 160974 80950 160975 77412 160975 80371 160975 80219 160976 80218 160976 80248 160976 80248 160977 80218 160977 77781 160977 77781 160978 80218 160978 80372 160978 77781 160979 80372 160979 77780 160979 77780 160980 80372 160980 80216 160980 77780 160981 80216 160981 80373 160981 80392 160982 80231 160982 80215 160982 80215 160983 80231 160983 80373 160983 80377 160984 81167 160984 80374 160984 80374 160985 81167 160985 77780 160985 80374 160986 77780 160986 80375 160986 80375 160987 77780 160987 80373 160987 80375 160988 80373 160988 80376 160988 80376 160989 80373 160989 80231 160989 80377 160990 80227 160990 81167 160990 81167 160991 80227 160991 80378 160991 81167 160992 80378 160992 80379 160992 80378 160993 80225 160993 80379 160993 80379 160994 80225 160994 80380 160994 80379 160995 80380 160995 80389 160995 80389 160996 80380 160996 80222 160996 80248 160997 80381 160997 80219 160997 80219 160998 80381 160998 80251 160998 80219 160999 80251 160999 80382 160999 80382 161000 80251 161000 80383 161000 80382 161001 80383 161001 80221 161001 80221 161002 80383 161002 80384 161002 80221 161003 80384 161003 80385 161003 80385 161004 80384 161004 80386 161004 80385 161005 80386 161005 80213 161005 80213 161006 80386 161006 80387 161006 80213 161007 80387 161007 80388 161007 80388 161008 80387 161008 80389 161008 80388 161009 80389 161009 80390 161009 80390 161010 80389 161010 80222 161010 80390 161011 80222 161011 80215 161011 80215 161012 80222 161012 80391 161012 80215 161013 80391 161013 80392 161013 80393 161014 77403 161014 77404 161014 77404 161015 81128 161015 80393 161015 80393 161016 81128 161016 80394 161016 80393 161017 80394 161017 80395 161017 77385 161018 80365 161018 80396 161018 80396 161019 80365 161019 80397 161019 80396 161020 80397 161020 81141 161020 81141 161021 80397 161021 81143 161021 80398 161022 80399 161022 77637 161022 77637 161023 80399 161023 83801 161023 83786 161024 77636 161024 83787 161024 83787 161025 77636 161025 80400 161025 83787 161026 80400 161026 83872 161026 83872 161027 80400 161027 81294 161027 81182 161028 83787 161028 80401 161028 80401 161029 83787 161029 83872 161029 80401 161030 83872 161030 80402 161030 80402 161031 83872 161031 83873 161031 77539 161032 80403 161032 77534 161032 77534 161033 80403 161033 80404 161033 77534 161034 80404 161034 77532 161034 77532 161035 80404 161035 81157 161035 80437 161036 83893 161036 83897 161036 83897 161037 83893 161037 83896 161037 81225 161038 80405 161038 83896 161038 83896 161039 80405 161039 77532 161039 83896 161040 77532 161040 83897 161040 83897 161041 77532 161041 81157 161041 80406 161042 83752 161042 77542 161042 77542 161043 83752 161043 80567 161043 77542 161044 80567 161044 77541 161044 80407 161045 80408 161045 80409 161045 80409 161046 80408 161046 81455 161046 81457 161047 81456 161047 80509 161047 80509 161048 81456 161048 80964 161048 80987 161049 80410 161049 80976 161049 80976 161050 80410 161050 80969 161050 80969 161051 80410 161051 80968 161051 80968 161052 80410 161052 77397 161052 80968 161053 77397 161053 80506 161053 81007 161054 80412 161054 81000 161054 81000 161055 80412 161055 77442 161055 81000 161056 77442 161056 80411 161056 80411 161057 77442 161057 80994 161057 80412 161058 81007 161058 77413 161058 77413 161059 81007 161059 80413 161059 77413 161060 80413 161060 80414 161060 80414 161061 80413 161061 80415 161061 80414 161062 80415 161062 80416 161062 80416 161063 80415 161063 81025 161063 80416 161064 81025 161064 77428 161064 77428 161065 81025 161065 81027 161065 77428 161066 81027 161066 77422 161066 77422 161067 81027 161067 81392 161067 77415 161068 81029 161068 80417 161068 80417 161069 81029 161069 80418 161069 80417 161070 80418 161070 80419 161070 80419 161071 80418 161071 80421 161071 80419 161072 80421 161072 80420 161072 80420 161073 80421 161073 80422 161073 80420 161074 80422 161074 80423 161074 80423 161075 80422 161075 81045 161075 80423 161076 81045 161076 77417 161076 77417 161077 81045 161077 81046 161077 81071 161078 80426 161078 77416 161078 81086 161079 80424 161079 81082 161079 81082 161080 80424 161080 77416 161080 81082 161081 77416 161081 80425 161081 80425 161082 77416 161082 80426 161082 77417 161083 81046 161083 81064 161083 81066 161084 81051 161084 81050 161084 81064 161085 81066 161085 77417 161085 77417 161086 81066 161086 81050 161086 77417 161087 81050 161087 77416 161087 77416 161088 81050 161088 80427 161088 77416 161089 80427 161089 81071 161089 78225 161090 77643 161090 3420 161090 3420 161091 77643 161091 80428 161091 3420 161092 80428 161092 80429 161092 80429 161093 80428 161093 80430 161093 80429 161094 80430 161094 3090 161094 3090 161095 80430 161095 80254 161095 80431 161096 81170 161096 81313 161096 77768 161097 77379 161097 77392 161097 77768 161098 77392 161098 80432 161098 80432 161099 77392 161099 81311 161099 81311 161100 77392 161100 77394 161100 81311 161101 77394 161101 80433 161101 80433 161102 77394 161102 80434 161102 80433 161103 80434 161103 81317 161103 81317 161104 80434 161104 80435 161104 81317 161105 80435 161105 80436 161105 80436 161106 80435 161106 77371 161106 80436 161107 77371 161107 81313 161107 81313 161108 77371 161108 77421 161108 81313 161109 77421 161109 80431 161109 83893 161110 80437 161110 80438 161110 80438 161111 80437 161111 80444 161111 81198 161112 81229 161112 81231 161112 81216 161113 80439 161113 80446 161113 80446 161114 80439 161114 81218 161114 80446 161115 81218 161115 80440 161115 80441 161116 81190 161116 81185 161116 81185 161117 81190 161117 80442 161117 81185 161118 80442 161118 80438 161118 80438 161119 80442 161119 81198 161119 80438 161120 81198 161120 80443 161120 80443 161121 81198 161121 81231 161121 80443 161122 81231 161122 81233 161122 81241 161123 81248 161123 77745 161123 77745 161124 81248 161124 80445 161124 77745 161125 80445 161125 80444 161125 80444 161126 80445 161126 80446 161126 80444 161127 80446 161127 80438 161127 80438 161128 80446 161128 80440 161128 80438 161129 80440 161129 81185 161129 80522 161130 81016 161130 81014 161130 81034 161131 80447 161131 80448 161131 80824 161132 80568 161132 80448 161132 80448 161133 80568 161133 81035 161133 80448 161134 81035 161134 81034 161134 80461 161135 81565 161135 80452 161135 80460 161136 80454 161136 80464 161136 80523 161137 80522 161137 80449 161137 80449 161138 80522 161138 80450 161138 81568 161139 80460 161139 81593 161139 81593 161140 80460 161140 80451 161140 81533 161141 81520 161141 80452 161141 80452 161142 81520 161142 81954 161142 80452 161143 81954 161143 80461 161143 80462 161144 80522 161144 80861 161144 80861 161145 80522 161145 80521 161145 80453 161146 80454 161146 80522 161146 80522 161147 80454 161147 80460 161147 80522 161148 80460 161148 81016 161148 81016 161149 80460 161149 81017 161149 81836 161150 80460 161150 80455 161150 80455 161151 80460 161151 80465 161151 80574 161152 80457 161152 80456 161152 80456 161153 80457 161153 80607 161153 80456 161154 80607 161154 81014 161154 81014 161155 80607 161155 80458 161155 81014 161156 80458 161156 80522 161156 80522 161157 80458 161157 80459 161157 80522 161158 80459 161158 80450 161158 81568 161159 81566 161159 80460 161159 80460 161160 81566 161160 81565 161160 80460 161161 81565 161161 81017 161161 81017 161162 81565 161162 80461 161162 80462 161163 80865 161163 80522 161163 80522 161164 80865 161164 80447 161164 80522 161165 80447 161165 80453 161165 80453 161166 80447 161166 81034 161166 81519 161167 80463 161167 81031 161167 81031 161168 80463 161168 81793 161168 81031 161169 81793 161169 80464 161169 80464 161170 81793 161170 81791 161170 80464 161171 81791 161171 80460 161171 80460 161172 81791 161172 81789 161172 80460 161173 81789 161173 80465 161173 80830 161174 80823 161174 80466 161174 80467 161175 80819 161175 80877 161175 80877 161176 80819 161176 80468 161176 80877 161177 80468 161177 80830 161177 80830 161178 80466 161178 80877 161178 80877 161179 80466 161179 80546 161179 80877 161180 80546 161180 80545 161180 80600 161181 80645 161181 80469 161181 80600 161182 80469 161182 80606 161182 80587 161183 80606 161183 80470 161183 80470 161184 80606 161184 80469 161184 80470 161185 80469 161185 80588 161185 80588 161186 80469 161186 80660 161186 80588 161187 80660 161187 80471 161187 80472 161188 80484 161188 77537 161188 77537 161189 80484 161189 80473 161189 77537 161190 80473 161190 80474 161190 80474 161191 80473 161191 80475 161191 80474 161192 80475 161192 77538 161192 77538 161193 80475 161193 80477 161193 77538 161194 80477 161194 80476 161194 80476 161195 80477 161195 80478 161195 80476 161196 80478 161196 80479 161196 80479 161197 80478 161197 80480 161197 80479 161198 80480 161198 77540 161198 77540 161199 80480 161199 77849 161199 77540 161200 77849 161200 80481 161200 80481 161201 77849 161201 77848 161201 80481 161202 77848 161202 80482 161202 80482 161203 77848 161203 77854 161203 80482 161204 77854 161204 77535 161204 77535 161205 77854 161205 77853 161205 77535 161206 77853 161206 77536 161206 77536 161207 77853 161207 77852 161207 77536 161208 77852 161208 80483 161208 80483 161209 77852 161209 77851 161209 80483 161210 77851 161210 80472 161210 80472 161211 77851 161211 80484 161211 80499 161212 80485 161212 80486 161212 80486 161213 80485 161213 80487 161213 80486 161214 80487 161214 80488 161214 80488 161215 80487 161215 77868 161215 80488 161216 77868 161216 80489 161216 80489 161217 77868 161217 77866 161217 80489 161218 77866 161218 77448 161218 77448 161219 77866 161219 80490 161219 77448 161220 80490 161220 77449 161220 77449 161221 80490 161221 80492 161221 77449 161222 80492 161222 80491 161222 80491 161223 80492 161223 77860 161223 80491 161224 77860 161224 77618 161224 77618 161225 77860 161225 80493 161225 77618 161226 80493 161226 80494 161226 80494 161227 80493 161227 77861 161227 80494 161228 77861 161228 77473 161228 77473 161229 77861 161229 80495 161229 77473 161230 80495 161230 80496 161230 80496 161231 80495 161231 77862 161231 80496 161232 77862 161232 80497 161232 80497 161233 77862 161233 80498 161233 80497 161234 80498 161234 80499 161234 80499 161235 80498 161235 80485 161235 80500 161236 80577 161236 80811 161236 80811 161237 80577 161237 80501 161237 80811 161238 80501 161238 80569 161238 80569 161239 80501 161239 80571 161239 80576 161240 80995 161240 80982 161240 80503 161241 80583 161241 80502 161241 80576 161242 80982 161242 80502 161242 80502 161243 80982 161243 80981 161243 80502 161244 80981 161244 80503 161244 80424 161245 81086 161245 77401 161245 77401 161246 81086 161246 81089 161246 77401 161247 81089 161247 77399 161247 77399 161248 81089 161248 81096 161248 77442 161249 80410 161249 80987 161249 80993 161250 80994 161250 80999 161250 80999 161251 80994 161251 77442 161251 80999 161252 77442 161252 80989 161252 80989 161253 77442 161253 80987 161253 80408 161254 80407 161254 77390 161254 80408 161255 77390 161255 81099 161255 81099 161256 77390 161256 80504 161256 81099 161257 80504 161257 81100 161257 81100 161258 80504 161258 80505 161258 81100 161259 80505 161259 81101 161259 81101 161260 80505 161260 77398 161260 81101 161261 77398 161261 81103 161261 80506 161262 77397 161262 80507 161262 80506 161263 80507 161263 80955 161263 80955 161264 80507 161264 77377 161264 80955 161265 77377 161265 80954 161265 80954 161266 77377 161266 80508 161266 80954 161267 80508 161267 80963 161267 80963 161268 80508 161268 80509 161268 80963 161269 80509 161269 80964 161269 80913 161270 80510 161270 80511 161270 80913 161271 80511 161271 80910 161271 80511 161272 80671 161272 80689 161272 80910 161273 80511 161273 80512 161273 80512 161274 80511 161274 80689 161274 80512 161275 80689 161275 80517 161275 80513 161276 80514 161276 80515 161276 80515 161277 80514 161277 80910 161277 80515 161278 80910 161278 80512 161278 80370 161279 80513 161279 80516 161279 80516 161280 80513 161280 80515 161280 80516 161281 80515 161281 80368 161281 80368 161282 80515 161282 80705 161282 80705 161283 80515 161283 80699 161283 80699 161284 80515 161284 80512 161284 80699 161285 80512 161285 80517 161285 80521 161286 80522 161286 80518 161286 80510 161287 80519 161287 80518 161287 80518 161288 80519 161288 80520 161288 80518 161289 80520 161289 80521 161289 80667 161290 80671 161290 80518 161290 80518 161291 80671 161291 80511 161291 80518 161292 80511 161292 80510 161292 80667 161293 80518 161293 80666 161293 80666 161294 80518 161294 80522 161294 80666 161295 80522 161295 80523 161295 80802 161296 80791 161296 80267 161296 80802 161297 80267 161297 80524 161297 80524 161298 80267 161298 80269 161298 80524 161299 80269 161299 80525 161299 80525 161300 80269 161300 80270 161300 80525 161301 80270 161301 80397 161301 80270 161302 80526 161302 80397 161302 80397 161303 80526 161303 81135 161303 81135 161304 81137 161304 80397 161304 80397 161305 81137 161305 81138 161305 80397 161306 81138 161306 81143 161306 80527 161307 80353 161307 80528 161307 80529 161308 80924 161308 80527 161308 80527 161309 80528 161309 80529 161309 80529 161310 80528 161310 80530 161310 80529 161311 80530 161311 80313 161311 80313 161312 80530 161312 80352 161312 80313 161313 80352 161313 80531 161313 80531 161314 80352 161314 80350 161314 80531 161315 80350 161315 80333 161315 80333 161316 80350 161316 80354 161316 80333 161317 80354 161317 80532 161317 80532 161318 80354 161318 80356 161318 80532 161319 80356 161319 80533 161319 80533 161320 80356 161320 80534 161320 80533 161321 80534 161321 80535 161321 80535 161322 80534 161322 80536 161322 80535 161323 80536 161323 80537 161323 80537 161324 80536 161324 80358 161324 80537 161325 80358 161325 80308 161325 80308 161326 80358 161326 80393 161326 80308 161327 80393 161327 80538 161327 80393 161328 80395 161328 80540 161328 81115 161329 80538 161329 81113 161329 81113 161330 80538 161330 80393 161330 81113 161331 80393 161331 80539 161331 80539 161332 80393 161332 80540 161332 80541 161333 80698 161333 80285 161333 80543 161334 80757 161334 80751 161334 80541 161335 80285 161335 80727 161335 80727 161336 80285 161336 80542 161336 80542 161337 80285 161337 80286 161337 80542 161338 80286 161338 80362 161338 80362 161339 80286 161339 80543 161339 80362 161340 80543 161340 80544 161340 80544 161341 80543 161341 80751 161341 80544 161342 80751 161342 80359 161342 80545 161343 80546 161343 80547 161343 80547 161344 80546 161344 80869 161344 80547 161345 80869 161345 80548 161345 80548 161346 80869 161346 80549 161346 80548 161347 80549 161347 80895 161347 80895 161348 80549 161348 80872 161348 80895 161349 80872 161349 80550 161349 80550 161350 80872 161350 80339 161350 80296 161351 80295 161351 80551 161351 80551 161352 80295 161352 80552 161352 80551 161353 80552 161353 80686 161353 80686 161354 80552 161354 80553 161354 80686 161355 80553 161355 80554 161355 80554 161356 80553 161356 80555 161356 80554 161357 80555 161357 80660 161357 80660 161358 80555 161358 80471 161358 80405 161359 81225 161359 81224 161359 81118 161360 80556 161360 80405 161360 80405 161361 80556 161361 80557 161361 80405 161362 80557 161362 81123 161362 80405 161363 81224 161363 81118 161363 81118 161364 81224 161364 81222 161364 81118 161365 81222 161365 80558 161365 80558 161366 81222 161366 80560 161366 80558 161367 80560 161367 80559 161367 81195 161368 81115 161368 80560 161368 80560 161369 81115 161369 80561 161369 80560 161370 80561 161370 80559 161370 80400 161371 77386 161371 81147 161371 80565 161372 81294 161372 80400 161372 80526 161373 81302 161373 81140 161373 81140 161374 81302 161374 80562 161374 81140 161375 80562 161375 80563 161375 80563 161376 80562 161376 81288 161376 80563 161377 81288 161377 80564 161377 80564 161378 81288 161378 80565 161378 80564 161379 80565 161379 80566 161379 80566 161380 80565 161380 80400 161380 80566 161381 80400 161381 81148 161381 81148 161382 80400 161382 81147 161382 80406 161383 77544 161383 83752 161383 83752 161384 77544 161384 83766 161384 77541 161385 80567 161385 77539 161385 77539 161386 80567 161386 80403 161386 83801 161387 77737 161387 77637 161387 77637 161388 77737 161388 77735 161388 80399 161389 80398 161389 83786 161389 83786 161390 80398 161390 77636 161390 80753 161391 77444 161391 80752 161391 80752 161392 77444 161392 77445 161392 80568 161393 80824 161393 80821 161393 80568 161394 80821 161394 81057 161394 81057 161395 80821 161395 80827 161395 81057 161396 80827 161396 80570 161396 80570 161397 80827 161397 80569 161397 80570 161398 80569 161398 80571 161398 80585 161399 80594 161399 80572 161399 80572 161400 80594 161400 80573 161400 80573 161401 80594 161401 80457 161401 80573 161402 80457 161402 80574 161402 80572 161403 80575 161403 80585 161403 80585 161404 80575 161404 80995 161404 80585 161405 80995 161405 80576 161405 80577 161406 80500 161406 80837 161406 80577 161407 80837 161407 80578 161407 80578 161408 80837 161408 80579 161408 80578 161409 80579 161409 81076 161409 81076 161410 80579 161410 80580 161410 80580 161411 80579 161411 80835 161411 80580 161412 80835 161412 80332 161412 80612 161413 80582 161413 80581 161413 80581 161414 80582 161414 80279 161414 80581 161415 80279 161415 80631 161415 80612 161416 80611 161416 80582 161416 80582 161417 80611 161417 80583 161417 80582 161418 80583 161418 80503 161418 80592 161419 80584 161419 80591 161419 80593 161420 80585 161420 80576 161420 80605 161421 80606 161421 80587 161421 80605 161422 80584 161422 80602 161422 80602 161423 80584 161423 80592 161423 80602 161424 80592 161424 80601 161424 80594 161425 80585 161425 80586 161425 80586 161426 80585 161426 80593 161426 80586 161427 80593 161427 80596 161427 80605 161428 80587 161428 80584 161428 80584 161429 80587 161429 80470 161429 80584 161430 80470 161430 80591 161430 80591 161431 80470 161431 80588 161431 80591 161432 80588 161432 80589 161432 80589 161433 80590 161433 80591 161433 80591 161434 80590 161434 80596 161434 80591 161435 80596 161435 80592 161435 80592 161436 80596 161436 80593 161436 80592 161437 80593 161437 80601 161437 80601 161438 80593 161438 80576 161438 80457 161439 80594 161439 80595 161439 80595 161440 80594 161440 80586 161440 80595 161441 80586 161441 80608 161441 80608 161442 80586 161442 80596 161442 80608 161443 80596 161443 80609 161443 80609 161444 80596 161444 80590 161444 80502 161445 80583 161445 80603 161445 80603 161446 80583 161446 80597 161446 80603 161447 80597 161447 80604 161447 80604 161448 80597 161448 80598 161448 80604 161449 80598 161449 80599 161449 80599 161450 80598 161450 80616 161450 80599 161451 80616 161451 80600 161451 80600 161452 80616 161452 80645 161452 80576 161453 80502 161453 80601 161453 80601 161454 80502 161454 80603 161454 80601 161455 80603 161455 80602 161455 80602 161456 80603 161456 80604 161456 80602 161457 80604 161457 80605 161457 80605 161458 80604 161458 80599 161458 80605 161459 80599 161459 80606 161459 80606 161460 80599 161460 80600 161460 80607 161461 80457 161461 80595 161461 80607 161462 80595 161462 80625 161462 80595 161463 80608 161463 80625 161463 80625 161464 80608 161464 80609 161464 80625 161465 80609 161465 80610 161465 80588 161466 80471 161466 80589 161466 80589 161467 80471 161467 80610 161467 80589 161468 80610 161468 80590 161468 80590 161469 80610 161469 80609 161469 80614 161470 80611 161470 80612 161470 80632 161471 80613 161471 80633 161471 80629 161472 80619 161472 80614 161472 80645 161473 80616 161473 80615 161473 80615 161474 80616 161474 80598 161474 80615 161475 80598 161475 80617 161475 80631 161476 80618 161476 80581 161476 80581 161477 80618 161477 80633 161477 80581 161478 80633 161478 80612 161478 80612 161479 80633 161479 80613 161479 80612 161480 80613 161480 80614 161480 80614 161481 80613 161481 80632 161481 80614 161482 80632 161482 80629 161482 80583 161483 80611 161483 80597 161483 80597 161484 80611 161484 80614 161484 80597 161485 80614 161485 80598 161485 80598 161486 80614 161486 80619 161486 80598 161487 80619 161487 80617 161487 80617 161488 80619 161488 80629 161488 80627 161489 80621 161489 80622 161489 80653 161490 80449 161490 80450 161490 80653 161491 80450 161491 80620 161491 80620 161492 80450 161492 80621 161492 80621 161493 80450 161493 80459 161493 80621 161494 80459 161494 80622 161494 80622 161495 80459 161495 80458 161495 80622 161496 80458 161496 80623 161496 80623 161497 80458 161497 80607 161497 80623 161498 80607 161498 80625 161498 80627 161499 80622 161499 80624 161499 80624 161500 80622 161500 80623 161500 80624 161501 80623 161501 80628 161501 80628 161502 80623 161502 80625 161502 80628 161503 80625 161503 80610 161503 80295 161504 80649 161504 80627 161504 80627 161505 80649 161505 80626 161505 80627 161506 80626 161506 80621 161506 80621 161507 80626 161507 80651 161507 80621 161508 80651 161508 80620 161508 80295 161509 80627 161509 80552 161509 80552 161510 80627 161510 80624 161510 80552 161511 80624 161511 80553 161511 80553 161512 80624 161512 80628 161512 80553 161513 80628 161513 80555 161513 80555 161514 80628 161514 80610 161514 80555 161515 80610 161515 80471 161515 80617 161516 80629 161516 80634 161516 80630 161517 80618 161517 80631 161517 80644 161518 80630 161518 80631 161518 80618 161519 80630 161519 80635 161519 80632 161520 80633 161520 80635 161520 80635 161521 80633 161521 80618 161521 80629 161522 80632 161522 80634 161522 80634 161523 80632 161523 80635 161523 80634 161524 80635 161524 80642 161524 80642 161525 80635 161525 80630 161525 80272 161526 80636 161526 80637 161526 80637 161527 80636 161527 80638 161527 80637 161528 80638 161528 80640 161528 80639 161529 80272 161529 80643 161529 80643 161530 80272 161530 80637 161530 80643 161531 80637 161531 80641 161531 80641 161532 80637 161532 80640 161532 80641 161533 80640 161533 80646 161533 80615 161534 80617 161534 80646 161534 80646 161535 80617 161535 80634 161535 80646 161536 80634 161536 80641 161536 80641 161537 80634 161537 80642 161537 80641 161538 80642 161538 80643 161538 80643 161539 80642 161539 80630 161539 80643 161540 80630 161540 80639 161540 80639 161541 80630 161541 80644 161541 80645 161542 80615 161542 80658 161542 80658 161543 80615 161543 80646 161543 80658 161544 80646 161544 80647 161544 80647 161545 80646 161545 80640 161545 80647 161546 80640 161546 80648 161546 80648 161547 80640 161547 80638 161547 80648 161548 80638 161548 80655 161548 80655 161549 80638 161549 80636 161549 80297 161550 80650 161550 80295 161550 80295 161551 80650 161551 80649 161551 80649 161552 80650 161552 80626 161552 80626 161553 80650 161553 80663 161553 80626 161554 80663 161554 80651 161554 80651 161555 80663 161555 80664 161555 80651 161556 80664 161556 80620 161556 80620 161557 80664 161557 80665 161557 80620 161558 80665 161558 80653 161558 80665 161559 80652 161559 80653 161559 80653 161560 80652 161560 80523 161560 80653 161561 80523 161561 80449 161561 80287 161562 80654 161562 80676 161562 80655 161563 80287 161563 80656 161563 80655 161564 80656 161564 80648 161564 80648 161565 80656 161565 80657 161565 80648 161566 80657 161566 80647 161566 80647 161567 80657 161567 80661 161567 80647 161568 80661 161568 80658 161568 80658 161569 80661 161569 80469 161569 80658 161570 80469 161570 80645 161570 80287 161571 80676 161571 80656 161571 80656 161572 80676 161572 80683 161572 80656 161573 80683 161573 80657 161573 80657 161574 80683 161574 80659 161574 80657 161575 80659 161575 80661 161575 80661 161576 80659 161576 80660 161576 80661 161577 80660 161577 80469 161577 80297 161578 80662 161578 80650 161578 80650 161579 80662 161579 80670 161579 80650 161580 80670 161580 80663 161580 80663 161581 80670 161581 80664 161581 80664 161582 80670 161582 80668 161582 80664 161583 80668 161583 80665 161583 80665 161584 80668 161584 80652 161584 80652 161585 80668 161585 80666 161585 80652 161586 80666 161586 80523 161586 80667 161587 80666 161587 80674 161587 80674 161588 80666 161588 80668 161588 80674 161589 80668 161589 80669 161589 80669 161590 80668 161590 80670 161590 80669 161591 80670 161591 80675 161591 80675 161592 80670 161592 80662 161592 80671 161593 80667 161593 80672 161593 80672 161594 80667 161594 80674 161594 80672 161595 80674 161595 80673 161595 80673 161596 80674 161596 80669 161596 80673 161597 80669 161597 80302 161597 80302 161598 80669 161598 80675 161598 80683 161599 80676 161599 80680 161599 80697 161600 80694 161600 80677 161600 80677 161601 80694 161601 80681 161601 80677 161602 80681 161602 80678 161602 80678 161603 80681 161603 80682 161603 80678 161604 80682 161604 80679 161604 80679 161605 80682 161605 80680 161605 80679 161606 80680 161606 80654 161606 80654 161607 80680 161607 80676 161607 80694 161608 80693 161608 80681 161608 80681 161609 80693 161609 80684 161609 80681 161610 80684 161610 80682 161610 80682 161611 80684 161611 80685 161611 80682 161612 80685 161612 80680 161612 80680 161613 80685 161613 80687 161613 80680 161614 80687 161614 80683 161614 80683 161615 80687 161615 80659 161615 80693 161616 80296 161616 80684 161616 80684 161617 80296 161617 80551 161617 80684 161618 80551 161618 80685 161618 80685 161619 80551 161619 80686 161619 80685 161620 80686 161620 80687 161620 80687 161621 80686 161621 80554 161621 80687 161622 80554 161622 80659 161622 80659 161623 80554 161623 80660 161623 80689 161624 80671 161624 80688 161624 80688 161625 80671 161625 80672 161625 80688 161626 80672 161626 80691 161626 80691 161627 80672 161627 80673 161627 80691 161628 80673 161628 80301 161628 80301 161629 80673 161629 80302 161629 80517 161630 80689 161630 80701 161630 80701 161631 80689 161631 80688 161631 80701 161632 80688 161632 80690 161632 80690 161633 80688 161633 80691 161633 80690 161634 80691 161634 80702 161634 80702 161635 80691 161635 80301 161635 80709 161636 80296 161636 80692 161636 80692 161637 80296 161637 80693 161637 80692 161638 80693 161638 80710 161638 80710 161639 80693 161639 80711 161639 80711 161640 80693 161640 80694 161640 80711 161641 80694 161641 80695 161641 80695 161642 80694 161642 80696 161642 80696 161643 80694 161643 80697 161643 80696 161644 80697 161644 80698 161644 80699 161645 80517 161645 80703 161645 80703 161646 80517 161646 80701 161646 80703 161647 80701 161647 80700 161647 80700 161648 80701 161648 80690 161648 80700 161649 80690 161649 80300 161649 80300 161650 80690 161650 80702 161650 80705 161651 80699 161651 80706 161651 80706 161652 80699 161652 80703 161652 80706 161653 80703 161653 80708 161653 80708 161654 80703 161654 80700 161654 80708 161655 80700 161655 80704 161655 80704 161656 80700 161656 80300 161656 80368 161657 80705 161657 80718 161657 80718 161658 80705 161658 80706 161658 80718 161659 80706 161659 80707 161659 80707 161660 80706 161660 80708 161660 80707 161661 80708 161661 80720 161661 80720 161662 80708 161662 80704 161662 80713 161663 80299 161663 80709 161663 80716 161664 80696 161664 80541 161664 80541 161665 80696 161665 80698 161665 80709 161666 80692 161666 80713 161666 80713 161667 80692 161667 80710 161667 80713 161668 80710 161668 80714 161668 80714 161669 80710 161669 80711 161669 80714 161670 80711 161670 80716 161670 80716 161671 80711 161671 80695 161671 80716 161672 80695 161672 80696 161672 80712 161673 80299 161673 80729 161673 80729 161674 80299 161674 80713 161674 80729 161675 80713 161675 80728 161675 80728 161676 80713 161676 80714 161676 80728 161677 80714 161677 80715 161677 80715 161678 80714 161678 80716 161678 80715 161679 80716 161679 80727 161679 80727 161680 80716 161680 80541 161680 80369 161681 80368 161681 80718 161681 80369 161682 80718 161682 80717 161682 80717 161683 80718 161683 80707 161683 80717 161684 80707 161684 80719 161684 80719 161685 80707 161685 80720 161685 80719 161686 80720 161686 80721 161686 80721 161687 80298 161687 80722 161687 80722 161688 80298 161688 80724 161688 80725 161689 80733 161689 80723 161689 80723 161690 80733 161690 80741 161690 80723 161691 80741 161691 80724 161691 80724 161692 80741 161692 80740 161692 80724 161693 80740 161693 80722 161693 80363 161694 77432 161694 80725 161694 80725 161695 77432 161695 77406 161695 77406 161696 77414 161696 80725 161696 80725 161697 77414 161697 80726 161697 80725 161698 80726 161698 80733 161698 80727 161699 80363 161699 80715 161699 80715 161700 80363 161700 80725 161700 80715 161701 80725 161701 80728 161701 80728 161702 80725 161702 80723 161702 80728 161703 80723 161703 80729 161703 80729 161704 80723 161704 80724 161704 80729 161705 80724 161705 80712 161705 80712 161706 80724 161706 80298 161706 80730 161707 80731 161707 80737 161707 80731 161708 80732 161708 80737 161708 80737 161709 80732 161709 77431 161709 80737 161710 77431 161710 80736 161710 80730 161711 80739 161711 80734 161711 80734 161712 80739 161712 80733 161712 80734 161713 80733 161713 80735 161713 80735 161714 80733 161714 80726 161714 80719 161715 80721 161715 80722 161715 77431 161716 80367 161716 80736 161716 80736 161717 80367 161717 80369 161717 80736 161718 80369 161718 80717 161718 80730 161719 80737 161719 80739 161719 80739 161720 80737 161720 80736 161720 80739 161721 80736 161721 80738 161721 80738 161722 80736 161722 80717 161722 80738 161723 80717 161723 80719 161723 80719 161724 80722 161724 80738 161724 80738 161725 80722 161725 80740 161725 80738 161726 80740 161726 80739 161726 80739 161727 80740 161727 80741 161727 80739 161728 80741 161728 80733 161728 80742 161729 80745 161729 80743 161729 80743 161730 80745 161730 77445 161730 77445 161731 80745 161731 80744 161731 77445 161732 80744 161732 80752 161732 77443 161733 80747 161733 80742 161733 80742 161734 80747 161734 80750 161734 80742 161735 80750 161735 80745 161735 80745 161736 80750 161736 80746 161736 80745 161737 80746 161737 80744 161737 80360 161738 80361 161738 77443 161738 77443 161739 80361 161739 80748 161739 77443 161740 80748 161740 80747 161740 80747 161741 80748 161741 80749 161741 80747 161742 80749 161742 80750 161742 80750 161743 80749 161743 80359 161743 80750 161744 80359 161744 80746 161744 80359 161745 80751 161745 80746 161745 80746 161746 80751 161746 80756 161746 80746 161747 80756 161747 80744 161747 80744 161748 80756 161748 80754 161748 80744 161749 80754 161749 80752 161749 80752 161750 80754 161750 80753 161750 80257 161751 80753 161751 80755 161751 80755 161752 80753 161752 80754 161752 80755 161753 80754 161753 80759 161753 80759 161754 80754 161754 80756 161754 80759 161755 80756 161755 80757 161755 80757 161756 80756 161756 80751 161756 80757 161757 80281 161757 80758 161757 80757 161758 80758 161758 80759 161758 80759 161759 80758 161759 80760 161759 80759 161760 80760 161760 80755 161760 80755 161761 80760 161761 80761 161761 80755 161762 80761 161762 80257 161762 80773 161763 80775 161763 80763 161763 80775 161764 80265 161764 80263 161764 80762 161765 80772 161765 80767 161765 80767 161766 80772 161766 80773 161766 80775 161767 80263 161767 80763 161767 80763 161768 80263 161768 80765 161768 80763 161769 80765 161769 80764 161769 80764 161770 80765 161770 80260 161770 80764 161771 80260 161771 80766 161771 80766 161772 80260 161772 80761 161772 80766 161773 80761 161773 80760 161773 80773 161774 80763 161774 80767 161774 80767 161775 80763 161775 80764 161775 80767 161776 80764 161776 80768 161776 80768 161777 80764 161777 80766 161777 80768 161778 80766 161778 80769 161778 80769 161779 80766 161779 80760 161779 80769 161780 80760 161780 80758 161780 80762 161781 80767 161781 80290 161781 80290 161782 80767 161782 80768 161782 80290 161783 80768 161783 80770 161783 80770 161784 80768 161784 80769 161784 80770 161785 80769 161785 80280 161785 80280 161786 80769 161786 80758 161786 80280 161787 80758 161787 80281 161787 80762 161788 80771 161788 80785 161788 80762 161789 80785 161789 80772 161789 80772 161790 80785 161790 80784 161790 80772 161791 80784 161791 80773 161791 80773 161792 80784 161792 80774 161792 80773 161793 80774 161793 80775 161793 80775 161794 80774 161794 80782 161794 80775 161795 80782 161795 80265 161795 80787 161796 80256 161796 80776 161796 80776 161797 80256 161797 80783 161797 80776 161798 80783 161798 80788 161798 80788 161799 80783 161799 80778 161799 80780 161800 80790 161800 80778 161800 80778 161801 80790 161801 80777 161801 80778 161802 80777 161802 80788 161802 80779 161803 80792 161803 80780 161803 80780 161804 80792 161804 80781 161804 80780 161805 80781 161805 80790 161805 80256 161806 80782 161806 80783 161806 80783 161807 80782 161807 80774 161807 80783 161808 80774 161808 80778 161808 80778 161809 80774 161809 80784 161809 80778 161810 80784 161810 80780 161810 80780 161811 80784 161811 80785 161811 80780 161812 80785 161812 80779 161812 80779 161813 80785 161813 80771 161813 80786 161814 80787 161814 80798 161814 80798 161815 80787 161815 80776 161815 80798 161816 80776 161816 80799 161816 80799 161817 80776 161817 80788 161817 80799 161818 80788 161818 80804 161818 80804 161819 80788 161819 80777 161819 80804 161820 80777 161820 80789 161820 80789 161821 80777 161821 80790 161821 80789 161822 80790 161822 80803 161822 80803 161823 80790 161823 80781 161823 80803 161824 80781 161824 80791 161824 80791 161825 80781 161825 80792 161825 80806 161826 80793 161826 80796 161826 80801 161827 80806 161827 80797 161827 80810 161828 80800 161828 80794 161828 80802 161829 80524 161829 80794 161829 80794 161830 80524 161830 80795 161830 80794 161831 80795 161831 80810 161831 80806 161832 80796 161832 80797 161832 80797 161833 80796 161833 80786 161833 80797 161834 80786 161834 80798 161834 80798 161835 80799 161835 80797 161835 80797 161836 80799 161836 80800 161836 80797 161837 80800 161837 80801 161837 80801 161838 80800 161838 80810 161838 80791 161839 80802 161839 80803 161839 80803 161840 80802 161840 80794 161840 80803 161841 80794 161841 80789 161841 80789 161842 80794 161842 80800 161842 80789 161843 80800 161843 80804 161843 80804 161844 80800 161844 80799 161844 80805 161845 80793 161845 80806 161845 80366 161846 77388 161846 80364 161846 80364 161847 77388 161847 77376 161847 80364 161848 77376 161848 80809 161848 80809 161849 77376 161849 77375 161849 80809 161850 77375 161850 80801 161850 80801 161851 77375 161851 80807 161851 80801 161852 80807 161852 80806 161852 80806 161853 80807 161853 80808 161853 80806 161854 80808 161854 80805 161854 80524 161855 80364 161855 80795 161855 80795 161856 80364 161856 80809 161856 80795 161857 80809 161857 80810 161857 80810 161858 80809 161858 80801 161858 80811 161859 80569 161859 80816 161859 80816 161860 80569 161860 80812 161860 80816 161861 80812 161861 80813 161861 80813 161862 80812 161862 80832 161862 80813 161863 80832 161863 80818 161863 80818 161864 80832 161864 80814 161864 80818 161865 80814 161865 80819 161865 80819 161866 80814 161866 80468 161866 80500 161867 80811 161867 80815 161867 80815 161868 80811 161868 80816 161868 80815 161869 80816 161869 80817 161869 80817 161870 80816 161870 80813 161870 80817 161871 80813 161871 80840 161871 80840 161872 80813 161872 80818 161872 80840 161873 80818 161873 80467 161873 80467 161874 80818 161874 80819 161874 80820 161875 80821 161875 80824 161875 80466 161876 80823 161876 80822 161876 80822 161877 80823 161877 80831 161877 80822 161878 80831 161878 80843 161878 80843 161879 80831 161879 80826 161879 80824 161880 80841 161880 80820 161880 80820 161881 80841 161881 80825 161881 80820 161882 80825 161882 80826 161882 80826 161883 80825 161883 80844 161883 80826 161884 80844 161884 80843 161884 80827 161885 80821 161885 80828 161885 80828 161886 80821 161886 80820 161886 80828 161887 80820 161887 80829 161887 80829 161888 80820 161888 80826 161888 80829 161889 80826 161889 80833 161889 80833 161890 80826 161890 80831 161890 80833 161891 80831 161891 80830 161891 80830 161892 80831 161892 80823 161892 80569 161893 80827 161893 80812 161893 80812 161894 80827 161894 80828 161894 80812 161895 80828 161895 80832 161895 80832 161896 80828 161896 80829 161896 80832 161897 80829 161897 80814 161897 80814 161898 80829 161898 80833 161898 80814 161899 80833 161899 80468 161899 80468 161900 80833 161900 80830 161900 80847 161901 80839 161901 80848 161901 80834 161902 80838 161902 80846 161902 80838 161903 80834 161903 80579 161903 80579 161904 80834 161904 80845 161904 80579 161905 80845 161905 80835 161905 80835 161906 80845 161906 80856 161906 80835 161907 80856 161907 80332 161907 80839 161908 80847 161908 80836 161908 80847 161909 80846 161909 80836 161909 80836 161910 80846 161910 80838 161910 80836 161911 80838 161911 80837 161911 80837 161912 80838 161912 80579 161912 80837 161913 80500 161913 80836 161913 80836 161914 80500 161914 80815 161914 80836 161915 80815 161915 80839 161915 80839 161916 80815 161916 80817 161916 80839 161917 80817 161917 80848 161917 80848 161918 80817 161918 80840 161918 80848 161919 80840 161919 80467 161919 80842 161920 80825 161920 80448 161920 80448 161921 80825 161921 80841 161921 80448 161922 80841 161922 80824 161922 80860 161923 80546 161923 80466 161923 80466 161924 80822 161924 80860 161924 80860 161925 80822 161925 80843 161925 80860 161926 80843 161926 80842 161926 80842 161927 80843 161927 80844 161927 80842 161928 80844 161928 80825 161928 80880 161929 80879 161929 80851 161929 80852 161930 80855 161930 80845 161930 80845 161931 80855 161931 80856 161931 80845 161932 80834 161932 80852 161932 80852 161933 80834 161933 80846 161933 80852 161934 80846 161934 80850 161934 80850 161935 80846 161935 80847 161935 80847 161936 80848 161936 80850 161936 80850 161937 80848 161937 80467 161937 80850 161938 80467 161938 80849 161938 80849 161939 80880 161939 80850 161939 80850 161940 80880 161940 80851 161940 80850 161941 80851 161941 80852 161941 80852 161942 80851 161942 80853 161942 80852 161943 80853 161943 80855 161943 80855 161944 80853 161944 80854 161944 80855 161945 80854 161945 80856 161945 80856 161946 80854 161946 80334 161946 80856 161947 80334 161947 80332 161947 80334 161948 80854 161948 80857 161948 80857 161949 80854 161949 80853 161949 80857 161950 80853 161950 80858 161950 80858 161951 80853 161951 80851 161951 80858 161952 80851 161952 80859 161952 80859 161953 80851 161953 80879 161953 80859 161954 80879 161954 80314 161954 80546 161955 80860 161955 80870 161955 80860 161956 80842 161956 80864 161956 80462 161957 80861 161957 80885 161957 80885 161958 80862 161958 80462 161958 80462 161959 80862 161959 80863 161959 80462 161960 80863 161960 80865 161960 80865 161961 80863 161961 80864 161961 80865 161962 80864 161962 80447 161962 80447 161963 80864 161963 80842 161963 80447 161964 80842 161964 80448 161964 80860 161965 80864 161965 80870 161965 80870 161966 80864 161966 80863 161966 80870 161967 80863 161967 80871 161967 80871 161968 80863 161968 80862 161968 80871 161969 80862 161969 80866 161969 80885 161970 80883 161970 80862 161970 80862 161971 80883 161971 80882 161971 80862 161972 80882 161972 80866 161972 80866 161973 80882 161973 80867 161973 80866 161974 80867 161974 80868 161974 80546 161975 80870 161975 80869 161975 80869 161976 80870 161976 80871 161976 80869 161977 80871 161977 80549 161977 80549 161978 80871 161978 80866 161978 80549 161979 80866 161979 80872 161979 80872 161980 80866 161980 80868 161980 80872 161981 80868 161981 80339 161981 80312 161982 80314 161982 80879 161982 80873 161983 80312 161983 80878 161983 80873 161984 80878 161984 80874 161984 80874 161985 80878 161985 80881 161985 80874 161986 80881 161986 80890 161986 80890 161987 80881 161987 80875 161987 80890 161988 80875 161988 80876 161988 80876 161989 80875 161989 80877 161989 80876 161990 80877 161990 80545 161990 80312 161991 80879 161991 80878 161991 80878 161992 80879 161992 80880 161992 80878 161993 80880 161993 80881 161993 80881 161994 80880 161994 80849 161994 80881 161995 80849 161995 80875 161995 80875 161996 80849 161996 80467 161996 80875 161997 80467 161997 80877 161997 80339 161998 80868 161998 80898 161998 80898 161999 80868 161999 80899 161999 80899 162000 80868 162000 80901 162000 80901 162001 80868 162001 80867 162001 80901 162002 80867 162002 80903 162002 80903 162003 80867 162003 80882 162003 80903 162004 80882 162004 80904 162004 80904 162005 80882 162005 80883 162005 80904 162006 80883 162006 80884 162006 80883 162007 80885 162007 80884 162007 80884 162008 80885 162008 80861 162008 80884 162009 80861 162009 80521 162009 80890 162010 80876 162010 80893 162010 80886 162011 80909 162011 80891 162011 80873 162012 80874 162012 80335 162012 80335 162013 80874 162013 80887 162013 80335 162014 80887 162014 80336 162014 80336 162015 80887 162015 80888 162015 80336 162016 80888 162016 80889 162016 80889 162017 80888 162017 80891 162017 80889 162018 80891 162018 80337 162018 80337 162019 80891 162019 80909 162019 80874 162020 80890 162020 80887 162020 80887 162021 80890 162021 80893 162021 80887 162022 80893 162022 80888 162022 80888 162023 80893 162023 80892 162023 80888 162024 80892 162024 80891 162024 80891 162025 80892 162025 80894 162025 80891 162026 80894 162026 80886 162026 80886 162027 80894 162027 80906 162027 80876 162028 80545 162028 80893 162028 80893 162029 80545 162029 80547 162029 80893 162030 80547 162030 80892 162030 80892 162031 80547 162031 80548 162031 80892 162032 80548 162032 80894 162032 80894 162033 80548 162033 80895 162033 80894 162034 80895 162034 80906 162034 80906 162035 80895 162035 80550 162035 80896 162036 80915 162036 80900 162036 80344 162037 80900 162037 80345 162037 80345 162038 80900 162038 80915 162038 80345 162039 80915 162039 80347 162039 80902 162040 80905 162040 80897 162040 80898 162041 80899 162041 80344 162041 80344 162042 80899 162042 80902 162042 80344 162043 80902 162043 80900 162043 80900 162044 80902 162044 80897 162044 80900 162045 80897 162045 80896 162045 80896 162046 80897 162046 80510 162046 80899 162047 80901 162047 80902 162047 80902 162048 80901 162048 80903 162048 80902 162049 80903 162049 80905 162049 80905 162050 80903 162050 80904 162050 80905 162051 80904 162051 80884 162051 80510 162052 80897 162052 80519 162052 80519 162053 80897 162053 80905 162053 80519 162054 80905 162054 80520 162054 80520 162055 80905 162055 80884 162055 80520 162056 80884 162056 80521 162056 80550 162057 80346 162057 80907 162057 80550 162058 80907 162058 80906 162058 80906 162059 80907 162059 80922 162059 80906 162060 80922 162060 80886 162060 80886 162061 80922 162061 80908 162061 80886 162062 80908 162062 80909 162062 80909 162063 80908 162063 80924 162063 80909 162064 80924 162064 80337 162064 80913 162065 80910 162065 80914 162065 80914 162066 80910 162066 80911 162066 80914 162067 80911 162067 80916 162067 80916 162068 80911 162068 80912 162068 80916 162069 80912 162069 80342 162069 80342 162070 80912 162070 80343 162070 80510 162071 80913 162071 80896 162071 80896 162072 80913 162072 80914 162072 80896 162073 80914 162073 80915 162073 80915 162074 80914 162074 80916 162074 80915 162075 80916 162075 80347 162075 80347 162076 80916 162076 80342 162076 80341 162077 80917 162077 80918 162077 80918 162078 80917 162078 80934 162078 80918 162079 80934 162079 80923 162079 80923 162080 80934 162080 80919 162080 80923 162081 80919 162081 80920 162081 80920 162082 80919 162082 80921 162082 80920 162083 80921 162083 80527 162083 80527 162084 80921 162084 80353 162084 80346 162085 80341 162085 80907 162085 80907 162086 80341 162086 80918 162086 80907 162087 80918 162087 80922 162087 80922 162088 80918 162088 80923 162088 80922 162089 80923 162089 80908 162089 80908 162090 80923 162090 80920 162090 80908 162091 80920 162091 80924 162091 80924 162092 80920 162092 80527 162092 80513 162093 80370 162093 80929 162093 80929 162094 80370 162094 80925 162094 80929 162095 80925 162095 80926 162095 80926 162096 80925 162096 80927 162096 80926 162097 80927 162097 80340 162097 80340 162098 80927 162098 80338 162098 80514 162099 80513 162099 80928 162099 80928 162100 80513 162100 80929 162100 80928 162101 80929 162101 80930 162101 80930 162102 80929 162102 80926 162102 80930 162103 80926 162103 80931 162103 80931 162104 80926 162104 80340 162104 80910 162105 80514 162105 80911 162105 80911 162106 80514 162106 80928 162106 80911 162107 80928 162107 80912 162107 80912 162108 80928 162108 80930 162108 80912 162109 80930 162109 80343 162109 80343 162110 80930 162110 80931 162110 80349 162111 80348 162111 77418 162111 77418 162112 80348 162112 80937 162112 77418 162113 80937 162113 80940 162113 80940 162114 80937 162114 80932 162114 80932 162115 80937 162115 80936 162115 80932 162116 80936 162116 80941 162116 80941 162117 80936 162117 80935 162117 80941 162118 80935 162118 80944 162118 80944 162119 80935 162119 80933 162119 80944 162120 80933 162120 80938 162120 80917 162121 80933 162121 80934 162121 80934 162122 80933 162122 80935 162122 80934 162123 80935 162123 80919 162123 80919 162124 80935 162124 80936 162124 80919 162125 80936 162125 80921 162125 80921 162126 80936 162126 80937 162126 80921 162127 80937 162127 80353 162127 80353 162128 80937 162128 80348 162128 80938 162129 80338 162129 80927 162129 80938 162130 80927 162130 80951 162130 80951 162131 80927 162131 80925 162131 80951 162132 80925 162132 80939 162132 80939 162133 80925 162133 80370 162133 80939 162134 80370 162134 80949 162134 80940 162135 80932 162135 80943 162135 80943 162136 80932 162136 80941 162136 80943 162137 80941 162137 80945 162137 77410 162138 77409 162138 80945 162138 80945 162139 77409 162139 80942 162139 80945 162140 80942 162140 80943 162140 80941 162141 80944 162141 80945 162141 80945 162142 80944 162142 80946 162142 80945 162143 80946 162143 77410 162143 77410 162144 80946 162144 80947 162144 77410 162145 80947 162145 80948 162145 80948 162146 80947 162146 80950 162146 80948 162147 80950 162147 80371 162147 80949 162148 80950 162148 80939 162148 80939 162149 80950 162149 80947 162149 80939 162150 80947 162150 80951 162150 80951 162151 80947 162151 80946 162151 80951 162152 80946 162152 80938 162152 80938 162153 80946 162153 80944 162153 80293 162154 80292 162154 80952 162154 80293 162155 80952 162155 81900 162155 81900 162156 80952 162156 80965 162156 81900 162157 80965 162157 80953 162157 80953 162158 80965 162158 80964 162158 80953 162159 80964 162159 81456 162159 80954 162160 80963 162160 80961 162160 80506 162161 80955 162161 80956 162161 80956 162162 80955 162162 80958 162162 80956 162163 80958 162163 80957 162163 80957 162164 80958 162164 80959 162164 80289 162165 80960 162165 80959 162165 80959 162166 80960 162166 80967 162166 80959 162167 80967 162167 80957 162167 80955 162168 80954 162168 80958 162168 80958 162169 80954 162169 80961 162169 80958 162170 80961 162170 80959 162170 80959 162171 80961 162171 80962 162171 80959 162172 80962 162172 80289 162172 80289 162173 80962 162173 80291 162173 80963 162174 80964 162174 80961 162174 80961 162175 80964 162175 80965 162175 80961 162176 80965 162176 80962 162176 80962 162177 80965 162177 80952 162177 80962 162178 80952 162178 80291 162178 80291 162179 80952 162179 80292 162179 80960 162180 80279 162180 80966 162180 80960 162181 80966 162181 80967 162181 80967 162182 80966 162182 80973 162182 80967 162183 80973 162183 80957 162183 80957 162184 80973 162184 80971 162184 80957 162185 80971 162185 80956 162185 80956 162186 80971 162186 80968 162186 80956 162187 80968 162187 80506 162187 80969 162188 80968 162188 80970 162188 80970 162189 80968 162189 80971 162189 80970 162190 80971 162190 80972 162190 80972 162191 80971 162191 80973 162191 80972 162192 80973 162192 80975 162192 80975 162193 80973 162193 80966 162193 80975 162194 80966 162194 80582 162194 80582 162195 80966 162195 80279 162195 80976 162196 80969 162196 80974 162196 80974 162197 80969 162197 80970 162197 80974 162198 80970 162198 80978 162198 80978 162199 80970 162199 80972 162199 80978 162200 80972 162200 80979 162200 80979 162201 80972 162201 80975 162201 80979 162202 80975 162202 80503 162202 80503 162203 80975 162203 80582 162203 80987 162204 80976 162204 80974 162204 80987 162205 80974 162205 80986 162205 80986 162206 80974 162206 80978 162206 80986 162207 80978 162207 80977 162207 80977 162208 80978 162208 80979 162208 80977 162209 80979 162209 80983 162209 80983 162210 80979 162210 80503 162210 80983 162211 80503 162211 80981 162211 80982 162212 80995 162212 80984 162212 80984 162213 80995 162213 80980 162213 80984 162214 80980 162214 80985 162214 80985 162215 80980 162215 80997 162215 80985 162216 80997 162216 80988 162216 80988 162217 80997 162217 80998 162217 80988 162218 80998 162218 80989 162218 80989 162219 80998 162219 80999 162219 80981 162220 80982 162220 80983 162220 80983 162221 80982 162221 80984 162221 80983 162222 80984 162222 80977 162222 80977 162223 80984 162223 80985 162223 80977 162224 80985 162224 80986 162224 80986 162225 80985 162225 80988 162225 80986 162226 80988 162226 80987 162226 80987 162227 80988 162227 80989 162227 80575 162228 80572 162228 80996 162228 80996 162229 80572 162229 81004 162229 80996 162230 81004 162230 80990 162230 80990 162231 81004 162231 80991 162231 80990 162232 80991 162232 80992 162232 80992 162233 80991 162233 81005 162233 80992 162234 81005 162234 80993 162234 80993 162235 81005 162235 80994 162235 80995 162236 80575 162236 80980 162236 80980 162237 80575 162237 80996 162237 80980 162238 80996 162238 80997 162238 80997 162239 80996 162239 80990 162239 80997 162240 80990 162240 80998 162240 80998 162241 80990 162241 80992 162241 80998 162242 80992 162242 80999 162242 80999 162243 80992 162243 80993 162243 81001 162244 80573 162244 80574 162244 81000 162245 80411 162245 81008 162245 81008 162246 80411 162246 81006 162246 81008 162247 81006 162247 81009 162247 81009 162248 81006 162248 81003 162248 80574 162249 81012 162249 81001 162249 81001 162250 81012 162250 81002 162250 81001 162251 81002 162251 81003 162251 81003 162252 81002 162252 81010 162252 81003 162253 81010 162253 81009 162253 80572 162254 80573 162254 81004 162254 81004 162255 80573 162255 81001 162255 81004 162256 81001 162256 80991 162256 80991 162257 81001 162257 81003 162257 80991 162258 81003 162258 81005 162258 81005 162259 81003 162259 81006 162259 81005 162260 81006 162260 80994 162260 80994 162261 81006 162261 80411 162261 81000 162262 81008 162262 81007 162262 81007 162263 81008 162263 81011 162263 81008 162264 81009 162264 81011 162264 81011 162265 81009 162265 81010 162265 81011 162266 81010 162266 81013 162266 80574 162267 80456 162267 81012 162267 81012 162268 80456 162268 81013 162268 81012 162269 81013 162269 81002 162269 81002 162270 81013 162270 81010 162270 81007 162271 81011 162271 81024 162271 81011 162272 81013 162272 81015 162272 81013 162273 80456 162273 81014 162273 81013 162274 81014 162274 81015 162274 81015 162275 81014 162275 81016 162275 81015 162276 81016 162276 81018 162276 81018 162277 81016 162277 81017 162277 81018 162278 81017 162278 81021 162278 81021 162279 81017 162279 80461 162279 81021 162280 80461 162280 81022 162280 81022 162281 80461 162281 81954 162281 81022 162282 81954 162282 81023 162282 81011 162283 81015 162283 81024 162283 81024 162284 81015 162284 81018 162284 81024 162285 81018 162285 81019 162285 81019 162286 81018 162286 81021 162286 81019 162287 81021 162287 81020 162287 81020 162288 81021 162288 81022 162288 81020 162289 81022 162289 81026 162289 81026 162290 81022 162290 81023 162290 81026 162291 81023 162291 81028 162291 81007 162292 81024 162292 80413 162292 80413 162293 81024 162293 81019 162293 80413 162294 81019 162294 80415 162294 80415 162295 81019 162295 81020 162295 80415 162296 81020 162296 81025 162296 81025 162297 81020 162297 81026 162297 81025 162298 81026 162298 81027 162298 81027 162299 81026 162299 81028 162299 81027 162300 81028 162300 81392 162300 81029 162301 81955 162301 81041 162301 81955 162302 81957 162302 81030 162302 81957 162303 81959 162303 81032 162303 81959 162304 81031 162304 80464 162304 81959 162305 80464 162305 81032 162305 81032 162306 80464 162306 80454 162306 81032 162307 80454 162307 81033 162307 81033 162308 80454 162308 80453 162308 81033 162309 80453 162309 81037 162309 81037 162310 80453 162310 81034 162310 81037 162311 81034 162311 81039 162311 81039 162312 81034 162312 81035 162312 81039 162313 81035 162313 81049 162313 81957 162314 81032 162314 81030 162314 81030 162315 81032 162315 81033 162315 81030 162316 81033 162316 81036 162316 81036 162317 81033 162317 81037 162317 81036 162318 81037 162318 81038 162318 81038 162319 81037 162319 81039 162319 81038 162320 81039 162320 81040 162320 81040 162321 81039 162321 81049 162321 81040 162322 81049 162322 81048 162322 81955 162323 81030 162323 81041 162323 81041 162324 81030 162324 81036 162324 81041 162325 81036 162325 81044 162325 81044 162326 81036 162326 81038 162326 81044 162327 81038 162327 81042 162327 81042 162328 81038 162328 81040 162328 81042 162329 81040 162329 81043 162329 81043 162330 81040 162330 81048 162330 81043 162331 81048 162331 81047 162331 81029 162332 81041 162332 80418 162332 80418 162333 81041 162333 81044 162333 80418 162334 81044 162334 80421 162334 80421 162335 81044 162335 81042 162335 80421 162336 81042 162336 80422 162336 80422 162337 81042 162337 81043 162337 80422 162338 81043 162338 81045 162338 81045 162339 81043 162339 81047 162339 81045 162340 81047 162340 81046 162340 81064 162341 81046 162341 81063 162341 81063 162342 81046 162342 81047 162342 81063 162343 81047 162343 81062 162343 81062 162344 81047 162344 81048 162344 81062 162345 81048 162345 81060 162345 81060 162346 81048 162346 81049 162346 81060 162347 81049 162347 80568 162347 80568 162348 81049 162348 81035 162348 81055 162349 80570 162349 80571 162349 81050 162350 81051 162350 81053 162350 81053 162351 81051 162351 81052 162351 81053 162352 81052 162352 81054 162352 81054 162353 81052 162353 81058 162353 81054 162354 81058 162354 81056 162354 81056 162355 81058 162355 81055 162355 81056 162356 81055 162356 81069 162356 81069 162357 81055 162357 80571 162357 81057 162358 80570 162358 81061 162358 81061 162359 80570 162359 81055 162359 81061 162360 81055 162360 81059 162360 81059 162361 81055 162361 81058 162361 81059 162362 81058 162362 81065 162362 81065 162363 81058 162363 81052 162363 81065 162364 81052 162364 81066 162364 81066 162365 81052 162365 81051 162365 80568 162366 81057 162366 81060 162366 81060 162367 81057 162367 81061 162367 81060 162368 81061 162368 81062 162368 81062 162369 81061 162369 81059 162369 81062 162370 81059 162370 81063 162370 81063 162371 81059 162371 81065 162371 81063 162372 81065 162372 81064 162372 81064 162373 81065 162373 81066 162373 81067 162374 80427 162374 81050 162374 80571 162375 80501 162375 81069 162375 81069 162376 80501 162376 81068 162376 81050 162377 81053 162377 81067 162377 81067 162378 81053 162378 81054 162378 81067 162379 81054 162379 81068 162379 81068 162380 81054 162380 81056 162380 81068 162381 81056 162381 81069 162381 81071 162382 80427 162382 81072 162382 81072 162383 80427 162383 81067 162383 81072 162384 81067 162384 81074 162384 81074 162385 81067 162385 81068 162385 81074 162386 81068 162386 80577 162386 80577 162387 81068 162387 80501 162387 80426 162388 81071 162388 81070 162388 81070 162389 81071 162389 81072 162389 81070 162390 81072 162390 81073 162390 81073 162391 81072 162391 81074 162391 81073 162392 81074 162392 80578 162392 80578 162393 81074 162393 80577 162393 80425 162394 80426 162394 81075 162394 81075 162395 80426 162395 81070 162395 81075 162396 81070 162396 81077 162396 81077 162397 81070 162397 81073 162397 81077 162398 81073 162398 81076 162398 81076 162399 81073 162399 80578 162399 81082 162400 80425 162400 81084 162400 81084 162401 80425 162401 81075 162401 81084 162402 81075 162402 81079 162402 81079 162403 81075 162403 81077 162403 81079 162404 81077 162404 80580 162404 80580 162405 81077 162405 81076 162405 80319 162406 81078 162406 80580 162406 80580 162407 81078 162407 81079 162407 81078 162408 81080 162408 81079 162408 81079 162409 81080 162409 81081 162409 81079 162410 81081 162410 81084 162410 81086 162411 81082 162411 81087 162411 81087 162412 81082 162412 81084 162412 81087 162413 81084 162413 81083 162413 81083 162414 81084 162414 81081 162414 81089 162415 81086 162415 81085 162415 81085 162416 81086 162416 81087 162416 81085 162417 81087 162417 81091 162417 81087 162418 81083 162418 81091 162418 81091 162419 81083 162419 81081 162419 81091 162420 81081 162420 81092 162420 81096 162421 81089 162421 81088 162421 81088 162422 81089 162422 81085 162422 81088 162423 81085 162423 81090 162423 81090 162424 81085 162424 81091 162424 81090 162425 81091 162425 81093 162425 81093 162426 81091 162426 81092 162426 81093 162427 81092 162427 80318 162427 80318 162428 81092 162428 80320 162428 81081 162429 81080 162429 81092 162429 81092 162430 81080 162430 81078 162430 81092 162431 81078 162431 80320 162431 80320 162432 81078 162432 80319 162432 80318 162433 80317 162433 81097 162433 80318 162434 81097 162434 81093 162434 81093 162435 81097 162435 81094 162435 81093 162436 81094 162436 81090 162436 81090 162437 81094 162437 81095 162437 81090 162438 81095 162438 81088 162438 81088 162439 81095 162439 81103 162439 81088 162440 81103 162440 81096 162440 81106 162441 81109 162441 81105 162441 81094 162442 81097 162442 81098 162442 81109 162443 81111 162443 81104 162443 81111 162444 80408 162444 81099 162444 81111 162445 81099 162445 81104 162445 81104 162446 81099 162446 81100 162446 81104 162447 81100 162447 81102 162447 81100 162448 81101 162448 81102 162448 81102 162449 81101 162449 81103 162449 81102 162450 81103 162450 81095 162450 81109 162451 81104 162451 81105 162451 81105 162452 81104 162452 81102 162452 81105 162453 81102 162453 81098 162453 81098 162454 81102 162454 81095 162454 81098 162455 81095 162455 81094 162455 81106 162456 81105 162456 80316 162456 80316 162457 81105 162457 81098 162457 80316 162458 81098 162458 81107 162458 81107 162459 81098 162459 81097 162459 81107 162460 81097 162460 80317 162460 81106 162461 80311 162461 81108 162461 81106 162462 81108 162462 81109 162462 81109 162463 81108 162463 81110 162463 81109 162464 81110 162464 81111 162464 81111 162465 81110 162465 81455 162465 81111 162466 81455 162466 80408 162466 81115 162467 81113 162467 81112 162467 81112 162468 81113 162468 80539 162468 81112 162469 80539 162469 81114 162469 81114 162470 80539 162470 80540 162470 81114 162471 80540 162471 81121 162471 81115 162472 81112 162472 81116 162472 81116 162473 81112 162473 81114 162473 81116 162474 81114 162474 81117 162474 81117 162475 81114 162475 81121 162475 81117 162476 81121 162476 81120 162476 81118 162477 80558 162477 81120 162477 81120 162478 80558 162478 80559 162478 81120 162479 80559 162479 81117 162479 81117 162480 80559 162480 80561 162480 81117 162481 80561 162481 81116 162481 81116 162482 80561 162482 81115 162482 80556 162483 81118 162483 81119 162483 81119 162484 81118 162484 81120 162484 81119 162485 81120 162485 81124 162485 81124 162486 81120 162486 81121 162486 81124 162487 81121 162487 80395 162487 80395 162488 81121 162488 80540 162488 80394 162489 81128 162489 81125 162489 81125 162490 81128 162490 81130 162490 81125 162491 81130 162491 81126 162491 81126 162492 81130 162492 81122 162492 81126 162493 81122 162493 80557 162493 80557 162494 81122 162494 81123 162494 80395 162495 80394 162495 81124 162495 81124 162496 80394 162496 81125 162496 81124 162497 81125 162497 81119 162497 81119 162498 81125 162498 81126 162498 81119 162499 81126 162499 80556 162499 80556 162500 81126 162500 80557 162500 77405 162501 81122 162501 81130 162501 81122 162502 77405 162502 81123 162502 77404 162503 81127 162503 81128 162503 81128 162504 81127 162504 77395 162504 81128 162505 77395 162505 81130 162505 81130 162506 77395 162506 81129 162506 81130 162507 81129 162507 77405 162507 80566 162508 81148 162508 81146 162508 80526 162509 81131 162509 81132 162509 81132 162510 81131 162510 81133 162510 81132 162511 81133 162511 81136 162511 81136 162512 81133 162512 81134 162512 81136 162513 81134 162513 81139 162513 80526 162514 81132 162514 81135 162514 81135 162515 81132 162515 81136 162515 81135 162516 81136 162516 81137 162516 81137 162517 81136 162517 81139 162517 81137 162518 81139 162518 81138 162518 80566 162519 81146 162519 80564 162519 81143 162520 81138 162520 81144 162520 81144 162521 81138 162521 81139 162521 81144 162522 81139 162522 81146 162522 81146 162523 81139 162523 81134 162523 81146 162524 81134 162524 80564 162524 80564 162525 81134 162525 81133 162525 80564 162526 81133 162526 80563 162526 80563 162527 81133 162527 81131 162527 80563 162528 81131 162528 81140 162528 81140 162529 81131 162529 80526 162529 81141 162530 81143 162530 81142 162530 81142 162531 81143 162531 81144 162531 81142 162532 81144 162532 81145 162532 81145 162533 81144 162533 81146 162533 81145 162534 81146 162534 81147 162534 81147 162535 81146 162535 81148 162535 80396 162536 81141 162536 81149 162536 81149 162537 81141 162537 81142 162537 81149 162538 81142 162538 81150 162538 81150 162539 81142 162539 81145 162539 81150 162540 81145 162540 77386 162540 77386 162541 81145 162541 81147 162541 81151 162542 81152 162542 80396 162542 80396 162543 81152 162543 77383 162543 80396 162544 77383 162544 77385 162544 77386 162545 77384 162545 81150 162545 81150 162546 77384 162546 81151 162546 81150 162547 81151 162547 81149 162547 81149 162548 81151 162548 80396 162548 81153 162549 81244 162549 83746 162549 83746 162550 81244 162550 81154 162550 83746 162551 81154 162551 83744 162551 83744 162552 81154 162552 81155 162552 81155 162553 81154 162553 81156 162553 81156 162554 81154 162554 81242 162554 81156 162555 81242 162555 81159 162555 80404 162556 83743 162556 81157 162556 81157 162557 83743 162557 83742 162557 81157 162558 83742 162558 81242 162558 81242 162559 83742 162559 81158 162559 81242 162560 81158 162560 81159 162560 77856 162561 77779 162561 81200 162561 77856 162562 81200 162562 81160 162562 81160 162563 81200 162563 81201 162563 81160 162564 81201 162564 77859 162564 77859 162565 81201 162565 81202 162565 77859 162566 81202 162566 77858 162566 77858 162567 81202 162567 81203 162567 77858 162568 81203 162568 77857 162568 81163 162569 81161 162569 81162 162569 81162 162570 81325 162570 81163 162570 81163 162571 81325 162571 81164 162571 81163 162572 81164 162572 80315 162572 81165 162573 81166 162573 81167 162573 81167 162574 81166 162574 81191 162574 81167 162575 81191 162575 77780 162575 81165 162576 81168 162576 81166 162576 81166 162577 81168 162577 81326 162577 81166 162578 81326 162578 81161 162578 81161 162579 81326 162579 81327 162579 81161 162580 81327 162580 81162 162580 80431 162581 81169 162581 81170 162581 81170 162582 81169 162582 81171 162582 81170 162583 81171 162583 81316 162583 81316 162584 81171 162584 81315 162584 81172 162585 81320 162585 81171 162585 81171 162586 81320 162586 81318 162586 81171 162587 81318 162587 81315 162587 80288 162588 81173 162588 80268 162588 80268 162589 81173 162589 81321 162589 80268 162590 81321 162590 81172 162590 81172 162591 81321 162591 81174 162591 81172 162592 81174 162592 81320 162592 78229 162593 81281 162593 81175 162593 78229 162594 81175 162594 81176 162594 81176 162595 81175 162595 81283 162595 81176 162596 81283 162596 81177 162596 81177 162597 81283 162597 81178 162597 81177 162598 81178 162598 81179 162598 81179 162599 81178 162599 77766 162599 81179 162600 77766 162600 77765 162600 83788 162601 83787 162601 81182 162601 83781 162602 81255 162602 81180 162602 81180 162603 81255 162603 81256 162603 81180 162604 81256 162604 83783 162604 83781 162605 83784 162605 81255 162605 81255 162606 83784 162606 81181 162606 81255 162607 81181 162607 81182 162607 81182 162608 81181 162608 83785 162608 81182 162609 83785 162609 83788 162609 77776 162610 78269 162610 81256 162610 81256 162611 78269 162611 81183 162611 81256 162612 81183 162612 83783 162612 81191 162613 81166 162613 81184 162613 81184 162614 81166 162614 81187 162614 81184 162615 81187 162615 81194 162615 81194 162616 81187 162616 81186 162616 81194 162617 81186 162617 81185 162617 81185 162618 81186 162618 80441 162618 81166 162619 81161 162619 81187 162619 81187 162620 81161 162620 81189 162620 81187 162621 81189 162621 81186 162621 81186 162622 81189 162622 81188 162622 81186 162623 81188 162623 80441 162623 80441 162624 81188 162624 81190 162624 81161 162625 81163 162625 81189 162625 81189 162626 81163 162626 81196 162626 81189 162627 81196 162627 81188 162627 81188 162628 81196 162628 81197 162628 81188 162629 81197 162629 81190 162629 81190 162630 81197 162630 80442 162630 77779 162631 81191 162631 81210 162631 81210 162632 81191 162632 81184 162632 81210 162633 81184 162633 81192 162633 81192 162634 81184 162634 81193 162634 81193 162635 81184 162635 81194 162635 81193 162636 81194 162636 81211 162636 81211 162637 81194 162637 81215 162637 81215 162638 81194 162638 81185 162638 81215 162639 81185 162639 80440 162639 81163 162640 81195 162640 81220 162640 81163 162641 81220 162641 81196 162641 81196 162642 81220 162642 81226 162642 81196 162643 81226 162643 81197 162643 81197 162644 81226 162644 81198 162644 81197 162645 81198 162645 80442 162645 81235 162646 81236 162646 81206 162646 77779 162647 81199 162647 81200 162647 81200 162648 81199 162648 81207 162648 81200 162649 81207 162649 81201 162649 81201 162650 81207 162650 81206 162650 81201 162651 81206 162651 81202 162651 81202 162652 81206 162652 81236 162652 81202 162653 81236 162653 81203 162653 81204 162654 81205 162654 81212 162654 81212 162655 81205 162655 81235 162655 81235 162656 81206 162656 81212 162656 81212 162657 81206 162657 81207 162657 81212 162658 81207 162658 81208 162658 81208 162659 81207 162659 81199 162659 81208 162660 81199 162660 81214 162660 80446 162661 81209 162661 81213 162661 81213 162662 81209 162662 81204 162662 77779 162663 81210 162663 81199 162663 81199 162664 81210 162664 81192 162664 81199 162665 81192 162665 81214 162665 81214 162666 81192 162666 81193 162666 81214 162667 81193 162667 81211 162667 81204 162668 81212 162668 81213 162668 81213 162669 81212 162669 81208 162669 81213 162670 81208 162670 81217 162670 81217 162671 81208 162671 81214 162671 81217 162672 81214 162672 81219 162672 81219 162673 81214 162673 81211 162673 81219 162674 81211 162674 81215 162674 80446 162675 81213 162675 81216 162675 81216 162676 81213 162676 81217 162676 81216 162677 81217 162677 80439 162677 80439 162678 81217 162678 81219 162678 80439 162679 81219 162679 81218 162679 81218 162680 81219 162680 81215 162680 81218 162681 81215 162681 80440 162681 81198 162682 81226 162682 81227 162682 81226 162683 81220 162683 81221 162683 81220 162684 81195 162684 80560 162684 81220 162685 80560 162685 81221 162685 81221 162686 80560 162686 81222 162686 81221 162687 81222 162687 81223 162687 81223 162688 81222 162688 81224 162688 81223 162689 81224 162689 81228 162689 81228 162690 81224 162690 81225 162690 81228 162691 81225 162691 81237 162691 81226 162692 81221 162692 81227 162692 81227 162693 81221 162693 81223 162693 81227 162694 81223 162694 81230 162694 81230 162695 81223 162695 81228 162695 81230 162696 81228 162696 81232 162696 81232 162697 81228 162697 81237 162697 81232 162698 81237 162698 81234 162698 81198 162699 81227 162699 81229 162699 81229 162700 81227 162700 81230 162700 81229 162701 81230 162701 81231 162701 81231 162702 81230 162702 81232 162702 81231 162703 81232 162703 81233 162703 81233 162704 81232 162704 81234 162704 81233 162705 81234 162705 80443 162705 81209 162706 80446 162706 80445 162706 81209 162707 80445 162707 81204 162707 81204 162708 80445 162708 81247 162708 81204 162709 81247 162709 81205 162709 81205 162710 81247 162710 81235 162710 81235 162711 81247 162711 81245 162711 81235 162712 81245 162712 81236 162712 81236 162713 81245 162713 81244 162713 81236 162714 81244 162714 81203 162714 81225 162715 83896 162715 83895 162715 81225 162716 83895 162716 81237 162716 81237 162717 83895 162717 83894 162717 81237 162718 83894 162718 81234 162718 81234 162719 83894 162719 80438 162719 81234 162720 80438 162720 80443 162720 81157 162721 81242 162721 81238 162721 81238 162722 81242 162722 81239 162722 81238 162723 81239 162723 77744 162723 77744 162724 81239 162724 81240 162724 77744 162725 81240 162725 77745 162725 77745 162726 81240 162726 81241 162726 81242 162727 81154 162727 81239 162727 81239 162728 81154 162728 81243 162728 81239 162729 81243 162729 81240 162729 81240 162730 81243 162730 81246 162730 81240 162731 81246 162731 81241 162731 81241 162732 81246 162732 81248 162732 81154 162733 81244 162733 81243 162733 81243 162734 81244 162734 81245 162734 81243 162735 81245 162735 81246 162735 81246 162736 81245 162736 81247 162736 81246 162737 81247 162737 81248 162737 81248 162738 81247 162738 80445 162738 80241 162739 80243 162739 81249 162739 81249 162740 80243 162740 81253 162740 81249 162741 81253 162741 81252 162741 81252 162742 81253 162742 81251 162742 81255 162743 81182 162743 81251 162743 81251 162744 81182 162744 81250 162744 81251 162745 81250 162745 81252 162745 80243 162746 80237 162746 81253 162746 81253 162747 80237 162747 81254 162747 81253 162748 81254 162748 81251 162748 81251 162749 81254 162749 81257 162749 81251 162750 81257 162750 81255 162750 81255 162751 81257 162751 81256 162751 80237 162752 80236 162752 81254 162752 81254 162753 80236 162753 81261 162753 81254 162754 81261 162754 81257 162754 81257 162755 81261 162755 81258 162755 81257 162756 81258 162756 81256 162756 81256 162757 81258 162757 77776 162757 81274 162758 81281 162758 77776 162758 81274 162759 77776 162759 81275 162759 81275 162760 77776 162760 81258 162760 81275 162761 81258 162761 81269 162761 81269 162762 81258 162762 81261 162762 81269 162763 81261 162763 81259 162763 81259 162764 81261 162764 81260 162764 81260 162765 81261 162765 80236 162765 81260 162766 80236 162766 80244 162766 81290 162767 81262 162767 83874 162767 81290 162768 83874 162768 81263 162768 81263 162769 83874 162769 81264 162769 81263 162770 81264 162770 81292 162770 81292 162771 81264 162771 81265 162771 81292 162772 81265 162772 81293 162772 81293 162773 81265 162773 83872 162773 81293 162774 83872 162774 81294 162774 81259 162775 81260 162775 81266 162775 80238 162776 81272 162776 80239 162776 80239 162777 81272 162777 81271 162777 80239 162778 81271 162778 81267 162778 81267 162779 81271 162779 81266 162779 81267 162780 81266 162780 81268 162780 81268 162781 81266 162781 81260 162781 81268 162782 81260 162782 80244 162782 81275 162783 81269 162783 81270 162783 81270 162784 81269 162784 81259 162784 81259 162785 81266 162785 81270 162785 81270 162786 81266 162786 81271 162786 81270 162787 81271 162787 81273 162787 81273 162788 81271 162788 81272 162788 81273 162789 81272 162789 81278 162789 81281 162790 81274 162790 81279 162790 81279 162791 81274 162791 81275 162791 80238 162792 81295 162792 81272 162792 81272 162793 81295 162793 81276 162793 81272 162794 81276 162794 81278 162794 81278 162795 81276 162795 81277 162795 81278 162796 81277 162796 81296 162796 81275 162797 81270 162797 81279 162797 81279 162798 81270 162798 81273 162798 81279 162799 81273 162799 81282 162799 81282 162800 81273 162800 81278 162800 81282 162801 81278 162801 81280 162801 81280 162802 81278 162802 81296 162802 81280 162803 81296 162803 81298 162803 81281 162804 81279 162804 81175 162804 81175 162805 81279 162805 81282 162805 81175 162806 81282 162806 81283 162806 81283 162807 81282 162807 81280 162807 81283 162808 81280 162808 81178 162808 81178 162809 81280 162809 81298 162809 81178 162810 81298 162810 77766 162810 81288 162811 80562 162811 81287 162811 81291 162812 81284 162812 81290 162812 80246 162813 80242 162813 81300 162813 81300 162814 80242 162814 81285 162814 81300 162815 81285 162815 81286 162815 81286 162816 81285 162816 81287 162816 81286 162817 81287 162817 81302 162817 81302 162818 81287 162818 80562 162818 80565 162819 81288 162819 81289 162819 81289 162820 81288 162820 81287 162820 81289 162821 81287 162821 81291 162821 81291 162822 81287 162822 81285 162822 81291 162823 81285 162823 81284 162823 81284 162824 81285 162824 80242 162824 81290 162825 81263 162825 81291 162825 81291 162826 81263 162826 81292 162826 81291 162827 81292 162827 81289 162827 81289 162828 81292 162828 81293 162828 81289 162829 81293 162829 80565 162829 80565 162830 81293 162830 81294 162830 80238 162831 81303 162831 81295 162831 81295 162832 81303 162832 81304 162832 81295 162833 81304 162833 81276 162833 81276 162834 81304 162834 81277 162834 81277 162835 81304 162835 81297 162835 81277 162836 81297 162836 81296 162836 81296 162837 81297 162837 81298 162837 81298 162838 81297 162838 81169 162838 81298 162839 81169 162839 77766 162839 81309 162840 80246 162840 81300 162840 81309 162841 81300 162841 81299 162841 81299 162842 81300 162842 81286 162842 81299 162843 81286 162843 81301 162843 81301 162844 81286 162844 81302 162844 81301 162845 81302 162845 80268 162845 81303 162846 80240 162846 81304 162846 81304 162847 80240 162847 81307 162847 81304 162848 81307 162848 81297 162848 81297 162849 81307 162849 81305 162849 81297 162850 81305 162850 81169 162850 81169 162851 81305 162851 81171 162851 80240 162852 81306 162852 81307 162852 81307 162853 81306 162853 81308 162853 81307 162854 81308 162854 81305 162854 81305 162855 81308 162855 81310 162855 81305 162856 81310 162856 81171 162856 81171 162857 81310 162857 81172 162857 81306 162858 81309 162858 81308 162858 81308 162859 81309 162859 81299 162859 81308 162860 81299 162860 81310 162860 81310 162861 81299 162861 81301 162861 81310 162862 81301 162862 81172 162862 81172 162863 81301 162863 80268 162863 81173 162864 80288 162864 82082 162864 82084 162865 80432 162865 81311 162865 82084 162866 81311 162866 81312 162866 81312 162867 81311 162867 80433 162867 81312 162868 80433 162868 81317 162868 81170 162869 81316 162869 81313 162869 81313 162870 81316 162870 80436 162870 81314 162871 82085 162871 81315 162871 81315 162872 82085 162872 81312 162872 81315 162873 81312 162873 81316 162873 81316 162874 81312 162874 81317 162874 81316 162875 81317 162875 80436 162875 81315 162876 81318 162876 81314 162876 81314 162877 81318 162877 81320 162877 81314 162878 81320 162878 81319 162878 81319 162879 81320 162879 82080 162879 82080 162880 81320 162880 81174 162880 82080 162881 81174 162881 81321 162881 81173 162882 82082 162882 81321 162882 81321 162883 82082 162883 82081 162883 81321 162884 82081 162884 82080 162884 81164 162885 81325 162885 81322 162885 81164 162886 81322 162886 80315 162886 80315 162887 81322 162887 82078 162887 80315 162888 82078 162888 81323 162888 81162 162889 81327 162889 82075 162889 81162 162890 82075 162890 81325 162890 81325 162891 82075 162891 81324 162891 81325 162892 81324 162892 81322 162892 81326 162893 81168 162893 81328 162893 81326 162894 81328 162894 81327 162894 81327 162895 81328 162895 82077 162895 81327 162896 82077 162896 82075 162896 81165 162897 81167 162897 80379 162897 81165 162898 80379 162898 81168 162898 81168 162899 80379 162899 82073 162899 81168 162900 82073 162900 81328 162900 83871 162901 83869 162901 81329 162901 81329 162902 83869 162902 81330 162902 82165 162903 81336 162903 81330 162903 81330 162904 81336 162904 82206 162904 81330 162905 82206 162905 82216 162905 82165 162906 82164 162906 82155 162906 81334 162907 81331 162907 82192 162907 82170 162908 82180 162908 82179 162908 82216 162909 81332 162909 81330 162909 81330 162910 81332 162910 81333 162910 81330 162911 81333 162911 81329 162911 81329 162912 81333 162912 81334 162912 81329 162913 81334 162913 81335 162913 81335 162914 81334 162914 82192 162914 82155 162915 82150 162915 82165 162915 82165 162916 82150 162916 82149 162916 82165 162917 82149 162917 81336 162917 81336 162918 82149 162918 82170 162918 81336 162919 82170 162919 81337 162919 81337 162920 82170 162920 82179 162920 77782 162921 80387 162921 77876 162921 77876 162922 80387 162922 80386 162922 77876 162923 80386 162923 77877 162923 77877 162924 80386 162924 80384 162924 77877 162925 80384 162925 81338 162925 81338 162926 80384 162926 80383 162926 81454 162927 81339 162927 77435 162927 77435 162928 81339 162928 82004 162928 80234 162929 81729 162929 81340 162929 81340 162930 81729 162930 81341 162930 81340 162931 81341 162931 81342 162931 81342 162932 81341 162932 81719 162932 81692 162933 81517 162933 81693 162933 81693 162934 81517 162934 77425 162934 81693 162935 77425 162935 81699 162935 77396 162936 81346 162936 81343 162936 81343 162937 81346 162937 81709 162937 81343 162938 81709 162938 81344 162938 81344 162939 81709 162939 81345 162939 81344 162940 81345 162940 77425 162940 77425 162941 81345 162941 81699 162941 81719 162942 81346 162942 81342 162942 81342 162943 81346 162943 77396 162943 81637 162944 81595 162944 81605 162944 81639 162945 81349 162945 81626 162945 81626 162946 81349 162946 81352 162946 81664 162947 81347 162947 81348 162947 81348 162948 81347 162948 81667 162948 81348 162949 81667 162949 81645 162949 81645 162950 81667 162950 81349 162950 81645 162951 81349 162951 81350 162951 81350 162952 81349 162952 81639 162952 81605 162953 81351 162953 81637 162953 81637 162954 81351 162954 81609 162954 81637 162955 81609 162955 81352 162955 81352 162956 81609 162956 81353 162956 81352 162957 81353 162957 81626 162957 81877 162958 81890 162958 81869 162958 81845 162959 81815 162959 81495 162959 81866 162960 81867 162960 81354 162960 81871 162961 81354 162961 81868 162961 81868 162962 81354 162962 81867 162962 81868 162963 81867 162963 81869 162963 81869 162964 81867 162964 81355 162964 81869 162965 81355 162965 81877 162965 81356 162966 81845 162966 81844 162966 81844 162967 81845 162967 81495 162967 81844 162968 81495 162968 81839 162968 81839 162969 81495 162969 81866 162969 81839 162970 81866 162970 81850 162970 81850 162971 81866 162971 81354 162971 81357 162972 81489 162972 77439 162972 81482 162973 81882 162973 81358 162973 81358 162974 81882 162974 81858 162974 81357 162975 77439 162975 81487 162975 81487 162976 77439 162976 81359 162976 81487 162977 81359 162977 81486 162977 81486 162978 81359 162978 81360 162978 81486 162979 81360 162979 81485 162979 81485 162980 81360 162980 81362 162980 81362 162981 81360 162981 81361 162981 81362 162982 81361 162982 81484 162982 81484 162983 81361 162983 81363 162983 81363 162984 81361 162984 77436 162984 81363 162985 77436 162985 81482 162985 81482 162986 77436 162986 81364 162986 81482 162987 81364 162987 81882 162987 81661 162988 81660 162988 77424 162988 81366 162989 81494 162989 81661 162989 81679 162990 81687 162990 81365 162990 81365 162991 81687 162991 81686 162991 81365 162992 81686 162992 81682 162992 81366 162993 81661 162993 81367 162993 81367 162994 81661 162994 77424 162994 81367 162995 77424 162995 81365 162995 81365 162996 77424 162996 77365 162996 81365 162997 77365 162997 81679 162997 81477 162998 81475 162998 81370 162998 81368 162999 81478 162999 81369 162999 81369 163000 81478 163000 81477 163000 81369 163001 81477 163001 77368 163001 77368 163002 81477 163002 81370 163002 81371 163003 81372 163003 81373 163003 81464 163004 81885 163004 81373 163004 81373 163005 81885 163005 81897 163005 81373 163006 81897 163006 81371 163006 81374 163007 81464 163007 81659 163007 81659 163008 81464 163008 81373 163008 81659 163009 81373 163009 81375 163009 81375 163010 81373 163010 77429 163010 82036 163011 77439 163011 81376 163011 81376 163012 77439 163012 81489 163012 81376 163013 81489 163013 82034 163013 82034 163014 81489 163014 82023 163014 81478 163015 81368 163015 81377 163015 81377 163016 82058 163016 81478 163016 81478 163017 82058 163017 81378 163017 81478 163018 81378 163018 82052 163018 81516 163019 83854 163019 77653 163019 77653 163020 83854 163020 83855 163020 81379 163021 81507 163021 81509 163021 81380 163022 82174 163022 82175 163022 82175 163023 83869 163023 83871 163023 83871 163024 81379 163024 82175 163024 82175 163025 81379 163025 81509 163025 82175 163026 81509 163026 81380 163026 81380 163027 81509 163027 81381 163027 81380 163028 81381 163028 83861 163028 81387 163029 83699 163029 81388 163029 81505 163030 82139 163030 81386 163030 81386 163031 82139 163031 82138 163031 81386 163032 82138 163032 81382 163032 81382 163033 82138 163033 81383 163033 81382 163034 81383 163034 81384 163034 81382 163035 81385 163035 81386 163035 81386 163036 81385 163036 81387 163036 81386 163037 81387 163037 77523 163037 77523 163038 81387 163038 81388 163038 81514 163039 83703 163039 81513 163039 81513 163040 83703 163040 83702 163040 81391 163041 81927 163041 81389 163041 81390 163042 81460 163042 81914 163042 81914 163043 81460 163043 81391 163043 81914 163044 81391 163044 81915 163044 81915 163045 81391 163045 81389 163045 77423 163046 77422 163046 81392 163046 81392 163047 81951 163047 77423 163047 77423 163048 81951 163048 81947 163048 77423 163049 81947 163049 81450 163049 81399 163050 81969 163050 77415 163050 77415 163051 81969 163051 81393 163051 77415 163052 81393 163052 81029 163052 81982 163053 81983 163053 81396 163053 81982 163054 81396 163054 81994 163054 81994 163055 81396 163055 81394 163055 81994 163056 81394 163056 81995 163056 81983 163057 81395 163057 81396 163057 81396 163058 81395 163058 81397 163058 81396 163059 81397 163059 77415 163059 77415 163060 81397 163060 81398 163060 77415 163061 81398 163061 81399 163061 80252 163062 77649 163062 81400 163062 81400 163063 77649 163063 77648 163063 81400 163064 77648 163064 78227 163064 78227 163065 77648 163065 77646 163065 78227 163066 77646 163066 78222 163066 78222 163067 77646 163067 77769 163067 77741 163068 81384 163068 81383 163068 81407 163069 82105 163069 81401 163069 81401 163070 82105 163070 82104 163070 81401 163071 82104 163071 81405 163071 82121 163072 82123 163072 82104 163072 82104 163073 82123 163073 82125 163073 82104 163074 82125 163074 81405 163074 82147 163075 81402 163075 81403 163075 81403 163076 81402 163076 81404 163076 81403 163077 81404 163077 81405 163077 81405 163078 81404 163078 77741 163078 81405 163079 77741 163079 81401 163079 81401 163080 77741 163080 81383 163080 82101 163081 82103 163081 82097 163081 82097 163082 82103 163082 82105 163082 82097 163083 82105 163083 81406 163083 81406 163084 82105 163084 81407 163084 81406 163085 81407 163085 82133 163085 82133 163086 81407 163086 82131 163086 81408 163087 81804 163087 81801 163087 81754 163088 81409 163088 81801 163088 81801 163089 81409 163089 81760 163089 81801 163090 81760 163090 81408 163090 81754 163091 81801 163091 81410 163091 81410 163092 81801 163092 81831 163092 81410 163093 81831 163093 81411 163093 81414 163094 81541 163094 81546 163094 81546 163095 81545 163095 81414 163095 81414 163096 81545 163096 81412 163096 81414 163097 81412 163097 81413 163097 81413 163098 81415 163098 81414 163098 81414 163099 81415 163099 81562 163099 81414 163100 81562 163100 81602 163100 77527 163101 81429 163101 81416 163101 81416 163102 81429 163102 81418 163102 81416 163103 81418 163103 81417 163103 81417 163104 81418 163104 77879 163104 81417 163105 77879 163105 77519 163105 77519 163106 77879 163106 77878 163106 77519 163107 77878 163107 81419 163107 81419 163108 77878 163108 81420 163108 81419 163109 81420 163109 77520 163109 77520 163110 81420 163110 81421 163110 77520 163111 81421 163111 77521 163111 77521 163112 81421 163112 81422 163112 77521 163113 81422 163113 77522 163113 77522 163114 81422 163114 81423 163114 77522 163115 81423 163115 81424 163115 81424 163116 81423 163116 81425 163116 81424 163117 81425 163117 77524 163117 77524 163118 81425 163118 81426 163118 77524 163119 81426 163119 81427 163119 81427 163120 81426 163120 81428 163120 81427 163121 81428 163121 77526 163121 77526 163122 81428 163122 77880 163122 77526 163123 77880 163123 77527 163123 77527 163124 77880 163124 81429 163124 81440 163125 81430 163125 77588 163125 77588 163126 81430 163126 81431 163126 77588 163127 81431 163127 77589 163127 77589 163128 81431 163128 77869 163128 77589 163129 77869 163129 77592 163129 77592 163130 77869 163130 77874 163130 77592 163131 77874 163131 77593 163131 77593 163132 77874 163132 81432 163132 77593 163133 81432 163133 77585 163133 77585 163134 81432 163134 77875 163134 77585 163135 77875 163135 77586 163135 77586 163136 77875 163136 81433 163136 77586 163137 81433 163137 81434 163137 81434 163138 81433 163138 81435 163138 81434 163139 81435 163139 81436 163139 81436 163140 81435 163140 81438 163140 81436 163141 81438 163141 81437 163141 81437 163142 81438 163142 77871 163142 81437 163143 77871 163143 81439 163143 81439 163144 77871 163144 77872 163144 81439 163145 77872 163145 77587 163145 77587 163146 77872 163146 81441 163146 77587 163147 81441 163147 81440 163147 81440 163148 81441 163148 81430 163148 81764 163149 81442 163149 81744 163149 81744 163150 81442 163150 81443 163150 81744 163151 81443 163151 81522 163151 81522 163152 81443 163152 81979 163152 81559 163153 81444 163153 81446 163153 81446 163154 81444 163154 81445 163154 81446 163155 81445 163155 81447 163155 81447 163156 81445 163156 81448 163156 81447 163157 81448 163157 81926 163157 77435 163158 82004 163158 81449 163158 81449 163159 82004 163159 81997 163159 81449 163160 81997 163160 81394 163160 81394 163161 81997 163161 81995 163161 77423 163162 81450 163162 81452 163162 81927 163163 81391 163163 81928 163163 81928 163164 81391 163164 77423 163164 81928 163165 77423 163165 81451 163165 81451 163166 77423 163166 81452 163166 81339 163167 81454 163167 81453 163167 81453 163168 81454 163168 77430 163168 81453 163169 77430 163169 82012 163169 82012 163170 77430 163170 77367 163170 82012 163171 77367 163171 81455 163171 81455 163172 77367 163172 80409 163172 81456 163173 81457 163173 81898 163173 81898 163174 81457 163174 77393 163174 81898 163175 77393 163175 81458 163175 81458 163176 77393 163176 81459 163176 81458 163177 81459 163177 81390 163177 81390 163178 81459 163178 81460 163178 81630 163179 81473 163179 81470 163179 81630 163180 81470 163180 81463 163180 81470 163181 81468 163181 81854 163181 81463 163182 81470 163182 81461 163182 81461 163183 81470 163183 81854 163183 81461 163184 81854 163184 81855 163184 81462 163185 81463 163185 81461 163185 81462 163186 81461 163186 81644 163186 81466 163187 81465 163187 81464 163187 81464 163188 81465 163188 81870 163188 81464 163189 81870 163189 81885 163189 81855 163190 81465 163190 81461 163190 81461 163191 81465 163191 81466 163191 81461 163192 81466 163192 81644 163192 81644 163193 81466 163193 81464 163193 81644 163194 81464 163194 81374 163194 81467 163195 80451 163195 80460 163195 81467 163196 80460 163196 81472 163196 81468 163197 81470 163197 81469 163197 81469 163198 81470 163198 81471 163198 81469 163199 81471 163199 81838 163199 81836 163200 81838 163200 80460 163200 80460 163201 81838 163201 81471 163201 80460 163202 81471 163202 81472 163202 81472 163203 81471 163203 81470 163203 81472 163204 81470 163204 81473 163204 80266 163205 81733 163205 81474 163205 81474 163206 81733 163206 81475 163206 81474 163207 81475 163207 81476 163207 81475 163208 81477 163208 81476 163208 81476 163209 81477 163209 81478 163209 81476 163210 81478 163210 80271 163210 81478 163211 82052 163211 82042 163211 82040 163212 80271 163212 81479 163212 81479 163213 80271 163213 81478 163213 81479 163214 81478 163214 82041 163214 82041 163215 81478 163215 82042 163215 81857 163216 80324 163216 81480 163216 81857 163217 81480 163217 81858 163217 81858 163218 81480 163218 81358 163218 81358 163219 81480 163219 81481 163219 81358 163220 81481 163220 81482 163220 81482 163221 81481 163221 81483 163221 81482 163222 81483 163222 81363 163222 81363 163223 81483 163223 80326 163223 81363 163224 80326 163224 81484 163224 81484 163225 80326 163225 80327 163225 81484 163226 80327 163226 81362 163226 81362 163227 80327 163227 80310 163227 81362 163228 80310 163228 81485 163228 81485 163229 80310 163229 80303 163229 81485 163230 80303 163230 81486 163230 81486 163231 80303 163231 80304 163231 81486 163232 80304 163232 81487 163232 81487 163233 80304 163233 81488 163233 81487 163234 81488 163234 81357 163234 81357 163235 81488 163235 80306 163235 81357 163236 80306 163236 81489 163236 80306 163237 81501 163237 81489 163237 81489 163238 81501 163238 82021 163238 82021 163239 82022 163239 81489 163239 81489 163240 82022 163240 81490 163240 81489 163241 81490 163241 82023 163241 81491 163242 81632 163242 81651 163242 81365 163243 81682 163243 81492 163243 81703 163244 80275 163244 81492 163244 81492 163245 80275 163245 81493 163245 81492 163246 81493 163246 81365 163246 81365 163247 81493 163247 80277 163247 81365 163248 80277 163248 81367 163248 81367 163249 80277 163249 81491 163249 81367 163250 81491 163250 81366 163250 81366 163251 81491 163251 81651 163251 81366 163252 81651 163252 81494 163252 81495 163253 81815 163253 81830 163253 81830 163254 81815 163254 81796 163254 81830 163255 81796 163255 81496 163255 81496 163256 81796 163256 81797 163256 81496 163257 81797 163257 81497 163257 81497 163258 81797 163258 81498 163258 81497 163259 81498 163259 81831 163259 81831 163260 81498 163260 81411 163260 81602 163261 81562 163261 81499 163261 81499 163262 81562 163262 81576 163262 81499 163263 81576 163263 81624 163263 81624 163264 81576 163264 81500 163264 81624 163265 81500 163265 81625 163265 81625 163266 81500 163266 81577 163266 81625 163267 81577 163267 81637 163267 81637 163268 81577 163268 81595 163268 81505 163269 82029 163269 81506 163269 81503 163270 82139 163270 81505 163270 81501 163271 80307 163271 81502 163271 81502 163272 80307 163272 82132 163272 81502 163273 82132 163273 82028 163273 82028 163274 82132 163274 82126 163274 82028 163275 82126 163275 82027 163275 82027 163276 82126 163276 81503 163276 82027 163277 81503 163277 81504 163277 81504 163278 81503 163278 81505 163278 81504 163279 81505 163279 82033 163279 82033 163280 81505 163280 81506 163280 81509 163281 81507 163281 82196 163281 81511 163282 81508 163282 81509 163282 81509 163283 81508 163283 81510 163283 81509 163284 81510 163284 82057 163284 81509 163285 82196 163285 81511 163285 81511 163286 82196 163286 82199 163286 81511 163287 82199 163287 82048 163287 82048 163288 82199 163288 81512 163288 82048 163289 81512 163289 82049 163289 82201 163290 82040 163290 81512 163290 81512 163291 82040 163291 82051 163291 81512 163292 82051 163292 82049 163292 77530 163293 81513 163293 83704 163293 83704 163294 81513 163294 83702 163294 81388 163295 83699 163295 81514 163295 81514 163296 83699 163296 83703 163296 83839 163297 83854 163297 81515 163297 81515 163298 83854 163298 81516 163298 83861 163299 81381 163299 83855 163299 83855 163300 81381 163300 77653 163300 77411 163301 81517 163301 81518 163301 81518 163302 81517 163302 81692 163302 80463 163303 81519 163303 81749 163303 81749 163304 81519 163304 81962 163304 81749 163305 81962 163305 81747 163305 81747 163306 81962 163306 81961 163306 81747 163307 81961 163307 81748 163307 81748 163308 81961 163308 81963 163308 81748 163309 81963 163309 81764 163309 81764 163310 81963 163310 81442 163310 81520 163311 81533 163311 81940 163311 81940 163312 81533 163312 81532 163312 81940 163313 81532 163313 81950 163313 81950 163314 81532 163314 81521 163314 81950 163315 81521 163315 81939 163315 81939 163316 81521 163316 81447 163316 81939 163317 81447 163317 81926 163317 81522 163318 81979 163318 81978 163318 81522 163319 81978 163319 81774 163319 81774 163320 81978 163320 81523 163320 81774 163321 81523 163321 81772 163321 81772 163322 81523 163322 81524 163322 81524 163323 81523 163323 80330 163323 81524 163324 80330 163324 80329 163324 81557 163325 80273 163325 81916 163325 81525 163326 81444 163326 81559 163326 81559 163327 81558 163327 81525 163327 81525 163328 81558 163328 81556 163328 81525 163329 81556 163329 81916 163329 81916 163330 81556 163330 81526 163330 81916 163331 81526 163331 81557 163331 81530 163332 81527 163332 81536 163332 81537 163333 81412 163333 81545 163333 81528 163334 81447 163334 81521 163334 81528 163335 81527 163335 81529 163335 81529 163336 81527 163336 81530 163336 81529 163337 81530 163337 81547 163337 81413 163338 81412 163338 81531 163338 81531 163339 81412 163339 81537 163339 81531 163340 81537 163340 81540 163340 81528 163341 81521 163341 81527 163341 81527 163342 81521 163342 81532 163342 81527 163343 81532 163343 81536 163343 81536 163344 81532 163344 81533 163344 81536 163345 81533 163345 81534 163345 81534 163346 81535 163346 81536 163346 81536 163347 81535 163347 81540 163347 81536 163348 81540 163348 81530 163348 81530 163349 81540 163349 81537 163349 81530 163350 81537 163350 81547 163350 81547 163351 81537 163351 81545 163351 81415 163352 81413 163352 81538 163352 81538 163353 81413 163353 81531 163353 81538 163354 81531 163354 81539 163354 81539 163355 81531 163355 81540 163355 81539 163356 81540 163356 81549 163356 81549 163357 81540 163357 81535 163357 81546 163358 81541 163358 81548 163358 81548 163359 81541 163359 81561 163359 81548 163360 81561 163360 81542 163360 81542 163361 81561 163361 81560 163361 81542 163362 81560 163362 81543 163362 81543 163363 81560 163363 81544 163363 81543 163364 81544 163364 81446 163364 81446 163365 81544 163365 81559 163365 81545 163366 81546 163366 81547 163366 81547 163367 81546 163367 81548 163367 81547 163368 81548 163368 81529 163368 81529 163369 81548 163369 81542 163369 81529 163370 81542 163370 81528 163370 81528 163371 81542 163371 81543 163371 81528 163372 81543 163372 81447 163372 81447 163373 81543 163373 81446 163373 81564 163374 81535 163374 80452 163374 80452 163375 81535 163375 81534 163375 80452 163376 81534 163376 81533 163376 81570 163377 81562 163377 81415 163377 81415 163378 81538 163378 81570 163378 81570 163379 81538 163379 81539 163379 81570 163380 81539 163380 81564 163380 81564 163381 81539 163381 81549 163381 81564 163382 81549 163382 81535 163382 81580 163383 81551 163383 81550 163383 81550 163384 81551 163384 81552 163384 81579 163385 81553 163385 81554 163385 81554 163386 81553 163386 81552 163386 81552 163387 81553 163387 81555 163387 81552 163388 81555 163388 81550 163388 81558 163389 81555 163389 81556 163389 81556 163390 81555 163390 81553 163390 81556 163391 81553 163391 81526 163391 81526 163392 81553 163392 81579 163392 81526 163393 81579 163393 81557 163393 81557 163394 81579 163394 81588 163394 81557 163395 81588 163395 80273 163395 81558 163396 81559 163396 81555 163396 81555 163397 81559 163397 81544 163397 81555 163398 81544 163398 81550 163398 81550 163399 81544 163399 81560 163399 81550 163400 81560 163400 81580 163400 81580 163401 81560 163401 81561 163401 81580 163402 81561 163402 81541 163402 81562 163403 81570 163403 81575 163403 81570 163404 81564 163404 81563 163404 81564 163405 80452 163405 81565 163405 81564 163406 81565 163406 81563 163406 81563 163407 81565 163407 81566 163407 81563 163408 81566 163408 81567 163408 81567 163409 81566 163409 81568 163409 81567 163410 81568 163410 81569 163410 81569 163411 81568 163411 81593 163411 81569 163412 81593 163412 81572 163412 81570 163413 81563 163413 81575 163413 81575 163414 81563 163414 81567 163414 81575 163415 81567 163415 81571 163415 81571 163416 81567 163416 81569 163416 81571 163417 81569 163417 81573 163417 81573 163418 81569 163418 81572 163418 81573 163419 81572 163419 81574 163419 81562 163420 81575 163420 81576 163420 81576 163421 81575 163421 81571 163421 81576 163422 81571 163422 81500 163422 81500 163423 81571 163423 81573 163423 81500 163424 81573 163424 81577 163424 81577 163425 81573 163425 81574 163425 81577 163426 81574 163426 81595 163426 81583 163427 81597 163427 81584 163427 81578 163428 81586 163428 81579 163428 81579 163429 81586 163429 81588 163429 81579 163430 81554 163430 81578 163430 81578 163431 81554 163431 81552 163431 81578 163432 81552 163432 81581 163432 81581 163433 81552 163433 81551 163433 81551 163434 81580 163434 81581 163434 81581 163435 81580 163435 81541 163435 81581 163436 81541 163436 81582 163436 81582 163437 81583 163437 81581 163437 81581 163438 81583 163438 81584 163438 81581 163439 81584 163439 81578 163439 81578 163440 81584 163440 81585 163440 81578 163441 81585 163441 81586 163441 81586 163442 81585 163442 81587 163442 81586 163443 81587 163443 81588 163443 81588 163444 81587 163444 81589 163444 81588 163445 81589 163445 80273 163445 81589 163446 81587 163446 81590 163446 81590 163447 81587 163447 81585 163447 81590 163448 81585 163448 81591 163448 81591 163449 81585 163449 81584 163449 81591 163450 81584 163450 80276 163450 80276 163451 81584 163451 81597 163451 80276 163452 81597 163452 81596 163452 81593 163453 80451 163453 81592 163453 81593 163454 81592 163454 81572 163454 81572 163455 81592 163455 81594 163455 81572 163456 81594 163456 81574 163456 81574 163457 81594 163457 81605 163457 81574 163458 81605 163458 81595 163458 80278 163459 81596 163459 81597 163459 80278 163460 81599 163460 80294 163460 80294 163461 81599 163461 81598 163461 81598 163462 81599 163462 81600 163462 81600 163463 81599 163463 81603 163463 81600 163464 81603 163464 81619 163464 81619 163465 81603 163465 81601 163465 81601 163466 81603 163466 81604 163466 81601 163467 81604 163467 81622 163467 81622 163468 81604 163468 81414 163468 81622 163469 81414 163469 81602 163469 80278 163470 81597 163470 81599 163470 81599 163471 81597 163471 81583 163471 81599 163472 81583 163472 81603 163472 81603 163473 81583 163473 81582 163473 81603 163474 81582 163474 81604 163474 81604 163475 81582 163475 81541 163475 81604 163476 81541 163476 81414 163476 81351 163477 81605 163477 81607 163477 81607 163478 81605 163478 81594 163478 81607 163479 81594 163479 81608 163479 81608 163480 81594 163480 81592 163480 81608 163481 81592 163481 81467 163481 81467 163482 81592 163482 80451 163482 81609 163483 81351 163483 81606 163483 81606 163484 81351 163484 81607 163484 81606 163485 81607 163485 81610 163485 81610 163486 81607 163486 81608 163486 81610 163487 81608 163487 81472 163487 81472 163488 81608 163488 81467 163488 81353 163489 81609 163489 81628 163489 81628 163490 81609 163490 81606 163490 81628 163491 81606 163491 81629 163491 81629 163492 81606 163492 81610 163492 81629 163493 81610 163493 81473 163493 81473 163494 81610 163494 81472 163494 81622 163495 81602 163495 81499 163495 81619 163496 81601 163496 81611 163496 81598 163497 81600 163497 81618 163497 80294 163498 81598 163498 81612 163498 81612 163499 81598 163499 81618 163499 81612 163500 81618 163500 81613 163500 81613 163501 81618 163501 81614 163501 81613 163502 81614 163502 81615 163502 81615 163503 81614 163503 81621 163503 81615 163504 81621 163504 81616 163504 81616 163505 81621 163505 81617 163505 81600 163506 81619 163506 81618 163506 81618 163507 81619 163507 81611 163507 81618 163508 81611 163508 81614 163508 81614 163509 81611 163509 81623 163509 81614 163510 81623 163510 81621 163510 81621 163511 81623 163511 81620 163511 81621 163512 81620 163512 81617 163512 81617 163513 81620 163513 81634 163513 81601 163514 81622 163514 81611 163514 81611 163515 81622 163515 81499 163515 81611 163516 81499 163516 81623 163516 81623 163517 81499 163517 81624 163517 81623 163518 81624 163518 81620 163518 81620 163519 81624 163519 81625 163519 81620 163520 81625 163520 81634 163520 81634 163521 81625 163521 81637 163521 81626 163522 81353 163522 81627 163522 81627 163523 81353 163523 81628 163523 81627 163524 81628 163524 81631 163524 81631 163525 81628 163525 81629 163525 81631 163526 81629 163526 81630 163526 81630 163527 81629 163527 81473 163527 81639 163528 81626 163528 81640 163528 81640 163529 81626 163529 81627 163529 81640 163530 81627 163530 81641 163530 81641 163531 81627 163531 81631 163531 81641 163532 81631 163532 81463 163532 81463 163533 81631 163533 81630 163533 81632 163534 81616 163534 81649 163534 81649 163535 81616 163535 81617 163535 81649 163536 81617 163536 81650 163536 81650 163537 81617 163537 81633 163537 81633 163538 81617 163538 81634 163538 81633 163539 81634 163539 81635 163539 81635 163540 81634 163540 81636 163540 81636 163541 81634 163541 81637 163541 81636 163542 81637 163542 81352 163542 81350 163543 81639 163543 81638 163543 81638 163544 81639 163544 81640 163544 81638 163545 81640 163545 81643 163545 81643 163546 81640 163546 81641 163546 81643 163547 81641 163547 81462 163547 81462 163548 81641 163548 81463 163548 81645 163549 81350 163549 81642 163549 81642 163550 81350 163550 81638 163550 81642 163551 81638 163551 81646 163551 81646 163552 81638 163552 81643 163552 81646 163553 81643 163553 81644 163553 81644 163554 81643 163554 81462 163554 81348 163555 81645 163555 81656 163555 81656 163556 81645 163556 81642 163556 81656 163557 81642 163557 81658 163557 81658 163558 81642 163558 81646 163558 81658 163559 81646 163559 81374 163559 81374 163560 81646 163560 81644 163560 81648 163561 81651 163561 81632 163561 81647 163562 81636 163562 81349 163562 81349 163563 81636 163563 81352 163563 81632 163564 81649 163564 81648 163564 81648 163565 81649 163565 81650 163565 81648 163566 81650 163566 81653 163566 81653 163567 81650 163567 81633 163567 81653 163568 81633 163568 81647 163568 81647 163569 81633 163569 81635 163569 81647 163570 81635 163570 81636 163570 81494 163571 81651 163571 81652 163571 81652 163572 81651 163572 81648 163572 81652 163573 81648 163573 81668 163573 81668 163574 81648 163574 81653 163574 81668 163575 81653 163575 81654 163575 81654 163576 81653 163576 81647 163576 81654 163577 81647 163577 81667 163577 81667 163578 81647 163578 81349 163578 81664 163579 81348 163579 81656 163579 81664 163580 81656 163580 81655 163580 81655 163581 81656 163581 81658 163581 81655 163582 81658 163582 81657 163582 81657 163583 81658 163583 81374 163583 81657 163584 81374 163584 81659 163584 81660 163585 81661 163585 77391 163585 77391 163586 81661 163586 81669 163586 77391 163587 81669 163587 77426 163587 77426 163588 81669 163588 81662 163588 77426 163589 81662 163589 81663 163589 81666 163590 81347 163590 81664 163590 81664 163591 81673 163591 81666 163591 81666 163592 81673 163592 81665 163592 81666 163593 81665 163593 81662 163593 81662 163594 81665 163594 81672 163594 81662 163595 81672 163595 81663 163595 81667 163596 81347 163596 81654 163596 81654 163597 81347 163597 81666 163597 81654 163598 81666 163598 81668 163598 81668 163599 81666 163599 81662 163599 81668 163600 81662 163600 81652 163600 81652 163601 81662 163601 81669 163601 81652 163602 81669 163602 81494 163602 81494 163603 81669 163603 81661 163603 77426 163604 81663 163604 81674 163604 81375 163605 77429 163605 81677 163605 81655 163606 81657 163606 81676 163606 81673 163607 81664 163607 81670 163607 81670 163608 81664 163608 81655 163608 81655 163609 81676 163609 81670 163609 81670 163610 81676 163610 81675 163610 81670 163611 81675 163611 81671 163611 81671 163612 81672 163612 81670 163612 81670 163613 81672 163613 81665 163613 81670 163614 81665 163614 81673 163614 81663 163615 81672 163615 81674 163615 81674 163616 81672 163616 81671 163616 81674 163617 81671 163617 77427 163617 77427 163618 81671 163618 81675 163618 77427 163619 81675 163619 81677 163619 81677 163620 81675 163620 81676 163620 81677 163621 81676 163621 81375 163621 81375 163622 81676 163622 81657 163622 81375 163623 81657 163623 81659 163623 81678 163624 81679 163624 77365 163624 81518 163625 81680 163625 77411 163625 77411 163626 81680 163626 81683 163626 81681 163627 81684 163627 81689 163627 81689 163628 81684 163628 81688 163628 81679 163629 81678 163629 81687 163629 81685 163630 81682 163630 81686 163630 81689 163631 81683 163631 81681 163631 81681 163632 81683 163632 81680 163632 81681 163633 81680 163633 81684 163633 81684 163634 81680 163634 81685 163634 81685 163635 81686 163635 81684 163635 81684 163636 81686 163636 81687 163636 81684 163637 81687 163637 81688 163637 81688 163638 81687 163638 81678 163638 81688 163639 81678 163639 81689 163639 81680 163640 81518 163640 81692 163640 81492 163641 81682 163641 81696 163641 81696 163642 81682 163642 81685 163642 81692 163643 81690 163643 81680 163643 81680 163644 81690 163644 81691 163644 81680 163645 81691 163645 81685 163645 81685 163646 81691 163646 81695 163646 81685 163647 81695 163647 81696 163647 81697 163648 81703 163648 81492 163648 81690 163649 81692 163649 81693 163649 81693 163650 81698 163650 81690 163650 81690 163651 81698 163651 81700 163651 81690 163652 81700 163652 81691 163652 81700 163653 81694 163653 81691 163653 81691 163654 81694 163654 81701 163654 81691 163655 81701 163655 81695 163655 81695 163656 81701 163656 81697 163656 81695 163657 81697 163657 81696 163657 81696 163658 81697 163658 81492 163658 81693 163659 81699 163659 81698 163659 81698 163660 81699 163660 81707 163660 81698 163661 81707 163661 81700 163661 81700 163662 81707 163662 81694 163662 81694 163663 81707 163663 81702 163663 81694 163664 81702 163664 81701 163664 81701 163665 81702 163665 81697 163665 81697 163666 81702 163666 80274 163666 81697 163667 80274 163667 81703 163667 81718 163668 80282 163668 81713 163668 80274 163669 81702 163669 81711 163669 81715 163670 81716 163670 81704 163670 81702 163671 81707 163671 81708 163671 81705 163672 81706 163672 81710 163672 81707 163673 81699 163673 81345 163673 81707 163674 81345 163674 81708 163674 81708 163675 81345 163675 81709 163675 81708 163676 81709 163676 81710 163676 81710 163677 81709 163677 81346 163677 81710 163678 81346 163678 81705 163678 81702 163679 81708 163679 81711 163679 81711 163680 81708 163680 81710 163680 81711 163681 81710 163681 81704 163681 81704 163682 81710 163682 81706 163682 81704 163683 81706 163683 81715 163683 80274 163684 81711 163684 81712 163684 81712 163685 81711 163685 81704 163685 81712 163686 81704 163686 81713 163686 81713 163687 81704 163687 81716 163687 81713 163688 81716 163688 81718 163688 81719 163689 81720 163689 81346 163689 81346 163690 81720 163690 81705 163690 81705 163691 81720 163691 81706 163691 81706 163692 81720 163692 81714 163692 81706 163693 81714 163693 81715 163693 81715 163694 81714 163694 81722 163694 81715 163695 81722 163695 81716 163695 81716 163696 81722 163696 81723 163696 81716 163697 81723 163697 81718 163697 81723 163698 81717 163698 81718 163698 81718 163699 81717 163699 81724 163699 81718 163700 81724 163700 80282 163700 81719 163701 81341 163701 81720 163701 81720 163702 81341 163702 81721 163702 81720 163703 81721 163703 81714 163703 81714 163704 81721 163704 81722 163704 81722 163705 81721 163705 81725 163705 81722 163706 81725 163706 81723 163706 81723 163707 81725 163707 81717 163707 81717 163708 81725 163708 80283 163708 81717 163709 80283 163709 81724 163709 81341 163710 81729 163710 81721 163710 81721 163711 81729 163711 81727 163711 81721 163712 81727 163712 81725 163712 81725 163713 81727 163713 81726 163713 81725 163714 81726 163714 80283 163714 80283 163715 81726 163715 80284 163715 80266 163716 80284 163716 81726 163716 80266 163717 81726 163717 81728 163717 81728 163718 81726 163718 81727 163718 81728 163719 81727 163719 81735 163719 81735 163720 81727 163720 81729 163720 81735 163721 81729 163721 80235 163721 81734 163722 81730 163722 81731 163722 81731 163723 81730 163723 81740 163723 81731 163724 81740 163724 81732 163724 81732 163725 81740 163725 81738 163725 81732 163726 81738 163726 81733 163726 81733 163727 81738 163727 81475 163727 80235 163728 81734 163728 81735 163728 81735 163729 81734 163729 81731 163729 81735 163730 81731 163730 81728 163730 81728 163731 81731 163731 81732 163731 81728 163732 81732 163732 80266 163732 80266 163733 81732 163733 81733 163733 77369 163734 77368 163734 81370 163734 77369 163735 81370 163735 81736 163735 81737 163736 81738 163736 81740 163736 81730 163737 81739 163737 81740 163737 81740 163738 81739 163738 77374 163738 81740 163739 77374 163739 81737 163739 81737 163740 77374 163740 77372 163740 81737 163741 77372 163741 81736 163741 81736 163742 81370 163742 81737 163742 81737 163743 81370 163743 81475 163743 81737 163744 81475 163744 81738 163744 81408 163745 81760 163745 81741 163745 81741 163746 81760 163746 81761 163746 81741 163747 81761 163747 81746 163747 81746 163748 81761 163748 81742 163748 81746 163749 81742 163749 81743 163749 81743 163750 81742 163750 81763 163750 81743 163751 81763 163751 81744 163751 81744 163752 81763 163752 81764 163752 81804 163753 81408 163753 81768 163753 81768 163754 81408 163754 81741 163754 81768 163755 81741 163755 81745 163755 81745 163756 81741 163756 81746 163756 81745 163757 81746 163757 81775 163757 81775 163758 81746 163758 81743 163758 81775 163759 81743 163759 81522 163759 81522 163760 81743 163760 81744 163760 81747 163761 81748 163761 81758 163761 81756 163762 81754 163762 81410 163762 80463 163763 81749 163763 81750 163763 81750 163764 81749 163764 81759 163764 81750 163765 81759 163765 81751 163765 81751 163766 81759 163766 81757 163766 81410 163767 81752 163767 81756 163767 81756 163768 81752 163768 81776 163768 81756 163769 81776 163769 81757 163769 81757 163770 81776 163770 81753 163770 81757 163771 81753 163771 81751 163771 81409 163772 81754 163772 81762 163772 81762 163773 81754 163773 81756 163773 81762 163774 81756 163774 81755 163774 81755 163775 81756 163775 81757 163775 81755 163776 81757 163776 81758 163776 81758 163777 81757 163777 81759 163777 81758 163778 81759 163778 81747 163778 81747 163779 81759 163779 81749 163779 81760 163780 81409 163780 81761 163780 81761 163781 81409 163781 81762 163781 81761 163782 81762 163782 81742 163782 81742 163783 81762 163783 81755 163783 81742 163784 81755 163784 81763 163784 81763 163785 81755 163785 81758 163785 81763 163786 81758 163786 81764 163786 81764 163787 81758 163787 81748 163787 81765 163788 81774 163788 81772 163788 81766 163789 81779 163789 81767 163789 81767 163790 81779 163790 81770 163790 81769 163791 81768 163791 81745 163791 81768 163792 81769 163792 81804 163792 81777 163793 81771 163793 81770 163793 81770 163794 81771 163794 81765 163794 81770 163795 81765 163795 81767 163795 81767 163796 81765 163796 81772 163796 81767 163797 81772 163797 81766 163797 81766 163798 81772 163798 81524 163798 81766 163799 81524 163799 81773 163799 81773 163800 81524 163800 80329 163800 81522 163801 81774 163801 81775 163801 81775 163802 81774 163802 81765 163802 81775 163803 81765 163803 81745 163803 81745 163804 81765 163804 81771 163804 81745 163805 81771 163805 81769 163805 81769 163806 81771 163806 81777 163806 81793 163807 80463 163807 81750 163807 81793 163808 81750 163808 81794 163808 81750 163809 81751 163809 81794 163809 81794 163810 81751 163810 81753 163810 81794 163811 81753 163811 81800 163811 81410 163812 81411 163812 81752 163812 81752 163813 81411 163813 81800 163813 81752 163814 81800 163814 81776 163814 81776 163815 81800 163815 81753 163815 81777 163816 81770 163816 81785 163816 80328 163817 81773 163817 80329 163817 81773 163818 80328 163818 81778 163818 81779 163819 81766 163819 81778 163819 81778 163820 81766 163820 81773 163820 81770 163821 81779 163821 81785 163821 81785 163822 81779 163822 81778 163822 81785 163823 81778 163823 81780 163823 81780 163824 81778 163824 80328 163824 81780 163825 80328 163825 81786 163825 80325 163826 81781 163826 81783 163826 81783 163827 81781 163827 81782 163827 81783 163828 81782 163828 81784 163828 81769 163829 81777 163829 81784 163829 81784 163830 81777 163830 81785 163830 81784 163831 81785 163831 81783 163831 81783 163832 81785 163832 81780 163832 81783 163833 81780 163833 80325 163833 80325 163834 81780 163834 81786 163834 81804 163835 81769 163835 81787 163835 81787 163836 81769 163836 81784 163836 81787 163837 81784 163837 81807 163837 81807 163838 81784 163838 81782 163838 81807 163839 81782 163839 80309 163839 80309 163840 81782 163840 81781 163840 81795 163841 81788 163841 81790 163841 81809 163842 80455 163842 80465 163842 81809 163843 80465 163843 81811 163843 81811 163844 80465 163844 81788 163844 81788 163845 80465 163845 81789 163845 81788 163846 81789 163846 81790 163846 81790 163847 81789 163847 81791 163847 81790 163848 81791 163848 81792 163848 81792 163849 81791 163849 81793 163849 81792 163850 81793 163850 81794 163850 81795 163851 81790 163851 81798 163851 81798 163852 81790 163852 81792 163852 81798 163853 81792 163853 81799 163853 81799 163854 81792 163854 81794 163854 81799 163855 81794 163855 81800 163855 81815 163856 81814 163856 81795 163856 81795 163857 81814 163857 81813 163857 81795 163858 81813 163858 81788 163858 81788 163859 81813 163859 81812 163859 81788 163860 81812 163860 81811 163860 81815 163861 81795 163861 81796 163861 81796 163862 81795 163862 81798 163862 81796 163863 81798 163863 81797 163863 81797 163864 81798 163864 81799 163864 81797 163865 81799 163865 81498 163865 81498 163866 81799 163866 81800 163866 81498 163867 81800 163867 81411 163867 81831 163868 81801 163868 81829 163868 81829 163869 81801 163869 81805 163869 81829 163870 81805 163870 81802 163870 81802 163871 81805 163871 81824 163871 81824 163872 81805 163872 81806 163872 81824 163873 81806 163873 81819 163873 81819 163874 81806 163874 81808 163874 81819 163875 81808 163875 81803 163875 81801 163876 81804 163876 81787 163876 81801 163877 81787 163877 81805 163877 81805 163878 81787 163878 81807 163878 81805 163879 81807 163879 81806 163879 81806 163880 81807 163880 80309 163880 81806 163881 80309 163881 81808 163881 80455 163882 81809 163882 81836 163882 81836 163883 81809 163883 81837 163883 81837 163884 81809 163884 81810 163884 81810 163885 81809 163885 81811 163885 81810 163886 81811 163886 81840 163886 81840 163887 81811 163887 81812 163887 81840 163888 81812 163888 81842 163888 81842 163889 81812 163889 81813 163889 81842 163890 81813 163890 81816 163890 81813 163891 81814 163891 81816 163891 81816 163892 81814 163892 81815 163892 81816 163893 81815 163893 81845 163893 81802 163894 81824 163894 81827 163894 80323 163895 81846 163895 81817 163895 81817 163896 81846 163896 81820 163896 81817 163897 81820 163897 80321 163897 80321 163898 81820 163898 81822 163898 80321 163899 81822 163899 80322 163899 80322 163900 81822 163900 81818 163900 80322 163901 81818 163901 81803 163901 81803 163902 81818 163902 81819 163902 81846 163903 81847 163903 81820 163903 81820 163904 81847 163904 81821 163904 81820 163905 81821 163905 81822 163905 81822 163906 81821 163906 81823 163906 81822 163907 81823 163907 81818 163907 81818 163908 81823 163908 81827 163908 81818 163909 81827 163909 81819 163909 81819 163910 81827 163910 81824 163910 81847 163911 81849 163911 81821 163911 81821 163912 81849 163912 81825 163912 81821 163913 81825 163913 81823 163913 81823 163914 81825 163914 81826 163914 81823 163915 81826 163915 81827 163915 81827 163916 81826 163916 81828 163916 81827 163917 81828 163917 81802 163917 81802 163918 81828 163918 81829 163918 81849 163919 81495 163919 81825 163919 81825 163920 81495 163920 81830 163920 81825 163921 81830 163921 81826 163921 81826 163922 81830 163922 81496 163922 81826 163923 81496 163923 81828 163923 81828 163924 81496 163924 81497 163924 81828 163925 81497 163925 81829 163925 81829 163926 81497 163926 81831 163926 81832 163927 81834 163927 81833 163927 81838 163928 81833 163928 81469 163928 81469 163929 81833 163929 81834 163929 81469 163930 81834 163930 81468 163930 81835 163931 81841 163931 81843 163931 81836 163932 81837 163932 81838 163932 81838 163933 81837 163933 81835 163933 81838 163934 81835 163934 81833 163934 81833 163935 81835 163935 81843 163935 81833 163936 81843 163936 81832 163936 81832 163937 81843 163937 81839 163937 81837 163938 81810 163938 81835 163938 81835 163939 81810 163939 81840 163939 81835 163940 81840 163940 81841 163940 81841 163941 81840 163941 81842 163941 81841 163942 81842 163942 81816 163942 81839 163943 81843 163943 81844 163943 81844 163944 81843 163944 81841 163944 81844 163945 81841 163945 81356 163945 81356 163946 81841 163946 81816 163946 81356 163947 81816 163947 81845 163947 80323 163948 80324 163948 81846 163948 81846 163949 80324 163949 81863 163949 81846 163950 81863 163950 81847 163950 81847 163951 81863 163951 81848 163951 81847 163952 81848 163952 81849 163952 81849 163953 81848 163953 81865 163953 81849 163954 81865 163954 81495 163954 81495 163955 81865 163955 81866 163955 81850 163956 81354 163956 81856 163956 81856 163957 81354 163957 81851 163957 81856 163958 81851 163958 81852 163958 81852 163959 81851 163959 81853 163959 81852 163960 81853 163960 81854 163960 81854 163961 81853 163961 81855 163961 81839 163962 81850 163962 81832 163962 81832 163963 81850 163963 81856 163963 81832 163964 81856 163964 81834 163964 81834 163965 81856 163965 81852 163965 81834 163966 81852 163966 81468 163966 81468 163967 81852 163967 81854 163967 81857 163968 81858 163968 81859 163968 81859 163969 81858 163969 81883 163969 81859 163970 81883 163970 81864 163970 81864 163971 81883 163971 81860 163971 81864 163972 81860 163972 81861 163972 81861 163973 81860 163973 81862 163973 81861 163974 81862 163974 81867 163974 81867 163975 81862 163975 81355 163975 80324 163976 81857 163976 81863 163976 81863 163977 81857 163977 81859 163977 81863 163978 81859 163978 81848 163978 81848 163979 81859 163979 81864 163979 81848 163980 81864 163980 81865 163980 81865 163981 81864 163981 81861 163981 81865 163982 81861 163982 81866 163982 81866 163983 81861 163983 81867 163983 81868 163984 81869 163984 81872 163984 81872 163985 81869 163985 81888 163985 81872 163986 81888 163986 81874 163986 81874 163987 81888 163987 81886 163987 81874 163988 81886 163988 81870 163988 81870 163989 81886 163989 81885 163989 81871 163990 81868 163990 81875 163990 81875 163991 81868 163991 81872 163991 81875 163992 81872 163992 81873 163992 81873 163993 81872 163993 81874 163993 81873 163994 81874 163994 81465 163994 81465 163995 81874 163995 81870 163995 81354 163996 81871 163996 81851 163996 81851 163997 81871 163997 81875 163997 81851 163998 81875 163998 81853 163998 81853 163999 81875 163999 81873 163999 81853 164000 81873 164000 81855 164000 81855 164001 81873 164001 81465 164001 81880 164002 81876 164002 81884 164002 81884 164003 81876 164003 81890 164003 81884 164004 81890 164004 81877 164004 81878 164005 81879 164005 81880 164005 81880 164006 81879 164006 81895 164006 81880 164007 81895 164007 81876 164007 81882 164008 81364 164008 81878 164008 81878 164009 81364 164009 77408 164009 77408 164010 77407 164010 81878 164010 81878 164011 77407 164011 81881 164011 81878 164012 81881 164012 81879 164012 81858 164013 81882 164013 81883 164013 81883 164014 81882 164014 81878 164014 81883 164015 81878 164015 81860 164015 81860 164016 81878 164016 81880 164016 81860 164017 81880 164017 81862 164017 81862 164018 81880 164018 81884 164018 81862 164019 81884 164019 81355 164019 81355 164020 81884 164020 81877 164020 81897 164021 81885 164021 81886 164021 81897 164022 81886 164022 81887 164022 81887 164023 81886 164023 81888 164023 81887 164024 81888 164024 81889 164024 81889 164025 81888 164025 81869 164025 81889 164026 81869 164026 81890 164026 81894 164027 81876 164027 81895 164027 81896 164028 77437 164028 81893 164028 81893 164029 77437 164029 81892 164029 81372 164030 81371 164030 77433 164030 77433 164031 81371 164031 81891 164031 77433 164032 81891 164032 77434 164032 77434 164033 81891 164033 81892 164033 81892 164034 81891 164034 81894 164034 81892 164035 81894 164035 81893 164035 81893 164036 81894 164036 81895 164036 81893 164037 81895 164037 81896 164037 81896 164038 81895 164038 81879 164038 81896 164039 81879 164039 81881 164039 81890 164040 81876 164040 81889 164040 81889 164041 81876 164041 81894 164041 81889 164042 81894 164042 81887 164042 81887 164043 81894 164043 81891 164043 81887 164044 81891 164044 81897 164044 81897 164045 81891 164045 81371 164045 81456 164046 81898 164046 80953 164046 80953 164047 81898 164047 81899 164047 80953 164048 81899 164048 81900 164048 81900 164049 81899 164049 81901 164049 81900 164050 81901 164050 80293 164050 80293 164051 81901 164051 81903 164051 81898 164052 81458 164052 81899 164052 81899 164053 81458 164053 81902 164053 81899 164054 81902 164054 81901 164054 81901 164055 81902 164055 81904 164055 81901 164056 81904 164056 81903 164056 81903 164057 81904 164057 81905 164057 81458 164058 81390 164058 81902 164058 81902 164059 81390 164059 81907 164059 81902 164060 81907 164060 81904 164060 81904 164061 81907 164061 81910 164061 81904 164062 81910 164062 81905 164062 81905 164063 81910 164063 81906 164063 81914 164064 81908 164064 81390 164064 81390 164065 81908 164065 81907 164065 81908 164066 81909 164066 81907 164066 81907 164067 81909 164067 81913 164067 81907 164068 81913 164068 81910 164068 81916 164069 81906 164069 81911 164069 81911 164070 81906 164070 81910 164070 81911 164071 81910 164071 81912 164071 81912 164072 81910 164072 81913 164072 81920 164073 81918 164073 81913 164073 81914 164074 81915 164074 81908 164074 81908 164075 81915 164075 81920 164075 81908 164076 81920 164076 81909 164076 81909 164077 81920 164077 81913 164077 81525 164078 81916 164078 81917 164078 81917 164079 81916 164079 81911 164079 81917 164080 81911 164080 81918 164080 81918 164081 81911 164081 81912 164081 81918 164082 81912 164082 81913 164082 81444 164083 81525 164083 81921 164083 81921 164084 81525 164084 81917 164084 81921 164085 81917 164085 81922 164085 81922 164086 81917 164086 81918 164086 81922 164087 81918 164087 81919 164087 81919 164088 81918 164088 81920 164088 81919 164089 81920 164089 81389 164089 81389 164090 81920 164090 81915 164090 81445 164091 81444 164091 81921 164091 81445 164092 81921 164092 81931 164092 81931 164093 81921 164093 81922 164093 81931 164094 81922 164094 81923 164094 81923 164095 81922 164095 81919 164095 81923 164096 81919 164096 81929 164096 81929 164097 81919 164097 81389 164097 81929 164098 81389 164098 81927 164098 81928 164099 81451 164099 81930 164099 81930 164100 81451 164100 81924 164100 81930 164101 81924 164101 81932 164101 81932 164102 81924 164102 81934 164102 81932 164103 81934 164103 81925 164103 81925 164104 81934 164104 81937 164104 81925 164105 81937 164105 81448 164105 81448 164106 81937 164106 81926 164106 81927 164107 81928 164107 81929 164107 81929 164108 81928 164108 81930 164108 81929 164109 81930 164109 81923 164109 81923 164110 81930 164110 81932 164110 81923 164111 81932 164111 81931 164111 81931 164112 81932 164112 81925 164112 81931 164113 81925 164113 81445 164113 81445 164114 81925 164114 81448 164114 81452 164115 81450 164115 81935 164115 81935 164116 81450 164116 81946 164116 81935 164117 81946 164117 81936 164117 81936 164118 81946 164118 81948 164118 81936 164119 81948 164119 81938 164119 81938 164120 81948 164120 81933 164120 81938 164121 81933 164121 81939 164121 81939 164122 81933 164122 81950 164122 81451 164123 81452 164123 81924 164123 81924 164124 81452 164124 81935 164124 81924 164125 81935 164125 81934 164125 81934 164126 81935 164126 81936 164126 81934 164127 81936 164127 81937 164127 81937 164128 81936 164128 81938 164128 81937 164129 81938 164129 81926 164129 81926 164130 81938 164130 81939 164130 81943 164131 81947 164131 81951 164131 81520 164132 81940 164132 81953 164132 81953 164133 81940 164133 81942 164133 81953 164134 81942 164134 81941 164134 81941 164135 81942 164135 81949 164135 81951 164136 81952 164136 81943 164136 81943 164137 81952 164137 81944 164137 81943 164138 81944 164138 81949 164138 81949 164139 81944 164139 81945 164139 81949 164140 81945 164140 81941 164140 81450 164141 81947 164141 81946 164141 81946 164142 81947 164142 81943 164142 81946 164143 81943 164143 81948 164143 81948 164144 81943 164144 81949 164144 81948 164145 81949 164145 81933 164145 81933 164146 81949 164146 81942 164146 81933 164147 81942 164147 81950 164147 81950 164148 81942 164148 81940 164148 81951 164149 81392 164149 81952 164149 81952 164150 81392 164150 81028 164150 81952 164151 81028 164151 81944 164151 81944 164152 81028 164152 81945 164152 81945 164153 81028 164153 81023 164153 81945 164154 81023 164154 81941 164154 81941 164155 81023 164155 81953 164155 81953 164156 81023 164156 81954 164156 81953 164157 81954 164157 81520 164157 81029 164158 81393 164158 81955 164158 81955 164159 81393 164159 81956 164159 81955 164160 81956 164160 81957 164160 81957 164161 81956 164161 81958 164161 81957 164162 81958 164162 81959 164162 81959 164163 81958 164163 81960 164163 81959 164164 81960 164164 81031 164164 81031 164165 81960 164165 81519 164165 81961 164166 81962 164166 81973 164166 81965 164167 81399 164167 81398 164167 81442 164168 81963 164168 81976 164168 81976 164169 81963 164169 81972 164169 81976 164170 81972 164170 81964 164170 81964 164171 81972 164171 81968 164171 81398 164172 81974 164172 81965 164172 81965 164173 81974 164173 81966 164173 81965 164174 81966 164174 81968 164174 81968 164175 81966 164175 81967 164175 81968 164176 81967 164176 81964 164176 81969 164177 81399 164177 81970 164177 81970 164178 81399 164178 81965 164178 81970 164179 81965 164179 81971 164179 81971 164180 81965 164180 81968 164180 81971 164181 81968 164181 81973 164181 81973 164182 81968 164182 81972 164182 81973 164183 81972 164183 81961 164183 81961 164184 81972 164184 81963 164184 81393 164185 81969 164185 81956 164185 81956 164186 81969 164186 81970 164186 81956 164187 81970 164187 81958 164187 81958 164188 81970 164188 81971 164188 81958 164189 81971 164189 81960 164189 81960 164190 81971 164190 81973 164190 81960 164191 81973 164191 81519 164191 81519 164192 81973 164192 81962 164192 81398 164193 81397 164193 81974 164193 81974 164194 81397 164194 81977 164194 81974 164195 81977 164195 81966 164195 81966 164196 81977 164196 81967 164196 81967 164197 81977 164197 81975 164197 81967 164198 81975 164198 81964 164198 81964 164199 81975 164199 81976 164199 81976 164200 81975 164200 81443 164200 81976 164201 81443 164201 81442 164201 81979 164202 81443 164202 81980 164202 81980 164203 81443 164203 81975 164203 81980 164204 81975 164204 81985 164204 81985 164205 81975 164205 81977 164205 81985 164206 81977 164206 81395 164206 81395 164207 81977 164207 81397 164207 81978 164208 81979 164208 81981 164208 81981 164209 81979 164209 81980 164209 81981 164210 81980 164210 81984 164210 81984 164211 81980 164211 81985 164211 81523 164212 81978 164212 81987 164212 81987 164213 81978 164213 81981 164213 81987 164214 81981 164214 81989 164214 81989 164215 81981 164215 81984 164215 81994 164216 81989 164216 81982 164216 81982 164217 81989 164217 81984 164217 81982 164218 81984 164218 81983 164218 81983 164219 81984 164219 81985 164219 81983 164220 81985 164220 81395 164220 80330 164221 81523 164221 81986 164221 81986 164222 81523 164222 81987 164222 81986 164223 81987 164223 81988 164223 81988 164224 81987 164224 81989 164224 81988 164225 81989 164225 81993 164225 81993 164226 81989 164226 81994 164226 80330 164227 81986 164227 81990 164227 81990 164228 81986 164228 81991 164228 81991 164229 81986 164229 81992 164229 81992 164230 81986 164230 81988 164230 81992 164231 81988 164231 82000 164231 82000 164232 81988 164232 81998 164232 81998 164233 81988 164233 81993 164233 81998 164234 81993 164234 81996 164234 81996 164235 81993 164235 81994 164235 81996 164236 81994 164236 81995 164236 81995 164237 81997 164237 81996 164237 81996 164238 81997 164238 82001 164238 81996 164239 82001 164239 81998 164239 81998 164240 82001 164240 82000 164240 82000 164241 82001 164241 81999 164241 82000 164242 81999 164242 81992 164242 81992 164243 81999 164243 81991 164243 81991 164244 81999 164244 82003 164244 81991 164245 82003 164245 81990 164245 81997 164246 82004 164246 82001 164246 82001 164247 82004 164247 82002 164247 82001 164248 82002 164248 81999 164248 81999 164249 82002 164249 82006 164249 81999 164250 82006 164250 82003 164250 82003 164251 82006 164251 82008 164251 82004 164252 81339 164252 82005 164252 82004 164253 82005 164253 82002 164253 82002 164254 82005 164254 82007 164254 82002 164255 82007 164255 82006 164255 82006 164256 82007 164256 82011 164256 82006 164257 82011 164257 82008 164257 81339 164258 81453 164258 82005 164258 82005 164259 81453 164259 82009 164259 82005 164260 82009 164260 82007 164260 82007 164261 82009 164261 82010 164261 82007 164262 82010 164262 82011 164262 82011 164263 82010 164263 80331 164263 81453 164264 82012 164264 82009 164264 82009 164265 82012 164265 82013 164265 82009 164266 82013 164266 82010 164266 82010 164267 82013 164267 82014 164267 82010 164268 82014 164268 80331 164268 80331 164269 82014 164269 82015 164269 82012 164270 81455 164270 82013 164270 82013 164271 81455 164271 81110 164271 82013 164272 81110 164272 82014 164272 82014 164273 81110 164273 81108 164273 82014 164274 81108 164274 82015 164274 82015 164275 81108 164275 80311 164275 81504 164276 82033 164276 82016 164276 81501 164277 82018 164277 82017 164277 82017 164278 82018 164278 82019 164278 82017 164279 82019 164279 82020 164279 82020 164280 82019 164280 82026 164280 82020 164281 82026 164281 82025 164281 81501 164282 82017 164282 82021 164282 82021 164283 82017 164283 82020 164283 82021 164284 82020 164284 82022 164284 82022 164285 82020 164285 82025 164285 82022 164286 82025 164286 81490 164286 81504 164287 82016 164287 82027 164287 82023 164288 81490 164288 82024 164288 82024 164289 81490 164289 82025 164289 82024 164290 82025 164290 82016 164290 82016 164291 82025 164291 82026 164291 82016 164292 82026 164292 82027 164292 82027 164293 82026 164293 82019 164293 82027 164294 82019 164294 82028 164294 82028 164295 82019 164295 82018 164295 82028 164296 82018 164296 81502 164296 81502 164297 82018 164297 81501 164297 81506 164298 82029 164298 82031 164298 82031 164299 82029 164299 82030 164299 82031 164300 82030 164300 82032 164300 82032 164301 82030 164301 82039 164301 82032 164302 82039 164302 82034 164302 82034 164303 82039 164303 81376 164303 82033 164304 81506 164304 82016 164304 82016 164305 81506 164305 82031 164305 82016 164306 82031 164306 82024 164306 82024 164307 82031 164307 82032 164307 82024 164308 82032 164308 82023 164308 82023 164309 82032 164309 82034 164309 82038 164310 82035 164310 81376 164310 81376 164311 82035 164311 77438 164311 81376 164312 77438 164312 82036 164312 82029 164313 82037 164313 82030 164313 82030 164314 82037 164314 82038 164314 82030 164315 82038 164315 82039 164315 82039 164316 82038 164316 81376 164316 82040 164317 81479 164317 82044 164317 82044 164318 81479 164318 82041 164318 82044 164319 82041 164319 82045 164319 82045 164320 82041 164320 82042 164320 82045 164321 82042 164321 82046 164321 82040 164322 82044 164322 82043 164322 82043 164323 82044 164323 82045 164323 82043 164324 82045 164324 82047 164324 82047 164325 82045 164325 82046 164325 82047 164326 82046 164326 82050 164326 81511 164327 82048 164327 82050 164327 82050 164328 82048 164328 82049 164328 82050 164329 82049 164329 82047 164329 82047 164330 82049 164330 82051 164330 82047 164331 82051 164331 82043 164331 82043 164332 82051 164332 82040 164332 81508 164333 81511 164333 82054 164333 82054 164334 81511 164334 82050 164334 82054 164335 82050 164335 82056 164335 82056 164336 82050 164336 82046 164336 82056 164337 82046 164337 82052 164337 82052 164338 82046 164338 82042 164338 81510 164339 81508 164339 82053 164339 82053 164340 81508 164340 82054 164340 82053 164341 82054 164341 82055 164341 82055 164342 82054 164342 82056 164342 82055 164343 82056 164343 81378 164343 81378 164344 82056 164344 82052 164344 82057 164345 81510 164345 82060 164345 82060 164346 81510 164346 82053 164346 82060 164347 82053 164347 82059 164347 82059 164348 82053 164348 82055 164348 82059 164349 82055 164349 82058 164349 82058 164350 82055 164350 81378 164350 77380 164351 82060 164351 82059 164351 82060 164352 77380 164352 82057 164352 81377 164353 77381 164353 82058 164353 82058 164354 77381 164354 77382 164354 82058 164355 77382 164355 82059 164355 82059 164356 77382 164356 77378 164356 82059 164357 77378 164357 77380 164357 82064 164358 83690 164358 82063 164358 83690 164359 83691 164359 82063 164359 82063 164360 83691 164360 82061 164360 82063 164361 82061 164361 81385 164361 81385 164362 82061 164362 82062 164362 81385 164363 82062 164363 81387 164363 82063 164364 82144 164364 82064 164364 82064 164365 82144 164365 82065 164365 82064 164366 82065 164366 82067 164366 77789 164367 77882 164367 82065 164367 82065 164368 77882 164368 82066 164368 82065 164369 82066 164369 82067 164369 82068 164370 82134 164370 82116 164370 82068 164371 82116 164371 82069 164371 82069 164372 82116 164372 82115 164372 82069 164373 82115 164373 82070 164373 82070 164374 82115 164374 82072 164374 82070 164375 82072 164375 82071 164375 82071 164376 82072 164376 82113 164376 82071 164377 82113 164377 77784 164377 81328 164378 82073 164378 82076 164378 82076 164379 82073 164379 82107 164379 82107 164380 82073 164380 80379 164380 82107 164381 80379 164381 80389 164381 82074 164382 82075 164382 82076 164382 82076 164383 82075 164383 82077 164383 82076 164384 82077 164384 81328 164384 81323 164385 82078 164385 80305 164385 80305 164386 82078 164386 81322 164386 80305 164387 81322 164387 82074 164387 82074 164388 81322 164388 81324 164388 82074 164389 81324 164389 82075 164389 82079 164390 82219 164390 81319 164390 81319 164391 82080 164391 82079 164391 82079 164392 82080 164392 82081 164392 82079 164393 82081 164393 82082 164393 82202 164394 77768 164394 82083 164394 82083 164395 77768 164395 80432 164395 82083 164396 80432 164396 82084 164396 82084 164397 81312 164397 82083 164397 82083 164398 81312 164398 82085 164398 82083 164399 82085 164399 82219 164399 82219 164400 82085 164400 81314 164400 82219 164401 81314 164401 81319 164401 77770 164402 82086 164402 82186 164402 77770 164403 82186 164403 82087 164403 82087 164404 82186 164404 82188 164404 82087 164405 82188 164405 82088 164405 82088 164406 82188 164406 82189 164406 82088 164407 82189 164407 78223 164407 78223 164408 82189 164408 82172 164408 78223 164409 82172 164409 78224 164409 77778 164410 82089 164410 83863 164410 83863 164411 82089 164411 82090 164411 83863 164412 82090 164412 83864 164412 83864 164413 82090 164413 82091 164413 82091 164414 82090 164414 82159 164414 82091 164415 82159 164415 82092 164415 82092 164416 82159 164416 82093 164416 82093 164417 82159 164417 82163 164417 82093 164418 82163 164418 82094 164418 82174 164419 81380 164419 82163 164419 82163 164420 81380 164420 83862 164420 82163 164421 83862 164421 82094 164421 80305 164422 82074 164422 82110 164422 82110 164423 82074 164423 82098 164423 82110 164424 82098 164424 82095 164424 82095 164425 82098 164425 82096 164425 82095 164426 82096 164426 82097 164426 82097 164427 82096 164427 82101 164427 82074 164428 82076 164428 82098 164428 82098 164429 82076 164429 82099 164429 82098 164430 82099 164430 82096 164430 82096 164431 82099 164431 82100 164431 82096 164432 82100 164432 82101 164432 82101 164433 82100 164433 82103 164433 82076 164434 82107 164434 82099 164434 82099 164435 82107 164435 82102 164435 82099 164436 82102 164436 82100 164436 82100 164437 82102 164437 82106 164437 82100 164438 82106 164438 82103 164438 82103 164439 82106 164439 82105 164439 82104 164440 82105 164440 82106 164440 82104 164441 82106 164441 82111 164441 82111 164442 82106 164442 82102 164442 82111 164443 82102 164443 82112 164443 82112 164444 82102 164444 82107 164444 82112 164445 82107 164445 82113 164445 82097 164446 81406 164446 82108 164446 82097 164447 82108 164447 82095 164447 82095 164448 82108 164448 82109 164448 82095 164449 82109 164449 82110 164449 82110 164450 82109 164450 80307 164450 82110 164451 80307 164451 80305 164451 82104 164452 82111 164452 82122 164452 82111 164453 82112 164453 82114 164453 82112 164454 82113 164454 82072 164454 82112 164455 82072 164455 82114 164455 82114 164456 82072 164456 82115 164456 82114 164457 82115 164457 82118 164457 82118 164458 82115 164458 82116 164458 82118 164459 82116 164459 82119 164459 82119 164460 82116 164460 82134 164460 82119 164461 82134 164461 82135 164461 82111 164462 82114 164462 82122 164462 82122 164463 82114 164463 82118 164463 82122 164464 82118 164464 82117 164464 82117 164465 82118 164465 82119 164465 82117 164466 82119 164466 82124 164466 82124 164467 82119 164467 82135 164467 82124 164468 82135 164468 82120 164468 82104 164469 82122 164469 82121 164469 82121 164470 82122 164470 82117 164470 82121 164471 82117 164471 82123 164471 82123 164472 82117 164472 82124 164472 82123 164473 82124 164473 82125 164473 82125 164474 82124 164474 82120 164474 82125 164475 82120 164475 81405 164475 82126 164476 82132 164476 82129 164476 82139 164477 81503 164477 82137 164477 82137 164478 81503 164478 82127 164478 82137 164479 82127 164479 82136 164479 82136 164480 82127 164480 82128 164480 82136 164481 82128 164481 81407 164481 81407 164482 82128 164482 82131 164482 81503 164483 82126 164483 82127 164483 82127 164484 82126 164484 82129 164484 82127 164485 82129 164485 82128 164485 82128 164486 82129 164486 82130 164486 82128 164487 82130 164487 82131 164487 82131 164488 82130 164488 82133 164488 82132 164489 80307 164489 82129 164489 82129 164490 80307 164490 82109 164490 82129 164491 82109 164491 82130 164491 82130 164492 82109 164492 82108 164492 82130 164493 82108 164493 82133 164493 82133 164494 82108 164494 81406 164494 82134 164495 77789 164495 82141 164495 82134 164496 82141 164496 82135 164496 82135 164497 82141 164497 82142 164497 82135 164498 82142 164498 82120 164498 82120 164499 82142 164499 81403 164499 82120 164500 81403 164500 81405 164500 81407 164501 81401 164501 83900 164501 81407 164502 83900 164502 82136 164502 82136 164503 83900 164503 83899 164503 82136 164504 83899 164504 82137 164504 82137 164505 83899 164505 82138 164505 82137 164506 82138 164506 82139 164506 82144 164507 82063 164507 82140 164507 77789 164508 82065 164508 82141 164508 82141 164509 82065 164509 82145 164509 82141 164510 82145 164510 82142 164510 82142 164511 82145 164511 82143 164511 82142 164512 82143 164512 81403 164512 81403 164513 82143 164513 82147 164513 82065 164514 82144 164514 82145 164514 82145 164515 82144 164515 82140 164515 82145 164516 82140 164516 82143 164516 82143 164517 82140 164517 82146 164517 82143 164518 82146 164518 82147 164518 82147 164519 82146 164519 81402 164519 82063 164520 81385 164520 82140 164520 82140 164521 81385 164521 82148 164521 82140 164522 82148 164522 82146 164522 82146 164523 82148 164523 77740 164523 82146 164524 77740 164524 81402 164524 81402 164525 77740 164525 81404 164525 82149 164526 82150 164526 82151 164526 82151 164527 82150 164527 82152 164527 82151 164528 82152 164528 82153 164528 82153 164529 82152 164529 82156 164529 82158 164530 82154 164530 82156 164530 82156 164531 82154 164531 82171 164531 82156 164532 82171 164532 82153 164532 82090 164533 82089 164533 82158 164533 82158 164534 82089 164534 82173 164534 82158 164535 82173 164535 82154 164535 82150 164536 82155 164536 82152 164536 82152 164537 82155 164537 82160 164537 82152 164538 82160 164538 82156 164538 82156 164539 82160 164539 82157 164539 82156 164540 82157 164540 82158 164540 82158 164541 82157 164541 82162 164541 82158 164542 82162 164542 82090 164542 82090 164543 82162 164543 82159 164543 82155 164544 82164 164544 82160 164544 82160 164545 82164 164545 82161 164545 82160 164546 82161 164546 82157 164546 82157 164547 82161 164547 82167 164547 82157 164548 82167 164548 82162 164548 82162 164549 82167 164549 82169 164549 82162 164550 82169 164550 82159 164550 82159 164551 82169 164551 82163 164551 82164 164552 82165 164552 82161 164552 82161 164553 82165 164553 82177 164553 82161 164554 82177 164554 82167 164554 82167 164555 82177 164555 82166 164555 82167 164556 82166 164556 82169 164556 82169 164557 82166 164557 82168 164557 82169 164558 82168 164558 82163 164558 82163 164559 82168 164559 82174 164559 82170 164560 82149 164560 82151 164560 82170 164561 82151 164561 82185 164561 82185 164562 82151 164562 82153 164562 82185 164563 82153 164563 82190 164563 82153 164564 82171 164564 82190 164564 82190 164565 82171 164565 82154 164565 82190 164566 82154 164566 82172 164566 82172 164567 82154 164567 82173 164567 82172 164568 82173 164568 82089 164568 82175 164569 82174 164569 82168 164569 82175 164570 82168 164570 83867 164570 83867 164571 82168 164571 82166 164571 83867 164572 82166 164572 83868 164572 83868 164573 82166 164573 82177 164573 83868 164574 82177 164574 82176 164574 82176 164575 82177 164575 82165 164575 82176 164576 82165 164576 81330 164576 82086 164577 82204 164577 82182 164577 82204 164578 82205 164578 82178 164578 82205 164579 81336 164579 81337 164579 82205 164580 81337 164580 82178 164580 82178 164581 81337 164581 82179 164581 82178 164582 82179 164582 82181 164582 82181 164583 82179 164583 82180 164583 82181 164584 82180 164584 82184 164584 82184 164585 82180 164585 82170 164585 82184 164586 82170 164586 82185 164586 82204 164587 82178 164587 82182 164587 82182 164588 82178 164588 82181 164588 82182 164589 82181 164589 82187 164589 82187 164590 82181 164590 82184 164590 82187 164591 82184 164591 82183 164591 82183 164592 82184 164592 82185 164592 82183 164593 82185 164593 82190 164593 82086 164594 82182 164594 82186 164594 82186 164595 82182 164595 82187 164595 82186 164596 82187 164596 82188 164596 82188 164597 82187 164597 82183 164597 82188 164598 82183 164598 82189 164598 82189 164599 82183 164599 82190 164599 82189 164600 82190 164600 82172 164600 81334 164601 82191 164601 81331 164601 81331 164602 82191 164602 82197 164602 81335 164603 82192 164603 77764 164603 77764 164604 82192 164604 82194 164604 77764 164605 82194 164605 82193 164605 82193 164606 82194 164606 82195 164606 82192 164607 81331 164607 82194 164607 82194 164608 81331 164608 82197 164608 82194 164609 82197 164609 82195 164609 82195 164610 82197 164610 82198 164610 82196 164611 81507 164611 82195 164611 82195 164612 81507 164612 77762 164612 82195 164613 77762 164613 82193 164613 82191 164614 82211 164614 82197 164614 82197 164615 82211 164615 82209 164615 82197 164616 82209 164616 82198 164616 82198 164617 82209 164617 82207 164617 82198 164618 82207 164618 82200 164618 82196 164619 82195 164619 82199 164619 82199 164620 82195 164620 82198 164620 82199 164621 82198 164621 81512 164621 81512 164622 82198 164622 82200 164622 81512 164623 82200 164623 82201 164623 82086 164624 82202 164624 82203 164624 82086 164625 82203 164625 82204 164625 82204 164626 82203 164626 82221 164626 82204 164627 82221 164627 82205 164627 82205 164628 82221 164628 82206 164628 82205 164629 82206 164629 81336 164629 82201 164630 82200 164630 82079 164630 82079 164631 82200 164631 82215 164631 82215 164632 82200 164632 82208 164632 82208 164633 82200 164633 82207 164633 82208 164634 82207 164634 82214 164634 82214 164635 82207 164635 82209 164635 82214 164636 82209 164636 82210 164636 82210 164637 82209 164637 82211 164637 82210 164638 82211 164638 82212 164638 82211 164639 82191 164639 82212 164639 82212 164640 82191 164640 81334 164640 82212 164641 81334 164641 81333 164641 81333 164642 81332 164642 82212 164642 82212 164643 81332 164643 82213 164643 82212 164644 82213 164644 82210 164644 82210 164645 82213 164645 82214 164645 82214 164646 82213 164646 82218 164646 82214 164647 82218 164647 82208 164647 82208 164648 82218 164648 82215 164648 82215 164649 82218 164649 82219 164649 82215 164650 82219 164650 82079 164650 81332 164651 82216 164651 82213 164651 82213 164652 82216 164652 82220 164652 82213 164653 82220 164653 82218 164653 82218 164654 82220 164654 82217 164654 82218 164655 82217 164655 82219 164655 82219 164656 82217 164656 82083 164656 82216 164657 82206 164657 82220 164657 82220 164658 82206 164658 82221 164658 82220 164659 82221 164659 82217 164659 82217 164660 82221 164660 82203 164660 82217 164661 82203 164661 82083 164661 82083 164662 82203 164662 82202 164662 82222 164663 77828 164663 77827 164663 77827 164664 77937 164664 82222 164664 82222 164665 77937 164665 82223 164665 82222 164666 82223 164666 82225 164666 82225 164667 82223 164667 82224 164667 82224 164668 77829 164668 82225 164668 82225 164669 77829 164669 82226 164669 82225 164670 82226 164670 77830 164670 82230 164671 82227 164671 77476 164671 77834 164672 82228 164672 82259 164672 82259 164673 82228 164673 82229 164673 82229 164674 78059 164674 82259 164674 82259 164675 78059 164675 78058 164675 82259 164676 78058 164676 77476 164676 77476 164677 78058 164677 78057 164677 77476 164678 78057 164678 82230 164678 77516 164679 77514 164679 77826 164679 77826 164680 77514 164680 77583 164680 77826 164681 77583 164681 77825 164681 77825 164682 77583 164682 82231 164682 82231 164683 82232 164683 77825 164683 77825 164684 82232 164684 77488 164684 77825 164685 77488 164685 82233 164685 82233 164686 77488 164686 77486 164686 82233 164687 77486 164687 77837 164687 77654 164688 77647 164688 78228 164688 78228 164689 77647 164689 82234 164689 78228 164690 82234 164690 78226 164690 78226 164691 82234 164691 77645 164691 78226 164692 77645 164692 77624 164692 77590 164693 77480 164693 82994 164693 77590 164694 82994 164694 77609 164694 77609 164695 82994 164695 77831 164695 77609 164696 77831 164696 82238 164696 82255 164697 82235 164697 77873 164697 77873 164698 82235 164698 82236 164698 77873 164699 82236 164699 77831 164699 77831 164700 82236 164700 82237 164700 77831 164701 82237 164701 82238 164701 82239 164702 82240 164702 82253 164702 82253 164703 82240 164703 83685 164703 82253 164704 83685 164704 78230 164704 82241 164705 82242 164705 82261 164705 82261 164706 82242 164706 78213 164706 78213 164707 78215 164707 82261 164707 82261 164708 78215 164708 78216 164708 82261 164709 78216 164709 77672 164709 77672 164710 78216 164710 78217 164710 78217 164711 78218 164711 77672 164711 77672 164712 78218 164712 78230 164712 77672 164713 78230 164713 83689 164713 83689 164714 78230 164714 83685 164714 82246 164715 77675 164715 82986 164715 82245 164716 78235 164716 82243 164716 82243 164717 82244 164717 82245 164717 82245 164718 82244 164718 82246 164718 82245 164719 82246 164719 82985 164719 82985 164720 82246 164720 82986 164720 82247 164721 82248 164721 78234 164721 78234 164722 82248 164722 82243 164722 78234 164723 82243 164723 82249 164723 82249 164724 82243 164724 78235 164724 82247 164725 78233 164725 82248 164725 82248 164726 78233 164726 78232 164726 82248 164727 78232 164727 78231 164727 78226 164728 77624 164728 78220 164728 78220 164729 77624 164729 77635 164729 78220 164730 77635 164730 78221 164730 78221 164731 77635 164731 82250 164731 78221 164732 82250 164732 82251 164732 82251 164733 82250 164733 82252 164733 82251 164734 82252 164734 82253 164734 82253 164735 82252 164735 82239 164735 82235 164736 82255 164736 82254 164736 82254 164737 82255 164737 82256 164737 82254 164738 82256 164738 77475 164738 77475 164739 82256 164739 82258 164739 77475 164740 82258 164740 82257 164740 82257 164741 82258 164741 77833 164741 82257 164742 77833 164742 82259 164742 82259 164743 77833 164743 77834 164743 82260 164744 77627 164744 78211 164744 78211 164745 77627 164745 77625 164745 78211 164746 77625 164746 78210 164746 78210 164747 77625 164747 77657 164747 78210 164748 77657 164748 77656 164748 82241 164749 82261 164749 78212 164749 78212 164750 82261 164750 82263 164750 78212 164751 82263 164751 82262 164751 82262 164752 82263 164752 77670 164752 82262 164753 77670 164753 78211 164753 78211 164754 77670 164754 82260 164754 77476 164755 82227 164755 77477 164755 77477 164756 82227 164756 82264 164756 77477 164757 82264 164757 77485 164757 77485 164758 82264 164758 77836 164758 77485 164759 77836 164759 82265 164759 82265 164760 77836 164760 77838 164760 82265 164761 77838 164761 77486 164761 77486 164762 77838 164762 77837 164762 77547 164763 83767 164763 82266 164763 82266 164764 83767 164764 83766 164764 82266 164765 83766 164765 77544 164765 82368 164766 82267 164766 82268 164766 82268 164767 82267 164767 82363 164767 82485 164768 82269 164768 82491 164768 82491 164769 82269 164769 78266 164769 82495 164770 82270 164770 82497 164770 82497 164771 82270 164771 82271 164771 82500 164772 82272 164772 82273 164772 82273 164773 82272 164773 82365 164773 82498 164774 82501 164774 82496 164774 82496 164775 82501 164775 82492 164775 82274 164776 82490 164776 82488 164776 82488 164777 82490 164777 82275 164777 82488 164778 82275 164778 82486 164778 82275 164779 82481 164779 82281 164779 82276 164780 82281 164780 82483 164780 82483 164781 82281 164781 82481 164781 82483 164782 82481 164782 82277 164782 82494 164783 82279 164783 82278 164783 82278 164784 82279 164784 82280 164784 82278 164785 82280 164785 82281 164785 82281 164786 82280 164786 82496 164786 82281 164787 82496 164787 82275 164787 82275 164788 82496 164788 82492 164788 82275 164789 82492 164789 82486 164789 82536 164790 82416 164790 82282 164790 82282 164791 82416 164791 78322 164791 82540 164792 82283 164792 82399 164792 82399 164793 82283 164793 78320 164793 82554 164794 82402 164794 82403 164794 82403 164795 82402 164795 78323 164795 82546 164796 78317 164796 82284 164796 82284 164797 78317 164797 82411 164797 82555 164798 82553 164798 82537 164798 82545 164799 82548 164799 82285 164799 82287 164800 82537 164800 82286 164800 82286 164801 82537 164801 82553 164801 82286 164802 82553 164802 82552 164802 82552 164803 82553 164803 82551 164803 82287 164804 82541 164804 82537 164804 82537 164805 82541 164805 82543 164805 82537 164806 82543 164806 82544 164806 82539 164807 82288 164807 82538 164807 82538 164808 82288 164808 82289 164808 82538 164809 82289 164809 82537 164809 82537 164810 82289 164810 82545 164810 82537 164811 82545 164811 82555 164811 82555 164812 82545 164812 82285 164812 82517 164813 78306 164813 82290 164813 82290 164814 78306 164814 82291 164814 82522 164815 82395 164815 82527 164815 82527 164816 82395 164816 78304 164816 82388 164817 82292 164817 82389 164817 82389 164818 82292 164818 78302 164818 82532 164819 82393 164819 82396 164819 82396 164820 82393 164820 78308 164820 82524 164821 82525 164821 82526 164821 82526 164822 82525 164822 82518 164822 82526 164823 82518 164823 82533 164823 82533 164824 82518 164824 82534 164824 82533 164825 82534 164825 82293 164825 82293 164826 82534 164826 82531 164826 82516 164827 82520 164827 82294 164827 82295 164828 82296 164828 82528 164828 82528 164829 82296 164829 82535 164829 82294 164830 82297 164830 82516 164830 82516 164831 82297 164831 82528 164831 82516 164832 82528 164832 82518 164832 82518 164833 82528 164833 82535 164833 82518 164834 82535 164834 82534 164834 82508 164835 82385 164835 82298 164835 82298 164836 82385 164836 82299 164836 82503 164837 82381 164837 82300 164837 82300 164838 82381 164838 78287 164838 82515 164839 82301 164839 82374 164839 82374 164840 82301 164840 82373 164840 82513 164841 82302 164841 82504 164841 82504 164842 82302 164842 78291 164842 82303 164843 82512 164843 82304 164843 82304 164844 82310 164844 82305 164844 82506 164845 82306 164845 82505 164845 82505 164846 82306 164846 82311 164846 82307 164847 82309 164847 82308 164847 82308 164848 82309 164848 82310 164848 82308 164849 82310 164849 82311 164849 82311 164850 82310 164850 82304 164850 82311 164851 82304 164851 82505 164851 82305 164852 82312 164852 82313 164852 82303 164853 82304 164853 82314 164853 82313 164854 82510 164854 82305 164854 82305 164855 82510 164855 82315 164855 82305 164856 82315 164856 82304 164856 82304 164857 82315 164857 82514 164857 82304 164858 82514 164858 82314 164858 82429 164859 82428 164859 82430 164859 82430 164860 82428 164860 82431 164860 82438 164861 82437 164861 82417 164861 82417 164862 82437 164862 78340 164862 82558 164863 78339 164863 82421 164863 82421 164864 78339 164864 78338 164864 82426 164865 78336 164865 82570 164865 82570 164866 78336 164866 82316 164866 82317 164867 82319 164867 82562 164867 82566 164868 82568 164868 82318 164868 82323 164869 82562 164869 82556 164869 82319 164870 82320 164870 82562 164870 82562 164871 82320 164871 82560 164871 82562 164872 82560 164872 82561 164872 82323 164873 82563 164873 82564 164873 82557 164874 82321 164874 82556 164874 82556 164875 82321 164875 82559 164875 82556 164876 82559 164876 82323 164876 82318 164877 82317 164877 82566 164877 82566 164878 82317 164878 82562 164878 82566 164879 82562 164879 82571 164879 82571 164880 82562 164880 82323 164880 82571 164881 82323 164881 82322 164881 82322 164882 82323 164882 82564 164882 82583 164883 82324 164883 82325 164883 82325 164884 82324 164884 82449 164884 82572 164885 82326 164885 82439 164885 82439 164886 82326 164886 78358 164886 82327 164887 82443 164887 82584 164887 82584 164888 82443 164888 82444 164888 82588 164889 82328 164889 82447 164889 82447 164890 82328 164890 82329 164890 82330 164891 82580 164891 82332 164891 82332 164892 82580 164892 82573 164892 82582 164893 82580 164893 82592 164893 82592 164894 82580 164894 82330 164894 82592 164895 82330 164895 82591 164895 82591 164896 82330 164896 82589 164896 82582 164897 82577 164897 82580 164897 82580 164898 82577 164898 82578 164898 82580 164899 82578 164899 82579 164899 82586 164900 82587 164900 82331 164900 82331 164901 82587 164901 82332 164901 82331 164902 82332 164902 82581 164902 82581 164903 82332 164903 82573 164903 82581 164904 82573 164904 82576 164904 82576 164905 82573 164905 82574 164905 82603 164906 82466 164906 82333 164906 82333 164907 82466 164907 78380 164907 82594 164908 82334 164908 82456 164908 82456 164909 82334 164909 78377 164909 82597 164910 78375 164910 82458 164910 82458 164911 78375 164911 82459 164911 82608 164912 82463 164912 82335 164912 82335 164913 82463 164913 78372 164913 82336 164914 82601 164914 82598 164914 82598 164915 82601 164915 82343 164915 82598 164916 82343 164916 82602 164916 82602 164917 82343 164917 82344 164917 82602 164918 82344 164918 82607 164918 82607 164919 82344 164919 82337 164919 82593 164920 82595 164920 82341 164920 82338 164921 82604 164921 82339 164921 82339 164922 82604 164922 82340 164922 82341 164923 82342 164923 82593 164923 82593 164924 82342 164924 82339 164924 82593 164925 82339 164925 82343 164925 82343 164926 82339 164926 82340 164926 82343 164927 82340 164927 82344 164927 82479 164928 78275 164928 82345 164928 82345 164929 78275 164929 78274 164929 82612 164930 82474 164930 82346 164930 82346 164931 82474 164931 78272 164931 82627 164932 82347 164932 82471 164932 82471 164933 82347 164933 78270 164933 82626 164934 78280 164934 82348 164934 82348 164935 78280 164935 78278 164935 82628 164936 82623 164936 82625 164936 82615 164937 82349 164937 82614 164937 82614 164938 82349 164938 82353 164938 82614 164939 82353 164939 82617 164939 82617 164940 82353 164940 82350 164940 82355 164941 82619 164941 82620 164941 82351 164942 82352 164942 82609 164942 82609 164943 82352 164943 82616 164943 82609 164944 82616 164944 82353 164944 82353 164945 82616 164945 82355 164945 82625 164946 82350 164946 82628 164946 82628 164947 82350 164947 82353 164947 82628 164948 82353 164948 82354 164948 82354 164949 82353 164949 82355 164949 82354 164950 82355 164950 82356 164950 82356 164951 82355 164951 82620 164951 82491 164952 78266 164952 82357 164952 82491 164953 82357 164953 82358 164953 82358 164954 82357 164954 82359 164954 82358 164955 82359 164955 82493 164955 82493 164956 82359 164956 82270 164956 82493 164957 82270 164957 82495 164957 82497 164958 82271 164958 82360 164958 82497 164959 82360 164959 82362 164959 82362 164960 82360 164960 82361 164960 82362 164961 82361 164961 82499 164961 82499 164962 82361 164962 82272 164962 82499 164963 82272 164963 82500 164963 82268 164964 82363 164964 78263 164964 82268 164965 78263 164965 82480 164965 82480 164966 78263 164966 78260 164966 82480 164967 78260 164967 82482 164967 82482 164968 78260 164968 82364 164968 82482 164969 82364 164969 82484 164969 82484 164970 82364 164970 82269 164970 82484 164971 82269 164971 82485 164971 82273 164972 82365 164972 78262 164972 82273 164973 78262 164973 82487 164973 82487 164974 78262 164974 78259 164974 82487 164975 78259 164975 82366 164975 82366 164976 78259 164976 82367 164976 82366 164977 82367 164977 82489 164977 82489 164978 82367 164978 82267 164978 82489 164979 82267 164979 82368 164979 82300 164980 78287 164980 82369 164980 82300 164981 82369 164981 82509 164981 82509 164982 82369 164982 82370 164982 82509 164983 82370 164983 82372 164983 82372 164984 82370 164984 82371 164984 82372 164985 82371 164985 82511 164985 82511 164986 82371 164986 82301 164986 82511 164987 82301 164987 82515 164987 82374 164988 82373 164988 82376 164988 82374 164989 82376 164989 82375 164989 82375 164990 82376 164990 82377 164990 82375 164991 82377 164991 82378 164991 82378 164992 82377 164992 82379 164992 82378 164993 82379 164993 82380 164993 82380 164994 82379 164994 82302 164994 82380 164995 82302 164995 82513 164995 82298 164996 82299 164996 78285 164996 82298 164997 78285 164997 82502 164997 82502 164998 78285 164998 78288 164998 82502 164999 78288 164999 82382 164999 82382 165000 78288 165000 82381 165000 82382 165001 82381 165001 82503 165001 82504 165002 78291 165002 78290 165002 82504 165003 78290 165003 82507 165003 82507 165004 78290 165004 82383 165004 82507 165005 82383 165005 82384 165005 82384 165006 82383 165006 82385 165006 82384 165007 82385 165007 82508 165007 82527 165008 78304 165008 78303 165008 82527 165009 78303 165009 82529 165009 82529 165010 78303 165010 82387 165010 82529 165011 82387 165011 82386 165011 82386 165012 82387 165012 82292 165012 82386 165013 82292 165013 82388 165013 82389 165014 78302 165014 82390 165014 82389 165015 82390 165015 82530 165015 82530 165016 82390 165016 82391 165016 82530 165017 82391 165017 82392 165017 82392 165018 82391 165018 82393 165018 82392 165019 82393 165019 82532 165019 82290 165020 82291 165020 78305 165020 82290 165021 78305 165021 82519 165021 82519 165022 78305 165022 82394 165022 82519 165023 82394 165023 82521 165023 82521 165024 82394 165024 82395 165024 82521 165025 82395 165025 82522 165025 82396 165026 78308 165026 82397 165026 82396 165027 82397 165027 82523 165027 82523 165028 82397 165028 78307 165028 82523 165029 78307 165029 82398 165029 82398 165030 78307 165030 78306 165030 82398 165031 78306 165031 82517 165031 82399 165032 78320 165032 82400 165032 82399 165033 82400 165033 82547 165033 82547 165034 82400 165034 82401 165034 82547 165035 82401 165035 82549 165035 82549 165036 82401 165036 78314 165036 82549 165037 78314 165037 82550 165037 82550 165038 78314 165038 82402 165038 82550 165039 82402 165039 82554 165039 82403 165040 78323 165040 82405 165040 82403 165041 82405 165041 82404 165041 82404 165042 82405 165042 78318 165042 82404 165043 78318 165043 82406 165043 82406 165044 78318 165044 78317 165044 82406 165045 78317 165045 82546 165045 82282 165046 78322 165046 82408 165046 82282 165047 82408 165047 82407 165047 82407 165048 82408 165048 82409 165048 82407 165049 82409 165049 82410 165049 82410 165050 82409 165050 82283 165050 82410 165051 82283 165051 82540 165051 82284 165052 82411 165052 78315 165052 82284 165053 78315 165053 82413 165053 82413 165054 78315 165054 82412 165054 82413 165055 82412 165055 82542 165055 82542 165056 82412 165056 82415 165056 82542 165057 82415 165057 82414 165057 82414 165058 82415 165058 82416 165058 82414 165059 82416 165059 82536 165059 82417 165060 78340 165060 82418 165060 82417 165061 82418 165061 82419 165061 82419 165062 82418 165062 78333 165062 82419 165063 78333 165063 82420 165063 82420 165064 78333 165064 78339 165064 82420 165065 78339 165065 82558 165065 82421 165066 78338 165066 82423 165066 82421 165067 82423 165067 82422 165067 82422 165068 82423 165068 82424 165068 82422 165069 82424 165069 82425 165069 82425 165070 82424 165070 78337 165070 82425 165071 78337 165071 82565 165071 82565 165072 78337 165072 78336 165072 82565 165073 78336 165073 82426 165073 82570 165074 82316 165074 82427 165074 82570 165075 82427 165075 82567 165075 82567 165076 82427 165076 78335 165076 82567 165077 78335 165077 82569 165077 82569 165078 78335 165078 82428 165078 82569 165079 82428 165079 82429 165079 82430 165080 82431 165080 82432 165080 82430 165081 82432 165081 82433 165081 82433 165082 82432 165082 78342 165082 82433 165083 78342 165083 82434 165083 82434 165084 78342 165084 82436 165084 82434 165085 82436 165085 82435 165085 82435 165086 82436 165086 82437 165086 82435 165087 82437 165087 82438 165087 82439 165088 78358 165088 82440 165088 82439 165089 82440 165089 82441 165089 82441 165090 82440 165090 78355 165090 82441 165091 78355 165091 82575 165091 82575 165092 78355 165092 78354 165092 82575 165093 78354 165093 82442 165093 82442 165094 78354 165094 82443 165094 82442 165095 82443 165095 82327 165095 82584 165096 82444 165096 78357 165096 82584 165097 78357 165097 82445 165097 82445 165098 78357 165098 78356 165098 82445 165099 78356 165099 82585 165099 82585 165100 78356 165100 82328 165100 82585 165101 82328 165101 82588 165101 82447 165102 82329 165102 82446 165102 82447 165103 82446 165103 82590 165103 82590 165104 82446 165104 78359 165104 82590 165105 78359 165105 82448 165105 82448 165106 78359 165106 82324 165106 82448 165107 82324 165107 82583 165107 82325 165108 82449 165108 82451 165108 82325 165109 82451 165109 82450 165109 82450 165110 82451 165110 82452 165110 82450 165111 82452 165111 82454 165111 82454 165112 82452 165112 82453 165112 82454 165113 82453 165113 82455 165113 82455 165114 82453 165114 82326 165114 82455 165115 82326 165115 82572 165115 82456 165116 78377 165116 78369 165116 82456 165117 78369 165117 82457 165117 82457 165118 78369 165118 78376 165118 82457 165119 78376 165119 82596 165119 82596 165120 78376 165120 78375 165120 82596 165121 78375 165121 82597 165121 82458 165122 82459 165122 82461 165122 82458 165123 82461 165123 82460 165123 82460 165124 82461 165124 82462 165124 82460 165125 82462 165125 82605 165125 82605 165126 82462 165126 82463 165126 82605 165127 82463 165127 82608 165127 82335 165128 78372 165128 78370 165128 82335 165129 78370 165129 82606 165129 82606 165130 78370 165130 82464 165130 82606 165131 82464 165131 82465 165131 82465 165132 82464 165132 82466 165132 82465 165133 82466 165133 82603 165133 82333 165134 78380 165134 82467 165134 82333 165135 82467 165135 82599 165135 82599 165136 82467 165136 78378 165136 82599 165137 78378 165137 82600 165137 82600 165138 78378 165138 82334 165138 82600 165139 82334 165139 82594 165139 82346 165140 78272 165140 82468 165140 82346 165141 82468 165141 82618 165141 82618 165142 82468 165142 78271 165142 82618 165143 78271 165143 82469 165143 82469 165144 78271 165144 82470 165144 82469 165145 82470 165145 82621 165145 82621 165146 82470 165146 82347 165146 82621 165147 82347 165147 82627 165147 82471 165148 78270 165148 78281 165148 82471 165149 78281 165149 82622 165149 82622 165150 78281 165150 82472 165150 82622 165151 82472 165151 82624 165151 82624 165152 82472 165152 78280 165152 82624 165153 78280 165153 82626 165153 82345 165154 78274 165154 82473 165154 82345 165155 82473 165155 82610 165155 82610 165156 82473 165156 78273 165156 82610 165157 78273 165157 82611 165157 82611 165158 78273 165158 82474 165158 82611 165159 82474 165159 82612 165159 82348 165160 78278 165160 78277 165160 82348 165161 78277 165161 82613 165161 82613 165162 78277 165162 82476 165162 82613 165163 82476 165163 82475 165163 82475 165164 82476 165164 82477 165164 82475 165165 82477 165165 82478 165165 82478 165166 82477 165166 78275 165166 82478 165167 78275 165167 82479 165167 82268 165168 82481 165168 82368 165168 82368 165169 82481 165169 82275 165169 82481 165170 82268 165170 82480 165170 82481 165171 82480 165171 82277 165171 82277 165172 82480 165172 82482 165172 82277 165173 82482 165173 82483 165173 82483 165174 82482 165174 82484 165174 82483 165175 82484 165175 82276 165175 82276 165176 82484 165176 82485 165176 82276 165177 82485 165177 82281 165177 82486 165178 82273 165178 82487 165178 82486 165179 82487 165179 82488 165179 82488 165180 82487 165180 82366 165180 82488 165181 82366 165181 82274 165181 82274 165182 82366 165182 82489 165182 82274 165183 82489 165183 82490 165183 82490 165184 82489 165184 82368 165184 82490 165185 82368 165185 82275 165185 82491 165186 82278 165186 82485 165186 82485 165187 82278 165187 82281 165187 82492 165188 82500 165188 82486 165188 82486 165189 82500 165189 82273 165189 82278 165190 82491 165190 82358 165190 82278 165191 82358 165191 82494 165191 82494 165192 82358 165192 82493 165192 82494 165193 82493 165193 82279 165193 82279 165194 82493 165194 82495 165194 82279 165195 82495 165195 82280 165195 82496 165196 82497 165196 82362 165196 82496 165197 82362 165197 82498 165197 82498 165198 82362 165198 82499 165198 82498 165199 82499 165199 82501 165199 82501 165200 82499 165200 82500 165200 82501 165201 82500 165201 82492 165201 82497 165202 82496 165202 82495 165202 82495 165203 82496 165203 82280 165203 82298 165204 82308 165204 82508 165204 82508 165205 82308 165205 82311 165205 82308 165206 82298 165206 82502 165206 82308 165207 82502 165207 82307 165207 82307 165208 82502 165208 82382 165208 82307 165209 82382 165209 82309 165209 82309 165210 82382 165210 82503 165210 82309 165211 82503 165211 82310 165211 82505 165212 82504 165212 82507 165212 82505 165213 82507 165213 82506 165213 82506 165214 82507 165214 82384 165214 82506 165215 82384 165215 82306 165215 82306 165216 82384 165216 82508 165216 82306 165217 82508 165217 82311 165217 82300 165218 82305 165218 82503 165218 82503 165219 82305 165219 82310 165219 82304 165220 82513 165220 82505 165220 82505 165221 82513 165221 82504 165221 82305 165222 82300 165222 82509 165222 82305 165223 82509 165223 82312 165223 82312 165224 82509 165224 82372 165224 82312 165225 82372 165225 82313 165225 82313 165226 82372 165226 82511 165226 82313 165227 82511 165227 82510 165227 82510 165228 82511 165228 82515 165228 82510 165229 82515 165229 82315 165229 82514 165230 82374 165230 82375 165230 82514 165231 82375 165231 82314 165231 82314 165232 82375 165232 82378 165232 82314 165233 82378 165233 82303 165233 82303 165234 82378 165234 82380 165234 82303 165235 82380 165235 82512 165235 82512 165236 82380 165236 82513 165236 82512 165237 82513 165237 82304 165237 82374 165238 82514 165238 82515 165238 82515 165239 82514 165239 82315 165239 82290 165240 82516 165240 82517 165240 82517 165241 82516 165241 82518 165241 82516 165242 82290 165242 82519 165242 82516 165243 82519 165243 82520 165243 82520 165244 82519 165244 82521 165244 82520 165245 82521 165245 82294 165245 82294 165246 82521 165246 82522 165246 82294 165247 82522 165247 82297 165247 82526 165248 82396 165248 82523 165248 82526 165249 82523 165249 82524 165249 82524 165250 82523 165250 82398 165250 82524 165251 82398 165251 82525 165251 82525 165252 82398 165252 82517 165252 82525 165253 82517 165253 82518 165253 82527 165254 82528 165254 82522 165254 82522 165255 82528 165255 82297 165255 82533 165256 82532 165256 82526 165256 82526 165257 82532 165257 82396 165257 82528 165258 82527 165258 82529 165258 82528 165259 82529 165259 82295 165259 82295 165260 82529 165260 82386 165260 82295 165261 82386 165261 82296 165261 82296 165262 82386 165262 82388 165262 82296 165263 82388 165263 82535 165263 82534 165264 82389 165264 82530 165264 82534 165265 82530 165265 82531 165265 82531 165266 82530 165266 82392 165266 82531 165267 82392 165267 82293 165267 82293 165268 82392 165268 82532 165268 82293 165269 82532 165269 82533 165269 82389 165270 82534 165270 82388 165270 82388 165271 82534 165271 82535 165271 82282 165272 82538 165272 82536 165272 82536 165273 82538 165273 82537 165273 82538 165274 82282 165274 82407 165274 82538 165275 82407 165275 82539 165275 82539 165276 82407 165276 82410 165276 82539 165277 82410 165277 82288 165277 82288 165278 82410 165278 82540 165278 82288 165279 82540 165279 82289 165279 82287 165280 82284 165280 82413 165280 82287 165281 82413 165281 82541 165281 82541 165282 82413 165282 82542 165282 82541 165283 82542 165283 82543 165283 82543 165284 82542 165284 82414 165284 82543 165285 82414 165285 82544 165285 82544 165286 82414 165286 82536 165286 82544 165287 82536 165287 82537 165287 82399 165288 82545 165288 82540 165288 82540 165289 82545 165289 82289 165289 82286 165290 82546 165290 82287 165290 82287 165291 82546 165291 82284 165291 82545 165292 82399 165292 82547 165292 82545 165293 82547 165293 82548 165293 82548 165294 82547 165294 82549 165294 82548 165295 82549 165295 82285 165295 82549 165296 82550 165296 82285 165296 82285 165297 82550 165297 82554 165297 82285 165298 82554 165298 82555 165298 82553 165299 82403 165299 82404 165299 82553 165300 82404 165300 82551 165300 82551 165301 82404 165301 82406 165301 82551 165302 82406 165302 82552 165302 82552 165303 82406 165303 82546 165303 82552 165304 82546 165304 82286 165304 82403 165305 82553 165305 82554 165305 82554 165306 82553 165306 82555 165306 82417 165307 82556 165307 82438 165307 82438 165308 82556 165308 82562 165308 82556 165309 82417 165309 82419 165309 82556 165310 82419 165310 82557 165310 82557 165311 82419 165311 82420 165311 82557 165312 82420 165312 82321 165312 82321 165313 82420 165313 82558 165313 82321 165314 82558 165314 82559 165314 82319 165315 82430 165315 82433 165315 82319 165316 82433 165316 82320 165316 82320 165317 82433 165317 82434 165317 82320 165318 82434 165318 82560 165318 82560 165319 82434 165319 82435 165319 82560 165320 82435 165320 82561 165320 82561 165321 82435 165321 82438 165321 82561 165322 82438 165322 82562 165322 82421 165323 82323 165323 82558 165323 82558 165324 82323 165324 82559 165324 82317 165325 82429 165325 82319 165325 82319 165326 82429 165326 82430 165326 82323 165327 82421 165327 82422 165327 82323 165328 82422 165328 82563 165328 82563 165329 82422 165329 82425 165329 82563 165330 82425 165330 82564 165330 82564 165331 82425 165331 82565 165331 82564 165332 82565 165332 82322 165332 82322 165333 82565 165333 82426 165333 82322 165334 82426 165334 82571 165334 82566 165335 82570 165335 82567 165335 82566 165336 82567 165336 82568 165336 82568 165337 82567 165337 82569 165337 82568 165338 82569 165338 82318 165338 82318 165339 82569 165339 82429 165339 82318 165340 82429 165340 82317 165340 82570 165341 82566 165341 82426 165341 82426 165342 82566 165342 82571 165342 82439 165343 82573 165343 82572 165343 82572 165344 82573 165344 82580 165344 82573 165345 82439 165345 82441 165345 82573 165346 82441 165346 82574 165346 82574 165347 82441 165347 82575 165347 82574 165348 82575 165348 82576 165348 82575 165349 82442 165349 82576 165349 82576 165350 82442 165350 82327 165350 82576 165351 82327 165351 82581 165351 82582 165352 82325 165352 82450 165352 82582 165353 82450 165353 82577 165353 82577 165354 82450 165354 82454 165354 82577 165355 82454 165355 82578 165355 82578 165356 82454 165356 82455 165356 82578 165357 82455 165357 82579 165357 82579 165358 82455 165358 82572 165358 82579 165359 82572 165359 82580 165359 82584 165360 82331 165360 82327 165360 82327 165361 82331 165361 82581 165361 82592 165362 82583 165362 82582 165362 82582 165363 82583 165363 82325 165363 82331 165364 82584 165364 82445 165364 82331 165365 82445 165365 82586 165365 82586 165366 82445 165366 82585 165366 82586 165367 82585 165367 82587 165367 82587 165368 82585 165368 82588 165368 82587 165369 82588 165369 82332 165369 82330 165370 82447 165370 82590 165370 82330 165371 82590 165371 82589 165371 82589 165372 82590 165372 82448 165372 82589 165373 82448 165373 82591 165373 82591 165374 82448 165374 82583 165374 82591 165375 82583 165375 82592 165375 82447 165376 82330 165376 82588 165376 82588 165377 82330 165377 82332 165377 82456 165378 82593 165378 82594 165378 82594 165379 82593 165379 82343 165379 82593 165380 82456 165380 82457 165380 82593 165381 82457 165381 82595 165381 82595 165382 82457 165382 82596 165382 82595 165383 82596 165383 82341 165383 82341 165384 82596 165384 82597 165384 82341 165385 82597 165385 82342 165385 82598 165386 82333 165386 82599 165386 82598 165387 82599 165387 82336 165387 82336 165388 82599 165388 82600 165388 82336 165389 82600 165389 82601 165389 82601 165390 82600 165390 82594 165390 82601 165391 82594 165391 82343 165391 82458 165392 82339 165392 82597 165392 82597 165393 82339 165393 82342 165393 82602 165394 82603 165394 82598 165394 82598 165395 82603 165395 82333 165395 82339 165396 82458 165396 82460 165396 82339 165397 82460 165397 82338 165397 82338 165398 82460 165398 82605 165398 82338 165399 82605 165399 82604 165399 82604 165400 82605 165400 82608 165400 82604 165401 82608 165401 82340 165401 82344 165402 82335 165402 82606 165402 82344 165403 82606 165403 82337 165403 82337 165404 82606 165404 82465 165404 82337 165405 82465 165405 82607 165405 82607 165406 82465 165406 82603 165406 82607 165407 82603 165407 82602 165407 82335 165408 82344 165408 82608 165408 82608 165409 82344 165409 82340 165409 82345 165410 82609 165410 82479 165410 82479 165411 82609 165411 82353 165411 82609 165412 82345 165412 82610 165412 82609 165413 82610 165413 82351 165413 82351 165414 82610 165414 82611 165414 82351 165415 82611 165415 82352 165415 82352 165416 82611 165416 82612 165416 82352 165417 82612 165417 82616 165417 82617 165418 82348 165418 82613 165418 82617 165419 82613 165419 82614 165419 82614 165420 82613 165420 82475 165420 82614 165421 82475 165421 82615 165421 82615 165422 82475 165422 82478 165422 82615 165423 82478 165423 82349 165423 82349 165424 82478 165424 82479 165424 82349 165425 82479 165425 82353 165425 82346 165426 82355 165426 82612 165426 82612 165427 82355 165427 82616 165427 82350 165428 82626 165428 82617 165428 82617 165429 82626 165429 82348 165429 82355 165430 82346 165430 82618 165430 82355 165431 82618 165431 82619 165431 82619 165432 82618 165432 82469 165432 82619 165433 82469 165433 82620 165433 82620 165434 82469 165434 82621 165434 82620 165435 82621 165435 82356 165435 82356 165436 82621 165436 82627 165436 82356 165437 82627 165437 82354 165437 82628 165438 82471 165438 82622 165438 82628 165439 82622 165439 82623 165439 82623 165440 82622 165440 82624 165440 82623 165441 82624 165441 82625 165441 82625 165442 82624 165442 82626 165442 82625 165443 82626 165443 82350 165443 82471 165444 82628 165444 82627 165444 82627 165445 82628 165445 82354 165445 82833 165446 82736 165446 82629 165446 82629 165447 82736 165447 82630 165447 82842 165448 82631 165448 82726 165448 82726 165449 82631 165449 82724 165449 82851 165450 82729 165450 82632 165450 82632 165451 82729 165451 78055 165451 82633 165452 82723 165452 82730 165452 82730 165453 82723 165453 82731 165453 82638 165454 82637 165454 82640 165454 82640 165455 82637 165455 82634 165455 82638 165456 82844 165456 82845 165456 82634 165457 82837 165457 82839 165457 82834 165458 82635 165458 82841 165458 82841 165459 82635 165459 82637 165459 82841 165460 82637 165460 82636 165460 82636 165461 82637 165461 82638 165461 82636 165462 82638 165462 82847 165462 82847 165463 82638 165463 82845 165463 82850 165464 82639 165464 82849 165464 82849 165465 82639 165465 82640 165465 82849 165466 82640 165466 82843 165466 82843 165467 82640 165467 82634 165467 82843 165468 82634 165468 82840 165468 82840 165469 82634 165469 82839 165469 82890 165470 82641 165470 82777 165470 82777 165471 82641 165471 82642 165471 82898 165472 82782 165472 82643 165472 82643 165473 82782 165473 78012 165473 82644 165474 82772 165474 82909 165474 82909 165475 82772 165475 82645 165475 82906 165476 82646 165476 82773 165476 82773 165477 82646 165477 78010 165477 82895 165478 82896 165478 82647 165478 82647 165479 82896 165479 82899 165479 82647 165480 82899 165480 82891 165480 82891 165481 82899 165481 82648 165481 82903 165482 82905 165482 82902 165482 82902 165483 82905 165483 82651 165483 82893 165484 82894 165484 82892 165484 82892 165485 82894 165485 82648 165485 82892 165486 82648 165486 82651 165486 82651 165487 82648 165487 82899 165487 82651 165488 82899 165488 82897 165488 82907 165489 82649 165489 82897 165489 82897 165490 82649 165490 82650 165490 82897 165491 82650 165491 82651 165491 82651 165492 82650 165492 82900 165492 82651 165493 82900 165493 82902 165493 82875 165494 82652 165494 82876 165494 82876 165495 82652 165495 78024 165495 82881 165496 82765 165496 82885 165496 82885 165497 82765 165497 78031 165497 82889 165498 82759 165498 82882 165498 82882 165499 82759 165499 82653 165499 82884 165500 82654 165500 82760 165500 82760 165501 82654 165501 78026 165501 82657 165502 82656 165502 82886 165502 82873 165503 82874 165503 82871 165503 82871 165504 82874 165504 82655 165504 82878 165505 82879 165505 82870 165505 82870 165506 82879 165506 82656 165506 82870 165507 82656 165507 82655 165507 82655 165508 82656 165508 82657 165508 82655 165509 82657 165509 82871 165509 82658 165510 82883 165510 82659 165510 82659 165511 82883 165511 82657 165511 82659 165512 82657 165512 82660 165512 82660 165513 82657 165513 82886 165513 82660 165514 82886 165514 82887 165514 82887 165515 82886 165515 82661 165515 82854 165516 82662 165516 82753 165516 82753 165517 82662 165517 82663 165517 82860 165518 82664 165518 82866 165518 82866 165519 82664 165519 82746 165519 82869 165520 82750 165520 82741 165520 82741 165521 82750 165521 82739 165521 82865 165522 82744 165522 82861 165522 82861 165523 82744 165523 78043 165523 82856 165524 82859 165524 82855 165524 82855 165525 82859 165525 82671 165525 82855 165526 82671 165526 82674 165526 82665 165527 82666 165527 82672 165527 82672 165528 82666 165528 82864 165528 82672 165529 82864 165529 82673 165529 82667 165530 82853 165530 82668 165530 82668 165531 82853 165531 82674 165531 82867 165532 82669 165532 82862 165532 82862 165533 82669 165533 82670 165533 82862 165534 82670 165534 82671 165534 82671 165535 82670 165535 82672 165535 82671 165536 82672 165536 82674 165536 82674 165537 82672 165537 82673 165537 82674 165538 82673 165538 82668 165538 82917 165539 82676 165539 82675 165539 82675 165540 82676 165540 82790 165540 82793 165541 77986 165541 82919 165541 82919 165542 77986 165542 77988 165542 82922 165543 77983 165543 82677 165543 82677 165544 77983 165544 82783 165544 82678 165545 82679 165545 82680 165545 82680 165546 82679 165546 82681 165546 82918 165547 82682 165547 82685 165547 82685 165548 82682 165548 82684 165548 82683 165549 82923 165549 82921 165549 82921 165550 82923 165550 82685 165550 82925 165551 82926 165551 82684 165551 82684 165552 82926 165552 82927 165552 82684 165553 82927 165553 82685 165553 82685 165554 82927 165554 82928 165554 82685 165555 82928 165555 82921 165555 82914 165556 82915 165556 82686 165556 82686 165557 82915 165557 82682 165557 82686 165558 82682 165558 82687 165558 82687 165559 82682 165559 82918 165559 82687 165560 82918 165560 82913 165560 82913 165561 82918 165561 82911 165561 82809 165562 82808 165562 82688 165562 82688 165563 82808 165563 77978 165563 82946 165564 77971 165564 82689 165564 82689 165565 77971 165565 77970 165565 82943 165566 77989 165566 82798 165566 82798 165567 77989 165567 77987 165567 82929 165568 77985 165568 82805 165568 82805 165569 77985 165569 77981 165569 82935 165570 82937 165570 82690 165570 82690 165571 82937 165571 82695 165571 82690 165572 82695 165572 82691 165572 82691 165573 82695 165573 82694 165573 82942 165574 82692 165574 82693 165574 82693 165575 82692 165575 82938 165575 82693 165576 82938 165576 82947 165576 82930 165577 82933 165577 82939 165577 82939 165578 82933 165578 82694 165578 82939 165579 82694 165579 82938 165579 82938 165580 82694 165580 82695 165580 82938 165581 82695 165581 82947 165581 82947 165582 82695 165582 82940 165582 82947 165583 82940 165583 82696 165583 82696 165584 82940 165584 82945 165584 82956 165585 77957 165585 82961 165585 82961 165586 77957 165586 82697 165586 82965 165587 77955 165587 82811 165587 82811 165588 77955 165588 77954 165588 82813 165589 82698 165589 82699 165589 82699 165590 82698 165590 77952 165590 82950 165591 77950 165591 82817 165591 82817 165592 77950 165592 82816 165592 82962 165593 82964 165593 82957 165593 82957 165594 82964 165594 82702 165594 82959 165595 82700 165595 82966 165595 82966 165596 82700 165596 82701 165596 82966 165597 82701 165597 82702 165597 82702 165598 82701 165598 82705 165598 82702 165599 82705 165599 82957 165599 82952 165600 82954 165600 82703 165600 82703 165601 82954 165601 82948 165601 82955 165602 82704 165602 82949 165602 82949 165603 82704 165603 82705 165603 82949 165604 82705 165604 82948 165604 82948 165605 82705 165605 82701 165605 82948 165606 82701 165606 82703 165606 82828 165607 82827 165607 82829 165607 82829 165608 82827 165608 82830 165608 82832 165609 82706 165609 82707 165609 82707 165610 82706 165610 77931 165610 82984 165611 82824 165611 82708 165611 82708 165612 82824 165612 77936 165612 82976 165613 82709 165613 82967 165613 82967 165614 82709 165614 77932 165614 82977 165615 82971 165615 82710 165615 82710 165616 82971 165616 82717 165616 82977 165617 82711 165617 82980 165617 82717 165618 82973 165618 82975 165618 82712 165619 82970 165619 82713 165619 82713 165620 82970 165620 82971 165620 82713 165621 82971 165621 82714 165621 82714 165622 82971 165622 82977 165622 82714 165623 82977 165623 82981 165623 82981 165624 82977 165624 82980 165624 82982 165625 82715 165625 82716 165625 82716 165626 82715 165626 82710 165626 82716 165627 82710 165627 82718 165627 82718 165628 82710 165628 82717 165628 82718 165629 82717 165629 82719 165629 82719 165630 82717 165630 82975 165630 82632 165631 78055 165631 78054 165631 82632 165632 78054 165632 82720 165632 82720 165633 78054 165633 82721 165633 82720 165634 82721 165634 82722 165634 82722 165635 82721 165635 78053 165635 82722 165636 78053 165636 82846 165636 82846 165637 78053 165637 82723 165637 82846 165638 82723 165638 82633 165638 82726 165639 82724 165639 82725 165639 82726 165640 82725 165640 82848 165640 82848 165641 82725 165641 82727 165641 82848 165642 82727 165642 82728 165642 82728 165643 82727 165643 82729 165643 82728 165644 82729 165644 82851 165644 82730 165645 82731 165645 82732 165645 82730 165646 82732 165646 82733 165646 82733 165647 82732 165647 82735 165647 82733 165648 82735 165648 82734 165648 82734 165649 82735 165649 82736 165649 82734 165650 82736 165650 82833 165650 82629 165651 82630 165651 82737 165651 82629 165652 82737 165652 82835 165652 82835 165653 82737 165653 82738 165653 82835 165654 82738 165654 82836 165654 82836 165655 82738 165655 78051 165655 82836 165656 78051 165656 82838 165656 82838 165657 78051 165657 82631 165657 82838 165658 82631 165658 82842 165658 82741 165659 82739 165659 82740 165659 82741 165660 82740 165660 82742 165660 82742 165661 82740 165661 78041 165661 82742 165662 78041 165662 82863 165662 82863 165663 78041 165663 82743 165663 82863 165664 82743 165664 82745 165664 82745 165665 82743 165665 82744 165665 82745 165666 82744 165666 82865 165666 82866 165667 82746 165667 82748 165667 82866 165668 82748 165668 82747 165668 82747 165669 82748 165669 82749 165669 82747 165670 82749 165670 82868 165670 82868 165671 82749 165671 82750 165671 82868 165672 82750 165672 82869 165672 82861 165673 78043 165673 78042 165673 82861 165674 78042 165674 82751 165674 82751 165675 78042 165675 82752 165675 82751 165676 82752 165676 82852 165676 82852 165677 82752 165677 82662 165677 82852 165678 82662 165678 82854 165678 82753 165679 82663 165679 78040 165679 82753 165680 78040 165680 82857 165680 82857 165681 78040 165681 82754 165681 82857 165682 82754 165682 82858 165682 82858 165683 82754 165683 82664 165683 82858 165684 82664 165684 82860 165684 82882 165685 82653 165685 78028 165685 82882 165686 78028 165686 82755 165686 82755 165687 78028 165687 78027 165687 82755 165688 78027 165688 82756 165688 82756 165689 78027 165689 82654 165689 82756 165690 82654 165690 82884 165690 82885 165691 78031 165691 82757 165691 82885 165692 82757 165692 82758 165692 82758 165693 82757 165693 78030 165693 82758 165694 78030 165694 82888 165694 82888 165695 78030 165695 82759 165695 82888 165696 82759 165696 82889 165696 82760 165697 78026 165697 82761 165697 82760 165698 82761 165698 82763 165698 82763 165699 82761 165699 82762 165699 82763 165700 82762 165700 82872 165700 82872 165701 82762 165701 82652 165701 82872 165702 82652 165702 82875 165702 82876 165703 78024 165703 82764 165703 82876 165704 82764 165704 82877 165704 82877 165705 82764 165705 78032 165705 82877 165706 78032 165706 82880 165706 82880 165707 78032 165707 82765 165707 82880 165708 82765 165708 82881 165708 82909 165709 82645 165709 82766 165709 82909 165710 82766 165710 82901 165710 82901 165711 82766 165711 78011 165711 82901 165712 78011 165712 82904 165712 82904 165713 78011 165713 82767 165713 82904 165714 82767 165714 82768 165714 82768 165715 82767 165715 82646 165715 82768 165716 82646 165716 82906 165716 82643 165717 78012 165717 82769 165717 82643 165718 82769 165718 82770 165718 82770 165719 82769 165719 82771 165719 82770 165720 82771 165720 82908 165720 82908 165721 82771 165721 82772 165721 82908 165722 82772 165722 82644 165722 82773 165723 78010 165723 82774 165723 82773 165724 82774 165724 82775 165724 82775 165725 82774 165725 78007 165725 82775 165726 78007 165726 82776 165726 82776 165727 78007 165727 82641 165727 82776 165728 82641 165728 82890 165728 82777 165729 82642 165729 78009 165729 82777 165730 78009 165730 82778 165730 82778 165731 78009 165731 82780 165731 82778 165732 82780 165732 82779 165732 82779 165733 82780 165733 78013 165733 82779 165734 78013 165734 82781 165734 82781 165735 78013 165735 82782 165735 82781 165736 82782 165736 82898 165736 82677 165737 82783 165737 82784 165737 82677 165738 82784 165738 82910 165738 82910 165739 82784 165739 77982 165739 82910 165740 77982 165740 82912 165740 82912 165741 77982 165741 82679 165741 82912 165742 82679 165742 82678 165742 82919 165743 77988 165743 82785 165743 82919 165744 82785 165744 82920 165744 82920 165745 82785 165745 82786 165745 82920 165746 82786 165746 82788 165746 82788 165747 82786 165747 82787 165747 82788 165748 82787 165748 82789 165748 82789 165749 82787 165749 77983 165749 82789 165750 77983 165750 82922 165750 82675 165751 82790 165751 77984 165751 82675 165752 77984 165752 82924 165752 82924 165753 77984 165753 82792 165753 82924 165754 82792 165754 82791 165754 82791 165755 82792 165755 77986 165755 82791 165756 77986 165756 82793 165756 82680 165757 82681 165757 77974 165757 82680 165758 77974 165758 82794 165758 82794 165759 77974 165759 82795 165759 82794 165760 82795 165760 82797 165760 82797 165761 82795 165761 82796 165761 82797 165762 82796 165762 82916 165762 82916 165763 82796 165763 82676 165763 82916 165764 82676 165764 82917 165764 82798 165765 77987 165765 82799 165765 82798 165766 82799 165766 82931 165766 82931 165767 82799 165767 82800 165767 82931 165768 82800 165768 82932 165768 82932 165769 82800 165769 77985 165769 82932 165770 77985 165770 82929 165770 82689 165771 77970 165771 82801 165771 82689 165772 82801 165772 82941 165772 82941 165773 82801 165773 77976 165773 82941 165774 77976 165774 82802 165774 82802 165775 77976 165775 77989 165775 82802 165776 77989 165776 82943 165776 82688 165777 77978 165777 77977 165777 82688 165778 77977 165778 82944 165778 82944 165779 77977 165779 82803 165779 82944 165780 82803 165780 82804 165780 82804 165781 82803 165781 77971 165781 82804 165782 77971 165782 82946 165782 82805 165783 77981 165783 77980 165783 82805 165784 77980 165784 82934 165784 82934 165785 77980 165785 82806 165785 82934 165786 82806 165786 82807 165786 82807 165787 82806 165787 77973 165787 82807 165788 77973 165788 82936 165788 82936 165789 77973 165789 82808 165789 82936 165790 82808 165790 82809 165790 82699 165791 77952 165791 82810 165791 82699 165792 82810 165792 82951 165792 82951 165793 82810 165793 77951 165793 82951 165794 77951 165794 82953 165794 82953 165795 77951 165795 77950 165795 82953 165796 77950 165796 82950 165796 82811 165797 77954 165797 77953 165797 82811 165798 77953 165798 82958 165798 82958 165799 77953 165799 82812 165799 82958 165800 82812 165800 82960 165800 82960 165801 82812 165801 82698 165801 82960 165802 82698 165802 82813 165802 82961 165803 82697 165803 82814 165803 82961 165804 82814 165804 82963 165804 82963 165805 82814 165805 77956 165805 82963 165806 77956 165806 82815 165806 82815 165807 77956 165807 77955 165807 82815 165808 77955 165808 82965 165808 82817 165809 82816 165809 82819 165809 82817 165810 82819 165810 82818 165810 82818 165811 82819 165811 77949 165811 82818 165812 77949 165812 82820 165812 82820 165813 77949 165813 77957 165813 82820 165814 77957 165814 82956 165814 82708 165815 77936 165815 77934 165815 82708 165816 77934 165816 82978 165816 82978 165817 77934 165817 77933 165817 82978 165818 77933 165818 82979 165818 82979 165819 77933 165819 82821 165819 82979 165820 82821 165820 82822 165820 82822 165821 82821 165821 82709 165821 82822 165822 82709 165822 82976 165822 82707 165823 77931 165823 77930 165823 82707 165824 77930 165824 82823 165824 82823 165825 77930 165825 77929 165825 82823 165826 77929 165826 82983 165826 82983 165827 77929 165827 82824 165827 82983 165828 82824 165828 82984 165828 82967 165829 77932 165829 82825 165829 82967 165830 82825 165830 82968 165830 82968 165831 82825 165831 82826 165831 82968 165832 82826 165832 82969 165832 82969 165833 82826 165833 82827 165833 82969 165834 82827 165834 82828 165834 82829 165835 82830 165835 77928 165835 82829 165836 77928 165836 82972 165836 82972 165837 77928 165837 77927 165837 82972 165838 77927 165838 82974 165838 82974 165839 77927 165839 77926 165839 82974 165840 77926 165840 82831 165840 82831 165841 77926 165841 82706 165841 82831 165842 82706 165842 82832 165842 82637 165843 82833 165843 82634 165843 82634 165844 82833 165844 82629 165844 82841 165845 82730 165845 82733 165845 82841 165846 82733 165846 82834 165846 82834 165847 82733 165847 82734 165847 82834 165848 82734 165848 82635 165848 82635 165849 82734 165849 82833 165849 82635 165850 82833 165850 82637 165850 82634 165851 82629 165851 82835 165851 82634 165852 82835 165852 82837 165852 82837 165853 82835 165853 82836 165853 82837 165854 82836 165854 82839 165854 82839 165855 82836 165855 82838 165855 82839 165856 82838 165856 82840 165856 82840 165857 82838 165857 82842 165857 82840 165858 82842 165858 82843 165858 82636 165859 82633 165859 82841 165859 82841 165860 82633 165860 82730 165860 82726 165861 82849 165861 82842 165861 82842 165862 82849 165862 82843 165862 82638 165863 82632 165863 82720 165863 82638 165864 82720 165864 82844 165864 82844 165865 82720 165865 82722 165865 82844 165866 82722 165866 82845 165866 82845 165867 82722 165867 82846 165867 82845 165868 82846 165868 82847 165868 82847 165869 82846 165869 82633 165869 82847 165870 82633 165870 82636 165870 82849 165871 82726 165871 82848 165871 82849 165872 82848 165872 82850 165872 82850 165873 82848 165873 82728 165873 82850 165874 82728 165874 82639 165874 82639 165875 82728 165875 82851 165875 82639 165876 82851 165876 82640 165876 82640 165877 82851 165877 82638 165877 82638 165878 82851 165878 82632 165878 82674 165879 82854 165879 82855 165879 82855 165880 82854 165880 82753 165880 82668 165881 82861 165881 82751 165881 82668 165882 82751 165882 82667 165882 82667 165883 82751 165883 82852 165883 82667 165884 82852 165884 82853 165884 82853 165885 82852 165885 82854 165885 82853 165886 82854 165886 82674 165886 82855 165887 82753 165887 82857 165887 82855 165888 82857 165888 82856 165888 82856 165889 82857 165889 82858 165889 82856 165890 82858 165890 82859 165890 82859 165891 82858 165891 82860 165891 82859 165892 82860 165892 82671 165892 82673 165893 82865 165893 82668 165893 82668 165894 82865 165894 82861 165894 82866 165895 82862 165895 82860 165895 82860 165896 82862 165896 82671 165896 82672 165897 82741 165897 82742 165897 82672 165898 82742 165898 82665 165898 82665 165899 82742 165899 82863 165899 82665 165900 82863 165900 82666 165900 82666 165901 82863 165901 82745 165901 82666 165902 82745 165902 82864 165902 82864 165903 82745 165903 82865 165903 82864 165904 82865 165904 82673 165904 82862 165905 82866 165905 82747 165905 82862 165906 82747 165906 82867 165906 82867 165907 82747 165907 82868 165907 82867 165908 82868 165908 82669 165908 82669 165909 82868 165909 82869 165909 82669 165910 82869 165910 82670 165910 82670 165911 82869 165911 82672 165911 82672 165912 82869 165912 82741 165912 82655 165913 82875 165913 82870 165913 82870 165914 82875 165914 82876 165914 82871 165915 82760 165915 82763 165915 82871 165916 82763 165916 82873 165916 82873 165917 82763 165917 82872 165917 82873 165918 82872 165918 82874 165918 82874 165919 82872 165919 82875 165919 82874 165920 82875 165920 82655 165920 82870 165921 82876 165921 82877 165921 82870 165922 82877 165922 82878 165922 82878 165923 82877 165923 82880 165923 82878 165924 82880 165924 82879 165924 82879 165925 82880 165925 82881 165925 82879 165926 82881 165926 82656 165926 82657 165927 82884 165927 82871 165927 82871 165928 82884 165928 82760 165928 82885 165929 82886 165929 82881 165929 82881 165930 82886 165930 82656 165930 82659 165931 82882 165931 82755 165931 82659 165932 82755 165932 82658 165932 82658 165933 82755 165933 82756 165933 82658 165934 82756 165934 82883 165934 82883 165935 82756 165935 82884 165935 82883 165936 82884 165936 82657 165936 82886 165937 82885 165937 82758 165937 82886 165938 82758 165938 82661 165938 82661 165939 82758 165939 82888 165939 82661 165940 82888 165940 82887 165940 82887 165941 82888 165941 82889 165941 82887 165942 82889 165942 82660 165942 82660 165943 82889 165943 82659 165943 82659 165944 82889 165944 82882 165944 82648 165945 82890 165945 82891 165945 82891 165946 82890 165946 82777 165946 82892 165947 82773 165947 82775 165947 82892 165948 82775 165948 82893 165948 82893 165949 82775 165949 82776 165949 82893 165950 82776 165950 82894 165950 82894 165951 82776 165951 82890 165951 82894 165952 82890 165952 82648 165952 82891 165953 82777 165953 82778 165953 82891 165954 82778 165954 82647 165954 82647 165955 82778 165955 82779 165955 82647 165956 82779 165956 82895 165956 82895 165957 82779 165957 82781 165957 82895 165958 82781 165958 82896 165958 82896 165959 82781 165959 82898 165959 82896 165960 82898 165960 82899 165960 82651 165961 82906 165961 82892 165961 82892 165962 82906 165962 82773 165962 82643 165963 82897 165963 82898 165963 82898 165964 82897 165964 82899 165964 82900 165965 82909 165965 82901 165965 82900 165966 82901 165966 82902 165966 82902 165967 82901 165967 82904 165967 82902 165968 82904 165968 82903 165968 82903 165969 82904 165969 82768 165969 82903 165970 82768 165970 82905 165970 82905 165971 82768 165971 82906 165971 82905 165972 82906 165972 82651 165972 82897 165973 82643 165973 82770 165973 82897 165974 82770 165974 82907 165974 82907 165975 82770 165975 82908 165975 82907 165976 82908 165976 82649 165976 82649 165977 82908 165977 82644 165977 82649 165978 82644 165978 82650 165978 82650 165979 82644 165979 82900 165979 82900 165980 82644 165980 82909 165980 82687 165981 82678 165981 82686 165981 82686 165982 82678 165982 82680 165982 82918 165983 82677 165983 82910 165983 82918 165984 82910 165984 82911 165984 82911 165985 82910 165985 82912 165985 82911 165986 82912 165986 82913 165986 82913 165987 82912 165987 82678 165987 82913 165988 82678 165988 82687 165988 82686 165989 82680 165989 82794 165989 82686 165990 82794 165990 82914 165990 82914 165991 82794 165991 82797 165991 82914 165992 82797 165992 82915 165992 82797 165993 82916 165993 82915 165993 82915 165994 82916 165994 82917 165994 82915 165995 82917 165995 82682 165995 82685 165996 82922 165996 82918 165996 82918 165997 82922 165997 82677 165997 82675 165998 82684 165998 82917 165998 82917 165999 82684 165999 82682 165999 82928 166000 82919 166000 82920 166000 82928 166001 82920 166001 82921 166001 82921 166002 82920 166002 82788 166002 82921 166003 82788 166003 82683 166003 82683 166004 82788 166004 82789 166004 82683 166005 82789 166005 82923 166005 82923 166006 82789 166006 82922 166006 82923 166007 82922 166007 82685 166007 82684 166008 82675 166008 82924 166008 82684 166009 82924 166009 82925 166009 82925 166010 82924 166010 82791 166010 82925 166011 82791 166011 82926 166011 82926 166012 82791 166012 82793 166012 82926 166013 82793 166013 82927 166013 82927 166014 82793 166014 82928 166014 82928 166015 82793 166015 82919 166015 82694 166016 82929 166016 82691 166016 82691 166017 82929 166017 82805 166017 82939 166018 82798 166018 82931 166018 82939 166019 82931 166019 82930 166019 82930 166020 82931 166020 82932 166020 82930 166021 82932 166021 82933 166021 82933 166022 82932 166022 82929 166022 82933 166023 82929 166023 82694 166023 82691 166024 82805 166024 82934 166024 82691 166025 82934 166025 82690 166025 82690 166026 82934 166026 82807 166026 82690 166027 82807 166027 82935 166027 82935 166028 82807 166028 82936 166028 82935 166029 82936 166029 82937 166029 82937 166030 82936 166030 82809 166030 82937 166031 82809 166031 82695 166031 82938 166032 82943 166032 82939 166032 82939 166033 82943 166033 82798 166033 82688 166034 82940 166034 82809 166034 82809 166035 82940 166035 82695 166035 82693 166036 82689 166036 82941 166036 82693 166037 82941 166037 82942 166037 82942 166038 82941 166038 82802 166038 82942 166039 82802 166039 82692 166039 82692 166040 82802 166040 82943 166040 82692 166041 82943 166041 82938 166041 82940 166042 82688 166042 82944 166042 82940 166043 82944 166043 82945 166043 82945 166044 82944 166044 82804 166044 82945 166045 82804 166045 82696 166045 82696 166046 82804 166046 82946 166046 82696 166047 82946 166047 82947 166047 82947 166048 82946 166048 82693 166048 82693 166049 82946 166049 82689 166049 82948 166050 82950 166050 82949 166050 82949 166051 82950 166051 82817 166051 82703 166052 82699 166052 82951 166052 82703 166053 82951 166053 82952 166053 82952 166054 82951 166054 82953 166054 82952 166055 82953 166055 82954 166055 82954 166056 82953 166056 82950 166056 82954 166057 82950 166057 82948 166057 82949 166058 82817 166058 82818 166058 82949 166059 82818 166059 82955 166059 82955 166060 82818 166060 82820 166060 82955 166061 82820 166061 82704 166061 82704 166062 82820 166062 82956 166062 82704 166063 82956 166063 82705 166063 82701 166064 82813 166064 82703 166064 82703 166065 82813 166065 82699 166065 82961 166066 82957 166066 82956 166066 82956 166067 82957 166067 82705 166067 82966 166068 82811 166068 82958 166068 82966 166069 82958 166069 82959 166069 82959 166070 82958 166070 82960 166070 82959 166071 82960 166071 82700 166071 82700 166072 82960 166072 82813 166072 82700 166073 82813 166073 82701 166073 82957 166074 82961 166074 82963 166074 82957 166075 82963 166075 82962 166075 82962 166076 82963 166076 82815 166076 82962 166077 82815 166077 82964 166077 82964 166078 82815 166078 82965 166078 82964 166079 82965 166079 82702 166079 82702 166080 82965 166080 82966 166080 82966 166081 82965 166081 82811 166081 82971 166082 82828 166082 82717 166082 82717 166083 82828 166083 82829 166083 82713 166084 82967 166084 82968 166084 82713 166085 82968 166085 82712 166085 82712 166086 82968 166086 82969 166086 82712 166087 82969 166087 82970 166087 82970 166088 82969 166088 82828 166088 82970 166089 82828 166089 82971 166089 82717 166090 82829 166090 82972 166090 82717 166091 82972 166091 82973 166091 82973 166092 82972 166092 82974 166092 82973 166093 82974 166093 82975 166093 82975 166094 82974 166094 82831 166094 82975 166095 82831 166095 82719 166095 82719 166096 82831 166096 82832 166096 82719 166097 82832 166097 82718 166097 82714 166098 82976 166098 82713 166098 82713 166099 82976 166099 82967 166099 82707 166100 82716 166100 82832 166100 82832 166101 82716 166101 82718 166101 82977 166102 82708 166102 82978 166102 82977 166103 82978 166103 82711 166103 82711 166104 82978 166104 82979 166104 82711 166105 82979 166105 82980 166105 82980 166106 82979 166106 82822 166106 82980 166107 82822 166107 82981 166107 82981 166108 82822 166108 82976 166108 82981 166109 82976 166109 82714 166109 82716 166110 82707 166110 82823 166110 82716 166111 82823 166111 82982 166111 82982 166112 82823 166112 82983 166112 82982 166113 82983 166113 82715 166113 82715 166114 82983 166114 82984 166114 82715 166115 82984 166115 82710 166115 82710 166116 82984 166116 82977 166116 82977 166117 82984 166117 82708 166117 82985 166118 82986 166118 82987 166118 82987 166119 82986 166119 82989 166119 82987 166120 82989 166120 82988 166120 82988 166121 82989 166121 82990 166121 82988 166122 82990 166122 78228 166122 78228 166123 82990 166123 77654 166123 82225 166124 77830 166124 82991 166124 82991 166125 77830 166125 82992 166125 82991 166126 82992 166126 77481 166126 77481 166127 82992 166127 82993 166127 77481 166128 82993 166128 77480 166128 77480 166129 82993 166129 82994 166129 78210 166130 77656 166130 78207 166130 78207 166131 77656 166131 82996 166131 78207 166132 82996 166132 82995 166132 82995 166133 82996 166133 77655 166133 82995 166134 77655 166134 78231 166134 78231 166135 77655 166135 82248 166135 77516 166136 77826 166136 77482 166136 77482 166137 77826 166137 77902 166137 77482 166138 77902 166138 77484 166138 77484 166139 77902 166139 82997 166139 77484 166140 82997 166140 82222 166140 82222 166141 82997 166141 77828 166141 77530 166142 83704 166142 77531 166142 77531 166143 83704 166143 83721 166143 77531 166144 83721 166144 77483 166144 78252 166145 83198 166145 82998 166145 82998 166146 83198 166146 83197 166146 78257 166147 82999 166147 83098 166147 83098 166148 82999 166148 83203 166148 83000 166149 83210 166149 83001 166149 83001 166150 83210 166150 83208 166150 83099 166151 83100 166151 83002 166151 83002 166152 83100 166152 83201 166152 83003 166153 83004 166153 83012 166153 83012 166154 83004 166154 83209 166154 83005 166155 83206 166155 83006 166155 83006 166156 83206 166156 83004 166156 83006 166157 83004 166157 83007 166157 83007 166158 83004 166158 83003 166158 83007 166159 83003 166159 83008 166159 83008 166160 83003 166160 83009 166160 83200 166161 83010 166161 83011 166161 83011 166162 83010 166162 83012 166162 83011 166163 83012 166163 83013 166163 83013 166164 83012 166164 83209 166164 83013 166165 83209 166165 83204 166165 83204 166166 83209 166166 83202 166166 83014 166167 83015 166167 83016 166167 83016 166168 83015 166168 83252 166168 83017 166169 83018 166169 83019 166169 83019 166170 83018 166170 83258 166170 83020 166171 83267 166171 83141 166171 83141 166172 83267 166172 83142 166172 78332 166173 83137 166173 78326 166173 78326 166174 83137 166174 83021 166174 83263 166175 83265 166175 83024 166175 83247 166176 83253 166176 83256 166176 83249 166177 83251 166177 83248 166177 83248 166178 83251 166178 83246 166178 83248 166179 83246 166179 83261 166179 83261 166180 83246 166180 83247 166180 83261 166181 83247 166181 83022 166181 83022 166182 83247 166182 83256 166182 83266 166183 83260 166183 83025 166183 83023 166184 83263 166184 83261 166184 83261 166185 83263 166185 83024 166185 83261 166186 83024 166186 83248 166186 83248 166187 83024 166187 83266 166187 83248 166188 83266 166188 83257 166188 83257 166189 83266 166189 83025 166189 83026 166190 83235 166190 83129 166190 83129 166191 83235 166191 83027 166191 78309 166192 83126 166192 83122 166192 83122 166193 83126 166193 83123 166193 78310 166194 83028 166194 78311 166194 78311 166195 83028 166195 83245 166195 78313 166196 83029 166196 83134 166196 83134 166197 83029 166197 83238 166197 83033 166198 83032 166198 83030 166198 83030 166199 83032 166199 83031 166199 83233 166200 83234 166200 83231 166200 83231 166201 83234 166201 83032 166201 83231 166202 83032 166202 83240 166202 83240 166203 83032 166203 83033 166203 83240 166204 83033 166204 83034 166204 83034 166205 83033 166205 83243 166205 83035 166206 83036 166206 83241 166206 83241 166207 83036 166207 83030 166207 83241 166208 83030 166208 83242 166208 83242 166209 83030 166209 83031 166209 83242 166210 83031 166210 83239 166210 83239 166211 83031 166211 83236 166211 78293 166212 83038 166212 83037 166212 83037 166213 83038 166213 83214 166213 83112 166214 83039 166214 83109 166214 83109 166215 83039 166215 83225 166215 78296 166216 83040 166216 83111 166216 83111 166217 83040 166217 83041 166217 78300 166218 83221 166218 78301 166218 78301 166219 83221 166219 83217 166219 83042 166220 83223 166220 83224 166220 83212 166221 83043 166221 83220 166221 83220 166222 83043 166222 83211 166222 83227 166223 83044 166223 83045 166223 83045 166224 83044 166224 83230 166224 83045 166225 83230 166225 83219 166225 83219 166226 83230 166226 83215 166226 83219 166227 83215 166227 83218 166227 83218 166228 83215 166228 83046 166228 83224 166229 83226 166229 83042 166229 83042 166230 83226 166230 83220 166230 83042 166231 83220 166231 83230 166231 83230 166232 83220 166232 83211 166232 83230 166233 83211 166233 83215 166233 83150 166234 83284 166234 83158 166234 83158 166235 83284 166235 83277 166235 83154 166236 83047 166236 83048 166236 83048 166237 83047 166237 83149 166237 78348 166238 83049 166238 78349 166238 78349 166239 83049 166239 83276 166239 78352 166240 83279 166240 83050 166240 83050 166241 83279 166241 83287 166241 83286 166242 83051 166242 83053 166242 83052 166243 83272 166243 83057 166243 83286 166244 83053 166244 83056 166244 83278 166245 83282 166245 83055 166245 83054 166246 83273 166246 83274 166246 83055 166247 83283 166247 83278 166247 83278 166248 83283 166248 83268 166248 83278 166249 83268 166249 83053 166249 83053 166250 83268 166250 83058 166250 83053 166251 83058 166251 83056 166251 83270 166252 83052 166252 83268 166252 83268 166253 83052 166253 83057 166253 83268 166254 83057 166254 83058 166254 83058 166255 83057 166255 83054 166255 83058 166256 83054 166256 83275 166256 83275 166257 83054 166257 83274 166257 83168 166258 83303 166258 83173 166258 83173 166259 83303 166259 83296 166259 78368 166260 83171 166260 83164 166260 83164 166261 83171 166261 83292 166261 78362 166262 83159 166262 83059 166262 83059 166263 83159 166263 83302 166263 78365 166264 83060 166264 83061 166264 83061 166265 83060 166265 83306 166265 83063 166266 83064 166266 83067 166266 83067 166267 83064 166267 83069 166267 83297 166268 83064 166268 83062 166268 83062 166269 83064 166269 83063 166269 83062 166270 83063 166270 83300 166270 83300 166271 83063 166271 83299 166271 83297 166272 83065 166272 83064 166272 83064 166273 83065 166273 83289 166273 83064 166274 83289 166274 83291 166274 83066 166275 83305 166275 83298 166275 83298 166276 83305 166276 83067 166276 83298 166277 83067 166277 83068 166277 83068 166278 83067 166278 83069 166278 83068 166279 83069 166279 83295 166279 83295 166280 83069 166280 83294 166280 83178 166281 83180 166281 83070 166281 83070 166282 83180 166282 83317 166282 78381 166283 83182 166283 83071 166283 83071 166284 83182 166284 83311 166284 78384 166285 83073 166285 83072 166285 83072 166286 83073 166286 83316 166286 78387 166287 83176 166287 83074 166287 83074 166288 83176 166288 83323 166288 83322 166289 83075 166289 83076 166289 83309 166290 83310 166290 83307 166290 83307 166291 83310 166291 83082 166291 83077 166292 83321 166292 83319 166292 83319 166293 83321 166293 83078 166293 83319 166294 83078 166294 83079 166294 83079 166295 83078 166295 83080 166295 83079 166296 83080 166296 83314 166296 83314 166297 83080 166297 83081 166297 83076 166298 83315 166298 83322 166298 83322 166299 83315 166299 83307 166299 83322 166300 83307 166300 83078 166300 83078 166301 83307 166301 83082 166301 83078 166302 83082 166302 83080 166302 83193 166303 83083 166303 78243 166303 78243 166304 83083 166304 83325 166304 78245 166305 83084 166305 83185 166305 83185 166306 83084 166306 83334 166306 78250 166307 83338 166307 83188 166307 83188 166308 83338 166308 83189 166308 78246 166309 83085 166309 78247 166309 78247 166310 83085 166310 83196 166310 83089 166311 83086 166311 83092 166311 83092 166312 83086 166312 83329 166312 83336 166313 83337 166313 83087 166313 83087 166314 83337 166314 83086 166314 83087 166315 83086 166315 83088 166315 83088 166316 83086 166316 83089 166316 83088 166317 83089 166317 83328 166317 83328 166318 83089 166318 83326 166318 83090 166319 83091 166319 83093 166319 83093 166320 83091 166320 83092 166320 83093 166321 83092 166321 83094 166321 83094 166322 83092 166322 83329 166322 83094 166323 83329 166323 83333 166323 83333 166324 83329 166324 83331 166324 83210 166325 83000 166325 78258 166325 83210 166326 78258 166326 83095 166326 83095 166327 78258 166327 83097 166327 83095 166328 83097 166328 83096 166328 83096 166329 83097 166329 83098 166329 83096 166330 83098 166330 83203 166330 83100 166331 83099 166331 78254 166331 83100 166332 78254 166332 83205 166332 83205 166333 78254 166333 83101 166333 83205 166334 83101 166334 83207 166334 83207 166335 83101 166335 83001 166335 83207 166336 83001 166336 83208 166336 82999 166337 78257 166337 78255 166337 82999 166338 78255 166338 83199 166338 83199 166339 78255 166339 78253 166339 83199 166340 78253 166340 83102 166340 83102 166341 78253 166341 82998 166341 83102 166342 82998 166342 83197 166342 83198 166343 78252 166343 83103 166343 83198 166344 83103 166344 83105 166344 83105 166345 83103 166345 83104 166345 83105 166346 83104 166346 83106 166346 83106 166347 83104 166347 83002 166347 83106 166348 83002 166348 83201 166348 83040 166349 78296 166349 78295 166349 83040 166350 78295 166350 83107 166350 83107 166351 78295 166351 83108 166351 83107 166352 83108 166352 83222 166352 83222 166353 83108 166353 83109 166353 83222 166354 83109 166354 83225 166354 83221 166355 78300 166355 83110 166355 83221 166356 83110 166356 83228 166356 83228 166357 83110 166357 78298 166357 83228 166358 78298 166358 83229 166358 83229 166359 78298 166359 83111 166359 83229 166360 83111 166360 83041 166360 83039 166361 83112 166361 83114 166361 83039 166362 83114 166362 83113 166362 83113 166363 83114 166363 83115 166363 83113 166364 83115 166364 83213 166364 83213 166365 83115 166365 83037 166365 83213 166366 83037 166366 83214 166366 83038 166367 78293 166367 78292 166367 83038 166368 78292 166368 83116 166368 83116 166369 78292 166369 83117 166369 83116 166370 83117 166370 83216 166370 83216 166371 83117 166371 78301 166371 83216 166372 78301 166372 83217 166372 83028 166373 78310 166373 83118 166373 83028 166374 83118 166374 83119 166374 83119 166375 83118 166375 83120 166375 83119 166376 83120 166376 83121 166376 83121 166377 83120 166377 83122 166377 83121 166378 83122 166378 83123 166378 83029 166379 78313 166379 83124 166379 83029 166380 83124 166380 83244 166380 83244 166381 83124 166381 78312 166381 83244 166382 78312 166382 83125 166382 83125 166383 78312 166383 78311 166383 83125 166384 78311 166384 83245 166384 83126 166385 78309 166385 83127 166385 83126 166386 83127 166386 83232 166386 83232 166387 83127 166387 83128 166387 83232 166388 83128 166388 83130 166388 83130 166389 83128 166389 83129 166389 83130 166390 83129 166390 83027 166390 83235 166391 83026 166391 83131 166391 83235 166392 83131 166392 83132 166392 83132 166393 83131 166393 83133 166393 83132 166394 83133 166394 83237 166394 83237 166395 83133 166395 83134 166395 83237 166396 83134 166396 83238 166396 83267 166397 83020 166397 83135 166397 83267 166398 83135 166398 83259 166398 83259 166399 83135 166399 78329 166399 83259 166400 78329 166400 83136 166400 83136 166401 78329 166401 83019 166401 83136 166402 83019 166402 83258 166402 83137 166403 78332 166403 78331 166403 83137 166404 78331 166404 83262 166404 83262 166405 78331 166405 83138 166405 83262 166406 83138 166406 83264 166406 83264 166407 83138 166407 83139 166407 83264 166408 83139 166408 83140 166408 83140 166409 83139 166409 83141 166409 83140 166410 83141 166410 83142 166410 83018 166411 83017 166411 83143 166411 83018 166412 83143 166412 83250 166412 83250 166413 83143 166413 83144 166413 83250 166414 83144 166414 83145 166414 83145 166415 83144 166415 83016 166415 83145 166416 83016 166416 83252 166416 83015 166417 83014 166417 78324 166417 83015 166418 78324 166418 83254 166418 83254 166419 78324 166419 78325 166419 83254 166420 78325 166420 83255 166420 83255 166421 78325 166421 78326 166421 83255 166422 78326 166422 83021 166422 83049 166423 78348 166423 78347 166423 83049 166424 78347 166424 83269 166424 83269 166425 78347 166425 83146 166425 83269 166426 83146 166426 83271 166426 83271 166427 83146 166427 83147 166427 83271 166428 83147 166428 83148 166428 83148 166429 83147 166429 83048 166429 83148 166430 83048 166430 83149 166430 83279 166431 78352 166431 78351 166431 83279 166432 78351 166432 83280 166432 83280 166433 78351 166433 78350 166433 83280 166434 78350 166434 83281 166434 83281 166435 78350 166435 78349 166435 83281 166436 78349 166436 83276 166436 83284 166437 83150 166437 83151 166437 83284 166438 83151 166438 83285 166438 83285 166439 83151 166439 78344 166439 83285 166440 78344 166440 83152 166440 83152 166441 78344 166441 78343 166441 83152 166442 78343 166442 83153 166442 83153 166443 78343 166443 83050 166443 83153 166444 83050 166444 83287 166444 83047 166445 83154 166445 78346 166445 83047 166446 78346 166446 83155 166446 83155 166447 78346 166447 83157 166447 83155 166448 83157 166448 83156 166448 83156 166449 83157 166449 83158 166449 83156 166450 83158 166450 83277 166450 83159 166451 78362 166451 83160 166451 83159 166452 83160 166452 83288 166452 83288 166453 83160 166453 83161 166453 83288 166454 83161 166454 83162 166454 83162 166455 83161 166455 83163 166455 83162 166456 83163 166456 83290 166456 83290 166457 83163 166457 83164 166457 83290 166458 83164 166458 83292 166458 83060 166459 78365 166459 83165 166459 83060 166460 83165 166460 83166 166460 83166 166461 83165 166461 83167 166461 83166 166462 83167 166462 83301 166462 83301 166463 83167 166463 83059 166463 83301 166464 83059 166464 83302 166464 83303 166465 83168 166465 78360 166465 83303 166466 78360 166466 83304 166466 83304 166467 78360 166467 83169 166467 83304 166468 83169 166468 83170 166468 83170 166469 83169 166469 83061 166469 83170 166470 83061 166470 83306 166470 83171 166471 78368 166471 78367 166471 83171 166472 78367 166472 83293 166472 83293 166473 78367 166473 78366 166473 83293 166474 78366 166474 83172 166474 83172 166475 78366 166475 83173 166475 83172 166476 83173 166476 83296 166476 83073 166477 78384 166477 78383 166477 83073 166478 78383 166478 83308 166478 83308 166479 78383 166479 83175 166479 83308 166480 83175 166480 83174 166480 83174 166481 83175 166481 83071 166481 83174 166482 83071 166482 83311 166482 83176 166483 78387 166483 78386 166483 83176 166484 78386 166484 83318 166484 83318 166485 78386 166485 78385 166485 83318 166486 78385 166486 83177 166486 83177 166487 78385 166487 83072 166487 83177 166488 83072 166488 83316 166488 83180 166489 83178 166489 83179 166489 83180 166490 83179 166490 83181 166490 83181 166491 83179 166491 78382 166491 83181 166492 78382 166492 83320 166492 83320 166493 78382 166493 83074 166493 83320 166494 83074 166494 83323 166494 83182 166495 78381 166495 83183 166495 83182 166496 83183 166496 83312 166496 83312 166497 83183 166497 83184 166497 83312 166498 83184 166498 83313 166498 83313 166499 83184 166499 83070 166499 83313 166500 83070 166500 83317 166500 83338 166501 78250 166501 78248 166501 83338 166502 78248 166502 83330 166502 83330 166503 78248 166503 78244 166503 83330 166504 78244 166504 83332 166504 83332 166505 78244 166505 83185 166505 83332 166506 83185 166506 83334 166506 83085 166507 78246 166507 83186 166507 83085 166508 83186 166508 83187 166508 83187 166509 83186 166509 78251 166509 83187 166510 78251 166510 83335 166510 83335 166511 78251 166511 83188 166511 83335 166512 83188 166512 83189 166512 83084 166513 78245 166513 83190 166513 83084 166514 83190 166514 83191 166514 83191 166515 83190 166515 83192 166515 83191 166516 83192 166516 83324 166516 83324 166517 83192 166517 78243 166517 83324 166518 78243 166518 83325 166518 83083 166519 83193 166519 78242 166519 83083 166520 78242 166520 83327 166520 83327 166521 78242 166521 83194 166521 83327 166522 83194 166522 83195 166522 83195 166523 83194 166523 78247 166523 83195 166524 78247 166524 83196 166524 83012 166525 83197 166525 83003 166525 83003 166526 83197 166526 83198 166526 83011 166527 82999 166527 83199 166527 83011 166528 83199 166528 83200 166528 83200 166529 83199 166529 83102 166529 83200 166530 83102 166530 83010 166530 83010 166531 83102 166531 83197 166531 83010 166532 83197 166532 83012 166532 83003 166533 83198 166533 83105 166533 83003 166534 83105 166534 83009 166534 83009 166535 83105 166535 83106 166535 83009 166536 83106 166536 83008 166536 83008 166537 83106 166537 83201 166537 83008 166538 83201 166538 83007 166538 83013 166539 83203 166539 83011 166539 83011 166540 83203 166540 82999 166540 83100 166541 83006 166541 83201 166541 83201 166542 83006 166542 83007 166542 83209 166543 83210 166543 83095 166543 83209 166544 83095 166544 83202 166544 83202 166545 83095 166545 83096 166545 83202 166546 83096 166546 83204 166546 83204 166547 83096 166547 83203 166547 83204 166548 83203 166548 83013 166548 83006 166549 83100 166549 83205 166549 83006 166550 83205 166550 83005 166550 83005 166551 83205 166551 83207 166551 83005 166552 83207 166552 83206 166552 83206 166553 83207 166553 83208 166553 83206 166554 83208 166554 83004 166554 83004 166555 83208 166555 83209 166555 83209 166556 83208 166556 83210 166556 83211 166557 83214 166557 83215 166557 83215 166558 83214 166558 83038 166558 83220 166559 83039 166559 83113 166559 83220 166560 83113 166560 83212 166560 83212 166561 83113 166561 83213 166561 83212 166562 83213 166562 83043 166562 83043 166563 83213 166563 83214 166563 83043 166564 83214 166564 83211 166564 83215 166565 83038 166565 83116 166565 83215 166566 83116 166566 83046 166566 83046 166567 83116 166567 83216 166567 83046 166568 83216 166568 83218 166568 83218 166569 83216 166569 83217 166569 83218 166570 83217 166570 83219 166570 83226 166571 83225 166571 83220 166571 83220 166572 83225 166572 83039 166572 83221 166573 83045 166573 83217 166573 83217 166574 83045 166574 83219 166574 83042 166575 83040 166575 83107 166575 83042 166576 83107 166576 83223 166576 83223 166577 83107 166577 83222 166577 83223 166578 83222 166578 83224 166578 83224 166579 83222 166579 83225 166579 83224 166580 83225 166580 83226 166580 83045 166581 83221 166581 83228 166581 83045 166582 83228 166582 83227 166582 83227 166583 83228 166583 83229 166583 83227 166584 83229 166584 83044 166584 83044 166585 83229 166585 83041 166585 83044 166586 83041 166586 83230 166586 83230 166587 83041 166587 83042 166587 83042 166588 83041 166588 83040 166588 83032 166589 83027 166589 83031 166589 83031 166590 83027 166590 83235 166590 83231 166591 83126 166591 83232 166591 83231 166592 83232 166592 83233 166592 83233 166593 83232 166593 83130 166593 83233 166594 83130 166594 83234 166594 83234 166595 83130 166595 83027 166595 83234 166596 83027 166596 83032 166596 83031 166597 83235 166597 83132 166597 83031 166598 83132 166598 83236 166598 83236 166599 83132 166599 83237 166599 83236 166600 83237 166600 83239 166600 83239 166601 83237 166601 83238 166601 83239 166602 83238 166602 83242 166602 83240 166603 83123 166603 83231 166603 83231 166604 83123 166604 83126 166604 83029 166605 83241 166605 83238 166605 83238 166606 83241 166606 83242 166606 83033 166607 83028 166607 83119 166607 83033 166608 83119 166608 83243 166608 83243 166609 83119 166609 83121 166609 83243 166610 83121 166610 83034 166610 83034 166611 83121 166611 83123 166611 83034 166612 83123 166612 83240 166612 83241 166613 83029 166613 83244 166613 83241 166614 83244 166614 83035 166614 83035 166615 83244 166615 83125 166615 83035 166616 83125 166616 83036 166616 83036 166617 83125 166617 83245 166617 83036 166618 83245 166618 83030 166618 83030 166619 83245 166619 83033 166619 83033 166620 83245 166620 83028 166620 83246 166621 83252 166621 83247 166621 83247 166622 83252 166622 83015 166622 83248 166623 83018 166623 83250 166623 83248 166624 83250 166624 83249 166624 83249 166625 83250 166625 83145 166625 83249 166626 83145 166626 83251 166626 83251 166627 83145 166627 83252 166627 83251 166628 83252 166628 83246 166628 83247 166629 83015 166629 83254 166629 83247 166630 83254 166630 83253 166630 83253 166631 83254 166631 83255 166631 83253 166632 83255 166632 83256 166632 83256 166633 83255 166633 83021 166633 83256 166634 83021 166634 83022 166634 83257 166635 83258 166635 83248 166635 83248 166636 83258 166636 83018 166636 83137 166637 83261 166637 83021 166637 83021 166638 83261 166638 83022 166638 83266 166639 83267 166639 83259 166639 83266 166640 83259 166640 83260 166640 83260 166641 83259 166641 83136 166641 83260 166642 83136 166642 83025 166642 83025 166643 83136 166643 83258 166643 83025 166644 83258 166644 83257 166644 83261 166645 83137 166645 83262 166645 83261 166646 83262 166646 83023 166646 83023 166647 83262 166647 83264 166647 83023 166648 83264 166648 83263 166648 83263 166649 83264 166649 83140 166649 83263 166650 83140 166650 83265 166650 83265 166651 83140 166651 83142 166651 83265 166652 83142 166652 83024 166652 83024 166653 83142 166653 83266 166653 83266 166654 83142 166654 83267 166654 83057 166655 83149 166655 83054 166655 83054 166656 83149 166656 83047 166656 83268 166657 83049 166657 83269 166657 83268 166658 83269 166658 83270 166658 83270 166659 83269 166659 83271 166659 83270 166660 83271 166660 83052 166660 83052 166661 83271 166661 83148 166661 83052 166662 83148 166662 83272 166662 83272 166663 83148 166663 83149 166663 83272 166664 83149 166664 83057 166664 83054 166665 83047 166665 83155 166665 83054 166666 83155 166666 83273 166666 83273 166667 83155 166667 83156 166667 83273 166668 83156 166668 83274 166668 83274 166669 83156 166669 83277 166669 83274 166670 83277 166670 83275 166670 83283 166671 83276 166671 83268 166671 83268 166672 83276 166672 83049 166672 83284 166673 83058 166673 83277 166673 83277 166674 83058 166674 83275 166674 83278 166675 83279 166675 83280 166675 83278 166676 83280 166676 83282 166676 83282 166677 83280 166677 83281 166677 83282 166678 83281 166678 83055 166678 83055 166679 83281 166679 83276 166679 83055 166680 83276 166680 83283 166680 83058 166681 83284 166681 83285 166681 83058 166682 83285 166682 83056 166682 83056 166683 83285 166683 83152 166683 83056 166684 83152 166684 83286 166684 83286 166685 83152 166685 83153 166685 83286 166686 83153 166686 83051 166686 83051 166687 83153 166687 83287 166687 83051 166688 83287 166688 83053 166688 83053 166689 83287 166689 83278 166689 83278 166690 83287 166690 83279 166690 83064 166691 83292 166691 83069 166691 83069 166692 83292 166692 83171 166692 83297 166693 83159 166693 83288 166693 83297 166694 83288 166694 83065 166694 83065 166695 83288 166695 83162 166695 83065 166696 83162 166696 83289 166696 83289 166697 83162 166697 83290 166697 83289 166698 83290 166698 83291 166698 83291 166699 83290 166699 83292 166699 83291 166700 83292 166700 83064 166700 83069 166701 83171 166701 83293 166701 83069 166702 83293 166702 83294 166702 83294 166703 83293 166703 83172 166703 83294 166704 83172 166704 83295 166704 83295 166705 83172 166705 83296 166705 83295 166706 83296 166706 83068 166706 83062 166707 83302 166707 83297 166707 83297 166708 83302 166708 83159 166708 83303 166709 83298 166709 83296 166709 83296 166710 83298 166710 83068 166710 83063 166711 83060 166711 83166 166711 83063 166712 83166 166712 83299 166712 83299 166713 83166 166713 83301 166713 83299 166714 83301 166714 83300 166714 83300 166715 83301 166715 83302 166715 83300 166716 83302 166716 83062 166716 83298 166717 83303 166717 83304 166717 83298 166718 83304 166718 83066 166718 83066 166719 83304 166719 83170 166719 83066 166720 83170 166720 83305 166720 83305 166721 83170 166721 83306 166721 83305 166722 83306 166722 83067 166722 83067 166723 83306 166723 83063 166723 83063 166724 83306 166724 83060 166724 83082 166725 83311 166725 83080 166725 83080 166726 83311 166726 83182 166726 83307 166727 83073 166727 83308 166727 83307 166728 83308 166728 83309 166728 83309 166729 83308 166729 83174 166729 83309 166730 83174 166730 83310 166730 83310 166731 83174 166731 83311 166731 83310 166732 83311 166732 83082 166732 83080 166733 83182 166733 83312 166733 83080 166734 83312 166734 83081 166734 83081 166735 83312 166735 83313 166735 83081 166736 83313 166736 83314 166736 83314 166737 83313 166737 83317 166737 83314 166738 83317 166738 83079 166738 83315 166739 83316 166739 83307 166739 83307 166740 83316 166740 83073 166740 83180 166741 83319 166741 83317 166741 83317 166742 83319 166742 83079 166742 83322 166743 83176 166743 83318 166743 83322 166744 83318 166744 83075 166744 83075 166745 83318 166745 83177 166745 83075 166746 83177 166746 83076 166746 83076 166747 83177 166747 83316 166747 83076 166748 83316 166748 83315 166748 83319 166749 83180 166749 83181 166749 83319 166750 83181 166750 83077 166750 83077 166751 83181 166751 83320 166751 83077 166752 83320 166752 83321 166752 83321 166753 83320 166753 83323 166753 83321 166754 83323 166754 83078 166754 83078 166755 83323 166755 83322 166755 83322 166756 83323 166756 83176 166756 83092 166757 83325 166757 83089 166757 83089 166758 83325 166758 83083 166758 83093 166759 83084 166759 83191 166759 83093 166760 83191 166760 83090 166760 83090 166761 83191 166761 83324 166761 83090 166762 83324 166762 83091 166762 83091 166763 83324 166763 83325 166763 83091 166764 83325 166764 83092 166764 83089 166765 83083 166765 83327 166765 83089 166766 83327 166766 83326 166766 83326 166767 83327 166767 83195 166767 83326 166768 83195 166768 83328 166768 83328 166769 83195 166769 83196 166769 83328 166770 83196 166770 83088 166770 83094 166771 83334 166771 83093 166771 83093 166772 83334 166772 83084 166772 83085 166773 83087 166773 83196 166773 83196 166774 83087 166774 83088 166774 83329 166775 83338 166775 83330 166775 83329 166776 83330 166776 83331 166776 83331 166777 83330 166777 83332 166777 83331 166778 83332 166778 83333 166778 83333 166779 83332 166779 83334 166779 83333 166780 83334 166780 83094 166780 83087 166781 83085 166781 83187 166781 83087 166782 83187 166782 83336 166782 83336 166783 83187 166783 83335 166783 83336 166784 83335 166784 83337 166784 83337 166785 83335 166785 83189 166785 83337 166786 83189 166786 83086 166786 83086 166787 83189 166787 83329 166787 83329 166788 83189 166788 83338 166788 78064 166789 83435 166789 83339 166789 83339 166790 83435 166790 83548 166790 83340 166791 83440 166791 78068 166791 78068 166792 83440 166792 83558 166792 83341 166793 83342 166793 83433 166793 83433 166794 83342 166794 83566 166794 78062 166795 83343 166795 83438 166795 83438 166796 83343 166796 83439 166796 83344 166797 83347 166797 83557 166797 83557 166798 83347 166798 83559 166798 83345 166799 83346 166799 83563 166799 83563 166800 83346 166800 83347 166800 83563 166801 83347 166801 83562 166801 83562 166802 83347 166802 83344 166802 83562 166803 83344 166803 83348 166803 83348 166804 83344 166804 83560 166804 83551 166805 83552 166805 83549 166805 83549 166806 83552 166806 83557 166806 83549 166807 83557 166807 83556 166807 83556 166808 83557 166808 83559 166808 83556 166809 83559 166809 83349 166809 83349 166810 83559 166810 83555 166810 83484 166811 83350 166811 83491 166811 83491 166812 83350 166812 83351 166812 83488 166813 83607 166813 78020 166813 78020 166814 83607 166814 83483 166814 78017 166815 83478 166815 78015 166815 78015 166816 83478 166816 83612 166816 78018 166817 83475 166817 83487 166817 83487 166818 83475 166818 83602 166818 83608 166819 83354 166819 83356 166819 83356 166820 83354 166820 83603 166820 83614 166821 83352 166821 83353 166821 83353 166822 83352 166822 83354 166822 83353 166823 83354 166823 83613 166823 83613 166824 83354 166824 83608 166824 83613 166825 83608 166825 83611 166825 83611 166826 83608 166826 83610 166826 83601 166827 83355 166827 83598 166827 83598 166828 83355 166828 83356 166828 83598 166829 83356 166829 83599 166829 83599 166830 83356 166830 83603 166830 83599 166831 83603 166831 83606 166831 83606 166832 83603 166832 83357 166832 83358 166833 83359 166833 78037 166833 78037 166834 83359 166834 83589 166834 83471 166835 83583 166835 83360 166835 83360 166836 83583 166836 83361 166836 83362 166837 83364 166837 83363 166837 83363 166838 83364 166838 83594 166838 78036 166839 83591 166839 83365 166839 83365 166840 83591 166840 83470 166840 83592 166841 83366 166841 83367 166841 83367 166842 83366 166842 83369 166842 83597 166843 83368 166843 83595 166843 83595 166844 83368 166844 83590 166844 83595 166845 83590 166845 83369 166845 83369 166846 83590 166846 83372 166846 83369 166847 83372 166847 83367 166847 83585 166848 83588 166848 83584 166848 83584 166849 83588 166849 83371 166849 83370 166850 83582 166850 83581 166850 83581 166851 83582 166851 83372 166851 83581 166852 83372 166852 83371 166852 83371 166853 83372 166853 83590 166853 83371 166854 83590 166854 83584 166854 83449 166855 83448 166855 83459 166855 83459 166856 83448 166856 83460 166856 83455 166857 83373 166857 78050 166857 78050 166858 83373 166858 83374 166858 78047 166859 83576 166859 83375 166859 83375 166860 83576 166860 83580 166860 83376 166861 83572 166861 83453 166861 83453 166862 83572 166862 83454 166862 83578 166863 83579 166863 83382 166863 83382 166864 83579 166864 83383 166864 83570 166865 83377 166865 83569 166865 83569 166866 83377 166866 83384 166866 83378 166867 83379 166867 83568 166867 83568 166868 83379 166868 83381 166868 83568 166869 83381 166869 83384 166869 83574 166870 83380 166870 83573 166870 83573 166871 83380 166871 83575 166871 83573 166872 83575 166872 83381 166872 83381 166873 83575 166873 83382 166873 83381 166874 83382 166874 83384 166874 83384 166875 83382 166875 83383 166875 83384 166876 83383 166876 83569 166876 77999 166877 83385 166877 78000 166877 78000 166878 83385 166878 83503 166878 77992 166879 83386 166879 77993 166879 77993 166880 83386 166880 83501 166880 83498 166881 83497 166881 83495 166881 83495 166882 83497 166882 83496 166882 78004 166883 83492 166883 83508 166883 83508 166884 83492 166884 83510 166884 83388 166885 83387 166885 83390 166885 83628 166886 83630 166886 83626 166886 83626 166887 83630 166887 83633 166887 83626 166888 83633 166888 83391 166888 83391 166889 83633 166889 83388 166889 83391 166890 83388 166890 83389 166890 83389 166891 83388 166891 83390 166891 83623 166892 83624 166892 83621 166892 83621 166893 83624 166893 83393 166893 83621 166894 83393 166894 83391 166894 83391 166895 83393 166895 83625 166895 83391 166896 83625 166896 83626 166896 83618 166897 83619 166897 83392 166897 83392 166898 83619 166898 83625 166898 83392 166899 83625 166899 83616 166899 83616 166900 83625 166900 83393 166900 77994 166901 83394 166901 77995 166901 77995 166902 83394 166902 83643 166902 83517 166903 83395 166903 83396 166903 83396 166904 83395 166904 83648 166904 78006 166905 83397 166905 78005 166905 78005 166906 83397 166906 83641 166906 83398 166907 83399 166907 83521 166907 83521 166908 83399 166908 83635 166908 83638 166909 83400 166909 83401 166909 83401 166910 83400 166910 83642 166910 83401 166911 83642 166911 83634 166911 83634 166912 83642 166912 83402 166912 83403 166913 83404 166913 83405 166913 83405 166914 83404 166914 83402 166914 83405 166915 83402 166915 83406 166915 83406 166916 83402 166916 83642 166916 83406 166917 83642 166917 83407 166917 83408 166918 83647 166918 83649 166918 83649 166919 83647 166919 83406 166919 83649 166920 83406 166920 83409 166920 83409 166921 83406 166921 83407 166921 83409 166922 83407 166922 83646 166922 83646 166923 83407 166923 83644 166923 77958 166924 83535 166924 83410 166924 83410 166925 83535 166925 83411 166925 83532 166926 83412 166926 83531 166926 83531 166927 83412 166927 83413 166927 77968 166928 83527 166928 83526 166928 83526 166929 83527 166929 83658 166929 77964 166930 83522 166930 83414 166930 83414 166931 83522 166931 83657 166931 83417 166932 83659 166932 83415 166932 83418 166933 83661 166933 83665 166933 83651 166934 83652 166934 83653 166934 83655 166935 83656 166935 83659 166935 83659 166936 83656 166936 83650 166936 83659 166937 83650 166937 83415 166937 83415 166938 83650 166938 83651 166938 83415 166939 83651 166939 83416 166939 83416 166940 83651 166940 83653 166940 83662 166941 83663 166941 83664 166941 83664 166942 83663 166942 83417 166942 83664 166943 83417 166943 83665 166943 83665 166944 83417 166944 83415 166944 83665 166945 83415 166945 83418 166945 83418 166946 83415 166946 83660 166946 77945 166947 83420 166947 83419 166947 83419 166948 83420 166948 83677 166948 77947 166949 83672 166949 77943 166949 77943 166950 83672 166950 83684 166950 83421 166951 83423 166951 83422 166951 83422 166952 83423 166952 83680 166952 77941 166953 83678 166953 83424 166953 83424 166954 83678 166954 83670 166954 83425 166955 83428 166955 83671 166955 83674 166956 83675 166956 83426 166956 83682 166957 83683 166957 83427 166957 83679 166958 83429 166958 83428 166958 83428 166959 83429 166959 83681 166959 83428 166960 83681 166960 83671 166960 83671 166961 83681 166961 83682 166961 83671 166962 83682 166962 83430 166962 83430 166963 83682 166963 83427 166963 83674 166964 83426 166964 83673 166964 83668 166965 83669 166965 83666 166965 83666 166966 83669 166966 83425 166966 83666 166967 83425 166967 83426 166967 83426 166968 83425 166968 83671 166968 83426 166969 83671 166969 83673 166969 83343 166970 78062 166970 83431 166970 83343 166971 83431 166971 83432 166971 83432 166972 83431 166972 78061 166972 83432 166973 78061 166973 83561 166973 83561 166974 78061 166974 83433 166974 83561 166975 83433 166975 83566 166975 83342 166976 83341 166976 78060 166976 83342 166977 78060 166977 83564 166977 83564 166978 78060 166978 83434 166978 83564 166979 83434 166979 83565 166979 83565 166980 83434 166980 78068 166980 83565 166981 78068 166981 83558 166981 83435 166982 78064 166982 83436 166982 83435 166983 83436 166983 83550 166983 83550 166984 83436 166984 83437 166984 83550 166985 83437 166985 83553 166985 83553 166986 83437 166986 83438 166986 83553 166987 83438 166987 83439 166987 83440 166988 83340 166988 78066 166988 83440 166989 78066 166989 83554 166989 83554 166990 78066 166990 78065 166990 83554 166991 78065 166991 83441 166991 83441 166992 78065 166992 83339 166992 83441 166993 83339 166993 83548 166993 83572 166994 83376 166994 83442 166994 83572 166995 83442 166995 83443 166995 83443 166996 83442 166996 83444 166996 83443 166997 83444 166997 83445 166997 83445 166998 83444 166998 83375 166998 83445 166999 83375 166999 83580 166999 83576 167000 78047 167000 78046 167000 83576 167001 78046 167001 83577 167001 83577 167002 78046 167002 83446 167002 83577 167003 83446 167003 83447 167003 83447 167004 83446 167004 78050 167004 83447 167005 78050 167005 83374 167005 83448 167006 83449 167006 83450 167006 83448 167007 83450 167007 83567 167007 83567 167008 83450 167008 83451 167008 83567 167009 83451 167009 83452 167009 83452 167010 83451 167010 83453 167010 83452 167011 83453 167011 83454 167011 83373 167012 83455 167012 83456 167012 83373 167013 83456 167013 83457 167013 83457 167014 83456 167014 83458 167014 83457 167015 83458 167015 83571 167015 83571 167016 83458 167016 83459 167016 83571 167017 83459 167017 83460 167017 83591 167018 78036 167018 83461 167018 83591 167019 83461 167019 83462 167019 83462 167020 83461 167020 83463 167020 83462 167021 83463 167021 83593 167021 83593 167022 83463 167022 83363 167022 83593 167023 83363 167023 83594 167023 83364 167024 83362 167024 83464 167024 83364 167025 83464 167025 83596 167025 83596 167026 83464 167026 83466 167026 83596 167027 83466 167027 83465 167027 83465 167028 83466 167028 83360 167028 83465 167029 83360 167029 83361 167029 83359 167030 83358 167030 83467 167030 83359 167031 83467 167031 83468 167031 83468 167032 83467 167032 78033 167032 83468 167033 78033 167033 83469 167033 83469 167034 78033 167034 83365 167034 83469 167035 83365 167035 83470 167035 83583 167036 83471 167036 83473 167036 83583 167037 83473 167037 83472 167037 83472 167038 83473 167038 83474 167038 83472 167039 83474 167039 83586 167039 83586 167040 83474 167040 78038 167040 83586 167041 78038 167041 83587 167041 83587 167042 78038 167042 78037 167042 83587 167043 78037 167043 83589 167043 83475 167044 78018 167044 83476 167044 83475 167045 83476 167045 83609 167045 83609 167046 83476 167046 78014 167046 83609 167047 78014 167047 83477 167047 83477 167048 78014 167048 78015 167048 83477 167049 78015 167049 83612 167049 83478 167050 78017 167050 83479 167050 83478 167051 83479 167051 83481 167051 83481 167052 83479 167052 83480 167052 83481 167053 83480 167053 83615 167053 83615 167054 83480 167054 78021 167054 83615 167055 78021 167055 83482 167055 83482 167056 78021 167056 78020 167056 83482 167057 78020 167057 83483 167057 83350 167058 83484 167058 83485 167058 83350 167059 83485 167059 83600 167059 83600 167060 83485 167060 78019 167060 83600 167061 78019 167061 83486 167061 83486 167062 78019 167062 83487 167062 83486 167063 83487 167063 83602 167063 83607 167064 83488 167064 83489 167064 83607 167065 83489 167065 83604 167065 83604 167066 83489 167066 83490 167066 83604 167067 83490 167067 83605 167067 83605 167068 83490 167068 83491 167068 83605 167069 83491 167069 83351 167069 83492 167070 78004 167070 77997 167070 83492 167071 77997 167071 83617 167071 83617 167072 77997 167072 83493 167072 83617 167073 83493 167073 83494 167073 83494 167074 83493 167074 78001 167074 83494 167075 78001 167075 83620 167075 83620 167076 78001 167076 83495 167076 83620 167077 83495 167077 83496 167077 83497 167078 83498 167078 83499 167078 83497 167079 83499 167079 83627 167079 83627 167080 83499 167080 83500 167080 83627 167081 83500 167081 83629 167081 83629 167082 83500 167082 77993 167082 83629 167083 77993 167083 83501 167083 83386 167084 77992 167084 77991 167084 83386 167085 77991 167085 83631 167085 83631 167086 77991 167086 83502 167086 83631 167087 83502 167087 83632 167087 83632 167088 83502 167088 78000 167088 83632 167089 78000 167089 83503 167089 83385 167090 77999 167090 83504 167090 83385 167091 83504 167091 83622 167091 83622 167092 83504 167092 83506 167092 83622 167093 83506 167093 83505 167093 83505 167094 83506 167094 83507 167094 83505 167095 83507 167095 83509 167095 83509 167096 83507 167096 83508 167096 83509 167097 83508 167097 83510 167097 83399 167098 83398 167098 83511 167098 83399 167099 83511 167099 83636 167099 83636 167100 83511 167100 83512 167100 83636 167101 83512 167101 83637 167101 83637 167102 83512 167102 83513 167102 83637 167103 83513 167103 83514 167103 83514 167104 83513 167104 78005 167104 83514 167105 78005 167105 83641 167105 83397 167106 78006 167106 83515 167106 83397 167107 83515 167107 83516 167107 83516 167108 83515 167108 77998 167108 83516 167109 77998 167109 83645 167109 83645 167110 77998 167110 83396 167110 83645 167111 83396 167111 83648 167111 83395 167112 83517 167112 77996 167112 83395 167113 77996 167113 83518 167113 83518 167114 77996 167114 77990 167114 83518 167115 77990 167115 83519 167115 83519 167116 77990 167116 77995 167116 83519 167117 77995 167117 83643 167117 83394 167118 77994 167118 83520 167118 83394 167119 83520 167119 83639 167119 83639 167120 83520 167120 78003 167120 83639 167121 78003 167121 83640 167121 83640 167122 78003 167122 83521 167122 83640 167123 83521 167123 83635 167123 83522 167124 77964 167124 83523 167124 83522 167125 83523 167125 83524 167125 83524 167126 83523 167126 77969 167126 83524 167127 77969 167127 83525 167127 83525 167128 77969 167128 83526 167128 83525 167129 83526 167129 83658 167129 83527 167130 77968 167130 77966 167130 83527 167131 77966 167131 83528 167131 83528 167132 77966 167132 77963 167132 83528 167133 77963 167133 83529 167133 83529 167134 77963 167134 77962 167134 83529 167135 77962 167135 83530 167135 83530 167136 77962 167136 83531 167136 83530 167137 83531 167137 83413 167137 83412 167138 83532 167138 77960 167138 83412 167139 77960 167139 83533 167139 83533 167140 77960 167140 77959 167140 83533 167141 77959 167141 83534 167141 83534 167142 77959 167142 83410 167142 83534 167143 83410 167143 83411 167143 83535 167144 77958 167144 83536 167144 83535 167145 83536 167145 83654 167145 83654 167146 83536 167146 77965 167146 83654 167147 77965 167147 83537 167147 83537 167148 77965 167148 83414 167148 83537 167149 83414 167149 83657 167149 83678 167150 77941 167150 77940 167150 83678 167151 77940 167151 83539 167151 83539 167152 77940 167152 83538 167152 83539 167153 83538 167153 83540 167153 83540 167154 83538 167154 83422 167154 83540 167155 83422 167155 83680 167155 83423 167156 83421 167156 77823 167156 83423 167157 77823 167157 83541 167157 83541 167158 77823 167158 83542 167158 83541 167159 83542 167159 83543 167159 83543 167160 83542 167160 77943 167160 83543 167161 77943 167161 83684 167161 83420 167162 77945 167162 77944 167162 83420 167163 77944 167163 83667 167163 83667 167164 77944 167164 77942 167164 83667 167165 77942 167165 83544 167165 83544 167166 77942 167166 83424 167166 83544 167167 83424 167167 83670 167167 83672 167168 77947 167168 77939 167168 83672 167169 77939 167169 83545 167169 83545 167170 77939 167170 77938 167170 83545 167171 77938 167171 83546 167171 83546 167172 77938 167172 83547 167172 83546 167173 83547 167173 83676 167173 83676 167174 83547 167174 83419 167174 83676 167175 83419 167175 83677 167175 83435 167176 83549 167176 83548 167176 83548 167177 83549 167177 83556 167177 83549 167178 83435 167178 83550 167178 83549 167179 83550 167179 83551 167179 83551 167180 83550 167180 83553 167180 83551 167181 83553 167181 83552 167181 83552 167182 83553 167182 83439 167182 83552 167183 83439 167183 83557 167183 83559 167184 83440 167184 83554 167184 83559 167185 83554 167185 83555 167185 83555 167186 83554 167186 83441 167186 83555 167187 83441 167187 83349 167187 83349 167188 83441 167188 83548 167188 83349 167189 83548 167189 83556 167189 83343 167190 83344 167190 83439 167190 83439 167191 83344 167191 83557 167191 83347 167192 83558 167192 83559 167192 83559 167193 83558 167193 83440 167193 83344 167194 83343 167194 83432 167194 83344 167195 83432 167195 83560 167195 83560 167196 83432 167196 83561 167196 83560 167197 83561 167197 83348 167197 83348 167198 83561 167198 83566 167198 83348 167199 83566 167199 83562 167199 83563 167200 83342 167200 83564 167200 83563 167201 83564 167201 83345 167201 83345 167202 83564 167202 83565 167202 83345 167203 83565 167203 83346 167203 83346 167204 83565 167204 83558 167204 83346 167205 83558 167205 83347 167205 83342 167206 83563 167206 83566 167206 83566 167207 83563 167207 83562 167207 83448 167208 83568 167208 83460 167208 83460 167209 83568 167209 83384 167209 83568 167210 83448 167210 83567 167210 83568 167211 83567 167211 83378 167211 83378 167212 83567 167212 83452 167212 83378 167213 83452 167213 83379 167213 83379 167214 83452 167214 83454 167214 83379 167215 83454 167215 83381 167215 83569 167216 83373 167216 83457 167216 83569 167217 83457 167217 83570 167217 83570 167218 83457 167218 83571 167218 83570 167219 83571 167219 83377 167219 83377 167220 83571 167220 83460 167220 83377 167221 83460 167221 83384 167221 83572 167222 83573 167222 83454 167222 83454 167223 83573 167223 83381 167223 83383 167224 83374 167224 83569 167224 83569 167225 83374 167225 83373 167225 83573 167226 83572 167226 83443 167226 83573 167227 83443 167227 83574 167227 83574 167228 83443 167228 83445 167228 83574 167229 83445 167229 83380 167229 83380 167230 83445 167230 83580 167230 83380 167231 83580 167231 83575 167231 83382 167232 83576 167232 83577 167232 83382 167233 83577 167233 83578 167233 83578 167234 83577 167234 83447 167234 83578 167235 83447 167235 83579 167235 83579 167236 83447 167236 83374 167236 83579 167237 83374 167237 83383 167237 83576 167238 83382 167238 83580 167238 83580 167239 83382 167239 83575 167239 83359 167240 83581 167240 83589 167240 83589 167241 83581 167241 83371 167241 83581 167242 83359 167242 83468 167242 83581 167243 83468 167243 83370 167243 83370 167244 83468 167244 83469 167244 83370 167245 83469 167245 83582 167245 83582 167246 83469 167246 83470 167246 83582 167247 83470 167247 83372 167247 83584 167248 83583 167248 83472 167248 83584 167249 83472 167249 83585 167249 83585 167250 83472 167250 83586 167250 83585 167251 83586 167251 83588 167251 83586 167252 83587 167252 83588 167252 83588 167253 83587 167253 83589 167253 83588 167254 83589 167254 83371 167254 83591 167255 83367 167255 83470 167255 83470 167256 83367 167256 83372 167256 83590 167257 83361 167257 83584 167257 83584 167258 83361 167258 83583 167258 83367 167259 83591 167259 83462 167259 83367 167260 83462 167260 83592 167260 83592 167261 83462 167261 83593 167261 83592 167262 83593 167262 83366 167262 83366 167263 83593 167263 83594 167263 83366 167264 83594 167264 83369 167264 83595 167265 83364 167265 83596 167265 83595 167266 83596 167266 83597 167266 83597 167267 83596 167267 83465 167267 83597 167268 83465 167268 83368 167268 83368 167269 83465 167269 83361 167269 83368 167270 83361 167270 83590 167270 83364 167271 83595 167271 83594 167271 83594 167272 83595 167272 83369 167272 83350 167273 83598 167273 83351 167273 83351 167274 83598 167274 83599 167274 83598 167275 83350 167275 83600 167275 83598 167276 83600 167276 83601 167276 83601 167277 83600 167277 83486 167277 83601 167278 83486 167278 83355 167278 83355 167279 83486 167279 83602 167279 83355 167280 83602 167280 83356 167280 83603 167281 83607 167281 83604 167281 83603 167282 83604 167282 83357 167282 83357 167283 83604 167283 83605 167283 83357 167284 83605 167284 83606 167284 83606 167285 83605 167285 83351 167285 83606 167286 83351 167286 83599 167286 83475 167287 83608 167287 83602 167287 83602 167288 83608 167288 83356 167288 83354 167289 83483 167289 83603 167289 83603 167290 83483 167290 83607 167290 83608 167291 83475 167291 83609 167291 83608 167292 83609 167292 83610 167292 83610 167293 83609 167293 83477 167293 83610 167294 83477 167294 83611 167294 83611 167295 83477 167295 83612 167295 83611 167296 83612 167296 83613 167296 83353 167297 83478 167297 83481 167297 83353 167298 83481 167298 83614 167298 83614 167299 83481 167299 83615 167299 83614 167300 83615 167300 83352 167300 83615 167301 83482 167301 83352 167301 83352 167302 83482 167302 83483 167302 83352 167303 83483 167303 83354 167303 83478 167304 83353 167304 83612 167304 83612 167305 83353 167305 83613 167305 83492 167306 83616 167306 83510 167306 83510 167307 83616 167307 83393 167307 83616 167308 83492 167308 83617 167308 83616 167309 83617 167309 83392 167309 83392 167310 83617 167310 83494 167310 83392 167311 83494 167311 83618 167311 83618 167312 83494 167312 83620 167312 83618 167313 83620 167313 83619 167313 83619 167314 83620 167314 83496 167314 83619 167315 83496 167315 83625 167315 83391 167316 83385 167316 83622 167316 83391 167317 83622 167317 83621 167317 83621 167318 83622 167318 83505 167318 83621 167319 83505 167319 83623 167319 83623 167320 83505 167320 83509 167320 83623 167321 83509 167321 83624 167321 83624 167322 83509 167322 83510 167322 83624 167323 83510 167323 83393 167323 83497 167324 83626 167324 83496 167324 83496 167325 83626 167325 83625 167325 83389 167326 83503 167326 83391 167326 83391 167327 83503 167327 83385 167327 83626 167328 83497 167328 83627 167328 83626 167329 83627 167329 83628 167329 83628 167330 83627 167330 83629 167330 83628 167331 83629 167331 83630 167331 83630 167332 83629 167332 83501 167332 83630 167333 83501 167333 83633 167333 83388 167334 83386 167334 83631 167334 83388 167335 83631 167335 83387 167335 83387 167336 83631 167336 83632 167336 83387 167337 83632 167337 83390 167337 83390 167338 83632 167338 83503 167338 83390 167339 83503 167339 83389 167339 83386 167340 83388 167340 83501 167340 83501 167341 83388 167341 83633 167341 83399 167342 83634 167342 83635 167342 83635 167343 83634 167343 83402 167343 83634 167344 83399 167344 83636 167344 83634 167345 83636 167345 83401 167345 83401 167346 83636 167346 83637 167346 83401 167347 83637 167347 83638 167347 83638 167348 83637 167348 83514 167348 83638 167349 83514 167349 83400 167349 83400 167350 83514 167350 83641 167350 83400 167351 83641 167351 83642 167351 83405 167352 83394 167352 83639 167352 83405 167353 83639 167353 83403 167353 83403 167354 83639 167354 83640 167354 83403 167355 83640 167355 83404 167355 83404 167356 83640 167356 83635 167356 83404 167357 83635 167357 83402 167357 83397 167358 83407 167358 83641 167358 83641 167359 83407 167359 83642 167359 83406 167360 83643 167360 83405 167360 83405 167361 83643 167361 83394 167361 83407 167362 83397 167362 83516 167362 83407 167363 83516 167363 83644 167363 83644 167364 83516 167364 83645 167364 83644 167365 83645 167365 83646 167365 83646 167366 83645 167366 83648 167366 83646 167367 83648 167367 83409 167367 83649 167368 83395 167368 83518 167368 83649 167369 83518 167369 83408 167369 83408 167370 83518 167370 83519 167370 83408 167371 83519 167371 83647 167371 83647 167372 83519 167372 83643 167372 83647 167373 83643 167373 83406 167373 83395 167374 83649 167374 83648 167374 83648 167375 83649 167375 83409 167375 83522 167376 83651 167376 83657 167376 83657 167377 83651 167377 83650 167377 83651 167378 83522 167378 83524 167378 83651 167379 83524 167379 83652 167379 83652 167380 83524 167380 83525 167380 83652 167381 83525 167381 83653 167381 83653 167382 83525 167382 83658 167382 83653 167383 83658 167383 83416 167383 83659 167384 83535 167384 83654 167384 83659 167385 83654 167385 83655 167385 83655 167386 83654 167386 83537 167386 83655 167387 83537 167387 83656 167387 83656 167388 83537 167388 83657 167388 83656 167389 83657 167389 83650 167389 83527 167390 83415 167390 83658 167390 83658 167391 83415 167391 83416 167391 83417 167392 83411 167392 83659 167392 83659 167393 83411 167393 83535 167393 83415 167394 83527 167394 83528 167394 83415 167395 83528 167395 83660 167395 83660 167396 83528 167396 83529 167396 83660 167397 83529 167397 83418 167397 83418 167398 83529 167398 83530 167398 83418 167399 83530 167399 83661 167399 83661 167400 83530 167400 83413 167400 83661 167401 83413 167401 83665 167401 83664 167402 83412 167402 83533 167402 83664 167403 83533 167403 83662 167403 83662 167404 83533 167404 83534 167404 83662 167405 83534 167405 83663 167405 83663 167406 83534 167406 83411 167406 83663 167407 83411 167407 83417 167407 83412 167408 83664 167408 83413 167408 83413 167409 83664 167409 83665 167409 83420 167410 83666 167410 83677 167410 83677 167411 83666 167411 83426 167411 83666 167412 83420 167412 83667 167412 83666 167413 83667 167413 83668 167413 83668 167414 83667 167414 83544 167414 83668 167415 83544 167415 83669 167415 83669 167416 83544 167416 83670 167416 83669 167417 83670 167417 83425 167417 83671 167418 83672 167418 83545 167418 83671 167419 83545 167419 83673 167419 83673 167420 83545 167420 83546 167420 83673 167421 83546 167421 83674 167421 83674 167422 83546 167422 83676 167422 83674 167423 83676 167423 83675 167423 83675 167424 83676 167424 83677 167424 83675 167425 83677 167425 83426 167425 83678 167426 83428 167426 83670 167426 83670 167427 83428 167427 83425 167427 83430 167428 83684 167428 83671 167428 83671 167429 83684 167429 83672 167429 83428 167430 83678 167430 83539 167430 83428 167431 83539 167431 83679 167431 83679 167432 83539 167432 83540 167432 83679 167433 83540 167433 83429 167433 83429 167434 83540 167434 83680 167434 83429 167435 83680 167435 83681 167435 83682 167436 83423 167436 83541 167436 83682 167437 83541 167437 83683 167437 83683 167438 83541 167438 83543 167438 83683 167439 83543 167439 83427 167439 83427 167440 83543 167440 83684 167440 83427 167441 83684 167441 83430 167441 83423 167442 83682 167442 83680 167442 83680 167443 83682 167443 83681 167443 82240 167444 77678 167444 83685 167444 83685 167445 77678 167445 83686 167445 83685 167446 83686 167446 82246 167446 82246 167447 83686 167447 77677 167447 82246 167448 77677 167448 77675 167448 83685 167449 82246 167449 83689 167449 83689 167450 82246 167450 82244 167450 82243 167451 83687 167451 82244 167451 82244 167452 83687 167452 83688 167452 82244 167453 83688 167453 83689 167453 83689 167454 83688 167454 77674 167454 83689 167455 77674 167455 77672 167455 83693 167456 83694 167456 82066 167456 82066 167457 83694 167457 82067 167457 82067 167458 83694 167458 82064 167458 82064 167459 83694 167459 83695 167459 82064 167460 83695 167460 83690 167460 83690 167461 83695 167461 83691 167461 83691 167462 83695 167462 83692 167462 83691 167463 83692 167463 82061 167463 83699 167464 81387 167464 83692 167464 83692 167465 81387 167465 82062 167465 83692 167466 82062 167466 82061 167466 83694 167467 83693 167467 77883 167467 77883 167468 83700 167468 83694 167468 83694 167469 83700 167469 83701 167469 83694 167470 83701 167470 83695 167470 83701 167471 83696 167471 83695 167471 83695 167472 83696 167472 83697 167472 83695 167473 83697 167473 83692 167473 83692 167474 83697 167474 83698 167474 83692 167475 83698 167475 83699 167475 83699 167476 83698 167476 83703 167476 77883 167477 77884 167477 83700 167477 83700 167478 77884 167478 83706 167478 83700 167479 83706 167479 83701 167479 83701 167480 83706 167480 83696 167480 83696 167481 83706 167481 83705 167481 83696 167482 83705 167482 83697 167482 83697 167483 83705 167483 83698 167483 83698 167484 83705 167484 83702 167484 83698 167485 83702 167485 83703 167485 83704 167486 83702 167486 83715 167486 83715 167487 83702 167487 83705 167487 83715 167488 83705 167488 83711 167488 83711 167489 83705 167489 83706 167489 83711 167490 83706 167490 83709 167490 83709 167491 83706 167491 77884 167491 83715 167492 83707 167492 83704 167492 83704 167493 83707 167493 83708 167493 83704 167494 83708 167494 83721 167494 83711 167495 83709 167495 83710 167495 83710 167496 83712 167496 83711 167496 83711 167497 83712 167497 78072 167497 83711 167498 78072 167498 83713 167498 83714 167499 78071 167499 83717 167499 83713 167500 83714 167500 83711 167500 83711 167501 83714 167501 83717 167501 83711 167502 83717 167502 83715 167502 83715 167503 83717 167503 83716 167503 83715 167504 83716 167504 83707 167504 78071 167505 78069 167505 83717 167505 83717 167506 78069 167506 83718 167506 83717 167507 83718 167507 83719 167507 83719 167508 83718 167508 77886 167508 83727 167509 83721 167509 83720 167509 83720 167510 83721 167510 83708 167510 83720 167511 83708 167511 83722 167511 83722 167512 83708 167512 83707 167512 83722 167513 83707 167513 83723 167513 83723 167514 83707 167514 83716 167514 83723 167515 83716 167515 83724 167515 83724 167516 83716 167516 83717 167516 83724 167517 83717 167517 83725 167517 83725 167518 83717 167518 83719 167518 83725 167519 83719 167519 77885 167519 77885 167520 83719 167520 77886 167520 77885 167521 77948 167521 83725 167521 83725 167522 77948 167522 83726 167522 83725 167523 83726 167523 83724 167523 83724 167524 83726 167524 83728 167524 83724 167525 83728 167525 83723 167525 83723 167526 83728 167526 83729 167526 83723 167527 83729 167527 83722 167527 83722 167528 83729 167528 83732 167528 83722 167529 83732 167529 83720 167529 83720 167530 83732 167530 83730 167530 83720 167531 83730 167531 83727 167531 83727 167532 83730 167532 79523 167532 83740 167533 83737 167533 83729 167533 77948 167534 77888 167534 83726 167534 83726 167535 77888 167535 83740 167535 83726 167536 83740 167536 83728 167536 83728 167537 83740 167537 83729 167537 83733 167538 79523 167538 83731 167538 83731 167539 79523 167539 83730 167539 83731 167540 83730 167540 83737 167540 83737 167541 83730 167541 83732 167541 83737 167542 83732 167542 83729 167542 83731 167543 80060 167543 83733 167543 83733 167544 80060 167544 83734 167544 83733 167545 83734 167545 83735 167545 83736 167546 80059 167546 83737 167546 83737 167547 80059 167547 83738 167547 83737 167548 83738 167548 83731 167548 83731 167549 83738 167549 83739 167549 83731 167550 83739 167550 80060 167550 83737 167551 83740 167551 83736 167551 83736 167552 83740 167552 77888 167552 83736 167553 77888 167553 80057 167553 83741 167554 83748 167554 81159 167554 81159 167555 81158 167555 83741 167555 83741 167556 81158 167556 83742 167556 83741 167557 83742 167557 80403 167557 80403 167558 83742 167558 83743 167558 80403 167559 83743 167559 80404 167559 83744 167560 81155 167560 83748 167560 83748 167561 81155 167561 81156 167561 83748 167562 81156 167562 81159 167562 83748 167563 83747 167563 83744 167563 83744 167564 83747 167564 83745 167564 83744 167565 83745 167565 83746 167565 83751 167566 77846 167566 83745 167566 83745 167567 83747 167567 83751 167567 83751 167568 83747 167568 83748 167568 83751 167569 83748 167569 83749 167569 83749 167570 83748 167570 83741 167570 83749 167571 83741 167571 80567 167571 80567 167572 83741 167572 80403 167572 80567 167573 83752 167573 83750 167573 80567 167574 83750 167574 83749 167574 83749 167575 83750 167575 83757 167575 83749 167576 83757 167576 83751 167576 83751 167577 83757 167577 83756 167577 83751 167578 83756 167578 77846 167578 83752 167579 83766 167579 83753 167579 83752 167580 83753 167580 83750 167580 83753 167581 83754 167581 83750 167581 83750 167582 83754 167582 83763 167582 83750 167583 83763 167583 83757 167583 83755 167584 83756 167584 83760 167584 83760 167585 83756 167585 83757 167585 83760 167586 83757 167586 83758 167586 83758 167587 83757 167587 83763 167587 83771 167588 77925 167588 83769 167588 83769 167589 77925 167589 83759 167589 83769 167590 83759 167590 77979 167590 78008 167591 78023 167591 83760 167591 83760 167592 78023 167592 78045 167592 78045 167593 78056 167593 83760 167593 83760 167594 78056 167594 78052 167594 83760 167595 78052 167595 83755 167595 77979 167596 78008 167596 83769 167596 83769 167597 78008 167597 83760 167597 83769 167598 83760 167598 83761 167598 83761 167599 83760 167599 83758 167599 83761 167600 83758 167600 83762 167600 83762 167601 83758 167601 83763 167601 83762 167602 83763 167602 83764 167602 83764 167603 83763 167603 83754 167603 83764 167604 83754 167604 83765 167604 83754 167605 83753 167605 83765 167605 83765 167606 83753 167606 83766 167606 83765 167607 83766 167607 83767 167607 83767 167608 78561 167608 83765 167608 83765 167609 78561 167609 83774 167609 83765 167610 83774 167610 83764 167610 83764 167611 83774 167611 83762 167611 83762 167612 83774 167612 83768 167612 83762 167613 83768 167613 83761 167613 83761 167614 83768 167614 83769 167614 83769 167615 83768 167615 83770 167615 83769 167616 83770 167616 83771 167616 83775 167617 83770 167617 83768 167617 83775 167618 83768 167618 83772 167618 83772 167619 83768 167619 83774 167619 83772 167620 83774 167620 83773 167620 83773 167621 83774 167621 78561 167621 83773 167622 78561 167622 78421 167622 77841 167623 83775 167623 83776 167623 83776 167624 83775 167624 83772 167624 78421 167625 78562 167625 83773 167625 83773 167626 78562 167626 83779 167626 83773 167627 83779 167627 83772 167627 83772 167628 83779 167628 83778 167628 83772 167629 83778 167629 83776 167629 77841 167630 83776 167630 79168 167630 79168 167631 83776 167631 79165 167631 79165 167632 83776 167632 83777 167632 83777 167633 83776 167633 83778 167633 83777 167634 83778 167634 79162 167634 79162 167635 83778 167635 79163 167635 79163 167636 83778 167636 83779 167636 79163 167637 83779 167637 83780 167637 78562 167638 78414 167638 83779 167638 83779 167639 78414 167639 79164 167639 83779 167640 79164 167640 83780 167640 81183 167641 83792 167641 83791 167641 83784 167642 83781 167642 83782 167642 83782 167643 83781 167643 81180 167643 83782 167644 81180 167644 83791 167644 83791 167645 81180 167645 83783 167645 83791 167646 83783 167646 81183 167646 83784 167647 83782 167647 81181 167647 81181 167648 83782 167648 83790 167648 81181 167649 83790 167649 83785 167649 83786 167650 83787 167650 83790 167650 83790 167651 83787 167651 83788 167651 83790 167652 83788 167652 83785 167652 80399 167653 83786 167653 83789 167653 83789 167654 83786 167654 83790 167654 83789 167655 83790 167655 83795 167655 83790 167656 83782 167656 83795 167656 83795 167657 83782 167657 83791 167657 83795 167658 83791 167658 78267 167658 78267 167659 83791 167659 83792 167659 83801 167660 80399 167660 83793 167660 83793 167661 80399 167661 83789 167661 83793 167662 83789 167662 83800 167662 83800 167663 83789 167663 83794 167663 83794 167664 83789 167664 83795 167664 83794 167665 83795 167665 83797 167665 83797 167666 83795 167666 83796 167666 83796 167667 83795 167667 78267 167667 83796 167668 78267 167668 78265 167668 78265 167669 78261 167669 83796 167669 83796 167670 78261 167670 83802 167670 83796 167671 83802 167671 83797 167671 83797 167672 83802 167672 83798 167672 83799 167673 83800 167673 83798 167673 83798 167674 83800 167674 83794 167674 83798 167675 83794 167675 83797 167675 77737 167676 83801 167676 83799 167676 83799 167677 83801 167677 83793 167677 83799 167678 83793 167678 83800 167678 78261 167679 78264 167679 83802 167679 83802 167680 78264 167680 78289 167680 83802 167681 78289 167681 78321 167681 78321 167682 78316 167682 83803 167682 83803 167683 78316 167683 78341 167683 78341 167684 78374 167684 83803 167684 83803 167685 78374 167685 78379 167685 83803 167686 78379 167686 78276 167686 78321 167687 83803 167687 83802 167687 83802 167688 83803 167688 83805 167688 83802 167689 83805 167689 83798 167689 83798 167690 83805 167690 83804 167690 83798 167691 83804 167691 83799 167691 83799 167692 83804 167692 77738 167692 83799 167693 77738 167693 77737 167693 78276 167694 83807 167694 83803 167694 83803 167695 83807 167695 83811 167695 83803 167696 83811 167696 83805 167696 83805 167697 83811 167697 83806 167697 78563 167698 77738 167698 83806 167698 83806 167699 77738 167699 83804 167699 83806 167700 83804 167700 83805 167700 78279 167701 83808 167701 83807 167701 83807 167702 83808 167702 83811 167702 83808 167703 83809 167703 83811 167703 83811 167704 83809 167704 83810 167704 83811 167705 83810 167705 83806 167705 78564 167706 78563 167706 83812 167706 83812 167707 78563 167707 83806 167707 83812 167708 83806 167708 83814 167708 83814 167709 83806 167709 83810 167709 83817 167710 78564 167710 83818 167710 83818 167711 78564 167711 83812 167711 83818 167712 83812 167712 83813 167712 83813 167713 83812 167713 83814 167713 83813 167714 83814 167714 83821 167714 83821 167715 83814 167715 83810 167715 83821 167716 83810 167716 83819 167716 83819 167717 83810 167717 83809 167717 83819 167718 83809 167718 83815 167718 83815 167719 83809 167719 83808 167719 83815 167720 83808 167720 78284 167720 78284 167721 83808 167721 78279 167721 79198 167722 79197 167722 83817 167722 79198 167723 83817 167723 83816 167723 83816 167724 83817 167724 83818 167724 83816 167725 83818 167725 83813 167725 78284 167726 79192 167726 83815 167726 83815 167727 79192 167727 79194 167727 83815 167728 79194 167728 83819 167728 83819 167729 79194 167729 83820 167729 83819 167730 83820 167730 83821 167730 83821 167731 83820 167731 79195 167731 83821 167732 79195 167732 83813 167732 83813 167733 79195 167733 83822 167733 83813 167734 83822 167734 83816 167734 78241 167735 83823 167735 80082 167735 80082 167736 83823 167736 83824 167736 83824 167737 83823 167737 80080 167737 80080 167738 83823 167738 83825 167738 80080 167739 83825 167739 80077 167739 80077 167740 83825 167740 83826 167740 83826 167741 83825 167741 83829 167741 83826 167742 83829 167742 80079 167742 79527 167743 79390 167743 83829 167743 83829 167744 79390 167744 83827 167744 83829 167745 83827 167745 80079 167745 83832 167746 79527 167746 83828 167746 83828 167747 79527 167747 83829 167747 83828 167748 83829 167748 83830 167748 83829 167749 83825 167749 83830 167749 83830 167750 83825 167750 83823 167750 83830 167751 83823 167751 78240 167751 78240 167752 83823 167752 78241 167752 83831 167753 83832 167753 83828 167753 83831 167754 83828 167754 83833 167754 83833 167755 83828 167755 83830 167755 83833 167756 83830 167756 83834 167756 83834 167757 83830 167757 78240 167757 83834 167758 78240 167758 78205 167758 78205 167759 83837 167759 83834 167759 83834 167760 83837 167760 83836 167760 83834 167761 83836 167761 83833 167761 83833 167762 83836 167762 83835 167762 83833 167763 83835 167763 83831 167763 83831 167764 83835 167764 79525 167764 83839 167765 79525 167765 83835 167765 83836 167766 83837 167766 78389 167766 78389 167767 83838 167767 83836 167767 83836 167768 83838 167768 78388 167768 83836 167769 78388 167769 83841 167769 83839 167770 83835 167770 83848 167770 83848 167771 83835 167771 83836 167771 83848 167772 83836 167772 83840 167772 83840 167773 83836 167773 83841 167773 83840 167774 83841 167774 83842 167774 83842 167775 83843 167775 83840 167775 83840 167776 83843 167776 83844 167776 83840 167777 83844 167777 83845 167777 78256 167778 83849 167778 83845 167778 83845 167779 83849 167779 83840 167779 83849 167780 83846 167780 83840 167780 83840 167781 83846 167781 83851 167781 83840 167782 83851 167782 83848 167782 83854 167783 83839 167783 83847 167783 83847 167784 83839 167784 83848 167784 83847 167785 83848 167785 83852 167785 83852 167786 83848 167786 83851 167786 83860 167787 83850 167787 78256 167787 78256 167788 83850 167788 83849 167788 83849 167789 83850 167789 83846 167789 83846 167790 83850 167790 83859 167790 83846 167791 83859 167791 83851 167791 83851 167792 83859 167792 83857 167792 83851 167793 83857 167793 83852 167793 83852 167794 83857 167794 83856 167794 83852 167795 83856 167795 83847 167795 83856 167796 83853 167796 83847 167796 83847 167797 83853 167797 83855 167797 83847 167798 83855 167798 83854 167798 83866 167799 83861 167799 83855 167799 83855 167800 83853 167800 83866 167800 83866 167801 83853 167801 83856 167801 83866 167802 83856 167802 83865 167802 83856 167803 83857 167803 83865 167803 83865 167804 83857 167804 83859 167804 83865 167805 83859 167805 83858 167805 83858 167806 83859 167806 83850 167806 83858 167807 83850 167807 83860 167807 82093 167808 82094 167808 83866 167808 83866 167809 82094 167809 83861 167809 83861 167810 82094 167810 83862 167810 83861 167811 83862 167811 81380 167811 83865 167812 83858 167812 83863 167812 83863 167813 83864 167813 83865 167813 83865 167814 83864 167814 82091 167814 83865 167815 82091 167815 83866 167815 83866 167816 82091 167816 82092 167816 83866 167817 82092 167817 82093 167817 83869 167818 82175 167818 83867 167818 83867 167819 83868 167819 83869 167819 83869 167820 83868 167820 82176 167820 83869 167821 82176 167821 81330 167821 83871 167822 81329 167822 77763 167822 77763 167823 83870 167823 83871 167823 83871 167824 83870 167824 77761 167824 83871 167825 77761 167825 81379 167825 83873 167826 83872 167826 81265 167826 81265 167827 81264 167827 83873 167827 83873 167828 81264 167828 83874 167828 83873 167829 83874 167829 81262 167829 83875 167830 80401 167830 80402 167830 80245 167831 83876 167831 80402 167831 80402 167832 83876 167832 77760 167832 80402 167833 77760 167833 83875 167833 79388 167834 83877 167834 83879 167834 83879 167835 83877 167835 83878 167835 83879 167836 83878 167836 79339 167836 79337 167837 77758 167837 83880 167837 83880 167838 77758 167838 77759 167838 83880 167839 77759 167839 79391 167839 78411 167840 83881 167840 83883 167840 83883 167841 83881 167841 83882 167841 83883 167842 83882 167842 79281 167842 78084 167843 77756 167843 78409 167843 78409 167844 77756 167844 77754 167844 78409 167845 77754 167845 78410 167845 78417 167846 83884 167846 78418 167846 78418 167847 83884 167847 79249 167847 78418 167848 79249 167848 83885 167848 78460 167849 77748 167849 83886 167849 83886 167850 77748 167850 77752 167850 83886 167851 77752 167851 83887 167851 79394 167852 83888 167852 79414 167852 79414 167853 83888 167853 80132 167853 79414 167854 80132 167854 79422 167854 83889 167855 83890 167855 79413 167855 79413 167856 83890 167856 83891 167856 79413 167857 83891 167857 83892 167857 80438 167858 83894 167858 83893 167858 83893 167859 83894 167859 83895 167859 83893 167860 83895 167860 83896 167860 83897 167861 83898 167861 80437 167861 80437 167862 83898 167862 77743 167862 80437 167863 77743 167863 80444 167863 82138 167864 83899 167864 81383 167864 81383 167865 83899 167865 83900 167865 81383 167866 83900 167866 81401 167866 77741 167867 83901 167867 81384 167867 81384 167868 83901 167868 77742 167868 81384 167869 77742 167869 81382 167869 84235 167870 83906 167870 83902 167870 83902 167871 83906 167871 87860 167871 83902 167872 87860 167872 83903 167872 83904 167873 87824 167873 83906 167873 87824 167874 87845 167874 83906 167874 83906 167875 87845 167875 83905 167875 83906 167876 83905 167876 87849 167876 87849 167877 87850 167877 83906 167877 83906 167878 87850 167878 87852 167878 83906 167879 87852 167879 87860 167879 83906 167880 83907 167880 83904 167880 83904 167881 83907 167881 84236 167881 83904 167882 84236 167882 83908 167882 83908 167883 84236 167883 83910 167883 83908 167884 83910 167884 83909 167884 83909 167885 83910 167885 83911 167885 83909 167886 83911 167886 87838 167886 87838 167887 83911 167887 87840 167887 83925 167888 84241 167888 84252 167888 83918 167889 87830 167889 84238 167889 87754 167890 87776 167890 83912 167890 83912 167891 87776 167891 87775 167891 83912 167892 87775 167892 84238 167892 83914 167893 83948 167893 83913 167893 83913 167894 87817 167894 83914 167894 83914 167895 87817 167895 87816 167895 83914 167896 87816 167896 87775 167896 87775 167897 87816 167897 87825 167897 83915 167898 83925 167898 83928 167898 87825 167899 83916 167899 87775 167899 87775 167900 83916 167900 83917 167900 87775 167901 83917 167901 84238 167901 84238 167902 83917 167902 87827 167902 84238 167903 87827 167903 83918 167903 84252 167904 87801 167904 83925 167904 83925 167905 87801 167905 87800 167905 83925 167906 87800 167906 87799 167906 87840 167907 83911 167907 87841 167907 87841 167908 83911 167908 84238 167908 87841 167909 84238 167909 87836 167909 87836 167910 84238 167910 87834 167910 83923 167911 83919 167911 83912 167911 83912 167912 83919 167912 87767 167912 83912 167913 87767 167913 87768 167913 87830 167914 83920 167914 84238 167914 84238 167915 83920 167915 83921 167915 84238 167916 83921 167916 87834 167916 83928 167917 87759 167917 83915 167917 83915 167918 87759 167918 83922 167918 83915 167919 83922 167919 83912 167919 83912 167920 83922 167920 87762 167920 83912 167921 87762 167921 83923 167921 87768 167922 87769 167922 83912 167922 83912 167923 87769 167923 87755 167923 83912 167924 87755 167924 87754 167924 87799 167925 83924 167925 83925 167925 83925 167926 83924 167926 83926 167926 83925 167927 83926 167927 87771 167927 87771 167928 83927 167928 83925 167928 83925 167929 83927 167929 87772 167929 83925 167930 87772 167930 83928 167930 83929 167931 83945 167931 83932 167931 83941 167932 83930 167932 83942 167932 83944 167933 83931 167933 83932 167933 83932 167934 83931 167934 87822 167934 83932 167935 87822 167935 83929 167935 83933 167936 87867 167936 83934 167936 83934 167937 87867 167937 87868 167937 83934 167938 87868 167938 87869 167938 87869 167939 83935 167939 83934 167939 83934 167940 83935 167940 83936 167940 83934 167941 83936 167941 87871 167941 83937 167942 87809 167942 83939 167942 83930 167943 84650 167943 83942 167943 83942 167944 84650 167944 83938 167944 83942 167945 83938 167945 83943 167945 83943 167946 83938 167946 84012 167946 83943 167947 84012 167947 83939 167947 83939 167948 84012 167948 83934 167948 83939 167949 83934 167949 83937 167949 83937 167950 83934 167950 87871 167950 83940 167951 83941 167951 83958 167951 83958 167952 83941 167952 83942 167952 83958 167953 83942 167953 83961 167953 83961 167954 83942 167954 83943 167954 83961 167955 83943 167955 83932 167955 83932 167956 83943 167956 83939 167956 83932 167957 83939 167957 83944 167957 83944 167958 83939 167958 87809 167958 84662 167959 83940 167959 83958 167959 83950 167960 83945 167960 87813 167960 87813 167961 83946 167961 83950 167961 83950 167962 83946 167962 83947 167962 83950 167963 83947 167963 87810 167963 87810 167964 87821 167964 83950 167964 83950 167965 87821 167965 87820 167965 83950 167966 87820 167966 83948 167966 83948 167967 83914 167967 83950 167967 83950 167968 83914 167968 87778 167968 83950 167969 87778 167969 83949 167969 83949 167970 83951 167970 83950 167970 83950 167971 83951 167971 83952 167971 83950 167972 83952 167972 87782 167972 83955 167973 87792 167973 83954 167973 87781 167974 83953 167974 83954 167974 83954 167975 83953 167975 87773 167975 83954 167976 87773 167976 83955 167976 87792 167977 87791 167977 83954 167977 83954 167978 87791 167978 83956 167978 83954 167979 83956 167979 84459 167979 84459 167980 83956 167980 83957 167980 83945 167981 83950 167981 83932 167981 83932 167982 83950 167982 83962 167982 83932 167983 83962 167983 83961 167983 84661 167984 84662 167984 83959 167984 83959 167985 84662 167985 83958 167985 83959 167986 83958 167986 83960 167986 83960 167987 83958 167987 83961 167987 83960 167988 83961 167988 83963 167988 83963 167989 83961 167989 83962 167989 87782 167990 87781 167990 83950 167990 83950 167991 87781 167991 83954 167991 83950 167992 83954 167992 83962 167992 83962 167993 83954 167993 84486 167993 83962 167994 84486 167994 83963 167994 83963 167995 84486 167995 84501 167995 83963 167996 84501 167996 83960 167996 83960 167997 84501 167997 84485 167997 83960 167998 84485 167998 83959 167998 83959 167999 84485 167999 83964 167999 83959 168000 83964 168000 84661 168000 84661 168001 83964 168001 84663 168001 83902 168002 83903 168002 84278 168002 84278 168003 83903 168003 83965 168003 83965 168004 87858 168004 84278 168004 84278 168005 87858 168005 87857 168005 84278 168006 87857 168006 87856 168006 83966 168007 83967 168007 83969 168007 83969 168008 83967 168008 87861 168008 87861 168009 83968 168009 83969 168009 83969 168010 83968 168010 87863 168010 83969 168011 87863 168011 87864 168011 87856 168012 83966 168012 84278 168012 84278 168013 83966 168013 83969 168013 84278 168014 83969 168014 84279 168014 84279 168015 83969 168015 83971 168015 83972 168016 83970 168016 84036 168016 84036 168017 83970 168017 83971 168017 84036 168018 83971 168018 84053 168018 84053 168019 83971 168019 83969 168019 83974 168020 83973 168020 83972 168020 83972 168021 83973 168021 84290 168021 83972 168022 84290 168022 83970 168022 83972 168023 83975 168023 83974 168023 83974 168024 83975 168024 84043 168024 83974 168025 84043 168025 83976 168025 83976 168026 84043 168026 83988 168026 83976 168027 83988 168027 83977 168027 83977 168028 83988 168028 83978 168028 83977 168029 83978 168029 84274 168029 84274 168030 83978 168030 83979 168030 83979 168031 83978 168031 83980 168031 83979 168032 83980 168032 84360 168032 84360 168033 83980 168033 84361 168033 84361 168034 83980 168034 83989 168034 84361 168035 83989 168035 83981 168035 83983 168036 83985 168036 83992 168036 83992 168037 83985 168037 84359 168037 83992 168038 84359 168038 83989 168038 83989 168039 84359 168039 84419 168039 83989 168040 84419 168040 83981 168040 83995 168041 84376 168041 83983 168041 83983 168042 84376 168042 83982 168042 83982 168043 84410 168043 83983 168043 83983 168044 84410 168044 83984 168044 83983 168045 83984 168045 83985 168045 83933 168046 84013 168046 83986 168046 84758 168047 84019 168047 83987 168047 84809 168048 83998 168048 83993 168048 83988 168049 84044 168049 84042 168049 83988 168050 84042 168050 83978 168050 83978 168051 84042 168051 84040 168051 83978 168052 84040 168052 83980 168052 83980 168053 84040 168053 84039 168053 83980 168054 84039 168054 83989 168054 83989 168055 84039 168055 83990 168055 83989 168056 83990 168056 83992 168056 83992 168057 83990 168057 83991 168057 83992 168058 83991 168058 83983 168058 83998 168059 83995 168059 83993 168059 83993 168060 83995 168060 83983 168060 83993 168061 83983 168061 83994 168061 83994 168062 83983 168062 83991 168062 84856 168063 83995 168063 83996 168063 83996 168064 83995 168064 83998 168064 83996 168065 83998 168065 83997 168065 83997 168066 83998 168066 84809 168066 84810 168067 84037 168067 84026 168067 84029 168068 83999 168068 84028 168068 84028 168069 83999 168069 84000 168069 84028 168070 84000 168070 84025 168070 84045 168071 84046 168071 84814 168071 84814 168072 84046 168072 84018 168072 84009 168073 84008 168073 84021 168073 84021 168074 84008 168074 84756 168074 84021 168075 84756 168075 84020 168075 84020 168076 84756 168076 84001 168076 84020 168077 84001 168077 84757 168077 84006 168078 84007 168078 84755 168078 84755 168079 84007 168079 84002 168079 84755 168080 84002 168080 84650 168080 84650 168081 84002 168081 83938 168081 83933 168082 83986 168082 84003 168082 84003 168083 83986 168083 83969 168083 84003 168084 83969 168084 87864 168084 84052 168085 84036 168085 84004 168085 84004 168086 84036 168086 84053 168086 83972 168087 84035 168087 83975 168087 83975 168088 84035 168088 84005 168088 83975 168089 84005 168089 84043 168089 84006 168090 84008 168090 84007 168090 84007 168091 84008 168091 84009 168091 84007 168092 84009 168092 84002 168092 84002 168093 84009 168093 84010 168093 84002 168094 84010 168094 83938 168094 83938 168095 84010 168095 84011 168095 83938 168096 84011 168096 84012 168096 84012 168097 84011 168097 84013 168097 84012 168098 84013 168098 83934 168098 83934 168099 84013 168099 83933 168099 84024 168100 84014 168100 84015 168100 84015 168101 84014 168101 84023 168101 84015 168102 84023 168102 84050 168102 84050 168103 84023 168103 84016 168103 84050 168104 84016 168104 84017 168104 84017 168105 84016 168105 84022 168105 84017 168106 84022 168106 84048 168106 84048 168107 84022 168107 83987 168107 84048 168108 83987 168108 84018 168108 84018 168109 83987 168109 84019 168109 84018 168110 84019 168110 84814 168110 84814 168111 84019 168111 84758 168111 84757 168112 84758 168112 84020 168112 84020 168113 84758 168113 83987 168113 84020 168114 83987 168114 84021 168114 84021 168115 83987 168115 84022 168115 84021 168116 84022 168116 84009 168116 84009 168117 84022 168117 84016 168117 84009 168118 84016 168118 84010 168118 84010 168119 84016 168119 84023 168119 84010 168120 84023 168120 84011 168120 84011 168121 84023 168121 84014 168121 84011 168122 84014 168122 84013 168122 84013 168123 84014 168123 84024 168123 84013 168124 84024 168124 83986 168124 84000 168125 84810 168125 84025 168125 84025 168126 84810 168126 84026 168126 84025 168127 84026 168127 84028 168127 84028 168128 84026 168128 84027 168128 84028 168129 84027 168129 84029 168129 84029 168130 84027 168130 84038 168130 84029 168131 84038 168131 84047 168131 84047 168132 84038 168132 84030 168132 84047 168133 84030 168133 84031 168133 84031 168134 84030 168134 84032 168134 84031 168135 84032 168135 84049 168135 84049 168136 84032 168136 84033 168136 84049 168137 84033 168137 84051 168137 84051 168138 84033 168138 84041 168138 84051 168139 84041 168139 84034 168139 84034 168140 84041 168140 84005 168140 84034 168141 84005 168141 84052 168141 84052 168142 84005 168142 84035 168142 84052 168143 84035 168143 84036 168143 84036 168144 84035 168144 83972 168144 84037 168145 84809 168145 84026 168145 84026 168146 84809 168146 83993 168146 84026 168147 83993 168147 84027 168147 84027 168148 83993 168148 83994 168148 84027 168149 83994 168149 84038 168149 84038 168150 83994 168150 83991 168150 84038 168151 83991 168151 84030 168151 84030 168152 83991 168152 83990 168152 84030 168153 83990 168153 84032 168153 84032 168154 83990 168154 84039 168154 84032 168155 84039 168155 84033 168155 84033 168156 84039 168156 84040 168156 84033 168157 84040 168157 84041 168157 84041 168158 84040 168158 84042 168158 84041 168159 84042 168159 84005 168159 84005 168160 84042 168160 84044 168160 84005 168161 84044 168161 84043 168161 84043 168162 84044 168162 83988 168162 84045 168163 83999 168163 84046 168163 84046 168164 83999 168164 84029 168164 84046 168165 84029 168165 84018 168165 84018 168166 84029 168166 84047 168166 84018 168167 84047 168167 84048 168167 84048 168168 84047 168168 84031 168168 84048 168169 84031 168169 84017 168169 84017 168170 84031 168170 84049 168170 84017 168171 84049 168171 84050 168171 84050 168172 84049 168172 84051 168172 84050 168173 84051 168173 84015 168173 84015 168174 84051 168174 84034 168174 84015 168175 84034 168175 84024 168175 84024 168176 84034 168176 84052 168176 84024 168177 84052 168177 83986 168177 83986 168178 84052 168178 84004 168178 83986 168179 84004 168179 83969 168179 83969 168180 84004 168180 84053 168180 87895 168181 84054 168181 84055 168181 84055 168182 84054 168182 88025 168182 84055 168183 88025 168183 87897 168183 87679 168184 84058 168184 88012 168184 84056 168185 88016 168185 84074 168185 84074 168186 88016 168186 84057 168186 84074 168187 84057 168187 84058 168187 84058 168188 84057 168188 84059 168188 84058 168189 84059 168189 88012 168189 84060 168190 84061 168190 88057 168190 88057 168191 84061 168191 84062 168191 88057 168192 84062 168192 87677 168192 88012 168193 84063 168193 87679 168193 87679 168194 84063 168194 88009 168194 87679 168195 88009 168195 84064 168195 84064 168196 88009 168196 88008 168196 88025 168197 88023 168197 84074 168197 84074 168198 88023 168198 88018 168198 84074 168199 88018 168199 84056 168199 84074 168200 84068 168200 84069 168200 88008 168201 84065 168201 84064 168201 84064 168202 84065 168202 84066 168202 84064 168203 84066 168203 87677 168203 87677 168204 84066 168204 84067 168204 87677 168205 84067 168205 88057 168205 84112 168206 87887 168206 84068 168206 84068 168207 87887 168207 87882 168207 84068 168208 87882 168208 84069 168208 84069 168209 84070 168209 84074 168209 84074 168210 84070 168210 84071 168210 84074 168211 84071 168211 84072 168211 84072 168212 87875 168212 84074 168212 84074 168213 87875 168213 84073 168213 84074 168214 84073 168214 88025 168214 88025 168215 84073 168215 84075 168215 88025 168216 84075 168216 87897 168216 84076 168217 84077 168217 84101 168217 88036 168218 84079 168218 84078 168218 84078 168219 84079 168219 88039 168219 87913 168220 87911 168220 84081 168220 84081 168221 87911 168221 88035 168221 84054 168222 87895 168222 88044 168222 88044 168223 87895 168223 84080 168223 88044 168224 84080 168224 84081 168224 84081 168225 84080 168225 84082 168225 84081 168226 84082 168226 87913 168226 88088 168227 84085 168227 88093 168227 88093 168228 84085 168228 84083 168228 88093 168229 84083 168229 88102 168229 88102 168230 84083 168230 85765 168230 88102 168231 85765 168231 84084 168231 88042 168232 84094 168232 84086 168232 84086 168233 84094 168233 84085 168233 84086 168234 84085 168234 84087 168234 84087 168235 84085 168235 88088 168235 84091 168236 85864 168236 84092 168236 84092 168237 85864 168237 84088 168237 84092 168238 84088 168238 84089 168238 88042 168239 88039 168239 84094 168239 84094 168240 88039 168240 84079 168240 84094 168241 84079 168241 87911 168241 87911 168242 84079 168242 88036 168242 87911 168243 88036 168243 88035 168243 84076 168244 84101 168244 87909 168244 85875 168245 84091 168245 84090 168245 84090 168246 84091 168246 84092 168246 84090 168247 84092 168247 84095 168247 84095 168248 84092 168248 84093 168248 84095 168249 84093 168249 84094 168249 84094 168250 84093 168250 85772 168250 84094 168251 85772 168251 84085 168251 87911 168252 87909 168252 84094 168252 84094 168253 87909 168253 84101 168253 84094 168254 84101 168254 84095 168254 84095 168255 84101 168255 84096 168255 84095 168256 84096 168256 84090 168256 84090 168257 84096 168257 85841 168257 84090 168258 85841 168258 85875 168258 87937 168259 84110 168259 84104 168259 87986 168260 84144 168260 84108 168260 85841 168261 84096 168261 85842 168261 85842 168262 84096 168262 84097 168262 85842 168263 84097 168263 85838 168263 85838 168264 84097 168264 85840 168264 84109 168265 84098 168265 84108 168265 84108 168266 84098 168266 84099 168266 84108 168267 84099 168267 87986 168267 84077 168268 84100 168268 84101 168268 84101 168269 84100 168269 84102 168269 84101 168270 84102 168270 84103 168270 84103 168271 87937 168271 84101 168271 84101 168272 87937 168272 84104 168272 84101 168273 84104 168273 84096 168273 84096 168274 84104 168274 84105 168274 84096 168275 84105 168275 84097 168275 84117 168276 85840 168276 84106 168276 84106 168277 85840 168277 84097 168277 84106 168278 84097 168278 84107 168278 84107 168279 84097 168279 84105 168279 84107 168280 84105 168280 84108 168280 84108 168281 84105 168281 84104 168281 84108 168282 84104 168282 84109 168282 84109 168283 84104 168283 84110 168283 87696 168284 87698 168284 84114 168284 84114 168285 87698 168285 84111 168285 87890 168286 87887 168286 84112 168286 87947 168287 84113 168287 84210 168287 84210 168288 84113 168288 87949 168288 87696 168289 84114 168289 87692 168289 87692 168290 84114 168290 84115 168290 87692 168291 84115 168291 84112 168291 84112 168292 84115 168292 87889 168292 84112 168293 87889 168293 87890 168293 84111 168294 87704 168294 84114 168294 84114 168295 87704 168295 84210 168295 84114 168296 84210 168296 87933 168296 87933 168297 84210 168297 87949 168297 84142 168298 84107 168298 84108 168298 88002 168299 88004 168299 84146 168299 84134 168300 84180 168300 84135 168300 85972 168301 84116 168301 84165 168301 84106 168302 84143 168302 84117 168302 84117 168303 84143 168303 84119 168303 85975 168304 84118 168304 84141 168304 84141 168305 84118 168305 85976 168305 84141 168306 85976 168306 84119 168306 84119 168307 85976 168307 84120 168307 84119 168308 84120 168308 84117 168308 84140 168309 84121 168309 85974 168309 85974 168310 84121 168310 84122 168310 84122 168311 84121 168311 84123 168311 84122 168312 84123 168312 84124 168312 85968 168313 84125 168313 84152 168313 84152 168314 84125 168314 84153 168314 84152 168315 84153 168315 84154 168315 84126 168316 85971 168316 84127 168316 84127 168317 85971 168317 85969 168317 84127 168318 85969 168318 84182 168318 84116 168319 85972 168319 84167 168319 84175 168320 84199 168320 84128 168320 84128 168321 84199 168321 86177 168321 84128 168322 86177 168322 84129 168322 84129 168323 86177 168323 86178 168323 84129 168324 86178 168324 84130 168324 84130 168325 86178 168325 85964 168325 84194 168326 84197 168326 84132 168326 84132 168327 84197 168327 84131 168327 84132 168328 84131 168328 84175 168328 84175 168329 84131 168329 84200 168329 84175 168330 84200 168330 84199 168330 84132 168331 84177 168331 84194 168331 84194 168332 84177 168332 84133 168332 84194 168333 84133 168333 84193 168333 84180 168334 84134 168334 84133 168334 84133 168335 84134 168335 84192 168335 84133 168336 84192 168336 84193 168336 84189 168337 84136 168337 84135 168337 84135 168338 84136 168338 84137 168338 84135 168339 84137 168339 84134 168339 84138 168340 84139 168340 84186 168340 84186 168341 84139 168341 87979 168341 84186 168342 87979 168342 84201 168342 85974 168343 85975 168343 84140 168343 84140 168344 85975 168344 84141 168344 84140 168345 84141 168345 84156 168345 84156 168346 84141 168346 84119 168346 84156 168347 84119 168347 84142 168347 84142 168348 84119 168348 84143 168348 84142 168349 84143 168349 84107 168349 84107 168350 84143 168350 84106 168350 84144 168351 88002 168351 84145 168351 84145 168352 88002 168352 84146 168352 84145 168353 84146 168353 84158 168353 84158 168354 84146 168354 84147 168354 84158 168355 84147 168355 84157 168355 84157 168356 84147 168356 84148 168356 84157 168357 84148 168357 84149 168357 84149 168358 84148 168358 84183 168358 84149 168359 84183 168359 84155 168359 84155 168360 84183 168360 84150 168360 84155 168361 84150 168361 84154 168361 84154 168362 84150 168362 84151 168362 84154 168363 84151 168363 84152 168363 84152 168364 84151 168364 84182 168364 84152 168365 84182 168365 85968 168365 85968 168366 84182 168366 85969 168366 84153 168367 84124 168367 84154 168367 84154 168368 84124 168368 84123 168368 84154 168369 84123 168369 84155 168369 84155 168370 84123 168370 84121 168370 84155 168371 84121 168371 84149 168371 84149 168372 84121 168372 84140 168372 84149 168373 84140 168373 84157 168373 84157 168374 84140 168374 84156 168374 84157 168375 84156 168375 84158 168375 84158 168376 84156 168376 84142 168376 84158 168377 84142 168377 84145 168377 84145 168378 84142 168378 84108 168378 84145 168379 84108 168379 84144 168379 84172 168380 84173 168380 84159 168380 84159 168381 84173 168381 84160 168381 84159 168382 84160 168382 84161 168382 84173 168383 84186 168383 84160 168383 84160 168384 84186 168384 84201 168384 84160 168385 84201 168385 84161 168385 84161 168386 84201 168386 84187 168386 84161 168387 84187 168387 84159 168387 84159 168388 84187 168388 84162 168388 84159 168389 84162 168389 84172 168389 85965 168390 85966 168390 84163 168390 84163 168391 85966 168391 84165 168391 84163 168392 84165 168392 84164 168392 84164 168393 84165 168393 84116 168393 84164 168394 84116 168394 84176 168394 84176 168395 84116 168395 84167 168395 84176 168396 84167 168396 84166 168396 84166 168397 84167 168397 84168 168397 84166 168398 84168 168398 84178 168398 84178 168399 84168 168399 84169 168399 84178 168400 84169 168400 84179 168400 84179 168401 84169 168401 84170 168401 84179 168402 84170 168402 84181 168402 84181 168403 84170 168403 84171 168403 84181 168404 84171 168404 84172 168404 84172 168405 84171 168405 84184 168405 84172 168406 84184 168406 84173 168406 84173 168407 84184 168407 84185 168407 84173 168408 84185 168408 84186 168408 85964 168409 84174 168409 84130 168409 84130 168410 84174 168410 85965 168410 84130 168411 85965 168411 84129 168411 84129 168412 85965 168412 84163 168412 84129 168413 84163 168413 84128 168413 84128 168414 84163 168414 84164 168414 84128 168415 84164 168415 84175 168415 84175 168416 84164 168416 84176 168416 84175 168417 84176 168417 84132 168417 84132 168418 84176 168418 84166 168418 84132 168419 84166 168419 84177 168419 84177 168420 84166 168420 84178 168420 84177 168421 84178 168421 84133 168421 84133 168422 84178 168422 84179 168422 84133 168423 84179 168423 84180 168423 84180 168424 84179 168424 84181 168424 84180 168425 84181 168425 84135 168425 84135 168426 84181 168426 84172 168426 84135 168427 84172 168427 84189 168427 84189 168428 84172 168428 84162 168428 85972 168429 84126 168429 84167 168429 84167 168430 84126 168430 84127 168430 84167 168431 84127 168431 84168 168431 84168 168432 84127 168432 84182 168432 84168 168433 84182 168433 84169 168433 84169 168434 84182 168434 84151 168434 84169 168435 84151 168435 84170 168435 84170 168436 84151 168436 84150 168436 84170 168437 84150 168437 84171 168437 84171 168438 84150 168438 84183 168438 84171 168439 84183 168439 84184 168439 84184 168440 84183 168440 84148 168440 84184 168441 84148 168441 84185 168441 84185 168442 84148 168442 84147 168442 84185 168443 84147 168443 84186 168443 84186 168444 84147 168444 84146 168444 84186 168445 84146 168445 84138 168445 84138 168446 84146 168446 88004 168446 84187 168447 87388 168447 84162 168447 84162 168448 87388 168448 84188 168448 84162 168449 84188 168449 84189 168449 84189 168450 84188 168450 87384 168450 84189 168451 87384 168451 84136 168451 84136 168452 87384 168452 84190 168452 84190 168453 87383 168453 84136 168453 84136 168454 87383 168454 84191 168454 84136 168455 84191 168455 84137 168455 84137 168456 84191 168456 87353 168456 84137 168457 87353 168457 84134 168457 84134 168458 87353 168458 87354 168458 84134 168459 87354 168459 84192 168459 84192 168460 87354 168460 87361 168460 84192 168461 87361 168461 84193 168461 84193 168462 87361 168462 87360 168462 84193 168463 87360 168463 84194 168463 84194 168464 87360 168464 84195 168464 84194 168465 84195 168465 84197 168465 84197 168466 84195 168466 84196 168466 84197 168467 84196 168467 84131 168467 84131 168468 84196 168468 84198 168468 84131 168469 84198 168469 84200 168469 86179 168470 86177 168470 84198 168470 84198 168471 86177 168471 84199 168471 84198 168472 84199 168472 84200 168472 84201 168473 84203 168473 87394 168473 87394 168474 87392 168474 84201 168474 84201 168475 87392 168475 87390 168475 84201 168476 87390 168476 84187 168476 84187 168477 87390 168477 87389 168477 84187 168478 87389 168478 87388 168478 87979 168479 84202 168479 84201 168479 84201 168480 84202 168480 87965 168480 84201 168481 87965 168481 84203 168481 87965 168482 87964 168482 84203 168482 84203 168483 87964 168483 84204 168483 84203 168484 84204 168484 84205 168484 84205 168485 84204 168485 87963 168485 84205 168486 87963 168486 84206 168486 84206 168487 87963 168487 84207 168487 87963 168488 87960 168488 84207 168488 84207 168489 87960 168489 87958 168489 84207 168490 87958 168490 84209 168490 85693 168491 84207 168491 84208 168491 84208 168492 84207 168492 84209 168492 84208 168493 84209 168493 84210 168493 84210 168494 84209 168494 87947 168494 84211 168495 84244 168495 84212 168495 84216 168496 84212 168496 84223 168496 84229 168497 84261 168497 84216 168497 84212 168498 84216 168498 84211 168498 84211 168499 84216 168499 84237 168499 84211 168500 84237 168500 84218 168500 84213 168501 84214 168501 84216 168501 84216 168502 84214 168502 84308 168502 84216 168503 84308 168503 84215 168503 84215 168504 84247 168504 84216 168504 84216 168505 84247 168505 84248 168505 84216 168506 84248 168506 84239 168506 84261 168507 84217 168507 84216 168507 84216 168508 84217 168508 84263 168508 84216 168509 84263 168509 84264 168509 84218 168510 84219 168510 84211 168510 84211 168511 84219 168511 84220 168511 84211 168512 84220 168512 84234 168512 84221 168513 84240 168513 84248 168513 84248 168514 84240 168514 84222 168514 84248 168515 84222 168515 84239 168515 84223 168516 84224 168516 84216 168516 84216 168517 84224 168517 84257 168517 84216 168518 84257 168518 84259 168518 84264 168519 84225 168519 84216 168519 84216 168520 84225 168520 84302 168520 84216 168521 84302 168521 84226 168521 84259 168522 84227 168522 84216 168522 84216 168523 84227 168523 84228 168523 84216 168524 84228 168524 84229 168524 84226 168525 84230 168525 84216 168525 84216 168526 84230 168526 84304 168526 84216 168527 84304 168527 84305 168527 84305 168528 84231 168528 84216 168528 84216 168529 84231 168529 84306 168529 84216 168530 84306 168530 84213 168530 84211 168531 84234 168531 84232 168531 84232 168532 84234 168532 84233 168532 84233 168533 84234 168533 84235 168533 84235 168534 84234 168534 84220 168534 84235 168535 84220 168535 83906 168535 83906 168536 84220 168536 84219 168536 83906 168537 84219 168537 83907 168537 83907 168538 84219 168538 84218 168538 83907 168539 84218 168539 84236 168539 84236 168540 84218 168540 84237 168540 84236 168541 84237 168541 83910 168541 83910 168542 84237 168542 83911 168542 83911 168543 84237 168543 84216 168543 83911 168544 84216 168544 84238 168544 84238 168545 84216 168545 84239 168545 84238 168546 84239 168546 83912 168546 83912 168547 84239 168547 84222 168547 83912 168548 84222 168548 83915 168548 83915 168549 84222 168549 84240 168549 83915 168550 84240 168550 83925 168550 83925 168551 84240 168551 84241 168551 84241 168552 84240 168552 84221 168552 84241 168553 84221 168553 84242 168553 84242 168554 84221 168554 84248 168554 84242 168555 84248 168555 84246 168555 84233 168556 84235 168556 83902 168556 83902 168557 84251 168557 84233 168557 84233 168558 84251 168558 84243 168558 84233 168559 84243 168559 84232 168559 84232 168560 84243 168560 84282 168560 84232 168561 84282 168561 84280 168561 84232 168562 84280 168562 84211 168562 84211 168563 84280 168563 84254 168563 84254 168564 84295 168564 84211 168564 84211 168565 84295 168565 84255 168565 84211 168566 84255 168566 84244 168566 84314 168567 84312 168567 84252 168567 84316 168568 84245 168568 84246 168568 84246 168569 84245 168569 84314 168569 84246 168570 84314 168570 84242 168570 84242 168571 84314 168571 84252 168571 84242 168572 84252 168572 84241 168572 84316 168573 84246 168573 84318 168573 84318 168574 84246 168574 84248 168574 84247 168575 84340 168575 84248 168575 84248 168576 84340 168576 84339 168576 84248 168577 84339 168577 84318 168577 84278 168578 84249 168578 83902 168578 83902 168579 84249 168579 84250 168579 83902 168580 84250 168580 84251 168580 84552 168581 84252 168581 84319 168581 84319 168582 84252 168582 84312 168582 84293 168583 84298 168583 84291 168583 84280 168584 84253 168584 84254 168584 84243 168585 84286 168585 84281 168585 84290 168586 83973 168586 84292 168586 84292 168587 83973 168587 83974 168587 84244 168588 84255 168588 84296 168588 84380 168589 84256 168589 84244 168589 84244 168590 84256 168590 84212 168590 84212 168591 84256 168591 84223 168591 84223 168592 84256 168592 84382 168592 84223 168593 84382 168593 84224 168593 84224 168594 84382 168594 84383 168594 84224 168595 84383 168595 84257 168595 84383 168596 84258 168596 84257 168596 84257 168597 84258 168597 84260 168597 84257 168598 84260 168598 84259 168598 84259 168599 84260 168599 84384 168599 84263 168600 84217 168600 84388 168600 84388 168601 84217 168601 84261 168601 84388 168602 84261 168602 84262 168602 84262 168603 84261 168603 84229 168603 84262 168604 84229 168604 84385 168604 84385 168605 84229 168605 84228 168605 84385 168606 84228 168606 84384 168606 84384 168607 84228 168607 84227 168607 84384 168608 84227 168608 84259 168608 84388 168609 84393 168609 84263 168609 84263 168610 84393 168610 84303 168610 84263 168611 84303 168611 84264 168611 84244 168612 84296 168612 84380 168612 84380 168613 84296 168613 84265 168613 84380 168614 84265 168614 84269 168614 84267 168615 84270 168615 84271 168615 84271 168616 84266 168616 84267 168616 84267 168617 84266 168617 84268 168617 84267 168618 84268 168618 84265 168618 84265 168619 84268 168619 84412 168619 84265 168620 84412 168620 84269 168620 84273 168621 84407 168621 84270 168621 84270 168622 84407 168622 84431 168622 84270 168623 84431 168623 84271 168623 84298 168624 84272 168624 84273 168624 84273 168625 84272 168625 84406 168625 84273 168626 84406 168626 84407 168626 84294 168627 83977 168627 84274 168627 84274 168628 84275 168628 84294 168628 84294 168629 84275 168629 84276 168629 84294 168630 84276 168630 84293 168630 84293 168631 84276 168631 84405 168631 84293 168632 84405 168632 84298 168632 84298 168633 84405 168633 84277 168633 84298 168634 84277 168634 84272 168634 84288 168635 83971 168635 84301 168635 84301 168636 83971 168636 83970 168636 84250 168637 84249 168637 84287 168637 84287 168638 84249 168638 84278 168638 84287 168639 84278 168639 84288 168639 84288 168640 84278 168640 84279 168640 84288 168641 84279 168641 83971 168641 84286 168642 84243 168642 84287 168642 84287 168643 84243 168643 84251 168643 84287 168644 84251 168644 84250 168644 84253 168645 84280 168645 84281 168645 84281 168646 84280 168646 84282 168646 84281 168647 84282 168647 84243 168647 84295 168648 84254 168648 84283 168648 84283 168649 84254 168649 84253 168649 84283 168650 84253 168650 84284 168650 84284 168651 84253 168651 84281 168651 84284 168652 84281 168652 84285 168652 84285 168653 84281 168653 84286 168653 84285 168654 84286 168654 84297 168654 84297 168655 84286 168655 84287 168655 84297 168656 84287 168656 84299 168656 84299 168657 84287 168657 84288 168657 84299 168658 84288 168658 84300 168658 84300 168659 84288 168659 84301 168659 84289 168660 84290 168660 84291 168660 84291 168661 84290 168661 84292 168661 84291 168662 84292 168662 84293 168662 84293 168663 84292 168663 83974 168663 84293 168664 83974 168664 84294 168664 84294 168665 83974 168665 83976 168665 84294 168666 83976 168666 83977 168666 84255 168667 84295 168667 84296 168667 84296 168668 84295 168668 84283 168668 84296 168669 84283 168669 84265 168669 84265 168670 84283 168670 84284 168670 84265 168671 84284 168671 84267 168671 84267 168672 84284 168672 84285 168672 84267 168673 84285 168673 84270 168673 84270 168674 84285 168674 84297 168674 84270 168675 84297 168675 84273 168675 84273 168676 84297 168676 84299 168676 84273 168677 84299 168677 84298 168677 84298 168678 84299 168678 84300 168678 84298 168679 84300 168679 84291 168679 84291 168680 84300 168680 84301 168680 84291 168681 84301 168681 84289 168681 84289 168682 84301 168682 83970 168682 84289 168683 83970 168683 84290 168683 84541 168684 84349 168684 84543 168684 84225 168685 84264 168685 84303 168685 84225 168686 84303 168686 84302 168686 84302 168687 84303 168687 84589 168687 84302 168688 84589 168688 84226 168688 84226 168689 84589 168689 84595 168689 84226 168690 84595 168690 84230 168690 84230 168691 84595 168691 84304 168691 84304 168692 84595 168692 84594 168692 84304 168693 84594 168693 84305 168693 84305 168694 84594 168694 84579 168694 84305 168695 84579 168695 84231 168695 84231 168696 84579 168696 84578 168696 84231 168697 84578 168697 84306 168697 84306 168698 84578 168698 84307 168698 84306 168699 84307 168699 84213 168699 84213 168700 84307 168700 84554 168700 84213 168701 84554 168701 84214 168701 84214 168702 84554 168702 84309 168702 84214 168703 84309 168703 84308 168703 84308 168704 84309 168704 84310 168704 84308 168705 84310 168705 84215 168705 84215 168706 84310 168706 84632 168706 84215 168707 84632 168707 84247 168707 84247 168708 84632 168708 84631 168708 84247 168709 84631 168709 84340 168709 84311 168710 84312 168710 84313 168710 84313 168711 84312 168711 84314 168711 84313 168712 84314 168712 84315 168712 84315 168713 84314 168713 84245 168713 84315 168714 84245 168714 84317 168714 84317 168715 84245 168715 84316 168715 84317 168716 84316 168716 84318 168716 84323 168717 84552 168717 84311 168717 84311 168718 84552 168718 84319 168718 84311 168719 84319 168719 84312 168719 84336 168720 84540 168720 84320 168720 84320 168721 84540 168721 84321 168721 84320 168722 84321 168722 84322 168722 84322 168723 84321 168723 84323 168723 84322 168724 84323 168724 84333 168724 84333 168725 84323 168725 84311 168725 84533 168726 84337 168726 84555 168726 84555 168727 84337 168727 84324 168727 84348 168728 84328 168728 84338 168728 84338 168729 84328 168729 84609 168729 84338 168730 84609 168730 84324 168730 84324 168731 84609 168731 84325 168731 84324 168732 84325 168732 84555 168732 84326 168733 84346 168733 84329 168733 84329 168734 84617 168734 84326 168734 84326 168735 84617 168735 84610 168735 84326 168736 84610 168736 84348 168736 84348 168737 84610 168737 84327 168737 84348 168738 84327 168738 84328 168738 84345 168739 84620 168739 84346 168739 84346 168740 84620 168740 84618 168740 84346 168741 84618 168741 84329 168741 84340 168742 84631 168742 84330 168742 84330 168743 84631 168743 84630 168743 84330 168744 84630 168744 84343 168744 84343 168745 84630 168745 84331 168745 84343 168746 84331 168746 84345 168746 84345 168747 84331 168747 84628 168747 84345 168748 84628 168748 84620 168748 84318 168749 84339 168749 84317 168749 84317 168750 84339 168750 84332 168750 84317 168751 84332 168751 84315 168751 84315 168752 84332 168752 84341 168752 84315 168753 84341 168753 84313 168753 84313 168754 84341 168754 84342 168754 84313 168755 84342 168755 84311 168755 84311 168756 84342 168756 84344 168756 84311 168757 84344 168757 84333 168757 84333 168758 84344 168758 84347 168758 84333 168759 84347 168759 84322 168759 84322 168760 84347 168760 84334 168760 84322 168761 84334 168761 84320 168761 84320 168762 84334 168762 84335 168762 84320 168763 84335 168763 84336 168763 84337 168764 84546 168764 84324 168764 84324 168765 84546 168765 84543 168765 84324 168766 84543 168766 84338 168766 84338 168767 84543 168767 84349 168767 84338 168768 84349 168768 84348 168768 84339 168769 84340 168769 84332 168769 84332 168770 84340 168770 84330 168770 84332 168771 84330 168771 84341 168771 84341 168772 84330 168772 84343 168772 84341 168773 84343 168773 84342 168773 84342 168774 84343 168774 84345 168774 84342 168775 84345 168775 84344 168775 84344 168776 84345 168776 84346 168776 84344 168777 84346 168777 84347 168777 84347 168778 84346 168778 84326 168778 84347 168779 84326 168779 84334 168779 84334 168780 84326 168780 84348 168780 84334 168781 84348 168781 84335 168781 84335 168782 84348 168782 84349 168782 84335 168783 84349 168783 84336 168783 84336 168784 84349 168784 84541 168784 84396 168785 84446 168785 84439 168785 84350 168786 84369 168786 84351 168786 84355 168787 84356 168787 84860 168787 84860 168788 84356 168788 85543 168788 84860 168789 85543 168789 84859 168789 84859 168790 85543 168790 84377 168790 85003 168791 92493 168791 84352 168791 84352 168792 92493 168792 84353 168792 84352 168793 84353 168793 84857 168793 84857 168794 84353 168794 85545 168794 84857 168795 85545 168795 84858 168795 84858 168796 85545 168796 84354 168796 84858 168797 84354 168797 84355 168797 84355 168798 84354 168798 92307 168798 84355 168799 92307 168799 84356 168799 84376 168800 84357 168800 83982 168800 83982 168801 84357 168801 84358 168801 83982 168802 84358 168802 84410 168802 84359 168803 83985 168803 84418 168803 84418 168804 83985 168804 83984 168804 84360 168805 84361 168805 84417 168805 84417 168806 84361 168806 83981 168806 84417 168807 83981 168807 84419 168807 92474 168808 84362 168808 85524 168808 85524 168809 84362 168809 84433 168809 84350 168810 92281 168810 84363 168810 84363 168811 92281 168811 84364 168811 84363 168812 84364 168812 84365 168812 84365 168813 84364 168813 85520 168813 84365 168814 85520 168814 84367 168814 84367 168815 85520 168815 84366 168815 84367 168816 84366 168816 84368 168816 84368 168817 84366 168817 85524 168817 84368 168818 85524 168818 84434 168818 84434 168819 85524 168819 84433 168819 84350 168820 84363 168820 84369 168820 84369 168821 84363 168821 84370 168821 84369 168822 84370 168822 84351 168822 84351 168823 84370 168823 84440 168823 84351 168824 84440 168824 84371 168824 84440 168825 84413 168825 84371 168825 84371 168826 84413 168826 84372 168826 84371 168827 84372 168827 84373 168827 84373 168828 84372 168828 84374 168828 84373 168829 84374 168829 85530 168829 85530 168830 84374 168830 92483 168830 92483 168831 84374 168831 84408 168831 92483 168832 84408 168832 85531 168832 85536 168833 85535 168833 84375 168833 84375 168834 85535 168834 85534 168834 84375 168835 85534 168835 84409 168835 84409 168836 85534 168836 85533 168836 84409 168837 85533 168837 85531 168837 84376 168838 84859 168838 84357 168838 84357 168839 84859 168839 84377 168839 84357 168840 84377 168840 84358 168840 84358 168841 84377 168841 84378 168841 84378 168842 85540 168842 84358 168842 84358 168843 85540 168843 85539 168843 84358 168844 85539 168844 84375 168844 84375 168845 85539 168845 84379 168845 84375 168846 84379 168846 85536 168846 84256 168847 84380 168847 84425 168847 84425 168848 84380 168848 84427 168848 84256 168849 84425 168849 84382 168849 84382 168850 84425 168850 84381 168850 84382 168851 84381 168851 84383 168851 84383 168852 84381 168852 84258 168852 84258 168853 84381 168853 84424 168853 84258 168854 84424 168854 84260 168854 84260 168855 84424 168855 84422 168855 84260 168856 84422 168856 84384 168856 84384 168857 84422 168857 84385 168857 84385 168858 84422 168858 84386 168858 84385 168859 84386 168859 84262 168859 84262 168860 84386 168860 84387 168860 84262 168861 84387 168861 84388 168861 84388 168862 84387 168862 84394 168862 84388 168863 84394 168863 84393 168863 84426 168864 84389 168864 84390 168864 84390 168865 84389 168865 84445 168865 84390 168866 84445 168866 84423 168866 84423 168867 84445 168867 84391 168867 84423 168868 84391 168868 84421 168868 84421 168869 84391 168869 84443 168869 84421 168870 84443 168870 84392 168870 84392 168871 84443 168871 84403 168871 84392 168872 84403 168872 84402 168872 84303 168873 84393 168873 84395 168873 84395 168874 84393 168874 84394 168874 84395 168875 84394 168875 84420 168875 84446 168876 84396 168876 84397 168876 84397 168877 84396 168877 84398 168877 84397 168878 84398 168878 84399 168878 84399 168879 84398 168879 84438 168879 84399 168880 84438 168880 84444 168880 84444 168881 84438 168881 84437 168881 84444 168882 84437 168882 84400 168882 84400 168883 84437 168883 84436 168883 84400 168884 84436 168884 84442 168884 84442 168885 84436 168885 84435 168885 84442 168886 84435 168886 84605 168886 84420 168887 84402 168887 84401 168887 84401 168888 84402 168888 84403 168888 84401 168889 84403 168889 84605 168889 84274 168890 83979 168890 84275 168890 84275 168891 83979 168891 84404 168891 84275 168892 84404 168892 84276 168892 84276 168893 84404 168893 84453 168893 84276 168894 84453 168894 84405 168894 84405 168895 84453 168895 84277 168895 84277 168896 84453 168896 84451 168896 84277 168897 84451 168897 84272 168897 84272 168898 84451 168898 84406 168898 84406 168899 84451 168899 84432 168899 84406 168900 84432 168900 84407 168900 85531 168901 84408 168901 84409 168901 84409 168902 84408 168902 84416 168902 84409 168903 84416 168903 84375 168903 84375 168904 84416 168904 84418 168904 84375 168905 84418 168905 84358 168905 84358 168906 84418 168906 83984 168906 84358 168907 83984 168907 84410 168907 84411 168908 84266 168908 84271 168908 84266 168909 84411 168909 84268 168909 84268 168910 84411 168910 84429 168910 84268 168911 84429 168911 84412 168911 84413 168912 84450 168912 84372 168912 84372 168913 84450 168913 84414 168913 84372 168914 84414 168914 84374 168914 84374 168915 84414 168915 84415 168915 84374 168916 84415 168916 84408 168916 84408 168917 84415 168917 84452 168917 84408 168918 84452 168918 84416 168918 84416 168919 84452 168919 84417 168919 84416 168920 84417 168920 84418 168920 84418 168921 84417 168921 84419 168921 84418 168922 84419 168922 84359 168922 84427 168923 84380 168923 84429 168923 84429 168924 84380 168924 84269 168924 84429 168925 84269 168925 84412 168925 84420 168926 84394 168926 84402 168926 84402 168927 84394 168927 84387 168927 84402 168928 84387 168928 84392 168928 84392 168929 84387 168929 84386 168929 84392 168930 84386 168930 84421 168930 84421 168931 84386 168931 84422 168931 84421 168932 84422 168932 84423 168932 84423 168933 84422 168933 84424 168933 84423 168934 84424 168934 84390 168934 84390 168935 84424 168935 84381 168935 84390 168936 84381 168936 84426 168936 84426 168937 84381 168937 84425 168937 84426 168938 84425 168938 84447 168938 84447 168939 84425 168939 84427 168939 84447 168940 84427 168940 84428 168940 84428 168941 84427 168941 84429 168941 84428 168942 84429 168942 84430 168942 84430 168943 84429 168943 84411 168943 84430 168944 84411 168944 84449 168944 84449 168945 84411 168945 84271 168945 84449 168946 84271 168946 84432 168946 84432 168947 84271 168947 84431 168947 84432 168948 84431 168948 84407 168948 84362 168949 84605 168949 84433 168949 84433 168950 84605 168950 84435 168950 84433 168951 84435 168951 84434 168951 84434 168952 84435 168952 84436 168952 84434 168953 84436 168953 84368 168953 84368 168954 84436 168954 84437 168954 84368 168955 84437 168955 84367 168955 84367 168956 84437 168956 84438 168956 84367 168957 84438 168957 84365 168957 84365 168958 84438 168958 84398 168958 84365 168959 84398 168959 84363 168959 84363 168960 84398 168960 84396 168960 84363 168961 84396 168961 84370 168961 84370 168962 84396 168962 84439 168962 84370 168963 84439 168963 84440 168963 84440 168964 84439 168964 84441 168964 84440 168965 84441 168965 84413 168965 84413 168966 84441 168966 84448 168966 84413 168967 84448 168967 84450 168967 84605 168968 84403 168968 84442 168968 84442 168969 84403 168969 84443 168969 84442 168970 84443 168970 84400 168970 84400 168971 84443 168971 84391 168971 84400 168972 84391 168972 84444 168972 84444 168973 84391 168973 84445 168973 84444 168974 84445 168974 84399 168974 84399 168975 84445 168975 84389 168975 84399 168976 84389 168976 84397 168976 84397 168977 84389 168977 84426 168977 84397 168978 84426 168978 84446 168978 84446 168979 84426 168979 84447 168979 84446 168980 84447 168980 84439 168980 84439 168981 84447 168981 84428 168981 84439 168982 84428 168982 84441 168982 84441 168983 84428 168983 84430 168983 84441 168984 84430 168984 84448 168984 84448 168985 84430 168985 84449 168985 84448 168986 84449 168986 84450 168986 84450 168987 84449 168987 84432 168987 84450 168988 84432 168988 84414 168988 84414 168989 84432 168989 84451 168989 84414 168990 84451 168990 84415 168990 84415 168991 84451 168991 84453 168991 84415 168992 84453 168992 84452 168992 84452 168993 84453 168993 84404 168993 84452 168994 84404 168994 84417 168994 84417 168995 84404 168995 83979 168995 84417 168996 83979 168996 84360 168996 84542 168997 84544 168997 84454 168997 84466 168998 84502 168998 84678 168998 84464 168999 84455 168999 84523 168999 84463 169000 84456 169000 84495 169000 84485 169001 84457 169001 84500 169001 84501 169002 84487 169002 84488 169002 83957 169003 84458 169003 84530 169003 84530 169004 84458 169004 87788 169004 84530 169005 87788 169005 87786 169005 84486 169006 83954 169006 84530 169006 84530 169007 83954 169007 84459 169007 84530 169008 84459 169008 83957 169008 84460 169009 84685 169009 84484 169009 84484 169010 84685 169010 84663 169010 84484 169011 84663 169011 84461 169011 84461 169012 84663 169012 83964 169012 84482 169013 84496 169013 84462 169013 84456 169014 84463 169014 84493 169014 84455 169015 84464 169015 84494 169015 84465 169016 84503 169016 84679 169016 84502 169017 84466 169017 84503 169017 84503 169018 84466 169018 84467 169018 84503 169019 84467 169019 84679 169019 84468 169020 84676 169020 84469 169020 84512 169021 84470 169021 84471 169021 84471 169022 84470 169022 84473 169022 84471 169023 84473 169023 84871 169023 84470 169024 84472 169024 84473 169024 84473 169025 84472 169025 84514 169025 84473 169026 84514 169026 84474 169026 84474 169027 84514 169027 84515 169027 84474 169028 84515 169028 84475 169028 84475 169029 84515 169029 84477 169029 84475 169030 84477 169030 84476 169030 84476 169031 84477 169031 84480 169031 84544 169032 84545 169032 84454 169032 84454 169033 84545 169033 84531 169033 84454 169034 84531 169034 84519 169034 84519 169035 84531 169035 84478 169035 84519 169036 84478 169036 84517 169036 84517 169037 84478 169037 84480 169037 84517 169038 84480 169038 84479 169038 84479 169039 84480 169039 84477 169039 84462 169040 84481 169040 84482 169040 84482 169041 84481 169041 84684 169041 84482 169042 84684 169042 84483 169042 84483 169043 84684 169043 84460 169043 84483 169044 84460 169044 84499 169044 84499 169045 84460 169045 84484 169045 84499 169046 84484 169046 84500 169046 84500 169047 84484 169047 84461 169047 84500 169048 84461 169048 84485 169048 84485 169049 84461 169049 83964 169049 84501 169050 84486 169050 84487 169050 84487 169051 84486 169051 84530 169051 84487 169052 84530 169052 84488 169052 84488 169053 84530 169053 84490 169053 84488 169054 84490 169054 84489 169054 84489 169055 84490 169055 84528 169055 84489 169056 84528 169056 84498 169056 84498 169057 84528 169057 84491 169057 84498 169058 84491 169058 84497 169058 84497 169059 84491 169059 84492 169059 84497 169060 84492 169060 84493 169060 84493 169061 84492 169061 84526 169061 84493 169062 84526 169062 84456 169062 84456 169063 84526 169063 84494 169063 84456 169064 84494 169064 84495 169064 84495 169065 84494 169065 84464 169065 84463 169066 84496 169066 84493 169066 84493 169067 84496 169067 84482 169067 84493 169068 84482 169068 84497 169068 84497 169069 84482 169069 84483 169069 84497 169070 84483 169070 84498 169070 84498 169071 84483 169071 84499 169071 84498 169072 84499 169072 84489 169072 84489 169073 84499 169073 84500 169073 84489 169074 84500 169074 84488 169074 84488 169075 84500 169075 84457 169075 84488 169076 84457 169076 84501 169076 84501 169077 84457 169077 84485 169077 84469 169078 84678 169078 84468 169078 84468 169079 84678 169079 84502 169079 84468 169080 84502 169080 84504 169080 84504 169081 84502 169081 84503 169081 84504 169082 84503 169082 84505 169082 84505 169083 84503 169083 84465 169083 84505 169084 84465 169084 84506 169084 84506 169085 84465 169085 84524 169085 84506 169086 84524 169086 84516 169086 84516 169087 84524 169087 84525 169087 84516 169088 84525 169088 84518 169088 84518 169089 84525 169089 84508 169089 84518 169090 84508 169090 84507 169090 84507 169091 84508 169091 84509 169091 84507 169092 84509 169092 84520 169092 84520 169093 84509 169093 84527 169093 84520 169094 84527 169094 84521 169094 84521 169095 84527 169095 84511 169095 84521 169096 84511 169096 84510 169096 84510 169097 84511 169097 84529 169097 84510 169098 84529 169098 84550 169098 84550 169099 84529 169099 84549 169099 84512 169100 84513 169100 84470 169100 84470 169101 84513 169101 84676 169101 84470 169102 84676 169102 84472 169102 84472 169103 84676 169103 84468 169103 84472 169104 84468 169104 84514 169104 84514 169105 84468 169105 84504 169105 84514 169106 84504 169106 84515 169106 84515 169107 84504 169107 84505 169107 84515 169108 84505 169108 84477 169108 84477 169109 84505 169109 84506 169109 84477 169110 84506 169110 84479 169110 84479 169111 84506 169111 84516 169111 84479 169112 84516 169112 84517 169112 84517 169113 84516 169113 84518 169113 84517 169114 84518 169114 84519 169114 84519 169115 84518 169115 84507 169115 84519 169116 84507 169116 84454 169116 84454 169117 84507 169117 84520 169117 84454 169118 84520 169118 84542 169118 84542 169119 84520 169119 84521 169119 84542 169120 84521 169120 84522 169120 84522 169121 84521 169121 84510 169121 84679 169122 84523 169122 84465 169122 84465 169123 84523 169123 84455 169123 84465 169124 84455 169124 84524 169124 84524 169125 84455 169125 84494 169125 84524 169126 84494 169126 84525 169126 84525 169127 84494 169127 84526 169127 84525 169128 84526 169128 84508 169128 84508 169129 84526 169129 84492 169129 84508 169130 84492 169130 84509 169130 84509 169131 84492 169131 84491 169131 84509 169132 84491 169132 84527 169132 84527 169133 84491 169133 84528 169133 84527 169134 84528 169134 84511 169134 84511 169135 84528 169135 84490 169135 84511 169136 84490 169136 84529 169136 84529 169137 84490 169137 84530 169137 84529 169138 84530 169138 84549 169138 84549 169139 84530 169139 87786 169139 84534 169140 84478 169140 84532 169140 84532 169141 84478 169141 84531 169141 84532 169142 84531 169142 84533 169142 84533 169143 84531 169143 84545 169143 84534 169144 84556 169144 84478 169144 84478 169145 84556 169145 84535 169145 84478 169146 84535 169146 84480 169146 84480 169147 84535 169147 84536 169147 84480 169148 84536 169148 84476 169148 84476 169149 84536 169149 84537 169149 84476 169150 84537 169150 84475 169150 84751 169151 84473 169151 84538 169151 84538 169152 84473 169152 84474 169152 84538 169153 84474 169153 84539 169153 84539 169154 84474 169154 84475 169154 84539 169155 84475 169155 84557 169155 84557 169156 84475 169156 84537 169156 84550 169157 84540 169157 84510 169157 84510 169158 84540 169158 84336 169158 84510 169159 84336 169159 84522 169159 84522 169160 84336 169160 84541 169160 84522 169161 84541 169161 84542 169161 84542 169162 84541 169162 84543 169162 84542 169163 84543 169163 84544 169163 84544 169164 84543 169164 84546 169164 84544 169165 84546 169165 84545 169165 84545 169166 84546 169166 84337 169166 84545 169167 84337 169167 84533 169167 84547 169168 84549 169168 87784 169168 87784 169169 84549 169169 87786 169169 84547 169170 84548 169170 84549 169170 84549 169171 84548 169171 87796 169171 84549 169172 87796 169172 87795 169172 87795 169173 84552 169173 84549 169173 84549 169174 84552 169174 84323 169174 84549 169175 84323 169175 84550 169175 84550 169176 84323 169176 84321 169176 84550 169177 84321 169177 84540 169177 87795 169178 87797 169178 84552 169178 84552 169179 87797 169179 87806 169179 84552 169180 87806 169180 84553 169180 87801 169181 84252 169181 84551 169181 84551 169182 84252 169182 84552 169182 84551 169183 84552 169183 87803 169183 87803 169184 84552 169184 84553 169184 84579 169185 84594 169185 84580 169185 84554 169186 84307 169186 84639 169186 84608 169187 84627 169187 84555 169187 84555 169188 84627 169188 84532 169188 84555 169189 84532 169189 84533 169189 84535 169190 84556 169190 84614 169190 84614 169191 84556 169191 84534 169191 84557 169192 84537 169192 84612 169192 84612 169193 84537 169193 84536 169193 84751 169194 84538 169194 84558 169194 84558 169195 84538 169195 84539 169195 84558 169196 84539 169196 84557 169196 84559 169197 84751 169197 84564 169197 84561 169198 84559 169198 84560 169198 84560 169199 84559 169199 84564 169199 84560 169200 84564 169200 85509 169200 84561 169201 85577 169201 84559 169201 84559 169202 85577 169202 85578 169202 84559 169203 85578 169203 84562 169203 84562 169204 85578 169204 85572 169204 84562 169205 85572 169205 84748 169205 85574 169206 85094 169206 85573 169206 85573 169207 85094 169207 84750 169207 85573 169208 84750 169208 92528 169208 92528 169209 84750 169209 84749 169209 92528 169210 84749 169210 85572 169210 85572 169211 84749 169211 84563 169211 85572 169212 84563 169212 84748 169212 84751 169213 84558 169213 84564 169213 84564 169214 84558 169214 85507 169214 84564 169215 85507 169215 85509 169215 92394 169216 84565 169216 85503 169216 85503 169217 84565 169217 84616 169217 92394 169218 85505 169218 84565 169218 84565 169219 85505 169219 84566 169219 84565 169220 84566 169220 84558 169220 84558 169221 84566 169221 85506 169221 84558 169222 85506 169222 85507 169222 84567 169223 84568 169223 84622 169223 84622 169224 84568 169224 85514 169224 84622 169225 85514 169225 84646 169225 84646 169226 85514 169226 85515 169226 84646 169227 85515 169227 92453 169227 85512 169228 92450 169228 84569 169228 84569 169229 92450 169229 85511 169229 84569 169230 85511 169230 84570 169230 84309 169231 84640 169231 84310 169231 84310 169232 84640 169232 84571 169232 84310 169233 84571 169233 84632 169233 84632 169234 84571 169234 84634 169234 84554 169235 84639 169235 84309 169235 84639 169236 84600 169236 84641 169236 84641 169237 84600 169237 84601 169237 84641 169238 84601 169238 84572 169238 84572 169239 84601 169239 84602 169239 84572 169240 84602 169240 84573 169240 84573 169241 84602 169241 84575 169241 84573 169242 84575 169242 84574 169242 84574 169243 84575 169243 84576 169243 84574 169244 84576 169244 84577 169244 84577 169245 84576 169245 85527 169245 84578 169246 84579 169246 84599 169246 84599 169247 84579 169247 84580 169247 84599 169248 84580 169248 84581 169248 84581 169249 84580 169249 84596 169249 84581 169250 84596 169250 84582 169250 84582 169251 84596 169251 84583 169251 84582 169252 84583 169252 84584 169252 84584 169253 84583 169253 84586 169253 84584 169254 84586 169254 84585 169254 84585 169255 84586 169255 84598 169255 84585 169256 84598 169256 84587 169256 84587 169257 84598 169257 84607 169257 84587 169258 84607 169258 85525 169258 84595 169259 84589 169259 84588 169259 84588 169260 84589 169260 84603 169260 84588 169261 84603 169261 84597 169261 84597 169262 84603 169262 84591 169262 84597 169263 84591 169263 84590 169263 84590 169264 84591 169264 84592 169264 84590 169265 84592 169265 84593 169265 84593 169266 84592 169266 84604 169266 84593 169267 84604 169267 84606 169267 84594 169268 84595 169268 84580 169268 84580 169269 84595 169269 84588 169269 84580 169270 84588 169270 84596 169270 84596 169271 84588 169271 84597 169271 84596 169272 84597 169272 84583 169272 84583 169273 84597 169273 84590 169273 84583 169274 84590 169274 84586 169274 84586 169275 84590 169275 84593 169275 84586 169276 84593 169276 84598 169276 84598 169277 84593 169277 84606 169277 84598 169278 84606 169278 84607 169278 84307 169279 84578 169279 84639 169279 84639 169280 84578 169280 84599 169280 84639 169281 84599 169281 84600 169281 84600 169282 84599 169282 84581 169282 84600 169283 84581 169283 84601 169283 84601 169284 84581 169284 84582 169284 84601 169285 84582 169285 84602 169285 84602 169286 84582 169286 84584 169286 84602 169287 84584 169287 84575 169287 84575 169288 84584 169288 84585 169288 84575 169289 84585 169289 84576 169289 84576 169290 84585 169290 84587 169290 84576 169291 84587 169291 85527 169291 85527 169292 84587 169292 85525 169292 84589 169293 84303 169293 84603 169293 84603 169294 84303 169294 84395 169294 84603 169295 84395 169295 84591 169295 84591 169296 84395 169296 84420 169296 84591 169297 84420 169297 84592 169297 84592 169298 84420 169298 84401 169298 84592 169299 84401 169299 84604 169299 84604 169300 84401 169300 84605 169300 84604 169301 84605 169301 84606 169301 84606 169302 84605 169302 84362 169302 84606 169303 84362 169303 84607 169303 84607 169304 84362 169304 92474 169304 84607 169305 92474 169305 85525 169305 84555 169306 84325 169306 84608 169306 84608 169307 84325 169307 84609 169307 84608 169308 84609 169308 84626 169308 84626 169309 84609 169309 84328 169309 84328 169310 84327 169310 84626 169310 84626 169311 84327 169311 84610 169311 84626 169312 84610 169312 84625 169312 84647 169313 84648 169313 84624 169313 84624 169314 84648 169314 84649 169314 84624 169315 84649 169315 84611 169315 84611 169316 84649 169316 84615 169316 84611 169317 84615 169317 84613 169317 84613 169318 84615 169318 84612 169318 84613 169319 84612 169319 84614 169319 84614 169320 84612 169320 84536 169320 84614 169321 84536 169321 84535 169321 84557 169322 84612 169322 84558 169322 84558 169323 84612 169323 84615 169323 84558 169324 84615 169324 84565 169324 84565 169325 84615 169325 84649 169325 84565 169326 84649 169326 84616 169326 84616 169327 84649 169327 92445 169327 84616 169328 92445 169328 85503 169328 84610 169329 84617 169329 84625 169329 84625 169330 84617 169330 84329 169330 84625 169331 84329 169331 84623 169331 84623 169332 84329 169332 84618 169332 84619 169333 84620 169333 84629 169333 84629 169334 84620 169334 84628 169334 85511 169335 85517 169335 84570 169335 84570 169336 85517 169336 84567 169336 84570 169337 84567 169337 84621 169337 84621 169338 84567 169338 84622 169338 84621 169339 84622 169339 84645 169339 84645 169340 84622 169340 84646 169340 84635 169341 84647 169341 84623 169341 84623 169342 84647 169342 84624 169342 84623 169343 84624 169343 84625 169343 84625 169344 84624 169344 84611 169344 84625 169345 84611 169345 84626 169345 84626 169346 84611 169346 84613 169346 84626 169347 84613 169347 84608 169347 84608 169348 84613 169348 84614 169348 84608 169349 84614 169349 84627 169349 84627 169350 84614 169350 84534 169350 84627 169351 84534 169351 84532 169351 84628 169352 84331 169352 84629 169352 84629 169353 84331 169353 84630 169353 84629 169354 84630 169354 84634 169354 84634 169355 84630 169355 84631 169355 84634 169356 84631 169356 84632 169356 84640 169357 84633 169357 84571 169357 84571 169358 84633 169358 84642 169358 84571 169359 84642 169359 84634 169359 84634 169360 84642 169360 84635 169360 84634 169361 84635 169361 84629 169361 84629 169362 84635 169362 84623 169362 84629 169363 84623 169363 84619 169363 84619 169364 84623 169364 84618 169364 84619 169365 84618 169365 84620 169365 84645 169366 84636 169366 84621 169366 84621 169367 84636 169367 84637 169367 84621 169368 84637 169368 84570 169368 84570 169369 84637 169369 84638 169369 84570 169370 84638 169370 84569 169370 84569 169371 84638 169371 84644 169371 84569 169372 84644 169372 85512 169372 84309 169373 84639 169373 84640 169373 84640 169374 84639 169374 84641 169374 84640 169375 84641 169375 84633 169375 84633 169376 84641 169376 84572 169376 84633 169377 84572 169377 84642 169377 84642 169378 84572 169378 84643 169378 84642 169379 84643 169379 84635 169379 84577 169380 85512 169380 84574 169380 84574 169381 85512 169381 84644 169381 84574 169382 84644 169382 84573 169382 84573 169383 84644 169383 84638 169383 84573 169384 84638 169384 84572 169384 84572 169385 84638 169385 84637 169385 84572 169386 84637 169386 84643 169386 84643 169387 84637 169387 84636 169387 84643 169388 84636 169388 84635 169388 84635 169389 84636 169389 84645 169389 84635 169390 84645 169390 84647 169390 84647 169391 84645 169391 84646 169391 84647 169392 84646 169392 84648 169392 84648 169393 84646 169393 92453 169393 84648 169394 92453 169394 84649 169394 84649 169395 92453 169395 85502 169395 84649 169396 85502 169396 92445 169396 84654 169397 84836 169397 84656 169397 84783 169398 84650 169398 83930 169398 84651 169399 84652 169399 84672 169399 84672 169400 84652 169400 84655 169400 84672 169401 84655 169401 84670 169401 84670 169402 84655 169402 84653 169402 84670 169403 84653 169403 84658 169403 84651 169404 84654 169404 84652 169404 84652 169405 84654 169405 84656 169405 84652 169406 84656 169406 84655 169406 84655 169407 84656 169407 84657 169407 84655 169408 84657 169408 84653 169408 84653 169409 84657 169409 84659 169409 83940 169410 84658 169410 83941 169410 83941 169411 84658 169411 84653 169411 83941 169412 84653 169412 83930 169412 83930 169413 84653 169413 84659 169413 83930 169414 84659 169414 84783 169414 84783 169415 84659 169415 84657 169415 84783 169416 84657 169416 84781 169416 84781 169417 84657 169417 84656 169417 84781 169418 84656 169418 84780 169418 84780 169419 84656 169419 84836 169419 84780 169420 84836 169420 84660 169420 84830 169421 84829 169421 84668 169421 84664 169422 84661 169422 84663 169422 84661 169423 84664 169423 84662 169423 84663 169424 84731 169424 84664 169424 84664 169425 84731 169425 84665 169425 84664 169426 84665 169426 84666 169426 84666 169427 84665 169427 84697 169427 84666 169428 84697 169428 84667 169428 84667 169429 84697 169429 84839 169429 84839 169430 84830 169430 84667 169430 84667 169431 84830 169431 84668 169431 84667 169432 84668 169432 84666 169432 84666 169433 84668 169433 84671 169433 84666 169434 84671 169434 84664 169434 84664 169435 84671 169435 84669 169435 84664 169436 84669 169436 84662 169436 84662 169437 84669 169437 83940 169437 83940 169438 84669 169438 84658 169438 84658 169439 84669 169439 84671 169439 84658 169440 84671 169440 84670 169440 84670 169441 84671 169441 84668 169441 84670 169442 84668 169442 84672 169442 84672 169443 84668 169443 84829 169443 84672 169444 84829 169444 84651 169444 84702 169445 84673 169445 84701 169445 84467 169446 84466 169446 84677 169446 84871 169447 84873 169447 84471 169447 84471 169448 84873 169448 84674 169448 84471 169449 84674 169449 84512 169449 84512 169450 84674 169450 84513 169450 84718 169451 84675 169451 84676 169451 84676 169452 84675 169452 84469 169452 84677 169453 84466 169453 84675 169453 84675 169454 84466 169454 84678 169454 84675 169455 84678 169455 84469 169455 84467 169456 84677 169456 84679 169456 84679 169457 84677 169457 84680 169457 84679 169458 84680 169458 84523 169458 84523 169459 84680 169459 84464 169459 84464 169460 84680 169460 84681 169460 84464 169461 84681 169461 84495 169461 84495 169462 84681 169462 84463 169462 84463 169463 84681 169463 84682 169463 84463 169464 84682 169464 84496 169464 84496 169465 84682 169465 84683 169465 84496 169466 84683 169466 84462 169466 84685 169467 84460 169467 84728 169467 84728 169468 84460 169468 84684 169468 84728 169469 84684 169469 84683 169469 84683 169470 84684 169470 84481 169470 84683 169471 84481 169471 84462 169471 84728 169472 84730 169472 84685 169472 84685 169473 84730 169473 84731 169473 84685 169474 84731 169474 84663 169474 84686 169475 84687 169475 84688 169475 84688 169476 84687 169476 84828 169476 84688 169477 84828 169477 84693 169477 84873 169478 84689 169478 84674 169478 84674 169479 84689 169479 84690 169479 84674 169480 84690 169480 84717 169480 84717 169481 84690 169481 84720 169481 84691 169482 84686 169482 84734 169482 84734 169483 84686 169483 84688 169483 84734 169484 84688 169484 84692 169484 84692 169485 84688 169485 84693 169485 84692 169486 84693 169486 84842 169486 84745 169487 84694 169487 84713 169487 84713 169488 84694 169488 84742 169488 84713 169489 84742 169489 84715 169489 84715 169490 84742 169490 84741 169490 84715 169491 84741 169491 84740 169491 84744 169492 84712 169492 84726 169492 84726 169493 84712 169493 84695 169493 84726 169494 84695 169494 84727 169494 84727 169495 84695 169495 84709 169495 84727 169496 84709 169496 84729 169496 84729 169497 84709 169497 84699 169497 84729 169498 84699 169498 84732 169498 84732 169499 84699 169499 84696 169499 84732 169500 84696 169500 84665 169500 84665 169501 84696 169501 84697 169501 84838 169502 84837 169502 84709 169502 84709 169503 84837 169503 84698 169503 84709 169504 84698 169504 84699 169504 84699 169505 84698 169505 84840 169505 84699 169506 84840 169506 84696 169506 84696 169507 84840 169507 84700 169507 84696 169508 84700 169508 84697 169508 84697 169509 84700 169509 84839 169509 84710 169510 84711 169510 84746 169510 84710 169511 84746 169511 84701 169511 84701 169512 84746 169512 84841 169512 84701 169513 84841 169513 84702 169513 84738 169514 84878 169514 84716 169514 84716 169515 84878 169515 84733 169515 84716 169516 84733 169516 84703 169516 84703 169517 84733 169517 84704 169517 84703 169518 84704 169518 84705 169518 84705 169519 84704 169519 84706 169519 84705 169520 84706 169520 84714 169520 84714 169521 84706 169521 84707 169521 84714 169522 84707 169522 84708 169522 84708 169523 84707 169523 84736 169523 84673 169524 84838 169524 84701 169524 84701 169525 84838 169525 84709 169525 84701 169526 84709 169526 84710 169526 84710 169527 84709 169527 84695 169527 84710 169528 84695 169528 84711 169528 84711 169529 84695 169529 84712 169529 84708 169530 84745 169530 84714 169530 84714 169531 84745 169531 84713 169531 84714 169532 84713 169532 84705 169532 84705 169533 84713 169533 84715 169533 84705 169534 84715 169534 84703 169534 84703 169535 84715 169535 84740 169535 84703 169536 84740 169536 84716 169536 84513 169537 84674 169537 84676 169537 84676 169538 84674 169538 84717 169538 84676 169539 84717 169539 84718 169539 84718 169540 84717 169540 84720 169540 84718 169541 84720 169541 84675 169541 84675 169542 84720 169542 84723 169542 84675 169543 84723 169543 84677 169543 84677 169544 84723 169544 84724 169544 84677 169545 84724 169545 84680 169545 84680 169546 84724 169546 84719 169546 84680 169547 84719 169547 84681 169547 84689 169548 84737 169548 84690 169548 84690 169549 84737 169549 84739 169549 84690 169550 84739 169550 84720 169550 84720 169551 84739 169551 84721 169551 84720 169552 84721 169552 84723 169552 84723 169553 84721 169553 84722 169553 84723 169554 84722 169554 84724 169554 84724 169555 84722 169555 84725 169555 84724 169556 84725 169556 84719 169556 84719 169557 84725 169557 84743 169557 84719 169558 84743 169558 84681 169558 84681 169559 84743 169559 84744 169559 84681 169560 84744 169560 84682 169560 84682 169561 84744 169561 84726 169561 84682 169562 84726 169562 84683 169562 84683 169563 84726 169563 84727 169563 84683 169564 84727 169564 84728 169564 84728 169565 84727 169565 84729 169565 84728 169566 84729 169566 84730 169566 84730 169567 84729 169567 84732 169567 84730 169568 84732 169568 84731 169568 84731 169569 84732 169569 84665 169569 84878 169570 84691 169570 84733 169570 84733 169571 84691 169571 84734 169571 84733 169572 84734 169572 84704 169572 84704 169573 84734 169573 84692 169573 84704 169574 84692 169574 84706 169574 84706 169575 84692 169575 84842 169575 84706 169576 84842 169576 84707 169576 84707 169577 84842 169577 84735 169577 84707 169578 84735 169578 84736 169578 84737 169579 84738 169579 84739 169579 84739 169580 84738 169580 84716 169580 84739 169581 84716 169581 84721 169581 84721 169582 84716 169582 84740 169582 84721 169583 84740 169583 84722 169583 84722 169584 84740 169584 84741 169584 84722 169585 84741 169585 84725 169585 84725 169586 84741 169586 84742 169586 84725 169587 84742 169587 84743 169587 84743 169588 84742 169588 84694 169588 84743 169589 84694 169589 84744 169589 84744 169590 84694 169590 84745 169590 84744 169591 84745 169591 84712 169591 84712 169592 84745 169592 84708 169592 84712 169593 84708 169593 84711 169593 84711 169594 84708 169594 84736 169594 84711 169595 84736 169595 84746 169595 84746 169596 84736 169596 84735 169596 84746 169597 84735 169597 84841 169597 85102 169598 84872 169598 84747 169598 84747 169599 84872 169599 85100 169599 84562 169600 84748 169600 84871 169600 84871 169601 84748 169601 84563 169601 84563 169602 84749 169602 84871 169602 84871 169603 84749 169603 84750 169603 84871 169604 84750 169604 85094 169604 84562 169605 84871 169605 84559 169605 84559 169606 84871 169606 84473 169606 84559 169607 84473 169607 84751 169607 85094 169608 85095 169608 84871 169608 84871 169609 85095 169609 85097 169609 84871 169610 85097 169610 84872 169610 84872 169611 85097 169611 84752 169611 84872 169612 84752 169612 85100 169612 84753 169613 84762 169613 84798 169613 84754 169614 84864 169614 84865 169614 84754 169615 84865 169615 84818 169615 84780 169616 84660 169616 84790 169616 84008 169617 84006 169617 84782 169617 84782 169618 84006 169618 84755 169618 84787 169619 84756 169619 84008 169619 84786 169620 84757 169620 84001 169620 84757 169621 84786 169621 84758 169621 84759 169622 84866 169622 84867 169622 84793 169623 84866 169623 84794 169623 84794 169624 84866 169624 84759 169624 84794 169625 84759 169625 84760 169625 84760 169626 84759 169626 84761 169626 84760 169627 84761 169627 84796 169627 84796 169628 84761 169628 84824 169628 84796 169629 84824 169629 84823 169629 84815 169630 84762 169630 84774 169630 84774 169631 84762 169631 84753 169631 84774 169632 84753 169632 84763 169632 84763 169633 84753 169633 84801 169633 84763 169634 84801 169634 84776 169634 84856 169635 83996 169635 84765 169635 84765 169636 83996 169636 84764 169636 84765 169637 84764 169637 84766 169637 84766 169638 84764 169638 84767 169638 84766 169639 84767 169639 84804 169639 84804 169640 84767 169640 84768 169640 84804 169641 84768 169641 84803 169641 84803 169642 84768 169642 84811 169642 84803 169643 84811 169643 84770 169643 84770 169644 84811 169644 84769 169644 84770 169645 84769 169645 84775 169645 84775 169646 84769 169646 84812 169646 84775 169647 84812 169647 84773 169647 84773 169648 84812 169648 84813 169648 84773 169649 84813 169649 84771 169649 84771 169650 84813 169650 84772 169650 84771 169651 84815 169651 84773 169651 84773 169652 84815 169652 84774 169652 84773 169653 84774 169653 84775 169653 84775 169654 84774 169654 84763 169654 84775 169655 84763 169655 84770 169655 84770 169656 84763 169656 84776 169656 84770 169657 84776 169657 84803 169657 84791 169658 84777 169658 84778 169658 84790 169659 84779 169659 84780 169659 84780 169660 84779 169660 84788 169660 84780 169661 84788 169661 84781 169661 84781 169662 84788 169662 84782 169662 84781 169663 84782 169663 84783 169663 84783 169664 84782 169664 84755 169664 84783 169665 84755 169665 84650 169665 84791 169666 84778 169666 84784 169666 84784 169667 84778 169667 84785 169667 84784 169668 84785 169668 84789 169668 84789 169669 84785 169669 84786 169669 84789 169670 84786 169670 84787 169670 84787 169671 84786 169671 84001 169671 84787 169672 84001 169672 84756 169672 84008 169673 84782 169673 84787 169673 84787 169674 84782 169674 84788 169674 84787 169675 84788 169675 84789 169675 84789 169676 84788 169676 84779 169676 84789 169677 84779 169677 84784 169677 84784 169678 84779 169678 84790 169678 84784 169679 84790 169679 84791 169679 84798 169680 84852 169680 84799 169680 84799 169681 84852 169681 84851 169681 84799 169682 84851 169682 84821 169682 84792 169683 84793 169683 84805 169683 84805 169684 84793 169684 84794 169684 84805 169685 84794 169685 84806 169685 84806 169686 84794 169686 84760 169686 84806 169687 84760 169687 84795 169687 84795 169688 84760 169688 84796 169688 84795 169689 84796 169689 84797 169689 84797 169690 84796 169690 84823 169690 84797 169691 84823 169691 84822 169691 84798 169692 84799 169692 84753 169692 84753 169693 84799 169693 84800 169693 84753 169694 84800 169694 84801 169694 84801 169695 84800 169695 84802 169695 84801 169696 84802 169696 84776 169696 84776 169697 84802 169697 84825 169697 84776 169698 84825 169698 84803 169698 84803 169699 84825 169699 84826 169699 84803 169700 84826 169700 84804 169700 84804 169701 84826 169701 84827 169701 84804 169702 84827 169702 84766 169702 84766 169703 84827 169703 84870 169703 84766 169704 84870 169704 84765 169704 84865 169705 84792 169705 84816 169705 84816 169706 84792 169706 84805 169706 84816 169707 84805 169707 84817 169707 84817 169708 84805 169708 84806 169708 84817 169709 84806 169709 84820 169709 84820 169710 84806 169710 84795 169710 84820 169711 84795 169711 84807 169711 84807 169712 84795 169712 84797 169712 84807 169713 84797 169713 84808 169713 84808 169714 84797 169714 84822 169714 83996 169715 83997 169715 84764 169715 84764 169716 83997 169716 84809 169716 84764 169717 84809 169717 84767 169717 84767 169718 84809 169718 84037 169718 84767 169719 84037 169719 84768 169719 84768 169720 84037 169720 84810 169720 84768 169721 84810 169721 84811 169721 84811 169722 84810 169722 84000 169722 84811 169723 84000 169723 84769 169723 84769 169724 84000 169724 83999 169724 84769 169725 83999 169725 84812 169725 84812 169726 83999 169726 84045 169726 84812 169727 84045 169727 84813 169727 84813 169728 84045 169728 84814 169728 84813 169729 84814 169729 84772 169729 84772 169730 84814 169730 84758 169730 84772 169731 84758 169731 84771 169731 84771 169732 84758 169732 84786 169732 84771 169733 84786 169733 84815 169733 84815 169734 84786 169734 84785 169734 84815 169735 84785 169735 84762 169735 84762 169736 84785 169736 84778 169736 84762 169737 84778 169737 84798 169737 84798 169738 84778 169738 84777 169738 84798 169739 84777 169739 84852 169739 84865 169740 84816 169740 84818 169740 84818 169741 84816 169741 84817 169741 84818 169742 84817 169742 84819 169742 84819 169743 84817 169743 84820 169743 84819 169744 84820 169744 84850 169744 84850 169745 84820 169745 84807 169745 84850 169746 84807 169746 84821 169746 84821 169747 84807 169747 84808 169747 84821 169748 84808 169748 84799 169748 84799 169749 84808 169749 84822 169749 84799 169750 84822 169750 84800 169750 84800 169751 84822 169751 84823 169751 84800 169752 84823 169752 84802 169752 84802 169753 84823 169753 84824 169753 84802 169754 84824 169754 84825 169754 84825 169755 84824 169755 84761 169755 84825 169756 84761 169756 84826 169756 84826 169757 84761 169757 84759 169757 84826 169758 84759 169758 84827 169758 84827 169759 84759 169759 84867 169759 84827 169760 84867 169760 84870 169760 84654 169761 84651 169761 84754 169761 84754 169762 84651 169762 84864 169762 84864 169763 84651 169763 85250 169763 84864 169764 85250 169764 85258 169764 84828 169765 84829 169765 84830 169765 84828 169766 84830 169766 84693 169766 84693 169767 84830 169767 84839 169767 84693 169768 84839 169768 84842 169768 84829 169769 84828 169769 84651 169769 84651 169770 84828 169770 84687 169770 84651 169771 84687 169771 85250 169771 85250 169772 84687 169772 85259 169772 85250 169773 85259 169773 84844 169773 84844 169774 85259 169774 84831 169774 84844 169775 84831 169775 84832 169775 84832 169776 85260 169776 84844 169776 84844 169777 85260 169777 85263 169777 84844 169778 85263 169778 85329 169778 84833 169779 84834 169779 85469 169779 85469 169780 84834 169780 85443 169780 85469 169781 85443 169781 85258 169781 85258 169782 85443 169782 84835 169782 85258 169783 84835 169783 84864 169783 85329 169784 85328 169784 84844 169784 84844 169785 85328 169785 85310 169785 84844 169786 85310 169786 85309 169786 84654 169787 84754 169787 84836 169787 84836 169788 84754 169788 84818 169788 84836 169789 84818 169789 84660 169789 84660 169790 84818 169790 84819 169790 84660 169791 84819 169791 84850 169791 84837 169792 84838 169792 84839 169792 84839 169793 84838 169793 84673 169793 84839 169794 84673 169794 84702 169794 84837 169795 84839 169795 84698 169795 84698 169796 84839 169796 84700 169796 84698 169797 84700 169797 84840 169797 85446 169798 85375 169798 85469 169798 85469 169799 85375 169799 85445 169799 85469 169800 85445 169800 84833 169800 84702 169801 84841 169801 84839 169801 84839 169802 84841 169802 84735 169802 84839 169803 84735 169803 84842 169803 85309 169804 84843 169804 84844 169804 84844 169805 84843 169805 85307 169805 84844 169806 85307 169806 84845 169806 84845 169807 85307 169807 85306 169807 85452 169808 85451 169808 84846 169808 84846 169809 84847 169809 85452 169809 85452 169810 84847 169810 84848 169810 85452 169811 84848 169811 85468 169811 85468 169812 84848 169812 85447 169812 85468 169813 85447 169813 85469 169813 85469 169814 85447 169814 84849 169814 85469 169815 84849 169815 85446 169815 84850 169816 84821 169816 84660 169816 84660 169817 84821 169817 84851 169817 84660 169818 84851 169818 84790 169818 84790 169819 84851 169819 84852 169819 84790 169820 84852 169820 84791 169820 84791 169821 84852 169821 84777 169821 85006 169822 84853 169822 84855 169822 84855 169823 84853 169823 84854 169823 84855 169824 84854 169824 84856 169824 84856 169825 84854 169825 85003 169825 84856 169826 85003 169826 84352 169826 84352 169827 84857 169827 84856 169827 84856 169828 84857 169828 84858 169828 84856 169829 84858 169829 84355 169829 84376 169830 83995 169830 84859 169830 84859 169831 83995 169831 84856 169831 84859 169832 84856 169832 84860 169832 84860 169833 84856 169833 84355 169833 84861 169834 84862 169834 84855 169834 84855 169835 84862 169835 84863 169835 84855 169836 84863 169836 85006 169836 84864 169837 84835 169837 85442 169837 84864 169838 85442 169838 84865 169838 84865 169839 85442 169839 85440 169839 84865 169840 85440 169840 84792 169840 84792 169841 85440 169841 85438 169841 84792 169842 85438 169842 84793 169842 84793 169843 85438 169843 85453 169843 84793 169844 85453 169844 84866 169844 84866 169845 85453 169845 85413 169845 84866 169846 85413 169846 84867 169846 84867 169847 85413 169847 84868 169847 84867 169848 84868 169848 84870 169848 84870 169849 84868 169849 84869 169849 84870 169850 84869 169850 84765 169850 84765 169851 84869 169851 84855 169851 84765 169852 84855 169852 84856 169852 84873 169853 84871 169853 84872 169853 84872 169854 85330 169854 84873 169854 84873 169855 85330 169855 84874 169855 84873 169856 84874 169856 84689 169856 84689 169857 84874 169857 84875 169857 84689 169858 84875 169858 84737 169858 84737 169859 84875 169859 84876 169859 84737 169860 84876 169860 84738 169860 84738 169861 84876 169861 84877 169861 84738 169862 84877 169862 84878 169862 84878 169863 84877 169863 84879 169863 84878 169864 84879 169864 84691 169864 84691 169865 84879 169865 84880 169865 84691 169866 84880 169866 84686 169866 84686 169867 84880 169867 85259 169867 84686 169868 85259 169868 84687 169868 84912 169869 84917 169869 84926 169869 85204 169870 84881 169870 84935 169870 84882 169871 84883 169871 84885 169871 84883 169872 84882 169872 85036 169872 85036 169873 84882 169873 85476 169873 85036 169874 85476 169874 84951 169874 84884 169875 84886 169875 84885 169875 84885 169876 84886 169876 84887 169876 84885 169877 84887 169877 84882 169877 84892 169878 84888 169878 84884 169878 84884 169879 84888 169879 85485 169879 84884 169880 85485 169880 84886 169880 84889 169881 84890 169881 84892 169881 84892 169882 84890 169882 84891 169882 84892 169883 84891 169883 84888 169883 84920 169884 85470 169884 84893 169884 84893 169885 85470 169885 85474 169885 84893 169886 85474 169886 84894 169886 84894 169887 85474 169887 85473 169887 84894 169888 85473 169888 84896 169888 84896 169889 85473 169889 84895 169889 84896 169890 84895 169890 84897 169890 84897 169891 84895 169891 85480 169891 84897 169892 85480 169892 84889 169892 84889 169893 85480 169893 85479 169893 84889 169894 85479 169894 84890 169894 85472 169895 84928 169895 84898 169895 84898 169896 84928 169896 84899 169896 84898 169897 84899 169897 84938 169897 84938 169898 84899 169898 84931 169898 84938 169899 84931 169899 84902 169899 84903 169900 85090 169900 84932 169900 84932 169901 85090 169901 84900 169901 84932 169902 84900 169902 84931 169902 84931 169903 84900 169903 84901 169903 84931 169904 84901 169904 84902 169904 84932 169905 84933 169905 84903 169905 84903 169906 84933 169906 84905 169906 84903 169907 84905 169907 84904 169907 84881 169908 85204 169908 84905 169908 84905 169909 85204 169909 85203 169909 84905 169910 85203 169910 84904 169910 84906 169911 84907 169911 84908 169911 84908 169912 84907 169912 84909 169912 84908 169913 84909 169913 84910 169913 84910 169914 84909 169914 84918 169914 84910 169915 84918 169915 84911 169915 84912 169916 84926 169916 84914 169916 84926 169917 84925 169917 84914 169917 84914 169918 84925 169918 84913 169918 84914 169919 84913 169919 85017 169919 85017 169920 84913 169920 84921 169920 85017 169921 84921 169921 84916 169921 84920 169922 84893 169922 84921 169922 84921 169923 84893 169923 84915 169923 84921 169924 84915 169924 84916 169924 84934 169925 84926 169925 84918 169925 84918 169926 84926 169926 84917 169926 84918 169927 84917 169927 84911 169927 84934 169928 84918 169928 84937 169928 84937 169929 84918 169929 84909 169929 84937 169930 84909 169930 84919 169930 84919 169931 84909 169931 84907 169931 84919 169932 84907 169932 85206 169932 85206 169933 84907 169933 84906 169933 85206 169934 84906 169934 85208 169934 85471 169935 85470 169935 84929 169935 84929 169936 85470 169936 84920 169936 84929 169937 84920 169937 84930 169937 84930 169938 84920 169938 84921 169938 84930 169939 84921 169939 84922 169939 84922 169940 84921 169940 84913 169940 84922 169941 84913 169941 84923 169941 84923 169942 84913 169942 84925 169942 84923 169943 84925 169943 84924 169943 84924 169944 84925 169944 84926 169944 84924 169945 84926 169945 84927 169945 84927 169946 84926 169946 84934 169946 85472 169947 85471 169947 84928 169947 84928 169948 85471 169948 84929 169948 84928 169949 84929 169949 84899 169949 84899 169950 84929 169950 84930 169950 84899 169951 84930 169951 84931 169951 84931 169952 84930 169952 84922 169952 84931 169953 84922 169953 84932 169953 84932 169954 84922 169954 84923 169954 84932 169955 84923 169955 84933 169955 84933 169956 84923 169956 84924 169956 84933 169957 84924 169957 84905 169957 84905 169958 84924 169958 84927 169958 84905 169959 84927 169959 84881 169959 84881 169960 84927 169960 84934 169960 84881 169961 84934 169961 84935 169961 84935 169962 84934 169962 84937 169962 84935 169963 84937 169963 84936 169963 84936 169964 84937 169964 84919 169964 84898 169965 84938 169965 84939 169965 84939 169966 84938 169966 84902 169966 84939 169967 84902 169967 85500 169967 85500 169968 84902 169968 84940 169968 85500 169969 84940 169969 85220 169969 84958 169970 84959 169970 84970 169970 84956 169971 84971 169971 84973 169971 85477 169972 85153 169972 84941 169972 84941 169973 85153 169973 85156 169973 84941 169974 85156 169974 84942 169974 84942 169975 85156 169975 84943 169975 84943 169976 85156 169976 85158 169976 84943 169977 85158 169977 84944 169977 85486 169978 84945 169978 84946 169978 84946 169979 84945 169979 84947 169979 84946 169980 84947 169980 85158 169980 85158 169981 84947 169981 84948 169981 85158 169982 84948 169982 84944 169982 84946 169983 84949 169983 85486 169983 85486 169984 84949 169984 84950 169984 85486 169985 84950 169985 85487 169985 85487 169986 84950 169986 85036 169986 85487 169987 85036 169987 84951 169987 84952 169988 85162 169988 84975 169988 84975 169989 85162 169989 85118 169989 84975 169990 85118 169990 84953 169990 84953 169991 85118 169991 84954 169991 84953 169992 84954 169992 84973 169992 84973 169993 84954 169993 84955 169993 84973 169994 84955 169994 84956 169994 84956 169995 84955 169995 85151 169995 84956 169996 85151 169996 85477 169996 85477 169997 85151 169997 85152 169997 85477 169998 85152 169998 85153 169998 85126 169999 85125 169999 84978 169999 84978 170000 85125 170000 85164 170000 84978 170001 85164 170001 84952 170001 84952 170002 85164 170002 84957 170002 84952 170003 84957 170003 85162 170003 84969 170004 85129 170004 84958 170004 84958 170005 85129 170005 85128 170005 84958 170006 85128 170006 84959 170006 84959 170007 85128 170007 84960 170007 84959 170008 84960 170008 85126 170008 85237 170009 84962 170009 84961 170009 84961 170010 84962 170010 84985 170010 84982 170011 85234 170011 84963 170011 84963 170012 85234 170012 84986 170012 84963 170013 84986 170013 84984 170013 84981 170014 85240 170014 84982 170014 84982 170015 85240 170015 85239 170015 84982 170016 85239 170016 85234 170016 85488 170017 84988 170017 84980 170017 84980 170018 84988 170018 84964 170018 84980 170019 84964 170019 84965 170019 84965 170020 84964 170020 84990 170020 84965 170021 84990 170021 84966 170021 84966 170022 84990 170022 85201 170022 84966 170023 85201 170023 84981 170023 84981 170024 85201 170024 85200 170024 84981 170025 85200 170025 85240 170025 85126 170026 84978 170026 84959 170026 84959 170027 84978 170027 84967 170027 84959 170028 84967 170028 84970 170028 85130 170029 85129 170029 84968 170029 84968 170030 85129 170030 84969 170030 84968 170031 84969 170031 85237 170031 85237 170032 84969 170032 84958 170032 85237 170033 84958 170033 84962 170033 84962 170034 84958 170034 84970 170034 84962 170035 84970 170035 84985 170035 84971 170036 84972 170036 84973 170036 84973 170037 84972 170037 84979 170037 84973 170038 84979 170038 84953 170038 84953 170039 84979 170039 84974 170039 84953 170040 84974 170040 84975 170040 84975 170041 84974 170041 84976 170041 84975 170042 84976 170042 84952 170042 84952 170043 84976 170043 84977 170043 84952 170044 84977 170044 84978 170044 84978 170045 84977 170045 84983 170045 84978 170046 84983 170046 84967 170046 84972 170047 85488 170047 84979 170047 84979 170048 85488 170048 84980 170048 84979 170049 84980 170049 84974 170049 84974 170050 84980 170050 84965 170050 84974 170051 84965 170051 84976 170051 84976 170052 84965 170052 84966 170052 84976 170053 84966 170053 84977 170053 84977 170054 84966 170054 84981 170054 84977 170055 84981 170055 84983 170055 84983 170056 84981 170056 84982 170056 84983 170057 84982 170057 84967 170057 84967 170058 84982 170058 84963 170058 84967 170059 84963 170059 84970 170059 84970 170060 84963 170060 84984 170060 84970 170061 84984 170061 84985 170061 84985 170062 84984 170062 84986 170062 85489 170063 84991 170063 84987 170063 84964 170064 84988 170064 84989 170064 85489 170065 84987 170065 84989 170065 84989 170066 84987 170066 84990 170066 84989 170067 84990 170067 84964 170067 84987 170068 84991 170068 85242 170068 85242 170069 84991 170069 85491 170069 85491 170070 84992 170070 85242 170070 85242 170071 84992 170071 85493 170071 85242 170072 85493 170072 85219 170072 85219 170073 85493 170073 84993 170073 85219 170074 84993 170074 85494 170074 84994 170075 84998 170075 85029 170075 84896 170076 84897 170076 85065 170076 85050 170077 85193 170077 85056 170077 85038 170078 85190 170078 85049 170078 85009 170079 85033 170079 85035 170079 85030 170080 85020 170080 85021 170080 85211 170081 85210 170081 84995 170081 85209 170082 85208 170082 84906 170082 85036 170083 85038 170083 85039 170083 85583 170084 85015 170084 84998 170084 85016 170085 85585 170085 85026 170085 85026 170086 85585 170086 84996 170086 85026 170087 84996 170087 85024 170087 85024 170088 84996 170088 92145 170088 85024 170089 92145 170089 85034 170089 84994 170090 84997 170090 84998 170090 84998 170091 84997 170091 84999 170091 84998 170092 84999 170092 85583 170092 85001 170093 85551 170093 85000 170093 85001 170094 85000 170094 85215 170094 85215 170095 85000 170095 85559 170095 85215 170096 85559 170096 85002 170096 85559 170097 85558 170097 85002 170097 85002 170098 85558 170098 92504 170098 85002 170099 92504 170099 84861 170099 92493 170100 85003 170100 85004 170100 85004 170101 85003 170101 84854 170101 85004 170102 84854 170102 85542 170102 85542 170103 84854 170103 84853 170103 85542 170104 84853 170104 85548 170104 85548 170105 84853 170105 85006 170105 85548 170106 85006 170106 85005 170106 85005 170107 85006 170107 84863 170107 85005 170108 84863 170108 85007 170108 85007 170109 84863 170109 84862 170109 85007 170110 84862 170110 85547 170110 85547 170111 84862 170111 84861 170111 85547 170112 84861 170112 85008 170112 85008 170113 84861 170113 92504 170113 85033 170114 85009 170114 85011 170114 85009 170115 85010 170115 85011 170115 85011 170116 85010 170116 85554 170116 85011 170117 85554 170117 92218 170117 85215 170118 85012 170118 85001 170118 85001 170119 85012 170119 85031 170119 85001 170120 85031 170120 85551 170120 85551 170121 85031 170121 85011 170121 85551 170122 85011 170122 85013 170122 85013 170123 85011 170123 92218 170123 84915 170124 84893 170124 85067 170124 84916 170125 84915 170125 85014 170125 85014 170126 84915 170126 85067 170126 85014 170127 85067 170127 85083 170127 85083 170128 85067 170128 85068 170128 85083 170129 85068 170129 85082 170129 85583 170130 85585 170130 85015 170130 85015 170131 85585 170131 85016 170131 85015 170132 85016 170132 84998 170132 84998 170133 85016 170133 85027 170133 84998 170134 85027 170134 85029 170134 84916 170135 85014 170135 85017 170135 85017 170136 85014 170136 85083 170136 85017 170137 85083 170137 84914 170137 84914 170138 85083 170138 85085 170138 84914 170139 85085 170139 84912 170139 84912 170140 85085 170140 85018 170140 84912 170141 85018 170141 84917 170141 84917 170142 85018 170142 85087 170142 84917 170143 85087 170143 84911 170143 85089 170144 85209 170144 85019 170144 85019 170145 85209 170145 84906 170145 85019 170146 84906 170146 85088 170146 85088 170147 84906 170147 84908 170147 85088 170148 84908 170148 85087 170148 85087 170149 84908 170149 84910 170149 85087 170150 84910 170150 84911 170150 85020 170151 85211 170151 85021 170151 85021 170152 85211 170152 84995 170152 85021 170153 84995 170153 85032 170153 85032 170154 84995 170154 85022 170154 85032 170155 85022 170155 85034 170155 85034 170156 85022 170156 85023 170156 85034 170157 85023 170157 85024 170157 85024 170158 85023 170158 85025 170158 85024 170159 85025 170159 85026 170159 85026 170160 85025 170160 85086 170160 85026 170161 85086 170161 85016 170161 85016 170162 85086 170162 85084 170162 85016 170163 85084 170163 85027 170163 85027 170164 85084 170164 85028 170164 85027 170165 85028 170165 85029 170165 85012 170166 85030 170166 85031 170166 85031 170167 85030 170167 85021 170167 85031 170168 85021 170168 85011 170168 85011 170169 85021 170169 85032 170169 85011 170170 85032 170170 85033 170170 85033 170171 85032 170171 85034 170171 85033 170172 85034 170172 85035 170172 85035 170173 85034 170173 92145 170173 85036 170174 85039 170174 84883 170174 84883 170175 85039 170175 85037 170175 84883 170176 85037 170176 84885 170176 84885 170177 85037 170177 85041 170177 84885 170178 85041 170178 84884 170178 84884 170179 85041 170179 85042 170179 84884 170180 85042 170180 84892 170180 84892 170181 85042 170181 85043 170181 84892 170182 85043 170182 84889 170182 85038 170183 85049 170183 85039 170183 85039 170184 85049 170184 85048 170184 85039 170185 85048 170185 85037 170185 85037 170186 85048 170186 85040 170186 85037 170187 85040 170187 85041 170187 85041 170188 85040 170188 85046 170188 85041 170189 85046 170189 85042 170189 85042 170190 85046 170190 85045 170190 85042 170191 85045 170191 85043 170191 84897 170192 84889 170192 85065 170192 85065 170193 84889 170193 85043 170193 85065 170194 85043 170194 85044 170194 85044 170195 85043 170195 85045 170195 85044 170196 85045 170196 85055 170196 85055 170197 85045 170197 85046 170197 85055 170198 85046 170198 85054 170198 85054 170199 85046 170199 85040 170199 85054 170200 85040 170200 85047 170200 85047 170201 85040 170201 85048 170201 85047 170202 85048 170202 85052 170202 85052 170203 85048 170203 85049 170203 85052 170204 85049 170204 85051 170204 85051 170205 85049 170205 85190 170205 85051 170206 85190 170206 85050 170206 85050 170207 85056 170207 85051 170207 85051 170208 85056 170208 85059 170208 85051 170209 85059 170209 85052 170209 85052 170210 85059 170210 85060 170210 85052 170211 85060 170211 85047 170211 85047 170212 85060 170212 85053 170212 85047 170213 85053 170213 85054 170213 85054 170214 85053 170214 85061 170214 85054 170215 85061 170215 85055 170215 85055 170216 85061 170216 85062 170216 85055 170217 85062 170217 85044 170217 85193 170218 85057 170218 85056 170218 85056 170219 85057 170219 85058 170219 85056 170220 85058 170220 85059 170220 85059 170221 85058 170221 85074 170221 85059 170222 85074 170222 85060 170222 85060 170223 85074 170223 85073 170223 85060 170224 85073 170224 85053 170224 85053 170225 85073 170225 85072 170225 85053 170226 85072 170226 85061 170226 85061 170227 85072 170227 85071 170227 85061 170228 85071 170228 85062 170228 85062 170229 85071 170229 85063 170229 85062 170230 85063 170230 85044 170230 85044 170231 85063 170231 85064 170231 85044 170232 85064 170232 85065 170232 85065 170233 85064 170233 85066 170233 85065 170234 85066 170234 84896 170234 84896 170235 85066 170235 84894 170235 84893 170236 84894 170236 85067 170236 85067 170237 84894 170237 85066 170237 85067 170238 85066 170238 85068 170238 85068 170239 85066 170239 85064 170239 85068 170240 85064 170240 85082 170240 85082 170241 85064 170241 85063 170241 85082 170242 85063 170242 85069 170242 85069 170243 85063 170243 85071 170243 85069 170244 85071 170244 85070 170244 85070 170245 85071 170245 85072 170245 85070 170246 85072 170246 85081 170246 85081 170247 85072 170247 85073 170247 85081 170248 85073 170248 85079 170248 85079 170249 85073 170249 85074 170249 85079 170250 85074 170250 85077 170250 85077 170251 85074 170251 85058 170251 85077 170252 85058 170252 85075 170252 85075 170253 85058 170253 85057 170253 85075 170254 85057 170254 85076 170254 85076 170255 85057 170255 85193 170255 85076 170256 85193 170256 85110 170256 85110 170257 85596 170257 85076 170257 85076 170258 85596 170258 85597 170258 85076 170259 85597 170259 85075 170259 85075 170260 85597 170260 85078 170260 85075 170261 85078 170261 85077 170261 85077 170262 85078 170262 85579 170262 85077 170263 85579 170263 85079 170263 85079 170264 85579 170264 85080 170264 85079 170265 85080 170265 85081 170265 85081 170266 85080 170266 84997 170266 85081 170267 84997 170267 85070 170267 85070 170268 84997 170268 84994 170268 85070 170269 84994 170269 85069 170269 85069 170270 84994 170270 85029 170270 85069 170271 85029 170271 85082 170271 85082 170272 85029 170272 85028 170272 85082 170273 85028 170273 85083 170273 85083 170274 85028 170274 85084 170274 85083 170275 85084 170275 85085 170275 85085 170276 85084 170276 85086 170276 85085 170277 85086 170277 85018 170277 85018 170278 85086 170278 85025 170278 85018 170279 85025 170279 85087 170279 85087 170280 85025 170280 85023 170280 85087 170281 85023 170281 85088 170281 85088 170282 85023 170282 85022 170282 85088 170283 85022 170283 85019 170283 85019 170284 85022 170284 84995 170284 85019 170285 84995 170285 85089 170285 85089 170286 84995 170286 85210 170286 84900 170287 85090 170287 85091 170287 84900 170288 85091 170288 84901 170288 84901 170289 85091 170289 84940 170289 84901 170290 84940 170290 84902 170290 85174 170291 85092 170291 85166 170291 85166 170292 85092 170292 85176 170292 85564 170293 85565 170293 85093 170293 85094 170294 85574 170294 85095 170294 85095 170295 85574 170295 85096 170295 85095 170296 85096 170296 85097 170296 85097 170297 85096 170297 85098 170297 85097 170298 85098 170298 84752 170298 84752 170299 85098 170299 85099 170299 84752 170300 85099 170300 85100 170300 85099 170301 85570 170301 85100 170301 85100 170302 85570 170302 85575 170302 85100 170303 85575 170303 84747 170303 84747 170304 85575 170304 85101 170304 84747 170305 85101 170305 85102 170305 85102 170306 85101 170306 85222 170306 85564 170307 85093 170307 85103 170307 85101 170308 85560 170308 85222 170308 85222 170309 85560 170309 85561 170309 85222 170310 85561 170310 85224 170310 85108 170311 85109 170311 85104 170311 85104 170312 85109 170312 85226 170312 85104 170313 85226 170313 85224 170313 85131 170314 85105 170314 85106 170314 85106 170315 85105 170315 85107 170315 85106 170316 85107 170316 85135 170316 85135 170317 85107 170317 85228 170317 85135 170318 85228 170318 85108 170318 85108 170319 85228 170319 85227 170319 85108 170320 85227 170320 85109 170320 85596 170321 85110 170321 85594 170321 85594 170322 85110 170322 85187 170322 85594 170323 85187 170323 85111 170323 85111 170324 85187 170324 85185 170324 85111 170325 85185 170325 92544 170325 92544 170326 85185 170326 85587 170326 85185 170327 85183 170327 85587 170327 85587 170328 85183 170328 85182 170328 85587 170329 85182 170329 85112 170329 85112 170330 85182 170330 85180 170330 85112 170331 85180 170331 85591 170331 85591 170332 85180 170332 85113 170332 85591 170333 85113 170333 85178 170333 85114 170334 85167 170334 85115 170334 85177 170335 85121 170335 85116 170335 85116 170336 85121 170336 85119 170336 85116 170337 85119 170337 85117 170337 85134 170338 85139 170338 92035 170338 92035 170339 85139 170339 85138 170339 92035 170340 85138 170340 85568 170340 85567 170341 92515 170341 85137 170341 85137 170342 92515 170342 85568 170342 85561 170343 85103 170343 85224 170343 85224 170344 85103 170344 85093 170344 85224 170345 85093 170345 85104 170345 85104 170346 85093 170346 85565 170346 85104 170347 85565 170347 85566 170347 84954 170348 85118 170348 85149 170348 85149 170349 85118 170349 85162 170349 85175 170350 85123 170350 85124 170350 85133 170351 85119 170351 85120 170351 85120 170352 85119 170352 85121 170352 85120 170353 85121 170353 85122 170353 85122 170354 85121 170354 85177 170354 85165 170355 85133 170355 85163 170355 85163 170356 85133 170356 85120 170356 85163 170357 85120 170357 85123 170357 85123 170358 85120 170358 85122 170358 85123 170359 85122 170359 85124 170359 85124 170360 85122 170360 85177 170360 85125 170361 85126 170361 85127 170361 85127 170362 85126 170362 84960 170362 85128 170363 85129 170363 85106 170363 85106 170364 85129 170364 85130 170364 85106 170365 85130 170365 85131 170365 85125 170366 85127 170366 85165 170366 85165 170367 85127 170367 85132 170367 85165 170368 85132 170368 85133 170368 85133 170369 85132 170369 85139 170369 85133 170370 85139 170370 85119 170370 85119 170371 85139 170371 85134 170371 85119 170372 85134 170372 85117 170372 85128 170373 85106 170373 85141 170373 85141 170374 85106 170374 85135 170374 85141 170375 85135 170375 85136 170375 85136 170376 85135 170376 85108 170376 85136 170377 85108 170377 85140 170377 85140 170378 85108 170378 85104 170378 85140 170379 85104 170379 85137 170379 85137 170380 85104 170380 85566 170380 85137 170381 85566 170381 85567 170381 85568 170382 85138 170382 85137 170382 85137 170383 85138 170383 85139 170383 85137 170384 85139 170384 85140 170384 85140 170385 85139 170385 85132 170385 85140 170386 85132 170386 85136 170386 85136 170387 85132 170387 85127 170387 85136 170388 85127 170388 85141 170388 85141 170389 85127 170389 84960 170389 85141 170390 84960 170390 85128 170390 85191 170391 85189 170391 85160 170391 85192 170392 85142 170392 85148 170392 85172 170393 85170 170393 85143 170393 85143 170394 85170 170394 85169 170394 85143 170395 85169 170395 85144 170395 85144 170396 85169 170396 85145 170396 85144 170397 85145 170397 85146 170397 85146 170398 85145 170398 85148 170398 85146 170399 85148 170399 85147 170399 85147 170400 85148 170400 85142 170400 85147 170401 85142 170401 85191 170401 84954 170402 85149 170402 84955 170402 84955 170403 85149 170403 85150 170403 84955 170404 85150 170404 85151 170404 85151 170405 85150 170405 85161 170405 85151 170406 85161 170406 85152 170406 85152 170407 85161 170407 85154 170407 85152 170408 85154 170408 85153 170408 85153 170409 85154 170409 85155 170409 85153 170410 85155 170410 85156 170410 85156 170411 85155 170411 85157 170411 85156 170412 85157 170412 85158 170412 85158 170413 85157 170413 85159 170413 85158 170414 85159 170414 84946 170414 84946 170415 85159 170415 85160 170415 84946 170416 85160 170416 84949 170416 84949 170417 85160 170417 85189 170417 84949 170418 85189 170418 84950 170418 85191 170419 85160 170419 85147 170419 85147 170420 85160 170420 85159 170420 85147 170421 85159 170421 85146 170421 85146 170422 85159 170422 85157 170422 85146 170423 85157 170423 85144 170423 85144 170424 85157 170424 85155 170424 85144 170425 85155 170425 85143 170425 85143 170426 85155 170426 85154 170426 85143 170427 85154 170427 85172 170427 85172 170428 85154 170428 85161 170428 85172 170429 85161 170429 85173 170429 85173 170430 85161 170430 85150 170430 85173 170431 85150 170431 85175 170431 85175 170432 85150 170432 85149 170432 85175 170433 85149 170433 85123 170433 85123 170434 85149 170434 85162 170434 85123 170435 85162 170435 85163 170435 85163 170436 85162 170436 84957 170436 85163 170437 84957 170437 85165 170437 85165 170438 84957 170438 85164 170438 85165 170439 85164 170439 85125 170439 85198 170440 85174 170440 85199 170440 85199 170441 85174 170441 85166 170441 85199 170442 85166 170442 85114 170442 85114 170443 85166 170443 85176 170443 85114 170444 85176 170444 85167 170444 85192 170445 85148 170445 85194 170445 85194 170446 85148 170446 85145 170446 85194 170447 85145 170447 85168 170447 85168 170448 85145 170448 85169 170448 85168 170449 85169 170449 85195 170449 85195 170450 85169 170450 85170 170450 85195 170451 85170 170451 85171 170451 85171 170452 85170 170452 85172 170452 85171 170453 85172 170453 85198 170453 85198 170454 85172 170454 85173 170454 85198 170455 85173 170455 85174 170455 85174 170456 85173 170456 85175 170456 85174 170457 85175 170457 85092 170457 85092 170458 85175 170458 85124 170458 85092 170459 85124 170459 85176 170459 85176 170460 85124 170460 85177 170460 85176 170461 85177 170461 85167 170461 85167 170462 85177 170462 85116 170462 85167 170463 85116 170463 85115 170463 92538 170464 85178 170464 85179 170464 85179 170465 85178 170465 85113 170465 85179 170466 85113 170466 85197 170466 85197 170467 85113 170467 85180 170467 85197 170468 85180 170468 85181 170468 85181 170469 85180 170469 85182 170469 85181 170470 85182 170470 85196 170470 85196 170471 85182 170471 85183 170471 85196 170472 85183 170472 85184 170472 85184 170473 85183 170473 85185 170473 85184 170474 85185 170474 85186 170474 85186 170475 85185 170475 85187 170475 85186 170476 85187 170476 85188 170476 85188 170477 85187 170477 85110 170477 85188 170478 85110 170478 85193 170478 85036 170479 84950 170479 85038 170479 85038 170480 84950 170480 85189 170480 85038 170481 85189 170481 85190 170481 85190 170482 85189 170482 85191 170482 85190 170483 85191 170483 85050 170483 85050 170484 85191 170484 85142 170484 85050 170485 85142 170485 85193 170485 85193 170486 85142 170486 85192 170486 85193 170487 85192 170487 85188 170487 85188 170488 85192 170488 85194 170488 85188 170489 85194 170489 85186 170489 85186 170490 85194 170490 85168 170490 85186 170491 85168 170491 85184 170491 85184 170492 85168 170492 85195 170492 85184 170493 85195 170493 85196 170493 85196 170494 85195 170494 85171 170494 85196 170495 85171 170495 85181 170495 85181 170496 85171 170496 85198 170496 85181 170497 85198 170497 85197 170497 85197 170498 85198 170498 85199 170498 85197 170499 85199 170499 85179 170499 85179 170500 85199 170500 85114 170500 85179 170501 85114 170501 92538 170501 92538 170502 85114 170502 85115 170502 84990 170503 84987 170503 85238 170503 85240 170504 85200 170504 85238 170504 85238 170505 85200 170505 85201 170505 85238 170506 85201 170506 84990 170506 84940 170507 85091 170507 85217 170507 85217 170508 85091 170508 85402 170508 85402 170509 85091 170509 85202 170509 85202 170510 85091 170510 85090 170510 85202 170511 85090 170511 85412 170511 85090 170512 84903 170512 85412 170512 85412 170513 84903 170513 84904 170513 85412 170514 84904 170514 85411 170514 84904 170515 85203 170515 85411 170515 85411 170516 85203 170516 85204 170516 85411 170517 85204 170517 85408 170517 85408 170518 85204 170518 84935 170518 85408 170519 84935 170519 85205 170519 85205 170520 84935 170520 84936 170520 84936 170521 84919 170521 85205 170521 85205 170522 84919 170522 85206 170522 85205 170523 85206 170523 85207 170523 85207 170524 85206 170524 85208 170524 85207 170525 85208 170525 85407 170525 85208 170526 85209 170526 85407 170526 85407 170527 85209 170527 85089 170527 85407 170528 85089 170528 85403 170528 85403 170529 85089 170529 85210 170529 85403 170530 85210 170530 85437 170530 85437 170531 85210 170531 85361 170531 85361 170532 85210 170532 85211 170532 85361 170533 85211 170533 85212 170533 85212 170534 85211 170534 85020 170534 85212 170535 85020 170535 85362 170535 85362 170536 85020 170536 85030 170536 85362 170537 85030 170537 85364 170537 85364 170538 85030 170538 85012 170538 85364 170539 85012 170539 85213 170539 85213 170540 85012 170540 85215 170540 85213 170541 85215 170541 85214 170541 85214 170542 85215 170542 85002 170542 85214 170543 85002 170543 85216 170543 85216 170544 85002 170544 84861 170544 85216 170545 84861 170545 84855 170545 85495 170546 85217 170546 85218 170546 85218 170547 85217 170547 85219 170547 85218 170548 85219 170548 85494 170548 85220 170549 84940 170549 85221 170549 85221 170550 84940 170550 85217 170550 85221 170551 85217 170551 85496 170551 85496 170552 85217 170552 85495 170552 84872 170553 85102 170553 85222 170553 84872 170554 85222 170554 85223 170554 85223 170555 85222 170555 85224 170555 85223 170556 85224 170556 85225 170556 85225 170557 85224 170557 85226 170557 85225 170558 85226 170558 85332 170558 85332 170559 85226 170559 85109 170559 85332 170560 85109 170560 85333 170560 85109 170561 85227 170561 85333 170561 85333 170562 85227 170562 85228 170562 85333 170563 85228 170563 85229 170563 85228 170564 85107 170564 85229 170564 85229 170565 85107 170565 85105 170565 85229 170566 85105 170566 85230 170566 85230 170567 85105 170567 85131 170567 85230 170568 85131 170568 85231 170568 85231 170569 85131 170569 85130 170569 85231 170570 85130 170570 85232 170570 85232 170571 85130 170571 84968 170571 85232 170572 84968 170572 85237 170572 85234 170573 85239 170573 85241 170573 85241 170574 85233 170574 85234 170574 85234 170575 85233 170575 85235 170575 85234 170576 85235 170576 84986 170576 84986 170577 85235 170577 85236 170577 84986 170578 85236 170578 84985 170578 84985 170579 85236 170579 85290 170579 84985 170580 85290 170580 84961 170580 84961 170581 85290 170581 85345 170581 84961 170582 85345 170582 85237 170582 85237 170583 85345 170583 85344 170583 85237 170584 85344 170584 85232 170584 85238 170585 84987 170585 85242 170585 85239 170586 85240 170586 85241 170586 85241 170587 85240 170587 85238 170587 85241 170588 85238 170588 85359 170588 85359 170589 85238 170589 85242 170589 85242 170590 85219 170590 85252 170590 85242 170591 85252 170591 85243 170591 85243 170592 85252 170592 85253 170592 85243 170593 85253 170593 85357 170593 85357 170594 85253 170594 85254 170594 85357 170595 85254 170595 85244 170595 85244 170596 85254 170596 85245 170596 85244 170597 85245 170597 85311 170597 85311 170598 85245 170598 85246 170598 85311 170599 85246 170599 85247 170599 85247 170600 85246 170600 85256 170600 85247 170601 85256 170601 85321 170601 85321 170602 85256 170602 85248 170602 85321 170603 85248 170603 85249 170603 85249 170604 85248 170604 85250 170604 85249 170605 85250 170605 84844 170605 85219 170606 85217 170606 85251 170606 85219 170607 85251 170607 85252 170607 85252 170608 85251 170608 85401 170608 85252 170609 85401 170609 85253 170609 85253 170610 85401 170610 85430 170610 85253 170611 85430 170611 85254 170611 85254 170612 85430 170612 85464 170612 85254 170613 85464 170613 85245 170613 85245 170614 85464 170614 85255 170614 85245 170615 85255 170615 85246 170615 85246 170616 85255 170616 85257 170616 85246 170617 85257 170617 85256 170617 85256 170618 85257 170618 85467 170618 85256 170619 85467 170619 85248 170619 85248 170620 85467 170620 85258 170620 85248 170621 85258 170621 85250 170621 85330 170622 84872 170622 85223 170622 85249 170623 84844 170623 84845 170623 85359 170624 85242 170624 85243 170624 85325 170625 85327 170625 85264 170625 85259 170626 84880 170626 84831 170626 84831 170627 84880 170627 85269 170627 84831 170628 85269 170628 84832 170628 84832 170629 85269 170629 85270 170629 84832 170630 85270 170630 85260 170630 85260 170631 85270 170631 85262 170631 85260 170632 85262 170632 85263 170632 85348 170633 85264 170633 85261 170633 85261 170634 85264 170634 85327 170634 85261 170635 85327 170635 85262 170635 85262 170636 85327 170636 85329 170636 85262 170637 85329 170637 85263 170637 85348 170638 85349 170638 85264 170638 85264 170639 85349 170639 85265 170639 85264 170640 85265 170640 85325 170640 85325 170641 85265 170641 85318 170641 84879 170642 84877 170642 85266 170642 85266 170643 84877 170643 85267 170643 85266 170644 85267 170644 85271 170644 85271 170645 85267 170645 85268 170645 85271 170646 85268 170646 85272 170646 85272 170647 85268 170647 85346 170647 84880 170648 84879 170648 85269 170648 85269 170649 84879 170649 85266 170649 85269 170650 85266 170650 85270 170650 85270 170651 85266 170651 85271 170651 85270 170652 85271 170652 85262 170652 85262 170653 85271 170653 85272 170653 85262 170654 85272 170654 85261 170654 85261 170655 85272 170655 85346 170655 85261 170656 85346 170656 85348 170656 84875 170657 84874 170657 85273 170657 85273 170658 84874 170658 85331 170658 85273 170659 85331 170659 85335 170659 85335 170660 85331 170660 85274 170660 85335 170661 85274 170661 85275 170661 85275 170662 85274 170662 85276 170662 85275 170663 85276 170663 85338 170663 85338 170664 85276 170664 85277 170664 85338 170665 85277 170665 85339 170665 85339 170666 85277 170666 85278 170666 85339 170667 85278 170667 85341 170667 85292 170668 85356 170668 85293 170668 85293 170669 85356 170669 85279 170669 85293 170670 85279 170670 85294 170670 85294 170671 85279 170671 85354 170671 85294 170672 85354 170672 85280 170672 85280 170673 85354 170673 85353 170673 85280 170674 85353 170674 85296 170674 85296 170675 85353 170675 85352 170675 85296 170676 85352 170676 85298 170676 85298 170677 85352 170677 85281 170677 85298 170678 85281 170678 85282 170678 85282 170679 85281 170679 85350 170679 85282 170680 85350 170680 85300 170680 85283 170681 85358 170681 85284 170681 85284 170682 85358 170682 85291 170682 85241 170683 85283 170683 85233 170683 85233 170684 85283 170684 85284 170684 85233 170685 85284 170685 85235 170685 85235 170686 85284 170686 85236 170686 85340 170687 85342 170687 85297 170687 85297 170688 85342 170688 85343 170688 85297 170689 85343 170689 85285 170689 85285 170690 85343 170690 85286 170690 85285 170691 85286 170691 85295 170691 85295 170692 85286 170692 85287 170692 85295 170693 85287 170693 85288 170693 85288 170694 85287 170694 85289 170694 85288 170695 85289 170695 85291 170695 85291 170696 85289 170696 85284 170696 85284 170697 85289 170697 85290 170697 85284 170698 85290 170698 85236 170698 85358 170699 85292 170699 85291 170699 85291 170700 85292 170700 85293 170700 85291 170701 85293 170701 85288 170701 85288 170702 85293 170702 85294 170702 85288 170703 85294 170703 85295 170703 85295 170704 85294 170704 85280 170704 85295 170705 85280 170705 85285 170705 85285 170706 85280 170706 85296 170706 85285 170707 85296 170707 85297 170707 85297 170708 85296 170708 85298 170708 85297 170709 85298 170709 85340 170709 85340 170710 85298 170710 85282 170710 85340 170711 85282 170711 85299 170711 85299 170712 85282 170712 85300 170712 85299 170713 85300 170713 85337 170713 85337 170714 85300 170714 85301 170714 85337 170715 85301 170715 85336 170715 85336 170716 85301 170716 85302 170716 85336 170717 85302 170717 85303 170717 85303 170718 85302 170718 85347 170718 85303 170719 85347 170719 85334 170719 85334 170720 85347 170720 85304 170720 85334 170721 85304 170721 84876 170721 85321 170722 85249 170722 85305 170722 85305 170723 85249 170723 84845 170723 85305 170724 84845 170724 85323 170724 85323 170725 84845 170725 85306 170725 85323 170726 85306 170726 85324 170726 85324 170727 85306 170727 85307 170727 85324 170728 85307 170728 85308 170728 85308 170729 85307 170729 84843 170729 85308 170730 84843 170730 85326 170730 85326 170731 84843 170731 85309 170731 85326 170732 85309 170732 85310 170732 85311 170733 85247 170733 85355 170733 85355 170734 85247 170734 85312 170734 85355 170735 85312 170735 85313 170735 85313 170736 85312 170736 85322 170736 85313 170737 85322 170737 85314 170737 85314 170738 85322 170738 85315 170738 85314 170739 85315 170739 85317 170739 85317 170740 85315 170740 85316 170740 85317 170741 85316 170741 85351 170741 85351 170742 85316 170742 85318 170742 85351 170743 85318 170743 85319 170743 85319 170744 85318 170744 85265 170744 85319 170745 85265 170745 85320 170745 85320 170746 85265 170746 85349 170746 85247 170747 85321 170747 85312 170747 85312 170748 85321 170748 85305 170748 85312 170749 85305 170749 85322 170749 85322 170750 85305 170750 85323 170750 85322 170751 85323 170751 85315 170751 85315 170752 85323 170752 85324 170752 85315 170753 85324 170753 85316 170753 85316 170754 85324 170754 85308 170754 85316 170755 85308 170755 85318 170755 85318 170756 85308 170756 85326 170756 85318 170757 85326 170757 85325 170757 85325 170758 85326 170758 85310 170758 85325 170759 85310 170759 85327 170759 85327 170760 85310 170760 85328 170760 85327 170761 85328 170761 85329 170761 84874 170762 85330 170762 85331 170762 85331 170763 85330 170763 85223 170763 85331 170764 85223 170764 85274 170764 85274 170765 85223 170765 85225 170765 85274 170766 85225 170766 85276 170766 85276 170767 85225 170767 85332 170767 85276 170768 85332 170768 85277 170768 85277 170769 85332 170769 85333 170769 85277 170770 85333 170770 85278 170770 85278 170771 85333 170771 85229 170771 85278 170772 85229 170772 85341 170772 85341 170773 85229 170773 85230 170773 84876 170774 84875 170774 85334 170774 85334 170775 84875 170775 85273 170775 85334 170776 85273 170776 85303 170776 85303 170777 85273 170777 85335 170777 85303 170778 85335 170778 85336 170778 85336 170779 85335 170779 85275 170779 85336 170780 85275 170780 85337 170780 85337 170781 85275 170781 85338 170781 85337 170782 85338 170782 85299 170782 85299 170783 85338 170783 85339 170783 85299 170784 85339 170784 85340 170784 85340 170785 85339 170785 85341 170785 85340 170786 85341 170786 85342 170786 85342 170787 85341 170787 85230 170787 85342 170788 85230 170788 85343 170788 85343 170789 85230 170789 85231 170789 85343 170790 85231 170790 85286 170790 85286 170791 85231 170791 85232 170791 85286 170792 85232 170792 85287 170792 85287 170793 85232 170793 85344 170793 85287 170794 85344 170794 85289 170794 85289 170795 85344 170795 85345 170795 85289 170796 85345 170796 85290 170796 84877 170797 84876 170797 85267 170797 85267 170798 84876 170798 85304 170798 85267 170799 85304 170799 85268 170799 85268 170800 85304 170800 85347 170800 85268 170801 85347 170801 85346 170801 85346 170802 85347 170802 85302 170802 85346 170803 85302 170803 85348 170803 85348 170804 85302 170804 85301 170804 85348 170805 85301 170805 85349 170805 85349 170806 85301 170806 85300 170806 85349 170807 85300 170807 85320 170807 85320 170808 85300 170808 85350 170808 85320 170809 85350 170809 85319 170809 85319 170810 85350 170810 85281 170810 85319 170811 85281 170811 85351 170811 85351 170812 85281 170812 85352 170812 85351 170813 85352 170813 85317 170813 85317 170814 85352 170814 85353 170814 85317 170815 85353 170815 85314 170815 85314 170816 85353 170816 85354 170816 85314 170817 85354 170817 85313 170817 85313 170818 85354 170818 85279 170818 85313 170819 85279 170819 85355 170819 85355 170820 85279 170820 85356 170820 85355 170821 85356 170821 85311 170821 85311 170822 85356 170822 85292 170822 85311 170823 85292 170823 85244 170823 85244 170824 85292 170824 85358 170824 85244 170825 85358 170825 85357 170825 85357 170826 85358 170826 85283 170826 85357 170827 85283 170827 85243 170827 85243 170828 85283 170828 85241 170828 85243 170829 85241 170829 85359 170829 85469 170830 85258 170830 85467 170830 85398 170831 85360 170831 85397 170831 85368 170832 85436 170832 85361 170832 85361 170833 85212 170833 85368 170833 85368 170834 85212 170834 85362 170834 85368 170835 85362 170835 85363 170835 85363 170836 85362 170836 85364 170836 85363 170837 85364 170837 85367 170837 85367 170838 85364 170838 85213 170838 85367 170839 85213 170839 85365 170839 85365 170840 85213 170840 85214 170840 85365 170841 85214 170841 84869 170841 84869 170842 85214 170842 85216 170842 84869 170843 85216 170843 84855 170843 84869 170844 84868 170844 85365 170844 85365 170845 84868 170845 85366 170845 85365 170846 85366 170846 85367 170846 85367 170847 85366 170847 85415 170847 85367 170848 85415 170848 85363 170848 85363 170849 85415 170849 85417 170849 85363 170850 85417 170850 85368 170850 85368 170851 85417 170851 85418 170851 85368 170852 85418 170852 85436 170852 85436 170853 85418 170853 85420 170853 85372 170854 85374 170854 85369 170854 85369 170855 85374 170855 85446 170855 85439 170856 85441 170856 85370 170856 85370 170857 85441 170857 85444 170857 85370 170858 85444 170858 85371 170858 85371 170859 85444 170859 85373 170859 85371 170860 85373 170860 85381 170860 85381 170861 85373 170861 85372 170861 85372 170862 85373 170862 85374 170862 85374 170863 85373 170863 85375 170863 85374 170864 85375 170864 85446 170864 85386 170865 85465 170865 85388 170865 85388 170866 85465 170866 85463 170866 85388 170867 85463 170867 85376 170867 85376 170868 85463 170868 85377 170868 85376 170869 85377 170869 85378 170869 85378 170870 85377 170870 85460 170870 85378 170871 85460 170871 85400 170871 85360 170872 85398 170872 85379 170872 85379 170873 85398 170873 85399 170873 85379 170874 85399 170874 85380 170874 85391 170875 85439 170875 85392 170875 85392 170876 85439 170876 85370 170876 85392 170877 85370 170877 85393 170877 85393 170878 85370 170878 85371 170878 85393 170879 85371 170879 85395 170879 85395 170880 85371 170880 85381 170880 85395 170881 85381 170881 85396 170881 85396 170882 85381 170882 85372 170882 85396 170883 85372 170883 85382 170883 85382 170884 85372 170884 85369 170884 85382 170885 85369 170885 85383 170885 85383 170886 85369 170886 85448 170886 85383 170887 85448 170887 85390 170887 85390 170888 85448 170888 85384 170888 85390 170889 85384 170889 85389 170889 85389 170890 85384 170890 85449 170890 85389 170891 85449 170891 85387 170891 85387 170892 85449 170892 85450 170892 85387 170893 85450 170893 85385 170893 85385 170894 85450 170894 85466 170894 85385 170895 85386 170895 85387 170895 85387 170896 85386 170896 85388 170896 85387 170897 85388 170897 85389 170897 85389 170898 85388 170898 85376 170898 85389 170899 85376 170899 85390 170899 85390 170900 85376 170900 85378 170900 85390 170901 85378 170901 85383 170901 85383 170902 85378 170902 85400 170902 85383 170903 85400 170903 85382 170903 85454 170904 85391 170904 85455 170904 85455 170905 85391 170905 85392 170905 85455 170906 85392 170906 85457 170906 85457 170907 85392 170907 85393 170907 85457 170908 85393 170908 85394 170908 85394 170909 85393 170909 85395 170909 85394 170910 85395 170910 85397 170910 85397 170911 85395 170911 85396 170911 85397 170912 85396 170912 85398 170912 85398 170913 85396 170913 85382 170913 85398 170914 85382 170914 85399 170914 85399 170915 85382 170915 85400 170915 85399 170916 85400 170916 85380 170916 85380 170917 85400 170917 85460 170917 85401 170918 85251 170918 85431 170918 85431 170919 85251 170919 85217 170919 85431 170920 85217 170920 85402 170920 85437 170921 85404 170921 85403 170921 85403 170922 85404 170922 85405 170922 85403 170923 85405 170923 85407 170923 85407 170924 85405 170924 85406 170924 85407 170925 85406 170925 85207 170925 85207 170926 85406 170926 85435 170926 85207 170927 85435 170927 85205 170927 85205 170928 85435 170928 85434 170928 85205 170929 85434 170929 85408 170929 85408 170930 85434 170930 85409 170930 85408 170931 85409 170931 85411 170931 85411 170932 85409 170932 85410 170932 85411 170933 85410 170933 85412 170933 85412 170934 85410 170934 85431 170934 85412 170935 85431 170935 85202 170935 85202 170936 85431 170936 85402 170936 84868 170937 85413 170937 85366 170937 85366 170938 85413 170938 85414 170938 85366 170939 85414 170939 85415 170939 85415 170940 85414 170940 85416 170940 85415 170941 85416 170941 85417 170941 85417 170942 85416 170942 85456 170942 85417 170943 85456 170943 85418 170943 85418 170944 85456 170944 85419 170944 85418 170945 85419 170945 85420 170945 85420 170946 85419 170946 85458 170946 85420 170947 85458 170947 85421 170947 85421 170948 85458 170948 85459 170948 85421 170949 85459 170949 85423 170949 85423 170950 85459 170950 85422 170950 85423 170951 85422 170951 85424 170951 85424 170952 85422 170952 85425 170952 85424 170953 85425 170953 85433 170953 85433 170954 85425 170954 85426 170954 85433 170955 85426 170955 85427 170955 85427 170956 85426 170956 85461 170956 85427 170957 85461 170957 85432 170957 85432 170958 85461 170958 85462 170958 85432 170959 85462 170959 85428 170959 85428 170960 85462 170960 85429 170960 85428 170961 85429 170961 85430 170961 85430 170962 85429 170962 85464 170962 85430 170963 85401 170963 85428 170963 85428 170964 85401 170964 85431 170964 85428 170965 85431 170965 85432 170965 85432 170966 85431 170966 85410 170966 85432 170967 85410 170967 85427 170967 85427 170968 85410 170968 85409 170968 85427 170969 85409 170969 85433 170969 85433 170970 85409 170970 85434 170970 85433 170971 85434 170971 85424 170971 85424 170972 85434 170972 85435 170972 85424 170973 85435 170973 85423 170973 85423 170974 85435 170974 85406 170974 85423 170975 85406 170975 85421 170975 85421 170976 85406 170976 85405 170976 85421 170977 85405 170977 85420 170977 85420 170978 85405 170978 85404 170978 85420 170979 85404 170979 85436 170979 85436 170980 85404 170980 85437 170980 85436 170981 85437 170981 85361 170981 85454 170982 85453 170982 85391 170982 85391 170983 85453 170983 85438 170983 85391 170984 85438 170984 85439 170984 85439 170985 85438 170985 85440 170985 85439 170986 85440 170986 85441 170986 85441 170987 85440 170987 85442 170987 85441 170988 85442 170988 84835 170988 84835 170989 85443 170989 85441 170989 85441 170990 85443 170990 84834 170990 85441 170991 84834 170991 85444 170991 85444 170992 84834 170992 84833 170992 85444 170993 84833 170993 85373 170993 85373 170994 84833 170994 85445 170994 85373 170995 85445 170995 85375 170995 85446 170996 84849 170996 85369 170996 85369 170997 84849 170997 85447 170997 85369 170998 85447 170998 85448 170998 85448 170999 85447 170999 84848 170999 85448 171000 84848 171000 85384 171000 85384 171001 84848 171001 84847 171001 85384 171002 84847 171002 85449 171002 85449 171003 84847 171003 84846 171003 85449 171004 84846 171004 85450 171004 85450 171005 84846 171005 85451 171005 85450 171006 85451 171006 85466 171006 85466 171007 85451 171007 85452 171007 85466 171008 85452 171008 85468 171008 85413 171009 85453 171009 85414 171009 85414 171010 85453 171010 85454 171010 85414 171011 85454 171011 85416 171011 85416 171012 85454 171012 85455 171012 85416 171013 85455 171013 85456 171013 85456 171014 85455 171014 85457 171014 85456 171015 85457 171015 85419 171015 85419 171016 85457 171016 85394 171016 85419 171017 85394 171017 85458 171017 85458 171018 85394 171018 85397 171018 85458 171019 85397 171019 85459 171019 85459 171020 85397 171020 85360 171020 85459 171021 85360 171021 85422 171021 85422 171022 85360 171022 85379 171022 85422 171023 85379 171023 85425 171023 85425 171024 85379 171024 85380 171024 85425 171025 85380 171025 85426 171025 85426 171026 85380 171026 85460 171026 85426 171027 85460 171027 85461 171027 85461 171028 85460 171028 85377 171028 85461 171029 85377 171029 85462 171029 85462 171030 85377 171030 85463 171030 85462 171031 85463 171031 85429 171031 85429 171032 85463 171032 85465 171032 85429 171033 85465 171033 85464 171033 85464 171034 85465 171034 85386 171034 85464 171035 85386 171035 85255 171035 85255 171036 85386 171036 85385 171036 85255 171037 85385 171037 85257 171037 85257 171038 85385 171038 85466 171038 85257 171039 85466 171039 85467 171039 85467 171040 85466 171040 85468 171040 85467 171041 85468 171041 85469 171041 84898 171042 84939 171042 85472 171042 85472 171043 84939 171043 85501 171043 85474 171044 85470 171044 85501 171044 85501 171045 85470 171045 85471 171045 85501 171046 85471 171046 85472 171046 84895 171047 85473 171047 85484 171047 85477 171048 84941 171048 85484 171048 85473 171049 85474 171049 85484 171049 85484 171050 85474 171050 85501 171050 85484 171051 85501 171051 85475 171051 84951 171052 85476 171052 85484 171052 85484 171053 85476 171053 84882 171053 84956 171054 85477 171054 85478 171054 85478 171055 85477 171055 85484 171055 85478 171056 85484 171056 85492 171056 84941 171057 84942 171057 85484 171057 85484 171058 84942 171058 84943 171058 85484 171059 84943 171059 84944 171059 84890 171060 85479 171060 85484 171060 85484 171061 85479 171061 85480 171061 85484 171062 85480 171062 84895 171062 85501 171063 85499 171063 85498 171063 85485 171064 84888 171064 85484 171064 85484 171065 84888 171065 84891 171065 85484 171066 84891 171066 84890 171066 85498 171067 85497 171067 85501 171067 85501 171068 85497 171068 85481 171068 85501 171069 85481 171069 85475 171069 85492 171070 85482 171070 85478 171070 85478 171071 85482 171071 85483 171071 85478 171072 85483 171072 85490 171072 84944 171073 84948 171073 85484 171073 85484 171074 84948 171074 84947 171074 85484 171075 84947 171075 84945 171075 84882 171076 84887 171076 85484 171076 85484 171077 84887 171077 84886 171077 85484 171078 84886 171078 85485 171078 84945 171079 85486 171079 85484 171079 85484 171080 85486 171080 85487 171080 85484 171081 85487 171081 84951 171081 84989 171082 84988 171082 85478 171082 85478 171083 84988 171083 85488 171083 85488 171084 84972 171084 85478 171084 85478 171085 84972 171085 84971 171085 85478 171086 84971 171086 84956 171086 85478 171087 85490 171087 84989 171087 84989 171088 85490 171088 85489 171088 85489 171089 85490 171089 84991 171089 84991 171090 85490 171090 85483 171090 84991 171091 85483 171091 85491 171091 85491 171092 85483 171092 85482 171092 85491 171093 85482 171093 84992 171093 84992 171094 85482 171094 85492 171094 84992 171095 85492 171095 85493 171095 85493 171096 85492 171096 85484 171096 85493 171097 85484 171097 84993 171097 84993 171098 85484 171098 85494 171098 85494 171099 85484 171099 85475 171099 85494 171100 85475 171100 85218 171100 85218 171101 85475 171101 85481 171101 85218 171102 85481 171102 85495 171102 85495 171103 85481 171103 85497 171103 85495 171104 85497 171104 85496 171104 85496 171105 85497 171105 85498 171105 85496 171106 85498 171106 85221 171106 85221 171107 85498 171107 85220 171107 85220 171108 85498 171108 85499 171108 85220 171109 85499 171109 85500 171109 85500 171110 85499 171110 85501 171110 85500 171111 85501 171111 84939 171111 92453 171112 86255 171112 86254 171112 92453 171113 86254 171113 85502 171113 85502 171114 86254 171114 92440 171114 85502 171115 92440 171115 92445 171115 92440 171116 86257 171116 92445 171116 92445 171117 86257 171117 86283 171117 92445 171118 86283 171118 85503 171118 85503 171119 86283 171119 85504 171119 85503 171120 85504 171120 92394 171120 92394 171121 85504 171121 86261 171121 92394 171122 86261 171122 85505 171122 85505 171123 86261 171123 86260 171123 85505 171124 86260 171124 84566 171124 84566 171125 86260 171125 86288 171125 84566 171126 86288 171126 85506 171126 85506 171127 86288 171127 85508 171127 85506 171128 85508 171128 85507 171128 85507 171129 85508 171129 86286 171129 85507 171130 86286 171130 85509 171130 85509 171131 86286 171131 86285 171131 85509 171132 86285 171132 84560 171132 84560 171133 86285 171133 92578 171133 84560 171134 92578 171134 84561 171134 85530 171135 92484 171135 84373 171135 84373 171136 92484 171136 85510 171136 84373 171137 85510 171137 84371 171137 85511 171138 92450 171138 86249 171138 86249 171139 92450 171139 85512 171139 86249 171140 85512 171140 92468 171140 92468 171141 85512 171141 84577 171141 84568 171142 86318 171142 85514 171142 85514 171143 86318 171143 85513 171143 85514 171144 85513 171144 85515 171144 85515 171145 85513 171145 86255 171145 85515 171146 86255 171146 92453 171146 86249 171147 85516 171147 85511 171147 85511 171148 85516 171148 92550 171148 85511 171149 92550 171149 85517 171149 85517 171150 92550 171150 86318 171150 85517 171151 86318 171151 84567 171151 84567 171152 86318 171152 84568 171152 84371 171153 85510 171153 84351 171153 84351 171154 85510 171154 85518 171154 84351 171155 85518 171155 84350 171155 84350 171156 85518 171156 86167 171156 84350 171157 86167 171157 92281 171157 92281 171158 86167 171158 86099 171158 92281 171159 86099 171159 84364 171159 84364 171160 86099 171160 85519 171160 84364 171161 85519 171161 85520 171161 85520 171162 85519 171162 85521 171162 85520 171163 85521 171163 84366 171163 84366 171164 85521 171164 85522 171164 84366 171165 85522 171165 85524 171165 85522 171166 85523 171166 85524 171166 85524 171167 85523 171167 86110 171167 85524 171168 86110 171168 92474 171168 92474 171169 86110 171169 86311 171169 92474 171170 86311 171170 85525 171170 85525 171171 86311 171171 85526 171171 85525 171172 85526 171172 85527 171172 85527 171173 85526 171173 85528 171173 85527 171174 85528 171174 84577 171174 84577 171175 85528 171175 85529 171175 84577 171176 85529 171176 92468 171176 86171 171177 92484 171177 85530 171177 85543 171178 92491 171178 84377 171178 84377 171179 92491 171179 86114 171179 84377 171180 86114 171180 84378 171180 84378 171181 86114 171181 86113 171181 86171 171182 85530 171182 85532 171182 85530 171183 92483 171183 85532 171183 85532 171184 92483 171184 85531 171184 85532 171185 85531 171185 86152 171185 86152 171186 85531 171186 85533 171186 86152 171187 85533 171187 92481 171187 92481 171188 85533 171188 85534 171188 92481 171189 85534 171189 86105 171189 86105 171190 85534 171190 85535 171190 86105 171191 85535 171191 85537 171191 85537 171192 85535 171192 85536 171192 85537 171193 85536 171193 92477 171193 92477 171194 85536 171194 84379 171194 92477 171195 84379 171195 85538 171195 85538 171196 84379 171196 85539 171196 85538 171197 85539 171197 86113 171197 86113 171198 85539 171198 85540 171198 86113 171199 85540 171199 84378 171199 85546 171200 84353 171200 92686 171200 92686 171201 84353 171201 92493 171201 92686 171202 92493 171202 85541 171202 85541 171203 92493 171203 85004 171203 85541 171204 85004 171204 86844 171204 86844 171205 85004 171205 85542 171205 86844 171206 85542 171206 86842 171206 86842 171207 85542 171207 85548 171207 86842 171208 85548 171208 92496 171208 92491 171209 85543 171209 86102 171209 86102 171210 85543 171210 84356 171210 86102 171211 84356 171211 85544 171211 85544 171212 84356 171212 92307 171212 85544 171213 92307 171213 92486 171213 92486 171214 92307 171214 84354 171214 92486 171215 84354 171215 85546 171215 85546 171216 84354 171216 85545 171216 85546 171217 85545 171217 84353 171217 85547 171218 85550 171218 85007 171218 85007 171219 85550 171219 92496 171219 85007 171220 92496 171220 85005 171220 85005 171221 92496 171221 85548 171221 85549 171222 85550 171222 85547 171222 86840 171223 85000 171223 92734 171223 92734 171224 85000 171224 85551 171224 92734 171225 85551 171225 86845 171225 86845 171226 85551 171226 85013 171226 86845 171227 85013 171227 85552 171227 85552 171228 85013 171228 92218 171228 85552 171229 92218 171229 85553 171229 85553 171230 92218 171230 85554 171230 85553 171231 85554 171231 85555 171231 85555 171232 85554 171232 85010 171232 85555 171233 85010 171233 85556 171233 85556 171234 85010 171234 85009 171234 85556 171235 85009 171235 86834 171235 86834 171236 85009 171236 85035 171236 86834 171237 85035 171237 86883 171237 86883 171238 85035 171238 92145 171238 86883 171239 92145 171239 86902 171239 85547 171240 85008 171240 85549 171240 85549 171241 85008 171241 92504 171241 85549 171242 92504 171242 85557 171242 85557 171243 92504 171243 85558 171243 85557 171244 85558 171244 86840 171244 86840 171245 85558 171245 85559 171245 86840 171246 85559 171246 85000 171246 85101 171247 92838 171247 85560 171247 85560 171248 92838 171248 85562 171248 85560 171249 85562 171249 85561 171249 85561 171250 85562 171250 92841 171250 85561 171251 92841 171251 85103 171251 85103 171252 92841 171252 85563 171252 85103 171253 85563 171253 85564 171253 85564 171254 85563 171254 86914 171254 85564 171255 86914 171255 85565 171255 85565 171256 86914 171256 92818 171256 85565 171257 92818 171257 85566 171257 85566 171258 92818 171258 86922 171258 85566 171259 86922 171259 85567 171259 85567 171260 86922 171260 86921 171260 85567 171261 86921 171261 92515 171261 92515 171262 86921 171262 86920 171262 92515 171263 86920 171263 85568 171263 85568 171264 86920 171264 86919 171264 85568 171265 86919 171265 92035 171265 92035 171266 86919 171266 92516 171266 92035 171267 92516 171267 85134 171267 85134 171268 92516 171268 86924 171268 85134 171269 86924 171269 85117 171269 85117 171270 86924 171270 92518 171270 92804 171271 85569 171271 85096 171271 85096 171272 85569 171272 85098 171272 85098 171273 85569 171273 85099 171273 85099 171274 85569 171274 92523 171274 85099 171275 92523 171275 85570 171275 92597 171276 85571 171276 85572 171276 85572 171277 85571 171277 86264 171277 85572 171278 86264 171278 92528 171278 92528 171279 86264 171279 86263 171279 92528 171280 86263 171280 85573 171280 85573 171281 86263 171281 92804 171281 85573 171282 92804 171282 85574 171282 85574 171283 92804 171283 85096 171283 92838 171284 85101 171284 86918 171284 86918 171285 85101 171285 85575 171285 86918 171286 85575 171286 86910 171286 86910 171287 85575 171287 85570 171287 86910 171288 85570 171288 85576 171288 85576 171289 85570 171289 92523 171289 84561 171290 92578 171290 85577 171290 85577 171291 92578 171291 92597 171291 85577 171292 92597 171292 85578 171292 85578 171293 92597 171293 85572 171293 85078 171294 85580 171294 85579 171294 85579 171295 85580 171295 92723 171295 85579 171296 92723 171296 85080 171296 85080 171297 92723 171297 85581 171297 85080 171298 85581 171298 84997 171298 84997 171299 85581 171299 85582 171299 84997 171300 85582 171300 84999 171300 84999 171301 85582 171301 85584 171301 84999 171302 85584 171302 85583 171302 85583 171303 85584 171303 86837 171303 85583 171304 86837 171304 85585 171304 85585 171305 86837 171305 85586 171305 85585 171306 85586 171306 84996 171306 84996 171307 85586 171307 86902 171307 84996 171308 86902 171308 92145 171308 85591 171309 85592 171309 85112 171309 85112 171310 85592 171310 86930 171310 85112 171311 86930 171311 85587 171311 85587 171312 86930 171312 85593 171312 85587 171313 85593 171313 92544 171313 92544 171314 85593 171314 85111 171314 85117 171315 92518 171315 85116 171315 85116 171316 92518 171316 86927 171316 85116 171317 86927 171317 85115 171317 85115 171318 86927 171318 85588 171318 85115 171319 85588 171319 92538 171319 92538 171320 85588 171320 85589 171320 92538 171321 85589 171321 85178 171321 85178 171322 85589 171322 85590 171322 85178 171323 85590 171323 85591 171323 85591 171324 85590 171324 86929 171324 85591 171325 86929 171325 85592 171325 85111 171326 85593 171326 85594 171326 85594 171327 85593 171327 85595 171327 85594 171328 85595 171328 85596 171328 85596 171329 85595 171329 92845 171329 85596 171330 92845 171330 85597 171330 85597 171331 92845 171331 86894 171331 85597 171332 86894 171332 85078 171332 85078 171333 86894 171333 86881 171333 85078 171334 86881 171334 85580 171334 85637 171335 85615 171335 87653 171335 87653 171336 85615 171336 85598 171336 87653 171337 85598 171337 85599 171337 85599 171338 85598 171338 85600 171338 85600 171339 85598 171339 87665 171339 87665 171340 85598 171340 85601 171340 87665 171341 85601 171341 87667 171341 87667 171342 85601 171342 87668 171342 87668 171343 85601 171343 85620 171343 87668 171344 85620 171344 85602 171344 85602 171345 85620 171345 85603 171345 85603 171346 85620 171346 85622 171346 85603 171347 85622 171347 87681 171347 85614 171348 85604 171348 85613 171348 85638 171349 85609 171349 85616 171349 85605 171350 85606 171350 87602 171350 87602 171351 85606 171351 85662 171351 85616 171352 85609 171352 85611 171352 85662 171353 85664 171353 87602 171353 87602 171354 85664 171354 85607 171354 87602 171355 85607 171355 87603 171355 85607 171356 85608 171356 87603 171356 87603 171357 85608 171357 85666 171357 87603 171358 85666 171358 85609 171358 85609 171359 85666 171359 85610 171359 85609 171360 85610 171360 85611 171360 85618 171361 85619 171361 85613 171361 85613 171362 85619 171362 85612 171362 85613 171363 85612 171363 85614 171363 85687 171364 85615 171364 85688 171364 85688 171365 85615 171365 85638 171365 85688 171366 85638 171366 85617 171366 85617 171367 85638 171367 85616 171367 85617 171368 85616 171368 85618 171368 85618 171369 85616 171369 85675 171369 85618 171370 85675 171370 85619 171370 85687 171371 85629 171371 85630 171371 85622 171372 85620 171372 85601 171372 85630 171373 85626 171373 85687 171373 85687 171374 85626 171374 85621 171374 85687 171375 85621 171375 85615 171375 85615 171376 85621 171376 85622 171376 85615 171377 85622 171377 85598 171377 85598 171378 85622 171378 85601 171378 85621 171379 87685 171379 85622 171379 85622 171380 87685 171380 85623 171380 85622 171381 85623 171381 87681 171381 87685 171382 85621 171382 85624 171382 85624 171383 85621 171383 85626 171383 85630 171384 85625 171384 85626 171384 85626 171385 85625 171385 85627 171385 85626 171386 85627 171386 85624 171386 85633 171387 85628 171387 85629 171387 85629 171388 85628 171388 85631 171388 85629 171389 85631 171389 85630 171389 85630 171390 85631 171390 85632 171390 85630 171391 85632 171391 85625 171391 85633 171392 85629 171392 85634 171392 85634 171393 85629 171393 85687 171393 85634 171394 85687 171394 87729 171394 87659 171395 84062 171395 84061 171395 87198 171396 87196 171396 87650 171396 84061 171397 87192 171397 87659 171397 87659 171398 87192 171398 85635 171398 87659 171399 85635 171399 87650 171399 87650 171400 85635 171400 85636 171400 87650 171401 85636 171401 87198 171401 85615 171402 85637 171402 85638 171402 85638 171403 85637 171403 87647 171403 85638 171404 87647 171404 85639 171404 85639 171405 87647 171405 85640 171405 85639 171406 85640 171406 85642 171406 85642 171407 85640 171407 85641 171407 85642 171408 85641 171408 87641 171408 87641 171409 87642 171409 85642 171409 85642 171410 87642 171410 87645 171410 85642 171411 87645 171411 87646 171411 85643 171412 87597 171412 85653 171412 87598 171413 85644 171413 85645 171413 85648 171414 85646 171414 85649 171414 85647 171415 85726 171415 85660 171415 85648 171416 85649 171416 85644 171416 87598 171417 85645 171417 87597 171417 85643 171418 85653 171418 85605 171418 85644 171419 85649 171419 85645 171419 85645 171420 85649 171420 85719 171420 85645 171421 85719 171421 85650 171421 85650 171422 85719 171422 85720 171422 85650 171423 85720 171423 85654 171423 85654 171424 85720 171424 85725 171424 85654 171425 85725 171425 85656 171425 85725 171426 85724 171426 85656 171426 85656 171427 85724 171427 85729 171427 85656 171428 85729 171428 85657 171428 85657 171429 85729 171429 85651 171429 85657 171430 85651 171430 85652 171430 85652 171431 85651 171431 85647 171431 85652 171432 85647 171432 85659 171432 85659 171433 85647 171433 85660 171433 87597 171434 85645 171434 85653 171434 85653 171435 85645 171435 85650 171435 85653 171436 85650 171436 85661 171436 85661 171437 85650 171437 85654 171437 85661 171438 85654 171438 85663 171438 85663 171439 85654 171439 85656 171439 85663 171440 85656 171440 85655 171440 85655 171441 85656 171441 85657 171441 85655 171442 85657 171442 85665 171442 85665 171443 85657 171443 85652 171443 85665 171444 85652 171444 85658 171444 85658 171445 85652 171445 85659 171445 85658 171446 85659 171446 85667 171446 85667 171447 85659 171447 85660 171447 85667 171448 85660 171448 85668 171448 85605 171449 85653 171449 85606 171449 85606 171450 85653 171450 85661 171450 85606 171451 85661 171451 85662 171451 85662 171452 85661 171452 85663 171452 85662 171453 85663 171453 85664 171453 85664 171454 85663 171454 85655 171454 85664 171455 85655 171455 85607 171455 85607 171456 85655 171456 85665 171456 85607 171457 85665 171457 85608 171457 85608 171458 85665 171458 85658 171458 85608 171459 85658 171459 85666 171459 85666 171460 85658 171460 85667 171460 85666 171461 85667 171461 85610 171461 85610 171462 85667 171462 85668 171462 85610 171463 85668 171463 85611 171463 87190 171464 84061 171464 85816 171464 84061 171465 87190 171465 87192 171465 84210 171466 87704 171466 87710 171466 85694 171467 84210 171467 85669 171467 85669 171468 84210 171468 87710 171468 85669 171469 87710 171469 85670 171469 87744 171470 87428 171470 85670 171470 85670 171471 87428 171471 87429 171471 85670 171472 87429 171472 85669 171472 87715 171473 85604 171473 85614 171473 85681 171474 85660 171474 85726 171474 85616 171475 85611 171475 85668 171475 85673 171476 87716 171476 87715 171476 85671 171477 87713 171477 87718 171477 87713 171478 85671 171478 85672 171478 87715 171479 85614 171479 85673 171479 85673 171480 85614 171480 85612 171480 85673 171481 85612 171481 85674 171481 85674 171482 85612 171482 85619 171482 85674 171483 85619 171483 85678 171483 85678 171484 85619 171484 85675 171484 85678 171485 85675 171485 85676 171485 85676 171486 85675 171486 85616 171486 85676 171487 85616 171487 85677 171487 85677 171488 85616 171488 85668 171488 85677 171489 85668 171489 85660 171489 85660 171490 85681 171490 85677 171490 85677 171491 85681 171491 85683 171491 85677 171492 85683 171492 85676 171492 85676 171493 85683 171493 85679 171493 85676 171494 85679 171494 85678 171494 85678 171495 85679 171495 85680 171495 85678 171496 85680 171496 85674 171496 85674 171497 85680 171497 85671 171497 85674 171498 85671 171498 85673 171498 85673 171499 85671 171499 87718 171499 85673 171500 87718 171500 87716 171500 85726 171501 86072 171501 85681 171501 85681 171502 86072 171502 85682 171502 85681 171503 85682 171503 85683 171503 85683 171504 85682 171504 86073 171504 85683 171505 86073 171505 85679 171505 85679 171506 86073 171506 85684 171506 85679 171507 85684 171507 85680 171507 85680 171508 85684 171508 86077 171508 85680 171509 86077 171509 85671 171509 85671 171510 86077 171510 87714 171510 85671 171511 87714 171511 85672 171511 87728 171512 87729 171512 85687 171512 85689 171513 87728 171513 85685 171513 85685 171514 87728 171514 85686 171514 85686 171515 87728 171515 85687 171515 85686 171516 85687 171516 85688 171516 85689 171517 85685 171517 85690 171517 85690 171518 85685 171518 85691 171518 85690 171519 85691 171519 85692 171519 85693 171520 84208 171520 87414 171520 87414 171521 84208 171521 84210 171521 87414 171522 84210 171522 85694 171522 85695 171523 87164 171523 85741 171523 86309 171524 85701 171524 85702 171524 85732 171525 86093 171525 86071 171525 86270 171526 85733 171526 86272 171526 86272 171527 85733 171527 85731 171527 86272 171528 85731 171528 86273 171528 85721 171529 85722 171529 85696 171529 85696 171530 85722 171530 85697 171530 85696 171531 85697 171531 86304 171531 86304 171532 85697 171532 85734 171532 86304 171533 85734 171533 85698 171533 85698 171534 85734 171534 85699 171534 85698 171535 85699 171535 85700 171535 85701 171536 86309 171536 85699 171536 85699 171537 86309 171537 86308 171537 85699 171538 86308 171538 85700 171538 85739 171539 85705 171539 85702 171539 85702 171540 85705 171540 86310 171540 85702 171541 86310 171541 86309 171541 86292 171542 85703 171542 85739 171542 85739 171543 85703 171543 85704 171543 85739 171544 85704 171544 85705 171544 87157 171545 85706 171545 86281 171545 85739 171546 85740 171546 86292 171546 86292 171547 85740 171547 85741 171547 86292 171548 85741 171548 86281 171548 86281 171549 85741 171549 87164 171549 86281 171550 87164 171550 87157 171550 87173 171551 85708 171551 85707 171551 85707 171552 85708 171552 85743 171552 85707 171553 85743 171553 85742 171553 85727 171554 85709 171554 87175 171554 87175 171555 85709 171555 85710 171555 87175 171556 85710 171556 87176 171556 87176 171557 85710 171557 85711 171557 85711 171558 85710 171558 85712 171558 85712 171559 85710 171559 85713 171559 85712 171560 85713 171560 85717 171560 87204 171561 85715 171561 85714 171561 85714 171562 85715 171562 87205 171562 85714 171563 87205 171563 85713 171563 85713 171564 87205 171564 85716 171564 85713 171565 85716 171565 85717 171565 85714 171566 85718 171566 87204 171566 87204 171567 85718 171567 87604 171567 87204 171568 87604 171568 87623 171568 85646 171569 85734 171569 85649 171569 85649 171570 85734 171570 85697 171570 85649 171571 85697 171571 85719 171571 85719 171572 85697 171572 85722 171572 85719 171573 85722 171573 85720 171573 85720 171574 85722 171574 85725 171574 85723 171575 85729 171575 85724 171575 86273 171576 85731 171576 85721 171576 85721 171577 85731 171577 85723 171577 85721 171578 85723 171578 85722 171578 85722 171579 85723 171579 85724 171579 85722 171580 85724 171580 85725 171580 85729 171581 85730 171581 85651 171581 85651 171582 85730 171582 85732 171582 85651 171583 85732 171583 85647 171583 85647 171584 85732 171584 86071 171584 85647 171585 86071 171585 85726 171585 85727 171586 87173 171586 85709 171586 85709 171587 87173 171587 85707 171587 85709 171588 85707 171588 85710 171588 85710 171589 85707 171589 85728 171589 85710 171590 85728 171590 85713 171590 85713 171591 85728 171591 85738 171591 85713 171592 85738 171592 85714 171592 85714 171593 85738 171593 85737 171593 85714 171594 85737 171594 85718 171594 85718 171595 85737 171595 85736 171595 85718 171596 85736 171596 87604 171596 87604 171597 85736 171597 85735 171597 87604 171598 85735 171598 87600 171598 85729 171599 85723 171599 85730 171599 85730 171600 85723 171600 85731 171600 85730 171601 85731 171601 85732 171601 85732 171602 85731 171602 85733 171602 85732 171603 85733 171603 86093 171603 86093 171604 85733 171604 86270 171604 86093 171605 86270 171605 86269 171605 85646 171606 87600 171606 85734 171606 85734 171607 87600 171607 85735 171607 85734 171608 85735 171608 85699 171608 85699 171609 85735 171609 85736 171609 85699 171610 85736 171610 85701 171610 85701 171611 85736 171611 85737 171611 85701 171612 85737 171612 85702 171612 85702 171613 85737 171613 85738 171613 85702 171614 85738 171614 85739 171614 85739 171615 85738 171615 85728 171615 85739 171616 85728 171616 85740 171616 85740 171617 85728 171617 85707 171617 85740 171618 85707 171618 85741 171618 85741 171619 85707 171619 85742 171619 85741 171620 85742 171620 85695 171620 85695 171621 85742 171621 85743 171621 85789 171622 85790 171622 85814 171622 85767 171623 85792 171623 85823 171623 84085 171624 85772 171624 85787 171624 85754 171625 85895 171625 85753 171625 85830 171626 85744 171626 85745 171626 85830 171627 85745 171627 85828 171627 85828 171628 85745 171628 85746 171628 85828 171629 85746 171629 85832 171629 85832 171630 85746 171630 85833 171630 85833 171631 85746 171631 85747 171631 85833 171632 85747 171632 85748 171632 85748 171633 85747 171633 85750 171633 85748 171634 85750 171634 85749 171634 85749 171635 85750 171635 85751 171635 85751 171636 85750 171636 85804 171636 85751 171637 85804 171637 85837 171637 85837 171638 85804 171638 85836 171638 85836 171639 85804 171639 85752 171639 85836 171640 85752 171640 85835 171640 85752 171641 85803 171641 85835 171641 85835 171642 85803 171642 85802 171642 85835 171643 85802 171643 85753 171643 85755 171644 85897 171644 85754 171644 85754 171645 85897 171645 85896 171645 85754 171646 85896 171646 85895 171646 85753 171647 85802 171647 85754 171647 85754 171648 85802 171648 85894 171648 85754 171649 85894 171649 85755 171649 85756 171650 85891 171650 85757 171650 85757 171651 85891 171651 85758 171651 85793 171652 85794 171652 85759 171652 85759 171653 85794 171653 85809 171653 85759 171654 85809 171654 85940 171654 85808 171655 85760 171655 85890 171655 85890 171656 85760 171656 85761 171656 85890 171657 85761 171657 85781 171657 85926 171658 85780 171658 85889 171658 85889 171659 85780 171659 85779 171659 85782 171660 85783 171660 85886 171660 85886 171661 85783 171661 85887 171661 85887 171662 85783 171662 85762 171662 85762 171663 85783 171663 85785 171663 85762 171664 85785 171664 85771 171664 85884 171665 85770 171665 85881 171665 85881 171666 85770 171666 85763 171666 85881 171667 85763 171667 84089 171667 84089 171668 85763 171668 85764 171668 84089 171669 85764 171669 84092 171669 84092 171670 85764 171670 84093 171670 85788 171671 85766 171671 84083 171671 85774 171672 88106 171672 85766 171672 84083 171673 85766 171673 85765 171673 85765 171674 85766 171674 88106 171674 85765 171675 88106 171675 84084 171675 88110 171676 88109 171676 85773 171676 85792 171677 85767 171677 85791 171677 85791 171678 85767 171678 85768 171678 85791 171679 85768 171679 85769 171679 85884 171680 85771 171680 85770 171680 85770 171681 85771 171681 85785 171681 85770 171682 85785 171682 85763 171682 85763 171683 85785 171683 85786 171683 85763 171684 85786 171684 85764 171684 85764 171685 85786 171685 85787 171685 85764 171686 85787 171686 84093 171686 84093 171687 85787 171687 85772 171687 88109 171688 85774 171688 85773 171688 85773 171689 85774 171689 85766 171689 85773 171690 85766 171690 85815 171690 85815 171691 85766 171691 85788 171691 85815 171692 85788 171692 85813 171692 85813 171693 85788 171693 85775 171693 85813 171694 85775 171694 85811 171694 85811 171695 85775 171695 85777 171695 85811 171696 85777 171696 85776 171696 85776 171697 85777 171697 85784 171697 85776 171698 85784 171698 85778 171698 85778 171699 85784 171699 85779 171699 85778 171700 85779 171700 85761 171700 85761 171701 85779 171701 85780 171701 85761 171702 85780 171702 85781 171702 85781 171703 85780 171703 85926 171703 85886 171704 85889 171704 85782 171704 85782 171705 85889 171705 85779 171705 85782 171706 85779 171706 85783 171706 85783 171707 85779 171707 85784 171707 85783 171708 85784 171708 85785 171708 85785 171709 85784 171709 85777 171709 85785 171710 85777 171710 85786 171710 85786 171711 85777 171711 85775 171711 85786 171712 85775 171712 85787 171712 85787 171713 85775 171713 85788 171713 85787 171714 85788 171714 84085 171714 84085 171715 85788 171715 84083 171715 85789 171716 85814 171716 85801 171716 85769 171717 85790 171717 85791 171717 85791 171718 85790 171718 85789 171718 85791 171719 85789 171719 85792 171719 85792 171720 85789 171720 85801 171720 85792 171721 85801 171721 85823 171721 85823 171722 85801 171722 85824 171722 85793 171723 85891 171723 85794 171723 85794 171724 85891 171724 85756 171724 85794 171725 85756 171725 85809 171725 85809 171726 85756 171726 85796 171726 85809 171727 85796 171727 85795 171727 85795 171728 85796 171728 85797 171728 85795 171729 85797 171729 85810 171729 85810 171730 85797 171730 85805 171730 85810 171731 85805 171731 85812 171731 85812 171732 85805 171732 85798 171732 85812 171733 85798 171733 85799 171733 85799 171734 85798 171734 85800 171734 85799 171735 85800 171735 85814 171735 85814 171736 85800 171736 85806 171736 85814 171737 85806 171737 85801 171737 85801 171738 85806 171738 85807 171738 85801 171739 85807 171739 85824 171739 85758 171740 85894 171740 85757 171740 85757 171741 85894 171741 85802 171741 85757 171742 85802 171742 85756 171742 85756 171743 85802 171743 85803 171743 85756 171744 85803 171744 85796 171744 85796 171745 85803 171745 85752 171745 85796 171746 85752 171746 85797 171746 85797 171747 85752 171747 85804 171747 85797 171748 85804 171748 85805 171748 85805 171749 85804 171749 85750 171749 85805 171750 85750 171750 85798 171750 85798 171751 85750 171751 85747 171751 85798 171752 85747 171752 85800 171752 85800 171753 85747 171753 85746 171753 85800 171754 85746 171754 85806 171754 85806 171755 85746 171755 85745 171755 85806 171756 85745 171756 85807 171756 85807 171757 85745 171757 85744 171757 85808 171758 85940 171758 85760 171758 85760 171759 85940 171759 85809 171759 85760 171760 85809 171760 85761 171760 85761 171761 85809 171761 85795 171761 85761 171762 85795 171762 85778 171762 85778 171763 85795 171763 85810 171763 85778 171764 85810 171764 85776 171764 85776 171765 85810 171765 85812 171765 85776 171766 85812 171766 85811 171766 85811 171767 85812 171767 85799 171767 85811 171768 85799 171768 85813 171768 85813 171769 85799 171769 85814 171769 85813 171770 85814 171770 85815 171770 85815 171771 85814 171771 85790 171771 85815 171772 85790 171772 85773 171772 85773 171773 85790 171773 85769 171773 85773 171774 85769 171774 88110 171774 88110 171775 85769 171775 85768 171775 84061 171776 84060 171776 85816 171776 85816 171777 84060 171777 85817 171777 85816 171778 85817 171778 85818 171778 85818 171779 85817 171779 88082 171779 88076 171780 85820 171780 85819 171780 88082 171781 88081 171781 85818 171781 85818 171782 88081 171782 88067 171782 85818 171783 88067 171783 87189 171783 88076 171784 85819 171784 88067 171784 88067 171785 85819 171785 87185 171785 88067 171786 87185 171786 87189 171786 88074 171787 88068 171787 85767 171787 88068 171788 88098 171788 85767 171788 85767 171789 88098 171789 88096 171789 85767 171790 88096 171790 85768 171790 87168 171791 87170 171791 85767 171791 85820 171792 88074 171792 85819 171792 85819 171793 88074 171793 85767 171793 85819 171794 85767 171794 85821 171794 85821 171795 85767 171795 87170 171795 87168 171796 85767 171796 87166 171796 87166 171797 85767 171797 85823 171797 87166 171798 85823 171798 85822 171798 85822 171799 85823 171799 85824 171799 85822 171800 85824 171800 85825 171800 85824 171801 85807 171801 85825 171801 85825 171802 85807 171802 85744 171802 85825 171803 85744 171803 85826 171803 85826 171804 85744 171804 85830 171804 87135 171805 85827 171805 85828 171805 85828 171806 85827 171806 85829 171806 85828 171807 85829 171807 85830 171807 85830 171808 85829 171808 85831 171808 85830 171809 85831 171809 85826 171809 85828 171810 85832 171810 87135 171810 87135 171811 85832 171811 85833 171811 87135 171812 85833 171812 85834 171812 85834 171813 85833 171813 85748 171813 85834 171814 85748 171814 87154 171814 87154 171815 85748 171815 87146 171815 85748 171816 85749 171816 87146 171816 87146 171817 85749 171817 85751 171817 87146 171818 85751 171818 87147 171818 87147 171819 85751 171819 85837 171819 87147 171820 85837 171820 87144 171820 85753 171821 87141 171821 85835 171821 85835 171822 87141 171822 87144 171822 85835 171823 87144 171823 85836 171823 85836 171824 87144 171824 85837 171824 85849 171825 86224 171825 85846 171825 85838 171826 85840 171826 85859 171826 85859 171827 85840 171827 85839 171827 85839 171828 85840 171828 84117 171828 85839 171829 84117 171829 85977 171829 85841 171830 85842 171830 85843 171830 85843 171831 85842 171831 85838 171831 85843 171832 85838 171832 85844 171832 85855 171833 85845 171833 85856 171833 85846 171834 85847 171834 85849 171834 85849 171835 85847 171835 85848 171835 85849 171836 85848 171836 85850 171836 85850 171837 85848 171837 85867 171837 85850 171838 85867 171838 85851 171838 85853 171839 86224 171839 85855 171839 85855 171840 86224 171840 85849 171840 85855 171841 85849 171841 85845 171841 85845 171842 85849 171842 85850 171842 85845 171843 85850 171843 85858 171843 85858 171844 85850 171844 85851 171844 85858 171845 85851 171845 85844 171845 85852 171846 85853 171846 85854 171846 85854 171847 85853 171847 85855 171847 85854 171848 85855 171848 85960 171848 85960 171849 85855 171849 85856 171849 85960 171850 85856 171850 86010 171850 86010 171851 85856 171851 85857 171851 85844 171852 85838 171852 85858 171852 85858 171853 85838 171853 85859 171853 85858 171854 85859 171854 85845 171854 85845 171855 85859 171855 85839 171855 85845 171856 85839 171856 85856 171856 85856 171857 85839 171857 85977 171857 85856 171858 85977 171858 85857 171858 85870 171859 85863 171859 85860 171859 85861 171860 85873 171860 85862 171860 85874 171861 85861 171861 85860 171861 84091 171862 85863 171862 85864 171862 85864 171863 85863 171863 85870 171863 85864 171864 85870 171864 84088 171864 85875 171865 85841 171865 85843 171865 85875 171866 85843 171866 85865 171866 85843 171867 85844 171867 85865 171867 85865 171868 85844 171868 85851 171868 85865 171869 85851 171869 85866 171869 85866 171870 85851 171870 85867 171870 85866 171871 85867 171871 85848 171871 85880 171872 85860 171872 85868 171872 85868 171873 85860 171873 85861 171873 85868 171874 85861 171874 85869 171874 85869 171875 85861 171875 85862 171875 84089 171876 84088 171876 85882 171876 85882 171877 84088 171877 85870 171877 85882 171878 85870 171878 85871 171878 85871 171879 85870 171879 85860 171879 85871 171880 85860 171880 85872 171880 85872 171881 85860 171881 85880 171881 85873 171882 85861 171882 86222 171882 86222 171883 85861 171883 85874 171883 86222 171884 85874 171884 86196 171884 86196 171885 85874 171885 85847 171885 86196 171886 85847 171886 85846 171886 84091 171887 85875 171887 85863 171887 85863 171888 85875 171888 85865 171888 85863 171889 85865 171889 85860 171889 85860 171890 85865 171890 85866 171890 85860 171891 85866 171891 85874 171891 85874 171892 85866 171892 85848 171892 85874 171893 85848 171893 85847 171893 86221 171894 85876 171894 85914 171894 85914 171895 85876 171895 86195 171895 85908 171896 85957 171896 85955 171896 86238 171897 86237 171897 85958 171897 85935 171898 86243 171898 85877 171898 85759 171899 85878 171899 85938 171899 85869 171900 85862 171900 86220 171900 85871 171901 85872 171901 85879 171901 85879 171902 85872 171902 85880 171902 85883 171903 85888 171903 85771 171903 84089 171904 85882 171904 85881 171904 85881 171905 85882 171905 85883 171905 85881 171906 85883 171906 85884 171906 85884 171907 85883 171907 85771 171907 85885 171908 85886 171908 85949 171908 85949 171909 85886 171909 85887 171909 85949 171910 85887 171910 85888 171910 85888 171911 85887 171911 85762 171911 85888 171912 85762 171912 85771 171912 85928 171913 85926 171913 85885 171913 85885 171914 85926 171914 85889 171914 85885 171915 85889 171915 85886 171915 85940 171916 85808 171916 85939 171916 85939 171917 85808 171917 85890 171917 85939 171918 85890 171918 85781 171918 85758 171919 85891 171919 85938 171919 85938 171920 85891 171920 85793 171920 85938 171921 85793 171921 85759 171921 85938 171922 85892 171922 85758 171922 85758 171923 85892 171923 85893 171923 85758 171924 85893 171924 85894 171924 85894 171925 85893 171925 85936 171925 85894 171926 85936 171926 85755 171926 85755 171927 85936 171927 85877 171927 85755 171928 85877 171928 85897 171928 86243 171929 85895 171929 85877 171929 85877 171930 85895 171930 85896 171930 85877 171931 85896 171931 85897 171931 86241 171932 85959 171932 85898 171932 85898 171933 85959 171933 85899 171933 85903 171934 85900 171934 85904 171934 85904 171935 85900 171935 85901 171935 85904 171936 85901 171936 86238 171936 86230 171937 86231 171937 85907 171937 85907 171938 86231 171938 85902 171938 85907 171939 85902 171939 85903 171939 85903 171940 85902 171940 86240 171940 85903 171941 86240 171941 85900 171941 86238 171942 85958 171942 85904 171942 85904 171943 85958 171943 85957 171943 85904 171944 85957 171944 85903 171944 85903 171945 85957 171945 85908 171945 85903 171946 85908 171946 85907 171946 86229 171947 86230 171947 85905 171947 85905 171948 86230 171948 85907 171948 85905 171949 85907 171949 85906 171949 85906 171950 85907 171950 85908 171950 85906 171951 85908 171951 85919 171951 85919 171952 85908 171952 85955 171952 85919 171953 85955 171953 85920 171953 85920 171954 85955 171954 85954 171954 85920 171955 85954 171955 85909 171955 85909 171956 85954 171956 85952 171956 85909 171957 85952 171957 85910 171957 85910 171958 85952 171958 85951 171958 85910 171959 85951 171959 85923 171959 85923 171960 85951 171960 85950 171960 85923 171961 85950 171961 85911 171961 85868 171962 85869 171962 85912 171962 85912 171963 85869 171963 86220 171963 85912 171964 86220 171964 85913 171964 85913 171965 86220 171965 85941 171965 85913 171966 85941 171966 85942 171966 86195 171967 85918 171967 85914 171967 85914 171968 85918 171968 85915 171968 85914 171969 85915 171969 85947 171969 85947 171970 85915 171970 85917 171970 85947 171971 85917 171971 85916 171971 85916 171972 85917 171972 85921 171972 85916 171973 85921 171973 85946 171973 85946 171974 85921 171974 85922 171974 85946 171975 85922 171975 85943 171975 85943 171976 85922 171976 85924 171976 85943 171977 85924 171977 85942 171977 86193 171978 86229 171978 86195 171978 86195 171979 86229 171979 85905 171979 86195 171980 85905 171980 85918 171980 85918 171981 85905 171981 85906 171981 85918 171982 85906 171982 85915 171982 85915 171983 85906 171983 85919 171983 85915 171984 85919 171984 85917 171984 85917 171985 85919 171985 85920 171985 85917 171986 85920 171986 85921 171986 85921 171987 85920 171987 85909 171987 85921 171988 85909 171988 85922 171988 85922 171989 85909 171989 85910 171989 85922 171990 85910 171990 85924 171990 85924 171991 85910 171991 85923 171991 85924 171992 85923 171992 85942 171992 85942 171993 85923 171993 85911 171993 85942 171994 85911 171994 85913 171994 85913 171995 85911 171995 85925 171995 85913 171996 85925 171996 85912 171996 85912 171997 85925 171997 85879 171997 85912 171998 85879 171998 85868 171998 85868 171999 85879 171999 85880 171999 85781 172000 85926 172000 85939 172000 85939 172001 85926 172001 85928 172001 85939 172002 85928 172002 85927 172002 85927 172003 85928 172003 85929 172003 85927 172004 85929 172004 85937 172004 85937 172005 85929 172005 85930 172005 85937 172006 85930 172006 85931 172006 85931 172007 85930 172007 85953 172007 85931 172008 85953 172008 85932 172008 85932 172009 85953 172009 85956 172009 85932 172010 85956 172010 85933 172010 85933 172011 85956 172011 85934 172011 85933 172012 85934 172012 85959 172012 86241 172013 85935 172013 85959 172013 85959 172014 85935 172014 85877 172014 85959 172015 85877 172015 85933 172015 85933 172016 85877 172016 85936 172016 85933 172017 85936 172017 85932 172017 85932 172018 85936 172018 85893 172018 85932 172019 85893 172019 85931 172019 85931 172020 85893 172020 85892 172020 85931 172021 85892 172021 85937 172021 85937 172022 85892 172022 85938 172022 85937 172023 85938 172023 85927 172023 85927 172024 85938 172024 85878 172024 85927 172025 85878 172025 85939 172025 85939 172026 85878 172026 85759 172026 85939 172027 85759 172027 85940 172027 85941 172028 86218 172028 85942 172028 85942 172029 86218 172029 85944 172029 85942 172030 85944 172030 85943 172030 85943 172031 85944 172031 85945 172031 85943 172032 85945 172032 85946 172032 85946 172033 85945 172033 86217 172033 85946 172034 86217 172034 85916 172034 85916 172035 86217 172035 86216 172035 85916 172036 86216 172036 85947 172036 85947 172037 86216 172037 86219 172037 85947 172038 86219 172038 85914 172038 85914 172039 86219 172039 85948 172039 85914 172040 85948 172040 86221 172040 85882 172041 85871 172041 85883 172041 85883 172042 85871 172042 85879 172042 85883 172043 85879 172043 85888 172043 85888 172044 85879 172044 85925 172044 85888 172045 85925 172045 85949 172045 85949 172046 85925 172046 85911 172046 85949 172047 85911 172047 85885 172047 85885 172048 85911 172048 85950 172048 85885 172049 85950 172049 85928 172049 85928 172050 85950 172050 85951 172050 85928 172051 85951 172051 85929 172051 85929 172052 85951 172052 85952 172052 85929 172053 85952 172053 85930 172053 85930 172054 85952 172054 85954 172054 85930 172055 85954 172055 85953 172055 85953 172056 85954 172056 85955 172056 85953 172057 85955 172057 85956 172057 85956 172058 85955 172058 85957 172058 85956 172059 85957 172059 85934 172059 85934 172060 85957 172060 85958 172060 85934 172061 85958 172061 85959 172061 85959 172062 85958 172062 86237 172062 85959 172063 86237 172063 85899 172063 85960 172064 86010 172064 86009 172064 85857 172065 85977 172065 86008 172065 85993 172066 86184 172066 85994 172066 85981 172067 85961 172067 85962 172067 86019 172068 86190 172068 86021 172068 86181 172069 85963 172069 85964 172069 85964 172070 85963 172070 84174 172070 85987 172071 85965 172071 84174 172071 85987 172072 85988 172072 85965 172072 85965 172073 85988 172073 85990 172073 85965 172074 85990 172074 85966 172074 85966 172075 85990 172075 85967 172075 85966 172076 85967 172076 84165 172076 85968 172077 85969 172077 85970 172077 85970 172078 85969 172078 85971 172078 85970 172079 85971 172079 85991 172079 85991 172080 85971 172080 84126 172080 85991 172081 84126 172081 85967 172081 85967 172082 84126 172082 85972 172082 85967 172083 85972 172083 84165 172083 85973 172084 84124 172084 84153 172084 85973 172085 84153 172085 85970 172085 85970 172086 84153 172086 84125 172086 85970 172087 84125 172087 85968 172087 84124 172088 85973 172088 84122 172088 84122 172089 85973 172089 86005 172089 84122 172090 86005 172090 85974 172090 85974 172091 86005 172091 86006 172091 85974 172092 86006 172092 85975 172092 85975 172093 86006 172093 84118 172093 84118 172094 86006 172094 86008 172094 84118 172095 86008 172095 85976 172095 85976 172096 86008 172096 84120 172096 84120 172097 86008 172097 85977 172097 84120 172098 85977 172098 84117 172098 86012 172099 85978 172099 86041 172099 86041 172100 85978 172100 85852 172100 86041 172101 85852 172101 85854 172101 86013 172102 86205 172102 86015 172102 85979 172103 86186 172103 86020 172103 86020 172104 86186 172104 86188 172104 85961 172105 86185 172105 85962 172105 85962 172106 86185 172106 85980 172106 85962 172107 85980 172107 86034 172107 86184 172108 85981 172108 85994 172108 85994 172109 85981 172109 85962 172109 85994 172110 85962 172110 85995 172110 85995 172111 85962 172111 86034 172111 85995 172112 86034 172112 85997 172112 85997 172113 86034 172113 85982 172113 85982 172114 86034 172114 86037 172114 85982 172115 86037 172115 86001 172115 86001 172116 86037 172116 85983 172116 86001 172117 85983 172117 86002 172117 86002 172118 85983 172118 85984 172118 86002 172119 85984 172119 86004 172119 86004 172120 85984 172120 85986 172120 86004 172121 85986 172121 85985 172121 85985 172122 85986 172122 86039 172122 85985 172123 86039 172123 86040 172123 84174 172124 85963 172124 85987 172124 85987 172125 85963 172125 85996 172125 85987 172126 85996 172126 85988 172126 85988 172127 85996 172127 85989 172127 85988 172128 85989 172128 85990 172128 85990 172129 85989 172129 85998 172129 85990 172130 85998 172130 85967 172130 85967 172131 85998 172131 85999 172131 85967 172132 85999 172132 85991 172132 85991 172133 85999 172133 86000 172133 85991 172134 86000 172134 85970 172134 85970 172135 86000 172135 85992 172135 85970 172136 85992 172136 85973 172136 85973 172137 85992 172137 86003 172137 85973 172138 86003 172138 86005 172138 86181 172139 85993 172139 85963 172139 85963 172140 85993 172140 85994 172140 85963 172141 85994 172141 85996 172141 85996 172142 85994 172142 85995 172142 85996 172143 85995 172143 85989 172143 85989 172144 85995 172144 85997 172144 85989 172145 85997 172145 85998 172145 85998 172146 85997 172146 85982 172146 85998 172147 85982 172147 85999 172147 85999 172148 85982 172148 86001 172148 85999 172149 86001 172149 86000 172149 86000 172150 86001 172150 86002 172150 86000 172151 86002 172151 85992 172151 85992 172152 86002 172152 86004 172152 85992 172153 86004 172153 86003 172153 86003 172154 86004 172154 85985 172154 86003 172155 85985 172155 86005 172155 86005 172156 85985 172156 86040 172156 86005 172157 86040 172157 86006 172157 86006 172158 86040 172158 86007 172158 86006 172159 86007 172159 86008 172159 86008 172160 86007 172160 86009 172160 86008 172161 86009 172161 85857 172161 85857 172162 86009 172162 86010 172162 86033 172163 86223 172163 86012 172163 86012 172164 86223 172164 86011 172164 86012 172165 86011 172165 85978 172165 86013 172166 86015 172166 86014 172166 86014 172167 86015 172167 86204 172167 86014 172168 86204 172168 86027 172168 86027 172169 86204 172169 86016 172169 86027 172170 86016 172170 86028 172170 86028 172171 86016 172171 86225 172171 86028 172172 86225 172172 86029 172172 86029 172173 86225 172173 86226 172173 86029 172174 86226 172174 86018 172174 86018 172175 86226 172175 86017 172175 86018 172176 86017 172176 86031 172176 86188 172177 86019 172177 86020 172177 86020 172178 86019 172178 86021 172178 86020 172179 86021 172179 86035 172179 86035 172180 86021 172180 86022 172180 86035 172181 86022 172181 86036 172181 86036 172182 86022 172182 86023 172182 86036 172183 86023 172183 86024 172183 86024 172184 86023 172184 86025 172184 86024 172185 86025 172185 86038 172185 86038 172186 86025 172186 86030 172186 86038 172187 86030 172187 86026 172187 86190 172188 86013 172188 86021 172188 86021 172189 86013 172189 86014 172189 86021 172190 86014 172190 86022 172190 86022 172191 86014 172191 86027 172191 86022 172192 86027 172192 86023 172192 86023 172193 86027 172193 86028 172193 86023 172194 86028 172194 86025 172194 86025 172195 86028 172195 86029 172195 86025 172196 86029 172196 86030 172196 86030 172197 86029 172197 86018 172197 86030 172198 86018 172198 86026 172198 86026 172199 86018 172199 86031 172199 86026 172200 86031 172200 86032 172200 86032 172201 86031 172201 86228 172201 86032 172202 86228 172202 86033 172202 86033 172203 86228 172203 86227 172203 86033 172204 86227 172204 86223 172204 86185 172205 85979 172205 85980 172205 85980 172206 85979 172206 86020 172206 85980 172207 86020 172207 86034 172207 86034 172208 86020 172208 86035 172208 86034 172209 86035 172209 86037 172209 86037 172210 86035 172210 86036 172210 86037 172211 86036 172211 85983 172211 85983 172212 86036 172212 86024 172212 85983 172213 86024 172213 85984 172213 85984 172214 86024 172214 86038 172214 85984 172215 86038 172215 85986 172215 85986 172216 86038 172216 86026 172216 85986 172217 86026 172217 86039 172217 86039 172218 86026 172218 86032 172218 86039 172219 86032 172219 86040 172219 86040 172220 86032 172220 86033 172220 86040 172221 86033 172221 86007 172221 86007 172222 86033 172222 86012 172222 86007 172223 86012 172223 86009 172223 86009 172224 86012 172224 86041 172224 86009 172225 86041 172225 85960 172225 85960 172226 86041 172226 85854 172226 86087 172227 86094 172227 86086 172227 86071 172228 86093 172228 86092 172228 86059 172229 86096 172229 86068 172229 86042 172230 86043 172230 86044 172230 86045 172231 86046 172231 87422 172231 87410 172232 86047 172232 86050 172232 86050 172233 86047 172233 86048 172233 86050 172234 86048 172234 86046 172234 86046 172235 86048 172235 87416 172235 86046 172236 87416 172236 87422 172236 86080 172237 86049 172237 86082 172237 86082 172238 86049 172238 87406 172238 86082 172239 87406 172239 86050 172239 86050 172240 87406 172240 87407 172240 86050 172241 87407 172241 87410 172241 86043 172242 86042 172242 86081 172242 87375 172243 86051 172243 86054 172243 86054 172244 86051 172244 86052 172244 86052 172245 87402 172245 86054 172245 86054 172246 87402 172246 86053 172246 86054 172247 86053 172247 86055 172247 86055 172248 86053 172248 86057 172248 86055 172249 86057 172249 86056 172249 86056 172250 86057 172250 86097 172250 86056 172251 86097 172251 86058 172251 86096 172252 86059 172252 86097 172252 86097 172253 86059 172253 86060 172253 86097 172254 86060 172254 86058 172254 86061 172255 86090 172255 86074 172255 86074 172256 86090 172256 86062 172256 86074 172257 86062 172257 86075 172257 86075 172258 86062 172258 86063 172258 86075 172259 86063 172259 86076 172259 86076 172260 86063 172260 86065 172260 86076 172261 86065 172261 86064 172261 86064 172262 86065 172262 86066 172262 86064 172263 86066 172263 86095 172263 86095 172264 86066 172264 86067 172264 86095 172265 86067 172265 86068 172265 86068 172266 86067 172266 86069 172266 86068 172267 86069 172267 86059 172267 86115 172268 86089 172268 86070 172268 86070 172269 86089 172269 86091 172269 86070 172270 86091 172270 86120 172270 85726 172271 86071 172271 86072 172271 86072 172272 86071 172272 86092 172272 86072 172273 86092 172273 85682 172273 85682 172274 86092 172274 86061 172274 85682 172275 86061 172275 86073 172275 86073 172276 86061 172276 86074 172276 86073 172277 86074 172277 85684 172277 85684 172278 86074 172278 86075 172278 85684 172279 86075 172279 86077 172279 86077 172280 86075 172280 86076 172280 86077 172281 86076 172281 87714 172281 87714 172282 86076 172282 86064 172282 87714 172283 86064 172283 87721 172283 86088 172284 86078 172284 86079 172284 86079 172285 86078 172285 86045 172285 86079 172286 86045 172286 87421 172286 87421 172287 86045 172287 87422 172287 86042 172288 86080 172288 86081 172288 86081 172289 86080 172289 86082 172289 86081 172290 86082 172290 86083 172290 86083 172291 86082 172291 86050 172291 86083 172292 86050 172292 86084 172292 86084 172293 86050 172293 86046 172293 86084 172294 86046 172294 86085 172294 86085 172295 86046 172295 86045 172295 86085 172296 86045 172296 86086 172296 86086 172297 86045 172297 86078 172297 86086 172298 86078 172298 86087 172298 86087 172299 86078 172299 86088 172299 86087 172300 86088 172300 87726 172300 86115 172301 86090 172301 86089 172301 86089 172302 86090 172302 86061 172302 86089 172303 86061 172303 86091 172303 86091 172304 86061 172304 86092 172304 86091 172305 86092 172305 86120 172305 86120 172306 86092 172306 86093 172306 86120 172307 86093 172307 86269 172307 86087 172308 87721 172308 86094 172308 86094 172309 87721 172309 86064 172309 86094 172310 86064 172310 86086 172310 86086 172311 86064 172311 86095 172311 86086 172312 86095 172312 86085 172312 86085 172313 86095 172313 86068 172313 86085 172314 86068 172314 86084 172314 86084 172315 86068 172315 86096 172315 86084 172316 86096 172316 86083 172316 86083 172317 86096 172317 86097 172317 86083 172318 86097 172318 86081 172318 86081 172319 86097 172319 86057 172319 86081 172320 86057 172320 86043 172320 86043 172321 86057 172321 86053 172321 86043 172322 86053 172322 86044 172322 86044 172323 86053 172323 87402 172323 86128 172324 86098 172324 86279 172324 86335 172325 86139 172325 86138 172325 86120 172326 86269 172326 86271 172326 86099 172327 86134 172327 86133 172327 87347 172328 92486 172328 87344 172328 87344 172329 92486 172329 85546 172329 87344 172330 85546 172330 87343 172330 87343 172331 85546 172331 92686 172331 87343 172332 92686 172332 87323 172332 87347 172333 87348 172333 92486 172333 92486 172334 87348 172334 86100 172334 92486 172335 86100 172335 85544 172335 85544 172336 86100 172336 86101 172336 85544 172337 86101 172337 86102 172337 86102 172338 86101 172338 92491 172338 92491 172339 86101 172339 87371 172339 92491 172340 87371 172340 86114 172340 86105 172341 86103 172341 92481 172341 92481 172342 86103 172342 86151 172342 85538 172343 86104 172343 92477 172343 92477 172344 86104 172344 86103 172344 92477 172345 86103 172345 85537 172345 85537 172346 86103 172346 86105 172346 86106 172347 85510 172347 92484 172347 85510 172348 86106 172348 85518 172348 85518 172349 86106 172349 86159 172349 85518 172350 86159 172350 86157 172350 86167 172351 85518 172351 86107 172351 86107 172352 85518 172352 86157 172352 86107 172353 86157 172353 86156 172353 86099 172354 86133 172354 85519 172354 85519 172355 86133 172355 86108 172355 85519 172356 86108 172356 85521 172356 85521 172357 86108 172357 86129 172357 85521 172358 86129 172358 85522 172358 85522 172359 86129 172359 86128 172359 85522 172360 86128 172360 85523 172360 86109 172361 86311 172361 86110 172361 85523 172362 86128 172362 86110 172362 86110 172363 86128 172363 86279 172363 86110 172364 86279 172364 86109 172364 87372 172365 86111 172365 86147 172365 86147 172366 86111 172366 87374 172366 87372 172367 86104 172367 86112 172367 86112 172368 86104 172368 85538 172368 86112 172369 85538 172369 87371 172369 87371 172370 85538 172370 86113 172370 87371 172371 86113 172371 86114 172371 86165 172372 86166 172372 86121 172372 86135 172373 86168 172373 86164 172373 86070 172374 86126 172374 86115 172374 86115 172375 86126 172375 86124 172375 86115 172376 86124 172376 86090 172376 86090 172377 86124 172377 86116 172377 86090 172378 86116 172378 86062 172378 86062 172379 86116 172379 86117 172379 86062 172380 86117 172380 86063 172380 86063 172381 86117 172381 86121 172381 86063 172382 86121 172382 86065 172382 86065 172383 86121 172383 86166 172383 86065 172384 86166 172384 86066 172384 86118 172385 86119 172385 86335 172385 86127 172386 86126 172386 86271 172386 86271 172387 86126 172387 86070 172387 86271 172388 86070 172388 86120 172388 86165 172389 86121 172389 86122 172389 86122 172390 86121 172390 86117 172390 86122 172391 86117 172391 86163 172391 86163 172392 86117 172392 86116 172392 86163 172393 86116 172393 86123 172393 86123 172394 86116 172394 86124 172394 86123 172395 86124 172395 86125 172395 86125 172396 86124 172396 86126 172396 86125 172397 86126 172397 86118 172397 86118 172398 86126 172398 86127 172398 86118 172399 86127 172399 86119 172399 86098 172400 86128 172400 86130 172400 86130 172401 86128 172401 86129 172401 86130 172402 86129 172402 86131 172402 86131 172403 86129 172403 86108 172403 86131 172404 86108 172404 86132 172404 86132 172405 86108 172405 86133 172405 86132 172406 86133 172406 86135 172406 86135 172407 86133 172407 86134 172407 86135 172408 86134 172408 86168 172408 86164 172409 86136 172409 86135 172409 86135 172410 86136 172410 86137 172410 86135 172411 86137 172411 86132 172411 86132 172412 86137 172412 86162 172412 86132 172413 86162 172413 86131 172413 86131 172414 86162 172414 86161 172414 86131 172415 86161 172415 86130 172415 86130 172416 86161 172416 86138 172416 86130 172417 86138 172417 86098 172417 86098 172418 86138 172418 86139 172418 86098 172419 86139 172419 86279 172419 87375 172420 86054 172420 86140 172420 86140 172421 86054 172421 86055 172421 86140 172422 86055 172422 86141 172422 86141 172423 86055 172423 86056 172423 86141 172424 86056 172424 86142 172424 86142 172425 86056 172425 86058 172425 86142 172426 86058 172426 86155 172426 86170 172427 86143 172427 86144 172427 86144 172428 86143 172428 86172 172428 86144 172429 86172 172429 86145 172429 86145 172430 86172 172430 86150 172430 86145 172431 86150 172431 86146 172431 86146 172432 86150 172432 86147 172432 86146 172433 86147 172433 86148 172433 86148 172434 86147 172434 87374 172434 86148 172435 87374 172435 86149 172435 87372 172436 86147 172436 86104 172436 86104 172437 86147 172437 86150 172437 86104 172438 86150 172438 86103 172438 86103 172439 86150 172439 86172 172439 86103 172440 86172 172440 86151 172440 86151 172441 86172 172441 86152 172441 86151 172442 86152 172442 92481 172442 86058 172443 86060 172443 86155 172443 86155 172444 86060 172444 86059 172444 86155 172445 86059 172445 86154 172445 86154 172446 86059 172446 86153 172446 86153 172447 86059 172447 86069 172447 86153 172448 86069 172448 86067 172448 86153 172449 86170 172449 86154 172449 86154 172450 86170 172450 86144 172450 86154 172451 86144 172451 86155 172451 86155 172452 86144 172452 86145 172452 86155 172453 86145 172453 86142 172453 86142 172454 86145 172454 86146 172454 86142 172455 86146 172455 86141 172455 86141 172456 86146 172456 86148 172456 86141 172457 86148 172457 86140 172457 86140 172458 86148 172458 86149 172458 86140 172459 86149 172459 87375 172459 86156 172460 86157 172460 86158 172460 86158 172461 86157 172461 86159 172461 86158 172462 86159 172462 86169 172462 86169 172463 86159 172463 86106 172463 86169 172464 86106 172464 86160 172464 86160 172465 86106 172465 92484 172465 86160 172466 92484 172466 86171 172466 86335 172467 86138 172467 86118 172467 86118 172468 86138 172468 86161 172468 86118 172469 86161 172469 86125 172469 86125 172470 86161 172470 86162 172470 86125 172471 86162 172471 86123 172471 86123 172472 86162 172472 86137 172472 86123 172473 86137 172473 86163 172473 86163 172474 86137 172474 86136 172474 86163 172475 86136 172475 86122 172475 86122 172476 86136 172476 86164 172476 86122 172477 86164 172477 86165 172477 86165 172478 86164 172478 86153 172478 86165 172479 86153 172479 86166 172479 86166 172480 86153 172480 86067 172480 86166 172481 86067 172481 86066 172481 86099 172482 86167 172482 86134 172482 86134 172483 86167 172483 86107 172483 86134 172484 86107 172484 86168 172484 86168 172485 86107 172485 86156 172485 86168 172486 86156 172486 86164 172486 86164 172487 86156 172487 86158 172487 86164 172488 86158 172488 86153 172488 86153 172489 86158 172489 86169 172489 86153 172490 86169 172490 86170 172490 86170 172491 86169 172491 86160 172491 86170 172492 86160 172492 86143 172492 86143 172493 86160 172493 86171 172493 86143 172494 86171 172494 86172 172494 86172 172495 86171 172495 85532 172495 86172 172496 85532 172496 86152 172496 86173 172497 87326 172497 85964 172497 86173 172498 85964 172498 87327 172498 87305 172499 86176 172499 87306 172499 87306 172500 86176 172500 85964 172500 87326 172501 86174 172501 85964 172501 85964 172502 86174 172502 86175 172502 85964 172503 86175 172503 87306 172503 87305 172504 87304 172504 86176 172504 86176 172505 87304 172505 87300 172505 86176 172506 87300 172506 86752 172506 86177 172507 86179 172507 86178 172507 86178 172508 86179 172508 86180 172508 86178 172509 86180 172509 85964 172509 85964 172510 86180 172510 87328 172510 85964 172511 87328 172511 87327 172511 85964 172512 86176 172512 86181 172512 86181 172513 86176 172513 86182 172513 86185 172514 85961 172514 86695 172514 86695 172515 85961 172515 85981 172515 86695 172516 85981 172516 86183 172516 86183 172517 85981 172517 86184 172517 86183 172518 86184 172518 86182 172518 86182 172519 86184 172519 85993 172519 86182 172520 85993 172520 86181 172520 86695 172521 86694 172521 86185 172521 86185 172522 86694 172522 86187 172522 86185 172523 86187 172523 85979 172523 85979 172524 86187 172524 86186 172524 86186 172525 86187 172525 86189 172525 86186 172526 86189 172526 86188 172526 86188 172527 86189 172527 86019 172527 86019 172528 86189 172528 86719 172528 86019 172529 86719 172529 86190 172529 86719 172530 86191 172530 86190 172530 86190 172531 86191 172531 86722 172531 86190 172532 86722 172532 86013 172532 86013 172533 86722 172533 86723 172533 86013 172534 86723 172534 86205 172534 86622 172535 86611 172535 85846 172535 86192 172536 86194 172536 86210 172536 85846 172537 86193 172537 86195 172537 86193 172538 85846 172538 86194 172538 86194 172539 85846 172539 86611 172539 86194 172540 86611 172540 86210 172540 86195 172541 85876 172541 85846 172541 85846 172542 85876 172542 86221 172542 85846 172543 86221 172543 86196 172543 86655 172544 86654 172544 86206 172544 86206 172545 86654 172545 86653 172545 86206 172546 86653 172546 86197 172546 86197 172547 86668 172547 86206 172547 86206 172548 86668 172548 86198 172548 86206 172549 86198 172549 86199 172549 86199 172550 86198 172550 86672 172550 86199 172551 86672 172551 86200 172551 86201 172552 86202 172552 86210 172552 86210 172553 86202 172553 86203 172553 86210 172554 86203 172554 86569 172554 86204 172555 86015 172555 85846 172555 85846 172556 86015 172556 86205 172556 85846 172557 86205 172557 86622 172557 86622 172558 86205 172558 86723 172558 86622 172559 86723 172559 86206 172559 86206 172560 86723 172560 86207 172560 86206 172561 86207 172561 86208 172561 86569 172562 86568 172562 86210 172562 86210 172563 86568 172563 86506 172563 86210 172564 86506 172564 86192 172564 86219 172565 86218 172565 85941 172565 86208 172566 86209 172566 86206 172566 86206 172567 86209 172567 86656 172567 86206 172568 86656 172568 86655 172568 86210 172569 86211 172569 86201 172569 86201 172570 86211 172570 86213 172570 86201 172571 86213 172571 86212 172571 86212 172572 86213 172572 86214 172572 86212 172573 86214 172573 86215 172573 86219 172574 86216 172574 86218 172574 86218 172575 86216 172575 86217 172575 86218 172576 86217 172576 85944 172576 85944 172577 86217 172577 85945 172577 85941 172578 86220 172578 86219 172578 86219 172579 86220 172579 85862 172579 86219 172580 85862 172580 85948 172580 85948 172581 85862 172581 85873 172581 85948 172582 85873 172582 86221 172582 86221 172583 85873 172583 86222 172583 86221 172584 86222 172584 86196 172584 86011 172585 86223 172585 86225 172585 86225 172586 86223 172586 86227 172586 86225 172587 86227 172587 86226 172587 85846 172588 86224 172588 86204 172588 86204 172589 86224 172589 85853 172589 86204 172590 85853 172590 86016 172590 86016 172591 85853 172591 85852 172591 86016 172592 85852 172592 86225 172592 86225 172593 85852 172593 85978 172593 86225 172594 85978 172594 86011 172594 86226 172595 86227 172595 86017 172595 86017 172596 86227 172596 86228 172596 86017 172597 86228 172597 86031 172597 86193 172598 86194 172598 86229 172598 86229 172599 86194 172599 86232 172599 86229 172600 86232 172600 86230 172600 86230 172601 86232 172601 86231 172601 86231 172602 86232 172602 86233 172602 86231 172603 86233 172603 85902 172603 86589 172604 86240 172604 86234 172604 86234 172605 86240 172605 85902 172605 86234 172606 85902 172606 86235 172606 86235 172607 85902 172607 86233 172607 85899 172608 86237 172608 86236 172608 86236 172609 86237 172609 86238 172609 86236 172610 86238 172610 86239 172610 86239 172611 86238 172611 85901 172611 86239 172612 85901 172612 86589 172612 86589 172613 85901 172613 85900 172613 86589 172614 85900 172614 86240 172614 85899 172615 86236 172615 85898 172615 85898 172616 86236 172616 86525 172616 85898 172617 86525 172617 86241 172617 86241 172618 86525 172618 86242 172618 86241 172619 86242 172619 85935 172619 85935 172620 86242 172620 86588 172620 85935 172621 86588 172621 86243 172621 86243 172622 86588 172622 86586 172622 86243 172623 86586 172623 85895 172623 86244 172624 86586 172624 86245 172624 86245 172625 86586 172625 86502 172625 86244 172626 87096 172626 86586 172626 86586 172627 87096 172627 86246 172627 86586 172628 86246 172628 85895 172628 85895 172629 86246 172629 86247 172629 85895 172630 86247 172630 87128 172630 87128 172631 87129 172631 85895 172631 85895 172632 87129 172632 86248 172632 85895 172633 86248 172633 87130 172633 87141 172634 85753 172634 87133 172634 87133 172635 85753 172635 85895 172635 87133 172636 85895 172636 87131 172636 87131 172637 85895 172637 87130 172637 86109 172638 86279 172638 86276 172638 92468 172639 86250 172639 86249 172639 86249 172640 86250 172640 86251 172640 86249 172641 86251 172641 85516 172641 85516 172642 86251 172642 86252 172642 85516 172643 86252 172643 92550 172643 92550 172644 86252 172644 86253 172644 92550 172645 86253 172645 86318 172645 86323 172646 86322 172646 86258 172646 92440 172647 86254 172647 86323 172647 86323 172648 86254 172648 86255 172648 86323 172649 86255 172649 86256 172649 92440 172650 86323 172650 86257 172650 86257 172651 86323 172651 86258 172651 86257 172652 86258 172652 86283 172652 86288 172653 86260 172653 86259 172653 86259 172654 86260 172654 86261 172654 86259 172655 86261 172655 85504 172655 87099 172656 92804 172656 86262 172656 86262 172657 92804 172657 86263 172657 86262 172658 86263 172658 87103 172658 87103 172659 86263 172659 86264 172659 87103 172660 86264 172660 87105 172660 87105 172661 86264 172661 85571 172661 87105 172662 85571 172662 87107 172662 87107 172663 85571 172663 92597 172663 87107 172664 92597 172664 87109 172664 87109 172665 92597 172665 92578 172665 87109 172666 92578 172666 87110 172666 87110 172667 92578 172667 86285 172667 87110 172668 86285 172668 87111 172668 86287 172669 86289 172669 86265 172669 86265 172670 86289 172670 86319 172670 86265 172671 86319 172671 87149 172671 86294 172672 86293 172672 87149 172672 86281 172673 85706 172673 86266 172673 86305 172674 86267 172674 85696 172674 86250 172675 86268 172675 86251 172675 86251 172676 86268 172676 86315 172676 86251 172677 86315 172677 86252 172677 86252 172678 86315 172678 86316 172678 86252 172679 86316 172679 86253 172679 85696 172680 86267 172680 85721 172680 85721 172681 86267 172681 86301 172681 85721 172682 86301 172682 86302 172682 86269 172683 86270 172683 86271 172683 86271 172684 86270 172684 86272 172684 86271 172685 86272 172685 86302 172685 86302 172686 86272 172686 86273 172686 86302 172687 86273 172687 85721 172687 86280 172688 86139 172688 86335 172688 86303 172689 86119 172689 86127 172689 86314 172690 86313 172690 86277 172690 86277 172691 86313 172691 86274 172691 86277 172692 86274 172692 86278 172692 86278 172693 86274 172693 86275 172693 86278 172694 86275 172694 86276 172694 86276 172695 86275 172695 86312 172695 86276 172696 86312 172696 86109 172696 86330 172697 86314 172697 86331 172697 86331 172698 86314 172698 86277 172698 86331 172699 86277 172699 86332 172699 86332 172700 86277 172700 86278 172700 86332 172701 86278 172701 86334 172701 86334 172702 86278 172702 86276 172702 86334 172703 86276 172703 86280 172703 86280 172704 86276 172704 86279 172704 86280 172705 86279 172705 86139 172705 86291 172706 86292 172706 86295 172706 86295 172707 86292 172707 86281 172707 86295 172708 86281 172708 86282 172708 86282 172709 86281 172709 86266 172709 86282 172710 86266 172710 86293 172710 85504 172711 86283 172711 86259 172711 86259 172712 86283 172712 86258 172712 86259 172713 86258 172713 86284 172713 86284 172714 86258 172714 86322 172714 86285 172715 86286 172715 87111 172715 87111 172716 86286 172716 85508 172716 87111 172717 85508 172717 86287 172717 86287 172718 85508 172718 86288 172718 86287 172719 86288 172719 86289 172719 86289 172720 86288 172720 86259 172720 86289 172721 86259 172721 86319 172721 86319 172722 86259 172722 86284 172722 86290 172723 85705 172723 86296 172723 86296 172724 85705 172724 85704 172724 86296 172725 85704 172725 86291 172725 86291 172726 85704 172726 85703 172726 86291 172727 85703 172727 86292 172727 86293 172728 86294 172728 86282 172728 86282 172729 86294 172729 86320 172729 86282 172730 86320 172730 86295 172730 86295 172731 86320 172731 86321 172731 86295 172732 86321 172732 86291 172732 86291 172733 86321 172733 86324 172733 86291 172734 86324 172734 86296 172734 86296 172735 86324 172735 86326 172735 86296 172736 86326 172736 86290 172736 86290 172737 86326 172737 86297 172737 86290 172738 86297 172738 86327 172738 86327 172739 86329 172739 86307 172739 86307 172740 86329 172740 86298 172740 86307 172741 86298 172741 86306 172741 86306 172742 86298 172742 86299 172742 86306 172743 86299 172743 86305 172743 86305 172744 86299 172744 86333 172744 86305 172745 86333 172745 86267 172745 86267 172746 86333 172746 86300 172746 86267 172747 86300 172747 86301 172747 86301 172748 86300 172748 86303 172748 86301 172749 86303 172749 86302 172749 86302 172750 86303 172750 86127 172750 86302 172751 86127 172751 86271 172751 85696 172752 86304 172752 86305 172752 86305 172753 86304 172753 85698 172753 86305 172754 85698 172754 86306 172754 86306 172755 85698 172755 85700 172755 86306 172756 85700 172756 86307 172756 86307 172757 85700 172757 86308 172757 86307 172758 86308 172758 86327 172758 86327 172759 86308 172759 86309 172759 86327 172760 86309 172760 86290 172760 86290 172761 86309 172761 86310 172761 86290 172762 86310 172762 85705 172762 86311 172763 86109 172763 85526 172763 85526 172764 86109 172764 86312 172764 85526 172765 86312 172765 85528 172765 85528 172766 86312 172766 86275 172766 85528 172767 86275 172767 85529 172767 85529 172768 86275 172768 86274 172768 85529 172769 86274 172769 92468 172769 92468 172770 86274 172770 86313 172770 92468 172771 86313 172771 86250 172771 86250 172772 86313 172772 86314 172772 86250 172773 86314 172773 86268 172773 86268 172774 86314 172774 86330 172774 86268 172775 86330 172775 86315 172775 86315 172776 86330 172776 86328 172776 86315 172777 86328 172777 86316 172777 86316 172778 86328 172778 86317 172778 86316 172779 86317 172779 86253 172779 86253 172780 86317 172780 86325 172780 86253 172781 86325 172781 86318 172781 86318 172782 86325 172782 86256 172782 86318 172783 86256 172783 85513 172783 85513 172784 86256 172784 86255 172784 87149 172785 86319 172785 86294 172785 86294 172786 86319 172786 86284 172786 86294 172787 86284 172787 86320 172787 86320 172788 86284 172788 86322 172788 86320 172789 86322 172789 86321 172789 86321 172790 86322 172790 86323 172790 86321 172791 86323 172791 86324 172791 86324 172792 86323 172792 86256 172792 86324 172793 86256 172793 86326 172793 86326 172794 86256 172794 86325 172794 86326 172795 86325 172795 86297 172795 86297 172796 86325 172796 86317 172796 86297 172797 86317 172797 86327 172797 86327 172798 86317 172798 86328 172798 86327 172799 86328 172799 86329 172799 86329 172800 86328 172800 86330 172800 86329 172801 86330 172801 86298 172801 86298 172802 86330 172802 86331 172802 86298 172803 86331 172803 86299 172803 86299 172804 86331 172804 86332 172804 86299 172805 86332 172805 86333 172805 86333 172806 86332 172806 86334 172806 86333 172807 86334 172807 86300 172807 86300 172808 86334 172808 86280 172808 86300 172809 86280 172809 86303 172809 86303 172810 86280 172810 86335 172810 86303 172811 86335 172811 86119 172811 87521 172812 86336 172812 86339 172812 86339 172813 86336 172813 86338 172813 86337 172814 87522 172814 86340 172814 86340 172815 87522 172815 87518 172815 86340 172816 87518 172816 86338 172816 86338 172817 87518 172817 87520 172817 86338 172818 87520 172818 86339 172818 86337 172819 86340 172819 87536 172819 87536 172820 86340 172820 86360 172820 87536 172821 86360 172821 87535 172821 87535 172822 86360 172822 86341 172822 86341 172823 86360 172823 86363 172823 86341 172824 86363 172824 87541 172824 86336 172825 87521 172825 86343 172825 86343 172826 87521 172826 86342 172826 86343 172827 86342 172827 86344 172827 86409 172828 86362 172828 86345 172828 86345 172829 86362 172829 86361 172829 86345 172830 86361 172830 87478 172830 87478 172831 86361 172831 86346 172831 86346 172832 86361 172832 86347 172832 86347 172833 86361 172833 86349 172833 86347 172834 86349 172834 87492 172834 87492 172835 86349 172835 86348 172835 86348 172836 86349 172836 86350 172836 86348 172837 86350 172837 86351 172837 86351 172838 86350 172838 87494 172838 87494 172839 86350 172839 86343 172839 87494 172840 86343 172840 86344 172840 87437 172841 87438 172841 86378 172841 86378 172842 87438 172842 86359 172842 86373 172843 86352 172843 87551 172843 87551 172844 86352 172844 86353 172844 87551 172845 86353 172845 87553 172845 86426 172846 86354 172846 87432 172846 87432 172847 86354 172847 86355 172847 87432 172848 86355 172848 86356 172848 86373 172849 87551 172849 86374 172849 86374 172850 87551 172850 87550 172850 86374 172851 87550 172851 86376 172851 86363 172852 86362 172852 86396 172852 86396 172853 86362 172853 87437 172853 86396 172854 87437 172854 87545 172854 87545 172855 87437 172855 86378 172855 87545 172856 86378 172856 87550 172856 87550 172857 86378 172857 86377 172857 87550 172858 86377 172858 86376 172858 86355 172859 86357 172859 86356 172859 86356 172860 86357 172860 86358 172860 86356 172861 86358 172861 87438 172861 87438 172862 86358 172862 86422 172862 87438 172863 86422 172863 86359 172863 86363 172864 86360 172864 86340 172864 86349 172865 86361 172865 86350 172865 86350 172866 86361 172866 86362 172866 86340 172867 86338 172867 86363 172867 86363 172868 86338 172868 86336 172868 86363 172869 86336 172869 86362 172869 86362 172870 86336 172870 86343 172870 86362 172871 86343 172871 86350 172871 87544 172872 86364 172872 87540 172872 87540 172873 86364 172873 86401 172873 87540 172874 86401 172874 87534 172874 87000 172875 86365 172875 87544 172875 87544 172876 86365 172876 86366 172876 87544 172877 86366 172877 86364 172877 87555 172878 87553 172878 86353 172878 86369 172879 86367 172879 86381 172879 86381 172880 86367 172880 87555 172880 86459 172881 86368 172881 86382 172881 86382 172882 86368 172882 87549 172882 86382 172883 87549 172883 86369 172883 86459 172884 86382 172884 86370 172884 86370 172885 86382 172885 86385 172885 86370 172886 86385 172886 86371 172886 86371 172887 86385 172887 86386 172887 86371 172888 86386 172888 86453 172888 86453 172889 86386 172889 86372 172889 86453 172890 86372 172890 86455 172890 86455 172891 86372 172891 86388 172891 86455 172892 86388 172892 86456 172892 87555 172893 86353 172893 86381 172893 86381 172894 86353 172894 86352 172894 86381 172895 86352 172895 86383 172895 86383 172896 86352 172896 86373 172896 86383 172897 86373 172897 86384 172897 86384 172898 86373 172898 86374 172898 86384 172899 86374 172899 86375 172899 86375 172900 86374 172900 86376 172900 86375 172901 86376 172901 86387 172901 86387 172902 86376 172902 86377 172902 86387 172903 86377 172903 86379 172903 86379 172904 86377 172904 86378 172904 86379 172905 86378 172905 86380 172905 86380 172906 86378 172906 86359 172906 86380 172907 86359 172907 86391 172907 86369 172908 86381 172908 86382 172908 86382 172909 86381 172909 86383 172909 86382 172910 86383 172910 86385 172910 86385 172911 86383 172911 86384 172911 86385 172912 86384 172912 86386 172912 86386 172913 86384 172913 86375 172913 86386 172914 86375 172914 86372 172914 86372 172915 86375 172915 86387 172915 86372 172916 86387 172916 86388 172916 86388 172917 86387 172917 86379 172917 86388 172918 86379 172918 86389 172918 86389 172919 86379 172919 86380 172919 86389 172920 86380 172920 86390 172920 86390 172921 86380 172921 86391 172921 86390 172922 86391 172922 86417 172922 86456 172923 86388 172923 86392 172923 86392 172924 86388 172924 86389 172924 86392 172925 86389 172925 86393 172925 86393 172926 86389 172926 86390 172926 86393 172927 86390 172927 86394 172927 86394 172928 86390 172928 86417 172928 86394 172929 86417 172929 86395 172929 87541 172930 86363 172930 87565 172930 87565 172931 86363 172931 86396 172931 87576 172932 87575 172932 86397 172932 86396 172933 87546 172933 87565 172933 87565 172934 87546 172934 86397 172934 87565 172935 86397 172935 86398 172935 86398 172936 86397 172936 87575 172936 87558 172937 86399 172937 86397 172937 86397 172938 86399 172938 86400 172938 86397 172939 86400 172939 87576 172939 87009 172940 86401 172940 86364 172940 86401 172941 87009 172941 87020 172941 87534 172942 86401 172942 86402 172942 86402 172943 86401 172943 86621 172943 86402 172944 86621 172944 87533 172944 87533 172945 86621 172945 87532 172945 87532 172946 86621 172946 87514 172946 87514 172947 86621 172947 86630 172947 87514 172948 86630 172948 87509 172948 87510 172949 87509 172949 86630 172949 86762 172950 86406 172950 86629 172950 86629 172951 86406 172951 87500 172951 86629 172952 87500 172952 87501 172952 87501 172953 86403 172953 86629 172953 86629 172954 86403 172954 87504 172954 86629 172955 87504 172955 86630 172955 86630 172956 87504 172956 86404 172956 86630 172957 86404 172957 87510 172957 86767 172958 87219 172958 86768 172958 86768 172959 87219 172959 87211 172959 86768 172960 87211 172960 86762 172960 87211 172961 86407 172961 86762 172961 86762 172962 86407 172962 86405 172962 86762 172963 86405 172963 86406 172963 87211 172964 87209 172964 86407 172964 86407 172965 87209 172965 86408 172965 86407 172966 86408 172966 87476 172966 87439 172967 87437 172967 86362 172967 86362 172968 86409 172968 87439 172968 87439 172969 86409 172969 87458 172969 87439 172970 87458 172970 87444 172970 87458 172971 86410 172971 87444 172971 87444 172972 86410 172972 87459 172972 87444 172973 87459 172973 87461 172973 87461 172974 87459 172974 87460 172974 86411 172975 87435 172975 86427 172975 87436 172976 86413 172976 86421 172976 86412 172977 86812 172977 86805 172977 86423 172978 86391 172978 86359 172978 86809 172979 86395 172979 86417 172979 86412 172980 86805 172980 86413 172980 86413 172981 86805 172981 86421 172981 86421 172982 86805 172982 86803 172982 86421 172983 86803 172983 86414 172983 86414 172984 86803 172984 86415 172984 86414 172985 86415 172985 86419 172985 86419 172986 86415 172986 86807 172986 86419 172987 86807 172987 86418 172987 86418 172988 86807 172988 86809 172988 86418 172989 86809 172989 86416 172989 86416 172990 86809 172990 86417 172990 86416 172991 86417 172991 86391 172991 86391 172992 86423 172992 86416 172992 86416 172993 86423 172993 86424 172993 86416 172994 86424 172994 86418 172994 86418 172995 86424 172995 86425 172995 86418 172996 86425 172996 86419 172996 86419 172997 86425 172997 86420 172997 86419 172998 86420 172998 86414 172998 86414 172999 86420 172999 86427 172999 86414 173000 86427 173000 86421 173000 86421 173001 86427 173001 87435 173001 86421 173002 87435 173002 87436 173002 86359 173003 86422 173003 86423 173003 86423 173004 86422 173004 86358 173004 86423 173005 86358 173005 86424 173005 86424 173006 86358 173006 86357 173006 86424 173007 86357 173007 86425 173007 86425 173008 86357 173008 86355 173008 86425 173009 86355 173009 86420 173009 86420 173010 86355 173010 86354 173010 86420 173011 86354 173011 86427 173011 86427 173012 86354 173012 86426 173012 86427 173013 86426 173013 86411 173013 86428 173014 86476 173014 87596 173014 86772 173015 86771 173015 86466 173015 86467 173016 86429 173016 86469 173016 86432 173017 87038 173017 86430 173017 86430 173018 87038 173018 87039 173018 86430 173019 87039 173019 86461 173019 86480 173020 86431 173020 86479 173020 86479 173021 86431 173021 87034 173021 86479 173022 87034 173022 86430 173022 86430 173023 87034 173023 87036 173023 86430 173024 87036 173024 86432 173024 86433 173025 86434 173025 86435 173025 86435 173026 86434 173026 87030 173026 86435 173027 87030 173027 86436 173027 86436 173028 87030 173028 86474 173028 86475 173029 86437 173029 86438 173029 86442 173030 86439 173030 86475 173030 86475 173031 86439 173031 86440 173031 86475 173032 86440 173032 86437 173032 86437 173033 86440 173033 86937 173033 86437 173034 86937 173034 87049 173034 86939 173035 86441 173035 86442 173035 86442 173036 86441 173036 86443 173036 86442 173037 86443 173037 86439 173037 86442 173038 86444 173038 86939 173038 86939 173039 86444 173039 86472 173039 86939 173040 86472 173040 86941 173040 86941 173041 86472 173041 86446 173041 86941 173042 86446 173042 86445 173042 86445 173043 86446 173043 86447 173043 86445 173044 86447 173044 86448 173044 86448 173045 86447 173045 86470 173045 86448 173046 86470 173046 86449 173046 86449 173047 86470 173047 86460 173047 86449 173048 86460 173048 86450 173048 86450 173049 86460 173049 86468 173049 86450 173050 86468 173050 86956 173050 86848 173051 86451 173051 86465 173051 86465 173052 86451 173052 86949 173052 86465 173053 86949 173053 86467 173053 86467 173054 86949 173054 86950 173054 86467 173055 86950 173055 86429 173055 86395 173056 86772 173056 86394 173056 86394 173057 86772 173057 86466 173057 86394 173058 86466 173058 86393 173058 86393 173059 86466 173059 86452 173059 86393 173060 86452 173060 86392 173060 86460 173061 86371 173061 86468 173061 86468 173062 86371 173062 86453 173062 86468 173063 86453 173063 86454 173063 86454 173064 86453 173064 86455 173064 86454 173065 86455 173065 86452 173065 86452 173066 86455 173066 86456 173066 86452 173067 86456 173067 86392 173067 86457 173068 86458 173068 86470 173068 86470 173069 86458 173069 86459 173069 86470 173070 86459 173070 86460 173070 86460 173071 86459 173071 86370 173071 86460 173072 86370 173072 86371 173072 87039 173073 87013 173073 86461 173073 86461 173074 87013 173074 87008 173074 86461 173075 87008 173075 86462 173075 86462 173076 87008 173076 87006 173076 86462 173077 87006 173077 86463 173077 86463 173078 87006 173078 86464 173078 86463 173079 86464 173079 86476 173079 86476 173080 86464 173080 86994 173080 86476 173081 86994 173081 87596 173081 86771 173082 86848 173082 86466 173082 86466 173083 86848 173083 86465 173083 86466 173084 86465 173084 86452 173084 86452 173085 86465 173085 86467 173085 86452 173086 86467 173086 86454 173086 86454 173087 86467 173087 86469 173087 86454 173088 86469 173088 86468 173088 86468 173089 86469 173089 86954 173089 86468 173090 86954 173090 86956 173090 86457 173091 86470 173091 86477 173091 86477 173092 86470 173092 86447 173092 86477 173093 86447 173093 86478 173093 86478 173094 86447 173094 86446 173094 86478 173095 86446 173095 86471 173095 86471 173096 86446 173096 86472 173096 86471 173097 86472 173097 86473 173097 86473 173098 86472 173098 86444 173098 86473 173099 86444 173099 86474 173099 86474 173100 86444 173100 86442 173100 86474 173101 86442 173101 86436 173101 86436 173102 86442 173102 86475 173102 86436 173103 86475 173103 86435 173103 86435 173104 86475 173104 86438 173104 86435 173105 86438 173105 86433 173105 86428 173106 86458 173106 86476 173106 86476 173107 86458 173107 86457 173107 86476 173108 86457 173108 86463 173108 86463 173109 86457 173109 86477 173109 86463 173110 86477 173110 86462 173110 86462 173111 86477 173111 86478 173111 86462 173112 86478 173112 86461 173112 86461 173113 86478 173113 86471 173113 86461 173114 86471 173114 86430 173114 86430 173115 86471 173115 86473 173115 86430 173116 86473 173116 86479 173116 86479 173117 86473 173117 86474 173117 86479 173118 86474 173118 86480 173118 86480 173119 86474 173119 87030 173119 87021 173120 86536 173120 87020 173120 87020 173121 86536 173121 86534 173121 87020 173122 86534 173122 86401 173122 86401 173123 86534 173123 86621 173123 87021 173124 86481 173124 86536 173124 86536 173125 86481 173125 87023 173125 86536 173126 87023 173126 86537 173126 86537 173127 87023 173127 86482 173127 86537 173128 86482 173128 86554 173128 86554 173129 86482 173129 86483 173129 86482 173130 87019 173130 86483 173130 86483 173131 87019 173131 86484 173131 86483 173132 86484 173132 86595 173132 86595 173133 86484 173133 87018 173133 86595 173134 87018 173134 86485 173134 86485 173135 87018 173135 87016 173135 86485 173136 87016 173136 86486 173136 86486 173137 87016 173137 87014 173137 86486 173138 87014 173138 86545 173138 86545 173139 87014 173139 86487 173139 86545 173140 86487 173140 86488 173140 86488 173141 86487 173141 86489 173141 86488 173142 86489 173142 86550 173142 86550 173143 86489 173143 87043 173143 86496 173144 86517 173144 87053 173144 87053 173145 86517 173145 86490 173145 87053 173146 86490 173146 86492 173146 86492 173147 86490 173147 86491 173147 86492 173148 86491 173148 86493 173148 86493 173149 86491 173149 86494 173149 86493 173150 86494 173150 87043 173150 87043 173151 86494 173151 86504 173151 87043 173152 86504 173152 86550 173152 86516 173153 86515 173153 87056 173153 87056 173154 86515 173154 86495 173154 87056 173155 86495 173155 87057 173155 87057 173156 86495 173156 86496 173156 87057 173157 86496 173157 87054 173157 87054 173158 86496 173158 87053 173158 87056 173159 87055 173159 86516 173159 86516 173160 87055 173160 87061 173160 86516 173161 87061 173161 86498 173161 86498 173162 87061 173162 86497 173162 86498 173163 86497 173163 86500 173163 86503 173164 86501 173164 86499 173164 86500 173165 86497 173165 86501 173165 86501 173166 86497 173166 87062 173166 86501 173167 87062 173167 86499 173167 86499 173168 87083 173168 86503 173168 86503 173169 87083 173169 86502 173169 86503 173170 86502 173170 86586 173170 86550 173171 86504 173171 86551 173171 86554 173172 86483 173172 86597 173172 86533 173173 86532 173173 86580 173173 86510 173174 86509 173174 86505 173174 86192 173175 86506 173175 86507 173175 86603 173176 86577 173176 86601 173176 86541 173177 86593 173177 86543 173177 86543 173178 86593 173178 86594 173178 86543 173179 86594 173179 86508 173179 86508 173180 86594 173180 86604 173180 86605 173181 86232 173181 86507 173181 86507 173182 86232 173182 86194 173182 86507 173183 86194 173183 86192 173183 86513 173184 86509 173184 86511 173184 86511 173185 86509 173185 86510 173185 86511 173186 86510 173186 86590 173186 86527 173187 86505 173187 86512 173187 86512 173188 86505 173188 86509 173188 86512 173189 86509 173189 86528 173189 86528 173190 86509 173190 86513 173190 86528 173191 86513 173191 86514 173191 86514 173192 86513 173192 86515 173192 86514 173193 86515 173193 86516 173193 86491 173194 86490 173194 86590 173194 86590 173195 86490 173195 86517 173195 86590 173196 86517 173196 86511 173196 86511 173197 86517 173197 86496 173197 86511 173198 86496 173198 86513 173198 86513 173199 86496 173199 86495 173199 86513 173200 86495 173200 86515 173200 86239 173201 86609 173201 86526 173201 86530 173202 86498 173202 86500 173202 86606 173203 86518 173203 86607 173203 86607 173204 86518 173204 86520 173204 86607 173205 86520 173205 86519 173205 86519 173206 86520 173206 86521 173206 86519 173207 86521 173207 86522 173207 86522 173208 86521 173208 86529 173208 86522 173209 86529 173209 86523 173209 86523 173210 86529 173210 86530 173210 86523 173211 86530 173211 86524 173211 86524 173212 86530 173212 86500 173212 86524 173213 86500 173213 86501 173213 86610 173214 86525 173214 86526 173214 86526 173215 86525 173215 86236 173215 86526 173216 86236 173216 86239 173216 86518 173217 86527 173217 86520 173217 86520 173218 86527 173218 86512 173218 86520 173219 86512 173219 86521 173219 86521 173220 86512 173220 86528 173220 86521 173221 86528 173221 86529 173221 86529 173222 86528 173222 86514 173222 86529 173223 86514 173223 86530 173223 86530 173224 86514 173224 86516 173224 86530 173225 86516 173225 86498 173225 86582 173226 86532 173226 86531 173226 86531 173227 86532 173227 86533 173227 86531 173228 86533 173228 86575 173228 86555 173229 86537 173229 86554 173229 86621 173230 86534 173230 86620 173230 86620 173231 86534 173231 86536 173231 86559 173232 86565 173232 86557 173232 86557 173233 86565 173233 86618 173233 86557 173234 86618 173234 86535 173234 86535 173235 86618 173235 86620 173235 86535 173236 86620 173236 86555 173236 86555 173237 86620 173237 86536 173237 86555 173238 86536 173238 86537 173238 86596 173239 86544 173239 86598 173239 86598 173240 86544 173240 86539 173240 86598 173241 86539 173241 86538 173241 86538 173242 86539 173242 86540 173242 86538 173243 86540 173243 86599 173243 86599 173244 86540 173244 86553 173244 86599 173245 86553 173245 86600 173245 86600 173246 86553 173246 86541 173246 86600 173247 86541 173247 86542 173247 86542 173248 86541 173248 86543 173248 86542 173249 86543 173249 86602 173249 86602 173250 86543 173250 86508 173250 86595 173251 86485 173251 86596 173251 86596 173252 86485 173252 86486 173252 86596 173253 86486 173253 86544 173253 86544 173254 86486 173254 86545 173254 86544 173255 86545 173255 86488 173255 86504 173256 86494 173256 86551 173256 86551 173257 86494 173257 86546 173257 86551 173258 86546 173258 86547 173258 86547 173259 86546 173259 86591 173259 86547 173260 86591 173260 86552 173260 86552 173261 86591 173261 86548 173261 86552 173262 86548 173262 86549 173262 86549 173263 86548 173263 86592 173263 86488 173264 86550 173264 86544 173264 86544 173265 86550 173265 86551 173265 86544 173266 86551 173266 86539 173266 86539 173267 86551 173267 86547 173267 86539 173268 86547 173268 86540 173268 86540 173269 86547 173269 86552 173269 86540 173270 86552 173270 86553 173270 86553 173271 86552 173271 86549 173271 86553 173272 86549 173272 86541 173272 86541 173273 86549 173273 86592 173273 86541 173274 86592 173274 86593 173274 86585 173275 86214 173275 86213 173275 86554 173276 86597 173276 86555 173276 86555 173277 86597 173277 86556 173277 86555 173278 86556 173278 86535 173278 86535 173279 86556 173279 86558 173279 86535 173280 86558 173280 86557 173280 86557 173281 86558 173281 86581 173281 86557 173282 86581 173282 86559 173282 86559 173283 86581 173283 86584 173283 86559 173284 86584 173284 86563 173284 86563 173285 86584 173285 86561 173285 86563 173286 86561 173286 86560 173286 86560 173287 86561 173287 86585 173287 86560 173288 86585 173288 86562 173288 86562 173289 86585 173289 86213 173289 86562 173290 86213 173290 86211 173290 86211 173291 86210 173291 86562 173291 86562 173292 86210 173292 86612 173292 86562 173293 86612 173293 86560 173293 86560 173294 86612 173294 86614 173294 86560 173295 86614 173295 86563 173295 86563 173296 86614 173296 86564 173296 86563 173297 86564 173297 86559 173297 86559 173298 86564 173298 86616 173298 86559 173299 86616 173299 86565 173299 86570 173300 86212 173300 86566 173300 86566 173301 86212 173301 86215 173301 86566 173302 86215 173302 86567 173302 86568 173303 86569 173303 86603 173303 86603 173304 86569 173304 86203 173304 86603 173305 86203 173305 86577 173305 86577 173306 86203 173306 86202 173306 86577 173307 86202 173307 86570 173307 86570 173308 86202 173308 86201 173308 86570 173309 86201 173309 86212 173309 86583 173310 86571 173310 86576 173310 86576 173311 86571 173311 86573 173311 86576 173312 86573 173312 86578 173312 86578 173313 86573 173313 86574 173313 86578 173314 86574 173314 86572 173314 86572 173315 86574 173315 86579 173315 86571 173316 86582 173316 86573 173316 86573 173317 86582 173317 86531 173317 86573 173318 86531 173318 86574 173318 86574 173319 86531 173319 86575 173319 86574 173320 86575 173320 86579 173320 86567 173321 86583 173321 86566 173321 86566 173322 86583 173322 86576 173322 86566 173323 86576 173323 86570 173323 86570 173324 86576 173324 86578 173324 86570 173325 86578 173325 86577 173325 86577 173326 86578 173326 86572 173326 86577 173327 86572 173327 86601 173327 86601 173328 86572 173328 86579 173328 86597 173329 86580 173329 86556 173329 86556 173330 86580 173330 86532 173330 86556 173331 86532 173331 86558 173331 86558 173332 86532 173332 86582 173332 86558 173333 86582 173333 86581 173333 86581 173334 86582 173334 86571 173334 86581 173335 86571 173335 86584 173335 86584 173336 86571 173336 86583 173336 86584 173337 86583 173337 86561 173337 86561 173338 86583 173338 86567 173338 86561 173339 86567 173339 86585 173339 86585 173340 86567 173340 86215 173340 86585 173341 86215 173341 86214 173341 86503 173342 86586 173342 86587 173342 86587 173343 86586 173343 86588 173343 86587 173344 86588 173344 86610 173344 86610 173345 86588 173345 86242 173345 86610 173346 86242 173346 86525 173346 86239 173347 86589 173347 86609 173347 86609 173348 86589 173348 86234 173348 86609 173349 86234 173349 86608 173349 86608 173350 86234 173350 86235 173350 86608 173351 86235 173351 86605 173351 86605 173352 86235 173352 86233 173352 86605 173353 86233 173353 86232 173353 86494 173354 86491 173354 86546 173354 86546 173355 86491 173355 86590 173355 86546 173356 86590 173356 86591 173356 86591 173357 86590 173357 86510 173357 86591 173358 86510 173358 86548 173358 86548 173359 86510 173359 86505 173359 86548 173360 86505 173360 86592 173360 86592 173361 86505 173361 86527 173361 86592 173362 86527 173362 86593 173362 86593 173363 86527 173363 86518 173363 86593 173364 86518 173364 86594 173364 86594 173365 86518 173365 86606 173365 86594 173366 86606 173366 86604 173366 86483 173367 86595 173367 86597 173367 86597 173368 86595 173368 86596 173368 86597 173369 86596 173369 86580 173369 86580 173370 86596 173370 86598 173370 86580 173371 86598 173371 86533 173371 86533 173372 86598 173372 86538 173372 86533 173373 86538 173373 86575 173373 86575 173374 86538 173374 86599 173374 86575 173375 86599 173375 86579 173375 86579 173376 86599 173376 86600 173376 86579 173377 86600 173377 86601 173377 86601 173378 86600 173378 86542 173378 86601 173379 86542 173379 86603 173379 86603 173380 86542 173380 86602 173380 86603 173381 86602 173381 86568 173381 86568 173382 86602 173382 86508 173382 86568 173383 86508 173383 86506 173383 86506 173384 86508 173384 86604 173384 86506 173385 86604 173385 86507 173385 86507 173386 86604 173386 86606 173386 86507 173387 86606 173387 86605 173387 86605 173388 86606 173388 86607 173388 86605 173389 86607 173389 86608 173389 86608 173390 86607 173390 86519 173390 86608 173391 86519 173391 86609 173391 86609 173392 86519 173392 86522 173392 86609 173393 86522 173393 86526 173393 86526 173394 86522 173394 86523 173394 86526 173395 86523 173395 86610 173395 86610 173396 86523 173396 86524 173396 86610 173397 86524 173397 86587 173397 86587 173398 86524 173398 86501 173398 86587 173399 86501 173399 86503 173399 86210 173400 86611 173400 86623 173400 86210 173401 86623 173401 86612 173401 86612 173402 86623 173402 86613 173402 86612 173403 86613 173403 86614 173403 86614 173404 86613 173404 86615 173404 86614 173405 86615 173405 86564 173405 86564 173406 86615 173406 86626 173406 86564 173407 86626 173407 86616 173407 86616 173408 86626 173408 86627 173408 86616 173409 86627 173409 86565 173409 86565 173410 86627 173410 86617 173410 86565 173411 86617 173411 86618 173411 86618 173412 86617 173412 86619 173412 86618 173413 86619 173413 86620 173413 86620 173414 86619 173414 86630 173414 86620 173415 86630 173415 86621 173415 86611 173416 86622 173416 86664 173416 86611 173417 86664 173417 86623 173417 86623 173418 86664 173418 86624 173418 86623 173419 86624 173419 86613 173419 86613 173420 86624 173420 86625 173420 86613 173421 86625 173421 86615 173421 86615 173422 86625 173422 86631 173422 86615 173423 86631 173423 86626 173423 86626 173424 86631 173424 86743 173424 86626 173425 86743 173425 86627 173425 86627 173426 86743 173426 86704 173426 86627 173427 86704 173427 86617 173427 86617 173428 86704 173428 86628 173428 86617 173429 86628 173429 86619 173429 86619 173430 86628 173430 86629 173430 86619 173431 86629 173431 86630 173431 86743 173432 86631 173432 86663 173432 86718 173433 86687 173433 86688 173433 86695 173434 86183 173434 86632 173434 86692 173435 86710 173435 86749 173435 86749 173436 86710 173436 86633 173436 86633 173437 86710 173437 86708 173437 86633 173438 86708 173438 86634 173438 86634 173439 86708 173439 86635 173439 86635 173440 86708 173440 86636 173440 86635 173441 86636 173441 86750 173441 86750 173442 86636 173442 86637 173442 86637 173443 86636 173443 86707 173443 86637 173444 86707 173444 86638 173444 86638 173445 86707 173445 86706 173445 86638 173446 86706 173446 86639 173446 86639 173447 86706 173447 86182 173447 86639 173448 86182 173448 86176 173448 86726 173449 86724 173449 86652 173449 86640 173450 86641 173450 86642 173450 86642 173451 86641 173451 86643 173451 86642 173452 86643 173452 86646 173452 86646 173453 86643 173453 86644 173453 86646 173454 86644 173454 86645 173454 86720 173455 86640 173455 86647 173455 86647 173456 86640 173456 86642 173456 86647 173457 86642 173457 86649 173457 86649 173458 86642 173458 86646 173458 86649 173459 86646 173459 86651 173459 86651 173460 86646 173460 86645 173460 86651 173461 86645 173461 86727 173461 86721 173462 86720 173462 86657 173462 86657 173463 86720 173463 86647 173463 86657 173464 86647 173464 86648 173464 86648 173465 86647 173465 86649 173465 86648 173466 86649 173466 86650 173466 86650 173467 86649 173467 86651 173467 86650 173468 86651 173468 86652 173468 86652 173469 86651 173469 86727 173469 86652 173470 86727 173470 86726 173470 86197 173471 86653 173471 86724 173471 86724 173472 86653 173472 86654 173472 86724 173473 86654 173473 86652 173473 86652 173474 86654 173474 86655 173474 86652 173475 86655 173475 86650 173475 86650 173476 86655 173476 86656 173476 86650 173477 86656 173477 86648 173477 86648 173478 86656 173478 86209 173478 86648 173479 86209 173479 86657 173479 86657 173480 86209 173480 86208 173480 86657 173481 86208 173481 86721 173481 86721 173482 86208 173482 86207 173482 86721 173483 86207 173483 86723 173483 86728 173484 86658 173484 86659 173484 86659 173485 86658 173485 86734 173485 86659 173486 86734 173486 86725 173486 86725 173487 86734 173487 86735 173487 86725 173488 86735 173488 86681 173488 86681 173489 86735 173489 86736 173489 86681 173490 86736 173490 86680 173490 86680 173491 86736 173491 86660 173491 86680 173492 86660 173492 86678 173492 86678 173493 86660 173493 86661 173493 86678 173494 86661 173494 86677 173494 86677 173495 86661 173495 86739 173495 86677 173496 86739 173496 86662 173496 86662 173497 86739 173497 86742 173497 86662 173498 86742 173498 86675 173498 86675 173499 86742 173499 86663 173499 86675 173500 86663 173500 86625 173500 86625 173501 86663 173501 86631 173501 86624 173502 86664 173502 86665 173502 86665 173503 86664 173503 86674 173503 86665 173504 86674 173504 86676 173504 86676 173505 86674 173505 86673 173505 86676 173506 86673 173506 86666 173506 86666 173507 86673 173507 86671 173507 86666 173508 86671 173508 86679 173508 86679 173509 86671 173509 86670 173509 86679 173510 86670 173510 86667 173510 86198 173511 86668 173511 86670 173511 86670 173512 86668 173512 86669 173512 86670 173513 86669 173513 86667 173513 86667 173514 86669 173514 86682 173514 86198 173515 86670 173515 86672 173515 86672 173516 86670 173516 86671 173516 86672 173517 86671 173517 86200 173517 86200 173518 86671 173518 86673 173518 86200 173519 86673 173519 86199 173519 86199 173520 86673 173520 86674 173520 86199 173521 86674 173521 86206 173521 86206 173522 86674 173522 86664 173522 86206 173523 86664 173523 86622 173523 86625 173524 86624 173524 86675 173524 86675 173525 86624 173525 86665 173525 86675 173526 86665 173526 86662 173526 86662 173527 86665 173527 86676 173527 86662 173528 86676 173528 86677 173528 86677 173529 86676 173529 86666 173529 86677 173530 86666 173530 86678 173530 86678 173531 86666 173531 86679 173531 86678 173532 86679 173532 86680 173532 86680 173533 86679 173533 86667 173533 86680 173534 86667 173534 86681 173534 86681 173535 86667 173535 86682 173535 86681 173536 86682 173536 86725 173536 86683 173537 86766 173537 86763 173537 86688 173538 86759 173538 86718 173538 86718 173539 86759 173539 86761 173539 86718 173540 86761 173540 86683 173540 86683 173541 86761 173541 86684 173541 86683 173542 86684 173542 86766 173542 86690 173543 86755 173543 86685 173543 86685 173544 86755 173544 86686 173544 86685 173545 86686 173545 86687 173545 86687 173546 86686 173546 86756 173546 86687 173547 86756 173547 86688 173547 86714 173548 86689 173548 86690 173548 86690 173549 86689 173549 86754 173549 86690 173550 86754 173550 86755 173550 86749 173551 86691 173551 86692 173551 86692 173552 86691 173552 86748 173552 86692 173553 86748 173553 86693 173553 86693 173554 86748 173554 86747 173554 86693 173555 86747 173555 86714 173555 86714 173556 86747 173556 86745 173556 86714 173557 86745 173557 86689 173557 86694 173558 86695 173558 86729 173558 86729 173559 86695 173559 86632 173559 86729 173560 86632 173560 86730 173560 86730 173561 86632 173561 86705 173561 86730 173562 86705 173562 86731 173562 86731 173563 86705 173563 86696 173563 86731 173564 86696 173564 86732 173564 86732 173565 86696 173565 86697 173565 86732 173566 86697 173566 86733 173566 86733 173567 86697 173567 86709 173567 86733 173568 86709 173568 86698 173568 86698 173569 86709 173569 86711 173569 86698 173570 86711 173570 86737 173570 86737 173571 86711 173571 86712 173571 86737 173572 86712 173572 86699 173572 86699 173573 86712 173573 86713 173573 86699 173574 86713 173574 86738 173574 86738 173575 86713 173575 86701 173575 86738 173576 86701 173576 86700 173576 86700 173577 86701 173577 86715 173577 86700 173578 86715 173578 86740 173578 86740 173579 86715 173579 86716 173579 86740 173580 86716 173580 86741 173580 86741 173581 86716 173581 86702 173581 86741 173582 86702 173582 86703 173582 86703 173583 86702 173583 86717 173583 86703 173584 86717 173584 86704 173584 86704 173585 86717 173585 86628 173585 86183 173586 86182 173586 86632 173586 86632 173587 86182 173587 86706 173587 86632 173588 86706 173588 86705 173588 86705 173589 86706 173589 86707 173589 86705 173590 86707 173590 86696 173590 86696 173591 86707 173591 86636 173591 86696 173592 86636 173592 86697 173592 86697 173593 86636 173593 86708 173593 86697 173594 86708 173594 86709 173594 86709 173595 86708 173595 86710 173595 86709 173596 86710 173596 86711 173596 86711 173597 86710 173597 86692 173597 86711 173598 86692 173598 86712 173598 86712 173599 86692 173599 86693 173599 86712 173600 86693 173600 86713 173600 86713 173601 86693 173601 86714 173601 86713 173602 86714 173602 86701 173602 86701 173603 86714 173603 86690 173603 86701 173604 86690 173604 86715 173604 86715 173605 86690 173605 86685 173605 86715 173606 86685 173606 86716 173606 86716 173607 86685 173607 86687 173607 86716 173608 86687 173608 86702 173608 86702 173609 86687 173609 86718 173609 86702 173610 86718 173610 86717 173610 86717 173611 86718 173611 86683 173611 86717 173612 86683 173612 86628 173612 86628 173613 86683 173613 86763 173613 86628 173614 86763 173614 86629 173614 86187 173615 86641 173615 86189 173615 86189 173616 86641 173616 86640 173616 86189 173617 86640 173617 86719 173617 86719 173618 86640 173618 86720 173618 86719 173619 86720 173619 86191 173619 86191 173620 86720 173620 86721 173620 86191 173621 86721 173621 86722 173621 86722 173622 86721 173622 86723 173622 86668 173623 86197 173623 86669 173623 86669 173624 86197 173624 86724 173624 86669 173625 86724 173625 86682 173625 86682 173626 86724 173626 86726 173626 86682 173627 86726 173627 86725 173627 86725 173628 86726 173628 86727 173628 86725 173629 86727 173629 86659 173629 86659 173630 86727 173630 86645 173630 86659 173631 86645 173631 86728 173631 86728 173632 86645 173632 86644 173632 86187 173633 86694 173633 86641 173633 86641 173634 86694 173634 86729 173634 86641 173635 86729 173635 86643 173635 86643 173636 86729 173636 86730 173636 86643 173637 86730 173637 86644 173637 86644 173638 86730 173638 86731 173638 86644 173639 86731 173639 86728 173639 86728 173640 86731 173640 86732 173640 86728 173641 86732 173641 86658 173641 86658 173642 86732 173642 86733 173642 86658 173643 86733 173643 86734 173643 86734 173644 86733 173644 86698 173644 86734 173645 86698 173645 86735 173645 86735 173646 86698 173646 86737 173646 86735 173647 86737 173647 86736 173647 86736 173648 86737 173648 86699 173648 86736 173649 86699 173649 86660 173649 86660 173650 86699 173650 86738 173650 86660 173651 86738 173651 86661 173651 86661 173652 86738 173652 86700 173652 86661 173653 86700 173653 86739 173653 86739 173654 86700 173654 86740 173654 86739 173655 86740 173655 86742 173655 86742 173656 86740 173656 86741 173656 86742 173657 86741 173657 86663 173657 86663 173658 86741 173658 86703 173658 86663 173659 86703 173659 86743 173659 86743 173660 86703 173660 86704 173660 86744 173661 86689 173661 87265 173661 87265 173662 86689 173662 86745 173662 87265 173663 86745 173663 87268 173663 87268 173664 86745 173664 86747 173664 87268 173665 86747 173665 86746 173665 86747 173666 86748 173666 86746 173666 86746 173667 86748 173667 86691 173667 86746 173668 86691 173668 87269 173668 87269 173669 86691 173669 86749 173669 87269 173670 86749 173670 87270 173670 86749 173671 86633 173671 87270 173671 87270 173672 86633 173672 86634 173672 87270 173673 86634 173673 87271 173673 87271 173674 86634 173674 86635 173674 87271 173675 86635 173675 87272 173675 87272 173676 86635 173676 86750 173676 87272 173677 86750 173677 87280 173677 87280 173678 86750 173678 87281 173678 87281 173679 86750 173679 86637 173679 87281 173680 86637 173680 86751 173680 86751 173681 86637 173681 86638 173681 86751 173682 86638 173682 86752 173682 86752 173683 86638 173683 86639 173683 86752 173684 86639 173684 86176 173684 86744 173685 87258 173685 86689 173685 86689 173686 87258 173686 86753 173686 86689 173687 86753 173687 86754 173687 86754 173688 86753 173688 87259 173688 86754 173689 87259 173689 86755 173689 86755 173690 87259 173690 87228 173690 86755 173691 87228 173691 86686 173691 86686 173692 87228 173692 87235 173692 86686 173693 87235 173693 86756 173693 86756 173694 87235 173694 87234 173694 86756 173695 87234 173695 86688 173695 87234 173696 86757 173696 86688 173696 86688 173697 86757 173697 86758 173697 86688 173698 86758 173698 86759 173698 86760 173699 87245 173699 86766 173699 86758 173700 87248 173700 86759 173700 86759 173701 87248 173701 87247 173701 86759 173702 87247 173702 86761 173702 86761 173703 87247 173703 86760 173703 86761 173704 86760 173704 86684 173704 86684 173705 86760 173705 86766 173705 86762 173706 86629 173706 86768 173706 86768 173707 86629 173707 86763 173707 87245 173708 86764 173708 86766 173708 86766 173709 86764 173709 86765 173709 86766 173710 86765 173710 86763 173710 86763 173711 86765 173711 86767 173711 86763 173712 86767 173712 86768 173712 86812 173713 87440 173713 86824 173713 86788 173714 86784 173714 86769 173714 86770 173715 86813 173715 86780 173715 86808 173716 86771 173716 86772 173716 86848 173717 86774 173717 86773 173717 86773 173718 86774 173718 86775 173718 86775 173719 86774 173719 86863 173719 86863 173720 86774 173720 86810 173720 86863 173721 86810 173721 86776 173721 86776 173722 86810 173722 86777 173722 86777 173723 86810 173723 86802 173723 86777 173724 86802 173724 86778 173724 86778 173725 86802 173725 86804 173725 86778 173726 86804 173726 86869 173726 86869 173727 86804 173727 86806 173727 86869 173728 86806 173728 86779 173728 86770 173729 86780 173729 86781 173729 86781 173730 86780 173730 86782 173730 86781 173731 86782 173731 86851 173731 86851 173732 86782 173732 86816 173732 86851 173733 86816 173733 86783 173733 86783 173734 86816 173734 86817 173734 86783 173735 86817 173735 86849 173735 86849 173736 86817 173736 86852 173736 86852 173737 86817 173737 86785 173737 86852 173738 86785 173738 86853 173738 86769 173739 86784 173739 86785 173739 86785 173740 86784 173740 86847 173740 86785 173741 86847 173741 86853 173741 87252 173742 86786 173742 86788 173742 86769 173743 86820 173743 86822 173743 86822 173744 87226 173744 86769 173744 86769 173745 87226 173745 86787 173745 86769 173746 86787 173746 86788 173746 86788 173747 86787 173747 87261 173747 86788 173748 87261 173748 87252 173748 86819 173749 87230 173749 86821 173749 87230 173750 86819 173750 86789 173750 86789 173751 86819 173751 86818 173751 86789 173752 86818 173752 87237 173752 86829 173753 86828 173753 87239 173753 87239 173754 86828 173754 86790 173754 87239 173755 86790 173755 86791 173755 86791 173756 86790 173756 86792 173756 86792 173757 86790 173757 86793 173757 86793 173758 86790 173758 86794 173758 86793 173759 86794 173759 86796 173759 86796 173760 86794 173760 86795 173760 86796 173761 86795 173761 86797 173761 86823 173762 87449 173762 86826 173762 86826 173763 87449 173763 86798 173763 86826 173764 86798 173764 86800 173764 86800 173765 86798 173765 86799 173765 86800 173766 86799 173766 86795 173766 86795 173767 86799 173767 86801 173767 86795 173768 86801 173768 86797 173768 86802 173769 86803 173769 86804 173769 86804 173770 86803 173770 86805 173770 86804 173771 86805 173771 86806 173771 86806 173772 86805 173772 86813 173772 86806 173773 86813 173773 86779 173773 86779 173774 86813 173774 86770 173774 86415 173775 86811 173775 86807 173775 86807 173776 86811 173776 86808 173776 86807 173777 86808 173777 86809 173777 86809 173778 86808 173778 86772 173778 86809 173779 86772 173779 86395 173779 86848 173780 86771 173780 86774 173780 86774 173781 86771 173781 86808 173781 86774 173782 86808 173782 86810 173782 86810 173783 86808 173783 86811 173783 86810 173784 86811 173784 86802 173784 86802 173785 86811 173785 86415 173785 86802 173786 86415 173786 86803 173786 86805 173787 86812 173787 86813 173787 86813 173788 86812 173788 86824 173788 86813 173789 86824 173789 86780 173789 86780 173790 86824 173790 86825 173790 86780 173791 86825 173791 86782 173791 86782 173792 86825 173792 86814 173792 86782 173793 86814 173793 86816 173793 86816 173794 86814 173794 86815 173794 86816 173795 86815 173795 86817 173795 86817 173796 86815 173796 86827 173796 86817 173797 86827 173797 86785 173797 86785 173798 86827 173798 86818 173798 86785 173799 86818 173799 86769 173799 86769 173800 86818 173800 86819 173800 86769 173801 86819 173801 86820 173801 86820 173802 86819 173802 86821 173802 86820 173803 86821 173803 86822 173803 87440 173804 86823 173804 86824 173804 86824 173805 86823 173805 86826 173805 86824 173806 86826 173806 86825 173806 86825 173807 86826 173807 86800 173807 86825 173808 86800 173808 86814 173808 86814 173809 86800 173809 86795 173809 86814 173810 86795 173810 86815 173810 86815 173811 86795 173811 86794 173811 86815 173812 86794 173812 86827 173812 86827 173813 86794 173813 86790 173813 86827 173814 86790 173814 86818 173814 86818 173815 86790 173815 86828 173815 86818 173816 86828 173816 87237 173816 87237 173817 86828 173817 86829 173817 86905 173818 86877 173818 86889 173818 86866 173819 86777 173819 86778 173819 86830 173820 86864 173820 86831 173820 86850 173821 86832 173821 86884 173821 86833 173822 86897 173822 86895 173822 85556 173823 86834 173823 86854 173823 85581 173824 86901 173824 86835 173824 86894 173825 92845 173825 86963 173825 85581 173826 86835 173826 85582 173826 85582 173827 86835 173827 86836 173827 85582 173828 86836 173828 85584 173828 85584 173829 86836 173829 86898 173829 85584 173830 86898 173830 86837 173830 86837 173831 86898 173831 86897 173831 86837 173832 86897 173832 85586 173832 85586 173833 86897 173833 86833 173833 85586 173834 86833 173834 86902 173834 86845 173835 85552 173835 86838 173835 86838 173836 85552 173836 85553 173836 86838 173837 85553 173837 85555 173837 86845 173838 87278 173838 92734 173838 92734 173839 87278 173839 86839 173839 92734 173840 86839 173840 86840 173840 86840 173841 86839 173841 87299 173841 86840 173842 87299 173842 85557 173842 85557 173843 87299 173843 86841 173843 85557 173844 86841 173844 85549 173844 85549 173845 86841 173845 87298 173845 85549 173846 87298 173846 85550 173846 85550 173847 87298 173847 87318 173847 87320 173848 86842 173848 87318 173848 87318 173849 86842 173849 92496 173849 87318 173850 92496 173850 85550 173850 87320 173851 87321 173851 86842 173851 86842 173852 87321 173852 86843 173852 86842 173853 86843 173853 86844 173853 87323 173854 92686 173854 86843 173854 86843 173855 92686 173855 85541 173855 86843 173856 85541 173856 86844 173856 86845 173857 86838 173857 87278 173857 87278 173858 86838 173858 86858 173858 87278 173859 86858 173859 87277 173859 87277 173860 86858 173860 86846 173860 86846 173861 86858 173861 86861 173861 86846 173862 86861 173862 87275 173862 87275 173863 86861 173863 87274 173863 87274 173864 86861 173864 86862 173864 87274 173865 86862 173865 87267 173865 87267 173866 86862 173866 86788 173866 87267 173867 86788 173867 86786 173867 86857 173868 86847 173868 86784 173868 86848 173869 86773 173869 86948 173869 86948 173870 86773 173870 86865 173870 86948 173871 86865 173871 86947 173871 86849 173872 86832 173872 86783 173872 86783 173873 86832 173873 86850 173873 86783 173874 86850 173874 86851 173874 86855 173875 86852 173875 86853 173875 86854 173876 86884 173876 86856 173876 86856 173877 86884 173877 86832 173877 86856 173878 86832 173878 86855 173878 86855 173879 86832 173879 86849 173879 86855 173880 86849 173880 86852 173880 85556 173881 86854 173881 86859 173881 86859 173882 86854 173882 86856 173882 86859 173883 86856 173883 86860 173883 86860 173884 86856 173884 86855 173884 86860 173885 86855 173885 86857 173885 86857 173886 86855 173886 86853 173886 86857 173887 86853 173887 86847 173887 85555 173888 85556 173888 86838 173888 86838 173889 85556 173889 86859 173889 86838 173890 86859 173890 86858 173890 86858 173891 86859 173891 86860 173891 86858 173892 86860 173892 86861 173892 86861 173893 86860 173893 86857 173893 86861 173894 86857 173894 86862 173894 86862 173895 86857 173895 86784 173895 86862 173896 86784 173896 86788 173896 86773 173897 86775 173897 86865 173897 86865 173898 86775 173898 86863 173898 86865 173899 86863 173899 86776 173899 86864 173900 86947 173900 86831 173900 86831 173901 86947 173901 86865 173901 86831 173902 86865 173902 86866 173902 86866 173903 86865 173903 86776 173903 86866 173904 86776 173904 86777 173904 86867 173905 86830 173905 86871 173905 86871 173906 86830 173906 86831 173906 86871 173907 86831 173907 86870 173907 86870 173908 86831 173908 86866 173908 86870 173909 86866 173909 86868 173909 86868 173910 86866 173910 86778 173910 86868 173911 86778 173911 86869 173911 86869 173912 86882 173912 86868 173912 86868 173913 86882 173913 86876 173913 86868 173914 86876 173914 86870 173914 86870 173915 86876 173915 86874 173915 86870 173916 86874 173916 86871 173916 86871 173917 86874 173917 86872 173917 86871 173918 86872 173918 86867 173918 86867 173919 86872 173919 86963 173919 86894 173920 86963 173920 86873 173920 86873 173921 86963 173921 86872 173921 86873 173922 86872 173922 86892 173922 86892 173923 86872 173923 86874 173923 86892 173924 86874 173924 86891 173924 86891 173925 86874 173925 86876 173925 86891 173926 86876 173926 86875 173926 86875 173927 86876 173927 86882 173927 86875 173928 86882 173928 86890 173928 86877 173929 86905 173929 86878 173929 86878 173930 86905 173930 86906 173930 86878 173931 86906 173931 86879 173931 86879 173932 86906 173932 86880 173932 86879 173933 86880 173933 86893 173933 86893 173934 86880 173934 85580 173934 86893 173935 85580 173935 86881 173935 86851 173936 86888 173936 86781 173936 86781 173937 86888 173937 86890 173937 86781 173938 86890 173938 86770 173938 86770 173939 86890 173939 86882 173939 86770 173940 86882 173940 86779 173940 86779 173941 86882 173941 86869 173941 86834 173942 86883 173942 86854 173942 86854 173943 86883 173943 86885 173943 86854 173944 86885 173944 86884 173944 86884 173945 86885 173945 86886 173945 86884 173946 86886 173946 86850 173946 86850 173947 86886 173947 86887 173947 86850 173948 86887 173948 86851 173948 86851 173949 86887 173949 86903 173949 86851 173950 86903 173950 86888 173950 86888 173951 86903 173951 86889 173951 86888 173952 86889 173952 86890 173952 86890 173953 86889 173953 86877 173953 86890 173954 86877 173954 86875 173954 86875 173955 86877 173955 86878 173955 86875 173956 86878 173956 86891 173956 86891 173957 86878 173957 86879 173957 86891 173958 86879 173958 86892 173958 86892 173959 86879 173959 86893 173959 86892 173960 86893 173960 86873 173960 86873 173961 86893 173961 86881 173961 86873 173962 86881 173962 86894 173962 86895 173963 86897 173963 86896 173963 86896 173964 86897 173964 86898 173964 86896 173965 86898 173965 86904 173965 86904 173966 86898 173966 86836 173966 86904 173967 86836 173967 86899 173967 86899 173968 86836 173968 86835 173968 86899 173969 86835 173969 86907 173969 86907 173970 86835 173970 86901 173970 86907 173971 86901 173971 86900 173971 86900 173972 86901 173972 85581 173972 86900 173973 85581 173973 92723 173973 86883 173974 86902 173974 86885 173974 86885 173975 86902 173975 86833 173975 86885 173976 86833 173976 86886 173976 86886 173977 86833 173977 86895 173977 86886 173978 86895 173978 86887 173978 86887 173979 86895 173979 86896 173979 86887 173980 86896 173980 86903 173980 86903 173981 86896 173981 86904 173981 86903 173982 86904 173982 86889 173982 86889 173983 86904 173983 86899 173983 86889 173984 86899 173984 86905 173984 86905 173985 86899 173985 86907 173985 86905 173986 86907 173986 86906 173986 86906 173987 86907 173987 86900 173987 86906 173988 86900 173988 86880 173988 86880 173989 86900 173989 92723 173989 86880 173990 92723 173990 85580 173990 86972 173991 86908 173991 86943 173991 86451 173992 86848 173992 86948 173992 86918 173993 87085 173993 86917 173993 92804 173994 87099 173994 86912 173994 87085 173995 86918 173995 86909 173995 86918 173996 86910 173996 86909 173996 86909 173997 86910 173997 85576 173997 86909 173998 85576 173998 86911 173998 86911 173999 85576 173999 92523 173999 86911 174000 92523 174000 86912 174000 86912 174001 92523 174001 85569 174001 86912 174002 85569 174002 92804 174002 86913 174003 92818 174003 86914 174003 86913 174004 86914 174004 86915 174004 86914 174005 85563 174005 86915 174005 86915 174006 85563 174006 92841 174006 86915 174007 92841 174007 86916 174007 86916 174008 92841 174008 85562 174008 86916 174009 85562 174009 86917 174009 86917 174010 85562 174010 92838 174010 86917 174011 92838 174011 86918 174011 86919 174012 86920 174012 86935 174012 86935 174013 86920 174013 86921 174013 86935 174014 86921 174014 86922 174014 86973 174015 86975 174015 86924 174015 86924 174016 92516 174016 86973 174016 86973 174017 92516 174017 86919 174017 86973 174018 86919 174018 86923 174018 86923 174019 86919 174019 86935 174019 86923 174020 86935 174020 86971 174020 86925 174021 86927 174021 86975 174021 86975 174022 86927 174022 92518 174022 86975 174023 92518 174023 86924 174023 86925 174024 86926 174024 86927 174024 86927 174025 86926 174025 86978 174025 86927 174026 86978 174026 85588 174026 85588 174027 86978 174027 86928 174027 85588 174028 86928 174028 85589 174028 85589 174029 86928 174029 86980 174029 85589 174030 86980 174030 85590 174030 85590 174031 86980 174031 86958 174031 85590 174032 86958 174032 86929 174032 86929 174033 86958 174033 86959 174033 86929 174034 86959 174034 85592 174034 85592 174035 86959 174035 86961 174035 85592 174036 86961 174036 86930 174036 86930 174037 86961 174037 86962 174037 86930 174038 86962 174038 85593 174038 85593 174039 86962 174039 86931 174039 85593 174040 86931 174040 85595 174040 85595 174041 86931 174041 86963 174041 85595 174042 86963 174042 92845 174042 86951 174043 86950 174043 86949 174043 86932 174044 86933 174044 86937 174044 87049 174045 86937 174045 86934 174045 86934 174046 86937 174046 86933 174046 86934 174047 86933 174047 87050 174047 92818 174048 86913 174048 86922 174048 86922 174049 86913 174049 87067 174049 86922 174050 87067 174050 86935 174050 86935 174051 87067 174051 87069 174051 86935 174052 87069 174052 86971 174052 86445 174053 86448 174053 86936 174053 86937 174054 86440 174054 86932 174054 86932 174055 86440 174055 86439 174055 86932 174056 86439 174056 86938 174056 86439 174057 86443 174057 86938 174057 86938 174058 86443 174058 86441 174058 86938 174059 86441 174059 86940 174059 86940 174060 86441 174060 86939 174060 86940 174061 86939 174061 86946 174061 86946 174062 86939 174062 86941 174062 86946 174063 86941 174063 86942 174063 86908 174064 87050 174064 86943 174064 86943 174065 87050 174065 86933 174065 86943 174066 86933 174066 86944 174066 86944 174067 86933 174067 86932 174067 86944 174068 86932 174068 86974 174068 86974 174069 86932 174069 86938 174069 86974 174070 86938 174070 86976 174070 86976 174071 86938 174071 86940 174071 86976 174072 86940 174072 86977 174072 86977 174073 86940 174073 86946 174073 86977 174074 86946 174074 86945 174074 86945 174075 86946 174075 86942 174075 86945 174076 86942 174076 86979 174076 86979 174077 86942 174077 86983 174077 86979 174078 86983 174078 86981 174078 86981 174079 86983 174079 86984 174079 86864 174080 86830 174080 86990 174080 86947 174081 86951 174081 86948 174081 86948 174082 86951 174082 86949 174082 86948 174083 86949 174083 86451 174083 86950 174084 86951 174084 86429 174084 86429 174085 86951 174085 86952 174085 86429 174086 86952 174086 86469 174086 86469 174087 86952 174087 86953 174087 86469 174088 86953 174088 86954 174088 86954 174089 86953 174089 86956 174089 86956 174090 86953 174090 86955 174090 86956 174091 86955 174091 86450 174091 86450 174092 86955 174092 86957 174092 86450 174093 86957 174093 86449 174093 86958 174094 86960 174094 86959 174094 86959 174095 86960 174095 86987 174095 86959 174096 86987 174096 86961 174096 86961 174097 86987 174097 86989 174097 86961 174098 86989 174098 86962 174098 86962 174099 86989 174099 86991 174099 86962 174100 86991 174100 86931 174100 86931 174101 86991 174101 86867 174101 86931 174102 86867 174102 86963 174102 86448 174103 86449 174103 86936 174103 86936 174104 86449 174104 86957 174104 86936 174105 86957 174105 86969 174105 86969 174106 86957 174106 86955 174106 86969 174107 86955 174107 86964 174107 86964 174108 86955 174108 86953 174108 86964 174109 86953 174109 86965 174109 86965 174110 86953 174110 86952 174110 86965 174111 86952 174111 86967 174111 86967 174112 86952 174112 86951 174112 86967 174113 86951 174113 86966 174113 86966 174114 86951 174114 86947 174114 86966 174115 86947 174115 86864 174115 86864 174116 86990 174116 86966 174116 86966 174117 86990 174117 86988 174117 86966 174118 86988 174118 86967 174118 86967 174119 86988 174119 86986 174119 86967 174120 86986 174120 86965 174120 86965 174121 86986 174121 86985 174121 86965 174122 86985 174122 86964 174122 86964 174123 86985 174123 86968 174123 86964 174124 86968 174124 86969 174124 86969 174125 86968 174125 86970 174125 86969 174126 86970 174126 86936 174126 87069 174127 86972 174127 86971 174127 86971 174128 86972 174128 86943 174128 86971 174129 86943 174129 86923 174129 86923 174130 86943 174130 86944 174130 86923 174131 86944 174131 86973 174131 86973 174132 86944 174132 86974 174132 86973 174133 86974 174133 86975 174133 86975 174134 86974 174134 86976 174134 86975 174135 86976 174135 86925 174135 86925 174136 86976 174136 86977 174136 86925 174137 86977 174137 86926 174137 86926 174138 86977 174138 86945 174138 86926 174139 86945 174139 86978 174139 86978 174140 86945 174140 86979 174140 86978 174141 86979 174141 86928 174141 86928 174142 86979 174142 86981 174142 86928 174143 86981 174143 86980 174143 86980 174144 86981 174144 86984 174144 86980 174145 86984 174145 86958 174145 86958 174146 86984 174146 86982 174146 86958 174147 86982 174147 86960 174147 86941 174148 86445 174148 86942 174148 86942 174149 86445 174149 86936 174149 86942 174150 86936 174150 86983 174150 86983 174151 86936 174151 86970 174151 86983 174152 86970 174152 86984 174152 86984 174153 86970 174153 86968 174153 86984 174154 86968 174154 86982 174154 86982 174155 86968 174155 86985 174155 86982 174156 86985 174156 86960 174156 86960 174157 86985 174157 86986 174157 86960 174158 86986 174158 86987 174158 86987 174159 86986 174159 86988 174159 86987 174160 86988 174160 86989 174160 86989 174161 86988 174161 86990 174161 86989 174162 86990 174162 86991 174162 86991 174163 86990 174163 86830 174163 86991 174164 86830 174164 86867 174164 86995 174165 86993 174165 86992 174165 86993 174166 86995 174166 86994 174166 86994 174167 86995 174167 86996 174167 86994 174168 86996 174168 87596 174168 86997 174169 86998 174169 86999 174169 86365 174170 87000 174170 86998 174170 86998 174171 87000 174171 87001 174171 86998 174172 87001 174172 86999 174172 86999 174173 86992 174173 86997 174173 86997 174174 86992 174174 86993 174174 86997 174175 86993 174175 86464 174175 86464 174176 86993 174176 86994 174176 86366 174177 86365 174177 87004 174177 87004 174178 86365 174178 86998 174178 87004 174179 86998 174179 87002 174179 87002 174180 86998 174180 86997 174180 87002 174181 86997 174181 87006 174181 87006 174182 86997 174182 86464 174182 86364 174183 86366 174183 87003 174183 87003 174184 86366 174184 87004 174184 87003 174185 87004 174185 87005 174185 87005 174186 87004 174186 87002 174186 87005 174187 87002 174187 87008 174187 87008 174188 87002 174188 87006 174188 87009 174189 86364 174189 87012 174189 87012 174190 86364 174190 87003 174190 87012 174191 87003 174191 87007 174191 87007 174192 87003 174192 87005 174192 87007 174193 87005 174193 87013 174193 87013 174194 87005 174194 87008 174194 87020 174195 87009 174195 87010 174195 87010 174196 87009 174196 87012 174196 87010 174197 87012 174197 87011 174197 87011 174198 87012 174198 87007 174198 87011 174199 87007 174199 87039 174199 87039 174200 87007 174200 87013 174200 87040 174201 86489 174201 86487 174201 86437 174202 87046 174202 87031 174202 87046 174203 87040 174203 87024 174203 87024 174204 87040 174204 86487 174204 87024 174205 86487 174205 87015 174205 87015 174206 86487 174206 87014 174206 86434 174207 86433 174207 87031 174207 87031 174208 86433 174208 86438 174208 87031 174209 86438 174209 86437 174209 87014 174210 87016 174210 87015 174210 87015 174211 87016 174211 87018 174211 87015 174212 87018 174212 87017 174212 87017 174213 87018 174213 86484 174213 87017 174214 86484 174214 87025 174214 87025 174215 86484 174215 87019 174215 87025 174216 87019 174216 87027 174216 87020 174217 87010 174217 87021 174217 87021 174218 87010 174218 87028 174218 87021 174219 87028 174219 86481 174219 86481 174220 87028 174220 87022 174220 86481 174221 87022 174221 87023 174221 87023 174222 87022 174222 87027 174222 87023 174223 87027 174223 86482 174223 86482 174224 87027 174224 87019 174224 87046 174225 87024 174225 87031 174225 87031 174226 87024 174226 87015 174226 87031 174227 87015 174227 87032 174227 87032 174228 87015 174228 87017 174228 87032 174229 87017 174229 87026 174229 87026 174230 87017 174230 87025 174230 87026 174231 87025 174231 87033 174231 87033 174232 87025 174232 87027 174232 87033 174233 87027 174233 87035 174233 87035 174234 87027 174234 87022 174234 87035 174235 87022 174235 87037 174235 87037 174236 87022 174236 87028 174236 87037 174237 87028 174237 87029 174237 87029 174238 87028 174238 87010 174238 87029 174239 87010 174239 87011 174239 86434 174240 87031 174240 87030 174240 87030 174241 87031 174241 87032 174241 87030 174242 87032 174242 86480 174242 86480 174243 87032 174243 87026 174243 86480 174244 87026 174244 86431 174244 86431 174245 87026 174245 87033 174245 86431 174246 87033 174246 87034 174246 87034 174247 87033 174247 87035 174247 87034 174248 87035 174248 87036 174248 87036 174249 87035 174249 87037 174249 87036 174250 87037 174250 86432 174250 86432 174251 87037 174251 87029 174251 86432 174252 87029 174252 87038 174252 87038 174253 87029 174253 87011 174253 87038 174254 87011 174254 87039 174254 87043 174255 86489 174255 87040 174255 87052 174256 86493 174256 87044 174256 87047 174257 87041 174257 87045 174257 87045 174258 87041 174258 87042 174258 87045 174259 87042 174259 87044 174259 86493 174260 87043 174260 87044 174260 87044 174261 87043 174261 87040 174261 87044 174262 87040 174262 87045 174262 87045 174263 87040 174263 87046 174263 87045 174264 87046 174264 87047 174264 87047 174265 87046 174265 86437 174265 87047 174266 86437 174266 87049 174266 87064 174267 86499 174267 87062 174267 87070 174268 87041 174268 87047 174268 87044 174269 87042 174269 87048 174269 87048 174270 87042 174270 87041 174270 87076 174271 87052 174271 87044 174271 87050 174272 87070 174272 86934 174272 86934 174273 87070 174273 87047 174273 86934 174274 87047 174274 87049 174274 86908 174275 87072 174275 87050 174275 87050 174276 87072 174276 87051 174276 87050 174277 87051 174277 87070 174277 86493 174278 87052 174278 86492 174278 86492 174279 87052 174279 87076 174279 86492 174280 87076 174280 87053 174280 87053 174281 87076 174281 87077 174281 87053 174282 87077 174282 87054 174282 87054 174283 87077 174283 87058 174283 87055 174284 87056 174284 87058 174284 87058 174285 87056 174285 87057 174285 87058 174286 87057 174286 87054 174286 87058 174287 87059 174287 87055 174287 87055 174288 87059 174288 87060 174288 87055 174289 87060 174289 87061 174289 87061 174290 87060 174290 86497 174290 86497 174291 87060 174291 87062 174291 87062 174292 87060 174292 87063 174292 87062 174293 87063 174293 87064 174293 86917 174294 87065 174294 86916 174294 86916 174295 87065 174295 87075 174295 86916 174296 87075 174296 86915 174296 86915 174297 87075 174297 87066 174297 86915 174298 87066 174298 86913 174298 86913 174299 87066 174299 87074 174299 86913 174300 87074 174300 87067 174300 87067 174301 87074 174301 87068 174301 87067 174302 87068 174302 87069 174302 87069 174303 87068 174303 87072 174303 87069 174304 87072 174304 86972 174304 86972 174305 87072 174305 86908 174305 87041 174306 87070 174306 87048 174306 87048 174307 87070 174307 87051 174307 87048 174308 87051 174308 87071 174308 87071 174309 87051 174309 87072 174309 87071 174310 87072 174310 87073 174310 87073 174311 87072 174311 87068 174311 87073 174312 87068 174312 87078 174312 87078 174313 87068 174313 87074 174313 87078 174314 87074 174314 87079 174314 87079 174315 87074 174315 87066 174315 87079 174316 87066 174316 87080 174316 87080 174317 87066 174317 87075 174317 87080 174318 87075 174318 87081 174318 87081 174319 87075 174319 87065 174319 87081 174320 87065 174320 87084 174320 87044 174321 87048 174321 87076 174321 87076 174322 87048 174322 87071 174322 87076 174323 87071 174323 87077 174323 87077 174324 87071 174324 87073 174324 87077 174325 87073 174325 87058 174325 87058 174326 87073 174326 87078 174326 87058 174327 87078 174327 87059 174327 87059 174328 87078 174328 87079 174328 87059 174329 87079 174329 87060 174329 87060 174330 87079 174330 87080 174330 87060 174331 87080 174331 87063 174331 87063 174332 87080 174332 87081 174332 87063 174333 87081 174333 87064 174333 87064 174334 87081 174334 87084 174334 87064 174335 87084 174335 87082 174335 87082 174336 86502 174336 87064 174336 87064 174337 86502 174337 87083 174337 87064 174338 87083 174338 86499 174338 87065 174339 86917 174339 87085 174339 87084 174340 87065 174340 87088 174340 87082 174341 87084 174341 87089 174341 86502 174342 87082 174342 87093 174342 87065 174343 87085 174343 87088 174343 87088 174344 87085 174344 86909 174344 87088 174345 86909 174345 87086 174345 87086 174346 86909 174346 86911 174346 87086 174347 86911 174347 87087 174347 87087 174348 86911 174348 86912 174348 87087 174349 86912 174349 87092 174349 87092 174350 86912 174350 87099 174350 87092 174351 87099 174351 87102 174351 87084 174352 87088 174352 87089 174352 87089 174353 87088 174353 87086 174353 87089 174354 87086 174354 87090 174354 87090 174355 87086 174355 87087 174355 87090 174356 87087 174356 87091 174356 87091 174357 87087 174357 87092 174357 87091 174358 87092 174358 87094 174358 87094 174359 87092 174359 87102 174359 87094 174360 87102 174360 87100 174360 87082 174361 87089 174361 87093 174361 87093 174362 87089 174362 87090 174362 87093 174363 87090 174363 87095 174363 87095 174364 87090 174364 87091 174364 87095 174365 87091 174365 87097 174365 87097 174366 87091 174366 87094 174366 87097 174367 87094 174367 87098 174367 87098 174368 87094 174368 87100 174368 87098 174369 87100 174369 87118 174369 86502 174370 87093 174370 86245 174370 86245 174371 87093 174371 87095 174371 86245 174372 87095 174372 86244 174372 86244 174373 87095 174373 87097 174373 86244 174374 87097 174374 87096 174374 87096 174375 87097 174375 87098 174375 87096 174376 87098 174376 86246 174376 86246 174377 87098 174377 87118 174377 86246 174378 87118 174378 86247 174378 87102 174379 87099 174379 86262 174379 87100 174380 87102 174380 87101 174380 87118 174381 87100 174381 87119 174381 86247 174382 87118 174382 87127 174382 87102 174383 86262 174383 87101 174383 87101 174384 86262 174384 87103 174384 87101 174385 87103 174385 87104 174385 87104 174386 87103 174386 87105 174386 87104 174387 87105 174387 87106 174387 87106 174388 87105 174388 87107 174388 87106 174389 87107 174389 87108 174389 87108 174390 87107 174390 87109 174390 87108 174391 87109 174391 87115 174391 87115 174392 87109 174392 87110 174392 87115 174393 87110 174393 87116 174393 87116 174394 87110 174394 87111 174394 87116 174395 87111 174395 87117 174395 87100 174396 87101 174396 87119 174396 87119 174397 87101 174397 87104 174397 87119 174398 87104 174398 87112 174398 87112 174399 87104 174399 87106 174399 87112 174400 87106 174400 87113 174400 87113 174401 87106 174401 87108 174401 87113 174402 87108 174402 87114 174402 87114 174403 87108 174403 87115 174403 87114 174404 87115 174404 87123 174404 87123 174405 87115 174405 87116 174405 87123 174406 87116 174406 87125 174406 87125 174407 87116 174407 87117 174407 87125 174408 87117 174408 87126 174408 87118 174409 87119 174409 87127 174409 87127 174410 87119 174410 87112 174410 87127 174411 87112 174411 87120 174411 87120 174412 87112 174412 87113 174412 87120 174413 87113 174413 87121 174413 87121 174414 87113 174414 87114 174414 87121 174415 87114 174415 87122 174415 87122 174416 87114 174416 87123 174416 87122 174417 87123 174417 87124 174417 87124 174418 87123 174418 87125 174418 87124 174419 87125 174419 87132 174419 87132 174420 87125 174420 87126 174420 87132 174421 87126 174421 87134 174421 86247 174422 87127 174422 87128 174422 87128 174423 87127 174423 87120 174423 87128 174424 87120 174424 87129 174424 87129 174425 87120 174425 87121 174425 87129 174426 87121 174426 86248 174426 86248 174427 87121 174427 87122 174427 86248 174428 87122 174428 87130 174428 87130 174429 87122 174429 87124 174429 87130 174430 87124 174430 87131 174430 87131 174431 87124 174431 87132 174431 87131 174432 87132 174432 87133 174432 87133 174433 87132 174433 87134 174433 87133 174434 87134 174434 87141 174434 86287 174435 86265 174435 87143 174435 85827 174436 87135 174436 87161 174436 87161 174437 87135 174437 87136 174437 87161 174438 87136 174438 87160 174438 87160 174439 87136 174439 87148 174439 87160 174440 87148 174440 87137 174440 87137 174441 87148 174441 87158 174441 87158 174442 87148 174442 87138 174442 87158 174443 87138 174443 87139 174443 87139 174444 87138 174444 86266 174444 87139 174445 86266 174445 85706 174445 86287 174446 87143 174446 87111 174446 87144 174447 87141 174447 87140 174447 87140 174448 87141 174448 87134 174448 87140 174449 87134 174449 87142 174449 87142 174450 87134 174450 87126 174450 87142 174451 87126 174451 87143 174451 87143 174452 87126 174452 87117 174452 87143 174453 87117 174453 87111 174453 86265 174454 87149 174454 87143 174454 87143 174455 87149 174455 87150 174455 87143 174456 87150 174456 87142 174456 87142 174457 87150 174457 87152 174457 87142 174458 87152 174458 87140 174458 87140 174459 87152 174459 87145 174459 87140 174460 87145 174460 87144 174460 87154 174461 87146 174461 87145 174461 87145 174462 87146 174462 87147 174462 87145 174463 87147 174463 87144 174463 86293 174464 86266 174464 87151 174464 87151 174465 86266 174465 87138 174465 87151 174466 87138 174466 87153 174466 87153 174467 87138 174467 87148 174467 87153 174468 87148 174468 87155 174468 87155 174469 87148 174469 87136 174469 87149 174470 86293 174470 87150 174470 87150 174471 86293 174471 87151 174471 87150 174472 87151 174472 87152 174472 87152 174473 87151 174473 87153 174473 87152 174474 87153 174474 87145 174474 87145 174475 87153 174475 87155 174475 87145 174476 87155 174476 87154 174476 87154 174477 87155 174477 87136 174477 87154 174478 87136 174478 85834 174478 85834 174479 87136 174479 87135 174479 85831 174480 85829 174480 87156 174480 85706 174481 87157 174481 87139 174481 87139 174482 87157 174482 87159 174482 87139 174483 87159 174483 87158 174483 87158 174484 87159 174484 87137 174484 87137 174485 87159 174485 87160 174485 87160 174486 87159 174486 87156 174486 87160 174487 87156 174487 87161 174487 87161 174488 87156 174488 85829 174488 87161 174489 85829 174489 85827 174489 85826 174490 85831 174490 87162 174490 87162 174491 85831 174491 87156 174491 87162 174492 87156 174492 87163 174492 87163 174493 87156 174493 87159 174493 87163 174494 87159 174494 87164 174494 87164 174495 87159 174495 87157 174495 87163 174496 87164 174496 85695 174496 87162 174497 87163 174497 87165 174497 85826 174498 87162 174498 87178 174498 85826 174499 87178 174499 85825 174499 85825 174500 87178 174500 87167 174500 85825 174501 87167 174501 85822 174501 85822 174502 87167 174502 87166 174502 87166 174503 87167 174503 87179 174503 87166 174504 87179 174504 87168 174504 87168 174505 87179 174505 87180 174505 87168 174506 87180 174506 87170 174506 87170 174507 87180 174507 87169 174507 87170 174508 87169 174508 85821 174508 87163 174509 85695 174509 87165 174509 87165 174510 85695 174510 85743 174510 87165 174511 85743 174511 87171 174511 87171 174512 85743 174512 85708 174512 87171 174513 85708 174513 87172 174513 87172 174514 85708 174514 87173 174514 87172 174515 87173 174515 87181 174515 87181 174516 87173 174516 85727 174516 87181 174517 85727 174517 87174 174517 87174 174518 85727 174518 87175 174518 87174 174519 87175 174519 87182 174519 87182 174520 87175 174520 87176 174520 87182 174521 87176 174521 87183 174521 87183 174522 87176 174522 85711 174522 87183 174523 85711 174523 87184 174523 87184 174524 85711 174524 85712 174524 87184 174525 85712 174525 87177 174525 87162 174526 87165 174526 87178 174526 87178 174527 87165 174527 87171 174527 87178 174528 87171 174528 87167 174528 87167 174529 87171 174529 87172 174529 87167 174530 87172 174530 87179 174530 87179 174531 87172 174531 87181 174531 87179 174532 87181 174532 87180 174532 87180 174533 87181 174533 87174 174533 87180 174534 87174 174534 87169 174534 87169 174535 87174 174535 87182 174535 87169 174536 87182 174536 87186 174536 87186 174537 87182 174537 87183 174537 87186 174538 87183 174538 87187 174538 87187 174539 87183 174539 87184 174539 87187 174540 87184 174540 87188 174540 87188 174541 87184 174541 87177 174541 87188 174542 87177 174542 87191 174542 85821 174543 87169 174543 85819 174543 85819 174544 87169 174544 87186 174544 85819 174545 87186 174545 87185 174545 87185 174546 87186 174546 87187 174546 87185 174547 87187 174547 87189 174547 87189 174548 87187 174548 87188 174548 87189 174549 87188 174549 85818 174549 85818 174550 87188 174550 87191 174550 85818 174551 87191 174551 85816 174551 87190 174552 85816 174552 87193 174552 87193 174553 85816 174553 87191 174553 87193 174554 87191 174554 87195 174554 87195 174555 87191 174555 87177 174555 87195 174556 87177 174556 85717 174556 85717 174557 87177 174557 85712 174557 87192 174558 87190 174558 87194 174558 87194 174559 87190 174559 87193 174559 87194 174560 87193 174560 87207 174560 87207 174561 87193 174561 87195 174561 87207 174562 87195 174562 85716 174562 85716 174563 87195 174563 85717 174563 87616 174564 87196 174564 87198 174564 87619 174565 87617 174565 87199 174565 87199 174566 87617 174566 87616 174566 87622 174567 87197 174567 87200 174567 87200 174568 87197 174568 87619 174568 87204 174569 87623 174569 87622 174569 87616 174570 87198 174570 87199 174570 87199 174571 87198 174571 85636 174571 87199 174572 85636 174572 87201 174572 87201 174573 85636 174573 85635 174573 87201 174574 85635 174574 87202 174574 87202 174575 85635 174575 87192 174575 87202 174576 87192 174576 87194 174576 87619 174577 87199 174577 87200 174577 87200 174578 87199 174578 87201 174578 87200 174579 87201 174579 87203 174579 87203 174580 87201 174580 87202 174580 87203 174581 87202 174581 87206 174581 87206 174582 87202 174582 87194 174582 87206 174583 87194 174583 87207 174583 87622 174584 87200 174584 87204 174584 87204 174585 87200 174585 87203 174585 87204 174586 87203 174586 85715 174586 85715 174587 87203 174587 87206 174587 85715 174588 87206 174588 87205 174588 87205 174589 87206 174589 87207 174589 87205 174590 87207 174590 85716 174590 87212 174591 87208 174591 87217 174591 87212 174592 87471 174592 87210 174592 87210 174593 87471 174593 87476 174593 87208 174594 87212 174594 87213 174594 86798 174595 87449 174595 87217 174595 87476 174596 86408 174596 87210 174596 87210 174597 86408 174597 87209 174597 87210 174598 87209 174598 87215 174598 87215 174599 87209 174599 87211 174599 87215 174600 87211 174600 87216 174600 87212 174601 87210 174601 87213 174601 87213 174602 87210 174602 87215 174602 87213 174603 87215 174603 87214 174603 87214 174604 87215 174604 87216 174604 87214 174605 87216 174605 87218 174605 87217 174606 87208 174606 86798 174606 86798 174607 87208 174607 87213 174607 86798 174608 87213 174608 86799 174608 86799 174609 87213 174609 87214 174609 86799 174610 87214 174610 86801 174610 86801 174611 87214 174611 87218 174611 86801 174612 87218 174612 86797 174612 86796 174613 86797 174613 87222 174613 87222 174614 86797 174614 87218 174614 87222 174615 87218 174615 87223 174615 87223 174616 87218 174616 87216 174616 87223 174617 87216 174617 87219 174617 87219 174618 87216 174618 87211 174618 86793 174619 86796 174619 87220 174619 87220 174620 86796 174620 87222 174620 87220 174621 87222 174621 87221 174621 87221 174622 87222 174622 87223 174622 87221 174623 87223 174623 86767 174623 86767 174624 87223 174624 87219 174624 87260 174625 87261 174625 86787 174625 87224 174626 87260 174626 87225 174626 87260 174627 86787 174627 87225 174627 87225 174628 86787 174628 87226 174628 87225 174629 87226 174629 87227 174629 87233 174630 87228 174630 87229 174630 87229 174631 87228 174631 87259 174631 87229 174632 87259 174632 87224 174632 87230 174633 87236 174633 86821 174633 86821 174634 87236 174634 87227 174634 86821 174635 87227 174635 86822 174635 86822 174636 87227 174636 87226 174636 87243 174637 86758 174637 87231 174637 87231 174638 86758 174638 86757 174638 87231 174639 86757 174639 87232 174639 87232 174640 86757 174640 87234 174640 87232 174641 87234 174641 87233 174641 87233 174642 87234 174642 87235 174642 87233 174643 87235 174643 87228 174643 87230 174644 86789 174644 87236 174644 87236 174645 86789 174645 87237 174645 87236 174646 87237 174646 87241 174646 87241 174647 87237 174647 86829 174647 87241 174648 86829 174648 87238 174648 87238 174649 86829 174649 87239 174649 87238 174650 87239 174650 87242 174650 87242 174651 87239 174651 86791 174651 87242 174652 86791 174652 87240 174652 87240 174653 86791 174653 86792 174653 87240 174654 86792 174654 87250 174654 87224 174655 87225 174655 87229 174655 87229 174656 87225 174656 87227 174656 87229 174657 87227 174657 87233 174657 87233 174658 87227 174658 87236 174658 87233 174659 87236 174659 87232 174659 87232 174660 87236 174660 87241 174660 87232 174661 87241 174661 87231 174661 87231 174662 87241 174662 87238 174662 87231 174663 87238 174663 87243 174663 87243 174664 87238 174664 87242 174664 87243 174665 87242 174665 87246 174665 87246 174666 87242 174666 87240 174666 87246 174667 87240 174667 87244 174667 87244 174668 87240 174668 87250 174668 87244 174669 87250 174669 87249 174669 86765 174670 86764 174670 87249 174670 87249 174671 86764 174671 87245 174671 87249 174672 87245 174672 87244 174672 87244 174673 87245 174673 86760 174673 87244 174674 86760 174674 87246 174674 87246 174675 86760 174675 87247 174675 87246 174676 87247 174676 87243 174676 87243 174677 87247 174677 87248 174677 87243 174678 87248 174678 86758 174678 86767 174679 86765 174679 87221 174679 87221 174680 86765 174680 87249 174680 87221 174681 87249 174681 87220 174681 87220 174682 87249 174682 87250 174682 87220 174683 87250 174683 86793 174683 86793 174684 87250 174684 86792 174684 86753 174685 87258 174685 87257 174685 87255 174686 87262 174686 87257 174686 86786 174687 87252 174687 87251 174687 87251 174688 87252 174688 87253 174688 87251 174689 87253 174689 87254 174689 87257 174690 87262 174690 87253 174690 87253 174691 87262 174691 87264 174691 87253 174692 87264 174692 87254 174692 87255 174693 87257 174693 87256 174693 87256 174694 87257 174694 87258 174694 87256 174695 87258 174695 86744 174695 87259 174696 86753 174696 87224 174696 87224 174697 86753 174697 87257 174697 87224 174698 87257 174698 87260 174698 87260 174699 87257 174699 87253 174699 87260 174700 87253 174700 87261 174700 87261 174701 87253 174701 87252 174701 87256 174702 86744 174702 87265 174702 87262 174703 87255 174703 87263 174703 87263 174704 87255 174704 87256 174704 87254 174705 87264 174705 87284 174705 87284 174706 87264 174706 87262 174706 86786 174707 87251 174707 87266 174707 87266 174708 87251 174708 87254 174708 87256 174709 87265 174709 87263 174709 87263 174710 87265 174710 87268 174710 87263 174711 87268 174711 87285 174711 86786 174712 87266 174712 87267 174712 87267 174713 87266 174713 87292 174713 87267 174714 87292 174714 87274 174714 87268 174715 86746 174715 87285 174715 87285 174716 86746 174716 87269 174716 87285 174717 87269 174717 87287 174717 87287 174718 87269 174718 87270 174718 87287 174719 87270 174719 87288 174719 87270 174720 87271 174720 87288 174720 87288 174721 87271 174721 87272 174721 87288 174722 87272 174722 87273 174722 87273 174723 87272 174723 87280 174723 87273 174724 87280 174724 87282 174724 87274 174725 87292 174725 87275 174725 87275 174726 87292 174726 87293 174726 87275 174727 87293 174727 86846 174727 86846 174728 87293 174728 87295 174728 86846 174729 87295 174729 87277 174729 87277 174730 87295 174730 87276 174730 87277 174731 87276 174731 87278 174731 87278 174732 87276 174732 87296 174732 87278 174733 87296 174733 86839 174733 86839 174734 87296 174734 87279 174734 86839 174735 87279 174735 87299 174735 87280 174736 87281 174736 87282 174736 87282 174737 87281 174737 86751 174737 87282 174738 86751 174738 87283 174738 87283 174739 86751 174739 86752 174739 87283 174740 86752 174740 87303 174740 87262 174741 87263 174741 87284 174741 87284 174742 87263 174742 87285 174742 87284 174743 87285 174743 87291 174743 87291 174744 87285 174744 87287 174744 87291 174745 87287 174745 87286 174745 87286 174746 87287 174746 87288 174746 87286 174747 87288 174747 87294 174747 87294 174748 87288 174748 87273 174748 87294 174749 87273 174749 87289 174749 87289 174750 87273 174750 87282 174750 87289 174751 87282 174751 87290 174751 87290 174752 87282 174752 87283 174752 87290 174753 87283 174753 87297 174753 87297 174754 87283 174754 87303 174754 87297 174755 87303 174755 87301 174755 87254 174756 87284 174756 87266 174756 87266 174757 87284 174757 87291 174757 87266 174758 87291 174758 87292 174758 87292 174759 87291 174759 87286 174759 87292 174760 87286 174760 87293 174760 87293 174761 87286 174761 87294 174761 87293 174762 87294 174762 87295 174762 87295 174763 87294 174763 87289 174763 87295 174764 87289 174764 87276 174764 87276 174765 87289 174765 87290 174765 87276 174766 87290 174766 87296 174766 87296 174767 87290 174767 87297 174767 87296 174768 87297 174768 87279 174768 87279 174769 87297 174769 87301 174769 87279 174770 87301 174770 87302 174770 87302 174771 87298 174771 87279 174771 87279 174772 87298 174772 86841 174772 87279 174773 86841 174773 87299 174773 87303 174774 86752 174774 87300 174774 87301 174775 87303 174775 87307 174775 87302 174776 87301 174776 87312 174776 87298 174777 87302 174777 87313 174777 87303 174778 87300 174778 87307 174778 87307 174779 87300 174779 87304 174779 87307 174780 87304 174780 87308 174780 87308 174781 87304 174781 87305 174781 87308 174782 87305 174782 87309 174782 87309 174783 87305 174783 87306 174783 87309 174784 87306 174784 87311 174784 87311 174785 87306 174785 86175 174785 87311 174786 86175 174786 87324 174786 87301 174787 87307 174787 87312 174787 87312 174788 87307 174788 87308 174788 87312 174789 87308 174789 87314 174789 87314 174790 87308 174790 87309 174790 87314 174791 87309 174791 87310 174791 87310 174792 87309 174792 87311 174792 87310 174793 87311 174793 87316 174793 87316 174794 87311 174794 87324 174794 87316 174795 87324 174795 87332 174795 87302 174796 87312 174796 87313 174796 87313 174797 87312 174797 87314 174797 87313 174798 87314 174798 87319 174798 87319 174799 87314 174799 87310 174799 87319 174800 87310 174800 87322 174800 87322 174801 87310 174801 87316 174801 87322 174802 87316 174802 87315 174802 87315 174803 87316 174803 87332 174803 87315 174804 87332 174804 87317 174804 87298 174805 87313 174805 87318 174805 87318 174806 87313 174806 87319 174806 87318 174807 87319 174807 87320 174807 87320 174808 87319 174808 87322 174808 87320 174809 87322 174809 87321 174809 87321 174810 87322 174810 87315 174810 87321 174811 87315 174811 86843 174811 86843 174812 87315 174812 87317 174812 86843 174813 87317 174813 87323 174813 87324 174814 86175 174814 86174 174814 87332 174815 87324 174815 87334 174815 87317 174816 87332 174816 87333 174816 87323 174817 87317 174817 87342 174817 87324 174818 86174 174818 87334 174818 87334 174819 86174 174819 87326 174819 87334 174820 87326 174820 87325 174820 87325 174821 87326 174821 86173 174821 87325 174822 86173 174822 87335 174822 87335 174823 86173 174823 87327 174823 87335 174824 87327 174824 87329 174824 87329 174825 87327 174825 87328 174825 87329 174826 87328 174826 87330 174826 87330 174827 87328 174827 86180 174827 87330 174828 86180 174828 87331 174828 87331 174829 86180 174829 86179 174829 87331 174830 86179 174830 87357 174830 87332 174831 87334 174831 87333 174831 87333 174832 87334 174832 87325 174832 87333 174833 87325 174833 87337 174833 87337 174834 87325 174834 87335 174834 87337 174835 87335 174835 87338 174835 87338 174836 87335 174836 87329 174836 87338 174837 87329 174837 87340 174837 87340 174838 87329 174838 87330 174838 87340 174839 87330 174839 87336 174839 87336 174840 87330 174840 87331 174840 87336 174841 87331 174841 87341 174841 87341 174842 87331 174842 87357 174842 87341 174843 87357 174843 87363 174843 87317 174844 87333 174844 87342 174844 87342 174845 87333 174845 87337 174845 87342 174846 87337 174846 87345 174846 87345 174847 87337 174847 87338 174847 87345 174848 87338 174848 87339 174848 87339 174849 87338 174849 87340 174849 87339 174850 87340 174850 87346 174850 87346 174851 87340 174851 87336 174851 87346 174852 87336 174852 87349 174852 87349 174853 87336 174853 87341 174853 87349 174854 87341 174854 87350 174854 87350 174855 87341 174855 87363 174855 87350 174856 87363 174856 87370 174856 87323 174857 87342 174857 87343 174857 87343 174858 87342 174858 87345 174858 87343 174859 87345 174859 87344 174859 87344 174860 87345 174860 87339 174860 87344 174861 87339 174861 87347 174861 87347 174862 87339 174862 87346 174862 87347 174863 87346 174863 87348 174863 87348 174864 87346 174864 87349 174864 87348 174865 87349 174865 86100 174865 86100 174866 87349 174866 87350 174866 86100 174867 87350 174867 86101 174867 86101 174868 87350 174868 87370 174868 86101 174869 87370 174869 87371 174869 87352 174870 87376 174870 87364 174870 87364 174871 87376 174871 87375 174871 87378 174872 87351 174872 87365 174872 87365 174873 87351 174873 87352 174873 87355 174874 87379 174874 87378 174874 87353 174875 87379 174875 87354 174875 87354 174876 87379 174876 87355 174876 87354 174877 87355 174877 87361 174877 87361 174878 87355 174878 87356 174878 87357 174879 86179 174879 84198 174879 87357 174880 84198 174880 87358 174880 87358 174881 84198 174881 84196 174881 87358 174882 84196 174882 87359 174882 87359 174883 84196 174883 84195 174883 87359 174884 84195 174884 87356 174884 87356 174885 84195 174885 87360 174885 87356 174886 87360 174886 87361 174886 87378 174887 87365 174887 87355 174887 87355 174888 87365 174888 87366 174888 87355 174889 87366 174889 87356 174889 87356 174890 87366 174890 87368 174890 87356 174891 87368 174891 87359 174891 87359 174892 87368 174892 87362 174892 87359 174893 87362 174893 87358 174893 87358 174894 87362 174894 87363 174894 87358 174895 87363 174895 87357 174895 87352 174896 87364 174896 87365 174896 87365 174897 87364 174897 87367 174897 87365 174898 87367 174898 87366 174898 87366 174899 87367 174899 87373 174899 87366 174900 87373 174900 87368 174900 87368 174901 87373 174901 87369 174901 87368 174902 87369 174902 87362 174902 87362 174903 87369 174903 87370 174903 87362 174904 87370 174904 87363 174904 87371 174905 87370 174905 86112 174905 86112 174906 87370 174906 87369 174906 86112 174907 87369 174907 87372 174907 87372 174908 87369 174908 87373 174908 87372 174909 87373 174909 86111 174909 86111 174910 87373 174910 87367 174910 86111 174911 87367 174911 87374 174911 87374 174912 87367 174912 87364 174912 87374 174913 87364 174913 86149 174913 86149 174914 87364 174914 87375 174914 86051 174915 87375 174915 87380 174915 87380 174916 87375 174916 87376 174916 87353 174917 84191 174917 87379 174917 87379 174918 84191 174918 87377 174918 87376 174919 87352 174919 87380 174919 87380 174920 87352 174920 87351 174920 87380 174921 87351 174921 87377 174921 87377 174922 87351 174922 87378 174922 87377 174923 87378 174923 87379 174923 86052 174924 86051 174924 87381 174924 87381 174925 86051 174925 87380 174925 87381 174926 87380 174926 87382 174926 87382 174927 87380 174927 87377 174927 87382 174928 87377 174928 87383 174928 87383 174929 87377 174929 84191 174929 87383 174930 84190 174930 87382 174930 87382 174931 84190 174931 87385 174931 87382 174932 87385 174932 87381 174932 86052 174933 87381 174933 87401 174933 84190 174934 87384 174934 87385 174934 87385 174935 87384 174935 84188 174935 87385 174936 84188 174936 87386 174936 87386 174937 84188 174937 87388 174937 87386 174938 87388 174938 87387 174938 87387 174939 87388 174939 87389 174939 87387 174940 87389 174940 87391 174940 87389 174941 87390 174941 87391 174941 87391 174942 87390 174942 87392 174942 87391 174943 87392 174943 87393 174943 87393 174944 87392 174944 87394 174944 87393 174945 87394 174945 87398 174945 87398 174946 87394 174946 84203 174946 87398 174947 84203 174947 87400 174947 84203 174948 84205 174948 87400 174948 87400 174949 84205 174949 84206 174949 87400 174950 84206 174950 87395 174950 87395 174951 84206 174951 84207 174951 87395 174952 84207 174952 87396 174952 87396 174953 84207 174953 85693 174953 87396 174954 85693 174954 87415 174954 87381 174955 87385 174955 87401 174955 87401 174956 87385 174956 87386 174956 87401 174957 87386 174957 87397 174957 87397 174958 87386 174958 87387 174958 87397 174959 87387 174959 87403 174959 87403 174960 87387 174960 87391 174960 87403 174961 87391 174961 87404 174961 87404 174962 87391 174962 87393 174962 87404 174963 87393 174963 87399 174963 87399 174964 87393 174964 87398 174964 87399 174965 87398 174965 87405 174965 87405 174966 87398 174966 87400 174966 87405 174967 87400 174967 87408 174967 87408 174968 87400 174968 87395 174968 87408 174969 87395 174969 87409 174969 87409 174970 87395 174970 87396 174970 87409 174971 87396 174971 87411 174971 87411 174972 87396 174972 87415 174972 87411 174973 87415 174973 87412 174973 86052 174974 87401 174974 87402 174974 87402 174975 87401 174975 87397 174975 87402 174976 87397 174976 86044 174976 86044 174977 87397 174977 87403 174977 86044 174978 87403 174978 86042 174978 86042 174979 87403 174979 87404 174979 86042 174980 87404 174980 86080 174980 86080 174981 87404 174981 87399 174981 86080 174982 87399 174982 86049 174982 86049 174983 87399 174983 87405 174983 86049 174984 87405 174984 87406 174984 87406 174985 87405 174985 87408 174985 87406 174986 87408 174986 87407 174986 87407 174987 87408 174987 87409 174987 87407 174988 87409 174988 87410 174988 87410 174989 87409 174989 87411 174989 87410 174990 87411 174990 86047 174990 86047 174991 87411 174991 87412 174991 86047 174992 87412 174992 86048 174992 87416 174993 86048 174993 87418 174993 87418 174994 86048 174994 87412 174994 87418 174995 87412 174995 87413 174995 87413 174996 87412 174996 87415 174996 87413 174997 87415 174997 87414 174997 87414 174998 87415 174998 85693 174998 87422 174999 87416 174999 87425 174999 87425 175000 87416 175000 87418 175000 87425 175001 87418 175001 87417 175001 87417 175002 87418 175002 87413 175002 87417 175003 87413 175003 85694 175003 85694 175004 87413 175004 87414 175004 87427 175005 87420 175005 87419 175005 87741 175006 87733 175006 87420 175006 87420 175007 87733 175007 87726 175007 87428 175008 87744 175008 87426 175008 87726 175009 86088 175009 87420 175009 87420 175010 86088 175010 86079 175010 87420 175011 86079 175011 87419 175011 87419 175012 86079 175012 87421 175012 87419 175013 87421 175013 87424 175013 87424 175014 87421 175014 87422 175014 87424 175015 87422 175015 87425 175015 87427 175016 87419 175016 87423 175016 87423 175017 87419 175017 87424 175017 87423 175018 87424 175018 87430 175018 87430 175019 87424 175019 87425 175019 87430 175020 87425 175020 87417 175020 87741 175021 87420 175021 87426 175021 87426 175022 87420 175022 87427 175022 87426 175023 87427 175023 87428 175023 87428 175024 87427 175024 87423 175024 87428 175025 87423 175025 87429 175025 87429 175026 87423 175026 87430 175026 87429 175027 87430 175027 85669 175027 85669 175028 87430 175028 87417 175028 85669 175029 87417 175029 85694 175029 87431 175030 86426 175030 87432 175030 87431 175031 87432 175031 87433 175031 86426 175032 87431 175032 86411 175032 86411 175033 87431 175033 87434 175033 86411 175034 87434 175034 87435 175034 87435 175035 87434 175035 87436 175035 87436 175036 87434 175036 87441 175036 87436 175037 87441 175037 86413 175037 87440 175038 86812 175038 87441 175038 87441 175039 86812 175039 86412 175039 87441 175040 86412 175040 86413 175040 87437 175041 87439 175041 87438 175041 87438 175042 87439 175042 87433 175042 87438 175043 87433 175043 86356 175043 86356 175044 87433 175044 87432 175044 86823 175045 87440 175045 87446 175045 87446 175046 87440 175046 87441 175046 87446 175047 87441 175047 87447 175047 87447 175048 87441 175048 87434 175048 87447 175049 87434 175049 87442 175049 87442 175050 87434 175050 87431 175050 87442 175051 87431 175051 87443 175051 87443 175052 87431 175052 87433 175052 87443 175053 87433 175053 87444 175053 87444 175054 87433 175054 87439 175054 87449 175055 86823 175055 87445 175055 87445 175056 86823 175056 87446 175056 87445 175057 87446 175057 87456 175057 87456 175058 87446 175058 87447 175058 87456 175059 87447 175059 87450 175059 87450 175060 87447 175060 87442 175060 87450 175061 87442 175061 87448 175061 87448 175062 87442 175062 87443 175062 87448 175063 87443 175063 87461 175063 87461 175064 87443 175064 87444 175064 87450 175065 87448 175065 87451 175065 87456 175066 87450 175066 87452 175066 87445 175067 87456 175067 87466 175067 87449 175068 87445 175068 87468 175068 87450 175069 87451 175069 87452 175069 87452 175070 87451 175070 87453 175070 87452 175071 87453 175071 87457 175071 87457 175072 87453 175072 87454 175072 87457 175073 87454 175073 87455 175073 87456 175074 87452 175074 87466 175074 87466 175075 87452 175075 87457 175075 87466 175076 87457 175076 87467 175076 87467 175077 87457 175077 87455 175077 87467 175078 87455 175078 87464 175078 87458 175079 87454 175079 86410 175079 86410 175080 87454 175080 87453 175080 86410 175081 87453 175081 87459 175081 87459 175082 87453 175082 87451 175082 87459 175083 87451 175083 87460 175083 87460 175084 87451 175084 87448 175084 87460 175085 87448 175085 87461 175085 87458 175086 87462 175086 87454 175086 87454 175087 87462 175087 87475 175087 87454 175088 87475 175088 87455 175088 87455 175089 87475 175089 87463 175089 87455 175090 87463 175090 87464 175090 87464 175091 87463 175091 87472 175091 87464 175092 87472 175092 87465 175092 87445 175093 87466 175093 87468 175093 87468 175094 87466 175094 87467 175094 87468 175095 87467 175095 87469 175095 87469 175096 87467 175096 87464 175096 87469 175097 87464 175097 87470 175097 87470 175098 87464 175098 87465 175098 87470 175099 87465 175099 87477 175099 87449 175100 87468 175100 87217 175100 87217 175101 87468 175101 87469 175101 87217 175102 87469 175102 87212 175102 87212 175103 87469 175103 87470 175103 87212 175104 87470 175104 87471 175104 87471 175105 87470 175105 87477 175105 87471 175106 87477 175106 87476 175106 87485 175107 87472 175107 87473 175107 87473 175108 87472 175108 87463 175108 87473 175109 87463 175109 87474 175109 87474 175110 87463 175110 87475 175110 87474 175111 87475 175111 87479 175111 87479 175112 87475 175112 87462 175112 87479 175113 87462 175113 86409 175113 86409 175114 87462 175114 87458 175114 86407 175115 87476 175115 87484 175115 87484 175116 87476 175116 87477 175116 87484 175117 87477 175117 87485 175117 87485 175118 87477 175118 87465 175118 87485 175119 87465 175119 87472 175119 87478 175120 86346 175120 87481 175120 87479 175121 86409 175121 86345 175121 87478 175122 87481 175122 86345 175122 87479 175123 87480 175123 87474 175123 87474 175124 87480 175124 87482 175124 87479 175125 86345 175125 87480 175125 87480 175126 86345 175126 87481 175126 87480 175127 87481 175127 87482 175127 87486 175128 87485 175128 87482 175128 87482 175129 87485 175129 87473 175129 87482 175130 87473 175130 87474 175130 87481 175131 87488 175131 87482 175131 87482 175132 87488 175132 87483 175132 87482 175133 87483 175133 87486 175133 86405 175134 86407 175134 87486 175134 87486 175135 86407 175135 87484 175135 87486 175136 87484 175136 87485 175136 87483 175137 87489 175137 87486 175137 87486 175138 87489 175138 87487 175138 87486 175139 87487 175139 86405 175139 86405 175140 87487 175140 86406 175140 87506 175141 87508 175141 87499 175141 87481 175142 86346 175142 86347 175142 87483 175143 87488 175143 87490 175143 87490 175144 87488 175144 87481 175144 87487 175145 87489 175145 87496 175145 87496 175146 87489 175146 87483 175146 87500 175147 86406 175147 87487 175147 87481 175148 86347 175148 87490 175148 87490 175149 86347 175149 87492 175149 87490 175150 87492 175150 87491 175150 87491 175151 87492 175151 86348 175151 87491 175152 86348 175152 87493 175152 87493 175153 86348 175153 86351 175153 87493 175154 86351 175154 87498 175154 87498 175155 86351 175155 87494 175155 87498 175156 87494 175156 87495 175156 87495 175157 87494 175157 86344 175157 87495 175158 86344 175158 87505 175158 87483 175159 87490 175159 87496 175159 87496 175160 87490 175160 87491 175160 87496 175161 87491 175161 87502 175161 87502 175162 87491 175162 87493 175162 87502 175163 87493 175163 87497 175163 87497 175164 87493 175164 87498 175164 87497 175165 87498 175165 87503 175165 87503 175166 87498 175166 87495 175166 87503 175167 87495 175167 87499 175167 87499 175168 87495 175168 87505 175168 87499 175169 87505 175169 87506 175169 87487 175170 87496 175170 87500 175170 87500 175171 87496 175171 87502 175171 87500 175172 87502 175172 87501 175172 87501 175173 87502 175173 87497 175173 87501 175174 87497 175174 86403 175174 86403 175175 87497 175175 87503 175175 86403 175176 87503 175176 87504 175176 87504 175177 87503 175177 87499 175177 87504 175178 87499 175178 86404 175178 86404 175179 87499 175179 87508 175179 86404 175180 87508 175180 87510 175180 86344 175181 86342 175181 87511 175181 86344 175182 87511 175182 87505 175182 87505 175183 87511 175183 87512 175183 87505 175184 87512 175184 87506 175184 87506 175185 87512 175185 87507 175185 87506 175186 87507 175186 87508 175186 87508 175187 87507 175187 87509 175187 87508 175188 87509 175188 87510 175188 86342 175189 87521 175189 87516 175189 86342 175190 87516 175190 87511 175190 87511 175191 87516 175191 87524 175191 87511 175192 87524 175192 87512 175192 87512 175193 87524 175193 87513 175193 87512 175194 87513 175194 87507 175194 87507 175195 87513 175195 87514 175195 87507 175196 87514 175196 87509 175196 87514 175197 87513 175197 87528 175197 87539 175198 87515 175198 87531 175198 87513 175199 87524 175199 87525 175199 87537 175200 87538 175200 87526 175200 87524 175201 87516 175201 87517 175201 87522 175202 87523 175202 87518 175202 87518 175203 87523 175203 87519 175203 87518 175204 87519 175204 87520 175204 87520 175205 87519 175205 87517 175205 87520 175206 87517 175206 86339 175206 86339 175207 87517 175207 87516 175207 86339 175208 87516 175208 87521 175208 87522 175209 86337 175209 87523 175209 87523 175210 86337 175210 87536 175210 87523 175211 87536 175211 87527 175211 87524 175212 87517 175212 87525 175212 87525 175213 87517 175213 87519 175213 87525 175214 87519 175214 87529 175214 87529 175215 87519 175215 87523 175215 87529 175216 87523 175216 87526 175216 87526 175217 87523 175217 87527 175217 87526 175218 87527 175218 87537 175218 87513 175219 87525 175219 87528 175219 87528 175220 87525 175220 87529 175220 87528 175221 87529 175221 87530 175221 87530 175222 87529 175222 87526 175222 87530 175223 87526 175223 87531 175223 87531 175224 87526 175224 87538 175224 87531 175225 87538 175225 87539 175225 87514 175226 87528 175226 87532 175226 87532 175227 87528 175227 87530 175227 87532 175228 87530 175228 87533 175228 87533 175229 87530 175229 87531 175229 87533 175230 87531 175230 86402 175230 86402 175231 87531 175231 87515 175231 86402 175232 87515 175232 87534 175232 87535 175233 86341 175233 87542 175233 87527 175234 87536 175234 87535 175234 87527 175235 87535 175235 87537 175235 87537 175236 87535 175236 87542 175236 87537 175237 87542 175237 87538 175237 87538 175238 87542 175238 87543 175238 87538 175239 87543 175239 87539 175239 87539 175240 87543 175240 87515 175240 87515 175241 87543 175241 87540 175241 87515 175242 87540 175242 87534 175242 86341 175243 87541 175243 87542 175243 87542 175244 87541 175244 87567 175244 87542 175245 87567 175245 87543 175245 87543 175246 87567 175246 87568 175246 87543 175247 87568 175247 87540 175247 87540 175248 87568 175248 87544 175248 86396 175249 87545 175249 87546 175249 87546 175250 87545 175250 87547 175250 87548 175251 87554 175251 86367 175251 86367 175252 86369 175252 87548 175252 87548 175253 86369 175253 87549 175253 87548 175254 87549 175254 86458 175254 86458 175255 87549 175255 86368 175255 86458 175256 86368 175256 86459 175256 87545 175257 87550 175257 87547 175257 87547 175258 87550 175258 87551 175258 87547 175259 87551 175259 87552 175259 87552 175260 87551 175260 87553 175260 87552 175261 87553 175261 87554 175261 87554 175262 87553 175262 87555 175262 87554 175263 87555 175263 86367 175263 86397 175264 87546 175264 87559 175264 87559 175265 87546 175265 87547 175265 87559 175266 87547 175266 87556 175266 87556 175267 87547 175267 87552 175267 87556 175268 87552 175268 87557 175268 87557 175269 87552 175269 87554 175269 87557 175270 87554 175270 87563 175270 87563 175271 87554 175271 87548 175271 87563 175272 87548 175272 86428 175272 86428 175273 87548 175273 86458 175273 87558 175274 86397 175274 87583 175274 87583 175275 86397 175275 87559 175275 87583 175276 87559 175276 87560 175276 87560 175277 87559 175277 87556 175277 87560 175278 87556 175278 87561 175278 87561 175279 87556 175279 87557 175279 87561 175280 87557 175280 87562 175280 87562 175281 87557 175281 87563 175281 87562 175282 87563 175282 87596 175282 87596 175283 87563 175283 86428 175283 87571 175284 87567 175284 87564 175284 87564 175285 87567 175285 87541 175285 87564 175286 87541 175286 87565 175286 87571 175287 87566 175287 87567 175287 87567 175288 87566 175288 87584 175288 87567 175289 87584 175289 87568 175289 87000 175290 87544 175290 87572 175290 87572 175291 87544 175291 87568 175291 87572 175292 87568 175292 87569 175292 87569 175293 87568 175293 87584 175293 87569 175294 87584 175294 87570 175294 87571 175295 87564 175295 87573 175295 87564 175296 87565 175296 86398 175296 87578 175297 87566 175297 87571 175297 87566 175298 87578 175298 87584 175298 87594 175299 87572 175299 87569 175299 87572 175300 87594 175300 87000 175300 87564 175301 86398 175301 87573 175301 87573 175302 86398 175302 87575 175302 87573 175303 87575 175303 87574 175303 87574 175304 87575 175304 87576 175304 87574 175305 87576 175305 87579 175305 87579 175306 87576 175306 86400 175306 87579 175307 86400 175307 87582 175307 87582 175308 86400 175308 86399 175308 87582 175309 86399 175309 87577 175309 87577 175310 86399 175310 87558 175310 87577 175311 87558 175311 87583 175311 87571 175312 87573 175312 87578 175312 87578 175313 87573 175313 87574 175313 87578 175314 87574 175314 87580 175314 87580 175315 87574 175315 87579 175315 87580 175316 87579 175316 87581 175316 87581 175317 87579 175317 87582 175317 87581 175318 87582 175318 87588 175318 87588 175319 87582 175319 87577 175319 87588 175320 87577 175320 87590 175320 87590 175321 87577 175321 87583 175321 87590 175322 87583 175322 87560 175322 87584 175323 87578 175323 87570 175323 87570 175324 87578 175324 87580 175324 87570 175325 87580 175325 87585 175325 87585 175326 87580 175326 87581 175326 87585 175327 87581 175327 87586 175327 87586 175328 87581 175328 87588 175328 87586 175329 87588 175329 87587 175329 87587 175330 87588 175330 87590 175330 87587 175331 87590 175331 87589 175331 87589 175332 87590 175332 87560 175332 87589 175333 87560 175333 87561 175333 87569 175334 87570 175334 87594 175334 87594 175335 87570 175335 87585 175335 87594 175336 87585 175336 87591 175336 87591 175337 87585 175337 87586 175337 87591 175338 87586 175338 87592 175338 87592 175339 87586 175339 87587 175339 87592 175340 87587 175340 87593 175340 87593 175341 87587 175341 87589 175341 87593 175342 87589 175342 87595 175342 87595 175343 87589 175343 87561 175343 87595 175344 87561 175344 87562 175344 87000 175345 87594 175345 87001 175345 87001 175346 87594 175346 87591 175346 87001 175347 87591 175347 86999 175347 86999 175348 87591 175348 87592 175348 86999 175349 87592 175349 86992 175349 86992 175350 87592 175350 87593 175350 86992 175351 87593 175351 86995 175351 86995 175352 87593 175352 87595 175352 86995 175353 87595 175353 86996 175353 86996 175354 87595 175354 87562 175354 86996 175355 87562 175355 87596 175355 87607 175356 87597 175356 85643 175356 87607 175357 85643 175357 87601 175357 87597 175358 87607 175358 87598 175358 87598 175359 87607 175359 87599 175359 87598 175360 87599 175360 85644 175360 87600 175361 85646 175361 87599 175361 87599 175362 85646 175362 85648 175362 87599 175363 85648 175363 85644 175363 85638 175364 85639 175364 85609 175364 85609 175365 85639 175365 87609 175365 85643 175366 85605 175366 87601 175366 87601 175367 85605 175367 87602 175367 87601 175368 87602 175368 87609 175368 87609 175369 87602 175369 87603 175369 87609 175370 87603 175370 85609 175370 87604 175371 87600 175371 87605 175371 87605 175372 87600 175372 87599 175372 87605 175373 87599 175373 87606 175373 87606 175374 87599 175374 87607 175374 87606 175375 87607 175375 87612 175375 87612 175376 87607 175376 87601 175376 87612 175377 87601 175377 87608 175377 87608 175378 87601 175378 87609 175378 87608 175379 87609 175379 85642 175379 85642 175380 87609 175380 85639 175380 87623 175381 87604 175381 87610 175381 87610 175382 87604 175382 87605 175382 87610 175383 87605 175383 87631 175383 87631 175384 87605 175384 87606 175384 87631 175385 87606 175385 87611 175385 87611 175386 87606 175386 87612 175386 87611 175387 87612 175387 87644 175387 87644 175388 87612 175388 87608 175388 87644 175389 87608 175389 87646 175389 87646 175390 87608 175390 85642 175390 87634 175391 87613 175391 87635 175391 87651 175392 87196 175392 87616 175392 87624 175393 87651 175393 87614 175393 87613 175394 87624 175394 87625 175394 87615 175395 87648 175395 87634 175395 87648 175396 87615 175396 87647 175396 87651 175397 87616 175397 87614 175397 87614 175398 87616 175398 87617 175398 87614 175399 87617 175399 87618 175399 87618 175400 87617 175400 87619 175400 87618 175401 87619 175401 87627 175401 87627 175402 87619 175402 87197 175402 87627 175403 87197 175403 87620 175403 87620 175404 87197 175404 87622 175404 87620 175405 87622 175405 87621 175405 87621 175406 87622 175406 87623 175406 87621 175407 87623 175407 87610 175407 87624 175408 87614 175408 87625 175408 87625 175409 87614 175409 87618 175409 87625 175410 87618 175410 87626 175410 87626 175411 87618 175411 87627 175411 87626 175412 87627 175412 87628 175412 87628 175413 87627 175413 87620 175413 87628 175414 87620 175414 87629 175414 87629 175415 87620 175415 87621 175415 87629 175416 87621 175416 87630 175416 87630 175417 87621 175417 87610 175417 87630 175418 87610 175418 87631 175418 87613 175419 87625 175419 87635 175419 87635 175420 87625 175420 87626 175420 87635 175421 87626 175421 87637 175421 87637 175422 87626 175422 87628 175422 87637 175423 87628 175423 87638 175423 87638 175424 87628 175424 87629 175424 87638 175425 87629 175425 87632 175425 87632 175426 87629 175426 87630 175426 87632 175427 87630 175427 87633 175427 87633 175428 87630 175428 87631 175428 87633 175429 87631 175429 87611 175429 87634 175430 87635 175430 87615 175430 87615 175431 87635 175431 87637 175431 87615 175432 87637 175432 87636 175432 87636 175433 87637 175433 87638 175433 87636 175434 87638 175434 87639 175434 87639 175435 87638 175435 87632 175435 87639 175436 87632 175436 87640 175436 87640 175437 87632 175437 87633 175437 87640 175438 87633 175438 87643 175438 87643 175439 87633 175439 87611 175439 87643 175440 87611 175440 87644 175440 87647 175441 87615 175441 85640 175441 85640 175442 87615 175442 87636 175442 85640 175443 87636 175443 85641 175443 85641 175444 87636 175444 87639 175444 85641 175445 87639 175445 87641 175445 87641 175446 87639 175446 87640 175446 87641 175447 87640 175447 87642 175447 87642 175448 87640 175448 87643 175448 87642 175449 87643 175449 87645 175449 87645 175450 87643 175450 87644 175450 87645 175451 87644 175451 87646 175451 87647 175452 85637 175452 87648 175452 87648 175453 85637 175453 87654 175453 87648 175454 87654 175454 87634 175454 87634 175455 87654 175455 87613 175455 87613 175456 87654 175456 87649 175456 87613 175457 87649 175457 87624 175457 87624 175458 87649 175458 87656 175458 87624 175459 87656 175459 87651 175459 87651 175460 87656 175460 87650 175460 87651 175461 87650 175461 87196 175461 85599 175462 85600 175462 87662 175462 87655 175463 87652 175463 87662 175463 87662 175464 87652 175464 87653 175464 87662 175465 87653 175465 85599 175465 87662 175466 87661 175466 87655 175466 87655 175467 87661 175467 87663 175467 87655 175468 87663 175468 87657 175468 85637 175469 87653 175469 87654 175469 87654 175470 87653 175470 87652 175470 87654 175471 87652 175471 87649 175471 87649 175472 87652 175472 87655 175472 87649 175473 87655 175473 87656 175473 87656 175474 87655 175474 87657 175474 87656 175475 87657 175475 87650 175475 87650 175476 87657 175476 87659 175476 87663 175477 87658 175477 87657 175477 87657 175478 87658 175478 87664 175478 87657 175479 87664 175479 87659 175479 87659 175480 87664 175480 84062 175480 87662 175481 85600 175481 87665 175481 87663 175482 87661 175482 87660 175482 87660 175483 87661 175483 87662 175483 87664 175484 87658 175484 87678 175484 87678 175485 87658 175485 87663 175485 87677 175486 84062 175486 87664 175486 87662 175487 87665 175487 87660 175487 87660 175488 87665 175488 87667 175488 87660 175489 87667 175489 87666 175489 87666 175490 87667 175490 87668 175490 87666 175491 87668 175491 87669 175491 87669 175492 87668 175492 85602 175492 87669 175493 85602 175493 87673 175493 87673 175494 85602 175494 85603 175494 87673 175495 85603 175495 87670 175495 87670 175496 85603 175496 87681 175496 87670 175497 87681 175497 87675 175497 87663 175498 87660 175498 87678 175498 87678 175499 87660 175499 87666 175499 87678 175500 87666 175500 87671 175500 87671 175501 87666 175501 87669 175501 87671 175502 87669 175502 87672 175502 87672 175503 87669 175503 87673 175503 87672 175504 87673 175504 87674 175504 87674 175505 87673 175505 87670 175505 87674 175506 87670 175506 87680 175506 87680 175507 87670 175507 87675 175507 87680 175508 87675 175508 87676 175508 87664 175509 87678 175509 87677 175509 87677 175510 87678 175510 87671 175510 87677 175511 87671 175511 84064 175511 84064 175512 87671 175512 87672 175512 84064 175513 87672 175513 87679 175513 87679 175514 87672 175514 87674 175514 87679 175515 87674 175515 84058 175515 84058 175516 87674 175516 87680 175516 84058 175517 87680 175517 84074 175517 84074 175518 87680 175518 87676 175518 84074 175519 87676 175519 84068 175519 87681 175520 85623 175520 87683 175520 87681 175521 87683 175521 87675 175521 87675 175522 87683 175522 87682 175522 87675 175523 87682 175523 87676 175523 87676 175524 87682 175524 84112 175524 87676 175525 84112 175525 84068 175525 87685 175526 87686 175526 85623 175526 85623 175527 87686 175527 87683 175527 87686 175528 87688 175528 87683 175528 87683 175529 87688 175529 87690 175529 87683 175530 87690 175530 87682 175530 87692 175531 84112 175531 87684 175531 87684 175532 84112 175532 87682 175532 87684 175533 87682 175533 87689 175533 87689 175534 87682 175534 87690 175534 85632 175535 85631 175535 87700 175535 85632 175536 87700 175536 85625 175536 87685 175537 85624 175537 87686 175537 87686 175538 85624 175538 87687 175538 87686 175539 87687 175539 87688 175539 87688 175540 87687 175540 87691 175540 87693 175541 87689 175541 87691 175541 87691 175542 87689 175542 87690 175542 87691 175543 87690 175543 87688 175543 87696 175544 87692 175544 87693 175544 87693 175545 87692 175545 87684 175545 87693 175546 87684 175546 87689 175546 85624 175547 85627 175547 87687 175547 87687 175548 85627 175548 87694 175548 87687 175549 87694 175549 87691 175549 87691 175550 87694 175550 87697 175550 87691 175551 87697 175551 87693 175551 87693 175552 87697 175552 87695 175552 87693 175553 87695 175553 87696 175553 87696 175554 87695 175554 87698 175554 85627 175555 85625 175555 87694 175555 87694 175556 85625 175556 87700 175556 87694 175557 87700 175557 87697 175557 87697 175558 87700 175558 87702 175558 87697 175559 87702 175559 87695 175559 87695 175560 87702 175560 87699 175560 87695 175561 87699 175561 87698 175561 87698 175562 87699 175562 84111 175562 85631 175563 85628 175563 87700 175563 87700 175564 85628 175564 87705 175564 87700 175565 87705 175565 87702 175565 87702 175566 87705 175566 87701 175566 87702 175567 87701 175567 87699 175567 87699 175568 87701 175568 87703 175568 87699 175569 87703 175569 84111 175569 84111 175570 87703 175570 87704 175570 85633 175571 85634 175571 87707 175571 85628 175572 85633 175572 87705 175572 87705 175573 85633 175573 87707 175573 87705 175574 87707 175574 87701 175574 87701 175575 87707 175575 87708 175575 87701 175576 87708 175576 87703 175576 87703 175577 87708 175577 87706 175577 87703 175578 87706 175578 87704 175578 87704 175579 87706 175579 87710 175579 85634 175580 87729 175580 87707 175580 87707 175581 87729 175581 87731 175581 87707 175582 87731 175582 87708 175582 87708 175583 87731 175583 87732 175583 87708 175584 87732 175584 87706 175584 87706 175585 87732 175585 87709 175585 87706 175586 87709 175586 87710 175586 87710 175587 87709 175587 85670 175587 87711 175588 87720 175588 85604 175588 85604 175589 87720 175589 85613 175589 85613 175590 87720 175590 87712 175590 85613 175591 87712 175591 85618 175591 85618 175592 87712 175592 85617 175592 85617 175593 87712 175593 85686 175593 85617 175594 85686 175594 85688 175594 87717 175595 87713 175595 87721 175595 87721 175596 87713 175596 85672 175596 87721 175597 85672 175597 87714 175597 85604 175598 87715 175598 87711 175598 87711 175599 87715 175599 87716 175599 87711 175600 87716 175600 87717 175600 87717 175601 87716 175601 87718 175601 87717 175602 87718 175602 87713 175602 85685 175603 85686 175603 87723 175603 87723 175604 85686 175604 87712 175604 87723 175605 87712 175605 87719 175605 87719 175606 87712 175606 87720 175606 87719 175607 87720 175607 87724 175607 87724 175608 87720 175608 87711 175608 87724 175609 87711 175609 87727 175609 87727 175610 87711 175610 87717 175610 87727 175611 87717 175611 86087 175611 86087 175612 87717 175612 87721 175612 85691 175613 85685 175613 87722 175613 87722 175614 85685 175614 87723 175614 87722 175615 87723 175615 87737 175615 87737 175616 87723 175616 87719 175616 87737 175617 87719 175617 87735 175617 87735 175618 87719 175618 87724 175618 87735 175619 87724 175619 87725 175619 87725 175620 87724 175620 87727 175620 87725 175621 87727 175621 87726 175621 87726 175622 87727 175622 86087 175622 87728 175623 87753 175623 87729 175623 87729 175624 87753 175624 87731 175624 87753 175625 87747 175625 87731 175625 87731 175626 87747 175626 87730 175626 87731 175627 87730 175627 87732 175627 87730 175628 87746 175628 87732 175628 87732 175629 87746 175629 87745 175629 87732 175630 87745 175630 87709 175630 87709 175631 87745 175631 87744 175631 87709 175632 87744 175632 85670 175632 87726 175633 87733 175633 87725 175633 87725 175634 87733 175634 87734 175634 87725 175635 87734 175635 87735 175635 87735 175636 87734 175636 87736 175636 87735 175637 87736 175637 87737 175637 87737 175638 87736 175638 87738 175638 87737 175639 87738 175639 87722 175639 85691 175640 87722 175640 87750 175640 87733 175641 87741 175641 87734 175641 87734 175642 87741 175642 87739 175642 87734 175643 87739 175643 87736 175643 87736 175644 87739 175644 87740 175644 87736 175645 87740 175645 87738 175645 87738 175646 87740 175646 87748 175646 87741 175647 87426 175647 87739 175647 87739 175648 87426 175648 87742 175648 87739 175649 87742 175649 87740 175649 87740 175650 87742 175650 87743 175650 87740 175651 87743 175651 87748 175651 87748 175652 87743 175652 87749 175652 87426 175653 87744 175653 87742 175653 87742 175654 87744 175654 87745 175654 87742 175655 87745 175655 87743 175655 87743 175656 87745 175656 87746 175656 87743 175657 87746 175657 87749 175657 87749 175658 87746 175658 87730 175658 87749 175659 87730 175659 87747 175659 87722 175660 87738 175660 87750 175660 87750 175661 87738 175661 87748 175661 87750 175662 87748 175662 87751 175662 87751 175663 87748 175663 87749 175663 87751 175664 87749 175664 87752 175664 87752 175665 87749 175665 87747 175665 87752 175666 87747 175666 87753 175666 85691 175667 87750 175667 85692 175667 85692 175668 87750 175668 87751 175668 85692 175669 87751 175669 85690 175669 85690 175670 87751 175670 87752 175670 85690 175671 87752 175671 85689 175671 85689 175672 87752 175672 87753 175672 85689 175673 87753 175673 87728 175673 83928 175674 87772 175674 88006 175674 88027 175675 87754 175675 88021 175675 88021 175676 87754 175676 87755 175676 88021 175677 87755 175677 87756 175677 88006 175678 87757 175678 83928 175678 83928 175679 87757 175679 87758 175679 83928 175680 87758 175680 87759 175680 87759 175681 87758 175681 87760 175681 87759 175682 87760 175682 83922 175682 83922 175683 87760 175683 87761 175683 83922 175684 87761 175684 87762 175684 87762 175685 87761 175685 87763 175685 87762 175686 87763 175686 83923 175686 83923 175687 87763 175687 87764 175687 83923 175688 87764 175688 83919 175688 83919 175689 87764 175689 87765 175689 83919 175690 87765 175690 87767 175690 87767 175691 87765 175691 87766 175691 87767 175692 87766 175692 87768 175692 87768 175693 87766 175693 87756 175693 87768 175694 87756 175694 87769 175694 87769 175695 87756 175695 87755 175695 88030 175696 83927 175696 87770 175696 87770 175697 83927 175697 87771 175697 88006 175698 87772 175698 88030 175698 88030 175699 87772 175699 83927 175699 83953 175700 88087 175700 87773 175700 87773 175701 88087 175701 87774 175701 87773 175702 87774 175702 87794 175702 88087 175703 83953 175703 88062 175703 88062 175704 83953 175704 87781 175704 88062 175705 87781 175705 88063 175705 87775 175706 87776 175706 87777 175706 87777 175707 87776 175707 88028 175707 88028 175708 87776 175708 87754 175708 88028 175709 87754 175709 88027 175709 87777 175710 88047 175710 87775 175710 87775 175711 88047 175711 88049 175711 87775 175712 88049 175712 83914 175712 83914 175713 88049 175713 88050 175713 83914 175714 88050 175714 87778 175714 87778 175715 88050 175715 87779 175715 87778 175716 87779 175716 83949 175716 83949 175717 87779 175717 87780 175717 88063 175718 87781 175718 88055 175718 88055 175719 87781 175719 87782 175719 88055 175720 87782 175720 87783 175720 87783 175721 87782 175721 83952 175721 87783 175722 83952 175722 87780 175722 87780 175723 83952 175723 83951 175723 87780 175724 83951 175724 83949 175724 88121 175725 87784 175725 87785 175725 87785 175726 87784 175726 87786 175726 87785 175727 87786 175727 87787 175727 87787 175728 87786 175728 87788 175728 87787 175729 87788 175729 87789 175729 87789 175730 87788 175730 84458 175730 87789 175731 84458 175731 88118 175731 88118 175732 84458 175732 83957 175732 88118 175733 83957 175733 88105 175733 88105 175734 83957 175734 83956 175734 88105 175735 83956 175735 87790 175735 87790 175736 83956 175736 87791 175736 87790 175737 87791 175737 87793 175737 87793 175738 87791 175738 87792 175738 87793 175739 87792 175739 87794 175739 87794 175740 87792 175740 83955 175740 87794 175741 83955 175741 87773 175741 88094 175742 88069 175742 87795 175742 87795 175743 87796 175743 88094 175743 88094 175744 87796 175744 84548 175744 88094 175745 84548 175745 88121 175745 88121 175746 84548 175746 84547 175746 88121 175747 84547 175747 87784 175747 87806 175748 87797 175748 88070 175748 88070 175749 87797 175749 87798 175749 87798 175750 87797 175750 87795 175750 87798 175751 87795 175751 88069 175751 87771 175752 83926 175752 87770 175752 87770 175753 83926 175753 83924 175753 87770 175754 83924 175754 88059 175754 88059 175755 83924 175755 87799 175755 88059 175756 87799 175756 88086 175756 88086 175757 87799 175757 87800 175757 88086 175758 87800 175758 88085 175758 88085 175759 87800 175759 87801 175759 88085 175760 87801 175760 88083 175760 88083 175761 87801 175761 84551 175761 88083 175762 84551 175762 87802 175762 87802 175763 84551 175763 87803 175763 87802 175764 87803 175764 87804 175764 87804 175765 87803 175765 84553 175765 87804 175766 84553 175766 87805 175766 87805 175767 84553 175767 87806 175767 87805 175768 87806 175768 87807 175768 87807 175769 87806 175769 88070 175769 87809 175770 87808 175770 83944 175770 83944 175771 87808 175771 87953 175771 83944 175772 87953 175772 83931 175772 83931 175773 87953 175773 87823 175773 87808 175774 87809 175774 87973 175774 87973 175775 87809 175775 83937 175775 87973 175776 83937 175776 87870 175776 87822 175777 87928 175777 87927 175777 87904 175778 87810 175778 87906 175778 87906 175779 87810 175779 83947 175779 87822 175780 87927 175780 83929 175780 83929 175781 87927 175781 87811 175781 83929 175782 87811 175782 83945 175782 83945 175783 87811 175783 87812 175783 83945 175784 87812 175784 87813 175784 87813 175785 87812 175785 87814 175785 87813 175786 87814 175786 83946 175786 83946 175787 87814 175787 87903 175787 83946 175788 87903 175788 83947 175788 83947 175789 87903 175789 87907 175789 83947 175790 87907 175790 87906 175790 87815 175791 87825 175791 87891 175791 87891 175792 87825 175792 87816 175792 87891 175793 87816 175793 87892 175793 87892 175794 87816 175794 87817 175794 87892 175795 87817 175795 87818 175795 87818 175796 87817 175796 83913 175796 87818 175797 83913 175797 87819 175797 87819 175798 83913 175798 83948 175798 87819 175799 83948 175799 87908 175799 87908 175800 83948 175800 87820 175800 87908 175801 87820 175801 87904 175801 87904 175802 87820 175802 87821 175802 87904 175803 87821 175803 87810 175803 87928 175804 87822 175804 87938 175804 87938 175805 87822 175805 83931 175805 87938 175806 83931 175806 87823 175806 87844 175807 87824 175807 87843 175807 87843 175808 87824 175808 83904 175808 87898 175809 83908 175809 87837 175809 87837 175810 83908 175810 83909 175810 87825 175811 87815 175811 83916 175811 83916 175812 87815 175812 87826 175812 83916 175813 87826 175813 83917 175813 83917 175814 87826 175814 87874 175814 83917 175815 87874 175815 87827 175815 87827 175816 87874 175816 87828 175816 87827 175817 87828 175817 83918 175817 83918 175818 87828 175818 87829 175818 83918 175819 87829 175819 87830 175819 87830 175820 87829 175820 87831 175820 87830 175821 87831 175821 83920 175821 83920 175822 87831 175822 87832 175822 83920 175823 87832 175823 83921 175823 83921 175824 87832 175824 87833 175824 83921 175825 87833 175825 87834 175825 87834 175826 87833 175826 87835 175826 87834 175827 87835 175827 87836 175827 87836 175828 87835 175828 87881 175828 87836 175829 87881 175829 87841 175829 87837 175830 83909 175830 87885 175830 87885 175831 83909 175831 87838 175831 87885 175832 87838 175832 87884 175832 87884 175833 87838 175833 87840 175833 87884 175834 87840 175834 87839 175834 87839 175835 87840 175835 87841 175835 87839 175836 87841 175836 87842 175836 87842 175837 87841 175837 87881 175837 87843 175838 83904 175838 87898 175838 87898 175839 83904 175839 83908 175839 87845 175840 87824 175840 87844 175840 87845 175841 87844 175841 83905 175841 87967 175842 87860 175842 87846 175842 87846 175843 87860 175843 87852 175843 87844 175844 87847 175844 83905 175844 83905 175845 87847 175845 87848 175845 83905 175846 87848 175846 87849 175846 87849 175847 87848 175847 87944 175847 87849 175848 87944 175848 87850 175848 87850 175849 87944 175849 87851 175849 87850 175850 87851 175850 87852 175850 87852 175851 87851 175851 87853 175851 87852 175852 87853 175852 87846 175852 87854 175853 83967 175853 87855 175853 87855 175854 83967 175854 83966 175854 87855 175855 83966 175855 87970 175855 83966 175856 87856 175856 87970 175856 87970 175857 87856 175857 87857 175857 87970 175858 87857 175858 87968 175858 87968 175859 87857 175859 87858 175859 87968 175860 87858 175860 87859 175860 87859 175861 87858 175861 83965 175861 87859 175862 83965 175862 87967 175862 87967 175863 83965 175863 83903 175863 87967 175864 83903 175864 87860 175864 83967 175865 87854 175865 87861 175865 87861 175866 87854 175866 87977 175866 87861 175867 87977 175867 83968 175867 83968 175868 87977 175868 87862 175868 83968 175869 87862 175869 87863 175869 87863 175870 87862 175870 87988 175870 87863 175871 87988 175871 87864 175871 87864 175872 87988 175872 87865 175872 87864 175873 87865 175873 84003 175873 84003 175874 87865 175874 87866 175874 84003 175875 87866 175875 83933 175875 83933 175876 87866 175876 87995 175876 83933 175877 87995 175877 87867 175877 87867 175878 87995 175878 87997 175878 87867 175879 87997 175879 87868 175879 87868 175880 87997 175880 87996 175880 87868 175881 87996 175881 87869 175881 87869 175882 87996 175882 87981 175882 87869 175883 87981 175883 83935 175883 83935 175884 87981 175884 83936 175884 83936 175885 87981 175885 87983 175885 83936 175886 87983 175886 87871 175886 87871 175887 87983 175887 87870 175887 87871 175888 87870 175888 83937 175888 87896 175889 87897 175889 84075 175889 87873 175890 87826 175890 87872 175890 87872 175891 87826 175891 87815 175891 87872 175892 87815 175892 87896 175892 87880 175893 87829 175893 87876 175893 87876 175894 87829 175894 87828 175894 87876 175895 87828 175895 87873 175895 87873 175896 87828 175896 87874 175896 87873 175897 87874 175897 87826 175897 87896 175898 84075 175898 87872 175898 87872 175899 84075 175899 84073 175899 87872 175900 84073 175900 87873 175900 87873 175901 84073 175901 87875 175901 87873 175902 87875 175902 87876 175902 87876 175903 87875 175903 84072 175903 87876 175904 84072 175904 87880 175904 87880 175905 84072 175905 84071 175905 87880 175906 84071 175906 87879 175906 87879 175907 84071 175907 84070 175907 87879 175908 84070 175908 87877 175908 87877 175909 84070 175909 84069 175909 87877 175910 84069 175910 87878 175910 87878 175911 87835 175911 87877 175911 87877 175912 87835 175912 87833 175912 87877 175913 87833 175913 87879 175913 87879 175914 87833 175914 87832 175914 87879 175915 87832 175915 87880 175915 87880 175916 87832 175916 87831 175916 87880 175917 87831 175917 87829 175917 87839 175918 87842 175918 87878 175918 87878 175919 87842 175919 87881 175919 87878 175920 87881 175920 87835 175920 87886 175921 87883 175921 87887 175921 87887 175922 87883 175922 87882 175922 84069 175923 87882 175923 87878 175923 87878 175924 87882 175924 87883 175924 87878 175925 87883 175925 87839 175925 87839 175926 87883 175926 87886 175926 87839 175927 87886 175927 87884 175927 87885 175928 87884 175928 87888 175928 87888 175929 87884 175929 87886 175929 87888 175930 87886 175930 87890 175930 87890 175931 87886 175931 87887 175931 87837 175932 87885 175932 87900 175932 87900 175933 87885 175933 87888 175933 87900 175934 87888 175934 87889 175934 87889 175935 87888 175935 87890 175935 87891 175936 87892 175936 87894 175936 87894 175937 87892 175937 87893 175937 87894 175938 87893 175938 84055 175938 84055 175939 87893 175939 87895 175939 87815 175940 87891 175940 87896 175940 87896 175941 87891 175941 87894 175941 87896 175942 87894 175942 87897 175942 87897 175943 87894 175943 84055 175943 87922 175944 87900 175944 84115 175944 84115 175945 87900 175945 87889 175945 87898 175946 87837 175946 87926 175946 87926 175947 87837 175947 87900 175947 87926 175948 87900 175948 87899 175948 87899 175949 87900 175949 87922 175949 87901 175950 84077 175950 84076 175950 87811 175951 87931 175951 87902 175951 87905 175952 87907 175952 87919 175952 87919 175953 87907 175953 87903 175953 87919 175954 87903 175954 87920 175954 87920 175955 87903 175955 87814 175955 87920 175956 87814 175956 87902 175956 87902 175957 87814 175957 87812 175957 87902 175958 87812 175958 87811 175958 87908 175959 87904 175959 87905 175959 87905 175960 87904 175960 87906 175960 87905 175961 87906 175961 87907 175961 87905 175962 87917 175962 87908 175962 87908 175963 87917 175963 87916 175963 87908 175964 87916 175964 87819 175964 87819 175965 87916 175965 87818 175965 87901 175966 84076 175966 87921 175966 87921 175967 84076 175967 87909 175967 87921 175968 87909 175968 87910 175968 87910 175969 87909 175969 87911 175969 87910 175970 87911 175970 87912 175970 87912 175971 87911 175971 87913 175971 87912 175972 87913 175972 87918 175972 87918 175973 87913 175973 84082 175973 87918 175974 84082 175974 87914 175974 87914 175975 84082 175975 84080 175975 87914 175976 84080 175976 87915 175976 87915 175977 84080 175977 87895 175977 87915 175978 87895 175978 87893 175978 87892 175979 87818 175979 87893 175979 87893 175980 87818 175980 87916 175980 87893 175981 87916 175981 87915 175981 87915 175982 87916 175982 87917 175982 87915 175983 87917 175983 87914 175983 87914 175984 87917 175984 87905 175984 87914 175985 87905 175985 87918 175985 87918 175986 87905 175986 87919 175986 87918 175987 87919 175987 87912 175987 87912 175988 87919 175988 87920 175988 87912 175989 87920 175989 87910 175989 87910 175990 87920 175990 87902 175990 87910 175991 87902 175991 87921 175991 87921 175992 87902 175992 87931 175992 87921 175993 87931 175993 87901 175993 84115 175994 84114 175994 87922 175994 87922 175995 84114 175995 87923 175995 87922 175996 87923 175996 87899 175996 87899 175997 87923 175997 87924 175997 87899 175998 87924 175998 87926 175998 87926 175999 87924 175999 87925 175999 87926 176000 87925 176000 87898 176000 87898 176001 87925 176001 87843 176001 87927 176002 87928 176002 87932 176002 87932 176003 87928 176003 87929 176003 87932 176004 87929 176004 87930 176004 87930 176005 87929 176005 87940 176005 87930 176006 87940 176006 84100 176006 84100 176007 87940 176007 84102 176007 87811 176008 87927 176008 87931 176008 87931 176009 87927 176009 87932 176009 87931 176010 87932 176010 87901 176010 87901 176011 87932 176011 87930 176011 87901 176012 87930 176012 84077 176012 84077 176013 87930 176013 84100 176013 87941 176014 87844 176014 87843 176014 84114 176015 87933 176015 87923 176015 87923 176016 87933 176016 87942 176016 87923 176017 87942 176017 87924 176017 87924 176018 87942 176018 87941 176018 87924 176019 87941 176019 87925 176019 87925 176020 87941 176020 87843 176020 87938 176021 87823 176021 87939 176021 87939 176022 87823 176022 87934 176022 87939 176023 87934 176023 87935 176023 87935 176024 87934 176024 87936 176024 87935 176025 87936 176025 84103 176025 84103 176026 87936 176026 87937 176026 87928 176027 87938 176027 87929 176027 87929 176028 87938 176028 87939 176028 87929 176029 87939 176029 87940 176029 87940 176030 87939 176030 87935 176030 87940 176031 87935 176031 84102 176031 84102 176032 87935 176032 84103 176032 87941 176033 87942 176033 87948 176033 87941 176034 87948 176034 87946 176034 87946 176035 87948 176035 87943 176035 87946 176036 87943 176036 87945 176036 87944 176037 87848 176037 87945 176037 87945 176038 87848 176038 87847 176038 87945 176039 87847 176039 87946 176039 87946 176040 87847 176040 87844 176040 87946 176041 87844 176041 87941 176041 87947 176042 87943 176042 84113 176042 84113 176043 87943 176043 87948 176043 84113 176044 87948 176044 87949 176044 87949 176045 87948 176045 87942 176045 87949 176046 87942 176046 87933 176046 87851 176047 87944 176047 87955 176047 87955 176048 87944 176048 87945 176048 87955 176049 87945 176049 87950 176049 87950 176050 87945 176050 87943 176050 87950 176051 87943 176051 87957 176051 87957 176052 87943 176052 87947 176052 87953 176053 87808 176053 87951 176053 87951 176054 87808 176054 87974 176054 87951 176055 87974 176055 87954 176055 87954 176056 87974 176056 87952 176056 87954 176057 87952 176057 84110 176057 84110 176058 87952 176058 84109 176058 87823 176059 87953 176059 87934 176059 87934 176060 87953 176060 87951 176060 87934 176061 87951 176061 87936 176061 87936 176062 87951 176062 87954 176062 87936 176063 87954 176063 87937 176063 87937 176064 87954 176064 84110 176064 87957 176065 87947 176065 84209 176065 87851 176066 87955 176066 87956 176066 87956 176067 87955 176067 87950 176067 87956 176068 87950 176068 87957 176068 87851 176069 87956 176069 87853 176069 87853 176070 87956 176070 87959 176070 87853 176071 87959 176071 87846 176071 87957 176072 84209 176072 87956 176072 87956 176073 84209 176073 87958 176073 87956 176074 87958 176074 87959 176074 87959 176075 87958 176075 87960 176075 87959 176076 87960 176076 87961 176076 87961 176077 87960 176077 87963 176077 87961 176078 87963 176078 87962 176078 87962 176079 87963 176079 84204 176079 87962 176080 84204 176080 87969 176080 87969 176081 84204 176081 87964 176081 87969 176082 87964 176082 87971 176082 87971 176083 87964 176083 87965 176083 87971 176084 87965 176084 87966 176084 87846 176085 87959 176085 87967 176085 87967 176086 87959 176086 87961 176086 87967 176087 87961 176087 87859 176087 87859 176088 87961 176088 87962 176088 87859 176089 87962 176089 87968 176089 87968 176090 87962 176090 87969 176090 87968 176091 87969 176091 87970 176091 87970 176092 87969 176092 87971 176092 87970 176093 87971 176093 87855 176093 87855 176094 87971 176094 87966 176094 87855 176095 87966 176095 87854 176095 87973 176096 87870 176096 87975 176096 87975 176097 87870 176097 87972 176097 87975 176098 87972 176098 87976 176098 87976 176099 87972 176099 87984 176099 87976 176100 87984 176100 84098 176100 84098 176101 87984 176101 84099 176101 87808 176102 87973 176102 87974 176102 87974 176103 87973 176103 87975 176103 87974 176104 87975 176104 87952 176104 87952 176105 87975 176105 87976 176105 87952 176106 87976 176106 84109 176106 84109 176107 87976 176107 84098 176107 87862 176108 87977 176108 87992 176108 87992 176109 87977 176109 87980 176109 87992 176110 87980 176110 87991 176110 87991 176111 87980 176111 87978 176111 87978 176112 87980 176112 84202 176112 87978 176113 84202 176113 87979 176113 87977 176114 87854 176114 87980 176114 87980 176115 87854 176115 87966 176115 87980 176116 87966 176116 84202 176116 84202 176117 87966 176117 87965 176117 87981 176118 87996 176118 87998 176118 87982 176119 88000 176119 87985 176119 87985 176120 88000 176120 84144 176120 87985 176121 84144 176121 87986 176121 87983 176122 87981 176122 87982 176122 87982 176123 87981 176123 87998 176123 87982 176124 87998 176124 88000 176124 87870 176125 87983 176125 87972 176125 87972 176126 87983 176126 87982 176126 87972 176127 87982 176127 87984 176127 87984 176128 87982 176128 87985 176128 87984 176129 87985 176129 84099 176129 84099 176130 87985 176130 87986 176130 87993 176131 87987 176131 88003 176131 87988 176132 87862 176132 87992 176132 87991 176133 87978 176133 87987 176133 88002 176134 84144 176134 88000 176134 87988 176135 87992 176135 87865 176135 87993 176136 88003 176136 87994 176136 87994 176137 88003 176137 87990 176137 87994 176138 87990 176138 87989 176138 87989 176139 87990 176139 88001 176139 87989 176140 88001 176140 87999 176140 87991 176141 87987 176141 87992 176141 87992 176142 87987 176142 87993 176142 87992 176143 87993 176143 87865 176143 87865 176144 87993 176144 87994 176144 87865 176145 87994 176145 87866 176145 87866 176146 87994 176146 87989 176146 87866 176147 87989 176147 87995 176147 87995 176148 87989 176148 87999 176148 87995 176149 87999 176149 87997 176149 87996 176150 87997 176150 87998 176150 87998 176151 87997 176151 87999 176151 87998 176152 87999 176152 88000 176152 88000 176153 87999 176153 88001 176153 88000 176154 88001 176154 88002 176154 88002 176155 88001 176155 87990 176155 88002 176156 87990 176156 88004 176156 88004 176157 87990 176157 88003 176157 88004 176158 88003 176158 84138 176158 84138 176159 88003 176159 87987 176159 84138 176160 87987 176160 84139 176160 84139 176161 87987 176161 87978 176161 84139 176162 87978 176162 87979 176162 88013 176163 87763 176163 87761 176163 88007 176164 84065 176164 88008 176164 87760 176165 87758 176165 88010 176165 88010 176166 87758 176166 87757 176166 88010 176167 87757 176167 88005 176167 88005 176168 87757 176168 88006 176168 88005 176169 88006 176169 88007 176169 87760 176170 88010 176170 87761 176170 87761 176171 88010 176171 88011 176171 87761 176172 88011 176172 88013 176172 88007 176173 88008 176173 88005 176173 88005 176174 88008 176174 88009 176174 88005 176175 88009 176175 88010 176175 88010 176176 88009 176176 84063 176176 88010 176177 84063 176177 88011 176177 88011 176178 84063 176178 88012 176178 88011 176179 88012 176179 88013 176179 88013 176180 88012 176180 84059 176180 88013 176181 84059 176181 88014 176181 88014 176182 84059 176182 84057 176182 88014 176183 84057 176183 88015 176183 88015 176184 84057 176184 88016 176184 88015 176185 88016 176185 88020 176185 88020 176186 88016 176186 84056 176186 88020 176187 84056 176187 88017 176187 88017 176188 84056 176188 88018 176188 88017 176189 88018 176189 88019 176189 87763 176190 88013 176190 87764 176190 87764 176191 88013 176191 88014 176191 87764 176192 88014 176192 87765 176192 87765 176193 88014 176193 88015 176193 87765 176194 88015 176194 87766 176194 87766 176195 88015 176195 88020 176195 87766 176196 88020 176196 87756 176196 87756 176197 88020 176197 88017 176197 87756 176198 88017 176198 88021 176198 88021 176199 88017 176199 88019 176199 88021 176200 88019 176200 88027 176200 88007 176201 88022 176201 84065 176201 84065 176202 88022 176202 84066 176202 88006 176203 88030 176203 88007 176203 88007 176204 88030 176204 88031 176204 88007 176205 88031 176205 88022 176205 88019 176206 88018 176206 88023 176206 88027 176207 88019 176207 88024 176207 88019 176208 88023 176208 88024 176208 88024 176209 88023 176209 88025 176209 88024 176210 88025 176210 88026 176210 88026 176211 88025 176211 84054 176211 88026 176212 84054 176212 88029 176212 88027 176213 88024 176213 88028 176213 88028 176214 88024 176214 88026 176214 88028 176215 88026 176215 87777 176215 87777 176216 88026 176216 88029 176216 87777 176217 88029 176217 88047 176217 88032 176218 84067 176218 84066 176218 88031 176219 88030 176219 87770 176219 87770 176220 88060 176220 88031 176220 88031 176221 88060 176221 88032 176221 88031 176222 88032 176222 88022 176222 88022 176223 88032 176223 84066 176223 88047 176224 88029 176224 88048 176224 88033 176225 88044 176225 84081 176225 88033 176226 84081 176226 88034 176226 88034 176227 84081 176227 88035 176227 88034 176228 88035 176228 88037 176228 88037 176229 88035 176229 88036 176229 88037 176230 88036 176230 88038 176230 88038 176231 88036 176231 84078 176231 88038 176232 84078 176232 88040 176232 88040 176233 84078 176233 88039 176233 88040 176234 88039 176234 88041 176234 88041 176235 88039 176235 88042 176235 88041 176236 88042 176236 88043 176236 84054 176237 88044 176237 88029 176237 88029 176238 88044 176238 88033 176238 88029 176239 88033 176239 88048 176239 88048 176240 88033 176240 88034 176240 88048 176241 88034 176241 88045 176241 88045 176242 88034 176242 88037 176242 88045 176243 88037 176243 88051 176243 88051 176244 88037 176244 88038 176244 88051 176245 88038 176245 88052 176245 88052 176246 88038 176246 88040 176246 88052 176247 88040 176247 88053 176247 88053 176248 88040 176248 88041 176248 88053 176249 88041 176249 88054 176249 88054 176250 88041 176250 88043 176250 88054 176251 88043 176251 88046 176251 88047 176252 88048 176252 88049 176252 88049 176253 88048 176253 88045 176253 88049 176254 88045 176254 88050 176254 88050 176255 88045 176255 88051 176255 88050 176256 88051 176256 87779 176256 87779 176257 88051 176257 88052 176257 87779 176258 88052 176258 87780 176258 87780 176259 88052 176259 88053 176259 87780 176260 88053 176260 87783 176260 87783 176261 88053 176261 88054 176261 87783 176262 88054 176262 88055 176262 88055 176263 88054 176263 88046 176263 88055 176264 88046 176264 88063 176264 88056 176265 88079 176265 88057 176265 88057 176266 88079 176266 84060 176266 88059 176267 88086 176267 88061 176267 88061 176268 88086 176268 88080 176268 88061 176269 88080 176269 88056 176269 88056 176270 88080 176270 88058 176270 88056 176271 88058 176271 88079 176271 87770 176272 88059 176272 88060 176272 88060 176273 88059 176273 88061 176273 88060 176274 88061 176274 88032 176274 88032 176275 88061 176275 88056 176275 88032 176276 88056 176276 84067 176276 84067 176277 88056 176277 88057 176277 88062 176278 88063 176278 88064 176278 88064 176279 88063 176279 88046 176279 88064 176280 88046 176280 88065 176280 88065 176281 88046 176281 88043 176281 88065 176282 88043 176282 84086 176282 84086 176283 88043 176283 88042 176283 88087 176284 88062 176284 88066 176284 88066 176285 88062 176285 88064 176285 88066 176286 88064 176286 88089 176286 88089 176287 88064 176287 88065 176287 88089 176288 88065 176288 84087 176288 84087 176289 88065 176289 84086 176289 88067 176290 88081 176290 88077 176290 88097 176291 88098 176291 88068 176291 88069 176292 88097 176292 88072 176292 88069 176293 88072 176293 87798 176293 87798 176294 88072 176294 88073 176294 87798 176295 88073 176295 88070 176295 88070 176296 88073 176296 88075 176296 88070 176297 88075 176297 87807 176297 87807 176298 88075 176298 88071 176298 87807 176299 88071 176299 87805 176299 88067 176300 88077 176300 88076 176300 88097 176301 88068 176301 88072 176301 88072 176302 88068 176302 88074 176302 88072 176303 88074 176303 88073 176303 88073 176304 88074 176304 85820 176304 88073 176305 85820 176305 88075 176305 88075 176306 85820 176306 88076 176306 88075 176307 88076 176307 88071 176307 88071 176308 88076 176308 88077 176308 88071 176309 88077 176309 87805 176309 88083 176310 87802 176310 88077 176310 88077 176311 87802 176311 87804 176311 88077 176312 87804 176312 87805 176312 88078 176313 88084 176313 85817 176313 85817 176314 88084 176314 88082 176314 85817 176315 84060 176315 88079 176315 85817 176316 88079 176316 88078 176316 88078 176317 88079 176317 88058 176317 88078 176318 88058 176318 88080 176318 88081 176319 88082 176319 88077 176319 88077 176320 88082 176320 88084 176320 88077 176321 88084 176321 88083 176321 88083 176322 88084 176322 88078 176322 88083 176323 88078 176323 88085 176323 88085 176324 88078 176324 88080 176324 88085 176325 88080 176325 88086 176325 87774 176326 88087 176326 88090 176326 88090 176327 88087 176327 88066 176327 88090 176328 88066 176328 88091 176328 88091 176329 88066 176329 88089 176329 88091 176330 88089 176330 88088 176330 88088 176331 88089 176331 84087 176331 87794 176332 87774 176332 88103 176332 88103 176333 87774 176333 88090 176333 88103 176334 88090 176334 88092 176334 88092 176335 88090 176335 88091 176335 88092 176336 88091 176336 88093 176336 88093 176337 88091 176337 88088 176337 88095 176338 88094 176338 88121 176338 88121 176339 88120 176339 88095 176339 88095 176340 88120 176340 88117 176340 88095 176341 88117 176341 88096 176341 88096 176342 88117 176342 88112 176342 88096 176343 88112 176343 85768 176343 88069 176344 88094 176344 88097 176344 88097 176345 88094 176345 88095 176345 88097 176346 88095 176346 88098 176346 88098 176347 88095 176347 88096 176347 87790 176348 87793 176348 88099 176348 87790 176349 88099 176349 88113 176349 88113 176350 88099 176350 88101 176350 88113 176351 88101 176351 88100 176351 88100 176352 88101 176352 88102 176352 88100 176353 88102 176353 84084 176353 87793 176354 87794 176354 88099 176354 88099 176355 87794 176355 88103 176355 88099 176356 88103 176356 88101 176356 88101 176357 88103 176357 88092 176357 88101 176358 88092 176358 88102 176358 88102 176359 88092 176359 88093 176359 87790 176360 88113 176360 88104 176360 88100 176361 84084 176361 88106 176361 88113 176362 88100 176362 88107 176362 87790 176363 88104 176363 88105 176363 88105 176364 88104 176364 88114 176364 88105 176365 88114 176365 88118 176365 88100 176366 88106 176366 88107 176366 88107 176367 88106 176367 85774 176367 88107 176368 85774 176368 88108 176368 88108 176369 85774 176369 88109 176369 88108 176370 88109 176370 88115 176370 88115 176371 88109 176371 88110 176371 88115 176372 88110 176372 88111 176372 88110 176373 85768 176373 88111 176373 88111 176374 85768 176374 88112 176374 88111 176375 88112 176375 88117 176375 88113 176376 88107 176376 88104 176376 88104 176377 88107 176377 88108 176377 88104 176378 88108 176378 88114 176378 88114 176379 88108 176379 88115 176379 88114 176380 88115 176380 88119 176380 88119 176381 88115 176381 88111 176381 88119 176382 88111 176382 88116 176382 88116 176383 88111 176383 88117 176383 88116 176384 88117 176384 88120 176384 88118 176385 88114 176385 87789 176385 87789 176386 88114 176386 88119 176386 87789 176387 88119 176387 87787 176387 87787 176388 88119 176388 88116 176388 87787 176389 88116 176389 87785 176389 87785 176390 88116 176390 88120 176390 87785 176391 88120 176391 88121 176391 88198 176392 88494 176392 91650 176392 91650 176393 88494 176393 88197 176393 88200 176394 88495 176394 88122 176394 88122 176395 88495 176395 88123 176395 91653 176396 88124 176396 91654 176396 91654 176397 88124 176397 88125 176397 88126 176398 88492 176398 91655 176398 91655 176399 88492 176399 88487 176399 91656 176400 88486 176400 88127 176400 88127 176401 88486 176401 88488 176401 88128 176402 88484 176402 91674 176402 91674 176403 88484 176403 88202 176403 91677 176404 91678 176404 88129 176404 88130 176405 91677 176405 88511 176405 88511 176406 91677 176406 88129 176406 88511 176407 88129 176407 88131 176407 88191 176408 88161 176408 88132 176408 88132 176409 88161 176409 88133 176409 88132 176410 88133 176410 88134 176410 91640 176411 88185 176411 91638 176411 91638 176412 88185 176412 88181 176412 91638 176413 88181 176413 88192 176413 88135 176414 88561 176414 88136 176414 88136 176415 88561 176415 91649 176415 88183 176416 88184 176416 88561 176416 88561 176417 88184 176417 88199 176417 88561 176418 88199 176418 91649 176418 88137 176419 88138 176419 88139 176419 88481 176420 88552 176420 88139 176420 88139 176421 88552 176421 88140 176421 88139 176422 88140 176422 88137 176422 88143 176423 88141 176423 88565 176423 88476 176424 88475 176424 88565 176424 88565 176425 88475 176425 88142 176425 88565 176426 88142 176426 88143 176426 89089 176427 91679 176427 88144 176427 88144 176428 91679 176428 88568 176428 88145 176429 91673 176429 88146 176429 88146 176430 91673 176430 88144 176430 88146 176431 88144 176431 88147 176431 88147 176432 88144 176432 88568 176432 88147 176433 88568 176433 88555 176433 88151 176434 88474 176434 88470 176434 88148 176435 88560 176435 88150 176435 88150 176436 88560 176436 88149 176436 88150 176437 88149 176437 88470 176437 88470 176438 88149 176438 88151 176438 88151 176439 88149 176439 88569 176439 88151 176440 88569 176440 88152 176440 88170 176441 88153 176441 88168 176441 88168 176442 88153 176442 91667 176442 88168 176443 91667 176443 88154 176443 88155 176444 88204 176444 88558 176444 88203 176445 88155 176445 88156 176445 88156 176446 88155 176446 88558 176446 88156 176447 88558 176447 88559 176447 88559 176448 88558 176448 88177 176448 88194 176449 88193 176449 88157 176449 88157 176450 88193 176450 88482 176450 88573 176451 88576 176451 88158 176451 88574 176452 88159 176452 88473 176452 88473 176453 88159 176453 88573 176453 88473 176454 88573 176454 88160 176454 88160 176455 88573 176455 88158 176455 88191 176456 90421 176456 88161 176456 88161 176457 90421 176457 88508 176457 88161 176458 88508 176458 88162 176458 88191 176459 88163 176459 90421 176459 90421 176460 88163 176460 88164 176460 90421 176461 88164 176461 91919 176461 88472 176462 91886 176462 90419 176462 90419 176463 91886 176463 88165 176463 90419 176464 88165 176464 88166 176464 91666 176465 88167 176465 88154 176465 88154 176466 88167 176466 90427 176466 88154 176467 90427 176467 88168 176467 88168 176468 90427 176468 88169 176468 88168 176469 88169 176469 88170 176469 88195 176470 88170 176470 88171 176470 88171 176471 88170 176471 88169 176471 88171 176472 88169 176472 88172 176472 88172 176473 88169 176473 88173 176473 88172 176474 88173 176474 88174 176474 88174 176475 88173 176475 91662 176475 88177 176476 88173 176476 88559 176476 88559 176477 88173 176477 88166 176477 88559 176478 88166 176478 88175 176478 88175 176479 88166 176479 88165 176479 88176 176480 88178 176480 88177 176480 88177 176481 88178 176481 91659 176481 88177 176482 91659 176482 88173 176482 88173 176483 91659 176483 88179 176483 88173 176484 88179 176484 91662 176484 90421 176485 91919 176485 91637 176485 88185 176486 88180 176486 88181 176486 88181 176487 88180 176487 90421 176487 88181 176488 90421 176488 88192 176488 88192 176489 90421 176489 91637 176489 91648 176490 88182 176490 88189 176490 88189 176491 88182 176491 88184 176491 88549 176492 88562 176492 88183 176492 88183 176493 88562 176493 90417 176493 88183 176494 90417 176494 88184 176494 88184 176495 90417 176495 88188 176495 88184 176496 88188 176496 88189 176496 88190 176497 91641 176497 88185 176497 88185 176498 91641 176498 91643 176498 88185 176499 91643 176499 88180 176499 88180 176500 91643 176500 88186 176500 88180 176501 88186 176501 88188 176501 88188 176502 88186 176502 88187 176502 88188 176503 88187 176503 88189 176503 91640 176504 88190 176504 88185 176504 88163 176505 88191 176505 88132 176505 91638 176506 88192 176506 91637 176506 91677 176507 88130 176507 91675 176507 91675 176508 88130 176508 91911 176508 91902 176509 88193 176509 88194 176509 88153 176510 88170 176510 88195 176510 88134 176511 88133 176511 88507 176511 88507 176512 88133 176512 88506 176512 88196 176513 88548 176513 91678 176513 91678 176514 88548 176514 88129 176514 91650 176515 88197 176515 91651 176515 88493 176516 88494 176516 88198 176516 88199 176517 88182 176517 91649 176517 91649 176518 88182 176518 91648 176518 88491 176519 88122 176519 88123 176519 91652 176520 88495 176520 88200 176520 91913 176521 91654 176521 88125 176521 91912 176522 88124 176522 91653 176522 88485 176523 91655 176523 88487 176523 88201 176524 88492 176524 88126 176524 88489 176525 88127 176525 88488 176525 91904 176526 88486 176526 91656 176526 91674 176527 88202 176527 88500 176527 88490 176528 88484 176528 88128 176528 91887 176529 88203 176529 88165 176529 88165 176530 88203 176530 88156 176530 88165 176531 88156 176531 88175 176531 91897 176532 88157 176532 88482 176532 88178 176533 88176 176533 88204 176533 88204 176534 88176 176534 88558 176534 91667 176535 91666 176535 88154 176535 90215 176536 88334 176536 88205 176536 88326 176537 88324 176537 88206 176537 88207 176538 89808 176538 88209 176538 88846 176539 89847 176539 88208 176539 88781 176540 88844 176540 88209 176540 88209 176541 88844 176541 88846 176541 88209 176542 88846 176542 88207 176542 88207 176543 88846 176543 88208 176543 89808 176544 88210 176544 88209 176544 88209 176545 88210 176545 89812 176545 88209 176546 89812 176546 89784 176546 89784 176547 89785 176547 88209 176547 88209 176548 89785 176548 89768 176548 88209 176549 89768 176549 89763 176549 88371 176550 91395 176550 88211 176550 88211 176551 91395 176551 91390 176551 88211 176552 91390 176552 88212 176552 88781 176553 88209 176553 88780 176553 88780 176554 88209 176554 88211 176554 88780 176555 88211 176555 88214 176555 88214 176556 88211 176556 88212 176556 88214 176557 88212 176557 91471 176557 91471 176558 91560 176558 88214 176558 88214 176559 91560 176559 88213 176559 88214 176560 88213 176560 91550 176560 91550 176561 88215 176561 88214 176561 88214 176562 88215 176562 88216 176562 88214 176563 88216 176563 88217 176563 88216 176564 91529 176564 88217 176564 88217 176565 91529 176565 91530 176565 88217 176566 91530 176566 88218 176566 88218 176567 91530 176567 88219 176567 88218 176568 88219 176568 88777 176568 88219 176569 88220 176569 88777 176569 88777 176570 88220 176570 88222 176570 88777 176571 88222 176571 88221 176571 88221 176572 88222 176572 91581 176572 88221 176573 91581 176573 88223 176573 88223 176574 91581 176574 91579 176574 88223 176575 91579 176575 88776 176575 88776 176576 91579 176576 91578 176576 88224 176577 88225 176577 91570 176577 91570 176578 88225 176578 88226 176578 91570 176579 88226 176579 91573 176579 91573 176580 88226 176580 88227 176580 91573 176581 88227 176581 91576 176581 91576 176582 88227 176582 88771 176582 91576 176583 88771 176583 88228 176583 88228 176584 88771 176584 88229 176584 88228 176585 88229 176585 91578 176585 91578 176586 88229 176586 88230 176586 91578 176587 88230 176587 88776 176587 88224 176588 91626 176588 88225 176588 88225 176589 91626 176589 91625 176589 88225 176590 91625 176590 88773 176590 88773 176591 91625 176591 88231 176591 88773 176592 88231 176592 88242 176592 88242 176593 88231 176593 91605 176593 88242 176594 91605 176594 91604 176594 91604 176595 91601 176595 88242 176595 88242 176596 91601 176596 91600 176596 88242 176597 91600 176597 91567 176597 88232 176598 88233 176598 88235 176598 88235 176599 88233 176599 91485 176599 88235 176600 91485 176600 91487 176600 91487 176601 91489 176601 88235 176601 88235 176602 91489 176602 91490 176602 88235 176603 91490 176603 88376 176603 91165 176604 88234 176604 88235 176604 88235 176605 88234 176605 91163 176605 88235 176606 91163 176606 88236 176606 88236 176607 91161 176607 88235 176607 88235 176608 91161 176608 91157 176608 88235 176609 91157 176609 88237 176609 91567 176610 88232 176610 88242 176610 88242 176611 88232 176611 88235 176611 88242 176612 88235 176612 88238 176612 88238 176613 88235 176613 88237 176613 88238 176614 88239 176614 88242 176614 88242 176615 88239 176615 88240 176615 88242 176616 88240 176616 88241 176616 88243 176617 91276 176617 88769 176617 88241 176618 91278 176618 88242 176618 88242 176619 91278 176619 88243 176619 88242 176620 88243 176620 88767 176620 88767 176621 88243 176621 88769 176621 91276 176622 88244 176622 88769 176622 88769 176623 88244 176623 91274 176623 88769 176624 91274 176624 88770 176624 88770 176625 91274 176625 91318 176625 88770 176626 91318 176626 88245 176626 88245 176627 91318 176627 88246 176627 88245 176628 88246 176628 88762 176628 88762 176629 88246 176629 88247 176629 88762 176630 88247 176630 88764 176630 88764 176631 88247 176631 88248 176631 88764 176632 88248 176632 88759 176632 88759 176633 88248 176633 91325 176633 88759 176634 91325 176634 88249 176634 88249 176635 91325 176635 88250 176635 88249 176636 88250 176636 88760 176636 88760 176637 88250 176637 88251 176637 88760 176638 88251 176638 88761 176638 88761 176639 88251 176639 91322 176639 88761 176640 91322 176640 88758 176640 88758 176641 91322 176641 88252 176641 88252 176642 91322 176642 88253 176642 88252 176643 88253 176643 88755 176643 88254 176644 88255 176644 91374 176644 91374 176645 88255 176645 88753 176645 91374 176646 88753 176646 91376 176646 91376 176647 88753 176647 88755 176647 91376 176648 88755 176648 91378 176648 91378 176649 88755 176649 88253 176649 88254 176650 91372 176650 88255 176650 88255 176651 91372 176651 91371 176651 88255 176652 91371 176652 88256 176652 88256 176653 88257 176653 88255 176653 88255 176654 88257 176654 91310 176654 88255 176655 91310 176655 88260 176655 91310 176656 91256 176656 88260 176656 88260 176657 91256 176657 91255 176657 88260 176658 91255 176658 91244 176658 91244 176659 91237 176659 88260 176659 88260 176660 91237 176660 91248 176660 88260 176661 91248 176661 88430 176661 88748 176662 88258 176662 88259 176662 88259 176663 88258 176663 88752 176663 88259 176664 88752 176664 88260 176664 88260 176665 88752 176665 88754 176665 88260 176666 88754 176666 88255 176666 88261 176667 90103 176667 88259 176667 88264 176668 88262 176668 88259 176668 88259 176669 88262 176669 90133 176669 88259 176670 90133 176670 88261 176670 90103 176671 90112 176671 88259 176671 88259 176672 90112 176672 90082 176672 88259 176673 90082 176673 88748 176673 88748 176674 90082 176674 90084 176674 88748 176675 90084 176675 88749 176675 88433 176676 88263 176676 88259 176676 88259 176677 88263 176677 90156 176677 88259 176678 90156 176678 88264 176678 90118 176679 90117 176679 88265 176679 88265 176680 90117 176680 90121 176680 88265 176681 90121 176681 88266 176681 88266 176682 90121 176682 90141 176682 88266 176683 90141 176683 90146 176683 90146 176684 90170 176684 88266 176684 88266 176685 90170 176685 90165 176685 88266 176686 90165 176686 88267 176686 88267 176687 90190 176687 88266 176687 88266 176688 90190 176688 90185 176688 88266 176689 90185 176689 90179 176689 88272 176690 88974 176690 88268 176690 88268 176691 88974 176691 88269 176691 88268 176692 88269 176692 88266 176692 88266 176693 88269 176693 88973 176693 88266 176694 88973 176694 88265 176694 88391 176695 91141 176695 88268 176695 91141 176696 88270 176696 88268 176696 88268 176697 88270 176697 91088 176697 88268 176698 91088 176698 88272 176698 88272 176699 91088 176699 91083 176699 91083 176700 88271 176700 88272 176700 88272 176701 88271 176701 91039 176701 88272 176702 91039 176702 91033 176702 91033 176703 88273 176703 88272 176703 88272 176704 88273 176704 91021 176704 88272 176705 91021 176705 88274 176705 88274 176706 91021 176706 91007 176706 88274 176707 91007 176707 88976 176707 88976 176708 91007 176708 88275 176708 88976 176709 88275 176709 88276 176709 88275 176710 91003 176710 88276 176710 88276 176711 91003 176711 88277 176711 88276 176712 88277 176712 88978 176712 88978 176713 88277 176713 88279 176713 88978 176714 88279 176714 88278 176714 88278 176715 88279 176715 90964 176715 88278 176716 90964 176716 88980 176716 88980 176717 90964 176717 90963 176717 88980 176718 90963 176718 88280 176718 88280 176719 90963 176719 88281 176719 88280 176720 88281 176720 88283 176720 88283 176721 88281 176721 88282 176721 88283 176722 88282 176722 88284 176722 88284 176723 88282 176723 88285 176723 88285 176724 88282 176724 88286 176724 88285 176725 88286 176725 88288 176725 88288 176726 88286 176726 88287 176726 88288 176727 88287 176727 88984 176727 88984 176728 88287 176728 88289 176728 88984 176729 88289 176729 88291 176729 88289 176730 88290 176730 88291 176730 88291 176731 88290 176731 90949 176731 88291 176732 90949 176732 88292 176732 88292 176733 90949 176733 90933 176733 88292 176734 90933 176734 88293 176734 88293 176735 90933 176735 88294 176735 88294 176736 90931 176736 88293 176736 88293 176737 90931 176737 90930 176737 88293 176738 90930 176738 88295 176738 88295 176739 88296 176739 88293 176739 88293 176740 88296 176740 88297 176740 88293 176741 88297 176741 88301 176741 88301 176742 88297 176742 88298 176742 88301 176743 88298 176743 90985 176743 90985 176744 88299 176744 88301 176744 88301 176745 88299 176745 88300 176745 88301 176746 88300 176746 91050 176746 90890 176747 90888 176747 88301 176747 88301 176748 90888 176748 90887 176748 90887 176749 90882 176749 88301 176749 88301 176750 90882 176750 90852 176750 88301 176751 90852 176751 88293 176751 88293 176752 90852 176752 90853 176752 90853 176753 90854 176753 88293 176753 88293 176754 90854 176754 90768 176754 88293 176755 90768 176755 88302 176755 90772 176756 90773 176756 88986 176756 88302 176757 90771 176757 88293 176757 88293 176758 90771 176758 90772 176758 88293 176759 90772 176759 88985 176759 88985 176760 90772 176760 88986 176760 90773 176761 90775 176761 88986 176761 88986 176762 90775 176762 88303 176762 88986 176763 88303 176763 88304 176763 90681 176764 90680 176764 88316 176764 88303 176765 90776 176765 88304 176765 88304 176766 90776 176766 88305 176766 88304 176767 88305 176767 88988 176767 88988 176768 88305 176768 88306 176768 88988 176769 88306 176769 88990 176769 88990 176770 88306 176770 88307 176770 88990 176771 88307 176771 88991 176771 88991 176772 88307 176772 90719 176772 88991 176773 90719 176773 88308 176773 88308 176774 90719 176774 90720 176774 88308 176775 90720 176775 88309 176775 88309 176776 90720 176776 88310 176776 88309 176777 88310 176777 88994 176777 88994 176778 88310 176778 90721 176778 88994 176779 90721 176779 88311 176779 88311 176780 90721 176780 88312 176780 88311 176781 88312 176781 88313 176781 88313 176782 88312 176782 88314 176782 88313 176783 88314 176783 88315 176783 88315 176784 88314 176784 88317 176784 88315 176785 88317 176785 88316 176785 88316 176786 88317 176786 88318 176786 88316 176787 88318 176787 90681 176787 90680 176788 90678 176788 88316 176788 88316 176789 90678 176789 90752 176789 88316 176790 90752 176790 90753 176790 88319 176791 90830 176791 88322 176791 88322 176792 90830 176792 88320 176792 88322 176793 88320 176793 90839 176793 90839 176794 88321 176794 88322 176794 88322 176795 88321 176795 90824 176795 88322 176796 90824 176796 88395 176796 90753 176797 88319 176797 88316 176797 88316 176798 88319 176798 88322 176798 88316 176799 88322 176799 88323 176799 88323 176800 88322 176800 88206 176800 88323 176801 88206 176801 88998 176801 88998 176802 88206 176802 88324 176802 89819 176803 88325 176803 88206 176803 89800 176804 89795 176804 88206 176804 88206 176805 89795 176805 89818 176805 88206 176806 89818 176806 89819 176806 88325 176807 89836 176807 88206 176807 88206 176808 89836 176808 89873 176808 88206 176809 89873 176809 88326 176809 88326 176810 89873 176810 89866 176810 88326 176811 89866 176811 89867 176811 88452 176812 89776 176812 88206 176812 88206 176813 89776 176813 89799 176813 88206 176814 89799 176814 89800 176814 90278 176815 88376 176815 88327 176815 88327 176816 88376 176816 88373 176816 88327 176817 88373 176817 90228 176817 90278 176818 88328 176818 88376 176818 88376 176819 88328 176819 88329 176819 88376 176820 88329 176820 88330 176820 88330 176821 90280 176821 88376 176821 88376 176822 90280 176822 90281 176822 88376 176823 90281 176823 90283 176823 88421 176824 88331 176824 88332 176824 88332 176825 88331 176825 88376 176825 88332 176826 88376 176826 88333 176826 88333 176827 88376 176827 90283 176827 88334 176828 88335 176828 88205 176828 88205 176829 88335 176829 90217 176829 88205 176830 90217 176830 88336 176830 88336 176831 90218 176831 88205 176831 88205 176832 90218 176832 88337 176832 88205 176833 88337 176833 88373 176833 88373 176834 88337 176834 88338 176834 88373 176835 88338 176835 90228 176835 88339 176836 90213 176836 88466 176836 88339 176837 88466 176837 88405 176837 88406 176838 90222 176838 88405 176838 90222 176839 88406 176839 90255 176839 90255 176840 88406 176840 88340 176840 90255 176841 88340 176841 90254 176841 90248 176842 88341 176842 88344 176842 88344 176843 88341 176843 88342 176843 88344 176844 88342 176844 88343 176844 90248 176845 88344 176845 90287 176845 90287 176846 88344 176846 88351 176846 90287 176847 88351 176847 88352 176847 88343 176848 88345 176848 88344 176848 88344 176849 88345 176849 90250 176849 88344 176850 90250 176850 88340 176850 88340 176851 90250 176851 90252 176851 88340 176852 90252 176852 90254 176852 88420 176853 88346 176853 88350 176853 88350 176854 88346 176854 90316 176854 88350 176855 90316 176855 90318 176855 90318 176856 88347 176856 88350 176856 88350 176857 88347 176857 88348 176857 88350 176858 88348 176858 90320 176858 90320 176859 88349 176859 88350 176859 88350 176860 88349 176860 90322 176860 88350 176861 90322 176861 88351 176861 88351 176862 90322 176862 90323 176862 88351 176863 90323 176863 88352 176863 90636 176864 88438 176864 88353 176864 90636 176865 88353 176865 88354 176865 88354 176866 88353 176866 90634 176866 90634 176867 88353 176867 88301 176867 90634 176868 88301 176868 90631 176868 88439 176869 88355 176869 88358 176869 88358 176870 88355 176870 88356 176870 88356 176871 88357 176871 88358 176871 88358 176872 88357 176872 90619 176872 88358 176873 90619 176873 88359 176873 90619 176874 90620 176874 88359 176874 88359 176875 90620 176875 90622 176875 88359 176876 90622 176876 88360 176876 88360 176877 90622 176877 90623 176877 88360 176878 90623 176878 90625 176878 88437 176879 90627 176879 88387 176879 88387 176880 90627 176880 88361 176880 88361 176881 88362 176881 88387 176881 88387 176882 88362 176882 90630 176882 88387 176883 90630 176883 88301 176883 88301 176884 90630 176884 88363 176884 88301 176885 88363 176885 90631 176885 90543 176886 90546 176886 88331 176886 88331 176887 90546 176887 90547 176887 88331 176888 90547 176888 88376 176888 88376 176889 90547 176889 90548 176889 88376 176890 90548 176890 90549 176890 90549 176891 90550 176891 88376 176891 88376 176892 90550 176892 88364 176892 88376 176893 88364 176893 88235 176893 88235 176894 88364 176894 88366 176894 88365 176895 88422 176895 88379 176895 88366 176896 90553 176896 88235 176896 88235 176897 90553 176897 90555 176897 88235 176898 90555 176898 88379 176898 88379 176899 90555 176899 90556 176899 88379 176900 90556 176900 88365 176900 88423 176901 90595 176901 88367 176901 88367 176902 90595 176902 90520 176902 90520 176903 88368 176903 88367 176903 88367 176904 88368 176904 90522 176904 88367 176905 90522 176905 88419 176905 88419 176906 90522 176906 88369 176906 88419 176907 88369 176907 88331 176907 88331 176908 88369 176908 90541 176908 88331 176909 90541 176909 90543 176909 91401 176910 91400 176910 88465 176910 88465 176911 91400 176911 91397 176911 88465 176912 91397 176912 88211 176912 88211 176913 91397 176913 88370 176913 88211 176914 88370 176914 88371 176914 90213 176915 90215 176915 88466 176915 88466 176916 90215 176916 88205 176916 88466 176917 88205 176917 91438 176917 91438 176918 88205 176918 91436 176918 91436 176919 88205 176919 88372 176919 88372 176920 88205 176920 88373 176920 88372 176921 88373 176921 88374 176921 91490 176922 91492 176922 88376 176922 88376 176923 91492 176923 88375 176923 88376 176924 88375 176924 91495 176924 91495 176925 91496 176925 88376 176925 88376 176926 91496 176926 91497 176926 88376 176927 91497 176927 88373 176927 88373 176928 91497 176928 91442 176928 88373 176929 91442 176929 88374 176929 88378 176930 91170 176930 88379 176930 88379 176931 91170 176931 88377 176931 88379 176932 88377 176932 88235 176932 88235 176933 88377 176933 91168 176933 88235 176934 91168 176934 91165 176934 88378 176935 88379 176935 91193 176935 91193 176936 88379 176936 88424 176936 91193 176937 88424 176937 88380 176937 88380 176938 88424 176938 88381 176938 88381 176939 88424 176939 88426 176939 88381 176940 88426 176940 88382 176940 88428 176941 91198 176941 88426 176941 88426 176942 91198 176942 91197 176942 88426 176943 91197 176943 88382 176943 91248 176944 91228 176944 88430 176944 88430 176945 91228 176945 88383 176945 88430 176946 88383 176946 88429 176946 88429 176947 88383 176947 88384 176947 88429 176948 88384 176948 88428 176948 88428 176949 88384 176949 88385 176949 88428 176950 88385 176950 91198 176950 91050 176951 91048 176951 88301 176951 88301 176952 91048 176952 88386 176952 88301 176953 88386 176953 88387 176953 88387 176954 88386 176954 91047 176954 88387 176955 91047 176955 91046 176955 91046 176956 91040 176956 88387 176956 88387 176957 91040 176957 91100 176957 88387 176958 91100 176958 88394 176958 88394 176959 91100 176959 91099 176959 88445 176960 88444 176960 88388 176960 88388 176961 88444 176961 91092 176961 91092 176962 88389 176962 88388 176962 88388 176963 88389 176963 91143 176963 88388 176964 91143 176964 88268 176964 88268 176965 91143 176965 88390 176965 88268 176966 88390 176966 88391 176966 91091 176967 88443 176967 88392 176967 88392 176968 88443 176968 88434 176968 88392 176969 88434 176969 88393 176969 91099 176970 91097 176970 88394 176970 88394 176971 91097 176971 91095 176971 88394 176972 91095 176972 88434 176972 88434 176973 91095 176973 91093 176973 88434 176974 91093 176974 88393 176974 90870 176975 88454 176975 90806 176975 90806 176976 88454 176976 88395 176976 90806 176977 88395 176977 90807 176977 90807 176978 88395 176978 90824 176978 88398 176979 90891 176979 88353 176979 88353 176980 90891 176980 88396 176980 88353 176981 88396 176981 88301 176981 88301 176982 88396 176982 88397 176982 88301 176983 88397 176983 90890 176983 88398 176984 88353 176984 90892 176984 90892 176985 88353 176985 88401 176985 90892 176986 88401 176986 88399 176986 88440 176987 88400 176987 88401 176987 88401 176988 88400 176988 90858 176988 88401 176989 90858 176989 88399 176989 90869 176990 88402 176990 88403 176990 88403 176991 88402 176991 90864 176991 88403 176992 90864 176992 88440 176992 88440 176993 90864 176993 90861 176993 88440 176994 90861 176994 88400 176994 88464 176995 88465 176995 88453 176995 88453 176996 88465 176996 88211 176996 88453 176997 88211 176997 88404 176997 88404 176998 88211 176998 88209 176998 88405 176999 88466 176999 88406 176999 88406 177000 88466 177000 88407 177000 88406 177001 88407 177001 88340 177001 88340 177002 88462 177002 88344 177002 88344 177003 88462 177003 88408 177003 88344 177004 88408 177004 88351 177004 88351 177005 88408 177005 88409 177005 88351 177006 88409 177006 88350 177006 88350 177007 88409 177007 88411 177007 88350 177008 88411 177008 88410 177008 88410 177009 88411 177009 88413 177009 88410 177010 88413 177010 88412 177010 88412 177011 88413 177011 88414 177011 88412 177012 88414 177012 88415 177012 88415 177013 88414 177013 88459 177013 88415 177014 88459 177014 88416 177014 88416 177015 88459 177015 88417 177015 88416 177016 88417 177016 88431 177016 88431 177017 88417 177017 88457 177017 88431 177018 88457 177018 88456 177018 88431 177019 88427 177019 88416 177019 88416 177020 88427 177020 88425 177020 88416 177021 88425 177021 88415 177021 88415 177022 88425 177022 88418 177022 88415 177023 88418 177023 88412 177023 88412 177024 88418 177024 88367 177024 88412 177025 88367 177025 88410 177025 88410 177026 88367 177026 88419 177026 88410 177027 88419 177027 88350 177027 88350 177028 88419 177028 88331 177028 88350 177029 88331 177029 88420 177029 88420 177030 88331 177030 88421 177030 88422 177031 88423 177031 88379 177031 88379 177032 88423 177032 88367 177032 88379 177033 88367 177033 88424 177033 88424 177034 88367 177034 88418 177034 88424 177035 88418 177035 88426 177035 88426 177036 88418 177036 88425 177036 88426 177037 88425 177037 88428 177037 88428 177038 88425 177038 88427 177038 88428 177039 88427 177039 88429 177039 88429 177040 88427 177040 88431 177040 88429 177041 88431 177041 88430 177041 88430 177042 88431 177042 88456 177042 88430 177043 88456 177043 88260 177043 88260 177044 88456 177044 88455 177044 88260 177045 88455 177045 88259 177045 88259 177046 88455 177046 88432 177046 88259 177047 88432 177047 88433 177047 88443 177048 88446 177048 88434 177048 88434 177049 88446 177049 88435 177049 88434 177050 88435 177050 88394 177050 88394 177051 88435 177051 88436 177051 88394 177052 88436 177052 88387 177052 88387 177053 88436 177053 88360 177053 88387 177054 88360 177054 88437 177054 88437 177055 88360 177055 90625 177055 88438 177056 88439 177056 88353 177056 88353 177057 88439 177057 88358 177057 88353 177058 88358 177058 88401 177058 88401 177059 88358 177059 88441 177059 88401 177060 88441 177060 88440 177060 88440 177061 88441 177061 88451 177061 88440 177062 88451 177062 88403 177062 88403 177063 88451 177063 88442 177063 88403 177064 88442 177064 90869 177064 91091 177065 91092 177065 88443 177065 88443 177066 91092 177066 88444 177066 88443 177067 88444 177067 88446 177067 88446 177068 88444 177068 88445 177068 88446 177069 88445 177069 88435 177069 88435 177070 88445 177070 88447 177070 88435 177071 88447 177071 88436 177071 88436 177072 88447 177072 88458 177072 88436 177073 88458 177073 88360 177073 88360 177074 88458 177074 88460 177074 88360 177075 88460 177075 88359 177075 88359 177076 88460 177076 88461 177076 88359 177077 88461 177077 88358 177077 88358 177078 88461 177078 88448 177078 88358 177079 88448 177079 88441 177079 88441 177080 88448 177080 88449 177080 88441 177081 88449 177081 88451 177081 88451 177082 88449 177082 88450 177082 88451 177083 88450 177083 88442 177083 88442 177084 88450 177084 88463 177084 89763 177085 89780 177085 88209 177085 88209 177086 89780 177086 88452 177086 88209 177087 88452 177087 88404 177087 88404 177088 88452 177088 88206 177088 88404 177089 88206 177089 88453 177089 88453 177090 88206 177090 88322 177090 88453 177091 88322 177091 88464 177091 88464 177092 88322 177092 88395 177092 88464 177093 88395 177093 88463 177093 88463 177094 88395 177094 88454 177094 88463 177095 88454 177095 88442 177095 88442 177096 88454 177096 90870 177096 88442 177097 90870 177097 90869 177097 90179 177098 88433 177098 88266 177098 88266 177099 88433 177099 88432 177099 88266 177100 88432 177100 88268 177100 88268 177101 88432 177101 88455 177101 88268 177102 88455 177102 88388 177102 88388 177103 88455 177103 88456 177103 88388 177104 88456 177104 88445 177104 88445 177105 88456 177105 88457 177105 88445 177106 88457 177106 88447 177106 88447 177107 88457 177107 88417 177107 88447 177108 88417 177108 88458 177108 88458 177109 88417 177109 88459 177109 88458 177110 88459 177110 88460 177110 88460 177111 88459 177111 88414 177111 88460 177112 88414 177112 88461 177112 88461 177113 88414 177113 88413 177113 88461 177114 88413 177114 88448 177114 88448 177115 88413 177115 88411 177115 88448 177116 88411 177116 88449 177116 88449 177117 88411 177117 88409 177117 88449 177118 88409 177118 88450 177118 88450 177119 88409 177119 88408 177119 88450 177120 88408 177120 88463 177120 88463 177121 88408 177121 88462 177121 88463 177122 88462 177122 88464 177122 88464 177123 88462 177123 88340 177123 88464 177124 88340 177124 88465 177124 88465 177125 88340 177125 88407 177125 88465 177126 88407 177126 91401 177126 91401 177127 88407 177127 88466 177127 91401 177128 88466 177128 91440 177128 91440 177129 88466 177129 91438 177129 88557 177130 91682 177130 88467 177130 88467 177131 91682 177131 88497 177131 91885 177132 91884 177132 88473 177132 88476 177133 88147 177133 90417 177133 88474 177134 90419 177134 88470 177134 88470 177135 90419 177135 90417 177135 88470 177136 90417 177136 88555 177136 88555 177137 90417 177137 88147 177137 90417 177138 88562 177138 88478 177138 88468 177139 88556 177139 88469 177139 88469 177140 88556 177140 88470 177140 88469 177141 88470 177141 88554 177141 88554 177142 88470 177142 88555 177142 91885 177143 88473 177143 88471 177143 88575 177144 88472 177144 88160 177144 88160 177145 88472 177145 90419 177145 88160 177146 90419 177146 88473 177146 88473 177147 90419 177147 88474 177147 88473 177148 88474 177148 88471 177148 88552 177149 88481 177149 90417 177149 90417 177150 88481 177150 88475 177150 90417 177151 88475 177151 88476 177151 88566 177152 88567 177152 88564 177152 88564 177153 88567 177153 88147 177153 88564 177154 88147 177154 88553 177154 88553 177155 88147 177155 88476 177155 88551 177156 88552 177156 88477 177156 88477 177157 88552 177157 90417 177157 88477 177158 90417 177158 91668 177158 91668 177159 90417 177159 88478 177159 88479 177160 88563 177160 88480 177160 88480 177161 88563 177161 88475 177161 88480 177162 88475 177162 88550 177162 88550 177163 88475 177163 88481 177163 88167 177164 91897 177164 88482 177164 91902 177165 91903 177165 88193 177165 88193 177166 91903 177166 88483 177166 88193 177167 88483 177167 88482 177167 88482 177168 88483 177168 90427 177168 88482 177169 90427 177169 88167 177169 90439 177170 88496 177170 88484 177170 88484 177171 88496 177171 88202 177171 88487 177172 88492 177172 90439 177172 88486 177173 91904 177173 88485 177173 88485 177174 88487 177174 88486 177174 88486 177175 88487 177175 90439 177175 88486 177176 90439 177176 88488 177176 88488 177177 90439 177177 88484 177177 88488 177178 88484 177178 88489 177178 88489 177179 88484 177179 88490 177179 88123 177180 88495 177180 90439 177180 88124 177181 91912 177181 88491 177181 88491 177182 88123 177182 88124 177182 88124 177183 88123 177183 90439 177183 88124 177184 90439 177184 88125 177184 88125 177185 90439 177185 88492 177185 88125 177186 88492 177186 91913 177186 91913 177187 88492 177187 88201 177187 88493 177188 88514 177188 88494 177188 88494 177189 88514 177189 90439 177189 88494 177190 90439 177190 88197 177190 88197 177191 90439 177191 88495 177191 88197 177192 88495 177192 91651 177192 91651 177193 88495 177193 91652 177193 88467 177194 90451 177194 88503 177194 88202 177195 88496 177195 90449 177195 90451 177196 88467 177196 90449 177196 90449 177197 88467 177197 88497 177197 90449 177198 88497 177198 91907 177198 91907 177199 91906 177199 90449 177199 90449 177200 91906 177200 88498 177200 90449 177201 88498 177201 88202 177201 88202 177202 88498 177202 88499 177202 88202 177203 88499 177203 88500 177203 88502 177204 88501 177204 88467 177204 88502 177205 88467 177205 88504 177205 88504 177206 88467 177206 88503 177206 88504 177207 88503 177207 88505 177207 88505 177208 88503 177208 88483 177208 88505 177209 88483 177209 91903 177209 88131 177210 88548 177210 88196 177210 88506 177211 88162 177211 88507 177211 88507 177212 88162 177212 88508 177212 88507 177213 88508 177213 91684 177213 91684 177214 88508 177214 88509 177214 91684 177215 88509 177215 88510 177215 88511 177216 90437 177216 88130 177216 88130 177217 90437 177217 88513 177217 88130 177218 88513 177218 91911 177218 88511 177219 88131 177219 90437 177219 90437 177220 88131 177220 88196 177220 90437 177221 88196 177221 88509 177221 88509 177222 88196 177222 91910 177222 88509 177223 91910 177223 88510 177223 91911 177224 88513 177224 88512 177224 88512 177225 88513 177225 90439 177225 88512 177226 90439 177226 88514 177226 90230 177227 90291 177227 88515 177227 90230 177228 88515 177228 88516 177228 88516 177229 88515 177229 90356 177229 88516 177230 90356 177230 90232 177230 90232 177231 90356 177231 90233 177231 90233 177232 90356 177232 88518 177232 90233 177233 88518 177233 88521 177233 90391 177234 88517 177234 88518 177234 88518 177235 88517 177235 90236 177235 90236 177236 88519 177236 88518 177236 88518 177237 88519 177237 88520 177237 88518 177238 88520 177238 88521 177238 90286 177239 88522 177239 88523 177239 88523 177240 88522 177240 88515 177240 88523 177241 88515 177241 90291 177241 90299 177242 90297 177242 90349 177242 90299 177243 90349 177243 90300 177243 90300 177244 90349 177244 88524 177244 90300 177245 88524 177245 88526 177245 88525 177246 88530 177246 88524 177246 88524 177247 88530 177247 90302 177247 88524 177248 90302 177248 88526 177248 90286 177249 88527 177249 88522 177249 88522 177250 88527 177250 88528 177250 88522 177251 88528 177251 88525 177251 88525 177252 88528 177252 88529 177252 88525 177253 88529 177253 88530 177253 88517 177254 90391 177254 90221 177254 90221 177255 90391 177255 88539 177255 90221 177256 88539 177256 88531 177256 88532 177257 88538 177257 90293 177257 90293 177258 88538 177258 90349 177258 90293 177259 90349 177259 90297 177259 88533 177260 90227 177260 88546 177260 88533 177261 88546 177261 90259 177261 90259 177262 88546 177262 88534 177262 90259 177263 88534 177263 90260 177263 90260 177264 88534 177264 90262 177264 90262 177265 88534 177265 88535 177265 90262 177266 88535 177266 90265 177266 90265 177267 88535 177267 90266 177267 90266 177268 88535 177268 88536 177268 90266 177269 88536 177269 88537 177269 88537 177270 88536 177270 90268 177270 90268 177271 88536 177271 88538 177271 90268 177272 88538 177272 88532 177272 88531 177273 88539 177273 88540 177273 88540 177274 88539 177274 88541 177274 90405 177275 88545 177275 88541 177275 88541 177276 88545 177276 88542 177276 88541 177277 88542 177277 88540 177277 90199 177278 90198 177278 88543 177278 88543 177279 90198 177279 88544 177279 88543 177280 88544 177280 90405 177280 90405 177281 88544 177281 90196 177281 90405 177282 90196 177282 88545 177282 90199 177283 88543 177283 90200 177283 90200 177284 88543 177284 90398 177284 90200 177285 90398 177285 90224 177285 90224 177286 90398 177286 88547 177286 88547 177287 90398 177287 88546 177287 88547 177288 88546 177288 90227 177288 88506 177289 88133 177289 88162 177289 88162 177290 88133 177290 88161 177290 88131 177291 88129 177291 88548 177291 88549 177292 88183 177292 88561 177292 88182 177293 88199 177293 88184 177293 88550 177294 88481 177294 88139 177294 88551 177295 88140 177295 88552 177295 88553 177296 88476 177296 88565 177296 88563 177297 88142 177297 88475 177297 88554 177298 88555 177298 88568 177298 88567 177299 88146 177299 88147 177299 88471 177300 88474 177300 88151 177300 88556 177301 88150 177301 88470 177301 88467 177302 88501 177302 88557 177302 88557 177303 88501 177303 91683 177303 91909 177304 91907 177304 91682 177304 91682 177305 91907 177305 88497 177305 88176 177306 88177 177306 88558 177306 88175 177307 88156 177307 88559 177307 88571 177308 88149 177308 90191 177308 90191 177309 88149 177309 88560 177309 90191 177310 88560 177310 91895 177310 88549 177311 88561 177311 88562 177311 88562 177312 88561 177312 88135 177312 88562 177313 88135 177313 88478 177313 91877 177314 88137 177314 88477 177314 88477 177315 88137 177315 88140 177315 88477 177316 88140 177316 88551 177316 88550 177317 88139 177317 88480 177317 88480 177318 88139 177318 88138 177318 88480 177319 88138 177319 91925 177319 91670 177320 88143 177320 88479 177320 88479 177321 88143 177321 88142 177321 88479 177322 88142 177322 88563 177322 88553 177323 88565 177323 88564 177323 88564 177324 88565 177324 88141 177324 88564 177325 88141 177325 91669 177325 91875 177326 88145 177326 88566 177326 88566 177327 88145 177327 88146 177327 88566 177328 88146 177328 88567 177328 88554 177329 88568 177329 88469 177329 88469 177330 88568 177330 91679 177330 88469 177331 91679 177331 91680 177331 91671 177332 88148 177332 88468 177332 88468 177333 88148 177333 88150 177333 88468 177334 88150 177334 88556 177334 88471 177335 88151 177335 91885 177335 91885 177336 88151 177336 88152 177336 91885 177337 88152 177337 91888 177337 91894 177338 88569 177338 88570 177338 88570 177339 88569 177339 88149 177339 88570 177340 88149 177340 88571 177340 88572 177341 88573 177341 91892 177341 91892 177342 88573 177342 88159 177342 91892 177343 88159 177343 91891 177343 88574 177344 88473 177344 91672 177344 91672 177345 88473 177345 91884 177345 88575 177346 88160 177346 91890 177346 91890 177347 88160 177347 88158 177347 91889 177348 88576 177348 91893 177348 91893 177349 88576 177349 88573 177349 91893 177350 88573 177350 88572 177350 89391 177351 88577 177351 89506 177351 89506 177352 88577 177352 89885 177352 89506 177353 89885 177353 88578 177353 88578 177354 89885 177354 88579 177354 88578 177355 88579 177355 89503 177355 89503 177356 88579 177356 89886 177356 89503 177357 89886 177357 88580 177357 88580 177358 89886 177358 89863 177358 88580 177359 89863 177359 89484 177359 89484 177360 89863 177360 89869 177360 89484 177361 89869 177361 89482 177361 89482 177362 89869 177362 89842 177362 89730 177363 90140 177363 88581 177363 88581 177364 90140 177364 88582 177364 88581 177365 88582 177365 88583 177365 88583 177366 88582 177366 88584 177366 88583 177367 88584 177367 89696 177367 89696 177368 88584 177368 88586 177368 89696 177369 88586 177369 88585 177369 88585 177370 88586 177370 90092 177370 88585 177371 90092 177371 89702 177371 89702 177372 90092 177372 88587 177372 89702 177373 88587 177373 88588 177373 88588 177374 88587 177374 90074 177374 89385 177375 88589 177375 89650 177375 89650 177376 88589 177376 90070 177376 89650 177377 90070 177377 89656 177377 89656 177378 90070 177378 90071 177378 89656 177379 90071 177379 89662 177379 89662 177380 90071 177380 88590 177380 89662 177381 88590 177381 89661 177381 89661 177382 88590 177382 88592 177382 89661 177383 88592 177383 88591 177383 88591 177384 88592 177384 88594 177384 88591 177385 88594 177385 88593 177385 88593 177386 88594 177386 90116 177386 89356 177387 88596 177387 88595 177387 88595 177388 88596 177388 88597 177388 88595 177389 88597 177389 89438 177389 89438 177390 88597 177390 89826 177390 89438 177391 89826 177391 89465 177391 89465 177392 89826 177392 88598 177392 89465 177393 88598 177393 89463 177393 89463 177394 88598 177394 89853 177394 89463 177395 89853 177395 89462 177395 89462 177396 89853 177396 89858 177396 89462 177397 89858 177397 88599 177397 88599 177398 89858 177398 89857 177398 88608 177399 88601 177399 88600 177399 88600 177400 88601 177400 88715 177400 88602 177401 88614 177401 88711 177401 88615 177402 88603 177402 88616 177402 88721 177403 88604 177403 88605 177403 88605 177404 88604 177404 89491 177404 88605 177405 89491 177405 88606 177405 88606 177406 89491 177406 89538 177406 88606 177407 89538 177407 88719 177407 88719 177408 89538 177408 88600 177408 88719 177409 88600 177409 88716 177409 88716 177410 88600 177410 88715 177410 88711 177411 88607 177411 88602 177411 88602 177412 88607 177412 88713 177412 88602 177413 88713 177413 88608 177413 88608 177414 88713 177414 88609 177414 88608 177415 88609 177415 88601 177415 89545 177416 88610 177416 89542 177416 89542 177417 88610 177417 88611 177417 89542 177418 88611 177418 89541 177418 89541 177419 88611 177419 88613 177419 89541 177420 88613 177420 88612 177420 88612 177421 88613 177421 88708 177421 88612 177422 88708 177422 88614 177422 88614 177423 88708 177423 88710 177423 88614 177424 88710 177424 88711 177424 88620 177425 89548 177425 88701 177425 88701 177426 89548 177426 88615 177426 88701 177427 88615 177427 88700 177427 88700 177428 88615 177428 88616 177428 89560 177429 88617 177429 89573 177429 89573 177430 88617 177430 88618 177430 89573 177431 88618 177431 88624 177431 89547 177432 88619 177432 89545 177432 89545 177433 88619 177433 88705 177433 89545 177434 88705 177434 88610 177434 88620 177435 88702 177435 89548 177435 89548 177436 88702 177436 88621 177436 89548 177437 88621 177437 89547 177437 89547 177438 88621 177438 88622 177438 89547 177439 88622 177439 88619 177439 88618 177440 88623 177440 88624 177440 88624 177441 88623 177441 88694 177441 88624 177442 88694 177442 89551 177442 89551 177443 88694 177443 88695 177443 89551 177444 88695 177444 88603 177444 88603 177445 88695 177445 88697 177445 88603 177446 88697 177446 88616 177446 89660 177447 89658 177447 88625 177447 88625 177448 89658 177448 89666 177448 89593 177449 88626 177449 88692 177449 88692 177450 88626 177450 88627 177450 88692 177451 88627 177451 89652 177451 88618 177452 88617 177452 89593 177452 88667 177453 89477 177453 88720 177453 89457 177454 89456 177454 88667 177454 88667 177455 89456 177455 89455 177455 88667 177456 89455 177456 89477 177456 88663 177457 89451 177457 88665 177457 88640 177458 88687 177458 88628 177458 88628 177459 88687 177459 88688 177459 88628 177460 88688 177460 88629 177460 88629 177461 88688 177461 88631 177461 88629 177462 88631 177462 88630 177462 88630 177463 88631 177463 88632 177463 88630 177464 88632 177464 91704 177464 91704 177465 88632 177465 88633 177465 91704 177466 88633 177466 91703 177466 91703 177467 88633 177467 88634 177467 91703 177468 88634 177468 88635 177468 88635 177469 88634 177469 88636 177469 88635 177470 88636 177470 88637 177470 88637 177471 88636 177471 88625 177471 88637 177472 88625 177472 88638 177472 88638 177473 88625 177473 89666 177473 88638 177474 89666 177474 88639 177474 88628 177475 91707 177475 88640 177475 88640 177476 91707 177476 88641 177476 88640 177477 88641 177477 88684 177477 88684 177478 88641 177478 88642 177478 88642 177479 91708 177479 88684 177479 88684 177480 91708 177480 88643 177480 88684 177481 88643 177481 88683 177481 88683 177482 88643 177482 91710 177482 88683 177483 91710 177483 88644 177483 91710 177484 91712 177484 88644 177484 88644 177485 91712 177485 88646 177485 88644 177486 88646 177486 88645 177486 88645 177487 88646 177487 91713 177487 88645 177488 91713 177488 88648 177488 91713 177489 88647 177489 88648 177489 88648 177490 88647 177490 88649 177490 88648 177491 88649 177491 88650 177491 88650 177492 88649 177492 91718 177492 88650 177493 91718 177493 88651 177493 91718 177494 88652 177494 88651 177494 88651 177495 88652 177495 91717 177495 88651 177496 91717 177496 88653 177496 91717 177497 91721 177497 88653 177497 88653 177498 91721 177498 91722 177498 88653 177499 91722 177499 88654 177499 88654 177500 91722 177500 91723 177500 88654 177501 91723 177501 88655 177501 88655 177502 91723 177502 91725 177502 88655 177503 91725 177503 88656 177503 88656 177504 91725 177504 88657 177504 88656 177505 88657 177505 88676 177505 88676 177506 88657 177506 91727 177506 88676 177507 91727 177507 88675 177507 88675 177508 91727 177508 88658 177508 88675 177509 88658 177509 88674 177509 88674 177510 88658 177510 91729 177510 88674 177511 91729 177511 88671 177511 88671 177512 91729 177512 91731 177512 88671 177513 91731 177513 88669 177513 88669 177514 91731 177514 91734 177514 88669 177515 91734 177515 88659 177515 88659 177516 91734 177516 88660 177516 88659 177517 88660 177517 88668 177517 88668 177518 88660 177518 88661 177518 88668 177519 88661 177519 88662 177519 88662 177520 88661 177520 88663 177520 88662 177521 88663 177521 88664 177521 88664 177522 88663 177522 88665 177522 88664 177523 88665 177523 88666 177523 88666 177524 89457 177524 88664 177524 88664 177525 89457 177525 88667 177525 88664 177526 88667 177526 88662 177526 88662 177527 88667 177527 88718 177527 88662 177528 88718 177528 88668 177528 88668 177529 88718 177529 88717 177529 88668 177530 88717 177530 88659 177530 88659 177531 88717 177531 88670 177531 88659 177532 88670 177532 88669 177532 88669 177533 88670 177533 88672 177533 88669 177534 88672 177534 88671 177534 88671 177535 88672 177535 88673 177535 88671 177536 88673 177536 88674 177536 88674 177537 88673 177537 88714 177537 88674 177538 88714 177538 88675 177538 88675 177539 88714 177539 88712 177539 88675 177540 88712 177540 88676 177540 88676 177541 88712 177541 88677 177541 88676 177542 88677 177542 88656 177542 88656 177543 88677 177543 88678 177543 88656 177544 88678 177544 88655 177544 88655 177545 88678 177545 88709 177545 88655 177546 88709 177546 88654 177546 88654 177547 88709 177547 88679 177547 88654 177548 88679 177548 88653 177548 88653 177549 88679 177549 88707 177549 88653 177550 88707 177550 88651 177550 88651 177551 88707 177551 88680 177551 88651 177552 88680 177552 88650 177552 88650 177553 88680 177553 88706 177553 88650 177554 88706 177554 88648 177554 88648 177555 88706 177555 88681 177555 88648 177556 88681 177556 88645 177556 88645 177557 88681 177557 88704 177557 88645 177558 88704 177558 88644 177558 88644 177559 88704 177559 88703 177559 88644 177560 88703 177560 88683 177560 88683 177561 88703 177561 88682 177561 88683 177562 88682 177562 88684 177562 88684 177563 88682 177563 88685 177563 88684 177564 88685 177564 88640 177564 88640 177565 88685 177565 88686 177565 88640 177566 88686 177566 88687 177566 88687 177567 88686 177567 88699 177567 88687 177568 88699 177568 88688 177568 88688 177569 88699 177569 88689 177569 88688 177570 88689 177570 88631 177570 88631 177571 88689 177571 88690 177571 88631 177572 88690 177572 88632 177572 88632 177573 88690 177573 88698 177573 88632 177574 88698 177574 88633 177574 88633 177575 88698 177575 88696 177575 88633 177576 88696 177576 88634 177576 88634 177577 88696 177577 88691 177577 88634 177578 88691 177578 88636 177578 88636 177579 88691 177579 88693 177579 88636 177580 88693 177580 88625 177580 88625 177581 88693 177581 88692 177581 88625 177582 88692 177582 89660 177582 89660 177583 88692 177583 89652 177583 89593 177584 88692 177584 88618 177584 88618 177585 88692 177585 88693 177585 88618 177586 88693 177586 88623 177586 88623 177587 88693 177587 88691 177587 88623 177588 88691 177588 88694 177588 88694 177589 88691 177589 88696 177589 88694 177590 88696 177590 88695 177590 88695 177591 88696 177591 88698 177591 88695 177592 88698 177592 88697 177592 88697 177593 88698 177593 88690 177593 88697 177594 88690 177594 88616 177594 88616 177595 88690 177595 88689 177595 88616 177596 88689 177596 88700 177596 88700 177597 88689 177597 88699 177597 88700 177598 88699 177598 88701 177598 88701 177599 88699 177599 88686 177599 88701 177600 88686 177600 88620 177600 88620 177601 88686 177601 88685 177601 88620 177602 88685 177602 88702 177602 88702 177603 88685 177603 88682 177603 88702 177604 88682 177604 88621 177604 88621 177605 88682 177605 88703 177605 88621 177606 88703 177606 88622 177606 88622 177607 88703 177607 88704 177607 88622 177608 88704 177608 88619 177608 88619 177609 88704 177609 88681 177609 88619 177610 88681 177610 88705 177610 88705 177611 88681 177611 88706 177611 88705 177612 88706 177612 88610 177612 88610 177613 88706 177613 88680 177613 88610 177614 88680 177614 88611 177614 88611 177615 88680 177615 88707 177615 88611 177616 88707 177616 88613 177616 88613 177617 88707 177617 88679 177617 88613 177618 88679 177618 88708 177618 88708 177619 88679 177619 88709 177619 88708 177620 88709 177620 88710 177620 88710 177621 88709 177621 88678 177621 88710 177622 88678 177622 88711 177622 88711 177623 88678 177623 88677 177623 88711 177624 88677 177624 88607 177624 88607 177625 88677 177625 88712 177625 88607 177626 88712 177626 88713 177626 88713 177627 88712 177627 88714 177627 88713 177628 88714 177628 88609 177628 88609 177629 88714 177629 88673 177629 88609 177630 88673 177630 88601 177630 88601 177631 88673 177631 88672 177631 88601 177632 88672 177632 88715 177632 88715 177633 88672 177633 88670 177633 88715 177634 88670 177634 88716 177634 88716 177635 88670 177635 88717 177635 88716 177636 88717 177636 88719 177636 88719 177637 88717 177637 88718 177637 88719 177638 88718 177638 88606 177638 88606 177639 88718 177639 88667 177639 88606 177640 88667 177640 88605 177640 88605 177641 88667 177641 88720 177641 88605 177642 88720 177642 88721 177642 89953 177643 88729 177643 88786 177643 89953 177644 88786 177644 88722 177644 88746 177645 89981 177645 88723 177645 88723 177646 89981 177646 88724 177646 88723 177647 88724 177647 88782 177647 88782 177648 88724 177648 88725 177648 88782 177649 88725 177649 88783 177649 88783 177650 88725 177650 88722 177650 88783 177651 88722 177651 88785 177651 88785 177652 88722 177652 88786 177652 89926 177653 88804 177653 89925 177653 89925 177654 88804 177654 88803 177654 89925 177655 88803 177655 88726 177655 89919 177656 88806 177656 89926 177656 89926 177657 88806 177657 88727 177657 89926 177658 88727 177658 88804 177658 89921 177659 88728 177659 89919 177659 89919 177660 88728 177660 88808 177660 89919 177661 88808 177661 88806 177661 88729 177662 89953 177662 88789 177662 88789 177663 89953 177663 88732 177663 88789 177664 88732 177664 88731 177664 88740 177665 88741 177665 89921 177665 89921 177666 88741 177666 88730 177666 89921 177667 88730 177667 88728 177667 88731 177668 88732 177668 88791 177668 88791 177669 88732 177669 88742 177669 88791 177670 88742 177670 88733 177670 89907 177671 89908 177671 88735 177671 88735 177672 89908 177672 88734 177672 88735 177673 88734 177673 88737 177673 88734 177674 88736 177674 88737 177674 88737 177675 88736 177675 88738 177675 88737 177676 88738 177676 88740 177676 88740 177677 88738 177677 88739 177677 88740 177678 88739 177678 88741 177678 88744 177679 88745 177679 88742 177679 88742 177680 88745 177680 88793 177680 88742 177681 88793 177681 88733 177681 88803 177682 88801 177682 88726 177682 88726 177683 88801 177683 88743 177683 88726 177684 88743 177684 89923 177684 89923 177685 88743 177685 88799 177685 89923 177686 88799 177686 89922 177686 89922 177687 88799 177687 88796 177687 89922 177688 88796 177688 88744 177688 88744 177689 88796 177689 88795 177689 88744 177690 88795 177690 88745 177690 88775 177691 88230 177691 88229 177691 88258 177692 88748 177692 88841 177692 90031 177693 88746 177693 88723 177693 88843 177694 90040 177694 88842 177694 88842 177695 90040 177695 90031 177695 88841 177696 90058 177696 88747 177696 90058 177697 88841 177697 90059 177697 90059 177698 88841 177698 88748 177698 90059 177699 88748 177699 88749 177699 89843 177700 89852 177700 88845 177700 88845 177701 89852 177701 88847 177701 88750 177702 88751 177702 88811 177702 88811 177703 88751 177703 89843 177703 88734 177704 89908 177704 89879 177704 88258 177705 88841 177705 88752 177705 88752 177706 88841 177706 88839 177706 88752 177707 88839 177707 88838 177707 88753 177708 88255 177708 88838 177708 88838 177709 88255 177709 88754 177709 88838 177710 88754 177710 88752 177710 88838 177711 88836 177711 88753 177711 88753 177712 88836 177712 88756 177712 88753 177713 88756 177713 88755 177713 88755 177714 88756 177714 88834 177714 88755 177715 88834 177715 88252 177715 88252 177716 88834 177716 88757 177716 88252 177717 88757 177717 88758 177717 88758 177718 88757 177718 88833 177718 88758 177719 88833 177719 88761 177719 88761 177720 88833 177720 88832 177720 88763 177721 88759 177721 88831 177721 88831 177722 88759 177722 88249 177722 88831 177723 88249 177723 88832 177723 88832 177724 88249 177724 88760 177724 88832 177725 88760 177725 88761 177725 88827 177726 88245 177726 88828 177726 88828 177727 88245 177727 88762 177727 88828 177728 88762 177728 88763 177728 88763 177729 88762 177729 88764 177729 88763 177730 88764 177730 88759 177730 88765 177731 88242 177731 88766 177731 88766 177732 88242 177732 88767 177732 88766 177733 88767 177733 88768 177733 88768 177734 88767 177734 88769 177734 88768 177735 88769 177735 88827 177735 88827 177736 88769 177736 88770 177736 88827 177737 88770 177737 88245 177737 88771 177738 88227 177738 88824 177738 88824 177739 88227 177739 88226 177739 88824 177740 88226 177740 88772 177740 88772 177741 88226 177741 88225 177741 88772 177742 88225 177742 88765 177742 88765 177743 88225 177743 88773 177743 88765 177744 88773 177744 88242 177744 88771 177745 88824 177745 88229 177745 88229 177746 88824 177746 88774 177746 88229 177747 88774 177747 88775 177747 88230 177748 88775 177748 88776 177748 88776 177749 88775 177749 88822 177749 88776 177750 88822 177750 88223 177750 88223 177751 88822 177751 88820 177751 88223 177752 88820 177752 88221 177752 88221 177753 88820 177753 88819 177753 88221 177754 88819 177754 88777 177754 88777 177755 88819 177755 88817 177755 88777 177756 88817 177756 88218 177756 88218 177757 88817 177757 88814 177757 88218 177758 88814 177758 88217 177758 88217 177759 88814 177759 88813 177759 88217 177760 88813 177760 88214 177760 88214 177761 88813 177761 88778 177761 88214 177762 88778 177762 88780 177762 88780 177763 88778 177763 88779 177763 88780 177764 88779 177764 88781 177764 90031 177765 88723 177765 88842 177765 88842 177766 88723 177766 88782 177766 88842 177767 88782 177767 88840 177767 88840 177768 88782 177768 88783 177768 88840 177769 88783 177769 88784 177769 88784 177770 88783 177770 88785 177770 88784 177771 88785 177771 88837 177771 88837 177772 88785 177772 88786 177772 88837 177773 88786 177773 88835 177773 88835 177774 88786 177774 88729 177774 88835 177775 88729 177775 88787 177775 88787 177776 88729 177776 88789 177776 88787 177777 88789 177777 88788 177777 88788 177778 88789 177778 88731 177778 88788 177779 88731 177779 88790 177779 88790 177780 88731 177780 88791 177780 88790 177781 88791 177781 88792 177781 88792 177782 88791 177782 88733 177782 88792 177783 88733 177783 88830 177783 88830 177784 88733 177784 88793 177784 88830 177785 88793 177785 88794 177785 88794 177786 88793 177786 88745 177786 88794 177787 88745 177787 88829 177787 88829 177788 88745 177788 88795 177788 88829 177789 88795 177789 88797 177789 88797 177790 88795 177790 88796 177790 88797 177791 88796 177791 88798 177791 88798 177792 88796 177792 88799 177792 88798 177793 88799 177793 88800 177793 88800 177794 88799 177794 88743 177794 88800 177795 88743 177795 88826 177795 88826 177796 88743 177796 88801 177796 88826 177797 88801 177797 88825 177797 88825 177798 88801 177798 88803 177798 88825 177799 88803 177799 88802 177799 88802 177800 88803 177800 88804 177800 88802 177801 88804 177801 88805 177801 88805 177802 88804 177802 88727 177802 88805 177803 88727 177803 88823 177803 88823 177804 88727 177804 88806 177804 88823 177805 88806 177805 88807 177805 88807 177806 88806 177806 88808 177806 88807 177807 88808 177807 88821 177807 88821 177808 88808 177808 88728 177808 88821 177809 88728 177809 88809 177809 88809 177810 88728 177810 88730 177810 88809 177811 88730 177811 88818 177811 88818 177812 88730 177812 88741 177812 88818 177813 88741 177813 88816 177813 88816 177814 88741 177814 88739 177814 88816 177815 88739 177815 88815 177815 88815 177816 88739 177816 88738 177816 88815 177817 88738 177817 88812 177817 88812 177818 88738 177818 88736 177818 88812 177819 88736 177819 88810 177819 88810 177820 88736 177820 88734 177820 88810 177821 88734 177821 88811 177821 88811 177822 88734 177822 89879 177822 88811 177823 89879 177823 88750 177823 89843 177824 88845 177824 88811 177824 88811 177825 88845 177825 88779 177825 88811 177826 88779 177826 88810 177826 88810 177827 88779 177827 88778 177827 88810 177828 88778 177828 88812 177828 88812 177829 88778 177829 88813 177829 88812 177830 88813 177830 88815 177830 88815 177831 88813 177831 88814 177831 88815 177832 88814 177832 88816 177832 88816 177833 88814 177833 88817 177833 88816 177834 88817 177834 88818 177834 88818 177835 88817 177835 88819 177835 88818 177836 88819 177836 88809 177836 88809 177837 88819 177837 88820 177837 88809 177838 88820 177838 88821 177838 88821 177839 88820 177839 88822 177839 88821 177840 88822 177840 88807 177840 88807 177841 88822 177841 88775 177841 88807 177842 88775 177842 88823 177842 88823 177843 88775 177843 88774 177843 88823 177844 88774 177844 88805 177844 88805 177845 88774 177845 88824 177845 88805 177846 88824 177846 88802 177846 88802 177847 88824 177847 88772 177847 88802 177848 88772 177848 88825 177848 88825 177849 88772 177849 88765 177849 88825 177850 88765 177850 88826 177850 88826 177851 88765 177851 88766 177851 88826 177852 88766 177852 88800 177852 88800 177853 88766 177853 88768 177853 88800 177854 88768 177854 88798 177854 88798 177855 88768 177855 88827 177855 88798 177856 88827 177856 88797 177856 88797 177857 88827 177857 88828 177857 88797 177858 88828 177858 88829 177858 88829 177859 88828 177859 88763 177859 88829 177860 88763 177860 88794 177860 88794 177861 88763 177861 88831 177861 88794 177862 88831 177862 88830 177862 88830 177863 88831 177863 88832 177863 88830 177864 88832 177864 88792 177864 88792 177865 88832 177865 88833 177865 88792 177866 88833 177866 88790 177866 88790 177867 88833 177867 88757 177867 88790 177868 88757 177868 88788 177868 88788 177869 88757 177869 88834 177869 88788 177870 88834 177870 88787 177870 88787 177871 88834 177871 88756 177871 88787 177872 88756 177872 88835 177872 88835 177873 88756 177873 88836 177873 88835 177874 88836 177874 88837 177874 88837 177875 88836 177875 88838 177875 88837 177876 88838 177876 88784 177876 88784 177877 88838 177877 88839 177877 88784 177878 88839 177878 88840 177878 88840 177879 88839 177879 88841 177879 88840 177880 88841 177880 88842 177880 88842 177881 88841 177881 88747 177881 88842 177882 88747 177882 88843 177882 88781 177883 88779 177883 88844 177883 88844 177884 88779 177884 88845 177884 88844 177885 88845 177885 88846 177885 88846 177886 88845 177886 88847 177886 88846 177887 88847 177887 89847 177887 89697 177888 88934 177888 88933 177888 89680 177889 89668 177889 88875 177889 88904 177890 88848 177890 88942 177890 88942 177891 88848 177891 89497 177891 89499 177892 88849 177892 88902 177892 88902 177893 88849 177893 88903 177893 88947 177894 88946 177894 89557 177894 88931 177895 89678 177895 89680 177895 88850 177896 88851 177896 88931 177896 88931 177897 88851 177897 89709 177897 88931 177898 89709 177898 89678 177898 91806 177899 89698 177899 89697 177899 89697 177900 88933 177900 91806 177900 91806 177901 88933 177901 88932 177901 91806 177902 88932 177902 88852 177902 88852 177903 88932 177903 88853 177903 88852 177904 88853 177904 91808 177904 91808 177905 88853 177905 88929 177905 91808 177906 88929 177906 91799 177906 91799 177907 88929 177907 88854 177907 91799 177908 88854 177908 88855 177908 88855 177909 88854 177909 88856 177909 88855 177910 88856 177910 91795 177910 91795 177911 88856 177911 88924 177911 91795 177912 88924 177912 91793 177912 91793 177913 88924 177913 88857 177913 91793 177914 88857 177914 91791 177914 91791 177915 88857 177915 91792 177915 91792 177916 88857 177916 88858 177916 91792 177917 88858 177917 88859 177917 88859 177918 88858 177918 88860 177918 88860 177919 88858 177919 88861 177919 88860 177920 88861 177920 88862 177920 88862 177921 88861 177921 88865 177921 88862 177922 88865 177922 88866 177922 91786 177923 91790 177923 88867 177923 88867 177924 91790 177924 88863 177924 88867 177925 88863 177925 88865 177925 88865 177926 88863 177926 88864 177926 88865 177927 88864 177927 88866 177927 88867 177928 88868 177928 91786 177928 91786 177929 88868 177929 88869 177929 91786 177930 88869 177930 91784 177930 91784 177931 88869 177931 88870 177931 91784 177932 88870 177932 91783 177932 91783 177933 88870 177933 91781 177933 91781 177934 88870 177934 91772 177934 91772 177935 88870 177935 88919 177935 91772 177936 88919 177936 91771 177936 91771 177937 88919 177937 88917 177937 91771 177938 88917 177938 91769 177938 91769 177939 88917 177939 88871 177939 91769 177940 88871 177940 91767 177940 91767 177941 88871 177941 88872 177941 91767 177942 88872 177942 88873 177942 88873 177943 88872 177943 91763 177943 91763 177944 88872 177944 88874 177944 91763 177945 88874 177945 91764 177945 89680 177946 88875 177946 88931 177946 88931 177947 88875 177947 88944 177947 88931 177948 88944 177948 88876 177948 88876 177949 88944 177949 88877 177949 88876 177950 88877 177950 88930 177950 88930 177951 88877 177951 88949 177951 88930 177952 88949 177952 88928 177952 88928 177953 88949 177953 88878 177953 88928 177954 88878 177954 88927 177954 88927 177955 88878 177955 88951 177955 88927 177956 88951 177956 88926 177956 88926 177957 88951 177957 88879 177957 88926 177958 88879 177958 88925 177958 88925 177959 88879 177959 88880 177959 88925 177960 88880 177960 88881 177960 88881 177961 88880 177961 88882 177961 88881 177962 88882 177962 88923 177962 88923 177963 88882 177963 88883 177963 88923 177964 88883 177964 88922 177964 88922 177965 88883 177965 88961 177965 88922 177966 88961 177966 88921 177966 88921 177967 88961 177967 88884 177967 88921 177968 88884 177968 88920 177968 88920 177969 88884 177969 88963 177969 88920 177970 88963 177970 88885 177970 88885 177971 88963 177971 88887 177971 88885 177972 88887 177972 88886 177972 88886 177973 88887 177973 88888 177973 88886 177974 88888 177974 88889 177974 88889 177975 88888 177975 88962 177975 88889 177976 88962 177976 88918 177976 88918 177977 88962 177977 88890 177977 88918 177978 88890 177978 88891 177978 88891 177979 88890 177979 88955 177979 88891 177980 88955 177980 88916 177980 88916 177981 88955 177981 88953 177981 88916 177982 88953 177982 88915 177982 88915 177983 88953 177983 88892 177983 88915 177984 88892 177984 88914 177984 88914 177985 88892 177985 88956 177985 88914 177986 88956 177986 88913 177986 88913 177987 88956 177987 88893 177987 88913 177988 88893 177988 88912 177988 88912 177989 88893 177989 88894 177989 88912 177990 88894 177990 88895 177990 88895 177991 88894 177991 88958 177991 88895 177992 88958 177992 88897 177992 88897 177993 88958 177993 88896 177993 88897 177994 88896 177994 88898 177994 88898 177995 88896 177995 88899 177995 88898 177996 88899 177996 88908 177996 88908 177997 88899 177997 88948 177997 88908 177998 88948 177998 88906 177998 88906 177999 88948 177999 88900 177999 88906 178000 88900 178000 88901 178000 88901 178001 88900 178001 88947 178001 88901 178002 88947 178002 88902 178002 88902 178003 88947 178003 89557 178003 88902 178004 89557 178004 89499 178004 88903 178005 88904 178005 88902 178005 88902 178006 88904 178006 88942 178006 88902 178007 88942 178007 88901 178007 88901 178008 88942 178008 88905 178008 88901 178009 88905 178009 88906 178009 88906 178010 88905 178010 88907 178010 88906 178011 88907 178011 88908 178011 88908 178012 88907 178012 88909 178012 88908 178013 88909 178013 88898 178013 88898 178014 88909 178014 88910 178014 88898 178015 88910 178015 88897 178015 88897 178016 88910 178016 88911 178016 88897 178017 88911 178017 88895 178017 88895 178018 88911 178018 88940 178018 88895 178019 88940 178019 88912 178019 88912 178020 88940 178020 88938 178020 88912 178021 88938 178021 88913 178021 88913 178022 88938 178022 88936 178022 88913 178023 88936 178023 88914 178023 88914 178024 88936 178024 88874 178024 88914 178025 88874 178025 88915 178025 88915 178026 88874 178026 88872 178026 88915 178027 88872 178027 88916 178027 88916 178028 88872 178028 88871 178028 88916 178029 88871 178029 88891 178029 88891 178030 88871 178030 88917 178030 88891 178031 88917 178031 88918 178031 88918 178032 88917 178032 88919 178032 88918 178033 88919 178033 88889 178033 88889 178034 88919 178034 88870 178034 88889 178035 88870 178035 88886 178035 88886 178036 88870 178036 88869 178036 88886 178037 88869 178037 88885 178037 88885 178038 88869 178038 88868 178038 88885 178039 88868 178039 88920 178039 88920 178040 88868 178040 88867 178040 88920 178041 88867 178041 88921 178041 88921 178042 88867 178042 88865 178042 88921 178043 88865 178043 88922 178043 88922 178044 88865 178044 88861 178044 88922 178045 88861 178045 88923 178045 88923 178046 88861 178046 88858 178046 88923 178047 88858 178047 88881 178047 88881 178048 88858 178048 88857 178048 88881 178049 88857 178049 88925 178049 88925 178050 88857 178050 88924 178050 88925 178051 88924 178051 88926 178051 88926 178052 88924 178052 88856 178052 88926 178053 88856 178053 88927 178053 88927 178054 88856 178054 88854 178054 88927 178055 88854 178055 88928 178055 88928 178056 88854 178056 88929 178056 88928 178057 88929 178057 88930 178057 88930 178058 88929 178058 88853 178058 88930 178059 88853 178059 88876 178059 88876 178060 88853 178060 88932 178060 88876 178061 88932 178061 88931 178061 88931 178062 88932 178062 88933 178062 88931 178063 88933 178063 88850 178063 88850 178064 88933 178064 88934 178064 91764 178065 88874 178065 88935 178065 88935 178066 88874 178066 88936 178066 88935 178067 88936 178067 88937 178067 88937 178068 88936 178068 88938 178068 88937 178069 88938 178069 88939 178069 88939 178070 88938 178070 88940 178070 88939 178071 88940 178071 91761 178071 91761 178072 88940 178072 88911 178072 91761 178073 88911 178073 91760 178073 91760 178074 88911 178074 88910 178074 91760 178075 88910 178075 91759 178075 91759 178076 88910 178076 88909 178076 91759 178077 88909 178077 91750 178077 91750 178078 88909 178078 88907 178078 91750 178079 88907 178079 88941 178079 88941 178080 88907 178080 88905 178080 88941 178081 88905 178081 91756 178081 91756 178082 88905 178082 88942 178082 91756 178083 88942 178083 91755 178083 91755 178084 88942 178084 89497 178084 91755 178085 89497 178085 91749 178085 89668 178086 89670 178086 88875 178086 88875 178087 89670 178087 88943 178087 88875 178088 88943 178088 88944 178088 88944 178089 88943 178089 89646 178089 88944 178090 89646 178090 88877 178090 88877 178091 89646 178091 88950 178091 88877 178092 88950 178092 88949 178092 88945 178093 88946 178093 89584 178093 89584 178094 88946 178094 88947 178094 89584 178095 88947 178095 89598 178095 88947 178096 88900 178096 89598 178096 89598 178097 88900 178097 88948 178097 89598 178098 88948 178098 89601 178098 88949 178099 88950 178099 88878 178099 88878 178100 88950 178100 89640 178100 88878 178101 89640 178101 88951 178101 88951 178102 89640 178102 88879 178102 88879 178103 89640 178103 88952 178103 88879 178104 88952 178104 88880 178104 88880 178105 88952 178105 88882 178105 88882 178106 88952 178106 88960 178106 88882 178107 88960 178107 88883 178107 89608 178108 88953 178108 88954 178108 88954 178109 88953 178109 88955 178109 88954 178110 88955 178110 89606 178110 88957 178111 88956 178111 89608 178111 89608 178112 88956 178112 88892 178112 89608 178113 88892 178113 88953 178113 89599 178114 88894 178114 88957 178114 88957 178115 88894 178115 88893 178115 88957 178116 88893 178116 88956 178116 88948 178117 88899 178117 89601 178117 89601 178118 88899 178118 88896 178118 89601 178119 88896 178119 89599 178119 89599 178120 88896 178120 88958 178120 89599 178121 88958 178121 88894 178121 88959 178122 88884 178122 88960 178122 88960 178123 88884 178123 88961 178123 88960 178124 88961 178124 88883 178124 88955 178125 88890 178125 89606 178125 89606 178126 88890 178126 88962 178126 89606 178127 88962 178127 89605 178127 89605 178128 88962 178128 88888 178128 89605 178129 88888 178129 89604 178129 89604 178130 88888 178130 88887 178130 89604 178131 88887 178131 88959 178131 88959 178132 88887 178132 88963 178132 88959 178133 88963 178133 88884 178133 90180 178134 88964 178134 90175 178134 90175 178135 88964 178135 88965 178135 90175 178136 88965 178136 90171 178136 90171 178137 88965 178137 89729 178137 90096 178138 90118 178138 88265 178138 88967 178139 88966 178139 89055 178139 89000 178140 89881 178140 88967 178140 88967 178141 89881 178141 89880 178141 88967 178142 89880 178142 88966 178142 88999 178143 89890 178143 89000 178143 89890 178144 88999 178144 88968 178144 88968 178145 88999 178145 88326 178145 88968 178146 88326 178146 89867 178146 88969 178147 88970 178147 90096 178147 88972 178148 90088 178148 88971 178148 90080 178149 90086 178149 88972 178149 88972 178150 90086 178150 90089 178150 88972 178151 90089 178151 90088 178151 89056 178152 90041 178152 90080 178152 90096 178153 88265 178153 88969 178153 88969 178154 88265 178154 88973 178154 88969 178155 88973 178155 89022 178155 88973 178156 88269 178156 89022 178156 89022 178157 88269 178157 88974 178157 89022 178158 88974 178158 89021 178158 89021 178159 88974 178159 88272 178159 89021 178160 88272 178160 88975 178160 88272 178161 88274 178161 88975 178161 88975 178162 88274 178162 88976 178162 88975 178163 88976 178163 88977 178163 88977 178164 88976 178164 88276 178164 88977 178165 88276 178165 89019 178165 89019 178166 88276 178166 88978 178166 89019 178167 88978 178167 89018 178167 89018 178168 88978 178168 88278 178168 89018 178169 88278 178169 88979 178169 88979 178170 88278 178170 88980 178170 88979 178171 88980 178171 88981 178171 88981 178172 88980 178172 88280 178172 88981 178173 88280 178173 88982 178173 88280 178174 88283 178174 88982 178174 88982 178175 88283 178175 88284 178175 88982 178176 88284 178176 89017 178176 89017 178177 88284 178177 88285 178177 89017 178178 88285 178178 89014 178178 89014 178179 88285 178179 88288 178179 89014 178180 88288 178180 88984 178180 88291 178181 88983 178181 88984 178181 88984 178182 88983 178182 89013 178182 88984 178183 89013 178183 89014 178183 88291 178184 88292 178184 88983 178184 88983 178185 88292 178185 88293 178185 88983 178186 88293 178186 89012 178186 89012 178187 88293 178187 88985 178187 89012 178188 88985 178188 89011 178188 89011 178189 88985 178189 88986 178189 89011 178190 88986 178190 88987 178190 88986 178191 88304 178191 88987 178191 88987 178192 88304 178192 88988 178192 88987 178193 88988 178193 88989 178193 88989 178194 88988 178194 88990 178194 88989 178195 88990 178195 88992 178195 88990 178196 88991 178196 88992 178196 88992 178197 88991 178197 88308 178197 88992 178198 88308 178198 88993 178198 88993 178199 88308 178199 88309 178199 88993 178200 88309 178200 89008 178200 89008 178201 88309 178201 88994 178201 89008 178202 88994 178202 89006 178202 89006 178203 88994 178203 88311 178203 89006 178204 88311 178204 88995 178204 88995 178205 88311 178205 88313 178205 88995 178206 88313 178206 89004 178206 89004 178207 88313 178207 88315 178207 89004 178208 88315 178208 88996 178208 88996 178209 88315 178209 88316 178209 88996 178210 88316 178210 88997 178210 88997 178211 88316 178211 88323 178211 88997 178212 88323 178212 89002 178212 89002 178213 88323 178213 88998 178213 89002 178214 88998 178214 89001 178214 89001 178215 88998 178215 88999 178215 88999 178216 88998 178216 88324 178216 88999 178217 88324 178217 88326 178217 89000 178218 88967 178218 88999 178218 88999 178219 88967 178219 89052 178219 88999 178220 89052 178220 89001 178220 89001 178221 89052 178221 89003 178221 89001 178222 89003 178222 89002 178222 89002 178223 89003 178223 89050 178223 89002 178224 89050 178224 88997 178224 88997 178225 89050 178225 89049 178225 88997 178226 89049 178226 88996 178226 88996 178227 89049 178227 89048 178227 88996 178228 89048 178228 89004 178228 89004 178229 89048 178229 89047 178229 89004 178230 89047 178230 88995 178230 88995 178231 89047 178231 89005 178231 88995 178232 89005 178232 89006 178232 89006 178233 89005 178233 89007 178233 89006 178234 89007 178234 89008 178234 89008 178235 89007 178235 89046 178235 89008 178236 89046 178236 88993 178236 88993 178237 89046 178237 89009 178237 88993 178238 89009 178238 88992 178238 88992 178239 89009 178239 89043 178239 88992 178240 89043 178240 88989 178240 88989 178241 89043 178241 89010 178241 88989 178242 89010 178242 88987 178242 88987 178243 89010 178243 89041 178243 88987 178244 89041 178244 89011 178244 89011 178245 89041 178245 89040 178245 89011 178246 89040 178246 89012 178246 89012 178247 89040 178247 89038 178247 89012 178248 89038 178248 88983 178248 88983 178249 89038 178249 89036 178249 88983 178250 89036 178250 89013 178250 89013 178251 89036 178251 89015 178251 89013 178252 89015 178252 89014 178252 89014 178253 89015 178253 89016 178253 89014 178254 89016 178254 89017 178254 89017 178255 89016 178255 89033 178255 89017 178256 89033 178256 88982 178256 88982 178257 89033 178257 89032 178257 88982 178258 89032 178258 88981 178258 88981 178259 89032 178259 89031 178259 88981 178260 89031 178260 88979 178260 88979 178261 89031 178261 89030 178261 88979 178262 89030 178262 89018 178262 89018 178263 89030 178263 89028 178263 89018 178264 89028 178264 89019 178264 89019 178265 89028 178265 89026 178265 89019 178266 89026 178266 88977 178266 88977 178267 89026 178267 89025 178267 88977 178268 89025 178268 88975 178268 88975 178269 89025 178269 89020 178269 88975 178270 89020 178270 89021 178270 89021 178271 89020 178271 89023 178271 89021 178272 89023 178272 89022 178272 89022 178273 89023 178273 88972 178273 89022 178274 88972 178274 88969 178274 88969 178275 88972 178275 88971 178275 88969 178276 88971 178276 88970 178276 90080 178277 88972 178277 89056 178277 89056 178278 88972 178278 89023 178278 89056 178279 89023 178279 89058 178279 89058 178280 89023 178280 89020 178280 89058 178281 89020 178281 89060 178281 89060 178282 89020 178282 89025 178282 89060 178283 89025 178283 89024 178283 89024 178284 89025 178284 89026 178284 89024 178285 89026 178285 89061 178285 89061 178286 89026 178286 89028 178286 89061 178287 89028 178287 89027 178287 89027 178288 89028 178288 89030 178288 89027 178289 89030 178289 89029 178289 89029 178290 89030 178290 89031 178290 89029 178291 89031 178291 89069 178291 89069 178292 89031 178292 89032 178292 89069 178293 89032 178293 89034 178293 89034 178294 89032 178294 89033 178294 89034 178295 89033 178295 89035 178295 89035 178296 89033 178296 89016 178296 89035 178297 89016 178297 89068 178297 89068 178298 89016 178298 89015 178298 89068 178299 89015 178299 89067 178299 89067 178300 89015 178300 89036 178300 89067 178301 89036 178301 89037 178301 89037 178302 89036 178302 89038 178302 89037 178303 89038 178303 89075 178303 89075 178304 89038 178304 89040 178304 89075 178305 89040 178305 89039 178305 89039 178306 89040 178306 89041 178306 89039 178307 89041 178307 89077 178307 89077 178308 89041 178308 89010 178308 89077 178309 89010 178309 89042 178309 89042 178310 89010 178310 89043 178310 89042 178311 89043 178311 89044 178311 89044 178312 89043 178312 89009 178312 89044 178313 89009 178313 89045 178313 89045 178314 89009 178314 89046 178314 89045 178315 89046 178315 89063 178315 89063 178316 89046 178316 89007 178316 89063 178317 89007 178317 89064 178317 89064 178318 89007 178318 89005 178318 89064 178319 89005 178319 89065 178319 89065 178320 89005 178320 89047 178320 89065 178321 89047 178321 89066 178321 89066 178322 89047 178322 89048 178322 89066 178323 89048 178323 89062 178323 89062 178324 89048 178324 89049 178324 89062 178325 89049 178325 89074 178325 89074 178326 89049 178326 89050 178326 89074 178327 89050 178327 89073 178327 89073 178328 89050 178328 89003 178328 89073 178329 89003 178329 89051 178329 89051 178330 89003 178330 89052 178330 89051 178331 89052 178331 89053 178331 89053 178332 89052 178332 88967 178332 89053 178333 88967 178333 89054 178333 89054 178334 88967 178334 89055 178334 89054 178335 89055 178335 89965 178335 90047 178336 90041 178336 90048 178336 90048 178337 90041 178337 89056 178337 90048 178338 89056 178338 89057 178338 90026 178339 89067 178339 89037 178339 90028 178340 90029 178340 89027 178340 90019 178341 90021 178341 89063 178341 90026 178342 89037 178342 90025 178342 89056 178343 89058 178343 89057 178343 89057 178344 89058 178344 89060 178344 89057 178345 89060 178345 89059 178345 89059 178346 89060 178346 89024 178346 89059 178347 89024 178347 90029 178347 90029 178348 89024 178348 89061 178348 90029 178349 89061 178349 89027 178349 90018 178350 89062 178350 89072 178350 89072 178351 89062 178351 89074 178351 89063 178352 89064 178352 90019 178352 90019 178353 89064 178353 89065 178353 90019 178354 89065 178354 90018 178354 90018 178355 89065 178355 89066 178355 90018 178356 89066 178356 89062 178356 89067 178357 90026 178357 89068 178357 89068 178358 90026 178358 89070 178358 89068 178359 89070 178359 89035 178359 89027 178360 89029 178360 90028 178360 90028 178361 89029 178361 89069 178361 90028 178362 89069 178362 89070 178362 89070 178363 89069 178363 89034 178363 89070 178364 89034 178364 89035 178364 89965 178365 89967 178365 89054 178365 89054 178366 89967 178366 89963 178366 89054 178367 89963 178367 89053 178367 89053 178368 89963 178368 89071 178368 89053 178369 89071 178369 89051 178369 89051 178370 89071 178370 89072 178370 89051 178371 89072 178371 89073 178371 89073 178372 89072 178372 89074 178372 89037 178373 89075 178373 90025 178373 90025 178374 89075 178374 89039 178374 90025 178375 89039 178375 89076 178375 89076 178376 89039 178376 89077 178376 89076 178377 89077 178377 90022 178377 90022 178378 89077 178378 89042 178378 90022 178379 89042 178379 89078 178379 89078 178380 89042 178380 89044 178380 89078 178381 89044 178381 90021 178381 90021 178382 89044 178382 89045 178382 90021 178383 89045 178383 89063 178383 89467 178384 89835 178384 89079 178384 89079 178385 89835 178385 89080 178385 89079 178386 89080 178386 89444 178386 89444 178387 89080 178387 89790 178387 89353 178388 89400 178388 89081 178388 89081 178389 89400 178389 89082 178389 89081 178390 89082 178390 89801 178390 89801 178391 89082 178391 89435 178391 89083 178392 89364 178392 89747 178392 89747 178393 89364 178393 90161 178393 89747 178394 90161 178394 89370 178394 89370 178395 90161 178395 89084 178395 89409 178396 89781 178396 89085 178396 89085 178397 89781 178397 89086 178397 89085 178398 89086 178398 89359 178398 89359 178399 89086 178399 89360 178399 89374 178400 90128 178400 89714 178400 89714 178401 90128 178401 89087 178401 89714 178402 89087 178402 89710 178402 89710 178403 89087 178403 89371 178403 89088 178404 88144 178404 91874 178404 91874 178405 88144 178405 91673 178405 89089 178406 88144 178406 89090 178406 89090 178407 88144 178407 89088 178407 89096 178408 91901 178408 91458 178408 89091 178409 91716 178409 89092 178409 89092 178410 91716 178410 89093 178410 89095 178411 91506 178411 91715 178411 91715 178412 91506 178412 91507 178412 91715 178413 91507 178413 89093 178413 89093 178414 91507 178414 89094 178414 89093 178415 89094 178415 89092 178415 89099 178416 89101 178416 89095 178416 89095 178417 89101 178417 91478 178417 89095 178418 91478 178418 91506 178418 91458 178419 89097 178419 89096 178419 89096 178420 89097 178420 89098 178420 89096 178421 89098 178421 91809 178421 91809 178422 89098 178422 89100 178422 91809 178423 89100 178423 89099 178423 89099 178424 89100 178424 91477 178424 89099 178425 91477 178425 89101 178425 91597 178426 89102 178426 91566 178426 91566 178427 89102 178427 91716 178427 91566 178428 91716 178428 89091 178428 89110 178429 89102 178429 91597 178429 89103 178430 89104 178430 89107 178430 89107 178431 89104 178431 91720 178431 89108 178432 89105 178432 89106 178432 89106 178433 89105 178433 91618 178433 89106 178434 91618 178434 91720 178434 91720 178435 91618 178435 91628 178435 91720 178436 91628 178436 89107 178436 91719 178437 91621 178437 89108 178437 89108 178438 91621 178438 91620 178438 89108 178439 91620 178439 89105 178439 91597 178440 89109 178440 89110 178440 89110 178441 89109 178441 91624 178441 89110 178442 91624 178442 89111 178442 89111 178443 91624 178443 89112 178443 89111 178444 89112 178444 91719 178444 91719 178445 89112 178445 89113 178445 91719 178446 89113 178446 91621 178446 89104 178447 89103 178447 89114 178447 89114 178448 89103 178448 89115 178448 89114 178449 89115 178449 91724 178449 91724 178450 89115 178450 91591 178450 91724 178451 91591 178451 91726 178451 91726 178452 91591 178452 89116 178452 91726 178453 89116 178453 89117 178453 89117 178454 89116 178454 89118 178454 89117 178455 89118 178455 91728 178455 91728 178456 89118 178456 91595 178456 91728 178457 91595 178457 91730 178457 91730 178458 91595 178458 91512 178458 91458 178459 91901 178459 89119 178459 89119 178460 91901 178460 91812 178460 89119 178461 91812 178461 91457 178461 91457 178462 91812 178462 91811 178462 91457 178463 91811 178463 91454 178463 91454 178464 91811 178464 89120 178464 91454 178465 89120 178465 89122 178465 89122 178466 89120 178466 89121 178466 89122 178467 89121 178467 89123 178467 89123 178468 89121 178468 91813 178468 89123 178469 91813 178469 89124 178469 89124 178470 91813 178470 89125 178470 89124 178471 89125 178471 91817 178471 89126 178472 89127 178472 89136 178472 91733 178473 91551 178473 89128 178473 89128 178474 91551 178474 89126 178474 89128 178475 89126 178475 91735 178475 91735 178476 89126 178476 89136 178476 91730 178477 91512 178477 89129 178477 89129 178478 91512 178478 91521 178478 89129 178479 91521 178479 89130 178479 89130 178480 91521 178480 91525 178480 89130 178481 91525 178481 91732 178481 91732 178482 91525 178482 91531 178482 91732 178483 91531 178483 89131 178483 89131 178484 91531 178484 89133 178484 89131 178485 89133 178485 89132 178485 89132 178486 89133 178486 91511 178486 89132 178487 91511 178487 91733 178487 91733 178488 91511 178488 89134 178488 91733 178489 89134 178489 91551 178489 91393 178490 89135 178490 89137 178490 89137 178491 89135 178491 89136 178491 89137 178492 89136 178492 89127 178492 89124 178493 91817 178493 89138 178493 89138 178494 91817 178494 89140 178494 89138 178495 89140 178495 89139 178495 89139 178496 89140 178496 91815 178496 89139 178497 91815 178497 91430 178497 91430 178498 91815 178498 89141 178498 91430 178499 89141 178499 91427 178499 89135 178500 91393 178500 91736 178500 91736 178501 91393 178501 89145 178501 89141 178502 89142 178502 91427 178502 91427 178503 89142 178503 89143 178503 91427 178504 89143 178504 91426 178504 91426 178505 89143 178505 89144 178505 91426 178506 89144 178506 89145 178506 89145 178507 89144 178507 89146 178507 89145 178508 89146 178508 91736 178508 91966 178509 89179 178509 89147 178509 89147 178510 89179 178510 89148 178510 89147 178511 89148 178511 91822 178511 91822 178512 89148 178512 91113 178512 91822 178513 91113 178513 91821 178513 91821 178514 91113 178514 89149 178514 91821 178515 89149 178515 89150 178515 89150 178516 89149 178516 91115 178516 89150 178517 91115 178517 91819 178517 91819 178518 91115 178518 89151 178518 91819 178519 89151 178519 91818 178519 91818 178520 89151 178520 91041 178520 89158 178521 91818 178521 91041 178521 90987 178522 91779 178522 91074 178522 91074 178523 91779 178523 89152 178523 89156 178524 89153 178524 89152 178524 89152 178525 89153 178525 89154 178525 89152 178526 89154 178526 91074 178526 89161 178527 89155 178527 89156 178527 89156 178528 89155 178528 91070 178528 89156 178529 91070 178529 89153 178529 91041 178530 89157 178530 89158 178530 89158 178531 89157 178531 91043 178531 89158 178532 91043 178532 89160 178532 89160 178533 91043 178533 89159 178533 89160 178534 89159 178534 89161 178534 89161 178535 89159 178535 91068 178535 89161 178536 91068 178536 89155 178536 89163 178537 89162 178537 90986 178537 90986 178538 89162 178538 91779 178538 90986 178539 91779 178539 90987 178539 91780 178540 89162 178540 89163 178540 89164 178541 89178 178541 90957 178541 90957 178542 89178 178542 89165 178542 89167 178543 90943 178543 91785 178543 91785 178544 90943 178544 89166 178544 91785 178545 89166 178545 89165 178545 89165 178546 89166 178546 90954 178546 89165 178547 90954 178547 90957 178547 91782 178548 90946 178548 89167 178548 89167 178549 90946 178549 90944 178549 89167 178550 90944 178550 90943 178550 89163 178551 90926 178551 91780 178551 91780 178552 90926 178552 89169 178552 91780 178553 89169 178553 89168 178553 89168 178554 89169 178554 89170 178554 89168 178555 89170 178555 91782 178555 91782 178556 89170 178556 89171 178556 91782 178557 89171 178557 90946 178557 89172 178558 91794 178558 89173 178558 89173 178559 91794 178559 89174 178559 89173 178560 89174 178560 90982 178560 90982 178561 89174 178561 89175 178561 90982 178562 89175 178562 90980 178562 90980 178563 89175 178563 89176 178563 90980 178564 89176 178564 89177 178564 89178 178565 89164 178565 91789 178565 91789 178566 89164 178566 90979 178566 91789 178567 90979 178567 91788 178567 91788 178568 90979 178568 89177 178568 91788 178569 89177 178569 91787 178569 91787 178570 89177 178570 89176 178570 91966 178571 89180 178571 89179 178571 89179 178572 89180 178572 91139 178572 91802 178573 89194 178573 91803 178573 91803 178574 89194 178574 89183 178574 91139 178575 89180 178575 91138 178575 91138 178576 89180 178576 91964 178576 91138 178577 91964 178577 91137 178577 91137 178578 91964 178578 89181 178578 91137 178579 89181 178579 89182 178579 89182 178580 89181 178580 91804 178580 89182 178581 91804 178581 91134 178581 91134 178582 91804 178582 91805 178582 91134 178583 91805 178583 89183 178583 89183 178584 91805 178584 89184 178584 89183 178585 89184 178585 91803 178585 91028 178586 89196 178586 91801 178586 89185 178587 89193 178587 89186 178587 89186 178588 89193 178588 91028 178588 89186 178589 91028 178589 91798 178589 91798 178590 91028 178590 91801 178590 91794 178591 89172 178591 91796 178591 91796 178592 89172 178592 89187 178592 91796 178593 89187 178593 89188 178593 89188 178594 89187 178594 89189 178594 89188 178595 89189 178595 91797 178595 91797 178596 89189 178596 91009 178596 91797 178597 91009 178597 89190 178597 89190 178598 91009 178598 89191 178598 89190 178599 89191 178599 91800 178599 91800 178600 89191 178600 89192 178600 91800 178601 89192 178601 89185 178601 89185 178602 89192 178602 90992 178602 89185 178603 90992 178603 89193 178603 89194 178604 91802 178604 89195 178604 89195 178605 91802 178605 91801 178605 89195 178606 91801 178606 89196 178606 91347 178607 91700 178607 91311 178607 91311 178608 91700 178608 89197 178608 91311 178609 89197 178609 89198 178609 89198 178610 89197 178610 89200 178610 89200 178611 89197 178611 89199 178611 89200 178612 89199 178612 89201 178612 89201 178613 89199 178613 91824 178613 89201 178614 91824 178614 89202 178614 89202 178615 91824 178615 89203 178615 89202 178616 89203 178616 89204 178616 89204 178617 89203 178617 89205 178617 89204 178618 89205 178618 89206 178618 89206 178619 89205 178619 91253 178619 89205 178620 89207 178620 91253 178620 91253 178621 89207 178621 91823 178621 91253 178622 91823 178622 89208 178622 89208 178623 91823 178623 91826 178623 89254 178624 91216 178624 91825 178624 91825 178625 91216 178625 89209 178625 91825 178626 89209 178626 91826 178626 91826 178627 89209 178627 89210 178627 91826 178628 89210 178628 89208 178628 89220 178629 89211 178629 91379 178629 91379 178630 89211 178630 89212 178630 91379 178631 89212 178631 91370 178631 91370 178632 89212 178632 89213 178632 91370 178633 89213 178633 89214 178633 89214 178634 89213 178634 89215 178634 89214 178635 89215 178635 89216 178635 91700 178636 91347 178636 89217 178636 89217 178637 91347 178637 91365 178637 89215 178638 91702 178638 89216 178638 89216 178639 91702 178639 89218 178639 89216 178640 89218 178640 91367 178640 91367 178641 89218 178641 91701 178641 91367 178642 91701 178642 91365 178642 91365 178643 91701 178643 91696 178643 91365 178644 91696 178644 89217 178644 89211 178645 89220 178645 89219 178645 89219 178646 89220 178646 91320 178646 89219 178647 91320 178647 89221 178647 89221 178648 91320 178648 91340 178648 91345 178649 91711 178649 91344 178649 91344 178650 91711 178650 89222 178650 91344 178651 89222 178651 91342 178651 91342 178652 89222 178652 91709 178652 91342 178653 91709 178653 91341 178653 91341 178654 91709 178654 91705 178654 91341 178655 91705 178655 91340 178655 91340 178656 91705 178656 91706 178656 91340 178657 91706 178657 89221 178657 89223 178658 91711 178658 91345 178658 89224 178659 89225 178659 89226 178659 89226 178660 89225 178660 89227 178660 89228 178661 89229 178661 89227 178661 89227 178662 89229 178662 91303 178662 89227 178663 91303 178663 89226 178663 89233 178664 89234 178664 89228 178664 89228 178665 89234 178665 91300 178665 89228 178666 91300 178666 89229 178666 91345 178667 89230 178667 89223 178667 89223 178668 89230 178668 91296 178668 89223 178669 91296 178669 89232 178669 89232 178670 91296 178670 89231 178670 89232 178671 89231 178671 89233 178671 89233 178672 89231 178672 91298 178672 89233 178673 91298 178673 89234 178673 91223 178674 89236 178674 89235 178674 89235 178675 89236 178675 89225 178675 89235 178676 89225 178676 89224 178676 89237 178677 89236 178677 91223 178677 91189 178678 91832 178678 89241 178678 89241 178679 91832 178679 89238 178679 91714 178680 89239 178680 89238 178680 89238 178681 89239 178681 89240 178681 89238 178682 89240 178682 89241 178682 89247 178683 89242 178683 91714 178683 91714 178684 89242 178684 89243 178684 91714 178685 89243 178685 89239 178685 91223 178686 91159 178686 89237 178686 89237 178687 91159 178687 89245 178687 89237 178688 89245 178688 89244 178688 89244 178689 89245 178689 89246 178689 89244 178690 89246 178690 89247 178690 89247 178691 89246 178691 89248 178691 89247 178692 89248 178692 89242 178692 91832 178693 91189 178693 89249 178693 89249 178694 91189 178694 91211 178694 89249 178695 91211 178695 89250 178695 89250 178696 91211 178696 91213 178696 89250 178697 91213 178697 91829 178697 91829 178698 91213 178698 91214 178698 91829 178699 91214 178699 89251 178699 89251 178700 91214 178700 89252 178700 89251 178701 89252 178701 89253 178701 89253 178702 89252 178702 91215 178702 89253 178703 91215 178703 89254 178703 89254 178704 91215 178704 91216 178704 90747 178705 89255 178705 89256 178705 89256 178706 89255 178706 89257 178706 89256 178707 89257 178707 90849 178707 90849 178708 89257 178708 89259 178708 89259 178709 89257 178709 89258 178709 89259 178710 89258 178710 90847 178710 90847 178711 89258 178711 91754 178711 90847 178712 91754 178712 89260 178712 89260 178713 91754 178713 91752 178713 89260 178714 91752 178714 89261 178714 89261 178715 91752 178715 91751 178715 89261 178716 91751 178716 89262 178716 89262 178717 91751 178717 90829 178717 91751 178718 91834 178718 90829 178718 90829 178719 91834 178719 89263 178719 90829 178720 89263 178720 90813 178720 90813 178721 89263 178721 91833 178721 91836 178722 90799 178722 91835 178722 91835 178723 90799 178723 90798 178723 91835 178724 90798 178724 91833 178724 91833 178725 90798 178725 90814 178725 91833 178726 90814 178726 90813 178726 89264 178727 89265 178727 89274 178727 89274 178728 89265 178728 90717 178728 89255 178729 90747 178729 91753 178729 91753 178730 90747 178730 89273 178730 90717 178731 89265 178731 89266 178731 89266 178732 89265 178732 89267 178732 89266 178733 89267 178733 90716 178733 90716 178734 89267 178734 89268 178734 90716 178735 89268 178735 90715 178735 90715 178736 89268 178736 89269 178736 90715 178737 89269 178737 89270 178737 89270 178738 89269 178738 89271 178738 89270 178739 89271 178739 89273 178739 89273 178740 89271 178740 89272 178740 89273 178741 89272 178741 91753 178741 89264 178742 89274 178742 89275 178742 89275 178743 89274 178743 89276 178743 89275 178744 89276 178744 91762 178744 91762 178745 89276 178745 89277 178745 91762 178746 89277 178746 91765 178746 91765 178747 89277 178747 89278 178747 91765 178748 89278 178748 91766 178748 91766 178749 89278 178749 90740 178749 91766 178750 90740 178750 89279 178750 89279 178751 90740 178751 90742 178751 89279 178752 90742 178752 91768 178752 91768 178753 90742 178753 90756 178753 89284 178754 91768 178754 90756 178754 89289 178755 89288 178755 90797 178755 90797 178756 89288 178756 89281 178756 91773 178757 89283 178757 91774 178757 91774 178758 89283 178758 89280 178758 91774 178759 89280 178759 89281 178759 89281 178760 89280 178760 90795 178760 89281 178761 90795 178761 90797 178761 89282 178762 90761 178762 91773 178762 91773 178763 90761 178763 90762 178763 91773 178764 90762 178764 89283 178764 90756 178765 90757 178765 89284 178765 89284 178766 90757 178766 90759 178766 89284 178767 90759 178767 91770 178767 91770 178768 90759 178768 89285 178768 91770 178769 89285 178769 89282 178769 89282 178770 89285 178770 89286 178770 89282 178771 89286 178771 90761 178771 90885 178772 89287 178772 90855 178772 90855 178773 89287 178773 89288 178773 90855 178774 89288 178774 89289 178774 91776 178775 89287 178775 90885 178775 90920 178776 89290 178776 89293 178776 89293 178777 89290 178777 89292 178777 91842 178778 89291 178778 89292 178778 89292 178779 89291 178779 90918 178779 89292 178780 90918 178780 89293 178780 91778 178781 89294 178781 91842 178781 91842 178782 89294 178782 90917 178782 91842 178783 90917 178783 89291 178783 90885 178784 90886 178784 91776 178784 91776 178785 90886 178785 89295 178785 91776 178786 89295 178786 91777 178786 91777 178787 89295 178787 89296 178787 91777 178788 89296 178788 91778 178788 91778 178789 89296 178789 89297 178789 91778 178790 89297 178790 89294 178790 89290 178791 90920 178791 89298 178791 89298 178792 90920 178792 90877 178792 89298 178793 90877 178793 91837 178793 91837 178794 90877 178794 89300 178794 91837 178795 89300 178795 89299 178795 89299 178796 89300 178796 89301 178796 89299 178797 89301 178797 91839 178797 91839 178798 89301 178798 89303 178798 91839 178799 89303 178799 89302 178799 89302 178800 89303 178800 89304 178800 89302 178801 89304 178801 91836 178801 91836 178802 89304 178802 90799 178802 89384 178803 89568 178803 89961 178803 89961 178804 89568 178804 89522 178804 89961 178805 89522 178805 89956 178805 89956 178806 89522 178806 89521 178806 89956 178807 89521 178807 89917 178807 89917 178808 89521 178808 89305 178808 89917 178809 89305 178809 89306 178809 89306 178810 89305 178810 89520 178810 89306 178811 89520 178811 89307 178811 89307 178812 89520 178812 89517 178812 89307 178813 89517 178813 89308 178813 89308 178814 89517 178814 89309 178814 89308 178815 89309 178815 89310 178815 89310 178816 89309 178816 89311 178816 89310 178817 89311 178817 89950 178817 89950 178818 89311 178818 89312 178818 89950 178819 89312 178819 89952 178819 89952 178820 89312 178820 89515 178820 89952 178821 89515 178821 89313 178821 89313 178822 89515 178822 89513 178822 89313 178823 89513 178823 89314 178823 89314 178824 89513 178824 89512 178824 89314 178825 89512 178825 89315 178825 89315 178826 89512 178826 89316 178826 89315 178827 89316 178827 89317 178827 89317 178828 89316 178828 89318 178828 89317 178829 89318 178829 89319 178829 89319 178830 89318 178830 89320 178830 89319 178831 89320 178831 89321 178831 89321 178832 89320 178832 89322 178832 89321 178833 89322 178833 89940 178833 89940 178834 89322 178834 89323 178834 89940 178835 89323 178835 89941 178835 89941 178836 89323 178836 89324 178836 89941 178837 89324 178837 89325 178837 89325 178838 89324 178838 89509 178838 89325 178839 89509 178839 89326 178839 89326 178840 89509 178840 89511 178840 89326 178841 89511 178841 89942 178841 89942 178842 89511 178842 89327 178842 89942 178843 89327 178843 89328 178843 89328 178844 89327 178844 89330 178844 89328 178845 89330 178845 89329 178845 89329 178846 89330 178846 89508 178846 89673 178847 90054 178847 89331 178847 89331 178848 90054 178848 89332 178848 89331 178849 89332 178849 89642 178849 89642 178850 89332 178850 89999 178850 89642 178851 89999 178851 89597 178851 89597 178852 89999 178852 90001 178852 89597 178853 90001 178853 89636 178853 89636 178854 90001 178854 89333 178854 89636 178855 89333 178855 89334 178855 89334 178856 89333 178856 89335 178856 89334 178857 89335 178857 89336 178857 89336 178858 89335 178858 89337 178858 89336 178859 89337 178859 89338 178859 89338 178860 89337 178860 89339 178860 89338 178861 89339 178861 89638 178861 89638 178862 89339 178862 89340 178862 89638 178863 89340 178863 89635 178863 89635 178864 89340 178864 89997 178864 89635 178865 89997 178865 89342 178865 89342 178866 89997 178866 89341 178866 89342 178867 89341 178867 89344 178867 89344 178868 89341 178868 89343 178868 89344 178869 89343 178869 89632 178869 89632 178870 89343 178870 89345 178870 89632 178871 89345 178871 89346 178871 89346 178872 89345 178872 89994 178872 89346 178873 89994 178873 89631 178873 89631 178874 89994 178874 89993 178874 89631 178875 89993 178875 89621 178875 89621 178876 89993 178876 89347 178876 89621 178877 89347 178877 89622 178877 89622 178878 89347 178878 89991 178878 89622 178879 89991 178879 89623 178879 89623 178880 89991 178880 89348 178880 89623 178881 89348 178881 89625 178881 89625 178882 89348 178882 89349 178882 89625 178883 89349 178883 89626 178883 89626 178884 89349 178884 89989 178884 89626 178885 89989 178885 89620 178885 89620 178886 89989 178886 89350 178886 89620 178887 89350 178887 89351 178887 89351 178888 89350 178888 89988 178888 89351 178889 89988 178889 89614 178889 89614 178890 89988 178890 89987 178890 89355 178891 89781 178891 89409 178891 89400 178892 89353 178892 89352 178892 89352 178893 89353 178893 89354 178893 89352 178894 89354 178894 89403 178894 89403 178895 89354 178895 89355 178895 89403 178896 89355 178896 89397 178896 89397 178897 89355 178897 89409 178897 88596 178898 89356 178898 89357 178898 89357 178899 89356 178899 89420 178899 89357 178900 89420 178900 89816 178900 89420 178901 89358 178901 89816 178901 89816 178902 89358 178902 89359 178902 89816 178903 89359 178903 89360 178903 89801 178904 89435 178904 89430 178904 89444 178905 89790 178905 89431 178905 89431 178906 89790 178906 89797 178906 89431 178907 89797 178907 89430 178907 89430 178908 89797 178908 89796 178908 89430 178909 89796 178909 89801 178909 89835 178910 89467 178910 89833 178910 89833 178911 89467 178911 89363 178911 89833 178912 89363 178912 89362 178912 89482 178913 89842 178913 89473 178913 89473 178914 89842 178914 89362 178914 89473 178915 89362 178915 89361 178915 89361 178916 89362 178916 89363 178916 89367 178917 89364 178917 89083 178917 88964 178918 90180 178918 89753 178918 89753 178919 90180 178919 89366 178919 89753 178920 89366 178920 89365 178920 89365 178921 89366 178921 89367 178921 89365 178922 89367 178922 89751 178922 89751 178923 89367 178923 89083 178923 90140 178924 89730 178924 90139 178924 90139 178925 89730 178925 89732 178925 90139 178926 89732 178926 89369 178926 89732 178927 89368 178927 89369 178927 89369 178928 89368 178928 89370 178928 89369 178929 89370 178929 89084 178929 90171 178930 89729 178930 89373 178930 89710 178931 89371 178931 89372 178931 89372 178932 89371 178932 90149 178932 89372 178933 90149 178933 89373 178933 89373 178934 90149 178934 90152 178934 89373 178935 90152 178935 90171 178935 90128 178936 89374 178936 90106 178936 90106 178937 89374 178937 89685 178937 90106 178938 89685 178938 90110 178938 88593 178939 90116 178939 89375 178939 89375 178940 90116 178940 90110 178940 89375 178941 90110 178941 89376 178941 89376 178942 90110 178942 89685 178942 88599 178943 89857 178943 89377 178943 89377 178944 89857 178944 89378 178944 89377 178945 89378 178945 89379 178945 89379 178946 89378 178946 89875 178946 89379 178947 89875 178947 89380 178947 89875 178948 89902 178948 89380 178948 89380 178949 89902 178949 89381 178949 89380 178950 89381 178950 89382 178950 89382 178951 89381 178951 89329 178951 89382 178952 89329 178952 89508 178952 89388 178953 89383 178953 89982 178953 89982 178954 89383 178954 89568 178954 89982 178955 89568 178955 89384 178955 88589 178956 89385 178956 90035 178956 90035 178957 89385 178957 89589 178957 90035 178958 89589 178958 89387 178958 89387 178959 89589 178959 89386 178959 89387 178960 89386 178960 89388 178960 89388 178961 89386 178961 89564 178961 89388 178962 89564 178962 89383 178962 89389 178963 89578 178963 89973 178963 89973 178964 89578 178964 89614 178964 89973 178965 89614 178965 89987 178965 88577 178966 89391 178966 89390 178966 89390 178967 89391 178967 89556 178967 89390 178968 89556 178968 89392 178968 89392 178969 89556 178969 89585 178969 89392 178970 89585 178970 89389 178970 89389 178971 89585 178971 89579 178971 89389 178972 89579 178972 89578 178972 88588 178973 90074 178973 89679 178973 89679 178974 90074 178974 90078 178974 89679 178975 90078 178975 89393 178975 89393 178976 90078 178976 90045 178976 89393 178977 90045 178977 89394 178977 90045 178978 90046 178978 89394 178978 89394 178979 90046 178979 89396 178979 89394 178980 89396 178980 89395 178980 89395 178981 89396 178981 90054 178981 89395 178982 90054 178982 89673 178982 89403 178983 89397 178983 89402 178983 91743 178984 91744 178984 89401 178984 89401 178985 91744 178985 89416 178985 89401 178986 89416 178986 89398 178986 89398 178987 89416 178987 89399 178987 89398 178988 89399 178988 89352 178988 89352 178989 89399 178989 89400 178989 89406 178990 91743 178990 89407 178990 89407 178991 91743 178991 89401 178991 89407 178992 89401 178992 89402 178992 89402 178993 89401 178993 89398 178993 89402 178994 89398 178994 89403 178994 89403 178995 89398 178995 89352 178995 89404 178996 89406 178996 89405 178996 89405 178997 89406 178997 89407 178997 89405 178998 89407 178998 89408 178998 89408 178999 89407 178999 89402 178999 89408 179000 89402 179000 89409 179000 89409 179001 89402 179001 89397 179001 89085 179002 89359 179002 89410 179002 89410 179003 89359 179003 89411 179003 89410 179004 89411 179004 89412 179004 89412 179005 89411 179005 89413 179005 89412 179006 89413 179006 89414 179006 89414 179007 89413 179007 91740 179007 89409 179008 89085 179008 89408 179008 89408 179009 89085 179009 89410 179009 89408 179010 89410 179010 89405 179010 89405 179011 89410 179011 89412 179011 89405 179012 89412 179012 89404 179012 89404 179013 89412 179013 89414 179013 89082 179014 89400 179014 89415 179014 89415 179015 89400 179015 89399 179015 89415 179016 89399 179016 89418 179016 89418 179017 89399 179017 89416 179017 89418 179018 89416 179018 89419 179018 89419 179019 89416 179019 91744 179019 89435 179020 89082 179020 89434 179020 89434 179021 89082 179021 89415 179021 89434 179022 89415 179022 89417 179022 89417 179023 89415 179023 89418 179023 89417 179024 89418 179024 91748 179024 91748 179025 89418 179025 89419 179025 89420 179026 89356 179026 89424 179026 89424 179027 89356 179027 89442 179027 89424 179028 89442 179028 89421 179028 89421 179029 89442 179029 89422 179029 89421 179030 89422 179030 91739 179030 91739 179031 89422 179031 91738 179031 89358 179032 89420 179032 89423 179032 89423 179033 89420 179033 89424 179033 89423 179034 89424 179034 89425 179034 89425 179035 89424 179035 89421 179035 89425 179036 89421 179036 91742 179036 91742 179037 89421 179037 91739 179037 89359 179038 89358 179038 89411 179038 89411 179039 89358 179039 89423 179039 89411 179040 89423 179040 89413 179040 89413 179041 89423 179041 89425 179041 89413 179042 89425 179042 91740 179042 91740 179043 89425 179043 91742 179043 91747 179044 89426 179044 89429 179044 89429 179045 89426 179045 89428 179045 89429 179046 89428 179046 89427 179046 89427 179047 89428 179047 89446 179047 89427 179048 89446 179048 89431 179048 89431 179049 89446 179049 89444 179049 89432 179050 91747 179050 89433 179050 89433 179051 91747 179051 89429 179051 89433 179052 89429 179052 89436 179052 89436 179053 89429 179053 89427 179053 89436 179054 89427 179054 89430 179054 89430 179055 89427 179055 89431 179055 91748 179056 89432 179056 89417 179056 89417 179057 89432 179057 89433 179057 89417 179058 89433 179058 89434 179058 89434 179059 89433 179059 89436 179059 89434 179060 89436 179060 89435 179060 89435 179061 89436 179061 89430 179061 88595 179062 89438 179062 89437 179062 89437 179063 89438 179063 89440 179063 89437 179064 89440 179064 89439 179064 89439 179065 89440 179065 89441 179065 89439 179066 89441 179066 89443 179066 89443 179067 89441 179067 89451 179067 89356 179068 88595 179068 89442 179068 89442 179069 88595 179069 89437 179069 89442 179070 89437 179070 89422 179070 89422 179071 89437 179071 89439 179071 89422 179072 89439 179072 91738 179072 91738 179073 89439 179073 89443 179073 89079 179074 89444 179074 89445 179074 89445 179075 89444 179075 89446 179075 89445 179076 89446 179076 89447 179076 89447 179077 89446 179077 89428 179077 89447 179078 89428 179078 89448 179078 89448 179079 89428 179079 89426 179079 89467 179080 89079 179080 89449 179080 89449 179081 89079 179081 89445 179081 89449 179082 89445 179082 89450 179082 89450 179083 89445 179083 89447 179083 89450 179084 89447 179084 89468 179084 89468 179085 89447 179085 89448 179085 89451 179086 89441 179086 89461 179086 89454 179087 89453 179087 89452 179087 89452 179088 89453 179088 89477 179088 89452 179089 89477 179089 89455 179089 88599 179090 89454 179090 89458 179090 89455 179091 89456 179091 89452 179091 89452 179092 89456 179092 89457 179092 89452 179093 89457 179093 89459 179093 89459 179094 89457 179094 88666 179094 89459 179095 88666 179095 89461 179095 89461 179096 88666 179096 88665 179096 89461 179097 88665 179097 89451 179097 89454 179098 89452 179098 89458 179098 89458 179099 89452 179099 89459 179099 89458 179100 89459 179100 89464 179100 89464 179101 89459 179101 89461 179101 89464 179102 89461 179102 89460 179102 89460 179103 89461 179103 89441 179103 89460 179104 89441 179104 89440 179104 88599 179105 89458 179105 89462 179105 89462 179106 89458 179106 89464 179106 89462 179107 89464 179107 89463 179107 89463 179108 89464 179108 89460 179108 89463 179109 89460 179109 89465 179109 89465 179110 89460 179110 89440 179110 89465 179111 89440 179111 89438 179111 89361 179112 89363 179112 89466 179112 89363 179113 89467 179113 89466 179113 89466 179114 89467 179114 89449 179114 89466 179115 89449 179115 89472 179115 89472 179116 89449 179116 89450 179116 89472 179117 89450 179117 91746 179117 91746 179118 89450 179118 89468 179118 89473 179119 89361 179119 89469 179119 89469 179120 89361 179120 89466 179120 89469 179121 89466 179121 89470 179121 89470 179122 89466 179122 89472 179122 89470 179123 89472 179123 89471 179123 89471 179124 89472 179124 91746 179124 89482 179125 89473 179125 89474 179125 89474 179126 89473 179126 89469 179126 89474 179127 89469 179127 89475 179127 89475 179128 89469 179128 89470 179128 89475 179129 89470 179129 89476 179129 89476 179130 89470 179130 89471 179130 88720 179131 89477 179131 89479 179131 89479 179132 89477 179132 89453 179132 89479 179133 89453 179133 89480 179133 89480 179134 89453 179134 89454 179134 89480 179135 89454 179135 89377 179135 89377 179136 89454 179136 88599 179136 88721 179137 88720 179137 89493 179137 89493 179138 88720 179138 89479 179138 89493 179139 89479 179139 89478 179139 89478 179140 89479 179140 89480 179140 89478 179141 89480 179141 89379 179141 89379 179142 89480 179142 89377 179142 89484 179143 89482 179143 89481 179143 89481 179144 89482 179144 89474 179144 89481 179145 89474 179145 89487 179145 89487 179146 89474 179146 89475 179146 89487 179147 89475 179147 89483 179147 89483 179148 89475 179148 89476 179148 88580 179149 89484 179149 89485 179149 89485 179150 89484 179150 89481 179150 89485 179151 89481 179151 89486 179151 89486 179152 89481 179152 89487 179152 89486 179153 89487 179153 91749 179153 91749 179154 89487 179154 89483 179154 89538 179155 89491 179155 89488 179155 89488 179156 89491 179156 89489 179156 89488 179157 89489 179157 89510 179157 89510 179158 89489 179158 89490 179158 89510 179159 89490 179159 89508 179159 89508 179160 89490 179160 89382 179160 89491 179161 88604 179161 89489 179161 89489 179162 88604 179162 89492 179162 89489 179163 89492 179163 89490 179163 89490 179164 89492 179164 89494 179164 89490 179165 89494 179165 89382 179165 89382 179166 89494 179166 89380 179166 88604 179167 88721 179167 89492 179167 89492 179168 88721 179168 89493 179168 89492 179169 89493 179169 89494 179169 89494 179170 89493 179170 89478 179170 89494 179171 89478 179171 89380 179171 89380 179172 89478 179172 89379 179172 89495 179173 89559 179173 89496 179173 89486 179174 91749 179174 89497 179174 88580 179175 89485 179175 89504 179175 89485 179176 89486 179176 89501 179176 89501 179177 89486 179177 89497 179177 89501 179178 89497 179178 89498 179178 89498 179179 89497 179179 88848 179179 89499 179180 89502 179180 88849 179180 88849 179181 89502 179181 89500 179181 88849 179182 89500 179182 88903 179182 88903 179183 89500 179183 89498 179183 88903 179184 89498 179184 88904 179184 88904 179185 89498 179185 88848 179185 89485 179186 89501 179186 89504 179186 89504 179187 89501 179187 89498 179187 89504 179188 89498 179188 89505 179188 89505 179189 89498 179189 89500 179189 89505 179190 89500 179190 89496 179190 89496 179191 89500 179191 89502 179191 89496 179192 89502 179192 89495 179192 88580 179193 89504 179193 89503 179193 89503 179194 89504 179194 89505 179194 89503 179195 89505 179195 88578 179195 88578 179196 89505 179196 89496 179196 88578 179197 89496 179197 89506 179197 89506 179198 89496 179198 89559 179198 89506 179199 89559 179199 89391 179199 89538 179200 89488 179200 89525 179200 89571 179201 89552 179201 89550 179201 89488 179202 89510 179202 89507 179202 89510 179203 89508 179203 89330 179203 89509 179204 89528 179204 89526 179204 89510 179205 89330 179205 89507 179205 89507 179206 89330 179206 89327 179206 89507 179207 89327 179207 89526 179207 89526 179208 89327 179208 89511 179208 89526 179209 89511 179209 89509 179209 89318 179210 89533 179210 89532 179210 89509 179211 89324 179211 89528 179211 89528 179212 89324 179212 89323 179212 89528 179213 89323 179213 89529 179213 89529 179214 89323 179214 89322 179214 89529 179215 89322 179215 89532 179215 89532 179216 89322 179216 89320 179216 89532 179217 89320 179217 89318 179217 89311 179218 89518 179218 89516 179218 89318 179219 89316 179219 89533 179219 89533 179220 89316 179220 89512 179220 89533 179221 89512 179221 89534 179221 89534 179222 89512 179222 89513 179222 89534 179223 89513 179223 89514 179223 89514 179224 89513 179224 89515 179224 89514 179225 89515 179225 89516 179225 89516 179226 89515 179226 89312 179226 89516 179227 89312 179227 89311 179227 89522 179228 89523 179228 89521 179228 89521 179229 89523 179229 89537 179229 89311 179230 89309 179230 89518 179230 89518 179231 89309 179231 89517 179231 89518 179232 89517 179232 89519 179232 89519 179233 89517 179233 89520 179233 89519 179234 89520 179234 89537 179234 89537 179235 89520 179235 89305 179235 89537 179236 89305 179236 89521 179236 89522 179237 89568 179237 89523 179237 89523 179238 89568 179238 89524 179238 89523 179239 89524 179239 89570 179239 89488 179240 89507 179240 89525 179240 89525 179241 89507 179241 89526 179241 89525 179242 89526 179242 89527 179242 89527 179243 89526 179243 89528 179243 89527 179244 89528 179244 89539 179244 89539 179245 89528 179245 89529 179245 89539 179246 89529 179246 89530 179246 89530 179247 89529 179247 89532 179247 89530 179248 89532 179248 89531 179248 89531 179249 89532 179249 89533 179249 89531 179250 89533 179250 89540 179250 89540 179251 89533 179251 89534 179251 89540 179252 89534 179252 89543 179252 89543 179253 89534 179253 89514 179253 89543 179254 89514 179254 89544 179254 89544 179255 89514 179255 89516 179255 89544 179256 89516 179256 89546 179256 89546 179257 89516 179257 89518 179257 89546 179258 89518 179258 89535 179258 89535 179259 89518 179259 89519 179259 89535 179260 89519 179260 89536 179260 89536 179261 89519 179261 89537 179261 89536 179262 89537 179262 89549 179262 89549 179263 89537 179263 89523 179263 89549 179264 89523 179264 89550 179264 89550 179265 89523 179265 89570 179265 89550 179266 89570 179266 89571 179266 89538 179267 89525 179267 88600 179267 88600 179268 89525 179268 89527 179268 88600 179269 89527 179269 88608 179269 88608 179270 89527 179270 89539 179270 88608 179271 89539 179271 88602 179271 88602 179272 89539 179272 89530 179272 88602 179273 89530 179273 88614 179273 88614 179274 89530 179274 89531 179274 88614 179275 89531 179275 88612 179275 88612 179276 89531 179276 89540 179276 88612 179277 89540 179277 89541 179277 89541 179278 89540 179278 89543 179278 89541 179279 89543 179279 89542 179279 89542 179280 89543 179280 89544 179280 89542 179281 89544 179281 89545 179281 89545 179282 89544 179282 89546 179282 89545 179283 89546 179283 89547 179283 89547 179284 89546 179284 89535 179284 89547 179285 89535 179285 89548 179285 89548 179286 89535 179286 89536 179286 89548 179287 89536 179287 88615 179287 88615 179288 89536 179288 89549 179288 88615 179289 89549 179289 88603 179289 88603 179290 89549 179290 89550 179290 88603 179291 89550 179291 89551 179291 89551 179292 89550 179292 89552 179292 89551 179293 89552 179293 88624 179293 89557 179294 88946 179294 89558 179294 89558 179295 88946 179295 89587 179295 89558 179296 89587 179296 89553 179296 89553 179297 89587 179297 89555 179297 89553 179298 89555 179298 89554 179298 89554 179299 89555 179299 89586 179299 89554 179300 89586 179300 89556 179300 89556 179301 89586 179301 89585 179301 89499 179302 89557 179302 89502 179302 89502 179303 89557 179303 89558 179303 89502 179304 89558 179304 89495 179304 89495 179305 89558 179305 89553 179305 89495 179306 89553 179306 89559 179306 89559 179307 89553 179307 89554 179307 89559 179308 89554 179308 89391 179308 89391 179309 89554 179309 89556 179309 88617 179310 89560 179310 89561 179310 89561 179311 89560 179311 89565 179311 89561 179312 89565 179312 89590 179312 89590 179313 89565 179313 89562 179313 89590 179314 89562 179314 89563 179314 89563 179315 89562 179315 89567 179315 89563 179316 89567 179316 89386 179316 89386 179317 89567 179317 89564 179317 89560 179318 89573 179318 89565 179318 89565 179319 89573 179319 89572 179319 89565 179320 89572 179320 89562 179320 89562 179321 89572 179321 89566 179321 89562 179322 89566 179322 89567 179322 89567 179323 89566 179323 89569 179323 89567 179324 89569 179324 89564 179324 89564 179325 89569 179325 89383 179325 89568 179326 89383 179326 89524 179326 89524 179327 89383 179327 89569 179327 89524 179328 89569 179328 89570 179328 89570 179329 89569 179329 89566 179329 89570 179330 89566 179330 89571 179330 89571 179331 89566 179331 89572 179331 89571 179332 89572 179332 89552 179332 89552 179333 89572 179333 89573 179333 89552 179334 89573 179334 88624 179334 89614 179335 89578 179335 89574 179335 89574 179336 89578 179336 89575 179336 89574 179337 89575 179337 89576 179337 89576 179338 89575 179338 89581 179338 89583 179339 89617 179339 89581 179339 89581 179340 89617 179340 89616 179340 89581 179341 89616 179341 89576 179341 89584 179342 89598 179342 89583 179342 89583 179343 89598 179343 89577 179343 89583 179344 89577 179344 89617 179344 89578 179345 89579 179345 89575 179345 89575 179346 89579 179346 89580 179346 89575 179347 89580 179347 89581 179347 89581 179348 89580 179348 89582 179348 89581 179349 89582 179349 89583 179349 89583 179350 89582 179350 89588 179350 89583 179351 89588 179351 89584 179351 89584 179352 89588 179352 88945 179352 89579 179353 89585 179353 89580 179353 89580 179354 89585 179354 89586 179354 89580 179355 89586 179355 89582 179355 89582 179356 89586 179356 89555 179356 89582 179357 89555 179357 89588 179357 89588 179358 89555 179358 89587 179358 89588 179359 89587 179359 88945 179359 88945 179360 89587 179360 88946 179360 89563 179361 89386 179361 89589 179361 89590 179362 89563 179362 89592 179362 89593 179363 88617 179363 89595 179363 89595 179364 88617 179364 89561 179364 89595 179365 89561 179365 89591 179365 89563 179366 89589 179366 89592 179366 89592 179367 89589 179367 89385 179367 89592 179368 89385 179368 89651 179368 89651 179369 89655 179369 89592 179369 89592 179370 89655 179370 89591 179370 89592 179371 89591 179371 89590 179371 89590 179372 89591 179372 89561 179372 88626 179373 89593 179373 89594 179373 89594 179374 89593 179374 89595 179374 89594 179375 89595 179375 89654 179375 89654 179376 89595 179376 89591 179376 89654 179377 89591 179377 89596 179377 89596 179378 89591 179378 89655 179378 89642 179379 89597 179379 89644 179379 89615 179380 89600 179380 89618 179380 89577 179381 89598 179381 89601 179381 88957 179382 89618 179382 89599 179382 89599 179383 89618 179383 89600 179383 89599 179384 89600 179384 89601 179384 89601 179385 89600 179385 89617 179385 89601 179386 89617 179386 89577 179386 88960 179387 89602 179387 88959 179387 88959 179388 89602 179388 89603 179388 88959 179389 89603 179389 89604 179389 89604 179390 89603 179390 89611 179390 89604 179391 89611 179391 89605 179391 89605 179392 89611 179392 89607 179392 89605 179393 89607 179393 89606 179393 89606 179394 89607 179394 89628 179394 89606 179395 89628 179395 88954 179395 89609 179396 89624 179396 89619 179396 88957 179397 89608 179397 89609 179397 89609 179398 89608 179398 89627 179398 89609 179399 89627 179399 89624 179399 89624 179400 89627 179400 89630 179400 89602 179401 89634 179401 89603 179401 89603 179402 89634 179402 89610 179402 89603 179403 89610 179403 89611 179403 89611 179404 89610 179404 89633 179404 89611 179405 89633 179405 89607 179405 89607 179406 89633 179406 89629 179406 89607 179407 89629 179407 89628 179407 89612 179408 89613 179408 89637 179408 88960 179409 88952 179409 89612 179409 89612 179410 88952 179410 89639 179410 89612 179411 89639 179411 89613 179411 89613 179412 89639 179412 89641 179412 89615 179413 89351 179413 89614 179413 89614 179414 89574 179414 89615 179414 89615 179415 89574 179415 89576 179415 89615 179416 89576 179416 89600 179416 89600 179417 89576 179417 89616 179417 89600 179418 89616 179418 89617 179418 88957 179419 89609 179419 89618 179419 89618 179420 89609 179420 89619 179420 89618 179421 89619 179421 89615 179421 89615 179422 89619 179422 89620 179422 89615 179423 89620 179423 89351 179423 89621 179424 89622 179424 89630 179424 89630 179425 89622 179425 89623 179425 89630 179426 89623 179426 89624 179426 89624 179427 89623 179427 89625 179427 89624 179428 89625 179428 89619 179428 89619 179429 89625 179429 89626 179429 89619 179430 89626 179430 89620 179430 89608 179431 88954 179431 89627 179431 89627 179432 88954 179432 89628 179432 89627 179433 89628 179433 89630 179433 89630 179434 89628 179434 89629 179434 89630 179435 89629 179435 89621 179435 89621 179436 89629 179436 89631 179436 89631 179437 89629 179437 89346 179437 89346 179438 89629 179438 89633 179438 89346 179439 89633 179439 89632 179439 89632 179440 89633 179440 89610 179440 89632 179441 89610 179441 89344 179441 89344 179442 89610 179442 89634 179442 89344 179443 89634 179443 89342 179443 88960 179444 89612 179444 89602 179444 89602 179445 89612 179445 89637 179445 89602 179446 89637 179446 89634 179446 89634 179447 89637 179447 89635 179447 89634 179448 89635 179448 89342 179448 89636 179449 89334 179449 89641 179449 89641 179450 89334 179450 89336 179450 89641 179451 89336 179451 89613 179451 89613 179452 89336 179452 89338 179452 89613 179453 89338 179453 89637 179453 89637 179454 89338 179454 89638 179454 89637 179455 89638 179455 89635 179455 88952 179456 89640 179456 89639 179456 89639 179457 89640 179457 89645 179457 89639 179458 89645 179458 89641 179458 89641 179459 89645 179459 89644 179459 89641 179460 89644 179460 89636 179460 89636 179461 89644 179461 89597 179461 89331 179462 89642 179462 89648 179462 89648 179463 89642 179463 89644 179463 89648 179464 89644 179464 89643 179464 89643 179465 89644 179465 89645 179465 89643 179466 89645 179466 88950 179466 88950 179467 89645 179467 89640 179467 88950 179468 89646 179468 89643 179468 89643 179469 89646 179469 89647 179469 89643 179470 89647 179470 89648 179470 89648 179471 89647 179471 89649 179471 89648 179472 89649 179472 89331 179472 89331 179473 89649 179473 89673 179473 89657 179474 89655 179474 89650 179474 89650 179475 89655 179475 89651 179475 89650 179476 89651 179476 89385 179476 89652 179477 88627 179477 89653 179477 89653 179478 88627 179478 88626 179478 88626 179479 89594 179479 89653 179479 89653 179480 89594 179480 89654 179480 89653 179481 89654 179481 89657 179481 89657 179482 89654 179482 89596 179482 89657 179483 89596 179483 89655 179483 89650 179484 89656 179484 89657 179484 89657 179485 89656 179485 89663 179485 89657 179486 89663 179486 89653 179486 89653 179487 89663 179487 89659 179487 89653 179488 89659 179488 89652 179488 89666 179489 89658 179489 89659 179489 89659 179490 89658 179490 89660 179490 89659 179491 89660 179491 89652 179491 89675 179492 89665 179492 89676 179492 89676 179493 89665 179493 89664 179493 89676 179494 89664 179494 89661 179494 89661 179495 89664 179495 89662 179495 89656 179496 89662 179496 89663 179496 89663 179497 89662 179497 89664 179497 89663 179498 89664 179498 89659 179498 89659 179499 89664 179499 89665 179499 89659 179500 89665 179500 89666 179500 89666 179501 89665 179501 89675 179501 89666 179502 89675 179502 88639 179502 89393 179503 89394 179503 89683 179503 89683 179504 89394 179504 89667 179504 89683 179505 89667 179505 89681 179505 89681 179506 89667 179506 89669 179506 89681 179507 89669 179507 89668 179507 89668 179508 89669 179508 89670 179508 89394 179509 89395 179509 89667 179509 89667 179510 89395 179510 89671 179510 89667 179511 89671 179511 89669 179511 89669 179512 89671 179512 89672 179512 89669 179513 89672 179513 89670 179513 89670 179514 89672 179514 88943 179514 89395 179515 89673 179515 89671 179515 89671 179516 89673 179516 89649 179516 89671 179517 89649 179517 89672 179517 89672 179518 89649 179518 89647 179518 89672 179519 89647 179519 88943 179519 88943 179520 89647 179520 89646 179520 91694 179521 88639 179521 89674 179521 89674 179522 88639 179522 89675 179522 89674 179523 89675 179523 89677 179523 89677 179524 89675 179524 89676 179524 89677 179525 89676 179525 88591 179525 88591 179526 89676 179526 89661 179526 91698 179527 91694 179527 89693 179527 89693 179528 91694 179528 89674 179528 89693 179529 89674 179529 89692 179529 89692 179530 89674 179530 89677 179530 89692 179531 89677 179531 88593 179531 88593 179532 89677 179532 88591 179532 89680 179533 89678 179533 89682 179533 89682 179534 89678 179534 89708 179534 89682 179535 89708 179535 89684 179535 89684 179536 89708 179536 89707 179536 89684 179537 89707 179537 89679 179537 89679 179538 89707 179538 88588 179538 89668 179539 89680 179539 89681 179539 89681 179540 89680 179540 89682 179540 89681 179541 89682 179541 89683 179541 89683 179542 89682 179542 89684 179542 89683 179543 89684 179543 89393 179543 89393 179544 89684 179544 89679 179544 89376 179545 89685 179545 89686 179545 89685 179546 89374 179546 89686 179546 89686 179547 89374 179547 89687 179547 89686 179548 89687 179548 89690 179548 89690 179549 89687 179549 89716 179549 89690 179550 89716 179550 89691 179550 89691 179551 89716 179551 89688 179551 89375 179552 89376 179552 89689 179552 89689 179553 89376 179553 89686 179553 89689 179554 89686 179554 89694 179554 89694 179555 89686 179555 89690 179555 89694 179556 89690 179556 91695 179556 91695 179557 89690 179557 89691 179557 88593 179558 89375 179558 89692 179558 89692 179559 89375 179559 89689 179559 89692 179560 89689 179560 89693 179560 89693 179561 89689 179561 89694 179561 89693 179562 89694 179562 91698 179562 91698 179563 89694 179563 91695 179563 89695 179564 88583 179564 89696 179564 89699 179565 89695 179565 89704 179565 89697 179566 89698 179566 89700 179566 89700 179567 89698 179567 89699 179567 89697 179568 89700 179568 88934 179568 88934 179569 89700 179569 89706 179569 88934 179570 89706 179570 88850 179570 88850 179571 89706 179571 89701 179571 88850 179572 89701 179572 88851 179572 89695 179573 89696 179573 89704 179573 89704 179574 89696 179574 88585 179574 89704 179575 88585 179575 89705 179575 89705 179576 88585 179576 89702 179576 89705 179577 89702 179577 89703 179577 89703 179578 89702 179578 88588 179578 89703 179579 88588 179579 89707 179579 89699 179580 89704 179580 89700 179580 89700 179581 89704 179581 89705 179581 89700 179582 89705 179582 89706 179582 89706 179583 89705 179583 89703 179583 89706 179584 89703 179584 89701 179584 89701 179585 89703 179585 89707 179585 89701 179586 89707 179586 89708 179586 89708 179587 89678 179587 89701 179587 89701 179588 89678 179588 89709 179588 89701 179589 89709 179589 88851 179589 89714 179590 89710 179590 89715 179590 89715 179591 89710 179591 89711 179591 89715 179592 89711 179592 89712 179592 89712 179593 89711 179593 89713 179593 89712 179594 89713 179594 89717 179594 89717 179595 89713 179595 91692 179595 89374 179596 89714 179596 89687 179596 89687 179597 89714 179597 89715 179597 89687 179598 89715 179598 89716 179598 89716 179599 89715 179599 89712 179599 89716 179600 89712 179600 89688 179600 89688 179601 89712 179601 89717 179601 89720 179602 89731 179602 89721 179602 89721 179603 89731 179603 89718 179603 89721 179604 89718 179604 89722 179604 89722 179605 89718 179605 89719 179605 89722 179606 89719 179606 88581 179606 88581 179607 89719 179607 89730 179607 89698 179608 89720 179608 89699 179608 89699 179609 89720 179609 89721 179609 89699 179610 89721 179610 89695 179610 89695 179611 89721 179611 89722 179611 89695 179612 89722 179612 88583 179612 88583 179613 89722 179613 88581 179613 91693 179614 91692 179614 89725 179614 89725 179615 91692 179615 89713 179615 89725 179616 89713 179616 89727 179616 89727 179617 89713 179617 89711 179617 89727 179618 89711 179618 89372 179618 89372 179619 89711 179619 89710 179619 89723 179620 91693 179620 89724 179620 89724 179621 91693 179621 89725 179621 89724 179622 89725 179622 89726 179622 89726 179623 89725 179623 89727 179623 89726 179624 89727 179624 89373 179624 89373 179625 89727 179625 89372 179625 89728 179626 89723 179626 89744 179626 89744 179627 89723 179627 89724 179627 89744 179628 89724 179628 89742 179628 89742 179629 89724 179629 89726 179629 89742 179630 89726 179630 89729 179630 89729 179631 89726 179631 89373 179631 89732 179632 89730 179632 89733 179632 89733 179633 89730 179633 89719 179633 89733 179634 89719 179634 89736 179634 89736 179635 89719 179635 89718 179635 89736 179636 89718 179636 89737 179636 89737 179637 89718 179637 89731 179637 89368 179638 89732 179638 89734 179638 89734 179639 89732 179639 89733 179639 89734 179640 89733 179640 89735 179640 89735 179641 89733 179641 89736 179641 89735 179642 89736 179642 91687 179642 91687 179643 89736 179643 89737 179643 89370 179644 89368 179644 89746 179644 89746 179645 89368 179645 89734 179645 89746 179646 89734 179646 89738 179646 89738 179647 89734 179647 89735 179647 89738 179648 89735 179648 89739 179648 89739 179649 89735 179649 91687 179649 88965 179650 88964 179650 89743 179650 89743 179651 88964 179651 89740 179651 89743 179652 89740 179652 89745 179652 89745 179653 89740 179653 89741 179653 89745 179654 89741 179654 92001 179654 92001 179655 89741 179655 91691 179655 89729 179656 88965 179656 89742 179656 89742 179657 88965 179657 89743 179657 89742 179658 89743 179658 89744 179658 89744 179659 89743 179659 89745 179659 89744 179660 89745 179660 89728 179660 89728 179661 89745 179661 92001 179661 89747 179662 89370 179662 89749 179662 89749 179663 89370 179663 89746 179663 89749 179664 89746 179664 89750 179664 89750 179665 89746 179665 89738 179665 89750 179666 89738 179666 91690 179666 91690 179667 89738 179667 89739 179667 89083 179668 89747 179668 89759 179668 89759 179669 89747 179669 89749 179669 89759 179670 89749 179670 89748 179670 89748 179671 89749 179671 89750 179671 89748 179672 89750 179672 91689 179672 91689 179673 89750 179673 91690 179673 89365 179674 89751 179674 89757 179674 89752 179675 91691 179675 89755 179675 89755 179676 91691 179676 89741 179676 89755 179677 89741 179677 89756 179677 89756 179678 89741 179678 89740 179678 89756 179679 89740 179679 89753 179679 89753 179680 89740 179680 88964 179680 89758 179681 89752 179681 89754 179681 89754 179682 89752 179682 89755 179682 89754 179683 89755 179683 89757 179683 89757 179684 89755 179684 89756 179684 89757 179685 89756 179685 89365 179685 89365 179686 89756 179686 89753 179686 91689 179687 89758 179687 89748 179687 89748 179688 89758 179688 89754 179688 89748 179689 89754 179689 89759 179689 89759 179690 89754 179690 89757 179690 89759 179691 89757 179691 89083 179691 89083 179692 89757 179692 89751 179692 89354 179693 89353 179693 89766 179693 89766 179694 89353 179694 89760 179694 89766 179695 89760 179695 89767 179695 89767 179696 89760 179696 89761 179696 89767 179697 89761 179697 89762 179697 89762 179698 89761 179698 89764 179698 89762 179699 89764 179699 89763 179699 89763 179700 89764 179700 89780 179700 89355 179701 89354 179701 89770 179701 89770 179702 89354 179702 89766 179702 89770 179703 89766 179703 89765 179703 89765 179704 89766 179704 89767 179704 89765 179705 89767 179705 89773 179705 89773 179706 89767 179706 89762 179706 89773 179707 89762 179707 89768 179707 89768 179708 89762 179708 89763 179708 89781 179709 89355 179709 89769 179709 89769 179710 89355 179710 89770 179710 89769 179711 89770 179711 89771 179711 89771 179712 89770 179712 89765 179712 89771 179713 89765 179713 89772 179713 89772 179714 89765 179714 89773 179714 89772 179715 89773 179715 89785 179715 89785 179716 89773 179716 89768 179716 89081 179717 89801 179717 89777 179717 89777 179718 89801 179718 89774 179718 89777 179719 89774 179719 89778 179719 89778 179720 89774 179720 89802 179720 89778 179721 89802 179721 89779 179721 89779 179722 89802 179722 89775 179722 89779 179723 89775 179723 88452 179723 88452 179724 89775 179724 89776 179724 89353 179725 89081 179725 89760 179725 89760 179726 89081 179726 89777 179726 89760 179727 89777 179727 89761 179727 89761 179728 89777 179728 89778 179728 89761 179729 89778 179729 89764 179729 89764 179730 89778 179730 89779 179730 89764 179731 89779 179731 89780 179731 89780 179732 89779 179732 88452 179732 89086 179733 89781 179733 89782 179733 89782 179734 89781 179734 89769 179734 89782 179735 89769 179735 89783 179735 89783 179736 89769 179736 89771 179736 89783 179737 89771 179737 89788 179737 89788 179738 89771 179738 89772 179738 89788 179739 89772 179739 89784 179739 89784 179740 89772 179740 89785 179740 89360 179741 89086 179741 89815 179741 89815 179742 89086 179742 89782 179742 89815 179743 89782 179743 89786 179743 89786 179744 89782 179744 89783 179744 89786 179745 89783 179745 89787 179745 89787 179746 89783 179746 89788 179746 89787 179747 89788 179747 89812 179747 89812 179748 89788 179748 89784 179748 89797 179749 89790 179749 89789 179749 89789 179750 89790 179750 89791 179750 89789 179751 89791 179751 89792 179751 89792 179752 89791 179752 89821 179752 89792 179753 89821 179753 89793 179753 89793 179754 89821 179754 89794 179754 89793 179755 89794 179755 89800 179755 89800 179756 89794 179756 89795 179756 89796 179757 89797 179757 89798 179757 89798 179758 89797 179758 89789 179758 89798 179759 89789 179759 89803 179759 89803 179760 89789 179760 89792 179760 89803 179761 89792 179761 89804 179761 89804 179762 89792 179762 89793 179762 89804 179763 89793 179763 89799 179763 89799 179764 89793 179764 89800 179764 89801 179765 89796 179765 89774 179765 89774 179766 89796 179766 89798 179766 89774 179767 89798 179767 89802 179767 89802 179768 89798 179768 89803 179768 89802 179769 89803 179769 89775 179769 89775 179770 89803 179770 89804 179770 89775 179771 89804 179771 89776 179771 89776 179772 89804 179772 89799 179772 89808 179773 88207 179773 89809 179773 89809 179774 88207 179774 89825 179774 89809 179775 89825 179775 89805 179775 89805 179776 89825 179776 89806 179776 89805 179777 89806 179777 89811 179777 89811 179778 89806 179778 89807 179778 89811 179779 89807 179779 89357 179779 89357 179780 89807 179780 88596 179780 88210 179781 89808 179781 89813 179781 89813 179782 89808 179782 89809 179782 89813 179783 89809 179783 89814 179783 89814 179784 89809 179784 89805 179784 89814 179785 89805 179785 89810 179785 89810 179786 89805 179786 89811 179786 89810 179787 89811 179787 89816 179787 89816 179788 89811 179788 89357 179788 89812 179789 88210 179789 89787 179789 89787 179790 88210 179790 89813 179790 89787 179791 89813 179791 89786 179791 89786 179792 89813 179792 89814 179792 89786 179793 89814 179793 89815 179793 89815 179794 89814 179794 89810 179794 89815 179795 89810 179795 89360 179795 89360 179796 89810 179796 89816 179796 89080 179797 89835 179797 89820 179797 89820 179798 89835 179798 89834 179798 89820 179799 89834 179799 89822 179799 89822 179800 89834 179800 89817 179800 89822 179801 89817 179801 89823 179801 89823 179802 89817 179802 89831 179802 89823 179803 89831 179803 89818 179803 89818 179804 89831 179804 89819 179804 89790 179805 89080 179805 89791 179805 89791 179806 89080 179806 89820 179806 89791 179807 89820 179807 89821 179807 89821 179808 89820 179808 89822 179808 89821 179809 89822 179809 89794 179809 89794 179810 89822 179810 89823 179810 89794 179811 89823 179811 89795 179811 89795 179812 89823 179812 89818 179812 88597 179813 88596 179813 89828 179813 89828 179814 88596 179814 89807 179814 89828 179815 89807 179815 89829 179815 89829 179816 89807 179816 89806 179816 89829 179817 89806 179817 89824 179817 89824 179818 89806 179818 89825 179818 89824 179819 89825 179819 88208 179819 88208 179820 89825 179820 88207 179820 89826 179821 88597 179821 89827 179821 89827 179822 88597 179822 89828 179822 89827 179823 89828 179823 89845 179823 89845 179824 89828 179824 89829 179824 89845 179825 89829 179825 89846 179825 89846 179826 89829 179826 89824 179826 89846 179827 89824 179827 89847 179827 89847 179828 89824 179828 88208 179828 88325 179829 89819 179829 89830 179829 89830 179830 89819 179830 89831 179830 89830 179831 89831 179831 89832 179831 89832 179832 89831 179832 89817 179832 89832 179833 89817 179833 89838 179833 89838 179834 89817 179834 89834 179834 89838 179835 89834 179835 89833 179835 89833 179836 89834 179836 89835 179836 89836 179837 88325 179837 89837 179837 89837 179838 88325 179838 89830 179838 89837 179839 89830 179839 89840 179839 89840 179840 89830 179840 89832 179840 89840 179841 89832 179841 89841 179841 89841 179842 89832 179842 89838 179842 89841 179843 89838 179843 89362 179843 89362 179844 89838 179844 89833 179844 89873 179845 89836 179845 89839 179845 89839 179846 89836 179846 89837 179846 89839 179847 89837 179847 89871 179847 89871 179848 89837 179848 89840 179848 89871 179849 89840 179849 89868 179849 89868 179850 89840 179850 89841 179850 89868 179851 89841 179851 89842 179851 89842 179852 89841 179852 89362 179852 89852 179853 89843 179853 89851 179853 88598 179854 89826 179854 89848 179854 89848 179855 89826 179855 89827 179855 89848 179856 89827 179856 89844 179856 89844 179857 89827 179857 89845 179857 89844 179858 89845 179858 89850 179858 89850 179859 89845 179859 89846 179859 89850 179860 89846 179860 88847 179860 88847 179861 89846 179861 89847 179861 89853 179862 88598 179862 89855 179862 89855 179863 88598 179863 89848 179863 89855 179864 89848 179864 89849 179864 89849 179865 89848 179865 89844 179865 89849 179866 89844 179866 89851 179866 89851 179867 89844 179867 89850 179867 89851 179868 89850 179868 89852 179868 89852 179869 89850 179869 88847 179869 89858 179870 89853 179870 89854 179870 89854 179871 89853 179871 89855 179871 89854 179872 89855 179872 89856 179872 89856 179873 89855 179873 89849 179873 89856 179874 89849 179874 89861 179874 89861 179875 89849 179875 89851 179875 89861 179876 89851 179876 88751 179876 88751 179877 89851 179877 89843 179877 89857 179878 89858 179878 89859 179878 89859 179879 89858 179879 89854 179879 89859 179880 89854 179880 89860 179880 89860 179881 89854 179881 89856 179881 89860 179882 89856 179882 89862 179882 89862 179883 89856 179883 89861 179883 89862 179884 89861 179884 88750 179884 88750 179885 89861 179885 88751 179885 89869 179886 89863 179886 89870 179886 89870 179887 89863 179887 89891 179887 89870 179888 89891 179888 89864 179888 89864 179889 89891 179889 89865 179889 89864 179890 89865 179890 89872 179890 89872 179891 89865 179891 89895 179891 89872 179892 89895 179892 89866 179892 89866 179893 89895 179893 89867 179893 89842 179894 89869 179894 89868 179894 89868 179895 89869 179895 89870 179895 89868 179896 89870 179896 89871 179896 89871 179897 89870 179897 89864 179897 89871 179898 89864 179898 89839 179898 89839 179899 89864 179899 89872 179899 89839 179900 89872 179900 89873 179900 89873 179901 89872 179901 89866 179901 89378 179902 89857 179902 89874 179902 89874 179903 89857 179903 89859 179903 89874 179904 89859 179904 89877 179904 89877 179905 89859 179905 89860 179905 89877 179906 89860 179906 89878 179906 89878 179907 89860 179907 89862 179907 89878 179908 89862 179908 89879 179908 89879 179909 89862 179909 88750 179909 89875 179910 89378 179910 89903 179910 89903 179911 89378 179911 89874 179911 89903 179912 89874 179912 89906 179912 89906 179913 89874 179913 89877 179913 89906 179914 89877 179914 89876 179914 89876 179915 89877 179915 89878 179915 89876 179916 89878 179916 89908 179916 89908 179917 89878 179917 89879 179917 89890 179918 88968 179918 89894 179918 89880 179919 89881 179919 89884 179919 89880 179920 89884 179920 88966 179920 89885 179921 88577 179921 89882 179921 89882 179922 88577 179922 89913 179922 89882 179923 89913 179923 89883 179923 89883 179924 89913 179924 89915 179924 89883 179925 89915 179925 89884 179925 89884 179926 89915 179926 89916 179926 89884 179927 89916 179927 88966 179927 88579 179928 89885 179928 89887 179928 89887 179929 89885 179929 89882 179929 89887 179930 89882 179930 89888 179930 89888 179931 89882 179931 89883 179931 89888 179932 89883 179932 89889 179932 89889 179933 89883 179933 89884 179933 89889 179934 89884 179934 89000 179934 89000 179935 89884 179935 89881 179935 89886 179936 88579 179936 89892 179936 89892 179937 88579 179937 89887 179937 89892 179938 89887 179938 89893 179938 89893 179939 89887 179939 89888 179939 89893 179940 89888 179940 89894 179940 89894 179941 89888 179941 89889 179941 89894 179942 89889 179942 89890 179942 89890 179943 89889 179943 89000 179943 89863 179944 89886 179944 89891 179944 89891 179945 89886 179945 89892 179945 89891 179946 89892 179946 89865 179946 89865 179947 89892 179947 89893 179947 89865 179948 89893 179948 89895 179948 89895 179949 89893 179949 89894 179949 89895 179950 89894 179950 89867 179950 89867 179951 89894 179951 88968 179951 89329 179952 89381 179952 89897 179952 89897 179953 89381 179953 89896 179953 89897 179954 89896 179954 89936 179954 89936 179955 89896 179955 89901 179955 89899 179956 89898 179956 89901 179956 89901 179957 89898 179957 89937 179957 89901 179958 89937 179958 89936 179958 88735 179959 88737 179959 89899 179959 89899 179960 88737 179960 89918 179960 89899 179961 89918 179961 89898 179961 89381 179962 89902 179962 89896 179962 89896 179963 89902 179963 89900 179963 89896 179964 89900 179964 89901 179964 89901 179965 89900 179965 89904 179965 89901 179966 89904 179966 89899 179966 89899 179967 89904 179967 89905 179967 89899 179968 89905 179968 88735 179968 88735 179969 89905 179969 89907 179969 89902 179970 89875 179970 89900 179970 89900 179971 89875 179971 89903 179971 89900 179972 89903 179972 89904 179972 89904 179973 89903 179973 89906 179973 89904 179974 89906 179974 89905 179974 89905 179975 89906 179975 89876 179975 89905 179976 89876 179976 89907 179976 89907 179977 89876 179977 89908 179977 89914 179978 89390 179978 89392 179978 89965 179979 89055 179979 89966 179979 89966 179980 89055 179980 89909 179980 89966 179981 89909 179981 89912 179981 89912 179982 89909 179982 89911 179982 89392 179983 89910 179983 89914 179983 89914 179984 89910 179984 89972 179984 89914 179985 89972 179985 89911 179985 89911 179986 89972 179986 89971 179986 89911 179987 89971 179987 89912 179987 88577 179988 89390 179988 89913 179988 89913 179989 89390 179989 89914 179989 89913 179990 89914 179990 89915 179990 89915 179991 89914 179991 89911 179991 89915 179992 89911 179992 89916 179992 89916 179993 89911 179993 89909 179993 89916 179994 89909 179994 88966 179994 88966 179995 89909 179995 89055 179995 89956 179996 89917 179996 89957 179996 89939 179997 89935 179997 89920 179997 89918 179998 88737 179998 88740 179998 89919 179999 89920 179999 89921 179999 89921 180000 89920 180000 89935 180000 89921 180001 89935 180001 88740 180001 88740 180002 89935 180002 89898 180002 88740 180003 89898 180003 89918 180003 88742 180004 89930 180004 88744 180004 88744 180005 89930 180005 89931 180005 88744 180006 89931 180006 89922 180006 89922 180007 89931 180007 89932 180007 89922 180008 89932 180008 89923 180008 89923 180009 89932 180009 89924 180009 89923 180010 89924 180010 88726 180010 88726 180011 89924 180011 89933 180011 88726 180012 89933 180012 89925 180012 89927 180013 89928 180013 89938 180013 89919 180014 89926 180014 89927 180014 89927 180015 89926 180015 89929 180015 89927 180016 89929 180016 89928 180016 89928 180017 89929 180017 89943 180017 89930 180018 89947 180018 89931 180018 89931 180019 89947 180019 89946 180019 89931 180020 89946 180020 89932 180020 89932 180021 89946 180021 89945 180021 89932 180022 89945 180022 89924 180022 89924 180023 89945 180023 89944 180023 89924 180024 89944 180024 89933 180024 89948 180025 89949 180025 89951 180025 88742 180026 88732 180026 89948 180026 89948 180027 88732 180027 89954 180027 89948 180028 89954 180028 89949 180028 89949 180029 89954 180029 89934 180029 89939 180030 89328 180030 89329 180030 89329 180031 89897 180031 89939 180031 89939 180032 89897 180032 89936 180032 89939 180033 89936 180033 89935 180033 89935 180034 89936 180034 89937 180034 89935 180035 89937 180035 89898 180035 89919 180036 89927 180036 89920 180036 89920 180037 89927 180037 89938 180037 89920 180038 89938 180038 89939 180038 89939 180039 89938 180039 89942 180039 89939 180040 89942 180040 89328 180040 89321 180041 89940 180041 89943 180041 89943 180042 89940 180042 89941 180042 89943 180043 89941 180043 89928 180043 89928 180044 89941 180044 89325 180044 89928 180045 89325 180045 89938 180045 89938 180046 89325 180046 89326 180046 89938 180047 89326 180047 89942 180047 89926 180048 89925 180048 89929 180048 89929 180049 89925 180049 89933 180049 89929 180050 89933 180050 89943 180050 89943 180051 89933 180051 89944 180051 89943 180052 89944 180052 89321 180052 89321 180053 89944 180053 89319 180053 89319 180054 89944 180054 89317 180054 89317 180055 89944 180055 89945 180055 89317 180056 89945 180056 89315 180056 89315 180057 89945 180057 89946 180057 89315 180058 89946 180058 89314 180058 89314 180059 89946 180059 89947 180059 89314 180060 89947 180060 89313 180060 88742 180061 89948 180061 89930 180061 89930 180062 89948 180062 89951 180062 89930 180063 89951 180063 89947 180063 89947 180064 89951 180064 89952 180064 89947 180065 89952 180065 89313 180065 89306 180066 89307 180066 89934 180066 89934 180067 89307 180067 89308 180067 89934 180068 89308 180068 89949 180068 89949 180069 89308 180069 89310 180069 89949 180070 89310 180070 89951 180070 89951 180071 89310 180071 89950 180071 89951 180072 89950 180072 89952 180072 88732 180073 89953 180073 89954 180073 89954 180074 89953 180074 89955 180074 89954 180075 89955 180075 89934 180075 89934 180076 89955 180076 89957 180076 89934 180077 89957 180077 89306 180077 89306 180078 89957 180078 89917 180078 89961 180079 89956 180079 89960 180079 89960 180080 89956 180080 89957 180080 89960 180081 89957 180081 89958 180081 89958 180082 89957 180082 89955 180082 89958 180083 89955 180083 88722 180083 88722 180084 89955 180084 89953 180084 88722 180085 88725 180085 89958 180085 89958 180086 88725 180086 89959 180086 89958 180087 89959 180087 89960 180087 89960 180088 89959 180088 89985 180088 89960 180089 89985 180089 89961 180089 89961 180090 89985 180090 89384 180090 89964 180091 89963 180091 89967 180091 89071 180092 89963 180092 89962 180092 89962 180093 89963 180093 89964 180093 89962 180094 89964 180094 89969 180094 89970 180095 89974 180095 89968 180095 89965 180096 89966 180096 89967 180096 89967 180097 89966 180097 89970 180097 89967 180098 89970 180098 89964 180098 89964 180099 89970 180099 89968 180099 89964 180100 89968 180100 89969 180100 89969 180101 89968 180101 89987 180101 89966 180102 89912 180102 89970 180102 89970 180103 89912 180103 89971 180103 89970 180104 89971 180104 89974 180104 89974 180105 89971 180105 89972 180105 89974 180106 89972 180106 89910 180106 89987 180107 89968 180107 89973 180107 89973 180108 89968 180108 89974 180108 89973 180109 89974 180109 89389 180109 89389 180110 89974 180110 89910 180110 89389 180111 89910 180111 89392 180111 89387 180112 89388 180112 89975 180112 89975 180113 89388 180113 89976 180113 89975 180114 89976 180114 90033 180114 90033 180115 89976 180115 89977 180115 89977 180116 89976 180116 89980 180116 89977 180117 89980 180117 89978 180117 89978 180118 89980 180118 89979 180118 89979 180119 89980 180119 89981 180119 89979 180120 89981 180120 88746 180120 89388 180121 89982 180121 89976 180121 89976 180122 89982 180122 89983 180122 89976 180123 89983 180123 89980 180123 89980 180124 89983 180124 89984 180124 89980 180125 89984 180125 89981 180125 89981 180126 89984 180126 88724 180126 89982 180127 89384 180127 89983 180127 89983 180128 89384 180128 89985 180128 89983 180129 89985 180129 89984 180129 89984 180130 89985 180130 89959 180130 89984 180131 89959 180131 88724 180131 88724 180132 89959 180132 88725 180132 89071 180133 89962 180133 90002 180133 90016 180134 89986 180134 90030 180134 89962 180135 89969 180135 90003 180135 89969 180136 89987 180136 89988 180136 89349 180137 89990 180137 90004 180137 89969 180138 89988 180138 90003 180138 90003 180139 89988 180139 89350 180139 90003 180140 89350 180140 90004 180140 90004 180141 89350 180141 89989 180141 90004 180142 89989 180142 89349 180142 89994 180143 90008 180143 89992 180143 89349 180144 89348 180144 89990 180144 89990 180145 89348 180145 89991 180145 89990 180146 89991 180146 90006 180146 90006 180147 89991 180147 89347 180147 90006 180148 89347 180148 89992 180148 89992 180149 89347 180149 89993 180149 89992 180150 89993 180150 89994 180150 89339 180151 90011 180151 89995 180151 89994 180152 89345 180152 90008 180152 90008 180153 89345 180153 89343 180153 90008 180154 89343 180154 89996 180154 89996 180155 89343 180155 89341 180155 89996 180156 89341 180156 89998 180156 89998 180157 89341 180157 89997 180157 89998 180158 89997 180158 89995 180158 89995 180159 89997 180159 89340 180159 89995 180160 89340 180160 89339 180160 89332 180161 90015 180161 89999 180161 89999 180162 90015 180162 90013 180162 89339 180163 89337 180163 90011 180163 90011 180164 89337 180164 89335 180164 90011 180165 89335 180165 90000 180165 90000 180166 89335 180166 89333 180166 90000 180167 89333 180167 90013 180167 90013 180168 89333 180168 90001 180168 90013 180169 90001 180169 89999 180169 89332 180170 90054 180170 90015 180170 90015 180171 90054 180171 90055 180171 90015 180172 90055 180172 90056 180172 89962 180173 90003 180173 90002 180173 90002 180174 90003 180174 90004 180174 90002 180175 90004 180175 90017 180175 90017 180176 90004 180176 89990 180176 90017 180177 89990 180177 90005 180177 90005 180178 89990 180178 90006 180178 90005 180179 90006 180179 90020 180179 90020 180180 90006 180180 89992 180180 90020 180181 89992 180181 90007 180181 90007 180182 89992 180182 90008 180182 90007 180183 90008 180183 90009 180183 90009 180184 90008 180184 89996 180184 90009 180185 89996 180185 90010 180185 90010 180186 89996 180186 89998 180186 90010 180187 89998 180187 90023 180187 90023 180188 89998 180188 89995 180188 90023 180189 89995 180189 90024 180189 90024 180190 89995 180190 90011 180190 90024 180191 90011 180191 90027 180191 90027 180192 90011 180192 90000 180192 90027 180193 90000 180193 90012 180193 90012 180194 90000 180194 90013 180194 90012 180195 90013 180195 90014 180195 90014 180196 90013 180196 90015 180196 90014 180197 90015 180197 90030 180197 90030 180198 90015 180198 90056 180198 90030 180199 90056 180199 90016 180199 89071 180200 90002 180200 89072 180200 89072 180201 90002 180201 90017 180201 89072 180202 90017 180202 90018 180202 90018 180203 90017 180203 90005 180203 90018 180204 90005 180204 90019 180204 90019 180205 90005 180205 90020 180205 90019 180206 90020 180206 90021 180206 90021 180207 90020 180207 90007 180207 90021 180208 90007 180208 89078 180208 89078 180209 90007 180209 90009 180209 89078 180210 90009 180210 90022 180210 90022 180211 90009 180211 90010 180211 90022 180212 90010 180212 89076 180212 89076 180213 90010 180213 90023 180213 89076 180214 90023 180214 90025 180214 90025 180215 90023 180215 90024 180215 90025 180216 90024 180216 90026 180216 90026 180217 90024 180217 90027 180217 90026 180218 90027 180218 89070 180218 89070 180219 90027 180219 90012 180219 89070 180220 90012 180220 90028 180220 90028 180221 90012 180221 90014 180221 90028 180222 90014 180222 90029 180222 90029 180223 90014 180223 90030 180223 90029 180224 90030 180224 89059 180224 89059 180225 90030 180225 89986 180225 89059 180226 89986 180226 89057 180226 90038 180227 90035 180227 89387 180227 88746 180228 90031 180228 89979 180228 89979 180229 90031 180229 90032 180229 89979 180230 90032 180230 89978 180230 89978 180231 90032 180231 90034 180231 89387 180232 89975 180232 90038 180232 90038 180233 89975 180233 90033 180233 90038 180234 90033 180234 90034 180234 90034 180235 90033 180235 89977 180235 90034 180236 89977 180236 89978 180236 88589 180237 90035 180237 90036 180237 90036 180238 90035 180238 90038 180238 90036 180239 90038 180239 90037 180239 90037 180240 90038 180240 90034 180240 90037 180241 90034 180241 90039 180241 90039 180242 90034 180242 90032 180242 90039 180243 90032 180243 90040 180243 90040 180244 90032 180244 90031 180244 90041 180245 90047 180245 90042 180245 90042 180246 90047 180246 90050 180246 90042 180247 90050 180247 90043 180247 90043 180248 90050 180248 90051 180248 90043 180249 90051 180249 90044 180249 90044 180250 90051 180250 90052 180250 90044 180251 90052 180251 90045 180251 90045 180252 90052 180252 90046 180252 90047 180253 90048 180253 90050 180253 90050 180254 90048 180254 90049 180254 90050 180255 90049 180255 90051 180255 90051 180256 90049 180256 90057 180256 90051 180257 90057 180257 90052 180257 90052 180258 90057 180258 90053 180258 90052 180259 90053 180259 90046 180259 90046 180260 90053 180260 89396 180260 90054 180261 89396 180261 90055 180261 90055 180262 89396 180262 90053 180262 90055 180263 90053 180263 90056 180263 90056 180264 90053 180264 90057 180264 90056 180265 90057 180265 90016 180265 90016 180266 90057 180266 90049 180266 90016 180267 90049 180267 89986 180267 89986 180268 90049 180268 90048 180268 89986 180269 90048 180269 89057 180269 90058 180270 90059 180270 90060 180270 90059 180271 88749 180271 90060 180271 90060 180272 88749 180272 90061 180272 90060 180273 90061 180273 90064 180273 90064 180274 90061 180274 90062 180274 90064 180275 90062 180275 90066 180275 90066 180276 90062 180276 90063 180276 90066 180277 90063 180277 88590 180277 88590 180278 90063 180278 88592 180278 88747 180279 90058 180279 90067 180279 90067 180280 90058 180280 90060 180280 90067 180281 90060 180281 90068 180281 90068 180282 90060 180282 90064 180282 90068 180283 90064 180283 90065 180283 90065 180284 90064 180284 90066 180284 90065 180285 90066 180285 90071 180285 90071 180286 90066 180286 88590 180286 88843 180287 88747 180287 90072 180287 90072 180288 88747 180288 90067 180288 90072 180289 90067 180289 90073 180289 90073 180290 90067 180290 90068 180290 90073 180291 90068 180291 90069 180291 90069 180292 90068 180292 90065 180292 90069 180293 90065 180293 90070 180293 90070 180294 90065 180294 90071 180294 90040 180295 88843 180295 90039 180295 90039 180296 88843 180296 90072 180296 90039 180297 90072 180297 90037 180297 90037 180298 90072 180298 90073 180298 90037 180299 90073 180299 90036 180299 90036 180300 90073 180300 90069 180300 90036 180301 90069 180301 88589 180301 88589 180302 90069 180302 90070 180302 90078 180303 90074 180303 90075 180303 90075 180304 90074 180304 90077 180304 90075 180305 90077 180305 90076 180305 90076 180306 90077 180306 90091 180306 90076 180307 90091 180307 90079 180307 90079 180308 90091 180308 90087 180308 90079 180309 90087 180309 90080 180309 90080 180310 90087 180310 90086 180310 90045 180311 90078 180311 90044 180311 90044 180312 90078 180312 90075 180312 90044 180313 90075 180313 90043 180313 90043 180314 90075 180314 90076 180314 90043 180315 90076 180315 90042 180315 90042 180316 90076 180316 90079 180316 90042 180317 90079 180317 90041 180317 90041 180318 90079 180318 90080 180318 90084 180319 90082 180319 90081 180319 90081 180320 90082 180320 90111 180320 90081 180321 90111 180321 90085 180321 90085 180322 90111 180322 90114 180322 90085 180323 90114 180323 90083 180323 90083 180324 90114 180324 90115 180324 90083 180325 90115 180325 88594 180325 88594 180326 90115 180326 90116 180326 88749 180327 90084 180327 90061 180327 90061 180328 90084 180328 90081 180328 90061 180329 90081 180329 90062 180329 90062 180330 90081 180330 90085 180330 90062 180331 90085 180331 90063 180331 90063 180332 90085 180332 90083 180332 90063 180333 90083 180333 88592 180333 88592 180334 90083 180334 88594 180334 90089 180335 90086 180335 90087 180335 90088 180336 90089 180336 90090 180336 90090 180337 90089 180337 90087 180337 90090 180338 90087 180338 90094 180338 90094 180339 90087 180339 90091 180339 90094 180340 90091 180340 90093 180340 90093 180341 90091 180341 90077 180341 90093 180342 90077 180342 88587 180342 88587 180343 90077 180343 90074 180343 88587 180344 90092 180344 90093 180344 90093 180345 90092 180345 90095 180345 90093 180346 90095 180346 90094 180346 90094 180347 90095 180347 90101 180347 90094 180348 90101 180348 90090 180348 90090 180349 90101 180349 90097 180349 90090 180350 90097 180350 90088 180350 90096 180351 88970 180351 90097 180351 90097 180352 88970 180352 88971 180352 90097 180353 88971 180353 90088 180353 90102 180354 90098 180354 90119 180354 90119 180355 90098 180355 90100 180355 90119 180356 90100 180356 90120 180356 90120 180357 90100 180357 90099 180357 90120 180358 90099 180358 88584 180358 88584 180359 90099 180359 88586 180359 90092 180360 88586 180360 90095 180360 90095 180361 88586 180361 90099 180361 90095 180362 90099 180362 90101 180362 90101 180363 90099 180363 90100 180363 90101 180364 90100 180364 90097 180364 90097 180365 90100 180365 90098 180365 90097 180366 90098 180366 90096 180366 90096 180367 90098 180367 90102 180367 90096 180368 90102 180368 90118 180368 90103 180369 88261 180369 90108 180369 90108 180370 88261 180370 90134 180370 90108 180371 90134 180371 90104 180371 90104 180372 90134 180372 90132 180372 90104 180373 90132 180373 90105 180373 90105 180374 90132 180374 90129 180374 90105 180375 90129 180375 90106 180375 90106 180376 90129 180376 90128 180376 90112 180377 90103 180377 90113 180377 90113 180378 90103 180378 90108 180378 90113 180379 90108 180379 90107 180379 90107 180380 90108 180380 90104 180380 90107 180381 90104 180381 90109 180381 90109 180382 90104 180382 90105 180382 90109 180383 90105 180383 90110 180383 90110 180384 90105 180384 90106 180384 90082 180385 90112 180385 90111 180385 90111 180386 90112 180386 90113 180386 90111 180387 90113 180387 90114 180387 90114 180388 90113 180388 90107 180388 90114 180389 90107 180389 90115 180389 90115 180390 90107 180390 90109 180390 90115 180391 90109 180391 90116 180391 90116 180392 90109 180392 90110 180392 90117 180393 90118 180393 90122 180393 90122 180394 90118 180394 90102 180394 90122 180395 90102 180395 90125 180395 90125 180396 90102 180396 90119 180396 90125 180397 90119 180397 90126 180397 90126 180398 90119 180398 90120 180398 90126 180399 90120 180399 88582 180399 88582 180400 90120 180400 88584 180400 90121 180401 90117 180401 90137 180401 90137 180402 90117 180402 90122 180402 90137 180403 90122 180403 90123 180403 90123 180404 90122 180404 90125 180404 90123 180405 90125 180405 90124 180405 90124 180406 90125 180406 90126 180406 90124 180407 90126 180407 90140 180407 90140 180408 90126 180408 88582 180408 89087 180409 90128 180409 90127 180409 90127 180410 90128 180410 90129 180410 90127 180411 90129 180411 90130 180411 90130 180412 90129 180412 90132 180412 90130 180413 90132 180413 90131 180413 90131 180414 90132 180414 90134 180414 90131 180415 90134 180415 90133 180415 90133 180416 90134 180416 88261 180416 89371 180417 89087 180417 90135 180417 90135 180418 89087 180418 90127 180418 90135 180419 90127 180419 90136 180419 90136 180420 90127 180420 90130 180420 90136 180421 90130 180421 90151 180421 90151 180422 90130 180422 90131 180422 90151 180423 90131 180423 88262 180423 88262 180424 90131 180424 90133 180424 90141 180425 90121 180425 90142 180425 90142 180426 90121 180426 90137 180426 90142 180427 90137 180427 90138 180427 90138 180428 90137 180428 90123 180428 90138 180429 90123 180429 90145 180429 90145 180430 90123 180430 90124 180430 90145 180431 90124 180431 90139 180431 90139 180432 90124 180432 90140 180432 90146 180433 90141 180433 90148 180433 90148 180434 90141 180434 90142 180434 90148 180435 90142 180435 90143 180435 90143 180436 90142 180436 90138 180436 90143 180437 90138 180437 90144 180437 90144 180438 90138 180438 90145 180438 90144 180439 90145 180439 89369 180439 89369 180440 90145 180440 90139 180440 90170 180441 90146 180441 90147 180441 90147 180442 90146 180442 90148 180442 90147 180443 90148 180443 90168 180443 90168 180444 90148 180444 90143 180444 90168 180445 90143 180445 90166 180445 90166 180446 90143 180446 90144 180446 90166 180447 90144 180447 89084 180447 89084 180448 90144 180448 89369 180448 90149 180449 89371 180449 90153 180449 90153 180450 89371 180450 90135 180450 90153 180451 90135 180451 90155 180451 90155 180452 90135 180452 90136 180452 90155 180453 90136 180453 90150 180453 90150 180454 90136 180454 90151 180454 90150 180455 90151 180455 88264 180455 88264 180456 90151 180456 88262 180456 90152 180457 90149 180457 90158 180457 90158 180458 90149 180458 90153 180458 90158 180459 90153 180459 90159 180459 90159 180460 90153 180460 90155 180460 90159 180461 90155 180461 90154 180461 90154 180462 90155 180462 90150 180462 90154 180463 90150 180463 90156 180463 90156 180464 90150 180464 88264 180464 90171 180465 90152 180465 90157 180465 90157 180466 90152 180466 90158 180466 90157 180467 90158 180467 90173 180467 90173 180468 90158 180468 90159 180468 90173 180469 90159 180469 90160 180469 90160 180470 90159 180470 90154 180470 90160 180471 90154 180471 88263 180471 88263 180472 90154 180472 90156 180472 90161 180473 89364 180473 90167 180473 90167 180474 89364 180474 90186 180474 90167 180475 90186 180475 90162 180475 90162 180476 90186 180476 90163 180476 90162 180477 90163 180477 90169 180477 90169 180478 90163 180478 90164 180478 90169 180479 90164 180479 90165 180479 90165 180480 90164 180480 88267 180480 89084 180481 90161 180481 90166 180481 90166 180482 90161 180482 90167 180482 90166 180483 90167 180483 90168 180483 90168 180484 90167 180484 90162 180484 90168 180485 90162 180485 90147 180485 90147 180486 90162 180486 90169 180486 90147 180487 90169 180487 90170 180487 90170 180488 90169 180488 90165 180488 90175 180489 90171 180489 90172 180489 90172 180490 90171 180490 90157 180490 90172 180491 90157 180491 90177 180491 90177 180492 90157 180492 90173 180492 90177 180493 90173 180493 90174 180493 90174 180494 90173 180494 90160 180494 90174 180495 90160 180495 88433 180495 88433 180496 90160 180496 88263 180496 90180 180497 90175 180497 90181 180497 90181 180498 90175 180498 90172 180498 90181 180499 90172 180499 90176 180499 90176 180500 90172 180500 90177 180500 90176 180501 90177 180501 90178 180501 90178 180502 90177 180502 90174 180502 90178 180503 90174 180503 90179 180503 90179 180504 90174 180504 88433 180504 89366 180505 90180 180505 90183 180505 90183 180506 90180 180506 90181 180506 90183 180507 90181 180507 90184 180507 90184 180508 90181 180508 90176 180508 90184 180509 90176 180509 90182 180509 90182 180510 90176 180510 90178 180510 90182 180511 90178 180511 90185 180511 90185 180512 90178 180512 90179 180512 89367 180513 89366 180513 90187 180513 90187 180514 89366 180514 90183 180514 90187 180515 90183 180515 90188 180515 90188 180516 90183 180516 90184 180516 90188 180517 90184 180517 90189 180517 90189 180518 90184 180518 90182 180518 90189 180519 90182 180519 90190 180519 90190 180520 90182 180520 90185 180520 89364 180521 89367 180521 90186 180521 90186 180522 89367 180522 90187 180522 90186 180523 90187 180523 90163 180523 90163 180524 90187 180524 90188 180524 90163 180525 90188 180525 90164 180525 90164 180526 90188 180526 90189 180526 90164 180527 90189 180527 88267 180527 88267 180528 90189 180528 90190 180528 90191 180529 88570 180529 88571 180529 91892 180530 91893 180530 88572 180530 90226 180531 90219 180531 90212 180531 90193 180532 88531 180532 88540 180532 90192 180533 90193 180533 90194 180533 88405 180534 90192 180534 90195 180534 90193 180535 88540 180535 90194 180535 90194 180536 88540 180536 88542 180536 90194 180537 88542 180537 90203 180537 90203 180538 88542 180538 88545 180538 90203 180539 88545 180539 90205 180539 90205 180540 88545 180540 90196 180540 90205 180541 90196 180541 90206 180541 90206 180542 90196 180542 88544 180542 90206 180543 88544 180543 90197 180543 90197 180544 88544 180544 90198 180544 90197 180545 90198 180545 90208 180545 90208 180546 90198 180546 90199 180546 90208 180547 90199 180547 90211 180547 90211 180548 90199 180548 90200 180548 90211 180549 90200 180549 90201 180549 90201 180550 90200 180550 90224 180550 90201 180551 90224 180551 90202 180551 90192 180552 90194 180552 90195 180552 90195 180553 90194 180553 90203 180553 90195 180554 90203 180554 90204 180554 90204 180555 90203 180555 90205 180555 90204 180556 90205 180556 90214 180556 90214 180557 90205 180557 90206 180557 90214 180558 90206 180558 90216 180558 90216 180559 90206 180559 90197 180559 90216 180560 90197 180560 90207 180560 90207 180561 90197 180561 90208 180561 90207 180562 90208 180562 90209 180562 90209 180563 90208 180563 90211 180563 90209 180564 90211 180564 90210 180564 90210 180565 90211 180565 90201 180565 90210 180566 90201 180566 90212 180566 90212 180567 90201 180567 90202 180567 90212 180568 90202 180568 90226 180568 88405 180569 90195 180569 88339 180569 88339 180570 90195 180570 90204 180570 88339 180571 90204 180571 90213 180571 90213 180572 90204 180572 90214 180572 90213 180573 90214 180573 90215 180573 90215 180574 90214 180574 90216 180574 90215 180575 90216 180575 88334 180575 88334 180576 90216 180576 90207 180576 88334 180577 90207 180577 88335 180577 88335 180578 90207 180578 90209 180578 88335 180579 90209 180579 90217 180579 90217 180580 90209 180580 90210 180580 90217 180581 90210 180581 88336 180581 88336 180582 90210 180582 90212 180582 88336 180583 90212 180583 90218 180583 90218 180584 90212 180584 90219 180584 90218 180585 90219 180585 88337 180585 90222 180586 90255 180586 90223 180586 90223 180587 90255 180587 90247 180587 90223 180588 90247 180588 90220 180588 90220 180589 90247 180589 90237 180589 90220 180590 90237 180590 90221 180590 90221 180591 90237 180591 88517 180591 88405 180592 90222 180592 90192 180592 90192 180593 90222 180593 90223 180593 90192 180594 90223 180594 90193 180594 90193 180595 90223 180595 90220 180595 90193 180596 90220 180596 88531 180596 88531 180597 90220 180597 90221 180597 90202 180598 90224 180598 88547 180598 90219 180599 90226 180599 90225 180599 90225 180600 90226 180600 90202 180600 90202 180601 88547 180601 90225 180601 90225 180602 88547 180602 90227 180602 90225 180603 90227 180603 90256 180603 88337 180604 90219 180604 88338 180604 88338 180605 90219 180605 90225 180605 88338 180606 90225 180606 90228 180606 90228 180607 90225 180607 90256 180607 90228 180608 90256 180608 88327 180608 90290 180609 90291 180609 90230 180609 90288 180610 90290 180610 90231 180610 90287 180611 90288 180611 90229 180611 90290 180612 90230 180612 90231 180612 90231 180613 90230 180613 88516 180613 90231 180614 88516 180614 90238 180614 90238 180615 88516 180615 90232 180615 90238 180616 90232 180616 90241 180616 90241 180617 90232 180617 90233 180617 90241 180618 90233 180618 90242 180618 90242 180619 90233 180619 88521 180619 90242 180620 88521 180620 90243 180620 90243 180621 88521 180621 88520 180621 90243 180622 88520 180622 90234 180622 90234 180623 88520 180623 88519 180623 90234 180624 88519 180624 90235 180624 90235 180625 88519 180625 90236 180625 90235 180626 90236 180626 90246 180626 90246 180627 90236 180627 88517 180627 90246 180628 88517 180628 90237 180628 90288 180629 90231 180629 90229 180629 90229 180630 90231 180630 90238 180630 90229 180631 90238 180631 90239 180631 90239 180632 90238 180632 90241 180632 90239 180633 90241 180633 90240 180633 90240 180634 90241 180634 90242 180634 90240 180635 90242 180635 90249 180635 90249 180636 90242 180636 90243 180636 90249 180637 90243 180637 90244 180637 90244 180638 90243 180638 90234 180638 90244 180639 90234 180639 90245 180639 90245 180640 90234 180640 90235 180640 90245 180641 90235 180641 90251 180641 90251 180642 90235 180642 90246 180642 90251 180643 90246 180643 90253 180643 90253 180644 90246 180644 90237 180644 90253 180645 90237 180645 90247 180645 90287 180646 90229 180646 90248 180646 90248 180647 90229 180647 90239 180647 90248 180648 90239 180648 88341 180648 88341 180649 90239 180649 90240 180649 88341 180650 90240 180650 88342 180650 88342 180651 90240 180651 90249 180651 88342 180652 90249 180652 88343 180652 88343 180653 90249 180653 90244 180653 88343 180654 90244 180654 88345 180654 88345 180655 90244 180655 90245 180655 88345 180656 90245 180656 90250 180656 90250 180657 90245 180657 90251 180657 90250 180658 90251 180658 90252 180658 90252 180659 90251 180659 90253 180659 90252 180660 90253 180660 90254 180660 90254 180661 90253 180661 90247 180661 90254 180662 90247 180662 90255 180662 88327 180663 90256 180663 90257 180663 90258 180664 88533 180664 90259 180664 90258 180665 90259 180665 90270 180665 90270 180666 90259 180666 90260 180666 90270 180667 90260 180667 90261 180667 90261 180668 90260 180668 90262 180668 90261 180669 90262 180669 90263 180669 90263 180670 90262 180670 90265 180670 90263 180671 90265 180671 90264 180671 90264 180672 90265 180672 90266 180672 90264 180673 90266 180673 90274 180673 90274 180674 90266 180674 88537 180674 90274 180675 88537 180675 90267 180675 90267 180676 88537 180676 90268 180676 90267 180677 90268 180677 90269 180677 90269 180678 90268 180678 88532 180678 90269 180679 88532 180679 90277 180679 90227 180680 88533 180680 90256 180680 90256 180681 88533 180681 90258 180681 90256 180682 90258 180682 90257 180682 90257 180683 90258 180683 90270 180683 90257 180684 90270 180684 90271 180684 90271 180685 90270 180685 90261 180685 90271 180686 90261 180686 90272 180686 90272 180687 90261 180687 90263 180687 90272 180688 90263 180688 90279 180688 90279 180689 90263 180689 90264 180689 90279 180690 90264 180690 90273 180690 90273 180691 90264 180691 90274 180691 90273 180692 90274 180692 90282 180692 90282 180693 90274 180693 90267 180693 90282 180694 90267 180694 90275 180694 90275 180695 90267 180695 90269 180695 90275 180696 90269 180696 90276 180696 90276 180697 90269 180697 90277 180697 90276 180698 90277 180698 90292 180698 88327 180699 90257 180699 90278 180699 90278 180700 90257 180700 90271 180700 90278 180701 90271 180701 88328 180701 88328 180702 90271 180702 90272 180702 88328 180703 90272 180703 88329 180703 88329 180704 90272 180704 90279 180704 88329 180705 90279 180705 88330 180705 88330 180706 90279 180706 90273 180706 88330 180707 90273 180707 90280 180707 90280 180708 90273 180708 90282 180708 90280 180709 90282 180709 90281 180709 90281 180710 90282 180710 90275 180710 90281 180711 90275 180711 90283 180711 90283 180712 90275 180712 90276 180712 90283 180713 90276 180713 88333 180713 88333 180714 90276 180714 90292 180714 88333 180715 90292 180715 88332 180715 88352 180716 90323 180716 90289 180716 90289 180717 90323 180717 90314 180717 90289 180718 90314 180718 90285 180718 90285 180719 90314 180719 90284 180719 90285 180720 90284 180720 88523 180720 88523 180721 90284 180721 90286 180721 90287 180722 88352 180722 90288 180722 90288 180723 88352 180723 90289 180723 90288 180724 90289 180724 90290 180724 90290 180725 90289 180725 90285 180725 90290 180726 90285 180726 90291 180726 90291 180727 90285 180727 88523 180727 88421 180728 88332 180728 90295 180728 90295 180729 88332 180729 90292 180729 90295 180730 90292 180730 90298 180730 90298 180731 90292 180731 90277 180731 90298 180732 90277 180732 90293 180732 90293 180733 90277 180733 88532 180733 88420 180734 88421 180734 90294 180734 90294 180735 88421 180735 90295 180735 90294 180736 90295 180736 90296 180736 90296 180737 90295 180737 90298 180737 90296 180738 90298 180738 90297 180738 90297 180739 90298 180739 90293 180739 90296 180740 90297 180740 90299 180740 90294 180741 90296 180741 90301 180741 88420 180742 90294 180742 90305 180742 90296 180743 90299 180743 90301 180743 90301 180744 90299 180744 90300 180744 90301 180745 90300 180745 90306 180745 90306 180746 90300 180746 88526 180746 90306 180747 88526 180747 90307 180747 90307 180748 88526 180748 90302 180748 90307 180749 90302 180749 90308 180749 90308 180750 90302 180750 88530 180750 90308 180751 88530 180751 90303 180751 90303 180752 88530 180752 88529 180752 90303 180753 88529 180753 90311 180753 90311 180754 88529 180754 88528 180754 90311 180755 88528 180755 90312 180755 90312 180756 88528 180756 88527 180756 90312 180757 88527 180757 90304 180757 90304 180758 88527 180758 90286 180758 90304 180759 90286 180759 90284 180759 90294 180760 90301 180760 90305 180760 90305 180761 90301 180761 90306 180761 90305 180762 90306 180762 90315 180762 90315 180763 90306 180763 90307 180763 90315 180764 90307 180764 90317 180764 90317 180765 90307 180765 90308 180765 90317 180766 90308 180766 90309 180766 90309 180767 90308 180767 90303 180767 90309 180768 90303 180768 90310 180768 90310 180769 90303 180769 90311 180769 90310 180770 90311 180770 90319 180770 90319 180771 90311 180771 90312 180771 90319 180772 90312 180772 90321 180772 90321 180773 90312 180773 90304 180773 90321 180774 90304 180774 90313 180774 90313 180775 90304 180775 90284 180775 90313 180776 90284 180776 90314 180776 88420 180777 90305 180777 88346 180777 88346 180778 90305 180778 90315 180778 88346 180779 90315 180779 90316 180779 90316 180780 90315 180780 90317 180780 90316 180781 90317 180781 90318 180781 90318 180782 90317 180782 90309 180782 90318 180783 90309 180783 88347 180783 88347 180784 90309 180784 90310 180784 88347 180785 90310 180785 88348 180785 88348 180786 90310 180786 90319 180786 88348 180787 90319 180787 90320 180787 90320 180788 90319 180788 90321 180788 90320 180789 90321 180789 88349 180789 88349 180790 90321 180790 90313 180790 88349 180791 90313 180791 90322 180791 90322 180792 90313 180792 90314 180792 90322 180793 90314 180793 90323 180793 90344 180794 90433 180794 90432 180794 90333 180795 90345 180795 90338 180795 88524 180796 90349 180796 90327 180796 88522 180797 88525 180797 90343 180797 90343 180798 88525 180798 90324 180798 90343 180799 90324 180799 90342 180799 90342 180800 90324 180800 90331 180800 90342 180801 90331 180801 90325 180801 90325 180802 90331 180802 90335 180802 88525 180803 88524 180803 90324 180803 90324 180804 88524 180804 90326 180804 90324 180805 90326 180805 90331 180805 90331 180806 90326 180806 90329 180806 88524 180807 90327 180807 90326 180807 90326 180808 90327 180808 90328 180808 90326 180809 90328 180809 90329 180809 90329 180810 90328 180810 90330 180810 90329 180811 90330 180811 90332 180811 90335 180812 90331 180812 90334 180812 90334 180813 90331 180813 90329 180813 90334 180814 90329 180814 90338 180814 90338 180815 90329 180815 90332 180815 90338 180816 90332 180816 90333 180816 90336 180817 90429 180817 90334 180817 90334 180818 90429 180818 90340 180818 90334 180819 90340 180819 90335 180819 90336 180820 90334 180820 90337 180820 90337 180821 90334 180821 90338 180821 90337 180822 90338 180822 90432 180822 90432 180823 90338 180823 90345 180823 90432 180824 90345 180824 90344 180824 90429 180825 90367 180825 90339 180825 90429 180826 90339 180826 90340 180826 90340 180827 90339 180827 90365 180827 90340 180828 90365 180828 90335 180828 90335 180829 90365 180829 90325 180829 90325 180830 90365 180830 90341 180830 90325 180831 90341 180831 90342 180831 90342 180832 90341 180832 90364 180832 90342 180833 90364 180833 90343 180833 90343 180834 90364 180834 88515 180834 90343 180835 88515 180835 88522 180835 90433 180836 90344 180836 90441 180836 90441 180837 90344 180837 90374 180837 90374 180838 90344 180838 90346 180838 90346 180839 90344 180839 90345 180839 90346 180840 90345 180840 90347 180840 90347 180841 90345 180841 90333 180841 90347 180842 90333 180842 90348 180842 90348 180843 90333 180843 90332 180843 90348 180844 90332 180844 90370 180844 90370 180845 90332 180845 90330 180845 90370 180846 90330 180846 90369 180846 90369 180847 90330 180847 90328 180847 90369 180848 90328 180848 90368 180848 90328 180849 90327 180849 90368 180849 90368 180850 90327 180850 90349 180850 90368 180851 90349 180851 88538 180851 90391 180852 88518 180852 90389 180852 90389 180853 88518 180853 90357 180853 90360 180854 90350 180854 90358 180854 90358 180855 90350 180855 90351 180855 90358 180856 90351 180856 90357 180856 90357 180857 90351 180857 90387 180857 90357 180858 90387 180858 90389 180858 90355 180859 90352 180859 90360 180859 90360 180860 90352 180860 90384 180860 90360 180861 90384 180861 90350 180861 90353 180862 90354 180862 90355 180862 90355 180863 90354 180863 90383 180863 90355 180864 90383 180864 90352 180864 88518 180865 90356 180865 90357 180865 90357 180866 90356 180866 90363 180866 90357 180867 90363 180867 90358 180867 90358 180868 90363 180868 90359 180868 90358 180869 90359 180869 90360 180869 90360 180870 90359 180870 90361 180870 90360 180871 90361 180871 90355 180871 90355 180872 90361 180872 90362 180872 90355 180873 90362 180873 90353 180873 90353 180874 90362 180874 90366 180874 90356 180875 88515 180875 90363 180875 90363 180876 88515 180876 90364 180876 90363 180877 90364 180877 90359 180877 90359 180878 90364 180878 90341 180878 90359 180879 90341 180879 90361 180879 90361 180880 90341 180880 90365 180880 90361 180881 90365 180881 90362 180881 90362 180882 90365 180882 90339 180882 90362 180883 90339 180883 90366 180883 90366 180884 90339 180884 90367 180884 88535 180885 88534 180885 90372 180885 90368 180886 88538 180886 88536 180886 90368 180887 88536 180887 90369 180887 88535 180888 90372 180888 88536 180888 90369 180889 90380 180889 90370 180889 90370 180890 90380 180890 90381 180890 88534 180891 88546 180891 90372 180891 90372 180892 88546 180892 90371 180892 90372 180893 90371 180893 90373 180893 90374 180894 90346 180894 90382 180894 90382 180895 90346 180895 90347 180895 90382 180896 90347 180896 90381 180896 90381 180897 90347 180897 90348 180897 90381 180898 90348 180898 90370 180898 90371 180899 90375 180899 90373 180899 90373 180900 90375 180900 90395 180900 90373 180901 90395 180901 90376 180901 90376 180902 90395 180902 90377 180902 90376 180903 90377 180903 90394 180903 90441 180904 90374 180904 90378 180904 90378 180905 90374 180905 90382 180905 90378 180906 90382 180906 90379 180906 90379 180907 90382 180907 90447 180907 90369 180908 88536 180908 90380 180908 90380 180909 88536 180909 90372 180909 90380 180910 90372 180910 90381 180910 90381 180911 90372 180911 90373 180911 90381 180912 90373 180912 90382 180912 90382 180913 90373 180913 90376 180913 90382 180914 90376 180914 90447 180914 90447 180915 90376 180915 90394 180915 90447 180916 90394 180916 90392 180916 90354 180917 90416 180917 90383 180917 90383 180918 90416 180918 90412 180918 90383 180919 90412 180919 90352 180919 90352 180920 90412 180920 90403 180920 90352 180921 90403 180921 90384 180921 90384 180922 90403 180922 90401 180922 90384 180923 90401 180923 90350 180923 90350 180924 90401 180924 90385 180924 90350 180925 90385 180925 90351 180925 90351 180926 90385 180926 90386 180926 90351 180927 90386 180927 90387 180927 90387 180928 90386 180928 90388 180928 90387 180929 90388 180929 90389 180929 90389 180930 90388 180930 90390 180930 90389 180931 90390 180931 90391 180931 90391 180932 90390 180932 88539 180932 90422 180933 90392 180933 90394 180933 90422 180934 90394 180934 90393 180934 90393 180935 90394 180935 90377 180935 90393 180936 90377 180936 90400 180936 90400 180937 90377 180937 90395 180937 90400 180938 90395 180938 90399 180938 90395 180939 90375 180939 90399 180939 90399 180940 90375 180940 90371 180940 90399 180941 90371 180941 90396 180941 90396 180942 90371 180942 88546 180942 90396 180943 88546 180943 90398 180943 90397 180944 88541 180944 88539 180944 88541 180945 90397 180945 90405 180945 88539 180946 90390 180946 90397 180946 90397 180947 90390 180947 90388 180947 90397 180948 90388 180948 90408 180948 90408 180949 90388 180949 90386 180949 90408 180950 90386 180950 90410 180950 90398 180951 88543 180951 90396 180951 90396 180952 88543 180952 90406 180952 90396 180953 90406 180953 90399 180953 90399 180954 90406 180954 90407 180954 90399 180955 90407 180955 90400 180955 90400 180956 90407 180956 90409 180956 90400 180957 90409 180957 90393 180957 90393 180958 90409 180958 90404 180958 90393 180959 90404 180959 90422 180959 90386 180960 90385 180960 90410 180960 90410 180961 90385 180961 90401 180961 90410 180962 90401 180962 90402 180962 90402 180963 90401 180963 90403 180963 90402 180964 90403 180964 90412 180964 90411 180965 90425 180965 90404 180965 90404 180966 90425 180966 90424 180966 90404 180967 90424 180967 90422 180967 88543 180968 90405 180968 90406 180968 90406 180969 90405 180969 90397 180969 90406 180970 90397 180970 90407 180970 90407 180971 90397 180971 90408 180971 90407 180972 90408 180972 90409 180972 90409 180973 90408 180973 90410 180973 90409 180974 90410 180974 90404 180974 90404 180975 90410 180975 90402 180975 90404 180976 90402 180976 90411 180976 90411 180977 90402 180977 90412 180977 90411 180978 90412 180978 90416 180978 90417 180979 90413 180979 90414 180979 90413 180980 90354 180980 90353 180980 90413 180981 90353 180981 90414 180981 90414 180982 90353 180982 90366 180982 90414 180983 90366 180983 90415 180983 90415 180984 90366 180984 90367 180984 90415 180985 90367 180985 90420 180985 90417 180986 90414 180986 88188 180986 88188 180987 90414 180987 90415 180987 88188 180988 90415 180988 88180 180988 88180 180989 90415 180989 90420 180989 88180 180990 90420 180990 90421 180990 90416 180991 90354 180991 90413 180991 90416 180992 90413 180992 90418 180992 90418 180993 90413 180993 90417 180993 90418 180994 90417 180994 90419 180994 90367 180995 90429 180995 90431 180995 90367 180996 90431 180996 90420 180996 90420 180997 90431 180997 88508 180997 90420 180998 88508 180998 90421 180998 90440 180999 90422 180999 90424 180999 90427 181000 90440 181000 90423 181000 90423 181001 90440 181001 90424 181001 90423 181002 90424 181002 90428 181002 90424 181003 90425 181003 90428 181003 90428 181004 90425 181004 90411 181004 90428 181005 90411 181005 90426 181005 90426 181006 90411 181006 90416 181006 90426 181007 90416 181007 90418 181007 90427 181008 90423 181008 88169 181008 88169 181009 90423 181009 90428 181009 88169 181010 90428 181010 88173 181010 88173 181011 90428 181011 90426 181011 88173 181012 90426 181012 88166 181012 88166 181013 90426 181013 90418 181013 88166 181014 90418 181014 90419 181014 90431 181015 90429 181015 90336 181015 88508 181016 90431 181016 90430 181016 90430 181017 90431 181017 90336 181017 90430 181018 90336 181018 90436 181018 90336 181019 90337 181019 90436 181019 90436 181020 90337 181020 90432 181020 90436 181021 90432 181021 90435 181021 90435 181022 90432 181022 90433 181022 90433 181023 90442 181023 90435 181023 90435 181024 90442 181024 90434 181024 90435 181025 90434 181025 90438 181025 88508 181026 90430 181026 88509 181026 88509 181027 90430 181027 90436 181027 88509 181028 90436 181028 90437 181028 90437 181029 90436 181029 90435 181029 90437 181030 90435 181030 88513 181030 88513 181031 90435 181031 90438 181031 88513 181032 90438 181032 90439 181032 90392 181033 90422 181033 90440 181033 90392 181034 90440 181034 90448 181034 90448 181035 90440 181035 90427 181035 90448 181036 90427 181036 88483 181036 90441 181037 90445 181037 90433 181037 90433 181038 90445 181038 90442 181038 90442 181039 90445 181039 90434 181039 90434 181040 90445 181040 90444 181040 90434 181041 90444 181041 90438 181041 90444 181042 90443 181042 90438 181042 90438 181043 90443 181043 88496 181043 90438 181044 88496 181044 90439 181044 90443 181045 90444 181045 90450 181045 90445 181046 90441 181046 90378 181046 90449 181047 88496 181047 90443 181047 90444 181048 90445 181048 90450 181048 90450 181049 90445 181049 90378 181049 90450 181050 90378 181050 90446 181050 90378 181051 90379 181051 90446 181051 90446 181052 90379 181052 90447 181052 90446 181053 90447 181053 90452 181053 90452 181054 90447 181054 90392 181054 90452 181055 90392 181055 90448 181055 90443 181056 90450 181056 90449 181056 90449 181057 90450 181057 90446 181057 90449 181058 90446 181058 90451 181058 90451 181059 90446 181059 90452 181059 90451 181060 90452 181060 88503 181060 88503 181061 90452 181061 90448 181061 88503 181062 90448 181062 88483 181062 90470 181063 90603 181063 90453 181063 90453 181064 90603 181064 90457 181064 90469 181065 90454 181065 91869 181065 91869 181066 90454 181066 90610 181066 91869 181067 90610 181067 91870 181067 91870 181068 90610 181068 90616 181068 91870 181069 90616 181069 91871 181069 91871 181070 90616 181070 90455 181070 91871 181071 90455 181071 91873 181071 90603 181072 90456 181072 90457 181072 90457 181073 90456 181073 90459 181073 90457 181074 90459 181074 90458 181074 90458 181075 90459 181075 90460 181075 90458 181076 90460 181076 91862 181076 91862 181077 90460 181077 90605 181077 91862 181078 90605 181078 90462 181078 90462 181079 90605 181079 90461 181079 90462 181080 90461 181080 91863 181080 91863 181081 90461 181081 90463 181081 91863 181082 90463 181082 91864 181082 91864 181083 90463 181083 90464 181083 91864 181084 90464 181084 91865 181084 91865 181085 90464 181085 90607 181085 91865 181086 90607 181086 91866 181086 91866 181087 90607 181087 90465 181087 91866 181088 90465 181088 90466 181088 90466 181089 90465 181089 90467 181089 90466 181090 90467 181090 91868 181090 91868 181091 90467 181091 90615 181091 91868 181092 90615 181092 90468 181092 90468 181093 90615 181093 90613 181093 90468 181094 90613 181094 90469 181094 90469 181095 90613 181095 90612 181095 90469 181096 90612 181096 90454 181096 90453 181097 91861 181097 90470 181097 90470 181098 91861 181098 91860 181098 90470 181099 91860 181099 90601 181099 90601 181100 91860 181100 90471 181100 90601 181101 90471 181101 90472 181101 90472 181102 90471 181102 91978 181102 90472 181103 91978 181103 90599 181103 90599 181104 91978 181104 90473 181104 90599 181105 90473 181105 90484 181105 90455 181106 90474 181106 91873 181106 91873 181107 90474 181107 90475 181107 91873 181108 90475 181108 90476 181108 90476 181109 90475 181109 90676 181109 90476 181110 90676 181110 90477 181110 90477 181111 90676 181111 90478 181111 90477 181112 90478 181112 90479 181112 90479 181113 90478 181113 90480 181113 90479 181114 90480 181114 90481 181114 90481 181115 90480 181115 90482 181115 90481 181116 90482 181116 91859 181116 91859 181117 90482 181117 90484 181117 91859 181118 90484 181118 90483 181118 90483 181119 90484 181119 90473 181119 90505 181120 90487 181120 90503 181120 90503 181121 90487 181121 90489 181121 90485 181122 90502 181122 91908 181122 91908 181123 90502 181123 90533 181123 91908 181124 90533 181124 91848 181124 91848 181125 90533 181125 90486 181125 91848 181126 90486 181126 91849 181126 91849 181127 90486 181127 90538 181127 91849 181128 90538 181128 91850 181128 90487 181129 90488 181129 90489 181129 90489 181130 90488 181130 90491 181130 90489 181131 90491 181131 90490 181131 90490 181132 90491 181132 90492 181132 90490 181133 90492 181133 91857 181133 91857 181134 90492 181134 90493 181134 91857 181135 90493 181135 90494 181135 90494 181136 90493 181136 90529 181136 90494 181137 90529 181137 90495 181137 90495 181138 90529 181138 90530 181138 90495 181139 90530 181139 91844 181139 91844 181140 90530 181140 90496 181140 91844 181141 90496 181141 91845 181141 91845 181142 90496 181142 90531 181142 91845 181143 90531 181143 90497 181143 90497 181144 90531 181144 90532 181144 90497 181145 90532 181145 90498 181145 90498 181146 90532 181146 90536 181146 90498 181147 90536 181147 91846 181147 91846 181148 90536 181148 90499 181148 91846 181149 90499 181149 91847 181149 91847 181150 90499 181150 90500 181150 91847 181151 90500 181151 90485 181151 90485 181152 90500 181152 90501 181152 90485 181153 90501 181153 90502 181153 90503 181154 90504 181154 90505 181154 90505 181155 90504 181155 90507 181155 90505 181156 90507 181156 90506 181156 90506 181157 90507 181157 90509 181157 90506 181158 90509 181158 90508 181158 90508 181159 90509 181159 90510 181159 90508 181160 90510 181160 90523 181160 90523 181161 90510 181161 91855 181161 90523 181162 91855 181162 90511 181162 91855 181163 91854 181163 90511 181163 90511 181164 91854 181164 91853 181164 90511 181165 91853 181165 90518 181165 90518 181166 91853 181166 90517 181166 90518 181167 90517 181167 90516 181167 90538 181168 90539 181168 91850 181168 91850 181169 90539 181169 90512 181169 91850 181170 90512 181170 90514 181170 90514 181171 90512 181171 90513 181171 90514 181172 90513 181172 91851 181172 91851 181173 90513 181173 90598 181173 91851 181174 90598 181174 90515 181174 90515 181175 90598 181175 90516 181175 90515 181176 90516 181176 91852 181176 91852 181177 90516 181177 90517 181177 90516 181178 90594 181178 90518 181178 90518 181179 90594 181179 90524 181179 90595 181180 90519 181180 90520 181180 90520 181181 90519 181181 90521 181181 90520 181182 90521 181182 88368 181182 88368 181183 90521 181183 90559 181183 88368 181184 90559 181184 90522 181184 90508 181185 90523 181185 90524 181185 90524 181186 90523 181186 90511 181186 90524 181187 90511 181187 90518 181187 90524 181188 90592 181188 90508 181188 90508 181189 90592 181189 90591 181189 90508 181190 90591 181190 90506 181190 90506 181191 90591 181191 90525 181191 90492 181192 90491 181192 90526 181192 90526 181193 90491 181193 90488 181193 90526 181194 90488 181194 90527 181194 90527 181195 90488 181195 90487 181195 90527 181196 90487 181196 90525 181196 90525 181197 90487 181197 90505 181197 90525 181198 90505 181198 90506 181198 90492 181199 90526 181199 90493 181199 90493 181200 90526 181200 90528 181200 90493 181201 90528 181201 90529 181201 90529 181202 90528 181202 90588 181202 90529 181203 90588 181203 90530 181203 90530 181204 90588 181204 90586 181204 90530 181205 90586 181205 90496 181205 90496 181206 90586 181206 90531 181206 90531 181207 90586 181207 90584 181207 90531 181208 90584 181208 90532 181208 90532 181209 90584 181209 90535 181209 90532 181210 90535 181210 90536 181210 90486 181211 90533 181211 90537 181211 90537 181212 90533 181212 90502 181212 90537 181213 90502 181213 90581 181213 90581 181214 90502 181214 90501 181214 90581 181215 90501 181215 90534 181215 90534 181216 90501 181216 90500 181216 90534 181217 90500 181217 90535 181217 90535 181218 90500 181218 90499 181218 90535 181219 90499 181219 90536 181219 90486 181220 90537 181220 90538 181220 90538 181221 90537 181221 90580 181221 90538 181222 90580 181222 90539 181222 90539 181223 90580 181223 90540 181223 90539 181224 90540 181224 90512 181224 90512 181225 90540 181225 90577 181225 90512 181226 90577 181226 90513 181226 90522 181227 90559 181227 88369 181227 88369 181228 90559 181228 90542 181228 88369 181229 90542 181229 90541 181229 90541 181230 90542 181230 90560 181230 90541 181231 90560 181231 90543 181231 90543 181232 90560 181232 90544 181232 90543 181233 90544 181233 90546 181233 90546 181234 90544 181234 90545 181234 90546 181235 90545 181235 90547 181235 90547 181236 90545 181236 90563 181236 90547 181237 90563 181237 90548 181237 90548 181238 90563 181238 90564 181238 90548 181239 90564 181239 90549 181239 90549 181240 90564 181240 90565 181240 90549 181241 90565 181241 90550 181241 90550 181242 90565 181242 90551 181242 90550 181243 90551 181243 88364 181243 88364 181244 90551 181244 90552 181244 88364 181245 90552 181245 88366 181245 88366 181246 90552 181246 90568 181246 88366 181247 90568 181247 90553 181247 90553 181248 90568 181248 90554 181248 90553 181249 90554 181249 90555 181249 90555 181250 90554 181250 90570 181250 90555 181251 90570 181251 90556 181251 90556 181252 90570 181252 90573 181252 90556 181253 90573 181253 88365 181253 88365 181254 90573 181254 90574 181254 88365 181255 90574 181255 88422 181255 88422 181256 90574 181256 90557 181256 88422 181257 90557 181257 88423 181257 88423 181258 90557 181258 90558 181258 88423 181259 90558 181259 90595 181259 90519 181260 90596 181260 90521 181260 90521 181261 90596 181261 90576 181261 90521 181262 90576 181262 90559 181262 90559 181263 90576 181263 90578 181263 90559 181264 90578 181264 90542 181264 90542 181265 90578 181265 90579 181265 90542 181266 90579 181266 90560 181266 90560 181267 90579 181267 90561 181267 90560 181268 90561 181268 90544 181268 90544 181269 90561 181269 90562 181269 90544 181270 90562 181270 90545 181270 90545 181271 90562 181271 90582 181271 90545 181272 90582 181272 90563 181272 90563 181273 90582 181273 90583 181273 90563 181274 90583 181274 90564 181274 90564 181275 90583 181275 90566 181275 90564 181276 90566 181276 90565 181276 90565 181277 90566 181277 90585 181277 90565 181278 90585 181278 90551 181278 90551 181279 90585 181279 90587 181279 90551 181280 90587 181280 90552 181280 90552 181281 90587 181281 90567 181281 90552 181282 90567 181282 90568 181282 90568 181283 90567 181283 90569 181283 90568 181284 90569 181284 90554 181284 90554 181285 90569 181285 90571 181285 90554 181286 90571 181286 90570 181286 90570 181287 90571 181287 90589 181287 90570 181288 90589 181288 90573 181288 90573 181289 90589 181289 90572 181289 90573 181290 90572 181290 90574 181290 90574 181291 90572 181291 90590 181291 90574 181292 90590 181292 90557 181292 90557 181293 90590 181293 90593 181293 90557 181294 90593 181294 90558 181294 90558 181295 90593 181295 90597 181295 90596 181296 90575 181296 90576 181296 90576 181297 90575 181297 90577 181297 90576 181298 90577 181298 90578 181298 90578 181299 90577 181299 90540 181299 90578 181300 90540 181300 90579 181300 90579 181301 90540 181301 90580 181301 90579 181302 90580 181302 90561 181302 90561 181303 90580 181303 90537 181303 90561 181304 90537 181304 90562 181304 90562 181305 90537 181305 90581 181305 90562 181306 90581 181306 90582 181306 90582 181307 90581 181307 90534 181307 90582 181308 90534 181308 90583 181308 90583 181309 90534 181309 90535 181309 90583 181310 90535 181310 90566 181310 90566 181311 90535 181311 90584 181311 90566 181312 90584 181312 90585 181312 90585 181313 90584 181313 90586 181313 90585 181314 90586 181314 90587 181314 90587 181315 90586 181315 90588 181315 90587 181316 90588 181316 90567 181316 90567 181317 90588 181317 90528 181317 90567 181318 90528 181318 90569 181318 90569 181319 90528 181319 90526 181319 90569 181320 90526 181320 90571 181320 90571 181321 90526 181321 90527 181321 90571 181322 90527 181322 90589 181322 90589 181323 90527 181323 90525 181323 90589 181324 90525 181324 90572 181324 90572 181325 90525 181325 90591 181325 90572 181326 90591 181326 90590 181326 90590 181327 90591 181327 90592 181327 90590 181328 90592 181328 90593 181328 90593 181329 90592 181329 90524 181329 90593 181330 90524 181330 90597 181330 90597 181331 90524 181331 90594 181331 90595 181332 90558 181332 90519 181332 90519 181333 90558 181333 90597 181333 90519 181334 90597 181334 90596 181334 90596 181335 90597 181335 90594 181335 90596 181336 90594 181336 90575 181336 90575 181337 90594 181337 90516 181337 90575 181338 90516 181338 90577 181338 90577 181339 90516 181339 90598 181339 90577 181340 90598 181340 90513 181340 90480 181341 90674 181341 90482 181341 90482 181342 90674 181342 90671 181342 88355 181343 90638 181343 88356 181343 88356 181344 90638 181344 90640 181344 88356 181345 90640 181345 88357 181345 88357 181346 90640 181346 90641 181346 88357 181347 90641 181347 90619 181347 90472 181348 90599 181348 90671 181348 90671 181349 90599 181349 90484 181349 90671 181350 90484 181350 90482 181350 90671 181351 90669 181351 90472 181351 90472 181352 90669 181352 90600 181352 90472 181353 90600 181353 90601 181353 90601 181354 90600 181354 90602 181354 90460 181355 90459 181355 90604 181355 90604 181356 90459 181356 90456 181356 90604 181357 90456 181357 90666 181357 90666 181358 90456 181358 90603 181358 90666 181359 90603 181359 90602 181359 90602 181360 90603 181360 90470 181360 90602 181361 90470 181361 90601 181361 90460 181362 90604 181362 90605 181362 90605 181363 90604 181363 90663 181363 90605 181364 90663 181364 90461 181364 90461 181365 90663 181365 90606 181365 90461 181366 90606 181366 90463 181366 90463 181367 90606 181367 90608 181367 90463 181368 90608 181368 90464 181368 90464 181369 90608 181369 90607 181369 90607 181370 90608 181370 90609 181370 90607 181371 90609 181371 90465 181371 90465 181372 90609 181372 90660 181372 90465 181373 90660 181373 90467 181373 90616 181374 90610 181374 90658 181374 90658 181375 90610 181375 90454 181375 90658 181376 90454 181376 90611 181376 90611 181377 90454 181377 90612 181377 90611 181378 90612 181378 90614 181378 90614 181379 90612 181379 90613 181379 90614 181380 90613 181380 90660 181380 90660 181381 90613 181381 90615 181381 90660 181382 90615 181382 90467 181382 90616 181383 90658 181383 90455 181383 90455 181384 90658 181384 90617 181384 90455 181385 90617 181385 90474 181385 90474 181386 90617 181386 90657 181386 90474 181387 90657 181387 90475 181387 90475 181388 90657 181388 90618 181388 90475 181389 90618 181389 90676 181389 90619 181390 90641 181390 90620 181390 90620 181391 90641 181391 90621 181391 90620 181392 90621 181392 90622 181392 90622 181393 90621 181393 90643 181393 90622 181394 90643 181394 90623 181394 90623 181395 90643 181395 90624 181395 90623 181396 90624 181396 90625 181396 90625 181397 90624 181397 90626 181397 90625 181398 90626 181398 88437 181398 88437 181399 90626 181399 90646 181399 88437 181400 90646 181400 90627 181400 90627 181401 90646 181401 90628 181401 90627 181402 90628 181402 88361 181402 88361 181403 90628 181403 90629 181403 88361 181404 90629 181404 88362 181404 88362 181405 90629 181405 90650 181405 88362 181406 90650 181406 90630 181406 90630 181407 90650 181407 90651 181407 90630 181408 90651 181408 88363 181408 88363 181409 90651 181409 90632 181409 88363 181410 90632 181410 90631 181410 90631 181411 90632 181411 90652 181411 90631 181412 90652 181412 90634 181412 90634 181413 90652 181413 90633 181413 90634 181414 90633 181414 88354 181414 88354 181415 90633 181415 90654 181415 88354 181416 90654 181416 90636 181416 90636 181417 90654 181417 90635 181417 90636 181418 90635 181418 88438 181418 88438 181419 90635 181419 90637 181419 88438 181420 90637 181420 88439 181420 88439 181421 90637 181421 90672 181421 88439 181422 90672 181422 88355 181422 90638 181423 90639 181423 90640 181423 90640 181424 90639 181424 90655 181424 90640 181425 90655 181425 90641 181425 90641 181426 90655 181426 90656 181426 90641 181427 90656 181427 90621 181427 90621 181428 90656 181428 90642 181428 90621 181429 90642 181429 90643 181429 90643 181430 90642 181430 90644 181430 90643 181431 90644 181431 90624 181431 90624 181432 90644 181432 90659 181432 90624 181433 90659 181433 90626 181433 90626 181434 90659 181434 90645 181434 90626 181435 90645 181435 90646 181435 90646 181436 90645 181436 90647 181436 90646 181437 90647 181437 90628 181437 90628 181438 90647 181438 90648 181438 90628 181439 90648 181439 90629 181439 90629 181440 90648 181440 90649 181440 90629 181441 90649 181441 90650 181441 90650 181442 90649 181442 90661 181442 90650 181443 90661 181443 90651 181443 90651 181444 90661 181444 90662 181444 90651 181445 90662 181445 90632 181445 90632 181446 90662 181446 90664 181446 90632 181447 90664 181447 90652 181447 90652 181448 90664 181448 90665 181448 90652 181449 90665 181449 90633 181449 90633 181450 90665 181450 90653 181450 90633 181451 90653 181451 90654 181451 90654 181452 90653 181452 90667 181452 90654 181453 90667 181453 90635 181453 90635 181454 90667 181454 90668 181454 90635 181455 90668 181455 90637 181455 90637 181456 90668 181456 90670 181456 90637 181457 90670 181457 90672 181457 90672 181458 90670 181458 90673 181458 90639 181459 90675 181459 90655 181459 90655 181460 90675 181460 90618 181460 90655 181461 90618 181461 90656 181461 90656 181462 90618 181462 90657 181462 90656 181463 90657 181463 90642 181463 90642 181464 90657 181464 90617 181464 90642 181465 90617 181465 90644 181465 90644 181466 90617 181466 90658 181466 90644 181467 90658 181467 90659 181467 90659 181468 90658 181468 90611 181468 90659 181469 90611 181469 90645 181469 90645 181470 90611 181470 90614 181470 90645 181471 90614 181471 90647 181471 90647 181472 90614 181472 90660 181472 90647 181473 90660 181473 90648 181473 90648 181474 90660 181474 90609 181474 90648 181475 90609 181475 90649 181475 90649 181476 90609 181476 90608 181476 90649 181477 90608 181477 90661 181477 90661 181478 90608 181478 90606 181478 90661 181479 90606 181479 90662 181479 90662 181480 90606 181480 90663 181480 90662 181481 90663 181481 90664 181481 90664 181482 90663 181482 90604 181482 90664 181483 90604 181483 90665 181483 90665 181484 90604 181484 90666 181484 90665 181485 90666 181485 90653 181485 90653 181486 90666 181486 90602 181486 90653 181487 90602 181487 90667 181487 90667 181488 90602 181488 90600 181488 90667 181489 90600 181489 90668 181489 90668 181490 90600 181490 90669 181490 90668 181491 90669 181491 90670 181491 90670 181492 90669 181492 90671 181492 90670 181493 90671 181493 90673 181493 90673 181494 90671 181494 90674 181494 88355 181495 90672 181495 90638 181495 90638 181496 90672 181496 90673 181496 90638 181497 90673 181497 90639 181497 90639 181498 90673 181498 90674 181498 90639 181499 90674 181499 90675 181499 90675 181500 90674 181500 90480 181500 90675 181501 90480 181501 90618 181501 90618 181502 90480 181502 90478 181502 90618 181503 90478 181503 90676 181503 90677 181504 90752 181504 90678 181504 90685 181505 90677 181505 90679 181505 90692 181506 90685 181506 90693 181506 90749 181507 90692 181507 90694 181507 90706 181508 90749 181508 90697 181508 90747 181509 90706 181509 90707 181509 90677 181510 90678 181510 90679 181510 90679 181511 90678 181511 90680 181511 90679 181512 90680 181512 90687 181512 90687 181513 90680 181513 90681 181513 90687 181514 90681 181514 90688 181514 90688 181515 90681 181515 88318 181515 90688 181516 88318 181516 90682 181516 90682 181517 88318 181517 88317 181517 90682 181518 88317 181518 90683 181518 90683 181519 88317 181519 88314 181519 90683 181520 88314 181520 90684 181520 90684 181521 88314 181521 88312 181521 90684 181522 88312 181522 90723 181522 90685 181523 90679 181523 90693 181523 90693 181524 90679 181524 90687 181524 90693 181525 90687 181525 90686 181525 90686 181526 90687 181526 90688 181526 90686 181527 90688 181527 90689 181527 90689 181528 90688 181528 90682 181528 90689 181529 90682 181529 90690 181529 90690 181530 90682 181530 90683 181530 90690 181531 90683 181531 90691 181531 90691 181532 90683 181532 90684 181532 90691 181533 90684 181533 90696 181533 90696 181534 90684 181534 90723 181534 90696 181535 90723 181535 90726 181535 90692 181536 90693 181536 90694 181536 90694 181537 90693 181537 90686 181537 90694 181538 90686 181538 90698 181538 90698 181539 90686 181539 90689 181539 90698 181540 90689 181540 90700 181540 90700 181541 90689 181541 90690 181541 90700 181542 90690 181542 90695 181542 90695 181543 90690 181543 90691 181543 90695 181544 90691 181544 90702 181544 90702 181545 90691 181545 90696 181545 90702 181546 90696 181546 90703 181546 90703 181547 90696 181547 90726 181547 90703 181548 90726 181548 90705 181548 90749 181549 90694 181549 90697 181549 90697 181550 90694 181550 90698 181550 90697 181551 90698 181551 90699 181551 90699 181552 90698 181552 90700 181552 90699 181553 90700 181553 90708 181553 90708 181554 90700 181554 90695 181554 90708 181555 90695 181555 90701 181555 90701 181556 90695 181556 90702 181556 90701 181557 90702 181557 90711 181557 90711 181558 90702 181558 90703 181558 90711 181559 90703 181559 90704 181559 90704 181560 90703 181560 90705 181560 90704 181561 90705 181561 90733 181561 90706 181562 90697 181562 90707 181562 90707 181563 90697 181563 90699 181563 90707 181564 90699 181564 90709 181564 90709 181565 90699 181565 90708 181565 90709 181566 90708 181566 90714 181566 90714 181567 90708 181567 90701 181567 90714 181568 90701 181568 90710 181568 90710 181569 90701 181569 90711 181569 90710 181570 90711 181570 90712 181570 90712 181571 90711 181571 90704 181571 90712 181572 90704 181572 90713 181572 90713 181573 90704 181573 90733 181573 90713 181574 90733 181574 90718 181574 90747 181575 90707 181575 89273 181575 89273 181576 90707 181576 90709 181576 89273 181577 90709 181577 89270 181577 89270 181578 90709 181578 90714 181578 89270 181579 90714 181579 90715 181579 90715 181580 90714 181580 90710 181580 90715 181581 90710 181581 90716 181581 90716 181582 90710 181582 90712 181582 90716 181583 90712 181583 89266 181583 89266 181584 90712 181584 90713 181584 89266 181585 90713 181585 90717 181585 90717 181586 90713 181586 90718 181586 90717 181587 90718 181587 89274 181587 90718 181588 90733 181588 90737 181588 90726 181589 90723 181589 90722 181589 90727 181590 90705 181590 90726 181590 90705 181591 90727 181591 90733 181591 89276 181592 89274 181592 90718 181592 90719 181593 90725 181593 90720 181593 90720 181594 90725 181594 90728 181594 90720 181595 90728 181595 88310 181595 88310 181596 90728 181596 90722 181596 88310 181597 90722 181597 90721 181597 90721 181598 90722 181598 90723 181598 90721 181599 90723 181599 88312 181599 88307 181600 90730 181600 90719 181600 90719 181601 90730 181601 90724 181601 90719 181602 90724 181602 90725 181602 88307 181603 88306 181603 90730 181603 90730 181604 88306 181604 88305 181604 90730 181605 88305 181605 90732 181605 90726 181606 90722 181606 90727 181606 90727 181607 90722 181607 90728 181607 90727 181608 90728 181608 90734 181608 90734 181609 90728 181609 90725 181609 90734 181610 90725 181610 90736 181610 90736 181611 90725 181611 90724 181611 90736 181612 90724 181612 90729 181612 90729 181613 90724 181613 90730 181613 90729 181614 90730 181614 90731 181614 90731 181615 90730 181615 90732 181615 90731 181616 90732 181616 90754 181616 90733 181617 90727 181617 90737 181617 90737 181618 90727 181618 90734 181618 90737 181619 90734 181619 90735 181619 90735 181620 90734 181620 90736 181620 90735 181621 90736 181621 90738 181621 90738 181622 90736 181622 90729 181622 90738 181623 90729 181623 90739 181623 90739 181624 90729 181624 90731 181624 90739 181625 90731 181625 90741 181625 90741 181626 90731 181626 90754 181626 90741 181627 90754 181627 90755 181627 90718 181628 90737 181628 89276 181628 89276 181629 90737 181629 90735 181629 89276 181630 90735 181630 89277 181630 89277 181631 90735 181631 90738 181631 89277 181632 90738 181632 89278 181632 89278 181633 90738 181633 90739 181633 89278 181634 90739 181634 90740 181634 90740 181635 90739 181635 90741 181635 90740 181636 90741 181636 90742 181636 90742 181637 90741 181637 90755 181637 90742 181638 90755 181638 90756 181638 89256 181639 90849 181639 90748 181639 90748 181640 90849 181640 90832 181640 90748 181641 90832 181641 90743 181641 90743 181642 90832 181642 90834 181642 90743 181643 90834 181643 90744 181643 90744 181644 90834 181644 90835 181644 90744 181645 90835 181645 90750 181645 90750 181646 90835 181646 90745 181646 90750 181647 90745 181647 90751 181647 90751 181648 90745 181648 90746 181648 90751 181649 90746 181649 90753 181649 90753 181650 90746 181650 88319 181650 90747 181651 89256 181651 90706 181651 90706 181652 89256 181652 90748 181652 90706 181653 90748 181653 90749 181653 90749 181654 90748 181654 90743 181654 90749 181655 90743 181655 90692 181655 90692 181656 90743 181656 90744 181656 90692 181657 90744 181657 90685 181657 90685 181658 90744 181658 90750 181658 90685 181659 90750 181659 90677 181659 90677 181660 90750 181660 90751 181660 90677 181661 90751 181661 90752 181661 90752 181662 90751 181662 90753 181662 90754 181663 90732 181663 90763 181663 90755 181664 90754 181664 90781 181664 90756 181665 90755 181665 90758 181665 90756 181666 90758 181666 90757 181666 90757 181667 90758 181667 90783 181667 90757 181668 90783 181668 90759 181668 90759 181669 90783 181669 89285 181669 89285 181670 90783 181670 90760 181670 89285 181671 90760 181671 89286 181671 89286 181672 90760 181672 90785 181672 89286 181673 90785 181673 90761 181673 90761 181674 90785 181674 90787 181674 90761 181675 90787 181675 90762 181675 90762 181676 90787 181676 90789 181676 90762 181677 90789 181677 89283 181677 90754 181678 90763 181678 90781 181678 90781 181679 90763 181679 90774 181679 90781 181680 90774 181680 90782 181680 90782 181681 90774 181681 90764 181681 90782 181682 90764 181682 90765 181682 90765 181683 90764 181683 90766 181683 90765 181684 90766 181684 90784 181684 90784 181685 90766 181685 90767 181685 90784 181686 90767 181686 90786 181686 90786 181687 90767 181687 90770 181687 90786 181688 90770 181688 90788 181688 90788 181689 90770 181689 90769 181689 90788 181690 90769 181690 90790 181690 90790 181691 90769 181691 90778 181691 90790 181692 90778 181692 90791 181692 90854 181693 90778 181693 90768 181693 90768 181694 90778 181694 90769 181694 90768 181695 90769 181695 88302 181695 88302 181696 90769 181696 90770 181696 88302 181697 90770 181697 90771 181697 90771 181698 90770 181698 90767 181698 90771 181699 90767 181699 90772 181699 90772 181700 90767 181700 90766 181700 90772 181701 90766 181701 90773 181701 90773 181702 90766 181702 90764 181702 90773 181703 90764 181703 90775 181703 90775 181704 90764 181704 90774 181704 90775 181705 90774 181705 88303 181705 88303 181706 90774 181706 90763 181706 88303 181707 90763 181707 90776 181707 90776 181708 90763 181708 90732 181708 90776 181709 90732 181709 88305 181709 90854 181710 90777 181710 90778 181710 90778 181711 90777 181711 90779 181711 90778 181712 90779 181712 90791 181712 90791 181713 90779 181713 90780 181713 90791 181714 90780 181714 90792 181714 90755 181715 90781 181715 90758 181715 90758 181716 90781 181716 90782 181716 90758 181717 90782 181717 90783 181717 90783 181718 90782 181718 90765 181718 90783 181719 90765 181719 90760 181719 90760 181720 90765 181720 90784 181720 90760 181721 90784 181721 90785 181721 90785 181722 90784 181722 90786 181722 90785 181723 90786 181723 90787 181723 90787 181724 90786 181724 90788 181724 90787 181725 90788 181725 90789 181725 90789 181726 90788 181726 90790 181726 90789 181727 90790 181727 90794 181727 90794 181728 90790 181728 90791 181728 90794 181729 90791 181729 90796 181729 90796 181730 90791 181730 90792 181730 90796 181731 90792 181731 90793 181731 89283 181732 90789 181732 89280 181732 89280 181733 90789 181733 90794 181733 89280 181734 90794 181734 90795 181734 90795 181735 90794 181735 90796 181735 90795 181736 90796 181736 90797 181736 90797 181737 90796 181737 90793 181737 90797 181738 90793 181738 89289 181738 90798 181739 90799 181739 90800 181739 90800 181740 90799 181740 90880 181740 90800 181741 90880 181741 90801 181741 90801 181742 90880 181742 90802 181742 90801 181743 90802 181743 90804 181743 90804 181744 90802 181744 90803 181744 90804 181745 90803 181745 90809 181745 90809 181746 90803 181746 90872 181746 90809 181747 90872 181747 90805 181747 90805 181748 90872 181748 90871 181748 90805 181749 90871 181749 90806 181749 90806 181750 90871 181750 90870 181750 90806 181751 90807 181751 90805 181751 90805 181752 90807 181752 90808 181752 90805 181753 90808 181753 90809 181753 90809 181754 90808 181754 90810 181754 90809 181755 90810 181755 90804 181755 90804 181756 90810 181756 90826 181756 90804 181757 90826 181757 90801 181757 90801 181758 90826 181758 90811 181758 90801 181759 90811 181759 90800 181759 90800 181760 90811 181760 90812 181760 90800 181761 90812 181761 90798 181761 90829 181762 90813 181762 90812 181762 90812 181763 90813 181763 90814 181763 90812 181764 90814 181764 90798 181764 90824 181765 88321 181765 90825 181765 90825 181766 88321 181766 90819 181766 90825 181767 90819 181767 90815 181767 90815 181768 90819 181768 90816 181768 90815 181769 90816 181769 90827 181769 90827 181770 90816 181770 90817 181770 90827 181771 90817 181771 90818 181771 90818 181772 90817 181772 90821 181772 90818 181773 90821 181773 90828 181773 90828 181774 90821 181774 90823 181774 88321 181775 90839 181775 90819 181775 90819 181776 90839 181776 90840 181776 90819 181777 90840 181777 90816 181777 90816 181778 90840 181778 90841 181778 90816 181779 90841 181779 90817 181779 90817 181780 90841 181780 90820 181780 90817 181781 90820 181781 90821 181781 90821 181782 90820 181782 90822 181782 90821 181783 90822 181783 90823 181783 90823 181784 90822 181784 90845 181784 90807 181785 90824 181785 90808 181785 90808 181786 90824 181786 90825 181786 90808 181787 90825 181787 90810 181787 90810 181788 90825 181788 90815 181788 90810 181789 90815 181789 90826 181789 90826 181790 90815 181790 90827 181790 90826 181791 90827 181791 90811 181791 90811 181792 90827 181792 90818 181792 90811 181793 90818 181793 90812 181793 90812 181794 90818 181794 90828 181794 90812 181795 90828 181795 90829 181795 90829 181796 90828 181796 90823 181796 90829 181797 90823 181797 89262 181797 89262 181798 90823 181798 90845 181798 90847 181799 89260 181799 90845 181799 90845 181800 89260 181800 89261 181800 90845 181801 89261 181801 89262 181801 88320 181802 90830 181802 90842 181802 90842 181803 90830 181803 90838 181803 90842 181804 90838 181804 90843 181804 90843 181805 90838 181805 90837 181805 90843 181806 90837 181806 90844 181806 90844 181807 90837 181807 90836 181807 90844 181808 90836 181808 90846 181808 90846 181809 90836 181809 90833 181809 90846 181810 90833 181810 90831 181810 90831 181811 90833 181811 90848 181811 90832 181812 90848 181812 90834 181812 90834 181813 90848 181813 90833 181813 90834 181814 90833 181814 90835 181814 90835 181815 90833 181815 90836 181815 90835 181816 90836 181816 90745 181816 90745 181817 90836 181817 90837 181817 90745 181818 90837 181818 90746 181818 90746 181819 90837 181819 90838 181819 90746 181820 90838 181820 88319 181820 88319 181821 90838 181821 90830 181821 90839 181822 88320 181822 90840 181822 90840 181823 88320 181823 90842 181823 90840 181824 90842 181824 90841 181824 90841 181825 90842 181825 90843 181825 90841 181826 90843 181826 90820 181826 90820 181827 90843 181827 90844 181827 90820 181828 90844 181828 90822 181828 90822 181829 90844 181829 90846 181829 90822 181830 90846 181830 90845 181830 90845 181831 90846 181831 90831 181831 90845 181832 90831 181832 90847 181832 90847 181833 90831 181833 90848 181833 90847 181834 90848 181834 89259 181834 89259 181835 90848 181835 90832 181835 89259 181836 90832 181836 90849 181836 90850 181837 90779 181837 90777 181837 90779 181838 90850 181838 90780 181838 90780 181839 90850 181839 90851 181839 90780 181840 90851 181840 90792 181840 90792 181841 90851 181841 90793 181841 90793 181842 90851 181842 90855 181842 90793 181843 90855 181843 89289 181843 90852 181844 90850 181844 90853 181844 90853 181845 90850 181845 90777 181845 90853 181846 90777 181846 90854 181846 90885 181847 90855 181847 90856 181847 90856 181848 90855 181848 90851 181848 90856 181849 90851 181849 90884 181849 90884 181850 90851 181850 90850 181850 90884 181851 90850 181851 90881 181851 90881 181852 90850 181852 90852 181852 90906 181853 90892 181853 88399 181853 90912 181854 90906 181854 90857 181854 90913 181855 90912 181855 90865 181855 90920 181856 90913 181856 90878 181856 90906 181857 88399 181857 90857 181857 90857 181858 88399 181858 90858 181858 90857 181859 90858 181859 90859 181859 90858 181860 88400 181860 90859 181860 90859 181861 88400 181861 90861 181861 90859 181862 90861 181862 90860 181862 90860 181863 90861 181863 90864 181863 90860 181864 90864 181864 90862 181864 90862 181865 90864 181865 90863 181865 90863 181866 90864 181866 88402 181866 90863 181867 88402 181867 90869 181867 90912 181868 90857 181868 90865 181868 90865 181869 90857 181869 90859 181869 90865 181870 90859 181870 90866 181870 90866 181871 90859 181871 90860 181871 90866 181872 90860 181872 90867 181872 90867 181873 90860 181873 90862 181873 90867 181874 90862 181874 90868 181874 90868 181875 90862 181875 90863 181875 90868 181876 90863 181876 90873 181876 90869 181877 90870 181877 90871 181877 90869 181878 90871 181878 90863 181878 90863 181879 90871 181879 90872 181879 90863 181880 90872 181880 90873 181880 90873 181881 90872 181881 90803 181881 90873 181882 90803 181882 90802 181882 90913 181883 90865 181883 90878 181883 90878 181884 90865 181884 90866 181884 90878 181885 90866 181885 90874 181885 90874 181886 90866 181886 90867 181886 90874 181887 90867 181887 90879 181887 90879 181888 90867 181888 90868 181888 90879 181889 90868 181889 90875 181889 90875 181890 90868 181890 90873 181890 90875 181891 90873 181891 90876 181891 90876 181892 90873 181892 90802 181892 90876 181893 90802 181893 90880 181893 90920 181894 90878 181894 90877 181894 90877 181895 90878 181895 90874 181895 90877 181896 90874 181896 89300 181896 89300 181897 90874 181897 90879 181897 89300 181898 90879 181898 89301 181898 89301 181899 90879 181899 90875 181899 89301 181900 90875 181900 89303 181900 89303 181901 90875 181901 90876 181901 89303 181902 90876 181902 89304 181902 89304 181903 90876 181903 90880 181903 89304 181904 90880 181904 90799 181904 90881 181905 90852 181905 90882 181905 90884 181906 90881 181906 90883 181906 90856 181907 90884 181907 90893 181907 90885 181908 90856 181908 90907 181908 90885 181909 90907 181909 90886 181909 90886 181910 90907 181910 90914 181910 90886 181911 90914 181911 89295 181911 90881 181912 90882 181912 90883 181912 90883 181913 90882 181913 90887 181913 90883 181914 90887 181914 90894 181914 90894 181915 90887 181915 90888 181915 90894 181916 90888 181916 90889 181916 90889 181917 90888 181917 90890 181917 90889 181918 90890 181918 90897 181918 90897 181919 90890 181919 88397 181919 90897 181920 88397 181920 90898 181920 90898 181921 88397 181921 88396 181921 90898 181922 88396 181922 90900 181922 90900 181923 88396 181923 90891 181923 90900 181924 90891 181924 90902 181924 90902 181925 90891 181925 88398 181925 90902 181926 88398 181926 90904 181926 90904 181927 88398 181927 90892 181927 90904 181928 90892 181928 90906 181928 90884 181929 90883 181929 90893 181929 90893 181930 90883 181930 90894 181930 90893 181931 90894 181931 90895 181931 90895 181932 90894 181932 90889 181932 90895 181933 90889 181933 90896 181933 90896 181934 90889 181934 90897 181934 90896 181935 90897 181935 90908 181935 90908 181936 90897 181936 90898 181936 90908 181937 90898 181937 90899 181937 90899 181938 90898 181938 90900 181938 90899 181939 90900 181939 90901 181939 90901 181940 90900 181940 90902 181940 90901 181941 90902 181941 90903 181941 90903 181942 90902 181942 90904 181942 90903 181943 90904 181943 90905 181943 90905 181944 90904 181944 90906 181944 90905 181945 90906 181945 90912 181945 90856 181946 90893 181946 90907 181946 90907 181947 90893 181947 90895 181947 90907 181948 90895 181948 90914 181948 90914 181949 90895 181949 90896 181949 90914 181950 90896 181950 90909 181950 90909 181951 90896 181951 90908 181951 90909 181952 90908 181952 90915 181952 90915 181953 90908 181953 90899 181953 90915 181954 90899 181954 90916 181954 90916 181955 90899 181955 90901 181955 90916 181956 90901 181956 90910 181956 90910 181957 90901 181957 90903 181957 90910 181958 90903 181958 90911 181958 90911 181959 90903 181959 90905 181959 90911 181960 90905 181960 90919 181960 90919 181961 90905 181961 90912 181961 90919 181962 90912 181962 90913 181962 89295 181963 90914 181963 89296 181963 89296 181964 90914 181964 90909 181964 89296 181965 90909 181965 89297 181965 89297 181966 90909 181966 90915 181966 89297 181967 90915 181967 89294 181967 89294 181968 90915 181968 90916 181968 89294 181969 90916 181969 90917 181969 90917 181970 90916 181970 90910 181970 90917 181971 90910 181971 89291 181971 89291 181972 90910 181972 90911 181972 89291 181973 90911 181973 90918 181973 90918 181974 90911 181974 90919 181974 90918 181975 90919 181975 89293 181975 89293 181976 90919 181976 90913 181976 89293 181977 90913 181977 90920 181977 90925 181978 90935 181978 90921 181978 90924 181979 90922 181979 90923 181979 90922 181980 88297 181980 88296 181980 90924 181981 90923 181981 90935 181981 90925 181982 90921 181982 90928 181982 90948 181983 90926 181983 90927 181983 90927 181984 90926 181984 89163 181984 90927 181985 89163 181985 90928 181985 90922 181986 88296 181986 90923 181986 90923 181987 88296 181987 88295 181987 90923 181988 88295 181988 90929 181988 90929 181989 88295 181989 90930 181989 90929 181990 90930 181990 90936 181990 90936 181991 90930 181991 90931 181991 90936 181992 90931 181992 90932 181992 90932 181993 90931 181993 88294 181993 90932 181994 88294 181994 90938 181994 90938 181995 88294 181995 90933 181995 90938 181996 90933 181996 90934 181996 90935 181997 90923 181997 90921 181997 90921 181998 90923 181998 90929 181998 90921 181999 90929 181999 90939 181999 90939 182000 90929 182000 90936 182000 90939 182001 90936 182001 90937 182001 90937 182002 90936 182002 90932 182002 90937 182003 90932 182003 90940 182003 90940 182004 90932 182004 90938 182004 90940 182005 90938 182005 90942 182005 90942 182006 90938 182006 90934 182006 90942 182007 90934 182007 90951 182007 90928 182008 90921 182008 90927 182008 90927 182009 90921 182009 90939 182009 90927 182010 90939 182010 90948 182010 90948 182011 90939 182011 90937 182011 90948 182012 90937 182012 90947 182012 90947 182013 90937 182013 90940 182013 90947 182014 90940 182014 90945 182014 90945 182015 90940 182015 90942 182015 90945 182016 90942 182016 90941 182016 90941 182017 90942 182017 90951 182017 90941 182018 90951 182018 90952 182018 89166 182019 90943 182019 90952 182019 90952 182020 90943 182020 90944 182020 90952 182021 90944 182021 90941 182021 90941 182022 90944 182022 90946 182022 90941 182023 90946 182023 90945 182023 90945 182024 90946 182024 89171 182024 90945 182025 89171 182025 90947 182025 90947 182026 89171 182026 89170 182026 90947 182027 89170 182027 90948 182027 90948 182028 89170 182028 89169 182028 90948 182029 89169 182029 90926 182029 90933 182030 90949 182030 90934 182030 90934 182031 90949 182031 90950 182031 90934 182032 90950 182032 90951 182032 90951 182033 90950 182033 90953 182033 90951 182034 90953 182034 90952 182034 90952 182035 90953 182035 90956 182035 90952 182036 90956 182036 89166 182036 89166 182037 90956 182037 90954 182037 90957 182038 90954 182038 90955 182038 90955 182039 90954 182039 90956 182039 90955 182040 90956 182040 90958 182040 90958 182041 90956 182041 90953 182041 90958 182042 90953 182042 90959 182042 90959 182043 90953 182043 90950 182043 90959 182044 90950 182044 88290 182044 88290 182045 90950 182045 90949 182045 89164 182046 90957 182046 90972 182046 90972 182047 90957 182047 90955 182047 90972 182048 90955 182048 90965 182048 90965 182049 90955 182049 90958 182049 90965 182050 90958 182050 90960 182050 90960 182051 90958 182051 90959 182051 90960 182052 90959 182052 88289 182052 88289 182053 90959 182053 88290 182053 90960 182054 88289 182054 88287 182054 90965 182055 90960 182055 90961 182055 90972 182056 90965 182056 90966 182056 89164 182057 90972 182057 90973 182057 90960 182058 88287 182058 90961 182058 90961 182059 88287 182059 88286 182059 90961 182060 88286 182060 90967 182060 88286 182061 88282 182061 90967 182061 90967 182062 88282 182062 88281 182062 90967 182063 88281 182063 90962 182063 90962 182064 88281 182064 90963 182064 90962 182065 90963 182065 90969 182065 90963 182066 90964 182066 90969 182066 90969 182067 90964 182067 88279 182067 90969 182068 88279 182068 90970 182068 90970 182069 88279 182069 88277 182069 90970 182070 88277 182070 90993 182070 90965 182071 90961 182071 90966 182071 90966 182072 90961 182072 90967 182072 90966 182073 90967 182073 90974 182073 90974 182074 90967 182074 90962 182074 90974 182075 90962 182075 90976 182075 90976 182076 90962 182076 90969 182076 90976 182077 90969 182077 90968 182077 90968 182078 90969 182078 90970 182078 90968 182079 90970 182079 90971 182079 90971 182080 90970 182080 90993 182080 90971 182081 90993 182081 90994 182081 90972 182082 90966 182082 90973 182082 90973 182083 90966 182083 90974 182083 90973 182084 90974 182084 90975 182084 90975 182085 90974 182085 90976 182085 90975 182086 90976 182086 90977 182086 90977 182087 90976 182087 90968 182087 90977 182088 90968 182088 90981 182088 90981 182089 90968 182089 90971 182089 90981 182090 90971 182090 90978 182090 90978 182091 90971 182091 90994 182091 90978 182092 90994 182092 90983 182092 89164 182093 90973 182093 90979 182093 90979 182094 90973 182094 90975 182094 90979 182095 90975 182095 89177 182095 89177 182096 90975 182096 90977 182096 89177 182097 90977 182097 90980 182097 90980 182098 90977 182098 90981 182098 90980 182099 90981 182099 90982 182099 90982 182100 90981 182100 90978 182100 90982 182101 90978 182101 89173 182101 89173 182102 90978 182102 90983 182102 89173 182103 90983 182103 89172 182103 90922 182104 90924 182104 90988 182104 90984 182105 90985 182105 88298 182105 90991 182106 90989 182106 91075 182106 91075 182107 90989 182107 90986 182107 91075 182108 90986 182108 90987 182108 88297 182109 90922 182109 88298 182109 88298 182110 90922 182110 90988 182110 88298 182111 90988 182111 90984 182111 90984 182112 90988 182112 90990 182112 90924 182113 90935 182113 90988 182113 90988 182114 90935 182114 90989 182114 90988 182115 90989 182115 90990 182115 90990 182116 90989 182116 90991 182116 89163 182117 90986 182117 90928 182117 90928 182118 90986 182118 90989 182118 90928 182119 90989 182119 90925 182119 90925 182120 90989 182120 90935 182120 90992 182121 89192 182121 91023 182121 90993 182122 88277 182122 91003 182122 91003 182123 91002 182123 90993 182123 90993 182124 91002 182124 91001 182124 90993 182125 91001 182125 90994 182125 90994 182126 91001 182126 91000 182126 90994 182127 91000 182127 90983 182127 89187 182128 89172 182128 90995 182128 90995 182129 89172 182129 90983 182129 90995 182130 90983 182130 90997 182130 90997 182131 90983 182131 91000 182131 89189 182132 89187 182132 90996 182132 90996 182133 89187 182133 90995 182133 90996 182134 90995 182134 91004 182134 91004 182135 90995 182135 90997 182135 91004 182136 90997 182136 90998 182136 90998 182137 90997 182137 91000 182137 90998 182138 91000 182138 90999 182138 90999 182139 91000 182139 91001 182139 90999 182140 91001 182140 91006 182140 91006 182141 91001 182141 91002 182141 91006 182142 91002 182142 88275 182142 88275 182143 91002 182143 91003 182143 91009 182144 89189 182144 91010 182144 91010 182145 89189 182145 90996 182145 91010 182146 90996 182146 91011 182146 91011 182147 90996 182147 91004 182147 91011 182148 91004 182148 91005 182148 91005 182149 91004 182149 90998 182149 91005 182150 90998 182150 91012 182150 91012 182151 90998 182151 90999 182151 91012 182152 90999 182152 91013 182152 91013 182153 90999 182153 91006 182153 91013 182154 91006 182154 91007 182154 91007 182155 91006 182155 88275 182155 89191 182156 91009 182156 91008 182156 91008 182157 91009 182157 91010 182157 91008 182158 91010 182158 91015 182158 91015 182159 91010 182159 91011 182159 91015 182160 91011 182160 91016 182160 91016 182161 91011 182161 91005 182161 91016 182162 91005 182162 91019 182162 91019 182163 91005 182163 91012 182163 91019 182164 91012 182164 91020 182164 91020 182165 91012 182165 91013 182165 91020 182166 91013 182166 91021 182166 91021 182167 91013 182167 91007 182167 89192 182168 89191 182168 91023 182168 91023 182169 89191 182169 91008 182169 91023 182170 91008 182170 91014 182170 91014 182171 91008 182171 91015 182171 91014 182172 91015 182172 91017 182172 91017 182173 91015 182173 91016 182173 91017 182174 91016 182174 91018 182174 91018 182175 91016 182175 91019 182175 91018 182176 91019 182176 91027 182176 91027 182177 91019 182177 91020 182177 91027 182178 91020 182178 88273 182178 88273 182179 91020 182179 91021 182179 89193 182180 90992 182180 91022 182180 91022 182181 90992 182181 91023 182181 91022 182182 91023 182182 91024 182182 91024 182183 91023 182183 91014 182183 91024 182184 91014 182184 91031 182184 91031 182185 91014 182185 91017 182185 91031 182186 91017 182186 91025 182186 91025 182187 91017 182187 91018 182187 91025 182188 91018 182188 91026 182188 91026 182189 91018 182189 91027 182189 91026 182190 91027 182190 91033 182190 91033 182191 91027 182191 88273 182191 91028 182192 89193 182192 91029 182192 91029 182193 89193 182193 91022 182193 91029 182194 91022 182194 91035 182194 91035 182195 91022 182195 91024 182195 91035 182196 91024 182196 91030 182196 91030 182197 91024 182197 91031 182197 91030 182198 91031 182198 91032 182198 91032 182199 91031 182199 91025 182199 91032 182200 91025 182200 91038 182200 91038 182201 91025 182201 91026 182201 91038 182202 91026 182202 91039 182202 91039 182203 91026 182203 91033 182203 89196 182204 91028 182204 91034 182204 91034 182205 91028 182205 91029 182205 91034 182206 91029 182206 91036 182206 91036 182207 91029 182207 91035 182207 91036 182208 91035 182208 91079 182208 91079 182209 91035 182209 91030 182209 91079 182210 91030 182210 91037 182210 91037 182211 91030 182211 91032 182211 91037 182212 91032 182212 91082 182212 91082 182213 91032 182213 91038 182213 91082 182214 91038 182214 88271 182214 88271 182215 91038 182215 91039 182215 91044 182216 91100 182216 91040 182216 91111 182217 91044 182217 91045 182217 91116 182218 91111 182218 91054 182218 91041 182219 91116 182219 91061 182219 91041 182220 91061 182220 89157 182220 89157 182221 91061 182221 91042 182221 89157 182222 91042 182222 91043 182222 91044 182223 91040 182223 91045 182223 91045 182224 91040 182224 91046 182224 91045 182225 91046 182225 91053 182225 91053 182226 91046 182226 91047 182226 91053 182227 91047 182227 91056 182227 91056 182228 91047 182228 88386 182228 91056 182229 88386 182229 91049 182229 91049 182230 88386 182230 91048 182230 91049 182231 91048 182231 91057 182231 91057 182232 91048 182232 91050 182232 91057 182233 91050 182233 91059 182233 91059 182234 91050 182234 88300 182234 91059 182235 88300 182235 91051 182235 91051 182236 88300 182236 88299 182236 91051 182237 88299 182237 91052 182237 91111 182238 91045 182238 91054 182238 91054 182239 91045 182239 91053 182239 91054 182240 91053 182240 91055 182240 91055 182241 91053 182241 91056 182241 91055 182242 91056 182242 91062 182242 91062 182243 91056 182243 91049 182243 91062 182244 91049 182244 91058 182244 91058 182245 91049 182245 91057 182245 91058 182246 91057 182246 91064 182246 91064 182247 91057 182247 91059 182247 91064 182248 91059 182248 91065 182248 91065 182249 91059 182249 91051 182249 91065 182250 91051 182250 91066 182250 91066 182251 91051 182251 91052 182251 91066 182252 91052 182252 91060 182252 88299 182253 90985 182253 91052 182253 91052 182254 90985 182254 90984 182254 91052 182255 90984 182255 91060 182255 91060 182256 90984 182256 90990 182256 91060 182257 90990 182257 90991 182257 91116 182258 91054 182258 91061 182258 91061 182259 91054 182259 91055 182259 91061 182260 91055 182260 91042 182260 91042 182261 91055 182261 91062 182261 91042 182262 91062 182262 91063 182262 91063 182263 91062 182263 91058 182263 91063 182264 91058 182264 91067 182264 91067 182265 91058 182265 91064 182265 91067 182266 91064 182266 91069 182266 91069 182267 91064 182267 91065 182267 91069 182268 91065 182268 91071 182268 91071 182269 91065 182269 91066 182269 91071 182270 91066 182270 91072 182270 91072 182271 91066 182271 91060 182271 91072 182272 91060 182272 91073 182272 91073 182273 91060 182273 90991 182273 91073 182274 90991 182274 91075 182274 91043 182275 91042 182275 89159 182275 89159 182276 91042 182276 91063 182276 89159 182277 91063 182277 91068 182277 91068 182278 91063 182278 91067 182278 91068 182279 91067 182279 89155 182279 89155 182280 91067 182280 91069 182280 89155 182281 91069 182281 91070 182281 91070 182282 91069 182282 91071 182282 91070 182283 91071 182283 89153 182283 89153 182284 91071 182284 91072 182284 89153 182285 91072 182285 89154 182285 89154 182286 91072 182286 91073 182286 89154 182287 91073 182287 91074 182287 91074 182288 91073 182288 91075 182288 91074 182289 91075 182289 90987 182289 89195 182290 89196 182290 91076 182290 91076 182291 89196 182291 91034 182291 91076 182292 91034 182292 91077 182292 91077 182293 91034 182293 91036 182293 91077 182294 91036 182294 91078 182294 91078 182295 91036 182295 91079 182295 91078 182296 91079 182296 91080 182296 91080 182297 91079 182297 91037 182297 91080 182298 91037 182298 91081 182298 91081 182299 91037 182299 91082 182299 91081 182300 91082 182300 91083 182300 91083 182301 91082 182301 88271 182301 89194 182302 89195 182302 91084 182302 91084 182303 89195 182303 91076 182303 91084 182304 91076 182304 91085 182304 91085 182305 91076 182305 91077 182305 91085 182306 91077 182306 91086 182306 91086 182307 91077 182307 91078 182307 91086 182308 91078 182308 91154 182308 91154 182309 91078 182309 91080 182309 91154 182310 91080 182310 91087 182310 91087 182311 91080 182311 91081 182311 91087 182312 91081 182312 91088 182312 91088 182313 91081 182313 91083 182313 91100 182314 91044 182314 91098 182314 91090 182315 91144 182315 91112 182315 91146 182316 91089 182316 91102 182316 91144 182317 91146 182317 91101 182317 89148 182318 89179 182318 91090 182318 88392 182319 91102 182319 91091 182319 91091 182320 91102 182320 91089 182320 91091 182321 91089 182321 91092 182321 88393 182322 91094 182322 88392 182322 88392 182323 91094 182323 91104 182323 88392 182324 91104 182324 91102 182324 88393 182325 91093 182325 91094 182325 91094 182326 91093 182326 91095 182326 91094 182327 91095 182327 91096 182327 91096 182328 91095 182328 91097 182328 91096 182329 91097 182329 91098 182329 91098 182330 91097 182330 91099 182330 91098 182331 91099 182331 91100 182331 91146 182332 91102 182332 91101 182332 91101 182333 91102 182333 91104 182333 91101 182334 91104 182334 91103 182334 91103 182335 91104 182335 91094 182335 91103 182336 91094 182336 91108 182336 91108 182337 91094 182337 91096 182337 91108 182338 91096 182338 91105 182338 91105 182339 91096 182339 91098 182339 91105 182340 91098 182340 91106 182340 91106 182341 91098 182341 91044 182341 91106 182342 91044 182342 91111 182342 91144 182343 91101 182343 91112 182343 91112 182344 91101 182344 91103 182344 91112 182345 91103 182345 91107 182345 91107 182346 91103 182346 91108 182346 91107 182347 91108 182347 91114 182347 91114 182348 91108 182348 91105 182348 91114 182349 91105 182349 91109 182349 91109 182350 91105 182350 91106 182350 91109 182351 91106 182351 91110 182351 91110 182352 91106 182352 91111 182352 91110 182353 91111 182353 91116 182353 91090 182354 91112 182354 89148 182354 89148 182355 91112 182355 91107 182355 89148 182356 91107 182356 91113 182356 91113 182357 91107 182357 91114 182357 91113 182358 91114 182358 89149 182358 89149 182359 91114 182359 91109 182359 89149 182360 91109 182360 91115 182360 91115 182361 91109 182361 91110 182361 91115 182362 91110 182362 89151 182362 89151 182363 91110 182363 91116 182363 89151 182364 91116 182364 91041 182364 91087 182365 91088 182365 88270 182365 91086 182366 91154 182366 91117 182366 91085 182367 91086 182367 91119 182367 91084 182368 91085 182368 91124 182368 89194 182369 91084 182369 91133 182369 91086 182370 91117 182370 91119 182370 91119 182371 91117 182371 91118 182371 91119 182372 91118 182372 91120 182372 91120 182373 91118 182373 91152 182373 91120 182374 91152 182374 91121 182374 91121 182375 91152 182375 91150 182375 91121 182376 91150 182376 91125 182376 91125 182377 91150 182377 91149 182377 91125 182378 91149 182378 91122 182378 91122 182379 91149 182379 91123 182379 91122 182380 91123 182380 91147 182380 91085 182381 91119 182381 91124 182381 91124 182382 91119 182382 91120 182382 91124 182383 91120 182383 91126 182383 91126 182384 91120 182384 91121 182384 91126 182385 91121 182385 91128 182385 91128 182386 91121 182386 91125 182386 91128 182387 91125 182387 91129 182387 91129 182388 91125 182388 91122 182388 91129 182389 91122 182389 91130 182389 91130 182390 91122 182390 91147 182390 91130 182391 91147 182391 91145 182391 91084 182392 91124 182392 91133 182392 91133 182393 91124 182393 91126 182393 91133 182394 91126 182394 91127 182394 91127 182395 91126 182395 91128 182395 91127 182396 91128 182396 91135 182396 91135 182397 91128 182397 91129 182397 91135 182398 91129 182398 91136 182398 91136 182399 91129 182399 91130 182399 91136 182400 91130 182400 91131 182400 91131 182401 91130 182401 91145 182401 91131 182402 91145 182402 91132 182402 89194 182403 91133 182403 89183 182403 89183 182404 91133 182404 91127 182404 89183 182405 91127 182405 91134 182405 91134 182406 91127 182406 91135 182406 91134 182407 91135 182407 89182 182407 89182 182408 91135 182408 91136 182408 89182 182409 91136 182409 91137 182409 91137 182410 91136 182410 91131 182410 91137 182411 91131 182411 91138 182411 91138 182412 91131 182412 91132 182412 91138 182413 91132 182413 91139 182413 91087 182414 88270 182414 91155 182414 91155 182415 88270 182415 91141 182415 91155 182416 91141 182416 91140 182416 91140 182417 91141 182417 88391 182417 91140 182418 88391 182418 91153 182418 91153 182419 88391 182419 88390 182419 91153 182420 88390 182420 91142 182420 91142 182421 88390 182421 91143 182421 91142 182422 91143 182422 91151 182422 91151 182423 91143 182423 88389 182423 91151 182424 88389 182424 91148 182424 91148 182425 88389 182425 91092 182425 91148 182426 91092 182426 91089 182426 89179 182427 91139 182427 91090 182427 91090 182428 91139 182428 91132 182428 91090 182429 91132 182429 91144 182429 91144 182430 91132 182430 91145 182430 91144 182431 91145 182431 91146 182431 91146 182432 91145 182432 91147 182432 91146 182433 91147 182433 91089 182433 91089 182434 91147 182434 91123 182434 91089 182435 91123 182435 91148 182435 91148 182436 91123 182436 91149 182436 91148 182437 91149 182437 91151 182437 91151 182438 91149 182438 91150 182438 91151 182439 91150 182439 91142 182439 91142 182440 91150 182440 91152 182440 91142 182441 91152 182441 91153 182441 91153 182442 91152 182442 91118 182442 91153 182443 91118 182443 91140 182443 91140 182444 91118 182444 91117 182444 91140 182445 91117 182445 91155 182445 91155 182446 91117 182446 91154 182446 91155 182447 91154 182447 91087 182447 91225 182448 91221 182448 91171 182448 91220 182449 91156 182449 91162 182449 91156 182450 91157 182450 91161 182450 91220 182451 91162 182451 91221 182451 91225 182452 91171 182452 91224 182452 91223 182453 91224 182453 91158 182453 91223 182454 91158 182454 91159 182454 91159 182455 91158 182455 91160 182455 91159 182456 91160 182456 89245 182456 91156 182457 91161 182457 91162 182457 91162 182458 91161 182458 88236 182458 91162 182459 88236 182459 91172 182459 91172 182460 88236 182460 91163 182460 91172 182461 91163 182461 91164 182461 91164 182462 91163 182462 88234 182462 91164 182463 88234 182463 91166 182463 91166 182464 88234 182464 91165 182464 91166 182465 91165 182465 91167 182465 91167 182466 91165 182466 91168 182466 91167 182467 91168 182467 91169 182467 91169 182468 91168 182468 88377 182468 91169 182469 88377 182469 91176 182469 91176 182470 88377 182470 91170 182470 91176 182471 91170 182471 91178 182471 91178 182472 91170 182472 88378 182472 91178 182473 88378 182473 91190 182473 91221 182474 91162 182474 91171 182474 91171 182475 91162 182475 91172 182475 91171 182476 91172 182476 91173 182476 91173 182477 91172 182477 91164 182477 91173 182478 91164 182478 91174 182478 91174 182479 91164 182479 91166 182479 91174 182480 91166 182480 91180 182480 91180 182481 91166 182481 91167 182481 91180 182482 91167 182482 91181 182482 91181 182483 91167 182483 91169 182483 91181 182484 91169 182484 91175 182484 91175 182485 91169 182485 91176 182485 91175 182486 91176 182486 91177 182486 91177 182487 91176 182487 91178 182487 91177 182488 91178 182488 91185 182488 91185 182489 91178 182489 91190 182489 91185 182490 91190 182490 91186 182490 91224 182491 91171 182491 91158 182491 91158 182492 91171 182492 91173 182492 91158 182493 91173 182493 91160 182493 91160 182494 91173 182494 91174 182494 91160 182495 91174 182495 91179 182495 91179 182496 91174 182496 91180 182496 91179 182497 91180 182497 91187 182497 91187 182498 91180 182498 91181 182498 91187 182499 91181 182499 91182 182499 91182 182500 91181 182500 91175 182500 91182 182501 91175 182501 91183 182501 91183 182502 91175 182502 91177 182502 91183 182503 91177 182503 91184 182503 91184 182504 91177 182504 91185 182504 91184 182505 91185 182505 91188 182505 91188 182506 91185 182506 91186 182506 91188 182507 91186 182507 91191 182507 89245 182508 91160 182508 89246 182508 89246 182509 91160 182509 91179 182509 89246 182510 91179 182510 89248 182510 89248 182511 91179 182511 91187 182511 89248 182512 91187 182512 89242 182512 89242 182513 91187 182513 91182 182513 89242 182514 91182 182514 89243 182514 89243 182515 91182 182515 91183 182515 89243 182516 91183 182516 89239 182516 89239 182517 91183 182517 91184 182517 89239 182518 91184 182518 89240 182518 89240 182519 91184 182519 91188 182519 89240 182520 91188 182520 89241 182520 89241 182521 91188 182521 91191 182521 89241 182522 91191 182522 91189 182522 91190 182523 88378 182523 91193 182523 91186 182524 91190 182524 91194 182524 91191 182525 91186 182525 91192 182525 91189 182526 91191 182526 91212 182526 91190 182527 91193 182527 91194 182527 91194 182528 91193 182528 88380 182528 91194 182529 88380 182529 91195 182529 88380 182530 88381 182530 91195 182530 91195 182531 88381 182531 88382 182531 91195 182532 88382 182532 91196 182532 91196 182533 88382 182533 91197 182533 91196 182534 91197 182534 91201 182534 91197 182535 91198 182535 91201 182535 91201 182536 91198 182536 88385 182536 91201 182537 88385 182537 91199 182537 91199 182538 88385 182538 88384 182538 91199 182539 88384 182539 91203 182539 91186 182540 91194 182540 91192 182540 91192 182541 91194 182541 91195 182541 91192 182542 91195 182542 91200 182542 91200 182543 91195 182543 91196 182543 91200 182544 91196 182544 91207 182544 91207 182545 91196 182545 91201 182545 91207 182546 91201 182546 91202 182546 91202 182547 91201 182547 91199 182547 91202 182548 91199 182548 91210 182548 91210 182549 91199 182549 91203 182549 91210 182550 91203 182550 91204 182550 91191 182551 91192 182551 91212 182551 91212 182552 91192 182552 91200 182552 91212 182553 91200 182553 91205 182553 91205 182554 91200 182554 91207 182554 91205 182555 91207 182555 91206 182555 91206 182556 91207 182556 91202 182556 91206 182557 91202 182557 91208 182557 91208 182558 91202 182558 91210 182558 91208 182559 91210 182559 91209 182559 91209 182560 91210 182560 91204 182560 91209 182561 91204 182561 91226 182561 91189 182562 91212 182562 91211 182562 91211 182563 91212 182563 91205 182563 91211 182564 91205 182564 91213 182564 91213 182565 91205 182565 91206 182565 91213 182566 91206 182566 91214 182566 91214 182567 91206 182567 91208 182567 91214 182568 91208 182568 89252 182568 89252 182569 91208 182569 91209 182569 89252 182570 91209 182570 91215 182570 91215 182571 91209 182571 91226 182571 91215 182572 91226 182572 91216 182572 91156 182573 91220 182573 91219 182573 91287 182574 88238 182574 88237 182574 91295 182575 91218 182575 91217 182575 91217 182576 91218 182576 89235 182576 91217 182577 89235 182577 89224 182577 91157 182578 91156 182578 88237 182578 88237 182579 91156 182579 91219 182579 88237 182580 91219 182580 91287 182580 91287 182581 91219 182581 91222 182581 91220 182582 91221 182582 91219 182582 91219 182583 91221 182583 91218 182583 91219 182584 91218 182584 91222 182584 91222 182585 91218 182585 91295 182585 91223 182586 89235 182586 91224 182586 91224 182587 89235 182587 91218 182587 91224 182588 91218 182588 91225 182588 91225 182589 91218 182589 91221 182589 91203 182590 88384 182590 88383 182590 88383 182591 91229 182591 91203 182591 91203 182592 91229 182592 91231 182592 91203 182593 91231 182593 91204 182593 91204 182594 91231 182594 91227 182594 91204 182595 91227 182595 91226 182595 89209 182596 91216 182596 91235 182596 91235 182597 91216 182597 91226 182597 91235 182598 91226 182598 91233 182598 91233 182599 91226 182599 91227 182599 88383 182600 91228 182600 91229 182600 91229 182601 91228 182601 91230 182601 91229 182602 91230 182602 91231 182602 91231 182603 91230 182603 91232 182603 91231 182604 91232 182604 91227 182604 91227 182605 91232 182605 91251 182605 91227 182606 91251 182606 91233 182606 91233 182607 91251 182607 91234 182607 91233 182608 91234 182608 91235 182608 91235 182609 91234 182609 91236 182609 91235 182610 91236 182610 89209 182610 91253 182611 89208 182611 91236 182611 91236 182612 89208 182612 89210 182612 91236 182613 89210 182613 89209 182613 91248 182614 91237 182614 91249 182614 91249 182615 91237 182615 91238 182615 91249 182616 91238 182616 91250 182616 91250 182617 91238 182617 91239 182617 91250 182618 91239 182618 91240 182618 91240 182619 91239 182619 91241 182619 91240 182620 91241 182620 91252 182620 91252 182621 91241 182621 91242 182621 91252 182622 91242 182622 91254 182622 91254 182623 91242 182623 91243 182623 91237 182624 91244 182624 91238 182624 91238 182625 91244 182625 91245 182625 91238 182626 91245 182626 91239 182626 91239 182627 91245 182627 91246 182627 91239 182628 91246 182628 91241 182628 91241 182629 91246 182629 91247 182629 91241 182630 91247 182630 91242 182630 91242 182631 91247 182631 91265 182631 91242 182632 91265 182632 91243 182632 91243 182633 91265 182633 91266 182633 91228 182634 91248 182634 91230 182634 91230 182635 91248 182635 91249 182635 91230 182636 91249 182636 91232 182636 91232 182637 91249 182637 91250 182637 91232 182638 91250 182638 91251 182638 91251 182639 91250 182639 91240 182639 91251 182640 91240 182640 91234 182640 91234 182641 91240 182641 91252 182641 91234 182642 91252 182642 91236 182642 91236 182643 91252 182643 91254 182643 91236 182644 91254 182644 91253 182644 91253 182645 91254 182645 91243 182645 91253 182646 91243 182646 89206 182646 89206 182647 91243 182647 91266 182647 89201 182648 89202 182648 91266 182648 91266 182649 89202 182649 89204 182649 91266 182650 89204 182650 89206 182650 91255 182651 91256 182651 91264 182651 91264 182652 91256 182652 91263 182652 91264 182653 91263 182653 91257 182653 91257 182654 91263 182654 91262 182654 91257 182655 91262 182655 91258 182655 91258 182656 91262 182656 91260 182656 91258 182657 91260 182657 91267 182657 91267 182658 91260 182658 91259 182658 91267 182659 91259 182659 91268 182659 91268 182660 91259 182660 91269 182660 91270 182661 91269 182661 91305 182661 91305 182662 91269 182662 91259 182662 91305 182663 91259 182663 91306 182663 91306 182664 91259 182664 91260 182664 91306 182665 91260 182665 91261 182665 91261 182666 91260 182666 91262 182666 91261 182667 91262 182667 91309 182667 91309 182668 91262 182668 91263 182668 91309 182669 91263 182669 91310 182669 91310 182670 91263 182670 91256 182670 91244 182671 91255 182671 91245 182671 91245 182672 91255 182672 91264 182672 91245 182673 91264 182673 91246 182673 91246 182674 91264 182674 91257 182674 91246 182675 91257 182675 91247 182675 91247 182676 91257 182676 91258 182676 91247 182677 91258 182677 91265 182677 91265 182678 91258 182678 91267 182678 91265 182679 91267 182679 91266 182679 91266 182680 91267 182680 91268 182680 91266 182681 91268 182681 89201 182681 89201 182682 91268 182682 91269 182682 89201 182683 91269 182683 89200 182683 89200 182684 91269 182684 91270 182684 89200 182685 91270 182685 89198 182685 91319 182686 91318 182686 91274 182686 91339 182687 91319 182687 91271 182687 91272 182688 91339 182688 91289 182688 91345 182689 91272 182689 91273 182689 91345 182690 91273 182690 89230 182690 89230 182691 91273 182691 91290 182691 89230 182692 91290 182692 91296 182692 91319 182693 91274 182693 91271 182693 91271 182694 91274 182694 88244 182694 91271 182695 88244 182695 91275 182695 91275 182696 88244 182696 91276 182696 91275 182697 91276 182697 91281 182697 91281 182698 91276 182698 88243 182698 91281 182699 88243 182699 91283 182699 91283 182700 88243 182700 91278 182700 91283 182701 91278 182701 91277 182701 91277 182702 91278 182702 88241 182702 91277 182703 88241 182703 91284 182703 91284 182704 88241 182704 88240 182704 91284 182705 88240 182705 91279 182705 91279 182706 88240 182706 88239 182706 91279 182707 88239 182707 91285 182707 91339 182708 91271 182708 91289 182708 91289 182709 91271 182709 91275 182709 91289 182710 91275 182710 91280 182710 91280 182711 91275 182711 91281 182711 91280 182712 91281 182712 91282 182712 91282 182713 91281 182713 91283 182713 91282 182714 91283 182714 91291 182714 91291 182715 91283 182715 91277 182715 91291 182716 91277 182716 91292 182716 91292 182717 91277 182717 91284 182717 91292 182718 91284 182718 91294 182718 91294 182719 91284 182719 91279 182719 91294 182720 91279 182720 91286 182720 91286 182721 91279 182721 91285 182721 91286 182722 91285 182722 91288 182722 88239 182723 88238 182723 91285 182723 91285 182724 88238 182724 91287 182724 91285 182725 91287 182725 91288 182725 91288 182726 91287 182726 91222 182726 91288 182727 91222 182727 91295 182727 91272 182728 91289 182728 91273 182728 91273 182729 91289 182729 91280 182729 91273 182730 91280 182730 91290 182730 91290 182731 91280 182731 91282 182731 91290 182732 91282 182732 91297 182732 91297 182733 91282 182733 91291 182733 91297 182734 91291 182734 91299 182734 91299 182735 91291 182735 91292 182735 91299 182736 91292 182736 91293 182736 91293 182737 91292 182737 91294 182737 91293 182738 91294 182738 91301 182738 91301 182739 91294 182739 91286 182739 91301 182740 91286 182740 91302 182740 91302 182741 91286 182741 91288 182741 91302 182742 91288 182742 91304 182742 91304 182743 91288 182743 91295 182743 91304 182744 91295 182744 91217 182744 91296 182745 91290 182745 89231 182745 89231 182746 91290 182746 91297 182746 89231 182747 91297 182747 91298 182747 91298 182748 91297 182748 91299 182748 91298 182749 91299 182749 89234 182749 89234 182750 91299 182750 91293 182750 89234 182751 91293 182751 91300 182751 91300 182752 91293 182752 91301 182752 91300 182753 91301 182753 89229 182753 89229 182754 91301 182754 91302 182754 89229 182755 91302 182755 91303 182755 91303 182756 91302 182756 91304 182756 91303 182757 91304 182757 89226 182757 89226 182758 91304 182758 91217 182758 89226 182759 91217 182759 89224 182759 91311 182760 89198 182760 91313 182760 91313 182761 89198 182761 91270 182761 91313 182762 91270 182762 91314 182762 91314 182763 91270 182763 91305 182763 91314 182764 91305 182764 91307 182764 91307 182765 91305 182765 91306 182765 91307 182766 91306 182766 91317 182766 91317 182767 91306 182767 91261 182767 91317 182768 91261 182768 91308 182768 91308 182769 91261 182769 91309 182769 91308 182770 91309 182770 88257 182770 88257 182771 91309 182771 91310 182771 91347 182772 91311 182772 91348 182772 91348 182773 91311 182773 91313 182773 91348 182774 91313 182774 91312 182774 91312 182775 91313 182775 91314 182775 91312 182776 91314 182776 91315 182776 91315 182777 91314 182777 91307 182777 91315 182778 91307 182778 91316 182778 91316 182779 91307 182779 91317 182779 91316 182780 91317 182780 91346 182780 91346 182781 91317 182781 91308 182781 91346 182782 91308 182782 88256 182782 88256 182783 91308 182783 88257 182783 91318 182784 91319 182784 91332 182784 91321 182785 91380 182785 91333 182785 91381 182786 91323 182786 91324 182786 91380 182787 91381 182787 91327 182787 91320 182788 89220 182788 91321 182788 88251 182789 91324 182789 91322 182789 91322 182790 91324 182790 91323 182790 91322 182791 91323 182791 88253 182791 88250 182792 91326 182792 88251 182792 88251 182793 91326 182793 91329 182793 88251 182794 91329 182794 91324 182794 88250 182795 91325 182795 91326 182795 91326 182796 91325 182796 88248 182796 91326 182797 88248 182797 91330 182797 91330 182798 88248 182798 88247 182798 91330 182799 88247 182799 91332 182799 91332 182800 88247 182800 88246 182800 91332 182801 88246 182801 91318 182801 91381 182802 91324 182802 91327 182802 91327 182803 91324 182803 91329 182803 91327 182804 91329 182804 91328 182804 91328 182805 91329 182805 91326 182805 91328 182806 91326 182806 91336 182806 91336 182807 91326 182807 91330 182807 91336 182808 91330 182808 91338 182808 91338 182809 91330 182809 91332 182809 91338 182810 91332 182810 91331 182810 91331 182811 91332 182811 91319 182811 91331 182812 91319 182812 91339 182812 91380 182813 91327 182813 91333 182813 91333 182814 91327 182814 91328 182814 91333 182815 91328 182815 91334 182815 91334 182816 91328 182816 91336 182816 91334 182817 91336 182817 91335 182817 91335 182818 91336 182818 91338 182818 91335 182819 91338 182819 91337 182819 91337 182820 91338 182820 91331 182820 91337 182821 91331 182821 91343 182821 91343 182822 91331 182822 91339 182822 91343 182823 91339 182823 91272 182823 91321 182824 91333 182824 91320 182824 91320 182825 91333 182825 91334 182825 91320 182826 91334 182826 91340 182826 91340 182827 91334 182827 91335 182827 91340 182828 91335 182828 91341 182828 91341 182829 91335 182829 91337 182829 91341 182830 91337 182830 91342 182830 91342 182831 91337 182831 91343 182831 91342 182832 91343 182832 91344 182832 91344 182833 91343 182833 91272 182833 91344 182834 91272 182834 91345 182834 91346 182835 88256 182835 91371 182835 91315 182836 91316 182836 91349 182836 91312 182837 91315 182837 91350 182837 91348 182838 91312 182838 91360 182838 91347 182839 91348 182839 91364 182839 91315 182840 91349 182840 91350 182840 91350 182841 91349 182841 91388 182841 91350 182842 91388 182842 91351 182842 91351 182843 91388 182843 91387 182843 91351 182844 91387 182844 91352 182844 91352 182845 91387 182845 91353 182845 91352 182846 91353 182846 91354 182846 91354 182847 91353 182847 91355 182847 91354 182848 91355 182848 91356 182848 91356 182849 91355 182849 91384 182849 91356 182850 91384 182850 91383 182850 91312 182851 91350 182851 91360 182851 91360 182852 91350 182852 91351 182852 91360 182853 91351 182853 91357 182853 91357 182854 91351 182854 91352 182854 91357 182855 91352 182855 91358 182855 91358 182856 91352 182856 91354 182856 91358 182857 91354 182857 91361 182857 91361 182858 91354 182858 91356 182858 91361 182859 91356 182859 91359 182859 91359 182860 91356 182860 91383 182860 91359 182861 91383 182861 91382 182861 91348 182862 91360 182862 91364 182862 91364 182863 91360 182863 91357 182863 91364 182864 91357 182864 91366 182864 91366 182865 91357 182865 91358 182865 91366 182866 91358 182866 91368 182866 91368 182867 91358 182867 91361 182867 91368 182868 91361 182868 91362 182868 91362 182869 91361 182869 91359 182869 91362 182870 91359 182870 91369 182870 91369 182871 91359 182871 91382 182871 91369 182872 91382 182872 91363 182872 91347 182873 91364 182873 91365 182873 91365 182874 91364 182874 91366 182874 91365 182875 91366 182875 91367 182875 91367 182876 91366 182876 91368 182876 91367 182877 91368 182877 89216 182877 89216 182878 91368 182878 91362 182878 89216 182879 91362 182879 89214 182879 89214 182880 91362 182880 91369 182880 89214 182881 91369 182881 91370 182881 91370 182882 91369 182882 91363 182882 91370 182883 91363 182883 91379 182883 91346 182884 91371 182884 91389 182884 91389 182885 91371 182885 91372 182885 91389 182886 91372 182886 91373 182886 91373 182887 91372 182887 88254 182887 91373 182888 88254 182888 91375 182888 91375 182889 88254 182889 91374 182889 91375 182890 91374 182890 91386 182890 91386 182891 91374 182891 91376 182891 91386 182892 91376 182892 91377 182892 91377 182893 91376 182893 91378 182893 91377 182894 91378 182894 91385 182894 91385 182895 91378 182895 88253 182895 91385 182896 88253 182896 91323 182896 89220 182897 91379 182897 91321 182897 91321 182898 91379 182898 91363 182898 91321 182899 91363 182899 91380 182899 91380 182900 91363 182900 91382 182900 91380 182901 91382 182901 91381 182901 91381 182902 91382 182902 91383 182902 91381 182903 91383 182903 91323 182903 91323 182904 91383 182904 91384 182904 91323 182905 91384 182905 91385 182905 91385 182906 91384 182906 91355 182906 91385 182907 91355 182907 91377 182907 91377 182908 91355 182908 91353 182908 91377 182909 91353 182909 91386 182909 91386 182910 91353 182910 91387 182910 91386 182911 91387 182911 91375 182911 91375 182912 91387 182912 91388 182912 91375 182913 91388 182913 91373 182913 91373 182914 91388 182914 91349 182914 91373 182915 91349 182915 91389 182915 91389 182916 91349 182916 91316 182916 91389 182917 91316 182917 91346 182917 91391 182918 88212 182918 91390 182918 91392 182919 91391 182919 91394 182919 91468 182920 91392 182920 91402 182920 91467 182921 91468 182921 91406 182921 91466 182922 91467 182922 91419 182922 91393 182923 91466 182923 91420 182923 91391 182924 91390 182924 91394 182924 91394 182925 91390 182925 91395 182925 91394 182926 91395 182926 91396 182926 91396 182927 91395 182927 88371 182927 91396 182928 88371 182928 91403 182928 91403 182929 88371 182929 88370 182929 91403 182930 88370 182930 91404 182930 91404 182931 88370 182931 91397 182931 91404 182932 91397 182932 91398 182932 91398 182933 91397 182933 91400 182933 91398 182934 91400 182934 91399 182934 91399 182935 91400 182935 91401 182935 91399 182936 91401 182936 91432 182936 91392 182937 91394 182937 91402 182937 91402 182938 91394 182938 91396 182938 91402 182939 91396 182939 91408 182939 91408 182940 91396 182940 91403 182940 91408 182941 91403 182941 91409 182941 91409 182942 91403 182942 91404 182942 91409 182943 91404 182943 91405 182943 91405 182944 91404 182944 91398 182944 91405 182945 91398 182945 91410 182945 91410 182946 91398 182946 91399 182946 91410 182947 91399 182947 91411 182947 91411 182948 91399 182948 91432 182948 91411 182949 91432 182949 91444 182949 91468 182950 91402 182950 91406 182950 91406 182951 91402 182951 91408 182951 91406 182952 91408 182952 91407 182952 91407 182953 91408 182953 91409 182953 91407 182954 91409 182954 91414 182954 91414 182955 91409 182955 91405 182955 91414 182956 91405 182956 91415 182956 91415 182957 91405 182957 91410 182957 91415 182958 91410 182958 91416 182958 91416 182959 91410 182959 91411 182959 91416 182960 91411 182960 91412 182960 91412 182961 91411 182961 91444 182961 91412 182962 91444 182962 91433 182962 91467 182963 91406 182963 91419 182963 91419 182964 91406 182964 91407 182964 91419 182965 91407 182965 91413 182965 91413 182966 91407 182966 91414 182966 91413 182967 91414 182967 91422 182967 91422 182968 91414 182968 91415 182968 91422 182969 91415 182969 91423 182969 91423 182970 91415 182970 91416 182970 91423 182971 91416 182971 91417 182971 91417 182972 91416 182972 91412 182972 91417 182973 91412 182973 91418 182973 91418 182974 91412 182974 91433 182974 91418 182975 91433 182975 91435 182975 91466 182976 91419 182976 91420 182976 91420 182977 91419 182977 91413 182977 91420 182978 91413 182978 91421 182978 91421 182979 91413 182979 91422 182979 91421 182980 91422 182980 91428 182980 91428 182981 91422 182981 91423 182981 91428 182982 91423 182982 91429 182982 91429 182983 91423 182983 91417 182983 91429 182984 91417 182984 91431 182984 91431 182985 91417 182985 91418 182985 91431 182986 91418 182986 91424 182986 91424 182987 91418 182987 91435 182987 91424 182988 91435 182988 91425 182988 91393 182989 91420 182989 89145 182989 89145 182990 91420 182990 91421 182990 89145 182991 91421 182991 91426 182991 91426 182992 91421 182992 91428 182992 91426 182993 91428 182993 91427 182993 91427 182994 91428 182994 91429 182994 91427 182995 91429 182995 91430 182995 91430 182996 91429 182996 91431 182996 91430 182997 91431 182997 89139 182997 89139 182998 91431 182998 91424 182998 89139 182999 91424 182999 89138 182999 89138 183000 91424 183000 91425 183000 89138 183001 91425 183001 89124 183001 91444 183002 91432 183002 91439 183002 91435 183003 91433 183003 91434 183003 91434 183004 91433 183004 91444 183004 91452 183005 91425 183005 91435 183005 91425 183006 91452 183006 89124 183006 88372 183007 91445 183007 91436 183007 91436 183008 91445 183008 91437 183008 91436 183009 91437 183009 91438 183009 91438 183010 91437 183010 91439 183010 91438 183011 91439 183011 91440 183011 91440 183012 91439 183012 91432 183012 91440 183013 91432 183013 91401 183013 88374 183014 91441 183014 88372 183014 88372 183015 91441 183015 91446 183015 88372 183016 91446 183016 91445 183016 88374 183017 91442 183017 91441 183017 91441 183018 91442 183018 91497 183018 91441 183019 91497 183019 91443 183019 91444 183020 91439 183020 91434 183020 91434 183021 91439 183021 91437 183021 91434 183022 91437 183022 91448 183022 91448 183023 91437 183023 91445 183023 91448 183024 91445 183024 91449 183024 91449 183025 91445 183025 91446 183025 91449 183026 91446 183026 91450 183026 91450 183027 91446 183027 91441 183027 91450 183028 91441 183028 91447 183028 91447 183029 91441 183029 91443 183029 91447 183030 91443 183030 91473 183030 91435 183031 91434 183031 91452 183031 91452 183032 91434 183032 91448 183032 91452 183033 91448 183033 91453 183033 91453 183034 91448 183034 91449 183034 91453 183035 91449 183035 91455 183035 91455 183036 91449 183036 91450 183036 91455 183037 91450 183037 91456 183037 91456 183038 91450 183038 91447 183038 91456 183039 91447 183039 91451 183039 91451 183040 91447 183040 91473 183040 91451 183041 91473 183041 91498 183041 89124 183042 91452 183042 89123 183042 89123 183043 91452 183043 91453 183043 89123 183044 91453 183044 89122 183044 89122 183045 91453 183045 91455 183045 89122 183046 91455 183046 91454 183046 91454 183047 91455 183047 91456 183047 91454 183048 91456 183048 91457 183048 91457 183049 91456 183049 91451 183049 91457 183050 91451 183050 89119 183050 89119 183051 91451 183051 91498 183051 89119 183052 91498 183052 91458 183052 89137 183053 89127 183053 91459 183053 91459 183054 89127 183054 91556 183054 91459 183055 91556 183055 91460 183055 91460 183056 91556 183056 91461 183056 91460 183057 91461 183057 91469 183057 91469 183058 91461 183058 91462 183058 91469 183059 91462 183059 91470 183059 91470 183060 91462 183060 91464 183060 91470 183061 91464 183061 91463 183061 91463 183062 91464 183062 91465 183062 91463 183063 91465 183063 91471 183063 91471 183064 91465 183064 91560 183064 91393 183065 89137 183065 91466 183065 91466 183066 89137 183066 91459 183066 91466 183067 91459 183067 91467 183067 91467 183068 91459 183068 91460 183068 91467 183069 91460 183069 91468 183069 91468 183070 91460 183070 91469 183070 91468 183071 91469 183071 91392 183071 91392 183072 91469 183072 91470 183072 91392 183073 91470 183073 91391 183073 91391 183074 91470 183074 91463 183074 91391 183075 91463 183075 88212 183075 88212 183076 91463 183076 91471 183076 91473 183077 91443 183077 91472 183077 91498 183078 91473 183078 91474 183078 91458 183079 91498 183079 91475 183079 91458 183080 91475 183080 89097 183080 89097 183081 91475 183081 91476 183081 89097 183082 91476 183082 89098 183082 89098 183083 91476 183083 89100 183083 89100 183084 91476 183084 91499 183084 89100 183085 91499 183085 91477 183085 91477 183086 91499 183086 91502 183086 91477 183087 91502 183087 89101 183087 89101 183088 91502 183088 91503 183088 89101 183089 91503 183089 91478 183089 91478 183090 91503 183090 91508 183090 91478 183091 91508 183091 91506 183091 91473 183092 91472 183092 91474 183092 91474 183093 91472 183093 91494 183093 91474 183094 91494 183094 91479 183094 91479 183095 91494 183095 91493 183095 91479 183096 91493 183096 91500 183096 91500 183097 91493 183097 91491 183097 91500 183098 91491 183098 91481 183098 91481 183099 91491 183099 91480 183099 91481 183100 91480 183100 91501 183100 91501 183101 91480 183101 91488 183101 91501 183102 91488 183102 91482 183102 91482 183103 91488 183103 91486 183103 91482 183104 91486 183104 91504 183104 91504 183105 91486 183105 91483 183105 91504 183106 91483 183106 91484 183106 88233 183107 91483 183107 91485 183107 91485 183108 91483 183108 91486 183108 91485 183109 91486 183109 91487 183109 91487 183110 91486 183110 91488 183110 91487 183111 91488 183111 91489 183111 91489 183112 91488 183112 91480 183112 91489 183113 91480 183113 91490 183113 91490 183114 91480 183114 91491 183114 91490 183115 91491 183115 91492 183115 91492 183116 91491 183116 91493 183116 91492 183117 91493 183117 88375 183117 88375 183118 91493 183118 91494 183118 88375 183119 91494 183119 91495 183119 91495 183120 91494 183120 91472 183120 91495 183121 91472 183121 91496 183121 91496 183122 91472 183122 91443 183122 91496 183123 91443 183123 91497 183123 88233 183124 91568 183124 91483 183124 91483 183125 91568 183125 91561 183125 91483 183126 91561 183126 91484 183126 91484 183127 91561 183127 91563 183127 91484 183128 91563 183128 91565 183128 91498 183129 91474 183129 91475 183129 91475 183130 91474 183130 91479 183130 91475 183131 91479 183131 91476 183131 91476 183132 91479 183132 91500 183132 91476 183133 91500 183133 91499 183133 91499 183134 91500 183134 91481 183134 91499 183135 91481 183135 91502 183135 91502 183136 91481 183136 91501 183136 91502 183137 91501 183137 91503 183137 91503 183138 91501 183138 91482 183138 91503 183139 91482 183139 91508 183139 91508 183140 91482 183140 91504 183140 91508 183141 91504 183141 91505 183141 91505 183142 91504 183142 91484 183142 91505 183143 91484 183143 91509 183143 91509 183144 91484 183144 91565 183144 91509 183145 91565 183145 91510 183145 91506 183146 91508 183146 91507 183146 91507 183147 91508 183147 91505 183147 91507 183148 91505 183148 89094 183148 89094 183149 91505 183149 91509 183149 89094 183150 91509 183150 89092 183150 89092 183151 91509 183151 91510 183151 89092 183152 91510 183152 89091 183152 89134 183153 91511 183153 91539 183153 91521 183154 91512 183154 91513 183154 91513 183155 91512 183155 91514 183155 91513 183156 91514 183156 91523 183156 91523 183157 91514 183157 91515 183157 91523 183158 91515 183158 91516 183158 91516 183159 91515 183159 91518 183159 91516 183160 91518 183160 91517 183160 91517 183161 91518 183161 91519 183161 91517 183162 91519 183162 91520 183162 91520 183163 91519 183163 91585 183163 91520 183164 91585 183164 88219 183164 88219 183165 91585 183165 88220 183165 91525 183166 91521 183166 91522 183166 91522 183167 91521 183167 91513 183167 91522 183168 91513 183168 91526 183168 91526 183169 91513 183169 91523 183169 91526 183170 91523 183170 91527 183170 91527 183171 91523 183171 91516 183171 91527 183172 91516 183172 91528 183172 91528 183173 91516 183173 91517 183173 91528 183174 91517 183174 91524 183174 91524 183175 91517 183175 91520 183175 91524 183176 91520 183176 91530 183176 91530 183177 91520 183177 88219 183177 91531 183178 91525 183178 91533 183178 91533 183179 91525 183179 91522 183179 91533 183180 91522 183180 91534 183180 91534 183181 91522 183181 91526 183181 91534 183182 91526 183182 91535 183182 91535 183183 91526 183183 91527 183183 91535 183184 91527 183184 91537 183184 91537 183185 91527 183185 91528 183185 91537 183186 91528 183186 91538 183186 91538 183187 91528 183187 91524 183187 91538 183188 91524 183188 91529 183188 91529 183189 91524 183189 91530 183189 89133 183190 91531 183190 91540 183190 91540 183191 91531 183191 91533 183191 91540 183192 91533 183192 91532 183192 91532 183193 91533 183193 91534 183193 91532 183194 91534 183194 91544 183194 91544 183195 91534 183195 91535 183195 91544 183196 91535 183196 91536 183196 91536 183197 91535 183197 91537 183197 91536 183198 91537 183198 91545 183198 91545 183199 91537 183199 91538 183199 91545 183200 91538 183200 88216 183200 88216 183201 91538 183201 91529 183201 91511 183202 89133 183202 91539 183202 91539 183203 89133 183203 91540 183203 91539 183204 91540 183204 91541 183204 91541 183205 91540 183205 91532 183205 91541 183206 91532 183206 91542 183206 91542 183207 91532 183207 91544 183207 91542 183208 91544 183208 91543 183208 91543 183209 91544 183209 91536 183209 91543 183210 91536 183210 91549 183210 91549 183211 91536 183211 91545 183211 91549 183212 91545 183212 88215 183212 88215 183213 91545 183213 88216 183213 91551 183214 89134 183214 91553 183214 91553 183215 89134 183215 91539 183215 91553 183216 91539 183216 91546 183216 91546 183217 91539 183217 91541 183217 91546 183218 91541 183218 91547 183218 91547 183219 91541 183219 91542 183219 91547 183220 91542 183220 91554 183220 91554 183221 91542 183221 91543 183221 91554 183222 91543 183222 91548 183222 91548 183223 91543 183223 91549 183223 91548 183224 91549 183224 91550 183224 91550 183225 91549 183225 88215 183225 89126 183226 91551 183226 91552 183226 91552 183227 91551 183227 91553 183227 91552 183228 91553 183228 91557 183228 91557 183229 91553 183229 91546 183229 91557 183230 91546 183230 91558 183230 91558 183231 91546 183231 91547 183231 91558 183232 91547 183232 91559 183232 91559 183233 91547 183233 91554 183233 91559 183234 91554 183234 91555 183234 91555 183235 91554 183235 91548 183235 91555 183236 91548 183236 88213 183236 88213 183237 91548 183237 91550 183237 89127 183238 89126 183238 91556 183238 91556 183239 89126 183239 91552 183239 91556 183240 91552 183240 91461 183240 91461 183241 91552 183241 91557 183241 91461 183242 91557 183242 91462 183242 91462 183243 91557 183243 91558 183243 91462 183244 91558 183244 91464 183244 91464 183245 91558 183245 91559 183245 91464 183246 91559 183246 91465 183246 91465 183247 91559 183247 91555 183247 91465 183248 91555 183248 91560 183248 91560 183249 91555 183249 88213 183249 91562 183250 91561 183250 91568 183250 91561 183251 91562 183251 91563 183251 91563 183252 91562 183252 91564 183252 91563 183253 91564 183253 91565 183253 91565 183254 91564 183254 91510 183254 91510 183255 91564 183255 91566 183255 91510 183256 91566 183256 89091 183256 91567 183257 91562 183257 88232 183257 88232 183258 91562 183258 91568 183258 88232 183259 91568 183259 88233 183259 91597 183260 91566 183260 91598 183260 91598 183261 91566 183261 91564 183261 91598 183262 91564 183262 91569 183262 91569 183263 91564 183263 91562 183263 91569 183264 91562 183264 91599 183264 91599 183265 91562 183265 91567 183265 91633 183266 91570 183266 91573 183266 91571 183267 91633 183267 91574 183267 91586 183268 91571 183268 91572 183268 89103 183269 91586 183269 91587 183269 91633 183270 91573 183270 91574 183270 91574 183271 91573 183271 91576 183271 91574 183272 91576 183272 91575 183272 91576 183273 88228 183273 91575 183273 91575 183274 88228 183274 91578 183274 91575 183275 91578 183275 91577 183275 91577 183276 91578 183276 91579 183276 91577 183277 91579 183277 91584 183277 91584 183278 91579 183278 91580 183278 91580 183279 91579 183279 91581 183279 91580 183280 91581 183280 88222 183280 91571 183281 91574 183281 91572 183281 91572 183282 91574 183282 91575 183282 91572 183283 91575 183283 91588 183283 91588 183284 91575 183284 91577 183284 91588 183285 91577 183285 91582 183285 91582 183286 91577 183286 91584 183286 91582 183287 91584 183287 91583 183287 91583 183288 91584 183288 91580 183288 91583 183289 91580 183289 91589 183289 88222 183290 88220 183290 91585 183290 88222 183291 91585 183291 91580 183291 91580 183292 91585 183292 91519 183292 91580 183293 91519 183293 91589 183293 91589 183294 91519 183294 91518 183294 91589 183295 91518 183295 91515 183295 91586 183296 91572 183296 91587 183296 91587 183297 91572 183297 91588 183297 91587 183298 91588 183298 91592 183298 91592 183299 91588 183299 91582 183299 91592 183300 91582 183300 91593 183300 91593 183301 91582 183301 91583 183301 91593 183302 91583 183302 91594 183302 91594 183303 91583 183303 91589 183303 91594 183304 91589 183304 91590 183304 91590 183305 91589 183305 91515 183305 91590 183306 91515 183306 91514 183306 89103 183307 91587 183307 89115 183307 89115 183308 91587 183308 91592 183308 89115 183309 91592 183309 91591 183309 91591 183310 91592 183310 91593 183310 91591 183311 91593 183311 89116 183311 89116 183312 91593 183312 91594 183312 89116 183313 91594 183313 89118 183313 89118 183314 91594 183314 91590 183314 89118 183315 91590 183315 91595 183315 91595 183316 91590 183316 91514 183316 91595 183317 91514 183317 91512 183317 91599 183318 91567 183318 91600 183318 91569 183319 91599 183319 91596 183319 91598 183320 91569 183320 91608 183320 91612 183321 89109 183321 91610 183321 91610 183322 89109 183322 91597 183322 91610 183323 91597 183323 91598 183323 91599 183324 91600 183324 91596 183324 91596 183325 91600 183325 91601 183325 91596 183326 91601 183326 91602 183326 91602 183327 91601 183327 91604 183327 91602 183328 91604 183328 91603 183328 91603 183329 91604 183329 91605 183329 91603 183330 91605 183330 91606 183330 91606 183331 91605 183331 88231 183331 91606 183332 88231 183332 91607 183332 91607 183333 88231 183333 91625 183333 91607 183334 91625 183334 91609 183334 91569 183335 91596 183335 91608 183335 91608 183336 91596 183336 91602 183336 91608 183337 91602 183337 91611 183337 91611 183338 91602 183338 91603 183338 91611 183339 91603 183339 91613 183339 91613 183340 91603 183340 91606 183340 91613 183341 91606 183341 91614 183341 91614 183342 91606 183342 91607 183342 91614 183343 91607 183343 91615 183343 91615 183344 91607 183344 91609 183344 91615 183345 91609 183345 91616 183345 91598 183346 91608 183346 91610 183346 91610 183347 91608 183347 91611 183347 91610 183348 91611 183348 91612 183348 91612 183349 91611 183349 91613 183349 91612 183350 91613 183350 91623 183350 91623 183351 91613 183351 91614 183351 91623 183352 91614 183352 91622 183352 91622 183353 91614 183353 91615 183353 91622 183354 91615 183354 91619 183354 91619 183355 91615 183355 91616 183355 91619 183356 91616 183356 91617 183356 91618 183357 89105 183357 91617 183357 91617 183358 89105 183358 91620 183358 91617 183359 91620 183359 91619 183359 91619 183360 91620 183360 91621 183360 91619 183361 91621 183361 91622 183361 91622 183362 91621 183362 89113 183362 91622 183363 89113 183363 91623 183363 91623 183364 89113 183364 89112 183364 91623 183365 89112 183365 91612 183365 91612 183366 89112 183366 91624 183366 91612 183367 91624 183367 89109 183367 91625 183368 91626 183368 91609 183368 91609 183369 91626 183369 91627 183369 91609 183370 91627 183370 91616 183370 91616 183371 91627 183371 91630 183371 91616 183372 91630 183372 91617 183372 91617 183373 91630 183373 91629 183373 91617 183374 91629 183374 91618 183374 91618 183375 91629 183375 91628 183375 89107 183376 91628 183376 91631 183376 91631 183377 91628 183377 91629 183377 91631 183378 91629 183378 91632 183378 91632 183379 91629 183379 91630 183379 91632 183380 91630 183380 91634 183380 91634 183381 91630 183381 91627 183381 91634 183382 91627 183382 88224 183382 88224 183383 91627 183383 91626 183383 89103 183384 89107 183384 91586 183384 91586 183385 89107 183385 91631 183385 91586 183386 91631 183386 91571 183386 91571 183387 91631 183387 91632 183387 91571 183388 91632 183388 91633 183388 91633 183389 91632 183389 91634 183389 91633 183390 91634 183390 91570 183390 91570 183391 91634 183391 88224 183391 88163 183392 88132 183392 88134 183392 88134 183393 88507 183393 88163 183393 88163 183394 88507 183394 91635 183394 88163 183395 91635 183395 88164 183395 88164 183396 91635 183396 91636 183396 88164 183397 91636 183397 91919 183397 91637 183398 91919 183398 91917 183398 91637 183399 91917 183399 91638 183399 91638 183400 91917 183400 91916 183400 91638 183401 91916 183401 91640 183401 91639 183402 88187 183402 88186 183402 91640 183403 91916 183403 88190 183403 88190 183404 91916 183404 91642 183404 88190 183405 91642 183405 91641 183405 91641 183406 91642 183406 91644 183406 91641 183407 91644 183407 91643 183407 91643 183408 91644 183408 91914 183408 91643 183409 91914 183409 88186 183409 88186 183410 91914 183410 91645 183410 88186 183411 91645 183411 91639 183411 91639 183412 91879 183412 88187 183412 88187 183413 91879 183413 91646 183413 88187 183414 91646 183414 88189 183414 88189 183415 91646 183415 91648 183415 91648 183416 91646 183416 91647 183416 91648 183417 91647 183417 91649 183417 91649 183418 91647 183418 91876 183418 91649 183419 91876 183419 88136 183419 88198 183420 91650 183420 88493 183420 88493 183421 91650 183421 91651 183421 88200 183422 88122 183422 91652 183422 91652 183423 88122 183423 88491 183423 91653 183424 91654 183424 91912 183424 91912 183425 91654 183425 91913 183425 88126 183426 91655 183426 88201 183426 88201 183427 91655 183427 88485 183427 91656 183428 88127 183428 91904 183428 91904 183429 88127 183429 88489 183429 91657 183430 91883 183430 88178 183430 88178 183431 91883 183431 91658 183431 88178 183432 91658 183432 91659 183432 91659 183433 91658 183433 88179 183433 88179 183434 91658 183434 91882 183434 88179 183435 91882 183435 91662 183435 91657 183436 88178 183436 91660 183436 91660 183437 88178 183437 88204 183437 91660 183438 88204 183438 91887 183438 91887 183439 88204 183439 88155 183439 91887 183440 88155 183440 88203 183440 91882 183441 91661 183441 91662 183441 91662 183442 91661 183442 91663 183442 91662 183443 91663 183443 88174 183443 88174 183444 91663 183444 91880 183444 88174 183445 91880 183445 88172 183445 91667 183446 88153 183446 88195 183446 88167 183447 91666 183447 91664 183447 91664 183448 91666 183448 91665 183448 91664 183449 91665 183449 91896 183449 88172 183450 91880 183450 88171 183450 88171 183451 91880 183451 91665 183451 88171 183452 91665 183452 88195 183452 88195 183453 91665 183453 91666 183453 88195 183454 91666 183454 91667 183454 91897 183455 88194 183455 88157 183455 88194 183456 91897 183456 91902 183456 88135 183457 88136 183457 88478 183457 88478 183458 88136 183458 91876 183458 88478 183459 91876 183459 91668 183459 88138 183460 88137 183460 91925 183460 91925 183461 88137 183461 91877 183461 88141 183462 88143 183462 91669 183462 91669 183463 88143 183463 91670 183463 88148 183464 91671 183464 88560 183464 88560 183465 91671 183465 91895 183465 88569 183466 91894 183466 88152 183466 88152 183467 91894 183467 91888 183467 88574 183468 91672 183468 88159 183468 88159 183469 91672 183469 91891 183469 91673 183470 88145 183470 91874 183470 91874 183471 88145 183471 91875 183471 88576 183472 91889 183472 88158 183472 88158 183473 91889 183473 91890 183473 88128 183474 91674 183474 88490 183474 88490 183475 91674 183475 88500 183475 91675 183476 91676 183476 91677 183476 91677 183477 91676 183477 88196 183477 91677 183478 88196 183478 91678 183478 89089 183479 89090 183479 91679 183479 91679 183480 89090 183480 91680 183480 91909 183481 91682 183481 91681 183481 91681 183482 91682 183482 88557 183482 91681 183483 88557 183483 91683 183483 88507 183484 91684 183484 91685 183484 89443 183485 89451 183485 88663 183485 91690 183486 89739 183486 91686 183486 91686 183487 89739 183487 91688 183487 89739 183488 91687 183488 91688 183488 91688 183489 91687 183489 89737 183489 91688 183490 89737 183490 89731 183490 89698 183491 91806 183491 89720 183491 89720 183492 91806 183492 89731 183492 89758 183493 91689 183493 89752 183493 89752 183494 91689 183494 91691 183494 91689 183495 91690 183495 91691 183495 91691 183496 91690 183496 91686 183496 91691 183497 91686 183497 92001 183497 92000 183498 89691 183498 89688 183498 89688 183499 89717 183499 92000 183499 92000 183500 89717 183500 91692 183500 92000 183501 91692 183501 91693 183501 88639 183502 91694 183502 88638 183502 88638 183503 91694 183503 91698 183503 89691 183504 92000 183504 91695 183504 91695 183505 92000 183505 91699 183505 91695 183506 91699 183506 91698 183506 89217 183507 91696 183507 88635 183507 89217 183508 88635 183508 91700 183508 91824 183509 89199 183509 91697 183509 91697 183510 89199 183510 89197 183510 91698 183511 91699 183511 88638 183511 88638 183512 91699 183512 91948 183512 88638 183513 91948 183513 88637 183513 88637 183514 91948 183514 91697 183514 88637 183515 91697 183515 88635 183515 88635 183516 91697 183516 89197 183516 88635 183517 89197 183517 91700 183517 91696 183518 91701 183518 88635 183518 88635 183519 91701 183519 89218 183519 88635 183520 89218 183520 91703 183520 89218 183521 91702 183521 91703 183521 91703 183522 91702 183522 89215 183522 91703 183523 89215 183523 91704 183523 91704 183524 89215 183524 89213 183524 89219 183525 88630 183525 89211 183525 89211 183526 88630 183526 91704 183526 89211 183527 91704 183527 89212 183527 89212 183528 91704 183528 89213 183528 91709 183529 88642 183529 91705 183529 91705 183530 88642 183530 88641 183530 91705 183531 88641 183531 91706 183531 91706 183532 88641 183532 91707 183532 91706 183533 91707 183533 89221 183533 89221 183534 91707 183534 88628 183534 89221 183535 88628 183535 89219 183535 89219 183536 88628 183536 88629 183536 89219 183537 88629 183537 88630 183537 91710 183538 88643 183538 91709 183538 91709 183539 88643 183539 91708 183539 91709 183540 91708 183540 88642 183540 91709 183541 89222 183541 91710 183541 91710 183542 89222 183542 91711 183542 91710 183543 91711 183543 91712 183543 89223 183544 91713 183544 91711 183544 91711 183545 91713 183545 88646 183545 91711 183546 88646 183546 91712 183546 89223 183547 89232 183547 91713 183547 91713 183548 89232 183548 89233 183548 91713 183549 89233 183549 88647 183549 88647 183550 89233 183550 89228 183550 88647 183551 89228 183551 88649 183551 88649 183552 89228 183552 91718 183552 89228 183553 89227 183553 91718 183553 91718 183554 89227 183554 89225 183554 91718 183555 89225 183555 91856 183555 89225 183556 89236 183556 91856 183556 91856 183557 89236 183557 89237 183557 91856 183558 89237 183558 89244 183558 89244 183559 89247 183559 91856 183559 91856 183560 89247 183560 91714 183560 91856 183561 91714 183561 91960 183561 91715 183562 89093 183562 91856 183562 91856 183563 89093 183563 91716 183563 91856 183564 91716 183564 91718 183564 91718 183565 91716 183565 89102 183565 91718 183566 89102 183566 89110 183566 91719 183567 89108 183567 91717 183567 89110 183568 89111 183568 91718 183568 91718 183569 89111 183569 91719 183569 91718 183570 91719 183570 88652 183570 88652 183571 91719 183571 91717 183571 89108 183572 89106 183572 91717 183572 91717 183573 89106 183573 91720 183573 91717 183574 91720 183574 91721 183574 91721 183575 91720 183575 91722 183575 91720 183576 89104 183576 91722 183576 91722 183577 89104 183577 89114 183577 91722 183578 89114 183578 91723 183578 91723 183579 89114 183579 91724 183579 91723 183580 91724 183580 91725 183580 91725 183581 91724 183581 91726 183581 91725 183582 91726 183582 88657 183582 88657 183583 91726 183583 89117 183583 88657 183584 89117 183584 91727 183584 91727 183585 89117 183585 91728 183585 91727 183586 91728 183586 88658 183586 88658 183587 91728 183587 91729 183587 91728 183588 91730 183588 91729 183588 91729 183589 91730 183589 89129 183589 91729 183590 89129 183590 91731 183590 91731 183591 89129 183591 89130 183591 91731 183592 89130 183592 91732 183592 91732 183593 89131 183593 91731 183593 91731 183594 89131 183594 89132 183594 91731 183595 89132 183595 91734 183595 91734 183596 89132 183596 91733 183596 91734 183597 91733 183597 89128 183597 89128 183598 91735 183598 91734 183598 91734 183599 91735 183599 89136 183599 91734 183600 89136 183600 89135 183600 89135 183601 91736 183601 91920 183601 91920 183602 91736 183602 89146 183602 91920 183603 89146 183603 89144 183603 89144 183604 89143 183604 91920 183604 91920 183605 89143 183605 89142 183605 91920 183606 89142 183606 91737 183606 89135 183607 91920 183607 91734 183607 91734 183608 91920 183608 91922 183608 91734 183609 91922 183609 88660 183609 91738 183610 91924 183610 91739 183610 91739 183611 91924 183611 91741 183611 88660 183612 91922 183612 88661 183612 88661 183613 91922 183613 91924 183613 88661 183614 91924 183614 88663 183614 88663 183615 91924 183615 91738 183615 88663 183616 91738 183616 89443 183616 89414 183617 91740 183617 91741 183617 91741 183618 91740 183618 91742 183618 91741 183619 91742 183619 91739 183619 89406 183620 89404 183620 91743 183620 91743 183621 89404 183621 91744 183621 89404 183622 89414 183622 91744 183622 91744 183623 89414 183623 91741 183623 91744 183624 91741 183624 89419 183624 91757 183625 89476 183625 91745 183625 91745 183626 89476 183626 89471 183626 89471 183627 91746 183627 91745 183627 91745 183628 91746 183628 89468 183628 91745 183629 89468 183629 89448 183629 89448 183630 89426 183630 91745 183630 91745 183631 89426 183631 91747 183631 91745 183632 91747 183632 91748 183632 91748 183633 91747 183633 89432 183633 91755 183634 91749 183634 89483 183634 91753 183635 89272 183635 91750 183635 92023 183636 91751 183636 91758 183636 91758 183637 91751 183637 91752 183637 91753 183638 91750 183638 89255 183638 91752 183639 91754 183639 91758 183639 91758 183640 91754 183640 89258 183640 91758 183641 89258 183641 89257 183641 89483 183642 89476 183642 91755 183642 91755 183643 89476 183643 91757 183643 91755 183644 91757 183644 91756 183644 91756 183645 91757 183645 92024 183645 91756 183646 92024 183646 88941 183646 88941 183647 92024 183647 91758 183647 88941 183648 91758 183648 91750 183648 91750 183649 91758 183649 89257 183649 91750 183650 89257 183650 89255 183650 89272 183651 89271 183651 91750 183651 91750 183652 89271 183652 89269 183652 91750 183653 89269 183653 91759 183653 89265 183654 91760 183654 89267 183654 89267 183655 91760 183655 91759 183655 89267 183656 91759 183656 89268 183656 89268 183657 91759 183657 89269 183657 89265 183658 89264 183658 91760 183658 91760 183659 89264 183659 89275 183659 91760 183660 89275 183660 91761 183660 91761 183661 89275 183661 91762 183661 91761 183662 91762 183662 88939 183662 91763 183663 91764 183663 91765 183663 91765 183664 91764 183664 88935 183664 91765 183665 88935 183665 91762 183665 91762 183666 88935 183666 88937 183666 91762 183667 88937 183667 88939 183667 91765 183668 91766 183668 91763 183668 91763 183669 91766 183669 89279 183669 91763 183670 89279 183670 88873 183670 88873 183671 89279 183671 91768 183671 88873 183672 91768 183672 91767 183672 91767 183673 91768 183673 91769 183673 91769 183674 91768 183674 89284 183674 91769 183675 89284 183675 91771 183675 89284 183676 91770 183676 91771 183676 91771 183677 91770 183677 89282 183677 91771 183678 89282 183678 91772 183678 91772 183679 89282 183679 91773 183679 91772 183680 91773 183680 91781 183680 91781 183681 91773 183681 91774 183681 91774 183682 89281 183682 91781 183682 91781 183683 89281 183683 89288 183683 91781 183684 89288 183684 91775 183684 91775 183685 89288 183685 89287 183685 91775 183686 89287 183686 91776 183686 91776 183687 91777 183687 91775 183687 91775 183688 91777 183688 91778 183688 91775 183689 91778 183689 91979 183689 91775 183690 89152 183690 91779 183690 91775 183691 91779 183691 91781 183691 91781 183692 91779 183692 89162 183692 91781 183693 89162 183693 91780 183693 91780 183694 89168 183694 91781 183694 91781 183695 89168 183695 91782 183695 91781 183696 91782 183696 91783 183696 91783 183697 91782 183697 89167 183697 91783 183698 89167 183698 91784 183698 89167 183699 91785 183699 91784 183699 91784 183700 91785 183700 89165 183700 91784 183701 89165 183701 91786 183701 91786 183702 89165 183702 89178 183702 91787 183703 89176 183703 88860 183703 88860 183704 88862 183704 91787 183704 91787 183705 88862 183705 88866 183705 91787 183706 88866 183706 91788 183706 91788 183707 88866 183707 88864 183707 91788 183708 88864 183708 91789 183708 91789 183709 88864 183709 88863 183709 91789 183710 88863 183710 89178 183710 89178 183711 88863 183711 91790 183711 89178 183712 91790 183712 91786 183712 91793 183713 91791 183713 89175 183713 89175 183714 91791 183714 91792 183714 89175 183715 91792 183715 89176 183715 89176 183716 91792 183716 88859 183716 89176 183717 88859 183717 88860 183717 89175 183718 89174 183718 91793 183718 91793 183719 89174 183719 91794 183719 91793 183720 91794 183720 91795 183720 91795 183721 91794 183721 91796 183721 91795 183722 91796 183722 88855 183722 91796 183723 89188 183723 88855 183723 88855 183724 89188 183724 91797 183724 88855 183725 91797 183725 91799 183725 89186 183726 91798 183726 91808 183726 91797 183727 89190 183727 91799 183727 91799 183728 89190 183728 91800 183728 91799 183729 91800 183729 91808 183729 91808 183730 91800 183730 89185 183730 91808 183731 89185 183731 89186 183731 91798 183732 91801 183732 91808 183732 91808 183733 91801 183733 91802 183733 91808 183734 91802 183734 91803 183734 91804 183735 91996 183735 91805 183735 91805 183736 91996 183736 91807 183736 91805 183737 91807 183737 89184 183737 89731 183738 91806 183738 91688 183738 91688 183739 91806 183739 88852 183739 91688 183740 88852 183740 91999 183740 91999 183741 88852 183741 91808 183741 91999 183742 91808 183742 91807 183742 91807 183743 91808 183743 91803 183743 91807 183744 91803 183744 89184 183744 91900 183745 91901 183745 91810 183745 91810 183746 91901 183746 89096 183746 89096 183747 91809 183747 91810 183747 91810 183748 91809 183748 89099 183748 91810 183749 89099 183749 91856 183749 91856 183750 89099 183750 89095 183750 91856 183751 89095 183751 91715 183751 91814 183752 89120 183752 91881 183752 91881 183753 89120 183753 91811 183753 91881 183754 91811 183754 91898 183754 91898 183755 91811 183755 91812 183755 91898 183756 91812 183756 91899 183756 91929 183757 91813 183757 91814 183757 91814 183758 91813 183758 89121 183758 91814 183759 89121 183759 89120 183759 91816 183760 91817 183760 91929 183760 91929 183761 91817 183761 89125 183761 91929 183762 89125 183762 91813 183762 89142 183763 89141 183763 91737 183763 91737 183764 89141 183764 91815 183764 91737 183765 91815 183765 91816 183765 91816 183766 91815 183766 89140 183766 91816 183767 89140 183767 91817 183767 91818 183768 89158 183768 91867 183768 91818 183769 91867 183769 91819 183769 89158 183770 89160 183770 91867 183770 91867 183771 89160 183771 89161 183771 91867 183772 89161 183772 91775 183772 91775 183773 89161 183773 89156 183773 91775 183774 89156 183774 89152 183774 91867 183775 91977 183775 91819 183775 91819 183776 91977 183776 91974 183776 91819 183777 91974 183777 89150 183777 89150 183778 91974 183778 91973 183778 89150 183779 91973 183779 91821 183779 91821 183780 91973 183780 91820 183780 91821 183781 91820 183781 91822 183781 91822 183782 91820 183782 91969 183782 91822 183783 91969 183783 89147 183783 89147 183784 91969 183784 91968 183784 89147 183785 91968 183785 91966 183785 91804 183786 89181 183786 91996 183786 91996 183787 89181 183787 91964 183787 91996 183788 91964 183788 91965 183788 91823 183789 89207 183789 91827 183789 91827 183790 89207 183790 89205 183790 91827 183791 89205 183791 91697 183791 91697 183792 89205 183792 89203 183792 91697 183793 89203 183793 91824 183793 92002 183794 89254 183794 92004 183794 92004 183795 89254 183795 91825 183795 92004 183796 91825 183796 91827 183796 91827 183797 91825 183797 91826 183797 91827 183798 91826 183798 91823 183798 91961 183799 89250 183799 91828 183799 91828 183800 89250 183800 91829 183800 91828 183801 91829 183801 91830 183801 91830 183802 91829 183802 89251 183802 91830 183803 89251 183803 91831 183803 91831 183804 89251 183804 89253 183804 91831 183805 89253 183805 91963 183805 91714 183806 89238 183806 91960 183806 91960 183807 89238 183807 91832 183807 91960 183808 91832 183808 91961 183808 91961 183809 91832 183809 89249 183809 91961 183810 89249 183810 89250 183810 91833 183811 89263 183811 92023 183811 92023 183812 89263 183812 91834 183812 92023 183813 91834 183813 91751 183813 91833 183814 92023 183814 91835 183814 91835 183815 92023 183815 92021 183815 91835 183816 92021 183816 91836 183816 91843 183817 89298 183817 91981 183817 91981 183818 89298 183818 91837 183818 91981 183819 91837 183819 91982 183819 91982 183820 91837 183820 89299 183820 91982 183821 89299 183821 91838 183821 91838 183822 89299 183822 91839 183822 91838 183823 91839 183823 91840 183823 91840 183824 91839 183824 89302 183824 91840 183825 89302 183825 91841 183825 91778 183826 91842 183826 91979 183826 91979 183827 91842 183827 89292 183827 91979 183828 89292 183828 91843 183828 91843 183829 89292 183829 89290 183829 91843 183830 89290 183830 89298 183830 90497 183831 90498 183831 91810 183831 90494 183832 90495 183832 91856 183832 91856 183833 90495 183833 91844 183833 91856 183834 91844 183834 91810 183834 91810 183835 91844 183835 91845 183835 91810 183836 91845 183836 90497 183836 90498 183837 91846 183837 91810 183837 91810 183838 91846 183838 91847 183838 91810 183839 91847 183839 90485 183839 91849 183840 91905 183840 91848 183840 91848 183841 91905 183841 91908 183841 91849 183842 91850 183842 91905 183842 91905 183843 91850 183843 90514 183843 91905 183844 90514 183844 91956 183844 90514 183845 91851 183845 91956 183845 91956 183846 91851 183846 90515 183846 91956 183847 90515 183847 91959 183847 91959 183848 90515 183848 91852 183848 91959 183849 91852 183849 90517 183849 90517 183850 91853 183850 91959 183850 91959 183851 91853 183851 91854 183851 91959 183852 91854 183852 91855 183852 90510 183853 90509 183853 91960 183853 90509 183854 90507 183854 91960 183854 91960 183855 90507 183855 90504 183855 91960 183856 90504 183856 90503 183856 90503 183857 90489 183857 91960 183857 91960 183858 90489 183858 90490 183858 91960 183859 90490 183859 91856 183859 91856 183860 90490 183860 91857 183860 91856 183861 91857 183861 90494 183861 91872 183862 90477 183862 91858 183862 91858 183863 90477 183863 90479 183863 91858 183864 90479 183864 90481 183864 90481 183865 91859 183865 91858 183865 91858 183866 91859 183866 90483 183866 91858 183867 90483 183867 90473 183867 91978 183868 90471 183868 91979 183868 90471 183869 91860 183869 91979 183869 91979 183870 91860 183870 91861 183870 91979 183871 91861 183871 90453 183871 90453 183872 90457 183872 91979 183872 91979 183873 90457 183873 90458 183873 91979 183874 90458 183874 91775 183874 91775 183875 90458 183875 91862 183875 91775 183876 91862 183876 90462 183876 90462 183877 91863 183877 91775 183877 91775 183878 91863 183878 91864 183878 91775 183879 91864 183879 91867 183879 91867 183880 91864 183880 91865 183880 91867 183881 91865 183881 91866 183881 91866 183882 90466 183882 91867 183882 91867 183883 90466 183883 91868 183883 91867 183884 91868 183884 90468 183884 90469 183885 91869 183885 91976 183885 91976 183886 91869 183886 91870 183886 91870 183887 91871 183887 91976 183887 91976 183888 91871 183888 91873 183888 91976 183889 91873 183889 91872 183889 91872 183890 91873 183890 90476 183890 91872 183891 90476 183891 90477 183891 91671 183892 88468 183892 88469 183892 91926 183893 91680 183893 89090 183893 91875 183894 91926 183894 91874 183894 91874 183895 91926 183895 89090 183895 91874 183896 89090 183896 89088 183896 88566 183897 88564 183897 91875 183897 91875 183898 88564 183898 91669 183898 91875 183899 91669 183899 91926 183899 91926 183900 91669 183900 91670 183900 91925 183901 91877 183901 91878 183901 91876 183902 91647 183902 91878 183902 91876 183903 91878 183903 91668 183903 91668 183904 91878 183904 91877 183904 91668 183905 91877 183905 88477 183905 91647 183906 91646 183906 91878 183906 91878 183907 91646 183907 91879 183907 91878 183908 91879 183908 91639 183908 91881 183909 91880 183909 91663 183909 91663 183910 91661 183910 91881 183910 91881 183911 91661 183911 91882 183911 91881 183912 91882 183912 91658 183912 91658 183913 91883 183913 91881 183913 91881 183914 91883 183914 91657 183914 91881 183915 91657 183915 91660 183915 91672 183916 91884 183916 91885 183916 88472 183917 91926 183917 91886 183917 91886 183918 91926 183918 91887 183918 91886 183919 91887 183919 88165 183919 91888 183920 91894 183920 91926 183920 91889 183921 91926 183921 91890 183921 91890 183922 91926 183922 88472 183922 91890 183923 88472 183923 88575 183923 91885 183924 91888 183924 91672 183924 91672 183925 91888 183925 91926 183925 91672 183926 91926 183926 91891 183926 91891 183927 91926 183927 91889 183927 91891 183928 91889 183928 91892 183928 91892 183929 91889 183929 91893 183929 88570 183930 90191 183930 91894 183930 91894 183931 90191 183931 91895 183931 91894 183932 91895 183932 91926 183932 91926 183933 91895 183933 91671 183933 91926 183934 91671 183934 91680 183934 91680 183935 91671 183935 88469 183935 88167 183936 91664 183936 91898 183936 91898 183937 91664 183937 91896 183937 91898 183938 91896 183938 91881 183938 91881 183939 91896 183939 91665 183939 91881 183940 91665 183940 91880 183940 88167 183941 91898 183941 91897 183941 91897 183942 91898 183942 91899 183942 91897 183943 91899 183943 91902 183943 88504 183944 88505 183944 91900 183944 91900 183945 88505 183945 91903 183945 91812 183946 91901 183946 91899 183946 91899 183947 91901 183947 91900 183947 91899 183948 91900 183948 91902 183948 91902 183949 91900 183949 91903 183949 88489 183950 91905 183950 91904 183950 91904 183951 91905 183951 88485 183951 88500 183952 91905 183952 88490 183952 88490 183953 91905 183953 88489 183953 91906 183954 91907 183954 91909 183954 88499 183955 88498 183955 91810 183955 88500 183956 88499 183956 91810 183956 88500 183957 91810 183957 91905 183957 91905 183958 91810 183958 90485 183958 91905 183959 90485 183959 91908 183959 88498 183960 91906 183960 91810 183960 91810 183961 91906 183961 91909 183961 91810 183962 91909 183962 91900 183962 91900 183963 91909 183963 91681 183963 91900 183964 91681 183964 91683 183964 91683 183965 88501 183965 91900 183965 91900 183966 88501 183966 88502 183966 91900 183967 88502 183967 88504 183967 91685 183968 91684 183968 91958 183968 91958 183969 91684 183969 88510 183969 91958 183970 88510 183970 91910 183970 91910 183971 88196 183971 91958 183971 91958 183972 88196 183972 91676 183972 91958 183973 91676 183973 91675 183973 88514 183974 88493 183974 91958 183974 88514 183975 91958 183975 88512 183975 88512 183976 91958 183976 91675 183976 88512 183977 91675 183977 91911 183977 91912 183978 91913 183978 91905 183978 91905 183979 91913 183979 88201 183979 91905 183980 88201 183980 88485 183980 91651 183981 91652 183981 91905 183981 91905 183982 91652 183982 88491 183982 91905 183983 88491 183983 91912 183983 88507 183984 91685 183984 91635 183984 91635 183985 91685 183985 91918 183985 91635 183986 91918 183986 91636 183986 91639 183987 91645 183987 91878 183987 91878 183988 91645 183988 91914 183988 91878 183989 91914 183989 91915 183989 91915 183990 91914 183990 91644 183990 91915 183991 91644 183991 91642 183991 91642 183992 91916 183992 91915 183992 91915 183993 91916 183993 91917 183993 91915 183994 91917 183994 91918 183994 91918 183995 91917 183995 91919 183995 91918 183996 91919 183996 91636 183996 91816 183997 92020 183997 91737 183997 91737 183998 92020 183998 91921 183998 91737 183999 91921 183999 91920 183999 91920 184000 91921 184000 92022 184000 91920 184001 92022 184001 91922 184001 91922 184002 92022 184002 91923 184002 91922 184003 91923 184003 91924 184003 91924 184004 91923 184004 92025 184004 91924 184005 92025 184005 91741 184005 91741 184006 92025 184006 92026 184006 91741 184007 92026 184007 89419 184007 88479 184008 88480 184008 91670 184008 91670 184009 88480 184009 91925 184009 91670 184010 91925 184010 91926 184010 91926 184011 91925 184011 91878 184011 91926 184012 91878 184012 91927 184012 91927 184013 91878 184013 91945 184013 91927 184014 91945 184014 91928 184014 91928 184015 91945 184015 91930 184015 91660 184016 91887 184016 91881 184016 91881 184017 91887 184017 91926 184017 91881 184018 91926 184018 91814 184018 91814 184019 91926 184019 91927 184019 91814 184020 91927 184020 91929 184020 91929 184021 91927 184021 91928 184021 91929 184022 91928 184022 91816 184022 91816 184023 91928 184023 91930 184023 91816 184024 91930 184024 92020 184024 91931 184025 91932 184025 91933 184025 91933 184026 91932 184026 91934 184026 91933 184027 91934 184027 91951 184027 91951 184028 91934 184028 91935 184028 91951 184029 91935 184029 91936 184029 91936 184030 91935 184030 91938 184030 91936 184031 91938 184031 91937 184031 91937 184032 91938 184032 92010 184032 91937 184033 92010 184033 91955 184033 91955 184034 92010 184034 91939 184034 91955 184035 91939 184035 91940 184035 91940 184036 91939 184036 92011 184036 91940 184037 92011 184037 91957 184037 91957 184038 92011 184038 91941 184038 91957 184039 91941 184039 91958 184039 91958 184040 91941 184040 91942 184040 91958 184041 91942 184041 91685 184041 91685 184042 91942 184042 92015 184042 91685 184043 92015 184043 91918 184043 91918 184044 92015 184044 91943 184044 91918 184045 91943 184045 91915 184045 91915 184046 91943 184046 91944 184046 91915 184047 91944 184047 91878 184047 91878 184048 91944 184048 92017 184048 91878 184049 92017 184049 91945 184049 91945 184050 92017 184050 92018 184050 91945 184051 92018 184051 91930 184051 91930 184052 92018 184052 92019 184052 91930 184053 92019 184053 92020 184053 92000 184054 91946 184054 91699 184054 91699 184055 91946 184055 91947 184055 91699 184056 91947 184056 91948 184056 91948 184057 91947 184057 91998 184057 91948 184058 91998 184058 91697 184058 91697 184059 91998 184059 91949 184059 91697 184060 91949 184060 91827 184060 91827 184061 91949 184061 91997 184061 91827 184062 91997 184062 92004 184062 92004 184063 91997 184063 92005 184063 92003 184064 91931 184064 91962 184064 91962 184065 91931 184065 91933 184065 91962 184066 91933 184066 91950 184066 91950 184067 91933 184067 91951 184067 91950 184068 91951 184068 91952 184068 91952 184069 91951 184069 91936 184069 91952 184070 91936 184070 91953 184070 91953 184071 91936 184071 91937 184071 91953 184072 91937 184072 91954 184072 91954 184073 91937 184073 91955 184073 91954 184074 91955 184074 91959 184074 91959 184075 91955 184075 91940 184075 91959 184076 91940 184076 91956 184076 91956 184077 91940 184077 91957 184077 91956 184078 91957 184078 91905 184078 91905 184079 91957 184079 91958 184079 91905 184080 91958 184080 91651 184080 91651 184081 91958 184081 88493 184081 91855 184082 90510 184082 91959 184082 91959 184083 90510 184083 91960 184083 91959 184084 91960 184084 91954 184084 91954 184085 91960 184085 91961 184085 91954 184086 91961 184086 91953 184086 91953 184087 91961 184087 91828 184087 91953 184088 91828 184088 91952 184088 91952 184089 91828 184089 91830 184089 91952 184090 91830 184090 91950 184090 91950 184091 91830 184091 91831 184091 91950 184092 91831 184092 91962 184092 91962 184093 91831 184093 91963 184093 91962 184094 91963 184094 92003 184094 91964 184095 89180 184095 91965 184095 91965 184096 89180 184096 91966 184096 91965 184097 91966 184097 91967 184097 91967 184098 91966 184098 91968 184098 91967 184099 91968 184099 91995 184099 91995 184100 91968 184100 91969 184100 91995 184101 91969 184101 91970 184101 91970 184102 91969 184102 91820 184102 91970 184103 91820 184103 91971 184103 91971 184104 91820 184104 91973 184104 91971 184105 91973 184105 91972 184105 91972 184106 91973 184106 91974 184106 91972 184107 91974 184107 91975 184107 91975 184108 91974 184108 91977 184108 91975 184109 91977 184109 91976 184109 91976 184110 91977 184110 91867 184110 91976 184111 91867 184111 90469 184111 90469 184112 91867 184112 90468 184112 90473 184113 91978 184113 91858 184113 91858 184114 91978 184114 91979 184114 91858 184115 91979 184115 91980 184115 91980 184116 91979 184116 91843 184116 91980 184117 91843 184117 91991 184117 91991 184118 91843 184118 91981 184118 91991 184119 91981 184119 91989 184119 91989 184120 91981 184120 91982 184120 91989 184121 91982 184121 91983 184121 91983 184122 91982 184122 91838 184122 91983 184123 91838 184123 91984 184123 91984 184124 91838 184124 91840 184124 91984 184125 91840 184125 91985 184125 91985 184126 91840 184126 91841 184126 89302 184127 91836 184127 91841 184127 91841 184128 91836 184128 92021 184128 91841 184129 92021 184129 91985 184129 91985 184130 92021 184130 91986 184130 91985 184131 91986 184131 91984 184131 91984 184132 91986 184132 91987 184132 91984 184133 91987 184133 91983 184133 91983 184134 91987 184134 91988 184134 91983 184135 91988 184135 91989 184135 91989 184136 91988 184136 91990 184136 91989 184137 91990 184137 91991 184137 91991 184138 91990 184138 92016 184138 91991 184139 92016 184139 91980 184139 91980 184140 92016 184140 92014 184140 91980 184141 92014 184141 91858 184141 91858 184142 92014 184142 92013 184142 91858 184143 92013 184143 91872 184143 91872 184144 92013 184144 92012 184144 91872 184145 92012 184145 91976 184145 91976 184146 92012 184146 91992 184146 91976 184147 91992 184147 91975 184147 91975 184148 91992 184148 91993 184148 91975 184149 91993 184149 91972 184149 91972 184150 91993 184150 92009 184150 91972 184151 92009 184151 91971 184151 91971 184152 92009 184152 91994 184152 91971 184153 91994 184153 91970 184153 91970 184154 91994 184154 92008 184154 91970 184155 92008 184155 91995 184155 91995 184156 92008 184156 92007 184156 91995 184157 92007 184157 91967 184157 91967 184158 92007 184158 92006 184158 91967 184159 92006 184159 91965 184159 91965 184160 92006 184160 92005 184160 91965 184161 92005 184161 91996 184161 91996 184162 92005 184162 91997 184162 91996 184163 91997 184163 91807 184163 91807 184164 91997 184164 91949 184164 91807 184165 91949 184165 91999 184165 91999 184166 91949 184166 91998 184166 91999 184167 91998 184167 91688 184167 91688 184168 91998 184168 91947 184168 91688 184169 91947 184169 91686 184169 91686 184170 91947 184170 91946 184170 91686 184171 91946 184171 92001 184171 92001 184172 91946 184172 92000 184172 92001 184173 92000 184173 89728 184173 89728 184174 92000 184174 91693 184174 89728 184175 91693 184175 89723 184175 89253 184176 89254 184176 91963 184176 91963 184177 89254 184177 92002 184177 91963 184178 92002 184178 92003 184178 92003 184179 92002 184179 92004 184179 92003 184180 92004 184180 91931 184180 91931 184181 92004 184181 92005 184181 91931 184182 92005 184182 91932 184182 91932 184183 92005 184183 92006 184183 91932 184184 92006 184184 91934 184184 91934 184185 92006 184185 92007 184185 91934 184186 92007 184186 91935 184186 91935 184187 92007 184187 92008 184187 91935 184188 92008 184188 91938 184188 91938 184189 92008 184189 91994 184189 91938 184190 91994 184190 92010 184190 92010 184191 91994 184191 92009 184191 92010 184192 92009 184192 91939 184192 91939 184193 92009 184193 91993 184193 91939 184194 91993 184194 92011 184194 92011 184195 91993 184195 91992 184195 92011 184196 91992 184196 91941 184196 91941 184197 91992 184197 92012 184197 91941 184198 92012 184198 91942 184198 91942 184199 92012 184199 92013 184199 91942 184200 92013 184200 92015 184200 92015 184201 92013 184201 92014 184201 92015 184202 92014 184202 91943 184202 91943 184203 92014 184203 92016 184203 91943 184204 92016 184204 91944 184204 91944 184205 92016 184205 91990 184205 91944 184206 91990 184206 92017 184206 92017 184207 91990 184207 91988 184207 92017 184208 91988 184208 92018 184208 92018 184209 91988 184209 91987 184209 92018 184210 91987 184210 92019 184210 92019 184211 91987 184211 91986 184211 92019 184212 91986 184212 92020 184212 92020 184213 91986 184213 92021 184213 92020 184214 92021 184214 91921 184214 91921 184215 92021 184215 92023 184215 91921 184216 92023 184216 92022 184216 92022 184217 92023 184217 91758 184217 92022 184218 91758 184218 91923 184218 91923 184219 91758 184219 92024 184219 91923 184220 92024 184220 92025 184220 92025 184221 92024 184221 91757 184221 92025 184222 91757 184222 92026 184222 92026 184223 91757 184223 91745 184223 92026 184224 91745 184224 89419 184224 89419 184225 91745 184225 91748 184225 92115 184226 92063 184226 92027 184226 92073 184227 92107 184227 92072 184227 92028 184228 92029 184228 92027 184228 92082 184229 92121 184229 92059 184229 92053 184230 92521 184230 85570 184230 92030 184231 92118 184231 92055 184231 92118 184232 92030 184232 85574 184232 92031 184233 92513 184233 92036 184233 92045 184234 92047 184234 92511 184234 92511 184235 85561 184235 92045 184235 92045 184236 85561 184236 92510 184236 92045 184237 92510 184237 85101 184237 92031 184238 92036 184238 92515 184238 92035 184239 92032 184239 92036 184239 92036 184240 92032 184240 92033 184240 92036 184241 92033 184241 92515 184241 92037 184242 85117 184242 92034 184242 92034 184243 92035 184243 92037 184243 92037 184244 92035 184244 92036 184244 92037 184245 92036 184245 92038 184245 92038 184246 92036 184246 92513 184246 92038 184247 92513 184247 92047 184247 92047 184248 92513 184248 85565 184248 92047 184249 85565 184249 92511 184249 92089 184250 92090 184250 92040 184250 92040 184251 92090 184251 92091 184251 92087 184252 92089 184252 92041 184252 92041 184253 92089 184253 92040 184253 92041 184254 92040 184254 92039 184254 92039 184255 92040 184255 92091 184255 92039 184256 92091 184256 92538 184256 92039 184257 92535 184257 92041 184257 92041 184258 92535 184258 92048 184258 92041 184259 92048 184259 92087 184259 92087 184260 92048 184260 92043 184260 92087 184261 92043 184261 92042 184261 92042 184262 92043 184262 92044 184262 92042 184263 92044 184263 92046 184263 92519 184264 92052 184264 85101 184264 85101 184265 92052 184265 92085 184265 85101 184266 92085 184266 92045 184266 92045 184267 92085 184267 92046 184267 92045 184268 92046 184268 92047 184268 92047 184269 92046 184269 92044 184269 92047 184270 92044 184270 92038 184270 92038 184271 92044 184271 92043 184271 92038 184272 92043 184272 92037 184272 92037 184273 92043 184273 92048 184273 92037 184274 92048 184274 85117 184274 85117 184275 92048 184275 92535 184275 92056 184276 92088 184276 92057 184276 92057 184277 92088 184277 92086 184277 92057 184278 92086 184278 92058 184278 92058 184279 92086 184279 92049 184279 92058 184280 92049 184280 92050 184280 92050 184281 92049 184281 92051 184281 92050 184282 92051 184282 92084 184282 92519 184283 92521 184283 92052 184283 92052 184284 92521 184284 92053 184284 92052 184285 92053 184285 92083 184285 92083 184286 92053 184286 85570 184286 92083 184287 85570 184287 92081 184287 92081 184288 85570 184288 92054 184288 92081 184289 92054 184289 92055 184289 92055 184290 92054 184290 92522 184290 92055 184291 92522 184291 92030 184291 92127 184292 92056 184292 92126 184292 92126 184293 92056 184293 92057 184293 92126 184294 92057 184294 92125 184294 92125 184295 92057 184295 92058 184295 92125 184296 92058 184296 92123 184296 92123 184297 92058 184297 92050 184297 92123 184298 92050 184298 92059 184298 92059 184299 92050 184299 92084 184299 92059 184300 92084 184300 92082 184300 92060 184301 92061 184301 92114 184301 92114 184302 92061 184302 92113 184302 92066 184303 92062 184303 92171 184303 92171 184304 92062 184304 92028 184304 92171 184305 92028 184305 92172 184305 92172 184306 92028 184306 92027 184306 92172 184307 92027 184307 92182 184307 92182 184308 92027 184308 92063 184308 92107 184309 92073 184309 92106 184309 92106 184310 92073 184310 92064 184310 92106 184311 92064 184311 92065 184311 92029 184312 92028 184312 92060 184312 92060 184313 92028 184313 92062 184313 92060 184314 92062 184314 92061 184314 92061 184315 92062 184315 92066 184315 92061 184316 92066 184316 92113 184316 92113 184317 92066 184317 92177 184317 92113 184318 92177 184318 92111 184318 92111 184319 92177 184319 92067 184319 92111 184320 92067 184320 92110 184320 92110 184321 92067 184321 92068 184321 92110 184322 92068 184322 92070 184322 92070 184323 92068 184323 92069 184323 92070 184324 92069 184324 92071 184324 92071 184325 92069 184325 92219 184325 92071 184326 92219 184326 92108 184326 92108 184327 92219 184327 92133 184327 92108 184328 92133 184328 92072 184328 92072 184329 92133 184329 92134 184329 92072 184330 92134 184330 92073 184330 92073 184331 92134 184331 92173 184331 92073 184332 92173 184332 92064 184332 92064 184333 92173 184333 92074 184333 92064 184334 92074 184334 92065 184334 92544 184335 92075 184335 92076 184335 92076 184336 92075 184336 92104 184336 92076 184337 92104 184337 92077 184337 92077 184338 92104 184338 92102 184338 92077 184339 92102 184339 92078 184339 92078 184340 92102 184340 92079 184340 92078 184341 92079 184341 92080 184341 92080 184342 92079 184342 92100 184342 92080 184343 92100 184343 92109 184343 92055 184344 92119 184344 92081 184344 92081 184345 92119 184345 92082 184345 92081 184346 92082 184346 92083 184346 92083 184347 92082 184347 92084 184347 92083 184348 92084 184348 92052 184348 92052 184349 92084 184349 92051 184349 92052 184350 92051 184350 92085 184350 92085 184351 92051 184351 92049 184351 92085 184352 92049 184352 92046 184352 92046 184353 92049 184353 92086 184353 92046 184354 92086 184354 92042 184354 92042 184355 92086 184355 92088 184355 92042 184356 92088 184356 92087 184356 92087 184357 92088 184357 92056 184357 92087 184358 92056 184358 92089 184358 92089 184359 92056 184359 92127 184359 92089 184360 92127 184360 92090 184360 92090 184361 92127 184361 92129 184361 92090 184362 92129 184362 92091 184362 92091 184363 92129 184363 92092 184363 92091 184364 92092 184364 92538 184364 92538 184365 92092 184365 92539 184365 92105 184366 92093 184366 92094 184366 92094 184367 92093 184367 92131 184367 92094 184368 92131 184368 92103 184368 92103 184369 92131 184369 92130 184369 92103 184370 92130 184370 92101 184370 92101 184371 92130 184371 92128 184371 92101 184372 92128 184372 92095 184372 92095 184373 92128 184373 92096 184373 92095 184374 92096 184374 92097 184374 92120 184375 92112 184375 92122 184375 92122 184376 92112 184376 92098 184376 92122 184377 92098 184377 92124 184377 92124 184378 92098 184378 92099 184378 92124 184379 92099 184379 92097 184379 92097 184380 92099 184380 92109 184380 92097 184381 92109 184381 92095 184381 92095 184382 92109 184382 92100 184382 92095 184383 92100 184383 92101 184383 92101 184384 92100 184384 92079 184384 92101 184385 92079 184385 92103 184385 92103 184386 92079 184386 92102 184386 92103 184387 92102 184387 92094 184387 92094 184388 92102 184388 92104 184388 92094 184389 92104 184389 92105 184389 92105 184390 92104 184390 92075 184390 92065 184391 92544 184391 92106 184391 92106 184392 92544 184392 92076 184392 92106 184393 92076 184393 92107 184393 92107 184394 92076 184394 92077 184394 92107 184395 92077 184395 92072 184395 92072 184396 92077 184396 92078 184396 92072 184397 92078 184397 92108 184397 92108 184398 92078 184398 92080 184398 92108 184399 92080 184399 92071 184399 92071 184400 92080 184400 92109 184400 92071 184401 92109 184401 92070 184401 92070 184402 92109 184402 92099 184402 92070 184403 92099 184403 92110 184403 92110 184404 92099 184404 92098 184404 92110 184405 92098 184405 92111 184405 92111 184406 92098 184406 92112 184406 92111 184407 92112 184407 92113 184407 92113 184408 92112 184408 92120 184408 92113 184409 92120 184409 92114 184409 92416 184410 92115 184410 92415 184410 92415 184411 92115 184411 92027 184411 92415 184412 92027 184412 92116 184412 92116 184413 92027 184413 92117 184413 85574 184414 92117 184414 92118 184414 92118 184415 92117 184415 92027 184415 92118 184416 92027 184416 92055 184416 92055 184417 92027 184417 92029 184417 92055 184418 92029 184418 92119 184418 92119 184419 92029 184419 92060 184419 92119 184420 92060 184420 92082 184420 92082 184421 92060 184421 92114 184421 92082 184422 92114 184422 92121 184422 92121 184423 92114 184423 92120 184423 92121 184424 92120 184424 92059 184424 92059 184425 92120 184425 92122 184425 92059 184426 92122 184426 92123 184426 92123 184427 92122 184427 92124 184427 92123 184428 92124 184428 92125 184428 92125 184429 92124 184429 92097 184429 92125 184430 92097 184430 92126 184430 92126 184431 92097 184431 92096 184431 92126 184432 92096 184432 92127 184432 92127 184433 92096 184433 92128 184433 92127 184434 92128 184434 92129 184434 92129 184435 92128 184435 92130 184435 92129 184436 92130 184436 92092 184436 92092 184437 92130 184437 92131 184437 92092 184438 92131 184438 92539 184438 92539 184439 92131 184439 92093 184439 92206 184440 92164 184440 92207 184440 92132 184441 92174 184441 92133 184441 92133 184442 92174 184442 92134 184442 92068 184443 92067 184443 92135 184443 92135 184444 92067 184444 92177 184444 92136 184445 92228 184445 92137 184445 92136 184446 92137 184446 92543 184446 92543 184447 92137 184447 92138 184447 92543 184448 92138 184448 92542 184448 92542 184449 92138 184449 92139 184449 92542 184450 92139 184450 92140 184450 92140 184451 92139 184451 92142 184451 92140 184452 92142 184452 92141 184452 92142 184453 92198 184453 92141 184453 92141 184454 92198 184454 92197 184454 92141 184455 92197 184455 84997 184455 84997 184456 92197 184456 92196 184456 84997 184457 92196 184457 92533 184457 92533 184458 92196 184458 92193 184458 92533 184459 92193 184459 92143 184459 92161 184460 92541 184460 92159 184460 92159 184461 92541 184461 92144 184461 92159 184462 92144 184462 92158 184462 92500 184463 92499 184463 92161 184463 92161 184464 92499 184464 92145 184464 92161 184465 92145 184465 92541 184465 85009 184466 92146 184466 92147 184466 92147 184467 92146 184467 92502 184467 85000 184468 92508 184468 92169 184468 92169 184469 92508 184469 92148 184469 92504 184470 92505 184470 92149 184470 92149 184471 92505 184471 92507 184471 92149 184472 92168 184472 92150 184472 92167 184473 92497 184473 92150 184473 92150 184474 92497 184474 85547 184474 92150 184475 85547 184475 92149 184475 92149 184476 85547 184476 92151 184476 92149 184477 92151 184477 92504 184477 92152 184478 92153 184478 92154 184478 92201 184479 92236 184479 92154 184479 92154 184480 92236 184480 92155 184480 92154 184481 92155 184481 92152 184481 92152 184482 92155 184482 92156 184482 92152 184483 92156 184483 92157 184483 92158 184484 92194 184484 92159 184484 92159 184485 92194 184485 92160 184485 92159 184486 92160 184486 92161 184486 92148 184487 92218 184487 92169 184487 92169 184488 92218 184488 92162 184488 92169 184489 92162 184489 92163 184489 92163 184490 92162 184490 92216 184490 92163 184491 92216 184491 92215 184491 92214 184492 92164 184492 92165 184492 92165 184493 92164 184493 92206 184493 92165 184494 92206 184494 92204 184494 92204 184495 92202 184495 92165 184495 92165 184496 92202 184496 92166 184496 92165 184497 92166 184497 92214 184497 92214 184498 92166 184498 92215 184498 92202 184499 92167 184499 92166 184499 92166 184500 92167 184500 92150 184500 92166 184501 92150 184501 92215 184501 92215 184502 92150 184502 92168 184502 92215 184503 92168 184503 92163 184503 92163 184504 92168 184504 92149 184504 92163 184505 92149 184505 92169 184505 92169 184506 92149 184506 92507 184506 92169 184507 92507 184507 85000 184507 92180 184508 92183 184508 92238 184508 92183 184509 92493 184509 92238 184509 92238 184510 92493 184510 85004 184510 92238 184511 85004 184511 92495 184511 92180 184512 92237 184512 92178 184512 92178 184513 92237 184513 92224 184513 92178 184514 92224 184514 92223 184514 92181 184515 92179 184515 92066 184515 92066 184516 92179 184516 92170 184516 92066 184517 92170 184517 92177 184517 92066 184518 92171 184518 92181 184518 92181 184519 92171 184519 92172 184519 92181 184520 92172 184520 92182 184520 92074 184521 92173 184521 92227 184521 92227 184522 92173 184522 92134 184522 92227 184523 92134 184523 92231 184523 92231 184524 92134 184524 92174 184524 92231 184525 92174 184525 92232 184525 92232 184526 92174 184526 92132 184526 92069 184527 92068 184527 92175 184527 92175 184528 92068 184528 92135 184528 92175 184529 92135 184529 92176 184529 92176 184530 92135 184530 92177 184530 92176 184531 92177 184531 92223 184531 92223 184532 92177 184532 92170 184532 92223 184533 92170 184533 92178 184533 92178 184534 92170 184534 92179 184534 92178 184535 92179 184535 92180 184535 92180 184536 92179 184536 92181 184536 92180 184537 92181 184537 92183 184537 92183 184538 92181 184538 92182 184538 92183 184539 92182 184539 92063 184539 92229 184540 92230 184540 92184 184540 92184 184541 92230 184541 92185 184541 92184 184542 92185 184542 92186 184542 92186 184543 92185 184543 92213 184543 92186 184544 92213 184544 92199 184544 92199 184545 92213 184545 92187 184545 85009 184546 92500 184546 92146 184546 92146 184547 92500 184547 92161 184547 92146 184548 92161 184548 92188 184548 92188 184549 92161 184549 92160 184549 92188 184550 92160 184550 92217 184550 92217 184551 92160 184551 92194 184551 92217 184552 92194 184552 92189 184552 92189 184553 92194 184553 92195 184553 92189 184554 92195 184554 92190 184554 92190 184555 92195 184555 92191 184555 92190 184556 92191 184556 92187 184556 92187 184557 92191 184557 92192 184557 92187 184558 92192 184558 92199 184558 92144 184559 92143 184559 92158 184559 92158 184560 92143 184560 92193 184560 92158 184561 92193 184561 92194 184561 92194 184562 92193 184562 92196 184562 92194 184563 92196 184563 92195 184563 92195 184564 92196 184564 92197 184564 92195 184565 92197 184565 92191 184565 92191 184566 92197 184566 92198 184566 92191 184567 92198 184567 92192 184567 92192 184568 92198 184568 92142 184568 92192 184569 92142 184569 92199 184569 92199 184570 92142 184570 92139 184570 92199 184571 92139 184571 92186 184571 92186 184572 92139 184572 92138 184572 92186 184573 92138 184573 92184 184573 92184 184574 92138 184574 92137 184574 92184 184575 92137 184575 92229 184575 92229 184576 92137 184576 92228 184576 92203 184577 92205 184577 92234 184577 92234 184578 92205 184578 92200 184578 92234 184579 92200 184579 92233 184579 92153 184580 92497 184580 92154 184580 92154 184581 92497 184581 92167 184581 92154 184582 92167 184582 92201 184582 92201 184583 92167 184583 92202 184583 92201 184584 92202 184584 92203 184584 92203 184585 92202 184585 92204 184585 92203 184586 92204 184586 92205 184586 92205 184587 92204 184587 92206 184587 92205 184588 92206 184588 92200 184588 92200 184589 92206 184589 92207 184589 92200 184590 92207 184590 92233 184590 92233 184591 92207 184591 92208 184591 92233 184592 92208 184592 92209 184592 92133 184593 92219 184593 92132 184593 92132 184594 92219 184594 92211 184594 92132 184595 92211 184595 92210 184595 92210 184596 92211 184596 92220 184596 92210 184597 92220 184597 92212 184597 92212 184598 92220 184598 92221 184598 92212 184599 92221 184599 92222 184599 92230 184600 92209 184600 92185 184600 92185 184601 92209 184601 92208 184601 92185 184602 92208 184602 92213 184602 92213 184603 92208 184603 92207 184603 92213 184604 92207 184604 92187 184604 92187 184605 92207 184605 92164 184605 92187 184606 92164 184606 92190 184606 92190 184607 92164 184607 92214 184607 92190 184608 92214 184608 92189 184608 92189 184609 92214 184609 92215 184609 92189 184610 92215 184610 92217 184610 92217 184611 92215 184611 92216 184611 92217 184612 92216 184612 92188 184612 92188 184613 92216 184613 92162 184613 92188 184614 92162 184614 92146 184614 92146 184615 92162 184615 92218 184615 92146 184616 92218 184616 92502 184616 92219 184617 92069 184617 92211 184617 92211 184618 92069 184618 92175 184618 92211 184619 92175 184619 92220 184619 92220 184620 92175 184620 92176 184620 92220 184621 92176 184621 92221 184621 92221 184622 92176 184622 92223 184622 92221 184623 92223 184623 92222 184623 92222 184624 92223 184624 92224 184624 92222 184625 92224 184625 92235 184625 92235 184626 92224 184626 92237 184626 92063 184627 92115 184627 92183 184627 92183 184628 92115 184628 92416 184628 92183 184629 92416 184629 92225 184629 92225 184630 92311 184630 92183 184630 92183 184631 92311 184631 92226 184631 92183 184632 92226 184632 92493 184632 92136 184633 92074 184633 92228 184633 92228 184634 92074 184634 92227 184634 92228 184635 92227 184635 92229 184635 92229 184636 92227 184636 92231 184636 92229 184637 92231 184637 92230 184637 92230 184638 92231 184638 92232 184638 92230 184639 92232 184639 92209 184639 92209 184640 92232 184640 92132 184640 92209 184641 92132 184641 92233 184641 92233 184642 92132 184642 92210 184642 92233 184643 92210 184643 92234 184643 92234 184644 92210 184644 92212 184644 92234 184645 92212 184645 92203 184645 92203 184646 92212 184646 92222 184646 92203 184647 92222 184647 92201 184647 92201 184648 92222 184648 92235 184648 92201 184649 92235 184649 92236 184649 92236 184650 92235 184650 92237 184650 92236 184651 92237 184651 92155 184651 92155 184652 92237 184652 92180 184652 92155 184653 92180 184653 92156 184653 92156 184654 92180 184654 92238 184654 92156 184655 92238 184655 92157 184655 92157 184656 92238 184656 92495 184656 92414 184657 92412 184657 92313 184657 92258 184658 92290 184658 92289 184658 92493 184659 92226 184659 92310 184659 92310 184660 92226 184660 92312 184660 92310 184661 92312 184661 92239 184661 92307 184662 92305 184662 92489 184662 92489 184663 92305 184663 92303 184663 92489 184664 92303 184664 92490 184664 92490 184665 92303 184665 92269 184665 92240 184666 85543 184666 92269 184666 92269 184667 85543 184667 92241 184667 92269 184668 92241 184668 92490 184668 84379 184669 92243 184669 92242 184669 92242 184670 92243 184670 92476 184670 92242 184671 92476 184671 92269 184671 92269 184672 92476 184672 84378 184672 92269 184673 84378 184673 92240 184673 92301 184674 92244 184674 85534 184674 92244 184675 92301 184675 92483 184675 92483 184676 92301 184676 92284 184676 92483 184677 92284 184677 85530 184677 85530 184678 92284 184678 92245 184678 85530 184679 92245 184679 92460 184679 92245 184680 92246 184680 92460 184680 92460 184681 92246 184681 92247 184681 92460 184682 92247 184682 92462 184682 92462 184683 92247 184683 92463 184683 92463 184684 92247 184684 92283 184684 92463 184685 92283 184685 92248 184685 92248 184686 92283 184686 92249 184686 92248 184687 92249 184687 92281 184687 92467 184688 92250 184688 85524 184688 85524 184689 92250 184689 92323 184689 92251 184690 92256 184690 92326 184690 92326 184691 92256 184691 92254 184691 92326 184692 92254 184692 92252 184692 92252 184693 92254 184693 92250 184693 92252 184694 92250 184694 92466 184694 92466 184695 92250 184695 92467 184695 92253 184696 92318 184696 92255 184696 92255 184697 92318 184697 92320 184697 92255 184698 92320 184698 92322 184698 92323 184699 92250 184699 92322 184699 92322 184700 92250 184700 92254 184700 92322 184701 92254 184701 92255 184701 92255 184702 92254 184702 92256 184702 92255 184703 92256 184703 92253 184703 92253 184704 92256 184704 92251 184704 92253 184705 92251 184705 92257 184705 92291 184706 92290 184706 92259 184706 92259 184707 92290 184707 92258 184707 92259 184708 92258 184708 92333 184708 92333 184709 92264 184709 92259 184709 92259 184710 92264 184710 92263 184710 92259 184711 92263 184711 92291 184711 92291 184712 92263 184712 92261 184712 92260 184713 92261 184713 92262 184713 92262 184714 92261 184714 92263 184714 92262 184715 92263 184715 92315 184715 92315 184716 92263 184716 92264 184716 92315 184717 92264 184717 92334 184717 92334 184718 92264 184718 92333 184718 92338 184719 92336 184719 92266 184719 92371 184720 92265 184720 92334 184720 92336 184721 92335 184721 92266 184721 92266 184722 92335 184722 92294 184722 92266 184723 92294 184723 92295 184723 92295 184724 92300 184724 92266 184724 92266 184725 92300 184725 92267 184725 92266 184726 92267 184726 92338 184726 92338 184727 92267 184727 92313 184727 92338 184728 92313 184728 92268 184728 92268 184729 92313 184729 92412 184729 92303 184730 92302 184730 92269 184730 92269 184731 92302 184731 92270 184731 92269 184732 92270 184732 92242 184732 92242 184733 92270 184733 92480 184733 92242 184734 92480 184734 84379 184734 92271 184735 92285 184735 92331 184735 92271 184736 92272 184736 92273 184736 92273 184737 92272 184737 92274 184737 92273 184738 92274 184738 92275 184738 92275 184739 92274 184739 92276 184739 92275 184740 92276 184740 92277 184740 92277 184741 92276 184741 92327 184741 92277 184742 92327 184742 92278 184742 92278 184743 92327 184743 92279 184743 92278 184744 92279 184744 92282 184744 92282 184745 92279 184745 92325 184745 92282 184746 92325 184746 92280 184746 92280 184747 92325 184747 92324 184747 92280 184748 92281 184748 92282 184748 92282 184749 92281 184749 92249 184749 92282 184750 92249 184750 92278 184750 92278 184751 92249 184751 92283 184751 92278 184752 92283 184752 92277 184752 92277 184753 92283 184753 92247 184753 92277 184754 92247 184754 92275 184754 92275 184755 92247 184755 92246 184755 92275 184756 92246 184756 92273 184756 92273 184757 92246 184757 92245 184757 92273 184758 92245 184758 92271 184758 92271 184759 92245 184759 92284 184759 92271 184760 92284 184760 92285 184760 92285 184761 92284 184761 92301 184761 92330 184762 92332 184762 92329 184762 92329 184763 92332 184763 92286 184763 92329 184764 92286 184764 92287 184764 92287 184765 92286 184765 92288 184765 92287 184766 92288 184766 92328 184766 92328 184767 92288 184767 92292 184767 92328 184768 92292 184768 92257 184768 92257 184769 92292 184769 92293 184769 92257 184770 92293 184770 92253 184770 92253 184771 92293 184771 92316 184771 92253 184772 92316 184772 92318 184772 92332 184773 92289 184773 92286 184773 92286 184774 92289 184774 92290 184774 92286 184775 92290 184775 92288 184775 92288 184776 92290 184776 92291 184776 92288 184777 92291 184777 92292 184777 92292 184778 92291 184778 92261 184778 92292 184779 92261 184779 92293 184779 92293 184780 92261 184780 92260 184780 92293 184781 92260 184781 92316 184781 92294 184782 92296 184782 92295 184782 92295 184783 92296 184783 92297 184783 92295 184784 92297 184784 92298 184784 92331 184785 92304 184785 92298 184785 92298 184786 92304 184786 92306 184786 92298 184787 92306 184787 92295 184787 92295 184788 92306 184788 92299 184788 92295 184789 92299 184789 92300 184789 92300 184790 92299 184790 92239 184790 92300 184791 92239 184791 92267 184791 92267 184792 92239 184792 92312 184792 92267 184793 92312 184793 92313 184793 85534 184794 92480 184794 92301 184794 92301 184795 92480 184795 92270 184795 92301 184796 92270 184796 92285 184796 92285 184797 92270 184797 92302 184797 92285 184798 92302 184798 92331 184798 92331 184799 92302 184799 92303 184799 92331 184800 92303 184800 92304 184800 92304 184801 92303 184801 92305 184801 92304 184802 92305 184802 92306 184802 92306 184803 92305 184803 92307 184803 92306 184804 92307 184804 92299 184804 92299 184805 92307 184805 92308 184805 92299 184806 92308 184806 92239 184806 92239 184807 92308 184807 92309 184807 92239 184808 92309 184808 92310 184808 92226 184809 92311 184809 92312 184809 92312 184810 92311 184810 92225 184810 92312 184811 92225 184811 92313 184811 92313 184812 92225 184812 92416 184812 92313 184813 92416 184813 92414 184813 92334 184814 92265 184814 92315 184814 92315 184815 92265 184815 92314 184815 92315 184816 92314 184816 92262 184816 92262 184817 92314 184817 92421 184817 92262 184818 92421 184818 92260 184818 92260 184819 92421 184819 92420 184819 92260 184820 92420 184820 92316 184820 92316 184821 92420 184821 92317 184821 92316 184822 92317 184822 92318 184822 92318 184823 92317 184823 92319 184823 92318 184824 92319 184824 92320 184824 92320 184825 92319 184825 92321 184825 92320 184826 92321 184826 92322 184826 92322 184827 92321 184827 92355 184827 92322 184828 92355 184828 92323 184828 92323 184829 92355 184829 92474 184829 92323 184830 92474 184830 85524 184830 92466 184831 92324 184831 92252 184831 92252 184832 92324 184832 92325 184832 92252 184833 92325 184833 92326 184833 92326 184834 92325 184834 92279 184834 92326 184835 92279 184835 92251 184835 92251 184836 92279 184836 92327 184836 92251 184837 92327 184837 92257 184837 92257 184838 92327 184838 92276 184838 92257 184839 92276 184839 92328 184839 92328 184840 92276 184840 92274 184840 92328 184841 92274 184841 92287 184841 92287 184842 92274 184842 92272 184842 92287 184843 92272 184843 92329 184843 92329 184844 92272 184844 92271 184844 92329 184845 92271 184845 92330 184845 92330 184846 92271 184846 92331 184846 92330 184847 92331 184847 92332 184847 92332 184848 92331 184848 92298 184848 92332 184849 92298 184849 92289 184849 92289 184850 92298 184850 92297 184850 92289 184851 92297 184851 92258 184851 92258 184852 92297 184852 92296 184852 92258 184853 92296 184853 92333 184853 92333 184854 92296 184854 92294 184854 92333 184855 92294 184855 92334 184855 92334 184856 92294 184856 92335 184856 92334 184857 92335 184857 92371 184857 92371 184858 92335 184858 92336 184858 92371 184859 92336 184859 92337 184859 92337 184860 92336 184860 92338 184860 92337 184861 92338 184861 92381 184861 92381 184862 92338 184862 92268 184862 92339 184863 92394 184863 92344 184863 92474 184864 92354 184864 92340 184864 92445 184865 92341 184865 92409 184865 92409 184866 92341 184866 92439 184866 92439 184867 92342 184867 92409 184867 92409 184868 92342 184868 92453 184868 92409 184869 92453 184869 92454 184869 92393 184870 92343 184870 92390 184870 92391 184871 92447 184871 92344 184871 92344 184872 92447 184872 85506 184872 92344 184873 85506 184873 92339 184873 92532 184874 84561 184874 92391 184874 92391 184875 84561 184875 84560 184875 92391 184876 84560 184876 92447 184876 92345 184877 92531 184877 92532 184877 92346 184878 92388 184878 92529 184878 92529 184879 92388 184879 92387 184879 92525 184880 92526 184880 92382 184880 92382 184881 92526 184881 92528 184881 85574 184882 92525 184882 92117 184882 92117 184883 92525 184883 92116 184883 92459 184884 92347 184884 92424 184884 92424 184885 92347 184885 92348 184885 92424 184886 92348 184886 92425 184886 92425 184887 92348 184887 92379 184887 92347 184888 92450 184888 92348 184888 92348 184889 92450 184889 92361 184889 92348 184890 92361 184890 92379 184890 92379 184891 92361 184891 92363 184891 92379 184892 92363 184892 92377 184892 92377 184893 92363 184893 92349 184893 92377 184894 92349 184894 92364 184894 92469 184895 92470 184895 92351 184895 92351 184896 92470 184896 92417 184896 92351 184897 92417 184897 92353 184897 92353 184898 92417 184898 92350 184898 92353 184899 92350 184899 92419 184899 92449 184900 92469 184900 92362 184900 92362 184901 92469 184901 92351 184901 92362 184902 92351 184902 92352 184902 92352 184903 92351 184903 92353 184903 92352 184904 92353 184904 92365 184904 92365 184905 92353 184905 92419 184905 92365 184906 92419 184906 92366 184906 92474 184907 92355 184907 92354 184907 92354 184908 92355 184908 92418 184908 92354 184909 92418 184909 92340 184909 92340 184910 92418 184910 92471 184910 92380 184911 92378 184911 92429 184911 92429 184912 92378 184912 92356 184912 92429 184913 92356 184913 92430 184913 92430 184914 92356 184914 92357 184914 92430 184915 92357 184915 92431 184915 92431 184916 92357 184916 92358 184916 92431 184917 92358 184917 92435 184917 92435 184918 92358 184918 92359 184918 92435 184919 92359 184919 92360 184919 92360 184920 92359 184920 92373 184920 92360 184921 92373 184921 92372 184921 92450 184922 92449 184922 92361 184922 92361 184923 92449 184923 92362 184923 92361 184924 92362 184924 92363 184924 92363 184925 92362 184925 92352 184925 92363 184926 92352 184926 92349 184926 92349 184927 92352 184927 92365 184927 92349 184928 92365 184928 92364 184928 92364 184929 92365 184929 92366 184929 92364 184930 92366 184930 92376 184930 92376 184931 92366 184931 92367 184931 92376 184932 92367 184932 92375 184932 92375 184933 92367 184933 92368 184933 92375 184934 92368 184934 92374 184934 92374 184935 92368 184935 92422 184935 92374 184936 92422 184936 92369 184936 92369 184937 92422 184937 92370 184937 92369 184938 92370 184938 92265 184938 92371 184939 92437 184939 92265 184939 92265 184940 92437 184940 92372 184940 92265 184941 92372 184941 92369 184941 92369 184942 92372 184942 92373 184942 92369 184943 92373 184943 92374 184943 92374 184944 92373 184944 92359 184944 92374 184945 92359 184945 92375 184945 92375 184946 92359 184946 92358 184946 92375 184947 92358 184947 92376 184947 92376 184948 92358 184948 92357 184948 92376 184949 92357 184949 92364 184949 92364 184950 92357 184950 92356 184950 92364 184951 92356 184951 92377 184951 92377 184952 92356 184952 92378 184952 92377 184953 92378 184953 92379 184953 92379 184954 92378 184954 92380 184954 92379 184955 92380 184955 92425 184955 92381 184956 92413 184956 92386 184956 92386 184957 92413 184957 92382 184957 92386 184958 92382 184958 92384 184958 92434 184959 92383 184959 92389 184959 92389 184960 92383 184960 92385 184960 92389 184961 92385 184961 92384 184961 92384 184962 92385 184962 92436 184962 92384 184963 92436 184963 92386 184963 92528 184964 92387 184964 92382 184964 92382 184965 92387 184965 92388 184965 92382 184966 92388 184966 92384 184966 92384 184967 92388 184967 92346 184967 92384 184968 92346 184968 92389 184968 92389 184969 92346 184969 92405 184969 92389 184970 92405 184970 92434 184970 92390 184971 92445 184971 92393 184971 92393 184972 92445 184972 92409 184972 92393 184973 92409 184973 92392 184973 92345 184974 92532 184974 92406 184974 92406 184975 92532 184975 92391 184975 92406 184976 92391 184976 92407 184976 92407 184977 92391 184977 92344 184977 92407 184978 92344 184978 92392 184978 92392 184979 92344 184979 92394 184979 92392 184980 92394 184980 92393 184980 92393 184981 92394 184981 92443 184981 92393 184982 92443 184982 92343 184982 92400 184983 92410 184983 92411 184983 92427 184984 92397 184984 92426 184984 92426 184985 92397 184985 92398 184985 92426 184986 92398 184986 92396 184986 92396 184987 92398 184987 92395 184987 92396 184988 92395 184988 92423 184988 92428 184989 92399 184989 92401 184989 92427 184990 92428 184990 92397 184990 92397 184991 92428 184991 92401 184991 92397 184992 92401 184992 92398 184992 92398 184993 92401 184993 92400 184993 92398 184994 92400 184994 92395 184994 92395 184995 92400 184995 92411 184995 92395 184996 92411 184996 92423 184996 92399 184997 92428 184997 92404 184997 92404 184998 92428 184998 92432 184998 92404 184999 92432 184999 92433 184999 92410 185000 92400 185000 92408 185000 92408 185001 92400 185001 92401 185001 92408 185002 92401 185002 92402 185002 92402 185003 92401 185003 92399 185003 92402 185004 92399 185004 92403 185004 92403 185005 92399 185005 92404 185005 92403 185006 92404 185006 92405 185006 92405 185007 92404 185007 92433 185007 92405 185008 92433 185008 92434 185008 92529 185009 92531 185009 92346 185009 92346 185010 92531 185010 92345 185010 92346 185011 92345 185011 92405 185011 92405 185012 92345 185012 92406 185012 92405 185013 92406 185013 92403 185013 92403 185014 92406 185014 92407 185014 92403 185015 92407 185015 92402 185015 92402 185016 92407 185016 92392 185016 92402 185017 92392 185017 92408 185017 92408 185018 92392 185018 92409 185018 92408 185019 92409 185019 92410 185019 92410 185020 92409 185020 92454 185020 92410 185021 92454 185021 92411 185021 92411 185022 92454 185022 92457 185022 92411 185023 92457 185023 92423 185023 92381 185024 92268 185024 92413 185024 92413 185025 92268 185025 92412 185025 92413 185026 92412 185026 92414 185026 92525 185027 92382 185027 92116 185027 92116 185028 92382 185028 92413 185028 92116 185029 92413 185029 92415 185029 92415 185030 92413 185030 92414 185030 92415 185031 92414 185031 92416 185031 92470 185032 92471 185032 92417 185032 92417 185033 92471 185033 92418 185033 92417 185034 92418 185034 92350 185034 92350 185035 92418 185035 92355 185035 92350 185036 92355 185036 92419 185036 92419 185037 92355 185037 92321 185037 92419 185038 92321 185038 92366 185038 92366 185039 92321 185039 92319 185039 92366 185040 92319 185040 92367 185040 92367 185041 92319 185041 92317 185041 92367 185042 92317 185042 92368 185042 92368 185043 92317 185043 92420 185043 92368 185044 92420 185044 92422 185044 92422 185045 92420 185045 92421 185045 92422 185046 92421 185046 92370 185046 92370 185047 92421 185047 92314 185047 92370 185048 92314 185048 92265 185048 92457 185049 92459 185049 92423 185049 92423 185050 92459 185050 92424 185050 92423 185051 92424 185051 92396 185051 92396 185052 92424 185052 92425 185052 92396 185053 92425 185053 92426 185053 92426 185054 92425 185054 92380 185054 92426 185055 92380 185055 92427 185055 92427 185056 92380 185056 92429 185056 92427 185057 92429 185057 92428 185057 92428 185058 92429 185058 92430 185058 92428 185059 92430 185059 92432 185059 92432 185060 92430 185060 92431 185060 92432 185061 92431 185061 92433 185061 92433 185062 92431 185062 92435 185062 92433 185063 92435 185063 92434 185063 92434 185064 92435 185064 92360 185064 92434 185065 92360 185065 92383 185065 92383 185066 92360 185066 92372 185066 92383 185067 92372 185067 92385 185067 92385 185068 92372 185068 92437 185068 92385 185069 92437 185069 92436 185069 92436 185070 92437 185070 92371 185070 92436 185071 92371 185071 92386 185071 92386 185072 92371 185072 92337 185072 92386 185073 92337 185073 92381 185073 86255 185074 92453 185074 92438 185074 92438 185075 92453 185075 92342 185075 92438 185076 92342 185076 92440 185076 92342 185077 92439 185077 92440 185077 92440 185078 92439 185078 92341 185078 92440 185079 92341 185079 92446 185079 92339 185080 92441 185080 92394 185080 92394 185081 92441 185081 92442 185081 92394 185082 92442 185082 92443 185082 92443 185083 92442 185083 85504 185083 92443 185084 85504 185084 92343 185084 92343 185085 85504 185085 92444 185085 92343 185086 92444 185086 92390 185086 92390 185087 92444 185087 92446 185087 92390 185088 92446 185088 92445 185088 92445 185089 92446 185089 92341 185089 84561 185090 92578 185090 84560 185090 84560 185091 92578 185091 86285 185091 84560 185092 86285 185092 92447 185092 92447 185093 86285 185093 92448 185093 92447 185094 92448 185094 85506 185094 85506 185095 92448 185095 86288 185095 85506 185096 86288 185096 92339 185096 92339 185097 86288 185097 92555 185097 92339 185098 92555 185098 92441 185098 92469 185099 92449 185099 92451 185099 92451 185100 92449 185100 92450 185100 92451 185101 92450 185101 92452 185101 92452 185102 92450 185102 92347 185102 92452 185103 92347 185103 92550 185103 92550 185104 92347 185104 92459 185104 92453 185105 86255 185105 92454 185105 92454 185106 86255 185106 92455 185106 92454 185107 92455 185107 92457 185107 92457 185108 92455 185108 92456 185108 92457 185109 92456 185109 92459 185109 92459 185110 92456 185110 92458 185110 92459 185111 92458 185111 92550 185111 92484 185112 85530 185112 92641 185112 92641 185113 85530 185113 92460 185113 92641 185114 92460 185114 92461 185114 92461 185115 92460 185115 92462 185115 92461 185116 92462 185116 92639 185116 92639 185117 92462 185117 92463 185117 92639 185118 92463 185118 86167 185118 86167 185119 92463 185119 92248 185119 86167 185120 92248 185120 92691 185120 92691 185121 92248 185121 92281 185121 92691 185122 92281 185122 92648 185122 92648 185123 92281 185123 92280 185123 92648 185124 92280 185124 92464 185124 92464 185125 92280 185125 92324 185125 92464 185126 92324 185126 92465 185126 92465 185127 92324 185127 92466 185127 92465 185128 92466 185128 85522 185128 85522 185129 92466 185129 92638 185129 92466 185130 92467 185130 92638 185130 92638 185131 92467 185131 85524 185131 92638 185132 85524 185132 92637 185132 92637 185133 85524 185133 92474 185133 92451 185134 92468 185134 92469 185134 92469 185135 92468 185135 92549 185135 92469 185136 92549 185136 92470 185136 92470 185137 92549 185137 92629 185137 92470 185138 92629 185138 92471 185138 92471 185139 92629 185139 92472 185139 92471 185140 92472 185140 92340 185140 92340 185141 92472 185141 92473 185141 92340 185142 92473 185142 92474 185142 92474 185143 92473 185143 86311 185143 92474 185144 86311 185144 92637 185144 92491 185145 85543 185145 92475 185145 92475 185146 85543 185146 92240 185146 92475 185147 92240 185147 86113 185147 92240 185148 84378 185148 86113 185148 86113 185149 84378 185149 92476 185149 86113 185150 92476 185150 92633 185150 92633 185151 92476 185151 92243 185151 92633 185152 92243 185152 92477 185152 92477 185153 92243 185153 84379 185153 92477 185154 84379 185154 92478 185154 92478 185155 84379 185155 92480 185155 92478 185156 92480 185156 92479 185156 92479 185157 92480 185157 92481 185157 92481 185158 92480 185158 85534 185158 92481 185159 85534 185159 92482 185159 85534 185160 92244 185160 92482 185160 92482 185161 92244 185161 92483 185161 92482 185162 92483 185162 86171 185162 86171 185163 92483 185163 85530 185163 86171 185164 85530 185164 92484 185164 92485 185165 92486 185165 92309 185165 92309 185166 92486 185166 92636 185166 92309 185167 92636 185167 92310 185167 92310 185168 92636 185168 92487 185168 92310 185169 92487 185169 92493 185169 92309 185170 92308 185170 92485 185170 92485 185171 92308 185171 92307 185171 92485 185172 92307 185172 92685 185172 92685 185173 92307 185173 92489 185173 92685 185174 92489 185174 92488 185174 92488 185175 92489 185175 92490 185175 92488 185176 92490 185176 92491 185176 92491 185177 92490 185177 92241 185177 92491 185178 92241 185178 85543 185178 92487 185179 92686 185179 92493 185179 92493 185180 92686 185180 92492 185180 92493 185181 92492 185181 85004 185181 85004 185182 92492 185182 92494 185182 85004 185183 92494 185183 92495 185183 92495 185184 92494 185184 92157 185184 92157 185185 92494 185185 92728 185185 92157 185186 92728 185186 92152 185186 92152 185187 92728 185187 92730 185187 92152 185188 92730 185188 92153 185188 92153 185189 92730 185189 92496 185189 92153 185190 92496 185190 92497 185190 85550 185191 85547 185191 92731 185191 92731 185192 85547 185192 92497 185192 92731 185193 92497 185193 92498 185193 92498 185194 92497 185194 92496 185194 86902 185195 92145 185195 92715 185195 92715 185196 92145 185196 92499 185196 92715 185197 92499 185197 86834 185197 86834 185198 92499 185198 92500 185198 86834 185199 92500 185199 92501 185199 92500 185200 85009 185200 92501 185200 92501 185201 85009 185201 92147 185201 92501 185202 92147 185202 92503 185202 92503 185203 92147 185203 92502 185203 92503 185204 92502 185204 85553 185204 85553 185205 92502 185205 92509 185205 85547 185206 85550 185206 92151 185206 92151 185207 85550 185207 92756 185207 92151 185208 92756 185208 92504 185208 92504 185209 92756 185209 85557 185209 92504 185210 85557 185210 92505 185210 92505 185211 85557 185211 92506 185211 92505 185212 92506 185212 92507 185212 92507 185213 92506 185213 92735 185213 92507 185214 92735 185214 85000 185214 85000 185215 92735 185215 92734 185215 85000 185216 92734 185216 92508 185216 92508 185217 92734 185217 92733 185217 92508 185218 92733 185218 92148 185218 92148 185219 92733 185219 92509 185219 92148 185220 92509 185220 92218 185220 92218 185221 92509 185221 92502 185221 92838 185222 85101 185222 92840 185222 92840 185223 85101 185223 92510 185223 92840 185224 92510 185224 92841 185224 92841 185225 92510 185225 85561 185225 92841 185226 85561 185226 92842 185226 92842 185227 85561 185227 92511 185227 92842 185228 92511 185228 92818 185228 92818 185229 92511 185229 85565 185229 92818 185230 85565 185230 92512 185230 92512 185231 85565 185231 92513 185231 92512 185232 92513 185232 86920 185232 86920 185233 92513 185233 92031 185233 92516 185234 92800 185234 92032 185234 92032 185235 92800 185235 92514 185235 92032 185236 92514 185236 92033 185236 92033 185237 92514 185237 86920 185237 92033 185238 86920 185238 92515 185238 92515 185239 86920 185239 92031 185239 92032 185240 92035 185240 92516 185240 92516 185241 92035 185241 92034 185241 92516 185242 92034 185242 92517 185242 92517 185243 92034 185243 85117 185243 92517 185244 85117 185244 92518 185244 85101 185245 92838 185245 92519 185245 92519 185246 92838 185246 92836 185246 92522 185247 92054 185247 92520 185247 92520 185248 92054 185248 85570 185248 92520 185249 85570 185249 92836 185249 92836 185250 85570 185250 92521 185250 92836 185251 92521 185251 92519 185251 92520 185252 92523 185252 92522 185252 92522 185253 92523 185253 92820 185253 92522 185254 92820 185254 92030 185254 92030 185255 92820 185255 92524 185255 92030 185256 92524 185256 85574 185256 85574 185257 92524 185257 92804 185257 85574 185258 92804 185258 92525 185258 92525 185259 92804 185259 92553 185259 92525 185260 92553 185260 92526 185260 92526 185261 92553 185261 92600 185261 92526 185262 92600 185262 92528 185262 92578 185263 84561 185263 92527 185263 92527 185264 84561 185264 92532 185264 92528 185265 92600 185265 92387 185265 92387 185266 92600 185266 92599 185266 92387 185267 92599 185267 92529 185267 92529 185268 92599 185268 92530 185268 92529 185269 92530 185269 92531 185269 92531 185270 92530 185270 92597 185270 92531 185271 92597 185271 92532 185271 92532 185272 92597 185272 92596 185272 92532 185273 92596 185273 92527 185273 92541 185274 92145 185274 86902 185274 92143 185275 85584 185275 92533 185275 92533 185276 85584 185276 92721 185276 92533 185277 92721 185277 84997 185277 84997 185278 92721 185278 92797 185278 84997 185279 92797 185279 92141 185279 92141 185280 92797 185280 92534 185280 92141 185281 92534 185281 92140 185281 92140 185282 92534 185282 92723 185282 92140 185283 92723 185283 92542 185283 92518 185284 85117 185284 92876 185284 92876 185285 85117 185285 92535 185285 92876 185286 92535 185286 92536 185286 92536 185287 92535 185287 92039 185287 92536 185288 92039 185288 85589 185288 85589 185289 92039 185289 92538 185289 85589 185290 92538 185290 92537 185290 92537 185291 92538 185291 92539 185291 92537 185292 92539 185292 92540 185292 92540 185293 92539 185293 92093 185293 92540 185294 92093 185294 92546 185294 92546 185295 92093 185295 92105 185295 86902 185296 92718 185296 92541 185296 92541 185297 92718 185297 92717 185297 92541 185298 92717 185298 92144 185298 92144 185299 92717 185299 92716 185299 92144 185300 92716 185300 92143 185300 92143 185301 92716 185301 92719 185301 92143 185302 92719 185302 85584 185302 92723 185303 92727 185303 92542 185303 92542 185304 92727 185304 92762 185304 92542 185305 92762 185305 92543 185305 92543 185306 92762 185306 92714 185306 92543 185307 92714 185307 92136 185307 92136 185308 92714 185308 92764 185308 92136 185309 92764 185309 92074 185309 92074 185310 92764 185310 92845 185310 92074 185311 92845 185311 92065 185311 92065 185312 92845 185312 92545 185312 92065 185313 92545 185313 92544 185313 92544 185314 92545 185314 85593 185314 92544 185315 85593 185315 92075 185315 92075 185316 85593 185316 92799 185316 92075 185317 92799 185317 92105 185317 92105 185318 92799 185318 92861 185318 92105 185319 92861 185319 92546 185319 92603 185320 92605 185320 92594 185320 92573 185321 92598 185321 92601 185321 92547 185322 92699 185322 92622 185322 92627 185323 92647 185323 92628 185323 92614 185324 92567 185324 92566 185324 92548 185325 92562 185325 92565 185325 92567 185326 92614 185326 92549 185326 92604 185327 92456 185327 92455 185327 92550 185328 92458 185328 92551 185328 92551 185329 92458 185329 92603 185329 92468 185330 92451 185330 92548 185330 92548 185331 92451 185331 92552 185331 92548 185332 92552 185332 92562 185332 92628 185333 92472 185333 92629 185333 92472 185334 92628 185334 92473 185334 92473 185335 92628 185335 92647 185335 92473 185336 92647 185336 86311 185336 92804 185337 92863 185337 92553 185337 92553 185338 92863 185338 92554 185338 92553 185339 92554 185339 92600 185339 92598 185340 92572 185340 92616 185340 92441 185341 92555 185341 92556 185341 92556 185342 92555 185342 86288 185342 92556 185343 86288 185343 92448 185343 92441 185344 92556 185344 92442 185344 92442 185345 92556 185345 92576 185345 92442 185346 92576 185346 85504 185346 85504 185347 92557 185347 92444 185347 92444 185348 92557 185348 92446 185348 92446 185349 92557 185349 92440 185349 92440 185350 92557 185350 92577 185350 92440 185351 92577 185351 92438 185351 92558 185352 92559 185352 92608 185352 92608 185353 92559 185353 92560 185353 92608 185354 92560 185354 92606 185354 92606 185355 92560 185355 92561 185355 92606 185356 92561 185356 92593 185356 92593 185357 92561 185357 92565 185357 92593 185358 92565 185358 92592 185358 92592 185359 92565 185359 92562 185359 92592 185360 92562 185360 92563 185360 92563 185361 92562 185361 92552 185361 92563 185362 92552 185362 92452 185362 92452 185363 92552 185363 92451 185363 92559 185364 92610 185364 92560 185364 92560 185365 92610 185365 92611 185365 92560 185366 92611 185366 92561 185366 92561 185367 92611 185367 92564 185367 92561 185368 92564 185368 92565 185368 92565 185369 92564 185369 92566 185369 92565 185370 92566 185370 92548 185370 92548 185371 92566 185371 92567 185371 92548 185372 92567 185372 92468 185372 92468 185373 92567 185373 92549 185373 92568 185374 92602 185374 92575 185374 92575 185375 92602 185375 92569 185375 92575 185376 92569 185376 92574 185376 92574 185377 92569 185377 92570 185377 92547 185378 92570 185378 92712 185378 92712 185379 92570 185379 92569 185379 92712 185380 92569 185380 92713 185380 92713 185381 92569 185381 92602 185381 92713 185382 92602 185382 92571 185382 92572 185383 92598 185383 92619 185383 92619 185384 92598 185384 92573 185384 92619 185385 92573 185385 92620 185385 92547 185386 92622 185386 92570 185386 92570 185387 92622 185387 92620 185387 92570 185388 92620 185388 92574 185388 92574 185389 92620 185389 92573 185389 92574 185390 92573 185390 92575 185390 92575 185391 92573 185391 92601 185391 92575 185392 92601 185392 92568 185392 85504 185393 92576 185393 92557 185393 92557 185394 92576 185394 92582 185394 92557 185395 92582 185395 92577 185395 92577 185396 92582 185396 92588 185396 92577 185397 92588 185397 92587 185397 92578 185398 92527 185398 92579 185398 92579 185399 92527 185399 92615 185399 92579 185400 92615 185400 92580 185400 92580 185401 92615 185401 92617 185401 92617 185402 92618 185402 92580 185402 92580 185403 92618 185403 92581 185403 92580 185404 92581 185404 92589 185404 92589 185405 92588 185405 92580 185405 92580 185406 92588 185406 92582 185406 92580 185407 92582 185407 92579 185407 92579 185408 92582 185408 92576 185408 92579 185409 92576 185409 92578 185409 92578 185410 92576 185410 92556 185410 92578 185411 92556 185411 86285 185411 86285 185412 92556 185412 92448 185412 92584 185413 92604 185413 92583 185413 92583 185414 92604 185414 92455 185414 92583 185415 92455 185415 86255 185415 92584 185416 92586 185416 92585 185416 92585 185417 92586 185417 92607 185417 92438 185418 92577 185418 86255 185418 86255 185419 92577 185419 92587 185419 86255 185420 92587 185420 92583 185420 92583 185421 92587 185421 92588 185421 92583 185422 92588 185422 92584 185422 92584 185423 92588 185423 92589 185423 92584 185424 92589 185424 92586 185424 92586 185425 92589 185425 92581 185425 92586 185426 92581 185426 92607 185426 92607 185427 92581 185427 92618 185427 92607 185428 92618 185428 92590 185428 92590 185429 92618 185429 92591 185429 92590 185430 92591 185430 92609 185430 92452 185431 92550 185431 92563 185431 92563 185432 92550 185432 92551 185432 92563 185433 92551 185433 92592 185433 92592 185434 92551 185434 92603 185434 92592 185435 92603 185435 92593 185435 92593 185436 92603 185436 92594 185436 92593 185437 92594 185437 92606 185437 92554 185438 92630 185438 92595 185438 92596 185439 92597 185439 92616 185439 92616 185440 92597 185440 92530 185440 92616 185441 92530 185441 92598 185441 92598 185442 92530 185442 92599 185442 92598 185443 92599 185443 92601 185443 92601 185444 92599 185444 92600 185444 92601 185445 92600 185445 92568 185445 92568 185446 92600 185446 92554 185446 92568 185447 92554 185447 92602 185447 92602 185448 92554 185448 92595 185448 92602 185449 92595 185449 92571 185449 92458 185450 92456 185450 92603 185450 92603 185451 92456 185451 92604 185451 92603 185452 92604 185452 92605 185452 92605 185453 92604 185453 92584 185453 92605 185454 92584 185454 92594 185454 92594 185455 92584 185455 92585 185455 92594 185456 92585 185456 92606 185456 92606 185457 92585 185457 92607 185457 92606 185458 92607 185458 92608 185458 92608 185459 92607 185459 92590 185459 92608 185460 92590 185460 92558 185460 92558 185461 92590 185461 92609 185461 92558 185462 92609 185462 92559 185462 92559 185463 92609 185463 92621 185463 92559 185464 92621 185464 92610 185464 92610 185465 92621 185465 92623 185465 92610 185466 92623 185466 92611 185466 92611 185467 92623 185467 92625 185467 92611 185468 92625 185468 92564 185468 92564 185469 92625 185469 92612 185469 92564 185470 92612 185470 92566 185470 92566 185471 92612 185471 92613 185471 92566 185472 92613 185472 92614 185472 92527 185473 92596 185473 92615 185473 92615 185474 92596 185474 92616 185474 92615 185475 92616 185475 92617 185475 92617 185476 92616 185476 92572 185476 92617 185477 92572 185477 92618 185477 92618 185478 92572 185478 92619 185478 92618 185479 92619 185479 92591 185479 92591 185480 92619 185480 92620 185480 92591 185481 92620 185481 92609 185481 92609 185482 92620 185482 92622 185482 92609 185483 92622 185483 92621 185483 92621 185484 92622 185484 92699 185484 92621 185485 92699 185485 92623 185485 92623 185486 92699 185486 92624 185486 92623 185487 92624 185487 92625 185487 92625 185488 92624 185488 92626 185488 92625 185489 92626 185489 92612 185489 92612 185490 92626 185490 92627 185490 92612 185491 92627 185491 92613 185491 92613 185492 92627 185492 92628 185492 92613 185493 92628 185493 92614 185493 92614 185494 92628 185494 92629 185494 92614 185495 92629 185495 92549 185495 92595 185496 92630 185496 92690 185496 92701 185497 92631 185497 92672 185497 92477 185498 92643 185498 92633 185498 92631 185499 92701 185499 92632 185499 92491 185500 92475 185500 92643 185500 92643 185501 92475 185501 86113 185501 92643 185502 86113 185502 92633 185502 92634 185503 92635 185503 92685 185503 92636 185504 92486 185504 92664 185504 92665 185505 92687 185505 92664 185505 92664 185506 92687 185506 92487 185506 92664 185507 92487 185507 92636 185507 86311 185508 92647 185508 92637 185508 92637 185509 92647 185509 92646 185509 92637 185510 92646 185510 92638 185510 92645 185511 92644 185511 85522 185511 85522 185512 92644 185512 92465 185512 92648 185513 92464 185513 92649 185513 92649 185514 92464 185514 92651 185514 92639 185515 92700 185515 92461 185515 92461 185516 92700 185516 92703 185516 92461 185517 92703 185517 92641 185517 92641 185518 92703 185518 92640 185518 92641 185519 92640 185519 92484 185519 92680 185520 86171 185520 92484 185520 92479 185521 92481 185521 92668 185521 92668 185522 92481 185522 92482 185522 92685 185523 92488 185523 92634 185523 92634 185524 92488 185524 92491 185524 92634 185525 92491 185525 92642 185525 92642 185526 92491 185526 92643 185526 92642 185527 92643 185527 92682 185527 92682 185528 92643 185528 92477 185528 92682 185529 92477 185529 92478 185529 92464 185530 92465 185530 92651 185530 92651 185531 92465 185531 92644 185531 92651 185532 92644 185532 92656 185532 92656 185533 92644 185533 92645 185533 92656 185534 92645 185534 92657 185534 85522 185535 92638 185535 92645 185535 92645 185536 92638 185536 92646 185536 92645 185537 92646 185537 92657 185537 92657 185538 92646 185538 92647 185538 92657 185539 92647 185539 92627 185539 92691 185540 92648 185540 92650 185540 92650 185541 92648 185541 92649 185541 92650 185542 92649 185542 92692 185542 92692 185543 92649 185543 92651 185543 92692 185544 92651 185544 92693 185544 92693 185545 92651 185545 92656 185545 92693 185546 92656 185546 92695 185546 92654 185547 92698 185547 92655 185547 92655 185548 92698 185548 92696 185548 92655 185549 92696 185549 92652 185549 92652 185550 92696 185550 92695 185550 92653 185551 92654 185551 92659 185551 92659 185552 92654 185552 92655 185552 92659 185553 92655 185553 92658 185553 92658 185554 92655 185554 92652 185554 92695 185555 92656 185555 92652 185555 92652 185556 92656 185556 92657 185556 92652 185557 92657 185557 92658 185557 92658 185558 92657 185558 92627 185558 92658 185559 92627 185559 92659 185559 92659 185560 92627 185560 92626 185560 92659 185561 92626 185561 92653 185561 92711 185562 92687 185562 92710 185562 92710 185563 92687 185563 92665 185563 92710 185564 92665 185564 92660 185564 92660 185565 92665 185565 92661 185565 92660 185566 92661 185566 92709 185566 92709 185567 92661 185567 92707 185567 92667 185568 92662 185568 92663 185568 92663 185569 92662 185569 92666 185569 92663 185570 92666 185570 92485 185570 92486 185571 92485 185571 92664 185571 92664 185572 92485 185572 92666 185572 92664 185573 92666 185573 92665 185573 92665 185574 92666 185574 92662 185574 92665 185575 92662 185575 92661 185575 92661 185576 92662 185576 92667 185576 92661 185577 92667 185577 92707 185577 92478 185578 92479 185578 92682 185578 92682 185579 92479 185579 92668 185579 92682 185580 92668 185580 92680 185580 92680 185581 92668 185581 92482 185581 92680 185582 92482 185582 86171 185582 92679 185583 92678 185583 92702 185583 92702 185584 92678 185584 92670 185584 92702 185585 92670 185585 92669 185585 92669 185586 92670 185586 92704 185586 92706 185587 92705 185587 92677 185587 92677 185588 92705 185588 92675 185588 92708 185589 92671 185589 92697 185589 92697 185590 92671 185590 92676 185590 92672 185591 92673 185591 92674 185591 92674 185592 92673 185592 92694 185592 92674 185593 92694 185593 92675 185593 92675 185594 92694 185594 92697 185594 92675 185595 92697 185595 92677 185595 92677 185596 92697 185596 92676 185596 92677 185597 92676 185597 92706 185597 92705 185598 92704 185598 92675 185598 92675 185599 92704 185599 92670 185599 92675 185600 92670 185600 92674 185600 92674 185601 92670 185601 92678 185601 92674 185602 92678 185602 92672 185602 92672 185603 92678 185603 92679 185603 92672 185604 92679 185604 92701 185604 92484 185605 92640 185605 92680 185605 92680 185606 92640 185606 92681 185606 92680 185607 92681 185607 92682 185607 92682 185608 92681 185608 92683 185608 92682 185609 92683 185609 92642 185609 92642 185610 92683 185610 92684 185610 92642 185611 92684 185611 92634 185611 92634 185612 92684 185612 92663 185612 92634 185613 92663 185613 92635 185613 92635 185614 92663 185614 92485 185614 92635 185615 92485 185615 92685 185615 92686 185616 92487 185616 92688 185616 92688 185617 92487 185617 92687 185617 92688 185618 92687 185618 92689 185618 92689 185619 92687 185619 92711 185619 92689 185620 92711 185620 92690 185620 92690 185621 92711 185621 92571 185621 92690 185622 92571 185622 92595 185622 86167 185623 92691 185623 92632 185623 92632 185624 92691 185624 92650 185624 92632 185625 92650 185625 92631 185625 92631 185626 92650 185626 92692 185626 92631 185627 92692 185627 92672 185627 92672 185628 92692 185628 92693 185628 92672 185629 92693 185629 92673 185629 92673 185630 92693 185630 92695 185630 92673 185631 92695 185631 92694 185631 92694 185632 92695 185632 92696 185632 92694 185633 92696 185633 92697 185633 92697 185634 92696 185634 92698 185634 92697 185635 92698 185635 92708 185635 92708 185636 92698 185636 92654 185636 92708 185637 92654 185637 92699 185637 92699 185638 92654 185638 92653 185638 92699 185639 92653 185639 92624 185639 92624 185640 92653 185640 92626 185640 86167 185641 92632 185641 92639 185641 92639 185642 92632 185642 92701 185642 92639 185643 92701 185643 92700 185643 92700 185644 92701 185644 92679 185644 92700 185645 92679 185645 92703 185645 92703 185646 92679 185646 92702 185646 92703 185647 92702 185647 92640 185647 92640 185648 92702 185648 92669 185648 92640 185649 92669 185649 92681 185649 92681 185650 92669 185650 92704 185650 92681 185651 92704 185651 92683 185651 92683 185652 92704 185652 92705 185652 92683 185653 92705 185653 92684 185653 92684 185654 92705 185654 92706 185654 92684 185655 92706 185655 92663 185655 92663 185656 92706 185656 92676 185656 92663 185657 92676 185657 92667 185657 92667 185658 92676 185658 92671 185658 92667 185659 92671 185659 92707 185659 92707 185660 92671 185660 92708 185660 92707 185661 92708 185661 92709 185661 92709 185662 92708 185662 92699 185662 92709 185663 92699 185663 92660 185663 92660 185664 92699 185664 92547 185664 92660 185665 92547 185665 92710 185665 92710 185666 92547 185666 92712 185666 92710 185667 92712 185667 92711 185667 92711 185668 92712 185668 92713 185668 92711 185669 92713 185669 92571 185669 92775 185670 92725 185670 92774 185670 92492 185671 92686 185671 92789 185671 92764 185672 92714 185672 92763 185672 86902 185673 92715 185673 92737 185673 92716 185674 92717 185674 92740 185674 92740 185675 92717 185675 92718 185675 85584 185676 92719 185676 92745 185676 92745 185677 92719 185677 92739 185677 92745 185678 92739 185678 92746 185678 92797 185679 92721 185679 92720 185679 92720 185680 92721 185680 92722 185680 92720 185681 92722 185681 92796 185681 92723 185682 92534 185682 92775 185682 92775 185683 92534 185683 92724 185683 92775 185684 92724 185684 92725 185684 92726 185685 92762 185685 92727 185685 92492 185686 92789 185686 92494 185686 92494 185687 92789 185687 92729 185687 92494 185688 92729 185688 92728 185688 92728 185689 92729 185689 92791 185689 92728 185690 92791 185690 92730 185690 92730 185691 92791 185691 92751 185691 92730 185692 92751 185692 92496 185692 92496 185693 92751 185693 92498 185693 92498 185694 92751 185694 92749 185694 92498 185695 92749 185695 92731 185695 92732 185696 92735 185696 92757 185696 92757 185697 92735 185697 92506 185697 92757 185698 92506 185698 85557 185698 92509 185699 92733 185699 92732 185699 92732 185700 92733 185700 92734 185700 92732 185701 92734 185701 92735 185701 86834 185702 92501 185702 92736 185702 92736 185703 92501 185703 92503 185703 92736 185704 92503 185704 85553 185704 92715 185705 86834 185705 92737 185705 92737 185706 86834 185706 92736 185706 92737 185707 92736 185707 92732 185707 92732 185708 92736 185708 85553 185708 92732 185709 85553 185709 92509 185709 92718 185710 86902 185710 92740 185710 92740 185711 86902 185711 92737 185711 92740 185712 92737 185712 92738 185712 92738 185713 92737 185713 92732 185713 92738 185714 92732 185714 92742 185714 92742 185715 92732 185715 92757 185715 92742 185716 92757 185716 92744 185716 92719 185717 92716 185717 92739 185717 92739 185718 92716 185718 92740 185718 92739 185719 92740 185719 92746 185719 92746 185720 92740 185720 92738 185720 92746 185721 92738 185721 92741 185721 92741 185722 92738 185722 92742 185722 92741 185723 92742 185723 92743 185723 92743 185724 92742 185724 92744 185724 92743 185725 92744 185725 92759 185725 92721 185726 85584 185726 92722 185726 92722 185727 85584 185727 92745 185727 92722 185728 92745 185728 92796 185728 92796 185729 92745 185729 92746 185729 92796 185730 92746 185730 92747 185730 92747 185731 92746 185731 92741 185731 92747 185732 92741 185732 92794 185732 92794 185733 92741 185733 92743 185733 92794 185734 92743 185734 92792 185734 92792 185735 92743 185735 92759 185735 92792 185736 92759 185736 92748 185736 85550 185737 92731 185737 92754 185737 92754 185738 92731 185738 92749 185738 92754 185739 92749 185739 92750 185739 92750 185740 92749 185740 92751 185740 92750 185741 92751 185741 92752 185741 92752 185742 92751 185742 92791 185742 92791 185743 92760 185743 92752 185743 92752 185744 92760 185744 92753 185744 92752 185745 92753 185745 92750 185745 92750 185746 92753 185746 92758 185746 92750 185747 92758 185747 92754 185747 92754 185748 92758 185748 92755 185748 92754 185749 92755 185749 85550 185749 85550 185750 92755 185750 92756 185750 85557 185751 92756 185751 92757 185751 92757 185752 92756 185752 92755 185752 92757 185753 92755 185753 92744 185753 92744 185754 92755 185754 92758 185754 92744 185755 92758 185755 92759 185755 92759 185756 92758 185756 92753 185756 92759 185757 92753 185757 92748 185757 92748 185758 92753 185758 92760 185758 92748 185759 92760 185759 92761 185759 92761 185760 92760 185760 92791 185760 92714 185761 92762 185761 92763 185761 92763 185762 92762 185762 92726 185762 92763 185763 92726 185763 92766 185763 92845 185764 92764 185764 92765 185764 92765 185765 92764 185765 92763 185765 92765 185766 92763 185766 92846 185766 92846 185767 92763 185767 92766 185767 92846 185768 92766 185768 92847 185768 92767 185769 92786 185769 92769 185769 92769 185770 92786 185770 92768 185770 92769 185771 92768 185771 92771 185771 92771 185772 92768 185772 92770 185772 92771 185773 92770 185773 92793 185773 92793 185774 92770 185774 92776 185774 92793 185775 92776 185775 92795 185775 92795 185776 92776 185776 92772 185776 92795 185777 92772 185777 92773 185777 92773 185778 92772 185778 92779 185778 92773 185779 92779 185779 92774 185779 92774 185780 92779 185780 92781 185780 92774 185781 92781 185781 92775 185781 92775 185782 92781 185782 92780 185782 92775 185783 92780 185783 92723 185783 92723 185784 92780 185784 92727 185784 92770 185785 92784 185785 92776 185785 92776 185786 92784 185786 92777 185786 92776 185787 92777 185787 92772 185787 92772 185788 92777 185788 92778 185788 92772 185789 92778 185789 92779 185789 92779 185790 92778 185790 92782 185790 92779 185791 92782 185791 92781 185791 92688 185792 92689 185792 92790 185792 92790 185793 92689 185793 92690 185793 92727 185794 92780 185794 92726 185794 92726 185795 92780 185795 92781 185795 92726 185796 92781 185796 92766 185796 92766 185797 92781 185797 92782 185797 92766 185798 92782 185798 92847 185798 92847 185799 92782 185799 92778 185799 92847 185800 92778 185800 92864 185800 92864 185801 92778 185801 92777 185801 92864 185802 92777 185802 92783 185802 92783 185803 92777 185803 92784 185803 92783 185804 92784 185804 92785 185804 92785 185805 92784 185805 92770 185805 92785 185806 92770 185806 92827 185806 92827 185807 92770 185807 92768 185807 92827 185808 92768 185808 92829 185808 92829 185809 92768 185809 92786 185809 92829 185810 92786 185810 92830 185810 92830 185811 92786 185811 92767 185811 92830 185812 92767 185812 92787 185812 92787 185813 92767 185813 92790 185813 92787 185814 92790 185814 92788 185814 92788 185815 92790 185815 92690 185815 92788 185816 92690 185816 92630 185816 92686 185817 92688 185817 92789 185817 92789 185818 92688 185818 92790 185818 92789 185819 92790 185819 92729 185819 92729 185820 92790 185820 92767 185820 92729 185821 92767 185821 92791 185821 92791 185822 92767 185822 92769 185822 92791 185823 92769 185823 92761 185823 92761 185824 92769 185824 92771 185824 92761 185825 92771 185825 92748 185825 92748 185826 92771 185826 92793 185826 92748 185827 92793 185827 92792 185827 92792 185828 92793 185828 92795 185828 92792 185829 92795 185829 92794 185829 92794 185830 92795 185830 92773 185830 92794 185831 92773 185831 92747 185831 92747 185832 92773 185832 92774 185832 92747 185833 92774 185833 92796 185833 92796 185834 92774 185834 92725 185834 92796 185835 92725 185835 92720 185835 92720 185836 92725 185836 92724 185836 92720 185837 92724 185837 92797 185837 92797 185838 92724 185838 92534 185838 92825 185839 92798 185839 92867 185839 92799 185840 85593 185840 92844 185840 92844 185841 85593 185841 92545 185841 92844 185842 92545 185842 92843 185842 92850 185843 92851 185843 92540 185843 92540 185844 92851 185844 92537 185844 92518 185845 92877 185845 92801 185845 92514 185846 92800 185846 92801 185846 92800 185847 92516 185847 92801 185847 92801 185848 92516 185848 92517 185848 92801 185849 92517 185849 92518 185849 92819 185850 92512 185850 86920 185850 92802 185851 92520 185851 92836 185851 92820 185852 92523 185852 92834 185852 92834 185853 92523 185853 92520 185853 92803 185854 92524 185854 92820 185854 92863 185855 92804 185855 92524 185855 92811 185856 92875 185856 92810 185856 92877 185857 92805 185857 92801 185857 92801 185858 92805 185858 92819 185858 92801 185859 92819 185859 92514 185859 92514 185860 92819 185860 86920 185860 92798 185861 92825 185861 92806 185861 92806 185862 92825 185862 92807 185862 92806 185863 92807 185863 92809 185863 92809 185864 92807 185864 92808 185864 92809 185865 92808 185865 92872 185865 92872 185866 92808 185866 92823 185866 92872 185867 92823 185867 92810 185867 92810 185868 92823 185868 92821 185868 92810 185869 92821 185869 92811 185869 92833 185870 92835 185870 92826 185870 92826 185871 92835 185871 92812 185871 92826 185872 92812 185872 92824 185872 92824 185873 92812 185873 92813 185873 92824 185874 92813 185874 92814 185874 92814 185875 92813 185875 92837 185875 92814 185876 92837 185876 92815 185876 92815 185877 92837 185877 92839 185877 92815 185878 92839 185878 92822 185878 92822 185879 92839 185879 92816 185879 92822 185880 92816 185880 92805 185880 92805 185881 92816 185881 92817 185881 92805 185882 92817 185882 92819 185882 92819 185883 92817 185883 92818 185883 92819 185884 92818 185884 92512 185884 92820 185885 92834 185885 92803 185885 92803 185886 92834 185886 92832 185886 92803 185887 92832 185887 92862 185887 92877 185888 92811 185888 92805 185888 92805 185889 92811 185889 92821 185889 92805 185890 92821 185890 92822 185890 92822 185891 92821 185891 92823 185891 92822 185892 92823 185892 92815 185892 92815 185893 92823 185893 92808 185893 92815 185894 92808 185894 92814 185894 92814 185895 92808 185895 92807 185895 92814 185896 92807 185896 92824 185896 92824 185897 92807 185897 92825 185897 92824 185898 92825 185898 92826 185898 92826 185899 92825 185899 92867 185899 92826 185900 92867 185900 92833 185900 92833 185901 92867 185901 92831 185901 92827 185902 92829 185902 92828 185902 92828 185903 92829 185903 92830 185903 92831 185904 92832 185904 92833 185904 92833 185905 92832 185905 92834 185905 92833 185906 92834 185906 92835 185906 92835 185907 92834 185907 92520 185907 92835 185908 92520 185908 92812 185908 92812 185909 92520 185909 92802 185909 92812 185910 92802 185910 92813 185910 92813 185911 92802 185911 92836 185911 92813 185912 92836 185912 92837 185912 92837 185913 92836 185913 92838 185913 92837 185914 92838 185914 92839 185914 92839 185915 92838 185915 92840 185915 92839 185916 92840 185916 92816 185916 92816 185917 92840 185917 92841 185917 92816 185918 92841 185918 92817 185918 92817 185919 92841 185919 92842 185919 92817 185920 92842 185920 92818 185920 92843 185921 92857 185921 92844 185921 92844 185922 92857 185922 92860 185922 92844 185923 92860 185923 92799 185923 92799 185924 92860 185924 92861 185924 92545 185925 92845 185925 92843 185925 92843 185926 92845 185926 92765 185926 92843 185927 92765 185927 92857 185927 92857 185928 92765 185928 92846 185928 92857 185929 92846 185929 92855 185929 92855 185930 92846 185930 92847 185930 92855 185931 92847 185931 92854 185931 92854 185932 92847 185932 92848 185932 92848 185933 92847 185933 92864 185933 92848 185934 92864 185934 92849 185934 92546 185935 92859 185935 92873 185935 92873 185936 92859 185936 92858 185936 92540 185937 92546 185937 92850 185937 92850 185938 92546 185938 92873 185938 92850 185939 92873 185939 92851 185939 92851 185940 92873 185940 92874 185940 92851 185941 92874 185941 92537 185941 92537 185942 92874 185942 85589 185942 92865 185943 92866 185943 92852 185943 92852 185944 92866 185944 92868 185944 92852 185945 92868 185945 92853 185945 92853 185946 92868 185946 92869 185946 92853 185947 92869 185947 92856 185947 92856 185948 92869 185948 92870 185948 92856 185949 92870 185949 92858 185949 92858 185950 92870 185950 92871 185950 92858 185951 92871 185951 92873 185951 92849 185952 92865 185952 92848 185952 92848 185953 92865 185953 92852 185953 92848 185954 92852 185954 92854 185954 92854 185955 92852 185955 92853 185955 92854 185956 92853 185956 92855 185956 92855 185957 92853 185957 92856 185957 92855 185958 92856 185958 92857 185958 92857 185959 92856 185959 92858 185959 92857 185960 92858 185960 92860 185960 92860 185961 92858 185961 92859 185961 92860 185962 92859 185962 92861 185962 92861 185963 92859 185963 92546 185963 92785 185964 92827 185964 92831 185964 92831 185965 92827 185965 92828 185965 92831 185966 92828 185966 92832 185966 92832 185967 92828 185967 92830 185967 92832 185968 92830 185968 92862 185968 92862 185969 92830 185969 92787 185969 92862 185970 92787 185970 92788 185970 92524 185971 92803 185971 92863 185971 92863 185972 92803 185972 92862 185972 92863 185973 92862 185973 92554 185973 92554 185974 92862 185974 92788 185974 92554 185975 92788 185975 92630 185975 92864 185976 92783 185976 92849 185976 92849 185977 92783 185977 92785 185977 92849 185978 92785 185978 92865 185978 92865 185979 92785 185979 92831 185979 92865 185980 92831 185980 92866 185980 92866 185981 92831 185981 92867 185981 92866 185982 92867 185982 92868 185982 92868 185983 92867 185983 92798 185983 92868 185984 92798 185984 92869 185984 92869 185985 92798 185985 92806 185985 92869 185986 92806 185986 92870 185986 92870 185987 92806 185987 92809 185987 92870 185988 92809 185988 92871 185988 92871 185989 92809 185989 92872 185989 92871 185990 92872 185990 92873 185990 92873 185991 92872 185991 92810 185991 92873 185992 92810 185992 92874 185992 92874 185993 92810 185993 92875 185993 92874 185994 92875 185994 85589 185994 85589 185995 92875 185995 92811 185995 85589 185996 92811 185996 92536 185996 92536 185997 92811 185997 92877 185997 92536 185998 92877 185998 92876 185998 92876 185999 92877 185999 92518 185999 92878 186000 92879 186000 93016 186000 93016 186001 92879 186001 92881 186001 93016 186002 92881 186002 92880 186002 92880 186003 92881 186003 92940 186003 92940 186004 92881 186004 93090 186004 92940 186005 93090 186005 92885 186005 93070 186006 92878 186006 93068 186006 93068 186007 92878 186007 92882 186007 93068 186008 92882 186008 93067 186008 93067 186009 92882 186009 92883 186009 93067 186010 92883 186010 92906 186010 93090 186011 93092 186011 92885 186011 92885 186012 93092 186012 92884 186012 92885 186013 92884 186013 93022 186013 93022 186014 92884 186014 92886 186014 93022 186015 92886 186015 92893 186015 92893 186016 92886 186016 92892 186016 93074 186017 93095 186017 93073 186017 93073 186018 93095 186018 93096 186018 93073 186019 93096 186019 93070 186019 93070 186020 93096 186020 92887 186020 93070 186021 92887 186021 92878 186021 92878 186022 92887 186022 92888 186022 92878 186023 92888 186023 92879 186023 93074 186024 92889 186024 93095 186024 93095 186025 92889 186025 93149 186025 93095 186026 93149 186026 92890 186026 92890 186027 93149 186027 92891 186027 92890 186028 92891 186028 92892 186028 92892 186029 92891 186029 93020 186029 92892 186030 93020 186030 92893 186030 92889 186031 92894 186031 93149 186031 93149 186032 92894 186032 93076 186032 93149 186033 93076 186033 92914 186033 92965 186034 92895 186034 93056 186034 92965 186035 93056 186035 92966 186035 93032 186036 92896 186036 92897 186036 92897 186037 92896 186037 92959 186037 92897 186038 92959 186038 92900 186038 92965 186039 92964 186039 92898 186039 92898 186040 92964 186040 92961 186040 92898 186041 92961 186041 93032 186041 93032 186042 92961 186042 92899 186042 93032 186043 92899 186043 92896 186043 92959 186044 92901 186044 92900 186044 92900 186045 92901 186045 92902 186045 92900 186046 92902 186046 92903 186046 92903 186047 92902 186047 92904 186047 92903 186048 92904 186048 92905 186048 92905 186049 92904 186049 92954 186049 92905 186050 92954 186050 93026 186050 93026 186051 92954 186051 92955 186051 93026 186052 92955 186052 93025 186052 92906 186053 92883 186053 92907 186053 92907 186054 92883 186054 92908 186054 92907 186055 92908 186055 92909 186055 92909 186056 92908 186056 92913 186056 92909 186057 92913 186057 92918 186057 93056 186058 92910 186058 92966 186058 92966 186059 92910 186059 93045 186059 92966 186060 93045 186060 92911 186060 92911 186061 93045 186061 93046 186061 92911 186062 93046 186062 92912 186062 92912 186063 93046 186063 92918 186063 92912 186064 92918 186064 93161 186064 93161 186065 92918 186065 92913 186065 93076 186066 93077 186066 92914 186066 92914 186067 93077 186067 92909 186067 92914 186068 92909 186068 92915 186068 92915 186069 92909 186069 92918 186069 92915 186070 92918 186070 92916 186070 93051 186071 92955 186071 92917 186071 92917 186072 92955 186072 93151 186072 92917 186073 93151 186073 92918 186073 92918 186074 93151 186074 93153 186074 92918 186075 93153 186075 92916 186075 93051 186076 92919 186076 92955 186076 92955 186077 92919 186077 93052 186077 92955 186078 93052 186078 93025 186078 93025 186079 93052 186079 92920 186079 93025 186080 92920 186080 92921 186080 92921 186081 92920 186081 92923 186081 92921 186082 92923 186082 92922 186082 92922 186083 92923 186083 92895 186083 92922 186084 92895 186084 92924 186084 92924 186085 92895 186085 92965 186085 92924 186086 92965 186086 92925 186086 92925 186087 92965 186087 92898 186087 92927 186088 92926 186088 92928 186088 92927 186089 92928 186089 93158 186089 93158 186090 92928 186090 93119 186090 93158 186091 93119 186091 92967 186091 92926 186092 92927 186092 93165 186092 92926 186093 93165 186093 93112 186093 93165 186094 93164 186094 93112 186094 93112 186095 93164 186095 93163 186095 93112 186096 93163 186096 92930 186096 93163 186097 92929 186097 92930 186097 92930 186098 92929 186098 93162 186098 92930 186099 93162 186099 92932 186099 93162 186100 92931 186100 92932 186100 92932 186101 92931 186101 93160 186101 92932 186102 93160 186102 92935 186102 92933 186103 92938 186103 92934 186103 92934 186104 92938 186104 92935 186104 92934 186105 92935 186105 92936 186105 92936 186106 92935 186106 93160 186106 93159 186107 93157 186107 92939 186107 93159 186108 92939 186108 92937 186108 92937 186109 92939 186109 92938 186109 92937 186110 92938 186110 92933 186110 93014 186111 93013 186111 93157 186111 93157 186112 93013 186112 92939 186112 93123 186113 92940 186113 92941 186113 92941 186114 92940 186114 92885 186114 92942 186115 92943 186115 93147 186115 93147 186116 92943 186116 93019 186116 93148 186117 92944 186117 93146 186117 93146 186118 92944 186118 92943 186118 93146 186119 92943 186119 92942 186119 93145 186120 92944 186120 93148 186120 93148 186121 92945 186121 93145 186121 93145 186122 92945 186122 92946 186122 93145 186123 92946 186123 92948 186123 92948 186124 92946 186124 93156 186124 93156 186125 92947 186125 92948 186125 92948 186126 92947 186126 93155 186126 92948 186127 93155 186127 93143 186127 93150 186128 92950 186128 92949 186128 92949 186129 92950 186129 93142 186129 93155 186130 93154 186130 93143 186130 93143 186131 93154 186131 92951 186131 93143 186132 92951 186132 93142 186132 93142 186133 92951 186133 93152 186133 93142 186134 93152 186134 92949 186134 92957 186135 92952 186135 93139 186135 92957 186136 93139 186136 92953 186136 92953 186137 93139 186137 92950 186137 92953 186138 92950 186138 93150 186138 92954 186139 92956 186139 92955 186139 92955 186140 92956 186140 92952 186140 92955 186141 92952 186141 92957 186141 92956 186142 92954 186142 92904 186142 92956 186143 92904 186143 93135 186143 93135 186144 92904 186144 92902 186144 93135 186145 92902 186145 93136 186145 93136 186146 92902 186146 92901 186146 93136 186147 92901 186147 93137 186147 93137 186148 92901 186148 92959 186148 93137 186149 92959 186149 92958 186149 92958 186150 92959 186150 92960 186150 92960 186151 92959 186151 92896 186151 92960 186152 92896 186152 92899 186152 92960 186153 92899 186153 92962 186153 92962 186154 92899 186154 92961 186154 92962 186155 92961 186155 92963 186155 92963 186156 92961 186156 92964 186156 92963 186157 92964 186157 93127 186157 93127 186158 92964 186158 92965 186158 93127 186159 92965 186159 93128 186159 93128 186160 92965 186160 93119 186160 93119 186161 92965 186161 92966 186161 93119 186162 92966 186162 92967 186162 93109 186163 93106 186163 93114 186163 93138 186164 93062 186164 93060 186164 93084 186165 92979 186165 92975 186165 93138 186166 93060 186166 93141 186166 93130 186167 93132 186167 92968 186167 92968 186168 93132 186168 92969 186168 92968 186169 92969 186169 93103 186169 93106 186170 92978 186170 92977 186170 92968 186171 92970 186171 93130 186171 93130 186172 92970 186172 92971 186172 93130 186173 92971 186173 92972 186173 92972 186174 92971 186174 93099 186174 92972 186175 93099 186175 93122 186175 93122 186176 93099 186176 92973 186176 93122 186177 92973 186177 92986 186177 92986 186178 92973 186178 92985 186178 92969 186179 93134 186179 93103 186179 93103 186180 93134 186180 92974 186180 93103 186181 92974 186181 92975 186181 92975 186182 92974 186182 92976 186182 92975 186183 92976 186183 93084 186183 92977 186184 92978 186184 92979 186184 92979 186185 92978 186185 93105 186185 92979 186186 93105 186186 92975 186186 92977 186187 92980 186187 93106 186187 93106 186188 92980 186188 92981 186188 93106 186189 92981 186189 93114 186189 93138 186190 92982 186190 93038 186190 93038 186191 92982 186191 92983 186191 93038 186192 92983 186192 93040 186192 93040 186193 92983 186193 93004 186193 93040 186194 93004 186194 93041 186194 93114 186195 92984 186195 93109 186195 93109 186196 92984 186196 93120 186196 93109 186197 93120 186197 92985 186197 92985 186198 93120 186198 93121 186198 92985 186199 93121 186199 92986 186199 92981 186200 92987 186200 93114 186200 93114 186201 92987 186201 93003 186201 93114 186202 93003 186202 93111 186202 92988 186203 92989 186203 93113 186203 93113 186204 92989 186204 93117 186204 93060 186205 92990 186205 93141 186205 93141 186206 92990 186206 92991 186206 93141 186207 92991 186207 93140 186207 93140 186208 92991 186208 92993 186208 93140 186209 92993 186209 92992 186209 92992 186210 92993 186210 93144 186210 93144 186211 92993 186211 92994 186211 92994 186212 92993 186212 92988 186212 92994 186213 92988 186213 92995 186213 92995 186214 92988 186214 93087 186214 92995 186215 93087 186215 92996 186215 92996 186216 93087 186216 92997 186216 92996 186217 92997 186217 92998 186217 92998 186218 92997 186218 92999 186218 92998 186219 92999 186219 92976 186219 92976 186220 92999 186220 93085 186220 92976 186221 93085 186221 93084 186221 93113 186222 93000 186222 92988 186222 92988 186223 93000 186223 93001 186223 92988 186224 93001 186224 93087 186224 93087 186225 93001 186225 93111 186225 93087 186226 93111 186226 93002 186226 93002 186227 93111 186227 93003 186227 93115 186228 93012 186228 93066 186228 93004 186229 93129 186229 93041 186229 93041 186230 93129 186230 93124 186230 93041 186231 93124 186231 93005 186231 93038 186232 93037 186232 93138 186232 93138 186233 93037 186233 93036 186233 93138 186234 93036 186234 93062 186234 93062 186235 93036 186235 93006 186235 93062 186236 93006 186236 93063 186236 93063 186237 93006 186237 93010 186237 93063 186238 93010 186238 93011 186238 93124 186239 93125 186239 93005 186239 93005 186240 93125 186240 93126 186240 93005 186241 93126 186241 93044 186241 93044 186242 93126 186242 93008 186242 93044 186243 93008 186243 93007 186243 93007 186244 93008 186244 93118 186244 93007 186245 93118 186245 93035 186245 93035 186246 93118 186246 93115 186246 93035 186247 93115 186247 93009 186247 93009 186248 93115 186248 93066 186248 93009 186249 93066 186249 93010 186249 93010 186250 93066 186250 93065 186250 93010 186251 93065 186251 93011 186251 93012 186252 93115 186252 92989 186252 92989 186253 93115 186253 93116 186253 92989 186254 93116 186254 93117 186254 93013 186255 93014 186255 92882 186255 93013 186256 92882 186256 93015 186256 92882 186257 92878 186257 93015 186257 93015 186258 92878 186258 93016 186258 93015 186259 93016 186259 93017 186259 93017 186260 93016 186260 92880 186260 93017 186261 92880 186261 93018 186261 93018 186262 92880 186262 92940 186262 93018 186263 92940 186263 93123 186263 93147 186264 93019 186264 92891 186264 92891 186265 93019 186265 93133 186265 92891 186266 93133 186266 93020 186266 93020 186267 93133 186267 93021 186267 93020 186268 93021 186268 92893 186268 92893 186269 93021 186269 93131 186269 92893 186270 93131 186270 93022 186270 93022 186271 93131 186271 92941 186271 93022 186272 92941 186272 92885 186272 92925 186273 93033 186273 92924 186273 92924 186274 93033 186274 93023 186274 92924 186275 93023 186275 92922 186275 92922 186276 93023 186276 93034 186276 92922 186277 93034 186277 92921 186277 92921 186278 93034 186278 93024 186278 92921 186279 93024 186279 93025 186279 93025 186280 93024 186280 93027 186280 93025 186281 93027 186281 93026 186281 93026 186282 93027 186282 93028 186282 93026 186283 93028 186283 92905 186283 92905 186284 93028 186284 93029 186284 92905 186285 93029 186285 92903 186285 92903 186286 93029 186286 93030 186286 92903 186287 93030 186287 92900 186287 92900 186288 93030 186288 93039 186288 92900 186289 93039 186289 92897 186289 92897 186290 93039 186290 93031 186290 92897 186291 93031 186291 93032 186291 93032 186292 93031 186292 93042 186292 93032 186293 93042 186293 92898 186293 92898 186294 93042 186294 93043 186294 92898 186295 93043 186295 92925 186295 92925 186296 93043 186296 93033 186296 93023 186297 93035 186297 93034 186297 93034 186298 93035 186298 93009 186298 93034 186299 93009 186299 93024 186299 93024 186300 93009 186300 93010 186300 93024 186301 93010 186301 93027 186301 93027 186302 93010 186302 93006 186302 93027 186303 93006 186303 93028 186303 93028 186304 93006 186304 93036 186304 93028 186305 93036 186305 93029 186305 93029 186306 93036 186306 93037 186306 93029 186307 93037 186307 93030 186307 93030 186308 93037 186308 93038 186308 93030 186309 93038 186309 93039 186309 93039 186310 93038 186310 93040 186310 93039 186311 93040 186311 93031 186311 93031 186312 93040 186312 93041 186312 93031 186313 93041 186313 93042 186313 93042 186314 93041 186314 93005 186314 93042 186315 93005 186315 93043 186315 93043 186316 93005 186316 93044 186316 93043 186317 93044 186317 93033 186317 93033 186318 93044 186318 93007 186318 93033 186319 93007 186319 93023 186319 93023 186320 93007 186320 93035 186320 92910 186321 93057 186321 93045 186321 93045 186322 93057 186322 93047 186322 93045 186323 93047 186323 93046 186323 93046 186324 93047 186324 93048 186324 93046 186325 93048 186325 92918 186325 92918 186326 93048 186326 93049 186326 92918 186327 93049 186327 92917 186327 92917 186328 93049 186328 93050 186328 92917 186329 93050 186329 93051 186329 93051 186330 93050 186330 93058 186330 93051 186331 93058 186331 92919 186331 92919 186332 93058 186332 93059 186332 92919 186333 93059 186333 93052 186333 93052 186334 93059 186334 93053 186334 93052 186335 93053 186335 92920 186335 92920 186336 93053 186336 93061 186336 92920 186337 93061 186337 92923 186337 92923 186338 93061 186338 93054 186338 92923 186339 93054 186339 92895 186339 92895 186340 93054 186340 93055 186340 92895 186341 93055 186341 93056 186341 93056 186342 93055 186342 93064 186342 93056 186343 93064 186343 92910 186343 92910 186344 93064 186344 93057 186344 93047 186345 93012 186345 93048 186345 93048 186346 93012 186346 92989 186346 93048 186347 92989 186347 93049 186347 93049 186348 92989 186348 92988 186348 93049 186349 92988 186349 93050 186349 93050 186350 92988 186350 92993 186350 93050 186351 92993 186351 93058 186351 93058 186352 92993 186352 92991 186352 93058 186353 92991 186353 93059 186353 93059 186354 92991 186354 92990 186354 93059 186355 92990 186355 93053 186355 93053 186356 92990 186356 93060 186356 93053 186357 93060 186357 93061 186357 93061 186358 93060 186358 93062 186358 93061 186359 93062 186359 93054 186359 93054 186360 93062 186360 93063 186360 93054 186361 93063 186361 93055 186361 93055 186362 93063 186362 93011 186362 93055 186363 93011 186363 93064 186363 93064 186364 93011 186364 93065 186364 93064 186365 93065 186365 93057 186365 93057 186366 93065 186366 93066 186366 93057 186367 93066 186367 93047 186367 93047 186368 93066 186368 93012 186368 93067 186369 93089 186369 93068 186369 93068 186370 93089 186370 93069 186370 93068 186371 93069 186371 93070 186371 93070 186372 93069 186372 93071 186372 93070 186373 93071 186373 93073 186373 93073 186374 93071 186374 93072 186374 93073 186375 93072 186375 93074 186375 93074 186376 93072 186376 93075 186376 93074 186377 93075 186377 92889 186377 92889 186378 93075 186378 93083 186378 92889 186379 93083 186379 92894 186379 92894 186380 93083 186380 93086 186380 92894 186381 93086 186381 93076 186381 93076 186382 93086 186382 93078 186382 93076 186383 93078 186383 93077 186383 93077 186384 93078 186384 93079 186384 93077 186385 93079 186385 92909 186385 92909 186386 93079 186386 93080 186386 92909 186387 93080 186387 92907 186387 92907 186388 93080 186388 93088 186388 92907 186389 93088 186389 92906 186389 92906 186390 93088 186390 93081 186390 92906 186391 93081 186391 93067 186391 93067 186392 93081 186392 93089 186392 93069 186393 92981 186393 93071 186393 93071 186394 92981 186394 92980 186394 93071 186395 92980 186395 93072 186395 93072 186396 92980 186396 93082 186396 93072 186397 93082 186397 93075 186397 93075 186398 93082 186398 92979 186398 93075 186399 92979 186399 93083 186399 93083 186400 92979 186400 93084 186400 93083 186401 93084 186401 93086 186401 93086 186402 93084 186402 93085 186402 93086 186403 93085 186403 93078 186403 93078 186404 93085 186404 92999 186404 93078 186405 92999 186405 93079 186405 93079 186406 92999 186406 92997 186406 93079 186407 92997 186407 93080 186407 93080 186408 92997 186408 93087 186408 93080 186409 93087 186409 93088 186409 93088 186410 93087 186410 93002 186410 93088 186411 93002 186411 93081 186411 93081 186412 93002 186412 93003 186412 93081 186413 93003 186413 93089 186413 93089 186414 93003 186414 92987 186414 93089 186415 92987 186415 93069 186415 93069 186416 92987 186416 92981 186416 92879 186417 93110 186417 92881 186417 92881 186418 93110 186418 93091 186418 92881 186419 93091 186419 93090 186419 93090 186420 93091 186420 93098 186420 93090 186421 93098 186421 93092 186421 93092 186422 93098 186422 93093 186422 93092 186423 93093 186423 92884 186423 92884 186424 93093 186424 93100 186424 92884 186425 93100 186425 92886 186425 92886 186426 93100 186426 93094 186426 92886 186427 93094 186427 92892 186427 92892 186428 93094 186428 93101 186428 92892 186429 93101 186429 92890 186429 92890 186430 93101 186430 93102 186430 92890 186431 93102 186431 93095 186431 93095 186432 93102 186432 93104 186432 93095 186433 93104 186433 93096 186433 93096 186434 93104 186434 93097 186434 93096 186435 93097 186435 92887 186435 92887 186436 93097 186436 93107 186436 92887 186437 93107 186437 92888 186437 92888 186438 93107 186438 93108 186438 92888 186439 93108 186439 92879 186439 92879 186440 93108 186440 93110 186440 93091 186441 92973 186441 93098 186441 93098 186442 92973 186442 93099 186442 93098 186443 93099 186443 93093 186443 93093 186444 93099 186444 92971 186444 93093 186445 92971 186445 93100 186445 93100 186446 92971 186446 92970 186446 93100 186447 92970 186447 93094 186447 93094 186448 92970 186448 92968 186448 93094 186449 92968 186449 93101 186449 93101 186450 92968 186450 93103 186450 93101 186451 93103 186451 93102 186451 93102 186452 93103 186452 92975 186452 93102 186453 92975 186453 93104 186453 93104 186454 92975 186454 93105 186454 93104 186455 93105 186455 93097 186455 93097 186456 93105 186456 92978 186456 93097 186457 92978 186457 93107 186457 93107 186458 92978 186458 93106 186458 93107 186459 93106 186459 93108 186459 93108 186460 93106 186460 93109 186460 93108 186461 93109 186461 93110 186461 93110 186462 93109 186462 92985 186462 93110 186463 92985 186463 93091 186463 93091 186464 92985 186464 92973 186464 92938 186465 93114 186465 92935 186465 92935 186466 93114 186466 93111 186466 92935 186467 93111 186467 92932 186467 92932 186468 93111 186468 93001 186468 92932 186469 93001 186469 92930 186469 92930 186470 93001 186470 93000 186470 92930 186471 93000 186471 93112 186471 93112 186472 93000 186472 93113 186472 93112 186473 93113 186473 92926 186473 92926 186474 93113 186474 93117 186474 92938 186475 92939 186475 93114 186475 93114 186476 92939 186476 92984 186476 93115 186477 93119 186477 92928 186477 93115 186478 92928 186478 93116 186478 93116 186479 92928 186479 92926 186479 93116 186480 92926 186480 93117 186480 93013 186481 93120 186481 92939 186481 92939 186482 93120 186482 92984 186482 93118 186483 93128 186483 93115 186483 93115 186484 93128 186484 93119 186484 93120 186485 93013 186485 93015 186485 93120 186486 93015 186486 93121 186486 93121 186487 93015 186487 93017 186487 93121 186488 93017 186488 92986 186488 92986 186489 93017 186489 93018 186489 92986 186490 93018 186490 93122 186490 93122 186491 93018 186491 93123 186491 93122 186492 93123 186492 92972 186492 93124 186493 92960 186493 92962 186493 93124 186494 92962 186494 93125 186494 93125 186495 92962 186495 92963 186495 93125 186496 92963 186496 93126 186496 93126 186497 92963 186497 93127 186497 93126 186498 93127 186498 93008 186498 93008 186499 93127 186499 93128 186499 93008 186500 93128 186500 93118 186500 92941 186501 93130 186501 93123 186501 93123 186502 93130 186502 92972 186502 93129 186503 92958 186503 93124 186503 93124 186504 92958 186504 92960 186504 93130 186505 92941 186505 93131 186505 93130 186506 93131 186506 93132 186506 93132 186507 93131 186507 93021 186507 93132 186508 93021 186508 92969 186508 92969 186509 93021 186509 93133 186509 92969 186510 93133 186510 93134 186510 93134 186511 93133 186511 93019 186511 93134 186512 93019 186512 92974 186512 93138 186513 92956 186513 93135 186513 93138 186514 93135 186514 92982 186514 92982 186515 93135 186515 93136 186515 92982 186516 93136 186516 92983 186516 92983 186517 93136 186517 93137 186517 92983 186518 93137 186518 93004 186518 93004 186519 93137 186519 92958 186519 93004 186520 92958 186520 93129 186520 92943 186521 92976 186521 93019 186521 93019 186522 92976 186522 92974 186522 93141 186523 92952 186523 93138 186523 93138 186524 92952 186524 92956 186524 92943 186525 92944 186525 92976 186525 92976 186526 92944 186526 92998 186526 92992 186527 92950 186527 93139 186527 92992 186528 93139 186528 93140 186528 93140 186529 93139 186529 92952 186529 93140 186530 92952 186530 93141 186530 92950 186531 92992 186531 93142 186531 93142 186532 92992 186532 93144 186532 93142 186533 93144 186533 93143 186533 93143 186534 93144 186534 92994 186534 93143 186535 92994 186535 92948 186535 92948 186536 92994 186536 92995 186536 92948 186537 92995 186537 93145 186537 93145 186538 92995 186538 92996 186538 93145 186539 92996 186539 92944 186539 92944 186540 92996 186540 92998 186540 92955 186541 92957 186541 93151 186541 93151 186542 92957 186542 92953 186542 93146 186543 92942 186543 93149 186543 93149 186544 92942 186544 93147 186544 93149 186545 93147 186545 92891 186545 93146 186546 93149 186546 93148 186546 93148 186547 93149 186547 92914 186547 93148 186548 92914 186548 92945 186548 92953 186549 93150 186549 93151 186549 93151 186550 93150 186550 92949 186550 93151 186551 92949 186551 93153 186551 92949 186552 93152 186552 93153 186552 93153 186553 93152 186553 92951 186553 93153 186554 92951 186554 92916 186554 92951 186555 93154 186555 92916 186555 92916 186556 93154 186556 93155 186556 92916 186557 93155 186557 92915 186557 93155 186558 92947 186558 92915 186558 92915 186559 92947 186559 93156 186559 92915 186560 93156 186560 92914 186560 92914 186561 93156 186561 92946 186561 92914 186562 92946 186562 92945 186562 92882 186563 93014 186563 92883 186563 92883 186564 93014 186564 93157 186564 92883 186565 93157 186565 93159 186565 92927 186566 93158 186566 92911 186566 92911 186567 93158 186567 92967 186567 92911 186568 92967 186568 92966 186568 93159 186569 92937 186569 92883 186569 92883 186570 92937 186570 92933 186570 92883 186571 92933 186571 92908 186571 92933 186572 92934 186572 92908 186572 92908 186573 92934 186573 92936 186573 92908 186574 92936 186574 92913 186574 92936 186575 93160 186575 92913 186575 92913 186576 93160 186576 92931 186576 92913 186577 92931 186577 93161 186577 92931 186578 93162 186578 93161 186578 93161 186579 93162 186579 92929 186579 93161 186580 92929 186580 92912 186580 92929 186581 93163 186581 92912 186581 92912 186582 93163 186582 93164 186582 92912 186583 93164 186583 92911 186583 92911 186584 93164 186584 93165 186584 92911 186585 93165 186585 92927 186585 93166 186586 93167 186586 96092 186586 96092 186587 93167 186587 95642 186587 95988 186588 95407 186588 93814 186588 93814 186589 95407 186589 95416 186589 95990 186590 95445 186590 93168 186590 93168 186591 95445 186591 93169 186591 93170 186592 93171 186592 93172 186592 93172 186593 93171 186593 95427 186593 93173 186594 93174 186594 95998 186594 95998 186595 93174 186595 93667 186595 95999 186596 93176 186596 93175 186596 93175 186597 93176 186597 95447 186597 93898 186598 95479 186598 96004 186598 96004 186599 95479 186599 93678 186599 96007 186600 93178 186600 93177 186600 93177 186601 93178 186601 95458 186601 96018 186602 95498 186602 93179 186602 93179 186603 95498 186603 93180 186603 96014 186604 95483 186604 96016 186604 96016 186605 95483 186605 93882 186605 93181 186606 93880 186606 96019 186606 96019 186607 93880 186607 95519 186607 93693 186608 93182 186608 93876 186608 93876 186609 93182 186609 93183 186609 96033 186610 93184 186610 93185 186610 93185 186611 93184 186611 93186 186611 96030 186612 95292 186612 96032 186612 96032 186613 95292 186613 93187 186613 93864 186614 93188 186614 93576 186614 93576 186615 93188 186615 93575 186615 96040 186616 95310 186616 93858 186616 93858 186617 95310 186617 95308 186617 96046 186618 95557 186618 96049 186618 96049 186619 95557 186619 95556 186619 93707 186620 95542 186620 96048 186620 96048 186621 95542 186621 93852 186621 93848 186622 95574 186622 96055 186622 96055 186623 95574 186623 95578 186623 93189 186624 93716 186624 93190 186624 93190 186625 93716 186625 93191 186625 93842 186626 95602 186626 96065 186626 96065 186627 95602 186627 95605 186627 93192 186628 95583 186628 96068 186628 96068 186629 95583 186629 93838 186629 96078 186630 93835 186630 96070 186630 96070 186631 93835 186631 95629 186631 96072 186632 93731 186632 96076 186632 96076 186633 93731 186633 95607 186633 96089 186634 93193 186634 96088 186634 96088 186635 93193 186635 95521 186635 96090 186636 93195 186636 93194 186636 93194 186637 93195 186637 93585 186637 93581 186638 95531 186638 96086 186638 96086 186639 95531 186639 96085 186639 93196 186640 93197 186640 93198 186640 93198 186641 93197 186641 96097 186641 95717 186642 93199 186642 93813 186642 93813 186643 93199 186643 96100 186643 95701 186644 95693 186644 93776 186644 93776 186645 95693 186645 96107 186645 93808 186646 95702 186646 96103 186646 96103 186647 95702 186647 96108 186647 95654 186648 95649 186648 93200 186648 93200 186649 95649 186649 93201 186649 95652 186650 93768 186650 93202 186650 93202 186651 93768 186651 93203 186651 95679 186652 93752 186652 93749 186652 93749 186653 93752 186653 93204 186653 95677 186654 93746 186654 96122 186654 96122 186655 93746 186655 93748 186655 93205 186656 93736 186656 93206 186656 93206 186657 93736 186657 96091 186657 95623 186658 95611 186658 93725 186658 93725 186659 95611 186659 96075 186659 93717 186660 93207 186660 96064 186660 96064 186661 93207 186661 96066 186661 93208 186662 93209 186662 96056 186662 96056 186663 93209 186663 93210 186663 93700 186664 93705 186664 93701 186664 93701 186665 93705 186665 96051 186665 95316 186666 95311 186666 93572 186666 93572 186667 95311 186667 93577 186667 95299 186668 95293 186668 93211 186668 93211 186669 95293 186669 93212 186669 95513 186670 93687 186670 96021 186670 96021 186671 93687 186671 96024 186671 95496 186672 95493 186672 96012 186672 96012 186673 95493 186673 96013 186673 95467 186674 93213 186674 93673 186674 93673 186675 93213 186675 96003 186675 93664 186676 93670 186676 93214 186676 93214 186677 93670 186677 96001 186677 93215 186678 93662 186678 93655 186678 93655 186679 93662 186679 93661 186679 95396 186680 93216 186680 93650 186680 93650 186681 93216 186681 93642 186681 95398 186682 93217 186682 96125 186682 96125 186683 93217 186683 93218 186683 93219 186684 95410 186684 93635 186684 93635 186685 95410 186685 93220 186685 95375 186686 93221 186686 96141 186686 96141 186687 93221 186687 96134 186687 93623 186688 95378 186688 96140 186688 96140 186689 95378 186689 96137 186689 95360 186690 93222 186690 93223 186690 93223 186691 93222 186691 96155 186691 93590 186692 93225 186692 93224 186692 93224 186693 93225 186693 93226 186693 93229 186694 95974 186694 95981 186694 93227 186695 93228 186695 95929 186695 95981 186696 95980 186696 93229 186696 93229 186697 95980 186697 95979 186697 93229 186698 95979 186698 95929 186698 95929 186699 95979 186699 93230 186699 95929 186700 93230 186700 93227 186700 93236 186701 95964 186701 93231 186701 93555 186702 93232 186702 95963 186702 95963 186703 93233 186703 93555 186703 93555 186704 93233 186704 93234 186704 93555 186705 93234 186705 93231 186705 93231 186706 93234 186706 93235 186706 93231 186707 93235 186707 93236 186707 96386 186708 94583 186708 93237 186708 93237 186709 94583 186709 93239 186709 93237 186710 93239 186710 93238 186710 93238 186711 93239 186711 94584 186711 93238 186712 94584 186712 96389 186712 96389 186713 94584 186713 93240 186713 96389 186714 93240 186714 93241 186714 93241 186715 93240 186715 93242 186715 93241 186716 93242 186716 96391 186716 96391 186717 93242 186717 93243 186717 96391 186718 93243 186718 93244 186718 93244 186719 93243 186719 94586 186719 93244 186720 94586 186720 93245 186720 93245 186721 94586 186721 94587 186721 93245 186722 94587 186722 96392 186722 96392 186723 94587 186723 93246 186723 96392 186724 93246 186724 96381 186724 96381 186725 93246 186725 94590 186725 96381 186726 94590 186726 96382 186726 96382 186727 94590 186727 94592 186727 96382 186728 94592 186728 96383 186728 96383 186729 94592 186729 94593 186729 96383 186730 94593 186730 96386 186730 96386 186731 94593 186731 94583 186731 96377 186732 94611 186732 96378 186732 96378 186733 94611 186733 94613 186733 96378 186734 94613 186734 93247 186734 93247 186735 94613 186735 94614 186735 93247 186736 94614 186736 93248 186736 93248 186737 94614 186737 94615 186737 93248 186738 94615 186738 93249 186738 93249 186739 94615 186739 94617 186739 93249 186740 94617 186740 96379 186740 96379 186741 94617 186741 94619 186741 96379 186742 94619 186742 93251 186742 93251 186743 94619 186743 93250 186743 93251 186744 93250 186744 96369 186744 96369 186745 93250 186745 93252 186745 96369 186746 93252 186746 96371 186746 96371 186747 93252 186747 94620 186747 96371 186748 94620 186748 96372 186748 96372 186749 94620 186749 94621 186749 96372 186750 94621 186750 96375 186750 96375 186751 94621 186751 93254 186751 96375 186752 93254 186752 93253 186752 93253 186753 93254 186753 94610 186753 93253 186754 94610 186754 96377 186754 96377 186755 94610 186755 94611 186755 96367 186756 94633 186756 93255 186756 93255 186757 94633 186757 93256 186757 93255 186758 93256 186758 96356 186758 96356 186759 93256 186759 94635 186759 96356 186760 94635 186760 96358 186760 96358 186761 94635 186761 94637 186761 96358 186762 94637 186762 93257 186762 93257 186763 94637 186763 94639 186763 93257 186764 94639 186764 96359 186764 96359 186765 94639 186765 93258 186765 96359 186766 93258 186766 93259 186766 93259 186767 93258 186767 94640 186767 93259 186768 94640 186768 96361 186768 96361 186769 94640 186769 93260 186769 96361 186770 93260 186770 96362 186770 96362 186771 93260 186771 93262 186771 96362 186772 93262 186772 93261 186772 93261 186773 93262 186773 94644 186773 93261 186774 94644 186774 93263 186774 93263 186775 94644 186775 93264 186775 93263 186776 93264 186776 96366 186776 96366 186777 93264 186777 94646 186777 96366 186778 94646 186778 96367 186778 96367 186779 94646 186779 94633 186779 96351 186780 93277 186780 93265 186780 93265 186781 93277 186781 94655 186781 93265 186782 94655 186782 96342 186782 96342 186783 94655 186783 93266 186783 96342 186784 93266 186784 93267 186784 93267 186785 93266 186785 94658 186785 93267 186786 94658 186786 93268 186786 93268 186787 94658 186787 94659 186787 93268 186788 94659 186788 93269 186788 93269 186789 94659 186789 94661 186789 93269 186790 94661 186790 93270 186790 93270 186791 94661 186791 94662 186791 93270 186792 94662 186792 96346 186792 96346 186793 94662 186793 93271 186793 96346 186794 93271 186794 93272 186794 93272 186795 93271 186795 93273 186795 93272 186796 93273 186796 93274 186796 93274 186797 93273 186797 94664 186797 93274 186798 94664 186798 93275 186798 93275 186799 94664 186799 93276 186799 93275 186800 93276 186800 96350 186800 96350 186801 93276 186801 94665 186801 96350 186802 94665 186802 96351 186802 96351 186803 94665 186803 93277 186803 93288 186804 94683 186804 93278 186804 93278 186805 94683 186805 93280 186805 93278 186806 93280 186806 93279 186806 93279 186807 93280 186807 94686 186807 93279 186808 94686 186808 93281 186808 93281 186809 94686 186809 94687 186809 93281 186810 94687 186810 93282 186810 93282 186811 94687 186811 94689 186811 93282 186812 94689 186812 96337 186812 96337 186813 94689 186813 93283 186813 96337 186814 93283 186814 96339 186814 96339 186815 93283 186815 94691 186815 96339 186816 94691 186816 93284 186816 93284 186817 94691 186817 93285 186817 93284 186818 93285 186818 96340 186818 96340 186819 93285 186819 94694 186819 96340 186820 94694 186820 96341 186820 96341 186821 94694 186821 93286 186821 96341 186822 93286 186822 96332 186822 96332 186823 93286 186823 94696 186823 96332 186824 94696 186824 93287 186824 93287 186825 94696 186825 94681 186825 93287 186826 94681 186826 93288 186826 93288 186827 94681 186827 94683 186827 96322 186828 94712 186828 93289 186828 93289 186829 94712 186829 93290 186829 93289 186830 93290 186830 96324 186830 96324 186831 93290 186831 94713 186831 96324 186832 94713 186832 93291 186832 93291 186833 94713 186833 93292 186833 93291 186834 93292 186834 96326 186834 96326 186835 93292 186835 93293 186835 96326 186836 93293 186836 96327 186836 96327 186837 93293 186837 94715 186837 96327 186838 94715 186838 96329 186838 96329 186839 94715 186839 94716 186839 96329 186840 94716 186840 93294 186840 93294 186841 94716 186841 93295 186841 93294 186842 93295 186842 93296 186842 93296 186843 93295 186843 94719 186843 93296 186844 94719 186844 93297 186844 93297 186845 94719 186845 94720 186845 93297 186846 94720 186846 93298 186846 93298 186847 94720 186847 94721 186847 93298 186848 94721 186848 96321 186848 96321 186849 94721 186849 94711 186849 96321 186850 94711 186850 96322 186850 96322 186851 94711 186851 94712 186851 93299 186852 93300 186852 93301 186852 93301 186853 93300 186853 94737 186853 93301 186854 94737 186854 93302 186854 93302 186855 94737 186855 93303 186855 93302 186856 93303 186856 93304 186856 93304 186857 93303 186857 93305 186857 93304 186858 93305 186858 93306 186858 93306 186859 93305 186859 93307 186859 93306 186860 93307 186860 93308 186860 93308 186861 93307 186861 93309 186861 93308 186862 93309 186862 96313 186862 96313 186863 93309 186863 93310 186863 96313 186864 93310 186864 93312 186864 93312 186865 93310 186865 93311 186865 93312 186866 93311 186866 93313 186866 93313 186867 93311 186867 94742 186867 93313 186868 94742 186868 96315 186868 96315 186869 94742 186869 93314 186869 96315 186870 93314 186870 93315 186870 93315 186871 93314 186871 93316 186871 93315 186872 93316 186872 96317 186872 96317 186873 93316 186873 93317 186873 96317 186874 93317 186874 93299 186874 93299 186875 93317 186875 93300 186875 96311 186876 94754 186876 96299 186876 96299 186877 94754 186877 94755 186877 96299 186878 94755 186878 93318 186878 93318 186879 94755 186879 94757 186879 93318 186880 94757 186880 93320 186880 93320 186881 94757 186881 93319 186881 93320 186882 93319 186882 93321 186882 93321 186883 93319 186883 93322 186883 93321 186884 93322 186884 96304 186884 96304 186885 93322 186885 94761 186885 96304 186886 94761 186886 96306 186886 96306 186887 94761 186887 93323 186887 96306 186888 93323 186888 96307 186888 96307 186889 93323 186889 94764 186889 96307 186890 94764 186890 93324 186890 93324 186891 94764 186891 94765 186891 93324 186892 94765 186892 93325 186892 93325 186893 94765 186893 93326 186893 93325 186894 93326 186894 93327 186894 93327 186895 93326 186895 93328 186895 93327 186896 93328 186896 96310 186896 96310 186897 93328 186897 93329 186897 96310 186898 93329 186898 96311 186898 96311 186899 93329 186899 94754 186899 93330 186900 93331 186900 93332 186900 93332 186901 93331 186901 94781 186901 93332 186902 94781 186902 93333 186902 93333 186903 94781 186903 94784 186903 93333 186904 94784 186904 93334 186904 93334 186905 94784 186905 94785 186905 93334 186906 94785 186906 96290 186906 96290 186907 94785 186907 93335 186907 96290 186908 93335 186908 96291 186908 96291 186909 93335 186909 93336 186909 96291 186910 93336 186910 96292 186910 96292 186911 93336 186911 93337 186911 96292 186912 93337 186912 96293 186912 96293 186913 93337 186913 93338 186913 96293 186914 93338 186914 96295 186914 96295 186915 93338 186915 93339 186915 96295 186916 93339 186916 96296 186916 96296 186917 93339 186917 93340 186917 96296 186918 93340 186918 96287 186918 96287 186919 93340 186919 93341 186919 96287 186920 93341 186920 96288 186920 96288 186921 93341 186921 94780 186921 96288 186922 94780 186922 93330 186922 93330 186923 94780 186923 93331 186923 96279 186924 93342 186924 96280 186924 96280 186925 93342 186925 93343 186925 96280 186926 93343 186926 96281 186926 96281 186927 93343 186927 94802 186927 96281 186928 94802 186928 96282 186928 96282 186929 94802 186929 93344 186929 96282 186930 93344 186930 93345 186930 93345 186931 93344 186931 93346 186931 93345 186932 93346 186932 96283 186932 96283 186933 93346 186933 93347 186933 96283 186934 93347 186934 93349 186934 93349 186935 93347 186935 93348 186935 93349 186936 93348 186936 93350 186936 93350 186937 93348 186937 93352 186937 93350 186938 93352 186938 93351 186938 93351 186939 93352 186939 93353 186939 93351 186940 93353 186940 93354 186940 93354 186941 93353 186941 93355 186941 93354 186942 93355 186942 93356 186942 93356 186943 93355 186943 93357 186943 93356 186944 93357 186944 96278 186944 96278 186945 93357 186945 94799 186945 96278 186946 94799 186946 96279 186946 96279 186947 94799 186947 93342 186947 96264 186948 94815 186948 93358 186948 93358 186949 94815 186949 94816 186949 93358 186950 94816 186950 93359 186950 93359 186951 94816 186951 94818 186951 93359 186952 94818 186952 93360 186952 93360 186953 94818 186953 94820 186953 93360 186954 94820 186954 93361 186954 93361 186955 94820 186955 93362 186955 93361 186956 93362 186956 96270 186956 96270 186957 93362 186957 94821 186957 96270 186958 94821 186958 93364 186958 93364 186959 94821 186959 93363 186959 93364 186960 93363 186960 93366 186960 93366 186961 93363 186961 93365 186961 93366 186962 93365 186962 96272 186962 96272 186963 93365 186963 94824 186963 96272 186964 94824 186964 96273 186964 96273 186965 94824 186965 93367 186965 96273 186966 93367 186966 96275 186966 96275 186967 93367 186967 94825 186967 96275 186968 94825 186968 93369 186968 93369 186969 94825 186969 93368 186969 93369 186970 93368 186970 96264 186970 96264 186971 93368 186971 94815 186971 96263 186972 94841 186972 93370 186972 93370 186973 94841 186973 94842 186973 93370 186974 94842 186974 93371 186974 93371 186975 94842 186975 93372 186975 93371 186976 93372 186976 93373 186976 93373 186977 93372 186977 93374 186977 93373 186978 93374 186978 96254 186978 96254 186979 93374 186979 93375 186979 96254 186980 93375 186980 93376 186980 93376 186981 93375 186981 93377 186981 93376 186982 93377 186982 96256 186982 96256 186983 93377 186983 94847 186983 96256 186984 94847 186984 96258 186984 96258 186985 94847 186985 93378 186985 96258 186986 93378 186986 96260 186986 96260 186987 93378 186987 93379 186987 96260 186988 93379 186988 96261 186988 96261 186989 93379 186989 93380 186989 96261 186990 93380 186990 93381 186990 93381 186991 93380 186991 93382 186991 93381 186992 93382 186992 96262 186992 96262 186993 93382 186993 93383 186993 96262 186994 93383 186994 96263 186994 96263 186995 93383 186995 94841 186995 93384 186996 93394 186996 96242 186996 96242 186997 93394 186997 93385 186997 96242 186998 93385 186998 93386 186998 93386 186999 93385 186999 94871 186999 93386 187000 94871 187000 93387 187000 93387 187001 94871 187001 93388 187001 93387 187002 93388 187002 96244 187002 96244 187003 93388 187003 93389 187003 96244 187004 93389 187004 96246 187004 96246 187005 93389 187005 94873 187005 96246 187006 94873 187006 96248 187006 96248 187007 94873 187007 94874 187007 96248 187008 94874 187008 96249 187008 96249 187009 94874 187009 93390 187009 96249 187010 93390 187010 93391 187010 93391 187011 93390 187011 94875 187011 93391 187012 94875 187012 96250 187012 96250 187013 94875 187013 94876 187013 96250 187014 94876 187014 93392 187014 93392 187015 94876 187015 94878 187015 93392 187016 94878 187016 96241 187016 96241 187017 94878 187017 93393 187017 96241 187018 93393 187018 93384 187018 93384 187019 93393 187019 93394 187019 93406 187020 93408 187020 93395 187020 93395 187021 93408 187021 94901 187021 93395 187022 94901 187022 93396 187022 93396 187023 94901 187023 94903 187023 93396 187024 94903 187024 93397 187024 93397 187025 94903 187025 93398 187025 93397 187026 93398 187026 96236 187026 96236 187027 93398 187027 93399 187027 96236 187028 93399 187028 96237 187028 96237 187029 93399 187029 94905 187029 96237 187030 94905 187030 96238 187030 96238 187031 94905 187031 93400 187031 96238 187032 93400 187032 93401 187032 93401 187033 93400 187033 94906 187033 93401 187034 94906 187034 93403 187034 93403 187035 94906 187035 93402 187035 93403 187036 93402 187036 93404 187036 93404 187037 93402 187037 94907 187037 93404 187038 94907 187038 93405 187038 93405 187039 94907 187039 94908 187039 93405 187040 94908 187040 96235 187040 96235 187041 94908 187041 93407 187041 96235 187042 93407 187042 93406 187042 93406 187043 93407 187043 93408 187043 96234 187044 94925 187044 96224 187044 96224 187045 94925 187045 94926 187045 96224 187046 94926 187046 96225 187046 96225 187047 94926 187047 93409 187047 96225 187048 93409 187048 96227 187048 96227 187049 93409 187049 94927 187049 96227 187050 94927 187050 96228 187050 96228 187051 94927 187051 93410 187051 96228 187052 93410 187052 93411 187052 93411 187053 93410 187053 94928 187053 93411 187054 94928 187054 93412 187054 93412 187055 94928 187055 93413 187055 93412 187056 93413 187056 93414 187056 93414 187057 93413 187057 93415 187057 93414 187058 93415 187058 96230 187058 96230 187059 93415 187059 94930 187059 96230 187060 94930 187060 93416 187060 93416 187061 94930 187061 93417 187061 93416 187062 93417 187062 93418 187062 93418 187063 93417 187063 93419 187063 93418 187064 93419 187064 96232 187064 96232 187065 93419 187065 94934 187065 96232 187066 94934 187066 96234 187066 96234 187067 94934 187067 94925 187067 96213 187068 93420 187068 93421 187068 93421 187069 93420 187069 94944 187069 93421 187070 94944 187070 93422 187070 93422 187071 94944 187071 94945 187071 93422 187072 94945 187072 96216 187072 96216 187073 94945 187073 93423 187073 96216 187074 93423 187074 96218 187074 96218 187075 93423 187075 93424 187075 96218 187076 93424 187076 96219 187076 96219 187077 93424 187077 94948 187077 96219 187078 94948 187078 93425 187078 93425 187079 94948 187079 94949 187079 93425 187080 94949 187080 96223 187080 96223 187081 94949 187081 93426 187081 96223 187082 93426 187082 93427 187082 93427 187083 93426 187083 93428 187083 93427 187084 93428 187084 93429 187084 93429 187085 93428 187085 94951 187085 93429 187086 94951 187086 96210 187086 96210 187087 94951 187087 93431 187087 96210 187088 93431 187088 93430 187088 93430 187089 93431 187089 93432 187089 93430 187090 93432 187090 96213 187090 96213 187091 93432 187091 93420 187091 95342 187092 93434 187092 93433 187092 93433 187093 93434 187093 93614 187093 93794 187094 93810 187094 96098 187094 96098 187095 93810 187095 96099 187095 95334 187096 95336 187096 96147 187096 96147 187097 95336 187097 93606 187097 93610 187098 95346 187098 93609 187098 93609 187099 95346 187099 93611 187099 93591 187100 95366 187100 93597 187100 93597 187101 95366 187101 95368 187101 96149 187102 95327 187102 96150 187102 96150 187103 95327 187103 95331 187103 96139 187104 95386 187104 93435 187104 93435 187105 95386 187105 95379 187105 96156 187106 95353 187106 96151 187106 96151 187107 95353 187107 95349 187107 95989 187108 95426 187108 93436 187108 93436 187109 95426 187109 95422 187109 96128 187110 95389 187110 93437 187110 93437 187111 95389 187111 95388 187111 96131 187112 93438 187112 93654 187112 93654 187113 93438 187113 93653 187113 96133 187114 95371 187114 93439 187114 93439 187115 95371 187115 95369 187115 96117 187116 93743 187116 96118 187116 96118 187117 93743 187117 93751 187117 96110 187118 93440 187118 96111 187118 96111 187119 93440 187119 93761 187119 93765 187120 95664 187120 93772 187120 93772 187121 95664 187121 95665 187121 93741 187122 95631 187122 96093 187122 96093 187123 95631 187123 95630 187123 96109 187124 95706 187124 93780 187124 93780 187125 95706 187125 95710 187125 93441 187126 95673 187126 93442 187126 93442 187127 95673 187127 93443 187127 93796 187128 95726 187128 93805 187128 93805 187129 95726 187129 93803 187129 93785 187130 95690 187130 96102 187130 96102 187131 95690 187131 93444 187131 93458 187132 93445 187132 93446 187132 93446 187133 93445 187133 93447 187133 93446 187134 93447 187134 96203 187134 96203 187135 93447 187135 93448 187135 96203 187136 93448 187136 96204 187136 96204 187137 93448 187137 93449 187137 96204 187138 93449 187138 96205 187138 96205 187139 93449 187139 93450 187139 96205 187140 93450 187140 96201 187140 96201 187141 93450 187141 95012 187141 96201 187142 95012 187142 93452 187142 93452 187143 95012 187143 93451 187143 93452 187144 93451 187144 96202 187144 96202 187145 93451 187145 93453 187145 96202 187146 93453 187146 96208 187146 96208 187147 93453 187147 93454 187147 96208 187148 93454 187148 93455 187148 93455 187149 93454 187149 93456 187149 93455 187150 93456 187150 96206 187150 96206 187151 93456 187151 95014 187151 96206 187152 95014 187152 93457 187152 93457 187153 95014 187153 95016 187153 93457 187154 95016 187154 93458 187154 93458 187155 95016 187155 93445 187155 93459 187156 95007 187156 93460 187156 93460 187157 95007 187157 94998 187157 93460 187158 94998 187158 93461 187158 93461 187159 94998 187159 95000 187159 93461 187160 95000 187160 96198 187160 96198 187161 95000 187161 95001 187161 96198 187162 95001 187162 96196 187162 96196 187163 95001 187163 95002 187163 96196 187164 95002 187164 93462 187164 93462 187165 95002 187165 95003 187165 93462 187166 95003 187166 93463 187166 93463 187167 95003 187167 93464 187167 93463 187168 93464 187168 96197 187168 96197 187169 93464 187169 93465 187169 96197 187170 93465 187170 96199 187170 96199 187171 93465 187171 95005 187171 96199 187172 95005 187172 93466 187172 93466 187173 95005 187173 93467 187173 93466 187174 93467 187174 93468 187174 93468 187175 93467 187175 95006 187175 93468 187176 95006 187176 93470 187176 93470 187177 95006 187177 93469 187177 93470 187178 93469 187178 93459 187178 93459 187179 93469 187179 95007 187179 93471 187180 95089 187180 96194 187180 96194 187181 95089 187181 95091 187181 96194 187182 95091 187182 96191 187182 96191 187183 95091 187183 93472 187183 96191 187184 93472 187184 96192 187184 96192 187185 93472 187185 93473 187185 96192 187186 93473 187186 93474 187186 93474 187187 93473 187187 95093 187187 93474 187188 95093 187188 93475 187188 93475 187189 95093 187189 95094 187189 93475 187190 95094 187190 93476 187190 93476 187191 95094 187191 95095 187191 93476 187192 95095 187192 93477 187192 93477 187193 95095 187193 95083 187193 93477 187194 95083 187194 93478 187194 93478 187195 95083 187195 93479 187195 93478 187196 93479 187196 96195 187196 96195 187197 93479 187197 93480 187197 96195 187198 93480 187198 93481 187198 93481 187199 93480 187199 95086 187199 93481 187200 95086 187200 96193 187200 96193 187201 95086 187201 93482 187201 96193 187202 93482 187202 93471 187202 93471 187203 93482 187203 95089 187203 93483 187204 93485 187204 93484 187204 93484 187205 93485 187205 93487 187205 93484 187206 93487 187206 93486 187206 93486 187207 93487 187207 93488 187207 93486 187208 93488 187208 96186 187208 96186 187209 93488 187209 95074 187209 96186 187210 95074 187210 96187 187210 96187 187211 95074 187211 95075 187211 96187 187212 95075 187212 93489 187212 93489 187213 95075 187213 93490 187213 93489 187214 93490 187214 96185 187214 96185 187215 93490 187215 95077 187215 96185 187216 95077 187216 93491 187216 93491 187217 95077 187217 93492 187217 93491 187218 93492 187218 93493 187218 93493 187219 93492 187219 95080 187219 93493 187220 95080 187220 93495 187220 93495 187221 95080 187221 93494 187221 93495 187222 93494 187222 96188 187222 96188 187223 93494 187223 95071 187223 96188 187224 95071 187224 96189 187224 96189 187225 95071 187225 95072 187225 96189 187226 95072 187226 93483 187226 93483 187227 95072 187227 93485 187227 93505 187228 95170 187228 93496 187228 93496 187229 95170 187229 93497 187229 93496 187230 93497 187230 96178 187230 96178 187231 93497 187231 95159 187231 96178 187232 95159 187232 93498 187232 93498 187233 95159 187233 95160 187233 93498 187234 95160 187234 96176 187234 96176 187235 95160 187235 93499 187235 96176 187236 93499 187236 96177 187236 96177 187237 93499 187237 95162 187237 96177 187238 95162 187238 93500 187238 93500 187239 95162 187239 93501 187239 93500 187240 93501 187240 93502 187240 93502 187241 93501 187241 93503 187241 93502 187242 93503 187242 96180 187242 96180 187243 93503 187243 95165 187243 96180 187244 95165 187244 96182 187244 96182 187245 95165 187245 93504 187245 96182 187246 93504 187246 96183 187246 96183 187247 93504 187247 95167 187247 96183 187248 95167 187248 96179 187248 96179 187249 95167 187249 93506 187249 96179 187250 93506 187250 93505 187250 93505 187251 93506 187251 95170 187251 96175 187252 93508 187252 93507 187252 93507 187253 93508 187253 95157 187253 93507 187254 95157 187254 96171 187254 96171 187255 95157 187255 95147 187255 96171 187256 95147 187256 96173 187256 96173 187257 95147 187257 93509 187257 96173 187258 93509 187258 96174 187258 96174 187259 93509 187259 95149 187259 96174 187260 95149 187260 93510 187260 93510 187261 95149 187261 95150 187261 93510 187262 95150 187262 93511 187262 93511 187263 95150 187263 95152 187263 93511 187264 95152 187264 96170 187264 96170 187265 95152 187265 93512 187265 96170 187266 93512 187266 93514 187266 93514 187267 93512 187267 93513 187267 93514 187268 93513 187268 93515 187268 93515 187269 93513 187269 93516 187269 93515 187270 93516 187270 93517 187270 93517 187271 93516 187271 93518 187271 93517 187272 93518 187272 93520 187272 93520 187273 93518 187273 93519 187273 93520 187274 93519 187274 96175 187274 96175 187275 93519 187275 93508 187275 93532 187276 93533 187276 96169 187276 96169 187277 93533 187277 95233 187277 96169 187278 95233 187278 93521 187278 93521 187279 95233 187279 95236 187279 93521 187280 95236 187280 93522 187280 93522 187281 95236 187281 93523 187281 93522 187282 93523 187282 96168 187282 96168 187283 93523 187283 93524 187283 96168 187284 93524 187284 96164 187284 96164 187285 93524 187285 95239 187285 96164 187286 95239 187286 96166 187286 96166 187287 95239 187287 95241 187287 96166 187288 95241 187288 96167 187288 96167 187289 95241 187289 93525 187289 96167 187290 93525 187290 93526 187290 93526 187291 93525 187291 95244 187291 93526 187292 95244 187292 93527 187292 93527 187293 95244 187293 95245 187293 93527 187294 95245 187294 93528 187294 93528 187295 95245 187295 93529 187295 93528 187296 93529 187296 93531 187296 93531 187297 93529 187297 93530 187297 93531 187298 93530 187298 93532 187298 93532 187299 93530 187299 93533 187299 93546 187300 93548 187300 96158 187300 96158 187301 93548 187301 95224 187301 96158 187302 95224 187302 96159 187302 96159 187303 95224 187303 93534 187303 96159 187304 93534 187304 93535 187304 93535 187305 93534 187305 95228 187305 93535 187306 95228 187306 93536 187306 93536 187307 95228 187307 93537 187307 93536 187308 93537 187308 96157 187308 96157 187309 93537 187309 93538 187309 96157 187310 93538 187310 93539 187310 93539 187311 93538 187311 95231 187311 93539 187312 95231 187312 93540 187312 93540 187313 95231 187313 93541 187313 93540 187314 93541 187314 93542 187314 93542 187315 93541 187315 93543 187315 93542 187316 93543 187316 96162 187316 96162 187317 93543 187317 93544 187317 96162 187318 93544 187318 96163 187318 96163 187319 93544 187319 93545 187319 96163 187320 93545 187320 96160 187320 96160 187321 93545 187321 93547 187321 96160 187322 93547 187322 93546 187322 93546 187323 93547 187323 93548 187323 95977 187324 95278 187324 93549 187324 93549 187325 95278 187325 93550 187325 93551 187326 93552 187326 93553 187326 93553 187327 93552 187327 95282 187327 95966 187328 95286 187328 93560 187328 93560 187329 95286 187329 93559 187329 95968 187330 95871 187330 95969 187330 95969 187331 95871 187331 95875 187331 93232 187332 93555 187332 93554 187332 93554 187333 93555 187333 93556 187333 93554 187334 93556 187334 95968 187334 95968 187335 93556 187335 95871 187335 93231 187336 95964 187336 93557 187336 93557 187337 95964 187337 93558 187337 93557 187338 93558 187338 93559 187338 93559 187339 93558 187339 93560 187339 93552 187340 93551 187340 95924 187340 95924 187341 93551 187341 93561 187341 95924 187342 93561 187342 93229 187342 93229 187343 93561 187343 95974 187343 93549 187344 93550 187344 95975 187344 95975 187345 93550 187345 95932 187345 95975 187346 95932 187346 93228 187346 93228 187347 95932 187347 95929 187347 95530 187348 93831 187348 93827 187348 93827 187349 93831 187349 93832 187349 95618 187350 93562 187350 96080 187350 96080 187351 93562 187351 96079 187351 95591 187352 93844 187352 96067 187352 96067 187353 93844 187353 96060 187353 95568 187354 93851 187354 93563 187354 93563 187355 93851 187355 96053 187355 95546 187356 95549 187356 96043 187356 96043 187357 95549 187357 93857 187357 93863 187358 95319 187358 93861 187358 93861 187359 95319 187359 96037 187359 93564 187360 93874 187360 96029 187360 96029 187361 93874 187361 93875 187361 95509 187362 95508 187362 93879 187362 93879 187363 95508 187363 96027 187363 93888 187364 93565 187364 93887 187364 93887 187365 93565 187365 93893 187365 93897 187366 95474 187366 96008 187366 96008 187367 95474 187367 96006 187367 95451 187368 93566 187368 93905 187368 93905 187369 93566 187369 95997 187369 95438 187370 95437 187370 93910 187370 93910 187371 95437 187371 93567 187371 93817 187372 95421 187372 93816 187372 93816 187373 95421 187373 93568 187373 93825 187374 93821 187374 96094 187374 96094 187375 93821 187375 93822 187375 93212 187376 95293 187376 93569 187376 93569 187377 95293 187377 95294 187377 93569 187378 95294 187378 93570 187378 93570 187379 95294 187379 93571 187379 93570 187380 93571 187380 96030 187380 96030 187381 93571 187381 95292 187381 95316 187382 93572 187382 93573 187382 93573 187383 93572 187383 93574 187383 93573 187384 93574 187384 95320 187384 95320 187385 93574 187385 96041 187385 95320 187386 96041 187386 93575 187386 93575 187387 96041 187387 93576 187387 93577 187388 95311 187388 96039 187388 96039 187389 95311 187389 93578 187389 96039 187390 93578 187390 93579 187390 93579 187391 93578 187391 93580 187391 93579 187392 93580 187392 96040 187392 96040 187393 93580 187393 95310 187393 93581 187394 96086 187394 93582 187394 93582 187395 96086 187395 96081 187395 93582 187396 96081 187396 93583 187396 93583 187397 96081 187397 93584 187397 93583 187398 93584 187398 95533 187398 95533 187399 93584 187399 96082 187399 95533 187400 96082 187400 93585 187400 93585 187401 96082 187401 93194 187401 96151 187402 95349 187402 93586 187402 93586 187403 95349 187403 93587 187403 93586 187404 93587 187404 96154 187404 96154 187405 93587 187405 93588 187405 96154 187406 93588 187406 93589 187406 93589 187407 93588 187407 95356 187407 93589 187408 95356 187408 93224 187408 93224 187409 95356 187409 93590 187409 95366 187410 93591 187410 95364 187410 95364 187411 93591 187411 93592 187411 95364 187412 93592 187412 93593 187412 93593 187413 93592 187413 93594 187413 93593 187414 93594 187414 95362 187414 95362 187415 93594 187415 93595 187415 95362 187416 93595 187416 93225 187416 93225 187417 93595 187417 93226 187417 95360 187418 93223 187418 93596 187418 93596 187419 93223 187419 96153 187419 93596 187420 96153 187420 95357 187420 95357 187421 96153 187421 96152 187421 95357 187422 96152 187422 95368 187422 95368 187423 96152 187423 93597 187423 96155 187424 93222 187424 93598 187424 93598 187425 93222 187425 95351 187425 93598 187426 95351 187426 93599 187426 93599 187427 95351 187427 93600 187427 93599 187428 93600 187428 96156 187428 96156 187429 93600 187429 95353 187429 96150 187430 95331 187430 93602 187430 93602 187431 95331 187431 93601 187431 93602 187432 93601 187432 93603 187432 93603 187433 93601 187433 95333 187433 93603 187434 95333 187434 93604 187434 93604 187435 95333 187435 93605 187435 93604 187436 93605 187436 96147 187436 96147 187437 93605 187437 95334 187437 93606 187438 95336 187438 96144 187438 96144 187439 95336 187439 93607 187439 96144 187440 93607 187440 96148 187440 96148 187441 93607 187441 93608 187441 96148 187442 93608 187442 93609 187442 93609 187443 93608 187443 93610 187443 93611 187444 95346 187444 93612 187444 93612 187445 95346 187445 95337 187445 93612 187446 95337 187446 96145 187446 96145 187447 95337 187447 95339 187447 96145 187448 95339 187448 96146 187448 96146 187449 95339 187449 93613 187449 96146 187450 93613 187450 93433 187450 93433 187451 93613 187451 95342 187451 93614 187452 93434 187452 95328 187452 93614 187453 95328 187453 93615 187453 93615 187454 95328 187454 95329 187454 93615 187455 95329 187455 93616 187455 93616 187456 95329 187456 95330 187456 93616 187457 95330 187457 93617 187457 93617 187458 95330 187458 95327 187458 93617 187459 95327 187459 96149 187459 93439 187460 95369 187460 96136 187460 96136 187461 95369 187461 93618 187461 96136 187462 93618 187462 93619 187462 93619 187463 93618 187463 93620 187463 93619 187464 93620 187464 93621 187464 93621 187465 93620 187465 93622 187465 93621 187466 93622 187466 96140 187466 96140 187467 93622 187467 93623 187467 95386 187468 96139 187468 93624 187468 93624 187469 96139 187469 96138 187469 93624 187470 96138 187470 95382 187470 95382 187471 96138 187471 93625 187471 95382 187472 93625 187472 95378 187472 95378 187473 93625 187473 96137 187473 95375 187474 96141 187474 93626 187474 93626 187475 96141 187475 93627 187475 93626 187476 93627 187476 93628 187476 93628 187477 93627 187477 96143 187477 93628 187478 96143 187478 93629 187478 93629 187479 96143 187479 96142 187479 93629 187480 96142 187480 95379 187480 95379 187481 96142 187481 93435 187481 96134 187482 93221 187482 93630 187482 96134 187483 93630 187483 93632 187483 93632 187484 93630 187484 93631 187484 93632 187485 93631 187485 93634 187485 93634 187486 93631 187486 93633 187486 93634 187487 93633 187487 96135 187487 96135 187488 93633 187488 95371 187488 96135 187489 95371 187489 96133 187489 93219 187490 93635 187490 93636 187490 93636 187491 93635 187491 93637 187491 93636 187492 93637 187492 93638 187492 93638 187493 93637 187493 95983 187493 93638 187494 95983 187494 93639 187494 93639 187495 95983 187495 93640 187495 93639 187496 93640 187496 95422 187496 95422 187497 93640 187497 93436 187497 93220 187498 95410 187498 95412 187498 93220 187499 95412 187499 95985 187499 95985 187500 95412 187500 95414 187500 95985 187501 95414 187501 95984 187501 95984 187502 95414 187502 95415 187502 95984 187503 95415 187503 93641 187503 93641 187504 95415 187504 95407 187504 93641 187505 95407 187505 95988 187505 93642 187506 93216 187506 93643 187506 93643 187507 93216 187507 93644 187507 93643 187508 93644 187508 96132 187508 96132 187509 93644 187509 93645 187509 96132 187510 93645 187510 96128 187510 96128 187511 93645 187511 95389 187511 93437 187512 95388 187512 96126 187512 96126 187513 95388 187513 95392 187513 96126 187514 95392 187514 96127 187514 96127 187515 95392 187515 93646 187515 96127 187516 93646 187516 93647 187516 93647 187517 93646 187517 93648 187517 93647 187518 93648 187518 96125 187518 96125 187519 93648 187519 95398 187519 93438 187520 96131 187520 95405 187520 95405 187521 96131 187521 96129 187521 95405 187522 96129 187522 95403 187522 95403 187523 96129 187523 93649 187523 95403 187524 93649 187524 95402 187524 95402 187525 93649 187525 96130 187525 95402 187526 96130 187526 93217 187526 93217 187527 96130 187527 93218 187527 95396 187528 93650 187528 95400 187528 95400 187529 93650 187529 93651 187529 95400 187530 93651 187530 95399 187530 95399 187531 93651 187531 93652 187531 95399 187532 93652 187532 93653 187532 93653 187533 93652 187533 93654 187533 93215 187534 93655 187534 95439 187534 95439 187535 93655 187535 93656 187535 95439 187536 93656 187536 93657 187536 93657 187537 93656 187537 93658 187537 93657 187538 93658 187538 93659 187538 93659 187539 93658 187539 93660 187539 93659 187540 93660 187540 93169 187540 93169 187541 93660 187541 93168 187541 93661 187542 93662 187542 93663 187542 93663 187543 93662 187543 95429 187543 93663 187544 95429 187544 95993 187544 95993 187545 95429 187545 95431 187545 95993 187546 95431 187546 93170 187546 93170 187547 95431 187547 93171 187547 93664 187548 93214 187548 95453 187548 95453 187549 93214 187549 93665 187549 95453 187550 93665 187550 93666 187550 93666 187551 93665 187551 93668 187551 93666 187552 93668 187552 93667 187552 93667 187553 93668 187553 95998 187553 96001 187554 93670 187554 93669 187554 93669 187555 93670 187555 93671 187555 93669 187556 93671 187556 96000 187556 96000 187557 93671 187557 93672 187557 96000 187558 93672 187558 95999 187558 95999 187559 93672 187559 93176 187559 95467 187560 93673 187560 95471 187560 95471 187561 93673 187561 93674 187561 95471 187562 93674 187562 93676 187562 93676 187563 93674 187563 93675 187563 93676 187564 93675 187564 93677 187564 93677 187565 93675 187565 93679 187565 93677 187566 93679 187566 93678 187566 93678 187567 93679 187567 96004 187567 96003 187568 93213 187568 95464 187568 96003 187569 95464 187569 93680 187569 93680 187570 95464 187570 95465 187570 93680 187571 95465 187571 96002 187571 96002 187572 95465 187572 95461 187572 96002 187573 95461 187573 93681 187573 93681 187574 95461 187574 93178 187574 93681 187575 93178 187575 96007 187575 95496 187576 96012 187576 93682 187576 93682 187577 96012 187577 96011 187577 93682 187578 96011 187578 93683 187578 93683 187579 96011 187579 96010 187579 93683 187580 96010 187580 93180 187580 93180 187581 96010 187581 93179 187581 96013 187582 95493 187582 93684 187582 93684 187583 95493 187583 95484 187583 93684 187584 95484 187584 96015 187584 96015 187585 95484 187585 95485 187585 96015 187586 95485 187586 96009 187586 96009 187587 95485 187587 95487 187587 96009 187588 95487 187588 96014 187588 96014 187589 95487 187589 95483 187589 95513 187590 96021 187590 93685 187590 93685 187591 96021 187591 96023 187591 93685 187592 96023 187592 95511 187592 95511 187593 96023 187593 93686 187593 95511 187594 93686 187594 95510 187594 95510 187595 93686 187595 96022 187595 95510 187596 96022 187596 95519 187596 95519 187597 96022 187597 96019 187597 96024 187598 93687 187598 93689 187598 96024 187599 93689 187599 93688 187599 93688 187600 93689 187600 93690 187600 93688 187601 93690 187601 96025 187601 96025 187602 93690 187602 93691 187602 96025 187603 93691 187603 93692 187603 93692 187604 93691 187604 93182 187604 93692 187605 93182 187605 93693 187605 95299 187606 93211 187606 93694 187606 93694 187607 93211 187607 93695 187607 93694 187608 93695 187608 95301 187608 95301 187609 93695 187609 96031 187609 95301 187610 96031 187610 93696 187610 93696 187611 96031 187611 93697 187611 93696 187612 93697 187612 93186 187612 93186 187613 93697 187613 93185 187613 96085 187614 95531 187614 95523 187614 96085 187615 95523 187615 96084 187615 96084 187616 95523 187616 95525 187616 96084 187617 95525 187617 96083 187617 96083 187618 95525 187618 93698 187618 96083 187619 93698 187619 93699 187619 93699 187620 93698 187620 93193 187620 93699 187621 93193 187621 96089 187621 93700 187622 93701 187622 93702 187622 93702 187623 93701 187623 96052 187623 93702 187624 96052 187624 95551 187624 95551 187625 96052 187625 93703 187625 95551 187626 93703 187626 95556 187626 95556 187627 93703 187627 96049 187627 96051 187628 93705 187628 93704 187628 93704 187629 93705 187629 93706 187629 93704 187630 93706 187630 96050 187630 96050 187631 93706 187631 95541 187631 96050 187632 95541 187632 93707 187632 93707 187633 95541 187633 95542 187633 93208 187634 96056 187634 93708 187634 93708 187635 96056 187635 93709 187635 93708 187636 93709 187636 95570 187636 95570 187637 93709 187637 96057 187637 95570 187638 96057 187638 93710 187638 93710 187639 96057 187639 93711 187639 93710 187640 93711 187640 95578 187640 95578 187641 93711 187641 96055 187641 93210 187642 93209 187642 93712 187642 93210 187643 93712 187643 96059 187643 96059 187644 93712 187644 93713 187644 96059 187645 93713 187645 93714 187645 93714 187646 93713 187646 95561 187646 93714 187647 95561 187647 93715 187647 93715 187648 95561 187648 93716 187648 93715 187649 93716 187649 93189 187649 93717 187650 96064 187650 93718 187650 93718 187651 96064 187651 96063 187651 93718 187652 96063 187652 93719 187652 93719 187653 96063 187653 95594 187653 95594 187654 96063 187654 93720 187654 95594 187655 93720 187655 93721 187655 93721 187656 93720 187656 95596 187656 95596 187657 93720 187657 96065 187657 95596 187658 96065 187658 95605 187658 96066 187659 93207 187659 93722 187659 93722 187660 93207 187660 95581 187660 93722 187661 95581 187661 93723 187661 93723 187662 95581 187662 93724 187662 93723 187663 93724 187663 93192 187663 93192 187664 93724 187664 95583 187664 95623 187665 93725 187665 95621 187665 95621 187666 93725 187666 93726 187666 95621 187667 93726 187667 93727 187667 93727 187668 93726 187668 96071 187668 93727 187669 96071 187669 93728 187669 93728 187670 96071 187670 96073 187670 93728 187671 96073 187671 95629 187671 95629 187672 96073 187672 96070 187672 96075 187673 95611 187673 95612 187673 96075 187674 95612 187674 93729 187674 93729 187675 95612 187675 95614 187675 93729 187676 95614 187676 93730 187676 93730 187677 95614 187677 95610 187677 93730 187678 95610 187678 96074 187678 96074 187679 95610 187679 93731 187679 96074 187680 93731 187680 96072 187680 93205 187681 93206 187681 95636 187681 95636 187682 93206 187682 93733 187682 95636 187683 93733 187683 93732 187683 93732 187684 93733 187684 93734 187684 93732 187685 93734 187685 95642 187685 95642 187686 93734 187686 96092 187686 96091 187687 93736 187687 93735 187687 93735 187688 93736 187688 93737 187688 93735 187689 93737 187689 93738 187689 93738 187690 93737 187690 95634 187690 93738 187691 95634 187691 93739 187691 93739 187692 95634 187692 93740 187692 93739 187693 93740 187693 93741 187693 93741 187694 93740 187694 95631 187694 93442 187695 93443 187695 93742 187695 93742 187696 93443 187696 95675 187696 93742 187697 95675 187697 96121 187697 96121 187698 95675 187698 95676 187698 96121 187699 95676 187699 96122 187699 96122 187700 95676 187700 95677 187700 93743 187701 96117 187701 93744 187701 93744 187702 96117 187702 96124 187702 93744 187703 96124 187703 95684 187703 95684 187704 96124 187704 96123 187704 95684 187705 96123 187705 93745 187705 93745 187706 96123 187706 93747 187706 93745 187707 93747 187707 93746 187707 93746 187708 93747 187708 93748 187708 95679 187709 93749 187709 95683 187709 95683 187710 93749 187710 96116 187710 95683 187711 96116 187711 95682 187711 95682 187712 96116 187712 93750 187712 95682 187713 93750 187713 93751 187713 93751 187714 93750 187714 96118 187714 93204 187715 93752 187715 96119 187715 96119 187716 93752 187716 93753 187716 96119 187717 93753 187717 96120 187717 96120 187718 93753 187718 95670 187718 96120 187719 95670 187719 93754 187719 93754 187720 95670 187720 95671 187720 93754 187721 95671 187721 93441 187721 93441 187722 95671 187722 95673 187722 95649 187723 95651 187723 93201 187723 93201 187724 95651 187724 96115 187724 95651 187725 93755 187725 96115 187725 96115 187726 93755 187726 93759 187726 96115 187727 93759 187727 93756 187727 93440 187728 96110 187728 93757 187728 93757 187729 96110 187729 93756 187729 93757 187730 93756 187730 93758 187730 93758 187731 93756 187731 93759 187731 96111 187732 93761 187732 93760 187732 93760 187733 93761 187733 93762 187733 93760 187734 93762 187734 93763 187734 93763 187735 93762 187735 93764 187735 93763 187736 93764 187736 93202 187736 93202 187737 93764 187737 95652 187737 95664 187738 93765 187738 95662 187738 95662 187739 93765 187739 96113 187739 95662 187740 96113 187740 93766 187740 93766 187741 96113 187741 93767 187741 93766 187742 93767 187742 95660 187742 95660 187743 93767 187743 96112 187743 95660 187744 96112 187744 93768 187744 93768 187745 96112 187745 93203 187745 95654 187746 93200 187746 93769 187746 93769 187747 93200 187747 93770 187747 93769 187748 93770 187748 93771 187748 93771 187749 93770 187749 96114 187749 93771 187750 96114 187750 95665 187750 95665 187751 96114 187751 93772 187751 95706 187752 96109 187752 93773 187752 93773 187753 96109 187753 96105 187753 93773 187754 96105 187754 95704 187754 95704 187755 96105 187755 96104 187755 95704 187756 96104 187756 93774 187756 93774 187757 96104 187757 93775 187757 93774 187758 93775 187758 95702 187758 95702 187759 93775 187759 96108 187759 95701 187760 93776 187760 93777 187760 93777 187761 93776 187761 93778 187761 93777 187762 93778 187762 95700 187762 95700 187763 93778 187763 93779 187763 95700 187764 93779 187764 95710 187764 95710 187765 93779 187765 93780 187765 95693 187766 93781 187766 96107 187766 96107 187767 93781 187767 93782 187767 93781 187768 93783 187768 93782 187768 93782 187769 93783 187769 93784 187769 93782 187770 93784 187770 96106 187770 95690 187771 93785 187771 93786 187771 93786 187772 93785 187772 96106 187772 93786 187773 96106 187773 93787 187773 93787 187774 96106 187774 93784 187774 96097 187775 93197 187775 93788 187775 93788 187776 93197 187776 93789 187776 93788 187777 93789 187777 93790 187777 93790 187778 93789 187778 93792 187778 93790 187779 93792 187779 93791 187779 93791 187780 93792 187780 93793 187780 93791 187781 93793 187781 96098 187781 96098 187782 93793 187782 93794 187782 95726 187783 93796 187783 93795 187783 93795 187784 93796 187784 93797 187784 93795 187785 93797 187785 93799 187785 93799 187786 93797 187786 93798 187786 93799 187787 93798 187787 95723 187787 95723 187788 93798 187788 93800 187788 95723 187789 93800 187789 93199 187789 93199 187790 93800 187790 96100 187790 93196 187791 93198 187791 93801 187791 93801 187792 93198 187792 96096 187792 93801 187793 96096 187793 93802 187793 93802 187794 96096 187794 93804 187794 93802 187795 93804 187795 93803 187795 93803 187796 93804 187796 93805 187796 96102 187797 93444 187797 96101 187797 96101 187798 93444 187798 95695 187798 96101 187799 95695 187799 93806 187799 93806 187800 95695 187800 93807 187800 93806 187801 93807 187801 96103 187801 96103 187802 93807 187802 93808 187802 96099 187803 93810 187803 93809 187803 93809 187804 93810 187804 93811 187804 93809 187805 93811 187805 93812 187805 93812 187806 93811 187806 95716 187806 93812 187807 95716 187807 93813 187807 93813 187808 95716 187808 95717 187808 93814 187809 95416 187809 95986 187809 95986 187810 95416 187810 95418 187810 95986 187811 95418 187811 95987 187811 95987 187812 95418 187812 93815 187812 95987 187813 93815 187813 93816 187813 93816 187814 93815 187814 93817 187814 93167 187815 93166 187815 93818 187815 93818 187816 93166 187816 93819 187816 93818 187817 93819 187817 95638 187817 95638 187818 93819 187818 93820 187818 95638 187819 93820 187819 93821 187819 93821 187820 93820 187820 93822 187820 96093 187821 95630 187821 93823 187821 93823 187822 95630 187822 95635 187822 93823 187823 95635 187823 96095 187823 96095 187824 95635 187824 93824 187824 96095 187825 93824 187825 96094 187825 96094 187826 93824 187826 93825 187826 96088 187827 95521 187827 93826 187827 93826 187828 95521 187828 95526 187828 93826 187829 95526 187829 96087 187829 96087 187830 95526 187830 95528 187830 96087 187831 95528 187831 93827 187831 93827 187832 95528 187832 95530 187832 93195 187833 96090 187833 95537 187833 95537 187834 96090 187834 93828 187834 95537 187835 93828 187835 93829 187835 93829 187836 93828 187836 93830 187836 93829 187837 93830 187837 93831 187837 93831 187838 93830 187838 93832 187838 96076 187839 95607 187839 93833 187839 93833 187840 95607 187840 95616 187840 93833 187841 95616 187841 93834 187841 93834 187842 95616 187842 95617 187842 93834 187843 95617 187843 96080 187843 96080 187844 95617 187844 95618 187844 93835 187845 96078 187845 95625 187845 95625 187846 96078 187846 93836 187846 95625 187847 93836 187847 93837 187847 93837 187848 93836 187848 96077 187848 93837 187849 96077 187849 93562 187849 93562 187850 96077 187850 96079 187850 96068 187851 93838 187851 96069 187851 96069 187852 93838 187852 93839 187852 96069 187853 93839 187853 93840 187853 93840 187854 93839 187854 95587 187854 93840 187855 95587 187855 93841 187855 93841 187856 95587 187856 95588 187856 93841 187857 95588 187857 96067 187857 96067 187858 95588 187858 95591 187858 95602 187859 93842 187859 95599 187859 95599 187860 93842 187860 96062 187860 95599 187861 96062 187861 93843 187861 93843 187862 96062 187862 96061 187862 93843 187863 96061 187863 93844 187863 93844 187864 96061 187864 96060 187864 93190 187865 93191 187865 93845 187865 93845 187866 93191 187866 95563 187866 93845 187867 95563 187867 96058 187867 96058 187868 95563 187868 93846 187868 96058 187869 93846 187869 93563 187869 93563 187870 93846 187870 95568 187870 95574 187871 93848 187871 93847 187871 93847 187872 93848 187872 93849 187872 93847 187873 93849 187873 93850 187873 93850 187874 93849 187874 96054 187874 93850 187875 96054 187875 93851 187875 93851 187876 96054 187876 96053 187876 96048 187877 93852 187877 96047 187877 96047 187878 93852 187878 93854 187878 96047 187879 93854 187879 93853 187879 93853 187880 93854 187880 95544 187880 93853 187881 95544 187881 96042 187881 96042 187882 95544 187882 93855 187882 96042 187883 93855 187883 96043 187883 96043 187884 93855 187884 95546 187884 95557 187885 96046 187885 95554 187885 95554 187886 96046 187886 96045 187886 95554 187887 96045 187887 93856 187887 93856 187888 96045 187888 96044 187888 93856 187889 96044 187889 95549 187889 95549 187890 96044 187890 93857 187890 93858 187891 95308 187891 93859 187891 93859 187892 95308 187892 93860 187892 93859 187893 93860 187893 96035 187893 96035 187894 93860 187894 95314 187894 96035 187895 95314 187895 96038 187895 96038 187896 95314 187896 93862 187896 96038 187897 93862 187897 93861 187897 93861 187898 93862 187898 93863 187898 93188 187899 93864 187899 93865 187899 93865 187900 93864 187900 93867 187900 93865 187901 93867 187901 93866 187901 93866 187902 93867 187902 96036 187902 93866 187903 96036 187903 95319 187903 95319 187904 96036 187904 96037 187904 96032 187905 93187 187905 93868 187905 93868 187906 93187 187906 95297 187906 93868 187907 95297 187907 96034 187907 96034 187908 95297 187908 93869 187908 96034 187909 93869 187909 93870 187909 93870 187910 93869 187910 93871 187910 93870 187911 93871 187911 96029 187911 96029 187912 93871 187912 93564 187912 93184 187913 96033 187913 93872 187913 93872 187914 96033 187914 96028 187914 93872 187915 96028 187915 95302 187915 95302 187916 96028 187916 93873 187916 95302 187917 93873 187917 93874 187917 93874 187918 93873 187918 93875 187918 93876 187919 93183 187919 93877 187919 93877 187920 93183 187920 93878 187920 93877 187921 93878 187921 96026 187921 96026 187922 93878 187922 95506 187922 96026 187923 95506 187923 93879 187923 93879 187924 95506 187924 95509 187924 93880 187925 93181 187925 95517 187925 95517 187926 93181 187926 93881 187926 95517 187927 93881 187927 95515 187927 95515 187928 93881 187928 96020 187928 95515 187929 96020 187929 95508 187929 95508 187930 96020 187930 96027 187930 96016 187931 93882 187931 96017 187931 96017 187932 93882 187932 93883 187932 96017 187933 93883 187933 93884 187933 93884 187934 93883 187934 93885 187934 93884 187935 93885 187935 93886 187935 93886 187936 93885 187936 95490 187936 93886 187937 95490 187937 93887 187937 93887 187938 95490 187938 93888 187938 95498 187939 96018 187939 93889 187939 93889 187940 96018 187940 93891 187940 93889 187941 93891 187941 93890 187941 93890 187942 93891 187942 93892 187942 93890 187943 93892 187943 93565 187943 93565 187944 93892 187944 93893 187944 93177 187945 95458 187945 93895 187945 93895 187946 95458 187946 93894 187946 93895 187947 93894 187947 96005 187947 96005 187948 93894 187948 93896 187948 96005 187949 93896 187949 96008 187949 96008 187950 93896 187950 93897 187950 95479 187951 93898 187951 95478 187951 95478 187952 93898 187952 93899 187952 95478 187953 93899 187953 95475 187953 95475 187954 93899 187954 93900 187954 95475 187955 93900 187955 95474 187955 95474 187956 93900 187956 96006 187956 93175 187957 95447 187957 93901 187957 93901 187958 95447 187958 93902 187958 93901 187959 93902 187959 95994 187959 95994 187960 93902 187960 93903 187960 95994 187961 93903 187961 95995 187961 95995 187962 93903 187962 93904 187962 95995 187963 93904 187963 93905 187963 93905 187964 93904 187964 95451 187964 93174 187965 93173 187965 95456 187965 95456 187966 93173 187966 95996 187966 95456 187967 95996 187967 93906 187967 93906 187968 95996 187968 93907 187968 93906 187969 93907 187969 93566 187969 93566 187970 93907 187970 95997 187970 93172 187971 95427 187971 93908 187971 93908 187972 95427 187972 95432 187972 93908 187973 95432 187973 93909 187973 93909 187974 95432 187974 95433 187974 93909 187975 95433 187975 95992 187975 95992 187976 95433 187976 95435 187976 95992 187977 95435 187977 93910 187977 93910 187978 95435 187978 95438 187978 95445 187979 95990 187979 93911 187979 93911 187980 95990 187980 95991 187980 93911 187981 95991 187981 95443 187981 95443 187982 95991 187982 93912 187982 95443 187983 93912 187983 95437 187983 95437 187984 93912 187984 93567 187984 93568 187985 95421 187985 93913 187985 93913 187986 95421 187986 93914 187986 93913 187987 93914 187987 93915 187987 93915 187988 93914 187988 93916 187988 93915 187989 93916 187989 95989 187989 95989 187990 93916 187990 95426 187990 94740 187991 94739 187991 93917 187991 95309 187992 94191 187992 94328 187992 95424 187993 95423 187993 93918 187993 94250 187994 94249 187994 94244 187994 94230 187995 93919 187995 94220 187995 94343 187996 94352 187996 93920 187996 95522 187997 95555 187997 95558 187997 95559 187998 94157 187998 94167 187998 95608 187999 94133 187999 94142 187999 94074 188000 94308 188000 93921 188000 94001 188001 95013 188001 94000 188001 95076 188002 93974 188002 93922 188002 93923 188003 93932 188003 95229 188003 95229 188004 93932 188004 94291 188004 95229 188005 94291 188005 95230 188005 93924 188006 93925 188006 94292 188006 93925 188007 93924 188007 93928 188007 93928 188008 93924 188008 93926 188008 93928 188009 93926 188009 95404 188009 95393 188010 95222 188010 95394 188010 95394 188011 95222 188011 93930 188011 95404 188012 93927 188012 93928 188012 93928 188013 93927 188013 93929 188013 93928 188014 93929 188014 95222 188014 95222 188015 93929 188015 95395 188015 95222 188016 95395 188016 93930 188016 95227 188017 94024 188017 93923 188017 93923 188018 94024 188018 93931 188018 93923 188019 93931 188019 93932 188019 96963 188020 93933 188020 96964 188020 96964 188021 93933 188021 94268 188021 96964 188022 94268 188022 96965 188022 95227 188023 95226 188023 94024 188023 94024 188024 95226 188024 95225 188024 94024 188025 95225 188025 96967 188025 96967 188026 95225 188026 93934 188026 96967 188027 93934 188027 96966 188027 96966 188028 93934 188028 95223 188028 96966 188029 95223 188029 93935 188029 93935 188030 95223 188030 94271 188030 93944 188031 94460 188031 93936 188031 93936 188032 94460 188032 95347 188032 93941 188033 93937 188033 93939 188033 94314 188034 95232 188034 93938 188034 93938 188035 95232 188035 93939 188035 93938 188036 93939 188036 95332 188036 95332 188037 93939 188037 93937 188037 93936 188038 93940 188038 93944 188038 93944 188039 93940 188039 95344 188039 93944 188040 95344 188040 95242 188040 93941 188041 93939 188041 93942 188041 93942 188042 93939 188042 95246 188042 93942 188043 95246 188043 95343 188043 95343 188044 95246 188044 93943 188044 95343 188045 93943 188045 95344 188045 95344 188046 93943 188046 95243 188046 95344 188047 95243 188047 95242 188047 95242 188048 95240 188048 93944 188048 93944 188049 95240 188049 95238 188049 93944 188050 95238 188050 93945 188050 93945 188051 95238 188051 93946 188051 93946 188052 95237 188052 93945 188052 93945 188053 95237 188053 95235 188053 93945 188054 95235 188054 95897 188054 95897 188055 95235 188055 95234 188055 95897 188056 95234 188056 93947 188056 93947 188057 95234 188057 93948 188057 93947 188058 93948 188058 95361 188058 95361 188059 93948 188059 95232 188059 95361 188060 95232 188060 95363 188060 95363 188061 95232 188061 94316 188061 95154 188062 95153 188062 94481 188062 95154 188063 94481 188063 95155 188063 95148 188064 94286 188064 95151 188064 95151 188065 94286 188065 94483 188065 95151 188066 94483 188066 93949 188066 93949 188067 94483 188067 94482 188067 95860 188068 94046 188068 95158 188068 95158 188069 94046 188069 95146 188069 94481 188070 93950 188070 95155 188070 95155 188071 93950 188071 93951 188071 95155 188072 93951 188072 93952 188072 93952 188073 93951 188073 95860 188073 93952 188074 95860 188074 95156 188074 95156 188075 95860 188075 95158 188075 94425 188076 93953 188076 94307 188076 94307 188077 93953 188077 95161 188077 95166 188078 95861 188078 93954 188078 93954 188079 95861 188079 93955 188079 95166 188080 95164 188080 95861 188080 95861 188081 95164 188081 93956 188081 95861 188082 93956 188082 94425 188082 94425 188083 93956 188083 95163 188083 94425 188084 95163 188084 93953 188084 95161 188085 93957 188085 94307 188085 94307 188086 93957 188086 93958 188086 94307 188087 93958 188087 94304 188087 94304 188088 93958 188088 93959 188088 94304 188089 93959 188089 95864 188089 95864 188090 93959 188090 95169 188090 95864 188091 95169 188091 93955 188091 93955 188092 95169 188092 95168 188092 93955 188093 95168 188093 93954 188093 95070 188094 93969 188094 93960 188094 93961 188095 93963 188095 93965 188095 95076 188096 93922 188096 93962 188096 93962 188097 93922 188097 94009 188097 93962 188098 94009 188098 93968 188098 96958 188099 95640 188099 93966 188099 93966 188100 95640 188100 95639 188100 93963 188101 93964 188101 93965 188101 93965 188102 93964 188102 93966 188102 93965 188103 93966 188103 93967 188103 93967 188104 93966 188104 95639 188104 93968 188105 94009 188105 95078 188105 95078 188106 94009 188106 94011 188106 95078 188107 94011 188107 95079 188107 95079 188108 94011 188108 93969 188108 93969 188109 94011 188109 93970 188109 93969 188110 93970 188110 93960 188110 93960 188111 93961 188111 95070 188111 95070 188112 93961 188112 93965 188112 95070 188113 93965 188113 93976 188113 93965 188114 93971 188114 93976 188114 93976 188115 93971 188115 94126 188115 93976 188116 94126 188116 94123 188116 94115 188117 93972 188117 93977 188117 93977 188118 93972 188118 93973 188118 93974 188119 95076 188119 94116 188119 94116 188120 95076 188120 95073 188120 94116 188121 95073 188121 93975 188121 95661 188122 95659 188122 93976 188122 93976 188123 95659 188123 95656 188123 93976 188124 95656 188124 93973 188124 93973 188125 95656 188125 95653 188125 93973 188126 95653 188126 93977 188126 93982 188127 95938 188127 95937 188127 93982 188128 95937 188128 95081 188128 95081 188129 95937 188129 93979 188129 95081 188130 93979 188130 95082 188130 95697 188131 95696 188131 95084 188131 95084 188132 95696 188132 93978 188132 95084 188133 93978 188133 94085 188133 95082 188134 93979 188134 95084 188134 95084 188135 93979 188135 95698 188135 95084 188136 95698 188136 95697 188136 95085 188137 94086 188137 93980 188137 93980 188138 95724 188138 95085 188138 95085 188139 95724 188139 95722 188139 95085 188140 95722 188140 95087 188140 95087 188141 95722 188141 93981 188141 95087 188142 93981 188142 94487 188142 94487 188143 93981 188143 95719 188143 94487 188144 95719 188144 94486 188144 93982 188145 93983 188145 95938 188145 95938 188146 93983 188146 93986 188146 95938 188147 93986 188147 95940 188147 95088 188148 94374 188148 95090 188148 95090 188149 94374 188149 93984 188149 95090 188150 93984 188150 93985 188150 93985 188151 93984 188151 95940 188151 93985 188152 95940 188152 95092 188152 95092 188153 95940 188153 93986 188153 93987 188154 93991 188154 93989 188154 95004 188155 94034 188155 93988 188155 93988 188156 94034 188156 93989 188156 93988 188157 93989 188157 93990 188157 93990 188158 93989 188158 93991 188158 93992 188159 94999 188159 93996 188159 93989 188160 95903 188160 93987 188160 93987 188161 95903 188161 95902 188161 93987 188162 95902 188162 93993 188162 93993 188163 95902 188163 95901 188163 93993 188164 95901 188164 93994 188164 93994 188165 95901 188165 93995 188165 93992 188166 93996 188166 94114 188166 94000 188167 95013 188167 95905 188167 95905 188168 95013 188168 93997 188168 95905 188169 93997 188169 94091 188169 93917 188170 95017 188170 93998 188170 93998 188171 95017 188171 93999 188171 93998 188172 93999 188172 94000 188172 94000 188173 93999 188173 95015 188173 94000 188174 95015 188174 94001 188174 95011 188175 95010 188175 94092 188175 94092 188176 95010 188176 94002 188176 94092 188177 94002 188177 94003 188177 94003 188178 94002 188178 95009 188178 94003 188179 95009 188179 95008 188179 95936 188180 94005 188180 94004 188180 95936 188181 94004 188181 94008 188181 95936 188182 94006 188182 94005 188182 94005 188183 94006 188183 94007 188183 94005 188184 94007 188184 94660 188184 94660 188185 94007 188185 95931 188185 94660 188186 95931 188186 94017 188186 94004 188187 94657 188187 94008 188187 94008 188188 94657 188188 94656 188188 94008 188189 94656 188189 94009 188189 94009 188190 94656 188190 94010 188190 94009 188191 94010 188191 94011 188191 94011 188192 94010 188192 94012 188192 94011 188193 94012 188193 94013 188193 94013 188194 94012 188194 94014 188194 94013 188195 94014 188195 96974 188195 96974 188196 94014 188196 94015 188196 96974 188197 94015 188197 96969 188197 96969 188198 94015 188198 94663 188198 96969 188199 94663 188199 94475 188199 94475 188200 94663 188200 94016 188200 94475 188201 94016 188201 94017 188201 94647 188202 94020 188202 94469 188202 95908 188203 95895 188203 94018 188203 94634 188204 95907 188204 94018 188204 94018 188205 95907 188205 94019 188205 94018 188206 94019 188206 95908 188206 94469 188207 94020 188207 94021 188207 94021 188208 94020 188208 94645 188208 94021 188209 94645 188209 94022 188209 94022 188210 94645 188210 94643 188210 94022 188211 94643 188211 96968 188211 94643 188212 94642 188212 96968 188212 96968 188213 94642 188213 94641 188213 96968 188214 94641 188214 96967 188214 96967 188215 94641 188215 94023 188215 96967 188216 94023 188216 94024 188216 94024 188217 94023 188217 94025 188217 94024 188218 94025 188218 94026 188218 94026 188219 94025 188219 94638 188219 94026 188220 94638 188220 95895 188220 95895 188221 94638 188221 94636 188221 95895 188222 94636 188222 94018 188222 94027 188223 94616 188223 94153 188223 94153 188224 94616 188224 94031 188224 94153 188225 94031 188225 94033 188225 95894 188226 95900 188226 94028 188226 95894 188227 94028 188227 94029 188227 94029 188228 94028 188228 95893 188228 95893 188229 94028 188229 94030 188229 95893 188230 94030 188230 94618 188230 94031 188231 94032 188231 94033 188231 94033 188232 94032 188232 94612 188232 94033 188233 94612 188233 94034 188233 94034 188234 94612 188234 94035 188234 94034 188235 94035 188235 93989 188235 93989 188236 94035 188236 94037 188236 93989 188237 94037 188237 94036 188237 94036 188238 94037 188238 94038 188238 94036 188239 94038 188239 95900 188239 95900 188240 94038 188240 94039 188240 95900 188241 94039 188241 94028 188241 94049 188242 94040 188242 94226 188242 94226 188243 94040 188243 94041 188243 94226 188244 94041 188244 94042 188244 94416 188245 94043 188245 95866 188245 95866 188246 94043 188246 94591 188246 95866 188247 94591 188247 95856 188247 95856 188248 94591 188248 95857 188248 95857 188249 94591 188249 94589 188249 95857 188250 94589 188250 95859 188250 94589 188251 94588 188251 95859 188251 95859 188252 94588 188252 94044 188252 95859 188253 94044 188253 95860 188253 95860 188254 94044 188254 94045 188254 95860 188255 94045 188255 94046 188255 94046 188256 94045 188256 94047 188256 94046 188257 94047 188257 94266 188257 94266 188258 94047 188258 94585 188258 94266 188259 94585 188259 94049 188259 94049 188260 94585 188260 94048 188260 94049 188261 94048 188261 94040 188261 94091 188262 94056 188262 94050 188262 94050 188263 94051 188263 94091 188263 94091 188264 94051 188264 94997 188264 94091 188265 94997 188265 95905 188265 95905 188266 94997 188266 94996 188266 95905 188267 94996 188267 95906 188267 94996 188268 94995 188268 95906 188268 95906 188269 94995 188269 94053 188269 95906 188270 94053 188270 94052 188270 94052 188271 94053 188271 94054 188271 94052 188272 94054 188272 94992 188272 94484 188273 94055 188273 94485 188273 94485 188274 94055 188274 94990 188274 94485 188275 94990 188275 94056 188275 94056 188276 94990 188276 94057 188276 94056 188277 94057 188277 94050 188277 95937 188278 94058 188278 93979 188278 93979 188279 94058 188279 95058 188279 93979 188280 95058 188280 95703 188280 95703 188281 95058 188281 95057 188281 95703 188282 95057 188282 94096 188282 94110 188283 94060 188283 94117 188283 95057 188284 94061 188284 94059 188284 94117 188285 94060 188285 95939 188285 95057 188286 94059 188286 94095 188286 94060 188287 95065 188287 95939 188287 95939 188288 95065 188288 95064 188288 95939 188289 95064 188289 95937 188289 95937 188290 95064 188290 95061 188290 95937 188291 95061 188291 94058 188291 94061 188292 95057 188292 95678 188292 95678 188293 95057 188293 95055 188293 95678 188294 95055 188294 95054 188294 94108 188295 95067 188295 94109 188295 95067 188296 94108 188296 95068 188296 95068 188297 94108 188297 95686 188297 95068 188298 95686 188298 95685 188298 95685 188299 94062 188299 95068 188299 95068 188300 94062 188300 94063 188300 95068 188301 94063 188301 95054 188301 95054 188302 94063 188302 95680 188302 95054 188303 95680 188303 95678 188303 95136 188304 94064 188304 94299 188304 94299 188305 94064 188305 95135 188305 94065 188306 95145 188306 95862 188306 95862 188307 95145 188307 94066 188307 95862 188308 94066 188308 94067 188308 94066 188309 95144 188309 94067 188309 94067 188310 95144 188310 95142 188310 94067 188311 95142 188311 95864 188311 95142 188312 95141 188312 95864 188312 95864 188313 95141 188313 95139 188313 95864 188314 95139 188314 94304 188314 94304 188315 95139 188315 95138 188315 94304 188316 95138 188316 94068 188316 94068 188317 95138 188317 95137 188317 94068 188318 95137 188318 95136 188318 94073 188319 95218 188319 95217 188319 94069 188320 94070 188320 94294 188320 94294 188321 94070 188321 94071 188321 94294 188322 94071 188322 94072 188322 94073 188323 95217 188323 95898 188323 95898 188324 95217 188324 95215 188324 95898 188325 95215 188325 95214 188325 94074 188326 93921 188326 94075 188326 94075 188327 93921 188327 94076 188327 94075 188328 94076 188328 94071 188328 94071 188329 94076 188329 95374 188329 94071 188330 95374 188330 94072 188330 95218 188331 94073 188331 95219 188331 95219 188332 94073 188332 95897 188332 95219 188333 95897 188333 95221 188333 95221 188334 95897 188334 93947 188334 95221 188335 93947 188335 94078 188335 94077 188336 95355 188336 94308 188336 94078 188337 93947 188337 94308 188337 94308 188338 93947 188338 94079 188338 94308 188339 94079 188339 94077 188339 95721 188340 95720 188340 94092 188340 94092 188341 95720 188341 94089 188341 94092 188342 94089 188342 94088 188342 94084 188343 94080 188343 94003 188343 94003 188344 94080 188344 95712 188344 94003 188345 95712 188345 94092 188345 94092 188346 95712 188346 95718 188346 94092 188347 95718 188347 95721 188347 95714 188348 95711 188348 94081 188348 94081 188349 95711 188349 94082 188349 94081 188350 94082 188350 94488 188350 94488 188351 94082 188351 94083 188351 94488 188352 94083 188352 94003 188352 94003 188353 94083 188353 95713 188353 94003 188354 95713 188354 94084 188354 95085 188355 95084 188355 94086 188355 94086 188356 95084 188356 94085 188356 94086 188357 94085 188357 94087 188357 94087 188358 94085 188358 94088 188358 94087 188359 94088 188359 95725 188359 95725 188360 94088 188360 94089 188360 95692 188361 94090 188361 94092 188361 94092 188362 94090 188362 94091 188362 94092 188363 94091 188363 95011 188363 95011 188364 94091 188364 93997 188364 93978 188365 94093 188365 94085 188365 94085 188366 94093 188366 95688 188366 94085 188367 95688 188367 94088 188367 94088 188368 95688 188368 95689 188368 94088 188369 95689 188369 94092 188369 94092 188370 95689 188370 95691 188370 94092 188371 95691 188371 95692 188371 94094 188372 95709 188372 94095 188372 94095 188373 95709 188373 95707 188373 94095 188374 95707 188374 95057 188374 95057 188375 95707 188375 95705 188375 95057 188376 95705 188376 94096 188376 94090 188377 95694 188377 94091 188377 94091 188378 95694 188378 94097 188378 94091 188379 94097 188379 94056 188379 94056 188380 94097 188380 94098 188380 94098 188381 94099 188381 94056 188381 94056 188382 94099 188382 95699 188382 94056 188383 95699 188383 94094 188383 94094 188384 95699 188384 95708 188384 94094 188385 95708 188385 95709 188385 94100 188386 94101 188386 94485 188386 94485 188387 94101 188387 95681 188387 94485 188388 95681 188388 94105 188388 94104 188389 94102 188389 94056 188389 94056 188390 94102 188390 95669 188390 94056 188391 95669 188391 94485 188391 94485 188392 95669 188392 94103 188392 94485 188393 94103 188393 94100 188393 94059 188394 95667 188394 94095 188394 94095 188395 95667 188395 95668 188395 94095 188396 95668 188396 94094 188396 94094 188397 95668 188397 95674 188397 94094 188398 95674 188398 94056 188398 94056 188399 95674 188399 95672 188399 94056 188400 95672 188400 94104 188400 95681 188401 95687 188401 94105 188401 94105 188402 95687 188402 94107 188402 94105 188403 94107 188403 94106 188403 94106 188404 94107 188404 94108 188404 94106 188405 94108 188405 94117 188405 94117 188406 94108 188406 94109 188406 94117 188407 94109 188407 94110 188407 95655 188408 95658 188408 94111 188408 95655 188409 94111 188409 95650 188409 95658 188410 94112 188410 94111 188410 94111 188411 94112 188411 95657 188411 94111 188412 95657 188412 94121 188412 94113 188413 95650 188413 93996 188413 93996 188414 95650 188414 94111 188414 93996 188415 94111 188415 94114 188415 94114 188416 94111 188416 94130 188416 94114 188417 94130 188417 94125 188417 93975 188418 94115 188418 94116 188418 94116 188419 94115 188419 93977 188419 94116 188420 93977 188420 94117 188420 94117 188421 93977 188421 94118 188421 94118 188422 95645 188422 94117 188422 94117 188423 95645 188423 95646 188423 94117 188424 95646 188424 94106 188424 94106 188425 95646 188425 95647 188425 94106 188426 95647 188426 94105 188426 94105 188427 95647 188427 95648 188427 94105 188428 95648 188428 94485 188428 94485 188429 95648 188429 94119 188429 94485 188430 94119 188430 93996 188430 93996 188431 94119 188431 94120 188431 93996 188432 94120 188432 94113 188432 95657 188433 95666 188433 94121 188433 94121 188434 95666 188434 94122 188434 94121 188435 94122 188435 94123 188435 94123 188436 94122 188436 94124 188436 94123 188437 94124 188437 93976 188437 93976 188438 94124 188438 95663 188438 93976 188439 95663 188439 95661 188439 94132 188440 95633 188440 94130 188440 94130 188441 95633 188441 94034 188441 94130 188442 94034 188442 94125 188442 94125 188443 94034 188443 95004 188443 94126 188444 94127 188444 94123 188444 94123 188445 94127 188445 94128 188445 94123 188446 94128 188446 94121 188446 94121 188447 94128 188447 95632 188447 94121 188448 95632 188448 94111 188448 94111 188449 95632 188449 94129 188449 94111 188450 94129 188450 94130 188450 94130 188451 94129 188451 94131 188451 94130 188452 94131 188452 94132 188452 94137 188453 95643 188453 94133 188453 94133 188454 95643 188454 94134 188454 94133 188455 94134 188455 94142 188455 94142 188456 94134 188456 95644 188456 94142 188457 95644 188457 96958 188457 96958 188458 95644 188458 95641 188458 96958 188459 95641 188459 95640 188459 95633 188460 94135 188460 94034 188460 94034 188461 94135 188461 95637 188461 94034 188462 95637 188462 94033 188462 94033 188463 95637 188463 94136 188463 95609 188464 94139 188464 94033 188464 94136 188465 94137 188465 94033 188465 94033 188466 94137 188466 94133 188466 94033 188467 94133 188467 95609 188467 95609 188468 94133 188468 95608 188468 94153 188469 95622 188469 94138 188469 94139 188470 95613 188470 94033 188470 94033 188471 95613 188471 95620 188471 94033 188472 95620 188472 94153 188472 94153 188473 95620 188473 95624 188473 94153 188474 95624 188474 95622 188474 94138 188475 94140 188475 94153 188475 94153 188476 94140 188476 94148 188476 94153 188477 94148 188477 94151 188477 94147 188478 94141 188478 96958 188478 96958 188479 94141 188479 95615 188479 96958 188480 95615 188480 94142 188480 94142 188481 95615 188481 94143 188481 94142 188482 94143 188482 95608 188482 94144 188483 94150 188483 94146 188483 94146 188484 94150 188484 94145 188484 94146 188485 94145 188485 96958 188485 96958 188486 94145 188486 95619 188486 96958 188487 95619 188487 94147 188487 94148 188488 95628 188488 94151 188488 94151 188489 95628 188489 95627 188489 94151 188490 95627 188490 94155 188490 94155 188491 95627 188491 95626 188491 94155 188492 95626 188492 94144 188492 94144 188493 95626 188493 94149 188493 94144 188494 94149 188494 94150 188494 94154 188495 94159 188495 94153 188495 94153 188496 94159 188496 94160 188496 94153 188497 94160 188497 94027 188497 94027 188498 94160 188498 94618 188498 94155 188499 94152 188499 94151 188499 94151 188500 94152 188500 95580 188500 94151 188501 95580 188501 94153 188501 94153 188502 95580 188502 95582 188502 94153 188503 95582 188503 94154 188503 95589 188504 95586 188504 94144 188504 95586 188505 95585 188505 94144 188505 94144 188506 95585 188506 95584 188506 94144 188507 95584 188507 94155 188507 94155 188508 95584 188508 95579 188508 94155 188509 95579 188509 94152 188509 94158 188510 95597 188510 94144 188510 94144 188511 95597 188511 94156 188511 94144 188512 94156 188512 95589 188512 95606 188513 95604 188513 94157 188513 94157 188514 95604 188514 95603 188514 94157 188515 95603 188515 94167 188515 94167 188516 95603 188516 95601 188516 94167 188517 95601 188517 94166 188517 94166 188518 95601 188518 95600 188518 94166 188519 95600 188519 94158 188519 94158 188520 95600 188520 95598 188520 94158 188521 95598 188521 95597 188521 94159 188522 95590 188522 94160 188522 94160 188523 95590 188523 95592 188523 94160 188524 95592 188524 94408 188524 94408 188525 95592 188525 95593 188525 94408 188526 95593 188526 95595 188526 95560 188527 94164 188527 94408 188527 95595 188528 95606 188528 94408 188528 94408 188529 95606 188529 94157 188529 94408 188530 94157 188530 95560 188530 95560 188531 94157 188531 95559 188531 95571 188532 94161 188532 94163 188532 94161 188533 95569 188533 94163 188533 94163 188534 95569 188534 94162 188534 94163 188535 94162 188535 94171 188535 94164 188536 95562 188536 94408 188536 94408 188537 95562 188537 94165 188537 94408 188538 94165 188538 94163 188538 94163 188539 94165 188539 95567 188539 94163 188540 95567 188540 95571 188540 95566 188541 95565 188541 94166 188541 95566 188542 94166 188542 95572 188542 95572 188543 94166 188543 94183 188543 95572 188544 94183 188544 95573 188544 95565 188545 95564 188545 94166 188545 94166 188546 95564 188546 94168 188546 94166 188547 94168 188547 94167 188547 94167 188548 94168 188548 94169 188548 94167 188549 94169 188549 95559 188549 94162 188550 95577 188550 94171 188550 94171 188551 95577 188551 94170 188551 94171 188552 94170 188552 94185 188552 94185 188553 94170 188553 95576 188553 94185 188554 95576 188554 94183 188554 94183 188555 95576 188555 95575 188555 94183 188556 95575 188556 95573 188556 94185 188557 94172 188557 94171 188557 94171 188558 94172 188558 94173 188558 94171 188559 94173 188559 94163 188559 94163 188560 94173 188560 95540 188560 94163 188561 95540 188561 94175 188561 95553 188562 94323 188562 94174 188562 94174 188563 94323 188563 94163 188563 94174 188564 94163 188564 95547 188564 95547 188565 94163 188565 94175 188565 95555 188566 95522 188566 95550 188566 95550 188567 95522 188567 94176 188567 95550 188568 94176 188568 95552 188568 95552 188569 94176 188569 94177 188569 95552 188570 94177 188570 95553 188570 94323 188571 95534 188571 94320 188571 95553 188572 94177 188572 94323 188572 94323 188573 94177 188573 95524 188573 94323 188574 95524 188574 95532 188574 95532 188575 94178 188575 94323 188575 94323 188576 94178 188576 95535 188576 94323 188577 95535 188577 95534 188577 95529 188578 94183 188578 94179 188578 94179 188579 94183 188579 94330 188579 94179 188580 94330 188580 94180 188580 94180 188581 94330 188581 95536 188581 95548 188582 94181 188582 94183 188582 94183 188583 94181 188583 94182 188583 94183 188584 94182 188584 95545 188584 95545 188585 94184 188585 94183 188585 94183 188586 94184 188586 95543 188586 94183 188587 95543 188587 94185 188587 94185 188588 95543 188588 94186 188588 94185 188589 94186 188589 94172 188589 95548 188590 94183 188590 94187 188590 94187 188591 94183 188591 95529 188591 94187 188592 95529 188592 94188 188592 94188 188593 95529 188593 95527 188593 94188 188594 95527 188594 94189 188594 94189 188595 95527 188595 95520 188595 94189 188596 95520 188596 95558 188596 95558 188597 95520 188597 94190 188597 95558 188598 94190 188598 95522 188598 95539 188599 94192 188599 94191 188599 94191 188600 94192 188600 94193 188600 94191 188601 94193 188601 94328 188601 94328 188602 94193 188602 94194 188602 94328 188603 94194 188603 94330 188603 94330 188604 94194 188604 95538 188604 94330 188605 95538 188605 95536 188605 95503 188606 95504 188606 94346 188606 94210 188607 95514 188607 95512 188607 95504 188608 95505 188608 94346 188608 94346 188609 95505 188609 94195 188609 94346 188610 94195 188610 94210 188610 94210 188611 94195 188611 95507 188611 94210 188612 95507 188612 95514 188612 95512 188613 94196 188613 94210 188613 94210 188614 94196 188614 94197 188614 94210 188615 94197 188615 94203 188615 94200 188616 94198 188616 94201 188616 94198 188617 94199 188617 94201 188617 94201 188618 94199 188618 95501 188618 94201 188619 95501 188619 93920 188619 93920 188620 95501 188620 95502 188620 93920 188621 95502 188621 94343 188621 94200 188622 94201 188622 94202 188622 94202 188623 94201 188623 94206 188623 94202 188624 94206 188624 95516 188624 94197 188625 94204 188625 94203 188625 94203 188626 94204 188626 94205 188626 94203 188627 94205 188627 94215 188627 94215 188628 94205 188628 95518 188628 94215 188629 95518 188629 94206 188629 94206 188630 95518 188630 94207 188630 94206 188631 94207 188631 95516 188631 94415 188632 94212 188632 95495 188632 94215 188633 94216 188633 94203 188633 94203 188634 94216 188634 94208 188634 94203 188635 94208 188635 94210 188635 94210 188636 94208 188636 94209 188636 94210 188637 94209 188637 95488 188637 95488 188638 95486 188638 94210 188638 94210 188639 95486 188639 94211 188639 94210 188640 94211 188640 94415 188640 94415 188641 94211 188641 95494 188641 94415 188642 95494 188642 94212 188642 94228 188643 94221 188643 94217 188643 94206 188644 95491 188644 94213 188644 94213 188645 95489 188645 94206 188645 94206 188646 95489 188646 94214 188646 94206 188647 94214 188647 94215 188647 94215 188648 94214 188648 95482 188648 94215 188649 95482 188649 94216 188649 94228 188650 94217 188650 94206 188650 94206 188651 94217 188651 95492 188651 94206 188652 95492 188652 95491 188652 95500 188653 94218 188653 93919 188653 93919 188654 94218 188654 94219 188654 93919 188655 94219 188655 94220 188655 94220 188656 94219 188656 95499 188656 94220 188657 95499 188657 94228 188657 94228 188658 95499 188658 95497 188658 94228 188659 95497 188659 94221 188659 95460 188660 95462 188660 94415 188660 94222 188661 94234 188661 95470 188661 95495 188662 95500 188662 94415 188662 94415 188663 95500 188663 93919 188663 94415 188664 93919 188664 95460 188664 95460 188665 93919 188665 94230 188665 94222 188666 95470 188666 95448 188666 95448 188667 95470 188667 94223 188667 95448 188668 94223 188668 94224 188668 94224 188669 94223 188669 94225 188669 94224 188670 94225 188670 95480 188670 95462 188671 95466 188671 94415 188671 94415 188672 95466 188672 95463 188672 94415 188673 95463 188673 94226 188673 94226 188674 95463 188674 95473 188674 94226 188675 95473 188675 95472 188675 94231 188676 94227 188676 94228 188676 94228 188677 94227 188677 94229 188677 94228 188678 94229 188678 94220 188678 94220 188679 94229 188679 95459 188679 94220 188680 95459 188680 94230 188680 95477 188681 95476 188681 94239 188681 94239 188682 95476 188682 95468 188682 94239 188683 95468 188683 94228 188683 94228 188684 95468 188684 95469 188684 94228 188685 95469 188685 94231 188685 95477 188686 94232 188686 95481 188686 95481 188687 94232 188687 95449 188687 95481 188688 95449 188688 95480 188688 95480 188689 95449 188689 94233 188689 95480 188690 94233 188690 94224 188690 94049 188691 95454 188691 95452 188691 94234 188692 94222 188692 95472 188692 95472 188693 94222 188693 94235 188693 95472 188694 94235 188694 94226 188694 94226 188695 94235 188695 94236 188695 94226 188696 94236 188696 94049 188696 94049 188697 94236 188697 94237 188697 94049 188698 94237 188698 95454 188698 94245 188699 95455 188699 94239 188699 94239 188700 95455 188700 94238 188700 94238 188701 95450 188701 94239 188701 94239 188702 95450 188702 94240 188702 94239 188703 94240 188703 95477 188703 95477 188704 94240 188704 94241 188704 95477 188705 94241 188705 94232 188705 94248 188706 94242 188706 94249 188706 94249 188707 94242 188707 94243 188707 94249 188708 94243 188708 94244 188708 94244 188709 94243 188709 95457 188709 94244 188710 95457 188710 94245 188710 94245 188711 95457 188711 94246 188711 94245 188712 94246 188712 95455 188712 95428 188713 94247 188713 94049 188713 95452 188714 94248 188714 94049 188714 94049 188715 94248 188715 94249 188715 94049 188716 94249 188716 95428 188716 95428 188717 94249 188717 94250 188717 95440 188718 94251 188718 94266 188718 94251 188719 94252 188719 94266 188719 94266 188720 94252 188720 94253 188720 94266 188721 94253 188721 94263 188721 94247 188722 95430 188722 94049 188722 94049 188723 95430 188723 94254 188723 94049 188724 94254 188724 94266 188724 94266 188725 94254 188725 95441 188725 94266 188726 95441 188726 95440 188726 95436 188727 95434 188727 94245 188727 95434 188728 94255 188728 94245 188728 94245 188729 94255 188729 94256 188729 94245 188730 94256 188730 94244 188730 94244 188731 94256 188731 94257 188731 94244 188732 94257 188732 94250 188732 94258 188733 94260 188733 94259 188733 94259 188734 94260 188734 95442 188734 94259 188735 95442 188735 94245 188735 94245 188736 95442 188736 94261 188736 94245 188737 94261 188737 95436 188737 94253 188738 94262 188738 94263 188738 94263 188739 94262 188739 95446 188739 94263 188740 95446 188740 94264 188740 94264 188741 95446 188741 95444 188741 94264 188742 95444 188742 94258 188742 94258 188743 95444 188743 94265 188743 94258 188744 94265 188744 94260 188744 94046 188745 95411 188745 93918 188745 93918 188746 95411 188746 95425 188746 93918 188747 95425 188747 95424 188747 94264 188748 95408 188748 94263 188748 94263 188749 95408 188749 94267 188749 94263 188750 94267 188750 94266 188750 94266 188751 94267 188751 95409 188751 94266 188752 95409 188752 94046 188752 94046 188753 95409 188753 95413 188753 94046 188754 95413 188754 95411 188754 94268 188755 94269 188755 96965 188755 96965 188756 94269 188756 95420 188756 96965 188757 95420 188757 94258 188757 95420 188758 95419 188758 94258 188758 94258 188759 95419 188759 95417 188759 94258 188760 95417 188760 94264 188760 94264 188761 95417 188761 94270 188761 94264 188762 94270 188762 95408 188762 96963 188763 93935 188763 93933 188763 93933 188764 93935 188764 94271 188764 93933 188765 94271 188765 94272 188765 94272 188766 94271 188766 95222 188766 94272 188767 95222 188767 94273 188767 94273 188768 95222 188768 94282 188768 94273 188769 94282 188769 94274 188769 94274 188770 94282 188770 94284 188770 95423 188771 94286 188771 93918 188771 93918 188772 94286 188772 95148 188772 93918 188773 95148 188773 94046 188773 94046 188774 95148 188774 94275 188774 94046 188775 94275 188775 95146 188775 95423 188776 94276 188776 94286 188776 94286 188777 94276 188777 94277 188777 94286 188778 94277 188778 94284 188778 94284 188779 94277 188779 94278 188779 94284 188780 94278 188780 94274 188780 94286 188781 95390 188781 95397 188781 94279 188782 95401 188782 94483 188782 94483 188783 95401 188783 95406 188783 94483 188784 95406 188784 94288 188784 94286 188785 95397 188785 94483 188785 94483 188786 95397 188786 94280 188786 94483 188787 94280 188787 94279 188787 95393 188788 95391 188788 95222 188788 95222 188789 95391 188789 94281 188789 95222 188790 94281 188790 94282 188790 94282 188791 94281 188791 94283 188791 94282 188792 94283 188792 94284 188792 94284 188793 94283 188793 94285 188793 94284 188794 94285 188794 94286 188794 94286 188795 94285 188795 94287 188795 94286 188796 94287 188796 95390 188796 95406 188797 94289 188797 94288 188797 94288 188798 94289 188798 94290 188798 94288 188799 94290 188799 94297 188799 94297 188800 94290 188800 93924 188800 94297 188801 93924 188801 94291 188801 94291 188802 93924 188802 94292 188802 94291 188803 94292 188803 95230 188803 95376 188804 95381 188804 94068 188804 94068 188805 95381 188805 95380 188805 95380 188806 94293 188806 94068 188806 94068 188807 94293 188807 95387 188807 94068 188808 95387 188808 94302 188808 95136 188809 94299 188809 94068 188809 94068 188810 94299 188810 95377 188810 94068 188811 95377 188811 95376 188811 95214 188812 94069 188812 95898 188812 95898 188813 94069 188813 94294 188813 95898 188814 94294 188814 94291 188814 94291 188815 94294 188815 94295 188815 94295 188816 94296 188816 94291 188816 94291 188817 94296 188817 95370 188817 94291 188818 95370 188818 94297 188818 94297 188819 95370 188819 95372 188819 94297 188820 95372 188820 94288 188820 94288 188821 95372 188821 95373 188821 94288 188822 95373 188822 94483 188822 94483 188823 95373 188823 94298 188823 94483 188824 94298 188824 94299 188824 94299 188825 94298 188825 94300 188825 94299 188826 94300 188826 95377 188826 95387 188827 94301 188827 94302 188827 94302 188828 94301 188828 95385 188828 94302 188829 95385 188829 94309 188829 94309 188830 95385 188830 95384 188830 94309 188831 95384 188831 94308 188831 94308 188832 95384 188832 95383 188832 94308 188833 95383 188833 93921 188833 95359 188834 95358 188834 94307 188834 94307 188835 95358 188835 94303 188835 94307 188836 94303 188836 94313 188836 94068 188837 94311 188837 94304 188837 94304 188838 94311 188838 94305 188838 94304 188839 94305 188839 94307 188839 94307 188840 94305 188840 94306 188840 94307 188841 94306 188841 95359 188841 95355 188842 95354 188842 94308 188842 94308 188843 95354 188843 95348 188843 94308 188844 95348 188844 94309 188844 94309 188845 95348 188845 94310 188845 94309 188846 94310 188846 94302 188846 94302 188847 94310 188847 95350 188847 94302 188848 95350 188848 94068 188848 94068 188849 95350 188849 95352 188849 94068 188850 95352 188850 94311 188850 94303 188851 94312 188851 94313 188851 94313 188852 94312 188852 95367 188852 94313 188853 95367 188853 94314 188853 94314 188854 95367 188854 94315 188854 94314 188855 94315 188855 95232 188855 95232 188856 94315 188856 95365 188856 95232 188857 95365 188857 94316 188857 95341 188858 95340 188858 94425 188858 94425 188859 95340 188859 95338 188859 94425 188860 95338 188860 94424 188860 94307 188861 94317 188861 94318 188861 94307 188862 94318 188862 94425 188862 94425 188863 94318 188863 95335 188863 94425 188864 95335 188864 95341 188864 93938 188865 95324 188865 94314 188865 94314 188866 95324 188866 95325 188866 94314 188867 95325 188867 94313 188867 94313 188868 95325 188868 95326 188868 94313 188869 95326 188869 94307 188869 94307 188870 95326 188870 94319 188870 94307 188871 94319 188871 94317 188871 94321 188872 95313 188872 94323 188872 94320 188873 95539 188873 94323 188873 94323 188874 95539 188874 94191 188874 94323 188875 94191 188875 94321 188875 94321 188876 94191 188876 95309 188876 95322 188877 95321 188877 94410 188877 94410 188878 95321 188878 94331 188878 94410 188879 94331 188879 94322 188879 95313 188880 95312 188880 94323 188880 94323 188881 95312 188881 95318 188881 94323 188882 95318 188882 94410 188882 94410 188883 95318 188883 95317 188883 94410 188884 95317 188884 95322 188884 94324 188885 94325 188885 94330 188885 94325 188886 94326 188886 94330 188886 94330 188887 94326 188887 94327 188887 94330 188888 94327 188888 94328 188888 94328 188889 94327 188889 95307 188889 94328 188890 95307 188890 95309 188890 94335 188891 94336 188891 94329 188891 94335 188892 94329 188892 94330 188892 94330 188893 94329 188893 95315 188893 94330 188894 95315 188894 94324 188894 94331 188895 94332 188895 94322 188895 94322 188896 94332 188896 94333 188896 94322 188897 94333 188897 94349 188897 94349 188898 94333 188898 94334 188898 94349 188899 94334 188899 94335 188899 94335 188900 94334 188900 95323 188900 94335 188901 95323 188901 94336 188901 94346 188902 94337 188902 94341 188902 94349 188903 94338 188903 94322 188903 94322 188904 94338 188904 94339 188904 94322 188905 94339 188905 94410 188905 94410 188906 94339 188906 95295 188906 94410 188907 95295 188907 94340 188907 94341 188908 94342 188908 94346 188908 94346 188909 94342 188909 94352 188909 94346 188910 94352 188910 95503 188910 95503 188911 94352 188911 94343 188911 94344 188912 94345 188912 94346 188912 94346 188913 94345 188913 94347 188913 94346 188914 94347 188914 94337 188914 94351 188915 95298 188915 94335 188915 94201 188916 94353 188916 94350 188916 95298 188917 94348 188917 94335 188917 94335 188918 94348 188918 95296 188918 94335 188919 95296 188919 94349 188919 94349 188920 95296 188920 95291 188920 94349 188921 95291 188921 94338 188921 94201 188922 94350 188922 94335 188922 94335 188923 94350 188923 95300 188923 94335 188924 95300 188924 94351 188924 94342 188925 95306 188925 94352 188925 94352 188926 95306 188926 95305 188926 94352 188927 95305 188927 93920 188927 93920 188928 95305 188928 95304 188928 93920 188929 95304 188929 94201 188929 94201 188930 95304 188930 95303 188930 94201 188931 95303 188931 94353 188931 94354 188932 95950 188932 95943 188932 95943 188933 95950 188933 95944 188933 95947 188934 95948 188934 94355 188934 94355 188935 95948 188935 94356 188935 94380 188936 94357 188936 94947 188936 94380 188937 94358 188937 94357 188937 94357 188938 94358 188938 94359 188938 94357 188939 94359 188939 94766 188939 94360 188940 94374 188940 94372 188940 94372 188941 94361 188941 94360 188941 94360 188942 94361 188942 94362 188942 94360 188943 94362 188943 94931 188943 94931 188944 94362 188944 94904 188944 94931 188945 94904 188945 94932 188945 94932 188946 94904 188946 94902 188946 94373 188947 94365 188947 94363 188947 94373 188948 94364 188948 94365 188948 94365 188949 94364 188949 94366 188949 94365 188950 94366 188950 94950 188950 94950 188951 94366 188951 94368 188951 94950 188952 94368 188952 94367 188952 94367 188953 94368 188953 94369 188953 94388 188954 95928 188954 94909 188954 94909 188955 95928 188955 94910 188955 94388 188956 94370 188956 94374 188956 94374 188957 94370 188957 94371 188957 94374 188958 94371 188958 94372 188958 94363 188959 94357 188959 94373 188959 94373 188960 94357 188960 94374 188960 94373 188961 94374 188961 94929 188961 94929 188962 94374 188962 94360 188962 94766 188963 94763 188963 94357 188963 94357 188964 94763 188964 94762 188964 94357 188965 94762 188965 94374 188965 94374 188966 94762 188966 94375 188966 94374 188967 94375 188967 93984 188967 94375 188968 94760 188968 93984 188968 93984 188969 94760 188969 94759 188969 93984 188970 94759 188970 95942 188970 94759 188971 94758 188971 95942 188971 95942 188972 94758 188972 94756 188972 95942 188973 94756 188973 94376 188973 94369 188974 94377 188974 94367 188974 94367 188975 94377 188975 94385 188975 94367 188976 94385 188976 94378 188976 94378 188977 94385 188977 94384 188977 94947 188978 94379 188978 94380 188978 94380 188979 94379 188979 94946 188979 94380 188980 94946 188980 94382 188980 94902 188981 94381 188981 94932 188981 94932 188982 94381 188982 94900 188982 94932 188983 94900 188983 94933 188983 94933 188984 94900 188984 94385 188984 95935 188985 95934 188985 95942 188985 95934 188986 95933 188986 95942 188986 95942 188987 95933 188987 95944 188987 95942 188988 95944 188988 94356 188988 94356 188989 95944 188989 95950 188989 94356 188990 95950 188990 94355 188990 94376 188991 94380 188991 95942 188991 95942 188992 94380 188992 94382 188992 95942 188993 94382 188993 95935 188993 95935 188994 94382 188994 94383 188994 94383 188995 94384 188995 95935 188995 95935 188996 94384 188996 94385 188996 95935 188997 94385 188997 95928 188997 95928 188998 94385 188998 94900 188998 95928 188999 94900 188999 94910 188999 95928 189000 94386 189000 94392 189000 94395 189001 94387 189001 94489 189001 94388 189002 94374 189002 95928 189002 95928 189003 94374 189003 94389 189003 95928 189004 94389 189004 94386 189004 94387 189005 94390 189005 94489 189005 94489 189006 94390 189006 94391 189006 94489 189007 94391 189007 94374 189007 94374 189008 94391 189008 94872 189008 94374 189009 94872 189009 94389 189009 94392 189010 94870 189010 95928 189010 95928 189011 94870 189011 94393 189011 95928 189012 94393 189012 95926 189012 95926 189013 94393 189013 94394 189013 95926 189014 94394 189014 94877 189014 94877 189015 94395 189015 95926 189015 95926 189016 94395 189016 94489 189016 95926 189017 94489 189017 95927 189017 95927 189018 94489 189018 94490 189018 95927 189019 94490 189019 95925 189019 94743 189020 94396 189020 94735 189020 94735 189021 94396 189021 95916 189021 94739 189022 94490 189022 93917 189022 93917 189023 94490 189023 94397 189023 93917 189024 94397 189024 95017 189024 94738 189025 94736 189025 95916 189025 95916 189026 94736 189026 94398 189026 95916 189027 94398 189027 94735 189027 94743 189028 94399 189028 94396 189028 94396 189029 94399 189029 94400 189029 94396 189030 94400 189030 93917 189030 93917 189031 94400 189031 94741 189031 93917 189032 94741 189032 94740 189032 94739 189033 94401 189033 94490 189033 94490 189034 94401 189034 94402 189034 94490 189035 94402 189035 95925 189035 95925 189036 94402 189036 94738 189036 95925 189037 94738 189037 95917 189037 95917 189038 94738 189038 95916 189038 94404 189039 95914 189039 94403 189039 94404 189040 94403 189040 94407 189040 94405 189041 94406 189041 95909 189041 95909 189042 94406 189042 94407 189042 95909 189043 94407 189043 94396 189043 94396 189044 94407 189044 94403 189044 94396 189045 94403 189045 95916 189045 94618 189046 94160 189046 95893 189046 95893 189047 94160 189047 94408 189047 95893 189048 94408 189048 95888 189048 95888 189049 94408 189049 94163 189049 95888 189050 94163 189050 94409 189050 94410 189051 94412 189051 94323 189051 94323 189052 94412 189052 95884 189052 94323 189053 95884 189053 94163 189053 94163 189054 95884 189054 95882 189054 94163 189055 95882 189055 94409 189055 94413 189056 95876 189056 94410 189056 94410 189057 95876 189057 94411 189057 94410 189058 94411 189058 94412 189058 94340 189059 94344 189059 94410 189059 94410 189060 94344 189060 94346 189060 94410 189061 94346 189061 94413 189061 94413 189062 94346 189062 94210 189062 94413 189063 94210 189063 94414 189063 94414 189064 94210 189064 94415 189064 94414 189065 94415 189065 95869 189065 95869 189066 94415 189066 95870 189066 95870 189067 94415 189067 94226 189067 95870 189068 94226 189068 94416 189068 94416 189069 94226 189069 94042 189069 94416 189070 94042 189070 94043 189070 94693 189071 94692 189071 95850 189071 95850 189072 94692 189072 94417 189072 95850 189073 94417 189073 94419 189073 94695 189074 94418 189074 95861 189074 94426 189075 94685 189075 94425 189075 95861 189076 94418 189076 94422 189076 94685 189077 94684 189077 94425 189077 94425 189078 94684 189078 94682 189078 94425 189079 94682 189079 95861 189079 95861 189080 94682 189080 94697 189080 95861 189081 94697 189081 94695 189081 94417 189082 94690 189082 94419 189082 94419 189083 94690 189083 94688 189083 94419 189084 94688 189084 94420 189084 94420 189085 94688 189085 94426 189085 94420 189086 94426 189086 95851 189086 95854 189087 94421 189087 95850 189087 95850 189088 94421 189088 94422 189088 95850 189089 94422 189089 94693 189089 94693 189090 94422 189090 94418 189090 94423 189091 94425 189091 94430 189091 94430 189092 94425 189092 94424 189092 94430 189093 94424 189093 95345 189093 94423 189094 95868 189094 94425 189094 94425 189095 95868 189095 95865 189095 94425 189096 95865 189096 94426 189096 94426 189097 95865 189097 95855 189097 94426 189098 95855 189098 95851 189098 94427 189099 94428 189099 94846 189099 94846 189100 94428 189100 94423 189100 94846 189101 94423 189101 94848 189101 94848 189102 94423 189102 94849 189102 94427 189103 94845 189103 94428 189103 94428 189104 94845 189104 94844 189104 94428 189105 94844 189105 94460 189105 94460 189106 94844 189106 94429 189106 94460 189107 94429 189107 94843 189107 95345 189108 95347 189108 94430 189108 94430 189109 95347 189109 94460 189109 94430 189110 94460 189110 94840 189110 94840 189111 94460 189111 94843 189111 94840 189112 94852 189112 94430 189112 94430 189113 94852 189113 94851 189113 94430 189114 94851 189114 94423 189114 94423 189115 94851 189115 94850 189115 94423 189116 94850 189116 94849 189116 94441 189117 94431 189117 94450 189117 94718 189118 94717 189118 95885 189118 95885 189119 94717 189119 94432 189119 95885 189120 94432 189120 94433 189120 94433 189121 94432 189121 94434 189121 94433 189122 94434 189122 94439 189122 95890 189123 95891 189123 94435 189123 94467 189124 94460 189124 94436 189124 94436 189125 94460 189125 93944 189125 94436 189126 93944 189126 94437 189126 94437 189127 93944 189127 94714 189127 94444 189128 94438 189128 94443 189128 94443 189129 94438 189129 94452 189129 94435 189130 94433 189130 95890 189130 95890 189131 94433 189131 94439 189131 95890 189132 94439 189132 93944 189132 93944 189133 94439 189133 94440 189133 93944 189134 94440 189134 94714 189134 94441 189135 94450 189135 94786 189135 94442 189136 94451 189136 94454 189136 94442 189137 94454 189137 95880 189137 94463 189138 94823 189138 94428 189138 94823 189139 94822 189139 94428 189139 94428 189140 94822 189140 94450 189140 94428 189141 94450 189141 94443 189141 94443 189142 94450 189142 94431 189142 94443 189143 94431 189143 94444 189143 94805 189144 94445 189144 94446 189144 94446 189145 94445 189145 94448 189145 94446 189146 94448 189146 94447 189146 94447 189147 94448 189147 94804 189147 94447 189148 94804 189148 94822 189148 94822 189149 94804 189149 94449 189149 94822 189150 94449 189150 94450 189150 94451 189151 94443 189151 94454 189151 94454 189152 94443 189152 94452 189152 94454 189153 94452 189153 94453 189153 94453 189154 94452 189154 94783 189154 94453 189155 94783 189155 94467 189155 94459 189156 94817 189156 94466 189156 94718 189157 95885 189157 94454 189157 94454 189158 95885 189158 95879 189158 94454 189159 95879 189159 95880 189159 94450 189160 94455 189160 94786 189160 94786 189161 94455 189161 94456 189161 94786 189162 94456 189162 94457 189162 94457 189163 94456 189163 94803 189163 94457 189164 94803 189164 94458 189164 94458 189165 94803 189165 94801 189165 94458 189166 94801 189166 94464 189166 94805 189167 94446 189167 94466 189167 94466 189168 94446 189168 94819 189168 94466 189169 94819 189169 94459 189169 94814 189170 94826 189170 94460 189170 94460 189171 94826 189171 94461 189171 94460 189172 94461 189172 94428 189172 94428 189173 94461 189173 94462 189173 94428 189174 94462 189174 94463 189174 94464 189175 94801 189175 94465 189175 94465 189176 94801 189176 94800 189176 94465 189177 94800 189177 94466 189177 94817 189178 94814 189178 94466 189178 94466 189179 94814 189179 94460 189179 94466 189180 94460 189180 94465 189180 94465 189181 94460 189181 94467 189181 94465 189182 94467 189182 94782 189182 94782 189183 94467 189183 94783 189183 94634 189184 94647 189184 95907 189184 95907 189185 94647 189185 94469 189185 95907 189186 94469 189186 94468 189186 94468 189187 94469 189187 95910 189187 94469 189188 94470 189188 95910 189188 95910 189189 94470 189189 94471 189189 95910 189190 94471 189190 95912 189190 95912 189191 94471 189191 94472 189191 95912 189192 94472 189192 95913 189192 95913 189193 94472 189193 94473 189193 94473 189194 94472 189194 94474 189194 94473 189195 94474 189195 94480 189195 94017 189196 95931 189196 94475 189196 94475 189197 95931 189197 94476 189197 94475 189198 94476 189198 96971 189198 96971 189199 94476 189199 94478 189199 96971 189200 94478 189200 94477 189200 94477 189201 94478 189201 94479 189201 94477 189202 94479 189202 96972 189202 96972 189203 94479 189203 95921 189203 96972 189204 95921 189204 94474 189204 94474 189205 95921 189205 95919 189205 94474 189206 95919 189206 94480 189206 95153 189207 94482 189207 94481 189207 94481 189208 94482 189208 94483 189208 94481 189209 94483 189209 95862 189209 95862 189210 94483 189210 94299 189210 95862 189211 94299 189211 94065 189211 94065 189212 94299 189212 95135 189212 94992 189213 94484 189213 94052 189213 94052 189214 94484 189214 94485 189214 94052 189215 94485 189215 95901 189215 95901 189216 94485 189216 93996 189216 95901 189217 93996 189217 93995 189217 93995 189218 93996 189218 94999 189218 94486 189219 95715 189219 94487 189219 94487 189220 95715 189220 95714 189220 94487 189221 95714 189221 95088 189221 95088 189222 95714 189222 94081 189222 95088 189223 94081 189223 94374 189223 94374 189224 94081 189224 94488 189224 94374 189225 94488 189225 94489 189225 94489 189226 94488 189226 94003 189226 94489 189227 94003 189227 94490 189227 94490 189228 94003 189228 95008 189228 94490 189229 95008 189229 94397 189229 94492 189230 95796 189230 95271 189230 95832 189231 95945 189231 95270 189231 95270 189232 95945 189232 95951 189232 95270 189233 95951 189233 95271 189233 95271 189234 95951 189234 95952 189234 95271 189235 95952 189235 94492 189235 94491 189236 95258 189236 95822 189236 95796 189237 94492 189237 95822 189237 95822 189238 94492 189238 94493 189238 95822 189239 94493 189239 94491 189239 94494 189240 95887 189240 95740 189240 95740 189241 95887 189241 95889 189241 95740 189242 95889 189242 95793 189242 95793 189243 95889 189243 95789 189243 95941 189244 95247 189244 94495 189244 94495 189245 95247 189245 95835 189245 94495 189246 95835 189246 94496 189246 94495 189247 94496 189247 95930 189247 95930 189248 94496 189248 95836 189248 95930 189249 95836 189249 94497 189249 94497 189250 95836 189250 95840 189250 94497 189251 95840 189251 94499 189251 94499 189252 95840 189252 94498 189252 95781 189253 95771 189253 94498 189253 94498 189254 95771 189254 95923 189254 94498 189255 95923 189255 94499 189255 94504 189256 95841 189256 94500 189256 95827 189257 95253 189257 94501 189257 94501 189258 95253 189258 95852 189258 94501 189259 95852 189259 94502 189259 94502 189260 95852 189260 94503 189260 94502 189261 94503 189261 95276 189261 95276 189262 94503 189262 95290 189262 95276 189263 95290 189263 94500 189263 94500 189264 95290 189264 95886 189264 94500 189265 95886 189265 94504 189265 94530 189266 94529 189266 94505 189266 94506 189267 95776 189267 94505 189267 94505 189268 95776 189268 95874 189268 94505 189269 95874 189269 94530 189269 94507 189270 94508 189270 95727 189270 95727 189271 94508 189271 94538 189271 95727 189272 94538 189272 95728 189272 95728 189273 94538 189273 95759 189273 94508 189274 94507 189274 94509 189274 94508 189275 94509 189275 94511 189275 94511 189276 94509 189276 94510 189276 94511 189277 94510 189277 94512 189277 94512 189278 94510 189278 94513 189278 94512 189279 94513 189279 95896 189279 95896 189280 94513 189280 95251 189280 95251 189281 94513 189281 94514 189281 94533 189282 94534 189282 95877 189282 95877 189283 94534 189283 95783 189283 95877 189284 95783 189284 95883 189284 95883 189285 95783 189285 95787 189285 95883 189286 95787 189286 95881 189286 95881 189287 95787 189287 94515 189287 95881 189288 94515 189288 95889 189288 95889 189289 94515 189289 95789 189289 95887 189290 94494 189290 94516 189290 95887 189291 94516 189291 94517 189291 94517 189292 94516 189292 94519 189292 94517 189293 94519 189293 94518 189293 94518 189294 94519 189294 94520 189294 94518 189295 94520 189295 95899 189295 95899 189296 94520 189296 95904 189296 95904 189297 94520 189297 94521 189297 95923 189298 95771 189298 95922 189298 95922 189299 95771 189299 94522 189299 95922 189300 94522 189300 95920 189300 95920 189301 94522 189301 95772 189301 95920 189302 95772 189302 95918 189302 95918 189303 95772 189303 94523 189303 95918 189304 94523 189304 95915 189304 95915 189305 94523 189305 94524 189305 95863 189306 94525 189306 95858 189306 95858 189307 94525 189307 95825 189307 95858 189308 95825 189308 94527 189308 95858 189309 94527 189309 94526 189309 94526 189310 94527 189310 94528 189310 94526 189311 94528 189311 95867 189311 95867 189312 94528 189312 94529 189312 95867 189313 94529 189313 94530 189313 95874 189314 95776 189314 95873 189314 95873 189315 95776 189315 94531 189315 95873 189316 94531 189316 95872 189316 95872 189317 94531 189317 94532 189317 95872 189318 94532 189318 94533 189318 94533 189319 94532 189319 94534 189319 95915 189320 94524 189320 94535 189320 94535 189321 94524 189321 94536 189321 94535 189322 94536 189322 95911 189322 95911 189323 94536 189323 94537 189323 95911 189324 94537 189324 94538 189324 94538 189325 94537 189325 95759 189325 94541 189326 94539 189326 94540 189326 95732 189327 95848 189327 95731 189327 95731 189328 95848 189328 95729 189328 94541 189329 94540 189329 95274 189329 94543 189330 95846 189330 94544 189330 94542 189331 95847 189331 95846 189331 95846 189332 95847 189332 95848 189332 95846 189333 95848 189333 94544 189333 94544 189334 95848 189334 95732 189334 95844 189335 95845 189335 94540 189335 94540 189336 95845 189336 94543 189336 94540 189337 94543 189337 95274 189337 95274 189338 94543 189338 94544 189338 95744 189339 95274 189339 95746 189339 95746 189340 95274 189340 94544 189340 95737 189341 94545 189341 94548 189341 94546 189342 95265 189342 95828 189342 95828 189343 95265 189343 94551 189343 94547 189344 94549 189344 94548 189344 94548 189345 94549 189345 95824 189345 94552 189346 95826 189346 94550 189346 94550 189347 95828 189347 94552 189347 94552 189348 95828 189348 94551 189348 94552 189349 94551 189349 95824 189349 95824 189350 94551 189350 94553 189350 95824 189351 94553 189351 94548 189351 94548 189352 94553 189352 95738 189352 94548 189353 95738 189353 95737 189353 95769 189354 94553 189354 95763 189354 95763 189355 94553 189355 94551 189355 95786 189356 94554 189356 95784 189356 95784 189357 94554 189357 94559 189357 95733 189358 95735 189358 94561 189358 95830 189359 94555 189359 94557 189359 94557 189360 94555 189360 94559 189360 95837 189361 95838 189361 94561 189361 94561 189362 95838 189362 94560 189362 94558 189363 95834 189363 94556 189363 94556 189364 94557 189364 94558 189364 94558 189365 94557 189365 94559 189365 94558 189366 94559 189366 94560 189366 94560 189367 94559 189367 94554 189367 94560 189368 94554 189368 94561 189368 94561 189369 94554 189369 94562 189369 94561 189370 94562 189370 95733 189370 95809 189371 94568 189371 95801 189371 95801 189372 94568 189372 95743 189372 94563 189373 95741 189373 95812 189373 95812 189374 95741 189374 94564 189374 95812 189375 94564 189375 95743 189375 95814 189376 95815 189376 94567 189376 95819 189377 94565 189377 94566 189377 94566 189378 94565 189378 95820 189378 94566 189379 95820 189379 95816 189379 94567 189380 95812 189380 95814 189380 95814 189381 95812 189381 95743 189381 95814 189382 95743 189382 94565 189382 94565 189383 95743 189383 94568 189383 94565 189384 94568 189384 95820 189384 95820 189385 94568 189385 95266 189385 95820 189386 95266 189386 94569 189386 96655 189387 94570 189387 94571 189387 94571 189388 94570 189388 96384 189388 94571 189389 96384 189389 94572 189389 94572 189390 96384 189390 96385 189390 94572 189391 96385 189391 94573 189391 94573 189392 96385 189392 96387 189392 94573 189393 96387 189393 94574 189393 94574 189394 96387 189394 96388 189394 94574 189395 96388 189395 96660 189395 96660 189396 96388 189396 96390 189396 96660 189397 96390 189397 96657 189397 96657 189398 96390 189398 94575 189398 96657 189399 94575 189399 96649 189399 96649 189400 94575 189400 94576 189400 96649 189401 94576 189401 94577 189401 94577 189402 94576 189402 94578 189402 94577 189403 94578 189403 94579 189403 94579 189404 94578 189404 94580 189404 94579 189405 94580 189405 94581 189405 94581 189406 94580 189406 96380 189406 94581 189407 96380 189407 96654 189407 96654 189408 96380 189408 94582 189408 96654 189409 94582 189409 96655 189409 96655 189410 94582 189410 94570 189410 94593 189411 94042 189411 94583 189411 94583 189412 94042 189412 94041 189412 94583 189413 94041 189413 93239 189413 93239 189414 94041 189414 94040 189414 93239 189415 94040 189415 94584 189415 94584 189416 94040 189416 94048 189416 94584 189417 94048 189417 93240 189417 93240 189418 94048 189418 94585 189418 93240 189419 94585 189419 93242 189419 93242 189420 94585 189420 94047 189420 93242 189421 94047 189421 93243 189421 93243 189422 94047 189422 94045 189422 93243 189423 94045 189423 94586 189423 94586 189424 94045 189424 94044 189424 94586 189425 94044 189425 94587 189425 94587 189426 94044 189426 94588 189426 94587 189427 94588 189427 93246 189427 93246 189428 94588 189428 94589 189428 93246 189429 94589 189429 94590 189429 94590 189430 94589 189430 94591 189430 94590 189431 94591 189431 94592 189431 94592 189432 94591 189432 94043 189432 94592 189433 94043 189433 94593 189433 94593 189434 94043 189434 94042 189434 94594 189435 94595 189435 96664 189435 96664 189436 94595 189436 94596 189436 96664 189437 94596 189437 94597 189437 94597 189438 94596 189438 96376 189438 94597 189439 96376 189439 96665 189439 96665 189440 96376 189440 94599 189440 96665 189441 94599 189441 94598 189441 94598 189442 94599 189442 94601 189442 94598 189443 94601 189443 94600 189443 94600 189444 94601 189444 94602 189444 94600 189445 94602 189445 96668 189445 96668 189446 94602 189446 94604 189446 96668 189447 94604 189447 94603 189447 94603 189448 94604 189448 94605 189448 94603 189449 94605 189449 94606 189449 94606 189450 94605 189450 96368 189450 94606 189451 96368 189451 94607 189451 94607 189452 96368 189452 96370 189452 94607 189453 96370 189453 94608 189453 94608 189454 96370 189454 96373 189454 94608 189455 96373 189455 94609 189455 94609 189456 96373 189456 96374 189456 94609 189457 96374 189457 94594 189457 94594 189458 96374 189458 94595 189458 94610 189459 94035 189459 94611 189459 94611 189460 94035 189460 94612 189460 94611 189461 94612 189461 94613 189461 94613 189462 94612 189462 94032 189462 94613 189463 94032 189463 94614 189463 94614 189464 94032 189464 94031 189464 94614 189465 94031 189465 94615 189465 94615 189466 94031 189466 94616 189466 94615 189467 94616 189467 94617 189467 94617 189468 94616 189468 94027 189468 94617 189469 94027 189469 94619 189469 94619 189470 94027 189470 94618 189470 94619 189471 94618 189471 93250 189471 93250 189472 94618 189472 94030 189472 93250 189473 94030 189473 93252 189473 93252 189474 94030 189474 94028 189474 93252 189475 94028 189475 94620 189475 94620 189476 94028 189476 94039 189476 94620 189477 94039 189477 94621 189477 94621 189478 94039 189478 94038 189478 94621 189479 94038 189479 93254 189479 93254 189480 94038 189480 94037 189480 93254 189481 94037 189481 94610 189481 94610 189482 94037 189482 94035 189482 96632 189483 96365 189483 94622 189483 94622 189484 96365 189484 96355 189484 94622 189485 96355 189485 94623 189485 94623 189486 96355 189486 94624 189486 94623 189487 94624 189487 96626 189487 96626 189488 94624 189488 94626 189488 96626 189489 94626 189489 94625 189489 94625 189490 94626 189490 96357 189490 94625 189491 96357 189491 96627 189491 96627 189492 96357 189492 94627 189492 96627 189493 94627 189493 96628 189493 96628 189494 94627 189494 94628 189494 96628 189495 94628 189495 96629 189495 96629 189496 94628 189496 94629 189496 96629 189497 94629 189497 96630 189497 96630 189498 94629 189498 96360 189498 96630 189499 96360 189499 94630 189499 94630 189500 96360 189500 94631 189500 94630 189501 94631 189501 96634 189501 96634 189502 94631 189502 96363 189502 96634 189503 96363 189503 94632 189503 94632 189504 96363 189504 96364 189504 94632 189505 96364 189505 96632 189505 96632 189506 96364 189506 96365 189506 94646 189507 94647 189507 94633 189507 94633 189508 94647 189508 94634 189508 94633 189509 94634 189509 93256 189509 93256 189510 94634 189510 94018 189510 93256 189511 94018 189511 94635 189511 94635 189512 94018 189512 94636 189512 94635 189513 94636 189513 94637 189513 94637 189514 94636 189514 94638 189514 94637 189515 94638 189515 94639 189515 94639 189516 94638 189516 94025 189516 94639 189517 94025 189517 93258 189517 93258 189518 94025 189518 94023 189518 93258 189519 94023 189519 94640 189519 94640 189520 94023 189520 94641 189520 94640 189521 94641 189521 93260 189521 93260 189522 94641 189522 94642 189522 93260 189523 94642 189523 93262 189523 93262 189524 94642 189524 94643 189524 93262 189525 94643 189525 94644 189525 94644 189526 94643 189526 94645 189526 94644 189527 94645 189527 93264 189527 93264 189528 94645 189528 94020 189528 93264 189529 94020 189529 94646 189529 94646 189530 94020 189530 94647 189530 96612 189531 96349 189531 96613 189531 96613 189532 96349 189532 96352 189532 96613 189533 96352 189533 94648 189533 94648 189534 96352 189534 96353 189534 94648 189535 96353 189535 94649 189535 94649 189536 96353 189536 96354 189536 94649 189537 96354 189537 96617 189537 96617 189538 96354 189538 94650 189538 96617 189539 94650 189539 96618 189539 96618 189540 94650 189540 94651 189540 96618 189541 94651 189541 96620 189541 96620 189542 94651 189542 96343 189542 96620 189543 96343 189543 96621 189543 96621 189544 96343 189544 96344 189544 96621 189545 96344 189545 94652 189545 94652 189546 96344 189546 96345 189546 94652 189547 96345 189547 94653 189547 94653 189548 96345 189548 94654 189548 94653 189549 94654 189549 96622 189549 96622 189550 94654 189550 96347 189550 96622 189551 96347 189551 96623 189551 96623 189552 96347 189552 96348 189552 96623 189553 96348 189553 96612 189553 96612 189554 96348 189554 96349 189554 94665 189555 94010 189555 93277 189555 93277 189556 94010 189556 94656 189556 93277 189557 94656 189557 94655 189557 94655 189558 94656 189558 94657 189558 94655 189559 94657 189559 93266 189559 93266 189560 94657 189560 94004 189560 93266 189561 94004 189561 94658 189561 94658 189562 94004 189562 94005 189562 94658 189563 94005 189563 94659 189563 94659 189564 94005 189564 94660 189564 94659 189565 94660 189565 94661 189565 94661 189566 94660 189566 94017 189566 94661 189567 94017 189567 94662 189567 94662 189568 94017 189568 94016 189568 94662 189569 94016 189569 93271 189569 93271 189570 94016 189570 94663 189570 93271 189571 94663 189571 93273 189571 93273 189572 94663 189572 94015 189572 93273 189573 94015 189573 94664 189573 94664 189574 94015 189574 94014 189574 94664 189575 94014 189575 93276 189575 93276 189576 94014 189576 94012 189576 93276 189577 94012 189577 94665 189577 94665 189578 94012 189578 94010 189578 96776 189579 94666 189579 96773 189579 96773 189580 94666 189580 94667 189580 96773 189581 94667 189581 94669 189581 94669 189582 94667 189582 94668 189582 94669 189583 94668 189583 94670 189583 94670 189584 94668 189584 96333 189584 94670 189585 96333 189585 96774 189585 96774 189586 96333 189586 96334 189586 96774 189587 96334 189587 94671 189587 94671 189588 96334 189588 96335 189588 94671 189589 96335 189589 94672 189589 94672 189590 96335 189590 96336 189590 94672 189591 96336 189591 94673 189591 94673 189592 96336 189592 96338 189592 94673 189593 96338 189593 94674 189593 94674 189594 96338 189594 94675 189594 94674 189595 94675 189595 96779 189595 96779 189596 94675 189596 94676 189596 96779 189597 94676 189597 94677 189597 94677 189598 94676 189598 94678 189598 94677 189599 94678 189599 94680 189599 94680 189600 94678 189600 94679 189600 94680 189601 94679 189601 96776 189601 96776 189602 94679 189602 94666 189602 94681 189603 94682 189603 94683 189603 94683 189604 94682 189604 94684 189604 94683 189605 94684 189605 93280 189605 93280 189606 94684 189606 94685 189606 93280 189607 94685 189607 94686 189607 94686 189608 94685 189608 94426 189608 94686 189609 94426 189609 94687 189609 94687 189610 94426 189610 94688 189610 94687 189611 94688 189611 94689 189611 94689 189612 94688 189612 94690 189612 94689 189613 94690 189613 93283 189613 93283 189614 94690 189614 94417 189614 93283 189615 94417 189615 94691 189615 94691 189616 94417 189616 94692 189616 94691 189617 94692 189617 93285 189617 93285 189618 94692 189618 94693 189618 93285 189619 94693 189619 94694 189619 94694 189620 94693 189620 94418 189620 94694 189621 94418 189621 93286 189621 93286 189622 94418 189622 94695 189622 93286 189623 94695 189623 94696 189623 94696 189624 94695 189624 94697 189624 94696 189625 94697 189625 94681 189625 94681 189626 94697 189626 94682 189626 94709 189627 94710 189627 94698 189627 94698 189628 94710 189628 94699 189628 94698 189629 94699 189629 94701 189629 94701 189630 94699 189630 94700 189630 94701 189631 94700 189631 96641 189631 96641 189632 94700 189632 96323 189632 96641 189633 96323 189633 96640 189633 96640 189634 96323 189634 94703 189634 96640 189635 94703 189635 94702 189635 94702 189636 94703 189636 96325 189636 94702 189637 96325 189637 94704 189637 94704 189638 96325 189638 94705 189638 94704 189639 94705 189639 96645 189639 96645 189640 94705 189640 96328 189640 96645 189641 96328 189641 94706 189641 94706 189642 96328 189642 94707 189642 94706 189643 94707 189643 96703 189643 96703 189644 94707 189644 96330 189644 96703 189645 96330 189645 96639 189645 96639 189646 96330 189646 96331 189646 96639 189647 96331 189647 94708 189647 94708 189648 96331 189648 96320 189648 94708 189649 96320 189649 94709 189649 94709 189650 96320 189650 94710 189650 94711 189651 94436 189651 94712 189651 94712 189652 94436 189652 94437 189652 94712 189653 94437 189653 93290 189653 93290 189654 94437 189654 94714 189654 93290 189655 94714 189655 94713 189655 94713 189656 94714 189656 94440 189656 94713 189657 94440 189657 93292 189657 93292 189658 94440 189658 94439 189658 93292 189659 94439 189659 93293 189659 93293 189660 94439 189660 94434 189660 93293 189661 94434 189661 94715 189661 94715 189662 94434 189662 94432 189662 94715 189663 94432 189663 94716 189663 94716 189664 94432 189664 94717 189664 94716 189665 94717 189665 93295 189665 93295 189666 94717 189666 94718 189666 93295 189667 94718 189667 94719 189667 94719 189668 94718 189668 94454 189668 94719 189669 94454 189669 94720 189669 94720 189670 94454 189670 94453 189670 94720 189671 94453 189671 94721 189671 94721 189672 94453 189672 94467 189672 94721 189673 94467 189673 94711 189673 94711 189674 94467 189674 94436 189674 96782 189675 94722 189675 96783 189675 96783 189676 94722 189676 94723 189676 96783 189677 94723 189677 96784 189677 96784 189678 94723 189678 94724 189678 96784 189679 94724 189679 94725 189679 94725 189680 94724 189680 94726 189680 94725 189681 94726 189681 96789 189681 96789 189682 94726 189682 96318 189682 96789 189683 96318 189683 94728 189683 94728 189684 96318 189684 94727 189684 94728 189685 94727 189685 96787 189685 96787 189686 94727 189686 94730 189686 96787 189687 94730 189687 94729 189687 94729 189688 94730 189688 96319 189688 94729 189689 96319 189689 96790 189689 96790 189690 96319 189690 96312 189690 96790 189691 96312 189691 94731 189691 94731 189692 96312 189692 94733 189692 94731 189693 94733 189693 94732 189693 94732 189694 94733 189694 96314 189694 94732 189695 96314 189695 94734 189695 94734 189696 96314 189696 96316 189696 94734 189697 96316 189697 96782 189697 96782 189698 96316 189698 94722 189698 93317 189699 94735 189699 93300 189699 93300 189700 94735 189700 94398 189700 93300 189701 94398 189701 94737 189701 94737 189702 94398 189702 94736 189702 94737 189703 94736 189703 93303 189703 93303 189704 94736 189704 94738 189704 93303 189705 94738 189705 93305 189705 93305 189706 94738 189706 94402 189706 93305 189707 94402 189707 93307 189707 93307 189708 94402 189708 94401 189708 93307 189709 94401 189709 93309 189709 93309 189710 94401 189710 94739 189710 93309 189711 94739 189711 93310 189711 93310 189712 94739 189712 94740 189712 93310 189713 94740 189713 93311 189713 93311 189714 94740 189714 94741 189714 93311 189715 94741 189715 94742 189715 94742 189716 94741 189716 94400 189716 94742 189717 94400 189717 93314 189717 93314 189718 94400 189718 94399 189718 93314 189719 94399 189719 93316 189719 93316 189720 94399 189720 94743 189720 93316 189721 94743 189721 93317 189721 93317 189722 94743 189722 94735 189722 96696 189723 94745 189723 94744 189723 94744 189724 94745 189724 94746 189724 94744 189725 94746 189725 96697 189725 96697 189726 94746 189726 96298 189726 96697 189727 96298 189727 96698 189727 96698 189728 96298 189728 96300 189728 96698 189729 96300 189729 96699 189729 96699 189730 96300 189730 96301 189730 96699 189731 96301 189731 96701 189731 96701 189732 96301 189732 96302 189732 96701 189733 96302 189733 94747 189733 94747 189734 96302 189734 96303 189734 94747 189735 96303 189735 94748 189735 94748 189736 96303 189736 96305 189736 94748 189737 96305 189737 94750 189737 94750 189738 96305 189738 94749 189738 94750 189739 94749 189739 94751 189739 94751 189740 94749 189740 96308 189740 94751 189741 96308 189741 94752 189741 94752 189742 96308 189742 96309 189742 94752 189743 96309 189743 96695 189743 96695 189744 96309 189744 94753 189744 96695 189745 94753 189745 96696 189745 96696 189746 94753 189746 94745 189746 93329 189747 94380 189747 94754 189747 94754 189748 94380 189748 94376 189748 94754 189749 94376 189749 94755 189749 94755 189750 94376 189750 94756 189750 94755 189751 94756 189751 94757 189751 94757 189752 94756 189752 94758 189752 94757 189753 94758 189753 93319 189753 93319 189754 94758 189754 94759 189754 93319 189755 94759 189755 93322 189755 93322 189756 94759 189756 94760 189756 93322 189757 94760 189757 94761 189757 94761 189758 94760 189758 94375 189758 94761 189759 94375 189759 93323 189759 93323 189760 94375 189760 94762 189760 93323 189761 94762 189761 94764 189761 94764 189762 94762 189762 94763 189762 94764 189763 94763 189763 94765 189763 94765 189764 94763 189764 94766 189764 94765 189765 94766 189765 93326 189765 93326 189766 94766 189766 94359 189766 93326 189767 94359 189767 93328 189767 93328 189768 94359 189768 94358 189768 93328 189769 94358 189769 93329 189769 93329 189770 94358 189770 94380 189770 96715 189771 94779 189771 94767 189771 94767 189772 94779 189772 94769 189772 94767 189773 94769 189773 94768 189773 94768 189774 94769 189774 94770 189774 94768 189775 94770 189775 96712 189775 96712 189776 94770 189776 94771 189776 96712 189777 94771 189777 96717 189777 96717 189778 94771 189778 94772 189778 96717 189779 94772 189779 94773 189779 94773 189780 94772 189780 96289 189780 94773 189781 96289 189781 96718 189781 96718 189782 96289 189782 94774 189782 96718 189783 94774 189783 96719 189783 96719 189784 94774 189784 94776 189784 96719 189785 94776 189785 94775 189785 94775 189786 94776 189786 94777 189786 94775 189787 94777 189787 96720 189787 96720 189788 94777 189788 96294 189788 96720 189789 96294 189789 96721 189789 96721 189790 96294 189790 94778 189790 96721 189791 94778 189791 96713 189791 96713 189792 94778 189792 96297 189792 96713 189793 96297 189793 96715 189793 96715 189794 96297 189794 94779 189794 94780 189795 94465 189795 93331 189795 93331 189796 94465 189796 94782 189796 93331 189797 94782 189797 94781 189797 94781 189798 94782 189798 94783 189798 94781 189799 94783 189799 94784 189799 94784 189800 94783 189800 94452 189800 94784 189801 94452 189801 94785 189801 94785 189802 94452 189802 94438 189802 94785 189803 94438 189803 93335 189803 93335 189804 94438 189804 94444 189804 93335 189805 94444 189805 93336 189805 93336 189806 94444 189806 94431 189806 93336 189807 94431 189807 93337 189807 93337 189808 94431 189808 94441 189808 93337 189809 94441 189809 93338 189809 93338 189810 94441 189810 94786 189810 93338 189811 94786 189811 93339 189811 93339 189812 94786 189812 94457 189812 93339 189813 94457 189813 93340 189813 93340 189814 94457 189814 94458 189814 93340 189815 94458 189815 93341 189815 93341 189816 94458 189816 94464 189816 93341 189817 94464 189817 94780 189817 94780 189818 94464 189818 94465 189818 94797 189819 94798 189819 96731 189819 96731 189820 94798 189820 96277 189820 96731 189821 96277 189821 94788 189821 94788 189822 96277 189822 94787 189822 94788 189823 94787 189823 96730 189823 96730 189824 94787 189824 94789 189824 96730 189825 94789 189825 96732 189825 96732 189826 94789 189826 94790 189826 96732 189827 94790 189827 96733 189827 96733 189828 94790 189828 94791 189828 96733 189829 94791 189829 94793 189829 94793 189830 94791 189830 94792 189830 94793 189831 94792 189831 96734 189831 96734 189832 94792 189832 96284 189832 96734 189833 96284 189833 94794 189833 94794 189834 96284 189834 96285 189834 94794 189835 96285 189835 96735 189835 96735 189836 96285 189836 96286 189836 96735 189837 96286 189837 96729 189837 96729 189838 96286 189838 94795 189838 96729 189839 94795 189839 94796 189839 94796 189840 94795 189840 96276 189840 94796 189841 96276 189841 94797 189841 94797 189842 96276 189842 94798 189842 94799 189843 94466 189843 93342 189843 93342 189844 94466 189844 94800 189844 93342 189845 94800 189845 93343 189845 93343 189846 94800 189846 94801 189846 93343 189847 94801 189847 94802 189847 94802 189848 94801 189848 94803 189848 94802 189849 94803 189849 93344 189849 93344 189850 94803 189850 94456 189850 93344 189851 94456 189851 93346 189851 93346 189852 94456 189852 94455 189852 93346 189853 94455 189853 93347 189853 93347 189854 94455 189854 94450 189854 93347 189855 94450 189855 93348 189855 93348 189856 94450 189856 94449 189856 93348 189857 94449 189857 93352 189857 93352 189858 94449 189858 94804 189858 93352 189859 94804 189859 93353 189859 93353 189860 94804 189860 94448 189860 93353 189861 94448 189861 93355 189861 93355 189862 94448 189862 94445 189862 93355 189863 94445 189863 93357 189863 93357 189864 94445 189864 94805 189864 93357 189865 94805 189865 94799 189865 94799 189866 94805 189866 94466 189866 96746 189867 94813 189867 96751 189867 96751 189868 94813 189868 94806 189868 96751 189869 94806 189869 96752 189869 96752 189870 94806 189870 94807 189870 96752 189871 94807 189871 96753 189871 96753 189872 94807 189872 96265 189872 96753 189873 96265 189873 96754 189873 96754 189874 96265 189874 96266 189874 96754 189875 96266 189875 94808 189875 94808 189876 96266 189876 96267 189876 94808 189877 96267 189877 96749 189877 96749 189878 96267 189878 96268 189878 96749 189879 96268 189879 94809 189879 94809 189880 96268 189880 96269 189880 94809 189881 96269 189881 96748 189881 96748 189882 96269 189882 96271 189882 96748 189883 96271 189883 96747 189883 96747 189884 96271 189884 94811 189884 96747 189885 94811 189885 94810 189885 94810 189886 94811 189886 94812 189886 94810 189887 94812 189887 96744 189887 96744 189888 94812 189888 96274 189888 96744 189889 96274 189889 96746 189889 96746 189890 96274 189890 94813 189890 93368 189891 94814 189891 94815 189891 94815 189892 94814 189892 94817 189892 94815 189893 94817 189893 94816 189893 94816 189894 94817 189894 94459 189894 94816 189895 94459 189895 94818 189895 94818 189896 94459 189896 94819 189896 94818 189897 94819 189897 94820 189897 94820 189898 94819 189898 94446 189898 94820 189899 94446 189899 93362 189899 93362 189900 94446 189900 94447 189900 93362 189901 94447 189901 94821 189901 94821 189902 94447 189902 94822 189902 94821 189903 94822 189903 93363 189903 93363 189904 94822 189904 94823 189904 93363 189905 94823 189905 93365 189905 93365 189906 94823 189906 94463 189906 93365 189907 94463 189907 94824 189907 94824 189908 94463 189908 94462 189908 94824 189909 94462 189909 93367 189909 93367 189910 94462 189910 94461 189910 93367 189911 94461 189911 94825 189911 94825 189912 94461 189912 94826 189912 94825 189913 94826 189913 93368 189913 93368 189914 94826 189914 94814 189914 96759 189915 94839 189915 96761 189915 96761 189916 94839 189916 94828 189916 96761 189917 94828 189917 94827 189917 94827 189918 94828 189918 96251 189918 94827 189919 96251 189919 94829 189919 94829 189920 96251 189920 96252 189920 94829 189921 96252 189921 96762 189921 96762 189922 96252 189922 94830 189922 96762 189923 94830 189923 96763 189923 96763 189924 94830 189924 94831 189924 96763 189925 94831 189925 96764 189925 96764 189926 94831 189926 96253 189926 96764 189927 96253 189927 94832 189927 94832 189928 96253 189928 96255 189928 94832 189929 96255 189929 94833 189929 94833 189930 96255 189930 96257 189930 94833 189931 96257 189931 94834 189931 94834 189932 96257 189932 96259 189932 94834 189933 96259 189933 94835 189933 94835 189934 96259 189934 94837 189934 94835 189935 94837 189935 94836 189935 94836 189936 94837 189936 94838 189936 94836 189937 94838 189937 96759 189937 96759 189938 94838 189938 94839 189938 93383 189939 94840 189939 94841 189939 94841 189940 94840 189940 94843 189940 94841 189941 94843 189941 94842 189941 94842 189942 94843 189942 94429 189942 94842 189943 94429 189943 93372 189943 93372 189944 94429 189944 94844 189944 93372 189945 94844 189945 93374 189945 93374 189946 94844 189946 94845 189946 93374 189947 94845 189947 93375 189947 93375 189948 94845 189948 94427 189948 93375 189949 94427 189949 93377 189949 93377 189950 94427 189950 94846 189950 93377 189951 94846 189951 94847 189951 94847 189952 94846 189952 94848 189952 94847 189953 94848 189953 93378 189953 93378 189954 94848 189954 94849 189954 93378 189955 94849 189955 93379 189955 93379 189956 94849 189956 94850 189956 93379 189957 94850 189957 93380 189957 93380 189958 94850 189958 94851 189958 93380 189959 94851 189959 93382 189959 93382 189960 94851 189960 94852 189960 93382 189961 94852 189961 93383 189961 93383 189962 94852 189962 94840 189962 96766 189963 94869 189963 94853 189963 94853 189964 94869 189964 94854 189964 94853 189965 94854 189965 94855 189965 94855 189966 94854 189966 94856 189966 94855 189967 94856 189967 94857 189967 94857 189968 94856 189968 94859 189968 94857 189969 94859 189969 94858 189969 94858 189970 94859 189970 96243 189970 94858 189971 96243 189971 94860 189971 94860 189972 96243 189972 94861 189972 94860 189973 94861 189973 96769 189973 96769 189974 94861 189974 96245 189974 96769 189975 96245 189975 94862 189975 94862 189976 96245 189976 96247 189976 94862 189977 96247 189977 96770 189977 96770 189978 96247 189978 94864 189978 96770 189979 94864 189979 94863 189979 94863 189980 94864 189980 94865 189980 94863 189981 94865 189981 94866 189981 94866 189982 94865 189982 94867 189982 94866 189983 94867 189983 96772 189983 96772 189984 94867 189984 94868 189984 96772 189985 94868 189985 96766 189985 96766 189986 94868 189986 94869 189986 93393 189987 94393 189987 93394 189987 93394 189988 94393 189988 94870 189988 93394 189989 94870 189989 93385 189989 93385 189990 94870 189990 94392 189990 93385 189991 94392 189991 94871 189991 94871 189992 94392 189992 94386 189992 94871 189993 94386 189993 93388 189993 93388 189994 94386 189994 94389 189994 93388 189995 94389 189995 93389 189995 93389 189996 94389 189996 94872 189996 93389 189997 94872 189997 94873 189997 94873 189998 94872 189998 94391 189998 94873 189999 94391 189999 94874 189999 94874 190000 94391 190000 94390 190000 94874 190001 94390 190001 93390 190001 93390 190002 94390 190002 94387 190002 93390 190003 94387 190003 94875 190003 94875 190004 94387 190004 94395 190004 94875 190005 94395 190005 94876 190005 94876 190006 94395 190006 94877 190006 94876 190007 94877 190007 94878 190007 94878 190008 94877 190008 94394 190008 94878 190009 94394 190009 93393 190009 93393 190010 94394 190010 94393 190010 94879 190011 94880 190011 96755 190011 96755 190012 94880 190012 94881 190012 96755 190013 94881 190013 94882 190013 94882 190014 94881 190014 94883 190014 94882 190015 94883 190015 94884 190015 94884 190016 94883 190016 94886 190016 94884 190017 94886 190017 94885 190017 94885 190018 94886 190018 94887 190018 94885 190019 94887 190019 94888 190019 94888 190020 94887 190020 94889 190020 94888 190021 94889 190021 94891 190021 94891 190022 94889 190022 94890 190022 94891 190023 94890 190023 94892 190023 94892 190024 94890 190024 94894 190024 94892 190025 94894 190025 94893 190025 94893 190026 94894 190026 94896 190026 94893 190027 94896 190027 94895 190027 94895 190028 94896 190028 96239 190028 94895 190029 96239 190029 94897 190029 94897 190030 96239 190030 94899 190030 94897 190031 94899 190031 94898 190031 94898 190032 94899 190032 96240 190032 94898 190033 96240 190033 94879 190033 94879 190034 96240 190034 94880 190034 93407 190035 94900 190035 93408 190035 93408 190036 94900 190036 94381 190036 93408 190037 94381 190037 94901 190037 94901 190038 94381 190038 94902 190038 94901 190039 94902 190039 94903 190039 94903 190040 94902 190040 94904 190040 94903 190041 94904 190041 93398 190041 93398 190042 94904 190042 94362 190042 93398 190043 94362 190043 93399 190043 93399 190044 94362 190044 94361 190044 93399 190045 94361 190045 94905 190045 94905 190046 94361 190046 94372 190046 94905 190047 94372 190047 93400 190047 93400 190048 94372 190048 94371 190048 93400 190049 94371 190049 94906 190049 94906 190050 94371 190050 94370 190050 94906 190051 94370 190051 93402 190051 93402 190052 94370 190052 94388 190052 93402 190053 94388 190053 94907 190053 94907 190054 94388 190054 94909 190054 94907 190055 94909 190055 94908 190055 94908 190056 94909 190056 94910 190056 94908 190057 94910 190057 93407 190057 93407 190058 94910 190058 94900 190058 94911 190059 96231 190059 96740 190059 96740 190060 96231 190060 96233 190060 96740 190061 96233 190061 96741 190061 96741 190062 96233 190062 94913 190062 96741 190063 94913 190063 94912 190063 94912 190064 94913 190064 94914 190064 94912 190065 94914 190065 94915 190065 94915 190066 94914 190066 94917 190066 94915 190067 94917 190067 94916 190067 94916 190068 94917 190068 96226 190068 94916 190069 96226 190069 96742 190069 96742 190070 96226 190070 94918 190070 96742 190071 94918 190071 96743 190071 96743 190072 94918 190072 94919 190072 96743 190073 94919 190073 96737 190073 96737 190074 94919 190074 96229 190074 96737 190075 96229 190075 94920 190075 94920 190076 96229 190076 94921 190076 94920 190077 94921 190077 96739 190077 96739 190078 94921 190078 94922 190078 96739 190079 94922 190079 94923 190079 94923 190080 94922 190080 94924 190080 94923 190081 94924 190081 94911 190081 94911 190082 94924 190082 96231 190082 94934 190083 94385 190083 94925 190083 94925 190084 94385 190084 94377 190084 94925 190085 94377 190085 94926 190085 94926 190086 94377 190086 94369 190086 94926 190087 94369 190087 93409 190087 93409 190088 94369 190088 94368 190088 93409 190089 94368 190089 94927 190089 94927 190090 94368 190090 94366 190090 94927 190091 94366 190091 93410 190091 93410 190092 94366 190092 94364 190092 93410 190093 94364 190093 94928 190093 94928 190094 94364 190094 94373 190094 94928 190095 94373 190095 93413 190095 93413 190096 94373 190096 94929 190096 93413 190097 94929 190097 93415 190097 93415 190098 94929 190098 94360 190098 93415 190099 94360 190099 94930 190099 94930 190100 94360 190100 94931 190100 94930 190101 94931 190101 93417 190101 93417 190102 94931 190102 94932 190102 93417 190103 94932 190103 93419 190103 93419 190104 94932 190104 94933 190104 93419 190105 94933 190105 94934 190105 94934 190106 94933 190106 94385 190106 94943 190107 96211 190107 94935 190107 94935 190108 96211 190108 96212 190108 94935 190109 96212 190109 96725 190109 96725 190110 96212 190110 94936 190110 96725 190111 94936 190111 96726 190111 96726 190112 94936 190112 96214 190112 96726 190113 96214 190113 94937 190113 94937 190114 96214 190114 96215 190114 94937 190115 96215 190115 94938 190115 94938 190116 96215 190116 96217 190116 94938 190117 96217 190117 94939 190117 94939 190118 96217 190118 96220 190118 94939 190119 96220 190119 94940 190119 94940 190120 96220 190120 96221 190120 94940 190121 96221 190121 96728 190121 96728 190122 96221 190122 96222 190122 96728 190123 96222 190123 96724 190123 96724 190124 96222 190124 94941 190124 96724 190125 94941 190125 96723 190125 96723 190126 94941 190126 94942 190126 96723 190127 94942 190127 96722 190127 96722 190128 94942 190128 96209 190128 96722 190129 96209 190129 94943 190129 94943 190130 96209 190130 96211 190130 93432 190131 94384 190131 93420 190131 93420 190132 94384 190132 94383 190132 93420 190133 94383 190133 94944 190133 94944 190134 94383 190134 94382 190134 94944 190135 94382 190135 94945 190135 94945 190136 94382 190136 94946 190136 94945 190137 94946 190137 93423 190137 93423 190138 94946 190138 94379 190138 93423 190139 94379 190139 93424 190139 93424 190140 94379 190140 94947 190140 93424 190141 94947 190141 94948 190141 94948 190142 94947 190142 94357 190142 94948 190143 94357 190143 94949 190143 94949 190144 94357 190144 94363 190144 94949 190145 94363 190145 93426 190145 93426 190146 94363 190146 94365 190146 93426 190147 94365 190147 93428 190147 93428 190148 94365 190148 94950 190148 93428 190149 94950 190149 94951 190149 94951 190150 94950 190150 94367 190150 94951 190151 94367 190151 93431 190151 93431 190152 94367 190152 94378 190152 93431 190153 94378 190153 93432 190153 93432 190154 94378 190154 94384 190154 96594 190155 94974 190155 96690 190155 96690 190156 94974 190156 94976 190156 96690 190157 94976 190157 96691 190157 96691 190158 94976 190158 94977 190158 96691 190159 94977 190159 94953 190159 94953 190160 94977 190160 94952 190160 94953 190161 94952 190161 96669 190161 96669 190162 94952 190162 94954 190162 96669 190163 94954 190163 96670 190163 96670 190164 94954 190164 94955 190164 96670 190165 94955 190165 94956 190165 94956 190166 94955 190166 94957 190166 94956 190167 94957 190167 94958 190167 94958 190168 94957 190168 94959 190168 94958 190169 94959 190169 94960 190169 94960 190170 94959 190170 94982 190170 94960 190171 94982 190171 96595 190171 96595 190172 94982 190172 94961 190172 96595 190173 94961 190173 96807 190173 96807 190174 94961 190174 94962 190174 96807 190175 94962 190175 94963 190175 94963 190176 94962 190176 94985 190176 94963 190177 94985 190177 96594 190177 96594 190178 94985 190178 94974 190178 94993 190179 94964 190179 94965 190179 94965 190180 94964 190180 94980 190180 94965 190181 94980 190181 94991 190181 94991 190182 94980 190182 94979 190182 94991 190183 94979 190183 94989 190183 94989 190184 94979 190184 94978 190184 94989 190185 94978 190185 94988 190185 94988 190186 94978 190186 94967 190186 94988 190187 94967 190187 94966 190187 94966 190188 94967 190188 94968 190188 94966 190189 94968 190189 94987 190189 94987 190190 94968 190190 94975 190190 94987 190191 94975 190191 94986 190191 94986 190192 94975 190192 94984 190192 94986 190193 94984 190193 94969 190193 94969 190194 94984 190194 94983 190194 94969 190195 94983 190195 94970 190195 94970 190196 94983 190196 94971 190196 94970 190197 94971 190197 94994 190197 94994 190198 94971 190198 94972 190198 94994 190199 94972 190199 94973 190199 94973 190200 94972 190200 94981 190200 94973 190201 94981 190201 94993 190201 94993 190202 94981 190202 94964 190202 94985 190203 94975 190203 94974 190203 94974 190204 94975 190204 94968 190204 94974 190205 94968 190205 94976 190205 94976 190206 94968 190206 94967 190206 94976 190207 94967 190207 94977 190207 94977 190208 94967 190208 94978 190208 94977 190209 94978 190209 94952 190209 94952 190210 94978 190210 94979 190210 94952 190211 94979 190211 94954 190211 94954 190212 94979 190212 94980 190212 94954 190213 94980 190213 94955 190213 94955 190214 94980 190214 94964 190214 94955 190215 94964 190215 94957 190215 94957 190216 94964 190216 94981 190216 94957 190217 94981 190217 94959 190217 94959 190218 94981 190218 94972 190218 94959 190219 94972 190219 94982 190219 94982 190220 94972 190220 94971 190220 94982 190221 94971 190221 94961 190221 94961 190222 94971 190222 94983 190222 94961 190223 94983 190223 94962 190223 94962 190224 94983 190224 94984 190224 94962 190225 94984 190225 94985 190225 94985 190226 94984 190226 94975 190226 94986 190227 94997 190227 94987 190227 94987 190228 94997 190228 94051 190228 94987 190229 94051 190229 94966 190229 94966 190230 94051 190230 94050 190230 94966 190231 94050 190231 94988 190231 94988 190232 94050 190232 94057 190232 94988 190233 94057 190233 94989 190233 94989 190234 94057 190234 94990 190234 94989 190235 94990 190235 94991 190235 94991 190236 94990 190236 94055 190236 94991 190237 94055 190237 94965 190237 94965 190238 94055 190238 94484 190238 94965 190239 94484 190239 94993 190239 94993 190240 94484 190240 94992 190240 94993 190241 94992 190241 94973 190241 94973 190242 94992 190242 94054 190242 94973 190243 94054 190243 94994 190243 94994 190244 94054 190244 94053 190244 94994 190245 94053 190245 94970 190245 94970 190246 94053 190246 94995 190246 94970 190247 94995 190247 94969 190247 94969 190248 94995 190248 94996 190248 94969 190249 94996 190249 94986 190249 94986 190250 94996 190250 94997 190250 94998 190251 94999 190251 95000 190251 95000 190252 94999 190252 93992 190252 95000 190253 93992 190253 95001 190253 95001 190254 93992 190254 94114 190254 95001 190255 94114 190255 95002 190255 95002 190256 94114 190256 94125 190256 95002 190257 94125 190257 95003 190257 95003 190258 94125 190258 95004 190258 95003 190259 95004 190259 93464 190259 93464 190260 95004 190260 93988 190260 93464 190261 93988 190261 93465 190261 93465 190262 93988 190262 93990 190262 93465 190263 93990 190263 95005 190263 95005 190264 93990 190264 93991 190264 95005 190265 93991 190265 93467 190265 93467 190266 93991 190266 93987 190266 93467 190267 93987 190267 95006 190267 95006 190268 93987 190268 93993 190268 95006 190269 93993 190269 93469 190269 93469 190270 93993 190270 93994 190270 93469 190271 93994 190271 95007 190271 95007 190272 93994 190272 93995 190272 95007 190273 93995 190273 94998 190273 94998 190274 93995 190274 94999 190274 93447 190275 95008 190275 93448 190275 93448 190276 95008 190276 95009 190276 93448 190277 95009 190277 93449 190277 93449 190278 95009 190278 94002 190278 93449 190279 94002 190279 93450 190279 93450 190280 94002 190280 95010 190280 93450 190281 95010 190281 95012 190281 95012 190282 95010 190282 95011 190282 95012 190283 95011 190283 93451 190283 93451 190284 95011 190284 93997 190284 93451 190285 93997 190285 93453 190285 93453 190286 93997 190286 95013 190286 93453 190287 95013 190287 93454 190287 93454 190288 95013 190288 94001 190288 93454 190289 94001 190289 93456 190289 93456 190290 94001 190290 95015 190290 93456 190291 95015 190291 95014 190291 95014 190292 95015 190292 93999 190292 95014 190293 93999 190293 95016 190293 95016 190294 93999 190294 95017 190294 95016 190295 95017 190295 93445 190295 93445 190296 95017 190296 94397 190296 93445 190297 94397 190297 93447 190297 93447 190298 94397 190298 95008 190298 95066 190299 95018 190299 95019 190299 95019 190300 95018 190300 95045 190300 95019 190301 95045 190301 95020 190301 95020 190302 95045 190302 95042 190302 95020 190303 95042 190303 95021 190303 95021 190304 95042 190304 95041 190304 95021 190305 95041 190305 95022 190305 95022 190306 95041 190306 95023 190306 95022 190307 95023 190307 95063 190307 95063 190308 95023 190308 95040 190308 95063 190309 95040 190309 95062 190309 95062 190310 95040 190310 95024 190310 95062 190311 95024 190311 95060 190311 95060 190312 95024 190312 95025 190312 95060 190313 95025 190313 95059 190313 95059 190314 95025 190314 95050 190314 95059 190315 95050 190315 95056 190315 95056 190316 95050 190316 95026 190316 95056 190317 95026 190317 95069 190317 95069 190318 95026 190318 95049 190318 95069 190319 95049 190319 95027 190319 95027 190320 95049 190320 95048 190320 95027 190321 95048 190321 95066 190321 95066 190322 95048 190322 95018 190322 95039 190323 95028 190323 95030 190323 95030 190324 95028 190324 95029 190324 95030 190325 95029 190325 96597 190325 96597 190326 95029 190326 95032 190326 96597 190327 95032 190327 95031 190327 95031 190328 95032 190328 95043 190328 95031 190329 95043 190329 95033 190329 95033 190330 95043 190330 95044 190330 95033 190331 95044 190331 96599 190331 96599 190332 95044 190332 95046 190332 96599 190333 95046 190333 96598 190333 96598 190334 95046 190334 95047 190334 96598 190335 95047 190335 95034 190335 95034 190336 95047 190336 95035 190336 95034 190337 95035 190337 96707 190337 96707 190338 95035 190338 95036 190338 96707 190339 95036 190339 96708 190339 96708 190340 95036 190340 95051 190340 96708 190341 95051 190341 95037 190341 95037 190342 95051 190342 95052 190342 95037 190343 95052 190343 95038 190343 95038 190344 95052 190344 95053 190344 95038 190345 95053 190345 95039 190345 95039 190346 95053 190346 95028 190346 95053 190347 95024 190347 95028 190347 95028 190348 95024 190348 95040 190348 95028 190349 95040 190349 95029 190349 95029 190350 95040 190350 95023 190350 95029 190351 95023 190351 95032 190351 95032 190352 95023 190352 95041 190352 95032 190353 95041 190353 95043 190353 95043 190354 95041 190354 95042 190354 95043 190355 95042 190355 95044 190355 95044 190356 95042 190356 95045 190356 95044 190357 95045 190357 95046 190357 95046 190358 95045 190358 95018 190358 95046 190359 95018 190359 95047 190359 95047 190360 95018 190360 95048 190360 95047 190361 95048 190361 95035 190361 95035 190362 95048 190362 95049 190362 95035 190363 95049 190363 95036 190363 95036 190364 95049 190364 95026 190364 95036 190365 95026 190365 95051 190365 95051 190366 95026 190366 95050 190366 95051 190367 95050 190367 95052 190367 95052 190368 95050 190368 95025 190368 95052 190369 95025 190369 95053 190369 95053 190370 95025 190370 95024 190370 95054 190371 95055 190371 95056 190371 95056 190372 95055 190372 95057 190372 95056 190373 95057 190373 95059 190373 95059 190374 95057 190374 95058 190374 95059 190375 95058 190375 95060 190375 95060 190376 95058 190376 94058 190376 95060 190377 94058 190377 95062 190377 95062 190378 94058 190378 95061 190378 95062 190379 95061 190379 95063 190379 95063 190380 95061 190380 95064 190380 95063 190381 95064 190381 95022 190381 95022 190382 95064 190382 95065 190382 95022 190383 95065 190383 95021 190383 95021 190384 95065 190384 94060 190384 95021 190385 94060 190385 95020 190385 95020 190386 94060 190386 94110 190386 95020 190387 94110 190387 95019 190387 95019 190388 94110 190388 94109 190388 95019 190389 94109 190389 95066 190389 95066 190390 94109 190390 95067 190390 95066 190391 95067 190391 95027 190391 95027 190392 95067 190392 95068 190392 95027 190393 95068 190393 95069 190393 95069 190394 95068 190394 95054 190394 95069 190395 95054 190395 95056 190395 93969 190396 95070 190396 93494 190396 93494 190397 95070 190397 93976 190397 93494 190398 93976 190398 95071 190398 95071 190399 93976 190399 93973 190399 95071 190400 93973 190400 95072 190400 95072 190401 93973 190401 93972 190401 95072 190402 93972 190402 93485 190402 93485 190403 93972 190403 94115 190403 93485 190404 94115 190404 93487 190404 93487 190405 94115 190405 93975 190405 93487 190406 93975 190406 93488 190406 93488 190407 93975 190407 95073 190407 93488 190408 95073 190408 95074 190408 95074 190409 95073 190409 95076 190409 95074 190410 95076 190410 95075 190410 95075 190411 95076 190411 93962 190411 95075 190412 93962 190412 93490 190412 93490 190413 93962 190413 93968 190413 93490 190414 93968 190414 95077 190414 95077 190415 93968 190415 95078 190415 95077 190416 95078 190416 93492 190416 93492 190417 95078 190417 95079 190417 93492 190418 95079 190418 95080 190418 95080 190419 95079 190419 93969 190419 95080 190420 93969 190420 93494 190420 95081 190421 95082 190421 95083 190421 95083 190422 95082 190422 95084 190422 95083 190423 95084 190423 93479 190423 93479 190424 95084 190424 95085 190424 93479 190425 95085 190425 93480 190425 93480 190426 95085 190426 95087 190426 93480 190427 95087 190427 95086 190427 95086 190428 95087 190428 94487 190428 95086 190429 94487 190429 93482 190429 93482 190430 94487 190430 95088 190430 93482 190431 95088 190431 95089 190431 95089 190432 95088 190432 95090 190432 95089 190433 95090 190433 95091 190433 95091 190434 95090 190434 93985 190434 95091 190435 93985 190435 93472 190435 93472 190436 93985 190436 95092 190436 93472 190437 95092 190437 93473 190437 93473 190438 95092 190438 93986 190438 93473 190439 93986 190439 95093 190439 95093 190440 93986 190440 93983 190440 95093 190441 93983 190441 95094 190441 95094 190442 93983 190442 93982 190442 95094 190443 93982 190443 95095 190443 95095 190444 93982 190444 95081 190444 95095 190445 95081 190445 95083 190445 95107 190446 95126 190446 95096 190446 95096 190447 95126 190447 95125 190447 95096 190448 95125 190448 95097 190448 95097 190449 95125 190449 95123 190449 95097 190450 95123 190450 95098 190450 95098 190451 95123 190451 95122 190451 95098 190452 95122 190452 95099 190452 95099 190453 95122 190453 95121 190453 95099 190454 95121 190454 95100 190454 95100 190455 95121 190455 95101 190455 95100 190456 95101 190456 95134 190456 95134 190457 95101 190457 95102 190457 95134 190458 95102 190458 95133 190458 95133 190459 95102 190459 95132 190459 95133 190460 95132 190460 95103 190460 95103 190461 95132 190461 95104 190461 95103 190462 95104 190462 95105 190462 95105 190463 95104 190463 95106 190463 95105 190464 95106 190464 95143 190464 95143 190465 95106 190465 95129 190465 95143 190466 95129 190466 95140 190466 95140 190467 95129 190467 95127 190467 95140 190468 95127 190468 95107 190468 95107 190469 95127 190469 95126 190469 96602 190470 95120 190470 95108 190470 95108 190471 95120 190471 95109 190471 95108 190472 95109 190472 96593 190472 96593 190473 95109 190473 95110 190473 96593 190474 95110 190474 95111 190474 95111 190475 95110 190475 95124 190475 95111 190476 95124 190476 95112 190476 95112 190477 95124 190477 95114 190477 95112 190478 95114 190478 95113 190478 95113 190479 95114 190479 95116 190479 95113 190480 95116 190480 95115 190480 95115 190481 95116 190481 95117 190481 95115 190482 95117 190482 96781 190482 96781 190483 95117 190483 95128 190483 96781 190484 95128 190484 96606 190484 96606 190485 95128 190485 95130 190485 96606 190486 95130 190486 96605 190486 96605 190487 95130 190487 95118 190487 96605 190488 95118 190488 96604 190488 96604 190489 95118 190489 95131 190489 96604 190490 95131 190490 96603 190490 96603 190491 95131 190491 95119 190491 96603 190492 95119 190492 96602 190492 96602 190493 95119 190493 95120 190493 95119 190494 95102 190494 95120 190494 95120 190495 95102 190495 95101 190495 95120 190496 95101 190496 95109 190496 95109 190497 95101 190497 95121 190497 95109 190498 95121 190498 95110 190498 95110 190499 95121 190499 95122 190499 95110 190500 95122 190500 95124 190500 95124 190501 95122 190501 95123 190501 95124 190502 95123 190502 95114 190502 95114 190503 95123 190503 95125 190503 95114 190504 95125 190504 95116 190504 95116 190505 95125 190505 95126 190505 95116 190506 95126 190506 95117 190506 95117 190507 95126 190507 95127 190507 95117 190508 95127 190508 95128 190508 95128 190509 95127 190509 95129 190509 95128 190510 95129 190510 95130 190510 95130 190511 95129 190511 95106 190511 95130 190512 95106 190512 95118 190512 95118 190513 95106 190513 95104 190513 95118 190514 95104 190514 95131 190514 95131 190515 95104 190515 95132 190515 95131 190516 95132 190516 95119 190516 95119 190517 95132 190517 95102 190517 95133 190518 94065 190518 95134 190518 95134 190519 94065 190519 95135 190519 95134 190520 95135 190520 95100 190520 95100 190521 95135 190521 94064 190521 95100 190522 94064 190522 95099 190522 95099 190523 94064 190523 95136 190523 95099 190524 95136 190524 95098 190524 95098 190525 95136 190525 95137 190525 95098 190526 95137 190526 95097 190526 95097 190527 95137 190527 95138 190527 95097 190528 95138 190528 95096 190528 95096 190529 95138 190529 95139 190529 95096 190530 95139 190530 95107 190530 95107 190531 95139 190531 95141 190531 95107 190532 95141 190532 95140 190532 95140 190533 95141 190533 95142 190533 95140 190534 95142 190534 95143 190534 95143 190535 95142 190535 95144 190535 95143 190536 95144 190536 95105 190536 95105 190537 95144 190537 94066 190537 95105 190538 94066 190538 95103 190538 95103 190539 94066 190539 95145 190539 95103 190540 95145 190540 95133 190540 95133 190541 95145 190541 94065 190541 95157 190542 95146 190542 95147 190542 95147 190543 95146 190543 94275 190543 95147 190544 94275 190544 93509 190544 93509 190545 94275 190545 95148 190545 93509 190546 95148 190546 95149 190546 95149 190547 95148 190547 95151 190547 95149 190548 95151 190548 95150 190548 95150 190549 95151 190549 93949 190549 95150 190550 93949 190550 95152 190550 95152 190551 93949 190551 94482 190551 95152 190552 94482 190552 93512 190552 93512 190553 94482 190553 95153 190553 93512 190554 95153 190554 93513 190554 93513 190555 95153 190555 95154 190555 93513 190556 95154 190556 93516 190556 93516 190557 95154 190557 95155 190557 93516 190558 95155 190558 93518 190558 93518 190559 95155 190559 93952 190559 93518 190560 93952 190560 93519 190560 93519 190561 93952 190561 95156 190561 93519 190562 95156 190562 93508 190562 93508 190563 95156 190563 95158 190563 93508 190564 95158 190564 95157 190564 95157 190565 95158 190565 95146 190565 93497 190566 93958 190566 95159 190566 95159 190567 93958 190567 93957 190567 95159 190568 93957 190568 95160 190568 95160 190569 93957 190569 95161 190569 95160 190570 95161 190570 93499 190570 93499 190571 95161 190571 93953 190571 93499 190572 93953 190572 95162 190572 95162 190573 93953 190573 95163 190573 95162 190574 95163 190574 93501 190574 93501 190575 95163 190575 93956 190575 93501 190576 93956 190576 93503 190576 93503 190577 93956 190577 95164 190577 93503 190578 95164 190578 95165 190578 95165 190579 95164 190579 95166 190579 95165 190580 95166 190580 93504 190580 93504 190581 95166 190581 93954 190581 93504 190582 93954 190582 95167 190582 95167 190583 93954 190583 95168 190583 95167 190584 95168 190584 93506 190584 93506 190585 95168 190585 95169 190585 93506 190586 95169 190586 95170 190586 95170 190587 95169 190587 93959 190587 95170 190588 93959 190588 93497 190588 93497 190589 93959 190589 93958 190589 95184 190590 95185 190590 95171 190590 95171 190591 95185 190591 95203 190591 95171 190592 95203 190592 95172 190592 95172 190593 95203 190593 95205 190593 95172 190594 95205 190594 95173 190594 95173 190595 95205 190595 95206 190595 95173 190596 95206 190596 96608 190596 96608 190597 95206 190597 95174 190597 96608 190598 95174 190598 95175 190598 95175 190599 95174 190599 95176 190599 95175 190600 95176 190600 95177 190600 95177 190601 95176 190601 95179 190601 95177 190602 95179 190602 95178 190602 95178 190603 95179 190603 95208 190603 95178 190604 95208 190604 95180 190604 95180 190605 95208 190605 95209 190605 95180 190606 95209 190606 96636 190606 96636 190607 95209 190607 95181 190607 96636 190608 95181 190608 96607 190608 96607 190609 95181 190609 95182 190609 96607 190610 95182 190610 95183 190610 95183 190611 95182 190611 95202 190611 95183 190612 95202 190612 95184 190612 95184 190613 95202 190613 95185 190613 95211 190614 95186 190614 95220 190614 95220 190615 95186 190615 95187 190615 95220 190616 95187 190616 95188 190616 95188 190617 95187 190617 95207 190617 95188 190618 95207 190618 95216 190618 95216 190619 95207 190619 95189 190619 95216 190620 95189 190620 95190 190620 95190 190621 95189 190621 95204 190621 95190 190622 95204 190622 95191 190622 95191 190623 95204 190623 95192 190623 95191 190624 95192 190624 95193 190624 95193 190625 95192 190625 95195 190625 95193 190626 95195 190626 95194 190626 95194 190627 95195 190627 95196 190627 95194 190628 95196 190628 95197 190628 95197 190629 95196 190629 95198 190629 95197 190630 95198 190630 95213 190630 95213 190631 95198 190631 95210 190631 95213 190632 95210 190632 95199 190632 95199 190633 95210 190633 95200 190633 95199 190634 95200 190634 95212 190634 95212 190635 95200 190635 95201 190635 95212 190636 95201 190636 95211 190636 95211 190637 95201 190637 95186 190637 95202 190638 95195 190638 95185 190638 95185 190639 95195 190639 95192 190639 95185 190640 95192 190640 95203 190640 95203 190641 95192 190641 95204 190641 95203 190642 95204 190642 95205 190642 95205 190643 95204 190643 95189 190643 95205 190644 95189 190644 95206 190644 95206 190645 95189 190645 95207 190645 95206 190646 95207 190646 95174 190646 95174 190647 95207 190647 95187 190647 95174 190648 95187 190648 95176 190648 95176 190649 95187 190649 95186 190649 95176 190650 95186 190650 95179 190650 95179 190651 95186 190651 95201 190651 95179 190652 95201 190652 95208 190652 95208 190653 95201 190653 95200 190653 95208 190654 95200 190654 95209 190654 95209 190655 95200 190655 95210 190655 95209 190656 95210 190656 95181 190656 95181 190657 95210 190657 95198 190657 95181 190658 95198 190658 95182 190658 95182 190659 95198 190659 95196 190659 95182 190660 95196 190660 95202 190660 95202 190661 95196 190661 95195 190661 95221 190662 94078 190662 95211 190662 95211 190663 94078 190663 94308 190663 95211 190664 94308 190664 95212 190664 95212 190665 94308 190665 94074 190665 95212 190666 94074 190666 95199 190666 95199 190667 94074 190667 94075 190667 95199 190668 94075 190668 95213 190668 95213 190669 94075 190669 94071 190669 95213 190670 94071 190670 95197 190670 95197 190671 94071 190671 94070 190671 95197 190672 94070 190672 95194 190672 95194 190673 94070 190673 94069 190673 95194 190674 94069 190674 95193 190674 95193 190675 94069 190675 95214 190675 95193 190676 95214 190676 95191 190676 95191 190677 95214 190677 95215 190677 95191 190678 95215 190678 95190 190678 95190 190679 95215 190679 95217 190679 95190 190680 95217 190680 95216 190680 95216 190681 95217 190681 95218 190681 95216 190682 95218 190682 95188 190682 95188 190683 95218 190683 95219 190683 95188 190684 95219 190684 95220 190684 95220 190685 95219 190685 95221 190685 95220 190686 95221 190686 95211 190686 93925 190687 93928 190687 93543 190687 93543 190688 93928 190688 95222 190688 93543 190689 95222 190689 93544 190689 93544 190690 95222 190690 94271 190690 93544 190691 94271 190691 93545 190691 93545 190692 94271 190692 95223 190692 93545 190693 95223 190693 93547 190693 93547 190694 95223 190694 93934 190694 93547 190695 93934 190695 93548 190695 93548 190696 93934 190696 95225 190696 93548 190697 95225 190697 95224 190697 95224 190698 95225 190698 95226 190698 95224 190699 95226 190699 93534 190699 93534 190700 95226 190700 95227 190700 93534 190701 95227 190701 95228 190701 95228 190702 95227 190702 93923 190702 95228 190703 93923 190703 93537 190703 93537 190704 93923 190704 95229 190704 93537 190705 95229 190705 93538 190705 93538 190706 95229 190706 95230 190706 93538 190707 95230 190707 95231 190707 95231 190708 95230 190708 94292 190708 95231 190709 94292 190709 93541 190709 93541 190710 94292 190710 93925 190710 93541 190711 93925 190711 93543 190711 95246 190712 93939 190712 93529 190712 93529 190713 93939 190713 95232 190713 93529 190714 95232 190714 93530 190714 93530 190715 95232 190715 93948 190715 93530 190716 93948 190716 93533 190716 93533 190717 93948 190717 95234 190717 93533 190718 95234 190718 95233 190718 95233 190719 95234 190719 95235 190719 95233 190720 95235 190720 95236 190720 95236 190721 95235 190721 95237 190721 95236 190722 95237 190722 93523 190722 93523 190723 95237 190723 93946 190723 93523 190724 93946 190724 93524 190724 93524 190725 93946 190725 95238 190725 93524 190726 95238 190726 95239 190726 95239 190727 95238 190727 95240 190727 95239 190728 95240 190728 95241 190728 95241 190729 95240 190729 95242 190729 95241 190730 95242 190730 93525 190730 93525 190731 95242 190731 95243 190731 93525 190732 95243 190732 95244 190732 95244 190733 95243 190733 93943 190733 95244 190734 93943 190734 95245 190734 95245 190735 93943 190735 95246 190735 95245 190736 95246 190736 93529 190736 95247 190737 95941 190737 95248 190737 95247 190738 95248 190738 95833 190738 95833 190739 95248 190739 95946 190739 95833 190740 95946 190740 95249 190740 95249 190741 95946 190741 95945 190741 95249 190742 95945 190742 95832 190742 95841 190743 94504 190743 95892 190743 95841 190744 95892 190744 95842 190744 95842 190745 95892 190745 95250 190745 95842 190746 95250 190746 95843 190746 95843 190747 95250 190747 95251 190747 95843 190748 95251 190748 94514 190748 95253 190749 95827 190749 95252 190749 95253 190750 95252 190750 95853 190750 95853 190751 95252 190751 95255 190751 95853 190752 95255 190752 95254 190752 95254 190753 95255 190753 94525 190753 95254 190754 94525 190754 95863 190754 94521 190755 95256 190755 95904 190755 95904 190756 95256 190756 95257 190756 95256 190757 95818 190757 95257 190757 95257 190758 95818 190758 95817 190758 95257 190759 95817 190759 95261 190759 95258 190760 94491 190760 95259 190760 95259 190761 94491 190761 95261 190761 95259 190762 95261 190762 95260 190762 95260 190763 95261 190763 95817 190763 95763 190764 94551 190764 95265 190764 94501 190765 94502 190765 95262 190765 95262 190766 94502 190766 95263 190766 95262 190767 95263 190767 95829 190767 95829 190768 95263 190768 94546 190768 94546 190769 95263 190769 95265 190769 95265 190770 95263 190770 95264 190770 95265 190771 95264 190771 95763 190771 94568 190772 95809 190772 95267 190772 94568 190773 95267 190773 95266 190773 95266 190774 95267 190774 95807 190774 95266 190775 95807 190775 94569 190775 94569 190776 95807 190776 95268 190776 94569 190777 95268 190777 95269 190777 95269 190778 95268 190778 95821 190778 95821 190779 95268 190779 95796 190779 95821 190780 95796 190780 95822 190780 95270 190781 95271 190781 95831 190781 95831 190782 95271 190782 95273 190782 95831 190783 95273 190783 95272 190783 95272 190784 95273 190784 95791 190784 95272 190785 95791 190785 95830 190785 95830 190786 95791 190786 95790 190786 95830 190787 95790 190787 94555 190787 94555 190788 95790 190788 95784 190788 94555 190789 95784 190789 94559 190789 95744 190790 95750 190790 95274 190790 95274 190791 95750 190791 94541 190791 94541 190792 95750 190792 94539 190792 94539 190793 95750 190793 95749 190793 94539 190794 95749 190794 95275 190794 95275 190795 95749 190795 95277 190795 95277 190796 95749 190796 95276 190796 95277 190797 95276 190797 94500 190797 95278 190798 95977 190798 95949 190798 95949 190799 95977 190799 95279 190799 95952 190800 95951 190800 95280 190800 95280 190801 95951 190801 95949 190801 95280 190802 95949 190802 95281 190802 95281 190803 95949 190803 95279 190803 95281 190804 95279 190804 95953 190804 93553 190805 95282 190805 95970 190805 95970 190806 95282 190806 95283 190806 95973 190807 95970 190807 95284 190807 95284 190808 95970 190808 95283 190808 95284 190809 95283 190809 95285 190809 95285 190810 95283 190810 94493 190810 95285 190811 94493 190811 94492 190811 95286 190812 95966 190812 95287 190812 95287 190813 95966 190813 95957 190813 94503 190814 95852 190814 95288 190814 95288 190815 95852 190815 95287 190815 95288 190816 95287 190816 95956 190816 95956 190817 95287 190817 95957 190817 95956 190818 95957 190818 95959 190818 95969 190819 95875 190819 95962 190819 95962 190820 95875 190820 95878 190820 95955 190821 95962 190821 95954 190821 95954 190822 95962 190822 95878 190822 95954 190823 95878 190823 95289 190823 95289 190824 95878 190824 95886 190824 95289 190825 95886 190825 95290 190825 95296 190826 93187 190826 95291 190826 95291 190827 93187 190827 95292 190827 95291 190828 95292 190828 94338 190828 94338 190829 95292 190829 94339 190829 95293 190830 94344 190830 95294 190830 95294 190831 94344 190831 94340 190831 95294 190832 94340 190832 93571 190832 93571 190833 94340 190833 95295 190833 93571 190834 95295 190834 95292 190834 95292 190835 95295 190835 94339 190835 93187 190836 95296 190836 95297 190836 95297 190837 95296 190837 94348 190837 95297 190838 94348 190838 93869 190838 93869 190839 94348 190839 95298 190839 93869 190840 95298 190840 93871 190840 93871 190841 95298 190841 94351 190841 93871 190842 94351 190842 93564 190842 93564 190843 94351 190843 95300 190843 95299 190844 94345 190844 95293 190844 95293 190845 94345 190845 94344 190845 94350 190846 93874 190846 95300 190846 95300 190847 93874 190847 93564 190847 93186 190848 94342 190848 93696 190848 93696 190849 94342 190849 94341 190849 93696 190850 94341 190850 95301 190850 95301 190851 94341 190851 94337 190851 95301 190852 94337 190852 93694 190852 93694 190853 94337 190853 94347 190853 93694 190854 94347 190854 95299 190854 95299 190855 94347 190855 94345 190855 93874 190856 94350 190856 95302 190856 95302 190857 94350 190857 94353 190857 95302 190858 94353 190858 93872 190858 93872 190859 94353 190859 95303 190859 93872 190860 95303 190860 93184 190860 93184 190861 95303 190861 95304 190861 93184 190862 95304 190862 95305 190862 93184 190863 95305 190863 93186 190863 93186 190864 95305 190864 95306 190864 93186 190865 95306 190865 94342 190865 94327 190866 95308 190866 95307 190866 95307 190867 95308 190867 95310 190867 95307 190868 95310 190868 95309 190868 95309 190869 95310 190869 94321 190869 95311 190870 95318 190870 93578 190870 93578 190871 95318 190871 95312 190871 93578 190872 95312 190872 93580 190872 93580 190873 95312 190873 95313 190873 93580 190874 95313 190874 95310 190874 95310 190875 95313 190875 94321 190875 95308 190876 94327 190876 93860 190876 93860 190877 94327 190877 94326 190877 93860 190878 94326 190878 95314 190878 95314 190879 94326 190879 94325 190879 95314 190880 94325 190880 93862 190880 93862 190881 94325 190881 94324 190881 93862 190882 94324 190882 93863 190882 93863 190883 94324 190883 95315 190883 95316 190884 95317 190884 95311 190884 95311 190885 95317 190885 95318 190885 94329 190886 95319 190886 95315 190886 95315 190887 95319 190887 93863 190887 93575 190888 94331 190888 95320 190888 95320 190889 94331 190889 95321 190889 95320 190890 95321 190890 93573 190890 93573 190891 95321 190891 95322 190891 93573 190892 95322 190892 95316 190892 95316 190893 95322 190893 95317 190893 95319 190894 94329 190894 93866 190894 93866 190895 94329 190895 94336 190895 93866 190896 94336 190896 93865 190896 93865 190897 94336 190897 95323 190897 93865 190898 95323 190898 93188 190898 93188 190899 95323 190899 94334 190899 93188 190900 94334 190900 94333 190900 93188 190901 94333 190901 93575 190901 93575 190902 94333 190902 94332 190902 93575 190903 94332 190903 94331 190903 93938 190904 95331 190904 95324 190904 95324 190905 95331 190905 95327 190905 95324 190906 95327 190906 95325 190906 95325 190907 95327 190907 95326 190907 94319 190908 95326 190908 95327 190908 93434 190909 94318 190909 95328 190909 95328 190910 94318 190910 94317 190910 95328 190911 94317 190911 95329 190911 95329 190912 94317 190912 94319 190912 95329 190913 94319 190913 95330 190913 95330 190914 94319 190914 95327 190914 95331 190915 93938 190915 93601 190915 93601 190916 93938 190916 95332 190916 93601 190917 95332 190917 95333 190917 95333 190918 95332 190918 93937 190918 95333 190919 93937 190919 93605 190919 93605 190920 93937 190920 93941 190920 93605 190921 93941 190921 95334 190921 95334 190922 93941 190922 93942 190922 95342 190923 95335 190923 93434 190923 93434 190924 95335 190924 94318 190924 95343 190925 95336 190925 93942 190925 93942 190926 95336 190926 95334 190926 95346 190927 94424 190927 95337 190927 95337 190928 94424 190928 95338 190928 95337 190929 95338 190929 95339 190929 95339 190930 95338 190930 95340 190930 95339 190931 95340 190931 93613 190931 93613 190932 95340 190932 95341 190932 93613 190933 95341 190933 95342 190933 95342 190934 95341 190934 95335 190934 95336 190935 95343 190935 93607 190935 93607 190936 95343 190936 95344 190936 93607 190937 95344 190937 93608 190937 93608 190938 95344 190938 93940 190938 93608 190939 93940 190939 93610 190939 93610 190940 93940 190940 93936 190940 95345 190941 94424 190941 95346 190941 95345 190942 95346 190942 95347 190942 95347 190943 95346 190943 93610 190943 95347 190944 93610 190944 93936 190944 95354 190945 95349 190945 95348 190945 95348 190946 95349 190946 95353 190946 95348 190947 95353 190947 94310 190947 94310 190948 95353 190948 95350 190948 93222 190949 94305 190949 95351 190949 95351 190950 94305 190950 94311 190950 95351 190951 94311 190951 93600 190951 93600 190952 94311 190952 95352 190952 93600 190953 95352 190953 95353 190953 95353 190954 95352 190954 95350 190954 95349 190955 95354 190955 93587 190955 93587 190956 95354 190956 95355 190956 93587 190957 95355 190957 93588 190957 93588 190958 95355 190958 94077 190958 93588 190959 94077 190959 95356 190959 95356 190960 94077 190960 94079 190960 95356 190961 94079 190961 93590 190961 93590 190962 94079 190962 93947 190962 95360 190963 94306 190963 93222 190963 93222 190964 94306 190964 94305 190964 95361 190965 93225 190965 93947 190965 93947 190966 93225 190966 93590 190966 95368 190967 94303 190967 95357 190967 95357 190968 94303 190968 95358 190968 95357 190969 95358 190969 93596 190969 93596 190970 95358 190970 95359 190970 93596 190971 95359 190971 95360 190971 95360 190972 95359 190972 94306 190972 93225 190973 95361 190973 95362 190973 95362 190974 95361 190974 95363 190974 95362 190975 95363 190975 93593 190975 93593 190976 95363 190976 94316 190976 93593 190977 94316 190977 95364 190977 95364 190978 94316 190978 95365 190978 95364 190979 95365 190979 95366 190979 95366 190980 95365 190980 94315 190980 95366 190981 94315 190981 95367 190981 95366 190982 95367 190982 95368 190982 95368 190983 95367 190983 94312 190983 95368 190984 94312 190984 94303 190984 94296 190985 95369 190985 95370 190985 95370 190986 95369 190986 95371 190986 95370 190987 95371 190987 95372 190987 95372 190988 95371 190988 95373 190988 95373 190989 95371 190989 94298 190989 94298 190990 95371 190990 93633 190990 94298 190991 93633 190991 94300 190991 93221 190992 95377 190992 93630 190992 93630 190993 95377 190993 94300 190993 93630 190994 94300 190994 93631 190994 93631 190995 94300 190995 93633 190995 95369 190996 94296 190996 93618 190996 93618 190997 94296 190997 94295 190997 93618 190998 94295 190998 93620 190998 93620 190999 94295 190999 94294 190999 93620 191000 94294 191000 93622 191000 93622 191001 94294 191001 94072 191001 93622 191002 94072 191002 93623 191002 93623 191003 94072 191003 95374 191003 95375 191004 95376 191004 93221 191004 93221 191005 95376 191005 95377 191005 94076 191006 95378 191006 95374 191006 95374 191007 95378 191007 93623 191007 95379 191008 95387 191008 93629 191008 93629 191009 95387 191009 94293 191009 93629 191010 94293 191010 93628 191010 93628 191011 94293 191011 95380 191011 93628 191012 95380 191012 93626 191012 93626 191013 95380 191013 95381 191013 93626 191014 95381 191014 95375 191014 95375 191015 95381 191015 95376 191015 95378 191016 94076 191016 95382 191016 95382 191017 94076 191017 93921 191017 95382 191018 93921 191018 93624 191018 93624 191019 93921 191019 95383 191019 93624 191020 95383 191020 95386 191020 95386 191021 95383 191021 95384 191021 95386 191022 95384 191022 95385 191022 95386 191023 95385 191023 95379 191023 95379 191024 95385 191024 94301 191024 95379 191025 94301 191025 95387 191025 95391 191026 95388 191026 94281 191026 94281 191027 95388 191027 95389 191027 94281 191028 95389 191028 94283 191028 94283 191029 95389 191029 94285 191029 93216 191030 95397 191030 93644 191030 93644 191031 95397 191031 95390 191031 93644 191032 95390 191032 93645 191032 93645 191033 95390 191033 94287 191033 93645 191034 94287 191034 95389 191034 95389 191035 94287 191035 94285 191035 95388 191036 95391 191036 95392 191036 95392 191037 95391 191037 95393 191037 95392 191038 95393 191038 93646 191038 93646 191039 95393 191039 95394 191039 93646 191040 95394 191040 93648 191040 93648 191041 95394 191041 93930 191041 93648 191042 93930 191042 95398 191042 95398 191043 93930 191043 95395 191043 95396 191044 94280 191044 93216 191044 93216 191045 94280 191045 95397 191045 93929 191046 93217 191046 95395 191046 95395 191047 93217 191047 95398 191047 93653 191048 95406 191048 95399 191048 95399 191049 95406 191049 95401 191049 95399 191050 95401 191050 95400 191050 95400 191051 95401 191051 94279 191051 95400 191052 94279 191052 95396 191052 95396 191053 94279 191053 94280 191053 93217 191054 93929 191054 95402 191054 95402 191055 93929 191055 93927 191055 95402 191056 93927 191056 95403 191056 95403 191057 93927 191057 95404 191057 95403 191058 95404 191058 95405 191058 95405 191059 95404 191059 93926 191059 95405 191060 93926 191060 93438 191060 93438 191061 93926 191061 93924 191061 94289 191062 95406 191062 93653 191062 94289 191063 93653 191063 94290 191063 94290 191064 93653 191064 93438 191064 94290 191065 93438 191065 93924 191065 95417 191066 95416 191066 94270 191066 94270 191067 95416 191067 95407 191067 94270 191068 95407 191068 95408 191068 95408 191069 95407 191069 94267 191069 94267 191070 95407 191070 95409 191070 95409 191071 95407 191071 95415 191071 95409 191072 95415 191072 95413 191072 95410 191073 95411 191073 95412 191073 95412 191074 95411 191074 95413 191074 95412 191075 95413 191075 95414 191075 95414 191076 95413 191076 95415 191076 95416 191077 95417 191077 95418 191077 95418 191078 95417 191078 95419 191078 95418 191079 95419 191079 93815 191079 93815 191080 95419 191080 95420 191080 93815 191081 95420 191081 93817 191081 93817 191082 95420 191082 94269 191082 93219 191083 95425 191083 95410 191083 95410 191084 95425 191084 95411 191084 94268 191085 95421 191085 94269 191085 94269 191086 95421 191086 93817 191086 95422 191087 94277 191087 93639 191087 93639 191088 94277 191088 94276 191088 93639 191089 94276 191089 93638 191089 93638 191090 94276 191090 95423 191090 93638 191091 95423 191091 93636 191091 93636 191092 95423 191092 95424 191092 93636 191093 95424 191093 93219 191093 93219 191094 95424 191094 95425 191094 95421 191095 94268 191095 93914 191095 93914 191096 94268 191096 93933 191096 93914 191097 93933 191097 93916 191097 93916 191098 93933 191098 94272 191098 93916 191099 94272 191099 95426 191099 95426 191100 94272 191100 94273 191100 94278 191101 94277 191101 95422 191101 94278 191102 95422 191102 94274 191102 94274 191103 95422 191103 95426 191103 94274 191104 95426 191104 94273 191104 94256 191105 95427 191105 94257 191105 94257 191106 95427 191106 93171 191106 94257 191107 93171 191107 94250 191107 94250 191108 93171 191108 95428 191108 93662 191109 94254 191109 95429 191109 95429 191110 94254 191110 95430 191110 95429 191111 95430 191111 95431 191111 95431 191112 95430 191112 94247 191112 95431 191113 94247 191113 93171 191113 93171 191114 94247 191114 95428 191114 95427 191115 94256 191115 95432 191115 95432 191116 94256 191116 94255 191116 95432 191117 94255 191117 95433 191117 95433 191118 94255 191118 95434 191118 95433 191119 95434 191119 95435 191119 95435 191120 95434 191120 95436 191120 95435 191121 95436 191121 95438 191121 95438 191122 95436 191122 94261 191122 93215 191123 95441 191123 93662 191123 93662 191124 95441 191124 94254 191124 95442 191125 95437 191125 94261 191125 94261 191126 95437 191126 95438 191126 93169 191127 94253 191127 93659 191127 93659 191128 94253 191128 94252 191128 93659 191129 94252 191129 93657 191129 93657 191130 94252 191130 94251 191130 93657 191131 94251 191131 95439 191131 95439 191132 94251 191132 95440 191132 95439 191133 95440 191133 93215 191133 93215 191134 95440 191134 95441 191134 95437 191135 95442 191135 95443 191135 95443 191136 95442 191136 94260 191136 95443 191137 94260 191137 93911 191137 93911 191138 94260 191138 94265 191138 93911 191139 94265 191139 95445 191139 95445 191140 94265 191140 95444 191140 95445 191141 95444 191141 95446 191141 95445 191142 95446 191142 93169 191142 93169 191143 95446 191143 94262 191143 93169 191144 94262 191144 94253 191144 95449 191145 95447 191145 94233 191145 94233 191146 95447 191146 93176 191146 94233 191147 93176 191147 94224 191147 94224 191148 93176 191148 95448 191148 93670 191149 94236 191149 93671 191149 93671 191150 94236 191150 94235 191150 93671 191151 94235 191151 93672 191151 93672 191152 94235 191152 94222 191152 93672 191153 94222 191153 93176 191153 93176 191154 94222 191154 95448 191154 95447 191155 95449 191155 93902 191155 93902 191156 95449 191156 94232 191156 93902 191157 94232 191157 93903 191157 93903 191158 94232 191158 94241 191158 93903 191159 94241 191159 93904 191159 93904 191160 94241 191160 94240 191160 93904 191161 94240 191161 95451 191161 95451 191162 94240 191162 95450 191162 93664 191163 94237 191163 93670 191163 93670 191164 94237 191164 94236 191164 94238 191165 93566 191165 95450 191165 95450 191166 93566 191166 95451 191166 93667 191167 94248 191167 93666 191167 93666 191168 94248 191168 95452 191168 93666 191169 95452 191169 95453 191169 95453 191170 95452 191170 95454 191170 95453 191171 95454 191171 93664 191171 93664 191172 95454 191172 94237 191172 93566 191173 94238 191173 93906 191173 93906 191174 94238 191174 95455 191174 93906 191175 95455 191175 95456 191175 95456 191176 95455 191176 94246 191176 95456 191177 94246 191177 93174 191177 93174 191178 94246 191178 95457 191178 94242 191179 94248 191179 93667 191179 94242 191180 93667 191180 94243 191180 94243 191181 93667 191181 93174 191181 94243 191182 93174 191182 95457 191182 94229 191183 95458 191183 95459 191183 95459 191184 95458 191184 93178 191184 95459 191185 93178 191185 94230 191185 94230 191186 93178 191186 95460 191186 95460 191187 93178 191187 95462 191187 95462 191188 93178 191188 95461 191188 95462 191189 95461 191189 95466 191189 93213 191190 95463 191190 95464 191190 95464 191191 95463 191191 95466 191191 95464 191192 95466 191192 95465 191192 95465 191193 95466 191193 95461 191193 95458 191194 94229 191194 93894 191194 93894 191195 94229 191195 94227 191195 93894 191196 94227 191196 93896 191196 93896 191197 94227 191197 94231 191197 93896 191198 94231 191198 93897 191198 93897 191199 94231 191199 95469 191199 95467 191200 95473 191200 93213 191200 93213 191201 95473 191201 95463 191201 95468 191202 95474 191202 95469 191202 95469 191203 95474 191203 93897 191203 93678 191204 94223 191204 93677 191204 93677 191205 94223 191205 95470 191205 93677 191206 95470 191206 93676 191206 93676 191207 95470 191207 94234 191207 93676 191208 94234 191208 95471 191208 95471 191209 94234 191209 95472 191209 95471 191210 95472 191210 95467 191210 95467 191211 95472 191211 95473 191211 95474 191212 95468 191212 95475 191212 95475 191213 95468 191213 95476 191213 95475 191214 95476 191214 95478 191214 95478 191215 95476 191215 95477 191215 95478 191216 95477 191216 95479 191216 95479 191217 95477 191217 95481 191217 94225 191218 94223 191218 93678 191218 94225 191219 93678 191219 95480 191219 95480 191220 93678 191220 95479 191220 95480 191221 95479 191221 95481 191221 94214 191222 93882 191222 95482 191222 95482 191223 93882 191223 95483 191223 95482 191224 95483 191224 94216 191224 94216 191225 95483 191225 94208 191225 95493 191226 94211 191226 95484 191226 95484 191227 94211 191227 95486 191227 95484 191228 95486 191228 95485 191228 95485 191229 95486 191229 95488 191229 95485 191230 95488 191230 95487 191230 95487 191231 95488 191231 94209 191231 95487 191232 94209 191232 95483 191232 95483 191233 94209 191233 94208 191233 93882 191234 94214 191234 93883 191234 93883 191235 94214 191235 95489 191235 93883 191236 95489 191236 93885 191236 93885 191237 95489 191237 94213 191237 93885 191238 94213 191238 95490 191238 95490 191239 94213 191239 95491 191239 95490 191240 95491 191240 93888 191240 93888 191241 95491 191241 95492 191241 95496 191242 95494 191242 95493 191242 95493 191243 95494 191243 94211 191243 94217 191244 93565 191244 95492 191244 95492 191245 93565 191245 93888 191245 93180 191246 95500 191246 93683 191246 93683 191247 95500 191247 95495 191247 93683 191248 95495 191248 93682 191248 93682 191249 95495 191249 94212 191249 93682 191250 94212 191250 95496 191250 95496 191251 94212 191251 95494 191251 93565 191252 94217 191252 93890 191252 93890 191253 94217 191253 94221 191253 93890 191254 94221 191254 93889 191254 93889 191255 94221 191255 95497 191255 93889 191256 95497 191256 95498 191256 95498 191257 95497 191257 95499 191257 95498 191258 95499 191258 94219 191258 95498 191259 94219 191259 93180 191259 93180 191260 94219 191260 94218 191260 93180 191261 94218 191261 95500 191261 95501 191262 93183 191262 95502 191262 95502 191263 93183 191263 93182 191263 95502 191264 93182 191264 94343 191264 94343 191265 93182 191265 95503 191265 95503 191266 93182 191266 95504 191266 95504 191267 93182 191267 93691 191267 95504 191268 93691 191268 95505 191268 93687 191269 94195 191269 93689 191269 93689 191270 94195 191270 95505 191270 93689 191271 95505 191271 93690 191271 93690 191272 95505 191272 93691 191272 93183 191273 95501 191273 93878 191273 93878 191274 95501 191274 94199 191274 93878 191275 94199 191275 95506 191275 95506 191276 94199 191276 94198 191276 95506 191277 94198 191277 95509 191277 95509 191278 94198 191278 94200 191278 95513 191279 95507 191279 93687 191279 93687 191280 95507 191280 94195 191280 94202 191281 95508 191281 94200 191281 94200 191282 95508 191282 95509 191282 95519 191283 94197 191283 95510 191283 95510 191284 94197 191284 94196 191284 95510 191285 94196 191285 95511 191285 95511 191286 94196 191286 95512 191286 95511 191287 95512 191287 93685 191287 93685 191288 95512 191288 95514 191288 93685 191289 95514 191289 95513 191289 95513 191290 95514 191290 95507 191290 95508 191291 94202 191291 95515 191291 95515 191292 94202 191292 95516 191292 95515 191293 95516 191293 95517 191293 95517 191294 95516 191294 94207 191294 95517 191295 94207 191295 93880 191295 93880 191296 94207 191296 95518 191296 93880 191297 95518 191297 94205 191297 93880 191298 94205 191298 95519 191298 95519 191299 94205 191299 94204 191299 95519 191300 94204 191300 94197 191300 95520 191301 95521 191301 94190 191301 94190 191302 95521 191302 93193 191302 94190 191303 93193 191303 95522 191303 95522 191304 93193 191304 94176 191304 94177 191305 94176 191305 93193 191305 95531 191306 95532 191306 95523 191306 95523 191307 95532 191307 95524 191307 95523 191308 95524 191308 95525 191308 95525 191309 95524 191309 94177 191309 95525 191310 94177 191310 93698 191310 93698 191311 94177 191311 93193 191311 95521 191312 95520 191312 95526 191312 95526 191313 95520 191313 95527 191313 95526 191314 95527 191314 95528 191314 95528 191315 95527 191315 95529 191315 95528 191316 95529 191316 95530 191316 95530 191317 95529 191317 94179 191317 93581 191318 94178 191318 95531 191318 95531 191319 94178 191319 95532 191319 94180 191320 93831 191320 94179 191320 94179 191321 93831 191321 95530 191321 93585 191322 95539 191322 95533 191322 95533 191323 95539 191323 94320 191323 95533 191324 94320 191324 93583 191324 93583 191325 94320 191325 95534 191325 93583 191326 95534 191326 93582 191326 93582 191327 95534 191327 95535 191327 93582 191328 95535 191328 93581 191328 93581 191329 95535 191329 94178 191329 93831 191330 94180 191330 93829 191330 93829 191331 94180 191331 95536 191331 93829 191332 95536 191332 95537 191332 95537 191333 95536 191333 95538 191333 95537 191334 95538 191334 93195 191334 93195 191335 95538 191335 94194 191335 93195 191336 94194 191336 94193 191336 93195 191337 94193 191337 93585 191337 93585 191338 94193 191338 94192 191338 93585 191339 94192 191339 95539 191339 95543 191340 93852 191340 94186 191340 94186 191341 93852 191341 95542 191341 94186 191342 95542 191342 94172 191342 94172 191343 95542 191343 94173 191343 93705 191344 95547 191344 93706 191344 93706 191345 95547 191345 94175 191345 93706 191346 94175 191346 95541 191346 95541 191347 94175 191347 95540 191347 95541 191348 95540 191348 95542 191348 95542 191349 95540 191349 94173 191349 93852 191350 95543 191350 93854 191350 93854 191351 95543 191351 94184 191351 93854 191352 94184 191352 95544 191352 95544 191353 94184 191353 95545 191353 95544 191354 95545 191354 93855 191354 93855 191355 95545 191355 94182 191355 93855 191356 94182 191356 95546 191356 95546 191357 94182 191357 94181 191357 93700 191358 94174 191358 93705 191358 93705 191359 94174 191359 95547 191359 95548 191360 95549 191360 94181 191360 94181 191361 95549 191361 95546 191361 95556 191362 95550 191362 95551 191362 95551 191363 95550 191363 95552 191363 95551 191364 95552 191364 93702 191364 93702 191365 95552 191365 95553 191365 93702 191366 95553 191366 93700 191366 93700 191367 95553 191367 94174 191367 95549 191368 95548 191368 93856 191368 93856 191369 95548 191369 94187 191369 93856 191370 94187 191370 95554 191370 95554 191371 94187 191371 94188 191371 95554 191372 94188 191372 95557 191372 95557 191373 94188 191373 94189 191373 95555 191374 95550 191374 95556 191374 95555 191375 95556 191375 95558 191375 95558 191376 95556 191376 95557 191376 95558 191377 95557 191377 94189 191377 94168 191378 93191 191378 94169 191378 94169 191379 93191 191379 93716 191379 94169 191380 93716 191380 95559 191380 95559 191381 93716 191381 95560 191381 95560 191382 93716 191382 94164 191382 94164 191383 93716 191383 95561 191383 94164 191384 95561 191384 95562 191384 93209 191385 94165 191385 93712 191385 93712 191386 94165 191386 95562 191386 93712 191387 95562 191387 93713 191387 93713 191388 95562 191388 95561 191388 93191 191389 94168 191389 95563 191389 95563 191390 94168 191390 95564 191390 95563 191391 95564 191391 93846 191391 93846 191392 95564 191392 95565 191392 93846 191393 95565 191393 95568 191393 95568 191394 95565 191394 95566 191394 93208 191395 95567 191395 93209 191395 93209 191396 95567 191396 94165 191396 95572 191397 93851 191397 95566 191397 95566 191398 93851 191398 95568 191398 95578 191399 94162 191399 93710 191399 93710 191400 94162 191400 95569 191400 93710 191401 95569 191401 95570 191401 95570 191402 95569 191402 94161 191402 95570 191403 94161 191403 93708 191403 93708 191404 94161 191404 95571 191404 93708 191405 95571 191405 93208 191405 93208 191406 95571 191406 95567 191406 93851 191407 95572 191407 93850 191407 93850 191408 95572 191408 95573 191408 93850 191409 95573 191409 93847 191409 93847 191410 95573 191410 95575 191410 93847 191411 95575 191411 95574 191411 95574 191412 95575 191412 95576 191412 95577 191413 94162 191413 95578 191413 95577 191414 95578 191414 94170 191414 94170 191415 95578 191415 95574 191415 94170 191416 95574 191416 95576 191416 95584 191417 93838 191417 95579 191417 95579 191418 93838 191418 95583 191418 95579 191419 95583 191419 94152 191419 94152 191420 95583 191420 95580 191420 93207 191421 94159 191421 95581 191421 95581 191422 94159 191422 94154 191422 95581 191423 94154 191423 93724 191423 93724 191424 94154 191424 95582 191424 93724 191425 95582 191425 95583 191425 95583 191426 95582 191426 95580 191426 93838 191427 95584 191427 93839 191427 93839 191428 95584 191428 95585 191428 93839 191429 95585 191429 95587 191429 95587 191430 95585 191430 95586 191430 95587 191431 95586 191431 95588 191431 95588 191432 95586 191432 95589 191432 95588 191433 95589 191433 95591 191433 95591 191434 95589 191434 94156 191434 93717 191435 95590 191435 93207 191435 93207 191436 95590 191436 94159 191436 95597 191437 93844 191437 94156 191437 94156 191438 93844 191438 95591 191438 95592 191439 95590 191439 93717 191439 93717 191440 93718 191440 95592 191440 95592 191441 93718 191441 93719 191441 95592 191442 93719 191442 95593 191442 95593 191443 93719 191443 95594 191443 95593 191444 95594 191444 95595 191444 95605 191445 95606 191445 95596 191445 95596 191446 95606 191446 95595 191446 95596 191447 95595 191447 93721 191447 93721 191448 95595 191448 95594 191448 93844 191449 95597 191449 93843 191449 93843 191450 95597 191450 95598 191450 93843 191451 95598 191451 95599 191451 95599 191452 95598 191452 95600 191452 95599 191453 95600 191453 95602 191453 95602 191454 95600 191454 95601 191454 95602 191455 95601 191455 95603 191455 95602 191456 95603 191456 95605 191456 95605 191457 95603 191457 95604 191457 95605 191458 95604 191458 95606 191458 95615 191459 95607 191459 94143 191459 94143 191460 95607 191460 93731 191460 94143 191461 93731 191461 95608 191461 95608 191462 93731 191462 95609 191462 95609 191463 93731 191463 94139 191463 94139 191464 93731 191464 95610 191464 94139 191465 95610 191465 95613 191465 95611 191466 95620 191466 95612 191466 95612 191467 95620 191467 95613 191467 95612 191468 95613 191468 95614 191468 95614 191469 95613 191469 95610 191469 95607 191470 95615 191470 95616 191470 95616 191471 95615 191471 94141 191471 95616 191472 94141 191472 95617 191472 95617 191473 94141 191473 94147 191473 95617 191474 94147 191474 95618 191474 95618 191475 94147 191475 95619 191475 95623 191476 95624 191476 95611 191476 95611 191477 95624 191477 95620 191477 94145 191478 93562 191478 95619 191478 95619 191479 93562 191479 95618 191479 95629 191480 94148 191480 93728 191480 93728 191481 94148 191481 94140 191481 93728 191482 94140 191482 93727 191482 93727 191483 94140 191483 94138 191483 93727 191484 94138 191484 95621 191484 95621 191485 94138 191485 95622 191485 95621 191486 95622 191486 95623 191486 95623 191487 95622 191487 95624 191487 93562 191488 94145 191488 93837 191488 93837 191489 94145 191489 94150 191489 93837 191490 94150 191490 95625 191490 95625 191491 94150 191491 94149 191491 95625 191492 94149 191492 93835 191492 93835 191493 94149 191493 95626 191493 93835 191494 95626 191494 95627 191494 93835 191495 95627 191495 95629 191495 95629 191496 95627 191496 95628 191496 95629 191497 95628 191497 94148 191497 94126 191498 95630 191498 94127 191498 94127 191499 95630 191499 95631 191499 94127 191500 95631 191500 94128 191500 94128 191501 95631 191501 95632 191501 93736 191502 95633 191502 93737 191502 93737 191503 95633 191503 94132 191503 93737 191504 94132 191504 95634 191504 95634 191505 94132 191505 94131 191505 95634 191506 94131 191506 93740 191506 93740 191507 94131 191507 94129 191507 93740 191508 94129 191508 95631 191508 95631 191509 94129 191509 95632 191509 95630 191510 94126 191510 95635 191510 95635 191511 94126 191511 93971 191511 95635 191512 93971 191512 93824 191512 93824 191513 93971 191513 93965 191513 93824 191514 93965 191514 93825 191514 93825 191515 93965 191515 93967 191515 93205 191516 94135 191516 93736 191516 93736 191517 94135 191517 95633 191517 95639 191518 93821 191518 93967 191518 93967 191519 93821 191519 93825 191519 95642 191520 94137 191520 93732 191520 93732 191521 94137 191521 94136 191521 93732 191522 94136 191522 95636 191522 95636 191523 94136 191523 95637 191523 95636 191524 95637 191524 93205 191524 93205 191525 95637 191525 94135 191525 93821 191526 95639 191526 95638 191526 95638 191527 95639 191527 95640 191527 95638 191528 95640 191528 93818 191528 93818 191529 95640 191529 95641 191529 93818 191530 95641 191530 93167 191530 93167 191531 95641 191531 95644 191531 95643 191532 94137 191532 95642 191532 95643 191533 95642 191533 94134 191533 94134 191534 95642 191534 93167 191534 94134 191535 93167 191535 95644 191535 95645 191536 93761 191536 95646 191536 95646 191537 93761 191537 93440 191537 95646 191538 93440 191538 95647 191538 95647 191539 93440 191539 95648 191539 94119 191540 95648 191540 93440 191540 93440 191541 93757 191541 94119 191541 94119 191542 93757 191542 93758 191542 94119 191543 93758 191543 94120 191543 94120 191544 93758 191544 93759 191544 94120 191545 93759 191545 94113 191545 95649 191546 95650 191546 95651 191546 95651 191547 95650 191547 94113 191547 95651 191548 94113 191548 93755 191548 93755 191549 94113 191549 93759 191549 93761 191550 95645 191550 93762 191550 93762 191551 95645 191551 94118 191551 93762 191552 94118 191552 93764 191552 93764 191553 94118 191553 93977 191553 93764 191554 93977 191554 95652 191554 95652 191555 93977 191555 95653 191555 95654 191556 95655 191556 95649 191556 95649 191557 95655 191557 95650 191557 95656 191558 93768 191558 95653 191558 95653 191559 93768 191559 95652 191559 95665 191560 95657 191560 93771 191560 93771 191561 95657 191561 94112 191561 93771 191562 94112 191562 93769 191562 93769 191563 94112 191563 95658 191563 93769 191564 95658 191564 95654 191564 95654 191565 95658 191565 95655 191565 93768 191566 95656 191566 95660 191566 95660 191567 95656 191567 95659 191567 95660 191568 95659 191568 93766 191568 93766 191569 95659 191569 95661 191569 93766 191570 95661 191570 95662 191570 95662 191571 95661 191571 95663 191571 95662 191572 95663 191572 95664 191572 95664 191573 95663 191573 94124 191573 95664 191574 94124 191574 94122 191574 95664 191575 94122 191575 95665 191575 95665 191576 94122 191576 95666 191576 95665 191577 95666 191577 95657 191577 94059 191578 93443 191578 95667 191578 95667 191579 93443 191579 95673 191579 95667 191580 95673 191580 95668 191580 95668 191581 95673 191581 95674 191581 93752 191582 95669 191582 93753 191582 93753 191583 95669 191583 94102 191583 93753 191584 94102 191584 95670 191584 95670 191585 94102 191585 94104 191585 95670 191586 94104 191586 95671 191586 95671 191587 94104 191587 95672 191587 95671 191588 95672 191588 95673 191588 95673 191589 95672 191589 95674 191589 93443 191590 94059 191590 95675 191590 95675 191591 94059 191591 94061 191591 95675 191592 94061 191592 95676 191592 95676 191593 94061 191593 95678 191593 95676 191594 95678 191594 95677 191594 95677 191595 95678 191595 95680 191595 95679 191596 94103 191596 93752 191596 93752 191597 94103 191597 95669 191597 94063 191598 93746 191598 95680 191598 95680 191599 93746 191599 95677 191599 93751 191600 95681 191600 95682 191600 95682 191601 95681 191601 94101 191601 95682 191602 94101 191602 95683 191602 95683 191603 94101 191603 94100 191603 95683 191604 94100 191604 95679 191604 95679 191605 94100 191605 94103 191605 93746 191606 94063 191606 93745 191606 93745 191607 94063 191607 94062 191607 93745 191608 94062 191608 95684 191608 95684 191609 94062 191609 95685 191609 95684 191610 95685 191610 93744 191610 93744 191611 95685 191611 95686 191611 93744 191612 95686 191612 93743 191612 93743 191613 95686 191613 94108 191613 93743 191614 94108 191614 94107 191614 93743 191615 94107 191615 93751 191615 93751 191616 94107 191616 95687 191616 93751 191617 95687 191617 95681 191617 93978 191618 93444 191618 94093 191618 94093 191619 93444 191619 95690 191619 94093 191620 95690 191620 95688 191620 95688 191621 95690 191621 95689 191621 95691 191622 95689 191622 95690 191622 95690 191623 93786 191623 95691 191623 95691 191624 93786 191624 93787 191624 95691 191625 93787 191625 95692 191625 95692 191626 93787 191626 93784 191626 95692 191627 93784 191627 94090 191627 95693 191628 95694 191628 93781 191628 93781 191629 95694 191629 94090 191629 93781 191630 94090 191630 93783 191630 93783 191631 94090 191631 93784 191631 93444 191632 93978 191632 95695 191632 95695 191633 93978 191633 95696 191633 95695 191634 95696 191634 93807 191634 93807 191635 95696 191635 95697 191635 93807 191636 95697 191636 93808 191636 93808 191637 95697 191637 95698 191637 95701 191638 94097 191638 95693 191638 95693 191639 94097 191639 95694 191639 93979 191640 95702 191640 95698 191640 95698 191641 95702 191641 93808 191641 95710 191642 95699 191642 95700 191642 95700 191643 95699 191643 94099 191643 95700 191644 94099 191644 93777 191644 93777 191645 94099 191645 94098 191645 93777 191646 94098 191646 95701 191646 95701 191647 94098 191647 94097 191647 95702 191648 93979 191648 93774 191648 93774 191649 93979 191649 95703 191649 93774 191650 95703 191650 95704 191650 95704 191651 95703 191651 94096 191651 95704 191652 94096 191652 93773 191652 93773 191653 94096 191653 95705 191653 93773 191654 95705 191654 95706 191654 95706 191655 95705 191655 95707 191655 95708 191656 95699 191656 95710 191656 95708 191657 95710 191657 95709 191657 95709 191658 95710 191658 95706 191658 95709 191659 95706 191659 95707 191659 95714 191660 93810 191660 95711 191660 95711 191661 93810 191661 93794 191661 95711 191662 93794 191662 94082 191662 94082 191663 93794 191663 94083 191663 93197 191664 95712 191664 93789 191664 93789 191665 95712 191665 94080 191665 93789 191666 94080 191666 93792 191666 93792 191667 94080 191667 94084 191667 93792 191668 94084 191668 93793 191668 93793 191669 94084 191669 95713 191669 93793 191670 95713 191670 93794 191670 93794 191671 95713 191671 94083 191671 93810 191672 95714 191672 93811 191672 93811 191673 95714 191673 95715 191673 93811 191674 95715 191674 95716 191674 95716 191675 95715 191675 94486 191675 95716 191676 94486 191676 95717 191676 95717 191677 94486 191677 95719 191677 93196 191678 95718 191678 93197 191678 93197 191679 95718 191679 95712 191679 93981 191680 93199 191680 95719 191680 95719 191681 93199 191681 95717 191681 93803 191682 94089 191682 93802 191682 93802 191683 94089 191683 95720 191683 93802 191684 95720 191684 93801 191684 93801 191685 95720 191685 95721 191685 93801 191686 95721 191686 93196 191686 93196 191687 95721 191687 95718 191687 93199 191688 93981 191688 95723 191688 95723 191689 93981 191689 95722 191689 95723 191690 95722 191690 93799 191690 93799 191691 95722 191691 95724 191691 93799 191692 95724 191692 93795 191692 93795 191693 95724 191693 93980 191693 93795 191694 93980 191694 95726 191694 95726 191695 93980 191695 94086 191695 95725 191696 94089 191696 93803 191696 95725 191697 93803 191697 94087 191697 94087 191698 93803 191698 95726 191698 94087 191699 95726 191699 94086 191699 95727 191700 95728 191700 95849 191700 95849 191701 95728 191701 95730 191701 95849 191702 95730 191702 95729 191702 95729 191703 95730 191703 95731 191703 95731 191704 95730 191704 95752 191704 95731 191705 95752 191705 95732 191705 95732 191706 95752 191706 95746 191706 95732 191707 95746 191707 94544 191707 95735 191708 95733 191708 95736 191708 95736 191709 95733 191709 94562 191709 95736 191710 94562 191710 95734 191710 95734 191711 94562 191711 94554 191711 95734 191712 94554 191712 95786 191712 95735 191713 95736 191713 95839 191713 95839 191714 95736 191714 95781 191714 95839 191715 95781 191715 94498 191715 94545 191716 95737 191716 95766 191716 95766 191717 95737 191717 95738 191717 95766 191718 95738 191718 95739 191718 95739 191719 95738 191719 94553 191719 95739 191720 94553 191720 95769 191720 94545 191721 95766 191721 95823 191721 95823 191722 95766 191722 94506 191722 95823 191723 94506 191723 94505 191723 95740 191724 95793 191724 95813 191724 95813 191725 95793 191725 95804 191725 95813 191726 95804 191726 94563 191726 94563 191727 95804 191727 95741 191727 95741 191728 95804 191728 95742 191728 95741 191729 95742 191729 94564 191729 94564 191730 95742 191730 95801 191730 94564 191731 95801 191731 95743 191731 96642 191732 96644 191732 95744 191732 96642 191733 95744 191733 95745 191733 95745 191734 95744 191734 95746 191734 95745 191735 95746 191735 95747 191735 95748 191736 95276 191736 95749 191736 95748 191737 95749 191737 96643 191737 96643 191738 95749 191738 95750 191738 96643 191739 95750 191739 95751 191739 95751 191740 95750 191740 95744 191740 95751 191741 95744 191741 96644 191741 95747 191742 95746 191742 95752 191742 95747 191743 95752 191743 95753 191743 95753 191744 95752 191744 95730 191744 95753 191745 95730 191745 95754 191745 95754 191746 95730 191746 95728 191746 95754 191747 95728 191747 96637 191747 95755 191748 95756 191748 94502 191748 95748 191749 96702 191749 95276 191749 95276 191750 96702 191750 95757 191750 95276 191751 95757 191751 96711 191751 96778 191752 96777 191752 94502 191752 94502 191753 96777 191753 96775 191753 94502 191754 96775 191754 95755 191754 96711 191755 95758 191755 95276 191755 95276 191756 95758 191756 96750 191756 95276 191757 96750 191757 94502 191757 94502 191758 96750 191758 96760 191758 94502 191759 96760 191759 96778 191759 96637 191760 95728 191760 96625 191760 96625 191761 95728 191761 95759 191761 96625 191762 95759 191762 96631 191762 96647 191763 95763 191763 95264 191763 96647 191764 95264 191764 96646 191764 96646 191765 95264 191765 95263 191765 96646 191766 95263 191766 95760 191766 95760 191767 95263 191767 94502 191767 95760 191768 94502 191768 95756 191768 94524 191769 95761 191769 94536 191769 94536 191770 95761 191770 95762 191770 94536 191771 95762 191771 94537 191771 94537 191772 95762 191772 96624 191772 94537 191773 96624 191773 95759 191773 95759 191774 96624 191774 96631 191774 96647 191775 95764 191775 95763 191775 95763 191776 95764 191776 96652 191776 95763 191777 96652 191777 95769 191777 95769 191778 96652 191778 95770 191778 95761 191779 94524 191779 95765 191779 95765 191780 94524 191780 94523 191780 95765 191781 94523 191781 95774 191781 95767 191782 94506 191782 95766 191782 95767 191783 95766 191783 95768 191783 95768 191784 95766 191784 95739 191784 95768 191785 95739 191785 96648 191785 96648 191786 95739 191786 95769 191786 96648 191787 95769 191787 95770 191787 95771 191788 95777 191788 94522 191788 94522 191789 95777 191789 96619 191789 94522 191790 96619 191790 95772 191790 95772 191791 96619 191791 95773 191791 95772 191792 95773 191792 94523 191792 94523 191793 95773 191793 95774 191793 95775 191794 95776 191794 96653 191794 96653 191795 95776 191795 94506 191795 96653 191796 94506 191796 95767 191796 95777 191797 95771 191797 95778 191797 95778 191798 95771 191798 95781 191798 95778 191799 95781 191799 95780 191799 95776 191800 95775 191800 94531 191800 94531 191801 95775 191801 96656 191801 94531 191802 96656 191802 94532 191802 94532 191803 96656 191803 95779 191803 94532 191804 95779 191804 94534 191804 94534 191805 95779 191805 96659 191805 95780 191806 95781 191806 95736 191806 95780 191807 95736 191807 95782 191807 95782 191808 95736 191808 95734 191808 95782 191809 95734 191809 96614 191809 96614 191810 95734 191810 95786 191810 96614 191811 95786 191811 96615 191811 96667 191812 95783 191812 96658 191812 96658 191813 95783 191813 94534 191813 96658 191814 94534 191814 96659 191814 95784 191815 96804 191815 96803 191815 96803 191816 96596 191816 95784 191816 95784 191817 96596 191817 95785 191817 95784 191818 95785 191818 95786 191818 95786 191819 95785 191819 96615 191819 95783 191820 96667 191820 95787 191820 95787 191821 96667 191821 96666 191821 95787 191822 96666 191822 94515 191822 94515 191823 96666 191823 95788 191823 94515 191824 95788 191824 95789 191824 95789 191825 95788 191825 95794 191825 96804 191826 95784 191826 95790 191826 96804 191827 95790 191827 96610 191827 96610 191828 95790 191828 95791 191828 96610 191829 95791 191829 95792 191829 95791 191830 95273 191830 95792 191830 95792 191831 95273 191831 95271 191831 95792 191832 95271 191832 96611 191832 96672 191833 95793 191833 96661 191833 96661 191834 95793 191834 95789 191834 96661 191835 95789 191835 95794 191835 95800 191836 96611 191836 95271 191836 95795 191837 95797 191837 95796 191837 95796 191838 95797 191838 95798 191838 95796 191839 95798 191839 96792 191839 96792 191840 96794 191840 95796 191840 95796 191841 96794 191841 96795 191841 95796 191842 96795 191842 96796 191842 96796 191843 96797 191843 95796 191843 95796 191844 96797 191844 95799 191844 95796 191845 95799 191845 95271 191845 95271 191846 95799 191846 96801 191846 95271 191847 96801 191847 95800 191847 95802 191848 95801 191848 95742 191848 95802 191849 95742 191849 95803 191849 95803 191850 95742 191850 95804 191850 95803 191851 95804 191851 95805 191851 95805 191852 95804 191852 95793 191852 95805 191853 95793 191853 96672 191853 95795 191854 95796 191854 95268 191854 95795 191855 95268 191855 95806 191855 95806 191856 95268 191856 95807 191856 95806 191857 95807 191857 95808 191857 95807 191858 95267 191858 95808 191858 95808 191859 95267 191859 95809 191859 95808 191860 95809 191860 95810 191860 96805 191861 95810 191861 95809 191861 96805 191862 95809 191862 95811 191862 95811 191863 95809 191863 96671 191863 96671 191864 95809 191864 95801 191864 96671 191865 95801 191865 95802 191865 94563 191866 95812 191866 95813 191866 95813 191867 95812 191867 94494 191867 95813 191868 94494 191868 95740 191868 95814 191869 94520 191869 94519 191869 95814 191870 94519 191870 95815 191870 95815 191871 94519 191871 94516 191871 95815 191872 94516 191872 94567 191872 94567 191873 94516 191873 94494 191873 94567 191874 94494 191874 95812 191874 94565 191875 94521 191875 95814 191875 95814 191876 94521 191876 94520 191876 95820 191877 95258 191877 95259 191877 95820 191878 95259 191878 95816 191878 95816 191879 95259 191879 95260 191879 95816 191880 95260 191880 94566 191880 95260 191881 95817 191881 94566 191881 94566 191882 95817 191882 95818 191882 94566 191883 95818 191883 95819 191883 95818 191884 95256 191884 95819 191884 95819 191885 95256 191885 94521 191885 95819 191886 94521 191886 94565 191886 95258 191887 95820 191887 94569 191887 94569 191888 95269 191888 95258 191888 95258 191889 95269 191889 95821 191889 95258 191890 95821 191890 95822 191890 94548 191891 94545 191891 94529 191891 94529 191892 94545 191892 95823 191892 94529 191893 95823 191893 94505 191893 94548 191894 94529 191894 94528 191894 94548 191895 94528 191895 94547 191895 94547 191896 94528 191896 94527 191896 94547 191897 94527 191897 94549 191897 94549 191898 94527 191898 95825 191898 94549 191899 95825 191899 95824 191899 94525 191900 94552 191900 95825 191900 95825 191901 94552 191901 95824 191901 94552 191902 94525 191902 95255 191902 94552 191903 95255 191903 95826 191903 95826 191904 95255 191904 95252 191904 95826 191905 95252 191905 94550 191905 94550 191906 95252 191906 95827 191906 94550 191907 95827 191907 95828 191907 95827 191908 94501 191908 95262 191908 95827 191909 95262 191909 95828 191909 95828 191910 95262 191910 95829 191910 95828 191911 95829 191911 94546 191911 95272 191912 95830 191912 94557 191912 95272 191913 94557 191913 95831 191913 95831 191914 94557 191914 95832 191914 95831 191915 95832 191915 95270 191915 94558 191916 95247 191916 95833 191916 94558 191917 95833 191917 95834 191917 95834 191918 95833 191918 95249 191918 95834 191919 95249 191919 94556 191919 94556 191920 95249 191920 95832 191920 94556 191921 95832 191921 94557 191921 94560 191922 95835 191922 94558 191922 94558 191923 95835 191923 95247 191923 94561 191924 95840 191924 95836 191924 94561 191925 95836 191925 95837 191925 95837 191926 95836 191926 94496 191926 95837 191927 94496 191927 95838 191927 95838 191928 94496 191928 95835 191928 95838 191929 95835 191929 94560 191929 94561 191930 95735 191930 95840 191930 95840 191931 95735 191931 95839 191931 95840 191932 95839 191932 94498 191932 95277 191933 94500 191933 95841 191933 94540 191934 94539 191934 95841 191934 95841 191935 94539 191935 95275 191935 95841 191936 95275 191936 95277 191936 94540 191937 95841 191937 95842 191937 94540 191938 95842 191938 95844 191938 95844 191939 95842 191939 95843 191939 95844 191940 95843 191940 95845 191940 95845 191941 95843 191941 94514 191941 95845 191942 94514 191942 94543 191942 94513 191943 95846 191943 94514 191943 94514 191944 95846 191944 94543 191944 95846 191945 94513 191945 94510 191945 95846 191946 94510 191946 94542 191946 94542 191947 94510 191947 94509 191947 94542 191948 94509 191948 95847 191948 95847 191949 94509 191949 94507 191949 95847 191950 94507 191950 95848 191950 95729 191951 95848 191951 95849 191951 95849 191952 95848 191952 94507 191952 95849 191953 94507 191953 95727 191953 94419 191954 95852 191954 95850 191954 95850 191955 95852 191955 95253 191955 95851 191956 95286 191956 95287 191956 95851 191957 95287 191957 94420 191957 94420 191958 95287 191958 95852 191958 94420 191959 95852 191959 94419 191959 95850 191960 95253 191960 95853 191960 95850 191961 95853 191961 95854 191961 95854 191962 95853 191962 95254 191962 95854 191963 95254 191963 94421 191963 94421 191964 95254 191964 95863 191964 94421 191965 95863 191965 94422 191965 95855 191966 93559 191966 95851 191966 95851 191967 93559 191967 95286 191967 95861 191968 94422 191968 95863 191968 95856 191969 95857 191969 95858 191969 95858 191970 95857 191970 95859 191970 95858 191971 95859 191971 95860 191971 95860 191972 93951 191972 95858 191972 95858 191973 93951 191973 93950 191973 95858 191974 93950 191974 94481 191974 95861 191975 95863 191975 93955 191975 94481 191976 95862 191976 95858 191976 95858 191977 95862 191977 94067 191977 95858 191978 94067 191978 95863 191978 95863 191979 94067 191979 95864 191979 95863 191980 95864 191980 93955 191980 93559 191981 95855 191981 93557 191981 93557 191982 95855 191982 95865 191982 93557 191983 95865 191983 93231 191983 93231 191984 95865 191984 95868 191984 95856 191985 95858 191985 94526 191985 95856 191986 94526 191986 95866 191986 95866 191987 94526 191987 95867 191987 95866 191988 95867 191988 94416 191988 94416 191989 95867 191989 94530 191989 94416 191990 94530 191990 95870 191990 94443 191991 93555 191991 94428 191991 94428 191992 93555 191992 93231 191992 94428 191993 93231 191993 94423 191993 94423 191994 93231 191994 95868 191994 95874 191995 95869 191995 94530 191995 94530 191996 95869 191996 95870 191996 93555 191997 94443 191997 93556 191997 93556 191998 94443 191998 94451 191998 93556 191999 94451 191999 95871 191999 95871 192000 94451 192000 94442 192000 94533 192001 95876 192001 95872 192001 95872 192002 95876 192002 94413 192002 95872 192003 94413 192003 95873 192003 95873 192004 94413 192004 94414 192004 95873 192005 94414 192005 95874 192005 95874 192006 94414 192006 95869 192006 95880 192007 95875 192007 94442 192007 94442 192008 95875 192008 95871 192008 95876 192009 94533 192009 94411 192009 94411 192010 94533 192010 95877 192010 94411 192011 95877 192011 94412 192011 95885 192012 95886 192012 95878 192012 95885 192013 95878 192013 95879 192013 95879 192014 95878 192014 95875 192014 95879 192015 95875 192015 95880 192015 95889 192016 94409 192016 95881 192016 95881 192017 94409 192017 95882 192017 95881 192018 95882 192018 95883 192018 95883 192019 95882 192019 95884 192019 95883 192020 95884 192020 95877 192020 95877 192021 95884 192021 94412 192021 94433 192022 94504 192022 95885 192022 95885 192023 94504 192023 95886 192023 95887 192024 95888 192024 95889 192024 95889 192025 95888 192025 94409 192025 95890 192026 95251 192026 95250 192026 95890 192027 95250 192027 95891 192027 95891 192028 95250 192028 95892 192028 95891 192029 95892 192029 94435 192029 94435 192030 95892 192030 94504 192030 94435 192031 94504 192031 94433 192031 95888 192032 95887 192032 94517 192032 95888 192033 94517 192033 95893 192033 95893 192034 94517 192034 94518 192034 95893 192035 94518 192035 94029 192035 94029 192036 94518 192036 95899 192036 94029 192037 95899 192037 95894 192037 95895 192038 95908 192038 95896 192038 94291 192039 93932 192039 95896 192039 95895 192040 95896 192040 94026 192040 94291 192041 95896 192041 95898 192041 95251 192042 95890 192042 93944 192042 93944 192043 93945 192043 95251 192043 95251 192044 93945 192044 95897 192044 95251 192045 95897 192045 95896 192045 95896 192046 95897 192046 94073 192046 95896 192047 94073 192047 95898 192047 93932 192048 93931 192048 95896 192048 95896 192049 93931 192049 94024 192049 95896 192050 94024 192050 94026 192050 95900 192051 95894 192051 95899 192051 95903 192052 93989 192052 95899 192052 95899 192053 93989 192053 94036 192053 95899 192054 94036 192054 95900 192054 95909 192055 94396 192055 95904 192055 95904 192056 94396 192056 93917 192056 95904 192057 93917 192057 93998 192057 94052 192058 95901 192058 95899 192058 95899 192059 95901 192059 95902 192059 95899 192060 95902 192060 95903 192060 93998 192061 94000 192061 95904 192061 95904 192062 94000 192062 95905 192062 95904 192063 95905 192063 95899 192063 95899 192064 95905 192064 95906 192064 95899 192065 95906 192065 94052 192065 94468 192066 94508 192066 94511 192066 94468 192067 94511 192067 95907 192067 95907 192068 94511 192068 94512 192068 95907 192069 94512 192069 94019 192069 94019 192070 94512 192070 95896 192070 94019 192071 95896 192071 95908 192071 95909 192072 95904 192072 95257 192072 95909 192073 95257 192073 94405 192073 94405 192074 95257 192074 95261 192074 94405 192075 95261 192075 94406 192075 94406 192076 95261 192076 94491 192076 94406 192077 94491 192077 94407 192077 95910 192078 94538 192078 94468 192078 94468 192079 94538 192079 94508 192079 94493 192080 94404 192080 94491 192080 94491 192081 94404 192081 94407 192081 94538 192082 95910 192082 95911 192082 95911 192083 95910 192083 95912 192083 95911 192084 95912 192084 94535 192084 94535 192085 95912 192085 95913 192085 94535 192086 95913 192086 95915 192086 95915 192087 95913 192087 94473 192087 94404 192088 94493 192088 95283 192088 94404 192089 95283 192089 95914 192089 95914 192090 95283 192090 95282 192090 95914 192091 95282 192091 94403 192091 95919 192092 95918 192092 94480 192092 94480 192093 95918 192093 95915 192093 94480 192094 95915 192094 94473 192094 94403 192095 95282 192095 95916 192095 95916 192096 95282 192096 93552 192096 95916 192097 93552 192097 95917 192097 95918 192098 95919 192098 95920 192098 95920 192099 95919 192099 95921 192099 95920 192100 95921 192100 95922 192100 95922 192101 95921 192101 94479 192101 95922 192102 94479 192102 95923 192102 95923 192103 94479 192103 94478 192103 93229 192104 95927 192104 95924 192104 95924 192105 95927 192105 95925 192105 95924 192106 95925 192106 93552 192106 93552 192107 95925 192107 95917 192107 94476 192108 94499 192108 94478 192108 94478 192109 94499 192109 95923 192109 95926 192110 95927 192110 93229 192110 95926 192111 93229 192111 95928 192111 95928 192112 93229 192112 95929 192112 95928 192113 95929 192113 95935 192113 94006 192114 94495 192114 95930 192114 94006 192115 95930 192115 94007 192115 94007 192116 95930 192116 94497 192116 94007 192117 94497 192117 95931 192117 95931 192118 94497 192118 94499 192118 95931 192119 94499 192119 94476 192119 93550 192120 95933 192120 95932 192120 95932 192121 95933 192121 95934 192121 95932 192122 95934 192122 95929 192122 95929 192123 95934 192123 95935 192123 94006 192124 95936 192124 94495 192124 94495 192125 95936 192125 94008 192125 94495 192126 95939 192126 95937 192126 94495 192127 95937 192127 95941 192127 95941 192128 95937 192128 95938 192128 95941 192129 95938 192129 95940 192129 94008 192130 94009 192130 94495 192130 94495 192131 94009 192131 93922 192131 94495 192132 93922 192132 93974 192132 93974 192133 94116 192133 94495 192133 94495 192134 94116 192134 94117 192134 94495 192135 94117 192135 95939 192135 95940 192136 93984 192136 95941 192136 95941 192137 93984 192137 95942 192137 95941 192138 95942 192138 94356 192138 95278 192139 95943 192139 93550 192139 93550 192140 95943 192140 95944 192140 93550 192141 95944 192141 95933 192141 94355 192142 95945 192142 95946 192142 94355 192143 95946 192143 95947 192143 95947 192144 95946 192144 95248 192144 95947 192145 95248 192145 95948 192145 95948 192146 95248 192146 95941 192146 95948 192147 95941 192147 94356 192147 95943 192148 95278 192148 95949 192148 95943 192149 95949 192149 94354 192149 94354 192150 95949 192150 95951 192150 94354 192151 95951 192151 95950 192151 95950 192152 95951 192152 94355 192152 94355 192153 95951 192153 95945 192153 95285 192154 94492 192154 95952 192154 95285 192155 95952 192155 95284 192155 95284 192156 95952 192156 95280 192156 95284 192157 95280 192157 95973 192157 95973 192158 95280 192158 95281 192158 95973 192159 95281 192159 95953 192159 95289 192160 95290 192160 94503 192160 95289 192161 94503 192161 95954 192161 95954 192162 94503 192162 95288 192162 95954 192163 95288 192163 95955 192163 95955 192164 95288 192164 95956 192164 95955 192165 95956 192165 95959 192165 95967 192166 95962 192166 95955 192166 95959 192167 95957 192167 95965 192167 95965 192168 95958 192168 95959 192168 95959 192169 95958 192169 95960 192169 95959 192170 95960 192170 95955 192170 95955 192171 95960 192171 95961 192171 95955 192172 95961 192172 95967 192172 95969 192173 95962 192173 95967 192173 93232 192174 93554 192174 95968 192174 93232 192175 95968 192175 95963 192175 93558 192176 95964 192176 93560 192176 93560 192177 95964 192177 95965 192177 93560 192178 95965 192178 95966 192178 95966 192179 95965 192179 95957 192179 95964 192180 93236 192180 95965 192180 95965 192181 93236 192181 93235 192181 95965 192182 93235 192182 95958 192182 95958 192183 93235 192183 93234 192183 95958 192184 93234 192184 95960 192184 95960 192185 93234 192185 93233 192185 95960 192186 93233 192186 95961 192186 95961 192187 93233 192187 95963 192187 95961 192188 95963 192188 95967 192188 95967 192189 95963 192189 95968 192189 95967 192190 95968 192190 95969 192190 95982 192191 95970 192191 95973 192191 95953 192192 95279 192192 95976 192192 95976 192193 95978 192193 95953 192193 95953 192194 95978 192194 95971 192194 95953 192195 95971 192195 95973 192195 95973 192196 95971 192196 95972 192196 95973 192197 95972 192197 95982 192197 93561 192198 93551 192198 95974 192198 95974 192199 93551 192199 93553 192199 95974 192200 93553 192200 95981 192200 95975 192201 93228 192201 93549 192201 93549 192202 93228 192202 95976 192202 93549 192203 95976 192203 95977 192203 95977 192204 95976 192204 95279 192204 93228 192205 93227 192205 95976 192205 95976 192206 93227 192206 93230 192206 95976 192207 93230 192207 95978 192207 95978 192208 93230 192208 95979 192208 95978 192209 95979 192209 95971 192209 95971 192210 95979 192210 95980 192210 95971 192211 95980 192211 95972 192211 95972 192212 95980 192212 95981 192212 95972 192213 95981 192213 95982 192213 95982 192214 95981 192214 93553 192214 95982 192215 93553 192215 95970 192215 93913 192216 93915 192216 95989 192216 93637 192217 93635 192217 95983 192217 95983 192218 93635 192218 95988 192218 95983 192219 95988 192219 93640 192219 95984 192220 93641 192220 95985 192220 95985 192221 93641 192221 95988 192221 95985 192222 95988 192222 93220 192222 93220 192223 95988 192223 93635 192223 95986 192224 95987 192224 93814 192224 93814 192225 95987 192225 93816 192225 93814 192226 93816 192226 93568 192226 93568 192227 93913 192227 93814 192227 93814 192228 93913 192228 95989 192228 93814 192229 95989 192229 95988 192229 95988 192230 95989 192230 93436 192230 95988 192231 93436 192231 93640 192231 93170 192232 93172 192232 95990 192232 95990 192233 93172 192233 93908 192233 95990 192234 93908 192234 93909 192234 93912 192235 95991 192235 93567 192235 93567 192236 95991 192236 95990 192236 93567 192237 95990 192237 93910 192237 93910 192238 95990 192238 93909 192238 93910 192239 93909 192239 95992 192239 95990 192240 93168 192240 93170 192240 93170 192241 93168 192241 93660 192241 93170 192242 93660 192242 93658 192242 93663 192243 95993 192243 93661 192243 93661 192244 95993 192244 93170 192244 93661 192245 93170 192245 93655 192245 93655 192246 93170 192246 93658 192246 93655 192247 93658 192247 93656 192247 95994 192248 95995 192248 93901 192248 93901 192249 95995 192249 93905 192249 93901 192250 93905 192250 93175 192250 93175 192251 93905 192251 95999 192251 93907 192252 95996 192252 95997 192252 95997 192253 95996 192253 93173 192253 95997 192254 93173 192254 93905 192254 93905 192255 93173 192255 95998 192255 93905 192256 95998 192256 95999 192256 95999 192257 95998 192257 93668 192257 95999 192258 93668 192258 93665 192258 93669 192259 96000 192259 96001 192259 96001 192260 96000 192260 95999 192260 96001 192261 95999 192261 93214 192261 93214 192262 95999 192262 93665 192262 93680 192263 96002 192263 96003 192263 96003 192264 96002 192264 93681 192264 96003 192265 93681 192265 96007 192265 93679 192266 93675 192266 96004 192266 96004 192267 93675 192267 93674 192267 93177 192268 93895 192268 96005 192268 93900 192269 93899 192269 96006 192269 96006 192270 93899 192270 93898 192270 93674 192271 93673 192271 96004 192271 96004 192272 93673 192272 96003 192272 96004 192273 96003 192273 93898 192273 93898 192274 96003 192274 96007 192274 93898 192275 96007 192275 96006 192275 96006 192276 96007 192276 93177 192276 96006 192277 93177 192277 96008 192277 96008 192278 93177 192278 96005 192278 96015 192279 96009 192279 96014 192279 96010 192280 96011 192280 93179 192280 93179 192281 96011 192281 96012 192281 93179 192282 96012 192282 96018 192282 96018 192283 96012 192283 96013 192283 96018 192284 96013 192284 96014 192284 96014 192285 96013 192285 93684 192285 96014 192286 93684 192286 96015 192286 96014 192287 96016 192287 96018 192287 96018 192288 96016 192288 96017 192288 96018 192289 96017 192289 93884 192289 93892 192290 93891 192290 93893 192290 93893 192291 93891 192291 96018 192291 93893 192292 96018 192292 93887 192292 93887 192293 96018 192293 93884 192293 93887 192294 93884 192294 93886 192294 93181 192295 96019 192295 96021 192295 93693 192296 93876 192296 96024 192296 96024 192297 93876 192297 96021 192297 96027 192298 96020 192298 93881 192298 96019 192299 96022 192299 96021 192299 96021 192300 96022 192300 93686 192300 96021 192301 93686 192301 96023 192301 93688 192302 96025 192302 96024 192302 96024 192303 96025 192303 93692 192303 96024 192304 93692 192304 93693 192304 93877 192305 96026 192305 93876 192305 93876 192306 96026 192306 93879 192306 93876 192307 93879 192307 96021 192307 96021 192308 93879 192308 96027 192308 96021 192309 96027 192309 93181 192309 93181 192310 96027 192310 93881 192310 96030 192311 96032 192311 96033 192311 93873 192312 96028 192312 93875 192312 93875 192313 96028 192313 96033 192313 93875 192314 96033 192314 96029 192314 96029 192315 96033 192315 93870 192315 96033 192316 93185 192316 96030 192316 96030 192317 93185 192317 93697 192317 96030 192318 93697 192318 96031 192318 93569 192319 93570 192319 93212 192319 93212 192320 93570 192320 96030 192320 93212 192321 96030 192321 93211 192321 93211 192322 96030 192322 96031 192322 93211 192323 96031 192323 93695 192323 96032 192324 93868 192324 96033 192324 96033 192325 93868 192325 96034 192325 96033 192326 96034 192326 93870 192326 93864 192327 93576 192327 96040 192327 96040 192328 93576 192328 96041 192328 96040 192329 93858 192329 93864 192329 93864 192330 93858 192330 93859 192330 93864 192331 93859 192331 96035 192331 96036 192332 93867 192332 96037 192332 96037 192333 93867 192333 93864 192333 96037 192334 93864 192334 93861 192334 93861 192335 93864 192335 96035 192335 93861 192336 96035 192336 96038 192336 96039 192337 93579 192337 93577 192337 93577 192338 93579 192338 96040 192338 93577 192339 96040 192339 93572 192339 93572 192340 96040 192340 96041 192340 93572 192341 96041 192341 93574 192341 93853 192342 96042 192342 96043 192342 96049 192343 96043 192343 93857 192343 96044 192344 96045 192344 93857 192344 93857 192345 96045 192345 96046 192345 93857 192346 96046 192346 96049 192346 96047 192347 93853 192347 96048 192347 96048 192348 93853 192348 96043 192348 96048 192349 96043 192349 93707 192349 93707 192350 96043 192350 96049 192350 93707 192351 96049 192351 93703 192351 93704 192352 96050 192352 96051 192352 96051 192353 96050 192353 93707 192353 96051 192354 93707 192354 93701 192354 93701 192355 93707 192355 93703 192355 93701 192356 93703 192356 96052 192356 93714 192357 93715 192357 93189 192357 96057 192358 93709 192358 96056 192358 96055 192359 93210 192359 96059 192359 93190 192360 96053 192360 96054 192360 93210 192361 96055 192361 96056 192361 96056 192362 96055 192362 93711 192362 96056 192363 93711 192363 96057 192363 93845 192364 96058 192364 93190 192364 93190 192365 96058 192365 93563 192365 93190 192366 93563 192366 96053 192366 96059 192367 93714 192367 96055 192367 96055 192368 93714 192368 93189 192368 96055 192369 93189 192369 93848 192369 93848 192370 93189 192370 93190 192370 93848 192371 93190 192371 93849 192371 93849 192372 93190 192372 96054 192372 93840 192373 93841 192373 96067 192373 96065 192374 96067 192374 96060 192374 93722 192375 93723 192375 93192 192375 93840 192376 96067 192376 96069 192376 96061 192377 96062 192377 96060 192377 96060 192378 96062 192378 93842 192378 96060 192379 93842 192379 96065 192379 93720 192380 96063 192380 96065 192380 96065 192381 96063 192381 96064 192381 96065 192382 96064 192382 96066 192382 96066 192383 93722 192383 96065 192383 96065 192384 93722 192384 93192 192384 96065 192385 93192 192385 96067 192385 96067 192386 93192 192386 96068 192386 96067 192387 96068 192387 96069 192387 96078 192388 96070 192388 96072 192388 93726 192389 93725 192389 96071 192389 96071 192390 93725 192390 96072 192390 96071 192391 96072 192391 96073 192391 96073 192392 96072 192392 96070 192392 93730 192393 96074 192393 93729 192393 93729 192394 96074 192394 96072 192394 93729 192395 96072 192395 96075 192395 96075 192396 96072 192396 93725 192396 96072 192397 96076 192397 96078 192397 96078 192398 96076 192398 93833 192398 96078 192399 93833 192399 93834 192399 96077 192400 93836 192400 96079 192400 96079 192401 93836 192401 96078 192401 96079 192402 96078 192402 96080 192402 96080 192403 96078 192403 93834 192403 96090 192404 93194 192404 96089 192404 96081 192405 96086 192405 96089 192405 93832 192406 93830 192406 93828 192406 93194 192407 96082 192407 96089 192407 96089 192408 96082 192408 93584 192408 96089 192409 93584 192409 96081 192409 96083 192410 93699 192410 96084 192410 96084 192411 93699 192411 96089 192411 96084 192412 96089 192412 96085 192412 96085 192413 96089 192413 96086 192413 93826 192414 96087 192414 96088 192414 96088 192415 96087 192415 93827 192415 96088 192416 93827 192416 96089 192416 96089 192417 93827 192417 93832 192417 96089 192418 93832 192418 96090 192418 96090 192419 93832 192419 93828 192419 96092 192420 93734 192420 93733 192420 93735 192421 93738 192421 96091 192421 96091 192422 93738 192422 93739 192422 96091 192423 93739 192423 93741 192423 96093 192424 93823 192424 96095 192424 93820 192425 93819 192425 93822 192425 93822 192426 93819 192426 93166 192426 93733 192427 93206 192427 96092 192427 96092 192428 93206 192428 96091 192428 96092 192429 96091 192429 93166 192429 93166 192430 96091 192430 93741 192430 93166 192431 93741 192431 93822 192431 93822 192432 93741 192432 96093 192432 93822 192433 96093 192433 96094 192433 96094 192434 96093 192434 96095 192434 96097 192435 93796 192435 93805 192435 96097 192436 93788 192436 93790 192436 93804 192437 96096 192437 93805 192437 93805 192438 96096 192438 93198 192438 93805 192439 93198 192439 96097 192439 93796 192440 96097 192440 96098 192440 96098 192441 96097 192441 93790 192441 96098 192442 93790 192442 93791 192442 93809 192443 93812 192443 96099 192443 96099 192444 93812 192444 93813 192444 96099 192445 93813 192445 96100 192445 93798 192446 93797 192446 93800 192446 93800 192447 93797 192447 93796 192447 93800 192448 93796 192448 96100 192448 96100 192449 93796 192449 96098 192449 96100 192450 96098 192450 96099 192450 96101 192451 93806 192451 96102 192451 96102 192452 93806 192452 96103 192452 96102 192453 96103 192453 93785 192453 93775 192454 96104 192454 96108 192454 96108 192455 96104 192455 96105 192455 96108 192456 96105 192456 96109 192456 93780 192457 93779 192457 93778 192457 93782 192458 96106 192458 96107 192458 96107 192459 96106 192459 93785 192459 96103 192460 96108 192460 93785 192460 93785 192461 96108 192461 96109 192461 93785 192462 96109 192462 96107 192462 96107 192463 96109 192463 93780 192463 96107 192464 93780 192464 93776 192464 93776 192465 93780 192465 93778 192465 96115 192466 93756 192466 96110 192466 93203 192467 96110 192467 96111 192467 93760 192468 93763 192468 96111 192468 96111 192469 93763 192469 93202 192469 96111 192470 93202 192470 93203 192470 93767 192471 96113 192471 96112 192471 96112 192472 96113 192472 93765 192472 96114 192473 93770 192473 93772 192473 93772 192474 93770 192474 93200 192474 93772 192475 93200 192475 93201 192475 93201 192476 96115 192476 93772 192476 93772 192477 96115 192477 96110 192477 93772 192478 96110 192478 93765 192478 93765 192479 96110 192479 93203 192479 93765 192480 93203 192480 96112 192480 96118 192481 93750 192481 96116 192481 93441 192482 96117 192482 93204 192482 93204 192483 96117 192483 96118 192483 93204 192484 96118 192484 93749 192484 93749 192485 96118 192485 96116 192485 96119 192486 96120 192486 93204 192486 93204 192487 96120 192487 93754 192487 93204 192488 93754 192488 93441 192488 93742 192489 96121 192489 93442 192489 93442 192490 96121 192490 96122 192490 93442 192491 96122 192491 93748 192491 96123 192492 96124 192492 93747 192492 93747 192493 96124 192493 96117 192493 93747 192494 96117 192494 93748 192494 93748 192495 96117 192495 93441 192495 93748 192496 93441 192496 93442 192496 96131 192497 93654 192497 96125 192497 93437 192498 96126 192498 96125 192498 96125 192499 96126 192499 96127 192499 96125 192500 96127 192500 93647 192500 93437 192501 96125 192501 96128 192501 96128 192502 96125 192502 93654 192502 96128 192503 93654 192503 93652 192503 93649 192504 96129 192504 96130 192504 96130 192505 96129 192505 96131 192505 96130 192506 96131 192506 93218 192506 93218 192507 96131 192507 96125 192507 93643 192508 96132 192508 93642 192508 93642 192509 96132 192509 96128 192509 93642 192510 96128 192510 93650 192510 93650 192511 96128 192511 93652 192511 93650 192512 93652 192512 93651 192512 96133 192513 93439 192513 96134 192513 96143 192514 93627 192514 96141 192514 93632 192515 93634 192515 96134 192515 96134 192516 93634 192516 96135 192516 96134 192517 96135 192517 96133 192517 93619 192518 93621 192518 96136 192518 96136 192519 93621 192519 96140 192519 96136 192520 96140 192520 93439 192520 93439 192521 96140 192521 96141 192521 93439 192522 96141 192522 96134 192522 93625 192523 96138 192523 96137 192523 96137 192524 96138 192524 96139 192524 96137 192525 96139 192525 96140 192525 96140 192526 96139 192526 93435 192526 96140 192527 93435 192527 96141 192527 96141 192528 93435 192528 96142 192528 96141 192529 96142 192529 96143 192529 93433 192530 93614 192530 93611 192530 93611 192531 93614 192531 93615 192531 93606 192532 96144 192532 96148 192532 93612 192533 96145 192533 93611 192533 93611 192534 96145 192534 96146 192534 93611 192535 96146 192535 93433 192535 93615 192536 93616 192536 93611 192536 93611 192537 93616 192537 93617 192537 93611 192538 93617 192538 96149 192538 96150 192539 93602 192539 96147 192539 96147 192540 93602 192540 93603 192540 96147 192541 93603 192541 93604 192541 96148 192542 93609 192542 93606 192542 93606 192543 93609 192543 93611 192543 93606 192544 93611 192544 96147 192544 96147 192545 93611 192545 96149 192545 96147 192546 96149 192546 96150 192546 96151 192547 93586 192547 96154 192547 93226 192548 93595 192548 96151 192548 96151 192549 93595 192549 93594 192549 96152 192550 96153 192550 93597 192550 93597 192551 96153 192551 93223 192551 93597 192552 93223 192552 93591 192552 93226 192553 96151 192553 93224 192553 93224 192554 96151 192554 96154 192554 93224 192555 96154 192555 93589 192555 93598 192556 93599 192556 96155 192556 96155 192557 93599 192557 96156 192557 96155 192558 96156 192558 93223 192558 93223 192559 96156 192559 96151 192559 93223 192560 96151 192560 93591 192560 93591 192561 96151 192561 93594 192561 93591 192562 93594 192562 93592 192562 93536 192563 96157 192563 96161 192563 96161 192564 96157 192564 93539 192564 96161 192565 93539 192565 93540 192565 96158 192566 96159 192566 96161 192566 96161 192567 96159 192567 93535 192567 96161 192568 93535 192568 93536 192568 96163 192569 96160 192569 96161 192569 96161 192570 96160 192570 93546 192570 96161 192571 93546 192571 96158 192571 93540 192572 93542 192572 96161 192572 96161 192573 93542 192573 96162 192573 96161 192574 96162 192574 96163 192574 96168 192575 96164 192575 96165 192575 96165 192576 96164 192576 96166 192576 96165 192577 96166 192577 96167 192577 96169 192578 93521 192578 96165 192578 96165 192579 93521 192579 93522 192579 96165 192580 93522 192580 96168 192580 93528 192581 93531 192581 96165 192581 96165 192582 93531 192582 93532 192582 96165 192583 93532 192583 96169 192583 96167 192584 93526 192584 96165 192584 96165 192585 93526 192585 93527 192585 96165 192586 93527 192586 93528 192586 96174 192587 93510 192587 96172 192587 96172 192588 93510 192588 93511 192588 96172 192589 93511 192589 96170 192589 93507 192590 96171 192590 96172 192590 96172 192591 96171 192591 96173 192591 96172 192592 96173 192592 96174 192592 93517 192593 93520 192593 96172 192593 96172 192594 93520 192594 96175 192594 96172 192595 96175 192595 93507 192595 96170 192596 93514 192596 96172 192596 96172 192597 93514 192597 93515 192597 96172 192598 93515 192598 93517 192598 96176 192599 96177 192599 96181 192599 96181 192600 96177 192600 93500 192600 96181 192601 93500 192601 93502 192601 93496 192602 96178 192602 96181 192602 96181 192603 96178 192603 93498 192603 96181 192604 93498 192604 96176 192604 96183 192605 96179 192605 96181 192605 96181 192606 96179 192606 93505 192606 96181 192607 93505 192607 93496 192607 93502 192608 96180 192608 96181 192608 96181 192609 96180 192609 96182 192609 96181 192610 96182 192610 96183 192610 96187 192611 93489 192611 96184 192611 96184 192612 93489 192612 96185 192612 96184 192613 96185 192613 93491 192613 93484 192614 93486 192614 96184 192614 96184 192615 93486 192615 96186 192615 96184 192616 96186 192616 96187 192616 96188 192617 96189 192617 96184 192617 96184 192618 96189 192618 93483 192618 96184 192619 93483 192619 93484 192619 93491 192620 93493 192620 96184 192620 96184 192621 93493 192621 93495 192621 96184 192622 93495 192622 96188 192622 93474 192623 93475 192623 96190 192623 96190 192624 93475 192624 93476 192624 96190 192625 93476 192625 93477 192625 96194 192626 96191 192626 96190 192626 96190 192627 96191 192627 96192 192627 96190 192628 96192 192628 93474 192628 93481 192629 96193 192629 96190 192629 96190 192630 96193 192630 93471 192630 96190 192631 93471 192631 96194 192631 93477 192632 93478 192632 96190 192632 96190 192633 93478 192633 96195 192633 96190 192634 96195 192634 93481 192634 96196 192635 93462 192635 96200 192635 96200 192636 93462 192636 93463 192636 96200 192637 93463 192637 96197 192637 93460 192638 93461 192638 96200 192638 96200 192639 93461 192639 96198 192639 96200 192640 96198 192640 96196 192640 93468 192641 93470 192641 96200 192641 96200 192642 93470 192642 93459 192642 96200 192643 93459 192643 93460 192643 96197 192644 96199 192644 96200 192644 96200 192645 96199 192645 93466 192645 96200 192646 93466 192646 93468 192646 96205 192647 96201 192647 96207 192647 96207 192648 96201 192648 93452 192648 96207 192649 93452 192649 96202 192649 93446 192650 96203 192650 96207 192650 96207 192651 96203 192651 96204 192651 96207 192652 96204 192652 96205 192652 96206 192653 93457 192653 96207 192653 96207 192654 93457 192654 93458 192654 96207 192655 93458 192655 93446 192655 96202 192656 96208 192656 96207 192656 96207 192657 96208 192657 93455 192657 96207 192658 93455 192658 96206 192658 94941 192659 93427 192659 94942 192659 94942 192660 93427 192660 93429 192660 94942 192661 93429 192661 96209 192661 96209 192662 93429 192662 96210 192662 96209 192663 96210 192663 96211 192663 96211 192664 96210 192664 93430 192664 96211 192665 93430 192665 96212 192665 96212 192666 93430 192666 96213 192666 96212 192667 96213 192667 94936 192667 94936 192668 96213 192668 93421 192668 94936 192669 93421 192669 96214 192669 96214 192670 93421 192670 93422 192670 96214 192671 93422 192671 96215 192671 96215 192672 93422 192672 96216 192672 96215 192673 96216 192673 96217 192673 96217 192674 96216 192674 96218 192674 96217 192675 96218 192675 96220 192675 96220 192676 96218 192676 96219 192676 96220 192677 96219 192677 96221 192677 96221 192678 96219 192678 93425 192678 96221 192679 93425 192679 96222 192679 96222 192680 93425 192680 96223 192680 96222 192681 96223 192681 94941 192681 94941 192682 96223 192682 93427 192682 96233 192683 96234 192683 94913 192683 94913 192684 96234 192684 96224 192684 94913 192685 96224 192685 94914 192685 94914 192686 96224 192686 96225 192686 94914 192687 96225 192687 94917 192687 94917 192688 96225 192688 96227 192688 94917 192689 96227 192689 96226 192689 96226 192690 96227 192690 96228 192690 96226 192691 96228 192691 94918 192691 94918 192692 96228 192692 93411 192692 94918 192693 93411 192693 94919 192693 94919 192694 93411 192694 93412 192694 94919 192695 93412 192695 96229 192695 96229 192696 93412 192696 93414 192696 96229 192697 93414 192697 94921 192697 94921 192698 93414 192698 96230 192698 94921 192699 96230 192699 94922 192699 94922 192700 96230 192700 93416 192700 94922 192701 93416 192701 94924 192701 94924 192702 93416 192702 93418 192702 94924 192703 93418 192703 96231 192703 96231 192704 93418 192704 96232 192704 96231 192705 96232 192705 96233 192705 96233 192706 96232 192706 96234 192706 96240 192707 93405 192707 94880 192707 94880 192708 93405 192708 96235 192708 94880 192709 96235 192709 94881 192709 94881 192710 96235 192710 93406 192710 94881 192711 93406 192711 94883 192711 94883 192712 93406 192712 93395 192712 94883 192713 93395 192713 94886 192713 94886 192714 93395 192714 93396 192714 94886 192715 93396 192715 94887 192715 94887 192716 93396 192716 93397 192716 94887 192717 93397 192717 94889 192717 94889 192718 93397 192718 96236 192718 94889 192719 96236 192719 94890 192719 94890 192720 96236 192720 96237 192720 94890 192721 96237 192721 94894 192721 94894 192722 96237 192722 96238 192722 94894 192723 96238 192723 94896 192723 94896 192724 96238 192724 93401 192724 94896 192725 93401 192725 96239 192725 96239 192726 93401 192726 93403 192726 96239 192727 93403 192727 94899 192727 94899 192728 93403 192728 93404 192728 94899 192729 93404 192729 96240 192729 96240 192730 93404 192730 93405 192730 94869 192731 96241 192731 94854 192731 94854 192732 96241 192732 93384 192732 94854 192733 93384 192733 94856 192733 94856 192734 93384 192734 96242 192734 94856 192735 96242 192735 94859 192735 94859 192736 96242 192736 93386 192736 94859 192737 93386 192737 96243 192737 96243 192738 93386 192738 93387 192738 96243 192739 93387 192739 94861 192739 94861 192740 93387 192740 96244 192740 94861 192741 96244 192741 96245 192741 96245 192742 96244 192742 96246 192742 96245 192743 96246 192743 96247 192743 96247 192744 96246 192744 96248 192744 96247 192745 96248 192745 94864 192745 94864 192746 96248 192746 96249 192746 94864 192747 96249 192747 94865 192747 94865 192748 96249 192748 93391 192748 94865 192749 93391 192749 94867 192749 94867 192750 93391 192750 96250 192750 94867 192751 96250 192751 94868 192751 94868 192752 96250 192752 93392 192752 94868 192753 93392 192753 94869 192753 94869 192754 93392 192754 96241 192754 94828 192755 96263 192755 96251 192755 96251 192756 96263 192756 93370 192756 96251 192757 93370 192757 96252 192757 96252 192758 93370 192758 93371 192758 96252 192759 93371 192759 94830 192759 94830 192760 93371 192760 93373 192760 94830 192761 93373 192761 94831 192761 94831 192762 93373 192762 96254 192762 94831 192763 96254 192763 96253 192763 96253 192764 96254 192764 93376 192764 96253 192765 93376 192765 96255 192765 96255 192766 93376 192766 96256 192766 96255 192767 96256 192767 96257 192767 96257 192768 96256 192768 96258 192768 96257 192769 96258 192769 96259 192769 96259 192770 96258 192770 96260 192770 96259 192771 96260 192771 94837 192771 94837 192772 96260 192772 96261 192772 94837 192773 96261 192773 94838 192773 94838 192774 96261 192774 93381 192774 94838 192775 93381 192775 94839 192775 94839 192776 93381 192776 96262 192776 94839 192777 96262 192777 94828 192777 94828 192778 96262 192778 96263 192778 94806 192779 96264 192779 94807 192779 94807 192780 96264 192780 93358 192780 94807 192781 93358 192781 96265 192781 96265 192782 93358 192782 93359 192782 96265 192783 93359 192783 96266 192783 96266 192784 93359 192784 93360 192784 96266 192785 93360 192785 96267 192785 96267 192786 93360 192786 93361 192786 96267 192787 93361 192787 96268 192787 96268 192788 93361 192788 96270 192788 96268 192789 96270 192789 96269 192789 96269 192790 96270 192790 93364 192790 96269 192791 93364 192791 96271 192791 96271 192792 93364 192792 93366 192792 96271 192793 93366 192793 94811 192793 94811 192794 93366 192794 96272 192794 94811 192795 96272 192795 94812 192795 94812 192796 96272 192796 96273 192796 94812 192797 96273 192797 96274 192797 96274 192798 96273 192798 96275 192798 96274 192799 96275 192799 94813 192799 94813 192800 96275 192800 93369 192800 94813 192801 93369 192801 94806 192801 94806 192802 93369 192802 96264 192802 94795 192803 93354 192803 96276 192803 96276 192804 93354 192804 93356 192804 96276 192805 93356 192805 94798 192805 94798 192806 93356 192806 96278 192806 94798 192807 96278 192807 96277 192807 96277 192808 96278 192808 96279 192808 96277 192809 96279 192809 94787 192809 94787 192810 96279 192810 96280 192810 94787 192811 96280 192811 94789 192811 94789 192812 96280 192812 96281 192812 94789 192813 96281 192813 94790 192813 94790 192814 96281 192814 96282 192814 94790 192815 96282 192815 94791 192815 94791 192816 96282 192816 93345 192816 94791 192817 93345 192817 94792 192817 94792 192818 93345 192818 96283 192818 94792 192819 96283 192819 96284 192819 96284 192820 96283 192820 93349 192820 96284 192821 93349 192821 96285 192821 96285 192822 93349 192822 93350 192822 96285 192823 93350 192823 96286 192823 96286 192824 93350 192824 93351 192824 96286 192825 93351 192825 94795 192825 94795 192826 93351 192826 93354 192826 96297 192827 96287 192827 94779 192827 94779 192828 96287 192828 96288 192828 94779 192829 96288 192829 94769 192829 94769 192830 96288 192830 93330 192830 94769 192831 93330 192831 94770 192831 94770 192832 93330 192832 93332 192832 94770 192833 93332 192833 94771 192833 94771 192834 93332 192834 93333 192834 94771 192835 93333 192835 94772 192835 94772 192836 93333 192836 93334 192836 94772 192837 93334 192837 96289 192837 96289 192838 93334 192838 96290 192838 96289 192839 96290 192839 94774 192839 94774 192840 96290 192840 96291 192840 94774 192841 96291 192841 94776 192841 94776 192842 96291 192842 96292 192842 94776 192843 96292 192843 94777 192843 94777 192844 96292 192844 96293 192844 94777 192845 96293 192845 96294 192845 96294 192846 96293 192846 96295 192846 96294 192847 96295 192847 94778 192847 94778 192848 96295 192848 96296 192848 94778 192849 96296 192849 96297 192849 96297 192850 96296 192850 96287 192850 94746 192851 96311 192851 96298 192851 96298 192852 96311 192852 96299 192852 96298 192853 96299 192853 96300 192853 96300 192854 96299 192854 93318 192854 96300 192855 93318 192855 96301 192855 96301 192856 93318 192856 93320 192856 96301 192857 93320 192857 96302 192857 96302 192858 93320 192858 93321 192858 96302 192859 93321 192859 96303 192859 96303 192860 93321 192860 96304 192860 96303 192861 96304 192861 96305 192861 96305 192862 96304 192862 96306 192862 96305 192863 96306 192863 94749 192863 94749 192864 96306 192864 96307 192864 94749 192865 96307 192865 96308 192865 96308 192866 96307 192866 93324 192866 96308 192867 93324 192867 96309 192867 96309 192868 93324 192868 93325 192868 96309 192869 93325 192869 94753 192869 94753 192870 93325 192870 93327 192870 94753 192871 93327 192871 94745 192871 94745 192872 93327 192872 96310 192872 94745 192873 96310 192873 94746 192873 94746 192874 96310 192874 96311 192874 96319 192875 96313 192875 96312 192875 96312 192876 96313 192876 93312 192876 96312 192877 93312 192877 94733 192877 94733 192878 93312 192878 93313 192878 94733 192879 93313 192879 96314 192879 96314 192880 93313 192880 96315 192880 96314 192881 96315 192881 96316 192881 96316 192882 96315 192882 93315 192882 96316 192883 93315 192883 94722 192883 94722 192884 93315 192884 96317 192884 94722 192885 96317 192885 94723 192885 94723 192886 96317 192886 93299 192886 94723 192887 93299 192887 94724 192887 94724 192888 93299 192888 93301 192888 94724 192889 93301 192889 94726 192889 94726 192890 93301 192890 93302 192890 94726 192891 93302 192891 96318 192891 96318 192892 93302 192892 93304 192892 96318 192893 93304 192893 94727 192893 94727 192894 93304 192894 93306 192894 94727 192895 93306 192895 94730 192895 94730 192896 93306 192896 93308 192896 94730 192897 93308 192897 96319 192897 96319 192898 93308 192898 96313 192898 96320 192899 93298 192899 94710 192899 94710 192900 93298 192900 96321 192900 94710 192901 96321 192901 94699 192901 94699 192902 96321 192902 96322 192902 94699 192903 96322 192903 94700 192903 94700 192904 96322 192904 93289 192904 94700 192905 93289 192905 96323 192905 96323 192906 93289 192906 96324 192906 96323 192907 96324 192907 94703 192907 94703 192908 96324 192908 93291 192908 94703 192909 93291 192909 96325 192909 96325 192910 93291 192910 96326 192910 96325 192911 96326 192911 94705 192911 94705 192912 96326 192912 96327 192912 94705 192913 96327 192913 96328 192913 96328 192914 96327 192914 96329 192914 96328 192915 96329 192915 94707 192915 94707 192916 96329 192916 93294 192916 94707 192917 93294 192917 96330 192917 96330 192918 93294 192918 93296 192918 96330 192919 93296 192919 96331 192919 96331 192920 93296 192920 93297 192920 96331 192921 93297 192921 96320 192921 96320 192922 93297 192922 93298 192922 94678 192923 96341 192923 94679 192923 94679 192924 96341 192924 96332 192924 94679 192925 96332 192925 94666 192925 94666 192926 96332 192926 93287 192926 94666 192927 93287 192927 94667 192927 94667 192928 93287 192928 93288 192928 94667 192929 93288 192929 94668 192929 94668 192930 93288 192930 93278 192930 94668 192931 93278 192931 96333 192931 96333 192932 93278 192932 93279 192932 96333 192933 93279 192933 96334 192933 96334 192934 93279 192934 93281 192934 96334 192935 93281 192935 96335 192935 96335 192936 93281 192936 93282 192936 96335 192937 93282 192937 96336 192937 96336 192938 93282 192938 96337 192938 96336 192939 96337 192939 96338 192939 96338 192940 96337 192940 96339 192940 96338 192941 96339 192941 94675 192941 94675 192942 96339 192942 93284 192942 94675 192943 93284 192943 94676 192943 94676 192944 93284 192944 96340 192944 94676 192945 96340 192945 94678 192945 94678 192946 96340 192946 96341 192946 96354 192947 96342 192947 94650 192947 94650 192948 96342 192948 93267 192948 94650 192949 93267 192949 94651 192949 94651 192950 93267 192950 93268 192950 94651 192951 93268 192951 96343 192951 96343 192952 93268 192952 93269 192952 96343 192953 93269 192953 96344 192953 96344 192954 93269 192954 93270 192954 96344 192955 93270 192955 96345 192955 96345 192956 93270 192956 96346 192956 96345 192957 96346 192957 94654 192957 94654 192958 96346 192958 93272 192958 94654 192959 93272 192959 96347 192959 96347 192960 93272 192960 93274 192960 96347 192961 93274 192961 96348 192961 96348 192962 93274 192962 93275 192962 96348 192963 93275 192963 96349 192963 96349 192964 93275 192964 96350 192964 96349 192965 96350 192965 96352 192965 96352 192966 96350 192966 96351 192966 96352 192967 96351 192967 96353 192967 96353 192968 96351 192968 93265 192968 96353 192969 93265 192969 96354 192969 96354 192970 93265 192970 96342 192970 96355 192971 96367 192971 94624 192971 94624 192972 96367 192972 93255 192972 94624 192973 93255 192973 94626 192973 94626 192974 93255 192974 96356 192974 94626 192975 96356 192975 96357 192975 96357 192976 96356 192976 96358 192976 96357 192977 96358 192977 94627 192977 94627 192978 96358 192978 93257 192978 94627 192979 93257 192979 94628 192979 94628 192980 93257 192980 96359 192980 94628 192981 96359 192981 94629 192981 94629 192982 96359 192982 93259 192982 94629 192983 93259 192983 96360 192983 96360 192984 93259 192984 96361 192984 96360 192985 96361 192985 94631 192985 94631 192986 96361 192986 96362 192986 94631 192987 96362 192987 96363 192987 96363 192988 96362 192988 93261 192988 96363 192989 93261 192989 96364 192989 96364 192990 93261 192990 93263 192990 96364 192991 93263 192991 96365 192991 96365 192992 93263 192992 96366 192992 96365 192993 96366 192993 96355 192993 96355 192994 96366 192994 96367 192994 94605 192995 93251 192995 96368 192995 96368 192996 93251 192996 96369 192996 96368 192997 96369 192997 96370 192997 96370 192998 96369 192998 96371 192998 96370 192999 96371 192999 96373 192999 96373 193000 96371 193000 96372 193000 96373 193001 96372 193001 96374 193001 96374 193002 96372 193002 96375 193002 96374 193003 96375 193003 94595 193003 94595 193004 96375 193004 93253 193004 94595 193005 93253 193005 94596 193005 94596 193006 93253 193006 96377 193006 94596 193007 96377 193007 96376 193007 96376 193008 96377 193008 96378 193008 96376 193009 96378 193009 94599 193009 94599 193010 96378 193010 93247 193010 94599 193011 93247 193011 94601 193011 94601 193012 93247 193012 93248 193012 94601 193013 93248 193013 94602 193013 94602 193014 93248 193014 93249 193014 94602 193015 93249 193015 94604 193015 94604 193016 93249 193016 96379 193016 94604 193017 96379 193017 94605 193017 94605 193018 96379 193018 93251 193018 94580 193019 96392 193019 96380 193019 96380 193020 96392 193020 96381 193020 96380 193021 96381 193021 94582 193021 94582 193022 96381 193022 96382 193022 94582 193023 96382 193023 94570 193023 94570 193024 96382 193024 96383 193024 94570 193025 96383 193025 96384 193025 96384 193026 96383 193026 96386 193026 96384 193027 96386 193027 96385 193027 96385 193028 96386 193028 93237 193028 96385 193029 93237 193029 96387 193029 96387 193030 93237 193030 93238 193030 96387 193031 93238 193031 96388 193031 96388 193032 93238 193032 96389 193032 96388 193033 96389 193033 96390 193033 96390 193034 96389 193034 93241 193034 96390 193035 93241 193035 94575 193035 94575 193036 93241 193036 96391 193036 94575 193037 96391 193037 94576 193037 94576 193038 96391 193038 93244 193038 94576 193039 93244 193039 94578 193039 94578 193040 93244 193040 93245 193040 94578 193041 93245 193041 94580 193041 94580 193042 93245 193042 96392 193042 96433 193043 96393 193043 96394 193043 96394 193044 96393 193044 96846 193044 96394 193045 96846 193045 96434 193045 96434 193046 96846 193046 96836 193046 96434 193047 96836 193047 96431 193047 96431 193048 96836 193048 96395 193048 96431 193049 96395 193049 96451 193049 96451 193050 96395 193050 96814 193050 96451 193051 96814 193051 96396 193051 96396 193052 96814 193052 96823 193052 96396 193053 96823 193053 96397 193053 96397 193054 96823 193054 96825 193054 96397 193055 96825 193055 96428 193055 96428 193056 96825 193056 96834 193056 96428 193057 96834 193057 96399 193057 96399 193058 96834 193058 96827 193058 96404 193059 96426 193059 96398 193059 96398 193060 96426 193060 96425 193060 96399 193061 96827 193061 96430 193061 96430 193062 96827 193062 96418 193062 96425 193063 96423 193063 96398 193063 96398 193064 96423 193064 96421 193064 96398 193065 96421 193065 96827 193065 96827 193066 96421 193066 96420 193066 96827 193067 96420 193067 96418 193067 96851 193068 96417 193068 96400 193068 96400 193069 96417 193069 96402 193069 96400 193070 96402 193070 96401 193070 96401 193071 96402 193071 96403 193071 96401 193072 96403 193072 96398 193072 96398 193073 96403 193073 96404 193073 96417 193074 96851 193074 96405 193074 96405 193075 96851 193075 96828 193075 96405 193076 96828 193076 96406 193076 96406 193077 96828 193077 96407 193077 96406 193078 96407 193078 96408 193078 96408 193079 96407 193079 96409 193079 96408 193080 96409 193080 96410 193080 96410 193081 96409 193081 96412 193081 96410 193082 96412 193082 96411 193082 96411 193083 96412 193083 96833 193083 96529 193084 96413 193084 96492 193084 96413 193085 96546 193085 96491 193085 96546 193086 96414 193086 96478 193086 96414 193087 96545 193087 96452 193087 96545 193088 96446 193088 96444 193088 96415 193089 96562 193089 96448 193089 96405 193090 96406 193090 96416 193090 96402 193091 96417 193091 96427 193091 96427 193092 96417 193092 96405 193092 96406 193093 96408 193093 96416 193093 96416 193094 96408 193094 96410 193094 96416 193095 96410 193095 96453 193095 96453 193096 96410 193096 96411 193096 96429 193097 96418 193097 96419 193097 96419 193098 96418 193098 96420 193098 96419 193099 96420 193099 96556 193099 96556 193100 96420 193100 96421 193100 96556 193101 96421 193101 96422 193101 96422 193102 96421 193102 96423 193102 96422 193103 96423 193103 96424 193103 96424 193104 96423 193104 96425 193104 96424 193105 96425 193105 96552 193105 96552 193106 96425 193106 96426 193106 96552 193107 96426 193107 96553 193107 96553 193108 96426 193108 96404 193108 96553 193109 96404 193109 96427 193109 96427 193110 96404 193110 96403 193110 96427 193111 96403 193111 96402 193111 96396 193112 96397 193112 96555 193112 96397 193113 96428 193113 96555 193113 96555 193114 96428 193114 96399 193114 96555 193115 96399 193115 96429 193115 96429 193116 96399 193116 96430 193116 96429 193117 96430 193117 96418 193117 96434 193118 96431 193118 96462 193118 96462 193119 96431 193119 96451 193119 96432 193120 96433 193120 96462 193120 96462 193121 96433 193121 96394 193121 96462 193122 96394 193122 96434 193122 96462 193123 96435 193123 96432 193123 96432 193124 96435 193124 96459 193124 96432 193125 96459 193125 96810 193125 96810 193126 96459 193126 96436 193126 96810 193127 96436 193127 96437 193127 96437 193128 96436 193128 96457 193128 96437 193129 96457 193129 96811 193129 96811 193130 96457 193130 96456 193130 96811 193131 96456 193131 96812 193131 96812 193132 96456 193132 96454 193132 96812 193133 96454 193133 96809 193133 96809 193134 96454 193134 96453 193134 96809 193135 96453 193135 96808 193135 96808 193136 96453 193136 96411 193136 96438 193137 96549 193137 96447 193137 96447 193138 96549 193138 96439 193138 96447 193139 96439 193139 96445 193139 96544 193140 96440 193140 96528 193140 96528 193141 96440 193141 96441 193141 96530 193142 96442 193142 96573 193142 96566 193143 96442 193143 96443 193143 96443 193144 96442 193144 96530 193144 96443 193145 96530 193145 96563 193145 96551 193146 96558 193146 96560 193146 96405 193147 96416 193147 96427 193147 96427 193148 96416 193148 96444 193148 96427 193149 96444 193149 96445 193149 96445 193150 96444 193150 96446 193150 96445 193151 96446 193151 96447 193151 96560 193152 96415 193152 96551 193152 96551 193153 96415 193153 96448 193153 96551 193154 96448 193154 96554 193154 96554 193155 96448 193155 96449 193155 96554 193156 96449 193156 96450 193156 96450 193157 96449 193157 96462 193157 96450 193158 96462 193158 96555 193158 96555 193159 96462 193159 96451 193159 96555 193160 96451 193160 96396 193160 96545 193161 96444 193161 96452 193161 96452 193162 96444 193162 96416 193162 96452 193163 96416 193163 96465 193163 96465 193164 96416 193164 96453 193164 96465 193165 96453 193165 96466 193165 96466 193166 96453 193166 96454 193166 96466 193167 96454 193167 96455 193167 96455 193168 96454 193168 96456 193168 96455 193169 96456 193169 96470 193169 96470 193170 96456 193170 96457 193170 96470 193171 96457 193171 96471 193171 96471 193172 96457 193172 96436 193172 96471 193173 96436 193173 96458 193173 96458 193174 96436 193174 96459 193174 96458 193175 96459 193175 96460 193175 96460 193176 96459 193176 96435 193176 96460 193177 96435 193177 96461 193177 96461 193178 96435 193178 96462 193178 96461 193179 96462 193179 96463 193179 96463 193180 96462 193180 96449 193180 96463 193181 96449 193181 96464 193181 96464 193182 96449 193182 96448 193182 96464 193183 96448 193183 96475 193183 96475 193184 96448 193184 96562 193184 96475 193185 96562 193185 96476 193185 96414 193186 96452 193186 96478 193186 96478 193187 96452 193187 96465 193187 96478 193188 96465 193188 96467 193188 96467 193189 96465 193189 96466 193189 96467 193190 96466 193190 96468 193190 96468 193191 96466 193191 96455 193191 96468 193192 96455 193192 96469 193192 96469 193193 96455 193193 96470 193193 96469 193194 96470 193194 96480 193194 96480 193195 96470 193195 96471 193195 96480 193196 96471 193196 96482 193196 96482 193197 96471 193197 96458 193197 96482 193198 96458 193198 96484 193198 96484 193199 96458 193199 96460 193199 96484 193200 96460 193200 96472 193200 96472 193201 96460 193201 96461 193201 96472 193202 96461 193202 96473 193202 96473 193203 96461 193203 96463 193203 96473 193204 96463 193204 96474 193204 96474 193205 96463 193205 96464 193205 96474 193206 96464 193206 96487 193206 96487 193207 96464 193207 96475 193207 96487 193208 96475 193208 96488 193208 96488 193209 96475 193209 96476 193209 96488 193210 96476 193210 96477 193210 96546 193211 96478 193211 96491 193211 96491 193212 96478 193212 96467 193212 96491 193213 96467 193213 96494 193213 96494 193214 96467 193214 96468 193214 96494 193215 96468 193215 96479 193215 96479 193216 96468 193216 96469 193216 96479 193217 96469 193217 96496 193217 96496 193218 96469 193218 96480 193218 96496 193219 96480 193219 96481 193219 96481 193220 96480 193220 96482 193220 96481 193221 96482 193221 96483 193221 96483 193222 96482 193222 96484 193222 96483 193223 96484 193223 96485 193223 96485 193224 96484 193224 96472 193224 96485 193225 96472 193225 96498 193225 96498 193226 96472 193226 96473 193226 96498 193227 96473 193227 96500 193227 96500 193228 96473 193228 96474 193228 96500 193229 96474 193229 96486 193229 96486 193230 96474 193230 96487 193230 96486 193231 96487 193231 96489 193231 96489 193232 96487 193232 96488 193232 96489 193233 96488 193233 96490 193233 96490 193234 96488 193234 96477 193234 96490 193235 96477 193235 96501 193235 96413 193236 96491 193236 96492 193236 96492 193237 96491 193237 96494 193237 96492 193238 96494 193238 96493 193238 96493 193239 96494 193239 96479 193239 96493 193240 96479 193240 96503 193240 96503 193241 96479 193241 96496 193241 96503 193242 96496 193242 96495 193242 96495 193243 96496 193243 96481 193243 96495 193244 96481 193244 96504 193244 96504 193245 96481 193245 96483 193245 96504 193246 96483 193246 96506 193246 96506 193247 96483 193247 96485 193247 96506 193248 96485 193248 96497 193248 96497 193249 96485 193249 96498 193249 96497 193250 96498 193250 96499 193250 96499 193251 96498 193251 96500 193251 96499 193252 96500 193252 96507 193252 96507 193253 96500 193253 96486 193253 96507 193254 96486 193254 96509 193254 96509 193255 96486 193255 96489 193255 96509 193256 96489 193256 96511 193256 96511 193257 96489 193257 96490 193257 96511 193258 96490 193258 96512 193258 96512 193259 96490 193259 96501 193259 96512 193260 96501 193260 96514 193260 96529 193261 96492 193261 96502 193261 96502 193262 96492 193262 96493 193262 96502 193263 96493 193263 96527 193263 96527 193264 96493 193264 96503 193264 96527 193265 96503 193265 96525 193265 96525 193266 96503 193266 96495 193266 96525 193267 96495 193267 96524 193267 96524 193268 96495 193268 96504 193268 96524 193269 96504 193269 96505 193269 96505 193270 96504 193270 96506 193270 96505 193271 96506 193271 96521 193271 96521 193272 96506 193272 96497 193272 96521 193273 96497 193273 96520 193273 96520 193274 96497 193274 96499 193274 96520 193275 96499 193275 96519 193275 96519 193276 96499 193276 96507 193276 96519 193277 96507 193277 96508 193277 96508 193278 96507 193278 96509 193278 96508 193279 96509 193279 96517 193279 96517 193280 96509 193280 96511 193280 96517 193281 96511 193281 96510 193281 96510 193282 96511 193282 96512 193282 96510 193283 96512 193283 96513 193283 96513 193284 96512 193284 96514 193284 96513 193285 96514 193285 96563 193285 96563 193286 96530 193286 96513 193286 96513 193287 96530 193287 96515 193287 96513 193288 96515 193288 96510 193288 96510 193289 96515 193289 96516 193289 96510 193290 96516 193290 96517 193290 96517 193291 96516 193291 96534 193291 96517 193292 96534 193292 96508 193292 96508 193293 96534 193293 96518 193293 96508 193294 96518 193294 96519 193294 96519 193295 96518 193295 96536 193295 96519 193296 96536 193296 96520 193296 96520 193297 96536 193297 96539 193297 96520 193298 96539 193298 96521 193298 96521 193299 96539 193299 96522 193299 96521 193300 96522 193300 96505 193300 96505 193301 96522 193301 96523 193301 96505 193302 96523 193302 96524 193302 96524 193303 96523 193303 96542 193303 96524 193304 96542 193304 96525 193304 96525 193305 96542 193305 96526 193305 96525 193306 96526 193306 96527 193306 96527 193307 96526 193307 96528 193307 96527 193308 96528 193308 96502 193308 96502 193309 96528 193309 96441 193309 96502 193310 96441 193310 96529 193310 96573 193311 96531 193311 96530 193311 96530 193312 96531 193312 96532 193312 96530 193313 96532 193313 96515 193313 96515 193314 96532 193314 96572 193314 96515 193315 96572 193315 96516 193315 96516 193316 96572 193316 96533 193316 96516 193317 96533 193317 96534 193317 96534 193318 96533 193318 96535 193318 96534 193319 96535 193319 96518 193319 96518 193320 96535 193320 96537 193320 96518 193321 96537 193321 96536 193321 96536 193322 96537 193322 96538 193322 96536 193323 96538 193323 96539 193323 96539 193324 96538 193324 96540 193324 96539 193325 96540 193325 96522 193325 96522 193326 96540 193326 96570 193326 96522 193327 96570 193327 96523 193327 96523 193328 96570 193328 96541 193328 96523 193329 96541 193329 96542 193329 96542 193330 96541 193330 96569 193330 96542 193331 96569 193331 96526 193331 96526 193332 96569 193332 96543 193332 96526 193333 96543 193333 96528 193333 96528 193334 96543 193334 96567 193334 96528 193335 96567 193335 96544 193335 96567 193336 96568 193336 96574 193336 96567 193337 96574 193337 96544 193337 96544 193338 96574 193338 96575 193338 96544 193339 96575 193339 96440 193339 96440 193340 96575 193340 96576 193340 96440 193341 96576 193341 96441 193341 96547 193342 96447 193342 96446 193342 96529 193343 96441 193343 96576 193343 96529 193344 96576 193344 96413 193344 96446 193345 96545 193345 96547 193345 96547 193346 96545 193346 96414 193346 96547 193347 96414 193347 96576 193347 96576 193348 96414 193348 96546 193348 96576 193349 96546 193349 96413 193349 96447 193350 96547 193350 96578 193350 96447 193351 96578 193351 96438 193351 96438 193352 96578 193352 96548 193352 96438 193353 96548 193353 96549 193353 96549 193354 96548 193354 96579 193354 96549 193355 96579 193355 96439 193355 96445 193356 96439 193356 96579 193356 96550 193357 96551 193357 96554 193357 96424 193358 96552 193358 96579 193358 96552 193359 96553 193359 96579 193359 96579 193360 96553 193360 96427 193360 96579 193361 96427 193361 96445 193361 96554 193362 96450 193362 96550 193362 96550 193363 96450 193363 96555 193363 96550 193364 96555 193364 96429 193364 96429 193365 96419 193365 96550 193365 96550 193366 96419 193366 96556 193366 96550 193367 96556 193367 96579 193367 96579 193368 96556 193368 96422 193368 96579 193369 96422 193369 96424 193369 96551 193370 96550 193370 96557 193370 96551 193371 96557 193371 96558 193371 96558 193372 96557 193372 96559 193372 96558 193373 96559 193373 96560 193373 96560 193374 96559 193374 96564 193374 96560 193375 96564 193375 96415 193375 96561 193376 96443 193376 96563 193376 96562 193377 96415 193377 96564 193377 96562 193378 96564 193378 96476 193378 96563 193379 96514 193379 96561 193379 96561 193380 96514 193380 96501 193380 96561 193381 96501 193381 96564 193381 96564 193382 96501 193382 96477 193382 96564 193383 96477 193383 96476 193383 96443 193384 96561 193384 96565 193384 96443 193385 96565 193385 96566 193385 96566 193386 96565 193386 96589 193386 96566 193387 96589 193387 96442 193387 96442 193388 96589 193388 96571 193388 96442 193389 96571 193389 96573 193389 96568 193390 96567 193390 96543 193390 96543 193391 96569 193391 96568 193391 96568 193392 96569 193392 96541 193392 96568 193393 96541 193393 96570 193393 96533 193394 96572 193394 96571 193394 96533 193395 96571 193395 96535 193395 96572 193396 96532 193396 96571 193396 96571 193397 96532 193397 96531 193397 96571 193398 96531 193398 96573 193398 96570 193399 96540 193399 96568 193399 96568 193400 96540 193400 96538 193400 96568 193401 96538 193401 96571 193401 96571 193402 96538 193402 96537 193402 96571 193403 96537 193403 96535 193403 96568 193404 96592 193404 96675 193404 96568 193405 96675 193405 96574 193405 96574 193406 96675 193406 96674 193406 96574 193407 96674 193407 96575 193407 96575 193408 96674 193408 96676 193408 96575 193409 96676 193409 96576 193409 96576 193410 96676 193410 96677 193410 96677 193411 96680 193411 96576 193411 96576 193412 96680 193412 96745 193412 96576 193413 96745 193413 96547 193413 96547 193414 96745 193414 96577 193414 96547 193415 96577 193415 96682 193415 96547 193416 96682 193416 96683 193416 96547 193417 96683 193417 96578 193417 96578 193418 96683 193418 96685 193418 96578 193419 96685 193419 96548 193419 96548 193420 96685 193420 96684 193420 96548 193421 96684 193421 96579 193421 96684 193422 96580 193422 96579 193422 96579 193423 96580 193423 96581 193423 96579 193424 96581 193424 96550 193424 96550 193425 96581 193425 96582 193425 96550 193426 96582 193426 96583 193426 96550 193427 96583 193427 96584 193427 96550 193428 96584 193428 96557 193428 96557 193429 96584 193429 96585 193429 96557 193430 96585 193430 96559 193430 96559 193431 96585 193431 96686 193431 96559 193432 96686 193432 96564 193432 96767 193433 96586 193433 96561 193433 96686 193434 96687 193434 96564 193434 96564 193435 96687 193435 96688 193435 96564 193436 96688 193436 96561 193436 96561 193437 96688 193437 96587 193437 96561 193438 96587 193438 96767 193438 96561 193439 96586 193439 96689 193439 96561 193440 96689 193440 96565 193440 96565 193441 96689 193441 96588 193441 96565 193442 96588 193442 96589 193442 96589 193443 96588 193443 96590 193443 96589 193444 96590 193444 96571 193444 96590 193445 96692 193445 96571 193445 96571 193446 96692 193446 96694 193446 96571 193447 96694 193447 96568 193447 96568 193448 96694 193448 96591 193448 96568 193449 96591 193449 96592 193449 96736 193450 96714 193450 96577 193450 96615 193451 95785 193451 96616 193451 95108 193452 96593 193452 96650 193452 95115 193453 96781 193453 96780 193453 96670 193454 94956 193454 96673 193454 96691 193455 94953 193455 96663 193455 96806 193456 94963 193456 96594 193456 96806 193457 96594 193457 96788 193457 96807 193458 95811 193458 96595 193458 96595 193459 95811 193459 96671 193459 96595 193460 96671 193460 94960 193460 94960 193461 96671 193461 94958 193461 96700 193462 95038 193462 95039 193462 95785 193463 96596 193463 95031 193463 95031 193464 96596 193464 96597 193464 96700 193465 95039 193465 96596 193465 96596 193466 95039 193466 95030 193466 96596 193467 95030 193467 96597 193467 96598 193468 96616 193468 96599 193468 96599 193469 96616 193469 95785 193469 96599 193470 95785 193470 95033 193470 95033 193471 95785 193471 95031 193471 96598 193472 95034 193472 96616 193472 96616 193473 95034 193473 96707 193473 96616 193474 96707 193474 96600 193474 95038 193475 96700 193475 95037 193475 95037 193476 96700 193476 96710 193476 95037 193477 96710 193477 96708 193477 96650 193478 96593 193478 96679 193478 95115 193479 96780 193479 95113 193479 95113 193480 96780 193480 96601 193480 95113 193481 96601 193481 95112 193481 95112 193482 96601 193482 96678 193482 95112 193483 96678 193483 95111 193483 95108 193484 96650 193484 96602 193484 96602 193485 96650 193485 96651 193485 96602 193486 96651 193486 96603 193486 96603 193487 96651 193487 96604 193487 96604 193488 96651 193488 96652 193488 96604 193489 96652 193489 96605 193489 96605 193490 96652 193490 95764 193490 96605 193491 95764 193491 96606 193491 96607 193492 95183 193492 96638 193492 96638 193493 95183 193493 95184 193493 95171 193494 95172 193494 95745 193494 95745 193495 95172 193495 95173 193495 95745 193496 95173 193496 96642 193496 95173 193497 96608 193497 96642 193497 96642 193498 96608 193498 95175 193498 96642 193499 95175 193499 96704 193499 96704 193500 95175 193500 95177 193500 95177 193501 95178 193501 96704 193501 96704 193502 95178 193502 95180 193502 96704 193503 95180 193503 96609 193503 96609 193504 95180 193504 96636 193504 96610 193505 95792 193505 96804 193505 96804 193506 95792 193506 96611 193506 96612 193507 96600 193507 96623 193507 96623 193508 96600 193508 96705 193508 96612 193509 96613 193509 96600 193509 96600 193510 96613 193510 94648 193510 96600 193511 94648 193511 94649 193511 96614 193512 96615 193512 95782 193512 95782 193513 96615 193513 96616 193513 95782 193514 96616 193514 95780 193514 95780 193515 96616 193515 96600 193515 95780 193516 96600 193516 95778 193516 95778 193517 96600 193517 94649 193517 94649 193518 96617 193518 95778 193518 95778 193519 96617 193519 96618 193519 95778 193520 96618 193520 95777 193520 95777 193521 96618 193521 96620 193521 95777 193522 96620 193522 96619 193522 96619 193523 96620 193523 96621 193523 96619 193524 96621 193524 95773 193524 95765 193525 95774 193525 96635 193525 96635 193526 95774 193526 95773 193526 96635 193527 95773 193527 96705 193527 96621 193528 94652 193528 95773 193528 95773 193529 94652 193529 94653 193529 95773 193530 94653 193530 96705 193530 96705 193531 94653 193531 96622 193531 96705 193532 96622 193532 96623 193532 96624 193533 95762 193533 94632 193533 94632 193534 95762 193534 96634 193534 96625 193535 94623 193535 96706 193535 96706 193536 94623 193536 96626 193536 96706 193537 96626 193537 94625 193537 94625 193538 96627 193538 96706 193538 96706 193539 96627 193539 96628 193539 96706 193540 96628 193540 96633 193540 96628 193541 96629 193541 96633 193541 96633 193542 96629 193542 96630 193542 96633 193543 96630 193543 94630 193543 96624 193544 94632 193544 96631 193544 96631 193545 94632 193545 96632 193545 96631 193546 96632 193546 96625 193546 96625 193547 96632 193547 94622 193547 96625 193548 94622 193548 94623 193548 94630 193549 96634 193549 96633 193549 96633 193550 96634 193550 95762 193550 96633 193551 95762 193551 96635 193551 96635 193552 95762 193552 95761 193552 96635 193553 95761 193553 95765 193553 96636 193554 96607 193554 96706 193554 96706 193555 96607 193555 96638 193555 96706 193556 96638 193556 96625 193556 96625 193557 96638 193557 96637 193557 95747 193558 96638 193558 95745 193558 95745 193559 96638 193559 95184 193559 95745 193560 95184 193560 95171 193560 95747 193561 95753 193561 96638 193561 96638 193562 95753 193562 95754 193562 96638 193563 95754 193563 96637 193563 96703 193564 96639 193564 96704 193564 96640 193565 96644 193565 96641 193565 96641 193566 96644 193566 96642 193566 96641 193567 96642 193567 94701 193567 96702 193568 96645 193568 94706 193568 96639 193569 94708 193569 96704 193569 96704 193570 94708 193570 94709 193570 96704 193571 94709 193571 96642 193571 96642 193572 94709 193572 94698 193572 96642 193573 94698 193573 94701 193573 95751 193574 96644 193574 96643 193574 96643 193575 96644 193575 96640 193575 96643 193576 96640 193576 95748 193576 95748 193577 96640 193577 94702 193577 95748 193578 94702 193578 96702 193578 96702 193579 94702 193579 94704 193579 96702 193580 94704 193580 96645 193580 95764 193581 96647 193581 95755 193581 96646 193582 95760 193582 96647 193582 96647 193583 95760 193583 95756 193583 96647 193584 95756 193584 95755 193584 95768 193585 96648 193585 95767 193585 95767 193586 96648 193586 95770 193586 96649 193587 94577 193587 96650 193587 96650 193588 94577 193588 94579 193588 94579 193589 96653 193589 96650 193589 96650 193590 96653 193590 95767 193590 96650 193591 95767 193591 96651 193591 96651 193592 95767 193592 95770 193592 96651 193593 95770 193593 96652 193593 94579 193594 94581 193594 96653 193594 96653 193595 94581 193595 96654 193595 96653 193596 96654 193596 95775 193596 95775 193597 96654 193597 96655 193597 95775 193598 96655 193598 96656 193598 96656 193599 96655 193599 94571 193599 96656 193600 94571 193600 95779 193600 96649 193601 96650 193601 96657 193601 96657 193602 96650 193602 96679 193602 96657 193603 96679 193603 96660 193603 96658 193604 96659 193604 96693 193604 96693 193605 96659 193605 95779 193605 96693 193606 95779 193606 96679 193606 94571 193607 94572 193607 95779 193607 95779 193608 94572 193608 94573 193608 95779 193609 94573 193609 96679 193609 96679 193610 94573 193610 94574 193610 96679 193611 94574 193611 96660 193611 96662 193612 96661 193612 94606 193612 94606 193613 94607 193613 96662 193613 96662 193614 94607 193614 94608 193614 96662 193615 94608 193615 94609 193615 94953 193616 96669 193616 96663 193616 96663 193617 96669 193617 96662 193617 96663 193618 96662 193618 94594 193618 94594 193619 96662 193619 94609 193619 94594 193620 96664 193620 96663 193620 96663 193621 96664 193621 94597 193621 96663 193622 94597 193622 96665 193622 94598 193623 95794 193623 96665 193623 96665 193624 95794 193624 95788 193624 96665 193625 95788 193625 96663 193625 96663 193626 95788 193626 96666 193626 96663 193627 96666 193627 96693 193627 96693 193628 96666 193628 96667 193628 96693 193629 96667 193629 96658 193629 94598 193630 94600 193630 95794 193630 95794 193631 94600 193631 96668 193631 95794 193632 96668 193632 96661 193632 96661 193633 96668 193633 94603 193633 96661 193634 94603 193634 94606 193634 96669 193635 96670 193635 96662 193635 96662 193636 96670 193636 96673 193636 96662 193637 96673 193637 96661 193637 96661 193638 96673 193638 96672 193638 95803 193639 95805 193639 95802 193639 95802 193640 95805 193640 96672 193640 95802 193641 96672 193641 96671 193641 96671 193642 96672 193642 96673 193642 96671 193643 96673 193643 94958 193643 94958 193644 96673 193644 94956 193644 95797 193645 95795 193645 96805 193645 95806 193646 95808 193646 95795 193646 95795 193647 95808 193647 95810 193647 95795 193648 95810 193648 96805 193648 96678 193649 96674 193649 96675 193649 96674 193650 96678 193650 96676 193650 96676 193651 96678 193651 96758 193651 96676 193652 96758 193652 96677 193652 96675 193653 96592 193653 96678 193653 96678 193654 96592 193654 96679 193654 96678 193655 96679 193655 95111 193655 95111 193656 96679 193656 96593 193656 96677 193657 96758 193657 96680 193657 96680 193658 96758 193658 96681 193658 96680 193659 96681 193659 96745 193659 96577 193660 96714 193660 96682 193660 96682 193661 96714 193661 96716 193661 96682 193662 96716 193662 96683 193662 96580 193663 96684 193663 96716 193663 96716 193664 96684 193664 96685 193664 96716 193665 96685 193665 96683 193665 96585 193666 96584 193666 96709 193666 96585 193667 96709 193667 96686 193667 96686 193668 96709 193668 96727 193668 96686 193669 96727 193669 96687 193669 96687 193670 96727 193670 96688 193670 96688 193671 96727 193671 96757 193671 96688 193672 96757 193672 96587 193672 96786 193673 96689 193673 96586 193673 96786 193674 96586 193674 96768 193674 96692 193675 96590 193675 96786 193675 96786 193676 96590 193676 96588 193676 96786 193677 96588 193677 96689 193677 96594 193678 96690 193678 96788 193678 96788 193679 96690 193679 96691 193679 96788 193680 96691 193680 96786 193680 96786 193681 96691 193681 96663 193681 96786 193682 96663 193682 96692 193682 96692 193683 96663 193683 96693 193683 96692 193684 96693 193684 96694 193684 96694 193685 96693 193685 96679 193685 96694 193686 96679 193686 96591 193686 96591 193687 96679 193687 96592 193687 94751 193688 94752 193688 96802 193688 94752 193689 96695 193689 96802 193689 96802 193690 96695 193690 96696 193690 96802 193691 96696 193691 96803 193691 96803 193692 96696 193692 94744 193692 94744 193693 96697 193693 96803 193693 96803 193694 96697 193694 96698 193694 96803 193695 96698 193695 96596 193695 96700 193696 94748 193696 94750 193696 96698 193697 96699 193697 96596 193697 96596 193698 96699 193698 96701 193698 96596 193699 96701 193699 96700 193699 96700 193700 96701 193700 94747 193700 96700 193701 94747 193701 94748 193701 94706 193702 96703 193702 96702 193702 96702 193703 96703 193703 96704 193703 96702 193704 96704 193704 95757 193704 95757 193705 96704 193705 96609 193705 95757 193706 96609 193706 96711 193706 96583 193707 96582 193707 96705 193707 96705 193708 96582 193708 96581 193708 96705 193709 96581 193709 96635 193709 96635 193710 96581 193710 96580 193710 96635 193711 96580 193711 96633 193711 96633 193712 96580 193712 96716 193712 96633 193713 96716 193713 96706 193713 96707 193714 96708 193714 96600 193714 96600 193715 96708 193715 96710 193715 96600 193716 96710 193716 96705 193716 96705 193717 96710 193717 96709 193717 96705 193718 96709 193718 96583 193718 96583 193719 96709 193719 96584 193719 94750 193720 94751 193720 96700 193720 96700 193721 94751 193721 96802 193721 96700 193722 96802 193722 96710 193722 96710 193723 96802 193723 96800 193723 96710 193724 96800 193724 96709 193724 96709 193725 96800 193725 96799 193725 94768 193726 96712 193726 96716 193726 96636 193727 96706 193727 96609 193727 96609 193728 96706 193728 96716 193728 96609 193729 96716 193729 96711 193729 96711 193730 96716 193730 96712 193730 96711 193731 96712 193731 96717 193731 96721 193732 96713 193732 96714 193732 96714 193733 96713 193733 96715 193733 96714 193734 96715 193734 96716 193734 96716 193735 96715 193735 94767 193735 96716 193736 94767 193736 94768 193736 96717 193737 94773 193737 96711 193737 96711 193738 94773 193738 96718 193738 96711 193739 96718 193739 95758 193739 96718 193740 96719 193740 95758 193740 95758 193741 96719 193741 94775 193741 95758 193742 94775 193742 96714 193742 96714 193743 94775 193743 96720 193743 96714 193744 96720 193744 96721 193744 94935 193745 96799 193745 94943 193745 94943 193746 96799 193746 96798 193746 94943 193747 96798 193747 96722 193747 96722 193748 96798 193748 96723 193748 96727 193749 96728 193749 96798 193749 96798 193750 96728 193750 96724 193750 96798 193751 96724 193751 96723 193751 94935 193752 96725 193752 96799 193752 96799 193753 96725 193753 96726 193753 96799 193754 96726 193754 96709 193754 96709 193755 96726 193755 94937 193755 94937 193756 94938 193756 96709 193756 96709 193757 94938 193757 94939 193757 96709 193758 94939 193758 96727 193758 96727 193759 94939 193759 94940 193759 96727 193760 94940 193760 96728 193760 96731 193761 96714 193761 94797 193761 94797 193762 96714 193762 96736 193762 94797 193763 96736 193763 94796 193763 94796 193764 96736 193764 96729 193764 96732 193765 95758 193765 96730 193765 96730 193766 95758 193766 96714 193766 96730 193767 96714 193767 94788 193767 94788 193768 96714 193768 96731 193768 96732 193769 96733 193769 95758 193769 95758 193770 96733 193770 94793 193770 95758 193771 94793 193771 96750 193771 94793 193772 96734 193772 96750 193772 96750 193773 96734 193773 94794 193773 96750 193774 94794 193774 96736 193774 96736 193775 94794 193775 96735 193775 96736 193776 96735 193776 96729 193776 96757 193777 96737 193777 96738 193777 96738 193778 96737 193778 94920 193778 96738 193779 94920 193779 96739 193779 96739 193780 94923 193780 96738 193780 96738 193781 94923 193781 94911 193781 96738 193782 94911 193782 96798 193782 96798 193783 94911 193783 96740 193783 96740 193784 96741 193784 96798 193784 96798 193785 96741 193785 94912 193785 96798 193786 94912 193786 96727 193786 96727 193787 94912 193787 94915 193787 94915 193788 94916 193788 96727 193788 96727 193789 94916 193789 96742 193789 96727 193790 96742 193790 96757 193790 96757 193791 96742 193791 96743 193791 96757 193792 96743 193792 96737 193792 96736 193793 96746 193793 96751 193793 96744 193794 96681 193794 94810 193794 94810 193795 96681 193795 96747 193795 96577 193796 96745 193796 96736 193796 96736 193797 96745 193797 96681 193797 96736 193798 96681 193798 96746 193798 96746 193799 96681 193799 96744 193799 96747 193800 96681 193800 96748 193800 96748 193801 96681 193801 96760 193801 96748 193802 96760 193802 94809 193802 94809 193803 96760 193803 96749 193803 96749 193804 96760 193804 96750 193804 96749 193805 96750 193805 94808 193805 96751 193806 96752 193806 96736 193806 96736 193807 96752 193807 96753 193807 96736 193808 96753 193808 96750 193808 96750 193809 96753 193809 96754 193809 96750 193810 96754 193810 94808 193810 94897 193811 94898 193811 96765 193811 96765 193812 94898 193812 94879 193812 96765 193813 94879 193813 96738 193813 96738 193814 94879 193814 96755 193814 96755 193815 94882 193815 96738 193815 96738 193816 94882 193816 94884 193816 96738 193817 94884 193817 96757 193817 96757 193818 94884 193818 94885 193818 96757 193819 94885 193819 94888 193819 96767 193820 96587 193820 96756 193820 96756 193821 96587 193821 96757 193821 96756 193822 96757 193822 94891 193822 94891 193823 96757 193823 94888 193823 94891 193824 94892 193824 96756 193824 96756 193825 94892 193825 94893 193825 96756 193826 94893 193826 96765 193826 96765 193827 94893 193827 94895 193827 96765 193828 94895 193828 94897 193828 94833 193829 94834 193829 96758 193829 96758 193830 94834 193830 94835 193830 96761 193831 96681 193831 96759 193831 96759 193832 96681 193832 96758 193832 96759 193833 96758 193833 94836 193833 94836 193834 96758 193834 94835 193834 96762 193835 96760 193835 94829 193835 94829 193836 96760 193836 96681 193836 94829 193837 96681 193837 94827 193837 94827 193838 96681 193838 96761 193838 96762 193839 96763 193839 96760 193839 96760 193840 96763 193840 96764 193840 96760 193841 96764 193841 96778 193841 96778 193842 96764 193842 94832 193842 94853 193843 96765 193843 96766 193843 96766 193844 96765 193844 96771 193844 96766 193845 96771 193845 96772 193845 96768 193846 96769 193846 94862 193846 94853 193847 94855 193847 96765 193847 96765 193848 94855 193848 94857 193848 96765 193849 94857 193849 96756 193849 96756 193850 94857 193850 94858 193850 96756 193851 94858 193851 94860 193851 96586 193852 96767 193852 96768 193852 96768 193853 96767 193853 96756 193853 96768 193854 96756 193854 96769 193854 96769 193855 96756 193855 94860 193855 96770 193856 94863 193856 96771 193856 96771 193857 94863 193857 94866 193857 96771 193858 94866 193858 96772 193858 96773 193859 94669 193859 96601 193859 94670 193860 96774 193860 96775 193860 96779 193861 94677 193861 96780 193861 96780 193862 94677 193862 94680 193862 96780 193863 94680 193863 96601 193863 96601 193864 94680 193864 96776 193864 96601 193865 96776 193865 96773 193865 94669 193866 94670 193866 96601 193866 96601 193867 94670 193867 96775 193867 96601 193868 96775 193868 96678 193868 96678 193869 96775 193869 96777 193869 96678 193870 96777 193870 96758 193870 96758 193871 96777 193871 96778 193871 96758 193872 96778 193872 94833 193872 94833 193873 96778 193873 94832 193873 96774 193874 94671 193874 96775 193874 96775 193875 94671 193875 94672 193875 96775 193876 94672 193876 95755 193876 95755 193877 94672 193877 94673 193877 95755 193878 94673 193878 94674 193878 94674 193879 96779 193879 95755 193879 95755 193880 96779 193880 96780 193880 95755 193881 96780 193881 95764 193881 95764 193882 96780 193882 96781 193882 95764 193883 96781 193883 96606 193883 96793 193884 96783 193884 96784 193884 94725 193885 96789 193885 96788 193885 96791 193886 94734 193886 96793 193886 96793 193887 94734 193887 96782 193887 96793 193888 96782 193888 96783 193888 96784 193889 94725 193889 96793 193889 96793 193890 94725 193890 96788 193890 96793 193891 96788 193891 96785 193891 96785 193892 96788 193892 96786 193892 96785 193893 96786 193893 96771 193893 96771 193894 96786 193894 96768 193894 96771 193895 96768 193895 96770 193895 96770 193896 96768 193896 94862 193896 94729 193897 96806 193897 96787 193897 96787 193898 96806 193898 96788 193898 96787 193899 96788 193899 94728 193899 94728 193900 96788 193900 96789 193900 94729 193901 96790 193901 96806 193901 96806 193902 96790 193902 94731 193902 96806 193903 94731 193903 96791 193903 96791 193904 94731 193904 94732 193904 96791 193905 94732 193905 94734 193905 95797 193906 96791 193906 95798 193906 95798 193907 96791 193907 96793 193907 95798 193908 96793 193908 96792 193908 96792 193909 96793 193909 96785 193909 96792 193910 96785 193910 96794 193910 96794 193911 96785 193911 96771 193911 96794 193912 96771 193912 96795 193912 96795 193913 96771 193913 96765 193913 96795 193914 96765 193914 96796 193914 96796 193915 96765 193915 96738 193915 96796 193916 96738 193916 96797 193916 96797 193917 96738 193917 96798 193917 96797 193918 96798 193918 95799 193918 95799 193919 96798 193919 96799 193919 95799 193920 96799 193920 96801 193920 96801 193921 96799 193921 96800 193921 96801 193922 96800 193922 95800 193922 95800 193923 96800 193923 96802 193923 95800 193924 96802 193924 96611 193924 96611 193925 96802 193925 96803 193925 96611 193926 96803 193926 96804 193926 95797 193927 96805 193927 96791 193927 96791 193928 96805 193928 95811 193928 96791 193929 95811 193929 96806 193929 96806 193930 95811 193930 96807 193930 96806 193931 96807 193931 94963 193931 96411 193932 96833 193932 96808 193932 96808 193933 96833 193933 96809 193933 96810 193934 96393 193934 96432 193934 96432 193935 96393 193935 96433 193935 96810 193936 96437 193936 96393 193936 96393 193937 96437 193937 96811 193937 96393 193938 96811 193938 96833 193938 96833 193939 96811 193939 96812 193939 96833 193940 96812 193940 96809 193940 96813 193941 96882 193941 96814 193941 96814 193942 96882 193942 96823 193942 96882 193943 96815 193943 96823 193943 96823 193944 96815 193944 96885 193944 96823 193945 96885 193945 96887 193945 96827 193946 96816 193946 96817 193946 96919 193947 96818 193947 96851 193947 96851 193948 96818 193948 96921 193948 96851 193949 96921 193949 96828 193949 96828 193950 96921 193950 96819 193950 96820 193951 96916 193951 96839 193951 96821 193952 96946 193952 96843 193952 96887 193953 96822 193953 96823 193953 96823 193954 96822 193954 96824 193954 96823 193955 96824 193955 96825 193955 96890 193956 96891 193956 96839 193956 96839 193957 96891 193957 96831 193957 96839 193958 96831 193958 96826 193958 96848 193959 96398 193959 96827 193959 96819 193960 96829 193960 96828 193960 96828 193961 96829 193961 96924 193961 96828 193962 96924 193962 96926 193962 96926 193963 96927 193963 96833 193963 96826 193964 96831 193964 96830 193964 96830 193965 96831 193965 96853 193965 96830 193966 96853 193966 96832 193966 96874 193967 96393 193967 96833 193967 96816 193968 96827 193968 96824 193968 96824 193969 96827 193969 96834 193969 96824 193970 96834 193970 96825 193970 96407 193971 96828 193971 96409 193971 96409 193972 96828 193972 96926 193972 96409 193973 96926 193973 96412 193973 96412 193974 96926 193974 96833 193974 96872 193975 96950 193975 96835 193975 96835 193976 96950 193976 96951 193976 96395 193977 96836 193977 96846 193977 96813 193978 96814 193978 96837 193978 96837 193979 96814 193979 96881 193979 96837 193980 96881 193980 96838 193980 96916 193981 96848 193981 96839 193981 96839 193982 96848 193982 96827 193982 96839 193983 96827 193983 96890 193983 96890 193984 96827 193984 96817 193984 96919 193985 96851 193985 96840 193985 96840 193986 96851 193986 96841 193986 96840 193987 96841 193987 96842 193987 96821 193988 96843 193988 96943 193988 96943 193989 96843 193989 96931 193989 96943 193990 96931 193990 96865 193990 96839 193991 96844 193991 96820 193991 96820 193992 96844 193992 96902 193992 96820 193993 96902 193993 96863 193993 96863 193994 96902 193994 96864 193994 96874 193995 96833 193995 96845 193995 96845 193996 96833 193996 96946 193996 96845 193997 96946 193997 96872 193997 96872 193998 96946 193998 96947 193998 96872 193999 96947 193999 96950 193999 96814 194000 96395 194000 96881 194000 96881 194001 96395 194001 96846 194001 96881 194002 96846 194002 96877 194002 96877 194003 96846 194003 96393 194003 96877 194004 96393 194004 96847 194004 96847 194005 96393 194005 96874 194005 96848 194006 96849 194006 96398 194006 96398 194007 96849 194007 96850 194007 96398 194008 96850 194008 96401 194008 96401 194009 96850 194009 96841 194009 96401 194010 96841 194010 96400 194010 96400 194011 96841 194011 96851 194011 96897 194012 96852 194012 96894 194012 96894 194013 96852 194013 96832 194013 96894 194014 96832 194014 96895 194014 96895 194015 96832 194015 96853 194015 96895 194016 96853 194016 96854 194016 96854 194017 96853 194017 96855 194017 96870 194018 96857 194018 96856 194018 96856 194019 96857 194019 96835 194019 96856 194020 96835 194020 96858 194020 96858 194021 96835 194021 96951 194021 96858 194022 96951 194022 96859 194022 96859 194023 96951 194023 96953 194023 96927 194024 96860 194024 96833 194024 96833 194025 96860 194025 96861 194025 96833 194026 96861 194026 96946 194026 96946 194027 96861 194027 96862 194027 96946 194028 96862 194028 96843 194028 96912 194029 96913 194029 96909 194029 96909 194030 96913 194030 96863 194030 96909 194031 96863 194031 96910 194031 96910 194032 96863 194032 96864 194032 96910 194033 96864 194033 96908 194033 96908 194034 96864 194034 96905 194034 96940 194035 96941 194035 96938 194035 96938 194036 96941 194036 96865 194036 96938 194037 96865 194037 96936 194037 96936 194038 96865 194038 96931 194038 96936 194039 96931 194039 96934 194039 96934 194040 96931 194040 96866 194040 96868 194041 96856 194041 96867 194041 96867 194042 96856 194042 96858 194042 96867 194043 96858 194043 96955 194043 96856 194044 96868 194044 96869 194044 96856 194045 96869 194045 96870 194045 96870 194046 96869 194046 97052 194046 96870 194047 97052 194047 96857 194047 96857 194048 97052 194048 96871 194048 96857 194049 96871 194049 96835 194049 96835 194050 96871 194050 96872 194050 96872 194051 96871 194051 97051 194051 96872 194052 97051 194052 96845 194052 96845 194053 97051 194053 96873 194053 96845 194054 96873 194054 96874 194054 96874 194055 96873 194055 96875 194055 96874 194056 96875 194056 96847 194056 96875 194057 96876 194057 96847 194057 96847 194058 96876 194058 96878 194058 96847 194059 96878 194059 96877 194059 96877 194060 96878 194060 96879 194060 96877 194061 96879 194061 96881 194061 96881 194062 96879 194062 97049 194062 97118 194063 96837 194063 96880 194063 96880 194064 96837 194064 96838 194064 96880 194065 96838 194065 97050 194065 97050 194066 96838 194066 96881 194066 97050 194067 96881 194067 97049 194067 96837 194068 97118 194068 96813 194068 96813 194069 97118 194069 97120 194069 96813 194070 97120 194070 96882 194070 96882 194071 97120 194071 96884 194071 96883 194072 96815 194072 96884 194072 96884 194073 96815 194073 96882 194073 96815 194074 96883 194074 96885 194074 96885 194075 96883 194075 97123 194075 96885 194076 97123 194076 96887 194076 96887 194077 97123 194077 96886 194077 96886 194078 97125 194078 96887 194078 96887 194079 97125 194079 96822 194079 97125 194080 96888 194080 96822 194080 96822 194081 96888 194081 97055 194081 96822 194082 97055 194082 96824 194082 96824 194083 97055 194083 96816 194083 96816 194084 97055 194084 96889 194084 96816 194085 96889 194085 96817 194085 96817 194086 96889 194086 97058 194086 96817 194087 97058 194087 96890 194087 96890 194088 97058 194088 97059 194088 96890 194089 97059 194089 96891 194089 96891 194090 97059 194090 96892 194090 96891 194091 96892 194091 96831 194091 96831 194092 96892 194092 97062 194092 96831 194093 97062 194093 96853 194093 96853 194094 97062 194094 97063 194094 96853 194095 97063 194095 97064 194095 96853 194096 97064 194096 96855 194096 96855 194097 97064 194097 97066 194097 96855 194098 97066 194098 96854 194098 96854 194099 97066 194099 97069 194099 96854 194100 97069 194100 96895 194100 96893 194101 96894 194101 97068 194101 97068 194102 96894 194102 96895 194102 97068 194103 96895 194103 97069 194103 96894 194104 96893 194104 96896 194104 96894 194105 96896 194105 96897 194105 96897 194106 96896 194106 97079 194106 96897 194107 97079 194107 96852 194107 96852 194108 97079 194108 96898 194108 96852 194109 96898 194109 96832 194109 96832 194110 96898 194110 96830 194110 96830 194111 96898 194111 96899 194111 96830 194112 96899 194112 96826 194112 96826 194113 96899 194113 96900 194113 96826 194114 96900 194114 96839 194114 96839 194115 96900 194115 97073 194115 96839 194116 97073 194116 96844 194116 96844 194117 97073 194117 96901 194117 96844 194118 96901 194118 96902 194118 96902 194119 96901 194119 97076 194119 96902 194120 97076 194120 96864 194120 96864 194121 97076 194121 96903 194121 96864 194122 96903 194122 96904 194122 96864 194123 96904 194123 96905 194123 96905 194124 96904 194124 96906 194124 96905 194125 96906 194125 96908 194125 96908 194126 96906 194126 96907 194126 96908 194127 96907 194127 96910 194127 97094 194128 96909 194128 96911 194128 96911 194129 96909 194129 96910 194129 96911 194130 96910 194130 96907 194130 96909 194131 97094 194131 97096 194131 96909 194132 97096 194132 96912 194132 96912 194133 97096 194133 96914 194133 96912 194134 96914 194134 96913 194134 96913 194135 96914 194135 96915 194135 96913 194136 96915 194136 96863 194136 96863 194137 96915 194137 96820 194137 96820 194138 96915 194138 97083 194138 96820 194139 97083 194139 96916 194139 96916 194140 97083 194140 96917 194140 96916 194141 96917 194141 96848 194141 96848 194142 96917 194142 97085 194142 96848 194143 97085 194143 96849 194143 96849 194144 97085 194144 96918 194144 96849 194145 96918 194145 96850 194145 96850 194146 96918 194146 97087 194146 96850 194147 97087 194147 96841 194147 96841 194148 97087 194148 97088 194148 97098 194149 96840 194149 97091 194149 97091 194150 96840 194150 96842 194150 97091 194151 96842 194151 97090 194151 97090 194152 96842 194152 96841 194152 97090 194153 96841 194153 97088 194153 96840 194154 97098 194154 96919 194154 96919 194155 97098 194155 96920 194155 96919 194156 96920 194156 96818 194156 96818 194157 96920 194157 97101 194157 96922 194158 96921 194158 97101 194158 97101 194159 96921 194159 96818 194159 96921 194160 96922 194160 96819 194160 96819 194161 96922 194161 97104 194161 96819 194162 97104 194162 96829 194162 96829 194163 97104 194163 96923 194163 96923 194164 97106 194164 96829 194164 96829 194165 97106 194165 96924 194165 97106 194166 96925 194166 96924 194166 96924 194167 96925 194167 97113 194167 96924 194168 97113 194168 96926 194168 96926 194169 97113 194169 96927 194169 96927 194170 97113 194170 96928 194170 96927 194171 96928 194171 96860 194171 96860 194172 96928 194172 96929 194172 96860 194173 96929 194173 96861 194173 96861 194174 96929 194174 96930 194174 96861 194175 96930 194175 96862 194175 96862 194176 96930 194176 97115 194176 96862 194177 97115 194177 96843 194177 96843 194178 97115 194178 97114 194178 96843 194179 97114 194179 96931 194179 96931 194180 97114 194180 96932 194180 96931 194181 96932 194181 96933 194181 96931 194182 96933 194182 96866 194182 96866 194183 96933 194183 96935 194183 96866 194184 96935 194184 96934 194184 96934 194185 96935 194185 97112 194185 96934 194186 97112 194186 96936 194186 97045 194187 96938 194187 96937 194187 96937 194188 96938 194188 96936 194188 96937 194189 96936 194189 97112 194189 96938 194190 97045 194190 96939 194190 96938 194191 96939 194191 96940 194191 96940 194192 96939 194192 97042 194192 96940 194193 97042 194193 96941 194193 96941 194194 97042 194194 96942 194194 96941 194195 96942 194195 96865 194195 96943 194196 96865 194196 96942 194196 96942 194197 97040 194197 96943 194197 96943 194198 97040 194198 96944 194198 96943 194199 96944 194199 96821 194199 96821 194200 96944 194200 96945 194200 96821 194201 96945 194201 96946 194201 96946 194202 96945 194202 96948 194202 96946 194203 96948 194203 96947 194203 96948 194204 97116 194204 96947 194204 96947 194205 97116 194205 96949 194205 96947 194206 96949 194206 96950 194206 96950 194207 96949 194207 97035 194207 96950 194208 97035 194208 96951 194208 96951 194209 97035 194209 97037 194209 96951 194210 97037 194210 96952 194210 96951 194211 96952 194211 96953 194211 96953 194212 96952 194212 96954 194212 96953 194213 96954 194213 96859 194213 96859 194214 96954 194214 96955 194214 96859 194215 96955 194215 96858 194215 93961 194216 97122 194216 93963 194216 93963 194217 97122 194217 97121 194217 93963 194218 97121 194218 93964 194218 93964 194219 97121 194219 96956 194219 93964 194220 96956 194220 93966 194220 93966 194221 96956 194221 96957 194221 93966 194222 96957 194222 96958 194222 96958 194223 96957 194223 97119 194223 96958 194224 97119 194224 94146 194224 94146 194225 97119 194225 96959 194225 94144 194226 94146 194226 96959 194226 94330 194227 94183 194227 96961 194227 96961 194228 94183 194228 94166 194228 96961 194229 94166 194229 96959 194229 96959 194230 94166 194230 94158 194230 96959 194231 94158 194231 94144 194231 94259 194232 94245 194232 97107 194232 97107 194233 94245 194233 94239 194233 97107 194234 94239 194234 96960 194234 96960 194235 94239 194235 94228 194235 94228 194236 94206 194236 96960 194236 96960 194237 94206 194237 94201 194237 96960 194238 94201 194238 96961 194238 96961 194239 94201 194239 94335 194239 96961 194240 94335 194240 94330 194240 94259 194241 97107 194241 94258 194241 94258 194242 97107 194242 96962 194242 97103 194243 96963 194243 97105 194243 97105 194244 96963 194244 96964 194244 97105 194245 96964 194245 96962 194245 96962 194246 96964 194246 96965 194246 96962 194247 96965 194247 94258 194247 96963 194248 97103 194248 93935 194248 93935 194249 97103 194249 97102 194249 93935 194250 97102 194250 96966 194250 96966 194251 97102 194251 97100 194251 96966 194252 97100 194252 96967 194252 96967 194253 97100 194253 97099 194253 97097 194254 94022 194254 97099 194254 97099 194255 94022 194255 96968 194255 97099 194256 96968 194256 96967 194256 94021 194257 94022 194257 97097 194257 96974 194258 96969 194258 96970 194258 96970 194259 96969 194259 94475 194259 96970 194260 94475 194260 96973 194260 96973 194261 94475 194261 96971 194261 96973 194262 96971 194262 94477 194262 94472 194263 97127 194263 94474 194263 94474 194264 97127 194264 96973 194264 94474 194265 96973 194265 96972 194265 96972 194266 96973 194266 94477 194266 94472 194267 94471 194267 97127 194267 97127 194268 94471 194268 94470 194268 97127 194269 94470 194269 97097 194269 97097 194270 94470 194270 94469 194270 97097 194271 94469 194271 94021 194271 96974 194272 96970 194272 94013 194272 94013 194273 96970 194273 96975 194273 94013 194274 96975 194274 94011 194274 94011 194275 96975 194275 96976 194275 97122 194276 93961 194276 97124 194276 97124 194277 93961 194277 93960 194277 97124 194278 93960 194278 96976 194278 96976 194279 93960 194279 93970 194279 96976 194280 93970 194280 94011 194280 96988 194281 97089 194281 97180 194281 97180 194282 97089 194282 96977 194282 97180 194283 96977 194283 97184 194283 97184 194284 96977 194284 96979 194284 97184 194285 96979 194285 96978 194285 96978 194286 96979 194286 96980 194286 96978 194287 96980 194287 96981 194287 96981 194288 96980 194288 97086 194288 96981 194289 97086 194289 96982 194289 96982 194290 97086 194290 97084 194290 96982 194291 97084 194291 97183 194291 97183 194292 97084 194292 97095 194292 97183 194293 97095 194293 97181 194293 97181 194294 97095 194294 96983 194294 97181 194295 96983 194295 96984 194295 96984 194296 96983 194296 97093 194296 96984 194297 97093 194297 97182 194297 97182 194298 97093 194298 97092 194298 97182 194299 97092 194299 96985 194299 96985 194300 97092 194300 96986 194300 96985 194301 96986 194301 97178 194301 97178 194302 96986 194302 96987 194302 97178 194303 96987 194303 96988 194303 96988 194304 96987 194304 97089 194304 97002 194305 96989 194305 96990 194305 96990 194306 96989 194306 97109 194306 96990 194307 97109 194307 97176 194307 97176 194308 97109 194308 96992 194308 97176 194309 96992 194309 96991 194309 96991 194310 96992 194310 96993 194310 96991 194311 96993 194311 97174 194311 97174 194312 96993 194312 97111 194312 97174 194313 97111 194313 97175 194313 97175 194314 97111 194314 97110 194314 97175 194315 97110 194315 96994 194315 96994 194316 97110 194316 96995 194316 96994 194317 96995 194317 97172 194317 97172 194318 96995 194318 96996 194318 97172 194319 96996 194319 97173 194319 97173 194320 96996 194320 97108 194320 97173 194321 97108 194321 96997 194321 96997 194322 97108 194322 96999 194322 96997 194323 96999 194323 96998 194323 96998 194324 96999 194324 97000 194324 96998 194325 97000 194325 97001 194325 97001 194326 97000 194326 97003 194326 97001 194327 97003 194327 97002 194327 97002 194328 97003 194328 96989 194328 97004 194329 97015 194329 97005 194329 97005 194330 97015 194330 97077 194330 97005 194331 97077 194331 97006 194331 97006 194332 97077 194332 97075 194332 97006 194333 97075 194333 97007 194333 97007 194334 97075 194334 97074 194334 97007 194335 97074 194335 97008 194335 97008 194336 97074 194336 97072 194336 97008 194337 97072 194337 97009 194337 97009 194338 97072 194338 97071 194338 97009 194339 97071 194339 97171 194339 97171 194340 97071 194340 97078 194340 97171 194341 97078 194341 97010 194341 97010 194342 97078 194342 97080 194342 97010 194343 97080 194343 97011 194343 97011 194344 97080 194344 97082 194344 97011 194345 97082 194345 97169 194345 97169 194346 97082 194346 97070 194346 97169 194347 97070 194347 97170 194347 97170 194348 97070 194348 97012 194348 97170 194349 97012 194349 97013 194349 97013 194350 97012 194350 97014 194350 97013 194351 97014 194351 97004 194351 97004 194352 97014 194352 97015 194352 97159 194353 97041 194353 97164 194353 97164 194354 97041 194354 97043 194354 97164 194355 97043 194355 97165 194355 97165 194356 97043 194356 97016 194356 97165 194357 97016 194357 97166 194357 97166 194358 97016 194358 97046 194358 97166 194359 97046 194359 97167 194359 97167 194360 97046 194360 97017 194360 97167 194361 97017 194361 97161 194361 97161 194362 97017 194362 97018 194362 97161 194363 97018 194363 97162 194363 97162 194364 97018 194364 97038 194364 97162 194365 97038 194365 97163 194365 97163 194366 97038 194366 97036 194366 97163 194367 97036 194367 97160 194367 97160 194368 97036 194368 97034 194368 97160 194369 97034 194369 97019 194369 97019 194370 97034 194370 97020 194370 97019 194371 97020 194371 97021 194371 97021 194372 97020 194372 97039 194372 97021 194373 97039 194373 97158 194373 97158 194374 97039 194374 97022 194374 97158 194375 97022 194375 97159 194375 97159 194376 97022 194376 97041 194376 97033 194377 97065 194377 97150 194377 97150 194378 97065 194378 97061 194378 97150 194379 97061 194379 97153 194379 97153 194380 97061 194380 97023 194380 97153 194381 97023 194381 97155 194381 97155 194382 97023 194382 97060 194382 97155 194383 97060 194383 97156 194383 97156 194384 97060 194384 97024 194384 97156 194385 97024 194385 97152 194385 97152 194386 97024 194386 97057 194386 97152 194387 97057 194387 97025 194387 97025 194388 97057 194388 97056 194388 97025 194389 97056 194389 97151 194389 97151 194390 97056 194390 97054 194390 97151 194391 97054 194391 97026 194391 97026 194392 97054 194392 97028 194392 97026 194393 97028 194393 97027 194393 97027 194394 97028 194394 97029 194394 97027 194395 97029 194395 97030 194395 97030 194396 97029 194396 97032 194396 97030 194397 97032 194397 97031 194397 97031 194398 97032 194398 97067 194398 97031 194399 97067 194399 97033 194399 97033 194400 97067 194400 97065 194400 97017 194401 96955 194401 97018 194401 97018 194402 96955 194402 96954 194402 97018 194403 96954 194403 97038 194403 97046 194404 97016 194404 97045 194404 97045 194405 97016 194405 97043 194405 97041 194406 97022 194406 97040 194406 96949 194407 97034 194407 97035 194407 97035 194408 97034 194408 97036 194408 97035 194409 97036 194409 97037 194409 97037 194410 97036 194410 97038 194410 97037 194411 97038 194411 96952 194411 96952 194412 97038 194412 96954 194412 97040 194413 97022 194413 96944 194413 96944 194414 97022 194414 97039 194414 96944 194415 97039 194415 97020 194415 97040 194416 96942 194416 97041 194416 97041 194417 96942 194417 97042 194417 97041 194418 97042 194418 97043 194418 97043 194419 97042 194419 96939 194419 97043 194420 96939 194420 97045 194420 97044 194421 97117 194421 97045 194421 97045 194422 97117 194422 96955 194422 97045 194423 96955 194423 97046 194423 97046 194424 96955 194424 97017 194424 97053 194425 97130 194425 96868 194425 96868 194426 97130 194426 97129 194426 96878 194427 97047 194427 96879 194427 96879 194428 97047 194428 97136 194428 96879 194429 97136 194429 97049 194429 97049 194430 97136 194430 97048 194430 97049 194431 97048 194431 97050 194431 97050 194432 97048 194432 97134 194432 97050 194433 97134 194433 96880 194433 96880 194434 97134 194434 97133 194434 97051 194435 97140 194435 97139 194435 97140 194436 97051 194436 97141 194436 97141 194437 97051 194437 96871 194437 97141 194438 96871 194438 97128 194438 97128 194439 96871 194439 97052 194439 97128 194440 97052 194440 97129 194440 97129 194441 97052 194441 96869 194441 97129 194442 96869 194442 96868 194442 97133 194443 97053 194443 96880 194443 96880 194444 97053 194444 96868 194444 96880 194445 96868 194445 97117 194445 97117 194446 96868 194446 96867 194446 97117 194447 96867 194447 96955 194447 96875 194448 96873 194448 96876 194448 96876 194449 96873 194449 97051 194449 96876 194450 97051 194450 96878 194450 96878 194451 97051 194451 97139 194451 96878 194452 97139 194452 97047 194452 96888 194453 97125 194453 97054 194453 97054 194454 97125 194454 97028 194454 96888 194455 97054 194455 97055 194455 97055 194456 97054 194456 97056 194456 97055 194457 97056 194457 96889 194457 96889 194458 97056 194458 97057 194458 96889 194459 97057 194459 97058 194459 97058 194460 97057 194460 97024 194460 97058 194461 97024 194461 97059 194461 97059 194462 97024 194462 97060 194462 97059 194463 97060 194463 96892 194463 96892 194464 97060 194464 97023 194464 96892 194465 97023 194465 97062 194465 97062 194466 97023 194466 97061 194466 97062 194467 97061 194467 97063 194467 97063 194468 97061 194468 97064 194468 97064 194469 97061 194469 97065 194469 97064 194470 97065 194470 97066 194470 97066 194471 97065 194471 97067 194471 97066 194472 97067 194472 97069 194472 97069 194473 97067 194473 97032 194473 97069 194474 97032 194474 97029 194474 96893 194475 97082 194475 97080 194475 96893 194476 97068 194476 97126 194476 97126 194477 97068 194477 97069 194477 97126 194478 97069 194478 97125 194478 97125 194479 97069 194479 97029 194479 97125 194480 97029 194480 97028 194480 97015 194481 97014 194481 96906 194481 96906 194482 97014 194482 96907 194482 96907 194483 97014 194483 97012 194483 96907 194484 97012 194484 97070 194484 97078 194485 96900 194485 96899 194485 97078 194486 97071 194486 96900 194486 96900 194487 97071 194487 97072 194487 96900 194488 97072 194488 97073 194488 97073 194489 97072 194489 97074 194489 97073 194490 97074 194490 96901 194490 96901 194491 97074 194491 97075 194491 96901 194492 97075 194492 97076 194492 97076 194493 97075 194493 97077 194493 97076 194494 97077 194494 96903 194494 96903 194495 97077 194495 97015 194495 96903 194496 97015 194496 96904 194496 96904 194497 97015 194497 96906 194497 96899 194498 96898 194498 97078 194498 97078 194499 96898 194499 97079 194499 97078 194500 97079 194500 97080 194500 97080 194501 97079 194501 96896 194501 97080 194502 96896 194502 96893 194502 97094 194503 96911 194503 97081 194503 97081 194504 96911 194504 96907 194504 97081 194505 96907 194505 96893 194505 96893 194506 96907 194506 97070 194506 96893 194507 97070 194507 97082 194507 97095 194508 96917 194508 97083 194508 97095 194509 97084 194509 96917 194509 96917 194510 97084 194510 97086 194510 96917 194511 97086 194511 97085 194511 97085 194512 97086 194512 96980 194512 97085 194513 96980 194513 96918 194513 96918 194514 96980 194514 96979 194514 96918 194515 96979 194515 97087 194515 97087 194516 96979 194516 96977 194516 97087 194517 96977 194517 97088 194517 97088 194518 96977 194518 97089 194518 97088 194519 97089 194519 97090 194519 97090 194520 97089 194520 96987 194520 97090 194521 96987 194521 97091 194521 96987 194522 96986 194522 97091 194522 97091 194523 96986 194523 97092 194523 97091 194524 97092 194524 97094 194524 97094 194525 97092 194525 97093 194525 97094 194526 97093 194526 96983 194526 97083 194527 96915 194527 97095 194527 97095 194528 96915 194528 96914 194528 97095 194529 96914 194529 96983 194529 96983 194530 96914 194530 97096 194530 96983 194531 97096 194531 97094 194531 96893 194532 97126 194532 97081 194532 97081 194533 97126 194533 97127 194533 97081 194534 97127 194534 97097 194534 97094 194535 97081 194535 97091 194535 97091 194536 97081 194536 97097 194536 97091 194537 97097 194537 97098 194537 97098 194538 97097 194538 97099 194538 97098 194539 97099 194539 96920 194539 96920 194540 97099 194540 97100 194540 96920 194541 97100 194541 97101 194541 97101 194542 97100 194542 97102 194542 97101 194543 97102 194543 96922 194543 96922 194544 97102 194544 97103 194544 96922 194545 97103 194545 97104 194545 97104 194546 97103 194546 97105 194546 97104 194547 97105 194547 96923 194547 96923 194548 97105 194548 96962 194548 96923 194549 96962 194549 97106 194549 97106 194550 96962 194550 97107 194550 97106 194551 97107 194551 97044 194551 96999 194552 97108 194552 97114 194552 96929 194553 97000 194553 96999 194553 97106 194554 96992 194554 97109 194554 97114 194555 97108 194555 96932 194555 96932 194556 97108 194556 96996 194556 96932 194557 96996 194557 96933 194557 96933 194558 96996 194558 96995 194558 96933 194559 96995 194559 96935 194559 96935 194560 96995 194560 97110 194560 96935 194561 97110 194561 97112 194561 97112 194562 97110 194562 97111 194562 97112 194563 97111 194563 96993 194563 97045 194564 96937 194564 97044 194564 97044 194565 96937 194565 97112 194565 97044 194566 97112 194566 97106 194566 97106 194567 97112 194567 96993 194567 97106 194568 96993 194568 96992 194568 97000 194569 96929 194569 97003 194569 97003 194570 96929 194570 96928 194570 97003 194571 96928 194571 96989 194571 96989 194572 96928 194572 97113 194572 96989 194573 97113 194573 97109 194573 97109 194574 97113 194574 96925 194574 97109 194575 96925 194575 97106 194575 96999 194576 97114 194576 96929 194576 96929 194577 97114 194577 97115 194577 96929 194578 97115 194578 96930 194578 96948 194579 96945 194579 97116 194579 97116 194580 96945 194580 96944 194580 97116 194581 96944 194581 96949 194581 96949 194582 96944 194582 97020 194582 96949 194583 97020 194583 97034 194583 97107 194584 96960 194584 97044 194584 97044 194585 96960 194585 96961 194585 97044 194586 96961 194586 97117 194586 97117 194587 96961 194587 96959 194587 97117 194588 96959 194588 96880 194588 96880 194589 96959 194589 97119 194589 96880 194590 97119 194590 97118 194590 97118 194591 97119 194591 96957 194591 97118 194592 96957 194592 97120 194592 97120 194593 96957 194593 96956 194593 97120 194594 96956 194594 96884 194594 96884 194595 96956 194595 97121 194595 96884 194596 97121 194596 96883 194596 96883 194597 97121 194597 97122 194597 96883 194598 97122 194598 97123 194598 97122 194599 97124 194599 97123 194599 97123 194600 97124 194600 96976 194600 97123 194601 96976 194601 96886 194601 96886 194602 96976 194602 96975 194602 96886 194603 96975 194603 97125 194603 97125 194604 96975 194604 96970 194604 97125 194605 96970 194605 97126 194605 97126 194606 96970 194606 96973 194606 97126 194607 96973 194607 97127 194607 97142 194608 97128 194608 97147 194608 97147 194609 97128 194609 97129 194609 97147 194610 97129 194610 97148 194610 97148 194611 97129 194611 97130 194611 97148 194612 97130 194612 97131 194612 97131 194613 97130 194613 97053 194613 97131 194614 97053 194614 97132 194614 97132 194615 97053 194615 97133 194615 97132 194616 97133 194616 97145 194616 97145 194617 97133 194617 97134 194617 97145 194618 97134 194618 97146 194618 97146 194619 97134 194619 97048 194619 97146 194620 97048 194620 97135 194620 97135 194621 97048 194621 97136 194621 97135 194622 97136 194622 97137 194622 97137 194623 97136 194623 97047 194623 97137 194624 97047 194624 97138 194624 97138 194625 97047 194625 97139 194625 97138 194626 97139 194626 97144 194626 97144 194627 97139 194627 97140 194627 97144 194628 97140 194628 97143 194628 97143 194629 97140 194629 97141 194629 97143 194630 97141 194630 97142 194630 97142 194631 97141 194631 97128 194631 97144 194632 97143 194632 97149 194632 97149 194633 97143 194633 97142 194633 97149 194634 97142 194634 97147 194634 97135 194635 97137 194635 97149 194635 97149 194636 97137 194636 97138 194636 97149 194637 97138 194637 97144 194637 97132 194638 97145 194638 97149 194638 97149 194639 97145 194639 97146 194639 97149 194640 97146 194640 97135 194640 97147 194641 97148 194641 97149 194641 97149 194642 97148 194642 97131 194642 97149 194643 97131 194643 97132 194643 97030 194644 97031 194644 97154 194644 97154 194645 97031 194645 97033 194645 97154 194646 97033 194646 97150 194646 97151 194647 97026 194647 97154 194647 97154 194648 97026 194648 97027 194648 97154 194649 97027 194649 97030 194649 97156 194650 97152 194650 97154 194650 97154 194651 97152 194651 97025 194651 97154 194652 97025 194652 97151 194652 97150 194653 97153 194653 97154 194653 97154 194654 97153 194654 97155 194654 97154 194655 97155 194655 97156 194655 97021 194656 97158 194656 97157 194656 97157 194657 97158 194657 97159 194657 97157 194658 97159 194658 97164 194658 97163 194659 97160 194659 97157 194659 97157 194660 97160 194660 97019 194660 97157 194661 97019 194661 97021 194661 97167 194662 97161 194662 97157 194662 97157 194663 97161 194663 97162 194663 97157 194664 97162 194664 97163 194664 97164 194665 97165 194665 97157 194665 97157 194666 97165 194666 97166 194666 97157 194667 97166 194667 97167 194667 97170 194668 97013 194668 97168 194668 97168 194669 97013 194669 97004 194669 97168 194670 97004 194670 97005 194670 97010 194671 97011 194671 97168 194671 97168 194672 97011 194672 97169 194672 97168 194673 97169 194673 97170 194673 97008 194674 97009 194674 97168 194674 97168 194675 97009 194675 97171 194675 97168 194676 97171 194676 97010 194676 97005 194677 97006 194677 97168 194677 97168 194678 97006 194678 97007 194678 97168 194679 97007 194679 97008 194679 96998 194680 97001 194680 97177 194680 97177 194681 97001 194681 97002 194681 97177 194682 97002 194682 96990 194682 97172 194683 97173 194683 97177 194683 97177 194684 97173 194684 96997 194684 97177 194685 96997 194685 96998 194685 97174 194686 97175 194686 97177 194686 97177 194687 97175 194687 96994 194687 97177 194688 96994 194688 97172 194688 96990 194689 97176 194689 97177 194689 97177 194690 97176 194690 96991 194690 97177 194691 96991 194691 97174 194691 96985 194692 97178 194692 97179 194692 97179 194693 97178 194693 96988 194693 97179 194694 96988 194694 97180 194694 97181 194695 96984 194695 97179 194695 97179 194696 96984 194696 97182 194696 97179 194697 97182 194697 96985 194697 96981 194698 96982 194698 97179 194698 97179 194699 96982 194699 97183 194699 97179 194700 97183 194700 97181 194700 97180 194701 97184 194701 97179 194701 97179 194702 97184 194702 96978 194702 97179 194703 96978 194703 96981 194703 97188 194704 97185 194704 97211 194704 97186 194705 97196 194705 97208 194705 97208 194706 97196 194706 97192 194706 97201 194707 97200 194707 97202 194707 97202 194708 97200 194708 97191 194708 97202 194709 97191 194709 97203 194709 97186 194710 97208 194710 97211 194710 97211 194711 97208 194711 97187 194711 97211 194712 97187 194712 97188 194712 97204 194713 97206 194713 97189 194713 97189 194714 97206 194714 97190 194714 97189 194715 97190 194715 97191 194715 97191 194716 97190 194716 97208 194716 97191 194717 97208 194717 97203 194717 97203 194718 97208 194718 97192 194718 97203 194719 97192 194719 97193 194719 97218 194720 97203 194720 97194 194720 97194 194721 97203 194721 97193 194721 97194 194722 97193 194722 97195 194722 97195 194723 97193 194723 97192 194723 97195 194724 97192 194724 97216 194724 97216 194725 97192 194725 97196 194725 97216 194726 97196 194726 97217 194726 97217 194727 97196 194727 97186 194727 97197 194728 97191 194728 97198 194728 97198 194729 97191 194729 97200 194729 97198 194730 97200 194730 97199 194730 97199 194731 97200 194731 97201 194731 97199 194732 97201 194732 97220 194732 97220 194733 97201 194733 97202 194733 97202 194734 97203 194734 97220 194734 97220 194735 97203 194735 97218 194735 97189 194736 97205 194736 97204 194736 97204 194737 97205 194737 97207 194737 97204 194738 97207 194738 97206 194738 97206 194739 97207 194739 97219 194739 97206 194740 97219 194740 97190 194740 97190 194741 97219 194741 97212 194741 97208 194742 97209 194742 97187 194742 97187 194743 97209 194743 97210 194743 97187 194744 97210 194744 97188 194744 97188 194745 97210 194745 97215 194745 97188 194746 97215 194746 97185 194746 97185 194747 97215 194747 97214 194747 97185 194748 97214 194748 97211 194748 97211 194749 97214 194749 97213 194749 97208 194750 97190 194750 97209 194750 97209 194751 97190 194751 97212 194751 97217 194752 97186 194752 97213 194752 97213 194753 97186 194753 97211 194753 97205 194754 97189 194754 97197 194754 97197 194755 97189 194755 97191 194755 97214 194756 97215 194756 97213 194756 97213 194757 97215 194757 97210 194757 97213 194758 97210 194758 97209 194758 97197 194759 97198 194759 97199 194759 97195 194760 97216 194760 97194 194760 97194 194761 97216 194761 97217 194761 97194 194762 97217 194762 97218 194762 97218 194763 97217 194763 97213 194763 97218 194764 97213 194764 97220 194764 97220 194765 97213 194765 97209 194765 97219 194766 97207 194766 97212 194766 97212 194767 97207 194767 97205 194767 97212 194768 97205 194768 97209 194768 97209 194769 97205 194769 97197 194769 97209 194770 97197 194770 97220 194770 97220 194771 97197 194771 97199 194771 97226 194772 97223 194772 97228 194772 97231 194773 97221 194773 97229 194773 97229 194774 97221 194774 97228 194774 97229 194775 97228 194775 97222 194775 97222 194776 97228 194776 97223 194776 97228 194777 97245 194777 97226 194777 97226 194778 97245 194778 97224 194778 97226 194779 97224 194779 97241 194779 97225 194780 97233 194780 97232 194780 97232 194781 97233 194781 97226 194781 97232 194782 97226 194782 97244 194782 97244 194783 97226 194783 97241 194783 97244 194784 97241 194784 97227 194784 97237 194785 97239 194785 97236 194785 97236 194786 97239 194786 97228 194786 97236 194787 97228 194787 97248 194787 97248 194788 97228 194788 97221 194788 97223 194789 97250 194789 97222 194789 97222 194790 97250 194790 97249 194790 97222 194791 97249 194791 97229 194791 97229 194792 97249 194792 97230 194792 97229 194793 97230 194793 97231 194793 97231 194794 97230 194794 97258 194794 97231 194795 97258 194795 97221 194795 97221 194796 97258 194796 97252 194796 97232 194797 97247 194797 97225 194797 97225 194798 97247 194798 97255 194798 97225 194799 97255 194799 97233 194799 97233 194800 97255 194800 97234 194800 97233 194801 97234 194801 97226 194801 97226 194802 97234 194802 97235 194802 97250 194803 97223 194803 97235 194803 97235 194804 97223 194804 97226 194804 97248 194805 97251 194805 97236 194805 97236 194806 97251 194806 97254 194806 97236 194807 97254 194807 97237 194807 97237 194808 97254 194808 97238 194808 97237 194809 97238 194809 97239 194809 97239 194810 97238 194810 97240 194810 97239 194811 97240 194811 97228 194811 97228 194812 97240 194812 97253 194812 97245 194813 97246 194813 97224 194813 97224 194814 97246 194814 97242 194814 97224 194815 97242 194815 97241 194815 97241 194816 97242 194816 97257 194816 97241 194817 97257 194817 97227 194817 97227 194818 97257 194818 97243 194818 97227 194819 97243 194819 97244 194819 97244 194820 97243 194820 97256 194820 97245 194821 97228 194821 97246 194821 97246 194822 97228 194822 97253 194822 97247 194823 97232 194823 97256 194823 97256 194824 97232 194824 97244 194824 97251 194825 97248 194825 97252 194825 97252 194826 97248 194826 97221 194826 97230 194827 97249 194827 97250 194827 97251 194828 97252 194828 97253 194828 97253 194829 97252 194829 97258 194829 97240 194830 97238 194830 97253 194830 97253 194831 97238 194831 97254 194831 97253 194832 97254 194832 97251 194832 97234 194833 97255 194833 97235 194833 97235 194834 97255 194834 97247 194834 97247 194835 97256 194835 97235 194835 97235 194836 97256 194836 97243 194836 97235 194837 97243 194837 97257 194837 97258 194838 97230 194838 97253 194838 97253 194839 97230 194839 97250 194839 97253 194840 97250 194840 97246 194840 97246 194841 97250 194841 97235 194841 97246 194842 97235 194842 97242 194842 97242 194843 97235 194843 97257 194843 97283 194844 97259 194844 97262 194844 97262 194845 97259 194845 97284 194845 97262 194846 97284 194846 97286 194846 97268 194847 97265 194847 97291 194847 97291 194848 97265 194848 97262 194848 97291 194849 97262 194849 97260 194849 97260 194850 97262 194850 97286 194850 97260 194851 97286 194851 97261 194851 97262 194852 97275 194852 97283 194852 97283 194853 97275 194853 97274 194853 97283 194854 97274 194854 97272 194854 97277 194855 97278 194855 97263 194855 97263 194856 97282 194856 97277 194856 97277 194857 97282 194857 97283 194857 97277 194858 97283 194858 97270 194858 97270 194859 97283 194859 97272 194859 97270 194860 97272 194860 97271 194860 97296 194861 97262 194861 97264 194861 97264 194862 97262 194862 97265 194862 97264 194863 97265 194863 97266 194863 97266 194864 97265 194864 97268 194864 97266 194865 97268 194865 97267 194865 97267 194866 97268 194866 97291 194866 97293 194867 97270 194867 97269 194867 97269 194868 97270 194868 97271 194868 97269 194869 97271 194869 97292 194869 97292 194870 97271 194870 97272 194870 97292 194871 97272 194871 97273 194871 97273 194872 97272 194872 97274 194872 97273 194873 97274 194873 97276 194873 97276 194874 97274 194874 97275 194874 97275 194875 97262 194875 97276 194875 97276 194876 97262 194876 97296 194876 97277 194877 97279 194877 97278 194877 97278 194878 97279 194878 97280 194878 97278 194879 97280 194879 97263 194879 97263 194880 97280 194880 97281 194880 97263 194881 97281 194881 97282 194881 97282 194882 97281 194882 97294 194882 97282 194883 97294 194883 97283 194883 97283 194884 97294 194884 97295 194884 97259 194885 97290 194885 97284 194885 97284 194886 97290 194886 97285 194886 97284 194887 97285 194887 97286 194887 97286 194888 97285 194888 97287 194888 97286 194889 97287 194889 97261 194889 97261 194890 97287 194890 97288 194890 97261 194891 97288 194891 97260 194891 97260 194892 97288 194892 97289 194892 97259 194893 97283 194893 97290 194893 97290 194894 97283 194894 97295 194894 97267 194895 97291 194895 97289 194895 97289 194896 97291 194896 97260 194896 97279 194897 97277 194897 97293 194897 97293 194898 97277 194898 97270 194898 97292 194899 97273 194899 97276 194899 97287 194900 97285 194900 97290 194900 97279 194901 97293 194901 97295 194901 97295 194902 97293 194902 97269 194902 97296 194903 97289 194903 97288 194903 97294 194904 97281 194904 97295 194904 97295 194905 97281 194905 97280 194905 97295 194906 97280 194906 97279 194906 97264 194907 97266 194907 97296 194907 97296 194908 97266 194908 97267 194908 97296 194909 97267 194909 97289 194909 97288 194910 97287 194910 97296 194910 97296 194911 97287 194911 97290 194911 97296 194912 97290 194912 97276 194912 97276 194913 97290 194913 97295 194913 97276 194914 97295 194914 97292 194914 97292 194915 97295 194915 97269 194915 97303 194916 97297 194916 97298 194916 97318 194917 97319 194917 97322 194917 97299 194918 97306 194918 97304 194918 97304 194919 97303 194919 97299 194919 97299 194920 97303 194920 97298 194920 97299 194921 97298 194921 97300 194921 97300 194922 97298 194922 97309 194922 97300 194923 97309 194923 97301 194923 97306 194924 97299 194924 97322 194924 97322 194925 97299 194925 97315 194925 97322 194926 97315 194926 97318 194926 97312 194927 97313 194927 97310 194927 97310 194928 97313 194928 97300 194928 97310 194929 97300 194929 97307 194929 97307 194930 97300 194930 97301 194930 97307 194931 97301 194931 97308 194931 97302 194932 97298 194932 97326 194932 97326 194933 97298 194933 97297 194933 97326 194934 97297 194934 97324 194934 97324 194935 97297 194935 97303 194935 97324 194936 97303 194936 97325 194936 97325 194937 97303 194937 97304 194937 97325 194938 97304 194938 97305 194938 97305 194939 97304 194939 97306 194939 97323 194940 97307 194940 97331 194940 97331 194941 97307 194941 97308 194941 97331 194942 97308 194942 97332 194942 97332 194943 97308 194943 97301 194943 97332 194944 97301 194944 97330 194944 97330 194945 97301 194945 97309 194945 97309 194946 97298 194946 97330 194946 97330 194947 97298 194947 97302 194947 97310 194948 97311 194948 97312 194948 97312 194949 97311 194949 97329 194949 97312 194950 97329 194950 97313 194950 97313 194951 97329 194951 97314 194951 97313 194952 97314 194952 97300 194952 97300 194953 97314 194953 97320 194953 97299 194954 97316 194954 97315 194954 97315 194955 97316 194955 97317 194955 97315 194956 97317 194956 97318 194956 97318 194957 97317 194957 97327 194957 97318 194958 97327 194958 97319 194958 97319 194959 97327 194959 97328 194959 97319 194960 97328 194960 97322 194960 97322 194961 97328 194961 97321 194961 97299 194962 97300 194962 97316 194962 97316 194963 97300 194963 97320 194963 97305 194964 97306 194964 97321 194964 97321 194965 97306 194965 97322 194965 97311 194966 97310 194966 97323 194966 97323 194967 97310 194967 97307 194967 97324 194968 97325 194968 97326 194968 97326 194969 97325 194969 97305 194969 97326 194970 97305 194970 97302 194970 97302 194971 97305 194971 97330 194971 97320 194972 97323 194972 97331 194972 97327 194973 97317 194973 97328 194973 97328 194974 97317 194974 97316 194974 97328 194975 97316 194975 97321 194975 97314 194976 97329 194976 97320 194976 97320 194977 97329 194977 97311 194977 97320 194978 97311 194978 97323 194978 97321 194979 97316 194979 97305 194979 97305 194980 97316 194980 97320 194980 97305 194981 97320 194981 97330 194981 97330 194982 97320 194982 97331 194982 97330 194983 97331 194983 97332 194983 97333 194984 97345 194984 97344 194984 97353 194985 97335 194985 97348 194985 97334 194986 97355 194986 97353 194986 97353 194987 97355 194987 97356 194987 97353 194988 97356 194988 97335 194988 97338 194989 97336 194989 97349 194989 97349 194990 97337 194990 97338 194990 97338 194991 97337 194991 97360 194991 97338 194992 97360 194992 97340 194992 97348 194993 97333 194993 97353 194993 97353 194994 97333 194994 97344 194994 97353 194995 97344 194995 97339 194995 97339 194996 97344 194996 97338 194996 97339 194997 97338 194997 97351 194997 97351 194998 97338 194998 97340 194998 97351 194999 97340 194999 97341 194999 97342 195000 97344 195000 97343 195000 97343 195001 97344 195001 97345 195001 97343 195002 97345 195002 97346 195002 97346 195003 97345 195003 97333 195003 97346 195004 97333 195004 97347 195004 97347 195005 97333 195005 97348 195005 97347 195006 97348 195006 97358 195006 97358 195007 97348 195007 97335 195007 97361 195008 97337 195008 97365 195008 97365 195009 97337 195009 97349 195009 97365 195010 97349 195010 97350 195010 97350 195011 97349 195011 97336 195011 97350 195012 97336 195012 97362 195012 97362 195013 97336 195013 97338 195013 97338 195014 97344 195014 97362 195014 97362 195015 97344 195015 97342 195015 97360 195016 97359 195016 97340 195016 97340 195017 97359 195017 97367 195017 97340 195018 97367 195018 97341 195018 97341 195019 97367 195019 97366 195019 97341 195020 97366 195020 97351 195020 97351 195021 97366 195021 97352 195021 97351 195022 97352 195022 97339 195022 97339 195023 97352 195023 97368 195023 97353 195024 97357 195024 97334 195024 97334 195025 97357 195025 97354 195025 97334 195026 97354 195026 97355 195026 97355 195027 97354 195027 97363 195027 97355 195028 97363 195028 97356 195028 97356 195029 97363 195029 97364 195029 97353 195030 97339 195030 97357 195030 97357 195031 97339 195031 97368 195031 97358 195032 97335 195032 97364 195032 97364 195033 97335 195033 97356 195033 97359 195034 97360 195034 97361 195034 97361 195035 97360 195035 97337 195035 97362 195036 97342 195036 97357 195036 97363 195037 97354 195037 97364 195037 97364 195038 97354 195038 97357 195038 97364 195039 97357 195039 97358 195039 97358 195040 97357 195040 97347 195040 97365 195041 97350 195041 97361 195041 97361 195042 97350 195042 97362 195042 97361 195043 97362 195043 97359 195043 97359 195044 97362 195044 97367 195044 97342 195045 97343 195045 97357 195045 97357 195046 97343 195046 97346 195046 97357 195047 97346 195047 97347 195047 97366 195048 97367 195048 97352 195048 97352 195049 97367 195049 97362 195049 97352 195050 97362 195050 97368 195050 97368 195051 97362 195051 97357 195051 97378 195052 97377 195052 97386 195052 97388 195053 97389 195053 97369 195053 97370 195054 97397 195054 97381 195054 97393 195055 97396 195055 97370 195055 97370 195056 97396 195056 97371 195056 97370 195057 97371 195057 97397 195057 97372 195058 97385 195058 97373 195058 97373 195059 97385 195059 97374 195059 97373 195060 97374 195060 97375 195060 97375 195061 97388 195061 97373 195061 97373 195062 97388 195062 97369 195062 97373 195063 97369 195063 97386 195063 97386 195064 97369 195064 97370 195064 97386 195065 97370 195065 97378 195065 97378 195066 97370 195066 97381 195066 97387 195067 97386 195067 97376 195067 97376 195068 97386 195068 97377 195068 97376 195069 97377 195069 97379 195069 97379 195070 97377 195070 97378 195070 97379 195071 97378 195071 97380 195071 97380 195072 97378 195072 97381 195072 97380 195073 97381 195073 97382 195073 97382 195074 97381 195074 97397 195074 97383 195075 97374 195075 97384 195075 97384 195076 97374 195076 97385 195076 97384 195077 97385 195077 97400 195077 97400 195078 97385 195078 97372 195078 97400 195079 97372 195079 97402 195079 97402 195080 97372 195080 97373 195080 97373 195081 97386 195081 97402 195081 97402 195082 97386 195082 97387 195082 97375 195083 97401 195083 97388 195083 97388 195084 97401 195084 97399 195084 97388 195085 97399 195085 97389 195085 97389 195086 97399 195086 97390 195086 97389 195087 97390 195087 97369 195087 97369 195088 97390 195088 97391 195088 97370 195089 97392 195089 97393 195089 97393 195090 97392 195090 97394 195090 97393 195091 97394 195091 97396 195091 97396 195092 97394 195092 97395 195092 97396 195093 97395 195093 97371 195093 97371 195094 97395 195094 97398 195094 97370 195095 97369 195095 97392 195095 97392 195096 97369 195096 97391 195096 97382 195097 97397 195097 97398 195097 97398 195098 97397 195098 97371 195098 97401 195099 97375 195099 97383 195099 97383 195100 97375 195100 97374 195100 97402 195101 97387 195101 97392 195101 97395 195102 97394 195102 97398 195102 97398 195103 97394 195103 97392 195103 97398 195104 97392 195104 97382 195104 97382 195105 97392 195105 97380 195105 97392 195106 97391 195106 97402 195106 97402 195107 97391 195107 97390 195107 97402 195108 97390 195108 97399 195108 97384 195109 97400 195109 97383 195109 97383 195110 97400 195110 97402 195110 97383 195111 97402 195111 97401 195111 97401 195112 97402 195112 97399 195112 97387 195113 97376 195113 97392 195113 97392 195114 97376 195114 97379 195114 97392 195115 97379 195115 97380 195115 97411 195116 97414 195116 97412 195116 97403 195117 97420 195117 97410 195117 97407 195118 97425 195118 97415 195118 97404 195119 97405 195119 97407 195119 97407 195120 97405 195120 97406 195120 97407 195121 97406 195121 97425 195121 97408 195122 97417 195122 97418 195122 97418 195123 97417 195123 97427 195123 97418 195124 97427 195124 97409 195124 97409 195125 97403 195125 97418 195125 97418 195126 97403 195126 97410 195126 97418 195127 97410 195127 97412 195127 97412 195128 97410 195128 97407 195128 97412 195129 97407 195129 97411 195129 97411 195130 97407 195130 97415 195130 97419 195131 97412 195131 97436 195131 97436 195132 97412 195132 97414 195132 97436 195133 97414 195133 97413 195133 97413 195134 97414 195134 97411 195134 97413 195135 97411 195135 97416 195135 97416 195136 97411 195136 97415 195136 97416 195137 97415 195137 97424 195137 97424 195138 97415 195138 97425 195138 97426 195139 97427 195139 97432 195139 97432 195140 97427 195140 97417 195140 97432 195141 97417 195141 97433 195141 97433 195142 97417 195142 97408 195142 97433 195143 97408 195143 97434 195143 97434 195144 97408 195144 97418 195144 97418 195145 97412 195145 97434 195145 97434 195146 97412 195146 97419 195146 97409 195147 97435 195147 97403 195147 97403 195148 97435 195148 97421 195148 97403 195149 97421 195149 97420 195149 97420 195150 97421 195150 97422 195150 97420 195151 97422 195151 97410 195151 97410 195152 97422 195152 97431 195152 97407 195153 97423 195153 97404 195153 97404 195154 97423 195154 97429 195154 97404 195155 97429 195155 97405 195155 97405 195156 97429 195156 97428 195156 97405 195157 97428 195157 97406 195157 97406 195158 97428 195158 97430 195158 97407 195159 97410 195159 97423 195159 97423 195160 97410 195160 97431 195160 97424 195161 97425 195161 97430 195161 97430 195162 97425 195162 97406 195162 97435 195163 97409 195163 97426 195163 97426 195164 97409 195164 97427 195164 97428 195165 97429 195165 97430 195165 97430 195166 97429 195166 97423 195166 97430 195167 97423 195167 97424 195167 97424 195168 97423 195168 97416 195168 97423 195169 97431 195169 97434 195169 97434 195170 97431 195170 97422 195170 97434 195171 97422 195171 97421 195171 97432 195172 97433 195172 97426 195172 97426 195173 97433 195173 97434 195173 97426 195174 97434 195174 97435 195174 97435 195175 97434 195175 97421 195175 97413 195176 97416 195176 97436 195176 97436 195177 97416 195177 97423 195177 97436 195178 97423 195178 97419 195178 97419 195179 97423 195179 97434 195179 97446 195180 97437 195180 97438 195180 97439 195181 97450 195181 97440 195181 97445 195182 97441 195182 97442 195182 97443 195183 97444 195183 97445 195183 97445 195184 97444 195184 97465 195184 97445 195185 97465 195185 97441 195185 97461 195186 97462 195186 97452 195186 97456 195187 97457 195187 97461 195187 97461 195188 97457 195188 97463 195188 97461 195189 97463 195189 97462 195189 97452 195190 97439 195190 97461 195190 97461 195191 97439 195191 97440 195191 97461 195192 97440 195192 97438 195192 97438 195193 97440 195193 97445 195193 97438 195194 97445 195194 97446 195194 97446 195195 97445 195195 97442 195195 97447 195196 97440 195196 97448 195196 97448 195197 97440 195197 97450 195197 97448 195198 97450 195198 97449 195198 97449 195199 97450 195199 97439 195199 97449 195200 97439 195200 97451 195200 97451 195201 97439 195201 97452 195201 97451 195202 97452 195202 97469 195202 97469 195203 97452 195203 97462 195203 97453 195204 97465 195204 97466 195204 97466 195205 97465 195205 97444 195205 97466 195206 97444 195206 97454 195206 97454 195207 97444 195207 97443 195207 97454 195208 97443 195208 97471 195208 97471 195209 97443 195209 97445 195209 97445 195210 97440 195210 97471 195210 97471 195211 97440 195211 97447 195211 97461 195212 97468 195212 97456 195212 97456 195213 97468 195213 97455 195213 97456 195214 97455 195214 97457 195214 97457 195215 97455 195215 97458 195215 97457 195216 97458 195216 97463 195216 97463 195217 97458 195217 97467 195217 97441 195218 97464 195218 97442 195218 97442 195219 97464 195219 97459 195219 97442 195220 97459 195220 97446 195220 97446 195221 97459 195221 97460 195221 97446 195222 97460 195222 97437 195222 97437 195223 97460 195223 97470 195223 97437 195224 97470 195224 97438 195224 97438 195225 97470 195225 97472 195225 97468 195226 97461 195226 97472 195226 97472 195227 97461 195227 97438 195227 97469 195228 97462 195228 97467 195228 97467 195229 97462 195229 97463 195229 97464 195230 97441 195230 97453 195230 97453 195231 97441 195231 97465 195231 97466 195232 97454 195232 97453 195232 97453 195233 97454 195233 97471 195233 97453 195234 97471 195234 97464 195234 97464 195235 97471 195235 97459 195235 97471 195236 97447 195236 97468 195236 97468 195237 97447 195237 97448 195237 97468 195238 97448 195238 97449 195238 97458 195239 97455 195239 97467 195239 97467 195240 97455 195240 97468 195240 97467 195241 97468 195241 97469 195241 97469 195242 97468 195242 97449 195242 97469 195243 97449 195243 97451 195243 97460 195244 97459 195244 97470 195244 97470 195245 97459 195245 97471 195245 97470 195246 97471 195246 97472 195246 97472 195247 97471 195247 97468 195247 97483 195248 97485 195248 97473 195248 97490 195249 97488 195249 97479 195249 97481 195250 97477 195250 97474 195250 97498 195251 97475 195251 97481 195251 97481 195252 97475 195252 97476 195252 97481 195253 97476 195253 97477 195253 97478 195254 97492 195254 97480 195254 97480 195255 97492 195255 97495 195255 97480 195256 97495 195256 97494 195256 97494 195257 97490 195257 97480 195257 97480 195258 97490 195258 97479 195258 97480 195259 97479 195259 97473 195259 97473 195260 97479 195260 97481 195260 97473 195261 97481 195261 97483 195261 97483 195262 97481 195262 97474 195262 97477 195263 97502 195263 97474 195263 97474 195264 97502 195264 97482 195264 97474 195265 97482 195265 97483 195265 97483 195266 97482 195266 97484 195266 97483 195267 97484 195267 97485 195267 97485 195268 97484 195268 97503 195268 97485 195269 97503 195269 97473 195269 97473 195270 97503 195270 97504 195270 97499 195271 97479 195271 97486 195271 97486 195272 97479 195272 97488 195272 97486 195273 97488 195273 97487 195273 97487 195274 97488 195274 97490 195274 97487 195275 97490 195275 97489 195275 97489 195276 97490 195276 97494 195276 97480 195277 97491 195277 97478 195277 97478 195278 97491 195278 97506 195278 97478 195279 97506 195279 97492 195279 97492 195280 97506 195280 97493 195280 97492 195281 97493 195281 97495 195281 97495 195282 97493 195282 97505 195282 97489 195283 97494 195283 97505 195283 97505 195284 97494 195284 97495 195284 97480 195285 97473 195285 97491 195285 97491 195286 97473 195286 97504 195286 97496 195287 97476 195287 97500 195287 97500 195288 97476 195288 97475 195288 97500 195289 97475 195289 97497 195289 97497 195290 97475 195290 97498 195290 97497 195291 97498 195291 97501 195291 97501 195292 97498 195292 97481 195292 97502 195293 97477 195293 97496 195293 97496 195294 97477 195294 97476 195294 97481 195295 97479 195295 97501 195295 97501 195296 97479 195296 97499 195296 97486 195297 97487 195297 97499 195297 97499 195298 97487 195298 97489 195298 97499 195299 97489 195299 97501 195299 97500 195300 97497 195300 97496 195300 97496 195301 97497 195301 97501 195301 97496 195302 97501 195302 97502 195302 97502 195303 97501 195303 97482 195303 97484 195304 97482 195304 97503 195304 97503 195305 97482 195305 97501 195305 97503 195306 97501 195306 97504 195306 97504 195307 97501 195307 97489 195307 97504 195308 97489 195308 97491 195308 97491 195309 97489 195309 97505 195309 97491 195310 97505 195310 97506 195310 97506 195311 97505 195311 97493 195311 97513 195312 97510 195312 97515 195312 97522 195313 97524 195313 97514 195313 97514 195314 97524 195314 97507 195314 97508 195315 97520 195315 97519 195315 97509 195316 97510 195316 97531 195316 97531 195317 97510 195317 97513 195317 97531 195318 97513 195318 97511 195318 97511 195319 97513 195319 97512 195319 97519 195320 97517 195320 97508 195320 97508 195321 97517 195321 97512 195321 97508 195322 97512 195322 97507 195322 97507 195323 97512 195323 97513 195323 97507 195324 97513 195324 97514 195324 97515 195325 97516 195325 97513 195325 97513 195326 97516 195326 97527 195326 97513 195327 97527 195327 97528 195327 97537 195328 97517 195328 97518 195328 97518 195329 97517 195329 97519 195329 97518 195330 97519 195330 97538 195330 97538 195331 97519 195331 97520 195331 97538 195332 97520 195332 97539 195332 97539 195333 97520 195333 97508 195333 97514 195334 97536 195334 97522 195334 97522 195335 97536 195335 97521 195335 97522 195336 97521 195336 97524 195336 97524 195337 97521 195337 97523 195337 97524 195338 97523 195338 97507 195338 97507 195339 97523 195339 97525 195339 97539 195340 97508 195340 97525 195340 97525 195341 97508 195341 97507 195341 97515 195342 97526 195342 97516 195342 97516 195343 97526 195343 97542 195343 97516 195344 97542 195344 97527 195344 97527 195345 97542 195345 97541 195345 97527 195346 97541 195346 97528 195346 97528 195347 97541 195347 97540 195347 97528 195348 97540 195348 97513 195348 97513 195349 97540 195349 97535 195349 97533 195350 97510 195350 97529 195350 97529 195351 97510 195351 97509 195351 97529 195352 97509 195352 97530 195352 97530 195353 97509 195353 97531 195353 97530 195354 97531 195354 97534 195354 97534 195355 97531 195355 97511 195355 97534 195356 97511 195356 97532 195356 97532 195357 97511 195357 97512 195357 97526 195358 97515 195358 97533 195358 97533 195359 97515 195359 97510 195359 97512 195360 97517 195360 97532 195360 97532 195361 97517 195361 97537 195361 97514 195362 97513 195362 97536 195362 97536 195363 97513 195363 97535 195363 97534 195364 97532 195364 97535 195364 97535 195365 97532 195365 97536 195365 97526 195366 97533 195366 97535 195366 97532 195367 97537 195367 97536 195367 97536 195368 97537 195368 97518 195368 97536 195369 97518 195369 97538 195369 97523 195370 97521 195370 97525 195370 97525 195371 97521 195371 97536 195371 97525 195372 97536 195372 97539 195372 97539 195373 97536 195373 97538 195373 97540 195374 97541 195374 97535 195374 97535 195375 97541 195375 97542 195375 97535 195376 97542 195376 97526 195376 97533 195377 97529 195377 97535 195377 97535 195378 97529 195378 97530 195378 97535 195379 97530 195379 97534 195379 97543 195380 97565 195380 97546 195380 97554 195381 97560 195381 97543 195381 97543 195382 97560 195382 97544 195382 97543 195383 97544 195383 97551 195383 97562 195384 97545 195384 97546 195384 97546 195385 97545 195385 97568 195385 97546 195386 97568 195386 97543 195386 97547 195387 97558 195387 97543 195387 97543 195388 97558 195388 97556 195388 97543 195389 97556 195389 97554 195389 97563 195390 97548 195390 97549 195390 97549 195391 97548 195391 97565 195391 97549 195392 97565 195392 97550 195392 97550 195393 97565 195393 97543 195393 97550 195394 97543 195394 97552 195394 97552 195395 97543 195395 97551 195395 97560 195396 97569 195396 97544 195396 97544 195397 97569 195397 97576 195397 97544 195398 97576 195398 97551 195398 97551 195399 97576 195399 97577 195399 97551 195400 97577 195400 97552 195400 97552 195401 97577 195401 97553 195401 97552 195402 97553 195402 97550 195402 97550 195403 97553 195403 97567 195403 97570 195404 97554 195404 97555 195404 97555 195405 97554 195405 97556 195405 97555 195406 97556 195406 97557 195406 97557 195407 97556 195407 97558 195407 97557 195408 97558 195408 97578 195408 97578 195409 97558 195409 97547 195409 97578 195410 97547 195410 97559 195410 97559 195411 97547 195411 97543 195411 97569 195412 97560 195412 97570 195412 97570 195413 97560 195413 97554 195413 97573 195414 97568 195414 97572 195414 97572 195415 97568 195415 97545 195415 97572 195416 97545 195416 97561 195416 97561 195417 97545 195417 97562 195417 97561 195418 97562 195418 97574 195418 97574 195419 97562 195419 97546 195419 97549 195420 97575 195420 97563 195420 97563 195421 97575 195421 97564 195421 97563 195422 97564 195422 97548 195422 97548 195423 97564 195423 97571 195423 97548 195424 97571 195424 97565 195424 97565 195425 97571 195425 97566 195425 97574 195426 97546 195426 97566 195426 97566 195427 97546 195427 97565 195427 97549 195428 97550 195428 97575 195428 97575 195429 97550 195429 97567 195429 97543 195430 97568 195430 97559 195430 97559 195431 97568 195431 97573 195431 97578 195432 97559 195432 97567 195432 97567 195433 97559 195433 97575 195433 97569 195434 97570 195434 97567 195434 97566 195435 97571 195435 97564 195435 97572 195436 97561 195436 97573 195436 97573 195437 97561 195437 97574 195437 97573 195438 97574 195438 97559 195438 97559 195439 97574 195439 97566 195439 97559 195440 97566 195440 97575 195440 97575 195441 97566 195441 97564 195441 97576 195442 97569 195442 97577 195442 97577 195443 97569 195443 97567 195443 97577 195444 97567 195444 97553 195444 97570 195445 97555 195445 97567 195445 97567 195446 97555 195446 97557 195446 97567 195447 97557 195447 97578 195447 97596 195448 97579 195448 97598 195448 97583 195449 97588 195449 97580 195449 97593 195450 97592 195450 97581 195450 97581 195451 97592 195451 97591 195451 97581 195452 97591 195452 97598 195452 97598 195453 97591 195453 97583 195453 97598 195454 97583 195454 97582 195454 97582 195455 97583 195455 97580 195455 97585 195456 97584 195456 97590 195456 97590 195457 97584 195457 97602 195457 97590 195458 97602 195458 97582 195458 97582 195459 97602 195459 97601 195459 97582 195460 97601 195460 97598 195460 97598 195461 97601 195461 97595 195461 97598 195462 97595 195462 97596 195462 97590 195463 97611 195463 97585 195463 97585 195464 97611 195464 97586 195464 97585 195465 97586 195465 97584 195465 97584 195466 97586 195466 97587 195466 97584 195467 97587 195467 97602 195467 97602 195468 97587 195468 97610 195468 97612 195469 97582 195469 97606 195469 97606 195470 97582 195470 97580 195470 97606 195471 97580 195471 97607 195471 97607 195472 97580 195472 97588 195472 97607 195473 97588 195473 97589 195473 97589 195474 97588 195474 97583 195474 97611 195475 97590 195475 97612 195475 97612 195476 97590 195476 97582 195476 97603 195477 97591 195477 97608 195477 97608 195478 97591 195478 97592 195478 97608 195479 97592 195479 97609 195479 97609 195480 97592 195480 97593 195480 97609 195481 97593 195481 97594 195481 97594 195482 97593 195482 97581 195482 97601 195483 97605 195483 97595 195483 97595 195484 97605 195484 97604 195484 97595 195485 97604 195485 97596 195485 97596 195486 97604 195486 97597 195486 97596 195487 97597 195487 97579 195487 97579 195488 97597 195488 97599 195488 97579 195489 97599 195489 97598 195489 97598 195490 97599 195490 97600 195490 97594 195491 97581 195491 97600 195491 97600 195492 97581 195492 97598 195492 97601 195493 97602 195493 97605 195493 97605 195494 97602 195494 97610 195494 97583 195495 97591 195495 97589 195495 97589 195496 97591 195496 97603 195496 97597 195497 97604 195497 97605 195497 97606 195498 97607 195498 97589 195498 97603 195499 97600 195499 97599 195499 97608 195500 97609 195500 97603 195500 97603 195501 97609 195501 97594 195501 97603 195502 97594 195502 97600 195502 97587 195503 97586 195503 97610 195503 97610 195504 97586 195504 97611 195504 97610 195505 97611 195505 97612 195505 97612 195506 97606 195506 97610 195506 97610 195507 97606 195507 97589 195507 97610 195508 97589 195508 97605 195508 97605 195509 97589 195509 97603 195509 97605 195510 97603 195510 97597 195510 97597 195511 97603 195511 97599 195511 97637 195512 97613 195512 97636 195512 97636 195513 97613 195513 97640 195513 97614 195514 97635 195514 97617 195514 97629 195515 97616 195515 97615 195515 97615 195516 97616 195516 97619 195516 97615 195517 97619 195517 97631 195517 97631 195518 97619 195518 97642 195518 97617 195519 97618 195519 97614 195519 97614 195520 97618 195520 97642 195520 97614 195521 97642 195521 97640 195521 97640 195522 97642 195522 97619 195522 97640 195523 97619 195523 97636 195523 97623 195524 97625 195524 97621 195524 97621 195525 97625 195525 97619 195525 97621 195526 97619 195526 97620 195526 97620 195527 97619 195527 97616 195527 97620 195528 97644 195528 97621 195528 97621 195529 97644 195529 97622 195529 97621 195530 97622 195530 97623 195530 97623 195531 97622 195531 97624 195531 97623 195532 97624 195532 97625 195532 97625 195533 97624 195533 97626 195533 97625 195534 97626 195534 97619 195534 97619 195535 97626 195535 97627 195535 97648 195536 97616 195536 97628 195536 97628 195537 97616 195537 97629 195537 97628 195538 97629 195538 97630 195538 97630 195539 97629 195539 97615 195539 97630 195540 97615 195540 97647 195540 97647 195541 97615 195541 97631 195541 97647 195542 97631 195542 97643 195542 97643 195543 97631 195543 97642 195543 97644 195544 97620 195544 97648 195544 97648 195545 97620 195545 97616 195545 97632 195546 97618 195546 97633 195546 97633 195547 97618 195547 97617 195547 97633 195548 97617 195548 97645 195548 97645 195549 97617 195549 97635 195549 97645 195550 97635 195550 97634 195550 97634 195551 97635 195551 97614 195551 97636 195552 97646 195552 97637 195552 97637 195553 97646 195553 97638 195553 97637 195554 97638 195554 97613 195554 97613 195555 97638 195555 97639 195555 97613 195556 97639 195556 97640 195556 97640 195557 97639 195557 97641 195557 97634 195558 97614 195558 97641 195558 97641 195559 97614 195559 97640 195559 97636 195560 97619 195560 97646 195560 97646 195561 97619 195561 97627 195561 97642 195562 97618 195562 97643 195562 97643 195563 97618 195563 97632 195563 97639 195564 97638 195564 97646 195564 97644 195565 97648 195565 97627 195565 97633 195566 97645 195566 97632 195566 97632 195567 97645 195567 97634 195567 97632 195568 97634 195568 97641 195568 97641 195569 97639 195569 97632 195569 97632 195570 97639 195570 97646 195570 97632 195571 97646 195571 97643 195571 97643 195572 97646 195572 97627 195572 97643 195573 97627 195573 97647 195573 97626 195574 97624 195574 97627 195574 97627 195575 97624 195575 97622 195575 97627 195576 97622 195576 97644 195576 97648 195577 97628 195577 97627 195577 97627 195578 97628 195578 97630 195578 97627 195579 97630 195579 97647 195579 97656 195580 97651 195580 97663 195580 97669 195581 97649 195581 97653 195581 97650 195582 97660 195582 97662 195582 97662 195583 97660 195583 97651 195583 97662 195584 97651 195584 97653 195584 97666 195585 97665 195585 97652 195585 97652 195586 97665 195586 97653 195586 97652 195587 97653 195587 97670 195587 97670 195588 97653 195588 97649 195588 97654 195589 97655 195589 97663 195589 97663 195590 97655 195590 97673 195590 97663 195591 97673 195591 97656 195591 97651 195592 97656 195592 97653 195592 97653 195593 97656 195593 97667 195593 97653 195594 97667 195594 97669 195594 97663 195595 97657 195595 97654 195595 97654 195596 97657 195596 97658 195596 97654 195597 97658 195597 97655 195597 97655 195598 97658 195598 97659 195598 97655 195599 97659 195599 97673 195599 97673 195600 97659 195600 97678 195600 97679 195601 97651 195601 97676 195601 97676 195602 97651 195602 97660 195602 97676 195603 97660 195603 97661 195603 97661 195604 97660 195604 97650 195604 97661 195605 97650 195605 97674 195605 97674 195606 97650 195606 97662 195606 97657 195607 97663 195607 97679 195607 97679 195608 97663 195608 97651 195608 97681 195609 97653 195609 97664 195609 97664 195610 97653 195610 97665 195610 97664 195611 97665 195611 97675 195611 97675 195612 97665 195612 97666 195612 97675 195613 97666 195613 97671 195613 97671 195614 97666 195614 97652 195614 97656 195615 97682 195615 97667 195615 97667 195616 97682 195616 97680 195616 97667 195617 97680 195617 97669 195617 97669 195618 97680 195618 97668 195618 97669 195619 97668 195619 97649 195619 97649 195620 97668 195620 97677 195620 97649 195621 97677 195621 97670 195621 97670 195622 97677 195622 97672 195622 97671 195623 97652 195623 97672 195623 97672 195624 97652 195624 97670 195624 97656 195625 97673 195625 97682 195625 97682 195626 97673 195626 97678 195626 97662 195627 97653 195627 97674 195627 97674 195628 97653 195628 97681 195628 97664 195629 97675 195629 97681 195629 97681 195630 97675 195630 97671 195630 97678 195631 97679 195631 97676 195631 97671 195632 97672 195632 97681 195632 97681 195633 97672 195633 97677 195633 97681 195634 97677 195634 97668 195634 97659 195635 97658 195635 97678 195635 97678 195636 97658 195636 97657 195636 97678 195637 97657 195637 97679 195637 97668 195638 97680 195638 97681 195638 97681 195639 97680 195639 97682 195639 97681 195640 97682 195640 97674 195640 97674 195641 97682 195641 97678 195641 97674 195642 97678 195642 97661 195642 97661 195643 97678 195643 97676 195643 97701 195644 97684 195644 97683 195644 97683 195645 97684 195645 97698 195645 97683 195646 97698 195646 97685 195646 97704 195647 97703 195647 97686 195647 97686 195648 97703 195648 97685 195648 97686 195649 97685 195649 97707 195649 97707 195650 97685 195650 97687 195650 97707 195651 97687 195651 97688 195651 97689 195652 97690 195652 97691 195652 97691 195653 97690 195653 97695 195653 97691 195654 97695 195654 97698 195654 97698 195655 97695 195655 97692 195655 97698 195656 97692 195656 97685 195656 97685 195657 97692 195657 97693 195657 97685 195658 97693 195658 97687 195658 97691 195659 97702 195659 97689 195659 97689 195660 97702 195660 97713 195660 97689 195661 97713 195661 97690 195661 97690 195662 97713 195662 97694 195662 97690 195663 97694 195663 97695 195663 97695 195664 97694 195664 97696 195664 97697 195665 97698 195665 97699 195665 97699 195666 97698 195666 97684 195666 97699 195667 97684 195667 97700 195667 97700 195668 97684 195668 97701 195668 97700 195669 97701 195669 97715 195669 97715 195670 97701 195670 97683 195670 97702 195671 97691 195671 97697 195671 97697 195672 97691 195672 97698 195672 97712 195673 97685 195673 97710 195673 97710 195674 97685 195674 97703 195674 97710 195675 97703 195675 97711 195675 97711 195676 97703 195676 97704 195676 97711 195677 97704 195677 97705 195677 97705 195678 97704 195678 97686 195678 97692 195679 97714 195679 97693 195679 97693 195680 97714 195680 97706 195680 97693 195681 97706 195681 97687 195681 97687 195682 97706 195682 97716 195682 97687 195683 97716 195683 97688 195683 97688 195684 97716 195684 97708 195684 97688 195685 97708 195685 97707 195685 97707 195686 97708 195686 97709 195686 97705 195687 97686 195687 97709 195687 97709 195688 97686 195688 97707 195688 97692 195689 97695 195689 97714 195689 97714 195690 97695 195690 97696 195690 97683 195691 97685 195691 97715 195691 97715 195692 97685 195692 97712 195692 97699 195693 97700 195693 97715 195693 97716 195694 97706 195694 97714 195694 97710 195695 97711 195695 97712 195695 97712 195696 97711 195696 97705 195696 97712 195697 97705 195697 97715 195697 97715 195698 97705 195698 97709 195698 97694 195699 97713 195699 97696 195699 97696 195700 97713 195700 97702 195700 97696 195701 97702 195701 97697 195701 97697 195702 97699 195702 97696 195702 97696 195703 97699 195703 97715 195703 97696 195704 97715 195704 97714 195704 97714 195705 97715 195705 97709 195705 97714 195706 97709 195706 97716 195706 97716 195707 97709 195707 97708 195707 97717 195708 97737 195708 97724 195708 97721 195709 97731 195709 97723 195709 97735 195710 97718 195710 97719 195710 97719 195711 97718 195711 97720 195711 97719 195712 97720 195712 97724 195712 97724 195713 97720 195713 97743 195713 97724 195714 97743 195714 97723 195714 97723 195715 97743 195715 97732 195715 97723 195716 97732 195716 97721 195716 97726 195717 97727 195717 97725 195717 97725 195718 97727 195718 97722 195718 97725 195719 97722 195719 97723 195719 97723 195720 97722 195720 97741 195720 97723 195721 97741 195721 97724 195721 97724 195722 97741 195722 97736 195722 97724 195723 97736 195723 97717 195723 97725 195724 97749 195724 97726 195724 97726 195725 97749 195725 97748 195725 97726 195726 97748 195726 97727 195726 97727 195727 97748 195727 97728 195727 97727 195728 97728 195728 97722 195728 97722 195729 97728 195729 97729 195729 97750 195730 97723 195730 97730 195730 97730 195731 97723 195731 97731 195731 97730 195732 97731 195732 97744 195732 97744 195733 97731 195733 97721 195733 97744 195734 97721 195734 97745 195734 97745 195735 97721 195735 97732 195735 97745 195736 97732 195736 97733 195736 97733 195737 97732 195737 97743 195737 97749 195738 97725 195738 97750 195738 97750 195739 97725 195739 97723 195739 97751 195740 97720 195740 97734 195740 97734 195741 97720 195741 97718 195741 97734 195742 97718 195742 97746 195742 97746 195743 97718 195743 97735 195743 97746 195744 97735 195744 97740 195744 97740 195745 97735 195745 97719 195745 97741 195746 97742 195746 97736 195746 97736 195747 97742 195747 97752 195747 97736 195748 97752 195748 97717 195748 97717 195749 97752 195749 97738 195749 97717 195750 97738 195750 97737 195750 97737 195751 97738 195751 97739 195751 97737 195752 97739 195752 97724 195752 97724 195753 97739 195753 97747 195753 97740 195754 97719 195754 97747 195754 97747 195755 97719 195755 97724 195755 97741 195756 97722 195756 97742 195756 97742 195757 97722 195757 97729 195757 97743 195758 97720 195758 97733 195758 97733 195759 97720 195759 97751 195759 97744 195760 97745 195760 97733 195760 97734 195761 97746 195761 97751 195761 97751 195762 97746 195762 97740 195762 97729 195763 97750 195763 97730 195763 97740 195764 97747 195764 97751 195764 97751 195765 97747 195765 97739 195765 97751 195766 97739 195766 97738 195766 97728 195767 97748 195767 97729 195767 97729 195768 97748 195768 97749 195768 97729 195769 97749 195769 97750 195769 97730 195770 97744 195770 97729 195770 97729 195771 97744 195771 97733 195771 97729 195772 97733 195772 97742 195772 97742 195773 97733 195773 97751 195773 97742 195774 97751 195774 97752 195774 97752 195775 97751 195775 97738 195775 97753 195776 97754 195776 97755 195776 97755 195777 97754 195777 97764 195777 97775 195778 97776 195778 97780 195778 97780 195779 97776 195779 97759 195779 97780 195780 97759 195780 97764 195780 97761 195781 97756 195781 97757 195781 97757 195782 97756 195782 97764 195782 97757 195783 97764 195783 97760 195783 97760 195784 97764 195784 97754 195784 97773 195785 97772 195785 97758 195785 97758 195786 97772 195786 97782 195786 97758 195787 97782 195787 97759 195787 97759 195788 97782 195788 97769 195788 97759 195789 97769 195789 97764 195789 97764 195790 97769 195790 97768 195790 97764 195791 97768 195791 97755 195791 97760 195792 97784 195792 97757 195792 97757 195793 97784 195793 97762 195793 97757 195794 97762 195794 97761 195794 97761 195795 97762 195795 97763 195795 97761 195796 97763 195796 97756 195796 97756 195797 97763 195797 97765 195797 97756 195798 97765 195798 97764 195798 97764 195799 97765 195799 97787 195799 97785 195800 97754 195800 97766 195800 97766 195801 97754 195801 97753 195801 97766 195802 97753 195802 97788 195802 97788 195803 97753 195803 97755 195803 97788 195804 97755 195804 97767 195804 97767 195805 97755 195805 97768 195805 97767 195806 97768 195806 97783 195806 97783 195807 97768 195807 97769 195807 97784 195808 97760 195808 97785 195808 97785 195809 97760 195809 97754 195809 97786 195810 97782 195810 97770 195810 97770 195811 97782 195811 97772 195811 97770 195812 97772 195812 97771 195812 97771 195813 97772 195813 97773 195813 97771 195814 97773 195814 97774 195814 97774 195815 97773 195815 97758 195815 97780 195816 97781 195816 97775 195816 97775 195817 97781 195817 97777 195817 97775 195818 97777 195818 97776 195818 97776 195819 97777 195819 97778 195819 97776 195820 97778 195820 97759 195820 97759 195821 97778 195821 97779 195821 97774 195822 97758 195822 97779 195822 97779 195823 97758 195823 97759 195823 97780 195824 97764 195824 97781 195824 97781 195825 97764 195825 97787 195825 97769 195826 97782 195826 97783 195826 97783 195827 97782 195827 97786 195827 97778 195828 97777 195828 97781 195828 97788 195829 97767 195829 97783 195829 97763 195830 97762 195830 97765 195830 97765 195831 97762 195831 97784 195831 97765 195832 97784 195832 97787 195832 97787 195833 97784 195833 97785 195833 97787 195834 97785 195834 97766 195834 97770 195835 97771 195835 97786 195835 97786 195836 97771 195836 97774 195836 97786 195837 97774 195837 97779 195837 97779 195838 97778 195838 97786 195838 97786 195839 97778 195839 97781 195839 97786 195840 97781 195840 97783 195840 97783 195841 97781 195841 97787 195841 97783 195842 97787 195842 97788 195842 97788 195843 97787 195843 97766 195843 97800 195844 97789 195844 97798 195844 97798 195845 97789 195845 97816 195845 97798 195846 97816 195846 97797 195846 97797 195847 97816 195847 97790 195847 97797 195848 97790 195848 97806 195848 97806 195849 97790 195849 97791 195849 97806 195850 97791 195850 97792 195850 97792 195851 97791 195851 97805 195851 97816 195852 97815 195852 97790 195852 97790 195853 97815 195853 97793 195853 97790 195854 97793 195854 97795 195854 97810 195855 97808 195855 97812 195855 97812 195856 97808 195856 97790 195856 97812 195857 97790 195857 97794 195857 97794 195858 97790 195858 97795 195858 97794 195859 97795 195859 97796 195859 97797 195860 97822 195860 97798 195860 97798 195861 97822 195861 97799 195861 97798 195862 97799 195862 97800 195862 97800 195863 97799 195863 97819 195863 97800 195864 97819 195864 97789 195864 97789 195865 97819 195865 97801 195865 97789 195866 97801 195866 97816 195866 97816 195867 97801 195867 97802 195867 97803 195868 97806 195868 97804 195868 97804 195869 97806 195869 97792 195869 97804 195870 97792 195870 97820 195870 97820 195871 97792 195871 97805 195871 97820 195872 97805 195872 97821 195872 97821 195873 97805 195873 97791 195873 97822 195874 97797 195874 97803 195874 97803 195875 97797 195875 97806 195875 97823 195876 97790 195876 97807 195876 97807 195877 97790 195877 97808 195877 97807 195878 97808 195878 97809 195878 97809 195879 97808 195879 97810 195879 97809 195880 97810 195880 97811 195880 97811 195881 97810 195881 97812 195881 97815 195882 97813 195882 97793 195882 97793 195883 97813 195883 97824 195883 97793 195884 97824 195884 97795 195884 97795 195885 97824 195885 97814 195885 97795 195886 97814 195886 97796 195886 97796 195887 97814 195887 97818 195887 97796 195888 97818 195888 97794 195888 97794 195889 97818 195889 97817 195889 97811 195890 97812 195890 97817 195890 97817 195891 97812 195891 97794 195891 97815 195892 97816 195892 97813 195892 97813 195893 97816 195893 97802 195893 97791 195894 97790 195894 97821 195894 97821 195895 97790 195895 97823 195895 97807 195896 97809 195896 97823 195896 97823 195897 97809 195897 97811 195897 97811 195898 97817 195898 97823 195898 97823 195899 97817 195899 97818 195899 97823 195900 97818 195900 97814 195900 97813 195901 97802 195901 97822 195901 97801 195902 97819 195902 97802 195902 97802 195903 97819 195903 97799 195903 97802 195904 97799 195904 97822 195904 97804 195905 97820 195905 97803 195905 97803 195906 97820 195906 97821 195906 97803 195907 97821 195907 97822 195907 97822 195908 97821 195908 97823 195908 97822 195909 97823 195909 97813 195909 97813 195910 97823 195910 97814 195910 97813 195911 97814 195911 97824 195911 97843 195912 97845 195912 97850 195912 97850 195913 97845 195913 97847 195913 97849 195914 97840 195914 97838 195914 97838 195915 97825 195915 97849 195915 97849 195916 97825 195916 97827 195916 97849 195917 97827 195917 97847 195917 97847 195918 97827 195918 97851 195918 97847 195919 97851 195919 97850 195919 97826 195920 97833 195920 97834 195920 97834 195921 97833 195921 97851 195921 97834 195922 97851 195922 97835 195922 97835 195923 97851 195923 97827 195923 97832 195924 97828 195924 97830 195924 97830 195925 97828 195925 97851 195925 97830 195926 97851 195926 97829 195926 97829 195927 97851 195927 97833 195927 97829 195928 97853 195928 97830 195928 97830 195929 97853 195929 97856 195929 97830 195930 97856 195930 97832 195930 97832 195931 97856 195931 97831 195931 97832 195932 97831 195932 97828 195932 97828 195933 97831 195933 97857 195933 97828 195934 97857 195934 97851 195934 97851 195935 97857 195935 97854 195935 97836 195936 97833 195936 97858 195936 97858 195937 97833 195937 97826 195937 97858 195938 97826 195938 97859 195938 97859 195939 97826 195939 97834 195939 97859 195940 97834 195940 97860 195940 97860 195941 97834 195941 97835 195941 97860 195942 97835 195942 97852 195942 97852 195943 97835 195943 97827 195943 97853 195944 97829 195944 97836 195944 97836 195945 97829 195945 97833 195945 97855 195946 97825 195946 97837 195946 97837 195947 97825 195947 97838 195947 97837 195948 97838 195948 97839 195948 97839 195949 97838 195949 97840 195949 97839 195950 97840 195950 97841 195950 97841 195951 97840 195951 97849 195951 97850 195952 97842 195952 97843 195952 97843 195953 97842 195953 97844 195953 97843 195954 97844 195954 97845 195954 97845 195955 97844 195955 97846 195955 97845 195956 97846 195956 97847 195956 97847 195957 97846 195957 97848 195957 97841 195958 97849 195958 97848 195958 97848 195959 97849 195959 97847 195959 97850 195960 97851 195960 97842 195960 97842 195961 97851 195961 97854 195961 97827 195962 97825 195962 97852 195962 97852 195963 97825 195963 97855 195963 97852 195964 97853 195964 97836 195964 97854 195965 97852 195965 97842 195965 97842 195966 97852 195966 97855 195966 97842 195967 97855 195967 97837 195967 97856 195968 97853 195968 97831 195968 97831 195969 97853 195969 97852 195969 97831 195970 97852 195970 97857 195970 97857 195971 97852 195971 97854 195971 97836 195972 97858 195972 97852 195972 97852 195973 97858 195973 97859 195973 97852 195974 97859 195974 97860 195974 97846 195975 97844 195975 97848 195975 97848 195976 97844 195976 97842 195976 97848 195977 97842 195977 97841 195977 97841 195978 97842 195978 97837 195978 97841 195979 97837 195979 97839 195979 97874 195980 97861 195980 97886 195980 97886 195981 97861 195981 97866 195981 97886 195982 97866 195982 97870 195982 97862 195983 97876 195983 97883 195983 97883 195984 97876 195984 97870 195984 97883 195985 97870 195985 97884 195985 97884 195986 97870 195986 97879 195986 97884 195987 97879 195987 97863 195987 97864 195988 97873 195988 97865 195988 97865 195989 97873 195989 97867 195989 97865 195990 97867 195990 97866 195990 97866 195991 97867 195991 97868 195991 97866 195992 97868 195992 97870 195992 97870 195993 97868 195993 97869 195993 97870 195994 97869 195994 97879 195994 97865 195995 97871 195995 97864 195995 97864 195996 97871 195996 97872 195996 97864 195997 97872 195997 97873 195997 97873 195998 97872 195998 97890 195998 97873 195999 97890 195999 97867 195999 97867 196000 97890 196000 97885 196000 97891 196001 97866 196001 97889 196001 97889 196002 97866 196002 97861 196002 97889 196003 97861 196003 97894 196003 97894 196004 97861 196004 97874 196004 97894 196005 97874 196005 97893 196005 97893 196006 97874 196006 97886 196006 97871 196007 97865 196007 97891 196007 97891 196008 97865 196008 97866 196008 97887 196009 97870 196009 97875 196009 97875 196010 97870 196010 97876 196010 97875 196011 97876 196011 97888 196011 97888 196012 97876 196012 97862 196012 97888 196013 97862 196013 97877 196013 97877 196014 97862 196014 97883 196014 97868 196015 97892 196015 97869 196015 97869 196016 97892 196016 97878 196016 97869 196017 97878 196017 97879 196017 97879 196018 97878 196018 97880 196018 97879 196019 97880 196019 97863 196019 97863 196020 97880 196020 97881 196020 97863 196021 97881 196021 97884 196021 97884 196022 97881 196022 97882 196022 97877 196023 97883 196023 97882 196023 97882 196024 97883 196024 97884 196024 97868 196025 97867 196025 97892 196025 97892 196026 97867 196026 97885 196026 97886 196027 97870 196027 97893 196027 97893 196028 97870 196028 97887 196028 97880 196029 97878 196029 97892 196029 97887 196030 97882 196030 97881 196030 97875 196031 97888 196031 97887 196031 97887 196032 97888 196032 97877 196032 97887 196033 97877 196033 97882 196033 97885 196034 97891 196034 97889 196034 97890 196035 97872 196035 97885 196035 97885 196036 97872 196036 97871 196036 97885 196037 97871 196037 97891 196037 97881 196038 97880 196038 97887 196038 97887 196039 97880 196039 97892 196039 97887 196040 97892 196040 97893 196040 97893 196041 97892 196041 97885 196041 97893 196042 97885 196042 97894 196042 97894 196043 97885 196043 97889 196043 97895 196044 97917 196044 97896 196044 97896 196045 97917 196045 97918 196045 97896 196046 97918 196046 97898 196046 97916 196047 97913 196047 97897 196047 97897 196048 97913 196048 97896 196048 97897 196049 97896 196049 97922 196049 97922 196050 97896 196050 97898 196050 97922 196051 97898 196051 97899 196051 97896 196052 97900 196052 97895 196052 97895 196053 97900 196053 97909 196053 97895 196054 97909 196054 97907 196054 97903 196055 97901 196055 97910 196055 97910 196056 97901 196056 97895 196056 97910 196057 97895 196057 97905 196057 97905 196058 97895 196058 97907 196058 97905 196059 97907 196059 97902 196059 97910 196060 97926 196060 97903 196060 97903 196061 97926 196061 97925 196061 97903 196062 97925 196062 97901 196062 97901 196063 97925 196063 97904 196063 97901 196064 97904 196064 97895 196064 97895 196065 97904 196065 97927 196065 97911 196066 97905 196066 97906 196066 97906 196067 97905 196067 97902 196067 97906 196068 97902 196068 97928 196068 97928 196069 97902 196069 97907 196069 97928 196070 97907 196070 97908 196070 97908 196071 97907 196071 97909 196071 97908 196072 97909 196072 97929 196072 97929 196073 97909 196073 97900 196073 97926 196074 97910 196074 97911 196074 97911 196075 97910 196075 97905 196075 97924 196076 97896 196076 97912 196076 97912 196077 97896 196077 97913 196077 97912 196078 97913 196078 97914 196078 97914 196079 97913 196079 97916 196079 97914 196080 97916 196080 97915 196080 97915 196081 97916 196081 97897 196081 97917 196082 97930 196082 97918 196082 97918 196083 97930 196083 97923 196083 97918 196084 97923 196084 97898 196084 97898 196085 97923 196085 97919 196085 97898 196086 97919 196086 97899 196086 97899 196087 97919 196087 97920 196087 97899 196088 97920 196088 97922 196088 97922 196089 97920 196089 97921 196089 97915 196090 97897 196090 97921 196090 97921 196091 97897 196091 97922 196091 97917 196092 97895 196092 97930 196092 97930 196093 97895 196093 97927 196093 97900 196094 97896 196094 97929 196094 97929 196095 97896 196095 97924 196095 97919 196096 97923 196096 97930 196096 97928 196097 97908 196097 97929 196097 97924 196098 97921 196098 97920 196098 97912 196099 97914 196099 97924 196099 97924 196100 97914 196100 97915 196100 97924 196101 97915 196101 97921 196101 97927 196102 97911 196102 97906 196102 97904 196103 97925 196103 97927 196103 97927 196104 97925 196104 97926 196104 97927 196105 97926 196105 97911 196105 97906 196106 97928 196106 97927 196106 97927 196107 97928 196107 97929 196107 97927 196108 97929 196108 97930 196108 97930 196109 97929 196109 97924 196109 97930 196110 97924 196110 97919 196110 97919 196111 97924 196111 97920 196111 97960 196112 97948 196112 97931 196112 97931 196113 97948 196113 97932 196113 97949 196114 97950 196114 97960 196114 97960 196115 97950 196115 97933 196115 97960 196116 97933 196116 97952 196116 97934 196117 97948 196117 97946 196117 97946 196118 97948 196118 97960 196118 97946 196119 97960 196119 97935 196119 97935 196120 97960 196120 97952 196120 97936 196121 97937 196121 97955 196121 97955 196122 97937 196122 97931 196122 97955 196123 97931 196123 97957 196123 97957 196124 97931 196124 97932 196124 97941 196125 97944 196125 97938 196125 97938 196126 97944 196126 97931 196126 97938 196127 97931 196127 97939 196127 97939 196128 97931 196128 97937 196128 97939 196129 97940 196129 97938 196129 97938 196130 97940 196130 97963 196130 97938 196131 97963 196131 97941 196131 97941 196132 97963 196132 97942 196132 97941 196133 97942 196133 97944 196133 97944 196134 97942 196134 97943 196134 97944 196135 97943 196135 97931 196135 97931 196136 97943 196136 97962 196136 97952 196137 97945 196137 97935 196137 97935 196138 97945 196138 97968 196138 97935 196139 97968 196139 97946 196139 97946 196140 97968 196140 97967 196140 97946 196141 97967 196141 97934 196141 97934 196142 97967 196142 97947 196142 97934 196143 97947 196143 97948 196143 97948 196144 97947 196144 97959 196144 97960 196145 97964 196145 97949 196145 97949 196146 97964 196146 97966 196146 97949 196147 97966 196147 97950 196147 97950 196148 97966 196148 97965 196148 97950 196149 97965 196149 97933 196149 97933 196150 97965 196150 97951 196150 97945 196151 97952 196151 97951 196151 97951 196152 97952 196152 97933 196152 97961 196153 97937 196153 97953 196153 97953 196154 97937 196154 97936 196154 97953 196155 97936 196155 97954 196155 97954 196156 97936 196156 97955 196156 97954 196157 97955 196157 97956 196157 97956 196158 97955 196158 97957 196158 97956 196159 97957 196159 97958 196159 97958 196160 97957 196160 97932 196160 97932 196161 97948 196161 97958 196161 97958 196162 97948 196162 97959 196162 97940 196163 97939 196163 97961 196163 97961 196164 97939 196164 97937 196164 97960 196165 97931 196165 97964 196165 97964 196166 97931 196166 97962 196166 97940 196167 97961 196167 97962 196167 97964 196168 97962 196168 97958 196168 97956 196169 97958 196169 97954 196169 97954 196170 97958 196170 97962 196170 97954 196171 97962 196171 97953 196171 97953 196172 97962 196172 97961 196172 97943 196173 97942 196173 97962 196173 97962 196174 97942 196174 97963 196174 97962 196175 97963 196175 97940 196175 97958 196176 97959 196176 97964 196176 97964 196177 97959 196177 97947 196177 97964 196178 97947 196178 97967 196178 97965 196179 97966 196179 97951 196179 97951 196180 97966 196180 97964 196180 97951 196181 97964 196181 97945 196181 97945 196182 97964 196182 97967 196182 97945 196183 97967 196183 97968 196183 97971 196184 97969 196184 97973 196184 97973 196185 97969 196185 97982 196185 97973 196186 97982 196186 97975 196186 97974 196187 97970 196187 97973 196187 97973 196188 97970 196188 97985 196188 97973 196189 97985 196189 97971 196189 97989 196190 97972 196190 97973 196190 97973 196191 97972 196191 97987 196191 97973 196192 97987 196192 97974 196192 97975 196193 97992 196193 97973 196193 97973 196194 97992 196194 97991 196194 97973 196195 97991 196195 97989 196195 97977 196196 97983 196196 97976 196196 97994 196197 97983 196197 97977 196197 97977 196198 97978 196198 97980 196198 97984 196199 97978 196199 97977 196199 97976 196200 97984 196200 97977 196200 97977 196201 97979 196201 97988 196201 97986 196202 97979 196202 97977 196202 97980 196203 97986 196203 97977 196203 97977 196204 97990 196204 97993 196204 97981 196205 97990 196205 97977 196205 97988 196206 97981 196206 97977 196206 97993 196207 97994 196207 97977 196207 97994 196208 97982 196208 97983 196208 97983 196209 97982 196209 97969 196209 97983 196210 97969 196210 97976 196210 97976 196211 97969 196211 97971 196211 97976 196212 97971 196212 97984 196212 97984 196213 97971 196213 97985 196213 97984 196214 97985 196214 97978 196214 97978 196215 97985 196215 97970 196215 97978 196216 97970 196216 97980 196216 97980 196217 97970 196217 97974 196217 97980 196218 97974 196218 97986 196218 97986 196219 97974 196219 97987 196219 97986 196220 97987 196220 97979 196220 97979 196221 97987 196221 97972 196221 97979 196222 97972 196222 97988 196222 97988 196223 97972 196223 97989 196223 97988 196224 97989 196224 97981 196224 97981 196225 97989 196225 97991 196225 97981 196226 97991 196226 97990 196226 97990 196227 97991 196227 97992 196227 97990 196228 97992 196228 97993 196228 97993 196229 97992 196229 97975 196229 97993 196230 97975 196230 97994 196230 97994 196231 97975 196231 97982 196231 98009 196232 98008 196232 97999 196232 97999 196233 98008 196233 98020 196233 97999 196234 98020 196234 97995 196234 97998 196235 98012 196235 97999 196235 97999 196236 98012 196236 98010 196236 97999 196237 98010 196237 98009 196237 98000 196238 97996 196238 97999 196238 97999 196239 97996 196239 97997 196239 97999 196240 97997 196240 97998 196240 97995 196241 98018 196241 97999 196241 97999 196242 98018 196242 98017 196242 97999 196243 98017 196243 98000 196243 98005 196244 98007 196244 98001 196244 98006 196245 98007 196245 98005 196245 98005 196246 98011 196246 98013 196246 98002 196247 98011 196247 98005 196247 98001 196248 98002 196248 98005 196248 98005 196249 98015 196249 98016 196249 98014 196250 98015 196250 98005 196250 98013 196251 98014 196251 98005 196251 98005 196252 98019 196252 98003 196252 98004 196253 98019 196253 98005 196253 98016 196254 98004 196254 98005 196254 98003 196255 98006 196255 98005 196255 98006 196256 98020 196256 98007 196256 98007 196257 98020 196257 98008 196257 98007 196258 98008 196258 98001 196258 98001 196259 98008 196259 98009 196259 98001 196260 98009 196260 98002 196260 98002 196261 98009 196261 98010 196261 98002 196262 98010 196262 98011 196262 98011 196263 98010 196263 98012 196263 98011 196264 98012 196264 98013 196264 98013 196265 98012 196265 97998 196265 98013 196266 97998 196266 98014 196266 98014 196267 97998 196267 97997 196267 98014 196268 97997 196268 98015 196268 98015 196269 97997 196269 97996 196269 98015 196270 97996 196270 98016 196270 98016 196271 97996 196271 98000 196271 98016 196272 98000 196272 98004 196272 98004 196273 98000 196273 98017 196273 98004 196274 98017 196274 98019 196274 98019 196275 98017 196275 98018 196275 98019 196276 98018 196276 98003 196276 98003 196277 98018 196277 97995 196277 98003 196278 97995 196278 98006 196278 98006 196279 97995 196279 98020 196279 98033 196280 98021 196280 98022 196280 98022 196281 98021 196281 98046 196281 98022 196282 98046 196282 98026 196282 98025 196283 98023 196283 98022 196283 98022 196284 98023 196284 98036 196284 98022 196285 98036 196285 98033 196285 98041 196286 98024 196286 98022 196286 98022 196287 98024 196287 98038 196287 98022 196288 98038 196288 98025 196288 98026 196289 98027 196289 98022 196289 98022 196290 98027 196290 98043 196290 98022 196291 98043 196291 98041 196291 98028 196292 98029 196292 98030 196292 98032 196293 98029 196293 98028 196293 98028 196294 98035 196294 98031 196294 98034 196295 98035 196295 98028 196295 98030 196296 98034 196296 98028 196296 98028 196297 98039 196297 98040 196297 98037 196298 98039 196298 98028 196298 98031 196299 98037 196299 98028 196299 98028 196300 98044 196300 98045 196300 98042 196301 98044 196301 98028 196301 98040 196302 98042 196302 98028 196302 98045 196303 98032 196303 98028 196303 98032 196304 98046 196304 98029 196304 98029 196305 98046 196305 98021 196305 98029 196306 98021 196306 98030 196306 98030 196307 98021 196307 98033 196307 98030 196308 98033 196308 98034 196308 98034 196309 98033 196309 98036 196309 98034 196310 98036 196310 98035 196310 98035 196311 98036 196311 98023 196311 98035 196312 98023 196312 98031 196312 98031 196313 98023 196313 98025 196313 98031 196314 98025 196314 98037 196314 98037 196315 98025 196315 98038 196315 98037 196316 98038 196316 98039 196316 98039 196317 98038 196317 98024 196317 98039 196318 98024 196318 98040 196318 98040 196319 98024 196319 98041 196319 98040 196320 98041 196320 98042 196320 98042 196321 98041 196321 98043 196321 98042 196322 98043 196322 98044 196322 98044 196323 98043 196323 98027 196323 98044 196324 98027 196324 98045 196324 98045 196325 98027 196325 98026 196325 98045 196326 98026 196326 98032 196326 98032 196327 98026 196327 98046 196327 98049 196328 98064 196328 98051 196328 98051 196329 98064 196329 98072 196329 98051 196330 98072 196330 98052 196330 98066 196331 98047 196331 98051 196331 98051 196332 98047 196332 98048 196332 98051 196333 98048 196333 98049 196333 98068 196334 98067 196334 98051 196334 98051 196335 98067 196335 98050 196335 98051 196336 98050 196336 98066 196336 98052 196337 98053 196337 98051 196337 98051 196338 98053 196338 98054 196338 98051 196339 98054 196339 98068 196339 98057 196340 98056 196340 98055 196340 98063 196341 98056 196341 98057 196341 98057 196342 98065 196342 98062 196342 98058 196343 98065 196343 98057 196343 98055 196344 98058 196344 98057 196344 98057 196345 98061 196345 98059 196345 98060 196346 98061 196346 98057 196346 98062 196347 98060 196347 98057 196347 98057 196348 98070 196348 98071 196348 98069 196349 98070 196349 98057 196349 98059 196350 98069 196350 98057 196350 98071 196351 98063 196351 98057 196351 98063 196352 98072 196352 98056 196352 98056 196353 98072 196353 98064 196353 98056 196354 98064 196354 98055 196354 98055 196355 98064 196355 98049 196355 98055 196356 98049 196356 98058 196356 98058 196357 98049 196357 98048 196357 98058 196358 98048 196358 98065 196358 98065 196359 98048 196359 98047 196359 98065 196360 98047 196360 98062 196360 98062 196361 98047 196361 98066 196361 98062 196362 98066 196362 98060 196362 98060 196363 98066 196363 98050 196363 98060 196364 98050 196364 98061 196364 98061 196365 98050 196365 98067 196365 98061 196366 98067 196366 98059 196366 98059 196367 98067 196367 98068 196367 98059 196368 98068 196368 98069 196368 98069 196369 98068 196369 98054 196369 98069 196370 98054 196370 98070 196370 98070 196371 98054 196371 98053 196371 98070 196372 98053 196372 98071 196372 98071 196373 98053 196373 98052 196373 98071 196374 98052 196374 98063 196374 98063 196375 98052 196375 98072 196375 98089 196376 98088 196376 98077 196376 98077 196377 98088 196377 98098 196377 98077 196378 98098 196378 98073 196378 98090 196379 98074 196379 98077 196379 98077 196380 98074 196380 98075 196380 98077 196381 98075 196381 98089 196381 98078 196382 98076 196382 98077 196382 98077 196383 98076 196383 98091 196383 98077 196384 98091 196384 98090 196384 98073 196385 98096 196385 98077 196385 98077 196386 98096 196386 98094 196386 98077 196387 98094 196387 98078 196387 98086 196388 98079 196388 98080 196388 98097 196389 98079 196389 98086 196389 98086 196390 98082 196390 98081 196390 98083 196391 98082 196391 98086 196391 98080 196392 98083 196392 98086 196392 98086 196393 98084 196393 98085 196393 98092 196394 98084 196394 98086 196394 98081 196395 98092 196395 98086 196395 98086 196396 98095 196396 98087 196396 98093 196397 98095 196397 98086 196397 98085 196398 98093 196398 98086 196398 98087 196399 98097 196399 98086 196399 98097 196400 98098 196400 98079 196400 98079 196401 98098 196401 98088 196401 98079 196402 98088 196402 98080 196402 98080 196403 98088 196403 98089 196403 98080 196404 98089 196404 98083 196404 98083 196405 98089 196405 98075 196405 98083 196406 98075 196406 98082 196406 98082 196407 98075 196407 98074 196407 98082 196408 98074 196408 98081 196408 98081 196409 98074 196409 98090 196409 98081 196410 98090 196410 98092 196410 98092 196411 98090 196411 98091 196411 98092 196412 98091 196412 98084 196412 98084 196413 98091 196413 98076 196413 98084 196414 98076 196414 98085 196414 98085 196415 98076 196415 98078 196415 98085 196416 98078 196416 98093 196416 98093 196417 98078 196417 98094 196417 98093 196418 98094 196418 98095 196418 98095 196419 98094 196419 98096 196419 98095 196420 98096 196420 98087 196420 98087 196421 98096 196421 98073 196421 98087 196422 98073 196422 98097 196422 98097 196423 98073 196423 98098 196423 98111 196424 98110 196424 98100 196424 98100 196425 98110 196425 98124 196425 98100 196426 98124 196426 98099 196426 98103 196427 98115 196427 98100 196427 98100 196428 98115 196428 98113 196428 98100 196429 98113 196429 98111 196429 98118 196430 98101 196430 98100 196430 98100 196431 98101 196431 98102 196431 98100 196432 98102 196432 98103 196432 98099 196433 98122 196433 98100 196433 98100 196434 98122 196434 98120 196434 98100 196435 98120 196435 98118 196435 98108 196436 98104 196436 98109 196436 98123 196437 98104 196437 98108 196437 98108 196438 98114 196438 98105 196438 98112 196439 98114 196439 98108 196439 98109 196440 98112 196440 98108 196440 98108 196441 98117 196441 98107 196441 98116 196442 98117 196442 98108 196442 98105 196443 98116 196443 98108 196443 98108 196444 98121 196444 98106 196444 98119 196445 98121 196445 98108 196445 98107 196446 98119 196446 98108 196446 98106 196447 98123 196447 98108 196447 98123 196448 98124 196448 98104 196448 98104 196449 98124 196449 98110 196449 98104 196450 98110 196450 98109 196450 98109 196451 98110 196451 98111 196451 98109 196452 98111 196452 98112 196452 98112 196453 98111 196453 98113 196453 98112 196454 98113 196454 98114 196454 98114 196455 98113 196455 98115 196455 98114 196456 98115 196456 98105 196456 98105 196457 98115 196457 98103 196457 98105 196458 98103 196458 98116 196458 98116 196459 98103 196459 98102 196459 98116 196460 98102 196460 98117 196460 98117 196461 98102 196461 98101 196461 98117 196462 98101 196462 98107 196462 98107 196463 98101 196463 98118 196463 98107 196464 98118 196464 98119 196464 98119 196465 98118 196465 98120 196465 98119 196466 98120 196466 98121 196466 98121 196467 98120 196467 98122 196467 98121 196468 98122 196468 98106 196468 98106 196469 98122 196469 98099 196469 98106 196470 98099 196470 98123 196470 98123 196471 98099 196471 98124 196471 102007 196472 105431 196472 98125 196472 98125 196473 105431 196473 98126 196473 98125 196474 98126 196474 102018 196474 98126 196475 98127 196475 102018 196475 102018 196476 98127 196476 105640 196476 102018 196477 105640 196477 98128 196477 98128 196478 105640 196478 105642 196478 98128 196479 105642 196479 102016 196479 102016 196480 105642 196480 105535 196480 102016 196481 105535 196481 98129 196481 98129 196482 105535 196482 105537 196482 98129 196483 105537 196483 102002 196483 102002 196484 105537 196484 105430 196484 102002 196485 105430 196485 98130 196485 105430 196486 98131 196486 98130 196486 98130 196487 98131 196487 98133 196487 98130 196488 98133 196488 98132 196488 98132 196489 98133 196489 105606 196489 98132 196490 105606 196490 101999 196490 101999 196491 105606 196491 105607 196491 101999 196492 105607 196492 98134 196492 98134 196493 105607 196493 105609 196493 98134 196494 105609 196494 102005 196494 102005 196495 105609 196495 105563 196495 102005 196496 105563 196496 98135 196496 105563 196497 105564 196497 98135 196497 98135 196498 105564 196498 98137 196498 98135 196499 98137 196499 98136 196499 98136 196500 98137 196500 98138 196500 98136 196501 98138 196501 102010 196501 102010 196502 98138 196502 105427 196502 102010 196503 105427 196503 102008 196503 102008 196504 105427 196504 105623 196504 102008 196505 105623 196505 101998 196505 101998 196506 105623 196506 98139 196506 101998 196507 98139 196507 101996 196507 101996 196508 98139 196508 105624 196508 101996 196509 105624 196509 98141 196509 105624 196510 98140 196510 98141 196510 98141 196511 98140 196511 105633 196511 98141 196512 105633 196512 98142 196512 98142 196513 105633 196513 98143 196513 98142 196514 98143 196514 98144 196514 98144 196515 98143 196515 98145 196515 98144 196516 98145 196516 102013 196516 102013 196517 98145 196517 105635 196517 102013 196518 105635 196518 98147 196518 98147 196519 105635 196519 98146 196519 98147 196520 98146 196520 98148 196520 98148 196521 98146 196521 105589 196521 98148 196522 105589 196522 98149 196522 98149 196523 105589 196523 98150 196523 98149 196524 98150 196524 102007 196524 102007 196525 98150 196525 105628 196525 102007 196526 105628 196526 105431 196526 104557 196527 98156 196527 98157 196527 98154 196528 98156 196528 104557 196528 98151 196529 98154 196529 104557 196529 104557 196530 98152 196530 98159 196530 98158 196531 98152 196531 104557 196531 98157 196532 98158 196532 104557 196532 98151 196533 98153 196533 98154 196533 98154 196534 98153 196534 98155 196534 98154 196535 98155 196535 98156 196535 98156 196536 98155 196536 104538 196536 98156 196537 104538 196537 98157 196537 98157 196538 104538 196538 104540 196538 98157 196539 104540 196539 98158 196539 98158 196540 104540 196540 104542 196540 98158 196541 104542 196541 98152 196541 98152 196542 104542 196542 98160 196542 98152 196543 98160 196543 98159 196543 98159 196544 98160 196544 104545 196544 98167 196545 98161 196545 98162 196545 98162 196546 98161 196546 98163 196546 98162 196547 98163 196547 98166 196547 98166 196548 98163 196548 98164 196548 98166 196549 98164 196549 98165 196549 98165 196550 98164 196550 104525 196550 98165 196551 104525 196551 98170 196551 98170 196552 104525 196552 104526 196552 98170 196553 104526 196553 98169 196553 98169 196554 104526 196554 104528 196554 98169 196555 104528 196555 98168 196555 98168 196556 104528 196556 104517 196556 104515 196557 98166 196557 98165 196557 98162 196558 98166 196558 104515 196558 98167 196559 98162 196559 104515 196559 104515 196560 98169 196560 98168 196560 98170 196561 98169 196561 104515 196561 98165 196562 98170 196562 104515 196562 104500 196563 98171 196563 98179 196563 98179 196564 98171 196564 98172 196564 98179 196565 98172 196565 98173 196565 98173 196566 98172 196566 104504 196566 98173 196567 104504 196567 98174 196567 98174 196568 104504 196568 104506 196568 98174 196569 104506 196569 98180 196569 98180 196570 104506 196570 98175 196570 98180 196571 98175 196571 98176 196571 98176 196572 98175 196572 98178 196572 98176 196573 98178 196573 98177 196573 98177 196574 98178 196574 104509 196574 104492 196575 98173 196575 98174 196575 98179 196576 98173 196576 104492 196576 104500 196577 98179 196577 104492 196577 104492 196578 98176 196578 98177 196578 98180 196579 98176 196579 104492 196579 98174 196580 98180 196580 104492 196580 104465 196581 104486 196581 98181 196581 98181 196582 104486 196582 104487 196582 98181 196583 104487 196583 98186 196583 98186 196584 104487 196584 104476 196584 98186 196585 104476 196585 98182 196585 98182 196586 104476 196586 98183 196586 98182 196587 98183 196587 98184 196587 98184 196588 98183 196588 98185 196588 98184 196589 98185 196589 98187 196589 98187 196590 98185 196590 104480 196590 98187 196591 104480 196591 98188 196591 98188 196592 104480 196592 104468 196592 104464 196593 98186 196593 98182 196593 98181 196594 98186 196594 104464 196594 104465 196595 98181 196595 104464 196595 104464 196596 98187 196596 98188 196596 98184 196597 98187 196597 104464 196597 98182 196598 98184 196598 104464 196598 104450 196599 104461 196599 98189 196599 98189 196600 104461 196600 104462 196600 98189 196601 104462 196601 98190 196601 98190 196602 104462 196602 98191 196602 98190 196603 98191 196603 98192 196603 98192 196604 98191 196604 104453 196604 98192 196605 104453 196605 98193 196605 98193 196606 104453 196606 98194 196606 98193 196607 98194 196607 98195 196607 98195 196608 98194 196608 104454 196608 98195 196609 104454 196609 98196 196609 98196 196610 104454 196610 104456 196610 104444 196611 98190 196611 98192 196611 98189 196612 98190 196612 104444 196612 104450 196613 98189 196613 104444 196613 104444 196614 98195 196614 98196 196614 98193 196615 98195 196615 104444 196615 98192 196616 98193 196616 104444 196616 104424 196617 98197 196617 98206 196617 98206 196618 98197 196618 104439 196618 98206 196619 104439 196619 98205 196619 98205 196620 104439 196620 98198 196620 98205 196621 98198 196621 98203 196621 98203 196622 98198 196622 104426 196622 98203 196623 104426 196623 98204 196623 98204 196624 104426 196624 98199 196624 98204 196625 98199 196625 98200 196625 98200 196626 98199 196626 98201 196626 98200 196627 98201 196627 98208 196627 98208 196628 98201 196628 104431 196628 98208 196629 104431 196629 98202 196629 98202 196630 104431 196630 104416 196630 98207 196631 104424 196631 98206 196631 98207 196632 98203 196632 98204 196632 98205 196633 98203 196633 98207 196633 98206 196634 98205 196634 98207 196634 98207 196635 98208 196635 98202 196635 98200 196636 98208 196636 98207 196636 98204 196637 98200 196637 98207 196637 104401 196638 104411 196638 98209 196638 98209 196639 104411 196639 104413 196639 98209 196640 104413 196640 98215 196640 98215 196641 104413 196641 104414 196641 98215 196642 104414 196642 98214 196642 98214 196643 104414 196643 98210 196643 98214 196644 98210 196644 98216 196644 98216 196645 98210 196645 98212 196645 98216 196646 98212 196646 98211 196646 98211 196647 98212 196647 98213 196647 98211 196648 98213 196648 104395 196648 104395 196649 98213 196649 104406 196649 104392 196650 98215 196650 98214 196650 98209 196651 98215 196651 104392 196651 104401 196652 98209 196652 104392 196652 104392 196653 98211 196653 104395 196653 98216 196654 98211 196654 104392 196654 98214 196655 98216 196655 104392 196655 104374 196656 98217 196656 98224 196656 98224 196657 98217 196657 98219 196657 98224 196658 98219 196658 98218 196658 98218 196659 98219 196659 98221 196659 98218 196660 98221 196660 98220 196660 98220 196661 98221 196661 104391 196661 98220 196662 104391 196662 98226 196662 98226 196663 104391 196663 104384 196663 98226 196664 104384 196664 98222 196664 98222 196665 104384 196665 98223 196665 98222 196666 98223 196666 98225 196666 98225 196667 98223 196667 104385 196667 104373 196668 98218 196668 98220 196668 98224 196669 98218 196669 104373 196669 104374 196670 98224 196670 104373 196670 104373 196671 98222 196671 98225 196671 98226 196672 98222 196672 104373 196672 98220 196673 98226 196673 104373 196673 104350 196674 104356 196674 98227 196674 98227 196675 104356 196675 98228 196675 98227 196676 98228 196676 98232 196676 98232 196677 98228 196677 98229 196677 98232 196678 98229 196678 98230 196678 98230 196679 98229 196679 104364 196679 98230 196680 104364 196680 98231 196680 98231 196681 104364 196681 104366 196681 98231 196682 104366 196682 98234 196682 98234 196683 104366 196683 104367 196683 98234 196684 104367 196684 104352 196684 104352 196685 104367 196685 104370 196685 98233 196686 98232 196686 98230 196686 98227 196687 98232 196687 98233 196687 104350 196688 98227 196688 98233 196688 98233 196689 98234 196689 104352 196689 98231 196690 98234 196690 98233 196690 98230 196691 98231 196691 98233 196691 98243 196692 98236 196692 98235 196692 98235 196693 98236 196693 104346 196693 98235 196694 104346 196694 98241 196694 98241 196695 104346 196695 104333 196695 98241 196696 104333 196696 98237 196696 98237 196697 104333 196697 104335 196697 98237 196698 104335 196698 98244 196698 98244 196699 104335 196699 104336 196699 98244 196700 104336 196700 98245 196700 98245 196701 104336 196701 98238 196701 98245 196702 98238 196702 98239 196702 98239 196703 98238 196703 98240 196703 98242 196704 98241 196704 98237 196704 98235 196705 98241 196705 98242 196705 98243 196706 98235 196706 98242 196706 98242 196707 98245 196707 98239 196707 98244 196708 98245 196708 98242 196708 98237 196709 98244 196709 98242 196709 98250 196710 98246 196710 98252 196710 98247 196711 98248 196711 98249 196711 98249 196712 98248 196712 102066 196712 98249 196713 102066 196713 98251 196713 98250 196714 98252 196714 98251 196714 98251 196715 98252 196715 98269 196715 98251 196716 98269 196716 98249 196716 98249 196717 98269 196717 98253 196717 98249 196718 98253 196718 98247 196718 98246 196719 102063 196719 98252 196719 98252 196720 102063 196720 102062 196720 98252 196721 102062 196721 98255 196721 99212 196722 98254 196722 102060 196722 102060 196723 98254 196723 98255 196723 102060 196724 98255 196724 98256 196724 98256 196725 98255 196725 102062 196725 102433 196726 98372 196726 98257 196726 98257 196727 98372 196727 102435 196727 102435 196728 102434 196728 98257 196728 98257 196729 102434 196729 102430 196729 98257 196730 102430 196730 102433 196730 102433 196731 102430 196731 98258 196731 102426 196732 102412 196732 98261 196732 98261 196733 102412 196733 98259 196733 98259 196734 102415 196734 98261 196734 98261 196735 102415 196735 98260 196735 98261 196736 98260 196736 102417 196736 102417 196737 98262 196737 98261 196737 98261 196738 98262 196738 98263 196738 98261 196739 98263 196739 103611 196739 102420 196740 98252 196740 98264 196740 98264 196741 98252 196741 103611 196741 98264 196742 103611 196742 102419 196742 102419 196743 103611 196743 98263 196743 102420 196744 102422 196744 98252 196744 98252 196745 102422 196745 98265 196745 98252 196746 98265 196746 98269 196746 98269 196747 98265 196747 102425 196747 98269 196748 102425 196748 98268 196748 102400 196749 98266 196749 98267 196749 98267 196750 98266 196750 102398 196750 98268 196751 102400 196751 98269 196751 98269 196752 102400 196752 98267 196752 98269 196753 98267 196753 102395 196753 102395 196754 98267 196754 102398 196754 102395 196755 102398 196755 102397 196755 98271 196756 98272 196756 98270 196756 98270 196757 98272 196757 102484 196757 98271 196758 102486 196758 98272 196758 98272 196759 102486 196759 102487 196759 98272 196760 102487 196760 103608 196760 102487 196761 102488 196761 103608 196761 103608 196762 102488 196762 102491 196762 103608 196763 102491 196763 98368 196763 98368 196764 102491 196764 98273 196764 98367 196765 102495 196765 102442 196765 102442 196766 102495 196766 102461 196766 98276 196767 98274 196767 98277 196767 98277 196768 98274 196768 98275 196768 102461 196769 98276 196769 102442 196769 102442 196770 98276 196770 98277 196770 102442 196771 98277 196771 102455 196771 102455 196772 98277 196772 98275 196772 102455 196773 98275 196773 102456 196773 98364 196774 102504 196774 98278 196774 102504 196775 98364 196775 102507 196775 98366 196776 98279 196776 98365 196776 98362 196777 102479 196777 103606 196777 103606 196778 102479 196778 98280 196778 103606 196779 98280 196779 98281 196779 98281 196780 98280 196780 102481 196780 98281 196781 102481 196781 98272 196781 98272 196782 102481 196782 102483 196782 98272 196783 102483 196783 102484 196783 98282 196784 103604 196784 102556 196784 102556 196785 103604 196785 103602 196785 102556 196786 103602 196786 98283 196786 98283 196787 103602 196787 98284 196787 98283 196788 98284 196788 102554 196788 102558 196789 102559 196789 98287 196789 98287 196790 102559 196790 98285 196790 102523 196791 102519 196791 98286 196791 98286 196792 102519 196792 102516 196792 98285 196793 102523 196793 98287 196793 98287 196794 102523 196794 98286 196794 98287 196795 98286 196795 102514 196795 102514 196796 98286 196796 102516 196796 102514 196797 102516 196797 102515 196797 98288 196798 102576 196798 102566 196798 102576 196799 98288 196799 98290 196799 98292 196800 102568 196800 98291 196800 102545 196801 98289 196801 102544 196801 102544 196802 98289 196802 98290 196802 102544 196803 98290 196803 98291 196803 98291 196804 98290 196804 98288 196804 98291 196805 98288 196805 98292 196805 98292 196806 98288 196806 102566 196806 98294 196807 103600 196807 98293 196807 98293 196808 103600 196808 98289 196808 98293 196809 98289 196809 102548 196809 102548 196810 98289 196810 102545 196810 98294 196811 98295 196811 103600 196811 103600 196812 98295 196812 102551 196812 103600 196813 102551 196813 98284 196813 98284 196814 102551 196814 102552 196814 98284 196815 102552 196815 102554 196815 98357 196816 98308 196816 98309 196816 98356 196817 102630 196817 98358 196817 98358 196818 102630 196818 102593 196818 102590 196819 102589 196819 98296 196819 98296 196820 102589 196820 98297 196820 102593 196821 102590 196821 98358 196821 98358 196822 102590 196822 98296 196822 98358 196823 98296 196823 102572 196823 102572 196824 98296 196824 98297 196824 102572 196825 98297 196825 98298 196825 98299 196826 102641 196826 98301 196826 98301 196827 102641 196827 102640 196827 102640 196828 98300 196828 98301 196828 98301 196829 98300 196829 98302 196829 98301 196830 98302 196830 98299 196830 98299 196831 98302 196831 98303 196831 102615 196832 102614 196832 98355 196832 98355 196833 102614 196833 102617 196833 102617 196834 102620 196834 98355 196834 98355 196835 102620 196835 98304 196835 98355 196836 98304 196836 103595 196836 103595 196837 98304 196837 98305 196837 103595 196838 98305 196838 102622 196838 102622 196839 102623 196839 103595 196839 103595 196840 102623 196840 102624 196840 103595 196841 102624 196841 98306 196841 98306 196842 102624 196842 102625 196842 102625 196843 102626 196843 98306 196843 98306 196844 102626 196844 102628 196844 98306 196845 102628 196845 98308 196845 98308 196846 102628 196846 98307 196846 98308 196847 98307 196847 98309 196847 98315 196848 98317 196848 102633 196848 102633 196849 98317 196849 98310 196849 102633 196850 98310 196850 102634 196850 98311 196851 98313 196851 98312 196851 98312 196852 98313 196852 102631 196852 98312 196853 102631 196853 98315 196853 98315 196854 102631 196854 98314 196854 98315 196855 98314 196855 98317 196855 98317 196856 98314 196856 98316 196856 98317 196857 98316 196857 98310 196857 98319 196858 102570 196858 98318 196858 98318 196859 102570 196859 102571 196859 102571 196860 102583 196860 98318 196860 98318 196861 102583 196861 102580 196861 98318 196862 102580 196862 98319 196862 98319 196863 102580 196863 102582 196863 98320 196864 98321 196864 98353 196864 98353 196865 98321 196865 102612 196865 102612 196866 102611 196866 98353 196866 98353 196867 102611 196867 102610 196867 98353 196868 102610 196868 98326 196868 98326 196869 102610 196869 102607 196869 98326 196870 102607 196870 102606 196870 102601 196871 98322 196871 98323 196871 98323 196872 98322 196872 102598 196872 98323 196873 102598 196873 98324 196873 98324 196874 102598 196874 102597 196874 98324 196875 102597 196875 98325 196875 102606 196876 102605 196876 98326 196876 98326 196877 102605 196877 98327 196877 98326 196878 98327 196878 98323 196878 98323 196879 98327 196879 102602 196879 98323 196880 102602 196880 102601 196880 102532 196881 102524 196881 98347 196881 102532 196882 98347 196882 98332 196882 98329 196883 102512 196883 102508 196883 102512 196884 98329 196884 98340 196884 98328 196885 102509 196885 102511 196885 102508 196886 98328 196886 98329 196886 98329 196887 98328 196887 102511 196887 98329 196888 102511 196888 98340 196888 98340 196889 102511 196889 102543 196889 98340 196890 102543 196890 98339 196890 98339 196891 102543 196891 98330 196891 98339 196892 98330 196892 102540 196892 102540 196893 98331 196893 98339 196893 98339 196894 98331 196894 102539 196894 98339 196895 102539 196895 102538 196895 102534 196896 103586 196896 102535 196896 102535 196897 103586 196897 98339 196897 102535 196898 98339 196898 102537 196898 102537 196899 98339 196899 102538 196899 102534 196900 102525 196900 103586 196900 103586 196901 102525 196901 102528 196901 103586 196902 102528 196902 98347 196902 98347 196903 102528 196903 102530 196903 98347 196904 102530 196904 98332 196904 98346 196905 102560 196905 98334 196905 102564 196906 102563 196906 98333 196906 98333 196907 102563 196907 98336 196907 102560 196908 102564 196908 98334 196908 98334 196909 102564 196909 98333 196909 98334 196910 98333 196910 98335 196910 98335 196911 98333 196911 98336 196911 98335 196912 98336 196912 102561 196912 103583 196913 102032 196913 98337 196913 98337 196914 102032 196914 102033 196914 98337 196915 102033 196915 98339 196915 102033 196916 102029 196916 98339 196916 98339 196917 102029 196917 98338 196917 98339 196918 98338 196918 102030 196918 98340 196919 98343 196919 98341 196919 98341 196920 98343 196920 102023 196920 98341 196921 102023 196921 102021 196921 102030 196922 102028 196922 98339 196922 98339 196923 102028 196923 98342 196923 98339 196924 98342 196924 98340 196924 98340 196925 98342 196925 98344 196925 98340 196926 98344 196926 98343 196926 98343 196927 98344 196927 98345 196927 98343 196928 98345 196928 102023 196928 102524 196929 98346 196929 98347 196929 98347 196930 98346 196930 98334 196930 98347 196931 98334 196931 98348 196931 98348 196932 98334 196932 98350 196932 98348 196933 98350 196933 98349 196933 98349 196934 98350 196934 98351 196934 98349 196935 98351 196935 103589 196935 103589 196936 98351 196936 98352 196936 103589 196937 98352 196937 98353 196937 98353 196938 98352 196938 102570 196938 98353 196939 102570 196939 98320 196939 98320 196940 102570 196940 98319 196940 102597 196941 98311 196941 98325 196941 98325 196942 98311 196942 98312 196942 98325 196943 98312 196943 98354 196943 98354 196944 98312 196944 102643 196944 98354 196945 102643 196945 98355 196945 98355 196946 102643 196946 102641 196946 98355 196947 102641 196947 102615 196947 102615 196948 102641 196948 98299 196948 98309 196949 98356 196949 98357 196949 98357 196950 98356 196950 98358 196950 98357 196951 98358 196951 103598 196951 103598 196952 98358 196952 102577 196952 103598 196953 102577 196953 98289 196953 98289 196954 102577 196954 98359 196954 98289 196955 98359 196955 98290 196955 98282 196956 102558 196956 103604 196956 103604 196957 102558 196957 98287 196957 103604 196958 98287 196958 98360 196958 98360 196959 98287 196959 98361 196959 98360 196960 98361 196960 103606 196960 103606 196961 98361 196961 98363 196961 103606 196962 98363 196962 98362 196962 98362 196963 98363 196963 102507 196963 98362 196964 102507 196964 98365 196964 98365 196965 102507 196965 98364 196965 98365 196966 98364 196966 98366 196966 98366 196967 98364 196967 98278 196967 98273 196968 98367 196968 98368 196968 98368 196969 98367 196969 102442 196969 98368 196970 102442 196970 98369 196970 98369 196971 102442 196971 102446 196971 98369 196972 102446 196972 98370 196972 98370 196973 102446 196973 102447 196973 98370 196974 102447 196974 98371 196974 98371 196975 102447 196975 102448 196975 98371 196976 102448 196976 98261 196976 98261 196977 102448 196977 98372 196977 98261 196978 98372 196978 102426 196978 102426 196979 98372 196979 102433 196979 103836 196980 104037 196980 98373 196980 98373 196981 104037 196981 98375 196981 98373 196982 98375 196982 98374 196982 98374 196983 98375 196983 98916 196983 98374 196984 98916 196984 98376 196984 98376 196985 98916 196985 98377 196985 98376 196986 98377 196986 103808 196986 103808 196987 98377 196987 98378 196987 103808 196988 98378 196988 103809 196988 103809 196989 98378 196989 98379 196989 103809 196990 98379 196990 98380 196990 98380 196991 98379 196991 98381 196991 98380 196992 98381 196992 103811 196992 103811 196993 98381 196993 98382 196993 103811 196994 98382 196994 103813 196994 103813 196995 98382 196995 98383 196995 103813 196996 98383 196996 98384 196996 98384 196997 98383 196997 98920 196997 98384 196998 98920 196998 98385 196998 98385 196999 98920 196999 98921 196999 98385 197000 98921 197000 103815 197000 103815 197001 98921 197001 98386 197001 103815 197002 98386 197002 103816 197002 103816 197003 98386 197003 98387 197003 103816 197004 98387 197004 103817 197004 103817 197005 98387 197005 98388 197005 103817 197006 98388 197006 103819 197006 103819 197007 98388 197007 98389 197007 103819 197008 98389 197008 98390 197008 98390 197009 98389 197009 98925 197009 98390 197010 98925 197010 103821 197010 103821 197011 98925 197011 98926 197011 103821 197012 98926 197012 98391 197012 98391 197013 98926 197013 104017 197013 103170 197014 98392 197014 98913 197014 98913 197015 98392 197015 98393 197015 98913 197016 98393 197016 98395 197016 98395 197017 98393 197017 98394 197017 98395 197018 98394 197018 98912 197018 98912 197019 98394 197019 99077 197019 98912 197020 99077 197020 98396 197020 98396 197021 99077 197021 98397 197021 98396 197022 98397 197022 98909 197022 98909 197023 98397 197023 99078 197023 98909 197024 99078 197024 98908 197024 98908 197025 99078 197025 98398 197025 98908 197026 98398 197026 98906 197026 98906 197027 98398 197027 98399 197027 98906 197028 98399 197028 98400 197028 98400 197029 98399 197029 99080 197029 98400 197030 99080 197030 98905 197030 98905 197031 99080 197031 98401 197031 98905 197032 98401 197032 98402 197032 98402 197033 98401 197033 99082 197033 98402 197034 99082 197034 98403 197034 98403 197035 99082 197035 99083 197035 98403 197036 99083 197036 98904 197036 98904 197037 99083 197037 98404 197037 98904 197038 98404 197038 98903 197038 98903 197039 98404 197039 99087 197039 98903 197040 99087 197040 98902 197040 98902 197041 99087 197041 99088 197041 98902 197042 99088 197042 98900 197042 98900 197043 99088 197043 99090 197043 98900 197044 99090 197044 98406 197044 98406 197045 99090 197045 98405 197045 98406 197046 98405 197046 98407 197046 98407 197047 98405 197047 103998 197047 103997 197048 102172 197048 98408 197048 98408 197049 102172 197049 99144 197049 98408 197050 99144 197050 99142 197050 99142 197051 99144 197051 98409 197051 99142 197052 98409 197052 99141 197052 99141 197053 98409 197053 99146 197053 99141 197054 99146 197054 98410 197054 98410 197055 99146 197055 99148 197055 98410 197056 99148 197056 99139 197056 99139 197057 99148 197057 99149 197057 99139 197058 99149 197058 98411 197058 98411 197059 99149 197059 99150 197059 98411 197060 99150 197060 99137 197060 99137 197061 99150 197061 98412 197061 99137 197062 98412 197062 98413 197062 98413 197063 98412 197063 99151 197063 98413 197064 99151 197064 99135 197064 99135 197065 99151 197065 99152 197065 99135 197066 99152 197066 99133 197066 99133 197067 99152 197067 98415 197067 99133 197068 98415 197068 98414 197068 98414 197069 98415 197069 98416 197069 98414 197070 98416 197070 99130 197070 99130 197071 98416 197071 99154 197071 99130 197072 99154 197072 98417 197072 98417 197073 99154 197073 98419 197073 98417 197074 98419 197074 98418 197074 98418 197075 98419 197075 99157 197075 98418 197076 99157 197076 99129 197076 99129 197077 99157 197077 99158 197077 99129 197078 99158 197078 98420 197078 98420 197079 99158 197079 99160 197079 98421 197080 103654 197080 99125 197080 99125 197081 103654 197081 103658 197081 99125 197082 103658 197082 103977 197082 103977 197083 103658 197083 98422 197083 103977 197084 98422 197084 103661 197084 98421 197085 99125 197085 98423 197085 98423 197086 99125 197086 98426 197086 98423 197087 98426 197087 103581 197087 98424 197088 103579 197088 99122 197088 99122 197089 103579 197089 103580 197089 99122 197090 103580 197090 98426 197090 98426 197091 103580 197091 98425 197091 98426 197092 98425 197092 103581 197092 98424 197093 99122 197093 98427 197093 98427 197094 99122 197094 98430 197094 98427 197095 98430 197095 98431 197095 103576 197096 103577 197096 98433 197096 98433 197097 103577 197097 98428 197097 98433 197098 98428 197098 98430 197098 98430 197099 98428 197099 98429 197099 98430 197100 98429 197100 98431 197100 103576 197101 98433 197101 98432 197101 98432 197102 98433 197102 98434 197102 98432 197103 98434 197103 98435 197103 98439 197104 103573 197104 98436 197104 98439 197105 98436 197105 98434 197105 98434 197106 98436 197106 103574 197106 98434 197107 103574 197107 98435 197107 98438 197108 98437 197108 103571 197108 98438 197109 103571 197109 98439 197109 98439 197110 103571 197110 103572 197110 98439 197111 103572 197111 103573 197111 103569 197112 103570 197112 98443 197112 98443 197113 103570 197113 98440 197113 98443 197114 98440 197114 98438 197114 98438 197115 98440 197115 98441 197115 98438 197116 98441 197116 98437 197116 103569 197117 98443 197117 98442 197117 98442 197118 98443 197118 99117 197118 98442 197119 99117 197119 103568 197119 98447 197120 103566 197120 98444 197120 98447 197121 98444 197121 99117 197121 99117 197122 98444 197122 98445 197122 99117 197123 98445 197123 103568 197123 103563 197124 103564 197124 98446 197124 98446 197125 103564 197125 103565 197125 98446 197126 103565 197126 98447 197126 98447 197127 103565 197127 98448 197127 98447 197128 98448 197128 103566 197128 103563 197129 98446 197129 103561 197129 103561 197130 98446 197130 98449 197130 103561 197131 98449 197131 103560 197131 103553 197132 103556 197132 98450 197132 98450 197133 103556 197133 103557 197133 98450 197134 103557 197134 98449 197134 98449 197135 103557 197135 103558 197135 98449 197136 103558 197136 103560 197136 103553 197137 98450 197137 103552 197137 103552 197138 98450 197138 99116 197138 103552 197139 99116 197139 103551 197139 98455 197140 98451 197140 103549 197140 98455 197141 103549 197141 99116 197141 99116 197142 103549 197142 98452 197142 99116 197143 98452 197143 103551 197143 98456 197144 98453 197144 99112 197144 99112 197145 98453 197145 98454 197145 99112 197146 98454 197146 98455 197146 98455 197147 98454 197147 103548 197147 98455 197148 103548 197148 98451 197148 98456 197149 99112 197149 103545 197149 103545 197150 99112 197150 103944 197150 103545 197151 103944 197151 98642 197151 103851 197152 102212 197152 103852 197152 103852 197153 102212 197153 99093 197153 103852 197154 99093 197154 103853 197154 103853 197155 99093 197155 99094 197155 103853 197156 99094 197156 103855 197156 103855 197157 99094 197157 99095 197157 103855 197158 99095 197158 103858 197158 103858 197159 99095 197159 98457 197159 103858 197160 98457 197160 98458 197160 98458 197161 98457 197161 99097 197161 98458 197162 99097 197162 103860 197162 103860 197163 99097 197163 99098 197163 103860 197164 99098 197164 103861 197164 103861 197165 99098 197165 99099 197165 103861 197166 99099 197166 98459 197166 98459 197167 99099 197167 98461 197167 98459 197168 98461 197168 98460 197168 98460 197169 98461 197169 98462 197169 98460 197170 98462 197170 103864 197170 103864 197171 98462 197171 99101 197171 103864 197172 99101 197172 103865 197172 103865 197173 99101 197173 99102 197173 103865 197174 99102 197174 103866 197174 103866 197175 99102 197175 99105 197175 103866 197176 99105 197176 103868 197176 103868 197177 99105 197177 98463 197177 103868 197178 98463 197178 103869 197178 103869 197179 98463 197179 99106 197179 103869 197180 99106 197180 98464 197180 98464 197181 99106 197181 99107 197181 98464 197182 99107 197182 103871 197182 103871 197183 99107 197183 99108 197183 103871 197184 99108 197184 98465 197184 98465 197185 99108 197185 99110 197185 98465 197186 99110 197186 103872 197186 103872 197187 99110 197187 99111 197187 103804 197188 103803 197188 98466 197188 103804 197189 98466 197189 103834 197189 103834 197190 98466 197190 99186 197190 103834 197191 99186 197191 103833 197191 103833 197192 99186 197192 99185 197192 103833 197193 99185 197193 103832 197193 103832 197194 99185 197194 99183 197194 103832 197195 99183 197195 103831 197195 103831 197196 99183 197196 98468 197196 103831 197197 98468 197197 98467 197197 98467 197198 98468 197198 98469 197198 98467 197199 98469 197199 103828 197199 103828 197200 98469 197200 98470 197200 103828 197201 98470 197201 98471 197201 98471 197202 98470 197202 98472 197202 98471 197203 98472 197203 98473 197203 98473 197204 98472 197204 99178 197204 98473 197205 99178 197205 103826 197205 103826 197206 99178 197206 99177 197206 103826 197207 99177 197207 98474 197207 98474 197208 99177 197208 99176 197208 98474 197209 99176 197209 98475 197209 98475 197210 99176 197210 98476 197210 98475 197211 98476 197211 103824 197211 103824 197212 98476 197212 98478 197212 103824 197213 98478 197213 98477 197213 98477 197214 98478 197214 98479 197214 98477 197215 98479 197215 98480 197215 98480 197216 98479 197216 98481 197216 98480 197217 98481 197217 98482 197217 98482 197218 98481 197218 98483 197218 98482 197219 98483 197219 98484 197219 98484 197220 98483 197220 102138 197220 98484 197221 102138 197221 103822 197221 103787 197222 103758 197222 98486 197222 103787 197223 98486 197223 98485 197223 98485 197224 98486 197224 99075 197224 98485 197225 99075 197225 103786 197225 103786 197226 99075 197226 98487 197226 103786 197227 98487 197227 103783 197227 103783 197228 98487 197228 99072 197228 103783 197229 99072 197229 98488 197229 98488 197230 99072 197230 98489 197230 98488 197231 98489 197231 103782 197231 103782 197232 98489 197232 99071 197232 103782 197233 99071 197233 103781 197233 103781 197234 99071 197234 98490 197234 103781 197235 98490 197235 103779 197235 103779 197236 98490 197236 98491 197236 103779 197237 98491 197237 98492 197237 98492 197238 98491 197238 98493 197238 98492 197239 98493 197239 98494 197239 98494 197240 98493 197240 98495 197240 98494 197241 98495 197241 103776 197241 103776 197242 98495 197242 98496 197242 103776 197243 98496 197243 98497 197243 98497 197244 98496 197244 99067 197244 98497 197245 99067 197245 98498 197245 98498 197246 99067 197246 98499 197246 98498 197247 98499 197247 98500 197247 98500 197248 98499 197248 99065 197248 98500 197249 99065 197249 103773 197249 103773 197250 99065 197250 99064 197250 103773 197251 99064 197251 98501 197251 98501 197252 99064 197252 98502 197252 98501 197253 98502 197253 103740 197253 103671 197254 98503 197254 103672 197254 103672 197255 98503 197255 98504 197255 103672 197256 98504 197256 98505 197256 98505 197257 98504 197257 98506 197257 98505 197258 98506 197258 98507 197258 98507 197259 98506 197259 98508 197259 98507 197260 98508 197260 103675 197260 103675 197261 98508 197261 98509 197261 103675 197262 98509 197262 98510 197262 98510 197263 98509 197263 98511 197263 98510 197264 98511 197264 103678 197264 103678 197265 98511 197265 98512 197265 103678 197266 98512 197266 98513 197266 98513 197267 98512 197267 98514 197267 98513 197268 98514 197268 103681 197268 103681 197269 98514 197269 98515 197269 103681 197270 98515 197270 98516 197270 98516 197271 98515 197271 99164 197271 98516 197272 99164 197272 98517 197272 98517 197273 99164 197273 98519 197273 98517 197274 98519 197274 98518 197274 98518 197275 98519 197275 99167 197275 98518 197276 99167 197276 98520 197276 98520 197277 99167 197277 99168 197277 98520 197278 99168 197278 98521 197278 98521 197279 99168 197279 99170 197279 98521 197280 99170 197280 103685 197280 103685 197281 99170 197281 99171 197281 103685 197282 99171 197282 103686 197282 103686 197283 99171 197283 99172 197283 103686 197284 99172 197284 98522 197284 98522 197285 99172 197285 102139 197285 103661 197286 103660 197286 103978 197286 103978 197287 103660 197287 98602 197287 103978 197288 98602 197288 103979 197288 103979 197289 98602 197289 98604 197289 103979 197290 98604 197290 98523 197290 98523 197291 98604 197291 98524 197291 98524 197292 98604 197292 98605 197292 98524 197293 98605 197293 98525 197293 98525 197294 98605 197294 98526 197294 98525 197295 98526 197295 103976 197295 103976 197296 98526 197296 103973 197296 103973 197297 98526 197297 98606 197297 103973 197298 98606 197298 103972 197298 103972 197299 98606 197299 98608 197299 103972 197300 98608 197300 98527 197300 98527 197301 98608 197301 98528 197301 98527 197302 98528 197302 98529 197302 98529 197303 98528 197303 98530 197303 98530 197304 98528 197304 98609 197304 98530 197305 98609 197305 103971 197305 103971 197306 98609 197306 98611 197306 103971 197307 98611 197307 98531 197307 98531 197308 98611 197308 98532 197308 98532 197309 98611 197309 98612 197309 98532 197310 98612 197310 98533 197310 98533 197311 98612 197311 98534 197311 98533 197312 98534 197312 103970 197312 103970 197313 98534 197313 98535 197313 98535 197314 98534 197314 98536 197314 98535 197315 98536 197315 98537 197315 98537 197316 98536 197316 98616 197316 98537 197317 98616 197317 103967 197317 103967 197318 98616 197318 98538 197318 98538 197319 98616 197319 98618 197319 98538 197320 98618 197320 98539 197320 98539 197321 98618 197321 98619 197321 98539 197322 98619 197322 103965 197322 103965 197323 98619 197323 98540 197323 98540 197324 98619 197324 98620 197324 98540 197325 98620 197325 98541 197325 98541 197326 98620 197326 98622 197326 98541 197327 98622 197327 98542 197327 98542 197328 98622 197328 103964 197328 103964 197329 98622 197329 98543 197329 103964 197330 98543 197330 98545 197330 98545 197331 98543 197331 98544 197331 98545 197332 98544 197332 98546 197332 98546 197333 98544 197333 98547 197333 98546 197334 98547 197334 98549 197334 98549 197335 98547 197335 98548 197335 98549 197336 98548 197336 103963 197336 103963 197337 98548 197337 103961 197337 103961 197338 98548 197338 98550 197338 103961 197339 98550 197339 103957 197339 103957 197340 98550 197340 98551 197340 103957 197341 98551 197341 103959 197341 103959 197342 98551 197342 98552 197342 98552 197343 98551 197343 98553 197343 98552 197344 98553 197344 98554 197344 98554 197345 98553 197345 98555 197345 98554 197346 98555 197346 103960 197346 103960 197347 98555 197347 98556 197347 103960 197348 98556 197348 103955 197348 103955 197349 98556 197349 98557 197349 98557 197350 98556 197350 98626 197350 98557 197351 98626 197351 103954 197351 103954 197352 98626 197352 98558 197352 103954 197353 98558 197353 98559 197353 98559 197354 98558 197354 98560 197354 98560 197355 98558 197355 98562 197355 98560 197356 98562 197356 98561 197356 98561 197357 98562 197357 98563 197357 98561 197358 98563 197358 103950 197358 103950 197359 98563 197359 98564 197359 98564 197360 98563 197360 98565 197360 98564 197361 98565 197361 103951 197361 103951 197362 98565 197362 98566 197362 103951 197363 98566 197363 103949 197363 103949 197364 98566 197364 98567 197364 98567 197365 98566 197365 98569 197365 98567 197366 98569 197366 98568 197366 98568 197367 98569 197367 98570 197367 98568 197368 98570 197368 103946 197368 98601 197369 98254 197369 98603 197369 98603 197370 98254 197370 104184 197370 98603 197371 104184 197371 98571 197371 98571 197372 104184 197372 104177 197372 98571 197373 104177 197373 98572 197373 98572 197374 104177 197374 98573 197374 98572 197375 98573 197375 98574 197375 98574 197376 98573 197376 104190 197376 98574 197377 104190 197377 98607 197377 98607 197378 104190 197378 98575 197378 98607 197379 98575 197379 98576 197379 98576 197380 98575 197380 104194 197380 98576 197381 104194 197381 98610 197381 98610 197382 104194 197382 104195 197382 98610 197383 104195 197383 98577 197383 98577 197384 104195 197384 98579 197384 98577 197385 98579 197385 98578 197385 98578 197386 98579 197386 104168 197386 98578 197387 104168 197387 98613 197387 98613 197388 104168 197388 104198 197388 98613 197389 104198 197389 98614 197389 98614 197390 104198 197390 104200 197390 98614 197391 104200 197391 98615 197391 98615 197392 104200 197392 104201 197392 98615 197393 104201 197393 98617 197393 98617 197394 104201 197394 104202 197394 98617 197395 104202 197395 98580 197395 98580 197396 104202 197396 104152 197396 98580 197397 104152 197397 98581 197397 98581 197398 104152 197398 98582 197398 98581 197399 98582 197399 98583 197399 98583 197400 98582 197400 104156 197400 98583 197401 104156 197401 98621 197401 98621 197402 104156 197402 98584 197402 98621 197403 98584 197403 98623 197403 98623 197404 98584 197404 98586 197404 98623 197405 98586 197405 98585 197405 98585 197406 98586 197406 104205 197406 98585 197407 104205 197407 98624 197407 98624 197408 104205 197408 98587 197408 98624 197409 98587 197409 98588 197409 98588 197410 98587 197410 98590 197410 98588 197411 98590 197411 98589 197411 98589 197412 98590 197412 104125 197412 98589 197413 104125 197413 98591 197413 98591 197414 104125 197414 98592 197414 98591 197415 98592 197415 98625 197415 98625 197416 98592 197416 104126 197416 98625 197417 104126 197417 98593 197417 98593 197418 104126 197418 104207 197418 98593 197419 104207 197419 98594 197419 98594 197420 104207 197420 104208 197420 98594 197421 104208 197421 98627 197421 98627 197422 104208 197422 98595 197422 98627 197423 98595 197423 98628 197423 98628 197424 98595 197424 104123 197424 98628 197425 104123 197425 98629 197425 98629 197426 104123 197426 104109 197426 98629 197427 104109 197427 98630 197427 98630 197428 104109 197428 104212 197428 98630 197429 104212 197429 98596 197429 98596 197430 104212 197430 104213 197430 98596 197431 104213 197431 98597 197431 98597 197432 104213 197432 104214 197432 98597 197433 104214 197433 98631 197433 98631 197434 104214 197434 98598 197434 98631 197435 98598 197435 98632 197435 98632 197436 98598 197436 104094 197436 98632 197437 104094 197437 98633 197437 98633 197438 104094 197438 98599 197438 98633 197439 98599 197439 98600 197439 98600 197440 98599 197440 98636 197440 103660 197441 98601 197441 98602 197441 98602 197442 98601 197442 98603 197442 98602 197443 98603 197443 98604 197443 98604 197444 98603 197444 98571 197444 98604 197445 98571 197445 98605 197445 98605 197446 98571 197446 98572 197446 98605 197447 98572 197447 98526 197447 98526 197448 98572 197448 98574 197448 98526 197449 98574 197449 98606 197449 98606 197450 98574 197450 98607 197450 98606 197451 98607 197451 98608 197451 98608 197452 98607 197452 98576 197452 98608 197453 98576 197453 98528 197453 98528 197454 98576 197454 98610 197454 98528 197455 98610 197455 98609 197455 98609 197456 98610 197456 98577 197456 98609 197457 98577 197457 98611 197457 98611 197458 98577 197458 98578 197458 98611 197459 98578 197459 98612 197459 98612 197460 98578 197460 98613 197460 98612 197461 98613 197461 98534 197461 98534 197462 98613 197462 98614 197462 98534 197463 98614 197463 98536 197463 98536 197464 98614 197464 98615 197464 98536 197465 98615 197465 98616 197465 98616 197466 98615 197466 98617 197466 98616 197467 98617 197467 98618 197467 98618 197468 98617 197468 98580 197468 98618 197469 98580 197469 98619 197469 98619 197470 98580 197470 98581 197470 98619 197471 98581 197471 98620 197471 98620 197472 98581 197472 98583 197472 98620 197473 98583 197473 98622 197473 98622 197474 98583 197474 98621 197474 98622 197475 98621 197475 98543 197475 98543 197476 98621 197476 98623 197476 98543 197477 98623 197477 98544 197477 98544 197478 98623 197478 98585 197478 98544 197479 98585 197479 98547 197479 98547 197480 98585 197480 98624 197480 98547 197481 98624 197481 98548 197481 98548 197482 98624 197482 98588 197482 98548 197483 98588 197483 98550 197483 98550 197484 98588 197484 98589 197484 98550 197485 98589 197485 98551 197485 98551 197486 98589 197486 98591 197486 98551 197487 98591 197487 98553 197487 98553 197488 98591 197488 98625 197488 98553 197489 98625 197489 98555 197489 98555 197490 98625 197490 98593 197490 98555 197491 98593 197491 98556 197491 98556 197492 98593 197492 98594 197492 98556 197493 98594 197493 98626 197493 98626 197494 98594 197494 98627 197494 98626 197495 98627 197495 98558 197495 98558 197496 98627 197496 98628 197496 98558 197497 98628 197497 98562 197497 98562 197498 98628 197498 98629 197498 98562 197499 98629 197499 98563 197499 98563 197500 98629 197500 98630 197500 98563 197501 98630 197501 98565 197501 98565 197502 98630 197502 98596 197502 98565 197503 98596 197503 98566 197503 98566 197504 98596 197504 98597 197504 98566 197505 98597 197505 98569 197505 98569 197506 98597 197506 98631 197506 98569 197507 98631 197507 98570 197507 98570 197508 98631 197508 98632 197508 98570 197509 98632 197509 98635 197509 98635 197510 98632 197510 98633 197510 98635 197511 98633 197511 98639 197511 98639 197512 98633 197512 98600 197512 103946 197513 98570 197513 98634 197513 98634 197514 98570 197514 98635 197514 98634 197515 98635 197515 103948 197515 103948 197516 98635 197516 98639 197516 103948 197517 98639 197517 98640 197517 98636 197518 104087 197518 98637 197518 98636 197519 98637 197519 98600 197519 98600 197520 98637 197520 98638 197520 98600 197521 98638 197521 98639 197521 98639 197522 98638 197522 103945 197522 98639 197523 103945 197523 98640 197523 104087 197524 103583 197524 103582 197524 104087 197525 103582 197525 98637 197525 98637 197526 103582 197526 98641 197526 98637 197527 98641 197527 98638 197527 98638 197528 98641 197528 98642 197528 98638 197529 98642 197529 103945 197529 103503 197530 103294 197530 98677 197530 98677 197531 103294 197531 98643 197531 98677 197532 98643 197532 98678 197532 98678 197533 98643 197533 98832 197533 98678 197534 98832 197534 98679 197534 98679 197535 98832 197535 98831 197535 98679 197536 98831 197536 98680 197536 98680 197537 98831 197537 98828 197537 98680 197538 98828 197538 98681 197538 98681 197539 98828 197539 98644 197539 98681 197540 98644 197540 98682 197540 98682 197541 98644 197541 98645 197541 98682 197542 98645 197542 98683 197542 98683 197543 98645 197543 98646 197543 98683 197544 98646 197544 98684 197544 98684 197545 98646 197545 98647 197545 98684 197546 98647 197546 98685 197546 98685 197547 98647 197547 98648 197547 98685 197548 98648 197548 98649 197548 98649 197549 98648 197549 98826 197549 98649 197550 98826 197550 98686 197550 98686 197551 98826 197551 98650 197551 98686 197552 98650 197552 98651 197552 98651 197553 98650 197553 98823 197553 98651 197554 98823 197554 98652 197554 98652 197555 98823 197555 98820 197555 98652 197556 98820 197556 98690 197556 98690 197557 98820 197557 98819 197557 98690 197558 98819 197558 98653 197558 98653 197559 98819 197559 98818 197559 98653 197560 98818 197560 98691 197560 98691 197561 98818 197561 98816 197561 98691 197562 98816 197562 98654 197562 98654 197563 98816 197563 98814 197563 98654 197564 98814 197564 98655 197564 98655 197565 98814 197565 98656 197565 98655 197566 98656 197566 98693 197566 98693 197567 98656 197567 98812 197567 98693 197568 98812 197568 98694 197568 98694 197569 98812 197569 98810 197569 98694 197570 98810 197570 98695 197570 98695 197571 98810 197571 98658 197571 98695 197572 98658 197572 98657 197572 98657 197573 98658 197573 98808 197573 98657 197574 98808 197574 98659 197574 98659 197575 98808 197575 98660 197575 98659 197576 98660 197576 98697 197576 98697 197577 98660 197577 98661 197577 98697 197578 98661 197578 98698 197578 98698 197579 98661 197579 98662 197579 98698 197580 98662 197580 98700 197580 98700 197581 98662 197581 98664 197581 98700 197582 98664 197582 98663 197582 98663 197583 98664 197583 98805 197583 98663 197584 98805 197584 98665 197584 98665 197585 98805 197585 98666 197585 98665 197586 98666 197586 98703 197586 98703 197587 98666 197587 98667 197587 98703 197588 98667 197588 98704 197588 98704 197589 98667 197589 98803 197589 98704 197590 98803 197590 98668 197590 98668 197591 98803 197591 98670 197591 98668 197592 98670 197592 98669 197592 98669 197593 98670 197593 98798 197593 98669 197594 98798 197594 98706 197594 98706 197595 98798 197595 98671 197595 98706 197596 98671 197596 98707 197596 98707 197597 98671 197597 98797 197597 98707 197598 98797 197598 98710 197598 98710 197599 98797 197599 98795 197599 98710 197600 98795 197600 98672 197600 98672 197601 98795 197601 98673 197601 103401 197602 98674 197602 98711 197602 98749 197603 103304 197603 98748 197603 98675 197604 103345 197604 98676 197604 103346 197605 103503 197605 98677 197605 103345 197606 103346 197606 98676 197606 98676 197607 103346 197607 98677 197607 98676 197608 98677 197608 98746 197608 98746 197609 98677 197609 98678 197609 98746 197610 98678 197610 98745 197610 98745 197611 98678 197611 98679 197611 98745 197612 98679 197612 98744 197612 98744 197613 98679 197613 98680 197613 98744 197614 98680 197614 98743 197614 98743 197615 98680 197615 98681 197615 98743 197616 98681 197616 98741 197616 98741 197617 98681 197617 98682 197617 98741 197618 98682 197618 98740 197618 98740 197619 98682 197619 98683 197619 98740 197620 98683 197620 98738 197620 98738 197621 98683 197621 98684 197621 98738 197622 98684 197622 98737 197622 98737 197623 98684 197623 98685 197623 98737 197624 98685 197624 98735 197624 98735 197625 98685 197625 98649 197625 98735 197626 98649 197626 98687 197626 98687 197627 98649 197627 98686 197627 98687 197628 98686 197628 98688 197628 98688 197629 98686 197629 98651 197629 98688 197630 98651 197630 98689 197630 98689 197631 98651 197631 98652 197631 98689 197632 98652 197632 98732 197632 98732 197633 98652 197633 98690 197633 98732 197634 98690 197634 98731 197634 98731 197635 98690 197635 98653 197635 98731 197636 98653 197636 98730 197636 98730 197637 98653 197637 98691 197637 98730 197638 98691 197638 98729 197638 98729 197639 98691 197639 98654 197639 98729 197640 98654 197640 98692 197640 98692 197641 98654 197641 98655 197641 98692 197642 98655 197642 98728 197642 98728 197643 98655 197643 98693 197643 98728 197644 98693 197644 98727 197644 98727 197645 98693 197645 98694 197645 98727 197646 98694 197646 98726 197646 98726 197647 98694 197647 98695 197647 98726 197648 98695 197648 98696 197648 98696 197649 98695 197649 98657 197649 98696 197650 98657 197650 98724 197650 98724 197651 98657 197651 98659 197651 98724 197652 98659 197652 98722 197652 98722 197653 98659 197653 98697 197653 98722 197654 98697 197654 98721 197654 98721 197655 98697 197655 98698 197655 98721 197656 98698 197656 98699 197656 98699 197657 98698 197657 98700 197657 98699 197658 98700 197658 98720 197658 98720 197659 98700 197659 98663 197659 98720 197660 98663 197660 98701 197660 98701 197661 98663 197661 98665 197661 98701 197662 98665 197662 98702 197662 98702 197663 98665 197663 98703 197663 98702 197664 98703 197664 98717 197664 98717 197665 98703 197665 98704 197665 98717 197666 98704 197666 98716 197666 98716 197667 98704 197667 98668 197667 98716 197668 98668 197668 98705 197668 98705 197669 98668 197669 98669 197669 98705 197670 98669 197670 98713 197670 98713 197671 98669 197671 98706 197671 98713 197672 98706 197672 98712 197672 98712 197673 98706 197673 98707 197673 98712 197674 98707 197674 98708 197674 98708 197675 98707 197675 98710 197675 98708 197676 98710 197676 98709 197676 98709 197677 98710 197677 98672 197677 98709 197678 103401 197678 98708 197678 98708 197679 103401 197679 98711 197679 98708 197680 98711 197680 98712 197680 98712 197681 98711 197681 98788 197681 98712 197682 98788 197682 98713 197682 98713 197683 98788 197683 98714 197683 98713 197684 98714 197684 98705 197684 98705 197685 98714 197685 98715 197685 98705 197686 98715 197686 98716 197686 98716 197687 98715 197687 98784 197687 98716 197688 98784 197688 98717 197688 98717 197689 98784 197689 98783 197689 98717 197690 98783 197690 98702 197690 98702 197691 98783 197691 98718 197691 98702 197692 98718 197692 98701 197692 98701 197693 98718 197693 98719 197693 98701 197694 98719 197694 98720 197694 98720 197695 98719 197695 98781 197695 98720 197696 98781 197696 98699 197696 98699 197697 98781 197697 98779 197697 98699 197698 98779 197698 98721 197698 98721 197699 98779 197699 98778 197699 98721 197700 98778 197700 98722 197700 98722 197701 98778 197701 98777 197701 98722 197702 98777 197702 98724 197702 98724 197703 98777 197703 98723 197703 98724 197704 98723 197704 98696 197704 98696 197705 98723 197705 98725 197705 98696 197706 98725 197706 98726 197706 98726 197707 98725 197707 98774 197707 98726 197708 98774 197708 98727 197708 98727 197709 98774 197709 98771 197709 98727 197710 98771 197710 98728 197710 98728 197711 98771 197711 98770 197711 98728 197712 98770 197712 98692 197712 98692 197713 98770 197713 98768 197713 98692 197714 98768 197714 98729 197714 98729 197715 98768 197715 98767 197715 98729 197716 98767 197716 98730 197716 98730 197717 98767 197717 98766 197717 98730 197718 98766 197718 98731 197718 98731 197719 98766 197719 98764 197719 98731 197720 98764 197720 98732 197720 98732 197721 98764 197721 98733 197721 98732 197722 98733 197722 98689 197722 98689 197723 98733 197723 98763 197723 98689 197724 98763 197724 98688 197724 98688 197725 98763 197725 98734 197725 98688 197726 98734 197726 98687 197726 98687 197727 98734 197727 98761 197727 98687 197728 98761 197728 98735 197728 98735 197729 98761 197729 98736 197729 98735 197730 98736 197730 98737 197730 98737 197731 98736 197731 98739 197731 98737 197732 98739 197732 98738 197732 98738 197733 98739 197733 98759 197733 98738 197734 98759 197734 98740 197734 98740 197735 98759 197735 98757 197735 98740 197736 98757 197736 98741 197736 98741 197737 98757 197737 98742 197737 98741 197738 98742 197738 98743 197738 98743 197739 98742 197739 98756 197739 98743 197740 98756 197740 98744 197740 98744 197741 98756 197741 98755 197741 98744 197742 98755 197742 98745 197742 98745 197743 98755 197743 98754 197743 98745 197744 98754 197744 98746 197744 98746 197745 98754 197745 98747 197745 98746 197746 98747 197746 98676 197746 98676 197747 98747 197747 98748 197747 98676 197748 98748 197748 98675 197748 98675 197749 98748 197749 103304 197749 103429 197750 98749 197750 98750 197750 98750 197751 98749 197751 98748 197751 98750 197752 98748 197752 98751 197752 98751 197753 98748 197753 98747 197753 98751 197754 98747 197754 98752 197754 98752 197755 98747 197755 98754 197755 98752 197756 98754 197756 98753 197756 98753 197757 98754 197757 98755 197757 98753 197758 98755 197758 103444 197758 103444 197759 98755 197759 98756 197759 103444 197760 98756 197760 103445 197760 103445 197761 98756 197761 98742 197761 103445 197762 98742 197762 103442 197762 103442 197763 98742 197763 98757 197763 103442 197764 98757 197764 98758 197764 98758 197765 98757 197765 98759 197765 98758 197766 98759 197766 103450 197766 103450 197767 98759 197767 98739 197767 103450 197768 98739 197768 98760 197768 98760 197769 98739 197769 98736 197769 98760 197770 98736 197770 103438 197770 103438 197771 98736 197771 98761 197771 103438 197772 98761 197772 98762 197772 98762 197773 98761 197773 98734 197773 98762 197774 98734 197774 103440 197774 103440 197775 98734 197775 98763 197775 103440 197776 98763 197776 103441 197776 103441 197777 98763 197777 98733 197777 103441 197778 98733 197778 98765 197778 98765 197779 98733 197779 98764 197779 98765 197780 98764 197780 103425 197780 103425 197781 98764 197781 98766 197781 103425 197782 98766 197782 103427 197782 103427 197783 98766 197783 98767 197783 103427 197784 98767 197784 103428 197784 103428 197785 98767 197785 98768 197785 103428 197786 98768 197786 98769 197786 98769 197787 98768 197787 98770 197787 98769 197788 98770 197788 103424 197788 103424 197789 98770 197789 98771 197789 103424 197790 98771 197790 98772 197790 98772 197791 98771 197791 98774 197791 98772 197792 98774 197792 98773 197792 98773 197793 98774 197793 98725 197793 98773 197794 98725 197794 103448 197794 103448 197795 98725 197795 98723 197795 103448 197796 98723 197796 98775 197796 98775 197797 98723 197797 98777 197797 98775 197798 98777 197798 98776 197798 98776 197799 98777 197799 98778 197799 98776 197800 98778 197800 98780 197800 98780 197801 98778 197801 98779 197801 98780 197802 98779 197802 103454 197802 103454 197803 98779 197803 98781 197803 103454 197804 98781 197804 103455 197804 103455 197805 98781 197805 98719 197805 103455 197806 98719 197806 103435 197806 103435 197807 98719 197807 98718 197807 103435 197808 98718 197808 98782 197808 98782 197809 98718 197809 98783 197809 98782 197810 98783 197810 103436 197810 103436 197811 98783 197811 98784 197811 103436 197812 98784 197812 103437 197812 103437 197813 98784 197813 98715 197813 103437 197814 98715 197814 98785 197814 98785 197815 98715 197815 98714 197815 98785 197816 98714 197816 98786 197816 98786 197817 98714 197817 98788 197817 98786 197818 98788 197818 98787 197818 98787 197819 98788 197819 98711 197819 98787 197820 98711 197820 103412 197820 103412 197821 98711 197821 98674 197821 98789 197822 103293 197822 98790 197822 98791 197823 98864 197823 98866 197823 98792 197824 98793 197824 98794 197824 103230 197825 98673 197825 98795 197825 98793 197826 103230 197826 98794 197826 98794 197827 103230 197827 98795 197827 98794 197828 98795 197828 98863 197828 98863 197829 98795 197829 98797 197829 98863 197830 98797 197830 98796 197830 98796 197831 98797 197831 98671 197831 98796 197832 98671 197832 98799 197832 98799 197833 98671 197833 98798 197833 98799 197834 98798 197834 98800 197834 98800 197835 98798 197835 98670 197835 98800 197836 98670 197836 98801 197836 98801 197837 98670 197837 98803 197837 98801 197838 98803 197838 98802 197838 98802 197839 98803 197839 98667 197839 98802 197840 98667 197840 98804 197840 98804 197841 98667 197841 98666 197841 98804 197842 98666 197842 98860 197842 98860 197843 98666 197843 98805 197843 98860 197844 98805 197844 98858 197844 98858 197845 98805 197845 98664 197845 98858 197846 98664 197846 98855 197846 98855 197847 98664 197847 98662 197847 98855 197848 98662 197848 98854 197848 98854 197849 98662 197849 98661 197849 98854 197850 98661 197850 98806 197850 98806 197851 98661 197851 98660 197851 98806 197852 98660 197852 98807 197852 98807 197853 98660 197853 98808 197853 98807 197854 98808 197854 98852 197854 98852 197855 98808 197855 98658 197855 98852 197856 98658 197856 98809 197856 98809 197857 98658 197857 98810 197857 98809 197858 98810 197858 98811 197858 98811 197859 98810 197859 98812 197859 98811 197860 98812 197860 98813 197860 98813 197861 98812 197861 98656 197861 98813 197862 98656 197862 98849 197862 98849 197863 98656 197863 98814 197863 98849 197864 98814 197864 98815 197864 98815 197865 98814 197865 98816 197865 98815 197866 98816 197866 98847 197866 98847 197867 98816 197867 98818 197867 98847 197868 98818 197868 98817 197868 98817 197869 98818 197869 98819 197869 98817 197870 98819 197870 98846 197870 98846 197871 98819 197871 98820 197871 98846 197872 98820 197872 98821 197872 98821 197873 98820 197873 98823 197873 98821 197874 98823 197874 98822 197874 98822 197875 98823 197875 98650 197875 98822 197876 98650 197876 98824 197876 98824 197877 98650 197877 98826 197877 98824 197878 98826 197878 98825 197878 98825 197879 98826 197879 98648 197879 98825 197880 98648 197880 98842 197880 98842 197881 98648 197881 98647 197881 98842 197882 98647 197882 98840 197882 98840 197883 98647 197883 98646 197883 98840 197884 98646 197884 98839 197884 98839 197885 98646 197885 98645 197885 98839 197886 98645 197886 98837 197886 98837 197887 98645 197887 98644 197887 98837 197888 98644 197888 98827 197888 98827 197889 98644 197889 98828 197889 98827 197890 98828 197890 98829 197890 98829 197891 98828 197891 98831 197891 98829 197892 98831 197892 98830 197892 98830 197893 98831 197893 98832 197893 98830 197894 98832 197894 98834 197894 98834 197895 98832 197895 98643 197895 98834 197896 98643 197896 98833 197896 98833 197897 98643 197897 103294 197897 98833 197898 98789 197898 98834 197898 98834 197899 98789 197899 98790 197899 98834 197900 98790 197900 98830 197900 98830 197901 98790 197901 98835 197901 98830 197902 98835 197902 98829 197902 98829 197903 98835 197903 98836 197903 98829 197904 98836 197904 98827 197904 98827 197905 98836 197905 98838 197905 98827 197906 98838 197906 98837 197906 98837 197907 98838 197907 98896 197907 98837 197908 98896 197908 98839 197908 98839 197909 98896 197909 98895 197909 98839 197910 98895 197910 98840 197910 98840 197911 98895 197911 98841 197911 98840 197912 98841 197912 98842 197912 98842 197913 98841 197913 98843 197913 98842 197914 98843 197914 98825 197914 98825 197915 98843 197915 98892 197915 98825 197916 98892 197916 98824 197916 98824 197917 98892 197917 98889 197917 98824 197918 98889 197918 98822 197918 98822 197919 98889 197919 98888 197919 98822 197920 98888 197920 98821 197920 98821 197921 98888 197921 98844 197921 98821 197922 98844 197922 98846 197922 98846 197923 98844 197923 98845 197923 98846 197924 98845 197924 98817 197924 98817 197925 98845 197925 98885 197925 98817 197926 98885 197926 98847 197926 98847 197927 98885 197927 98884 197927 98847 197928 98884 197928 98815 197928 98815 197929 98884 197929 98848 197929 98815 197930 98848 197930 98849 197930 98849 197931 98848 197931 98882 197931 98849 197932 98882 197932 98813 197932 98813 197933 98882 197933 98850 197933 98813 197934 98850 197934 98811 197934 98811 197935 98850 197935 98879 197935 98811 197936 98879 197936 98809 197936 98809 197937 98879 197937 98877 197937 98809 197938 98877 197938 98852 197938 98852 197939 98877 197939 98851 197939 98852 197940 98851 197940 98807 197940 98807 197941 98851 197941 98853 197941 98807 197942 98853 197942 98806 197942 98806 197943 98853 197943 98876 197943 98806 197944 98876 197944 98854 197944 98854 197945 98876 197945 98856 197945 98854 197946 98856 197946 98855 197946 98855 197947 98856 197947 98857 197947 98855 197948 98857 197948 98858 197948 98858 197949 98857 197949 98859 197949 98858 197950 98859 197950 98860 197950 98860 197951 98859 197951 98874 197951 98860 197952 98874 197952 98804 197952 98804 197953 98874 197953 98873 197953 98804 197954 98873 197954 98802 197954 98802 197955 98873 197955 98861 197955 98802 197956 98861 197956 98801 197956 98801 197957 98861 197957 98871 197957 98801 197958 98871 197958 98800 197958 98800 197959 98871 197959 98862 197959 98800 197960 98862 197960 98799 197960 98799 197961 98862 197961 98870 197961 98799 197962 98870 197962 98796 197962 98796 197963 98870 197963 98868 197963 98796 197964 98868 197964 98863 197964 98863 197965 98868 197965 98867 197965 98863 197966 98867 197966 98794 197966 98794 197967 98867 197967 98866 197967 98794 197968 98866 197968 98792 197968 98792 197969 98866 197969 98864 197969 103189 197970 98791 197970 98865 197970 98865 197971 98791 197971 98866 197971 98865 197972 98866 197972 103484 197972 103484 197973 98866 197973 98867 197973 103484 197974 98867 197974 103485 197974 103485 197975 98867 197975 98868 197975 103485 197976 98868 197976 98869 197976 98869 197977 98868 197977 98870 197977 98869 197978 98870 197978 103473 197978 103473 197979 98870 197979 98862 197979 103473 197980 98862 197980 103475 197980 103475 197981 98862 197981 98871 197981 103475 197982 98871 197982 103476 197982 103476 197983 98871 197983 98861 197983 103476 197984 98861 197984 98872 197984 98872 197985 98861 197985 98873 197985 98872 197986 98873 197986 103480 197986 103480 197987 98873 197987 98874 197987 103480 197988 98874 197988 103482 197988 103482 197989 98874 197989 98859 197989 103482 197990 98859 197990 98875 197990 98875 197991 98859 197991 98857 197991 98875 197992 98857 197992 103465 197992 103465 197993 98857 197993 98856 197993 103465 197994 98856 197994 103463 197994 103463 197995 98856 197995 98876 197995 103463 197996 98876 197996 103477 197996 103477 197997 98876 197997 98853 197997 103477 197998 98853 197998 103478 197998 103478 197999 98853 197999 98851 197999 103478 198000 98851 198000 103479 198000 103479 198001 98851 198001 98877 198001 103479 198002 98877 198002 98878 198002 98878 198003 98877 198003 98879 198003 98878 198004 98879 198004 103471 198004 103471 198005 98879 198005 98850 198005 103471 198006 98850 198006 98880 198006 98880 198007 98850 198007 98882 198007 98880 198008 98882 198008 98881 198008 98881 198009 98882 198009 98848 198009 98881 198010 98848 198010 103490 198010 103490 198011 98848 198011 98884 198011 103490 198012 98884 198012 98883 198012 98883 198013 98884 198013 98885 198013 98883 198014 98885 198014 98886 198014 98886 198015 98885 198015 98845 198015 98886 198016 98845 198016 98887 198016 98887 198017 98845 198017 98844 198017 98887 198018 98844 198018 103500 198018 103500 198019 98844 198019 98888 198019 103500 198020 98888 198020 103502 198020 103502 198021 98888 198021 98889 198021 103502 198022 98889 198022 98890 198022 98890 198023 98889 198023 98892 198023 98890 198024 98892 198024 98891 198024 98891 198025 98892 198025 98843 198025 98891 198026 98843 198026 98893 198026 98893 198027 98843 198027 98841 198027 98893 198028 98841 198028 103492 198028 103492 198029 98841 198029 98895 198029 103492 198030 98895 198030 98894 198030 98894 198031 98895 198031 98896 198031 98894 198032 98896 198032 98897 198032 98897 198033 98896 198033 98838 198033 98897 198034 98838 198034 98898 198034 98898 198035 98838 198035 98836 198035 98898 198036 98836 198036 103468 198036 103468 198037 98836 198037 98835 198037 103468 198038 98835 198038 98899 198038 98899 198039 98835 198039 98790 198039 98899 198040 98790 198040 103456 198040 103456 198041 98790 198041 103293 198041 98407 198042 103404 198042 98406 198042 98406 198043 103404 198043 103430 198043 98406 198044 103430 198044 98900 198044 98900 198045 103430 198045 103443 198045 98900 198046 103443 198046 98902 198046 98902 198047 103443 198047 98901 198047 98902 198048 98901 198048 98903 198048 98903 198049 98901 198049 103451 198049 98903 198050 103451 198050 98904 198050 98904 198051 103451 198051 103452 198051 98904 198052 103452 198052 98403 198052 98403 198053 103452 198053 103439 198053 98403 198054 103439 198054 98402 198054 98402 198055 103439 198055 103416 198055 98402 198056 103416 198056 98905 198056 98905 198057 103416 198057 103426 198057 98905 198058 103426 198058 98400 198058 98400 198059 103426 198059 103423 198059 98400 198060 103423 198060 98906 198060 98906 198061 103423 198061 98907 198061 98906 198062 98907 198062 98908 198062 98908 198063 98907 198063 103449 198063 98908 198064 103449 198064 98909 198064 98909 198065 103449 198065 103453 198065 98909 198066 103453 198066 98396 198066 98396 198067 103453 198067 98910 198067 98396 198068 98910 198068 98912 198068 98912 198069 98910 198069 98911 198069 98912 198070 98911 198070 98395 198070 98395 198071 98911 198071 98914 198071 98395 198072 98914 198072 98913 198072 98913 198073 98914 198073 98915 198073 98913 198074 98915 198074 103170 198074 103170 198075 98915 198075 103405 198075 104037 198076 103483 198076 98375 198076 98375 198077 103483 198077 98917 198077 98375 198078 98917 198078 98916 198078 98916 198079 98917 198079 103472 198079 98916 198080 103472 198080 98377 198080 98377 198081 103472 198081 103474 198081 98377 198082 103474 198082 98378 198082 98378 198083 103474 198083 98918 198083 98378 198084 98918 198084 98379 198084 98379 198085 98918 198085 103481 198085 98379 198086 103481 198086 98381 198086 98381 198087 103481 198087 103459 198087 98381 198088 103459 198088 98382 198088 98382 198089 103459 198089 103464 198089 98382 198090 103464 198090 98383 198090 98383 198091 103464 198091 98919 198091 98383 198092 98919 198092 98920 198092 98920 198093 98919 198093 103470 198093 98920 198094 103470 198094 98921 198094 98921 198095 103470 198095 103491 198095 98921 198096 103491 198096 98386 198096 98386 198097 103491 198097 98922 198097 98386 198098 98922 198098 98387 198098 98387 198099 98922 198099 103501 198099 98387 198100 103501 198100 98388 198100 98388 198101 103501 198101 98923 198101 98388 198102 98923 198102 98389 198102 98389 198103 98923 198103 98924 198103 98389 198104 98924 198104 98925 198104 98925 198105 98924 198105 103493 198105 98925 198106 103493 198106 98926 198106 98926 198107 103493 198107 103469 198107 98926 198108 103469 198108 104017 198108 104017 198109 103469 198109 103458 198109 103147 198110 103123 198110 98927 198110 98927 198111 103123 198111 102594 198111 101215 198112 103121 198112 98928 198112 98928 198113 103121 198113 103146 198113 98928 198114 103146 198114 98929 198114 98929 198115 103146 198115 98931 198115 98929 198116 98931 198116 98930 198116 98930 198117 98931 198117 98932 198117 98930 198118 98932 198118 98933 198118 98933 198119 98932 198119 98934 198119 98933 198120 98934 198120 98935 198120 98935 198121 98934 198121 103144 198121 98935 198122 103144 198122 101223 198122 101223 198123 103144 198123 103143 198123 98936 198124 103150 198124 103122 198124 103122 198125 103150 198125 102591 198125 102353 198126 102990 198126 102352 198126 102352 198127 102990 198127 98937 198127 98940 198128 102341 198128 98937 198128 98937 198129 102341 198129 102350 198129 98937 198130 102350 198130 102352 198130 102344 198131 98939 198131 98938 198131 98938 198132 98939 198132 102347 198132 98938 198133 102347 198133 98940 198133 98940 198134 102347 198134 98941 198134 98940 198135 98941 198135 102341 198135 102344 198136 98938 198136 102343 198136 102343 198137 98938 198137 98942 198137 102343 198138 98942 198138 102337 198138 102337 198139 98942 198139 102339 198139 102339 198140 98942 198140 102983 198140 102339 198141 102983 198141 98943 198141 98943 198142 102983 198142 98944 198142 98944 198143 102983 198143 102977 198143 98944 198144 102977 198144 98945 198144 102408 198145 102974 198145 102407 198145 102407 198146 102974 198146 102973 198146 102407 198147 102973 198147 98950 198147 98946 198148 98947 198148 98951 198148 98951 198149 98947 198149 98948 198149 98951 198150 98948 198150 102973 198150 102973 198151 98948 198151 98949 198151 102973 198152 98949 198152 98950 198152 98946 198153 98951 198153 102405 198153 102405 198154 98951 198154 98952 198154 102405 198155 98952 198155 98953 198155 98953 198156 98952 198156 102403 198156 102403 198157 98952 198157 102970 198157 102403 198158 102970 198158 98954 198158 98954 198159 102970 198159 98955 198159 98955 198160 102970 198160 102969 198160 98955 198161 102969 198161 102402 198161 102466 198162 98956 198162 102940 198162 102466 198163 102940 198163 98957 198163 98957 198164 102940 198164 102952 198164 98957 198165 102952 198165 98958 198165 98958 198166 102952 198166 102469 198166 102469 198167 102952 198167 102949 198167 102469 198168 102949 198168 102470 198168 102470 198169 102949 198169 102471 198169 102471 198170 102949 198170 102948 198170 102471 198171 102948 198171 102462 198171 102462 198172 102948 198172 102946 198172 102462 198173 102946 198173 102463 198173 102529 198174 102927 198174 98959 198174 98959 198175 102927 198175 102934 198175 98959 198176 102934 198176 102531 198176 102531 198177 102934 198177 102533 198177 102533 198178 102934 198178 98961 198178 102533 198179 98961 198179 98960 198179 98960 198180 98961 198180 102931 198180 98960 198181 102931 198181 102917 198181 102599 198182 102914 198182 98962 198182 98962 198183 102914 198183 98963 198183 98962 198184 98963 198184 102596 198184 102596 198185 98963 198185 102900 198185 102596 198186 102900 198186 102595 198186 101227 198187 102899 198187 98964 198187 98964 198188 102899 198188 98965 198188 98964 198189 98965 198189 98966 198189 98966 198190 98965 198190 98967 198190 98966 198191 98967 198191 101225 198191 101225 198192 98967 198192 98968 198192 101225 198193 98968 198193 98969 198193 98969 198194 98968 198194 102896 198194 98969 198195 102896 198195 98970 198195 98970 198196 102896 198196 98971 198196 98970 198197 98971 198197 98972 198197 98972 198198 98971 198198 102889 198198 98973 198199 104040 198199 98974 198199 98974 198200 104040 198200 104041 198200 98974 198201 104041 198201 98975 198201 98975 198202 104041 198202 104043 198202 98975 198203 104043 198203 98976 198203 98976 198204 104043 198204 104044 198204 98976 198205 104044 198205 101248 198205 101248 198206 104044 198206 98977 198206 101248 198207 98977 198207 98978 198207 98978 198208 98977 198208 98979 198208 98978 198209 98979 198209 101244 198209 101244 198210 98979 198210 102866 198210 101256 198211 103076 198211 101254 198211 101254 198212 103076 198212 103075 198212 101254 198213 103075 198213 98980 198213 98980 198214 103075 198214 98981 198214 98980 198215 98981 198215 101251 198215 101251 198216 98981 198216 103078 198216 101251 198217 103078 198217 98982 198217 98982 198218 103078 198218 103079 198218 98982 198219 103079 198219 98983 198219 98983 198220 103079 198220 103082 198220 98983 198221 103082 198221 98984 198221 98984 198222 103082 198222 102860 198222 101267 198223 98986 198223 98985 198223 98985 198224 98986 198224 103048 198224 98985 198225 103048 198225 98987 198225 98987 198226 103048 198226 98988 198226 98987 198227 98988 198227 101275 198227 101275 198228 98988 198228 103052 198228 101275 198229 103052 198229 98989 198229 98989 198230 103052 198230 103053 198230 98989 198231 103053 198231 101273 198231 101273 198232 103053 198232 98990 198232 101273 198233 98990 198233 101271 198233 101271 198234 98990 198234 102852 198234 98991 198235 98992 198235 101284 198235 101284 198236 98992 198236 98993 198236 101284 198237 98993 198237 98994 198237 98994 198238 98993 198238 98996 198238 98994 198239 98996 198239 98995 198239 98995 198240 98996 198240 98997 198240 98995 198241 98997 198241 98998 198241 98998 198242 98997 198242 103039 198242 98998 198243 103039 198243 101287 198243 101287 198244 103039 198244 98999 198244 101287 198245 98999 198245 101277 198245 101277 198246 98999 198246 99000 198246 101297 198247 99001 198247 101296 198247 101296 198248 99001 198248 99002 198248 101296 198249 99002 198249 101295 198249 101295 198250 99002 198250 99003 198250 101295 198251 99003 198251 99004 198251 99004 198252 99003 198252 99005 198252 99004 198253 99005 198253 99006 198253 99006 198254 99005 198254 103014 198254 99006 198255 103014 198255 99007 198255 99007 198256 103014 198256 103015 198256 99007 198257 103015 198257 102843 198257 102843 198258 103015 198258 103003 198258 101304 198259 102989 198259 101303 198259 101303 198260 102989 198260 99008 198260 101303 198261 99008 198261 101302 198261 101302 198262 99008 198262 99009 198262 101302 198263 99009 198263 99010 198263 99010 198264 99009 198264 99011 198264 99010 198265 99011 198265 101312 198265 101312 198266 99011 198266 102988 198266 101312 198267 102988 198267 101309 198267 101309 198268 102988 198268 102986 198268 101309 198269 102986 198269 99012 198269 99012 198270 102986 198270 102984 198270 99013 198271 99014 198271 99015 198271 99015 198272 99014 198272 102975 198272 99015 198273 102975 198273 99016 198273 99016 198274 102975 198274 99017 198274 99016 198275 99017 198275 101320 198275 101320 198276 99017 198276 102967 198276 101320 198277 102967 198277 99018 198277 99018 198278 102967 198278 99019 198278 99018 198279 99019 198279 101318 198279 101318 198280 99019 198280 102966 198280 101318 198281 102966 198281 99020 198281 99020 198282 102966 198282 102831 198282 102830 198283 102951 198283 99021 198283 99021 198284 102951 198284 102953 198284 99021 198285 102953 198285 99022 198285 99022 198286 102953 198286 102954 198286 99022 198287 102954 198287 101324 198287 101324 198288 102954 198288 102956 198288 101324 198289 102956 198289 101331 198289 101331 198290 102956 198290 102941 198290 101331 198291 102941 198291 99024 198291 99024 198292 102941 198292 99023 198292 99024 198293 99023 198293 101330 198293 101330 198294 99023 198294 102826 198294 99025 198295 102933 198295 101336 198295 101336 198296 102933 198296 99026 198296 101336 198297 99026 198297 101335 198297 101335 198298 99026 198298 99027 198298 101335 198299 99027 198299 101334 198299 101334 198300 99027 198300 99028 198300 101334 198301 99028 198301 99029 198301 99029 198302 99028 198302 102936 198302 99029 198303 102936 198303 101345 198303 101345 198304 102936 198304 99030 198304 101345 198305 99030 198305 101344 198305 101344 198306 99030 198306 99031 198306 101350 198307 99033 198307 99032 198307 99032 198308 99033 198308 102915 198308 99032 198309 102915 198309 101347 198309 101347 198310 102915 198310 99034 198310 101347 198311 99034 198311 101346 198311 101346 198312 99034 198312 99035 198312 101346 198313 99035 198313 99036 198313 99036 198314 99035 198314 99037 198314 99036 198315 99037 198315 101354 198315 101354 198316 99037 198316 99038 198316 101354 198317 99038 198317 99039 198317 99039 198318 99038 198318 102813 198318 102659 198319 99040 198319 99041 198319 99041 198320 99040 198320 102330 198320 99041 198321 102330 198321 99042 198321 99042 198322 102330 198322 99043 198322 99042 198323 99043 198323 102661 198323 102329 198324 99044 198324 99045 198324 99045 198325 99044 198325 99046 198325 99045 198326 99046 198326 99047 198326 99047 198327 99046 198327 99048 198327 99047 198328 99048 198328 102659 198328 102659 198329 99048 198329 99049 198329 102659 198330 99049 198330 99040 198330 102976 198331 102391 198331 102656 198331 102656 198332 102391 198332 102393 198332 102656 198333 102393 198333 99050 198333 99050 198334 102393 198334 102658 198334 102658 198335 102393 198335 102394 198335 102658 198336 102394 198336 99051 198336 102651 198337 102653 198337 102454 198337 102454 198338 102653 198338 102453 198338 99052 198339 99057 198339 102562 198339 99052 198340 102562 198340 99053 198340 102562 198341 99054 198341 99053 198341 99053 198342 99054 198342 102918 198342 99053 198343 102918 198343 99055 198343 99052 198344 99056 198344 99057 198344 99057 198345 99056 198345 99058 198345 99057 198346 99058 198346 99059 198346 102635 198347 102632 198347 99060 198347 102635 198348 99060 198348 99061 198348 99060 198349 99062 198349 99061 198349 99061 198350 99062 198350 102682 198350 99061 198351 102682 198351 102685 198351 99063 198352 98502 198352 99064 198352 99063 198353 99064 198353 103736 198353 103736 198354 99064 198354 99065 198354 103736 198355 99065 198355 99066 198355 99066 198356 99065 198356 98499 198356 99066 198357 98499 198357 99068 198357 99068 198358 98499 198358 99067 198358 99068 198359 99067 198359 103737 198359 103737 198360 99067 198360 98496 198360 103737 198361 98496 198361 103739 198361 103739 198362 98496 198362 98495 198362 103739 198363 98495 198363 99069 198363 99069 198364 98495 198364 98493 198364 99069 198365 98493 198365 103709 198365 103709 198366 98493 198366 98491 198366 103709 198367 98491 198367 103712 198367 103712 198368 98491 198368 98490 198368 103712 198369 98490 198369 99070 198369 99070 198370 98490 198370 99071 198370 99070 198371 99071 198371 103713 198371 103713 198372 99071 198372 98489 198372 103713 198373 98489 198373 103715 198373 103715 198374 98489 198374 99072 198374 103715 198375 99072 198375 99073 198375 99073 198376 99072 198376 98487 198376 99073 198377 98487 198377 103717 198377 103717 198378 98487 198378 99075 198378 103717 198379 99075 198379 99074 198379 99074 198380 99075 198380 98486 198380 99074 198381 98486 198381 103718 198381 103718 198382 98486 198382 103758 198382 103718 198383 103758 198383 102227 198383 98392 198384 99076 198384 98393 198384 98393 198385 99076 198385 103850 198385 98393 198386 103850 198386 98394 198386 98394 198387 103850 198387 103854 198387 98394 198388 103854 198388 99077 198388 99077 198389 103854 198389 103856 198389 99077 198390 103856 198390 98397 198390 98397 198391 103856 198391 103857 198391 98397 198392 103857 198392 99078 198392 99078 198393 103857 198393 103859 198393 99078 198394 103859 198394 98398 198394 98398 198395 103859 198395 103862 198395 98398 198396 103862 198396 98399 198396 98399 198397 103862 198397 99079 198397 98399 198398 99079 198398 99080 198398 99080 198399 99079 198399 103863 198399 99080 198400 103863 198400 98401 198400 98401 198401 103863 198401 99081 198401 98401 198402 99081 198402 99082 198402 99082 198403 99081 198403 99084 198403 99082 198404 99084 198404 99083 198404 99083 198405 99084 198405 99085 198405 99083 198406 99085 198406 98404 198406 98404 198407 99085 198407 99086 198407 98404 198408 99086 198408 99087 198408 99087 198409 99086 198409 103867 198409 99087 198410 103867 198410 99088 198410 99088 198411 103867 198411 99089 198411 99088 198412 99089 198412 99090 198412 99090 198413 99089 198413 103870 198413 99090 198414 103870 198414 98405 198414 98405 198415 103870 198415 99091 198415 98405 198416 99091 198416 103998 198416 103998 198417 99091 198417 99092 198417 102212 198418 102213 198418 99093 198418 99093 198419 102213 198419 103932 198419 99093 198420 103932 198420 99094 198420 99094 198421 103932 198421 103934 198421 99094 198422 103934 198422 99095 198422 99095 198423 103934 198423 99096 198423 99095 198424 99096 198424 98457 198424 98457 198425 99096 198425 103936 198425 98457 198426 103936 198426 99097 198426 99097 198427 103936 198427 103937 198427 99097 198428 103937 198428 99098 198428 99098 198429 103937 198429 99100 198429 99098 198430 99100 198430 99099 198430 99099 198431 99100 198431 103940 198431 99099 198432 103940 198432 98461 198432 98461 198433 103940 198433 103941 198433 98461 198434 103941 198434 98462 198434 98462 198435 103941 198435 103942 198435 98462 198436 103942 198436 99101 198436 99101 198437 103942 198437 99103 198437 99101 198438 99103 198438 99102 198438 99102 198439 99103 198439 99104 198439 99102 198440 99104 198440 99105 198440 99105 198441 99104 198441 103901 198441 99105 198442 103901 198442 98463 198442 98463 198443 103901 198443 103903 198443 98463 198444 103903 198444 99106 198444 99106 198445 103903 198445 103904 198445 99106 198446 103904 198446 99107 198446 99107 198447 103904 198447 103906 198447 99107 198448 103906 198448 99108 198448 99108 198449 103906 198449 99109 198449 99108 198450 99109 198450 99110 198450 99110 198451 99109 198451 103909 198451 99110 198452 103909 198452 99111 198452 99111 198453 103909 198453 103911 198453 99113 198454 103944 198454 99112 198454 99113 198455 99112 198455 99114 198455 99114 198456 99112 198456 98455 198456 99114 198457 98455 198457 99115 198457 99115 198458 98455 198458 99116 198458 99115 198459 99116 198459 103914 198459 103914 198460 99116 198460 98450 198460 103914 198461 98450 198461 103916 198461 103916 198462 98450 198462 98449 198462 103916 198463 98449 198463 103918 198463 103918 198464 98449 198464 98446 198464 103918 198465 98446 198465 103919 198465 103919 198466 98446 198466 98447 198466 103919 198467 98447 198467 99118 198467 99118 198468 98447 198468 99117 198468 99118 198469 99117 198469 103922 198469 103922 198470 99117 198470 98443 198470 103922 198471 98443 198471 103924 198471 103924 198472 98443 198472 98438 198472 103924 198473 98438 198473 99119 198473 99119 198474 98438 198474 98439 198474 99119 198475 98439 198475 99120 198475 99120 198476 98439 198476 98434 198476 99120 198477 98434 198477 99121 198477 99121 198478 98434 198478 98433 198478 99121 198479 98433 198479 103928 198479 103928 198480 98433 198480 98430 198480 103928 198481 98430 198481 103929 198481 103929 198482 98430 198482 99122 198482 103929 198483 99122 198483 99123 198483 99123 198484 99122 198484 98426 198484 99123 198485 98426 198485 99124 198485 99124 198486 98426 198486 99125 198486 99124 198487 99125 198487 99126 198487 99126 198488 99125 198488 103977 198488 99126 198489 103977 198489 103933 198489 98420 198490 99127 198490 99129 198490 99129 198491 99127 198491 99128 198491 99129 198492 99128 198492 98418 198492 98418 198493 99128 198493 102012 198493 98418 198494 102012 198494 98417 198494 98417 198495 102012 198495 102011 198495 98417 198496 102011 198496 99130 198496 99130 198497 102011 198497 99131 198497 99130 198498 99131 198498 98414 198498 98414 198499 99131 198499 99132 198499 98414 198500 99132 198500 99133 198500 99133 198501 99132 198501 99134 198501 99133 198502 99134 198502 99135 198502 99135 198503 99134 198503 99136 198503 99135 198504 99136 198504 98413 198504 98413 198505 99136 198505 102019 198505 98413 198506 102019 198506 99137 198506 99137 198507 102019 198507 102017 198507 99137 198508 102017 198508 98411 198508 98411 198509 102017 198509 99138 198509 98411 198510 99138 198510 99139 198510 99139 198511 99138 198511 102015 198511 99139 198512 102015 198512 98410 198512 98410 198513 102015 198513 99140 198513 98410 198514 99140 198514 99141 198514 99141 198515 99140 198515 102004 198515 99141 198516 102004 198516 99142 198516 99142 198517 102004 198517 102003 198517 99142 198518 102003 198518 98408 198518 98408 198519 102003 198519 102001 198519 98408 198520 102001 198520 103997 198520 103997 198521 102001 198521 102000 198521 102172 198522 99143 198522 99144 198522 99144 198523 99143 198523 99145 198523 99144 198524 99145 198524 98409 198524 98409 198525 99145 198525 103673 198525 98409 198526 103673 198526 99146 198526 99146 198527 103673 198527 99147 198527 99146 198528 99147 198528 99148 198528 99148 198529 99147 198529 103674 198529 99148 198530 103674 198530 99149 198530 99149 198531 103674 198531 103676 198531 99149 198532 103676 198532 99150 198532 99150 198533 103676 198533 103677 198533 99150 198534 103677 198534 98412 198534 98412 198535 103677 198535 103679 198535 98412 198536 103679 198536 99151 198536 99151 198537 103679 198537 103680 198537 99151 198538 103680 198538 99152 198538 99152 198539 103680 198539 103682 198539 99152 198540 103682 198540 98415 198540 98415 198541 103682 198541 103683 198541 98415 198542 103683 198542 98416 198542 98416 198543 103683 198543 99153 198543 98416 198544 99153 198544 99154 198544 99154 198545 99153 198545 99155 198545 99154 198546 99155 198546 98419 198546 98419 198547 99155 198547 99156 198547 98419 198548 99156 198548 99157 198548 99157 198549 99156 198549 103684 198549 99157 198550 103684 198550 99158 198550 99158 198551 103684 198551 99159 198551 99158 198552 99159 198552 99160 198552 99160 198553 99159 198553 103687 198553 98503 198554 103719 198554 98504 198554 98504 198555 103719 198555 103720 198555 98504 198556 103720 198556 98506 198556 98506 198557 103720 198557 99161 198557 98506 198558 99161 198558 98508 198558 98508 198559 99161 198559 103721 198559 98508 198560 103721 198560 98509 198560 98509 198561 103721 198561 99162 198561 98509 198562 99162 198562 98511 198562 98511 198563 99162 198563 103722 198563 98511 198564 103722 198564 98512 198564 98512 198565 103722 198565 103724 198565 98512 198566 103724 198566 98514 198566 98514 198567 103724 198567 99163 198567 98514 198568 99163 198568 98515 198568 98515 198569 99163 198569 103726 198569 98515 198570 103726 198570 99164 198570 99164 198571 103726 198571 99165 198571 99164 198572 99165 198572 98519 198572 98519 198573 99165 198573 99166 198573 98519 198574 99166 198574 99167 198574 99167 198575 99166 198575 103729 198575 99167 198576 103729 198576 99168 198576 99168 198577 103729 198577 103730 198577 99168 198578 103730 198578 99170 198578 99170 198579 103730 198579 99169 198579 99170 198580 99169 198580 99171 198580 99171 198581 99169 198581 103732 198581 99171 198582 103732 198582 99172 198582 99172 198583 103732 198583 99173 198583 99172 198584 99173 198584 102139 198584 102139 198585 99173 198585 102140 198585 103771 198586 102138 198586 98483 198586 103771 198587 98483 198587 99174 198587 99174 198588 98483 198588 98481 198588 99174 198589 98481 198589 103772 198589 103772 198590 98481 198590 98479 198590 103772 198591 98479 198591 103774 198591 103774 198592 98479 198592 98478 198592 103774 198593 98478 198593 99175 198593 99175 198594 98478 198594 98476 198594 99175 198595 98476 198595 103775 198595 103775 198596 98476 198596 99176 198596 103775 198597 99176 198597 103777 198597 103777 198598 99176 198598 99177 198598 103777 198599 99177 198599 103778 198599 103778 198600 99177 198600 99178 198600 103778 198601 99178 198601 99179 198601 99179 198602 99178 198602 98472 198602 99179 198603 98472 198603 99180 198603 99180 198604 98472 198604 98470 198604 99180 198605 98470 198605 103780 198605 103780 198606 98470 198606 98469 198606 103780 198607 98469 198607 99181 198607 99181 198608 98469 198608 98468 198608 99181 198609 98468 198609 99182 198609 99182 198610 98468 198610 99183 198610 99182 198611 99183 198611 99184 198611 99184 198612 99183 198612 99185 198612 99184 198613 99185 198613 103784 198613 103784 198614 99185 198614 99186 198614 103784 198615 99186 198615 103785 198615 103785 198616 99186 198616 98466 198616 103785 198617 98466 198617 99187 198617 99187 198618 98466 198618 103803 198618 99187 198619 103803 198619 99188 198619 102119 198620 99189 198620 99190 198620 99190 198621 99189 198621 102056 198621 99191 198622 102112 198622 102064 198622 102064 198623 102112 198623 99197 198623 99192 198624 99193 198624 99194 198624 99194 198625 99193 198625 99195 198625 99194 198626 99195 198626 99196 198626 99196 198627 99195 198627 102061 198627 99196 198628 102061 198628 99197 198628 99197 198629 102061 198629 99198 198629 99197 198630 99198 198630 102064 198630 102031 198631 102108 198631 99206 198631 99206 198632 102108 198632 99207 198632 99209 198633 99208 198633 104082 198633 104082 198634 99208 198634 102090 198634 99199 198635 102089 198635 102022 198635 102022 198636 102024 198636 99199 198636 99199 198637 102024 198637 102025 198637 99199 198638 102025 198638 102101 198638 102101 198639 102025 198639 102026 198639 102101 198640 102026 198640 99200 198640 99201 198641 102089 198641 99199 198641 99201 198642 99199 198642 99202 198642 99202 198643 99199 198643 102101 198643 99202 198644 102101 198644 101931 198644 99205 198645 101930 198645 102100 198645 102104 198646 99204 198646 99203 198646 99203 198647 99204 198647 99205 198647 99203 198648 99205 198648 102105 198648 102105 198649 99205 198649 102100 198649 99206 198650 99207 198650 101927 198650 101927 198651 99207 198651 101926 198651 102086 198652 101925 198652 99207 198652 99207 198653 101925 198653 101926 198653 99208 198654 99209 198654 99210 198654 99210 198655 99209 198655 99211 198655 102059 198656 99190 198656 99212 198656 99212 198657 99190 198657 104183 198657 101891 198658 99213 198658 99545 198658 99545 198659 99213 198659 99547 198659 101904 198660 101582 198660 101946 198660 101946 198661 101582 198661 101581 198661 99231 198662 102078 198662 99214 198662 99214 198663 102078 198663 99215 198663 101877 198664 99214 198664 101940 198664 101940 198665 99214 198665 99215 198665 99228 198666 101939 198666 99229 198666 99229 198667 101939 198667 99216 198667 99229 198668 99216 198668 99217 198668 99217 198669 99216 198669 99218 198669 99217 198670 99218 198670 101887 198670 101887 198671 99218 198671 101937 198671 101911 198672 99219 198672 101914 198672 101914 198673 99219 198673 102071 198673 101914 198674 102071 198674 99220 198674 99220 198675 102071 198675 102072 198675 99220 198676 102072 198676 101935 198676 101935 198677 102072 198677 101936 198677 101915 198678 101596 198678 99221 198678 99221 198679 101596 198679 101535 198679 101932 198680 99222 198680 101994 198680 101994 198681 99222 198681 99223 198681 99223 198682 99222 198682 99224 198682 99223 198683 99224 198683 101898 198683 99225 198684 101933 198684 99226 198684 99226 198685 101933 198685 101932 198685 99226 198686 101932 198686 101546 198686 101546 198687 101932 198687 101994 198687 101928 198688 99227 198688 101891 198688 101891 198689 99227 198689 99213 198689 101962 198690 101964 198690 99228 198690 101962 198691 99228 198691 101959 198691 101959 198692 99228 198692 99229 198692 101959 198693 99229 198693 101957 198693 101957 198694 99229 198694 101956 198694 101956 198695 99229 198695 99217 198695 101956 198696 99217 198696 99230 198696 99230 198697 99217 198697 101887 198697 99230 198698 101887 198698 101886 198698 101880 198699 99231 198699 99232 198699 99232 198700 99231 198700 99214 198700 99232 198701 99214 198701 99233 198701 101433 198702 99234 198702 101349 198702 101433 198703 101349 198703 99235 198703 99235 198704 101349 198704 99236 198704 99235 198705 99236 198705 99237 198705 99237 198706 99236 198706 101348 198706 99237 198707 101348 198707 99238 198707 99238 198708 101348 198708 99239 198708 99238 198709 99239 198709 99240 198709 99240 198710 99239 198710 99241 198710 99240 198711 99241 198711 99242 198711 99242 198712 99241 198712 99243 198712 99242 198713 99243 198713 101435 198713 101435 198714 99243 198714 101869 198714 101435 198715 101869 198715 101436 198715 99244 198716 101337 198716 99245 198716 99244 198717 99245 198717 99246 198717 99246 198718 99245 198718 99247 198718 99246 198719 99247 198719 99249 198719 99249 198720 99247 198720 99248 198720 99249 198721 99248 198721 99251 198721 99251 198722 99248 198722 99250 198722 99251 198723 99250 198723 101450 198723 101450 198724 99250 198724 99252 198724 101450 198725 99252 198725 101451 198725 101451 198726 99252 198726 99253 198726 101451 198727 99253 198727 99255 198727 99255 198728 99253 198728 99254 198728 99255 198729 99254 198729 99256 198729 99555 198730 101859 198730 99257 198730 99555 198731 99257 198731 99258 198731 99258 198732 99257 198732 99259 198732 99258 198733 99259 198733 99260 198733 99260 198734 99259 198734 99261 198734 99260 198735 99261 198735 99262 198735 99262 198736 99261 198736 99263 198736 99262 198737 99263 198737 99264 198737 99264 198738 99263 198738 101333 198738 99264 198739 101333 198739 99265 198739 99265 198740 101333 198740 101332 198740 99265 198741 101332 198741 99266 198741 99266 198742 101332 198742 99267 198742 99266 198743 99267 198743 99557 198743 99565 198744 99566 198744 101319 198744 99268 198745 101321 198745 99270 198745 99268 198746 99270 198746 99269 198746 99269 198747 99270 198747 99271 198747 99269 198748 99271 198748 99272 198748 99272 198749 99271 198749 99273 198749 99272 198750 99273 198750 99274 198750 101319 198751 99566 198751 99273 198751 99273 198752 99566 198752 99568 198752 99273 198753 99568 198753 99274 198753 99565 198754 101319 198754 99569 198754 99569 198755 101319 198755 99275 198755 99569 198756 99275 198756 99276 198756 99276 198757 99275 198757 101317 198757 99276 198758 101317 198758 101840 198758 99278 198759 99277 198759 99279 198759 99278 198760 99279 198760 99280 198760 99280 198761 99279 198761 99281 198761 99280 198762 99281 198762 99282 198762 99282 198763 99281 198763 99283 198763 99282 198764 99283 198764 99585 198764 99585 198765 99283 198765 99284 198765 99585 198766 99284 198766 99285 198766 99285 198767 99284 198767 99286 198767 99285 198768 99286 198768 99576 198768 99576 198769 99286 198769 101311 198769 99576 198770 101311 198770 99577 198770 99577 198771 101311 198771 101310 198771 99577 198772 101310 198772 99578 198772 99601 198773 99600 198773 101294 198773 99287 198774 99289 198774 99598 198774 99598 198775 99289 198775 99599 198775 101294 198776 99600 198776 99289 198776 99289 198777 99600 198777 99288 198777 99289 198778 99288 198778 99599 198778 99601 198779 101294 198779 99290 198779 99290 198780 101294 198780 99291 198780 99290 198781 99291 198781 99292 198781 99292 198782 99291 198782 99294 198782 99292 198783 99294 198783 99293 198783 99293 198784 99294 198784 101293 198784 99293 198785 101293 198785 99295 198785 99295 198786 101293 198786 101292 198786 99295 198787 101292 198787 99593 198787 99616 198788 99614 198788 101282 198788 99616 198789 101282 198789 99296 198789 99296 198790 101282 198790 101283 198790 99296 198791 101283 198791 99617 198791 99617 198792 101283 198792 99297 198792 99617 198793 99297 198793 99298 198793 99298 198794 99297 198794 99299 198794 99299 198795 99297 198795 101285 198795 99299 198796 101285 198796 99300 198796 99300 198797 101285 198797 101286 198797 99300 198798 101286 198798 99301 198798 99301 198799 101286 198799 99302 198799 99301 198800 99302 198800 99609 198800 99609 198801 99302 198801 101276 198801 99609 198802 101276 198802 99611 198802 99303 198803 101268 198803 99304 198803 99303 198804 99304 198804 99305 198804 99305 198805 99304 198805 99306 198805 99305 198806 99306 198806 99532 198806 99532 198807 99306 198807 99307 198807 99532 198808 99307 198808 99533 198808 99533 198809 99307 198809 101266 198809 99533 198810 101266 198810 99534 198810 99534 198811 101266 198811 101265 198811 99534 198812 101265 198812 99308 198812 99308 198813 101265 198813 101274 198813 99308 198814 101274 198814 99309 198814 99309 198815 101274 198815 101272 198815 99309 198816 101272 198816 99535 198816 101811 198817 101255 198817 99310 198817 101811 198818 99310 198818 101372 198818 101372 198819 99310 198819 101253 198819 101372 198820 101253 198820 99311 198820 99311 198821 101253 198821 99312 198821 99311 198822 99312 198822 101383 198822 101383 198823 99312 198823 101252 198823 101383 198824 101252 198824 101381 198824 101381 198825 101252 198825 101250 198825 101381 198826 101250 198826 99313 198826 99313 198827 101250 198827 101264 198827 99313 198828 101264 198828 101373 198828 101373 198829 101264 198829 99314 198829 101373 198830 99314 198830 99315 198830 99316 198831 101237 198831 99317 198831 99316 198832 99317 198832 101398 198832 101398 198833 99317 198833 99318 198833 101398 198834 99318 198834 101399 198834 101399 198835 99318 198835 101236 198835 101399 198836 101236 198836 99319 198836 99319 198837 101236 198837 101235 198837 99319 198838 101235 198838 99320 198838 99320 198839 101235 198839 101249 198839 99320 198840 101249 198840 101395 198840 101395 198841 101249 198841 101247 198841 101395 198842 101247 198842 99321 198842 99321 198843 101247 198843 101246 198843 99321 198844 101246 198844 101800 198844 101411 198845 101228 198845 99322 198845 101411 198846 99322 198846 99323 198846 99323 198847 99322 198847 101226 198847 99323 198848 101226 198848 99324 198848 99324 198849 101226 198849 99325 198849 99324 198850 99325 198850 101413 198850 101413 198851 99325 198851 99326 198851 101413 198852 99326 198852 101415 198852 101415 198853 99326 198853 99328 198853 101415 198854 99328 198854 99327 198854 99327 198855 99328 198855 99329 198855 99327 198856 99329 198856 99330 198856 99330 198857 99329 198857 101234 198857 99330 198858 101234 198858 101794 198858 101423 198859 101216 198859 101214 198859 101423 198860 101214 198860 99331 198860 99331 198861 101214 198861 99332 198861 99331 198862 99332 198862 99333 198862 99333 198863 99332 198863 99334 198863 99333 198864 99334 198864 99335 198864 99335 198865 99334 198865 99336 198865 99335 198866 99336 198866 99337 198866 99337 198867 99336 198867 99338 198867 99337 198868 99338 198868 99339 198868 99339 198869 99338 198869 99340 198869 99339 198870 99340 198870 99341 198870 99341 198871 99340 198871 101224 198871 99341 198872 101224 198872 101784 198872 101768 198873 101766 198873 99633 198873 99633 198874 101766 198874 99342 198874 99633 198875 99342 198875 99631 198875 99631 198876 99342 198876 99344 198876 99631 198877 99344 198877 99343 198877 99343 198878 99344 198878 100099 198878 99343 198879 100099 198879 99345 198879 99345 198880 100099 198880 99346 198880 99345 198881 99346 198881 99348 198881 99348 198882 99346 198882 99347 198882 99348 198883 99347 198883 99629 198883 99629 198884 99347 198884 99349 198884 99629 198885 99349 198885 99350 198885 99350 198886 99349 198886 99351 198886 99350 198887 99351 198887 99627 198887 99627 198888 99351 198888 100096 198888 99627 198889 100096 198889 99626 198889 99626 198890 100096 198890 100095 198890 99626 198891 100095 198891 99353 198891 99353 198892 100095 198892 99352 198892 99353 198893 99352 198893 99354 198893 99354 198894 99352 198894 99355 198894 99354 198895 99355 198895 99624 198895 99624 198896 99355 198896 99356 198896 99624 198897 99356 198897 99622 198897 99622 198898 99356 198898 100092 198898 99622 198899 100092 198899 99358 198899 99358 198900 100092 198900 99357 198900 99358 198901 99357 198901 101370 198901 101370 198902 99357 198902 99359 198902 99361 198903 99360 198903 99505 198903 99361 198904 99505 198904 104323 198904 104323 198905 99505 198905 99362 198905 104323 198906 99362 198906 99363 198906 99363 198907 99362 198907 99364 198907 99363 198908 99364 198908 104324 198908 104324 198909 99364 198909 99366 198909 104324 198910 99366 198910 99365 198910 99365 198911 99366 198911 99512 198911 99365 198912 99512 198912 99367 198912 99367 198913 99512 198913 99513 198913 99367 198914 99513 198914 104311 198914 104311 198915 99513 198915 99368 198915 104311 198916 99368 198916 104285 198916 104285 198917 99368 198917 99520 198917 104285 198918 99520 198918 99369 198918 99369 198919 99520 198919 99370 198919 99369 198920 99370 198920 104287 198920 104287 198921 99370 198921 99371 198921 104287 198922 99371 198922 104284 198922 104284 198923 99371 198923 99372 198923 104284 198924 99372 198924 99373 198924 99373 198925 99372 198925 99526 198925 99373 198926 99526 198926 99374 198926 99374 198927 99526 198927 99524 198927 99374 198928 99524 198928 99375 198928 99375 198929 99524 198929 99528 198929 99375 198930 99528 198930 99376 198930 99376 198931 99528 198931 99529 198931 99376 198932 99529 198932 104298 198932 104298 198933 99529 198933 99378 198933 104298 198934 99378 198934 99377 198934 99377 198935 99378 198935 99379 198935 99377 198936 99379 198936 104300 198936 104300 198937 99379 198937 99380 198937 104300 198938 99380 198938 101751 198938 99432 198939 99382 198939 101659 198939 99381 198940 101969 198940 99430 198940 99430 198941 101969 198941 101966 198941 99430 198942 101966 198942 101697 198942 99503 198943 101659 198943 101696 198943 101696 198944 101659 198944 99382 198944 101696 198945 99382 198945 99429 198945 101659 198946 99383 198946 99432 198946 99432 198947 99383 198947 99384 198947 99432 198948 99384 198948 99385 198948 99385 198949 99384 198949 99386 198949 99385 198950 99386 198950 99434 198950 99386 198951 101658 198951 99434 198951 99434 198952 101658 198952 99387 198952 99434 198953 99387 198953 99435 198953 99435 198954 99387 198954 101656 198954 99435 198955 101656 198955 99388 198955 101656 198956 101655 198956 99388 198956 99388 198957 101655 198957 99389 198957 99388 198958 99389 198958 99438 198958 99438 198959 99389 198959 101654 198959 99438 198960 101654 198960 99391 198960 101654 198961 99390 198961 99391 198961 99391 198962 99390 198962 101651 198962 99391 198963 101651 198963 99392 198963 99392 198964 101651 198964 101650 198964 99392 198965 101650 198965 99440 198965 99440 198966 101650 198966 101649 198966 99440 198967 101649 198967 99441 198967 101649 198968 99393 198968 99441 198968 99441 198969 99393 198969 99394 198969 99441 198970 99394 198970 99396 198970 99396 198971 99394 198971 99395 198971 99396 198972 99395 198972 99443 198972 99395 198973 99397 198973 99443 198973 99443 198974 99397 198974 99398 198974 99443 198975 99398 198975 99399 198975 99399 198976 99398 198976 99400 198976 99399 198977 99400 198977 99401 198977 99400 198978 101647 198978 99401 198978 99401 198979 101647 198979 101645 198979 99401 198980 101645 198980 99402 198980 99402 198981 101645 198981 101644 198981 99402 198982 101644 198982 99404 198982 101644 198983 101642 198983 99404 198983 99404 198984 101642 198984 99403 198984 99404 198985 99403 198985 99405 198985 99405 198986 99403 198986 99406 198986 99405 198987 99406 198987 99446 198987 99406 198988 101639 198988 99446 198988 99446 198989 101639 198989 101637 198989 99446 198990 101637 198990 99407 198990 99407 198991 101637 198991 101638 198991 99407 198992 101638 198992 99409 198992 101638 198993 99408 198993 99409 198993 99409 198994 99408 198994 99410 198994 99409 198995 99410 198995 99411 198995 99411 198996 99410 198996 99412 198996 99411 198997 99412 198997 99449 198997 99449 198998 99412 198998 101636 198998 99449 198999 101636 198999 99450 198999 101636 199000 101634 199000 99450 199000 99450 199001 101634 199001 99413 199001 99450 199002 99413 199002 99451 199002 99451 199003 99413 199003 101633 199003 99451 199004 101633 199004 99452 199004 101633 199005 101616 199005 99452 199005 99452 199006 101616 199006 99414 199006 99452 199007 99414 199007 99415 199007 99415 199008 99414 199008 101632 199008 99415 199009 101632 199009 99417 199009 101632 199010 99416 199010 99417 199010 99417 199011 99416 199011 99418 199011 99417 199012 99418 199012 99454 199012 99454 199013 99418 199013 101631 199013 99454 199014 101631 199014 99419 199014 101631 199015 101628 199015 99419 199015 99419 199016 101628 199016 101630 199016 99419 199017 101630 199017 99420 199017 99420 199018 101630 199018 99421 199018 99420 199019 99421 199019 99422 199019 99421 199020 101627 199020 99422 199020 99422 199021 101627 199021 101626 199021 99422 199022 101626 199022 99457 199022 99457 199023 101626 199023 101625 199023 99457 199024 101625 199024 99423 199024 101625 199025 101623 199025 99423 199025 99423 199026 101623 199026 99424 199026 99423 199027 99424 199027 99425 199027 99425 199028 99424 199028 101622 199028 99425 199029 101622 199029 99458 199029 99458 199030 101622 199030 99426 199030 99458 199031 99426 199031 99459 199031 99426 199032 99427 199032 99459 199032 99459 199033 99427 199033 101618 199033 99459 199034 101618 199034 99428 199034 99428 199035 101618 199035 101620 199035 99428 199036 101620 199036 99461 199036 99461 199037 101620 199037 101621 199037 101697 199038 99429 199038 99430 199038 99430 199039 99429 199039 99382 199039 99430 199040 99382 199040 99431 199040 99431 199041 99382 199041 99432 199041 99431 199042 99432 199042 99501 199042 99501 199043 99432 199043 99385 199043 99501 199044 99385 199044 99433 199044 99433 199045 99385 199045 99434 199045 99433 199046 99434 199046 99499 199046 99499 199047 99434 199047 99435 199047 99499 199048 99435 199048 99436 199048 99436 199049 99435 199049 99388 199049 99436 199050 99388 199050 99437 199050 99437 199051 99388 199051 99438 199051 99437 199052 99438 199052 99497 199052 99497 199053 99438 199053 99391 199053 99497 199054 99391 199054 99494 199054 99494 199055 99391 199055 99392 199055 99494 199056 99392 199056 99439 199056 99439 199057 99392 199057 99440 199057 99439 199058 99440 199058 99442 199058 99442 199059 99440 199059 99441 199059 99442 199060 99441 199060 99493 199060 99493 199061 99441 199061 99396 199061 99493 199062 99396 199062 99491 199062 99491 199063 99396 199063 99443 199063 99491 199064 99443 199064 99444 199064 99444 199065 99443 199065 99399 199065 99444 199066 99399 199066 99488 199066 99488 199067 99399 199067 99401 199067 99488 199068 99401 199068 99486 199068 99486 199069 99401 199069 99402 199069 99486 199070 99402 199070 99445 199070 99445 199071 99402 199071 99404 199071 99445 199072 99404 199072 99484 199072 99484 199073 99404 199073 99405 199073 99484 199074 99405 199074 99482 199074 99482 199075 99405 199075 99446 199075 99482 199076 99446 199076 99481 199076 99481 199077 99446 199077 99407 199077 99481 199078 99407 199078 99447 199078 99447 199079 99407 199079 99409 199079 99447 199080 99409 199080 99480 199080 99480 199081 99409 199081 99411 199081 99480 199082 99411 199082 99448 199082 99448 199083 99411 199083 99449 199083 99448 199084 99449 199084 99479 199084 99479 199085 99449 199085 99450 199085 99479 199086 99450 199086 99478 199086 99478 199087 99450 199087 99451 199087 99478 199088 99451 199088 99476 199088 99476 199089 99451 199089 99452 199089 99476 199090 99452 199090 99453 199090 99453 199091 99452 199091 99415 199091 99453 199092 99415 199092 99474 199092 99474 199093 99415 199093 99417 199093 99474 199094 99417 199094 99473 199094 99473 199095 99417 199095 99454 199095 99473 199096 99454 199096 99471 199096 99471 199097 99454 199097 99419 199097 99471 199098 99419 199098 99469 199098 99469 199099 99419 199099 99420 199099 99469 199100 99420 199100 99455 199100 99455 199101 99420 199101 99422 199101 99455 199102 99422 199102 99456 199102 99456 199103 99422 199103 99457 199103 99456 199104 99457 199104 99466 199104 99466 199105 99457 199105 99423 199105 99466 199106 99423 199106 99464 199106 99464 199107 99423 199107 99425 199107 99464 199108 99425 199108 99463 199108 99463 199109 99425 199109 99458 199109 99463 199110 99458 199110 99462 199110 99462 199111 99458 199111 99459 199111 99462 199112 99459 199112 99460 199112 99460 199113 99459 199113 99428 199113 99460 199114 99428 199114 101663 199114 101663 199115 99428 199115 99461 199115 101663 199116 101664 199116 99460 199116 99460 199117 101664 199117 99546 199117 99460 199118 99546 199118 99462 199118 99462 199119 99546 199119 99552 199119 99462 199120 99552 199120 99463 199120 99463 199121 99552 199121 99554 199121 99463 199122 99554 199122 99464 199122 99464 199123 99554 199123 99465 199123 99464 199124 99465 199124 99466 199124 99466 199125 99465 199125 99467 199125 99466 199126 99467 199126 99456 199126 99456 199127 99467 199127 99468 199127 99456 199128 99468 199128 99455 199128 99455 199129 99468 199129 99470 199129 99455 199130 99470 199130 99469 199130 99469 199131 99470 199131 99561 199131 99469 199132 99561 199132 99471 199132 99471 199133 99561 199133 99472 199133 99471 199134 99472 199134 99473 199134 99473 199135 99472 199135 99564 199135 99473 199136 99564 199136 99474 199136 99474 199137 99564 199137 99570 199137 99474 199138 99570 199138 99453 199138 99453 199139 99570 199139 99475 199139 99453 199140 99475 199140 99476 199140 99476 199141 99475 199141 99477 199141 99476 199142 99477 199142 99478 199142 99478 199143 99477 199143 99571 199143 99478 199144 99571 199144 99479 199144 99479 199145 99571 199145 99573 199145 99479 199146 99573 199146 99448 199146 99448 199147 99573 199147 99582 199147 99448 199148 99582 199148 99480 199148 99480 199149 99582 199149 99584 199149 99480 199150 99584 199150 99447 199150 99447 199151 99584 199151 99587 199151 99447 199152 99587 199152 99481 199152 99481 199153 99587 199153 99483 199153 99481 199154 99483 199154 99482 199154 99482 199155 99483 199155 99588 199155 99482 199156 99588 199156 99484 199156 99484 199157 99588 199157 99590 199157 99484 199158 99590 199158 99445 199158 99445 199159 99590 199159 99485 199159 99445 199160 99485 199160 99486 199160 99486 199161 99485 199161 99487 199161 99486 199162 99487 199162 99488 199162 99488 199163 99487 199163 99489 199163 99488 199164 99489 199164 99444 199164 99444 199165 99489 199165 99490 199165 99444 199166 99490 199166 99491 199166 99491 199167 99490 199167 99492 199167 99491 199168 99492 199168 99493 199168 99493 199169 99492 199169 99606 199169 99493 199170 99606 199170 99442 199170 99442 199171 99606 199171 99610 199171 99442 199172 99610 199172 99439 199172 99439 199173 99610 199173 99495 199173 99439 199174 99495 199174 99494 199174 99494 199175 99495 199175 99496 199175 99494 199176 99496 199176 99497 199176 99497 199177 99496 199177 99619 199177 99497 199178 99619 199178 99437 199178 99437 199179 99619 199179 99498 199179 99437 199180 99498 199180 99436 199180 99436 199181 99498 199181 99620 199181 99436 199182 99620 199182 99499 199182 99499 199183 99620 199183 99621 199183 99499 199184 99621 199184 99433 199184 99433 199185 99621 199185 99500 199185 99433 199186 99500 199186 99501 199186 99501 199187 99500 199187 99536 199187 99501 199188 99536 199188 99431 199188 99431 199189 99536 199189 99502 199189 99431 199190 99502 199190 99430 199190 99430 199191 99502 199191 101970 199191 99430 199192 101970 199192 99381 199192 99503 199193 99506 199193 99360 199193 99360 199194 99506 199194 99505 199194 101701 199195 99362 199195 99504 199195 99504 199196 99362 199196 99505 199196 99504 199197 99505 199197 101699 199197 101699 199198 99505 199198 99506 199198 101701 199199 101705 199199 99362 199199 99362 199200 101705 199200 101707 199200 99362 199201 101707 199201 99364 199201 99509 199202 99366 199202 99507 199202 99507 199203 99366 199203 99364 199203 99507 199204 99364 199204 99508 199204 99508 199205 99364 199205 101707 199205 99509 199206 99510 199206 99366 199206 99366 199207 99510 199207 99511 199207 99366 199208 99511 199208 99512 199208 99511 199209 101683 199209 99512 199209 99512 199210 101683 199210 101714 199210 99512 199211 101714 199211 99513 199211 101718 199212 99368 199212 99514 199212 99514 199213 99368 199213 99513 199213 99514 199214 99513 199214 99515 199214 99515 199215 99513 199215 101714 199215 101718 199216 99516 199216 99368 199216 99368 199217 99516 199217 99517 199217 99368 199218 99517 199218 99520 199218 99517 199219 99518 199219 99520 199219 99520 199220 99518 199220 99519 199220 99520 199221 99519 199221 99370 199221 99519 199222 99521 199222 99370 199222 99370 199223 99521 199223 99522 199223 99370 199224 99522 199224 99371 199224 99522 199225 101721 199225 99371 199225 99371 199226 101721 199226 101725 199226 99371 199227 101725 199227 99372 199227 101731 199228 99526 199228 101729 199228 101729 199229 99526 199229 99372 199229 101729 199230 99372 199230 99523 199230 99523 199231 99372 199231 101725 199231 101733 199232 99524 199232 101734 199232 101734 199233 99524 199233 99526 199233 101734 199234 99526 199234 99525 199234 99525 199235 99526 199235 101731 199235 101733 199236 99527 199236 99524 199236 99524 199237 99527 199237 101691 199237 99524 199238 101691 199238 99528 199238 101736 199239 99529 199239 101741 199239 101741 199240 99529 199240 99528 199240 101741 199241 99528 199241 101692 199241 101692 199242 99528 199242 101691 199242 101736 199243 101745 199243 99529 199243 99529 199244 101745 199244 99530 199244 99529 199245 99530 199245 99378 199245 99530 199246 101750 199246 99378 199246 99378 199247 101750 199247 101749 199247 99378 199248 101749 199248 99379 199248 101621 199249 99380 199249 101746 199249 101746 199250 99380 199250 99379 199250 101746 199251 99379 199251 101748 199251 101748 199252 99379 199252 101749 199252 99537 199253 101970 199253 99502 199253 101821 199254 101820 199254 99531 199254 99531 199255 101820 199255 99303 199255 99531 199256 99303 199256 101544 199256 99303 199257 99305 199257 101544 199257 101544 199258 99305 199258 99532 199258 101544 199259 99532 199259 101543 199259 101543 199260 99532 199260 99533 199260 101543 199261 99533 199261 99534 199261 99308 199262 99309 199262 99500 199262 99500 199263 99309 199263 99535 199263 99500 199264 99535 199264 99536 199264 99536 199265 99535 199265 101813 199265 101813 199266 101815 199266 99536 199266 99536 199267 101815 199267 101816 199267 99536 199268 101816 199268 101817 199268 99537 199269 99502 199269 99538 199269 99543 199270 99542 199270 101973 199270 101973 199271 99542 199271 99539 199271 101973 199272 99539 199272 101975 199272 101975 199273 99539 199273 99541 199273 101821 199274 99531 199274 99539 199274 99539 199275 99531 199275 99540 199275 99539 199276 99540 199276 99541 199276 101817 199277 99542 199277 99536 199277 99536 199278 99542 199278 99543 199278 99536 199279 99543 199279 99502 199279 99502 199280 99543 199280 99544 199280 99502 199281 99544 199281 99538 199281 101664 199282 99545 199282 99546 199282 99546 199283 99545 199283 99547 199283 99546 199284 99547 199284 99552 199284 99552 199285 99547 199285 101986 199285 101986 199286 99548 199286 99552 199286 99552 199287 99548 199287 101983 199287 99552 199288 101983 199288 99549 199288 101982 199289 101980 199289 99558 199289 99558 199290 101980 199290 99550 199290 99558 199291 99550 199291 99551 199291 101850 199292 101852 199292 99558 199292 99558 199293 101852 199293 99552 199293 99558 199294 99552 199294 101982 199294 101982 199295 99552 199295 99549 199295 101852 199296 99553 199296 99552 199296 99552 199297 99553 199297 101853 199297 99552 199298 101853 199298 99554 199298 99554 199299 101853 199299 101854 199299 101854 199300 101856 199300 99554 199300 99554 199301 101856 199301 101858 199301 99554 199302 101858 199302 99465 199302 99465 199303 101858 199303 99555 199303 99465 199304 99555 199304 99258 199304 99265 199305 99556 199305 99264 199305 99264 199306 99556 199306 101534 199306 99264 199307 101534 199307 99262 199307 99262 199308 101534 199308 99260 199308 99265 199309 99266 199309 99556 199309 99556 199310 99266 199310 99557 199310 99556 199311 99557 199311 99558 199311 99558 199312 99557 199312 101848 199312 99558 199313 101848 199313 101850 199313 99258 199314 99260 199314 99465 199314 99465 199315 99260 199315 101534 199315 99465 199316 101534 199316 99467 199316 99467 199317 101534 199317 99559 199317 99467 199318 99559 199318 99468 199318 99468 199319 99559 199319 99560 199319 99468 199320 99560 199320 99470 199320 99470 199321 99560 199321 101529 199321 99470 199322 101529 199322 99561 199322 99561 199323 101529 199323 99562 199323 101844 199324 99472 199324 101843 199324 101843 199325 99472 199325 99561 199325 101843 199326 99561 199326 101841 199326 101841 199327 99561 199327 99562 199327 101844 199328 101845 199328 99472 199328 99472 199329 101845 199329 99563 199329 99472 199330 99563 199330 99564 199330 99564 199331 99563 199331 101847 199331 99564 199332 101847 199332 99268 199332 99269 199333 99272 199333 101527 199333 101527 199334 99272 199334 99274 199334 99565 199335 99567 199335 99566 199335 99566 199336 99567 199336 101527 199336 99566 199337 101527 199337 99568 199337 99568 199338 101527 199338 99274 199338 99565 199339 99569 199339 99567 199339 99567 199340 99569 199340 99276 199340 99567 199341 99276 199341 99562 199341 99562 199342 99276 199342 101840 199342 99562 199343 101840 199343 101841 199343 99268 199344 99269 199344 99564 199344 99564 199345 99269 199345 101527 199345 99564 199346 101527 199346 99570 199346 99570 199347 101527 199347 101526 199347 99570 199348 101526 199348 99475 199348 99475 199349 101526 199349 101525 199349 99475 199350 101525 199350 99477 199350 99477 199351 101525 199351 101523 199351 99477 199352 101523 199352 99571 199352 99571 199353 101523 199353 99572 199353 99571 199354 99572 199354 99573 199354 99573 199355 99572 199355 99574 199355 99573 199356 99574 199356 99582 199356 99582 199357 99574 199357 99575 199357 99575 199358 99576 199358 99577 199358 99577 199359 99578 199359 99575 199359 99575 199360 99578 199360 101835 199360 99575 199361 101835 199361 99582 199361 99582 199362 101835 199362 99579 199362 99582 199363 99579 199363 99580 199363 99580 199364 99581 199364 99582 199364 99582 199365 99581 199365 99583 199365 99582 199366 99583 199366 99584 199366 99584 199367 99583 199367 101837 199367 99584 199368 101837 199368 101838 199368 99278 199369 99280 199369 101519 199369 101519 199370 99280 199370 101520 199370 99280 199371 99282 199371 101520 199371 101520 199372 99282 199372 99585 199372 101520 199373 99585 199373 99575 199373 99575 199374 99585 199374 99285 199374 99575 199375 99285 199375 99576 199375 101838 199376 99586 199376 99584 199376 99584 199377 99586 199377 99278 199377 99584 199378 99278 199378 99587 199378 99587 199379 99278 199379 101519 199379 99587 199380 101519 199380 99483 199380 99483 199381 101519 199381 101517 199381 99483 199382 101517 199382 99588 199382 99588 199383 101517 199383 99589 199383 99588 199384 99589 199384 99590 199384 99590 199385 99589 199385 99591 199385 99590 199386 99591 199386 99485 199386 99485 199387 99591 199387 99592 199387 99292 199388 99293 199388 99592 199388 99592 199389 99293 199389 99295 199389 99592 199390 99295 199390 99485 199390 99485 199391 99295 199391 99593 199391 99485 199392 99593 199392 101831 199392 99602 199393 99598 199393 99603 199393 101831 199394 99594 199394 99485 199394 99485 199395 99594 199395 99595 199395 99485 199396 99595 199396 99487 199396 99487 199397 99595 199397 99596 199397 99487 199398 99596 199398 99489 199398 99489 199399 99596 199399 101833 199399 99603 199400 99598 199400 99597 199400 99597 199401 99598 199401 99599 199401 99597 199402 99599 199402 99288 199402 99288 199403 99600 199403 99597 199403 99597 199404 99600 199404 99601 199404 99597 199405 99601 199405 99592 199405 99592 199406 99601 199406 99290 199406 99592 199407 99290 199407 99292 199407 101833 199408 99602 199408 99489 199408 99489 199409 99602 199409 99603 199409 99489 199410 99603 199410 99490 199410 99490 199411 99603 199411 99604 199411 99490 199412 99604 199412 99492 199412 99492 199413 99604 199413 99605 199413 99492 199414 99605 199414 99606 199414 99606 199415 99605 199415 101510 199415 99606 199416 101510 199416 99610 199416 99610 199417 101510 199417 99618 199417 99618 199418 99300 199418 99301 199418 99607 199419 99608 199419 99496 199419 99618 199420 99301 199420 99610 199420 99610 199421 99301 199421 99609 199421 99610 199422 99609 199422 99495 199422 99495 199423 99609 199423 99611 199423 99495 199424 99611 199424 101822 199424 101822 199425 101824 199425 99495 199425 99495 199426 101824 199426 101825 199426 99495 199427 101825 199427 99496 199427 99496 199428 101825 199428 101826 199428 99496 199429 101826 199429 99607 199429 101828 199430 99612 199430 99613 199430 99613 199431 99612 199431 99614 199431 99613 199432 99614 199432 99615 199432 99615 199433 99614 199433 99616 199433 99615 199434 99616 199434 99296 199434 99296 199435 99617 199435 99615 199435 99615 199436 99617 199436 99298 199436 99615 199437 99298 199437 99618 199437 99618 199438 99298 199438 99299 199438 99618 199439 99299 199439 99300 199439 99608 199440 101828 199440 99496 199440 99496 199441 101828 199441 99613 199441 99496 199442 99613 199442 99619 199442 99619 199443 99613 199443 101538 199443 99619 199444 101538 199444 99498 199444 99498 199445 101538 199445 101540 199445 99498 199446 101540 199446 99620 199446 99620 199447 101540 199447 101541 199447 99620 199448 101541 199448 99621 199448 99621 199449 101541 199449 101543 199449 99621 199450 101543 199450 99500 199450 99500 199451 101543 199451 99534 199451 99500 199452 99534 199452 99308 199452 101370 199453 101371 199453 99358 199453 99358 199454 101371 199454 101199 199454 99358 199455 101199 199455 99622 199455 99622 199456 101199 199456 99623 199456 99622 199457 99623 199457 99624 199457 99624 199458 99623 199458 101213 199458 99624 199459 101213 199459 99354 199459 99354 199460 101213 199460 101212 199460 99354 199461 101212 199461 99353 199461 99353 199462 101212 199462 99625 199462 99353 199463 99625 199463 99626 199463 99626 199464 99625 199464 101211 199464 99626 199465 101211 199465 99627 199465 99627 199466 101211 199466 101204 199466 99627 199467 101204 199467 99350 199467 99350 199468 101204 199468 99628 199468 99350 199469 99628 199469 99629 199469 99629 199470 99628 199470 101203 199470 99629 199471 101203 199471 99348 199471 99348 199472 101203 199472 101202 199472 99348 199473 101202 199473 99345 199473 99345 199474 101202 199474 101201 199474 99345 199475 101201 199475 99343 199475 99343 199476 101201 199476 99630 199476 99343 199477 99630 199477 99631 199477 99631 199478 99630 199478 99632 199478 99631 199479 99632 199479 99633 199479 99633 199480 99632 199480 101200 199480 99633 199481 101200 199481 101768 199481 101768 199482 101200 199482 101206 199482 99638 199483 100263 199483 99637 199483 99634 199484 100263 199484 99638 199484 100262 199485 99634 199485 99638 199485 99638 199486 99636 199486 100260 199486 99635 199487 99636 199487 99638 199487 99637 199488 99635 199488 99638 199488 99641 199489 100247 199489 99639 199489 99640 199490 100247 199490 99641 199490 101181 199491 99640 199491 99641 199491 99641 199492 100271 199492 100270 199492 100272 199493 100271 199493 99641 199493 99639 199494 100272 199494 99641 199494 99644 199495 99642 199495 100254 199495 99643 199496 99642 199496 99644 199496 100276 199497 99643 199497 99644 199497 99644 199498 99645 199498 100274 199498 100253 199499 99645 199499 99644 199499 100254 199500 100253 199500 99644 199500 99647 199501 100251 199501 100266 199501 99646 199502 100251 199502 99647 199502 100250 199503 99646 199503 99647 199503 99647 199504 100259 199504 101176 199504 100268 199505 100259 199505 99647 199505 100266 199506 100268 199506 99647 199506 99665 199507 99664 199507 100283 199507 99665 199508 100283 199508 104301 199508 104301 199509 100283 199509 99648 199509 104301 199510 99648 199510 104299 199510 104299 199511 99648 199511 100281 199511 104299 199512 100281 199512 99649 199512 99649 199513 100281 199513 99650 199513 99649 199514 99650 199514 104297 199514 104297 199515 99650 199515 100279 199515 104297 199516 100279 199516 104296 199516 104321 199517 100060 199517 100059 199517 104321 199518 100059 199518 104319 199518 104319 199519 100059 199519 100057 199519 104319 199520 100057 199520 99651 199520 99651 199521 100057 199521 100056 199521 99651 199522 100056 199522 104316 199522 104316 199523 100056 199523 100055 199523 104316 199524 100055 199524 104315 199524 104315 199525 100055 199525 99652 199525 104315 199526 99652 199526 99653 199526 99653 199527 99652 199527 99654 199527 99653 199528 99654 199528 104310 199528 104310 199529 99654 199529 99655 199529 104310 199530 99655 199530 104308 199530 104308 199531 99655 199531 100051 199531 104308 199532 100051 199532 104307 199532 104307 199533 100051 199533 100050 199533 104307 199534 100050 199534 99656 199534 99656 199535 100050 199535 100048 199535 99656 199536 100048 199536 99658 199536 99658 199537 100048 199537 99657 199537 99658 199538 99657 199538 99659 199538 99659 199539 99657 199539 100046 199539 99659 199540 100046 199540 104306 199540 104306 199541 100046 199541 99660 199541 104306 199542 99660 199542 99662 199542 99662 199543 99660 199543 99661 199543 99662 199544 99661 199544 104304 199544 104304 199545 99661 199545 99663 199545 104304 199546 99663 199546 104302 199546 104302 199547 99663 199547 99664 199547 104302 199548 99664 199548 99665 199548 100134 199549 101108 199549 100897 199549 100134 199550 100897 199550 99666 199550 99666 199551 100897 199551 99668 199551 99666 199552 99668 199552 99667 199552 99667 199553 99668 199553 99669 199553 99667 199554 99669 199554 100153 199554 99669 199555 99670 199555 100153 199555 100153 199556 99670 199556 99671 199556 100153 199557 99671 199557 100152 199557 100152 199558 99671 199558 100284 199558 100152 199559 100284 199559 100159 199559 100159 199560 100284 199560 100286 199560 100159 199561 100286 199561 100285 199561 100161 199562 99672 199562 99673 199562 100161 199563 99673 199563 99674 199563 99674 199564 99673 199564 99675 199564 99674 199565 99675 199565 99676 199565 99676 199566 99675 199566 100043 199566 99676 199567 100043 199567 99678 199567 99678 199568 100043 199568 99677 199568 99678 199569 99677 199569 100148 199569 100148 199570 99677 199570 99679 199570 100148 199571 99679 199571 101095 199571 99680 199572 100206 199572 100045 199572 100045 199573 100206 199573 99681 199573 100045 199574 99681 199574 99682 199574 99682 199575 99681 199575 100208 199575 99682 199576 100208 199576 100044 199576 100049 199577 100196 199577 100047 199577 100047 199578 100196 199578 99683 199578 100047 199579 99683 199579 99685 199579 99685 199580 99683 199580 99684 199580 99685 199581 99684 199581 99680 199581 99680 199582 99684 199582 100204 199582 99680 199583 100204 199583 100206 199583 100054 199584 99686 199584 100053 199584 100053 199585 99686 199585 99687 199585 100053 199586 99687 199586 100052 199586 100052 199587 99687 199587 100186 199587 100052 199588 100186 199588 99688 199588 99688 199589 100186 199589 99689 199589 99688 199590 99689 199590 100049 199590 100049 199591 99689 199591 99690 199591 100049 199592 99690 199592 100196 199592 99693 199593 100173 199593 99691 199593 99691 199594 100173 199594 100174 199594 99691 199595 100174 199595 99692 199595 99692 199596 100174 199596 100172 199596 99692 199597 100172 199597 100054 199597 100054 199598 100172 199598 100171 199598 100054 199599 100171 199599 99686 199599 99694 199600 100167 199600 99693 199600 99693 199601 100167 199601 100168 199601 99693 199602 100168 199602 100173 199602 99693 199603 100058 199603 99694 199603 99694 199604 100058 199604 99695 199604 99694 199605 99695 199605 99696 199605 99696 199606 99695 199606 99672 199606 99696 199607 99672 199607 100161 199607 100452 199608 101057 199608 99697 199608 99697 199609 101057 199609 100454 199609 99702 199610 99698 199610 99704 199610 99704 199611 99698 199611 100408 199611 99704 199612 100408 199612 99699 199612 99699 199613 100408 199613 100407 199613 99699 199614 100407 199614 99706 199614 99706 199615 100407 199615 100405 199615 99706 199616 100405 199616 99707 199616 99707 199617 100405 199617 99700 199617 99707 199618 99700 199618 99709 199618 99709 199619 99700 199619 100414 199619 99709 199620 100414 199620 101031 199620 101031 199621 100414 199621 100416 199621 99701 199622 99702 199622 99703 199622 99703 199623 99702 199623 99704 199623 99703 199624 99704 199624 99711 199624 99711 199625 99704 199625 99699 199625 99711 199626 99699 199626 99710 199626 99710 199627 99699 199627 99706 199627 99710 199628 99706 199628 99705 199628 99705 199629 99706 199629 99707 199629 99705 199630 99707 199630 99708 199630 99708 199631 99707 199631 99709 199631 99708 199632 99709 199632 101030 199632 101030 199633 99709 199633 101031 199633 101028 199634 99711 199634 99710 199634 99703 199635 99711 199635 101028 199635 99701 199636 99703 199636 101028 199636 101028 199637 99708 199637 101030 199637 99705 199638 99708 199638 101028 199638 99710 199639 99705 199639 101028 199639 101027 199640 99712 199640 99713 199640 99713 199641 99712 199641 100437 199641 99713 199642 100437 199642 99714 199642 99714 199643 100437 199643 100438 199643 99714 199644 100438 199644 99715 199644 99715 199645 100438 199645 100429 199645 99715 199646 100429 199646 99716 199646 99716 199647 100429 199647 99717 199647 99716 199648 99717 199648 99719 199648 99719 199649 99717 199649 99718 199649 99719 199650 99718 199650 99726 199650 99726 199651 99718 199651 99720 199651 99726 199652 99720 199652 99721 199652 99721 199653 99720 199653 99722 199653 101018 199654 101027 199654 99727 199654 99727 199655 101027 199655 99713 199655 99727 199656 99713 199656 99723 199656 99723 199657 99713 199657 99714 199657 99723 199658 99714 199658 99729 199658 99729 199659 99714 199659 99715 199659 99729 199660 99715 199660 99728 199660 99728 199661 99715 199661 99716 199661 99728 199662 99716 199662 99724 199662 99724 199663 99716 199663 99719 199663 99724 199664 99719 199664 99725 199664 99725 199665 99719 199665 99726 199665 99725 199666 99726 199666 101016 199666 101016 199667 99726 199667 99721 199667 99730 199668 101018 199668 99727 199668 99730 199669 99729 199669 99728 199669 99723 199670 99729 199670 99730 199670 99727 199671 99723 199671 99730 199671 99730 199672 99725 199672 101016 199672 99724 199673 99725 199673 99730 199673 99728 199674 99724 199674 99730 199674 99731 199675 100410 199675 101001 199675 101001 199676 99748 199676 99731 199676 99731 199677 99748 199677 99749 199677 99731 199678 99749 199678 99733 199678 99749 199679 99732 199679 99733 199679 99733 199680 99732 199680 99735 199680 99733 199681 99735 199681 99734 199681 99735 199682 99736 199682 99734 199682 99734 199683 99736 199683 99737 199683 99734 199684 99737 199684 99739 199684 99739 199685 99737 199685 99738 199685 99739 199686 99738 199686 100417 199686 99738 199687 99740 199687 100417 199687 100417 199688 99740 199688 99741 199688 100417 199689 99741 199689 99745 199689 99742 199690 101013 199690 99743 199690 99743 199691 101013 199691 99745 199691 99743 199692 99745 199692 99744 199692 99744 199693 99745 199693 99741 199693 99742 199694 99743 199694 99746 199694 99746 199695 99743 199695 99752 199695 99743 199696 99744 199696 99752 199696 99752 199697 99744 199697 99741 199697 99752 199698 99741 199698 99750 199698 99741 199699 99740 199699 99750 199699 99750 199700 99740 199700 99738 199700 99750 199701 99738 199701 99751 199701 99738 199702 99737 199702 99751 199702 99751 199703 99737 199703 99736 199703 99751 199704 99736 199704 99754 199704 99736 199705 99735 199705 99754 199705 99754 199706 99735 199706 99732 199706 99754 199707 99732 199707 99753 199707 101001 199708 99747 199708 99748 199708 99748 199709 99747 199709 99753 199709 99748 199710 99753 199710 99749 199710 99749 199711 99753 199711 99732 199711 99755 199712 99750 199712 99751 199712 99752 199713 99750 199713 99755 199713 99746 199714 99752 199714 99755 199714 99755 199715 99753 199715 99747 199715 99754 199716 99753 199716 99755 199716 99751 199717 99754 199717 99755 199717 99817 199718 99813 199718 99816 199718 99816 199719 99813 199719 99783 199719 100115 199720 99756 199720 99805 199720 99805 199721 99756 199721 99779 199721 99757 199722 99820 199722 99818 199722 99766 199723 99806 199723 99807 199723 99792 199724 99759 199724 99793 199724 99822 199725 100968 199725 100969 199725 99819 199726 99822 199726 99823 199726 99758 199727 100368 199727 99768 199727 100386 199728 99762 199728 99776 199728 100376 199729 100375 199729 99787 199729 100386 199730 99759 199730 100387 199730 100387 199731 99759 199731 99792 199731 100387 199732 99792 199732 99760 199732 99776 199733 99762 199733 99761 199733 99761 199734 99762 199734 99763 199734 99761 199735 99763 199735 99777 199735 99777 199736 99763 199736 100374 199736 99777 199737 100374 199737 99764 199737 99764 199738 100374 199738 100373 199738 99764 199739 100373 199739 99804 199739 99758 199740 99806 199740 99765 199740 99765 199741 99806 199741 99766 199741 99765 199742 99766 199742 99767 199742 99768 199743 100368 199743 99781 199743 99781 199744 100368 199744 99769 199744 99781 199745 99769 199745 99782 199745 99782 199746 99769 199746 100396 199746 99782 199747 100396 199747 99770 199747 99770 199748 100396 199748 100395 199748 99770 199749 100395 199749 99784 199749 99819 199750 99820 199750 100399 199750 100399 199751 99820 199751 99757 199751 100399 199752 99757 199752 100401 199752 99774 199753 99771 199753 99772 199753 100375 199754 100388 199754 99772 199754 99772 199755 100388 199755 99773 199755 99772 199756 99773 199756 99774 199756 99774 199757 99773 199757 99791 199757 99774 199758 99791 199758 99775 199758 99775 199759 99791 199759 100124 199759 99795 199760 99776 199760 99799 199760 99799 199761 99776 199761 99761 199761 99799 199762 99761 199762 99798 199762 99798 199763 99761 199763 99777 199763 99798 199764 99777 199764 99778 199764 99778 199765 99777 199765 99764 199765 99778 199766 99764 199766 99779 199766 99779 199767 99764 199767 99804 199767 99779 199768 99804 199768 99805 199768 99780 199769 99768 199769 99810 199769 99810 199770 99768 199770 99781 199770 99810 199771 99781 199771 99809 199771 99809 199772 99781 199772 99782 199772 99809 199773 99782 199773 99808 199773 99808 199774 99782 199774 99770 199774 99808 199775 99770 199775 99783 199775 99783 199776 99770 199776 99784 199776 99783 199777 99784 199777 99816 199777 100376 199778 99787 199778 99785 199778 99785 199779 99787 199779 99788 199779 99785 199780 99788 199780 99786 199780 99786 199781 99788 199781 100129 199781 99786 199782 100129 199782 100061 199782 100375 199783 99772 199783 99787 199783 99787 199784 99772 199784 99771 199784 99787 199785 99771 199785 99788 199785 99788 199786 99771 199786 99789 199786 99788 199787 99789 199787 100129 199787 99775 199788 99790 199788 99774 199788 99774 199789 99790 199789 100125 199789 99774 199790 100125 199790 99771 199790 99771 199791 100125 199791 100126 199791 99771 199792 100126 199792 99789 199792 100388 199793 99760 199793 99773 199793 99773 199794 99760 199794 99792 199794 99773 199795 99792 199795 99791 199795 99791 199796 99792 199796 99793 199796 99791 199797 99793 199797 100124 199797 100124 199798 99793 199798 99794 199798 100386 199799 99776 199799 99759 199799 99759 199800 99776 199800 99795 199800 99759 199801 99795 199801 99793 199801 99793 199802 99795 199802 100121 199802 99793 199803 100121 199803 99794 199803 99778 199804 99796 199804 99798 199804 99798 199805 99796 199805 99797 199805 99798 199806 99797 199806 99799 199806 99799 199807 99797 199807 99800 199807 99799 199808 99800 199808 99795 199808 99795 199809 99800 199809 100120 199809 99795 199810 100120 199810 100121 199810 99756 199811 99801 199811 99779 199811 99779 199812 99801 199812 99802 199812 99779 199813 99802 199813 99778 199813 99778 199814 99802 199814 99803 199814 99778 199815 99803 199815 99796 199815 100373 199816 99767 199816 99804 199816 99804 199817 99767 199817 99766 199817 99804 199818 99766 199818 99805 199818 99805 199819 99766 199819 99807 199819 99805 199820 99807 199820 100115 199820 100115 199821 99807 199821 100116 199821 99758 199822 99768 199822 99806 199822 99806 199823 99768 199823 99780 199823 99806 199824 99780 199824 99807 199824 99807 199825 99780 199825 100117 199825 99807 199826 100117 199826 100116 199826 99808 199827 100113 199827 99809 199827 99809 199828 100113 199828 100111 199828 99809 199829 100111 199829 99810 199829 99810 199830 100111 199830 99811 199830 99810 199831 99811 199831 99780 199831 99780 199832 99811 199832 99812 199832 99780 199833 99812 199833 100117 199833 99813 199834 99814 199834 99783 199834 99783 199835 99814 199835 100110 199835 99783 199836 100110 199836 99808 199836 99808 199837 100110 199837 99815 199837 99808 199838 99815 199838 100113 199838 100395 199839 100401 199839 99784 199839 99784 199840 100401 199840 99757 199840 99784 199841 99757 199841 99816 199841 99816 199842 99757 199842 99818 199842 99816 199843 99818 199843 99817 199843 99817 199844 99818 199844 100108 199844 99824 199845 100107 199845 99821 199845 99819 199846 99823 199846 99820 199846 99820 199847 99823 199847 99824 199847 99820 199848 99824 199848 99818 199848 99818 199849 99824 199849 99821 199849 99818 199850 99821 199850 100108 199850 99822 199851 100969 199851 99823 199851 99823 199852 100969 199852 99825 199852 99823 199853 99825 199853 99824 199853 99824 199854 99825 199854 99826 199854 99824 199855 99826 199855 100107 199855 100932 199856 99827 199856 100029 199856 100932 199857 100029 199857 99828 199857 99828 199858 100029 199858 100028 199858 99828 199859 100028 199859 99829 199859 99829 199860 100028 199860 99830 199860 99829 199861 99830 199861 100397 199861 100397 199862 99830 199862 99831 199862 100397 199863 99831 199863 99832 199863 99832 199864 99831 199864 100026 199864 99832 199865 100026 199865 99833 199865 99833 199866 100026 199866 99834 199866 99833 199867 99834 199867 99835 199867 99835 199868 99834 199868 99836 199868 99835 199869 99836 199869 100390 199869 100390 199870 99836 199870 100016 199870 100390 199871 100016 199871 100385 199871 100385 199872 100016 199872 100011 199872 100385 199873 100011 199873 100384 199873 100384 199874 100011 199874 100033 199874 100384 199875 100033 199875 99837 199875 99837 199876 100033 199876 99839 199876 99837 199877 99839 199877 99838 199877 99838 199878 99839 199878 99840 199878 99838 199879 99840 199879 99841 199879 99841 199880 99840 199880 100036 199880 99841 199881 100036 199881 99842 199881 99842 199882 100036 199882 99843 199882 99842 199883 99843 199883 100378 199883 100378 199884 99843 199884 99844 199884 100378 199885 99844 199885 100917 199885 99845 199886 100908 199886 99846 199886 99846 199887 100908 199887 100458 199887 99847 199888 100211 199888 99848 199888 99848 199889 100211 199889 100131 199889 99848 199890 100131 199890 99857 199890 99857 199891 100131 199891 100216 199891 99857 199892 100216 199892 99849 199892 99849 199893 100216 199893 99850 199893 99849 199894 99850 199894 99860 199894 99860 199895 99850 199895 99851 199895 99860 199896 99851 199896 99852 199896 99852 199897 99851 199897 99853 199897 99852 199898 99853 199898 100849 199898 100849 199899 99853 199899 100221 199899 99854 199900 99847 199900 99855 199900 99855 199901 99847 199901 99848 199901 99855 199902 99848 199902 99856 199902 99856 199903 99848 199903 99857 199903 99856 199904 99857 199904 99858 199904 99858 199905 99857 199905 99849 199905 99858 199906 99849 199906 99859 199906 99859 199907 99849 199907 99860 199907 99859 199908 99860 199908 99861 199908 99861 199909 99860 199909 99852 199909 99861 199910 99852 199910 100848 199910 100848 199911 99852 199911 100849 199911 100848 199912 100847 199912 99861 199912 99861 199913 100847 199913 104338 199913 99861 199914 104338 199914 99859 199914 99859 199915 104338 199915 99862 199915 99859 199916 99862 199916 99858 199916 99858 199917 99862 199917 104337 199917 99858 199918 104337 199918 99856 199918 99856 199919 104337 199919 104334 199919 99856 199920 104334 199920 99855 199920 99855 199921 104334 199921 99863 199921 99855 199922 99863 199922 99854 199922 99854 199923 99863 199923 104345 199923 99869 199924 100843 199924 99871 199924 99871 199925 100843 199925 99864 199925 99871 199926 99864 199926 99865 199926 99865 199927 99864 199927 100203 199927 99865 199928 100203 199928 99866 199928 99866 199929 100203 199929 99867 199929 99866 199930 99867 199930 99872 199930 99872 199931 99867 199931 100205 199931 99872 199932 100205 199932 99874 199932 99874 199933 100205 199933 100202 199933 99874 199934 100202 199934 99868 199934 99868 199935 100202 199935 100838 199935 100837 199936 99869 199936 99870 199936 99870 199937 99869 199937 99871 199937 99870 199938 99871 199938 99879 199938 99879 199939 99871 199939 99865 199939 99879 199940 99865 199940 99877 199940 99877 199941 99865 199941 99866 199941 99877 199942 99866 199942 99876 199942 99876 199943 99866 199943 99872 199943 99876 199944 99872 199944 99873 199944 99873 199945 99872 199945 99874 199945 99873 199946 99874 199946 99875 199946 99875 199947 99874 199947 99868 199947 99875 199948 104369 199948 99873 199948 99873 199949 104369 199949 104368 199949 99873 199950 104368 199950 99876 199950 99876 199951 104368 199951 99878 199951 99876 199952 99878 199952 99877 199952 99877 199953 99878 199953 104365 199953 99877 199954 104365 199954 99879 199954 99879 199955 104365 199955 104363 199955 99879 199956 104363 199956 99870 199956 99870 199957 104363 199957 99880 199957 99870 199958 99880 199958 100837 199958 100837 199959 99880 199959 100826 199959 100816 199960 100193 199960 99884 199960 99884 199961 100193 199961 100192 199961 99884 199962 100192 199962 99881 199962 99881 199963 100192 199963 100191 199963 99881 199964 100191 199964 99885 199964 99885 199965 100191 199965 100195 199965 99885 199966 100195 199966 99886 199966 99886 199967 100195 199967 100197 199967 99886 199968 100197 199968 99888 199968 99888 199969 100197 199969 100198 199969 99888 199970 100198 199970 100808 199970 100808 199971 100198 199971 100818 199971 100814 199972 100816 199972 99882 199972 99882 199973 100816 199973 99884 199973 99882 199974 99884 199974 99883 199974 99883 199975 99884 199975 99881 199975 99883 199976 99881 199976 99891 199976 99891 199977 99881 199977 99885 199977 99891 199978 99885 199978 99890 199978 99890 199979 99885 199979 99886 199979 99890 199980 99886 199980 99887 199980 99887 199981 99886 199981 99888 199981 99887 199982 99888 199982 100805 199982 100805 199983 99888 199983 100808 199983 100805 199984 100807 199984 99887 199984 99887 199985 100807 199985 99889 199985 99887 199986 99889 199986 99890 199986 99890 199987 99889 199987 104383 199987 99890 199988 104383 199988 99891 199988 99891 199989 104383 199989 104382 199989 99891 199990 104382 199990 99883 199990 99883 199991 104382 199991 104390 199991 99883 199992 104390 199992 99882 199992 99882 199993 104390 199993 104389 199993 99882 199994 104389 199994 100814 199994 100814 199995 104389 199995 99892 199995 100801 199996 100187 199996 99893 199996 99893 199997 100187 199997 99895 199997 99893 199998 99895 199998 99894 199998 99894 199999 99895 199999 99896 199999 99894 200000 99896 200000 99897 200000 99897 200001 99896 200001 100185 200001 99897 200002 100185 200002 99898 200002 99898 200003 100185 200003 100184 200003 99898 200004 100184 200004 99904 200004 99904 200005 100184 200005 99899 200005 99904 200006 99899 200006 99900 200006 99900 200007 99899 200007 100796 200007 100784 200008 100801 200008 99907 200008 99907 200009 100801 200009 99893 200009 99907 200010 99893 200010 99901 200010 99901 200011 99893 200011 99894 200011 99901 200012 99894 200012 99902 200012 99902 200013 99894 200013 99897 200013 99902 200014 99897 200014 99906 200014 99906 200015 99897 200015 99898 200015 99906 200016 99898 200016 99903 200016 99903 200017 99898 200017 99904 200017 99903 200018 99904 200018 99905 200018 99905 200019 99904 200019 99900 200019 99905 200020 100789 200020 99903 200020 99903 200021 100789 200021 104405 200021 99903 200022 104405 200022 99906 200022 99906 200023 104405 200023 104404 200023 99906 200024 104404 200024 99902 200024 99902 200025 104404 200025 104403 200025 99902 200026 104403 200026 99901 200026 99901 200027 104403 200027 99908 200027 99901 200028 99908 200028 99907 200028 99907 200029 99908 200029 99909 200029 99907 200030 99909 200030 100784 200030 100784 200031 99909 200031 104412 200031 100781 200032 100783 200032 99910 200032 99910 200033 100783 200033 100178 200033 99910 200034 100178 200034 99911 200034 99911 200035 100178 200035 100176 200035 99911 200036 100176 200036 99920 200036 99920 200037 100176 200037 100175 200037 99920 200038 100175 200038 99912 200038 99912 200039 100175 200039 99913 200039 99912 200040 99913 200040 99914 200040 99914 200041 99913 200041 99915 200041 99914 200042 99915 200042 99922 200042 99922 200043 99915 200043 99916 200043 99922 200044 99916 200044 100775 200044 100775 200045 99916 200045 99917 200045 100766 200046 100781 200046 99918 200046 99918 200047 100781 200047 99910 200047 99918 200048 99910 200048 99926 200048 99926 200049 99910 200049 99911 200049 99926 200050 99911 200050 99919 200050 99919 200051 99911 200051 99920 200051 99919 200052 99920 200052 99925 200052 99925 200053 99920 200053 99912 200053 99925 200054 99912 200054 99924 200054 99924 200055 99912 200055 99914 200055 99924 200056 99914 200056 99921 200056 99921 200057 99914 200057 99922 200057 99921 200058 99922 200058 99923 200058 99923 200059 99922 200059 100775 200059 99923 200060 104433 200060 99921 200060 99921 200061 104433 200061 104432 200061 99921 200062 104432 200062 99924 200062 99924 200063 104432 200063 104430 200063 99924 200064 104430 200064 99925 200064 99925 200065 104430 200065 104429 200065 99925 200066 104429 200066 99919 200066 99919 200067 104429 200067 104428 200067 99919 200068 104428 200068 99926 200068 99926 200069 104428 200069 104427 200069 99926 200070 104427 200070 99918 200070 99918 200071 104427 200071 104425 200071 99918 200072 104425 200072 100766 200072 100766 200073 104425 200073 104440 200073 99932 200074 99927 200074 99933 200074 99933 200075 99927 200075 99928 200075 99933 200076 99928 200076 99934 200076 99934 200077 99928 200077 100162 200077 99934 200078 100162 200078 99936 200078 99936 200079 100162 200079 99929 200079 99936 200080 99929 200080 99937 200080 99937 200081 99929 200081 99930 200081 99937 200082 99930 200082 99938 200082 99938 200083 99930 200083 99931 200083 99938 200084 99931 200084 100760 200084 100760 200085 99931 200085 100761 200085 99944 200086 99932 200086 99943 200086 99943 200087 99932 200087 99933 200087 99943 200088 99933 200088 99942 200088 99942 200089 99933 200089 99934 200089 99942 200090 99934 200090 99935 200090 99935 200091 99934 200091 99936 200091 99935 200092 99936 200092 99941 200092 99941 200093 99936 200093 99937 200093 99941 200094 99937 200094 99939 200094 99939 200095 99937 200095 99938 200095 99939 200096 99938 200096 100752 200096 100752 200097 99938 200097 100760 200097 100752 200098 100754 200098 99939 200098 99939 200099 100754 200099 99940 200099 99939 200100 99940 200100 99941 200100 99941 200101 99940 200101 104455 200101 99941 200102 104455 200102 99935 200102 99935 200103 104455 200103 104452 200103 99935 200104 104452 200104 99942 200104 99942 200105 104452 200105 104451 200105 99942 200106 104451 200106 99943 200106 99943 200107 104451 200107 104463 200107 99943 200108 104463 200108 99944 200108 99944 200109 104463 200109 104460 200109 100745 200110 100154 200110 99945 200110 99945 200111 100154 200111 99946 200111 99945 200112 99946 200112 99953 200112 99953 200113 99946 200113 99947 200113 99953 200114 99947 200114 99948 200114 99948 200115 99947 200115 99949 200115 99948 200116 99949 200116 99955 200116 99955 200117 99949 200117 100150 200117 99955 200118 100150 200118 99957 200118 99957 200119 100150 200119 100151 200119 99957 200120 100151 200120 99950 200120 99950 200121 100151 200121 99951 200121 100738 200122 100745 200122 99962 200122 99962 200123 100745 200123 99945 200123 99962 200124 99945 200124 99952 200124 99952 200125 99945 200125 99953 200125 99952 200126 99953 200126 99954 200126 99954 200127 99953 200127 99948 200127 99954 200128 99948 200128 99960 200128 99960 200129 99948 200129 99955 200129 99960 200130 99955 200130 99958 200130 99958 200131 99955 200131 99957 200131 99958 200132 99957 200132 99956 200132 99956 200133 99957 200133 99950 200133 99956 200134 100730 200134 99958 200134 99958 200135 100730 200135 99959 200135 99958 200136 99959 200136 99960 200136 99960 200137 99959 200137 104479 200137 99960 200138 104479 200138 99954 200138 99954 200139 104479 200139 99961 200139 99954 200140 99961 200140 99952 200140 99952 200141 99961 200141 104478 200141 99952 200142 104478 200142 99962 200142 99962 200143 104478 200143 104477 200143 99962 200144 104477 200144 100738 200144 100738 200145 104477 200145 100728 200145 100727 200146 99963 200146 99964 200146 99964 200147 99963 200147 99965 200147 99964 200148 99965 200148 99966 200148 99966 200149 99965 200149 99967 200149 99966 200150 99967 200150 99968 200150 99968 200151 99967 200151 99969 200151 99968 200152 99969 200152 99970 200152 99970 200153 99969 200153 100140 200153 99970 200154 100140 200154 99971 200154 99971 200155 100140 200155 100135 200155 99971 200156 100135 200156 100721 200156 100721 200157 100135 200157 100722 200157 100720 200158 100727 200158 99977 200158 99977 200159 100727 200159 99964 200159 99977 200160 99964 200160 99972 200160 99972 200161 99964 200161 99966 200161 99972 200162 99966 200162 99975 200162 99975 200163 99966 200163 99968 200163 99975 200164 99968 200164 99973 200164 99973 200165 99968 200165 99970 200165 99973 200166 99970 200166 99974 200166 99974 200167 99970 200167 99971 200167 99974 200168 99971 200168 100711 200168 100711 200169 99971 200169 100721 200169 100711 200170 104510 200170 99974 200170 99974 200171 104510 200171 104508 200171 99974 200172 104508 200172 99973 200172 99973 200173 104508 200173 104507 200173 99973 200174 104507 200174 99975 200174 99975 200175 104507 200175 99976 200175 99975 200176 99976 200176 99972 200176 99972 200177 99976 200177 104505 200177 99972 200178 104505 200178 99977 200178 99977 200179 104505 200179 104503 200179 99977 200180 104503 200180 100720 200180 100720 200181 104503 200181 99978 200181 100704 200182 100705 200182 99986 200182 99986 200183 100705 200183 99979 200183 99986 200184 99979 200184 99988 200184 99988 200185 99979 200185 99980 200185 99988 200186 99980 200186 99982 200186 99982 200187 99980 200187 99981 200187 99982 200188 99981 200188 99983 200188 99983 200189 99981 200189 100315 200189 99983 200190 100315 200190 99989 200190 99989 200191 100315 200191 99984 200191 99989 200192 99984 200192 100690 200192 100690 200193 99984 200193 99985 200193 100684 200194 100704 200194 99995 200194 99995 200195 100704 200195 99986 200195 99995 200196 99986 200196 99987 200196 99987 200197 99986 200197 99988 200197 99987 200198 99988 200198 99993 200198 99993 200199 99988 200199 99982 200199 99993 200200 99982 200200 99992 200200 99992 200201 99982 200201 99983 200201 99992 200202 99983 200202 99990 200202 99990 200203 99983 200203 99989 200203 99990 200204 99989 200204 100689 200204 100689 200205 99989 200205 100690 200205 100689 200206 104529 200206 99990 200206 99990 200207 104529 200207 99991 200207 99990 200208 99991 200208 99992 200208 99992 200209 99991 200209 99994 200209 99992 200210 99994 200210 99993 200210 99993 200211 99994 200211 104527 200211 99993 200212 104527 200212 99987 200212 99987 200213 104527 200213 104524 200213 99987 200214 104524 200214 99995 200214 99995 200215 104524 200215 104523 200215 99995 200216 104523 200216 100684 200216 100684 200217 104523 200217 104535 200217 100682 200218 99996 200218 100003 200218 100003 200219 99996 200219 100223 200219 100003 200220 100223 200220 99997 200220 99997 200221 100223 200221 100228 200221 99997 200222 100228 200222 99998 200222 99998 200223 100228 200223 100229 200223 99998 200224 100229 200224 100004 200224 100004 200225 100229 200225 99999 200225 100004 200226 99999 200226 100006 200226 100006 200227 99999 200227 100232 200227 100006 200228 100232 200228 100000 200228 100000 200229 100232 200229 100234 200229 100001 200230 100682 200230 100002 200230 100002 200231 100682 200231 100003 200231 100002 200232 100003 200232 100009 200232 100009 200233 100003 200233 99997 200233 100009 200234 99997 200234 100008 200234 100008 200235 99997 200235 99998 200235 100008 200236 99998 200236 100007 200236 100007 200237 99998 200237 100004 200237 100007 200238 100004 200238 100005 200238 100005 200239 100004 200239 100006 200239 100005 200240 100006 200240 100666 200240 100666 200241 100006 200241 100000 200241 100666 200242 100667 200242 100005 200242 100005 200243 100667 200243 104544 200243 100005 200244 104544 200244 100007 200244 100007 200245 104544 200245 104543 200245 100007 200246 104543 200246 100008 200246 100008 200247 104543 200247 104541 200247 100008 200248 104541 200248 100009 200248 100009 200249 104541 200249 104539 200249 100009 200250 104539 200250 100002 200250 100002 200251 104539 200251 100010 200251 100002 200252 100010 200252 100001 200252 100001 200253 100010 200253 100658 200253 101149 200254 101148 200254 100016 200254 100033 200255 100011 200255 100013 200255 100013 200256 100011 200256 101137 200256 100012 200257 101173 200257 100013 200257 100013 200258 101173 200258 101172 200258 100013 200259 101172 200259 100033 200259 101148 200260 100014 200260 100016 200260 100016 200261 100014 200261 100015 200261 100016 200262 100015 200262 100011 200262 100011 200263 100015 200263 101136 200263 100011 200264 101136 200264 101137 200264 100017 200265 99836 200265 100018 200265 100018 200266 99836 200266 99834 200266 100018 200267 99834 200267 100019 200267 101149 200268 100016 200268 100020 200268 100020 200269 100016 200269 99836 200269 100020 200270 99836 200270 101157 200270 101157 200271 99836 200271 100017 200271 101157 200272 100017 200272 100490 200272 100021 200273 100022 200273 100025 200273 100025 200274 100022 200274 100023 200274 100025 200275 100023 200275 100024 200275 100019 200276 99834 200276 100025 200276 100025 200277 99834 200277 100026 200277 100025 200278 100026 200278 100021 200278 100021 200279 100026 200279 99831 200279 100021 200280 99831 200280 100027 200280 100027 200281 99831 200281 99830 200281 100027 200282 99830 200282 100104 200282 100104 200283 99830 200283 100028 200283 100104 200284 100028 200284 100103 200284 100103 200285 100028 200285 100029 200285 100103 200286 100029 200286 100030 200286 100030 200287 100029 200287 99827 200287 100030 200288 99827 200288 100031 200288 101172 200289 100032 200289 100033 200289 100033 200290 100032 200290 100034 200290 100033 200291 100034 200291 99839 200291 99839 200292 100034 200292 100035 200292 99839 200293 100035 200293 99840 200293 99840 200294 100035 200294 100088 200294 99840 200295 100088 200295 100036 200295 100036 200296 100088 200296 100090 200296 100036 200297 100090 200297 99843 200297 99843 200298 100090 200298 100091 200298 99843 200299 100091 200299 99844 200299 101074 200300 101073 200300 100330 200300 101074 200301 100330 200301 101075 200301 101075 200302 100330 200302 100329 200302 101075 200303 100329 200303 100037 200303 100037 200304 100329 200304 100038 200304 100037 200305 100038 200305 100039 200305 100039 200306 100038 200306 100041 200306 100039 200307 100041 200307 100040 200307 100040 200308 100041 200308 100042 200308 100040 200309 100042 200309 101077 200309 99672 200310 100060 200310 101168 200310 99672 200311 101168 200311 99673 200311 99673 200312 101168 200312 101166 200312 99673 200313 101166 200313 99675 200313 99675 200314 101166 200314 101164 200314 99675 200315 101164 200315 100043 200315 100043 200316 101164 200316 101163 200316 100043 200317 101163 200317 99677 200317 99677 200318 101163 200318 101162 200318 99677 200319 101162 200319 99679 200319 100044 200320 99664 200320 99663 200320 100044 200321 99663 200321 99682 200321 99682 200322 99663 200322 99661 200322 99682 200323 99661 200323 100045 200323 100045 200324 99661 200324 99660 200324 100045 200325 99660 200325 99680 200325 99680 200326 99660 200326 100046 200326 99680 200327 100046 200327 99685 200327 99685 200328 100046 200328 99657 200328 99685 200329 99657 200329 100047 200329 100047 200330 99657 200330 100048 200330 100047 200331 100048 200331 100049 200331 100049 200332 100048 200332 100050 200332 100049 200333 100050 200333 99688 200333 99688 200334 100050 200334 100051 200334 99688 200335 100051 200335 100052 200335 100052 200336 100051 200336 99655 200336 100052 200337 99655 200337 100053 200337 100053 200338 99655 200338 99654 200338 100053 200339 99654 200339 100054 200339 100054 200340 99654 200340 99652 200340 100054 200341 99652 200341 99692 200341 99692 200342 99652 200342 100055 200342 99692 200343 100055 200343 99691 200343 99691 200344 100055 200344 100056 200344 99691 200345 100056 200345 99693 200345 99693 200346 100056 200346 100057 200346 99693 200347 100057 200347 100058 200347 100058 200348 100057 200348 100059 200348 100058 200349 100059 200349 99695 200349 99695 200350 100059 200350 100060 200350 99695 200351 100060 200351 99672 200351 100061 200352 100130 200352 100064 200352 100064 200353 100130 200353 100265 200353 100992 200354 100997 200354 100264 200354 100264 200355 100997 200355 100062 200355 100264 200356 100062 200356 100265 200356 100265 200357 100062 200357 100063 200357 100265 200358 100063 200358 100064 200358 100992 200359 100264 200359 100993 200359 100993 200360 100264 200360 100065 200360 100993 200361 100065 200361 100995 200361 100995 200362 100065 200362 100066 200362 100066 200363 100065 200363 100261 200363 100066 200364 100261 200364 100996 200364 100996 200365 100261 200365 100067 200365 100067 200366 100261 200366 100069 200366 100067 200367 100069 200367 100990 200367 100990 200368 100069 200368 100068 200368 100068 200369 100069 200369 100071 200369 100068 200370 100071 200370 100070 200370 100070 200371 100071 200371 100989 200371 100989 200372 100071 200372 100243 200372 100989 200373 100243 200373 100934 200373 100074 200374 100072 200374 100243 200374 100243 200375 100072 200375 100984 200375 100243 200376 100984 200376 100934 200376 100073 200377 100076 200377 100074 200377 100074 200378 100076 200378 100985 200378 100074 200379 100985 200379 100072 200379 100244 200380 100982 200380 100073 200380 100073 200381 100982 200381 100075 200381 100073 200382 100075 200382 100076 200382 100241 200383 100078 200383 100244 200383 100244 200384 100078 200384 100983 200384 100244 200385 100983 200385 100982 200385 100079 200386 100077 200386 100258 200386 100258 200387 100077 200387 100980 200387 100258 200388 100980 200388 100241 200388 100241 200389 100980 200389 100979 200389 100241 200390 100979 200390 100078 200390 100079 200391 100258 200391 100080 200391 100080 200392 100258 200392 100082 200392 100080 200393 100082 200393 100975 200393 100975 200394 100082 200394 100081 200394 100081 200395 100082 200395 100083 200395 100081 200396 100083 200396 100973 200396 100973 200397 100083 200397 100084 200397 100084 200398 100083 200398 100106 200398 100084 200399 100106 200399 99826 200399 101172 200400 104292 200400 100032 200400 100032 200401 104292 200401 100085 200401 100032 200402 100085 200402 100034 200402 100034 200403 100085 200403 100086 200403 100034 200404 100086 200404 100035 200404 100035 200405 100086 200405 100087 200405 100035 200406 100087 200406 100088 200406 100088 200407 100087 200407 100089 200407 100088 200408 100089 200408 100090 200408 100090 200409 100089 200409 101782 200409 100090 200410 101782 200410 100091 200410 100091 200411 101782 200411 99359 200411 100091 200412 99359 200412 100366 200412 100366 200413 99359 200413 99357 200413 100366 200414 99357 200414 100093 200414 100093 200415 99357 200415 100092 200415 100093 200416 100092 200416 100364 200416 100364 200417 100092 200417 99356 200417 100364 200418 99356 200418 100363 200418 100363 200419 99356 200419 99355 200419 100363 200420 99355 200420 100094 200420 100094 200421 99355 200421 99352 200421 100094 200422 99352 200422 100361 200422 100361 200423 99352 200423 100095 200423 100361 200424 100095 200424 100359 200424 100359 200425 100095 200425 100096 200425 100359 200426 100096 200426 100358 200426 100358 200427 100096 200427 99351 200427 100358 200428 99351 200428 100097 200428 100097 200429 99351 200429 99349 200429 100097 200430 99349 200430 100356 200430 100356 200431 99349 200431 99347 200431 100356 200432 99347 200432 100098 200432 100098 200433 99347 200433 99346 200433 100098 200434 99346 200434 100100 200434 100100 200435 99346 200435 100099 200435 100100 200436 100099 200436 100101 200436 100101 200437 100099 200437 99344 200437 100101 200438 99344 200438 100102 200438 100102 200439 99344 200439 99342 200439 100102 200440 99342 200440 100031 200440 100031 200441 99342 200441 101766 200441 100031 200442 101766 200442 100030 200442 100030 200443 101766 200443 101767 200443 100030 200444 101767 200444 100103 200444 100103 200445 101767 200445 101769 200445 100103 200446 101769 200446 100104 200446 100104 200447 101769 200447 100105 200447 100104 200448 100105 200448 100027 200448 100027 200449 100105 200449 101771 200449 100027 200450 101771 200450 100021 200450 100021 200451 101771 200451 101773 200451 100021 200452 101773 200452 100022 200452 100022 200453 101773 200453 101158 200453 101778 200454 101149 200454 104283 200454 104283 200455 101149 200455 100020 200455 99826 200456 100106 200456 100107 200456 100107 200457 100106 200457 100269 200457 100107 200458 100269 200458 99821 200458 99821 200459 100269 200459 100108 200459 100108 200460 100269 200460 100109 200460 100108 200461 100109 200461 99817 200461 100257 200462 99814 200462 100109 200462 100109 200463 99814 200463 99813 200463 100109 200464 99813 200464 99817 200464 100112 200465 99815 200465 100257 200465 100257 200466 99815 200466 100110 200466 100257 200467 100110 200467 99814 200467 100114 200468 100111 200468 100112 200468 100112 200469 100111 200469 100113 200469 100112 200470 100113 200470 99815 200470 100273 200471 99812 200471 100114 200471 100114 200472 99812 200472 99811 200472 100114 200473 99811 200473 100111 200473 99756 200474 100115 200474 100275 200474 100275 200475 100115 200475 100116 200475 100275 200476 100116 200476 100273 200476 100273 200477 100116 200477 100117 200477 100273 200478 100117 200478 99812 200478 99756 200479 100275 200479 99801 200479 99801 200480 100275 200480 100118 200480 99801 200481 100118 200481 99802 200481 99802 200482 100118 200482 99803 200482 99803 200483 100118 200483 100119 200483 99803 200484 100119 200484 99796 200484 99796 200485 100119 200485 99797 200485 99797 200486 100119 200486 100255 200486 99797 200487 100255 200487 99800 200487 99800 200488 100255 200488 100120 200488 100120 200489 100255 200489 100122 200489 100120 200490 100122 200490 100121 200490 100121 200491 100122 200491 99794 200491 99794 200492 100122 200492 100123 200492 99794 200493 100123 200493 100124 200493 100127 200494 100125 200494 99790 200494 100127 200495 99790 200495 100123 200495 100123 200496 99790 200496 99775 200496 100123 200497 99775 200497 100124 200497 100125 200498 100127 200498 100126 200498 100126 200499 100127 200499 100128 200499 100126 200500 100128 200500 99789 200500 99789 200501 100128 200501 100129 200501 100129 200502 100128 200502 100130 200502 100129 200503 100130 200503 100061 200503 100227 200504 100219 200504 100214 200504 100131 200505 100211 200505 101094 200505 99689 200506 100132 200506 99690 200506 99928 200507 99927 200507 101112 200507 101108 200508 100134 200508 100140 200508 99678 200509 100148 200509 100133 200509 100133 200510 100148 200510 100134 200510 100133 200511 100134 200511 99666 200511 100140 200512 100134 200512 100135 200512 100135 200513 100134 200513 100148 200513 100135 200514 100148 200514 100722 200514 100136 200515 99967 200515 99965 200515 99963 200516 100137 200516 99965 200516 99965 200517 100137 200517 101101 200517 99965 200518 101101 200518 100136 200518 100138 200519 100726 200519 100139 200519 100136 200520 101103 200520 99967 200520 99967 200521 101103 200521 101105 200521 99967 200522 101105 200522 99969 200522 99969 200523 101105 200523 101107 200523 99969 200524 101107 200524 100140 200524 100140 200525 101107 200525 101110 200525 100140 200526 101110 200526 101108 200526 100139 200527 100726 200527 100144 200527 100139 200528 100141 200528 100138 200528 100138 200529 100141 200529 100142 200529 100138 200530 100142 200530 99963 200530 99963 200531 100142 200531 100143 200531 99963 200532 100143 200532 100137 200532 100726 200533 100724 200533 100144 200533 100144 200534 100724 200534 100145 200534 100144 200535 100145 200535 101095 200535 101095 200536 100145 200536 100146 200536 101095 200537 100146 200537 100148 200537 100148 200538 100146 200538 100147 200538 100148 200539 100147 200539 100722 200539 100151 200540 99674 200540 99951 200540 99951 200541 99674 200541 99676 200541 99951 200542 99676 200542 100149 200542 100159 200543 100160 200543 99674 200543 99666 200544 99667 200544 100133 200544 100133 200545 99667 200545 100155 200545 100133 200546 100155 200546 99678 200546 99678 200547 100155 200547 100742 200547 99678 200548 100742 200548 99676 200548 99676 200549 100742 200549 100740 200549 99676 200550 100740 200550 100149 200550 100152 200551 100159 200551 99949 200551 99949 200552 100159 200552 99674 200552 99949 200553 99674 200553 100150 200553 100150 200554 99674 200554 100151 200554 99949 200555 99947 200555 100152 200555 100152 200556 99947 200556 99946 200556 100152 200557 99946 200557 100153 200557 100153 200558 99946 200558 100154 200558 100153 200559 100154 200559 99667 200559 99667 200560 100154 200560 100744 200560 99667 200561 100744 200561 100155 200561 100765 200562 100159 200562 100158 200562 100158 200563 100159 200563 101111 200563 100156 200564 100762 200564 99696 200564 99696 200565 100762 200565 100761 200565 99696 200566 100761 200566 99694 200566 101112 200567 99927 200567 101111 200567 101111 200568 99927 200568 100157 200568 101111 200569 100157 200569 100158 200569 100765 200570 100156 200570 100159 200570 100159 200571 100156 200571 99696 200571 100159 200572 99696 200572 100160 200572 100160 200573 99696 200573 100161 200573 100160 200574 100161 200574 99674 200574 100761 200575 99931 200575 99694 200575 99694 200576 99931 200576 99930 200576 99694 200577 99930 200577 100167 200577 99929 200578 100162 200578 100165 200578 99928 200579 101112 200579 100162 200579 100162 200580 101112 200580 101114 200580 100162 200581 101114 200581 100165 200581 100165 200582 101114 200582 101116 200582 100165 200583 101116 200583 101115 200583 101118 200584 100170 200584 100549 200584 100783 200585 100782 200585 100177 200585 100177 200586 100782 200586 100163 200586 100177 200587 100163 200587 100164 200587 100164 200588 100163 200588 100778 200588 100164 200589 100778 200589 100166 200589 100169 200590 100165 200590 100166 200590 100166 200591 100165 200591 101115 200591 100166 200592 101115 200592 100164 200592 99930 200593 99929 200593 100167 200593 100167 200594 99929 200594 100165 200594 100167 200595 100165 200595 100168 200595 100168 200596 100165 200596 100169 200596 100168 200597 100169 200597 100173 200597 100173 200598 100169 200598 99917 200598 100549 200599 100170 200599 100456 200599 100456 200600 100170 200600 101121 200600 100456 200601 101121 200601 100461 200601 100171 200602 100172 200602 100180 200602 100180 200603 100172 200603 100176 200603 100180 200604 100176 200604 100178 200604 99917 200605 99916 200605 100173 200605 100173 200606 99916 200606 99915 200606 100173 200607 99915 200607 100174 200607 100174 200608 99915 200608 99913 200608 100174 200609 99913 200609 100172 200609 100172 200610 99913 200610 100175 200610 100172 200611 100175 200611 100176 200611 100177 200612 101118 200612 100783 200612 100783 200613 101118 200613 100549 200613 100783 200614 100549 200614 100178 200614 100178 200615 100549 200615 100179 200615 100178 200616 100179 200616 100180 200616 100180 200617 100179 200617 100181 200617 100182 200618 100798 200618 100180 200618 100180 200619 100798 200619 100171 200619 100171 200620 100798 200620 100796 200620 100171 200621 100796 200621 99686 200621 100182 200622 100180 200622 100183 200622 100183 200623 100180 200623 100132 200623 100183 200624 100132 200624 100189 200624 100796 200625 99899 200625 99686 200625 99686 200626 99899 200626 100184 200626 99686 200627 100184 200627 99687 200627 100184 200628 100185 200628 99687 200628 99687 200629 100185 200629 99896 200629 99687 200630 99896 200630 100186 200630 100186 200631 99896 200631 99895 200631 100186 200632 99895 200632 99689 200632 99689 200633 99895 200633 100187 200633 99689 200634 100187 200634 100132 200634 100132 200635 100187 200635 100188 200635 100132 200636 100188 200636 100189 200636 100204 200637 99684 200637 100190 200637 100190 200638 99684 200638 101065 200638 100190 200639 101065 200639 101066 200639 100195 200640 100191 200640 100196 200640 100196 200641 100191 200641 100192 200641 100196 200642 100192 200642 99683 200642 99683 200643 100192 200643 100193 200643 99683 200644 100193 200644 99684 200644 99684 200645 100193 200645 100825 200645 99684 200646 100825 200646 101065 200646 101065 200647 100825 200647 100823 200647 101065 200648 100823 200648 101063 200648 101063 200649 100823 200649 100822 200649 101063 200650 100822 200650 101062 200650 100201 200651 100818 200651 100553 200651 100553 200652 100818 200652 100198 200652 100553 200653 100198 200653 100194 200653 100195 200654 100196 200654 100197 200654 100197 200655 100196 200655 99690 200655 100197 200656 99690 200656 100198 200656 100198 200657 99690 200657 100132 200657 100198 200658 100132 200658 100194 200658 100822 200659 100821 200659 101062 200659 101062 200660 100821 200660 100819 200660 101062 200661 100819 200661 100199 200661 100199 200662 100819 200662 100818 200662 100199 200663 100818 200663 100200 200663 100200 200664 100818 200664 100201 200664 100200 200665 100201 200665 101060 200665 101060 200666 100201 200666 100551 200666 101060 200667 100551 200667 101061 200667 101069 200668 100838 200668 101067 200668 101067 200669 100838 200669 100202 200669 101067 200670 100202 200670 100205 200670 100203 200671 100206 200671 99867 200671 99867 200672 100206 200672 100204 200672 99867 200673 100204 200673 100205 200673 100205 200674 100204 200674 100190 200674 100205 200675 100190 200675 101067 200675 101067 200676 100190 200676 101066 200676 100203 200677 99864 200677 100206 200677 100206 200678 99864 200678 100843 200678 100206 200679 100843 200679 99681 200679 99681 200680 100843 200680 100207 200680 99681 200681 100207 200681 100208 200681 100208 200682 100207 200682 100842 200682 100208 200683 100842 200683 100217 200683 100217 200684 100842 200684 100840 200684 100217 200685 100840 200685 101070 200685 101070 200686 100840 200686 100209 200686 101070 200687 100209 200687 101069 200687 101069 200688 100209 200688 100210 200688 101069 200689 100210 200689 100838 200689 101094 200690 100211 200690 100213 200690 100211 200691 100860 200691 100213 200691 100213 200692 100860 200692 100212 200692 100213 200693 100212 200693 100225 200693 100214 200694 100219 200694 100215 200694 100131 200695 101094 200695 100216 200695 100216 200696 101094 200696 100208 200696 100216 200697 100208 200697 99850 200697 99850 200698 100208 200698 100217 200698 99850 200699 100217 200699 100222 200699 100218 200700 100856 200700 100219 200700 100219 200701 100856 200701 100220 200701 100219 200702 100220 200702 100215 200702 100215 200703 100220 200703 100221 200703 100215 200704 100221 200704 101076 200704 101076 200705 100221 200705 99853 200705 101076 200706 99853 200706 100222 200706 100222 200707 99853 200707 99851 200707 100222 200708 99851 200708 99850 200708 101079 200709 99999 200709 100229 200709 100228 200710 100223 200710 100227 200710 100227 200711 100223 200711 100224 200711 100227 200712 100224 200712 100219 200712 100219 200713 100224 200713 100225 200713 100219 200714 100225 200714 100218 200714 100218 200715 100225 200715 100212 200715 101079 200716 100226 200716 99999 200716 99999 200717 100226 200717 101080 200717 99999 200718 101080 200718 100232 200718 100227 200719 101078 200719 100228 200719 100228 200720 101078 200720 100230 200720 100228 200721 100230 200721 100229 200721 100229 200722 100230 200722 100231 200722 100229 200723 100231 200723 101079 200723 101080 200724 100233 200724 100232 200724 100232 200725 100233 200725 101084 200725 100232 200726 101084 200726 100234 200726 100223 200727 99996 200727 100224 200727 100224 200728 99996 200728 100683 200728 100224 200729 100683 200729 101091 200729 101091 200730 100683 200730 100680 200730 101091 200731 100680 200731 100235 200731 100680 200732 100679 200732 100235 200732 100235 200733 100679 200733 100678 200733 100235 200734 100678 200734 101090 200734 101090 200735 100678 200735 100676 200735 101090 200736 100676 200736 101088 200736 101088 200737 100676 200737 100675 200737 101088 200738 100675 200738 100236 200738 100236 200739 100675 200739 100234 200739 100236 200740 100234 200740 101086 200740 101086 200741 100234 200741 101084 200741 100181 200742 100237 200742 100180 200742 100180 200743 100237 200743 100402 200743 100180 200744 100402 200744 100132 200744 100132 200745 100402 200745 100238 200745 100132 200746 100238 200746 100194 200746 100239 200747 100242 200747 100261 200747 100240 200748 100274 200748 99639 200748 100241 200749 100244 200749 101174 200749 100261 200750 100242 200750 100069 200750 100069 200751 100242 200751 101183 200751 100069 200752 101183 200752 100071 200752 100250 200753 100246 200753 100243 200753 101174 200754 100244 200754 100245 200754 100245 200755 100244 200755 100073 200755 100245 200756 100073 200756 100246 200756 100246 200757 100073 200757 100074 200757 100246 200758 100074 200758 100243 200758 100240 200759 99639 200759 100248 200759 100248 200760 99639 200760 100247 200760 100248 200761 100247 200761 100249 200761 100249 200762 100247 200762 99640 200762 100249 200763 99640 200763 101181 200763 100243 200764 100071 200764 100250 200764 100250 200765 100071 200765 101183 200765 100250 200766 101183 200766 99646 200766 99646 200767 101183 200767 100251 200767 100251 200768 101183 200768 100252 200768 100251 200769 100252 200769 100266 200769 100266 200770 100252 200770 101184 200770 100266 200771 101184 200771 100260 200771 100130 200772 100128 200772 100263 200772 99645 200773 100253 200773 100119 200773 100119 200774 100253 200774 100255 200774 100255 200775 100253 200775 100254 200775 100255 200776 100254 200776 100122 200776 100269 200777 100256 200777 100109 200777 100109 200778 100256 200778 101179 200778 100109 200779 101179 200779 100257 200779 100257 200780 101179 200780 100270 200780 100257 200781 100270 200781 100112 200781 101174 200782 101175 200782 100241 200782 100241 200783 101175 200783 101177 200783 100241 200784 101177 200784 100258 200784 100258 200785 101177 200785 101176 200785 100258 200786 101176 200786 100082 200786 100082 200787 101176 200787 100259 200787 100082 200788 100259 200788 100083 200788 100083 200789 100259 200789 100268 200789 100083 200790 100268 200790 100106 200790 101181 200791 101180 200791 100260 200791 100260 200792 101180 200792 101182 200792 100260 200793 101182 200793 100266 200793 100260 200794 99636 200794 101181 200794 101181 200795 99636 200795 99635 200795 101181 200796 99635 200796 100249 200796 100249 200797 99635 200797 99637 200797 100249 200798 99637 200798 100277 200798 100239 200799 100261 200799 100262 200799 100262 200800 100261 200800 100065 200800 100262 200801 100065 200801 99634 200801 99634 200802 100065 200802 100264 200802 99634 200803 100264 200803 100263 200803 100263 200804 100264 200804 100265 200804 100263 200805 100265 200805 100130 200805 101182 200806 100267 200806 100266 200806 100266 200807 100267 200807 100256 200807 100266 200808 100256 200808 100268 200808 100268 200809 100256 200809 100269 200809 100268 200810 100269 200810 100106 200810 100270 200811 100271 200811 100112 200811 100112 200812 100271 200812 100272 200812 100112 200813 100272 200813 100114 200813 100114 200814 100272 200814 99639 200814 100114 200815 99639 200815 100273 200815 100273 200816 99639 200816 100274 200816 100273 200817 100274 200817 100275 200817 100275 200818 100274 200818 99645 200818 100275 200819 99645 200819 100118 200819 100118 200820 99645 200820 100119 200820 100254 200821 99642 200821 100122 200821 100122 200822 99642 200822 99643 200822 100122 200823 99643 200823 100123 200823 100123 200824 99643 200824 100276 200824 100123 200825 100276 200825 100127 200825 100127 200826 100276 200826 101178 200826 100127 200827 101178 200827 100128 200827 100128 200828 101178 200828 100277 200828 100128 200829 100277 200829 100263 200829 100263 200830 100277 200830 99637 200830 100278 200831 100279 200831 99650 200831 100278 200832 99650 200832 100280 200832 100280 200833 99650 200833 100281 200833 100280 200834 100281 200834 100282 200834 100282 200835 100281 200835 99648 200835 100282 200836 99648 200836 101092 200836 101092 200837 99648 200837 100283 200837 101092 200838 100283 200838 101093 200838 101093 200839 100283 200839 99664 200839 101093 200840 99664 200840 100044 200840 100292 200841 100287 200841 100316 200841 100897 200842 100898 200842 99668 200842 99668 200843 100898 200843 100323 200843 99668 200844 100323 200844 99669 200844 99669 200845 100323 200845 99670 200845 99670 200846 100323 200846 100324 200846 99670 200847 100324 200847 99671 200847 99671 200848 100324 200848 100284 200848 100284 200849 100324 200849 100327 200849 100284 200850 100327 200850 100286 200850 100328 200851 100291 200851 100327 200851 100327 200852 100291 200852 100285 200852 100327 200853 100285 200853 100286 200853 100316 200854 100287 200854 100289 200854 100287 200855 100288 200855 100289 200855 100289 200856 100288 200856 101113 200856 100289 200857 101113 200857 100328 200857 100328 200858 101113 200858 100290 200858 100328 200859 100290 200859 100291 200859 100292 200860 100316 200860 101117 200860 101117 200861 100316 200861 100293 200861 101117 200862 100293 200862 100294 200862 100294 200863 100293 200863 100295 200863 100294 200864 100295 200864 100296 200864 100297 200865 100916 200865 100339 200865 100297 200866 100339 200866 101064 200866 101064 200867 100339 200867 100298 200867 101064 200868 100298 200868 100301 200868 100299 200869 100300 200869 100298 200869 100298 200870 100300 200870 101068 200870 100298 200871 101068 200871 100301 200871 100302 200872 100330 200872 101073 200872 101073 200873 101072 200873 100302 200873 100302 200874 101072 200874 101071 200874 100302 200875 101071 200875 100299 200875 100299 200876 101071 200876 100303 200876 100299 200877 100303 200877 100300 200877 100304 200878 99979 200878 101053 200878 101053 200879 99979 200879 100705 200879 101053 200880 100705 200880 101050 200880 101050 200881 100705 200881 100703 200881 101050 200882 100703 200882 101049 200882 101049 200883 100703 200883 100701 200883 101049 200884 100701 200884 100305 200884 100305 200885 100701 200885 100699 200885 100305 200886 100699 200886 100306 200886 100306 200887 100699 200887 100698 200887 100306 200888 100698 200888 100307 200888 100307 200889 100698 200889 100696 200889 100307 200890 100696 200890 100308 200890 100308 200891 100696 200891 100309 200891 100309 200892 100696 200892 99985 200892 100309 200893 99985 200893 100313 200893 100313 200894 99985 200894 99984 200894 100313 200895 99984 200895 100315 200895 100315 200896 99981 200896 100311 200896 100310 200897 100311 200897 101043 200897 101043 200898 100311 200898 99981 200898 101043 200899 99981 200899 100304 200899 100304 200900 99981 200900 99980 200900 100304 200901 99980 200901 99979 200901 100312 200902 100313 200902 100314 200902 100314 200903 100313 200903 100315 200903 100314 200904 100315 200904 101046 200904 101046 200905 100315 200905 100311 200905 100905 200906 100903 200906 100295 200906 100459 200907 100458 200907 100295 200907 100316 200908 100322 200908 100293 200908 100293 200909 100322 200909 100317 200909 100293 200910 100317 200910 100295 200910 100295 200911 100317 200911 100546 200911 100295 200912 100546 200912 100462 200912 100335 200913 100565 200913 100331 200913 100335 200914 100445 200914 100565 200914 100565 200915 100445 200915 100318 200915 100565 200916 100318 200916 100319 200916 100319 200917 100318 200917 100404 200917 100319 200918 100404 200918 100320 200918 100342 200919 100544 200919 100339 200919 100339 200920 100544 200920 100542 200920 100339 200921 100542 200921 100298 200921 100344 200922 100569 200922 100571 200922 100289 200923 100326 200923 100316 200923 100316 200924 100326 200924 100321 200924 100316 200925 100321 200925 100322 200925 100896 200926 100320 200926 100898 200926 100898 200927 100320 200927 100404 200927 100898 200928 100404 200928 100323 200928 100323 200929 100404 200929 100325 200929 100323 200930 100325 200930 100324 200930 100324 200931 100325 200931 100557 200931 100324 200932 100557 200932 100327 200932 100327 200933 100557 200933 100326 200933 100327 200934 100326 200934 100328 200934 100328 200935 100326 200935 100289 200935 100462 200936 100539 200936 100295 200936 100295 200937 100539 200937 100541 200937 100295 200938 100541 200938 100459 200938 100906 200939 100905 200939 100907 200939 100907 200940 100905 200940 100295 200940 100907 200941 100295 200941 100908 200941 100908 200942 100295 200942 100458 200942 100337 200943 100038 200943 100556 200943 100556 200944 100038 200944 100329 200944 100556 200945 100329 200945 100330 200945 100038 200946 100487 200946 100041 200946 100041 200947 100487 200947 100902 200947 100041 200948 100902 200948 100042 200948 100042 200949 100902 200949 100901 200949 100527 200950 100331 200950 100332 200950 100332 200951 100331 200951 100574 200951 100527 200952 100333 200952 100331 200952 100331 200953 100333 200953 100334 200953 100331 200954 100334 200954 100335 200954 100335 200955 100334 200955 100530 200955 100530 200956 100336 200956 100335 200956 100335 200957 100336 200957 100338 200957 100335 200958 100338 200958 100337 200958 100337 200959 100338 200959 100344 200959 100337 200960 100344 200960 100038 200960 100038 200961 100344 200961 100571 200961 100038 200962 100571 200962 100487 200962 100536 200963 100339 200963 100340 200963 100340 200964 100339 200964 100916 200964 100340 200965 100916 200965 100915 200965 100536 200966 100341 200966 100339 200966 100339 200967 100341 200967 100538 200967 100339 200968 100538 200968 100342 200968 100345 200969 100533 200969 100577 200969 100542 200970 100343 200970 100298 200970 100298 200971 100343 200971 100450 200971 100298 200972 100450 200972 100299 200972 100299 200973 100450 200973 100556 200973 100299 200974 100556 200974 100302 200974 100302 200975 100556 200975 100330 200975 100345 200976 100580 200976 100579 200976 100569 200977 100344 200977 100567 200977 100567 200978 100344 200978 100345 200978 100567 200979 100345 200979 100346 200979 100346 200980 100345 200980 100577 200980 100346 200981 100577 200981 100575 200981 100574 200982 100572 200982 100332 200982 100332 200983 100572 200983 100347 200983 100332 200984 100347 200984 100534 200984 100915 200985 100348 200985 100340 200985 100340 200986 100348 200986 100913 200986 100340 200987 100913 200987 100911 200987 100533 200988 100345 200988 100578 200988 100578 200989 100345 200989 100579 200989 100578 200990 100579 200990 100349 200990 100584 200991 100582 200991 100350 200991 100350 200992 100582 200992 100332 200992 100350 200993 100332 200993 100351 200993 100351 200994 100332 200994 100534 200994 101155 200995 101153 200995 100352 200995 100352 200996 101153 200996 101055 200996 100031 200997 99827 200997 100353 200997 100031 200998 100353 200998 100102 200998 100102 200999 100353 200999 100354 200999 100102 201000 100354 201000 100101 201000 100101 201001 100354 201001 100930 201001 100101 201002 100930 201002 100100 201002 100100 201003 100930 201003 100929 201003 100100 201004 100929 201004 100098 201004 100098 201005 100929 201005 100355 201005 100098 201006 100355 201006 100356 201006 100356 201007 100355 201007 100926 201007 100356 201008 100926 201008 100097 201008 100097 201009 100926 201009 100357 201009 100097 201010 100357 201010 100358 201010 100358 201011 100357 201011 100360 201011 100358 201012 100360 201012 100359 201012 100359 201013 100360 201013 100922 201013 100359 201014 100922 201014 100361 201014 100361 201015 100922 201015 100921 201015 100361 201016 100921 201016 100094 201016 100094 201017 100921 201017 100362 201017 100094 201018 100362 201018 100363 201018 100363 201019 100362 201019 100918 201019 100363 201020 100918 201020 100364 201020 100364 201021 100918 201021 100365 201021 100364 201022 100365 201022 100093 201022 100093 201023 100365 201023 100367 201023 100093 201024 100367 201024 100366 201024 100366 201025 100367 201025 99844 201025 100366 201026 99844 201026 100091 201026 100927 201027 100368 201027 100369 201027 100369 201028 100368 201028 99758 201028 100369 201029 99758 201029 100372 201029 100370 201030 100388 201030 100371 201030 100371 201031 100388 201031 100375 201031 100371 201032 100375 201032 100917 201032 99758 201033 99765 201033 100372 201033 100372 201034 99765 201034 99767 201034 100372 201035 99767 201035 100925 201035 100925 201036 99767 201036 100373 201036 100925 201037 100373 201037 100924 201037 100924 201038 100373 201038 100374 201038 100924 201039 100374 201039 100923 201039 100375 201040 100376 201040 100917 201040 100917 201041 100376 201041 100377 201041 100917 201042 100377 201042 100378 201042 100378 201043 100377 201043 100954 201043 100378 201044 100954 201044 99842 201044 99842 201045 100954 201045 100379 201045 99842 201046 100379 201046 99841 201046 100379 201047 100380 201047 99841 201047 99841 201048 100380 201048 100381 201048 99841 201049 100381 201049 99838 201049 99838 201050 100381 201050 100382 201050 99838 201051 100382 201051 99837 201051 100382 201052 100383 201052 99837 201052 99837 201053 100383 201053 100950 201053 99837 201054 100950 201054 100384 201054 100384 201055 100950 201055 100389 201055 100384 201056 100389 201056 100385 201056 100374 201057 99763 201057 100923 201057 100923 201058 99763 201058 99762 201058 100923 201059 99762 201059 100920 201059 100920 201060 99762 201060 100386 201060 100920 201061 100386 201061 100919 201061 100919 201062 100386 201062 100387 201062 100919 201063 100387 201063 100370 201063 100370 201064 100387 201064 99760 201064 100370 201065 99760 201065 100388 201065 100389 201066 100948 201066 100385 201066 100385 201067 100948 201067 100949 201067 100385 201068 100949 201068 100390 201068 100390 201069 100949 201069 100391 201069 100390 201070 100391 201070 99835 201070 99835 201071 100391 201071 100945 201071 99835 201072 100945 201072 99833 201072 100945 201073 100392 201073 99833 201073 99833 201074 100392 201074 100393 201074 99833 201075 100393 201075 99832 201075 99832 201076 100393 201076 100394 201076 99832 201077 100394 201077 100397 201077 100400 201078 100395 201078 100928 201078 100928 201079 100395 201079 100396 201079 100928 201080 100396 201080 100927 201080 100927 201081 100396 201081 99769 201081 100927 201082 99769 201082 100368 201082 100394 201083 100940 201083 100397 201083 100397 201084 100940 201084 100941 201084 100397 201085 100941 201085 99829 201085 99829 201086 100941 201086 100956 201086 99829 201087 100956 201087 99828 201087 99828 201088 100956 201088 100955 201088 99828 201089 100955 201089 100932 201089 100955 201090 100968 201090 100932 201090 100932 201091 100968 201091 99822 201091 100932 201092 99822 201092 100931 201092 100931 201093 99822 201093 99819 201093 100931 201094 99819 201094 100398 201094 100398 201095 99819 201095 100399 201095 100398 201096 100399 201096 100400 201096 100400 201097 100399 201097 100401 201097 100400 201098 100401 201098 100395 201098 100555 201099 100194 201099 100238 201099 100555 201100 100238 201100 100647 201100 100647 201101 100238 201101 100402 201101 100647 201102 100402 201102 100649 201102 100649 201103 100402 201103 100237 201103 100649 201104 100237 201104 100650 201104 100650 201105 100237 201105 100181 201105 100650 201106 100181 201106 100548 201106 100638 201107 100321 201107 100403 201107 100403 201108 100321 201108 100326 201108 100419 201109 100420 201109 100411 201109 99700 201110 100405 201110 100404 201110 100404 201111 100405 201111 100407 201111 101011 201112 100406 201112 100440 201112 100407 201113 100408 201113 100404 201113 100404 201114 100408 201114 99698 201114 100404 201115 99698 201115 100422 201115 100422 201116 99698 201116 100409 201116 100406 201117 101010 201117 100440 201117 100440 201118 101010 201118 100410 201118 100440 201119 100410 201119 100431 201119 100431 201120 100410 201120 99731 201120 100891 201121 101013 201121 100411 201121 100411 201122 101013 201122 100412 201122 100411 201123 100412 201123 100419 201123 100409 201124 100413 201124 100422 201124 100422 201125 100413 201125 101040 201125 100422 201126 101040 201126 100425 201126 100404 201127 100882 201127 99700 201127 99700 201128 100882 201128 100415 201128 99700 201129 100415 201129 100414 201129 100414 201130 100415 201130 100416 201130 99731 201131 99733 201131 100431 201131 100431 201132 99733 201132 99734 201132 100431 201133 99734 201133 100418 201133 100891 201134 100890 201134 101013 201134 101013 201135 100890 201135 100884 201135 101013 201136 100884 201136 99745 201136 99745 201137 100884 201137 100880 201137 99745 201138 100880 201138 100417 201138 100417 201139 100880 201139 100418 201139 100417 201140 100418 201140 99739 201140 99739 201141 100418 201141 99734 201141 100419 201142 101011 201142 100420 201142 100420 201143 101011 201143 100440 201143 100420 201144 100440 201144 100421 201144 100421 201145 100440 201145 100422 201145 100415 201146 100888 201146 100416 201146 100416 201147 100888 201147 100887 201147 100416 201148 100887 201148 100424 201148 100424 201149 100887 201149 100423 201149 100424 201150 100423 201150 100425 201150 100425 201151 100423 201151 100426 201151 100425 201152 100426 201152 100422 201152 100422 201153 100426 201153 100427 201153 100422 201154 100427 201154 100421 201154 100418 201155 100428 201155 100318 201155 100318 201156 100428 201156 100879 201156 100318 201157 100879 201157 100404 201157 100404 201158 100879 201158 100883 201158 100404 201159 100883 201159 100882 201159 100418 201160 100318 201160 100431 201160 100431 201161 100318 201161 100448 201161 100431 201162 100448 201162 100866 201162 99717 201163 100429 201163 100445 201163 100865 201164 100430 201164 100445 201164 99717 201165 100445 201165 99718 201165 100866 201166 100871 201166 100431 201166 100431 201167 100871 201167 100432 201167 100431 201168 100432 201168 100440 201168 100440 201169 100432 201169 100878 201169 100440 201170 100878 201170 100877 201170 100441 201171 100630 201171 100433 201171 100433 201172 100630 201172 100434 201172 100433 201173 100434 201173 101025 201173 101025 201174 100434 201174 100436 201174 101025 201175 100436 201175 100435 201175 100435 201176 100436 201176 99712 201176 100444 201177 100865 201177 100437 201177 100437 201178 100865 201178 100445 201178 100437 201179 100445 201179 100438 201179 100438 201180 100445 201180 100429 201180 100877 201181 100876 201181 100440 201181 100440 201182 100876 201182 100439 201182 100440 201183 100439 201183 100630 201183 100630 201184 100439 201184 100874 201184 100630 201185 100874 201185 100434 201185 100441 201186 100442 201186 100630 201186 100630 201187 100442 201187 99722 201187 100630 201188 99722 201188 100445 201188 100445 201189 99722 201189 99720 201189 100445 201190 99720 201190 99718 201190 99712 201191 100436 201191 100437 201191 100437 201192 100436 201192 100443 201192 100437 201193 100443 201193 100444 201193 100430 201194 100446 201194 100445 201194 100445 201195 100446 201195 100862 201195 100445 201196 100862 201196 100318 201196 100318 201197 100862 201197 100447 201197 100318 201198 100447 201198 100448 201198 100627 201199 100556 201199 100449 201199 100449 201200 100556 201200 100450 201200 100545 201201 100544 201201 100451 201201 100451 201202 100544 201202 100342 201202 100536 201203 100340 201203 100455 201203 100455 201204 100340 201204 100452 201204 100455 201205 100452 201205 100453 201205 100551 201206 100639 201206 101061 201206 101061 201207 100639 201207 100455 201207 100453 201208 100454 201208 100455 201208 100455 201209 100454 201209 101056 201209 100455 201210 101056 201210 101061 201210 100550 201211 100456 201211 100457 201211 100457 201212 100456 201212 100461 201212 100458 201213 100459 201213 99846 201213 99846 201214 100459 201214 100457 201214 99846 201215 100457 201215 100460 201215 100460 201216 100457 201216 100461 201216 100651 201217 100462 201217 100463 201217 100463 201218 100462 201218 100546 201218 100482 201219 100657 201219 100483 201219 100635 201220 100466 201220 100473 201220 100473 201221 100466 201221 100470 201221 100464 201222 100466 201222 100465 201222 100465 201223 100466 201223 100635 201223 100465 201224 100635 201224 100475 201224 100475 201225 100635 201225 100467 201225 100468 201226 100475 201226 100657 201226 100657 201227 100475 201227 100467 201227 100657 201228 100467 201228 100483 201228 100472 201229 100629 201229 100469 201229 100632 201230 100634 201230 100470 201230 100470 201231 100634 201231 100471 201231 100470 201232 100471 201232 100473 201232 100473 201233 100471 201233 100472 201233 100473 201234 100472 201234 100474 201234 100474 201235 100472 201235 100469 201235 100477 201236 100644 201236 100645 201236 100484 201237 100640 201237 100641 201237 100468 201238 100476 201238 100475 201238 100475 201239 100476 201239 100477 201239 100475 201240 100477 201240 100646 201240 100646 201241 100477 201241 100645 201241 100652 201242 100655 201242 100479 201242 100479 201243 100655 201243 100478 201243 100479 201244 100478 201244 100480 201244 100480 201245 100478 201245 100482 201245 100480 201246 100482 201246 100481 201246 100481 201247 100482 201247 100483 201247 100481 201248 100483 201248 100648 201248 100648 201249 100483 201249 100484 201249 100648 201250 100484 201250 100642 201250 100642 201251 100484 201251 100641 201251 101082 201252 100485 201252 101083 201252 101083 201253 100485 201253 100508 201253 100900 201254 100902 201254 100486 201254 100486 201255 100902 201255 100487 201255 101152 201256 100519 201256 100014 201256 100014 201257 100519 201257 100488 201257 101142 201258 101140 201258 100488 201258 100488 201259 101140 201259 100489 201259 100488 201260 100489 201260 100014 201260 100014 201261 100489 201261 100494 201261 100014 201262 100494 201262 100015 201262 101045 201263 100336 201263 100529 201263 100529 201264 100336 201264 100530 201264 101131 201265 100524 201265 101042 201265 101042 201266 101052 201266 100490 201266 100490 201267 101052 201267 100491 201267 100490 201268 100017 201268 100506 201268 100490 201269 100506 201269 101042 201269 101042 201270 100506 201270 100492 201270 101042 201271 100492 201271 101131 201271 101104 201272 100319 201272 101106 201272 101106 201273 100319 201273 100320 201273 100559 201274 100500 201274 101100 201274 101100 201275 100500 201275 100563 201275 100493 201276 101098 201276 100513 201276 100513 201277 101098 201277 101097 201277 100494 201278 100489 201278 100495 201278 101145 201279 100501 201279 100496 201279 101145 201280 100496 201280 100497 201280 100495 201281 101144 201281 100494 201281 100494 201282 101144 201282 101143 201282 100494 201283 101143 201283 100496 201283 100496 201284 101143 201284 100498 201284 100496 201285 100498 201285 100497 201285 100499 201286 100563 201286 100501 201286 100501 201287 100563 201287 100500 201287 100501 201288 100500 201288 100496 201288 100496 201289 100500 201289 100560 201289 100496 201290 100560 201290 100502 201290 100503 201291 100514 201291 100504 201291 100504 201292 100514 201292 101087 201292 100492 201293 100506 201293 100505 201293 100505 201294 100506 201294 101134 201294 100566 201295 101125 201295 100485 201295 100485 201296 101125 201296 100508 201296 100561 201297 100507 201297 100509 201297 100509 201298 100507 201298 100508 201298 101125 201299 101124 201299 100508 201299 100508 201300 101124 201300 101128 201300 100508 201301 101128 201301 100509 201301 100509 201302 101128 201302 101127 201302 100509 201303 101127 201303 100506 201303 100506 201304 101127 201304 101135 201304 100506 201305 101135 201305 101134 201305 99679 201306 101162 201306 100510 201306 99679 201307 100510 201307 101096 201307 101096 201308 100510 201308 100511 201308 101096 201309 100511 201309 100512 201309 100512 201310 100511 201310 100513 201310 100512 201311 100513 201311 101097 201311 100514 201312 100503 201312 101160 201312 100514 201313 101160 201313 100515 201313 100515 201314 101160 201314 100516 201314 100515 201315 100516 201315 101089 201315 101089 201316 100516 201316 100279 201316 101089 201317 100279 201317 100278 201317 101055 201318 101153 201318 100517 201318 101055 201319 100517 201319 101048 201319 101048 201320 100517 201320 100518 201320 101048 201321 100518 201321 101051 201321 101051 201322 100518 201322 100491 201322 101051 201323 100491 201323 101052 201323 100519 201324 101152 201324 100520 201324 100519 201325 100520 201325 100521 201325 100521 201326 100520 201326 101151 201326 100521 201327 101151 201327 101054 201327 101054 201328 101151 201328 101155 201328 101054 201329 101155 201329 100352 201329 100522 201330 100345 201330 100344 201330 100522 201331 100523 201331 101130 201331 101130 201332 100523 201332 101042 201332 101130 201333 101042 201333 100524 201333 100522 201334 100344 201334 100523 201334 100523 201335 100344 201335 100338 201335 100523 201336 100338 201336 101044 201336 101044 201337 100338 201337 100336 201337 101044 201338 100336 201338 101045 201338 100332 201339 100583 201339 101047 201339 101047 201340 100583 201340 100488 201340 100488 201341 100583 201341 100525 201341 100488 201342 100525 201342 101142 201342 100332 201343 101047 201343 100527 201343 100527 201344 101047 201344 100526 201344 100527 201345 100526 201345 100333 201345 100333 201346 100526 201346 100528 201346 100333 201347 100528 201347 100334 201347 100334 201348 100528 201348 100529 201348 100334 201349 100529 201349 100530 201349 101129 201350 100577 201350 100531 201350 100531 201351 100577 201351 100533 201351 100531 201352 100533 201352 100532 201352 100532 201353 100533 201353 100578 201353 101146 201354 100351 201354 100535 201354 100535 201355 100351 201355 100534 201355 100535 201356 100534 201356 100573 201356 100573 201357 100534 201357 100347 201357 100536 201358 100455 201358 100341 201358 100341 201359 100455 201359 100537 201359 100341 201360 100537 201360 100538 201360 100538 201361 100537 201361 100636 201361 100538 201362 100636 201362 100342 201362 100342 201363 100636 201363 100451 201363 100462 201364 100651 201364 100539 201364 100539 201365 100651 201365 100540 201365 100539 201366 100540 201366 100541 201366 100541 201367 100540 201367 100656 201367 100541 201368 100656 201368 100459 201368 100459 201369 100656 201369 100457 201369 100449 201370 100450 201370 100343 201370 100449 201371 100343 201371 100628 201371 100628 201372 100343 201372 100542 201372 100628 201373 100542 201373 100543 201373 100543 201374 100542 201374 100544 201374 100543 201375 100544 201375 100545 201375 100463 201376 100546 201376 100317 201376 100463 201377 100317 201377 100643 201377 100643 201378 100317 201378 100322 201378 100643 201379 100322 201379 100547 201379 100547 201380 100322 201380 100321 201380 100547 201381 100321 201381 100638 201381 100548 201382 100181 201382 100179 201382 100548 201383 100179 201383 100653 201383 100653 201384 100179 201384 100549 201384 100653 201385 100549 201385 100654 201385 100654 201386 100549 201386 100456 201386 100654 201387 100456 201387 100550 201387 100639 201388 100551 201388 100201 201388 100639 201389 100201 201389 100552 201389 100552 201390 100201 201390 100553 201390 100552 201391 100553 201391 100554 201391 100554 201392 100553 201392 100194 201392 100554 201393 100194 201393 100555 201393 100630 201394 100445 201394 100335 201394 100630 201395 100335 201395 100631 201395 100631 201396 100335 201396 100337 201396 100631 201397 100337 201397 100633 201397 100633 201398 100337 201398 100556 201398 100633 201399 100556 201399 100627 201399 100403 201400 100326 201400 100557 201400 100403 201401 100557 201401 100637 201401 100637 201402 100557 201402 100325 201402 100637 201403 100325 201403 100558 201403 100558 201404 100325 201404 100404 201404 100558 201405 100404 201405 100422 201405 100500 201406 100559 201406 101099 201406 101098 201407 100493 201407 101099 201407 101099 201408 100493 201408 100012 201408 100013 201409 101138 201409 100012 201409 100012 201410 101138 201410 100502 201410 100012 201411 100502 201411 101099 201411 101099 201412 100502 201412 100560 201412 101099 201413 100560 201413 100500 201413 100507 201414 100561 201414 100024 201414 100024 201415 100561 201415 101139 201415 100024 201416 101139 201416 100025 201416 100504 201417 101087 201417 100024 201417 100024 201418 101087 201418 101085 201418 100024 201419 101085 201419 100507 201419 100507 201420 101085 201420 101083 201420 100507 201421 101083 201421 100508 201421 100562 201422 100574 201422 100331 201422 100562 201423 100564 201423 100499 201423 100499 201424 100564 201424 101100 201424 100499 201425 101100 201425 100563 201425 100562 201426 100331 201426 100564 201426 100564 201427 100331 201427 100565 201427 100564 201428 100565 201428 101102 201428 101102 201429 100565 201429 100319 201429 101102 201430 100319 201430 101104 201430 100346 201431 101126 201431 101081 201431 101081 201432 101126 201432 101082 201432 101082 201433 101126 201433 100566 201433 101082 201434 100566 201434 100485 201434 100346 201435 101081 201435 100567 201435 100567 201436 101081 201436 100568 201436 100567 201437 100568 201437 100569 201437 100569 201438 100568 201438 100570 201438 100569 201439 100570 201439 100571 201439 100571 201440 100570 201440 100486 201440 100571 201441 100486 201441 100487 201441 100573 201442 100347 201442 100572 201442 100573 201443 100572 201443 101147 201443 101147 201444 100572 201444 100574 201444 101147 201445 100574 201445 100562 201445 101126 201446 100346 201446 100575 201446 101126 201447 100575 201447 100576 201447 100576 201448 100575 201448 100577 201448 100576 201449 100577 201449 101129 201449 100532 201450 100578 201450 100349 201450 100532 201451 100349 201451 101133 201451 101133 201452 100349 201452 100579 201452 101133 201453 100579 201453 101132 201453 101132 201454 100579 201454 100580 201454 101132 201455 100580 201455 100581 201455 100581 201456 100580 201456 100345 201456 100581 201457 100345 201457 100522 201457 100583 201458 100332 201458 100582 201458 100583 201459 100582 201459 101141 201459 101141 201460 100582 201460 100584 201460 101141 201461 100584 201461 100585 201461 100585 201462 100584 201462 100350 201462 100585 201463 100350 201463 100586 201463 100586 201464 100350 201464 100351 201464 100586 201465 100351 201465 101146 201465 100601 201466 100869 201466 100597 201466 100597 201467 100869 201467 100870 201467 101197 201468 100587 201468 101198 201468 101198 201469 100587 201469 100872 201469 101198 201470 100872 201470 100588 201470 100588 201471 100872 201471 100873 201471 100588 201472 100873 201472 101191 201472 101191 201473 100873 201473 100589 201473 101191 201474 100589 201474 100603 201474 100603 201475 100589 201475 100590 201475 101192 201476 100591 201476 101197 201476 101197 201477 100591 201477 100587 201477 101195 201478 100861 201478 100592 201478 100592 201479 100861 201479 100863 201479 100592 201480 100863 201480 100593 201480 100593 201481 100863 201481 100594 201481 100593 201482 100594 201482 100595 201482 100595 201483 100594 201483 100864 201483 100595 201484 100864 201484 101192 201484 101192 201485 100864 201485 100591 201485 101194 201486 100596 201486 101195 201486 101195 201487 100596 201487 100861 201487 100597 201488 100870 201488 101193 201488 101193 201489 100870 201489 100867 201489 101193 201490 100867 201490 100598 201490 100598 201491 100867 201491 100868 201491 100598 201492 100868 201492 101194 201492 101194 201493 100868 201493 100596 201493 100604 201494 100599 201494 101196 201494 101196 201495 100599 201495 100875 201495 101196 201496 100875 201496 100600 201496 100600 201497 100875 201497 100602 201497 100600 201498 100602 201498 100601 201498 100601 201499 100602 201499 100869 201499 100603 201500 100590 201500 100604 201500 100604 201501 100590 201501 100599 201501 101188 201502 100885 201502 101185 201502 101185 201503 100885 201503 100605 201503 101185 201504 100605 201504 100606 201504 100606 201505 100605 201505 100889 201505 100606 201506 100889 201506 101186 201506 101186 201507 100889 201507 100892 201507 101186 201508 100892 201508 100607 201508 100607 201509 100892 201509 100893 201509 100607 201510 100893 201510 100608 201510 100608 201511 100893 201511 100626 201511 100616 201512 100610 201512 100609 201512 100609 201513 100610 201513 100611 201513 100609 201514 100611 201514 100612 201514 100612 201515 100611 201515 100613 201515 100612 201516 100613 201516 100614 201516 100614 201517 100613 201517 100615 201517 100614 201518 100615 201518 101188 201518 101188 201519 100615 201519 100885 201519 100619 201520 100620 201520 100616 201520 100616 201521 100620 201521 100610 201521 100622 201522 100886 201522 100617 201522 100617 201523 100886 201523 100881 201523 100617 201524 100881 201524 101187 201524 101187 201525 100881 201525 100618 201525 101187 201526 100618 201526 100619 201526 100619 201527 100618 201527 100620 201527 100625 201528 100621 201528 100622 201528 100622 201529 100621 201529 100886 201529 101190 201530 100895 201530 100623 201530 100623 201531 100895 201531 100624 201531 100623 201532 100624 201532 101189 201532 101189 201533 100624 201533 100894 201533 101189 201534 100894 201534 100625 201534 100625 201535 100894 201535 100621 201535 100608 201536 100626 201536 101190 201536 101190 201537 100626 201537 100895 201537 100449 201538 100472 201538 100627 201538 100627 201539 100472 201539 100471 201539 100472 201540 100449 201540 100628 201540 100472 201541 100628 201541 100629 201541 100629 201542 100628 201542 100543 201542 100629 201543 100543 201543 100469 201543 100469 201544 100543 201544 100545 201544 100469 201545 100545 201545 100474 201545 100470 201546 100630 201546 100631 201546 100470 201547 100631 201547 100632 201547 100632 201548 100631 201548 100633 201548 100632 201549 100633 201549 100634 201549 100634 201550 100633 201550 100627 201550 100634 201551 100627 201551 100471 201551 100451 201552 100473 201552 100545 201552 100545 201553 100473 201553 100474 201553 100630 201554 100470 201554 100440 201554 100440 201555 100470 201555 100466 201555 100440 201556 100466 201556 100422 201556 100455 201557 100483 201557 100537 201557 100537 201558 100483 201558 100467 201558 100537 201559 100467 201559 100636 201559 100636 201560 100467 201560 100635 201560 100636 201561 100635 201561 100451 201561 100451 201562 100635 201562 100473 201562 100475 201563 100403 201563 100637 201563 100475 201564 100637 201564 100465 201564 100465 201565 100637 201565 100558 201565 100465 201566 100558 201566 100464 201566 100464 201567 100558 201567 100422 201567 100464 201568 100422 201568 100466 201568 100639 201569 100484 201569 100455 201569 100455 201570 100484 201570 100483 201570 100646 201571 100638 201571 100475 201571 100475 201572 100638 201572 100403 201572 100484 201573 100639 201573 100552 201573 100484 201574 100552 201574 100640 201574 100640 201575 100552 201575 100554 201575 100640 201576 100554 201576 100641 201576 100641 201577 100554 201577 100555 201577 100641 201578 100555 201578 100642 201578 100477 201579 100463 201579 100643 201579 100477 201580 100643 201580 100644 201580 100644 201581 100643 201581 100547 201581 100644 201582 100547 201582 100645 201582 100645 201583 100547 201583 100638 201583 100645 201584 100638 201584 100646 201584 100642 201585 100555 201585 100647 201585 100642 201586 100647 201586 100648 201586 100648 201587 100647 201587 100649 201587 100648 201588 100649 201588 100481 201588 100481 201589 100649 201589 100650 201589 100481 201590 100650 201590 100480 201590 100480 201591 100650 201591 100548 201591 100480 201592 100548 201592 100479 201592 100476 201593 100651 201593 100477 201593 100477 201594 100651 201594 100463 201594 100479 201595 100548 201595 100653 201595 100479 201596 100653 201596 100652 201596 100652 201597 100653 201597 100654 201597 100652 201598 100654 201598 100655 201598 100655 201599 100654 201599 100550 201599 100655 201600 100550 201600 100478 201600 100651 201601 100476 201601 100540 201601 100540 201602 100476 201602 100468 201602 100540 201603 100468 201603 100656 201603 100656 201604 100468 201604 100657 201604 100656 201605 100657 201605 100457 201605 100457 201606 100657 201606 100482 201606 100457 201607 100482 201607 100550 201607 100550 201608 100482 201608 100478 201608 100001 201609 100658 201609 100674 201609 100674 201610 100658 201610 100659 201610 100674 201611 100659 201611 100672 201611 100672 201612 100659 201612 100660 201612 100672 201613 100660 201613 100661 201613 100661 201614 100660 201614 100662 201614 100661 201615 100662 201615 100663 201615 100663 201616 100662 201616 100664 201616 100663 201617 100664 201617 100665 201617 100665 201618 100664 201618 104547 201618 100665 201619 104547 201619 100668 201619 100668 201620 104547 201620 104546 201620 100668 201621 104546 201621 100666 201621 100666 201622 104546 201622 100667 201622 100666 201623 100000 201623 100668 201623 100668 201624 100000 201624 100669 201624 100668 201625 100669 201625 100665 201625 100665 201626 100669 201626 100670 201626 100665 201627 100670 201627 100663 201627 100663 201628 100670 201628 100671 201628 100663 201629 100671 201629 100661 201629 100661 201630 100671 201630 100677 201630 100661 201631 100677 201631 100672 201631 100672 201632 100677 201632 100673 201632 100672 201633 100673 201633 100674 201633 100674 201634 100673 201634 100681 201634 100674 201635 100681 201635 100001 201635 100001 201636 100681 201636 100682 201636 100000 201637 100234 201637 100669 201637 100669 201638 100234 201638 100675 201638 100669 201639 100675 201639 100670 201639 100670 201640 100675 201640 100676 201640 100670 201641 100676 201641 100671 201641 100671 201642 100676 201642 100678 201642 100671 201643 100678 201643 100677 201643 100677 201644 100678 201644 100679 201644 100677 201645 100679 201645 100673 201645 100673 201646 100679 201646 100680 201646 100673 201647 100680 201647 100681 201647 100681 201648 100680 201648 100683 201648 100681 201649 100683 201649 100682 201649 100682 201650 100683 201650 99996 201650 100684 201651 104535 201651 100695 201651 100695 201652 104535 201652 104534 201652 100695 201653 104534 201653 100693 201653 100693 201654 104534 201654 104533 201654 100693 201655 104533 201655 100692 201655 100692 201656 104533 201656 100685 201656 100692 201657 100685 201657 100686 201657 100686 201658 100685 201658 104531 201658 100686 201659 104531 201659 100687 201659 100687 201660 104531 201660 100688 201660 100687 201661 100688 201661 100689 201661 100689 201662 100688 201662 104529 201662 100689 201663 100690 201663 100687 201663 100687 201664 100690 201664 100691 201664 100687 201665 100691 201665 100686 201665 100686 201666 100691 201666 100697 201666 100686 201667 100697 201667 100692 201667 100692 201668 100697 201668 100700 201668 100692 201669 100700 201669 100693 201669 100693 201670 100700 201670 100694 201670 100693 201671 100694 201671 100695 201671 100695 201672 100694 201672 100702 201672 100695 201673 100702 201673 100684 201673 100684 201674 100702 201674 100704 201674 100690 201675 99985 201675 100691 201675 100691 201676 99985 201676 100696 201676 100691 201677 100696 201677 100697 201677 100697 201678 100696 201678 100698 201678 100697 201679 100698 201679 100700 201679 100700 201680 100698 201680 100699 201680 100700 201681 100699 201681 100694 201681 100694 201682 100699 201682 100701 201682 100694 201683 100701 201683 100702 201683 100702 201684 100701 201684 100703 201684 100702 201685 100703 201685 100704 201685 100704 201686 100703 201686 100705 201686 100720 201687 99978 201687 100706 201687 100706 201688 99978 201688 100708 201688 100706 201689 100708 201689 100707 201689 100707 201690 100708 201690 100709 201690 100707 201691 100709 201691 100718 201691 100718 201692 100709 201692 104501 201692 100718 201693 104501 201693 100716 201693 100716 201694 104501 201694 104512 201694 100716 201695 104512 201695 100714 201695 100714 201696 104512 201696 104511 201696 100714 201697 104511 201697 100712 201697 100712 201698 104511 201698 100710 201698 100712 201699 100710 201699 100711 201699 100711 201700 100710 201700 104510 201700 100711 201701 100721 201701 100712 201701 100712 201702 100721 201702 100713 201702 100712 201703 100713 201703 100714 201703 100714 201704 100713 201704 100715 201704 100714 201705 100715 201705 100716 201705 100716 201706 100715 201706 100723 201706 100716 201707 100723 201707 100718 201707 100718 201708 100723 201708 100717 201708 100718 201709 100717 201709 100707 201709 100707 201710 100717 201710 100725 201710 100707 201711 100725 201711 100706 201711 100706 201712 100725 201712 100719 201712 100706 201713 100719 201713 100720 201713 100720 201714 100719 201714 100727 201714 100721 201715 100722 201715 100713 201715 100713 201716 100722 201716 100147 201716 100713 201717 100147 201717 100715 201717 100715 201718 100147 201718 100146 201718 100715 201719 100146 201719 100723 201719 100723 201720 100146 201720 100145 201720 100723 201721 100145 201721 100717 201721 100717 201722 100145 201722 100724 201722 100717 201723 100724 201723 100725 201723 100725 201724 100724 201724 100726 201724 100725 201725 100726 201725 100719 201725 100719 201726 100726 201726 100138 201726 100719 201727 100138 201727 100727 201727 100727 201728 100138 201728 99963 201728 100738 201729 100728 201729 100737 201729 100737 201730 100728 201730 104485 201730 100737 201731 104485 201731 100735 201731 100735 201732 104485 201732 104483 201732 100735 201733 104483 201733 100734 201733 100734 201734 104483 201734 100729 201734 100734 201735 100729 201735 100733 201735 100733 201736 100729 201736 104482 201736 100733 201737 104482 201737 100731 201737 100731 201738 104482 201738 104481 201738 100731 201739 104481 201739 99956 201739 99956 201740 104481 201740 100730 201740 99956 201741 99950 201741 100731 201741 100731 201742 99950 201742 100732 201742 100731 201743 100732 201743 100733 201743 100733 201744 100732 201744 100739 201744 100733 201745 100739 201745 100734 201745 100734 201746 100739 201746 100741 201746 100734 201747 100741 201747 100735 201747 100735 201748 100741 201748 100736 201748 100735 201749 100736 201749 100737 201749 100737 201750 100736 201750 100743 201750 100737 201751 100743 201751 100738 201751 100738 201752 100743 201752 100745 201752 99950 201753 99951 201753 100732 201753 100732 201754 99951 201754 100149 201754 100732 201755 100149 201755 100739 201755 100739 201756 100149 201756 100740 201756 100739 201757 100740 201757 100741 201757 100741 201758 100740 201758 100742 201758 100741 201759 100742 201759 100736 201759 100736 201760 100742 201760 100155 201760 100736 201761 100155 201761 100743 201761 100743 201762 100155 201762 100744 201762 100743 201763 100744 201763 100745 201763 100745 201764 100744 201764 100154 201764 99944 201765 104460 201765 100746 201765 100746 201766 104460 201766 100747 201766 100746 201767 100747 201767 100748 201767 100748 201768 100747 201768 104459 201768 100748 201769 104459 201769 100757 201769 100757 201770 104459 201770 100749 201770 100757 201771 100749 201771 100750 201771 100750 201772 100749 201772 100751 201772 100750 201773 100751 201773 100755 201773 100755 201774 100751 201774 100753 201774 100755 201775 100753 201775 100752 201775 100752 201776 100753 201776 100754 201776 100752 201777 100760 201777 100755 201777 100755 201778 100760 201778 100763 201778 100755 201779 100763 201779 100750 201779 100750 201780 100763 201780 100756 201780 100750 201781 100756 201781 100757 201781 100757 201782 100756 201782 100764 201782 100757 201783 100764 201783 100748 201783 100748 201784 100764 201784 100758 201784 100748 201785 100758 201785 100746 201785 100746 201786 100758 201786 100759 201786 100746 201787 100759 201787 99944 201787 99944 201788 100759 201788 99932 201788 100760 201789 100761 201789 100763 201789 100763 201790 100761 201790 100762 201790 100763 201791 100762 201791 100756 201791 100756 201792 100762 201792 100156 201792 100756 201793 100156 201793 100764 201793 100764 201794 100156 201794 100765 201794 100764 201795 100765 201795 100758 201795 100758 201796 100765 201796 100158 201796 100758 201797 100158 201797 100759 201797 100759 201798 100158 201798 100157 201798 100759 201799 100157 201799 99932 201799 99932 201800 100157 201800 99927 201800 100766 201801 104440 201801 100768 201801 100768 201802 104440 201802 100767 201802 100768 201803 100767 201803 100769 201803 100769 201804 100767 201804 100770 201804 100769 201805 100770 201805 100774 201805 100774 201806 100770 201806 104438 201806 100774 201807 104438 201807 100771 201807 100771 201808 104438 201808 104437 201808 100771 201809 104437 201809 100772 201809 100772 201810 104437 201810 104435 201810 100772 201811 104435 201811 99923 201811 99923 201812 104435 201812 104433 201812 99923 201813 100775 201813 100772 201813 100772 201814 100775 201814 100773 201814 100772 201815 100773 201815 100771 201815 100771 201816 100773 201816 100776 201816 100771 201817 100776 201817 100774 201817 100774 201818 100776 201818 100777 201818 100774 201819 100777 201819 100769 201819 100769 201820 100777 201820 100779 201820 100769 201821 100779 201821 100768 201821 100768 201822 100779 201822 100780 201822 100768 201823 100780 201823 100766 201823 100766 201824 100780 201824 100781 201824 100775 201825 99917 201825 100773 201825 100773 201826 99917 201826 100169 201826 100773 201827 100169 201827 100776 201827 100776 201828 100169 201828 100166 201828 100776 201829 100166 201829 100777 201829 100777 201830 100166 201830 100778 201830 100777 201831 100778 201831 100779 201831 100779 201832 100778 201832 100163 201832 100779 201833 100163 201833 100780 201833 100780 201834 100163 201834 100782 201834 100780 201835 100782 201835 100781 201835 100781 201836 100782 201836 100783 201836 100784 201837 104412 201837 100795 201837 100795 201838 104412 201838 100786 201838 100795 201839 100786 201839 100785 201839 100785 201840 100786 201840 100787 201840 100785 201841 100787 201841 100793 201841 100793 201842 100787 201842 100788 201842 100793 201843 100788 201843 100792 201843 100792 201844 100788 201844 104410 201844 100792 201845 104410 201845 100790 201845 100790 201846 104410 201846 104407 201846 100790 201847 104407 201847 99905 201847 99905 201848 104407 201848 100789 201848 99905 201849 99900 201849 100790 201849 100790 201850 99900 201850 100797 201850 100790 201851 100797 201851 100792 201851 100792 201852 100797 201852 100791 201852 100792 201853 100791 201853 100793 201853 100793 201854 100791 201854 100794 201854 100793 201855 100794 201855 100785 201855 100785 201856 100794 201856 100799 201856 100785 201857 100799 201857 100795 201857 100795 201858 100799 201858 100800 201858 100795 201859 100800 201859 100784 201859 100784 201860 100800 201860 100801 201860 99900 201861 100796 201861 100797 201861 100797 201862 100796 201862 100798 201862 100797 201863 100798 201863 100791 201863 100791 201864 100798 201864 100182 201864 100791 201865 100182 201865 100794 201865 100794 201866 100182 201866 100183 201866 100794 201867 100183 201867 100799 201867 100799 201868 100183 201868 100189 201868 100799 201869 100189 201869 100800 201869 100800 201870 100189 201870 100188 201870 100800 201871 100188 201871 100801 201871 100801 201872 100188 201872 100187 201872 100814 201873 99892 201873 100802 201873 100802 201874 99892 201874 100803 201874 100802 201875 100803 201875 100813 201875 100813 201876 100803 201876 100804 201876 100813 201877 100804 201877 100811 201877 100811 201878 100804 201878 104388 201878 100811 201879 104388 201879 100810 201879 100810 201880 104388 201880 104387 201880 100810 201881 104387 201881 100809 201881 100809 201882 104387 201882 100806 201882 100809 201883 100806 201883 100805 201883 100805 201884 100806 201884 100807 201884 100805 201885 100808 201885 100809 201885 100809 201886 100808 201886 100817 201886 100809 201887 100817 201887 100810 201887 100810 201888 100817 201888 100820 201888 100810 201889 100820 201889 100811 201889 100811 201890 100820 201890 100812 201890 100811 201891 100812 201891 100813 201891 100813 201892 100812 201892 100824 201892 100813 201893 100824 201893 100802 201893 100802 201894 100824 201894 100815 201894 100802 201895 100815 201895 100814 201895 100814 201896 100815 201896 100816 201896 100808 201897 100818 201897 100817 201897 100817 201898 100818 201898 100819 201898 100817 201899 100819 201899 100820 201899 100820 201900 100819 201900 100821 201900 100820 201901 100821 201901 100812 201901 100812 201902 100821 201902 100822 201902 100812 201903 100822 201903 100824 201903 100824 201904 100822 201904 100823 201904 100824 201905 100823 201905 100815 201905 100815 201906 100823 201906 100825 201906 100815 201907 100825 201907 100816 201907 100816 201908 100825 201908 100193 201908 100837 201909 100826 201909 100835 201909 100835 201910 100826 201910 104362 201910 100835 201911 104362 201911 100833 201911 100833 201912 104362 201912 100827 201912 100833 201913 100827 201913 100832 201913 100832 201914 100827 201914 100828 201914 100832 201915 100828 201915 100829 201915 100829 201916 100828 201916 104358 201916 100829 201917 104358 201917 100830 201917 100830 201918 104358 201918 104357 201918 100830 201919 104357 201919 99875 201919 99875 201920 104357 201920 104369 201920 99875 201921 99868 201921 100830 201921 100830 201922 99868 201922 100831 201922 100830 201923 100831 201923 100829 201923 100829 201924 100831 201924 100839 201924 100829 201925 100839 201925 100832 201925 100832 201926 100839 201926 100834 201926 100832 201927 100834 201927 100833 201927 100833 201928 100834 201928 100836 201928 100833 201929 100836 201929 100835 201929 100835 201930 100836 201930 100841 201930 100835 201931 100841 201931 100837 201931 100837 201932 100841 201932 99869 201932 99868 201933 100838 201933 100831 201933 100831 201934 100838 201934 100210 201934 100831 201935 100210 201935 100839 201935 100839 201936 100210 201936 100209 201936 100839 201937 100209 201937 100834 201937 100834 201938 100209 201938 100840 201938 100834 201939 100840 201939 100836 201939 100836 201940 100840 201940 100842 201940 100836 201941 100842 201941 100841 201941 100841 201942 100842 201942 100207 201942 100841 201943 100207 201943 99869 201943 99869 201944 100207 201944 100843 201944 99854 201945 104345 201945 100855 201945 100855 201946 104345 201946 104344 201946 100855 201947 104344 201947 100844 201947 100844 201948 104344 201948 100845 201948 100844 201949 100845 201949 100853 201949 100853 201950 100845 201950 100846 201950 100853 201951 100846 201951 100852 201951 100852 201952 100846 201952 104341 201952 100852 201953 104341 201953 100850 201953 100850 201954 104341 201954 104340 201954 100850 201955 104340 201955 100848 201955 100848 201956 104340 201956 100847 201956 100848 201957 100849 201957 100850 201957 100850 201958 100849 201958 100851 201958 100850 201959 100851 201959 100852 201959 100852 201960 100851 201960 100857 201960 100852 201961 100857 201961 100853 201961 100853 201962 100857 201962 100858 201962 100853 201963 100858 201963 100844 201963 100844 201964 100858 201964 100854 201964 100844 201965 100854 201965 100855 201965 100855 201966 100854 201966 100859 201966 100855 201967 100859 201967 99854 201967 99854 201968 100859 201968 99847 201968 100849 201969 100221 201969 100851 201969 100851 201970 100221 201970 100220 201970 100851 201971 100220 201971 100857 201971 100857 201972 100220 201972 100856 201972 100857 201973 100856 201973 100858 201973 100858 201974 100856 201974 100218 201974 100858 201975 100218 201975 100854 201975 100854 201976 100218 201976 100212 201976 100854 201977 100212 201977 100859 201977 100859 201978 100212 201978 100860 201978 100859 201979 100860 201979 99847 201979 99847 201980 100860 201980 100211 201980 100862 201981 100861 201981 100447 201981 100447 201982 100861 201982 100596 201982 100861 201983 100862 201983 100863 201983 100863 201984 100862 201984 100446 201984 100863 201985 100446 201985 100594 201985 100594 201986 100446 201986 100430 201986 100594 201987 100430 201987 100864 201987 100864 201988 100430 201988 100865 201988 100864 201989 100865 201989 100591 201989 100591 201990 100865 201990 100444 201990 100870 201991 100871 201991 100867 201991 100867 201992 100871 201992 100866 201992 100867 201993 100866 201993 100868 201993 100868 201994 100866 201994 100448 201994 100868 201995 100448 201995 100596 201995 100596 201996 100448 201996 100447 201996 100443 201997 100587 201997 100444 201997 100444 201998 100587 201998 100591 201998 100869 201999 100432 201999 100870 201999 100870 202000 100432 202000 100871 202000 100587 202001 100443 202001 100872 202001 100872 202002 100443 202002 100436 202002 100872 202003 100436 202003 100873 202003 100873 202004 100436 202004 100434 202004 100873 202005 100434 202005 100589 202005 100589 202006 100434 202006 100874 202006 100589 202007 100874 202007 100590 202007 100590 202008 100874 202008 100439 202008 100599 202009 100876 202009 100875 202009 100875 202010 100876 202010 100877 202010 100875 202011 100877 202011 100602 202011 100602 202012 100877 202012 100878 202012 100602 202013 100878 202013 100869 202013 100869 202014 100878 202014 100432 202014 100876 202015 100599 202015 100439 202015 100439 202016 100599 202016 100590 202016 100879 202017 100610 202017 100883 202017 100883 202018 100610 202018 100620 202018 100610 202019 100879 202019 100611 202019 100611 202020 100879 202020 100428 202020 100611 202021 100428 202021 100613 202021 100613 202022 100428 202022 100418 202022 100613 202023 100418 202023 100615 202023 100615 202024 100418 202024 100880 202024 100615 202025 100880 202025 100885 202025 100885 202026 100880 202026 100884 202026 100886 202027 100888 202027 100881 202027 100881 202028 100888 202028 100415 202028 100881 202029 100415 202029 100618 202029 100618 202030 100415 202030 100882 202030 100618 202031 100882 202031 100620 202031 100620 202032 100882 202032 100883 202032 100890 202033 100605 202033 100884 202033 100884 202034 100605 202034 100885 202034 100621 202035 100887 202035 100886 202035 100886 202036 100887 202036 100888 202036 100605 202037 100890 202037 100889 202037 100889 202038 100890 202038 100891 202038 100889 202039 100891 202039 100892 202039 100892 202040 100891 202040 100411 202040 100892 202041 100411 202041 100893 202041 100893 202042 100411 202042 100420 202042 100893 202043 100420 202043 100626 202043 100626 202044 100420 202044 100421 202044 100895 202045 100427 202045 100624 202045 100624 202046 100427 202046 100426 202046 100624 202047 100426 202047 100894 202047 100894 202048 100426 202048 100423 202048 100894 202049 100423 202049 100621 202049 100621 202050 100423 202050 100887 202050 100427 202051 100895 202051 100421 202051 100421 202052 100895 202052 100626 202052 101106 202053 100320 202053 101109 202053 101109 202054 100320 202054 100896 202054 101109 202055 100896 202055 100897 202055 100897 202056 100896 202056 100898 202056 101077 202057 100042 202057 100899 202057 100899 202058 100042 202058 100901 202058 100899 202059 100901 202059 100900 202059 100900 202060 100901 202060 100902 202060 100296 202061 100295 202061 100903 202061 100296 202062 100903 202062 101119 202062 101119 202063 100903 202063 100905 202063 101119 202064 100905 202064 100904 202064 100904 202065 100905 202065 100906 202065 100904 202066 100906 202066 101120 202066 101120 202067 100906 202067 100907 202067 101120 202068 100907 202068 101122 202068 101122 202069 100907 202069 101123 202069 101123 202070 100907 202070 100908 202070 101123 202071 100908 202071 99845 202071 100452 202072 100340 202072 101057 202072 101057 202073 100340 202073 100911 202073 101057 202074 100911 202074 100909 202074 100909 202075 100911 202075 100910 202075 100910 202076 100911 202076 100913 202076 100910 202077 100913 202077 100912 202077 100912 202078 100913 202078 100914 202078 100914 202079 100913 202079 100348 202079 100914 202080 100348 202080 101059 202080 101059 202081 100348 202081 100915 202081 101059 202082 100915 202082 101058 202082 101058 202083 100915 202083 100916 202083 101058 202084 100916 202084 100297 202084 100917 202085 99844 202085 100367 202085 100917 202086 100367 202086 100371 202086 100371 202087 100367 202087 100365 202087 100371 202088 100365 202088 100370 202088 100370 202089 100365 202089 100918 202089 100370 202090 100918 202090 100919 202090 100919 202091 100918 202091 100362 202091 100919 202092 100362 202092 100920 202092 100920 202093 100362 202093 100921 202093 100920 202094 100921 202094 100923 202094 100923 202095 100921 202095 100922 202095 100923 202096 100922 202096 100924 202096 100924 202097 100922 202097 100360 202097 100924 202098 100360 202098 100925 202098 100925 202099 100360 202099 100357 202099 100925 202100 100357 202100 100372 202100 100372 202101 100357 202101 100926 202101 100372 202102 100926 202102 100369 202102 100369 202103 100926 202103 100355 202103 100369 202104 100355 202104 100927 202104 100927 202105 100355 202105 100929 202105 100927 202106 100929 202106 100928 202106 100928 202107 100929 202107 100930 202107 100928 202108 100930 202108 100400 202108 100400 202109 100930 202109 100354 202109 100400 202110 100354 202110 100398 202110 100398 202111 100354 202111 100353 202111 100398 202112 100353 202112 100931 202112 100931 202113 100353 202113 99827 202113 100931 202114 99827 202114 100932 202114 100997 202115 100992 202115 100933 202115 100933 202116 100992 202116 100994 202116 100934 202117 100984 202117 100935 202117 100935 202118 100984 202118 100962 202118 100936 202119 100937 202119 100998 202119 100986 202120 100988 202120 100987 202120 100977 202121 100939 202121 100978 202121 100377 202122 100376 202122 99785 202122 100954 202123 100377 202123 100938 202123 100389 202124 100950 202124 100963 202124 100394 202125 100393 202125 100942 202125 100968 202126 100955 202126 100972 202126 100394 202127 100939 202127 100940 202127 100940 202128 100939 202128 100977 202128 100940 202129 100977 202129 100941 202129 100942 202130 100393 202130 100943 202130 100943 202131 100393 202131 100392 202131 100943 202132 100392 202132 100944 202132 100944 202133 100392 202133 100945 202133 100944 202134 100945 202134 100946 202134 100946 202135 100945 202135 100391 202135 100946 202136 100391 202136 100947 202136 100389 202137 100988 202137 100948 202137 100948 202138 100988 202138 100986 202138 100948 202139 100986 202139 100949 202139 100963 202140 100950 202140 100965 202140 100965 202141 100950 202141 100383 202141 100965 202142 100383 202142 100951 202142 100951 202143 100383 202143 100382 202143 100951 202144 100382 202144 100952 202144 100952 202145 100382 202145 100381 202145 100952 202146 100381 202146 100953 202146 100954 202147 100937 202147 100379 202147 100379 202148 100937 202148 100936 202148 100379 202149 100936 202149 100380 202149 100958 202150 100974 202150 100971 202150 100955 202151 100956 202151 100971 202151 100971 202152 100956 202152 100957 202152 100971 202153 100957 202153 100958 202153 100958 202154 100957 202154 100976 202154 100958 202155 100976 202155 100079 202155 100079 202156 100976 202156 100077 202156 100959 202157 100942 202157 100960 202157 100960 202158 100942 202158 100943 202158 100960 202159 100943 202159 100961 202159 100961 202160 100943 202160 100944 202160 100961 202161 100944 202161 100981 202161 100981 202162 100944 202162 100946 202162 100981 202163 100946 202163 100962 202163 100962 202164 100946 202164 100947 202164 100962 202165 100947 202165 100935 202165 100991 202166 100963 202166 100964 202166 100964 202167 100963 202167 100965 202167 100964 202168 100965 202168 100966 202168 100966 202169 100965 202169 100951 202169 100966 202170 100951 202170 100967 202170 100967 202171 100951 202171 100952 202171 100967 202172 100952 202172 100994 202172 100994 202173 100952 202173 100953 202173 100994 202174 100953 202174 100933 202174 100968 202175 100972 202175 100969 202175 100969 202176 100972 202176 100970 202176 100969 202177 100970 202177 99825 202177 99825 202178 100970 202178 100084 202178 99825 202179 100084 202179 99826 202179 100955 202180 100971 202180 100972 202180 100972 202181 100971 202181 100974 202181 100972 202182 100974 202182 100970 202182 100970 202183 100974 202183 100973 202183 100970 202184 100973 202184 100084 202184 100079 202185 100080 202185 100958 202185 100958 202186 100080 202186 100975 202186 100958 202187 100975 202187 100974 202187 100974 202188 100975 202188 100081 202188 100974 202189 100081 202189 100973 202189 100956 202190 100941 202190 100957 202190 100957 202191 100941 202191 100977 202191 100957 202192 100977 202192 100976 202192 100976 202193 100977 202193 100978 202193 100976 202194 100978 202194 100077 202194 100077 202195 100978 202195 100980 202195 100394 202196 100942 202196 100939 202196 100939 202197 100942 202197 100959 202197 100939 202198 100959 202198 100978 202198 100978 202199 100959 202199 100979 202199 100978 202200 100979 202200 100980 202200 100981 202201 100075 202201 100961 202201 100961 202202 100075 202202 100982 202202 100961 202203 100982 202203 100960 202203 100960 202204 100982 202204 100983 202204 100960 202205 100983 202205 100959 202205 100959 202206 100983 202206 100078 202206 100959 202207 100078 202207 100979 202207 100984 202208 100072 202208 100962 202208 100962 202209 100072 202209 100985 202209 100962 202210 100985 202210 100981 202210 100981 202211 100985 202211 100076 202211 100981 202212 100076 202212 100075 202212 100391 202213 100949 202213 100947 202213 100947 202214 100949 202214 100986 202214 100947 202215 100986 202215 100935 202215 100935 202216 100986 202216 100987 202216 100935 202217 100987 202217 100934 202217 100934 202218 100987 202218 100989 202218 100389 202219 100963 202219 100988 202219 100988 202220 100963 202220 100991 202220 100988 202221 100991 202221 100987 202221 100987 202222 100991 202222 100070 202222 100987 202223 100070 202223 100989 202223 100967 202224 100996 202224 100966 202224 100966 202225 100996 202225 100067 202225 100966 202226 100067 202226 100964 202226 100964 202227 100067 202227 100990 202227 100964 202228 100990 202228 100991 202228 100991 202229 100990 202229 100068 202229 100991 202230 100068 202230 100070 202230 100992 202231 100993 202231 100994 202231 100994 202232 100993 202232 100995 202232 100994 202233 100995 202233 100967 202233 100967 202234 100995 202234 100066 202234 100967 202235 100066 202235 100996 202235 100381 202236 100380 202236 100953 202236 100953 202237 100380 202237 100936 202237 100953 202238 100936 202238 100933 202238 100933 202239 100936 202239 100998 202239 100933 202240 100998 202240 100997 202240 100997 202241 100998 202241 100062 202241 100999 202242 100064 202242 100063 202242 100954 202243 100938 202243 100937 202243 100937 202244 100938 202244 100999 202244 100937 202245 100999 202245 100998 202245 100998 202246 100999 202246 100063 202246 100998 202247 100063 202247 100062 202247 100377 202248 99785 202248 100938 202248 100938 202249 99785 202249 99786 202249 100938 202250 99786 202250 100999 202250 100999 202251 99786 202251 100061 202251 100999 202252 100061 202252 100064 202252 99755 202253 101004 202253 101005 202253 101002 202254 101004 202254 99755 202254 99747 202255 101002 202255 99755 202255 99755 202256 101000 202256 99746 202256 101007 202257 101000 202257 99755 202257 101005 202258 101007 202258 99755 202258 99747 202259 101001 202259 101002 202259 101002 202260 101001 202260 101003 202260 101002 202261 101003 202261 101004 202261 101004 202262 101003 202262 101009 202262 101004 202263 101009 202263 101005 202263 101005 202264 101009 202264 101006 202264 101005 202265 101006 202265 101007 202265 101007 202266 101006 202266 101012 202266 101007 202267 101012 202267 101000 202267 101000 202268 101012 202268 101008 202268 101000 202269 101008 202269 99746 202269 99746 202270 101008 202270 99742 202270 101001 202271 100410 202271 101003 202271 101003 202272 100410 202272 101010 202272 101003 202273 101010 202273 101009 202273 101009 202274 101010 202274 100406 202274 101009 202275 100406 202275 101006 202275 101006 202276 100406 202276 101011 202276 101006 202277 101011 202277 101012 202277 101012 202278 101011 202278 100419 202278 101012 202279 100419 202279 101008 202279 101008 202280 100419 202280 100412 202280 101008 202281 100412 202281 99742 202281 99742 202282 100412 202282 101013 202282 99730 202283 101014 202283 101015 202283 101020 202284 101014 202284 99730 202284 101016 202285 101020 202285 99730 202285 99730 202286 101017 202286 101018 202286 101019 202287 101017 202287 99730 202287 101015 202288 101019 202288 99730 202288 101016 202289 99721 202289 101020 202289 101020 202290 99721 202290 101022 202290 101020 202291 101022 202291 101014 202291 101014 202292 101022 202292 101021 202292 101014 202293 101021 202293 101015 202293 101015 202294 101021 202294 101023 202294 101015 202295 101023 202295 101019 202295 101019 202296 101023 202296 101024 202296 101019 202297 101024 202297 101017 202297 101017 202298 101024 202298 101026 202298 101017 202299 101026 202299 101018 202299 101018 202300 101026 202300 101027 202300 99721 202301 99722 202301 101022 202301 101022 202302 99722 202302 100442 202302 101022 202303 100442 202303 101021 202303 101021 202304 100442 202304 100441 202304 101021 202305 100441 202305 101023 202305 101023 202306 100441 202306 100433 202306 101023 202307 100433 202307 101024 202307 101024 202308 100433 202308 101025 202308 101024 202309 101025 202309 101026 202309 101026 202310 101025 202310 100435 202310 101026 202311 100435 202311 101027 202311 101027 202312 100435 202312 99712 202312 101028 202313 101029 202313 101034 202313 101032 202314 101029 202314 101028 202314 101030 202315 101032 202315 101028 202315 101028 202316 101038 202316 99701 202316 101037 202317 101038 202317 101028 202317 101034 202318 101037 202318 101028 202318 101030 202319 101031 202319 101032 202319 101032 202320 101031 202320 101033 202320 101032 202321 101033 202321 101029 202321 101029 202322 101033 202322 101035 202322 101029 202323 101035 202323 101034 202323 101034 202324 101035 202324 101039 202324 101034 202325 101039 202325 101037 202325 101037 202326 101039 202326 101036 202326 101037 202327 101036 202327 101038 202327 101038 202328 101036 202328 101041 202328 101038 202329 101041 202329 99701 202329 99701 202330 101041 202330 99702 202330 101031 202331 100416 202331 101033 202331 101033 202332 100416 202332 100424 202332 101033 202333 100424 202333 101035 202333 101035 202334 100424 202334 100425 202334 101035 202335 100425 202335 101039 202335 101039 202336 100425 202336 101040 202336 101039 202337 101040 202337 101036 202337 101036 202338 101040 202338 100413 202338 101036 202339 100413 202339 101041 202339 101041 202340 100413 202340 100409 202340 101041 202341 100409 202341 99702 202341 99702 202342 100409 202342 99698 202342 100311 202343 101045 202343 101046 202343 101046 202344 101045 202344 100529 202344 100304 202345 101042 202345 100523 202345 100304 202346 100523 202346 101043 202346 101043 202347 100523 202347 101044 202347 101043 202348 101044 202348 100310 202348 100310 202349 101044 202349 101045 202349 100310 202350 101045 202350 100311 202350 101046 202351 100529 202351 100528 202351 101046 202352 100528 202352 100314 202352 100314 202353 100528 202353 100526 202353 100314 202354 100526 202354 100312 202354 100526 202355 101047 202355 100312 202355 100312 202356 101047 202356 100488 202356 100312 202357 100488 202357 100313 202357 101053 202358 101052 202358 100304 202358 100304 202359 101052 202359 101042 202359 100519 202360 100309 202360 100488 202360 100488 202361 100309 202361 100313 202361 100305 202362 101055 202362 101048 202362 100305 202363 101048 202363 101049 202363 101049 202364 101048 202364 101051 202364 101049 202365 101051 202365 101050 202365 101050 202366 101051 202366 101052 202366 101050 202367 101052 202367 101053 202367 100309 202368 100519 202368 100521 202368 100309 202369 100521 202369 100308 202369 100308 202370 100521 202370 101054 202370 100308 202371 101054 202371 100307 202371 100307 202372 101054 202372 100352 202372 100307 202373 100352 202373 100306 202373 100352 202374 101055 202374 100306 202374 100306 202375 101055 202375 100305 202375 101056 202376 100454 202376 101057 202376 101057 202377 100909 202377 101056 202377 101056 202378 100909 202378 100910 202378 101056 202379 100910 202379 100912 202379 100297 202380 101062 202380 101058 202380 101058 202381 101062 202381 100199 202381 101058 202382 100199 202382 101059 202382 101059 202383 100199 202383 100200 202383 101059 202384 100200 202384 100914 202384 100914 202385 100200 202385 101060 202385 100914 202386 101060 202386 100912 202386 100912 202387 101060 202387 101061 202387 100912 202388 101061 202388 101056 202388 101062 202389 100297 202389 101063 202389 101063 202390 100297 202390 101064 202390 101063 202391 101064 202391 101065 202391 101065 202392 101064 202392 100301 202392 101065 202393 100301 202393 101066 202393 101066 202394 100301 202394 101067 202394 101067 202395 100301 202395 101068 202395 101067 202396 101068 202396 101069 202396 101068 202397 100300 202397 101069 202397 101069 202398 100300 202398 100303 202398 101069 202399 100303 202399 101070 202399 100303 202400 101071 202400 101070 202400 101070 202401 101071 202401 101072 202401 101070 202402 101072 202402 100217 202402 100217 202403 101072 202403 101073 202403 100217 202404 101073 202404 100222 202404 101073 202405 101074 202405 100222 202405 100222 202406 101074 202406 101075 202406 100222 202407 101075 202407 101076 202407 101077 202408 101078 202408 100227 202408 101077 202409 100227 202409 100040 202409 101075 202410 100037 202410 101076 202410 101076 202411 100037 202411 100039 202411 101076 202412 100039 202412 100215 202412 100215 202413 100039 202413 100040 202413 100215 202414 100040 202414 100214 202414 100214 202415 100040 202415 100227 202415 100900 202416 100231 202416 100899 202416 100899 202417 100231 202417 100230 202417 100899 202418 100230 202418 101077 202418 101077 202419 100230 202419 101078 202419 100486 202420 101079 202420 100900 202420 100900 202421 101079 202421 100231 202421 101079 202422 100486 202422 100570 202422 101079 202423 100570 202423 100226 202423 100226 202424 100570 202424 100568 202424 100226 202425 100568 202425 101080 202425 100568 202426 101081 202426 101080 202426 101080 202427 101081 202427 101082 202427 101080 202428 101082 202428 100233 202428 101083 202429 101084 202429 101082 202429 101082 202430 101084 202430 100233 202430 101084 202431 101083 202431 101085 202431 101084 202432 101085 202432 101086 202432 101086 202433 101085 202433 101087 202433 101086 202434 101087 202434 100236 202434 100514 202435 101088 202435 101087 202435 101087 202436 101088 202436 100236 202436 101088 202437 100514 202437 100515 202437 101088 202438 100515 202438 101090 202438 101090 202439 100515 202439 101089 202439 101090 202440 101089 202440 100235 202440 100235 202441 101089 202441 100278 202441 100235 202442 100278 202442 101091 202442 101091 202443 100278 202443 100280 202443 101091 202444 100280 202444 100224 202444 100224 202445 100280 202445 100282 202445 100224 202446 100282 202446 100225 202446 100225 202447 100282 202447 101092 202447 100225 202448 101092 202448 100213 202448 100213 202449 101092 202449 101093 202449 100213 202450 101093 202450 101094 202450 101094 202451 101093 202451 100044 202451 101094 202452 100044 202452 100208 202452 101095 202453 99679 202453 101096 202453 101095 202454 101096 202454 100144 202454 100144 202455 101096 202455 100512 202455 100144 202456 100512 202456 100139 202456 100139 202457 100512 202457 101097 202457 100139 202458 101097 202458 100141 202458 101098 202459 100142 202459 101097 202459 101097 202460 100142 202460 100141 202460 100142 202461 101098 202461 101099 202461 100142 202462 101099 202462 100143 202462 100143 202463 101099 202463 100559 202463 100143 202464 100559 202464 100137 202464 101100 202465 101101 202465 100559 202465 100559 202466 101101 202466 100137 202466 101101 202467 101100 202467 100564 202467 101101 202468 100564 202468 100136 202468 100136 202469 100564 202469 101102 202469 100136 202470 101102 202470 101103 202470 101103 202471 101102 202471 101104 202471 101103 202472 101104 202472 101105 202472 101106 202473 101107 202473 101104 202473 101104 202474 101107 202474 101105 202474 100897 202475 101108 202475 101109 202475 101109 202476 101108 202476 101110 202476 101109 202477 101110 202477 101106 202477 101106 202478 101110 202478 101107 202478 101111 202479 100159 202479 100285 202479 100285 202480 100291 202480 101111 202480 101111 202481 100291 202481 100290 202481 101111 202482 100290 202482 101112 202482 100290 202483 101113 202483 101112 202483 101112 202484 101113 202484 100288 202484 101112 202485 100288 202485 101114 202485 101114 202486 100288 202486 100287 202486 101114 202487 100287 202487 100292 202487 100164 202488 101115 202488 100292 202488 100292 202489 101115 202489 101116 202489 100292 202490 101116 202490 101114 202490 100296 202491 100177 202491 100294 202491 100294 202492 100177 202492 100164 202492 100294 202493 100164 202493 101117 202493 101117 202494 100164 202494 100292 202494 99845 202495 99846 202495 100460 202495 100177 202496 100296 202496 101118 202496 101118 202497 100296 202497 101119 202497 101118 202498 101119 202498 100170 202498 100170 202499 101119 202499 100904 202499 100170 202500 100904 202500 101121 202500 101121 202501 100904 202501 101120 202501 101121 202502 101120 202502 100461 202502 100461 202503 101120 202503 101122 202503 100461 202504 101122 202504 100460 202504 100460 202505 101122 202505 101123 202505 100460 202506 101123 202506 99845 202506 101129 202507 101124 202507 100576 202507 100576 202508 101124 202508 101125 202508 100576 202509 101125 202509 101126 202509 101126 202510 101125 202510 100566 202510 100532 202511 101127 202511 100531 202511 100531 202512 101127 202512 101128 202512 100531 202513 101128 202513 101129 202513 101129 202514 101128 202514 101124 202514 101131 202515 100492 202515 100505 202515 100524 202516 100581 202516 101130 202516 101130 202517 100581 202517 100522 202517 100524 202518 101131 202518 100581 202518 100581 202519 101131 202519 100505 202519 100581 202520 100505 202520 101132 202520 101132 202521 100505 202521 101134 202521 101132 202522 101134 202522 101133 202522 101133 202523 101134 202523 101135 202523 101133 202524 101135 202524 100532 202524 100532 202525 101135 202525 101127 202525 100496 202526 100502 202526 101138 202526 100015 202527 100494 202527 101136 202527 101136 202528 100494 202528 100496 202528 101136 202529 100496 202529 101137 202529 101137 202530 100496 202530 101138 202530 101137 202531 101138 202531 100013 202531 100025 202532 101139 202532 100019 202532 100019 202533 101139 202533 100561 202533 100019 202534 100561 202534 100509 202534 100506 202535 100017 202535 100509 202535 100509 202536 100017 202536 100018 202536 100509 202537 100018 202537 100019 202537 100489 202538 101140 202538 101141 202538 101140 202539 101142 202539 101141 202539 101141 202540 101142 202540 100525 202540 101141 202541 100525 202541 100583 202541 101146 202542 100498 202542 100586 202542 100586 202543 100498 202543 101143 202543 100586 202544 101143 202544 100585 202544 100585 202545 101143 202545 101144 202545 100585 202546 101144 202546 101141 202546 101141 202547 101144 202547 100495 202547 101141 202548 100495 202548 100489 202548 100573 202549 101145 202549 100535 202549 100535 202550 101145 202550 100497 202550 100535 202551 100497 202551 101146 202551 101146 202552 100497 202552 100498 202552 100562 202553 100499 202553 101147 202553 101147 202554 100499 202554 100501 202554 101147 202555 100501 202555 100573 202555 100573 202556 100501 202556 101145 202556 101152 202557 100014 202557 101148 202557 104290 202558 101152 202558 101778 202558 101778 202559 101152 202559 101148 202559 101778 202560 101148 202560 101149 202560 101150 202561 101155 202561 101151 202561 101150 202562 101151 202562 104288 202562 104288 202563 101151 202563 100520 202563 104288 202564 100520 202564 104289 202564 104289 202565 100520 202565 101152 202565 104289 202566 101152 202566 104290 202566 101153 202567 101155 202567 101154 202567 101154 202568 101155 202568 101150 202568 101156 202569 100491 202569 100518 202569 101156 202570 100518 202570 104282 202570 104282 202571 100518 202571 100517 202571 104282 202572 100517 202572 104286 202572 104286 202573 100517 202573 101153 202573 104286 202574 101153 202574 101154 202574 104283 202575 100020 202575 101157 202575 101156 202576 104283 202576 100491 202576 100491 202577 104283 202577 101157 202577 100491 202578 101157 202578 100490 202578 101158 202579 101159 202579 100504 202579 100022 202580 101158 202580 100023 202580 100023 202581 101158 202581 100504 202581 100023 202582 100504 202582 100024 202582 104294 202583 100503 202583 101159 202583 101159 202584 100503 202584 100504 202584 104296 202585 100279 202585 100516 202585 104296 202586 100516 202586 104295 202586 104295 202587 100516 202587 101160 202587 104295 202588 101160 202588 101161 202588 101161 202589 101160 202589 100503 202589 101161 202590 100503 202590 104294 202590 104313 202591 101162 202591 101163 202591 104313 202592 101163 202592 104325 202592 104325 202593 101163 202593 101164 202593 104325 202594 101164 202594 101165 202594 101165 202595 101164 202595 101166 202595 101165 202596 101166 202596 101167 202596 101167 202597 101166 202597 101168 202597 101167 202598 101168 202598 104322 202598 104322 202599 101168 202599 100060 202599 104322 202600 100060 202600 104321 202600 101171 202601 100513 202601 100511 202601 101171 202602 100511 202602 101169 202602 101169 202603 100511 202603 100510 202603 101169 202604 100510 202604 104312 202604 104312 202605 100510 202605 101162 202605 104312 202606 101162 202606 104313 202606 101170 202607 100493 202607 101171 202607 101171 202608 100493 202608 100513 202608 100493 202609 101170 202609 104292 202609 104292 202610 101172 202610 100493 202610 100493 202611 101172 202611 101173 202611 100493 202612 101173 202612 100012 202612 99647 202613 101175 202613 101174 202613 101177 202614 101175 202614 99647 202614 101176 202615 101177 202615 99647 202615 99647 202616 100246 202616 100250 202616 100245 202617 100246 202617 99647 202617 101174 202618 100245 202618 99647 202618 99644 202619 100248 202619 100249 202619 100240 202620 100248 202620 99644 202620 100274 202621 100240 202621 99644 202621 99644 202622 101178 202622 100276 202622 100277 202623 101178 202623 99644 202623 100249 202624 100277 202624 99644 202624 99641 202625 100256 202625 100267 202625 101179 202626 100256 202626 99641 202626 100270 202627 101179 202627 99641 202627 99641 202628 101180 202628 101181 202628 101182 202629 101180 202629 99641 202629 100267 202630 101182 202630 99641 202630 99638 202631 100252 202631 101183 202631 101184 202632 100252 202632 99638 202632 100260 202633 101184 202633 99638 202633 99638 202634 100239 202634 100262 202634 100242 202635 100239 202635 99638 202635 101183 202636 100242 202636 99638 202636 100622 202637 100617 202637 101185 202637 101186 202638 100607 202638 100608 202638 101186 202639 100608 202639 100606 202639 101185 202640 100617 202640 101188 202640 101188 202641 100617 202641 101187 202641 101188 202642 101187 202642 100619 202642 100612 202643 100614 202643 100609 202643 100609 202644 100614 202644 101188 202644 100609 202645 101188 202645 100616 202645 100616 202646 101188 202646 100619 202646 101190 202647 100623 202647 101189 202647 101189 202648 100625 202648 101190 202648 101190 202649 100625 202649 100622 202649 101190 202650 100622 202650 100608 202650 100608 202651 100622 202651 101185 202651 100608 202652 101185 202652 100606 202652 100597 202653 101193 202653 101197 202653 100588 202654 101191 202654 100603 202654 101194 202655 101195 202655 101192 202655 100588 202656 100603 202656 101198 202656 101197 202657 101193 202657 101192 202657 101192 202658 101193 202658 100598 202658 101192 202659 100598 202659 101194 202659 101195 202660 100592 202660 101192 202660 101192 202661 100592 202661 100593 202661 101192 202662 100593 202662 100595 202662 100604 202663 101196 202663 100600 202663 100600 202664 100601 202664 100604 202664 100604 202665 100601 202665 100597 202665 100604 202666 100597 202666 100603 202666 100603 202667 100597 202667 101197 202667 100603 202668 101197 202668 101198 202668 99630 202669 101199 202669 99632 202669 99632 202670 101199 202670 101200 202670 99630 202671 101201 202671 101199 202671 101199 202672 101201 202672 101202 202672 101199 202673 101202 202673 101203 202673 101203 202674 99628 202674 101199 202674 101199 202675 99628 202675 101204 202675 101199 202676 101204 202676 101211 202676 101199 202677 101371 202677 101200 202677 101200 202678 101371 202678 101369 202678 101200 202679 101369 202679 101206 202679 101206 202680 101369 202680 101368 202680 101368 202681 101366 202681 101206 202681 101206 202682 101366 202682 101364 202682 101206 202683 101364 202683 101205 202683 101205 202684 101362 202684 101206 202684 101206 202685 101362 202685 101361 202685 101206 202686 101361 202686 101207 202686 101208 202687 101357 202687 101209 202687 101209 202688 101357 202688 101360 202688 101207 202689 101210 202689 101206 202689 101206 202690 101210 202690 101360 202690 101206 202691 101360 202691 101356 202691 101356 202692 101360 202692 101357 202692 101211 202693 99625 202693 101199 202693 101199 202694 99625 202694 101212 202694 101199 202695 101212 202695 99623 202695 99623 202696 101212 202696 101213 202696 99338 202697 99336 202697 98930 202697 98930 202698 99336 202698 99334 202698 98930 202699 99334 202699 98929 202699 98929 202700 99334 202700 99332 202700 98929 202701 99332 202701 98928 202701 98928 202702 99332 202702 101214 202702 98928 202703 101214 202703 101215 202703 101215 202704 101214 202704 101216 202704 101215 202705 101216 202705 101217 202705 101217 202706 101216 202706 101218 202706 101217 202707 101218 202707 103120 202707 103120 202708 101218 202708 101790 202708 103120 202709 101790 202709 101219 202709 101219 202710 101790 202710 101788 202710 101219 202711 101788 202711 103117 202711 103117 202712 101788 202712 101786 202712 103117 202713 101786 202713 101220 202713 101220 202714 101786 202714 101221 202714 101220 202715 101221 202715 103116 202715 103116 202716 101221 202716 101222 202716 103116 202717 101222 202717 101223 202717 101223 202718 101222 202718 101224 202718 101223 202719 101224 202719 98935 202719 98935 202720 101224 202720 99340 202720 98935 202721 99340 202721 98933 202721 98933 202722 99340 202722 99338 202722 98933 202723 99338 202723 98930 202723 99328 202724 99326 202724 101225 202724 101225 202725 99326 202725 99325 202725 101225 202726 99325 202726 98966 202726 98966 202727 99325 202727 101226 202727 98966 202728 101226 202728 98964 202728 98964 202729 101226 202729 99322 202729 98964 202730 99322 202730 101227 202730 101227 202731 99322 202731 101228 202731 101227 202732 101228 202732 102875 202732 102875 202733 101228 202733 101799 202733 102875 202734 101799 202734 101229 202734 101229 202735 101799 202735 101797 202735 101229 202736 101797 202736 102873 202736 102873 202737 101797 202737 101231 202737 102873 202738 101231 202738 101230 202738 101230 202739 101231 202739 101792 202739 101230 202740 101792 202740 101232 202740 101232 202741 101792 202741 101233 202741 101232 202742 101233 202742 98972 202742 98972 202743 101233 202743 101234 202743 98972 202744 101234 202744 98970 202744 98970 202745 101234 202745 99329 202745 98970 202746 99329 202746 98969 202746 98969 202747 99329 202747 99328 202747 98969 202748 99328 202748 101225 202748 101249 202749 101235 202749 98976 202749 98976 202750 101235 202750 101236 202750 98976 202751 101236 202751 98975 202751 98975 202752 101236 202752 99318 202752 98975 202753 99318 202753 98974 202753 98974 202754 99318 202754 99317 202754 98974 202755 99317 202755 98973 202755 98973 202756 99317 202756 101237 202756 98973 202757 101237 202757 102870 202757 102870 202758 101237 202758 101238 202758 102870 202759 101238 202759 101239 202759 101239 202760 101238 202760 101240 202760 101239 202761 101240 202761 102868 202761 102868 202762 101240 202762 101805 202762 102868 202763 101805 202763 101241 202763 101241 202764 101805 202764 101802 202764 101241 202765 101802 202765 101242 202765 101242 202766 101802 202766 101801 202766 101242 202767 101801 202767 101243 202767 101243 202768 101801 202768 101245 202768 101243 202769 101245 202769 101244 202769 101244 202770 101245 202770 101246 202770 101244 202771 101246 202771 98978 202771 98978 202772 101246 202772 101247 202772 98978 202773 101247 202773 101248 202773 101248 202774 101247 202774 101249 202774 101248 202775 101249 202775 98976 202775 101250 202776 101252 202776 101251 202776 101251 202777 101252 202777 99312 202777 101251 202778 99312 202778 98980 202778 98980 202779 99312 202779 101253 202779 98980 202780 101253 202780 101254 202780 101254 202781 101253 202781 99310 202781 101254 202782 99310 202782 101256 202782 101256 202783 99310 202783 101255 202783 101256 202784 101255 202784 102865 202784 102865 202785 101255 202785 101258 202785 102865 202786 101258 202786 101257 202786 101257 202787 101258 202787 101259 202787 101257 202788 101259 202788 101260 202788 101260 202789 101259 202789 101261 202789 101260 202790 101261 202790 102862 202790 102862 202791 101261 202791 101262 202791 102862 202792 101262 202792 102861 202792 102861 202793 101262 202793 101263 202793 102861 202794 101263 202794 98984 202794 98984 202795 101263 202795 99314 202795 98984 202796 99314 202796 98983 202796 98983 202797 99314 202797 101264 202797 98983 202798 101264 202798 98982 202798 98982 202799 101264 202799 101250 202799 98982 202800 101250 202800 101251 202800 101265 202801 101266 202801 101275 202801 101275 202802 101266 202802 99307 202802 101275 202803 99307 202803 98987 202803 98987 202804 99307 202804 99306 202804 98987 202805 99306 202805 98985 202805 98985 202806 99306 202806 99304 202806 98985 202807 99304 202807 101267 202807 101267 202808 99304 202808 101268 202808 101267 202809 101268 202809 102859 202809 102859 202810 101268 202810 101819 202810 102859 202811 101819 202811 102857 202811 102857 202812 101819 202812 101269 202812 102857 202813 101269 202813 102856 202813 102856 202814 101269 202814 101818 202814 102856 202815 101818 202815 102855 202815 102855 202816 101818 202816 101270 202816 102855 202817 101270 202817 102853 202817 102853 202818 101270 202818 101814 202818 102853 202819 101814 202819 101271 202819 101271 202820 101814 202820 101272 202820 101271 202821 101272 202821 101273 202821 101273 202822 101272 202822 101274 202822 101273 202823 101274 202823 98989 202823 98989 202824 101274 202824 101265 202824 98989 202825 101265 202825 101275 202825 99302 202826 101287 202826 101276 202826 101276 202827 101287 202827 101277 202827 101276 202828 101277 202828 101823 202828 101823 202829 101277 202829 101278 202829 101823 202830 101278 202830 101279 202830 101279 202831 101278 202831 102848 202831 101279 202832 102848 202832 101280 202832 101280 202833 102848 202833 102849 202833 101280 202834 102849 202834 101827 202834 101827 202835 102849 202835 101281 202835 101827 202836 101281 202836 101829 202836 101829 202837 101281 202837 102851 202837 101829 202838 102851 202838 101282 202838 101282 202839 102851 202839 98991 202839 101282 202840 98991 202840 101283 202840 101283 202841 98991 202841 101284 202841 101283 202842 101284 202842 99297 202842 99297 202843 101284 202843 98994 202843 99297 202844 98994 202844 101285 202844 101285 202845 98994 202845 98995 202845 101285 202846 98995 202846 101286 202846 101286 202847 98995 202847 98998 202847 101286 202848 98998 202848 99302 202848 99302 202849 98998 202849 101287 202849 101300 202850 101288 202850 101289 202850 101289 202851 101288 202851 101830 202851 101289 202852 101830 202852 101290 202852 101290 202853 101830 202853 101291 202853 101290 202854 101291 202854 102843 202854 102843 202855 101291 202855 101292 202855 102843 202856 101292 202856 99007 202856 99007 202857 101292 202857 101293 202857 99007 202858 101293 202858 99006 202858 99006 202859 101293 202859 99294 202859 99006 202860 99294 202860 99004 202860 99004 202861 99294 202861 99291 202861 99004 202862 99291 202862 101295 202862 101295 202863 99291 202863 101294 202863 101295 202864 101294 202864 101296 202864 101296 202865 101294 202865 99289 202865 101296 202866 99289 202866 101297 202866 101297 202867 99289 202867 99287 202867 101297 202868 99287 202868 102845 202868 102845 202869 99287 202869 101298 202869 102845 202870 101298 202870 101299 202870 101299 202871 101298 202871 101832 202871 101299 202872 101832 202872 101300 202872 101300 202873 101832 202873 101301 202873 101300 202874 101301 202874 101288 202874 99286 202875 99284 202875 99010 202875 99010 202876 99284 202876 99283 202876 99010 202877 99283 202877 101302 202877 101302 202878 99283 202878 99281 202878 101302 202879 99281 202879 101303 202879 101303 202880 99281 202880 99279 202880 101303 202881 99279 202881 101304 202881 101304 202882 99279 202882 99277 202882 101304 202883 99277 202883 101305 202883 101305 202884 99277 202884 101307 202884 101305 202885 101307 202885 101306 202885 101306 202886 101307 202886 101839 202886 101306 202887 101839 202887 102841 202887 102841 202888 101839 202888 101836 202888 102841 202889 101836 202889 102839 202889 102839 202890 101836 202890 101308 202890 102839 202891 101308 202891 102837 202891 102837 202892 101308 202892 101834 202892 102837 202893 101834 202893 99012 202893 99012 202894 101834 202894 101310 202894 99012 202895 101310 202895 101309 202895 101309 202896 101310 202896 101311 202896 101309 202897 101311 202897 101312 202897 101312 202898 101311 202898 99286 202898 101312 202899 99286 202899 99010 202899 101322 202900 101313 202900 101323 202900 101323 202901 101313 202901 101314 202901 101323 202902 101314 202902 102832 202902 102832 202903 101314 202903 101842 202903 102832 202904 101842 202904 101315 202904 101315 202905 101842 202905 101316 202905 101315 202906 101316 202906 99020 202906 99020 202907 101316 202907 101317 202907 99020 202908 101317 202908 101318 202908 101318 202909 101317 202909 99275 202909 101318 202910 99275 202910 99018 202910 99018 202911 99275 202911 101319 202911 99018 202912 101319 202912 101320 202912 101320 202913 101319 202913 99273 202913 101320 202914 99273 202914 99016 202914 99016 202915 99273 202915 99271 202915 99016 202916 99271 202916 99015 202916 99015 202917 99271 202917 99270 202917 99015 202918 99270 202918 99013 202918 99013 202919 99270 202919 101321 202919 99013 202920 101321 202920 102836 202920 102836 202921 101321 202921 101846 202921 102836 202922 101846 202922 102835 202922 102835 202923 101846 202923 101322 202923 102835 202924 101322 202924 101323 202924 101333 202925 99263 202925 101324 202925 101324 202926 99263 202926 99261 202926 101324 202927 99261 202927 99022 202927 99022 202928 99261 202928 99259 202928 99022 202929 99259 202929 99021 202929 99021 202930 99259 202930 99257 202930 99021 202931 99257 202931 102830 202931 102830 202932 99257 202932 101859 202932 102830 202933 101859 202933 101325 202933 101325 202934 101859 202934 101857 202934 101325 202935 101857 202935 101326 202935 101326 202936 101857 202936 101855 202936 101326 202937 101855 202937 101327 202937 101327 202938 101855 202938 101328 202938 101327 202939 101328 202939 102827 202939 102827 202940 101328 202940 101851 202940 102827 202941 101851 202941 101329 202941 101329 202942 101851 202942 101849 202942 101329 202943 101849 202943 101330 202943 101330 202944 101849 202944 99267 202944 101330 202945 99267 202945 99024 202945 99024 202946 99267 202946 101332 202946 99024 202947 101332 202947 101331 202947 101331 202948 101332 202948 101333 202948 101331 202949 101333 202949 101324 202949 99252 202950 99250 202950 101334 202950 101334 202951 99250 202951 99248 202951 101334 202952 99248 202952 101335 202952 101335 202953 99248 202953 99247 202953 101335 202954 99247 202954 101336 202954 101336 202955 99247 202955 99245 202955 101336 202956 99245 202956 99025 202956 99025 202957 99245 202957 101337 202957 99025 202958 101337 202958 101338 202958 101338 202959 101337 202959 101339 202959 101338 202960 101339 202960 102823 202960 102823 202961 101339 202961 101865 202961 102823 202962 101865 202962 101340 202962 101340 202963 101865 202963 101341 202963 101340 202964 101341 202964 101342 202964 101342 202965 101341 202965 101343 202965 101342 202966 101343 202966 102820 202966 102820 202967 101343 202967 101861 202967 102820 202968 101861 202968 101344 202968 101344 202969 101861 202969 99254 202969 101344 202970 99254 202970 101345 202970 101345 202971 99254 202971 99253 202971 101345 202972 99253 202972 99029 202972 99029 202973 99253 202973 99252 202973 99029 202974 99252 202974 101334 202974 99241 202975 99239 202975 101346 202975 101346 202976 99239 202976 101348 202976 101346 202977 101348 202977 101347 202977 101347 202978 101348 202978 99236 202978 101347 202979 99236 202979 99032 202979 99032 202980 99236 202980 101349 202980 99032 202981 101349 202981 101350 202981 101350 202982 101349 202982 99234 202982 101350 202983 99234 202983 102818 202983 102818 202984 99234 202984 101876 202984 102818 202985 101876 202985 102816 202985 102816 202986 101876 202986 101351 202986 102816 202987 101351 202987 102815 202987 102815 202988 101351 202988 101352 202988 102815 202989 101352 202989 101353 202989 101353 202990 101352 202990 101872 202990 101353 202991 101872 202991 102812 202991 102812 202992 101872 202992 101871 202992 102812 202993 101871 202993 99039 202993 99039 202994 101871 202994 101869 202994 99039 202995 101869 202995 101354 202995 101354 202996 101869 202996 99243 202996 101354 202997 99243 202997 99036 202997 99036 202998 99243 202998 99241 202998 99036 202999 99241 202999 101346 202999 101768 203000 101206 203000 101355 203000 101355 203001 101206 203001 101356 203001 101355 203002 101356 203002 101770 203002 101770 203003 101356 203003 101357 203003 101770 203004 101357 203004 101358 203004 101358 203005 101357 203005 101208 203005 101358 203006 101208 203006 101772 203006 101772 203007 101208 203007 101209 203007 101772 203008 101209 203008 101774 203008 101774 203009 101209 203009 101360 203009 101774 203010 101360 203010 101359 203010 101359 203011 101360 203011 101210 203011 101359 203012 101210 203012 101776 203012 101776 203013 101210 203013 101207 203013 101776 203014 101207 203014 101777 203014 101777 203015 101207 203015 101361 203015 101777 203016 101361 203016 101779 203016 101779 203017 101361 203017 101362 203017 101779 203018 101362 203018 101783 203018 101783 203019 101362 203019 101205 203019 101783 203020 101205 203020 101363 203020 101363 203021 101205 203021 101364 203021 101363 203022 101364 203022 101365 203022 101365 203023 101364 203023 101366 203023 101365 203024 101366 203024 101367 203024 101367 203025 101366 203025 101368 203025 101367 203026 101368 203026 101781 203026 101781 203027 101368 203027 101369 203027 101781 203028 101369 203028 101370 203028 101370 203029 101369 203029 101371 203029 101372 203030 99311 203030 101375 203030 101380 203031 101381 203031 99313 203031 99313 203032 101373 203032 101380 203032 101380 203033 101373 203033 99315 203033 101380 203034 99315 203034 101374 203034 101374 203035 99315 203035 101808 203035 101372 203036 101375 203036 101811 203036 101376 203037 101548 203037 101810 203037 101810 203038 101548 203038 101549 203038 101810 203039 101549 203039 101809 203039 101376 203040 101377 203040 101548 203040 101548 203041 101377 203041 101378 203041 101548 203042 101378 203042 101375 203042 101375 203043 101378 203043 101812 203043 101375 203044 101812 203044 101811 203044 101952 203045 101375 203045 101379 203045 101379 203046 101375 203046 99311 203046 101379 203047 99311 203047 101948 203047 101948 203048 99311 203048 101383 203048 101679 203049 101961 203049 101958 203049 101679 203050 101958 203050 101380 203050 101958 203051 101955 203051 101380 203051 101380 203052 101955 203052 101954 203052 101380 203053 101954 203053 101381 203053 101381 203054 101954 203054 101382 203054 101381 203055 101382 203055 101383 203055 101383 203056 101382 203056 101953 203056 101383 203057 101953 203057 101948 203057 101384 203058 101389 203058 101385 203058 101385 203059 101389 203059 101386 203059 101385 203060 101386 203060 101993 203060 101993 203061 101386 203061 101387 203061 101990 203062 101388 203062 101991 203062 101991 203063 101388 203063 101389 203063 101991 203064 101389 203064 101992 203064 101992 203065 101389 203065 101384 203065 99545 203066 101664 203066 101390 203066 101390 203067 101664 203067 101388 203067 101390 203068 101388 203068 101988 203068 101988 203069 101388 203069 101990 203069 101808 203070 101391 203070 101374 203070 101374 203071 101391 203071 101809 203071 101374 203072 101809 203072 101392 203072 101392 203073 101809 203073 101549 203073 101392 203074 101549 203074 101677 203074 101677 203075 101549 203075 101393 203075 101677 203076 101393 203076 101706 203076 101706 203077 101393 203077 101551 203077 101706 203078 101551 203078 101709 203078 101709 203079 101551 203079 101552 203079 101709 203080 101552 203080 101394 203080 101394 203081 101552 203081 101553 203081 99321 203082 101400 203082 101395 203082 101395 203083 101400 203083 101394 203083 101395 203084 101394 203084 99320 203084 99320 203085 101394 203085 99319 203085 101401 203086 101803 203086 101555 203086 101803 203087 101804 203087 101555 203087 101555 203088 101804 203088 101806 203088 101555 203089 101806 203089 101396 203089 101806 203090 101807 203090 101396 203090 101396 203091 101807 203091 101397 203091 101396 203092 101397 203092 101553 203092 101397 203093 99316 203093 101553 203093 101553 203094 99316 203094 101398 203094 101553 203095 101398 203095 101394 203095 101394 203096 101398 203096 101399 203096 101394 203097 101399 203097 99319 203097 99321 203098 101800 203098 101400 203098 101400 203099 101800 203099 101401 203099 101400 203100 101401 203100 101675 203100 101675 203101 101401 203101 101555 203101 101675 203102 101555 203102 101402 203102 101402 203103 101555 203103 101403 203103 101402 203104 101403 203104 101676 203104 101676 203105 101403 203105 101404 203105 101676 203106 101404 203106 101715 203106 101715 203107 101404 203107 101405 203107 101715 203108 101405 203108 101412 203108 101412 203109 101405 203109 101406 203109 101794 203110 101793 203110 101560 203110 101560 203111 101793 203111 101407 203111 101560 203112 101407 203112 101408 203112 101408 203113 101795 203113 101560 203113 101560 203114 101795 203114 101796 203114 101560 203115 101796 203115 101561 203115 101561 203116 101796 203116 101798 203116 101798 203117 101409 203117 101561 203117 101561 203118 101409 203118 101410 203118 101561 203119 101410 203119 101406 203119 101406 203120 101410 203120 101411 203120 101406 203121 101411 203121 101412 203121 101412 203122 101411 203122 99323 203122 101412 203123 99323 203123 99324 203123 99324 203124 101413 203124 101412 203124 101412 203125 101413 203125 101415 203125 101412 203126 101415 203126 101414 203126 101414 203127 101415 203127 99327 203127 101414 203128 99327 203128 101672 203128 101672 203129 99327 203129 99330 203129 101784 203130 101416 203130 101417 203130 101784 203131 101417 203131 99341 203131 101416 203132 101785 203132 101417 203132 101417 203133 101785 203133 101787 203133 101417 203134 101787 203134 101419 203134 101787 203135 101418 203135 101419 203135 101419 203136 101418 203136 101789 203136 101419 203137 101789 203137 101421 203137 101789 203138 101791 203138 101421 203138 101421 203139 101791 203139 101420 203139 101421 203140 101420 203140 101422 203140 101422 203141 101420 203141 101668 203141 101422 203142 101668 203142 101563 203142 101563 203143 101668 203143 101670 203143 101563 203144 101670 203144 101564 203144 101564 203145 101670 203145 101671 203145 101564 203146 101671 203146 101560 203146 101560 203147 101671 203147 101672 203147 101560 203148 101672 203148 101794 203148 101794 203149 101672 203149 99330 203149 101791 203150 101423 203150 101420 203150 101420 203151 101423 203151 99331 203151 101420 203152 99331 203152 101424 203152 99331 203153 99333 203153 101424 203153 101424 203154 99333 203154 99335 203154 101424 203155 99335 203155 101425 203155 101425 203156 99335 203156 99337 203156 101425 203157 99337 203157 99339 203157 99339 203158 99341 203158 101425 203158 101425 203159 99341 203159 101417 203159 101425 203160 101417 203160 101666 203160 101666 203161 101417 203161 101567 203161 101666 203162 101567 203162 101726 203162 101726 203163 101567 203163 101569 203163 101726 203164 101569 203164 101426 203164 101426 203165 101569 203165 101571 203165 101426 203166 101571 203166 101427 203166 101870 203167 101428 203167 101437 203167 101437 203168 101428 203168 101574 203168 101574 203169 101428 203169 101429 203169 101574 203170 101429 203170 101873 203170 101873 203171 101874 203171 101574 203171 101574 203172 101874 203172 101875 203172 101574 203173 101875 203173 101430 203173 101571 203174 101572 203174 101427 203174 101427 203175 101572 203175 101573 203175 101427 203176 101573 203176 101431 203176 101431 203177 101573 203177 101574 203177 101431 203178 101574 203178 101432 203178 101432 203179 101574 203179 101430 203179 101432 203180 101430 203180 101433 203180 101433 203181 99235 203181 101432 203181 101432 203182 99235 203182 99237 203182 101432 203183 99237 203183 101438 203183 99242 203184 101435 203184 101434 203184 101434 203185 101435 203185 101436 203185 101434 203186 101436 203186 101437 203186 101437 203187 101436 203187 101868 203187 101437 203188 101868 203188 101870 203188 99237 203189 99238 203189 101438 203189 101438 203190 99238 203190 99240 203190 101438 203191 99240 203191 101439 203191 99240 203192 99242 203192 101439 203192 101439 203193 99242 203193 101434 203193 101439 203194 101434 203194 101737 203194 101737 203195 101434 203195 101440 203195 101737 203196 101440 203196 101441 203196 101440 203197 101442 203197 101441 203197 101441 203198 101442 203198 101443 203198 101441 203199 101443 203199 101665 203199 101665 203200 101443 203200 101446 203200 101665 203201 101446 203201 101448 203201 101860 203202 101445 203202 99256 203202 99256 203203 101445 203203 101386 203203 99256 203204 101386 203204 99255 203204 101860 203205 101444 203205 101445 203205 101445 203206 101444 203206 101862 203206 101445 203207 101862 203207 101446 203207 101862 203208 101863 203208 101446 203208 101446 203209 101863 203209 101864 203209 101446 203210 101864 203210 101448 203210 101448 203211 101864 203211 101866 203211 101448 203212 101866 203212 101867 203212 101867 203213 101447 203213 101448 203213 101448 203214 101447 203214 99244 203214 101448 203215 99244 203215 101449 203215 99244 203216 99246 203216 101449 203216 101449 203217 99246 203217 99249 203217 101449 203218 99249 203218 101389 203218 99249 203219 99251 203219 101389 203219 101389 203220 99251 203220 101450 203220 101389 203221 101450 203221 101386 203221 101386 203222 101450 203222 101451 203222 101386 203223 101451 203223 99255 203223 101535 203224 101596 203224 101533 203224 101533 203225 101596 203225 101452 203225 101533 203226 101452 203226 101532 203226 101532 203227 101452 203227 101531 203227 101531 203228 101452 203228 101453 203228 101531 203229 101453 203229 101530 203229 101530 203230 101453 203230 101528 203230 101528 203231 101453 203231 101594 203231 101528 203232 101594 203232 101454 203232 101454 203233 101594 203233 101455 203233 101455 203234 101594 203234 101591 203234 101455 203235 101591 203235 101456 203235 101456 203236 101591 203236 101457 203236 101457 203237 101591 203237 101458 203237 101457 203238 101458 203238 101524 203238 101524 203239 101458 203239 101459 203239 101459 203240 101458 203240 101461 203240 101459 203241 101461 203241 101522 203241 101522 203242 101461 203242 101460 203242 101460 203243 101461 203243 101590 203243 101460 203244 101590 203244 101521 203244 101521 203245 101590 203245 101462 203245 101462 203246 101590 203246 101463 203246 101462 203247 101463 203247 101518 203247 101586 203248 101464 203248 101463 203248 101463 203249 101464 203249 101516 203249 101463 203250 101516 203250 101518 203250 101465 203251 101585 203251 101512 203251 101512 203252 101513 203252 101465 203252 101465 203253 101513 203253 101514 203253 101465 203254 101514 203254 101586 203254 101586 203255 101514 203255 101515 203255 101586 203256 101515 203256 101464 203256 101584 203257 101471 203257 101466 203257 101466 203258 101467 203258 101584 203258 101584 203259 101467 203259 101511 203259 101584 203260 101511 203260 101585 203260 101585 203261 101511 203261 101468 203261 101585 203262 101468 203262 101512 203262 101470 203263 101474 203263 101469 203263 101469 203264 101539 203264 101470 203264 101470 203265 101539 203265 101537 203265 101470 203266 101537 203266 101471 203266 101471 203267 101537 203267 101536 203267 101471 203268 101536 203268 101466 203268 101472 203269 101582 203269 101905 203269 101905 203270 101505 203270 101472 203270 101472 203271 101505 203271 101473 203271 101472 203272 101473 203272 101474 203272 101474 203273 101473 203273 101542 203273 101474 203274 101542 203274 101469 203274 101475 203275 101615 203275 101547 203275 101547 203276 101615 203276 101477 203276 101547 203277 101477 203277 101476 203277 101476 203278 101477 203278 101550 203278 101550 203279 101477 203279 101479 203279 101550 203280 101479 203280 101478 203280 101478 203281 101479 203281 101480 203281 101480 203282 101479 203282 101482 203282 101480 203283 101482 203283 101481 203283 101481 203284 101482 203284 101554 203284 101554 203285 101482 203285 101612 203285 101554 203286 101612 203286 101483 203286 101483 203287 101612 203287 101556 203287 101556 203288 101612 203288 101484 203288 101556 203289 101484 203289 101557 203289 101557 203290 101484 203290 101485 203290 101485 203291 101484 203291 101486 203291 101485 203292 101486 203292 101558 203292 101558 203293 101486 203293 101559 203293 101559 203294 101486 203294 101608 203294 101559 203295 101608 203295 101487 203295 101487 203296 101608 203296 101562 203296 101562 203297 101608 203297 101607 203297 101562 203298 101607 203298 101565 203298 101565 203299 101607 203299 101488 203299 101488 203300 101607 203300 101605 203300 101488 203301 101605 203301 101489 203301 101604 203302 101494 203302 101495 203302 101495 203303 101570 203303 101604 203303 101604 203304 101570 203304 101568 203304 101604 203305 101568 203305 101605 203305 101605 203306 101568 203306 101566 203306 101605 203307 101566 203307 101489 203307 101491 203308 101602 203308 101490 203308 101490 203309 101575 203309 101491 203309 101491 203310 101575 203310 101492 203310 101491 203311 101492 203311 101494 203311 101494 203312 101492 203312 101493 203312 101494 203313 101493 203313 101495 203313 101601 203314 101599 203314 101496 203314 101496 203315 101576 203315 101601 203315 101601 203316 101576 203316 101497 203316 101601 203317 101497 203317 101602 203317 101602 203318 101497 203318 101498 203318 101602 203319 101498 203319 101490 203319 101500 203320 101597 203320 101578 203320 101578 203321 101499 203321 101500 203321 101500 203322 101499 203322 101501 203322 101500 203323 101501 203323 101599 203323 101599 203324 101501 203324 101577 203324 101599 203325 101577 203325 101496 203325 101503 203326 101908 203326 101504 203326 101502 203327 101503 203327 101905 203327 101905 203328 101503 203328 101504 203328 101905 203329 101504 203329 101505 203329 99551 203330 101507 203330 101535 203330 99221 203331 101535 203331 101506 203331 101506 203332 101535 203332 101507 203332 101506 203333 101507 203333 101508 203333 101508 203334 101507 203334 101509 203334 99615 203335 99618 203335 101467 203335 101467 203336 99618 203336 101510 203336 101467 203337 101510 203337 101511 203337 101511 203338 101510 203338 99605 203338 101511 203339 99605 203339 101468 203339 101468 203340 99605 203340 99604 203340 101468 203341 99604 203341 101512 203341 101512 203342 99604 203342 99603 203342 101512 203343 99603 203343 101513 203343 101513 203344 99603 203344 99597 203344 101513 203345 99597 203345 101514 203345 101514 203346 99597 203346 99592 203346 101514 203347 99592 203347 101515 203347 101515 203348 99592 203348 99591 203348 101515 203349 99591 203349 101464 203349 101464 203350 99591 203350 99589 203350 101464 203351 99589 203351 101516 203351 101516 203352 99589 203352 101517 203352 101516 203353 101517 203353 101518 203353 101518 203354 101517 203354 101519 203354 101518 203355 101519 203355 101462 203355 101462 203356 101519 203356 101520 203356 101462 203357 101520 203357 101521 203357 101521 203358 101520 203358 99575 203358 101521 203359 99575 203359 101460 203359 101460 203360 99575 203360 99574 203360 101460 203361 99574 203361 101522 203361 101522 203362 99574 203362 99572 203362 101522 203363 99572 203363 101459 203363 101459 203364 99572 203364 101523 203364 101459 203365 101523 203365 101524 203365 101524 203366 101523 203366 101525 203366 101524 203367 101525 203367 101457 203367 101457 203368 101525 203368 101526 203368 101457 203369 101526 203369 101456 203369 101456 203370 101526 203370 101527 203370 101456 203371 101527 203371 101455 203371 101455 203372 101527 203372 99567 203372 101455 203373 99567 203373 101454 203373 101454 203374 99567 203374 99562 203374 101454 203375 99562 203375 101528 203375 101528 203376 99562 203376 101529 203376 101528 203377 101529 203377 101530 203377 101530 203378 101529 203378 99560 203378 101530 203379 99560 203379 101531 203379 101531 203380 99560 203380 99559 203380 101531 203381 99559 203381 101532 203381 101532 203382 99559 203382 101534 203382 101532 203383 101534 203383 101533 203383 101533 203384 101534 203384 99556 203384 101533 203385 99556 203385 101535 203385 101535 203386 99556 203386 99558 203386 101535 203387 99558 203387 99551 203387 101467 203388 101466 203388 99615 203388 99615 203389 101466 203389 101536 203389 99615 203390 101536 203390 99613 203390 99613 203391 101536 203391 101538 203391 101536 203392 101537 203392 101538 203392 101538 203393 101537 203393 101539 203393 101538 203394 101539 203394 101540 203394 101540 203395 101539 203395 101541 203395 101539 203396 101469 203396 101541 203396 101541 203397 101469 203397 101542 203397 101541 203398 101542 203398 101543 203398 101543 203399 101542 203399 101473 203399 101543 203400 101473 203400 101544 203400 101544 203401 101473 203401 101505 203401 101544 203402 101505 203402 99531 203402 99531 203403 101505 203403 101504 203403 99531 203404 101504 203404 99540 203404 101947 203405 101913 203405 101547 203405 101547 203406 101913 203406 101545 203406 101547 203407 101545 203407 101475 203407 101475 203408 101545 203408 101912 203408 101580 203409 101387 203409 101386 203409 99225 203410 99226 203410 101580 203410 101580 203411 99226 203411 101546 203411 101580 203412 101546 203412 101994 203412 101952 203413 101947 203413 101375 203413 101375 203414 101947 203414 101547 203414 101375 203415 101547 203415 101548 203415 101548 203416 101547 203416 101476 203416 101548 203417 101476 203417 101549 203417 101549 203418 101476 203418 101550 203418 101549 203419 101550 203419 101393 203419 101393 203420 101550 203420 101478 203420 101393 203421 101478 203421 101551 203421 101551 203422 101478 203422 101480 203422 101551 203423 101480 203423 101552 203423 101552 203424 101480 203424 101481 203424 101552 203425 101481 203425 101553 203425 101553 203426 101481 203426 101554 203426 101553 203427 101554 203427 101396 203427 101396 203428 101554 203428 101483 203428 101396 203429 101483 203429 101555 203429 101555 203430 101483 203430 101556 203430 101555 203431 101556 203431 101403 203431 101403 203432 101556 203432 101557 203432 101403 203433 101557 203433 101404 203433 101404 203434 101557 203434 101485 203434 101404 203435 101485 203435 101405 203435 101405 203436 101485 203436 101558 203436 101405 203437 101558 203437 101406 203437 101406 203438 101558 203438 101559 203438 101406 203439 101559 203439 101561 203439 101562 203440 101564 203440 101560 203440 101561 203441 101559 203441 101560 203441 101560 203442 101559 203442 101487 203442 101560 203443 101487 203443 101562 203443 101488 203444 101422 203444 101563 203444 101564 203445 101562 203445 101563 203445 101563 203446 101562 203446 101565 203446 101563 203447 101565 203447 101488 203447 101422 203448 101488 203448 101421 203448 101421 203449 101488 203449 101489 203449 101421 203450 101489 203450 101419 203450 101419 203451 101489 203451 101566 203451 101419 203452 101566 203452 101417 203452 101417 203453 101566 203453 101568 203453 101417 203454 101568 203454 101567 203454 101567 203455 101568 203455 101570 203455 101567 203456 101570 203456 101569 203456 101569 203457 101570 203457 101495 203457 101569 203458 101495 203458 101571 203458 101571 203459 101495 203459 101493 203459 101571 203460 101493 203460 101572 203460 101572 203461 101493 203461 101492 203461 101572 203462 101492 203462 101573 203462 101573 203463 101492 203463 101575 203463 101573 203464 101575 203464 101574 203464 101574 203465 101575 203465 101490 203465 101574 203466 101490 203466 101437 203466 101437 203467 101490 203467 101498 203467 101437 203468 101498 203468 101434 203468 101434 203469 101498 203469 101497 203469 101434 203470 101497 203470 101440 203470 101440 203471 101497 203471 101576 203471 101440 203472 101576 203472 101442 203472 101442 203473 101576 203473 101496 203473 101442 203474 101496 203474 101443 203474 101443 203475 101496 203475 101577 203475 101443 203476 101577 203476 101446 203476 101446 203477 101577 203477 101501 203477 101446 203478 101501 203478 101445 203478 101445 203479 101501 203479 101499 203479 101445 203480 101499 203480 101386 203480 101386 203481 101499 203481 101578 203481 101386 203482 101578 203482 101580 203482 101580 203483 101578 203483 101579 203483 101580 203484 101579 203484 99225 203484 101581 203485 101582 203485 101472 203485 101581 203486 101472 203486 104077 203486 104077 203487 101472 203487 101474 203487 104077 203488 101474 203488 104074 203488 104074 203489 101474 203489 101470 203489 104074 203490 101470 203490 104073 203490 104073 203491 101470 203491 101471 203491 104073 203492 101471 203492 101583 203492 101583 203493 101471 203493 101584 203493 101583 203494 101584 203494 104072 203494 104072 203495 101584 203495 101585 203495 104072 203496 101585 203496 104071 203496 104071 203497 101585 203497 101465 203497 104071 203498 101465 203498 101587 203498 101587 203499 101465 203499 101586 203499 101587 203500 101586 203500 101588 203500 101588 203501 101586 203501 101463 203501 101588 203502 101463 203502 101589 203502 101589 203503 101463 203503 101590 203503 101589 203504 101590 203504 104070 203504 104070 203505 101590 203505 101461 203505 104070 203506 101461 203506 104069 203506 104069 203507 101461 203507 101458 203507 104069 203508 101458 203508 104068 203508 104068 203509 101458 203509 101591 203509 104068 203510 101591 203510 101592 203510 101592 203511 101591 203511 101594 203511 101592 203512 101594 203512 101593 203512 101593 203513 101594 203513 101453 203513 101593 203514 101453 203514 101595 203514 101595 203515 101453 203515 101452 203515 101595 203516 101452 203516 104066 203516 104066 203517 101452 203517 101596 203517 104066 203518 101596 203518 99211 203518 101934 203519 101597 203519 101500 203519 101934 203520 101500 203520 101598 203520 101598 203521 101500 203521 101599 203521 101598 203522 101599 203522 101600 203522 101600 203523 101599 203523 101601 203523 101600 203524 101601 203524 104064 203524 104064 203525 101601 203525 101602 203525 104064 203526 101602 203526 104063 203526 104063 203527 101602 203527 101491 203527 104063 203528 101491 203528 101603 203528 101603 203529 101491 203529 101494 203529 101603 203530 101494 203530 104062 203530 104062 203531 101494 203531 101604 203531 104062 203532 101604 203532 104059 203532 104059 203533 101604 203533 101605 203533 104059 203534 101605 203534 101606 203534 101606 203535 101605 203535 101607 203535 101606 203536 101607 203536 104058 203536 104058 203537 101607 203537 101608 203537 104058 203538 101608 203538 101609 203538 101609 203539 101608 203539 101486 203539 101609 203540 101486 203540 101610 203540 101610 203541 101486 203541 101484 203541 101610 203542 101484 203542 101611 203542 101611 203543 101484 203543 101612 203543 101611 203544 101612 203544 104054 203544 104054 203545 101612 203545 101482 203545 104054 203546 101482 203546 101613 203546 101613 203547 101482 203547 101479 203547 101613 203548 101479 203548 104051 203548 104051 203549 101479 203549 101477 203549 104051 203550 101477 203550 101614 203550 101614 203551 101477 203551 101615 203551 101614 203552 101615 203552 104049 203552 99414 203553 101616 203553 101617 203553 99427 203554 101619 203554 101618 203554 101618 203555 101619 203555 99380 203555 101618 203556 99380 203556 101620 203556 101620 203557 99380 203557 101621 203557 99427 203558 99426 203558 101619 203558 101619 203559 99426 203559 101622 203559 101619 203560 101622 203560 101752 203560 101622 203561 99424 203561 101752 203561 101752 203562 99424 203562 101623 203562 101752 203563 101623 203563 101624 203563 101624 203564 101623 203564 101625 203564 101624 203565 101625 203565 101626 203565 101626 203566 101627 203566 101624 203566 101624 203567 101627 203567 99421 203567 101624 203568 99421 203568 101629 203568 101631 203569 101755 203569 101628 203569 101628 203570 101755 203570 101629 203570 101628 203571 101629 203571 101630 203571 101630 203572 101629 203572 99421 203572 101631 203573 99418 203573 101755 203573 101755 203574 99418 203574 99416 203574 101755 203575 99416 203575 101617 203575 101617 203576 99416 203576 101632 203576 101617 203577 101632 203577 99414 203577 101616 203578 101633 203578 101617 203578 101617 203579 101633 203579 99413 203579 101617 203580 99413 203580 101635 203580 99413 203581 101634 203581 101635 203581 101635 203582 101634 203582 101636 203582 101635 203583 101636 203583 101759 203583 101759 203584 101636 203584 99412 203584 101759 203585 99412 203585 99410 203585 101637 203586 101640 203586 101638 203586 101638 203587 101640 203587 101759 203587 101638 203588 101759 203588 99408 203588 99408 203589 101759 203589 99410 203589 101637 203590 101639 203590 101640 203590 101640 203591 101639 203591 99406 203591 101640 203592 99406 203592 101641 203592 99406 203593 99403 203593 101641 203593 101641 203594 99403 203594 101642 203594 101641 203595 101642 203595 101643 203595 101643 203596 101642 203596 101644 203596 101643 203597 101644 203597 101645 203597 99398 203598 101646 203598 99400 203598 99400 203599 101646 203599 101643 203599 99400 203600 101643 203600 101647 203600 101647 203601 101643 203601 101645 203601 99394 203602 101648 203602 99395 203602 99395 203603 101648 203603 101646 203603 99395 203604 101646 203604 99397 203604 99397 203605 101646 203605 99398 203605 99394 203606 99393 203606 101648 203606 101648 203607 99393 203607 101649 203607 101648 203608 101649 203608 101652 203608 101652 203609 101649 203609 101650 203609 101652 203610 101650 203610 101651 203610 101651 203611 99390 203611 101652 203611 101652 203612 99390 203612 101654 203612 101652 203613 101654 203613 101653 203613 101654 203614 99389 203614 101653 203614 101653 203615 99389 203615 101655 203615 101653 203616 101655 203616 101657 203616 101657 203617 101655 203617 101656 203617 101657 203618 101656 203618 99387 203618 99384 203619 101765 203619 99386 203619 99386 203620 101765 203620 101657 203620 99386 203621 101657 203621 101658 203621 101658 203622 101657 203622 99387 203622 99503 203623 99360 203623 101659 203623 101659 203624 99360 203624 101765 203624 101659 203625 101765 203625 99383 203625 99383 203626 101765 203626 99384 203626 101747 203627 99461 203627 101621 203627 99516 203628 101718 203628 101688 203628 101660 203629 101738 203629 101740 203629 101674 203630 101712 203630 101711 203630 101678 203631 101661 203631 101662 203631 101676 203632 101715 203632 101716 203632 101726 203633 101426 203633 101727 203633 101427 203634 101431 203634 101735 203634 101737 203635 101441 203635 101743 203635 101664 203636 101663 203636 101693 203636 101694 203637 101389 203637 101693 203637 101693 203638 101389 203638 101388 203638 101693 203639 101388 203639 101664 203639 101441 203640 101665 203640 101742 203640 101742 203641 101665 203641 101448 203641 101742 203642 101448 203642 101694 203642 101694 203643 101448 203643 101449 203643 101694 203644 101449 203644 101389 203644 101432 203645 101438 203645 101660 203645 101660 203646 101438 203646 101439 203646 101660 203647 101439 203647 101738 203647 101738 203648 101439 203648 101737 203648 101425 203649 101666 203649 101723 203649 101723 203650 101666 203650 101726 203650 101722 203651 101424 203651 101425 203651 101424 203652 101722 203652 101420 203652 101420 203653 101722 203653 101667 203653 101420 203654 101667 203654 101668 203654 101668 203655 101667 203655 101669 203655 101668 203656 101669 203656 101670 203656 101670 203657 101669 203657 101686 203657 101670 203658 101686 203658 101671 203658 101671 203659 101686 203659 101672 203659 101672 203660 101686 203660 101673 203660 101672 203661 101673 203661 101414 203661 101414 203662 101673 203662 101412 203662 101412 203663 101673 203663 101717 203663 101412 203664 101717 203664 101715 203664 101394 203665 101400 203665 101674 203665 101674 203666 101400 203666 101675 203666 101674 203667 101675 203667 101712 203667 101712 203668 101675 203668 101402 203668 101712 203669 101402 203669 101676 203669 101392 203670 101677 203670 101702 203670 101702 203671 101677 203671 101706 203671 101380 203672 101374 203672 101700 203672 101700 203673 101374 203673 101392 203673 101960 203674 101963 203674 101678 203674 101380 203675 101661 203675 101679 203675 101679 203676 101661 203676 101678 203676 101679 203677 101678 203677 101961 203677 101961 203678 101678 203678 101963 203678 101698 203679 101696 203679 99429 203679 101682 203680 101708 203680 101680 203680 101706 203681 101709 203681 101680 203681 101680 203682 101709 203682 101681 203682 101680 203683 101681 203683 101682 203683 101682 203684 101681 203684 101710 203684 101682 203685 101710 203685 99511 203685 99511 203686 101710 203686 101683 203686 101722 203687 101684 203687 101667 203687 101667 203688 101684 203688 101720 203688 101667 203689 101720 203689 101669 203689 101669 203690 101720 203690 101685 203690 101669 203691 101685 203691 101686 203691 101686 203692 101685 203692 101719 203692 101686 203693 101719 203693 101673 203693 101673 203694 101719 203694 101687 203694 101673 203695 101687 203695 101717 203695 101717 203696 101687 203696 101688 203696 101732 203697 101730 203697 101689 203697 101426 203698 101427 203698 101689 203698 101689 203699 101427 203699 101735 203699 101689 203700 101735 203700 101732 203700 101732 203701 101735 203701 101690 203701 101732 203702 101690 203702 101691 203702 101691 203703 101690 203703 101692 203703 101663 203704 99461 203704 101693 203704 101693 203705 99461 203705 101747 203705 101693 203706 101747 203706 101694 203706 101694 203707 101747 203707 101695 203707 101694 203708 101695 203708 101742 203708 101742 203709 101695 203709 101744 203709 99503 203710 101696 203710 99506 203710 99506 203711 101696 203711 101698 203711 99506 203712 101698 203712 101699 203712 101697 203713 101960 203713 99429 203713 99429 203714 101960 203714 101678 203714 99429 203715 101678 203715 101698 203715 101698 203716 101678 203716 101662 203716 101698 203717 101662 203717 101699 203717 101699 203718 101662 203718 99504 203718 101703 203719 101705 203719 101701 203719 101380 203720 101700 203720 101661 203720 101661 203721 101700 203721 101703 203721 101661 203722 101703 203722 101662 203722 101662 203723 101703 203723 101701 203723 101662 203724 101701 203724 99504 203724 101392 203725 101702 203725 101700 203725 101700 203726 101702 203726 101704 203726 101700 203727 101704 203727 101703 203727 101703 203728 101704 203728 101707 203728 101703 203729 101707 203729 101705 203729 101706 203730 101680 203730 101702 203730 101702 203731 101680 203731 101708 203731 101702 203732 101708 203732 101704 203732 101704 203733 101708 203733 99508 203733 101704 203734 99508 203734 101707 203734 99511 203735 99510 203735 101682 203735 101682 203736 99510 203736 99509 203736 101682 203737 99509 203737 101708 203737 101708 203738 99509 203738 99507 203738 101708 203739 99507 203739 99508 203739 101709 203740 101394 203740 101681 203740 101681 203741 101394 203741 101674 203741 101681 203742 101674 203742 101710 203742 101710 203743 101674 203743 101711 203743 101710 203744 101711 203744 101683 203744 101683 203745 101711 203745 101714 203745 101713 203746 99514 203746 99515 203746 101676 203747 101716 203747 101712 203747 101712 203748 101716 203748 101713 203748 101712 203749 101713 203749 101711 203749 101711 203750 101713 203750 99515 203750 101711 203751 99515 203751 101714 203751 101715 203752 101717 203752 101716 203752 101716 203753 101717 203753 101688 203753 101716 203754 101688 203754 101713 203754 101713 203755 101688 203755 101718 203755 101713 203756 101718 203756 99514 203756 99516 203757 101688 203757 99517 203757 99517 203758 101688 203758 101687 203758 99517 203759 101687 203759 99518 203759 99518 203760 101687 203760 101719 203760 99518 203761 101719 203761 99519 203761 99519 203762 101719 203762 99521 203762 99521 203763 101719 203763 101685 203763 99521 203764 101685 203764 99522 203764 99522 203765 101685 203765 101720 203765 99522 203766 101720 203766 101721 203766 101721 203767 101720 203767 101684 203767 101721 203768 101684 203768 101725 203768 101724 203769 101729 203769 99523 203769 101425 203770 101723 203770 101722 203770 101722 203771 101723 203771 101724 203771 101722 203772 101724 203772 101684 203772 101684 203773 101724 203773 99523 203773 101684 203774 99523 203774 101725 203774 101726 203775 101727 203775 101723 203775 101723 203776 101727 203776 101728 203776 101723 203777 101728 203777 101724 203777 101724 203778 101728 203778 101731 203778 101724 203779 101731 203779 101729 203779 101426 203780 101689 203780 101727 203780 101727 203781 101689 203781 101730 203781 101727 203782 101730 203782 101728 203782 101728 203783 101730 203783 99525 203783 101728 203784 99525 203784 101731 203784 101691 203785 99527 203785 101732 203785 101732 203786 99527 203786 101733 203786 101732 203787 101733 203787 101730 203787 101730 203788 101733 203788 101734 203788 101730 203789 101734 203789 99525 203789 101431 203790 101432 203790 101735 203790 101735 203791 101432 203791 101660 203791 101735 203792 101660 203792 101690 203792 101690 203793 101660 203793 101740 203793 101690 203794 101740 203794 101692 203794 101692 203795 101740 203795 101741 203795 101739 203796 101745 203796 101736 203796 101737 203797 101743 203797 101738 203797 101738 203798 101743 203798 101739 203798 101738 203799 101739 203799 101740 203799 101740 203800 101739 203800 101736 203800 101740 203801 101736 203801 101741 203801 101441 203802 101742 203802 101743 203802 101743 203803 101742 203803 101744 203803 101743 203804 101744 203804 101739 203804 101739 203805 101744 203805 99530 203805 101739 203806 99530 203806 101745 203806 101621 203807 101746 203807 101747 203807 101747 203808 101746 203808 101748 203808 101747 203809 101748 203809 101695 203809 101695 203810 101748 203810 101749 203810 101695 203811 101749 203811 101744 203811 101744 203812 101749 203812 101750 203812 101744 203813 101750 203813 99530 203813 101751 203814 99380 203814 101619 203814 101751 203815 101619 203815 104303 203815 104303 203816 101619 203816 101752 203816 104303 203817 101752 203817 101753 203817 101753 203818 101752 203818 101624 203818 101753 203819 101624 203819 104305 203819 104305 203820 101624 203820 101629 203820 104305 203821 101629 203821 101754 203821 101754 203822 101629 203822 101755 203822 101754 203823 101755 203823 101756 203823 101756 203824 101755 203824 101617 203824 101756 203825 101617 203825 101757 203825 101757 203826 101617 203826 101635 203826 101757 203827 101635 203827 101758 203827 101758 203828 101635 203828 101759 203828 101758 203829 101759 203829 101760 203829 101760 203830 101759 203830 101640 203830 101760 203831 101640 203831 101761 203831 101761 203832 101640 203832 101641 203832 101761 203833 101641 203833 104309 203833 104309 203834 101641 203834 101643 203834 104309 203835 101643 203835 101762 203835 101762 203836 101643 203836 101646 203836 101762 203837 101646 203837 101763 203837 101763 203838 101646 203838 101648 203838 101763 203839 101648 203839 104314 203839 104314 203840 101648 203840 101652 203840 104314 203841 101652 203841 101764 203841 101764 203842 101652 203842 101653 203842 101764 203843 101653 203843 104317 203843 104317 203844 101653 203844 101657 203844 104317 203845 101657 203845 104318 203845 104318 203846 101657 203846 101765 203846 104318 203847 101765 203847 104320 203847 104320 203848 101765 203848 99360 203848 104320 203849 99360 203849 99361 203849 101766 203850 101768 203850 101767 203850 101767 203851 101768 203851 101355 203851 101767 203852 101355 203852 101769 203852 101769 203853 101355 203853 101770 203853 101769 203854 101770 203854 100105 203854 100105 203855 101770 203855 101358 203855 100105 203856 101358 203856 101771 203856 101771 203857 101358 203857 101772 203857 101771 203858 101772 203858 101773 203858 101773 203859 101772 203859 101774 203859 101773 203860 101774 203860 101158 203860 101158 203861 101774 203861 101775 203861 101775 203862 101774 203862 101359 203862 101775 203863 101359 203863 104291 203863 104291 203864 101359 203864 101776 203864 104291 203865 101776 203865 104283 203865 104283 203866 101776 203866 101777 203866 104283 203867 101777 203867 101778 203867 101783 203868 104292 203868 101779 203868 101779 203869 104292 203869 104293 203869 101779 203870 104293 203870 101777 203870 101777 203871 104293 203871 101780 203871 101777 203872 101780 203872 101778 203872 101370 203873 99359 203873 101781 203873 101781 203874 99359 203874 101782 203874 101781 203875 101782 203875 101367 203875 101367 203876 101782 203876 100089 203876 101367 203877 100089 203877 101365 203877 101365 203878 100089 203878 100087 203878 101365 203879 100087 203879 101363 203879 101363 203880 100087 203880 100086 203880 101363 203881 100086 203881 101783 203881 101783 203882 100086 203882 100085 203882 101783 203883 100085 203883 104292 203883 101784 203884 101224 203884 101222 203884 101784 203885 101222 203885 101416 203885 101416 203886 101222 203886 101221 203886 101416 203887 101221 203887 101785 203887 101785 203888 101221 203888 101786 203888 101785 203889 101786 203889 101787 203889 101787 203890 101786 203890 101788 203890 101787 203891 101788 203891 101418 203891 101418 203892 101788 203892 101790 203892 101418 203893 101790 203893 101789 203893 101789 203894 101790 203894 101218 203894 101789 203895 101218 203895 101791 203895 101791 203896 101218 203896 101216 203896 101791 203897 101216 203897 101423 203897 101408 203898 101407 203898 101792 203898 101792 203899 101407 203899 101793 203899 101792 203900 101793 203900 101233 203900 101233 203901 101793 203901 101794 203901 101233 203902 101794 203902 101234 203902 101408 203903 101792 203903 101795 203903 101795 203904 101792 203904 101231 203904 101795 203905 101231 203905 101796 203905 101796 203906 101231 203906 101797 203906 101796 203907 101797 203907 101798 203907 101798 203908 101797 203908 101409 203908 101409 203909 101797 203909 101799 203909 101409 203910 101799 203910 101410 203910 101410 203911 101799 203911 101228 203911 101410 203912 101228 203912 101411 203912 101800 203913 101246 203913 101245 203913 101800 203914 101245 203914 101401 203914 101401 203915 101245 203915 101801 203915 101401 203916 101801 203916 101803 203916 101803 203917 101801 203917 101802 203917 101803 203918 101802 203918 101804 203918 101804 203919 101802 203919 101805 203919 101804 203920 101805 203920 101806 203920 101806 203921 101805 203921 101240 203921 101806 203922 101240 203922 101807 203922 101807 203923 101240 203923 101238 203923 101807 203924 101238 203924 101397 203924 101397 203925 101238 203925 101237 203925 101397 203926 101237 203926 99316 203926 99315 203927 99314 203927 101808 203927 101808 203928 99314 203928 101263 203928 101808 203929 101263 203929 101391 203929 101391 203930 101263 203930 101262 203930 101391 203931 101262 203931 101809 203931 101809 203932 101262 203932 101261 203932 101809 203933 101261 203933 101810 203933 101810 203934 101261 203934 101259 203934 101810 203935 101259 203935 101376 203935 101258 203936 101255 203936 101811 203936 101811 203937 101812 203937 101258 203937 101258 203938 101812 203938 101378 203938 101258 203939 101378 203939 101259 203939 101259 203940 101378 203940 101377 203940 101259 203941 101377 203941 101376 203941 99535 203942 101272 203942 101813 203942 101813 203943 101272 203943 101814 203943 101813 203944 101814 203944 101815 203944 101815 203945 101814 203945 101816 203945 101816 203946 101814 203946 101270 203946 101816 203947 101270 203947 101817 203947 101817 203948 101270 203948 101818 203948 101817 203949 101818 203949 99542 203949 99542 203950 101818 203950 101269 203950 99542 203951 101269 203951 99539 203951 99539 203952 101269 203952 101819 203952 99539 203953 101819 203953 101821 203953 101268 203954 99303 203954 101819 203954 101819 203955 99303 203955 101820 203955 101819 203956 101820 203956 101821 203956 99611 203957 101276 203957 101822 203957 101822 203958 101276 203958 101823 203958 101822 203959 101823 203959 101824 203959 101824 203960 101823 203960 101825 203960 101825 203961 101823 203961 101279 203961 101825 203962 101279 203962 101826 203962 101826 203963 101279 203963 99607 203963 99607 203964 101279 203964 101280 203964 99607 203965 101280 203965 99608 203965 99608 203966 101280 203966 101827 203966 99608 203967 101827 203967 101828 203967 101828 203968 101827 203968 101829 203968 101828 203969 101829 203969 99612 203969 99612 203970 101829 203970 101282 203970 99612 203971 101282 203971 99614 203971 99593 203972 101292 203972 101291 203972 99593 203973 101291 203973 101831 203973 101831 203974 101291 203974 101830 203974 101831 203975 101830 203975 99594 203975 99594 203976 101830 203976 101288 203976 99594 203977 101288 203977 99595 203977 99595 203978 101288 203978 101301 203978 99595 203979 101301 203979 99596 203979 99596 203980 101301 203980 101832 203980 99596 203981 101832 203981 101833 203981 101833 203982 101832 203982 101298 203982 101833 203983 101298 203983 99602 203983 99602 203984 101298 203984 99287 203984 99602 203985 99287 203985 99598 203985 99578 203986 101310 203986 101834 203986 99578 203987 101834 203987 101835 203987 101835 203988 101834 203988 101308 203988 101835 203989 101308 203989 99579 203989 99579 203990 101308 203990 99580 203990 99580 203991 101308 203991 101836 203991 99580 203992 101836 203992 99581 203992 99581 203993 101836 203993 99583 203993 99583 203994 101836 203994 101839 203994 99583 203995 101839 203995 101837 203995 101837 203996 101839 203996 101838 203996 101838 203997 101839 203997 101307 203997 101838 203998 101307 203998 99586 203998 99586 203999 101307 203999 99277 203999 99586 204000 99277 204000 99278 204000 101840 204001 101317 204001 101316 204001 101840 204002 101316 204002 101841 204002 101841 204003 101316 204003 101842 204003 101841 204004 101842 204004 101843 204004 101843 204005 101842 204005 101314 204005 101843 204006 101314 204006 101844 204006 101844 204007 101314 204007 101313 204007 101844 204008 101313 204008 101845 204008 101845 204009 101313 204009 101322 204009 101845 204010 101322 204010 99563 204010 99563 204011 101322 204011 101846 204011 99563 204012 101846 204012 101847 204012 101847 204013 101846 204013 101321 204013 101847 204014 101321 204014 99268 204014 99557 204015 99267 204015 101848 204015 101848 204016 99267 204016 101849 204016 101848 204017 101849 204017 101850 204017 101850 204018 101849 204018 101851 204018 101850 204019 101851 204019 101852 204019 101852 204020 101851 204020 101328 204020 101852 204021 101328 204021 99553 204021 99553 204022 101328 204022 101855 204022 99553 204023 101855 204023 101853 204023 101853 204024 101855 204024 101854 204024 101854 204025 101855 204025 101857 204025 101854 204026 101857 204026 101856 204026 101856 204027 101857 204027 101858 204027 101858 204028 101857 204028 101859 204028 101858 204029 101859 204029 99555 204029 101860 204030 99256 204030 99254 204030 101860 204031 99254 204031 101444 204031 101444 204032 99254 204032 101861 204032 101444 204033 101861 204033 101862 204033 101862 204034 101861 204034 101343 204034 101862 204035 101343 204035 101863 204035 101863 204036 101343 204036 101341 204036 101863 204037 101341 204037 101864 204037 101864 204038 101341 204038 101865 204038 101864 204039 101865 204039 101866 204039 101866 204040 101865 204040 101339 204040 101866 204041 101339 204041 101867 204041 101867 204042 101339 204042 101447 204042 101447 204043 101339 204043 101337 204043 101447 204044 101337 204044 99244 204044 101868 204045 101436 204045 101869 204045 101868 204046 101869 204046 101870 204046 101870 204047 101869 204047 101871 204047 101870 204048 101871 204048 101428 204048 101428 204049 101871 204049 101872 204049 101428 204050 101872 204050 101429 204050 101429 204051 101872 204051 101873 204051 101873 204052 101872 204052 101352 204052 101873 204053 101352 204053 101874 204053 101874 204054 101352 204054 101351 204054 101874 204055 101351 204055 101875 204055 101875 204056 101351 204056 101876 204056 101875 204057 101876 204057 101430 204057 101430 204058 101876 204058 99234 204058 101430 204059 99234 204059 101433 204059 99233 204060 99214 204060 101877 204060 99233 204061 101877 204061 101878 204061 101878 204062 101877 204062 101938 204062 101878 204063 101938 204063 101965 204063 101879 204064 101941 204064 101884 204064 101884 204065 101941 204065 101943 204065 99231 204066 101880 204066 101881 204066 101881 204067 101882 204067 99231 204067 99231 204068 101882 204068 101971 204068 99231 204069 101971 204069 101943 204069 101943 204070 101971 204070 101883 204070 101943 204071 101883 204071 101884 204071 101938 204072 99228 204072 101965 204072 101965 204073 99228 204073 101964 204073 101974 204074 101909 204074 101885 204074 101885 204075 101909 204075 101941 204075 101885 204076 101941 204076 101879 204076 101886 204077 101887 204077 101949 204077 101949 204078 101887 204078 101911 204078 99213 204079 99227 204079 101987 204079 101987 204080 99227 204080 101924 204080 101987 204081 101924 204081 101888 204081 101888 204082 101924 204082 101889 204082 101888 204083 101889 204083 101985 204083 101985 204084 101889 204084 101922 204084 101985 204085 101922 204085 101984 204085 101929 204086 101928 204086 101890 204086 101890 204087 101928 204087 101891 204087 101900 204088 101892 204088 101893 204088 101893 204089 101892 204089 101894 204089 101893 204090 101894 204090 101895 204090 101895 204091 101894 204091 101896 204091 101895 204092 101896 204092 101989 204092 101989 204093 101896 204093 101929 204093 101989 204094 101929 204094 101890 204094 101984 204095 101922 204095 101897 204095 101897 204096 101922 204096 101920 204096 101897 204097 101920 204097 101979 204097 101898 204098 99224 204098 101899 204098 101899 204099 99224 204099 101892 204099 101899 204100 101892 204100 101900 204100 101578 204101 101597 204101 101901 204101 101901 204102 101597 204102 101933 204102 101901 204103 101933 204103 99225 204103 101902 204104 101903 204104 101918 204104 101918 204105 101903 204105 101979 204105 101918 204106 101979 204106 101920 204106 101915 204107 99221 204107 101919 204107 101919 204108 99221 204108 101506 204108 101919 204109 101506 204109 101902 204109 101902 204110 101506 204110 101508 204110 101902 204111 101508 204111 101903 204111 101903 204112 101508 204112 101509 204112 101906 204113 101503 204113 101502 204113 101906 204114 101502 204114 101904 204114 101904 204115 101502 204115 101905 204115 101904 204116 101905 204116 101582 204116 101503 204117 101906 204117 101908 204117 101908 204118 101906 204118 101907 204118 101908 204119 101907 204119 101978 204119 101978 204120 101907 204120 101977 204120 101977 204121 101907 204121 101909 204121 101977 204122 101909 204122 101974 204122 101914 204123 101910 204123 101911 204123 101911 204124 101910 204124 101951 204124 101911 204125 101951 204125 101949 204125 101615 204126 101475 204126 101935 204126 101935 204127 101475 204127 101912 204127 101935 204128 101912 204128 99220 204128 99220 204129 101912 204129 101545 204129 99220 204130 101545 204130 101914 204130 101914 204131 101545 204131 101913 204131 101914 204132 101913 204132 101910 204132 99211 204133 101596 204133 99210 204133 99210 204134 101596 204134 101915 204134 99210 204135 101915 204135 101917 204135 101917 204136 101915 204136 101919 204136 101920 204137 101916 204137 101918 204137 101918 204138 101916 204138 101917 204138 101918 204139 101917 204139 101902 204139 101902 204140 101917 204140 101919 204140 101922 204141 101921 204141 101920 204141 101920 204142 101921 204142 101916 204142 101923 204143 101921 204143 101922 204143 101922 204144 101889 204144 101923 204144 101923 204145 101889 204145 101924 204145 101923 204146 101924 204146 101925 204146 101925 204147 101924 204147 99227 204147 101925 204148 99227 204148 101926 204148 101926 204149 99227 204149 101928 204149 101926 204150 101928 204150 101927 204150 101927 204151 101928 204151 101929 204151 101927 204152 101929 204152 102088 204152 99204 204153 102088 204153 101929 204153 99204 204154 101929 204154 99205 204154 101892 204155 101930 204155 101894 204155 101894 204156 101930 204156 99205 204156 101894 204157 99205 204157 101896 204157 101896 204158 99205 204158 101929 204158 99224 204159 101931 204159 101892 204159 101892 204160 101931 204160 101930 204160 99202 204161 101931 204161 99224 204161 99224 204162 99222 204162 99202 204162 99202 204163 99222 204163 101932 204163 99202 204164 101932 204164 99201 204164 99201 204165 101932 204165 101933 204165 99201 204166 101933 204166 101934 204166 101934 204167 101933 204167 101597 204167 101615 204168 101935 204168 104049 204168 104049 204169 101935 204169 101936 204169 101887 204170 101937 204170 101911 204170 101911 204171 101937 204171 99219 204171 101938 204172 102076 204172 99228 204172 99228 204173 102076 204173 101939 204173 101938 204174 101877 204174 102076 204174 102076 204175 101877 204175 101940 204175 101943 204176 101941 204176 102080 204176 102078 204177 99231 204177 101942 204177 101942 204178 99231 204178 101943 204178 101942 204179 101943 204179 101944 204179 101944 204180 101943 204180 102080 204180 101909 204181 101945 204181 101941 204181 101941 204182 101945 204182 102080 204182 101904 204183 101946 204183 101906 204183 101906 204184 101946 204184 102081 204184 101906 204185 102081 204185 101907 204185 101907 204186 102081 204186 102082 204186 101907 204187 102082 204187 101909 204187 101909 204188 102082 204188 101945 204188 101913 204189 101947 204189 101910 204189 101910 204190 101947 204190 101951 204190 101948 204191 101949 204191 101950 204191 101950 204192 101949 204192 101951 204192 101950 204193 101951 204193 101952 204193 101952 204194 101951 204194 101947 204194 101949 204195 101948 204195 101886 204195 101886 204196 101948 204196 101953 204196 101886 204197 101953 204197 101382 204197 101886 204198 101382 204198 99230 204198 99230 204199 101382 204199 101954 204199 99230 204200 101954 204200 101956 204200 101956 204201 101954 204201 101955 204201 101956 204202 101955 204202 101957 204202 101957 204203 101955 204203 101958 204203 101957 204204 101958 204204 101959 204204 101959 204205 101958 204205 101961 204205 101963 204206 101960 204206 101965 204206 101959 204207 101961 204207 101962 204207 101962 204208 101961 204208 101963 204208 101962 204209 101963 204209 101964 204209 101964 204210 101963 204210 101965 204210 101966 204211 101969 204211 99233 204211 101966 204212 99233 204212 101697 204212 99233 204213 101878 204213 101697 204213 101697 204214 101878 204214 101965 204214 101697 204215 101965 204215 101960 204215 99381 204216 101970 204216 101882 204216 101882 204217 101967 204217 99381 204217 99381 204218 101967 204218 101880 204218 99381 204219 101880 204219 101969 204219 101969 204220 101880 204220 101968 204220 101969 204221 101968 204221 99233 204221 101882 204222 101970 204222 101971 204222 101971 204223 101970 204223 99537 204223 101971 204224 99537 204224 101883 204224 101883 204225 99537 204225 99538 204225 101883 204226 99538 204226 101884 204226 101884 204227 99538 204227 99544 204227 101884 204228 99544 204228 101879 204228 101879 204229 99544 204229 99543 204229 101879 204230 99543 204230 101972 204230 101972 204231 99543 204231 101973 204231 101972 204232 101973 204232 101974 204232 101974 204233 101973 204233 101975 204233 101974 204234 101975 204234 101977 204234 101977 204235 101975 204235 101976 204235 101976 204236 99540 204236 101977 204236 101977 204237 99540 204237 101504 204237 101977 204238 101504 204238 101978 204238 101978 204239 101504 204239 101908 204239 101507 204240 99551 204240 99550 204240 101980 204241 101979 204241 99550 204241 99550 204242 101979 204242 101903 204242 99550 204243 101903 204243 101507 204243 101507 204244 101903 204244 101509 204244 101979 204245 101980 204245 101981 204245 101981 204246 101980 204246 101982 204246 101981 204247 101982 204247 101984 204247 101984 204248 101982 204248 99549 204248 101984 204249 99549 204249 101983 204249 101984 204250 101983 204250 101985 204250 101983 204251 99548 204251 101985 204251 101985 204252 99548 204252 101986 204252 101985 204253 101986 204253 101888 204253 101888 204254 101986 204254 101987 204254 101987 204255 101986 204255 99547 204255 101987 204256 99547 204256 99213 204256 101890 204257 101891 204257 101390 204257 101390 204258 101891 204258 99545 204258 101890 204259 101390 204259 101988 204259 101890 204260 101988 204260 101989 204260 101989 204261 101988 204261 101990 204261 101989 204262 101990 204262 101895 204262 101895 204263 101990 204263 101991 204263 101895 204264 101991 204264 101893 204264 101893 204265 101991 204265 101992 204265 101893 204266 101992 204266 101900 204266 101900 204267 101992 204267 101899 204267 101899 204268 101992 204268 101384 204268 101899 204269 101384 204269 101898 204269 101898 204270 101384 204270 101385 204270 101898 204271 101385 204271 99223 204271 99223 204272 101385 204272 101993 204272 101993 204273 101387 204273 99223 204273 99223 204274 101387 204274 101580 204274 99223 204275 101580 204275 101994 204275 98144 204276 102014 204276 98142 204276 98142 204277 102014 204277 101995 204277 98142 204278 101995 204278 98141 204278 98141 204279 101995 204279 102186 204279 98141 204280 102186 204280 101996 204280 101996 204281 102186 204281 101997 204281 101996 204282 101997 204282 101998 204282 101999 204283 102000 204283 98132 204283 98132 204284 102000 204284 102001 204284 98132 204285 102001 204285 98130 204285 98130 204286 102001 204286 102003 204286 98130 204287 102003 204287 102002 204287 102002 204288 102003 204288 102004 204288 102002 204289 102004 204289 98129 204289 98136 204290 102179 204290 98135 204290 98135 204291 102179 204291 102178 204291 98135 204292 102178 204292 102005 204292 102005 204293 102178 204293 102176 204293 102005 204294 102176 204294 98134 204294 98134 204295 102176 204295 102174 204295 98134 204296 102174 204296 101999 204296 101999 204297 102174 204297 102006 204297 101999 204298 102006 204298 102000 204298 102018 204299 99136 204299 98125 204299 98125 204300 99136 204300 99134 204300 98125 204301 99134 204301 102007 204301 102007 204302 99134 204302 99132 204302 102007 204303 99132 204303 98149 204303 98149 204304 99132 204304 99131 204304 98149 204305 99131 204305 98148 204305 101997 204306 102184 204306 101998 204306 101998 204307 102184 204307 102183 204307 101998 204308 102183 204308 102008 204308 102008 204309 102183 204309 102009 204309 102008 204310 102009 204310 102010 204310 102010 204311 102009 204311 102182 204311 102010 204312 102182 204312 98136 204312 98136 204313 102182 204313 102181 204313 98136 204314 102181 204314 102179 204314 99131 204315 102011 204315 98148 204315 98148 204316 102011 204316 102012 204316 98148 204317 102012 204317 98147 204317 98147 204318 102012 204318 99128 204318 98147 204319 99128 204319 102013 204319 102013 204320 99128 204320 99127 204320 102013 204321 99127 204321 98144 204321 98144 204322 99127 204322 102188 204322 98144 204323 102188 204323 102014 204323 102004 204324 99140 204324 98129 204324 98129 204325 99140 204325 102015 204325 98129 204326 102015 204326 102016 204326 102016 204327 102015 204327 99138 204327 102016 204328 99138 204328 98128 204328 98128 204329 99138 204329 102017 204329 98128 204330 102017 204330 102018 204330 102018 204331 102017 204331 102019 204331 102018 204332 102019 204332 99136 204332 104221 204333 98341 204333 102020 204333 102020 204334 98341 204334 102021 204334 102020 204335 102021 204335 102022 204335 102022 204336 102021 204336 102023 204336 102022 204337 102023 204337 102024 204337 102024 204338 102023 204338 102025 204338 102025 204339 102023 204339 98345 204339 102025 204340 98345 204340 102026 204340 102026 204341 98345 204341 98344 204341 102026 204342 98344 204342 99200 204342 99200 204343 98344 204343 102027 204343 102027 204344 98344 204344 98342 204344 102027 204345 98342 204345 102099 204345 102099 204346 98342 204346 102028 204346 102033 204347 102107 204347 102102 204347 102033 204348 102102 204348 102029 204348 102029 204349 102102 204349 102103 204349 102029 204350 102103 204350 98338 204350 98338 204351 102103 204351 102106 204351 98338 204352 102106 204352 102030 204352 102030 204353 102106 204353 102099 204353 102030 204354 102099 204354 102028 204354 102041 204355 102108 204355 102031 204355 102041 204356 102031 204356 102032 204356 102032 204357 102031 204357 102107 204357 102032 204358 102107 204358 102033 204358 102034 204359 102035 204359 102037 204359 102034 204360 102037 204360 102036 204360 102036 204361 102037 204361 102111 204361 102036 204362 102111 204362 104086 204362 102111 204363 102038 204363 104086 204363 104086 204364 102038 204364 102039 204364 104086 204365 102039 204365 102040 204365 102040 204366 102039 204366 102108 204366 102040 204367 102108 204367 102041 204367 102035 204368 102034 204368 102042 204368 102042 204369 102034 204369 102043 204369 102042 204370 102043 204370 102044 204370 102044 204371 102043 204371 102045 204371 102044 204372 102045 204372 104084 204372 102044 204373 104084 204373 102046 204373 102046 204374 104084 204374 102047 204374 102046 204375 102047 204375 102048 204375 102048 204376 102047 204376 102049 204376 102048 204377 102049 204377 102091 204377 102091 204378 102049 204378 102090 204378 102090 204379 102049 204379 104083 204379 102090 204380 104083 204380 104082 204380 104079 204381 104080 204381 102051 204381 104079 204382 102051 204382 102050 204382 102050 204383 102051 204383 102052 204383 102050 204384 102052 204384 102053 204384 102053 204385 102052 204385 104189 204385 102053 204386 104189 204386 102097 204386 102097 204387 104189 204387 102054 204387 102097 204388 102054 204388 102096 204388 102096 204389 102054 204389 102055 204389 102055 204390 102054 204390 104188 204390 102055 204391 104188 204391 102118 204391 102118 204392 104188 204392 102058 204392 104183 204393 99190 204393 102056 204393 104183 204394 102056 204394 104185 204394 104185 204395 102056 204395 102116 204395 104185 204396 102116 204396 104186 204396 104186 204397 102116 204397 102117 204397 104186 204398 102117 204398 102057 204398 102057 204399 102117 204399 102118 204399 102057 204400 102118 204400 102058 204400 102113 204401 102059 204401 102060 204401 102060 204402 102059 204402 99212 204402 99191 204403 102064 204403 98246 204403 98246 204404 102064 204404 102063 204404 102113 204405 102060 204405 99193 204405 99193 204406 102060 204406 98256 204406 99193 204407 98256 204407 99195 204407 99195 204408 98256 204408 102062 204408 99195 204409 102062 204409 102061 204409 102061 204410 102062 204410 102063 204410 102061 204411 102063 204411 99198 204411 99198 204412 102063 204412 102064 204412 99191 204413 98246 204413 102065 204413 102065 204414 98246 204414 98250 204414 102065 204415 98250 204415 102095 204415 102095 204416 98250 204416 98251 204416 102095 204417 98251 204417 102066 204417 102095 204418 102066 204418 102067 204418 102067 204419 102066 204419 98248 204419 102067 204420 98248 204420 102094 204420 102094 204421 98248 204421 98247 204421 102094 204422 98247 204422 102068 204422 102068 204423 98247 204423 98253 204423 102068 204424 98253 204424 102069 204424 99219 204425 102075 204425 102070 204425 99219 204426 102070 204426 102071 204426 102071 204427 102070 204427 102073 204427 102071 204428 102073 204428 102072 204428 102072 204429 102073 204429 101936 204429 101936 204430 102073 204430 102074 204430 101936 204431 102074 204431 104049 204431 102075 204432 99219 204432 102112 204432 102112 204433 99219 204433 101937 204433 102076 204434 102077 204434 101939 204434 101939 204435 102077 204435 99192 204435 101939 204436 99192 204436 99216 204436 99216 204437 99192 204437 99194 204437 99216 204438 99194 204438 99218 204438 102112 204439 101937 204439 99197 204439 99197 204440 101937 204440 99218 204440 99197 204441 99218 204441 99196 204441 99196 204442 99218 204442 99194 204442 99215 204443 102119 204443 102120 204443 99215 204444 102120 204444 101940 204444 101940 204445 102120 204445 102077 204445 101940 204446 102077 204446 102076 204446 102119 204447 99215 204447 99189 204447 99189 204448 99215 204448 102078 204448 99189 204449 102078 204449 102114 204449 102114 204450 102078 204450 101942 204450 102114 204451 101942 204451 102115 204451 102115 204452 101942 204452 101944 204452 102115 204453 101944 204453 102079 204453 102079 204454 101944 204454 102080 204454 102079 204455 102080 204455 102084 204455 102084 204456 102080 204456 101945 204456 101946 204457 101581 204457 104253 204457 101946 204458 104253 204458 102081 204458 104253 204459 102098 204459 102081 204459 102081 204460 102098 204460 102083 204460 102081 204461 102083 204461 102082 204461 102082 204462 102083 204462 102084 204462 102082 204463 102084 204463 101945 204463 101916 204464 102093 204464 102092 204464 101916 204465 102092 204465 101917 204465 101917 204466 102092 204466 99208 204466 101917 204467 99208 204467 99210 204467 102093 204468 101916 204468 102085 204468 102085 204469 101916 204469 101921 204469 101923 204470 101925 204470 102086 204470 102085 204471 101921 204471 102110 204471 102110 204472 101921 204472 101923 204472 102110 204473 101923 204473 102109 204473 102109 204474 101923 204474 102086 204474 102087 204475 99206 204475 102088 204475 102088 204476 99206 204476 101927 204476 102087 204477 102088 204477 102104 204477 102104 204478 102088 204478 99204 204478 102100 204479 101930 204479 102101 204479 102101 204480 101930 204480 101931 204480 104223 204481 102089 204481 101934 204481 101934 204482 102089 204482 99201 204482 104223 204483 104221 204483 102089 204483 102089 204484 104221 204484 102020 204484 102089 204485 102020 204485 102022 204485 102090 204486 99208 204486 102091 204486 102091 204487 99208 204487 102092 204487 102091 204488 102092 204488 102048 204488 102048 204489 102092 204489 102046 204489 102046 204490 102092 204490 102093 204490 102046 204491 102093 204491 102044 204491 102069 204492 102074 204492 102068 204492 102068 204493 102074 204493 102073 204493 102068 204494 102073 204494 102094 204494 102094 204495 102073 204495 102070 204495 102094 204496 102070 204496 102067 204496 102067 204497 102070 204497 102075 204497 102067 204498 102075 204498 102095 204498 102097 204499 102096 204499 102084 204499 102097 204500 102084 204500 102053 204500 102084 204501 102083 204501 102053 204501 102053 204502 102083 204502 102098 204502 102053 204503 102098 204503 102050 204503 102050 204504 102098 204504 104253 204504 102050 204505 104253 204505 104079 204505 102099 204506 102100 204506 102027 204506 102027 204507 102100 204507 102101 204507 102027 204508 102101 204508 99200 204508 102044 204509 102093 204509 102042 204509 102042 204510 102093 204510 102085 204510 102042 204511 102085 204511 102035 204511 102107 204512 102087 204512 102102 204512 102102 204513 102087 204513 102104 204513 102102 204514 102104 204514 102103 204514 102104 204515 99203 204515 102103 204515 102103 204516 99203 204516 102105 204516 102103 204517 102105 204517 102106 204517 102106 204518 102105 204518 102100 204518 102106 204519 102100 204519 102099 204519 102107 204520 102031 204520 102087 204520 102087 204521 102031 204521 99206 204521 102035 204522 102085 204522 102037 204522 102037 204523 102085 204523 102110 204523 99207 204524 102108 204524 102086 204524 102086 204525 102108 204525 102039 204525 102086 204526 102039 204526 102109 204526 102109 204527 102039 204527 102038 204527 102109 204528 102038 204528 102110 204528 102110 204529 102038 204529 102111 204529 102110 204530 102111 204530 102037 204530 102095 204531 102075 204531 102065 204531 102065 204532 102075 204532 102112 204532 102065 204533 102112 204533 99191 204533 102118 204534 102079 204534 102055 204534 102055 204535 102079 204535 102084 204535 102055 204536 102084 204536 102096 204536 99192 204537 102077 204537 99193 204537 99193 204538 102077 204538 102113 204538 102056 204539 99189 204539 102114 204539 102056 204540 102114 204540 102116 204540 102116 204541 102114 204541 102115 204541 102116 204542 102115 204542 102117 204542 102117 204543 102115 204543 102079 204543 102117 204544 102079 204544 102118 204544 102119 204545 99190 204545 102059 204545 102119 204546 102059 204546 102120 204546 102120 204547 102059 204547 102113 204547 102120 204548 102113 204548 102077 204548 99188 204549 103803 204549 102121 204549 99188 204550 102121 204550 102122 204550 102122 204551 102121 204551 102123 204551 102122 204552 102123 204552 103788 204552 103788 204553 102123 204553 103802 204553 103788 204554 103802 204554 103789 204554 103789 204555 103802 204555 103801 204555 103789 204556 103801 204556 102124 204556 102124 204557 103801 204557 102125 204557 102124 204558 102125 204558 103760 204558 103760 204559 102125 204559 103799 204559 103760 204560 103799 204560 103761 204560 103761 204561 103799 204561 102126 204561 103761 204562 102126 204562 102127 204562 102127 204563 102126 204563 102129 204563 102127 204564 102129 204564 102128 204564 102128 204565 102129 204565 102130 204565 102128 204566 102130 204566 102131 204566 102131 204567 102130 204567 103795 204567 102131 204568 103795 204568 103764 204568 103764 204569 103795 204569 102132 204569 103764 204570 102132 204570 102133 204570 102133 204571 102132 204571 102134 204571 102133 204572 102134 204572 103766 204572 103766 204573 102134 204573 103793 204573 103766 204574 103793 204574 102135 204574 102135 204575 103793 204575 102136 204575 102135 204576 102136 204576 103767 204576 103767 204577 102136 204577 103791 204577 103767 204578 103791 204578 103769 204578 103769 204579 103791 204579 102137 204579 103769 204580 102137 204580 103770 204580 103770 204581 102137 204581 102138 204581 103770 204582 102138 204582 103771 204582 102139 204583 102140 204583 102141 204583 102141 204584 102140 204584 103735 204584 102141 204585 103735 204585 103694 204585 103694 204586 103735 204586 102142 204586 103694 204587 102142 204587 102143 204587 102143 204588 102142 204588 102144 204588 102143 204589 102144 204589 102145 204589 102145 204590 102144 204590 103738 204590 102145 204591 103738 204591 103696 204591 103696 204592 103738 204592 103707 204592 103696 204593 103707 204593 102146 204593 102146 204594 103707 204594 103708 204594 102146 204595 103708 204595 103698 204595 103698 204596 103708 204596 103710 204596 103698 204597 103710 204597 102148 204597 102148 204598 103710 204598 102147 204598 102148 204599 102147 204599 103699 204599 103699 204600 102147 204600 103711 204600 103699 204601 103711 204601 103700 204601 103700 204602 103711 204602 102149 204602 103700 204603 102149 204603 103701 204603 103701 204604 102149 204604 103714 204604 103701 204605 103714 204605 103702 204605 103702 204606 103714 204606 102150 204606 103702 204607 102150 204607 103703 204607 103703 204608 102150 204608 102151 204608 103703 204609 102151 204609 103706 204609 103706 204610 102151 204610 103716 204610 103706 204611 103716 204611 102152 204611 102152 204612 103716 204612 102153 204612 102152 204613 102153 204613 98503 204613 98503 204614 102153 204614 103719 204614 99160 204615 103687 204615 102154 204615 102154 204616 103687 204616 102155 204616 102154 204617 102155 204617 103982 204617 103982 204618 102155 204618 103688 204618 103982 204619 103688 204619 102156 204619 102156 204620 103688 204620 103689 204620 102156 204621 103689 204621 102157 204621 102157 204622 103689 204622 103690 204622 102157 204623 103690 204623 103984 204623 103984 204624 103690 204624 102158 204624 103984 204625 102158 204625 103986 204625 103986 204626 102158 204626 102159 204626 103986 204627 102159 204627 103988 204627 103988 204628 102159 204628 102160 204628 103988 204629 102160 204629 102161 204629 102161 204630 102160 204630 102162 204630 102161 204631 102162 204631 103990 204631 103990 204632 102162 204632 103665 204632 103990 204633 103665 204633 103992 204633 103992 204634 103665 204634 102164 204634 103992 204635 102164 204635 102163 204635 102163 204636 102164 204636 102165 204636 102163 204637 102165 204637 102166 204637 102166 204638 102165 204638 102167 204638 102166 204639 102167 204639 103994 204639 103994 204640 102167 204640 102168 204640 103994 204641 102168 204641 103996 204641 103996 204642 102168 204642 102169 204642 103996 204643 102169 204643 102170 204643 102170 204644 102169 204644 102171 204644 102170 204645 102171 204645 102172 204645 102172 204646 102171 204646 99143 204646 103997 204647 102000 204647 102173 204647 102173 204648 102000 204648 102006 204648 102173 204649 102006 204649 103995 204649 103995 204650 102006 204650 102174 204650 103995 204651 102174 204651 102175 204651 102175 204652 102174 204652 102176 204652 102175 204653 102176 204653 103993 204653 103993 204654 102176 204654 102178 204654 103993 204655 102178 204655 102177 204655 102177 204656 102178 204656 102179 204656 102177 204657 102179 204657 103991 204657 103991 204658 102179 204658 102181 204658 103991 204659 102181 204659 102180 204659 102180 204660 102181 204660 102182 204660 102180 204661 102182 204661 103989 204661 103989 204662 102182 204662 102009 204662 103989 204663 102009 204663 103987 204663 103987 204664 102009 204664 102183 204664 103987 204665 102183 204665 102185 204665 102185 204666 102183 204666 102184 204666 102185 204667 102184 204667 103985 204667 103985 204668 102184 204668 101997 204668 103985 204669 101997 204669 103983 204669 103983 204670 101997 204670 102186 204670 103983 204671 102186 204671 103981 204671 103981 204672 102186 204672 101995 204672 103981 204673 101995 204673 102187 204673 102187 204674 101995 204674 102014 204674 102187 204675 102014 204675 103980 204675 103980 204676 102014 204676 102188 204676 103980 204677 102188 204677 98420 204677 98420 204678 102188 204678 99127 204678 103933 204679 103977 204679 102189 204679 103933 204680 102189 204680 102190 204680 102190 204681 102189 204681 103975 204681 102190 204682 103975 204682 103935 204682 103935 204683 103975 204683 103974 204683 103935 204684 103974 204684 102192 204684 102192 204685 103974 204685 102191 204685 102192 204686 102191 204686 102193 204686 102193 204687 102191 204687 103968 204687 102193 204688 103968 204688 103938 204688 103938 204689 103968 204689 103969 204689 103938 204690 103969 204690 103939 204690 103939 204691 103969 204691 103966 204691 103939 204692 103966 204692 102194 204692 102194 204693 103966 204693 102195 204693 102194 204694 102195 204694 102196 204694 102196 204695 102195 204695 102197 204695 102196 204696 102197 204696 102198 204696 102198 204697 102197 204697 103962 204697 102198 204698 103962 204698 103899 204698 103899 204699 103962 204699 103958 204699 103899 204700 103958 204700 103900 204700 103900 204701 103958 204701 103956 204701 103900 204702 103956 204702 103902 204702 103902 204703 103956 204703 103953 204703 103902 204704 103953 204704 103905 204704 103905 204705 103953 204705 103952 204705 103905 204706 103952 204706 102199 204706 102199 204707 103952 204707 102200 204707 102199 204708 102200 204708 103907 204708 103907 204709 102200 204709 103947 204709 103907 204710 103947 204710 103908 204710 103908 204711 103947 204711 103943 204711 103908 204712 103943 204712 103910 204712 103910 204713 103943 204713 103944 204713 103910 204714 103944 204714 99113 204714 99111 204715 103911 204715 103882 204715 103882 204716 103911 204716 102201 204716 103882 204717 102201 204717 102202 204717 102202 204718 102201 204718 103912 204718 102202 204719 103912 204719 103883 204719 103883 204720 103912 204720 103913 204720 103883 204721 103913 204721 103884 204721 103884 204722 103913 204722 103915 204722 103884 204723 103915 204723 102203 204723 102203 204724 103915 204724 102204 204724 102203 204725 102204 204725 103886 204725 103886 204726 102204 204726 103917 204726 103886 204727 103917 204727 102205 204727 102205 204728 103917 204728 103920 204728 102205 204729 103920 204729 103888 204729 103888 204730 103920 204730 103921 204730 103888 204731 103921 204731 103889 204731 103889 204732 103921 204732 102206 204732 103889 204733 102206 204733 103891 204733 103891 204734 102206 204734 103923 204734 103891 204735 103923 204735 102207 204735 102207 204736 103923 204736 103925 204736 102207 204737 103925 204737 103892 204737 103892 204738 103925 204738 103926 204738 103892 204739 103926 204739 103893 204739 103893 204740 103926 204740 103927 204740 103893 204741 103927 204741 103895 204741 103895 204742 103927 204742 102208 204742 103895 204743 102208 204743 103896 204743 103896 204744 102208 204744 103930 204744 103896 204745 103930 204745 102209 204745 102209 204746 103930 204746 102211 204746 102209 204747 102211 204747 102210 204747 102210 204748 102211 204748 103931 204748 102210 204749 103931 204749 102212 204749 102212 204750 103931 204750 102213 204750 103998 204751 99092 204751 102214 204751 102214 204752 99092 204752 103873 204752 102214 204753 103873 204753 104000 204753 104000 204754 103873 204754 103874 204754 104000 204755 103874 204755 104001 204755 104001 204756 103874 204756 102215 204756 104001 204757 102215 204757 104003 204757 104003 204758 102215 204758 103878 204758 104003 204759 103878 204759 102216 204759 102216 204760 103878 204760 103879 204760 102216 204761 103879 204761 102217 204761 102217 204762 103879 204762 103837 204762 102217 204763 103837 204763 102218 204763 102218 204764 103837 204764 102219 204764 102218 204765 102219 204765 104007 204765 104007 204766 102219 204766 102220 204766 104007 204767 102220 204767 104009 204767 104009 204768 102220 204768 102221 204768 104009 204769 102221 204769 104010 204769 104010 204770 102221 204770 103840 204770 104010 204771 103840 204771 102222 204771 102222 204772 103840 204772 103842 204772 102222 204773 103842 204773 104012 204773 104012 204774 103842 204774 103844 204774 104012 204775 103844 204775 102223 204775 102223 204776 103844 204776 102224 204776 102223 204777 102224 204777 104014 204777 104014 204778 102224 204778 103846 204778 104014 204779 103846 204779 102225 204779 102225 204780 103846 204780 103848 204780 102225 204781 103848 204781 102226 204781 102226 204782 103848 204782 103849 204782 102226 204783 103849 204783 98392 204783 98392 204784 103849 204784 99076 204784 102227 204785 103758 204785 102228 204785 102227 204786 102228 204786 102229 204786 102229 204787 102228 204787 103756 204787 102229 204788 103756 204788 102231 204788 102231 204789 103756 204789 102230 204789 102231 204790 102230 204790 102232 204790 102232 204791 102230 204791 102233 204791 102232 204792 102233 204792 102234 204792 102234 204793 102233 204793 102236 204793 102234 204794 102236 204794 102235 204794 102235 204795 102236 204795 102237 204795 102235 204796 102237 204796 103723 204796 103723 204797 102237 204797 103751 204797 103723 204798 103751 204798 103725 204798 103725 204799 103751 204799 103750 204799 103725 204800 103750 204800 103727 204800 103727 204801 103750 204801 103748 204801 103727 204802 103748 204802 102238 204802 102238 204803 103748 204803 102239 204803 102238 204804 102239 204804 102240 204804 102240 204805 102239 204805 103747 204805 102240 204806 103747 204806 103728 204806 103728 204807 103747 204807 102241 204807 103728 204808 102241 204808 103731 204808 103731 204809 102241 204809 103743 204809 103731 204810 103743 204810 102242 204810 102242 204811 103743 204811 103741 204811 102242 204812 103741 204812 103733 204812 103733 204813 103741 204813 102243 204813 103733 204814 102243 204814 103734 204814 103734 204815 102243 204815 98502 204815 103734 204816 98502 204816 99063 204816 102255 204817 102244 204817 104257 204817 102742 204818 102254 204818 104279 204818 104279 204819 102254 204819 102246 204819 104279 204820 102246 204820 102245 204820 102245 204821 102246 204821 104203 204821 102245 204822 104203 204822 104256 204822 104256 204823 104203 204823 104159 204823 104256 204824 104159 204824 104257 204824 104257 204825 104159 204825 102247 204825 104257 204826 102247 204826 102255 204826 102248 204827 102249 204827 102250 204827 102250 204828 102249 204828 102251 204828 102250 204829 102251 204829 104151 204829 104151 204830 102251 204830 102739 204830 104151 204831 102739 204831 102252 204831 102252 204832 102739 204832 102740 204832 102252 204833 102740 204833 102253 204833 102248 204834 102250 204834 102741 204834 102741 204835 102250 204835 102254 204835 102741 204836 102254 204836 102742 204836 102255 204837 102256 204837 102244 204837 102244 204838 102256 204838 102257 204838 102257 204839 102256 204839 102258 204839 102258 204840 102256 204840 102259 204840 102258 204841 102259 204841 102260 204841 102260 204842 102259 204842 102261 204842 102261 204843 102259 204843 102262 204843 102261 204844 102262 204844 102746 204844 102746 204845 102262 204845 102264 204845 102746 204846 102264 204846 102265 204846 102284 204847 102253 204847 102263 204847 102263 204848 102253 204848 102740 204848 104161 204849 102302 204849 102264 204849 102264 204850 102302 204850 102265 204850 102999 204851 103000 204851 104204 204851 104204 204852 103000 204852 104145 204852 104145 204853 103000 204853 102266 204853 104145 204854 102266 204854 102267 204854 102999 204855 104204 204855 102268 204855 102268 204856 104204 204856 102269 204856 102268 204857 102269 204857 102998 204857 102998 204858 102269 204858 104158 204858 102998 204859 104158 204859 102271 204859 102279 204860 102277 204860 104155 204860 104158 204861 102270 204861 102271 204861 102271 204862 102270 204862 104157 204862 102271 204863 104157 204863 102272 204863 102272 204864 104157 204864 102273 204864 102272 204865 102273 204865 102996 204865 102996 204866 102273 204866 102274 204866 102996 204867 102274 204867 102997 204867 102997 204868 102274 204868 102275 204868 102997 204869 102275 204869 102995 204869 102995 204870 102275 204870 102276 204870 102995 204871 102276 204871 102277 204871 102277 204872 102276 204872 102278 204872 102277 204873 102278 204873 104155 204873 104155 204874 104154 204874 102279 204874 102279 204875 104154 204875 102281 204875 102279 204876 102281 204876 102280 204876 102280 204877 102281 204877 104153 204877 102280 204878 104153 204878 102282 204878 102282 204879 104153 204879 102283 204879 102282 204880 102283 204880 102993 204880 102993 204881 102283 204881 102284 204881 102993 204882 102284 204882 102263 204882 102285 204883 103019 204883 102286 204883 102285 204884 102286 204884 104165 204884 104165 204885 102286 204885 102287 204885 104165 204886 102287 204886 102288 204886 102288 204887 102287 204887 103020 204887 102288 204888 103020 204888 102289 204888 102289 204889 103020 204889 104166 204889 104166 204890 103020 204890 103021 204890 104166 204891 103021 204891 104167 204891 104167 204892 103021 204892 102290 204892 104167 204893 102290 204893 102291 204893 102291 204894 102290 204894 103022 204894 102291 204895 103022 204895 102292 204895 102292 204896 103022 204896 102293 204896 102292 204897 102293 204897 102294 204897 102294 204898 102293 204898 103024 204898 102294 204899 103024 204899 104197 204899 103024 204900 102295 204900 104197 204900 104197 204901 102295 204901 102296 204901 104197 204902 102296 204902 104199 204902 104199 204903 102296 204903 103025 204903 104199 204904 103025 204904 102299 204904 102299 204905 103025 204905 102297 204905 102297 204906 102298 204906 102299 204906 102299 204907 102298 204907 102301 204907 102299 204908 102301 204908 102300 204908 102300 204909 102301 204909 104160 204909 104160 204910 102301 204910 102302 204910 104160 204911 102302 204911 104161 204911 102267 204912 102266 204912 102308 204912 102308 204913 102266 204913 102738 204913 102285 204914 102303 204914 103019 204914 103019 204915 102303 204915 102304 204915 104149 204916 102305 204916 102306 204916 102306 204917 102305 204917 102735 204917 102735 204918 102305 204918 102307 204918 102307 204919 102305 204919 104147 204919 102307 204920 104147 204920 102734 204920 102734 204921 104147 204921 102736 204921 102736 204922 104147 204922 104146 204922 102736 204923 104146 204923 102737 204923 102737 204924 104146 204924 102308 204924 102737 204925 102308 204925 102738 204925 102750 204926 102749 204926 102313 204926 102313 204927 102749 204927 102747 204927 102313 204928 102747 204928 102309 204928 102309 204929 102747 204929 102310 204929 102309 204930 102310 204930 102311 204930 102311 204931 102310 204931 102304 204931 102311 204932 102304 204932 102303 204932 102750 204933 102313 204933 102312 204933 102312 204934 102313 204934 102326 204934 102312 204935 102326 204935 102752 204935 104149 204936 102306 204936 104144 204936 104144 204937 102306 204937 102314 204937 104144 204938 102314 204938 102315 204938 102315 204939 102314 204939 102316 204939 102315 204940 102316 204940 102317 204940 99043 204941 104133 204941 102318 204941 102318 204942 104133 204942 102319 204942 102318 204943 102319 204943 102317 204943 102317 204944 102319 204944 102320 204944 102317 204945 102320 204945 102315 204945 102321 204946 102322 204946 104192 204946 104192 204947 102322 204947 104280 204947 104192 204948 104280 204948 104193 204948 104193 204949 104280 204949 102323 204949 104193 204950 102323 204950 102324 204950 102324 204951 102323 204951 104281 204951 102324 204952 104281 204952 104196 204952 104196 204953 104281 204953 102325 204953 104196 204954 102325 204954 104163 204954 104163 204955 102325 204955 102327 204955 104163 204956 102327 204956 102326 204956 102326 204957 102327 204957 102752 204957 102328 204958 104136 204958 102329 204958 102329 204959 104136 204959 104135 204959 102329 204960 104135 204960 99044 204960 99044 204961 104135 204961 99046 204961 99046 204962 104135 204962 99048 204962 99048 204963 104135 204963 104134 204963 99048 204964 104134 204964 99049 204964 99049 204965 104134 204965 99040 204965 99040 204966 104134 204966 104138 204966 99040 204967 104138 204967 102330 204967 102330 204968 104138 204968 104133 204968 102330 204969 104133 204969 99043 204969 102321 204970 102331 204970 102322 204970 102322 204971 102331 204971 102758 204971 102758 204972 102331 204972 102756 204972 102756 204973 102331 204973 102332 204973 102756 204974 102332 204974 102755 204974 102755 204975 102332 204975 102754 204975 102754 204976 102332 204976 102333 204976 102754 204977 102333 204977 102760 204977 102760 204978 102333 204978 104181 204978 102760 204979 104181 204979 102762 204979 102349 204980 104136 204980 102334 204980 102334 204981 104136 204981 102328 204981 102372 204982 103047 204982 104181 204982 104181 204983 103047 204983 102762 204983 104206 204984 98944 204984 102335 204984 102335 204985 98944 204985 98945 204985 102335 204986 98945 204986 102336 204986 102343 204987 102337 204987 102338 204987 102338 204988 102337 204988 102339 204988 102338 204989 102339 204989 104206 204989 104206 204990 102339 204990 98943 204990 104206 204991 98943 204991 98944 204991 104141 204992 102350 204992 102340 204992 102340 204993 102350 204993 102341 204993 102338 204994 102342 204994 102343 204994 102343 204995 102342 204995 102345 204995 102343 204996 102345 204996 102344 204996 102344 204997 102345 204997 104127 204997 102344 204998 104127 204998 98939 204998 98939 204999 104127 204999 102346 204999 98939 205000 102346 205000 102347 205000 102347 205001 102346 205001 104143 205001 102347 205002 104143 205002 98941 205002 98941 205003 104143 205003 104142 205003 98941 205004 104142 205004 102341 205004 102341 205005 104142 205005 102348 205005 102341 205006 102348 205006 102340 205006 104139 205007 102349 205007 102334 205007 104141 205008 104140 205008 102350 205008 102350 205009 104140 205009 102351 205009 102350 205010 102351 205010 102352 205010 102352 205011 102351 205011 104139 205011 102352 205012 104139 205012 102353 205012 102353 205013 104139 205013 102334 205013 104175 205014 103041 205014 103042 205014 104175 205015 103042 205015 104176 205015 104176 205016 103042 205016 103043 205016 104176 205017 103043 205017 102354 205017 102354 205018 103043 205018 102355 205018 102354 205019 102355 205019 102357 205019 102357 205020 102355 205020 102356 205020 102357 205021 102356 205021 102358 205021 102358 205022 102356 205022 102359 205022 102358 205023 102359 205023 104178 205023 104178 205024 102359 205024 102360 205024 102360 205025 102359 205025 102361 205025 102360 205026 102361 205026 102362 205026 102362 205027 102361 205027 102363 205027 102362 205028 102363 205028 102364 205028 102364 205029 102363 205029 102365 205029 102364 205030 102365 205030 104179 205030 104179 205031 102365 205031 103044 205031 104179 205032 103044 205032 102366 205032 103044 205033 102367 205033 102366 205033 102366 205034 102367 205034 103046 205034 102366 205035 103046 205035 102368 205035 102368 205036 103046 205036 102369 205036 102368 205037 102369 205037 104180 205037 102369 205038 102370 205038 104180 205038 104180 205039 102370 205039 102371 205039 104180 205040 102371 205040 104191 205040 104191 205041 102371 205041 103047 205041 104191 205042 103047 205042 102372 205042 102336 205043 98945 205043 102373 205043 102373 205044 98945 205044 102978 205044 104175 205045 104174 205045 103041 205045 103041 205046 104174 205046 102378 205046 104131 205047 104132 205047 104266 205047 104266 205048 104132 205048 102728 205048 102728 205049 104132 205049 102726 205049 102726 205050 104132 205050 104129 205050 102726 205051 104129 205051 102724 205051 102724 205052 104129 205052 102374 205052 102374 205053 104129 205053 104128 205053 102374 205054 104128 205054 102731 205054 102731 205055 104128 205055 102373 205055 102731 205056 102373 205056 102978 205056 102767 205057 102766 205057 102375 205057 102375 205058 102766 205058 102376 205058 102375 205059 102376 205059 104170 205059 104170 205060 102376 205060 102377 205060 104170 205061 102377 205061 104171 205061 104171 205062 102377 205062 102378 205062 104171 205063 102378 205063 104174 205063 102767 205064 102375 205064 102379 205064 102379 205065 102375 205065 104169 205065 102379 205066 104169 205066 104078 205066 104131 205067 104266 205067 102380 205067 102380 205068 104266 205068 102381 205068 102380 205069 102381 205069 102382 205069 102382 205070 102381 205070 102383 205070 102382 205071 102383 205071 102384 205071 102384 205072 102383 205072 102385 205072 102384 205073 102385 205073 102386 205073 102385 205074 104276 205074 102386 205074 102386 205075 104276 205075 102394 205075 102386 205076 102394 205076 102387 205076 102399 205077 102388 205077 102389 205077 102389 205078 102388 205078 102723 205078 102723 205079 102388 205079 102390 205079 102390 205080 102388 205080 104120 205080 102390 205081 104120 205081 102391 205081 102391 205082 104120 205082 102392 205082 102391 205083 102392 205083 102393 205083 102393 205084 102392 205084 102387 205084 102393 205085 102387 205085 102394 205085 102395 205086 102397 205086 102396 205086 102396 205087 102397 205087 102774 205087 102774 205088 102397 205088 102772 205088 102772 205089 102397 205089 102398 205089 102772 205090 102398 205090 102771 205090 102771 205091 102398 205091 102770 205091 102770 205092 102398 205092 98266 205092 102770 205093 98266 205093 102777 205093 102777 205094 98266 205094 102400 205094 102777 205095 102400 205095 102778 205095 104209 205096 102399 205096 102959 205096 102959 205097 102399 205097 102389 205097 98268 205098 102424 205098 102400 205098 102400 205099 102424 205099 102778 205099 98954 205100 98955 205100 104112 205100 104112 205101 98955 205101 102401 205101 102401 205102 98955 205102 102402 205102 102401 205103 102402 205103 104116 205103 98954 205104 104112 205104 102403 205104 102403 205105 104112 205105 104211 205105 102403 205106 104211 205106 98953 205106 98953 205107 104211 205107 102404 205107 98953 205108 102404 205108 102405 205108 102405 205109 102404 205109 104110 205109 102405 205110 104110 205110 98946 205110 98946 205111 104110 205111 104111 205111 98946 205112 104111 205112 98947 205112 98947 205113 104111 205113 104107 205113 98947 205114 104107 205114 98948 205114 98948 205115 104107 205115 102406 205115 98948 205116 102406 205116 98949 205116 98949 205117 102406 205117 104108 205117 98949 205118 104108 205118 98950 205118 102408 205119 102407 205119 104124 205119 98950 205120 104108 205120 102407 205120 102407 205121 104108 205121 104106 205121 102407 205122 104106 205122 104124 205122 104121 205123 104209 205123 102959 205123 104124 205124 102409 205124 102408 205124 102408 205125 102409 205125 104122 205125 102408 205126 104122 205126 102963 205126 102963 205127 104122 205127 102410 205127 102963 205128 102410 205128 102411 205128 102411 205129 102410 205129 104121 205129 102411 205130 104121 205130 102962 205130 102962 205131 104121 205131 102959 205131 102426 205132 103064 205132 102413 205132 102426 205133 102413 205133 102412 205133 102412 205134 102413 205134 103065 205134 102412 205135 103065 205135 98259 205135 98259 205136 103065 205136 102414 205136 98259 205137 102414 205137 102415 205137 102415 205138 102414 205138 102416 205138 102415 205139 102416 205139 98260 205139 98260 205140 102416 205140 103067 205140 98260 205141 103067 205141 102417 205141 102417 205142 103067 205142 98262 205142 98262 205143 103067 205143 103068 205143 98262 205144 103068 205144 98263 205144 98263 205145 103068 205145 102418 205145 98263 205146 102418 205146 102419 205146 102419 205147 102418 205147 103070 205147 102419 205148 103070 205148 98264 205148 98264 205149 103070 205149 103069 205149 98264 205150 103069 205150 102420 205150 103069 205151 102421 205151 102420 205151 102420 205152 102421 205152 103072 205152 102420 205153 103072 205153 102422 205153 102422 205154 103072 205154 103073 205154 102422 205155 103073 205155 98265 205155 103073 205156 103074 205156 98265 205156 98265 205157 103074 205157 102423 205157 98265 205158 102423 205158 102425 205158 102425 205159 102423 205159 102424 205159 102425 205160 102424 205160 98268 205160 104116 205161 102402 205161 104113 205161 104113 205162 102402 205162 102720 205162 102426 205163 102433 205163 103064 205163 103064 205164 102433 205164 102432 205164 104118 205165 104119 205165 102715 205165 102715 205166 104119 205166 102718 205166 102718 205167 104119 205167 102717 205167 102717 205168 104119 205168 104117 205168 102717 205169 104117 205169 102716 205169 102716 205170 104117 205170 102427 205170 102427 205171 104117 205171 104115 205171 102427 205172 104115 205172 102428 205172 102428 205173 104115 205173 104113 205173 102428 205174 104113 205174 102720 205174 102429 205175 102782 205175 102434 205175 102434 205176 102782 205176 102781 205176 102434 205177 102781 205177 102430 205177 102430 205178 102781 205178 102431 205178 102430 205179 102431 205179 98258 205179 98258 205180 102431 205180 102432 205180 98258 205181 102432 205181 102433 205181 102429 205182 102434 205182 102784 205182 102784 205183 102434 205183 102435 205183 102784 205184 102435 205184 104219 205184 104118 205185 102715 205185 102436 205185 102436 205186 102715 205186 102437 205186 102436 205187 102437 205187 102438 205187 102438 205188 102437 205188 104275 205188 102438 205189 104275 205189 104215 205189 104215 205190 104275 205190 102439 205190 104215 205191 102439 205191 104216 205191 104216 205192 102439 205192 102440 205192 104216 205193 102440 205193 102441 205193 102441 205194 102440 205194 104273 205194 102441 205195 104273 205195 104088 205195 104088 205196 104273 205196 102454 205196 102455 205197 102443 205197 102442 205197 102442 205198 102443 205198 102444 205198 102442 205199 102444 205199 102446 205199 102446 205200 102444 205200 102445 205200 102446 205201 102445 205201 102447 205201 102447 205202 102445 205202 104237 205202 102447 205203 104237 205203 102448 205203 102448 205204 104237 205204 104236 205204 102448 205205 104236 205205 98372 205205 98372 205206 104236 205206 104220 205206 98372 205207 104220 205207 102435 205207 102435 205208 104220 205208 104219 205208 102449 205209 104090 205209 104091 205209 102449 205210 104091 205210 102714 205210 102714 205211 104091 205211 102450 205211 102714 205212 102450 205212 102712 205212 102712 205213 102450 205213 102711 205213 102711 205214 102450 205214 102451 205214 102711 205215 102451 205215 102452 205215 102452 205216 102451 205216 102453 205216 102453 205217 102451 205217 104088 205217 102453 205218 104088 205218 102454 205218 102455 205219 102456 205219 102443 205219 102443 205220 102456 205220 102788 205220 102788 205221 102456 205221 102457 205221 102457 205222 102456 205222 98275 205222 102457 205223 98275 205223 102458 205223 102458 205224 98275 205224 102459 205224 102459 205225 98275 205225 98274 205225 102459 205226 98274 205226 102460 205226 102460 205227 98274 205227 98276 205227 102460 205228 98276 205228 102790 205228 104217 205229 104090 205229 102478 205229 102478 205230 104090 205230 102449 205230 102461 205231 102496 205231 98276 205231 98276 205232 102496 205232 102790 205232 102462 205233 104099 205233 104098 205233 104099 205234 102462 205234 104101 205234 104101 205235 102462 205235 102463 205235 104101 205236 102463 205236 104102 205236 102465 205237 104095 205237 102464 205237 102464 205238 98956 205238 102465 205238 102465 205239 98956 205239 102466 205239 102465 205240 102466 205240 104096 205240 104096 205241 102466 205241 98957 205241 104096 205242 98957 205242 104097 205242 104097 205243 98957 205243 98958 205243 104097 205244 98958 205244 102467 205244 102467 205245 98958 205245 102469 205245 102467 205246 102469 205246 102468 205246 102468 205247 102469 205247 102470 205247 102468 205248 102470 205248 104098 205248 104098 205249 102470 205249 102471 205249 104098 205250 102471 205250 102462 205250 104095 205251 102472 205251 102464 205251 102464 205252 102472 205252 102473 205252 102464 205253 102473 205253 102474 205253 102474 205254 102473 205254 104093 205254 102474 205255 104093 205255 102475 205255 102475 205256 104093 205256 102476 205256 102475 205257 102476 205257 102938 205257 102938 205258 102476 205258 104092 205258 102938 205259 104092 205259 102477 205259 102477 205260 104092 205260 104217 205260 102477 205261 104217 205261 102478 205261 98362 205262 103091 205262 103093 205262 98362 205263 103093 205263 102479 205263 102479 205264 103093 205264 102480 205264 102479 205265 102480 205265 98280 205265 98280 205266 102480 205266 102482 205266 98280 205267 102482 205267 102481 205267 102481 205268 102482 205268 103095 205268 102481 205269 103095 205269 102483 205269 102483 205270 103095 205270 102484 205270 102484 205271 103095 205271 102485 205271 102484 205272 102485 205272 98270 205272 98270 205273 102485 205273 98271 205273 98271 205274 102485 205274 103097 205274 98271 205275 103097 205275 102486 205275 102486 205276 103097 205276 103098 205276 102486 205277 103098 205277 102487 205277 102487 205278 103098 205278 102489 205278 102487 205279 102489 205279 102488 205279 102488 205280 102489 205280 103099 205280 102488 205281 103099 205281 102491 205281 103099 205282 102490 205282 102491 205282 102491 205283 102490 205283 103101 205283 102491 205284 103101 205284 98273 205284 98273 205285 103101 205285 102492 205285 98273 205286 102492 205286 98367 205286 102492 205287 102493 205287 98367 205287 98367 205288 102493 205288 102494 205288 98367 205289 102494 205289 102495 205289 102495 205290 102494 205290 102496 205290 102495 205291 102496 205291 102461 205291 104102 205292 102463 205292 102501 205292 102501 205293 102463 205293 102708 205293 98362 205294 98365 205294 103091 205294 103091 205295 98365 205295 102503 205295 104081 205296 102497 205296 102498 205296 102498 205297 102497 205297 102499 205297 102499 205298 102497 205298 102500 205298 102500 205299 102497 205299 104105 205299 102500 205300 104105 205300 102703 205300 102703 205301 104105 205301 102706 205301 102706 205302 104105 205302 104104 205302 102706 205303 104104 205303 102707 205303 102707 205304 104104 205304 102501 205304 102707 205305 102501 205305 102708 205305 102795 205306 102794 205306 98278 205306 98278 205307 102794 205307 102791 205307 98278 205308 102791 205308 98366 205308 98366 205309 102791 205309 102502 205309 98366 205310 102502 205310 98279 205310 98279 205311 102502 205311 102503 205311 98279 205312 102503 205312 98365 205312 102795 205313 98278 205313 102796 205313 102796 205314 98278 205314 102504 205314 102796 205315 102504 205315 104233 205315 102514 205316 102797 205316 98287 205316 98287 205317 102797 205317 102505 205317 98287 205318 102505 205318 98361 205318 98361 205319 102505 205319 102506 205319 98361 205320 102506 205320 98363 205320 98363 205321 102506 205321 104239 205321 98363 205322 104239 205322 102507 205322 104239 205323 104238 205323 102507 205323 102507 205324 104238 205324 104233 205324 102507 205325 104233 205325 102504 205325 102699 205326 102698 205326 102508 205326 102508 205327 102698 205327 102696 205327 102508 205328 102696 205328 98328 205328 98328 205329 102696 205329 102697 205329 98328 205330 102697 205330 102509 205330 102509 205331 102697 205331 102510 205331 102509 205332 102510 205332 102511 205332 102699 205333 102508 205333 102700 205333 102700 205334 102508 205334 102512 205334 102700 205335 102512 205335 102513 205335 102514 205336 102515 205336 102797 205336 102797 205337 102515 205337 102798 205337 102798 205338 102515 205338 102799 205338 102799 205339 102515 205339 102516 205339 102799 205340 102516 205340 102517 205340 102517 205341 102516 205341 102518 205341 102518 205342 102516 205342 102519 205342 102518 205343 102519 205343 102801 205343 102801 205344 102519 205344 102523 205344 102801 205345 102523 205345 102520 205345 102543 205346 102511 205346 102521 205346 102521 205347 102511 205347 102510 205347 98285 205348 102522 205348 102523 205348 102523 205349 102522 205349 102520 205349 98960 205350 102524 205350 102532 205350 102524 205351 98960 205351 98346 205351 98346 205352 98960 205352 102917 205352 98346 205353 102917 205353 102560 205353 102536 205354 102923 205354 102534 205354 102534 205355 102923 205355 102525 205355 102923 205356 102526 205356 102525 205356 102525 205357 102526 205357 102527 205357 102525 205358 102527 205358 102528 205358 102528 205359 102527 205359 102529 205359 102528 205360 102529 205360 102530 205360 102530 205361 102529 205361 98959 205361 102530 205362 98959 205362 98332 205362 98332 205363 98959 205363 102531 205363 98332 205364 102531 205364 102532 205364 102532 205365 102531 205365 102533 205365 102532 205366 102533 205366 98960 205366 102534 205367 102535 205367 102536 205367 102536 205368 102535 205368 102537 205368 102536 205369 102537 205369 102925 205369 102925 205370 102537 205370 102538 205370 102925 205371 102538 205371 102926 205371 102538 205372 102539 205372 102926 205372 102926 205373 102539 205373 98331 205373 102926 205374 98331 205374 102922 205374 102922 205375 98331 205375 102540 205375 102922 205376 102540 205376 102541 205376 102541 205377 102540 205377 98330 205377 102541 205378 98330 205378 102542 205378 102542 205379 98330 205379 102543 205379 102542 205380 102543 205380 102521 205380 102544 205381 102877 205381 102546 205381 102544 205382 102546 205382 102545 205382 102545 205383 102546 205383 102547 205383 102545 205384 102547 205384 102548 205384 102548 205385 102547 205385 102549 205385 102548 205386 102549 205386 98293 205386 98293 205387 102549 205387 102550 205387 98293 205388 102550 205388 98294 205388 98294 205389 102550 205389 102880 205389 98294 205390 102880 205390 98295 205390 98295 205391 102880 205391 102551 205391 102551 205392 102880 205392 102553 205392 102551 205393 102553 205393 102552 205393 102552 205394 102553 205394 102881 205394 102552 205395 102881 205395 102554 205395 102554 205396 102881 205396 102883 205396 102554 205397 102883 205397 98283 205397 98283 205398 102883 205398 102555 205398 98283 205399 102555 205399 102556 205399 102555 205400 102884 205400 102556 205400 102556 205401 102884 205401 102885 205401 102556 205402 102885 205402 98282 205402 98282 205403 102885 205403 102557 205403 98282 205404 102557 205404 102558 205404 102557 205405 102886 205405 102558 205405 102558 205406 102886 205406 102887 205406 102558 205407 102887 205407 102559 205407 102559 205408 102887 205408 102522 205408 102559 205409 102522 205409 98285 205409 102560 205410 102917 205410 102564 205410 102564 205411 102917 205411 102918 205411 102544 205412 98291 205412 102877 205412 102877 205413 98291 205413 102806 205413 98335 205414 102561 205414 104248 205414 104248 205415 102561 205415 99059 205415 99059 205416 102561 205416 99057 205416 99057 205417 102561 205417 98336 205417 99057 205418 98336 205418 102562 205418 102562 205419 98336 205419 102563 205419 102562 205420 102563 205420 99054 205420 99054 205421 102563 205421 102564 205421 99054 205422 102564 205422 102918 205422 102565 205423 102567 205423 102566 205423 102566 205424 102567 205424 102804 205424 102566 205425 102804 205425 98292 205425 98292 205426 102804 205426 102569 205426 98292 205427 102569 205427 102568 205427 102568 205428 102569 205428 102806 205428 102568 205429 102806 205429 98291 205429 102565 205430 102566 205430 102809 205430 102809 205431 102566 205431 102576 205431 102809 205432 102576 205432 102810 205432 98335 205433 104248 205433 98334 205433 98334 205434 104248 205434 104249 205434 98334 205435 104249 205435 98350 205435 98350 205436 104249 205436 104250 205436 98350 205437 104250 205437 98351 205437 98351 205438 104250 205438 104251 205438 98351 205439 104251 205439 98352 205439 98352 205440 104251 205440 104247 205440 98352 205441 104247 205441 102570 205441 102570 205442 104247 205442 104245 205442 102570 205443 104245 205443 102571 205443 102571 205444 104245 205444 102695 205444 102572 205445 102573 205445 98358 205445 98358 205446 102573 205446 102574 205446 98358 205447 102574 205447 102577 205447 102577 205448 102574 205448 104241 205448 102577 205449 104241 205449 102575 205449 102810 205450 102576 205450 104229 205450 104229 205451 102576 205451 98290 205451 104229 205452 98290 205452 102575 205452 102575 205453 98290 205453 98359 205453 102575 205454 98359 205454 102577 205454 102693 205455 102578 205455 102583 205455 102583 205456 102578 205456 102579 205456 102583 205457 102579 205457 102580 205457 102580 205458 102579 205458 102690 205458 102580 205459 102690 205459 102582 205459 102582 205460 102690 205460 102581 205460 102582 205461 102581 205461 98319 205461 102693 205462 102583 205462 102584 205462 102584 205463 102583 205463 102571 205463 102584 205464 102571 205464 102695 205464 102572 205465 98298 205465 102573 205465 102573 205466 98298 205466 102585 205466 102585 205467 98298 205467 102586 205467 102586 205468 98298 205468 98297 205468 102586 205469 98297 205469 103108 205469 103108 205470 98297 205470 102587 205470 102587 205471 98297 205471 102589 205471 102587 205472 102589 205472 102588 205472 102588 205473 102589 205473 102591 205473 102591 205474 102589 205474 102590 205474 102591 205475 102590 205475 103122 205475 98320 205476 98319 205476 102592 205476 102592 205477 98319 205477 102581 205477 102593 205478 102594 205478 102590 205478 102590 205479 102594 205479 103122 205479 102595 205480 102631 205480 98313 205480 102595 205481 98313 205481 102596 205481 102596 205482 98313 205482 98311 205482 102596 205483 98311 205483 98962 205483 98962 205484 98311 205484 102597 205484 98962 205485 102597 205485 102599 205485 102597 205486 102598 205486 102599 205486 102599 205487 102598 205487 98322 205487 102599 205488 98322 205488 102910 205488 102910 205489 98322 205489 102601 205489 102910 205490 102601 205490 102600 205490 102600 205491 102601 205491 102602 205491 102600 205492 102602 205492 102603 205492 102603 205493 102602 205493 98327 205493 102603 205494 98327 205494 102905 205494 102905 205495 98327 205495 102605 205495 102905 205496 102605 205496 102604 205496 102604 205497 102605 205497 102606 205497 102604 205498 102606 205498 102906 205498 102906 205499 102606 205499 102607 205499 102906 205500 102607 205500 102608 205500 102608 205501 102607 205501 102610 205501 102608 205502 102610 205502 102609 205502 102609 205503 102610 205503 102611 205503 102609 205504 102611 205504 102904 205504 102904 205505 102611 205505 102612 205505 102904 205506 102612 205506 102903 205506 102903 205507 102612 205507 98321 205507 102903 205508 98321 205508 102901 205508 102901 205509 98321 205509 98320 205509 102901 205510 98320 205510 102592 205510 103124 205511 102614 205511 102613 205511 102613 205512 102614 205512 102615 205512 102613 205513 102615 205513 102616 205513 103124 205514 103127 205514 102614 205514 102614 205515 103127 205515 103126 205515 102614 205516 103126 205516 102617 205516 102617 205517 103126 205517 102618 205517 102617 205518 102618 205518 102620 205518 102620 205519 102618 205519 102619 205519 102620 205520 102619 205520 98304 205520 98304 205521 102619 205521 103132 205521 98304 205522 103132 205522 98305 205522 98305 205523 103132 205523 102621 205523 98305 205524 102621 205524 102622 205524 102622 205525 102621 205525 103131 205525 102622 205526 103131 205526 102623 205526 102623 205527 103131 205527 103129 205527 102623 205528 103129 205528 102624 205528 102624 205529 103129 205529 103128 205529 102624 205530 103128 205530 102625 205530 102625 205531 103128 205531 102627 205531 102625 205532 102627 205532 102626 205532 102626 205533 102627 205533 103134 205533 102626 205534 103134 205534 102628 205534 102628 205535 103134 205535 98307 205535 103134 205536 103133 205536 98307 205536 98307 205537 103133 205537 102629 205537 98307 205538 102629 205538 98309 205538 98309 205539 102629 205539 103139 205539 98309 205540 103139 205540 98356 205540 102594 205541 102593 205541 98927 205541 98927 205542 102593 205542 102630 205542 98927 205543 102630 205543 103137 205543 103137 205544 102630 205544 98356 205544 103137 205545 98356 205545 103138 205545 103138 205546 98356 205546 103139 205546 102631 205547 102595 205547 98314 205547 98314 205548 102595 205548 102632 205548 102615 205549 98299 205549 102616 205549 102616 205550 98299 205550 102639 205550 102633 205551 102634 205551 102686 205551 102686 205552 102634 205552 102683 205552 102683 205553 102634 205553 102684 205553 102684 205554 102634 205554 98310 205554 102684 205555 98310 205555 102685 205555 102685 205556 98310 205556 98316 205556 102685 205557 98316 205557 99061 205557 99061 205558 98316 205558 102635 205558 102635 205559 98316 205559 98314 205559 102635 205560 98314 205560 102632 205560 102636 205561 102637 205561 98300 205561 98300 205562 102637 205562 103109 205562 98300 205563 103109 205563 98302 205563 98302 205564 103109 205564 102638 205564 98302 205565 102638 205565 98303 205565 98303 205566 102638 205566 102639 205566 98303 205567 102639 205567 98299 205567 102636 205568 98300 205568 103114 205568 103114 205569 98300 205569 102640 205569 103114 205570 102640 205570 104244 205570 102633 205571 102686 205571 104226 205571 104244 205572 102640 205572 102642 205572 102642 205573 102640 205573 102641 205573 102642 205574 102641 205574 104243 205574 104243 205575 102641 205575 102643 205575 104243 205576 102643 205576 102644 205576 102644 205577 102643 205577 98312 205577 102644 205578 98312 205578 104226 205578 104226 205579 98312 205579 98315 205579 104226 205580 98315 205580 102633 205580 102645 205581 102646 205581 104227 205581 104227 205582 102646 205582 102647 205582 104227 205583 102647 205583 102687 205583 102687 205584 102688 205584 102692 205584 102687 205585 102692 205585 104227 205585 104227 205586 102692 205586 102694 205586 104227 205587 102694 205587 102648 205587 102650 205588 104222 205588 99058 205588 99052 205589 102930 205589 99056 205589 99056 205590 102930 205590 102701 205590 99056 205591 102701 205591 99058 205591 99058 205592 102701 205592 102649 205592 99058 205593 102649 205593 102650 205593 102653 205594 102651 205594 102702 205594 102705 205595 102943 205595 102942 205595 102702 205596 102652 205596 102653 205596 102653 205597 102652 205597 102705 205597 102653 205598 102705 205598 102710 205598 102710 205599 102705 205599 102942 205599 102657 205600 104270 205600 102654 205600 102654 205601 102655 205601 102657 205601 102657 205602 102655 205602 102965 205602 102657 205603 102965 205603 102656 205603 102656 205604 99050 205604 102657 205604 102657 205605 99050 205605 102658 205605 102657 205606 102658 205606 99051 205606 102660 205607 104268 205607 102729 205607 102729 205608 102727 205608 102660 205608 102660 205609 102727 205609 102987 205609 102660 205610 102987 205610 102659 205610 102659 205611 99041 205611 102660 205611 102660 205612 99041 205612 99042 205612 102660 205613 99042 205613 102661 205613 102666 205614 102662 205614 102732 205614 102732 205615 102663 205615 102666 205615 102666 205616 102663 205616 103016 205616 102666 205617 103016 205617 103002 205617 103002 205618 102664 205618 102666 205618 102666 205619 102664 205619 102665 205619 102666 205620 102665 205620 102743 205620 104258 205621 102667 205621 104260 205621 104260 205622 102667 205622 102745 205622 104260 205623 102745 205623 102668 205623 102668 205624 103028 205624 102751 205624 102668 205625 102751 205625 104260 205625 104260 205626 102751 205626 102669 205626 104260 205627 102669 205627 104261 205627 102757 205628 102765 205628 102759 205628 102759 205629 102765 205629 102768 205629 102759 205630 102768 205630 102753 205630 102753 205631 102768 205631 104254 205631 104254 205632 102768 205632 102670 205632 104254 205633 102670 205633 104252 205633 102775 205634 102783 205634 102671 205634 102671 205635 102783 205635 102672 205635 102671 205636 102672 205636 102769 205636 102769 205637 102672 205637 104234 205637 104234 205638 102672 205638 102673 205638 104234 205639 102673 205639 104218 205639 102675 205640 102785 205640 102786 205640 102786 205641 102674 205641 102675 205641 102675 205642 102674 205642 104038 205642 102675 205643 104038 205643 102793 205643 102793 205644 102676 205644 102675 205644 102675 205645 102676 205645 102677 205645 102675 205646 102677 205646 104232 205646 102680 205647 104231 205647 102800 205647 102800 205648 102678 205648 102680 205648 102680 205649 102678 205649 102679 205649 102680 205650 102679 205650 102807 205650 102807 205651 102808 205651 102680 205651 102680 205652 102808 205652 102681 205652 102680 205653 102681 205653 102811 205653 102687 205654 102683 205654 102682 205654 102682 205655 102683 205655 102684 205655 102682 205656 102684 205656 102685 205656 102645 205657 102686 205657 102646 205657 102646 205658 102686 205658 102683 205658 102646 205659 102683 205659 102647 205659 102647 205660 102683 205660 102687 205660 102688 205661 102912 205661 102579 205661 102579 205662 102912 205662 102689 205662 102579 205663 102689 205663 102690 205663 102690 205664 102689 205664 102691 205664 102690 205665 102691 205665 102581 205665 102579 205666 102578 205666 102688 205666 102688 205667 102578 205667 102693 205667 102688 205668 102693 205668 102692 205668 102692 205669 102693 205669 102584 205669 102692 205670 102584 205670 102694 205670 102694 205671 102584 205671 102695 205671 102694 205672 102695 205672 102648 205672 99058 205673 104222 205673 99059 205673 99059 205674 104222 205674 104248 205674 102930 205675 102929 205675 102696 205675 102696 205676 102929 205676 102928 205676 102696 205677 102928 205677 102697 205677 102697 205678 102928 205678 102919 205678 102697 205679 102919 205679 102510 205679 102696 205680 102698 205680 102930 205680 102930 205681 102698 205681 102699 205681 102930 205682 102699 205682 102701 205682 102701 205683 102699 205683 102700 205683 102701 205684 102700 205684 102649 205684 102649 205685 102700 205685 102513 205685 102649 205686 102513 205686 102650 205686 102702 205687 102498 205687 102652 205687 102652 205688 102498 205688 102499 205688 102706 205689 102704 205689 102703 205689 102703 205690 102704 205690 102945 205690 102703 205691 102945 205691 102500 205691 102500 205692 102945 205692 102943 205692 102500 205693 102943 205693 102499 205693 102499 205694 102943 205694 102705 205694 102499 205695 102705 205695 102652 205695 102706 205696 102707 205696 102704 205696 102704 205697 102707 205697 102708 205697 102704 205698 102708 205698 102709 205698 102453 205699 102653 205699 102452 205699 102452 205700 102653 205700 102710 205700 102452 205701 102710 205701 102711 205701 102711 205702 102710 205702 102942 205702 102711 205703 102942 205703 102712 205703 102712 205704 102942 205704 102713 205704 102712 205705 102713 205705 102714 205705 102714 205706 102713 205706 102937 205706 102714 205707 102937 205707 102449 205707 104270 205708 102715 205708 102654 205708 102654 205709 102715 205709 102718 205709 102427 205710 102719 205710 102716 205710 102716 205711 102719 205711 102964 205711 102716 205712 102964 205712 102717 205712 102717 205713 102964 205713 102965 205713 102717 205714 102965 205714 102718 205714 102718 205715 102965 205715 102655 205715 102718 205716 102655 205716 102654 205716 102427 205717 102428 205717 102719 205717 102719 205718 102428 205718 102720 205718 102719 205719 102720 205719 102721 205719 102391 205720 102976 205720 102390 205720 102390 205721 102976 205721 102722 205721 102390 205722 102722 205722 102723 205722 102723 205723 102722 205723 102958 205723 102723 205724 102958 205724 102389 205724 104268 205725 104266 205725 102729 205725 102729 205726 104266 205726 102728 205726 102374 205727 102730 205727 102724 205727 102724 205728 102730 205728 102725 205728 102724 205729 102725 205729 102726 205729 102726 205730 102725 205730 102987 205730 102726 205731 102987 205731 102728 205731 102728 205732 102987 205732 102727 205732 102728 205733 102727 205733 102729 205733 102374 205734 102731 205734 102730 205734 102730 205735 102731 205735 102978 205735 102730 205736 102978 205736 102985 205736 99045 205737 102979 205737 102329 205737 102329 205738 102979 205738 102328 205738 102662 205739 102306 205739 102732 205739 102732 205740 102306 205740 102735 205740 102736 205741 102733 205741 102734 205741 102734 205742 102733 205742 103017 205742 102734 205743 103017 205743 102307 205743 102307 205744 103017 205744 103016 205744 102307 205745 103016 205745 102735 205745 102735 205746 103016 205746 102663 205746 102735 205747 102663 205747 102732 205747 102736 205748 102737 205748 102733 205748 102733 205749 102737 205749 102738 205749 102733 205750 102738 205750 102992 205750 103002 205751 103013 205751 102251 205751 102251 205752 103013 205752 103012 205752 102251 205753 103012 205753 102739 205753 102739 205754 103012 205754 103011 205754 102739 205755 103011 205755 102740 205755 102251 205756 102249 205756 103002 205756 103002 205757 102249 205757 102248 205757 103002 205758 102248 205758 102664 205758 102664 205759 102248 205759 102741 205759 102664 205760 102741 205760 102665 205760 102665 205761 102741 205761 102742 205761 102665 205762 102742 205762 102743 205762 104258 205763 102244 205763 102667 205763 102667 205764 102244 205764 102257 205764 102261 205765 103038 205765 102260 205765 102260 205766 103038 205766 102744 205766 102260 205767 102744 205767 102258 205767 102258 205768 102744 205768 102668 205768 102258 205769 102668 205769 102257 205769 102257 205770 102668 205770 102745 205770 102257 205771 102745 205771 102667 205771 102261 205772 102746 205772 103038 205772 103038 205773 102746 205773 102265 205773 103038 205774 102265 205774 103040 205774 103028 205775 103027 205775 102747 205775 102747 205776 103027 205776 102748 205776 102747 205777 102748 205777 102310 205777 102310 205778 102748 205778 103026 205778 102310 205779 103026 205779 102304 205779 102747 205780 102749 205780 103028 205780 103028 205781 102749 205781 102750 205781 103028 205782 102750 205782 102751 205782 102751 205783 102750 205783 102312 205783 102751 205784 102312 205784 102669 205784 102669 205785 102312 205785 102752 205785 102669 205786 102752 205786 104261 205786 104254 205787 102322 205787 102753 205787 102753 205788 102322 205788 102758 205788 102754 205789 102761 205789 102755 205789 102755 205790 102761 205790 103051 205790 102755 205791 103051 205791 102756 205791 102756 205792 103051 205792 102757 205792 102756 205793 102757 205793 102758 205793 102758 205794 102757 205794 102759 205794 102758 205795 102759 205795 102753 205795 102754 205796 102760 205796 102761 205796 102761 205797 102760 205797 102762 205797 102761 205798 102762 205798 102763 205798 102765 205799 103050 205799 102376 205799 102376 205800 103050 205800 102764 205800 102376 205801 102764 205801 102377 205801 102377 205802 102764 205802 103062 205802 102377 205803 103062 205803 102378 205803 102376 205804 102766 205804 102765 205804 102765 205805 102766 205805 102767 205805 102765 205806 102767 205806 102768 205806 102768 205807 102767 205807 102379 205807 102768 205808 102379 205808 102670 205808 102670 205809 102379 205809 104078 205809 102670 205810 104078 205810 104252 205810 104234 205811 102396 205811 102769 205811 102769 205812 102396 205812 102774 205812 102770 205813 102776 205813 102771 205813 102771 205814 102776 205814 102773 205814 102771 205815 102773 205815 102772 205815 102772 205816 102773 205816 102775 205816 102772 205817 102775 205817 102774 205817 102774 205818 102775 205818 102671 205818 102774 205819 102671 205819 102769 205819 102770 205820 102777 205820 102776 205820 102776 205821 102777 205821 102778 205821 102776 205822 102778 205822 103063 205822 102783 205823 102779 205823 102781 205823 102781 205824 102779 205824 102780 205824 102781 205825 102780 205825 102431 205825 102431 205826 102780 205826 103087 205826 102431 205827 103087 205827 102432 205827 102781 205828 102782 205828 102783 205828 102783 205829 102782 205829 102429 205829 102783 205830 102429 205830 102672 205830 102672 205831 102429 205831 102784 205831 102672 205832 102784 205832 102673 205832 102673 205833 102784 205833 104219 205833 102673 205834 104219 205834 104218 205834 102785 205835 102443 205835 102786 205835 102786 205836 102443 205836 102788 205836 102459 205837 102789 205837 102458 205837 102458 205838 102789 205838 102787 205838 102458 205839 102787 205839 102457 205839 102457 205840 102787 205840 104038 205840 102457 205841 104038 205841 102788 205841 102788 205842 104038 205842 102674 205842 102788 205843 102674 205843 102786 205843 102459 205844 102460 205844 102789 205844 102789 205845 102460 205845 102790 205845 102789 205846 102790 205846 104042 205846 102793 205847 104048 205847 102791 205847 102791 205848 104048 205848 102792 205848 102791 205849 102792 205849 102502 205849 102502 205850 102792 205850 103090 205850 102502 205851 103090 205851 102503 205851 102791 205852 102794 205852 102793 205852 102793 205853 102794 205853 102795 205853 102793 205854 102795 205854 102676 205854 102676 205855 102795 205855 102796 205855 102676 205856 102796 205856 102677 205856 102677 205857 102796 205857 104233 205857 102677 205858 104233 205858 104232 205858 104231 205859 102797 205859 102800 205859 102800 205860 102797 205860 102798 205860 102518 205861 102802 205861 102517 205861 102517 205862 102802 205862 102890 205862 102517 205863 102890 205863 102799 205863 102799 205864 102890 205864 102679 205864 102799 205865 102679 205865 102798 205865 102798 205866 102679 205866 102678 205866 102798 205867 102678 205867 102800 205867 102518 205868 102801 205868 102802 205868 102802 205869 102801 205869 102520 205869 102802 205870 102520 205870 102876 205870 102807 205871 102895 205871 102804 205871 102804 205872 102895 205872 102803 205872 102804 205873 102803 205873 102569 205873 102569 205874 102803 205874 102805 205874 102569 205875 102805 205875 102806 205875 102804 205876 102567 205876 102807 205876 102807 205877 102567 205877 102565 205877 102807 205878 102565 205878 102808 205878 102808 205879 102565 205879 102809 205879 102808 205880 102809 205880 102681 205880 102681 205881 102809 205881 102810 205881 102681 205882 102810 205882 102811 205882 99039 205883 102813 205883 102812 205883 102812 205884 102813 205884 102814 205884 102812 205885 102814 205885 101353 205885 101353 205886 102814 205886 102911 205886 101353 205887 102911 205887 102815 205887 102815 205888 102911 205888 102913 205888 102815 205889 102913 205889 102816 205889 102816 205890 102913 205890 102817 205890 102816 205891 102817 205891 102818 205891 102818 205892 102817 205892 102819 205892 102818 205893 102819 205893 101350 205893 101350 205894 102819 205894 99033 205894 101344 205895 99031 205895 102820 205895 102820 205896 99031 205896 102821 205896 102820 205897 102821 205897 101342 205897 101342 205898 102821 205898 102822 205898 101342 205899 102822 205899 101340 205899 101340 205900 102822 205900 102824 205900 101340 205901 102824 205901 102823 205901 102823 205902 102824 205902 102825 205902 102823 205903 102825 205903 101338 205903 101338 205904 102825 205904 102932 205904 101338 205905 102932 205905 99025 205905 99025 205906 102932 205906 102933 205906 101330 205907 102826 205907 101329 205907 101329 205908 102826 205908 102944 205908 101329 205909 102944 205909 102827 205909 102827 205910 102944 205910 102947 205910 102827 205911 102947 205911 101327 205911 101327 205912 102947 205912 102828 205912 101327 205913 102828 205913 101326 205913 101326 205914 102828 205914 102829 205914 101326 205915 102829 205915 101325 205915 101325 205916 102829 205916 102950 205916 101325 205917 102950 205917 102830 205917 102830 205918 102950 205918 102951 205918 99020 205919 102831 205919 101315 205919 101315 205920 102831 205920 102968 205920 101315 205921 102968 205921 102832 205921 102832 205922 102968 205922 102833 205922 102832 205923 102833 205923 101323 205923 101323 205924 102833 205924 102834 205924 101323 205925 102834 205925 102835 205925 102835 205926 102834 205926 102971 205926 102835 205927 102971 205927 102836 205927 102836 205928 102971 205928 102972 205928 102836 205929 102972 205929 99013 205929 99013 205930 102972 205930 99014 205930 99012 205931 102984 205931 102837 205931 102837 205932 102984 205932 102982 205932 102837 205933 102982 205933 102839 205933 102839 205934 102982 205934 102838 205934 102839 205935 102838 205935 102841 205935 102841 205936 102838 205936 102840 205936 102841 205937 102840 205937 101306 205937 101306 205938 102840 205938 102842 205938 101306 205939 102842 205939 101305 205939 101305 205940 102842 205940 102981 205940 101305 205941 102981 205941 101304 205941 101304 205942 102981 205942 102989 205942 102843 205943 103003 205943 101290 205943 101290 205944 103003 205944 103004 205944 101290 205945 103004 205945 101289 205945 101289 205946 103004 205946 103006 205946 101289 205947 103006 205947 101300 205947 101300 205948 103006 205948 103008 205948 101300 205949 103008 205949 101299 205949 101299 205950 103008 205950 102844 205950 101299 205951 102844 205951 102845 205951 102845 205952 102844 205952 102846 205952 102845 205953 102846 205953 101297 205953 101297 205954 102846 205954 99001 205954 101277 205955 99000 205955 101278 205955 101278 205956 99000 205956 102847 205956 101278 205957 102847 205957 102848 205957 102848 205958 102847 205958 103032 205958 102848 205959 103032 205959 102849 205959 102849 205960 103032 205960 103034 205960 102849 205961 103034 205961 101281 205961 101281 205962 103034 205962 102850 205962 101281 205963 102850 205963 102851 205963 102851 205964 102850 205964 103037 205964 102851 205965 103037 205965 98991 205965 98991 205966 103037 205966 98992 205966 101271 205967 102852 205967 102853 205967 102853 205968 102852 205968 103057 205968 102853 205969 103057 205969 102855 205969 102855 205970 103057 205970 102854 205970 102855 205971 102854 205971 102856 205971 102856 205972 102854 205972 103059 205972 102856 205973 103059 205973 102857 205973 102857 205974 103059 205974 102858 205974 102857 205975 102858 205975 102859 205975 102859 205976 102858 205976 103049 205976 102859 205977 103049 205977 101267 205977 101267 205978 103049 205978 98986 205978 98984 205979 102860 205979 102861 205979 102861 205980 102860 205980 102863 205980 102861 205981 102863 205981 102862 205981 102862 205982 102863 205982 103085 205982 102862 205983 103085 205983 101260 205983 101260 205984 103085 205984 103088 205984 101260 205985 103088 205985 101257 205985 101257 205986 103088 205986 102864 205986 101257 205987 102864 205987 102865 205987 102865 205988 102864 205988 103077 205988 102865 205989 103077 205989 101256 205989 101256 205990 103077 205990 103076 205990 101244 205991 102866 205991 101243 205991 101243 205992 102866 205992 102867 205992 101243 205993 102867 205993 101242 205993 101242 205994 102867 205994 104046 205994 101242 205995 104046 205995 101241 205995 101241 205996 104046 205996 104047 205996 101241 205997 104047 205997 102868 205997 102868 205998 104047 205998 102869 205998 102868 205999 102869 205999 101239 205999 101239 206000 102869 206000 104039 206000 101239 206001 104039 206001 102870 206001 102870 206002 104039 206002 102871 206002 102870 206003 102871 206003 98973 206003 98973 206004 102871 206004 104040 206004 98972 206005 102889 206005 101232 206005 101232 206006 102889 206006 102893 206006 101232 206007 102893 206007 101230 206007 101230 206008 102893 206008 102872 206008 101230 206009 102872 206009 102873 206009 102873 206010 102872 206010 102874 206010 102873 206011 102874 206011 101229 206011 101229 206012 102874 206012 102892 206012 101229 206013 102892 206013 102875 206013 102875 206014 102892 206014 102891 206014 102875 206015 102891 206015 101227 206015 101227 206016 102891 206016 102899 206016 102522 206017 102888 206017 102520 206017 102520 206018 102888 206018 102876 206018 102806 206019 102805 206019 102877 206019 102877 206020 102805 206020 102894 206020 102877 206021 102894 206021 102546 206021 102546 206022 102894 206022 102878 206022 102546 206023 102878 206023 102547 206023 102547 206024 102878 206024 102549 206024 102549 206025 102878 206025 102550 206025 102550 206026 102878 206026 102879 206026 102550 206027 102879 206027 102880 206027 102880 206028 102879 206028 102553 206028 102553 206029 102879 206029 102882 206029 102553 206030 102882 206030 102881 206030 102884 206031 102555 206031 102882 206031 102882 206032 102555 206032 102883 206032 102882 206033 102883 206033 102881 206033 102884 206034 102882 206034 102885 206034 102885 206035 102882 206035 102897 206035 102885 206036 102897 206036 102557 206036 102557 206037 102897 206037 102898 206037 102557 206038 102898 206038 102886 206038 102886 206039 102898 206039 102887 206039 102887 206040 102898 206040 102888 206040 102887 206041 102888 206041 102522 206041 102895 206042 102807 206042 102872 206042 102890 206043 102802 206043 102891 206043 102893 206044 102889 206044 102878 206044 102878 206045 102889 206045 102879 206045 102891 206046 102802 206046 102899 206046 102890 206047 102891 206047 102679 206047 102679 206048 102891 206048 102892 206048 102679 206049 102892 206049 102807 206049 102807 206050 102892 206050 102874 206050 102807 206051 102874 206051 102872 206051 102878 206052 102894 206052 102893 206052 102893 206053 102894 206053 102805 206053 102893 206054 102805 206054 102872 206054 102872 206055 102805 206055 102803 206055 102872 206056 102803 206056 102895 206056 102889 206057 98971 206057 102879 206057 102879 206058 98971 206058 102896 206058 102879 206059 102896 206059 102882 206059 102882 206060 102896 206060 98968 206060 102882 206061 98968 206061 102897 206061 102897 206062 98968 206062 102898 206062 98968 206063 98967 206063 102898 206063 102898 206064 98967 206064 98965 206064 102898 206065 98965 206065 102888 206065 102888 206066 98965 206066 102899 206066 102888 206067 102899 206067 102876 206067 102876 206068 102899 206068 102802 206068 102595 206069 102900 206069 102632 206069 102632 206070 102900 206070 99060 206070 102581 206071 102691 206071 102592 206071 102592 206072 102691 206072 102916 206072 102592 206073 102916 206073 102901 206073 102901 206074 102916 206074 102902 206074 102901 206075 102902 206075 102903 206075 102903 206076 102902 206076 102904 206076 102904 206077 102902 206077 102907 206077 102904 206078 102907 206078 102609 206078 102905 206079 102604 206079 102908 206079 102908 206080 102604 206080 102906 206080 102908 206081 102906 206081 102907 206081 102907 206082 102906 206082 102608 206082 102907 206083 102608 206083 102609 206083 102905 206084 102908 206084 102603 206084 102603 206085 102908 206085 102909 206085 102603 206086 102909 206086 102600 206086 102600 206087 102909 206087 102910 206087 102910 206088 102909 206088 102914 206088 102910 206089 102914 206089 102599 206089 102913 206090 102911 206090 102687 206090 102687 206091 102911 206091 102688 206091 99038 206092 102691 206092 102813 206092 102813 206093 102691 206093 102689 206093 102911 206094 102814 206094 102688 206094 102688 206095 102814 206095 102813 206095 102688 206096 102813 206096 102912 206096 102912 206097 102813 206097 102689 206097 102687 206098 102682 206098 102913 206098 102913 206099 102682 206099 99062 206099 102913 206100 99062 206100 102817 206100 99062 206101 99060 206101 102817 206101 102817 206102 99060 206102 102900 206102 102817 206103 102900 206103 102819 206103 102819 206104 102900 206104 98963 206104 102819 206105 98963 206105 99033 206105 99033 206106 98963 206106 102914 206106 99033 206107 102914 206107 102915 206107 102915 206108 102914 206108 102909 206108 102915 206109 102909 206109 99034 206109 99034 206110 102909 206110 102908 206110 99034 206111 102908 206111 99035 206111 99035 206112 102908 206112 102907 206112 99035 206113 102907 206113 99037 206113 99037 206114 102907 206114 102902 206114 99037 206115 102902 206115 99038 206115 99038 206116 102902 206116 102916 206116 99038 206117 102916 206117 102691 206117 102917 206118 102931 206118 102918 206118 102918 206119 102931 206119 99055 206119 102510 206120 102919 206120 102521 206120 102521 206121 102919 206121 102920 206121 102521 206122 102920 206122 102542 206122 102542 206123 102920 206123 102921 206123 102542 206124 102921 206124 102541 206124 102541 206125 102921 206125 102922 206125 102922 206126 102921 206126 102935 206126 102922 206127 102935 206127 102926 206127 102526 206128 102923 206128 102924 206128 102924 206129 102923 206129 102536 206129 102924 206130 102536 206130 102935 206130 102935 206131 102536 206131 102925 206131 102935 206132 102925 206132 102926 206132 102526 206133 102924 206133 102527 206133 102527 206134 102924 206134 102927 206134 102527 206135 102927 206135 102529 206135 99030 206136 102936 206136 102919 206136 102824 206137 102822 206137 99053 206137 102919 206138 102928 206138 99030 206138 99030 206139 102928 206139 102929 206139 99030 206140 102929 206140 102930 206140 99053 206141 102822 206141 99052 206141 99052 206142 102822 206142 102821 206142 99052 206143 102821 206143 102930 206143 102930 206144 102821 206144 99031 206144 102930 206145 99031 206145 99030 206145 99053 206146 99055 206146 102824 206146 102824 206147 99055 206147 102931 206147 102824 206148 102931 206148 102825 206148 102825 206149 102931 206149 98961 206149 102825 206150 98961 206150 102932 206150 102932 206151 98961 206151 102934 206151 102932 206152 102934 206152 102933 206152 102933 206153 102934 206153 102927 206153 102933 206154 102927 206154 99026 206154 99026 206155 102927 206155 102924 206155 99026 206156 102924 206156 99027 206156 99027 206157 102924 206157 102935 206157 99027 206158 102935 206158 99028 206158 99028 206159 102935 206159 102921 206159 99028 206160 102921 206160 102936 206160 102936 206161 102921 206161 102920 206161 102936 206162 102920 206162 102919 206162 102463 206163 102946 206163 102708 206163 102708 206164 102946 206164 102709 206164 102449 206165 102937 206165 102478 206165 102478 206166 102937 206166 102957 206166 102478 206167 102957 206167 102477 206167 102477 206168 102957 206168 102939 206168 102477 206169 102939 206169 102938 206169 102938 206170 102939 206170 102475 206170 102475 206171 102939 206171 102955 206171 102475 206172 102955 206172 102474 206172 102474 206173 102955 206173 102464 206173 102464 206174 102955 206174 102940 206174 102464 206175 102940 206175 98956 206175 99023 206176 102941 206176 102942 206176 102956 206177 102937 206177 102941 206177 102941 206178 102937 206178 102713 206178 102941 206179 102713 206179 102942 206179 102947 206180 102944 206180 102704 206180 99023 206181 102942 206181 102826 206181 102826 206182 102942 206182 102943 206182 102826 206183 102943 206183 102944 206183 102944 206184 102943 206184 102945 206184 102944 206185 102945 206185 102704 206185 102704 206186 102709 206186 102947 206186 102947 206187 102709 206187 102946 206187 102947 206188 102946 206188 102828 206188 102828 206189 102946 206189 102948 206189 102828 206190 102948 206190 102829 206190 102829 206191 102948 206191 102949 206191 102829 206192 102949 206192 102950 206192 102950 206193 102949 206193 102952 206193 102950 206194 102952 206194 102951 206194 102951 206195 102952 206195 102940 206195 102951 206196 102940 206196 102953 206196 102953 206197 102940 206197 102955 206197 102953 206198 102955 206198 102954 206198 102954 206199 102955 206199 102939 206199 102954 206200 102939 206200 102956 206200 102956 206201 102939 206201 102957 206201 102956 206202 102957 206202 102937 206202 102402 206203 102969 206203 102720 206203 102720 206204 102969 206204 102721 206204 102389 206205 102958 206205 102959 206205 102959 206206 102958 206206 102960 206206 102959 206207 102960 206207 102962 206207 102962 206208 102960 206208 102961 206208 102962 206209 102961 206209 102411 206209 102411 206210 102961 206210 102963 206210 102963 206211 102961 206211 102974 206211 102963 206212 102974 206212 102408 206212 102964 206213 102719 206213 102831 206213 102976 206214 102656 206214 102967 206214 102831 206215 102719 206215 102968 206215 102964 206216 102831 206216 102965 206216 102965 206217 102831 206217 102966 206217 102965 206218 102966 206218 102656 206218 102656 206219 102966 206219 99019 206219 102656 206220 99019 206220 102967 206220 102719 206221 102721 206221 102968 206221 102968 206222 102721 206222 102969 206222 102968 206223 102969 206223 102833 206223 102833 206224 102969 206224 102970 206224 102833 206225 102970 206225 102834 206225 102834 206226 102970 206226 98952 206226 102834 206227 98952 206227 102971 206227 102971 206228 98952 206228 98951 206228 102971 206229 98951 206229 102972 206229 102972 206230 98951 206230 102973 206230 102972 206231 102973 206231 99014 206231 99014 206232 102973 206232 102974 206232 99014 206233 102974 206233 102975 206233 102975 206234 102974 206234 102961 206234 102975 206235 102961 206235 99017 206235 102961 206236 102960 206236 99017 206236 99017 206237 102960 206237 102958 206237 99017 206238 102958 206238 102967 206238 102967 206239 102958 206239 102722 206239 102967 206240 102722 206240 102976 206240 98945 206241 102977 206241 102978 206241 102978 206242 102977 206242 102985 206242 102328 206243 102979 206243 102334 206243 102334 206244 102979 206244 102980 206244 102980 206245 102990 206245 102334 206245 102334 206246 102990 206246 102353 206246 102989 206247 102981 206247 98937 206247 98937 206248 102981 206248 98940 206248 98940 206249 102981 206249 102842 206249 98940 206250 102842 206250 98938 206250 98938 206251 102842 206251 102840 206251 98938 206252 102840 206252 98942 206252 98942 206253 102840 206253 102838 206253 98942 206254 102838 206254 102983 206254 102983 206255 102838 206255 102982 206255 102983 206256 102982 206256 102977 206256 102977 206257 102982 206257 102984 206257 102977 206258 102984 206258 102985 206258 102985 206259 102984 206259 102730 206259 102730 206260 102984 206260 102986 206260 102730 206261 102986 206261 102725 206261 102725 206262 102986 206262 102987 206262 102987 206263 102986 206263 102988 206263 102987 206264 102988 206264 102659 206264 102988 206265 99011 206265 102659 206265 102659 206266 99011 206266 99009 206266 102659 206267 99009 206267 99047 206267 98937 206268 102990 206268 102989 206268 102989 206269 102990 206269 102980 206269 102989 206270 102980 206270 99008 206270 99008 206271 102980 206271 102979 206271 99008 206272 102979 206272 99009 206272 99009 206273 102979 206273 99045 206273 99009 206274 99045 206274 99047 206274 102266 206275 102991 206275 102738 206275 102738 206276 102991 206276 102992 206276 102740 206277 103011 206277 102263 206277 102263 206278 103011 206278 103010 206278 102263 206279 103010 206279 102993 206279 102993 206280 103010 206280 103009 206280 102993 206281 103009 206281 102282 206281 102282 206282 103009 206282 102280 206282 102280 206283 103009 206283 102279 206283 102279 206284 103009 206284 103007 206284 102279 206285 103007 206285 102277 206285 102277 206286 103007 206286 102995 206286 102995 206287 103007 206287 102994 206287 102995 206288 102994 206288 102997 206288 102271 206289 102272 206289 102994 206289 102994 206290 102272 206290 102996 206290 102994 206291 102996 206291 102997 206291 102271 206292 102994 206292 102998 206292 102998 206293 102994 206293 103005 206293 102998 206294 103005 206294 102268 206294 102268 206295 103005 206295 103001 206295 102268 206296 103001 206296 102999 206296 102999 206297 103001 206297 103000 206297 103000 206298 103001 206298 102991 206298 103000 206299 102991 206299 102266 206299 103013 206300 103002 206300 99002 206300 99002 206301 103002 206301 99003 206301 103015 206302 102991 206302 103003 206302 103003 206303 102991 206303 103001 206303 103003 206304 103001 206304 103004 206304 103004 206305 103001 206305 103005 206305 103004 206306 103005 206306 103006 206306 103006 206307 103005 206307 102994 206307 103006 206308 102994 206308 103008 206308 103008 206309 102994 206309 103007 206309 103008 206310 103007 206310 102844 206310 102844 206311 103007 206311 103009 206311 102844 206312 103009 206312 102846 206312 102846 206313 103009 206313 103010 206313 102846 206314 103010 206314 99001 206314 99001 206315 103010 206315 103011 206315 99001 206316 103011 206316 99002 206316 99002 206317 103011 206317 103012 206317 99002 206318 103012 206318 103013 206318 103014 206319 102733 206319 103015 206319 103015 206320 102733 206320 102992 206320 103015 206321 102992 206321 102991 206321 99003 206322 103002 206322 99005 206322 99005 206323 103002 206323 103016 206323 99005 206324 103016 206324 103014 206324 103014 206325 103016 206325 103017 206325 103014 206326 103017 206326 102733 206326 102302 206327 103029 206327 102265 206327 102265 206328 103029 206328 103040 206328 102304 206329 103026 206329 103019 206329 103019 206330 103026 206330 103018 206330 103019 206331 103018 206331 102286 206331 102286 206332 103018 206332 103036 206332 102286 206333 103036 206333 102287 206333 102287 206334 103036 206334 103020 206334 103020 206335 103036 206335 103035 206335 103020 206336 103035 206336 103021 206336 103021 206337 103035 206337 102290 206337 102290 206338 103035 206338 103033 206338 102290 206339 103033 206339 103022 206339 102296 206340 102295 206340 103023 206340 103023 206341 102295 206341 103024 206341 103023 206342 103024 206342 103033 206342 103033 206343 103024 206343 102293 206343 103033 206344 102293 206344 103022 206344 102296 206345 103023 206345 103025 206345 103025 206346 103023 206346 103031 206346 103025 206347 103031 206347 102297 206347 102297 206348 103031 206348 102298 206348 102298 206349 103031 206349 103030 206349 102298 206350 103030 206350 102301 206350 102301 206351 103030 206351 103029 206351 102301 206352 103029 206352 102302 206352 103037 206353 103026 206353 98992 206353 98992 206354 103026 206354 102748 206354 102748 206355 103027 206355 98992 206355 98992 206356 103027 206356 103028 206356 98992 206357 103028 206357 98993 206357 98993 206358 103028 206358 98996 206358 98996 206359 103028 206359 102668 206359 98996 206360 102668 206360 98997 206360 103039 206361 103029 206361 98999 206361 98999 206362 103029 206362 103030 206362 98999 206363 103030 206363 99000 206363 99000 206364 103030 206364 103031 206364 99000 206365 103031 206365 102847 206365 102847 206366 103031 206366 103023 206366 102847 206367 103023 206367 103032 206367 103032 206368 103023 206368 103033 206368 103032 206369 103033 206369 103034 206369 103034 206370 103033 206370 103035 206370 103034 206371 103035 206371 102850 206371 102850 206372 103035 206372 103036 206372 102850 206373 103036 206373 103037 206373 103037 206374 103036 206374 103018 206374 103037 206375 103018 206375 103026 206375 102668 206376 102744 206376 98997 206376 98997 206377 102744 206377 103038 206377 98997 206378 103038 206378 103039 206378 103039 206379 103038 206379 103040 206379 103039 206380 103040 206380 103029 206380 103047 206381 103054 206381 102762 206381 102762 206382 103054 206382 102763 206382 102378 206383 103062 206383 103041 206383 103041 206384 103062 206384 103061 206384 103041 206385 103061 206385 103042 206385 103042 206386 103061 206386 103060 206386 103042 206387 103060 206387 103043 206387 103043 206388 103060 206388 102355 206388 102355 206389 103060 206389 102356 206389 102356 206390 103060 206390 103058 206390 102356 206391 103058 206391 102359 206391 102359 206392 103058 206392 102361 206392 102361 206393 103058 206393 103045 206393 102361 206394 103045 206394 102363 206394 102367 206395 103044 206395 103045 206395 103045 206396 103044 206396 102365 206396 103045 206397 102365 206397 102363 206397 102367 206398 103045 206398 103046 206398 103046 206399 103045 206399 103056 206399 103046 206400 103056 206400 102369 206400 102369 206401 103056 206401 103055 206401 102369 206402 103055 206402 102370 206402 102370 206403 103055 206403 102371 206403 102371 206404 103055 206404 103054 206404 102371 206405 103054 206405 103047 206405 98988 206406 103048 206406 102757 206406 102757 206407 103048 206407 102765 206407 103048 206408 98986 206408 102765 206408 102765 206409 98986 206409 103049 206409 102765 206410 103049 206410 103050 206410 102757 206411 103051 206411 98988 206411 98988 206412 103051 206412 102761 206412 98988 206413 102761 206413 103052 206413 103052 206414 102761 206414 102763 206414 103052 206415 102763 206415 103053 206415 103053 206416 102763 206416 103054 206416 103053 206417 103054 206417 98990 206417 103054 206418 103055 206418 98990 206418 98990 206419 103055 206419 103056 206419 98990 206420 103056 206420 102852 206420 102852 206421 103056 206421 103045 206421 102852 206422 103045 206422 103057 206422 103057 206423 103045 206423 103058 206423 103057 206424 103058 206424 102854 206424 102854 206425 103058 206425 103060 206425 102854 206426 103060 206426 103059 206426 103059 206427 103060 206427 103061 206427 103059 206428 103061 206428 102858 206428 102858 206429 103061 206429 103062 206429 102858 206430 103062 206430 103049 206430 103049 206431 103062 206431 102764 206431 103049 206432 102764 206432 103050 206432 102424 206433 103080 206433 102778 206433 102778 206434 103080 206434 103063 206434 102432 206435 103087 206435 103064 206435 103064 206436 103087 206436 103086 206436 103064 206437 103086 206437 102413 206437 102413 206438 103086 206438 103084 206438 102413 206439 103084 206439 103065 206439 103065 206440 103084 206440 102414 206440 102414 206441 103084 206441 102416 206441 102416 206442 103084 206442 103066 206442 102416 206443 103066 206443 103067 206443 103067 206444 103066 206444 103068 206444 103068 206445 103066 206445 103071 206445 103068 206446 103071 206446 102418 206446 102421 206447 103069 206447 103071 206447 103071 206448 103069 206448 103070 206448 103071 206449 103070 206449 102418 206449 102421 206450 103071 206450 103072 206450 103072 206451 103071 206451 103083 206451 103072 206452 103083 206452 103073 206452 103073 206453 103083 206453 103081 206453 103073 206454 103081 206454 103074 206454 103074 206455 103081 206455 102423 206455 102423 206456 103081 206456 103080 206456 102423 206457 103080 206457 102424 206457 103075 206458 103076 206458 102775 206458 102779 206459 102783 206459 102864 206459 102775 206460 103076 206460 102783 206460 102783 206461 103076 206461 103077 206461 102783 206462 103077 206462 102864 206462 102775 206463 102773 206463 103075 206463 103075 206464 102773 206464 102776 206464 103075 206465 102776 206465 98981 206465 98981 206466 102776 206466 103063 206466 98981 206467 103063 206467 103078 206467 103078 206468 103063 206468 103080 206468 103078 206469 103080 206469 103079 206469 103079 206470 103080 206470 103081 206470 103079 206471 103081 206471 103082 206471 103082 206472 103081 206472 103083 206472 103082 206473 103083 206473 102860 206473 102860 206474 103083 206474 103071 206474 102860 206475 103071 206475 102863 206475 103071 206476 103066 206476 102863 206476 102863 206477 103066 206477 103084 206477 102863 206478 103084 206478 103085 206478 103085 206479 103084 206479 103086 206479 103085 206480 103086 206480 103088 206480 103088 206481 103086 206481 103087 206481 103088 206482 103087 206482 102864 206482 102864 206483 103087 206483 102780 206483 102864 206484 102780 206484 102779 206484 102496 206485 103089 206485 102790 206485 102790 206486 103089 206486 104042 206486 102503 206487 103090 206487 103091 206487 103091 206488 103090 206488 103092 206488 103091 206489 103092 206489 103093 206489 103093 206490 103092 206490 103094 206490 103093 206491 103094 206491 102480 206491 102480 206492 103094 206492 102482 206492 102482 206493 103094 206493 103095 206493 103095 206494 103094 206494 103096 206494 103095 206495 103096 206495 102485 206495 102485 206496 103096 206496 103097 206496 103097 206497 103096 206497 103100 206497 103097 206498 103100 206498 103098 206498 102490 206499 103099 206499 103100 206499 103100 206500 103099 206500 102489 206500 103100 206501 102489 206501 103098 206501 102490 206502 103100 206502 103101 206502 103101 206503 103100 206503 104045 206503 103101 206504 104045 206504 102492 206504 102492 206505 104045 206505 103102 206505 102492 206506 103102 206506 102493 206506 102493 206507 103102 206507 102494 206507 102494 206508 103102 206508 103089 206508 102494 206509 103089 206509 102496 206509 103104 206510 103105 206510 103106 206510 103106 206511 103103 206511 103104 206511 103104 206512 103103 206512 103107 206512 103104 206513 103107 206513 103112 206513 103112 206514 103113 206514 103104 206514 103104 206515 103113 206515 103115 206515 103104 206516 103115 206516 104228 206516 103105 206517 102573 206517 103106 206517 103106 206518 102573 206518 102585 206518 103106 206519 102585 206519 103103 206519 103103 206520 102585 206520 102586 206520 103103 206521 102586 206521 103107 206521 103107 206522 102586 206522 103108 206522 103107 206523 103108 206523 103151 206523 103151 206524 103108 206524 102587 206524 103151 206525 102587 206525 103150 206525 103150 206526 102587 206526 102588 206526 103150 206527 102588 206527 102591 206527 103112 206528 103110 206528 103109 206528 103109 206529 103110 206529 103140 206529 103109 206530 103140 206530 102638 206530 102638 206531 103140 206531 103111 206531 102638 206532 103111 206532 102639 206532 103109 206533 102637 206533 103112 206533 103112 206534 102637 206534 102636 206534 103112 206535 102636 206535 103113 206535 103113 206536 102636 206536 103114 206536 103113 206537 103114 206537 103115 206537 103115 206538 103114 206538 104244 206538 103115 206539 104244 206539 104228 206539 101223 206540 103143 206540 103116 206540 103116 206541 103143 206541 103141 206541 103116 206542 103141 206542 101220 206542 101220 206543 103141 206543 103152 206543 101220 206544 103152 206544 103117 206544 103117 206545 103152 206545 103118 206545 103117 206546 103118 206546 101219 206546 101219 206547 103118 206547 103119 206547 101219 206548 103119 206548 103120 206548 103120 206549 103119 206549 103149 206549 103120 206550 103149 206550 101217 206550 101217 206551 103149 206551 103148 206551 101217 206552 103148 206552 101215 206552 101215 206553 103148 206553 103121 206553 102594 206554 103123 206554 103122 206554 103122 206555 103123 206555 98936 206555 102639 206556 103111 206556 102616 206556 102616 206557 103111 206557 103142 206557 102627 206558 103128 206558 103135 206558 102616 206559 103142 206559 102613 206559 102613 206560 103142 206560 103125 206560 102613 206561 103125 206561 103124 206561 103124 206562 103125 206562 103127 206562 103132 206563 102619 206563 103130 206563 103130 206564 102619 206564 102618 206564 103130 206565 102618 206565 103125 206565 103125 206566 102618 206566 103126 206566 103125 206567 103126 206567 103127 206567 103128 206568 103129 206568 103135 206568 103135 206569 103129 206569 103131 206569 103135 206570 103131 206570 103130 206570 103130 206571 103131 206571 102621 206571 103130 206572 102621 206572 103132 206572 103136 206573 102629 206573 103145 206573 103145 206574 102629 206574 103133 206574 103145 206575 103133 206575 103135 206575 103135 206576 103133 206576 103134 206576 103135 206577 103134 206577 102627 206577 103147 206578 98927 206578 103136 206578 103136 206579 98927 206579 103137 206579 103137 206580 103138 206580 103136 206580 103136 206581 103138 206581 103139 206581 103136 206582 103139 206582 102629 206582 103111 206583 103140 206583 103141 206583 103141 206584 103140 206584 103110 206584 103141 206585 103110 206585 103112 206585 103111 206586 103141 206586 103142 206586 103142 206587 103141 206587 103143 206587 103142 206588 103143 206588 103125 206588 103125 206589 103143 206589 103144 206589 103125 206590 103144 206590 103130 206590 103130 206591 103144 206591 98934 206591 103130 206592 98934 206592 103135 206592 103135 206593 98934 206593 98932 206593 103135 206594 98932 206594 103145 206594 103145 206595 98932 206595 98931 206595 103145 206596 98931 206596 103136 206596 103136 206597 98931 206597 103146 206597 103136 206598 103146 206598 103147 206598 103147 206599 103146 206599 103121 206599 103147 206600 103121 206600 103123 206600 103123 206601 103121 206601 103148 206601 103123 206602 103148 206602 98936 206602 98936 206603 103148 206603 103149 206603 98936 206604 103149 206604 103150 206604 103150 206605 103149 206605 103151 206605 103151 206606 103149 206606 103119 206606 103151 206607 103119 206607 103107 206607 103107 206608 103119 206608 103118 206608 103107 206609 103118 206609 103112 206609 103112 206610 103118 206610 103152 206610 103112 206611 103152 206611 103141 206611 104017 206612 103458 206612 103153 206612 103153 206613 103458 206613 103462 206613 103153 206614 103462 206614 104019 206614 104019 206615 103462 206615 103154 206615 104019 206616 103154 206616 104020 206616 104020 206617 103154 206617 103155 206617 104020 206618 103155 206618 103157 206618 103157 206619 103155 206619 103156 206619 103157 206620 103156 206620 104022 206620 104022 206621 103156 206621 103158 206621 104022 206622 103158 206622 104024 206622 104024 206623 103158 206623 103159 206623 104024 206624 103159 206624 103160 206624 103160 206625 103159 206625 103494 206625 103160 206626 103494 206626 104027 206626 104027 206627 103494 206627 103495 206627 104027 206628 103495 206628 103161 206628 103161 206629 103495 206629 103496 206629 103161 206630 103496 206630 104029 206630 104029 206631 103496 206631 103162 206631 104029 206632 103162 206632 103163 206632 103163 206633 103162 206633 103164 206633 103163 206634 103164 206634 104030 206634 104030 206635 103164 206635 103489 206635 104030 206636 103489 206636 103165 206636 103165 206637 103489 206637 103166 206637 103165 206638 103166 206638 104033 206638 104033 206639 103166 206639 103167 206639 104033 206640 103167 206640 103168 206640 103168 206641 103167 206641 103169 206641 103168 206642 103169 206642 104035 206642 104035 206643 103169 206643 103457 206643 104035 206644 103457 206644 104037 206644 104037 206645 103457 206645 103483 206645 103170 206646 103405 206646 104015 206646 104015 206647 103405 206647 103171 206647 104015 206648 103171 206648 104013 206648 104013 206649 103171 206649 103415 206649 104013 206650 103415 206650 103172 206650 103172 206651 103415 206651 103173 206651 103172 206652 103173 206652 104011 206652 104011 206653 103173 206653 103175 206653 104011 206654 103175 206654 103174 206654 103174 206655 103175 206655 103422 206655 103174 206656 103422 206656 103176 206656 103176 206657 103422 206657 103177 206657 103176 206658 103177 206658 103178 206658 103178 206659 103177 206659 103179 206659 103178 206660 103179 206660 104008 206660 104008 206661 103179 206661 103418 206661 104008 206662 103418 206662 104006 206662 104006 206663 103418 206663 103431 206663 104006 206664 103431 206664 104005 206664 104005 206665 103431 206665 103432 206665 104005 206666 103432 206666 103180 206666 103180 206667 103432 206667 103181 206667 103180 206668 103181 206668 104004 206668 104004 206669 103181 206669 103182 206669 104004 206670 103182 206670 104002 206670 104002 206671 103182 206671 103406 206671 104002 206672 103406 206672 103999 206672 103999 206673 103406 206673 103409 206673 103999 206674 103409 206674 103183 206674 103183 206675 103409 206675 103184 206675 103183 206676 103184 206676 103185 206676 103185 206677 103184 206677 103186 206677 103185 206678 103186 206678 98407 206678 98407 206679 103186 206679 103404 206679 103280 206680 103275 206680 103274 206680 103284 206681 103194 206681 103199 206681 103258 206682 103191 206682 103261 206682 103190 206683 103196 206683 103187 206683 103188 206684 103456 206684 103293 206684 103201 206685 103188 206685 103288 206685 103231 206686 103232 206686 103189 206686 103189 206687 103232 206687 98791 206687 103460 206688 103196 206688 103461 206688 103461 206689 103196 206689 103190 206689 103461 206690 103190 206690 103239 206690 103486 206691 103191 206691 103487 206691 103487 206692 103191 206692 103258 206692 103487 206693 103258 206693 103192 206693 103200 206694 103194 206694 103193 206694 103193 206695 103194 206695 103284 206695 103193 206696 103284 206696 103282 206696 98791 206697 103232 206697 98864 206697 98864 206698 103232 206698 103234 206698 98864 206699 103234 206699 98792 206699 103195 206700 103187 206700 103245 206700 103245 206701 103187 206701 103196 206701 103245 206702 103196 206702 103244 206702 103244 206703 103196 206703 103460 206703 103244 206704 103460 206704 103467 206704 103262 206705 103261 206705 103264 206705 103264 206706 103261 206706 103191 206706 103264 206707 103191 206707 103197 206707 103197 206708 103191 206708 103486 206708 103197 206709 103486 206709 103198 206709 103292 206710 103199 206710 103291 206710 103291 206711 103199 206711 103194 206711 103291 206712 103194 206712 103289 206712 103289 206713 103194 206713 103200 206713 103289 206714 103200 206714 103201 206714 103202 206715 103237 206715 103233 206715 103540 206716 103203 206716 103242 206716 103242 206717 103203 206717 103202 206717 103242 206718 103202 206718 103241 206718 103241 206719 103202 206719 103233 206719 103241 206720 103233 206720 103240 206720 103249 206721 103204 206721 103205 206721 103257 206722 103247 206722 103254 206722 103254 206723 103247 206723 103249 206723 103254 206724 103249 206724 103252 206724 103252 206725 103249 206725 103205 206725 103252 206726 103205 206726 103243 206726 103251 206727 103466 206727 103253 206727 103253 206728 103466 206728 103206 206728 103253 206729 103206 206729 103207 206729 103207 206730 103206 206730 103208 206730 103207 206731 103208 206731 103209 206731 103209 206732 103208 206732 103256 206732 103466 206733 103488 206733 103206 206733 103206 206734 103488 206734 103210 206734 103206 206735 103210 206735 103208 206735 103208 206736 103210 206736 103259 206736 103208 206737 103259 206737 103256 206737 103256 206738 103259 206738 103260 206738 103256 206739 103260 206739 103211 206739 103211 206740 103260 206740 103527 206740 103212 206741 103267 206741 103216 206741 103521 206742 103213 206742 103214 206742 103214 206743 103213 206743 103212 206743 103214 206744 103212 206744 103215 206744 103215 206745 103212 206745 103216 206745 103215 206746 103216 206746 103263 206746 103269 206747 103217 206747 103218 206747 103218 206748 103217 206748 103223 206748 103218 206749 103223 206749 103219 206749 103219 206750 103223 206750 103220 206750 103219 206751 103220 206751 103271 206751 103271 206752 103220 206752 103225 206752 103217 206753 103221 206753 103223 206753 103223 206754 103221 206754 103222 206754 103223 206755 103222 206755 103220 206755 103220 206756 103222 206756 103224 206756 103220 206757 103224 206757 103225 206757 103225 206758 103224 206758 103226 206758 103225 206759 103226 206759 103516 206759 103516 206760 103226 206760 103515 206760 103499 206761 103498 206761 103277 206761 103277 206762 103498 206762 103227 206762 103277 206763 103227 206763 103278 206763 103278 206764 103227 206764 103228 206764 103278 206765 103228 206765 103279 206765 103279 206766 103228 206766 103281 206766 103498 206767 103497 206767 103227 206767 103227 206768 103497 206768 103283 206768 103227 206769 103283 206769 103228 206769 103228 206770 103283 206770 103285 206770 103228 206771 103285 206771 103281 206771 103281 206772 103285 206772 103286 206772 103281 206773 103286 206773 103508 206773 103508 206774 103286 206774 103287 206774 98792 206775 103234 206775 98793 206775 98793 206776 103234 206776 103235 206776 98793 206777 103235 206777 103230 206777 103230 206778 103235 206778 103229 206778 103230 206779 103229 206779 98673 206779 103231 206780 103240 206780 103232 206780 103232 206781 103240 206781 103233 206781 103232 206782 103233 206782 103234 206782 103234 206783 103233 206783 103237 206783 103234 206784 103237 206784 103235 206784 103235 206785 103237 206785 103236 206785 103235 206786 103236 206786 103229 206786 103203 206787 103542 206787 103202 206787 103202 206788 103542 206788 103543 206788 103202 206789 103543 206789 103237 206789 103237 206790 103543 206790 103238 206790 103237 206791 103238 206791 103236 206791 103231 206792 103239 206792 103240 206792 103240 206793 103239 206793 103190 206793 103240 206794 103190 206794 103241 206794 103241 206795 103190 206795 103187 206795 103241 206796 103187 206796 103242 206796 103242 206797 103187 206797 103195 206797 103242 206798 103195 206798 103540 206798 103540 206799 103195 206799 103539 206799 103467 206800 103243 206800 103244 206800 103244 206801 103243 206801 103205 206801 103244 206802 103205 206802 103245 206802 103245 206803 103205 206803 103204 206803 103245 206804 103204 206804 103195 206804 103195 206805 103204 206805 103246 206805 103195 206806 103246 206806 103539 206806 103247 206807 103248 206807 103249 206807 103249 206808 103248 206808 103250 206808 103249 206809 103250 206809 103204 206809 103204 206810 103250 206810 103536 206810 103204 206811 103536 206811 103246 206811 103467 206812 103251 206812 103243 206812 103243 206813 103251 206813 103253 206813 103243 206814 103253 206814 103252 206814 103252 206815 103253 206815 103207 206815 103252 206816 103207 206816 103254 206816 103254 206817 103207 206817 103209 206817 103254 206818 103209 206818 103257 206818 103211 206819 103255 206819 103256 206819 103256 206820 103255 206820 103530 206820 103256 206821 103530 206821 103209 206821 103209 206822 103530 206822 103531 206822 103209 206823 103531 206823 103257 206823 103488 206824 103192 206824 103210 206824 103210 206825 103192 206825 103258 206825 103210 206826 103258 206826 103259 206826 103259 206827 103258 206827 103261 206827 103259 206828 103261 206828 103260 206828 103260 206829 103261 206829 103262 206829 103260 206830 103262 206830 103527 206830 103527 206831 103262 206831 103526 206831 103198 206832 103263 206832 103197 206832 103197 206833 103263 206833 103216 206833 103197 206834 103216 206834 103264 206834 103264 206835 103216 206835 103267 206835 103264 206836 103267 206836 103262 206836 103262 206837 103267 206837 103268 206837 103262 206838 103268 206838 103526 206838 103213 206839 103523 206839 103212 206839 103212 206840 103523 206840 103265 206840 103212 206841 103265 206841 103267 206841 103267 206842 103265 206842 103266 206842 103267 206843 103266 206843 103268 206843 103198 206844 103269 206844 103263 206844 103263 206845 103269 206845 103218 206845 103263 206846 103218 206846 103215 206846 103215 206847 103218 206847 103219 206847 103215 206848 103219 206848 103214 206848 103214 206849 103219 206849 103271 206849 103214 206850 103271 206850 103521 206850 103516 206851 103518 206851 103225 206851 103225 206852 103518 206852 103270 206852 103225 206853 103270 206853 103271 206853 103271 206854 103270 206854 103520 206854 103271 206855 103520 206855 103521 206855 103221 206856 103272 206856 103222 206856 103222 206857 103272 206857 103276 206857 103222 206858 103276 206858 103224 206858 103224 206859 103276 206859 103273 206859 103224 206860 103273 206860 103226 206860 103226 206861 103273 206861 103274 206861 103226 206862 103274 206862 103515 206862 103515 206863 103274 206863 103275 206863 103272 206864 103499 206864 103276 206864 103276 206865 103499 206865 103277 206865 103276 206866 103277 206866 103273 206866 103273 206867 103277 206867 103278 206867 103273 206868 103278 206868 103274 206868 103274 206869 103278 206869 103279 206869 103274 206870 103279 206870 103280 206870 103508 206871 103510 206871 103281 206871 103281 206872 103510 206872 103511 206872 103281 206873 103511 206873 103279 206873 103279 206874 103511 206874 103512 206874 103279 206875 103512 206875 103280 206875 103497 206876 103282 206876 103283 206876 103283 206877 103282 206877 103284 206877 103283 206878 103284 206878 103285 206878 103285 206879 103284 206879 103199 206879 103285 206880 103199 206880 103286 206880 103286 206881 103199 206881 103292 206881 103286 206882 103292 206882 103287 206882 103287 206883 103292 206883 103506 206883 103295 206884 103296 206884 103505 206884 103201 206885 103288 206885 103289 206885 103289 206886 103288 206886 103290 206886 103289 206887 103290 206887 103291 206887 103291 206888 103290 206888 103295 206888 103291 206889 103295 206889 103292 206889 103292 206890 103295 206890 103505 206890 103292 206891 103505 206891 103506 206891 103188 206892 103293 206892 103288 206892 103288 206893 103293 206893 98789 206893 103288 206894 98789 206894 103290 206894 103290 206895 98789 206895 98833 206895 103290 206896 98833 206896 103295 206896 103295 206897 98833 206897 103294 206897 103295 206898 103294 206898 103296 206898 103538 206899 103537 206899 103391 206899 103525 206900 103297 206900 103374 206900 103298 206901 103302 206901 103299 206901 103358 206902 103301 206902 103306 206902 103413 206903 103412 206903 98674 206903 103414 206904 103413 206904 103397 206904 103300 206905 103348 206905 103429 206905 103429 206906 103348 206906 98749 206906 103410 206907 103301 206907 103411 206907 103411 206908 103301 206908 103358 206908 103411 206909 103358 206909 103355 206909 103310 206910 103302 206910 103303 206910 103303 206911 103302 206911 103298 206911 103303 206912 103298 206912 103420 206912 98749 206913 103348 206913 103304 206913 103304 206914 103348 206914 103349 206914 103304 206915 103349 206915 98675 206915 103359 206916 103306 206916 103305 206916 103305 206917 103306 206917 103301 206917 103305 206918 103301 206918 103307 206918 103307 206919 103301 206919 103410 206919 103307 206920 103410 206920 103408 206920 103308 206921 103299 206921 103399 206921 103399 206922 103299 206922 103302 206922 103399 206923 103302 206923 103309 206923 103309 206924 103302 206924 103310 206924 103309 206925 103310 206925 103414 206925 103352 206926 103353 206926 103311 206926 103360 206927 103351 206927 103312 206927 103312 206928 103351 206928 103352 206928 103312 206929 103352 206929 103357 206929 103357 206930 103352 206930 103311 206930 103357 206931 103311 206931 103356 206931 103314 206932 103364 206932 103361 206932 103519 206933 103313 206933 103368 206933 103368 206934 103313 206934 103314 206934 103368 206935 103314 206935 103367 206935 103367 206936 103314 206936 103361 206936 103367 206937 103361 206937 103366 206937 103407 206938 103318 206938 103365 206938 103365 206939 103318 206939 103315 206939 103365 206940 103315 206940 103316 206940 103316 206941 103315 206941 103317 206941 103316 206942 103317 206942 103369 206942 103369 206943 103317 206943 103320 206943 103318 206944 103319 206944 103315 206944 103315 206945 103319 206945 103371 206945 103315 206946 103371 206946 103317 206946 103317 206947 103371 206947 103373 206947 103317 206948 103373 206948 103320 206948 103320 206949 103373 206949 103322 206949 103320 206950 103322 206950 103321 206950 103321 206951 103322 206951 103375 206951 103433 206952 103323 206952 103324 206952 103324 206953 103323 206953 103325 206953 103324 206954 103325 206954 103376 206954 103376 206955 103325 206955 103326 206955 103376 206956 103326 206956 103378 206956 103378 206957 103326 206957 103327 206957 103323 206958 103328 206958 103325 206958 103325 206959 103328 206959 103329 206959 103325 206960 103329 206960 103326 206960 103326 206961 103329 206961 103330 206961 103326 206962 103330 206962 103327 206962 103327 206963 103330 206963 103383 206963 103327 206964 103383 206964 103529 206964 103529 206965 103383 206965 103384 206965 103419 206966 103417 206966 103381 206966 103381 206967 103417 206967 103331 206967 103381 206968 103331 206968 103382 206968 103382 206969 103331 206969 103332 206969 103382 206970 103332 206970 103385 206970 103385 206971 103332 206971 103335 206971 103417 206972 103333 206972 103331 206972 103331 206973 103333 206973 103334 206973 103331 206974 103334 206974 103332 206974 103332 206975 103334 206975 103336 206975 103332 206976 103336 206976 103335 206976 103335 206977 103336 206977 103387 206977 103335 206978 103387 206978 103535 206978 103535 206979 103387 206979 103388 206979 103389 206980 103446 206980 103337 206980 103337 206981 103446 206981 103340 206981 103337 206982 103340 206982 103338 206982 103338 206983 103340 206983 103339 206983 103338 206984 103339 206984 103393 206984 103393 206985 103339 206985 103342 206985 103446 206986 103421 206986 103340 206986 103340 206987 103421 206987 103395 206987 103340 206988 103395 206988 103339 206988 103339 206989 103395 206989 103341 206989 103339 206990 103341 206990 103342 206990 103342 206991 103341 206991 103396 206991 103342 206992 103396 206992 103343 206992 103343 206993 103396 206993 103344 206993 98675 206994 103349 206994 103345 206994 103345 206995 103349 206995 103350 206995 103345 206996 103350 206996 103346 206996 103346 206997 103350 206997 103347 206997 103346 206998 103347 206998 103503 206998 103300 206999 103356 206999 103348 206999 103348 207000 103356 207000 103311 207000 103348 207001 103311 207001 103349 207001 103349 207002 103311 207002 103353 207002 103349 207003 103353 207003 103350 207003 103350 207004 103353 207004 103504 207004 103350 207005 103504 207005 103347 207005 103351 207006 103509 207006 103352 207006 103352 207007 103509 207007 103507 207007 103352 207008 103507 207008 103353 207008 103353 207009 103507 207009 103354 207009 103353 207010 103354 207010 103504 207010 103300 207011 103355 207011 103356 207011 103356 207012 103355 207012 103358 207012 103356 207013 103358 207013 103357 207013 103357 207014 103358 207014 103306 207014 103357 207015 103306 207015 103312 207015 103312 207016 103306 207016 103359 207016 103312 207017 103359 207017 103360 207017 103360 207018 103359 207018 103513 207018 103408 207019 103366 207019 103307 207019 103307 207020 103366 207020 103361 207020 103307 207021 103361 207021 103305 207021 103305 207022 103361 207022 103364 207022 103305 207023 103364 207023 103359 207023 103359 207024 103364 207024 103362 207024 103359 207025 103362 207025 103513 207025 103313 207026 103363 207026 103314 207026 103314 207027 103363 207027 103517 207027 103314 207028 103517 207028 103364 207028 103364 207029 103517 207029 103514 207029 103364 207030 103514 207030 103362 207030 103408 207031 103407 207031 103366 207031 103366 207032 103407 207032 103365 207032 103366 207033 103365 207033 103367 207033 103367 207034 103365 207034 103316 207034 103367 207035 103316 207035 103368 207035 103368 207036 103316 207036 103369 207036 103368 207037 103369 207037 103519 207037 103321 207038 103524 207038 103320 207038 103320 207039 103524 207039 103522 207039 103320 207040 103522 207040 103369 207040 103369 207041 103522 207041 103370 207041 103369 207042 103370 207042 103519 207042 103319 207043 103434 207043 103371 207043 103371 207044 103434 207044 103372 207044 103371 207045 103372 207045 103373 207045 103373 207046 103372 207046 103377 207046 103373 207047 103377 207047 103322 207047 103322 207048 103377 207048 103374 207048 103322 207049 103374 207049 103375 207049 103375 207050 103374 207050 103297 207050 103434 207051 103433 207051 103372 207051 103372 207052 103433 207052 103324 207052 103372 207053 103324 207053 103377 207053 103377 207054 103324 207054 103376 207054 103377 207055 103376 207055 103374 207055 103374 207056 103376 207056 103378 207056 103374 207057 103378 207057 103525 207057 103529 207058 103528 207058 103327 207058 103327 207059 103528 207059 103379 207059 103327 207060 103379 207060 103378 207060 103378 207061 103379 207061 103380 207061 103378 207062 103380 207062 103525 207062 103328 207063 103419 207063 103329 207063 103329 207064 103419 207064 103381 207064 103329 207065 103381 207065 103330 207065 103330 207066 103381 207066 103382 207066 103330 207067 103382 207067 103383 207067 103383 207068 103382 207068 103385 207068 103383 207069 103385 207069 103384 207069 103535 207070 103534 207070 103335 207070 103335 207071 103534 207071 103533 207071 103335 207072 103533 207072 103385 207072 103385 207073 103533 207073 103532 207073 103385 207074 103532 207074 103384 207074 103333 207075 103447 207075 103334 207075 103334 207076 103447 207076 103390 207076 103334 207077 103390 207077 103336 207077 103336 207078 103390 207078 103386 207078 103336 207079 103386 207079 103387 207079 103387 207080 103386 207080 103391 207080 103387 207081 103391 207081 103388 207081 103388 207082 103391 207082 103537 207082 103447 207083 103389 207083 103390 207083 103390 207084 103389 207084 103337 207084 103390 207085 103337 207085 103386 207085 103386 207086 103337 207086 103338 207086 103386 207087 103338 207087 103391 207087 103391 207088 103338 207088 103393 207088 103391 207089 103393 207089 103538 207089 103343 207090 103392 207090 103342 207090 103342 207091 103392 207091 103541 207091 103342 207092 103541 207092 103393 207092 103393 207093 103541 207093 103394 207093 103393 207094 103394 207094 103538 207094 103421 207095 103420 207095 103395 207095 103395 207096 103420 207096 103298 207096 103395 207097 103298 207097 103341 207097 103341 207098 103298 207098 103299 207098 103341 207099 103299 207099 103396 207099 103396 207100 103299 207100 103308 207100 103396 207101 103308 207101 103344 207101 103344 207102 103308 207102 103400 207102 103402 207103 103403 207103 103544 207103 103414 207104 103397 207104 103309 207104 103309 207105 103397 207105 103398 207105 103309 207106 103398 207106 103399 207106 103399 207107 103398 207107 103402 207107 103399 207108 103402 207108 103308 207108 103308 207109 103402 207109 103544 207109 103308 207110 103544 207110 103400 207110 103413 207111 98674 207111 103397 207111 103397 207112 98674 207112 103401 207112 103397 207113 103401 207113 103398 207113 103398 207114 103401 207114 98709 207114 103398 207115 98709 207115 103402 207115 103402 207116 98709 207116 98672 207116 103402 207117 98672 207117 103403 207117 103404 207118 103186 207118 103300 207118 103171 207119 103405 207119 103412 207119 103412 207120 103405 207120 98787 207120 98787 207121 103405 207121 98915 207121 98787 207122 98915 207122 98786 207122 103182 207123 103318 207123 103406 207123 103406 207124 103318 207124 103407 207124 103406 207125 103407 207125 103409 207125 103407 207126 103408 207126 103409 207126 103409 207127 103408 207127 103410 207127 103409 207128 103410 207128 103184 207128 103184 207129 103410 207129 103411 207129 103184 207130 103411 207130 103186 207130 103186 207131 103411 207131 103355 207131 103186 207132 103355 207132 103300 207132 103412 207133 103413 207133 103171 207133 103171 207134 103413 207134 103414 207134 103171 207135 103414 207135 103415 207135 103415 207136 103414 207136 103310 207136 103415 207137 103310 207137 103173 207137 98786 207138 98915 207138 98785 207138 98785 207139 98915 207139 98914 207139 98785 207140 98914 207140 103437 207140 103426 207141 103416 207141 103425 207141 103425 207142 103416 207142 98765 207142 103179 207143 103417 207143 103418 207143 103418 207144 103417 207144 103419 207144 103418 207145 103419 207145 103431 207145 103310 207146 103303 207146 103173 207146 103173 207147 103303 207147 103420 207147 103173 207148 103420 207148 103175 207148 103175 207149 103420 207149 103421 207149 103175 207150 103421 207150 103422 207150 98911 207151 98910 207151 103455 207151 103449 207152 98907 207152 98773 207152 103423 207153 103424 207153 98907 207153 98907 207154 103424 207154 98772 207154 98907 207155 98772 207155 98773 207155 103425 207156 103427 207156 103426 207156 103426 207157 103427 207157 103428 207157 103426 207158 103428 207158 103423 207158 103423 207159 103428 207159 98769 207159 103423 207160 98769 207160 103424 207160 103439 207161 103452 207161 103438 207161 103443 207162 103430 207162 98752 207162 103300 207163 103429 207163 103404 207163 103404 207164 103429 207164 98750 207164 103404 207165 98750 207165 103430 207165 103430 207166 98750 207166 98751 207166 103430 207167 98751 207167 98752 207167 103419 207168 103328 207168 103431 207168 103431 207169 103328 207169 103323 207169 103431 207170 103323 207170 103432 207170 103432 207171 103323 207171 103433 207171 103432 207172 103433 207172 103181 207172 103181 207173 103433 207173 103434 207173 103181 207174 103434 207174 103182 207174 103182 207175 103434 207175 103319 207175 103182 207176 103319 207176 103318 207176 103455 207177 103435 207177 98911 207177 98911 207178 103435 207178 98782 207178 98911 207179 98782 207179 98914 207179 98914 207180 98782 207180 103436 207180 98914 207181 103436 207181 103437 207181 103438 207182 98762 207182 103439 207182 103439 207183 98762 207183 103440 207183 103439 207184 103440 207184 103416 207184 103416 207185 103440 207185 103441 207185 103416 207186 103441 207186 98765 207186 103451 207187 98901 207187 103442 207187 98752 207188 98753 207188 103443 207188 103443 207189 98753 207189 103444 207189 103443 207190 103444 207190 98901 207190 98901 207191 103444 207191 103445 207191 98901 207192 103445 207192 103442 207192 103421 207193 103446 207193 103422 207193 103422 207194 103446 207194 103389 207194 103422 207195 103389 207195 103177 207195 103177 207196 103389 207196 103447 207196 103177 207197 103447 207197 103179 207197 103179 207198 103447 207198 103333 207198 103179 207199 103333 207199 103417 207199 98773 207200 103448 207200 103449 207200 103449 207201 103448 207201 98775 207201 103449 207202 98775 207202 103453 207202 103442 207203 98758 207203 103451 207203 103451 207204 98758 207204 103450 207204 103451 207205 103450 207205 103452 207205 103452 207206 103450 207206 98760 207206 103452 207207 98760 207207 103438 207207 98775 207208 98776 207208 103453 207208 103453 207209 98776 207209 98780 207209 103453 207210 98780 207210 98910 207210 98910 207211 98780 207211 103454 207211 98910 207212 103454 207212 103455 207212 103462 207213 103458 207213 103456 207213 103483 207214 103457 207214 103231 207214 103456 207215 103458 207215 98899 207215 98899 207216 103458 207216 103469 207216 98899 207217 103469 207217 103468 207217 103459 207218 103481 207218 98875 207218 103167 207219 103460 207219 103169 207219 103169 207220 103460 207220 103461 207220 103169 207221 103461 207221 103457 207221 103457 207222 103461 207222 103239 207222 103457 207223 103239 207223 103231 207223 103456 207224 103188 207224 103462 207224 103462 207225 103188 207225 103201 207225 103462 207226 103201 207226 103154 207226 103154 207227 103201 207227 103200 207227 103154 207228 103200 207228 103155 207228 103477 207229 103464 207229 103463 207229 103463 207230 103464 207230 103459 207230 103463 207231 103459 207231 103465 207231 103465 207232 103459 207232 98875 207232 103489 207233 103466 207233 103166 207233 103166 207234 103466 207234 103251 207234 103166 207235 103251 207235 103167 207235 103167 207236 103251 207236 103467 207236 103167 207237 103467 207237 103460 207237 103468 207238 103469 207238 98898 207238 98898 207239 103469 207239 103493 207239 98898 207240 103493 207240 98897 207240 103491 207241 103470 207241 98881 207241 98919 207242 103471 207242 103470 207242 103470 207243 103471 207243 98880 207243 103470 207244 98880 207244 98881 207244 98918 207245 103474 207245 103476 207245 103472 207246 103473 207246 103474 207246 103474 207247 103473 207247 103475 207247 103474 207248 103475 207248 103476 207248 103477 207249 103478 207249 103464 207249 103464 207250 103478 207250 103479 207250 103464 207251 103479 207251 98919 207251 98919 207252 103479 207252 98878 207252 98919 207253 98878 207253 103471 207253 103476 207254 98872 207254 98918 207254 98918 207255 98872 207255 103480 207255 98918 207256 103480 207256 103481 207256 103481 207257 103480 207257 103482 207257 103481 207258 103482 207258 98875 207258 98917 207259 103485 207259 103472 207259 103472 207260 103485 207260 98869 207260 103472 207261 98869 207261 103473 207261 103231 207262 103189 207262 103483 207262 103483 207263 103189 207263 98865 207263 103483 207264 98865 207264 98917 207264 98917 207265 98865 207265 103484 207265 98917 207266 103484 207266 103485 207266 103496 207267 103486 207267 103162 207267 103162 207268 103486 207268 103487 207268 103162 207269 103487 207269 103164 207269 103164 207270 103487 207270 103192 207270 103164 207271 103192 207271 103489 207271 103489 207272 103192 207272 103488 207272 103489 207273 103488 207273 103466 207273 98924 207274 98923 207274 98891 207274 98881 207275 103490 207275 103491 207275 103491 207276 103490 207276 98883 207276 103491 207277 98883 207277 98922 207277 103200 207278 103193 207278 103155 207278 103155 207279 103193 207279 103282 207279 103155 207280 103282 207280 103156 207280 103156 207281 103282 207281 103497 207281 103156 207282 103497 207282 103158 207282 98891 207283 98893 207283 98924 207283 98924 207284 98893 207284 103492 207284 98924 207285 103492 207285 103493 207285 103493 207286 103492 207286 98894 207286 103493 207287 98894 207287 98897 207287 103494 207288 103217 207288 103495 207288 103495 207289 103217 207289 103269 207289 103495 207290 103269 207290 103496 207290 103496 207291 103269 207291 103198 207291 103496 207292 103198 207292 103486 207292 98883 207293 98886 207293 98922 207293 98922 207294 98886 207294 98887 207294 98922 207295 98887 207295 103501 207295 103497 207296 103498 207296 103158 207296 103158 207297 103498 207297 103499 207297 103158 207298 103499 207298 103159 207298 103159 207299 103499 207299 103272 207299 103159 207300 103272 207300 103494 207300 103494 207301 103272 207301 103221 207301 103494 207302 103221 207302 103217 207302 98887 207303 103500 207303 103501 207303 103501 207304 103500 207304 103502 207304 103501 207305 103502 207305 98923 207305 98923 207306 103502 207306 98890 207306 98923 207307 98890 207307 98891 207307 103294 207308 103503 207308 103296 207308 103296 207309 103503 207309 103347 207309 103296 207310 103347 207310 103505 207310 103505 207311 103347 207311 103504 207311 103505 207312 103504 207312 103506 207312 103506 207313 103504 207313 103354 207313 103506 207314 103354 207314 103287 207314 103287 207315 103354 207315 103507 207315 103287 207316 103507 207316 103508 207316 103508 207317 103507 207317 103509 207317 103508 207318 103509 207318 103510 207318 103510 207319 103509 207319 103351 207319 103510 207320 103351 207320 103511 207320 103511 207321 103351 207321 103360 207321 103511 207322 103360 207322 103512 207322 103512 207323 103360 207323 103513 207323 103512 207324 103513 207324 103280 207324 103280 207325 103513 207325 103362 207325 103280 207326 103362 207326 103275 207326 103275 207327 103362 207327 103514 207327 103275 207328 103514 207328 103515 207328 103515 207329 103514 207329 103517 207329 103515 207330 103517 207330 103516 207330 103516 207331 103517 207331 103363 207331 103516 207332 103363 207332 103518 207332 103518 207333 103363 207333 103313 207333 103518 207334 103313 207334 103270 207334 103270 207335 103313 207335 103519 207335 103270 207336 103519 207336 103520 207336 103520 207337 103519 207337 103370 207337 103520 207338 103370 207338 103521 207338 103521 207339 103370 207339 103522 207339 103521 207340 103522 207340 103213 207340 103213 207341 103522 207341 103524 207341 103213 207342 103524 207342 103523 207342 103523 207343 103524 207343 103321 207343 103523 207344 103321 207344 103265 207344 103265 207345 103321 207345 103375 207345 103265 207346 103375 207346 103266 207346 103266 207347 103375 207347 103297 207347 103266 207348 103297 207348 103268 207348 103268 207349 103297 207349 103525 207349 103268 207350 103525 207350 103526 207350 103526 207351 103525 207351 103380 207351 103526 207352 103380 207352 103527 207352 103527 207353 103380 207353 103379 207353 103527 207354 103379 207354 103211 207354 103211 207355 103379 207355 103528 207355 103211 207356 103528 207356 103255 207356 103255 207357 103528 207357 103529 207357 103255 207358 103529 207358 103530 207358 103530 207359 103529 207359 103384 207359 103530 207360 103384 207360 103531 207360 103531 207361 103384 207361 103532 207361 103531 207362 103532 207362 103257 207362 103257 207363 103532 207363 103533 207363 103257 207364 103533 207364 103247 207364 103247 207365 103533 207365 103534 207365 103247 207366 103534 207366 103248 207366 103248 207367 103534 207367 103535 207367 103248 207368 103535 207368 103250 207368 103250 207369 103535 207369 103388 207369 103250 207370 103388 207370 103536 207370 103536 207371 103388 207371 103537 207371 103536 207372 103537 207372 103246 207372 103246 207373 103537 207373 103538 207373 103246 207374 103538 207374 103539 207374 103539 207375 103538 207375 103394 207375 103539 207376 103394 207376 103540 207376 103540 207377 103394 207377 103541 207377 103540 207378 103541 207378 103203 207378 103203 207379 103541 207379 103392 207379 103203 207380 103392 207380 103542 207380 103542 207381 103392 207381 103343 207381 103542 207382 103343 207382 103543 207382 103543 207383 103343 207383 103344 207383 103543 207384 103344 207384 103238 207384 103238 207385 103344 207385 103400 207385 103238 207386 103400 207386 103236 207386 103236 207387 103400 207387 103544 207387 103236 207388 103544 207388 103229 207388 103229 207389 103544 207389 103403 207389 103229 207390 103403 207390 98673 207390 98673 207391 103403 207391 98672 207391 98642 207392 98641 207392 103545 207392 103545 207393 98641 207393 103612 207393 103545 207394 103612 207394 98456 207394 98456 207395 103612 207395 103546 207395 98456 207396 103546 207396 98453 207396 98453 207397 103546 207397 98454 207397 98454 207398 103546 207398 103547 207398 98454 207399 103547 207399 103548 207399 103548 207400 103547 207400 103614 207400 103548 207401 103614 207401 98451 207401 98451 207402 103614 207402 103549 207402 103549 207403 103614 207403 103550 207403 103549 207404 103550 207404 98452 207404 98452 207405 103550 207405 103615 207405 98452 207406 103615 207406 103551 207406 103551 207407 103615 207407 103554 207407 103551 207408 103554 207408 103552 207408 103552 207409 103554 207409 103553 207409 103553 207410 103554 207410 103555 207410 103553 207411 103555 207411 103556 207411 103556 207412 103555 207412 103618 207412 103556 207413 103618 207413 103557 207413 103557 207414 103618 207414 103558 207414 103558 207415 103618 207415 103559 207415 103558 207416 103559 207416 103560 207416 103560 207417 103559 207417 103562 207417 103560 207418 103562 207418 103561 207418 103561 207419 103562 207419 103563 207419 103563 207420 103562 207420 103620 207420 103563 207421 103620 207421 103564 207421 103564 207422 103620 207422 103623 207422 103564 207423 103623 207423 103565 207423 103565 207424 103623 207424 98448 207424 98448 207425 103623 207425 103624 207425 98448 207426 103624 207426 103566 207426 103566 207427 103624 207427 103625 207427 103566 207428 103625 207428 98444 207428 98444 207429 103625 207429 98445 207429 98445 207430 103625 207430 103567 207430 98445 207431 103567 207431 103568 207431 103568 207432 103567 207432 103627 207432 103568 207433 103627 207433 98442 207433 98442 207434 103627 207434 103569 207434 103569 207435 103627 207435 103628 207435 103569 207436 103628 207436 103570 207436 103570 207437 103628 207437 103630 207437 103570 207438 103630 207438 98440 207438 98440 207439 103630 207439 103631 207439 98440 207440 103631 207440 98441 207440 98441 207441 103631 207441 103633 207441 98441 207442 103633 207442 98437 207442 98437 207443 103633 207443 103571 207443 103571 207444 103633 207444 103634 207444 103571 207445 103634 207445 103572 207445 103572 207446 103634 207446 103635 207446 103572 207447 103635 207447 103573 207447 103573 207448 103635 207448 98436 207448 98436 207449 103635 207449 103575 207449 98436 207450 103575 207450 103574 207450 103574 207451 103575 207451 103637 207451 103574 207452 103637 207452 98435 207452 98435 207453 103637 207453 103639 207453 98435 207454 103639 207454 98432 207454 98432 207455 103639 207455 103576 207455 103576 207456 103639 207456 103640 207456 103576 207457 103640 207457 103577 207457 103577 207458 103640 207458 103642 207458 103577 207459 103642 207459 98428 207459 98428 207460 103642 207460 98429 207460 98429 207461 103642 207461 103578 207461 98429 207462 103578 207462 98431 207462 98431 207463 103578 207463 103644 207463 98431 207464 103644 207464 98427 207464 98427 207465 103644 207465 98424 207465 98424 207466 103644 207466 103645 207466 98424 207467 103645 207467 103579 207467 103579 207468 103645 207468 103648 207468 103579 207469 103648 207469 103580 207469 103580 207470 103648 207470 98425 207470 98425 207471 103648 207471 103649 207471 98425 207472 103649 207472 103581 207472 103581 207473 103649 207473 103653 207473 103581 207474 103653 207474 98423 207474 103582 207475 103583 207475 103613 207475 103613 207476 103583 207476 98337 207476 103613 207477 98337 207477 103584 207477 103584 207478 98337 207478 98339 207478 103584 207479 98339 207479 103585 207479 103585 207480 98339 207480 103586 207480 103585 207481 103586 207481 103587 207481 103587 207482 103586 207482 98347 207482 103587 207483 98347 207483 103588 207483 103588 207484 98347 207484 98348 207484 103588 207485 98348 207485 103616 207485 103616 207486 98348 207486 98349 207486 103616 207487 98349 207487 103617 207487 103617 207488 98349 207488 103589 207488 103617 207489 103589 207489 103590 207489 103590 207490 103589 207490 98353 207490 103590 207491 98353 207491 103591 207491 103591 207492 98353 207492 98326 207492 103591 207493 98326 207493 103619 207493 103619 207494 98326 207494 98323 207494 103619 207495 98323 207495 103592 207495 103592 207496 98323 207496 98324 207496 103592 207497 98324 207497 103621 207497 103621 207498 98324 207498 98325 207498 103621 207499 98325 207499 103622 207499 103622 207500 98325 207500 98354 207500 103622 207501 98354 207501 103593 207501 103593 207502 98354 207502 98355 207502 103593 207503 98355 207503 103594 207503 103594 207504 98355 207504 103595 207504 103594 207505 103595 207505 103626 207505 103626 207506 103595 207506 98306 207506 103626 207507 98306 207507 103629 207507 103629 207508 98306 207508 98308 207508 103629 207509 98308 207509 103596 207509 103596 207510 98308 207510 98357 207510 103596 207511 98357 207511 103597 207511 103597 207512 98357 207512 103598 207512 103597 207513 103598 207513 103632 207513 103632 207514 103598 207514 98289 207514 103632 207515 98289 207515 103599 207515 103599 207516 98289 207516 103600 207516 103599 207517 103600 207517 103601 207517 103601 207518 103600 207518 98284 207518 103601 207519 98284 207519 103636 207519 103636 207520 98284 207520 103602 207520 103636 207521 103602 207521 103603 207521 103603 207522 103602 207522 103604 207522 103603 207523 103604 207523 103638 207523 103638 207524 103604 207524 98360 207524 103638 207525 98360 207525 103605 207525 103605 207526 98360 207526 103606 207526 103605 207527 103606 207527 103607 207527 103607 207528 103606 207528 98281 207528 103607 207529 98281 207529 103641 207529 103641 207530 98281 207530 98272 207530 103641 207531 98272 207531 103643 207531 103643 207532 98272 207532 103608 207532 103643 207533 103608 207533 103646 207533 103646 207534 103608 207534 98368 207534 103646 207535 98368 207535 103647 207535 103647 207536 98368 207536 98369 207536 103647 207537 98369 207537 103609 207537 103609 207538 98369 207538 98370 207538 103609 207539 98370 207539 103650 207539 103650 207540 98370 207540 98371 207540 103650 207541 98371 207541 103651 207541 103651 207542 98371 207542 98261 207542 103651 207543 98261 207543 103610 207543 103610 207544 98261 207544 103611 207544 103610 207545 103611 207545 103655 207545 103655 207546 103611 207546 98252 207546 98641 207547 103582 207547 103612 207547 103612 207548 103582 207548 103613 207548 103612 207549 103613 207549 103546 207549 103546 207550 103613 207550 103584 207550 103546 207551 103584 207551 103547 207551 103547 207552 103584 207552 103585 207552 103547 207553 103585 207553 103614 207553 103614 207554 103585 207554 103587 207554 103614 207555 103587 207555 103550 207555 103550 207556 103587 207556 103588 207556 103550 207557 103588 207557 103615 207557 103615 207558 103588 207558 103616 207558 103615 207559 103616 207559 103554 207559 103554 207560 103616 207560 103617 207560 103554 207561 103617 207561 103555 207561 103555 207562 103617 207562 103590 207562 103555 207563 103590 207563 103618 207563 103618 207564 103590 207564 103591 207564 103618 207565 103591 207565 103559 207565 103559 207566 103591 207566 103619 207566 103559 207567 103619 207567 103562 207567 103562 207568 103619 207568 103592 207568 103562 207569 103592 207569 103620 207569 103620 207570 103592 207570 103621 207570 103620 207571 103621 207571 103623 207571 103623 207572 103621 207572 103622 207572 103623 207573 103622 207573 103624 207573 103624 207574 103622 207574 103593 207574 103624 207575 103593 207575 103625 207575 103625 207576 103593 207576 103594 207576 103625 207577 103594 207577 103567 207577 103567 207578 103594 207578 103626 207578 103567 207579 103626 207579 103627 207579 103627 207580 103626 207580 103629 207580 103627 207581 103629 207581 103628 207581 103628 207582 103629 207582 103596 207582 103628 207583 103596 207583 103630 207583 103630 207584 103596 207584 103597 207584 103630 207585 103597 207585 103631 207585 103631 207586 103597 207586 103632 207586 103631 207587 103632 207587 103633 207587 103633 207588 103632 207588 103599 207588 103633 207589 103599 207589 103634 207589 103634 207590 103599 207590 103601 207590 103634 207591 103601 207591 103635 207591 103635 207592 103601 207592 103636 207592 103635 207593 103636 207593 103575 207593 103575 207594 103636 207594 103603 207594 103575 207595 103603 207595 103637 207595 103637 207596 103603 207596 103638 207596 103637 207597 103638 207597 103639 207597 103639 207598 103638 207598 103605 207598 103639 207599 103605 207599 103640 207599 103640 207600 103605 207600 103607 207600 103640 207601 103607 207601 103642 207601 103642 207602 103607 207602 103641 207602 103642 207603 103641 207603 103578 207603 103578 207604 103641 207604 103643 207604 103578 207605 103643 207605 103644 207605 103644 207606 103643 207606 103646 207606 103644 207607 103646 207607 103645 207607 103645 207608 103646 207608 103647 207608 103645 207609 103647 207609 103648 207609 103648 207610 103647 207610 103609 207610 103648 207611 103609 207611 103649 207611 103649 207612 103609 207612 103650 207612 103649 207613 103650 207613 103653 207613 103653 207614 103650 207614 103651 207614 103653 207615 103651 207615 103652 207615 103652 207616 103651 207616 103610 207616 103652 207617 103610 207617 103657 207617 103657 207618 103610 207618 103655 207618 98423 207619 103653 207619 98421 207619 98421 207620 103653 207620 103652 207620 98421 207621 103652 207621 103654 207621 103654 207622 103652 207622 103657 207622 103654 207623 103657 207623 103658 207623 98252 207624 98255 207624 103659 207624 98252 207625 103659 207625 103655 207625 103655 207626 103659 207626 103656 207626 103655 207627 103656 207627 103657 207627 103657 207628 103656 207628 98422 207628 103657 207629 98422 207629 103658 207629 98255 207630 98254 207630 98601 207630 98255 207631 98601 207631 103659 207631 103659 207632 98601 207632 103660 207632 103659 207633 103660 207633 103656 207633 103656 207634 103660 207634 103661 207634 103656 207635 103661 207635 98422 207635 102158 207636 103662 207636 102159 207636 102159 207637 103662 207637 103663 207637 102159 207638 103663 207638 102160 207638 102160 207639 103663 207639 103697 207639 102160 207640 103697 207640 102162 207640 102162 207641 103697 207641 103664 207641 102162 207642 103664 207642 103665 207642 103665 207643 103664 207643 103666 207643 103665 207644 103666 207644 102164 207644 102164 207645 103666 207645 103667 207645 102164 207646 103667 207646 102165 207646 102165 207647 103667 207647 103668 207647 102165 207648 103668 207648 102167 207648 102167 207649 103668 207649 103669 207649 102167 207650 103669 207650 102168 207650 102168 207651 103669 207651 103670 207651 102168 207652 103670 207652 102169 207652 102169 207653 103670 207653 103704 207653 102169 207654 103704 207654 102171 207654 102171 207655 103704 207655 103705 207655 102171 207656 103705 207656 99143 207656 99143 207657 103705 207657 103671 207657 99143 207658 103671 207658 99145 207658 99145 207659 103671 207659 103672 207659 99145 207660 103672 207660 103673 207660 103673 207661 103672 207661 98505 207661 103673 207662 98505 207662 99147 207662 99147 207663 98505 207663 98507 207663 99147 207664 98507 207664 103674 207664 103674 207665 98507 207665 103675 207665 103674 207666 103675 207666 103676 207666 103676 207667 103675 207667 98510 207667 103676 207668 98510 207668 103677 207668 103677 207669 98510 207669 103678 207669 103677 207670 103678 207670 103679 207670 103679 207671 103678 207671 98513 207671 103679 207672 98513 207672 103680 207672 103680 207673 98513 207673 103681 207673 103680 207674 103681 207674 103682 207674 103682 207675 103681 207675 98516 207675 103682 207676 98516 207676 103683 207676 103683 207677 98516 207677 98517 207677 103683 207678 98517 207678 99153 207678 99153 207679 98517 207679 98518 207679 99153 207680 98518 207680 99155 207680 99155 207681 98518 207681 98520 207681 99155 207682 98520 207682 99156 207682 99156 207683 98520 207683 98521 207683 99156 207684 98521 207684 103684 207684 103684 207685 98521 207685 103685 207685 103684 207686 103685 207686 99159 207686 99159 207687 103685 207687 103686 207687 99159 207688 103686 207688 103687 207688 103687 207689 103686 207689 98522 207689 103687 207690 98522 207690 102155 207690 102155 207691 98522 207691 103691 207691 102155 207692 103691 207692 103688 207692 103688 207693 103691 207693 103692 207693 103688 207694 103692 207694 103689 207694 103689 207695 103692 207695 103693 207695 103689 207696 103693 207696 103690 207696 103690 207697 103693 207697 103695 207697 103690 207698 103695 207698 102158 207698 102158 207699 103695 207699 103662 207699 98522 207700 102139 207700 103691 207700 103691 207701 102139 207701 102141 207701 103691 207702 102141 207702 103692 207702 103692 207703 102141 207703 103694 207703 103692 207704 103694 207704 103693 207704 103693 207705 103694 207705 102143 207705 103693 207706 102143 207706 103695 207706 103695 207707 102143 207707 102145 207707 103695 207708 102145 207708 103662 207708 103662 207709 102145 207709 103696 207709 103662 207710 103696 207710 103663 207710 103663 207711 103696 207711 102146 207711 103663 207712 102146 207712 103697 207712 103697 207713 102146 207713 103698 207713 103697 207714 103698 207714 103664 207714 103664 207715 103698 207715 102148 207715 103664 207716 102148 207716 103666 207716 103666 207717 102148 207717 103699 207717 103666 207718 103699 207718 103667 207718 103667 207719 103699 207719 103700 207719 103667 207720 103700 207720 103668 207720 103668 207721 103700 207721 103701 207721 103668 207722 103701 207722 103669 207722 103669 207723 103701 207723 103702 207723 103669 207724 103702 207724 103670 207724 103670 207725 103702 207725 103703 207725 103670 207726 103703 207726 103704 207726 103704 207727 103703 207727 103706 207727 103704 207728 103706 207728 103705 207728 103705 207729 103706 207729 102152 207729 103705 207730 102152 207730 103671 207730 103671 207731 102152 207731 98503 207731 103707 207732 103739 207732 103708 207732 103708 207733 103739 207733 99069 207733 103708 207734 99069 207734 103710 207734 103710 207735 99069 207735 103709 207735 103710 207736 103709 207736 102147 207736 102147 207737 103709 207737 103712 207737 102147 207738 103712 207738 103711 207738 103711 207739 103712 207739 99070 207739 103711 207740 99070 207740 102149 207740 102149 207741 99070 207741 103713 207741 102149 207742 103713 207742 103714 207742 103714 207743 103713 207743 103715 207743 103714 207744 103715 207744 102150 207744 102150 207745 103715 207745 99073 207745 102150 207746 99073 207746 102151 207746 102151 207747 99073 207747 103717 207747 102151 207748 103717 207748 103716 207748 103716 207749 103717 207749 99074 207749 103716 207750 99074 207750 102153 207750 102153 207751 99074 207751 103718 207751 102153 207752 103718 207752 103719 207752 103719 207753 103718 207753 102227 207753 103719 207754 102227 207754 103720 207754 103720 207755 102227 207755 102229 207755 103720 207756 102229 207756 99161 207756 99161 207757 102229 207757 102231 207757 99161 207758 102231 207758 103721 207758 103721 207759 102231 207759 102232 207759 103721 207760 102232 207760 99162 207760 99162 207761 102232 207761 102234 207761 99162 207762 102234 207762 103722 207762 103722 207763 102234 207763 102235 207763 103722 207764 102235 207764 103724 207764 103724 207765 102235 207765 103723 207765 103724 207766 103723 207766 99163 207766 99163 207767 103723 207767 103725 207767 99163 207768 103725 207768 103726 207768 103726 207769 103725 207769 103727 207769 103726 207770 103727 207770 99165 207770 99165 207771 103727 207771 102238 207771 99165 207772 102238 207772 99166 207772 99166 207773 102238 207773 102240 207773 99166 207774 102240 207774 103729 207774 103729 207775 102240 207775 103728 207775 103729 207776 103728 207776 103730 207776 103730 207777 103728 207777 103731 207777 103730 207778 103731 207778 99169 207778 99169 207779 103731 207779 102242 207779 99169 207780 102242 207780 103732 207780 103732 207781 102242 207781 103733 207781 103732 207782 103733 207782 99173 207782 99173 207783 103733 207783 103734 207783 99173 207784 103734 207784 102140 207784 102140 207785 103734 207785 99063 207785 102140 207786 99063 207786 103735 207786 103735 207787 99063 207787 103736 207787 103735 207788 103736 207788 102142 207788 102142 207789 103736 207789 99066 207789 102142 207790 99066 207790 102144 207790 102144 207791 99066 207791 99068 207791 102144 207792 99068 207792 103738 207792 103738 207793 99068 207793 103737 207793 103738 207794 103737 207794 103707 207794 103707 207795 103737 207795 103739 207795 103740 207796 98502 207796 102243 207796 103740 207797 102243 207797 103768 207797 103768 207798 102243 207798 103741 207798 103768 207799 103741 207799 103742 207799 103742 207800 103741 207800 103743 207800 103742 207801 103743 207801 103744 207801 103744 207802 103743 207802 102241 207802 103744 207803 102241 207803 103745 207803 103745 207804 102241 207804 103747 207804 103745 207805 103747 207805 103746 207805 103746 207806 103747 207806 102239 207806 103746 207807 102239 207807 103765 207807 103765 207808 102239 207808 103748 207808 103765 207809 103748 207809 103749 207809 103749 207810 103748 207810 103750 207810 103749 207811 103750 207811 103763 207811 103763 207812 103750 207812 103751 207812 103763 207813 103751 207813 103752 207813 103752 207814 103751 207814 102237 207814 103752 207815 102237 207815 103762 207815 103762 207816 102237 207816 102236 207816 103762 207817 102236 207817 103753 207817 103753 207818 102236 207818 102233 207818 103753 207819 102233 207819 103754 207819 103754 207820 102233 207820 102230 207820 103754 207821 102230 207821 103759 207821 103759 207822 102230 207822 103756 207822 103759 207823 103756 207823 103755 207823 103755 207824 103756 207824 102228 207824 103755 207825 102228 207825 103757 207825 103757 207826 102228 207826 103758 207826 103757 207827 103758 207827 103787 207827 103755 207828 103789 207828 103759 207828 103759 207829 103789 207829 102124 207829 103759 207830 102124 207830 103754 207830 103754 207831 102124 207831 103760 207831 103754 207832 103760 207832 103753 207832 103753 207833 103760 207833 103761 207833 103753 207834 103761 207834 103762 207834 103762 207835 103761 207835 102127 207835 103762 207836 102127 207836 103752 207836 103752 207837 102127 207837 102128 207837 103752 207838 102128 207838 103763 207838 103763 207839 102128 207839 102131 207839 103763 207840 102131 207840 103749 207840 103749 207841 102131 207841 103764 207841 103749 207842 103764 207842 103765 207842 103765 207843 103764 207843 102133 207843 103765 207844 102133 207844 103746 207844 103746 207845 102133 207845 103766 207845 103746 207846 103766 207846 103745 207846 103745 207847 103766 207847 102135 207847 103745 207848 102135 207848 103744 207848 103744 207849 102135 207849 103767 207849 103744 207850 103767 207850 103742 207850 103742 207851 103767 207851 103769 207851 103742 207852 103769 207852 103768 207852 103768 207853 103769 207853 103770 207853 103768 207854 103770 207854 103740 207854 103740 207855 103770 207855 103771 207855 103740 207856 103771 207856 98501 207856 98501 207857 103771 207857 99174 207857 98501 207858 99174 207858 103773 207858 99174 207859 103772 207859 103773 207859 103773 207860 103772 207860 103774 207860 103773 207861 103774 207861 98500 207861 98500 207862 103774 207862 99175 207862 98500 207863 99175 207863 98498 207863 98498 207864 99175 207864 103775 207864 98498 207865 103775 207865 98497 207865 98497 207866 103775 207866 103777 207866 98497 207867 103777 207867 103776 207867 103776 207868 103777 207868 103778 207868 103776 207869 103778 207869 98494 207869 98494 207870 103778 207870 99179 207870 98494 207871 99179 207871 98492 207871 98492 207872 99179 207872 99180 207872 98492 207873 99180 207873 103779 207873 103779 207874 99180 207874 103780 207874 103779 207875 103780 207875 103781 207875 103781 207876 103780 207876 99181 207876 103781 207877 99181 207877 103782 207877 103782 207878 99181 207878 99182 207878 103782 207879 99182 207879 98488 207879 98488 207880 99182 207880 99184 207880 98488 207881 99184 207881 103783 207881 103783 207882 99184 207882 103784 207882 103783 207883 103784 207883 103786 207883 103786 207884 103784 207884 103785 207884 103786 207885 103785 207885 98485 207885 98485 207886 103785 207886 99187 207886 98485 207887 99187 207887 103787 207887 103787 207888 99187 207888 99188 207888 103787 207889 99188 207889 103757 207889 103757 207890 99188 207890 102122 207890 103757 207891 102122 207891 103755 207891 103755 207892 102122 207892 103788 207892 103755 207893 103788 207893 103789 207893 103822 207894 102138 207894 102137 207894 103822 207895 102137 207895 103820 207895 103820 207896 102137 207896 103791 207896 103820 207897 103791 207897 103790 207897 103790 207898 103791 207898 102136 207898 103790 207899 102136 207899 103792 207899 103792 207900 102136 207900 103793 207900 103792 207901 103793 207901 103818 207901 103818 207902 103793 207902 102134 207902 103818 207903 102134 207903 103794 207903 103794 207904 102134 207904 102132 207904 103794 207905 102132 207905 103814 207905 103814 207906 102132 207906 103795 207906 103814 207907 103795 207907 103796 207907 103796 207908 103795 207908 102130 207908 103796 207909 102130 207909 103812 207909 103812 207910 102130 207910 102129 207910 103812 207911 102129 207911 103810 207911 103810 207912 102129 207912 102126 207912 103810 207913 102126 207913 103797 207913 103797 207914 102126 207914 103799 207914 103797 207915 103799 207915 103798 207915 103798 207916 103799 207916 102125 207916 103798 207917 102125 207917 103800 207917 103800 207918 102125 207918 103801 207918 103800 207919 103801 207919 103807 207919 103807 207920 103801 207920 103802 207920 103807 207921 103802 207921 103806 207921 103806 207922 103802 207922 102123 207922 103806 207923 102123 207923 103805 207923 103805 207924 102123 207924 102121 207924 103805 207925 102121 207925 103835 207925 103835 207926 102121 207926 103803 207926 103835 207927 103803 207927 103804 207927 103805 207928 98374 207928 103806 207928 103806 207929 98374 207929 98376 207929 103806 207930 98376 207930 103807 207930 103807 207931 98376 207931 103808 207931 103807 207932 103808 207932 103800 207932 103800 207933 103808 207933 103809 207933 103800 207934 103809 207934 103798 207934 103798 207935 103809 207935 98380 207935 103798 207936 98380 207936 103797 207936 103797 207937 98380 207937 103811 207937 103797 207938 103811 207938 103810 207938 103810 207939 103811 207939 103813 207939 103810 207940 103813 207940 103812 207940 103812 207941 103813 207941 98384 207941 103812 207942 98384 207942 103796 207942 103796 207943 98384 207943 98385 207943 103796 207944 98385 207944 103814 207944 103814 207945 98385 207945 103815 207945 103814 207946 103815 207946 103794 207946 103794 207947 103815 207947 103816 207947 103794 207948 103816 207948 103818 207948 103818 207949 103816 207949 103817 207949 103818 207950 103817 207950 103792 207950 103792 207951 103817 207951 103819 207951 103792 207952 103819 207952 103790 207952 103790 207953 103819 207953 98390 207953 103790 207954 98390 207954 103820 207954 103820 207955 98390 207955 103821 207955 103820 207956 103821 207956 103822 207956 103822 207957 103821 207957 98391 207957 103822 207958 98391 207958 98484 207958 98484 207959 98391 207959 104016 207959 98484 207960 104016 207960 98482 207960 98482 207961 104016 207961 104018 207961 98482 207962 104018 207962 98480 207962 98480 207963 104018 207963 103823 207963 98480 207964 103823 207964 98477 207964 98477 207965 103823 207965 103825 207965 98477 207966 103825 207966 103824 207966 103824 207967 103825 207967 104021 207967 103824 207968 104021 207968 98475 207968 98475 207969 104021 207969 104023 207969 98475 207970 104023 207970 98474 207970 98474 207971 104023 207971 104025 207971 98474 207972 104025 207972 103826 207972 103826 207973 104025 207973 103827 207973 103826 207974 103827 207974 98473 207974 98473 207975 103827 207975 104026 207975 98473 207976 104026 207976 98471 207976 98471 207977 104026 207977 104028 207977 98471 207978 104028 207978 103828 207978 103828 207979 104028 207979 103829 207979 103828 207980 103829 207980 98467 207980 98467 207981 103829 207981 103830 207981 98467 207982 103830 207982 103831 207982 103831 207983 103830 207983 104031 207983 103831 207984 104031 207984 103832 207984 103832 207985 104031 207985 104032 207985 103832 207986 104032 207986 103833 207986 103833 207987 104032 207987 104034 207987 103833 207988 104034 207988 103834 207988 103834 207989 104034 207989 104036 207989 103834 207990 104036 207990 103804 207990 103804 207991 104036 207991 103836 207991 103804 207992 103836 207992 103835 207992 103835 207993 103836 207993 98373 207993 103835 207994 98373 207994 103805 207994 103805 207995 98373 207995 98374 207995 103879 207996 103885 207996 103837 207996 103837 207997 103885 207997 103838 207997 103837 207998 103838 207998 102219 207998 102219 207999 103838 207999 103839 207999 102219 208000 103839 208000 102220 208000 102220 208001 103839 208001 103887 208001 102220 208002 103887 208002 102221 208002 102221 208003 103887 208003 103890 208003 102221 208004 103890 208004 103840 208004 103840 208005 103890 208005 103841 208005 103840 208006 103841 208006 103842 208006 103842 208007 103841 208007 103843 208007 103842 208008 103843 208008 103844 208008 103844 208009 103843 208009 103845 208009 103844 208010 103845 208010 102224 208010 102224 208011 103845 208011 103847 208011 102224 208012 103847 208012 103846 208012 103846 208013 103847 208013 103894 208013 103846 208014 103894 208014 103848 208014 103848 208015 103894 208015 103897 208015 103848 208016 103897 208016 103849 208016 103849 208017 103897 208017 103898 208017 103849 208018 103898 208018 99076 208018 99076 208019 103898 208019 103851 208019 99076 208020 103851 208020 103850 208020 103850 208021 103851 208021 103852 208021 103850 208022 103852 208022 103854 208022 103854 208023 103852 208023 103853 208023 103854 208024 103853 208024 103856 208024 103856 208025 103853 208025 103855 208025 103856 208026 103855 208026 103857 208026 103857 208027 103855 208027 103858 208027 103857 208028 103858 208028 103859 208028 103858 208029 98458 208029 103859 208029 103859 208030 98458 208030 103860 208030 103859 208031 103860 208031 103862 208031 103862 208032 103860 208032 103861 208032 103862 208033 103861 208033 99079 208033 99079 208034 103861 208034 98459 208034 99079 208035 98459 208035 103863 208035 103863 208036 98459 208036 98460 208036 103863 208037 98460 208037 99081 208037 99081 208038 98460 208038 103864 208038 99081 208039 103864 208039 99084 208039 99084 208040 103864 208040 103865 208040 99084 208041 103865 208041 99085 208041 99085 208042 103865 208042 103866 208042 99085 208043 103866 208043 99086 208043 99086 208044 103866 208044 103868 208044 99086 208045 103868 208045 103867 208045 103867 208046 103868 208046 103869 208046 103867 208047 103869 208047 99089 208047 99089 208048 103869 208048 98464 208048 99089 208049 98464 208049 103870 208049 103870 208050 98464 208050 103871 208050 103870 208051 103871 208051 99091 208051 99091 208052 103871 208052 98465 208052 99091 208053 98465 208053 99092 208053 99092 208054 98465 208054 103872 208054 99092 208055 103872 208055 103873 208055 103873 208056 103872 208056 103881 208056 103873 208057 103881 208057 103874 208057 103874 208058 103881 208058 103875 208058 103874 208059 103875 208059 102215 208059 102215 208060 103875 208060 103876 208060 102215 208061 103876 208061 103878 208061 103878 208062 103876 208062 103877 208062 103878 208063 103877 208063 103879 208063 103879 208064 103877 208064 103880 208064 103879 208065 103880 208065 103885 208065 103872 208066 99111 208066 103881 208066 103881 208067 99111 208067 103882 208067 103881 208068 103882 208068 103875 208068 103875 208069 103882 208069 102202 208069 103875 208070 102202 208070 103876 208070 103876 208071 102202 208071 103883 208071 103876 208072 103883 208072 103877 208072 103877 208073 103883 208073 103884 208073 103877 208074 103884 208074 103880 208074 103880 208075 103884 208075 102203 208075 103880 208076 102203 208076 103885 208076 103885 208077 102203 208077 103886 208077 103885 208078 103886 208078 103838 208078 103838 208079 103886 208079 102205 208079 103838 208080 102205 208080 103839 208080 103839 208081 102205 208081 103888 208081 103839 208082 103888 208082 103887 208082 103887 208083 103888 208083 103889 208083 103887 208084 103889 208084 103890 208084 103890 208085 103889 208085 103891 208085 103890 208086 103891 208086 103841 208086 103841 208087 103891 208087 102207 208087 103841 208088 102207 208088 103843 208088 103843 208089 102207 208089 103892 208089 103843 208090 103892 208090 103845 208090 103845 208091 103892 208091 103893 208091 103845 208092 103893 208092 103847 208092 103847 208093 103893 208093 103895 208093 103847 208094 103895 208094 103894 208094 103894 208095 103895 208095 103896 208095 103894 208096 103896 208096 103897 208096 103897 208097 103896 208097 102209 208097 103897 208098 102209 208098 103898 208098 103898 208099 102209 208099 102210 208099 103898 208100 102210 208100 103851 208100 103851 208101 102210 208101 102212 208101 99103 208102 103899 208102 99104 208102 99104 208103 103899 208103 103900 208103 99104 208104 103900 208104 103901 208104 103901 208105 103900 208105 103902 208105 103901 208106 103902 208106 103903 208106 103903 208107 103902 208107 103905 208107 103903 208108 103905 208108 103904 208108 103904 208109 103905 208109 102199 208109 103904 208110 102199 208110 103906 208110 103906 208111 102199 208111 103907 208111 103906 208112 103907 208112 99109 208112 99109 208113 103907 208113 103908 208113 99109 208114 103908 208114 103909 208114 103909 208115 103908 208115 103910 208115 103909 208116 103910 208116 103911 208116 103911 208117 103910 208117 99113 208117 103911 208118 99113 208118 102201 208118 102201 208119 99113 208119 99114 208119 102201 208120 99114 208120 103912 208120 103912 208121 99114 208121 99115 208121 103912 208122 99115 208122 103913 208122 103913 208123 99115 208123 103914 208123 103913 208124 103914 208124 103915 208124 103915 208125 103914 208125 103916 208125 103915 208126 103916 208126 102204 208126 102204 208127 103916 208127 103918 208127 102204 208128 103918 208128 103917 208128 103917 208129 103918 208129 103919 208129 103917 208130 103919 208130 103920 208130 103920 208131 103919 208131 99118 208131 103920 208132 99118 208132 103921 208132 103921 208133 99118 208133 103922 208133 103921 208134 103922 208134 102206 208134 102206 208135 103922 208135 103924 208135 102206 208136 103924 208136 103923 208136 103923 208137 103924 208137 99119 208137 103923 208138 99119 208138 103925 208138 103925 208139 99119 208139 99120 208139 103925 208140 99120 208140 103926 208140 103926 208141 99120 208141 99121 208141 103926 208142 99121 208142 103927 208142 103927 208143 99121 208143 103928 208143 103927 208144 103928 208144 102208 208144 102208 208145 103928 208145 103929 208145 102208 208146 103929 208146 103930 208146 103930 208147 103929 208147 99123 208147 103930 208148 99123 208148 102211 208148 102211 208149 99123 208149 99124 208149 102211 208150 99124 208150 103931 208150 103931 208151 99124 208151 99126 208151 103931 208152 99126 208152 102213 208152 102213 208153 99126 208153 103933 208153 102213 208154 103933 208154 103932 208154 103932 208155 103933 208155 102190 208155 103932 208156 102190 208156 103934 208156 103934 208157 102190 208157 103935 208157 103934 208158 103935 208158 99096 208158 99096 208159 103935 208159 102192 208159 99096 208160 102192 208160 103936 208160 103936 208161 102192 208161 102193 208161 103936 208162 102193 208162 103937 208162 103937 208163 102193 208163 103938 208163 103937 208164 103938 208164 99100 208164 99100 208165 103938 208165 103939 208165 99100 208166 103939 208166 103940 208166 103940 208167 103939 208167 102194 208167 103940 208168 102194 208168 103941 208168 103941 208169 102194 208169 102196 208169 103941 208170 102196 208170 103942 208170 103942 208171 102196 208171 102198 208171 103942 208172 102198 208172 99103 208172 99103 208173 102198 208173 103899 208173 103943 208174 103948 208174 98640 208174 103943 208175 98640 208175 103944 208175 103944 208176 98640 208176 103945 208176 103944 208177 103945 208177 98642 208177 98567 208178 98568 208178 103947 208178 103947 208179 98568 208179 103946 208179 103947 208180 103946 208180 103943 208180 103943 208181 103946 208181 98634 208181 103943 208182 98634 208182 103948 208182 98567 208183 103947 208183 103949 208183 103949 208184 103947 208184 102200 208184 103949 208185 102200 208185 103951 208185 98560 208186 98561 208186 103952 208186 103952 208187 98561 208187 103950 208187 103952 208188 103950 208188 102200 208188 102200 208189 103950 208189 98564 208189 102200 208190 98564 208190 103951 208190 98560 208191 103952 208191 98559 208191 98559 208192 103952 208192 103953 208192 98559 208193 103953 208193 103954 208193 103956 208194 103960 208194 103955 208194 103956 208195 103955 208195 103953 208195 103953 208196 103955 208196 98557 208196 103953 208197 98557 208197 103954 208197 103957 208198 103959 208198 103958 208198 103958 208199 103959 208199 98552 208199 103958 208200 98552 208200 103956 208200 103956 208201 98552 208201 98554 208201 103956 208202 98554 208202 103960 208202 103957 208203 103958 208203 103961 208203 103961 208204 103958 208204 103962 208204 103961 208205 103962 208205 103963 208205 102197 208206 98545 208206 98546 208206 102197 208207 98546 208207 103962 208207 103962 208208 98546 208208 98549 208208 103962 208209 98549 208209 103963 208209 102195 208210 98541 208210 98542 208210 102195 208211 98542 208211 102197 208211 102197 208212 98542 208212 103964 208212 102197 208213 103964 208213 98545 208213 98538 208214 98539 208214 103966 208214 103966 208215 98539 208215 103965 208215 103966 208216 103965 208216 102195 208216 102195 208217 103965 208217 98540 208217 102195 208218 98540 208218 98541 208218 98538 208219 103966 208219 103967 208219 103967 208220 103966 208220 103969 208220 103967 208221 103969 208221 98537 208221 98532 208222 98533 208222 103968 208222 103968 208223 98533 208223 103970 208223 103968 208224 103970 208224 103969 208224 103969 208225 103970 208225 98535 208225 103969 208226 98535 208226 98537 208226 98532 208227 103968 208227 98531 208227 98531 208228 103968 208228 102191 208228 98531 208229 102191 208229 103971 208229 103972 208230 98527 208230 103974 208230 103974 208231 98527 208231 98529 208231 103974 208232 98529 208232 102191 208232 102191 208233 98529 208233 98530 208233 102191 208234 98530 208234 103971 208234 103972 208235 103974 208235 103973 208235 103973 208236 103974 208236 103975 208236 103973 208237 103975 208237 103976 208237 102189 208238 98523 208238 98524 208238 102189 208239 98524 208239 103975 208239 103975 208240 98524 208240 98525 208240 103975 208241 98525 208241 103976 208241 103977 208242 103661 208242 103978 208242 103977 208243 103978 208243 102189 208243 102189 208244 103978 208244 103979 208244 102189 208245 103979 208245 98523 208245 98420 208246 99160 208246 103980 208246 103980 208247 99160 208247 102154 208247 103980 208248 102154 208248 102187 208248 102187 208249 102154 208249 103982 208249 102187 208250 103982 208250 103981 208250 103981 208251 103982 208251 102156 208251 103981 208252 102156 208252 103983 208252 103983 208253 102156 208253 102157 208253 103983 208254 102157 208254 103985 208254 103985 208255 102157 208255 103984 208255 103985 208256 103984 208256 102185 208256 102185 208257 103984 208257 103986 208257 102185 208258 103986 208258 103987 208258 103987 208259 103986 208259 103988 208259 103987 208260 103988 208260 103989 208260 103989 208261 103988 208261 102161 208261 103989 208262 102161 208262 102180 208262 102180 208263 102161 208263 103990 208263 102180 208264 103990 208264 103991 208264 103991 208265 103990 208265 103992 208265 103991 208266 103992 208266 102177 208266 102177 208267 103992 208267 102163 208267 102177 208268 102163 208268 103993 208268 103993 208269 102163 208269 102166 208269 103993 208270 102166 208270 102175 208270 102175 208271 102166 208271 103994 208271 102175 208272 103994 208272 103995 208272 103995 208273 103994 208273 103996 208273 103995 208274 103996 208274 102173 208274 102173 208275 103996 208275 102170 208275 102173 208276 102170 208276 103997 208276 103997 208277 102170 208277 102172 208277 98407 208278 103998 208278 103185 208278 103185 208279 103998 208279 102214 208279 103185 208280 102214 208280 103183 208280 103183 208281 102214 208281 104000 208281 103183 208282 104000 208282 103999 208282 103999 208283 104000 208283 104001 208283 103999 208284 104001 208284 104002 208284 104002 208285 104001 208285 104003 208285 104002 208286 104003 208286 104004 208286 104004 208287 104003 208287 102216 208287 104004 208288 102216 208288 103180 208288 103180 208289 102216 208289 102217 208289 103180 208290 102217 208290 104005 208290 104005 208291 102217 208291 102218 208291 104005 208292 102218 208292 104006 208292 104006 208293 102218 208293 104007 208293 104006 208294 104007 208294 104008 208294 104008 208295 104007 208295 104009 208295 104008 208296 104009 208296 103178 208296 103178 208297 104009 208297 104010 208297 103178 208298 104010 208298 103176 208298 103176 208299 104010 208299 102222 208299 103176 208300 102222 208300 103174 208300 103174 208301 102222 208301 104012 208301 103174 208302 104012 208302 104011 208302 104011 208303 104012 208303 102223 208303 104011 208304 102223 208304 103172 208304 103172 208305 102223 208305 104014 208305 103172 208306 104014 208306 104013 208306 104013 208307 104014 208307 102225 208307 104013 208308 102225 208308 104015 208308 104015 208309 102225 208309 102226 208309 104015 208310 102226 208310 103170 208310 103170 208311 102226 208311 98392 208311 98391 208312 104017 208312 104016 208312 104016 208313 104017 208313 103153 208313 104016 208314 103153 208314 104018 208314 104018 208315 103153 208315 104019 208315 104018 208316 104019 208316 103823 208316 103823 208317 104019 208317 104020 208317 103823 208318 104020 208318 103825 208318 103825 208319 104020 208319 103157 208319 103825 208320 103157 208320 104021 208320 104021 208321 103157 208321 104022 208321 104021 208322 104022 208322 104023 208322 104023 208323 104022 208323 104024 208323 104023 208324 104024 208324 104025 208324 104025 208325 104024 208325 103160 208325 104025 208326 103160 208326 103827 208326 103827 208327 103160 208327 104027 208327 103827 208328 104027 208328 104026 208328 104026 208329 104027 208329 103161 208329 104026 208330 103161 208330 104028 208330 104028 208331 103161 208331 104029 208331 104028 208332 104029 208332 103829 208332 103829 208333 104029 208333 103163 208333 103829 208334 103163 208334 103830 208334 103830 208335 103163 208335 104030 208335 103830 208336 104030 208336 104031 208336 104031 208337 104030 208337 103165 208337 104031 208338 103165 208338 104032 208338 104032 208339 103165 208339 104033 208339 104032 208340 104033 208340 104034 208340 104034 208341 104033 208341 103168 208341 104034 208342 103168 208342 104036 208342 104036 208343 103168 208343 104035 208343 104036 208344 104035 208344 103836 208344 103836 208345 104035 208345 104037 208345 104040 208346 102871 208346 104038 208346 104038 208347 102871 208347 104039 208347 104038 208348 104039 208348 102793 208348 102793 208349 104039 208349 102869 208349 102793 208350 102869 208350 104048 208350 104038 208351 102787 208351 104040 208351 104040 208352 102787 208352 102789 208352 104040 208353 102789 208353 104041 208353 104041 208354 102789 208354 104042 208354 104041 208355 104042 208355 104043 208355 104043 208356 104042 208356 103089 208356 104043 208357 103089 208357 104044 208357 104044 208358 103089 208358 103102 208358 104044 208359 103102 208359 98977 208359 98977 208360 103102 208360 104045 208360 98977 208361 104045 208361 98979 208361 98979 208362 104045 208362 103100 208362 98979 208363 103100 208363 102866 208363 102866 208364 103100 208364 103096 208364 102866 208365 103096 208365 102867 208365 102867 208366 103096 208366 103094 208366 102867 208367 103094 208367 104046 208367 104046 208368 103094 208368 103092 208368 104046 208369 103092 208369 104047 208369 104047 208370 103092 208370 103090 208370 104047 208371 103090 208371 102869 208371 102869 208372 103090 208372 102792 208372 102869 208373 102792 208373 104048 208373 104049 208374 102074 208374 104235 208374 104049 208375 104235 208375 101614 208375 101614 208376 104235 208376 104050 208376 101614 208377 104050 208377 104051 208377 104051 208378 104050 208378 104052 208378 104051 208379 104052 208379 101613 208379 101613 208380 104052 208380 104053 208380 101613 208381 104053 208381 104054 208381 104054 208382 104053 208382 104055 208382 104054 208383 104055 208383 101611 208383 101611 208384 104055 208384 104056 208384 101611 208385 104056 208385 101610 208385 101610 208386 104056 208386 104230 208386 101610 208387 104230 208387 101609 208387 101609 208388 104230 208388 104240 208388 101609 208389 104240 208389 104058 208389 104058 208390 104240 208390 104057 208390 104058 208391 104057 208391 101606 208391 101606 208392 104057 208392 104060 208392 101606 208393 104060 208393 104059 208393 104059 208394 104060 208394 104061 208394 104059 208395 104061 208395 104062 208395 104062 208396 104061 208396 104242 208396 104062 208397 104242 208397 101603 208397 101603 208398 104242 208398 104225 208398 101603 208399 104225 208399 104063 208399 104063 208400 104225 208400 104246 208400 104063 208401 104246 208401 104064 208401 104064 208402 104246 208402 104065 208402 104064 208403 104065 208403 101600 208403 101600 208404 104065 208404 104224 208404 101600 208405 104224 208405 101598 208405 101598 208406 104224 208406 104223 208406 101598 208407 104223 208407 101934 208407 99211 208408 99209 208408 104272 208408 99211 208409 104272 208409 104066 208409 104066 208410 104272 208410 104274 208410 104066 208411 104274 208411 101595 208411 101595 208412 104274 208412 104269 208412 101595 208413 104269 208413 101593 208413 101593 208414 104269 208414 104271 208414 101593 208415 104271 208415 101592 208415 101592 208416 104271 208416 104067 208416 101592 208417 104067 208417 104068 208417 104068 208418 104067 208418 104267 208418 104068 208419 104267 208419 104069 208419 104069 208420 104267 208420 104265 208420 104069 208421 104265 208421 104070 208421 104070 208422 104265 208422 104264 208422 104070 208423 104264 208423 101589 208423 101589 208424 104264 208424 104277 208424 101589 208425 104277 208425 101588 208425 101588 208426 104277 208426 104263 208426 101588 208427 104263 208427 101587 208427 101587 208428 104263 208428 104262 208428 101587 208429 104262 208429 104071 208429 104071 208430 104262 208430 104278 208430 104071 208431 104278 208431 104072 208431 104072 208432 104278 208432 104259 208432 104072 208433 104259 208433 101583 208433 101583 208434 104259 208434 104255 208434 101583 208435 104255 208435 104073 208435 104073 208436 104255 208436 104075 208436 104073 208437 104075 208437 104074 208437 104074 208438 104075 208438 104076 208438 104074 208439 104076 208439 104077 208439 104077 208440 104076 208440 104253 208440 104077 208441 104253 208441 101581 208441 102395 208442 102396 208442 98269 208442 98269 208443 102396 208443 102069 208443 98269 208444 102069 208444 98253 208444 104078 208445 104169 208445 104079 208445 104079 208446 104169 208446 104173 208446 104079 208447 104173 208447 104080 208447 102513 208448 102512 208448 104221 208448 104221 208449 102512 208449 98340 208449 104221 208450 98340 208450 98341 208450 104081 208451 102498 208451 104100 208451 104100 208452 102498 208452 104082 208452 104100 208453 104082 208453 104083 208453 102043 208454 102034 208454 98636 208454 102049 208455 102047 208455 104085 208455 104085 208456 102047 208456 104084 208456 104085 208457 104084 208457 102045 208457 102043 208458 98636 208458 102045 208458 102045 208459 98636 208459 104100 208459 102045 208460 104100 208460 104085 208460 104085 208461 104100 208461 104083 208461 104085 208462 104083 208462 102049 208462 102034 208463 102036 208463 98636 208463 98636 208464 102036 208464 104086 208464 98636 208465 104086 208465 104087 208465 102032 208466 103583 208466 102041 208466 102041 208467 103583 208467 104087 208467 102041 208468 104087 208468 102040 208468 102040 208469 104087 208469 104086 208469 104090 208470 102441 208470 104089 208470 104089 208471 102441 208471 104088 208471 104088 208472 102451 208472 104089 208472 104089 208473 102451 208473 102450 208473 104089 208474 102450 208474 104090 208474 104090 208475 102450 208475 104091 208475 104217 208476 104092 208476 104094 208476 104094 208477 104092 208477 102476 208477 102476 208478 104093 208478 104094 208478 104094 208479 104093 208479 102473 208479 104094 208480 102473 208480 102472 208480 102472 208481 104095 208481 104094 208481 104094 208482 104095 208482 102465 208482 104094 208483 102465 208483 98599 208483 102465 208484 104096 208484 98599 208484 98599 208485 104096 208485 104097 208485 98599 208486 104097 208486 98636 208486 98636 208487 104097 208487 102467 208487 98636 208488 102467 208488 102468 208488 102468 208489 104098 208489 98636 208489 98636 208490 104098 208490 104099 208490 98636 208491 104099 208491 104100 208491 104100 208492 104099 208492 104101 208492 104100 208493 104101 208493 104102 208493 102501 208494 104104 208494 104103 208494 104103 208495 104104 208495 104105 208495 104102 208496 102501 208496 104100 208496 104100 208497 102501 208497 104103 208497 104100 208498 104103 208498 104081 208498 104081 208499 104103 208499 104105 208499 104081 208500 104105 208500 102497 208500 104108 208501 104123 208501 104106 208501 104106 208502 104123 208502 104124 208502 104111 208503 104109 208503 104107 208503 104107 208504 104109 208504 104123 208504 104107 208505 104123 208505 102406 208505 102406 208506 104123 208506 104108 208506 104211 208507 104212 208507 102404 208507 102404 208508 104212 208508 104109 208508 102404 208509 104109 208509 104110 208509 104110 208510 104109 208510 104111 208510 104112 208511 102401 208511 102436 208511 102436 208512 102401 208512 104116 208512 104113 208513 104115 208513 104114 208513 104114 208514 104115 208514 104117 208514 104116 208515 104113 208515 102436 208515 102436 208516 104113 208516 104114 208516 102436 208517 104114 208517 104118 208517 104118 208518 104114 208518 104117 208518 104118 208519 104117 208519 104119 208519 104210 208520 102387 208520 102392 208520 102387 208521 104210 208521 102386 208521 104120 208522 102388 208522 102399 208522 104209 208523 104121 208523 104208 208523 104208 208524 104121 208524 102410 208524 104208 208525 102410 208525 98595 208525 98595 208526 102410 208526 104122 208526 98595 208527 104122 208527 104123 208527 104123 208528 104122 208528 102409 208528 104123 208529 102409 208529 104124 208529 102346 208530 104127 208530 104125 208530 104125 208531 104127 208531 98592 208531 102338 208532 104126 208532 102342 208532 102342 208533 104126 208533 98592 208533 102342 208534 98592 208534 102345 208534 102345 208535 98592 208535 104127 208535 104206 208536 102335 208536 102380 208536 102380 208537 102335 208537 102336 208537 102373 208538 104128 208538 104130 208538 104130 208539 104128 208539 104129 208539 102336 208540 102373 208540 102380 208540 102380 208541 102373 208541 104130 208541 102380 208542 104130 208542 104131 208542 104131 208543 104130 208543 104129 208543 104131 208544 104129 208544 104132 208544 104137 208545 104133 208545 104138 208545 104133 208546 104137 208546 102319 208546 104134 208547 104135 208547 104136 208547 104139 208548 98587 208548 102349 208548 102349 208549 98587 208549 102319 208549 102349 208550 102319 208550 104136 208550 104136 208551 102319 208551 104137 208551 104136 208552 104137 208552 104134 208552 104134 208553 104137 208553 104138 208553 104139 208554 102351 208554 98587 208554 98587 208555 102351 208555 104140 208555 98587 208556 104140 208556 98590 208556 98590 208557 104140 208557 104141 208557 98590 208558 104141 208558 102340 208558 102340 208559 102348 208559 98590 208559 98590 208560 102348 208560 104142 208560 98590 208561 104142 208561 104125 208561 104125 208562 104142 208562 104143 208562 104125 208563 104143 208563 102346 208563 104158 208564 102269 208564 98584 208564 98584 208565 102269 208565 98586 208565 104204 208566 104145 208566 104144 208566 104144 208567 104145 208567 102267 208567 102308 208568 104146 208568 104148 208568 104148 208569 104146 208569 104147 208569 102267 208570 102308 208570 104144 208570 104144 208571 102308 208571 104148 208571 104144 208572 104148 208572 104149 208572 104149 208573 104148 208573 104147 208573 104149 208574 104147 208574 102305 208574 102253 208575 102246 208575 104150 208575 104150 208576 102246 208576 102254 208576 102254 208577 102250 208577 104150 208577 104150 208578 102250 208578 104151 208578 104150 208579 104151 208579 102253 208579 102253 208580 104151 208580 102252 208580 102284 208581 102283 208581 104152 208581 104152 208582 102283 208582 104153 208582 104153 208583 102281 208583 104152 208583 104152 208584 102281 208584 104154 208584 104152 208585 104154 208585 98582 208585 98582 208586 104154 208586 104155 208586 98582 208587 104155 208587 102278 208587 102278 208588 102276 208588 98582 208588 98582 208589 102276 208589 102275 208589 98582 208590 102275 208590 104156 208590 104156 208591 102275 208591 102274 208591 102274 208592 102273 208592 104156 208592 104156 208593 102273 208593 104157 208593 104156 208594 104157 208594 98584 208594 98584 208595 104157 208595 102270 208595 98584 208596 102270 208596 104158 208596 102247 208597 104162 208597 102255 208597 102255 208598 104162 208598 102259 208598 102255 208599 102259 208599 102256 208599 102300 208600 104160 208600 104159 208600 104159 208601 104160 208601 104161 208601 104159 208602 104161 208602 102247 208602 102247 208603 104161 208603 102264 208603 102247 208604 102264 208604 104162 208604 104162 208605 102264 208605 102262 208605 104162 208606 102262 208606 102259 208606 102303 208607 104163 208607 104164 208607 104164 208608 104163 208608 102326 208608 102326 208609 102313 208609 104164 208609 104164 208610 102313 208610 102309 208610 104164 208611 102309 208611 102303 208611 102303 208612 102309 208612 102311 208612 102285 208613 104165 208613 98579 208613 98579 208614 104165 208614 102288 208614 102288 208615 102289 208615 98579 208615 98579 208616 102289 208616 104166 208616 98579 208617 104166 208617 104168 208617 104168 208618 104166 208618 104167 208618 104168 208619 104167 208619 102291 208619 104197 208620 104198 208620 102294 208620 102294 208621 104198 208621 104168 208621 102294 208622 104168 208622 102292 208622 102292 208623 104168 208623 102291 208623 104172 208624 104169 208624 102375 208624 104169 208625 104172 208625 104173 208625 104170 208626 104171 208626 104174 208626 102357 208627 102358 208627 104177 208627 102357 208628 104177 208628 102354 208628 102375 208629 104170 208629 104172 208629 104172 208630 104170 208630 104174 208630 104172 208631 104174 208631 104173 208631 104173 208632 104174 208632 104175 208632 104173 208633 104175 208633 104177 208633 104177 208634 104175 208634 104176 208634 104177 208635 104176 208635 102354 208635 102358 208636 104178 208636 104177 208636 104177 208637 104178 208637 102360 208637 104177 208638 102360 208638 98573 208638 104179 208639 104190 208639 102364 208639 102364 208640 104190 208640 98573 208640 102364 208641 98573 208641 102362 208641 102362 208642 98573 208642 102360 208642 104179 208643 102366 208643 104190 208643 104190 208644 102366 208644 102368 208644 104190 208645 102368 208645 104180 208645 104191 208646 102372 208646 104192 208646 104181 208647 102333 208647 104182 208647 104182 208648 102333 208648 102332 208648 102372 208649 104181 208649 104192 208649 104192 208650 104181 208650 104182 208650 104192 208651 104182 208651 102321 208651 102321 208652 104182 208652 102332 208652 102321 208653 102332 208653 102331 208653 98254 208654 99212 208654 104184 208654 104184 208655 99212 208655 104183 208655 104184 208656 104183 208656 104177 208656 104183 208657 104185 208657 104177 208657 104177 208658 104185 208658 104186 208658 104177 208659 104186 208659 102057 208659 104173 208660 104187 208660 104080 208660 104080 208661 104187 208661 102052 208661 104080 208662 102052 208662 102051 208662 102057 208663 102058 208663 104177 208663 104177 208664 102058 208664 104188 208664 104177 208665 104188 208665 104173 208665 104173 208666 104188 208666 102054 208666 104173 208667 102054 208667 104187 208667 104187 208668 102054 208668 104189 208668 104187 208669 104189 208669 102052 208669 104180 208670 104191 208670 104190 208670 104190 208671 104191 208671 104192 208671 104190 208672 104192 208672 98575 208672 98575 208673 104192 208673 104193 208673 98575 208674 104193 208674 104194 208674 104194 208675 104193 208675 102324 208675 104194 208676 102324 208676 104195 208676 104195 208677 102324 208677 104196 208677 104195 208678 104196 208678 98579 208678 98579 208679 104196 208679 104163 208679 98579 208680 104163 208680 102285 208680 102285 208681 104163 208681 102303 208681 104197 208682 104199 208682 104198 208682 104198 208683 104199 208683 102299 208683 104198 208684 102299 208684 104200 208684 104200 208685 102299 208685 102300 208685 104200 208686 102300 208686 104201 208686 104201 208687 102300 208687 104159 208687 104201 208688 104159 208688 104202 208688 104202 208689 104159 208689 104203 208689 104202 208690 104203 208690 104152 208690 104152 208691 104203 208691 102246 208691 104152 208692 102246 208692 102284 208692 102284 208693 102246 208693 102253 208693 102269 208694 104204 208694 98586 208694 98586 208695 104204 208695 104144 208695 98586 208696 104144 208696 104205 208696 104205 208697 104144 208697 102315 208697 104205 208698 102315 208698 98587 208698 98587 208699 102315 208699 102320 208699 98587 208700 102320 208700 102319 208700 102338 208701 104206 208701 104126 208701 104126 208702 104206 208702 102380 208702 104126 208703 102380 208703 104207 208703 104207 208704 102380 208704 102382 208704 104207 208705 102382 208705 104208 208705 104208 208706 102382 208706 102384 208706 104208 208707 102384 208707 104209 208707 104209 208708 102384 208708 102386 208708 104209 208709 102386 208709 102399 208709 102399 208710 102386 208710 104210 208710 102399 208711 104210 208711 104120 208711 104120 208712 104210 208712 102392 208712 104211 208713 104112 208713 104212 208713 104212 208714 104112 208714 102436 208714 104212 208715 102436 208715 104213 208715 104213 208716 102436 208716 102438 208716 104213 208717 102438 208717 104214 208717 104214 208718 102438 208718 104215 208718 104214 208719 104215 208719 98598 208719 98598 208720 104215 208720 104216 208720 98598 208721 104216 208721 104094 208721 104094 208722 104216 208722 102441 208722 104094 208723 102441 208723 104217 208723 104217 208724 102441 208724 104090 208724 104218 208725 104219 208725 104220 208725 102648 208726 102695 208726 104245 208726 102513 208727 104221 208727 102650 208727 102650 208728 104221 208728 104223 208728 102650 208729 104223 208729 104222 208729 104222 208730 104223 208730 104224 208730 102648 208731 104246 208731 104225 208731 104226 208732 102686 208732 102645 208732 102644 208733 104226 208733 104242 208733 104242 208734 104226 208734 102645 208734 104242 208735 102645 208735 104225 208735 104225 208736 102645 208736 104227 208736 104225 208737 104227 208737 102648 208737 104061 208738 104060 208738 104228 208738 104228 208739 104060 208739 103104 208739 103104 208740 104060 208740 103105 208740 103105 208741 104060 208741 104057 208741 103105 208742 104057 208742 102573 208742 102810 208743 104229 208743 102811 208743 102811 208744 104229 208744 104240 208744 102811 208745 104240 208745 104230 208745 102505 208746 102797 208746 104056 208746 104056 208747 102797 208747 104231 208747 104056 208748 104231 208748 104230 208748 104230 208749 104231 208749 102680 208749 104230 208750 102680 208750 102811 208750 104232 208751 104055 208751 104053 208751 104232 208752 104233 208752 104238 208752 102444 208753 102443 208753 104052 208753 104052 208754 102443 208754 102785 208754 104052 208755 102785 208755 104053 208755 104053 208756 102785 208756 102675 208756 104053 208757 102675 208757 104232 208757 102069 208758 102396 208758 102074 208758 102074 208759 102396 208759 104234 208759 102074 208760 104234 208760 104235 208760 104234 208761 104218 208761 104235 208761 104235 208762 104218 208762 104220 208762 104235 208763 104220 208763 104050 208763 104220 208764 104236 208764 104050 208764 104050 208765 104236 208765 104237 208765 104050 208766 104237 208766 104052 208766 104052 208767 104237 208767 102445 208767 104052 208768 102445 208768 102444 208768 104232 208769 104238 208769 104055 208769 104055 208770 104238 208770 104239 208770 104055 208771 104239 208771 104056 208771 104056 208772 104239 208772 102506 208772 104056 208773 102506 208773 102505 208773 104229 208774 102575 208774 104240 208774 104240 208775 102575 208775 104241 208775 104240 208776 104241 208776 104057 208776 104057 208777 104241 208777 102574 208777 104057 208778 102574 208778 102573 208778 102644 208779 104242 208779 104243 208779 104243 208780 104242 208780 104061 208780 104243 208781 104061 208781 102642 208781 102642 208782 104061 208782 104228 208782 102642 208783 104228 208783 104244 208783 102648 208784 104245 208784 104246 208784 104246 208785 104245 208785 104247 208785 104246 208786 104247 208786 104065 208786 104248 208787 104222 208787 104249 208787 104249 208788 104222 208788 104224 208788 104249 208789 104224 208789 104250 208789 104250 208790 104224 208790 104065 208790 104250 208791 104065 208791 104251 208791 104251 208792 104065 208792 104247 208792 102316 208793 102314 208793 104277 208793 102651 208794 102454 208794 104273 208794 104261 208795 102752 208795 102327 208795 104078 208796 104079 208796 104252 208796 104252 208797 104079 208797 104253 208797 104252 208798 104253 208798 104254 208798 104254 208799 104253 208799 104076 208799 104261 208800 104255 208800 104259 208800 104257 208801 102244 208801 104258 208801 104256 208802 104257 208802 104278 208802 104278 208803 104257 208803 104258 208803 104278 208804 104258 208804 104259 208804 104259 208805 104258 208805 104260 208805 104259 208806 104260 208806 104261 208806 102743 208807 104262 208807 104263 208807 102314 208808 102306 208808 104277 208808 104277 208809 102306 208809 102662 208809 104277 208810 102662 208810 104263 208810 104263 208811 102662 208811 102666 208811 104263 208812 102666 208812 102743 208812 102661 208813 104264 208813 104265 208813 102381 208814 104266 208814 104267 208814 104267 208815 104266 208815 104268 208815 104267 208816 104268 208816 104265 208816 104265 208817 104268 208817 102660 208817 104265 208818 102660 208818 102661 208818 99051 208819 104067 208819 104271 208819 99051 208820 102394 208820 104276 208820 102437 208821 102715 208821 104269 208821 104269 208822 102715 208822 104270 208822 104269 208823 104270 208823 104271 208823 104271 208824 104270 208824 102657 208824 104271 208825 102657 208825 99051 208825 104082 208826 102498 208826 99209 208826 99209 208827 102498 208827 102702 208827 99209 208828 102702 208828 104272 208828 102702 208829 102651 208829 104272 208829 104272 208830 102651 208830 104273 208830 104272 208831 104273 208831 104274 208831 104273 208832 102440 208832 104274 208832 104274 208833 102440 208833 102439 208833 104274 208834 102439 208834 104269 208834 104269 208835 102439 208835 104275 208835 104269 208836 104275 208836 102437 208836 99051 208837 104276 208837 104067 208837 104067 208838 104276 208838 102385 208838 104067 208839 102385 208839 104267 208839 104267 208840 102385 208840 102383 208840 104267 208841 102383 208841 102381 208841 102316 208842 104277 208842 102317 208842 102317 208843 104277 208843 104264 208843 102317 208844 104264 208844 102318 208844 102318 208845 104264 208845 102661 208845 102318 208846 102661 208846 99043 208846 104256 208847 104278 208847 102245 208847 102245 208848 104278 208848 104262 208848 102245 208849 104262 208849 104279 208849 104279 208850 104262 208850 102743 208850 104279 208851 102743 208851 102742 208851 104261 208852 102327 208852 104255 208852 104255 208853 102327 208853 102325 208853 104255 208854 102325 208854 104075 208854 102322 208855 104254 208855 104280 208855 104280 208856 104254 208856 104076 208856 104280 208857 104076 208857 102323 208857 102323 208858 104076 208858 104075 208858 102323 208859 104075 208859 104281 208859 104281 208860 104075 208860 102325 208860 101156 208861 104282 208861 99373 208861 104291 208862 104283 208862 101156 208862 99373 208863 104282 208863 104284 208863 104284 208864 104282 208864 104286 208864 104284 208865 104286 208865 104287 208865 104311 208866 104285 208866 101169 208866 104286 208867 101154 208867 104287 208867 104287 208868 101154 208868 101150 208868 104287 208869 101150 208869 99369 208869 99369 208870 101150 208870 104288 208870 99369 208871 104288 208871 104285 208871 104285 208872 104288 208872 104289 208872 104285 208873 104289 208873 101169 208873 101169 208874 104289 208874 104290 208874 101169 208875 104290 208875 101171 208875 101171 208876 104290 208876 101170 208876 101156 208877 104294 208877 101159 208877 104291 208878 101156 208878 101775 208878 101775 208879 101156 208879 101159 208879 101775 208880 101159 208880 101158 208880 104292 208881 101170 208881 104293 208881 104293 208882 101170 208882 104290 208882 104293 208883 104290 208883 101780 208883 101780 208884 104290 208884 101778 208884 104294 208885 101156 208885 101161 208885 101161 208886 101156 208886 99373 208886 101161 208887 99373 208887 104295 208887 104295 208888 99373 208888 99374 208888 104295 208889 99374 208889 104296 208889 104296 208890 99374 208890 99375 208890 104296 208891 99375 208891 104297 208891 104297 208892 99375 208892 99376 208892 104297 208893 99376 208893 99649 208893 99649 208894 99376 208894 104298 208894 99649 208895 104298 208895 104299 208895 104299 208896 104298 208896 99377 208896 104299 208897 99377 208897 104301 208897 104301 208898 99377 208898 104300 208898 104301 208899 104300 208899 99665 208899 99665 208900 104300 208900 101751 208900 99665 208901 101751 208901 104302 208901 104302 208902 101751 208902 104303 208902 104302 208903 104303 208903 104304 208903 104304 208904 104303 208904 101753 208904 104304 208905 101753 208905 99662 208905 99662 208906 101753 208906 104305 208906 99662 208907 104305 208907 104306 208907 104305 208908 101754 208908 104306 208908 104306 208909 101754 208909 101756 208909 104306 208910 101756 208910 99659 208910 99659 208911 101756 208911 101757 208911 99659 208912 101757 208912 99658 208912 99658 208913 101757 208913 101758 208913 99658 208914 101758 208914 99656 208914 99656 208915 101758 208915 101760 208915 99656 208916 101760 208916 104307 208916 104307 208917 101760 208917 101761 208917 104307 208918 101761 208918 104308 208918 104308 208919 101761 208919 104309 208919 104308 208920 104309 208920 104310 208920 104310 208921 104309 208921 101762 208921 104310 208922 101762 208922 99653 208922 99653 208923 101762 208923 101763 208923 99653 208924 101763 208924 104315 208924 101169 208925 104312 208925 104311 208925 104311 208926 104312 208926 104313 208926 104311 208927 104313 208927 99367 208927 99367 208928 104313 208928 104325 208928 101763 208929 104314 208929 104315 208929 104315 208930 104314 208930 101764 208930 104315 208931 101764 208931 104316 208931 104316 208932 101764 208932 104317 208932 104316 208933 104317 208933 99651 208933 99651 208934 104317 208934 104318 208934 99651 208935 104318 208935 104319 208935 104319 208936 104318 208936 104320 208936 104319 208937 104320 208937 104321 208937 104321 208938 104320 208938 99361 208938 104321 208939 99361 208939 104322 208939 104322 208940 99361 208940 104323 208940 104322 208941 104323 208941 101167 208941 101167 208942 104323 208942 99363 208942 101167 208943 99363 208943 101165 208943 101165 208944 99363 208944 104324 208944 101165 208945 104324 208945 104325 208945 104325 208946 104324 208946 99365 208946 104325 208947 99365 208947 99367 208947 98242 208948 104329 208948 104330 208948 104326 208949 104329 208949 98242 208949 98239 208950 104326 208950 98242 208950 98242 208951 104327 208951 98243 208951 104332 208952 104327 208952 98242 208952 104330 208953 104332 208953 98242 208953 98239 208954 98240 208954 104326 208954 104326 208955 98240 208955 104328 208955 104326 208956 104328 208956 104329 208956 104329 208957 104328 208957 104339 208957 104329 208958 104339 208958 104330 208958 104330 208959 104339 208959 104331 208959 104330 208960 104331 208960 104332 208960 104332 208961 104331 208961 104342 208961 104332 208962 104342 208962 104327 208962 104327 208963 104342 208963 104343 208963 104327 208964 104343 208964 98243 208964 98243 208965 104343 208965 98236 208965 104333 208966 104334 208966 104335 208966 104335 208967 104334 208967 104337 208967 104335 208968 104337 208968 104336 208968 104336 208969 104337 208969 99862 208969 104336 208970 99862 208970 98238 208970 98238 208971 99862 208971 104338 208971 98238 208972 104338 208972 98240 208972 98240 208973 104338 208973 100847 208973 98240 208974 100847 208974 104328 208974 104328 208975 100847 208975 104340 208975 104328 208976 104340 208976 104339 208976 104339 208977 104340 208977 104341 208977 104339 208978 104341 208978 104331 208978 104331 208979 104341 208979 100846 208979 104331 208980 100846 208980 104342 208980 104342 208981 100846 208981 100845 208981 104342 208982 100845 208982 104343 208982 104343 208983 100845 208983 104344 208983 104343 208984 104344 208984 98236 208984 98236 208985 104344 208985 104345 208985 98236 208986 104345 208986 104346 208986 104346 208987 104345 208987 99863 208987 104346 208988 99863 208988 104333 208988 104333 208989 99863 208989 104334 208989 98233 208990 104348 208990 104347 208990 104353 208991 104348 208991 98233 208991 104352 208992 104353 208992 98233 208992 98233 208993 104349 208993 104350 208993 104351 208994 104349 208994 98233 208994 104347 208995 104351 208995 98233 208995 104352 208996 104370 208996 104353 208996 104353 208997 104370 208997 104354 208997 104353 208998 104354 208998 104348 208998 104348 208999 104354 208999 104359 208999 104348 209000 104359 209000 104347 209000 104347 209001 104359 209001 104360 209001 104347 209002 104360 209002 104351 209002 104351 209003 104360 209003 104361 209003 104351 209004 104361 209004 104349 209004 104349 209005 104361 209005 104355 209005 104349 209006 104355 209006 104350 209006 104350 209007 104355 209007 104356 209007 104354 209008 104357 209008 104359 209008 104359 209009 104357 209009 104358 209009 104359 209010 104358 209010 104360 209010 104360 209011 104358 209011 100828 209011 104360 209012 100828 209012 104361 209012 104361 209013 100828 209013 100827 209013 104361 209014 100827 209014 104355 209014 104355 209015 100827 209015 104362 209015 104355 209016 104362 209016 104356 209016 104356 209017 104362 209017 100826 209017 104356 209018 100826 209018 98228 209018 98228 209019 100826 209019 99880 209019 98228 209020 99880 209020 98229 209020 98229 209021 99880 209021 104363 209021 98229 209022 104363 209022 104364 209022 104364 209023 104363 209023 104365 209023 104364 209024 104365 209024 104366 209024 104366 209025 104365 209025 99878 209025 104366 209026 99878 209026 104367 209026 104367 209027 99878 209027 104368 209027 104367 209028 104368 209028 104370 209028 104370 209029 104368 209029 104369 209029 104370 209030 104369 209030 104354 209030 104354 209031 104369 209031 104357 209031 104373 209032 104372 209032 104376 209032 104371 209033 104372 209033 104373 209033 98225 209034 104371 209034 104373 209034 104373 209035 104375 209035 104374 209035 104379 209036 104375 209036 104373 209036 104376 209037 104379 209037 104373 209037 98225 209038 104385 209038 104371 209038 104371 209039 104385 209039 104386 209039 104371 209040 104386 209040 104372 209040 104372 209041 104386 209041 104377 209041 104372 209042 104377 209042 104376 209042 104376 209043 104377 209043 104378 209043 104376 209044 104378 209044 104379 209044 104379 209045 104378 209045 104380 209045 104379 209046 104380 209046 104375 209046 104375 209047 104380 209047 104381 209047 104375 209048 104381 209048 104374 209048 104374 209049 104381 209049 98217 209049 104391 209050 104382 209050 104384 209050 104384 209051 104382 209051 104383 209051 104384 209052 104383 209052 98223 209052 98223 209053 104383 209053 99889 209053 98223 209054 99889 209054 104385 209054 104385 209055 99889 209055 100807 209055 104385 209056 100807 209056 104386 209056 104386 209057 100807 209057 100806 209057 104386 209058 100806 209058 104377 209058 104377 209059 100806 209059 104387 209059 104377 209060 104387 209060 104378 209060 104378 209061 104387 209061 104388 209061 104378 209062 104388 209062 104380 209062 104380 209063 104388 209063 100804 209063 104380 209064 100804 209064 104381 209064 104381 209065 100804 209065 100803 209065 104381 209066 100803 209066 98217 209066 98217 209067 100803 209067 99892 209067 98217 209068 99892 209068 98219 209068 98219 209069 99892 209069 104389 209069 98219 209070 104389 209070 98221 209070 98221 209071 104389 209071 104390 209071 98221 209072 104390 209072 104391 209072 104391 209073 104390 209073 104382 209073 104392 209074 104397 209074 104393 209074 104396 209075 104397 209075 104392 209075 104395 209076 104396 209076 104392 209076 104392 209077 104400 209077 104401 209077 104394 209078 104400 209078 104392 209078 104393 209079 104394 209079 104392 209079 104395 209080 104406 209080 104396 209080 104396 209081 104406 209081 104398 209081 104396 209082 104398 209082 104397 209082 104397 209083 104398 209083 104408 209083 104397 209084 104408 209084 104393 209084 104393 209085 104408 209085 104409 209085 104393 209086 104409 209086 104394 209086 104394 209087 104409 209087 104399 209087 104394 209088 104399 209088 104400 209088 104400 209089 104399 209089 104402 209089 104400 209090 104402 209090 104401 209090 104401 209091 104402 209091 104411 209091 98210 209092 104403 209092 98212 209092 98212 209093 104403 209093 104404 209093 98212 209094 104404 209094 98213 209094 98213 209095 104404 209095 104405 209095 98213 209096 104405 209096 104406 209096 104406 209097 104405 209097 100789 209097 104406 209098 100789 209098 104398 209098 104398 209099 100789 209099 104407 209099 104398 209100 104407 209100 104408 209100 104408 209101 104407 209101 104410 209101 104408 209102 104410 209102 104409 209102 104409 209103 104410 209103 100788 209103 104409 209104 100788 209104 104399 209104 104399 209105 100788 209105 100787 209105 104399 209106 100787 209106 104402 209106 104402 209107 100787 209107 100786 209107 104402 209108 100786 209108 104411 209108 104411 209109 100786 209109 104412 209109 104411 209110 104412 209110 104413 209110 104413 209111 104412 209111 99909 209111 104413 209112 99909 209112 104414 209112 104414 209113 99909 209113 99908 209113 104414 209114 99908 209114 98210 209114 98210 209115 99908 209115 104403 209115 98207 209116 104417 209116 104418 209116 104415 209117 104417 209117 98207 209117 98202 209118 104415 209118 98207 209118 98207 209119 104421 209119 104424 209119 104419 209120 104421 209120 98207 209120 104418 209121 104419 209121 98207 209121 98202 209122 104416 209122 104415 209122 104415 209123 104416 209123 104434 209123 104415 209124 104434 209124 104417 209124 104417 209125 104434 209125 104436 209125 104417 209126 104436 209126 104418 209126 104418 209127 104436 209127 104420 209127 104418 209128 104420 209128 104419 209128 104419 209129 104420 209129 104422 209129 104419 209130 104422 209130 104421 209130 104421 209131 104422 209131 104423 209131 104421 209132 104423 209132 104424 209132 104424 209133 104423 209133 98197 209133 104439 209134 104425 209134 98198 209134 98198 209135 104425 209135 104427 209135 98198 209136 104427 209136 104426 209136 104426 209137 104427 209137 104428 209137 104426 209138 104428 209138 98199 209138 98199 209139 104428 209139 104429 209139 98199 209140 104429 209140 98201 209140 98201 209141 104429 209141 104430 209141 98201 209142 104430 209142 104431 209142 104431 209143 104430 209143 104432 209143 104431 209144 104432 209144 104416 209144 104416 209145 104432 209145 104433 209145 104416 209146 104433 209146 104434 209146 104434 209147 104433 209147 104435 209147 104434 209148 104435 209148 104436 209148 104436 209149 104435 209149 104437 209149 104436 209150 104437 209150 104420 209150 104420 209151 104437 209151 104438 209151 104420 209152 104438 209152 104422 209152 104422 209153 104438 209153 100770 209153 104422 209154 100770 209154 104423 209154 104423 209155 100770 209155 100767 209155 104423 209156 100767 209156 98197 209156 98197 209157 100767 209157 104440 209157 98197 209158 104440 209158 104439 209158 104439 209159 104440 209159 104425 209159 104444 209160 104443 209160 104441 209160 104442 209161 104443 209161 104444 209161 98196 209162 104442 209162 104444 209162 104444 209163 104445 209163 104450 209163 104448 209164 104445 209164 104444 209164 104441 209165 104448 209165 104444 209165 98196 209166 104456 209166 104442 209166 104442 209167 104456 209167 104446 209167 104442 209168 104446 209168 104443 209168 104443 209169 104446 209169 104447 209169 104443 209170 104447 209170 104441 209170 104441 209171 104447 209171 104457 209171 104441 209172 104457 209172 104448 209172 104448 209173 104457 209173 104458 209173 104448 209174 104458 209174 104445 209174 104445 209175 104458 209175 104449 209175 104445 209176 104449 209176 104450 209176 104450 209177 104449 209177 104461 209177 104462 209178 104463 209178 98191 209178 98191 209179 104463 209179 104451 209179 98191 209180 104451 209180 104453 209180 104453 209181 104451 209181 104452 209181 104453 209182 104452 209182 98194 209182 98194 209183 104452 209183 104455 209183 98194 209184 104455 209184 104454 209184 104454 209185 104455 209185 99940 209185 104454 209186 99940 209186 104456 209186 104456 209187 99940 209187 100754 209187 104456 209188 100754 209188 104446 209188 104446 209189 100754 209189 100753 209189 104446 209190 100753 209190 104447 209190 104447 209191 100753 209191 100751 209191 104447 209192 100751 209192 104457 209192 104457 209193 100751 209193 100749 209193 104457 209194 100749 209194 104458 209194 104458 209195 100749 209195 104459 209195 104458 209196 104459 209196 104449 209196 104449 209197 104459 209197 100747 209197 104449 209198 100747 209198 104461 209198 104461 209199 100747 209199 104460 209199 104461 209200 104460 209200 104462 209200 104462 209201 104460 209201 104463 209201 104464 209202 104471 209202 104473 209202 104469 209203 104471 209203 104464 209203 98188 209204 104469 209204 104464 209204 104464 209205 104466 209205 104465 209205 104467 209206 104466 209206 104464 209206 104473 209207 104467 209207 104464 209207 98188 209208 104468 209208 104469 209208 104469 209209 104468 209209 104470 209209 104469 209210 104470 209210 104471 209210 104471 209211 104470 209211 104472 209211 104471 209212 104472 209212 104473 209212 104473 209213 104472 209213 104474 209213 104473 209214 104474 209214 104467 209214 104467 209215 104474 209215 104475 209215 104467 209216 104475 209216 104466 209216 104466 209217 104475 209217 104484 209217 104466 209218 104484 209218 104465 209218 104465 209219 104484 209219 104486 209219 104487 209220 104477 209220 104476 209220 104476 209221 104477 209221 104478 209221 104476 209222 104478 209222 98183 209222 98183 209223 104478 209223 99961 209223 98183 209224 99961 209224 98185 209224 98185 209225 99961 209225 104479 209225 98185 209226 104479 209226 104480 209226 104480 209227 104479 209227 99959 209227 104480 209228 99959 209228 104468 209228 104468 209229 99959 209229 100730 209229 104468 209230 100730 209230 104470 209230 104470 209231 100730 209231 104481 209231 104470 209232 104481 209232 104472 209232 104472 209233 104481 209233 104482 209233 104472 209234 104482 209234 104474 209234 104474 209235 104482 209235 100729 209235 104474 209236 100729 209236 104475 209236 104475 209237 100729 209237 104483 209237 104475 209238 104483 209238 104484 209238 104484 209239 104483 209239 104485 209239 104484 209240 104485 209240 104486 209240 104486 209241 104485 209241 100728 209241 104486 209242 100728 209242 104487 209242 104487 209243 100728 209243 104477 209243 104492 209244 98177 209244 104488 209244 104492 209245 104489 209245 104493 209245 104490 209246 104489 209246 104492 209246 104488 209247 104490 209247 104492 209247 104492 209248 104491 209248 104500 209248 104498 209249 104491 209249 104492 209249 104493 209250 104498 209250 104492 209250 98177 209251 104509 209251 104488 209251 104488 209252 104509 209252 104494 209252 104488 209253 104494 209253 104490 209253 104490 209254 104494 209254 104495 209254 104490 209255 104495 209255 104489 209255 104489 209256 104495 209256 104496 209256 104489 209257 104496 209257 104493 209257 104493 209258 104496 209258 104497 209258 104493 209259 104497 209259 104498 209259 104498 209260 104497 209260 104502 209260 104498 209261 104502 209261 104491 209261 104491 209262 104502 209262 104499 209262 104491 209263 104499 209263 104500 209263 104500 209264 104499 209264 98171 209264 104496 209265 104512 209265 104497 209265 104497 209266 104512 209266 104501 209266 104497 209267 104501 209267 104502 209267 104502 209268 104501 209268 100709 209268 104502 209269 100709 209269 104499 209269 104499 209270 100709 209270 100708 209270 104499 209271 100708 209271 98171 209271 98171 209272 100708 209272 99978 209272 98171 209273 99978 209273 98172 209273 98172 209274 99978 209274 104503 209274 98172 209275 104503 209275 104504 209275 104504 209276 104503 209276 104505 209276 104504 209277 104505 209277 104506 209277 104506 209278 104505 209278 99976 209278 104506 209279 99976 209279 98175 209279 98175 209280 99976 209280 104507 209280 98175 209281 104507 209281 98178 209281 98178 209282 104507 209282 104508 209282 98178 209283 104508 209283 104509 209283 104509 209284 104508 209284 104510 209284 104509 209285 104510 209285 104494 209285 104494 209286 104510 209286 100710 209286 104494 209287 100710 209287 104495 209287 104495 209288 100710 209288 104511 209288 104495 209289 104511 209289 104496 209289 104496 209290 104511 209290 104512 209290 104515 209291 104513 209291 104516 209291 104519 209292 104513 209292 104515 209292 98168 209293 104519 209293 104515 209293 104515 209294 104514 209294 98167 209294 104521 209295 104514 209295 104515 209295 104516 209296 104521 209296 104515 209296 98168 209297 104517 209297 104519 209297 104519 209298 104517 209298 104518 209298 104519 209299 104518 209299 104513 209299 104513 209300 104518 209300 104530 209300 104513 209301 104530 209301 104516 209301 104516 209302 104530 209302 104520 209302 104516 209303 104520 209303 104521 209303 104521 209304 104520 209304 104522 209304 104521 209305 104522 209305 104514 209305 104514 209306 104522 209306 104532 209306 104514 209307 104532 209307 98167 209307 98167 209308 104532 209308 98161 209308 98163 209309 104523 209309 98164 209309 98164 209310 104523 209310 104524 209310 98164 209311 104524 209311 104525 209311 104525 209312 104524 209312 104527 209312 104525 209313 104527 209313 104526 209313 104526 209314 104527 209314 99994 209314 104526 209315 99994 209315 104528 209315 104528 209316 99994 209316 99991 209316 104528 209317 99991 209317 104517 209317 104517 209318 99991 209318 104529 209318 104517 209319 104529 209319 104518 209319 104518 209320 104529 209320 100688 209320 104518 209321 100688 209321 104530 209321 104530 209322 100688 209322 104531 209322 104530 209323 104531 209323 104520 209323 104520 209324 104531 209324 100685 209324 104520 209325 100685 209325 104522 209325 104522 209326 100685 209326 104533 209326 104522 209327 104533 209327 104532 209327 104532 209328 104533 209328 104534 209328 104532 209329 104534 209329 98161 209329 98161 209330 104534 209330 104535 209330 98161 209331 104535 209331 98163 209331 98163 209332 104535 209332 104523 209332 104536 209333 100664 209333 104551 209333 104551 209334 100664 209334 100662 209334 104551 209335 100662 209335 104553 209335 104553 209336 100662 209336 100660 209336 104553 209337 100660 209337 104537 209337 104537 209338 100660 209338 100659 209338 104537 209339 100659 209339 98153 209339 98153 209340 100659 209340 100658 209340 98153 209341 100658 209341 98155 209341 98155 209342 100658 209342 100010 209342 98155 209343 100010 209343 104538 209343 104538 209344 100010 209344 104539 209344 104538 209345 104539 209345 104540 209345 104540 209346 104539 209346 104541 209346 104540 209347 104541 209347 104542 209347 104542 209348 104541 209348 104543 209348 104542 209349 104543 209349 98160 209349 98160 209350 104543 209350 104544 209350 98160 209351 104544 209351 104545 209351 104545 209352 104544 209352 100667 209352 104545 209353 100667 209353 104548 209353 104548 209354 100667 209354 104546 209354 104548 209355 104546 209355 104549 209355 104549 209356 104546 209356 104547 209356 104549 209357 104547 209357 104536 209357 104536 209358 104547 209358 100664 209358 98159 209359 104545 209359 104555 209359 104555 209360 104545 209360 104548 209360 104555 209361 104548 209361 104556 209361 104556 209362 104548 209362 104549 209362 104556 209363 104549 209363 104554 209363 104554 209364 104549 209364 104536 209364 104554 209365 104536 209365 104550 209365 104550 209366 104536 209366 104551 209366 104550 209367 104551 209367 104552 209367 104552 209368 104551 209368 104553 209368 104552 209369 104553 209369 104558 209369 104558 209370 104553 209370 104537 209370 104558 209371 104537 209371 98151 209371 98151 209372 104537 209372 98153 209372 104557 209373 98159 209373 104555 209373 104557 209374 104554 209374 104550 209374 104556 209375 104554 209375 104557 209375 104555 209376 104556 209376 104557 209376 104557 209377 104558 209377 98151 209377 104552 209378 104558 209378 104557 209378 104550 209379 104552 209379 104557 209379 105172 209380 105204 209380 105171 209380 105171 209381 105204 209381 105205 209381 105171 209382 105205 209382 105169 209382 105169 209383 105205 209383 104559 209383 105169 209384 104559 209384 104560 209384 104560 209385 104559 209385 105173 209385 104560 209386 105173 209386 104561 209386 104561 209387 105173 209387 105174 209387 104561 209388 105174 209388 104562 209388 104562 209389 105174 209389 105176 209389 104562 209390 105176 209390 105168 209390 105168 209391 105176 209391 104563 209391 105168 209392 104563 209392 105167 209392 105167 209393 104563 209393 104565 209393 105167 209394 104565 209394 104564 209394 104564 209395 104565 209395 105178 209395 104564 209396 105178 209396 105165 209396 105165 209397 105178 209397 104566 209397 105165 209398 104566 209398 105164 209398 105164 209399 104566 209399 104567 209399 105164 209400 104567 209400 105163 209400 105163 209401 104567 209401 104568 209401 105163 209402 104568 209402 104569 209402 104569 209403 104568 209403 105181 209403 104569 209404 105181 209404 105161 209404 105161 209405 105181 209405 105183 209405 105161 209406 105183 209406 104570 209406 104570 209407 105183 209407 104571 209407 104570 209408 104571 209408 105160 209408 105160 209409 104571 209409 105185 209409 105160 209410 105185 209410 104572 209410 104572 209411 105185 209411 105186 209411 104572 209412 105186 209412 105784 209412 105784 209413 105186 209413 105187 209413 105749 209414 106332 209414 104573 209414 104573 209415 106332 209415 104575 209415 104573 209416 104575 209416 104574 209416 104574 209417 104575 209417 104576 209417 104574 209418 104576 209418 104577 209418 104577 209419 104576 209419 105241 209419 104577 209420 105241 209420 105224 209420 105224 209421 105241 209421 105242 209421 105224 209422 105242 209422 104578 209422 104578 209423 105242 209423 104579 209423 104578 209424 104579 209424 105221 209424 105221 209425 104579 209425 105245 209425 105221 209426 105245 209426 105220 209426 105220 209427 105245 209427 105246 209427 105220 209428 105246 209428 105219 209428 105219 209429 105246 209429 105247 209429 105219 209430 105247 209430 105217 209430 105217 209431 105247 209431 105249 209431 105217 209432 105249 209432 105215 209432 105215 209433 105249 209433 104580 209433 105215 209434 104580 209434 105214 209434 105214 209435 104580 209435 104581 209435 105214 209436 104581 209436 105213 209436 105213 209437 104581 209437 105250 209437 105213 209438 105250 209438 104582 209438 104582 209439 105250 209439 105251 209439 104582 209440 105251 209440 105211 209440 105211 209441 105251 209441 104583 209441 105211 209442 104583 209442 105209 209442 105209 209443 104583 209443 105253 209443 105209 209444 105253 209444 104584 209444 104584 209445 105253 209445 105254 209445 104584 209446 105254 209446 106320 209446 106320 209447 105254 209447 105256 209447 104585 209448 105748 209448 104586 209448 104585 209449 104586 209449 104587 209449 104587 209450 104586 209450 104588 209450 104587 209451 104588 209451 105259 209451 105259 209452 104588 209452 104590 209452 105259 209453 104590 209453 104589 209453 104589 209454 104590 209454 105264 209454 104589 209455 105264 209455 104591 209455 104591 209456 105264 209456 105265 209456 104591 209457 105265 209457 104592 209457 104592 209458 105265 209458 105267 209458 104592 209459 105267 209459 105228 209459 105228 209460 105267 209460 104594 209460 105228 209461 104594 209461 104593 209461 104593 209462 104594 209462 104595 209462 104593 209463 104595 209463 104596 209463 104596 209464 104595 209464 105270 209464 104596 209465 105270 209465 104597 209465 104597 209466 105270 209466 105271 209466 104597 209467 105271 209467 105233 209467 105233 209468 105271 209468 104598 209468 105233 209469 104598 209469 104599 209469 104599 209470 104598 209470 105273 209470 104599 209471 105273 209471 104600 209471 104600 209472 105273 209472 104601 209472 104600 209473 104601 209473 104602 209473 104602 209474 104601 209474 105275 209474 104602 209475 105275 209475 105235 209475 105235 209476 105275 209476 104603 209476 105235 209477 104603 209477 105237 209477 105237 209478 104603 209478 105279 209478 105237 209479 105279 209479 104604 209479 104604 209480 105279 209480 104605 209480 104604 209481 104605 209481 105238 209481 105238 209482 104605 209482 105280 209482 105238 209483 105280 209483 105239 209483 105102 209484 106299 209484 105104 209484 105102 209485 105104 209485 105070 209485 105070 209486 105104 209486 104606 209486 105070 209487 104606 209487 105072 209487 105072 209488 104606 209488 104607 209488 105072 209489 104607 209489 104608 209489 104608 209490 104607 209490 104609 209490 104608 209491 104609 209491 105074 209491 105074 209492 104609 209492 105108 209492 105074 209493 105108 209493 105075 209493 105075 209494 105108 209494 105110 209494 105075 209495 105110 209495 105076 209495 105076 209496 105110 209496 105111 209496 105076 209497 105111 209497 105078 209497 105078 209498 105111 209498 105112 209498 105078 209499 105112 209499 104610 209499 104610 209500 105112 209500 104611 209500 104610 209501 104611 209501 104612 209501 104612 209502 104611 209502 105114 209502 104612 209503 105114 209503 105080 209503 105080 209504 105114 209504 105116 209504 105080 209505 105116 209505 105082 209505 105082 209506 105116 209506 104613 209506 105082 209507 104613 209507 104614 209507 104614 209508 104613 209508 104615 209508 104614 209509 104615 209509 104616 209509 104616 209510 104615 209510 104617 209510 104616 209511 104617 209511 104618 209511 104618 209512 104617 209512 104619 209512 104618 209513 104619 209513 104620 209513 104620 209514 104619 209514 105121 209514 104620 209515 105121 209515 104621 209515 104621 209516 105121 209516 106283 209516 104621 209517 106283 209517 105087 209517 104622 209518 105086 209518 105068 209518 105068 209519 105086 209519 104624 209519 105068 209520 104624 209520 104623 209520 104623 209521 104624 209521 105089 209521 104623 209522 105089 209522 104625 209522 104625 209523 105089 209523 104626 209523 104625 209524 104626 209524 104627 209524 104627 209525 104626 209525 105090 209525 104627 209526 105090 209526 104628 209526 104628 209527 105090 209527 105091 209527 104628 209528 105091 209528 104629 209528 104629 209529 105091 209529 104630 209529 104629 209530 104630 209530 104632 209530 104632 209531 104630 209531 104631 209531 104632 209532 104631 209532 104634 209532 104634 209533 104631 209533 104633 209533 104634 209534 104633 209534 104635 209534 104635 209535 104633 209535 104636 209535 104635 209536 104636 209536 104637 209536 104637 209537 104636 209537 104638 209537 104637 209538 104638 209538 105062 209538 105062 209539 104638 209539 105094 209539 105062 209540 105094 209540 105059 209540 105059 209541 105094 209541 104639 209541 105059 209542 104639 209542 105058 209542 105058 209543 104639 209543 104641 209543 105058 209544 104641 209544 104640 209544 104640 209545 104641 209545 104642 209545 104640 209546 104642 209546 104643 209546 104643 209547 104642 209547 105097 209547 104643 209548 105097 209548 105055 209548 105055 209549 105097 209549 105098 209549 105055 209550 105098 209550 105054 209550 105054 209551 105098 209551 105099 209551 105300 209552 104644 209552 104645 209552 105300 209553 104645 209553 105301 209553 105301 209554 104645 209554 104646 209554 105301 209555 104646 209555 105302 209555 105302 209556 104646 209556 104647 209556 105302 209557 104647 209557 105303 209557 105303 209558 104647 209558 104648 209558 105303 209559 104648 209559 104649 209559 104649 209560 104648 209560 105314 209560 104649 209561 105314 209561 104650 209561 104650 209562 105314 209562 104651 209562 104650 209563 104651 209563 105305 209563 105305 209564 104651 209564 105315 209564 105305 209565 105315 209565 104652 209565 104652 209566 105315 209566 105316 209566 104652 209567 105316 209567 105307 209567 105307 209568 105316 209568 105317 209568 105307 209569 105317 209569 105309 209569 105309 209570 105317 209570 104653 209570 105309 209571 104653 209571 104654 209571 104654 209572 104653 209572 104656 209572 104654 209573 104656 209573 104655 209573 104655 209574 104656 209574 104657 209574 104655 209575 104657 209575 105281 209575 105281 209576 104657 209576 104658 209576 105281 209577 104658 209577 105282 209577 105282 209578 104658 209578 105321 209578 105282 209579 105321 209579 105283 209579 105283 209580 105321 209580 104660 209580 105283 209581 104660 209581 104659 209581 104659 209582 104660 209582 105324 209582 104659 209583 105324 209583 104661 209583 104661 209584 105324 209584 105325 209584 104661 209585 105325 209585 104662 209585 104662 209586 105325 209586 104663 209586 104662 209587 104663 209587 106249 209587 104839 209588 105582 209588 104838 209588 104838 209589 105582 209589 104664 209589 104838 209590 104664 209590 104837 209590 104837 209591 104664 209591 105581 209591 104837 209592 105581 209592 104665 209592 104665 209593 105581 209593 105580 209593 104665 209594 105580 209594 104836 209594 104836 209595 105580 209595 104666 209595 104836 209596 104666 209596 104834 209596 104834 209597 104666 209597 104668 209597 104834 209598 104668 209598 104667 209598 104667 209599 104668 209599 106240 209599 104669 209600 105575 209600 104832 209600 104832 209601 105575 209601 104671 209601 104832 209602 104671 209602 104670 209602 104670 209603 104671 209603 105574 209603 104670 209604 105574 209604 104831 209604 104831 209605 105574 209605 105590 209605 104831 209606 105590 209606 104829 209606 104829 209607 105590 209607 105506 209607 104829 209608 105506 209608 104828 209608 104828 209609 105506 209609 104672 209609 104828 209610 104672 209610 106056 209610 106056 209611 104672 209611 104673 209611 104674 209612 104676 209612 104675 209612 104675 209613 104676 209613 105509 209613 104675 209614 105509 209614 104827 209614 104827 209615 105509 209615 104677 209615 104827 209616 104677 209616 104825 209616 104825 209617 104677 209617 104679 209617 104825 209618 104679 209618 104678 209618 104678 209619 104679 209619 104680 209619 104678 209620 104680 209620 104681 209620 104681 209621 104680 209621 104682 209621 104681 209622 104682 209622 106061 209622 106061 209623 104682 209623 104683 209623 104897 209624 105443 209624 104684 209624 104684 209625 105443 209625 105442 209625 104684 209626 105442 209626 104895 209626 104895 209627 105442 209627 105441 209627 104895 209628 105441 209628 104685 209628 104685 209629 105441 209629 105451 209629 104685 209630 105451 209630 104891 209630 104891 209631 105451 209631 105450 209631 104891 209632 105450 209632 104890 209632 104890 209633 105450 209633 104686 209633 104890 209634 104686 209634 106222 209634 106222 209635 104686 209635 105449 209635 104887 209636 105572 209636 104885 209636 104885 209637 105572 209637 104687 209637 104885 209638 104687 209638 104688 209638 104688 209639 104687 209639 105654 209639 104688 209640 105654 209640 104883 209640 104883 209641 105654 209641 104689 209641 104883 209642 104689 209642 104882 209642 104882 209643 104689 209643 104690 209643 104882 209644 104690 209644 104691 209644 104691 209645 104690 209645 105463 209645 104691 209646 105463 209646 106217 209646 106217 209647 105463 209647 105462 209647 105997 209648 104692 209648 104880 209648 104880 209649 104692 209649 105470 209649 104880 209650 105470 209650 104879 209650 104879 209651 105470 209651 104693 209651 104879 209652 104693 209652 104694 209652 104694 209653 104693 209653 105468 209653 104694 209654 105468 209654 104877 209654 104877 209655 105468 209655 104695 209655 104877 209656 104695 209656 104876 209656 104876 209657 104695 209657 104696 209657 104876 209658 104696 209658 106004 209658 106004 209659 104696 209659 104697 209659 106005 209660 105471 209660 104874 209660 104874 209661 105471 209661 105655 209661 104874 209662 105655 209662 104698 209662 104698 209663 105655 209663 105482 209663 104698 209664 105482 209664 104871 209664 104871 209665 105482 209665 104699 209665 104871 209666 104699 209666 104870 209666 104870 209667 104699 209667 104700 209667 104870 209668 104700 209668 104701 209668 104701 209669 104700 209669 104702 209669 104701 209670 104702 209670 106207 209670 106207 209671 104702 209671 105478 209671 104869 209672 106206 209672 104868 209672 104868 209673 106206 209673 104703 209673 104868 209674 104703 209674 104867 209674 104867 209675 104703 209675 105560 209675 104867 209676 105560 209676 104704 209676 104704 209677 105560 209677 105661 209677 104704 209678 105661 209678 104866 209678 104866 209679 105661 209679 105659 209679 104866 209680 105659 209680 104864 209680 104864 209681 105659 209681 105566 209681 104864 209682 105566 209682 104705 209682 104705 209683 105566 209683 104706 209683 104707 209684 105489 209684 104708 209684 104708 209685 105489 209685 105488 209685 104708 209686 105488 209686 104861 209686 104861 209687 105488 209687 104709 209687 104861 209688 104709 209688 104860 209688 104860 209689 104709 209689 105555 209689 104860 209690 105555 209690 104858 209690 104858 209691 105555 209691 104710 209691 104858 209692 104710 209692 104711 209692 104711 209693 104710 209693 105553 209693 104711 209694 105553 209694 104712 209694 104712 209695 105553 209695 104713 209695 106192 209696 105547 209696 104856 209696 104856 209697 105547 209697 105546 209697 104856 209698 105546 209698 104855 209698 104855 209699 105546 209699 105544 209699 104855 209700 105544 209700 104714 209700 104714 209701 105544 209701 104715 209701 104714 209702 104715 209702 104717 209702 104717 209703 104715 209703 104716 209703 104717 209704 104716 209704 104854 209704 104854 209705 104716 209705 105631 209705 104854 209706 105631 209706 104718 209706 104718 209707 105631 209707 105548 209707 106031 209708 105540 209708 104853 209708 104853 209709 105540 209709 104719 209709 104853 209710 104719 209710 104852 209710 104852 209711 104719 209711 104721 209711 104852 209712 104721 209712 104720 209712 104720 209713 104721 209713 105539 209713 104720 209714 105539 209714 104850 209714 104850 209715 105539 209715 105538 209715 104850 209716 105538 209716 104848 209716 104848 209717 105538 209717 105536 209717 104848 209718 105536 209718 104722 209718 104722 209719 105536 209719 106180 209719 104846 209720 104723 209720 104844 209720 104844 209721 104723 209721 105515 209721 104844 209722 105515 209722 104842 209722 104842 209723 105515 209723 104724 209723 104842 209724 104724 209724 104725 209724 104725 209725 104724 209725 105525 209725 104725 209726 105525 209726 104840 209726 104840 209727 105525 209727 105526 209727 104840 209728 105526 209728 104726 209728 104726 209729 105526 209729 105531 209729 104726 209730 105531 209730 106043 209730 106043 209731 105531 209731 105532 209731 106176 209732 106513 209732 104727 209732 104727 209733 106513 209733 106516 209733 104727 209734 106516 209734 104878 209734 104878 209735 106516 209735 106386 209735 104878 209736 106386 209736 104728 209736 104728 209737 106386 209737 104729 209737 104728 209738 104729 209738 104730 209738 104730 209739 104729 209739 106383 209739 104730 209740 106383 209740 104731 209740 104731 209741 106383 209741 104732 209741 104731 209742 104732 209742 106170 209742 106170 209743 104732 209743 106381 209743 105996 209744 104733 209744 104881 209744 104881 209745 104733 209745 104734 209745 104881 209746 104734 209746 104884 209746 104884 209747 104734 209747 104736 209747 104884 209748 104736 209748 104735 209748 104735 209749 104736 209749 104737 209749 104735 209750 104737 209750 104886 209750 104886 209751 104737 209751 106494 209751 104886 209752 106494 209752 104888 209752 104888 209753 106494 209753 106492 209753 104888 209754 106492 209754 105990 209754 105990 209755 106492 209755 106165 209755 104889 209756 106164 209756 104892 209756 104892 209757 106164 209757 106398 209757 104892 209758 106398 209758 104893 209758 104893 209759 106398 209759 104738 209759 104893 209760 104738 209760 104894 209760 104894 209761 104738 209761 104739 209761 104894 209762 104739 209762 104896 209762 104896 209763 104739 209763 104740 209763 104896 209764 104740 209764 104898 209764 104898 209765 104740 209765 106527 209765 104898 209766 106527 209766 104741 209766 104741 209767 106527 209767 106392 209767 106158 209768 106159 209768 104742 209768 104742 209769 106159 209769 106406 209769 104742 209770 106406 209770 104743 209770 104743 209771 106406 209771 104744 209771 104743 209772 104744 209772 104826 209772 104826 209773 104744 209773 106403 209773 104826 209774 106403 209774 104745 209774 104745 209775 106403 209775 104746 209775 104745 209776 104746 209776 104747 209776 104747 209777 104746 209777 106402 209777 104747 209778 106402 209778 106149 209778 106149 209779 106402 209779 106150 209779 106148 209780 104749 209780 104748 209780 104748 209781 104749 209781 104750 209781 104748 209782 104750 209782 104830 209782 104830 209783 104750 209783 106523 209783 104830 209784 106523 209784 104751 209784 104751 209785 106523 209785 106522 209785 104751 209786 106522 209786 104752 209786 104752 209787 106522 209787 106534 209787 104752 209788 106534 209788 104833 209788 104833 209789 106534 209789 106533 209789 104833 209790 106533 209790 106049 209790 106049 209791 106533 209791 106487 209791 106139 209792 104753 209792 104835 209792 104835 209793 104753 209793 104754 209793 104835 209794 104754 209794 104755 209794 104755 209795 104754 209795 104757 209795 104755 209796 104757 209796 104756 209796 104756 209797 104757 209797 106475 209797 104756 209798 106475 209798 104758 209798 104758 209799 106475 209799 104759 209799 104758 209800 104759 209800 104760 209800 104760 209801 104759 209801 104762 209801 104760 209802 104762 209802 104761 209802 104761 209803 104762 209803 106477 209803 106132 209804 104763 209804 104764 209804 104764 209805 104763 209805 106467 209805 104764 209806 106467 209806 104841 209806 104841 209807 106467 209807 106459 209807 104841 209808 106459 209808 104765 209808 104765 209809 106459 209809 106568 209809 104765 209810 106568 209810 104843 209810 104843 209811 106568 209811 104766 209811 104843 209812 104766 209812 104845 209812 104845 209813 104766 209813 106464 209813 104845 209814 106464 209814 104847 209814 104847 209815 106464 209815 106463 209815 106124 209816 106446 209816 104849 209816 104849 209817 106446 209817 104767 209817 104849 209818 104767 209818 104768 209818 104768 209819 104767 209819 106448 209819 104768 209820 106448 209820 104851 209820 104851 209821 106448 209821 104769 209821 104851 209822 104769 209822 104770 209822 104770 209823 104769 209823 104771 209823 104770 209824 104771 209824 104772 209824 104772 209825 104771 209825 106449 209825 104772 209826 106449 209826 106032 209826 106032 209827 106449 209827 106118 209827 106030 209828 104774 209828 104773 209828 104773 209829 104774 209829 104776 209829 104773 209830 104776 209830 104775 209830 104775 209831 104776 209831 104777 209831 104775 209832 104777 209832 104778 209832 104778 209833 104777 209833 106445 209833 104778 209834 106445 209834 104779 209834 104779 209835 106445 209835 106444 209835 104779 209836 106444 209836 104857 209836 104857 209837 106444 209837 106443 209837 104857 209838 106443 209838 106110 209838 106110 209839 106443 209839 106417 209839 106109 209840 106442 209840 104780 209840 104780 209841 106442 209841 104781 209841 104780 209842 104781 209842 104859 209842 104859 209843 104781 209843 106438 209843 104859 209844 106438 209844 104783 209844 104783 209845 106438 209845 104782 209845 104783 209846 104782 209846 104862 209846 104862 209847 104782 209847 106426 209847 104862 209848 106426 209848 104784 209848 104784 209849 106426 209849 104785 209849 104784 209850 104785 209850 106019 209850 106019 209851 104785 209851 106102 209851 104863 209852 104786 209852 104787 209852 104787 209853 104786 209853 106424 209853 104787 209854 106424 209854 104865 209854 104865 209855 106424 209855 106422 209855 104865 209856 106422 209856 104788 209856 104788 209857 106422 209857 104789 209857 104788 209858 104789 209858 104790 209858 104790 209859 104789 209859 104792 209859 104790 209860 104792 209860 104791 209860 104791 209861 104792 209861 106419 209861 104791 209862 106419 209862 106011 209862 106011 209863 106419 209863 106099 209863 104793 209864 106379 209864 104795 209864 104795 209865 106379 209865 104794 209865 104795 209866 104794 209866 104796 209866 104796 209867 104794 209867 106378 209867 104796 209868 106378 209868 104872 209868 104872 209869 106378 209869 106375 209869 104872 209870 106375 209870 104873 209870 104873 209871 106375 209871 106374 209871 104873 209872 106374 209872 104797 209872 104797 209873 106374 209873 104798 209873 104797 209874 104798 209874 104875 209874 104875 209875 104798 209875 106371 209875 104802 209876 104799 209876 105397 209876 105397 209877 104799 209877 104800 209877 105397 209878 104800 209878 104801 209878 104802 209879 105397 209879 106353 209879 106353 209880 105397 209880 105396 209880 106353 209881 105396 209881 106453 209881 106453 209882 105396 209882 105393 209882 106453 209883 105393 209883 106455 209883 106455 209884 105393 209884 104803 209884 106455 209885 104803 209885 104804 209885 104804 209886 104803 209886 105390 209886 104804 209887 105390 209887 104805 209887 104805 209888 105390 209888 104806 209888 104805 209889 104806 209889 104807 209889 104807 209890 104806 209890 105388 209890 104807 209891 105388 209891 106470 209891 106470 209892 105388 209892 104808 209892 106470 209893 104808 209893 104809 209893 104809 209894 104808 209894 105385 209894 104809 209895 105385 209895 104810 209895 104810 209896 105385 209896 104811 209896 104810 209897 104811 209897 106354 209897 106354 209898 104811 209898 105383 209898 106354 209899 105383 209899 106485 209899 106485 209900 105383 209900 105382 209900 106485 209901 105382 209901 104812 209901 104812 209902 105382 209902 105381 209902 104812 209903 105381 209903 106409 209903 106409 209904 105381 209904 105380 209904 106409 209905 105380 209905 106405 209905 106405 209906 105380 209906 106077 209906 106405 209907 106077 209907 106396 209907 104815 209908 106076 209908 105399 209908 104817 209909 104813 209909 105401 209909 105401 209910 104813 209910 105513 209910 105401 209911 105513 209911 105399 209911 105399 209912 105513 209912 104814 209912 105399 209913 104814 209913 104815 209913 105402 209914 105502 209914 105403 209914 105403 209915 105502 209915 104816 209915 104816 209916 105637 209916 105403 209916 105403 209917 105637 209917 105579 209917 105403 209918 105579 209918 104817 209918 104817 209919 105579 209919 105435 209919 104817 209920 105435 209920 104813 209920 105497 209921 105402 209921 105408 209921 105497 209922 105505 209922 105402 209922 105402 209923 105505 209923 105503 209923 105402 209924 105503 209924 105502 209924 105495 209925 104818 209925 105419 209925 105419 209926 104818 209926 105438 209926 105419 209927 105438 209927 105417 209927 105417 209928 105438 209928 105518 209928 105417 209929 105518 209929 104819 209929 104819 209930 105518 209930 105516 209930 104819 209931 105516 209931 105413 209931 105413 209932 105516 209932 104820 209932 105413 209933 104820 209933 105412 209933 105412 209934 104820 209934 104821 209934 105412 209935 104821 209935 105408 209935 105408 209936 104821 209936 105436 209936 105408 209937 105436 209937 105497 209937 105420 209938 105494 209938 105534 209938 105420 209939 105534 209939 105419 209939 105419 209940 105534 209940 105533 209940 105419 209941 105533 209941 105495 209941 105494 209942 105420 209942 105439 209942 105439 209943 105420 209943 105422 209943 105439 209944 105422 209944 104822 209944 104822 209945 105422 209945 104823 209945 104823 209946 105422 209946 105426 209946 104823 209947 105426 209947 104824 209947 104824 209948 105426 209948 105424 209948 104824 209949 105424 209949 105493 209949 106061 209950 106158 209950 104681 209950 104681 209951 106158 209951 104742 209951 104681 209952 104742 209952 104678 209952 104678 209953 104742 209953 104743 209953 104678 209954 104743 209954 104825 209954 104825 209955 104743 209955 104826 209955 104825 209956 104826 209956 104827 209956 104827 209957 104826 209957 104745 209957 104827 209958 104745 209958 104675 209958 104675 209959 104745 209959 104747 209959 104675 209960 104747 209960 104674 209960 104674 209961 104747 209961 106149 209961 106056 209962 106148 209962 104828 209962 104828 209963 106148 209963 104748 209963 104828 209964 104748 209964 104829 209964 104829 209965 104748 209965 104830 209965 104829 209966 104830 209966 104831 209966 104831 209967 104830 209967 104751 209967 104831 209968 104751 209968 104670 209968 104670 209969 104751 209969 104752 209969 104670 209970 104752 209970 104832 209970 104832 209971 104752 209971 104833 209971 104832 209972 104833 209972 104669 209972 104669 209973 104833 209973 106049 209973 104667 209974 106139 209974 104834 209974 104834 209975 106139 209975 104835 209975 104834 209976 104835 209976 104836 209976 104836 209977 104835 209977 104755 209977 104836 209978 104755 209978 104665 209978 104665 209979 104755 209979 104756 209979 104665 209980 104756 209980 104837 209980 104837 209981 104756 209981 104758 209981 104837 209982 104758 209982 104838 209982 104838 209983 104758 209983 104760 209983 104838 209984 104760 209984 104839 209984 104839 209985 104760 209985 104761 209985 106043 209986 106132 209986 104726 209986 104726 209987 106132 209987 104764 209987 104726 209988 104764 209988 104840 209988 104840 209989 104764 209989 104841 209989 104840 209990 104841 209990 104725 209990 104725 209991 104841 209991 104765 209991 104725 209992 104765 209992 104842 209992 104842 209993 104765 209993 104843 209993 104842 209994 104843 209994 104844 209994 104844 209995 104843 209995 104845 209995 104844 209996 104845 209996 104846 209996 104846 209997 104845 209997 104847 209997 104722 209998 106124 209998 104848 209998 104848 209999 106124 209999 104849 209999 104848 210000 104849 210000 104850 210000 104850 210001 104849 210001 104768 210001 104850 210002 104768 210002 104720 210002 104720 210003 104768 210003 104851 210003 104720 210004 104851 210004 104852 210004 104852 210005 104851 210005 104770 210005 104852 210006 104770 210006 104853 210006 104853 210007 104770 210007 104772 210007 104853 210008 104772 210008 106031 210008 106031 210009 104772 210009 106032 210009 104718 210010 106030 210010 104854 210010 104854 210011 106030 210011 104773 210011 104854 210012 104773 210012 104717 210012 104717 210013 104773 210013 104775 210013 104717 210014 104775 210014 104714 210014 104714 210015 104775 210015 104778 210015 104714 210016 104778 210016 104855 210016 104855 210017 104778 210017 104779 210017 104855 210018 104779 210018 104856 210018 104856 210019 104779 210019 104857 210019 104856 210020 104857 210020 106192 210020 106192 210021 104857 210021 106110 210021 104712 210022 106109 210022 104711 210022 104711 210023 106109 210023 104780 210023 104711 210024 104780 210024 104858 210024 104858 210025 104780 210025 104859 210025 104858 210026 104859 210026 104860 210026 104860 210027 104859 210027 104783 210027 104860 210028 104783 210028 104861 210028 104861 210029 104783 210029 104862 210029 104861 210030 104862 210030 104708 210030 104708 210031 104862 210031 104784 210031 104708 210032 104784 210032 104707 210032 104707 210033 104784 210033 106019 210033 104705 210034 104863 210034 104864 210034 104864 210035 104863 210035 104787 210035 104864 210036 104787 210036 104866 210036 104866 210037 104787 210037 104865 210037 104866 210038 104865 210038 104704 210038 104704 210039 104865 210039 104788 210039 104704 210040 104788 210040 104867 210040 104867 210041 104788 210041 104790 210041 104867 210042 104790 210042 104868 210042 104868 210043 104790 210043 104791 210043 104868 210044 104791 210044 104869 210044 104869 210045 104791 210045 106011 210045 106207 210046 104793 210046 104701 210046 104701 210047 104793 210047 104795 210047 104701 210048 104795 210048 104870 210048 104870 210049 104795 210049 104796 210049 104870 210050 104796 210050 104871 210050 104871 210051 104796 210051 104872 210051 104871 210052 104872 210052 104698 210052 104698 210053 104872 210053 104873 210053 104698 210054 104873 210054 104874 210054 104874 210055 104873 210055 104797 210055 104874 210056 104797 210056 106005 210056 106005 210057 104797 210057 104875 210057 106004 210058 106176 210058 104876 210058 104876 210059 106176 210059 104727 210059 104876 210060 104727 210060 104877 210060 104877 210061 104727 210061 104878 210061 104877 210062 104878 210062 104694 210062 104694 210063 104878 210063 104728 210063 104694 210064 104728 210064 104879 210064 104879 210065 104728 210065 104730 210065 104879 210066 104730 210066 104880 210066 104880 210067 104730 210067 104731 210067 104880 210068 104731 210068 105997 210068 105997 210069 104731 210069 106170 210069 106217 210070 105996 210070 104691 210070 104691 210071 105996 210071 104881 210071 104691 210072 104881 210072 104882 210072 104882 210073 104881 210073 104884 210073 104882 210074 104884 210074 104883 210074 104883 210075 104884 210075 104735 210075 104883 210076 104735 210076 104688 210076 104688 210077 104735 210077 104886 210077 104688 210078 104886 210078 104885 210078 104885 210079 104886 210079 104888 210079 104885 210080 104888 210080 104887 210080 104887 210081 104888 210081 105990 210081 106222 210082 104889 210082 104890 210082 104890 210083 104889 210083 104892 210083 104890 210084 104892 210084 104891 210084 104891 210085 104892 210085 104893 210085 104891 210086 104893 210086 104685 210086 104685 210087 104893 210087 104894 210087 104685 210088 104894 210088 104895 210088 104895 210089 104894 210089 104896 210089 104895 210090 104896 210090 104684 210090 104684 210091 104896 210091 104898 210091 104684 210092 104898 210092 104897 210092 104897 210093 104898 210093 104741 210093 105976 210094 104912 210094 106521 210094 106521 210095 104912 210095 104911 210095 106521 210096 104911 210096 106349 210096 106349 210097 104911 210097 104900 210097 106349 210098 104900 210098 104899 210098 104899 210099 104900 210099 104901 210099 104899 210100 104901 210100 104902 210100 104902 210101 104901 210101 104903 210101 104902 210102 104903 210102 106408 210102 106408 210103 104903 210103 104904 210103 106408 210104 104904 210104 106410 210104 106410 210105 104904 210105 104906 210105 106410 210106 104906 210106 104905 210106 104905 210107 104906 210107 105982 210107 104905 210108 105982 210108 106484 210108 105507 210109 105982 210109 105512 210109 105512 210110 105982 210110 104906 210110 105512 210111 104906 210111 104907 210111 104907 210112 104906 210112 104904 210112 104907 210113 104904 210113 105433 210113 105433 210114 104904 210114 104903 210114 105433 210115 104903 210115 104908 210115 104908 210116 104903 210116 104901 210116 104908 210117 104901 210117 104909 210117 104909 210118 104901 210118 104900 210118 104909 210119 104900 210119 104910 210119 104910 210120 104900 210120 104911 210120 104910 210121 104911 210121 105584 210121 105584 210122 104911 210122 104912 210122 105969 210123 104913 210123 104918 210123 104918 210124 104913 210124 106350 210124 104918 210125 106350 210125 104920 210125 104920 210126 106350 210126 104914 210126 104920 210127 104914 210127 104915 210127 104915 210128 104914 210128 104916 210128 104915 210129 104916 210129 104922 210129 104922 210130 104916 210130 104917 210130 104922 210131 104917 210131 104924 210131 104924 210132 104917 210132 106500 210132 104924 210133 106500 210133 105957 210133 105957 210134 106500 210134 106476 210134 105963 210135 105969 210135 105636 210135 105636 210136 105969 210136 104918 210136 105636 210137 104918 210137 104919 210137 104919 210138 104918 210138 104920 210138 104919 210139 104920 210139 105592 210139 105592 210140 104920 210140 104915 210140 105592 210141 104915 210141 104921 210141 104921 210142 104915 210142 104922 210142 104921 210143 104922 210143 104923 210143 104923 210144 104922 210144 104924 210144 104923 210145 104924 210145 105956 210145 105956 210146 104924 210146 105957 210146 105955 210147 106465 210147 104925 210147 104925 210148 106465 210148 104926 210148 104925 210149 104926 210149 104927 210149 104927 210150 104926 210150 104929 210150 104927 210151 104929 210151 104928 210151 104928 210152 104929 210152 104930 210152 104928 210153 104930 210153 104934 210153 104934 210154 104930 210154 106466 210154 104934 210155 106466 210155 104936 210155 104936 210156 106466 210156 106468 210156 104936 210157 106468 210157 105948 210157 105948 210158 106468 210158 105949 210158 105947 210159 105955 210159 104931 210159 104931 210160 105955 210160 104925 210160 104931 210161 104925 210161 105530 210161 105530 210162 104925 210162 104927 210162 105530 210163 104927 210163 104932 210163 104932 210164 104927 210164 104928 210164 104932 210165 104928 210165 104933 210165 104933 210166 104928 210166 104934 210166 104933 210167 104934 210167 104935 210167 104935 210168 104934 210168 104936 210168 104935 210169 104936 210169 104937 210169 104937 210170 104936 210170 105948 210170 104938 210171 104939 210171 104945 210171 104945 210172 104939 210172 104940 210172 104945 210173 104940 210173 104946 210173 104946 210174 104940 210174 106503 210174 104946 210175 106503 210175 104941 210175 104941 210176 106503 210176 106532 210176 104941 210177 106532 210177 104942 210177 104942 210178 106532 210178 104943 210178 104942 210179 104943 210179 104948 210179 104948 210180 104943 210180 106450 210180 104948 210181 106450 210181 104944 210181 104944 210182 106450 210182 105935 210182 105934 210183 104938 210183 105602 210183 105602 210184 104938 210184 104945 210184 105602 210185 104945 210185 105593 210185 105593 210186 104945 210186 104946 210186 105593 210187 104946 210187 104947 210187 104947 210188 104946 210188 104941 210188 104947 210189 104941 210189 105594 210189 105594 210190 104941 210190 104942 210190 105594 210191 104942 210191 105595 210191 105595 210192 104942 210192 104948 210192 105595 210193 104948 210193 105604 210193 105604 210194 104948 210194 104944 210194 105920 210195 106505 210195 104954 210195 104954 210196 106505 210196 106506 210196 104954 210197 106506 210197 104950 210197 104950 210198 106506 210198 104949 210198 104950 210199 104949 210199 104957 210199 104957 210200 104949 210200 104951 210200 104957 210201 104951 210201 104958 210201 104958 210202 104951 210202 104952 210202 104958 210203 104952 210203 104960 210203 104960 210204 104952 210204 106509 210204 104960 210205 106509 210205 105915 210205 105915 210206 106509 210206 105921 210206 105646 210207 105920 210207 104953 210207 104953 210208 105920 210208 104954 210208 104953 210209 104954 210209 104955 210209 104955 210210 104954 210210 104950 210210 104955 210211 104950 210211 104956 210211 104956 210212 104950 210212 104957 210212 104956 210213 104957 210213 105647 210213 105647 210214 104957 210214 104958 210214 105647 210215 104958 210215 105648 210215 105648 210216 104958 210216 104960 210216 105648 210217 104960 210217 104959 210217 104959 210218 104960 210218 105915 210218 105900 210219 106427 210219 104961 210219 104961 210220 106427 210220 106428 210220 104961 210221 106428 210221 104966 210221 104966 210222 106428 210222 106430 210222 104966 210223 106430 210223 104962 210223 104962 210224 106430 210224 106431 210224 104962 210225 106431 210225 104969 210225 104969 210226 106431 210226 104963 210226 104969 210227 104963 210227 104971 210227 104971 210228 104963 210228 104964 210228 104971 210229 104964 210229 105911 210229 105911 210230 104964 210230 105912 210230 105901 210231 105900 210231 104965 210231 104965 210232 105900 210232 104961 210232 104965 210233 104961 210233 105610 210233 105610 210234 104961 210234 104966 210234 105610 210235 104966 210235 104967 210235 104967 210236 104966 210236 104962 210236 104967 210237 104962 210237 104968 210237 104968 210238 104962 210238 104969 210238 104968 210239 104969 210239 104970 210239 104970 210240 104969 210240 104971 210240 104970 210241 104971 210241 105615 210241 105615 210242 104971 210242 105911 210242 104979 210243 104972 210243 104973 210243 104973 210244 104972 210244 106370 210244 104973 210245 106370 210245 104974 210245 104974 210246 106370 210246 106368 210246 104974 210247 106368 210247 104982 210247 104982 210248 106368 210248 104975 210248 104982 210249 104975 210249 104976 210249 104976 210250 104975 210250 104977 210250 104976 210251 104977 210251 104983 210251 104983 210252 104977 210252 106376 210252 104983 210253 106376 210253 104984 210253 104984 210254 106376 210254 106377 210254 104978 210255 104979 210255 104980 210255 104980 210256 104979 210256 104973 210256 104980 210257 104973 210257 105476 210257 105476 210258 104973 210258 104974 210258 105476 210259 104974 210259 104981 210259 104981 210260 104974 210260 104982 210260 104981 210261 104982 210261 105484 210261 105484 210262 104982 210262 104976 210262 105484 210263 104976 210263 105477 210263 105477 210264 104976 210264 104983 210264 105477 210265 104983 210265 105479 210265 105479 210266 104983 210266 104984 210266 105879 210267 105878 210267 104989 210267 104989 210268 105878 210268 104985 210268 104989 210269 104985 210269 104991 210269 104991 210270 104985 210270 106517 210270 104991 210271 106517 210271 104992 210271 104992 210272 106517 210272 106515 210272 104992 210273 106515 210273 104986 210273 104986 210274 106515 210274 106514 210274 104986 210275 106514 210275 104988 210275 104988 210276 106514 210276 104987 210276 104988 210277 104987 210277 105868 210277 105868 210278 104987 210278 106512 210278 105621 210279 105879 210279 105622 210279 105622 210280 105879 210280 104989 210280 105622 210281 104989 210281 104990 210281 104990 210282 104989 210282 104991 210282 104990 210283 104991 210283 105616 210283 105616 210284 104991 210284 104992 210284 105616 210285 104992 210285 105618 210285 105618 210286 104992 210286 104986 210286 105618 210287 104986 210287 104993 210287 104993 210288 104986 210288 104988 210288 104993 210289 104988 210289 104994 210289 104994 210290 104988 210290 105868 210290 105865 210291 105867 210291 105001 210291 105001 210292 105867 210292 106391 210292 105001 210293 106391 210293 104995 210293 104995 210294 106391 210294 104996 210294 104995 210295 104996 210295 104997 210295 104997 210296 104996 210296 104998 210296 104997 210297 104998 210297 105003 210297 105003 210298 104998 210298 106497 210298 105003 210299 106497 210299 105004 210299 105004 210300 106497 210300 104999 210300 105004 210301 104999 210301 105860 210301 105860 210302 104999 210302 106539 210302 105453 210303 105865 210303 105452 210303 105452 210304 105865 210304 105001 210304 105452 210305 105001 210305 105000 210305 105000 210306 105001 210306 104995 210306 105000 210307 104995 210307 105626 210307 105626 210308 104995 210308 104997 210308 105626 210309 104997 210309 105627 210309 105627 210310 104997 210310 105003 210310 105627 210311 105003 210311 105002 210311 105002 210312 105003 210312 105004 210312 105002 210313 105004 210313 105005 210313 105005 210314 105004 210314 105860 210314 105014 210315 105410 210315 105041 210315 105854 210316 105010 210316 105681 210316 105681 210317 105010 210317 105398 210317 105006 210318 105012 210318 105007 210318 105007 210319 105008 210319 105006 210319 105006 210320 105008 210320 105009 210320 105006 210321 105009 210321 105010 210321 105010 210322 105009 210322 105400 210322 105010 210323 105400 210323 105398 210323 105037 210324 105039 210324 105405 210324 105405 210325 105011 210325 105037 210325 105037 210326 105011 210326 105404 210326 105037 210327 105404 210327 105012 210327 105012 210328 105404 210328 105013 210328 105012 210329 105013 210329 105007 210329 105041 210330 105410 210330 105040 210330 105410 210331 105409 210331 105040 210331 105040 210332 105409 210332 105407 210332 105040 210333 105407 210333 105039 210333 105039 210334 105407 210334 105406 210334 105039 210335 105406 210335 105405 210335 105014 210336 105041 210336 105411 210336 105411 210337 105041 210337 105015 210337 105411 210338 105015 210338 105414 210338 105414 210339 105015 210339 105016 210339 105414 210340 105016 210340 105415 210340 105415 210341 105016 210341 105416 210341 105416 210342 105016 210342 105017 210342 105416 210343 105017 210343 105018 210343 105018 210344 105017 210344 105019 210344 105019 210345 105017 210345 105021 210345 105019 210346 105021 210346 105020 210346 105020 210347 105021 210347 105418 210347 105418 210348 105021 210348 105022 210348 105418 210349 105022 210349 105023 210349 105023 210350 105022 210350 105421 210350 105421 210351 105022 210351 105025 210351 105421 210352 105025 210352 105024 210352 105024 210353 105025 210353 105026 210353 105026 210354 105025 210354 105027 210354 105026 210355 105027 210355 105028 210355 105028 210356 105027 210356 105029 210356 105029 210357 105027 210357 105030 210357 105029 210358 105030 210358 105425 210358 105425 210359 105030 210359 105825 210359 105425 210360 105825 210360 105423 210360 105031 210361 105053 210361 105838 210361 105838 210362 105053 210362 105063 210362 105838 210363 105063 210363 105839 210363 105839 210364 105063 210364 105061 210364 105839 210365 105061 210365 105840 210365 105840 210366 105061 210366 105060 210366 105840 210367 105060 210367 105843 210367 105843 210368 105060 210368 105032 210368 105843 210369 105032 210369 105846 210369 105846 210370 105032 210370 105033 210370 105846 210371 105033 210371 105850 210371 105850 210372 105033 210372 105057 210372 105850 210373 105057 210373 105852 210373 105852 210374 105057 210374 105056 210374 105852 210375 105056 210375 105854 210375 105854 210376 105056 210376 105034 210376 105854 210377 105034 210377 105010 210377 105010 210378 105034 210378 105035 210378 105010 210379 105035 210379 105006 210379 105006 210380 105035 210380 105036 210380 105006 210381 105036 210381 105012 210381 105012 210382 105036 210382 105038 210382 105012 210383 105038 210383 105037 210383 105037 210384 105038 210384 105822 210384 105037 210385 105822 210385 105039 210385 105039 210386 105822 210386 105821 210386 105039 210387 105821 210387 105040 210387 105040 210388 105821 210388 105818 210388 105040 210389 105818 210389 105041 210389 105041 210390 105818 210390 105042 210390 105041 210391 105042 210391 105015 210391 105042 210392 105816 210392 105015 210392 105015 210393 105816 210393 105043 210393 105015 210394 105043 210394 105016 210394 105016 210395 105043 210395 105815 210395 105016 210396 105815 210396 105017 210396 105017 210397 105815 210397 105044 210397 105017 210398 105044 210398 105021 210398 105021 210399 105044 210399 105045 210399 105021 210400 105045 210400 105022 210400 105022 210401 105045 210401 105046 210401 105022 210402 105046 210402 105025 210402 105025 210403 105046 210403 105811 210403 105025 210404 105811 210404 105027 210404 105027 210405 105811 210405 105047 210405 105027 210406 105047 210406 105030 210406 105030 210407 105047 210407 105808 210407 105030 210408 105808 210408 105825 210408 105825 210409 105808 210409 105807 210409 105825 210410 105807 210410 105048 210410 105048 210411 105807 210411 105069 210411 105048 210412 105069 210412 105049 210412 105049 210413 105069 210413 105050 210413 105049 210414 105050 210414 105826 210414 105826 210415 105050 210415 105067 210415 105826 210416 105067 210416 105829 210416 105829 210417 105067 210417 105066 210417 105829 210418 105066 210418 105834 210418 105834 210419 105066 210419 105051 210419 105834 210420 105051 210420 105831 210420 105831 210421 105051 210421 105052 210421 105831 210422 105052 210422 105824 210422 105824 210423 105052 210423 105065 210423 105824 210424 105065 210424 105031 210424 105031 210425 105065 210425 105064 210425 105031 210426 105064 210426 105053 210426 105054 210427 105034 210427 105055 210427 105055 210428 105034 210428 105056 210428 105055 210429 105056 210429 104643 210429 104643 210430 105056 210430 105057 210430 104643 210431 105057 210431 104640 210431 104640 210432 105057 210432 105033 210432 104640 210433 105033 210433 105058 210433 105058 210434 105033 210434 105032 210434 105058 210435 105032 210435 105059 210435 105059 210436 105032 210436 105060 210436 105059 210437 105060 210437 105062 210437 105062 210438 105060 210438 105061 210438 105062 210439 105061 210439 104637 210439 104637 210440 105061 210440 105063 210440 104637 210441 105063 210441 104635 210441 104635 210442 105063 210442 105053 210442 104635 210443 105053 210443 104634 210443 104634 210444 105053 210444 105064 210444 104634 210445 105064 210445 104632 210445 104632 210446 105064 210446 105065 210446 104632 210447 105065 210447 104629 210447 104629 210448 105065 210448 105052 210448 104629 210449 105052 210449 104628 210449 104628 210450 105052 210450 105051 210450 104628 210451 105051 210451 104627 210451 104627 210452 105051 210452 105066 210452 104627 210453 105066 210453 104625 210453 104625 210454 105066 210454 105067 210454 104625 210455 105067 210455 104623 210455 104623 210456 105067 210456 105050 210456 104623 210457 105050 210457 105068 210457 105068 210458 105050 210458 105069 210458 105068 210459 105069 210459 104622 210459 104622 210460 105069 210460 105807 210460 105101 210461 105070 210461 105071 210461 105071 210462 105070 210462 105072 210462 105071 210463 105072 210463 106271 210463 106271 210464 105072 210464 104608 210464 106271 210465 104608 210465 105073 210465 105073 210466 104608 210466 105074 210466 105073 210467 105074 210467 106272 210467 106272 210468 105074 210468 105075 210468 106272 210469 105075 210469 105077 210469 105077 210470 105075 210470 105076 210470 105077 210471 105076 210471 106275 210471 106275 210472 105076 210472 105078 210472 106275 210473 105078 210473 106276 210473 106276 210474 105078 210474 104610 210474 106276 210475 104610 210475 105079 210475 105079 210476 104610 210476 104612 210476 105079 210477 104612 210477 106279 210477 106279 210478 104612 210478 105080 210478 106279 210479 105080 210479 105081 210479 105081 210480 105080 210480 105082 210480 105081 210481 105082 210481 105083 210481 105083 210482 105082 210482 104614 210482 105083 210483 104614 210483 106280 210483 106280 210484 104614 210484 104616 210484 106280 210485 104616 210485 105084 210485 105084 210486 104616 210486 104618 210486 105084 210487 104618 210487 105085 210487 105085 210488 104618 210488 104620 210488 105085 210489 104620 210489 106281 210489 106281 210490 104620 210490 104621 210490 106281 210491 104621 210491 105086 210491 105086 210492 104621 210492 105087 210492 105086 210493 105087 210493 104624 210493 104624 210494 105087 210494 105088 210494 104624 210495 105088 210495 105089 210495 105089 210496 105088 210496 106286 210496 105089 210497 106286 210497 104626 210497 104626 210498 106286 210498 106287 210498 104626 210499 106287 210499 105090 210499 105090 210500 106287 210500 106288 210500 105090 210501 106288 210501 105091 210501 105091 210502 106288 210502 105092 210502 105091 210503 105092 210503 104630 210503 104630 210504 105092 210504 106289 210504 104630 210505 106289 210505 104631 210505 104631 210506 106289 210506 106290 210506 104631 210507 106290 210507 104633 210507 104633 210508 106290 210508 106292 210508 104633 210509 106292 210509 104636 210509 104636 210510 106292 210510 106294 210510 104636 210511 106294 210511 104638 210511 104638 210512 106294 210512 105093 210512 104638 210513 105093 210513 105094 210513 105094 210514 105093 210514 106296 210514 105094 210515 106296 210515 104639 210515 104639 210516 106296 210516 105095 210516 104639 210517 105095 210517 104641 210517 104641 210518 105095 210518 105096 210518 104641 210519 105096 210519 104642 210519 104642 210520 105096 210520 106297 210520 104642 210521 106297 210521 105097 210521 105097 210522 106297 210522 106298 210522 105097 210523 106298 210523 105098 210523 105098 210524 106298 210524 105100 210524 105098 210525 105100 210525 105099 210525 105099 210526 105100 210526 105102 210526 105099 210527 105102 210527 105101 210527 105101 210528 105102 210528 105070 210528 106299 210529 105103 210529 105139 210529 106299 210530 105139 210530 105104 210530 105104 210531 105139 210531 105105 210531 105104 210532 105105 210532 104606 210532 104606 210533 105105 210533 105106 210533 104606 210534 105106 210534 104607 210534 104607 210535 105106 210535 105107 210535 104607 210536 105107 210536 104609 210536 104609 210537 105107 210537 105143 210537 104609 210538 105143 210538 105108 210538 105108 210539 105143 210539 105109 210539 105108 210540 105109 210540 105110 210540 105110 210541 105109 210541 105145 210541 105110 210542 105145 210542 105111 210542 105111 210543 105145 210543 105147 210543 105111 210544 105147 210544 105112 210544 105112 210545 105147 210545 105148 210545 105112 210546 105148 210546 104611 210546 104611 210547 105148 210547 105113 210547 104611 210548 105113 210548 105114 210548 105114 210549 105113 210549 105115 210549 105114 210550 105115 210550 105116 210550 105116 210551 105115 210551 105117 210551 105116 210552 105117 210552 104613 210552 104613 210553 105117 210553 105118 210553 104613 210554 105118 210554 104615 210554 104615 210555 105118 210555 105119 210555 104615 210556 105119 210556 104617 210556 104617 210557 105119 210557 105120 210557 104617 210558 105120 210558 104619 210558 104619 210559 105120 210559 105155 210559 104619 210560 105155 210560 105121 210560 105121 210561 105155 210561 105785 210561 105121 210562 105785 210562 106283 210562 105159 210563 105122 210563 105789 210563 105789 210564 105122 210564 105123 210564 105789 210565 105123 210565 105790 210565 105790 210566 105123 210566 105124 210566 105790 210567 105124 210567 105792 210567 105792 210568 105124 210568 105125 210568 105792 210569 105125 210569 105793 210569 105793 210570 105125 210570 105126 210570 105793 210571 105126 210571 105127 210571 105127 210572 105126 210572 105166 210572 105127 210573 105166 210573 105796 210573 105796 210574 105166 210574 105128 210574 105796 210575 105128 210575 105129 210575 105129 210576 105128 210576 105130 210576 105129 210577 105130 210577 105797 210577 105797 210578 105130 210578 105131 210578 105797 210579 105131 210579 105132 210579 105132 210580 105131 210580 105162 210580 105132 210581 105162 210581 105800 210581 105800 210582 105162 210582 105133 210582 105800 210583 105133 210583 105134 210583 105134 210584 105133 210584 105135 210584 105134 210585 105135 210585 105803 210585 105803 210586 105135 210586 105136 210586 105803 210587 105136 210587 105806 210587 105806 210588 105136 210588 105137 210588 105806 210589 105137 210589 105103 210589 105103 210590 105137 210590 105138 210590 105103 210591 105138 210591 105139 210591 105139 210592 105138 210592 105140 210592 105139 210593 105140 210593 105105 210593 105105 210594 105140 210594 105141 210594 105105 210595 105141 210595 105106 210595 105106 210596 105141 210596 105142 210596 105106 210597 105142 210597 105107 210597 105107 210598 105142 210598 105782 210598 105107 210599 105782 210599 105143 210599 105143 210600 105782 210600 105781 210600 105143 210601 105781 210601 105109 210601 105109 210602 105781 210602 105144 210602 105109 210603 105144 210603 105145 210603 105145 210604 105144 210604 105146 210604 105145 210605 105146 210605 105147 210605 105147 210606 105146 210606 105778 210606 105147 210607 105778 210607 105148 210607 105148 210608 105778 210608 105149 210608 105148 210609 105149 210609 105113 210609 105113 210610 105149 210610 105150 210610 105113 210611 105150 210611 105115 210611 105115 210612 105150 210612 105151 210612 105115 210613 105151 210613 105117 210613 105117 210614 105151 210614 105775 210614 105117 210615 105775 210615 105118 210615 105118 210616 105775 210616 105152 210616 105118 210617 105152 210617 105119 210617 105119 210618 105152 210618 105153 210618 105119 210619 105153 210619 105120 210619 105120 210620 105153 210620 105154 210620 105120 210621 105154 210621 105155 210621 105155 210622 105154 210622 105156 210622 105155 210623 105156 210623 105785 210623 105785 210624 105156 210624 105772 210624 105785 210625 105772 210625 105786 210625 105786 210626 105772 210626 105158 210626 105786 210627 105158 210627 105157 210627 105157 210628 105158 210628 105170 210628 105157 210629 105170 210629 105159 210629 105159 210630 105170 210630 105122 210630 105784 210631 105138 210631 104572 210631 104572 210632 105138 210632 105137 210632 104572 210633 105137 210633 105160 210633 105160 210634 105137 210634 105136 210634 105160 210635 105136 210635 104570 210635 104570 210636 105136 210636 105135 210636 104570 210637 105135 210637 105161 210637 105161 210638 105135 210638 105133 210638 105161 210639 105133 210639 104569 210639 104569 210640 105133 210640 105162 210640 104569 210641 105162 210641 105163 210641 105163 210642 105162 210642 105131 210642 105163 210643 105131 210643 105164 210643 105164 210644 105131 210644 105130 210644 105164 210645 105130 210645 105165 210645 105165 210646 105130 210646 105128 210646 105165 210647 105128 210647 104564 210647 104564 210648 105128 210648 105166 210648 104564 210649 105166 210649 105167 210649 105167 210650 105166 210650 105126 210650 105167 210651 105126 210651 105168 210651 105168 210652 105126 210652 105125 210652 105168 210653 105125 210653 104562 210653 104562 210654 105125 210654 105124 210654 104562 210655 105124 210655 104561 210655 104561 210656 105124 210656 105123 210656 104561 210657 105123 210657 104560 210657 104560 210658 105123 210658 105122 210658 104560 210659 105122 210659 105169 210659 105169 210660 105122 210660 105170 210660 105169 210661 105170 210661 105171 210661 105171 210662 105170 210662 105158 210662 105171 210663 105158 210663 105172 210663 105172 210664 105158 210664 105772 210664 104559 210665 105226 210665 105173 210665 105173 210666 105226 210666 105225 210666 105173 210667 105225 210667 105174 210667 105174 210668 105225 210668 105175 210668 105174 210669 105175 210669 105176 210669 105176 210670 105175 210670 105223 210670 105176 210671 105223 210671 104563 210671 104563 210672 105223 210672 105222 210672 104563 210673 105222 210673 104565 210673 104565 210674 105222 210674 105177 210674 104565 210675 105177 210675 105178 210675 105178 210676 105177 210676 105179 210676 105178 210677 105179 210677 104566 210677 104566 210678 105179 210678 105218 210678 104566 210679 105218 210679 104567 210679 104567 210680 105218 210680 105216 210680 104567 210681 105216 210681 104568 210681 104568 210682 105216 210682 105180 210682 104568 210683 105180 210683 105181 210683 105181 210684 105180 210684 105182 210684 105181 210685 105182 210685 105183 210685 105183 210686 105182 210686 105212 210686 105183 210687 105212 210687 104571 210687 104571 210688 105212 210688 105184 210688 104571 210689 105184 210689 105185 210689 105185 210690 105184 210690 105210 210690 105185 210691 105210 210691 105186 210691 105186 210692 105210 210692 105208 210692 105186 210693 105208 210693 105187 210693 105187 210694 105208 210694 105207 210694 105187 210695 105207 210695 105188 210695 105188 210696 105207 210696 105771 210696 105188 210697 105771 210697 105189 210697 105189 210698 105771 210698 105770 210698 105189 210699 105770 210699 106334 210699 106334 210700 105770 210700 105190 210700 106334 210701 105190 210701 106336 210701 106336 210702 105190 210702 105767 210702 106336 210703 105767 210703 105191 210703 105191 210704 105767 210704 105192 210704 105191 210705 105192 210705 106338 210705 106338 210706 105192 210706 105764 210706 106338 210707 105764 210707 106340 210707 106340 210708 105764 210708 105193 210708 106340 210709 105193 210709 105194 210709 105194 210710 105193 210710 105762 210710 105194 210711 105762 210711 105195 210711 105195 210712 105762 210712 105196 210712 105195 210713 105196 210713 105197 210713 105197 210714 105196 210714 105199 210714 105197 210715 105199 210715 105198 210715 105198 210716 105199 210716 105758 210716 105198 210717 105758 210717 106343 210717 106343 210718 105758 210718 105200 210718 106343 210719 105200 210719 106344 210719 106344 210720 105200 210720 105756 210720 106344 210721 105756 210721 106346 210721 106346 210722 105756 210722 105201 210722 106346 210723 105201 210723 105202 210723 105202 210724 105201 210724 105754 210724 105202 210725 105754 210725 105203 210725 105203 210726 105754 210726 105752 210726 105203 210727 105752 210727 105204 210727 105204 210728 105752 210728 105750 210728 105204 210729 105750 210729 105205 210729 105205 210730 105750 210730 105206 210730 105205 210731 105206 210731 104559 210731 104559 210732 105206 210732 105226 210732 106320 210733 105207 210733 104584 210733 104584 210734 105207 210734 105208 210734 104584 210735 105208 210735 105209 210735 105209 210736 105208 210736 105210 210736 105209 210737 105210 210737 105211 210737 105211 210738 105210 210738 105184 210738 105211 210739 105184 210739 104582 210739 104582 210740 105184 210740 105212 210740 104582 210741 105212 210741 105213 210741 105213 210742 105212 210742 105182 210742 105213 210743 105182 210743 105214 210743 105214 210744 105182 210744 105180 210744 105214 210745 105180 210745 105215 210745 105215 210746 105180 210746 105216 210746 105215 210747 105216 210747 105217 210747 105217 210748 105216 210748 105218 210748 105217 210749 105218 210749 105219 210749 105219 210750 105218 210750 105179 210750 105219 210751 105179 210751 105220 210751 105220 210752 105179 210752 105177 210752 105220 210753 105177 210753 105221 210753 105221 210754 105177 210754 105222 210754 105221 210755 105222 210755 104578 210755 104578 210756 105222 210756 105223 210756 104578 210757 105223 210757 105224 210757 105224 210758 105223 210758 105175 210758 105224 210759 105175 210759 104577 210759 104577 210760 105175 210760 105225 210760 104577 210761 105225 210761 104574 210761 104574 210762 105225 210762 105226 210762 104574 210763 105226 210763 104573 210763 104573 210764 105226 210764 105206 210764 104573 210765 105206 210765 105749 210765 105749 210766 105206 210766 105750 210766 105258 210767 104591 210767 106323 210767 106323 210768 104591 210768 104592 210768 106323 210769 104592 210769 105227 210769 105227 210770 104592 210770 105228 210770 105227 210771 105228 210771 105229 210771 105229 210772 105228 210772 104593 210772 105229 210773 104593 210773 105230 210773 105230 210774 104593 210774 104596 210774 105230 210775 104596 210775 105231 210775 105231 210776 104596 210776 104597 210776 105231 210777 104597 210777 105232 210777 105232 210778 104597 210778 105233 210778 105232 210779 105233 210779 106325 210779 106325 210780 105233 210780 104599 210780 106325 210781 104599 210781 106327 210781 106327 210782 104599 210782 104600 210782 106327 210783 104600 210783 106328 210783 106328 210784 104600 210784 104602 210784 106328 210785 104602 210785 105234 210785 105234 210786 104602 210786 105235 210786 105234 210787 105235 210787 105236 210787 105236 210788 105235 210788 105237 210788 105236 210789 105237 210789 106330 210789 106330 210790 105237 210790 104604 210790 106330 210791 104604 210791 106331 210791 106331 210792 104604 210792 105238 210792 106331 210793 105238 210793 106332 210793 106332 210794 105238 210794 105239 210794 106332 210795 105239 210795 104575 210795 104575 210796 105239 210796 105240 210796 104575 210797 105240 210797 104576 210797 104576 210798 105240 210798 106303 210798 104576 210799 106303 210799 105241 210799 106303 210800 106304 210800 105241 210800 105241 210801 106304 210801 105243 210801 105241 210802 105243 210802 105242 210802 105242 210803 105243 210803 105244 210803 105242 210804 105244 210804 104579 210804 104579 210805 105244 210805 106306 210805 104579 210806 106306 210806 105245 210806 105245 210807 106306 210807 106307 210807 105245 210808 106307 210808 105246 210808 105246 210809 106307 210809 106309 210809 105246 210810 106309 210810 105247 210810 105247 210811 106309 210811 105248 210811 105247 210812 105248 210812 105249 210812 105249 210813 105248 210813 106310 210813 105249 210814 106310 210814 104580 210814 104580 210815 106310 210815 106311 210815 104580 210816 106311 210816 104581 210816 104581 210817 106311 210817 106313 210817 104581 210818 106313 210818 105250 210818 105250 210819 106313 210819 106315 210819 105250 210820 106315 210820 105251 210820 105251 210821 106315 210821 106316 210821 105251 210822 106316 210822 104583 210822 104583 210823 106316 210823 105252 210823 104583 210824 105252 210824 105253 210824 105253 210825 105252 210825 106317 210825 105253 210826 106317 210826 105254 210826 105254 210827 106317 210827 105255 210827 105254 210828 105255 210828 105256 210828 105256 210829 105255 210829 104585 210829 105256 210830 104585 210830 106322 210830 106322 210831 104585 210831 104587 210831 106322 210832 104587 210832 105257 210832 105257 210833 104587 210833 105259 210833 105257 210834 105259 210834 105258 210834 105258 210835 105259 210835 104589 210835 105258 210836 104589 210836 104591 210836 105748 210837 105299 210837 105260 210837 105748 210838 105260 210838 104586 210838 104586 210839 105260 210839 105261 210839 104586 210840 105261 210840 104588 210840 104588 210841 105261 210841 105262 210841 104588 210842 105262 210842 104590 210842 104590 210843 105262 210843 105263 210843 104590 210844 105263 210844 105264 210844 105264 210845 105263 210845 105304 210845 105264 210846 105304 210846 105265 210846 105265 210847 105304 210847 105266 210847 105265 210848 105266 210848 105267 210848 105267 210849 105266 210849 105306 210849 105267 210850 105306 210850 104594 210850 104594 210851 105306 210851 105268 210851 104594 210852 105268 210852 104595 210852 104595 210853 105268 210853 105308 210853 104595 210854 105308 210854 105270 210854 105270 210855 105308 210855 105269 210855 105270 210856 105269 210856 105271 210856 105271 210857 105269 210857 105310 210857 105271 210858 105310 210858 104598 210858 104598 210859 105310 210859 105272 210859 104598 210860 105272 210860 105273 210860 105273 210861 105272 210861 105274 210861 105273 210862 105274 210862 104601 210862 104601 210863 105274 210863 105276 210863 104601 210864 105276 210864 105275 210864 105275 210865 105276 210865 105277 210865 105275 210866 105277 210866 104603 210866 104603 210867 105277 210867 105278 210867 104603 210868 105278 210868 105279 210868 105279 210869 105278 210869 105284 210869 105279 210870 105284 210870 104605 210870 104605 210871 105284 210871 105285 210871 104605 210872 105285 210872 105280 210872 105272 210873 105281 210873 105274 210873 105274 210874 105281 210874 105282 210874 105274 210875 105282 210875 105276 210875 105276 210876 105282 210876 105283 210876 105276 210877 105283 210877 105277 210877 105277 210878 105283 210878 104659 210878 105277 210879 104659 210879 105278 210879 105278 210880 104659 210880 104661 210880 105278 210881 104661 210881 105284 210881 105284 210882 104661 210882 104662 210882 105284 210883 104662 210883 105285 210883 105285 210884 104662 210884 106249 210884 105285 210885 106249 210885 105286 210885 105286 210886 106249 210886 106251 210886 105286 210887 106251 210887 105728 210887 105728 210888 106251 210888 105287 210888 105728 210889 105287 210889 105288 210889 105288 210890 105287 210890 106253 210890 105288 210891 106253 210891 105729 210891 105729 210892 106253 210892 105289 210892 105729 210893 105289 210893 105730 210893 105730 210894 105289 210894 105290 210894 105730 210895 105290 210895 105733 210895 105733 210896 105290 210896 105291 210896 105733 210897 105291 210897 105292 210897 105292 210898 105291 210898 105293 210898 105292 210899 105293 210899 105734 210899 105734 210900 105293 210900 105294 210900 105734 210901 105294 210901 105736 210901 105736 210902 105294 210902 105295 210902 105736 210903 105295 210903 105738 210903 105738 210904 105295 210904 105296 210904 105738 210905 105296 210905 105740 210905 105740 210906 105296 210906 106259 210906 105740 210907 106259 210907 105742 210907 105742 210908 106259 210908 106261 210908 105742 210909 106261 210909 105743 210909 105743 210910 106261 210910 106262 210910 105743 210911 106262 210911 105297 210911 105297 210912 106262 210912 106264 210912 105297 210913 106264 210913 105298 210913 105298 210914 106264 210914 106265 210914 105298 210915 106265 210915 105746 210915 105746 210916 106265 210916 106267 210916 105746 210917 106267 210917 105747 210917 105747 210918 106267 210918 106268 210918 105747 210919 106268 210919 105299 210919 105299 210920 106268 210920 105300 210920 105299 210921 105300 210921 105260 210921 105260 210922 105300 210922 105301 210922 105260 210923 105301 210923 105261 210923 105261 210924 105301 210924 105302 210924 105261 210925 105302 210925 105262 210925 105262 210926 105302 210926 105303 210926 105262 210927 105303 210927 105263 210927 105263 210928 105303 210928 104649 210928 105263 210929 104649 210929 105304 210929 105304 210930 104649 210930 104650 210930 105304 210931 104650 210931 105266 210931 105266 210932 104650 210932 105305 210932 105266 210933 105305 210933 105306 210933 105306 210934 105305 210934 104652 210934 105306 210935 104652 210935 105268 210935 105268 210936 104652 210936 105307 210936 105268 210937 105307 210937 105308 210937 105308 210938 105307 210938 105309 210938 105308 210939 105309 210939 105269 210939 105269 210940 105309 210940 104654 210940 105269 210941 104654 210941 105310 210941 105310 210942 104654 210942 104655 210942 105310 210943 104655 210943 105272 210943 105272 210944 104655 210944 105281 210944 104644 210945 105346 210945 105311 210945 104644 210946 105311 210946 104645 210946 104645 210947 105311 210947 105312 210947 104645 210948 105312 210948 104646 210948 104646 210949 105312 210949 105313 210949 104646 210950 105313 210950 104647 210950 104647 210951 105313 210951 105342 210951 104647 210952 105342 210952 104648 210952 104648 210953 105342 210953 105341 210953 104648 210954 105341 210954 105314 210954 105314 210955 105341 210955 105340 210955 105314 210956 105340 210956 104651 210956 104651 210957 105340 210957 105337 210957 104651 210958 105337 210958 105315 210958 105315 210959 105337 210959 105335 210959 105315 210960 105335 210960 105316 210960 105316 210961 105335 210961 105333 210961 105316 210962 105333 210962 105317 210962 105317 210963 105333 210963 105318 210963 105317 210964 105318 210964 104653 210964 104653 210965 105318 210965 105330 210965 104653 210966 105330 210966 104656 210966 104656 210967 105330 210967 105319 210967 104656 210968 105319 210968 104657 210968 104657 210969 105319 210969 105320 210969 104657 210970 105320 210970 104658 210970 104658 210971 105320 210971 105328 210971 104658 210972 105328 210972 105321 210972 105321 210973 105328 210973 105322 210973 105321 210974 105322 210974 104660 210974 104660 210975 105322 210975 105327 210975 104660 210976 105327 210976 105324 210976 105324 210977 105327 210977 105323 210977 105324 210978 105323 210978 105325 210978 105325 210979 105323 210979 105710 210979 105325 210980 105710 210980 104663 210980 105377 210981 105710 210981 105323 210981 105377 210982 105323 210982 105379 210982 105379 210983 105323 210983 105327 210983 105379 210984 105327 210984 105326 210984 105326 210985 105327 210985 105322 210985 105326 210986 105322 210986 105371 210986 105371 210987 105322 210987 105328 210987 105371 210988 105328 210988 105372 210988 105372 210989 105328 210989 105320 210989 105372 210990 105320 210990 105373 210990 105373 210991 105320 210991 105319 210991 105373 210992 105319 210992 105329 210992 105329 210993 105319 210993 105330 210993 105329 210994 105330 210994 105331 210994 105331 210995 105330 210995 105318 210995 105331 210996 105318 210996 105332 210996 105332 210997 105318 210997 105333 210997 105332 210998 105333 210998 105334 210998 105334 210999 105333 210999 105335 210999 105334 211000 105335 211000 105336 211000 105336 211001 105335 211001 105337 211001 105336 211002 105337 211002 105338 211002 105338 211003 105337 211003 105340 211003 105338 211004 105340 211004 105339 211004 105339 211005 105340 211005 105341 211005 105339 211006 105341 211006 105343 211006 105343 211007 105341 211007 105342 211007 105343 211008 105342 211008 105344 211008 105344 211009 105342 211009 105313 211009 105344 211010 105313 211010 105345 211010 105345 211011 105313 211011 105312 211011 105345 211012 105312 211012 105347 211012 105347 211013 105312 211013 105311 211013 105347 211014 105311 211014 105350 211014 105350 211015 105311 211015 105346 211015 105350 211016 105346 211016 105351 211016 105370 211017 105345 211017 105348 211017 105348 211018 105345 211018 105347 211018 105348 211019 105347 211019 105349 211019 105349 211020 105347 211020 105350 211020 105349 211021 105350 211021 105352 211021 105352 211022 105350 211022 105351 211022 105352 211023 105351 211023 105697 211023 105697 211024 105351 211024 105353 211024 105697 211025 105353 211025 105358 211025 105692 211026 105367 211026 105690 211026 105690 211027 105367 211027 105354 211027 105690 211028 105354 211028 105356 211028 105356 211029 105354 211029 105355 211029 105356 211030 105355 211030 105689 211030 105689 211031 105355 211031 105704 211031 105689 211032 105704 211032 105357 211032 105357 211033 105704 211033 105706 211033 105357 211034 105706 211034 105686 211034 105353 211035 105699 211035 105358 211035 105358 211036 105699 211036 105359 211036 105358 211037 105359 211037 105696 211037 105696 211038 105359 211038 105360 211038 105696 211039 105360 211039 105693 211039 105693 211040 105360 211040 105361 211040 105693 211041 105361 211041 105362 211041 105362 211042 105361 211042 105363 211042 105362 211043 105363 211043 105365 211043 105365 211044 105363 211044 105364 211044 105365 211045 105364 211045 105692 211045 105692 211046 105364 211046 105366 211046 105692 211047 105366 211047 105367 211047 105387 211048 105334 211048 105368 211048 105368 211049 105334 211049 105336 211049 105368 211050 105336 211050 105386 211050 105386 211051 105336 211051 105338 211051 105386 211052 105338 211052 105384 211052 105384 211053 105338 211053 105339 211053 105384 211054 105339 211054 105369 211054 105369 211055 105339 211055 105343 211055 105369 211056 105343 211056 105370 211056 105370 211057 105343 211057 105344 211057 105370 211058 105344 211058 105345 211058 105395 211059 105371 211059 105394 211059 105394 211060 105371 211060 105372 211060 105394 211061 105372 211061 105392 211061 105392 211062 105372 211062 105373 211062 105392 211063 105373 211063 105391 211063 105391 211064 105373 211064 105329 211064 105391 211065 105329 211065 105389 211065 105389 211066 105329 211066 105331 211066 105389 211067 105331 211067 105387 211067 105387 211068 105331 211068 105332 211068 105387 211069 105332 211069 105334 211069 105706 211070 105708 211070 105686 211070 105686 211071 105708 211071 105374 211071 105686 211072 105374 211072 105375 211072 105375 211073 105374 211073 105376 211073 105375 211074 105376 211074 105685 211074 105685 211075 105376 211075 105709 211075 105685 211076 105709 211076 105683 211076 105683 211077 105709 211077 105377 211077 105683 211078 105377 211078 105378 211078 105378 211079 105377 211079 105379 211079 105378 211080 105379 211080 105395 211080 105395 211081 105379 211081 105326 211081 105395 211082 105326 211082 105371 211082 105352 211083 106077 211083 105380 211083 105352 211084 105380 211084 105349 211084 105349 211085 105380 211085 105381 211085 105349 211086 105381 211086 105348 211086 105348 211087 105381 211087 105382 211087 105348 211088 105382 211088 105370 211088 105370 211089 105382 211089 105383 211089 105370 211090 105383 211090 105369 211090 105369 211091 105383 211091 104811 211091 105369 211092 104811 211092 105384 211092 105384 211093 104811 211093 105385 211093 105384 211094 105385 211094 105386 211094 105386 211095 105385 211095 104808 211095 105386 211096 104808 211096 105368 211096 105368 211097 104808 211097 105388 211097 105368 211098 105388 211098 105387 211098 105387 211099 105388 211099 104806 211099 105387 211100 104806 211100 105389 211100 105389 211101 104806 211101 105390 211101 105389 211102 105390 211102 105391 211102 105391 211103 105390 211103 104803 211103 105391 211104 104803 211104 105392 211104 105392 211105 104803 211105 105393 211105 105392 211106 105393 211106 105394 211106 105394 211107 105393 211107 105396 211107 105394 211108 105396 211108 105395 211108 105395 211109 105396 211109 105397 211109 105395 211110 105397 211110 105378 211110 105378 211111 105397 211111 104801 211111 105378 211112 104801 211112 105683 211112 105399 211113 106076 211113 105681 211113 105681 211114 105398 211114 105399 211114 105399 211115 105398 211115 105400 211115 105399 211116 105400 211116 105401 211116 105401 211117 105400 211117 105009 211117 105009 211118 105008 211118 105401 211118 105401 211119 105008 211119 105007 211119 105401 211120 105007 211120 104817 211120 105405 211121 105402 211121 105403 211121 105007 211122 105013 211122 104817 211122 104817 211123 105013 211123 105404 211123 104817 211124 105404 211124 105403 211124 105403 211125 105404 211125 105011 211125 105403 211126 105011 211126 105405 211126 105410 211127 105412 211127 105408 211127 105405 211128 105406 211128 105402 211128 105402 211129 105406 211129 105407 211129 105402 211130 105407 211130 105408 211130 105408 211131 105407 211131 105409 211131 105408 211132 105409 211132 105410 211132 105410 211133 105014 211133 105412 211133 105412 211134 105014 211134 105411 211134 105412 211135 105411 211135 105413 211135 105411 211136 105414 211136 105413 211136 105413 211137 105414 211137 105415 211137 105413 211138 105415 211138 104819 211138 105415 211139 105416 211139 104819 211139 104819 211140 105416 211140 105018 211140 104819 211141 105018 211141 105417 211141 105018 211142 105019 211142 105417 211142 105417 211143 105019 211143 105020 211143 105417 211144 105020 211144 105419 211144 105020 211145 105418 211145 105419 211145 105419 211146 105418 211146 105023 211146 105419 211147 105023 211147 105420 211147 105023 211148 105421 211148 105420 211148 105420 211149 105421 211149 105024 211149 105420 211150 105024 211150 105422 211150 105024 211151 105026 211151 105422 211151 105422 211152 105026 211152 105028 211152 105422 211153 105028 211153 105426 211153 105423 211154 105424 211154 105425 211154 105425 211155 105424 211155 105426 211155 105425 211156 105426 211156 105029 211156 105029 211157 105426 211157 105028 211157 105427 211158 105428 211158 105623 211158 105609 211159 105562 211159 105563 211159 105537 211160 105601 211160 105430 211160 105855 211161 105429 211161 105634 211161 98133 211162 98131 211162 105549 211162 105549 211163 98131 211163 105430 211163 98126 211164 105431 211164 105432 211164 105432 211165 105431 211165 105628 211165 106248 211166 106246 211166 105524 211166 106208 211167 105474 211167 105475 211167 106198 211168 106196 211168 105629 211168 105433 211169 104908 211169 105511 211169 105579 211170 105434 211170 105435 211170 105502 211171 105501 211171 104816 211171 105436 211172 105437 211172 105497 211172 105438 211173 105519 211173 105518 211173 105597 211174 105439 211174 104822 211174 105493 211175 105644 211175 105545 211175 105612 211176 105554 211176 105490 211176 104690 211177 104689 211177 105465 211177 105625 211178 105458 211178 105440 211178 105451 211179 105441 211179 105634 211179 105441 211180 105442 211180 105634 211180 105634 211181 105442 211181 105443 211181 105634 211182 105443 211182 105445 211182 105445 211183 105443 211183 105444 211183 105445 211184 105444 211184 106226 211184 106225 211185 105446 211185 104815 211185 104815 211186 105446 211186 105447 211186 104815 211187 105447 211187 105448 211187 105448 211188 105447 211188 105449 211188 105448 211189 105449 211189 105454 211189 105454 211190 105449 211190 104686 211190 105454 211191 104686 211191 105450 211191 105429 211192 105456 211192 105634 211192 105634 211193 105456 211193 105454 211193 105634 211194 105454 211194 105451 211194 105451 211195 105454 211195 105450 211195 105452 211196 105625 211196 105453 211196 105453 211197 105625 211197 106075 211197 105453 211198 106075 211198 105859 211198 105859 211199 106075 211199 105454 211199 105859 211200 105454 211200 105455 211200 105455 211201 105454 211201 105456 211201 105460 211202 105458 211202 105457 211202 105457 211203 105458 211203 105459 211203 105457 211204 105459 211204 106221 211204 105460 211205 105461 211205 105458 211205 105458 211206 105461 211206 105462 211206 105458 211207 105462 211207 105440 211207 105440 211208 105462 211208 105463 211208 105440 211209 105463 211209 105464 211209 105464 211210 105463 211210 104690 211210 104690 211211 105465 211211 105464 211211 105464 211212 105465 211212 105652 211212 105464 211213 105652 211213 105466 211213 105466 211214 105652 211214 105467 211214 105467 211215 105652 211215 105651 211215 105467 211216 105651 211216 106072 211216 105470 211217 104692 211217 105475 211217 105617 211218 104697 211218 106073 211218 106073 211219 104697 211219 104696 211219 106073 211220 104696 211220 106074 211220 106074 211221 104696 211221 104695 211221 106074 211222 104695 211222 105469 211222 105469 211223 104695 211223 105468 211223 105469 211224 105468 211224 104693 211224 105886 211225 104978 211225 105475 211225 105475 211226 104978 211226 105469 211226 105475 211227 105469 211227 105470 211227 105470 211228 105469 211228 104693 211228 105471 211229 105472 211229 105567 211229 105478 211230 105473 211230 105474 211230 105474 211231 105473 211231 105884 211231 105474 211232 105884 211232 105475 211232 105475 211233 105884 211233 105885 211233 105475 211234 105885 211234 105886 211234 104978 211235 104980 211235 105469 211235 105469 211236 104980 211236 105476 211236 105469 211237 105476 211237 105483 211237 105483 211238 105476 211238 104981 211238 105483 211239 104981 211239 105484 211239 104700 211240 105477 211240 104702 211240 104702 211241 105477 211241 105479 211241 104702 211242 105479 211242 105478 211242 105478 211243 105479 211243 105480 211243 105478 211244 105480 211244 105473 211244 105655 211245 105481 211245 105482 211245 105482 211246 105481 211246 106068 211246 105482 211247 106068 211247 104699 211247 104699 211248 106068 211248 105483 211248 104699 211249 105483 211249 104700 211249 104700 211250 105483 211250 105484 211250 104700 211251 105484 211251 105477 211251 105485 211252 105486 211252 105611 211252 105611 211253 105486 211253 105487 211253 105490 211254 105488 211254 105489 211254 105492 211255 106065 211255 105490 211255 105490 211256 106065 211256 106064 211256 105490 211257 106064 211257 105612 211257 105612 211258 106064 211258 105491 211258 105612 211259 105491 211259 106063 211259 105490 211260 105489 211260 105492 211260 105492 211261 105489 211261 105556 211261 105492 211262 105556 211262 105493 211262 105493 211263 105545 211263 104824 211263 104823 211264 104824 211264 106191 211264 105439 211265 105597 211265 105494 211265 105494 211266 105597 211266 105599 211266 105494 211267 105599 211267 105534 211267 105533 211268 105541 211268 105495 211268 105495 211269 105541 211269 105638 211269 104820 211270 105516 211270 105517 211270 105496 211271 104923 211271 105956 211271 105496 211272 105956 211272 105437 211272 105956 211273 105959 211273 105437 211273 105437 211274 105959 211274 105960 211274 105437 211275 105960 211275 105497 211275 105497 211276 105960 211276 105498 211276 105497 211277 105498 211277 105505 211277 105963 211278 105504 211278 105499 211278 105499 211279 105504 211279 105505 211279 105499 211280 105505 211280 105500 211280 105500 211281 105505 211281 105498 211281 105501 211282 105502 211282 105504 211282 105504 211283 105502 211283 105503 211283 105504 211284 105503 211284 105505 211284 105590 211285 105585 211285 105506 211285 105506 211286 105585 211286 105434 211286 105579 211287 104673 211287 105434 211287 105434 211288 104673 211288 104672 211288 105434 211289 104672 211289 105506 211289 105433 211290 105511 211290 104907 211290 104813 211291 105507 211291 105513 211291 105513 211292 105507 211292 105512 211292 104815 211293 104680 211293 104679 211293 104677 211294 105509 211294 105508 211294 105508 211295 105509 211295 104676 211295 105508 211296 104676 211296 105511 211296 105511 211297 104676 211297 106232 211297 105511 211298 106232 211298 105510 211298 106226 211299 106225 211299 105445 211299 105445 211300 106225 211300 104815 211300 105445 211301 104815 211301 105508 211301 105508 211302 104815 211302 104679 211302 105508 211303 104679 211303 104677 211303 105510 211304 106231 211304 105511 211304 105511 211305 106231 211305 105513 211305 105511 211306 105513 211306 104907 211306 104907 211307 105513 211307 105512 211307 106231 211308 106229 211308 105513 211308 105513 211309 106229 211309 105514 211309 105513 211310 105514 211310 104814 211310 104814 211311 105514 211311 104683 211311 104814 211312 104683 211312 104815 211312 104815 211313 104683 211313 104682 211313 104815 211314 104682 211314 104680 211314 104724 211315 105515 211315 105639 211315 104723 211316 105520 211316 105519 211316 105943 211317 105944 211317 105524 211317 105516 211318 105518 211318 105517 211318 105517 211319 105518 211319 105519 211319 105517 211320 105519 211320 106179 211320 106179 211321 105519 211321 105520 211321 105517 211322 105941 211322 105521 211322 104818 211323 105522 211323 105438 211323 105438 211324 105522 211324 105639 211324 105438 211325 105639 211325 105519 211325 105519 211326 105639 211326 105515 211326 105519 211327 105515 211327 104723 211327 104931 211328 105529 211328 105947 211328 105947 211329 105529 211329 105524 211329 105947 211330 105524 211330 105946 211330 105946 211331 105524 211331 105944 211331 105523 211332 104821 211332 106246 211332 106246 211333 104821 211333 104820 211333 106246 211334 104820 211334 105524 211334 105524 211335 104820 211335 105517 211335 105524 211336 105517 211336 105943 211336 105943 211337 105517 211337 105521 211337 104724 211338 105639 211338 105525 211338 105525 211339 105639 211339 105529 211339 105525 211340 105529 211340 105526 211340 105517 211341 105527 211341 105941 211341 105941 211342 105527 211342 105528 211342 105941 211343 105528 211343 104937 211343 104937 211344 105528 211344 104935 211344 104931 211345 105530 211345 105529 211345 105529 211346 105530 211346 104932 211346 105529 211347 104932 211347 105526 211347 105526 211348 104932 211348 104933 211348 105526 211349 104933 211349 105531 211349 105531 211350 104933 211350 104935 211350 105531 211351 104935 211351 105532 211351 105532 211352 104935 211352 105528 211352 105533 211353 105534 211353 105541 211353 105541 211354 105534 211354 105599 211354 105541 211355 105599 211355 105540 211355 105540 211356 105599 211356 104719 211356 106180 211357 105536 211357 105535 211357 105535 211358 105536 211358 105537 211358 105537 211359 105536 211359 105538 211359 105537 211360 105538 211360 105601 211360 105601 211361 105538 211361 105539 211361 105601 211362 105539 211362 105599 211362 105599 211363 105539 211363 104721 211363 105599 211364 104721 211364 104719 211364 105540 211365 106185 211365 105541 211365 105541 211366 106185 211366 106183 211366 105541 211367 106183 211367 105638 211367 105638 211368 106183 211368 105542 211368 105638 211369 105542 211369 105641 211369 105641 211370 105542 211370 106181 211370 105641 211371 106181 211371 105543 211371 104715 211372 105544 211372 105545 211372 105545 211373 105544 211373 105546 211373 105545 211374 105546 211374 104824 211374 104824 211375 105546 211375 105547 211375 104824 211376 105547 211376 106191 211376 105549 211377 105603 211377 106189 211377 105631 211378 98133 211378 105548 211378 105548 211379 98133 211379 105549 211379 105548 211380 105549 211380 106187 211380 106187 211381 105549 211381 106189 211381 104823 211382 106191 211382 105550 211382 105550 211383 106191 211383 105551 211383 105550 211384 105551 211384 105603 211384 105603 211385 105551 211385 105552 211385 105603 211386 105552 211386 106189 211386 105553 211387 104710 211387 105554 211387 105554 211388 104710 211388 105555 211388 105554 211389 105555 211389 105490 211389 105490 211390 105555 211390 104709 211390 105490 211391 104709 211391 105488 211391 104713 211392 105553 211392 105608 211392 106196 211393 106194 211393 105606 211393 105606 211394 106194 211394 105605 211394 105493 211395 105556 211395 105644 211395 105644 211396 105556 211396 105557 211396 105644 211397 105557 211397 106198 211397 105481 211398 105558 211398 105559 211398 105559 211399 105558 211399 105656 211399 105559 211400 105656 211400 105487 211400 105487 211401 105656 211401 105660 211401 105487 211402 105660 211402 105611 211402 105611 211403 105660 211403 105661 211403 105611 211404 105661 211404 105560 211404 105560 211405 104703 211405 105611 211405 105611 211406 104703 211406 106206 211406 105611 211407 106206 211407 105561 211407 106206 211408 106205 211408 105561 211408 105561 211409 106205 211409 106204 211409 105561 211410 106204 211410 105562 211410 105562 211411 106204 211411 106203 211411 105562 211412 106203 211412 105563 211412 105563 211413 106203 211413 106201 211413 105563 211414 106201 211414 105564 211414 106201 211415 105565 211415 105564 211415 105564 211416 105565 211416 104706 211416 105564 211417 104706 211417 105658 211417 105658 211418 104706 211418 105566 211418 105658 211419 105566 211419 105659 211419 105567 211420 105472 211420 105657 211420 105472 211421 106212 211421 105657 211421 105657 211422 106212 211422 106211 211422 105657 211423 106211 211423 105632 211423 104692 211424 105568 211424 105475 211424 105475 211425 105568 211425 105632 211425 105475 211426 105632 211426 106208 211426 106208 211427 105632 211427 106211 211427 105568 211428 105569 211428 105632 211428 105632 211429 105569 211429 105570 211429 105632 211430 105570 211430 105571 211430 105571 211431 105570 211431 106215 211431 105571 211432 106215 211432 105617 211432 105617 211433 106215 211433 106214 211433 105617 211434 106214 211434 104697 211434 105654 211435 104687 211435 105619 211435 105619 211436 104687 211436 105572 211436 105619 211437 105572 211437 105624 211437 105624 211438 105572 211438 105573 211438 105624 211439 105573 211439 98140 211439 105589 211440 105574 211440 98150 211440 98150 211441 105574 211441 104671 211441 98150 211442 104671 211442 105575 211442 105591 211443 106239 211443 105576 211443 105576 211444 106239 211444 105577 211444 105576 211445 105577 211445 105578 211445 105578 211446 105577 211446 106236 211446 105578 211447 106236 211447 105637 211447 105637 211448 106236 211448 106235 211448 105637 211449 106235 211449 105579 211449 105579 211450 106235 211450 106234 211450 105579 211451 106234 211451 104673 211451 105581 211452 105529 211452 105580 211452 105580 211453 105529 211453 105496 211453 105580 211454 105496 211454 104666 211454 106242 211455 105437 211455 105523 211455 105523 211456 105437 211456 105436 211456 105523 211457 105436 211457 104821 211457 106242 211458 106241 211458 105437 211458 105437 211459 106241 211459 106240 211459 105437 211460 106240 211460 105496 211460 105496 211461 106240 211461 104668 211461 105496 211462 104668 211462 104666 211462 105581 211463 104664 211463 105529 211463 105529 211464 104664 211464 105582 211464 105529 211465 105582 211465 105524 211465 105524 211466 105582 211466 105583 211466 105524 211467 105583 211467 106248 211467 104910 211468 105584 211468 105585 211468 105584 211469 105970 211469 105585 211469 105585 211470 105970 211470 105972 211470 105585 211471 105972 211471 105434 211471 105434 211472 105972 211472 105586 211472 105434 211473 105586 211473 105435 211473 105435 211474 105586 211474 105587 211474 105435 211475 105587 211475 104813 211475 104813 211476 105587 211476 105588 211476 104813 211477 105588 211477 105507 211477 104909 211478 104910 211478 98146 211478 98146 211479 104910 211479 105585 211479 98146 211480 105585 211480 105589 211480 105589 211481 105585 211481 105590 211481 105589 211482 105590 211482 105574 211482 105636 211483 98150 211483 105576 211483 105576 211484 98150 211484 105575 211484 105576 211485 105575 211485 105591 211485 105636 211486 104919 211486 98150 211486 98150 211487 104919 211487 105592 211487 98150 211488 105592 211488 105628 211488 105430 211489 105602 211489 105593 211489 105430 211490 105593 211490 105549 211490 105549 211491 105593 211491 104947 211491 105549 211492 104947 211492 105603 211492 105603 211493 104947 211493 105594 211493 105603 211494 105594 211494 105595 211494 105597 211495 105604 211495 105596 211495 105596 211496 105598 211496 105597 211496 105597 211497 105598 211497 105929 211497 105597 211498 105929 211498 105599 211498 105599 211499 105929 211499 105600 211499 105599 211500 105600 211500 105601 211500 105601 211501 105600 211501 105933 211501 105601 211502 105933 211502 105430 211502 105430 211503 105933 211503 105934 211503 105430 211504 105934 211504 105602 211504 105595 211505 105604 211505 105603 211505 105603 211506 105604 211506 105597 211506 105603 211507 105597 211507 105550 211507 105550 211508 105597 211508 104822 211508 105550 211509 104822 211509 104823 211509 105605 211510 104713 211510 105606 211510 105606 211511 104713 211511 105608 211511 105606 211512 105608 211512 105607 211512 105607 211513 105608 211513 105609 211513 105614 211514 105898 211514 105608 211514 105608 211515 105898 211515 105903 211515 105608 211516 105903 211516 105609 211516 105609 211517 105903 211517 105901 211517 105609 211518 105901 211518 105562 211518 105562 211519 105901 211519 104965 211519 105562 211520 104965 211520 105561 211520 105561 211521 104965 211521 105610 211521 105561 211522 105610 211522 104967 211522 105485 211523 105611 211523 106063 211523 106063 211524 105611 211524 105561 211524 106063 211525 105561 211525 105612 211525 105612 211526 105561 211526 104967 211526 105612 211527 104967 211527 104968 211527 105553 211528 105554 211528 105608 211528 105608 211529 105554 211529 105613 211529 105608 211530 105613 211530 105614 211530 104968 211531 104970 211531 105612 211531 105612 211532 104970 211532 105615 211532 105612 211533 105615 211533 105554 211533 105554 211534 105615 211534 105894 211534 105554 211535 105894 211535 105613 211535 104990 211536 105616 211536 105653 211536 105653 211537 105616 211537 105617 211537 105653 211538 105617 211538 106072 211538 106072 211539 105617 211539 106073 211539 104994 211540 105571 211540 104993 211540 104993 211541 105571 211541 105617 211541 104993 211542 105617 211542 105618 211542 105618 211543 105617 211543 105616 211543 105428 211544 105869 211544 105870 211544 105624 211545 105875 211545 105619 211545 105619 211546 105875 211546 105876 211546 105619 211547 105876 211547 105620 211547 105620 211548 105876 211548 105621 211548 105620 211549 105621 211549 105653 211549 105653 211550 105621 211550 105622 211550 105653 211551 105622 211551 104990 211551 105623 211552 105428 211552 98139 211552 98139 211553 105428 211553 105870 211553 98139 211554 105870 211554 105624 211554 105624 211555 105870 211555 105873 211555 105624 211556 105873 211556 105875 211556 105573 211557 106221 211557 98140 211557 98140 211558 106221 211558 105459 211558 98140 211559 105459 211559 105633 211559 105633 211560 105459 211560 105005 211560 105452 211561 105000 211561 105625 211561 105625 211562 105000 211562 105626 211562 105625 211563 105626 211563 105458 211563 105458 211564 105626 211564 105627 211564 105458 211565 105627 211565 105459 211565 105459 211566 105627 211566 105002 211566 105459 211567 105002 211567 105005 211567 105592 211568 104921 211568 105628 211568 105628 211569 104921 211569 104923 211569 105628 211570 104923 211570 105432 211570 105432 211571 104923 211571 105496 211571 105432 211572 105496 211572 98126 211572 98126 211573 105496 211573 105529 211573 98126 211574 105529 211574 98127 211574 98127 211575 105529 211575 105639 211575 98127 211576 105639 211576 105640 211576 105642 211577 105641 211577 105535 211577 105535 211578 105641 211578 105543 211578 105535 211579 105543 211579 106180 211579 106196 211580 105606 211580 105629 211580 105629 211581 105606 211581 98133 211581 105629 211582 98133 211582 105630 211582 105630 211583 98133 211583 105631 211583 105630 211584 105631 211584 104716 211584 104994 211585 105869 211585 105571 211585 105571 211586 105869 211586 105428 211586 105571 211587 105428 211587 105632 211587 105632 211588 105428 211588 105427 211588 105632 211589 105427 211589 105657 211589 105657 211590 105427 211590 98138 211590 105657 211591 98138 211591 105658 211591 105658 211592 98138 211592 98137 211592 105658 211593 98137 211593 105564 211593 105005 211594 105855 211594 105633 211594 105633 211595 105855 211595 105634 211595 105633 211596 105634 211596 98143 211596 98143 211597 105634 211597 105445 211597 98143 211598 105445 211598 98145 211598 98145 211599 105445 211599 105508 211599 98145 211600 105508 211600 105635 211600 105635 211601 105508 211601 105511 211601 105635 211602 105511 211602 98146 211602 98146 211603 105511 211603 104908 211603 98146 211604 104908 211604 104909 211604 105963 211605 105636 211605 105504 211605 105504 211606 105636 211606 105576 211606 105504 211607 105576 211607 105501 211607 105501 211608 105576 211608 105578 211608 105501 211609 105578 211609 104816 211609 104816 211610 105578 211610 105637 211610 104818 211611 105495 211611 105522 211611 105522 211612 105495 211612 105638 211612 105522 211613 105638 211613 105639 211613 105639 211614 105638 211614 105641 211614 105639 211615 105641 211615 105640 211615 105640 211616 105641 211616 105642 211616 104955 211617 104956 211617 105629 211617 105630 211618 105645 211618 105643 211618 106198 211619 105629 211619 105644 211619 105644 211620 105629 211620 104956 211620 105644 211621 104956 211621 105647 211621 104716 211622 104715 211622 105630 211622 105630 211623 104715 211623 105545 211623 105630 211624 105545 211624 105645 211624 105645 211625 105545 211625 105650 211625 105643 211626 105919 211626 105630 211626 105630 211627 105919 211627 105646 211627 105630 211628 105646 211628 105629 211628 105629 211629 105646 211629 104953 211629 105629 211630 104953 211630 104955 211630 105647 211631 105648 211631 105644 211631 105644 211632 105648 211632 104959 211632 105644 211633 104959 211633 105545 211633 105545 211634 104959 211634 105649 211634 105545 211635 105649 211635 105650 211635 106072 211636 105651 211636 105653 211636 105653 211637 105651 211637 105652 211637 105653 211638 105652 211638 105620 211638 105620 211639 105652 211639 105465 211639 105620 211640 105465 211640 105619 211640 105619 211641 105465 211641 104689 211641 105619 211642 104689 211642 105654 211642 105655 211643 105471 211643 105481 211643 105481 211644 105471 211644 105567 211644 105481 211645 105567 211645 105558 211645 105558 211646 105567 211646 105657 211646 105558 211647 105657 211647 105656 211647 105656 211648 105657 211648 105658 211648 105656 211649 105658 211649 105660 211649 105660 211650 105658 211650 105659 211650 105660 211651 105659 211651 105661 211651 106062 211652 105424 211652 105423 211652 105423 211653 105662 211653 106062 211653 106062 211654 105662 211654 105828 211654 106062 211655 105828 211655 105665 211655 105665 211656 105828 211656 105663 211656 105663 211657 105664 211657 105665 211657 105665 211658 105664 211658 105827 211658 105665 211659 105827 211659 106066 211659 105666 211660 106070 211660 106071 211660 105827 211661 105667 211661 106066 211661 106066 211662 105667 211662 105830 211662 106066 211663 105830 211663 106071 211663 106071 211664 105830 211664 105668 211664 106071 211665 105668 211665 105666 211665 105832 211666 105671 211666 106069 211666 105666 211667 105835 211667 106070 211667 106070 211668 105835 211668 105833 211668 106070 211669 105833 211669 106069 211669 106069 211670 105833 211670 105669 211670 106069 211671 105669 211671 105832 211671 105832 211672 105670 211672 105671 211672 105671 211673 105670 211673 105672 211673 105671 211674 105672 211674 106067 211674 105672 211675 105836 211675 106067 211675 106067 211676 105836 211676 105837 211676 106067 211677 105837 211677 105673 211677 105837 211678 105674 211678 105673 211678 105673 211679 105674 211679 105675 211679 105673 211680 105675 211680 105677 211680 105675 211681 105676 211681 105677 211681 105677 211682 105676 211682 105841 211682 105677 211683 105841 211683 105678 211683 105841 211684 105842 211684 105678 211684 105678 211685 105842 211685 105844 211685 105678 211686 105844 211686 105679 211686 105844 211687 105845 211687 105679 211687 105679 211688 105845 211688 105847 211688 105679 211689 105847 211689 105680 211689 105847 211690 105848 211690 105680 211690 105680 211691 105848 211691 105849 211691 105680 211692 105849 211692 105682 211692 105681 211693 106076 211693 105853 211693 105853 211694 106076 211694 105682 211694 105853 211695 105682 211695 105851 211695 105851 211696 105682 211696 105849 211696 105683 211697 104801 211697 106093 211697 105683 211698 106093 211698 105685 211698 105685 211699 106093 211699 105684 211699 105685 211700 105684 211700 105375 211700 105375 211701 105684 211701 106091 211701 105375 211702 106091 211702 105686 211702 105686 211703 106091 211703 105687 211703 105686 211704 105687 211704 105357 211704 105357 211705 105687 211705 105688 211705 105357 211706 105688 211706 105689 211706 105689 211707 105688 211707 106083 211707 105689 211708 106083 211708 105356 211708 105356 211709 106083 211709 106084 211709 105356 211710 106084 211710 105690 211710 105690 211711 106084 211711 106087 211711 105690 211712 106087 211712 105692 211712 105692 211713 106087 211713 105691 211713 105692 211714 105691 211714 105365 211714 105365 211715 105691 211715 106080 211715 105365 211716 106080 211716 105362 211716 105362 211717 106080 211717 105694 211717 105362 211718 105694 211718 105693 211718 105693 211719 105694 211719 105695 211719 105693 211720 105695 211720 105696 211720 105696 211721 105695 211721 106079 211721 105696 211722 106079 211722 105358 211722 105358 211723 106079 211723 106078 211723 105358 211724 106078 211724 105697 211724 105697 211725 106078 211725 106077 211725 105697 211726 106077 211726 105352 211726 105351 211727 105346 211727 105698 211727 105351 211728 105698 211728 105353 211728 105353 211729 105698 211729 105726 211729 105353 211730 105726 211730 105699 211730 105699 211731 105726 211731 105700 211731 105699 211732 105700 211732 105359 211732 105359 211733 105700 211733 105725 211733 105359 211734 105725 211734 105360 211734 105360 211735 105725 211735 105722 211735 105360 211736 105722 211736 105361 211736 105361 211737 105722 211737 105701 211737 105361 211738 105701 211738 105363 211738 105363 211739 105701 211739 105720 211739 105363 211740 105720 211740 105364 211740 105364 211741 105720 211741 105719 211741 105364 211742 105719 211742 105366 211742 105366 211743 105719 211743 105718 211743 105366 211744 105718 211744 105367 211744 105367 211745 105718 211745 105702 211745 105367 211746 105702 211746 105354 211746 105354 211747 105702 211747 105703 211747 105354 211748 105703 211748 105355 211748 105355 211749 105703 211749 105716 211749 105355 211750 105716 211750 105704 211750 105704 211751 105716 211751 105705 211751 105704 211752 105705 211752 105706 211752 105706 211753 105705 211753 105707 211753 105706 211754 105707 211754 105708 211754 105708 211755 105707 211755 105713 211755 105708 211756 105713 211756 105374 211756 105374 211757 105713 211757 105712 211757 105374 211758 105712 211758 105376 211758 105376 211759 105712 211759 105711 211759 105376 211760 105711 211760 105709 211760 105709 211761 105711 211761 105710 211761 105709 211762 105710 211762 105377 211762 104663 211763 105710 211763 105711 211763 104663 211764 105711 211764 106250 211764 106250 211765 105711 211765 105712 211765 106250 211766 105712 211766 106252 211766 106252 211767 105712 211767 105713 211767 106252 211768 105713 211768 105714 211768 105714 211769 105713 211769 105707 211769 105714 211770 105707 211770 105715 211770 105715 211771 105707 211771 105705 211771 105715 211772 105705 211772 106254 211772 106254 211773 105705 211773 105716 211773 106254 211774 105716 211774 106255 211774 106255 211775 105716 211775 105703 211775 106255 211776 105703 211776 105717 211776 105717 211777 105703 211777 105702 211777 105717 211778 105702 211778 106256 211778 106256 211779 105702 211779 105718 211779 106256 211780 105718 211780 106257 211780 106257 211781 105718 211781 105719 211781 106257 211782 105719 211782 106258 211782 106258 211783 105719 211783 105720 211783 106258 211784 105720 211784 105721 211784 105721 211785 105720 211785 105701 211785 105721 211786 105701 211786 106260 211786 106260 211787 105701 211787 105722 211787 106260 211788 105722 211788 105723 211788 105723 211789 105722 211789 105725 211789 105723 211790 105725 211790 105724 211790 105724 211791 105725 211791 105700 211791 105724 211792 105700 211792 106263 211792 106263 211793 105700 211793 105726 211793 106263 211794 105726 211794 106266 211794 106266 211795 105726 211795 105698 211795 106266 211796 105698 211796 105727 211796 105727 211797 105698 211797 105346 211797 105727 211798 105346 211798 104644 211798 105280 211799 105285 211799 105286 211799 105280 211800 105286 211800 106300 211800 106300 211801 105286 211801 105728 211801 106300 211802 105728 211802 106301 211802 106301 211803 105728 211803 105288 211803 106301 211804 105288 211804 106302 211804 106302 211805 105288 211805 105729 211805 106302 211806 105729 211806 106305 211806 106305 211807 105729 211807 105730 211807 106305 211808 105730 211808 105731 211808 105731 211809 105730 211809 105733 211809 105731 211810 105733 211810 105732 211810 105732 211811 105733 211811 105292 211811 105732 211812 105292 211812 105735 211812 105735 211813 105292 211813 105734 211813 105735 211814 105734 211814 105737 211814 105737 211815 105734 211815 105736 211815 105737 211816 105736 211816 106308 211816 106308 211817 105736 211817 105738 211817 106308 211818 105738 211818 105739 211818 105739 211819 105738 211819 105740 211819 105739 211820 105740 211820 105741 211820 105741 211821 105740 211821 105742 211821 105741 211822 105742 211822 106312 211822 106312 211823 105742 211823 105743 211823 106312 211824 105743 211824 106314 211824 106314 211825 105743 211825 105297 211825 106314 211826 105297 211826 105744 211826 105744 211827 105297 211827 105298 211827 105744 211828 105298 211828 105745 211828 105745 211829 105298 211829 105746 211829 105745 211830 105746 211830 106318 211830 106318 211831 105746 211831 105747 211831 106318 211832 105747 211832 106319 211832 106319 211833 105747 211833 105299 211833 106319 211834 105299 211834 105748 211834 105749 211835 105750 211835 105751 211835 105751 211836 105750 211836 105752 211836 105751 211837 105752 211837 105753 211837 105753 211838 105752 211838 105754 211838 105753 211839 105754 211839 105755 211839 105755 211840 105754 211840 105201 211840 105755 211841 105201 211841 106329 211841 106329 211842 105201 211842 105756 211842 106329 211843 105756 211843 106326 211843 106326 211844 105756 211844 105200 211844 106326 211845 105200 211845 105757 211845 105757 211846 105200 211846 105758 211846 105757 211847 105758 211847 105759 211847 105759 211848 105758 211848 105199 211848 105759 211849 105199 211849 105760 211849 105760 211850 105199 211850 105196 211850 105760 211851 105196 211851 106324 211851 106324 211852 105196 211852 105762 211852 106324 211853 105762 211853 105761 211853 105761 211854 105762 211854 105193 211854 105761 211855 105193 211855 105763 211855 105763 211856 105193 211856 105764 211856 105763 211857 105764 211857 105765 211857 105765 211858 105764 211858 105192 211858 105765 211859 105192 211859 105766 211859 105766 211860 105192 211860 105767 211860 105766 211861 105767 211861 105768 211861 105768 211862 105767 211862 105190 211862 105768 211863 105190 211863 105769 211863 105769 211864 105190 211864 105770 211864 105769 211865 105770 211865 106321 211865 106321 211866 105770 211866 105771 211866 106321 211867 105771 211867 106320 211867 106320 211868 105771 211868 105207 211868 105172 211869 105772 211869 106348 211869 106348 211870 105772 211870 105156 211870 106348 211871 105156 211871 106347 211871 106347 211872 105156 211872 105154 211872 106347 211873 105154 211873 106345 211873 106345 211874 105154 211874 105153 211874 106345 211875 105153 211875 105773 211875 105773 211876 105153 211876 105152 211876 105773 211877 105152 211877 106342 211877 106342 211878 105152 211878 105775 211878 106342 211879 105775 211879 105774 211879 105774 211880 105775 211880 105151 211880 105774 211881 105151 211881 105776 211881 105776 211882 105151 211882 105150 211882 105776 211883 105150 211883 105777 211883 105777 211884 105150 211884 105149 211884 105777 211885 105149 211885 106341 211885 106341 211886 105149 211886 105778 211886 106341 211887 105778 211887 106339 211887 106339 211888 105778 211888 105146 211888 106339 211889 105146 211889 105779 211889 105779 211890 105146 211890 105144 211890 105779 211891 105144 211891 106337 211891 106337 211892 105144 211892 105781 211892 106337 211893 105781 211893 105780 211893 105780 211894 105781 211894 105782 211894 105780 211895 105782 211895 106335 211895 106335 211896 105782 211896 105142 211896 106335 211897 105142 211897 105783 211897 105783 211898 105142 211898 105141 211898 105783 211899 105141 211899 106333 211899 106333 211900 105141 211900 105140 211900 106333 211901 105140 211901 105784 211901 105784 211902 105140 211902 105138 211902 106283 211903 105785 211903 105786 211903 106283 211904 105786 211904 106284 211904 106284 211905 105786 211905 105157 211905 106284 211906 105157 211906 105787 211906 105787 211907 105157 211907 105159 211907 105787 211908 105159 211908 106285 211908 106285 211909 105159 211909 105789 211909 106285 211910 105789 211910 105788 211910 105788 211911 105789 211911 105790 211911 105788 211912 105790 211912 105791 211912 105791 211913 105790 211913 105792 211913 105791 211914 105792 211914 105794 211914 105794 211915 105792 211915 105793 211915 105794 211916 105793 211916 105795 211916 105795 211917 105793 211917 105127 211917 105795 211918 105127 211918 106291 211918 106291 211919 105127 211919 105796 211919 106291 211920 105796 211920 106293 211920 106293 211921 105796 211921 105129 211921 106293 211922 105129 211922 106295 211922 106295 211923 105129 211923 105797 211923 106295 211924 105797 211924 105798 211924 105798 211925 105797 211925 105132 211925 105798 211926 105132 211926 105799 211926 105799 211927 105132 211927 105800 211927 105799 211928 105800 211928 105801 211928 105801 211929 105800 211929 105134 211929 105801 211930 105134 211930 105802 211930 105802 211931 105134 211931 105803 211931 105802 211932 105803 211932 105804 211932 105804 211933 105803 211933 105806 211933 105804 211934 105806 211934 105805 211934 105805 211935 105806 211935 105103 211935 105805 211936 105103 211936 106299 211936 104622 211937 105807 211937 106282 211937 106282 211938 105807 211938 105808 211938 106282 211939 105808 211939 105809 211939 105809 211940 105808 211940 105047 211940 105809 211941 105047 211941 105810 211941 105810 211942 105047 211942 105811 211942 105810 211943 105811 211943 105812 211943 105812 211944 105811 211944 105046 211944 105812 211945 105046 211945 105813 211945 105813 211946 105046 211946 105045 211946 105813 211947 105045 211947 105814 211947 105814 211948 105045 211948 105044 211948 105814 211949 105044 211949 106278 211949 106278 211950 105044 211950 105815 211950 106278 211951 105815 211951 106277 211951 106277 211952 105815 211952 105043 211952 106277 211953 105043 211953 106274 211953 106274 211954 105043 211954 105816 211954 106274 211955 105816 211955 105817 211955 105817 211956 105816 211956 105042 211956 105817 211957 105042 211957 106273 211957 106273 211958 105042 211958 105818 211958 106273 211959 105818 211959 105819 211959 105819 211960 105818 211960 105821 211960 105819 211961 105821 211961 105820 211961 105820 211962 105821 211962 105822 211962 105820 211963 105822 211963 106270 211963 106270 211964 105822 211964 105038 211964 106270 211965 105038 211965 105823 211965 105823 211966 105038 211966 105036 211966 105823 211967 105036 211967 106269 211967 106269 211968 105036 211968 105035 211968 106269 211969 105035 211969 105054 211969 105054 211970 105035 211970 105034 211970 105670 211971 105832 211971 105824 211971 105825 211972 105048 211972 105423 211972 105423 211973 105048 211973 105662 211973 105049 211974 105826 211974 105827 211974 105827 211975 105664 211975 105049 211975 105049 211976 105664 211976 105663 211976 105049 211977 105663 211977 105048 211977 105048 211978 105663 211978 105828 211978 105048 211979 105828 211979 105662 211979 105829 211980 105834 211980 105666 211980 105666 211981 105668 211981 105829 211981 105829 211982 105668 211982 105830 211982 105829 211983 105830 211983 105826 211983 105826 211984 105830 211984 105667 211984 105826 211985 105667 211985 105827 211985 105824 211986 105832 211986 105831 211986 105832 211987 105669 211987 105831 211987 105831 211988 105669 211988 105833 211988 105831 211989 105833 211989 105834 211989 105834 211990 105833 211990 105835 211990 105834 211991 105835 211991 105666 211991 105670 211992 105824 211992 105672 211992 105672 211993 105824 211993 105031 211993 105672 211994 105031 211994 105836 211994 105836 211995 105031 211995 105838 211995 105836 211996 105838 211996 105837 211996 105837 211997 105838 211997 105674 211997 105674 211998 105838 211998 105839 211998 105674 211999 105839 211999 105675 211999 105675 212000 105839 212000 105676 212000 105676 212001 105839 212001 105840 212001 105676 212002 105840 212002 105841 212002 105841 212003 105840 212003 105842 212003 105842 212004 105840 212004 105843 212004 105842 212005 105843 212005 105844 212005 105844 212006 105843 212006 105845 212006 105845 212007 105843 212007 105846 212007 105845 212008 105846 212008 105847 212008 105847 212009 105846 212009 105848 212009 105848 212010 105846 212010 105850 212010 105848 212011 105850 212011 105849 212011 105849 212012 105850 212012 105851 212012 105851 212013 105850 212013 105852 212013 105851 212014 105852 212014 105853 212014 105853 212015 105852 212015 105854 212015 105853 212016 105854 212016 105681 212016 105005 212017 105860 212017 105855 212017 105855 212018 105860 212018 105856 212018 105855 212019 105856 212019 105429 212019 105429 212020 105856 212020 105857 212020 105429 212021 105857 212021 105456 212021 105456 212022 105857 212022 105858 212022 105456 212023 105858 212023 105455 212023 105455 212024 105858 212024 105862 212024 105455 212025 105862 212025 105859 212025 105859 212026 105862 212026 105864 212026 105859 212027 105864 212027 105453 212027 105453 212028 105864 212028 105865 212028 105860 212029 106539 212029 105856 212029 105856 212030 106539 212030 105861 212030 105856 212031 105861 212031 105857 212031 105857 212032 105861 212032 106528 212032 105857 212033 106528 212033 105858 212033 105858 212034 106528 212034 105863 212034 105858 212035 105863 212035 105862 212035 105862 212036 105863 212036 106526 212036 105862 212037 106526 212037 105864 212037 105864 212038 106526 212038 105866 212038 105864 212039 105866 212039 105865 212039 105865 212040 105866 212040 105867 212040 104994 212041 105868 212041 105869 212041 105869 212042 105868 212042 105871 212042 105869 212043 105871 212043 105870 212043 105870 212044 105871 212044 105872 212044 105870 212045 105872 212045 105873 212045 105873 212046 105872 212046 105874 212046 105873 212047 105874 212047 105875 212047 105875 212048 105874 212048 105882 212048 105875 212049 105882 212049 105876 212049 105876 212050 105882 212050 105877 212050 105876 212051 105877 212051 105621 212051 105621 212052 105877 212052 105879 212052 105878 212053 105879 212053 105880 212053 105880 212054 105879 212054 105877 212054 105868 212055 106512 212055 105871 212055 105871 212056 106512 212056 106511 212056 105871 212057 106511 212057 105872 212057 105872 212058 106511 212058 105881 212058 105872 212059 105881 212059 105874 212059 105874 212060 105881 212060 106541 212060 105874 212061 106541 212061 105882 212061 105882 212062 106541 212062 105883 212062 105882 212063 105883 212063 105877 212063 105877 212064 105883 212064 106493 212064 105877 212065 106493 212065 105880 212065 105479 212066 104984 212066 105480 212066 105480 212067 104984 212067 105888 212067 105480 212068 105888 212068 105473 212068 105473 212069 105888 212069 105890 212069 105473 212070 105890 212070 105884 212070 105884 212071 105890 212071 105891 212071 105884 212072 105891 212072 105885 212072 105885 212073 105891 212073 105892 212073 105885 212074 105892 212074 105886 212074 105886 212075 105892 212075 105887 212075 105886 212076 105887 212076 104978 212076 104978 212077 105887 212077 104979 212077 104984 212078 106377 212078 105888 212078 105888 212079 106377 212079 105889 212079 105888 212080 105889 212080 105890 212080 105890 212081 105889 212081 106367 212081 105890 212082 106367 212082 105891 212082 105891 212083 106367 212083 106561 212083 105891 212084 106561 212084 105892 212084 105892 212085 106561 212085 106560 212085 105892 212086 106560 212086 105887 212086 105887 212087 106560 212087 105893 212087 105887 212088 105893 212088 104979 212088 104979 212089 105893 212089 104972 212089 105615 212090 105911 212090 105913 212090 105615 212091 105913 212091 105894 212091 105894 212092 105913 212092 105914 212092 105894 212093 105914 212093 105613 212093 105914 212094 105895 212094 105613 212094 105613 212095 105895 212095 105896 212095 105613 212096 105896 212096 105614 212096 105614 212097 105896 212097 105909 212097 105909 212098 105897 212098 105614 212098 105614 212099 105897 212099 105908 212099 105614 212100 105908 212100 105898 212100 105908 212101 105907 212101 105898 212101 105898 212102 105907 212102 105899 212102 105898 212103 105899 212103 105903 212103 105900 212104 105901 212104 105902 212104 105902 212105 105901 212105 105903 212105 105902 212106 105903 212106 105905 212106 105905 212107 105903 212107 105899 212107 105904 212108 106427 212108 105900 212108 105900 212109 105902 212109 105904 212109 105904 212110 105902 212110 105905 212110 105904 212111 105905 212111 105906 212111 105905 212112 105899 212112 105906 212112 105906 212113 105899 212113 105907 212113 105906 212114 105907 212114 106440 212114 105907 212115 105908 212115 106440 212115 106440 212116 105908 212116 105897 212116 106440 212117 105897 212117 106439 212117 106439 212118 105897 212118 105909 212118 106439 212119 105909 212119 105910 212119 105909 212120 105896 212120 105910 212120 105910 212121 105896 212121 105895 212121 105910 212122 105895 212122 106434 212122 105911 212123 105912 212123 105913 212123 105913 212124 105912 212124 106434 212124 105913 212125 106434 212125 105914 212125 105914 212126 106434 212126 105895 212126 104959 212127 105915 212127 105649 212127 105649 212128 105915 212128 105916 212128 105649 212129 105916 212129 105650 212129 105650 212130 105916 212130 105923 212130 105650 212131 105923 212131 105645 212131 105645 212132 105923 212132 105917 212132 105645 212133 105917 212133 105643 212133 105643 212134 105917 212134 105918 212134 105643 212135 105918 212135 105919 212135 105919 212136 105918 212136 105926 212136 105919 212137 105926 212137 105646 212137 105646 212138 105926 212138 105920 212138 105915 212139 105921 212139 105916 212139 105916 212140 105921 212140 105922 212140 105916 212141 105922 212141 105923 212141 105923 212142 105922 212142 105924 212142 105923 212143 105924 212143 105917 212143 105917 212144 105924 212144 105925 212144 105917 212145 105925 212145 105918 212145 105918 212146 105925 212146 106507 212146 105918 212147 106507 212147 105926 212147 105926 212148 106507 212148 105927 212148 105926 212149 105927 212149 105920 212149 105920 212150 105927 212150 106505 212150 105604 212151 104944 212151 105596 212151 105596 212152 104944 212152 105928 212152 105596 212153 105928 212153 105598 212153 105598 212154 105928 212154 105930 212154 105598 212155 105930 212155 105929 212155 105929 212156 105930 212156 105931 212156 105929 212157 105931 212157 105600 212157 105600 212158 105931 212158 105932 212158 105600 212159 105932 212159 105933 212159 105933 212160 105932 212160 105938 212160 105933 212161 105938 212161 105934 212161 105934 212162 105938 212162 104938 212162 104944 212163 105935 212163 105928 212163 105928 212164 105935 212164 105936 212164 105928 212165 105936 212165 105930 212165 105930 212166 105936 212166 106454 212166 105930 212167 106454 212167 105931 212167 105931 212168 106454 212168 105937 212168 105931 212169 105937 212169 105932 212169 105932 212170 105937 212170 105939 212170 105932 212171 105939 212171 105938 212171 105938 212172 105939 212172 105940 212172 105938 212173 105940 212173 104938 212173 104938 212174 105940 212174 104939 212174 104937 212175 105948 212175 105941 212175 105941 212176 105948 212176 105942 212176 105941 212177 105942 212177 105521 212177 105521 212178 105942 212178 105950 212178 105521 212179 105950 212179 105943 212179 105943 212180 105950 212180 105945 212180 105943 212181 105945 212181 105944 212181 105944 212182 105945 212182 105952 212182 105944 212183 105952 212183 105946 212183 105946 212184 105952 212184 105954 212184 105946 212185 105954 212185 105947 212185 105947 212186 105954 212186 105955 212186 105948 212187 105949 212187 105942 212187 105942 212188 105949 212188 106415 212188 105942 212189 106415 212189 105950 212189 105950 212190 106415 212190 105951 212190 105950 212191 105951 212191 105945 212191 105945 212192 105951 212192 106414 212192 105945 212193 106414 212193 105952 212193 105952 212194 106414 212194 105953 212194 105952 212195 105953 212195 105954 212195 105954 212196 105953 212196 106413 212196 105954 212197 106413 212197 105955 212197 105955 212198 106413 212198 106465 212198 105956 212199 105957 212199 105959 212199 105959 212200 105957 212200 105958 212200 105959 212201 105958 212201 105960 212201 105960 212202 105958 212202 105964 212202 105960 212203 105964 212203 105498 212203 105498 212204 105964 212204 105961 212204 105498 212205 105961 212205 105500 212205 105500 212206 105961 212206 105962 212206 105500 212207 105962 212207 105499 212207 105499 212208 105962 212208 105966 212208 105499 212209 105966 212209 105963 212209 105963 212210 105966 212210 105969 212210 105957 212211 106476 212211 105958 212211 105958 212212 106476 212212 106473 212212 105958 212213 106473 212213 105964 212213 105964 212214 106473 212214 105965 212214 105964 212215 105965 212215 105961 212215 105961 212216 105965 212216 106486 212216 105961 212217 106486 212217 105962 212217 105962 212218 106486 212218 105967 212218 105962 212219 105967 212219 105966 212219 105966 212220 105967 212220 105968 212220 105966 212221 105968 212221 105969 212221 105969 212222 105968 212222 104913 212222 105584 212223 104912 212223 105970 212223 105970 212224 104912 212224 105971 212224 105970 212225 105971 212225 105972 212225 105972 212226 105971 212226 105973 212226 105972 212227 105973 212227 105586 212227 105586 212228 105973 212228 105974 212228 105586 212229 105974 212229 105587 212229 105587 212230 105974 212230 105975 212230 105587 212231 105975 212231 105588 212231 105588 212232 105975 212232 105980 212232 105588 212233 105980 212233 105507 212233 105507 212234 105980 212234 105982 212234 104912 212235 105976 212235 105971 212235 105971 212236 105976 212236 105977 212236 105971 212237 105977 212237 105973 212237 105973 212238 105977 212238 105978 212238 105973 212239 105978 212239 105974 212239 105974 212240 105978 212240 105979 212240 105974 212241 105979 212241 105975 212241 105975 212242 105979 212242 106483 212242 105975 212243 106483 212243 105980 212243 105980 212244 106483 212244 105981 212244 105980 212245 105981 212245 105982 212245 105982 212246 105981 212246 106484 212246 104897 212247 104741 212247 105983 212247 105983 212248 104741 212248 106160 212248 105983 212249 106160 212249 105984 212249 105984 212250 106160 212250 105985 212250 105984 212251 105985 212251 106224 212251 106224 212252 105985 212252 106162 212252 106224 212253 106162 212253 106223 212253 106223 212254 106162 212254 105986 212254 106223 212255 105986 212255 105987 212255 105987 212256 105986 212256 105988 212256 105987 212257 105988 212257 106222 212257 106222 212258 105988 212258 104889 212258 104887 212259 105990 212259 105989 212259 105989 212260 105990 212260 106166 212260 105989 212261 106166 212261 106220 212261 106220 212262 106166 212262 105991 212262 106220 212263 105991 212263 106219 212263 106219 212264 105991 212264 105992 212264 106219 212265 105992 212265 105994 212265 105994 212266 105992 212266 105993 212266 105994 212267 105993 212267 106218 212267 106218 212268 105993 212268 105995 212268 106218 212269 105995 212269 106217 212269 106217 212270 105995 212270 105996 212270 105997 212271 106170 212271 106216 212271 106216 212272 106170 212272 105998 212272 106216 212273 105998 212273 105999 212273 105999 212274 105998 212274 106172 212274 105999 212275 106172 212275 106000 212275 106000 212276 106172 212276 106173 212276 106000 212277 106173 212277 106001 212277 106001 212278 106173 212278 106003 212278 106001 212279 106003 212279 106002 212279 106002 212280 106003 212280 106175 212280 106002 212281 106175 212281 106004 212281 106004 212282 106175 212282 106176 212282 106005 212283 104875 212283 106213 212283 106213 212284 104875 212284 106095 212284 106213 212285 106095 212285 106210 212285 106210 212286 106095 212286 106096 212286 106210 212287 106096 212287 106209 212287 106209 212288 106096 212288 106006 212288 106209 212289 106006 212289 106007 212289 106007 212290 106006 212290 106008 212290 106007 212291 106008 212291 106009 212291 106009 212292 106008 212292 106097 212292 106009 212293 106097 212293 106207 212293 106207 212294 106097 212294 104793 212294 104869 212295 106011 212295 106010 212295 106010 212296 106011 212296 106012 212296 106010 212297 106012 212297 106014 212297 106014 212298 106012 212298 106013 212298 106014 212299 106013 212299 106202 212299 106202 212300 106013 212300 106015 212300 106202 212301 106015 212301 106200 212301 106200 212302 106015 212302 106016 212302 106200 212303 106016 212303 106017 212303 106017 212304 106016 212304 106018 212304 106017 212305 106018 212305 104705 212305 104705 212306 106018 212306 104863 212306 104707 212307 106019 212307 106199 212307 106199 212308 106019 212308 106021 212308 106199 212309 106021 212309 106020 212309 106020 212310 106021 212310 106022 212310 106020 212311 106022 212311 106197 212311 106197 212312 106022 212312 106105 212312 106197 212313 106105 212313 106195 212313 106195 212314 106105 212314 106106 212314 106195 212315 106106 212315 106023 212315 106023 212316 106106 212316 106107 212316 106023 212317 106107 212317 106193 212317 106193 212318 106107 212318 106024 212318 106193 212319 106024 212319 104712 212319 104712 212320 106024 212320 106109 212320 106192 212321 106110 212321 106190 212321 106190 212322 106110 212322 106025 212322 106190 212323 106025 212323 106026 212323 106026 212324 106025 212324 106111 212324 106026 212325 106111 212325 106027 212325 106027 212326 106111 212326 106028 212326 106027 212327 106028 212327 106188 212327 106188 212328 106028 212328 106114 212328 106188 212329 106114 212329 106186 212329 106186 212330 106114 212330 106029 212330 106186 212331 106029 212331 104718 212331 104718 212332 106029 212332 106030 212332 106031 212333 106032 212333 106184 212333 106184 212334 106032 212334 106117 212334 106184 212335 106117 212335 106182 212335 106182 212336 106117 212336 106034 212336 106182 212337 106034 212337 106033 212337 106033 212338 106034 212338 106035 212338 106033 212339 106035 212339 106036 212339 106036 212340 106035 212340 106122 212340 106036 212341 106122 212341 106037 212341 106037 212342 106122 212342 106123 212342 106037 212343 106123 212343 104722 212343 104722 212344 106123 212344 106124 212344 104846 212345 104847 212345 106038 212345 106038 212346 104847 212346 106126 212346 106038 212347 106126 212347 106178 212347 106178 212348 106126 212348 106128 212348 106178 212349 106128 212349 106039 212349 106039 212350 106128 212350 106129 212350 106039 212351 106129 212351 106040 212351 106040 212352 106129 212352 106130 212352 106040 212353 106130 212353 106041 212353 106041 212354 106130 212354 106042 212354 106041 212355 106042 212355 106043 212355 106043 212356 106042 212356 106132 212356 104839 212357 104761 212357 106044 212357 106044 212358 104761 212358 106133 212358 106044 212359 106133 212359 106247 212359 106247 212360 106133 212360 106045 212360 106247 212361 106045 212361 106245 212361 106245 212362 106045 212362 106046 212362 106245 212363 106046 212363 106244 212363 106244 212364 106046 212364 106135 212364 106244 212365 106135 212365 106243 212365 106243 212366 106135 212366 106136 212366 106243 212367 106136 212367 106048 212367 106048 212368 106136 212368 106047 212368 106048 212369 106047 212369 104667 212369 104667 212370 106047 212370 106139 212370 104669 212371 106049 212371 106238 212371 106238 212372 106049 212372 106050 212372 106238 212373 106050 212373 106237 212373 106237 212374 106050 212374 106141 212374 106237 212375 106141 212375 106051 212375 106051 212376 106141 212376 106143 212376 106051 212377 106143 212377 106052 212377 106052 212378 106143 212378 106053 212378 106052 212379 106053 212379 106054 212379 106054 212380 106053 212380 106055 212380 106054 212381 106055 212381 106233 212381 106233 212382 106055 212382 106147 212382 106233 212383 106147 212383 106056 212383 106056 212384 106147 212384 106148 212384 104674 212385 106149 212385 106058 212385 106058 212386 106149 212386 106057 212386 106058 212387 106057 212387 106230 212387 106230 212388 106057 212388 106152 212388 106230 212389 106152 212389 106228 212389 106228 212390 106152 212390 106153 212390 106228 212391 106153 212391 106059 212391 106059 212392 106153 212392 106155 212392 106059 212393 106155 212393 106227 212393 106227 212394 106155 212394 106060 212394 106227 212395 106060 212395 106061 212395 106061 212396 106060 212396 106158 212396 105665 212397 105492 212397 106062 212397 106062 212398 105492 212398 105493 212398 106062 212399 105493 212399 105424 212399 106063 212400 105491 212400 106066 212400 106066 212401 105491 212401 106064 212401 106066 212402 106064 212402 105665 212402 105665 212403 106064 212403 106065 212403 105665 212404 106065 212404 105492 212404 106063 212405 106066 212405 105485 212405 105485 212406 106066 212406 106071 212406 105485 212407 106071 212407 105486 212407 105673 212408 105469 212408 106067 212408 106067 212409 105469 212409 105483 212409 106067 212410 105483 212410 105671 212410 105671 212411 105483 212411 106068 212411 105671 212412 106068 212412 106069 212412 106069 212413 106068 212413 105481 212413 106069 212414 105481 212414 106070 212414 106070 212415 105481 212415 105559 212415 106070 212416 105559 212416 106071 212416 106071 212417 105559 212417 105487 212417 106071 212418 105487 212418 105486 212418 105678 212419 106072 212419 105677 212419 105677 212420 106072 212420 106073 212420 105677 212421 106073 212421 105673 212421 105673 212422 106073 212422 106074 212422 105673 212423 106074 212423 105469 212423 105464 212424 105466 212424 105678 212424 105678 212425 105466 212425 105467 212425 105678 212426 105467 212426 106072 212426 105464 212427 105678 212427 105440 212427 105440 212428 105678 212428 105679 212428 105440 212429 105679 212429 105625 212429 105625 212430 105679 212430 105680 212430 105625 212431 105680 212431 106075 212431 106075 212432 105680 212432 105454 212432 105454 212433 105680 212433 105682 212433 105454 212434 105682 212434 105448 212434 105448 212435 105682 212435 106076 212435 105448 212436 106076 212436 104815 212436 106396 212437 106077 212437 106078 212437 106396 212438 106078 212438 106399 212438 106399 212439 106078 212439 106079 212439 106399 212440 106079 212440 106397 212440 106397 212441 106079 212441 105695 212441 106397 212442 105695 212442 106496 212442 106496 212443 105695 212443 106388 212443 106388 212444 105695 212444 105694 212444 106388 212445 105694 212445 106389 212445 105691 212446 106385 212446 106080 212446 106080 212447 106385 212447 106081 212447 106080 212448 106081 212448 105694 212448 105694 212449 106081 212449 106082 212449 105694 212450 106082 212450 106389 212450 105687 212451 106372 212451 105688 212451 105688 212452 106372 212452 106373 212452 105688 212453 106373 212453 106083 212453 106083 212454 106373 212454 106085 212454 106083 212455 106085 212455 106084 212455 106084 212456 106085 212456 106086 212456 106084 212457 106086 212457 106087 212457 106087 212458 106086 212458 106369 212458 106087 212459 106369 212459 105691 212459 105691 212460 106369 212460 106384 212460 105691 212461 106384 212461 106385 212461 106089 212462 106365 212462 105687 212462 105687 212463 106365 212463 106088 212463 105687 212464 106088 212464 106372 212464 106089 212465 105687 212465 106090 212465 106090 212466 105687 212466 106091 212466 106090 212467 106091 212467 106433 212467 106433 212468 106091 212468 105684 212468 106433 212469 105684 212469 106094 212469 106357 212470 106092 212470 106093 212470 106093 212471 106092 212471 105684 212471 105684 212472 106092 212472 106425 212472 105684 212473 106425 212473 106094 212473 106357 212474 106093 212474 106358 212474 106358 212475 106093 212475 104801 212475 106358 212476 104801 212476 104800 212476 104875 212477 106371 212477 106095 212477 106095 212478 106371 212478 106363 212478 106095 212479 106363 212479 106096 212479 106096 212480 106363 212480 106361 212480 106096 212481 106361 212481 106006 212481 106006 212482 106361 212482 106525 212482 106006 212483 106525 212483 106008 212483 106008 212484 106525 212484 106098 212484 106008 212485 106098 212485 106097 212485 106097 212486 106098 212486 106366 212486 106097 212487 106366 212487 104793 212487 104793 212488 106366 212488 106379 212488 106011 212489 106099 212489 106012 212489 106012 212490 106099 212490 106100 212490 106012 212491 106100 212491 106013 212491 106013 212492 106100 212492 106429 212492 106013 212493 106429 212493 106015 212493 106015 212494 106429 212494 106418 212494 106015 212495 106418 212495 106016 212495 106016 212496 106418 212496 106101 212496 106016 212497 106101 212497 106018 212497 106018 212498 106101 212498 106518 212498 106018 212499 106518 212499 104863 212499 104863 212500 106518 212500 104786 212500 106019 212501 106102 212501 106021 212501 106021 212502 106102 212502 106103 212502 106021 212503 106103 212503 106022 212503 106022 212504 106103 212504 106104 212504 106022 212505 106104 212505 106105 212505 106105 212506 106104 212506 106435 212506 106105 212507 106435 212507 106106 212507 106106 212508 106435 212508 106436 212508 106106 212509 106436 212509 106107 212509 106107 212510 106436 212510 106437 212510 106107 212511 106437 212511 106024 212511 106024 212512 106437 212512 106108 212512 106024 212513 106108 212513 106109 212513 106109 212514 106108 212514 106442 212514 106110 212515 106417 212515 106025 212515 106025 212516 106417 212516 106112 212516 106025 212517 106112 212517 106111 212517 106111 212518 106112 212518 106451 212518 106111 212519 106451 212519 106028 212519 106028 212520 106451 212520 106113 212520 106028 212521 106113 212521 106114 212521 106114 212522 106113 212522 106115 212522 106114 212523 106115 212523 106029 212523 106029 212524 106115 212524 106116 212524 106029 212525 106116 212525 106030 212525 106030 212526 106116 212526 104774 212526 106032 212527 106118 212527 106117 212527 106117 212528 106118 212528 106457 212528 106117 212529 106457 212529 106034 212529 106034 212530 106457 212530 106119 212530 106034 212531 106119 212531 106035 212531 106035 212532 106119 212532 106120 212532 106035 212533 106120 212533 106122 212533 106122 212534 106120 212534 106121 212534 106122 212535 106121 212535 106123 212535 106123 212536 106121 212536 106125 212536 106123 212537 106125 212537 106124 212537 106124 212538 106125 212538 106446 212538 104847 212539 106463 212539 106126 212539 106126 212540 106463 212540 106127 212540 106126 212541 106127 212541 106128 212541 106128 212542 106127 212542 106472 212542 106128 212543 106472 212543 106129 212543 106129 212544 106472 212544 106471 212544 106129 212545 106471 212545 106130 212545 106130 212546 106471 212546 106131 212546 106130 212547 106131 212547 106042 212547 106042 212548 106131 212548 106469 212548 106042 212549 106469 212549 106132 212549 106132 212550 106469 212550 104763 212550 104761 212551 106477 212551 106133 212551 106133 212552 106477 212552 106479 212552 106133 212553 106479 212553 106045 212553 106045 212554 106479 212554 106134 212554 106045 212555 106134 212555 106046 212555 106046 212556 106134 212556 106478 212556 106046 212557 106478 212557 106135 212557 106135 212558 106478 212558 106411 212558 106135 212559 106411 212559 106136 212559 106136 212560 106411 212560 106137 212560 106136 212561 106137 212561 106047 212561 106047 212562 106137 212562 106138 212562 106047 212563 106138 212563 106139 212563 106139 212564 106138 212564 104753 212564 106049 212565 106487 212565 106050 212565 106050 212566 106487 212566 106140 212566 106050 212567 106140 212567 106141 212567 106141 212568 106140 212568 106142 212568 106141 212569 106142 212569 106143 212569 106143 212570 106142 212570 106144 212570 106143 212571 106144 212571 106053 212571 106053 212572 106144 212572 106145 212572 106053 212573 106145 212573 106055 212573 106055 212574 106145 212574 106146 212574 106055 212575 106146 212575 106147 212575 106147 212576 106146 212576 106481 212576 106147 212577 106481 212577 106148 212577 106148 212578 106481 212578 104749 212578 106149 212579 106150 212579 106057 212579 106057 212580 106150 212580 106151 212580 106057 212581 106151 212581 106152 212581 106152 212582 106151 212582 106154 212582 106152 212583 106154 212583 106153 212583 106153 212584 106154 212584 106407 212584 106153 212585 106407 212585 106155 212585 106155 212586 106407 212586 106156 212586 106155 212587 106156 212587 106060 212587 106060 212588 106156 212588 106157 212588 106060 212589 106157 212589 106158 212589 106158 212590 106157 212590 106159 212590 104741 212591 106392 212591 106160 212591 106160 212592 106392 212592 106394 212592 106160 212593 106394 212593 105985 212593 105985 212594 106394 212594 106161 212594 105985 212595 106161 212595 106162 212595 106162 212596 106161 212596 106163 212596 106162 212597 106163 212597 105986 212597 105986 212598 106163 212598 106395 212598 105986 212599 106395 212599 105988 212599 105988 212600 106395 212600 106400 212600 105988 212601 106400 212601 104889 212601 104889 212602 106400 212602 106164 212602 105990 212603 106165 212603 106166 212603 106166 212604 106165 212604 106167 212604 106166 212605 106167 212605 105991 212605 105991 212606 106167 212606 106168 212606 105991 212607 106168 212607 105992 212607 105992 212608 106168 212608 106169 212608 105992 212609 106169 212609 105993 212609 105993 212610 106169 212610 106499 212610 105993 212611 106499 212611 105995 212611 105995 212612 106499 212612 106498 212612 105995 212613 106498 212613 105996 212613 105996 212614 106498 212614 104733 212614 106170 212615 106381 212615 105998 212615 105998 212616 106381 212616 106171 212616 105998 212617 106171 212617 106172 212617 106172 212618 106171 212618 106174 212618 106172 212619 106174 212619 106173 212619 106173 212620 106174 212620 106559 212620 106173 212621 106559 212621 106003 212621 106003 212622 106559 212622 106387 212622 106003 212623 106387 212623 106175 212623 106175 212624 106387 212624 106177 212624 106175 212625 106177 212625 106176 212625 106176 212626 106177 212626 106513 212626 106043 212627 105532 212627 106041 212627 106041 212628 105532 212628 105528 212628 106041 212629 105528 212629 106040 212629 106040 212630 105528 212630 105527 212630 106040 212631 105527 212631 106039 212631 106039 212632 105527 212632 105517 212632 106039 212633 105517 212633 106178 212633 106178 212634 105517 212634 106179 212634 106178 212635 106179 212635 106038 212635 106038 212636 106179 212636 105520 212636 106038 212637 105520 212637 104846 212637 104846 212638 105520 212638 104723 212638 104722 212639 106180 212639 106037 212639 106037 212640 106180 212640 105543 212640 106037 212641 105543 212641 106036 212641 106036 212642 105543 212642 106181 212642 106036 212643 106181 212643 106033 212643 106033 212644 106181 212644 105542 212644 106033 212645 105542 212645 106182 212645 106182 212646 105542 212646 106183 212646 106182 212647 106183 212647 106184 212647 106184 212648 106183 212648 106185 212648 106184 212649 106185 212649 106031 212649 106031 212650 106185 212650 105540 212650 104718 212651 105548 212651 106186 212651 106186 212652 105548 212652 106187 212652 106186 212653 106187 212653 106188 212653 106188 212654 106187 212654 106189 212654 106188 212655 106189 212655 106027 212655 106027 212656 106189 212656 105552 212656 106027 212657 105552 212657 106026 212657 106026 212658 105552 212658 105551 212658 106026 212659 105551 212659 106190 212659 106190 212660 105551 212660 106191 212660 106190 212661 106191 212661 106192 212661 106192 212662 106191 212662 105547 212662 104712 212663 104713 212663 106193 212663 106193 212664 104713 212664 105605 212664 106193 212665 105605 212665 106023 212665 106023 212666 105605 212666 106194 212666 106023 212667 106194 212667 106195 212667 106195 212668 106194 212668 106196 212668 106195 212669 106196 212669 106197 212669 106197 212670 106196 212670 106198 212670 106197 212671 106198 212671 106020 212671 106020 212672 106198 212672 105557 212672 106020 212673 105557 212673 106199 212673 106199 212674 105557 212674 105556 212674 106199 212675 105556 212675 104707 212675 104707 212676 105556 212676 105489 212676 104705 212677 104706 212677 106017 212677 106017 212678 104706 212678 105565 212678 106017 212679 105565 212679 106200 212679 106200 212680 105565 212680 106201 212680 106200 212681 106201 212681 106202 212681 106202 212682 106201 212682 106203 212682 106202 212683 106203 212683 106014 212683 106014 212684 106203 212684 106204 212684 106014 212685 106204 212685 106010 212685 106010 212686 106204 212686 106205 212686 106010 212687 106205 212687 104869 212687 104869 212688 106205 212688 106206 212688 106207 212689 105478 212689 106009 212689 106009 212690 105478 212690 105474 212690 106009 212691 105474 212691 106007 212691 106007 212692 105474 212692 106208 212692 106007 212693 106208 212693 106209 212693 106209 212694 106208 212694 106211 212694 106209 212695 106211 212695 106210 212695 106210 212696 106211 212696 106212 212696 106210 212697 106212 212697 106213 212697 106213 212698 106212 212698 105472 212698 106213 212699 105472 212699 106005 212699 106005 212700 105472 212700 105471 212700 106004 212701 104697 212701 106002 212701 106002 212702 104697 212702 106214 212702 106002 212703 106214 212703 106001 212703 106001 212704 106214 212704 106215 212704 106001 212705 106215 212705 106000 212705 106000 212706 106215 212706 105570 212706 106000 212707 105570 212707 105999 212707 105999 212708 105570 212708 105569 212708 105999 212709 105569 212709 106216 212709 106216 212710 105569 212710 105568 212710 106216 212711 105568 212711 105997 212711 105997 212712 105568 212712 104692 212712 106217 212713 105462 212713 106218 212713 106218 212714 105462 212714 105461 212714 106218 212715 105461 212715 105994 212715 105994 212716 105461 212716 105460 212716 105994 212717 105460 212717 106219 212717 106219 212718 105460 212718 105457 212718 106219 212719 105457 212719 106220 212719 106220 212720 105457 212720 106221 212720 106220 212721 106221 212721 105989 212721 105989 212722 106221 212722 105573 212722 105989 212723 105573 212723 104887 212723 104887 212724 105573 212724 105572 212724 106222 212725 105449 212725 105987 212725 105987 212726 105449 212726 105447 212726 105987 212727 105447 212727 106223 212727 106223 212728 105447 212728 105446 212728 106223 212729 105446 212729 106224 212729 106224 212730 105446 212730 106225 212730 106224 212731 106225 212731 105984 212731 105984 212732 106225 212732 106226 212732 105984 212733 106226 212733 105983 212733 105983 212734 106226 212734 105444 212734 105983 212735 105444 212735 104897 212735 104897 212736 105444 212736 105443 212736 106061 212737 104683 212737 106227 212737 106227 212738 104683 212738 105514 212738 106227 212739 105514 212739 106059 212739 106059 212740 105514 212740 106229 212740 106059 212741 106229 212741 106228 212741 106228 212742 106229 212742 106231 212742 106228 212743 106231 212743 106230 212743 106230 212744 106231 212744 105510 212744 106230 212745 105510 212745 106058 212745 106058 212746 105510 212746 106232 212746 106058 212747 106232 212747 104674 212747 104674 212748 106232 212748 104676 212748 106056 212749 104673 212749 106233 212749 106233 212750 104673 212750 106234 212750 106233 212751 106234 212751 106054 212751 106054 212752 106234 212752 106235 212752 106054 212753 106235 212753 106052 212753 106052 212754 106235 212754 106236 212754 106052 212755 106236 212755 106051 212755 106051 212756 106236 212756 105577 212756 106051 212757 105577 212757 106237 212757 106237 212758 105577 212758 106239 212758 106237 212759 106239 212759 106238 212759 106238 212760 106239 212760 105591 212760 106238 212761 105591 212761 104669 212761 104669 212762 105591 212762 105575 212762 104667 212763 106240 212763 106048 212763 106048 212764 106240 212764 106241 212764 106048 212765 106241 212765 106243 212765 106243 212766 106241 212766 106242 212766 106243 212767 106242 212767 106244 212767 106244 212768 106242 212768 105523 212768 106244 212769 105523 212769 106245 212769 106245 212770 105523 212770 106246 212770 106245 212771 106246 212771 106247 212771 106247 212772 106246 212772 106248 212772 106247 212773 106248 212773 106044 212773 106044 212774 106248 212774 105583 212774 106044 212775 105583 212775 104839 212775 104839 212776 105583 212776 105582 212776 106249 212777 104663 212777 106250 212777 106249 212778 106250 212778 106251 212778 106251 212779 106250 212779 106252 212779 106251 212780 106252 212780 105287 212780 105287 212781 106252 212781 105714 212781 105287 212782 105714 212782 106253 212782 106253 212783 105714 212783 105715 212783 106253 212784 105715 212784 105289 212784 105289 212785 105715 212785 106254 212785 105289 212786 106254 212786 105290 212786 105290 212787 106254 212787 106255 212787 105290 212788 106255 212788 105291 212788 105291 212789 106255 212789 105717 212789 105291 212790 105717 212790 105293 212790 105293 212791 105717 212791 106256 212791 105293 212792 106256 212792 105294 212792 105294 212793 106256 212793 106257 212793 105294 212794 106257 212794 105295 212794 105295 212795 106257 212795 106258 212795 105295 212796 106258 212796 105296 212796 105296 212797 106258 212797 105721 212797 105296 212798 105721 212798 106259 212798 106259 212799 105721 212799 106260 212799 106259 212800 106260 212800 106261 212800 106261 212801 106260 212801 105723 212801 106261 212802 105723 212802 106262 212802 106262 212803 105723 212803 105724 212803 106262 212804 105724 212804 106264 212804 106264 212805 105724 212805 106263 212805 106264 212806 106263 212806 106265 212806 106265 212807 106263 212807 106266 212807 106265 212808 106266 212808 106267 212808 106267 212809 106266 212809 105727 212809 106267 212810 105727 212810 106268 212810 106268 212811 105727 212811 104644 212811 106268 212812 104644 212812 105300 212812 105054 212813 105099 212813 106269 212813 106269 212814 105099 212814 105101 212814 106269 212815 105101 212815 105823 212815 105823 212816 105101 212816 105071 212816 105823 212817 105071 212817 106270 212817 106270 212818 105071 212818 106271 212818 106270 212819 106271 212819 105820 212819 105820 212820 106271 212820 105073 212820 105820 212821 105073 212821 105819 212821 105819 212822 105073 212822 106272 212822 105819 212823 106272 212823 106273 212823 106273 212824 106272 212824 105077 212824 106273 212825 105077 212825 105817 212825 105817 212826 105077 212826 106275 212826 105817 212827 106275 212827 106274 212827 106274 212828 106275 212828 106276 212828 106274 212829 106276 212829 106277 212829 106277 212830 106276 212830 105079 212830 106277 212831 105079 212831 106278 212831 106278 212832 105079 212832 106279 212832 106278 212833 106279 212833 105814 212833 105814 212834 106279 212834 105081 212834 105814 212835 105081 212835 105813 212835 105813 212836 105081 212836 105083 212836 105813 212837 105083 212837 105812 212837 105812 212838 105083 212838 106280 212838 105812 212839 106280 212839 105810 212839 105810 212840 106280 212840 105084 212840 105810 212841 105084 212841 105809 212841 105809 212842 105084 212842 105085 212842 105809 212843 105085 212843 106282 212843 106282 212844 105085 212844 106281 212844 106282 212845 106281 212845 104622 212845 104622 212846 106281 212846 105086 212846 105087 212847 106283 212847 106284 212847 105087 212848 106284 212848 105088 212848 105088 212849 106284 212849 105787 212849 105088 212850 105787 212850 106286 212850 106286 212851 105787 212851 106285 212851 106286 212852 106285 212852 106287 212852 106287 212853 106285 212853 105788 212853 106287 212854 105788 212854 106288 212854 106288 212855 105788 212855 105791 212855 106288 212856 105791 212856 105092 212856 105092 212857 105791 212857 105794 212857 105092 212858 105794 212858 106289 212858 106289 212859 105794 212859 105795 212859 106289 212860 105795 212860 106290 212860 106290 212861 105795 212861 106291 212861 106290 212862 106291 212862 106292 212862 106292 212863 106291 212863 106293 212863 106292 212864 106293 212864 106294 212864 106294 212865 106293 212865 106295 212865 106294 212866 106295 212866 105093 212866 105093 212867 106295 212867 105798 212867 105093 212868 105798 212868 106296 212868 106296 212869 105798 212869 105799 212869 106296 212870 105799 212870 105095 212870 105095 212871 105799 212871 105801 212871 105095 212872 105801 212872 105096 212872 105096 212873 105801 212873 105802 212873 105096 212874 105802 212874 106297 212874 106297 212875 105802 212875 105804 212875 106297 212876 105804 212876 106298 212876 106298 212877 105804 212877 105805 212877 106298 212878 105805 212878 105100 212878 105100 212879 105805 212879 106299 212879 105100 212880 106299 212880 105102 212880 105239 212881 105280 212881 106300 212881 105239 212882 106300 212882 105240 212882 105240 212883 106300 212883 106301 212883 105240 212884 106301 212884 106303 212884 106303 212885 106301 212885 106302 212885 106303 212886 106302 212886 106304 212886 106304 212887 106302 212887 106305 212887 106304 212888 106305 212888 105243 212888 105243 212889 106305 212889 105731 212889 105243 212890 105731 212890 105244 212890 105244 212891 105731 212891 105732 212891 105244 212892 105732 212892 106306 212892 106306 212893 105732 212893 105735 212893 106306 212894 105735 212894 106307 212894 106307 212895 105735 212895 105737 212895 106307 212896 105737 212896 106309 212896 106309 212897 105737 212897 106308 212897 106309 212898 106308 212898 105248 212898 105248 212899 106308 212899 105739 212899 105248 212900 105739 212900 106310 212900 106310 212901 105739 212901 105741 212901 106310 212902 105741 212902 106311 212902 106311 212903 105741 212903 106312 212903 106311 212904 106312 212904 106313 212904 106313 212905 106312 212905 106314 212905 106313 212906 106314 212906 106315 212906 106315 212907 106314 212907 105744 212907 106315 212908 105744 212908 106316 212908 106316 212909 105744 212909 105745 212909 106316 212910 105745 212910 105252 212910 105252 212911 105745 212911 106318 212911 105252 212912 106318 212912 106317 212912 106317 212913 106318 212913 106319 212913 106317 212914 106319 212914 105255 212914 105255 212915 106319 212915 105748 212915 105255 212916 105748 212916 104585 212916 106320 212917 105256 212917 106321 212917 106321 212918 105256 212918 106322 212918 106321 212919 106322 212919 105769 212919 105769 212920 106322 212920 105257 212920 105769 212921 105257 212921 105768 212921 105768 212922 105257 212922 105258 212922 105768 212923 105258 212923 105766 212923 105766 212924 105258 212924 106323 212924 105766 212925 106323 212925 105765 212925 105765 212926 106323 212926 105227 212926 105765 212927 105227 212927 105763 212927 105763 212928 105227 212928 105229 212928 105763 212929 105229 212929 105761 212929 105761 212930 105229 212930 105230 212930 105761 212931 105230 212931 106324 212931 106324 212932 105230 212932 105231 212932 106324 212933 105231 212933 105760 212933 105760 212934 105231 212934 105232 212934 105760 212935 105232 212935 105759 212935 105759 212936 105232 212936 106325 212936 105759 212937 106325 212937 105757 212937 105757 212938 106325 212938 106327 212938 105757 212939 106327 212939 106326 212939 106326 212940 106327 212940 106328 212940 106326 212941 106328 212941 106329 212941 106329 212942 106328 212942 105234 212942 106329 212943 105234 212943 105755 212943 105755 212944 105234 212944 105236 212944 105755 212945 105236 212945 105753 212945 105753 212946 105236 212946 106330 212946 105753 212947 106330 212947 105751 212947 105751 212948 106330 212948 106331 212948 105751 212949 106331 212949 105749 212949 105749 212950 106331 212950 106332 212950 105784 212951 105187 212951 106333 212951 106333 212952 105187 212952 105188 212952 106333 212953 105188 212953 105783 212953 105783 212954 105188 212954 105189 212954 105783 212955 105189 212955 106335 212955 106335 212956 105189 212956 106334 212956 106335 212957 106334 212957 105780 212957 105780 212958 106334 212958 106336 212958 105780 212959 106336 212959 106337 212959 106337 212960 106336 212960 105191 212960 106337 212961 105191 212961 105779 212961 105779 212962 105191 212962 106338 212962 105779 212963 106338 212963 106339 212963 106339 212964 106338 212964 106340 212964 106339 212965 106340 212965 106341 212965 106341 212966 106340 212966 105194 212966 106341 212967 105194 212967 105777 212967 105777 212968 105194 212968 105195 212968 105777 212969 105195 212969 105776 212969 105776 212970 105195 212970 105197 212970 105776 212971 105197 212971 105774 212971 105774 212972 105197 212972 105198 212972 105774 212973 105198 212973 106342 212973 106342 212974 105198 212974 106343 212974 106342 212975 106343 212975 105773 212975 105773 212976 106343 212976 106344 212976 105773 212977 106344 212977 106345 212977 106345 212978 106344 212978 106346 212978 106345 212979 106346 212979 106347 212979 106347 212980 106346 212980 105202 212980 106347 212981 105202 212981 106348 212981 106348 212982 105202 212982 105203 212982 106348 212983 105203 212983 105172 212983 105172 212984 105203 212984 105204 212984 106349 212985 104899 212985 106401 212985 105906 212986 106440 212986 106441 212986 106497 212987 104998 212987 106498 212987 106142 212988 106350 212988 104913 212988 106534 212989 106522 212989 106351 212989 106465 212990 106413 212990 106412 212990 106435 212991 106104 212991 106359 212991 104802 212992 106352 212992 104799 212992 106453 212993 106452 212993 106353 212993 106455 212994 106456 212994 106458 212994 104807 212995 106461 212995 104805 212995 106354 212996 106474 212996 104810 212996 106480 212997 106485 212997 106355 212997 106355 212998 106485 212998 104812 212998 106355 212999 104812 212999 106482 212999 106151 213000 106150 213000 104899 213000 106090 213001 106524 213001 106089 213001 106425 213002 106356 213002 106094 213002 106357 213003 106358 213003 106360 213003 106360 213004 106358 213004 104800 213004 106359 213005 106104 213005 106360 213005 106360 213006 106104 213006 106103 213006 106360 213007 106103 213007 106357 213007 106357 213008 106103 213008 106102 213008 106357 213009 106102 213009 106092 213009 106561 213010 106367 213010 106525 213010 106369 213011 104972 213011 106382 213011 106382 213012 104972 213012 105893 213012 106382 213013 105893 213013 106560 213013 106361 213014 106363 213014 106362 213014 106362 213015 106363 213015 106372 213015 106362 213016 106372 213016 106364 213016 106364 213017 106372 213017 106088 213017 106364 213018 106088 213018 106365 213018 105889 213019 106366 213019 106367 213019 106367 213020 106366 213020 106098 213020 106367 213021 106098 213021 106525 213021 106376 213022 104977 213022 106085 213022 106085 213023 104977 213023 104975 213023 106085 213024 104975 213024 106086 213024 106086 213025 104975 213025 106368 213025 106086 213026 106368 213026 106369 213026 106369 213027 106368 213027 106370 213027 106369 213028 106370 213028 104972 213028 106363 213029 106371 213029 106372 213029 106372 213030 106371 213030 104798 213030 106372 213031 104798 213031 106373 213031 106373 213032 104798 213032 106374 213032 106373 213033 106374 213033 106085 213033 106085 213034 106374 213034 106375 213034 106085 213035 106375 213035 106376 213035 106376 213036 106375 213036 106378 213036 106376 213037 106378 213037 106377 213037 106377 213038 106378 213038 104794 213038 106377 213039 104794 213039 105889 213039 105889 213040 104794 213040 106379 213040 105889 213041 106379 213041 106366 213041 106380 213042 106559 213042 106382 213042 106382 213043 106559 213043 106174 213043 104732 213044 106369 213044 106381 213044 106381 213045 106369 213045 106382 213045 106381 213046 106382 213046 106171 213046 106171 213047 106382 213047 106174 213047 104732 213048 106383 213048 106369 213048 106369 213049 106383 213049 104729 213049 106369 213050 104729 213050 106384 213050 106384 213051 104729 213051 106386 213051 106384 213052 106386 213052 106385 213052 106385 213053 106386 213053 106516 213053 106513 213054 106177 213054 106512 213054 106512 213055 106177 213055 106387 213055 106512 213056 106387 213056 106559 213056 106388 213057 106389 213057 106390 213057 106390 213058 106389 213058 106082 213058 106390 213059 106082 213059 106489 213059 106488 213060 106496 213060 106388 213060 106397 213061 106496 213061 106391 213061 106393 213062 106392 213062 106527 213062 106392 213063 106393 213063 106394 213063 106394 213064 106393 213064 106404 213064 106394 213065 106404 213065 106161 213065 106395 213066 106163 213066 106396 213066 104739 213067 104738 213067 106397 213067 106397 213068 104738 213068 106398 213068 106397 213069 106398 213069 106399 213069 106399 213070 106398 213070 106164 213070 106399 213071 106164 213071 106396 213071 106396 213072 106164 213072 106400 213072 106396 213073 106400 213073 106395 213073 104899 213074 106150 213074 106401 213074 106401 213075 106150 213075 106402 213075 106401 213076 106402 213076 104746 213076 106156 213077 106407 213077 106409 213077 104746 213078 106403 213078 106401 213078 106401 213079 106403 213079 106396 213079 106401 213080 106396 213080 106404 213080 106404 213081 106396 213081 106163 213081 106404 213082 106163 213082 106161 213082 106403 213083 104744 213083 106396 213083 106396 213084 104744 213084 106406 213084 106396 213085 106406 213085 106405 213085 106405 213086 106406 213086 106159 213086 106405 213087 106159 213087 106409 213087 106409 213088 106159 213088 106157 213088 106409 213089 106157 213089 106156 213089 106151 213090 104899 213090 106154 213090 106154 213091 104899 213091 104902 213091 106154 213092 104902 213092 106407 213092 106407 213093 104902 213093 106408 213093 106407 213094 106408 213094 106409 213094 106409 213095 106408 213095 106410 213095 106409 213096 106410 213096 104905 213096 106474 213097 106137 213097 104810 213097 104810 213098 106137 213098 106411 213098 104810 213099 106411 213099 104809 213099 106412 213100 106413 213100 104809 213100 106413 213101 105953 213101 104809 213101 104809 213102 105953 213102 106414 213102 104809 213103 106414 213103 106470 213103 106470 213104 106414 213104 105951 213104 106470 213105 105951 213105 106415 213105 106461 213106 106462 213106 104805 213106 104805 213107 106462 213107 106416 213107 104805 213108 106416 213108 104804 213108 106452 213109 106451 213109 106353 213109 106353 213110 106451 213110 106112 213110 106353 213111 106112 213111 104802 213111 104802 213112 106112 213112 106417 213112 104802 213113 106417 213113 106352 213113 106352 213114 106417 213114 106443 213114 106352 213115 106443 213115 106508 213115 106099 213116 106419 213116 106524 213116 106090 213117 106433 213117 106524 213117 106524 213118 106433 213118 106432 213118 106524 213119 106432 213119 106099 213119 106099 213120 106432 213120 106100 213120 106101 213121 106418 213121 106427 213121 106419 213122 104792 213122 106524 213122 106524 213123 104792 213123 104789 213123 106524 213124 104789 213124 106420 213124 106420 213125 104789 213125 106422 213125 106420 213126 106422 213126 106421 213126 106421 213127 106422 213127 106424 213127 106421 213128 106424 213128 106423 213128 106423 213129 106424 213129 104786 213129 106423 213130 104786 213130 106563 213130 106092 213131 106102 213131 106425 213131 106425 213132 106102 213132 104785 213132 106425 213133 104785 213133 106356 213133 106356 213134 104785 213134 106426 213134 106356 213135 106426 213135 104782 213135 106427 213136 106418 213136 106428 213136 106428 213137 106418 213137 106429 213137 106428 213138 106429 213138 106430 213138 106430 213139 106429 213139 106100 213139 106430 213140 106100 213140 106431 213140 106431 213141 106100 213141 106432 213141 106431 213142 106432 213142 104963 213142 104963 213143 106432 213143 106433 213143 104963 213144 106433 213144 104964 213144 104964 213145 106433 213145 106094 213145 104964 213146 106094 213146 105912 213146 105912 213147 106094 213147 106356 213147 105912 213148 106356 213148 106434 213148 106434 213149 106356 213149 104782 213149 106434 213150 104782 213150 105910 213150 106435 213151 106359 213151 106436 213151 106436 213152 106359 213152 106531 213152 106436 213153 106531 213153 106437 213153 105910 213154 104782 213154 106439 213154 106439 213155 104782 213155 106438 213155 106439 213156 106438 213156 106440 213156 106440 213157 106438 213157 104781 213157 106440 213158 104781 213158 106441 213158 106441 213159 104781 213159 106442 213159 106441 213160 106442 213160 106531 213160 106531 213161 106442 213161 106108 213161 106531 213162 106108 213162 106437 213162 106443 213163 106444 213163 106508 213163 106508 213164 106444 213164 106445 213164 106508 213165 106445 213165 106504 213165 106445 213166 104777 213166 106504 213166 106504 213167 104777 213167 104776 213167 106504 213168 104776 213168 104774 213168 106121 213169 106416 213169 106125 213169 106125 213170 106416 213170 106462 213170 106125 213171 106462 213171 106446 213171 106446 213172 106462 213172 106567 213172 106446 213173 106567 213173 104767 213173 104767 213174 106567 213174 106447 213174 104767 213175 106447 213175 106448 213175 105940 213176 105939 213176 106449 213176 106449 213177 105939 213177 105937 213177 106532 213178 106115 213178 104943 213178 104943 213179 106115 213179 106113 213179 104943 213180 106113 213180 106450 213180 106450 213181 106113 213181 106451 213181 106450 213182 106451 213182 105935 213182 105935 213183 106451 213183 106452 213183 105935 213184 106452 213184 105936 213184 105936 213185 106452 213185 106453 213185 105936 213186 106453 213186 106454 213186 106454 213187 106453 213187 106455 213187 106454 213188 106455 213188 105937 213188 105937 213189 106455 213189 106458 213189 105937 213190 106458 213190 106449 213190 106121 213191 106120 213191 106416 213191 106416 213192 106120 213192 106456 213192 106416 213193 106456 213193 104804 213193 104804 213194 106456 213194 106455 213194 106120 213195 106119 213195 106456 213195 106456 213196 106119 213196 106457 213196 106456 213197 106457 213197 106458 213197 106458 213198 106457 213198 106118 213198 106458 213199 106118 213199 106449 213199 106568 213200 106459 213200 106460 213200 106461 213201 106463 213201 106462 213201 106462 213202 106463 213202 106464 213202 106462 213203 106464 213203 104766 213203 104929 213204 104926 213204 106460 213204 106460 213205 104926 213205 106465 213205 104929 213206 106460 213206 104930 213206 104930 213207 106460 213207 106459 213207 104930 213208 106459 213208 106466 213208 106466 213209 106459 213209 106467 213209 106466 213210 106467 213210 106468 213210 106468 213211 106467 213211 104763 213211 106468 213212 104763 213212 105949 213212 105949 213213 104763 213213 106469 213213 105949 213214 106469 213214 106415 213214 106415 213215 106469 213215 106131 213215 106415 213216 106131 213216 106470 213216 106470 213217 106131 213217 106471 213217 106470 213218 106471 213218 104807 213218 104807 213219 106471 213219 106472 213219 104807 213220 106472 213220 106461 213220 106461 213221 106472 213221 106127 213221 106461 213222 106127 213222 106463 213222 105965 213223 106473 213223 106474 213223 106475 213224 104757 213224 106500 213224 106500 213225 104757 213225 106476 213225 106476 213226 104757 213226 104754 213226 106476 213227 104754 213227 106473 213227 106473 213228 104754 213228 104753 213228 106473 213229 104753 213229 106474 213229 106474 213230 104753 213230 106138 213230 106474 213231 106138 213231 106137 213231 106465 213232 106412 213232 106460 213232 106460 213233 106412 213233 106477 213233 106460 213234 106477 213234 104762 213234 106411 213235 106478 213235 104809 213235 104809 213236 106478 213236 106134 213236 104809 213237 106134 213237 106412 213237 106412 213238 106134 213238 106479 213238 106412 213239 106479 213239 106477 213239 106144 213240 106480 213240 106145 213240 106145 213241 106480 213241 106355 213241 106145 213242 106355 213242 106146 213242 106146 213243 106355 213243 106481 213243 106481 213244 106355 213244 104749 213244 104749 213245 106355 213245 106482 213245 104749 213246 106482 213246 104750 213246 105977 213247 106523 213247 105978 213247 105978 213248 106523 213248 104750 213248 105978 213249 104750 213249 105979 213249 105979 213250 104750 213250 106482 213250 105979 213251 106482 213251 106483 213251 106483 213252 106482 213252 104812 213252 106483 213253 104812 213253 105981 213253 105981 213254 104812 213254 106409 213254 105981 213255 106409 213255 106484 213255 106484 213256 106409 213256 104905 213256 106544 213257 106487 213257 106535 213257 106535 213258 106487 213258 106533 213258 106350 213259 106142 213259 104914 213259 106144 213260 106142 213260 106480 213260 106480 213261 106142 213261 104913 213261 106480 213262 104913 213262 106485 213262 106485 213263 104913 213263 105968 213263 106485 213264 105968 213264 106354 213264 106354 213265 105968 213265 105967 213265 106354 213266 105967 213266 106474 213266 106474 213267 105967 213267 106486 213267 106474 213268 106486 213268 105965 213268 106142 213269 106140 213269 104914 213269 104914 213270 106140 213270 106487 213270 104914 213271 106487 213271 104916 213271 104916 213272 106487 213272 106544 213272 104916 213273 106544 213273 104917 213273 104736 213274 104734 213274 106390 213274 106388 213275 106390 213275 106488 213275 106488 213276 106390 213276 104734 213276 106488 213277 104734 213277 104733 213277 104736 213278 106390 213278 104737 213278 104737 213279 106390 213279 106489 213279 104737 213280 106489 213280 106494 213280 106169 213281 106168 213281 106490 213281 106490 213282 106168 213282 106167 213282 106490 213283 106167 213283 106491 213283 106491 213284 106167 213284 106165 213284 106491 213285 106165 213285 105883 213285 105883 213286 106165 213286 106492 213286 105883 213287 106492 213287 106493 213287 106493 213288 106492 213288 106494 213288 106493 213289 106494 213289 105880 213289 105880 213290 106494 213290 106489 213290 105880 213291 106489 213291 106495 213291 106495 213292 106489 213292 106082 213292 106495 213293 106082 213293 106081 213293 104733 213294 106498 213294 106488 213294 106488 213295 106498 213295 104998 213295 106488 213296 104998 213296 106496 213296 106496 213297 104998 213297 104996 213297 106496 213298 104996 213298 106391 213298 106497 213299 106498 213299 104999 213299 104999 213300 106498 213300 106499 213300 104999 213301 106499 213301 106169 213301 104759 213302 106475 213302 106545 213302 106545 213303 106475 213303 106500 213303 106545 213304 106500 213304 106547 213304 106449 213305 104771 213305 105940 213305 105940 213306 104771 213306 104769 213306 105940 213307 104769 213307 104939 213307 104939 213308 104769 213308 106501 213308 104939 213309 106501 213309 104940 213309 104940 213310 106501 213310 106502 213310 104940 213311 106502 213311 106503 213311 105921 213312 106360 213312 106352 213312 106352 213313 106360 213313 104800 213313 106352 213314 104800 213314 104799 213314 105927 213315 106504 213315 106505 213315 106505 213316 106504 213316 106531 213316 106505 213317 106531 213317 106506 213317 105927 213318 106507 213318 106504 213318 106504 213319 106507 213319 105925 213319 106504 213320 105925 213320 106508 213320 106508 213321 105925 213321 105924 213321 106508 213322 105924 213322 106352 213322 106352 213323 105924 213323 105922 213323 106352 213324 105922 213324 105921 213324 105921 213325 106509 213325 106360 213325 106360 213326 106509 213326 104952 213326 106360 213327 104952 213327 106359 213327 106359 213328 104952 213328 104951 213328 106359 213329 104951 213329 106531 213329 106531 213330 104951 213330 104949 213330 106531 213331 104949 213331 106506 213331 106539 213332 106538 213332 105861 213332 105861 213333 106538 213333 106510 213333 105861 213334 106510 213334 106528 213334 106511 213335 106558 213335 105881 213335 105881 213336 106558 213336 106557 213336 105881 213337 106557 213337 106541 213337 106512 213338 104987 213338 106513 213338 106513 213339 104987 213339 106514 213339 106513 213340 106514 213340 106516 213340 106516 213341 106514 213341 106515 213341 106516 213342 106515 213342 106385 213342 106385 213343 106515 213343 106517 213343 106385 213344 106517 213344 106081 213344 106081 213345 106517 213345 104985 213345 106081 213346 104985 213346 106495 213346 106495 213347 104985 213347 105878 213347 106495 213348 105878 213348 105880 213348 106518 213349 106101 213349 106519 213349 106519 213350 106101 213350 106427 213350 106519 213351 106427 213351 106520 213351 106520 213352 106427 213352 105904 213352 106521 213353 106536 213353 105976 213353 105976 213354 106536 213354 106351 213354 105976 213355 106351 213355 105977 213355 105977 213356 106351 213356 106522 213356 105977 213357 106522 213357 106523 213357 106089 213358 106524 213358 106365 213358 106365 213359 106524 213359 106420 213359 106365 213360 106420 213360 106364 213360 106364 213361 106420 213361 106421 213361 106364 213362 106421 213362 106362 213362 106362 213363 106421 213363 106525 213363 106362 213364 106525 213364 106361 213364 106391 213365 105867 213365 106397 213365 106397 213366 105867 213366 105866 213366 106397 213367 105866 213367 104739 213367 104739 213368 105866 213368 106526 213368 104739 213369 106526 213369 104740 213369 104740 213370 106526 213370 105863 213370 104740 213371 105863 213371 106527 213371 106527 213372 105863 213372 106528 213372 106527 213373 106528 213373 106393 213373 106393 213374 106528 213374 106510 213374 106393 213375 106510 213375 106404 213375 106404 213376 106510 213376 106529 213376 106404 213377 106529 213377 106401 213377 106401 213378 106529 213378 106536 213378 106401 213379 106536 213379 106349 213379 106349 213380 106536 213380 106521 213380 105904 213381 105906 213381 106520 213381 106520 213382 105906 213382 106441 213382 106520 213383 106441 213383 106530 213383 106530 213384 106441 213384 106531 213384 106530 213385 106531 213385 106502 213385 106502 213386 106531 213386 106504 213386 106502 213387 106504 213387 106503 213387 106503 213388 106504 213388 104774 213388 106503 213389 104774 213389 106532 213389 106532 213390 104774 213390 106116 213390 106532 213391 106116 213391 106115 213391 106533 213392 106534 213392 106535 213392 106535 213393 106534 213393 106351 213393 106535 213394 106351 213394 106543 213394 106543 213395 106351 213395 106536 213395 106543 213396 106536 213396 106542 213396 106542 213397 106536 213397 106529 213397 106542 213398 106529 213398 106537 213398 106537 213399 106529 213399 106510 213399 106537 213400 106510 213400 106490 213400 106490 213401 106510 213401 106538 213401 106490 213402 106538 213402 106169 213402 106169 213403 106538 213403 106539 213403 106169 213404 106539 213404 104999 213404 104786 213405 106518 213405 106563 213405 106563 213406 106518 213406 106519 213406 106563 213407 106519 213407 106540 213407 106540 213408 106519 213408 106520 213408 106540 213409 106520 213409 106564 213409 106564 213410 106520 213410 106530 213410 106564 213411 106530 213411 106566 213411 106566 213412 106530 213412 106502 213412 106566 213413 106502 213413 106447 213413 106447 213414 106502 213414 106501 213414 106447 213415 106501 213415 106448 213415 106448 213416 106501 213416 104769 213416 105883 213417 106541 213417 106491 213417 106491 213418 106541 213418 106557 213418 106491 213419 106557 213419 106490 213419 106490 213420 106557 213420 106555 213420 106490 213421 106555 213421 106537 213421 106537 213422 106555 213422 106554 213422 106537 213423 106554 213423 106542 213423 106542 213424 106554 213424 106553 213424 106542 213425 106553 213425 106543 213425 106543 213426 106553 213426 106551 213426 106543 213427 106551 213427 106535 213427 106535 213428 106551 213428 106549 213428 106535 213429 106549 213429 106544 213429 106544 213430 106549 213430 106547 213430 106544 213431 106547 213431 104917 213431 104917 213432 106547 213432 106500 213432 104762 213433 104759 213433 106460 213433 106460 213434 104759 213434 106545 213434 106460 213435 106545 213435 106546 213435 106546 213436 106545 213436 106547 213436 106546 213437 106547 213437 106548 213437 106548 213438 106547 213438 106549 213438 106548 213439 106549 213439 106565 213439 106565 213440 106549 213440 106551 213440 106565 213441 106551 213441 106550 213441 106550 213442 106551 213442 106553 213442 106550 213443 106553 213443 106552 213443 106552 213444 106553 213444 106554 213444 106552 213445 106554 213445 106562 213445 106562 213446 106554 213446 106555 213446 106562 213447 106555 213447 106556 213447 106556 213448 106555 213448 106557 213448 106556 213449 106557 213449 106380 213449 106380 213450 106557 213450 106558 213450 106380 213451 106558 213451 106559 213451 106559 213452 106558 213452 106511 213452 106559 213453 106511 213453 106512 213453 106560 213454 106561 213454 106382 213454 106382 213455 106561 213455 106525 213455 106382 213456 106525 213456 106380 213456 106380 213457 106525 213457 106421 213457 106380 213458 106421 213458 106556 213458 106556 213459 106421 213459 106423 213459 106556 213460 106423 213460 106562 213460 106562 213461 106423 213461 106563 213461 106562 213462 106563 213462 106552 213462 106552 213463 106563 213463 106540 213463 106552 213464 106540 213464 106550 213464 106550 213465 106540 213465 106564 213465 106550 213466 106564 213466 106565 213466 106565 213467 106564 213467 106566 213467 106565 213468 106566 213468 106548 213468 106548 213469 106566 213469 106447 213469 106548 213470 106447 213470 106546 213470 106546 213471 106447 213471 106567 213471 106546 213472 106567 213472 106460 213472 106460 213473 106567 213473 106462 213473 106460 213474 106462 213474 106568 213474 106568 213475 106462 213475 104766 213475 106569 213476 106595 213476 106582 213476 106583 213477 106570 213477 106878 213477 106571 213478 106570 213478 106572 213478 106572 213479 106570 213479 106583 213479 106572 213480 106583 213480 106573 213480 106573 213481 106583 213481 106577 213481 106922 213482 106574 213482 106583 213482 106583 213483 106574 213483 106575 213483 106575 213484 106895 213484 106583 213484 106583 213485 106895 213485 106576 213485 106583 213486 106576 213486 106577 213486 106941 213487 106939 213487 106569 213487 106569 213488 106939 213488 106938 213488 106931 213489 106595 213489 106578 213489 106578 213490 106595 213490 106569 213490 106578 213491 106569 213491 106932 213491 106932 213492 106569 213492 106938 213492 106580 213493 106930 213493 106569 213493 106569 213494 106930 213494 106579 213494 106569 213495 106579 213495 106941 213495 106580 213496 106569 213496 106581 213496 106581 213497 106569 213497 106582 213497 106581 213498 106582 213498 106879 213498 106879 213499 106582 213499 106593 213499 106879 213500 106593 213500 106878 213500 106878 213501 106593 213501 106591 213501 106878 213502 106591 213502 106583 213502 106583 213503 106591 213503 106584 213503 106583 213504 106584 213504 106922 213504 106585 213505 106805 213505 106880 213505 106586 213506 106587 213506 106599 213506 106600 213507 106919 213507 106598 213507 106588 213508 106589 213508 106590 213508 106589 213509 106584 213509 106590 213509 106590 213510 106584 213510 106591 213510 106590 213511 106591 213511 106592 213511 106592 213512 106591 213512 106593 213512 106592 213513 106593 213513 106596 213513 106596 213514 106593 213514 106582 213514 106596 213515 106582 213515 106594 213515 106594 213516 106582 213516 106595 213516 106594 213517 106586 213517 106596 213517 106596 213518 106586 213518 106599 213518 106596 213519 106599 213519 106592 213519 106592 213520 106599 213520 106597 213520 106592 213521 106597 213521 106590 213521 106590 213522 106597 213522 106598 213522 106590 213523 106598 213523 106588 213523 106588 213524 106598 213524 106919 213524 106587 213525 106585 213525 106599 213525 106599 213526 106585 213526 106880 213526 106599 213527 106880 213527 106597 213527 106597 213528 106880 213528 106881 213528 106597 213529 106881 213529 106598 213529 106598 213530 106881 213530 106601 213530 106598 213531 106601 213531 106600 213531 106600 213532 106601 213532 106602 213532 106619 213533 106824 213533 106603 213533 106619 213534 106603 213534 106604 213534 106603 213535 106647 213535 106604 213535 106604 213536 106647 213536 106606 213536 106604 213537 106606 213537 106605 213537 106605 213538 106606 213538 106815 213538 106815 213539 106606 213539 106607 213539 106815 213540 106607 213540 106608 213540 106643 213541 106832 213541 106644 213541 106644 213542 106832 213542 106833 213542 106644 213543 106833 213543 106646 213543 106646 213544 106833 213544 106834 213544 106646 213545 106834 213545 106609 213545 106609 213546 106834 213546 106835 213546 106610 213547 106608 213547 106607 213547 106626 213548 106841 213548 106611 213548 106607 213549 106621 213549 106610 213549 106610 213550 106621 213550 106634 213550 106610 213551 106634 213551 106611 213551 106611 213552 106634 213552 106635 213552 106611 213553 106635 213553 106626 213553 106626 213554 106627 213554 106841 213554 106841 213555 106627 213555 106612 213555 106841 213556 106612 213556 106614 213556 106609 213557 106835 213557 106623 213557 106623 213558 106835 213558 106837 213558 106623 213559 106837 213559 106625 213559 106625 213560 106837 213560 106614 213560 106625 213561 106614 213561 106613 213561 106613 213562 106614 213562 106612 213562 106603 213563 106824 213563 106615 213563 106615 213564 106824 213564 106831 213564 106615 213565 106831 213565 106616 213565 106616 213566 106831 213566 106830 213566 106616 213567 106830 213567 106640 213567 106640 213568 106830 213568 106829 213568 106640 213569 106829 213569 106797 213569 106797 213570 106829 213570 106617 213570 106618 213571 106619 213571 106817 213571 106817 213572 106619 213572 106604 213572 106817 213573 106604 213573 106620 213573 106620 213574 106604 213574 106605 213574 106620 213575 106605 213575 106813 213575 106813 213576 106605 213576 106815 213576 106813 213577 106815 213577 106814 213577 106621 213578 106607 213578 106632 213578 106674 213579 106609 213579 106622 213579 106622 213580 106609 213580 106623 213580 106622 213581 106623 213581 106624 213581 106624 213582 106623 213582 106680 213582 106612 213583 106681 213583 106613 213583 106613 213584 106681 213584 106680 213584 106613 213585 106680 213585 106625 213585 106625 213586 106680 213586 106623 213586 106626 213587 106684 213587 106627 213587 106627 213588 106684 213588 106628 213588 106627 213589 106628 213589 106612 213589 106612 213590 106628 213590 106683 213590 106612 213591 106683 213591 106681 213591 106629 213592 106630 213592 106635 213592 106635 213593 106630 213593 106631 213593 106635 213594 106631 213594 106626 213594 106626 213595 106631 213595 106676 213595 106626 213596 106676 213596 106684 213596 106632 213597 106633 213597 106621 213597 106621 213598 106633 213598 106629 213598 106621 213599 106629 213599 106634 213599 106634 213600 106629 213600 106635 213600 106774 213601 106603 213601 106636 213601 106636 213602 106603 213602 106615 213602 106636 213603 106615 213603 106720 213603 106720 213604 106615 213604 106616 213604 106720 213605 106616 213605 106637 213605 106637 213606 106616 213606 106638 213606 106638 213607 106616 213607 106640 213607 106638 213608 106640 213608 106639 213608 106639 213609 106640 213609 106641 213609 106641 213610 106640 213610 106797 213610 106641 213611 106797 213611 106724 213611 106800 213612 106643 213612 106642 213612 106642 213613 106643 213613 106644 213613 106642 213614 106644 213614 106645 213614 106645 213615 106644 213615 106646 213615 106645 213616 106646 213616 106674 213616 106674 213617 106646 213617 106609 213617 106632 213618 106607 213618 106606 213618 106632 213619 106606 213619 106778 213619 106778 213620 106606 213620 106647 213620 106778 213621 106647 213621 106772 213621 106772 213622 106647 213622 106603 213622 106772 213623 106603 213623 106774 213623 106650 213624 106648 213624 106649 213624 106670 213625 106650 213625 106697 213625 106663 213626 106652 213626 106651 213626 106651 213627 106652 213627 106653 213627 106651 213628 106653 213628 106783 213628 106783 213629 106653 213629 106654 213629 106783 213630 106654 213630 106655 213630 106655 213631 106654 213631 106666 213631 106665 213632 106656 213632 106657 213632 106703 213633 106658 213633 106659 213633 106659 213634 106658 213634 106660 213634 106659 213635 106660 213635 106665 213635 106665 213636 106660 213636 106661 213636 106665 213637 106661 213637 106656 213637 106664 213638 106652 213638 106662 213638 106662 213639 106652 213639 106663 213639 106662 213640 106663 213640 106780 213640 106664 213641 106703 213641 106652 213641 106652 213642 106703 213642 106659 213642 106652 213643 106659 213643 106653 213643 106653 213644 106659 213644 106665 213644 106653 213645 106665 213645 106654 213645 106654 213646 106665 213646 106657 213646 106654 213647 106657 213647 106666 213647 106667 213648 106668 213648 106664 213648 106664 213649 106668 213649 106669 213649 106664 213650 106669 213650 106703 213650 106699 213651 106670 213651 106700 213651 106700 213652 106670 213652 106697 213652 106700 213653 106697 213653 106671 213653 106671 213654 106697 213654 106701 213654 106691 213655 106679 213655 106682 213655 106624 213656 106672 213656 106622 213656 106622 213657 106672 213657 106673 213657 106622 213658 106673 213658 106674 213658 106678 213659 106633 213659 106675 213659 106675 213660 106633 213660 106632 213660 106675 213661 106632 213661 106696 213661 106676 213662 106631 213662 106677 213662 106677 213663 106631 213663 106630 213663 106677 213664 106630 213664 106678 213664 106678 213665 106630 213665 106629 213665 106678 213666 106629 213666 106633 213666 106624 213667 106680 213667 106679 213667 106679 213668 106680 213668 106681 213668 106679 213669 106681 213669 106682 213669 106682 213670 106681 213670 106683 213670 106682 213671 106683 213671 106692 213671 106692 213672 106683 213672 106628 213672 106692 213673 106628 213673 106677 213673 106677 213674 106628 213674 106684 213674 106677 213675 106684 213675 106676 213675 106691 213676 106685 213676 106702 213676 106702 213677 106685 213677 106693 213677 106702 213678 106693 213678 106686 213678 106686 213679 106693 213679 106694 213679 106686 213680 106694 213680 106687 213680 106687 213681 106694 213681 106688 213681 106687 213682 106688 213682 106704 213682 106704 213683 106688 213683 106695 213683 106704 213684 106695 213684 106689 213684 106689 213685 106695 213685 106690 213685 106689 213686 106690 213686 106775 213686 106691 213687 106682 213687 106685 213687 106685 213688 106682 213688 106692 213688 106685 213689 106692 213689 106693 213689 106693 213690 106692 213690 106677 213690 106693 213691 106677 213691 106694 213691 106694 213692 106677 213692 106678 213692 106694 213693 106678 213693 106688 213693 106688 213694 106678 213694 106675 213694 106688 213695 106675 213695 106695 213695 106695 213696 106675 213696 106696 213696 106695 213697 106696 213697 106690 213697 106650 213698 106649 213698 106697 213698 106697 213699 106649 213699 106754 213699 106697 213700 106754 213700 106701 213700 106701 213701 106754 213701 106698 213701 106701 213702 106698 213702 106757 213702 106780 213703 106699 213703 106662 213703 106662 213704 106699 213704 106700 213704 106662 213705 106700 213705 106664 213705 106664 213706 106700 213706 106671 213706 106664 213707 106671 213707 106667 213707 106667 213708 106671 213708 106701 213708 106667 213709 106701 213709 106672 213709 106672 213710 106701 213710 106757 213710 106672 213711 106757 213711 106673 213711 106624 213712 106679 213712 106672 213712 106672 213713 106679 213713 106691 213713 106672 213714 106691 213714 106667 213714 106667 213715 106691 213715 106702 213715 106667 213716 106702 213716 106668 213716 106668 213717 106702 213717 106686 213717 106668 213718 106686 213718 106669 213718 106669 213719 106686 213719 106687 213719 106669 213720 106687 213720 106703 213720 106703 213721 106687 213721 106704 213721 106703 213722 106704 213722 106658 213722 106658 213723 106704 213723 106689 213723 106658 213724 106689 213724 106660 213724 106660 213725 106689 213725 106775 213725 106660 213726 106775 213726 106661 213726 106728 213727 106800 213727 106762 213727 106749 213728 106745 213728 106711 213728 106743 213729 106758 213729 106730 213729 106789 213730 106788 213730 106709 213730 106764 213731 106771 213731 106705 213731 106705 213732 106771 213732 106717 213732 106705 213733 106717 213733 106706 213733 106706 213734 106717 213734 106716 213734 106706 213735 106716 213735 106790 213735 106790 213736 106716 213736 106715 213736 106709 213737 106788 213737 106708 213737 106708 213738 106788 213738 106710 213738 106708 213739 106710 213739 106711 213739 106707 213740 106730 213740 106786 213740 106711 213741 106745 213741 106708 213741 106708 213742 106745 213742 106744 213742 106708 213743 106744 213743 106709 213743 106710 213744 106713 213744 106711 213744 106711 213745 106713 213745 106714 213745 106711 213746 106714 213746 106749 213746 106749 213747 106714 213747 106712 213747 106749 213748 106712 213748 106750 213748 106750 213749 106712 213749 106718 213749 106750 213750 106718 213750 106752 213750 106752 213751 106718 213751 106719 213751 106752 213752 106719 213752 106769 213752 106713 213753 106715 213753 106714 213753 106714 213754 106715 213754 106716 213754 106714 213755 106716 213755 106712 213755 106712 213756 106716 213756 106717 213756 106712 213757 106717 213757 106718 213757 106718 213758 106717 213758 106771 213758 106718 213759 106771 213759 106719 213759 106737 213760 106638 213760 106639 213760 106737 213761 106639 213761 106723 213761 106638 213762 106737 213762 106637 213762 106637 213763 106737 213763 106736 213763 106637 213764 106736 213764 106720 213764 106720 213765 106736 213765 106721 213765 106720 213766 106721 213766 106636 213766 106774 213767 106636 213767 106722 213767 106722 213768 106636 213768 106721 213768 106722 213769 106721 213769 106763 213769 106639 213770 106641 213770 106723 213770 106723 213771 106641 213771 106724 213771 106723 213772 106724 213772 106725 213772 106725 213773 106724 213773 106798 213773 106725 213774 106798 213774 106741 213774 106741 213775 106798 213775 106726 213775 106741 213776 106726 213776 106796 213776 106796 213777 106727 213777 106741 213777 106741 213778 106727 213778 106728 213778 106741 213779 106728 213779 106729 213779 106729 213780 106728 213780 106762 213780 106729 213781 106762 213781 106759 213781 106730 213782 106707 213782 106743 213782 106743 213783 106707 213783 106731 213783 106743 213784 106731 213784 106742 213784 106742 213785 106731 213785 106746 213785 106742 213786 106746 213786 106740 213786 106740 213787 106746 213787 106747 213787 106740 213788 106747 213788 106739 213788 106739 213789 106747 213789 106748 213789 106739 213790 106748 213790 106732 213790 106732 213791 106748 213791 106733 213791 106732 213792 106733 213792 106738 213792 106738 213793 106733 213793 106751 213793 106738 213794 106751 213794 106734 213794 106734 213795 106751 213795 106735 213795 106734 213796 106735 213796 106763 213796 106763 213797 106721 213797 106734 213797 106734 213798 106721 213798 106736 213798 106734 213799 106736 213799 106738 213799 106738 213800 106736 213800 106737 213800 106738 213801 106737 213801 106732 213801 106732 213802 106737 213802 106723 213802 106732 213803 106723 213803 106739 213803 106739 213804 106723 213804 106725 213804 106739 213805 106725 213805 106740 213805 106740 213806 106725 213806 106741 213806 106740 213807 106741 213807 106742 213807 106742 213808 106741 213808 106729 213808 106742 213809 106729 213809 106743 213809 106743 213810 106729 213810 106759 213810 106743 213811 106759 213811 106758 213811 106786 213812 106789 213812 106707 213812 106707 213813 106789 213813 106709 213813 106707 213814 106709 213814 106731 213814 106731 213815 106709 213815 106744 213815 106731 213816 106744 213816 106746 213816 106746 213817 106744 213817 106745 213817 106746 213818 106745 213818 106747 213818 106747 213819 106745 213819 106749 213819 106747 213820 106749 213820 106748 213820 106748 213821 106749 213821 106750 213821 106748 213822 106750 213822 106733 213822 106733 213823 106750 213823 106752 213823 106733 213824 106752 213824 106751 213824 106751 213825 106752 213825 106769 213825 106751 213826 106769 213826 106735 213826 106753 213827 106755 213827 106761 213827 106792 213828 106786 213828 106730 213828 106649 213829 106648 213829 106795 213829 106698 213830 106754 213830 106753 213830 106753 213831 106754 213831 106649 213831 106649 213832 106795 213832 106753 213832 106753 213833 106795 213833 106794 213833 106753 213834 106794 213834 106755 213834 106755 213835 106794 213835 106756 213835 106755 213836 106756 213836 106792 213836 106673 213837 106757 213837 106760 213837 106760 213838 106757 213838 106698 213838 106674 213839 106673 213839 106645 213839 106645 213840 106673 213840 106760 213840 106645 213841 106760 213841 106642 213841 106792 213842 106730 213842 106755 213842 106755 213843 106730 213843 106758 213843 106755 213844 106758 213844 106761 213844 106761 213845 106758 213845 106759 213845 106761 213846 106759 213846 106762 213846 106698 213847 106753 213847 106760 213847 106760 213848 106753 213848 106761 213848 106760 213849 106761 213849 106642 213849 106642 213850 106761 213850 106762 213850 106642 213851 106762 213851 106800 213851 106722 213852 106763 213852 106773 213852 106768 213853 106793 213853 106767 213853 106764 213854 106765 213854 106771 213854 106771 213855 106765 213855 106770 213855 106655 213856 106666 213856 106779 213856 106779 213857 106666 213857 106793 213857 106776 213858 106777 213858 106766 213858 106766 213859 106777 213859 106770 213859 106793 213860 106666 213860 106767 213860 106767 213861 106666 213861 106657 213861 106767 213862 106657 213862 106656 213862 106765 213863 106768 213863 106770 213863 106770 213864 106768 213864 106767 213864 106770 213865 106767 213865 106766 213865 106766 213866 106767 213866 106656 213866 106763 213867 106735 213867 106777 213867 106777 213868 106735 213868 106769 213868 106777 213869 106769 213869 106770 213869 106770 213870 106769 213870 106719 213870 106770 213871 106719 213871 106771 213871 106778 213872 106772 213872 106773 213872 106773 213873 106772 213873 106774 213873 106773 213874 106774 213874 106722 213874 106656 213875 106661 213875 106766 213875 106766 213876 106661 213876 106775 213876 106766 213877 106775 213877 106776 213877 106776 213878 106775 213878 106690 213878 106776 213879 106690 213879 106696 213879 106763 213880 106777 213880 106773 213880 106773 213881 106777 213881 106776 213881 106773 213882 106776 213882 106778 213882 106778 213883 106776 213883 106696 213883 106778 213884 106696 213884 106632 213884 106782 213885 106655 213885 106779 213885 106782 213886 106780 213886 106781 213886 106781 213887 106651 213887 106782 213887 106782 213888 106651 213888 106783 213888 106782 213889 106783 213889 106655 213889 106784 213890 106670 213890 106782 213890 106782 213891 106670 213891 106785 213891 106782 213892 106785 213892 106780 213892 106791 213893 106786 213893 106792 213893 106787 213894 106788 213894 106791 213894 106791 213895 106788 213895 106789 213895 106791 213896 106789 213896 106786 213896 106764 213897 106705 213897 106791 213897 106791 213898 106705 213898 106706 213898 106791 213899 106706 213899 106790 213899 106790 213900 106715 213900 106791 213900 106791 213901 106715 213901 106713 213901 106791 213902 106713 213902 106787 213902 106764 213903 106791 213903 106765 213903 106765 213904 106791 213904 106792 213904 106765 213905 106792 213905 106768 213905 106768 213906 106792 213906 106756 213906 106768 213907 106756 213907 106793 213907 106793 213908 106756 213908 106794 213908 106793 213909 106794 213909 106779 213909 106779 213910 106794 213910 106795 213910 106779 213911 106795 213911 106782 213911 106782 213912 106795 213912 106648 213912 106782 213913 106648 213913 106784 213913 106728 213914 106727 213914 106801 213914 106727 213915 106796 213915 106801 213915 106801 213916 106796 213916 106726 213916 106801 213917 106726 213917 106797 213917 106797 213918 106726 213918 106798 213918 106797 213919 106798 213919 106724 213919 106801 213920 106799 213920 106728 213920 106728 213921 106799 213921 106643 213921 106728 213922 106643 213922 106800 213922 106797 213923 106617 213923 106801 213923 106801 213924 106617 213924 106828 213924 106801 213925 106828 213925 106799 213925 106799 213926 106828 213926 106827 213926 106799 213927 106827 213927 106643 213927 106643 213928 106827 213928 106832 213928 106802 213929 106803 213929 106808 213929 106956 213930 106955 213930 106804 213930 106808 213931 106803 213931 106804 213931 106804 213932 106803 213932 106959 213932 106804 213933 106959 213933 106956 213933 106807 213934 106809 213934 106805 213934 106805 213935 106806 213935 106807 213935 106807 213936 106806 213936 106961 213936 106807 213937 106961 213937 106808 213937 106808 213938 106961 213938 106960 213938 106808 213939 106960 213939 106802 213939 106804 213940 106840 213940 106808 213940 106808 213941 106840 213941 106839 213941 106808 213942 106839 213942 106807 213942 106807 213943 106839 213943 106838 213943 106807 213944 106838 213944 106809 213944 106809 213945 106838 213945 106836 213945 106816 213946 106810 213946 106811 213946 106811 213947 106810 213947 106812 213947 106811 213948 106812 213948 106804 213948 106804 213949 106812 213949 106840 213949 106861 213950 106813 213950 106863 213950 106863 213951 106813 213951 106814 213951 106863 213952 106814 213952 106816 213952 106816 213953 106814 213953 106815 213953 106816 213954 106815 213954 106810 213954 106859 213955 106825 213955 106819 213955 106817 213956 106843 213956 106618 213956 106618 213957 106843 213957 106818 213957 106618 213958 106818 213958 106619 213958 106619 213959 106818 213959 106855 213959 106619 213960 106855 213960 106819 213960 106819 213961 106855 213961 106857 213961 106819 213962 106857 213962 106859 213962 106859 213963 106820 213963 106825 213963 106825 213964 106820 213964 106854 213964 106825 213965 106854 213965 106826 213965 106849 213966 106821 213966 106851 213966 106851 213967 106821 213967 106822 213967 106851 213968 106822 213968 106823 213968 106823 213969 106822 213969 106826 213969 106823 213970 106826 213970 106852 213970 106852 213971 106826 213971 106854 213971 106824 213972 106619 213972 106819 213972 106617 213973 106825 213973 106826 213973 106832 213974 106827 213974 106826 213974 106826 213975 106827 213975 106828 213975 106826 213976 106828 213976 106617 213976 106617 213977 106829 213977 106825 213977 106825 213978 106829 213978 106830 213978 106825 213979 106830 213979 106819 213979 106819 213980 106830 213980 106831 213980 106819 213981 106831 213981 106824 213981 106826 213982 106822 213982 106832 213982 106832 213983 106822 213983 106821 213983 106832 213984 106821 213984 106833 213984 106833 213985 106821 213985 106850 213985 106833 213986 106850 213986 106834 213986 106834 213987 106850 213987 106836 213987 106834 213988 106836 213988 106835 213988 106835 213989 106836 213989 106838 213989 106835 213990 106838 213990 106837 213990 106837 213991 106838 213991 106839 213991 106837 213992 106839 213992 106614 213992 106614 213993 106839 213993 106840 213993 106815 213994 106608 213994 106810 213994 106810 213995 106608 213995 106610 213995 106810 213996 106610 213996 106812 213996 106812 213997 106610 213997 106611 213997 106812 213998 106611 213998 106840 213998 106840 213999 106611 213999 106841 213999 106840 214000 106841 214000 106614 214000 106813 214001 106861 214001 106842 214001 106813 214002 106842 214002 106620 214002 106620 214003 106842 214003 106843 214003 106620 214004 106843 214004 106817 214004 106865 214005 106843 214005 106844 214005 106844 214006 106843 214006 106842 214006 106844 214007 106842 214007 106845 214007 106861 214008 106846 214008 106842 214008 106842 214009 106846 214009 106847 214009 106842 214010 106847 214010 106845 214010 106809 214011 106836 214011 106848 214011 106848 214012 106836 214012 106850 214012 106848 214013 106850 214013 106849 214013 106849 214014 106850 214014 106821 214014 106818 214015 106843 214015 106865 214015 106602 214016 106849 214016 106918 214016 106918 214017 106849 214017 106851 214017 106918 214018 106851 214018 106923 214018 106923 214019 106851 214019 106924 214019 106851 214020 106823 214020 106924 214020 106924 214021 106823 214021 106852 214021 106924 214022 106852 214022 106853 214022 106859 214023 106860 214023 106820 214023 106820 214024 106860 214024 106853 214024 106820 214025 106853 214025 106854 214025 106854 214026 106853 214026 106852 214026 106855 214027 106856 214027 106857 214027 106857 214028 106856 214028 106858 214028 106857 214029 106858 214029 106859 214029 106859 214030 106858 214030 106901 214030 106859 214031 106901 214031 106860 214031 106865 214032 106906 214032 106818 214032 106818 214033 106906 214033 106917 214033 106818 214034 106917 214034 106855 214034 106855 214035 106917 214035 106900 214035 106855 214036 106900 214036 106856 214036 106846 214037 106861 214037 106862 214037 106862 214038 106861 214038 106863 214038 106862 214039 106863 214039 106951 214039 106951 214040 106863 214040 106816 214040 106951 214041 106816 214041 106864 214041 106864 214042 106816 214042 106949 214042 106949 214043 106816 214043 106811 214043 106949 214044 106811 214044 106948 214044 106948 214045 106811 214045 106947 214045 106947 214046 106811 214046 106804 214046 106947 214047 106804 214047 106955 214047 106875 214048 106946 214048 106580 214048 106946 214049 106875 214049 106877 214049 106867 214050 106870 214050 106874 214050 106904 214051 106865 214051 106844 214051 106869 214052 106866 214052 106867 214052 106867 214053 106866 214053 106904 214053 106904 214054 106844 214054 106867 214054 106867 214055 106844 214055 106845 214055 106867 214056 106845 214056 106870 214056 106870 214057 106845 214057 106847 214057 106870 214058 106847 214058 106846 214058 106873 214059 106902 214059 106868 214059 106868 214060 106902 214060 106869 214060 106846 214061 106952 214061 106870 214061 106870 214062 106952 214062 106954 214062 106870 214063 106954 214063 106874 214063 106874 214064 106954 214064 106871 214064 106874 214065 106871 214065 106876 214065 106883 214066 106873 214066 106872 214066 106872 214067 106873 214067 106868 214067 106872 214068 106868 214068 106875 214068 106869 214069 106867 214069 106868 214069 106868 214070 106867 214070 106874 214070 106868 214071 106874 214071 106875 214071 106875 214072 106874 214072 106876 214072 106875 214073 106876 214073 106877 214073 106570 214074 106883 214074 106878 214074 106878 214075 106883 214075 106872 214075 106878 214076 106872 214076 106879 214076 106879 214077 106872 214077 106875 214077 106879 214078 106875 214078 106581 214078 106581 214079 106875 214079 106580 214079 106805 214080 106809 214080 106880 214080 106880 214081 106809 214081 106848 214081 106880 214082 106848 214082 106881 214082 106881 214083 106848 214083 106601 214083 106601 214084 106848 214084 106849 214084 106601 214085 106849 214085 106602 214085 106896 214086 106891 214086 106892 214086 106577 214087 106576 214087 106886 214087 106574 214088 106922 214088 106890 214088 106896 214089 106895 214089 106891 214089 106891 214090 106895 214090 106575 214090 106891 214091 106575 214091 106574 214091 106571 214092 106572 214092 106928 214092 106928 214093 106572 214093 106573 214093 106928 214094 106573 214094 106884 214094 106928 214095 106882 214095 106571 214095 106571 214096 106882 214096 106883 214096 106571 214097 106883 214097 106570 214097 106573 214098 106577 214098 106884 214098 106884 214099 106577 214099 106886 214099 106884 214100 106886 214100 106885 214100 106885 214101 106886 214101 106887 214101 106885 214102 106887 214102 106927 214102 106927 214103 106887 214103 106897 214103 106927 214104 106897 214104 106888 214104 106888 214105 106897 214105 106889 214105 106888 214106 106889 214106 106925 214106 106918 214107 106923 214107 106920 214107 106920 214108 106923 214108 106894 214108 106574 214109 106890 214109 106891 214109 106891 214110 106890 214110 106921 214110 106891 214111 106921 214111 106892 214111 106892 214112 106921 214112 106920 214112 106892 214113 106920 214113 106893 214113 106893 214114 106920 214114 106894 214114 106893 214115 106894 214115 106898 214115 106576 214116 106895 214116 106886 214116 106886 214117 106895 214117 106896 214117 106886 214118 106896 214118 106887 214118 106887 214119 106896 214119 106892 214119 106887 214120 106892 214120 106897 214120 106897 214121 106892 214121 106893 214121 106897 214122 106893 214122 106889 214122 106889 214123 106893 214123 106898 214123 106889 214124 106898 214124 106925 214124 106858 214125 106856 214125 106899 214125 106899 214126 106856 214126 106900 214126 106899 214127 106900 214127 106917 214127 106860 214128 106901 214128 106907 214128 106873 214129 106912 214129 106902 214129 106902 214130 106912 214130 106913 214130 106902 214131 106913 214131 106869 214131 106869 214132 106913 214132 106915 214132 106869 214133 106915 214133 106866 214133 106866 214134 106915 214134 106903 214134 106866 214135 106903 214135 106904 214135 106904 214136 106903 214136 106905 214136 106904 214137 106905 214137 106865 214137 106865 214138 106905 214138 106906 214138 106901 214139 106858 214139 106907 214139 106907 214140 106858 214140 106899 214140 106907 214141 106899 214141 106926 214141 106926 214142 106899 214142 106909 214142 106926 214143 106909 214143 106908 214143 106908 214144 106909 214144 106916 214144 106908 214145 106916 214145 106910 214145 106910 214146 106916 214146 106911 214146 106910 214147 106911 214147 106914 214147 106912 214148 106914 214148 106913 214148 106913 214149 106914 214149 106911 214149 106913 214150 106911 214150 106915 214150 106915 214151 106911 214151 106916 214151 106915 214152 106916 214152 106903 214152 106903 214153 106916 214153 106909 214153 106903 214154 106909 214154 106905 214154 106905 214155 106909 214155 106899 214155 106905 214156 106899 214156 106906 214156 106906 214157 106899 214157 106917 214157 106602 214158 106918 214158 106600 214158 106600 214159 106918 214159 106920 214159 106600 214160 106920 214160 106919 214160 106919 214161 106920 214161 106921 214161 106919 214162 106921 214162 106588 214162 106588 214163 106921 214163 106890 214163 106588 214164 106890 214164 106589 214164 106589 214165 106890 214165 106922 214165 106589 214166 106922 214166 106584 214166 106923 214167 106924 214167 106894 214167 106894 214168 106924 214168 106853 214168 106894 214169 106853 214169 106898 214169 106898 214170 106853 214170 106860 214170 106898 214171 106860 214171 106925 214171 106925 214172 106860 214172 106907 214172 106925 214173 106907 214173 106888 214173 106888 214174 106907 214174 106926 214174 106888 214175 106926 214175 106927 214175 106927 214176 106926 214176 106908 214176 106927 214177 106908 214177 106885 214177 106885 214178 106908 214178 106910 214178 106885 214179 106910 214179 106884 214179 106884 214180 106910 214180 106914 214180 106884 214181 106914 214181 106928 214181 106928 214182 106914 214182 106912 214182 106928 214183 106912 214183 106882 214183 106882 214184 106912 214184 106873 214184 106882 214185 106873 214185 106883 214185 106587 214186 106586 214186 106970 214186 106806 214187 106805 214187 106585 214187 106871 214188 106954 214188 106963 214188 106976 214189 106934 214189 106940 214189 106941 214190 106579 214190 106929 214190 106929 214191 106579 214191 106930 214191 106929 214192 106930 214192 106944 214192 106944 214193 106930 214193 106580 214193 106944 214194 106580 214194 106946 214194 106933 214195 106594 214195 106595 214195 106931 214196 106578 214196 106937 214196 106937 214197 106578 214197 106932 214197 106937 214198 106932 214198 106935 214198 106935 214199 106932 214199 106938 214199 106935 214200 106938 214200 106940 214200 106586 214201 106594 214201 106970 214201 106970 214202 106594 214202 106933 214202 106970 214203 106933 214203 106968 214203 106940 214204 106934 214204 106935 214204 106935 214205 106934 214205 106936 214205 106935 214206 106936 214206 106937 214206 106938 214207 106939 214207 106940 214207 106940 214208 106939 214208 106942 214208 106940 214209 106942 214209 106976 214209 106976 214210 106942 214210 106943 214210 106976 214211 106943 214211 106977 214211 106977 214212 106943 214212 106945 214212 106977 214213 106945 214213 106979 214213 106979 214214 106945 214214 106877 214214 106979 214215 106877 214215 106876 214215 106939 214216 106941 214216 106942 214216 106942 214217 106941 214217 106929 214217 106942 214218 106929 214218 106943 214218 106943 214219 106929 214219 106944 214219 106943 214220 106944 214220 106945 214220 106945 214221 106944 214221 106946 214221 106945 214222 106946 214222 106877 214222 106947 214223 106957 214223 106948 214223 106948 214224 106957 214224 106972 214224 106948 214225 106972 214225 106949 214225 106949 214226 106972 214226 106864 214226 106864 214227 106972 214227 106950 214227 106864 214228 106950 214228 106951 214228 106951 214229 106950 214229 106953 214229 106951 214230 106953 214230 106862 214230 106846 214231 106862 214231 106952 214231 106952 214232 106862 214232 106953 214232 106952 214233 106953 214233 106954 214233 106802 214234 106962 214234 106803 214234 106803 214235 106962 214235 106958 214235 106947 214236 106955 214236 106957 214236 106957 214237 106955 214237 106956 214237 106957 214238 106956 214238 106958 214238 106958 214239 106956 214239 106959 214239 106958 214240 106959 214240 106803 214240 106802 214241 106960 214241 106962 214241 106962 214242 106960 214242 106961 214242 106962 214243 106961 214243 106806 214243 106871 214244 106963 214244 106980 214244 106980 214245 106963 214245 106971 214245 106980 214246 106971 214246 106978 214246 106978 214247 106971 214247 106965 214247 106978 214248 106965 214248 106964 214248 106964 214249 106965 214249 106966 214249 106964 214250 106966 214250 106975 214250 106975 214251 106966 214251 106967 214251 106975 214252 106967 214252 106974 214252 106974 214253 106967 214253 106969 214253 106974 214254 106969 214254 106968 214254 106968 214255 106969 214255 106970 214255 106970 214256 106969 214256 106973 214256 106970 214257 106973 214257 106587 214257 106954 214258 106953 214258 106963 214258 106963 214259 106953 214259 106950 214259 106963 214260 106950 214260 106971 214260 106971 214261 106950 214261 106972 214261 106971 214262 106972 214262 106965 214262 106965 214263 106972 214263 106957 214263 106965 214264 106957 214264 106966 214264 106966 214265 106957 214265 106958 214265 106966 214266 106958 214266 106967 214266 106967 214267 106958 214267 106962 214267 106967 214268 106962 214268 106969 214268 106969 214269 106962 214269 106806 214269 106969 214270 106806 214270 106973 214270 106973 214271 106806 214271 106585 214271 106973 214272 106585 214272 106587 214272 106595 214273 106931 214273 106933 214273 106933 214274 106931 214274 106937 214274 106933 214275 106937 214275 106968 214275 106968 214276 106937 214276 106936 214276 106968 214277 106936 214277 106974 214277 106974 214278 106936 214278 106934 214278 106974 214279 106934 214279 106975 214279 106975 214280 106934 214280 106976 214280 106975 214281 106976 214281 106964 214281 106964 214282 106976 214282 106977 214282 106964 214283 106977 214283 106978 214283 106978 214284 106977 214284 106979 214284 106978 214285 106979 214285 106980 214285 106980 214286 106979 214286 106876 214286 106980 214287 106876 214287 106871 214287 107276 214288 106981 214288 107189 214288 107276 214289 107189 214289 107275 214289 107275 214290 107189 214290 107188 214290 107275 214291 107188 214291 106982 214291 106982 214292 107188 214292 107200 214292 106982 214293 107200 214293 107268 214293 107190 214294 106981 214294 107276 214294 106997 214295 106983 214295 106984 214295 106984 214296 106983 214296 107195 214296 106984 214297 107195 214297 106985 214297 106985 214298 107195 214298 106986 214298 107195 214299 107198 214299 106986 214299 106986 214300 107198 214300 107199 214300 106986 214301 107199 214301 107234 214301 107234 214302 107199 214302 107194 214302 107234 214303 107194 214303 107235 214303 107235 214304 107194 214304 107236 214304 107236 214305 107194 214305 106990 214305 107236 214306 106990 214306 106991 214306 107233 214307 106987 214307 107193 214307 107193 214308 106987 214308 106988 214308 107193 214309 106988 214309 106990 214309 106990 214310 106988 214310 106989 214310 106990 214311 106989 214311 106991 214311 107276 214312 106992 214312 107190 214312 107190 214313 106992 214313 107233 214313 107190 214314 107233 214314 107192 214314 107192 214315 107233 214315 107193 214315 107002 214316 106993 214316 107285 214316 107285 214317 106993 214317 106994 214317 107285 214318 106994 214318 106995 214318 106995 214319 106994 214319 106996 214319 106995 214320 106996 214320 106997 214320 106997 214321 106996 214321 106983 214321 107363 214322 107368 214322 107387 214322 107387 214323 107368 214323 107187 214323 107387 214324 107187 214324 106998 214324 106998 214325 107187 214325 106999 214325 106998 214326 106999 214326 107361 214326 107361 214327 106999 214327 107362 214327 107361 214328 107362 214328 107000 214328 107001 214329 107357 214329 107356 214329 107001 214330 107356 214330 107311 214330 107356 214331 107003 214331 107311 214331 107311 214332 107003 214332 106993 214332 107311 214333 106993 214333 107002 214333 107356 214334 107207 214334 107003 214334 107003 214335 107207 214335 107004 214335 107003 214336 107004 214336 106993 214336 106993 214337 107004 214337 107208 214337 107135 214338 107005 214338 107006 214338 107006 214339 107005 214339 107133 214339 107006 214340 107133 214340 107012 214340 107012 214341 107133 214341 107130 214341 107012 214342 107130 214342 107360 214342 107360 214343 107130 214343 107129 214343 107135 214344 107006 214344 107007 214344 107007 214345 107006 214345 107009 214345 107007 214346 107009 214346 107008 214346 107009 214347 107013 214347 107008 214347 107008 214348 107013 214348 107010 214348 107008 214349 107010 214349 107137 214349 107137 214350 107010 214350 107017 214350 107137 214351 107017 214351 107049 214351 107381 214352 107382 214352 107017 214352 107017 214353 107010 214353 107381 214353 107381 214354 107010 214354 107013 214354 107381 214355 107013 214355 107380 214355 107360 214356 107373 214356 107012 214356 107012 214357 107373 214357 107011 214357 107012 214358 107011 214358 107006 214358 107006 214359 107011 214359 107380 214359 107006 214360 107380 214360 107009 214360 107009 214361 107380 214361 107013 214361 107014 214362 107386 214362 107038 214362 107038 214363 107386 214363 107015 214363 107038 214364 107015 214364 107016 214364 107385 214365 107124 214365 107015 214365 107015 214366 107124 214366 107040 214366 107015 214367 107040 214367 107016 214367 107017 214368 107382 214368 107050 214368 107050 214369 107382 214369 107383 214369 107050 214370 107383 214370 107051 214370 107051 214371 107383 214371 107018 214371 107027 214372 107386 214372 107014 214372 107088 214373 107051 214373 107089 214373 107089 214374 107051 214374 107019 214374 107089 214375 107019 214375 107020 214375 107020 214376 107019 214376 107022 214376 107019 214377 107021 214377 107022 214377 107022 214378 107021 214378 107366 214378 107022 214379 107366 214379 107025 214379 107031 214380 107024 214380 107023 214380 107023 214381 107024 214381 107025 214381 107023 214382 107025 214382 107026 214382 107026 214383 107025 214383 107366 214383 107014 214384 107087 214384 107027 214384 107027 214385 107087 214385 107052 214385 107027 214386 107052 214386 107029 214386 107029 214387 107052 214387 107028 214387 107029 214388 107028 214388 107030 214388 107030 214389 107028 214389 107032 214389 107030 214390 107032 214390 107031 214390 107031 214391 107032 214391 107072 214391 107031 214392 107072 214392 107024 214392 107124 214393 107385 214393 107125 214393 107125 214394 107385 214394 107033 214394 107125 214395 107033 214395 107034 214395 107034 214396 107033 214396 107035 214396 107034 214397 107035 214397 107127 214397 107127 214398 107035 214398 107360 214398 107127 214399 107360 214399 107129 214399 107046 214400 107122 214400 107107 214400 107122 214401 107046 214401 107116 214401 107045 214402 107039 214402 107036 214402 107037 214403 107014 214403 107038 214403 107074 214404 107075 214404 107045 214404 107045 214405 107075 214405 107037 214405 107037 214406 107038 214406 107045 214406 107045 214407 107038 214407 107016 214407 107045 214408 107016 214408 107039 214408 107039 214409 107016 214409 107040 214409 107039 214410 107040 214410 107124 214410 107102 214411 107041 214411 107044 214411 107044 214412 107041 214412 107074 214412 107124 214413 107123 214413 107039 214413 107039 214414 107123 214414 107042 214414 107039 214415 107042 214415 107036 214415 107036 214416 107042 214416 107147 214416 107036 214417 107147 214417 107047 214417 107060 214418 107102 214418 107043 214418 107043 214419 107102 214419 107044 214419 107043 214420 107044 214420 107046 214420 107074 214421 107045 214421 107044 214421 107044 214422 107045 214422 107036 214422 107044 214423 107036 214423 107046 214423 107046 214424 107036 214424 107047 214424 107046 214425 107047 214425 107116 214425 107159 214426 107060 214426 107048 214426 107048 214427 107060 214427 107043 214427 107048 214428 107043 214428 107169 214428 107169 214429 107043 214429 107046 214429 107169 214430 107046 214430 107167 214430 107167 214431 107046 214431 107107 214431 107049 214432 107017 214432 107183 214432 107183 214433 107017 214433 107050 214433 107183 214434 107050 214434 107185 214434 107185 214435 107050 214435 107186 214435 107186 214436 107050 214436 107051 214436 107186 214437 107051 214437 107088 214437 107072 214438 107032 214438 107097 214438 107028 214439 107052 214439 107077 214439 107068 214440 107053 214440 107069 214440 107061 214441 107054 214441 107062 214441 107162 214442 107055 214442 107093 214442 107068 214443 107067 214443 107053 214443 107053 214444 107067 214444 107163 214444 107053 214445 107163 214445 107162 214445 107059 214446 107160 214446 107056 214446 107056 214447 107160 214447 107161 214447 107056 214448 107161 214448 107057 214448 107056 214449 107058 214449 107059 214449 107059 214450 107058 214450 107060 214450 107059 214451 107060 214451 107159 214451 107161 214452 107061 214452 107057 214452 107057 214453 107061 214453 107062 214453 107057 214454 107062 214454 107101 214454 107101 214455 107062 214455 107063 214455 107101 214456 107063 214456 107100 214456 107100 214457 107063 214457 107070 214457 107100 214458 107070 214458 107098 214458 107098 214459 107070 214459 107071 214459 107098 214460 107071 214460 107096 214460 107089 214461 107020 214461 107064 214461 107064 214462 107020 214462 107066 214462 107162 214463 107093 214463 107053 214463 107053 214464 107093 214464 107092 214464 107053 214465 107092 214465 107069 214465 107069 214466 107092 214466 107064 214466 107069 214467 107064 214467 107065 214467 107065 214468 107064 214468 107066 214468 107065 214469 107066 214469 107095 214469 107054 214470 107067 214470 107062 214470 107062 214471 107067 214471 107068 214471 107062 214472 107068 214472 107063 214472 107063 214473 107068 214473 107069 214473 107063 214474 107069 214474 107070 214474 107070 214475 107069 214475 107065 214475 107070 214476 107065 214476 107071 214476 107071 214477 107065 214477 107095 214477 107071 214478 107095 214478 107096 214478 107072 214479 107097 214479 107024 214479 107102 214480 107073 214480 107041 214480 107041 214481 107073 214481 107084 214481 107041 214482 107084 214482 107074 214482 107074 214483 107084 214483 107085 214483 107074 214484 107085 214484 107075 214484 107075 214485 107085 214485 107076 214485 107075 214486 107076 214486 107037 214486 107037 214487 107076 214487 107086 214487 107037 214488 107086 214488 107014 214488 107014 214489 107086 214489 107087 214489 107032 214490 107028 214490 107097 214490 107097 214491 107028 214491 107077 214491 107097 214492 107077 214492 107099 214492 107099 214493 107077 214493 107079 214493 107099 214494 107079 214494 107078 214494 107078 214495 107079 214495 107080 214495 107078 214496 107080 214496 107082 214496 107082 214497 107080 214497 107081 214497 107082 214498 107081 214498 107083 214498 107073 214499 107083 214499 107084 214499 107084 214500 107083 214500 107081 214500 107084 214501 107081 214501 107085 214501 107085 214502 107081 214502 107080 214502 107085 214503 107080 214503 107076 214503 107076 214504 107080 214504 107079 214504 107076 214505 107079 214505 107086 214505 107086 214506 107079 214506 107077 214506 107086 214507 107077 214507 107087 214507 107087 214508 107077 214508 107052 214508 107088 214509 107089 214509 107172 214509 107172 214510 107089 214510 107064 214510 107172 214511 107064 214511 107090 214511 107090 214512 107064 214512 107092 214512 107090 214513 107092 214513 107091 214513 107091 214514 107092 214514 107093 214514 107091 214515 107093 214515 107094 214515 107094 214516 107093 214516 107055 214516 107094 214517 107055 214517 107173 214517 107020 214518 107022 214518 107066 214518 107066 214519 107022 214519 107025 214519 107066 214520 107025 214520 107095 214520 107095 214521 107025 214521 107024 214521 107095 214522 107024 214522 107096 214522 107096 214523 107024 214523 107097 214523 107096 214524 107097 214524 107098 214524 107098 214525 107097 214525 107099 214525 107098 214526 107099 214526 107100 214526 107100 214527 107099 214527 107078 214527 107100 214528 107078 214528 107101 214528 107101 214529 107078 214529 107082 214529 107101 214530 107082 214530 107057 214530 107057 214531 107082 214531 107083 214531 107057 214532 107083 214532 107056 214532 107056 214533 107083 214533 107073 214533 107056 214534 107073 214534 107058 214534 107058 214535 107073 214535 107102 214535 107058 214536 107102 214536 107060 214536 107137 214537 107049 214537 107181 214537 107115 214538 107153 214538 107112 214538 107148 214539 107103 214539 107177 214539 107117 214540 107104 214540 107120 214540 107120 214541 107104 214541 107106 214541 107120 214542 107106 214542 107105 214542 107105 214543 107106 214543 107107 214543 107105 214544 107107 214544 107122 214544 107138 214545 107177 214545 107164 214545 107150 214546 107108 214546 107109 214546 107109 214547 107108 214547 107111 214547 107109 214548 107111 214548 107110 214548 107110 214549 107111 214549 107113 214549 107110 214550 107113 214550 107112 214550 107112 214551 107153 214551 107110 214551 107110 214552 107153 214552 107151 214552 107110 214553 107151 214553 107109 214553 107113 214554 107114 214554 107112 214554 107112 214555 107114 214555 107118 214555 107112 214556 107118 214556 107115 214556 107115 214557 107118 214557 107119 214557 107115 214558 107119 214558 107155 214558 107155 214559 107119 214559 107121 214559 107155 214560 107121 214560 107158 214560 107158 214561 107121 214561 107116 214561 107158 214562 107116 214562 107047 214562 107114 214563 107117 214563 107118 214563 107118 214564 107117 214564 107120 214564 107118 214565 107120 214565 107119 214565 107119 214566 107120 214566 107105 214566 107119 214567 107105 214567 107121 214567 107121 214568 107105 214568 107122 214568 107121 214569 107122 214569 107116 214569 107042 214570 107123 214570 107126 214570 107126 214571 107123 214571 107124 214571 107126 214572 107124 214572 107125 214572 107134 214573 107135 214573 107136 214573 107136 214574 107135 214574 107007 214574 107125 214575 107034 214575 107126 214575 107126 214576 107034 214576 107127 214576 107126 214577 107127 214577 107128 214577 107128 214578 107127 214578 107129 214578 107128 214579 107129 214579 107131 214579 107131 214580 107129 214580 107130 214580 107131 214581 107130 214581 107132 214581 107132 214582 107130 214582 107133 214582 107132 214583 107133 214583 107134 214583 107134 214584 107133 214584 107005 214584 107134 214585 107005 214585 107135 214585 107007 214586 107008 214586 107136 214586 107136 214587 107008 214587 107137 214587 107136 214588 107137 214588 107149 214588 107149 214589 107137 214589 107181 214589 107149 214590 107181 214590 107180 214590 107177 214591 107138 214591 107148 214591 107148 214592 107138 214592 107139 214592 107148 214593 107139 214593 107140 214593 107140 214594 107139 214594 107152 214594 107140 214595 107152 214595 107141 214595 107141 214596 107152 214596 107143 214596 107141 214597 107143 214597 107142 214597 107142 214598 107143 214598 107154 214598 107142 214599 107154 214599 107144 214599 107144 214600 107154 214600 107156 214600 107144 214601 107156 214601 107145 214601 107145 214602 107156 214602 107157 214602 107145 214603 107157 214603 107146 214603 107146 214604 107157 214604 107147 214604 107146 214605 107147 214605 107042 214605 107042 214606 107126 214606 107146 214606 107146 214607 107126 214607 107128 214607 107146 214608 107128 214608 107145 214608 107145 214609 107128 214609 107131 214609 107145 214610 107131 214610 107144 214610 107144 214611 107131 214611 107132 214611 107144 214612 107132 214612 107142 214612 107142 214613 107132 214613 107134 214613 107142 214614 107134 214614 107141 214614 107141 214615 107134 214615 107136 214615 107141 214616 107136 214616 107140 214616 107140 214617 107136 214617 107149 214617 107140 214618 107149 214618 107148 214618 107148 214619 107149 214619 107180 214619 107148 214620 107180 214620 107103 214620 107164 214621 107150 214621 107138 214621 107138 214622 107150 214622 107109 214622 107138 214623 107109 214623 107139 214623 107139 214624 107109 214624 107151 214624 107139 214625 107151 214625 107152 214625 107152 214626 107151 214626 107153 214626 107152 214627 107153 214627 107143 214627 107143 214628 107153 214628 107115 214628 107143 214629 107115 214629 107154 214629 107154 214630 107115 214630 107155 214630 107154 214631 107155 214631 107156 214631 107156 214632 107155 214632 107158 214632 107156 214633 107158 214633 107157 214633 107157 214634 107158 214634 107047 214634 107157 214635 107047 214635 107147 214635 107165 214636 107164 214636 107168 214636 107171 214637 107159 214637 107048 214637 107059 214638 107159 214638 107160 214638 107160 214639 107159 214639 107171 214639 107160 214640 107171 214640 107161 214640 107161 214641 107171 214641 107061 214641 107055 214642 107162 214642 107171 214642 107171 214643 107162 214643 107163 214643 107163 214644 107067 214644 107171 214644 107171 214645 107067 214645 107054 214645 107171 214646 107054 214646 107061 214646 107117 214647 107114 214647 107165 214647 107165 214648 107114 214648 107113 214648 107150 214649 107164 214649 107108 214649 107108 214650 107164 214650 107165 214650 107108 214651 107165 214651 107111 214651 107111 214652 107165 214652 107113 214652 107107 214653 107106 214653 107165 214653 107165 214654 107106 214654 107166 214654 107165 214655 107166 214655 107117 214655 107107 214656 107165 214656 107167 214656 107167 214657 107165 214657 107168 214657 107167 214658 107168 214658 107169 214658 107169 214659 107168 214659 107175 214659 107169 214660 107175 214660 107048 214660 107048 214661 107175 214661 107170 214661 107048 214662 107170 214662 107171 214662 107171 214663 107170 214663 107173 214663 107171 214664 107173 214664 107055 214664 107181 214665 107049 214665 107183 214665 107103 214666 107180 214666 107182 214666 107172 214667 107090 214667 107179 214667 107091 214668 107094 214668 107174 214668 107094 214669 107173 214669 107174 214669 107174 214670 107173 214670 107170 214670 107174 214671 107170 214671 107176 214671 107176 214672 107170 214672 107175 214672 107176 214673 107175 214673 107178 214673 107178 214674 107175 214674 107168 214674 107178 214675 107168 214675 107177 214675 107177 214676 107168 214676 107164 214676 107177 214677 107103 214677 107178 214677 107178 214678 107103 214678 107182 214678 107178 214679 107182 214679 107176 214679 107176 214680 107182 214680 107184 214680 107176 214681 107184 214681 107174 214681 107174 214682 107184 214682 107179 214682 107174 214683 107179 214683 107091 214683 107091 214684 107179 214684 107090 214684 107180 214685 107181 214685 107182 214685 107182 214686 107181 214686 107183 214686 107182 214687 107183 214687 107184 214687 107184 214688 107183 214688 107185 214688 107184 214689 107185 214689 107179 214689 107179 214690 107185 214690 107186 214690 107179 214691 107186 214691 107172 214691 107172 214692 107186 214692 107088 214692 107368 214693 107367 214693 107200 214693 107368 214694 107200 214694 107187 214694 107200 214695 107188 214695 107187 214695 107187 214696 107188 214696 107189 214696 107187 214697 107189 214697 106999 214697 106999 214698 107189 214698 107362 214698 107362 214699 107189 214699 106981 214699 107362 214700 106981 214700 107374 214700 107374 214701 106981 214701 107191 214701 107191 214702 106981 214702 107190 214702 107191 214703 107190 214703 107376 214703 107190 214704 107192 214704 107376 214704 107376 214705 107192 214705 107193 214705 107376 214706 107193 214706 107377 214706 107377 214707 107193 214707 106990 214707 107377 214708 106990 214708 107378 214708 107378 214709 106990 214709 107194 214709 107378 214710 107194 214710 107379 214710 106983 214711 107196 214711 107195 214711 107195 214712 107196 214712 107197 214712 107195 214713 107197 214713 107198 214713 107198 214714 107197 214714 107379 214714 107198 214715 107379 214715 107199 214715 107199 214716 107379 214716 107194 214716 107200 214717 107367 214717 107201 214717 107201 214718 107367 214718 107202 214718 107201 214719 107202 214719 107203 214719 107203 214720 107202 214720 107372 214720 107203 214721 107372 214721 107204 214721 107204 214722 107372 214722 107205 214722 107204 214723 107205 214723 107206 214723 107206 214724 107205 214724 107370 214724 107206 214725 107370 214725 107356 214725 107356 214726 107370 214726 107207 214726 106993 214727 107208 214727 106994 214727 106994 214728 107208 214728 107384 214728 106994 214729 107384 214729 106996 214729 106996 214730 107384 214730 107209 214730 106996 214731 107209 214731 106983 214731 106983 214732 107209 214732 107196 214732 107210 214733 107211 214733 107212 214733 107341 214734 107210 214734 107247 214734 107222 214735 107224 214735 107339 214735 107339 214736 107224 214736 107213 214736 107339 214737 107213 214737 107214 214737 107214 214738 107213 214738 107215 214738 107214 214739 107215 214739 107340 214739 107340 214740 107215 214740 107264 214740 107220 214741 107216 214741 107226 214741 107217 214742 107218 214742 107225 214742 107225 214743 107218 214743 107219 214743 107225 214744 107219 214744 107220 214744 107220 214745 107219 214745 107269 214745 107220 214746 107269 214746 107216 214746 107223 214747 107224 214747 107221 214747 107221 214748 107224 214748 107222 214748 107221 214749 107222 214749 107337 214749 107223 214750 107217 214750 107224 214750 107224 214751 107217 214751 107225 214751 107224 214752 107225 214752 107213 214752 107213 214753 107225 214753 107220 214753 107213 214754 107220 214754 107215 214754 107215 214755 107220 214755 107226 214755 107215 214756 107226 214756 107264 214756 107227 214757 107255 214757 107223 214757 107223 214758 107255 214758 107256 214758 107223 214759 107256 214759 107217 214759 107343 214760 107341 214760 107228 214760 107228 214761 107341 214761 107247 214761 107228 214762 107247 214762 107251 214762 107251 214763 107247 214763 107249 214763 107254 214764 107253 214764 107242 214764 106985 214765 107252 214765 106984 214765 106984 214766 107252 214766 107229 214766 106984 214767 107229 214767 106997 214767 107232 214768 106992 214768 107230 214768 107230 214769 106992 214769 107276 214769 107230 214770 107276 214770 107246 214770 106989 214771 106988 214771 107231 214771 107231 214772 106988 214772 106987 214772 107231 214773 106987 214773 107232 214773 107232 214774 106987 214774 107233 214774 107232 214775 107233 214775 106992 214775 106985 214776 106986 214776 107253 214776 107253 214777 106986 214777 107234 214777 107253 214778 107234 214778 107242 214778 107242 214779 107234 214779 107235 214779 107242 214780 107235 214780 107243 214780 107243 214781 107235 214781 107236 214781 107243 214782 107236 214782 107231 214782 107231 214783 107236 214783 106991 214783 107231 214784 106991 214784 106989 214784 107254 214785 107237 214785 107238 214785 107238 214786 107237 214786 107239 214786 107238 214787 107239 214787 107240 214787 107240 214788 107239 214788 107244 214788 107240 214789 107244 214789 107257 214789 107257 214790 107244 214790 107245 214790 107257 214791 107245 214791 107258 214791 107258 214792 107245 214792 107241 214792 107258 214793 107241 214793 107259 214793 107259 214794 107241 214794 107271 214794 107259 214795 107271 214795 107260 214795 107254 214796 107242 214796 107237 214796 107237 214797 107242 214797 107243 214797 107237 214798 107243 214798 107239 214798 107239 214799 107243 214799 107231 214799 107239 214800 107231 214800 107244 214800 107244 214801 107231 214801 107232 214801 107244 214802 107232 214802 107245 214802 107245 214803 107232 214803 107230 214803 107245 214804 107230 214804 107241 214804 107241 214805 107230 214805 107246 214805 107241 214806 107246 214806 107271 214806 107210 214807 107212 214807 107247 214807 107247 214808 107212 214808 107280 214808 107247 214809 107280 214809 107249 214809 107249 214810 107280 214810 107248 214810 107249 214811 107248 214811 107250 214811 107337 214812 107343 214812 107221 214812 107221 214813 107343 214813 107228 214813 107221 214814 107228 214814 107223 214814 107223 214815 107228 214815 107251 214815 107223 214816 107251 214816 107227 214816 107227 214817 107251 214817 107249 214817 107227 214818 107249 214818 107252 214818 107252 214819 107249 214819 107250 214819 107252 214820 107250 214820 107229 214820 106985 214821 107253 214821 107252 214821 107252 214822 107253 214822 107254 214822 107252 214823 107254 214823 107227 214823 107227 214824 107254 214824 107238 214824 107227 214825 107238 214825 107255 214825 107255 214826 107238 214826 107240 214826 107255 214827 107240 214827 107256 214827 107256 214828 107240 214828 107257 214828 107256 214829 107257 214829 107217 214829 107217 214830 107257 214830 107258 214830 107217 214831 107258 214831 107218 214831 107218 214832 107258 214832 107259 214832 107218 214833 107259 214833 107219 214833 107219 214834 107259 214834 107260 214834 107219 214835 107260 214835 107269 214835 107261 214836 107322 214836 107274 214836 107262 214837 107263 214837 107266 214837 107346 214838 107350 214838 107286 214838 107286 214839 107350 214839 107265 214839 107340 214840 107264 214840 107353 214840 107353 214841 107264 214841 107263 214841 107272 214842 107273 214842 107270 214842 107270 214843 107273 214843 107265 214843 107263 214844 107264 214844 107266 214844 107266 214845 107264 214845 107226 214845 107266 214846 107226 214846 107216 214846 107350 214847 107262 214847 107265 214847 107265 214848 107262 214848 107266 214848 107265 214849 107266 214849 107270 214849 107270 214850 107266 214850 107216 214850 107322 214851 107267 214851 107273 214851 107273 214852 107267 214852 107336 214852 107273 214853 107336 214853 107265 214853 107265 214854 107336 214854 107300 214854 107265 214855 107300 214855 107286 214855 107275 214856 106982 214856 107274 214856 107274 214857 106982 214857 107268 214857 107274 214858 107268 214858 107261 214858 107216 214859 107269 214859 107270 214859 107270 214860 107269 214860 107260 214860 107270 214861 107260 214861 107272 214861 107272 214862 107260 214862 107271 214862 107272 214863 107271 214863 107246 214863 107322 214864 107273 214864 107274 214864 107274 214865 107273 214865 107272 214865 107274 214866 107272 214866 107275 214866 107275 214867 107272 214867 107246 214867 107275 214868 107246 214868 107276 214868 107277 214869 107282 214869 107278 214869 107351 214870 107345 214870 107314 214870 107212 214871 107211 214871 107279 214871 107248 214872 107280 214872 107277 214872 107277 214873 107280 214873 107212 214873 107212 214874 107279 214874 107277 214874 107277 214875 107279 214875 107281 214875 107277 214876 107281 214876 107282 214876 107282 214877 107281 214877 107352 214877 107282 214878 107352 214878 107351 214878 107229 214879 107250 214879 107284 214879 107284 214880 107250 214880 107248 214880 106997 214881 107229 214881 106995 214881 106995 214882 107229 214882 107284 214882 106995 214883 107284 214883 107285 214883 107351 214884 107314 214884 107282 214884 107282 214885 107314 214885 107283 214885 107282 214886 107283 214886 107278 214886 107278 214887 107283 214887 107327 214887 107278 214888 107327 214888 107313 214888 107248 214889 107277 214889 107284 214889 107284 214890 107277 214890 107278 214890 107284 214891 107278 214891 107285 214891 107285 214892 107278 214892 107313 214892 107285 214893 107313 214893 107002 214893 107311 214894 107002 214894 107313 214894 107296 214895 107332 214895 107294 214895 107316 214896 107283 214896 107314 214896 107328 214897 107344 214897 107329 214897 107346 214898 107286 214898 107347 214898 107347 214899 107286 214899 107287 214899 107347 214900 107287 214900 107288 214900 107288 214901 107287 214901 107290 214901 107288 214902 107290 214902 107289 214902 107289 214903 107290 214903 107291 214903 107329 214904 107344 214904 107292 214904 107292 214905 107344 214905 107293 214905 107292 214906 107293 214906 107294 214906 107315 214907 107314 214907 107345 214907 107294 214908 107332 214908 107292 214908 107292 214909 107332 214909 107331 214909 107292 214910 107331 214910 107329 214910 107293 214911 107349 214911 107294 214911 107294 214912 107349 214912 107295 214912 107294 214913 107295 214913 107296 214913 107296 214914 107295 214914 107298 214914 107296 214915 107298 214915 107333 214915 107333 214916 107298 214916 107299 214916 107333 214917 107299 214917 107297 214917 107297 214918 107299 214918 107300 214918 107297 214919 107300 214919 107336 214919 107349 214920 107291 214920 107295 214920 107295 214921 107291 214921 107290 214921 107295 214922 107290 214922 107298 214922 107298 214923 107290 214923 107287 214923 107298 214924 107287 214924 107299 214924 107299 214925 107287 214925 107286 214925 107299 214926 107286 214926 107300 214926 107301 214927 107303 214927 107354 214927 107354 214928 107303 214928 107302 214928 107302 214929 107303 214929 107304 214929 107302 214930 107304 214930 107305 214930 107268 214931 107305 214931 107261 214931 107261 214932 107305 214932 107304 214932 107261 214933 107304 214933 107322 214933 107309 214934 107358 214934 107306 214934 107306 214935 107358 214935 107357 214935 107354 214936 107355 214936 107301 214936 107301 214937 107355 214937 107307 214937 107301 214938 107307 214938 107308 214938 107308 214939 107307 214939 107359 214939 107308 214940 107359 214940 107309 214940 107309 214941 107359 214941 107310 214941 107309 214942 107310 214942 107358 214942 107357 214943 107001 214943 107306 214943 107306 214944 107001 214944 107311 214944 107306 214945 107311 214945 107312 214945 107312 214946 107311 214946 107313 214946 107312 214947 107313 214947 107327 214947 107314 214948 107315 214948 107316 214948 107316 214949 107315 214949 107330 214949 107316 214950 107330 214950 107326 214950 107326 214951 107330 214951 107318 214951 107326 214952 107318 214952 107317 214952 107317 214953 107318 214953 107319 214953 107317 214954 107319 214954 107325 214954 107325 214955 107319 214955 107320 214955 107325 214956 107320 214956 107321 214956 107321 214957 107320 214957 107334 214957 107321 214958 107334 214958 107324 214958 107324 214959 107334 214959 107335 214959 107324 214960 107335 214960 107323 214960 107323 214961 107335 214961 107267 214961 107323 214962 107267 214962 107322 214962 107322 214963 107304 214963 107323 214963 107323 214964 107304 214964 107303 214964 107323 214965 107303 214965 107324 214965 107324 214966 107303 214966 107301 214966 107324 214967 107301 214967 107321 214967 107321 214968 107301 214968 107308 214968 107321 214969 107308 214969 107325 214969 107325 214970 107308 214970 107309 214970 107325 214971 107309 214971 107317 214971 107317 214972 107309 214972 107306 214972 107317 214973 107306 214973 107326 214973 107326 214974 107306 214974 107312 214974 107326 214975 107312 214975 107316 214975 107316 214976 107312 214976 107327 214976 107316 214977 107327 214977 107283 214977 107345 214978 107328 214978 107315 214978 107315 214979 107328 214979 107329 214979 107315 214980 107329 214980 107330 214980 107330 214981 107329 214981 107331 214981 107330 214982 107331 214982 107318 214982 107318 214983 107331 214983 107332 214983 107318 214984 107332 214984 107319 214984 107319 214985 107332 214985 107296 214985 107319 214986 107296 214986 107320 214986 107320 214987 107296 214987 107333 214987 107320 214988 107333 214988 107334 214988 107334 214989 107333 214989 107297 214989 107334 214990 107297 214990 107335 214990 107335 214991 107297 214991 107336 214991 107335 214992 107336 214992 107267 214992 107342 214993 107340 214993 107353 214993 107342 214994 107337 214994 107338 214994 107338 214995 107339 214995 107342 214995 107342 214996 107339 214996 107214 214996 107342 214997 107214 214997 107340 214997 107210 214998 107341 214998 107342 214998 107342 214999 107341 214999 107343 214999 107342 215000 107343 215000 107337 215000 107348 215001 107345 215001 107351 215001 107293 215002 107344 215002 107348 215002 107348 215003 107344 215003 107328 215003 107348 215004 107328 215004 107345 215004 107346 215005 107347 215005 107348 215005 107348 215006 107347 215006 107288 215006 107348 215007 107288 215007 107289 215007 107289 215008 107291 215008 107348 215008 107348 215009 107291 215009 107349 215009 107348 215010 107349 215010 107293 215010 107346 215011 107348 215011 107350 215011 107350 215012 107348 215012 107351 215012 107350 215013 107351 215013 107262 215013 107262 215014 107351 215014 107352 215014 107262 215015 107352 215015 107263 215015 107263 215016 107352 215016 107281 215016 107263 215017 107281 215017 107353 215017 107353 215018 107281 215018 107279 215018 107353 215019 107279 215019 107342 215019 107342 215020 107279 215020 107211 215020 107342 215021 107211 215021 107210 215021 107268 215022 107200 215022 107305 215022 107305 215023 107200 215023 107201 215023 107305 215024 107201 215024 107302 215024 107302 215025 107201 215025 107203 215025 107302 215026 107203 215026 107354 215026 107354 215027 107203 215027 107355 215027 107355 215028 107203 215028 107204 215028 107355 215029 107204 215029 107307 215029 107206 215030 107356 215030 107357 215030 107357 215031 107358 215031 107206 215031 107206 215032 107358 215032 107310 215032 107206 215033 107310 215033 107204 215033 107204 215034 107310 215034 107359 215034 107204 215035 107359 215035 107307 215035 107035 215036 107375 215036 107360 215036 107360 215037 107375 215037 107373 215037 107385 215038 107361 215038 107033 215038 107033 215039 107361 215039 107000 215039 107033 215040 107000 215040 107035 215040 107035 215041 107000 215041 107362 215041 107035 215042 107362 215042 107375 215042 107031 215043 107371 215043 107364 215043 107387 215044 107386 215044 107363 215044 107363 215045 107386 215045 107027 215045 107363 215046 107027 215046 107368 215046 107368 215047 107027 215047 107029 215047 107368 215048 107029 215048 107364 215048 107364 215049 107029 215049 107030 215049 107364 215050 107030 215050 107031 215050 107031 215051 107023 215051 107371 215051 107371 215052 107023 215052 107026 215052 107371 215053 107026 215053 107369 215053 107051 215054 107018 215054 107019 215054 107019 215055 107018 215055 107365 215055 107019 215056 107365 215056 107021 215056 107021 215057 107365 215057 107369 215057 107021 215058 107369 215058 107366 215058 107366 215059 107369 215059 107026 215059 107367 215060 107368 215060 107364 215060 107370 215061 107371 215061 107369 215061 107370 215062 107205 215062 107371 215062 107371 215063 107205 215063 107372 215063 107371 215064 107372 215064 107364 215064 107364 215065 107372 215065 107202 215065 107364 215066 107202 215066 107367 215066 107208 215067 107004 215067 107369 215067 107369 215068 107004 215068 107207 215068 107369 215069 107207 215069 107370 215069 107377 215070 107011 215070 107373 215070 107362 215071 107374 215071 107375 215071 107375 215072 107374 215072 107191 215072 107375 215073 107191 215073 107373 215073 107373 215074 107191 215074 107376 215074 107373 215075 107376 215075 107377 215075 107377 215076 107378 215076 107011 215076 107011 215077 107378 215077 107379 215077 107011 215078 107379 215078 107380 215078 107380 215079 107379 215079 107197 215079 107380 215080 107197 215080 107381 215080 107381 215081 107197 215081 107196 215081 107381 215082 107196 215082 107382 215082 107382 215083 107196 215083 107209 215083 107382 215084 107209 215084 107383 215084 107383 215085 107209 215085 107384 215085 107383 215086 107384 215086 107018 215086 107018 215087 107384 215087 107208 215087 107018 215088 107208 215088 107365 215088 107365 215089 107208 215089 107369 215089 107361 215090 107385 215090 107015 215090 107361 215091 107015 215091 106998 215091 106998 215092 107015 215092 107386 215092 106998 215093 107386 215093 107387 215093 107388 215094 107796 215094 107399 215094 107389 215095 107614 215095 107615 215095 107399 215096 107408 215096 107388 215096 107388 215097 107408 215097 107409 215097 107388 215098 107409 215098 107615 215098 107615 215099 107409 215099 107406 215099 107615 215100 107406 215100 107389 215100 107389 215101 107402 215101 107614 215101 107614 215102 107402 215102 107403 215102 107614 215103 107403 215103 107613 215103 107418 215104 107611 215104 107401 215104 107401 215105 107611 215105 107391 215105 107401 215106 107391 215106 107390 215106 107390 215107 107391 215107 107613 215107 107390 215108 107613 215108 107400 215108 107400 215109 107613 215109 107403 215109 107410 215110 107792 215110 107392 215110 107392 215111 107792 215111 107393 215111 107392 215112 107393 215112 107412 215112 107412 215113 107393 215113 107606 215113 107412 215114 107606 215114 107574 215114 107574 215115 107606 215115 107582 215115 107592 215116 107793 215116 107394 215116 107394 215117 107793 215117 107794 215117 107394 215118 107794 215118 107395 215118 107395 215119 107794 215119 107396 215119 107395 215120 107396 215120 107591 215120 107591 215121 107396 215121 107397 215121 107591 215122 107397 215122 107398 215122 107408 215123 107399 215123 107419 215123 107417 215124 107418 215124 107440 215124 107440 215125 107418 215125 107401 215125 107440 215126 107401 215126 107438 215126 107438 215127 107401 215127 107443 215127 107403 215128 107404 215128 107400 215128 107400 215129 107404 215129 107443 215129 107400 215130 107443 215130 107390 215130 107390 215131 107443 215131 107401 215131 107389 215132 107448 215132 107402 215132 107402 215133 107448 215133 107447 215133 107402 215134 107447 215134 107403 215134 107403 215135 107447 215135 107446 215135 107403 215136 107446 215136 107404 215136 107405 215137 107442 215137 107406 215137 107406 215138 107442 215138 107441 215138 107406 215139 107441 215139 107389 215139 107389 215140 107441 215140 107449 215140 107389 215141 107449 215141 107448 215141 107419 215142 107407 215142 107408 215142 107408 215143 107407 215143 107405 215143 107408 215144 107405 215144 107409 215144 107409 215145 107405 215145 107406 215145 107504 215146 107410 215146 107503 215146 107503 215147 107410 215147 107392 215147 107503 215148 107392 215148 107411 215148 107411 215149 107392 215149 107412 215149 107411 215150 107412 215150 107500 215150 107500 215151 107412 215151 107574 215151 107500 215152 107574 215152 107413 215152 107414 215153 107415 215153 107542 215153 107542 215154 107415 215154 107416 215154 107542 215155 107416 215155 107537 215155 107537 215156 107416 215156 107797 215156 107537 215157 107797 215157 107417 215157 107417 215158 107797 215158 107418 215158 107419 215159 107399 215159 107795 215159 107419 215160 107795 215160 107550 215160 107550 215161 107795 215161 107420 215161 107550 215162 107420 215162 107421 215162 107421 215163 107420 215163 107410 215163 107421 215164 107410 215164 107504 215164 107573 215165 107531 215165 107535 215165 107422 215166 107573 215166 107462 215166 107428 215167 107430 215167 107423 215167 107423 215168 107430 215168 107424 215168 107423 215169 107424 215169 107425 215169 107425 215170 107424 215170 107433 215170 107425 215171 107433 215171 107558 215171 107558 215172 107433 215172 107434 215172 107432 215173 107552 215173 107545 215173 107429 215174 107473 215174 107431 215174 107431 215175 107473 215175 107474 215175 107431 215176 107474 215176 107432 215176 107432 215177 107474 215177 107553 215177 107432 215178 107553 215178 107552 215178 107426 215179 107430 215179 107427 215179 107427 215180 107430 215180 107428 215180 107427 215181 107428 215181 107559 215181 107426 215182 107429 215182 107430 215182 107430 215183 107429 215183 107431 215183 107430 215184 107431 215184 107424 215184 107424 215185 107431 215185 107432 215185 107424 215186 107432 215186 107433 215186 107433 215187 107432 215187 107545 215187 107433 215188 107545 215188 107434 215188 107465 215189 107471 215189 107426 215189 107426 215190 107471 215190 107435 215190 107426 215191 107435 215191 107429 215191 107464 215192 107422 215192 107436 215192 107436 215193 107422 215193 107462 215193 107436 215194 107462 215194 107437 215194 107437 215195 107462 215195 107466 215195 107468 215196 107467 215196 107444 215196 107438 215197 107439 215197 107440 215197 107440 215198 107439 215198 107538 215198 107440 215199 107538 215199 107417 215199 107457 215200 107407 215200 107459 215200 107459 215201 107407 215201 107419 215201 107459 215202 107419 215202 107460 215202 107449 215203 107441 215203 107456 215203 107456 215204 107441 215204 107442 215204 107456 215205 107442 215205 107457 215205 107457 215206 107442 215206 107405 215206 107457 215207 107405 215207 107407 215207 107438 215208 107443 215208 107467 215208 107467 215209 107443 215209 107404 215209 107467 215210 107404 215210 107444 215210 107444 215211 107404 215211 107446 215211 107444 215212 107446 215212 107445 215212 107445 215213 107446 215213 107447 215213 107445 215214 107447 215214 107456 215214 107456 215215 107447 215215 107448 215215 107456 215216 107448 215216 107449 215216 107468 215217 107450 215217 107469 215217 107469 215218 107450 215218 107451 215218 107469 215219 107451 215219 107470 215219 107470 215220 107451 215220 107452 215220 107470 215221 107452 215221 107453 215221 107453 215222 107452 215222 107458 215222 107453 215223 107458 215223 107472 215223 107472 215224 107458 215224 107455 215224 107472 215225 107455 215225 107454 215225 107454 215226 107455 215226 107461 215226 107454 215227 107461 215227 107475 215227 107468 215228 107444 215228 107450 215228 107450 215229 107444 215229 107445 215229 107450 215230 107445 215230 107451 215230 107451 215231 107445 215231 107456 215231 107451 215232 107456 215232 107452 215232 107452 215233 107456 215233 107457 215233 107452 215234 107457 215234 107458 215234 107458 215235 107457 215235 107459 215235 107458 215236 107459 215236 107455 215236 107455 215237 107459 215237 107460 215237 107455 215238 107460 215238 107461 215238 107573 215239 107535 215239 107462 215239 107462 215240 107535 215240 107533 215240 107462 215241 107533 215241 107466 215241 107466 215242 107533 215242 107539 215242 107466 215243 107539 215243 107463 215243 107559 215244 107464 215244 107427 215244 107427 215245 107464 215245 107436 215245 107427 215246 107436 215246 107426 215246 107426 215247 107436 215247 107437 215247 107426 215248 107437 215248 107465 215248 107465 215249 107437 215249 107466 215249 107465 215250 107466 215250 107439 215250 107439 215251 107466 215251 107463 215251 107439 215252 107463 215252 107538 215252 107438 215253 107467 215253 107439 215253 107439 215254 107467 215254 107468 215254 107439 215255 107468 215255 107465 215255 107465 215256 107468 215256 107469 215256 107465 215257 107469 215257 107471 215257 107471 215258 107469 215258 107470 215258 107471 215259 107470 215259 107435 215259 107435 215260 107470 215260 107453 215260 107435 215261 107453 215261 107429 215261 107429 215262 107453 215262 107472 215262 107429 215263 107472 215263 107473 215263 107473 215264 107472 215264 107454 215264 107473 215265 107454 215265 107474 215265 107474 215266 107454 215266 107475 215266 107474 215267 107475 215267 107553 215267 107509 215268 107414 215268 107476 215268 107529 215269 107487 215269 107485 215269 107511 215270 107524 215270 107477 215270 107478 215271 107561 215271 107489 215271 107565 215272 107549 215272 107479 215272 107479 215273 107549 215273 107480 215273 107479 215274 107480 215274 107481 215274 107481 215275 107480 215275 107482 215275 107481 215276 107482 215276 107562 215276 107562 215277 107482 215277 107483 215277 107489 215278 107561 215278 107484 215278 107484 215279 107561 215279 107560 215279 107484 215280 107560 215280 107485 215280 107486 215281 107477 215281 107525 215281 107485 215282 107487 215282 107484 215282 107484 215283 107487 215283 107488 215283 107484 215284 107488 215284 107489 215284 107560 215285 107497 215285 107485 215285 107485 215286 107497 215286 107490 215286 107485 215287 107490 215287 107529 215287 107529 215288 107490 215288 107491 215288 107529 215289 107491 215289 107492 215289 107492 215290 107491 215290 107494 215290 107492 215291 107494 215291 107493 215291 107493 215292 107494 215292 107495 215292 107493 215293 107495 215293 107496 215293 107497 215294 107483 215294 107490 215294 107490 215295 107483 215295 107482 215295 107490 215296 107482 215296 107491 215296 107491 215297 107482 215297 107480 215297 107491 215298 107480 215298 107494 215298 107494 215299 107480 215299 107549 215299 107494 215300 107549 215300 107495 215300 107413 215301 107498 215301 107519 215301 107519 215302 107499 215302 107413 215302 107413 215303 107499 215303 107501 215303 107413 215304 107501 215304 107500 215304 107500 215305 107501 215305 107502 215305 107500 215306 107502 215306 107411 215306 107411 215307 107502 215307 107503 215307 107555 215308 107551 215308 107502 215308 107502 215309 107551 215309 107504 215309 107502 215310 107504 215310 107503 215310 107505 215311 107506 215311 107521 215311 107521 215312 107507 215312 107505 215312 107505 215313 107507 215313 107519 215313 107505 215314 107519 215314 107508 215314 107508 215315 107519 215315 107498 215315 107506 215316 107577 215316 107521 215316 107521 215317 107577 215317 107509 215317 107521 215318 107509 215318 107510 215318 107510 215319 107509 215319 107476 215319 107510 215320 107476 215320 107523 215320 107477 215321 107486 215321 107511 215321 107511 215322 107486 215322 107526 215322 107511 215323 107526 215323 107522 215323 107522 215324 107526 215324 107527 215324 107522 215325 107527 215325 107520 215325 107520 215326 107527 215326 107528 215326 107520 215327 107528 215327 107512 215327 107512 215328 107528 215328 107513 215328 107512 215329 107513 215329 107518 215329 107518 215330 107513 215330 107530 215330 107518 215331 107530 215331 107514 215331 107514 215332 107530 215332 107515 215332 107514 215333 107515 215333 107517 215333 107517 215334 107515 215334 107516 215334 107517 215335 107516 215335 107555 215335 107555 215336 107502 215336 107517 215336 107517 215337 107502 215337 107501 215337 107517 215338 107501 215338 107514 215338 107514 215339 107501 215339 107499 215339 107514 215340 107499 215340 107518 215340 107518 215341 107499 215341 107519 215341 107518 215342 107519 215342 107512 215342 107512 215343 107519 215343 107507 215343 107512 215344 107507 215344 107520 215344 107520 215345 107507 215345 107521 215345 107520 215346 107521 215346 107522 215346 107522 215347 107521 215347 107510 215347 107522 215348 107510 215348 107511 215348 107511 215349 107510 215349 107523 215349 107511 215350 107523 215350 107524 215350 107525 215351 107478 215351 107486 215351 107486 215352 107478 215352 107489 215352 107486 215353 107489 215353 107526 215353 107526 215354 107489 215354 107488 215354 107526 215355 107488 215355 107527 215355 107527 215356 107488 215356 107487 215356 107527 215357 107487 215357 107528 215357 107528 215358 107487 215358 107529 215358 107528 215359 107529 215359 107513 215359 107513 215360 107529 215360 107492 215360 107513 215361 107492 215361 107530 215361 107530 215362 107492 215362 107493 215362 107530 215363 107493 215363 107515 215363 107515 215364 107493 215364 107496 215364 107515 215365 107496 215365 107516 215365 107534 215366 107536 215366 107541 215366 107567 215367 107525 215367 107477 215367 107535 215368 107531 215368 107532 215368 107539 215369 107533 215369 107534 215369 107534 215370 107533 215370 107535 215370 107535 215371 107532 215371 107534 215371 107534 215372 107532 215372 107570 215372 107534 215373 107570 215373 107536 215373 107536 215374 107570 215374 107569 215374 107536 215375 107569 215375 107567 215375 107538 215376 107463 215376 107540 215376 107540 215377 107463 215377 107539 215377 107417 215378 107538 215378 107537 215378 107537 215379 107538 215379 107540 215379 107537 215380 107540 215380 107542 215380 107567 215381 107477 215381 107536 215381 107536 215382 107477 215382 107524 215382 107536 215383 107524 215383 107541 215383 107541 215384 107524 215384 107523 215384 107541 215385 107523 215385 107476 215385 107539 215386 107534 215386 107540 215386 107540 215387 107534 215387 107541 215387 107540 215388 107541 215388 107542 215388 107542 215389 107541 215389 107476 215389 107542 215390 107476 215390 107414 215390 107551 215391 107555 215391 107556 215391 107568 215392 107544 215392 107546 215392 107565 215393 107566 215393 107549 215393 107549 215394 107566 215394 107548 215394 107558 215395 107434 215395 107571 215395 107571 215396 107434 215396 107544 215396 107554 215397 107547 215397 107543 215397 107543 215398 107547 215398 107548 215398 107544 215399 107434 215399 107546 215399 107546 215400 107434 215400 107545 215400 107546 215401 107545 215401 107552 215401 107566 215402 107568 215402 107548 215402 107548 215403 107568 215403 107546 215403 107548 215404 107546 215404 107543 215404 107543 215405 107546 215405 107552 215405 107555 215406 107516 215406 107547 215406 107547 215407 107516 215407 107496 215407 107547 215408 107496 215408 107548 215408 107548 215409 107496 215409 107495 215409 107548 215410 107495 215410 107549 215410 107550 215411 107421 215411 107556 215411 107556 215412 107421 215412 107504 215412 107556 215413 107504 215413 107551 215413 107552 215414 107553 215414 107543 215414 107543 215415 107553 215415 107475 215415 107543 215416 107475 215416 107554 215416 107554 215417 107475 215417 107461 215417 107554 215418 107461 215418 107460 215418 107555 215419 107547 215419 107556 215419 107556 215420 107547 215420 107554 215420 107556 215421 107554 215421 107550 215421 107550 215422 107554 215422 107460 215422 107550 215423 107460 215423 107419 215423 107572 215424 107558 215424 107571 215424 107572 215425 107559 215425 107557 215425 107557 215426 107423 215426 107572 215426 107572 215427 107423 215427 107425 215427 107572 215428 107425 215428 107558 215428 107573 215429 107422 215429 107572 215429 107572 215430 107422 215430 107464 215430 107572 215431 107464 215431 107559 215431 107564 215432 107525 215432 107567 215432 107560 215433 107561 215433 107564 215433 107564 215434 107561 215434 107478 215434 107564 215435 107478 215435 107525 215435 107565 215436 107479 215436 107564 215436 107564 215437 107479 215437 107481 215437 107564 215438 107481 215438 107562 215438 107562 215439 107563 215439 107564 215439 107564 215440 107563 215440 107497 215440 107564 215441 107497 215441 107560 215441 107565 215442 107564 215442 107566 215442 107566 215443 107564 215443 107567 215443 107566 215444 107567 215444 107568 215444 107568 215445 107567 215445 107569 215445 107568 215446 107569 215446 107544 215446 107544 215447 107569 215447 107570 215447 107544 215448 107570 215448 107571 215448 107571 215449 107570 215449 107532 215449 107571 215450 107532 215450 107572 215450 107572 215451 107532 215451 107531 215451 107572 215452 107531 215452 107573 215452 107413 215453 107574 215453 107498 215453 107498 215454 107574 215454 107581 215454 107498 215455 107581 215455 107508 215455 107508 215456 107581 215456 107505 215456 107505 215457 107581 215457 107575 215457 107505 215458 107575 215458 107506 215458 107506 215459 107575 215459 107576 215459 107506 215460 107576 215460 107577 215460 107576 215461 107580 215461 107577 215461 107577 215462 107580 215462 107579 215462 107577 215463 107579 215463 107509 215463 107509 215464 107579 215464 107415 215464 107509 215465 107415 215465 107414 215465 107601 215466 107415 215466 107578 215466 107578 215467 107415 215467 107579 215467 107578 215468 107579 215468 107602 215468 107602 215469 107579 215469 107580 215469 107574 215470 107582 215470 107581 215470 107581 215471 107582 215471 107583 215471 107581 215472 107583 215472 107575 215472 107575 215473 107583 215473 107602 215473 107575 215474 107602 215474 107576 215474 107576 215475 107602 215475 107580 215475 107584 215476 107643 215476 107589 215476 107584 215477 107589 215477 107713 215477 107589 215478 107585 215478 107713 215478 107713 215479 107585 215479 107586 215479 107713 215480 107586 215480 107714 215480 107589 215481 107612 215481 107585 215481 107585 215482 107612 215482 107587 215482 107585 215483 107587 215483 107586 215483 107586 215484 107587 215484 107610 215484 107636 215485 107588 215485 107640 215485 107640 215486 107588 215486 107604 215486 107640 215487 107604 215487 107645 215487 107645 215488 107604 215488 107590 215488 107645 215489 107590 215489 107589 215489 107589 215490 107590 215490 107612 215490 107616 215491 107591 215491 107638 215491 107638 215492 107591 215492 107398 215492 107638 215493 107398 215493 107636 215493 107636 215494 107398 215494 107397 215494 107636 215495 107397 215495 107588 215495 107394 215496 107617 215496 107592 215496 107592 215497 107617 215497 107632 215497 107592 215498 107632 215498 107793 215498 107793 215499 107632 215499 107635 215499 107793 215500 107635 215500 107600 215500 107600 215501 107635 215501 107593 215501 107600 215502 107593 215502 107605 215502 107605 215503 107593 215503 107594 215503 107605 215504 107594 215504 107603 215504 107603 215505 107594 215505 107595 215505 107603 215506 107595 215506 107607 215506 107663 215507 107596 215507 107625 215507 107625 215508 107596 215508 107597 215508 107625 215509 107597 215509 107598 215509 107598 215510 107597 215510 107607 215510 107598 215511 107607 215511 107599 215511 107599 215512 107607 215512 107595 215512 107792 215513 107793 215513 107600 215513 107601 215514 107578 215514 107607 215514 107607 215515 107578 215515 107602 215515 107607 215516 107602 215516 107603 215516 107603 215517 107602 215517 107583 215517 107603 215518 107583 215518 107605 215518 107397 215519 107796 215519 107588 215519 107588 215520 107796 215520 107388 215520 107588 215521 107388 215521 107604 215521 107583 215522 107582 215522 107605 215522 107605 215523 107582 215523 107606 215523 107605 215524 107606 215524 107600 215524 107600 215525 107606 215525 107393 215525 107600 215526 107393 215526 107792 215526 107607 215527 107597 215527 107601 215527 107601 215528 107597 215528 107596 215528 107601 215529 107596 215529 107608 215529 107608 215530 107596 215530 107621 215530 107608 215531 107621 215531 107609 215531 107609 215532 107621 215532 107610 215532 107609 215533 107610 215533 107611 215533 107611 215534 107610 215534 107587 215534 107611 215535 107587 215535 107391 215535 107391 215536 107587 215536 107612 215536 107391 215537 107612 215537 107613 215537 107613 215538 107612 215538 107590 215538 107613 215539 107590 215539 107614 215539 107614 215540 107590 215540 107604 215540 107614 215541 107604 215541 107615 215541 107615 215542 107604 215542 107388 215542 107591 215543 107616 215543 107619 215543 107591 215544 107619 215544 107395 215544 107395 215545 107619 215545 107617 215545 107395 215546 107617 215546 107394 215546 107631 215547 107617 215547 107618 215547 107618 215548 107617 215548 107619 215548 107618 215549 107619 215549 107651 215549 107616 215550 107620 215550 107619 215550 107619 215551 107620 215551 107653 215551 107619 215552 107653 215552 107651 215552 107586 215553 107610 215553 107664 215553 107664 215554 107610 215554 107621 215554 107664 215555 107621 215555 107663 215555 107663 215556 107621 215556 107596 215556 107632 215557 107617 215557 107631 215557 107622 215558 107663 215558 107623 215558 107623 215559 107663 215559 107625 215559 107623 215560 107625 215560 107624 215560 107624 215561 107625 215561 107626 215561 107625 215562 107598 215562 107626 215562 107626 215563 107598 215563 107599 215563 107626 215564 107599 215564 107627 215564 107627 215565 107599 215565 107595 215565 107627 215566 107595 215566 107705 215566 107705 215567 107595 215567 107594 215567 107705 215568 107594 215568 107628 215568 107634 215569 107666 215569 107593 215569 107593 215570 107666 215570 107629 215570 107593 215571 107629 215571 107594 215571 107594 215572 107629 215572 107630 215572 107594 215573 107630 215573 107628 215573 107631 215574 107633 215574 107632 215574 107632 215575 107633 215575 107634 215575 107632 215576 107634 215576 107635 215576 107635 215577 107634 215577 107593 215577 107734 215578 107637 215578 107636 215578 107620 215579 107616 215579 107735 215579 107735 215580 107616 215580 107638 215580 107637 215581 107738 215581 107636 215581 107636 215582 107738 215582 107737 215582 107636 215583 107737 215583 107638 215583 107638 215584 107737 215584 107736 215584 107638 215585 107736 215585 107735 215585 107734 215586 107636 215586 107639 215586 107639 215587 107636 215587 107640 215587 107639 215588 107640 215588 107641 215588 107641 215589 107640 215589 107642 215589 107642 215590 107640 215590 107645 215590 107642 215591 107645 215591 107646 215591 107589 215592 107643 215592 107645 215592 107645 215593 107643 215593 107644 215593 107645 215594 107644 215594 107646 215594 107658 215595 107647 215595 107662 215595 107647 215596 107658 215596 107727 215596 107650 215597 107652 215597 107648 215597 107649 215598 107631 215598 107618 215598 107689 215599 107691 215599 107650 215599 107650 215600 107691 215600 107649 215600 107649 215601 107618 215601 107650 215601 107650 215602 107618 215602 107651 215602 107650 215603 107651 215603 107652 215603 107652 215604 107651 215604 107653 215604 107652 215605 107653 215605 107620 215605 107654 215606 107687 215606 107655 215606 107655 215607 107687 215607 107689 215607 107620 215608 107739 215608 107652 215608 107652 215609 107739 215609 107656 215609 107652 215610 107656 215610 107648 215610 107648 215611 107656 215611 107764 215611 107648 215612 107764 215612 107659 215612 107657 215613 107654 215613 107660 215613 107660 215614 107654 215614 107655 215614 107660 215615 107655 215615 107658 215615 107689 215616 107650 215616 107655 215616 107655 215617 107650 215617 107648 215617 107655 215618 107648 215618 107658 215618 107658 215619 107648 215619 107659 215619 107658 215620 107659 215620 107727 215620 107765 215621 107657 215621 107766 215621 107766 215622 107657 215622 107660 215622 107766 215623 107660 215623 107775 215623 107775 215624 107660 215624 107658 215624 107775 215625 107658 215625 107661 215625 107661 215626 107658 215626 107662 215626 107714 215627 107586 215627 107788 215627 107788 215628 107586 215628 107664 215628 107788 215629 107664 215629 107790 215629 107663 215630 107622 215630 107664 215630 107664 215631 107622 215631 107665 215631 107664 215632 107665 215632 107790 215632 107666 215633 107634 215633 107700 215633 107684 215634 107681 215634 107667 215634 107674 215635 107668 215635 107676 215635 107768 215636 107669 215636 107702 215636 107684 215637 107670 215637 107681 215637 107681 215638 107670 215638 107671 215638 107681 215639 107671 215639 107768 215639 107672 215640 107767 215640 107711 215640 107711 215641 107767 215641 107673 215641 107711 215642 107673 215642 107675 215642 107711 215643 107712 215643 107672 215643 107672 215644 107712 215644 107657 215644 107672 215645 107657 215645 107765 215645 107673 215646 107674 215646 107675 215646 107675 215647 107674 215647 107676 215647 107675 215648 107676 215648 107678 215648 107678 215649 107676 215649 107677 215649 107678 215650 107677 215650 107708 215650 107708 215651 107677 215651 107685 215651 107708 215652 107685 215652 107706 215652 107706 215653 107685 215653 107686 215653 107706 215654 107686 215654 107679 215654 107623 215655 107624 215655 107680 215655 107680 215656 107624 215656 107703 215656 107768 215657 107702 215657 107681 215657 107681 215658 107702 215658 107682 215658 107681 215659 107682 215659 107667 215659 107667 215660 107682 215660 107680 215660 107667 215661 107680 215661 107683 215661 107683 215662 107680 215662 107703 215662 107683 215663 107703 215663 107704 215663 107668 215664 107670 215664 107676 215664 107676 215665 107670 215665 107684 215665 107676 215666 107684 215666 107677 215666 107677 215667 107684 215667 107667 215667 107677 215668 107667 215668 107685 215668 107685 215669 107667 215669 107683 215669 107685 215670 107683 215670 107686 215670 107686 215671 107683 215671 107704 215671 107686 215672 107704 215672 107679 215672 107705 215673 107628 215673 107707 215673 107707 215674 107628 215674 107630 215674 107707 215675 107630 215675 107629 215675 107654 215676 107688 215676 107687 215676 107687 215677 107688 215677 107697 215677 107687 215678 107697 215678 107689 215678 107689 215679 107697 215679 107690 215679 107689 215680 107690 215680 107691 215680 107691 215681 107690 215681 107692 215681 107691 215682 107692 215682 107649 215682 107649 215683 107692 215683 107693 215683 107649 215684 107693 215684 107631 215684 107631 215685 107693 215685 107633 215685 107629 215686 107666 215686 107707 215686 107707 215687 107666 215687 107700 215687 107707 215688 107700 215688 107694 215688 107694 215689 107700 215689 107699 215689 107694 215690 107699 215690 107695 215690 107695 215691 107699 215691 107696 215691 107695 215692 107696 215692 107709 215692 107709 215693 107696 215693 107698 215693 107709 215694 107698 215694 107710 215694 107688 215695 107710 215695 107697 215695 107697 215696 107710 215696 107698 215696 107697 215697 107698 215697 107690 215697 107690 215698 107698 215698 107696 215698 107690 215699 107696 215699 107692 215699 107692 215700 107696 215700 107699 215700 107692 215701 107699 215701 107693 215701 107693 215702 107699 215702 107700 215702 107693 215703 107700 215703 107633 215703 107633 215704 107700 215704 107634 215704 107622 215705 107623 215705 107791 215705 107791 215706 107623 215706 107680 215706 107791 215707 107680 215707 107701 215707 107701 215708 107680 215708 107682 215708 107701 215709 107682 215709 107786 215709 107786 215710 107682 215710 107702 215710 107786 215711 107702 215711 107780 215711 107780 215712 107702 215712 107669 215712 107780 215713 107669 215713 107778 215713 107624 215714 107626 215714 107703 215714 107703 215715 107626 215715 107627 215715 107703 215716 107627 215716 107704 215716 107704 215717 107627 215717 107705 215717 107704 215718 107705 215718 107679 215718 107679 215719 107705 215719 107707 215719 107679 215720 107707 215720 107706 215720 107706 215721 107707 215721 107694 215721 107706 215722 107694 215722 107708 215722 107708 215723 107694 215723 107695 215723 107708 215724 107695 215724 107678 215724 107678 215725 107695 215725 107709 215725 107678 215726 107709 215726 107675 215726 107675 215727 107709 215727 107710 215727 107675 215728 107710 215728 107711 215728 107711 215729 107710 215729 107688 215729 107711 215730 107688 215730 107712 215730 107712 215731 107688 215731 107654 215731 107712 215732 107654 215732 107657 215732 107713 215733 107714 215733 107787 215733 107762 215734 107761 215734 107724 215734 107756 215735 107758 215735 107743 215735 107769 215736 107773 215736 107716 215736 107716 215737 107773 215737 107715 215737 107716 215738 107715 215738 107730 215738 107730 215739 107715 215739 107662 215739 107730 215740 107662 215740 107647 215740 107717 215741 107743 215741 107772 215741 107759 215742 107771 215742 107719 215742 107719 215743 107771 215743 107718 215743 107719 215744 107718 215744 107721 215744 107721 215745 107718 215745 107720 215745 107721 215746 107720 215746 107724 215746 107724 215747 107761 215747 107721 215747 107721 215748 107761 215748 107722 215748 107721 215749 107722 215749 107719 215749 107720 215750 107728 215750 107724 215750 107724 215751 107728 215751 107723 215751 107724 215752 107723 215752 107762 215752 107762 215753 107723 215753 107729 215753 107762 215754 107729 215754 107725 215754 107725 215755 107729 215755 107731 215755 107725 215756 107731 215756 107726 215756 107726 215757 107731 215757 107727 215757 107726 215758 107727 215758 107659 215758 107728 215759 107769 215759 107723 215759 107723 215760 107769 215760 107716 215760 107723 215761 107716 215761 107729 215761 107729 215762 107716 215762 107730 215762 107729 215763 107730 215763 107731 215763 107731 215764 107730 215764 107647 215764 107731 215765 107647 215765 107727 215765 107732 215766 107639 215766 107641 215766 107732 215767 107641 215767 107733 215767 107639 215768 107732 215768 107734 215768 107734 215769 107732 215769 107755 215769 107734 215770 107755 215770 107637 215770 107735 215771 107736 215771 107754 215771 107754 215772 107736 215772 107737 215772 107754 215773 107737 215773 107755 215773 107755 215774 107737 215774 107738 215774 107755 215775 107738 215775 107637 215775 107620 215776 107735 215776 107739 215776 107739 215777 107735 215777 107754 215777 107739 215778 107754 215778 107656 215778 107643 215779 107740 215779 107644 215779 107644 215780 107740 215780 107741 215780 107644 215781 107741 215781 107646 215781 107646 215782 107741 215782 107733 215782 107646 215783 107733 215783 107642 215783 107642 215784 107733 215784 107641 215784 107643 215785 107584 215785 107740 215785 107740 215786 107584 215786 107713 215786 107740 215787 107713 215787 107742 215787 107742 215788 107713 215788 107787 215788 107742 215789 107787 215789 107757 215789 107743 215790 107717 215790 107756 215790 107756 215791 107717 215791 107760 215791 107756 215792 107760 215792 107744 215792 107744 215793 107760 215793 107745 215793 107744 215794 107745 215794 107746 215794 107746 215795 107745 215795 107747 215795 107746 215796 107747 215796 107749 215796 107749 215797 107747 215797 107748 215797 107749 215798 107748 215798 107750 215798 107750 215799 107748 215799 107752 215799 107750 215800 107752 215800 107751 215800 107751 215801 107752 215801 107763 215801 107751 215802 107763 215802 107753 215802 107753 215803 107763 215803 107764 215803 107753 215804 107764 215804 107656 215804 107656 215805 107754 215805 107753 215805 107753 215806 107754 215806 107755 215806 107753 215807 107755 215807 107751 215807 107751 215808 107755 215808 107732 215808 107751 215809 107732 215809 107750 215809 107750 215810 107732 215810 107733 215810 107750 215811 107733 215811 107749 215811 107749 215812 107733 215812 107741 215812 107749 215813 107741 215813 107746 215813 107746 215814 107741 215814 107740 215814 107746 215815 107740 215815 107744 215815 107744 215816 107740 215816 107742 215816 107744 215817 107742 215817 107756 215817 107756 215818 107742 215818 107757 215818 107756 215819 107757 215819 107758 215819 107772 215820 107759 215820 107717 215820 107717 215821 107759 215821 107719 215821 107717 215822 107719 215822 107760 215822 107760 215823 107719 215823 107722 215823 107760 215824 107722 215824 107745 215824 107745 215825 107722 215825 107761 215825 107745 215826 107761 215826 107747 215826 107747 215827 107761 215827 107762 215827 107747 215828 107762 215828 107748 215828 107748 215829 107762 215829 107725 215829 107748 215830 107725 215830 107752 215830 107752 215831 107725 215831 107726 215831 107752 215832 107726 215832 107763 215832 107763 215833 107726 215833 107659 215833 107763 215834 107659 215834 107764 215834 107770 215835 107772 215835 107774 215835 107777 215836 107765 215836 107766 215836 107672 215837 107765 215837 107767 215837 107767 215838 107765 215838 107777 215838 107767 215839 107777 215839 107673 215839 107673 215840 107777 215840 107674 215840 107669 215841 107768 215841 107777 215841 107777 215842 107768 215842 107671 215842 107671 215843 107670 215843 107777 215843 107777 215844 107670 215844 107668 215844 107777 215845 107668 215845 107674 215845 107769 215846 107728 215846 107770 215846 107770 215847 107728 215847 107720 215847 107759 215848 107772 215848 107771 215848 107771 215849 107772 215849 107770 215849 107771 215850 107770 215850 107718 215850 107718 215851 107770 215851 107720 215851 107662 215852 107715 215852 107770 215852 107770 215853 107715 215853 107773 215853 107770 215854 107773 215854 107769 215854 107662 215855 107770 215855 107661 215855 107661 215856 107770 215856 107774 215856 107661 215857 107774 215857 107775 215857 107775 215858 107774 215858 107782 215858 107775 215859 107782 215859 107766 215859 107766 215860 107782 215860 107776 215860 107766 215861 107776 215861 107777 215861 107777 215862 107776 215862 107778 215862 107777 215863 107778 215863 107669 215863 107787 215864 107714 215864 107788 215864 107758 215865 107757 215865 107789 215865 107791 215866 107701 215866 107779 215866 107786 215867 107780 215867 107784 215867 107780 215868 107778 215868 107784 215868 107784 215869 107778 215869 107776 215869 107784 215870 107776 215870 107781 215870 107781 215871 107776 215871 107782 215871 107781 215872 107782 215872 107783 215872 107783 215873 107782 215873 107774 215873 107783 215874 107774 215874 107743 215874 107743 215875 107774 215875 107772 215875 107743 215876 107758 215876 107783 215876 107783 215877 107758 215877 107789 215877 107783 215878 107789 215878 107781 215878 107781 215879 107789 215879 107785 215879 107781 215880 107785 215880 107784 215880 107784 215881 107785 215881 107779 215881 107784 215882 107779 215882 107786 215882 107786 215883 107779 215883 107701 215883 107757 215884 107787 215884 107789 215884 107789 215885 107787 215885 107788 215885 107789 215886 107788 215886 107785 215886 107785 215887 107788 215887 107790 215887 107785 215888 107790 215888 107779 215888 107779 215889 107790 215889 107665 215889 107779 215890 107665 215890 107791 215890 107791 215891 107665 215891 107622 215891 107793 215892 107792 215892 107410 215892 107793 215893 107410 215893 107794 215893 107410 215894 107420 215894 107794 215894 107794 215895 107420 215895 107795 215895 107794 215896 107795 215896 107396 215896 107396 215897 107795 215897 107397 215897 107397 215898 107795 215898 107399 215898 107397 215899 107399 215899 107796 215899 107415 215900 107601 215900 107416 215900 107416 215901 107601 215901 107608 215901 107416 215902 107608 215902 107797 215902 107797 215903 107608 215903 107609 215903 107797 215904 107609 215904 107418 215904 107418 215905 107609 215905 107611 215905 108002 215906 108001 215906 107799 215906 107799 215907 108001 215907 107798 215907 107799 215908 107798 215908 108080 215908 108086 215909 107800 215909 107801 215909 107801 215910 107800 215910 107802 215910 107801 215911 107802 215911 107798 215911 107798 215912 107802 215912 108077 215912 107798 215913 108077 215913 108080 215913 108086 215914 107801 215914 108085 215914 108085 215915 107801 215915 107809 215915 108085 215916 107809 215916 108083 215916 108083 215917 107809 215917 107803 215917 108083 215918 107803 215918 108088 215918 108088 215919 107803 215919 107804 215919 108088 215920 107804 215920 107805 215920 107804 215921 107806 215921 107805 215921 107805 215922 107806 215922 107807 215922 107805 215923 107807 215923 108090 215923 108090 215924 107807 215924 107969 215924 108090 215925 107969 215925 108060 215925 108173 215926 107969 215926 107808 215926 107808 215927 107969 215927 107807 215927 107808 215928 107807 215928 108175 215928 108175 215929 107807 215929 107806 215929 107806 215930 107804 215930 108175 215930 108175 215931 107804 215931 107803 215931 108175 215932 107803 215932 107810 215932 108001 215933 108177 215933 107798 215933 107798 215934 108177 215934 108176 215934 107798 215935 108176 215935 107801 215935 107801 215936 108176 215936 107810 215936 107801 215937 107810 215937 107809 215937 107809 215938 107810 215938 107803 215938 107828 215939 107811 215939 108214 215939 108214 215940 107811 215940 107907 215940 108214 215941 107907 215941 107812 215941 108214 215942 108185 215942 107828 215942 107828 215943 108185 215943 108182 215943 107825 215944 107889 215944 107945 215944 107889 215945 107825 215945 107826 215945 107816 215946 107818 215946 107824 215946 107813 215947 107814 215947 108190 215947 107823 215948 107815 215948 107816 215948 107816 215949 107815 215949 107813 215949 107813 215950 108190 215950 107816 215950 107816 215951 108190 215951 108193 215951 107816 215952 108193 215952 107818 215952 107818 215953 108193 215953 108192 215953 107818 215954 108192 215954 107817 215954 107821 215955 107852 215955 107822 215955 107822 215956 107852 215956 107823 215956 107817 215957 107905 215957 107818 215957 107818 215958 107905 215958 107919 215958 107818 215959 107919 215959 107824 215959 107824 215960 107919 215960 107918 215960 107824 215961 107918 215961 107819 215961 107883 215962 107821 215962 107820 215962 107820 215963 107821 215963 107822 215963 107820 215964 107822 215964 107825 215964 107823 215965 107816 215965 107822 215965 107822 215966 107816 215966 107824 215966 107822 215967 107824 215967 107825 215967 107825 215968 107824 215968 107819 215968 107825 215969 107819 215969 107826 215969 107935 215970 107883 215970 107947 215970 107947 215971 107883 215971 107820 215971 107947 215972 107820 215972 107827 215972 107827 215973 107820 215973 107825 215973 107827 215974 107825 215974 107946 215974 107946 215975 107825 215975 107945 215975 107811 215976 107828 215976 107950 215976 107950 215977 107828 215977 108194 215977 107950 215978 108194 215978 107960 215978 107960 215979 108194 215979 107962 215979 107962 215980 108194 215980 107829 215980 107962 215981 107829 215981 107866 215981 107830 215982 108201 215982 107831 215982 107858 215983 107865 215983 107859 215983 107848 215984 107834 215984 107849 215984 107838 215985 107832 215985 107847 215985 107844 215986 107938 215986 107871 215986 107848 215987 107833 215987 107834 215987 107834 215988 107833 215988 107835 215988 107834 215989 107835 215989 107844 215989 107837 215990 107936 215990 107882 215990 107882 215991 107936 215991 107937 215991 107882 215992 107937 215992 107881 215992 107882 215993 107836 215993 107837 215993 107837 215994 107836 215994 107883 215994 107837 215995 107883 215995 107935 215995 107937 215996 107838 215996 107881 215996 107881 215997 107838 215997 107847 215997 107881 215998 107847 215998 107879 215998 107879 215999 107847 215999 107839 215999 107879 216000 107839 216000 107878 216000 107878 216001 107839 216001 107841 216001 107878 216002 107841 216002 107840 216002 107840 216003 107841 216003 107842 216003 107840 216004 107842 216004 107876 216004 107867 216005 107843 216005 107868 216005 107868 216006 107843 216006 107846 216006 107844 216007 107871 216007 107834 216007 107834 216008 107871 216008 107870 216008 107834 216009 107870 216009 107849 216009 107849 216010 107870 216010 107868 216010 107849 216011 107868 216011 107845 216011 107845 216012 107868 216012 107846 216012 107845 216013 107846 216013 107875 216013 107832 216014 107833 216014 107847 216014 107847 216015 107833 216015 107848 216015 107847 216016 107848 216016 107839 216016 107839 216017 107848 216017 107849 216017 107839 216018 107849 216018 107841 216018 107841 216019 107849 216019 107845 216019 107841 216020 107845 216020 107842 216020 107842 216021 107845 216021 107875 216021 107842 216022 107875 216022 107876 216022 107830 216023 107831 216023 107850 216023 107821 216024 107851 216024 107852 216024 107852 216025 107851 216025 107853 216025 107852 216026 107853 216026 107823 216026 107823 216027 107853 216027 107854 216027 107823 216028 107854 216028 107815 216028 107815 216029 107854 216029 107855 216029 107815 216030 107855 216030 107813 216030 107813 216031 107855 216031 107856 216031 107813 216032 107856 216032 107814 216032 107814 216033 107856 216033 107857 216033 108201 216034 107858 216034 107831 216034 107831 216035 107858 216035 107859 216035 107831 216036 107859 216036 107877 216036 107877 216037 107859 216037 107864 216037 107877 216038 107864 216038 107880 216038 107880 216039 107864 216039 107863 216039 107880 216040 107863 216040 107860 216040 107860 216041 107863 216041 107861 216041 107860 216042 107861 216042 107862 216042 107851 216043 107862 216043 107853 216043 107853 216044 107862 216044 107861 216044 107853 216045 107861 216045 107854 216045 107854 216046 107861 216046 107863 216046 107854 216047 107863 216047 107855 216047 107855 216048 107863 216048 107864 216048 107855 216049 107864 216049 107856 216049 107856 216050 107864 216050 107859 216050 107856 216051 107859 216051 107857 216051 107857 216052 107859 216052 107865 216052 107866 216053 107867 216053 107951 216053 107951 216054 107867 216054 107868 216054 107951 216055 107868 216055 107952 216055 107952 216056 107868 216056 107870 216056 107952 216057 107870 216057 107869 216057 107869 216058 107870 216058 107871 216058 107869 216059 107871 216059 107872 216059 107872 216060 107871 216060 107938 216060 107872 216061 107938 216061 107873 216061 107843 216062 107874 216062 107846 216062 107846 216063 107874 216063 108198 216063 107846 216064 108198 216064 107875 216064 107875 216065 108198 216065 107850 216065 107875 216066 107850 216066 107876 216066 107876 216067 107850 216067 107831 216067 107876 216068 107831 216068 107840 216068 107840 216069 107831 216069 107877 216069 107840 216070 107877 216070 107878 216070 107878 216071 107877 216071 107880 216071 107878 216072 107880 216072 107879 216072 107879 216073 107880 216073 107860 216073 107879 216074 107860 216074 107881 216074 107881 216075 107860 216075 107862 216075 107881 216076 107862 216076 107882 216076 107882 216077 107862 216077 107851 216077 107882 216078 107851 216078 107836 216078 107836 216079 107851 216079 107821 216079 107836 216080 107821 216080 107883 216080 107907 216081 107811 216081 107884 216081 107895 216082 107885 216082 107894 216082 107886 216083 107956 216083 107911 216083 107900 216084 107944 216084 107887 216084 107887 216085 107944 216085 107943 216085 107887 216086 107943 216086 107888 216086 107888 216087 107943 216087 107945 216087 107888 216088 107945 216088 107889 216088 107890 216089 107911 216089 107955 216089 107926 216090 107891 216090 107927 216090 107927 216091 107891 216091 107892 216091 107927 216092 107892 216092 107893 216092 107893 216093 107892 216093 107940 216093 107893 216094 107940 216094 107894 216094 107894 216095 107885 216095 107893 216095 107893 216096 107885 216096 107929 216096 107893 216097 107929 216097 107927 216097 107940 216098 107899 216098 107894 216098 107894 216099 107899 216099 107901 216099 107894 216100 107901 216100 107895 216100 107895 216101 107901 216101 107902 216101 107895 216102 107902 216102 107897 216102 107897 216103 107902 216103 107896 216103 107897 216104 107896 216104 107898 216104 107898 216105 107896 216105 107826 216105 107898 216106 107826 216106 107819 216106 107899 216107 107900 216107 107901 216107 107901 216108 107900 216108 107887 216108 107901 216109 107887 216109 107902 216109 107902 216110 107887 216110 107888 216110 107902 216111 107888 216111 107896 216111 107896 216112 107888 216112 107889 216112 107896 216113 107889 216113 107826 216113 107923 216114 108210 216114 107903 216114 107923 216115 107903 216115 107904 216115 108210 216116 107923 216116 108209 216116 108209 216117 107923 216117 107921 216117 108209 216118 107921 216118 108206 216118 108206 216119 107921 216119 107906 216119 108206 216120 107906 216120 108203 216120 107817 216121 108203 216121 107905 216121 107905 216122 108203 216122 107906 216122 107905 216123 107906 216123 107919 216123 107907 216124 107884 216124 107812 216124 108213 216125 107908 216125 107909 216125 107909 216126 107924 216126 108213 216126 108213 216127 107924 216127 107904 216127 108213 216128 107904 216128 108211 216128 108211 216129 107904 216129 107903 216129 107908 216130 108215 216130 107909 216130 107909 216131 108215 216131 107812 216131 107909 216132 107812 216132 107925 216132 107925 216133 107812 216133 107884 216133 107925 216134 107884 216134 107910 216134 107911 216135 107890 216135 107886 216135 107886 216136 107890 216136 107928 216136 107886 216137 107928 216137 107912 216137 107912 216138 107928 216138 107913 216138 107912 216139 107913 216139 107914 216139 107914 216140 107913 216140 107930 216140 107914 216141 107930 216141 107915 216141 107915 216142 107930 216142 107931 216142 107915 216143 107931 216143 107916 216143 107916 216144 107931 216144 107917 216144 107916 216145 107917 216145 107922 216145 107922 216146 107917 216146 107932 216146 107922 216147 107932 216147 107920 216147 107920 216148 107932 216148 107918 216148 107920 216149 107918 216149 107919 216149 107919 216150 107906 216150 107920 216150 107920 216151 107906 216151 107921 216151 107920 216152 107921 216152 107922 216152 107922 216153 107921 216153 107923 216153 107922 216154 107923 216154 107916 216154 107916 216155 107923 216155 107904 216155 107916 216156 107904 216156 107915 216156 107915 216157 107904 216157 107924 216157 107915 216158 107924 216158 107914 216158 107914 216159 107924 216159 107909 216159 107914 216160 107909 216160 107912 216160 107912 216161 107909 216161 107925 216161 107912 216162 107925 216162 107886 216162 107886 216163 107925 216163 107910 216163 107886 216164 107910 216164 107956 216164 107955 216165 107926 216165 107890 216165 107890 216166 107926 216166 107927 216166 107890 216167 107927 216167 107928 216167 107928 216168 107927 216168 107929 216168 107928 216169 107929 216169 107913 216169 107913 216170 107929 216170 107885 216170 107913 216171 107885 216171 107930 216171 107930 216172 107885 216172 107895 216172 107930 216173 107895 216173 107931 216173 107931 216174 107895 216174 107897 216174 107931 216175 107897 216175 107917 216175 107917 216176 107897 216176 107898 216176 107917 216177 107898 216177 107932 216177 107932 216178 107898 216178 107819 216178 107932 216179 107819 216179 107918 216179 107933 216180 107955 216180 107934 216180 107939 216181 107935 216181 107947 216181 107837 216182 107935 216182 107936 216182 107936 216183 107935 216183 107939 216183 107936 216184 107939 216184 107937 216184 107937 216185 107939 216185 107838 216185 107938 216186 107844 216186 107939 216186 107939 216187 107844 216187 107835 216187 107835 216188 107833 216188 107939 216188 107939 216189 107833 216189 107832 216189 107939 216190 107832 216190 107838 216190 107900 216191 107899 216191 107933 216191 107933 216192 107899 216192 107940 216192 107941 216193 107955 216193 107942 216193 107942 216194 107955 216194 107933 216194 107942 216195 107933 216195 107892 216195 107892 216196 107933 216196 107940 216196 107945 216197 107943 216197 107933 216197 107933 216198 107943 216198 107944 216198 107933 216199 107944 216199 107900 216199 107945 216200 107933 216200 107946 216200 107946 216201 107933 216201 107934 216201 107946 216202 107934 216202 107827 216202 107827 216203 107934 216203 107948 216203 107827 216204 107948 216204 107947 216204 107947 216205 107948 216205 107949 216205 107947 216206 107949 216206 107939 216206 107939 216207 107949 216207 107873 216207 107939 216208 107873 216208 107938 216208 107884 216209 107811 216209 107950 216209 107956 216210 107910 216210 107957 216210 107951 216211 107952 216211 107961 216211 107869 216212 107872 216212 107959 216212 107872 216213 107873 216213 107959 216213 107959 216214 107873 216214 107949 216214 107959 216215 107949 216215 107953 216215 107953 216216 107949 216216 107948 216216 107953 216217 107948 216217 107954 216217 107954 216218 107948 216218 107934 216218 107954 216219 107934 216219 107911 216219 107911 216220 107934 216220 107955 216220 107911 216221 107956 216221 107954 216221 107954 216222 107956 216222 107957 216222 107954 216223 107957 216223 107953 216223 107953 216224 107957 216224 107958 216224 107953 216225 107958 216225 107959 216225 107959 216226 107958 216226 107961 216226 107959 216227 107961 216227 107869 216227 107869 216228 107961 216228 107952 216228 107910 216229 107884 216229 107957 216229 107957 216230 107884 216230 107950 216230 107957 216231 107950 216231 107958 216231 107958 216232 107950 216232 107960 216232 107958 216233 107960 216233 107961 216233 107961 216234 107960 216234 107962 216234 107961 216235 107962 216235 107951 216235 107951 216236 107962 216236 107866 216236 107982 216237 107980 216237 107963 216237 107982 216238 107963 216238 107965 216238 107963 216239 107964 216239 107965 216239 107965 216240 107964 216240 107966 216240 107965 216241 107966 216241 107967 216241 107967 216242 107966 216242 107968 216242 107968 216243 107966 216243 107985 216243 107968 216244 107985 216244 107972 216244 107969 216245 108173 216245 108004 216245 108004 216246 108173 216246 108180 216246 108004 216247 108180 216247 108005 216247 108005 216248 108180 216248 107971 216248 108005 216249 107971 216249 107970 216249 107970 216250 107971 216250 108183 216250 108186 216251 107972 216251 107985 216251 107999 216252 107978 216252 107974 216252 107985 216253 107984 216253 108186 216253 108186 216254 107984 216254 107973 216254 108186 216255 107973 216255 107974 216255 107974 216256 107973 216256 107975 216256 107974 216257 107975 216257 107999 216257 107999 216258 107976 216258 107978 216258 107978 216259 107976 216259 107977 216259 107978 216260 107977 216260 107979 216260 107970 216261 108183 216261 107987 216261 107987 216262 108183 216262 108184 216262 107987 216263 108184 216263 107991 216263 107991 216264 108184 216264 107979 216264 107991 216265 107979 216265 107989 216265 107989 216266 107979 216266 107977 216266 107963 216267 107980 216267 108000 216267 108000 216268 107980 216268 108178 216268 108000 216269 108178 216269 108001 216269 108001 216270 108178 216270 108177 216270 107967 216271 107968 216271 108164 216271 107981 216272 107982 216272 107983 216272 107983 216273 107982 216273 107965 216273 107983 216274 107965 216274 108188 216274 108188 216275 107965 216275 107967 216275 108188 216276 107967 216276 108187 216276 108187 216277 107967 216277 108164 216277 107984 216278 107985 216278 108142 216278 108121 216279 107970 216279 107986 216279 107986 216280 107970 216280 107987 216280 107986 216281 107987 216281 108029 216281 108029 216282 107987 216282 107988 216282 107977 216283 107990 216283 107989 216283 107989 216284 107990 216284 107988 216284 107989 216285 107988 216285 107991 216285 107991 216286 107988 216286 107987 216286 107999 216287 107992 216287 107976 216287 107976 216288 107992 216288 107993 216288 107976 216289 107993 216289 107977 216289 107977 216290 107993 216290 107994 216290 107977 216291 107994 216291 107990 216291 107995 216292 107996 216292 107975 216292 107975 216293 107996 216293 107997 216293 107975 216294 107997 216294 107999 216294 107999 216295 107997 216295 107998 216295 107999 216296 107998 216296 107992 216296 108142 216297 108027 216297 107984 216297 107984 216298 108027 216298 107995 216298 107984 216299 107995 216299 107973 216299 107973 216300 107995 216300 107975 216300 108082 216301 108138 216301 107963 216301 107963 216302 108000 216302 108082 216302 108082 216303 108000 216303 108001 216303 108082 216304 108001 216304 108002 216304 108060 216305 107969 216305 108003 216305 108003 216306 107969 216306 108004 216306 108003 216307 108004 216307 108122 216307 108122 216308 108004 216308 108005 216308 108122 216309 108005 216309 108121 216309 108121 216310 108005 216310 107970 216310 108142 216311 107985 216311 107966 216311 108142 216312 107966 216312 108006 216312 108006 216313 107966 216313 107964 216313 108006 216314 107964 216314 108007 216314 108007 216315 107964 216315 107963 216315 108007 216316 107963 216316 108138 216316 108044 216317 108157 216317 108118 216317 108008 216318 108044 216318 108024 216318 108016 216319 108018 216319 108009 216319 108009 216320 108018 216320 108010 216320 108009 216321 108010 216321 108011 216321 108011 216322 108010 216322 108020 216322 108011 216323 108020 216323 108146 216323 108146 216324 108020 216324 108132 216324 108021 216325 108014 216325 108022 216325 108012 216326 108058 216326 108019 216326 108019 216327 108058 216327 108013 216327 108019 216328 108013 216328 108021 216328 108021 216329 108013 216329 108059 216329 108021 216330 108059 216330 108014 216330 108048 216331 108018 216331 108015 216331 108015 216332 108018 216332 108016 216332 108015 216333 108016 216333 108017 216333 108048 216334 108012 216334 108018 216334 108018 216335 108012 216335 108019 216335 108018 216336 108019 216336 108010 216336 108010 216337 108019 216337 108021 216337 108010 216338 108021 216338 108020 216338 108020 216339 108021 216339 108022 216339 108020 216340 108022 216340 108132 216340 108052 216341 108023 216341 108048 216341 108048 216342 108023 216342 108056 216342 108048 216343 108056 216343 108012 216343 108047 216344 108008 216344 108049 216344 108049 216345 108008 216345 108024 216345 108049 216346 108024 216346 108050 216346 108050 216347 108024 216347 108051 216347 108054 216348 108053 216348 108030 216348 108029 216349 108025 216349 107986 216349 107986 216350 108025 216350 108026 216350 107986 216351 108026 216351 108121 216351 108028 216352 108027 216352 108042 216352 108042 216353 108027 216353 108142 216353 108042 216354 108142 216354 108141 216354 107998 216355 107997 216355 108040 216355 108040 216356 107997 216356 107996 216356 108040 216357 107996 216357 108028 216357 108028 216358 107996 216358 107995 216358 108028 216359 107995 216359 108027 216359 108029 216360 107988 216360 108053 216360 108053 216361 107988 216361 107990 216361 108053 216362 107990 216362 108030 216362 108030 216363 107990 216363 107994 216363 108030 216364 107994 216364 108031 216364 108031 216365 107994 216365 107993 216365 108031 216366 107993 216366 108040 216366 108040 216367 107993 216367 107992 216367 108040 216368 107992 216368 107998 216368 108054 216369 108039 216369 108032 216369 108032 216370 108039 216370 108033 216370 108032 216371 108033 216371 108055 216371 108055 216372 108033 216372 108034 216372 108055 216373 108034 216373 108057 216373 108057 216374 108034 216374 108041 216374 108057 216375 108041 216375 108035 216375 108035 216376 108041 216376 108036 216376 108035 216377 108036 216377 108037 216377 108037 216378 108036 216378 108043 216378 108037 216379 108043 216379 108038 216379 108054 216380 108030 216380 108039 216380 108039 216381 108030 216381 108031 216381 108039 216382 108031 216382 108033 216382 108033 216383 108031 216383 108040 216383 108033 216384 108040 216384 108034 216384 108034 216385 108040 216385 108028 216385 108034 216386 108028 216386 108041 216386 108041 216387 108028 216387 108042 216387 108041 216388 108042 216388 108036 216388 108036 216389 108042 216389 108141 216389 108036 216390 108141 216390 108043 216390 108044 216391 108118 216391 108024 216391 108024 216392 108118 216392 108119 216392 108024 216393 108119 216393 108051 216393 108051 216394 108119 216394 108045 216394 108051 216395 108045 216395 108046 216395 108017 216396 108047 216396 108015 216396 108015 216397 108047 216397 108049 216397 108015 216398 108049 216398 108048 216398 108048 216399 108049 216399 108050 216399 108048 216400 108050 216400 108052 216400 108052 216401 108050 216401 108051 216401 108052 216402 108051 216402 108025 216402 108025 216403 108051 216403 108046 216403 108025 216404 108046 216404 108026 216404 108029 216405 108053 216405 108025 216405 108025 216406 108053 216406 108054 216406 108025 216407 108054 216407 108052 216407 108052 216408 108054 216408 108032 216408 108052 216409 108032 216409 108023 216409 108023 216410 108032 216410 108055 216410 108023 216411 108055 216411 108056 216411 108056 216412 108055 216412 108057 216412 108056 216413 108057 216413 108012 216413 108012 216414 108057 216414 108035 216414 108012 216415 108035 216415 108058 216415 108058 216416 108035 216416 108037 216416 108058 216417 108037 216417 108013 216417 108013 216418 108037 216418 108038 216418 108013 216419 108038 216419 108059 216419 108090 216420 108060 216420 108127 216420 108081 216421 108138 216421 108082 216421 108070 216422 108110 216422 108069 216422 108093 216423 108061 216423 108091 216423 108105 216424 108067 216424 108106 216424 108062 216425 108130 216425 108063 216425 108063 216426 108130 216426 108064 216426 108063 216427 108064 216427 108149 216427 108149 216428 108064 216428 108065 216428 108149 216429 108065 216429 108150 216429 108150 216430 108065 216430 108075 216430 108106 216431 108067 216431 108066 216431 108066 216432 108067 216432 108068 216432 108066 216433 108068 216433 108069 216433 108104 216434 108091 216434 108103 216434 108069 216435 108110 216435 108066 216435 108066 216436 108110 216436 108107 216436 108066 216437 108107 216437 108106 216437 108068 216438 108074 216438 108069 216438 108069 216439 108074 216439 108076 216439 108069 216440 108076 216440 108070 216440 108070 216441 108076 216441 108071 216441 108070 216442 108071 216442 108112 216442 108112 216443 108071 216443 108072 216443 108112 216444 108072 216444 108113 216444 108113 216445 108072 216445 108073 216445 108113 216446 108073 216446 108115 216446 108074 216447 108075 216447 108076 216447 108076 216448 108075 216448 108065 216448 108076 216449 108065 216449 108071 216449 108071 216450 108065 216450 108064 216450 108071 216451 108064 216451 108072 216451 108072 216452 108064 216452 108130 216452 108072 216453 108130 216453 108073 216453 107800 216454 108087 216454 107802 216454 107802 216455 108087 216455 108078 216455 107802 216456 108078 216456 108077 216456 108077 216457 108078 216457 108080 216457 108080 216458 108078 216458 108079 216458 108080 216459 108079 216459 107799 216459 108128 216460 108081 216460 108097 216460 108097 216461 108081 216461 108082 216461 108097 216462 108082 216462 108079 216462 108079 216463 108082 216463 108002 216463 108079 216464 108002 216464 107799 216464 108088 216465 108084 216465 108083 216465 108083 216466 108084 216466 108100 216466 108083 216467 108100 216467 108085 216467 108085 216468 108100 216468 108087 216468 108085 216469 108087 216469 108086 216469 108086 216470 108087 216470 107800 216470 108088 216471 107805 216471 108084 216471 108084 216472 107805 216472 108090 216472 108084 216473 108090 216473 108089 216473 108089 216474 108090 216474 108127 216474 108089 216475 108127 216475 108124 216475 108091 216476 108104 216476 108093 216476 108093 216477 108104 216477 108092 216477 108093 216478 108092 216478 108102 216478 108102 216479 108092 216479 108108 216479 108102 216480 108108 216480 108101 216480 108101 216481 108108 216481 108109 216481 108101 216482 108109 216482 108099 216482 108099 216483 108109 216483 108111 216483 108099 216484 108111 216484 108094 216484 108094 216485 108111 216485 108095 216485 108094 216486 108095 216486 108098 216486 108098 216487 108095 216487 108114 216487 108098 216488 108114 216488 108096 216488 108096 216489 108114 216489 108116 216489 108096 216490 108116 216490 108128 216490 108128 216491 108097 216491 108096 216491 108096 216492 108097 216492 108079 216492 108096 216493 108079 216493 108098 216493 108098 216494 108079 216494 108078 216494 108098 216495 108078 216495 108094 216495 108094 216496 108078 216496 108087 216496 108094 216497 108087 216497 108099 216497 108099 216498 108087 216498 108100 216498 108099 216499 108100 216499 108101 216499 108101 216500 108100 216500 108084 216500 108101 216501 108084 216501 108102 216501 108102 216502 108084 216502 108089 216502 108102 216503 108089 216503 108093 216503 108093 216504 108089 216504 108124 216504 108093 216505 108124 216505 108061 216505 108103 216506 108105 216506 108104 216506 108104 216507 108105 216507 108106 216507 108104 216508 108106 216508 108092 216508 108092 216509 108106 216509 108107 216509 108092 216510 108107 216510 108108 216510 108108 216511 108107 216511 108110 216511 108108 216512 108110 216512 108109 216512 108109 216513 108110 216513 108070 216513 108109 216514 108070 216514 108111 216514 108111 216515 108070 216515 108112 216515 108111 216516 108112 216516 108095 216516 108095 216517 108112 216517 108113 216517 108095 216518 108113 216518 108114 216518 108114 216519 108113 216519 108115 216519 108114 216520 108115 216520 108116 216520 108125 216521 108123 216521 108117 216521 108154 216522 108103 216522 108091 216522 108118 216523 108157 216523 108120 216523 108045 216524 108119 216524 108125 216524 108125 216525 108119 216525 108118 216525 108118 216526 108120 216526 108125 216526 108125 216527 108120 216527 108156 216527 108125 216528 108156 216528 108123 216528 108123 216529 108156 216529 108155 216529 108123 216530 108155 216530 108154 216530 108026 216531 108046 216531 108126 216531 108126 216532 108046 216532 108045 216532 108121 216533 108026 216533 108122 216533 108122 216534 108026 216534 108126 216534 108122 216535 108126 216535 108003 216535 108154 216536 108091 216536 108123 216536 108123 216537 108091 216537 108061 216537 108123 216538 108061 216538 108117 216538 108117 216539 108061 216539 108124 216539 108117 216540 108124 216540 108127 216540 108045 216541 108125 216541 108126 216541 108126 216542 108125 216542 108117 216542 108126 216543 108117 216543 108003 216543 108003 216544 108117 216544 108127 216544 108003 216545 108127 216545 108060 216545 108081 216546 108128 216546 108140 216546 108129 216547 108133 216547 108136 216547 108062 216548 108131 216548 108130 216548 108130 216549 108131 216549 108137 216549 108146 216550 108132 216550 108143 216550 108143 216551 108132 216551 108133 216551 108139 216552 108135 216552 108134 216552 108134 216553 108135 216553 108137 216553 108133 216554 108132 216554 108136 216554 108136 216555 108132 216555 108022 216555 108136 216556 108022 216556 108014 216556 108131 216557 108129 216557 108137 216557 108137 216558 108129 216558 108136 216558 108137 216559 108136 216559 108134 216559 108134 216560 108136 216560 108014 216560 108128 216561 108116 216561 108135 216561 108135 216562 108116 216562 108115 216562 108135 216563 108115 216563 108137 216563 108137 216564 108115 216564 108073 216564 108137 216565 108073 216565 108130 216565 108006 216566 108007 216566 108140 216566 108140 216567 108007 216567 108138 216567 108140 216568 108138 216568 108081 216568 108014 216569 108059 216569 108134 216569 108134 216570 108059 216570 108038 216570 108134 216571 108038 216571 108139 216571 108139 216572 108038 216572 108043 216572 108139 216573 108043 216573 108141 216573 108128 216574 108135 216574 108140 216574 108140 216575 108135 216575 108139 216575 108140 216576 108139 216576 108006 216576 108006 216577 108139 216577 108141 216577 108006 216578 108141 216578 108142 216578 108145 216579 108146 216579 108143 216579 108145 216580 108017 216580 108144 216580 108144 216581 108009 216581 108145 216581 108145 216582 108009 216582 108011 216582 108145 216583 108011 216583 108146 216583 108158 216584 108008 216584 108145 216584 108145 216585 108008 216585 108147 216585 108145 216586 108147 216586 108017 216586 108152 216587 108103 216587 108154 216587 108153 216588 108067 216588 108152 216588 108152 216589 108067 216589 108105 216589 108152 216590 108105 216590 108103 216590 108062 216591 108148 216591 108152 216591 108152 216592 108148 216592 108149 216592 108152 216593 108149 216593 108150 216593 108150 216594 108151 216594 108152 216594 108152 216595 108151 216595 108074 216595 108152 216596 108074 216596 108153 216596 108062 216597 108152 216597 108131 216597 108131 216598 108152 216598 108154 216598 108131 216599 108154 216599 108129 216599 108129 216600 108154 216600 108155 216600 108129 216601 108155 216601 108133 216601 108133 216602 108155 216602 108156 216602 108133 216603 108156 216603 108143 216603 108143 216604 108156 216604 108120 216604 108143 216605 108120 216605 108145 216605 108145 216606 108120 216606 108157 216606 108145 216607 108157 216607 108158 216607 108185 216608 108214 216608 108159 216608 108159 216609 108214 216609 108216 216609 108159 216610 108216 216610 108160 216610 108216 216611 108212 216611 108160 216611 108160 216612 108212 216612 108161 216612 108160 216613 108161 216613 108162 216613 108162 216614 108161 216614 108163 216614 108162 216615 108163 216615 108179 216615 108163 216616 108208 216616 108179 216616 108179 216617 108208 216617 108207 216617 108179 216618 108207 216618 107968 216618 107968 216619 108207 216619 108164 216619 108204 216620 108187 216620 108205 216620 108205 216621 108187 216621 108164 216621 108205 216622 108164 216622 108165 216622 108165 216623 108164 216623 108207 216623 108202 216624 108168 216624 108174 216624 107983 216625 108189 216625 107981 216625 107981 216626 108189 216626 108166 216626 107981 216627 108166 216627 107982 216627 107982 216628 108166 216628 108199 216628 107982 216629 108199 216629 108174 216629 108174 216630 108199 216630 108200 216630 108174 216631 108200 216631 108202 216631 108202 216632 108167 216632 108168 216632 108168 216633 108167 216633 108169 216633 108168 216634 108169 216634 108172 216634 107829 216635 108195 216635 108196 216635 108196 216636 108195 216636 108170 216636 108196 216637 108170 216637 108171 216637 108171 216638 108170 216638 108172 216638 108171 216639 108172 216639 108197 216639 108197 216640 108172 216640 108169 216640 107980 216641 107982 216641 108174 216641 108175 216642 108168 216642 107808 216642 107808 216643 108168 216643 108172 216643 107808 216644 108172 216644 108173 216644 107980 216645 108174 216645 108178 216645 108175 216646 107810 216646 108168 216646 108168 216647 107810 216647 108176 216647 108168 216648 108176 216648 108174 216648 108174 216649 108176 216649 108177 216649 108174 216650 108177 216650 108178 216650 107968 216651 107972 216651 108179 216651 108179 216652 107972 216652 108186 216652 108179 216653 108186 216653 108162 216653 108172 216654 108170 216654 108173 216654 108173 216655 108170 216655 108195 216655 108173 216656 108195 216656 108180 216656 108180 216657 108195 216657 108181 216657 108180 216658 108181 216658 107971 216658 107971 216659 108181 216659 108182 216659 107971 216660 108182 216660 108183 216660 108183 216661 108182 216661 108185 216661 108183 216662 108185 216662 108184 216662 108184 216663 108185 216663 108159 216663 108184 216664 108159 216664 107979 216664 107979 216665 108159 216665 108160 216665 107979 216666 108160 216666 107978 216666 107978 216667 108160 216667 108162 216667 107978 216668 108162 216668 107974 216668 107974 216669 108162 216669 108186 216669 108187 216670 108204 216670 108191 216670 108187 216671 108191 216671 108188 216671 108188 216672 108191 216672 108189 216672 108188 216673 108189 216673 107983 216673 107814 216674 108189 216674 108190 216674 108190 216675 108189 216675 108191 216675 108190 216676 108191 216676 108193 216676 108204 216677 107817 216677 108191 216677 108191 216678 107817 216678 108192 216678 108191 216679 108192 216679 108193 216679 107828 216680 108182 216680 108194 216680 108194 216681 108182 216681 108181 216681 108194 216682 108181 216682 107829 216682 107829 216683 108181 216683 108195 216683 108166 216684 108189 216684 107814 216684 107866 216685 107829 216685 107867 216685 107867 216686 107829 216686 108196 216686 107867 216687 108196 216687 107843 216687 107843 216688 108196 216688 107874 216688 108196 216689 108171 216689 107874 216689 107874 216690 108171 216690 108197 216690 107874 216691 108197 216691 108198 216691 108202 216692 107850 216692 108167 216692 108167 216693 107850 216693 108198 216693 108167 216694 108198 216694 108169 216694 108169 216695 108198 216695 108197 216695 107814 216696 107857 216696 108166 216696 108166 216697 107857 216697 107865 216697 108166 216698 107865 216698 108199 216698 108199 216699 107865 216699 107858 216699 108199 216700 107858 216700 108200 216700 108200 216701 107858 216701 108201 216701 108200 216702 108201 216702 108202 216702 108202 216703 108201 216703 107830 216703 108202 216704 107830 216704 107850 216704 108203 216705 107817 216705 108204 216705 108204 216706 108205 216706 108203 216706 108203 216707 108205 216707 108165 216707 108203 216708 108165 216708 108206 216708 108206 216709 108165 216709 108207 216709 108206 216710 108207 216710 108209 216710 108209 216711 108207 216711 108208 216711 108209 216712 108208 216712 108210 216712 108210 216713 108208 216713 108163 216713 108210 216714 108163 216714 107903 216714 107903 216715 108163 216715 108211 216715 108211 216716 108163 216716 108161 216716 108211 216717 108161 216717 108213 216717 108161 216718 108212 216718 108213 216718 108213 216719 108212 216719 108216 216719 108213 216720 108216 216720 107908 216720 108214 216721 107812 216721 108216 216721 108216 216722 107812 216722 108215 216722 108216 216723 108215 216723 107908 216723 108238 216724 108217 216724 108308 216724 108308 216725 108217 216725 108613 216725 108308 216726 108613 216726 108218 216726 108218 216727 108613 216727 108223 216727 108219 216728 108611 216728 108229 216728 108229 216729 108220 216729 108219 216729 108219 216730 108220 216730 108221 216730 108219 216731 108221 216731 108612 216731 108612 216732 108221 216732 108222 216732 108612 216733 108222 216733 108616 216733 108616 216734 108222 216734 108224 216734 108616 216735 108224 216735 108223 216735 108223 216736 108224 216736 108309 216736 108223 216737 108309 216737 108218 216737 108231 216738 108230 216738 108225 216738 108225 216739 108230 216739 108316 216739 108225 216740 108316 216740 108227 216740 108316 216741 108226 216741 108227 216741 108227 216742 108226 216742 108314 216742 108227 216743 108314 216743 108610 216743 108610 216744 108314 216744 108228 216744 108610 216745 108228 216745 108611 216745 108611 216746 108228 216746 108313 216746 108611 216747 108313 216747 108229 216747 108230 216748 108231 216748 108354 216748 108354 216749 108231 216749 108232 216749 108354 216750 108232 216750 108347 216750 108347 216751 108232 216751 108602 216751 108347 216752 108602 216752 108259 216752 108259 216753 108602 216753 108633 216753 108387 216754 108233 216754 108235 216754 108387 216755 108235 216755 108234 216755 108234 216756 108235 216756 108236 216756 108234 216757 108236 216757 108237 216757 108237 216758 108236 216758 108217 216758 108237 216759 108217 216759 108238 216759 108239 216760 108385 216760 108341 216760 108371 216761 108239 216761 108254 216761 108369 216762 108240 216762 108241 216762 108241 216763 108240 216763 108249 216763 108241 216764 108249 216764 108370 216764 108370 216765 108249 216765 108250 216765 108370 216766 108250 216766 108242 216766 108242 216767 108250 216767 108243 216767 108245 216768 108364 216768 108357 216768 108247 216769 108290 216769 108248 216769 108248 216770 108290 216770 108244 216770 108248 216771 108244 216771 108245 216771 108245 216772 108244 216772 108291 216772 108245 216773 108291 216773 108364 216773 108251 216774 108240 216774 108246 216774 108246 216775 108240 216775 108369 216775 108246 216776 108369 216776 108281 216776 108251 216777 108247 216777 108240 216777 108240 216778 108247 216778 108248 216778 108240 216779 108248 216779 108249 216779 108249 216780 108248 216780 108245 216780 108249 216781 108245 216781 108250 216781 108250 216782 108245 216782 108357 216782 108250 216783 108357 216783 108243 216783 108284 216784 108288 216784 108251 216784 108251 216785 108288 216785 108252 216785 108251 216786 108252 216786 108247 216786 108282 216787 108371 216787 108253 216787 108253 216788 108371 216788 108254 216788 108253 216789 108254 216789 108283 216789 108283 216790 108254 216790 108279 216790 108626 216791 108625 216791 108269 216791 108269 216792 108625 216792 108622 216792 108269 216793 108622 216793 108255 216793 108264 216794 108256 216794 108269 216794 108285 216795 108632 216795 108629 216795 108626 216796 108269 216796 108627 216796 108627 216797 108269 216797 108256 216797 108627 216798 108256 216798 108629 216798 108632 216799 108285 216799 108257 216799 108257 216800 108285 216800 108258 216800 108257 216801 108258 216801 108259 216801 108387 216802 108276 216802 108275 216802 108272 216803 108263 216803 108274 216803 108274 216804 108263 216804 108260 216804 108274 216805 108260 216805 108275 216805 108275 216806 108260 216806 108261 216806 108275 216807 108261 216807 108387 216807 108622 216808 108262 216808 108255 216808 108255 216809 108262 216809 108635 216809 108255 216810 108635 216810 108272 216810 108272 216811 108635 216811 108636 216811 108272 216812 108636 216812 108263 216812 108264 216813 108270 216813 108286 216813 108286 216814 108270 216814 108271 216814 108286 216815 108271 216815 108287 216815 108287 216816 108271 216816 108273 216816 108287 216817 108273 216817 108265 216817 108265 216818 108273 216818 108266 216818 108265 216819 108266 216819 108289 216819 108289 216820 108266 216820 108267 216820 108289 216821 108267 216821 108268 216821 108268 216822 108267 216822 108277 216822 108268 216823 108277 216823 108366 216823 108264 216824 108269 216824 108270 216824 108270 216825 108269 216825 108255 216825 108270 216826 108255 216826 108271 216826 108271 216827 108255 216827 108272 216827 108271 216828 108272 216828 108273 216828 108273 216829 108272 216829 108274 216829 108273 216830 108274 216830 108266 216830 108266 216831 108274 216831 108275 216831 108266 216832 108275 216832 108267 216832 108267 216833 108275 216833 108276 216833 108267 216834 108276 216834 108277 216834 108239 216835 108341 216835 108254 216835 108254 216836 108341 216836 108278 216836 108254 216837 108278 216837 108279 216837 108279 216838 108278 216838 108280 216838 108279 216839 108280 216839 108346 216839 108281 216840 108282 216840 108246 216840 108246 216841 108282 216841 108253 216841 108246 216842 108253 216842 108251 216842 108251 216843 108253 216843 108283 216843 108251 216844 108283 216844 108284 216844 108284 216845 108283 216845 108279 216845 108284 216846 108279 216846 108285 216846 108285 216847 108279 216847 108346 216847 108285 216848 108346 216848 108258 216848 108629 216849 108256 216849 108285 216849 108285 216850 108256 216850 108264 216850 108285 216851 108264 216851 108284 216851 108284 216852 108264 216852 108286 216852 108284 216853 108286 216853 108288 216853 108288 216854 108286 216854 108287 216854 108288 216855 108287 216855 108252 216855 108252 216856 108287 216856 108265 216856 108252 216857 108265 216857 108247 216857 108247 216858 108265 216858 108289 216858 108247 216859 108289 216859 108290 216859 108290 216860 108289 216860 108268 216860 108290 216861 108268 216861 108244 216861 108244 216862 108268 216862 108366 216862 108244 216863 108366 216863 108291 216863 108316 216864 108230 216864 108353 216864 108338 216865 108300 216865 108299 216865 108292 216866 108350 216866 108318 216866 108333 216867 108298 216867 108335 216867 108379 216868 108306 216868 108293 216868 108293 216869 108306 216869 108305 216869 108293 216870 108305 216870 108294 216870 108294 216871 108305 216871 108304 216871 108294 216872 108304 216872 108295 216872 108295 216873 108304 216873 108296 216873 108335 216874 108298 216874 108297 216874 108297 216875 108298 216875 108301 216875 108297 216876 108301 216876 108299 216876 108334 216877 108318 216877 108373 216877 108299 216878 108300 216878 108297 216878 108297 216879 108300 216879 108337 216879 108297 216880 108337 216880 108335 216880 108301 216881 108377 216881 108299 216881 108299 216882 108377 216882 108303 216882 108299 216883 108303 216883 108338 216883 108338 216884 108303 216884 108302 216884 108338 216885 108302 216885 108339 216885 108339 216886 108302 216886 108307 216886 108339 216887 108307 216887 108340 216887 108340 216888 108307 216888 108362 216888 108340 216889 108362 216889 108361 216889 108377 216890 108296 216890 108303 216890 108303 216891 108296 216891 108304 216891 108303 216892 108304 216892 108302 216892 108302 216893 108304 216893 108305 216893 108302 216894 108305 216894 108307 216894 108307 216895 108305 216895 108306 216895 108307 216896 108306 216896 108362 216896 108308 216897 108218 216897 108312 216897 108312 216898 108218 216898 108309 216898 108312 216899 108309 216899 108310 216899 108310 216900 108309 216900 108224 216900 108310 216901 108224 216901 108329 216901 108329 216902 108224 216902 108222 216902 108329 216903 108222 216903 108330 216903 108311 216904 108355 216904 108312 216904 108312 216905 108355 216905 108238 216905 108312 216906 108238 216906 108308 216906 108315 216907 108313 216907 108332 216907 108332 216908 108313 216908 108228 216908 108332 216909 108228 216909 108314 216909 108222 216910 108221 216910 108330 216910 108330 216911 108221 216911 108220 216911 108330 216912 108220 216912 108315 216912 108315 216913 108220 216913 108229 216913 108315 216914 108229 216914 108313 216914 108314 216915 108226 216915 108332 216915 108332 216916 108226 216916 108316 216916 108332 216917 108316 216917 108317 216917 108317 216918 108316 216918 108353 216918 108317 216919 108353 216919 108352 216919 108318 216920 108334 216920 108292 216920 108292 216921 108334 216921 108319 216921 108292 216922 108319 216922 108320 216922 108320 216923 108319 216923 108336 216923 108320 216924 108336 216924 108322 216924 108322 216925 108336 216925 108321 216925 108322 216926 108321 216926 108331 216926 108331 216927 108321 216927 108323 216927 108331 216928 108323 216928 108324 216928 108324 216929 108323 216929 108326 216929 108324 216930 108326 216930 108325 216930 108325 216931 108326 216931 108327 216931 108325 216932 108327 216932 108328 216932 108328 216933 108327 216933 108360 216933 108328 216934 108360 216934 108311 216934 108311 216935 108312 216935 108328 216935 108328 216936 108312 216936 108310 216936 108328 216937 108310 216937 108325 216937 108325 216938 108310 216938 108329 216938 108325 216939 108329 216939 108324 216939 108324 216940 108329 216940 108330 216940 108324 216941 108330 216941 108331 216941 108331 216942 108330 216942 108315 216942 108331 216943 108315 216943 108322 216943 108322 216944 108315 216944 108332 216944 108322 216945 108332 216945 108320 216945 108320 216946 108332 216946 108317 216946 108320 216947 108317 216947 108292 216947 108292 216948 108317 216948 108352 216948 108292 216949 108352 216949 108350 216949 108373 216950 108333 216950 108334 216950 108334 216951 108333 216951 108335 216951 108334 216952 108335 216952 108319 216952 108319 216953 108335 216953 108337 216953 108319 216954 108337 216954 108336 216954 108336 216955 108337 216955 108300 216955 108336 216956 108300 216956 108321 216956 108321 216957 108300 216957 108338 216957 108321 216958 108338 216958 108323 216958 108323 216959 108338 216959 108339 216959 108323 216960 108339 216960 108326 216960 108326 216961 108339 216961 108340 216961 108326 216962 108340 216962 108327 216962 108327 216963 108340 216963 108361 216963 108327 216964 108361 216964 108360 216964 108343 216965 108349 216965 108351 216965 108348 216966 108373 216966 108318 216966 108341 216967 108385 216967 108342 216967 108280 216968 108278 216968 108343 216968 108343 216969 108278 216969 108341 216969 108341 216970 108342 216970 108343 216970 108343 216971 108342 216971 108383 216971 108343 216972 108383 216972 108349 216972 108349 216973 108383 216973 108344 216973 108349 216974 108344 216974 108348 216974 108258 216975 108346 216975 108345 216975 108345 216976 108346 216976 108280 216976 108259 216977 108258 216977 108347 216977 108347 216978 108258 216978 108345 216978 108347 216979 108345 216979 108354 216979 108348 216980 108318 216980 108349 216980 108349 216981 108318 216981 108350 216981 108349 216982 108350 216982 108351 216982 108351 216983 108350 216983 108352 216983 108351 216984 108352 216984 108353 216984 108280 216985 108343 216985 108345 216985 108345 216986 108343 216986 108351 216986 108345 216987 108351 216987 108354 216987 108354 216988 108351 216988 108353 216988 108354 216989 108353 216989 108230 216989 108355 216990 108311 216990 108363 216990 108381 216991 108382 216991 108358 216991 108379 216992 108380 216992 108306 216992 108306 216993 108380 216993 108359 216993 108242 216994 108243 216994 108384 216994 108384 216995 108243 216995 108382 216995 108367 216996 108356 216996 108365 216996 108365 216997 108356 216997 108359 216997 108382 216998 108243 216998 108358 216998 108358 216999 108243 216999 108357 216999 108358 217000 108357 217000 108364 217000 108380 217001 108381 217001 108359 217001 108359 217002 108381 217002 108358 217002 108359 217003 108358 217003 108365 217003 108365 217004 108358 217004 108364 217004 108311 217005 108360 217005 108356 217005 108356 217006 108360 217006 108361 217006 108356 217007 108361 217007 108359 217007 108359 217008 108361 217008 108362 217008 108359 217009 108362 217009 108306 217009 108234 217010 108237 217010 108363 217010 108363 217011 108237 217011 108238 217011 108363 217012 108238 217012 108355 217012 108364 217013 108291 217013 108365 217013 108365 217014 108291 217014 108366 217014 108365 217015 108366 217015 108367 217015 108367 217016 108366 217016 108277 217016 108367 217017 108277 217017 108276 217017 108311 217018 108356 217018 108363 217018 108363 217019 108356 217019 108367 217019 108363 217020 108367 217020 108234 217020 108234 217021 108367 217021 108276 217021 108234 217022 108276 217022 108387 217022 108368 217023 108242 217023 108384 217023 108368 217024 108281 217024 108369 217024 108369 217025 108241 217025 108368 217025 108368 217026 108241 217026 108370 217026 108368 217027 108370 217027 108242 217027 108386 217028 108371 217028 108368 217028 108368 217029 108371 217029 108372 217029 108368 217030 108372 217030 108281 217030 108375 217031 108373 217031 108348 217031 108378 217032 108298 217032 108375 217032 108375 217033 108298 217033 108333 217033 108375 217034 108333 217034 108373 217034 108379 217035 108374 217035 108375 217035 108375 217036 108374 217036 108294 217036 108375 217037 108294 217037 108295 217037 108295 217038 108376 217038 108375 217038 108375 217039 108376 217039 108377 217039 108375 217040 108377 217040 108378 217040 108379 217041 108375 217041 108380 217041 108380 217042 108375 217042 108348 217042 108380 217043 108348 217043 108381 217043 108381 217044 108348 217044 108344 217044 108381 217045 108344 217045 108382 217045 108382 217046 108344 217046 108383 217046 108382 217047 108383 217047 108384 217047 108384 217048 108383 217048 108342 217048 108384 217049 108342 217049 108368 217049 108368 217050 108342 217050 108385 217050 108368 217051 108385 217051 108386 217051 108261 217052 108260 217052 108637 217052 108637 217053 108389 217053 108261 217053 108261 217054 108389 217054 108233 217054 108261 217055 108233 217055 108387 217055 108637 217056 108388 217056 108389 217056 108389 217057 108388 217057 108420 217057 108389 217058 108420 217058 108233 217058 108233 217059 108420 217059 108419 217059 108489 217060 108488 217060 108390 217060 108390 217061 108488 217061 108391 217061 108390 217062 108391 217062 108408 217062 108408 217063 108391 217063 108487 217063 108408 217064 108487 217064 108392 217064 108392 217065 108487 217065 108393 217065 108392 217066 108393 217066 108394 217066 108394 217067 108393 217067 108395 217067 108394 217068 108395 217068 108417 217068 108417 217069 108395 217069 108435 217069 108489 217070 108390 217070 108490 217070 108490 217071 108390 217071 108396 217071 108490 217072 108396 217072 108397 217072 108397 217073 108396 217073 108398 217073 108397 217074 108398 217074 108399 217074 108399 217075 108398 217075 108400 217075 108399 217076 108400 217076 108486 217076 108486 217077 108400 217077 108401 217077 108486 217078 108401 217078 108450 217078 108620 217079 108401 217079 108402 217079 108402 217080 108401 217080 108400 217080 108402 217081 108400 217081 108403 217081 108403 217082 108400 217082 108398 217082 108403 217083 108398 217083 108423 217083 108423 217084 108398 217084 108396 217084 108423 217085 108396 217085 108404 217085 108404 217086 108396 217086 108390 217086 108404 217087 108390 217087 108405 217087 108417 217088 108406 217088 108394 217088 108394 217089 108406 217089 108407 217089 108394 217090 108407 217090 108392 217090 108392 217091 108407 217091 108405 217091 108392 217092 108405 217092 108408 217092 108408 217093 108405 217093 108390 217093 108426 217094 108425 217094 108442 217094 108409 217095 108418 217095 108410 217095 108442 217096 108444 217096 108426 217096 108426 217097 108444 217097 108446 217097 108426 217098 108446 217098 108410 217098 108410 217099 108446 217099 108411 217099 108410 217100 108411 217100 108409 217100 108428 217101 108621 217101 108412 217101 108412 217102 108621 217102 108413 217102 108412 217103 108413 217103 108414 217103 108414 217104 108413 217104 108599 217104 108414 217105 108599 217105 108439 217105 108439 217106 108599 217106 108415 217106 108439 217107 108415 217107 108436 217107 108436 217108 108415 217108 108418 217108 108436 217109 108418 217109 108416 217109 108416 217110 108418 217110 108409 217110 108465 217111 108433 217111 108417 217111 108417 217112 108433 217112 108406 217112 108405 217113 108407 217113 108609 217113 108609 217114 108407 217114 108424 217114 108605 217115 108418 217115 108415 217115 108415 217116 108599 217116 108419 217116 108614 217117 108403 217117 108423 217117 108605 217118 108415 217118 108388 217118 108388 217119 108415 217119 108419 217119 108388 217120 108419 217120 108420 217120 108609 217121 108421 217121 108405 217121 108405 217122 108421 217122 108422 217122 108405 217123 108422 217123 108404 217123 108404 217124 108422 217124 108617 217124 108404 217125 108617 217125 108423 217125 108423 217126 108617 217126 108615 217126 108423 217127 108615 217127 108614 217127 108407 217128 108406 217128 108424 217128 108424 217129 108406 217129 108433 217129 108424 217130 108433 217130 108600 217130 108600 217131 108433 217131 108432 217131 108600 217132 108432 217132 108601 217132 108601 217133 108432 217133 108425 217133 108601 217134 108425 217134 108603 217134 108603 217135 108425 217135 108426 217135 108603 217136 108426 217136 108607 217136 108607 217137 108426 217137 108410 217137 108607 217138 108410 217138 108608 217138 108608 217139 108410 217139 108418 217139 108608 217140 108418 217140 108427 217140 108427 217141 108418 217141 108605 217141 108621 217142 108428 217142 108429 217142 108621 217143 108429 217143 108430 217143 108430 217144 108429 217144 108401 217144 108430 217145 108401 217145 108620 217145 108450 217146 108401 217146 108451 217146 108451 217147 108401 217147 108429 217147 108451 217148 108429 217148 108453 217148 108428 217149 108456 217149 108429 217149 108429 217150 108456 217150 108454 217150 108429 217151 108454 217151 108453 217151 108442 217152 108425 217152 108431 217152 108431 217153 108425 217153 108432 217153 108431 217154 108432 217154 108465 217154 108465 217155 108432 217155 108433 217155 108434 217156 108465 217156 108503 217156 108503 217157 108465 217157 108417 217157 108503 217158 108417 217158 108435 217158 108456 217159 108428 217159 108536 217159 108536 217160 108428 217160 108412 217160 108536 217161 108412 217161 108537 217161 108537 217162 108412 217162 108414 217162 108409 217163 108540 217163 108416 217163 108416 217164 108540 217164 108437 217164 108416 217165 108437 217165 108436 217165 108436 217166 108437 217166 108438 217166 108436 217167 108438 217167 108439 217167 108439 217168 108438 217168 108440 217168 108439 217169 108440 217169 108414 217169 108414 217170 108440 217170 108441 217170 108414 217171 108441 217171 108537 217171 108442 217172 108443 217172 108444 217172 108444 217173 108443 217173 108518 217173 108444 217174 108518 217174 108446 217174 108518 217175 108445 217175 108446 217175 108446 217176 108445 217176 108447 217176 108446 217177 108447 217177 108411 217177 108411 217178 108447 217178 108448 217178 108411 217179 108448 217179 108409 217179 108409 217180 108448 217180 108542 217180 108409 217181 108542 217181 108540 217181 108461 217182 108535 217182 108522 217182 108535 217183 108461 217183 108532 217183 108452 217184 108455 217184 108449 217184 108501 217185 108450 217185 108451 217185 108517 217186 108502 217186 108452 217186 108452 217187 108502 217187 108501 217187 108501 217188 108451 217188 108452 217188 108452 217189 108451 217189 108453 217189 108452 217190 108453 217190 108455 217190 108455 217191 108453 217191 108454 217191 108455 217192 108454 217192 108456 217192 108471 217193 108457 217193 108460 217193 108460 217194 108457 217194 108517 217194 108456 217195 108458 217195 108455 217195 108455 217196 108458 217196 108459 217196 108455 217197 108459 217197 108449 217197 108449 217198 108459 217198 108551 217198 108449 217199 108551 217199 108569 217199 108462 217200 108471 217200 108463 217200 108463 217201 108471 217201 108460 217201 108463 217202 108460 217202 108461 217202 108517 217203 108452 217203 108460 217203 108460 217204 108452 217204 108449 217204 108460 217205 108449 217205 108461 217205 108461 217206 108449 217206 108569 217206 108461 217207 108569 217207 108532 217207 108571 217208 108462 217208 108582 217208 108582 217209 108462 217209 108463 217209 108582 217210 108463 217210 108581 217210 108581 217211 108463 217211 108461 217211 108581 217212 108461 217212 108578 217212 108578 217213 108461 217213 108522 217213 108443 217214 108442 217214 108596 217214 108596 217215 108442 217215 108431 217215 108596 217216 108431 217216 108464 217216 108464 217217 108431 217217 108598 217217 108598 217218 108431 217218 108465 217218 108598 217219 108465 217219 108434 217219 108478 217220 108474 217220 108479 217220 108466 217221 108573 217221 108467 217221 108466 217222 108467 217222 108468 217222 108475 217223 108570 217223 108474 217223 108474 217224 108570 217224 108572 217224 108474 217225 108572 217225 108479 217225 108479 217226 108572 217226 108469 217226 108479 217227 108469 217227 108470 217227 108462 217228 108476 217228 108471 217228 108471 217229 108476 217229 108472 217229 108471 217230 108472 217230 108457 217230 108457 217231 108472 217231 108473 217231 108515 217232 108473 217232 108478 217232 108478 217233 108473 217233 108472 217233 108478 217234 108472 217234 108474 217234 108474 217235 108472 217235 108476 217235 108474 217236 108476 217236 108475 217236 108475 217237 108476 217237 108462 217237 108475 217238 108462 217238 108571 217238 108507 217239 108467 217239 108477 217239 108477 217240 108467 217240 108573 217240 108477 217241 108573 217241 108508 217241 108515 217242 108478 217242 108513 217242 108513 217243 108478 217243 108479 217243 108513 217244 108479 217244 108512 217244 108512 217245 108479 217245 108470 217245 108512 217246 108470 217246 108480 217246 108480 217247 108470 217247 108481 217247 108480 217248 108481 217248 108484 217248 108482 217249 108393 217249 108487 217249 108482 217250 108487 217250 108495 217250 108395 217251 108393 217251 108509 217251 108509 217252 108393 217252 108482 217252 108509 217253 108482 217253 108510 217253 108503 217254 108435 217254 108504 217254 108504 217255 108435 217255 108395 217255 108469 217256 108483 217256 108470 217256 108470 217257 108483 217257 108468 217257 108470 217258 108468 217258 108481 217258 108481 217259 108468 217259 108467 217259 108481 217260 108467 217260 108484 217260 108484 217261 108467 217261 108507 217261 108484 217262 108507 217262 108504 217262 108450 217263 108501 217263 108485 217263 108450 217264 108485 217264 108486 217264 108486 217265 108485 217265 108499 217265 108486 217266 108499 217266 108399 217266 108399 217267 108499 217267 108397 217267 108397 217268 108499 217268 108496 217268 108397 217269 108496 217269 108490 217269 108487 217270 108391 217270 108495 217270 108495 217271 108391 217271 108488 217271 108495 217272 108488 217272 108496 217272 108496 217273 108488 217273 108489 217273 108496 217274 108489 217274 108490 217274 108510 217275 108494 217275 108511 217275 108511 217276 108494 217276 108491 217276 108511 217277 108491 217277 108492 217277 108492 217278 108491 217278 108497 217278 108492 217279 108497 217279 108493 217279 108493 217280 108497 217280 108498 217280 108493 217281 108498 217281 108514 217281 108514 217282 108498 217282 108500 217282 108514 217283 108500 217283 108516 217283 108516 217284 108500 217284 108502 217284 108516 217285 108502 217285 108517 217285 108510 217286 108482 217286 108494 217286 108494 217287 108482 217287 108495 217287 108494 217288 108495 217288 108491 217288 108491 217289 108495 217289 108496 217289 108491 217290 108496 217290 108497 217290 108497 217291 108496 217291 108499 217291 108497 217292 108499 217292 108498 217292 108498 217293 108499 217293 108485 217293 108498 217294 108485 217294 108500 217294 108500 217295 108485 217295 108501 217295 108500 217296 108501 217296 108502 217296 108434 217297 108503 217297 108597 217297 108597 217298 108503 217298 108504 217298 108597 217299 108504 217299 108505 217299 108505 217300 108504 217300 108507 217300 108505 217301 108507 217301 108506 217301 108506 217302 108507 217302 108477 217302 108506 217303 108477 217303 108586 217303 108586 217304 108477 217304 108508 217304 108586 217305 108508 217305 108587 217305 108395 217306 108509 217306 108504 217306 108504 217307 108509 217307 108510 217307 108504 217308 108510 217308 108484 217308 108484 217309 108510 217309 108511 217309 108484 217310 108511 217310 108480 217310 108480 217311 108511 217311 108492 217311 108480 217312 108492 217312 108512 217312 108512 217313 108492 217313 108493 217313 108512 217314 108493 217314 108513 217314 108513 217315 108493 217315 108514 217315 108513 217316 108514 217316 108515 217316 108515 217317 108514 217317 108516 217317 108515 217318 108516 217318 108473 217318 108473 217319 108516 217319 108517 217319 108473 217320 108517 217320 108457 217320 108518 217321 108443 217321 108543 217321 108566 217322 108526 217322 108525 217322 108557 217323 108590 217323 108589 217323 108533 217324 108519 217324 108534 217324 108534 217325 108519 217325 108520 217325 108534 217326 108520 217326 108521 217326 108521 217327 108520 217327 108522 217327 108521 217328 108522 217328 108535 217328 108561 217329 108589 217329 108559 217329 108560 217330 108523 217330 108563 217330 108563 217331 108523 217331 108576 217331 108563 217332 108576 217332 108524 217332 108524 217333 108576 217333 108574 217333 108524 217334 108574 217334 108525 217334 108525 217335 108526 217335 108524 217335 108524 217336 108526 217336 108564 217336 108524 217337 108564 217337 108563 217337 108574 217338 108527 217338 108525 217338 108525 217339 108527 217339 108528 217339 108525 217340 108528 217340 108566 217340 108566 217341 108528 217341 108529 217341 108566 217342 108529 217342 108568 217342 108568 217343 108529 217343 108530 217343 108568 217344 108530 217344 108531 217344 108531 217345 108530 217345 108532 217345 108531 217346 108532 217346 108569 217346 108527 217347 108533 217347 108528 217347 108528 217348 108533 217348 108534 217348 108528 217349 108534 217349 108529 217349 108529 217350 108534 217350 108521 217350 108529 217351 108521 217351 108530 217351 108530 217352 108521 217352 108535 217352 108530 217353 108535 217353 108532 217353 108536 217354 108537 217354 108539 217354 108539 217355 108537 217355 108441 217355 108539 217356 108441 217356 108538 217356 108538 217357 108441 217357 108440 217357 108538 217358 108440 217358 108552 217358 108552 217359 108440 217359 108438 217359 108552 217360 108438 217360 108554 217360 108459 217361 108458 217361 108539 217361 108539 217362 108458 217362 108456 217362 108539 217363 108456 217363 108536 217363 108438 217364 108437 217364 108554 217364 108554 217365 108437 217365 108540 217365 108554 217366 108540 217366 108541 217366 108541 217367 108540 217367 108542 217367 108541 217368 108542 217368 108556 217368 108556 217369 108542 217369 108448 217369 108556 217370 108448 217370 108447 217370 108447 217371 108445 217371 108556 217371 108556 217372 108445 217372 108518 217372 108556 217373 108518 217373 108558 217373 108558 217374 108518 217374 108543 217374 108558 217375 108543 217375 108584 217375 108589 217376 108561 217376 108557 217376 108557 217377 108561 217377 108562 217377 108557 217378 108562 217378 108555 217378 108555 217379 108562 217379 108544 217379 108555 217380 108544 217380 108545 217380 108545 217381 108544 217381 108565 217381 108545 217382 108565 217382 108546 217382 108546 217383 108565 217383 108567 217383 108546 217384 108567 217384 108553 217384 108553 217385 108567 217385 108548 217385 108553 217386 108548 217386 108547 217386 108547 217387 108548 217387 108550 217387 108547 217388 108550 217388 108549 217388 108549 217389 108550 217389 108551 217389 108549 217390 108551 217390 108459 217390 108459 217391 108539 217391 108549 217391 108549 217392 108539 217392 108538 217392 108549 217393 108538 217393 108547 217393 108547 217394 108538 217394 108552 217394 108547 217395 108552 217395 108553 217395 108553 217396 108552 217396 108554 217396 108553 217397 108554 217397 108546 217397 108546 217398 108554 217398 108541 217398 108546 217399 108541 217399 108545 217399 108545 217400 108541 217400 108556 217400 108545 217401 108556 217401 108555 217401 108555 217402 108556 217402 108558 217402 108555 217403 108558 217403 108557 217403 108557 217404 108558 217404 108584 217404 108557 217405 108584 217405 108590 217405 108559 217406 108560 217406 108561 217406 108561 217407 108560 217407 108563 217407 108561 217408 108563 217408 108562 217408 108562 217409 108563 217409 108564 217409 108562 217410 108564 217410 108544 217410 108544 217411 108564 217411 108526 217411 108544 217412 108526 217412 108565 217412 108565 217413 108526 217413 108566 217413 108565 217414 108566 217414 108567 217414 108567 217415 108566 217415 108568 217415 108567 217416 108568 217416 108548 217416 108548 217417 108568 217417 108531 217417 108548 217418 108531 217418 108550 217418 108550 217419 108531 217419 108569 217419 108550 217420 108569 217420 108551 217420 108575 217421 108559 217421 108579 217421 108583 217422 108571 217422 108582 217422 108475 217423 108571 217423 108570 217423 108570 217424 108571 217424 108583 217424 108570 217425 108583 217425 108572 217425 108572 217426 108583 217426 108469 217426 108508 217427 108573 217427 108583 217427 108583 217428 108573 217428 108466 217428 108466 217429 108468 217429 108583 217429 108583 217430 108468 217430 108483 217430 108583 217431 108483 217431 108469 217431 108533 217432 108527 217432 108575 217432 108575 217433 108527 217433 108574 217433 108560 217434 108559 217434 108523 217434 108523 217435 108559 217435 108575 217435 108523 217436 108575 217436 108576 217436 108576 217437 108575 217437 108574 217437 108522 217438 108520 217438 108575 217438 108575 217439 108520 217439 108577 217439 108575 217440 108577 217440 108533 217440 108522 217441 108575 217441 108578 217441 108578 217442 108575 217442 108579 217442 108578 217443 108579 217443 108581 217443 108581 217444 108579 217444 108580 217444 108581 217445 108580 217445 108582 217445 108582 217446 108580 217446 108588 217446 108582 217447 108588 217447 108583 217447 108583 217448 108588 217448 108587 217448 108583 217449 108587 217449 108508 217449 108543 217450 108443 217450 108596 217450 108590 217451 108584 217451 108585 217451 108597 217452 108505 217452 108595 217452 108506 217453 108586 217453 108594 217453 108586 217454 108587 217454 108594 217454 108594 217455 108587 217455 108588 217455 108594 217456 108588 217456 108592 217456 108592 217457 108588 217457 108580 217457 108592 217458 108580 217458 108591 217458 108591 217459 108580 217459 108579 217459 108591 217460 108579 217460 108589 217460 108589 217461 108579 217461 108559 217461 108589 217462 108590 217462 108591 217462 108591 217463 108590 217463 108585 217463 108591 217464 108585 217464 108592 217464 108592 217465 108585 217465 108593 217465 108592 217466 108593 217466 108594 217466 108594 217467 108593 217467 108595 217467 108594 217468 108595 217468 108506 217468 108506 217469 108595 217469 108505 217469 108584 217470 108543 217470 108585 217470 108585 217471 108543 217471 108596 217471 108585 217472 108596 217472 108593 217472 108593 217473 108596 217473 108464 217473 108593 217474 108464 217474 108595 217474 108595 217475 108464 217475 108598 217475 108595 217476 108598 217476 108597 217476 108597 217477 108598 217477 108434 217477 108403 217478 108614 217478 108217 217478 108403 217479 108217 217479 108619 217479 108217 217480 108236 217480 108619 217480 108619 217481 108236 217481 108235 217481 108619 217482 108235 217482 108618 217482 108618 217483 108235 217483 108599 217483 108599 217484 108235 217484 108233 217484 108599 217485 108233 217485 108419 217485 108231 217486 108424 217486 108232 217486 108232 217487 108424 217487 108600 217487 108232 217488 108600 217488 108602 217488 108602 217489 108600 217489 108601 217489 108602 217490 108601 217490 108633 217490 108633 217491 108601 217491 108603 217491 108605 217492 108388 217492 108637 217492 108637 217493 108604 217493 108605 217493 108605 217494 108604 217494 108606 217494 108605 217495 108606 217495 108427 217495 108427 217496 108606 217496 108634 217496 108634 217497 108623 217497 108427 217497 108427 217498 108623 217498 108624 217498 108427 217499 108624 217499 108608 217499 108633 217500 108603 217500 108631 217500 108631 217501 108603 217501 108607 217501 108631 217502 108607 217502 108630 217502 108630 217503 108607 217503 108608 217503 108630 217504 108608 217504 108628 217504 108628 217505 108608 217505 108624 217505 108609 217506 108424 217506 108231 217506 108611 217507 108422 217507 108421 217507 108231 217508 108225 217508 108609 217508 108609 217509 108225 217509 108227 217509 108609 217510 108227 217510 108421 217510 108421 217511 108227 217511 108610 217511 108421 217512 108610 217512 108611 217512 108611 217513 108219 217513 108422 217513 108422 217514 108219 217514 108612 217514 108422 217515 108612 217515 108617 217515 108217 217516 108614 217516 108613 217516 108613 217517 108614 217517 108615 217517 108613 217518 108615 217518 108223 217518 108223 217519 108615 217519 108617 217519 108223 217520 108617 217520 108616 217520 108616 217521 108617 217521 108612 217521 108618 217522 108599 217522 108413 217522 108402 217523 108403 217523 108620 217523 108620 217524 108403 217524 108619 217524 108620 217525 108619 217525 108430 217525 108430 217526 108619 217526 108618 217526 108430 217527 108618 217527 108621 217527 108621 217528 108618 217528 108413 217528 108262 217529 108622 217529 108634 217529 108634 217530 108622 217530 108623 217530 108623 217531 108622 217531 108625 217531 108623 217532 108625 217532 108624 217532 108624 217533 108625 217533 108626 217533 108624 217534 108626 217534 108628 217534 108628 217535 108626 217535 108627 217535 108628 217536 108627 217536 108630 217536 108630 217537 108627 217537 108629 217537 108630 217538 108629 217538 108631 217538 108631 217539 108629 217539 108632 217539 108631 217540 108632 217540 108633 217540 108633 217541 108632 217541 108257 217541 108633 217542 108257 217542 108259 217542 108262 217543 108634 217543 108635 217543 108635 217544 108634 217544 108606 217544 108635 217545 108606 217545 108636 217545 108636 217546 108606 217546 108604 217546 108636 217547 108604 217547 108263 217547 108263 217548 108604 217548 108637 217548 108263 217549 108637 217549 108260 217549 108645 217550 108647 217550 108661 217550 108640 217551 108638 217551 108650 217551 108639 217552 108638 217552 108953 217552 108953 217553 108638 217553 108640 217553 108953 217554 108640 217554 108954 217554 108954 217555 108640 217555 108956 217555 108987 217556 108641 217556 108640 217556 108640 217557 108641 217557 108952 217557 108952 217558 108642 217558 108640 217558 108640 217559 108642 217559 108643 217559 108640 217560 108643 217560 108956 217560 108644 217561 109015 217561 108645 217561 108645 217562 109015 217562 109006 217562 108646 217563 108647 217563 109004 217563 109004 217564 108647 217564 108645 217564 109004 217565 108645 217565 109005 217565 109005 217566 108645 217566 109006 217566 108943 217567 109002 217567 108645 217567 108645 217568 109002 217568 109000 217568 108645 217569 109000 217569 108644 217569 108943 217570 108645 217570 108648 217570 108648 217571 108645 217571 108661 217571 108648 217572 108661 217572 108649 217572 108649 217573 108661 217573 108659 217573 108649 217574 108659 217574 108650 217574 108650 217575 108659 217575 108658 217575 108650 217576 108658 217576 108640 217576 108640 217577 108658 217577 108656 217577 108640 217578 108656 217578 108987 217578 108651 217579 108944 217579 108652 217579 108653 217580 109031 217580 108663 217580 108654 217581 108991 217581 108665 217581 108667 217582 108655 217582 108666 217582 108655 217583 108656 217583 108666 217583 108666 217584 108656 217584 108658 217584 108666 217585 108658 217585 108657 217585 108657 217586 108658 217586 108659 217586 108657 217587 108659 217587 108660 217587 108660 217588 108659 217588 108661 217588 108660 217589 108661 217589 108662 217589 108662 217590 108661 217590 108647 217590 108662 217591 108653 217591 108660 217591 108660 217592 108653 217592 108663 217592 108660 217593 108663 217593 108657 217593 108657 217594 108663 217594 108664 217594 108657 217595 108664 217595 108666 217595 108666 217596 108664 217596 108665 217596 108666 217597 108665 217597 108667 217597 108667 217598 108665 217598 108991 217598 109031 217599 108651 217599 108663 217599 108663 217600 108651 217600 108652 217600 108663 217601 108652 217601 108664 217601 108664 217602 108652 217602 108946 217602 108664 217603 108946 217603 108665 217603 108665 217604 108946 217604 108668 217604 108665 217605 108668 217605 108654 217605 108654 217606 108668 217606 108947 217606 108879 217607 108896 217607 108718 217607 108879 217608 108718 217608 108670 217608 108718 217609 108669 217609 108670 217609 108670 217610 108669 217610 108715 217610 108670 217611 108715 217611 108689 217611 108689 217612 108715 217612 108886 217612 108886 217613 108715 217613 108867 217613 108886 217614 108867 217614 108894 217614 108680 217615 108671 217615 108711 217615 108711 217616 108671 217616 108905 217616 108711 217617 108905 217617 108713 217617 108713 217618 108905 217618 108906 217618 108713 217619 108906 217619 108672 217619 108672 217620 108906 217620 108673 217620 108674 217621 108870 217621 108675 217621 108675 217622 108676 217622 108674 217622 108674 217623 108676 217623 108677 217623 108674 217624 108677 217624 108910 217624 108910 217625 108677 217625 108678 217625 108672 217626 108673 217626 108679 217626 108679 217627 108673 217627 108909 217627 108679 217628 108909 217628 108692 217628 108692 217629 108909 217629 108910 217629 108692 217630 108910 217630 108691 217630 108691 217631 108910 217631 108678 217631 108671 217632 108680 217632 108899 217632 108899 217633 108680 217633 108705 217633 108899 217634 108705 217634 108900 217634 108705 217635 108707 217635 108900 217635 108900 217636 108707 217636 108682 217636 108900 217637 108682 217637 108681 217637 108681 217638 108682 217638 108704 217638 108681 217639 108704 217639 108902 217639 108902 217640 108704 217640 108683 217640 108902 217641 108683 217641 108903 217641 108718 217642 108896 217642 108696 217642 108696 217643 108896 217643 108684 217643 108696 217644 108684 217644 108685 217644 108685 217645 108684 217645 108903 217645 108685 217646 108903 217646 108699 217646 108699 217647 108903 217647 108683 217647 108689 217648 108886 217648 108686 217648 108877 217649 108879 217649 108687 217649 108687 217650 108879 217650 108670 217650 108687 217651 108670 217651 108688 217651 108688 217652 108670 217652 108689 217652 108688 217653 108689 217653 108911 217653 108911 217654 108689 217654 108686 217654 108736 217655 108672 217655 108769 217655 108769 217656 108672 217656 108679 217656 108769 217657 108679 217657 108692 217657 108694 217658 108690 217658 108691 217658 108691 217659 108690 217659 108734 217659 108691 217660 108734 217660 108692 217660 108692 217661 108734 217661 108693 217661 108692 217662 108693 217662 108769 217662 108691 217663 108678 217663 108694 217663 108694 217664 108678 217664 108677 217664 108694 217665 108677 217665 108741 217665 108741 217666 108677 217666 108676 217666 108741 217667 108676 217667 108695 217667 108695 217668 108676 217668 108675 217668 108695 217669 108675 217669 108743 217669 108800 217670 108718 217670 108697 217670 108697 217671 108718 217671 108696 217671 108697 217672 108696 217672 108698 217672 108698 217673 108696 217673 108685 217673 108698 217674 108685 217674 108796 217674 108796 217675 108685 217675 108699 217675 108796 217676 108699 217676 108700 217676 108700 217677 108699 217677 108683 217677 108700 217678 108683 217678 108701 217678 108701 217679 108683 217679 108702 217679 108702 217680 108683 217680 108703 217680 108703 217681 108683 217681 108704 217681 108703 217682 108704 217682 108803 217682 108680 217683 108710 217683 108705 217683 108705 217684 108710 217684 108706 217684 108705 217685 108706 217685 108707 217685 108706 217686 108805 217686 108707 217686 108707 217687 108805 217687 108708 217687 108707 217688 108708 217688 108682 217688 108682 217689 108708 217689 108709 217689 108682 217690 108709 217690 108704 217690 108704 217691 108709 217691 108801 217691 108704 217692 108801 217692 108803 217692 108710 217693 108680 217693 108837 217693 108837 217694 108680 217694 108711 217694 108837 217695 108711 217695 108712 217695 108712 217696 108711 217696 108713 217696 108712 217697 108713 217697 108736 217697 108736 217698 108713 217698 108672 217698 108714 217699 108867 217699 108715 217699 108714 217700 108715 217700 108716 217700 108716 217701 108715 217701 108669 217701 108716 217702 108669 217702 108717 217702 108717 217703 108669 217703 108718 217703 108717 217704 108718 217704 108800 217704 108719 217705 108830 217705 108720 217705 108733 217706 108719 217706 108758 217706 108730 217707 108722 217707 108721 217707 108721 217708 108722 217708 108723 217708 108721 217709 108723 217709 108724 217709 108724 217710 108723 217710 108732 217710 108724 217711 108732 217711 108854 217711 108854 217712 108732 217712 108842 217712 108729 217713 108846 217713 108725 217713 108774 217714 108726 217714 108727 217714 108727 217715 108726 217715 108728 217715 108727 217716 108728 217716 108729 217716 108729 217717 108728 217717 108850 217717 108729 217718 108850 217718 108846 217718 108731 217719 108722 217719 108765 217719 108765 217720 108722 217720 108730 217720 108765 217721 108730 217721 108763 217721 108731 217722 108774 217722 108722 217722 108722 217723 108774 217723 108727 217723 108722 217724 108727 217724 108723 217724 108723 217725 108727 217725 108729 217725 108723 217726 108729 217726 108732 217726 108732 217727 108729 217727 108725 217727 108732 217728 108725 217728 108842 217728 108768 217729 108772 217729 108731 217729 108731 217730 108772 217730 108773 217730 108731 217731 108773 217731 108774 217731 108764 217732 108733 217732 108766 217732 108766 217733 108733 217733 108758 217733 108766 217734 108758 217734 108767 217734 108767 217735 108758 217735 108759 217735 108694 217736 108741 217736 108735 217736 108735 217737 108741 217737 108753 217737 108771 217738 108770 217738 108735 217738 108769 217739 108693 217739 108770 217739 108770 217740 108693 217740 108734 217740 108770 217741 108734 217741 108735 217741 108735 217742 108734 217742 108690 217742 108735 217743 108690 217743 108694 217743 108834 217744 108736 217744 108737 217744 108737 217745 108736 217745 108769 217745 108714 217746 108756 217746 108868 217746 108868 217747 108756 217747 108738 217747 108868 217748 108738 217748 108739 217748 108739 217749 108738 217749 108740 217749 108741 217750 108695 217750 108753 217750 108753 217751 108695 217751 108743 217751 108753 217752 108743 217752 108742 217752 108742 217753 108743 217753 108744 217753 108742 217754 108744 217754 108740 217754 108740 217755 108744 217755 108745 217755 108740 217756 108745 217756 108739 217756 108771 217757 108746 217757 108747 217757 108747 217758 108746 217758 108752 217758 108747 217759 108752 217759 108748 217759 108748 217760 108752 217760 108754 217760 108748 217761 108754 217761 108749 217761 108749 217762 108754 217762 108755 217762 108749 217763 108755 217763 108775 217763 108775 217764 108755 217764 108751 217764 108775 217765 108751 217765 108750 217765 108750 217766 108751 217766 108757 217766 108750 217767 108757 217767 108851 217767 108771 217768 108735 217768 108746 217768 108746 217769 108735 217769 108753 217769 108746 217770 108753 217770 108752 217770 108752 217771 108753 217771 108742 217771 108752 217772 108742 217772 108754 217772 108754 217773 108742 217773 108740 217773 108754 217774 108740 217774 108755 217774 108755 217775 108740 217775 108738 217775 108755 217776 108738 217776 108751 217776 108751 217777 108738 217777 108756 217777 108751 217778 108756 217778 108757 217778 108719 217779 108720 217779 108758 217779 108758 217780 108720 217780 108760 217780 108758 217781 108760 217781 108759 217781 108759 217782 108760 217782 108761 217782 108759 217783 108761 217783 108762 217783 108763 217784 108764 217784 108765 217784 108765 217785 108764 217785 108766 217785 108765 217786 108766 217786 108731 217786 108731 217787 108766 217787 108767 217787 108731 217788 108767 217788 108768 217788 108768 217789 108767 217789 108759 217789 108768 217790 108759 217790 108737 217790 108737 217791 108759 217791 108762 217791 108737 217792 108762 217792 108834 217792 108769 217793 108770 217793 108737 217793 108737 217794 108770 217794 108771 217794 108737 217795 108771 217795 108768 217795 108768 217796 108771 217796 108747 217796 108768 217797 108747 217797 108772 217797 108772 217798 108747 217798 108748 217798 108772 217799 108748 217799 108773 217799 108773 217800 108748 217800 108749 217800 108773 217801 108749 217801 108774 217801 108774 217802 108749 217802 108775 217802 108774 217803 108775 217803 108726 217803 108726 217804 108775 217804 108750 217804 108726 217805 108750 217805 108728 217805 108728 217806 108750 217806 108851 217806 108728 217807 108851 217807 108850 217807 108706 217808 108710 217808 108776 217808 108823 217809 108822 217809 108783 217809 108814 217810 108777 217810 108785 217810 108817 217811 108778 217811 108818 217811 108838 217812 108839 217812 108779 217812 108779 217813 108839 217813 108794 217813 108779 217814 108794 217814 108780 217814 108780 217815 108794 217815 108781 217815 108780 217816 108781 217816 108860 217816 108860 217817 108781 217817 108792 217817 108818 217818 108778 217818 108782 217818 108782 217819 108778 217819 108786 217819 108782 217820 108786 217820 108783 217820 108784 217821 108785 217821 108857 217821 108783 217822 108822 217822 108782 217822 108782 217823 108822 217823 108820 217823 108782 217824 108820 217824 108818 217824 108786 217825 108787 217825 108783 217825 108783 217826 108787 217826 108788 217826 108783 217827 108788 217827 108823 217827 108823 217828 108788 217828 108789 217828 108823 217829 108789 217829 108790 217829 108790 217830 108789 217830 108793 217830 108790 217831 108793 217831 108827 217831 108827 217832 108793 217832 108847 217832 108827 217833 108847 217833 108791 217833 108787 217834 108792 217834 108788 217834 108788 217835 108792 217835 108781 217835 108788 217836 108781 217836 108789 217836 108789 217837 108781 217837 108794 217837 108789 217838 108794 217838 108793 217838 108793 217839 108794 217839 108839 217839 108793 217840 108839 217840 108847 217840 108697 217841 108698 217841 108795 217841 108795 217842 108698 217842 108796 217842 108795 217843 108796 217843 108813 217843 108813 217844 108796 217844 108700 217844 108813 217845 108700 217845 108797 217845 108797 217846 108700 217846 108701 217846 108797 217847 108701 217847 108802 217847 108798 217848 108799 217848 108795 217848 108795 217849 108799 217849 108800 217849 108795 217850 108800 217850 108697 217850 108804 217851 108801 217851 108806 217851 108806 217852 108801 217852 108709 217852 108806 217853 108709 217853 108708 217853 108701 217854 108702 217854 108802 217854 108802 217855 108702 217855 108703 217855 108802 217856 108703 217856 108804 217856 108804 217857 108703 217857 108803 217857 108804 217858 108803 217858 108801 217858 108708 217859 108805 217859 108806 217859 108806 217860 108805 217860 108706 217860 108806 217861 108706 217861 108815 217861 108815 217862 108706 217862 108776 217862 108815 217863 108776 217863 108816 217863 108785 217864 108784 217864 108814 217864 108814 217865 108784 217865 108819 217865 108814 217866 108819 217866 108807 217866 108807 217867 108819 217867 108821 217867 108807 217868 108821 217868 108808 217868 108808 217869 108821 217869 108824 217869 108808 217870 108824 217870 108809 217870 108809 217871 108824 217871 108825 217871 108809 217872 108825 217872 108810 217872 108810 217873 108825 217873 108826 217873 108810 217874 108826 217874 108811 217874 108811 217875 108826 217875 108828 217875 108811 217876 108828 217876 108812 217876 108812 217877 108828 217877 108829 217877 108812 217878 108829 217878 108798 217878 108798 217879 108795 217879 108812 217879 108812 217880 108795 217880 108813 217880 108812 217881 108813 217881 108811 217881 108811 217882 108813 217882 108797 217882 108811 217883 108797 217883 108810 217883 108810 217884 108797 217884 108802 217884 108810 217885 108802 217885 108809 217885 108809 217886 108802 217886 108804 217886 108809 217887 108804 217887 108808 217887 108808 217888 108804 217888 108806 217888 108808 217889 108806 217889 108807 217889 108807 217890 108806 217890 108815 217890 108807 217891 108815 217891 108814 217891 108814 217892 108815 217892 108816 217892 108814 217893 108816 217893 108777 217893 108857 217894 108817 217894 108784 217894 108784 217895 108817 217895 108818 217895 108784 217896 108818 217896 108819 217896 108819 217897 108818 217897 108820 217897 108819 217898 108820 217898 108821 217898 108821 217899 108820 217899 108822 217899 108821 217900 108822 217900 108824 217900 108824 217901 108822 217901 108823 217901 108824 217902 108823 217902 108825 217902 108825 217903 108823 217903 108790 217903 108825 217904 108790 217904 108826 217904 108826 217905 108790 217905 108827 217905 108826 217906 108827 217906 108828 217906 108828 217907 108827 217907 108791 217907 108828 217908 108791 217908 108829 217908 108831 217909 108832 217909 108835 217909 108861 217910 108857 217910 108785 217910 108720 217911 108830 217911 108865 217911 108761 217912 108760 217912 108831 217912 108831 217913 108760 217913 108720 217913 108720 217914 108865 217914 108831 217914 108831 217915 108865 217915 108863 217915 108831 217916 108863 217916 108832 217916 108832 217917 108863 217917 108833 217917 108832 217918 108833 217918 108861 217918 108834 217919 108762 217919 108836 217919 108836 217920 108762 217920 108761 217920 108736 217921 108834 217921 108712 217921 108712 217922 108834 217922 108836 217922 108712 217923 108836 217923 108837 217923 108861 217924 108785 217924 108832 217924 108832 217925 108785 217925 108777 217925 108832 217926 108777 217926 108835 217926 108835 217927 108777 217927 108816 217927 108835 217928 108816 217928 108776 217928 108761 217929 108831 217929 108836 217929 108836 217930 108831 217930 108835 217930 108836 217931 108835 217931 108837 217931 108837 217932 108835 217932 108776 217932 108837 217933 108776 217933 108710 217933 108799 217934 108798 217934 108848 217934 108844 217935 108862 217935 108845 217935 108838 217936 108840 217936 108839 217936 108839 217937 108840 217937 108843 217937 108854 217938 108842 217938 108864 217938 108864 217939 108842 217939 108862 217939 108852 217940 108841 217940 108849 217940 108849 217941 108841 217941 108843 217941 108862 217942 108842 217942 108845 217942 108845 217943 108842 217943 108725 217943 108845 217944 108725 217944 108846 217944 108840 217945 108844 217945 108843 217945 108843 217946 108844 217946 108845 217946 108843 217947 108845 217947 108849 217947 108849 217948 108845 217948 108846 217948 108798 217949 108829 217949 108841 217949 108841 217950 108829 217950 108791 217950 108841 217951 108791 217951 108843 217951 108843 217952 108791 217952 108847 217952 108843 217953 108847 217953 108839 217953 108716 217954 108717 217954 108848 217954 108848 217955 108717 217955 108800 217955 108848 217956 108800 217956 108799 217956 108846 217957 108850 217957 108849 217957 108849 217958 108850 217958 108851 217958 108849 217959 108851 217959 108852 217959 108852 217960 108851 217960 108757 217960 108852 217961 108757 217961 108756 217961 108798 217962 108841 217962 108848 217962 108848 217963 108841 217963 108852 217963 108848 217964 108852 217964 108716 217964 108716 217965 108852 217965 108756 217965 108716 217966 108756 217966 108714 217966 108853 217967 108854 217967 108864 217967 108853 217968 108763 217968 108730 217968 108730 217969 108721 217969 108853 217969 108853 217970 108721 217970 108724 217970 108853 217971 108724 217971 108854 217971 108855 217972 108733 217972 108853 217972 108853 217973 108733 217973 108764 217973 108853 217974 108764 217974 108763 217974 108856 217975 108857 217975 108861 217975 108858 217976 108778 217976 108856 217976 108856 217977 108778 217977 108817 217977 108856 217978 108817 217978 108857 217978 108838 217979 108859 217979 108856 217979 108856 217980 108859 217980 108780 217980 108856 217981 108780 217981 108860 217981 108860 217982 108792 217982 108856 217982 108856 217983 108792 217983 108787 217983 108856 217984 108787 217984 108858 217984 108838 217985 108856 217985 108840 217985 108840 217986 108856 217986 108861 217986 108840 217987 108861 217987 108844 217987 108844 217988 108861 217988 108833 217988 108844 217989 108833 217989 108862 217989 108862 217990 108833 217990 108863 217990 108862 217991 108863 217991 108864 217991 108864 217992 108863 217992 108865 217992 108864 217993 108865 217993 108853 217993 108853 217994 108865 217994 108830 217994 108853 217995 108830 217995 108855 217995 108743 217996 108675 217996 108744 217996 108744 217997 108675 217997 108869 217997 108744 217998 108869 217998 108745 217998 108745 217999 108869 217999 108866 217999 108745 218000 108866 218000 108739 218000 108739 218001 108866 218001 108868 218001 108868 218002 108866 218002 108867 218002 108868 218003 108867 218003 108714 218003 108675 218004 108870 218004 108869 218004 108869 218005 108870 218005 108895 218005 108869 218006 108895 218006 108866 218006 108866 218007 108895 218007 108871 218007 108866 218008 108871 218008 108867 218008 108867 218009 108871 218009 108894 218009 108965 218010 108872 218010 108992 218010 108992 218011 108872 218011 108880 218011 108992 218012 108880 218012 108993 218012 108993 218013 108880 218013 108873 218013 108993 218014 108873 218014 108948 218014 108948 218015 108873 218015 108874 218015 108874 218016 108873 218016 108875 218016 108874 218017 108875 218017 108949 218017 108949 218018 108875 218018 108950 218018 108950 218019 108875 218019 108878 218019 108950 218020 108878 218020 108984 218020 108984 218021 108878 218021 108876 218021 108984 218022 108876 218022 108933 218022 108687 218023 108876 218023 108877 218023 108877 218024 108876 218024 108878 218024 108877 218025 108878 218025 108879 218025 108879 218026 108878 218026 108875 218026 108872 218027 108898 218027 108880 218027 108880 218028 108898 218028 108901 218028 108880 218029 108901 218029 108873 218029 108873 218030 108901 218030 108881 218030 108873 218031 108881 218031 108875 218031 108875 218032 108881 218032 108897 218032 108875 218033 108897 218033 108879 218033 108908 218034 108907 218034 108945 218034 108892 218035 108891 218035 108882 218035 108945 218036 108883 218036 108908 218036 108908 218037 108883 218037 108884 218037 108908 218038 108884 218038 108882 218038 108882 218039 108884 218039 108885 218039 108882 218040 108885 218040 108892 218040 108922 218041 108911 218041 108924 218041 108924 218042 108911 218042 108686 218042 108924 218043 108686 218043 108887 218043 108887 218044 108686 218044 108886 218044 108887 218045 108886 218045 108888 218045 108888 218046 108886 218046 108889 218046 108888 218047 108889 218047 108926 218047 108926 218048 108889 218048 108891 218048 108926 218049 108891 218049 108890 218049 108890 218050 108891 218050 108892 218050 108917 218051 108904 218051 108918 218051 108918 218052 108904 218052 108893 218052 108918 218053 108893 218053 108872 218053 108872 218054 108893 218054 108898 218054 108895 218055 108891 218055 108889 218055 108886 218056 108894 218056 108889 218056 108889 218057 108894 218057 108871 218057 108889 218058 108871 218058 108895 218058 108895 218059 108870 218059 108891 218059 108891 218060 108870 218060 108674 218060 108891 218061 108674 218061 108882 218061 108896 218062 108879 218062 108897 218062 108671 218063 108899 218063 108898 218063 108898 218064 108899 218064 108900 218064 108898 218065 108900 218065 108901 218065 108900 218066 108681 218066 108901 218066 108901 218067 108681 218067 108902 218067 108901 218068 108902 218068 108881 218068 108881 218069 108902 218069 108903 218069 108881 218070 108903 218070 108897 218070 108897 218071 108903 218071 108684 218071 108897 218072 108684 218072 108896 218072 108898 218073 108893 218073 108671 218073 108671 218074 108893 218074 108904 218074 108671 218075 108904 218075 108905 218075 108905 218076 108904 218076 108916 218076 108905 218077 108916 218077 108906 218077 108906 218078 108916 218078 108907 218078 108906 218079 108907 218079 108673 218079 108673 218080 108907 218080 108908 218080 108673 218081 108908 218081 108909 218081 108909 218082 108908 218082 108882 218082 108909 218083 108882 218083 108910 218083 108910 218084 108882 218084 108674 218084 108911 218085 108922 218085 108912 218085 108911 218086 108912 218086 108688 218086 108688 218087 108912 218087 108876 218087 108688 218088 108876 218088 108687 218088 108933 218089 108876 218089 108913 218089 108913 218090 108876 218090 108912 218090 108913 218091 108912 218091 108914 218091 108922 218092 108921 218092 108912 218092 108912 218093 108921 218093 108935 218093 108912 218094 108935 218094 108914 218094 108945 218095 108907 218095 108915 218095 108915 218096 108907 218096 108916 218096 108915 218097 108916 218097 108917 218097 108917 218098 108916 218098 108904 218098 108947 218099 108917 218099 108919 218099 108919 218100 108917 218100 108918 218100 108919 218101 108918 218101 108964 218101 108964 218102 108918 218102 108920 218102 108920 218103 108918 218103 108872 218103 108920 218104 108872 218104 108965 218104 108921 218105 108922 218105 108923 218105 108923 218106 108922 218106 108924 218106 108923 218107 108924 218107 109019 218107 109019 218108 108924 218108 108887 218108 108892 218109 108925 218109 108890 218109 108890 218110 108925 218110 109024 218110 108890 218111 109024 218111 108926 218111 108926 218112 109024 218112 109023 218112 108926 218113 109023 218113 108888 218113 108888 218114 109023 218114 108927 218114 108888 218115 108927 218115 108887 218115 108887 218116 108927 218116 109021 218116 108887 218117 109021 218117 109019 218117 108945 218118 108944 218118 108883 218118 108883 218119 108944 218119 108928 218119 108883 218120 108928 218120 108884 218120 108928 218121 108929 218121 108884 218121 108884 218122 108929 218122 109028 218122 108884 218123 109028 218123 108885 218123 108885 218124 109028 218124 109027 218124 108885 218125 109027 218125 108892 218125 108892 218126 109027 218126 108930 218126 108892 218127 108930 218127 108925 218127 108942 218128 109018 218128 108943 218128 109018 218129 108942 218129 109014 218129 108934 218130 108931 218130 108938 218130 108932 218131 108933 218131 108913 218131 108940 218132 108973 218132 108934 218132 108934 218133 108973 218133 108932 218133 108932 218134 108913 218134 108934 218134 108934 218135 108913 218135 108914 218135 108934 218136 108914 218136 108931 218136 108931 218137 108914 218137 108935 218137 108931 218138 108935 218138 108921 218138 108998 218139 108936 218139 108939 218139 108939 218140 108936 218140 108940 218140 108921 218141 108937 218141 108931 218141 108931 218142 108937 218142 109041 218142 108931 218143 109041 218143 108938 218143 108938 218144 109041 218144 109040 218144 108938 218145 109040 218145 109051 218145 108957 218146 108998 218146 108941 218146 108941 218147 108998 218147 108939 218147 108941 218148 108939 218148 108942 218148 108940 218149 108934 218149 108939 218149 108939 218150 108934 218150 108938 218150 108939 218151 108938 218151 108942 218151 108942 218152 108938 218152 109051 218152 108942 218153 109051 218153 109014 218153 108638 218154 108957 218154 108650 218154 108650 218155 108957 218155 108941 218155 108650 218156 108941 218156 108649 218156 108649 218157 108941 218157 108942 218157 108649 218158 108942 218158 108648 218158 108648 218159 108942 218159 108943 218159 108944 218160 108945 218160 108652 218160 108652 218161 108945 218161 108915 218161 108652 218162 108915 218162 108946 218162 108946 218163 108915 218163 108668 218163 108668 218164 108915 218164 108917 218164 108668 218165 108917 218165 108947 218165 108948 218166 108874 218166 108975 218166 108949 218167 108950 218167 108985 218167 108997 218168 108951 218168 108996 218168 108952 218169 108641 218169 108960 218169 108952 218170 108960 218170 108642 218170 108958 218171 108953 218171 108955 218171 108955 218172 108953 218172 108954 218172 108955 218173 108954 218173 108997 218173 108997 218174 108954 218174 108956 218174 108997 218175 108956 218175 108951 218175 108955 218176 108999 218176 108958 218176 108958 218177 108999 218177 108957 218177 108958 218178 108957 218178 108638 218178 108986 218179 108960 218179 108959 218179 108959 218180 108960 218180 108641 218180 108959 218181 108641 218181 108987 218181 108996 218182 108951 218182 108961 218182 108961 218183 108951 218183 108988 218183 108961 218184 108988 218184 108989 218184 108968 218185 108962 218185 108963 218185 108963 218186 108962 218186 108967 218186 108920 218187 108966 218187 108964 218187 108964 218188 108966 218188 108919 218188 108654 218189 108947 218189 108990 218189 108990 218190 108947 218190 108919 218190 108920 218191 108965 218191 108966 218191 108966 218192 108965 218192 108967 218192 108966 218193 108967 218193 108969 218193 108969 218194 108967 218194 108962 218194 108969 218195 108962 218195 108970 218195 108970 218196 108962 218196 108968 218196 108970 218197 108968 218197 108971 218197 108919 218198 108966 218198 108990 218198 108990 218199 108966 218199 108969 218199 108990 218200 108969 218200 108989 218200 108989 218201 108969 218201 108970 218201 108989 218202 108970 218202 108961 218202 108961 218203 108970 218203 108971 218203 108961 218204 108971 218204 108996 218204 108948 218205 108975 218205 108993 218205 108998 218206 108978 218206 108936 218206 108936 218207 108978 218207 108972 218207 108936 218208 108972 218208 108940 218208 108940 218209 108972 218209 108980 218209 108940 218210 108980 218210 108973 218210 108973 218211 108980 218211 108982 218211 108973 218212 108982 218212 108932 218212 108932 218213 108982 218213 108974 218213 108932 218214 108974 218214 108933 218214 108933 218215 108974 218215 108984 218215 108874 218216 108949 218216 108975 218216 108975 218217 108949 218217 108985 218217 108975 218218 108985 218218 108994 218218 108994 218219 108985 218219 108983 218219 108994 218220 108983 218220 108995 218220 108995 218221 108983 218221 108981 218221 108995 218222 108981 218222 108976 218222 108976 218223 108981 218223 108979 218223 108976 218224 108979 218224 108977 218224 108978 218225 108977 218225 108972 218225 108972 218226 108977 218226 108979 218226 108972 218227 108979 218227 108980 218227 108980 218228 108979 218228 108981 218228 108980 218229 108981 218229 108982 218229 108982 218230 108981 218230 108983 218230 108982 218231 108983 218231 108974 218231 108974 218232 108983 218232 108985 218232 108974 218233 108985 218233 108984 218233 108984 218234 108985 218234 108950 218234 108991 218235 108986 218235 108667 218235 108667 218236 108986 218236 108959 218236 108667 218237 108959 218237 108655 218237 108655 218238 108959 218238 108987 218238 108655 218239 108987 218239 108656 218239 108956 218240 108643 218240 108951 218240 108951 218241 108643 218241 108642 218241 108951 218242 108642 218242 108988 218242 108988 218243 108642 218243 108960 218243 108988 218244 108960 218244 108989 218244 108989 218245 108960 218245 108986 218245 108989 218246 108986 218246 108990 218246 108990 218247 108986 218247 108991 218247 108990 218248 108991 218248 108654 218248 108965 218249 108992 218249 108967 218249 108967 218250 108992 218250 108993 218250 108967 218251 108993 218251 108963 218251 108963 218252 108993 218252 108975 218252 108963 218253 108975 218253 108968 218253 108968 218254 108975 218254 108994 218254 108968 218255 108994 218255 108971 218255 108971 218256 108994 218256 108995 218256 108971 218257 108995 218257 108996 218257 108996 218258 108995 218258 108976 218258 108996 218259 108976 218259 108997 218259 108997 218260 108976 218260 108977 218260 108997 218261 108977 218261 108955 218261 108955 218262 108977 218262 108978 218262 108955 218263 108978 218263 108999 218263 108999 218264 108978 218264 108998 218264 108999 218265 108998 218265 108957 218265 108928 218266 108944 218266 108651 218266 109011 218267 109009 218267 109007 218267 109032 218268 108653 218268 108662 218268 108644 218269 109000 218269 109001 218269 109001 218270 109000 218270 109002 218270 109001 218271 109002 218271 109003 218271 109003 218272 109002 218272 108943 218272 109003 218273 108943 218273 109018 218273 109046 218274 108662 218274 108647 218274 108646 218275 109004 218275 109047 218275 109047 218276 109004 218276 109005 218276 109047 218277 109005 218277 109008 218277 109008 218278 109005 218278 109006 218278 109008 218279 109006 218279 109007 218279 109007 218280 109009 218280 109008 218280 109008 218281 109009 218281 109010 218281 109008 218282 109010 218282 109047 218282 109006 218283 109015 218283 109007 218283 109007 218284 109015 218284 109012 218284 109007 218285 109012 218285 109011 218285 109011 218286 109012 218286 109016 218286 109011 218287 109016 218287 109013 218287 109013 218288 109016 218288 109017 218288 109013 218289 109017 218289 109050 218289 109050 218290 109017 218290 109014 218290 109050 218291 109014 218291 109051 218291 109015 218292 108644 218292 109012 218292 109012 218293 108644 218293 109001 218293 109012 218294 109001 218294 109016 218294 109016 218295 109001 218295 109003 218295 109016 218296 109003 218296 109017 218296 109017 218297 109003 218297 109018 218297 109017 218298 109018 218298 109014 218298 108923 218299 109019 218299 109042 218299 109042 218300 109019 218300 109021 218300 109042 218301 109021 218301 109020 218301 109020 218302 109021 218302 108927 218302 109020 218303 108927 218303 109022 218303 109022 218304 108927 218304 109023 218304 109022 218305 109023 218305 109025 218305 109041 218306 108937 218306 109042 218306 109042 218307 108937 218307 108921 218307 109042 218308 108921 218308 108923 218308 109023 218309 109024 218309 109025 218309 109025 218310 109024 218310 108925 218310 109025 218311 108925 218311 109026 218311 109026 218312 108925 218312 108930 218312 109026 218313 108930 218313 109029 218313 109029 218314 108930 218314 109027 218314 109029 218315 109027 218315 109028 218315 109028 218316 108929 218316 109029 218316 109029 218317 108929 218317 108928 218317 109029 218318 108928 218318 109030 218318 109030 218319 108928 218319 108651 218319 109030 218320 108651 218320 109031 218320 108662 218321 109046 218321 109032 218321 109032 218322 109046 218322 109048 218322 109032 218323 109048 218323 109033 218323 109033 218324 109048 218324 109034 218324 109033 218325 109034 218325 109035 218325 109035 218326 109034 218326 109049 218326 109035 218327 109049 218327 109045 218327 109045 218328 109049 218328 109036 218328 109045 218329 109036 218329 109044 218329 109044 218330 109036 218330 109038 218330 109044 218331 109038 218331 109037 218331 109037 218332 109038 218332 109039 218332 109037 218333 109039 218333 109043 218333 109043 218334 109039 218334 109040 218334 109043 218335 109040 218335 109041 218335 109041 218336 109042 218336 109043 218336 109043 218337 109042 218337 109020 218337 109043 218338 109020 218338 109037 218338 109037 218339 109020 218339 109022 218339 109037 218340 109022 218340 109044 218340 109044 218341 109022 218341 109025 218341 109044 218342 109025 218342 109045 218342 109045 218343 109025 218343 109026 218343 109045 218344 109026 218344 109035 218344 109035 218345 109026 218345 109029 218345 109035 218346 109029 218346 109033 218346 109033 218347 109029 218347 109030 218347 109033 218348 109030 218348 109032 218348 109032 218349 109030 218349 109031 218349 109032 218350 109031 218350 108653 218350 108647 218351 108646 218351 109046 218351 109046 218352 108646 218352 109047 218352 109046 218353 109047 218353 109048 218353 109048 218354 109047 218354 109010 218354 109048 218355 109010 218355 109034 218355 109034 218356 109010 218356 109009 218356 109034 218357 109009 218357 109049 218357 109049 218358 109009 218358 109011 218358 109049 218359 109011 218359 109036 218359 109036 218360 109011 218360 109013 218360 109036 218361 109013 218361 109038 218361 109038 218362 109013 218362 109050 218362 109038 218363 109050 218363 109039 218363 109039 218364 109050 218364 109051 218364 109039 218365 109051 218365 109040 218365 109052 218366 109115 218366 109111 218366 109101 218367 109064 218367 109062 218367 109096 218368 109098 218368 109053 218368 109054 218369 109055 218369 109099 218369 109056 218370 109119 218370 109057 218370 109057 218371 109119 218371 109071 218371 109057 218372 109071 218372 109058 218372 109058 218373 109071 218373 109060 218373 109058 218374 109060 218374 109059 218374 109059 218375 109060 218375 109061 218375 109099 218376 109055 218376 109065 218376 109065 218377 109055 218377 109066 218377 109065 218378 109066 218378 109062 218378 109081 218379 109053 218379 109063 218379 109062 218380 109064 218380 109065 218380 109065 218381 109064 218381 109100 218381 109065 218382 109100 218382 109099 218382 109066 218383 109135 218383 109062 218383 109062 218384 109135 218384 109067 218384 109062 218385 109067 218385 109101 218385 109101 218386 109067 218386 109070 218386 109101 218387 109070 218387 109103 218387 109103 218388 109070 218388 109069 218388 109103 218389 109069 218389 109068 218389 109068 218390 109069 218390 109072 218390 109068 218391 109072 218391 109104 218391 109135 218392 109061 218392 109067 218392 109067 218393 109061 218393 109060 218393 109067 218394 109060 218394 109070 218394 109070 218395 109060 218395 109071 218395 109070 218396 109071 218396 109069 218396 109069 218397 109071 218397 109119 218397 109069 218398 109119 218398 109072 218398 109362 218399 109073 218399 109089 218399 109089 218400 109073 218400 109368 218400 109089 218401 109368 218401 109074 218401 109074 218402 109368 218402 109075 218402 109074 218403 109075 218403 109076 218403 109076 218404 109075 218404 109367 218404 109076 218405 109367 218405 109078 218405 109116 218406 109126 218406 109089 218406 109089 218407 109126 218407 109125 218407 109089 218408 109125 218408 109362 218408 109079 218409 109077 218409 109095 218409 109095 218410 109077 218410 109372 218410 109095 218411 109372 218411 109371 218411 109367 218412 109366 218412 109078 218412 109078 218413 109366 218413 109365 218413 109078 218414 109365 218414 109079 218414 109079 218415 109365 218415 109373 218415 109079 218416 109373 218416 109077 218416 109371 218417 109369 218417 109095 218417 109095 218418 109369 218418 109052 218418 109095 218419 109052 218419 109080 218419 109080 218420 109052 218420 109111 218420 109080 218421 109111 218421 109097 218421 109053 218422 109081 218422 109096 218422 109096 218423 109081 218423 109082 218423 109096 218424 109082 218424 109094 218424 109094 218425 109082 218425 109083 218425 109094 218426 109083 218426 109085 218426 109085 218427 109083 218427 109084 218427 109085 218428 109084 218428 109093 218428 109093 218429 109084 218429 109102 218429 109093 218430 109102 218430 109092 218430 109092 218431 109102 218431 109086 218431 109092 218432 109086 218432 109091 218432 109091 218433 109086 218433 109087 218433 109091 218434 109087 218434 109090 218434 109090 218435 109087 218435 109088 218435 109090 218436 109088 218436 109116 218436 109116 218437 109089 218437 109090 218437 109090 218438 109089 218438 109074 218438 109090 218439 109074 218439 109091 218439 109091 218440 109074 218440 109076 218440 109091 218441 109076 218441 109092 218441 109092 218442 109076 218442 109078 218442 109092 218443 109078 218443 109093 218443 109093 218444 109078 218444 109079 218444 109093 218445 109079 218445 109085 218445 109085 218446 109079 218446 109095 218446 109085 218447 109095 218447 109094 218447 109094 218448 109095 218448 109080 218448 109094 218449 109080 218449 109096 218449 109096 218450 109080 218450 109097 218450 109096 218451 109097 218451 109098 218451 109063 218452 109054 218452 109081 218452 109081 218453 109054 218453 109099 218453 109081 218454 109099 218454 109082 218454 109082 218455 109099 218455 109100 218455 109082 218456 109100 218456 109083 218456 109083 218457 109100 218457 109064 218457 109083 218458 109064 218458 109084 218458 109084 218459 109064 218459 109101 218459 109084 218460 109101 218460 109102 218460 109102 218461 109101 218461 109103 218461 109102 218462 109103 218462 109086 218462 109086 218463 109103 218463 109068 218463 109086 218464 109068 218464 109087 218464 109087 218465 109068 218465 109104 218465 109087 218466 109104 218466 109088 218466 109113 218467 109109 218467 109114 218467 109136 218468 109063 218468 109053 218468 109422 218469 109380 218469 109105 218469 109106 218470 109107 218470 109113 218470 109113 218471 109107 218471 109422 218471 109422 218472 109105 218472 109113 218472 109113 218473 109105 218473 109108 218473 109113 218474 109108 218474 109109 218474 109109 218475 109108 218475 109139 218475 109109 218476 109139 218476 109136 218476 109429 218477 109428 218477 109112 218477 109112 218478 109428 218478 109106 218478 109403 218479 109429 218479 109110 218479 109110 218480 109429 218480 109112 218480 109110 218481 109112 218481 109376 218481 109136 218482 109053 218482 109109 218482 109109 218483 109053 218483 109098 218483 109109 218484 109098 218484 109114 218484 109114 218485 109098 218485 109097 218485 109114 218486 109097 218486 109111 218486 109106 218487 109113 218487 109112 218487 109112 218488 109113 218488 109114 218488 109112 218489 109114 218489 109376 218489 109376 218490 109114 218490 109111 218490 109376 218491 109111 218491 109115 218491 109126 218492 109116 218492 109129 218492 109137 218493 109138 218493 109117 218493 109056 218494 109118 218494 109119 218494 109119 218495 109118 218495 109123 218495 109384 218496 109385 218496 109140 218496 109140 218497 109385 218497 109138 218497 109120 218498 109121 218498 109122 218498 109122 218499 109121 218499 109123 218499 109138 218500 109385 218500 109117 218500 109117 218501 109385 218501 109387 218501 109117 218502 109387 218502 109390 218502 109118 218503 109137 218503 109123 218503 109123 218504 109137 218504 109117 218504 109123 218505 109117 218505 109122 218505 109122 218506 109117 218506 109390 218506 109116 218507 109088 218507 109121 218507 109121 218508 109088 218508 109104 218508 109121 218509 109104 218509 109123 218509 109123 218510 109104 218510 109072 218510 109123 218511 109072 218511 109119 218511 109130 218512 109124 218512 109129 218512 109129 218513 109124 218513 109125 218513 109129 218514 109125 218514 109126 218514 109390 218515 109389 218515 109122 218515 109122 218516 109389 218516 109127 218516 109122 218517 109127 218517 109120 218517 109120 218518 109127 218518 109414 218518 109120 218519 109414 218519 109128 218519 109116 218520 109121 218520 109129 218520 109129 218521 109121 218521 109120 218521 109129 218522 109120 218522 109130 218522 109130 218523 109120 218523 109128 218523 109130 218524 109128 218524 109377 218524 109141 218525 109384 218525 109140 218525 109141 218526 109133 218526 109392 218526 109392 218527 109382 218527 109141 218527 109141 218528 109382 218528 109383 218528 109141 218529 109383 218529 109384 218529 109142 218530 109131 218530 109141 218530 109141 218531 109131 218531 109132 218531 109141 218532 109132 218532 109133 218532 109134 218533 109063 218533 109136 218533 109066 218534 109055 218534 109134 218534 109134 218535 109055 218535 109054 218535 109134 218536 109054 218536 109063 218536 109056 218537 109057 218537 109134 218537 109134 218538 109057 218538 109058 218538 109134 218539 109058 218539 109059 218539 109059 218540 109061 218540 109134 218540 109134 218541 109061 218541 109135 218541 109134 218542 109135 218542 109066 218542 109056 218543 109134 218543 109118 218543 109118 218544 109134 218544 109136 218544 109118 218545 109136 218545 109137 218545 109137 218546 109136 218546 109139 218546 109137 218547 109139 218547 109138 218547 109138 218548 109139 218548 109108 218548 109138 218549 109108 218549 109140 218549 109140 218550 109108 218550 109105 218550 109140 218551 109105 218551 109141 218551 109141 218552 109105 218552 109380 218552 109141 218553 109380 218553 109142 218553 109143 218554 109361 218554 109144 218554 109144 218555 109361 218555 109145 218555 109144 218556 109145 218556 109408 218556 109408 218557 109145 218557 109407 218557 109407 218558 109145 218558 109150 218558 109407 218559 109150 218559 109146 218559 109146 218560 109150 218560 109148 218560 109148 218561 109150 218561 109147 218561 109148 218562 109147 218562 109406 218562 109406 218563 109147 218563 109378 218563 109406 218564 109378 218564 109377 218564 109361 218565 109149 218565 109145 218565 109145 218566 109149 218566 109452 218566 109145 218567 109452 218567 109150 218567 109150 218568 109452 218568 109451 218568 109150 218569 109451 218569 109147 218569 109147 218570 109451 218570 109151 218570 109147 218571 109151 218571 109378 218571 109378 218572 109151 218572 109152 218572 109153 218573 109163 218573 109154 218573 109154 218574 109163 218574 109155 218574 109154 218575 109155 218575 109156 218575 109156 218576 109155 218576 109226 218576 109226 218577 109155 218577 109157 218577 109226 218578 109157 218578 109158 218578 109158 218579 109157 218579 109159 218579 109159 218580 109157 218580 109160 218580 109159 218581 109160 218581 109224 218581 109224 218582 109160 218582 109161 218582 109224 218583 109161 218583 109183 218583 109351 218584 109161 218584 109162 218584 109162 218585 109161 218585 109160 218585 109162 218586 109160 218586 109350 218586 109350 218587 109160 218587 109157 218587 109163 218588 109450 218588 109155 218588 109155 218589 109450 218589 109455 218589 109155 218590 109455 218590 109157 218590 109157 218591 109455 218591 109164 218591 109157 218592 109164 218592 109350 218592 109183 218593 109161 218593 109185 218593 109185 218594 109161 218594 109463 218594 109185 218595 109463 218595 109186 218595 109171 218596 109189 218596 109463 218596 109463 218597 109189 218597 109187 218597 109463 218598 109187 218598 109186 218598 109201 218599 109459 218599 109203 218599 109203 218600 109459 218600 109165 218600 109203 218601 109165 218601 109204 218601 109204 218602 109165 218602 109447 218602 109446 218603 109219 218603 109166 218603 109446 218604 109166 218604 109204 218604 109204 218605 109166 218605 109239 218605 109204 218606 109239 218606 109167 218606 109219 218607 109446 218607 109168 218607 109168 218608 109446 218608 109449 218608 109168 218609 109449 218609 109169 218609 109163 218610 109153 218610 109170 218610 109163 218611 109170 218611 109449 218611 109449 218612 109170 218612 109221 218612 109449 218613 109221 218613 109169 218613 109189 218614 109171 218614 109172 218614 109172 218615 109171 218615 109439 218615 109172 218616 109439 218616 109173 218616 109173 218617 109439 218617 109440 218617 109445 218618 109174 218618 109444 218618 109444 218619 109174 218619 109175 218619 109444 218620 109175 218620 109442 218620 109442 218621 109175 218621 109176 218621 109442 218622 109176 218622 109177 218622 109177 218623 109176 218623 109273 218623 109177 218624 109273 218624 109440 218624 109440 218625 109273 218625 109272 218625 109440 218626 109272 218626 109173 218626 109201 218627 109317 218627 109435 218627 109435 218628 109317 218628 109178 218628 109435 218629 109178 218629 109437 218629 109178 218630 109179 218630 109437 218630 109437 218631 109179 218631 109180 218631 109437 218632 109180 218632 109438 218632 109438 218633 109180 218633 109278 218633 109438 218634 109278 218634 109445 218634 109445 218635 109278 218635 109181 218635 109445 218636 109181 218636 109174 218636 109200 218637 109269 218637 109182 218637 109269 218638 109200 218638 109270 218638 109197 218639 109191 218639 109193 218639 109184 218640 109183 218640 109185 218640 109188 218641 109233 218641 109197 218641 109197 218642 109233 218642 109184 218642 109184 218643 109185 218643 109197 218643 109197 218644 109185 218644 109186 218644 109197 218645 109186 218645 109191 218645 109191 218646 109186 218646 109187 218646 109191 218647 109187 218647 109189 218647 109195 218648 109251 218648 109196 218648 109196 218649 109251 218649 109188 218649 109189 218650 109190 218650 109191 218650 109191 218651 109190 218651 109192 218651 109191 218652 109192 218652 109193 218652 109193 218653 109192 218653 109286 218653 109193 218654 109286 218654 109194 218654 109198 218655 109195 218655 109199 218655 109199 218656 109195 218656 109196 218656 109199 218657 109196 218657 109200 218657 109188 218658 109197 218658 109196 218658 109196 218659 109197 218659 109193 218659 109196 218660 109193 218660 109200 218660 109200 218661 109193 218661 109194 218661 109200 218662 109194 218662 109270 218662 109302 218663 109198 218663 109315 218663 109315 218664 109198 218664 109199 218664 109315 218665 109199 218665 109314 218665 109314 218666 109199 218666 109200 218666 109314 218667 109200 218667 109312 218667 109312 218668 109200 218668 109182 218668 109317 218669 109201 218669 109318 218669 109318 218670 109201 218670 109203 218670 109318 218671 109203 218671 109202 218671 109202 218672 109203 218672 109330 218672 109330 218673 109203 218673 109204 218673 109330 218674 109204 218674 109167 218674 109239 218675 109166 218675 109245 218675 109221 218676 109170 218676 109234 218676 109214 218677 109212 218677 109215 218677 109305 218678 109304 218678 109213 218678 109305 218679 109213 218679 109205 218679 109301 218680 109303 218680 109212 218680 109212 218681 109303 218681 109206 218681 109212 218682 109206 218682 109215 218682 109215 218683 109206 218683 109306 218683 109215 218684 109306 218684 109207 218684 109198 218685 109208 218685 109195 218685 109195 218686 109208 218686 109209 218686 109195 218687 109209 218687 109251 218687 109251 218688 109209 218688 109210 218688 109211 218689 109210 218689 109214 218689 109214 218690 109210 218690 109209 218690 109214 218691 109209 218691 109212 218691 109212 218692 109209 218692 109208 218692 109212 218693 109208 218693 109301 218693 109301 218694 109208 218694 109198 218694 109301 218695 109198 218695 109302 218695 109242 218696 109213 218696 109243 218696 109243 218697 109213 218697 109304 218697 109243 218698 109304 218698 109244 218698 109211 218699 109214 218699 109249 218699 109249 218700 109214 218700 109215 218700 109249 218701 109215 218701 109248 218701 109248 218702 109215 218702 109207 218702 109248 218703 109207 218703 109216 218703 109216 218704 109207 218704 109217 218704 109216 218705 109217 218705 109223 218705 109234 218706 109170 218706 109218 218706 109227 218707 109220 218707 109234 218707 109166 218708 109219 218708 109220 218708 109220 218709 109219 218709 109168 218709 109220 218710 109168 218710 109234 218710 109234 218711 109168 218711 109169 218711 109234 218712 109169 218712 109221 218712 109306 218713 109222 218713 109207 218713 109207 218714 109222 218714 109205 218714 109207 218715 109205 218715 109217 218715 109217 218716 109205 218716 109213 218716 109217 218717 109213 218717 109223 218717 109223 218718 109213 218718 109242 218718 109223 218719 109242 218719 109245 218719 109183 218720 109184 218720 109238 218720 109183 218721 109238 218721 109224 218721 109224 218722 109238 218722 109236 218722 109224 218723 109236 218723 109159 218723 109159 218724 109236 218724 109158 218724 109158 218725 109236 218725 109225 218725 109158 218726 109225 218726 109226 218726 109170 218727 109153 218727 109218 218727 109218 218728 109153 218728 109154 218728 109218 218729 109154 218729 109225 218729 109225 218730 109154 218730 109156 218730 109225 218731 109156 218731 109226 218731 109227 218732 109235 218732 109246 218732 109246 218733 109235 218733 109228 218733 109246 218734 109228 218734 109247 218734 109247 218735 109228 218735 109229 218735 109247 218736 109229 218736 109230 218736 109230 218737 109229 218737 109237 218737 109230 218738 109237 218738 109231 218738 109231 218739 109237 218739 109232 218739 109231 218740 109232 218740 109250 218740 109250 218741 109232 218741 109233 218741 109250 218742 109233 218742 109188 218742 109227 218743 109234 218743 109235 218743 109235 218744 109234 218744 109218 218744 109235 218745 109218 218745 109228 218745 109228 218746 109218 218746 109225 218746 109228 218747 109225 218747 109229 218747 109229 218748 109225 218748 109236 218748 109229 218749 109236 218749 109237 218749 109237 218750 109236 218750 109238 218750 109237 218751 109238 218751 109232 218751 109232 218752 109238 218752 109184 218752 109232 218753 109184 218753 109233 218753 109167 218754 109239 218754 109240 218754 109240 218755 109239 218755 109245 218755 109240 218756 109245 218756 109327 218756 109327 218757 109245 218757 109242 218757 109327 218758 109242 218758 109241 218758 109241 218759 109242 218759 109243 218759 109241 218760 109243 218760 109320 218760 109320 218761 109243 218761 109244 218761 109320 218762 109244 218762 109321 218762 109166 218763 109220 218763 109245 218763 109245 218764 109220 218764 109227 218764 109245 218765 109227 218765 109223 218765 109223 218766 109227 218766 109246 218766 109223 218767 109246 218767 109216 218767 109216 218768 109246 218768 109247 218768 109216 218769 109247 218769 109248 218769 109248 218770 109247 218770 109230 218770 109248 218771 109230 218771 109249 218771 109249 218772 109230 218772 109231 218772 109249 218773 109231 218773 109211 218773 109211 218774 109231 218774 109250 218774 109211 218775 109250 218775 109210 218775 109210 218776 109250 218776 109188 218776 109210 218777 109188 218777 109251 218777 109178 218778 109317 218778 109252 218778 109264 218779 109253 218779 109262 218779 109282 218780 109323 218780 109281 218780 109311 218781 109310 218781 109254 218781 109254 218782 109310 218782 109255 218782 109254 218783 109255 218783 109267 218783 109267 218784 109255 218784 109182 218784 109267 218785 109182 218785 109269 218785 109256 218786 109281 218786 109308 218786 109257 218787 109258 218787 109292 218787 109292 218788 109258 218788 109309 218788 109292 218789 109309 218789 109259 218789 109259 218790 109309 218790 109261 218790 109259 218791 109261 218791 109262 218791 109262 218792 109253 218792 109259 218792 109259 218793 109253 218793 109260 218793 109259 218794 109260 218794 109292 218794 109261 218795 109263 218795 109262 218795 109262 218796 109263 218796 109265 218796 109262 218797 109265 218797 109264 218797 109264 218798 109265 218798 109266 218798 109264 218799 109266 218799 109296 218799 109296 218800 109266 218800 109268 218800 109296 218801 109268 218801 109299 218801 109299 218802 109268 218802 109270 218802 109299 218803 109270 218803 109194 218803 109263 218804 109311 218804 109265 218804 109265 218805 109311 218805 109254 218805 109265 218806 109254 218806 109266 218806 109266 218807 109254 218807 109267 218807 109266 218808 109267 218808 109268 218808 109268 218809 109267 218809 109269 218809 109268 218810 109269 218810 109270 218810 109172 218811 109173 218811 109271 218811 109271 218812 109173 218812 109272 218812 109271 218813 109272 218813 109289 218813 109289 218814 109272 218814 109273 218814 109289 218815 109273 218815 109274 218815 109274 218816 109273 218816 109176 218816 109274 218817 109176 218817 109275 218817 109192 218818 109190 218818 109271 218818 109271 218819 109190 218819 109189 218819 109271 218820 109189 218820 109172 218820 109176 218821 109175 218821 109275 218821 109275 218822 109175 218822 109174 218822 109275 218823 109174 218823 109276 218823 109276 218824 109174 218824 109181 218824 109276 218825 109181 218825 109277 218825 109277 218826 109181 218826 109278 218826 109277 218827 109278 218827 109180 218827 109180 218828 109179 218828 109277 218828 109277 218829 109179 218829 109178 218829 109277 218830 109178 218830 109279 218830 109279 218831 109178 218831 109252 218831 109279 218832 109252 218832 109280 218832 109281 218833 109256 218833 109282 218833 109282 218834 109256 218834 109283 218834 109282 218835 109283 218835 109291 218835 109291 218836 109283 218836 109293 218836 109291 218837 109293 218837 109290 218837 109290 218838 109293 218838 109294 218838 109290 218839 109294 218839 109284 218839 109284 218840 109294 218840 109295 218840 109284 218841 109295 218841 109285 218841 109285 218842 109295 218842 109297 218842 109285 218843 109297 218843 109288 218843 109288 218844 109297 218844 109298 218844 109288 218845 109298 218845 109287 218845 109287 218846 109298 218846 109286 218846 109287 218847 109286 218847 109192 218847 109192 218848 109271 218848 109287 218848 109287 218849 109271 218849 109289 218849 109287 218850 109289 218850 109288 218850 109288 218851 109289 218851 109274 218851 109288 218852 109274 218852 109285 218852 109285 218853 109274 218853 109275 218853 109285 218854 109275 218854 109284 218854 109284 218855 109275 218855 109276 218855 109284 218856 109276 218856 109290 218856 109290 218857 109276 218857 109277 218857 109290 218858 109277 218858 109291 218858 109291 218859 109277 218859 109279 218859 109291 218860 109279 218860 109282 218860 109282 218861 109279 218861 109280 218861 109282 218862 109280 218862 109323 218862 109308 218863 109257 218863 109256 218863 109256 218864 109257 218864 109292 218864 109256 218865 109292 218865 109283 218865 109283 218866 109292 218866 109260 218866 109283 218867 109260 218867 109293 218867 109293 218868 109260 218868 109253 218868 109293 218869 109253 218869 109294 218869 109294 218870 109253 218870 109264 218870 109294 218871 109264 218871 109295 218871 109295 218872 109264 218872 109296 218872 109295 218873 109296 218873 109297 218873 109297 218874 109296 218874 109299 218874 109297 218875 109299 218875 109298 218875 109298 218876 109299 218876 109194 218876 109298 218877 109194 218877 109286 218877 109307 218878 109308 218878 109300 218878 109316 218879 109302 218879 109315 218879 109301 218880 109302 218880 109303 218880 109303 218881 109302 218881 109316 218881 109303 218882 109316 218882 109206 218882 109206 218883 109316 218883 109306 218883 109244 218884 109304 218884 109316 218884 109316 218885 109304 218885 109305 218885 109305 218886 109205 218886 109316 218886 109316 218887 109205 218887 109222 218887 109316 218888 109222 218888 109306 218888 109311 218889 109263 218889 109307 218889 109307 218890 109263 218890 109261 218890 109257 218891 109308 218891 109258 218891 109258 218892 109308 218892 109307 218892 109258 218893 109307 218893 109309 218893 109309 218894 109307 218894 109261 218894 109182 218895 109255 218895 109307 218895 109307 218896 109255 218896 109310 218896 109307 218897 109310 218897 109311 218897 109182 218898 109307 218898 109312 218898 109312 218899 109307 218899 109300 218899 109312 218900 109300 218900 109314 218900 109314 218901 109300 218901 109313 218901 109314 218902 109313 218902 109315 218902 109315 218903 109313 218903 109322 218903 109315 218904 109322 218904 109316 218904 109316 218905 109322 218905 109321 218905 109316 218906 109321 218906 109244 218906 109252 218907 109317 218907 109318 218907 109323 218908 109280 218908 109328 218908 109240 218909 109327 218909 109326 218909 109241 218910 109320 218910 109319 218910 109320 218911 109321 218911 109319 218911 109319 218912 109321 218912 109322 218912 109319 218913 109322 218913 109325 218913 109325 218914 109322 218914 109313 218914 109325 218915 109313 218915 109324 218915 109324 218916 109313 218916 109300 218916 109324 218917 109300 218917 109281 218917 109281 218918 109300 218918 109308 218918 109281 218919 109323 218919 109324 218919 109324 218920 109323 218920 109328 218920 109324 218921 109328 218921 109325 218921 109325 218922 109328 218922 109329 218922 109325 218923 109329 218923 109319 218923 109319 218924 109329 218924 109326 218924 109319 218925 109326 218925 109241 218925 109241 218926 109326 218926 109327 218926 109280 218927 109252 218927 109328 218927 109328 218928 109252 218928 109318 218928 109328 218929 109318 218929 109329 218929 109329 218930 109318 218930 109202 218930 109329 218931 109202 218931 109326 218931 109326 218932 109202 218932 109330 218932 109326 218933 109330 218933 109240 218933 109240 218934 109330 218934 109167 218934 109350 218935 109345 218935 109331 218935 109350 218936 109331 218936 109353 218936 109331 218937 109379 218937 109353 218937 109353 218938 109379 218938 109332 218938 109353 218939 109332 218939 109354 218939 109354 218940 109332 218940 109348 218940 109348 218941 109332 218941 109378 218941 109348 218942 109378 218942 109152 218942 109374 218943 109457 218943 109375 218943 109375 218944 109457 218944 109333 218944 109375 218945 109333 218945 109334 218945 109334 218946 109333 218946 109458 218946 109334 218947 109458 218947 109335 218947 109335 218948 109458 218948 109460 218948 109335 218949 109460 218949 109355 218949 109355 218950 109460 218950 109336 218950 109355 218951 109336 218951 109360 218951 109360 218952 109336 218952 109337 218952 109360 218953 109337 218953 109361 218953 109361 218954 109337 218954 109149 218954 109339 218955 109457 218955 109374 218955 109341 218956 109344 218956 109454 218956 109374 218957 109338 218957 109339 218957 109339 218958 109338 218958 109370 218958 109339 218959 109370 218959 109454 218959 109454 218960 109370 218960 109340 218960 109454 218961 109340 218961 109341 218961 109341 218962 109342 218962 109344 218962 109344 218963 109342 218963 109343 218963 109344 218964 109343 218964 109456 218964 109331 218965 109345 218965 109363 218965 109363 218966 109345 218966 109346 218966 109363 218967 109346 218967 109364 218967 109364 218968 109346 218968 109456 218968 109364 218969 109456 218969 109347 218969 109347 218970 109456 218970 109343 218970 109354 218971 109348 218971 109349 218971 109162 218972 109350 218972 109351 218972 109351 218973 109350 218973 109353 218973 109351 218974 109353 218974 109352 218974 109352 218975 109353 218975 109354 218975 109352 218976 109354 218976 109462 218976 109462 218977 109354 218977 109349 218977 109403 218978 109335 218978 109404 218978 109404 218979 109335 218979 109355 218979 109404 218980 109355 218980 109356 218980 109356 218981 109355 218981 109357 218981 109357 218982 109355 218982 109360 218982 109357 218983 109360 218983 109358 218983 109358 218984 109360 218984 109359 218984 109359 218985 109360 218985 109361 218985 109359 218986 109361 218986 109143 218986 109125 218987 109331 218987 109362 218987 109362 218988 109331 218988 109363 218988 109362 218989 109363 218989 109073 218989 109073 218990 109363 218990 109364 218990 109342 218991 109341 218991 109373 218991 109373 218992 109365 218992 109342 218992 109342 218993 109365 218993 109366 218993 109342 218994 109366 218994 109343 218994 109343 218995 109366 218995 109367 218995 109343 218996 109367 218996 109347 218996 109347 218997 109367 218997 109075 218997 109347 218998 109075 218998 109364 218998 109364 218999 109075 218999 109368 218999 109364 219000 109368 219000 109073 219000 109374 219001 109115 219001 109338 219001 109338 219002 109115 219002 109052 219002 109338 219003 109052 219003 109370 219003 109052 219004 109369 219004 109370 219004 109370 219005 109369 219005 109371 219005 109370 219006 109371 219006 109340 219006 109340 219007 109371 219007 109372 219007 109340 219008 109372 219008 109341 219008 109341 219009 109372 219009 109077 219009 109341 219010 109077 219010 109373 219010 109115 219011 109374 219011 109376 219011 109376 219012 109374 219012 109375 219012 109376 219013 109375 219013 109110 219013 109110 219014 109375 219014 109334 219014 109110 219015 109334 219015 109403 219015 109403 219016 109334 219016 109335 219016 109377 219017 109378 219017 109332 219017 109377 219018 109332 219018 109130 219018 109130 219019 109332 219019 109379 219019 109130 219020 109379 219020 109124 219020 109124 219021 109379 219021 109331 219021 109124 219022 109331 219022 109125 219022 109381 219023 109380 219023 109422 219023 109131 219024 109381 219024 109400 219024 109392 219025 109394 219025 109382 219025 109382 219026 109394 219026 109396 219026 109382 219027 109396 219027 109383 219027 109383 219028 109396 219028 109397 219028 109383 219029 109397 219029 109384 219029 109384 219030 109397 219030 109385 219030 109386 219031 109390 219031 109387 219031 109393 219032 109434 219032 109395 219032 109395 219033 109434 219033 109388 219033 109395 219034 109388 219034 109386 219034 109386 219035 109388 219035 109389 219035 109386 219036 109389 219036 109390 219036 109425 219037 109394 219037 109391 219037 109391 219038 109394 219038 109392 219038 109391 219039 109392 219039 109133 219039 109425 219040 109393 219040 109394 219040 109394 219041 109393 219041 109395 219041 109394 219042 109395 219042 109396 219042 109396 219043 109395 219043 109386 219043 109396 219044 109386 219044 109397 219044 109397 219045 109386 219045 109387 219045 109397 219046 109387 219046 109385 219046 109398 219047 109431 219047 109425 219047 109425 219048 109431 219048 109399 219048 109425 219049 109399 219049 109393 219049 109424 219050 109131 219050 109426 219050 109426 219051 109131 219051 109400 219051 109426 219052 109400 219052 109401 219052 109401 219053 109400 219053 109423 219053 109417 219054 109415 219054 109359 219054 109430 219055 109402 219055 109415 219055 109415 219056 109402 219056 109358 219056 109415 219057 109358 219057 109359 219057 109404 219058 109356 219058 109402 219058 109402 219059 109356 219059 109357 219059 109402 219060 109357 219060 109358 219060 109429 219061 109403 219061 109427 219061 109427 219062 109403 219062 109404 219062 109377 219063 109128 219063 109405 219063 109377 219064 109405 219064 109406 219064 109406 219065 109405 219065 109420 219065 109406 219066 109420 219066 109148 219066 109148 219067 109420 219067 109146 219067 109146 219068 109420 219068 109419 219068 109146 219069 109419 219069 109407 219069 109359 219070 109143 219070 109417 219070 109417 219071 109143 219071 109144 219071 109417 219072 109144 219072 109419 219072 109419 219073 109144 219073 109408 219073 109419 219074 109408 219074 109407 219074 109430 219075 109416 219075 109409 219075 109409 219076 109416 219076 109418 219076 109409 219077 109418 219077 109432 219077 109432 219078 109418 219078 109411 219078 109432 219079 109411 219079 109410 219079 109410 219080 109411 219080 109421 219080 109410 219081 109421 219081 109433 219081 109433 219082 109421 219082 109412 219082 109433 219083 109412 219083 109413 219083 109413 219084 109412 219084 109414 219084 109413 219085 109414 219085 109127 219085 109430 219086 109415 219086 109416 219086 109416 219087 109415 219087 109417 219087 109416 219088 109417 219088 109418 219088 109418 219089 109417 219089 109419 219089 109418 219090 109419 219090 109411 219090 109411 219091 109419 219091 109420 219091 109411 219092 109420 219092 109421 219092 109421 219093 109420 219093 109405 219093 109421 219094 109405 219094 109412 219094 109412 219095 109405 219095 109128 219095 109412 219096 109128 219096 109414 219096 109381 219097 109422 219097 109400 219097 109400 219098 109422 219098 109107 219098 109400 219099 109107 219099 109423 219099 109423 219100 109107 219100 109106 219100 109423 219101 109106 219101 109428 219101 109133 219102 109424 219102 109391 219102 109391 219103 109424 219103 109426 219103 109391 219104 109426 219104 109425 219104 109425 219105 109426 219105 109401 219105 109425 219106 109401 219106 109398 219106 109398 219107 109401 219107 109423 219107 109398 219108 109423 219108 109427 219108 109427 219109 109423 219109 109428 219109 109427 219110 109428 219110 109429 219110 109404 219111 109402 219111 109427 219111 109427 219112 109402 219112 109430 219112 109427 219113 109430 219113 109398 219113 109398 219114 109430 219114 109409 219114 109398 219115 109409 219115 109431 219115 109431 219116 109409 219116 109432 219116 109431 219117 109432 219117 109399 219117 109399 219118 109432 219118 109410 219118 109399 219119 109410 219119 109393 219119 109393 219120 109410 219120 109433 219120 109393 219121 109433 219121 109434 219121 109434 219122 109433 219122 109413 219122 109434 219123 109413 219123 109388 219123 109388 219124 109413 219124 109127 219124 109388 219125 109127 219125 109389 219125 109436 219126 109459 219126 109201 219126 109445 219127 109443 219127 109461 219127 109201 219128 109435 219128 109436 219128 109436 219129 109435 219129 109437 219129 109436 219130 109437 219130 109461 219130 109461 219131 109437 219131 109438 219131 109461 219132 109438 219132 109445 219132 109171 219133 109462 219133 109439 219133 109439 219134 109462 219134 109349 219134 109439 219135 109349 219135 109440 219135 109440 219136 109349 219136 109348 219136 109440 219137 109348 219137 109177 219137 109177 219138 109348 219138 109441 219138 109177 219139 109441 219139 109442 219139 109442 219140 109441 219140 109443 219140 109442 219141 109443 219141 109444 219141 109444 219142 109443 219142 109445 219142 109204 219143 109447 219143 109446 219143 109446 219144 109447 219144 109448 219144 109446 219145 109448 219145 109449 219145 109449 219146 109448 219146 109453 219146 109449 219147 109453 219147 109163 219147 109163 219148 109453 219148 109450 219148 109345 219149 109350 219149 109164 219149 109461 219150 109443 219150 109149 219150 109441 219151 109451 219151 109443 219151 109443 219152 109451 219152 109452 219152 109443 219153 109452 219153 109149 219153 109348 219154 109152 219154 109441 219154 109441 219155 109152 219155 109151 219155 109441 219156 109151 219156 109451 219156 109457 219157 109339 219157 109453 219157 109453 219158 109339 219158 109454 219158 109453 219159 109454 219159 109450 219159 109450 219160 109454 219160 109344 219160 109450 219161 109344 219161 109455 219161 109455 219162 109344 219162 109456 219162 109455 219163 109456 219163 109164 219163 109164 219164 109456 219164 109346 219164 109164 219165 109346 219165 109345 219165 109453 219166 109448 219166 109457 219166 109457 219167 109448 219167 109447 219167 109457 219168 109447 219168 109333 219168 109333 219169 109447 219169 109165 219169 109333 219170 109165 219170 109458 219170 109458 219171 109165 219171 109459 219171 109458 219172 109459 219172 109460 219172 109460 219173 109459 219173 109436 219173 109460 219174 109436 219174 109336 219174 109336 219175 109436 219175 109461 219175 109336 219176 109461 219176 109337 219176 109337 219177 109461 219177 109149 219177 109462 219178 109171 219178 109463 219178 109462 219179 109463 219179 109352 219179 109352 219180 109463 219180 109161 219180 109352 219181 109161 219181 109351 219181 109472 219182 109464 219182 109474 219182 109474 219183 109464 219183 109465 219183 109474 219184 109465 219184 109648 219184 109648 219185 109465 219185 109683 219185 109467 219186 109689 219186 109490 219186 109489 219187 109677 219187 109466 219187 109490 219188 109483 219188 109467 219188 109467 219189 109483 219189 109486 219189 109467 219190 109486 219190 109466 219190 109466 219191 109486 219191 109468 219191 109466 219192 109468 219192 109489 219192 109489 219193 109469 219193 109677 219193 109677 219194 109469 219194 109480 219194 109677 219195 109480 219195 109678 219195 109476 219196 109680 219196 109470 219196 109470 219197 109680 219197 109679 219197 109470 219198 109679 219198 109478 219198 109478 219199 109679 219199 109678 219199 109478 219200 109678 219200 109481 219200 109481 219201 109678 219201 109480 219201 109874 219202 109875 219202 109667 219202 109665 219203 109872 219203 109694 219203 109694 219204 109872 219204 109873 219204 109694 219205 109873 219205 109692 219205 109692 219206 109873 219206 109874 219206 109692 219207 109874 219207 109691 219207 109691 219208 109874 219208 109667 219208 109471 219209 109472 219209 109473 219209 109473 219210 109472 219210 109474 219210 109473 219211 109474 219211 109515 219211 109515 219212 109474 219212 109648 219212 109515 219213 109648 219213 109516 219213 109475 219214 109476 219214 109477 219214 109477 219215 109476 219215 109470 219215 109477 219216 109470 219216 109567 219216 109567 219217 109470 219217 109478 219217 109469 219218 109489 219218 109575 219218 109575 219219 109574 219219 109469 219219 109469 219220 109574 219220 109479 219220 109469 219221 109479 219221 109480 219221 109480 219222 109479 219222 109571 219222 109480 219223 109571 219223 109481 219223 109481 219224 109571 219224 109482 219224 109481 219225 109482 219225 109478 219225 109478 219226 109482 219226 109569 219226 109478 219227 109569 219227 109567 219227 109490 219228 109610 219228 109483 219228 109483 219229 109610 219229 109484 219229 109483 219230 109484 219230 109486 219230 109484 219231 109485 219231 109486 219231 109486 219232 109485 219232 109487 219232 109486 219233 109487 219233 109468 219233 109468 219234 109487 219234 109488 219234 109468 219235 109488 219235 109489 219235 109489 219236 109488 219236 109572 219236 109489 219237 109572 219237 109575 219237 109610 219238 109490 219238 109608 219238 109608 219239 109490 219239 109491 219239 109608 219240 109491 219240 109492 219240 109492 219241 109491 219241 109493 219241 109492 219242 109493 219242 109471 219242 109471 219243 109493 219243 109472 219243 109522 219244 109494 219244 109495 219244 109522 219245 109495 219245 109630 219245 109630 219246 109495 219246 109496 219246 109630 219247 109496 219247 109624 219247 109624 219248 109496 219248 109476 219248 109624 219249 109476 219249 109475 219249 109535 219250 109599 219250 109601 219250 109634 219251 109535 219251 109536 219251 109497 219252 109498 219252 109633 219252 109633 219253 109498 219253 109507 219253 109633 219254 109507 219254 109499 219254 109499 219255 109507 219255 109500 219255 109499 219256 109500 219256 109615 219256 109615 219257 109500 219257 109617 219257 109501 219258 109619 219258 109508 219258 109506 219259 109503 219259 109502 219259 109502 219260 109503 219260 109504 219260 109502 219261 109504 219261 109501 219261 109501 219262 109504 219262 109505 219262 109501 219263 109505 219263 109619 219263 109510 219264 109498 219264 109540 219264 109540 219265 109498 219265 109497 219265 109540 219266 109497 219266 109635 219266 109510 219267 109506 219267 109498 219267 109498 219268 109506 219268 109502 219268 109498 219269 109502 219269 109507 219269 109507 219270 109502 219270 109501 219270 109507 219271 109501 219271 109500 219271 109500 219272 109501 219272 109508 219272 109500 219273 109508 219273 109617 219273 109509 219274 109544 219274 109510 219274 109510 219275 109544 219275 109547 219275 109510 219276 109547 219276 109506 219276 109539 219277 109634 219277 109511 219277 109511 219278 109634 219278 109536 219278 109511 219279 109536 219279 109512 219279 109512 219280 109536 219280 109541 219280 109518 219281 109528 219281 109513 219281 109543 219282 109514 219282 109513 219282 109473 219283 109515 219283 109514 219283 109514 219284 109515 219284 109516 219284 109514 219285 109516 219285 109513 219285 109513 219286 109516 219286 109517 219286 109513 219287 109517 219287 109518 219287 109519 219288 109471 219288 109542 219288 109542 219289 109471 219289 109473 219289 109523 219290 109654 219290 109520 219290 109520 219291 109654 219291 109521 219291 109520 219292 109521 219292 109534 219292 109534 219293 109521 219293 109522 219293 109534 219294 109522 219294 109631 219294 109523 219295 109520 219295 109649 219295 109649 219296 109520 219296 109530 219296 109649 219297 109530 219297 109651 219297 109528 219298 109518 219298 109530 219298 109530 219299 109518 219299 109653 219299 109530 219300 109653 219300 109651 219300 109543 219301 109529 219301 109545 219301 109545 219302 109529 219302 109524 219302 109545 219303 109524 219303 109546 219303 109546 219304 109524 219304 109531 219304 109546 219305 109531 219305 109525 219305 109525 219306 109531 219306 109532 219306 109525 219307 109532 219307 109548 219307 109548 219308 109532 219308 109533 219308 109548 219309 109533 219309 109526 219309 109526 219310 109533 219310 109626 219310 109526 219311 109626 219311 109527 219311 109543 219312 109513 219312 109529 219312 109529 219313 109513 219313 109528 219313 109529 219314 109528 219314 109524 219314 109524 219315 109528 219315 109530 219315 109524 219316 109530 219316 109531 219316 109531 219317 109530 219317 109520 219317 109531 219318 109520 219318 109532 219318 109532 219319 109520 219319 109534 219319 109532 219320 109534 219320 109533 219320 109533 219321 109534 219321 109631 219321 109533 219322 109631 219322 109626 219322 109535 219323 109601 219323 109536 219323 109536 219324 109601 219324 109537 219324 109536 219325 109537 219325 109541 219325 109541 219326 109537 219326 109600 219326 109541 219327 109600 219327 109538 219327 109635 219328 109539 219328 109540 219328 109540 219329 109539 219329 109511 219329 109540 219330 109511 219330 109510 219330 109510 219331 109511 219331 109512 219331 109510 219332 109512 219332 109509 219332 109509 219333 109512 219333 109541 219333 109509 219334 109541 219334 109542 219334 109542 219335 109541 219335 109538 219335 109542 219336 109538 219336 109519 219336 109473 219337 109514 219337 109542 219337 109542 219338 109514 219338 109543 219338 109542 219339 109543 219339 109509 219339 109509 219340 109543 219340 109545 219340 109509 219341 109545 219341 109544 219341 109544 219342 109545 219342 109546 219342 109544 219343 109546 219343 109547 219343 109547 219344 109546 219344 109525 219344 109547 219345 109525 219345 109506 219345 109506 219346 109525 219346 109548 219346 109506 219347 109548 219347 109503 219347 109503 219348 109548 219348 109526 219348 109503 219349 109526 219349 109504 219349 109504 219350 109526 219350 109527 219350 109504 219351 109527 219351 109505 219351 109484 219352 109610 219352 109609 219352 109559 219353 109594 219353 109555 219353 109578 219354 109588 219354 109554 219354 109637 219355 109551 219355 109590 219355 109613 219356 109623 219356 109639 219356 109639 219357 109623 219357 109564 219357 109639 219358 109564 219358 109640 219358 109640 219359 109564 219359 109549 219359 109640 219360 109549 219360 109550 219360 109550 219361 109549 219361 109563 219361 109590 219362 109551 219362 109556 219362 109556 219363 109551 219363 109552 219363 109556 219364 109552 219364 109555 219364 109553 219365 109554 219365 109589 219365 109555 219366 109594 219366 109556 219366 109556 219367 109594 219367 109557 219367 109556 219368 109557 219368 109590 219368 109552 219369 109558 219369 109555 219369 109555 219370 109558 219370 109562 219370 109555 219371 109562 219371 109559 219371 109559 219372 109562 219372 109560 219372 109559 219373 109560 219373 109561 219373 109561 219374 109560 219374 109565 219374 109561 219375 109565 219375 109596 219375 109596 219376 109565 219376 109566 219376 109596 219377 109566 219377 109622 219377 109558 219378 109563 219378 109562 219378 109562 219379 109563 219379 109549 219379 109562 219380 109549 219380 109560 219380 109560 219381 109549 219381 109564 219381 109560 219382 109564 219382 109565 219382 109565 219383 109564 219383 109623 219383 109565 219384 109623 219384 109566 219384 109477 219385 109567 219385 109568 219385 109568 219386 109567 219386 109569 219386 109568 219387 109569 219387 109570 219387 109570 219388 109569 219388 109482 219388 109570 219389 109482 219389 109584 219389 109584 219390 109482 219390 109571 219390 109584 219391 109571 219391 109573 219391 109627 219392 109625 219392 109568 219392 109568 219393 109625 219393 109475 219393 109568 219394 109475 219394 109477 219394 109576 219395 109572 219395 109586 219395 109586 219396 109572 219396 109488 219396 109586 219397 109488 219397 109487 219397 109571 219398 109479 219398 109573 219398 109573 219399 109479 219399 109574 219399 109573 219400 109574 219400 109576 219400 109576 219401 109574 219401 109575 219401 109576 219402 109575 219402 109572 219402 109487 219403 109485 219403 109586 219403 109586 219404 109485 219404 109484 219404 109586 219405 109484 219405 109577 219405 109577 219406 109484 219406 109609 219406 109577 219407 109609 219407 109605 219407 109554 219408 109553 219408 109578 219408 109578 219409 109553 219409 109591 219409 109578 219410 109591 219410 109587 219410 109587 219411 109591 219411 109592 219411 109587 219412 109592 219412 109579 219412 109579 219413 109592 219413 109593 219413 109579 219414 109593 219414 109585 219414 109585 219415 109593 219415 109595 219415 109585 219416 109595 219416 109583 219416 109583 219417 109595 219417 109580 219417 109583 219418 109580 219418 109582 219418 109582 219419 109580 219419 109597 219419 109582 219420 109597 219420 109581 219420 109581 219421 109597 219421 109598 219421 109581 219422 109598 219422 109627 219422 109627 219423 109568 219423 109581 219423 109581 219424 109568 219424 109570 219424 109581 219425 109570 219425 109582 219425 109582 219426 109570 219426 109584 219426 109582 219427 109584 219427 109583 219427 109583 219428 109584 219428 109573 219428 109583 219429 109573 219429 109585 219429 109585 219430 109573 219430 109576 219430 109585 219431 109576 219431 109579 219431 109579 219432 109576 219432 109586 219432 109579 219433 109586 219433 109587 219433 109587 219434 109586 219434 109577 219434 109587 219435 109577 219435 109578 219435 109578 219436 109577 219436 109605 219436 109578 219437 109605 219437 109588 219437 109589 219438 109637 219438 109553 219438 109553 219439 109637 219439 109590 219439 109553 219440 109590 219440 109591 219440 109591 219441 109590 219441 109557 219441 109591 219442 109557 219442 109592 219442 109592 219443 109557 219443 109594 219443 109592 219444 109594 219444 109593 219444 109593 219445 109594 219445 109559 219445 109593 219446 109559 219446 109595 219446 109595 219447 109559 219447 109561 219447 109595 219448 109561 219448 109580 219448 109580 219449 109561 219449 109596 219449 109580 219450 109596 219450 109597 219450 109597 219451 109596 219451 109622 219451 109597 219452 109622 219452 109598 219452 109606 219453 109604 219453 109607 219453 109636 219454 109589 219454 109554 219454 109601 219455 109599 219455 109646 219455 109600 219456 109537 219456 109606 219456 109606 219457 109537 219457 109601 219457 109601 219458 109646 219458 109606 219458 109606 219459 109646 219459 109602 219459 109606 219460 109602 219460 109604 219460 109604 219461 109602 219461 109645 219461 109604 219462 109645 219462 109636 219462 109519 219463 109538 219463 109603 219463 109603 219464 109538 219464 109600 219464 109471 219465 109519 219465 109492 219465 109492 219466 109519 219466 109603 219466 109492 219467 109603 219467 109608 219467 109636 219468 109554 219468 109604 219468 109604 219469 109554 219469 109588 219469 109604 219470 109588 219470 109607 219470 109607 219471 109588 219471 109605 219471 109607 219472 109605 219472 109609 219472 109600 219473 109606 219473 109603 219473 109603 219474 109606 219474 109607 219474 109603 219475 109607 219475 109608 219475 109608 219476 109607 219476 109609 219476 109608 219477 109609 219477 109610 219477 109625 219478 109627 219478 109629 219478 109611 219479 109644 219479 109612 219479 109613 219480 109614 219480 109623 219480 109623 219481 109614 219481 109620 219481 109615 219482 109617 219482 109616 219482 109616 219483 109617 219483 109644 219483 109628 219484 109618 219484 109621 219484 109621 219485 109618 219485 109620 219485 109644 219486 109617 219486 109612 219486 109612 219487 109617 219487 109508 219487 109612 219488 109508 219488 109619 219488 109614 219489 109611 219489 109620 219489 109620 219490 109611 219490 109612 219490 109620 219491 109612 219491 109621 219491 109621 219492 109612 219492 109619 219492 109627 219493 109598 219493 109618 219493 109618 219494 109598 219494 109622 219494 109618 219495 109622 219495 109620 219495 109620 219496 109622 219496 109566 219496 109620 219497 109566 219497 109623 219497 109630 219498 109624 219498 109629 219498 109629 219499 109624 219499 109475 219499 109629 219500 109475 219500 109625 219500 109619 219501 109505 219501 109621 219501 109621 219502 109505 219502 109527 219502 109621 219503 109527 219503 109628 219503 109628 219504 109527 219504 109626 219504 109628 219505 109626 219505 109631 219505 109627 219506 109618 219506 109629 219506 109629 219507 109618 219507 109628 219507 109629 219508 109628 219508 109630 219508 109630 219509 109628 219509 109631 219509 109630 219510 109631 219510 109522 219510 109647 219511 109615 219511 109616 219511 109647 219512 109635 219512 109632 219512 109632 219513 109633 219513 109647 219513 109647 219514 109633 219514 109499 219514 109647 219515 109499 219515 109615 219515 109535 219516 109634 219516 109647 219516 109647 219517 109634 219517 109539 219517 109647 219518 109539 219518 109635 219518 109638 219519 109589 219519 109636 219519 109643 219520 109551 219520 109638 219520 109638 219521 109551 219521 109637 219521 109638 219522 109637 219522 109589 219522 109613 219523 109639 219523 109638 219523 109638 219524 109639 219524 109640 219524 109638 219525 109640 219525 109641 219525 109641 219526 109642 219526 109638 219526 109638 219527 109642 219527 109558 219527 109638 219528 109558 219528 109643 219528 109613 219529 109638 219529 109614 219529 109614 219530 109638 219530 109636 219530 109614 219531 109636 219531 109611 219531 109611 219532 109636 219532 109645 219532 109611 219533 109645 219533 109644 219533 109644 219534 109645 219534 109602 219534 109644 219535 109602 219535 109616 219535 109616 219536 109602 219536 109646 219536 109616 219537 109646 219537 109647 219537 109647 219538 109646 219538 109599 219538 109647 219539 109599 219539 109535 219539 109516 219540 109648 219540 109517 219540 109517 219541 109648 219541 109655 219541 109517 219542 109655 219542 109518 219542 109518 219543 109655 219543 109652 219543 109523 219544 109649 219544 109650 219544 109650 219545 109649 219545 109651 219545 109650 219546 109651 219546 109652 219546 109652 219547 109651 219547 109653 219547 109652 219548 109653 219548 109518 219548 109523 219549 109650 219549 109654 219549 109654 219550 109650 219550 109659 219550 109654 219551 109659 219551 109521 219551 109521 219552 109659 219552 109494 219552 109521 219553 109494 219553 109522 219553 109648 219554 109683 219554 109655 219554 109655 219555 109683 219555 109656 219555 109655 219556 109656 219556 109652 219556 109652 219557 109656 219557 109657 219557 109652 219558 109657 219558 109650 219558 109650 219559 109657 219559 109658 219559 109650 219560 109658 219560 109659 219560 109659 219561 109658 219561 109660 219561 109659 219562 109660 219562 109494 219562 109494 219563 109660 219563 109675 219563 109762 219564 109670 219564 109764 219564 109764 219565 109670 219565 109661 219565 109764 219566 109661 219566 109766 219566 109766 219567 109661 219567 109666 219567 109766 219568 109666 219568 109760 219568 109760 219569 109666 219569 109662 219569 109662 219570 109666 219570 109663 219570 109662 219571 109663 219571 109726 219571 109661 219572 109670 219572 109664 219572 109694 219573 109663 219573 109665 219573 109665 219574 109663 219574 109666 219574 109665 219575 109666 219575 109872 219575 109872 219576 109666 219576 109661 219576 109872 219577 109661 219577 109681 219577 109681 219578 109661 219578 109664 219578 109684 219579 109685 219579 109697 219579 109712 219580 109673 219580 109682 219580 109697 219581 109717 219581 109684 219581 109684 219582 109717 219582 109720 219582 109684 219583 109720 219583 109682 219583 109682 219584 109720 219584 109722 219584 109682 219585 109722 219585 109712 219585 109710 219586 109691 219586 109711 219586 109711 219587 109691 219587 109667 219587 109711 219588 109667 219588 109716 219588 109716 219589 109667 219589 109875 219589 109716 219590 109875 219590 109668 219590 109668 219591 109875 219591 109674 219591 109668 219592 109674 219592 109669 219592 109669 219593 109674 219593 109673 219593 109669 219594 109673 219594 109713 219594 109713 219595 109673 219595 109712 219595 109671 219596 109664 219596 109670 219596 109670 219597 109672 219597 109671 219597 109671 219598 109672 219598 109707 219598 109671 219599 109707 219599 109676 219599 109698 219600 109688 219600 109700 219600 109700 219601 109688 219601 109690 219601 109700 219602 109690 219602 109702 219602 109702 219603 109690 219603 109676 219603 109702 219604 109676 219604 109704 219604 109704 219605 109676 219605 109707 219605 109658 219606 109673 219606 109674 219606 109875 219607 109675 219607 109674 219607 109674 219608 109675 219608 109660 219608 109674 219609 109660 219609 109658 219609 109689 219610 109467 219610 109676 219610 109676 219611 109467 219611 109466 219611 109676 219612 109466 219612 109671 219612 109671 219613 109466 219613 109677 219613 109671 219614 109677 219614 109664 219614 109658 219615 109657 219615 109673 219615 109673 219616 109657 219616 109656 219616 109673 219617 109656 219617 109682 219617 109677 219618 109678 219618 109664 219618 109664 219619 109678 219619 109679 219619 109664 219620 109679 219620 109681 219620 109681 219621 109679 219621 109680 219621 109681 219622 109680 219622 109872 219622 109656 219623 109683 219623 109682 219623 109682 219624 109683 219624 109465 219624 109682 219625 109465 219625 109684 219625 109684 219626 109465 219626 109464 219626 109684 219627 109464 219627 109685 219627 109685 219628 109464 219628 109687 219628 109685 219629 109687 219629 109686 219629 109686 219630 109687 219630 109876 219630 109686 219631 109876 219631 109688 219631 109688 219632 109876 219632 109689 219632 109688 219633 109689 219633 109690 219633 109690 219634 109689 219634 109676 219634 109691 219635 109710 219635 109693 219635 109691 219636 109693 219636 109692 219636 109692 219637 109693 219637 109663 219637 109692 219638 109663 219638 109694 219638 109726 219639 109663 219639 109695 219639 109695 219640 109663 219640 109693 219640 109695 219641 109693 219641 109729 219641 109710 219642 109730 219642 109693 219642 109693 219643 109730 219643 109696 219643 109693 219644 109696 219644 109729 219644 109697 219645 109685 219645 109741 219645 109741 219646 109685 219646 109686 219646 109741 219647 109686 219647 109698 219647 109698 219648 109686 219648 109688 219648 109699 219649 109698 219649 109759 219649 109759 219650 109698 219650 109700 219650 109759 219651 109700 219651 109701 219651 109701 219652 109700 219652 109702 219652 109701 219653 109702 219653 109703 219653 109703 219654 109702 219654 109704 219654 109703 219655 109704 219655 109705 219655 109705 219656 109704 219656 109707 219656 109705 219657 109707 219657 109706 219657 109706 219658 109707 219658 109708 219658 109708 219659 109707 219659 109672 219659 109708 219660 109672 219660 109709 219660 109709 219661 109672 219661 109670 219661 109709 219662 109670 219662 109762 219662 109730 219663 109710 219663 109817 219663 109817 219664 109710 219664 109711 219664 109817 219665 109711 219665 109810 219665 109810 219666 109711 219666 109716 219666 109712 219667 109818 219667 109713 219667 109713 219668 109818 219668 109714 219668 109713 219669 109714 219669 109669 219669 109669 219670 109714 219670 109812 219670 109669 219671 109812 219671 109668 219671 109668 219672 109812 219672 109715 219672 109668 219673 109715 219673 109716 219673 109716 219674 109715 219674 109811 219674 109716 219675 109811 219675 109810 219675 109697 219676 109718 219676 109717 219676 109717 219677 109718 219677 109719 219677 109717 219678 109719 219678 109720 219678 109719 219679 109820 219679 109720 219679 109720 219680 109820 219680 109721 219680 109720 219681 109721 219681 109722 219681 109722 219682 109721 219682 109819 219682 109722 219683 109819 219683 109712 219683 109712 219684 109819 219684 109723 219684 109712 219685 109723 219685 109818 219685 109738 219686 109798 219686 109724 219686 109798 219687 109738 219687 109808 219687 109728 219688 109733 219688 109725 219688 109778 219689 109726 219689 109695 219689 109737 219690 109727 219690 109728 219690 109728 219691 109727 219691 109778 219691 109778 219692 109695 219692 109728 219692 109728 219693 109695 219693 109729 219693 109728 219694 109729 219694 109733 219694 109733 219695 109729 219695 109696 219695 109733 219696 109696 219696 109730 219696 109735 219697 109732 219697 109731 219697 109731 219698 109732 219698 109737 219698 109730 219699 109816 219699 109733 219699 109733 219700 109816 219700 109814 219700 109733 219701 109814 219701 109725 219701 109725 219702 109814 219702 109831 219702 109725 219703 109831 219703 109848 219703 109734 219704 109735 219704 109736 219704 109736 219705 109735 219705 109731 219705 109736 219706 109731 219706 109738 219706 109737 219707 109728 219707 109731 219707 109731 219708 109728 219708 109725 219708 109731 219709 109725 219709 109738 219709 109738 219710 109725 219710 109848 219710 109738 219711 109848 219711 109808 219711 109849 219712 109734 219712 109739 219712 109739 219713 109734 219713 109736 219713 109739 219714 109736 219714 109740 219714 109740 219715 109736 219715 109738 219715 109740 219716 109738 219716 109857 219716 109857 219717 109738 219717 109724 219717 109718 219718 109697 219718 109869 219718 109869 219719 109697 219719 109741 219719 109869 219720 109741 219720 109870 219720 109870 219721 109741 219721 109742 219721 109742 219722 109741 219722 109698 219722 109742 219723 109698 219723 109699 219723 109743 219724 109747 219724 109744 219724 109745 219725 109851 219725 109785 219725 109745 219726 109785 219726 109784 219726 109751 219727 109746 219727 109747 219727 109747 219728 109746 219728 109850 219728 109747 219729 109850 219729 109744 219729 109744 219730 109850 219730 109748 219730 109744 219731 109748 219731 109755 219731 109734 219732 109749 219732 109735 219732 109735 219733 109749 219733 109750 219733 109735 219734 109750 219734 109732 219734 109732 219735 109750 219735 109792 219735 109790 219736 109792 219736 109743 219736 109743 219737 109792 219737 109750 219737 109743 219738 109750 219738 109747 219738 109747 219739 109750 219739 109749 219739 109747 219740 109749 219740 109751 219740 109751 219741 109749 219741 109734 219741 109751 219742 109734 219742 109849 219742 109786 219743 109785 219743 109781 219743 109781 219744 109785 219744 109851 219744 109781 219745 109851 219745 109782 219745 109790 219746 109743 219746 109752 219746 109752 219747 109743 219747 109744 219747 109752 219748 109744 219748 109753 219748 109753 219749 109744 219749 109755 219749 109753 219750 109755 219750 109754 219750 109754 219751 109755 219751 109756 219751 109754 219752 109756 219752 109789 219752 109708 219753 109763 219753 109706 219753 109706 219754 109763 219754 109774 219754 109706 219755 109774 219755 109705 219755 109757 219756 109788 219756 109774 219756 109705 219757 109774 219757 109703 219757 109703 219758 109774 219758 109788 219758 109703 219759 109788 219759 109701 219759 109758 219760 109699 219760 109787 219760 109787 219761 109699 219761 109759 219761 109787 219762 109759 219762 109701 219762 109726 219763 109778 219763 109662 219763 109662 219764 109778 219764 109761 219764 109662 219765 109761 219765 109760 219765 109760 219766 109761 219766 109765 219766 109708 219767 109709 219767 109763 219767 109763 219768 109709 219768 109762 219768 109763 219769 109762 219769 109776 219769 109776 219770 109762 219770 109764 219770 109776 219771 109764 219771 109765 219771 109765 219772 109764 219772 109766 219772 109765 219773 109766 219773 109760 219773 109757 219774 109775 219774 109767 219774 109767 219775 109775 219775 109768 219775 109767 219776 109768 219776 109769 219776 109769 219777 109768 219777 109777 219777 109769 219778 109777 219778 109770 219778 109770 219779 109777 219779 109771 219779 109770 219780 109771 219780 109791 219780 109791 219781 109771 219781 109772 219781 109791 219782 109772 219782 109773 219782 109773 219783 109772 219783 109727 219783 109773 219784 109727 219784 109737 219784 109757 219785 109774 219785 109775 219785 109775 219786 109774 219786 109763 219786 109775 219787 109763 219787 109768 219787 109768 219788 109763 219788 109776 219788 109768 219789 109776 219789 109777 219789 109777 219790 109776 219790 109765 219790 109777 219791 109765 219791 109771 219791 109771 219792 109765 219792 109761 219792 109771 219793 109761 219793 109772 219793 109772 219794 109761 219794 109778 219794 109772 219795 109778 219795 109727 219795 109779 219796 109786 219796 109780 219796 109780 219797 109786 219797 109781 219797 109780 219798 109781 219798 109859 219798 109859 219799 109781 219799 109782 219799 109859 219800 109782 219800 109783 219800 109748 219801 109853 219801 109755 219801 109755 219802 109853 219802 109784 219802 109755 219803 109784 219803 109756 219803 109756 219804 109784 219804 109785 219804 109756 219805 109785 219805 109789 219805 109789 219806 109785 219806 109786 219806 109789 219807 109786 219807 109787 219807 109787 219808 109786 219808 109779 219808 109787 219809 109779 219809 109758 219809 109701 219810 109788 219810 109787 219810 109787 219811 109788 219811 109757 219811 109787 219812 109757 219812 109789 219812 109789 219813 109757 219813 109767 219813 109789 219814 109767 219814 109754 219814 109754 219815 109767 219815 109769 219815 109754 219816 109769 219816 109753 219816 109753 219817 109769 219817 109770 219817 109753 219818 109770 219818 109752 219818 109752 219819 109770 219819 109791 219819 109752 219820 109791 219820 109790 219820 109790 219821 109791 219821 109773 219821 109790 219822 109773 219822 109792 219822 109792 219823 109773 219823 109737 219823 109792 219824 109737 219824 109732 219824 109719 219825 109718 219825 109868 219825 109846 219826 109845 219826 109793 219826 109822 219827 109840 219827 109863 219827 109809 219828 109794 219828 109795 219828 109795 219829 109794 219829 109796 219829 109795 219830 109796 219830 109797 219830 109797 219831 109796 219831 109724 219831 109797 219832 109724 219832 109798 219832 109842 219833 109863 219833 109854 219833 109841 219834 109799 219834 109843 219834 109843 219835 109799 219835 109856 219835 109843 219836 109856 219836 109800 219836 109800 219837 109856 219837 109801 219837 109800 219838 109801 219838 109793 219838 109793 219839 109845 219839 109800 219839 109800 219840 109845 219840 109844 219840 109800 219841 109844 219841 109843 219841 109801 219842 109802 219842 109793 219842 109793 219843 109802 219843 109803 219843 109793 219844 109803 219844 109846 219844 109846 219845 109803 219845 109804 219845 109846 219846 109804 219846 109805 219846 109805 219847 109804 219847 109807 219847 109805 219848 109807 219848 109806 219848 109806 219849 109807 219849 109808 219849 109806 219850 109808 219850 109848 219850 109802 219851 109809 219851 109803 219851 109803 219852 109809 219852 109795 219852 109803 219853 109795 219853 109804 219853 109804 219854 109795 219854 109797 219854 109804 219855 109797 219855 109807 219855 109807 219856 109797 219856 109798 219856 109807 219857 109798 219857 109808 219857 109817 219858 109810 219858 109815 219858 109815 219859 109810 219859 109811 219859 109815 219860 109811 219860 109832 219860 109832 219861 109811 219861 109715 219861 109832 219862 109715 219862 109834 219862 109834 219863 109715 219863 109812 219863 109834 219864 109812 219864 109813 219864 109814 219865 109816 219865 109815 219865 109815 219866 109816 219866 109730 219866 109815 219867 109730 219867 109817 219867 109812 219868 109714 219868 109813 219868 109813 219869 109714 219869 109818 219869 109813 219870 109818 219870 109835 219870 109835 219871 109818 219871 109723 219871 109835 219872 109723 219872 109837 219872 109837 219873 109723 219873 109819 219873 109837 219874 109819 219874 109721 219874 109721 219875 109820 219875 109837 219875 109837 219876 109820 219876 109719 219876 109837 219877 109719 219877 109821 219877 109821 219878 109719 219878 109868 219878 109821 219879 109868 219879 109839 219879 109863 219880 109842 219880 109822 219880 109822 219881 109842 219881 109823 219881 109822 219882 109823 219882 109838 219882 109838 219883 109823 219883 109824 219883 109838 219884 109824 219884 109836 219884 109836 219885 109824 219885 109825 219885 109836 219886 109825 219886 109826 219886 109826 219887 109825 219887 109847 219887 109826 219888 109847 219888 109827 219888 109827 219889 109847 219889 109828 219889 109827 219890 109828 219890 109833 219890 109833 219891 109828 219891 109829 219891 109833 219892 109829 219892 109830 219892 109830 219893 109829 219893 109831 219893 109830 219894 109831 219894 109814 219894 109814 219895 109815 219895 109830 219895 109830 219896 109815 219896 109832 219896 109830 219897 109832 219897 109833 219897 109833 219898 109832 219898 109834 219898 109833 219899 109834 219899 109827 219899 109827 219900 109834 219900 109813 219900 109827 219901 109813 219901 109826 219901 109826 219902 109813 219902 109835 219902 109826 219903 109835 219903 109836 219903 109836 219904 109835 219904 109837 219904 109836 219905 109837 219905 109838 219905 109838 219906 109837 219906 109821 219906 109838 219907 109821 219907 109822 219907 109822 219908 109821 219908 109839 219908 109822 219909 109839 219909 109840 219909 109854 219910 109841 219910 109842 219910 109842 219911 109841 219911 109843 219911 109842 219912 109843 219912 109823 219912 109823 219913 109843 219913 109844 219913 109823 219914 109844 219914 109824 219914 109824 219915 109844 219915 109845 219915 109824 219916 109845 219916 109825 219916 109825 219917 109845 219917 109846 219917 109825 219918 109846 219918 109847 219918 109847 219919 109846 219919 109805 219919 109847 219920 109805 219920 109828 219920 109828 219921 109805 219921 109806 219921 109828 219922 109806 219922 109829 219922 109829 219923 109806 219923 109848 219923 109829 219924 109848 219924 109831 219924 109855 219925 109854 219925 109862 219925 109852 219926 109849 219926 109739 219926 109751 219927 109849 219927 109746 219927 109746 219928 109849 219928 109852 219928 109746 219929 109852 219929 109850 219929 109850 219930 109852 219930 109748 219930 109782 219931 109851 219931 109852 219931 109852 219932 109851 219932 109745 219932 109745 219933 109784 219933 109852 219933 109852 219934 109784 219934 109853 219934 109852 219935 109853 219935 109748 219935 109809 219936 109802 219936 109855 219936 109855 219937 109802 219937 109801 219937 109841 219938 109854 219938 109799 219938 109799 219939 109854 219939 109855 219939 109799 219940 109855 219940 109856 219940 109856 219941 109855 219941 109801 219941 109724 219942 109796 219942 109855 219942 109855 219943 109796 219943 109794 219943 109855 219944 109794 219944 109809 219944 109724 219945 109855 219945 109857 219945 109857 219946 109855 219946 109862 219946 109857 219947 109862 219947 109740 219947 109740 219948 109862 219948 109861 219948 109740 219949 109861 219949 109739 219949 109739 219950 109861 219950 109858 219950 109739 219951 109858 219951 109852 219951 109852 219952 109858 219952 109783 219952 109852 219953 109783 219953 109782 219953 109868 219954 109718 219954 109869 219954 109840 219955 109839 219955 109865 219955 109758 219956 109779 219956 109871 219956 109780 219957 109859 219957 109866 219957 109859 219958 109783 219958 109866 219958 109866 219959 109783 219959 109858 219959 109866 219960 109858 219960 109860 219960 109860 219961 109858 219961 109861 219961 109860 219962 109861 219962 109864 219962 109864 219963 109861 219963 109862 219963 109864 219964 109862 219964 109863 219964 109863 219965 109862 219965 109854 219965 109863 219966 109840 219966 109864 219966 109864 219967 109840 219967 109865 219967 109864 219968 109865 219968 109860 219968 109860 219969 109865 219969 109867 219969 109860 219970 109867 219970 109866 219970 109866 219971 109867 219971 109871 219971 109866 219972 109871 219972 109780 219972 109780 219973 109871 219973 109779 219973 109839 219974 109868 219974 109865 219974 109865 219975 109868 219975 109869 219975 109865 219976 109869 219976 109867 219976 109867 219977 109869 219977 109870 219977 109867 219978 109870 219978 109871 219978 109871 219979 109870 219979 109742 219979 109871 219980 109742 219980 109758 219980 109758 219981 109742 219981 109699 219981 109872 219982 109680 219982 109476 219982 109872 219983 109476 219983 109873 219983 109476 219984 109496 219984 109873 219984 109873 219985 109496 219985 109495 219985 109873 219986 109495 219986 109874 219986 109874 219987 109495 219987 109875 219987 109875 219988 109495 219988 109494 219988 109875 219989 109494 219989 109675 219989 109490 219990 109689 219990 109491 219990 109491 219991 109689 219991 109876 219991 109491 219992 109876 219992 109493 219992 109493 219993 109876 219993 109687 219993 109493 219994 109687 219994 109472 219994 109472 219995 109687 219995 109464 219995 109881 219996 109877 219996 110067 219996 110067 219997 109877 219997 109878 219997 110067 219998 109878 219998 109879 219998 109882 219999 110089 219999 109893 219999 109893 220000 110089 220000 109880 220000 109893 220001 109880 220001 109891 220001 109891 220002 109880 220002 110091 220002 109891 220003 110091 220003 109890 220003 109890 220004 110091 220004 110093 220004 109890 220005 110093 220005 109881 220005 109881 220006 110093 220006 110087 220006 109881 220007 110087 220007 109877 220007 109882 220008 109893 220008 110088 220008 110088 220009 109893 220009 109883 220009 110088 220010 109883 220010 109884 220010 109884 220011 109883 220011 109888 220011 109884 220012 109888 220012 110110 220012 110110 220013 109888 220013 109885 220013 110110 220014 109885 220014 109886 220014 109886 220015 109885 220015 110050 220015 109886 220016 110050 220016 110084 220016 110244 220017 110050 220017 109887 220017 109887 220018 110050 220018 109885 220018 109887 220019 109885 220019 110242 220019 109885 220020 109888 220020 110242 220020 110242 220021 109888 220021 109883 220021 110242 220022 109883 220022 110245 220022 110245 220023 109883 220023 109893 220023 110245 220024 109893 220024 109892 220024 110067 220025 110055 220025 109881 220025 109881 220026 110055 220026 109889 220026 109881 220027 109889 220027 109890 220027 109890 220028 109889 220028 109892 220028 109890 220029 109892 220029 109891 220029 109891 220030 109892 220030 109893 220030 110280 220031 109894 220031 109947 220031 109947 220032 109894 220032 109895 220032 109947 220033 109895 220033 109945 220033 109945 220034 109895 220034 110260 220034 109945 220035 110260 220035 109943 220035 109894 220036 110062 220036 109895 220036 109895 220037 110062 220037 109896 220037 109895 220038 109896 220038 110260 220038 110260 220039 109896 220039 110063 220039 109910 220040 109897 220040 110024 220040 109897 220041 109910 220041 109982 220041 109898 220042 109900 220042 109907 220042 109944 220043 109943 220043 109899 220043 109951 220044 109959 220044 109898 220044 109898 220045 109959 220045 109944 220045 109944 220046 109899 220046 109898 220046 109898 220047 109899 220047 110262 220047 109898 220048 110262 220048 109900 220048 109900 220049 110262 220049 109901 220049 109900 220050 109901 220050 109902 220050 109905 220051 109922 220051 109906 220051 109906 220052 109922 220052 109951 220052 109902 220053 109991 220053 109900 220053 109900 220054 109991 220054 110008 220054 109900 220055 110008 220055 109907 220055 109907 220056 110008 220056 109903 220056 109907 220057 109903 220057 109908 220057 109904 220058 109905 220058 109909 220058 109909 220059 109905 220059 109906 220059 109909 220060 109906 220060 109910 220060 109951 220061 109898 220061 109906 220061 109906 220062 109898 220062 109907 220062 109906 220063 109907 220063 109910 220063 109910 220064 109907 220064 109908 220064 109910 220065 109908 220065 109982 220065 109927 220066 109904 220066 110030 220066 110030 220067 109904 220067 109909 220067 110030 220068 109909 220068 110029 220068 110029 220069 109909 220069 109910 220069 110029 220070 109910 220070 110025 220070 110025 220071 109910 220071 110024 220071 109911 220072 110288 220072 110287 220072 109911 220073 110287 220073 109913 220073 109913 220074 110287 220074 109912 220074 109913 220075 109912 220075 109915 220075 109915 220076 109912 220076 109914 220076 109915 220077 109914 220077 109916 220077 109929 220078 109918 220078 109930 220078 109917 220079 110020 220079 109941 220079 109917 220080 109941 220080 109940 220080 109926 220081 110018 220081 109918 220081 109918 220082 110018 220082 109919 220082 109918 220083 109919 220083 109930 220083 109930 220084 109919 220084 109920 220084 109930 220085 109920 220085 109938 220085 109904 220086 109921 220086 109905 220086 109905 220087 109921 220087 109923 220087 109905 220088 109923 220088 109922 220088 109922 220089 109923 220089 109924 220089 109925 220090 109924 220090 109929 220090 109929 220091 109924 220091 109923 220091 109929 220092 109923 220092 109918 220092 109918 220093 109923 220093 109921 220093 109918 220094 109921 220094 109926 220094 109926 220095 109921 220095 109904 220095 109926 220096 109904 220096 109927 220096 109960 220097 109941 220097 109928 220097 109928 220098 109941 220098 110020 220098 109928 220099 110020 220099 109961 220099 109925 220100 109929 220100 109967 220100 109967 220101 109929 220101 109930 220101 109967 220102 109930 220102 109931 220102 109931 220103 109930 220103 109938 220103 109931 220104 109938 220104 109932 220104 109932 220105 109938 220105 109939 220105 109932 220106 109939 220106 109942 220106 110265 220107 109953 220107 110267 220107 110267 220108 109953 220108 109952 220108 110267 220109 109952 220109 110269 220109 109963 220110 109933 220110 109952 220110 109934 220111 109935 220111 109936 220111 109936 220112 109935 220112 109962 220112 110269 220113 109952 220113 110272 220113 110272 220114 109952 220114 109933 220114 110272 220115 109933 220115 109962 220115 109920 220116 109937 220116 109938 220116 109938 220117 109937 220117 109940 220117 109938 220118 109940 220118 109939 220118 109939 220119 109940 220119 109941 220119 109939 220120 109941 220120 109942 220120 109942 220121 109941 220121 109960 220121 109942 220122 109960 220122 109936 220122 109943 220123 109944 220123 109945 220123 109945 220124 109944 220124 109946 220124 109948 220125 110278 220125 109956 220125 109956 220126 110278 220126 110280 220126 109956 220127 110280 220127 109946 220127 109946 220128 110280 220128 109947 220128 109946 220129 109947 220129 109945 220129 110265 220130 110274 220130 109953 220130 109953 220131 110274 220131 110275 220131 109953 220132 110275 220132 109948 220132 109948 220133 110275 220133 110276 220133 109948 220134 110276 220134 110278 220134 109963 220135 109949 220135 109964 220135 109964 220136 109949 220136 109954 220136 109964 220137 109954 220137 109965 220137 109965 220138 109954 220138 109955 220138 109965 220139 109955 220139 109966 220139 109966 220140 109955 220140 109957 220140 109966 220141 109957 220141 109950 220141 109950 220142 109957 220142 109958 220142 109950 220143 109958 220143 109968 220143 109968 220144 109958 220144 109959 220144 109968 220145 109959 220145 109951 220145 109963 220146 109952 220146 109949 220146 109949 220147 109952 220147 109953 220147 109949 220148 109953 220148 109954 220148 109954 220149 109953 220149 109948 220149 109954 220150 109948 220150 109955 220150 109955 220151 109948 220151 109956 220151 109955 220152 109956 220152 109957 220152 109957 220153 109956 220153 109946 220153 109957 220154 109946 220154 109958 220154 109958 220155 109946 220155 109944 220155 109958 220156 109944 220156 109959 220156 109916 220157 109934 220157 110046 220157 110046 220158 109934 220158 109936 220158 110046 220159 109936 220159 110032 220159 110032 220160 109936 220160 109960 220160 110032 220161 109960 220161 110042 220161 110042 220162 109960 220162 109928 220162 110042 220163 109928 220163 110033 220163 110033 220164 109928 220164 109961 220164 110033 220165 109961 220165 110034 220165 109962 220166 109933 220166 109936 220166 109936 220167 109933 220167 109963 220167 109936 220168 109963 220168 109942 220168 109942 220169 109963 220169 109964 220169 109942 220170 109964 220170 109932 220170 109932 220171 109964 220171 109965 220171 109932 220172 109965 220172 109931 220172 109931 220173 109965 220173 109966 220173 109931 220174 109966 220174 109967 220174 109967 220175 109966 220175 109950 220175 109967 220176 109950 220176 109925 220176 109925 220177 109950 220177 109968 220177 109925 220178 109968 220178 109924 220178 109924 220179 109968 220179 109951 220179 109924 220180 109951 220180 109922 220180 109998 220181 110288 220181 110043 220181 110016 220182 109975 220182 109978 220182 110000 220183 110039 220183 110038 220183 109969 220184 109970 220184 109986 220184 109986 220185 109970 220185 109971 220185 109986 220186 109971 220186 109972 220186 109972 220187 109971 220187 110024 220187 109972 220188 110024 220188 109897 220188 110013 220189 110038 220189 110022 220189 109973 220190 110021 220190 110014 220190 110014 220191 110021 220191 109974 220191 110014 220192 109974 220192 109977 220192 109977 220193 109974 220193 110023 220193 109977 220194 110023 220194 109978 220194 109978 220195 109975 220195 109977 220195 109977 220196 109975 220196 109976 220196 109977 220197 109976 220197 110014 220197 110023 220198 109983 220198 109978 220198 109978 220199 109983 220199 109984 220199 109978 220200 109984 220200 110016 220200 110016 220201 109984 220201 109985 220201 110016 220202 109985 220202 109979 220202 109979 220203 109985 220203 109981 220203 109979 220204 109981 220204 109980 220204 109980 220205 109981 220205 109982 220205 109980 220206 109982 220206 109908 220206 109983 220207 109969 220207 109984 220207 109984 220208 109969 220208 109986 220208 109984 220209 109986 220209 109985 220209 109985 220210 109986 220210 109972 220210 109985 220211 109972 220211 109981 220211 109981 220212 109972 220212 109897 220212 109981 220213 109897 220213 109982 220213 110281 220214 110283 220214 109992 220214 109992 220215 110283 220215 109987 220215 109992 220216 109987 220216 110009 220216 110009 220217 109987 220217 109989 220217 110009 220218 109989 220218 109988 220218 109988 220219 109989 220219 109990 220219 109988 220220 109990 220220 109993 220220 110008 220221 109991 220221 109992 220221 109992 220222 109991 220222 109902 220222 109992 220223 109902 220223 110281 220223 109990 220224 110285 220224 109993 220224 109993 220225 110285 220225 109994 220225 109993 220226 109994 220226 109995 220226 109995 220227 109994 220227 110293 220227 109995 220228 110293 220228 109997 220228 109997 220229 110293 220229 109996 220229 109997 220230 109996 220230 110291 220230 110291 220231 110289 220231 109997 220231 109997 220232 110289 220232 109998 220232 109997 220233 109998 220233 110012 220233 110012 220234 109998 220234 110043 220234 110012 220235 110043 220235 110031 220235 110038 220236 110013 220236 110000 220236 110000 220237 110013 220237 109999 220237 110000 220238 109999 220238 110001 220238 110001 220239 109999 220239 110003 220239 110001 220240 110003 220240 110002 220240 110002 220241 110003 220241 110015 220241 110002 220242 110015 220242 110004 220242 110004 220243 110015 220243 110005 220243 110004 220244 110005 220244 110011 220244 110011 220245 110005 220245 110017 220245 110011 220246 110017 220246 110010 220246 110010 220247 110017 220247 110006 220247 110010 220248 110006 220248 110007 220248 110007 220249 110006 220249 109903 220249 110007 220250 109903 220250 110008 220250 110008 220251 109992 220251 110007 220251 110007 220252 109992 220252 110009 220252 110007 220253 110009 220253 110010 220253 110010 220254 110009 220254 109988 220254 110010 220255 109988 220255 110011 220255 110011 220256 109988 220256 109993 220256 110011 220257 109993 220257 110004 220257 110004 220258 109993 220258 109995 220258 110004 220259 109995 220259 110002 220259 110002 220260 109995 220260 109997 220260 110002 220261 109997 220261 110001 220261 110001 220262 109997 220262 110012 220262 110001 220263 110012 220263 110000 220263 110000 220264 110012 220264 110031 220264 110000 220265 110031 220265 110039 220265 110022 220266 109973 220266 110013 220266 110013 220267 109973 220267 110014 220267 110013 220268 110014 220268 109999 220268 109999 220269 110014 220269 109976 220269 109999 220270 109976 220270 110003 220270 110003 220271 109976 220271 109975 220271 110003 220272 109975 220272 110015 220272 110015 220273 109975 220273 110016 220273 110015 220274 110016 220274 110005 220274 110005 220275 110016 220275 109979 220275 110005 220276 109979 220276 110017 220276 110017 220277 109979 220277 109980 220277 110017 220278 109980 220278 110006 220278 110006 220279 109980 220279 109908 220279 110006 220280 109908 220280 109903 220280 110026 220281 110022 220281 110027 220281 110019 220282 109927 220282 110030 220282 109926 220283 109927 220283 110018 220283 110018 220284 109927 220284 110019 220284 110018 220285 110019 220285 109919 220285 109919 220286 110019 220286 109920 220286 109961 220287 110020 220287 110019 220287 110019 220288 110020 220288 109917 220288 109917 220289 109940 220289 110019 220289 110019 220290 109940 220290 109937 220290 110019 220291 109937 220291 109920 220291 109969 220292 109983 220292 110026 220292 110026 220293 109983 220293 110023 220293 109973 220294 110022 220294 110021 220294 110021 220295 110022 220295 110026 220295 110021 220296 110026 220296 109974 220296 109974 220297 110026 220297 110023 220297 110024 220298 109971 220298 110026 220298 110026 220299 109971 220299 109970 220299 110026 220300 109970 220300 109969 220300 110024 220301 110026 220301 110025 220301 110025 220302 110026 220302 110027 220302 110025 220303 110027 220303 110029 220303 110029 220304 110027 220304 110028 220304 110029 220305 110028 220305 110030 220305 110030 220306 110028 220306 110036 220306 110030 220307 110036 220307 110019 220307 110019 220308 110036 220308 110034 220308 110019 220309 110034 220309 109961 220309 110043 220310 110288 220310 109911 220310 110039 220311 110031 220311 110040 220311 110046 220312 110032 220312 110045 220312 110042 220313 110033 220313 110035 220313 110033 220314 110034 220314 110035 220314 110035 220315 110034 220315 110036 220315 110035 220316 110036 220316 110041 220316 110041 220317 110036 220317 110028 220317 110041 220318 110028 220318 110037 220318 110037 220319 110028 220319 110027 220319 110037 220320 110027 220320 110038 220320 110038 220321 110027 220321 110022 220321 110038 220322 110039 220322 110037 220322 110037 220323 110039 220323 110040 220323 110037 220324 110040 220324 110041 220324 110041 220325 110040 220325 110044 220325 110041 220326 110044 220326 110035 220326 110035 220327 110044 220327 110045 220327 110035 220328 110045 220328 110042 220328 110042 220329 110045 220329 110032 220329 110031 220330 110043 220330 110040 220330 110040 220331 110043 220331 109911 220331 110040 220332 109911 220332 110044 220332 110044 220333 109911 220333 109913 220333 110044 220334 109913 220334 110045 220334 110045 220335 109913 220335 109915 220335 110045 220336 109915 220336 110046 220336 110046 220337 109915 220337 109916 220337 110064 220338 110252 220338 110047 220338 110064 220339 110047 220339 110048 220339 110047 220340 110085 220340 110048 220340 110048 220341 110085 220341 110049 220341 110048 220342 110049 220342 110066 220342 110066 220343 110049 220343 110051 220343 110051 220344 110049 220344 110050 220344 110051 220345 110050 220345 110244 220345 110081 220346 110052 220346 110082 220346 110082 220347 110052 220347 110053 220347 110082 220348 110053 220348 110054 220348 110054 220349 110053 220349 110255 220349 110054 220350 110255 220350 110083 220350 110083 220351 110255 220351 110253 220351 110083 220352 110253 220352 110067 220352 110067 220353 110253 220353 110055 220353 110247 220354 110052 220354 110081 220354 110058 220355 110059 220355 110248 220355 110081 220356 110056 220356 110247 220356 110247 220357 110056 220357 110057 220357 110247 220358 110057 220358 110248 220358 110248 220359 110057 220359 110078 220359 110248 220360 110078 220360 110058 220360 110058 220361 110071 220361 110059 220361 110059 220362 110071 220362 110060 220362 110059 220363 110060 220363 110250 220363 110047 220364 110252 220364 110068 220364 110068 220365 110252 220365 110251 220365 110068 220366 110251 220366 110074 220366 110074 220367 110251 220367 110250 220367 110074 220368 110250 220368 110072 220368 110072 220369 110250 220369 110060 220369 110066 220370 110051 220370 110061 220370 110063 220371 109896 220371 110062 220371 110062 220372 110064 220372 110063 220372 110063 220373 110064 220373 110048 220373 110063 220374 110048 220374 110065 220374 110065 220375 110048 220375 110066 220375 110065 220376 110066 220376 110258 220376 110258 220377 110066 220377 110061 220377 110067 220378 109879 220378 110083 220378 110083 220379 109879 220379 110194 220379 110159 220380 110047 220380 110161 220380 110161 220381 110047 220381 110068 220381 110161 220382 110068 220382 110154 220382 110154 220383 110068 220383 110074 220383 110071 220384 110058 220384 110069 220384 110069 220385 110070 220385 110071 220385 110071 220386 110070 220386 110162 220386 110071 220387 110162 220387 110060 220387 110060 220388 110162 220388 110073 220388 110060 220389 110073 220389 110072 220389 110072 220390 110073 220390 110156 220390 110072 220391 110156 220391 110074 220391 110074 220392 110156 220392 110075 220392 110074 220393 110075 220393 110154 220393 110081 220394 110076 220394 110056 220394 110056 220395 110076 220395 110136 220395 110056 220396 110136 220396 110057 220396 110136 220397 110164 220397 110057 220397 110057 220398 110164 220398 110077 220398 110057 220399 110077 220399 110078 220399 110078 220400 110077 220400 110079 220400 110078 220401 110079 220401 110058 220401 110058 220402 110079 220402 110080 220402 110058 220403 110080 220403 110069 220403 110076 220404 110081 220404 110197 220404 110197 220405 110081 220405 110082 220405 110197 220406 110082 220406 110195 220406 110195 220407 110082 220407 110054 220407 110195 220408 110054 220408 110194 220408 110194 220409 110054 220409 110083 220409 110084 220410 110050 220410 110049 220410 110084 220411 110049 220411 110211 220411 110211 220412 110049 220412 110085 220412 110211 220413 110085 220413 110086 220413 110086 220414 110085 220414 110047 220414 110086 220415 110047 220415 110159 220415 110094 220416 110232 220416 110122 220416 109877 220417 110087 220417 110117 220417 109882 220418 110088 220418 110120 220418 110120 220419 110088 220419 109884 220419 110120 220420 109884 220420 110111 220420 109882 220421 110120 220421 110089 220421 110089 220422 110120 220422 110090 220422 110089 220423 110090 220423 109880 220423 109880 220424 110090 220424 110092 220424 109880 220425 110092 220425 110091 220425 110117 220426 110087 220426 110092 220426 110092 220427 110087 220427 110093 220427 110092 220428 110093 220428 110091 220428 109878 220429 109877 220429 110118 220429 110194 220430 109879 220430 110196 220430 110196 220431 109879 220431 110126 220431 110108 220432 110094 220432 110109 220432 110220 220433 110095 220433 110221 220433 110221 220434 110095 220434 110096 220434 110221 220435 110096 220435 110222 220435 110222 220436 110096 220436 110097 220436 110222 220437 110097 220437 110204 220437 110204 220438 110097 220438 110206 220438 110103 220439 110212 220439 110104 220439 110133 220440 110098 220440 110102 220440 110102 220441 110098 220441 110099 220441 110102 220442 110099 220442 110103 220442 110103 220443 110099 220443 110213 220443 110103 220444 110213 220444 110212 220444 110100 220445 110095 220445 110101 220445 110101 220446 110095 220446 110220 220446 110101 220447 110220 220447 110223 220447 110100 220448 110133 220448 110095 220448 110095 220449 110133 220449 110102 220449 110095 220450 110102 220450 110096 220450 110096 220451 110102 220451 110103 220451 110096 220452 110103 220452 110097 220452 110097 220453 110103 220453 110104 220453 110097 220454 110104 220454 110206 220454 110124 220455 110130 220455 110100 220455 110100 220456 110130 220456 110105 220456 110100 220457 110105 220457 110133 220457 110106 220458 110108 220458 110107 220458 110107 220459 110108 220459 110109 220459 110107 220460 110109 220460 110125 220460 110125 220461 110109 220461 110127 220461 109884 220462 110110 220462 110111 220462 110111 220463 110110 220463 109886 220463 110111 220464 109886 220464 110121 220464 110121 220465 109886 220465 110084 220465 110121 220466 110084 220466 110219 220466 110118 220467 110119 220467 110129 220467 110129 220468 110119 220468 110112 220468 110129 220469 110112 220469 110131 220469 110131 220470 110112 220470 110113 220470 110131 220471 110113 220471 110132 220471 110132 220472 110113 220472 110114 220472 110132 220473 110114 220473 110134 220473 110134 220474 110114 220474 110115 220474 110134 220475 110115 220475 110135 220475 110135 220476 110115 220476 110116 220476 110135 220477 110116 220477 110215 220477 109877 220478 110117 220478 110118 220478 110118 220479 110117 220479 110092 220479 110118 220480 110092 220480 110119 220480 110119 220481 110092 220481 110090 220481 110119 220482 110090 220482 110112 220482 110112 220483 110090 220483 110120 220483 110112 220484 110120 220484 110113 220484 110113 220485 110120 220485 110111 220485 110113 220486 110111 220486 110114 220486 110114 220487 110111 220487 110121 220487 110114 220488 110121 220488 110115 220488 110115 220489 110121 220489 110219 220489 110115 220490 110219 220490 110116 220490 110094 220491 110122 220491 110109 220491 110109 220492 110122 220492 110123 220492 110109 220493 110123 220493 110127 220493 110127 220494 110123 220494 110193 220494 110127 220495 110193 220495 110128 220495 110223 220496 110106 220496 110101 220496 110101 220497 110106 220497 110107 220497 110101 220498 110107 220498 110100 220498 110100 220499 110107 220499 110125 220499 110100 220500 110125 220500 110124 220500 110124 220501 110125 220501 110127 220501 110124 220502 110127 220502 110126 220502 110126 220503 110127 220503 110128 220503 110126 220504 110128 220504 110196 220504 109879 220505 109878 220505 110126 220505 110126 220506 109878 220506 110118 220506 110126 220507 110118 220507 110124 220507 110124 220508 110118 220508 110129 220508 110124 220509 110129 220509 110130 220509 110130 220510 110129 220510 110131 220510 110130 220511 110131 220511 110105 220511 110105 220512 110131 220512 110132 220512 110105 220513 110132 220513 110133 220513 110133 220514 110132 220514 110134 220514 110133 220515 110134 220515 110098 220515 110098 220516 110134 220516 110135 220516 110098 220517 110135 220517 110099 220517 110099 220518 110135 220518 110215 220518 110099 220519 110215 220519 110213 220519 110136 220520 110076 220520 110201 220520 110185 220521 110137 220521 110147 220521 110181 220522 110138 220522 110166 220522 110226 220523 110225 220523 110144 220523 110139 220524 110140 220524 110227 220524 110227 220525 110140 220525 110141 220525 110227 220526 110141 220526 110142 220526 110142 220527 110141 220527 110153 220527 110142 220528 110153 220528 110143 220528 110143 220529 110153 220529 110152 220529 110144 220530 110225 220530 110146 220530 110146 220531 110225 220531 110145 220531 110146 220532 110145 220532 110147 220532 110182 220533 110166 220533 110224 220533 110147 220534 110137 220534 110146 220534 110146 220535 110137 220535 110184 220535 110146 220536 110184 220536 110144 220536 110145 220537 110148 220537 110147 220537 110147 220538 110148 220538 110149 220538 110147 220539 110149 220539 110185 220539 110185 220540 110149 220540 110150 220540 110185 220541 110150 220541 110186 220541 110186 220542 110150 220542 110151 220542 110186 220543 110151 220543 110187 220543 110187 220544 110151 220544 110210 220544 110187 220545 110210 220545 110188 220545 110148 220546 110152 220546 110149 220546 110149 220547 110152 220547 110153 220547 110149 220548 110153 220548 110150 220548 110150 220549 110153 220549 110141 220549 110150 220550 110141 220550 110151 220550 110151 220551 110141 220551 110140 220551 110151 220552 110140 220552 110210 220552 110161 220553 110154 220553 110160 220553 110160 220554 110154 220554 110075 220554 110160 220555 110075 220555 110155 220555 110155 220556 110075 220556 110156 220556 110155 220557 110156 220557 110157 220557 110157 220558 110156 220558 110073 220558 110157 220559 110073 220559 110158 220559 110216 220560 110202 220560 110160 220560 110160 220561 110202 220561 110159 220561 110160 220562 110159 220562 110161 220562 110163 220563 110080 220563 110178 220563 110178 220564 110080 220564 110079 220564 110178 220565 110079 220565 110077 220565 110073 220566 110162 220566 110158 220566 110158 220567 110162 220567 110070 220567 110158 220568 110070 220568 110163 220568 110163 220569 110070 220569 110069 220569 110163 220570 110069 220570 110080 220570 110077 220571 110164 220571 110178 220571 110178 220572 110164 220572 110136 220572 110178 220573 110136 220573 110165 220573 110165 220574 110136 220574 110201 220574 110165 220575 110201 220575 110180 220575 110166 220576 110182 220576 110181 220576 110181 220577 110182 220577 110183 220577 110181 220578 110183 220578 110179 220578 110179 220579 110183 220579 110167 220579 110179 220580 110167 220580 110168 220580 110168 220581 110167 220581 110169 220581 110168 220582 110169 220582 110177 220582 110177 220583 110169 220583 110170 220583 110177 220584 110170 220584 110176 220584 110176 220585 110170 220585 110171 220585 110176 220586 110171 220586 110175 220586 110175 220587 110171 220587 110173 220587 110175 220588 110173 220588 110172 220588 110172 220589 110173 220589 110174 220589 110172 220590 110174 220590 110216 220590 110216 220591 110160 220591 110172 220591 110172 220592 110160 220592 110155 220592 110172 220593 110155 220593 110175 220593 110175 220594 110155 220594 110157 220594 110175 220595 110157 220595 110176 220595 110176 220596 110157 220596 110158 220596 110176 220597 110158 220597 110177 220597 110177 220598 110158 220598 110163 220598 110177 220599 110163 220599 110168 220599 110168 220600 110163 220600 110178 220600 110168 220601 110178 220601 110179 220601 110179 220602 110178 220602 110165 220602 110179 220603 110165 220603 110181 220603 110181 220604 110165 220604 110180 220604 110181 220605 110180 220605 110138 220605 110224 220606 110226 220606 110182 220606 110182 220607 110226 220607 110144 220607 110182 220608 110144 220608 110183 220608 110183 220609 110144 220609 110184 220609 110183 220610 110184 220610 110167 220610 110167 220611 110184 220611 110137 220611 110167 220612 110137 220612 110169 220612 110169 220613 110137 220613 110185 220613 110169 220614 110185 220614 110170 220614 110170 220615 110185 220615 110186 220615 110170 220616 110186 220616 110171 220616 110171 220617 110186 220617 110187 220617 110171 220618 110187 220618 110173 220618 110173 220619 110187 220619 110188 220619 110173 220620 110188 220620 110174 220620 110200 220621 110191 220621 110199 220621 110198 220622 110224 220622 110166 220622 110122 220623 110232 220623 110189 220623 110193 220624 110123 220624 110200 220624 110200 220625 110123 220625 110122 220625 110122 220626 110189 220626 110200 220626 110200 220627 110189 220627 110190 220627 110200 220628 110190 220628 110191 220628 110191 220629 110190 220629 110230 220629 110191 220630 110230 220630 110198 220630 110196 220631 110128 220631 110192 220631 110192 220632 110128 220632 110193 220632 110194 220633 110196 220633 110195 220633 110195 220634 110196 220634 110192 220634 110195 220635 110192 220635 110197 220635 110198 220636 110166 220636 110191 220636 110191 220637 110166 220637 110138 220637 110191 220638 110138 220638 110199 220638 110199 220639 110138 220639 110180 220639 110199 220640 110180 220640 110201 220640 110193 220641 110200 220641 110192 220641 110192 220642 110200 220642 110199 220642 110192 220643 110199 220643 110197 220643 110197 220644 110199 220644 110201 220644 110197 220645 110201 220645 110076 220645 110202 220646 110216 220646 110217 220646 110207 220647 110231 220647 110203 220647 110139 220648 110229 220648 110140 220648 110140 220649 110229 220649 110209 220649 110204 220650 110206 220650 110205 220650 110205 220651 110206 220651 110231 220651 110218 220652 110208 220652 110214 220652 110214 220653 110208 220653 110209 220653 110231 220654 110206 220654 110203 220654 110203 220655 110206 220655 110104 220655 110203 220656 110104 220656 110212 220656 110229 220657 110207 220657 110209 220657 110209 220658 110207 220658 110203 220658 110209 220659 110203 220659 110214 220659 110214 220660 110203 220660 110212 220660 110216 220661 110174 220661 110208 220661 110208 220662 110174 220662 110188 220662 110208 220663 110188 220663 110209 220663 110209 220664 110188 220664 110210 220664 110209 220665 110210 220665 110140 220665 110211 220666 110086 220666 110217 220666 110217 220667 110086 220667 110159 220667 110217 220668 110159 220668 110202 220668 110212 220669 110213 220669 110214 220669 110214 220670 110213 220670 110215 220670 110214 220671 110215 220671 110218 220671 110218 220672 110215 220672 110116 220672 110218 220673 110116 220673 110219 220673 110216 220674 110208 220674 110217 220674 110217 220675 110208 220675 110218 220675 110217 220676 110218 220676 110211 220676 110211 220677 110218 220677 110219 220677 110211 220678 110219 220678 110084 220678 110233 220679 110204 220679 110205 220679 110233 220680 110223 220680 110220 220680 110220 220681 110221 220681 110233 220681 110233 220682 110221 220682 110222 220682 110233 220683 110222 220683 110204 220683 110094 220684 110108 220684 110233 220684 110233 220685 110108 220685 110106 220685 110233 220686 110106 220686 110223 220686 110228 220687 110224 220687 110198 220687 110145 220688 110225 220688 110228 220688 110228 220689 110225 220689 110226 220689 110228 220690 110226 220690 110224 220690 110139 220691 110227 220691 110228 220691 110228 220692 110227 220692 110142 220692 110228 220693 110142 220693 110143 220693 110143 220694 110152 220694 110228 220694 110228 220695 110152 220695 110148 220695 110228 220696 110148 220696 110145 220696 110139 220697 110228 220697 110229 220697 110229 220698 110228 220698 110198 220698 110229 220699 110198 220699 110207 220699 110207 220700 110198 220700 110230 220700 110207 220701 110230 220701 110231 220701 110231 220702 110230 220702 110190 220702 110231 220703 110190 220703 110205 220703 110205 220704 110190 220704 110189 220704 110205 220705 110189 220705 110233 220705 110233 220706 110189 220706 110232 220706 110233 220707 110232 220707 110094 220707 110235 220708 110254 220708 110287 220708 110284 220709 110246 220709 110234 220709 110287 220710 110236 220710 110235 220710 110235 220711 110236 220711 110290 220711 110235 220712 110290 220712 110234 220712 110234 220713 110290 220713 110292 220713 110234 220714 110292 220714 110284 220714 110259 220715 110258 220715 110282 220715 110282 220716 110258 220716 110061 220716 110282 220717 110061 220717 110286 220717 110286 220718 110061 220718 110051 220718 110286 220719 110051 220719 110237 220719 110237 220720 110051 220720 110243 220720 110237 220721 110243 220721 110238 220721 110238 220722 110243 220722 110246 220722 110238 220723 110246 220723 110239 220723 110239 220724 110246 220724 110284 220724 110279 220725 110240 220725 109894 220725 109894 220726 110240 220726 110064 220726 109894 220727 110064 220727 110062 220727 110279 220728 110277 220728 110240 220728 110240 220729 110277 220729 110264 220729 110240 220730 110264 220730 110249 220730 110264 220731 110266 220731 110249 220731 110249 220732 110266 220732 110268 220732 110249 220733 110268 220733 110241 220733 109914 220734 110256 220734 110273 220734 110273 220735 110256 220735 110257 220735 110273 220736 110257 220736 110271 220736 110271 220737 110257 220737 110241 220737 110271 220738 110241 220738 110270 220738 110270 220739 110241 220739 110268 220739 110242 220740 110246 220740 110243 220740 110051 220741 110244 220741 110243 220741 110243 220742 110244 220742 109887 220742 110243 220743 109887 220743 110242 220743 110242 220744 110245 220744 110246 220744 110246 220745 110245 220745 109892 220745 110246 220746 109892 220746 110234 220746 110252 220747 110064 220747 110240 220747 110052 220748 110247 220748 110241 220748 110241 220749 110247 220749 110248 220749 110241 220750 110248 220750 110249 220750 110248 220751 110059 220751 110249 220751 110249 220752 110059 220752 110250 220752 110249 220753 110250 220753 110240 220753 110240 220754 110250 220754 110251 220754 110240 220755 110251 220755 110252 220755 109892 220756 109889 220756 110234 220756 110234 220757 109889 220757 110055 220757 110234 220758 110055 220758 110235 220758 110235 220759 110055 220759 110253 220759 110235 220760 110253 220760 110254 220760 110254 220761 110253 220761 110255 220761 110254 220762 110255 220762 110263 220762 110263 220763 110255 220763 110053 220763 110263 220764 110053 220764 110256 220764 110256 220765 110053 220765 110052 220765 110256 220766 110052 220766 110257 220766 110257 220767 110052 220767 110241 220767 110258 220768 110259 220768 110261 220768 110258 220769 110261 220769 110065 220769 110065 220770 110261 220770 110260 220770 110065 220771 110260 220771 110063 220771 109943 220772 110260 220772 109899 220772 109899 220773 110260 220773 110261 220773 109899 220774 110261 220774 110262 220774 110259 220775 109902 220775 110261 220775 110261 220776 109902 220776 109901 220776 110261 220777 109901 220777 110262 220777 110287 220778 110254 220778 109912 220778 109912 220779 110254 220779 110263 220779 109912 220780 110263 220780 109914 220780 109914 220781 110263 220781 110256 220781 110274 220782 110265 220782 110264 220782 110264 220783 110265 220783 110266 220783 110266 220784 110265 220784 110267 220784 110266 220785 110267 220785 110268 220785 110268 220786 110267 220786 110269 220786 110268 220787 110269 220787 110270 220787 110270 220788 110269 220788 110272 220788 110270 220789 110272 220789 110271 220789 110271 220790 110272 220790 109962 220790 110271 220791 109962 220791 110273 220791 110273 220792 109962 220792 109935 220792 110273 220793 109935 220793 109914 220793 109914 220794 109935 220794 109934 220794 109914 220795 109934 220795 109916 220795 110274 220796 110264 220796 110275 220796 110275 220797 110264 220797 110277 220797 110275 220798 110277 220798 110276 220798 110276 220799 110277 220799 110279 220799 110276 220800 110279 220800 110278 220800 110278 220801 110279 220801 109894 220801 110278 220802 109894 220802 110280 220802 109902 220803 110259 220803 110281 220803 110281 220804 110259 220804 110282 220804 110281 220805 110282 220805 110283 220805 110283 220806 110282 220806 110286 220806 110284 220807 109994 220807 110239 220807 110239 220808 109994 220808 110285 220808 110239 220809 110285 220809 110238 220809 110238 220810 110285 220810 109990 220810 110238 220811 109990 220811 110237 220811 110237 220812 109990 220812 109989 220812 110237 220813 109989 220813 110286 220813 110286 220814 109989 220814 109987 220814 110286 220815 109987 220815 110283 220815 110287 220816 110288 220816 110236 220816 110236 220817 110288 220817 109998 220817 110236 220818 109998 220818 110290 220818 109998 220819 110289 220819 110290 220819 110290 220820 110289 220820 110291 220820 110290 220821 110291 220821 110292 220821 110292 220822 110291 220822 109996 220822 110292 220823 109996 220823 110284 220823 110284 220824 109996 220824 110293 220824 110284 220825 110293 220825 109994 220825 110391 220826 110390 220826 110294 220826 110294 220827 110295 220827 110391 220827 110391 220828 110295 220828 110688 220828 110391 220829 110688 220829 110389 220829 110389 220830 110688 220830 110296 220830 110389 220831 110296 220831 110297 220831 110297 220832 110296 220832 110298 220832 110297 220833 110298 220833 110300 220833 110300 220834 110298 220834 110299 220834 110300 220835 110299 220835 110387 220835 110387 220836 110299 220836 110301 220836 110301 220837 110299 220837 110685 220837 110301 220838 110685 220838 110302 220838 110685 220839 110684 220839 110302 220839 110302 220840 110684 220840 110303 220840 110302 220841 110303 220841 110304 220841 110304 220842 110303 220842 110392 220842 110392 220843 110303 220843 110457 220843 110392 220844 110457 220844 110397 220844 110455 220845 110677 220845 110423 220845 110423 220846 110677 220846 110305 220846 110423 220847 110305 220847 110307 220847 110307 220848 110305 220848 110306 220848 110307 220849 110306 220849 110329 220849 110329 220850 110306 220850 110696 220850 110694 220851 110676 220851 110675 220851 110694 220852 110675 220852 110434 220852 110434 220853 110675 220853 110674 220853 110434 220854 110674 220854 110308 220854 110308 220855 110674 220855 110294 220855 110308 220856 110294 220856 110390 220856 110309 220857 110310 220857 110415 220857 110311 220858 110309 220858 110349 220858 110319 220859 110322 220859 110312 220859 110312 220860 110322 220860 110323 220860 110312 220861 110323 220861 110442 220861 110442 220862 110323 220862 110324 220862 110442 220863 110324 220863 110443 220863 110443 220864 110324 220864 110429 220864 110313 220865 110317 220865 110314 220865 110321 220866 110364 220866 110316 220866 110316 220867 110364 220867 110315 220867 110316 220868 110315 220868 110313 220868 110313 220869 110315 220869 110435 220869 110313 220870 110435 220870 110317 220870 110318 220871 110322 220871 110351 220871 110351 220872 110322 220872 110319 220872 110351 220873 110319 220873 110320 220873 110318 220874 110321 220874 110322 220874 110322 220875 110321 220875 110316 220875 110322 220876 110316 220876 110323 220876 110323 220877 110316 220877 110313 220877 110323 220878 110313 220878 110324 220878 110324 220879 110313 220879 110314 220879 110324 220880 110314 220880 110429 220880 110359 220881 110361 220881 110318 220881 110318 220882 110361 220882 110362 220882 110318 220883 110362 220883 110321 220883 110325 220884 110311 220884 110352 220884 110352 220885 110311 220885 110349 220885 110352 220886 110349 220886 110326 220886 110326 220887 110349 220887 110353 220887 110357 220888 110355 220888 110335 220888 110327 220889 110356 220889 110695 220889 110695 220890 110356 220890 110328 220890 110695 220891 110328 220891 110329 220891 110344 220892 110333 220892 110346 220892 110346 220893 110333 220893 110694 220893 110346 220894 110694 220894 110347 220894 110330 220895 110705 220895 110331 220895 110331 220896 110705 220896 110332 220896 110331 220897 110332 220897 110344 220897 110344 220898 110332 220898 110707 220898 110344 220899 110707 220899 110333 220899 110327 220900 110334 220900 110355 220900 110355 220901 110334 220901 110699 220901 110355 220902 110699 220902 110335 220902 110335 220903 110699 220903 110336 220903 110335 220904 110336 220904 110342 220904 110342 220905 110336 220905 110702 220905 110342 220906 110702 220906 110331 220906 110331 220907 110702 220907 110706 220907 110331 220908 110706 220908 110330 220908 110357 220909 110341 220909 110358 220909 110358 220910 110341 220910 110337 220910 110358 220911 110337 220911 110360 220911 110360 220912 110337 220912 110343 220912 110360 220913 110343 220913 110338 220913 110338 220914 110343 220914 110345 220914 110338 220915 110345 220915 110363 220915 110363 220916 110345 220916 110340 220916 110363 220917 110340 220917 110339 220917 110339 220918 110340 220918 110348 220918 110339 220919 110348 220919 110365 220919 110357 220920 110335 220920 110341 220920 110341 220921 110335 220921 110342 220921 110341 220922 110342 220922 110337 220922 110337 220923 110342 220923 110331 220923 110337 220924 110331 220924 110343 220924 110343 220925 110331 220925 110344 220925 110343 220926 110344 220926 110345 220926 110345 220927 110344 220927 110346 220927 110345 220928 110346 220928 110340 220928 110340 220929 110346 220929 110347 220929 110340 220930 110347 220930 110348 220930 110309 220931 110415 220931 110349 220931 110349 220932 110415 220932 110350 220932 110349 220933 110350 220933 110353 220933 110353 220934 110350 220934 110420 220934 110353 220935 110420 220935 110354 220935 110320 220936 110325 220936 110351 220936 110351 220937 110325 220937 110352 220937 110351 220938 110352 220938 110318 220938 110318 220939 110352 220939 110326 220939 110318 220940 110326 220940 110359 220940 110359 220941 110326 220941 110353 220941 110359 220942 110353 220942 110356 220942 110356 220943 110353 220943 110354 220943 110356 220944 110354 220944 110328 220944 110327 220945 110355 220945 110356 220945 110356 220946 110355 220946 110357 220946 110356 220947 110357 220947 110359 220947 110359 220948 110357 220948 110358 220948 110359 220949 110358 220949 110361 220949 110361 220950 110358 220950 110360 220950 110361 220951 110360 220951 110362 220951 110362 220952 110360 220952 110338 220952 110362 220953 110338 220953 110321 220953 110321 220954 110338 220954 110363 220954 110321 220955 110363 220955 110364 220955 110364 220956 110363 220956 110339 220956 110364 220957 110339 220957 110315 220957 110315 220958 110339 220958 110365 220958 110315 220959 110365 220959 110435 220959 110456 220960 110455 220960 110366 220960 110367 220961 110374 220961 110373 220961 110410 220962 110418 220962 110368 220962 110411 220963 110444 220963 110372 220963 110369 220964 110427 220964 110446 220964 110446 220965 110427 220965 110385 220965 110446 220966 110385 220966 110370 220966 110370 220967 110385 220967 110371 220967 110370 220968 110371 220968 110448 220968 110448 220969 110371 220969 110384 220969 110372 220970 110444 220970 110375 220970 110375 220971 110444 220971 110377 220971 110375 220972 110377 220972 110373 220972 110412 220973 110368 220973 110445 220973 110373 220974 110374 220974 110375 220974 110375 220975 110374 220975 110376 220975 110375 220976 110376 220976 110372 220976 110377 220977 110449 220977 110373 220977 110373 220978 110449 220978 110378 220978 110373 220979 110378 220979 110367 220979 110367 220980 110378 220980 110379 220980 110367 220981 110379 220981 110380 220981 110380 220982 110379 220982 110382 220982 110380 220983 110382 220983 110381 220983 110381 220984 110382 220984 110383 220984 110381 220985 110383 220985 110432 220985 110449 220986 110384 220986 110378 220986 110378 220987 110384 220987 110371 220987 110378 220988 110371 220988 110379 220988 110379 220989 110371 220989 110385 220989 110379 220990 110385 220990 110382 220990 110382 220991 110385 220991 110427 220991 110382 220992 110427 220992 110383 220992 110386 220993 110300 220993 110387 220993 110386 220994 110387 220994 110396 220994 110300 220995 110386 220995 110297 220995 110297 220996 110386 220996 110405 220996 110297 220997 110405 220997 110389 220997 110389 220998 110405 220998 110388 220998 110389 220999 110388 220999 110391 220999 110390 221000 110391 221000 110424 221000 110424 221001 110391 221001 110388 221001 110424 221002 110388 221002 110437 221002 110397 221003 110393 221003 110392 221003 110392 221004 110393 221004 110394 221004 110392 221005 110394 221005 110304 221005 110304 221006 110394 221006 110395 221006 110304 221007 110395 221007 110302 221007 110302 221008 110395 221008 110396 221008 110302 221009 110396 221009 110301 221009 110301 221010 110396 221010 110387 221010 110419 221011 110393 221011 110366 221011 110366 221012 110393 221012 110397 221012 110366 221013 110397 221013 110456 221013 110368 221014 110412 221014 110410 221014 110410 221015 110412 221015 110398 221015 110410 221016 110398 221016 110409 221016 110409 221017 110398 221017 110413 221017 110409 221018 110413 221018 110408 221018 110408 221019 110413 221019 110399 221019 110408 221020 110399 221020 110400 221020 110400 221021 110399 221021 110401 221021 110400 221022 110401 221022 110402 221022 110402 221023 110401 221023 110403 221023 110402 221024 110403 221024 110407 221024 110407 221025 110403 221025 110404 221025 110407 221026 110404 221026 110406 221026 110406 221027 110404 221027 110431 221027 110406 221028 110431 221028 110437 221028 110437 221029 110388 221029 110406 221029 110406 221030 110388 221030 110405 221030 110406 221031 110405 221031 110407 221031 110407 221032 110405 221032 110386 221032 110407 221033 110386 221033 110402 221033 110402 221034 110386 221034 110396 221034 110402 221035 110396 221035 110400 221035 110400 221036 110396 221036 110395 221036 110400 221037 110395 221037 110408 221037 110408 221038 110395 221038 110394 221038 110408 221039 110394 221039 110409 221039 110409 221040 110394 221040 110393 221040 110409 221041 110393 221041 110410 221041 110410 221042 110393 221042 110419 221042 110410 221043 110419 221043 110418 221043 110445 221044 110411 221044 110412 221044 110412 221045 110411 221045 110372 221045 110412 221046 110372 221046 110398 221046 110398 221047 110372 221047 110376 221047 110398 221048 110376 221048 110413 221048 110413 221049 110376 221049 110374 221049 110413 221050 110374 221050 110399 221050 110399 221051 110374 221051 110367 221051 110399 221052 110367 221052 110401 221052 110401 221053 110367 221053 110380 221053 110401 221054 110380 221054 110403 221054 110403 221055 110380 221055 110381 221055 110403 221056 110381 221056 110404 221056 110404 221057 110381 221057 110432 221057 110404 221058 110432 221058 110431 221058 110414 221059 110417 221059 110422 221059 110450 221060 110445 221060 110368 221060 110415 221061 110310 221061 110453 221061 110420 221062 110350 221062 110414 221062 110414 221063 110350 221063 110415 221063 110415 221064 110453 221064 110414 221064 110414 221065 110453 221065 110416 221065 110414 221066 110416 221066 110417 221066 110417 221067 110416 221067 110452 221067 110417 221068 110452 221068 110450 221068 110328 221069 110354 221069 110421 221069 110421 221070 110354 221070 110420 221070 110329 221071 110328 221071 110307 221071 110307 221072 110328 221072 110421 221072 110307 221073 110421 221073 110423 221073 110450 221074 110368 221074 110417 221074 110417 221075 110368 221075 110418 221075 110417 221076 110418 221076 110422 221076 110422 221077 110418 221077 110419 221077 110422 221078 110419 221078 110366 221078 110420 221079 110414 221079 110421 221079 110421 221080 110414 221080 110422 221080 110421 221081 110422 221081 110423 221081 110423 221082 110422 221082 110366 221082 110423 221083 110366 221083 110455 221083 110424 221084 110437 221084 110425 221084 110451 221085 110426 221085 110430 221085 110369 221086 110428 221086 110427 221086 110427 221087 110428 221087 110433 221087 110443 221088 110429 221088 110440 221088 110440 221089 110429 221089 110426 221089 110439 221090 110438 221090 110436 221090 110436 221091 110438 221091 110433 221091 110426 221092 110429 221092 110430 221092 110430 221093 110429 221093 110314 221093 110430 221094 110314 221094 110317 221094 110428 221095 110451 221095 110433 221095 110433 221096 110451 221096 110430 221096 110433 221097 110430 221097 110436 221097 110436 221098 110430 221098 110317 221098 110437 221099 110431 221099 110438 221099 110438 221100 110431 221100 110432 221100 110438 221101 110432 221101 110433 221101 110433 221102 110432 221102 110383 221102 110433 221103 110383 221103 110427 221103 110434 221104 110308 221104 110425 221104 110425 221105 110308 221105 110390 221105 110425 221106 110390 221106 110424 221106 110317 221107 110435 221107 110436 221107 110436 221108 110435 221108 110365 221108 110436 221109 110365 221109 110439 221109 110439 221110 110365 221110 110348 221110 110439 221111 110348 221111 110347 221111 110437 221112 110438 221112 110425 221112 110425 221113 110438 221113 110439 221113 110425 221114 110439 221114 110434 221114 110434 221115 110439 221115 110347 221115 110434 221116 110347 221116 110694 221116 110441 221117 110443 221117 110440 221117 110441 221118 110320 221118 110319 221118 110319 221119 110312 221119 110441 221119 110441 221120 110312 221120 110442 221120 110441 221121 110442 221121 110443 221121 110454 221122 110311 221122 110441 221122 110441 221123 110311 221123 110325 221123 110441 221124 110325 221124 110320 221124 110447 221125 110445 221125 110450 221125 110377 221126 110444 221126 110447 221126 110447 221127 110444 221127 110411 221127 110447 221128 110411 221128 110445 221128 110369 221129 110446 221129 110447 221129 110447 221130 110446 221130 110370 221130 110447 221131 110370 221131 110448 221131 110448 221132 110384 221132 110447 221132 110447 221133 110384 221133 110449 221133 110447 221134 110449 221134 110377 221134 110369 221135 110447 221135 110428 221135 110428 221136 110447 221136 110450 221136 110428 221137 110450 221137 110451 221137 110451 221138 110450 221138 110452 221138 110451 221139 110452 221139 110426 221139 110426 221140 110452 221140 110416 221140 110426 221141 110416 221141 110440 221141 110440 221142 110416 221142 110453 221142 110440 221143 110453 221143 110441 221143 110441 221144 110453 221144 110310 221144 110441 221145 110310 221145 110454 221145 110677 221146 110455 221146 110457 221146 110457 221147 110455 221147 110456 221147 110457 221148 110456 221148 110397 221148 110457 221149 110458 221149 110677 221149 110677 221150 110458 221150 110459 221150 110622 221151 110460 221151 110478 221151 110615 221152 110461 221152 110464 221152 110464 221153 110461 221153 110462 221153 110464 221154 110462 221154 110463 221154 110463 221155 110462 221155 110617 221155 110463 221156 110617 221156 110616 221156 110478 221157 110460 221157 110464 221157 110464 221158 110460 221158 110465 221158 110464 221159 110465 221159 110615 221159 110622 221160 110478 221160 110466 221160 110466 221161 110478 221161 110467 221161 110466 221162 110467 221162 110468 221162 110467 221163 110475 221163 110468 221163 110468 221164 110475 221164 110474 221164 110468 221165 110474 221165 110623 221165 110623 221166 110474 221166 110469 221166 110623 221167 110469 221167 110624 221167 110624 221168 110469 221168 110471 221168 110469 221169 110470 221169 110471 221169 110471 221170 110470 221170 110472 221170 110471 221171 110472 221171 110596 221171 110473 221172 110499 221172 110472 221172 110472 221173 110470 221173 110473 221173 110473 221174 110470 221174 110469 221174 110473 221175 110469 221175 110498 221175 110469 221176 110474 221176 110498 221176 110498 221177 110474 221177 110475 221177 110498 221178 110475 221178 110476 221178 110475 221179 110467 221179 110476 221179 110476 221180 110467 221180 110478 221180 110476 221181 110478 221181 110477 221181 110477 221182 110478 221182 110464 221182 110477 221183 110464 221183 110479 221183 110479 221184 110464 221184 110463 221184 110479 221185 110463 221185 110481 221185 110519 221186 110692 221186 110521 221186 110521 221187 110692 221187 110480 221187 110521 221188 110480 221188 110463 221188 110463 221189 110480 221189 110481 221189 110512 221190 110492 221190 110483 221190 110689 221191 110504 221191 110482 221191 110482 221192 110504 221192 110516 221192 110482 221193 110516 221193 110673 221193 110673 221194 110516 221194 110517 221194 110673 221195 110517 221195 110483 221195 110483 221196 110517 221196 110484 221196 110483 221197 110484 221197 110512 221197 110512 221198 110513 221198 110492 221198 110492 221199 110513 221199 110515 221199 110492 221200 110515 221200 110485 221200 110507 221201 110501 221201 110510 221201 110510 221202 110501 221202 110486 221202 110510 221203 110486 221203 110487 221203 110487 221204 110486 221204 110485 221204 110487 221205 110485 221205 110488 221205 110488 221206 110485 221206 110515 221206 110489 221207 110673 221207 110483 221207 110686 221208 110492 221208 110485 221208 110459 221209 110458 221209 110485 221209 110485 221210 110458 221210 110490 221210 110485 221211 110490 221211 110686 221211 110686 221212 110491 221212 110492 221212 110492 221213 110491 221213 110493 221213 110492 221214 110493 221214 110483 221214 110483 221215 110493 221215 110687 221215 110483 221216 110687 221216 110489 221216 110682 221217 110476 221217 110477 221217 110477 221218 110479 221218 110680 221218 110682 221219 110477 221219 110494 221219 110494 221220 110477 221220 110680 221220 110494 221221 110680 221221 110495 221221 110682 221222 110683 221222 110476 221222 110476 221223 110683 221223 110496 221223 110476 221224 110496 221224 110498 221224 110498 221225 110496 221225 110497 221225 110498 221226 110497 221226 110473 221226 110473 221227 110497 221227 110679 221227 110473 221228 110679 221228 110499 221228 110499 221229 110679 221229 110500 221229 110499 221230 110500 221230 110508 221230 110508 221231 110500 221231 110678 221231 110508 221232 110678 221232 110501 221232 110501 221233 110678 221233 110459 221233 110501 221234 110459 221234 110486 221234 110486 221235 110459 221235 110485 221235 110692 221236 110519 221236 110505 221236 110692 221237 110505 221237 110502 221237 110502 221238 110505 221238 110504 221238 110502 221239 110504 221239 110689 221239 110503 221240 110504 221240 110528 221240 110528 221241 110504 221241 110505 221241 110528 221242 110505 221242 110529 221242 110519 221243 110533 221243 110505 221243 110505 221244 110533 221244 110531 221244 110505 221245 110531 221245 110529 221245 110472 221246 110499 221246 110506 221246 110506 221247 110499 221247 110508 221247 110506 221248 110508 221248 110507 221248 110507 221249 110508 221249 110501 221249 110516 221250 110504 221250 110503 221250 110580 221251 110507 221251 110554 221251 110554 221252 110507 221252 110510 221252 110554 221253 110510 221253 110509 221253 110509 221254 110510 221254 110511 221254 110510 221255 110487 221255 110511 221255 110511 221256 110487 221256 110488 221256 110511 221257 110488 221257 110587 221257 110512 221258 110514 221258 110513 221258 110513 221259 110514 221259 110587 221259 110513 221260 110587 221260 110515 221260 110515 221261 110587 221261 110488 221261 110503 221262 110578 221262 110516 221262 110516 221263 110578 221263 110579 221263 110516 221264 110579 221264 110517 221264 110517 221265 110579 221265 110568 221265 110517 221266 110568 221266 110484 221266 110484 221267 110568 221267 110567 221267 110484 221268 110567 221268 110512 221268 110512 221269 110567 221269 110518 221269 110512 221270 110518 221270 110514 221270 110533 221271 110519 221271 110520 221271 110520 221272 110519 221272 110521 221272 110520 221273 110521 221273 110522 221273 110522 221274 110521 221274 110463 221274 110522 221275 110463 221275 110616 221275 110541 221276 110600 221276 110523 221276 110600 221277 110541 221277 110524 221277 110536 221278 110530 221278 110537 221278 110527 221279 110503 221279 110528 221279 110525 221280 110526 221280 110536 221280 110536 221281 110526 221281 110527 221281 110527 221282 110528 221282 110536 221282 110536 221283 110528 221283 110529 221283 110536 221284 110529 221284 110530 221284 110530 221285 110529 221285 110531 221285 110530 221286 110531 221286 110533 221286 110535 221287 110565 221287 110532 221287 110532 221288 110565 221288 110525 221288 110533 221289 110618 221289 110530 221289 110530 221290 110618 221290 110632 221290 110530 221291 110632 221291 110537 221291 110537 221292 110632 221292 110631 221292 110537 221293 110631 221293 110649 221293 110538 221294 110535 221294 110534 221294 110534 221295 110535 221295 110532 221295 110534 221296 110532 221296 110541 221296 110525 221297 110536 221297 110532 221297 110532 221298 110536 221298 110537 221298 110532 221299 110537 221299 110541 221299 110541 221300 110537 221300 110649 221300 110541 221301 110649 221301 110524 221301 110651 221302 110538 221302 110539 221302 110539 221303 110538 221303 110534 221303 110539 221304 110534 221304 110540 221304 110540 221305 110534 221305 110541 221305 110540 221306 110541 221306 110660 221306 110660 221307 110541 221307 110523 221307 110596 221308 110472 221308 110542 221308 110542 221309 110472 221309 110506 221309 110542 221310 110506 221310 110671 221310 110671 221311 110506 221311 110543 221311 110543 221312 110506 221312 110507 221312 110543 221313 110507 221313 110580 221313 110518 221314 110567 221314 110589 221314 110568 221315 110579 221315 110569 221315 110558 221316 110547 221316 110561 221316 110544 221317 110654 221317 110545 221317 110549 221318 110653 221318 110546 221318 110558 221319 110557 221319 110547 221319 110547 221320 110557 221320 110548 221320 110547 221321 110548 221321 110549 221321 110550 221322 110650 221322 110595 221322 110595 221323 110650 221323 110552 221323 110595 221324 110552 221324 110593 221324 110595 221325 110551 221325 110550 221325 110550 221326 110551 221326 110538 221326 110550 221327 110538 221327 110651 221327 110552 221328 110544 221328 110593 221328 110593 221329 110544 221329 110545 221329 110593 221330 110545 221330 110592 221330 110592 221331 110545 221331 110559 221331 110592 221332 110559 221332 110553 221332 110553 221333 110559 221333 110560 221333 110553 221334 110560 221334 110590 221334 110590 221335 110560 221335 110562 221335 110590 221336 110562 221336 110588 221336 110554 221337 110509 221337 110581 221337 110581 221338 110509 221338 110556 221338 110549 221339 110546 221339 110547 221339 110547 221340 110546 221340 110582 221340 110547 221341 110582 221341 110561 221341 110561 221342 110582 221342 110581 221342 110561 221343 110581 221343 110555 221343 110555 221344 110581 221344 110556 221344 110555 221345 110556 221345 110563 221345 110654 221346 110557 221346 110545 221346 110545 221347 110557 221347 110558 221347 110545 221348 110558 221348 110559 221348 110559 221349 110558 221349 110561 221349 110559 221350 110561 221350 110560 221350 110560 221351 110561 221351 110555 221351 110560 221352 110555 221352 110562 221352 110562 221353 110555 221353 110563 221353 110562 221354 110563 221354 110588 221354 110518 221355 110589 221355 110514 221355 110535 221356 110564 221356 110565 221356 110565 221357 110564 221357 110575 221357 110565 221358 110575 221358 110525 221358 110525 221359 110575 221359 110566 221359 110525 221360 110566 221360 110526 221360 110526 221361 110566 221361 110576 221361 110526 221362 110576 221362 110527 221362 110527 221363 110576 221363 110577 221363 110527 221364 110577 221364 110503 221364 110503 221365 110577 221365 110578 221365 110567 221366 110568 221366 110589 221366 110589 221367 110568 221367 110569 221367 110589 221368 110569 221368 110591 221368 110591 221369 110569 221369 110570 221369 110591 221370 110570 221370 110572 221370 110572 221371 110570 221371 110571 221371 110572 221372 110571 221372 110573 221372 110573 221373 110571 221373 110574 221373 110573 221374 110574 221374 110594 221374 110564 221375 110594 221375 110575 221375 110575 221376 110594 221376 110574 221376 110575 221377 110574 221377 110566 221377 110566 221378 110574 221378 110571 221378 110566 221379 110571 221379 110576 221379 110576 221380 110571 221380 110570 221380 110576 221381 110570 221381 110577 221381 110577 221382 110570 221382 110569 221382 110577 221383 110569 221383 110578 221383 110578 221384 110569 221384 110579 221384 110580 221385 110554 221385 110672 221385 110672 221386 110554 221386 110581 221386 110672 221387 110581 221387 110583 221387 110583 221388 110581 221388 110582 221388 110583 221389 110582 221389 110584 221389 110584 221390 110582 221390 110546 221390 110584 221391 110546 221391 110585 221391 110585 221392 110546 221392 110653 221392 110585 221393 110653 221393 110586 221393 110509 221394 110511 221394 110556 221394 110556 221395 110511 221395 110587 221395 110556 221396 110587 221396 110563 221396 110563 221397 110587 221397 110514 221397 110563 221398 110514 221398 110588 221398 110588 221399 110514 221399 110589 221399 110588 221400 110589 221400 110590 221400 110590 221401 110589 221401 110591 221401 110590 221402 110591 221402 110553 221402 110553 221403 110591 221403 110572 221403 110553 221404 110572 221404 110592 221404 110592 221405 110572 221405 110573 221405 110592 221406 110573 221406 110593 221406 110593 221407 110573 221407 110594 221407 110593 221408 110594 221408 110595 221408 110595 221409 110594 221409 110564 221409 110595 221410 110564 221410 110551 221410 110551 221411 110564 221411 110535 221411 110551 221412 110535 221412 110538 221412 110471 221413 110596 221413 110625 221413 110520 221414 110522 221414 110619 221414 110607 221415 110597 221415 110603 221415 110626 221416 110642 221416 110667 221416 110609 221417 110659 221417 110598 221417 110598 221418 110659 221418 110599 221418 110598 221419 110599 221419 110611 221419 110611 221420 110599 221420 110523 221420 110611 221421 110523 221421 110600 221421 110643 221422 110667 221422 110656 221422 110655 221423 110657 221423 110605 221423 110605 221424 110657 221424 110601 221424 110605 221425 110601 221425 110604 221425 110604 221426 110601 221426 110602 221426 110604 221427 110602 221427 110603 221427 110603 221428 110597 221428 110604 221428 110604 221429 110597 221429 110644 221429 110604 221430 110644 221430 110605 221430 110602 221431 110606 221431 110603 221431 110603 221432 110606 221432 110608 221432 110603 221433 110608 221433 110607 221433 110607 221434 110608 221434 110610 221434 110607 221435 110610 221435 110647 221435 110647 221436 110610 221436 110612 221436 110647 221437 110612 221437 110648 221437 110648 221438 110612 221438 110524 221438 110648 221439 110524 221439 110649 221439 110606 221440 110609 221440 110608 221440 110608 221441 110609 221441 110598 221441 110608 221442 110598 221442 110610 221442 110610 221443 110598 221443 110611 221443 110610 221444 110611 221444 110612 221444 110612 221445 110611 221445 110600 221445 110612 221446 110600 221446 110524 221446 110621 221447 110614 221447 110465 221447 110617 221448 110462 221448 110613 221448 110613 221449 110462 221449 110461 221449 110613 221450 110461 221450 110614 221450 110614 221451 110461 221451 110615 221451 110614 221452 110615 221452 110465 221452 110619 221453 110522 221453 110613 221453 110613 221454 110522 221454 110616 221454 110613 221455 110616 221455 110617 221455 110632 221456 110618 221456 110619 221456 110619 221457 110618 221457 110533 221457 110619 221458 110533 221458 110520 221458 110620 221459 110468 221459 110638 221459 110638 221460 110468 221460 110623 221460 110465 221461 110460 221461 110621 221461 110621 221462 110460 221462 110622 221462 110621 221463 110622 221463 110620 221463 110620 221464 110622 221464 110466 221464 110620 221465 110466 221465 110468 221465 110623 221466 110624 221466 110638 221466 110638 221467 110624 221467 110471 221467 110638 221468 110471 221468 110640 221468 110640 221469 110471 221469 110625 221469 110640 221470 110625 221470 110641 221470 110667 221471 110643 221471 110626 221471 110626 221472 110643 221472 110627 221472 110626 221473 110627 221473 110639 221473 110639 221474 110627 221474 110628 221474 110639 221475 110628 221475 110637 221475 110637 221476 110628 221476 110645 221476 110637 221477 110645 221477 110636 221477 110636 221478 110645 221478 110629 221478 110636 221479 110629 221479 110635 221479 110635 221480 110629 221480 110646 221480 110635 221481 110646 221481 110634 221481 110634 221482 110646 221482 110630 221482 110634 221483 110630 221483 110633 221483 110633 221484 110630 221484 110631 221484 110633 221485 110631 221485 110632 221485 110632 221486 110619 221486 110633 221486 110633 221487 110619 221487 110613 221487 110633 221488 110613 221488 110634 221488 110634 221489 110613 221489 110614 221489 110634 221490 110614 221490 110635 221490 110635 221491 110614 221491 110621 221491 110635 221492 110621 221492 110636 221492 110636 221493 110621 221493 110620 221493 110636 221494 110620 221494 110637 221494 110637 221495 110620 221495 110638 221495 110637 221496 110638 221496 110639 221496 110639 221497 110638 221497 110640 221497 110639 221498 110640 221498 110626 221498 110626 221499 110640 221499 110641 221499 110626 221500 110641 221500 110642 221500 110656 221501 110655 221501 110643 221501 110643 221502 110655 221502 110605 221502 110643 221503 110605 221503 110627 221503 110627 221504 110605 221504 110644 221504 110627 221505 110644 221505 110628 221505 110628 221506 110644 221506 110597 221506 110628 221507 110597 221507 110645 221507 110645 221508 110597 221508 110607 221508 110645 221509 110607 221509 110629 221509 110629 221510 110607 221510 110647 221510 110629 221511 110647 221511 110646 221511 110646 221512 110647 221512 110648 221512 110646 221513 110648 221513 110630 221513 110630 221514 110648 221514 110649 221514 110630 221515 110649 221515 110631 221515 110658 221516 110656 221516 110661 221516 110652 221517 110651 221517 110539 221517 110550 221518 110651 221518 110650 221518 110650 221519 110651 221519 110652 221519 110650 221520 110652 221520 110552 221520 110552 221521 110652 221521 110544 221521 110653 221522 110549 221522 110652 221522 110652 221523 110549 221523 110548 221523 110548 221524 110557 221524 110652 221524 110652 221525 110557 221525 110654 221525 110652 221526 110654 221526 110544 221526 110609 221527 110606 221527 110658 221527 110658 221528 110606 221528 110602 221528 110655 221529 110656 221529 110657 221529 110657 221530 110656 221530 110658 221530 110657 221531 110658 221531 110601 221531 110601 221532 110658 221532 110602 221532 110523 221533 110599 221533 110658 221533 110658 221534 110599 221534 110659 221534 110658 221535 110659 221535 110609 221535 110523 221536 110658 221536 110660 221536 110660 221537 110658 221537 110661 221537 110660 221538 110661 221538 110540 221538 110540 221539 110661 221539 110662 221539 110540 221540 110662 221540 110539 221540 110539 221541 110662 221541 110665 221541 110539 221542 110665 221542 110652 221542 110652 221543 110665 221543 110586 221543 110652 221544 110586 221544 110653 221544 110625 221545 110596 221545 110542 221545 110642 221546 110641 221546 110669 221546 110672 221547 110583 221547 110663 221547 110584 221548 110585 221548 110664 221548 110585 221549 110586 221549 110664 221549 110664 221550 110586 221550 110665 221550 110664 221551 110665 221551 110668 221551 110668 221552 110665 221552 110662 221552 110668 221553 110662 221553 110666 221553 110666 221554 110662 221554 110661 221554 110666 221555 110661 221555 110667 221555 110667 221556 110661 221556 110656 221556 110667 221557 110642 221557 110666 221557 110666 221558 110642 221558 110669 221558 110666 221559 110669 221559 110668 221559 110668 221560 110669 221560 110670 221560 110668 221561 110670 221561 110664 221561 110664 221562 110670 221562 110663 221562 110664 221563 110663 221563 110584 221563 110584 221564 110663 221564 110583 221564 110641 221565 110625 221565 110669 221565 110669 221566 110625 221566 110542 221566 110669 221567 110542 221567 110670 221567 110670 221568 110542 221568 110671 221568 110670 221569 110671 221569 110663 221569 110663 221570 110671 221570 110543 221570 110663 221571 110543 221571 110672 221571 110672 221572 110543 221572 110580 221572 110673 221573 110489 221573 110294 221573 110673 221574 110294 221574 110690 221574 110294 221575 110674 221575 110690 221575 110690 221576 110674 221576 110675 221576 110690 221577 110675 221577 110691 221577 110691 221578 110675 221578 110479 221578 110479 221579 110675 221579 110676 221579 110479 221580 110676 221580 110680 221580 110677 221581 110459 221581 110305 221581 110305 221582 110459 221582 110678 221582 110305 221583 110678 221583 110306 221583 110306 221584 110678 221584 110500 221584 110306 221585 110500 221585 110696 221585 110696 221586 110500 221586 110679 221586 110680 221587 110676 221587 110495 221587 110495 221588 110676 221588 110693 221588 110495 221589 110693 221589 110494 221589 110693 221590 110681 221590 110494 221590 110494 221591 110681 221591 110704 221591 110494 221592 110704 221592 110682 221592 110682 221593 110704 221593 110703 221593 110682 221594 110703 221594 110683 221594 110683 221595 110703 221595 110701 221595 110683 221596 110701 221596 110496 221596 110696 221597 110679 221597 110697 221597 110697 221598 110679 221598 110497 221598 110697 221599 110497 221599 110698 221599 110698 221600 110497 221600 110496 221600 110698 221601 110496 221601 110700 221601 110700 221602 110496 221602 110701 221602 110458 221603 110457 221603 110490 221603 110490 221604 110457 221604 110303 221604 110490 221605 110303 221605 110686 221605 110303 221606 110684 221606 110686 221606 110686 221607 110684 221607 110685 221607 110686 221608 110685 221608 110491 221608 110491 221609 110685 221609 110299 221609 110491 221610 110299 221610 110493 221610 110299 221611 110298 221611 110493 221611 110493 221612 110298 221612 110296 221612 110493 221613 110296 221613 110687 221613 110294 221614 110489 221614 110295 221614 110295 221615 110489 221615 110687 221615 110295 221616 110687 221616 110688 221616 110688 221617 110687 221617 110296 221617 110481 221618 110480 221618 110692 221618 110482 221619 110673 221619 110689 221619 110689 221620 110673 221620 110690 221620 110689 221621 110690 221621 110502 221621 110502 221622 110690 221622 110691 221622 110502 221623 110691 221623 110692 221623 110692 221624 110691 221624 110479 221624 110692 221625 110479 221625 110481 221625 110693 221626 110676 221626 110694 221626 110329 221627 110696 221627 110695 221627 110695 221628 110696 221628 110697 221628 110695 221629 110697 221629 110327 221629 110327 221630 110697 221630 110334 221630 110697 221631 110698 221631 110334 221631 110334 221632 110698 221632 110700 221632 110334 221633 110700 221633 110699 221633 110699 221634 110700 221634 110701 221634 110699 221635 110701 221635 110336 221635 110336 221636 110701 221636 110702 221636 110702 221637 110701 221637 110703 221637 110702 221638 110703 221638 110706 221638 110707 221639 110332 221639 110704 221639 110704 221640 110332 221640 110705 221640 110704 221641 110705 221641 110703 221641 110703 221642 110705 221642 110330 221642 110703 221643 110330 221643 110706 221643 110694 221644 110333 221644 110693 221644 110693 221645 110333 221645 110707 221645 110693 221646 110707 221646 110681 221646 110681 221647 110707 221647 110704 221647 112042 221648 110723 221648 110708 221648 110708 221649 110723 221649 110709 221649 111821 221650 110831 221650 111823 221650 111823 221651 110831 221651 110754 221651 110766 221652 110859 221652 111138 221652 111138 221653 110859 221653 110711 221653 110710 221654 110714 221654 110711 221654 110711 221655 110714 221655 111137 221655 110711 221656 111137 221656 111138 221656 110854 221657 110712 221657 110710 221657 110710 221658 110712 221658 110713 221658 110710 221659 110713 221659 110714 221659 110720 221660 112108 221660 110721 221660 110721 221661 112108 221661 110715 221661 110721 221662 110715 221662 110716 221662 110716 221663 112085 221663 110721 221663 110721 221664 112085 221664 110717 221664 110721 221665 110717 221665 112083 221665 112083 221666 112081 221666 110721 221666 110721 221667 112081 221667 112079 221667 110721 221668 112079 221668 110718 221668 110718 221669 112095 221669 110721 221669 110721 221670 112095 221670 111127 221670 110721 221671 111127 221671 110854 221671 110854 221672 111127 221672 110719 221672 110854 221673 110719 221673 110712 221673 110720 221674 110721 221674 110722 221674 110722 221675 110721 221675 110723 221675 110722 221676 110723 221676 112042 221676 110708 221677 110709 221677 112028 221677 112028 221678 110709 221678 110726 221678 112019 221679 112020 221679 110726 221679 112019 221680 110726 221680 112017 221680 112013 221681 112015 221681 110726 221681 110726 221682 112015 221682 112016 221682 110726 221683 112016 221683 112017 221683 112012 221684 112013 221684 110724 221684 110724 221685 112013 221685 110726 221685 110724 221686 110726 221686 110725 221686 110725 221687 110726 221687 110729 221687 112020 221688 110727 221688 110726 221688 110726 221689 110727 221689 110728 221689 110726 221690 110728 221690 112028 221690 110729 221691 110726 221691 111088 221691 111088 221692 110726 221692 110731 221692 111088 221693 110731 221693 110730 221693 110730 221694 110731 221694 110809 221694 110730 221695 110809 221695 111089 221695 111089 221696 110809 221696 111091 221696 111091 221697 110809 221697 110808 221697 111091 221698 110808 221698 111093 221698 111093 221699 110808 221699 111095 221699 111095 221700 110808 221700 110810 221700 111095 221701 110810 221701 110740 221701 111239 221702 110741 221702 111245 221702 111245 221703 110741 221703 110732 221703 110810 221704 110811 221704 110740 221704 110740 221705 110811 221705 111236 221705 110740 221706 111236 221706 111235 221706 110732 221707 110733 221707 111342 221707 110740 221708 110734 221708 111368 221708 111342 221709 110735 221709 110732 221709 110732 221710 110735 221710 111246 221710 110732 221711 111246 221711 111245 221711 111235 221712 111384 221712 110740 221712 110740 221713 111384 221713 110736 221713 110740 221714 110736 221714 110734 221714 111357 221715 111359 221715 110732 221715 110732 221716 111359 221716 111360 221716 110732 221717 111360 221717 110733 221717 111368 221718 111367 221718 110740 221718 110740 221719 111367 221719 110737 221719 110740 221720 110737 221720 110738 221720 110738 221721 110739 221721 110740 221721 110740 221722 110739 221722 111364 221722 110740 221723 111364 221723 110732 221723 110732 221724 111364 221724 111355 221724 110732 221725 111355 221725 111357 221725 110732 221726 110741 221726 111081 221726 111081 221727 110741 221727 110742 221727 110743 221728 111078 221728 110742 221728 110742 221729 111078 221729 111079 221729 110742 221730 111079 221730 111081 221730 110751 221731 110744 221731 110743 221731 110743 221732 110744 221732 111076 221732 110743 221733 111076 221733 111078 221733 111874 221734 110745 221734 110752 221734 110752 221735 110745 221735 111873 221735 110752 221736 111873 221736 110746 221736 110746 221737 110747 221737 110752 221737 110752 221738 110747 221738 110748 221738 110752 221739 110748 221739 110749 221739 110749 221740 111869 221740 110752 221740 110752 221741 111869 221741 111866 221741 110752 221742 111866 221742 110750 221742 110750 221743 111851 221743 110752 221743 110752 221744 111851 221744 111062 221744 110752 221745 111062 221745 110751 221745 110751 221746 111062 221746 111074 221746 110751 221747 111074 221747 110744 221747 111874 221748 110752 221748 110753 221748 110753 221749 110752 221749 110831 221749 110753 221750 110831 221750 111821 221750 111823 221751 110754 221751 111805 221751 111805 221752 110754 221752 110830 221752 110755 221753 111797 221753 110830 221753 110755 221754 110830 221754 111795 221754 111791 221755 111792 221755 110830 221755 110830 221756 111792 221756 111794 221756 110830 221757 111794 221757 111795 221757 111789 221758 111791 221758 111787 221758 111787 221759 111791 221759 110830 221759 111787 221760 110830 221760 110756 221760 110756 221761 110830 221761 111107 221761 111797 221762 111798 221762 110830 221762 110830 221763 111798 221763 111799 221763 110830 221764 111799 221764 111805 221764 111107 221765 110830 221765 111108 221765 111108 221766 110830 221766 110758 221766 111108 221767 110758 221767 110757 221767 110757 221768 110758 221768 110759 221768 110757 221769 110759 221769 111111 221769 111111 221770 110759 221770 111112 221770 111112 221771 110759 221771 110760 221771 111112 221772 110760 221772 111114 221772 111114 221773 110760 221773 111115 221773 111115 221774 110760 221774 110761 221774 111115 221775 110761 221775 110768 221775 110878 221776 110859 221776 110767 221776 110767 221777 110859 221777 110766 221777 110761 221778 110762 221778 110768 221778 110768 221779 110762 221779 110763 221779 110768 221780 110763 221780 111257 221780 110766 221781 110771 221781 110764 221781 110768 221782 111403 221782 110765 221782 110764 221783 111435 221783 110766 221783 110766 221784 111435 221784 111252 221784 110766 221785 111252 221785 110767 221785 111257 221786 111386 221786 110768 221786 110768 221787 111386 221787 111390 221787 110768 221788 111390 221788 111403 221788 111429 221789 110769 221789 110766 221789 110766 221790 110769 221790 110770 221790 110766 221791 110770 221791 110771 221791 110765 221792 111397 221792 110768 221792 110768 221793 111397 221793 111395 221793 110768 221794 111395 221794 110772 221794 110772 221795 110773 221795 110768 221795 110768 221796 110773 221796 111413 221796 110768 221797 111413 221797 110766 221797 110766 221798 111413 221798 111427 221798 110766 221799 111427 221799 111429 221799 110775 221800 110785 221800 110774 221800 110774 221801 111021 221801 110775 221801 110775 221802 111021 221802 111019 221802 110775 221803 111019 221803 110776 221803 110777 221804 110797 221804 110801 221804 111048 221805 111641 221805 111050 221805 111050 221806 111641 221806 111643 221806 110776 221807 111018 221807 110775 221807 110775 221808 111018 221808 110778 221808 110775 221809 110778 221809 111570 221809 111631 221810 110787 221810 111629 221810 111629 221811 110787 221811 110798 221811 111636 221812 110781 221812 110779 221812 110779 221813 110781 221813 110787 221813 110779 221814 110787 221814 111633 221814 111633 221815 110787 221815 111631 221815 111636 221816 110780 221816 110781 221816 110781 221817 110780 221817 111641 221817 110781 221818 111641 221818 110782 221818 110782 221819 111641 221819 111044 221819 111048 221820 111046 221820 111641 221820 111641 221821 111046 221821 110783 221821 111641 221822 110783 221822 111044 221822 111507 221823 110784 221823 110798 221823 110775 221824 111621 221824 110785 221824 110785 221825 111621 221825 111622 221825 110785 221826 111622 221826 110801 221826 110801 221827 111622 221827 111623 221827 110801 221828 111623 221828 110777 221828 110786 221829 110787 221829 110792 221829 110786 221830 111506 221830 110787 221830 110787 221831 111506 221831 110788 221831 110787 221832 110788 221832 110798 221832 110798 221833 110788 221833 110789 221833 110798 221834 110789 221834 111507 221834 110797 221835 111625 221835 110790 221835 110790 221836 111625 221836 111626 221836 110790 221837 111626 221837 110791 221837 110792 221838 110793 221838 110786 221838 110786 221839 110793 221839 110794 221839 110786 221840 110794 221840 110795 221840 110795 221841 111033 221841 110786 221841 110786 221842 111033 221842 111031 221842 110786 221843 111031 221843 110796 221843 110790 221844 111515 221844 110797 221844 110797 221845 111515 221845 111516 221845 110797 221846 111516 221846 110801 221846 110801 221847 111516 221847 111517 221847 110784 221848 110799 221848 110798 221848 110798 221849 110799 221849 110800 221849 110798 221850 110800 221850 111627 221850 111627 221851 110800 221851 111511 221851 111627 221852 111511 221852 111626 221852 111626 221853 111511 221853 111513 221853 111626 221854 111513 221854 110791 221854 111517 221855 111519 221855 110801 221855 110801 221856 111519 221856 111522 221856 110801 221857 111522 221857 110802 221857 111008 221858 111006 221858 111522 221858 111522 221859 111006 221859 111004 221859 111522 221860 111004 221860 110802 221860 110803 221861 111011 221861 111522 221861 111522 221862 111011 221862 110804 221862 111522 221863 110804 221863 111008 221863 110837 221864 110818 221864 110892 221864 110844 221865 110817 221865 110805 221865 110844 221866 110805 221866 110731 221866 110805 221867 110806 221867 110731 221867 110731 221868 110806 221868 110807 221868 110731 221869 110807 221869 111222 221869 110808 221870 110809 221870 110810 221870 110810 221871 110809 221871 110731 221871 110810 221872 110731 221872 110811 221872 110811 221873 110731 221873 111222 221873 110811 221874 111222 221874 110812 221874 110813 221875 110814 221875 111222 221875 111222 221876 110814 221876 111234 221876 111222 221877 111234 221877 110812 221877 111224 221878 110815 221878 110919 221878 110919 221879 110815 221879 111225 221879 110844 221880 110816 221880 110817 221880 110817 221881 110816 221881 110892 221881 110817 221882 110892 221882 111225 221882 111225 221883 110892 221883 110818 221883 111225 221884 110818 221884 110919 221884 110741 221885 110751 221885 110742 221885 110742 221886 110751 221886 110743 221886 110741 221887 111239 221887 110751 221887 110751 221888 111239 221888 111240 221888 110751 221889 111240 221889 111244 221889 111244 221890 110819 221890 110751 221890 110751 221891 110819 221891 110820 221891 110751 221892 110820 221892 111242 221892 110822 221893 110751 221893 110919 221893 110919 221894 110751 221894 111242 221894 110919 221895 111242 221895 111224 221895 110828 221896 110825 221896 110760 221896 110821 221897 112114 221897 110822 221897 110822 221898 112114 221898 110823 221898 110822 221899 110823 221899 110751 221899 110751 221900 110823 221900 112116 221900 110751 221901 112116 221901 110752 221901 110752 221902 112116 221902 112118 221902 110824 221903 110762 221903 110825 221903 110825 221904 110762 221904 110761 221904 110825 221905 110761 221905 110760 221905 110822 221906 110916 221906 110821 221906 110821 221907 110916 221907 110826 221907 110821 221908 110826 221908 110827 221908 110760 221909 110759 221909 110828 221909 110828 221910 110759 221910 110758 221910 110828 221911 110758 221911 110829 221911 110829 221912 110758 221912 110830 221912 110829 221913 110830 221913 112119 221913 112119 221914 110830 221914 110754 221914 112119 221915 110754 221915 112118 221915 112118 221916 110754 221916 110831 221916 112118 221917 110831 221917 110752 221917 111217 221918 110832 221918 110835 221918 110835 221919 110832 221919 110833 221919 110835 221920 110833 221920 110834 221920 110914 221921 110835 221921 110915 221921 110915 221922 110835 221922 110827 221922 110915 221923 110827 221923 110836 221923 110836 221924 110827 221924 110826 221924 110837 221925 110892 221925 110920 221925 110920 221926 110892 221926 110848 221926 110920 221927 110848 221927 110850 221927 110835 221928 110838 221928 110824 221928 110824 221929 110838 221929 111255 221929 110824 221930 111255 221930 110762 221930 110834 221931 110839 221931 110835 221931 110835 221932 110839 221932 111256 221932 110835 221933 111256 221933 110838 221933 110840 221934 111215 221934 111217 221934 110883 221935 110901 221935 111215 221935 111215 221936 110901 221936 110841 221936 111215 221937 110841 221937 110842 221937 110843 221938 110845 221938 110844 221938 110844 221939 110845 221939 110846 221939 110844 221940 110846 221940 110816 221940 110914 221941 110913 221941 110835 221941 110835 221942 110913 221942 110910 221942 110835 221943 110910 221943 111217 221943 111217 221944 110910 221944 110929 221944 111217 221945 110929 221945 110840 221945 110840 221946 110927 221946 111215 221946 111215 221947 110927 221947 110926 221947 111215 221948 110926 221948 110883 221948 110883 221949 110926 221949 110847 221949 110848 221950 110889 221950 110850 221950 110850 221951 110889 221951 110849 221951 110850 221952 110849 221952 110922 221952 110922 221953 110849 221953 110888 221953 110922 221954 110888 221954 110923 221954 110923 221955 110888 221955 110851 221955 110923 221956 110851 221956 110852 221956 110852 221957 110851 221957 110885 221957 110852 221958 110885 221958 110926 221958 110926 221959 110885 221959 110884 221959 110926 221960 110884 221960 110847 221960 110842 221961 110898 221961 111215 221961 111215 221962 110898 221962 110853 221962 111215 221963 110853 221963 110844 221963 110844 221964 110853 221964 110896 221964 110844 221965 110896 221965 110843 221965 110721 221966 110854 221966 110855 221966 110855 221967 110854 221967 110858 221967 110865 221968 110731 221968 110856 221968 110856 221969 110731 221969 110726 221969 110856 221970 110726 221970 110857 221970 110857 221971 110726 221971 110709 221971 110857 221972 110709 221972 110855 221972 110855 221973 110709 221973 110723 221973 110855 221974 110723 221974 110721 221974 110854 221975 110710 221975 110858 221975 110858 221976 110710 221976 110711 221976 110858 221977 110711 221977 112120 221977 112120 221978 110711 221978 110859 221978 112120 221979 110859 221979 110860 221979 110860 221980 110859 221980 110878 221980 110867 221981 110946 221981 110844 221981 110873 221982 110862 221982 110861 221982 110861 221983 110862 221983 110863 221983 110861 221984 110863 221984 112125 221984 112125 221985 110863 221985 110731 221985 112125 221986 110731 221986 110864 221986 110864 221987 110731 221987 110865 221987 110863 221988 110866 221988 110731 221988 110731 221989 110866 221989 110950 221989 110731 221990 110950 221990 110844 221990 110844 221991 110950 221991 110948 221991 110844 221992 110948 221992 110867 221992 111226 221993 110868 221993 110881 221993 110881 221994 110868 221994 110872 221994 110946 221995 110869 221995 110844 221995 110844 221996 110869 221996 110870 221996 110844 221997 110870 221997 111215 221997 111215 221998 110870 221998 110943 221998 111215 221999 110943 221999 110940 221999 110940 222000 110871 222000 111215 222000 111215 222001 110871 222001 110960 222001 111215 222002 110960 222002 111229 222002 111229 222003 110960 222003 110872 222003 111229 222004 110872 222004 111228 222004 111228 222005 110872 222005 110868 222005 110873 222006 110861 222006 110954 222006 110954 222007 110861 222007 110874 222007 110954 222008 110874 222008 110875 222008 110875 222009 110874 222009 110876 222009 110875 222010 110876 222010 110877 222010 110877 222011 110876 222011 110860 222011 110877 222012 110860 222012 110957 222012 110957 222013 110860 222013 110878 222013 110957 222014 110878 222014 110881 222014 110881 222015 110878 222015 111250 222015 110881 222016 111250 222016 110879 222016 110879 222017 110880 222017 110881 222017 110881 222018 110880 222018 110882 222018 110881 222019 110882 222019 111226 222019 112160 222020 110883 222020 110847 222020 112160 222021 110847 222021 112161 222021 112161 222022 110847 222022 110884 222022 112161 222023 110884 222023 112163 222023 112163 222024 110884 222024 110885 222024 112163 222025 110885 222025 112165 222025 112165 222026 110885 222026 110851 222026 112165 222027 110851 222027 110886 222027 110886 222028 110851 222028 110887 222028 110887 222029 110851 222029 110888 222029 110887 222030 110888 222030 110849 222030 110887 222031 110849 222031 112150 222031 112150 222032 110849 222032 110889 222032 112150 222033 110889 222033 110890 222033 110890 222034 110889 222034 110848 222034 110890 222035 110848 222035 110891 222035 110891 222036 110848 222036 110892 222036 110891 222037 110892 222037 110893 222037 110893 222038 110892 222038 110894 222038 110894 222039 110892 222039 110816 222039 110894 222040 110816 222040 110846 222040 110894 222041 110846 222041 112155 222041 112155 222042 110846 222042 110845 222042 112155 222043 110845 222043 112156 222043 112156 222044 110845 222044 110843 222044 112156 222045 110843 222045 110895 222045 110895 222046 110843 222046 110896 222046 110895 222047 110896 222047 112158 222047 112158 222048 110896 222048 110897 222048 110897 222049 110896 222049 110853 222049 110897 222050 110853 222050 110898 222050 110897 222051 110898 222051 112167 222051 112167 222052 110898 222052 110842 222052 112167 222053 110842 222053 110899 222053 110899 222054 110842 222054 110841 222054 110899 222055 110841 222055 112169 222055 112169 222056 110841 222056 110901 222056 112169 222057 110901 222057 110900 222057 110900 222058 110901 222058 112160 222058 112160 222059 110901 222059 110883 222059 110905 222060 112159 222060 112166 222060 112159 222061 112151 222061 110902 222061 110902 222062 112151 222062 112152 222062 110902 222063 112152 222063 112153 222063 112159 222064 110902 222064 112166 222064 112166 222065 110902 222065 112149 222065 112166 222066 112149 222066 110903 222066 112166 222067 110904 222067 112168 222067 110905 222068 112166 222068 110906 222068 110906 222069 112166 222069 112168 222069 110906 222070 112168 222070 112170 222070 112154 222071 112157 222071 112149 222071 112149 222072 112157 222072 110907 222072 112149 222073 110907 222073 110903 222073 112164 222074 110908 222074 112162 222074 112162 222075 110908 222075 110905 222075 112162 222076 110905 222076 110909 222076 110909 222077 110905 222077 110906 222077 112140 222078 110929 222078 110910 222078 112140 222079 110910 222079 110911 222079 110911 222080 110910 222080 110913 222080 110911 222081 110913 222081 110912 222081 110912 222082 110913 222082 110914 222082 110912 222083 110914 222083 112142 222083 112142 222084 110914 222084 110915 222084 112142 222085 110915 222085 112137 222085 112137 222086 110915 222086 112128 222086 112128 222087 110915 222087 110836 222087 112128 222088 110836 222088 110826 222088 112128 222089 110826 222089 112129 222089 112129 222090 110826 222090 110916 222090 112129 222091 110916 222091 110917 222091 110917 222092 110916 222092 110822 222092 110917 222093 110822 222093 110918 222093 110918 222094 110822 222094 110919 222094 110918 222095 110919 222095 112127 222095 112127 222096 110919 222096 112132 222096 112132 222097 110919 222097 110818 222097 112132 222098 110818 222098 110837 222098 112132 222099 110837 222099 112133 222099 112133 222100 110837 222100 110920 222100 112133 222101 110920 222101 110921 222101 110921 222102 110920 222102 110850 222102 110921 222103 110850 222103 112136 222103 112136 222104 110850 222104 110922 222104 112136 222105 110922 222105 112138 222105 112138 222106 110922 222106 112144 222106 112144 222107 110922 222107 110923 222107 112144 222108 110923 222108 110852 222108 112144 222109 110852 222109 110924 222109 110924 222110 110852 222110 110926 222110 110924 222111 110926 222111 110925 222111 110925 222112 110926 222112 110927 222112 110925 222113 110927 222113 112147 222113 112147 222114 110927 222114 110840 222114 112147 222115 110840 222115 110928 222115 110928 222116 110840 222116 112140 222116 112140 222117 110840 222117 110929 222117 112134 222118 112135 222118 110930 222118 110930 222119 112135 222119 110938 222119 110930 222120 110938 222120 110937 222120 110939 222121 110932 222121 110936 222121 110936 222122 110932 222122 112148 222122 112145 222123 110931 222123 110932 222123 110932 222124 110931 222124 112146 222124 110932 222125 112146 222125 112148 222125 110935 222126 110933 222126 112130 222126 110934 222127 112143 222127 112141 222127 112141 222128 112143 222128 110936 222128 112141 222129 110936 222129 112139 222129 112139 222130 110936 222130 112148 222130 112130 222131 112131 222131 110935 222131 110935 222132 112131 222132 110937 222132 110935 222133 110937 222133 110936 222133 110936 222134 110937 222134 110938 222134 110936 222135 110938 222135 110939 222135 110959 222136 110960 222136 110871 222136 110959 222137 110871 222137 110941 222137 110941 222138 110871 222138 110940 222138 110941 222139 110940 222139 112182 222139 112182 222140 110940 222140 110943 222140 112182 222141 110943 222141 110942 222141 110942 222142 110943 222142 110870 222142 110942 222143 110870 222143 110944 222143 110944 222144 110870 222144 110945 222144 110945 222145 110870 222145 110869 222145 110945 222146 110869 222146 110946 222146 110945 222147 110946 222147 112172 222147 112172 222148 110946 222148 110867 222148 112172 222149 110867 222149 110947 222149 110947 222150 110867 222150 110948 222150 110947 222151 110948 222151 110949 222151 110949 222152 110948 222152 110950 222152 110949 222153 110950 222153 112176 222153 112176 222154 110950 222154 110951 222154 110951 222155 110950 222155 110866 222155 110951 222156 110866 222156 110863 222156 110951 222157 110863 222157 110952 222157 110952 222158 110863 222158 110862 222158 110952 222159 110862 222159 112178 222159 112178 222160 110862 222160 110873 222160 112178 222161 110873 222161 110953 222161 110953 222162 110873 222162 110954 222162 110953 222163 110954 222163 112180 222163 112180 222164 110954 222164 110955 222164 110955 222165 110954 222165 110875 222165 110955 222166 110875 222166 110877 222166 110955 222167 110877 222167 110956 222167 110956 222168 110877 222168 110957 222168 110956 222169 110957 222169 110958 222169 110958 222170 110957 222170 110881 222170 110958 222171 110881 222171 112185 222171 112185 222172 110881 222172 110872 222172 112185 222173 110872 222173 112188 222173 112188 222174 110872 222174 110959 222174 110959 222175 110872 222175 110960 222175 110966 222176 112173 222176 110964 222176 110961 222177 110962 222177 112186 222177 110964 222178 112173 222178 112187 222178 112175 222179 110963 222179 112174 222179 112174 222180 110963 222180 112171 222180 112186 222181 112187 222181 110961 222181 110961 222182 112187 222182 112173 222182 110961 222183 112173 222183 112184 222183 112184 222184 112173 222184 112174 222184 112184 222185 112174 222185 110968 222185 110968 222186 112174 222186 112171 222186 112181 222187 112183 222187 110964 222187 110964 222188 112183 222188 110965 222188 110964 222189 110965 222189 110966 222189 112179 222190 110967 222190 110969 222190 110969 222191 110967 222191 110968 222191 110969 222192 110968 222192 112177 222192 112177 222193 110968 222193 112171 222193 110983 222194 110970 222194 110971 222194 110971 222195 110970 222195 111123 222195 111454 222196 111462 222196 110973 222196 111125 222197 111442 222197 111454 222197 111125 222198 111454 222198 110972 222198 110972 222199 111454 222199 110973 222199 110972 222200 110973 222200 110979 222200 110971 222201 111123 222201 110974 222201 110974 222202 111123 222202 111134 222202 110974 222203 111134 222203 110975 222203 110975 222204 111134 222204 110976 222204 110975 222205 110976 222205 110977 222205 110977 222206 110976 222206 111133 222206 110977 222207 111133 222207 110978 222207 110978 222208 111133 222208 110979 222208 110978 222209 110979 222209 111039 222209 111039 222210 110979 222210 110973 222210 111654 222211 111117 222211 111664 222211 111664 222212 111117 222212 110980 222212 111664 222213 110980 222213 111651 222213 110981 222214 111056 222214 110980 222214 110980 222215 111056 222215 111058 222215 110980 222216 111058 222216 111651 222216 110970 222217 110983 222217 110982 222217 110982 222218 110983 222218 110984 222218 110982 222219 110984 222219 110985 222219 110985 222220 110984 222220 111054 222220 110985 222221 111054 222221 111119 222221 111119 222222 111054 222222 111055 222222 111119 222223 111055 222223 110981 222223 110981 222224 111055 222224 110986 222224 110981 222225 110986 222225 111056 222225 110987 222226 111101 222226 111537 222226 111537 222227 111101 222227 111100 222227 111537 222228 111100 222228 110991 222228 110988 222229 110989 222229 111100 222229 111100 222230 110989 222230 110990 222230 111100 222231 110990 222231 110991 222231 111083 222232 111015 222232 111096 222232 111096 222233 111015 222233 111013 222233 111096 222234 111013 222234 111097 222234 111097 222235 111013 222235 110992 222235 111097 222236 110992 222236 110993 222236 110993 222237 110992 222237 110994 222237 110993 222238 110994 222238 110988 222238 110988 222239 110994 222239 111014 222239 110988 222240 111014 222240 110989 222240 111562 222241 110995 222241 111023 222241 110996 222242 111060 222242 111562 222242 110996 222243 111562 222243 111067 222243 111067 222244 111562 222244 111023 222244 111067 222245 111023 222245 111001 222245 110997 222246 111002 222246 110998 222246 110998 222247 111002 222247 110999 222247 110998 222248 110999 222248 111028 222248 111028 222249 110999 222249 111069 222249 111028 222250 111069 222250 111027 222250 111027 222251 111069 222251 111068 222251 111027 222252 111068 222252 111000 222252 111000 222253 111068 222253 111001 222253 111000 222254 111001 222254 111025 222254 111025 222255 111001 222255 111023 222255 111015 222256 111083 222256 110997 222256 110997 222257 111083 222257 111002 222257 111015 222258 111016 222258 111003 222258 111016 222259 110801 222259 110802 222259 111016 222260 110802 222260 111003 222260 111003 222261 110802 222261 111004 222261 111003 222262 111004 222262 111005 222262 111005 222263 111004 222263 111006 222263 111005 222264 111006 222264 111007 222264 111007 222265 111006 222265 111008 222265 111007 222266 111008 222266 111009 222266 111009 222267 111008 222267 110804 222267 111009 222268 110804 222268 111010 222268 111010 222269 110804 222269 111011 222269 111010 222270 111011 222270 111012 222270 111011 222271 110803 222271 111012 222271 111012 222272 110803 222272 111526 222272 111012 222273 111526 222273 111533 222273 111015 222274 111003 222274 111013 222274 111013 222275 111003 222275 111005 222275 111013 222276 111005 222276 110992 222276 110992 222277 111005 222277 111007 222277 110992 222278 111007 222278 110994 222278 110994 222279 111007 222279 111009 222279 110994 222280 111009 222280 111014 222280 111014 222281 111009 222281 111010 222281 111014 222282 111010 222282 110989 222282 110989 222283 111010 222283 111012 222283 110989 222284 111012 222284 110990 222284 110990 222285 111012 222285 111533 222285 110990 222286 111533 222286 110991 222286 111015 222287 110997 222287 111030 222287 111015 222288 111030 222288 111016 222288 111016 222289 111030 222289 110785 222289 111016 222290 110785 222290 110801 222290 111572 222291 111571 222291 111017 222291 111571 222292 111570 222292 110778 222292 111023 222293 110995 222293 111572 222293 111571 222294 110778 222294 111017 222294 111017 222295 110778 222295 111018 222295 111017 222296 111018 222296 111024 222296 111024 222297 111018 222297 110776 222297 111024 222298 110776 222298 111026 222298 111026 222299 110776 222299 111019 222299 111026 222300 111019 222300 111020 222300 111020 222301 111019 222301 111021 222301 111020 222302 111021 222302 111029 222302 111029 222303 111021 222303 110774 222303 111029 222304 110774 222304 111022 222304 111022 222305 110774 222305 110785 222305 111022 222306 110785 222306 111030 222306 111572 222307 111017 222307 111023 222307 111023 222308 111017 222308 111024 222308 111023 222309 111024 222309 111025 222309 111025 222310 111024 222310 111026 222310 111025 222311 111026 222311 111000 222311 111000 222312 111026 222312 111020 222312 111000 222313 111020 222313 111027 222313 111027 222314 111020 222314 111029 222314 111027 222315 111029 222315 111028 222315 111028 222316 111029 222316 111022 222316 111028 222317 111022 222317 110998 222317 110998 222318 111022 222318 111030 222318 110998 222319 111030 222319 110997 222319 111037 222320 111032 222320 111038 222320 111032 222321 110796 222321 111031 222321 110973 222322 111462 222322 111037 222322 111032 222323 111031 222323 111038 222323 111038 222324 111031 222324 111033 222324 111038 222325 111033 222325 111034 222325 111034 222326 111033 222326 110795 222326 111034 222327 110795 222327 111035 222327 111035 222328 110795 222328 110794 222328 111035 222329 110794 222329 111040 222329 111040 222330 110794 222330 110793 222330 111040 222331 110793 222331 111036 222331 111036 222332 110793 222332 110792 222332 111036 222333 110792 222333 111041 222333 111041 222334 110792 222334 110787 222334 111041 222335 110787 222335 111042 222335 111037 222336 111038 222336 110973 222336 110973 222337 111038 222337 111034 222337 110973 222338 111034 222338 111039 222338 111039 222339 111034 222339 111035 222339 111039 222340 111035 222340 110978 222340 110978 222341 111035 222341 111040 222341 110978 222342 111040 222342 110977 222342 110977 222343 111040 222343 111036 222343 110977 222344 111036 222344 110975 222344 110975 222345 111036 222345 111041 222345 110975 222346 111041 222346 110974 222346 110974 222347 111041 222347 111042 222347 110974 222348 111042 222348 110971 222348 110983 222349 110971 222349 111042 222349 110983 222350 111042 222350 111043 222350 111043 222351 111042 222351 110787 222351 111043 222352 110787 222352 110781 222352 110983 222353 111043 222353 111052 222353 111043 222354 110781 222354 110782 222354 111043 222355 110782 222355 111052 222355 111052 222356 110782 222356 111044 222356 111052 222357 111044 222357 111053 222357 111053 222358 111044 222358 110783 222358 111053 222359 110783 222359 111045 222359 111045 222360 110783 222360 111046 222360 111045 222361 111046 222361 111047 222361 111047 222362 111046 222362 111048 222362 111047 222363 111048 222363 111049 222363 111049 222364 111048 222364 111050 222364 111049 222365 111050 222365 111057 222365 111050 222366 111643 222366 111057 222366 111057 222367 111643 222367 111051 222367 111057 222368 111051 222368 111650 222368 110983 222369 111052 222369 110984 222369 110984 222370 111052 222370 111053 222370 110984 222371 111053 222371 111054 222371 111054 222372 111053 222372 111045 222372 111054 222373 111045 222373 111055 222373 111055 222374 111045 222374 111047 222374 111055 222375 111047 222375 110986 222375 110986 222376 111047 222376 111049 222376 110986 222377 111049 222377 111056 222377 111056 222378 111049 222378 111057 222378 111056 222379 111057 222379 111058 222379 111058 222380 111057 222380 111650 222380 111058 222381 111650 222381 111651 222381 111059 222382 111060 222382 110996 222382 111828 222383 111829 222383 111061 222383 111852 222384 111072 222384 111066 222384 111062 222385 111063 222385 111072 222385 111063 222386 111064 222386 111072 222386 111072 222387 111064 222387 111065 222387 111072 222388 111065 222388 111066 222388 111059 222389 111072 222389 111061 222389 111061 222390 111072 222390 111852 222390 111061 222391 111852 222391 111828 222391 111059 222392 110996 222392 111072 222392 111072 222393 110996 222393 111067 222393 111072 222394 111067 222394 111073 222394 111073 222395 111067 222395 111001 222395 111073 222396 111001 222396 111075 222396 111075 222397 111001 222397 111068 222397 111075 222398 111068 222398 111077 222398 111077 222399 111068 222399 111069 222399 111077 222400 111069 222400 111070 222400 111070 222401 111069 222401 110999 222401 111070 222402 110999 222402 111071 222402 111071 222403 110999 222403 111002 222403 111071 222404 111002 222404 111080 222404 111062 222405 111072 222405 111074 222405 111074 222406 111072 222406 111073 222406 111074 222407 111073 222407 110744 222407 110744 222408 111073 222408 111075 222408 110744 222409 111075 222409 111076 222409 111076 222410 111075 222410 111077 222410 111076 222411 111077 222411 111078 222411 111078 222412 111077 222412 111070 222412 111078 222413 111070 222413 111079 222413 111079 222414 111070 222414 111071 222414 111079 222415 111071 222415 111081 222415 111081 222416 111071 222416 111080 222416 111081 222417 111080 222417 110732 222417 110740 222418 110732 222418 111080 222418 110740 222419 111080 222419 111082 222419 111082 222420 111080 222420 111002 222420 111082 222421 111002 222421 111083 222421 111082 222422 111083 222422 111096 222422 111973 222423 111102 222423 111985 222423 111985 222424 111102 222424 111084 222424 111985 222425 111084 222425 111085 222425 111088 222426 111973 222426 111086 222426 111088 222427 111086 222427 111087 222427 111087 222428 111974 222428 111088 222428 111088 222429 111974 222429 111976 222429 111088 222430 111976 222430 110729 222430 111973 222431 111088 222431 111102 222431 111102 222432 111088 222432 110730 222432 111102 222433 110730 222433 111099 222433 111099 222434 110730 222434 111089 222434 111099 222435 111089 222435 111090 222435 111090 222436 111089 222436 111091 222436 111090 222437 111091 222437 111092 222437 111092 222438 111091 222438 111093 222438 111092 222439 111093 222439 111098 222439 111098 222440 111093 222440 111095 222440 111098 222441 111095 222441 111094 222441 111094 222442 111095 222442 110740 222442 111094 222443 110740 222443 111082 222443 111101 222444 110987 222444 111103 222444 111082 222445 111096 222445 111094 222445 111094 222446 111096 222446 111097 222446 111094 222447 111097 222447 111098 222447 111098 222448 111097 222448 110993 222448 111098 222449 110993 222449 111092 222449 111092 222450 110993 222450 110988 222450 111092 222451 110988 222451 111090 222451 111090 222452 110988 222452 111100 222452 111090 222453 111100 222453 111099 222453 111099 222454 111100 222454 111101 222454 111099 222455 111101 222455 111102 222455 111102 222456 111101 222456 111103 222456 111102 222457 111103 222457 111084 222457 111118 222458 110970 222458 110982 222458 111104 222459 111109 222459 111751 222459 111751 222460 111109 222460 111105 222460 111751 222461 111105 222461 111686 222461 111108 222462 111104 222462 111753 222462 111108 222463 111753 222463 111754 222463 111754 222464 111106 222464 111108 222464 111108 222465 111106 222465 111755 222465 111108 222466 111755 222466 111107 222466 111104 222467 111108 222467 111109 222467 111109 222468 111108 222468 110757 222468 111109 222469 110757 222469 111121 222469 111121 222470 110757 222470 111111 222470 111121 222471 111111 222471 111110 222471 111110 222472 111111 222472 111112 222472 111110 222473 111112 222473 111113 222473 111113 222474 111112 222474 111114 222474 111113 222475 111114 222475 111120 222475 111120 222476 111114 222476 111115 222476 111120 222477 111115 222477 111116 222477 111116 222478 111115 222478 110768 222478 111116 222479 110768 222479 111118 222479 111117 222480 111654 222480 111122 222480 111118 222481 110982 222481 111116 222481 111116 222482 110982 222482 110985 222482 111116 222483 110985 222483 111120 222483 111120 222484 110985 222484 111119 222484 111120 222485 111119 222485 111113 222485 111113 222486 111119 222486 110981 222486 111113 222487 110981 222487 111110 222487 111110 222488 110981 222488 110980 222488 111110 222489 110980 222489 111121 222489 111121 222490 110980 222490 111117 222490 111121 222491 111117 222491 111109 222491 111109 222492 111117 222492 111122 222492 111109 222493 111122 222493 111105 222493 110768 222494 110766 222494 111140 222494 110768 222495 111140 222495 111118 222495 111118 222496 111140 222496 111123 222496 111118 222497 111123 222497 110970 222497 111124 222498 111442 222498 111125 222498 112046 222499 112047 222499 111441 222499 111126 222500 111130 222500 112098 222500 111127 222501 111128 222501 111130 222501 111128 222502 111129 222502 111130 222502 111130 222503 111129 222503 112096 222503 111130 222504 112096 222504 112098 222504 111124 222505 111130 222505 111441 222505 111441 222506 111130 222506 111126 222506 111441 222507 111126 222507 112046 222507 111124 222508 111125 222508 111130 222508 111130 222509 111125 222509 110972 222509 111130 222510 110972 222510 111135 222510 111135 222511 110972 222511 110979 222511 111135 222512 110979 222512 111131 222512 111131 222513 110979 222513 111133 222513 111131 222514 111133 222514 111132 222514 111132 222515 111133 222515 110976 222515 111132 222516 110976 222516 111136 222516 111136 222517 110976 222517 111134 222517 111136 222518 111134 222518 111139 222518 111139 222519 111134 222519 111123 222519 111139 222520 111123 222520 111140 222520 111127 222521 111130 222521 110719 222521 110719 222522 111130 222522 111135 222522 110719 222523 111135 222523 110712 222523 110712 222524 111135 222524 111131 222524 110712 222525 111131 222525 110713 222525 110713 222526 111131 222526 111132 222526 110713 222527 111132 222527 110714 222527 110714 222528 111132 222528 111136 222528 110714 222529 111136 222529 111137 222529 111137 222530 111136 222530 111139 222530 111137 222531 111139 222531 111138 222531 111138 222532 111139 222532 111140 222532 111138 222533 111140 222533 110766 222533 111147 222534 111958 222534 111141 222534 111141 222535 111958 222535 112126 222535 111142 222536 111963 222536 111143 222536 111143 222537 111963 222537 111965 222537 111143 222538 111965 222538 111144 222538 111142 222539 111143 222539 111962 222539 111962 222540 111143 222540 111146 222540 111962 222541 111146 222541 111961 222541 111958 222542 111959 222542 112126 222542 112126 222543 111959 222543 111145 222543 112126 222544 111145 222544 111146 222544 111146 222545 111145 222545 111960 222545 111146 222546 111960 222546 111961 222546 111147 222547 111141 222547 111956 222547 111956 222548 111141 222548 111148 222548 111956 222549 111148 222549 111150 222549 112124 222550 111149 222550 111148 222550 111148 222551 111149 222551 111955 222551 111148 222552 111955 222552 111150 222552 111156 222553 111907 222553 111157 222553 112032 222554 112031 222554 111151 222554 111151 222555 112031 222555 112044 222555 111151 222556 112044 222556 112066 222556 111965 222557 111152 222557 111144 222557 111144 222558 111152 222558 111967 222558 111144 222559 111967 222559 112121 222559 111967 222560 111969 222560 112121 222560 112121 222561 111969 222561 111970 222561 112121 222562 111970 222562 111153 222562 111153 222563 111970 222563 112032 222563 111153 222564 112032 222564 112122 222564 112122 222565 112032 222565 111151 222565 112122 222566 111151 222566 112123 222566 112123 222567 111151 222567 111155 222567 112123 222568 111155 222568 111154 222568 111154 222569 111155 222569 112038 222569 111154 222570 112038 222570 111156 222570 112124 222571 111154 222571 111149 222571 111149 222572 111154 222572 111156 222572 111149 222573 111156 222573 111896 222573 111896 222574 111156 222574 111157 222574 111900 222575 111158 222575 111924 222575 111924 222576 111158 222576 111487 222576 111924 222577 111487 222577 111159 222577 111159 222578 111487 222578 111160 222578 111159 222579 111160 222579 111926 222579 111926 222580 111160 222580 111161 222580 111926 222581 111161 222581 111927 222581 111927 222582 111161 222582 111483 222582 111927 222583 111483 222583 111162 222583 111162 222584 111483 222584 111482 222584 111162 222585 111482 222585 111163 222585 111163 222586 111482 222586 111481 222586 111163 222587 111481 222587 111164 222587 111164 222588 111481 222588 111480 222588 111164 222589 111480 222589 111165 222589 111165 222590 111480 222590 111479 222590 111165 222591 111479 222591 111166 222591 111166 222592 111479 222592 111167 222592 111166 222593 111167 222593 111934 222593 111934 222594 111167 222594 111168 222594 111934 222595 111168 222595 111936 222595 111936 222596 111168 222596 111169 222596 111936 222597 111169 222597 111937 222597 111937 222598 111169 222598 111170 222598 111937 222599 111170 222599 111171 222599 111171 222600 111170 222600 111172 222600 111171 222601 111172 222601 111174 222601 111174 222602 111172 222602 111173 222602 111174 222603 111173 222603 111175 222603 111175 222604 111173 222604 111475 222604 111175 222605 111475 222605 112022 222605 112022 222606 111475 222606 111469 222606 111536 222607 111158 222607 111541 222607 111541 222608 111158 222608 111900 222608 111541 222609 111900 222609 111899 222609 111469 222610 111467 222610 112022 222610 112022 222611 111467 222611 111176 222611 112022 222612 111176 222612 112037 222612 111841 222613 111827 222613 111844 222613 111748 222614 111182 222614 112115 222614 111177 222615 111180 222615 111178 222615 111178 222616 111180 222616 112112 222616 111178 222617 112112 222617 111189 222617 111841 222618 111844 222618 111842 222618 111689 222619 111179 222619 111807 222619 111807 222620 111179 222620 111673 222620 111184 222621 111186 222621 111740 222621 111740 222622 111186 222622 111181 222622 111177 222623 111735 222623 111180 222623 111180 222624 111735 222624 111737 222624 111180 222625 111737 222625 111181 222625 111181 222626 111737 222626 111738 222626 111181 222627 111738 222627 111740 222627 112115 222628 111182 222628 112117 222628 112117 222629 111182 222629 111193 222629 112117 222630 111193 222630 111192 222630 111748 222631 112115 222631 111747 222631 111747 222632 112115 222632 112113 222632 111747 222633 112113 222633 111183 222633 111183 222634 112113 222634 111744 222634 111744 222635 112113 222635 111194 222635 111744 222636 111194 222636 111196 222636 111184 222637 111185 222637 111186 222637 111186 222638 111185 222638 111187 222638 111186 222639 111187 222639 111188 222639 111673 222640 111178 222640 111807 222640 111807 222641 111178 222641 111189 222641 111807 222642 111189 222642 111806 222642 111806 222643 111189 222643 111190 222643 111806 222644 111190 222644 111191 222644 111191 222645 111190 222645 111192 222645 111191 222646 111192 222646 111844 222646 111844 222647 111192 222647 111193 222647 111844 222648 111193 222648 111842 222648 111187 222649 111741 222649 111188 222649 111188 222650 111741 222650 111195 222650 111188 222651 111195 222651 111194 222651 111194 222652 111195 222652 111743 222652 111194 222653 111743 222653 111196 222653 111700 222654 111638 222654 111197 222654 111197 222655 111638 222655 111601 222655 111197 222656 111601 222656 111703 222656 111703 222657 111601 222657 111600 222657 111703 222658 111600 222658 111198 222658 111198 222659 111600 222659 111199 222659 111198 222660 111199 222660 111704 222660 111704 222661 111199 222661 111200 222661 111704 222662 111200 222662 111201 222662 111201 222663 111200 222663 111598 222663 111201 222664 111598 222664 111707 222664 111707 222665 111598 222665 111597 222665 111707 222666 111597 222666 111202 222666 111202 222667 111597 222667 111596 222667 111202 222668 111596 222668 111709 222668 111709 222669 111596 222669 111204 222669 111709 222670 111204 222670 111203 222670 111203 222671 111204 222671 111595 222671 111203 222672 111595 222672 111205 222672 111205 222673 111595 222673 111594 222673 111205 222674 111594 222674 111711 222674 111711 222675 111594 222675 111592 222675 111711 222676 111592 222676 111206 222676 111206 222677 111592 222677 111207 222677 111206 222678 111207 222678 111208 222678 111208 222679 111207 222679 111590 222679 111208 222680 111590 222680 111715 222680 111715 222681 111590 222681 111588 222681 111715 222682 111588 222682 111209 222682 111209 222683 111588 222683 111210 222683 111209 222684 111210 222684 111717 222684 111717 222685 111210 222685 111212 222685 111211 222686 111638 222686 111659 222686 111659 222687 111638 222687 111700 222687 111659 222688 111700 222688 111680 222688 111212 222689 111213 222689 111717 222689 111717 222690 111213 222690 111214 222690 111717 222691 111214 222691 111566 222691 111229 222692 111216 222692 111215 222692 111215 222693 111216 222693 111230 222693 111215 222694 111230 222694 111217 222694 111225 222695 111314 222695 110817 222695 110817 222696 111314 222696 111218 222696 110817 222697 111218 222697 110805 222697 110805 222698 111218 222698 111323 222698 111221 222699 111219 222699 111220 222699 110805 222700 111323 222700 110806 222700 110806 222701 111323 222701 111221 222701 110806 222702 111221 222702 110807 222702 110807 222703 111221 222703 111220 222703 110807 222704 111220 222704 111222 222704 111241 222705 111223 222705 111313 222705 111224 222706 111242 222706 111241 222706 111241 222707 111313 222707 111224 222707 111224 222708 111313 222708 111311 222708 111224 222709 111311 222709 110815 222709 110815 222710 111311 222710 111314 222710 110815 222711 111314 222711 111225 222711 111251 222712 111266 222712 111275 222712 110868 222713 111226 222713 111251 222713 111251 222714 111275 222714 110868 222714 110868 222715 111275 222715 111227 222715 110868 222716 111227 222716 111228 222716 111228 222717 111227 222717 111216 222717 111228 222718 111216 222718 111229 222718 111217 222719 111230 222719 111231 222719 111232 222720 111296 222720 111258 222720 111217 222721 111231 222721 110832 222721 110832 222722 111231 222722 111232 222722 110832 222723 111232 222723 110833 222723 110833 222724 111232 222724 111258 222724 110833 222725 111258 222725 110834 222725 111222 222726 111220 222726 110813 222726 110813 222727 111220 222727 111233 222727 110811 222728 110812 222728 111236 222728 111236 222729 110812 222729 111234 222729 111236 222730 111234 222730 111233 222730 111233 222731 111234 222731 110814 222731 111233 222732 110814 222732 110813 222732 111235 222733 111236 222733 111237 222733 111237 222734 111236 222734 111233 222734 111237 222735 111233 222735 111332 222735 111332 222736 111233 222736 111336 222736 111336 222737 111233 222737 111238 222737 111238 222738 111233 222738 111220 222738 111238 222739 111220 222739 111219 222739 110819 222740 111244 222740 111243 222740 111240 222741 111239 222741 111245 222741 111240 222742 111245 222742 111244 222742 110819 222743 111243 222743 110820 222743 111241 222744 111242 222744 110820 222744 110820 222745 111243 222745 111241 222745 111241 222746 111243 222746 111297 222746 111241 222747 111297 222747 111223 222747 111244 222748 111245 222748 111243 222748 111243 222749 111245 222749 111246 222749 111243 222750 111246 222750 111247 222750 111247 222751 111248 222751 111243 222751 111243 222752 111248 222752 111249 222752 111243 222753 111249 222753 111297 222753 110880 222754 110879 222754 111253 222754 111250 222755 110878 222755 110767 222755 111250 222756 110767 222756 110879 222756 110880 222757 111253 222757 110882 222757 111251 222758 111226 222758 110882 222758 110882 222759 111253 222759 111251 222759 111251 222760 111253 222760 111262 222760 111251 222761 111262 222761 111266 222761 110879 222762 110767 222762 111253 222762 111253 222763 110767 222763 111252 222763 111253 222764 111252 222764 111263 222764 111263 222765 111264 222765 111253 222765 111253 222766 111264 222766 111265 222766 111253 222767 111265 222767 111262 222767 110834 222768 111258 222768 110839 222768 110839 222769 111258 222769 111254 222769 110762 222770 111255 222770 110763 222770 110763 222771 111255 222771 110838 222771 110763 222772 110838 222772 111254 222772 111254 222773 110838 222773 111256 222773 111254 222774 111256 222774 110839 222774 111257 222775 110763 222775 111289 222775 111289 222776 110763 222776 111254 222776 111289 222777 111254 222777 111290 222777 111290 222778 111254 222778 111294 222778 111294 222779 111254 222779 111259 222779 111259 222780 111254 222780 111258 222780 111259 222781 111258 222781 111296 222781 111438 222782 111260 222782 111261 222782 111261 222783 111260 222783 111262 222783 111261 222784 111262 222784 111432 222784 111263 222785 111433 222785 111264 222785 111264 222786 111433 222786 111432 222786 111264 222787 111432 222787 111265 222787 111265 222788 111432 222788 111262 222788 111252 222789 111436 222789 111263 222789 111263 222790 111436 222790 111434 222790 111263 222791 111434 222791 111433 222791 111266 222792 111262 222792 111267 222792 111267 222793 111262 222793 111260 222793 111267 222794 111260 222794 111268 222794 111268 222795 111260 222795 111438 222795 111268 222796 111438 222796 111270 222796 111277 222797 111216 222797 111227 222797 111267 222798 111268 222798 111271 222798 111273 222799 111418 222799 111272 222799 111417 222800 111411 222800 111269 222800 111268 222801 111270 222801 111271 222801 111271 222802 111270 222802 111421 222802 111271 222803 111421 222803 111272 222803 111272 222804 111421 222804 111419 222804 111272 222805 111419 222805 111273 222805 111274 222806 111271 222806 111276 222806 111276 222807 111271 222807 111272 222807 111276 222808 111272 222808 111269 222808 111269 222809 111272 222809 111418 222809 111269 222810 111418 222810 111417 222810 111274 222811 111277 222811 111271 222811 111271 222812 111277 222812 111227 222812 111271 222813 111227 222813 111267 222813 111267 222814 111227 222814 111275 222814 111267 222815 111275 222815 111266 222815 111411 222816 111393 222816 111269 222816 111269 222817 111393 222817 111284 222817 111269 222818 111284 222818 111276 222818 111276 222819 111284 222819 111285 222819 111276 222820 111285 222820 111274 222820 111274 222821 111285 222821 111278 222821 111274 222822 111278 222822 111277 222822 111277 222823 111278 222823 111279 222823 111277 222824 111279 222824 111216 222824 111216 222825 111279 222825 111230 222825 111286 222826 111408 222826 111280 222826 111391 222827 111281 222827 111283 222827 111283 222828 111281 222828 111401 222828 111401 222829 111282 222829 111283 222829 111283 222830 111282 222830 111400 222830 111283 222831 111400 222831 111287 222831 111393 222832 111391 222832 111284 222832 111284 222833 111391 222833 111283 222833 111284 222834 111283 222834 111285 222834 111285 222835 111283 222835 111287 222835 111285 222836 111287 222836 111278 222836 111278 222837 111287 222837 111279 222837 111279 222838 111287 222838 111231 222838 111279 222839 111231 222839 111230 222839 111400 222840 111286 222840 111287 222840 111287 222841 111286 222841 111280 222841 111287 222842 111280 222842 111231 222842 111231 222843 111280 222843 111292 222843 111231 222844 111292 222844 111232 222844 111232 222845 111292 222845 111296 222845 111388 222846 111295 222846 111389 222846 111385 222847 111257 222847 111289 222847 111385 222848 111289 222848 111288 222848 111288 222849 111289 222849 111290 222849 111288 222850 111290 222850 111291 222850 111291 222851 111290 222851 111294 222851 111291 222852 111294 222852 111293 222852 111295 222853 111292 222853 111389 222853 111389 222854 111292 222854 111280 222854 111389 222855 111280 222855 111408 222855 111293 222856 111294 222856 111388 222856 111388 222857 111294 222857 111259 222857 111388 222858 111259 222858 111295 222858 111295 222859 111259 222859 111296 222859 111295 222860 111296 222860 111292 222860 111344 222861 111300 222861 111339 222861 111339 222862 111300 222862 111297 222862 111339 222863 111297 222863 111298 222863 111247 222864 111340 222864 111248 222864 111248 222865 111340 222865 111298 222865 111248 222866 111298 222866 111249 222866 111249 222867 111298 222867 111297 222867 111246 222868 111299 222868 111247 222868 111247 222869 111299 222869 111341 222869 111247 222870 111341 222870 111340 222870 111223 222871 111297 222871 111312 222871 111312 222872 111297 222872 111300 222872 111312 222873 111300 222873 111301 222873 111301 222874 111300 222874 111344 222874 111301 222875 111344 222875 111307 222875 111312 222876 111301 222876 111306 222876 111315 222877 111314 222877 111311 222877 111302 222878 111309 222878 111303 222878 111304 222879 111362 222879 111318 222879 111302 222880 111303 222880 111305 222880 111301 222881 111307 222881 111306 222881 111306 222882 111307 222882 111308 222882 111306 222883 111308 222883 111303 222883 111303 222884 111308 222884 111350 222884 111303 222885 111350 222885 111305 222885 111310 222886 111306 222886 111317 222886 111317 222887 111306 222887 111303 222887 111317 222888 111303 222888 111318 222888 111318 222889 111303 222889 111309 222889 111318 222890 111309 222890 111304 222890 111310 222891 111315 222891 111306 222891 111306 222892 111315 222892 111311 222892 111306 222893 111311 222893 111312 222893 111312 222894 111311 222894 111313 222894 111312 222895 111313 222895 111223 222895 111218 222896 111314 222896 111324 222896 111324 222897 111314 222897 111315 222897 111324 222898 111315 222898 111328 222898 111328 222899 111315 222899 111310 222899 111328 222900 111310 222900 111327 222900 111327 222901 111310 222901 111317 222901 111327 222902 111317 222902 111316 222902 111316 222903 111317 222903 111318 222903 111316 222904 111318 222904 111361 222904 111361 222905 111318 222905 111362 222905 111375 222906 111320 222906 111319 222906 111319 222907 111320 222907 111321 222907 111321 222908 111379 222908 111319 222908 111319 222909 111379 222909 111322 222909 111319 222910 111322 222910 111329 222910 111219 222911 111221 222911 111335 222911 111335 222912 111221 222912 111323 222912 111335 222913 111323 222913 111325 222913 111218 222914 111324 222914 111323 222914 111323 222915 111324 222915 111329 222915 111323 222916 111329 222916 111325 222916 111325 222917 111329 222917 111322 222917 111325 222918 111322 222918 111326 222918 111361 222919 111375 222919 111316 222919 111316 222920 111375 222920 111319 222920 111316 222921 111319 222921 111327 222921 111327 222922 111319 222922 111329 222922 111327 222923 111329 222923 111328 222923 111328 222924 111329 222924 111324 222924 111383 222925 111337 222925 111334 222925 111330 222926 111235 222926 111237 222926 111330 222927 111237 222927 111382 222927 111382 222928 111237 222928 111332 222928 111382 222929 111332 222929 111331 222929 111331 222930 111332 222930 111336 222930 111331 222931 111336 222931 111333 222931 111337 222932 111335 222932 111334 222932 111334 222933 111335 222933 111325 222933 111334 222934 111325 222934 111326 222934 111333 222935 111336 222935 111383 222935 111383 222936 111336 222936 111238 222936 111383 222937 111238 222937 111337 222937 111337 222938 111238 222938 111219 222938 111337 222939 111219 222939 111335 222939 110735 222940 111342 222940 111338 222940 111344 222941 111339 222941 111338 222941 111338 222942 111339 222942 111298 222942 111298 222943 111340 222943 111338 222943 111338 222944 111340 222944 111341 222944 111338 222945 111341 222945 110735 222945 110735 222946 111341 222946 111299 222946 110735 222947 111299 222947 111246 222947 111342 222948 110733 222948 111338 222948 111338 222949 110733 222949 111343 222949 111338 222950 111343 222950 111344 222950 111344 222951 111343 222951 111345 222951 111344 222952 111345 222952 111307 222952 111307 222953 111345 222953 111346 222953 111347 222954 111362 222954 111304 222954 111364 222955 111348 222955 111356 222955 111348 222956 111347 222956 111351 222956 111351 222957 111347 222957 111304 222957 111351 222958 111304 222958 111349 222958 111349 222959 111304 222959 111309 222959 111309 222960 111302 222960 111349 222960 111349 222961 111302 222961 111305 222961 111349 222962 111305 222962 111353 222962 111353 222963 111305 222963 111350 222963 111353 222964 111350 222964 111346 222964 111346 222965 111350 222965 111308 222965 111346 222966 111308 222966 111307 222966 111348 222967 111351 222967 111356 222967 111356 222968 111351 222968 111349 222968 111356 222969 111349 222969 111352 222969 111352 222970 111349 222970 111353 222970 111352 222971 111353 222971 111358 222971 111358 222972 111353 222972 111346 222972 111358 222973 111346 222973 111354 222973 111354 222974 111346 222974 111345 222974 111354 222975 111345 222975 111343 222975 111364 222976 111356 222976 111355 222976 111355 222977 111356 222977 111352 222977 111355 222978 111352 222978 111357 222978 111357 222979 111352 222979 111358 222979 111357 222980 111358 222980 111359 222980 111359 222981 111358 222981 111354 222981 111359 222982 111354 222982 111360 222982 111360 222983 111354 222983 111343 222983 111360 222984 111343 222984 110733 222984 111361 222985 111362 222985 111347 222985 111361 222986 111347 222986 111363 222986 111363 222987 111347 222987 111348 222987 111363 222988 111348 222988 111365 222988 111365 222989 111348 222989 111364 222989 111365 222990 111364 222990 110739 222990 111365 222991 110739 222991 110738 222991 111363 222992 111365 222992 111366 222992 111375 222993 111361 222993 111376 222993 111376 222994 111361 222994 111363 222994 111365 222995 110738 222995 111366 222995 111366 222996 110738 222996 110737 222996 111366 222997 110737 222997 111370 222997 111370 222998 110737 222998 111367 222998 111370 222999 111367 222999 111371 222999 111371 223000 111367 223000 111368 223000 111371 223001 111368 223001 111372 223001 111368 223002 110734 223002 111372 223002 111372 223003 110734 223003 111369 223003 111372 223004 111369 223004 111373 223004 111363 223005 111366 223005 111376 223005 111376 223006 111366 223006 111370 223006 111376 223007 111370 223007 111377 223007 111377 223008 111370 223008 111371 223008 111377 223009 111371 223009 111378 223009 111378 223010 111371 223010 111372 223010 111378 223011 111372 223011 111380 223011 111380 223012 111372 223012 111373 223012 111380 223013 111373 223013 111374 223013 111375 223014 111376 223014 111320 223014 111320 223015 111376 223015 111377 223015 111320 223016 111377 223016 111321 223016 111321 223017 111377 223017 111378 223017 111321 223018 111378 223018 111379 223018 111379 223019 111378 223019 111380 223019 111379 223020 111380 223020 111322 223020 111322 223021 111380 223021 111374 223021 111322 223022 111374 223022 111326 223022 111333 223023 111383 223023 111381 223023 111330 223024 111382 223024 111381 223024 111381 223025 111382 223025 111331 223025 111381 223026 111331 223026 111333 223026 111373 223027 111334 223027 111374 223027 111374 223028 111334 223028 111326 223028 111369 223029 111381 223029 111373 223029 111373 223030 111381 223030 111383 223030 111373 223031 111383 223031 111334 223031 111235 223032 111330 223032 111384 223032 111384 223033 111330 223033 111381 223033 111384 223034 111381 223034 110736 223034 110736 223035 111381 223035 111369 223035 110736 223036 111369 223036 110734 223036 111257 223037 111385 223037 111386 223037 111386 223038 111385 223038 111288 223038 111386 223039 111288 223039 111387 223039 111387 223040 111288 223040 111291 223040 111291 223041 111293 223041 111387 223041 111387 223042 111293 223042 111388 223042 111387 223043 111388 223043 111402 223043 111402 223044 111388 223044 111389 223044 111402 223045 111389 223045 111407 223045 111407 223046 111389 223046 111408 223046 111386 223047 111387 223047 111390 223047 111390 223048 111387 223048 111402 223048 111390 223049 111402 223049 111403 223049 111281 223050 111391 223050 111392 223050 111391 223051 111393 223051 111392 223051 111392 223052 111393 223052 111410 223052 111392 223053 111410 223053 111396 223053 111396 223054 111410 223054 111409 223054 111396 223055 111409 223055 110772 223055 110772 223056 111409 223056 110773 223056 111401 223057 111281 223057 111394 223057 111394 223058 111281 223058 111392 223058 111394 223059 111392 223059 111398 223059 111398 223060 111392 223060 111396 223060 111398 223061 111396 223061 111395 223061 111395 223062 111396 223062 110772 223062 111395 223063 111397 223063 111398 223063 111398 223064 111397 223064 111405 223064 111398 223065 111405 223065 111394 223065 111394 223066 111405 223066 111399 223066 111394 223067 111399 223067 111401 223067 111286 223068 111400 223068 111399 223068 111399 223069 111400 223069 111282 223069 111399 223070 111282 223070 111401 223070 111407 223071 111406 223071 111402 223071 111402 223072 111406 223072 111404 223072 111402 223073 111404 223073 111403 223073 111403 223074 111404 223074 110765 223074 111397 223075 110765 223075 111405 223075 111405 223076 110765 223076 111404 223076 111405 223077 111404 223077 111399 223077 111399 223078 111404 223078 111406 223078 111399 223079 111406 223079 111286 223079 111286 223080 111406 223080 111407 223080 111286 223081 111407 223081 111408 223081 111413 223082 110773 223082 111409 223082 111413 223083 111409 223083 111423 223083 111423 223084 111409 223084 111410 223084 111423 223085 111410 223085 111414 223085 111414 223086 111410 223086 111393 223086 111414 223087 111393 223087 111411 223087 111437 223088 111412 223088 111430 223088 111414 223089 111411 223089 111417 223089 111413 223090 111423 223090 111424 223090 111423 223091 111414 223091 111415 223091 111415 223092 111414 223092 111417 223092 111415 223093 111417 223093 111416 223093 111416 223094 111417 223094 111418 223094 111418 223095 111273 223095 111416 223095 111416 223096 111273 223096 111419 223096 111416 223097 111419 223097 111425 223097 111425 223098 111419 223098 111421 223098 111425 223099 111421 223099 111420 223099 111420 223100 111421 223100 111270 223100 111420 223101 111270 223101 111422 223101 111423 223102 111415 223102 111424 223102 111424 223103 111415 223103 111416 223103 111424 223104 111416 223104 111428 223104 111428 223105 111416 223105 111425 223105 111428 223106 111425 223106 111426 223106 111426 223107 111425 223107 111420 223107 111426 223108 111420 223108 111430 223108 111430 223109 111420 223109 111422 223109 111430 223110 111422 223110 111437 223110 111413 223111 111424 223111 111427 223111 111427 223112 111424 223112 111428 223112 111427 223113 111428 223113 111429 223113 111429 223114 111428 223114 111426 223114 111429 223115 111426 223115 110769 223115 110769 223116 111426 223116 111430 223116 110769 223117 111430 223117 110770 223117 110770 223118 111430 223118 111412 223118 110770 223119 111412 223119 110771 223119 111438 223120 111261 223120 111431 223120 111431 223121 111261 223121 111432 223121 111432 223122 111433 223122 111431 223122 111431 223123 111433 223123 111434 223123 111431 223124 111434 223124 111436 223124 111252 223125 111435 223125 111436 223125 111436 223126 111435 223126 110764 223126 111436 223127 110764 223127 111431 223127 111431 223128 110764 223128 110771 223128 110771 223129 111412 223129 111431 223129 111431 223130 111412 223130 111437 223130 111431 223131 111437 223131 111438 223131 111438 223132 111437 223132 111422 223132 111438 223133 111422 223133 111270 223133 111458 223134 111459 223134 112055 223134 112055 223135 111459 223135 111447 223135 112055 223136 111447 223136 112054 223136 112054 223137 111447 223137 111448 223137 112054 223138 111448 223138 111439 223138 111439 223139 111448 223139 111445 223139 111439 223140 111445 223140 111440 223140 111445 223141 111124 223141 111441 223141 111440 223142 111445 223142 112048 223142 112048 223143 111445 223143 111441 223143 112048 223144 111441 223144 112047 223144 111442 223145 111124 223145 111443 223145 111443 223146 111124 223146 111445 223146 111443 223147 111445 223147 111444 223147 111444 223148 111445 223148 111448 223148 111459 223149 111446 223149 111447 223149 111447 223150 111446 223150 111449 223150 111447 223151 111449 223151 111448 223151 111448 223152 111449 223152 111461 223152 111448 223153 111461 223153 111444 223153 111443 223154 111444 223154 111456 223154 111450 223155 111455 223155 111456 223155 111451 223156 111462 223156 111454 223156 112037 223157 111176 223157 111460 223157 111176 223158 111467 223158 111460 223158 111460 223159 111467 223159 111452 223159 111460 223160 111452 223160 111457 223160 111457 223161 111452 223161 111453 223161 111442 223162 111443 223162 111454 223162 111454 223163 111443 223163 111456 223163 111454 223164 111456 223164 111451 223164 111451 223165 111456 223165 111455 223165 111444 223166 111461 223166 111456 223166 111456 223167 111461 223167 111457 223167 111456 223168 111457 223168 111450 223168 111450 223169 111457 223169 111453 223169 111458 223170 112037 223170 111459 223170 111459 223171 112037 223171 111460 223171 111459 223172 111460 223172 111446 223172 111446 223173 111460 223173 111457 223173 111446 223174 111457 223174 111449 223174 111449 223175 111457 223175 111461 223175 110796 223176 111032 223176 111464 223176 111464 223177 111032 223177 111037 223177 111464 223178 111037 223178 111462 223178 111465 223179 111463 223179 111464 223179 111464 223180 111463 223180 111473 223180 111464 223181 111473 223181 110796 223181 111462 223182 111451 223182 111464 223182 111464 223183 111451 223183 111455 223183 111464 223184 111455 223184 111465 223184 111467 223185 111468 223185 111466 223185 111466 223186 111468 223186 111470 223186 111466 223187 111470 223187 111465 223187 111465 223188 111470 223188 111471 223188 111465 223189 111471 223189 111463 223189 111455 223190 111450 223190 111465 223190 111465 223191 111450 223191 111453 223191 111465 223192 111453 223192 111466 223192 111466 223193 111453 223193 111452 223193 111466 223194 111452 223194 111467 223194 111468 223195 111467 223195 111469 223195 111468 223196 111469 223196 111470 223196 111470 223197 111469 223197 111474 223197 111470 223198 111474 223198 111471 223198 111471 223199 111474 223199 111472 223199 111471 223200 111472 223200 111463 223200 111463 223201 111472 223201 111473 223201 111473 223202 111472 223202 110786 223202 111473 223203 110786 223203 110796 223203 110786 223204 111472 223204 111489 223204 111472 223205 111474 223205 111476 223205 111474 223206 111469 223206 111475 223206 111474 223207 111475 223207 111476 223207 111476 223208 111475 223208 111173 223208 111476 223209 111173 223209 111490 223209 111490 223210 111173 223210 111172 223210 111490 223211 111172 223211 111477 223211 111477 223212 111172 223212 111170 223212 111477 223213 111170 223213 111478 223213 111478 223214 111170 223214 111169 223214 111478 223215 111169 223215 111493 223215 111493 223216 111169 223216 111168 223216 111493 223217 111168 223217 111494 223217 111494 223218 111168 223218 111167 223218 111494 223219 111167 223219 111496 223219 111496 223220 111167 223220 111479 223220 111496 223221 111479 223221 111497 223221 111497 223222 111479 223222 111480 223222 111497 223223 111480 223223 111498 223223 111498 223224 111480 223224 111481 223224 111498 223225 111481 223225 111500 223225 111500 223226 111481 223226 111482 223226 111500 223227 111482 223227 111502 223227 111502 223228 111482 223228 111483 223228 111502 223229 111483 223229 111484 223229 111484 223230 111483 223230 111161 223230 111484 223231 111161 223231 111485 223231 111485 223232 111161 223232 111160 223232 111485 223233 111160 223233 111486 223233 111486 223234 111160 223234 111487 223234 111486 223235 111487 223235 111488 223235 111488 223236 111487 223236 111158 223236 111488 223237 111158 223237 111521 223237 111472 223238 111476 223238 111489 223238 111489 223239 111476 223239 111490 223239 111489 223240 111490 223240 111491 223240 111491 223241 111490 223241 111477 223241 111491 223242 111477 223242 111492 223242 111492 223243 111477 223243 111478 223243 111492 223244 111478 223244 111508 223244 111508 223245 111478 223245 111493 223245 111508 223246 111493 223246 111509 223246 111509 223247 111493 223247 111494 223247 111509 223248 111494 223248 111495 223248 111495 223249 111494 223249 111496 223249 111495 223250 111496 223250 111510 223250 111510 223251 111496 223251 111497 223251 111510 223252 111497 223252 111512 223252 111512 223253 111497 223253 111498 223253 111512 223254 111498 223254 111499 223254 111499 223255 111498 223255 111500 223255 111499 223256 111500 223256 111501 223256 111501 223257 111500 223257 111502 223257 111501 223258 111502 223258 111503 223258 111503 223259 111502 223259 111484 223259 111503 223260 111484 223260 111504 223260 111504 223261 111484 223261 111485 223261 111504 223262 111485 223262 111514 223262 111514 223263 111485 223263 111486 223263 111514 223264 111486 223264 111505 223264 111505 223265 111486 223265 111488 223265 111505 223266 111488 223266 111518 223266 111518 223267 111488 223267 111521 223267 111518 223268 111521 223268 111524 223268 110786 223269 111489 223269 111506 223269 111506 223270 111489 223270 111491 223270 111506 223271 111491 223271 110788 223271 110788 223272 111491 223272 111492 223272 110788 223273 111492 223273 110789 223273 110789 223274 111492 223274 111508 223274 110789 223275 111508 223275 111507 223275 111507 223276 111508 223276 111509 223276 111507 223277 111509 223277 110784 223277 110784 223278 111509 223278 111495 223278 110784 223279 111495 223279 110799 223279 110799 223280 111495 223280 111510 223280 110799 223281 111510 223281 110800 223281 110800 223282 111510 223282 111512 223282 110800 223283 111512 223283 111511 223283 111511 223284 111512 223284 111499 223284 111511 223285 111499 223285 111513 223285 111513 223286 111499 223286 111501 223286 111513 223287 111501 223287 110791 223287 110791 223288 111501 223288 111503 223288 110791 223289 111503 223289 110790 223289 110790 223290 111503 223290 111504 223290 110790 223291 111504 223291 111515 223291 111515 223292 111504 223292 111514 223292 111515 223293 111514 223293 111516 223293 111516 223294 111514 223294 111505 223294 111516 223295 111505 223295 111517 223295 111517 223296 111505 223296 111518 223296 111517 223297 111518 223297 111519 223297 111519 223298 111518 223298 111524 223298 111519 223299 111524 223299 111522 223299 111536 223300 111520 223300 111158 223300 111158 223301 111520 223301 111521 223301 111520 223302 111535 223302 111521 223302 111521 223303 111535 223303 111534 223303 111521 223304 111534 223304 111524 223304 110803 223305 111522 223305 111523 223305 111523 223306 111522 223306 111524 223306 111523 223307 111524 223307 111525 223307 111525 223308 111524 223308 111534 223308 111526 223309 110803 223309 111523 223309 111527 223310 111533 223310 111526 223310 111526 223311 111523 223311 111527 223311 111527 223312 111523 223312 111525 223312 111527 223313 111525 223313 111531 223313 111536 223314 111528 223314 111529 223314 111529 223315 111528 223315 111530 223315 111529 223316 111530 223316 111531 223316 111531 223317 111530 223317 111543 223317 111531 223318 111543 223318 111527 223318 111527 223319 111543 223319 111532 223319 111527 223320 111532 223320 111533 223320 111533 223321 111532 223321 110991 223321 111525 223322 111534 223322 111531 223322 111531 223323 111534 223323 111535 223323 111531 223324 111535 223324 111529 223324 111529 223325 111535 223325 111520 223325 111529 223326 111520 223326 111536 223326 111542 223327 111541 223327 111899 223327 110987 223328 111537 223328 111544 223328 111544 223329 111537 223329 111538 223329 111544 223330 111538 223330 111539 223330 111539 223331 111538 223331 111547 223331 111547 223332 111538 223332 111540 223332 111547 223333 111540 223333 111550 223333 111550 223334 111540 223334 111551 223334 111551 223335 111540 223335 111542 223335 111551 223336 111542 223336 111552 223336 111552 223337 111542 223337 111899 223337 111552 223338 111899 223338 111915 223338 111536 223339 111541 223339 111528 223339 111528 223340 111541 223340 111542 223340 111528 223341 111542 223341 111530 223341 111530 223342 111542 223342 111540 223342 111530 223343 111540 223343 111543 223343 111543 223344 111540 223344 111538 223344 111543 223345 111538 223345 111532 223345 111532 223346 111538 223346 111537 223346 111532 223347 111537 223347 110991 223347 111544 223348 111546 223348 110987 223348 110987 223349 111546 223349 111103 223349 111546 223350 111905 223350 111904 223350 111103 223351 111546 223351 111084 223351 111084 223352 111546 223352 111904 223352 111084 223353 111904 223353 111085 223353 111914 223354 111912 223354 111549 223354 111549 223355 111912 223355 111545 223355 111549 223356 111545 223356 111548 223356 111544 223357 111539 223357 111546 223357 111546 223358 111539 223358 111548 223358 111546 223359 111548 223359 111905 223359 111905 223360 111548 223360 111545 223360 111539 223361 111547 223361 111548 223361 111548 223362 111547 223362 111550 223362 111548 223363 111550 223363 111549 223363 111549 223364 111550 223364 111551 223364 111549 223365 111551 223365 111914 223365 111914 223366 111551 223366 111552 223366 111914 223367 111552 223367 111915 223367 111837 223368 111568 223368 111835 223368 111835 223369 111568 223369 111558 223369 111835 223370 111558 223370 111554 223370 111554 223371 111558 223371 111553 223371 111554 223372 111553 223372 111834 223372 111834 223373 111553 223373 111555 223373 111834 223374 111555 223374 111832 223374 111555 223375 111059 223375 111061 223375 111832 223376 111555 223376 111830 223376 111830 223377 111555 223377 111061 223377 111830 223378 111061 223378 111829 223378 111060 223379 111059 223379 111556 223379 111556 223380 111059 223380 111555 223380 111556 223381 111555 223381 111565 223381 111565 223382 111555 223382 111553 223382 111568 223383 111569 223383 111558 223383 111558 223384 111569 223384 111557 223384 111558 223385 111557 223385 111553 223385 111553 223386 111557 223386 111559 223386 111553 223387 111559 223387 111565 223387 111556 223388 111565 223388 111563 223388 111560 223389 111576 223389 111563 223389 111564 223390 110995 223390 111562 223390 111566 223391 111214 223391 111567 223391 111214 223392 111213 223392 111567 223392 111567 223393 111213 223393 111581 223393 111567 223394 111581 223394 111561 223394 111561 223395 111581 223395 111580 223395 111060 223396 111556 223396 111562 223396 111562 223397 111556 223397 111563 223397 111562 223398 111563 223398 111564 223398 111564 223399 111563 223399 111576 223399 111565 223400 111559 223400 111563 223400 111563 223401 111559 223401 111561 223401 111563 223402 111561 223402 111560 223402 111560 223403 111561 223403 111580 223403 111837 223404 111566 223404 111568 223404 111568 223405 111566 223405 111567 223405 111568 223406 111567 223406 111569 223406 111569 223407 111567 223407 111561 223407 111569 223408 111561 223408 111557 223408 111557 223409 111561 223409 111559 223409 111570 223410 111571 223410 111574 223410 111574 223411 111571 223411 111572 223411 111574 223412 111572 223412 110995 223412 111573 223413 111585 223413 111574 223413 111574 223414 111585 223414 111575 223414 111574 223415 111575 223415 111570 223415 110995 223416 111564 223416 111574 223416 111574 223417 111564 223417 111576 223417 111574 223418 111576 223418 111573 223418 111213 223419 111577 223419 111578 223419 111578 223420 111577 223420 111582 223420 111578 223421 111582 223421 111573 223421 111573 223422 111582 223422 111579 223422 111573 223423 111579 223423 111585 223423 111576 223424 111560 223424 111573 223424 111573 223425 111560 223425 111580 223425 111573 223426 111580 223426 111578 223426 111578 223427 111580 223427 111581 223427 111578 223428 111581 223428 111213 223428 111213 223429 111212 223429 111587 223429 111213 223430 111587 223430 111577 223430 111577 223431 111587 223431 111583 223431 111577 223432 111583 223432 111582 223432 111582 223433 111583 223433 111579 223433 111579 223434 111583 223434 111584 223434 111579 223435 111584 223435 111585 223435 111585 223436 111584 223436 111575 223436 111575 223437 111584 223437 110775 223437 111575 223438 110775 223438 111570 223438 111583 223439 111587 223439 111586 223439 111587 223440 111212 223440 111210 223440 110775 223441 111584 223441 111602 223441 111602 223442 111584 223442 111583 223442 111587 223443 111210 223443 111586 223443 111586 223444 111210 223444 111588 223444 111586 223445 111588 223445 111603 223445 111603 223446 111588 223446 111590 223446 111603 223447 111590 223447 111589 223447 111589 223448 111590 223448 111207 223448 111589 223449 111207 223449 111591 223449 111591 223450 111207 223450 111592 223450 111591 223451 111592 223451 111607 223451 111607 223452 111592 223452 111594 223452 111607 223453 111594 223453 111593 223453 111593 223454 111594 223454 111595 223454 111593 223455 111595 223455 111610 223455 111610 223456 111595 223456 111204 223456 111610 223457 111204 223457 111611 223457 111611 223458 111204 223458 111596 223458 111611 223459 111596 223459 111613 223459 111613 223460 111596 223460 111597 223460 111613 223461 111597 223461 111614 223461 111614 223462 111597 223462 111598 223462 111614 223463 111598 223463 111599 223463 111599 223464 111598 223464 111200 223464 111599 223465 111200 223465 111616 223465 111616 223466 111200 223466 111199 223466 111616 223467 111199 223467 111617 223467 111617 223468 111199 223468 111600 223468 111617 223469 111600 223469 111618 223469 111618 223470 111600 223470 111601 223470 111618 223471 111601 223471 111619 223471 111619 223472 111601 223472 111638 223472 111619 223473 111638 223473 111640 223473 111583 223474 111586 223474 111602 223474 111602 223475 111586 223475 111603 223475 111602 223476 111603 223476 111604 223476 111604 223477 111603 223477 111589 223477 111604 223478 111589 223478 111605 223478 111605 223479 111589 223479 111591 223479 111605 223480 111591 223480 111606 223480 111606 223481 111591 223481 111607 223481 111606 223482 111607 223482 111624 223482 111624 223483 111607 223483 111593 223483 111624 223484 111593 223484 111608 223484 111608 223485 111593 223485 111610 223485 111608 223486 111610 223486 111609 223486 111609 223487 111610 223487 111611 223487 111609 223488 111611 223488 111612 223488 111612 223489 111611 223489 111613 223489 111612 223490 111613 223490 111628 223490 111628 223491 111613 223491 111614 223491 111628 223492 111614 223492 111615 223492 111615 223493 111614 223493 111599 223493 111615 223494 111599 223494 111630 223494 111630 223495 111599 223495 111616 223495 111630 223496 111616 223496 111632 223496 111632 223497 111616 223497 111617 223497 111632 223498 111617 223498 111634 223498 111634 223499 111617 223499 111618 223499 111634 223500 111618 223500 111635 223500 111635 223501 111618 223501 111619 223501 111635 223502 111619 223502 111637 223502 111637 223503 111619 223503 111640 223503 111637 223504 111640 223504 111620 223504 110775 223505 111602 223505 111621 223505 111621 223506 111602 223506 111604 223506 111621 223507 111604 223507 111622 223507 111622 223508 111604 223508 111605 223508 111622 223509 111605 223509 111623 223509 111623 223510 111605 223510 111606 223510 111623 223511 111606 223511 110777 223511 110777 223512 111606 223512 111624 223512 110777 223513 111624 223513 110797 223513 110797 223514 111624 223514 111608 223514 110797 223515 111608 223515 111625 223515 111625 223516 111608 223516 111609 223516 111625 223517 111609 223517 111626 223517 111626 223518 111609 223518 111612 223518 111626 223519 111612 223519 111627 223519 111627 223520 111612 223520 111628 223520 111627 223521 111628 223521 110798 223521 110798 223522 111628 223522 111615 223522 110798 223523 111615 223523 111629 223523 111629 223524 111615 223524 111630 223524 111629 223525 111630 223525 111631 223525 111631 223526 111630 223526 111632 223526 111631 223527 111632 223527 111633 223527 111633 223528 111632 223528 111634 223528 111633 223529 111634 223529 110779 223529 110779 223530 111634 223530 111635 223530 110779 223531 111635 223531 111636 223531 111636 223532 111635 223532 111637 223532 111636 223533 111637 223533 110780 223533 110780 223534 111637 223534 111620 223534 110780 223535 111620 223535 111641 223535 111211 223536 111639 223536 111638 223536 111638 223537 111639 223537 111640 223537 111639 223538 111653 223538 111640 223538 111640 223539 111653 223539 111642 223539 111640 223540 111642 223540 111620 223540 111643 223541 111641 223541 111644 223541 111644 223542 111641 223542 111620 223542 111644 223543 111620 223543 111652 223543 111652 223544 111620 223544 111642 223544 111051 223545 111643 223545 111644 223545 111645 223546 111650 223546 111051 223546 111051 223547 111644 223547 111645 223547 111645 223548 111644 223548 111652 223548 111645 223549 111652 223549 111646 223549 111211 223550 111660 223550 111647 223550 111647 223551 111660 223551 111662 223551 111647 223552 111662 223552 111646 223552 111646 223553 111662 223553 111648 223553 111646 223554 111648 223554 111645 223554 111645 223555 111648 223555 111649 223555 111645 223556 111649 223556 111650 223556 111650 223557 111649 223557 111651 223557 111652 223558 111642 223558 111646 223558 111646 223559 111642 223559 111653 223559 111646 223560 111653 223560 111647 223560 111647 223561 111653 223561 111639 223561 111647 223562 111639 223562 111211 223562 111661 223563 111659 223563 111680 223563 111654 223564 111664 223564 111668 223564 111668 223565 111664 223565 111663 223565 111668 223566 111663 223566 111655 223566 111655 223567 111663 223567 111670 223567 111670 223568 111663 223568 111657 223568 111670 223569 111657 223569 111656 223569 111656 223570 111657 223570 111671 223570 111671 223571 111657 223571 111661 223571 111671 223572 111661 223572 111658 223572 111658 223573 111661 223573 111680 223573 111658 223574 111680 223574 111672 223574 111211 223575 111659 223575 111660 223575 111660 223576 111659 223576 111661 223576 111660 223577 111661 223577 111662 223577 111662 223578 111661 223578 111657 223578 111662 223579 111657 223579 111648 223579 111648 223580 111657 223580 111663 223580 111648 223581 111663 223581 111649 223581 111649 223582 111663 223582 111664 223582 111649 223583 111664 223583 111651 223583 111668 223584 111665 223584 111654 223584 111654 223585 111665 223585 111122 223585 111665 223586 111666 223586 111683 223586 111122 223587 111665 223587 111105 223587 111105 223588 111665 223588 111683 223588 111105 223589 111683 223589 111686 223589 111694 223590 111693 223590 111667 223590 111667 223591 111693 223591 111691 223591 111667 223592 111691 223592 111669 223592 111668 223593 111655 223593 111665 223593 111665 223594 111655 223594 111669 223594 111665 223595 111669 223595 111666 223595 111666 223596 111669 223596 111691 223596 111655 223597 111670 223597 111669 223597 111669 223598 111670 223598 111656 223598 111669 223599 111656 223599 111667 223599 111667 223600 111656 223600 111671 223600 111667 223601 111671 223601 111694 223601 111694 223602 111671 223602 111658 223602 111694 223603 111658 223603 111672 223603 111178 223604 111673 223604 111682 223604 111682 223605 111673 223605 111674 223605 111682 223606 111674 223606 111675 223606 111675 223607 111674 223607 111699 223607 111675 223608 111699 223608 111676 223608 111676 223609 111699 223609 111677 223609 111676 223610 111677 223610 111681 223610 111681 223611 111677 223611 111697 223611 111681 223612 111697 223612 111678 223612 111678 223613 111697 223613 111679 223613 111678 223614 111679 223614 111680 223614 111680 223615 111679 223615 111672 223615 111680 223616 111700 223616 111678 223616 111678 223617 111700 223617 111719 223617 111678 223618 111719 223618 111681 223618 111681 223619 111719 223619 111676 223619 111676 223620 111719 223620 111718 223620 111676 223621 111718 223621 111675 223621 111675 223622 111718 223622 111682 223622 111682 223623 111718 223623 111177 223623 111682 223624 111177 223624 111178 223624 111759 223625 111760 223625 111683 223625 111760 223626 111684 223626 111683 223626 111683 223627 111684 223627 111685 223627 111683 223628 111685 223628 111686 223628 111686 223629 111685 223629 111687 223629 111686 223630 111687 223630 111751 223630 111691 223631 111688 223631 111666 223631 111666 223632 111688 223632 111756 223632 111666 223633 111756 223633 111683 223633 111683 223634 111756 223634 111757 223634 111683 223635 111757 223635 111759 223635 111179 223636 111689 223636 111698 223636 111698 223637 111689 223637 111690 223637 111698 223638 111690 223638 111763 223638 111696 223639 111688 223639 111695 223639 111695 223640 111688 223640 111691 223640 111695 223641 111691 223641 111692 223641 111692 223642 111691 223642 111693 223642 111692 223643 111693 223643 111694 223643 111694 223644 111672 223644 111692 223644 111692 223645 111672 223645 111679 223645 111692 223646 111679 223646 111697 223646 111697 223647 111698 223647 111692 223647 111692 223648 111698 223648 111763 223648 111692 223649 111763 223649 111695 223649 111695 223650 111763 223650 111696 223650 111697 223651 111677 223651 111698 223651 111698 223652 111677 223652 111699 223652 111698 223653 111699 223653 111179 223653 111179 223654 111699 223654 111674 223654 111179 223655 111674 223655 111673 223655 111719 223656 111700 223656 111701 223656 111701 223657 111700 223657 111197 223657 111701 223658 111197 223658 111702 223658 111702 223659 111197 223659 111703 223659 111702 223660 111703 223660 111721 223660 111721 223661 111703 223661 111198 223661 111721 223662 111198 223662 111705 223662 111705 223663 111198 223663 111704 223663 111705 223664 111704 223664 111706 223664 111706 223665 111704 223665 111201 223665 111706 223666 111201 223666 111725 223666 111725 223667 111201 223667 111707 223667 111725 223668 111707 223668 111708 223668 111708 223669 111707 223669 111202 223669 111708 223670 111202 223670 111727 223670 111727 223671 111202 223671 111709 223671 111727 223672 111709 223672 111729 223672 111729 223673 111709 223673 111203 223673 111729 223674 111203 223674 111710 223674 111710 223675 111203 223675 111205 223675 111710 223676 111205 223676 111731 223676 111731 223677 111205 223677 111711 223677 111731 223678 111711 223678 111712 223678 111712 223679 111711 223679 111206 223679 111712 223680 111206 223680 111713 223680 111713 223681 111206 223681 111208 223681 111713 223682 111208 223682 111714 223682 111714 223683 111208 223683 111715 223683 111714 223684 111715 223684 111734 223684 111734 223685 111715 223685 111209 223685 111734 223686 111209 223686 111716 223686 111716 223687 111209 223687 111717 223687 111718 223688 111719 223688 111736 223688 111736 223689 111719 223689 111701 223689 111736 223690 111701 223690 111720 223690 111720 223691 111701 223691 111702 223691 111720 223692 111702 223692 111739 223692 111739 223693 111702 223693 111721 223693 111739 223694 111721 223694 111722 223694 111722 223695 111721 223695 111705 223695 111722 223696 111705 223696 111723 223696 111723 223697 111705 223697 111706 223697 111723 223698 111706 223698 111724 223698 111724 223699 111706 223699 111725 223699 111724 223700 111725 223700 111726 223700 111726 223701 111725 223701 111708 223701 111726 223702 111708 223702 111742 223702 111742 223703 111708 223703 111727 223703 111742 223704 111727 223704 111728 223704 111728 223705 111727 223705 111729 223705 111728 223706 111729 223706 111730 223706 111730 223707 111729 223707 111710 223707 111730 223708 111710 223708 111732 223708 111732 223709 111710 223709 111731 223709 111732 223710 111731 223710 111745 223710 111745 223711 111731 223711 111712 223711 111745 223712 111712 223712 111746 223712 111746 223713 111712 223713 111713 223713 111746 223714 111713 223714 111733 223714 111733 223715 111713 223715 111714 223715 111733 223716 111714 223716 111749 223716 111749 223717 111714 223717 111734 223717 111749 223718 111734 223718 111802 223718 111802 223719 111734 223719 111716 223719 111177 223720 111718 223720 111735 223720 111735 223721 111718 223721 111736 223721 111735 223722 111736 223722 111737 223722 111737 223723 111736 223723 111720 223723 111737 223724 111720 223724 111738 223724 111738 223725 111720 223725 111739 223725 111738 223726 111739 223726 111740 223726 111740 223727 111739 223727 111722 223727 111740 223728 111722 223728 111184 223728 111184 223729 111722 223729 111723 223729 111184 223730 111723 223730 111185 223730 111185 223731 111723 223731 111724 223731 111185 223732 111724 223732 111187 223732 111187 223733 111724 223733 111726 223733 111187 223734 111726 223734 111741 223734 111741 223735 111726 223735 111742 223735 111741 223736 111742 223736 111195 223736 111195 223737 111742 223737 111728 223737 111195 223738 111728 223738 111743 223738 111743 223739 111728 223739 111730 223739 111743 223740 111730 223740 111196 223740 111196 223741 111730 223741 111732 223741 111196 223742 111732 223742 111744 223742 111744 223743 111732 223743 111745 223743 111744 223744 111745 223744 111183 223744 111183 223745 111745 223745 111746 223745 111183 223746 111746 223746 111747 223746 111747 223747 111746 223747 111733 223747 111747 223748 111733 223748 111748 223748 111748 223749 111733 223749 111749 223749 111748 223750 111749 223750 111182 223750 111182 223751 111749 223751 111802 223751 111784 223752 111804 223752 111782 223752 111750 223753 111104 223753 111751 223753 111750 223754 111751 223754 111752 223754 111754 223755 111753 223755 111773 223755 111773 223756 111753 223756 111104 223756 111755 223757 111106 223757 111785 223757 111785 223758 111106 223758 111754 223758 111785 223759 111754 223759 111786 223759 110756 223760 111107 223760 111755 223760 111688 223761 111762 223761 111756 223761 111756 223762 111762 223762 111769 223762 111756 223763 111769 223763 111757 223763 111757 223764 111769 223764 111758 223764 111757 223765 111758 223765 111759 223765 111759 223766 111758 223766 111768 223766 111759 223767 111768 223767 111760 223767 111760 223768 111768 223768 111767 223768 111760 223769 111767 223769 111684 223769 111684 223770 111767 223770 111761 223770 111684 223771 111761 223771 111685 223771 111685 223772 111761 223772 111752 223772 111685 223773 111752 223773 111687 223773 111687 223774 111752 223774 111751 223774 111688 223775 111696 223775 111762 223775 111762 223776 111696 223776 111764 223776 111764 223777 111696 223777 111763 223777 111764 223778 111763 223778 111690 223778 111690 223779 111689 223779 111764 223779 111764 223780 111689 223780 111765 223780 111764 223781 111765 223781 111771 223781 111104 223782 111750 223782 111773 223782 111773 223783 111750 223783 111752 223783 111773 223784 111752 223784 111774 223784 111774 223785 111752 223785 111761 223785 111774 223786 111761 223786 111775 223786 111775 223787 111761 223787 111767 223787 111775 223788 111767 223788 111766 223788 111766 223789 111767 223789 111768 223789 111766 223790 111768 223790 111777 223790 111777 223791 111768 223791 111758 223791 111777 223792 111758 223792 111778 223792 111778 223793 111758 223793 111769 223793 111778 223794 111769 223794 111770 223794 111770 223795 111769 223795 111762 223795 111770 223796 111762 223796 111780 223796 111780 223797 111762 223797 111764 223797 111780 223798 111764 223798 111772 223798 111772 223799 111764 223799 111771 223799 111772 223800 111771 223800 111783 223800 111754 223801 111773 223801 111786 223801 111786 223802 111773 223802 111774 223802 111786 223803 111774 223803 111788 223803 111788 223804 111774 223804 111775 223804 111788 223805 111775 223805 111776 223805 111776 223806 111775 223806 111766 223806 111776 223807 111766 223807 111790 223807 111790 223808 111766 223808 111777 223808 111790 223809 111777 223809 111793 223809 111793 223810 111777 223810 111778 223810 111793 223811 111778 223811 111779 223811 111779 223812 111778 223812 111770 223812 111779 223813 111770 223813 111796 223813 111796 223814 111770 223814 111780 223814 111796 223815 111780 223815 111781 223815 111781 223816 111780 223816 111772 223816 111781 223817 111772 223817 111782 223817 111782 223818 111772 223818 111783 223818 111782 223819 111783 223819 111784 223819 111755 223820 111785 223820 110756 223820 110756 223821 111785 223821 111786 223821 110756 223822 111786 223822 111787 223822 111787 223823 111786 223823 111788 223823 111787 223824 111788 223824 111789 223824 111789 223825 111788 223825 111776 223825 111789 223826 111776 223826 111791 223826 111791 223827 111776 223827 111790 223827 111791 223828 111790 223828 111792 223828 111792 223829 111790 223829 111793 223829 111792 223830 111793 223830 111794 223830 111794 223831 111793 223831 111779 223831 111794 223832 111779 223832 111795 223832 111795 223833 111779 223833 111796 223833 111795 223834 111796 223834 110755 223834 110755 223835 111796 223835 111781 223835 110755 223836 111781 223836 111797 223836 111797 223837 111781 223837 111782 223837 111797 223838 111782 223838 111798 223838 111798 223839 111782 223839 111804 223839 111798 223840 111804 223840 111799 223840 111566 223841 111800 223841 111717 223841 111717 223842 111800 223842 111716 223842 111800 223843 111813 223843 111716 223843 111716 223844 111813 223844 111812 223844 111716 223845 111812 223845 111802 223845 111193 223846 111182 223846 111801 223846 111801 223847 111182 223847 111802 223847 111801 223848 111802 223848 111811 223848 111811 223849 111802 223849 111812 223849 111815 223850 111816 223850 111803 223850 111783 223851 111771 223851 111803 223851 111765 223852 111689 223852 111807 223852 111784 223853 111809 223853 111804 223853 111804 223854 111809 223854 111805 223854 111804 223855 111805 223855 111799 223855 111806 223856 111815 223856 111807 223856 111807 223857 111815 223857 111803 223857 111807 223858 111803 223858 111765 223858 111765 223859 111803 223859 111771 223859 111816 223860 111808 223860 111803 223860 111803 223861 111808 223861 111809 223861 111803 223862 111809 223862 111783 223862 111783 223863 111809 223863 111784 223863 111823 223864 111805 223864 111822 223864 111822 223865 111805 223865 111809 223865 111822 223866 111809 223866 111818 223866 111818 223867 111809 223867 111808 223867 111842 223868 111193 223868 111840 223868 111840 223869 111193 223869 111801 223869 111840 223870 111801 223870 111810 223870 111810 223871 111801 223871 111811 223871 111810 223872 111811 223872 111838 223872 111838 223873 111811 223873 111812 223873 111838 223874 111812 223874 111814 223874 111814 223875 111812 223875 111813 223875 111814 223876 111813 223876 111836 223876 111836 223877 111813 223877 111800 223877 111836 223878 111800 223878 111837 223878 111837 223879 111800 223879 111566 223879 111191 223880 111846 223880 111806 223880 111806 223881 111846 223881 111815 223881 111815 223882 111846 223882 111816 223882 111816 223883 111846 223883 111817 223883 111816 223884 111817 223884 111808 223884 111808 223885 111817 223885 111848 223885 111808 223886 111848 223886 111818 223886 111818 223887 111848 223887 111819 223887 111818 223888 111819 223888 111822 223888 111819 223889 111820 223889 111822 223889 111822 223890 111820 223890 111821 223890 111822 223891 111821 223891 111823 223891 111833 223892 111824 223892 111825 223892 111825 223893 111824 223893 111831 223893 111831 223894 111824 223894 111894 223894 111831 223895 111894 223895 111839 223895 111839 223896 111894 223896 111826 223896 111839 223897 111826 223897 111841 223897 111841 223898 111826 223898 111827 223898 111828 223899 111855 223899 111829 223899 111829 223900 111855 223900 111857 223900 111829 223901 111857 223901 111830 223901 111857 223902 111858 223902 111830 223902 111830 223903 111858 223903 111859 223903 111830 223904 111859 223904 111860 223904 111831 223905 111814 223905 111836 223905 111860 223906 111861 223906 111830 223906 111830 223907 111861 223907 111864 223907 111830 223908 111864 223908 111832 223908 111832 223909 111864 223909 111833 223909 111832 223910 111833 223910 111834 223910 111834 223911 111833 223911 111825 223911 111834 223912 111825 223912 111554 223912 111554 223913 111825 223913 111831 223913 111554 223914 111831 223914 111835 223914 111835 223915 111831 223915 111836 223915 111835 223916 111836 223916 111837 223916 111814 223917 111831 223917 111838 223917 111838 223918 111831 223918 111839 223918 111838 223919 111839 223919 111810 223919 111810 223920 111839 223920 111840 223920 111840 223921 111839 223921 111841 223921 111840 223922 111841 223922 111842 223922 111843 223923 111849 223923 111845 223923 111848 223924 111817 223924 111845 223924 111846 223925 111191 223925 111844 223925 111819 223926 111847 223926 111820 223926 111820 223927 111847 223927 110753 223927 111820 223928 110753 223928 111821 223928 111827 223929 111843 223929 111844 223929 111844 223930 111843 223930 111845 223930 111844 223931 111845 223931 111846 223931 111846 223932 111845 223932 111817 223932 111849 223933 111893 223933 111845 223933 111845 223934 111893 223934 111847 223934 111845 223935 111847 223935 111848 223935 111848 223936 111847 223936 111819 223936 111874 223937 110753 223937 111875 223937 111875 223938 110753 223938 111847 223938 111875 223939 111847 223939 111884 223939 111884 223940 111847 223940 111893 223940 111849 223941 111843 223941 111892 223941 111850 223942 111865 223942 111867 223942 111063 223943 111062 223943 111851 223943 111854 223944 111852 223944 111066 223944 111853 223945 111851 223945 110750 223945 111852 223946 111854 223946 111828 223946 111828 223947 111854 223947 111886 223947 111828 223948 111886 223948 111855 223948 111855 223949 111886 223949 111856 223949 111855 223950 111856 223950 111857 223950 111857 223951 111856 223951 111887 223951 111857 223952 111887 223952 111858 223952 111858 223953 111887 223953 111888 223953 111858 223954 111888 223954 111859 223954 111859 223955 111888 223955 111890 223955 111859 223956 111890 223956 111860 223956 111860 223957 111890 223957 111863 223957 111860 223958 111863 223958 111861 223958 111862 223959 111824 223959 111833 223959 111862 223960 111833 223960 111863 223960 111863 223961 111833 223961 111864 223961 111863 223962 111864 223962 111861 223962 111853 223963 110750 223963 111865 223963 111865 223964 110750 223964 111866 223964 111865 223965 111866 223965 111867 223965 111867 223966 111866 223966 111869 223966 111867 223967 111869 223967 111868 223967 111868 223968 111869 223968 110749 223968 111868 223969 110749 223969 111870 223969 111870 223970 110749 223970 110748 223970 111870 223971 110748 223971 111871 223971 111871 223972 110748 223972 110747 223972 111871 223973 110747 223973 111879 223973 111879 223974 110747 223974 110746 223974 111879 223975 110746 223975 111872 223975 111872 223976 110746 223976 111873 223976 111872 223977 111873 223977 111880 223977 111880 223978 111873 223978 110745 223978 111880 223979 110745 223979 111882 223979 110745 223980 111874 223980 111882 223980 111882 223981 111874 223981 111875 223981 111882 223982 111875 223982 111884 223982 111850 223983 111867 223983 111885 223983 111885 223984 111867 223984 111868 223984 111885 223985 111868 223985 111876 223985 111876 223986 111868 223986 111870 223986 111876 223987 111870 223987 111877 223987 111877 223988 111870 223988 111871 223988 111877 223989 111871 223989 111878 223989 111878 223990 111871 223990 111879 223990 111878 223991 111879 223991 111889 223991 111889 223992 111879 223992 111872 223992 111889 223993 111872 223993 111881 223993 111881 223994 111872 223994 111880 223994 111881 223995 111880 223995 111891 223995 111891 223996 111880 223996 111882 223996 111891 223997 111882 223997 111883 223997 111883 223998 111882 223998 111884 223998 111883 223999 111884 223999 111893 223999 111063 224000 111851 224000 111064 224000 111064 224001 111851 224001 111853 224001 111064 224002 111853 224002 111065 224002 111065 224003 111853 224003 111865 224003 111065 224004 111865 224004 111066 224004 111066 224005 111865 224005 111850 224005 111066 224006 111850 224006 111854 224006 111854 224007 111850 224007 111885 224007 111854 224008 111885 224008 111886 224008 111886 224009 111885 224009 111876 224009 111886 224010 111876 224010 111856 224010 111856 224011 111876 224011 111877 224011 111856 224012 111877 224012 111887 224012 111887 224013 111877 224013 111878 224013 111887 224014 111878 224014 111888 224014 111888 224015 111878 224015 111889 224015 111888 224016 111889 224016 111890 224016 111890 224017 111889 224017 111881 224017 111890 224018 111881 224018 111863 224018 111863 224019 111881 224019 111891 224019 111863 224020 111891 224020 111862 224020 111862 224021 111891 224021 111883 224021 111862 224022 111883 224022 111892 224022 111892 224023 111883 224023 111893 224023 111892 224024 111893 224024 111849 224024 111824 224025 111862 224025 111894 224025 111894 224026 111862 224026 111892 224026 111894 224027 111892 224027 111826 224027 111826 224028 111892 224028 111843 224028 111826 224029 111843 224029 111827 224029 111149 224030 111896 224030 111895 224030 111895 224031 111896 224031 111921 224031 111895 224032 111921 224032 111903 224032 111903 224033 111921 224033 111920 224033 111903 224034 111920 224034 111901 224034 111901 224035 111920 224035 111919 224035 111901 224036 111919 224036 111897 224036 111897 224037 111919 224037 111917 224037 111897 224038 111917 224038 111898 224038 111898 224039 111917 224039 111916 224039 111898 224040 111916 224040 111899 224040 111899 224041 111916 224041 111915 224041 111899 224042 111900 224042 111898 224042 111898 224043 111900 224043 111940 224043 111898 224044 111940 224044 111897 224044 111897 224045 111940 224045 111901 224045 111901 224046 111940 224046 111902 224046 111901 224047 111902 224047 111903 224047 111903 224048 111902 224048 111895 224048 111895 224049 111902 224049 111955 224049 111895 224050 111955 224050 111149 224050 111906 224051 111980 224051 111904 224051 111980 224052 111981 224052 111904 224052 111904 224053 111981 224053 111983 224053 111904 224054 111983 224054 111085 224054 111085 224055 111983 224055 111984 224055 111085 224056 111984 224056 111985 224056 111545 224057 111911 224057 111905 224057 111905 224058 111911 224058 111977 224058 111905 224059 111977 224059 111904 224059 111904 224060 111977 224060 111979 224060 111904 224061 111979 224061 111906 224061 111157 224062 111907 224062 111908 224062 111908 224063 111907 224063 111909 224063 111908 224064 111909 224064 111918 224064 111986 224065 111911 224065 111910 224065 111910 224066 111911 224066 111545 224066 111910 224067 111545 224067 111913 224067 111913 224068 111545 224068 111912 224068 111913 224069 111912 224069 111914 224069 111914 224070 111915 224070 111913 224070 111913 224071 111915 224071 111916 224071 111913 224072 111916 224072 111917 224072 111917 224073 111908 224073 111913 224073 111913 224074 111908 224074 111918 224074 111913 224075 111918 224075 111910 224075 111910 224076 111918 224076 111986 224076 111917 224077 111919 224077 111908 224077 111908 224078 111919 224078 111920 224078 111908 224079 111920 224079 111157 224079 111157 224080 111920 224080 111921 224080 111157 224081 111921 224081 111896 224081 111940 224082 111900 224082 111922 224082 111922 224083 111900 224083 111924 224083 111922 224084 111924 224084 111923 224084 111923 224085 111924 224085 111159 224085 111923 224086 111159 224086 111925 224086 111925 224087 111159 224087 111926 224087 111925 224088 111926 224088 111943 224088 111943 224089 111926 224089 111927 224089 111943 224090 111927 224090 111928 224090 111928 224091 111927 224091 111162 224091 111928 224092 111162 224092 111929 224092 111929 224093 111162 224093 111163 224093 111929 224094 111163 224094 111930 224094 111930 224095 111163 224095 111164 224095 111930 224096 111164 224096 111931 224096 111931 224097 111164 224097 111165 224097 111931 224098 111165 224098 111932 224098 111932 224099 111165 224099 111166 224099 111932 224100 111166 224100 111933 224100 111933 224101 111166 224101 111934 224101 111933 224102 111934 224102 111935 224102 111935 224103 111934 224103 111936 224103 111935 224104 111936 224104 111951 224104 111951 224105 111936 224105 111937 224105 111951 224106 111937 224106 111953 224106 111953 224107 111937 224107 111171 224107 111953 224108 111171 224108 111938 224108 111938 224109 111171 224109 111174 224109 111938 224110 111174 224110 111954 224110 111954 224111 111174 224111 111175 224111 111954 224112 111175 224112 111939 224112 111939 224113 111175 224113 112022 224113 111902 224114 111940 224114 111941 224114 111941 224115 111940 224115 111922 224115 111941 224116 111922 224116 111957 224116 111957 224117 111922 224117 111923 224117 111957 224118 111923 224118 111942 224118 111942 224119 111923 224119 111925 224119 111942 224120 111925 224120 111944 224120 111944 224121 111925 224121 111943 224121 111944 224122 111943 224122 111945 224122 111945 224123 111943 224123 111928 224123 111945 224124 111928 224124 111946 224124 111946 224125 111928 224125 111929 224125 111946 224126 111929 224126 111947 224126 111947 224127 111929 224127 111930 224127 111947 224128 111930 224128 111948 224128 111948 224129 111930 224129 111931 224129 111948 224130 111931 224130 111949 224130 111949 224131 111931 224131 111932 224131 111949 224132 111932 224132 111950 224132 111950 224133 111932 224133 111933 224133 111950 224134 111933 224134 111964 224134 111964 224135 111933 224135 111935 224135 111964 224136 111935 224136 111952 224136 111952 224137 111935 224137 111951 224137 111952 224138 111951 224138 111966 224138 111966 224139 111951 224139 111953 224139 111966 224140 111953 224140 111968 224140 111968 224141 111953 224141 111938 224141 111968 224142 111938 224142 111971 224142 111971 224143 111938 224143 111954 224143 111971 224144 111954 224144 112024 224144 112024 224145 111954 224145 111939 224145 111955 224146 111902 224146 111150 224146 111150 224147 111902 224147 111941 224147 111150 224148 111941 224148 111956 224148 111956 224149 111941 224149 111957 224149 111956 224150 111957 224150 111147 224150 111147 224151 111957 224151 111942 224151 111147 224152 111942 224152 111958 224152 111958 224153 111942 224153 111944 224153 111958 224154 111944 224154 111959 224154 111959 224155 111944 224155 111945 224155 111959 224156 111945 224156 111145 224156 111145 224157 111945 224157 111946 224157 111145 224158 111946 224158 111960 224158 111960 224159 111946 224159 111947 224159 111960 224160 111947 224160 111961 224160 111961 224161 111947 224161 111948 224161 111961 224162 111948 224162 111962 224162 111962 224163 111948 224163 111949 224163 111962 224164 111949 224164 111142 224164 111142 224165 111949 224165 111950 224165 111142 224166 111950 224166 111963 224166 111963 224167 111950 224167 111964 224167 111963 224168 111964 224168 111965 224168 111965 224169 111964 224169 111952 224169 111965 224170 111952 224170 111152 224170 111152 224171 111952 224171 111966 224171 111152 224172 111966 224172 111967 224172 111967 224173 111966 224173 111968 224173 111967 224174 111968 224174 111969 224174 111969 224175 111968 224175 111971 224175 111969 224176 111971 224176 111970 224176 111970 224177 111971 224177 112024 224177 112027 224178 112021 224178 111972 224178 111989 224179 111973 224179 111985 224179 111989 224180 111985 224180 111990 224180 111087 224181 111086 224181 111999 224181 111999 224182 111086 224182 111973 224182 111976 224183 111974 224183 111975 224183 111975 224184 111974 224184 111087 224184 111975 224185 111087 224185 112010 224185 110725 224186 110729 224186 111976 224186 111911 224187 111978 224187 111977 224187 111977 224188 111978 224188 111996 224188 111977 224189 111996 224189 111979 224189 111979 224190 111996 224190 111994 224190 111979 224191 111994 224191 111906 224191 111906 224192 111994 224192 111993 224192 111906 224193 111993 224193 111980 224193 111980 224194 111993 224194 111992 224194 111980 224195 111992 224195 111981 224195 111981 224196 111992 224196 111982 224196 111981 224197 111982 224197 111983 224197 111983 224198 111982 224198 111990 224198 111983 224199 111990 224199 111984 224199 111984 224200 111990 224200 111985 224200 111911 224201 111986 224201 111978 224201 111978 224202 111986 224202 111987 224202 111987 224203 111986 224203 111918 224203 111987 224204 111918 224204 111909 224204 111909 224205 111907 224205 111987 224205 111987 224206 111907 224206 111988 224206 111987 224207 111988 224207 111998 224207 111973 224208 111989 224208 111999 224208 111999 224209 111989 224209 111990 224209 111999 224210 111990 224210 112000 224210 112000 224211 111990 224211 111982 224211 112000 224212 111982 224212 111991 224212 111991 224213 111982 224213 111992 224213 111991 224214 111992 224214 112002 224214 112002 224215 111992 224215 111993 224215 112002 224216 111993 224216 112003 224216 112003 224217 111993 224217 111994 224217 112003 224218 111994 224218 111995 224218 111995 224219 111994 224219 111996 224219 111995 224220 111996 224220 112007 224220 112007 224221 111996 224221 111978 224221 112007 224222 111978 224222 112008 224222 112008 224223 111978 224223 111987 224223 112008 224224 111987 224224 111997 224224 111997 224225 111987 224225 111998 224225 111997 224226 111998 224226 112009 224226 111087 224227 111999 224227 112010 224227 112010 224228 111999 224228 112000 224228 112010 224229 112000 224229 112011 224229 112011 224230 112000 224230 111991 224230 112011 224231 111991 224231 112001 224231 112001 224232 111991 224232 112002 224232 112001 224233 112002 224233 112014 224233 112014 224234 112002 224234 112003 224234 112014 224235 112003 224235 112004 224235 112004 224236 112003 224236 111995 224236 112004 224237 111995 224237 112005 224237 112005 224238 111995 224238 112007 224238 112005 224239 112007 224239 112006 224239 112006 224240 112007 224240 112008 224240 112006 224241 112008 224241 112018 224241 112018 224242 112008 224242 111997 224242 112018 224243 111997 224243 111972 224243 111972 224244 111997 224244 112009 224244 111972 224245 112009 224245 112027 224245 111976 224246 111975 224246 110725 224246 110725 224247 111975 224247 112010 224247 110725 224248 112010 224248 110724 224248 110724 224249 112010 224249 112011 224249 110724 224250 112011 224250 112012 224250 112012 224251 112011 224251 112001 224251 112012 224252 112001 224252 112013 224252 112013 224253 112001 224253 112014 224253 112013 224254 112014 224254 112015 224254 112015 224255 112014 224255 112004 224255 112015 224256 112004 224256 112016 224256 112016 224257 112004 224257 112005 224257 112016 224258 112005 224258 112017 224258 112017 224259 112005 224259 112006 224259 112017 224260 112006 224260 112019 224260 112019 224261 112006 224261 112018 224261 112019 224262 112018 224262 112020 224262 112020 224263 112018 224263 111972 224263 112020 224264 111972 224264 110727 224264 110727 224265 111972 224265 112021 224265 110727 224266 112021 224266 110728 224266 112037 224267 112036 224267 112022 224267 112022 224268 112036 224268 111939 224268 112036 224269 112023 224269 111939 224269 111939 224270 112023 224270 112034 224270 111939 224271 112034 224271 112024 224271 112032 224272 111970 224272 112033 224272 112033 224273 111970 224273 112024 224273 112033 224274 112024 224274 112025 224274 112025 224275 112024 224275 112034 224275 112026 224276 111156 224276 112038 224276 111907 224277 111156 224277 111988 224277 111988 224278 111156 224278 112026 224278 111988 224279 112026 224279 111998 224279 111998 224280 112026 224280 112009 224280 112009 224281 112026 224281 112030 224281 112009 224282 112030 224282 112027 224282 112027 224283 112030 224283 112021 224283 112021 224284 112030 224284 112028 224284 112021 224285 112028 224285 110728 224285 112038 224286 112039 224286 112026 224286 112026 224287 112039 224287 112029 224287 112026 224288 112029 224288 112030 224288 112030 224289 112029 224289 112041 224289 112030 224290 112041 224290 112028 224290 112028 224291 112041 224291 110708 224291 112031 224292 112032 224292 112061 224292 112061 224293 112032 224293 112033 224293 112061 224294 112033 224294 112059 224294 112059 224295 112033 224295 112025 224295 112059 224296 112025 224296 112058 224296 112058 224297 112025 224297 112034 224297 112058 224298 112034 224298 112056 224298 112056 224299 112034 224299 112023 224299 112056 224300 112023 224300 112035 224300 112035 224301 112023 224301 112036 224301 112035 224302 112036 224302 111458 224302 111458 224303 112036 224303 112037 224303 112038 224304 111155 224304 112062 224304 112038 224305 112062 224305 112039 224305 112039 224306 112062 224306 112064 224306 112039 224307 112064 224307 112029 224307 112029 224308 112064 224308 112040 224308 112029 224309 112040 224309 112041 224309 112041 224310 112040 224310 112042 224310 112041 224311 112042 224311 110708 224311 112053 224312 112070 224312 112043 224312 112043 224313 112070 224313 112057 224313 112057 224314 112070 224314 112105 224314 112057 224315 112105 224315 112060 224315 112060 224316 112105 224316 112045 224316 112060 224317 112045 224317 112044 224317 112044 224318 112045 224318 112066 224318 112046 224319 112072 224319 112047 224319 112047 224320 112072 224320 112073 224320 112047 224321 112073 224321 112048 224321 112073 224322 112049 224322 112048 224322 112048 224323 112049 224323 112050 224323 112048 224324 112050 224324 112077 224324 112057 224325 112056 224325 112035 224325 112077 224326 112051 224326 112048 224326 112048 224327 112051 224327 112052 224327 112048 224328 112052 224328 111440 224328 111440 224329 112052 224329 112053 224329 111440 224330 112053 224330 111439 224330 111439 224331 112053 224331 112043 224331 111439 224332 112043 224332 112054 224332 112054 224333 112043 224333 112057 224333 112054 224334 112057 224334 112055 224334 112055 224335 112057 224335 112035 224335 112055 224336 112035 224336 111458 224336 112056 224337 112057 224337 112058 224337 112058 224338 112057 224338 112060 224338 112058 224339 112060 224339 112059 224339 112059 224340 112060 224340 112061 224340 112061 224341 112060 224341 112044 224341 112061 224342 112044 224342 112031 224342 111155 224343 111151 224343 112062 224343 112062 224344 111151 224344 112063 224344 112062 224345 112063 224345 112064 224345 112064 224346 112063 224346 112068 224346 112064 224347 112068 224347 112040 224347 112040 224348 112068 224348 112065 224348 112040 224349 112065 224349 112042 224349 112042 224350 112065 224350 110722 224350 111151 224351 112066 224351 112063 224351 112063 224352 112066 224352 112067 224352 112063 224353 112067 224353 112068 224353 112068 224354 112067 224354 112109 224354 112068 224355 112109 224355 112065 224355 112065 224356 112109 224356 112069 224356 112065 224357 112069 224357 110722 224357 110722 224358 112069 224358 110720 224358 112105 224359 112070 224359 112104 224359 112086 224360 112097 224360 112071 224360 111128 224361 111127 224361 112095 224361 112099 224362 111126 224362 112098 224362 112078 224363 112095 224363 110718 224363 111126 224364 112099 224364 112046 224364 112046 224365 112099 224365 112100 224365 112046 224366 112100 224366 112072 224366 112072 224367 112100 224367 112101 224367 112072 224368 112101 224368 112073 224368 112073 224369 112101 224369 112074 224369 112073 224370 112074 224370 112049 224370 112049 224371 112074 224371 112103 224371 112049 224372 112103 224372 112050 224372 112050 224373 112103 224373 112075 224373 112050 224374 112075 224374 112077 224374 112077 224375 112075 224375 112076 224375 112077 224376 112076 224376 112051 224376 112078 224377 110718 224377 112097 224377 112097 224378 110718 224378 112079 224378 112097 224379 112079 224379 112071 224379 112071 224380 112079 224380 112081 224380 112071 224381 112081 224381 112080 224381 112080 224382 112081 224382 112083 224382 112080 224383 112083 224383 112082 224383 112082 224384 112083 224384 110717 224384 112082 224385 110717 224385 112084 224385 112084 224386 110717 224386 112085 224386 112084 224387 112085 224387 112090 224387 112090 224388 112085 224388 110716 224388 112090 224389 110716 224389 112092 224389 112092 224390 110716 224390 110715 224390 112092 224391 110715 224391 112094 224391 112086 224392 112071 224392 112087 224392 112087 224393 112071 224393 112080 224393 112087 224394 112080 224394 112088 224394 112088 224395 112080 224395 112082 224395 112088 224396 112082 224396 112089 224396 112089 224397 112082 224397 112084 224397 112089 224398 112084 224398 112102 224398 112102 224399 112084 224399 112090 224399 112102 224400 112090 224400 112091 224400 112091 224401 112090 224401 112092 224401 112091 224402 112092 224402 112093 224402 112093 224403 112092 224403 112094 224403 112093 224404 112094 224404 112107 224404 111128 224405 112095 224405 111129 224405 111129 224406 112095 224406 112078 224406 111129 224407 112078 224407 112096 224407 112096 224408 112078 224408 112097 224408 112096 224409 112097 224409 112098 224409 112098 224410 112097 224410 112086 224410 112098 224411 112086 224411 112099 224411 112099 224412 112086 224412 112087 224412 112099 224413 112087 224413 112100 224413 112100 224414 112087 224414 112088 224414 112100 224415 112088 224415 112101 224415 112101 224416 112088 224416 112089 224416 112101 224417 112089 224417 112074 224417 112074 224418 112089 224418 112102 224418 112074 224419 112102 224419 112103 224419 112103 224420 112102 224420 112091 224420 112103 224421 112091 224421 112075 224421 112075 224422 112091 224422 112093 224422 112075 224423 112093 224423 112076 224423 112076 224424 112093 224424 112107 224424 112076 224425 112107 224425 112104 224425 112104 224426 112070 224426 112053 224426 112104 224427 112053 224427 112076 224427 112076 224428 112053 224428 112052 224428 112076 224429 112052 224429 112051 224429 112045 224430 112105 224430 112106 224430 112106 224431 112105 224431 112104 224431 112106 224432 112104 224432 112110 224432 112110 224433 112104 224433 112107 224433 112110 224434 112107 224434 112111 224434 112111 224435 112107 224435 112094 224435 112111 224436 112094 224436 112108 224436 112108 224437 112094 224437 110715 224437 112066 224438 112045 224438 112067 224438 112067 224439 112045 224439 112106 224439 112067 224440 112106 224440 112109 224440 112109 224441 112106 224441 112110 224441 112109 224442 112110 224442 112069 224442 112069 224443 112110 224443 112111 224443 112069 224444 112111 224444 110720 224444 110720 224445 112111 224445 112108 224445 112119 224446 111190 224446 110829 224446 110829 224447 111190 224447 111189 224447 110829 224448 111189 224448 110828 224448 110828 224449 111189 224449 112112 224449 110828 224450 112112 224450 110825 224450 110825 224451 112112 224451 111180 224451 110825 224452 111180 224452 110824 224452 110824 224453 111180 224453 111181 224453 110824 224454 111181 224454 110835 224454 110835 224455 111181 224455 111186 224455 110835 224456 111186 224456 110827 224456 110827 224457 111186 224457 111188 224457 110827 224458 111188 224458 110821 224458 110821 224459 111188 224459 111194 224459 110821 224460 111194 224460 112114 224460 112114 224461 111194 224461 112113 224461 112114 224462 112113 224462 110823 224462 110823 224463 112113 224463 112115 224463 110823 224464 112115 224464 112116 224464 112116 224465 112115 224465 112117 224465 112116 224466 112117 224466 112118 224466 112118 224467 112117 224467 111192 224467 112118 224468 111192 224468 112119 224468 112119 224469 111192 224469 111190 224469 110874 224470 111146 224470 110876 224470 110876 224471 111146 224471 111143 224471 110876 224472 111143 224472 110860 224472 110860 224473 111143 224473 111144 224473 110860 224474 111144 224474 112120 224474 112120 224475 111144 224475 112121 224475 112120 224476 112121 224476 110858 224476 110858 224477 112121 224477 111153 224477 110858 224478 111153 224478 110855 224478 110855 224479 111153 224479 112122 224479 110855 224480 112122 224480 110857 224480 110857 224481 112122 224481 112123 224481 110857 224482 112123 224482 110856 224482 110856 224483 112123 224483 111154 224483 110856 224484 111154 224484 110865 224484 110865 224485 111154 224485 112124 224485 110865 224486 112124 224486 110864 224486 110864 224487 112124 224487 111148 224487 110864 224488 111148 224488 112125 224488 112125 224489 111148 224489 111141 224489 112125 224490 111141 224490 110861 224490 110861 224491 111141 224491 112126 224491 110861 224492 112126 224492 110874 224492 110874 224493 112126 224493 111146 224493 110937 224494 112127 224494 110930 224494 110930 224495 112127 224495 112132 224495 110935 224496 112128 224496 112129 224496 110935 224497 112129 224497 110933 224497 110933 224498 112129 224498 110917 224498 110933 224499 110917 224499 112130 224499 112130 224500 110917 224500 110918 224500 112130 224501 110918 224501 112131 224501 112131 224502 110918 224502 112127 224502 112131 224503 112127 224503 110937 224503 110930 224504 112132 224504 112133 224504 110930 224505 112133 224505 112134 224505 112134 224506 112133 224506 110921 224506 112134 224507 110921 224507 112135 224507 112135 224508 110921 224508 112136 224508 112135 224509 112136 224509 110938 224509 110938 224510 112136 224510 112138 224510 110938 224511 112138 224511 110939 224511 110936 224512 112137 224512 110935 224512 110935 224513 112137 224513 112128 224513 112144 224514 110932 224514 112138 224514 112138 224515 110932 224515 110939 224515 112139 224516 112140 224516 110911 224516 112139 224517 110911 224517 112141 224517 112141 224518 110911 224518 110912 224518 112141 224519 110912 224519 110934 224519 110934 224520 110912 224520 112142 224520 110934 224521 112142 224521 112143 224521 112143 224522 112142 224522 112137 224522 112143 224523 112137 224523 110936 224523 110932 224524 112144 224524 110924 224524 110932 224525 110924 224525 112145 224525 112145 224526 110924 224526 110925 224526 112145 224527 110925 224527 110931 224527 110931 224528 110925 224528 112147 224528 110931 224529 112147 224529 112146 224529 112146 224530 112147 224530 110928 224530 112146 224531 110928 224531 112148 224531 112148 224532 110928 224532 112139 224532 112139 224533 110928 224533 112140 224533 110902 224534 110893 224534 112149 224534 112149 224535 110893 224535 110894 224535 112159 224536 110887 224536 112150 224536 112159 224537 112150 224537 112151 224537 112151 224538 112150 224538 110890 224538 112151 224539 110890 224539 112152 224539 112152 224540 110890 224540 110891 224540 112152 224541 110891 224541 112153 224541 112153 224542 110891 224542 110893 224542 112153 224543 110893 224543 110902 224543 112149 224544 110894 224544 112155 224544 112149 224545 112155 224545 112154 224545 112154 224546 112155 224546 112156 224546 112154 224547 112156 224547 112157 224547 112157 224548 112156 224548 110895 224548 112157 224549 110895 224549 110907 224549 110907 224550 110895 224550 112158 224550 110907 224551 112158 224551 110903 224551 110905 224552 110886 224552 112159 224552 112159 224553 110886 224553 110887 224553 110897 224554 112166 224554 112158 224554 112158 224555 112166 224555 110903 224555 110909 224556 112160 224556 112161 224556 110909 224557 112161 224557 112162 224557 112162 224558 112161 224558 112163 224558 112162 224559 112163 224559 112164 224559 112164 224560 112163 224560 112165 224560 112164 224561 112165 224561 110908 224561 110908 224562 112165 224562 110886 224562 110908 224563 110886 224563 110905 224563 112166 224564 110897 224564 112167 224564 112166 224565 112167 224565 110904 224565 110904 224566 112167 224566 110899 224566 110904 224567 110899 224567 112168 224567 112168 224568 110899 224568 112169 224568 112168 224569 112169 224569 112170 224569 112170 224570 112169 224570 110900 224570 112170 224571 110900 224571 110906 224571 110906 224572 110900 224572 110909 224572 110909 224573 110900 224573 112160 224573 112171 224574 112176 224574 112177 224574 112177 224575 112176 224575 110951 224575 112173 224576 110945 224576 112172 224576 112173 224577 112172 224577 112174 224577 112174 224578 112172 224578 110947 224578 112174 224579 110947 224579 112175 224579 112175 224580 110947 224580 110949 224580 112175 224581 110949 224581 110963 224581 110963 224582 110949 224582 112176 224582 110963 224583 112176 224583 112171 224583 112177 224584 110951 224584 110952 224584 112177 224585 110952 224585 110969 224585 110969 224586 110952 224586 112178 224586 110969 224587 112178 224587 112179 224587 112179 224588 112178 224588 110953 224588 112179 224589 110953 224589 110967 224589 110967 224590 110953 224590 112180 224590 110967 224591 112180 224591 110968 224591 110966 224592 110944 224592 112173 224592 112173 224593 110944 224593 110945 224593 110955 224594 112184 224594 112180 224594 112180 224595 112184 224595 110968 224595 110964 224596 110959 224596 110941 224596 110964 224597 110941 224597 112181 224597 112181 224598 110941 224598 112182 224598 112181 224599 112182 224599 112183 224599 112183 224600 112182 224600 110942 224600 112183 224601 110942 224601 110965 224601 110965 224602 110942 224602 110944 224602 110965 224603 110944 224603 110966 224603 112184 224604 110955 224604 110956 224604 112184 224605 110956 224605 110961 224605 110961 224606 110956 224606 110958 224606 110961 224607 110958 224607 110962 224607 110962 224608 110958 224608 112185 224608 110962 224609 112185 224609 112186 224609 112186 224610 112185 224610 112188 224610 112186 224611 112188 224611 112187 224611 112187 224612 112188 224612 110964 224612 110964 224613 112188 224613 110959 224613 123619 224614 119330 224614 123606 224614 123606 224615 119330 224615 112190 224615 123606 224616 112190 224616 112189 224616 112189 224617 112190 224617 123607 224617 123607 224618 112190 224618 123594 224618 123594 224619 112190 224619 112194 224619 123594 224620 112194 224620 112191 224620 112195 224621 112192 224621 112193 224621 112193 224622 112192 224622 123609 224622 112193 224623 123609 224623 112194 224623 112194 224624 123609 224624 123610 224624 112194 224625 123610 224625 112191 224625 112195 224626 112193 224626 123612 224626 123612 224627 112193 224627 119353 224627 123612 224628 119353 224628 123586 224628 123586 224629 119353 224629 119352 224629 123586 224630 119352 224630 123585 224630 123585 224631 119352 224631 112196 224631 123585 224632 112196 224632 123583 224632 123583 224633 112196 224633 119355 224633 123583 224634 119355 224634 123582 224634 123857 224635 123884 224635 112205 224635 112205 224636 123884 224636 114157 224636 112199 224637 112197 224637 112204 224637 123915 224638 112198 224638 114202 224638 112199 224639 112204 224639 112201 224639 112204 224640 112200 224640 112201 224640 112201 224641 112200 224641 112202 224641 112201 224642 112202 224642 114201 224642 114201 224643 112202 224643 123848 224643 114201 224644 123848 224644 114202 224644 114202 224645 123848 224645 112203 224645 114202 224646 112203 224646 123915 224646 123844 224647 123843 224647 112197 224647 112197 224648 123843 224648 123846 224648 112197 224649 123846 224649 112204 224649 123844 224650 112197 224650 123884 224650 123884 224651 112197 224651 114156 224651 123884 224652 114156 224652 114157 224652 112206 224653 123841 224653 112205 224653 112205 224654 123841 224654 123840 224654 112205 224655 123840 224655 123857 224655 112205 224656 114152 224656 112206 224656 112206 224657 114152 224657 114153 224657 112206 224658 114153 224658 123893 224658 123893 224659 114153 224659 123842 224659 120523 224660 123842 224660 114149 224660 123842 224661 114153 224661 114155 224661 123842 224662 114155 224662 114149 224662 112207 224663 119848 224663 119849 224663 112207 224664 119849 224664 122768 224664 122768 224665 119849 224665 122770 224665 122770 224666 119849 224666 122764 224666 122764 224667 119849 224667 119844 224667 122764 224668 119844 224668 122776 224668 122776 224669 119844 224669 119852 224669 122776 224670 119852 224670 122777 224670 122777 224671 119852 224671 112208 224671 122777 224672 112208 224672 122762 224672 122762 224673 112208 224673 119850 224673 122762 224674 119850 224674 112209 224674 112209 224675 119850 224675 112210 224675 112209 224676 112210 224676 112211 224676 114553 224677 114554 224677 112218 224677 112212 224678 112213 224678 114552 224678 112212 224679 114552 224679 112214 224679 114553 224680 112218 224680 114552 224680 114552 224681 112218 224681 124639 224681 114552 224682 124639 224682 112214 224682 124612 224683 112215 224683 112216 224683 124612 224684 112216 224684 112220 224684 112216 224685 112215 224685 124616 224685 112216 224686 124616 224686 114554 224686 114554 224687 124616 224687 112217 224687 114554 224688 112217 224688 112218 224688 114532 224689 119763 224689 114533 224689 114533 224690 119763 224690 124614 224690 112216 224691 112219 224691 112220 224691 112220 224692 112219 224692 114533 224692 112220 224693 114533 224693 112221 224693 112221 224694 114533 224694 124614 224694 123281 224695 119646 224695 123282 224695 123282 224696 119646 224696 112223 224696 123282 224697 112223 224697 112222 224697 112222 224698 112223 224698 112225 224698 112225 224699 112223 224699 112224 224699 112225 224700 112224 224700 123288 224700 123288 224701 112224 224701 112226 224701 123288 224702 112226 224702 123292 224702 112226 224703 112227 224703 123292 224703 123292 224704 112227 224704 112228 224704 123292 224705 112228 224705 123291 224705 123291 224706 112228 224706 119649 224706 123291 224707 119649 224707 123289 224707 114643 224708 114642 224708 112233 224708 112233 224709 112229 224709 114643 224709 114643 224710 112229 224710 112230 224710 114643 224711 112230 224711 114637 224711 114637 224712 112230 224712 112231 224712 114637 224713 112231 224713 119517 224713 119517 224714 112231 224714 124845 224714 119517 224715 124845 224715 112232 224715 114642 224716 114640 224716 112233 224716 112233 224717 114640 224717 114638 224717 112233 224718 114638 224718 124882 224718 114639 224719 112234 224719 114638 224719 114638 224720 112234 224720 124882 224720 114639 224721 112235 224721 112234 224721 112234 224722 112235 224722 119523 224722 123364 224723 123304 224723 119373 224723 119373 224724 119374 224724 123364 224724 123364 224725 119374 224725 112236 224725 123364 224726 112236 224726 123363 224726 123363 224727 112236 224727 112237 224727 123363 224728 112237 224728 112238 224728 112238 224729 112237 224729 119371 224729 112238 224730 119371 224730 112239 224730 112239 224731 119371 224731 112240 224731 112239 224732 112240 224732 112241 224732 112241 224733 112240 224733 112242 224733 112242 224734 112240 224734 119369 224734 112242 224735 119369 224735 112243 224735 125121 224736 112244 224736 116228 224736 125116 224737 125059 224737 116231 224737 116231 224738 125059 224738 119291 224738 116228 224739 112244 224739 116230 224739 112244 224740 112245 224740 116230 224740 116230 224741 112245 224741 112246 224741 116230 224742 112246 224742 116233 224742 116233 224743 112246 224743 125090 224743 116233 224744 125090 224744 116231 224744 116231 224745 125090 224745 125117 224745 116231 224746 125117 224746 125116 224746 125095 224747 112248 224747 112247 224747 112247 224748 112248 224748 116226 224748 112247 224749 116226 224749 119300 224749 125095 224750 125094 224750 112248 224750 112248 224751 125094 224751 112249 224751 112248 224752 112249 224752 116228 224752 116228 224753 112249 224753 125122 224753 116228 224754 125122 224754 125121 224754 112262 224755 112273 224755 112274 224755 114082 224756 114081 224756 112258 224756 119198 224757 112250 224757 112267 224757 116082 224758 112251 224758 112280 224758 116082 224759 112280 224759 116090 224759 116090 224760 112280 224760 112281 224760 116090 224761 112281 224761 116092 224761 116092 224762 112281 224762 112254 224762 116092 224763 112254 224763 116093 224763 112256 224764 116097 224764 112286 224764 112286 224765 116097 224765 112252 224765 112286 224766 112252 224766 112285 224766 112285 224767 112252 224767 116096 224767 112285 224768 116096 224768 112253 224768 112253 224769 116096 224769 112255 224769 112253 224770 112255 224770 112254 224770 112254 224771 112255 224771 116094 224771 112254 224772 116094 224772 116093 224772 112286 224773 112287 224773 112256 224773 112256 224774 112287 224774 112288 224774 112256 224775 112288 224775 116099 224775 119198 224776 112267 224776 119196 224776 112278 224777 112279 224777 114076 224777 112278 224778 114076 224778 112257 224778 112257 224779 114076 224779 114077 224779 112257 224780 114077 224780 112258 224780 112258 224781 114077 224781 114083 224781 112258 224782 114083 224782 114082 224782 112259 224783 112275 224783 112270 224783 112259 224784 112260 224784 112275 224784 112275 224785 112260 224785 114071 224785 112275 224786 114071 224786 112271 224786 119211 224787 112262 224787 112261 224787 112261 224788 112262 224788 112274 224788 112261 224789 112274 224789 112282 224789 112282 224790 112274 224790 112276 224790 112282 224791 112276 224791 112283 224791 112283 224792 112276 224792 112263 224792 112283 224793 112263 224793 112284 224793 112284 224794 112263 224794 112265 224794 112284 224795 112265 224795 112264 224795 112264 224796 112265 224796 112278 224796 112264 224797 112278 224797 112266 224797 112266 224798 112278 224798 112257 224798 112266 224799 112257 224799 112267 224799 112267 224800 112257 224800 112258 224800 112267 224801 112258 224801 119196 224801 119196 224802 112258 224802 114081 224802 119196 224803 114081 224803 112268 224803 114068 224804 112269 224804 112270 224804 112270 224805 112269 224805 114066 224805 112270 224806 114066 224806 112259 224806 114071 224807 114074 224807 112271 224807 112271 224808 114074 224808 114073 224808 112271 224809 114073 224809 112272 224809 112272 224810 114073 224810 112277 224810 119188 224811 114068 224811 112273 224811 112273 224812 114068 224812 112270 224812 112273 224813 112270 224813 112274 224813 112274 224814 112270 224814 112275 224814 112274 224815 112275 224815 112276 224815 112276 224816 112275 224816 112271 224816 112276 224817 112271 224817 112263 224817 112263 224818 112271 224818 112272 224818 112263 224819 112272 224819 112265 224819 112265 224820 112272 224820 112277 224820 112265 224821 112277 224821 112278 224821 112278 224822 112277 224822 114075 224822 112278 224823 114075 224823 112279 224823 112251 224824 119211 224824 112280 224824 112280 224825 119211 224825 112261 224825 112280 224826 112261 224826 112281 224826 112281 224827 112261 224827 112282 224827 112281 224828 112282 224828 112254 224828 112254 224829 112282 224829 112283 224829 112254 224830 112283 224830 112253 224830 112253 224831 112283 224831 112284 224831 112253 224832 112284 224832 112285 224832 112285 224833 112284 224833 112264 224833 112285 224834 112264 224834 112286 224834 112286 224835 112264 224835 112266 224835 112286 224836 112266 224836 112287 224836 112287 224837 112266 224837 112267 224837 112287 224838 112267 224838 112288 224838 112288 224839 112267 224839 112250 224839 112305 224840 112318 224840 112306 224840 112289 224841 112313 224841 112300 224841 112290 224842 119156 224842 112312 224842 119135 224843 119134 224843 112325 224843 119135 224844 112325 224844 116114 224844 116114 224845 112325 224845 112328 224845 116114 224846 112328 224846 112291 224846 112291 224847 112328 224847 112292 224847 112291 224848 112292 224848 112296 224848 112297 224849 112293 224849 112294 224849 112294 224850 112293 224850 116122 224850 112294 224851 116122 224851 112331 224851 112331 224852 116122 224852 116121 224852 112331 224853 116121 224853 112329 224853 112329 224854 116121 224854 116120 224854 112329 224855 116120 224855 112292 224855 112292 224856 116120 224856 112295 224856 112292 224857 112295 224857 112296 224857 112294 224858 112298 224858 112297 224858 112297 224859 112298 224859 119162 224859 112297 224860 119162 224860 116106 224860 112290 224861 112312 224861 119154 224861 112322 224862 112324 224862 114132 224862 112322 224863 114132 224863 112311 224863 112311 224864 114132 224864 112299 224864 112311 224865 112299 224865 112300 224865 112300 224866 112299 224866 114133 224866 112300 224867 114133 224867 112289 224867 114125 224868 112302 224868 112319 224868 114125 224869 112301 224869 112302 224869 112302 224870 112301 224870 112303 224870 112302 224871 112303 224871 112316 224871 112326 224872 112305 224872 112304 224872 112304 224873 112305 224873 112306 224873 112304 224874 112306 224874 112327 224874 112327 224875 112306 224875 112307 224875 112327 224876 112307 224876 112308 224876 112308 224877 112307 224877 112309 224877 112308 224878 112309 224878 112330 224878 112330 224879 112309 224879 112321 224879 112330 224880 112321 224880 112332 224880 112332 224881 112321 224881 112322 224881 112332 224882 112322 224882 112310 224882 112310 224883 112322 224883 112311 224883 112310 224884 112311 224884 112312 224884 112312 224885 112311 224885 112300 224885 112312 224886 112300 224886 119154 224886 119154 224887 112300 224887 112313 224887 119154 224888 112313 224888 114134 224888 114124 224889 112314 224889 112319 224889 112319 224890 112314 224890 112315 224890 112319 224891 112315 224891 114125 224891 112303 224892 114127 224892 112316 224892 112316 224893 114127 224893 114131 224893 112316 224894 114131 224894 112320 224894 112320 224895 114131 224895 114130 224895 112317 224896 114124 224896 112318 224896 112318 224897 114124 224897 112319 224897 112318 224898 112319 224898 112306 224898 112306 224899 112319 224899 112302 224899 112306 224900 112302 224900 112307 224900 112307 224901 112302 224901 112316 224901 112307 224902 112316 224902 112309 224902 112309 224903 112316 224903 112320 224903 112309 224904 112320 224904 112321 224904 112321 224905 112320 224905 114130 224905 112321 224906 114130 224906 112322 224906 112322 224907 114130 224907 112323 224907 112322 224908 112323 224908 112324 224908 119134 224909 112326 224909 112325 224909 112325 224910 112326 224910 112304 224910 112325 224911 112304 224911 112328 224911 112328 224912 112304 224912 112327 224912 112328 224913 112327 224913 112292 224913 112292 224914 112327 224914 112308 224914 112292 224915 112308 224915 112329 224915 112329 224916 112308 224916 112330 224916 112329 224917 112330 224917 112331 224917 112331 224918 112330 224918 112332 224918 112331 224919 112332 224919 112294 224919 112294 224920 112332 224920 112310 224920 112294 224921 112310 224921 112298 224921 112298 224922 112310 224922 112312 224922 112298 224923 112312 224923 119162 224923 119162 224924 112312 224924 119156 224924 112334 224925 112348 224925 113834 224925 113834 224926 112333 224926 112334 224926 112334 224927 112333 224927 112335 224927 112334 224928 112335 224928 112360 224928 112335 224929 113831 224929 112360 224929 112360 224930 113831 224930 112336 224930 112360 224931 112336 224931 112338 224931 112336 224932 112337 224932 112338 224932 112338 224933 112337 224933 113830 224933 112338 224934 113830 224934 112358 224934 112341 224935 112344 224935 112339 224935 113830 224936 112340 224936 112358 224936 112358 224937 112340 224937 113829 224937 112358 224938 113829 224938 112339 224938 112339 224939 113829 224939 113828 224939 112339 224940 113828 224940 112341 224940 112341 224941 112342 224941 112344 224941 112344 224942 112342 224942 112343 224942 112344 224943 112343 224943 112355 224943 112355 224944 112343 224944 113826 224944 112355 224945 113826 224945 112353 224945 113826 224946 112345 224946 112353 224946 112353 224947 112345 224947 113825 224947 112353 224948 113825 224948 112352 224948 113825 224949 113824 224949 112352 224949 112352 224950 113824 224950 113823 224950 112352 224951 113823 224951 112350 224951 112350 224952 113823 224952 112346 224952 112346 224953 113838 224953 112350 224953 112350 224954 113838 224954 113837 224954 112350 224955 113837 224955 112347 224955 112347 224956 113837 224956 113836 224956 112347 224957 113836 224957 112363 224957 112363 224958 113836 224958 113835 224958 112363 224959 113835 224959 112348 224959 112348 224960 113835 224960 112349 224960 112348 224961 112349 224961 113834 224961 112347 224962 112365 224962 112350 224962 112350 224963 112365 224963 112351 224963 112350 224964 112351 224964 112352 224964 112352 224965 112351 224965 112354 224965 112352 224966 112354 224966 112353 224966 112353 224967 112354 224967 112356 224967 112353 224968 112356 224968 112355 224968 112355 224969 112356 224969 112369 224969 112355 224970 112369 224970 112344 224970 112344 224971 112369 224971 112357 224971 112344 224972 112357 224972 112339 224972 112339 224973 112357 224973 112371 224973 112339 224974 112371 224974 112358 224974 112358 224975 112371 224975 112374 224975 112358 224976 112374 224976 112338 224976 112338 224977 112374 224977 112359 224977 112338 224978 112359 224978 112360 224978 112360 224979 112359 224979 112375 224979 112360 224980 112375 224980 112334 224980 112334 224981 112375 224981 112361 224981 112334 224982 112361 224982 112348 224982 112348 224983 112361 224983 112362 224983 112348 224984 112362 224984 112363 224984 112363 224985 112362 224985 112364 224985 112363 224986 112364 224986 112347 224986 112347 224987 112364 224987 112365 224987 112364 224988 112379 224988 112365 224988 112365 224989 112379 224989 112380 224989 112365 224990 112380 224990 112351 224990 112351 224991 112380 224991 112366 224991 112351 224992 112366 224992 112354 224992 112354 224993 112366 224993 112367 224993 112354 224994 112367 224994 112356 224994 112356 224995 112367 224995 112368 224995 112356 224996 112368 224996 112369 224996 112369 224997 112368 224997 112370 224997 112369 224998 112370 224998 112357 224998 112357 224999 112370 224999 112372 224999 112357 225000 112372 225000 112371 225000 112371 225001 112372 225001 112373 225001 112371 225002 112373 225002 112374 225002 112374 225003 112373 225003 112386 225003 112374 225004 112386 225004 112359 225004 112359 225005 112386 225005 112376 225005 112359 225006 112376 225006 112375 225006 112375 225007 112376 225007 112387 225007 112375 225008 112387 225008 112361 225008 112361 225009 112387 225009 112377 225009 112361 225010 112377 225010 112362 225010 112362 225011 112377 225011 112378 225011 112362 225012 112378 225012 112364 225012 112364 225013 112378 225013 112379 225013 112378 225014 116042 225014 112379 225014 112379 225015 116042 225015 116041 225015 112379 225016 116041 225016 112380 225016 112380 225017 116041 225017 116055 225017 112380 225018 116055 225018 112366 225018 112366 225019 116055 225019 112381 225019 112366 225020 112381 225020 112367 225020 112367 225021 112381 225021 112382 225021 112367 225022 112382 225022 112368 225022 112368 225023 112382 225023 112383 225023 112368 225024 112383 225024 112370 225024 112370 225025 112383 225025 116058 225025 112370 225026 116058 225026 112372 225026 112372 225027 116058 225027 112384 225027 112372 225028 112384 225028 112373 225028 112373 225029 112384 225029 112385 225029 112373 225030 112385 225030 112386 225030 112386 225031 112385 225031 116048 225031 112386 225032 116048 225032 112376 225032 112376 225033 116048 225033 116046 225033 112376 225034 116046 225034 112387 225034 112387 225035 116046 225035 116045 225035 112387 225036 116045 225036 112377 225036 112377 225037 116045 225037 116044 225037 112377 225038 116044 225038 112378 225038 112378 225039 116044 225039 116042 225039 112390 225040 112417 225040 112388 225040 112388 225041 112389 225041 112390 225041 112390 225042 112389 225042 113808 225042 112390 225043 113808 225043 112391 225043 113808 225044 113807 225044 112391 225044 112391 225045 113807 225045 112393 225045 112391 225046 112393 225046 112392 225046 112393 225047 113806 225047 112392 225047 112392 225048 113806 225048 112396 225048 112392 225049 112396 225049 112397 225049 113802 225050 112394 225050 112395 225050 112396 225051 113805 225051 112397 225051 112397 225052 113805 225052 113803 225052 112397 225053 113803 225053 112395 225053 112395 225054 113803 225054 112398 225054 112395 225055 112398 225055 113802 225055 113802 225056 113801 225056 112394 225056 112394 225057 113801 225057 112399 225057 112394 225058 112399 225058 112412 225058 112412 225059 112399 225059 113798 225059 112412 225060 113798 225060 112410 225060 113798 225061 112400 225061 112410 225061 112410 225062 112400 225062 112401 225062 112410 225063 112401 225063 112402 225063 112401 225064 113796 225064 112402 225064 112402 225065 113796 225065 113795 225065 112402 225066 113795 225066 112403 225066 112403 225067 113795 225067 112404 225067 112404 225068 112405 225068 112403 225068 112403 225069 112405 225069 112406 225069 112403 225070 112406 225070 112407 225070 112407 225071 112406 225071 113811 225071 112407 225072 113811 225072 112419 225072 112419 225073 113811 225073 112408 225073 112419 225074 112408 225074 112417 225074 112417 225075 112408 225075 113809 225075 112417 225076 113809 225076 112388 225076 112407 225077 112420 225077 112403 225077 112403 225078 112420 225078 112409 225078 112403 225079 112409 225079 112402 225079 112402 225080 112409 225080 112422 225080 112402 225081 112422 225081 112410 225081 112410 225082 112422 225082 112411 225082 112410 225083 112411 225083 112412 225083 112412 225084 112411 225084 112413 225084 112412 225085 112413 225085 112394 225085 112394 225086 112413 225086 112424 225086 112394 225087 112424 225087 112395 225087 112395 225088 112424 225088 112414 225088 112395 225089 112414 225089 112397 225089 112397 225090 112414 225090 112415 225090 112397 225091 112415 225091 112392 225091 112392 225092 112415 225092 112427 225092 112392 225093 112427 225093 112391 225093 112391 225094 112427 225094 112416 225094 112391 225095 112416 225095 112390 225095 112390 225096 112416 225096 112428 225096 112390 225097 112428 225097 112417 225097 112417 225098 112428 225098 112418 225098 112417 225099 112418 225099 112419 225099 112419 225100 112418 225100 112431 225100 112419 225101 112431 225101 112407 225101 112407 225102 112431 225102 112420 225102 112431 225103 112432 225103 112420 225103 112420 225104 112432 225104 112421 225104 112420 225105 112421 225105 112409 225105 112409 225106 112421 225106 112434 225106 112409 225107 112434 225107 112422 225107 112422 225108 112434 225108 112435 225108 112422 225109 112435 225109 112411 225109 112411 225110 112435 225110 112436 225110 112411 225111 112436 225111 112413 225111 112413 225112 112436 225112 112423 225112 112413 225113 112423 225113 112424 225113 112424 225114 112423 225114 112438 225114 112424 225115 112438 225115 112414 225115 112414 225116 112438 225116 112425 225116 112414 225117 112425 225117 112415 225117 112415 225118 112425 225118 112426 225118 112415 225119 112426 225119 112427 225119 112427 225120 112426 225120 112439 225120 112427 225121 112439 225121 112416 225121 112416 225122 112439 225122 112441 225122 112416 225123 112441 225123 112428 225123 112428 225124 112441 225124 112429 225124 112428 225125 112429 225125 112418 225125 112418 225126 112429 225126 112430 225126 112418 225127 112430 225127 112431 225127 112431 225128 112430 225128 112432 225128 112430 225129 116052 225129 112432 225129 112432 225130 116052 225130 116053 225130 112432 225131 116053 225131 112421 225131 112421 225132 116053 225132 112433 225132 112421 225133 112433 225133 112434 225133 112434 225134 112433 225134 116023 225134 112434 225135 116023 225135 112435 225135 112435 225136 116023 225136 112437 225136 112435 225137 112437 225137 112436 225137 112436 225138 112437 225138 116026 225138 112436 225139 116026 225139 112423 225139 112423 225140 116026 225140 116030 225140 112423 225141 116030 225141 112438 225141 112438 225142 116030 225142 116031 225142 112438 225143 116031 225143 112425 225143 112425 225144 116031 225144 116034 225144 112425 225145 116034 225145 112426 225145 112426 225146 116034 225146 116035 225146 112426 225147 116035 225147 112439 225147 112439 225148 116035 225148 112440 225148 112439 225149 112440 225149 112441 225149 112441 225150 112440 225150 112442 225150 112441 225151 112442 225151 112429 225151 112429 225152 112442 225152 112443 225152 112429 225153 112443 225153 112430 225153 112430 225154 112443 225154 116052 225154 112444 225155 112469 225155 112445 225155 112445 225156 113728 225156 112444 225156 112444 225157 113728 225157 113726 225157 112444 225158 113726 225158 112466 225158 113726 225159 113725 225159 112466 225159 112466 225160 113725 225160 112446 225160 112466 225161 112446 225161 112447 225161 112446 225162 112448 225162 112447 225162 112447 225163 112448 225163 112449 225163 112447 225164 112449 225164 112451 225164 112450 225165 112464 225165 112453 225165 112449 225166 113723 225166 112451 225166 112451 225167 113723 225167 112452 225167 112451 225168 112452 225168 112453 225168 112453 225169 112452 225169 112454 225169 112453 225170 112454 225170 112450 225170 112450 225171 113721 225171 112464 225171 112464 225172 113721 225172 112455 225172 112464 225173 112455 225173 112456 225173 112456 225174 112455 225174 113719 225174 112456 225175 113719 225175 112458 225175 113719 225176 112457 225176 112458 225176 112458 225177 112457 225177 113718 225177 112458 225178 113718 225178 112462 225178 113718 225179 112459 225179 112462 225179 112462 225180 112459 225180 113716 225180 112462 225181 113716 225181 112461 225181 112461 225182 113716 225182 113715 225182 113715 225183 113734 225183 112461 225183 112461 225184 113734 225184 113733 225184 112461 225185 113733 225185 112472 225185 112472 225186 113733 225186 112460 225186 112472 225187 112460 225187 112470 225187 112470 225188 112460 225188 113732 225188 112470 225189 113732 225189 112469 225189 112469 225190 113732 225190 113730 225190 112469 225191 113730 225191 112445 225191 112472 225192 112473 225192 112461 225192 112461 225193 112473 225193 112474 225193 112461 225194 112474 225194 112462 225194 112462 225195 112474 225195 112475 225195 112462 225196 112475 225196 112458 225196 112458 225197 112475 225197 112463 225197 112458 225198 112463 225198 112456 225198 112456 225199 112463 225199 112476 225199 112456 225200 112476 225200 112464 225200 112464 225201 112476 225201 112478 225201 112464 225202 112478 225202 112453 225202 112453 225203 112478 225203 112465 225203 112453 225204 112465 225204 112451 225204 112451 225205 112465 225205 112481 225205 112451 225206 112481 225206 112447 225206 112447 225207 112481 225207 112467 225207 112447 225208 112467 225208 112466 225208 112466 225209 112467 225209 112468 225209 112466 225210 112468 225210 112444 225210 112444 225211 112468 225211 112484 225211 112444 225212 112484 225212 112469 225212 112469 225213 112484 225213 112485 225213 112469 225214 112485 225214 112470 225214 112470 225215 112485 225215 112471 225215 112470 225216 112471 225216 112472 225216 112472 225217 112471 225217 112473 225217 112471 225218 112486 225218 112473 225218 112473 225219 112486 225219 112488 225219 112473 225220 112488 225220 112474 225220 112474 225221 112488 225221 112489 225221 112474 225222 112489 225222 112475 225222 112475 225223 112489 225223 112490 225223 112475 225224 112490 225224 112463 225224 112463 225225 112490 225225 112492 225225 112463 225226 112492 225226 112476 225226 112476 225227 112492 225227 112477 225227 112476 225228 112477 225228 112478 225228 112478 225229 112477 225229 112479 225229 112478 225230 112479 225230 112465 225230 112465 225231 112479 225231 112480 225231 112465 225232 112480 225232 112481 225232 112481 225233 112480 225233 112494 225233 112481 225234 112494 225234 112467 225234 112467 225235 112494 225235 112482 225235 112467 225236 112482 225236 112468 225236 112468 225237 112482 225237 112483 225237 112468 225238 112483 225238 112484 225238 112484 225239 112483 225239 112496 225239 112484 225240 112496 225240 112485 225240 112485 225241 112496 225241 112487 225241 112485 225242 112487 225242 112471 225242 112471 225243 112487 225243 112486 225243 112487 225244 115349 225244 112486 225244 112486 225245 115349 225245 115318 225245 112486 225246 115318 225246 112488 225246 112488 225247 115318 225247 115319 225247 112488 225248 115319 225248 112489 225248 112489 225249 115319 225249 115321 225249 112489 225250 115321 225250 112490 225250 112490 225251 115321 225251 115311 225251 112490 225252 115311 225252 112492 225252 112492 225253 115311 225253 112491 225253 112492 225254 112491 225254 112477 225254 112477 225255 112491 225255 115309 225255 112477 225256 115309 225256 112479 225256 112479 225257 115309 225257 115329 225257 112479 225258 115329 225258 112480 225258 112480 225259 115329 225259 112493 225259 112480 225260 112493 225260 112494 225260 112494 225261 112493 225261 115328 225261 112494 225262 115328 225262 112482 225262 112482 225263 115328 225263 112495 225263 112482 225264 112495 225264 112483 225264 112483 225265 112495 225265 115327 225265 112483 225266 115327 225266 112496 225266 112496 225267 115327 225267 115348 225267 112496 225268 115348 225268 112487 225268 112487 225269 115348 225269 115349 225269 112524 225270 112527 225270 112512 225270 112512 225271 112497 225271 112524 225271 112524 225272 112497 225272 112498 225272 112524 225273 112498 225273 112499 225273 112498 225274 113699 225274 112499 225274 112499 225275 113699 225275 112501 225275 112499 225276 112501 225276 112500 225276 112501 225277 113698 225277 112500 225277 112500 225278 113698 225278 113695 225278 112500 225279 113695 225279 112522 225279 113693 225280 112518 225280 112520 225280 113695 225281 112502 225281 112522 225281 112522 225282 112502 225282 113694 225282 112522 225283 113694 225283 112520 225283 112520 225284 113694 225284 112503 225284 112520 225285 112503 225285 113693 225285 113693 225286 113692 225286 112518 225286 112518 225287 113692 225287 112504 225287 112518 225288 112504 225288 112505 225288 112505 225289 112504 225289 112506 225289 112505 225290 112506 225290 112516 225290 112506 225291 112507 225291 112516 225291 112516 225292 112507 225292 113689 225292 112516 225293 113689 225293 112514 225293 113689 225294 113688 225294 112514 225294 112514 225295 113688 225295 113687 225295 112514 225296 113687 225296 112513 225296 112513 225297 113687 225297 112508 225297 112508 225298 113686 225298 112513 225298 112513 225299 113686 225299 113704 225299 112513 225300 113704 225300 112509 225300 112509 225301 113704 225301 112511 225301 112509 225302 112511 225302 112510 225302 112510 225303 112511 225303 113703 225303 112510 225304 113703 225304 112527 225304 112527 225305 113703 225305 113702 225305 112527 225306 113702 225306 112512 225306 112509 225307 112530 225307 112513 225307 112513 225308 112530 225308 112515 225308 112513 225309 112515 225309 112514 225309 112514 225310 112515 225310 112533 225310 112514 225311 112533 225311 112516 225311 112516 225312 112533 225312 112517 225312 112516 225313 112517 225313 112505 225313 112505 225314 112517 225314 112519 225314 112505 225315 112519 225315 112518 225315 112518 225316 112519 225316 112521 225316 112518 225317 112521 225317 112520 225317 112520 225318 112521 225318 112535 225318 112520 225319 112535 225319 112522 225319 112522 225320 112535 225320 112523 225320 112522 225321 112523 225321 112500 225321 112500 225322 112523 225322 112536 225322 112500 225323 112536 225323 112499 225323 112499 225324 112536 225324 112525 225324 112499 225325 112525 225325 112524 225325 112524 225326 112525 225326 112526 225326 112524 225327 112526 225327 112527 225327 112527 225328 112526 225328 112528 225328 112527 225329 112528 225329 112510 225329 112510 225330 112528 225330 112529 225330 112510 225331 112529 225331 112509 225331 112509 225332 112529 225332 112530 225332 112529 225333 112531 225333 112530 225333 112530 225334 112531 225334 112532 225334 112530 225335 112532 225335 112515 225335 112515 225336 112532 225336 112542 225336 112515 225337 112542 225337 112533 225337 112533 225338 112542 225338 112534 225338 112533 225339 112534 225339 112517 225339 112517 225340 112534 225340 112545 225340 112517 225341 112545 225341 112519 225341 112519 225342 112545 225342 112547 225342 112519 225343 112547 225343 112521 225343 112521 225344 112547 225344 112548 225344 112521 225345 112548 225345 112535 225345 112535 225346 112548 225346 112550 225346 112535 225347 112550 225347 112523 225347 112523 225348 112550 225348 112537 225348 112523 225349 112537 225349 112536 225349 112536 225350 112537 225350 112538 225350 112536 225351 112538 225351 112525 225351 112525 225352 112538 225352 112539 225352 112525 225353 112539 225353 112526 225353 112526 225354 112539 225354 112552 225354 112526 225355 112552 225355 112528 225355 112528 225356 112552 225356 112540 225356 112528 225357 112540 225357 112529 225357 112529 225358 112540 225358 112531 225358 112540 225359 112553 225359 112531 225359 112531 225360 112553 225360 112541 225360 112531 225361 112541 225361 112532 225361 112532 225362 112541 225362 115315 225362 112532 225363 115315 225363 112542 225363 112542 225364 115315 225364 112543 225364 112542 225365 112543 225365 112534 225365 112534 225366 112543 225366 112544 225366 112534 225367 112544 225367 112545 225367 112545 225368 112544 225368 112546 225368 112545 225369 112546 225369 112547 225369 112547 225370 112546 225370 112549 225370 112547 225371 112549 225371 112548 225371 112548 225372 112549 225372 115352 225372 112548 225373 115352 225373 112550 225373 112550 225374 115352 225374 115333 225374 112550 225375 115333 225375 112537 225375 112537 225376 115333 225376 115334 225376 112537 225377 115334 225377 112538 225377 112538 225378 115334 225378 112551 225378 112538 225379 112551 225379 112539 225379 112539 225380 112551 225380 115313 225380 112539 225381 115313 225381 112552 225381 112552 225382 115313 225382 115324 225382 112552 225383 115324 225383 112540 225383 112540 225384 115324 225384 112553 225384 112554 225385 112555 225385 116784 225385 116784 225386 112555 225386 112569 225386 116784 225387 112569 225387 112556 225387 112556 225388 112569 225388 112557 225388 112556 225389 112557 225389 112558 225389 112558 225390 112557 225390 112571 225390 112558 225391 112571 225391 116781 225391 116781 225392 112571 225392 112559 225392 116781 225393 112559 225393 112560 225393 112560 225394 112559 225394 112574 225394 112560 225395 112574 225395 116778 225395 116778 225396 112574 225396 112561 225396 116778 225397 112561 225397 112562 225397 112562 225398 112561 225398 112564 225398 112562 225399 112564 225399 112563 225399 112563 225400 112564 225400 112576 225400 112563 225401 112576 225401 112565 225401 112565 225402 112576 225402 112578 225402 112565 225403 112578 225403 116786 225403 116786 225404 112578 225404 112566 225404 116786 225405 112566 225405 112567 225405 112567 225406 112566 225406 112580 225406 112567 225407 112580 225407 112554 225407 112554 225408 112580 225408 112555 225408 112580 225409 112581 225409 112555 225409 112555 225410 112581 225410 112568 225410 112555 225411 112568 225411 112569 225411 112569 225412 112568 225412 112570 225412 112569 225413 112570 225413 112557 225413 112557 225414 112570 225414 112584 225414 112557 225415 112584 225415 112571 225415 112571 225416 112584 225416 112572 225416 112571 225417 112572 225417 112559 225417 112559 225418 112572 225418 112573 225418 112559 225419 112573 225419 112574 225419 112574 225420 112573 225420 112575 225420 112574 225421 112575 225421 112561 225421 112561 225422 112575 225422 112587 225422 112561 225423 112587 225423 112564 225423 112564 225424 112587 225424 112588 225424 112564 225425 112588 225425 112576 225425 112576 225426 112588 225426 112590 225426 112576 225427 112590 225427 112578 225427 112578 225428 112590 225428 112577 225428 112578 225429 112577 225429 112566 225429 112566 225430 112577 225430 112579 225430 112566 225431 112579 225431 112580 225431 112580 225432 112579 225432 112581 225432 112579 225433 112592 225433 112581 225433 112581 225434 112592 225434 112582 225434 112581 225435 112582 225435 112568 225435 112568 225436 112582 225436 112583 225436 112568 225437 112583 225437 112570 225437 112570 225438 112583 225438 113707 225438 112570 225439 113707 225439 112584 225439 112584 225440 113707 225440 113705 225440 112584 225441 113705 225441 112572 225441 112572 225442 113705 225442 112585 225442 112572 225443 112585 225443 112573 225443 112573 225444 112585 225444 112586 225444 112573 225445 112586 225445 112575 225445 112575 225446 112586 225446 113714 225446 112575 225447 113714 225447 112587 225447 112587 225448 113714 225448 112589 225448 112587 225449 112589 225449 112588 225449 112588 225450 112589 225450 113711 225450 112588 225451 113711 225451 112590 225451 112590 225452 113711 225452 113709 225452 112590 225453 113709 225453 112577 225453 112577 225454 113709 225454 112591 225454 112577 225455 112591 225455 112579 225455 112579 225456 112591 225456 112592 225456 116774 225457 112604 225457 116773 225457 116773 225458 112604 225458 112606 225458 116773 225459 112606 225459 112593 225459 112593 225460 112606 225460 112594 225460 112593 225461 112594 225461 116771 225461 116771 225462 112594 225462 112608 225462 116771 225463 112608 225463 116770 225463 116770 225464 112608 225464 112596 225464 116770 225465 112596 225465 112595 225465 112595 225466 112596 225466 112611 225466 112595 225467 112611 225467 116766 225467 116766 225468 112611 225468 112613 225468 116766 225469 112613 225469 112597 225469 112597 225470 112613 225470 112598 225470 112597 225471 112598 225471 116776 225471 116776 225472 112598 225472 112600 225472 116776 225473 112600 225473 112599 225473 112599 225474 112600 225474 112616 225474 112599 225475 112616 225475 112601 225475 112601 225476 112616 225476 112617 225476 112601 225477 112617 225477 112603 225477 112603 225478 112617 225478 112602 225478 112603 225479 112602 225479 116774 225479 116774 225480 112602 225480 112604 225480 112602 225481 112618 225481 112604 225481 112604 225482 112618 225482 112605 225482 112604 225483 112605 225483 112606 225483 112606 225484 112605 225484 112620 225484 112606 225485 112620 225485 112594 225485 112594 225486 112620 225486 112607 225486 112594 225487 112607 225487 112608 225487 112608 225488 112607 225488 112609 225488 112608 225489 112609 225489 112596 225489 112596 225490 112609 225490 112610 225490 112596 225491 112610 225491 112611 225491 112611 225492 112610 225492 112612 225492 112611 225493 112612 225493 112613 225493 112613 225494 112612 225494 112614 225494 112613 225495 112614 225495 112598 225495 112598 225496 112614 225496 112623 225496 112598 225497 112623 225497 112600 225497 112600 225498 112623 225498 112615 225498 112600 225499 112615 225499 112616 225499 112616 225500 112615 225500 112626 225500 112616 225501 112626 225501 112617 225501 112617 225502 112626 225502 112619 225502 112617 225503 112619 225503 112602 225503 112602 225504 112619 225504 112618 225504 112619 225505 113740 225505 112618 225505 112618 225506 113740 225506 113739 225506 112618 225507 113739 225507 112605 225507 112605 225508 113739 225508 113738 225508 112605 225509 113738 225509 112620 225509 112620 225510 113738 225510 113737 225510 112620 225511 113737 225511 112607 225511 112607 225512 113737 225512 113735 225512 112607 225513 113735 225513 112609 225513 112609 225514 113735 225514 112621 225514 112609 225515 112621 225515 112610 225515 112610 225516 112621 225516 113744 225516 112610 225517 113744 225517 112612 225517 112612 225518 113744 225518 112622 225518 112612 225519 112622 225519 112614 225519 112614 225520 112622 225520 112624 225520 112614 225521 112624 225521 112623 225521 112623 225522 112624 225522 112625 225522 112623 225523 112625 225523 112615 225523 112615 225524 112625 225524 113742 225524 112615 225525 113742 225525 112626 225525 112626 225526 113742 225526 112627 225526 112626 225527 112627 225527 112619 225527 112619 225528 112627 225528 113740 225528 112628 225529 112640 225529 116720 225529 116720 225530 112640 225530 112641 225530 116720 225531 112641 225531 116719 225531 116719 225532 112641 225532 112642 225532 116719 225533 112642 225533 116718 225533 116718 225534 112642 225534 112630 225534 116718 225535 112630 225535 112629 225535 112629 225536 112630 225536 112643 225536 112629 225537 112643 225537 112631 225537 112631 225538 112643 225538 112632 225538 112631 225539 112632 225539 116727 225539 116727 225540 112632 225540 112644 225540 116727 225541 112644 225541 116726 225541 116726 225542 112644 225542 112633 225542 116726 225543 112633 225543 116723 225543 116723 225544 112633 225544 112646 225544 116723 225545 112646 225545 112634 225545 112634 225546 112646 225546 112635 225546 112634 225547 112635 225547 112636 225547 112636 225548 112635 225548 112637 225548 112636 225549 112637 225549 112638 225549 112638 225550 112637 225550 112639 225550 112638 225551 112639 225551 112628 225551 112628 225552 112639 225552 112640 225552 112639 225553 112650 225553 112640 225553 112640 225554 112650 225554 112651 225554 112640 225555 112651 225555 112641 225555 112641 225556 112651 225556 112652 225556 112641 225557 112652 225557 112642 225557 112642 225558 112652 225558 112654 225558 112642 225559 112654 225559 112630 225559 112630 225560 112654 225560 112655 225560 112630 225561 112655 225561 112643 225561 112643 225562 112655 225562 112656 225562 112643 225563 112656 225563 112632 225563 112632 225564 112656 225564 112658 225564 112632 225565 112658 225565 112644 225565 112644 225566 112658 225566 112660 225566 112644 225567 112660 225567 112633 225567 112633 225568 112660 225568 112645 225568 112633 225569 112645 225569 112646 225569 112646 225570 112645 225570 112647 225570 112646 225571 112647 225571 112635 225571 112635 225572 112647 225572 112648 225572 112635 225573 112648 225573 112637 225573 112637 225574 112648 225574 112649 225574 112637 225575 112649 225575 112639 225575 112639 225576 112649 225576 112650 225576 112649 225577 113816 225577 112650 225577 112650 225578 113816 225578 113815 225578 112650 225579 113815 225579 112651 225579 112651 225580 113815 225580 113814 225580 112651 225581 113814 225581 112652 225581 112652 225582 113814 225582 112653 225582 112652 225583 112653 225583 112654 225583 112654 225584 112653 225584 113813 225584 112654 225585 113813 225585 112655 225585 112655 225586 113813 225586 113812 225586 112655 225587 113812 225587 112656 225587 112656 225588 113812 225588 112657 225588 112656 225589 112657 225589 112658 225589 112658 225590 112657 225590 112659 225590 112658 225591 112659 225591 112660 225591 112660 225592 112659 225592 113820 225592 112660 225593 113820 225593 112645 225593 112645 225594 113820 225594 112661 225594 112645 225595 112661 225595 112647 225595 112647 225596 112661 225596 112662 225596 112647 225597 112662 225597 112648 225597 112648 225598 112662 225598 113818 225598 112648 225599 113818 225599 112649 225599 112649 225600 113818 225600 113816 225600 116707 225601 112672 225601 116705 225601 116705 225602 112672 225602 112673 225602 116705 225603 112673 225603 116704 225603 116704 225604 112673 225604 112663 225604 116704 225605 112663 225605 116702 225605 116702 225606 112663 225606 112664 225606 116702 225607 112664 225607 116700 225607 116700 225608 112664 225608 112675 225608 116700 225609 112675 225609 116716 225609 116716 225610 112675 225610 112665 225610 116716 225611 112665 225611 116713 225611 116713 225612 112665 225612 112666 225612 116713 225613 112666 225613 112668 225613 112668 225614 112666 225614 112667 225614 112668 225615 112667 225615 116712 225615 116712 225616 112667 225616 112678 225616 116712 225617 112678 225617 116710 225617 116710 225618 112678 225618 112680 225618 116710 225619 112680 225619 112669 225619 112669 225620 112680 225620 112670 225620 112669 225621 112670 225621 112671 225621 112671 225622 112670 225622 112683 225622 112671 225623 112683 225623 116707 225623 116707 225624 112683 225624 112672 225624 112683 225625 112684 225625 112672 225625 112672 225626 112684 225626 112686 225626 112672 225627 112686 225627 112673 225627 112673 225628 112686 225628 112687 225628 112673 225629 112687 225629 112663 225629 112663 225630 112687 225630 112690 225630 112663 225631 112690 225631 112664 225631 112664 225632 112690 225632 112674 225632 112664 225633 112674 225633 112675 225633 112675 225634 112674 225634 112692 225634 112675 225635 112692 225635 112665 225635 112665 225636 112692 225636 112676 225636 112665 225637 112676 225637 112666 225637 112666 225638 112676 225638 112677 225638 112666 225639 112677 225639 112667 225639 112667 225640 112677 225640 112679 225640 112667 225641 112679 225641 112678 225641 112678 225642 112679 225642 112681 225642 112678 225643 112681 225643 112680 225643 112680 225644 112681 225644 112695 225644 112680 225645 112695 225645 112670 225645 112670 225646 112695 225646 112682 225646 112670 225647 112682 225647 112683 225647 112683 225648 112682 225648 112684 225648 112682 225649 113841 225649 112684 225649 112684 225650 113841 225650 112685 225650 112684 225651 112685 225651 112686 225651 112686 225652 112685 225652 112688 225652 112686 225653 112688 225653 112687 225653 112687 225654 112688 225654 112689 225654 112687 225655 112689 225655 112690 225655 112690 225656 112689 225656 112691 225656 112690 225657 112691 225657 112674 225657 112674 225658 112691 225658 112693 225658 112674 225659 112693 225659 112692 225659 112692 225660 112693 225660 112694 225660 112692 225661 112694 225661 112676 225661 112676 225662 112694 225662 113845 225662 112676 225663 113845 225663 112677 225663 112677 225664 113845 225664 113844 225664 112677 225665 113844 225665 112679 225665 112679 225666 113844 225666 113843 225666 112679 225667 113843 225667 112681 225667 112681 225668 113843 225668 112696 225668 112681 225669 112696 225669 112695 225669 112695 225670 112696 225670 112697 225670 112695 225671 112697 225671 112682 225671 112682 225672 112697 225672 113841 225672 113910 225673 112709 225673 112698 225673 112698 225674 112709 225674 112699 225674 112698 225675 112699 225675 113912 225675 113912 225676 112699 225676 112710 225676 113912 225677 112710 225677 112700 225677 112700 225678 112710 225678 112711 225678 112700 225679 112711 225679 113914 225679 113914 225680 112711 225680 112701 225680 113914 225681 112701 225681 113915 225681 113915 225682 112701 225682 112703 225682 113915 225683 112703 225683 112702 225683 112702 225684 112703 225684 112716 225684 112702 225685 112716 225685 113916 225685 113916 225686 112716 225686 112718 225686 113916 225687 112718 225687 112704 225687 112704 225688 112718 225688 112719 225688 112704 225689 112719 225689 112705 225689 112705 225690 112719 225690 112720 225690 112705 225691 112720 225691 113919 225691 113919 225692 112720 225692 112706 225692 113919 225693 112706 225693 112707 225693 112707 225694 112706 225694 112708 225694 112707 225695 112708 225695 113910 225695 113910 225696 112708 225696 112709 225696 112708 225697 112723 225697 112709 225697 112709 225698 112723 225698 112725 225698 112709 225699 112725 225699 112699 225699 112699 225700 112725 225700 112727 225700 112699 225701 112727 225701 112710 225701 112710 225702 112727 225702 112712 225702 112710 225703 112712 225703 112711 225703 112711 225704 112712 225704 112713 225704 112711 225705 112713 225705 112701 225705 112701 225706 112713 225706 112714 225706 112701 225707 112714 225707 112703 225707 112703 225708 112714 225708 112715 225708 112703 225709 112715 225709 112716 225709 112716 225710 112715 225710 112731 225710 112716 225711 112731 225711 112718 225711 112718 225712 112731 225712 112717 225712 112718 225713 112717 225713 112719 225713 112719 225714 112717 225714 112734 225714 112719 225715 112734 225715 112720 225715 112720 225716 112734 225716 112721 225716 112720 225717 112721 225717 112706 225717 112706 225718 112721 225718 112722 225718 112706 225719 112722 225719 112708 225719 112708 225720 112722 225720 112723 225720 112722 225721 116556 225721 112723 225721 112723 225722 116556 225722 112724 225722 112723 225723 112724 225723 112725 225723 112725 225724 112724 225724 112726 225724 112725 225725 112726 225725 112727 225725 112727 225726 112726 225726 116550 225726 112727 225727 116550 225727 112712 225727 112712 225728 116550 225728 112728 225728 112712 225729 112728 225729 112713 225729 112713 225730 112728 225730 112729 225730 112713 225731 112729 225731 112714 225731 112714 225732 112729 225732 116551 225732 112714 225733 116551 225733 112715 225733 112715 225734 116551 225734 112730 225734 112715 225735 112730 225735 112731 225735 112731 225736 112730 225736 112732 225736 112731 225737 112732 225737 112717 225737 112717 225738 112732 225738 112733 225738 112717 225739 112733 225739 112734 225739 112734 225740 112733 225740 116555 225740 112734 225741 116555 225741 112721 225741 112721 225742 116555 225742 112735 225742 112721 225743 112735 225743 112722 225743 112722 225744 112735 225744 116556 225744 113899 225745 112736 225745 113900 225745 113900 225746 112736 225746 112749 225746 113900 225747 112749 225747 113902 225747 113902 225748 112749 225748 112737 225748 113902 225749 112737 225749 113903 225749 113903 225750 112737 225750 112751 225750 113903 225751 112751 225751 113905 225751 113905 225752 112751 225752 112738 225752 113905 225753 112738 225753 112739 225753 112739 225754 112738 225754 112740 225754 112739 225755 112740 225755 112741 225755 112741 225756 112740 225756 112754 225756 112741 225757 112754 225757 113907 225757 113907 225758 112754 225758 112743 225758 113907 225759 112743 225759 112742 225759 112742 225760 112743 225760 112757 225760 112742 225761 112757 225761 112744 225761 112744 225762 112757 225762 112758 225762 112744 225763 112758 225763 112745 225763 112745 225764 112758 225764 112759 225764 112745 225765 112759 225765 112746 225765 112746 225766 112759 225766 112747 225766 112746 225767 112747 225767 113899 225767 113899 225768 112747 225768 112736 225768 112747 225769 112762 225769 112736 225769 112736 225770 112762 225770 112748 225770 112736 225771 112748 225771 112749 225771 112749 225772 112748 225772 112750 225772 112749 225773 112750 225773 112737 225773 112737 225774 112750 225774 112764 225774 112737 225775 112764 225775 112751 225775 112751 225776 112764 225776 112752 225776 112751 225777 112752 225777 112738 225777 112738 225778 112752 225778 112753 225778 112738 225779 112753 225779 112740 225779 112740 225780 112753 225780 112765 225780 112740 225781 112765 225781 112754 225781 112754 225782 112765 225782 112755 225782 112754 225783 112755 225783 112743 225783 112743 225784 112755 225784 112756 225784 112743 225785 112756 225785 112757 225785 112757 225786 112756 225786 112767 225786 112757 225787 112767 225787 112758 225787 112758 225788 112767 225788 112760 225788 112758 225789 112760 225789 112759 225789 112759 225790 112760 225790 112761 225790 112759 225791 112761 225791 112747 225791 112747 225792 112761 225792 112762 225792 112761 225793 112768 225793 112762 225793 112762 225794 112768 225794 112763 225794 112762 225795 112763 225795 112748 225795 112748 225796 112763 225796 116571 225796 112748 225797 116571 225797 112750 225797 112750 225798 116571 225798 116558 225798 112750 225799 116558 225799 112764 225799 112764 225800 116558 225800 116560 225800 112764 225801 116560 225801 112752 225801 112752 225802 116560 225802 116562 225802 112752 225803 116562 225803 112753 225803 112753 225804 116562 225804 116563 225804 112753 225805 116563 225805 112765 225805 112765 225806 116563 225806 116566 225806 112765 225807 116566 225807 112755 225807 112755 225808 116566 225808 116567 225808 112755 225809 116567 225809 112756 225809 112756 225810 116567 225810 112766 225810 112756 225811 112766 225811 112767 225811 112767 225812 112766 225812 116568 225812 112767 225813 116568 225813 112760 225813 112760 225814 116568 225814 116569 225814 112760 225815 116569 225815 112761 225815 112761 225816 116569 225816 112768 225816 112785 225817 112786 225817 112769 225817 112769 225818 112786 225818 112770 225818 112769 225819 112770 225819 112771 225819 112771 225820 112770 225820 112772 225820 112771 225821 112772 225821 112773 225821 112773 225822 112772 225822 112790 225822 112773 225823 112790 225823 113921 225823 113921 225824 112790 225824 112774 225824 113921 225825 112774 225825 113920 225825 113920 225826 112774 225826 112776 225826 113920 225827 112776 225827 112775 225827 112775 225828 112776 225828 112777 225828 112775 225829 112777 225829 112778 225829 112778 225830 112777 225830 112779 225830 112778 225831 112779 225831 112780 225831 112780 225832 112779 225832 112782 225832 112780 225833 112782 225833 112781 225833 112781 225834 112782 225834 112783 225834 112781 225835 112783 225835 113926 225835 113926 225836 112783 225836 112792 225836 113926 225837 112792 225837 113925 225837 113925 225838 112792 225838 112784 225838 113925 225839 112784 225839 112785 225839 112785 225840 112784 225840 112786 225840 112784 225841 112793 225841 112786 225841 112786 225842 112793 225842 112787 225842 112786 225843 112787 225843 112770 225843 112770 225844 112787 225844 112788 225844 112770 225845 112788 225845 112772 225845 112772 225846 112788 225846 112789 225846 112772 225847 112789 225847 112790 225847 112790 225848 112789 225848 112797 225848 112790 225849 112797 225849 112774 225849 112774 225850 112797 225850 112798 225850 112774 225851 112798 225851 112776 225851 112776 225852 112798 225852 112800 225852 112776 225853 112800 225853 112777 225853 112777 225854 112800 225854 112791 225854 112777 225855 112791 225855 112779 225855 112779 225856 112791 225856 112802 225856 112779 225857 112802 225857 112782 225857 112782 225858 112802 225858 112804 225858 112782 225859 112804 225859 112783 225859 112783 225860 112804 225860 112805 225860 112783 225861 112805 225861 112792 225861 112792 225862 112805 225862 112806 225862 112792 225863 112806 225863 112784 225863 112784 225864 112806 225864 112793 225864 112806 225865 116588 225865 112793 225865 112793 225866 116588 225866 116589 225866 112793 225867 116589 225867 112787 225867 112787 225868 116589 225868 112794 225868 112787 225869 112794 225869 112788 225869 112788 225870 112794 225870 112795 225870 112788 225871 112795 225871 112789 225871 112789 225872 112795 225872 112796 225872 112789 225873 112796 225873 112797 225873 112797 225874 112796 225874 112799 225874 112797 225875 112799 225875 112798 225875 112798 225876 112799 225876 116582 225876 112798 225877 116582 225877 112800 225877 112800 225878 116582 225878 116583 225878 112800 225879 116583 225879 112791 225879 112791 225880 116583 225880 112801 225880 112791 225881 112801 225881 112802 225881 112802 225882 112801 225882 112803 225882 112802 225883 112803 225883 112804 225883 112804 225884 112803 225884 116586 225884 112804 225885 116586 225885 112805 225885 112805 225886 116586 225886 116587 225886 112805 225887 116587 225887 112806 225887 112806 225888 116587 225888 116588 225888 112807 225889 112820 225889 113931 225889 113931 225890 112820 225890 112809 225890 113931 225891 112809 225891 112808 225891 112808 225892 112809 225892 112810 225892 112808 225893 112810 225893 113929 225893 113929 225894 112810 225894 112823 225894 113929 225895 112823 225895 112811 225895 112811 225896 112823 225896 112825 225896 112811 225897 112825 225897 112812 225897 112812 225898 112825 225898 112826 225898 112812 225899 112826 225899 113938 225899 113938 225900 112826 225900 112813 225900 113938 225901 112813 225901 113935 225901 113935 225902 112813 225902 112828 225902 113935 225903 112828 225903 113934 225903 113934 225904 112828 225904 112830 225904 113934 225905 112830 225905 112814 225905 112814 225906 112830 225906 112831 225906 112814 225907 112831 225907 112816 225907 112816 225908 112831 225908 112815 225908 112816 225909 112815 225909 112817 225909 112817 225910 112815 225910 112818 225910 112817 225911 112818 225911 112807 225911 112807 225912 112818 225912 112820 225912 112818 225913 112819 225913 112820 225913 112820 225914 112819 225914 112821 225914 112820 225915 112821 225915 112809 225915 112809 225916 112821 225916 112833 225916 112809 225917 112833 225917 112810 225917 112810 225918 112833 225918 112822 225918 112810 225919 112822 225919 112823 225919 112823 225920 112822 225920 112824 225920 112823 225921 112824 225921 112825 225921 112825 225922 112824 225922 112836 225922 112825 225923 112836 225923 112826 225923 112826 225924 112836 225924 112827 225924 112826 225925 112827 225925 112813 225925 112813 225926 112827 225926 112829 225926 112813 225927 112829 225927 112828 225927 112828 225928 112829 225928 112839 225928 112828 225929 112839 225929 112830 225929 112830 225930 112839 225930 112840 225930 112830 225931 112840 225931 112831 225931 112831 225932 112840 225932 112842 225932 112831 225933 112842 225933 112815 225933 112815 225934 112842 225934 112832 225934 112815 225935 112832 225935 112818 225935 112818 225936 112832 225936 112819 225936 112832 225937 112843 225937 112819 225937 112819 225938 112843 225938 116578 225938 112819 225939 116578 225939 112821 225939 112821 225940 116578 225940 116579 225940 112821 225941 116579 225941 112833 225941 112833 225942 116579 225942 112834 225942 112833 225943 112834 225943 112822 225943 112822 225944 112834 225944 112835 225944 112822 225945 112835 225945 112824 225945 112824 225946 112835 225946 116573 225946 112824 225947 116573 225947 112836 225947 112836 225948 116573 225948 112837 225948 112836 225949 112837 225949 112827 225949 112827 225950 112837 225950 116575 225950 112827 225951 116575 225951 112829 225951 112829 225952 116575 225952 112838 225952 112829 225953 112838 225953 112839 225953 112839 225954 112838 225954 112841 225954 112839 225955 112841 225955 112840 225955 112840 225956 112841 225956 116576 225956 112840 225957 116576 225957 112842 225957 112842 225958 116576 225958 116577 225958 112842 225959 116577 225959 112832 225959 112832 225960 116577 225960 112843 225960 114014 225961 112863 225961 112844 225961 112844 225962 112863 225962 112865 225962 112844 225963 112865 225963 114022 225963 114022 225964 112865 225964 112866 225964 114022 225965 112866 225965 112845 225965 112845 225966 112866 225966 112846 225966 112845 225967 112846 225967 114018 225967 114018 225968 112846 225968 112867 225968 114018 225969 112867 225969 112847 225969 112847 225970 112867 225970 112868 225970 112847 225971 112868 225971 114026 225971 114026 225972 112868 225972 112848 225972 114026 225973 112848 225973 114023 225973 114023 225974 112848 225974 112869 225974 114023 225975 112869 225975 114034 225975 114034 225976 112869 225976 112871 225976 114034 225977 112871 225977 114032 225977 114032 225978 112871 225978 112872 225978 114032 225979 112872 225979 114030 225979 114030 225980 112872 225980 112849 225980 114030 225981 112849 225981 112850 225981 112850 225982 112849 225982 112873 225982 112850 225983 112873 225983 112851 225983 112851 225984 112873 225984 112874 225984 112851 225985 112874 225985 112852 225985 112852 225986 112874 225986 112875 225986 112852 225987 112875 225987 112853 225987 112853 225988 112875 225988 112876 225988 112853 225989 112876 225989 112854 225989 112854 225990 112876 225990 112878 225990 112854 225991 112878 225991 112856 225991 112856 225992 112878 225992 112855 225992 112856 225993 112855 225993 114035 225993 114035 225994 112855 225994 112881 225994 114035 225995 112881 225995 112857 225995 112857 225996 112881 225996 112883 225996 112857 225997 112883 225997 114013 225997 114013 225998 112883 225998 112858 225998 114013 225999 112858 225999 112859 225999 112859 226000 112858 226000 112885 226000 112859 226001 112885 226001 112860 226001 112860 226002 112885 226002 112886 226002 112860 226003 112886 226003 112861 226003 112861 226004 112886 226004 112887 226004 112861 226005 112887 226005 114011 226005 114011 226006 112887 226006 112862 226006 114011 226007 112862 226007 114014 226007 114014 226008 112862 226008 112863 226008 112862 226009 112890 226009 112863 226009 112863 226010 112890 226010 112864 226010 112863 226011 112864 226011 112865 226011 112865 226012 112864 226012 112892 226012 112865 226013 112892 226013 112866 226013 112866 226014 112892 226014 112894 226014 112866 226015 112894 226015 112846 226015 112846 226016 112894 226016 112896 226016 112846 226017 112896 226017 112867 226017 112867 226018 112896 226018 112898 226018 112867 226019 112898 226019 112868 226019 112868 226020 112898 226020 112899 226020 112868 226021 112899 226021 112848 226021 112848 226022 112899 226022 112901 226022 112848 226023 112901 226023 112869 226023 112869 226024 112901 226024 112870 226024 112869 226025 112870 226025 112871 226025 112871 226026 112870 226026 112902 226026 112871 226027 112902 226027 112872 226027 112872 226028 112902 226028 112904 226028 112872 226029 112904 226029 112849 226029 112849 226030 112904 226030 112906 226030 112849 226031 112906 226031 112873 226031 112873 226032 112906 226032 112908 226032 112873 226033 112908 226033 112874 226033 112874 226034 112908 226034 112909 226034 112874 226035 112909 226035 112875 226035 112875 226036 112909 226036 112911 226036 112875 226037 112911 226037 112876 226037 112876 226038 112911 226038 112877 226038 112876 226039 112877 226039 112878 226039 112878 226040 112877 226040 112879 226040 112878 226041 112879 226041 112855 226041 112855 226042 112879 226042 112880 226042 112855 226043 112880 226043 112881 226043 112881 226044 112880 226044 112882 226044 112881 226045 112882 226045 112883 226045 112883 226046 112882 226046 112917 226046 112883 226047 112917 226047 112858 226047 112858 226048 112917 226048 112884 226048 112858 226049 112884 226049 112885 226049 112885 226050 112884 226050 112919 226050 112885 226051 112919 226051 112886 226051 112886 226052 112919 226052 112888 226052 112886 226053 112888 226053 112887 226053 112887 226054 112888 226054 112889 226054 112887 226055 112889 226055 112862 226055 112862 226056 112889 226056 112890 226056 112889 226057 116602 226057 112890 226057 112890 226058 116602 226058 112891 226058 112890 226059 112891 226059 112864 226059 112864 226060 112891 226060 116600 226060 112864 226061 116600 226061 112892 226061 112892 226062 116600 226062 112893 226062 112892 226063 112893 226063 112894 226063 112894 226064 112893 226064 112895 226064 112894 226065 112895 226065 112896 226065 112896 226066 112895 226066 112897 226066 112896 226067 112897 226067 112898 226067 112898 226068 112897 226068 116605 226068 112898 226069 116605 226069 112899 226069 112899 226070 116605 226070 112900 226070 112899 226071 112900 226071 112901 226071 112901 226072 112900 226072 116603 226072 112901 226073 116603 226073 112870 226073 112870 226074 116603 226074 116598 226074 112870 226075 116598 226075 112902 226075 112902 226076 116598 226076 112903 226076 112902 226077 112903 226077 112904 226077 112904 226078 112903 226078 112905 226078 112904 226079 112905 226079 112906 226079 112906 226080 112905 226080 112907 226080 112906 226081 112907 226081 112908 226081 112908 226082 112907 226082 116597 226082 112908 226083 116597 226083 112909 226083 112909 226084 116597 226084 112910 226084 112909 226085 112910 226085 112911 226085 112911 226086 112910 226086 112912 226086 112911 226087 112912 226087 112877 226087 112877 226088 112912 226088 112913 226088 112877 226089 112913 226089 112879 226089 112879 226090 112913 226090 112914 226090 112879 226091 112914 226091 112880 226091 112880 226092 112914 226092 112915 226092 112880 226093 112915 226093 112882 226093 112882 226094 112915 226094 112916 226094 112882 226095 112916 226095 112917 226095 112917 226096 112916 226096 112918 226096 112917 226097 112918 226097 112884 226097 112884 226098 112918 226098 116595 226098 112884 226099 116595 226099 112919 226099 112919 226100 116595 226100 116594 226100 112919 226101 116594 226101 112888 226101 112888 226102 116594 226102 116593 226102 112888 226103 116593 226103 112889 226103 112889 226104 116593 226104 116602 226104 113956 226105 112920 226105 112921 226105 112921 226106 112920 226106 112948 226106 112921 226107 112948 226107 113958 226107 113958 226108 112948 226108 112949 226108 113958 226109 112949 226109 112922 226109 112922 226110 112949 226110 112950 226110 112922 226111 112950 226111 112923 226111 112923 226112 112950 226112 112951 226112 112923 226113 112951 226113 112924 226113 112924 226114 112951 226114 112952 226114 112924 226115 112952 226115 113941 226115 113941 226116 112952 226116 112925 226116 113941 226117 112925 226117 112926 226117 112926 226118 112925 226118 112954 226118 112926 226119 112954 226119 112927 226119 112927 226120 112954 226120 112957 226120 112927 226121 112957 226121 112928 226121 112928 226122 112957 226122 112930 226122 112928 226123 112930 226123 112929 226123 112929 226124 112930 226124 112959 226124 112929 226125 112959 226125 113945 226125 113945 226126 112959 226126 112960 226126 113945 226127 112960 226127 112931 226127 112931 226128 112960 226128 112961 226128 112931 226129 112961 226129 113946 226129 113946 226130 112961 226130 112962 226130 113946 226131 112962 226131 112932 226131 112932 226132 112962 226132 112933 226132 112932 226133 112933 226133 112934 226133 112934 226134 112933 226134 112964 226134 112934 226135 112964 226135 112935 226135 112935 226136 112964 226136 112936 226136 112935 226137 112936 226137 113948 226137 113948 226138 112936 226138 112937 226138 113948 226139 112937 226139 113950 226139 113950 226140 112937 226140 112938 226140 113950 226141 112938 226141 113952 226141 113952 226142 112938 226142 112939 226142 113952 226143 112939 226143 112940 226143 112940 226144 112939 226144 112968 226144 112940 226145 112968 226145 113954 226145 113954 226146 112968 226146 112941 226146 113954 226147 112941 226147 112942 226147 112942 226148 112941 226148 112944 226148 112942 226149 112944 226149 112943 226149 112943 226150 112944 226150 112945 226150 112943 226151 112945 226151 113956 226151 113956 226152 112945 226152 112920 226152 112945 226153 112946 226153 112920 226153 112920 226154 112946 226154 112947 226154 112920 226155 112947 226155 112948 226155 112948 226156 112947 226156 112972 226156 112948 226157 112972 226157 112949 226157 112949 226158 112972 226158 112973 226158 112949 226159 112973 226159 112950 226159 112950 226160 112973 226160 112974 226160 112950 226161 112974 226161 112951 226161 112951 226162 112974 226162 112953 226162 112951 226163 112953 226163 112952 226163 112952 226164 112953 226164 112976 226164 112952 226165 112976 226165 112925 226165 112925 226166 112976 226166 112977 226166 112925 226167 112977 226167 112954 226167 112954 226168 112977 226168 112955 226168 112954 226169 112955 226169 112957 226169 112957 226170 112955 226170 112956 226170 112957 226171 112956 226171 112930 226171 112930 226172 112956 226172 112958 226172 112930 226173 112958 226173 112959 226173 112959 226174 112958 226174 112979 226174 112959 226175 112979 226175 112960 226175 112960 226176 112979 226176 112980 226176 112960 226177 112980 226177 112961 226177 112961 226178 112980 226178 112981 226178 112961 226179 112981 226179 112962 226179 112962 226180 112981 226180 112963 226180 112962 226181 112963 226181 112933 226181 112933 226182 112963 226182 112984 226182 112933 226183 112984 226183 112964 226183 112964 226184 112984 226184 112965 226184 112964 226185 112965 226185 112936 226185 112936 226186 112965 226186 112966 226186 112936 226187 112966 226187 112937 226187 112937 226188 112966 226188 112989 226188 112937 226189 112989 226189 112938 226189 112938 226190 112989 226190 112990 226190 112938 226191 112990 226191 112939 226191 112939 226192 112990 226192 112967 226192 112939 226193 112967 226193 112968 226193 112968 226194 112967 226194 112969 226194 112968 226195 112969 226195 112941 226195 112941 226196 112969 226196 112970 226196 112941 226197 112970 226197 112944 226197 112944 226198 112970 226198 112971 226198 112944 226199 112971 226199 112945 226199 112945 226200 112971 226200 112946 226200 112971 226201 116646 226201 112946 226201 112946 226202 116646 226202 116652 226202 112946 226203 116652 226203 112947 226203 112947 226204 116652 226204 116651 226204 112947 226205 116651 226205 112972 226205 112972 226206 116651 226206 116650 226206 112972 226207 116650 226207 112973 226207 112973 226208 116650 226208 116657 226208 112973 226209 116657 226209 112974 226209 112974 226210 116657 226210 116656 226210 112974 226211 116656 226211 112953 226211 112953 226212 116656 226212 116655 226212 112953 226213 116655 226213 112976 226213 112976 226214 116655 226214 112975 226214 112976 226215 112975 226215 112977 226215 112977 226216 112975 226216 116653 226216 112977 226217 116653 226217 112955 226217 112955 226218 116653 226218 116648 226218 112955 226219 116648 226219 112956 226219 112956 226220 116648 226220 116639 226220 112956 226221 116639 226221 112958 226221 112958 226222 116639 226222 112978 226222 112958 226223 112978 226223 112979 226223 112979 226224 112978 226224 116640 226224 112979 226225 116640 226225 112980 226225 112980 226226 116640 226226 116641 226226 112980 226227 116641 226227 112981 226227 112981 226228 116641 226228 112982 226228 112981 226229 112982 226229 112963 226229 112963 226230 112982 226230 112983 226230 112963 226231 112983 226231 112984 226231 112984 226232 112983 226232 112985 226232 112984 226233 112985 226233 112965 226233 112965 226234 112985 226234 112986 226234 112965 226235 112986 226235 112966 226235 112966 226236 112986 226236 112987 226236 112966 226237 112987 226237 112989 226237 112989 226238 112987 226238 112988 226238 112989 226239 112988 226239 112990 226239 112990 226240 112988 226240 112991 226240 112990 226241 112991 226241 112967 226241 112967 226242 112991 226242 112992 226242 112967 226243 112992 226243 112969 226243 112969 226244 112992 226244 116643 226244 112969 226245 116643 226245 112970 226245 112970 226246 116643 226246 112993 226246 112970 226247 112993 226247 112971 226247 112971 226248 112993 226248 116646 226248 113012 226249 112995 226249 112994 226249 112994 226250 112995 226250 112996 226250 112994 226251 112996 226251 113966 226251 113966 226252 112996 226252 112997 226252 113966 226253 112997 226253 113971 226253 113971 226254 112997 226254 113014 226254 113971 226255 113014 226255 113969 226255 113969 226256 113014 226256 112999 226256 113969 226257 112999 226257 112998 226257 112998 226258 112999 226258 113017 226258 112998 226259 113017 226259 113000 226259 113000 226260 113017 226260 113019 226260 113000 226261 113019 226261 113967 226261 113967 226262 113019 226262 113001 226262 113967 226263 113001 226263 113981 226263 113981 226264 113001 226264 113021 226264 113981 226265 113021 226265 113980 226265 113980 226266 113021 226266 113022 226266 113980 226267 113022 226267 113977 226267 113977 226268 113022 226268 113002 226268 113977 226269 113002 226269 113976 226269 113976 226270 113002 226270 113023 226270 113976 226271 113023 226271 113003 226271 113003 226272 113023 226272 113025 226272 113003 226273 113025 226273 113004 226273 113004 226274 113025 226274 113026 226274 113004 226275 113026 226275 113974 226275 113974 226276 113026 226276 113028 226276 113974 226277 113028 226277 113972 226277 113972 226278 113028 226278 113005 226278 113972 226279 113005 226279 113006 226279 113006 226280 113005 226280 113007 226280 113006 226281 113007 226281 113985 226281 113985 226282 113007 226282 113031 226282 113985 226283 113031 226283 113984 226283 113984 226284 113031 226284 113008 226284 113984 226285 113008 226285 113959 226285 113959 226286 113008 226286 113035 226286 113959 226287 113035 226287 113009 226287 113009 226288 113035 226288 113037 226288 113009 226289 113037 226289 113010 226289 113010 226290 113037 226290 113038 226290 113010 226291 113038 226291 113963 226291 113963 226292 113038 226292 113040 226292 113963 226293 113040 226293 113011 226293 113011 226294 113040 226294 113041 226294 113011 226295 113041 226295 113012 226295 113012 226296 113041 226296 112995 226296 113041 226297 113043 226297 112995 226297 112995 226298 113043 226298 113013 226298 112995 226299 113013 226299 112996 226299 112996 226300 113013 226300 113045 226300 112996 226301 113045 226301 112997 226301 112997 226302 113045 226302 113015 226302 112997 226303 113015 226303 113014 226303 113014 226304 113015 226304 113016 226304 113014 226305 113016 226305 112999 226305 112999 226306 113016 226306 113018 226306 112999 226307 113018 226307 113017 226307 113017 226308 113018 226308 113049 226308 113017 226309 113049 226309 113019 226309 113019 226310 113049 226310 113020 226310 113019 226311 113020 226311 113001 226311 113001 226312 113020 226312 113052 226312 113001 226313 113052 226313 113021 226313 113021 226314 113052 226314 113053 226314 113021 226315 113053 226315 113022 226315 113022 226316 113053 226316 113054 226316 113022 226317 113054 226317 113002 226317 113002 226318 113054 226318 113056 226318 113002 226319 113056 226319 113023 226319 113023 226320 113056 226320 113024 226320 113023 226321 113024 226321 113025 226321 113025 226322 113024 226322 113058 226322 113025 226323 113058 226323 113026 226323 113026 226324 113058 226324 113027 226324 113026 226325 113027 226325 113028 226325 113028 226326 113027 226326 113029 226326 113028 226327 113029 226327 113005 226327 113005 226328 113029 226328 113030 226328 113005 226329 113030 226329 113007 226329 113007 226330 113030 226330 113032 226330 113007 226331 113032 226331 113031 226331 113031 226332 113032 226332 113033 226332 113031 226333 113033 226333 113008 226333 113008 226334 113033 226334 113034 226334 113008 226335 113034 226335 113035 226335 113035 226336 113034 226336 113036 226336 113035 226337 113036 226337 113037 226337 113037 226338 113036 226338 113063 226338 113037 226339 113063 226339 113038 226339 113038 226340 113063 226340 113039 226340 113038 226341 113039 226341 113040 226341 113040 226342 113039 226342 113042 226342 113040 226343 113042 226343 113041 226343 113041 226344 113042 226344 113043 226344 113042 226345 113064 226345 113043 226345 113043 226346 113064 226346 116636 226346 113043 226347 116636 226347 113013 226347 113013 226348 116636 226348 113044 226348 113013 226349 113044 226349 113045 226349 113045 226350 113044 226350 113046 226350 113045 226351 113046 226351 113015 226351 113015 226352 113046 226352 113047 226352 113015 226353 113047 226353 113016 226353 113016 226354 113047 226354 113048 226354 113016 226355 113048 226355 113018 226355 113018 226356 113048 226356 113050 226356 113018 226357 113050 226357 113049 226357 113049 226358 113050 226358 116637 226358 113049 226359 116637 226359 113020 226359 113020 226360 116637 226360 113051 226360 113020 226361 113051 226361 113052 226361 113052 226362 113051 226362 116635 226362 113052 226363 116635 226363 113053 226363 113053 226364 116635 226364 116622 226364 113053 226365 116622 226365 113054 226365 113054 226366 116622 226366 113055 226366 113054 226367 113055 226367 113056 226367 113056 226368 113055 226368 116621 226368 113056 226369 116621 226369 113024 226369 113024 226370 116621 226370 113057 226370 113024 226371 113057 226371 113058 226371 113058 226372 113057 226372 116624 226372 113058 226373 116624 226373 113027 226373 113027 226374 116624 226374 113059 226374 113027 226375 113059 226375 113029 226375 113029 226376 113059 226376 116626 226376 113029 226377 116626 226377 113030 226377 113030 226378 116626 226378 113060 226378 113030 226379 113060 226379 113032 226379 113032 226380 113060 226380 116630 226380 113032 226381 116630 226381 113033 226381 113033 226382 116630 226382 116628 226382 113033 226383 116628 226383 113034 226383 113034 226384 116628 226384 113061 226384 113034 226385 113061 226385 113036 226385 113036 226386 113061 226386 113062 226386 113036 226387 113062 226387 113063 226387 113063 226388 113062 226388 116632 226388 113063 226389 116632 226389 113039 226389 113039 226390 116632 226390 116633 226390 113039 226391 116633 226391 113042 226391 113042 226392 116633 226392 113064 226392 113093 226393 113094 226393 113065 226393 113065 226394 113094 226394 113095 226394 113065 226395 113095 226395 113066 226395 113066 226396 113095 226396 113097 226396 113066 226397 113097 226397 113067 226397 113067 226398 113097 226398 113068 226398 113067 226399 113068 226399 113991 226399 113991 226400 113068 226400 113070 226400 113991 226401 113070 226401 113069 226401 113069 226402 113070 226402 113071 226402 113069 226403 113071 226403 113993 226403 113993 226404 113071 226404 113101 226404 113993 226405 113101 226405 113072 226405 113072 226406 113101 226406 113074 226406 113072 226407 113074 226407 113073 226407 113073 226408 113074 226408 113102 226408 113073 226409 113102 226409 113997 226409 113997 226410 113102 226410 113075 226410 113997 226411 113075 226411 113076 226411 113076 226412 113075 226412 113077 226412 113076 226413 113077 226413 113078 226413 113078 226414 113077 226414 113106 226414 113078 226415 113106 226415 113079 226415 113079 226416 113106 226416 113108 226416 113079 226417 113108 226417 113080 226417 113080 226418 113108 226418 113081 226418 113080 226419 113081 226419 113082 226419 113082 226420 113081 226420 113083 226420 113082 226421 113083 226421 113084 226421 113084 226422 113083 226422 113085 226422 113084 226423 113085 226423 113086 226423 113086 226424 113085 226424 113110 226424 113086 226425 113110 226425 113087 226425 113087 226426 113110 226426 113111 226426 113087 226427 113111 226427 114001 226427 114001 226428 113111 226428 113088 226428 114001 226429 113088 226429 114004 226429 114004 226430 113088 226430 113112 226430 114004 226431 113112 226431 113089 226431 113089 226432 113112 226432 113114 226432 113089 226433 113114 226433 114008 226433 114008 226434 113114 226434 113116 226434 114008 226435 113116 226435 113090 226435 113090 226436 113116 226436 113117 226436 113090 226437 113117 226437 113091 226437 113091 226438 113117 226438 113092 226438 113091 226439 113092 226439 113093 226439 113093 226440 113092 226440 113094 226440 113092 226441 113120 226441 113094 226441 113094 226442 113120 226442 113096 226442 113094 226443 113096 226443 113095 226443 113095 226444 113096 226444 113122 226444 113095 226445 113122 226445 113097 226445 113097 226446 113122 226446 113098 226446 113097 226447 113098 226447 113068 226447 113068 226448 113098 226448 113099 226448 113068 226449 113099 226449 113070 226449 113070 226450 113099 226450 113126 226450 113070 226451 113126 226451 113071 226451 113071 226452 113126 226452 113100 226452 113071 226453 113100 226453 113101 226453 113101 226454 113100 226454 113127 226454 113101 226455 113127 226455 113074 226455 113074 226456 113127 226456 113103 226456 113074 226457 113103 226457 113102 226457 113102 226458 113103 226458 113104 226458 113102 226459 113104 226459 113075 226459 113075 226460 113104 226460 113105 226460 113075 226461 113105 226461 113077 226461 113077 226462 113105 226462 113107 226462 113077 226463 113107 226463 113106 226463 113106 226464 113107 226464 113133 226464 113106 226465 113133 226465 113108 226465 113108 226466 113133 226466 113134 226466 113108 226467 113134 226467 113081 226467 113081 226468 113134 226468 113109 226468 113081 226469 113109 226469 113083 226469 113083 226470 113109 226470 113136 226470 113083 226471 113136 226471 113085 226471 113085 226472 113136 226472 113138 226472 113085 226473 113138 226473 113110 226473 113110 226474 113138 226474 113139 226474 113110 226475 113139 226475 113111 226475 113111 226476 113139 226476 113141 226476 113111 226477 113141 226477 113088 226477 113088 226478 113141 226478 113142 226478 113088 226479 113142 226479 113112 226479 113112 226480 113142 226480 113113 226480 113112 226481 113113 226481 113114 226481 113114 226482 113113 226482 113115 226482 113114 226483 113115 226483 113116 226483 113116 226484 113115 226484 113118 226484 113116 226485 113118 226485 113117 226485 113117 226486 113118 226486 113119 226486 113117 226487 113119 226487 113092 226487 113092 226488 113119 226488 113120 226488 113119 226489 113147 226489 113120 226489 113120 226490 113147 226490 113121 226490 113120 226491 113121 226491 113096 226491 113096 226492 113121 226492 116620 226492 113096 226493 116620 226493 113122 226493 113122 226494 116620 226494 113123 226494 113122 226495 113123 226495 113098 226495 113098 226496 113123 226496 113124 226496 113098 226497 113124 226497 113099 226497 113099 226498 113124 226498 116613 226498 113099 226499 116613 226499 113126 226499 113126 226500 116613 226500 113125 226500 113126 226501 113125 226501 113100 226501 113100 226502 113125 226502 113128 226502 113100 226503 113128 226503 113127 226503 113127 226504 113128 226504 113129 226504 113127 226505 113129 226505 113103 226505 113103 226506 113129 226506 113130 226506 113103 226507 113130 226507 113104 226507 113104 226508 113130 226508 116609 226508 113104 226509 116609 226509 113105 226509 113105 226510 116609 226510 113131 226510 113105 226511 113131 226511 113107 226511 113107 226512 113131 226512 113132 226512 113107 226513 113132 226513 113133 226513 113133 226514 113132 226514 116614 226514 113133 226515 116614 226515 113134 226515 113134 226516 116614 226516 116616 226516 113134 226517 116616 226517 113109 226517 113109 226518 116616 226518 113135 226518 113109 226519 113135 226519 113136 226519 113136 226520 113135 226520 113137 226520 113136 226521 113137 226521 113138 226521 113138 226522 113137 226522 116618 226522 113138 226523 116618 226523 113139 226523 113139 226524 116618 226524 113140 226524 113139 226525 113140 226525 113141 226525 113141 226526 113140 226526 116617 226526 113141 226527 116617 226527 113142 226527 113142 226528 116617 226528 113143 226528 113142 226529 113143 226529 113113 226529 113113 226530 113143 226530 113144 226530 113113 226531 113144 226531 113115 226531 113115 226532 113144 226532 113145 226532 113115 226533 113145 226533 113118 226533 113118 226534 113145 226534 113146 226534 113118 226535 113146 226535 113119 226535 113119 226536 113146 226536 113147 226536 116699 226537 113148 226537 113149 226537 113149 226538 113148 226538 113174 226538 113149 226539 113174 226539 113150 226539 113150 226540 113174 226540 113175 226540 113150 226541 113175 226541 113151 226541 113151 226542 113175 226542 113152 226542 113151 226543 113152 226543 116694 226543 116694 226544 113152 226544 113176 226544 116694 226545 113176 226545 116695 226545 116695 226546 113176 226546 113153 226546 116695 226547 113153 226547 116696 226547 116696 226548 113153 226548 113154 226548 116696 226549 113154 226549 116697 226549 116697 226550 113154 226550 113155 226550 116697 226551 113155 226551 113156 226551 113156 226552 113155 226552 113158 226552 113156 226553 113158 226553 113157 226553 113157 226554 113158 226554 113180 226554 113157 226555 113180 226555 113159 226555 113159 226556 113180 226556 113181 226556 113159 226557 113181 226557 116682 226557 116682 226558 113181 226558 113184 226558 116682 226559 113184 226559 116683 226559 116683 226560 113184 226560 113186 226560 116683 226561 113186 226561 113160 226561 113160 226562 113186 226562 113162 226562 113160 226563 113162 226563 113161 226563 113161 226564 113162 226564 113189 226564 113161 226565 113189 226565 116685 226565 116685 226566 113189 226566 113163 226566 116685 226567 113163 226567 113164 226567 113164 226568 113163 226568 113191 226568 113164 226569 113191 226569 116691 226569 116691 226570 113191 226570 113165 226570 116691 226571 113165 226571 116692 226571 116692 226572 113165 226572 113192 226572 116692 226573 113192 226573 113166 226573 113166 226574 113192 226574 113167 226574 113166 226575 113167 226575 116690 226575 116690 226576 113167 226576 113193 226576 116690 226577 113193 226577 113168 226577 113168 226578 113193 226578 113169 226578 113168 226579 113169 226579 116698 226579 116698 226580 113169 226580 113171 226580 116698 226581 113171 226581 113170 226581 113170 226582 113171 226582 113172 226582 113170 226583 113172 226583 116699 226583 116699 226584 113172 226584 113148 226584 113172 226585 113173 226585 113148 226585 113148 226586 113173 226586 113196 226586 113148 226587 113196 226587 113174 226587 113174 226588 113196 226588 113197 226588 113174 226589 113197 226589 113175 226589 113175 226590 113197 226590 113199 226590 113175 226591 113199 226591 113152 226591 113152 226592 113199 226592 113177 226592 113152 226593 113177 226593 113176 226593 113176 226594 113177 226594 113201 226594 113176 226595 113201 226595 113153 226595 113153 226596 113201 226596 113202 226596 113153 226597 113202 226597 113154 226597 113154 226598 113202 226598 113178 226598 113154 226599 113178 226599 113155 226599 113155 226600 113178 226600 113205 226600 113155 226601 113205 226601 113158 226601 113158 226602 113205 226602 113179 226602 113158 226603 113179 226603 113180 226603 113180 226604 113179 226604 113182 226604 113180 226605 113182 226605 113181 226605 113181 226606 113182 226606 113183 226606 113181 226607 113183 226607 113184 226607 113184 226608 113183 226608 113185 226608 113184 226609 113185 226609 113186 226609 113186 226610 113185 226610 113187 226610 113186 226611 113187 226611 113162 226611 113162 226612 113187 226612 113188 226612 113162 226613 113188 226613 113189 226613 113189 226614 113188 226614 113190 226614 113189 226615 113190 226615 113163 226615 113163 226616 113190 226616 113209 226616 113163 226617 113209 226617 113191 226617 113191 226618 113209 226618 113212 226618 113191 226619 113212 226619 113165 226619 113165 226620 113212 226620 113213 226620 113165 226621 113213 226621 113192 226621 113192 226622 113213 226622 113214 226622 113192 226623 113214 226623 113167 226623 113167 226624 113214 226624 113215 226624 113167 226625 113215 226625 113193 226625 113193 226626 113215 226626 113217 226626 113193 226627 113217 226627 113169 226627 113169 226628 113217 226628 113218 226628 113169 226629 113218 226629 113171 226629 113171 226630 113218 226630 113194 226630 113171 226631 113194 226631 113172 226631 113172 226632 113194 226632 113173 226632 113194 226633 113195 226633 113173 226633 113173 226634 113195 226634 113849 226634 113173 226635 113849 226635 113196 226635 113196 226636 113849 226636 113851 226636 113196 226637 113851 226637 113197 226637 113197 226638 113851 226638 113198 226638 113197 226639 113198 226639 113199 226639 113199 226640 113198 226640 113852 226640 113199 226641 113852 226641 113177 226641 113177 226642 113852 226642 113200 226642 113177 226643 113200 226643 113201 226643 113201 226644 113200 226644 113203 226644 113201 226645 113203 226645 113202 226645 113202 226646 113203 226646 113854 226646 113202 226647 113854 226647 113178 226647 113178 226648 113854 226648 113204 226648 113178 226649 113204 226649 113205 226649 113205 226650 113204 226650 113858 226650 113205 226651 113858 226651 113179 226651 113179 226652 113858 226652 113206 226652 113179 226653 113206 226653 113182 226653 113182 226654 113206 226654 113207 226654 113182 226655 113207 226655 113183 226655 113183 226656 113207 226656 113861 226656 113183 226657 113861 226657 113185 226657 113185 226658 113861 226658 113862 226658 113185 226659 113862 226659 113187 226659 113187 226660 113862 226660 113208 226660 113187 226661 113208 226661 113188 226661 113188 226662 113208 226662 113865 226662 113188 226663 113865 226663 113190 226663 113190 226664 113865 226664 113210 226664 113190 226665 113210 226665 113209 226665 113209 226666 113210 226666 113211 226666 113209 226667 113211 226667 113212 226667 113212 226668 113211 226668 113866 226668 113212 226669 113866 226669 113213 226669 113213 226670 113866 226670 113867 226670 113213 226671 113867 226671 113214 226671 113214 226672 113867 226672 113868 226672 113214 226673 113868 226673 113215 226673 113215 226674 113868 226674 113216 226674 113215 226675 113216 226675 113217 226675 113217 226676 113216 226676 113848 226676 113217 226677 113848 226677 113218 226677 113218 226678 113848 226678 113219 226678 113218 226679 113219 226679 113194 226679 113194 226680 113219 226680 113195 226680 113239 226681 113220 226681 116680 226681 116680 226682 113220 226682 113221 226682 116680 226683 113221 226683 116662 226683 116662 226684 113221 226684 113222 226684 116662 226685 113222 226685 116664 226685 116664 226686 113222 226686 113243 226686 116664 226687 113243 226687 113223 226687 113223 226688 113243 226688 113245 226688 113223 226689 113245 226689 116676 226689 116676 226690 113245 226690 113224 226690 116676 226691 113224 226691 113225 226691 113225 226692 113224 226692 113246 226692 113225 226693 113246 226693 116672 226693 116672 226694 113246 226694 113247 226694 116672 226695 113247 226695 116673 226695 116673 226696 113247 226696 113249 226696 116673 226697 113249 226697 113226 226697 113226 226698 113249 226698 113250 226698 113226 226699 113250 226699 113227 226699 113227 226700 113250 226700 113252 226700 113227 226701 113252 226701 116659 226701 116659 226702 113252 226702 113255 226702 116659 226703 113255 226703 113228 226703 113228 226704 113255 226704 113229 226704 113228 226705 113229 226705 116661 226705 116661 226706 113229 226706 113231 226706 116661 226707 113231 226707 113230 226707 113230 226708 113231 226708 113256 226708 113230 226709 113256 226709 113232 226709 113232 226710 113256 226710 113257 226710 113232 226711 113257 226711 116667 226711 116667 226712 113257 226712 113259 226712 116667 226713 113259 226713 116669 226713 116669 226714 113259 226714 113233 226714 116669 226715 113233 226715 116670 226715 116670 226716 113233 226716 113234 226716 116670 226717 113234 226717 116671 226717 116671 226718 113234 226718 113261 226718 116671 226719 113261 226719 113235 226719 113235 226720 113261 226720 113236 226720 113235 226721 113236 226721 116665 226721 116665 226722 113236 226722 113264 226722 116665 226723 113264 226723 113237 226723 113237 226724 113264 226724 113265 226724 113237 226725 113265 226725 116679 226725 116679 226726 113265 226726 113238 226726 116679 226727 113238 226727 113239 226727 113239 226728 113238 226728 113220 226728 113238 226729 113267 226729 113220 226729 113220 226730 113267 226730 113240 226730 113220 226731 113240 226731 113221 226731 113221 226732 113240 226732 113241 226732 113221 226733 113241 226733 113222 226733 113222 226734 113241 226734 113242 226734 113222 226735 113242 226735 113243 226735 113243 226736 113242 226736 113244 226736 113243 226737 113244 226737 113245 226737 113245 226738 113244 226738 113272 226738 113245 226739 113272 226739 113224 226739 113224 226740 113272 226740 113273 226740 113224 226741 113273 226741 113246 226741 113246 226742 113273 226742 113274 226742 113246 226743 113274 226743 113247 226743 113247 226744 113274 226744 113248 226744 113247 226745 113248 226745 113249 226745 113249 226746 113248 226746 113275 226746 113249 226747 113275 226747 113250 226747 113250 226748 113275 226748 113251 226748 113250 226749 113251 226749 113252 226749 113252 226750 113251 226750 113253 226750 113252 226751 113253 226751 113255 226751 113255 226752 113253 226752 113254 226752 113255 226753 113254 226753 113229 226753 113229 226754 113254 226754 113278 226754 113229 226755 113278 226755 113231 226755 113231 226756 113278 226756 113280 226756 113231 226757 113280 226757 113256 226757 113256 226758 113280 226758 113281 226758 113256 226759 113281 226759 113257 226759 113257 226760 113281 226760 113258 226760 113257 226761 113258 226761 113259 226761 113259 226762 113258 226762 113283 226762 113259 226763 113283 226763 113233 226763 113233 226764 113283 226764 113260 226764 113233 226765 113260 226765 113234 226765 113234 226766 113260 226766 113284 226766 113234 226767 113284 226767 113261 226767 113261 226768 113284 226768 113262 226768 113261 226769 113262 226769 113236 226769 113236 226770 113262 226770 113263 226770 113236 226771 113263 226771 113264 226771 113264 226772 113263 226772 113286 226772 113264 226773 113286 226773 113265 226773 113265 226774 113286 226774 113266 226774 113265 226775 113266 226775 113238 226775 113238 226776 113266 226776 113267 226776 113266 226777 113268 226777 113267 226777 113267 226778 113268 226778 113269 226778 113267 226779 113269 226779 113240 226779 113240 226780 113269 226780 113270 226780 113240 226781 113270 226781 113241 226781 113241 226782 113270 226782 113873 226782 113241 226783 113873 226783 113242 226783 113242 226784 113873 226784 113271 226784 113242 226785 113271 226785 113244 226785 113244 226786 113271 226786 113877 226786 113244 226787 113877 226787 113272 226787 113272 226788 113877 226788 113878 226788 113272 226789 113878 226789 113273 226789 113273 226790 113878 226790 113880 226790 113273 226791 113880 226791 113274 226791 113274 226792 113880 226792 113881 226792 113274 226793 113881 226793 113248 226793 113248 226794 113881 226794 113883 226794 113248 226795 113883 226795 113275 226795 113275 226796 113883 226796 113276 226796 113275 226797 113276 226797 113251 226797 113251 226798 113276 226798 113277 226798 113251 226799 113277 226799 113253 226799 113253 226800 113277 226800 113886 226800 113253 226801 113886 226801 113254 226801 113254 226802 113886 226802 113279 226802 113254 226803 113279 226803 113278 226803 113278 226804 113279 226804 113888 226804 113278 226805 113888 226805 113280 226805 113280 226806 113888 226806 113889 226806 113280 226807 113889 226807 113281 226807 113281 226808 113889 226808 113891 226808 113281 226809 113891 226809 113258 226809 113258 226810 113891 226810 113282 226810 113258 226811 113282 226811 113283 226811 113283 226812 113282 226812 113893 226812 113283 226813 113893 226813 113260 226813 113260 226814 113893 226814 113895 226814 113260 226815 113895 226815 113284 226815 113284 226816 113895 226816 113896 226816 113284 226817 113896 226817 113262 226817 113262 226818 113896 226818 113285 226818 113262 226819 113285 226819 113263 226819 113263 226820 113285 226820 113870 226820 113263 226821 113870 226821 113286 226821 113286 226822 113870 226822 113287 226822 113286 226823 113287 226823 113266 226823 113266 226824 113287 226824 113268 226824 113309 226825 113311 226825 116762 226825 116762 226826 113311 226826 113312 226826 116762 226827 113312 226827 113288 226827 113288 226828 113312 226828 113313 226828 113288 226829 113313 226829 116764 226829 116764 226830 113313 226830 113289 226830 116764 226831 113289 226831 116765 226831 116765 226832 113289 226832 113315 226832 116765 226833 113315 226833 113290 226833 113290 226834 113315 226834 113316 226834 113290 226835 113316 226835 116754 226835 116754 226836 113316 226836 113317 226836 116754 226837 113317 226837 113291 226837 113291 226838 113317 226838 113292 226838 113291 226839 113292 226839 113293 226839 113293 226840 113292 226840 113320 226840 113293 226841 113320 226841 116746 226841 116746 226842 113320 226842 113294 226842 116746 226843 113294 226843 113295 226843 113295 226844 113294 226844 113322 226844 113295 226845 113322 226845 113296 226845 113296 226846 113322 226846 113323 226846 113296 226847 113323 226847 116749 226847 116749 226848 113323 226848 113297 226848 116749 226849 113297 226849 116758 226849 116758 226850 113297 226850 113326 226850 116758 226851 113326 226851 113298 226851 113298 226852 113326 226852 113328 226852 113298 226853 113328 226853 116759 226853 116759 226854 113328 226854 113300 226854 116759 226855 113300 226855 113299 226855 113299 226856 113300 226856 113301 226856 113299 226857 113301 226857 116761 226857 116761 226858 113301 226858 113330 226858 116761 226859 113330 226859 113302 226859 113302 226860 113330 226860 113333 226860 113302 226861 113333 226861 113303 226861 113303 226862 113333 226862 113304 226862 113303 226863 113304 226863 113305 226863 113305 226864 113304 226864 113334 226864 113305 226865 113334 226865 116755 226865 116755 226866 113334 226866 113306 226866 116755 226867 113306 226867 113307 226867 113307 226868 113306 226868 113337 226868 113307 226869 113337 226869 116756 226869 116756 226870 113337 226870 113308 226870 116756 226871 113308 226871 113309 226871 113309 226872 113308 226872 113311 226872 113308 226873 113310 226873 113311 226873 113311 226874 113310 226874 113339 226874 113311 226875 113339 226875 113312 226875 113312 226876 113339 226876 113340 226876 113312 226877 113340 226877 113313 226877 113313 226878 113340 226878 113342 226878 113313 226879 113342 226879 113289 226879 113289 226880 113342 226880 113314 226880 113289 226881 113314 226881 113315 226881 113315 226882 113314 226882 113344 226882 113315 226883 113344 226883 113316 226883 113316 226884 113344 226884 113318 226884 113316 226885 113318 226885 113317 226885 113317 226886 113318 226886 113319 226886 113317 226887 113319 226887 113292 226887 113292 226888 113319 226888 113347 226888 113292 226889 113347 226889 113320 226889 113320 226890 113347 226890 113348 226890 113320 226891 113348 226891 113294 226891 113294 226892 113348 226892 113321 226892 113294 226893 113321 226893 113322 226893 113322 226894 113321 226894 113324 226894 113322 226895 113324 226895 113323 226895 113323 226896 113324 226896 113325 226896 113323 226897 113325 226897 113297 226897 113297 226898 113325 226898 113352 226898 113297 226899 113352 226899 113326 226899 113326 226900 113352 226900 113327 226900 113326 226901 113327 226901 113328 226901 113328 226902 113327 226902 113354 226902 113328 226903 113354 226903 113300 226903 113300 226904 113354 226904 113329 226904 113300 226905 113329 226905 113301 226905 113301 226906 113329 226906 113331 226906 113301 226907 113331 226907 113330 226907 113330 226908 113331 226908 113332 226908 113330 226909 113332 226909 113333 226909 113333 226910 113332 226910 113358 226910 113333 226911 113358 226911 113304 226911 113304 226912 113358 226912 113359 226912 113304 226913 113359 226913 113334 226913 113334 226914 113359 226914 113335 226914 113334 226915 113335 226915 113306 226915 113306 226916 113335 226916 113336 226916 113306 226917 113336 226917 113337 226917 113337 226918 113336 226918 113338 226918 113337 226919 113338 226919 113308 226919 113308 226920 113338 226920 113310 226920 113338 226921 113748 226921 113310 226921 113310 226922 113748 226922 113749 226922 113310 226923 113749 226923 113339 226923 113339 226924 113749 226924 113751 226924 113339 226925 113751 226925 113340 226925 113340 226926 113751 226926 113341 226926 113340 226927 113341 226927 113342 226927 113342 226928 113341 226928 113343 226928 113342 226929 113343 226929 113314 226929 113314 226930 113343 226930 113753 226930 113314 226931 113753 226931 113344 226931 113344 226932 113753 226932 113345 226932 113344 226933 113345 226933 113318 226933 113318 226934 113345 226934 113757 226934 113318 226935 113757 226935 113319 226935 113319 226936 113757 226936 113346 226936 113319 226937 113346 226937 113347 226937 113347 226938 113346 226938 113759 226938 113347 226939 113759 226939 113348 226939 113348 226940 113759 226940 113349 226940 113348 226941 113349 226941 113321 226941 113321 226942 113349 226942 113350 226942 113321 226943 113350 226943 113324 226943 113324 226944 113350 226944 113351 226944 113324 226945 113351 226945 113325 226945 113325 226946 113351 226946 113761 226946 113325 226947 113761 226947 113352 226947 113352 226948 113761 226948 113762 226948 113352 226949 113762 226949 113327 226949 113327 226950 113762 226950 113764 226950 113327 226951 113764 226951 113354 226951 113354 226952 113764 226952 113353 226952 113354 226953 113353 226953 113329 226953 113329 226954 113353 226954 113355 226954 113329 226955 113355 226955 113331 226955 113331 226956 113355 226956 113356 226956 113331 226957 113356 226957 113332 226957 113332 226958 113356 226958 113357 226958 113332 226959 113357 226959 113358 226959 113358 226960 113357 226960 113360 226960 113358 226961 113360 226961 113359 226961 113359 226962 113360 226962 113767 226962 113359 226963 113767 226963 113335 226963 113335 226964 113767 226964 113361 226964 113335 226965 113361 226965 113336 226965 113336 226966 113361 226966 113747 226966 113336 226967 113747 226967 113338 226967 113338 226968 113747 226968 113748 226968 113388 226969 113362 226969 116741 226969 116741 226970 113362 226970 113391 226970 116741 226971 113391 226971 116745 226971 116745 226972 113391 226972 113363 226972 116745 226973 113363 226973 113364 226973 113364 226974 113363 226974 113365 226974 113364 226975 113365 226975 113366 226975 113366 226976 113365 226976 113367 226976 113366 226977 113367 226977 116740 226977 116740 226978 113367 226978 113368 226978 116740 226979 113368 226979 113369 226979 113369 226980 113368 226980 113394 226980 113369 226981 113394 226981 116736 226981 116736 226982 113394 226982 113370 226982 116736 226983 113370 226983 116737 226983 116737 226984 113370 226984 113397 226984 116737 226985 113397 226985 116738 226985 116738 226986 113397 226986 113398 226986 116738 226987 113398 226987 113371 226987 113371 226988 113398 226988 113400 226988 113371 226989 113400 226989 113373 226989 113373 226990 113400 226990 113372 226990 113373 226991 113372 226991 113375 226991 113375 226992 113372 226992 113374 226992 113375 226993 113374 226993 116734 226993 116734 226994 113374 226994 113401 226994 116734 226995 113401 226995 113376 226995 113376 226996 113401 226996 113378 226996 113376 226997 113378 226997 113377 226997 113377 226998 113378 226998 113403 226998 113377 226999 113403 226999 113379 226999 113379 227000 113403 227000 113381 227000 113379 227001 113381 227001 113380 227001 113380 227002 113381 227002 113405 227002 113380 227003 113405 227003 113382 227003 113382 227004 113405 227004 113383 227004 113382 227005 113383 227005 116731 227005 116731 227006 113383 227006 113384 227006 116731 227007 113384 227007 116732 227007 116732 227008 113384 227008 113386 227008 116732 227009 113386 227009 113385 227009 113385 227010 113386 227010 113408 227010 113385 227011 113408 227011 113387 227011 113387 227012 113408 227012 113409 227012 113387 227013 113409 227013 116743 227013 116743 227014 113409 227014 113389 227014 116743 227015 113389 227015 113388 227015 113388 227016 113389 227016 113362 227016 113389 227017 113390 227017 113362 227017 113362 227018 113390 227018 113411 227018 113362 227019 113411 227019 113391 227019 113391 227020 113411 227020 113392 227020 113391 227021 113392 227021 113363 227021 113363 227022 113392 227022 113412 227022 113363 227023 113412 227023 113365 227023 113365 227024 113412 227024 113393 227024 113365 227025 113393 227025 113367 227025 113367 227026 113393 227026 113414 227026 113367 227027 113414 227027 113368 227027 113368 227028 113414 227028 113415 227028 113368 227029 113415 227029 113394 227029 113394 227030 113415 227030 113395 227030 113394 227031 113395 227031 113370 227031 113370 227032 113395 227032 113396 227032 113370 227033 113396 227033 113397 227033 113397 227034 113396 227034 113418 227034 113397 227035 113418 227035 113398 227035 113398 227036 113418 227036 113399 227036 113398 227037 113399 227037 113400 227037 113400 227038 113399 227038 113420 227038 113400 227039 113420 227039 113372 227039 113372 227040 113420 227040 113421 227040 113372 227041 113421 227041 113374 227041 113374 227042 113421 227042 113422 227042 113374 227043 113422 227043 113401 227043 113401 227044 113422 227044 113423 227044 113401 227045 113423 227045 113378 227045 113378 227046 113423 227046 113402 227046 113378 227047 113402 227047 113403 227047 113403 227048 113402 227048 113404 227048 113403 227049 113404 227049 113381 227049 113381 227050 113404 227050 113428 227050 113381 227051 113428 227051 113405 227051 113405 227052 113428 227052 113406 227052 113405 227053 113406 227053 113383 227053 113383 227054 113406 227054 113407 227054 113383 227055 113407 227055 113384 227055 113384 227056 113407 227056 113431 227056 113384 227057 113431 227057 113386 227057 113386 227058 113431 227058 113432 227058 113386 227059 113432 227059 113408 227059 113408 227060 113432 227060 113434 227060 113408 227061 113434 227061 113409 227061 113409 227062 113434 227062 113410 227062 113409 227063 113410 227063 113389 227063 113389 227064 113410 227064 113390 227064 113410 227065 113771 227065 113390 227065 113390 227066 113771 227066 113772 227066 113390 227067 113772 227067 113411 227067 113411 227068 113772 227068 113773 227068 113411 227069 113773 227069 113392 227069 113392 227070 113773 227070 113774 227070 113392 227071 113774 227071 113412 227071 113412 227072 113774 227072 113776 227072 113412 227073 113776 227073 113393 227073 113393 227074 113776 227074 113413 227074 113393 227075 113413 227075 113414 227075 113414 227076 113413 227076 113777 227076 113414 227077 113777 227077 113415 227077 113415 227078 113777 227078 113416 227078 113415 227079 113416 227079 113395 227079 113395 227080 113416 227080 113779 227080 113395 227081 113779 227081 113396 227081 113396 227082 113779 227082 113781 227082 113396 227083 113781 227083 113418 227083 113418 227084 113781 227084 113417 227084 113418 227085 113417 227085 113399 227085 113399 227086 113417 227086 113419 227086 113399 227087 113419 227087 113420 227087 113420 227088 113419 227088 113785 227088 113420 227089 113785 227089 113421 227089 113421 227090 113785 227090 113786 227090 113421 227091 113786 227091 113422 227091 113422 227092 113786 227092 113424 227092 113422 227093 113424 227093 113423 227093 113423 227094 113424 227094 113425 227094 113423 227095 113425 227095 113402 227095 113402 227096 113425 227096 113789 227096 113402 227097 113789 227097 113404 227097 113404 227098 113789 227098 113426 227098 113404 227099 113426 227099 113428 227099 113428 227100 113426 227100 113427 227100 113428 227101 113427 227101 113406 227101 113406 227102 113427 227102 113429 227102 113406 227103 113429 227103 113407 227103 113407 227104 113429 227104 113430 227104 113407 227105 113430 227105 113431 227105 113431 227106 113430 227106 113768 227106 113431 227107 113768 227107 113432 227107 113432 227108 113768 227108 113433 227108 113432 227109 113433 227109 113434 227109 113434 227110 113433 227110 113769 227110 113434 227111 113769 227111 113410 227111 113410 227112 113769 227112 113771 227112 113435 227113 113489 227113 117746 227113 117746 227114 113489 227114 117780 227114 117780 227115 113489 227115 113477 227115 117780 227116 113477 227116 117777 227116 117777 227117 113477 227117 113436 227117 113436 227118 113477 227118 113437 227118 113436 227119 113437 227119 113438 227119 113438 227120 113437 227120 113479 227120 113438 227121 113479 227121 117774 227121 113439 227122 116313 227122 113440 227122 113440 227123 116313 227123 117797 227123 113440 227124 117797 227124 113441 227124 113441 227125 117797 227125 117754 227125 113441 227126 117754 227126 113479 227126 113479 227127 117754 227127 113442 227127 113479 227128 113442 227128 117774 227128 117746 227129 117704 227129 113435 227129 113435 227130 117704 227130 113443 227130 113435 227131 113443 227131 113445 227131 113445 227132 113443 227132 113444 227132 113445 227133 113444 227133 113447 227133 113447 227134 113444 227134 113446 227134 113447 227135 113446 227135 113448 227135 113448 227136 113446 227136 116297 227136 113448 227137 116297 227137 113487 227137 113487 227138 116297 227138 113449 227138 113487 227139 113449 227139 113485 227139 113485 227140 113449 227140 113450 227140 113485 227141 113450 227141 113483 227141 113483 227142 113450 227142 116295 227142 113483 227143 116295 227143 113439 227143 113439 227144 116295 227144 113451 227144 113439 227145 113451 227145 116313 227145 113452 227146 113455 227146 113499 227146 113499 227147 113455 227147 113453 227147 113499 227148 113453 227148 113473 227148 113496 227149 113459 227149 113452 227149 113452 227150 113459 227150 113454 227150 113452 227151 113454 227151 113455 227151 113456 227152 113457 227152 113496 227152 113496 227153 113457 227153 113458 227153 113496 227154 113458 227154 113459 227154 113494 227155 113869 227155 113456 227155 113456 227156 113869 227156 113460 227156 113456 227157 113460 227157 113457 227157 113461 227158 113468 227158 113462 227158 113462 227159 113468 227159 113463 227159 113462 227160 113463 227160 113494 227160 113494 227161 113463 227161 113464 227161 113494 227162 113464 227162 113869 227162 113492 227163 113465 227163 113466 227163 113466 227164 113465 227164 113467 227164 113466 227165 113467 227165 113461 227165 113461 227166 113467 227166 113850 227166 113461 227167 113850 227167 113468 227167 113469 227168 113470 227168 113492 227168 113492 227169 113470 227169 113853 227169 113492 227170 113853 227170 113465 227170 113471 227171 113856 227171 113469 227171 113469 227172 113856 227172 113855 227172 113469 227173 113855 227173 113470 227173 113475 227174 113472 227174 113471 227174 113471 227175 113472 227175 113857 227175 113471 227176 113857 227176 113856 227176 113453 227177 113864 227177 113473 227177 113473 227178 113864 227178 113863 227178 113473 227179 113863 227179 113474 227179 113474 227180 113863 227180 113860 227180 113474 227181 113860 227181 113475 227181 113475 227182 113860 227182 113859 227182 113475 227183 113859 227183 113472 227183 113489 227184 113476 227184 113477 227184 113477 227185 113476 227185 113478 227185 113477 227186 113478 227186 113437 227186 113437 227187 113478 227187 113491 227187 113437 227188 113491 227188 113479 227188 113479 227189 113491 227189 113480 227189 113479 227190 113480 227190 113441 227190 113441 227191 113480 227191 113481 227191 113441 227192 113481 227192 113440 227192 113440 227193 113481 227193 113493 227193 113440 227194 113493 227194 113439 227194 113439 227195 113493 227195 113482 227195 113439 227196 113482 227196 113483 227196 113483 227197 113482 227197 113484 227197 113483 227198 113484 227198 113485 227198 113485 227199 113484 227199 113486 227199 113485 227200 113486 227200 113487 227200 113487 227201 113486 227201 113495 227201 113487 227202 113495 227202 113448 227202 113448 227203 113495 227203 113497 227203 113448 227204 113497 227204 113447 227204 113447 227205 113497 227205 113498 227205 113447 227206 113498 227206 113445 227206 113445 227207 113498 227207 113488 227207 113445 227208 113488 227208 113435 227208 113435 227209 113488 227209 113490 227209 113435 227210 113490 227210 113489 227210 113489 227211 113490 227211 113476 227211 113476 227212 113475 227212 113478 227212 113478 227213 113475 227213 113471 227213 113478 227214 113471 227214 113491 227214 113491 227215 113471 227215 113469 227215 113491 227216 113469 227216 113480 227216 113480 227217 113469 227217 113492 227217 113480 227218 113492 227218 113481 227218 113481 227219 113492 227219 113466 227219 113481 227220 113466 227220 113493 227220 113493 227221 113466 227221 113461 227221 113493 227222 113461 227222 113482 227222 113482 227223 113461 227223 113462 227223 113482 227224 113462 227224 113484 227224 113484 227225 113462 227225 113494 227225 113484 227226 113494 227226 113486 227226 113486 227227 113494 227227 113456 227227 113486 227228 113456 227228 113495 227228 113495 227229 113456 227229 113496 227229 113495 227230 113496 227230 113497 227230 113497 227231 113496 227231 113452 227231 113497 227232 113452 227232 113498 227232 113498 227233 113452 227233 113499 227233 113498 227234 113499 227234 113488 227234 113488 227235 113499 227235 113473 227235 113488 227236 113473 227236 113490 227236 113490 227237 113473 227237 113474 227237 113490 227238 113474 227238 113476 227238 113476 227239 113474 227239 113475 227239 113500 227240 113527 227240 113501 227240 113501 227241 113527 227241 113502 227241 113502 227242 113527 227242 113528 227242 113502 227243 113528 227243 117863 227243 117863 227244 113528 227244 113503 227244 117863 227245 113503 227245 117862 227245 113505 227246 117860 227246 113503 227246 113503 227247 117860 227247 113504 227247 113503 227248 113504 227248 117862 227248 113532 227249 117800 227249 113531 227249 113531 227250 117800 227250 117829 227250 113531 227251 117829 227251 113505 227251 113505 227252 117829 227252 117858 227252 113505 227253 117858 227253 117860 227253 113501 227254 113506 227254 113500 227254 113500 227255 113506 227255 117877 227255 113500 227256 117877 227256 113543 227256 113543 227257 117877 227257 116302 227257 113543 227258 116302 227258 113507 227258 113507 227259 116302 227259 116305 227259 113507 227260 116305 227260 113539 227260 113539 227261 116305 227261 113508 227261 113539 227262 113508 227262 113537 227262 113537 227263 113508 227263 113509 227263 113537 227264 113509 227264 113535 227264 113535 227265 113509 227265 116307 227265 113535 227266 116307 227266 113534 227266 113534 227267 116307 227267 113510 227267 113534 227268 113510 227268 113533 227268 113533 227269 113510 227269 116299 227269 113533 227270 116299 227270 113532 227270 113532 227271 116299 227271 116300 227271 113532 227272 116300 227272 117800 227272 113511 227273 113890 227273 113556 227273 113556 227274 113890 227274 113512 227274 113556 227275 113512 227275 113513 227275 113554 227276 113892 227276 113511 227276 113511 227277 113892 227277 113514 227277 113511 227278 113514 227278 113890 227278 113516 227279 113897 227279 113554 227279 113554 227280 113897 227280 113894 227280 113554 227281 113894 227281 113892 227281 113515 227282 113898 227282 113516 227282 113516 227283 113898 227283 113517 227283 113516 227284 113517 227284 113897 227284 113518 227285 113871 227285 113552 227285 113552 227286 113871 227286 113519 227286 113552 227287 113519 227287 113515 227287 113515 227288 113519 227288 113520 227288 113515 227289 113520 227289 113898 227289 113521 227290 113874 227290 113549 227290 113549 227291 113874 227291 113522 227291 113549 227292 113522 227292 113518 227292 113518 227293 113522 227293 113872 227293 113518 227294 113872 227294 113871 227294 113548 227295 113876 227295 113521 227295 113521 227296 113876 227296 113875 227296 113521 227297 113875 227297 113874 227297 113524 227298 113523 227298 113548 227298 113548 227299 113523 227299 113879 227299 113548 227300 113879 227300 113876 227300 113546 227301 113525 227301 113524 227301 113524 227302 113525 227302 113882 227302 113524 227303 113882 227303 113523 227303 113512 227304 113887 227304 113513 227304 113513 227305 113887 227305 113526 227305 113513 227306 113526 227306 113557 227306 113557 227307 113526 227307 113885 227307 113557 227308 113885 227308 113546 227308 113546 227309 113885 227309 113884 227309 113546 227310 113884 227310 113525 227310 113500 227311 113544 227311 113527 227311 113527 227312 113544 227312 113545 227312 113527 227313 113545 227313 113528 227313 113528 227314 113545 227314 113547 227314 113528 227315 113547 227315 113503 227315 113503 227316 113547 227316 113529 227316 113503 227317 113529 227317 113505 227317 113505 227318 113529 227318 113550 227318 113505 227319 113550 227319 113531 227319 113531 227320 113550 227320 113530 227320 113531 227321 113530 227321 113532 227321 113532 227322 113530 227322 113551 227322 113532 227323 113551 227323 113533 227323 113533 227324 113551 227324 113553 227324 113533 227325 113553 227325 113534 227325 113534 227326 113553 227326 113536 227326 113534 227327 113536 227327 113535 227327 113535 227328 113536 227328 113538 227328 113535 227329 113538 227329 113537 227329 113537 227330 113538 227330 113555 227330 113537 227331 113555 227331 113539 227331 113539 227332 113555 227332 113540 227332 113539 227333 113540 227333 113507 227333 113507 227334 113540 227334 113541 227334 113507 227335 113541 227335 113543 227335 113543 227336 113541 227336 113542 227336 113543 227337 113542 227337 113500 227337 113500 227338 113542 227338 113544 227338 113544 227339 113546 227339 113545 227339 113545 227340 113546 227340 113524 227340 113545 227341 113524 227341 113547 227341 113547 227342 113524 227342 113548 227342 113547 227343 113548 227343 113529 227343 113529 227344 113548 227344 113521 227344 113529 227345 113521 227345 113550 227345 113550 227346 113521 227346 113549 227346 113550 227347 113549 227347 113530 227347 113530 227348 113549 227348 113518 227348 113530 227349 113518 227349 113551 227349 113551 227350 113518 227350 113552 227350 113551 227351 113552 227351 113553 227351 113553 227352 113552 227352 113515 227352 113553 227353 113515 227353 113536 227353 113536 227354 113515 227354 113516 227354 113536 227355 113516 227355 113538 227355 113538 227356 113516 227356 113554 227356 113538 227357 113554 227357 113555 227357 113555 227358 113554 227358 113511 227358 113555 227359 113511 227359 113540 227359 113540 227360 113511 227360 113556 227360 113540 227361 113556 227361 113541 227361 113541 227362 113556 227362 113513 227362 113541 227363 113513 227363 113542 227363 113542 227364 113513 227364 113557 227364 113542 227365 113557 227365 113544 227365 113544 227366 113557 227366 113546 227366 113558 227367 113565 227367 113559 227367 113559 227368 113565 227368 113596 227368 113559 227369 113596 227369 117364 227369 117364 227370 113596 227370 113560 227370 117364 227371 113560 227371 117363 227371 117363 227372 113560 227372 113561 227372 113561 227373 113560 227373 113562 227373 113561 227374 113562 227374 113563 227374 113563 227375 113562 227375 113598 227375 113563 227376 113598 227376 117344 227376 113558 227377 113564 227377 113565 227377 113565 227378 113564 227378 117321 227378 113565 227379 117321 227379 113594 227379 113594 227380 117321 227380 113566 227380 113594 227381 113566 227381 113606 227381 113606 227382 113566 227382 115953 227382 113606 227383 115953 227383 113567 227383 113567 227384 115953 227384 115960 227384 113567 227385 115960 227385 113604 227385 113604 227386 115960 227386 113568 227386 113604 227387 113568 227387 113569 227387 113569 227388 113568 227388 115945 227388 113569 227389 115945 227389 113570 227389 113570 227390 115945 227390 115946 227390 113570 227391 115946 227391 113571 227391 113571 227392 115946 227392 115948 227392 113571 227393 115948 227393 113573 227393 113573 227394 115948 227394 113572 227394 113573 227395 113572 227395 113599 227395 113599 227396 113572 227396 113574 227396 113599 227397 113574 227397 113598 227397 113598 227398 113574 227398 113575 227398 113598 227399 113575 227399 117344 227399 113616 227400 113576 227400 113618 227400 113618 227401 113576 227401 113763 227401 113618 227402 113763 227402 113620 227402 113615 227403 113765 227403 113616 227403 113616 227404 113765 227404 113577 227404 113616 227405 113577 227405 113576 227405 113581 227406 113582 227406 113615 227406 113615 227407 113582 227407 113578 227407 113615 227408 113578 227408 113765 227408 113579 227409 113580 227409 113581 227409 113581 227410 113580 227410 113766 227410 113581 227411 113766 227411 113582 227411 113586 227412 113583 227412 113613 227412 113613 227413 113583 227413 113746 227413 113613 227414 113746 227414 113579 227414 113579 227415 113746 227415 113745 227415 113579 227416 113745 227416 113580 227416 113584 227417 113587 227417 113585 227417 113585 227418 113587 227418 113752 227418 113585 227419 113752 227419 113586 227419 113586 227420 113752 227420 113750 227420 113586 227421 113750 227421 113583 227421 113611 227422 113755 227422 113584 227422 113584 227423 113755 227423 113754 227423 113584 227424 113754 227424 113587 227424 113590 227425 113756 227425 113611 227425 113611 227426 113756 227426 113588 227426 113611 227427 113588 227427 113755 227427 113608 227428 113589 227428 113590 227428 113590 227429 113589 227429 113758 227429 113590 227430 113758 227430 113756 227430 113763 227431 113591 227431 113620 227431 113620 227432 113591 227432 113592 227432 113620 227433 113592 227433 113621 227433 113621 227434 113592 227434 113760 227434 113621 227435 113760 227435 113608 227435 113608 227436 113760 227436 113593 227436 113608 227437 113593 227437 113589 227437 113594 227438 113607 227438 113565 227438 113565 227439 113607 227439 113609 227439 113565 227440 113609 227440 113596 227440 113596 227441 113609 227441 113595 227441 113596 227442 113595 227442 113560 227442 113560 227443 113595 227443 113610 227443 113560 227444 113610 227444 113562 227444 113562 227445 113610 227445 113597 227445 113562 227446 113597 227446 113598 227446 113598 227447 113597 227447 113612 227447 113598 227448 113612 227448 113599 227448 113599 227449 113612 227449 113600 227449 113599 227450 113600 227450 113573 227450 113573 227451 113600 227451 113601 227451 113573 227452 113601 227452 113571 227452 113571 227453 113601 227453 113602 227453 113571 227454 113602 227454 113570 227454 113570 227455 113602 227455 113603 227455 113570 227456 113603 227456 113569 227456 113569 227457 113603 227457 113614 227457 113569 227458 113614 227458 113604 227458 113604 227459 113614 227459 113617 227459 113604 227460 113617 227460 113567 227460 113567 227461 113617 227461 113605 227461 113567 227462 113605 227462 113606 227462 113606 227463 113605 227463 113619 227463 113606 227464 113619 227464 113594 227464 113594 227465 113619 227465 113607 227465 113607 227466 113608 227466 113609 227466 113609 227467 113608 227467 113590 227467 113609 227468 113590 227468 113595 227468 113595 227469 113590 227469 113611 227469 113595 227470 113611 227470 113610 227470 113610 227471 113611 227471 113584 227471 113610 227472 113584 227472 113597 227472 113597 227473 113584 227473 113585 227473 113597 227474 113585 227474 113612 227474 113612 227475 113585 227475 113586 227475 113612 227476 113586 227476 113600 227476 113600 227477 113586 227477 113613 227477 113600 227478 113613 227478 113601 227478 113601 227479 113613 227479 113579 227479 113601 227480 113579 227480 113602 227480 113602 227481 113579 227481 113581 227481 113602 227482 113581 227482 113603 227482 113603 227483 113581 227483 113615 227483 113603 227484 113615 227484 113614 227484 113614 227485 113615 227485 113616 227485 113614 227486 113616 227486 113617 227486 113617 227487 113616 227487 113618 227487 113617 227488 113618 227488 113605 227488 113605 227489 113618 227489 113620 227489 113605 227490 113620 227490 113619 227490 113619 227491 113620 227491 113621 227491 113619 227492 113621 227492 113607 227492 113607 227493 113621 227493 113608 227493 117450 227494 113659 227494 113623 227494 113623 227495 113659 227495 113622 227495 113623 227496 113622 227496 113624 227496 113624 227497 113622 227497 113626 227497 113624 227498 113626 227498 113625 227498 113625 227499 113626 227499 117446 227499 117446 227500 113626 227500 113661 227500 117446 227501 113661 227501 117445 227501 117445 227502 113661 227502 113663 227502 117445 227503 113663 227503 117428 227503 117450 227504 113627 227504 113659 227504 113659 227505 113627 227505 113628 227505 113659 227506 113628 227506 113658 227506 113658 227507 113628 227507 113629 227507 113658 227508 113629 227508 113630 227508 113630 227509 113629 227509 113631 227509 113630 227510 113631 227510 113674 227510 113674 227511 113631 227511 113632 227511 113674 227512 113632 227512 113633 227512 113633 227513 113632 227513 115939 227513 113633 227514 115939 227514 113672 227514 113672 227515 115939 227515 113634 227515 113672 227516 113634 227516 113669 227516 113669 227517 113634 227517 113636 227517 113669 227518 113636 227518 113635 227518 113635 227519 113636 227519 115951 227519 113635 227520 115951 227520 113665 227520 113665 227521 115951 227521 113637 227521 113665 227522 113637 227522 113638 227522 113638 227523 113637 227523 115964 227523 113638 227524 115964 227524 113663 227524 113663 227525 115964 227525 117382 227525 113663 227526 117382 227526 117428 227526 113640 227527 113788 227527 113683 227527 113683 227528 113788 227528 113639 227528 113683 227529 113639 227529 113684 227529 113682 227530 113642 227530 113640 227530 113640 227531 113642 227531 113641 227531 113640 227532 113641 227532 113788 227532 113643 227533 113791 227533 113682 227533 113682 227534 113791 227534 113790 227534 113682 227535 113790 227535 113642 227535 113681 227536 113793 227536 113643 227536 113643 227537 113793 227537 113792 227537 113643 227538 113792 227538 113791 227538 113644 227539 113770 227539 113680 227539 113680 227540 113770 227540 113645 227540 113680 227541 113645 227541 113681 227541 113681 227542 113645 227542 113646 227542 113681 227543 113646 227543 113793 227543 113647 227544 113648 227544 113679 227544 113679 227545 113648 227545 113649 227545 113679 227546 113649 227546 113644 227546 113644 227547 113649 227547 113650 227547 113644 227548 113650 227548 113770 227548 113651 227549 113653 227549 113647 227549 113647 227550 113653 227550 113775 227550 113647 227551 113775 227551 113648 227551 113655 227552 113652 227552 113651 227552 113651 227553 113652 227553 113778 227553 113651 227554 113778 227554 113653 227554 113657 227555 113654 227555 113655 227555 113655 227556 113654 227556 113780 227556 113655 227557 113780 227557 113652 227557 113639 227558 113787 227558 113684 227558 113684 227559 113787 227559 113784 227559 113684 227560 113784 227560 113656 227560 113656 227561 113784 227561 113783 227561 113656 227562 113783 227562 113657 227562 113657 227563 113783 227563 113782 227563 113657 227564 113782 227564 113654 227564 113658 227565 113676 227565 113659 227565 113659 227566 113676 227566 113660 227566 113659 227567 113660 227567 113622 227567 113622 227568 113660 227568 113677 227568 113622 227569 113677 227569 113626 227569 113626 227570 113677 227570 113678 227570 113626 227571 113678 227571 113661 227571 113661 227572 113678 227572 113662 227572 113661 227573 113662 227573 113663 227573 113663 227574 113662 227574 113664 227574 113663 227575 113664 227575 113638 227575 113638 227576 113664 227576 113666 227576 113638 227577 113666 227577 113665 227577 113665 227578 113666 227578 113667 227578 113665 227579 113667 227579 113635 227579 113635 227580 113667 227580 113668 227580 113635 227581 113668 227581 113669 227581 113669 227582 113668 227582 113670 227582 113669 227583 113670 227583 113672 227583 113672 227584 113670 227584 113671 227584 113672 227585 113671 227585 113633 227585 113633 227586 113671 227586 113673 227586 113633 227587 113673 227587 113674 227587 113674 227588 113673 227588 113685 227588 113674 227589 113685 227589 113630 227589 113630 227590 113685 227590 113675 227590 113630 227591 113675 227591 113658 227591 113658 227592 113675 227592 113676 227592 113676 227593 113657 227593 113660 227593 113660 227594 113657 227594 113655 227594 113660 227595 113655 227595 113677 227595 113677 227596 113655 227596 113651 227596 113677 227597 113651 227597 113678 227597 113678 227598 113651 227598 113647 227598 113678 227599 113647 227599 113662 227599 113662 227600 113647 227600 113679 227600 113662 227601 113679 227601 113664 227601 113664 227602 113679 227602 113644 227602 113664 227603 113644 227603 113666 227603 113666 227604 113644 227604 113680 227604 113666 227605 113680 227605 113667 227605 113667 227606 113680 227606 113681 227606 113667 227607 113681 227607 113668 227607 113668 227608 113681 227608 113643 227608 113668 227609 113643 227609 113670 227609 113670 227610 113643 227610 113682 227610 113670 227611 113682 227611 113671 227611 113671 227612 113682 227612 113640 227612 113671 227613 113640 227613 113673 227613 113673 227614 113640 227614 113683 227614 113673 227615 113683 227615 113685 227615 113685 227616 113683 227616 113684 227616 113685 227617 113684 227617 113675 227617 113675 227618 113684 227618 113656 227618 113675 227619 113656 227619 113676 227619 113676 227620 113656 227620 113657 227620 113686 227621 116780 227621 116779 227621 113686 227622 112508 227622 116780 227622 116780 227623 112508 227623 113687 227623 116780 227624 113687 227624 116782 227624 113687 227625 113688 227625 116782 227625 116782 227626 113688 227626 113689 227626 116782 227627 113689 227627 116783 227627 113689 227628 112507 227628 116783 227628 116783 227629 112507 227629 112506 227629 116783 227630 112506 227630 113690 227630 112506 227631 112504 227631 113690 227631 113690 227632 112504 227632 113692 227632 113690 227633 113692 227633 113691 227633 113692 227634 113693 227634 113691 227634 113691 227635 113693 227635 112503 227635 113691 227636 112503 227636 116785 227636 112503 227637 113694 227637 116785 227637 116785 227638 113694 227638 112502 227638 116785 227639 112502 227639 113696 227639 112502 227640 113695 227640 113696 227640 113696 227641 113695 227641 113698 227641 113696 227642 113698 227642 113697 227642 113698 227643 112501 227643 113697 227643 113697 227644 112501 227644 113699 227644 113697 227645 113699 227645 113700 227645 113699 227646 112498 227646 113700 227646 113700 227647 112498 227647 112497 227647 113700 227648 112497 227648 113701 227648 112497 227649 112512 227649 113701 227649 113701 227650 112512 227650 113702 227650 113701 227651 113702 227651 116777 227651 113702 227652 113703 227652 116777 227652 116777 227653 113703 227653 112511 227653 116777 227654 112511 227654 116779 227654 116779 227655 112511 227655 113704 227655 116779 227656 113704 227656 113686 227656 116730 227657 112585 227657 116729 227657 116729 227658 112585 227658 113705 227658 116729 227659 113705 227659 113706 227659 113706 227660 113705 227660 113707 227660 113706 227661 113707 227661 116735 227661 116735 227662 113707 227662 112583 227662 116735 227663 112583 227663 116739 227663 116739 227664 112583 227664 112582 227664 116739 227665 112582 227665 113708 227665 113708 227666 112582 227666 112592 227666 113708 227667 112592 227667 116744 227667 116744 227668 112592 227668 112591 227668 116744 227669 112591 227669 116742 227669 116742 227670 112591 227670 113709 227670 116742 227671 113709 227671 113710 227671 113710 227672 113709 227672 113711 227672 113710 227673 113711 227673 116733 227673 116733 227674 113711 227674 112589 227674 116733 227675 112589 227675 113712 227675 113712 227676 112589 227676 113714 227676 113712 227677 113714 227677 113713 227677 113713 227678 113714 227678 112586 227678 113713 227679 112586 227679 116730 227679 116730 227680 112586 227680 112585 227680 113734 227681 116768 227681 116767 227681 113734 227682 113715 227682 116768 227682 116768 227683 113715 227683 113716 227683 116768 227684 113716 227684 116769 227684 113716 227685 112459 227685 116769 227685 116769 227686 112459 227686 113718 227686 116769 227687 113718 227687 113717 227687 113718 227688 112457 227688 113717 227688 113717 227689 112457 227689 113719 227689 113717 227690 113719 227690 116772 227690 113719 227691 112455 227691 116772 227691 116772 227692 112455 227692 113721 227692 116772 227693 113721 227693 113720 227693 113721 227694 112450 227694 113720 227694 113720 227695 112450 227695 112454 227695 113720 227696 112454 227696 113722 227696 112454 227697 112452 227697 113722 227697 113722 227698 112452 227698 113723 227698 113722 227699 113723 227699 116775 227699 113723 227700 112449 227700 116775 227700 116775 227701 112449 227701 112448 227701 116775 227702 112448 227702 113724 227702 112448 227703 112446 227703 113724 227703 113724 227704 112446 227704 113725 227704 113724 227705 113725 227705 113727 227705 113725 227706 113726 227706 113727 227706 113727 227707 113726 227707 113728 227707 113727 227708 113728 227708 113729 227708 113728 227709 112445 227709 113729 227709 113729 227710 112445 227710 113730 227710 113729 227711 113730 227711 113731 227711 113730 227712 113732 227712 113731 227712 113731 227713 113732 227713 112460 227713 113731 227714 112460 227714 116767 227714 116767 227715 112460 227715 113733 227715 116767 227716 113733 227716 113734 227716 116747 227717 112621 227717 113736 227717 113736 227718 112621 227718 113735 227718 113736 227719 113735 227719 116751 227719 116751 227720 113735 227720 113737 227720 116751 227721 113737 227721 116753 227721 116753 227722 113737 227722 113738 227722 116753 227723 113738 227723 116752 227723 116752 227724 113738 227724 113739 227724 116752 227725 113739 227725 116763 227725 116763 227726 113739 227726 113740 227726 116763 227727 113740 227727 116757 227727 116757 227728 113740 227728 112627 227728 116757 227729 112627 227729 113741 227729 113741 227730 112627 227730 113742 227730 113741 227731 113742 227731 116748 227731 116748 227732 113742 227732 112625 227732 116748 227733 112625 227733 113743 227733 113743 227734 112625 227734 112624 227734 113743 227735 112624 227735 116760 227735 116760 227736 112624 227736 112622 227736 116760 227737 112622 227737 116750 227737 116750 227738 112622 227738 113744 227738 116750 227739 113744 227739 116747 227739 116747 227740 113744 227740 112621 227740 113767 227741 113745 227741 113361 227741 113361 227742 113745 227742 113746 227742 113361 227743 113746 227743 113747 227743 113747 227744 113746 227744 113748 227744 113748 227745 113746 227745 113583 227745 113748 227746 113583 227746 113749 227746 113749 227747 113583 227747 113750 227747 113749 227748 113750 227748 113751 227748 113751 227749 113750 227749 113752 227749 113751 227750 113752 227750 113341 227750 113341 227751 113752 227751 113587 227751 113341 227752 113587 227752 113343 227752 113343 227753 113587 227753 113754 227753 113343 227754 113754 227754 113753 227754 113753 227755 113754 227755 113755 227755 113753 227756 113755 227756 113345 227756 113345 227757 113755 227757 113588 227757 113345 227758 113588 227758 113757 227758 113757 227759 113588 227759 113756 227759 113757 227760 113756 227760 113346 227760 113346 227761 113756 227761 113758 227761 113346 227762 113758 227762 113759 227762 113759 227763 113758 227763 113589 227763 113759 227764 113589 227764 113349 227764 113349 227765 113589 227765 113593 227765 113349 227766 113593 227766 113350 227766 113350 227767 113593 227767 113760 227767 113350 227768 113760 227768 113351 227768 113351 227769 113760 227769 113592 227769 113351 227770 113592 227770 113761 227770 113761 227771 113592 227771 113591 227771 113761 227772 113591 227772 113762 227772 113762 227773 113591 227773 113763 227773 113762 227774 113763 227774 113764 227774 113764 227775 113763 227775 113576 227775 113764 227776 113576 227776 113353 227776 113353 227777 113576 227777 113577 227777 113353 227778 113577 227778 113355 227778 113355 227779 113577 227779 113765 227779 113355 227780 113765 227780 113356 227780 113356 227781 113765 227781 113578 227781 113356 227782 113578 227782 113357 227782 113357 227783 113578 227783 113582 227783 113357 227784 113582 227784 113360 227784 113360 227785 113582 227785 113766 227785 113360 227786 113766 227786 113767 227786 113767 227787 113766 227787 113580 227787 113767 227788 113580 227788 113745 227788 113768 227789 113646 227789 113433 227789 113433 227790 113646 227790 113645 227790 113433 227791 113645 227791 113769 227791 113769 227792 113645 227792 113771 227792 113771 227793 113645 227793 113770 227793 113771 227794 113770 227794 113772 227794 113772 227795 113770 227795 113650 227795 113772 227796 113650 227796 113773 227796 113773 227797 113650 227797 113649 227797 113773 227798 113649 227798 113774 227798 113774 227799 113649 227799 113648 227799 113774 227800 113648 227800 113776 227800 113776 227801 113648 227801 113775 227801 113776 227802 113775 227802 113413 227802 113413 227803 113775 227803 113653 227803 113413 227804 113653 227804 113777 227804 113777 227805 113653 227805 113778 227805 113777 227806 113778 227806 113416 227806 113416 227807 113778 227807 113652 227807 113416 227808 113652 227808 113779 227808 113779 227809 113652 227809 113780 227809 113779 227810 113780 227810 113781 227810 113781 227811 113780 227811 113654 227811 113781 227812 113654 227812 113417 227812 113417 227813 113654 227813 113782 227813 113417 227814 113782 227814 113419 227814 113419 227815 113782 227815 113783 227815 113419 227816 113783 227816 113785 227816 113785 227817 113783 227817 113784 227817 113785 227818 113784 227818 113786 227818 113786 227819 113784 227819 113787 227819 113786 227820 113787 227820 113424 227820 113424 227821 113787 227821 113639 227821 113424 227822 113639 227822 113425 227822 113425 227823 113639 227823 113788 227823 113425 227824 113788 227824 113789 227824 113789 227825 113788 227825 113641 227825 113789 227826 113641 227826 113426 227826 113426 227827 113641 227827 113642 227827 113426 227828 113642 227828 113427 227828 113427 227829 113642 227829 113790 227829 113427 227830 113790 227830 113429 227830 113429 227831 113790 227831 113791 227831 113429 227832 113791 227832 113430 227832 113430 227833 113791 227833 113792 227833 113430 227834 113792 227834 113768 227834 113768 227835 113792 227835 113793 227835 113768 227836 113793 227836 113646 227836 112405 227837 113794 227837 116728 227837 112405 227838 112404 227838 113794 227838 113794 227839 112404 227839 113795 227839 113794 227840 113795 227840 116717 227840 113795 227841 113796 227841 116717 227841 116717 227842 113796 227842 112401 227842 116717 227843 112401 227843 113797 227843 112401 227844 112400 227844 113797 227844 113797 227845 112400 227845 113798 227845 113797 227846 113798 227846 113799 227846 113798 227847 112399 227847 113799 227847 113799 227848 112399 227848 113801 227848 113799 227849 113801 227849 113800 227849 113801 227850 113802 227850 113800 227850 113800 227851 113802 227851 112398 227851 113800 227852 112398 227852 113804 227852 112398 227853 113803 227853 113804 227853 113804 227854 113803 227854 113805 227854 113804 227855 113805 227855 116721 227855 113805 227856 112396 227856 116721 227856 116721 227857 112396 227857 113806 227857 116721 227858 113806 227858 116722 227858 113806 227859 112393 227859 116722 227859 116722 227860 112393 227860 113807 227860 116722 227861 113807 227861 116724 227861 113807 227862 113808 227862 116724 227862 116724 227863 113808 227863 112389 227863 116724 227864 112389 227864 116725 227864 112389 227865 112388 227865 116725 227865 116725 227866 112388 227866 113809 227866 116725 227867 113809 227867 113810 227867 113809 227868 112408 227868 113810 227868 113810 227869 112408 227869 113811 227869 113810 227870 113811 227870 116728 227870 116728 227871 113811 227871 112406 227871 116728 227872 112406 227872 112405 227872 116660 227873 113812 227873 116658 227873 116658 227874 113812 227874 113813 227874 116658 227875 113813 227875 116674 227875 116674 227876 113813 227876 112653 227876 116674 227877 112653 227877 116677 227877 116677 227878 112653 227878 113814 227878 116677 227879 113814 227879 116675 227879 116675 227880 113814 227880 113815 227880 116675 227881 113815 227881 116663 227881 116663 227882 113815 227882 113816 227882 116663 227883 113816 227883 113817 227883 113817 227884 113816 227884 113818 227884 113817 227885 113818 227885 116678 227885 116678 227886 113818 227886 112662 227886 116678 227887 112662 227887 113819 227887 113819 227888 112662 227888 112661 227888 113819 227889 112661 227889 116666 227889 116666 227890 112661 227890 113820 227890 116666 227891 113820 227891 116668 227891 116668 227892 113820 227892 112659 227892 116668 227893 112659 227893 113821 227893 113821 227894 112659 227894 112657 227894 113821 227895 112657 227895 116660 227895 116660 227896 112657 227896 113812 227896 113838 227897 113822 227897 116715 227897 113838 227898 112346 227898 113822 227898 113822 227899 112346 227899 113823 227899 113822 227900 113823 227900 116701 227900 113823 227901 113824 227901 116701 227901 116701 227902 113824 227902 113825 227902 116701 227903 113825 227903 116703 227903 113825 227904 112345 227904 116703 227904 116703 227905 112345 227905 113826 227905 116703 227906 113826 227906 113827 227906 113826 227907 112343 227907 113827 227907 113827 227908 112343 227908 112342 227908 113827 227909 112342 227909 116706 227909 112342 227910 112341 227910 116706 227910 116706 227911 112341 227911 113828 227911 116706 227912 113828 227912 116708 227912 113828 227913 113829 227913 116708 227913 116708 227914 113829 227914 112340 227914 116708 227915 112340 227915 116709 227915 112340 227916 113830 227916 116709 227916 116709 227917 113830 227917 112337 227917 116709 227918 112337 227918 116711 227918 112337 227919 112336 227919 116711 227919 116711 227920 112336 227920 113831 227920 116711 227921 113831 227921 113832 227921 113831 227922 112335 227922 113832 227922 113832 227923 112335 227923 112333 227923 113832 227924 112333 227924 113833 227924 112333 227925 113834 227925 113833 227925 113833 227926 113834 227926 112349 227926 113833 227927 112349 227927 116714 227927 112349 227928 113835 227928 116714 227928 116714 227929 113835 227929 113836 227929 116714 227930 113836 227930 116715 227930 116715 227931 113836 227931 113837 227931 116715 227932 113837 227932 113838 227932 116684 227933 112693 227933 116681 227933 116681 227934 112693 227934 112691 227934 116681 227935 112691 227935 113839 227935 113839 227936 112691 227936 112689 227936 113839 227937 112689 227937 113840 227937 113840 227938 112689 227938 112688 227938 113840 227939 112688 227939 116693 227939 116693 227940 112688 227940 112685 227940 116693 227941 112685 227941 116686 227941 116686 227942 112685 227942 113841 227942 116686 227943 113841 227943 113842 227943 113842 227944 113841 227944 112697 227944 113842 227945 112697 227945 116687 227945 116687 227946 112697 227946 112696 227946 116687 227947 112696 227947 116689 227947 116689 227948 112696 227948 113843 227948 116689 227949 113843 227949 116688 227949 116688 227950 113843 227950 113844 227950 116688 227951 113844 227951 113846 227951 113846 227952 113844 227952 113845 227952 113846 227953 113845 227953 113847 227953 113847 227954 113845 227954 112694 227954 113847 227955 112694 227955 116684 227955 116684 227956 112694 227956 112693 227956 113216 227957 113464 227957 113848 227957 113848 227958 113464 227958 113463 227958 113848 227959 113463 227959 113219 227959 113219 227960 113463 227960 113195 227960 113195 227961 113463 227961 113468 227961 113195 227962 113468 227962 113849 227962 113849 227963 113468 227963 113850 227963 113849 227964 113850 227964 113851 227964 113851 227965 113850 227965 113467 227965 113851 227966 113467 227966 113198 227966 113198 227967 113467 227967 113465 227967 113198 227968 113465 227968 113852 227968 113852 227969 113465 227969 113853 227969 113852 227970 113853 227970 113200 227970 113200 227971 113853 227971 113470 227971 113200 227972 113470 227972 113203 227972 113203 227973 113470 227973 113855 227973 113203 227974 113855 227974 113854 227974 113854 227975 113855 227975 113856 227975 113854 227976 113856 227976 113204 227976 113204 227977 113856 227977 113857 227977 113204 227978 113857 227978 113858 227978 113858 227979 113857 227979 113472 227979 113858 227980 113472 227980 113206 227980 113206 227981 113472 227981 113859 227981 113206 227982 113859 227982 113207 227982 113207 227983 113859 227983 113860 227983 113207 227984 113860 227984 113861 227984 113861 227985 113860 227985 113863 227985 113861 227986 113863 227986 113862 227986 113862 227987 113863 227987 113864 227987 113862 227988 113864 227988 113208 227988 113208 227989 113864 227989 113453 227989 113208 227990 113453 227990 113865 227990 113865 227991 113453 227991 113455 227991 113865 227992 113455 227992 113210 227992 113210 227993 113455 227993 113454 227993 113210 227994 113454 227994 113211 227994 113211 227995 113454 227995 113459 227995 113211 227996 113459 227996 113866 227996 113866 227997 113459 227997 113458 227997 113866 227998 113458 227998 113867 227998 113867 227999 113458 227999 113457 227999 113867 228000 113457 228000 113868 228000 113868 228001 113457 228001 113460 228001 113868 228002 113460 228002 113216 228002 113216 228003 113460 228003 113869 228003 113216 228004 113869 228004 113464 228004 113285 228005 113520 228005 113870 228005 113870 228006 113520 228006 113519 228006 113870 228007 113519 228007 113287 228007 113287 228008 113519 228008 113268 228008 113268 228009 113519 228009 113871 228009 113268 228010 113871 228010 113269 228010 113269 228011 113871 228011 113872 228011 113269 228012 113872 228012 113270 228012 113270 228013 113872 228013 113522 228013 113270 228014 113522 228014 113873 228014 113873 228015 113522 228015 113874 228015 113873 228016 113874 228016 113271 228016 113271 228017 113874 228017 113875 228017 113271 228018 113875 228018 113877 228018 113877 228019 113875 228019 113876 228019 113877 228020 113876 228020 113878 228020 113878 228021 113876 228021 113879 228021 113878 228022 113879 228022 113880 228022 113880 228023 113879 228023 113523 228023 113880 228024 113523 228024 113881 228024 113881 228025 113523 228025 113882 228025 113881 228026 113882 228026 113883 228026 113883 228027 113882 228027 113525 228027 113883 228028 113525 228028 113276 228028 113276 228029 113525 228029 113884 228029 113276 228030 113884 228030 113277 228030 113277 228031 113884 228031 113885 228031 113277 228032 113885 228032 113886 228032 113886 228033 113885 228033 113526 228033 113886 228034 113526 228034 113279 228034 113279 228035 113526 228035 113887 228035 113279 228036 113887 228036 113888 228036 113888 228037 113887 228037 113512 228037 113888 228038 113512 228038 113889 228038 113889 228039 113512 228039 113890 228039 113889 228040 113890 228040 113891 228040 113891 228041 113890 228041 113514 228041 113891 228042 113514 228042 113282 228042 113282 228043 113514 228043 113892 228043 113282 228044 113892 228044 113893 228044 113893 228045 113892 228045 113894 228045 113893 228046 113894 228046 113895 228046 113895 228047 113894 228047 113897 228047 113895 228048 113897 228048 113896 228048 113896 228049 113897 228049 113517 228049 113896 228050 113517 228050 113285 228050 113285 228051 113517 228051 113898 228051 113285 228052 113898 228052 113520 228052 113909 228053 113899 228053 116601 228053 116601 228054 113899 228054 113900 228054 116601 228055 113900 228055 113901 228055 113901 228056 113900 228056 113902 228056 113901 228057 113902 228057 113904 228057 113904 228058 113902 228058 113903 228058 113904 228059 113903 228059 116604 228059 116604 228060 113903 228060 113905 228060 116604 228061 113905 228061 116599 228061 116599 228062 113905 228062 112739 228062 116599 228063 112739 228063 113906 228063 113906 228064 112739 228064 112741 228064 113906 228065 112741 228065 116596 228065 116596 228066 112741 228066 113907 228066 116596 228067 113907 228067 116590 228067 116590 228068 113907 228068 112742 228068 116590 228069 112742 228069 116591 228069 116591 228070 112742 228070 112744 228070 116591 228071 112744 228071 116592 228071 116592 228072 112744 228072 112745 228072 116592 228073 112745 228073 113908 228073 113908 228074 112745 228074 112746 228074 113908 228075 112746 228075 113909 228075 113909 228076 112746 228076 113899 228076 116607 228077 113910 228077 116619 228077 116619 228078 113910 228078 112698 228078 116619 228079 112698 228079 113911 228079 113911 228080 112698 228080 113912 228080 113911 228081 113912 228081 116612 228081 116612 228082 113912 228082 112700 228082 116612 228083 112700 228083 113913 228083 113913 228084 112700 228084 113914 228084 113913 228085 113914 228085 116610 228085 116610 228086 113914 228086 113915 228086 116610 228087 113915 228087 116608 228087 116608 228088 113915 228088 112702 228088 116608 228089 112702 228089 116606 228089 116606 228090 112702 228090 113916 228090 116606 228091 113916 228091 113917 228091 113917 228092 113916 228092 112704 228092 113917 228093 112704 228093 116615 228093 116615 228094 112704 228094 112705 228094 116615 228095 112705 228095 113918 228095 113918 228096 112705 228096 113919 228096 113918 228097 113919 228097 116611 228097 116611 228098 113919 228098 112707 228098 116611 228099 112707 228099 116607 228099 116607 228100 112707 228100 113910 228100 112775 228101 113928 228101 113920 228101 113920 228102 113928 228102 116634 228102 113920 228103 116634 228103 113921 228103 113921 228104 116634 228104 113922 228104 113921 228105 113922 228105 112773 228105 112773 228106 113922 228106 116638 228106 112773 228107 116638 228107 112771 228107 112771 228108 116638 228108 113923 228108 112771 228109 113923 228109 112769 228109 112769 228110 113923 228110 113924 228110 112769 228111 113924 228111 112785 228111 112785 228112 113924 228112 116631 228112 112785 228113 116631 228113 113925 228113 113925 228114 116631 228114 116627 228114 113925 228115 116627 228115 113926 228115 113926 228116 116627 228116 116629 228116 113926 228117 116629 228117 112781 228117 112781 228118 116629 228118 113927 228118 112781 228119 113927 228119 112780 228119 112780 228120 113927 228120 116623 228120 112780 228121 116623 228121 112778 228121 112778 228122 116623 228122 116625 228122 112778 228123 116625 228123 112775 228123 112775 228124 116625 228124 113928 228124 113938 228125 113939 228125 112812 228125 112812 228126 113939 228126 116649 228126 112812 228127 116649 228127 112811 228127 112811 228128 116649 228128 116654 228128 112811 228129 116654 228129 113929 228129 113929 228130 116654 228130 113930 228130 113929 228131 113930 228131 112808 228131 112808 228132 113930 228132 116647 228132 112808 228133 116647 228133 113931 228133 113931 228134 116647 228134 116645 228134 113931 228135 116645 228135 112807 228135 112807 228136 116645 228136 113932 228136 112807 228137 113932 228137 112817 228137 112817 228138 113932 228138 116644 228138 112817 228139 116644 228139 112816 228139 112816 228140 116644 228140 116642 228140 112816 228141 116642 228141 112814 228141 112814 228142 116642 228142 113933 228142 112814 228143 113933 228143 113934 228143 113934 228144 113933 228144 113936 228144 113934 228145 113936 228145 113935 228145 113935 228146 113936 228146 113937 228146 113935 228147 113937 228147 113938 228147 113938 228148 113937 228148 113939 228148 116253 228149 113958 228149 113940 228149 113940 228150 113958 228150 112922 228150 113940 228151 112922 228151 116255 228151 116255 228152 112922 228152 112923 228152 116255 228153 112923 228153 116259 228153 116259 228154 112923 228154 112924 228154 116259 228155 112924 228155 116258 228155 116258 228156 112924 228156 113941 228156 116258 228157 113941 228157 116249 228157 116249 228158 113941 228158 112926 228158 116249 228159 112926 228159 116260 228159 116260 228160 112926 228160 112927 228160 116260 228161 112927 228161 113942 228161 113942 228162 112927 228162 112928 228162 113942 228163 112928 228163 113943 228163 113943 228164 112928 228164 112929 228164 113943 228165 112929 228165 113944 228165 113944 228166 112929 228166 113945 228166 113944 228167 113945 228167 116261 228167 116261 228168 113945 228168 112931 228168 116261 228169 112931 228169 113947 228169 112935 228170 116250 228170 116262 228170 112931 228171 113946 228171 113947 228171 113947 228172 113946 228172 112932 228172 113947 228173 112932 228173 116262 228173 116262 228174 112932 228174 112934 228174 116262 228175 112934 228175 112935 228175 113950 228176 113949 228176 116264 228176 116250 228177 112935 228177 116264 228177 116264 228178 112935 228178 113948 228178 116264 228179 113948 228179 113950 228179 113949 228180 113950 228180 113951 228180 113951 228181 113950 228181 113952 228181 113951 228182 113952 228182 113953 228182 113953 228183 113952 228183 112940 228183 113953 228184 112940 228184 116265 228184 116265 228185 112940 228185 113954 228185 116265 228186 113954 228186 116266 228186 116266 228187 113954 228187 112942 228187 116266 228188 112942 228188 113955 228188 113955 228189 112942 228189 112943 228189 113955 228190 112943 228190 113957 228190 113957 228191 112943 228191 113956 228191 113957 228192 113956 228192 116253 228192 116253 228193 113956 228193 112921 228193 116253 228194 112921 228194 113958 228194 113984 228195 113959 228195 113982 228195 113010 228196 113960 228196 113009 228196 113009 228197 113960 228197 113961 228197 113009 228198 113961 228198 113959 228198 113959 228199 113961 228199 113962 228199 113959 228200 113962 228200 113982 228200 113012 228201 114598 228201 113011 228201 113011 228202 114598 228202 114597 228202 113011 228203 114597 228203 113963 228203 113963 228204 114597 228204 113964 228204 113963 228205 113964 228205 113010 228205 113010 228206 113964 228206 113965 228206 113010 228207 113965 228207 113960 228207 113971 228208 114601 228208 113966 228208 113966 228209 114601 228209 114600 228209 113966 228210 114600 228210 112994 228210 112994 228211 114600 228211 114599 228211 112994 228212 114599 228212 113012 228212 113012 228213 114599 228213 114746 228213 113012 228214 114746 228214 114598 228214 113981 228215 116240 228215 113967 228215 113967 228216 116240 228216 116232 228216 113967 228217 116232 228217 113000 228217 113000 228218 116232 228218 113968 228218 113000 228219 113968 228219 112998 228219 112998 228220 113968 228220 114760 228220 112998 228221 114760 228221 113969 228221 113969 228222 114760 228222 113970 228222 113969 228223 113970 228223 113971 228223 113971 228224 113970 228224 114602 228224 113971 228225 114602 228225 114601 228225 113006 228226 113973 228226 113972 228226 113972 228227 113973 228227 116246 228227 113972 228228 116246 228228 113974 228228 113974 228229 116246 228229 116244 228229 113974 228230 116244 228230 113004 228230 113004 228231 116244 228231 113975 228231 113004 228232 113975 228232 113003 228232 113003 228233 113975 228233 116242 228233 113003 228234 116242 228234 113976 228234 113976 228235 116242 228235 113978 228235 113976 228236 113978 228236 113977 228236 113977 228237 113978 228237 113979 228237 113977 228238 113979 228238 113980 228238 113980 228239 113979 228239 116241 228239 113980 228240 116241 228240 113981 228240 113981 228241 116241 228241 116239 228241 113981 228242 116239 228242 116240 228242 113982 228243 113983 228243 113984 228243 113984 228244 113983 228244 113986 228244 113984 228245 113986 228245 113985 228245 113985 228246 113986 228246 113987 228246 113985 228247 113987 228247 113006 228247 113006 228248 113987 228248 113988 228248 113006 228249 113988 228249 113973 228249 116198 228250 113066 228250 113989 228250 113989 228251 113066 228251 113067 228251 113989 228252 113067 228252 113990 228252 113990 228253 113067 228253 113991 228253 113990 228254 113991 228254 113992 228254 113992 228255 113991 228255 113069 228255 113992 228256 113069 228256 116205 228256 116205 228257 113069 228257 113993 228257 116205 228258 113993 228258 116204 228258 116204 228259 113993 228259 113072 228259 116204 228260 113072 228260 113994 228260 113994 228261 113072 228261 113073 228261 113994 228262 113073 228262 113995 228262 113995 228263 113073 228263 113997 228263 113995 228264 113997 228264 113996 228264 113996 228265 113997 228265 113076 228265 113996 228266 113076 228266 113998 228266 113998 228267 113076 228267 113078 228267 113998 228268 113078 228268 116196 228268 116196 228269 113078 228269 113079 228269 116196 228270 113079 228270 113999 228270 113086 228271 114000 228271 116199 228271 113079 228272 113080 228272 113999 228272 113999 228273 113080 228273 113082 228273 113999 228274 113082 228274 116199 228274 116199 228275 113082 228275 113084 228275 116199 228276 113084 228276 113086 228276 114001 228277 114002 228277 114003 228277 114000 228278 113086 228278 114003 228278 114003 228279 113086 228279 113087 228279 114003 228280 113087 228280 114001 228280 114002 228281 114001 228281 116200 228281 116200 228282 114001 228282 114004 228282 116200 228283 114004 228283 114005 228283 114005 228284 114004 228284 113089 228284 114005 228285 113089 228285 114006 228285 114006 228286 113089 228286 114008 228286 114006 228287 114008 228287 114007 228287 114007 228288 114008 228288 113090 228288 114007 228289 113090 228289 116202 228289 116202 228290 113090 228290 113091 228290 116202 228291 113091 228291 114009 228291 114009 228292 113091 228292 113093 228292 114009 228293 113093 228293 116198 228293 116198 228294 113093 228294 113065 228294 116198 228295 113065 228295 113066 228295 114014 228296 114010 228296 114011 228296 114011 228297 114010 228297 114012 228297 114011 228298 114012 228298 112861 228298 112861 228299 114012 228299 114457 228299 112861 228300 114457 228300 112860 228300 112860 228301 114457 228301 114456 228301 112860 228302 114456 228302 112859 228302 112859 228303 114456 228303 114455 228303 112859 228304 114455 228304 114013 228304 114013 228305 114455 228305 114454 228305 114013 228306 114454 228306 112857 228306 112857 228307 114454 228307 114453 228307 112857 228308 114453 228308 114035 228308 114022 228309 114451 228309 112844 228309 112844 228310 114451 228310 114450 228310 112844 228311 114450 228311 114014 228311 114014 228312 114450 228312 114015 228312 114014 228313 114015 228313 114010 228313 114026 228314 114016 228314 112847 228314 112847 228315 114016 228315 114462 228315 112847 228316 114462 228316 114018 228316 114462 228317 114017 228317 114018 228317 114018 228318 114017 228318 114019 228318 114018 228319 114019 228319 112845 228319 112845 228320 114019 228320 114020 228320 112845 228321 114020 228321 114022 228321 114022 228322 114020 228322 114021 228322 114022 228323 114021 228323 114451 228323 114034 228324 114024 228324 114023 228324 114023 228325 114024 228325 114025 228325 114023 228326 114025 228326 114026 228326 114026 228327 114025 228327 114027 228327 114026 228328 114027 228328 114016 228328 112853 228329 114028 228329 112852 228329 112852 228330 114028 228330 114191 228330 112852 228331 114191 228331 112851 228331 112851 228332 114191 228332 114190 228332 112851 228333 114190 228333 112850 228333 112850 228334 114190 228334 114029 228334 112850 228335 114029 228335 114030 228335 114030 228336 114029 228336 114031 228336 114030 228337 114031 228337 114032 228337 114032 228338 114031 228338 114033 228338 114032 228339 114033 228339 114034 228339 114034 228340 114033 228340 114188 228340 114034 228341 114188 228341 114024 228341 114453 228342 114452 228342 114035 228342 114035 228343 114452 228343 114143 228343 114035 228344 114143 228344 112856 228344 112856 228345 114143 228345 114184 228345 112856 228346 114184 228346 112854 228346 112854 228347 114184 228347 114036 228347 112854 228348 114036 228348 112853 228348 112853 228349 114036 228349 114037 228349 112853 228350 114037 228350 114028 228350 114045 228351 119046 228351 114038 228351 119073 228352 114052 228352 119035 228352 119035 228353 114052 228353 114040 228353 119035 228354 114040 228354 114039 228354 114039 228355 114040 228355 114041 228355 114039 228356 114041 228356 119033 228356 114043 228357 114042 228357 114041 228357 114041 228358 114042 228358 119032 228358 114041 228359 119032 228359 119033 228359 119046 228360 119044 228360 114038 228360 114038 228361 119044 228361 119042 228361 114038 228362 119042 228362 114043 228362 114043 228363 119042 228363 114044 228363 114043 228364 114044 228364 114042 228364 114045 228365 114038 228365 119048 228365 119048 228366 114038 228366 116585 228366 119048 228367 116585 228367 114046 228367 114046 228368 116585 228368 119049 228368 119049 228369 116585 228369 114047 228369 119049 228370 114047 228370 119098 228370 119093 228371 119095 228371 116584 228371 116584 228372 119095 228372 119094 228372 116584 228373 119094 228373 114047 228373 114047 228374 119094 228374 114048 228374 114047 228375 114048 228375 119098 228375 119093 228376 116584 228376 119091 228376 119091 228377 116584 228377 114049 228377 119091 228378 114049 228378 119089 228378 119089 228379 114049 228379 114050 228379 114050 228380 114049 228380 116581 228380 114050 228381 116581 228381 114051 228381 119086 228382 119084 228382 114053 228382 114053 228383 119084 228383 119083 228383 114053 228384 119083 228384 116581 228384 116581 228385 119083 228385 119109 228385 116581 228386 119109 228386 114051 228386 119073 228387 119072 228387 114052 228387 114052 228388 119072 228388 119036 228388 114052 228389 119036 228389 116580 228389 116580 228390 119036 228390 119082 228390 116580 228391 119082 228391 114053 228391 114053 228392 119082 228392 119087 228392 114053 228393 119087 228393 119086 228393 114070 228394 114061 228394 114054 228394 119197 228395 114079 228395 119189 228395 119189 228396 114079 228396 114055 228396 119189 228397 114055 228397 119190 228397 119200 228398 119195 228398 114056 228398 114056 228399 119195 228399 119194 228399 114056 228400 119194 228400 114055 228400 114055 228401 119194 228401 119191 228401 114055 228402 119191 228402 119190 228402 119200 228403 114056 228403 119201 228403 119201 228404 114056 228404 114059 228404 119201 228405 114059 228405 119202 228405 114064 228406 114057 228406 114063 228406 114063 228407 114057 228407 114058 228407 114063 228408 114058 228408 114059 228408 114059 228409 114058 228409 114060 228409 114059 228410 114060 228410 119202 228410 114054 228411 114061 228411 114063 228411 114063 228412 114061 228412 114062 228412 114063 228413 114062 228413 114064 228413 114065 228414 114066 228414 112269 228414 114065 228415 112269 228415 114067 228415 112269 228416 114068 228416 114067 228416 114067 228417 114068 228417 119188 228417 114067 228418 119188 228418 114054 228418 114054 228419 119188 228419 114069 228419 114054 228420 114069 228420 114070 228420 114072 228421 114071 228421 112260 228421 114072 228422 112260 228422 114065 228422 114065 228423 112260 228423 112259 228423 114065 228424 112259 228424 114066 228424 116574 228425 114073 228425 114072 228425 114072 228426 114073 228426 114074 228426 114072 228427 114074 228427 114071 228427 114076 228428 112279 228428 114078 228428 114078 228429 112279 228429 114075 228429 114078 228430 114075 228430 116574 228430 116574 228431 114075 228431 112277 228431 116574 228432 112277 228432 114073 228432 114076 228433 114078 228433 114077 228433 114077 228434 114078 228434 114080 228434 114077 228435 114080 228435 114083 228435 119197 228436 112268 228436 114079 228436 114079 228437 112268 228437 114081 228437 114079 228438 114081 228438 114080 228438 114080 228439 114081 228439 114082 228439 114080 228440 114082 228440 114083 228440 114084 228441 114100 228441 116565 228441 114099 228442 118981 228442 114094 228442 116572 228443 114088 228443 114108 228443 114108 228444 114088 228444 119000 228444 118985 228445 114085 228445 116570 228445 116570 228446 114085 228446 114086 228446 116570 228447 114086 228447 116572 228447 116572 228448 114086 228448 114087 228448 116572 228449 114087 228449 114088 228449 118985 228450 116570 228450 118987 228450 118987 228451 116570 228451 114091 228451 118987 228452 114091 228452 114089 228452 114090 228453 114092 228453 114091 228453 114091 228454 114092 228454 114093 228454 114091 228455 114093 228455 114089 228455 118981 228456 114095 228456 114094 228456 114094 228457 114095 228457 114096 228457 114094 228458 114096 228458 114090 228458 114090 228459 114096 228459 114097 228459 114090 228460 114097 228460 114092 228460 114102 228461 118979 228461 114098 228461 114098 228462 118979 228462 118978 228462 114098 228463 118978 228463 114094 228463 114094 228464 118978 228464 118980 228464 114094 228465 118980 228465 114099 228465 114100 228466 118952 228466 116565 228466 116565 228467 118952 228467 118955 228467 116565 228468 118955 228468 114102 228468 114102 228469 118955 228469 114101 228469 114102 228470 114101 228470 118979 228470 116561 228471 114106 228471 116564 228471 116564 228472 114106 228472 118930 228472 118930 228473 118932 228473 116564 228473 116564 228474 118932 228474 114103 228474 116564 228475 114103 228475 116565 228475 116565 228476 114103 228476 114104 228476 116565 228477 114104 228477 114084 228477 116559 228478 118929 228478 116561 228478 116561 228479 118929 228479 114105 228479 116561 228480 114105 228480 114106 228480 119000 228481 114107 228481 114108 228481 114108 228482 114107 228482 114109 228482 114108 228483 114109 228483 116559 228483 116559 228484 114109 228484 114110 228484 116559 228485 114110 228485 118929 228485 119139 228486 114111 228486 116554 228486 119153 228487 116557 228487 119149 228487 119149 228488 116557 228488 114112 228488 119149 228489 114112 228489 119150 228489 119152 228490 119151 228490 114116 228490 114116 228491 119151 228491 114113 228491 114116 228492 114113 228492 114112 228492 114112 228493 114113 228493 114114 228493 114112 228494 114114 228494 119150 228494 119152 228495 114116 228495 114115 228495 114115 228496 114116 228496 114117 228496 114115 228497 114117 228497 119158 228497 114118 228498 114119 228498 114122 228498 114122 228499 114119 228499 114120 228499 114122 228500 114120 228500 114117 228500 114117 228501 114120 228501 114121 228501 114117 228502 114121 228502 119158 228502 116554 228503 114111 228503 114122 228503 114122 228504 114111 228504 114123 228504 114122 228505 114123 228505 114118 228505 116552 228506 112315 228506 112314 228506 116552 228507 112314 228507 116553 228507 112314 228508 114124 228508 116553 228508 116553 228509 114124 228509 112317 228509 116553 228510 112317 228510 116554 228510 116554 228511 112317 228511 119140 228511 116554 228512 119140 228512 119139 228512 114126 228513 112303 228513 112301 228513 114126 228514 112301 228514 116552 228514 116552 228515 112301 228515 114125 228515 116552 228516 114125 228516 112315 228516 114129 228517 114131 228517 114126 228517 114126 228518 114131 228518 114127 228518 114126 228519 114127 228519 112303 228519 114132 228520 112324 228520 114128 228520 114128 228521 112324 228521 112323 228521 114128 228522 112323 228522 114129 228522 114129 228523 112323 228523 114130 228523 114129 228524 114130 228524 114131 228524 114132 228525 114128 228525 112299 228525 112299 228526 114128 228526 114135 228526 112299 228527 114135 228527 114133 228527 119153 228528 114134 228528 116557 228528 116557 228529 114134 228529 112313 228529 116557 228530 112313 228530 114135 228530 114135 228531 112313 228531 112289 228531 114135 228532 112289 228532 114133 228532 114136 228533 119239 228533 114137 228533 114137 228534 119239 228534 119243 228534 114137 228535 119243 228535 124976 228535 123831 228536 123906 228536 120472 228536 120472 228537 123906 228537 114138 228537 120472 228538 114138 228538 114139 228538 114380 228539 114389 228539 114386 228539 114318 228540 114425 228540 114319 228540 114393 228541 114440 228541 114442 228541 114394 228542 114140 228542 114417 228542 114413 228543 114141 228543 114140 228543 114250 228544 114323 228544 114249 228544 114245 228545 114325 228545 114323 228545 114243 228546 114238 228546 114244 228546 114234 228547 114237 228547 114142 228547 120504 228548 114404 228548 120505 228548 114184 228549 114143 228549 114185 228549 116207 228550 114185 228550 116206 228550 115926 228551 114290 228551 115927 228551 114144 228552 114293 228552 114294 228552 115871 228553 114145 228553 114422 228553 114468 228554 120531 228554 114146 228554 114468 228555 114146 228555 114469 228555 114469 228556 114146 228556 114211 228556 114469 228557 114211 228557 120262 228557 114210 228558 114209 228558 114147 228558 114147 228559 114209 228559 114206 228559 114147 228560 114206 228560 120263 228560 120263 228561 114206 228561 114148 228561 120263 228562 114148 228562 120265 228562 114154 228563 120523 228563 114149 228563 114154 228564 114149 228564 114155 228564 114150 228565 114151 228565 114152 228565 114152 228566 114151 228566 114154 228566 114152 228567 114154 228567 114153 228567 114153 228568 114154 228568 114155 228568 114157 228569 114156 228569 114158 228569 114157 228570 114158 228570 112205 228570 114214 228571 120237 228571 114159 228571 114159 228572 120237 228572 120236 228572 120233 228573 120239 228573 114158 228573 120233 228574 114158 228574 120234 228574 120239 228575 120241 228575 114158 228575 114158 228576 120241 228576 120242 228576 114158 228577 120242 228577 120244 228577 114152 228578 112205 228578 114150 228578 114150 228579 112205 228579 114158 228579 114150 228580 114158 228580 120266 228580 120266 228581 114158 228581 120244 228581 114218 228582 114217 228582 114215 228582 114215 228583 114217 228583 114495 228583 114517 228584 114216 228584 114518 228584 114518 228585 114216 228585 114220 228585 114518 228586 114220 228586 114160 228586 114225 228587 114161 228587 114511 228587 118393 228588 114161 228588 114162 228588 114162 228589 114161 228589 114225 228589 114162 228590 114225 228590 118387 228590 118387 228591 114225 228591 118456 228591 114163 228592 114164 228592 114448 228592 114228 228593 118412 228593 114229 228593 114229 228594 118412 228594 118411 228594 114164 228595 118441 228595 114448 228595 114448 228596 118441 228596 118462 228596 114448 228597 118462 228597 114226 228597 114230 228598 118373 228598 114165 228598 114165 228599 114166 228599 114230 228599 114230 228600 114166 228600 118408 228600 114230 228601 118408 228601 114227 228601 114167 228602 114168 228602 114331 228602 114331 228603 114168 228603 115881 228603 114167 228604 114331 228604 115880 228604 115880 228605 114331 228605 114265 228605 115880 228606 114265 228606 114169 228606 114169 228607 114265 228607 114170 228607 114169 228608 114170 228608 115880 228608 114269 228609 115908 228609 114267 228609 114267 228610 115908 228610 114170 228610 114267 228611 114170 228611 114171 228611 114171 228612 114170 228612 114265 228612 114172 228613 114271 228613 114173 228613 114173 228614 114271 228614 114174 228614 114174 228615 114271 228615 115876 228615 115876 228616 114271 228616 114272 228616 115876 228617 114272 228617 115877 228617 115877 228618 114272 228618 114274 228618 115877 228619 114274 228619 114275 228619 114175 228620 114279 228620 114320 228620 114320 228621 114279 228621 114278 228621 114320 228622 114278 228622 114321 228622 114175 228623 114320 228623 115890 228623 115890 228624 114320 228624 114319 228624 115890 228625 114319 228625 115871 228625 115871 228626 114319 228626 114425 228626 115871 228627 114425 228627 114145 228627 118601 228628 118593 228628 115923 228628 115923 228629 118593 228629 114423 228629 115922 228630 114303 228630 114176 228630 114176 228631 114303 228631 114177 228631 114176 228632 114177 228632 114292 228632 115927 228633 114290 228633 115929 228633 115929 228634 114290 228634 114289 228634 115929 228635 114289 228635 114180 228635 114286 228636 114178 228636 114289 228636 114289 228637 114178 228637 114179 228637 114289 228638 114179 228638 114180 228638 115933 228639 115932 228639 114181 228639 114181 228640 115932 228640 115931 228640 115931 228641 114178 228641 114181 228641 114181 228642 114178 228642 114286 228642 114181 228643 114286 228643 115933 228643 115933 228644 114286 228644 114285 228644 114414 228645 114346 228645 114182 228645 114182 228646 114346 228646 114347 228646 114182 228647 114347 228647 116203 228647 116203 228648 114347 228648 114187 228648 116203 228649 114187 228649 116209 228649 116206 228650 114185 228650 114183 228650 114183 228651 114185 228651 114143 228651 114183 228652 114143 228652 114452 228652 114037 228653 114036 228653 114192 228653 114036 228654 114184 228654 114192 228654 114192 228655 114184 228655 114185 228655 114192 228656 114185 228656 114348 228656 114348 228657 114185 228657 116207 228657 114348 228658 116207 228658 114187 228658 114187 228659 116207 228659 114186 228659 114187 228660 114186 228660 116209 228660 114343 228661 114188 228661 114189 228661 114189 228662 114188 228662 114033 228662 114189 228663 114033 228663 114031 228663 114031 228664 114029 228664 114189 228664 114189 228665 114029 228665 114190 228665 114189 228666 114190 228666 114350 228666 114350 228667 114190 228667 114191 228667 114350 228668 114191 228668 114192 228668 114192 228669 114191 228669 114028 228669 114192 228670 114028 228670 114037 228670 114196 228671 114462 228671 114016 228671 114196 228672 114016 228672 114194 228672 114016 228673 114027 228673 114194 228673 114194 228674 114027 228674 114025 228674 114194 228675 114025 228675 114024 228675 114193 228676 114449 228676 114344 228676 114449 228677 114459 228677 114344 228677 114344 228678 114459 228678 114195 228678 114344 228679 114195 228679 114194 228679 114194 228680 114195 228680 114461 228680 114194 228681 114461 228681 114196 228681 114344 228682 114197 228682 114193 228682 114193 228683 114197 228683 114345 228683 114193 228684 114345 228684 114463 228684 120503 228685 120502 228685 114354 228685 114354 228686 120502 228686 120506 228686 114354 228687 120506 228687 120507 228687 114404 228688 114374 228688 120505 228688 120505 228689 114374 228689 114373 228689 120505 228690 114373 228690 114199 228690 114372 228691 120498 228691 114198 228691 114198 228692 120498 228692 120497 228692 114198 228693 120497 228693 114373 228693 114373 228694 120497 228694 120501 228694 114373 228695 120501 228695 114199 228695 114369 228696 114202 228696 114372 228696 114372 228697 114202 228697 120499 228697 114372 228698 120499 228698 120498 228698 114156 228699 112197 228699 114158 228699 114158 228700 112197 228700 112199 228700 114158 228701 112199 228701 114200 228701 114200 228702 112199 228702 112201 228702 114200 228703 112201 228703 114369 228703 114369 228704 112201 228704 114201 228704 114369 228705 114201 228705 114202 228705 114213 228706 120529 228706 114212 228706 114212 228707 120529 228707 114203 228707 114212 228708 114203 228708 114208 228708 114208 228709 114203 228709 114207 228709 114151 228710 114204 228710 114154 228710 114154 228711 114204 228711 114205 228711 114154 228712 114205 228712 120523 228712 120523 228713 114205 228713 120265 228713 120523 228714 120265 228714 120524 228714 120524 228715 120265 228715 114148 228715 120524 228716 114148 228716 120525 228716 120525 228717 114148 228717 114206 228717 120525 228718 114206 228718 114207 228718 114207 228719 114206 228719 114209 228719 114207 228720 114209 228720 114208 228720 114208 228721 114209 228721 114210 228721 114208 228722 114210 228722 114212 228722 114212 228723 114210 228723 114211 228723 114212 228724 114211 228724 114213 228724 114213 228725 114211 228725 114146 228725 114213 228726 114146 228726 120533 228726 120533 228727 114146 228727 120531 228727 120236 228728 120234 228728 114159 228728 114159 228729 120234 228729 114158 228729 114159 228730 114158 228730 114367 228730 114367 228731 114158 228731 114200 228731 114495 228732 120268 228732 114215 228732 114215 228733 120268 228733 114214 228733 114215 228734 114214 228734 114218 228734 114218 228735 114214 228735 114159 228735 114218 228736 114159 228736 114219 228736 114219 228737 114159 228737 114367 228737 114517 228738 114217 228738 114216 228738 114216 228739 114217 228739 114218 228739 114216 228740 114218 228740 114220 228740 114220 228741 114218 228741 114219 228741 114220 228742 114219 228742 114365 228742 114221 228743 114383 228743 114224 228743 114445 228744 114444 228744 114332 228744 114332 228745 114444 228745 114443 228745 114332 228746 114443 228746 114333 228746 114221 228747 114224 228747 114398 228747 114398 228748 114224 228748 114222 228748 114398 228749 114222 228749 114396 228749 114396 228750 114222 228750 114225 228750 114396 228751 114225 228751 114223 228751 114223 228752 114225 228752 114511 228752 114223 228753 114511 228753 114512 228753 114383 228754 114446 228754 114224 228754 114224 228755 114446 228755 114447 228755 114224 228756 114447 228756 114222 228756 114222 228757 114447 228757 114448 228757 114222 228758 114448 228758 114225 228758 114225 228759 114448 228759 114226 228759 114225 228760 114226 228760 118456 228760 114227 228761 114228 228761 114230 228761 114230 228762 114228 228762 114229 228762 114230 228763 114229 228763 114236 228763 114236 228764 114229 228764 114231 228764 114236 228765 114231 228765 114235 228765 114235 228766 114231 228766 114232 228766 114235 228767 114232 228767 114233 228767 114233 228768 114234 228768 114235 228768 114235 228769 114234 228769 114142 228769 114235 228770 114142 228770 114236 228770 114236 228771 114142 228771 114257 228771 114236 228772 114257 228772 114230 228772 114230 228773 114257 228773 114259 228773 114230 228774 114259 228774 118373 228774 114237 228775 114335 228775 114329 228775 114238 228776 114243 228776 114328 228776 114328 228777 114243 228777 114242 228777 114328 228778 114242 228778 114240 228778 114239 228779 114240 228779 114241 228779 114241 228780 114240 228780 114242 228780 114241 228781 114242 228781 114253 228781 114253 228782 114242 228782 114243 228782 114253 228783 114243 228783 114252 228783 114252 228784 114243 228784 114244 228784 114252 228785 114244 228785 114325 228785 114323 228786 114250 228786 114245 228786 114245 228787 114250 228787 114246 228787 114245 228788 114246 228788 114247 228788 114321 228789 114278 228789 114322 228789 114322 228790 114278 228790 114276 228790 114322 228791 114276 228791 114249 228791 114249 228792 114276 228792 114248 228792 114249 228793 114248 228793 114250 228793 114250 228794 114248 228794 114273 228794 114250 228795 114273 228795 114246 228795 114273 228796 114270 228796 114246 228796 114246 228797 114270 228797 114251 228797 114246 228798 114251 228798 114247 228798 114247 228799 114251 228799 114262 228799 114247 228800 114262 228800 114254 228800 114254 228801 114262 228801 114263 228801 114254 228802 114263 228802 114255 228802 114325 228803 114245 228803 114252 228803 114252 228804 114245 228804 114247 228804 114252 228805 114247 228805 114253 228805 114253 228806 114247 228806 114254 228806 114253 228807 114254 228807 114241 228807 114241 228808 114254 228808 114255 228808 114241 228809 114255 228809 114239 228809 114237 228810 114329 228810 114142 228810 114142 228811 114329 228811 114256 228811 114142 228812 114256 228812 114257 228812 114257 228813 114256 228813 114258 228813 114257 228814 114258 228814 114259 228814 114259 228815 114258 228815 115883 228815 114259 228816 115883 228816 118373 228816 114270 228817 114260 228817 114251 228817 114251 228818 114260 228818 114261 228818 114251 228819 114261 228819 114262 228819 114262 228820 114261 228820 114268 228820 114262 228821 114268 228821 114263 228821 114263 228822 114268 228822 114266 228822 114263 228823 114266 228823 114255 228823 114255 228824 114266 228824 114264 228824 114255 228825 114264 228825 114239 228825 114239 228826 114264 228826 114330 228826 114331 228827 114330 228827 114265 228827 114265 228828 114330 228828 114264 228828 114265 228829 114264 228829 114171 228829 114171 228830 114264 228830 114266 228830 114171 228831 114266 228831 114267 228831 114267 228832 114266 228832 114268 228832 114267 228833 114268 228833 114269 228833 114269 228834 114268 228834 114261 228834 114269 228835 114261 228835 115878 228835 115878 228836 114261 228836 114260 228836 115878 228837 114260 228837 114172 228837 114172 228838 114260 228838 114270 228838 114172 228839 114270 228839 114271 228839 114271 228840 114270 228840 114273 228840 114271 228841 114273 228841 114272 228841 114272 228842 114273 228842 114248 228842 114272 228843 114248 228843 114274 228843 114274 228844 114248 228844 114276 228844 114274 228845 114276 228845 114275 228845 114275 228846 114276 228846 114278 228846 114275 228847 114278 228847 114277 228847 114277 228848 114278 228848 114279 228848 114440 228849 114393 228849 114280 228849 114280 228850 114393 228850 114281 228850 114280 228851 114281 228851 114302 228851 114302 228852 114281 228852 114282 228852 114302 228853 114282 228853 114283 228853 114283 228854 114282 228854 114418 228854 114283 228855 114418 228855 114300 228855 114300 228856 114418 228856 114419 228856 114300 228857 114419 228857 114299 228857 114299 228858 114419 228858 114420 228858 114299 228859 114420 228859 114284 228859 114284 228860 114420 228860 114285 228860 114284 228861 114285 228861 114297 228861 114297 228862 114285 228862 114286 228862 114297 228863 114286 228863 114287 228863 114287 228864 114286 228864 114289 228864 114287 228865 114289 228865 114288 228865 114288 228866 114289 228866 114290 228866 114288 228867 114290 228867 114295 228867 114295 228868 114290 228868 115926 228868 114295 228869 115926 228869 114294 228869 114294 228870 115926 228870 114291 228870 114294 228871 114291 228871 114144 228871 114144 228872 114292 228872 114293 228872 114293 228873 114292 228873 114177 228873 114293 228874 114177 228874 114294 228874 114294 228875 114177 228875 114304 228875 114294 228876 114304 228876 114295 228876 114295 228877 114304 228877 114306 228877 114295 228878 114306 228878 114288 228878 114288 228879 114306 228879 114296 228879 114288 228880 114296 228880 114287 228880 114287 228881 114296 228881 114309 228881 114287 228882 114309 228882 114297 228882 114297 228883 114309 228883 114298 228883 114297 228884 114298 228884 114284 228884 114284 228885 114298 228885 114310 228885 114284 228886 114310 228886 114299 228886 114299 228887 114310 228887 114311 228887 114299 228888 114311 228888 114300 228888 114300 228889 114311 228889 114313 228889 114300 228890 114313 228890 114283 228890 114283 228891 114313 228891 114301 228891 114283 228892 114301 228892 114302 228892 114302 228893 114301 228893 114314 228893 114302 228894 114314 228894 114280 228894 114280 228895 114314 228895 114438 228895 114280 228896 114438 228896 114440 228896 115922 228897 115923 228897 114303 228897 114303 228898 115923 228898 114423 228898 114303 228899 114423 228899 114177 228899 114177 228900 114423 228900 114424 228900 114177 228901 114424 228901 114304 228901 114304 228902 114424 228902 114305 228902 114304 228903 114305 228903 114306 228903 114306 228904 114305 228904 114307 228904 114306 228905 114307 228905 114296 228905 114296 228906 114307 228906 114308 228906 114296 228907 114308 228907 114309 228907 114309 228908 114308 228908 114427 228908 114309 228909 114427 228909 114298 228909 114298 228910 114427 228910 114431 228910 114298 228911 114431 228911 114310 228911 114310 228912 114431 228912 114432 228912 114310 228913 114432 228913 114311 228913 114311 228914 114432 228914 114312 228914 114311 228915 114312 228915 114313 228915 114313 228916 114312 228916 114434 228916 114313 228917 114434 228917 114301 228917 114301 228918 114434 228918 114436 228918 114301 228919 114436 228919 114314 228919 114314 228920 114436 228920 114315 228920 114314 228921 114315 228921 114438 228921 114342 228922 114428 228922 114316 228922 114316 228923 114428 228923 114426 228923 114316 228924 114426 228924 114317 228924 114317 228925 114426 228925 114318 228925 114318 228926 114319 228926 114317 228926 114317 228927 114319 228927 114320 228927 114317 228928 114320 228928 114316 228928 114316 228929 114320 228929 114321 228929 114316 228930 114321 228930 114342 228930 114342 228931 114321 228931 114322 228931 114342 228932 114322 228932 114341 228932 114341 228933 114322 228933 114249 228933 114341 228934 114249 228934 114340 228934 114340 228935 114249 228935 114323 228935 114340 228936 114323 228936 114324 228936 114324 228937 114323 228937 114325 228937 114324 228938 114325 228938 114338 228938 114338 228939 114325 228939 114244 228939 114338 228940 114244 228940 114326 228940 114326 228941 114244 228941 114238 228941 114326 228942 114238 228942 114327 228942 114327 228943 114238 228943 114328 228943 114327 228944 114328 228944 114336 228944 114336 228945 114328 228945 114240 228945 114336 228946 114240 228946 114335 228946 114335 228947 114240 228947 114239 228947 114335 228948 114239 228948 114329 228948 114329 228949 114239 228949 114330 228949 114329 228950 114330 228950 114256 228950 114256 228951 114330 228951 114331 228951 114256 228952 114331 228952 114258 228952 114258 228953 114331 228953 115881 228953 114258 228954 115881 228954 115883 228954 114232 228955 114445 228955 114233 228955 114233 228956 114445 228956 114332 228956 114233 228957 114332 228957 114234 228957 114234 228958 114332 228958 114333 228958 114234 228959 114333 228959 114237 228959 114237 228960 114333 228960 114334 228960 114237 228961 114334 228961 114335 228961 114335 228962 114334 228962 114441 228962 114335 228963 114441 228963 114336 228963 114336 228964 114441 228964 114439 228964 114336 228965 114439 228965 114327 228965 114327 228966 114439 228966 114337 228966 114327 228967 114337 228967 114326 228967 114326 228968 114337 228968 114437 228968 114326 228969 114437 228969 114338 228969 114338 228970 114437 228970 114339 228970 114338 228971 114339 228971 114324 228971 114324 228972 114339 228972 114435 228972 114324 228973 114435 228973 114340 228973 114340 228974 114435 228974 114433 228974 114340 228975 114433 228975 114341 228975 114341 228976 114433 228976 114430 228976 114341 228977 114430 228977 114342 228977 114342 228978 114430 228978 114429 228978 114342 228979 114429 228979 114428 228979 114024 228980 114188 228980 114194 228980 114194 228981 114188 228981 114343 228981 114194 228982 114343 228982 114344 228982 114344 228983 114343 228983 114354 228983 114344 228984 114354 228984 114197 228984 114197 228985 114354 228985 120507 228985 114197 228986 120507 228986 114345 228986 114346 228987 114411 228987 114347 228987 114347 228988 114411 228988 114410 228988 114347 228989 114410 228989 114187 228989 114187 228990 114410 228990 114408 228990 114187 228991 114408 228991 114348 228991 114348 228992 114408 228992 114407 228992 114348 228993 114407 228993 114192 228993 114192 228994 114407 228994 114349 228994 114192 228995 114349 228995 114350 228995 114350 228996 114349 228996 114351 228996 114350 228997 114351 228997 114189 228997 114189 228998 114351 228998 114352 228998 114189 228999 114352 228999 114343 228999 114343 229000 114352 229000 114353 229000 114343 229001 114353 229001 114354 229001 114354 229002 114353 229002 114355 229002 114354 229003 114355 229003 120503 229003 114356 229004 114403 229004 114357 229004 114356 229005 114357 229005 114358 229005 114358 229006 114357 229006 114360 229006 114358 229007 114360 229007 114359 229007 114359 229008 114360 229008 114361 229008 114359 229009 114361 229009 114371 229009 114371 229010 114361 229010 114399 229010 114371 229011 114399 229011 114370 229011 114370 229012 114399 229012 114362 229012 114370 229013 114362 229013 114368 229013 114368 229014 114362 229014 114397 229014 114368 229015 114397 229015 114363 229015 114363 229016 114397 229016 114395 229016 114363 229017 114395 229017 114366 229017 114366 229018 114395 229018 114364 229018 114366 229019 114364 229019 114365 229019 114365 229020 114219 229020 114366 229020 114366 229021 114219 229021 114367 229021 114366 229022 114367 229022 114363 229022 114363 229023 114367 229023 114200 229023 114363 229024 114200 229024 114368 229024 114368 229025 114200 229025 114369 229025 114368 229026 114369 229026 114370 229026 114370 229027 114369 229027 114372 229027 114370 229028 114372 229028 114371 229028 114371 229029 114372 229029 114198 229029 114371 229030 114198 229030 114359 229030 114359 229031 114198 229031 114373 229031 114359 229032 114373 229032 114358 229032 114358 229033 114373 229033 114374 229033 114358 229034 114374 229034 114356 229034 114140 229035 114394 229035 114413 229035 114413 229036 114394 229036 114375 229036 114413 229037 114375 229037 114412 229037 114412 229038 114375 229038 114392 229038 114412 229039 114392 229039 114409 229039 114409 229040 114392 229040 114376 229040 114409 229041 114376 229041 114406 229041 114406 229042 114376 229042 114377 229042 114406 229043 114377 229043 114405 229043 114405 229044 114377 229044 114390 229044 114405 229045 114390 229045 114378 229045 114378 229046 114390 229046 114388 229046 114378 229047 114388 229047 114402 229047 114384 229048 114400 229048 114381 229048 114389 229049 114381 229049 114379 229049 114379 229050 114381 229050 114400 229050 114379 229051 114400 229051 114401 229051 114389 229052 114380 229052 114381 229052 114381 229053 114380 229053 114382 229053 114381 229054 114382 229054 114384 229054 114221 229055 114384 229055 114383 229055 114383 229056 114384 229056 114382 229056 114383 229057 114382 229057 114385 229057 114385 229058 114382 229058 114380 229058 114385 229059 114380 229059 114387 229059 114387 229060 114380 229060 114386 229060 114387 229061 114386 229061 114391 229061 114401 229062 114402 229062 114379 229062 114379 229063 114402 229063 114388 229063 114379 229064 114388 229064 114389 229064 114389 229065 114388 229065 114390 229065 114389 229066 114390 229066 114386 229066 114386 229067 114390 229067 114377 229067 114386 229068 114377 229068 114391 229068 114391 229069 114377 229069 114376 229069 114391 229070 114376 229070 114442 229070 114442 229071 114376 229071 114392 229071 114442 229072 114392 229072 114393 229072 114393 229073 114392 229073 114375 229073 114393 229074 114375 229074 114281 229074 114281 229075 114375 229075 114394 229075 114281 229076 114394 229076 114282 229076 114282 229077 114394 229077 114417 229077 114282 229078 114417 229078 114418 229078 114160 229079 114220 229079 114514 229079 114514 229080 114220 229080 114365 229080 114514 229081 114365 229081 114512 229081 114512 229082 114365 229082 114364 229082 114512 229083 114364 229083 114223 229083 114223 229084 114364 229084 114395 229084 114223 229085 114395 229085 114396 229085 114396 229086 114395 229086 114397 229086 114396 229087 114397 229087 114398 229087 114398 229088 114397 229088 114362 229088 114398 229089 114362 229089 114221 229089 114221 229090 114362 229090 114399 229090 114221 229091 114399 229091 114384 229091 114384 229092 114399 229092 114361 229092 114384 229093 114361 229093 114400 229093 114400 229094 114361 229094 114360 229094 114400 229095 114360 229095 114401 229095 114401 229096 114360 229096 114357 229096 114401 229097 114357 229097 114402 229097 114402 229098 114357 229098 114403 229098 114402 229099 114403 229099 114378 229099 120504 229100 120503 229100 114404 229100 114404 229101 120503 229101 114355 229101 114404 229102 114355 229102 114374 229102 114374 229103 114355 229103 114353 229103 114374 229104 114353 229104 114356 229104 114356 229105 114353 229105 114352 229105 114356 229106 114352 229106 114403 229106 114403 229107 114352 229107 114351 229107 114403 229108 114351 229108 114378 229108 114378 229109 114351 229109 114349 229109 114378 229110 114349 229110 114405 229110 114405 229111 114349 229111 114407 229111 114405 229112 114407 229112 114406 229112 114406 229113 114407 229113 114408 229113 114406 229114 114408 229114 114409 229114 114409 229115 114408 229115 114410 229115 114409 229116 114410 229116 114412 229116 114412 229117 114410 229117 114411 229117 114412 229118 114411 229118 114413 229118 114413 229119 114411 229119 114346 229119 114413 229120 114346 229120 114141 229120 114141 229121 114346 229121 114414 229121 114141 229122 114414 229122 114140 229122 114140 229123 114414 229123 114415 229123 114140 229124 114415 229124 114417 229124 114417 229125 114415 229125 114416 229125 114417 229126 114416 229126 114418 229126 114418 229127 114416 229127 115938 229127 114418 229128 115938 229128 114419 229128 114419 229129 115938 229129 115937 229129 114419 229130 115937 229130 114420 229130 114420 229131 115937 229131 114421 229131 114420 229132 114421 229132 114285 229132 114285 229133 114421 229133 115934 229133 114285 229134 115934 229134 115933 229134 118593 229135 114422 229135 114423 229135 114423 229136 114422 229136 114145 229136 114423 229137 114145 229137 114424 229137 114424 229138 114145 229138 114425 229138 114424 229139 114425 229139 114305 229139 114305 229140 114425 229140 114318 229140 114305 229141 114318 229141 114307 229141 114307 229142 114318 229142 114426 229142 114307 229143 114426 229143 114308 229143 114308 229144 114426 229144 114428 229144 114308 229145 114428 229145 114427 229145 114427 229146 114428 229146 114429 229146 114427 229147 114429 229147 114431 229147 114431 229148 114429 229148 114430 229148 114431 229149 114430 229149 114432 229149 114432 229150 114430 229150 114433 229150 114432 229151 114433 229151 114312 229151 114312 229152 114433 229152 114435 229152 114312 229153 114435 229153 114434 229153 114434 229154 114435 229154 114339 229154 114434 229155 114339 229155 114436 229155 114436 229156 114339 229156 114437 229156 114436 229157 114437 229157 114315 229157 114315 229158 114437 229158 114337 229158 114315 229159 114337 229159 114438 229159 114438 229160 114337 229160 114439 229160 114438 229161 114439 229161 114440 229161 114440 229162 114439 229162 114441 229162 114440 229163 114441 229163 114442 229163 114442 229164 114441 229164 114334 229164 114442 229165 114334 229165 114391 229165 114391 229166 114334 229166 114333 229166 114391 229167 114333 229167 114387 229167 114387 229168 114333 229168 114443 229168 114387 229169 114443 229169 114385 229169 114385 229170 114443 229170 114444 229170 114385 229171 114444 229171 114383 229171 114383 229172 114444 229172 114445 229172 114383 229173 114445 229173 114446 229173 114446 229174 114445 229174 114232 229174 114446 229175 114232 229175 114447 229175 114447 229176 114232 229176 114231 229176 114447 229177 114231 229177 114448 229177 114448 229178 114231 229178 114229 229178 114448 229179 114229 229179 114163 229179 114163 229180 114229 229180 118411 229180 114459 229181 114449 229181 114464 229181 117568 229182 114458 229182 114450 229182 114019 229183 114017 229183 117574 229183 114450 229184 114451 229184 117568 229184 117568 229185 114451 229185 114021 229185 117568 229186 114021 229186 117574 229186 117574 229187 114021 229187 114020 229187 117574 229188 114020 229188 114019 229188 117562 229189 116206 229189 114453 229189 114453 229190 116206 229190 114183 229190 114453 229191 114183 229191 114452 229191 114453 229192 114454 229192 117562 229192 117562 229193 114454 229193 114455 229193 117562 229194 114455 229194 114456 229194 114456 229195 114457 229195 117562 229195 117562 229196 114457 229196 114012 229196 117562 229197 114012 229197 117563 229197 117563 229198 114012 229198 114010 229198 117563 229199 114010 229199 114458 229199 114458 229200 114010 229200 114015 229200 114458 229201 114015 229201 114450 229201 114459 229202 114464 229202 114195 229202 114195 229203 114464 229203 114460 229203 114195 229204 114460 229204 114461 229204 114461 229205 114460 229205 117574 229205 114461 229206 117574 229206 114196 229206 114196 229207 117574 229207 114017 229207 114196 229208 114017 229208 114462 229208 114463 229209 120513 229209 114193 229209 114193 229210 120513 229210 114449 229210 114449 229211 120513 229211 114464 229211 114464 229212 120513 229212 120514 229212 114464 229213 120514 229213 114465 229213 120514 229214 120516 229214 114465 229214 114465 229215 120516 229215 120517 229215 114465 229216 120517 229216 114466 229216 120517 229217 120518 229217 114466 229217 114466 229218 120518 229218 120519 229218 114466 229219 120519 229219 114467 229219 114467 229220 120519 229220 120509 229220 120531 229221 114468 229221 120536 229221 120536 229222 114468 229222 114469 229222 120536 229223 114469 229223 120537 229223 120537 229224 114469 229224 117652 229224 120537 229225 117652 229225 114470 229225 114470 229226 117652 229226 114471 229226 114470 229227 114471 229227 120540 229227 120540 229228 114471 229228 114473 229228 120540 229229 114473 229229 114472 229229 114472 229230 114473 229230 114474 229230 114472 229231 114474 229231 120534 229231 120534 229232 114474 229232 117569 229232 120534 229233 117569 229233 120509 229233 120509 229234 117569 229234 114475 229234 120509 229235 114475 229235 114467 229235 120262 229236 120261 229236 114469 229236 114469 229237 120261 229237 120253 229237 114469 229238 120253 229238 117652 229238 117652 229239 120253 229239 120251 229239 120246 229240 116298 229240 117651 229240 120251 229241 120250 229241 117652 229241 117652 229242 120250 229242 120255 229242 117652 229243 120255 229243 114476 229243 120255 229244 114477 229244 114476 229244 114476 229245 114477 229245 114478 229245 114476 229246 114478 229246 117651 229246 117651 229247 114478 229247 120248 229247 117651 229248 120248 229248 120246 229248 118407 229249 118370 229249 114510 229249 114521 229250 114479 229250 114520 229250 114480 229251 114481 229251 114549 229251 119995 229252 116309 229252 114482 229252 114482 229253 120274 229253 119995 229253 119995 229254 120274 229254 120275 229254 119995 229255 120275 229255 114483 229255 120275 229256 114484 229256 114483 229256 114483 229257 114484 229257 114486 229257 114483 229258 114486 229258 114485 229258 114485 229259 114486 229259 120272 229259 114485 229260 120272 229260 114488 229260 114488 229261 120272 229261 114487 229261 114488 229262 114487 229262 114489 229262 114489 229263 114487 229263 120276 229263 114489 229264 120276 229264 119998 229264 119998 229265 120276 229265 120277 229265 119998 229266 120277 229266 114490 229266 114490 229267 120277 229267 114491 229267 114490 229268 114491 229268 119999 229268 119999 229269 114491 229269 114492 229269 114492 229270 114491 229270 120278 229270 114492 229271 120278 229271 120224 229271 120224 229272 114493 229272 114492 229272 114492 229273 114493 229273 120225 229273 114492 229274 120225 229274 119987 229274 119987 229275 120225 229275 120222 229275 120230 229276 120232 229276 114498 229276 114498 229277 120232 229277 114516 229277 120268 229278 114495 229278 114494 229278 114494 229279 114495 229279 114516 229279 114519 229280 120001 229280 114496 229280 120001 229281 114497 229281 114496 229281 114496 229282 114497 229282 119983 229282 114496 229283 119983 229283 114498 229283 114498 229284 119983 229284 114499 229284 114498 229285 114499 229285 120230 229285 120230 229286 114499 229286 119985 229286 120230 229287 119985 229287 120221 229287 120221 229288 119985 229288 119986 229288 120221 229289 119986 229289 120227 229289 120227 229290 119986 229290 119987 229290 120227 229291 119987 229291 114500 229291 114500 229292 119987 229292 120222 229292 119979 229293 114557 229293 114501 229293 114501 229294 114557 229294 114558 229294 114501 229295 114558 229295 119974 229295 119974 229296 114558 229296 119973 229296 114549 229297 114481 229297 114558 229297 114558 229298 114481 229298 114502 229298 114558 229299 114502 229299 119973 229299 114480 229300 114549 229300 114503 229300 114503 229301 114549 229301 114504 229301 114503 229302 114504 229302 120003 229302 120003 229303 114504 229303 114546 229303 120003 229304 114546 229304 114505 229304 114505 229305 114546 229305 114543 229305 114505 229306 114543 229306 114506 229306 114506 229307 114543 229307 120009 229307 120009 229308 114543 229308 114545 229308 120009 229309 114545 229309 114507 229309 114507 229310 114545 229310 114541 229310 114507 229311 114541 229311 114508 229311 114508 229312 114541 229312 10504 229312 114508 229313 10504 229313 120006 229313 114161 229314 118393 229314 114509 229314 114161 229315 114509 229315 114511 229315 114511 229316 114509 229316 118406 229316 114511 229317 118406 229317 118407 229317 118407 229318 114510 229318 114511 229318 114511 229319 114510 229319 114513 229319 114511 229320 114513 229320 114512 229320 114512 229321 114513 229321 114514 229321 114514 229322 114513 229322 114515 229322 114514 229323 114515 229323 114160 229323 114516 229324 114495 229324 114498 229324 114498 229325 114495 229325 114217 229325 114498 229326 114217 229326 114496 229326 114496 229327 114217 229327 114517 229327 114496 229328 114517 229328 114515 229328 114515 229329 114517 229329 114518 229329 114515 229330 114518 229330 114160 229330 119979 229331 114519 229331 114557 229331 114557 229332 114519 229332 114496 229332 114557 229333 114496 229333 114561 229333 114561 229334 114496 229334 114515 229334 114561 229335 114515 229335 114563 229335 114563 229336 114515 229336 114513 229336 114563 229337 114513 229337 114520 229337 114520 229338 114513 229338 114510 229338 114520 229339 114510 229339 114521 229339 114521 229340 114510 229340 118370 229340 114540 229341 10504 229341 114541 229341 119759 229342 119509 229342 114523 229342 114523 229343 119509 229343 114522 229343 114523 229344 114522 229344 119758 229344 114524 229345 114525 229345 119757 229345 119757 229346 114525 229346 119512 229346 119757 229347 119512 229347 119759 229347 119759 229348 119512 229348 119510 229348 119759 229349 119510 229349 119509 229349 119486 229350 119505 229350 114532 229350 114532 229351 119505 229351 119503 229351 114532 229352 119503 229352 119762 229352 119762 229353 119503 229353 114526 229353 119762 229354 114526 229354 114527 229354 114527 229355 114526 229355 114528 229355 114527 229356 114528 229356 119755 229356 119755 229357 114528 229357 114529 229357 119755 229358 114529 229358 114524 229358 114524 229359 114529 229359 119499 229359 114524 229360 119499 229360 114525 229360 114633 229361 114530 229361 114634 229361 114634 229362 114530 229362 119513 229362 114634 229363 119513 229363 119475 229363 119475 229364 119479 229364 114531 229364 114531 229365 119479 229365 119478 229365 112219 229366 112216 229366 119485 229366 119485 229367 112216 229367 114555 229367 119486 229368 114532 229368 119485 229368 119485 229369 114532 229369 114533 229369 119485 229370 114533 229370 112219 229370 119475 229371 114531 229371 114634 229371 114634 229372 114531 229372 114560 229372 114634 229373 114560 229373 114635 229373 114635 229374 114560 229374 114534 229374 114534 229375 114560 229375 114535 229375 114534 229376 114535 229376 114738 229376 114738 229377 114535 229377 114537 229377 114738 229378 114537 229378 114536 229378 114536 229379 114537 229379 114770 229379 114770 229380 114537 229380 114562 229380 114770 229381 114562 229381 114538 229381 114538 229382 118296 229382 114631 229382 114631 229383 118296 229383 114539 229383 114631 229384 114539 229384 118259 229384 114479 229385 118334 229385 114562 229385 114562 229386 118334 229386 118343 229386 114562 229387 118343 229387 114538 229387 114538 229388 118343 229388 118308 229388 114538 229389 118308 229389 118296 229389 114540 229390 114541 229390 114542 229390 114542 229391 114541 229391 114545 229391 114542 229392 114545 229392 119748 229392 114543 229393 114544 229393 114545 229393 114545 229394 114544 229394 119749 229394 114545 229395 119749 229395 119748 229395 114546 229396 114504 229396 114551 229396 114551 229397 119751 229397 114546 229397 114546 229398 119751 229398 114547 229398 114546 229399 114547 229399 114543 229399 114543 229400 114547 229400 119750 229400 114543 229401 119750 229401 114544 229401 119730 229402 114548 229402 114558 229402 114558 229403 114548 229403 119738 229403 114558 229404 119738 229404 114549 229404 114549 229405 119738 229405 119737 229405 114549 229406 119737 229406 114504 229406 114504 229407 119737 229407 114550 229407 114504 229408 114550 229408 114551 229408 114552 229409 114560 229409 114553 229409 114553 229410 114560 229410 114531 229410 114553 229411 114531 229411 114554 229411 114554 229412 114531 229412 119478 229412 114554 229413 119478 229413 112216 229413 112216 229414 119478 229414 119481 229414 112216 229415 119481 229415 114555 229415 119752 229416 114556 229416 114557 229416 114557 229417 114556 229417 114559 229417 114557 229418 114559 229418 114558 229418 114558 229419 114559 229419 119732 229419 114558 229420 119732 229420 119730 229420 114552 229421 119752 229421 114560 229421 114560 229422 119752 229422 114557 229422 114560 229423 114557 229423 114535 229423 114535 229424 114557 229424 114561 229424 114535 229425 114561 229425 114537 229425 114537 229426 114561 229426 114563 229426 114537 229427 114563 229427 114562 229427 114562 229428 114563 229428 114520 229428 114562 229429 114520 229429 114479 229429 114868 229430 114832 229430 114866 229430 114564 229431 114862 229431 114742 229431 114867 229432 114565 229432 114699 229432 114702 229433 114566 229433 114867 229433 114680 229434 114707 229434 114706 229434 114677 229435 114676 229435 114566 229435 114678 229436 114567 229436 114676 229436 114664 229437 114870 229437 114567 229437 114648 229438 114568 229438 119525 229438 114635 229439 114569 229439 114736 229439 114569 229440 114635 229440 114534 229440 114624 229441 114623 229441 115827 229441 115832 229442 114570 229442 114669 229442 114571 229443 116271 229443 114806 229443 116275 229444 114614 229444 114846 229444 116247 229445 114604 229445 116269 229445 119279 229446 114572 229446 114590 229446 119284 229447 119282 229447 114756 229447 119287 229448 114573 229448 114587 229448 114574 229449 114575 229449 114655 229449 114655 229450 114575 229450 119527 229450 114655 229451 119527 229451 114653 229451 114576 229452 119296 229452 114651 229452 114651 229453 119296 229453 114577 229453 114651 229454 114577 229454 114652 229454 114652 229455 114577 229455 119299 229455 114652 229456 119299 229456 114654 229456 119274 229457 114578 229457 114579 229457 114579 229458 114578 229458 119293 229458 114579 229459 119293 229459 114647 229459 119273 229460 119271 229460 114733 229460 114733 229461 119271 229461 114579 229461 114579 229462 119271 229462 114580 229462 114579 229463 114580 229463 119274 229463 119266 229464 114581 229464 114582 229464 114581 229465 114583 229465 114582 229465 114582 229466 114583 229466 114584 229466 114582 229467 114584 229467 114733 229467 114733 229468 114584 229468 114585 229468 114733 229469 114585 229469 119273 229469 114765 229470 114771 229470 114586 229470 114586 229471 114771 229471 119288 229471 119287 229472 114587 229472 114854 229472 119282 229473 114855 229473 114762 229473 119284 229474 114756 229474 114588 229474 114588 229475 114756 229475 114589 229475 114588 229476 114589 229476 119286 229476 114590 229477 116235 229477 114591 229477 119279 229478 114590 229478 119280 229478 119280 229479 114590 229479 114591 229479 119280 229480 114591 229480 114592 229480 114759 229481 116238 229481 116236 229481 119286 229482 114589 229482 114593 229482 114593 229483 114589 229483 114758 229483 114593 229484 114758 229484 114572 229484 114572 229485 114758 229485 114759 229485 114572 229486 114759 229486 114590 229486 114590 229487 114759 229487 116236 229487 114590 229488 116236 229488 116235 229488 114596 229489 114595 229489 114594 229489 116232 229490 114595 229490 113968 229490 113968 229491 114595 229491 114596 229491 113968 229492 114596 229492 114760 229492 114597 229493 114598 229493 114744 229493 114744 229494 114598 229494 114746 229494 114603 229495 114599 229495 114600 229495 114600 229496 114601 229496 114603 229496 114603 229497 114601 229497 114602 229497 114603 229498 114602 229498 113970 229498 113960 229499 113965 229499 114754 229499 114754 229500 113965 229500 113964 229500 116247 229501 113982 229501 114604 229501 114604 229502 113982 229502 113962 229502 114604 229503 113962 229503 113961 229503 113961 229504 113960 229504 114604 229504 114604 229505 113960 229505 114754 229505 114604 229506 114754 229506 116269 229506 116269 229507 114754 229507 114605 229507 116269 229508 114605 229508 114753 229508 114747 229509 114606 229509 114749 229509 114749 229510 114606 229510 116256 229510 114749 229511 116256 229511 114750 229511 114750 229512 116256 229512 114607 229512 114750 229513 114607 229513 114753 229513 114753 229514 114607 229514 116252 229514 114753 229515 116252 229515 116269 229515 116254 229516 114608 229516 116267 229516 116267 229517 114608 229517 114841 229517 116267 229518 114841 229518 11003 229518 114841 229519 114609 229519 11003 229519 11003 229520 114609 229520 114612 229520 11003 229521 114612 229521 116283 229521 114611 229522 116278 229522 114610 229522 114611 229523 114610 229523 114612 229523 114612 229524 114610 229524 116282 229524 114612 229525 116282 229525 116283 229525 114611 229526 114845 229526 114613 229526 116278 229527 114611 229527 116279 229527 116279 229528 114611 229528 114613 229528 116279 229529 114613 229529 116280 229529 114846 229530 114614 229530 114845 229530 114845 229531 114614 229531 114615 229531 114845 229532 114615 229532 114613 229532 114613 229533 114615 229533 114616 229533 114613 229534 114616 229534 116280 229534 114799 229535 116289 229535 114800 229535 114800 229536 116289 229536 116288 229536 114800 229537 116288 229537 114571 229537 114798 229538 116286 229538 114617 229538 114617 229539 116286 229539 116287 229539 114617 229540 116287 229540 116291 229540 115821 229541 118898 229541 114618 229541 114618 229542 118898 229542 118926 229542 114618 229543 118926 229543 114798 229543 114798 229544 118926 229544 118925 229544 114798 229545 118925 229545 116286 229545 114881 229546 114619 229546 114879 229546 114879 229547 114619 229547 115821 229547 114879 229548 115821 229548 114804 229548 114880 229549 114877 229549 115847 229549 115847 229550 114877 229550 114659 229550 115847 229551 114659 229551 115848 229551 114620 229552 114660 229552 114675 229552 114675 229553 114660 229553 114662 229553 114675 229554 114662 229554 114666 229554 115833 229555 115835 229555 114621 229555 114621 229556 115835 229556 114622 229556 114621 229557 114622 229557 114674 229557 115828 229558 115827 229558 114690 229558 114690 229559 115827 229559 114623 229559 114690 229560 114623 229560 114689 229560 114689 229561 114623 229561 114624 229561 114689 229562 114624 229562 114625 229562 115828 229563 114690 229563 115830 229563 115830 229564 114690 229564 114691 229564 115830 229565 114691 229565 115831 229565 115831 229566 114691 229566 114693 229566 115831 229567 114693 229567 115822 229567 118261 229568 114626 229568 114779 229568 114779 229569 114626 229569 118235 229569 118234 229570 118219 229570 114709 229570 114709 229571 118219 229571 118213 229571 114709 229572 118213 229572 118236 229572 118236 229573 118281 229573 114709 229573 114709 229574 118281 229574 114627 229574 114709 229575 114627 229575 118283 229575 114713 229576 118266 229576 114629 229576 114629 229577 118266 229577 114628 229577 114628 229578 118248 229578 114629 229578 114629 229579 118248 229579 118247 229579 114629 229580 118247 229580 114630 229580 114538 229581 114631 229581 114712 229581 114712 229582 114631 229582 118259 229582 114728 229583 114738 229583 114536 229583 114636 229584 114633 229584 114632 229584 114632 229585 114633 229585 114634 229585 114634 229586 114635 229586 114632 229586 114632 229587 114635 229587 114736 229587 114632 229588 114736 229588 114636 229588 114636 229589 114736 229589 114734 229589 114636 229590 114734 229590 119517 229590 119517 229591 114734 229591 114637 229591 114639 229592 114638 229592 114641 229592 114641 229593 119523 229593 112235 229593 114641 229594 112235 229594 114639 229594 114638 229595 114640 229595 114641 229595 114641 229596 114640 229596 114642 229596 114641 229597 114642 229597 114734 229597 114734 229598 114642 229598 114643 229598 114734 229599 114643 229599 114637 229599 114568 229600 114650 229600 119525 229600 119525 229601 114650 229601 114644 229601 119525 229602 114644 229602 114645 229602 114645 229603 114644 229603 114646 229603 114647 229604 119293 229604 114648 229604 114648 229605 119293 229605 119294 229605 114648 229606 119294 229606 114568 229606 114568 229607 119294 229607 114649 229607 114568 229608 114649 229608 114650 229608 114650 229609 114649 229609 114576 229609 114650 229610 114576 229610 114644 229610 114644 229611 114576 229611 114651 229611 114644 229612 114651 229612 114646 229612 114646 229613 114651 229613 114652 229613 114646 229614 114652 229614 114653 229614 114653 229615 114652 229615 114654 229615 114653 229616 114654 229616 114655 229616 114655 229617 114654 229617 114656 229617 114655 229618 114656 229618 114574 229618 114877 229619 114657 229619 114659 229619 114659 229620 114657 229620 114875 229620 114659 229621 114875 229621 114658 229621 114658 229622 114875 229622 114665 229622 114658 229623 114665 229623 114661 229623 115848 229624 114659 229624 114660 229624 114660 229625 114659 229625 114658 229625 114660 229626 114658 229626 114662 229626 114662 229627 114658 229627 114661 229627 114662 229628 114661 229628 114666 229628 114872 229629 114870 229629 114663 229629 114663 229630 114870 229630 114664 229630 114663 229631 114664 229631 114684 229631 114665 229632 114874 229632 114661 229632 114661 229633 114874 229633 114682 229633 114661 229634 114682 229634 114666 229634 114666 229635 114682 229635 114683 229635 114666 229636 114683 229636 114673 229636 114673 229637 114683 229637 114686 229637 114567 229638 114678 229638 114664 229638 114664 229639 114678 229639 114667 229639 114664 229640 114667 229640 114684 229640 114672 229641 114673 229641 114670 229641 114670 229642 114673 229642 114686 229642 114670 229643 114686 229643 114668 229643 114624 229644 114669 229644 114625 229644 114625 229645 114669 229645 114570 229645 114625 229646 114570 229646 114668 229646 114668 229647 114570 229647 115832 229647 114668 229648 115832 229648 114670 229648 114670 229649 115832 229649 114671 229649 114670 229650 114671 229650 114672 229650 114672 229651 114671 229651 115833 229651 114672 229652 115833 229652 114673 229652 114673 229653 115833 229653 114621 229653 114673 229654 114621 229654 114666 229654 114666 229655 114621 229655 114674 229655 114666 229656 114674 229656 114675 229656 114675 229657 114674 229657 115836 229657 114675 229658 115836 229658 114620 229658 114676 229659 114677 229659 114678 229659 114678 229660 114677 229660 114679 229660 114678 229661 114679 229661 114667 229661 114667 229662 114679 229662 114685 229662 114667 229663 114685 229663 114684 229663 114706 229664 114705 229664 114680 229664 114680 229665 114705 229665 114681 229665 114680 229666 114681 229666 114696 229666 114696 229667 114681 229667 114702 229667 114696 229668 114702 229668 114703 229668 114874 229669 114872 229669 114682 229669 114682 229670 114872 229670 114663 229670 114682 229671 114663 229671 114683 229671 114683 229672 114663 229672 114684 229672 114683 229673 114684 229673 114686 229673 114686 229674 114684 229674 114685 229674 114686 229675 114685 229675 114668 229675 114668 229676 114685 229676 114687 229676 114668 229677 114687 229677 114625 229677 114625 229678 114687 229678 114688 229678 114625 229679 114688 229679 114689 229679 114689 229680 114688 229680 114708 229680 114689 229681 114708 229681 114690 229681 114690 229682 114708 229682 114692 229682 114690 229683 114692 229683 114691 229683 114691 229684 114692 229684 114694 229684 114691 229685 114694 229685 114693 229685 114693 229686 114694 229686 114709 229686 114693 229687 114709 229687 115822 229687 115822 229688 114709 229688 118283 229688 114707 229689 114680 229689 114695 229689 114695 229690 114680 229690 114696 229690 114695 229691 114696 229691 114697 229691 114697 229692 114696 229692 114703 229692 114697 229693 114703 229693 114698 229693 114704 229694 114699 229694 114777 229694 114777 229695 114699 229695 114565 229695 114777 229696 114565 229696 114864 229696 114700 229697 114714 229697 114769 229697 119288 229698 119266 229698 114586 229698 114586 229699 119266 229699 114582 229699 114586 229700 114582 229700 114701 229700 114702 229701 114867 229701 114703 229701 114703 229702 114867 229702 114699 229702 114703 229703 114699 229703 114698 229703 114698 229704 114699 229704 114704 229704 114698 229705 114704 229705 114778 229705 114566 229706 114702 229706 114677 229706 114677 229707 114702 229707 114681 229707 114677 229708 114681 229708 114679 229708 114679 229709 114681 229709 114705 229709 114679 229710 114705 229710 114685 229710 114685 229711 114705 229711 114706 229711 114685 229712 114706 229712 114687 229712 114687 229713 114706 229713 114707 229713 114687 229714 114707 229714 114688 229714 114688 229715 114707 229715 114695 229715 114688 229716 114695 229716 114708 229716 114708 229717 114695 229717 114697 229717 114708 229718 114697 229718 114692 229718 114692 229719 114697 229719 114698 229719 114692 229720 114698 229720 114694 229720 114694 229721 114698 229721 114778 229721 114694 229722 114778 229722 114709 229722 114700 229723 114769 229723 114710 229723 114710 229724 114769 229724 114711 229724 114710 229725 114711 229725 114717 229725 114717 229726 114711 229726 114712 229726 114717 229727 114712 229727 114629 229727 114629 229728 114712 229728 118259 229728 114629 229729 118259 229729 114713 229729 114774 229730 114714 229730 114715 229730 114715 229731 114714 229731 114700 229731 114715 229732 114700 229732 114716 229732 114716 229733 114700 229733 114710 229733 114716 229734 114710 229734 114776 229734 114776 229735 114710 229735 114717 229735 114776 229736 114717 229736 114718 229736 114718 229737 114717 229737 114629 229737 114718 229738 114629 229738 114779 229738 114779 229739 114629 229739 114630 229739 114779 229740 114630 229740 118261 229740 114770 229741 114719 229741 114721 229741 114721 229742 114719 229742 114720 229742 114721 229743 114720 229743 114722 229743 114722 229744 114720 229744 114723 229744 114722 229745 114723 229745 114724 229745 114724 229746 114723 229746 114725 229746 114724 229747 114725 229747 114730 229747 114730 229748 114725 229748 114768 229748 114730 229749 114768 229749 114731 229749 114701 229750 114582 229750 114732 229750 114732 229751 114582 229751 114735 229751 114732 229752 114735 229752 114729 229752 114729 229753 114735 229753 114737 229753 114729 229754 114737 229754 114726 229754 114726 229755 114737 229755 114728 229755 114726 229756 114728 229756 114727 229756 114727 229757 114728 229757 114536 229757 114727 229758 114536 229758 114770 229758 114770 229759 114721 229759 114727 229759 114727 229760 114721 229760 114722 229760 114727 229761 114722 229761 114726 229761 114726 229762 114722 229762 114724 229762 114726 229763 114724 229763 114729 229763 114729 229764 114724 229764 114730 229764 114729 229765 114730 229765 114732 229765 114732 229766 114730 229766 114731 229766 114732 229767 114731 229767 114701 229767 114647 229768 119522 229768 114579 229768 114579 229769 119522 229769 119523 229769 114579 229770 119523 229770 114733 229770 114733 229771 119523 229771 114641 229771 114733 229772 114641 229772 114582 229772 114582 229773 114641 229773 114734 229773 114582 229774 114734 229774 114735 229774 114735 229775 114734 229775 114736 229775 114735 229776 114736 229776 114737 229776 114737 229777 114736 229777 114569 229777 114737 229778 114569 229778 114728 229778 114728 229779 114569 229779 114534 229779 114728 229780 114534 229780 114738 229780 114790 229781 114858 229781 114788 229781 114788 229782 114858 229782 114860 229782 114788 229783 114860 229783 114786 229783 114865 229784 114836 229784 114863 229784 114863 229785 114836 229785 114739 229785 114863 229786 114739 229786 114861 229786 114861 229787 114739 229787 114835 229787 114775 229788 114741 229788 114740 229788 114740 229789 114741 229789 114564 229789 114740 229790 114564 229790 114773 229790 114773 229791 114564 229791 114742 229791 114773 229792 114742 229792 114859 229792 114862 229793 114564 229793 114743 229793 114743 229794 114564 229794 114741 229794 114743 229795 114741 229795 114864 229795 114864 229796 114741 229796 114775 229796 114864 229797 114775 229797 114777 229797 114755 229798 114754 229798 114744 229798 114744 229799 114754 229799 113964 229799 114744 229800 113964 229800 114597 229800 114763 229801 114755 229801 114745 229801 114745 229802 114755 229802 114744 229802 114745 229803 114744 229803 114603 229803 114603 229804 114744 229804 114746 229804 114603 229805 114746 229805 114599 229805 114780 229806 114747 229806 114748 229806 114748 229807 114747 229807 114749 229807 114748 229808 114749 229808 114782 229808 114782 229809 114749 229809 114750 229809 114782 229810 114750 229810 114751 229810 114751 229811 114750 229811 114753 229811 114751 229812 114753 229812 114752 229812 114752 229813 114753 229813 114605 229813 114752 229814 114605 229814 114785 229814 114785 229815 114605 229815 114754 229815 114785 229816 114754 229816 114787 229816 114787 229817 114754 229817 114755 229817 114787 229818 114755 229818 114789 229818 114789 229819 114755 229819 114763 229819 114789 229820 114763 229820 114764 229820 119282 229821 114762 229821 114756 229821 114756 229822 114762 229822 114757 229822 114756 229823 114757 229823 114589 229823 114589 229824 114757 229824 114761 229824 114589 229825 114761 229825 114758 229825 114758 229826 114761 229826 114596 229826 114758 229827 114596 229827 114759 229827 114759 229828 114596 229828 114594 229828 114759 229829 114594 229829 116238 229829 114760 229830 114596 229830 113970 229830 113970 229831 114596 229831 114761 229831 113970 229832 114761 229832 114603 229832 114603 229833 114761 229833 114757 229833 114603 229834 114757 229834 114745 229834 114745 229835 114757 229835 114762 229835 114745 229836 114762 229836 114763 229836 114763 229837 114762 229837 114855 229837 114763 229838 114855 229838 114764 229838 114765 229839 114586 229839 114766 229839 114766 229840 114586 229840 114701 229840 114766 229841 114701 229841 114767 229841 114767 229842 114701 229842 114731 229842 114767 229843 114731 229843 114772 229843 114772 229844 114731 229844 114768 229844 114772 229845 114768 229845 114774 229845 114774 229846 114768 229846 114725 229846 114774 229847 114725 229847 114714 229847 114714 229848 114725 229848 114723 229848 114714 229849 114723 229849 114769 229849 114769 229850 114723 229850 114720 229850 114769 229851 114720 229851 114711 229851 114711 229852 114720 229852 114719 229852 114711 229853 114719 229853 114712 229853 114712 229854 114719 229854 114770 229854 114712 229855 114770 229855 114538 229855 114573 229856 114771 229856 114587 229856 114587 229857 114771 229857 114765 229857 114587 229858 114765 229858 114856 229858 114856 229859 114765 229859 114766 229859 114856 229860 114766 229860 114857 229860 114857 229861 114766 229861 114767 229861 114857 229862 114767 229862 114859 229862 114859 229863 114767 229863 114772 229863 114859 229864 114772 229864 114773 229864 114773 229865 114772 229865 114774 229865 114773 229866 114774 229866 114740 229866 114740 229867 114774 229867 114715 229867 114740 229868 114715 229868 114775 229868 114775 229869 114715 229869 114716 229869 114775 229870 114716 229870 114777 229870 114777 229871 114716 229871 114776 229871 114777 229872 114776 229872 114704 229872 114704 229873 114776 229873 114718 229873 114704 229874 114718 229874 114778 229874 114778 229875 114718 229875 114779 229875 114778 229876 114779 229876 114709 229876 114709 229877 114779 229877 118235 229877 114709 229878 118235 229878 118234 229878 116254 229879 114780 229879 114608 229879 114608 229880 114780 229880 114748 229880 114608 229881 114748 229881 114781 229881 114781 229882 114748 229882 114782 229882 114781 229883 114782 229883 114783 229883 114783 229884 114782 229884 114751 229884 114783 229885 114751 229885 114784 229885 114784 229886 114751 229886 114752 229886 114784 229887 114752 229887 114837 229887 114837 229888 114752 229888 114785 229888 114837 229889 114785 229889 114786 229889 114786 229890 114785 229890 114787 229890 114786 229891 114787 229891 114788 229891 114788 229892 114787 229892 114789 229892 114788 229893 114789 229893 114790 229893 114790 229894 114789 229894 114764 229894 114850 229895 114849 229895 114791 229895 114791 229896 114849 229896 114847 229896 114791 229897 114847 229897 114811 229897 114811 229898 114847 229898 114792 229898 114811 229899 114792 229899 114812 229899 114812 229900 114792 229900 114844 229900 114812 229901 114844 229901 114793 229901 114793 229902 114844 229902 114843 229902 114793 229903 114843 229903 114794 229903 114794 229904 114843 229904 114842 229904 114794 229905 114842 229905 114796 229905 114796 229906 114842 229906 114795 229906 114796 229907 114795 229907 114814 229907 114814 229908 114795 229908 114797 229908 114814 229909 114797 229909 114815 229909 114815 229910 114797 229910 114840 229910 114815 229911 114840 229911 114839 229911 115821 229912 114618 229912 114804 229912 114804 229913 114618 229913 114798 229913 114804 229914 114798 229914 114803 229914 114803 229915 114798 229915 114617 229915 114803 229916 114617 229916 114799 229916 114799 229917 114617 229917 116291 229917 114799 229918 116291 229918 116289 229918 114571 229919 114806 229919 114800 229919 114800 229920 114806 229920 114801 229920 114800 229921 114801 229921 114799 229921 114799 229922 114801 229922 114807 229922 114799 229923 114807 229923 114803 229923 114803 229924 114807 229924 114802 229924 114803 229925 114802 229925 114804 229925 114804 229926 114802 229926 114878 229926 114804 229927 114878 229927 114879 229927 116275 229928 114846 229928 116273 229928 116273 229929 114846 229929 114848 229929 116273 229930 114848 229930 116271 229930 116271 229931 114848 229931 114805 229931 116271 229932 114805 229932 114806 229932 114806 229933 114805 229933 114851 229933 114806 229934 114851 229934 114801 229934 114801 229935 114851 229935 114852 229935 114801 229936 114852 229936 114807 229936 114807 229937 114852 229937 114808 229937 114807 229938 114808 229938 114802 229938 114802 229939 114808 229939 114876 229939 114802 229940 114876 229940 114878 229940 114825 229941 114850 229941 114809 229941 114809 229942 114850 229942 114791 229942 114809 229943 114791 229943 114810 229943 114810 229944 114791 229944 114811 229944 114810 229945 114811 229945 114826 229945 114826 229946 114811 229946 114812 229946 114826 229947 114812 229947 114827 229947 114827 229948 114812 229948 114793 229948 114827 229949 114793 229949 114829 229949 114829 229950 114793 229950 114794 229950 114829 229951 114794 229951 114830 229951 114830 229952 114794 229952 114796 229952 114830 229953 114796 229953 114813 229953 114813 229954 114796 229954 114814 229954 114813 229955 114814 229955 114833 229955 114833 229956 114814 229956 114815 229956 114833 229957 114815 229957 114834 229957 114834 229958 114815 229958 114839 229958 114834 229959 114839 229959 114838 229959 114832 229960 114868 229960 114831 229960 114831 229961 114868 229961 114869 229961 114831 229962 114869 229962 114816 229962 114816 229963 114869 229963 114817 229963 114816 229964 114817 229964 114828 229964 114828 229965 114817 229965 114818 229965 114828 229966 114818 229966 114819 229966 114819 229967 114818 229967 114871 229967 114819 229968 114871 229968 114820 229968 114820 229969 114871 229969 114821 229969 114820 229970 114821 229970 114822 229970 114822 229971 114821 229971 114873 229971 114822 229972 114873 229972 114823 229972 114823 229973 114873 229973 114853 229973 114823 229974 114853 229974 114824 229974 114824 229975 114825 229975 114823 229975 114823 229976 114825 229976 114809 229976 114823 229977 114809 229977 114822 229977 114822 229978 114809 229978 114810 229978 114822 229979 114810 229979 114820 229979 114820 229980 114810 229980 114826 229980 114820 229981 114826 229981 114819 229981 114819 229982 114826 229982 114827 229982 114819 229983 114827 229983 114828 229983 114828 229984 114827 229984 114829 229984 114828 229985 114829 229985 114816 229985 114816 229986 114829 229986 114830 229986 114816 229987 114830 229987 114831 229987 114831 229988 114830 229988 114813 229988 114831 229989 114813 229989 114832 229989 114832 229990 114813 229990 114833 229990 114832 229991 114833 229991 114866 229991 114866 229992 114833 229992 114834 229992 114866 229993 114834 229993 114865 229993 114865 229994 114834 229994 114838 229994 114865 229995 114838 229995 114836 229995 114860 229996 114835 229996 114786 229996 114786 229997 114835 229997 114739 229997 114786 229998 114739 229998 114837 229998 114837 229999 114739 229999 114836 229999 114837 230000 114836 230000 114784 230000 114784 230001 114836 230001 114838 230001 114784 230002 114838 230002 114783 230002 114783 230003 114838 230003 114839 230003 114783 230004 114839 230004 114781 230004 114781 230005 114839 230005 114840 230005 114781 230006 114840 230006 114608 230006 114608 230007 114840 230007 114797 230007 114608 230008 114797 230008 114841 230008 114841 230009 114797 230009 114795 230009 114841 230010 114795 230010 114609 230010 114609 230011 114795 230011 114842 230011 114609 230012 114842 230012 114612 230012 114612 230013 114842 230013 114843 230013 114612 230014 114843 230014 114611 230014 114611 230015 114843 230015 114844 230015 114611 230016 114844 230016 114845 230016 114845 230017 114844 230017 114792 230017 114845 230018 114792 230018 114846 230018 114846 230019 114792 230019 114847 230019 114846 230020 114847 230020 114848 230020 114848 230021 114847 230021 114849 230021 114848 230022 114849 230022 114805 230022 114805 230023 114849 230023 114850 230023 114805 230024 114850 230024 114851 230024 114851 230025 114850 230025 114825 230025 114851 230026 114825 230026 114852 230026 114852 230027 114825 230027 114824 230027 114852 230028 114824 230028 114808 230028 114808 230029 114824 230029 114853 230029 114808 230030 114853 230030 114876 230030 119282 230031 114854 230031 114855 230031 114855 230032 114854 230032 114587 230032 114855 230033 114587 230033 114764 230033 114764 230034 114587 230034 114856 230034 114764 230035 114856 230035 114790 230035 114790 230036 114856 230036 114857 230036 114790 230037 114857 230037 114858 230037 114858 230038 114857 230038 114859 230038 114858 230039 114859 230039 114860 230039 114860 230040 114859 230040 114742 230040 114860 230041 114742 230041 114835 230041 114835 230042 114742 230042 114862 230042 114835 230043 114862 230043 114861 230043 114861 230044 114862 230044 114743 230044 114861 230045 114743 230045 114863 230045 114863 230046 114743 230046 114864 230046 114863 230047 114864 230047 114865 230047 114865 230048 114864 230048 114565 230048 114865 230049 114565 230049 114866 230049 114866 230050 114565 230050 114867 230050 114866 230051 114867 230051 114868 230051 114868 230052 114867 230052 114566 230052 114868 230053 114566 230053 114869 230053 114869 230054 114566 230054 114676 230054 114869 230055 114676 230055 114817 230055 114817 230056 114676 230056 114567 230056 114817 230057 114567 230057 114818 230057 114818 230058 114567 230058 114870 230058 114818 230059 114870 230059 114871 230059 114871 230060 114870 230060 114872 230060 114871 230061 114872 230061 114821 230061 114821 230062 114872 230062 114874 230062 114821 230063 114874 230063 114873 230063 114873 230064 114874 230064 114665 230064 114873 230065 114665 230065 114853 230065 114853 230066 114665 230066 114875 230066 114853 230067 114875 230067 114876 230067 114876 230068 114875 230068 114657 230068 114876 230069 114657 230069 114878 230069 114878 230070 114657 230070 114877 230070 114878 230071 114877 230071 114879 230071 114879 230072 114877 230072 114880 230072 114879 230073 114880 230073 114881 230073 114973 230074 119027 230074 117003 230074 117003 230075 119027 230075 119078 230075 117003 230076 119078 230076 114882 230076 114882 230077 119079 230077 117003 230077 117003 230078 119079 230078 114883 230078 117003 230079 114883 230079 117062 230079 117062 230080 114883 230080 114884 230080 117062 230081 114884 230081 114887 230081 114884 230082 114885 230082 114887 230082 114887 230083 114885 230083 114886 230083 114887 230084 114886 230084 114888 230084 114888 230085 114886 230085 119081 230085 114888 230086 119081 230086 114889 230086 119081 230087 119076 230087 114889 230087 114889 230088 119076 230088 114914 230088 114889 230089 114914 230089 114913 230089 114913 230090 114977 230090 114889 230090 114889 230091 114977 230091 114890 230091 114889 230092 114890 230092 117065 230092 117065 230093 114890 230093 114891 230093 117065 230094 114891 230094 114892 230094 114891 230095 114893 230095 114892 230095 114892 230096 114893 230096 114894 230096 114892 230097 114894 230097 114895 230097 114895 230098 114894 230098 114896 230098 114895 230099 114896 230099 114897 230099 114897 230100 114896 230100 114979 230100 114897 230101 114979 230101 114898 230101 114898 230102 114979 230102 114899 230102 114898 230103 114899 230103 114900 230103 114900 230104 114899 230104 114901 230104 114900 230105 114901 230105 114902 230105 114902 230106 114901 230106 114921 230106 114902 230107 114921 230107 114903 230107 114921 230108 114922 230108 114903 230108 114903 230109 114922 230109 114924 230109 114903 230110 114924 230110 114904 230110 114904 230111 114924 230111 114905 230111 114904 230112 114905 230112 117132 230112 117132 230113 114905 230113 114906 230113 117132 230114 114906 230114 117194 230114 114906 230115 115085 230115 117194 230115 117194 230116 115085 230116 114907 230116 117194 230117 114907 230117 114908 230117 114908 230118 114907 230118 114919 230118 114908 230119 114919 230119 117192 230119 117192 230120 114919 230120 114918 230120 117192 230121 114918 230121 117191 230121 117191 230122 114918 230122 116033 230122 117191 230123 116033 230123 116032 230123 114909 230124 114910 230124 115222 230124 115083 230125 114923 230125 114920 230125 114911 230126 115081 230126 115103 230126 115097 230127 114912 230127 115123 230127 115123 230128 114912 230128 115070 230128 115154 230129 115156 230129 115033 230129 115057 230130 115257 230130 115260 230130 115019 230131 115262 230131 115263 230131 115061 230132 115012 230132 115011 230132 114890 230133 114977 230133 115072 230133 114913 230134 114914 230134 119020 230134 115103 230135 115081 230135 119020 230135 119023 230136 119024 230136 115098 230136 115181 230137 114915 230137 115237 230137 116069 230138 114916 230138 114958 230138 114956 230139 115272 230139 115273 230139 114991 230140 115271 230140 115272 230140 118187 230141 115969 230141 115968 230141 114917 230142 115037 230142 115036 230142 114918 230143 114919 230143 115129 230143 115085 230144 114906 230144 115087 230144 114901 230145 114920 230145 114921 230145 114921 230146 114920 230146 114923 230146 114921 230147 114923 230147 114922 230147 114922 230148 114923 230148 114924 230148 115982 230149 115139 230149 114925 230149 114925 230150 115139 230150 115152 230150 114925 230151 115152 230151 115150 230151 114917 230152 115036 230152 115043 230152 115064 230153 114926 230153 114928 230153 114928 230154 114926 230154 114927 230154 114928 230155 114927 230155 115976 230155 115975 230156 115042 230156 115976 230156 115976 230157 115042 230157 115045 230157 115976 230158 115045 230158 114928 230158 114928 230159 115045 230159 115046 230159 114928 230160 115046 230160 115064 230160 114929 230161 115065 230161 115972 230161 115972 230162 115065 230162 115971 230162 115971 230163 115065 230163 114930 230163 114930 230164 115065 230164 115066 230164 114930 230165 115066 230165 114931 230165 114931 230166 115066 230166 115068 230166 114931 230167 115068 230167 115968 230167 115968 230168 115068 230168 115251 230168 115968 230169 115251 230169 118187 230169 114932 230170 118155 230170 114933 230170 118176 230171 115252 230171 118175 230171 118175 230172 115252 230172 114933 230172 118176 230173 114934 230173 115252 230173 115252 230174 114934 230174 114935 230174 115252 230175 114935 230175 118177 230175 114940 230176 114936 230176 114938 230176 114938 230177 114936 230177 114937 230177 114937 230178 118151 230178 114938 230178 114938 230179 118151 230179 114939 230179 114938 230180 114939 230180 114932 230180 114932 230181 114939 230181 118156 230181 114932 230182 118156 230182 118155 230182 114940 230183 114938 230183 118135 230183 118135 230184 114938 230184 115059 230184 118135 230185 115059 230185 114941 230185 114941 230186 115059 230186 114942 230186 114942 230187 115059 230187 114945 230187 114942 230188 114945 230188 114946 230188 115395 230189 115393 230189 114943 230189 115393 230190 115392 230190 114943 230190 114943 230191 115392 230191 114944 230191 114943 230192 114944 230192 114945 230192 114945 230193 114944 230193 115400 230193 114945 230194 115400 230194 114946 230194 114947 230195 115004 230195 115403 230195 115403 230196 115004 230196 115404 230196 114948 230197 114950 230197 114949 230197 114949 230198 114950 230198 115365 230198 114949 230199 115365 230199 115003 230199 115003 230200 115365 230200 115406 230200 115003 230201 115406 230201 115405 230201 115377 230202 115376 230202 114996 230202 114951 230203 114952 230203 115378 230203 114955 230204 114953 230204 114986 230204 114986 230205 114953 230205 114954 230205 114989 230206 115373 230206 114955 230206 114955 230207 115373 230207 115374 230207 114955 230208 115374 230208 114953 230208 118063 230209 115362 230209 114956 230209 114956 230210 115273 230210 118063 230210 118063 230211 115273 230211 114957 230211 118063 230212 114957 230212 118061 230212 118061 230213 114957 230213 118059 230213 118059 230214 114957 230214 115274 230214 118059 230215 115274 230215 118058 230215 116069 230216 114958 230216 115225 230216 115224 230217 115226 230217 114959 230217 114959 230218 115226 230218 114960 230218 114959 230219 114960 230219 116073 230219 116073 230220 114960 230220 114961 230220 114960 230221 114962 230221 114961 230221 114961 230222 114962 230222 115228 230222 114961 230223 115228 230223 116074 230223 116074 230224 115228 230224 114963 230224 116074 230225 114963 230225 115171 230225 115169 230226 116078 230226 115170 230226 115170 230227 116078 230227 116077 230227 115170 230228 116077 230228 114964 230228 114964 230229 116077 230229 116076 230229 116081 230230 116080 230230 114965 230230 114965 230231 116080 230231 115175 230231 116081 230232 114965 230232 114966 230232 114966 230233 114965 230233 114967 230233 114966 230234 114967 230234 114968 230234 114970 230235 116103 230235 114967 230235 114967 230236 116103 230236 116083 230236 114967 230237 116083 230237 114968 230237 116084 230238 114969 230238 116089 230238 116089 230239 114969 230239 116088 230239 115237 230240 116088 230240 115181 230240 115181 230241 116088 230241 114969 230241 115181 230242 114969 230242 114970 230242 114970 230243 114969 230243 116084 230243 114970 230244 116084 230244 116103 230244 116085 230245 114971 230245 115125 230245 115125 230246 114971 230246 116087 230246 115125 230247 116087 230247 114972 230247 119027 230248 114973 230248 119028 230248 119028 230249 114973 230249 115075 230249 115098 230250 119024 230250 115074 230250 119024 230251 119025 230251 115074 230251 115074 230252 119025 230252 114974 230252 115074 230253 114974 230253 115075 230253 115075 230254 114974 230254 119060 230254 115075 230255 119060 230255 119028 230255 115102 230256 119018 230256 114976 230256 114976 230257 119018 230257 114975 230257 114976 230258 114975 230258 119023 230258 114913 230259 119020 230259 114977 230259 114890 230260 115072 230260 114891 230260 114894 230261 114893 230261 114978 230261 114978 230262 114893 230262 114891 230262 115147 230263 114979 230263 114896 230263 114979 230264 115147 230264 114899 230264 114899 230265 115147 230265 115146 230265 114899 230266 115146 230266 114901 230266 114980 230267 114990 230267 114981 230267 114981 230268 114990 230268 114988 230268 114981 230269 114988 230269 114982 230269 114982 230270 114988 230270 114987 230270 115017 230271 114984 230271 114983 230271 114983 230272 114984 230272 115267 230272 114983 230273 115267 230273 114987 230273 114987 230274 115267 230274 114985 230274 114987 230275 114985 230275 114982 230275 114993 230276 115017 230276 114994 230276 114994 230277 115017 230277 114983 230277 114994 230278 114983 230278 114986 230278 114986 230279 114983 230279 114987 230279 114986 230280 114987 230280 114955 230280 114955 230281 114987 230281 114988 230281 114955 230282 114988 230282 114989 230282 114989 230283 114988 230283 114990 230283 114989 230284 114990 230284 114991 230284 114991 230285 114990 230285 114980 230285 114991 230286 114980 230286 115271 230286 114992 230287 114993 230287 114995 230287 114995 230288 114993 230288 114994 230288 114995 230289 114994 230289 114997 230289 114997 230290 114994 230290 114986 230290 114997 230291 114986 230291 114951 230291 114951 230292 114986 230292 114954 230292 114951 230293 114954 230293 114952 230293 115002 230294 114992 230294 115001 230294 115001 230295 114992 230295 114995 230295 115001 230296 114995 230296 115000 230296 115000 230297 114995 230297 114997 230297 115000 230298 114997 230298 114996 230298 114996 230299 114997 230299 114951 230299 114996 230300 114951 230300 115377 230300 115377 230301 114951 230301 115378 230301 115376 230302 114998 230302 114996 230302 114996 230303 114998 230303 115368 230303 114996 230304 115368 230304 115000 230304 115000 230305 115368 230305 114999 230305 115000 230306 114999 230306 115001 230306 115001 230307 114999 230307 114948 230307 115001 230308 114948 230308 115002 230308 115002 230309 114948 230309 114949 230309 115002 230310 114949 230310 115015 230310 115015 230311 114949 230311 115003 230311 115015 230312 115003 230312 115004 230312 115004 230313 115003 230313 115405 230313 115004 230314 115405 230314 115404 230314 115012 230315 115061 230315 115005 230315 115005 230316 115061 230316 115006 230316 115005 230317 115006 230317 115007 230317 115262 230318 115019 230318 115008 230318 115008 230319 115019 230319 115021 230319 115008 230320 115021 230320 115056 230320 115009 230321 115257 230321 115010 230321 115010 230322 115257 230322 115057 230322 115010 230323 115057 230323 115055 230323 115018 230324 115011 230324 115013 230324 115013 230325 115011 230325 115012 230325 115013 230326 115012 230326 115020 230326 115020 230327 115012 230327 115005 230327 115020 230328 115005 230328 115022 230328 115022 230329 115005 230329 115007 230329 115022 230330 115007 230330 115024 230330 115403 230331 115395 230331 114947 230331 114947 230332 115395 230332 114943 230332 114947 230333 114943 230333 115004 230333 115004 230334 114943 230334 115014 230334 115004 230335 115014 230335 115015 230335 115015 230336 115014 230336 115060 230336 115015 230337 115060 230337 115002 230337 115002 230338 115060 230338 115062 230338 115002 230339 115062 230339 114992 230339 114992 230340 115062 230340 115016 230340 114992 230341 115016 230341 114993 230341 114993 230342 115016 230342 115063 230342 114993 230343 115063 230343 115017 230343 115017 230344 115063 230344 115266 230344 115017 230345 115266 230345 114984 230345 115265 230346 115018 230346 115263 230346 115263 230347 115018 230347 115013 230347 115263 230348 115013 230348 115019 230348 115019 230349 115013 230349 115020 230349 115019 230350 115020 230350 115021 230350 115021 230351 115020 230351 115022 230351 115021 230352 115022 230352 115056 230352 115056 230353 115022 230353 115024 230353 115056 230354 115024 230354 115023 230354 115023 230355 115024 230355 115025 230355 115023 230356 115025 230356 115053 230356 115040 230357 115031 230357 115048 230357 115048 230358 115031 230358 115026 230358 115048 230359 115026 230359 115049 230359 115049 230360 115026 230360 115029 230360 115049 230361 115029 230361 115050 230361 115050 230362 115029 230362 115027 230362 115050 230363 115027 230363 115051 230363 115051 230364 115027 230364 115028 230364 115164 230365 115028 230365 115162 230365 115162 230366 115028 230366 115027 230366 115162 230367 115027 230367 115160 230367 115160 230368 115027 230368 115029 230368 115160 230369 115029 230369 115158 230369 115158 230370 115029 230370 115026 230370 115158 230371 115026 230371 115030 230371 115030 230372 115026 230372 115031 230372 115030 230373 115031 230373 115156 230373 115149 230374 115151 230374 115038 230374 115038 230375 115151 230375 115153 230375 115038 230376 115153 230376 115032 230376 115032 230377 115153 230377 115039 230377 115154 230378 115033 230378 115034 230378 115034 230379 115033 230379 115035 230379 115034 230380 115035 230380 115036 230380 114917 230381 115977 230381 115037 230381 115037 230382 115977 230382 115038 230382 115037 230383 115038 230383 115036 230383 115036 230384 115038 230384 115032 230384 115036 230385 115032 230385 115034 230385 115034 230386 115032 230386 115039 230386 115034 230387 115039 230387 115154 230387 115156 230388 115031 230388 115033 230388 115033 230389 115031 230389 115040 230389 115033 230390 115040 230390 115035 230390 115035 230391 115040 230391 115044 230391 115035 230392 115044 230392 115036 230392 115036 230393 115044 230393 115041 230393 115036 230394 115041 230394 115043 230394 115975 230395 115043 230395 115042 230395 115042 230396 115043 230396 115041 230396 115042 230397 115041 230397 115045 230397 115045 230398 115041 230398 115044 230398 115045 230399 115044 230399 115046 230399 115046 230400 115044 230400 115040 230400 115046 230401 115040 230401 115047 230401 115047 230402 115040 230402 115048 230402 115047 230403 115048 230403 115067 230403 115067 230404 115048 230404 115049 230404 115067 230405 115049 230405 115069 230405 115069 230406 115049 230406 115050 230406 115069 230407 115050 230407 115249 230407 115249 230408 115050 230408 115051 230408 115249 230409 115051 230409 115052 230409 115052 230410 115051 230410 115028 230410 115052 230411 115028 230411 115247 230411 115247 230412 115028 230412 115164 230412 115247 230413 115164 230413 115246 230413 115252 230414 115253 230414 115058 230414 115058 230415 115253 230415 115254 230415 115058 230416 115254 230416 115053 230416 115053 230417 115254 230417 115054 230417 115053 230418 115054 230418 115023 230418 115023 230419 115054 230419 115055 230419 115023 230420 115055 230420 115056 230420 115056 230421 115055 230421 115057 230421 115056 230422 115057 230422 115008 230422 115008 230423 115057 230423 115260 230423 115008 230424 115260 230424 115262 230424 114933 230425 115252 230425 114932 230425 114932 230426 115252 230426 115058 230426 114932 230427 115058 230427 114938 230427 114938 230428 115058 230428 115053 230428 114938 230429 115053 230429 115059 230429 115059 230430 115053 230430 115025 230430 115059 230431 115025 230431 114945 230431 114945 230432 115025 230432 115024 230432 114945 230433 115024 230433 114943 230433 114943 230434 115024 230434 115007 230434 114943 230435 115007 230435 115014 230435 115014 230436 115007 230436 115006 230436 115014 230437 115006 230437 115060 230437 115060 230438 115006 230438 115061 230438 115060 230439 115061 230439 115062 230439 115062 230440 115061 230440 115011 230440 115062 230441 115011 230441 115016 230441 115016 230442 115011 230442 115018 230442 115016 230443 115018 230443 115063 230443 115063 230444 115018 230444 115265 230444 115063 230445 115265 230445 115266 230445 115972 230446 115064 230446 114929 230446 114929 230447 115064 230447 115046 230447 114929 230448 115046 230448 115065 230448 115065 230449 115046 230449 115047 230449 115065 230450 115047 230450 115066 230450 115066 230451 115047 230451 115067 230451 115066 230452 115067 230452 115068 230452 115068 230453 115067 230453 115069 230453 115068 230454 115069 230454 115251 230454 115251 230455 115069 230455 115249 230455 115124 230456 115070 230456 115078 230456 115078 230457 115070 230457 114912 230457 115078 230458 114912 230458 115071 230458 115071 230459 114912 230459 115097 230459 114891 230460 115072 230460 114978 230460 114978 230461 115072 230461 115082 230461 114978 230462 115082 230462 114894 230462 115076 230463 115099 230463 115077 230463 115077 230464 115099 230464 115098 230464 115077 230465 115098 230465 115079 230465 115079 230466 115098 230466 115074 230466 115079 230467 115074 230467 115073 230467 115073 230468 115074 230468 115075 230468 115073 230469 115075 230469 115080 230469 115080 230470 115075 230470 114973 230470 115101 230471 115076 230471 115095 230471 115095 230472 115076 230472 115077 230472 115095 230473 115077 230473 115071 230473 115071 230474 115077 230474 115079 230474 115071 230475 115079 230475 115078 230475 115078 230476 115079 230476 115073 230476 115078 230477 115073 230477 115124 230477 115124 230478 115073 230478 115080 230478 114977 230479 119020 230479 115072 230479 115072 230480 119020 230480 115081 230480 115072 230481 115081 230481 115082 230481 115082 230482 115081 230482 114911 230482 115082 230483 114911 230483 115104 230483 114901 230484 115146 230484 114920 230484 114920 230485 115146 230485 115145 230485 114920 230486 115145 230486 115083 230486 114906 230487 114905 230487 115087 230487 115087 230488 114905 230488 114924 230488 115087 230489 114924 230489 115089 230489 115089 230490 114924 230490 114923 230490 115089 230491 114923 230491 115091 230491 115091 230492 114923 230492 115083 230492 115091 230493 115083 230493 115092 230493 115092 230494 115083 230494 115145 230494 115092 230495 115145 230495 115084 230495 114919 230496 114907 230496 115129 230496 115129 230497 114907 230497 115085 230497 115129 230498 115085 230498 115086 230498 115086 230499 115085 230499 115087 230499 115086 230500 115087 230500 115088 230500 115088 230501 115087 230501 115089 230501 115088 230502 115089 230502 115127 230502 115127 230503 115089 230503 115091 230503 115127 230504 115091 230504 115090 230504 115090 230505 115091 230505 115092 230505 115090 230506 115092 230506 115093 230506 115093 230507 115092 230507 115084 230507 115121 230508 115101 230508 115094 230508 115094 230509 115101 230509 115095 230509 115094 230510 115095 230510 115096 230510 115096 230511 115095 230511 115071 230511 115096 230512 115071 230512 115122 230512 115122 230513 115071 230513 115097 230513 119023 230514 115098 230514 114976 230514 114976 230515 115098 230515 115099 230515 114976 230516 115099 230516 115105 230516 115105 230517 115099 230517 115076 230517 115105 230518 115076 230518 115100 230518 115100 230519 115076 230519 115101 230519 115100 230520 115101 230520 115107 230520 115107 230521 115101 230521 115121 230521 115107 230522 115121 230522 115120 230522 119020 230523 115102 230523 115103 230523 115103 230524 115102 230524 114976 230524 115103 230525 114976 230525 114911 230525 114911 230526 114976 230526 115105 230526 114911 230527 115105 230527 115104 230527 115104 230528 115105 230528 115100 230528 115104 230529 115100 230529 115106 230529 115106 230530 115100 230530 115107 230530 115106 230531 115107 230531 115108 230531 115108 230532 115107 230532 115120 230532 115108 230533 115120 230533 115144 230533 115157 230534 115109 230534 115110 230534 115110 230535 115109 230535 115119 230535 115110 230536 115119 230536 115159 230536 115159 230537 115119 230537 115111 230537 115159 230538 115111 230538 115161 230538 115161 230539 115111 230539 115112 230539 115161 230540 115112 230540 115163 230540 115163 230541 115112 230541 115113 230541 115163 230542 115113 230542 115115 230542 115115 230543 115113 230543 115114 230543 115115 230544 115114 230544 115165 230544 115165 230545 115114 230545 115116 230545 115165 230546 115116 230546 115166 230546 115166 230547 115116 230547 115117 230547 115166 230548 115117 230548 115118 230548 115118 230549 115117 230549 114972 230549 115118 230550 114972 230550 115167 230550 115167 230551 114972 230551 116087 230551 115109 230552 115144 230552 115119 230552 115119 230553 115144 230553 115120 230553 115119 230554 115120 230554 115111 230554 115111 230555 115120 230555 115121 230555 115111 230556 115121 230556 115112 230556 115112 230557 115121 230557 115094 230557 115112 230558 115094 230558 115113 230558 115113 230559 115094 230559 115096 230559 115113 230560 115096 230560 115114 230560 115114 230561 115096 230561 115122 230561 115114 230562 115122 230562 115116 230562 115116 230563 115122 230563 115097 230563 115116 230564 115097 230564 115117 230564 115117 230565 115097 230565 115123 230565 115117 230566 115123 230566 114972 230566 114972 230567 115123 230567 115070 230567 114972 230568 115070 230568 115125 230568 115125 230569 115070 230569 115124 230569 115125 230570 115124 230570 116085 230570 116085 230571 115124 230571 115080 230571 115093 230572 115126 230572 115090 230572 115090 230573 115126 230573 115131 230573 115090 230574 115131 230574 115127 230574 115127 230575 115131 230575 115134 230575 115127 230576 115134 230576 115088 230576 115088 230577 115134 230577 115135 230577 115088 230578 115135 230578 115086 230578 115086 230579 115135 230579 115128 230579 115086 230580 115128 230580 115129 230580 115129 230581 115128 230581 115130 230581 115129 230582 115130 230582 114918 230582 114918 230583 115130 230583 115138 230583 114918 230584 115138 230584 116033 230584 115126 230585 115143 230585 115131 230585 115131 230586 115143 230586 115132 230586 115131 230587 115132 230587 115134 230587 115134 230588 115132 230588 115133 230588 115134 230589 115133 230589 115135 230589 115135 230590 115133 230590 115136 230590 115135 230591 115136 230591 115128 230591 115128 230592 115136 230592 115141 230592 115128 230593 115141 230593 115130 230593 115130 230594 115141 230594 115137 230594 115130 230595 115137 230595 115138 230595 115138 230596 115137 230596 115981 230596 115138 230597 115981 230597 116033 230597 115982 230598 115981 230598 115139 230598 115139 230599 115981 230599 115137 230599 115139 230600 115137 230600 115152 230600 115152 230601 115137 230601 115141 230601 115152 230602 115141 230602 115140 230602 115140 230603 115141 230603 115136 230603 115140 230604 115136 230604 115142 230604 115142 230605 115136 230605 115133 230605 115142 230606 115133 230606 115155 230606 115155 230607 115133 230607 115132 230607 115155 230608 115132 230608 115157 230608 115157 230609 115132 230609 115143 230609 115157 230610 115143 230610 115109 230610 115109 230611 115143 230611 115126 230611 115109 230612 115126 230612 115144 230612 115144 230613 115126 230613 115093 230613 115144 230614 115093 230614 115108 230614 115108 230615 115093 230615 115084 230615 115108 230616 115084 230616 115106 230616 115106 230617 115084 230617 115145 230617 115106 230618 115145 230618 115104 230618 115104 230619 115145 230619 115146 230619 115104 230620 115146 230620 115082 230620 115082 230621 115146 230621 115147 230621 115082 230622 115147 230622 114894 230622 114894 230623 115147 230623 114896 230623 115977 230624 115148 230624 115038 230624 115038 230625 115148 230625 115979 230625 115038 230626 115979 230626 115149 230626 115149 230627 115979 230627 115150 230627 115149 230628 115150 230628 115151 230628 115151 230629 115150 230629 115152 230629 115151 230630 115152 230630 115153 230630 115153 230631 115152 230631 115140 230631 115153 230632 115140 230632 115039 230632 115039 230633 115140 230633 115142 230633 115039 230634 115142 230634 115154 230634 115154 230635 115142 230635 115155 230635 115154 230636 115155 230636 115156 230636 115156 230637 115155 230637 115157 230637 115156 230638 115157 230638 115030 230638 115030 230639 115157 230639 115110 230639 115030 230640 115110 230640 115158 230640 115158 230641 115110 230641 115159 230641 115158 230642 115159 230642 115160 230642 115160 230643 115159 230643 115161 230643 115160 230644 115161 230644 115162 230644 115162 230645 115161 230645 115163 230645 115162 230646 115163 230646 115164 230646 115164 230647 115163 230647 115115 230647 115164 230648 115115 230648 115246 230648 115246 230649 115115 230649 115165 230649 115246 230650 115165 230650 115244 230650 115244 230651 115165 230651 115166 230651 115244 230652 115166 230652 115243 230652 115243 230653 115166 230653 115118 230653 115243 230654 115118 230654 115239 230654 115239 230655 115118 230655 115167 230655 115239 230656 115167 230656 115237 230656 115237 230657 115167 230657 116087 230657 115237 230658 116087 230658 116088 230658 116080 230659 115168 230659 115175 230659 115175 230660 115168 230660 115169 230660 115175 230661 115169 230661 115230 230661 115230 230662 115169 230662 115170 230662 115230 230663 115170 230663 114963 230663 114963 230664 115170 230664 114964 230664 114963 230665 114964 230665 115171 230665 115171 230666 114964 230666 116076 230666 115223 230667 115229 230667 115187 230667 115187 230668 115229 230668 115172 230668 115187 230669 115172 230669 115173 230669 115173 230670 115172 230670 115174 230670 115173 230671 115174 230671 115189 230671 115189 230672 115174 230672 115227 230672 115189 230673 115227 230673 115190 230673 115190 230674 115227 230674 114958 230674 115190 230675 114958 230675 115275 230675 115275 230676 114958 230676 114916 230676 115275 230677 114916 230677 116071 230677 116071 230678 114916 230678 116069 230678 115175 230679 115176 230679 115177 230679 115177 230680 115176 230680 115178 230680 115177 230681 115178 230681 115179 230681 115179 230682 115178 230682 115182 230682 115175 230683 115177 230683 114965 230683 114965 230684 115177 230684 115179 230684 114965 230685 115179 230685 114967 230685 114967 230686 115179 230686 115182 230686 114967 230687 115182 230687 114970 230687 114970 230688 115182 230688 115180 230688 114970 230689 115180 230689 115181 230689 115181 230690 115180 230690 115235 230690 115181 230691 115235 230691 114915 230691 115176 230692 115231 230692 115178 230692 115178 230693 115231 230693 115183 230693 115178 230694 115183 230694 115182 230694 115182 230695 115183 230695 115233 230695 115182 230696 115233 230696 115180 230696 115180 230697 115233 230697 115184 230697 115180 230698 115184 230698 115235 230698 115185 230699 115223 230699 115186 230699 115186 230700 115223 230700 115187 230700 115186 230701 115187 230701 115192 230701 115192 230702 115187 230702 115173 230702 115192 230703 115173 230703 115188 230703 115188 230704 115173 230704 115189 230704 115188 230705 115189 230705 115193 230705 115193 230706 115189 230706 115190 230706 115193 230707 115190 230707 115191 230707 115191 230708 115190 230708 115275 230708 115221 230709 115185 230709 115203 230709 115203 230710 115185 230710 115186 230710 115203 230711 115186 230711 115202 230711 115202 230712 115186 230712 115192 230712 115202 230713 115192 230713 115199 230713 115199 230714 115192 230714 115188 230714 115199 230715 115188 230715 115194 230715 115194 230716 115188 230716 115193 230716 115194 230717 115193 230717 115195 230717 115195 230718 115193 230718 115191 230718 114909 230719 115222 230719 115197 230719 115197 230720 115222 230720 115196 230720 115197 230721 115196 230721 115232 230721 115195 230722 115198 230722 115194 230722 115194 230723 115198 230723 115270 230723 115194 230724 115270 230724 115199 230724 115199 230725 115270 230725 115200 230725 115199 230726 115200 230726 115202 230726 115202 230727 115200 230727 115201 230727 115202 230728 115201 230728 115203 230728 115203 230729 115201 230729 115269 230729 115203 230730 115269 230730 115221 230730 115221 230731 115269 230731 115268 230731 115196 230732 115204 230732 115232 230732 115232 230733 115204 230733 115205 230733 115232 230734 115205 230734 115206 230734 115206 230735 115205 230735 115208 230735 115206 230736 115208 230736 115207 230736 115207 230737 115208 230737 115218 230737 115207 230738 115218 230738 115234 230738 115234 230739 115218 230739 115216 230739 115234 230740 115216 230740 115236 230740 115236 230741 115216 230741 115209 230741 115236 230742 115209 230742 115238 230742 115238 230743 115209 230743 115215 230743 115238 230744 115215 230744 115240 230744 115250 230745 115210 230745 115255 230745 115255 230746 115210 230746 115248 230746 115255 230747 115248 230747 115211 230747 115211 230748 115248 230748 115212 230748 115211 230749 115212 230749 115213 230749 115213 230750 115212 230750 115245 230750 115213 230751 115245 230751 115256 230751 115256 230752 115245 230752 115242 230752 115256 230753 115242 230753 115258 230753 115258 230754 115242 230754 115241 230754 115258 230755 115241 230755 115259 230755 115259 230756 115241 230756 115240 230756 115259 230757 115240 230757 115214 230757 115214 230758 115240 230758 115215 230758 115214 230759 115215 230759 115261 230759 115261 230760 115215 230760 115209 230760 115261 230761 115209 230761 115264 230761 115264 230762 115209 230762 115216 230762 115264 230763 115216 230763 115217 230763 115217 230764 115216 230764 115218 230764 115217 230765 115218 230765 115219 230765 115219 230766 115218 230766 115208 230766 115219 230767 115208 230767 115220 230767 115220 230768 115208 230768 115205 230768 115220 230769 115205 230769 115268 230769 115268 230770 115205 230770 115204 230770 115268 230771 115204 230771 115221 230771 115221 230772 115204 230772 115196 230772 115221 230773 115196 230773 115185 230773 115185 230774 115196 230774 115222 230774 115185 230775 115222 230775 115223 230775 115223 230776 115222 230776 114910 230776 115223 230777 114910 230777 115229 230777 115224 230778 115225 230778 115226 230778 115226 230779 115225 230779 114958 230779 115226 230780 114958 230780 114960 230780 114960 230781 114958 230781 115227 230781 114960 230782 115227 230782 114962 230782 114962 230783 115227 230783 115174 230783 114962 230784 115174 230784 115228 230784 115228 230785 115174 230785 115172 230785 115228 230786 115172 230786 114963 230786 114963 230787 115172 230787 115229 230787 114963 230788 115229 230788 115230 230788 115230 230789 115229 230789 114910 230789 115230 230790 114910 230790 115175 230790 115175 230791 114910 230791 114909 230791 115175 230792 114909 230792 115176 230792 115176 230793 114909 230793 115197 230793 115176 230794 115197 230794 115231 230794 115231 230795 115197 230795 115232 230795 115231 230796 115232 230796 115183 230796 115183 230797 115232 230797 115206 230797 115183 230798 115206 230798 115233 230798 115233 230799 115206 230799 115207 230799 115233 230800 115207 230800 115184 230800 115184 230801 115207 230801 115234 230801 115184 230802 115234 230802 115235 230802 115235 230803 115234 230803 115236 230803 115235 230804 115236 230804 114915 230804 114915 230805 115236 230805 115238 230805 114915 230806 115238 230806 115237 230806 115237 230807 115238 230807 115240 230807 115237 230808 115240 230808 115239 230808 115239 230809 115240 230809 115241 230809 115239 230810 115241 230810 115243 230810 115243 230811 115241 230811 115242 230811 115243 230812 115242 230812 115244 230812 115244 230813 115242 230813 115245 230813 115244 230814 115245 230814 115246 230814 115246 230815 115245 230815 115212 230815 115246 230816 115212 230816 115247 230816 115247 230817 115212 230817 115248 230817 115247 230818 115248 230818 115052 230818 115052 230819 115248 230819 115210 230819 115052 230820 115210 230820 115249 230820 115249 230821 115210 230821 115250 230821 115249 230822 115250 230822 115251 230822 118177 230823 118187 230823 115252 230823 115252 230824 118187 230824 115251 230824 115252 230825 115251 230825 115253 230825 115253 230826 115251 230826 115250 230826 115253 230827 115250 230827 115254 230827 115254 230828 115250 230828 115255 230828 115254 230829 115255 230829 115054 230829 115054 230830 115255 230830 115211 230830 115054 230831 115211 230831 115055 230831 115055 230832 115211 230832 115213 230832 115055 230833 115213 230833 115010 230833 115010 230834 115213 230834 115256 230834 115010 230835 115256 230835 115009 230835 115009 230836 115256 230836 115258 230836 115009 230837 115258 230837 115257 230837 115257 230838 115258 230838 115259 230838 115257 230839 115259 230839 115260 230839 115260 230840 115259 230840 115214 230840 115260 230841 115214 230841 115262 230841 115262 230842 115214 230842 115261 230842 115262 230843 115261 230843 115263 230843 115263 230844 115261 230844 115264 230844 115263 230845 115264 230845 115265 230845 115265 230846 115264 230846 115217 230846 115265 230847 115217 230847 115266 230847 115266 230848 115217 230848 115219 230848 115266 230849 115219 230849 114984 230849 114984 230850 115219 230850 115220 230850 114984 230851 115220 230851 115267 230851 115267 230852 115220 230852 115268 230852 115267 230853 115268 230853 114985 230853 114985 230854 115268 230854 115269 230854 114985 230855 115269 230855 114982 230855 114982 230856 115269 230856 115201 230856 114982 230857 115201 230857 114981 230857 114981 230858 115201 230858 115200 230858 114981 230859 115200 230859 114980 230859 114980 230860 115200 230860 115270 230860 114980 230861 115270 230861 115271 230861 115271 230862 115270 230862 115198 230862 115271 230863 115198 230863 115272 230863 115272 230864 115198 230864 115195 230864 115272 230865 115195 230865 115273 230865 115273 230866 115195 230866 115191 230866 115273 230867 115191 230867 114957 230867 114957 230868 115191 230868 115275 230868 114957 230869 115275 230869 115274 230869 115274 230870 115275 230870 116071 230870 115274 230871 116071 230871 118058 230871 117368 230872 116831 230872 115276 230872 115276 230873 116831 230873 116803 230873 115284 230874 115277 230874 117599 230874 117599 230875 115277 230875 116915 230875 117599 230876 116915 230876 115278 230876 115278 230877 116915 230877 116916 230877 115278 230878 116916 230878 115279 230878 115279 230879 116916 230879 116917 230879 115279 230880 116917 230880 116963 230880 117557 230881 116543 230881 115280 230881 115280 230882 116543 230882 115282 230882 115280 230883 115282 230883 115281 230883 115281 230884 115282 230884 116913 230884 115281 230885 116913 230885 117597 230885 117597 230886 116913 230886 115283 230886 117597 230887 115283 230887 115284 230887 115284 230888 115283 230888 116911 230888 115284 230889 116911 230889 115277 230889 116172 230890 116171 230890 115286 230890 115286 230891 116171 230891 115285 230891 115286 230892 115285 230892 116493 230892 115299 230893 115287 230893 115298 230893 115298 230894 115287 230894 115479 230894 115479 230895 115287 230895 115288 230895 115479 230896 115288 230896 115289 230896 115289 230897 115288 230897 116991 230897 115289 230898 116991 230898 115754 230898 115698 230899 115697 230899 115294 230899 115294 230900 115697 230900 115478 230900 115294 230901 115478 230901 115291 230901 115478 230902 115290 230902 115291 230902 115291 230903 115290 230903 115292 230903 115291 230904 115292 230904 115293 230904 115293 230905 115292 230905 115693 230905 115293 230906 115693 230906 116991 230906 116991 230907 115693 230907 115692 230907 116991 230908 115692 230908 115754 230908 115698 230909 115294 230909 115477 230909 115477 230910 115294 230910 115295 230910 115477 230911 115295 230911 115296 230911 115296 230912 115295 230912 117055 230912 115296 230913 117055 230913 115297 230913 115297 230914 117055 230914 116110 230914 115297 230915 116110 230915 116111 230915 115298 230916 115481 230916 115299 230916 115299 230917 115481 230917 115715 230917 115299 230918 115715 230918 115300 230918 115300 230919 115715 230919 115302 230919 115300 230920 115302 230920 115301 230920 115301 230921 115302 230921 115471 230921 115301 230922 115471 230922 115305 230922 116950 230923 115303 230923 117947 230923 117958 230924 117957 230924 115471 230924 115471 230925 117957 230925 115304 230925 115471 230926 115304 230926 115305 230926 115305 230927 115304 230927 117947 230927 115305 230928 117947 230928 116956 230928 116956 230929 117947 230929 115303 230929 117947 230930 115306 230930 116950 230930 116950 230931 115306 230931 117945 230931 116950 230932 117945 230932 115307 230932 115307 230933 117945 230933 115308 230933 115307 230934 115308 230934 115310 230934 112491 230935 116910 230935 115309 230935 115309 230936 116910 230936 115310 230936 115309 230937 115310 230937 115329 230937 115321 230938 116867 230938 115311 230938 115311 230939 116867 230939 115312 230939 115311 230940 115312 230940 112491 230940 112491 230941 115312 230941 116905 230941 112491 230942 116905 230942 116910 230942 115324 230943 115313 230943 116065 230943 112541 230944 115317 230944 115315 230944 115315 230945 115317 230945 115314 230945 115315 230946 115314 230946 112543 230946 112553 230947 115326 230947 112541 230947 112541 230948 115326 230948 115316 230948 112541 230949 115316 230949 115317 230949 115318 230950 116863 230950 115319 230950 115319 230951 116863 230951 115320 230951 115319 230952 115320 230952 115321 230952 115321 230953 115320 230953 116864 230953 115321 230954 116864 230954 116867 230954 115349 230955 116860 230955 115318 230955 115318 230956 116860 230956 116861 230956 115318 230957 116861 230957 116863 230957 112546 230958 115322 230958 112549 230958 112549 230959 115322 230959 116798 230959 115314 230960 116809 230960 112543 230960 112543 230961 116809 230961 116808 230961 112543 230962 116808 230962 112544 230962 112544 230963 116808 230963 116807 230963 112544 230964 116807 230964 112546 230964 112546 230965 116807 230965 115323 230965 112546 230966 115323 230966 115322 230966 116065 230967 116064 230967 115324 230967 115324 230968 116064 230968 115325 230968 115324 230969 115325 230969 112553 230969 112553 230970 115325 230970 116813 230970 112553 230971 116813 230971 115326 230971 115327 230972 112495 230972 115347 230972 115347 230973 112495 230973 115328 230973 115347 230974 115328 230974 117910 230974 117910 230975 115328 230975 112493 230975 117910 230976 112493 230976 115330 230976 115330 230977 112493 230977 115329 230977 115330 230978 115329 230978 115308 230978 115308 230979 115329 230979 115310 230979 115331 230980 115332 230980 115352 230980 115352 230981 115332 230981 117982 230981 115352 230982 117982 230982 115333 230982 115333 230983 117982 230983 117983 230983 115333 230984 117983 230984 115334 230984 115334 230985 117983 230985 117984 230985 115334 230986 117984 230986 112551 230986 112551 230987 117984 230987 115335 230987 112551 230988 115335 230988 115313 230988 115313 230989 115335 230989 115336 230989 115313 230990 115336 230990 116065 230990 117915 230991 115337 230991 117907 230991 117907 230992 115337 230992 115338 230992 117907 230993 115338 230993 117888 230993 117888 230994 115338 230994 115339 230994 117888 230995 115339 230995 115340 230995 115339 230996 115341 230996 115340 230996 115340 230997 115341 230997 117987 230997 115340 230998 117987 230998 117890 230998 117890 230999 117987 230999 117986 230999 117890 231000 117986 231000 115342 231000 115351 231001 115350 231001 115343 231001 115343 231002 115350 231002 116800 231002 115343 231003 116800 231003 117893 231003 117893 231004 116800 231004 115344 231004 117893 231005 115344 231005 117895 231005 117895 231006 115344 231006 115345 231006 117895 231007 115345 231007 117896 231007 117896 231008 115345 231008 115347 231008 115345 231009 115346 231009 115347 231009 115347 231010 115346 231010 116840 231010 115347 231011 116840 231011 115327 231011 115327 231012 116840 231012 116842 231012 115327 231013 116842 231013 115348 231013 115348 231014 116842 231014 116843 231014 115348 231015 116843 231015 115349 231015 115349 231016 116843 231016 116859 231016 115349 231017 116859 231017 116860 231017 116798 231018 115350 231018 112549 231018 112549 231019 115350 231019 115351 231019 112549 231020 115351 231020 115352 231020 115352 231021 115351 231021 117890 231021 115352 231022 117890 231022 115331 231022 115331 231023 117890 231023 115342 231023 118109 231024 118110 231024 115399 231024 115380 231025 117928 231025 115353 231025 115354 231026 115355 231026 115380 231026 117917 231027 115356 231027 115355 231027 115356 231028 117923 231028 115355 231028 115355 231029 117923 231029 115357 231029 115355 231030 115357 231030 115380 231030 115337 231031 117915 231031 115358 231031 115358 231032 117915 231032 115359 231032 115358 231033 115359 231033 118009 231033 118009 231034 115359 231034 117917 231034 118010 231035 115363 231035 115360 231035 115360 231036 115363 231036 115361 231036 115372 231037 118004 231037 115355 231037 115362 231038 118056 231038 114956 231038 114956 231039 118056 231039 118055 231039 114956 231040 118055 231040 118026 231040 118004 231041 115361 231041 115355 231041 115355 231042 115361 231042 115363 231042 115355 231043 115363 231043 117917 231043 117917 231044 115363 231044 118010 231044 117917 231045 118010 231045 118009 231045 115398 231046 115364 231046 114942 231046 114942 231047 115364 231047 114941 231047 114941 231048 115364 231048 118138 231048 114941 231049 118138 231049 118135 231049 118109 231050 115399 231050 118077 231050 115406 231051 115365 231051 115366 231051 115366 231052 115365 231052 114950 231052 115366 231053 114950 231053 115367 231053 114950 231054 114948 231054 115367 231054 115367 231055 114948 231055 114999 231055 115367 231056 114999 231056 115369 231056 115369 231057 114999 231057 115368 231057 115369 231058 115368 231058 115385 231058 115370 231059 115371 231059 115378 231059 114953 231060 115375 231060 114954 231060 114954 231061 115375 231061 115370 231061 114954 231062 115370 231062 114952 231062 114952 231063 115370 231063 115378 231063 118026 231064 115372 231064 114956 231064 114956 231065 115372 231065 115355 231065 114956 231066 115355 231066 115272 231066 115272 231067 115355 231067 115354 231067 115272 231068 115354 231068 114991 231068 114991 231069 115354 231069 115381 231069 114991 231070 115381 231070 114989 231070 114989 231071 115381 231071 115382 231071 114989 231072 115382 231072 115373 231072 115373 231073 115382 231073 115375 231073 115373 231074 115375 231074 115374 231074 115374 231075 115375 231075 114953 231075 115368 231076 114998 231076 115385 231076 115385 231077 114998 231077 115376 231077 115385 231078 115376 231078 115371 231078 115371 231079 115376 231079 115377 231079 115371 231080 115377 231080 115378 231080 115385 231081 115386 231081 115369 231081 115369 231082 115386 231082 115379 231082 115369 231083 115379 231083 115367 231083 115367 231084 115379 231084 115438 231084 115367 231085 115438 231085 115366 231085 115380 231086 115353 231086 115354 231086 115354 231087 115353 231087 115430 231087 115354 231088 115430 231088 115381 231088 115381 231089 115430 231089 115383 231089 115381 231090 115383 231090 115382 231090 115382 231091 115383 231091 115431 231091 115382 231092 115431 231092 115375 231092 115375 231093 115431 231093 115433 231093 115375 231094 115433 231094 115370 231094 115370 231095 115433 231095 115436 231095 115370 231096 115436 231096 115371 231096 115371 231097 115436 231097 115384 231097 115371 231098 115384 231098 115385 231098 115385 231099 115384 231099 115439 231099 115385 231100 115439 231100 115386 231100 115388 231101 115389 231101 115387 231101 115387 231102 115389 231102 115402 231102 115388 231103 115440 231103 115389 231103 115389 231104 115440 231104 115390 231104 115389 231105 115390 231105 115399 231105 115399 231106 115390 231106 115391 231106 115399 231107 115391 231107 118077 231107 114944 231108 115392 231108 115394 231108 115392 231109 115393 231109 115394 231109 115394 231110 115393 231110 115395 231110 115394 231111 115395 231111 115402 231111 115402 231112 115395 231112 115396 231112 115402 231113 115389 231113 115394 231113 115394 231114 115389 231114 115397 231114 115394 231115 115397 231115 114944 231115 118110 231116 115398 231116 115399 231116 115399 231117 115398 231117 114942 231117 115399 231118 114942 231118 115389 231118 115389 231119 114942 231119 114946 231119 115389 231120 114946 231120 115397 231120 115397 231121 114946 231121 115400 231121 115397 231122 115400 231122 114944 231122 115438 231123 115437 231123 115366 231123 115366 231124 115437 231124 115429 231124 115366 231125 115429 231125 115396 231125 115396 231126 115429 231126 115401 231126 115396 231127 115401 231127 115402 231127 115402 231128 115401 231128 115447 231128 115402 231129 115447 231129 115387 231129 115395 231130 115403 231130 115396 231130 115396 231131 115403 231131 115404 231131 115396 231132 115404 231132 115366 231132 115366 231133 115404 231133 115405 231133 115366 231134 115405 231134 115406 231134 115415 231135 115408 231135 115416 231135 117960 231136 115407 231136 115738 231136 115408 231137 115409 231137 115416 231137 115416 231138 115409 231138 117960 231138 115416 231139 117960 231139 115410 231139 115410 231140 117960 231140 115738 231140 115353 231141 117928 231141 117929 231141 118091 231142 115454 231142 115665 231142 115665 231143 115454 231143 115453 231143 115452 231144 118078 231144 115411 231144 115411 231145 118078 231145 115412 231145 115411 231146 115412 231146 115442 231146 115548 231147 115414 231147 115489 231147 115489 231148 115414 231148 115428 231148 115548 231149 115413 231149 115414 231149 115414 231150 115413 231150 115546 231150 115414 231151 115546 231151 115448 231151 115448 231152 115546 231152 115469 231152 115448 231153 115469 231153 115490 231153 117935 231154 115415 231154 115417 231154 115417 231155 115415 231155 115416 231155 115417 231156 115416 231156 115419 231156 115419 231157 115416 231157 115418 231157 115418 231158 115483 231158 115419 231158 115419 231159 115483 231159 115420 231159 115419 231160 115420 231160 115432 231160 115420 231161 115421 231161 115432 231161 115432 231162 115421 231162 115422 231162 115432 231163 115422 231163 115434 231163 115434 231164 115422 231164 115486 231164 115434 231165 115486 231165 115435 231165 115435 231166 115486 231166 115515 231166 115435 231167 115515 231167 115423 231167 115423 231168 115515 231168 115424 231168 115423 231169 115424 231169 115425 231169 115424 231170 115514 231170 115425 231170 115425 231171 115514 231171 115426 231171 115425 231172 115426 231172 115428 231172 115428 231173 115426 231173 115427 231173 115428 231174 115427 231174 115489 231174 115449 231175 115429 231175 115448 231175 115448 231176 115429 231176 115437 231176 115448 231177 115437 231177 115414 231177 117929 231178 117935 231178 115353 231178 115353 231179 117935 231179 115417 231179 115353 231180 115417 231180 115430 231180 115430 231181 115417 231181 115419 231181 115430 231182 115419 231182 115383 231182 115383 231183 115419 231183 115432 231183 115383 231184 115432 231184 115431 231184 115431 231185 115432 231185 115434 231185 115431 231186 115434 231186 115433 231186 115433 231187 115434 231187 115435 231187 115433 231188 115435 231188 115436 231188 115436 231189 115435 231189 115423 231189 115436 231190 115423 231190 115384 231190 115384 231191 115423 231191 115425 231191 115437 231192 115438 231192 115414 231192 115414 231193 115438 231193 115379 231193 115414 231194 115379 231194 115428 231194 115428 231195 115379 231195 115386 231195 115428 231196 115386 231196 115425 231196 115425 231197 115386 231197 115439 231197 115425 231198 115439 231198 115384 231198 115451 231199 115440 231199 115388 231199 115451 231200 115388 231200 115441 231200 115440 231201 115451 231201 115390 231201 115390 231202 115451 231202 115411 231202 115390 231203 115411 231203 115391 231203 115391 231204 115411 231204 115442 231204 115391 231205 115442 231205 118077 231205 115468 231206 115450 231206 115443 231206 115443 231207 115450 231207 115444 231207 115443 231208 115444 231208 115491 231208 115468 231209 115445 231209 115450 231209 115450 231210 115445 231210 115493 231210 115450 231211 115493 231211 115446 231211 115388 231212 115387 231212 115441 231212 115441 231213 115387 231213 115447 231213 115441 231214 115447 231214 115449 231214 115449 231215 115447 231215 115401 231215 115449 231216 115401 231216 115429 231216 115490 231217 115491 231217 115448 231217 115448 231218 115491 231218 115444 231218 115448 231219 115444 231219 115449 231219 115449 231220 115444 231220 115450 231220 115449 231221 115450 231221 115441 231221 115441 231222 115450 231222 115446 231222 115441 231223 115446 231223 115451 231223 115451 231224 115446 231224 115467 231224 115451 231225 115467 231225 115411 231225 115411 231226 115467 231226 115453 231226 115411 231227 115453 231227 115452 231227 115452 231228 115453 231228 115454 231228 115735 231229 115482 231229 115455 231229 115744 231230 115709 231230 115705 231230 115456 231231 115679 231231 115472 231231 115810 231232 115621 231232 115809 231232 115457 231233 115633 231233 115605 231233 115601 231234 115604 231234 115458 231234 115562 231235 115574 231235 115459 231235 115573 231236 115667 231236 115460 231236 115532 231237 115522 231237 115518 231237 115461 231238 116124 231238 115462 231238 115462 231239 116124 231239 115820 231239 116047 231240 115506 231240 115508 231240 115816 231241 115463 231241 115464 231241 115465 231242 115503 231242 115580 231242 115466 231243 115664 231243 115576 231243 115453 231244 115467 231244 115726 231244 115443 231245 115492 231245 115468 231245 115546 231246 115538 231246 115469 231246 115471 231247 115714 231247 115470 231247 115714 231248 115471 231248 115302 231248 115298 231249 115479 231249 115681 231249 115289 231250 115754 231250 115472 231250 115296 231251 115297 231251 115688 231251 116111 231252 116115 231252 115707 231252 115585 231253 115473 231253 115474 231253 115474 231254 115473 231254 115475 231254 115474 231255 115475 231255 116107 231255 115776 231256 115476 231256 115741 231256 115741 231257 115476 231257 115778 231257 115296 231258 115688 231258 115477 231258 115697 231259 115696 231259 115478 231259 115478 231260 115696 231260 115684 231260 115478 231261 115684 231261 115290 231261 115290 231262 115684 231262 115292 231262 115289 231263 115472 231263 115479 231263 115479 231264 115472 231264 115480 231264 115479 231265 115480 231265 115681 231265 115298 231266 115681 231266 115481 231266 115481 231267 115681 231267 115682 231267 115481 231268 115682 231268 115715 231268 115720 231269 117978 231269 117958 231269 115738 231270 115407 231270 115739 231270 115416 231271 115410 231271 115455 231271 115455 231272 115410 231272 115738 231272 115735 231273 115420 231273 115482 231273 115482 231274 115420 231274 115483 231274 115482 231275 115483 231275 115455 231275 115455 231276 115483 231276 115418 231276 115455 231277 115418 231277 115416 231277 115421 231278 115484 231278 115422 231278 115422 231279 115484 231279 115485 231279 115422 231280 115485 231280 115486 231280 115486 231281 115485 231281 115515 231281 115426 231282 115514 231282 115487 231282 115487 231283 115514 231283 115731 231283 115547 231284 115548 231284 115488 231284 115488 231285 115548 231285 115489 231285 115488 231286 115489 231286 115487 231286 115487 231287 115489 231287 115427 231287 115487 231288 115427 231288 115426 231288 115469 231289 115538 231289 115490 231289 115490 231290 115538 231290 115539 231290 115490 231291 115539 231291 115491 231291 115491 231292 115539 231292 115443 231292 115443 231293 115539 231293 115540 231293 115443 231294 115540 231294 115492 231294 115446 231295 115493 231295 115541 231295 115541 231296 115493 231296 115445 231296 115563 231297 115494 231297 115564 231297 118084 231298 118087 231298 115576 231298 115576 231299 118087 231299 118088 231299 115576 231300 118088 231300 115466 231300 115495 231301 118128 231301 115496 231301 115496 231302 118128 231302 118118 231302 115496 231303 118118 231303 118117 231303 115502 231304 115997 231304 115497 231304 115497 231305 115997 231305 115498 231305 115497 231306 115498 231306 115499 231306 115499 231307 115498 231307 118114 231307 115499 231308 118114 231308 115496 231308 115496 231309 118114 231309 118115 231309 115496 231310 118115 231310 115495 231310 115503 231311 116014 231311 115580 231311 115580 231312 116014 231312 116013 231312 115580 231313 116013 231313 115500 231313 115500 231314 116013 231314 115501 231314 115500 231315 115501 231315 115502 231315 115502 231316 115501 231316 116011 231316 115502 231317 116011 231317 115997 231317 116018 231318 116016 231318 115465 231318 115465 231319 116016 231319 116015 231319 115465 231320 116015 231320 115503 231320 115994 231321 115504 231321 115993 231321 115993 231322 115504 231322 115505 231322 115993 231323 115505 231323 115507 231323 116047 231324 115993 231324 115506 231324 115506 231325 115993 231325 115507 231325 115506 231326 115507 231326 115508 231326 115508 231327 115507 231327 115818 231327 115508 231328 115818 231328 115509 231328 115602 231329 116133 231329 116132 231329 115603 231330 119017 231330 115602 231330 115602 231331 119017 231331 115510 231331 115602 231332 115510 231332 116133 231332 115600 231333 118940 231333 115606 231333 115586 231334 115511 231334 115512 231334 115512 231335 115511 231335 118936 231335 118936 231336 115513 231336 115512 231336 115512 231337 115513 231337 118937 231337 115512 231338 118937 231338 115768 231338 115514 231339 115424 231339 115731 231339 115731 231340 115424 231340 115515 231340 115731 231341 115515 231341 115733 231341 115733 231342 115515 231342 115485 231342 115733 231343 115485 231343 115516 231343 115516 231344 115485 231344 115484 231344 115516 231345 115484 231345 115735 231345 115735 231346 115484 231346 115421 231346 115735 231347 115421 231347 115420 231347 115520 231348 115519 231348 115517 231348 115518 231349 115522 231349 115794 231349 115794 231350 115522 231350 115519 231350 115794 231351 115519 231351 115792 231351 115792 231352 115519 231352 115520 231352 115792 231353 115520 231353 115791 231353 115517 231354 115519 231354 115521 231354 115521 231355 115519 231355 115522 231355 115521 231356 115522 231356 115526 231356 115526 231357 115522 231357 115532 231357 115526 231358 115532 231358 115535 231358 115598 231359 115523 231359 115536 231359 115536 231360 115523 231360 115727 231360 115536 231361 115727 231361 115524 231361 115524 231362 115727 231362 115525 231362 115524 231363 115525 231363 115535 231363 115535 231364 115525 231364 115527 231364 115535 231365 115527 231365 115526 231365 115526 231366 115527 231366 115730 231366 115526 231367 115730 231367 115521 231367 115521 231368 115730 231368 115725 231368 115521 231369 115725 231369 115517 231369 115533 231370 115797 231370 115534 231370 115534 231371 115797 231371 115528 231371 115534 231372 115528 231372 115529 231372 115529 231373 115528 231373 115798 231373 115529 231374 115798 231374 115530 231374 115530 231375 115798 231375 115800 231375 115530 231376 115800 231376 115531 231376 115531 231377 115800 231377 115802 231377 115531 231378 115802 231378 115595 231378 115518 231379 115533 231379 115532 231379 115532 231380 115533 231380 115534 231380 115532 231381 115534 231381 115535 231381 115535 231382 115534 231382 115529 231382 115535 231383 115529 231383 115524 231383 115524 231384 115529 231384 115530 231384 115524 231385 115530 231385 115536 231385 115536 231386 115530 231386 115531 231386 115536 231387 115531 231387 115598 231387 115598 231388 115531 231388 115595 231388 115598 231389 115595 231389 115537 231389 115538 231390 115545 231390 115539 231390 115539 231391 115545 231391 115543 231391 115539 231392 115543 231392 115540 231392 115540 231393 115543 231393 115541 231393 115540 231394 115541 231394 115492 231394 115492 231395 115541 231395 115445 231395 115492 231396 115445 231396 115468 231396 115467 231397 115446 231397 115726 231397 115726 231398 115446 231398 115541 231398 115726 231399 115541 231399 115542 231399 115542 231400 115541 231400 115543 231400 115542 231401 115543 231401 115544 231401 115544 231402 115543 231402 115545 231402 115544 231403 115545 231403 115728 231403 115728 231404 115545 231404 115538 231404 115728 231405 115538 231405 115729 231405 115729 231406 115538 231406 115546 231406 115729 231407 115546 231407 115547 231407 115547 231408 115546 231408 115413 231408 115547 231409 115413 231409 115548 231409 115667 231410 115573 231410 115666 231410 115666 231411 115573 231411 115549 231411 115666 231412 115549 231412 115550 231412 115669 231413 115671 231413 115551 231413 115551 231414 115671 231414 115672 231414 115551 231415 115672 231415 115552 231415 115552 231416 115672 231416 115674 231416 115552 231417 115674 231417 115553 231417 115553 231418 115674 231418 115555 231418 115553 231419 115555 231419 115554 231419 115554 231420 115555 231420 115557 231420 115554 231421 115557 231421 115556 231421 115556 231422 115557 231422 115678 231422 115556 231423 115678 231423 115812 231423 115667 231424 115669 231424 115460 231424 115460 231425 115669 231425 115551 231425 115460 231426 115551 231426 115571 231426 115571 231427 115551 231427 115552 231427 115571 231428 115552 231428 115558 231428 115558 231429 115552 231429 115553 231429 115558 231430 115553 231430 115570 231430 115570 231431 115553 231431 115554 231431 115570 231432 115554 231432 115559 231432 115559 231433 115554 231433 115556 231433 115559 231434 115556 231434 115568 231434 115568 231435 115556 231435 115812 231435 115568 231436 115812 231436 115567 231436 115560 231437 115578 231437 115569 231437 115569 231438 115578 231438 115579 231438 115569 231439 115579 231439 115561 231439 115574 231440 115562 231440 115575 231440 115575 231441 115562 231441 115563 231441 115575 231442 115563 231442 115576 231442 115576 231443 115563 231443 115564 231443 115576 231444 115564 231444 118084 231444 115463 231445 115565 231445 115464 231445 115464 231446 115565 231446 115566 231446 115464 231447 115566 231447 115567 231447 115567 231448 115566 231448 115560 231448 115567 231449 115560 231449 115568 231449 115568 231450 115560 231450 115569 231450 115568 231451 115569 231451 115559 231451 115559 231452 115569 231452 115561 231452 115559 231453 115561 231453 115570 231453 115570 231454 115561 231454 115581 231454 115570 231455 115581 231455 115558 231455 115558 231456 115581 231456 115582 231456 115558 231457 115582 231457 115571 231457 115571 231458 115582 231458 115572 231458 115571 231459 115572 231459 115460 231459 115460 231460 115572 231460 115459 231460 115460 231461 115459 231461 115573 231461 115573 231462 115459 231462 115574 231462 115573 231463 115574 231463 115549 231463 115549 231464 115574 231464 115575 231464 115549 231465 115575 231465 115550 231465 115550 231466 115575 231466 115576 231466 115566 231467 116020 231467 115560 231467 115560 231468 116020 231468 115577 231468 115560 231469 115577 231469 115578 231469 115578 231470 115577 231470 116018 231470 115578 231471 116018 231471 115579 231471 115579 231472 116018 231472 115465 231472 115579 231473 115465 231473 115561 231473 115561 231474 115465 231474 115580 231474 115561 231475 115580 231475 115581 231475 115581 231476 115580 231476 115500 231476 115581 231477 115500 231477 115582 231477 115582 231478 115500 231478 115502 231478 115582 231479 115502 231479 115572 231479 115572 231480 115502 231480 115497 231480 115572 231481 115497 231481 115459 231481 115459 231482 115497 231482 115499 231482 115459 231483 115499 231483 115562 231483 115562 231484 115499 231484 115496 231484 115562 231485 115496 231485 115563 231485 115563 231486 115496 231486 118117 231486 115563 231487 118117 231487 115494 231487 115585 231488 115583 231488 115473 231488 115473 231489 115583 231489 115587 231489 115473 231490 115587 231490 115475 231490 115475 231491 115587 231491 115584 231491 116144 231492 115511 231492 116143 231492 116143 231493 115511 231493 115586 231493 116143 231494 115586 231494 115585 231494 115585 231495 115586 231495 115512 231495 115585 231496 115512 231496 115583 231496 115583 231497 115512 231497 115765 231497 115583 231498 115765 231498 115587 231498 115587 231499 115765 231499 115588 231499 115587 231500 115588 231500 115584 231500 115584 231501 115588 231501 115764 231501 115584 231502 115764 231502 115777 231502 115777 231503 115764 231503 115589 231503 115777 231504 115589 231504 115763 231504 115809 231505 115621 231505 115590 231505 115590 231506 115621 231506 115591 231506 115590 231507 115591 231507 115592 231507 115592 231508 115591 231508 115620 231508 115592 231509 115620 231509 115805 231509 115805 231510 115620 231510 115619 231510 115805 231511 115619 231511 115593 231511 115593 231512 115619 231512 115617 231512 115593 231513 115617 231513 115802 231513 115802 231514 115617 231514 115594 231514 115802 231515 115594 231515 115595 231515 115595 231516 115594 231516 115596 231516 115595 231517 115596 231517 115537 231517 115537 231518 115596 231518 115597 231518 115537 231519 115597 231519 115598 231519 115598 231520 115597 231520 115599 231520 115598 231521 115599 231521 115523 231521 118937 231522 118938 231522 115768 231522 115768 231523 118938 231523 118940 231523 115768 231524 118940 231524 115458 231524 115458 231525 118940 231525 115600 231525 115458 231526 115600 231526 115601 231526 116132 231527 115457 231527 115602 231527 115602 231528 115457 231528 115605 231528 115602 231529 115605 231529 115603 231529 115603 231530 115605 231530 115607 231530 115603 231531 115607 231531 118943 231531 118943 231532 115607 231532 118941 231532 115771 231533 115604 231533 115633 231533 115633 231534 115604 231534 115601 231534 115633 231535 115601 231535 115605 231535 115605 231536 115601 231536 115600 231536 115605 231537 115600 231537 115607 231537 115607 231538 115600 231538 115606 231538 115607 231539 115606 231539 118941 231539 116130 231540 116129 231540 115634 231540 115634 231541 116129 231541 116128 231541 115634 231542 116128 231542 115635 231542 115635 231543 116128 231543 115608 231543 115635 231544 115608 231544 115636 231544 115636 231545 115608 231545 115609 231545 115636 231546 115609 231546 115610 231546 115820 231547 115819 231547 115462 231547 115462 231548 115819 231548 115610 231548 115462 231549 115610 231549 115461 231549 115461 231550 115610 231550 115609 231550 115461 231551 115609 231551 115611 231551 115611 231552 115609 231552 115608 231552 115611 231553 115608 231553 115612 231553 115612 231554 115608 231554 116128 231554 115613 231555 115599 231555 115614 231555 115614 231556 115599 231556 115597 231556 115614 231557 115597 231557 115615 231557 115615 231558 115597 231558 115596 231558 115615 231559 115596 231559 115616 231559 115616 231560 115596 231560 115594 231560 115616 231561 115594 231561 115668 231561 115668 231562 115594 231562 115617 231562 115668 231563 115617 231563 115618 231563 115618 231564 115617 231564 115619 231564 115618 231565 115619 231565 115670 231565 115670 231566 115619 231566 115620 231566 115670 231567 115620 231567 115673 231567 115673 231568 115620 231568 115591 231568 115673 231569 115591 231569 115675 231569 115675 231570 115591 231570 115621 231570 115675 231571 115621 231571 115676 231571 115676 231572 115621 231572 115810 231572 115676 231573 115810 231573 115677 231573 115807 231574 115766 231574 115808 231574 115808 231575 115766 231575 115622 231575 115808 231576 115622 231576 115623 231576 115623 231577 115622 231577 115624 231577 115623 231578 115624 231578 115811 231578 115811 231579 115624 231579 115625 231579 115811 231580 115625 231580 115627 231580 115627 231581 115625 231581 115626 231581 115627 231582 115626 231582 115813 231582 115813 231583 115626 231583 115628 231583 115813 231584 115628 231584 115814 231584 115814 231585 115628 231585 115815 231585 115766 231586 115629 231586 115622 231586 115622 231587 115629 231587 115643 231587 115622 231588 115643 231588 115624 231588 115624 231589 115643 231589 115630 231589 115624 231590 115630 231590 115625 231590 115625 231591 115630 231591 115631 231591 115625 231592 115631 231592 115626 231592 116132 231593 115632 231593 115457 231593 115457 231594 115632 231594 116130 231594 115457 231595 116130 231595 115633 231595 115633 231596 116130 231596 115634 231596 115633 231597 115634 231597 115771 231597 115771 231598 115634 231598 115635 231598 115771 231599 115635 231599 115772 231599 115772 231600 115635 231600 115636 231600 115772 231601 115636 231601 115637 231601 115637 231602 115636 231602 115610 231602 115637 231603 115610 231603 115774 231603 115774 231604 115610 231604 115819 231604 115774 231605 115819 231605 115638 231605 115639 231606 115815 231606 115640 231606 115640 231607 115815 231607 115628 231607 115640 231608 115628 231608 115661 231608 115661 231609 115628 231609 115626 231609 115661 231610 115626 231610 115641 231610 115641 231611 115626 231611 115631 231611 115641 231612 115631 231612 115659 231612 115659 231613 115631 231613 115630 231613 115659 231614 115630 231614 115642 231614 115642 231615 115630 231615 115643 231615 115642 231616 115643 231616 115767 231616 115767 231617 115643 231617 115629 231617 115769 231618 115644 231618 115658 231618 115658 231619 115644 231619 115654 231619 115658 231620 115654 231620 115645 231620 115645 231621 115654 231621 115646 231621 115645 231622 115646 231622 115660 231622 115660 231623 115646 231623 115655 231623 115660 231624 115655 231624 115647 231624 115647 231625 115655 231625 115656 231625 115647 231626 115656 231626 115662 231626 115662 231627 115656 231627 115657 231627 115662 231628 115657 231628 115663 231628 115770 231629 115649 231629 115648 231629 115648 231630 115649 231630 115650 231630 115648 231631 115650 231631 115651 231631 115651 231632 115650 231632 115773 231632 115651 231633 115773 231633 115652 231633 115652 231634 115773 231634 115775 231634 115652 231635 115775 231635 115653 231635 115644 231636 115770 231636 115654 231636 115654 231637 115770 231637 115648 231637 115654 231638 115648 231638 115646 231638 115646 231639 115648 231639 115651 231639 115646 231640 115651 231640 115655 231640 115655 231641 115651 231641 115652 231641 115655 231642 115652 231642 115656 231642 115656 231643 115652 231643 115653 231643 115656 231644 115653 231644 115657 231644 115767 231645 115769 231645 115642 231645 115642 231646 115769 231646 115658 231646 115642 231647 115658 231647 115659 231647 115659 231648 115658 231648 115645 231648 115659 231649 115645 231649 115641 231649 115641 231650 115645 231650 115660 231650 115641 231651 115660 231651 115661 231651 115661 231652 115660 231652 115647 231652 115661 231653 115647 231653 115640 231653 115640 231654 115647 231654 115662 231654 115640 231655 115662 231655 115639 231655 115639 231656 115662 231656 115663 231656 118091 231657 115665 231657 115664 231657 115664 231658 115665 231658 115613 231658 115664 231659 115613 231659 115576 231659 115576 231660 115613 231660 115614 231660 115576 231661 115614 231661 115550 231661 115550 231662 115614 231662 115615 231662 115550 231663 115615 231663 115666 231663 115666 231664 115615 231664 115616 231664 115666 231665 115616 231665 115667 231665 115667 231666 115616 231666 115668 231666 115667 231667 115668 231667 115669 231667 115669 231668 115668 231668 115618 231668 115669 231669 115618 231669 115671 231669 115671 231670 115618 231670 115670 231670 115671 231671 115670 231671 115672 231671 115672 231672 115670 231672 115673 231672 115672 231673 115673 231673 115674 231673 115674 231674 115673 231674 115675 231674 115674 231675 115675 231675 115555 231675 115555 231676 115675 231676 115676 231676 115555 231677 115676 231677 115557 231677 115557 231678 115676 231678 115677 231678 115557 231679 115677 231679 115678 231679 115472 231680 115679 231680 115480 231680 115480 231681 115679 231681 115680 231681 115480 231682 115680 231682 115681 231682 115681 231683 115680 231683 115700 231683 115681 231684 115700 231684 115682 231684 115682 231685 115700 231685 115713 231685 115682 231686 115713 231686 115715 231686 115693 231687 115292 231687 115683 231687 115683 231688 115292 231688 115684 231688 115683 231689 115684 231689 115691 231689 115691 231690 115684 231690 115696 231690 115691 231691 115696 231691 115690 231691 115710 231692 115694 231692 115708 231692 115708 231693 115694 231693 115685 231693 115708 231694 115685 231694 115686 231694 115686 231695 115685 231695 115687 231695 115686 231696 115687 231696 115688 231696 115688 231697 115687 231697 115689 231697 115688 231698 115689 231698 115477 231698 115477 231699 115689 231699 115698 231699 115695 231700 115749 231700 115690 231700 115690 231701 115749 231701 115752 231701 115690 231702 115752 231702 115691 231702 115691 231703 115752 231703 115753 231703 115691 231704 115753 231704 115683 231704 115683 231705 115753 231705 115692 231705 115683 231706 115692 231706 115693 231706 115694 231707 115695 231707 115685 231707 115685 231708 115695 231708 115690 231708 115685 231709 115690 231709 115687 231709 115687 231710 115690 231710 115696 231710 115687 231711 115696 231711 115689 231711 115689 231712 115696 231712 115697 231712 115689 231713 115697 231713 115698 231713 115712 231714 115713 231714 115699 231714 115699 231715 115713 231715 115700 231715 115699 231716 115700 231716 115701 231716 115701 231717 115700 231717 115680 231717 115701 231718 115680 231718 115717 231718 115717 231719 115680 231719 115679 231719 115717 231720 115679 231720 115702 231720 115702 231721 115679 231721 115456 231721 115702 231722 115456 231722 115751 231722 116115 231723 115703 231723 115707 231723 115707 231724 115703 231724 115704 231724 115707 231725 115704 231725 115705 231725 115705 231726 115704 231726 115742 231726 115705 231727 115742 231727 115744 231727 115744 231728 115742 231728 115706 231728 115297 231729 116111 231729 115688 231729 115688 231730 116111 231730 115707 231730 115688 231731 115707 231731 115686 231731 115686 231732 115707 231732 115705 231732 115686 231733 115705 231733 115708 231733 115708 231734 115705 231734 115709 231734 115708 231735 115709 231735 115710 231735 115711 231736 115470 231736 115712 231736 115712 231737 115470 231737 115714 231737 115712 231738 115714 231738 115713 231738 115713 231739 115714 231739 115302 231739 115713 231740 115302 231740 115715 231740 115737 231741 115716 231741 115720 231741 115720 231742 115716 231742 117977 231742 115720 231743 117977 231743 117978 231743 115711 231744 115712 231744 115787 231744 115787 231745 115712 231745 115699 231745 115787 231746 115699 231746 115785 231746 115785 231747 115699 231747 115701 231747 115785 231748 115701 231748 115784 231748 115784 231749 115701 231749 115717 231749 115784 231750 115717 231750 115782 231750 115782 231751 115717 231751 115702 231751 115782 231752 115702 231752 115718 231752 115718 231753 115702 231753 115751 231753 115718 231754 115751 231754 115750 231754 115790 231755 115786 231755 115719 231755 117958 231756 115788 231756 115720 231756 115720 231757 115788 231757 115721 231757 115720 231758 115721 231758 115737 231758 115737 231759 115721 231759 115789 231759 115737 231760 115789 231760 115722 231760 115722 231761 115789 231761 115723 231761 115722 231762 115723 231762 115736 231762 115736 231763 115723 231763 115791 231763 115736 231764 115791 231764 115734 231764 115734 231765 115791 231765 115520 231765 115734 231766 115520 231766 115732 231766 115732 231767 115520 231767 115517 231767 115732 231768 115517 231768 115724 231768 115724 231769 115517 231769 115725 231769 115665 231770 115453 231770 115613 231770 115613 231771 115453 231771 115726 231771 115613 231772 115726 231772 115599 231772 115599 231773 115726 231773 115542 231773 115599 231774 115542 231774 115523 231774 115523 231775 115542 231775 115544 231775 115523 231776 115544 231776 115727 231776 115727 231777 115544 231777 115728 231777 115727 231778 115728 231778 115525 231778 115525 231779 115728 231779 115729 231779 115525 231780 115729 231780 115527 231780 115527 231781 115729 231781 115547 231781 115527 231782 115547 231782 115730 231782 115730 231783 115547 231783 115488 231783 115730 231784 115488 231784 115725 231784 115725 231785 115488 231785 115487 231785 115725 231786 115487 231786 115724 231786 115724 231787 115487 231787 115731 231787 115724 231788 115731 231788 115732 231788 115732 231789 115731 231789 115733 231789 115732 231790 115733 231790 115734 231790 115734 231791 115733 231791 115516 231791 115734 231792 115516 231792 115736 231792 115736 231793 115516 231793 115735 231793 115736 231794 115735 231794 115722 231794 115722 231795 115735 231795 115455 231795 115722 231796 115455 231796 115737 231796 115737 231797 115455 231797 115738 231797 115737 231798 115738 231798 115716 231798 115716 231799 115738 231799 115739 231799 115716 231800 115739 231800 117977 231800 115719 231801 115786 231801 115740 231801 115740 231802 115786 231802 115783 231802 115740 231803 115783 231803 115793 231803 115703 231804 116117 231804 115704 231804 115704 231805 116117 231805 115741 231805 115704 231806 115741 231806 115742 231806 115742 231807 115741 231807 115778 231807 115742 231808 115778 231808 115706 231808 115706 231809 115778 231809 115743 231809 115706 231810 115743 231810 115744 231810 115744 231811 115743 231811 115745 231811 115744 231812 115745 231812 115709 231812 115709 231813 115745 231813 115746 231813 115709 231814 115746 231814 115710 231814 115710 231815 115746 231815 115747 231815 115710 231816 115747 231816 115694 231816 115694 231817 115747 231817 115748 231817 115694 231818 115748 231818 115695 231818 115695 231819 115748 231819 115750 231819 115695 231820 115750 231820 115749 231820 115749 231821 115750 231821 115751 231821 115749 231822 115751 231822 115752 231822 115752 231823 115751 231823 115456 231823 115752 231824 115456 231824 115753 231824 115753 231825 115456 231825 115472 231825 115753 231826 115472 231826 115692 231826 115692 231827 115472 231827 115754 231827 115783 231828 115755 231828 115793 231828 115793 231829 115755 231829 115781 231829 115793 231830 115781 231830 115795 231830 115795 231831 115781 231831 115757 231831 115795 231832 115757 231832 115756 231832 115756 231833 115757 231833 115759 231833 115756 231834 115759 231834 115758 231834 115758 231835 115759 231835 115760 231835 115758 231836 115760 231836 115796 231836 115796 231837 115760 231837 115780 231837 115796 231838 115780 231838 115761 231838 115761 231839 115780 231839 115762 231839 115761 231840 115762 231840 115799 231840 115799 231841 115762 231841 115779 231841 115799 231842 115779 231842 115801 231842 115801 231843 115779 231843 115763 231843 115801 231844 115763 231844 115803 231844 115803 231845 115763 231845 115589 231845 115803 231846 115589 231846 115804 231846 115804 231847 115589 231847 115764 231847 115804 231848 115764 231848 115806 231848 115806 231849 115764 231849 115588 231849 115806 231850 115588 231850 115807 231850 115807 231851 115588 231851 115765 231851 115807 231852 115765 231852 115766 231852 115766 231853 115765 231853 115512 231853 115766 231854 115512 231854 115629 231854 115629 231855 115512 231855 115768 231855 115629 231856 115768 231856 115767 231856 115767 231857 115768 231857 115458 231857 115767 231858 115458 231858 115769 231858 115769 231859 115458 231859 115604 231859 115769 231860 115604 231860 115644 231860 115644 231861 115604 231861 115771 231861 115644 231862 115771 231862 115770 231862 115770 231863 115771 231863 115772 231863 115770 231864 115772 231864 115649 231864 115649 231865 115772 231865 115637 231865 115649 231866 115637 231866 115650 231866 115650 231867 115637 231867 115774 231867 115650 231868 115774 231868 115773 231868 115773 231869 115774 231869 115638 231869 115773 231870 115638 231870 115775 231870 116107 231871 115475 231871 115776 231871 115776 231872 115475 231872 115584 231872 115776 231873 115584 231873 115476 231873 115476 231874 115584 231874 115777 231874 115476 231875 115777 231875 115778 231875 115778 231876 115777 231876 115763 231876 115778 231877 115763 231877 115743 231877 115743 231878 115763 231878 115779 231878 115743 231879 115779 231879 115745 231879 115745 231880 115779 231880 115762 231880 115745 231881 115762 231881 115746 231881 115746 231882 115762 231882 115780 231882 115746 231883 115780 231883 115747 231883 115747 231884 115780 231884 115760 231884 115747 231885 115760 231885 115748 231885 115748 231886 115760 231886 115759 231886 115748 231887 115759 231887 115750 231887 115750 231888 115759 231888 115757 231888 115750 231889 115757 231889 115718 231889 115718 231890 115757 231890 115781 231890 115718 231891 115781 231891 115782 231891 115782 231892 115781 231892 115755 231892 115782 231893 115755 231893 115784 231893 115784 231894 115755 231894 115783 231894 115784 231895 115783 231895 115785 231895 115785 231896 115783 231896 115786 231896 115785 231897 115786 231897 115787 231897 115787 231898 115786 231898 115790 231898 115787 231899 115790 231899 115711 231899 117958 231900 115471 231900 115788 231900 115788 231901 115471 231901 115470 231901 115788 231902 115470 231902 115721 231902 115721 231903 115470 231903 115711 231903 115721 231904 115711 231904 115789 231904 115789 231905 115711 231905 115790 231905 115789 231906 115790 231906 115723 231906 115723 231907 115790 231907 115719 231907 115723 231908 115719 231908 115791 231908 115791 231909 115719 231909 115740 231909 115791 231910 115740 231910 115792 231910 115792 231911 115740 231911 115793 231911 115792 231912 115793 231912 115794 231912 115794 231913 115793 231913 115795 231913 115794 231914 115795 231914 115518 231914 115518 231915 115795 231915 115756 231915 115518 231916 115756 231916 115533 231916 115533 231917 115756 231917 115758 231917 115533 231918 115758 231918 115797 231918 115797 231919 115758 231919 115796 231919 115797 231920 115796 231920 115528 231920 115528 231921 115796 231921 115761 231921 115528 231922 115761 231922 115798 231922 115798 231923 115761 231923 115799 231923 115798 231924 115799 231924 115800 231924 115800 231925 115799 231925 115801 231925 115800 231926 115801 231926 115802 231926 115802 231927 115801 231927 115803 231927 115802 231928 115803 231928 115593 231928 115593 231929 115803 231929 115804 231929 115593 231930 115804 231930 115805 231930 115805 231931 115804 231931 115806 231931 115805 231932 115806 231932 115592 231932 115592 231933 115806 231933 115807 231933 115592 231934 115807 231934 115590 231934 115590 231935 115807 231935 115808 231935 115590 231936 115808 231936 115809 231936 115809 231937 115808 231937 115623 231937 115809 231938 115623 231938 115810 231938 115810 231939 115623 231939 115811 231939 115810 231940 115811 231940 115677 231940 115677 231941 115811 231941 115627 231941 115677 231942 115627 231942 115678 231942 115678 231943 115627 231943 115813 231943 115678 231944 115813 231944 115812 231944 115812 231945 115813 231945 115814 231945 115812 231946 115814 231946 115567 231946 115567 231947 115814 231947 115815 231947 115567 231948 115815 231948 115464 231948 115464 231949 115815 231949 115639 231949 115464 231950 115639 231950 115816 231950 115816 231951 115639 231951 115663 231951 115816 231952 115663 231952 115817 231952 115817 231953 115663 231953 115657 231953 115817 231954 115657 231954 115994 231954 115994 231955 115657 231955 115653 231955 115994 231956 115653 231956 115504 231956 115504 231957 115653 231957 115775 231957 115504 231958 115775 231958 115505 231958 115505 231959 115775 231959 115638 231959 115505 231960 115638 231960 115507 231960 115507 231961 115638 231961 115819 231961 115507 231962 115819 231962 115818 231962 115818 231963 115819 231963 115820 231963 115818 231964 115820 231964 115509 231964 115841 231965 118898 231965 115821 231965 115822 231966 115825 231966 115866 231966 118325 231967 115823 231967 115861 231967 115824 231968 115825 231968 115826 231968 115826 231969 115825 231969 115822 231969 115826 231970 115822 231970 118283 231970 115827 231971 115828 231971 115829 231971 115829 231972 115828 231972 115830 231972 115829 231973 115830 231973 115866 231973 115866 231974 115830 231974 115831 231974 115866 231975 115831 231975 115822 231975 115827 231976 115829 231976 114624 231976 114624 231977 115829 231977 115868 231977 114624 231978 115868 231978 114669 231978 114669 231979 115868 231979 115854 231979 114669 231980 115854 231980 115832 231980 115832 231981 115854 231981 114671 231981 114671 231982 115854 231982 115856 231982 114671 231983 115856 231983 115833 231983 115833 231984 115856 231984 115834 231984 115833 231985 115834 231985 115835 231985 115835 231986 115834 231986 114622 231986 114622 231987 115834 231987 115858 231987 114622 231988 115858 231988 114674 231988 114660 231989 114620 231989 115858 231989 115858 231990 114620 231990 115836 231990 115858 231991 115836 231991 114674 231991 115850 231992 114880 231992 115847 231992 118838 231993 115837 231993 118787 231993 118787 231994 115837 231994 115843 231994 114880 231995 115850 231995 114881 231995 114881 231996 115850 231996 115837 231996 114881 231997 115837 231997 114619 231997 114619 231998 115837 231998 118838 231998 114619 231999 118838 231999 118837 231999 118837 232000 115838 232000 114619 232000 114619 232001 115838 232001 115839 232001 114619 232002 115839 232002 115821 232002 115821 232003 115839 232003 115840 232003 115821 232004 115840 232004 115841 232004 115843 232005 115842 232005 118802 232005 118802 232006 118786 232006 115843 232006 115843 232007 118786 232007 118811 232007 115843 232008 118811 232008 118787 232008 115966 232009 115842 232009 118663 232009 118663 232010 115842 232010 115843 232010 118663 232011 115843 232011 115844 232011 115844 232012 115843 232012 115845 232012 115845 232013 115843 232013 118670 232013 118670 232014 115843 232014 115837 232014 118670 232015 115837 232015 118659 232015 115852 232016 115848 232016 115846 232016 115846 232017 115848 232017 114660 232017 115846 232018 114660 232018 115851 232018 115851 232019 114660 232019 115858 232019 115851 232020 115858 232020 115898 232020 115894 232021 115850 232021 115852 232021 115852 232022 115850 232022 115847 232022 115852 232023 115847 232023 115848 232023 115894 232024 115893 232024 115850 232024 115850 232025 115893 232025 115849 232025 115850 232026 115849 232026 115837 232026 115837 232027 115849 232027 115891 232027 115837 232028 115891 232028 118659 232028 115898 232029 115897 232029 115851 232029 115851 232030 115897 232030 115895 232030 115851 232031 115895 232031 115846 232031 115846 232032 115895 232032 115889 232032 115846 232033 115889 232033 115852 232033 115852 232034 115889 232034 115853 232034 115852 232035 115853 232035 115894 232035 115854 232036 115855 232036 115856 232036 115856 232037 115855 232037 115900 232037 115856 232038 115900 232038 115834 232038 115834 232039 115900 232039 115857 232039 115834 232040 115857 232040 115858 232040 115858 232041 115857 232041 115899 232041 115858 232042 115899 232042 115898 232042 115864 232043 115867 232043 115859 232043 115859 232044 115867 232044 115861 232044 115859 232045 115861 232045 115860 232045 115860 232046 115861 232046 115823 232046 115860 232047 115823 232047 118319 232047 115906 232048 115862 232048 115863 232048 115863 232049 115862 232049 115864 232049 115863 232050 115864 232050 115865 232050 115865 232051 115864 232051 115859 232051 115865 232052 115859 232052 115904 232052 115904 232053 115859 232053 115860 232053 115904 232054 115860 232054 115915 232054 115915 232055 115860 232055 118319 232055 115824 232056 118325 232056 115825 232056 115825 232057 118325 232057 115861 232057 115825 232058 115861 232058 115866 232058 115866 232059 115861 232059 115867 232059 115866 232060 115867 232060 115829 232060 115829 232061 115867 232061 115864 232061 115829 232062 115864 232062 115868 232062 115868 232063 115864 232063 115862 232063 115868 232064 115862 232064 115854 232064 115854 232065 115862 232065 115906 232065 115854 232066 115906 232066 115855 232066 115896 232067 115873 232067 115889 232067 118689 232068 118659 232068 115891 232068 118689 232069 115891 232069 118684 232069 115869 232070 118696 232070 115872 232070 115872 232071 118696 232071 118695 232071 114422 232072 118641 232072 115871 232072 115871 232073 118641 232073 115870 232073 115870 232074 118626 232074 115871 232074 115871 232075 118626 232075 118678 232075 115871 232076 118678 232076 115872 232076 115872 232077 118678 232077 118679 232077 115872 232078 118679 232078 115869 232078 115892 232079 115888 232079 115890 232079 115890 232080 115888 232080 114175 232080 114175 232081 115873 232081 114279 232081 114279 232082 115873 232082 115896 232082 114279 232083 115896 232083 114277 232083 114277 232084 115896 232084 115875 232084 114277 232085 115875 232085 114275 232085 114173 232086 114174 232086 115874 232086 115874 232087 114174 232087 115876 232087 115874 232088 115876 232088 115875 232088 115875 232089 115876 232089 115877 232089 115875 232090 115877 232090 114275 232090 114269 232091 115878 232091 115907 232091 115907 232092 115878 232092 114172 232092 114170 232093 115901 232093 115880 232093 115880 232094 115901 232094 115879 232094 115881 232095 114168 232095 115879 232095 115879 232096 114168 232096 114167 232096 115879 232097 114167 232097 115880 232097 115879 232098 115902 232098 115881 232098 115881 232099 115902 232099 115882 232099 115881 232100 115882 232100 115883 232100 118344 232101 115884 232101 115882 232101 115882 232102 115884 232102 115885 232102 115882 232103 115885 232103 115883 232103 115883 232104 115885 232104 118380 232104 115883 232105 118380 232105 118373 232105 115907 232106 115855 232106 115886 232106 115886 232107 115855 232107 115910 232107 114173 232108 115874 232108 114172 232108 114172 232109 115874 232109 115887 232109 114172 232110 115887 232110 115907 232110 115907 232111 115887 232111 115900 232111 115907 232112 115900 232112 115855 232112 114175 232113 115888 232113 115873 232113 115873 232114 115888 232114 115853 232114 115873 232115 115853 232115 115889 232115 115890 232116 115871 232116 115892 232116 115892 232117 115871 232117 115872 232117 115892 232118 115872 232118 115891 232118 115891 232119 115872 232119 118695 232119 115891 232120 118695 232120 118684 232120 115891 232121 115849 232121 115892 232121 115892 232122 115849 232122 115893 232122 115892 232123 115893 232123 115888 232123 115888 232124 115893 232124 115894 232124 115888 232125 115894 232125 115853 232125 115889 232126 115895 232126 115896 232126 115896 232127 115895 232127 115897 232127 115896 232128 115897 232128 115875 232128 115875 232129 115897 232129 115898 232129 115875 232130 115898 232130 115874 232130 115874 232131 115898 232131 115899 232131 115874 232132 115899 232132 115887 232132 115887 232133 115899 232133 115857 232133 115887 232134 115857 232134 115900 232134 114170 232135 115908 232135 115901 232135 115901 232136 115908 232136 115909 232136 115901 232137 115909 232137 115879 232137 115879 232138 115909 232138 115911 232138 115879 232139 115911 232139 115902 232139 115902 232140 115911 232140 115913 232140 115902 232141 115913 232141 115882 232141 115882 232142 115913 232142 115903 232142 115882 232143 115903 232143 118344 232143 115915 232144 115914 232144 115904 232144 115904 232145 115914 232145 115905 232145 115904 232146 115905 232146 115865 232146 115865 232147 115905 232147 115912 232147 115865 232148 115912 232148 115863 232148 115863 232149 115912 232149 115910 232149 115863 232150 115910 232150 115906 232150 115906 232151 115910 232151 115855 232151 114269 232152 115907 232152 115908 232152 115908 232153 115907 232153 115886 232153 115908 232154 115886 232154 115909 232154 115909 232155 115886 232155 115910 232155 115909 232156 115910 232156 115911 232156 115911 232157 115910 232157 115912 232157 115911 232158 115912 232158 115913 232158 115913 232159 115912 232159 115905 232159 115913 232160 115905 232160 115903 232160 115903 232161 115905 232161 115914 232161 115903 232162 115914 232162 118344 232162 118344 232163 115914 232163 115915 232163 118344 232164 115915 232164 118319 232164 117426 232165 115921 232165 115922 232165 115916 232166 115921 232166 115917 232166 115917 232167 115921 232167 117421 232167 115917 232168 117421 232168 115942 232168 115942 232169 117421 232169 115918 232169 115942 232170 115918 232170 115919 232170 115916 232171 115920 232171 115921 232171 115921 232172 115920 232172 118517 232172 115921 232173 118517 232173 115922 232173 118517 232174 118536 232174 115922 232174 115922 232175 118536 232175 118529 232175 115922 232176 118529 232176 115923 232176 115923 232177 118529 232177 118601 232177 117426 232178 115922 232178 117425 232178 117425 232179 115922 232179 114176 232179 117425 232180 114176 232180 115924 232180 115924 232181 114176 232181 114292 232181 115924 232182 114292 232182 117462 232182 117462 232183 114292 232183 114144 232183 117462 232184 114144 232184 115925 232184 114144 232185 114291 232185 115925 232185 115925 232186 114291 232186 115926 232186 115925 232187 115926 232187 115928 232187 115928 232188 115926 232188 115927 232188 115928 232189 115927 232189 117465 232189 115927 232190 115929 232190 117465 232190 117465 232191 115929 232191 114180 232191 117465 232192 114180 232192 117466 232192 114180 232193 114179 232193 117466 232193 117466 232194 114179 232194 114178 232194 117466 232195 114178 232195 115930 232195 115930 232196 114178 232196 115931 232196 115930 232197 115931 232197 117492 232197 117492 232198 115931 232198 115932 232198 117492 232199 115932 232199 117491 232199 115932 232200 115933 232200 117491 232200 117491 232201 115933 232201 115934 232201 117491 232202 115934 232202 115935 232202 115935 232203 115934 232203 114421 232203 115935 232204 114421 232204 115936 232204 115936 232205 114421 232205 115937 232205 115936 232206 115937 232206 115938 232206 115939 232207 113632 232207 115940 232207 115953 232208 113566 232208 115959 232208 118785 232209 115842 232209 115966 232209 115940 232210 113632 232210 117500 232210 117500 232211 113632 232211 113631 232211 117500 232212 113631 232212 113629 232212 113568 232213 115960 232213 115941 232213 115941 232214 115960 232214 115962 232214 118475 232215 118476 232215 115948 232215 115948 232216 118476 232216 115942 232216 115948 232217 115942 232217 113572 232217 113572 232218 115942 232218 115919 232218 113572 232219 115919 232219 113574 232219 113574 232220 115919 232220 115943 232220 113574 232221 115943 232221 113575 232221 115940 232222 115944 232222 115939 232222 115939 232223 115944 232223 118825 232223 115939 232224 118825 232224 113634 232224 113568 232225 115941 232225 115945 232225 115945 232226 115941 232226 118473 232226 115945 232227 118473 232227 115946 232227 115946 232228 118473 232228 115947 232228 115946 232229 115947 232229 115948 232229 115948 232230 115947 232230 115949 232230 115948 232231 115949 232231 118475 232231 118544 232232 115950 232232 115951 232232 115951 232233 115950 232233 118547 232233 115951 232234 118547 232234 113637 232234 113637 232235 118547 232235 115954 232235 118825 232236 118769 232236 113634 232236 113634 232237 118769 232237 118768 232237 113634 232238 118768 232238 113636 232238 115952 232239 118710 232239 115966 232239 115953 232240 115959 232240 115960 232240 115954 232241 115955 232241 113637 232241 113637 232242 115955 232242 118573 232242 113637 232243 118573 232243 115963 232243 118768 232244 115956 232244 113636 232244 113636 232245 115956 232245 118740 232245 113636 232246 118740 232246 115957 232246 118710 232247 118712 232247 115966 232247 115966 232248 118712 232248 118784 232248 115966 232249 118784 232249 118785 232249 115963 232250 115962 232250 115958 232250 115959 232251 117331 232251 115960 232251 115960 232252 117331 232252 115961 232252 115960 232253 115961 232253 115962 232253 115962 232254 115961 232254 117329 232254 115962 232255 117329 232255 115958 232255 115958 232256 117387 232256 115963 232256 115963 232257 117387 232257 117386 232257 115963 232258 117386 232258 113637 232258 113637 232259 117386 232259 117385 232259 113637 232260 117385 232260 115964 232260 115964 232261 117385 232261 115965 232261 115964 232262 115965 232262 117382 232262 115957 232263 115952 232263 113636 232263 113636 232264 115952 232264 115966 232264 113636 232265 115966 232265 115951 232265 115951 232266 115966 232266 118615 232266 115951 232267 118615 232267 118544 232267 115967 232268 118197 232268 115992 232268 115968 232269 115969 232269 118201 232269 118201 232270 115967 232270 115968 232270 115968 232271 115967 232271 115992 232271 115968 232272 115992 232272 114931 232272 114931 232273 115992 232273 115970 232273 114931 232274 115970 232274 114930 232274 114930 232275 115970 232275 115971 232275 115971 232276 115970 232276 115972 232276 115972 232277 115970 232277 115973 232277 115972 232278 115973 232278 115064 232278 115064 232279 115973 232279 115974 232279 115064 232280 115974 232280 114926 232280 115978 232281 115043 232281 115989 232281 115989 232282 115043 232282 115975 232282 115989 232283 115975 232283 115990 232283 115990 232284 115975 232284 115976 232284 115990 232285 115976 232285 115974 232285 115974 232286 115976 232286 114927 232286 115974 232287 114927 232287 114926 232287 115988 232288 115977 232288 115978 232288 115978 232289 115977 232289 114917 232289 115978 232290 114917 232290 115043 232290 115984 232291 115979 232291 115988 232291 115988 232292 115979 232292 115148 232292 115988 232293 115148 232293 115977 232293 115983 232294 115980 232294 115981 232294 115981 232295 115980 232295 116049 232295 115981 232296 116049 232296 116033 232296 115981 232297 115982 232297 115983 232297 115983 232298 115982 232298 114925 232298 115983 232299 114925 232299 115984 232299 115984 232300 114925 232300 115150 232300 115984 232301 115150 232301 115979 232301 116000 232302 116049 232302 116001 232302 116001 232303 116049 232303 115980 232303 116001 232304 115980 232304 115985 232304 115985 232305 115980 232305 115983 232305 115985 232306 115983 232306 115986 232306 115986 232307 115983 232307 115984 232307 115986 232308 115984 232308 115987 232308 115987 232309 115984 232309 115988 232309 115987 232310 115988 232310 116003 232310 116003 232311 115988 232311 115978 232311 116003 232312 115978 232312 116004 232312 116004 232313 115978 232313 115989 232313 116004 232314 115989 232314 116005 232314 116005 232315 115989 232315 115990 232315 116005 232316 115990 232316 115991 232316 115991 232317 115990 232317 115974 232317 115991 232318 115974 232318 116008 232318 116008 232319 115974 232319 115973 232319 116008 232320 115973 232320 116009 232320 116009 232321 115973 232321 115970 232321 116009 232322 115970 232322 116010 232322 116010 232323 115970 232323 115992 232323 116010 232324 115992 232324 118199 232324 118199 232325 115992 232325 118197 232325 118143 232326 115498 232326 115997 232326 115993 232327 116047 232327 115998 232327 115998 232328 115999 232328 115993 232328 115993 232329 115999 232329 116002 232329 115993 232330 116002 232330 115994 232330 115994 232331 116002 232331 115995 232331 115994 232332 115995 232332 115817 232332 116022 232333 115463 232333 115995 232333 115995 232334 115463 232334 115816 232334 115995 232335 115816 232335 115817 232335 115996 232336 115997 232336 116012 232336 116012 232337 115997 232337 116011 232337 115996 232338 118166 232338 115997 232338 115997 232339 118166 232339 118142 232339 115997 232340 118142 232340 118143 232340 115998 232341 116000 232341 115999 232341 115999 232342 116000 232342 116001 232342 115999 232343 116001 232343 116002 232343 116002 232344 116001 232344 115985 232344 116002 232345 115985 232345 115995 232345 115995 232346 115985 232346 115986 232346 115995 232347 115986 232347 116022 232347 116022 232348 115986 232348 115987 232348 116022 232349 115987 232349 116021 232349 116021 232350 115987 232350 116003 232350 116021 232351 116003 232351 116019 232351 116019 232352 116003 232352 116004 232352 116019 232353 116004 232353 116017 232353 116017 232354 116004 232354 116005 232354 116017 232355 116005 232355 116006 232355 116006 232356 116005 232356 115991 232356 116006 232357 115991 232357 116007 232357 116007 232358 115991 232358 116008 232358 116007 232359 116008 232359 116012 232359 116012 232360 116008 232360 116009 232360 116012 232361 116009 232361 115996 232361 115996 232362 116009 232362 116010 232362 115996 232363 116010 232363 118166 232363 118166 232364 116010 232364 118199 232364 116011 232365 115501 232365 116012 232365 116012 232366 115501 232366 116013 232366 116012 232367 116013 232367 116007 232367 116007 232368 116013 232368 116014 232368 116007 232369 116014 232369 116006 232369 116006 232370 116014 232370 115503 232370 115503 232371 116015 232371 116006 232371 116006 232372 116015 232372 116016 232372 116006 232373 116016 232373 116017 232373 116017 232374 116016 232374 116018 232374 116017 232375 116018 232375 116019 232375 116019 232376 116018 232376 115577 232376 116019 232377 115577 232377 116021 232377 115577 232378 116020 232378 116021 232378 116021 232379 116020 232379 115566 232379 116021 232380 115566 232380 116022 232380 116022 232381 115566 232381 115565 232381 116022 232382 115565 232382 115463 232382 116023 232383 116024 232383 112437 232383 112437 232384 116024 232384 116025 232384 112437 232385 116025 232385 116026 232385 116026 232386 116025 232386 117231 232386 116026 232387 117231 232387 116030 232387 112433 232388 116027 232388 116023 232388 116023 232389 116027 232389 116028 232389 116023 232390 116028 232390 116024 232390 117231 232391 116029 232391 116030 232391 116030 232392 116029 232392 116032 232392 116030 232393 116032 232393 116031 232393 116031 232394 116032 232394 116033 232394 116031 232395 116033 232395 116034 232395 116034 232396 116033 232396 116035 232396 116039 232397 112442 232397 116036 232397 116036 232398 112442 232398 112440 232398 116036 232399 112440 232399 116037 232399 116055 232400 116041 232400 117296 232400 116053 232401 116054 232401 112433 232401 112433 232402 116054 232402 116038 232402 112433 232403 116038 232403 116027 232403 116039 232404 117271 232404 112442 232404 112442 232405 117271 232405 117274 232405 112442 232406 117274 232406 112443 232406 112443 232407 117274 232407 116040 232407 112443 232408 116040 232408 116052 232408 117296 232409 116041 232409 117261 232409 117261 232410 116041 232410 116042 232410 117261 232411 116042 232411 116043 232411 116043 232412 116042 232412 116044 232412 116043 232413 116044 232413 117257 232413 117257 232414 116044 232414 116045 232414 117257 232415 116045 232415 116047 232415 116045 232416 116046 232416 116047 232416 116047 232417 116046 232417 116048 232417 116047 232418 116048 232418 115998 232418 115998 232419 116048 232419 112385 232419 115998 232420 112385 232420 116000 232420 116000 232421 112385 232421 112384 232421 116000 232422 112384 232422 116049 232422 116049 232423 112384 232423 116058 232423 116049 232424 116058 232424 116033 232424 116040 232425 116050 232425 116052 232425 116052 232426 116050 232426 116051 232426 116052 232427 116051 232427 116053 232427 116053 232428 116051 232428 117234 232428 116053 232429 117234 232429 116054 232429 117296 232430 117295 232430 116055 232430 116055 232431 117295 232431 116056 232431 116055 232432 116056 232432 112381 232432 112381 232433 116056 232433 117278 232433 112381 232434 117278 232434 112382 232434 112382 232435 117278 232435 116057 232435 112382 232436 116057 232436 112383 232436 112383 232437 116057 232437 116059 232437 112383 232438 116059 232438 116058 232438 116058 232439 116059 232439 116060 232439 116058 232440 116060 232440 116061 232440 116061 232441 116062 232441 116058 232441 116058 232442 116062 232442 117319 232442 116058 232443 117319 232443 116033 232443 116033 232444 117319 232444 116037 232444 116033 232445 116037 232445 116035 232445 116035 232446 116037 232446 112440 232446 118046 232447 118058 232447 116071 232447 116063 232448 116064 232448 116065 232448 116063 232449 116065 232449 116890 232449 116890 232450 116065 232450 118036 232450 116890 232451 118036 232451 116066 232451 118036 232452 118031 232452 116066 232452 116066 232453 118031 232453 118030 232453 116066 232454 118030 232454 116881 232454 116071 232455 116072 232455 116881 232455 116881 232456 118030 232456 116071 232456 116071 232457 118030 232457 118044 232457 116071 232458 118044 232458 118046 232458 116067 232459 116068 232459 116069 232459 116069 232460 116068 232460 116070 232460 116069 232461 116070 232461 116071 232461 116071 232462 116070 232462 116919 232462 116071 232463 116919 232463 116072 232463 116069 232464 115225 232464 116067 232464 116067 232465 115225 232465 115224 232465 116067 232466 115224 232466 116918 232466 115224 232467 114959 232467 116918 232467 116918 232468 114959 232468 116073 232468 116918 232469 116073 232469 116924 232469 116924 232470 116073 232470 114961 232470 116924 232471 114961 232471 116925 232471 116925 232472 114961 232472 116074 232472 116925 232473 116074 232473 116075 232473 116074 232474 115171 232474 116075 232474 116075 232475 115171 232475 116076 232475 116075 232476 116076 232476 116962 232476 116076 232477 116077 232477 116962 232477 116962 232478 116077 232478 116078 232478 116962 232479 116078 232479 116079 232479 116079 232480 116078 232480 115169 232480 115169 232481 115168 232481 116079 232481 116079 232482 115168 232482 116080 232482 116079 232483 116080 232483 116960 232483 116960 232484 116080 232484 116081 232484 116960 232485 116081 232485 116976 232485 116976 232486 116081 232486 114966 232486 116976 232487 114966 232487 116091 232487 116091 232488 114966 232488 114968 232488 116091 232489 114968 232489 116083 232489 116097 232490 112256 232490 117009 232490 116082 232491 116091 232491 119177 232491 119177 232492 116091 232492 116083 232492 119177 232493 116083 232493 119172 232493 117009 232494 112256 232494 117010 232494 116098 232495 119169 232495 116084 232495 114973 232496 117003 232496 115080 232496 115080 232497 117003 232497 117002 232497 115080 232498 117002 232498 116085 232498 116085 232499 117002 232499 117005 232499 116085 232500 117005 232500 114971 232500 114971 232501 117005 232501 116086 232501 114971 232502 116086 232502 116087 232502 116086 232503 117001 232503 116087 232503 116087 232504 117001 232504 117038 232504 116087 232505 117038 232505 116088 232505 116088 232506 117038 232506 116089 232506 119172 232507 116083 232507 119173 232507 119173 232508 116083 232508 116103 232508 119173 232509 116103 232509 116104 232509 116082 232510 116090 232510 116091 232510 116091 232511 116090 232511 116092 232511 116091 232512 116092 232512 116095 232512 116095 232513 116092 232513 116093 232513 116095 232514 116093 232514 116094 232514 116094 232515 112255 232515 116095 232515 116095 232516 112255 232516 116096 232516 116095 232517 116096 232517 117009 232517 117009 232518 116096 232518 112252 232518 117009 232519 112252 232519 116097 232519 116084 232520 116089 232520 116098 232520 116098 232521 116089 232521 117038 232521 116098 232522 117038 232522 116099 232522 116099 232523 117038 232523 116100 232523 116099 232524 116100 232524 112256 232524 112256 232525 116100 232525 116101 232525 112256 232526 116101 232526 117010 232526 119169 232527 119171 232527 116084 232527 116084 232528 119171 232528 116102 232528 116084 232529 116102 232529 116103 232529 116103 232530 116102 232530 119176 232530 116103 232531 119176 232531 116104 232531 116105 232532 116118 232532 116106 232532 116105 232533 116106 232533 116108 232533 115474 232534 116107 232534 116112 232534 116106 232535 119122 232535 116108 232535 116108 232536 119122 232536 119123 232536 116108 232537 119123 232537 116109 232537 119125 232538 119133 232538 116110 232538 116110 232539 119133 232539 119135 232539 116110 232540 119135 232540 116111 232540 116112 232541 116107 232541 117096 232541 117096 232542 116107 232542 115776 232542 117096 232543 115776 232543 116118 232543 112297 232544 116117 232544 112293 232544 112293 232545 116117 232545 115703 232545 112293 232546 115703 232546 116122 232546 119125 232547 116110 232547 119126 232547 119126 232548 116110 232548 116113 232548 119126 232549 116113 232549 119128 232549 119135 232550 116114 232550 116111 232550 116111 232551 116114 232551 112291 232551 116111 232552 112291 232552 116115 232552 116115 232553 112291 232553 112296 232553 117101 232554 116143 232554 116116 232554 116116 232555 116143 232555 115585 232555 116116 232556 115585 232556 117100 232556 117100 232557 115585 232557 115474 232557 117100 232558 115474 232558 117097 232558 117097 232559 115474 232559 116112 232559 112297 232560 116106 232560 116117 232560 116117 232561 116106 232561 116118 232561 116117 232562 116118 232562 115741 232562 115741 232563 116118 232563 115776 232563 119123 232564 116119 232564 116109 232564 116109 232565 116119 232565 119132 232565 116109 232566 119132 232566 116113 232566 116113 232567 119132 232567 119129 232567 116113 232568 119129 232568 119128 232568 112296 232569 112295 232569 116115 232569 116115 232570 112295 232570 116120 232570 116115 232571 116120 232571 115703 232571 115703 232572 116120 232572 116121 232572 115703 232573 116121 232573 116122 232573 117225 232574 117257 232574 116047 232574 116124 232575 115461 232575 116123 232575 116123 232576 115461 232576 117145 232576 116123 232577 117195 232577 116124 232577 116124 232578 117195 232578 116125 232578 116124 232579 116125 232579 115820 232579 115820 232580 116125 232580 116126 232580 115820 232581 116126 232581 115509 232581 115509 232582 116126 232582 116127 232582 115509 232583 116127 232583 115508 232583 116127 232584 117210 232584 115508 232584 115508 232585 117210 232585 117218 232585 115508 232586 117218 232586 116047 232586 116047 232587 117218 232587 117216 232587 116047 232588 117216 232588 117225 232588 115461 232589 115611 232589 117145 232589 117145 232590 115611 232590 115612 232590 117145 232591 115612 232591 117146 232591 117146 232592 115612 232592 116128 232592 117146 232593 116128 232593 117148 232593 117148 232594 116128 232594 116129 232594 117148 232595 116129 232595 117149 232595 117149 232596 116129 232596 116130 232596 117149 232597 116130 232597 116131 232597 116130 232598 115632 232598 116131 232598 116131 232599 115632 232599 116132 232599 116131 232600 116132 232600 117150 232600 117150 232601 116132 232601 116133 232601 117150 232602 116133 232602 116134 232602 116134 232603 116133 232603 115510 232603 115510 232604 119017 232604 116134 232604 116134 232605 119017 232605 119016 232605 116134 232606 119016 232606 116135 232606 116135 232607 119016 232607 116136 232607 116136 232608 116137 232608 116135 232608 116135 232609 116137 232609 116138 232609 116135 232610 116138 232610 117153 232610 117153 232611 116138 232611 116139 232611 117153 232612 116139 232612 116140 232612 116140 232613 116139 232613 116141 232613 116140 232614 116141 232614 117101 232614 117101 232615 116141 232615 116142 232615 117101 232616 116142 232616 116143 232616 116143 232617 116142 232617 118991 232617 116143 232618 118991 232618 116144 232618 117485 232619 116177 232619 117459 232619 117459 232620 116177 232620 116146 232620 117459 232621 116146 232621 116145 232621 116145 232622 116146 232622 116982 232622 116145 232623 116982 232623 117458 232623 117458 232624 116982 232624 116979 232624 117458 232625 116979 232625 117457 232625 117457 232626 116979 232626 116147 232626 117457 232627 116147 232627 117456 232627 117456 232628 116147 232628 116978 232628 117456 232629 116978 232629 117455 232629 117455 232630 116978 232630 116977 232630 117455 232631 116977 232631 116148 232631 116148 232632 116977 232632 116149 232632 116148 232633 116149 232633 116536 232633 116150 232634 117709 232634 117733 232634 116150 232635 117733 232635 117089 232635 117089 232636 117733 232636 116151 232636 117089 232637 116151 232637 117087 232637 117087 232638 116151 232638 116152 232638 117087 232639 116152 232639 116153 232639 116153 232640 116152 232640 117086 232640 117086 232641 116152 232641 117735 232641 117086 232642 117735 232642 116154 232642 116154 232643 117735 232643 117737 232643 116154 232644 117737 232644 116155 232644 116155 232645 117737 232645 117739 232645 116155 232646 117739 232646 117084 232646 117084 232647 117739 232647 117741 232647 117084 232648 117741 232648 116157 232648 117741 232649 116156 232649 116157 232649 116157 232650 116156 232650 117687 232650 116157 232651 117687 232651 117047 232651 117047 232652 117687 232652 116158 232652 117047 232653 116158 232653 117046 232653 116158 232654 116159 232654 117046 232654 117046 232655 116159 232655 117690 232655 117046 232656 117690 232656 117044 232656 117044 232657 117690 232657 116160 232657 116160 232658 117690 232658 117691 232658 116160 232659 117691 232659 116161 232659 116161 232660 117691 232660 116163 232660 116161 232661 116163 232661 116162 232661 116162 232662 116163 232662 117029 232662 117029 232663 116163 232663 117693 232663 117029 232664 117693 232664 117026 232664 117026 232665 117693 232665 116164 232665 117026 232666 116164 232666 116166 232666 116166 232667 116164 232667 116165 232667 116166 232668 116165 232668 117023 232668 117023 232669 116165 232669 116167 232669 117023 232670 116167 232670 116168 232670 115279 232671 116963 232671 117638 232671 117638 232672 116963 232672 116967 232672 117638 232673 116967 232673 117637 232673 117637 232674 116967 232674 116973 232674 117637 232675 116973 232675 116169 232675 116169 232676 116973 232676 116170 232676 116169 232677 116170 232677 117623 232677 117623 232678 116170 232678 117020 232678 117623 232679 117020 232679 116168 232679 116168 232680 117020 232680 117021 232680 116168 232681 117021 232681 117023 232681 117596 232682 116171 232682 116172 232682 116177 232683 117485 232683 117488 232683 116173 232684 116174 232684 117495 232684 117495 232685 116174 232685 117051 232685 117495 232686 117051 232686 116175 232686 116175 232687 117051 232687 116176 232687 116175 232688 116176 232688 117488 232688 117488 232689 116176 232689 117058 232689 117488 232690 117058 232690 116177 232690 116181 232691 116178 232691 116179 232691 116179 232692 116178 232692 116174 232692 116179 232693 116174 232693 116180 232693 116180 232694 116174 232694 116173 232694 116179 232695 117525 232695 116181 232695 116181 232696 117525 232696 117524 232696 116181 232697 117524 232697 116182 232697 116182 232698 117524 232698 116183 232698 116182 232699 116183 232699 117129 232699 117129 232700 116183 232700 116184 232700 117129 232701 116184 232701 116185 232701 116185 232702 116184 232702 116187 232702 116185 232703 116187 232703 116186 232703 116186 232704 116187 232704 117539 232704 116186 232705 117539 232705 117127 232705 117127 232706 117539 232706 116188 232706 117127 232707 116188 232707 117542 232707 117592 232708 117169 232708 116189 232708 116189 232709 117169 232709 116190 232709 116189 232710 116190 232710 117589 232710 117589 232711 116190 232711 117171 232711 117589 232712 117171 232712 117587 232712 117587 232713 117171 232713 117173 232713 117587 232714 117173 232714 116191 232714 116191 232715 117173 232715 117176 232715 116191 232716 117176 232716 117546 232716 117546 232717 117176 232717 117124 232717 117546 232718 117124 232718 117545 232718 117545 232719 117124 232719 116193 232719 117545 232720 116193 232720 116192 232720 116192 232721 116193 232721 116194 232721 116192 232722 116194 232722 117542 232722 117542 232723 116194 232723 116195 232723 117542 232724 116195 232724 117127 232724 117596 232725 116172 232725 117595 232725 117595 232726 116172 232726 117166 232726 117595 232727 117166 232727 117592 232727 117592 232728 117166 232728 117167 232728 117592 232729 117167 232729 117169 232729 117187 232730 117747 232730 117134 232730 117134 232731 117747 232731 117709 232731 117134 232732 117709 232732 116150 232732 116202 232733 114009 232733 116201 232733 114416 232734 116196 232734 115938 232734 115938 232735 116196 232735 113999 232735 115938 232736 113999 232736 116199 232736 116201 232737 114009 232737 116197 232737 116197 232738 114009 232738 116198 232738 116197 232739 116198 232739 117508 232739 117508 232740 116198 232740 113989 232740 117508 232741 113989 232741 117534 232741 116199 232742 114000 232742 115938 232742 115938 232743 114000 232743 114003 232743 115938 232744 114003 232744 115936 232744 115936 232745 114003 232745 114002 232745 115936 232746 114002 232746 116200 232746 116200 232747 114005 232747 115936 232747 115936 232748 114005 232748 114006 232748 115936 232749 114006 232749 116201 232749 116201 232750 114006 232750 114007 232750 116201 232751 114007 232751 116202 232751 113994 232752 114415 232752 116204 232752 116204 232753 114415 232753 114414 232753 116204 232754 114414 232754 114182 232754 113994 232755 113995 232755 114415 232755 114415 232756 113995 232756 113996 232756 114415 232757 113996 232757 114416 232757 114416 232758 113996 232758 113998 232758 114416 232759 113998 232759 116196 232759 114182 232760 116203 232760 116204 232760 116204 232761 116203 232761 117514 232761 116204 232762 117514 232762 116205 232762 116205 232763 117514 232763 117515 232763 116205 232764 117515 232764 113992 232764 113992 232765 117515 232765 117534 232765 113992 232766 117534 232766 113990 232766 113990 232767 117534 232767 113989 232767 116206 232768 117562 232768 116207 232768 116207 232769 117562 232769 117543 232769 116207 232770 117543 232770 114186 232770 114186 232771 117543 232771 116208 232771 114186 232772 116208 232772 116209 232772 116209 232773 116208 232773 117511 232773 116209 232774 117511 232774 116203 232774 116203 232775 117511 232775 117513 232775 116203 232776 117513 232776 117514 232776 113983 232777 113982 232777 116247 232777 116231 232778 114592 232778 114591 232778 116210 232779 116211 232779 116212 232779 116212 232780 116211 232780 116214 232780 116212 232781 116214 232781 116213 232781 116213 232782 116214 232782 116215 232782 116214 232783 119494 232783 116215 232783 116215 232784 119494 232784 116216 232784 116215 232785 116216 232785 116217 232785 116217 232786 116216 232786 116218 232786 116217 232787 116218 232787 116221 232787 116220 232788 119527 232788 116219 232788 116219 232789 119527 232789 114575 232789 116219 232790 114575 232790 114574 232790 116220 232791 116219 232791 116218 232791 116218 232792 116219 232792 119303 232792 116218 232793 119303 232793 116221 232793 119303 232794 119306 232794 116221 232794 116221 232795 119306 232795 119307 232795 116221 232796 119307 232796 117751 232796 117751 232797 119307 232797 116222 232797 117751 232798 116222 232798 116223 232798 116223 232799 116222 232799 116224 232799 116223 232800 116224 232800 117711 232800 117711 232801 116224 232801 116225 232801 116224 232802 119300 232802 116225 232802 116225 232803 119300 232803 116226 232803 116225 232804 116226 232804 117714 232804 117714 232805 116226 232805 112248 232805 117714 232806 112248 232806 116227 232806 116227 232807 112248 232807 116228 232807 116227 232808 116228 232808 116229 232808 116229 232809 116228 232809 116230 232809 116229 232810 116230 232810 116233 232810 116231 232811 114591 232811 116233 232811 114595 232812 116232 232812 116240 232812 116233 232813 114591 232813 116229 232813 116229 232814 114591 232814 116235 232814 116229 232815 116235 232815 116234 232815 116234 232816 116235 232816 116236 232816 116234 232817 116236 232817 116237 232817 116237 232818 116236 232818 116238 232818 116237 232819 116238 232819 114594 232819 116239 232820 116241 232820 117717 232820 117717 232821 117718 232821 116239 232821 116239 232822 117718 232822 116237 232822 116239 232823 116237 232823 116240 232823 116240 232824 116237 232824 114594 232824 116240 232825 114594 232825 114595 232825 116241 232826 113979 232826 117717 232826 117717 232827 113979 232827 113978 232827 117717 232828 113978 232828 116242 232828 113975 232829 116245 232829 116242 232829 116242 232830 116245 232830 116243 232830 116242 232831 116243 232831 117717 232831 113975 232832 116244 232832 116245 232832 116245 232833 116244 232833 116246 232833 116245 232834 116246 232834 116268 232834 116268 232835 116246 232835 113973 232835 113973 232836 113988 232836 116268 232836 116268 232837 113988 232837 113987 232837 116268 232838 113987 232838 116247 232838 116247 232839 113987 232839 113986 232839 116247 232840 113986 232840 113983 232840 117662 232841 116248 232841 116252 232841 116258 232842 116249 232842 116257 232842 116257 232843 116249 232843 116260 232843 116263 232844 116262 232844 116250 232844 114607 232845 116256 232845 116259 232845 116248 232846 116251 232846 116252 232846 116252 232847 116251 232847 117663 232847 116252 232848 117663 232848 117665 232848 113953 232849 116265 232849 11003 232849 116267 232850 116253 232850 116254 232850 116254 232851 116253 232851 113940 232851 116254 232852 113940 232852 114780 232852 114780 232853 113940 232853 116255 232853 114780 232854 116255 232854 114747 232854 114747 232855 116255 232855 116259 232855 114747 232856 116259 232856 114606 232856 114606 232857 116259 232857 116256 232857 116257 232858 117660 232858 116258 232858 116258 232859 117660 232859 117662 232859 116258 232860 117662 232860 116259 232860 116259 232861 117662 232861 116252 232861 116259 232862 116252 232862 114607 232862 116260 232863 113942 232863 116257 232863 116257 232864 113942 232864 113943 232864 116257 232865 113943 232865 117658 232865 117658 232866 113943 232866 113944 232866 117658 232867 113944 232867 117657 232867 117657 232868 113944 232868 116261 232868 117657 232869 116261 232869 116263 232869 116263 232870 116261 232870 113947 232870 116263 232871 113947 232871 116262 232871 116250 232872 116264 232872 116263 232872 116263 232873 116264 232873 113949 232873 116263 232874 113949 232874 11003 232874 11003 232875 113949 232875 113951 232875 11003 232876 113951 232876 113953 232876 116265 232877 116266 232877 11003 232877 11003 232878 116266 232878 113955 232878 11003 232879 113955 232879 116267 232879 116267 232880 113955 232880 113957 232880 116267 232881 113957 232881 116253 232881 116268 232882 116247 232882 117666 232882 117666 232883 116247 232883 116269 232883 117666 232884 116269 232884 116270 232884 116270 232885 116269 232885 116252 232885 116270 232886 116252 232886 117667 232886 117667 232887 116252 232887 117665 232887 117607 232888 117604 232888 114571 232888 114571 232889 117604 232889 116271 232889 116271 232890 117604 232890 116272 232890 116271 232891 116272 232891 116273 232891 116273 232892 116272 232892 116274 232892 116273 232893 116274 232893 116275 232893 116275 232894 116274 232894 116276 232894 116275 232895 116276 232895 114614 232895 114614 232896 116276 232896 116277 232896 114614 232897 116277 232897 114615 232897 114610 232898 116278 232898 116281 232898 116281 232899 116278 232899 116279 232899 116281 232900 116279 232900 117628 232900 117628 232901 116279 232901 116280 232901 114615 232902 116277 232902 114616 232902 114616 232903 116277 232903 117625 232903 114616 232904 117625 232904 116280 232904 116280 232905 117625 232905 117627 232905 116280 232906 117627 232906 117628 232906 114610 232907 116281 232907 116282 232907 116282 232908 116281 232908 116284 232908 116282 232909 116284 232909 116283 232909 116283 232910 116284 232910 116263 232910 116283 232911 116263 232911 11003 232911 118860 232912 118853 232912 117548 232912 118860 232913 117548 232913 116285 232913 116286 232914 118925 232914 118890 232914 116286 232915 118890 232915 116287 232915 116287 232916 118890 232916 118892 232916 116287 232917 118892 232917 118891 232917 114571 232918 116288 232918 117607 232918 117607 232919 116288 232919 116289 232919 117607 232920 116289 232920 116290 232920 116290 232921 116289 232921 116291 232921 116290 232922 116291 232922 117547 232922 117547 232923 116291 232923 116287 232923 117547 232924 116287 232924 117548 232924 117548 232925 116287 232925 118891 232925 117548 232926 118891 232926 116285 232926 115944 232927 115940 232927 116292 232927 115944 232928 116292 232928 118853 232928 118853 232929 116292 232929 116293 232929 118853 232930 116293 232930 117548 232930 116296 232931 116294 232931 113450 232931 113450 232932 116294 232932 116295 232932 113450 232933 113449 232933 116296 232933 116296 232934 113449 232934 116297 232934 116296 232935 116297 232935 120246 232935 120246 232936 116297 232936 113446 232936 120246 232937 113446 232937 116298 232937 116298 232938 113446 232938 113444 232938 116298 232939 113444 232939 117701 232939 117701 232940 113444 232940 113443 232940 117701 232941 113443 232941 117704 232941 116299 232942 116301 232942 116300 232942 116300 232943 116301 232943 117800 232943 116317 232944 116305 232944 117875 232944 117875 232945 116305 232945 116302 232945 117875 232946 116302 232946 117877 232946 119744 232947 113509 232947 116303 232947 116303 232948 113509 232948 113508 232948 116303 232949 113508 232949 116304 232949 116304 232950 113508 232950 116305 232950 116304 232951 116305 232951 116306 232951 116306 232952 116305 232952 116317 232952 119758 232953 114522 232953 119745 232953 119745 232954 114522 232954 119507 232954 119745 232955 119507 232955 119744 232955 119744 232956 119507 232956 119491 232956 119744 232957 119491 232957 113509 232957 113509 232958 119491 232958 119492 232958 113509 232959 119492 232959 116307 232959 116307 232960 119492 232960 116308 232960 116307 232961 116308 232961 113510 232961 113510 232962 116308 232962 116211 232962 113510 232963 116211 232963 116299 232963 116299 232964 116211 232964 116210 232964 116299 232965 116210 232965 116301 232965 114482 232966 116309 232966 120273 232966 120273 232967 116309 232967 119994 232967 120273 232968 119994 232968 120258 232968 120258 232969 119994 232969 116310 232969 120258 232970 116310 232970 116294 232970 116294 232971 116310 232971 116295 232971 116295 232972 116310 232972 116311 232972 116295 232973 116311 232973 113451 232973 113451 232974 116311 232974 116312 232974 113451 232975 116312 232975 116315 232975 10504 232976 114540 232976 119740 232976 116313 232977 113451 232977 117813 232977 117813 232978 113451 232978 116314 232978 116315 232979 116320 232979 113451 232979 113451 232980 116320 232980 116316 232980 113451 232981 116316 232981 116314 232981 116317 232982 116318 232982 116306 232982 116306 232983 116318 232983 117833 232983 116306 232984 117833 232984 119743 232984 119743 232985 117833 232985 117809 232985 119743 232986 117809 232986 116316 232986 116316 232987 117809 232987 117827 232987 116316 232988 117827 232988 116314 232988 120006 232989 10504 232989 119993 232989 119993 232990 10504 232990 119740 232990 119993 232991 119740 232991 119992 232991 119992 232992 119740 232992 116316 232992 119992 232993 116316 232993 116319 232993 116319 232994 116316 232994 116320 232994 118366 232995 118148 232995 118365 232995 118365 232996 118148 232996 116321 232996 118365 232997 116321 232997 118335 232997 118335 232998 116321 232998 118170 232998 118335 232999 118170 232999 116322 232999 116322 233000 118170 233000 118193 233000 116322 233001 118193 233001 116323 233001 116323 233002 118193 233002 116324 233002 118333 233003 118106 233003 116325 233003 116325 233004 118106 233004 118105 233004 116325 233005 118105 233005 118315 233005 118315 233006 118105 233006 118107 233006 118315 233007 118107 233007 116326 233007 116326 233008 118107 233008 118081 233008 116326 233009 118081 233009 116328 233009 116328 233010 118081 233010 116327 233010 116328 233011 116327 233011 118357 233011 118357 233012 116327 233012 118082 233012 118357 233013 118082 233013 116329 233013 116329 233014 118082 233014 118083 233014 118106 233015 118333 233015 118136 233015 118136 233016 118333 233016 118288 233016 118136 233017 118288 233017 118134 233017 118134 233018 118288 233018 118218 233018 118134 233019 118218 233019 118165 233019 118165 233020 118218 233020 118163 233020 118218 233021 118217 233021 118163 233021 118163 233022 118217 233022 118215 233022 118163 233023 118215 233023 116330 233023 116330 233024 118215 233024 116331 233024 116331 233025 118227 233025 116330 233025 116330 233026 118227 233026 116333 233026 116330 233027 116333 233027 116332 233027 116332 233028 116333 233028 118161 233028 118161 233029 116333 233029 116334 233029 118161 233030 116334 233030 118160 233030 118160 233031 116334 233031 118245 233031 118160 233032 118245 233032 118159 233032 118245 233033 118233 233033 118159 233033 118159 233034 118233 233034 118249 233034 118159 233035 118249 233035 118158 233035 118249 233036 116335 233036 118158 233036 118158 233037 116335 233037 118186 233037 118186 233038 116335 233038 116336 233038 116336 233039 116335 233039 118267 233039 116336 233040 118267 233040 116337 233040 118267 233041 118254 233041 116337 233041 116337 233042 118254 233042 118252 233042 116337 233043 118252 233043 116338 233043 116338 233044 118252 233044 116339 233044 118252 233045 118251 233045 116339 233045 116339 233046 118251 233046 118271 233046 116339 233047 118271 233047 118183 233047 118183 233048 118271 233048 118303 233048 118183 233049 118303 233049 116340 233049 116340 233050 118303 233050 118305 233050 116340 233051 118305 233051 116341 233051 116341 233052 118305 233052 118306 233052 116341 233053 118306 233053 116324 233053 116324 233054 118306 233054 116342 233054 116324 233055 116342 233055 116323 233055 116343 233056 118140 233056 118401 233056 118401 233057 118140 233057 118139 233057 118401 233058 118139 233058 118398 233058 118398 233059 118139 233059 118148 233059 118398 233060 118148 233060 118366 233060 118401 233061 118400 233061 116343 233061 116343 233062 118400 233062 118389 233062 116343 233063 118389 233063 118127 233063 118127 233064 118389 233064 118442 233064 118127 233065 118442 233065 116348 233065 116350 233066 116344 233066 116345 233066 116345 233067 116344 233067 116347 233067 116345 233068 116347 233068 116346 233068 116346 233069 116347 233069 116348 233069 116346 233070 116348 233070 118461 233070 118461 233071 116348 233071 118442 233071 118409 233072 118102 233072 116349 233072 116349 233073 118102 233073 118124 233073 116349 233074 118124 233074 116350 233074 116350 233075 118124 233075 118123 233075 116350 233076 118123 233076 116344 233076 118417 233077 118101 233077 118433 233077 118433 233078 118101 233078 118102 233078 118433 233079 118102 233079 118409 233079 118440 233080 118097 233080 118419 233080 118419 233081 118097 233081 116351 233081 118419 233082 116351 233082 118417 233082 118417 233083 116351 233083 118099 233083 118417 233084 118099 233084 118101 233084 116353 233085 118095 233085 118440 233085 118440 233086 118095 233086 116352 233086 118440 233087 116352 233087 118097 233087 118440 233088 118426 233088 116353 233088 116353 233089 118426 233089 116354 233089 116353 233090 116354 233090 118093 233090 118093 233091 116354 233091 118386 233091 118093 233092 118386 233092 118073 233092 118073 233093 118386 233093 116329 233093 118073 233094 116329 233094 118083 233094 117930 233095 117926 233095 116357 233095 116355 233096 116381 233096 118693 233096 118693 233097 116381 233097 116356 233097 118693 233098 116356 233098 118694 233098 118694 233099 116356 233099 117930 233099 118694 233100 117930 233100 118703 233100 118703 233101 117930 233101 116357 233101 116358 233102 116359 233102 116370 233102 116370 233103 116359 233103 117908 233103 118506 233104 116367 233104 116360 233104 116360 233105 116367 233105 116361 233105 116360 233106 116361 233106 116392 233106 116362 233107 117946 233107 118516 233107 118516 233108 117946 233108 117949 233108 118516 233109 117949 233109 116363 233109 116363 233110 117949 233110 116365 233110 116363 233111 116365 233111 116364 233111 116364 233112 116365 233112 116367 233112 116364 233113 116367 233113 116366 233113 116366 233114 116367 233114 118506 233114 116362 233115 116368 233115 117946 233115 117946 233116 116368 233116 116369 233116 117946 233117 116369 233117 116371 233117 116371 233118 116369 233118 116370 233118 116371 233119 116370 233119 117908 233119 116359 233120 116358 233120 116372 233120 116359 233121 116372 233121 117904 233121 117904 233122 116372 233122 116374 233122 117904 233123 116374 233123 116373 233123 116373 233124 116374 233124 118580 233124 116373 233125 118580 233125 117902 233125 118580 233126 118579 233126 117902 233126 117902 233127 118579 233127 116375 233127 117902 233128 116375 233128 117901 233128 117901 233129 116375 233129 118577 233129 117901 233130 118577 233130 116376 233130 116376 233131 118577 233131 116377 233131 116376 233132 116377 233132 116379 233132 116377 233133 116378 233133 116379 233133 116379 233134 116378 233134 116380 233134 116379 233135 116380 233135 117898 233135 117898 233136 116380 233136 116397 233136 117898 233137 116397 233137 116396 233137 116381 233138 116355 233138 117965 233138 117965 233139 116355 233139 118637 233139 117965 233140 118637 233140 116382 233140 116382 233141 118637 233141 116383 233141 116382 233142 116383 233142 116384 233142 116384 233143 116383 233143 118648 233143 116384 233144 118648 233144 116385 233144 116385 233145 118648 233145 116386 233145 116385 233146 116386 233146 117968 233146 117968 233147 116386 233147 116388 233147 116388 233148 116386 233148 116387 233148 116388 233149 116387 233149 116389 233149 116389 233150 116387 233150 116390 233150 116389 233151 116390 233151 117956 233151 117956 233152 116390 233152 118535 233152 117956 233153 118535 233153 116391 233153 116391 233154 118535 233154 116392 233154 116391 233155 116392 233155 116361 233155 118617 233156 117925 233156 117922 233156 117922 233157 116393 233157 118617 233157 118617 233158 116393 233158 116394 233158 118617 233159 116394 233159 118618 233159 116394 233160 116395 233160 118618 233160 118618 233161 116395 233161 116396 233161 118618 233162 116396 233162 116397 233162 118617 233163 116398 233163 117925 233163 117925 233164 116398 233164 116399 233164 117925 233165 116399 233165 116401 233165 116401 233166 116399 233166 116400 233166 116401 233167 116400 233167 117914 233167 117914 233168 116400 233168 118677 233168 117914 233169 118677 233169 116402 233169 116402 233170 118677 233170 118656 233170 116402 233171 118656 233171 116403 233171 116403 233172 118656 233172 118655 233172 118655 233173 118688 233173 116403 233173 116403 233174 118688 233174 116357 233174 116403 233175 116357 233175 117926 233175 118839 233176 118024 233176 118840 233176 118840 233177 118024 233177 118023 233177 118840 233178 118023 233178 116404 233178 116404 233179 118023 233179 116405 233179 116406 233180 118777 233180 117992 233180 117992 233181 118777 233181 116407 233181 117992 233182 116407 233182 116408 233182 116408 233183 116407 233183 116409 233183 116408 233184 116409 233184 117995 233184 117995 233185 116409 233185 116410 233185 117995 233186 116410 233186 117996 233186 117996 233187 116410 233187 116411 233187 117996 233188 116411 233188 117998 233188 116411 233189 116412 233189 117998 233189 117998 233190 116412 233190 118726 233190 117998 233191 118726 233191 116413 233191 116413 233192 118726 233192 118709 233192 116413 233193 118709 233193 117981 233193 116414 233194 116415 233194 118757 233194 118757 233195 116415 233195 117981 233195 118757 233196 117981 233196 118709 233196 116414 233197 116416 233197 116415 233197 116415 233198 116416 233198 117999 233198 116426 233199 116404 233199 116405 233199 118028 233200 116432 233200 116417 233200 116417 233201 116432 233201 116419 233201 116417 233202 116419 233202 116418 233202 116418 233203 116419 233203 116420 233203 116418 233204 116420 233204 118064 233204 118064 233205 116420 233205 118883 233205 116427 233206 118068 233206 116421 233206 116421 233207 118068 233207 116422 233207 116421 233208 116422 233208 116423 233208 116423 233209 116422 233209 116424 233209 116423 233210 116424 233210 116425 233210 116425 233211 116424 233211 118072 233211 116425 233212 118072 233212 118883 233212 118883 233213 118072 233213 118071 233213 118883 233214 118071 233214 118064 233214 116426 233215 116405 233215 116429 233215 116421 233216 118901 233216 116427 233216 116427 233217 118901 233217 116428 233217 116427 233218 116428 233218 118049 233218 118049 233219 116428 233219 116429 233219 118049 233220 116429 233220 116430 233220 116430 233221 116429 233221 116405 233221 117999 233222 116416 233222 118021 233222 118021 233223 116416 233223 116431 233223 118021 233224 116431 233224 118040 233224 118040 233225 116431 233225 118821 233225 118040 233226 118821 233226 118037 233226 116432 233227 118028 233227 118867 233227 118867 233228 118028 233228 116433 233228 118867 233229 116433 233229 118865 233229 118865 233230 116433 233230 116434 233230 118865 233231 116434 233231 116435 233231 116435 233232 116434 233232 116436 233232 116435 233233 116436 233233 116437 233233 116437 233234 116436 233234 118034 233234 116437 233235 118034 233235 116438 233235 116438 233236 118034 233236 118033 233236 116438 233237 118033 233237 116439 233237 116439 233238 118033 233238 118037 233238 116439 233239 118037 233239 116440 233239 116440 233240 118037 233240 118821 233240 118839 233241 118789 233241 118024 233241 118024 233242 118789 233242 116442 233242 118024 233243 116442 233243 116441 233243 116441 233244 116442 233244 118788 233244 116441 233245 118788 233245 116443 233245 118788 233246 116444 233246 116443 233246 116443 233247 116444 233247 116445 233247 116443 233248 116445 233248 118007 233248 118007 233249 116445 233249 116446 233249 118007 233250 116446 233250 118018 233250 118018 233251 116446 233251 118792 233251 118018 233252 118792 233252 118019 233252 118019 233253 118792 233253 116448 233253 118019 233254 116448 233254 116447 233254 116447 233255 116448 233255 116450 233255 118777 233256 116406 233256 118770 233256 118770 233257 116406 233257 116449 233257 118770 233258 116449 233258 116450 233258 116450 233259 116449 233259 118002 233259 116450 233260 118002 233260 116447 233260 117300 233261 117841 233261 116451 233261 116451 233262 117841 233262 116452 233262 116451 233263 116452 233263 117263 233263 117263 233264 116452 233264 117872 233264 117263 233265 117872 233265 116453 233265 116453 233266 117872 233266 116454 233266 116453 233267 116454 233267 116455 233267 116455 233268 116454 233268 117879 233268 116455 233269 117879 233269 117266 233269 117266 233270 117879 233270 117881 233270 117266 233271 117881 233271 117253 233271 117253 233272 117881 233272 116456 233272 117253 233273 116456 233273 116457 233273 117841 233274 117300 233274 116458 233274 116458 233275 117300 233275 116459 233275 116458 233276 116459 233276 117828 233276 117828 233277 116459 233277 116460 233277 117828 233278 116460 233278 117824 233278 117824 233279 116460 233279 116461 233279 117824 233280 116461 233280 117822 233280 117822 233281 116461 233281 116462 233281 117822 233282 116462 233282 117816 233282 117816 233283 116462 233283 116463 233283 117816 233284 116463 233284 116464 233284 116464 233285 116463 233285 116465 233285 116464 233286 116465 233286 116466 233286 116466 233287 116465 233287 117304 233287 116466 233288 117304 233288 117795 233288 117795 233289 117304 233289 117762 233289 117762 233290 117304 233290 117285 233290 117762 233291 117285 233291 117761 233291 117761 233292 117285 233292 117287 233292 117761 233293 117287 233293 116468 233293 116468 233294 117287 233294 116467 233294 116468 233295 116467 233295 117760 233295 117760 233296 116467 233296 117290 233296 117760 233297 117290 233297 117759 233297 117759 233298 117290 233298 116469 233298 117759 233299 116469 233299 116470 233299 116469 233300 117277 233300 116470 233300 116470 233301 117277 233301 116471 233301 116470 233302 116471 233302 117756 233302 117756 233303 116471 233303 116502 233303 117756 233304 116502 233304 117770 233304 117253 233305 116457 233305 116472 233305 116472 233306 116457 233306 116473 233306 116472 233307 116473 233307 117252 233307 117252 233308 116473 233308 116474 233308 117252 233309 116474 233309 117251 233309 117251 233310 116474 233310 117851 233310 117251 233311 117851 233311 117250 233311 117250 233312 117851 233312 116475 233312 117250 233313 116475 233313 117248 233313 117248 233314 116475 233314 116476 233314 117248 233315 116476 233315 116478 233315 116478 233316 116476 233316 116477 233316 116478 233317 116477 233317 116479 233317 116479 233318 116477 233318 116480 233318 116479 233319 116480 233319 117228 233319 117228 233320 116480 233320 116492 233320 117747 233321 117187 233321 116481 233321 116481 233322 117187 233322 117186 233322 116481 233323 117186 233323 116482 233323 116482 233324 117186 233324 116483 233324 116482 233325 116483 233325 117781 233325 117781 233326 116483 233326 116484 233326 117781 233327 116484 233327 116485 233327 116484 233328 116486 233328 116485 233328 116485 233329 116486 233329 116487 233329 116485 233330 116487 233330 117808 233330 117808 233331 116487 233331 116488 233331 117808 233332 116488 233332 117806 233332 117806 233333 116488 233333 116489 233333 117806 233334 116489 233334 116490 233334 116490 233335 116489 233335 117228 233335 116490 233336 117228 233336 116491 233336 116491 233337 117228 233337 116492 233337 116493 233338 115285 233338 117212 233338 117212 233339 115285 233339 116494 233339 117212 233340 116494 233340 117221 233340 117221 233341 116494 233341 116495 233341 117221 233342 116495 233342 117211 233342 117211 233343 116495 233343 116497 233343 117211 233344 116497 233344 116496 233344 116496 233345 116497 233345 116498 233345 116496 233346 116498 233346 117208 233346 117208 233347 116498 233347 116500 233347 117208 233348 116500 233348 116499 233348 116499 233349 116500 233349 117708 233349 116499 233350 117708 233350 117258 233350 117258 233351 117708 233351 116501 233351 117258 233352 116501 233352 116502 233352 116502 233353 116501 233353 116503 233353 116502 233354 116503 233354 117770 233354 115276 233355 116803 233355 117394 233355 117394 233356 116803 233356 116791 233356 117394 233357 116791 233357 116504 233357 116504 233358 116791 233358 116505 233358 116504 233359 116505 233359 116506 233359 116506 233360 116505 233360 116512 233360 116506 233361 116512 233361 116507 233361 116508 233362 117403 233362 116513 233362 116513 233363 117403 233363 116509 233363 116513 233364 116509 233364 116510 233364 116510 233365 116509 233365 116507 233365 116510 233366 116507 233366 116511 233366 116511 233367 116507 233367 116512 233367 116508 233368 116513 233368 117437 233368 117437 233369 116513 233369 116824 233369 117437 233370 116824 233370 117436 233370 117436 233371 116824 233371 116514 233371 117436 233372 116514 233372 117434 233372 117434 233373 116514 233373 116515 233373 117434 233374 116515 233374 116517 233374 116517 233375 116515 233375 116516 233375 116517 233376 116516 233376 117432 233376 117432 233377 116516 233377 116519 233377 117432 233378 116519 233378 116518 233378 116518 233379 116519 233379 116825 233379 116518 233380 116825 233380 116520 233380 116520 233381 116825 233381 116522 233381 116520 233382 116522 233382 116521 233382 116521 233383 116522 233383 116548 233383 116834 233384 117323 233384 116523 233384 116523 233385 117323 233385 117353 233385 116523 233386 117353 233386 116879 233386 116879 233387 117353 233387 116525 233387 116879 233388 116525 233388 116524 233388 116524 233389 116525 233389 117354 233389 116524 233390 117354 233390 116878 233390 116878 233391 117354 233391 117355 233391 116878 233392 117355 233392 116876 233392 116876 233393 117355 233393 116526 233393 116876 233394 116526 233394 116874 233394 116874 233395 116526 233395 116527 233395 116874 233396 116527 233396 116528 233396 116528 233397 116527 233397 117358 233397 116528 233398 117358 233398 116900 233398 116900 233399 117358 233399 117359 233399 116831 233400 117368 233400 116530 233400 116530 233401 117368 233401 116529 233401 116530 233402 116529 233402 116531 233402 116531 233403 116529 233403 117328 233403 116531 233404 117328 233404 116532 233404 116532 233405 117328 233405 117339 233405 116532 233406 117339 233406 116533 233406 116533 233407 117339 233407 116534 233407 116533 233408 116534 233408 116833 233408 116833 233409 116534 233409 116535 233409 116833 233410 116535 233410 116834 233410 116834 233411 116535 233411 117324 233411 116834 233412 117324 233412 117323 233412 116148 233413 116536 233413 116537 233413 116537 233414 116536 233414 116959 233414 116537 233415 116959 233415 116538 233415 116538 233416 116959 233416 116539 233416 116538 233417 116539 233417 117411 233417 117411 233418 116539 233418 116948 233418 117411 233419 116948 233419 117399 233419 117399 233420 116948 233420 116542 233420 117359 233421 117378 233421 116900 233421 116900 233422 117378 233422 116540 233422 116900 233423 116540 233423 116906 233423 116906 233424 116540 233424 116541 233424 116906 233425 116541 233425 116542 233425 116542 233426 116541 233426 117400 233426 116542 233427 117400 233427 117399 233427 116543 233428 117557 233428 116884 233428 116884 233429 117557 233429 116544 233429 116884 233430 116544 233430 116889 233430 116889 233431 116544 233431 116545 233431 116889 233432 116545 233432 116899 233432 116899 233433 116545 233433 116546 233433 116899 233434 116546 233434 116898 233434 116546 233435 117561 233435 116898 233435 116898 233436 117561 233436 117505 233436 116898 233437 117505 233437 116844 233437 116844 233438 117505 233438 116547 233438 116844 233439 116547 233439 116548 233439 116548 233440 116547 233440 116549 233440 116548 233441 116549 233441 116521 233441 112726 233442 116557 233442 116550 233442 116550 233443 116557 233443 114135 233443 116550 233444 114135 233444 112728 233444 112728 233445 114135 233445 114128 233445 112728 233446 114128 233446 112729 233446 112729 233447 114128 233447 114129 233447 112729 233448 114129 233448 116551 233448 116551 233449 114129 233449 114126 233449 116551 233450 114126 233450 112730 233450 112730 233451 114126 233451 116552 233451 112730 233452 116552 233452 112732 233452 112732 233453 116552 233453 116553 233453 112732 233454 116553 233454 112733 233454 112733 233455 116553 233455 116554 233455 112733 233456 116554 233456 116555 233456 116555 233457 116554 233457 114122 233457 116555 233458 114122 233458 112735 233458 112735 233459 114122 233459 114117 233459 112735 233460 114117 233460 116556 233460 116556 233461 114117 233461 114116 233461 116556 233462 114116 233462 112724 233462 112724 233463 114116 233463 114112 233463 112724 233464 114112 233464 112726 233464 112726 233465 114112 233465 116557 233465 116571 233466 114108 233466 116558 233466 116558 233467 114108 233467 116559 233467 116558 233468 116559 233468 116560 233468 116560 233469 116559 233469 116561 233469 116560 233470 116561 233470 116562 233470 116562 233471 116561 233471 116564 233471 116562 233472 116564 233472 116563 233472 116563 233473 116564 233473 116565 233473 116563 233474 116565 233474 116566 233474 116566 233475 116565 233475 114102 233475 116566 233476 114102 233476 116567 233476 116567 233477 114102 233477 114098 233477 116567 233478 114098 233478 112766 233478 112766 233479 114098 233479 114094 233479 112766 233480 114094 233480 116568 233480 116568 233481 114094 233481 114090 233481 116568 233482 114090 233482 116569 233482 116569 233483 114090 233483 114091 233483 116569 233484 114091 233484 112768 233484 112768 233485 114091 233485 116570 233485 112768 233486 116570 233486 112763 233486 112763 233487 116570 233487 116572 233487 112763 233488 116572 233488 116571 233488 116571 233489 116572 233489 114108 233489 116579 233490 114079 233490 112834 233490 112834 233491 114079 233491 114080 233491 112834 233492 114080 233492 112835 233492 112835 233493 114080 233493 114078 233493 112835 233494 114078 233494 116573 233494 116573 233495 114078 233495 116574 233495 116573 233496 116574 233496 112837 233496 112837 233497 116574 233497 114072 233497 112837 233498 114072 233498 116575 233498 116575 233499 114072 233499 114065 233499 116575 233500 114065 233500 112838 233500 112838 233501 114065 233501 114067 233501 112838 233502 114067 233502 112841 233502 112841 233503 114067 233503 114054 233503 112841 233504 114054 233504 116576 233504 116576 233505 114054 233505 114063 233505 116576 233506 114063 233506 116577 233506 116577 233507 114063 233507 114059 233507 116577 233508 114059 233508 112843 233508 112843 233509 114059 233509 114056 233509 112843 233510 114056 233510 116578 233510 116578 233511 114056 233511 114055 233511 116578 233512 114055 233512 116579 233512 116579 233513 114055 233513 114079 233513 112794 233514 114052 233514 112795 233514 112795 233515 114052 233515 116580 233515 112795 233516 116580 233516 112796 233516 112796 233517 116580 233517 114053 233517 112796 233518 114053 233518 112799 233518 112799 233519 114053 233519 116581 233519 112799 233520 116581 233520 116582 233520 116582 233521 116581 233521 114049 233521 116582 233522 114049 233522 116583 233522 116583 233523 114049 233523 116584 233523 116583 233524 116584 233524 112801 233524 112801 233525 116584 233525 114047 233525 112801 233526 114047 233526 112803 233526 112803 233527 114047 233527 116585 233527 112803 233528 116585 233528 116586 233528 116586 233529 116585 233529 114038 233529 116586 233530 114038 233530 116587 233530 116587 233531 114038 233531 114043 233531 116587 233532 114043 233532 116588 233532 116588 233533 114043 233533 114041 233533 116588 233534 114041 233534 116589 233534 116589 233535 114041 233535 114040 233535 116589 233536 114040 233536 112794 233536 112794 233537 114040 233537 114052 233537 116602 233538 113909 233538 116601 233538 112903 233539 116599 233539 113906 233539 116596 233540 112907 233540 113906 233540 113906 233541 112907 233541 112905 233541 113906 233542 112905 233542 112903 233542 116590 233543 116591 233543 112913 233543 116592 233544 112915 233544 116591 233544 116591 233545 112915 233545 112914 233545 116591 233546 112914 233546 112913 233546 113908 233547 112918 233547 116592 233547 116592 233548 112918 233548 112916 233548 116592 233549 112916 233549 112915 233549 116602 233550 116593 233550 113909 233550 113909 233551 116593 233551 116594 233551 113909 233552 116594 233552 113908 233552 113908 233553 116594 233553 116595 233553 113908 233554 116595 233554 112918 233554 112913 233555 112912 233555 116590 233555 116590 233556 112912 233556 112910 233556 116590 233557 112910 233557 116596 233557 116596 233558 112910 233558 116597 233558 116596 233559 116597 233559 112907 233559 112895 233560 113901 233560 113904 233560 112903 233561 116598 233561 116599 233561 116599 233562 116598 233562 116603 233562 116599 233563 116603 233563 116604 233563 112895 233564 112893 233564 113901 233564 113901 233565 112893 233565 116600 233565 113901 233566 116600 233566 116601 233566 116601 233567 116600 233567 112891 233567 116601 233568 112891 233568 116602 233568 116603 233569 112900 233569 116604 233569 116604 233570 112900 233570 116605 233570 116604 233571 116605 233571 113904 233571 113904 233572 116605 233572 112897 233572 113904 233573 112897 233573 112895 233573 113132 233574 116608 233574 116606 233574 113145 233575 116611 233575 116607 233575 116619 233576 113147 233576 116607 233576 116607 233577 113147 233577 113146 233577 116607 233578 113146 233578 113145 233578 113132 233579 113131 233579 116608 233579 116608 233580 113131 233580 116609 233580 116608 233581 116609 233581 116610 233581 116609 233582 113130 233582 116610 233582 116610 233583 113130 233583 113129 233583 116610 233584 113129 233584 113913 233584 113145 233585 113144 233585 116611 233585 116611 233586 113144 233586 113143 233586 116611 233587 113143 233587 113918 233587 113124 233588 113911 233588 116612 233588 113129 233589 113128 233589 113913 233589 113913 233590 113128 233590 113125 233590 113913 233591 113125 233591 116612 233591 116612 233592 113125 233592 116613 233592 116612 233593 116613 233593 113124 233593 113917 233594 116616 233594 116606 233594 116606 233595 116616 233595 116614 233595 116606 233596 116614 233596 113132 233596 116615 233597 113137 233597 113917 233597 113917 233598 113137 233598 113135 233598 113917 233599 113135 233599 116616 233599 113143 233600 116617 233600 113918 233600 113918 233601 116617 233601 113140 233601 113918 233602 113140 233602 116615 233602 116615 233603 113140 233603 116618 233603 116615 233604 116618 233604 113137 233604 113124 233605 113123 233605 113911 233605 113911 233606 113123 233606 116620 233606 113911 233607 116620 233607 116619 233607 116619 233608 116620 233608 113121 233608 116619 233609 113121 233609 113147 233609 116622 233610 116634 233610 113928 233610 116625 233611 116621 233611 113928 233611 113928 233612 116621 233612 113055 233612 113928 233613 113055 233613 116622 233613 116623 233614 116624 233614 116625 233614 116625 233615 116624 233615 113057 233615 116625 233616 113057 233616 116621 233616 113927 233617 116626 233617 116623 233617 116623 233618 116626 233618 113059 233618 116623 233619 113059 233619 116624 233619 113061 233620 116629 233620 116627 233620 113061 233621 116628 233621 116629 233621 116629 233622 116628 233622 116630 233622 116629 233623 116630 233623 113927 233623 113927 233624 116630 233624 113060 233624 113927 233625 113060 233625 116626 233625 116631 233626 116632 233626 116627 233626 116627 233627 116632 233627 113062 233627 116627 233628 113062 233628 113061 233628 113924 233629 113064 233629 116631 233629 116631 233630 113064 233630 116633 233630 116631 233631 116633 233631 116632 233631 113047 233632 113923 233632 116638 233632 116622 233633 116635 233633 116634 233633 116634 233634 116635 233634 113051 233634 116634 233635 113051 233635 113922 233635 113047 233636 113046 233636 113923 233636 113923 233637 113046 233637 113044 233637 113923 233638 113044 233638 113924 233638 113924 233639 113044 233639 116636 233639 113924 233640 116636 233640 113064 233640 113051 233641 116637 233641 113922 233641 113922 233642 116637 233642 113050 233642 113922 233643 113050 233643 116638 233643 116638 233644 113050 233644 113048 233644 116638 233645 113048 233645 113047 233645 116639 233646 116649 233646 113939 233646 113937 233647 116640 233647 113939 233647 113939 233648 116640 233648 112978 233648 113939 233649 112978 233649 116639 233649 113936 233650 112982 233650 113937 233650 113937 233651 112982 233651 116641 233651 113937 233652 116641 233652 116640 233652 113933 233653 112985 233653 113936 233653 113936 233654 112985 233654 112983 233654 113936 233655 112983 233655 112982 233655 116642 233656 112987 233656 113933 233656 113933 233657 112987 233657 112986 233657 113933 233658 112986 233658 112985 233658 116644 233659 112991 233659 116642 233659 116642 233660 112991 233660 112988 233660 116642 233661 112988 233661 112987 233661 113932 233662 116643 233662 116644 233662 116644 233663 116643 233663 112992 233663 116644 233664 112992 233664 112991 233664 116645 233665 116646 233665 113932 233665 113932 233666 116646 233666 112993 233666 113932 233667 112993 233667 116643 233667 116657 233668 116647 233668 113930 233668 116639 233669 116648 233669 116649 233669 116649 233670 116648 233670 116653 233670 116649 233671 116653 233671 116654 233671 116657 233672 116650 233672 116647 233672 116647 233673 116650 233673 116651 233673 116647 233674 116651 233674 116645 233674 116645 233675 116651 233675 116652 233675 116645 233676 116652 233676 116646 233676 116653 233677 112975 233677 116654 233677 116654 233678 112975 233678 116655 233678 116654 233679 116655 233679 113930 233679 113930 233680 116655 233680 116656 233680 113930 233681 116656 233681 116657 233681 116660 233682 116658 233682 116659 233682 116674 233683 113226 233683 116658 233683 116658 233684 113226 233684 113227 233684 116658 233685 113227 233685 116659 233685 113232 233686 116668 233686 113821 233686 116659 233687 113228 233687 116660 233687 116660 233688 113228 233688 116661 233688 116660 233689 116661 233689 113821 233689 113821 233690 116661 233690 113230 233690 113821 233691 113230 233691 113232 233691 116675 233692 116663 233692 116664 233692 113817 233693 116680 233693 116663 233693 116663 233694 116680 233694 116662 233694 116663 233695 116662 233695 116664 233695 116665 233696 116678 233696 113819 233696 116666 233697 116671 233697 113819 233697 113819 233698 116671 233698 113235 233698 113819 233699 113235 233699 116665 233699 113232 233700 116667 233700 116668 233700 116668 233701 116667 233701 116669 233701 116668 233702 116669 233702 116666 233702 116666 233703 116669 233703 116670 233703 116666 233704 116670 233704 116671 233704 116677 233705 116672 233705 116674 233705 116674 233706 116672 233706 116673 233706 116674 233707 116673 233707 113226 233707 116664 233708 113223 233708 116675 233708 116675 233709 113223 233709 116676 233709 116675 233710 116676 233710 116677 233710 116677 233711 116676 233711 113225 233711 116677 233712 113225 233712 116672 233712 116665 233713 113237 233713 116678 233713 116678 233714 113237 233714 116679 233714 116678 233715 116679 233715 113817 233715 113817 233716 116679 233716 113239 233716 113817 233717 113239 233717 116680 233717 116684 233718 116681 233718 116682 233718 113839 233719 113157 233719 116681 233719 116681 233720 113157 233720 113159 233720 116681 233721 113159 233721 116682 233721 116685 233722 113846 233722 113847 233722 116682 233723 116683 233723 116684 233723 116684 233724 116683 233724 113160 233724 116684 233725 113160 233725 113847 233725 113847 233726 113160 233726 113161 233726 113847 233727 113161 233727 116685 233727 116693 233728 116686 233728 113151 233728 113842 233729 113149 233729 116686 233729 116686 233730 113149 233730 113150 233730 116686 233731 113150 233731 113151 233731 113168 233732 116687 233732 116689 233732 116688 233733 113166 233733 116689 233733 116689 233734 113166 233734 116690 233734 116689 233735 116690 233735 113168 233735 116685 233736 113164 233736 113846 233736 113846 233737 113164 233737 116691 233737 113846 233738 116691 233738 116688 233738 116688 233739 116691 233739 116692 233739 116688 233740 116692 233740 113166 233740 113840 233741 116697 233741 113839 233741 113839 233742 116697 233742 113156 233742 113839 233743 113156 233743 113157 233743 113151 233744 116694 233744 116693 233744 116693 233745 116694 233745 116695 233745 116693 233746 116695 233746 113840 233746 113840 233747 116695 233747 116696 233747 113840 233748 116696 233748 116697 233748 113168 233749 116698 233749 116687 233749 116687 233750 116698 233750 113170 233750 116687 233751 113170 233751 113842 233751 113842 233752 113170 233752 116699 233752 113842 233753 116699 233753 113149 233753 116716 233754 113822 233754 116700 233754 116700 233755 113822 233755 116701 233755 116700 233756 116701 233756 116702 233756 116702 233757 116701 233757 116703 233757 116702 233758 116703 233758 116704 233758 116704 233759 116703 233759 113827 233759 116704 233760 113827 233760 116705 233760 116705 233761 113827 233761 116706 233761 116705 233762 116706 233762 116707 233762 116707 233763 116706 233763 116708 233763 116707 233764 116708 233764 112671 233764 112671 233765 116708 233765 116709 233765 112671 233766 116709 233766 112669 233766 112669 233767 116709 233767 116711 233767 112669 233768 116711 233768 116710 233768 116710 233769 116711 233769 113832 233769 116710 233770 113832 233770 116712 233770 116712 233771 113832 233771 113833 233771 116712 233772 113833 233772 112668 233772 112668 233773 113833 233773 116714 233773 112668 233774 116714 233774 116713 233774 116713 233775 116714 233775 116715 233775 116713 233776 116715 233776 116716 233776 116716 233777 116715 233777 113822 233777 112631 233778 113794 233778 112629 233778 112629 233779 113794 233779 116717 233779 112629 233780 116717 233780 116718 233780 116718 233781 116717 233781 113797 233781 116718 233782 113797 233782 116719 233782 116719 233783 113797 233783 113799 233783 116719 233784 113799 233784 116720 233784 116720 233785 113799 233785 113800 233785 116720 233786 113800 233786 112628 233786 112628 233787 113800 233787 113804 233787 112628 233788 113804 233788 112638 233788 112638 233789 113804 233789 116721 233789 112638 233790 116721 233790 112636 233790 112636 233791 116721 233791 116722 233791 112636 233792 116722 233792 112634 233792 112634 233793 116722 233793 116724 233793 112634 233794 116724 233794 116723 233794 116723 233795 116724 233795 116725 233795 116723 233796 116725 233796 116726 233796 116726 233797 116725 233797 113810 233797 116726 233798 113810 233798 116727 233798 116727 233799 113810 233799 116728 233799 116727 233800 116728 233800 112631 233800 112631 233801 116728 233801 113794 233801 116738 233802 116729 233802 113706 233802 116738 233803 113371 233803 116729 233803 116729 233804 113371 233804 113373 233804 116729 233805 113373 233805 116730 233805 113385 233806 116742 233806 113710 233806 116733 233807 116731 233807 113710 233807 113710 233808 116731 233808 116732 233808 113710 233809 116732 233809 113385 233809 113712 233810 113380 233810 116733 233810 116733 233811 113380 233811 113382 233811 116733 233812 113382 233812 116731 233812 113373 233813 113375 233813 116730 233813 116730 233814 113375 233814 116734 233814 116730 233815 116734 233815 113713 233815 116735 233816 116736 233816 113706 233816 113706 233817 116736 233817 116737 233817 113706 233818 116737 233818 116738 233818 116739 233819 116740 233819 116735 233819 116735 233820 116740 233820 113369 233820 116735 233821 113369 233821 116736 233821 116741 233822 113708 233822 116744 233822 113385 233823 113387 233823 116742 233823 116742 233824 113387 233824 116743 233824 116742 233825 116743 233825 116744 233825 116744 233826 116743 233826 113388 233826 116744 233827 113388 233827 116741 233827 116734 233828 113376 233828 113713 233828 113713 233829 113376 233829 113377 233829 113713 233830 113377 233830 113712 233830 113712 233831 113377 233831 113379 233831 113712 233832 113379 233832 113380 233832 116741 233833 116745 233833 113708 233833 113708 233834 116745 233834 113364 233834 113708 233835 113364 233835 116739 233835 116739 233836 113364 233836 113366 233836 116739 233837 113366 233837 116740 233837 116746 233838 113736 233838 116751 233838 116746 233839 113295 233839 113736 233839 113736 233840 113295 233840 113296 233840 113736 233841 113296 233841 116747 233841 116755 233842 113741 233842 116748 233842 113743 233843 113303 233843 116748 233843 116748 233844 113303 233844 113305 233844 116748 233845 113305 233845 116755 233845 116760 233846 116761 233846 113743 233846 113743 233847 116761 233847 113302 233847 113743 233848 113302 233848 113303 233848 113296 233849 116749 233849 116747 233849 116747 233850 116749 233850 116758 233850 116747 233851 116758 233851 116750 233851 116753 233852 113291 233852 116751 233852 116751 233853 113291 233853 113293 233853 116751 233854 113293 233854 116746 233854 116752 233855 113290 233855 116753 233855 116753 233856 113290 233856 116754 233856 116753 233857 116754 233857 113291 233857 116762 233858 116763 233858 116757 233858 116755 233859 113307 233859 113741 233859 113741 233860 113307 233860 116756 233860 113741 233861 116756 233861 116757 233861 116757 233862 116756 233862 113309 233862 116757 233863 113309 233863 116762 233863 116758 233864 113298 233864 116750 233864 116750 233865 113298 233865 116759 233865 116750 233866 116759 233866 116760 233866 116760 233867 116759 233867 113299 233867 116760 233868 113299 233868 116761 233868 116762 233869 113288 233869 116763 233869 116763 233870 113288 233870 116764 233870 116763 233871 116764 233871 116752 233871 116752 233872 116764 233872 116765 233872 116752 233873 116765 233873 113290 233873 112597 233874 113731 233874 116766 233874 116766 233875 113731 233875 116767 233875 116766 233876 116767 233876 112595 233876 112595 233877 116767 233877 116768 233877 112595 233878 116768 233878 116770 233878 116770 233879 116768 233879 116769 233879 116770 233880 116769 233880 116771 233880 116771 233881 116769 233881 113717 233881 116771 233882 113717 233882 112593 233882 112593 233883 113717 233883 116772 233883 112593 233884 116772 233884 116773 233884 116773 233885 116772 233885 113720 233885 116773 233886 113720 233886 116774 233886 116774 233887 113720 233887 113722 233887 116774 233888 113722 233888 112603 233888 112603 233889 113722 233889 116775 233889 112603 233890 116775 233890 112601 233890 112601 233891 116775 233891 113724 233891 112601 233892 113724 233892 112599 233892 112599 233893 113724 233893 113727 233893 112599 233894 113727 233894 116776 233894 116776 233895 113727 233895 113729 233895 116776 233896 113729 233896 112597 233896 112597 233897 113729 233897 113731 233897 112562 233898 116777 233898 116778 233898 116778 233899 116777 233899 116779 233899 116778 233900 116779 233900 112560 233900 112560 233901 116779 233901 116780 233901 112560 233902 116780 233902 116781 233902 116781 233903 116780 233903 116782 233903 116781 233904 116782 233904 112558 233904 112558 233905 116782 233905 116783 233905 112558 233906 116783 233906 112556 233906 112556 233907 116783 233907 113690 233907 112556 233908 113690 233908 116784 233908 116784 233909 113690 233909 113691 233909 116784 233910 113691 233910 112554 233910 112554 233911 113691 233911 116785 233911 112554 233912 116785 233912 112567 233912 112567 233913 116785 233913 113696 233913 112567 233914 113696 233914 116786 233914 116786 233915 113696 233915 113697 233915 116786 233916 113697 233916 112565 233916 112565 233917 113697 233917 113700 233917 112565 233918 113700 233918 112563 233918 112563 233919 113700 233919 113701 233919 112563 233920 113701 233920 112562 233920 112562 233921 113701 233921 116777 233921 116804 233922 116787 233922 116802 233922 115323 233923 116793 233923 116794 233923 116793 233924 116806 233924 116788 233924 116806 233925 116513 233925 116510 233925 116806 233926 116510 233926 116788 233926 116788 233927 116510 233927 116511 233927 116788 233928 116511 233928 116789 233928 116789 233929 116511 233929 116512 233929 116789 233930 116512 233930 116795 233930 116795 233931 116512 233931 116505 233931 116795 233932 116505 233932 116796 233932 116796 233933 116505 233933 116791 233933 116796 233934 116791 233934 116790 233934 116790 233935 116791 233935 116803 233935 116790 233936 116803 233936 116792 233936 116793 233937 116788 233937 116794 233937 116794 233938 116788 233938 116789 233938 116794 233939 116789 233939 116797 233939 116797 233940 116789 233940 116795 233940 116797 233941 116795 233941 116799 233941 116799 233942 116795 233942 116796 233942 116799 233943 116796 233943 116801 233943 116801 233944 116796 233944 116790 233944 116801 233945 116790 233945 116802 233945 116802 233946 116790 233946 116792 233946 116802 233947 116792 233947 116804 233947 115323 233948 116794 233948 115322 233948 115322 233949 116794 233949 116797 233949 115322 233950 116797 233950 116798 233950 116798 233951 116797 233951 116799 233951 116798 233952 116799 233952 115350 233952 115350 233953 116799 233953 116801 233953 115350 233954 116801 233954 116800 233954 116800 233955 116801 233955 116802 233955 116800 233956 116802 233956 115344 233956 115344 233957 116802 233957 116787 233957 115344 233958 116787 233958 115345 233958 116803 233959 116831 233959 116829 233959 116803 233960 116829 233960 116792 233960 116792 233961 116829 233961 116827 233961 116792 233962 116827 233962 116804 233962 116804 233963 116827 233963 116805 233963 116804 233964 116805 233964 116787 233964 116787 233965 116805 233965 115346 233965 116787 233966 115346 233966 115345 233966 116513 233967 116806 233967 116823 233967 116806 233968 116793 233968 116815 233968 116793 233969 115323 233969 116807 233969 116793 233970 116807 233970 116815 233970 116815 233971 116807 233971 116808 233971 116815 233972 116808 233972 116810 233972 116810 233973 116808 233973 116809 233973 116810 233974 116809 233974 116818 233974 116818 233975 116809 233975 115314 233975 116818 233976 115314 233976 116819 233976 116819 233977 115314 233977 115317 233977 116819 233978 115317 233978 116811 233978 116811 233979 115317 233979 115316 233979 116811 233980 115316 233980 116812 233980 116812 233981 115316 233981 115326 233981 116812 233982 115326 233982 116814 233982 116814 233983 115326 233983 116813 233983 116814 233984 116813 233984 116849 233984 116806 233985 116815 233985 116823 233985 116823 233986 116815 233986 116810 233986 116823 233987 116810 233987 116816 233987 116816 233988 116810 233988 116818 233988 116816 233989 116818 233989 116817 233989 116817 233990 116818 233990 116819 233990 116817 233991 116819 233991 116820 233991 116820 233992 116819 233992 116811 233992 116820 233993 116811 233993 116821 233993 116821 233994 116811 233994 116812 233994 116821 233995 116812 233995 116822 233995 116822 233996 116812 233996 116814 233996 116822 233997 116814 233997 116826 233997 116826 233998 116814 233998 116849 233998 116826 233999 116849 233999 116848 233999 116513 234000 116823 234000 116824 234000 116824 234001 116823 234001 116816 234001 116824 234002 116816 234002 116514 234002 116514 234003 116816 234003 116817 234003 116514 234004 116817 234004 116515 234004 116515 234005 116817 234005 116820 234005 116515 234006 116820 234006 116516 234006 116516 234007 116820 234007 116821 234007 116516 234008 116821 234008 116519 234008 116519 234009 116821 234009 116822 234009 116519 234010 116822 234010 116825 234010 116825 234011 116822 234011 116826 234011 116825 234012 116826 234012 116522 234012 116522 234013 116826 234013 116848 234013 116522 234014 116848 234014 116548 234014 115346 234015 116805 234015 116839 234015 116869 234016 116868 234016 116838 234016 116805 234017 116827 234017 116835 234017 116872 234018 116870 234018 116828 234018 116827 234019 116829 234019 116830 234019 116829 234020 116831 234020 116530 234020 116533 234021 116837 234021 116832 234021 116829 234022 116530 234022 116830 234022 116830 234023 116530 234023 116531 234023 116830 234024 116531 234024 116832 234024 116832 234025 116531 234025 116532 234025 116832 234026 116532 234026 116533 234026 116533 234027 116833 234027 116837 234027 116837 234028 116833 234028 116834 234028 116837 234029 116834 234029 116873 234029 116827 234030 116830 234030 116835 234030 116835 234031 116830 234031 116832 234031 116835 234032 116832 234032 116836 234032 116836 234033 116832 234033 116837 234033 116836 234034 116837 234034 116828 234034 116828 234035 116837 234035 116873 234035 116828 234036 116873 234036 116872 234036 116805 234037 116835 234037 116839 234037 116839 234038 116835 234038 116836 234038 116839 234039 116836 234039 116841 234039 116841 234040 116836 234040 116828 234040 116841 234041 116828 234041 116838 234041 116838 234042 116828 234042 116870 234042 116838 234043 116870 234043 116869 234043 115346 234044 116839 234044 116840 234044 116840 234045 116839 234045 116841 234045 116840 234046 116841 234046 116842 234046 116842 234047 116841 234047 116838 234047 116842 234048 116838 234048 116843 234048 116843 234049 116838 234049 116868 234049 116843 234050 116868 234050 116859 234050 116898 234051 116844 234051 116897 234051 116897 234052 116844 234052 116847 234052 116897 234053 116847 234053 116846 234053 116846 234054 116847 234054 116845 234054 115325 234055 116064 234055 116845 234055 116845 234056 116064 234056 116894 234056 116845 234057 116894 234057 116846 234057 116844 234058 116548 234058 116847 234058 116847 234059 116548 234059 116848 234059 116847 234060 116848 234060 116845 234060 116845 234061 116848 234061 116849 234061 116845 234062 116849 234062 115325 234062 115325 234063 116849 234063 116813 234063 116851 234064 116904 234064 116866 234064 116850 234065 116902 234065 116852 234065 116852 234066 116902 234066 116851 234066 116528 234067 116900 234067 116850 234067 116851 234068 116866 234068 116852 234068 116852 234069 116866 234069 116854 234069 116852 234070 116854 234070 116853 234070 116853 234071 116854 234071 116865 234071 116853 234072 116865 234072 116875 234072 116875 234073 116865 234073 116855 234073 116875 234074 116855 234074 116856 234074 116856 234075 116855 234075 116862 234075 116856 234076 116862 234076 116877 234076 116877 234077 116862 234077 116858 234077 116877 234078 116858 234078 116857 234078 116857 234079 116858 234079 116871 234079 116857 234080 116871 234080 116880 234080 116860 234081 116859 234081 116868 234081 116868 234082 116871 234082 116860 234082 116860 234083 116871 234083 116858 234083 116860 234084 116858 234084 116861 234084 116861 234085 116858 234085 116862 234085 116861 234086 116862 234086 116863 234086 116863 234087 116862 234087 116855 234087 116863 234088 116855 234088 115320 234088 115320 234089 116855 234089 116865 234089 115320 234090 116865 234090 116864 234090 116864 234091 116865 234091 116854 234091 116864 234092 116854 234092 116867 234092 116867 234093 116854 234093 116866 234093 116867 234094 116866 234094 115312 234094 115312 234095 116866 234095 116904 234095 115312 234096 116904 234096 116905 234096 116868 234097 116869 234097 116871 234097 116871 234098 116869 234098 116870 234098 116871 234099 116870 234099 116880 234099 116880 234100 116870 234100 116872 234100 116880 234101 116872 234101 116873 234101 116850 234102 116852 234102 116528 234102 116528 234103 116852 234103 116853 234103 116528 234104 116853 234104 116874 234104 116874 234105 116853 234105 116875 234105 116874 234106 116875 234106 116876 234106 116876 234107 116875 234107 116856 234107 116876 234108 116856 234108 116878 234108 116878 234109 116856 234109 116877 234109 116878 234110 116877 234110 116524 234110 116524 234111 116877 234111 116857 234111 116524 234112 116857 234112 116879 234112 116879 234113 116857 234113 116880 234113 116879 234114 116880 234114 116523 234114 116523 234115 116880 234115 116873 234115 116523 234116 116873 234116 116834 234116 116066 234117 116881 234117 116886 234117 116881 234118 116072 234118 116886 234118 116886 234119 116072 234119 116929 234119 116886 234120 116929 234120 116887 234120 116887 234121 116929 234121 116882 234121 116887 234122 116882 234122 116888 234122 116888 234123 116882 234123 116883 234123 116888 234124 116883 234124 116884 234124 116884 234125 116883 234125 116543 234125 116890 234126 116066 234126 116885 234126 116885 234127 116066 234127 116886 234127 116885 234128 116886 234128 116891 234128 116891 234129 116886 234129 116887 234129 116891 234130 116887 234130 116893 234130 116893 234131 116887 234131 116888 234131 116893 234132 116888 234132 116889 234132 116889 234133 116888 234133 116884 234133 116063 234134 116890 234134 116895 234134 116895 234135 116890 234135 116885 234135 116895 234136 116885 234136 116896 234136 116896 234137 116885 234137 116891 234137 116896 234138 116891 234138 116892 234138 116892 234139 116891 234139 116893 234139 116892 234140 116893 234140 116899 234140 116899 234141 116893 234141 116889 234141 116064 234142 116063 234142 116894 234142 116894 234143 116063 234143 116895 234143 116894 234144 116895 234144 116846 234144 116846 234145 116895 234145 116896 234145 116846 234146 116896 234146 116897 234146 116897 234147 116896 234147 116892 234147 116897 234148 116892 234148 116898 234148 116898 234149 116892 234149 116899 234149 116900 234150 116906 234150 116850 234150 116850 234151 116906 234151 116901 234151 116850 234152 116901 234152 116902 234152 116902 234153 116901 234153 116907 234153 116902 234154 116907 234154 116851 234154 116851 234155 116907 234155 116903 234155 116851 234156 116903 234156 116904 234156 116904 234157 116903 234157 116910 234157 116904 234158 116910 234158 116905 234158 116906 234159 116542 234159 116901 234159 116901 234160 116542 234160 116908 234160 116901 234161 116908 234161 116907 234161 116907 234162 116908 234162 116909 234162 116907 234163 116909 234163 116903 234163 116903 234164 116909 234164 116945 234164 116903 234165 116945 234165 116910 234165 116910 234166 116945 234166 115310 234166 116925 234167 116075 234167 116927 234167 116931 234168 116930 234168 116920 234168 115277 234169 116911 234169 116940 234169 116940 234170 116911 234170 115283 234170 116940 234171 115283 234171 116912 234171 116912 234172 115283 234172 116913 234172 116912 234173 116913 234173 116938 234173 116938 234174 116913 234174 115282 234174 116938 234175 115282 234175 116937 234175 116937 234176 115282 234176 116543 234176 116937 234177 116543 234177 116883 234177 115277 234178 116940 234178 116915 234178 116915 234179 116940 234179 116914 234179 116915 234180 116914 234180 116916 234180 116916 234181 116914 234181 116917 234181 116917 234182 116914 234182 116964 234182 116917 234183 116964 234183 116963 234183 116883 234184 116882 234184 116932 234184 116924 234185 116923 234185 116918 234185 116918 234186 116923 234186 116922 234186 116918 234187 116922 234187 116067 234187 116067 234188 116922 234188 116921 234188 116067 234189 116921 234189 116068 234189 116068 234190 116921 234190 116920 234190 116068 234191 116920 234191 116070 234191 116070 234192 116920 234192 116930 234192 116070 234193 116930 234193 116919 234193 116931 234194 116920 234194 116933 234194 116933 234195 116920 234195 116921 234195 116933 234196 116921 234196 116935 234196 116935 234197 116921 234197 116922 234197 116935 234198 116922 234198 116936 234198 116936 234199 116922 234199 116923 234199 116936 234200 116923 234200 116926 234200 116924 234201 116925 234201 116923 234201 116923 234202 116925 234202 116927 234202 116923 234203 116927 234203 116926 234203 116926 234204 116927 234204 116965 234204 116926 234205 116965 234205 116928 234205 116072 234206 116919 234206 116929 234206 116929 234207 116919 234207 116930 234207 116929 234208 116930 234208 116882 234208 116882 234209 116930 234209 116931 234209 116882 234210 116931 234210 116932 234210 116932 234211 116931 234211 116933 234211 116932 234212 116933 234212 116934 234212 116934 234213 116933 234213 116935 234213 116934 234214 116935 234214 116939 234214 116939 234215 116935 234215 116936 234215 116939 234216 116936 234216 116941 234216 116941 234217 116936 234217 116926 234217 116941 234218 116926 234218 116942 234218 116942 234219 116926 234219 116928 234219 116942 234220 116928 234220 116943 234220 116883 234221 116932 234221 116937 234221 116937 234222 116932 234222 116934 234222 116937 234223 116934 234223 116938 234223 116938 234224 116934 234224 116939 234224 116938 234225 116939 234225 116912 234225 116912 234226 116939 234226 116941 234226 116912 234227 116941 234227 116940 234227 116940 234228 116941 234228 116942 234228 116940 234229 116942 234229 116914 234229 116914 234230 116942 234230 116943 234230 116914 234231 116943 234231 116964 234231 115307 234232 115310 234232 116944 234232 116944 234233 115310 234233 116945 234233 116944 234234 116945 234234 116946 234234 116946 234235 116945 234235 116909 234235 116946 234236 116909 234236 116947 234236 116947 234237 116909 234237 116908 234237 116947 234238 116908 234238 116948 234238 116948 234239 116908 234239 116542 234239 116950 234240 115307 234240 116953 234240 116953 234241 115307 234241 116944 234241 116953 234242 116944 234242 116954 234242 116954 234243 116944 234243 116946 234243 116954 234244 116946 234244 116949 234244 116949 234245 116946 234245 116947 234245 116949 234246 116947 234246 116539 234246 116539 234247 116947 234247 116948 234247 115303 234248 116950 234248 116951 234248 116951 234249 116950 234249 116953 234249 116951 234250 116953 234250 116952 234250 116952 234251 116953 234251 116954 234251 116952 234252 116954 234252 116955 234252 116955 234253 116954 234253 116949 234253 116955 234254 116949 234254 116959 234254 116959 234255 116949 234255 116539 234255 116956 234256 115303 234256 116996 234256 116996 234257 115303 234257 116951 234257 116996 234258 116951 234258 116957 234258 116957 234259 116951 234259 116952 234259 116957 234260 116952 234260 116958 234260 116958 234261 116952 234261 116955 234261 116958 234262 116955 234262 116536 234262 116536 234263 116955 234263 116959 234263 116960 234264 116976 234264 116961 234264 116969 234265 116967 234265 116963 234265 116075 234266 116962 234266 116927 234266 116927 234267 116962 234267 116972 234267 116927 234268 116972 234268 116965 234268 116965 234269 116972 234269 116970 234269 116963 234270 116964 234270 116969 234270 116969 234271 116964 234271 116943 234271 116969 234272 116943 234272 116970 234272 116970 234273 116943 234273 116928 234273 116970 234274 116928 234274 116965 234274 116973 234275 116967 234275 116966 234275 116966 234276 116967 234276 116969 234276 116966 234277 116969 234277 116968 234277 116968 234278 116969 234278 116970 234278 116968 234279 116970 234279 116971 234279 116971 234280 116970 234280 116972 234280 116971 234281 116972 234281 116079 234281 116079 234282 116972 234282 116962 234282 116170 234283 116973 234283 116975 234283 116975 234284 116973 234284 116966 234284 116975 234285 116966 234285 116974 234285 116974 234286 116966 234286 116968 234286 116974 234287 116968 234287 116961 234287 116961 234288 116968 234288 116971 234288 116961 234289 116971 234289 116960 234289 116960 234290 116971 234290 116079 234290 117020 234291 116170 234291 117018 234291 117018 234292 116170 234292 116975 234292 117018 234293 116975 234293 117011 234293 117011 234294 116975 234294 116974 234294 117011 234295 116974 234295 117006 234295 117006 234296 116974 234296 116961 234296 117006 234297 116961 234297 116091 234297 116091 234298 116961 234298 116976 234298 116149 234299 116977 234299 116983 234299 116983 234300 116977 234300 116985 234300 116985 234301 116977 234301 116978 234301 116985 234302 116978 234302 116986 234302 116986 234303 116978 234303 116147 234303 116986 234304 116147 234304 116980 234304 116980 234305 116147 234305 116979 234305 116980 234306 116979 234306 116981 234306 116981 234307 116979 234307 116982 234307 116981 234308 116982 234308 116146 234308 116536 234309 116149 234309 116958 234309 116958 234310 116149 234310 116983 234310 116958 234311 116983 234311 116957 234311 116996 234312 116957 234312 116987 234312 116957 234313 116983 234313 116987 234313 116987 234314 116983 234314 116985 234314 116987 234315 116985 234315 116984 234315 116984 234316 116985 234316 116986 234316 116984 234317 116986 234317 116988 234317 116988 234318 116986 234318 116980 234318 116988 234319 116980 234319 116989 234319 116989 234320 116980 234320 116981 234320 116989 234321 116981 234321 116990 234321 116996 234322 116987 234322 116995 234322 116995 234323 116987 234323 116984 234323 116995 234324 116984 234324 116994 234324 116994 234325 116984 234325 116988 234325 116994 234326 116988 234326 116993 234326 116993 234327 116988 234327 116989 234327 116993 234328 116989 234328 116992 234328 116992 234329 116989 234329 116990 234329 116992 234330 116990 234330 116999 234330 116991 234331 115288 234331 116999 234331 116999 234332 115288 234332 115287 234332 116999 234333 115287 234333 116992 234333 116992 234334 115287 234334 115299 234334 116992 234335 115299 234335 116993 234335 116993 234336 115299 234336 115300 234336 116993 234337 115300 234337 116994 234337 116994 234338 115300 234338 115301 234338 116994 234339 115301 234339 116995 234339 116995 234340 115301 234340 115305 234340 116995 234341 115305 234341 116996 234341 116996 234342 115305 234342 116956 234342 115293 234343 116991 234343 116997 234343 116997 234344 116991 234344 116999 234344 116997 234345 116999 234345 116998 234345 116998 234346 116999 234346 116990 234346 116998 234347 116990 234347 117000 234347 117000 234348 116990 234348 116981 234348 117000 234349 116981 234349 116177 234349 116177 234350 116981 234350 116146 234350 117042 234351 117041 234351 117030 234351 117041 234352 117040 234352 117004 234352 117038 234353 117001 234353 117040 234353 117032 234354 117002 234354 117033 234354 117033 234355 117002 234355 117003 234355 117033 234356 117003 234356 117035 234356 117040 234357 117001 234357 117004 234357 117004 234358 117001 234358 116086 234358 117004 234359 116086 234359 117032 234359 117032 234360 116086 234360 117005 234360 117032 234361 117005 234361 117002 234361 117013 234362 116101 234362 117016 234362 117016 234363 116101 234363 116100 234363 117016 234364 116100 234364 117039 234364 117006 234365 116091 234365 116095 234365 117011 234366 117006 234366 117007 234366 117007 234367 117006 234367 116095 234367 117007 234368 116095 234368 117008 234368 117008 234369 116095 234369 117009 234369 117008 234370 117009 234370 117013 234370 117013 234371 117009 234371 117010 234371 117013 234372 117010 234372 116101 234372 117018 234373 117011 234373 117019 234373 117011 234374 117007 234374 117019 234374 117019 234375 117007 234375 117008 234375 117019 234376 117008 234376 117012 234376 117012 234377 117008 234377 117013 234377 117012 234378 117013 234378 117014 234378 117014 234379 117013 234379 117016 234379 117014 234380 117016 234380 117015 234380 117015 234381 117016 234381 117039 234381 117015 234382 117039 234382 117017 234382 117018 234383 117019 234383 117022 234383 117022 234384 117019 234384 117012 234384 117022 234385 117012 234385 117024 234385 117024 234386 117012 234386 117014 234386 117024 234387 117014 234387 117025 234387 117025 234388 117014 234388 117015 234388 117025 234389 117015 234389 117027 234389 117027 234390 117015 234390 117017 234390 117027 234391 117017 234391 117028 234391 117020 234392 117018 234392 117021 234392 117021 234393 117018 234393 117022 234393 117021 234394 117022 234394 117023 234394 117023 234395 117022 234395 117024 234395 117023 234396 117024 234396 116166 234396 116166 234397 117024 234397 117025 234397 116166 234398 117025 234398 117026 234398 117026 234399 117025 234399 117027 234399 117026 234400 117027 234400 117029 234400 117029 234401 117027 234401 117028 234401 116160 234402 116161 234402 117028 234402 117028 234403 116161 234403 116162 234403 117028 234404 116162 234404 117029 234404 117041 234405 117004 234405 117030 234405 117030 234406 117004 234406 117032 234406 117030 234407 117032 234407 117031 234407 117031 234408 117032 234408 117033 234408 117031 234409 117033 234409 117034 234409 117034 234410 117033 234410 117035 234410 117034 234411 117035 234411 117037 234411 117042 234412 117030 234412 117043 234412 117043 234413 117030 234413 117031 234413 117043 234414 117031 234414 117045 234414 117045 234415 117031 234415 117034 234415 117045 234416 117034 234416 117036 234416 117036 234417 117034 234417 117037 234417 117036 234418 117037 234418 117048 234418 116100 234419 117038 234419 117039 234419 117039 234420 117038 234420 117040 234420 117039 234421 117040 234421 117017 234421 117017 234422 117040 234422 117041 234422 117017 234423 117041 234423 117028 234423 117028 234424 117041 234424 117042 234424 117028 234425 117042 234425 116160 234425 116160 234426 117042 234426 117043 234426 116160 234427 117043 234427 117044 234427 117044 234428 117043 234428 117045 234428 117044 234429 117045 234429 117046 234429 117046 234430 117045 234430 117036 234430 117046 234431 117036 234431 117047 234431 117047 234432 117036 234432 117048 234432 117047 234433 117048 234433 116157 234433 115295 234434 115294 234434 117057 234434 117051 234435 116174 234435 117052 234435 117052 234436 116174 234436 117050 234436 117052 234437 117050 234437 117049 234437 117049 234438 117050 234438 117123 234438 117049 234439 117123 234439 117054 234439 117054 234440 117123 234440 117109 234440 117054 234441 117109 234441 117055 234441 117055 234442 117109 234442 116110 234442 116176 234443 117051 234443 117056 234443 117056 234444 117051 234444 117052 234444 117056 234445 117052 234445 117053 234445 117053 234446 117052 234446 117049 234446 117053 234447 117049 234447 117057 234447 117057 234448 117049 234448 117054 234448 117057 234449 117054 234449 115295 234449 115295 234450 117054 234450 117055 234450 117058 234451 116176 234451 117059 234451 117059 234452 116176 234452 117056 234452 117059 234453 117056 234453 117060 234453 117060 234454 117056 234454 117053 234454 117060 234455 117053 234455 117061 234455 117061 234456 117053 234456 117057 234456 117061 234457 117057 234457 115291 234457 115291 234458 117057 234458 115294 234458 116177 234459 117058 234459 117000 234459 117000 234460 117058 234460 117059 234460 117000 234461 117059 234461 116998 234461 116998 234462 117059 234462 117060 234462 116998 234463 117060 234463 116997 234463 116997 234464 117060 234464 117061 234464 116997 234465 117061 234465 115293 234465 115293 234466 117061 234466 115291 234466 117035 234467 117003 234467 117062 234467 117037 234468 117035 234468 117063 234468 117048 234469 117037 234469 117076 234469 116157 234470 117048 234470 117085 234470 117035 234471 117062 234471 117063 234471 117063 234472 117062 234472 114887 234472 117063 234473 114887 234473 117064 234473 114887 234474 114888 234474 117064 234474 117064 234475 114888 234475 114889 234475 117064 234476 114889 234476 117068 234476 117068 234477 114889 234477 117065 234477 117068 234478 117065 234478 117066 234478 117066 234479 117065 234479 114892 234479 117066 234480 114892 234480 117071 234480 117071 234481 114892 234481 114895 234481 117071 234482 114895 234482 117067 234482 117067 234483 114895 234483 114897 234483 114903 234484 117074 234484 114902 234484 114902 234485 117074 234485 117073 234485 114902 234486 117073 234486 114900 234486 114900 234487 117073 234487 117067 234487 114900 234488 117067 234488 114898 234488 114898 234489 117067 234489 114897 234489 117037 234490 117063 234490 117076 234490 117076 234491 117063 234491 117064 234491 117076 234492 117064 234492 117069 234492 117069 234493 117064 234493 117068 234493 117069 234494 117068 234494 117070 234494 117070 234495 117068 234495 117066 234495 117070 234496 117066 234496 117078 234496 117078 234497 117066 234497 117071 234497 117078 234498 117071 234498 117081 234498 117081 234499 117071 234499 117067 234499 117081 234500 117067 234500 117083 234500 117083 234501 117067 234501 117073 234501 117083 234502 117073 234502 117072 234502 117072 234503 117073 234503 117074 234503 117072 234504 117074 234504 117075 234504 117048 234505 117076 234505 117085 234505 117085 234506 117076 234506 117069 234506 117085 234507 117069 234507 117077 234507 117077 234508 117069 234508 117070 234508 117077 234509 117070 234509 117079 234509 117079 234510 117070 234510 117078 234510 117079 234511 117078 234511 117080 234511 117080 234512 117078 234512 117081 234512 117080 234513 117081 234513 117082 234513 117082 234514 117081 234514 117083 234514 117082 234515 117083 234515 117088 234515 117088 234516 117083 234516 117072 234516 117088 234517 117072 234517 117090 234517 117090 234518 117072 234518 117075 234518 117090 234519 117075 234519 117091 234519 116157 234520 117085 234520 117084 234520 117084 234521 117085 234521 117077 234521 117084 234522 117077 234522 116155 234522 116155 234523 117077 234523 117079 234523 116155 234524 117079 234524 116154 234524 116154 234525 117079 234525 117080 234525 116154 234526 117080 234526 117086 234526 117086 234527 117080 234527 117082 234527 117086 234528 117082 234528 116153 234528 116153 234529 117082 234529 117088 234529 116153 234530 117088 234530 117087 234530 117087 234531 117088 234531 117090 234531 117087 234532 117090 234532 117089 234532 117089 234533 117090 234533 117091 234533 117089 234534 117091 234534 116150 234534 117109 234535 117092 234535 116110 234535 116110 234536 117092 234536 116113 234536 116113 234537 117092 234537 116109 234537 116109 234538 117092 234538 117093 234538 116109 234539 117093 234539 116108 234539 116108 234540 117093 234540 117094 234540 116108 234541 117094 234541 116105 234541 117094 234542 117095 234542 116105 234542 116105 234543 117095 234543 117107 234543 116105 234544 117107 234544 116118 234544 116118 234545 117107 234545 117106 234545 116118 234546 117106 234546 117096 234546 117096 234547 117106 234547 117098 234547 117096 234548 117098 234548 116112 234548 116112 234549 117098 234549 117097 234549 117097 234550 117098 234550 117105 234550 117097 234551 117105 234551 117100 234551 117100 234552 117105 234552 117099 234552 117100 234553 117099 234553 116116 234553 117101 234554 116116 234554 117102 234554 117102 234555 116116 234555 117099 234555 117102 234556 117099 234556 117103 234556 117177 234557 117103 234557 117104 234557 117103 234558 117099 234558 117104 234558 117104 234559 117099 234559 117105 234559 117104 234560 117105 234560 117111 234560 117111 234561 117105 234561 117098 234561 117111 234562 117098 234562 117113 234562 117113 234563 117098 234563 117106 234563 117113 234564 117106 234564 117114 234564 117114 234565 117106 234565 117107 234565 117114 234566 117107 234566 117115 234566 117115 234567 117107 234567 117095 234567 117115 234568 117095 234568 117108 234568 117108 234569 117095 234569 117094 234569 117108 234570 117094 234570 117119 234570 117119 234571 117094 234571 117093 234571 117119 234572 117093 234572 117121 234572 117121 234573 117093 234573 117092 234573 117121 234574 117092 234574 117110 234574 117110 234575 117092 234575 117109 234575 117110 234576 117109 234576 117123 234576 117177 234577 117104 234577 117125 234577 117125 234578 117104 234578 117111 234578 117125 234579 117111 234579 117126 234579 117126 234580 117111 234580 117113 234580 117126 234581 117113 234581 117112 234581 117112 234582 117113 234582 117114 234582 117112 234583 117114 234583 117128 234583 117128 234584 117114 234584 117115 234584 117128 234585 117115 234585 117116 234585 117116 234586 117115 234586 117108 234586 117116 234587 117108 234587 117117 234587 117117 234588 117108 234588 117119 234588 117117 234589 117119 234589 117118 234589 117118 234590 117119 234590 117121 234590 117118 234591 117121 234591 117120 234591 117120 234592 117121 234592 117110 234592 117120 234593 117110 234593 117122 234593 117122 234594 117110 234594 117123 234594 117122 234595 117123 234595 117050 234595 117124 234596 117177 234596 116193 234596 116193 234597 117177 234597 117125 234597 116193 234598 117125 234598 116194 234598 116194 234599 117125 234599 117126 234599 116194 234600 117126 234600 116195 234600 116195 234601 117126 234601 117112 234601 116195 234602 117112 234602 117127 234602 117127 234603 117112 234603 117128 234603 117127 234604 117128 234604 116186 234604 116186 234605 117128 234605 117116 234605 116186 234606 117116 234606 116185 234606 116185 234607 117116 234607 117117 234607 116185 234608 117117 234608 117129 234608 117129 234609 117117 234609 117118 234609 117129 234610 117118 234610 116182 234610 116182 234611 117118 234611 117120 234611 116182 234612 117120 234612 116181 234612 116181 234613 117120 234613 117122 234613 116181 234614 117122 234614 116178 234614 116178 234615 117122 234615 117050 234615 116178 234616 117050 234616 116174 234616 117074 234617 114903 234617 114904 234617 117075 234618 117074 234618 117140 234618 117140 234619 117130 234619 117075 234619 117075 234620 117130 234620 117137 234620 117075 234621 117137 234621 117091 234621 117091 234622 117137 234622 117136 234622 117091 234623 117136 234623 116150 234623 116150 234624 117136 234624 117131 234624 116150 234625 117131 234625 117134 234625 117074 234626 114904 234626 117140 234626 117140 234627 114904 234627 117132 234627 117140 234628 117132 234628 117194 234628 117187 234629 117134 234629 117133 234629 117133 234630 117134 234630 117131 234630 117133 234631 117131 234631 117135 234631 117135 234632 117131 234632 117136 234632 117135 234633 117136 234633 117138 234633 117138 234634 117136 234634 117137 234634 117138 234635 117137 234635 117139 234635 117139 234636 117137 234636 117130 234636 117139 234637 117130 234637 117190 234637 117190 234638 117130 234638 117140 234638 117190 234639 117140 234639 117193 234639 117193 234640 117140 234640 117194 234640 117101 234641 117102 234641 117161 234641 117141 234642 116123 234642 117145 234642 117143 234643 117141 234643 117154 234643 117142 234644 117143 234644 117162 234644 116172 234645 117142 234645 117144 234645 117141 234646 117145 234646 117154 234646 117154 234647 117145 234647 117146 234647 117154 234648 117146 234648 117155 234648 117155 234649 117146 234649 117148 234649 117155 234650 117148 234650 117147 234650 117148 234651 117149 234651 117147 234651 117147 234652 117149 234652 116131 234652 117147 234653 116131 234653 117156 234653 117156 234654 116131 234654 117150 234654 117156 234655 117150 234655 117151 234655 117151 234656 117150 234656 116134 234656 117151 234657 116134 234657 117152 234657 116134 234658 116135 234658 117152 234658 117152 234659 116135 234659 117153 234659 117152 234660 117153 234660 117161 234660 117161 234661 117153 234661 116140 234661 117161 234662 116140 234662 117101 234662 117143 234663 117154 234663 117162 234663 117162 234664 117154 234664 117155 234664 117162 234665 117155 234665 117163 234665 117163 234666 117155 234666 117147 234666 117163 234667 117147 234667 117157 234667 117157 234668 117147 234668 117156 234668 117157 234669 117156 234669 117158 234669 117158 234670 117156 234670 117151 234670 117158 234671 117151 234671 117159 234671 117159 234672 117151 234672 117152 234672 117159 234673 117152 234673 117160 234673 117160 234674 117152 234674 117161 234674 117160 234675 117161 234675 117165 234675 117165 234676 117161 234676 117102 234676 117165 234677 117102 234677 117103 234677 117142 234678 117162 234678 117144 234678 117144 234679 117162 234679 117163 234679 117144 234680 117163 234680 117164 234680 117164 234681 117163 234681 117157 234681 117164 234682 117157 234682 117168 234682 117168 234683 117157 234683 117158 234683 117168 234684 117158 234684 117170 234684 117170 234685 117158 234685 117159 234685 117170 234686 117159 234686 117172 234686 117172 234687 117159 234687 117160 234687 117172 234688 117160 234688 117174 234688 117174 234689 117160 234689 117165 234689 117174 234690 117165 234690 117175 234690 117175 234691 117165 234691 117103 234691 117175 234692 117103 234692 117177 234692 116172 234693 117144 234693 117166 234693 117166 234694 117144 234694 117164 234694 117166 234695 117164 234695 117167 234695 117167 234696 117164 234696 117168 234696 117167 234697 117168 234697 117169 234697 117169 234698 117168 234698 117170 234698 117169 234699 117170 234699 116190 234699 116190 234700 117170 234700 117172 234700 116190 234701 117172 234701 117171 234701 117171 234702 117172 234702 117174 234702 117171 234703 117174 234703 117173 234703 117173 234704 117174 234704 117175 234704 117173 234705 117175 234705 117176 234705 117176 234706 117175 234706 117177 234706 117176 234707 117177 234707 117124 234707 117203 234708 116488 234708 116487 234708 117182 234709 117206 234709 117204 234709 117206 234710 117182 234710 117178 234710 116032 234711 117178 234711 117179 234711 117186 234712 117188 234712 116483 234712 116483 234713 117188 234713 117180 234713 117203 234714 116487 234714 117181 234714 117181 234715 116487 234715 116486 234715 117181 234716 116486 234716 117180 234716 117180 234717 116486 234717 116484 234717 117180 234718 116484 234718 116483 234718 117178 234719 117182 234719 117179 234719 117179 234720 117182 234720 117184 234720 117179 234721 117184 234721 117183 234721 117183 234722 117184 234722 117185 234722 117183 234723 117185 234723 117189 234723 117186 234724 117187 234724 117188 234724 117188 234725 117187 234725 117133 234725 117188 234726 117133 234726 117135 234726 117135 234727 117185 234727 117188 234727 117188 234728 117185 234728 117184 234728 117188 234729 117184 234729 117180 234729 117180 234730 117184 234730 117182 234730 117180 234731 117182 234731 117181 234731 117181 234732 117182 234732 117204 234732 117181 234733 117204 234733 117203 234733 117135 234734 117138 234734 117185 234734 117185 234735 117138 234735 117139 234735 117185 234736 117139 234736 117189 234736 117189 234737 117139 234737 117190 234737 117189 234738 117190 234738 117193 234738 116032 234739 117179 234739 117191 234739 117191 234740 117179 234740 117183 234740 117191 234741 117183 234741 117192 234741 117192 234742 117183 234742 117189 234742 117192 234743 117189 234743 114908 234743 114908 234744 117189 234744 117193 234744 114908 234745 117193 234745 117194 234745 116126 234746 116125 234746 117196 234746 117195 234747 116123 234747 117141 234747 117142 234748 116172 234748 115286 234748 116125 234749 117195 234749 117196 234749 117196 234750 117195 234750 117141 234750 117196 234751 117141 234751 117198 234751 117198 234752 117141 234752 117143 234752 117198 234753 117143 234753 117201 234753 117201 234754 117143 234754 117142 234754 117201 234755 117142 234755 117202 234755 117202 234756 117142 234756 115286 234756 117202 234757 115286 234757 116493 234757 116127 234758 116126 234758 117215 234758 117215 234759 116126 234759 117196 234759 117215 234760 117196 234760 117197 234760 117197 234761 117196 234761 117198 234761 117197 234762 117198 234762 117199 234762 117199 234763 117198 234763 117201 234763 117199 234764 117201 234764 117200 234764 117200 234765 117201 234765 117202 234765 117200 234766 117202 234766 117213 234766 117213 234767 117202 234767 116493 234767 117230 234768 117229 234768 117205 234768 117229 234769 117228 234769 116489 234769 117207 234770 116029 234770 117231 234770 117229 234771 116489 234771 117205 234771 117205 234772 116489 234772 116488 234772 117205 234773 116488 234773 117203 234773 117203 234774 117204 234774 117205 234774 117205 234775 117204 234775 117207 234775 117205 234776 117207 234776 117230 234776 117230 234777 117207 234777 117231 234777 117204 234778 117206 234778 117207 234778 117207 234779 117206 234779 117178 234779 117207 234780 117178 234780 116029 234780 116029 234781 117178 234781 116032 234781 116496 234782 117208 234782 117209 234782 117218 234783 117210 234783 117219 234783 117221 234784 117211 234784 117224 234784 116493 234785 117212 234785 117213 234785 117213 234786 117212 234786 117214 234786 117220 234787 117199 234787 117214 234787 117214 234788 117199 234788 117200 234788 117214 234789 117200 234789 117213 234789 117210 234790 116127 234790 117219 234790 117219 234791 116127 234791 117215 234791 117219 234792 117215 234792 117220 234792 117220 234793 117215 234793 117197 234793 117220 234794 117197 234794 117199 234794 117216 234795 117218 234795 117217 234795 117217 234796 117218 234796 117219 234796 117217 234797 117219 234797 117222 234797 117222 234798 117219 234798 117220 234798 117222 234799 117220 234799 117224 234799 117224 234800 117220 234800 117214 234800 117224 234801 117214 234801 117221 234801 117221 234802 117214 234802 117212 234802 117225 234803 117216 234803 117227 234803 117227 234804 117216 234804 117217 234804 117227 234805 117217 234805 117223 234805 117223 234806 117217 234806 117222 234806 117223 234807 117222 234807 117209 234807 117209 234808 117222 234808 117224 234808 117209 234809 117224 234809 116496 234809 116496 234810 117224 234810 117211 234810 117257 234811 117225 234811 117226 234811 117226 234812 117225 234812 117227 234812 117226 234813 117227 234813 117255 234813 117255 234814 117227 234814 117223 234814 117255 234815 117223 234815 117254 234815 117254 234816 117223 234816 117209 234816 117254 234817 117209 234817 116499 234817 116499 234818 117209 234818 117208 234818 117228 234819 117229 234819 117236 234819 117229 234820 117230 234820 117232 234820 117230 234821 117231 234821 116025 234821 117230 234822 116025 234822 117232 234822 117232 234823 116025 234823 116024 234823 117232 234824 116024 234824 117237 234824 117237 234825 116024 234825 116028 234825 117237 234826 116028 234826 117238 234826 117238 234827 116028 234827 116027 234827 117238 234828 116027 234828 117239 234828 117239 234829 116027 234829 116038 234829 117239 234830 116038 234830 117233 234830 117233 234831 116038 234831 116054 234831 117233 234832 116054 234832 117241 234832 117241 234833 116054 234833 117234 234833 117241 234834 117234 234834 117235 234834 117235 234835 117234 234835 116051 234835 117235 234836 116051 234836 117244 234836 117229 234837 117232 234837 117236 234837 117236 234838 117232 234838 117237 234838 117236 234839 117237 234839 117246 234839 117246 234840 117237 234840 117238 234840 117246 234841 117238 234841 117247 234841 117247 234842 117238 234842 117239 234842 117247 234843 117239 234843 117240 234843 117240 234844 117239 234844 117233 234844 117240 234845 117233 234845 117249 234845 117249 234846 117233 234846 117241 234846 117249 234847 117241 234847 117242 234847 117242 234848 117241 234848 117235 234848 117242 234849 117235 234849 117243 234849 117243 234850 117235 234850 117244 234850 117243 234851 117244 234851 117245 234851 117228 234852 117236 234852 116479 234852 116479 234853 117236 234853 117246 234853 116479 234854 117246 234854 116478 234854 116478 234855 117246 234855 117247 234855 116478 234856 117247 234856 117248 234856 117248 234857 117247 234857 117240 234857 117248 234858 117240 234858 117250 234858 117250 234859 117240 234859 117249 234859 117250 234860 117249 234860 117251 234860 117251 234861 117249 234861 117242 234861 117251 234862 117242 234862 117252 234862 117252 234863 117242 234863 117243 234863 117252 234864 117243 234864 116472 234864 116472 234865 117243 234865 117245 234865 116472 234866 117245 234866 117253 234866 116499 234867 117258 234867 117254 234867 117254 234868 117258 234868 117259 234868 117254 234869 117259 234869 117255 234869 117255 234870 117259 234870 117256 234870 117255 234871 117256 234871 117226 234871 117226 234872 117256 234872 117260 234872 117226 234873 117260 234873 117257 234873 117257 234874 117260 234874 116043 234874 117258 234875 116502 234875 117259 234875 117259 234876 116502 234876 117299 234876 117259 234877 117299 234877 117256 234877 117256 234878 117299 234878 117298 234878 117256 234879 117298 234879 117260 234879 117260 234880 117298 234880 117297 234880 117260 234881 117297 234881 116043 234881 116043 234882 117297 234882 117261 234882 116036 234883 117267 234883 117270 234883 117267 234884 117301 234884 117262 234884 117301 234885 117300 234885 116451 234885 117301 234886 116451 234886 117262 234886 117262 234887 116451 234887 117263 234887 117262 234888 117263 234888 117268 234888 117268 234889 117263 234889 116453 234889 117268 234890 116453 234890 117264 234890 117264 234891 116453 234891 116455 234891 117264 234892 116455 234892 117265 234892 117265 234893 116455 234893 117266 234893 117265 234894 117266 234894 117269 234894 117269 234895 117266 234895 117253 234895 117269 234896 117253 234896 117245 234896 117267 234897 117262 234897 117270 234897 117270 234898 117262 234898 117268 234898 117270 234899 117268 234899 117272 234899 117272 234900 117268 234900 117264 234900 117272 234901 117264 234901 117273 234901 117273 234902 117264 234902 117265 234902 117273 234903 117265 234903 117275 234903 117275 234904 117265 234904 117269 234904 117275 234905 117269 234905 117276 234905 117276 234906 117269 234906 117245 234906 117276 234907 117245 234907 117244 234907 116036 234908 117270 234908 116039 234908 116039 234909 117270 234909 117272 234909 116039 234910 117272 234910 117271 234910 117271 234911 117272 234911 117273 234911 117271 234912 117273 234912 117274 234912 117274 234913 117273 234913 117275 234913 117274 234914 117275 234914 116040 234914 116040 234915 117275 234915 117276 234915 116040 234916 117276 234916 116050 234916 116050 234917 117276 234917 117244 234917 116050 234918 117244 234918 116051 234918 117277 234919 116469 234919 117289 234919 117290 234920 116467 234920 117284 234920 116057 234921 117278 234921 117306 234921 117306 234922 117278 234922 117280 234922 117306 234923 117280 234923 117307 234923 117307 234924 117280 234924 117281 234924 117286 234925 117279 234925 117281 234925 117281 234926 117279 234926 117312 234926 117281 234927 117312 234927 117307 234927 117278 234928 116056 234928 117280 234928 117280 234929 116056 234929 117282 234929 117280 234930 117282 234930 117281 234930 117281 234931 117282 234931 117283 234931 117281 234932 117283 234932 117286 234932 117286 234933 117283 234933 117284 234933 117285 234934 117304 234934 117286 234934 117286 234935 117304 234935 117303 234935 117286 234936 117303 234936 117279 234936 117284 234937 116467 234937 117286 234937 117286 234938 116467 234938 117287 234938 117286 234939 117287 234939 117285 234939 116056 234940 117295 234940 117282 234940 117282 234941 117295 234941 117288 234941 117282 234942 117288 234942 117283 234942 117283 234943 117288 234943 117292 234943 117283 234944 117292 234944 117284 234944 117284 234945 117292 234945 117289 234945 117284 234946 117289 234946 117290 234946 117290 234947 117289 234947 116469 234947 116471 234948 117277 234948 117291 234948 117291 234949 117277 234949 117289 234949 117291 234950 117289 234950 117293 234950 117293 234951 117289 234951 117292 234951 117293 234952 117292 234952 117294 234952 117294 234953 117292 234953 117288 234953 117294 234954 117288 234954 117296 234954 117296 234955 117288 234955 117295 234955 117296 234956 117261 234956 117294 234956 117294 234957 117261 234957 117297 234957 117294 234958 117297 234958 117293 234958 117293 234959 117297 234959 117298 234959 117293 234960 117298 234960 117291 234960 117291 234961 117298 234961 117299 234961 117291 234962 117299 234962 116471 234962 116471 234963 117299 234963 116502 234963 116459 234964 117300 234964 117301 234964 116459 234965 117301 234965 117311 234965 117311 234966 117301 234966 117267 234966 117311 234967 117267 234967 117302 234967 117302 234968 117267 234968 116036 234968 117302 234969 116036 234969 116037 234969 117303 234970 117304 234970 116465 234970 117312 234971 117279 234971 117305 234971 117305 234972 117279 234972 117303 234972 117306 234973 117307 234973 117313 234973 117313 234974 117307 234974 117312 234974 116059 234975 116057 234975 117306 234975 117303 234976 116465 234976 117305 234976 117305 234977 116465 234977 116463 234977 117305 234978 116463 234978 117308 234978 117308 234979 116463 234979 116462 234979 117308 234980 116462 234980 117309 234980 117309 234981 116462 234981 116461 234981 117309 234982 116461 234982 117316 234982 117316 234983 116461 234983 116460 234983 117316 234984 116460 234984 117310 234984 117310 234985 116460 234985 116459 234985 117310 234986 116459 234986 117311 234986 117312 234987 117305 234987 117313 234987 117313 234988 117305 234988 117308 234988 117313 234989 117308 234989 117314 234989 117314 234990 117308 234990 117309 234990 117314 234991 117309 234991 117315 234991 117315 234992 117309 234992 117316 234992 117315 234993 117316 234993 117317 234993 117317 234994 117316 234994 117310 234994 117317 234995 117310 234995 117318 234995 117318 234996 117310 234996 117311 234996 117318 234997 117311 234997 117302 234997 117306 234998 117313 234998 116059 234998 116059 234999 117313 234999 117314 234999 116059 235000 117314 235000 116060 235000 116060 235001 117314 235001 117315 235001 116060 235002 117315 235002 116061 235002 116061 235003 117315 235003 117317 235003 116061 235004 117317 235004 116062 235004 116062 235005 117317 235005 117318 235005 116062 235006 117318 235006 117319 235006 117319 235007 117318 235007 117302 235007 117319 235008 117302 235008 116037 235008 117320 235009 113566 235009 117321 235009 117352 235010 117323 235010 117322 235010 117322 235011 117323 235011 117324 235011 117322 235012 117324 235012 116535 235012 117321 235013 117367 235013 117320 235013 117320 235014 117367 235014 117325 235014 117320 235015 117325 235015 117327 235015 117327 235016 117325 235016 117326 235016 117327 235017 117326 235017 117322 235017 117322 235018 117326 235018 117360 235018 117322 235019 117360 235019 117352 235019 117328 235020 116529 235020 117336 235020 117329 235021 115961 235021 117372 235021 117372 235022 115961 235022 117332 235022 117372 235023 117332 235023 117370 235023 117370 235024 117332 235024 117334 235024 117370 235025 117334 235025 117330 235025 117330 235026 117334 235026 117336 235026 117330 235027 117336 235027 117368 235027 117368 235028 117336 235028 116529 235028 115961 235029 117331 235029 117332 235029 117332 235030 117331 235030 117333 235030 117332 235031 117333 235031 117334 235031 117334 235032 117333 235032 117335 235032 117334 235033 117335 235033 117336 235033 117336 235034 117335 235034 117338 235034 117336 235035 117338 235035 117328 235035 117328 235036 117338 235036 117339 235036 117331 235037 115959 235037 117333 235037 117333 235038 115959 235038 117337 235038 117333 235039 117337 235039 117335 235039 117335 235040 117337 235040 117340 235040 117335 235041 117340 235041 117338 235041 117338 235042 117340 235042 117341 235042 117338 235043 117341 235043 117339 235043 117339 235044 117341 235044 116534 235044 115959 235045 113566 235045 117337 235045 117337 235046 113566 235046 117320 235046 117337 235047 117320 235047 117340 235047 117340 235048 117320 235048 117327 235048 117340 235049 117327 235049 117341 235049 117341 235050 117327 235050 117322 235050 117341 235051 117322 235051 116534 235051 116534 235052 117322 235052 116535 235052 117376 235053 117343 235053 117342 235053 117342 235054 117343 235054 117377 235054 117373 235055 117374 235055 117345 235055 117345 235056 117374 235056 117376 235056 113563 235057 117344 235057 117373 235057 117376 235058 117342 235058 117345 235058 117345 235059 117342 235059 117357 235059 117345 235060 117357 235060 117362 235060 117362 235061 117357 235061 117356 235061 117362 235062 117356 235062 117346 235062 117346 235063 117356 235063 117347 235063 117346 235064 117347 235064 117365 235064 117365 235065 117347 235065 117349 235065 117365 235066 117349 235066 117348 235066 117348 235067 117349 235067 117350 235067 117348 235068 117350 235068 117351 235068 117351 235069 117350 235069 117361 235069 117351 235070 117361 235070 117366 235070 117353 235071 117323 235071 117352 235071 117352 235072 117361 235072 117353 235072 117353 235073 117361 235073 117350 235073 117353 235074 117350 235074 116525 235074 116525 235075 117350 235075 117349 235075 116525 235076 117349 235076 117354 235076 117354 235077 117349 235077 117347 235077 117354 235078 117347 235078 117355 235078 117355 235079 117347 235079 117356 235079 117355 235080 117356 235080 116526 235080 116526 235081 117356 235081 117357 235081 116526 235082 117357 235082 116527 235082 116527 235083 117357 235083 117342 235083 116527 235084 117342 235084 117358 235084 117358 235085 117342 235085 117377 235085 117358 235086 117377 235086 117359 235086 117352 235087 117360 235087 117361 235087 117361 235088 117360 235088 117326 235088 117361 235089 117326 235089 117366 235089 117366 235090 117326 235090 117325 235090 117366 235091 117325 235091 117367 235091 117373 235092 117345 235092 113563 235092 113563 235093 117345 235093 117362 235093 113563 235094 117362 235094 113561 235094 113561 235095 117362 235095 117346 235095 113561 235096 117346 235096 117363 235096 117363 235097 117346 235097 117365 235097 117363 235098 117365 235098 117364 235098 117364 235099 117365 235099 117348 235099 117364 235100 117348 235100 113559 235100 113559 235101 117348 235101 117351 235101 113559 235102 117351 235102 113558 235102 113558 235103 117351 235103 117366 235103 113558 235104 117366 235104 113564 235104 113564 235105 117366 235105 117367 235105 113564 235106 117367 235106 117321 235106 117368 235107 115276 235107 117391 235107 117368 235108 117391 235108 117330 235108 117330 235109 117391 235109 117369 235109 117330 235110 117369 235110 117370 235110 117370 235111 117369 235111 117371 235111 117370 235112 117371 235112 117372 235112 117372 235113 117371 235113 115958 235113 117372 235114 115958 235114 117329 235114 117397 235115 116540 235115 117378 235115 117344 235116 113575 235116 117373 235116 117373 235117 113575 235117 117395 235117 117373 235118 117395 235118 117374 235118 117374 235119 117395 235119 117376 235119 117376 235120 117395 235120 117375 235120 117376 235121 117375 235121 117343 235121 117343 235122 117375 235122 117397 235122 117343 235123 117397 235123 117377 235123 117377 235124 117397 235124 117378 235124 117377 235125 117378 235125 117359 235125 117379 235126 117404 235126 117380 235126 117381 235127 117408 235127 117383 235127 117409 235128 117382 235128 115965 235128 117409 235129 115965 235129 117408 235129 117381 235130 117383 235130 117404 235130 117379 235131 117380 235131 116509 235131 117408 235132 115965 235132 117383 235132 117383 235133 115965 235133 117385 235133 117383 235134 117385 235134 117384 235134 117384 235135 117385 235135 117386 235135 117384 235136 117386 235136 117388 235136 117388 235137 117386 235137 117387 235137 117388 235138 117387 235138 117390 235138 117387 235139 115958 235139 117390 235139 117390 235140 115958 235140 117371 235140 117390 235141 117371 235141 117369 235141 117404 235142 117383 235142 117380 235142 117380 235143 117383 235143 117384 235143 117380 235144 117384 235144 117392 235144 117392 235145 117384 235145 117388 235145 117392 235146 117388 235146 117393 235146 117393 235147 117388 235147 117390 235147 117393 235148 117390 235148 117389 235148 117389 235149 117390 235149 117369 235149 117389 235150 117369 235150 117391 235150 116509 235151 117380 235151 116507 235151 116507 235152 117380 235152 117392 235152 116507 235153 117392 235153 116506 235153 116506 235154 117392 235154 117393 235154 116506 235155 117393 235155 116504 235155 116504 235156 117393 235156 117389 235156 116504 235157 117389 235157 117394 235157 117394 235158 117389 235158 117391 235158 117394 235159 117391 235159 115276 235159 117400 235160 116541 235160 117398 235160 113575 235161 115943 235161 117395 235161 117395 235162 115943 235162 117396 235162 117395 235163 117396 235163 117375 235163 117375 235164 117396 235164 117402 235164 117375 235165 117402 235165 117397 235165 117397 235166 117402 235166 117398 235166 117397 235167 117398 235167 116540 235167 116540 235168 117398 235168 116541 235168 117399 235169 117400 235169 117401 235169 117401 235170 117400 235170 117398 235170 117401 235171 117398 235171 117413 235171 117413 235172 117398 235172 117402 235172 117413 235173 117402 235173 117414 235173 117414 235174 117402 235174 117396 235174 117414 235175 117396 235175 115919 235175 115919 235176 117396 235176 115943 235176 117444 235177 117428 235177 117382 235177 117404 235178 117379 235178 117405 235178 117379 235179 116509 235179 117405 235179 117405 235180 116509 235180 117403 235180 117405 235181 117403 235181 116508 235181 117404 235182 117405 235182 117381 235182 117381 235183 117405 235183 117406 235183 117381 235184 117406 235184 117408 235184 117406 235185 117407 235185 117408 235185 117408 235186 117407 235186 117444 235186 117408 235187 117444 235187 117409 235187 117409 235188 117444 235188 117382 235188 115921 235189 117426 235189 117410 235189 117411 235190 117399 235190 117416 235190 117416 235191 117399 235191 117401 235191 117416 235192 117401 235192 117412 235192 117412 235193 117401 235193 117413 235193 117412 235194 117413 235194 117419 235194 117419 235195 117413 235195 117414 235195 117419 235196 117414 235196 115918 235196 115918 235197 117414 235197 115919 235197 116538 235198 117411 235198 117415 235198 117415 235199 117411 235199 117416 235199 117415 235200 117416 235200 117417 235200 117417 235201 117416 235201 117412 235201 117417 235202 117412 235202 117418 235202 117418 235203 117412 235203 117419 235203 117418 235204 117419 235204 117421 235204 117421 235205 117419 235205 115918 235205 116537 235206 116538 235206 117420 235206 117420 235207 116538 235207 117415 235207 117420 235208 117415 235208 117423 235208 117423 235209 117415 235209 117417 235209 117423 235210 117417 235210 117410 235210 117410 235211 117417 235211 117418 235211 117410 235212 117418 235212 115921 235212 115921 235213 117418 235213 117421 235213 116148 235214 116537 235214 117422 235214 117422 235215 116537 235215 117420 235215 117422 235216 117420 235216 117469 235216 117469 235217 117420 235217 117423 235217 117469 235218 117423 235218 117424 235218 117424 235219 117423 235219 117410 235219 117424 235220 117410 235220 117425 235220 117425 235221 117410 235221 117426 235221 117406 235222 117405 235222 117427 235222 117444 235223 117407 235223 117438 235223 117438 235224 117407 235224 117406 235224 117445 235225 117428 235225 117444 235225 116521 235226 117429 235226 116520 235226 116520 235227 117429 235227 117430 235227 116520 235228 117430 235228 116518 235228 116518 235229 117430 235229 117431 235229 116518 235230 117431 235230 117432 235230 117432 235231 117431 235231 117441 235231 117432 235232 117441 235232 116517 235232 116517 235233 117441 235233 117433 235233 116517 235234 117433 235234 117434 235234 117434 235235 117433 235235 117435 235235 117434 235236 117435 235236 117436 235236 117436 235237 117435 235237 117427 235237 117436 235238 117427 235238 117437 235238 117437 235239 117427 235239 117405 235239 117437 235240 117405 235240 116508 235240 117406 235241 117427 235241 117438 235241 117438 235242 117427 235242 117435 235242 117438 235243 117435 235243 117447 235243 117447 235244 117435 235244 117433 235244 117447 235245 117433 235245 117439 235245 117439 235246 117433 235246 117441 235246 117439 235247 117441 235247 117440 235247 117440 235248 117441 235248 117431 235248 117440 235249 117431 235249 117448 235249 117448 235250 117431 235250 117430 235250 117448 235251 117430 235251 117449 235251 117449 235252 117430 235252 117429 235252 117449 235253 117429 235253 117443 235253 116521 235254 117482 235254 117429 235254 117429 235255 117482 235255 117442 235255 117429 235256 117442 235256 117443 235256 117443 235257 117442 235257 117479 235257 117443 235258 117479 235258 117451 235258 117444 235259 117438 235259 117445 235259 117445 235260 117438 235260 117447 235260 117445 235261 117447 235261 117446 235261 117446 235262 117447 235262 117439 235262 117446 235263 117439 235263 113625 235263 113625 235264 117439 235264 117440 235264 113625 235265 117440 235265 113624 235265 113624 235266 117440 235266 117448 235266 113624 235267 117448 235267 113623 235267 113623 235268 117448 235268 117449 235268 113623 235269 117449 235269 117450 235269 117450 235270 117449 235270 117443 235270 117450 235271 117443 235271 113627 235271 113627 235272 117443 235272 117451 235272 113627 235273 117451 235273 113628 235273 117452 235274 117453 235274 117473 235274 117454 235275 117463 235275 117464 235275 117456 235276 117455 235276 117475 235276 117475 235277 117455 235277 116148 235277 117475 235278 116148 235278 117422 235278 117456 235279 117475 235279 117457 235279 117457 235280 117475 235280 117476 235280 117457 235281 117476 235281 117458 235281 117458 235282 117476 235282 117460 235282 117458 235283 117460 235283 116145 235283 116145 235284 117460 235284 117459 235284 117459 235285 117460 235285 117461 235285 117459 235286 117461 235286 117485 235286 117422 235287 117469 235287 117474 235287 115924 235288 117462 235288 117463 235288 117463 235289 117462 235289 115925 235289 117463 235290 115925 235290 117464 235290 115925 235291 115928 235291 117464 235291 117464 235292 115928 235292 117465 235292 117464 235293 117465 235293 117468 235293 117468 235294 117465 235294 117466 235294 117468 235295 117466 235295 117467 235295 117454 235296 117464 235296 117470 235296 117470 235297 117464 235297 117468 235297 117470 235298 117468 235298 117472 235298 117472 235299 117468 235299 117467 235299 117472 235300 117467 235300 117483 235300 117425 235301 115924 235301 117424 235301 117424 235302 115924 235302 117463 235302 117424 235303 117463 235303 117469 235303 117469 235304 117463 235304 117454 235304 117469 235305 117454 235305 117474 235305 117474 235306 117454 235306 117470 235306 117474 235307 117470 235307 117471 235307 117471 235308 117470 235308 117472 235308 117471 235309 117472 235309 117473 235309 117473 235310 117472 235310 117483 235310 117473 235311 117483 235311 117452 235311 117422 235312 117474 235312 117475 235312 117475 235313 117474 235313 117471 235313 117475 235314 117471 235314 117476 235314 117476 235315 117471 235315 117473 235315 117476 235316 117473 235316 117460 235316 117460 235317 117473 235317 117453 235317 117460 235318 117453 235318 117461 235318 116549 235319 116547 235319 117481 235319 116549 235320 117481 235320 116521 235320 113629 235321 113628 235321 117477 235321 117477 235322 113628 235322 117451 235322 117477 235323 117451 235323 117478 235323 117478 235324 117451 235324 117479 235324 117478 235325 117479 235325 117480 235325 117480 235326 117479 235326 117442 235326 117480 235327 117442 235327 117481 235327 117481 235328 117442 235328 117482 235328 117481 235329 117482 235329 116521 235329 117486 235330 117488 235330 117485 235330 115930 235331 117492 235331 117484 235331 117466 235332 115930 235332 117467 235332 117467 235333 115930 235333 117484 235333 117467 235334 117484 235334 117483 235334 117483 235335 117484 235335 117487 235335 117485 235336 117461 235336 117486 235336 117486 235337 117461 235337 117453 235337 117486 235338 117453 235338 117487 235338 117487 235339 117453 235339 117452 235339 117487 235340 117452 235340 117483 235340 116175 235341 117488 235341 117494 235341 117494 235342 117488 235342 117486 235342 117494 235343 117486 235343 117489 235343 117489 235344 117486 235344 117487 235344 117489 235345 117487 235345 117490 235345 117490 235346 117487 235346 117484 235346 117490 235347 117484 235347 117491 235347 117491 235348 117484 235348 117492 235348 117495 235349 116175 235349 117493 235349 117493 235350 116175 235350 117494 235350 117493 235351 117494 235351 117497 235351 117497 235352 117494 235352 117489 235352 117497 235353 117489 235353 117499 235353 117499 235354 117489 235354 117490 235354 117499 235355 117490 235355 115935 235355 115935 235356 117490 235356 117491 235356 116173 235357 117495 235357 117507 235357 117507 235358 117495 235358 117493 235358 117507 235359 117493 235359 117496 235359 117496 235360 117493 235360 117497 235360 117496 235361 117497 235361 117498 235361 117498 235362 117497 235362 117499 235362 117498 235363 117499 235363 115936 235363 115936 235364 117499 235364 115935 235364 117552 235365 115940 235365 117500 235365 117503 235366 117505 235366 117561 235366 117501 235367 117504 235367 117556 235367 117556 235368 117504 235368 117503 235368 117556 235369 117503 235369 117502 235369 117502 235370 117503 235370 117561 235370 113629 235371 117477 235371 117500 235371 117500 235372 117477 235372 117504 235372 117500 235373 117504 235373 117552 235373 117552 235374 117504 235374 117501 235374 117477 235375 117478 235375 117504 235375 117504 235376 117478 235376 117480 235376 117504 235377 117480 235377 117503 235377 117503 235378 117480 235378 117481 235378 117503 235379 117481 235379 117505 235379 117505 235380 117481 235380 116547 235380 117537 235381 117506 235381 117526 235381 117506 235382 117536 235382 117527 235382 116180 235383 116173 235383 117507 235383 116197 235384 117508 235384 117518 235384 117509 235385 117510 235385 117543 235385 117543 235386 117510 235386 116208 235386 116208 235387 117510 235387 117511 235387 117511 235388 117510 235388 117512 235388 117511 235389 117512 235389 117513 235389 117513 235390 117512 235390 117528 235390 117513 235391 117528 235391 117514 235391 117514 235392 117528 235392 117527 235392 117514 235393 117527 235393 117515 235393 117515 235394 117527 235394 117536 235394 117515 235395 117536 235395 117534 235395 116180 235396 117507 235396 116179 235396 117523 235397 117516 235397 117519 235397 117519 235398 117516 235398 117522 235398 117519 235399 117522 235399 117517 235399 117517 235400 117522 235400 117521 235400 117517 235401 117521 235401 116201 235401 116201 235402 116197 235402 117517 235402 117517 235403 116197 235403 117518 235403 117517 235404 117518 235404 117519 235404 117519 235405 117518 235405 117535 235405 117519 235406 117535 235406 117523 235406 117523 235407 117535 235407 117520 235407 115936 235408 116201 235408 117498 235408 117498 235409 116201 235409 117521 235409 117498 235410 117521 235410 117496 235410 117496 235411 117521 235411 117522 235411 117496 235412 117522 235412 117507 235412 117507 235413 117522 235413 117516 235413 117507 235414 117516 235414 116179 235414 116179 235415 117516 235415 117523 235415 116179 235416 117523 235416 117525 235416 117525 235417 117523 235417 117520 235417 116184 235418 116183 235418 117520 235418 117520 235419 116183 235419 117524 235419 117520 235420 117524 235420 117525 235420 117506 235421 117527 235421 117526 235421 117526 235422 117527 235422 117528 235422 117526 235423 117528 235423 117529 235423 117529 235424 117528 235424 117512 235424 117529 235425 117512 235425 117530 235425 117530 235426 117512 235426 117510 235426 117530 235427 117510 235427 117531 235427 117531 235428 117510 235428 117509 235428 117531 235429 117509 235429 117532 235429 117537 235430 117526 235430 117533 235430 117533 235431 117526 235431 117529 235431 117533 235432 117529 235432 117538 235432 117538 235433 117529 235433 117530 235433 117538 235434 117530 235434 117540 235434 117540 235435 117530 235435 117531 235435 117540 235436 117531 235436 117541 235436 117541 235437 117531 235437 117532 235437 117541 235438 117532 235438 117544 235438 117508 235439 117534 235439 117518 235439 117518 235440 117534 235440 117536 235440 117518 235441 117536 235441 117535 235441 117535 235442 117536 235442 117506 235442 117535 235443 117506 235443 117520 235443 117520 235444 117506 235444 117537 235444 117520 235445 117537 235445 116184 235445 116184 235446 117537 235446 117533 235446 116184 235447 117533 235447 116187 235447 116187 235448 117533 235448 117538 235448 116187 235449 117538 235449 117539 235449 117539 235450 117538 235450 117540 235450 117539 235451 117540 235451 116188 235451 116188 235452 117540 235452 117541 235452 116188 235453 117541 235453 117542 235453 117542 235454 117541 235454 117544 235454 117542 235455 117544 235455 116192 235455 116192 235456 117544 235456 117545 235456 117543 235457 117562 235457 117509 235457 117509 235458 117562 235458 117566 235458 117509 235459 117566 235459 117532 235459 117532 235460 117566 235460 117564 235460 117532 235461 117564 235461 117544 235461 117544 235462 117564 235462 117565 235462 117544 235463 117565 235463 117545 235463 117545 235464 117565 235464 117546 235464 116292 235465 117553 235465 117550 235465 117606 235466 116290 235466 117547 235466 117611 235467 117606 235467 117549 235467 117610 235468 117611 235468 117555 235468 117557 235469 117610 235469 117558 235469 117606 235470 117547 235470 117549 235470 117549 235471 117547 235471 117548 235471 117549 235472 117548 235472 117550 235472 117550 235473 117548 235473 116293 235473 117550 235474 116293 235474 116292 235474 117611 235475 117549 235475 117555 235475 117555 235476 117549 235476 117550 235476 117555 235477 117550 235477 117551 235477 117551 235478 117550 235478 117553 235478 117551 235479 117553 235479 117554 235479 116292 235480 115940 235480 117553 235480 117553 235481 115940 235481 117552 235481 117553 235482 117552 235482 117554 235482 117554 235483 117552 235483 117501 235483 117554 235484 117501 235484 117556 235484 117610 235485 117555 235485 117558 235485 117558 235486 117555 235486 117551 235486 117558 235487 117551 235487 117559 235487 117559 235488 117551 235488 117554 235488 117559 235489 117554 235489 117560 235489 117560 235490 117554 235490 117556 235490 117560 235491 117556 235491 117502 235491 117557 235492 117558 235492 116544 235492 116544 235493 117558 235493 117559 235493 116544 235494 117559 235494 116545 235494 116545 235495 117559 235495 117560 235495 116545 235496 117560 235496 116546 235496 116546 235497 117560 235497 117502 235497 116546 235498 117502 235498 117561 235498 117566 235499 117562 235499 117563 235499 117564 235500 117566 235500 117567 235500 117565 235501 117564 235501 117582 235501 117546 235502 117565 235502 117581 235502 117574 235503 117577 235503 117576 235503 117566 235504 117563 235504 117567 235504 117567 235505 117563 235505 114458 235505 117567 235506 114458 235506 117576 235506 117576 235507 114458 235507 117568 235507 117576 235508 117568 235508 117574 235508 117569 235509 117570 235509 114475 235509 114475 235510 117570 235510 117571 235510 114475 235511 117571 235511 114467 235511 114467 235512 117571 235512 117580 235512 114467 235513 117580 235513 114466 235513 114466 235514 117580 235514 117572 235514 114466 235515 117572 235515 114465 235515 114465 235516 117572 235516 117573 235516 114465 235517 117573 235517 114464 235517 114464 235518 117573 235518 117577 235518 114464 235519 117577 235519 114460 235519 114460 235520 117577 235520 117574 235520 117564 235521 117567 235521 117582 235521 117582 235522 117567 235522 117576 235522 117582 235523 117576 235523 117575 235523 117575 235524 117576 235524 117577 235524 117575 235525 117577 235525 117584 235525 117584 235526 117577 235526 117573 235526 117584 235527 117573 235527 117578 235527 117578 235528 117573 235528 117572 235528 117578 235529 117572 235529 117579 235529 117579 235530 117572 235530 117580 235530 117579 235531 117580 235531 117585 235531 117585 235532 117580 235532 117571 235532 117585 235533 117571 235533 117586 235533 117586 235534 117571 235534 117570 235534 117586 235535 117570 235535 117619 235535 117565 235536 117582 235536 117581 235536 117581 235537 117582 235537 117575 235537 117581 235538 117575 235538 117583 235538 117583 235539 117575 235539 117584 235539 117583 235540 117584 235540 117588 235540 117588 235541 117584 235541 117578 235541 117588 235542 117578 235542 117590 235542 117590 235543 117578 235543 117579 235543 117590 235544 117579 235544 117591 235544 117591 235545 117579 235545 117585 235545 117591 235546 117585 235546 117593 235546 117593 235547 117585 235547 117586 235547 117593 235548 117586 235548 117594 235548 117594 235549 117586 235549 117619 235549 117594 235550 117619 235550 117621 235550 117546 235551 117581 235551 116191 235551 116191 235552 117581 235552 117583 235552 116191 235553 117583 235553 117587 235553 117587 235554 117583 235554 117588 235554 117587 235555 117588 235555 117589 235555 117589 235556 117588 235556 117590 235556 117589 235557 117590 235557 116189 235557 116189 235558 117590 235558 117591 235558 116189 235559 117591 235559 117592 235559 117592 235560 117591 235560 117593 235560 117592 235561 117593 235561 117595 235561 117595 235562 117593 235562 117594 235562 117595 235563 117594 235563 117596 235563 117596 235564 117594 235564 117621 235564 117596 235565 117621 235565 116171 235565 115279 235566 117640 235566 117601 235566 117598 235567 117599 235567 117601 235567 117601 235568 117599 235568 115278 235568 117601 235569 115278 235569 115279 235569 115280 235570 115281 235570 117603 235570 117603 235571 115281 235571 117597 235571 117603 235572 117597 235572 117598 235572 117598 235573 117597 235573 115284 235573 117598 235574 115284 235574 117599 235574 116277 235575 116276 235575 117600 235575 117600 235576 116276 235576 117608 235576 117600 235577 117608 235577 117622 235577 117602 235578 117636 235578 117635 235578 117636 235579 117602 235579 117640 235579 116276 235580 116274 235580 117608 235580 117608 235581 116274 235581 116272 235581 117608 235582 116272 235582 117609 235582 117609 235583 116272 235583 117605 235583 117640 235584 117602 235584 117601 235584 117601 235585 117602 235585 117614 235585 117601 235586 117614 235586 117598 235586 117598 235587 117614 235587 117612 235587 117598 235588 117612 235588 117603 235588 116272 235589 117604 235589 117605 235589 117605 235590 117604 235590 117607 235590 117605 235591 117607 235591 117606 235591 117606 235592 117607 235592 116290 235592 117622 235593 117608 235593 117616 235593 117616 235594 117608 235594 117609 235594 117616 235595 117609 235595 117615 235595 117615 235596 117609 235596 117605 235596 117615 235597 117605 235597 117613 235597 117613 235598 117605 235598 117606 235598 117613 235599 117606 235599 117611 235599 117557 235600 115280 235600 117610 235600 117610 235601 115280 235601 117603 235601 117610 235602 117603 235602 117611 235602 117611 235603 117603 235603 117612 235603 117611 235604 117612 235604 117613 235604 117613 235605 117612 235605 117614 235605 117613 235606 117614 235606 117615 235606 117615 235607 117614 235607 117602 235607 117615 235608 117602 235608 117616 235608 117616 235609 117602 235609 117635 235609 117616 235610 117635 235610 117622 235610 114474 235611 114473 235611 117618 235611 117617 235612 117619 235612 117618 235612 117618 235613 117619 235613 117570 235613 117618 235614 117570 235614 114474 235614 114474 235615 117570 235615 117569 235615 117617 235616 117641 235616 117619 235616 117619 235617 117641 235617 117620 235617 117619 235618 117620 235618 117621 235618 115285 235619 116171 235619 117642 235619 117642 235620 116171 235620 117621 235620 117642 235621 117621 235621 117644 235621 117644 235622 117621 235622 117620 235622 117636 235623 117640 235623 117639 235623 117622 235624 117635 235624 117632 235624 117698 235625 116263 235625 116284 235625 117696 235626 117698 235626 117624 235626 117695 235627 117696 235627 117629 235627 117623 235628 117695 235628 117633 235628 117698 235629 116284 235629 117624 235629 117624 235630 116284 235630 116281 235630 117624 235631 116281 235631 117630 235631 116277 235632 117600 235632 117625 235632 117625 235633 117600 235633 117626 235633 117625 235634 117626 235634 117627 235634 117627 235635 117626 235635 117630 235635 117627 235636 117630 235636 117628 235636 117628 235637 117630 235637 116281 235637 117696 235638 117624 235638 117629 235638 117629 235639 117624 235639 117630 235639 117629 235640 117630 235640 117631 235640 117631 235641 117630 235641 117626 235641 117631 235642 117626 235642 117632 235642 117632 235643 117626 235643 117600 235643 117632 235644 117600 235644 117622 235644 117695 235645 117629 235645 117633 235645 117633 235646 117629 235646 117631 235646 117633 235647 117631 235647 117634 235647 117634 235648 117631 235648 117632 235648 117634 235649 117632 235649 117639 235649 117639 235650 117632 235650 117635 235650 117639 235651 117635 235651 117636 235651 117623 235652 117633 235652 116169 235652 116169 235653 117633 235653 117634 235653 116169 235654 117634 235654 117637 235654 117637 235655 117634 235655 117639 235655 117637 235656 117639 235656 117638 235656 117638 235657 117639 235657 117640 235657 117638 235658 117640 235658 115279 235658 117652 235659 114476 235659 117654 235659 117653 235660 117643 235660 117641 235660 114473 235661 114471 235661 117618 235661 117618 235662 114471 235662 117653 235662 117618 235663 117653 235663 117617 235663 117617 235664 117653 235664 117641 235664 115285 235665 117642 235665 117655 235665 117655 235666 117642 235666 117644 235666 117655 235667 117644 235667 117643 235667 117643 235668 117644 235668 117620 235668 117643 235669 117620 235669 117641 235669 116497 235670 116495 235670 117655 235670 117655 235671 116495 235671 116494 235671 117655 235672 116494 235672 115285 235672 114476 235673 117651 235673 117654 235673 117654 235674 117651 235674 117645 235674 117654 235675 117645 235675 117646 235675 117646 235676 117645 235676 117647 235676 117646 235677 117647 235677 117656 235677 117656 235678 117647 235678 117648 235678 117703 235679 117648 235679 117649 235679 117649 235680 117648 235680 117647 235680 117649 235681 117647 235681 117650 235681 117650 235682 117647 235682 117645 235682 117650 235683 117645 235683 116298 235683 116298 235684 117645 235684 117651 235684 114471 235685 117652 235685 117653 235685 117653 235686 117652 235686 117654 235686 117653 235687 117654 235687 117643 235687 117643 235688 117654 235688 117646 235688 117643 235689 117646 235689 117655 235689 117655 235690 117646 235690 117656 235690 117655 235691 117656 235691 116497 235691 116497 235692 117656 235692 117648 235692 116497 235693 117648 235693 116498 235693 116498 235694 117648 235694 117703 235694 116498 235695 117703 235695 116500 235695 117657 235696 117700 235696 117658 235696 117658 235697 117700 235697 117659 235697 117658 235698 117659 235698 116257 235698 116257 235699 117659 235699 117677 235699 116257 235700 117677 235700 117660 235700 117660 235701 117677 235701 117661 235701 117660 235702 117661 235702 117662 235702 117662 235703 117661 235703 117674 235703 117662 235704 117674 235704 116248 235704 116248 235705 117674 235705 116251 235705 116251 235706 117674 235706 117673 235706 116251 235707 117673 235707 117663 235707 117663 235708 117673 235708 117664 235708 117663 235709 117664 235709 117665 235709 117665 235710 117664 235710 117671 235710 117665 235711 117671 235711 117667 235711 117668 235712 117666 235712 117671 235712 117671 235713 117666 235713 116270 235713 117671 235714 116270 235714 117667 235714 117670 235715 117716 235715 117668 235715 117668 235716 117716 235716 116268 235716 117668 235717 116268 235717 117666 235717 117669 235718 117670 235718 117679 235718 117670 235719 117668 235719 117679 235719 117679 235720 117668 235720 117671 235720 117679 235721 117671 235721 117680 235721 117680 235722 117671 235722 117664 235722 117680 235723 117664 235723 117672 235723 117672 235724 117664 235724 117673 235724 117672 235725 117673 235725 117681 235725 117681 235726 117673 235726 117674 235726 117681 235727 117674 235727 117675 235727 117675 235728 117674 235728 117661 235728 117675 235729 117661 235729 117676 235729 117676 235730 117661 235730 117677 235730 117676 235731 117677 235731 117684 235731 117684 235732 117677 235732 117659 235732 117684 235733 117659 235733 117685 235733 117685 235734 117659 235734 117700 235734 117685 235735 117700 235735 117699 235735 117669 235736 117679 235736 117678 235736 117678 235737 117679 235737 117680 235737 117678 235738 117680 235738 117688 235738 117688 235739 117680 235739 117672 235739 117688 235740 117672 235740 117689 235740 117689 235741 117672 235741 117681 235741 117689 235742 117681 235742 117682 235742 117682 235743 117681 235743 117675 235743 117682 235744 117675 235744 117692 235744 117692 235745 117675 235745 117676 235745 117692 235746 117676 235746 117683 235746 117683 235747 117676 235747 117684 235747 117683 235748 117684 235748 117686 235748 117686 235749 117684 235749 117685 235749 117686 235750 117685 235750 117694 235750 117694 235751 117685 235751 117699 235751 117694 235752 117699 235752 117697 235752 116156 235753 117669 235753 117687 235753 117687 235754 117669 235754 117678 235754 117687 235755 117678 235755 116158 235755 116158 235756 117678 235756 117688 235756 116158 235757 117688 235757 116159 235757 116159 235758 117688 235758 117689 235758 116159 235759 117689 235759 117690 235759 117690 235760 117689 235760 117682 235760 117690 235761 117682 235761 117691 235761 117691 235762 117682 235762 117692 235762 117691 235763 117692 235763 116163 235763 116163 235764 117692 235764 117683 235764 116163 235765 117683 235765 117693 235765 117693 235766 117683 235766 117686 235766 117693 235767 117686 235767 116164 235767 116164 235768 117686 235768 117694 235768 116164 235769 117694 235769 116165 235769 116165 235770 117694 235770 117697 235770 116165 235771 117697 235771 116167 235771 116167 235772 117697 235772 116168 235772 117623 235773 116168 235773 117695 235773 117695 235774 116168 235774 117697 235774 117695 235775 117697 235775 117696 235775 117696 235776 117697 235776 117699 235776 117696 235777 117699 235777 117698 235777 117698 235778 117699 235778 117700 235778 117698 235779 117700 235779 116263 235779 116263 235780 117700 235780 117657 235780 116298 235781 117701 235781 117650 235781 117650 235782 117701 235782 117705 235782 117650 235783 117705 235783 117649 235783 117649 235784 117705 235784 117702 235784 117649 235785 117702 235785 117703 235785 117703 235786 117702 235786 117706 235786 117703 235787 117706 235787 116500 235787 116500 235788 117706 235788 117708 235788 117701 235789 117704 235789 117705 235789 117705 235790 117704 235790 117742 235790 117705 235791 117742 235791 117702 235791 117702 235792 117742 235792 117707 235792 117702 235793 117707 235793 117706 235793 117706 235794 117707 235794 117743 235794 117706 235795 117743 235795 117708 235795 117708 235796 117743 235796 116501 235796 117750 235797 117713 235797 117712 235797 117748 235798 117750 235798 117725 235798 117709 235799 117748 235799 117710 235799 116225 235800 117719 235800 117711 235800 117711 235801 117719 235801 117712 235801 117711 235802 117712 235802 116223 235802 116223 235803 117712 235803 117713 235803 116223 235804 117713 235804 117751 235804 116237 235805 117722 235805 117720 235805 116225 235806 117714 235806 117719 235806 117719 235807 117714 235807 116227 235807 117719 235808 116227 235808 117715 235808 117715 235809 116227 235809 116229 235809 117715 235810 116229 235810 117720 235810 117720 235811 116229 235811 116234 235811 117720 235812 116234 235812 116237 235812 116268 235813 117716 235813 116245 235813 116245 235814 117716 235814 117724 235814 116245 235815 117724 235815 116243 235815 116243 235816 117724 235816 117723 235816 116243 235817 117723 235817 117717 235817 117717 235818 117723 235818 117722 235818 117717 235819 117722 235819 117718 235819 117718 235820 117722 235820 116237 235820 117750 235821 117712 235821 117725 235821 117725 235822 117712 235822 117719 235822 117725 235823 117719 235823 117726 235823 117726 235824 117719 235824 117715 235824 117726 235825 117715 235825 117727 235825 117727 235826 117715 235826 117720 235826 117727 235827 117720 235827 117721 235827 117721 235828 117720 235828 117722 235828 117721 235829 117722 235829 117730 235829 117730 235830 117722 235830 117723 235830 117730 235831 117723 235831 117731 235831 117731 235832 117723 235832 117724 235832 117731 235833 117724 235833 117732 235833 117732 235834 117724 235834 117716 235834 117732 235835 117716 235835 117670 235835 117748 235836 117725 235836 117710 235836 117710 235837 117725 235837 117726 235837 117710 235838 117726 235838 117734 235838 117734 235839 117726 235839 117727 235839 117734 235840 117727 235840 117728 235840 117728 235841 117727 235841 117721 235841 117728 235842 117721 235842 117729 235842 117729 235843 117721 235843 117730 235843 117729 235844 117730 235844 117736 235844 117736 235845 117730 235845 117731 235845 117736 235846 117731 235846 117738 235846 117738 235847 117731 235847 117732 235847 117738 235848 117732 235848 117740 235848 117740 235849 117732 235849 117670 235849 117740 235850 117670 235850 117669 235850 117709 235851 117710 235851 117733 235851 117733 235852 117710 235852 117734 235852 117733 235853 117734 235853 116151 235853 116151 235854 117734 235854 117728 235854 116151 235855 117728 235855 116152 235855 116152 235856 117728 235856 117729 235856 116152 235857 117729 235857 117735 235857 117735 235858 117729 235858 117736 235858 117735 235859 117736 235859 117737 235859 117737 235860 117736 235860 117738 235860 117737 235861 117738 235861 117739 235861 117739 235862 117738 235862 117740 235862 117739 235863 117740 235863 117741 235863 117741 235864 117740 235864 117669 235864 117741 235865 117669 235865 116156 235865 116503 235866 116501 235866 117743 235866 117742 235867 117704 235867 117746 235867 117770 235868 116503 235868 117771 235868 117771 235869 116503 235869 117743 235869 117771 235870 117743 235870 117744 235870 117744 235871 117743 235871 117707 235871 117744 235872 117707 235872 117772 235872 117772 235873 117707 235873 117742 235873 117772 235874 117742 235874 117745 235874 117745 235875 117742 235875 117746 235875 117709 235876 117747 235876 117748 235876 117748 235877 117747 235877 117749 235877 117748 235878 117749 235878 117750 235878 117750 235879 117749 235879 117794 235879 117750 235880 117794 235880 117713 235880 117713 235881 117794 235881 117752 235881 117713 235882 117752 235882 117751 235882 117751 235883 117752 235883 116221 235883 117763 235884 117796 235884 117764 235884 117764 235885 117796 235885 117753 235885 117798 235886 117799 235886 117765 235886 117765 235887 117799 235887 117763 235887 117754 235888 117797 235888 117798 235888 117770 235889 117755 235889 117756 235889 117756 235890 117755 235890 117769 235890 117756 235891 117769 235891 116470 235891 116470 235892 117769 235892 117757 235892 116470 235893 117757 235893 117759 235893 117759 235894 117757 235894 117758 235894 117759 235895 117758 235895 117760 235895 117760 235896 117758 235896 117768 235896 117760 235897 117768 235897 116468 235897 116468 235898 117768 235898 117766 235898 116468 235899 117766 235899 117761 235899 117761 235900 117766 235900 117764 235900 117761 235901 117764 235901 117762 235901 117762 235902 117764 235902 117753 235902 117762 235903 117753 235903 117795 235903 117763 235904 117764 235904 117765 235904 117765 235905 117764 235905 117766 235905 117765 235906 117766 235906 117773 235906 117773 235907 117766 235907 117768 235907 117773 235908 117768 235908 117767 235908 117767 235909 117768 235909 117758 235909 117767 235910 117758 235910 117775 235910 117775 235911 117758 235911 117757 235911 117775 235912 117757 235912 117776 235912 117776 235913 117757 235913 117769 235913 117776 235914 117769 235914 117778 235914 117778 235915 117769 235915 117755 235915 117778 235916 117755 235916 117779 235916 117770 235917 117771 235917 117755 235917 117755 235918 117771 235918 117744 235918 117755 235919 117744 235919 117779 235919 117779 235920 117744 235920 117772 235920 117779 235921 117772 235921 117745 235921 117798 235922 117765 235922 117754 235922 117754 235923 117765 235923 117773 235923 117754 235924 117773 235924 113442 235924 113442 235925 117773 235925 117767 235925 113442 235926 117767 235926 117774 235926 117774 235927 117767 235927 117775 235927 117774 235928 117775 235928 113438 235928 113438 235929 117775 235929 117776 235929 113438 235930 117776 235930 113436 235930 113436 235931 117776 235931 117778 235931 113436 235932 117778 235932 117777 235932 117777 235933 117778 235933 117779 235933 117777 235934 117779 235934 117780 235934 117780 235935 117779 235935 117745 235935 117780 235936 117745 235936 117746 235936 116482 235937 117781 235937 117788 235937 116215 235938 116217 235938 117792 235938 116485 235939 117808 235939 117782 235939 117782 235940 117808 235940 117783 235940 117782 235941 117783 235941 117785 235941 117785 235942 117783 235942 117784 235942 117785 235943 117784 235943 117786 235943 117786 235944 117784 235944 117787 235944 117786 235945 117787 235945 116212 235945 116212 235946 117787 235946 116210 235946 117781 235947 116485 235947 117788 235947 117788 235948 116485 235948 117782 235948 117788 235949 117782 235949 117790 235949 117790 235950 117782 235950 117785 235950 117790 235951 117785 235951 117793 235951 117793 235952 117785 235952 117786 235952 117793 235953 117786 235953 116213 235953 116213 235954 117786 235954 116212 235954 116481 235955 116482 235955 117789 235955 117789 235956 116482 235956 117788 235956 117789 235957 117788 235957 117791 235957 117791 235958 117788 235958 117790 235958 117791 235959 117790 235959 117792 235959 117792 235960 117790 235960 117793 235960 117792 235961 117793 235961 116215 235961 116215 235962 117793 235962 116213 235962 117747 235963 116481 235963 117749 235963 117749 235964 116481 235964 117789 235964 117749 235965 117789 235965 117794 235965 117794 235966 117789 235966 117791 235966 117794 235967 117791 235967 117752 235967 117752 235968 117791 235968 117792 235968 117752 235969 117792 235969 116221 235969 116221 235970 117792 235970 116217 235970 116466 235971 117795 235971 117753 235971 117815 235972 116464 235972 116466 235972 116466 235973 117753 235973 117815 235973 117815 235974 117753 235974 117796 235974 117815 235975 117796 235975 117814 235975 117814 235976 117796 235976 117763 235976 117814 235977 117763 235977 117812 235977 117797 235978 116313 235978 117798 235978 117798 235979 116313 235979 117812 235979 117798 235980 117812 235980 117799 235980 117799 235981 117812 235981 117763 235981 117800 235982 116301 235982 117801 235982 117801 235983 116301 235983 117803 235983 117801 235984 117803 235984 117802 235984 117802 235985 117803 235985 117807 235985 117802 235986 117807 235986 117804 235986 117804 235987 117807 235987 117805 235987 117804 235988 117805 235988 116490 235988 116490 235989 117805 235989 117806 235989 116301 235990 116210 235990 117803 235990 117803 235991 116210 235991 117787 235991 117803 235992 117787 235992 117807 235992 117807 235993 117787 235993 117784 235993 117807 235994 117784 235994 117805 235994 117805 235995 117784 235995 117783 235995 117805 235996 117783 235996 117806 235996 117806 235997 117783 235997 117808 235997 117824 235998 117822 235998 117825 235998 117826 235999 117827 235999 117809 235999 117809 236000 117834 236000 117826 236000 117826 236001 117834 236001 117810 236001 117826 236002 117810 236002 117811 236002 116313 236003 117813 236003 117812 236003 117812 236004 117813 236004 117817 236004 117812 236005 117817 236005 117814 236005 117814 236006 117817 236006 117819 236006 117814 236007 117819 236007 117815 236007 117815 236008 117819 236008 117821 236008 117815 236009 117821 236009 116464 236009 116464 236010 117821 236010 117816 236010 117813 236011 116314 236011 117817 236011 117817 236012 116314 236012 117818 236012 117817 236013 117818 236013 117819 236013 117819 236014 117818 236014 117820 236014 117819 236015 117820 236015 117821 236015 117821 236016 117820 236016 117825 236016 117821 236017 117825 236017 117816 236017 117816 236018 117825 236018 117822 236018 117828 236019 117824 236019 117823 236019 117823 236020 117824 236020 117825 236020 117823 236021 117825 236021 117811 236021 117811 236022 117825 236022 117820 236022 117811 236023 117820 236023 117826 236023 117826 236024 117820 236024 117818 236024 117826 236025 117818 236025 117827 236025 117827 236026 117818 236026 116314 236026 117810 236027 117836 236027 117811 236027 117811 236028 117836 236028 117837 236028 117811 236029 117837 236029 117823 236029 117823 236030 117837 236030 117838 236030 117823 236031 117838 236031 117828 236031 117828 236032 117838 236032 116458 236032 117804 236033 116490 236033 117830 236033 117830 236034 116490 236034 116491 236034 117830 236035 116491 236035 116492 236035 117801 236036 117842 236036 117800 236036 117800 236037 117842 236037 117829 236037 117804 236038 117830 236038 117802 236038 117802 236039 117830 236039 117831 236039 117802 236040 117831 236040 117801 236040 117801 236041 117831 236041 117832 236041 117801 236042 117832 236042 117842 236042 117809 236043 117833 236043 117834 236043 117834 236044 117833 236044 117865 236044 117834 236045 117865 236045 117810 236045 117810 236046 117865 236046 117835 236046 117810 236047 117835 236047 117836 236047 117836 236048 117835 236048 117867 236048 117836 236049 117867 236049 117837 236049 117837 236050 117867 236050 117839 236050 117837 236051 117839 236051 117838 236051 117838 236052 117839 236052 117840 236052 117838 236053 117840 236053 116458 236053 116458 236054 117840 236054 117841 236054 117831 236055 117830 236055 117854 236055 117842 236056 117832 236056 117859 236056 117859 236057 117832 236057 117831 236057 117858 236058 117829 236058 117842 236058 117831 236059 117854 236059 117859 236059 117859 236060 117854 236060 117843 236060 117859 236061 117843 236061 117844 236061 117844 236062 117843 236062 117853 236062 117844 236063 117853 236063 117845 236063 117845 236064 117853 236064 117852 236064 117845 236065 117852 236065 117861 236065 117861 236066 117852 236066 117847 236066 117861 236067 117847 236067 117846 236067 117846 236068 117847 236068 117848 236068 117846 236069 117848 236069 117849 236069 117849 236070 117848 236070 117856 236070 117849 236071 117856 236071 117864 236071 116473 236072 116457 236072 117850 236072 117850 236073 117856 236073 116473 236073 116473 236074 117856 236074 117848 236074 116473 236075 117848 236075 116474 236075 116474 236076 117848 236076 117847 236076 116474 236077 117847 236077 117851 236077 117851 236078 117847 236078 117852 236078 117851 236079 117852 236079 116475 236079 116475 236080 117852 236080 117853 236080 116475 236081 117853 236081 116476 236081 116476 236082 117853 236082 117843 236082 116476 236083 117843 236083 116477 236083 116477 236084 117843 236084 117854 236084 116477 236085 117854 236085 116480 236085 116480 236086 117854 236086 117830 236086 116480 236087 117830 236087 116492 236087 117850 236088 117855 236088 117856 236088 117856 236089 117855 236089 117885 236089 117856 236090 117885 236090 117864 236090 117864 236091 117885 236091 117884 236091 117864 236092 117884 236092 117857 236092 117842 236093 117859 236093 117858 236093 117858 236094 117859 236094 117844 236094 117858 236095 117844 236095 117860 236095 117860 236096 117844 236096 117845 236096 117860 236097 117845 236097 113504 236097 113504 236098 117845 236098 117861 236098 113504 236099 117861 236099 117862 236099 117862 236100 117861 236100 117846 236100 117862 236101 117846 236101 117863 236101 117863 236102 117846 236102 117849 236102 117863 236103 117849 236103 113502 236103 113502 236104 117849 236104 117864 236104 113502 236105 117864 236105 113501 236105 113501 236106 117864 236106 117857 236106 113501 236107 117857 236107 113506 236107 117872 236108 116452 236108 117871 236108 117866 236109 117868 236109 117867 236109 117833 236110 116318 236110 117865 236110 117865 236111 116318 236111 117866 236111 117865 236112 117866 236112 117835 236112 117835 236113 117866 236113 117867 236113 116452 236114 117841 236114 117871 236114 117871 236115 117841 236115 117840 236115 117871 236116 117840 236116 117868 236116 117868 236117 117840 236117 117839 236117 117868 236118 117839 236118 117867 236118 116318 236119 116317 236119 117866 236119 117866 236120 116317 236120 117873 236120 117866 236121 117873 236121 117868 236121 117868 236122 117873 236122 117869 236122 117868 236123 117869 236123 117871 236123 117871 236124 117869 236124 117870 236124 117871 236125 117870 236125 117872 236125 117872 236126 117870 236126 116454 236126 116317 236127 117875 236127 117873 236127 117873 236128 117875 236128 117876 236128 117873 236129 117876 236129 117869 236129 117869 236130 117876 236130 117878 236130 117869 236131 117878 236131 117870 236131 117870 236132 117878 236132 117874 236132 117870 236133 117874 236133 116454 236133 116454 236134 117874 236134 117879 236134 117875 236135 117877 236135 117876 236135 117876 236136 117877 236136 117882 236136 117876 236137 117882 236137 117878 236137 117878 236138 117882 236138 117883 236138 117878 236139 117883 236139 117874 236139 117874 236140 117883 236140 117880 236140 117874 236141 117880 236141 117879 236141 117879 236142 117880 236142 117881 236142 117882 236143 117877 236143 113506 236143 117850 236144 116457 236144 117880 236144 117880 236145 116457 236145 116456 236145 117880 236146 116456 236146 117881 236146 113506 236147 117857 236147 117882 236147 117882 236148 117857 236148 117884 236148 117882 236149 117884 236149 117883 236149 117883 236150 117884 236150 117885 236150 117883 236151 117885 236151 117880 236151 117880 236152 117885 236152 117855 236152 117880 236153 117855 236153 117850 236153 116359 236154 117904 236154 117886 236154 117886 236155 117904 236155 117887 236155 117897 236156 117888 236156 117889 236156 117889 236157 117888 236157 115340 236157 117889 236158 115340 236158 117899 236158 117899 236159 115340 236159 117890 236159 117899 236160 117890 236160 117900 236160 117900 236161 117890 236161 115351 236161 117900 236162 115351 236162 117891 236162 117891 236163 115351 236163 115343 236163 117891 236164 115343 236164 117892 236164 117892 236165 115343 236165 117893 236165 117892 236166 117893 236166 117903 236166 117903 236167 117893 236167 117895 236167 117903 236168 117895 236168 117894 236168 117894 236169 117895 236169 117896 236169 117894 236170 117896 236170 117909 236170 117909 236171 117896 236171 115347 236171 116396 236172 117897 236172 117898 236172 117898 236173 117897 236173 117889 236173 117898 236174 117889 236174 116379 236174 116379 236175 117889 236175 117899 236175 116379 236176 117899 236176 116376 236176 116376 236177 117899 236177 117900 236177 116376 236178 117900 236178 117901 236178 117901 236179 117900 236179 117891 236179 117901 236180 117891 236180 117902 236180 117902 236181 117891 236181 117892 236181 117902 236182 117892 236182 116373 236182 116373 236183 117892 236183 117903 236183 116373 236184 117903 236184 117904 236184 117904 236185 117903 236185 117894 236185 117904 236186 117894 236186 117887 236186 117887 236187 117894 236187 117909 236187 117887 236188 117909 236188 117886 236188 116395 236189 116394 236189 117905 236189 117905 236190 116394 236190 117906 236190 117905 236191 117906 236191 117907 236191 117907 236192 117906 236192 117915 236192 116396 236193 116395 236193 117897 236193 117897 236194 116395 236194 117905 236194 117897 236195 117905 236195 117888 236195 117888 236196 117905 236196 117907 236196 117908 236197 116359 236197 117886 236197 117908 236198 117886 236198 117939 236198 117939 236199 117886 236199 117909 236199 117939 236200 117909 236200 117936 236200 117936 236201 117909 236201 115347 236201 117936 236202 115347 236202 117910 236202 115380 236203 115357 236203 117911 236203 117914 236204 116402 236204 117912 236204 117906 236205 116394 236205 116393 236205 117928 236206 115380 236206 117927 236206 117927 236207 115380 236207 117911 236207 117927 236208 117911 236208 117920 236208 117920 236209 117911 236209 117913 236209 117920 236210 117913 236210 117912 236210 117912 236211 117913 236211 117924 236211 117912 236212 117924 236212 117914 236212 117914 236213 117924 236213 116401 236213 117915 236214 117906 236214 115359 236214 115359 236215 117906 236215 117916 236215 115359 236216 117916 236216 117917 236216 117917 236217 117916 236217 117918 236217 117917 236218 117918 236218 115356 236218 115356 236219 117918 236219 117923 236219 116402 236220 116403 236220 117912 236220 117912 236221 116403 236221 117919 236221 117912 236222 117919 236222 117920 236222 117920 236223 117919 236223 117921 236223 117920 236224 117921 236224 117927 236224 117906 236225 116393 236225 117916 236225 117916 236226 116393 236226 117922 236226 117916 236227 117922 236227 117925 236227 115357 236228 117923 236228 117911 236228 117911 236229 117923 236229 117918 236229 117911 236230 117918 236230 117913 236230 117913 236231 117918 236231 117916 236231 117913 236232 117916 236232 117924 236232 117924 236233 117916 236233 117925 236233 117924 236234 117925 236234 116401 236234 116403 236235 117926 236235 117919 236235 117919 236236 117926 236236 117932 236236 117919 236237 117932 236237 117921 236237 117921 236238 117932 236238 117933 236238 117921 236239 117933 236239 117927 236239 117927 236240 117933 236240 117934 236240 117927 236241 117934 236241 117928 236241 117928 236242 117934 236242 117929 236242 117926 236243 117930 236243 117932 236243 117932 236244 117930 236244 117931 236244 117932 236245 117931 236245 117933 236245 117933 236246 117931 236246 117941 236246 117933 236247 117941 236247 117934 236247 117934 236248 117941 236248 117942 236248 117934 236249 117942 236249 117929 236249 117929 236250 117942 236250 117935 236250 117936 236251 117910 236251 115330 236251 116371 236252 117908 236252 117938 236252 117938 236253 117908 236253 117939 236253 117936 236254 115330 236254 117937 236254 117937 236255 115330 236255 115308 236255 117937 236256 115308 236256 117944 236256 117946 236257 116371 236257 117944 236257 117944 236258 116371 236258 117938 236258 117944 236259 117938 236259 117937 236259 117937 236260 117938 236260 117939 236260 117937 236261 117939 236261 117936 236261 117930 236262 116356 236262 117931 236262 117931 236263 116356 236263 117940 236263 117931 236264 117940 236264 117941 236264 117941 236265 117940 236265 117953 236265 117941 236266 117953 236266 117942 236266 117942 236267 117953 236267 117943 236267 117942 236268 117943 236268 117935 236268 117935 236269 117943 236269 115415 236269 117944 236270 115308 236270 117945 236270 117946 236271 117944 236271 117950 236271 117944 236272 117945 236272 117950 236272 117950 236273 117945 236273 115306 236273 117950 236274 115306 236274 117951 236274 117951 236275 115306 236275 117947 236275 117951 236276 117947 236276 117948 236276 117948 236277 117947 236277 115304 236277 117948 236278 115304 236278 117952 236278 117946 236279 117950 236279 117949 236279 117949 236280 117950 236280 117951 236280 117949 236281 117951 236281 116365 236281 116365 236282 117951 236282 117948 236282 116365 236283 117948 236283 116367 236283 116367 236284 117948 236284 117952 236284 116367 236285 117952 236285 116361 236285 115408 236286 115415 236286 117943 236286 116356 236287 116381 236287 117940 236287 117940 236288 116381 236288 117964 236288 117940 236289 117964 236289 117953 236289 117953 236290 117964 236290 117966 236290 117953 236291 117966 236291 117943 236291 117943 236292 117966 236292 117954 236292 117943 236293 117954 236293 115408 236293 115408 236294 117954 236294 115409 236294 117959 236295 117955 236295 117956 236295 117952 236296 115304 236296 117957 236296 117956 236297 116391 236297 117959 236297 117959 236298 116391 236298 116361 236298 117959 236299 116361 236299 117952 236299 117952 236300 117957 236300 117959 236300 117959 236301 117957 236301 117958 236301 117959 236302 117958 236302 117955 236302 117965 236303 116382 236303 117963 236303 117970 236304 115407 236304 117960 236304 117960 236305 117967 236305 117970 236305 117970 236306 117967 236306 117961 236306 117970 236307 117961 236307 117972 236307 117972 236308 117961 236308 117963 236308 117972 236309 117963 236309 117962 236309 117962 236310 117963 236310 116382 236310 117962 236311 116382 236311 116384 236311 116381 236312 117965 236312 117964 236312 117964 236313 117965 236313 117963 236313 117964 236314 117963 236314 117966 236314 117966 236315 117963 236315 117961 236315 117966 236316 117961 236316 117954 236316 117954 236317 117961 236317 117967 236317 117954 236318 117967 236318 115409 236318 115409 236319 117967 236319 117960 236319 116388 236320 116389 236320 117969 236320 116385 236321 117968 236321 117975 236321 117975 236322 117968 236322 116388 236322 117962 236323 116384 236323 116385 236323 116385 236324 117975 236324 117962 236324 117962 236325 117975 236325 117973 236325 117962 236326 117973 236326 117972 236326 115407 236327 117970 236327 115739 236327 115739 236328 117970 236328 117971 236328 115739 236329 117971 236329 117977 236329 117977 236330 117971 236330 117976 236330 116389 236331 117956 236331 117969 236331 117969 236332 117956 236332 117955 236332 117969 236333 117955 236333 117978 236333 117978 236334 117955 236334 117958 236334 117970 236335 117972 236335 117971 236335 117971 236336 117972 236336 117973 236336 117971 236337 117973 236337 117976 236337 117976 236338 117973 236338 117975 236338 117976 236339 117975 236339 117974 236339 117974 236340 117975 236340 116388 236340 117974 236341 116388 236341 117976 236341 117976 236342 116388 236342 117969 236342 117976 236343 117969 236343 117977 236343 117977 236344 117969 236344 117978 236344 117979 236345 117991 236345 117980 236345 117985 236346 117997 236346 115332 236346 117979 236347 117980 236347 117981 236347 115332 236348 117997 236348 117982 236348 117982 236349 117997 236349 117980 236349 117982 236350 117980 236350 117983 236350 117983 236351 117980 236351 117991 236351 117983 236352 117991 236352 117984 236352 115332 236353 115331 236353 117985 236353 117985 236354 115331 236354 115342 236354 117985 236355 115342 236355 117994 236355 117994 236356 115342 236356 117986 236356 117994 236357 117986 236357 117993 236357 117993 236358 117986 236358 117987 236358 117993 236359 117987 236359 117988 236359 117988 236360 117987 236360 115341 236360 117988 236361 115341 236361 117989 236361 117989 236362 115341 236362 115339 236362 117981 236363 116415 236363 117979 236363 117979 236364 116415 236364 117990 236364 117979 236365 117990 236365 117991 236365 117991 236366 117990 236366 118001 236366 117991 236367 118001 236367 117984 236367 117989 236368 116406 236368 117988 236368 117988 236369 116406 236369 117992 236369 117988 236370 117992 236370 117993 236370 117993 236371 117992 236371 116408 236371 117993 236372 116408 236372 117994 236372 117994 236373 116408 236373 117995 236373 117994 236374 117995 236374 117985 236374 117985 236375 117995 236375 117996 236375 117985 236376 117996 236376 117997 236376 117997 236377 117996 236377 117998 236377 117997 236378 117998 236378 117980 236378 117980 236379 117998 236379 116413 236379 117980 236380 116413 236380 117981 236380 116415 236381 117999 236381 117990 236381 117990 236382 117999 236382 118000 236382 117990 236383 118000 236383 118001 236383 118000 236384 118022 236384 118001 236384 118001 236385 118022 236385 115335 236385 118001 236386 115335 236386 117984 236386 117989 236387 115339 236387 115338 236387 116449 236388 116406 236388 118003 236388 118003 236389 116406 236389 117989 236389 117989 236390 115338 236390 118003 236390 118003 236391 115338 236391 115337 236391 118003 236392 115337 236392 118013 236392 116449 236393 118003 236393 118002 236393 118002 236394 118003 236394 118013 236394 118002 236395 118013 236395 116447 236395 115361 236396 118004 236396 118012 236396 118006 236397 118005 236397 118024 236397 118012 236398 118015 236398 118016 236398 118004 236399 115372 236399 118012 236399 118012 236400 115372 236400 118027 236400 118012 236401 118027 236401 118015 236401 118015 236402 118027 236402 118014 236402 118010 236403 115360 236403 118011 236403 118024 236404 116441 236404 118006 236404 118006 236405 116441 236405 116443 236405 118006 236406 116443 236406 118017 236406 118017 236407 116443 236407 118007 236407 118017 236408 118007 236408 118018 236408 118013 236409 115337 236409 115358 236409 115358 236410 118009 236410 118008 236410 118008 236411 118009 236411 118010 236411 118008 236412 118010 236412 118016 236412 118016 236413 118010 236413 118011 236413 118016 236414 118011 236414 118012 236414 118012 236415 118011 236415 115360 236415 118012 236416 115360 236416 115361 236416 115358 236417 118008 236417 118013 236417 118013 236418 118008 236418 118019 236418 118013 236419 118019 236419 116447 236419 118014 236420 118005 236420 118015 236420 118015 236421 118005 236421 118006 236421 118015 236422 118006 236422 118016 236422 118016 236423 118006 236423 118017 236423 118016 236424 118017 236424 118008 236424 118008 236425 118017 236425 118018 236425 118008 236426 118018 236426 118019 236426 118020 236427 118022 236427 118000 236427 118021 236428 118040 236428 118039 236428 115335 236429 118022 236429 115336 236429 115336 236430 118022 236430 118020 236430 115336 236431 118020 236431 116065 236431 117999 236432 118021 236432 118000 236432 118000 236433 118021 236433 118039 236433 118000 236434 118039 236434 118020 236434 118020 236435 118039 236435 118038 236435 118020 236436 118038 236436 116065 236436 118023 236437 118024 236437 118041 236437 118041 236438 118024 236438 118005 236438 118041 236439 118005 236439 118025 236439 118025 236440 118005 236440 118014 236440 118025 236441 118014 236441 118042 236441 118042 236442 118014 236442 118027 236442 118042 236443 118027 236443 118026 236443 118026 236444 118027 236444 115372 236444 118047 236445 118044 236445 118030 236445 116433 236446 118028 236446 118029 236446 118029 236447 118028 236447 118047 236447 118047 236448 118030 236448 118029 236448 118029 236449 118030 236449 118031 236449 118029 236450 118031 236450 118035 236450 118035 236451 118031 236451 118036 236451 118035 236452 118036 236452 118032 236452 118037 236453 118033 236453 118032 236453 118032 236454 118033 236454 118034 236454 118032 236455 118034 236455 118035 236455 118035 236456 118034 236456 116436 236456 118035 236457 116436 236457 118029 236457 118029 236458 116436 236458 116434 236458 118029 236459 116434 236459 116433 236459 118036 236460 116065 236460 118032 236460 118032 236461 116065 236461 118038 236461 118032 236462 118038 236462 118037 236462 118037 236463 118038 236463 118039 236463 118037 236464 118039 236464 118040 236464 116405 236465 118023 236465 118050 236465 118050 236466 118023 236466 118041 236466 118050 236467 118041 236467 118051 236467 118051 236468 118041 236468 118025 236468 118051 236469 118025 236469 118054 236469 118054 236470 118025 236470 118042 236470 118054 236471 118042 236471 118055 236471 118055 236472 118042 236472 118026 236472 116418 236473 118064 236473 118043 236473 116418 236474 118043 236474 116417 236474 118047 236475 118045 236475 118044 236475 118044 236476 118045 236476 118046 236476 118058 236477 118046 236477 118043 236477 118043 236478 118046 236478 118045 236478 118043 236479 118045 236479 116417 236479 116417 236480 118045 236480 118047 236480 116417 236481 118047 236481 118028 236481 116430 236482 116405 236482 118050 236482 118048 236483 118049 236483 116430 236483 116430 236484 118050 236484 118048 236484 118048 236485 118050 236485 118052 236485 118048 236486 118052 236486 118069 236486 118069 236487 118052 236487 118053 236487 118069 236488 118053 236488 118065 236488 118065 236489 118053 236489 118056 236489 118065 236490 118056 236490 115362 236490 118050 236491 118051 236491 118052 236491 118052 236492 118051 236492 118054 236492 118052 236493 118054 236493 118053 236493 118053 236494 118054 236494 118055 236494 118053 236495 118055 236495 118056 236495 118067 236496 118069 236496 118066 236496 118066 236497 118069 236497 118065 236497 118062 236498 118060 236498 118057 236498 118058 236499 118043 236499 118070 236499 118057 236500 118060 236500 118070 236500 118058 236501 118070 236501 118059 236501 118059 236502 118070 236502 118060 236502 118059 236503 118060 236503 118061 236503 118061 236504 118060 236504 118062 236504 118061 236505 118062 236505 118063 236505 118043 236506 118064 236506 118071 236506 118057 236507 116422 236507 118068 236507 115362 236508 118063 236508 118065 236508 118065 236509 118063 236509 118062 236509 118065 236510 118062 236510 118066 236510 118066 236511 118062 236511 118057 236511 118066 236512 118057 236512 118067 236512 118067 236513 118057 236513 118068 236513 118067 236514 118068 236514 118069 236514 118069 236515 118068 236515 116427 236515 118069 236516 116427 236516 118048 236516 118048 236517 116427 236517 118049 236517 118043 236518 118071 236518 118070 236518 118070 236519 118071 236519 118072 236519 118070 236520 118072 236520 118057 236520 118057 236521 118072 236521 116424 236521 118057 236522 116424 236522 116422 236522 115454 236523 118091 236523 118092 236523 118074 236524 115452 236524 115454 236524 118075 236525 118093 236525 118073 236525 115454 236526 118092 236526 118074 236526 118074 236527 118092 236527 118075 236527 118074 236528 118075 236528 118080 236528 118080 236529 118075 236529 118073 236529 118080 236530 118073 236530 118083 236530 118081 236531 118103 236531 118076 236531 118078 236532 118079 236532 115412 236532 115412 236533 118079 236533 118076 236533 115412 236534 118076 236534 115442 236534 115442 236535 118076 236535 118103 236535 115442 236536 118103 236536 118077 236536 118078 236537 115452 236537 118079 236537 118079 236538 115452 236538 118074 236538 118079 236539 118074 236539 118080 236539 118081 236540 118076 236540 116327 236540 116327 236541 118076 236541 118079 236541 116327 236542 118079 236542 118082 236542 118082 236543 118079 236543 118080 236543 118082 236544 118080 236544 118083 236544 118084 236545 115564 236545 118085 236545 118085 236546 115564 236546 118100 236546 118085 236547 118086 236547 118084 236547 118084 236548 118086 236548 118098 236548 118084 236549 118098 236549 118087 236549 118087 236550 118098 236550 118096 236550 118087 236551 118096 236551 118088 236551 118088 236552 118096 236552 118089 236552 118088 236553 118089 236553 115466 236553 115466 236554 118089 236554 118090 236554 115466 236555 118090 236555 115664 236555 118091 236556 115664 236556 118092 236556 118092 236557 115664 236557 118090 236557 118092 236558 118090 236558 118075 236558 118075 236559 118090 236559 118093 236559 115564 236560 115494 236560 118100 236560 118100 236561 115494 236561 118094 236561 118100 236562 118094 236562 118113 236562 118093 236563 118090 236563 116353 236563 116353 236564 118090 236564 118089 236564 116353 236565 118089 236565 118095 236565 118095 236566 118089 236566 118096 236566 118095 236567 118096 236567 116352 236567 116352 236568 118096 236568 118098 236568 116352 236569 118098 236569 118097 236569 118097 236570 118098 236570 118086 236570 118097 236571 118086 236571 116351 236571 116351 236572 118086 236572 118085 236572 116351 236573 118085 236573 118099 236573 118099 236574 118085 236574 118100 236574 118099 236575 118100 236575 118101 236575 118101 236576 118100 236576 118113 236576 118101 236577 118113 236577 118102 236577 118103 236578 118081 236578 118107 236578 118109 236579 118077 236579 118104 236579 118104 236580 118077 236580 118103 236580 118105 236581 118106 236581 118108 236581 118103 236582 118107 236582 118104 236582 118104 236583 118107 236583 118105 236583 118104 236584 118105 236584 118111 236584 118111 236585 118105 236585 118108 236585 118111 236586 118108 236586 118112 236586 118109 236587 118104 236587 118110 236587 118110 236588 118104 236588 118111 236588 118110 236589 118111 236589 115398 236589 115398 236590 118111 236590 118112 236590 115398 236591 118112 236591 115364 236591 118113 236592 118094 236592 118116 236592 118124 236593 118102 236593 118113 236593 118114 236594 115498 236594 118144 236594 118144 236595 118121 236595 118114 236595 118114 236596 118121 236596 118119 236596 118114 236597 118119 236597 118115 236597 118130 236598 118131 236598 115495 236598 118116 236599 118118 236599 118128 236599 118094 236600 115494 236600 118116 236600 118116 236601 115494 236601 118117 236601 118116 236602 118117 236602 118118 236602 115495 236603 118115 236603 118130 236603 118130 236604 118115 236604 118119 236604 118130 236605 118119 236605 118120 236605 118120 236606 118119 236606 118121 236606 118120 236607 118121 236607 118122 236607 118122 236608 118121 236608 118144 236608 118132 236609 118123 236609 118124 236609 118125 236610 118140 236610 118129 236610 118129 236611 118140 236611 116343 236611 118129 236612 116343 236612 118126 236612 116343 236613 118127 236613 118126 236613 118126 236614 118127 236614 116348 236614 118126 236615 116348 236615 118133 236615 118133 236616 116348 236616 116347 236616 118133 236617 116347 236617 116344 236617 118124 236618 118113 236618 118132 236618 118132 236619 118113 236619 118116 236619 118132 236620 118116 236620 118131 236620 118131 236621 118116 236621 118128 236621 118131 236622 118128 236622 115495 236622 118122 236623 118125 236623 118120 236623 118120 236624 118125 236624 118129 236624 118120 236625 118129 236625 118130 236625 118130 236626 118129 236626 118126 236626 118130 236627 118126 236627 118131 236627 118131 236628 118126 236628 118133 236628 118131 236629 118133 236629 118132 236629 118132 236630 118133 236630 116344 236630 118132 236631 116344 236631 118123 236631 118136 236632 118134 236632 118137 236632 118137 236633 118135 236633 118138 236633 118106 236634 118136 236634 118108 236634 118108 236635 118136 236635 118137 236635 118108 236636 118137 236636 118112 236636 118112 236637 118137 236637 118138 236637 118112 236638 118138 236638 115364 236638 118139 236639 118140 236639 118125 236639 118147 236640 118146 236640 118172 236640 118172 236641 118146 236641 118145 236641 118172 236642 118145 236642 118171 236642 118171 236643 118145 236643 118141 236643 118171 236644 118141 236644 118142 236644 118142 236645 118141 236645 118143 236645 115498 236646 118143 236646 118144 236646 118144 236647 118143 236647 118141 236647 118144 236648 118141 236648 118122 236648 118122 236649 118141 236649 118145 236649 118122 236650 118145 236650 118125 236650 118125 236651 118145 236651 118146 236651 118125 236652 118146 236652 118139 236652 118139 236653 118146 236653 118147 236653 118139 236654 118147 236654 118148 236654 118135 236655 118137 236655 118164 236655 118135 236656 118164 236656 114940 236656 114940 236657 118164 236657 118149 236657 114940 236658 118149 236658 114936 236658 114936 236659 118149 236659 118150 236659 114936 236660 118150 236660 114937 236660 118150 236661 118162 236661 114937 236661 114937 236662 118162 236662 118152 236662 114937 236663 118152 236663 118151 236663 118151 236664 118152 236664 118153 236664 118151 236665 118153 236665 114939 236665 114939 236666 118153 236666 118154 236666 114939 236667 118154 236667 118156 236667 118155 236668 118156 236668 118174 236668 118174 236669 118156 236669 118154 236669 118174 236670 118154 236670 118157 236670 118157 236671 118154 236671 118158 236671 118158 236672 118154 236672 118159 236672 118159 236673 118154 236673 118153 236673 118159 236674 118153 236674 118160 236674 118160 236675 118153 236675 118152 236675 118160 236676 118152 236676 118161 236676 118161 236677 118152 236677 118162 236677 118161 236678 118162 236678 116332 236678 116332 236679 118162 236679 118150 236679 116332 236680 118150 236680 116330 236680 116330 236681 118150 236681 118149 236681 116330 236682 118149 236682 118163 236682 118163 236683 118149 236683 118164 236683 118163 236684 118164 236684 118165 236684 118165 236685 118164 236685 118137 236685 118165 236686 118137 236686 118134 236686 118166 236687 118199 236687 118167 236687 118167 236688 118199 236688 118198 236688 118167 236689 118198 236689 118168 236689 118168 236690 118198 236690 118169 236690 118168 236691 118169 236691 118173 236691 118173 236692 118169 236692 118194 236692 118173 236693 118194 236693 116321 236693 116321 236694 118194 236694 118170 236694 118142 236695 118166 236695 118171 236695 118171 236696 118166 236696 118167 236696 118171 236697 118167 236697 118172 236697 118172 236698 118167 236698 118168 236698 118172 236699 118168 236699 118147 236699 118147 236700 118168 236700 118173 236700 118147 236701 118173 236701 118148 236701 118148 236702 118173 236702 116321 236702 118178 236703 114934 236703 118176 236703 118155 236704 118174 236704 114933 236704 114933 236705 118174 236705 118191 236705 114933 236706 118191 236706 118175 236706 118175 236707 118191 236707 118176 236707 114934 236708 118178 236708 114935 236708 114935 236709 118178 236709 118179 236709 114935 236710 118179 236710 118177 236710 118177 236711 118179 236711 118181 236711 118177 236712 118181 236712 118187 236712 118176 236713 118191 236713 118178 236713 118178 236714 118191 236714 118180 236714 118178 236715 118180 236715 118179 236715 118179 236716 118180 236716 118189 236716 118179 236717 118189 236717 118181 236717 118181 236718 118189 236718 118188 236718 118181 236719 118188 236719 118187 236719 116339 236720 118182 236720 118190 236720 118183 236721 116340 236721 118184 236721 118184 236722 116340 236722 118207 236722 118184 236723 118207 236723 118208 236723 116339 236724 118183 236724 118182 236724 118182 236725 118183 236725 118184 236725 118182 236726 118184 236726 118185 236726 118185 236727 118184 236727 118208 236727 118185 236728 118208 236728 118209 236728 118157 236729 118158 236729 118186 236729 118157 236730 118186 236730 118192 236730 118186 236731 116336 236731 118192 236731 118192 236732 116336 236732 116337 236732 118192 236733 116337 236733 118190 236733 118190 236734 116337 236734 116338 236734 118190 236735 116338 236735 116339 236735 115969 236736 118187 236736 118209 236736 118209 236737 118187 236737 118188 236737 118209 236738 118188 236738 118185 236738 118185 236739 118188 236739 118189 236739 118185 236740 118189 236740 118182 236740 118182 236741 118189 236741 118180 236741 118182 236742 118180 236742 118190 236742 118190 236743 118180 236743 118191 236743 118190 236744 118191 236744 118192 236744 118192 236745 118191 236745 118174 236745 118192 236746 118174 236746 118157 236746 118193 236747 118170 236747 118195 236747 118195 236748 118170 236748 118194 236748 118195 236749 118194 236749 118200 236749 118200 236750 118194 236750 118169 236750 118200 236751 118169 236751 118196 236751 118196 236752 118169 236752 118198 236752 118196 236753 118198 236753 118197 236753 118197 236754 118198 236754 118199 236754 116324 236755 118193 236755 118203 236755 118203 236756 118193 236756 118195 236756 118203 236757 118195 236757 118205 236757 118205 236758 118195 236758 118200 236758 118205 236759 118200 236759 118206 236759 118206 236760 118200 236760 118196 236760 118206 236761 118196 236761 115967 236761 115967 236762 118196 236762 118197 236762 118201 236763 115969 236763 118209 236763 116341 236764 116324 236764 118202 236764 118202 236765 116324 236765 118203 236765 118202 236766 118203 236766 118204 236766 118204 236767 118203 236767 118205 236767 118204 236768 118205 236768 118210 236768 118210 236769 118205 236769 118206 236769 116340 236770 116341 236770 118207 236770 118207 236771 116341 236771 118202 236771 118207 236772 118202 236772 118208 236772 118208 236773 118202 236773 118204 236773 118208 236774 118204 236774 118209 236774 118209 236775 118204 236775 118210 236775 118209 236776 118210 236776 118201 236776 118201 236777 118210 236777 118206 236777 118201 236778 118206 236778 115967 236778 118211 236779 118216 236779 118212 236779 118215 236780 118217 236780 118211 236780 118236 236781 118213 236781 118237 236781 118261 236782 118229 236782 118228 236782 118239 236783 118225 236783 118214 236783 118214 236784 118225 236784 118227 236784 118215 236785 118211 236785 116331 236785 118216 236786 118211 236786 118286 236786 118286 236787 118211 236787 118217 236787 118286 236788 118217 236788 118218 236788 118213 236789 118219 236789 118237 236789 118237 236790 118219 236790 118240 236790 118237 236791 118240 236791 118220 236791 118220 236792 118240 236792 118222 236792 118220 236793 118222 236793 118221 236793 118221 236794 118222 236794 118223 236794 118221 236795 118223 236795 118239 236795 118239 236796 118223 236796 118224 236796 118239 236797 118224 236797 118225 236797 118225 236798 118224 236798 118226 236798 118225 236799 118226 236799 118227 236799 118227 236800 118226 236800 118244 236800 118227 236801 118244 236801 116333 236801 116333 236802 118244 236802 116334 236802 118250 236803 118249 236803 118233 236803 118228 236804 118229 236804 118241 236804 118241 236805 118229 236805 118230 236805 118241 236806 118230 236806 118231 236806 118231 236807 118230 236807 118270 236807 118231 236808 118270 236808 118242 236808 118242 236809 118270 236809 118269 236809 118242 236810 118269 236810 118243 236810 118243 236811 118269 236811 118250 236811 118243 236812 118250 236812 118232 236812 118232 236813 118250 236813 118233 236813 118232 236814 118233 236814 118245 236814 118234 236815 118235 236815 118228 236815 118228 236816 118235 236816 114626 236816 118228 236817 114626 236817 118261 236817 118281 236818 118236 236818 118284 236818 118284 236819 118236 236819 118237 236819 118284 236820 118237 236820 118238 236820 118238 236821 118237 236821 118220 236821 118238 236822 118220 236822 118285 236822 118285 236823 118220 236823 118221 236823 118285 236824 118221 236824 118212 236824 118212 236825 118221 236825 118239 236825 118212 236826 118239 236826 118211 236826 118211 236827 118239 236827 118214 236827 118211 236828 118214 236828 116331 236828 116331 236829 118214 236829 118227 236829 118219 236830 118234 236830 118240 236830 118240 236831 118234 236831 118228 236831 118240 236832 118228 236832 118222 236832 118222 236833 118228 236833 118241 236833 118222 236834 118241 236834 118223 236834 118223 236835 118241 236835 118231 236835 118223 236836 118231 236836 118224 236836 118224 236837 118231 236837 118242 236837 118224 236838 118242 236838 118226 236838 118226 236839 118242 236839 118243 236839 118226 236840 118243 236840 118244 236840 118244 236841 118243 236841 118232 236841 118244 236842 118232 236842 116334 236842 116334 236843 118232 236843 118245 236843 118274 236844 118246 236844 118276 236844 114630 236845 118247 236845 118260 236845 118248 236846 114628 236846 118280 236846 118266 236847 114713 236847 118258 236847 118267 236848 116335 236848 118268 236848 118268 236849 116335 236849 118249 236849 118268 236850 118249 236850 118250 236850 118271 236851 118251 236851 118272 236851 118272 236852 118251 236852 118252 236852 118272 236853 118252 236853 118253 236853 118253 236854 118252 236854 118254 236854 118253 236855 118254 236855 118274 236855 118304 236856 118273 236856 118255 236856 118255 236857 118273 236857 118262 236857 118255 236858 118262 236858 118256 236858 118256 236859 118262 236859 118264 236859 118256 236860 118264 236860 118301 236860 118301 236861 118264 236861 118257 236861 118301 236862 118257 236862 118300 236862 118300 236863 118257 236863 118258 236863 118300 236864 118258 236864 118298 236864 118259 236865 114539 236865 118297 236865 118298 236866 118258 236866 118297 236866 118297 236867 118258 236867 114713 236867 118297 236868 114713 236868 118259 236868 114630 236869 118260 236869 118261 236869 118273 236870 118263 236870 118262 236870 118262 236871 118263 236871 118275 236871 118262 236872 118275 236872 118264 236872 118264 236873 118275 236873 118265 236873 118264 236874 118265 236874 118257 236874 118257 236875 118265 236875 118278 236875 118257 236876 118278 236876 118258 236876 118258 236877 118278 236877 118280 236877 118258 236878 118280 236878 118266 236878 118266 236879 118280 236879 114628 236879 118254 236880 118267 236880 118274 236880 118274 236881 118267 236881 118268 236881 118274 236882 118268 236882 118246 236882 118246 236883 118268 236883 118250 236883 118246 236884 118250 236884 118276 236884 118276 236885 118250 236885 118269 236885 118276 236886 118269 236886 118277 236886 118277 236887 118269 236887 118270 236887 118277 236888 118270 236888 118279 236888 118279 236889 118270 236889 118230 236889 118279 236890 118230 236890 118260 236890 118260 236891 118230 236891 118229 236891 118260 236892 118229 236892 118261 236892 118303 236893 118271 236893 118304 236893 118304 236894 118271 236894 118272 236894 118304 236895 118272 236895 118273 236895 118273 236896 118272 236896 118253 236896 118273 236897 118253 236897 118263 236897 118263 236898 118253 236898 118274 236898 118263 236899 118274 236899 118275 236899 118275 236900 118274 236900 118276 236900 118275 236901 118276 236901 118265 236901 118265 236902 118276 236902 118277 236902 118265 236903 118277 236903 118278 236903 118278 236904 118277 236904 118279 236904 118278 236905 118279 236905 118280 236905 118280 236906 118279 236906 118260 236906 118280 236907 118260 236907 118248 236907 118248 236908 118260 236908 118247 236908 114627 236909 118281 236909 118284 236909 114627 236910 118284 236910 118283 236910 118282 236911 115826 236911 118283 236911 118283 236912 118284 236912 118282 236912 118282 236913 118284 236913 118238 236913 118282 236914 118238 236914 118290 236914 118290 236915 118238 236915 118285 236915 118290 236916 118285 236916 118291 236916 118291 236917 118285 236917 118212 236917 118291 236918 118212 236918 118292 236918 118292 236919 118212 236919 118216 236919 118292 236920 118216 236920 118293 236920 118293 236921 118216 236921 118286 236921 118293 236922 118286 236922 118287 236922 118287 236923 118286 236923 118218 236923 118287 236924 118218 236924 118288 236924 115824 236925 115826 236925 118327 236925 118327 236926 115826 236926 118282 236926 118327 236927 118282 236927 118289 236927 118289 236928 118282 236928 118290 236928 118289 236929 118290 236929 118329 236929 118329 236930 118290 236930 118291 236930 118329 236931 118291 236931 118331 236931 118331 236932 118291 236932 118292 236932 118331 236933 118292 236933 118332 236933 118332 236934 118292 236934 118293 236934 118332 236935 118293 236935 118294 236935 118294 236936 118293 236936 118287 236936 118294 236937 118287 236937 118333 236937 118333 236938 118287 236938 118288 236938 118295 236939 118307 236939 118313 236939 118313 236940 118307 236940 118302 236940 114539 236941 118296 236941 118297 236941 118297 236942 118296 236942 118310 236942 118297 236943 118310 236943 118298 236943 118298 236944 118310 236944 118299 236944 118298 236945 118299 236945 118300 236945 118300 236946 118299 236946 118311 236946 118300 236947 118311 236947 118301 236947 118301 236948 118311 236948 118313 236948 118301 236949 118313 236949 118256 236949 118256 236950 118313 236950 118302 236950 118256 236951 118302 236951 118255 236951 118255 236952 118302 236952 118304 236952 118303 236953 118304 236953 118305 236953 118305 236954 118304 236954 118302 236954 118305 236955 118302 236955 118306 236955 118306 236956 118302 236956 118307 236956 118306 236957 118307 236957 116342 236957 116342 236958 118307 236958 118295 236958 116342 236959 118295 236959 116323 236959 118296 236960 118308 236960 118310 236960 118310 236961 118308 236961 118309 236961 118310 236962 118309 236962 118299 236962 118299 236963 118309 236963 118312 236963 118299 236964 118312 236964 118311 236964 118311 236965 118312 236965 118340 236965 118311 236966 118340 236966 118313 236966 118313 236967 118340 236967 118339 236967 118313 236968 118339 236968 118295 236968 118295 236969 118339 236969 118314 236969 118295 236970 118314 236970 116323 236970 118315 236971 116326 236971 118316 236971 118316 236972 116326 236972 118351 236972 118316 236973 118351 236973 118317 236973 118317 236974 118351 236974 118350 236974 118317 236975 118350 236975 118321 236975 118321 236976 118350 236976 118348 236976 118321 236977 118348 236977 118323 236977 118323 236978 118348 236978 118318 236978 118323 236979 118318 236979 118326 236979 118326 236980 118318 236980 118346 236980 118326 236981 118346 236981 115823 236981 115823 236982 118346 236982 118319 236982 116325 236983 118315 236983 118320 236983 118320 236984 118315 236984 118316 236984 118320 236985 118316 236985 118330 236985 118330 236986 118316 236986 118317 236986 118330 236987 118317 236987 118328 236987 118328 236988 118317 236988 118321 236988 118328 236989 118321 236989 118322 236989 118322 236990 118321 236990 118323 236990 118322 236991 118323 236991 118324 236991 118324 236992 118323 236992 118326 236992 118324 236993 118326 236993 118325 236993 118325 236994 118326 236994 115823 236994 118325 236995 115824 236995 118324 236995 118324 236996 115824 236996 118327 236996 118324 236997 118327 236997 118322 236997 118322 236998 118327 236998 118289 236998 118322 236999 118289 236999 118328 236999 118328 237000 118289 237000 118329 237000 118328 237001 118329 237001 118330 237001 118330 237002 118329 237002 118331 237002 118330 237003 118331 237003 118320 237003 118320 237004 118331 237004 118332 237004 118320 237005 118332 237005 116325 237005 116325 237006 118332 237006 118294 237006 116325 237007 118294 237007 118333 237007 118343 237008 118334 237008 118342 237008 118314 237009 118338 237009 116323 237009 116323 237010 118338 237010 116322 237010 118335 237011 116322 237011 118336 237011 118336 237012 116322 237012 118338 237012 118336 237013 118338 237013 118337 237013 118334 237014 114479 237014 118342 237014 118342 237015 114479 237015 118367 237015 118342 237016 118367 237016 118341 237016 118314 237017 118339 237017 118338 237017 118338 237018 118339 237018 118341 237018 118338 237019 118341 237019 118337 237019 118337 237020 118341 237020 118367 237020 118339 237021 118340 237021 118341 237021 118341 237022 118340 237022 118312 237022 118341 237023 118312 237023 118342 237023 118342 237024 118312 237024 118309 237024 118342 237025 118309 237025 118343 237025 118343 237026 118309 237026 118308 237026 118344 237027 118319 237027 118353 237027 118353 237028 118319 237028 118346 237028 118353 237029 118346 237029 118345 237029 118345 237030 118346 237030 118318 237030 118345 237031 118318 237031 118347 237031 118347 237032 118318 237032 118348 237032 118347 237033 118348 237033 118349 237033 118349 237034 118348 237034 118350 237034 118349 237035 118350 237035 118356 237035 118356 237036 118350 237036 118351 237036 118356 237037 118351 237037 116328 237037 116328 237038 118351 237038 116326 237038 115884 237039 118344 237039 118352 237039 118352 237040 118344 237040 118353 237040 118352 237041 118353 237041 118359 237041 118359 237042 118353 237042 118345 237042 118359 237043 118345 237043 118354 237043 118354 237044 118345 237044 118347 237044 118354 237045 118347 237045 118361 237045 118361 237046 118347 237046 118349 237046 118361 237047 118349 237047 118355 237047 118355 237048 118349 237048 118356 237048 118355 237049 118356 237049 118357 237049 118357 237050 118356 237050 116328 237050 115885 237051 115884 237051 118358 237051 118358 237052 115884 237052 118352 237052 118358 237053 118352 237053 118382 237053 118382 237054 118352 237054 118359 237054 118382 237055 118359 237055 118360 237055 118360 237056 118359 237056 118354 237056 118360 237057 118354 237057 118362 237057 118362 237058 118354 237058 118361 237058 118362 237059 118361 237059 118363 237059 118363 237060 118361 237060 118355 237060 118363 237061 118355 237061 116329 237061 116329 237062 118355 237062 118357 237062 118371 237063 118364 237063 118336 237063 118336 237064 118364 237064 118335 237064 118335 237065 118364 237065 118365 237065 118365 237066 118364 237066 118397 237066 118365 237067 118397 237067 118366 237067 118337 237068 118367 237068 118368 237068 118370 237069 118368 237069 114521 237069 114521 237070 118368 237070 118367 237070 114521 237071 118367 237071 114479 237071 118336 237072 118337 237072 118371 237072 118371 237073 118337 237073 118368 237073 118371 237074 118368 237074 118369 237074 118369 237075 118368 237075 118370 237075 118369 237076 118370 237076 118407 237076 118369 237077 118404 237077 118371 237077 118371 237078 118404 237078 118403 237078 118371 237079 118403 237079 118364 237079 118364 237080 118403 237080 118372 237080 118364 237081 118372 237081 118397 237081 118363 237082 116329 237082 118386 237082 118380 237083 118381 237083 118373 237083 118373 237084 118381 237084 118374 237084 118374 237085 118381 237085 118422 237085 118422 237086 118381 237086 118375 237086 118422 237087 118375 237087 118376 237087 118376 237088 118375 237088 118383 237088 118376 237089 118383 237089 118377 237089 118377 237090 118383 237090 118384 237090 118377 237091 118384 237091 118378 237091 118378 237092 118384 237092 118379 237092 118378 237093 118379 237093 118424 237093 118424 237094 118379 237094 118385 237094 118424 237095 118385 237095 116354 237095 118380 237096 115885 237096 118381 237096 118381 237097 115885 237097 118358 237097 118381 237098 118358 237098 118375 237098 118375 237099 118358 237099 118382 237099 118375 237100 118382 237100 118383 237100 118383 237101 118382 237101 118360 237101 118383 237102 118360 237102 118384 237102 118384 237103 118360 237103 118362 237103 118384 237104 118362 237104 118379 237104 118379 237105 118362 237105 118363 237105 118379 237106 118363 237106 118385 237106 118385 237107 118363 237107 118386 237107 118385 237108 118386 237108 116354 237108 118399 237109 118397 237109 118372 237109 118406 237110 114509 237110 118405 237110 114162 237111 118387 237111 118394 237111 118388 237112 118443 237112 118396 237112 118396 237113 118443 237113 118389 237113 118396 237114 118389 237114 118400 237114 118395 237115 118390 237115 118391 237115 118391 237116 118390 237116 118392 237116 118391 237117 118392 237117 118457 237117 118457 237118 118392 237118 118405 237118 118457 237119 118405 237119 118394 237119 118405 237120 114509 237120 118394 237120 118394 237121 114509 237121 118393 237121 118394 237122 118393 237122 114162 237122 118391 237123 118388 237123 118395 237123 118395 237124 118388 237124 118396 237124 118395 237125 118396 237125 118402 237125 118402 237126 118396 237126 118400 237126 118366 237127 118397 237127 118398 237127 118398 237128 118397 237128 118399 237128 118398 237129 118399 237129 118401 237129 118400 237130 118401 237130 118402 237130 118402 237131 118401 237131 118399 237131 118402 237132 118399 237132 118395 237132 118395 237133 118399 237133 118372 237133 118395 237134 118372 237134 118390 237134 118390 237135 118372 237135 118403 237135 118390 237136 118403 237136 118392 237136 118392 237137 118403 237137 118404 237137 118392 237138 118404 237138 118405 237138 118405 237139 118404 237139 118369 237139 118405 237140 118369 237140 118406 237140 118406 237141 118369 237141 118407 237141 118426 237142 118440 237142 118425 237142 118415 237143 118416 237143 118432 237143 118432 237144 118416 237144 118417 237144 118408 237145 114166 237145 118420 237145 114165 237146 118373 237146 118374 237146 118408 237147 118420 237147 114227 237147 118412 237148 114228 237148 118413 237148 118433 237149 118409 237149 118431 237149 118431 237150 118409 237150 118410 237150 118431 237151 118410 237151 118430 237151 118411 237152 118412 237152 118428 237152 118428 237153 118412 237153 118413 237153 118428 237154 118413 237154 118414 237154 118414 237155 118413 237155 118434 237155 118414 237156 118434 237156 118429 237156 118429 237157 118434 237157 118435 237157 118429 237158 118435 237158 118415 237158 118415 237159 118435 237159 118436 237159 118415 237160 118436 237160 118416 237160 118416 237161 118436 237161 118438 237161 118416 237162 118438 237162 118417 237162 118417 237163 118438 237163 118418 237163 118417 237164 118418 237164 118419 237164 114166 237165 114165 237165 118420 237165 118420 237166 114165 237166 118374 237166 118420 237167 118374 237167 118421 237167 118421 237168 118374 237168 118422 237168 118421 237169 118422 237169 118437 237169 118437 237170 118422 237170 118376 237170 118437 237171 118376 237171 118423 237171 118423 237172 118376 237172 118377 237172 118423 237173 118377 237173 118439 237173 118439 237174 118377 237174 118378 237174 118439 237175 118378 237175 118425 237175 118425 237176 118378 237176 118424 237176 118425 237177 118424 237177 118426 237177 118426 237178 118424 237178 116354 237178 114163 237179 118411 237179 118427 237179 118427 237180 118411 237180 118428 237180 118427 237181 118428 237181 118452 237181 118452 237182 118428 237182 118414 237182 118452 237183 118414 237183 118453 237183 118453 237184 118414 237184 118429 237184 118453 237185 118429 237185 118430 237185 118430 237186 118429 237186 118415 237186 118430 237187 118415 237187 118431 237187 118431 237188 118415 237188 118432 237188 118431 237189 118432 237189 118433 237189 118433 237190 118432 237190 118417 237190 114228 237191 114227 237191 118413 237191 118413 237192 114227 237192 118420 237192 118413 237193 118420 237193 118434 237193 118434 237194 118420 237194 118421 237194 118434 237195 118421 237195 118435 237195 118435 237196 118421 237196 118437 237196 118435 237197 118437 237197 118436 237197 118436 237198 118437 237198 118423 237198 118436 237199 118423 237199 118438 237199 118438 237200 118423 237200 118439 237200 118438 237201 118439 237201 118418 237201 118418 237202 118439 237202 118425 237202 118418 237203 118425 237203 118419 237203 118419 237204 118425 237204 118440 237204 118441 237205 114164 237205 118451 237205 118444 237206 118443 237206 118388 237206 114226 237207 118462 237207 118446 237207 118447 237208 118448 237208 118460 237208 118460 237209 118448 237209 116346 237209 118389 237210 118443 237210 118442 237210 118442 237211 118443 237211 118444 237211 118442 237212 118444 237212 118461 237212 118456 237213 114226 237213 118445 237213 118445 237214 114226 237214 118446 237214 118445 237215 118446 237215 118458 237215 118458 237216 118446 237216 118463 237216 118458 237217 118463 237217 118459 237217 118459 237218 118463 237218 118465 237218 118459 237219 118465 237219 118447 237219 118447 237220 118465 237220 118467 237220 118447 237221 118467 237221 118448 237221 118448 237222 118467 237222 118449 237222 118448 237223 118449 237223 116346 237223 116346 237224 118449 237224 118450 237224 116346 237225 118450 237225 116345 237225 116345 237226 118450 237226 116350 237226 114164 237227 114163 237227 118451 237227 118451 237228 114163 237228 118427 237228 118451 237229 118427 237229 118464 237229 118464 237230 118427 237230 118452 237230 118464 237231 118452 237231 118466 237231 118466 237232 118452 237232 118453 237232 118466 237233 118453 237233 118468 237233 118468 237234 118453 237234 118430 237234 118468 237235 118430 237235 118454 237235 118454 237236 118430 237236 118410 237236 118454 237237 118410 237237 118455 237237 118455 237238 118410 237238 118409 237238 118455 237239 118409 237239 116349 237239 118387 237240 118456 237240 118394 237240 118394 237241 118456 237241 118445 237241 118394 237242 118445 237242 118457 237242 118457 237243 118445 237243 118458 237243 118457 237244 118458 237244 118391 237244 118391 237245 118458 237245 118459 237245 118391 237246 118459 237246 118388 237246 118388 237247 118459 237247 118447 237247 118388 237248 118447 237248 118444 237248 118444 237249 118447 237249 118460 237249 118444 237250 118460 237250 118461 237250 118461 237251 118460 237251 116346 237251 118462 237252 118441 237252 118446 237252 118446 237253 118441 237253 118451 237253 118446 237254 118451 237254 118463 237254 118463 237255 118451 237255 118464 237255 118463 237256 118464 237256 118465 237256 118465 237257 118464 237257 118466 237257 118465 237258 118466 237258 118467 237258 118467 237259 118466 237259 118468 237259 118467 237260 118468 237260 118449 237260 118449 237261 118468 237261 118454 237261 118449 237262 118454 237262 118450 237262 118450 237263 118454 237263 118455 237263 118450 237264 118455 237264 116350 237264 116350 237265 118455 237265 116349 237265 118501 237266 118469 237266 118470 237266 118470 237267 118469 237267 116358 237267 118470 237268 116358 237268 116370 237268 118556 237269 118471 237269 118501 237269 118501 237270 118471 237270 118472 237270 118501 237271 118472 237271 118469 237271 118501 237272 118495 237272 118556 237272 118556 237273 118495 237273 118494 237273 118556 237274 118494 237274 118548 237274 118548 237275 118494 237275 115947 237275 118548 237276 115947 237276 118473 237276 118470 237277 116370 237277 116369 237277 115947 237278 118494 237278 118474 237278 115947 237279 118474 237279 115949 237279 115949 237280 118474 237280 118493 237280 115949 237281 118493 237281 118475 237281 118475 237282 118493 237282 118478 237282 118475 237283 118478 237283 118476 237283 115942 237284 118476 237284 118477 237284 118477 237285 118476 237285 118478 237285 118477 237286 118478 237286 118479 237286 118483 237287 118479 237287 118492 237287 116362 237288 118516 237288 118485 237288 118485 237289 118516 237289 118480 237289 118485 237290 118480 237290 118487 237290 118487 237291 118480 237291 118481 237291 118487 237292 118481 237292 118488 237292 118488 237293 118481 237293 118482 237293 118488 237294 118482 237294 118496 237294 118496 237295 118482 237295 118483 237295 116368 237296 116362 237296 118484 237296 118484 237297 116362 237297 118485 237297 118484 237298 118485 237298 118486 237298 118486 237299 118485 237299 118487 237299 118486 237300 118487 237300 118490 237300 118490 237301 118487 237301 118488 237301 118490 237302 118488 237302 118499 237302 118499 237303 118488 237303 118496 237303 118499 237304 118489 237304 118490 237304 118490 237305 118489 237305 118500 237305 118490 237306 118500 237306 118486 237306 118486 237307 118500 237307 118502 237307 118486 237308 118502 237308 118484 237308 118484 237309 118502 237309 118491 237309 118484 237310 118491 237310 116368 237310 118479 237311 118478 237311 118492 237311 118492 237312 118478 237312 118493 237312 118492 237313 118493 237313 118497 237313 118497 237314 118493 237314 118474 237314 118497 237315 118474 237315 118498 237315 118498 237316 118474 237316 118494 237316 118498 237317 118494 237317 118495 237317 118483 237318 118492 237318 118496 237318 118496 237319 118492 237319 118497 237319 118496 237320 118497 237320 118499 237320 118499 237321 118497 237321 118498 237321 118499 237322 118498 237322 118489 237322 118489 237323 118498 237323 118495 237323 118489 237324 118495 237324 118500 237324 118500 237325 118495 237325 118501 237325 118500 237326 118501 237326 118502 237326 118502 237327 118501 237327 118470 237327 118502 237328 118470 237328 118491 237328 118491 237329 118470 237329 116369 237329 118491 237330 116369 237330 116368 237330 116363 237331 116364 237331 118515 237331 116392 237332 118503 237332 116360 237332 116360 237333 118503 237333 118504 237333 116360 237334 118504 237334 118506 237334 118506 237335 118504 237335 118505 237335 118506 237336 118505 237336 116366 237336 118519 237337 118507 237337 118508 237337 118508 237338 118507 237338 118524 237338 118508 237339 118524 237339 118509 237339 118509 237340 118524 237340 118525 237340 118509 237341 118525 237341 118510 237341 118510 237342 118525 237342 118511 237342 118510 237343 118511 237343 118512 237343 118512 237344 118511 237344 118523 237344 115917 237345 115942 237345 118513 237345 118513 237346 115942 237346 118477 237346 118513 237347 118477 237347 118526 237347 118526 237348 118477 237348 118479 237348 118526 237349 118479 237349 118527 237349 118527 237350 118479 237350 118483 237350 118527 237351 118483 237351 118514 237351 118514 237352 118483 237352 118482 237352 118514 237353 118482 237353 118528 237353 118528 237354 118482 237354 118481 237354 118528 237355 118481 237355 118515 237355 118515 237356 118481 237356 118480 237356 118515 237357 118480 237357 116363 237357 116363 237358 118480 237358 118516 237358 118519 237359 118518 237359 118536 237359 115916 237360 118507 237360 115920 237360 115920 237361 118507 237361 118519 237361 115920 237362 118519 237362 118517 237362 118517 237363 118519 237363 118536 237363 118518 237364 118519 237364 118520 237364 118520 237365 118519 237365 118508 237365 118520 237366 118508 237366 118521 237366 118521 237367 118508 237367 118509 237367 118521 237368 118509 237368 118522 237368 118522 237369 118509 237369 118510 237369 118522 237370 118510 237370 118503 237370 118503 237371 118510 237371 118512 237371 118503 237372 118512 237372 118504 237372 118504 237373 118512 237373 118523 237373 118504 237374 118523 237374 118505 237374 115916 237375 115917 237375 118507 237375 118507 237376 115917 237376 118513 237376 118507 237377 118513 237377 118524 237377 118524 237378 118513 237378 118526 237378 118524 237379 118526 237379 118525 237379 118525 237380 118526 237380 118527 237380 118525 237381 118527 237381 118511 237381 118511 237382 118527 237382 118514 237382 118511 237383 118514 237383 118523 237383 118523 237384 118514 237384 118528 237384 118523 237385 118528 237385 118505 237385 118505 237386 118528 237386 118515 237386 118505 237387 118515 237387 116366 237387 116366 237388 118515 237388 116364 237388 118531 237389 118601 237389 118529 237389 118529 237390 118530 237390 118531 237390 118531 237391 118530 237391 118537 237391 118531 237392 118537 237392 118603 237392 118537 237393 118532 237393 118603 237393 118603 237394 118532 237394 118538 237394 118603 237395 118538 237395 118533 237395 118533 237396 118538 237396 118534 237396 118534 237397 118538 237397 118539 237397 118534 237398 118539 237398 118600 237398 118539 237399 118540 237399 118600 237399 118600 237400 118540 237400 118535 237400 118600 237401 118535 237401 116390 237401 118529 237402 118536 237402 118530 237402 118530 237403 118536 237403 118518 237403 118530 237404 118518 237404 118537 237404 118537 237405 118518 237405 118520 237405 118537 237406 118520 237406 118532 237406 118532 237407 118520 237407 118521 237407 118532 237408 118521 237408 118538 237408 118538 237409 118521 237409 118522 237409 118538 237410 118522 237410 118539 237410 118539 237411 118522 237411 118503 237411 118539 237412 118503 237412 118540 237412 118540 237413 118503 237413 116392 237413 118540 237414 116392 237414 118535 237414 118562 237415 118561 237415 118469 237415 118612 237416 118610 237416 118541 237416 118616 237417 118542 237417 118543 237417 115950 237418 118544 237418 118616 237418 118616 237419 118543 237419 115950 237419 115950 237420 118543 237420 118545 237420 115950 237421 118545 237421 118547 237421 118547 237422 118545 237422 118546 237422 118547 237423 118546 237423 115954 237423 115954 237424 118546 237424 118572 237424 115954 237425 118572 237425 115955 237425 118548 237426 118473 237426 115941 237426 118542 237427 118612 237427 118550 237427 118612 237428 118541 237428 118550 237428 118550 237429 118541 237429 118549 237429 118550 237430 118549 237430 118554 237430 118554 237431 118549 237431 118552 237431 118554 237432 118552 237432 118551 237432 118551 237433 118552 237433 118553 237433 118551 237434 118553 237434 118571 237434 118542 237435 118550 237435 118543 237435 118543 237436 118550 237436 118554 237436 118543 237437 118554 237437 118545 237437 118545 237438 118554 237438 118551 237438 118545 237439 118551 237439 118546 237439 118546 237440 118551 237440 118571 237440 118546 237441 118571 237441 118572 237441 118472 237442 118471 237442 118555 237442 118555 237443 118471 237443 118556 237443 118555 237444 118556 237444 118557 237444 118557 237445 118556 237445 118548 237445 118557 237446 118548 237446 118558 237446 118558 237447 118548 237447 115941 237447 118558 237448 115941 237448 115962 237448 116372 237449 118559 237449 116374 237449 116374 237450 118559 237450 118560 237450 118561 237451 118562 237451 118563 237451 118563 237452 118562 237452 118564 237452 118563 237453 118564 237453 118570 237453 118570 237454 118564 237454 118588 237454 118570 237455 118588 237455 118565 237455 118565 237456 118588 237456 118566 237456 118565 237457 118566 237457 118567 237457 118567 237458 118566 237458 115963 237458 118567 237459 115963 237459 118573 237459 116358 237460 118469 237460 118592 237460 118592 237461 118469 237461 118561 237461 118592 237462 118561 237462 118568 237462 118568 237463 118561 237463 118563 237463 118568 237464 118563 237464 118569 237464 118569 237465 118563 237465 118570 237465 118569 237466 118570 237466 118553 237466 118553 237467 118570 237467 118565 237467 118553 237468 118565 237468 118571 237468 118571 237469 118565 237469 118567 237469 118571 237470 118567 237470 118572 237470 118572 237471 118567 237471 118573 237471 118572 237472 118573 237472 115955 237472 116397 237473 116380 237473 118574 237473 118574 237474 116380 237474 118575 237474 116380 237475 116378 237475 118575 237475 118575 237476 116378 237476 116377 237476 118575 237477 116377 237477 118576 237477 118576 237478 116377 237478 118577 237478 118576 237479 118577 237479 118585 237479 118585 237480 118577 237480 116375 237480 118585 237481 116375 237481 118578 237481 118578 237482 116375 237482 118579 237482 118578 237483 118579 237483 118560 237483 118560 237484 118579 237484 118580 237484 118560 237485 118580 237485 116374 237485 118608 237486 118607 237486 118589 237486 118589 237487 118607 237487 118582 237487 118589 237488 118582 237488 118581 237488 118581 237489 118582 237489 118587 237489 118581 237490 118587 237490 118590 237490 118590 237491 118587 237491 118586 237491 118590 237492 118586 237492 118583 237492 118583 237493 118586 237493 118584 237493 118583 237494 118584 237494 118591 237494 118559 237495 118591 237495 118560 237495 118560 237496 118591 237496 118584 237496 118560 237497 118584 237497 118578 237497 118578 237498 118584 237498 118586 237498 118578 237499 118586 237499 118585 237499 118585 237500 118586 237500 118587 237500 118585 237501 118587 237501 118576 237501 118576 237502 118587 237502 118582 237502 118576 237503 118582 237503 118575 237503 118575 237504 118582 237504 118607 237504 118575 237505 118607 237505 118574 237505 118469 237506 118472 237506 118562 237506 118562 237507 118472 237507 118555 237507 118562 237508 118555 237508 118564 237508 118564 237509 118555 237509 118557 237509 118564 237510 118557 237510 118588 237510 118588 237511 118557 237511 118558 237511 118588 237512 118558 237512 118566 237512 118566 237513 118558 237513 115962 237513 118566 237514 115962 237514 115963 237514 118610 237515 118608 237515 118541 237515 118541 237516 118608 237516 118589 237516 118541 237517 118589 237517 118549 237517 118549 237518 118589 237518 118581 237518 118549 237519 118581 237519 118552 237519 118552 237520 118581 237520 118590 237520 118552 237521 118590 237521 118553 237521 118553 237522 118590 237522 118583 237522 118553 237523 118583 237523 118569 237523 118569 237524 118583 237524 118591 237524 118569 237525 118591 237525 118568 237525 118568 237526 118591 237526 118559 237526 118568 237527 118559 237527 118592 237527 118592 237528 118559 237528 116372 237528 118592 237529 116372 237529 116358 237529 118602 237530 118593 237530 118601 237530 118594 237531 114422 237531 118593 237531 118593 237532 118602 237532 118594 237532 118594 237533 118602 237533 118604 237533 118594 237534 118604 237534 118627 237534 118599 237535 118598 237535 118595 237535 118595 237536 118598 237536 118596 237536 118595 237537 118596 237537 118597 237537 118597 237538 118596 237538 118629 237538 118597 237539 118629 237539 118605 237539 116386 237540 118598 237540 116387 237540 116387 237541 118598 237541 118599 237541 116387 237542 118599 237542 116390 237542 116390 237543 118599 237543 118600 237543 118600 237544 118599 237544 118595 237544 118600 237545 118595 237545 118534 237545 118534 237546 118595 237546 118597 237546 118534 237547 118597 237547 118533 237547 118533 237548 118597 237548 118605 237548 118533 237549 118605 237549 118603 237549 118601 237550 118531 237550 118602 237550 118602 237551 118531 237551 118603 237551 118602 237552 118603 237552 118604 237552 118604 237553 118603 237553 118605 237553 118604 237554 118605 237554 118627 237554 118627 237555 118605 237555 118629 237555 118618 237556 116397 237556 118606 237556 118606 237557 116397 237557 118574 237557 118606 237558 118574 237558 118620 237558 118620 237559 118574 237559 118607 237559 118620 237560 118607 237560 118621 237560 118621 237561 118607 237561 118608 237561 118621 237562 118608 237562 118609 237562 118609 237563 118608 237563 118610 237563 118609 237564 118610 237564 118611 237564 118611 237565 118610 237565 118612 237565 118611 237566 118612 237566 118613 237566 118613 237567 118612 237567 118542 237567 118613 237568 118542 237568 118614 237568 118614 237569 118542 237569 118616 237569 118614 237570 118616 237570 118615 237570 118615 237571 118616 237571 118544 237571 118617 237572 118618 237572 118619 237572 118619 237573 118618 237573 118606 237573 118619 237574 118606 237574 118664 237574 118664 237575 118606 237575 118620 237575 118664 237576 118620 237576 118622 237576 118622 237577 118620 237577 118621 237577 118622 237578 118621 237578 118623 237578 118623 237579 118621 237579 118609 237579 118623 237580 118609 237580 118624 237580 118624 237581 118609 237581 118611 237581 118624 237582 118611 237582 118669 237582 118669 237583 118611 237583 118613 237583 118669 237584 118613 237584 118625 237584 118625 237585 118613 237585 118614 237585 118625 237586 118614 237586 115966 237586 115966 237587 118614 237587 118615 237587 118637 237588 116355 237588 118640 237588 118642 237589 118641 237589 114422 237589 118631 237590 118678 237590 118626 237590 118630 237591 118598 237591 116386 237591 114422 237592 118594 237592 118642 237592 118642 237593 118594 237593 118627 237593 118642 237594 118627 237594 118628 237594 118628 237595 118627 237595 118629 237595 118628 237596 118629 237596 118644 237596 118644 237597 118629 237597 118596 237597 118644 237598 118596 237598 118646 237598 118646 237599 118596 237599 118598 237599 118646 237600 118598 237600 118647 237600 118647 237601 118598 237601 118630 237601 118634 237602 118631 237602 118632 237602 118632 237603 118631 237603 118626 237603 118632 237604 118626 237604 115870 237604 115870 237605 118633 237605 118632 237605 118632 237606 118633 237606 118643 237606 118632 237607 118643 237607 118634 237607 118634 237608 118643 237608 118635 237608 118634 237609 118635 237609 118639 237609 118639 237610 118635 237610 118636 237610 118639 237611 118636 237611 118638 237611 118638 237612 118636 237612 118645 237612 118638 237613 118645 237613 116383 237613 116383 237614 118637 237614 118638 237614 118638 237615 118637 237615 118640 237615 118638 237616 118640 237616 118639 237616 118639 237617 118640 237617 118682 237617 118639 237618 118682 237618 118634 237618 118634 237619 118682 237619 118681 237619 118634 237620 118681 237620 118631 237620 115870 237621 118641 237621 118633 237621 118633 237622 118641 237622 118642 237622 118633 237623 118642 237623 118643 237623 118643 237624 118642 237624 118628 237624 118643 237625 118628 237625 118635 237625 118635 237626 118628 237626 118644 237626 118635 237627 118644 237627 118636 237627 118636 237628 118644 237628 118646 237628 118636 237629 118646 237629 118645 237629 118645 237630 118646 237630 118647 237630 118645 237631 118647 237631 116383 237631 116383 237632 118647 237632 118630 237632 116383 237633 118630 237633 118648 237633 118648 237634 118630 237634 116386 237634 116399 237635 116398 237635 118649 237635 118668 237636 118662 237636 118667 237636 118667 237637 118662 237637 118672 237637 118667 237638 118672 237638 118666 237638 118666 237639 118672 237639 118650 237639 118666 237640 118650 237640 118651 237640 118651 237641 118650 237641 118652 237641 118651 237642 118652 237642 118665 237642 118665 237643 118652 237643 118653 237643 118665 237644 118653 237644 118649 237644 118649 237645 118653 237645 118654 237645 118649 237646 118654 237646 116399 237646 116399 237647 118654 237647 116400 237647 118657 237648 118655 237648 118656 237648 118656 237649 118677 237649 118657 237649 118657 237650 118677 237650 118658 237650 118657 237651 118658 237651 118686 237651 118686 237652 118658 237652 118676 237652 118670 237653 118659 237653 118671 237653 118671 237654 118659 237654 118690 237654 118671 237655 118690 237655 118673 237655 118673 237656 118690 237656 118691 237656 118673 237657 118691 237657 118674 237657 118674 237658 118691 237658 118660 237658 118674 237659 118660 237659 118675 237659 118675 237660 118660 237660 118661 237660 118675 237661 118661 237661 118676 237661 118676 237662 118661 237662 118685 237662 118676 237663 118685 237663 118686 237663 115845 237664 118662 237664 115844 237664 115844 237665 118662 237665 118668 237665 115844 237666 118668 237666 118663 237666 118663 237667 118668 237667 118625 237667 118663 237668 118625 237668 115966 237668 116398 237669 118617 237669 118649 237669 118649 237670 118617 237670 118619 237670 118649 237671 118619 237671 118665 237671 118665 237672 118619 237672 118664 237672 118665 237673 118664 237673 118651 237673 118651 237674 118664 237674 118622 237674 118651 237675 118622 237675 118666 237675 118666 237676 118622 237676 118623 237676 118666 237677 118623 237677 118667 237677 118667 237678 118623 237678 118624 237678 118667 237679 118624 237679 118668 237679 118668 237680 118624 237680 118669 237680 118668 237681 118669 237681 118625 237681 115845 237682 118670 237682 118662 237682 118662 237683 118670 237683 118671 237683 118662 237684 118671 237684 118672 237684 118672 237685 118671 237685 118673 237685 118672 237686 118673 237686 118650 237686 118650 237687 118673 237687 118674 237687 118650 237688 118674 237688 118652 237688 118652 237689 118674 237689 118675 237689 118652 237690 118675 237690 118653 237690 118653 237691 118675 237691 118676 237691 118653 237692 118676 237692 118654 237692 118654 237693 118676 237693 118658 237693 118654 237694 118658 237694 116400 237694 116400 237695 118658 237695 118677 237695 118680 237696 118698 237696 118631 237696 118678 237697 118631 237697 118679 237697 118679 237698 118631 237698 118698 237698 118679 237699 118698 237699 115869 237699 118680 237700 118631 237700 118700 237700 118700 237701 118631 237701 118681 237701 118700 237702 118681 237702 118683 237702 116355 237703 118693 237703 118640 237703 118640 237704 118693 237704 118683 237704 118640 237705 118683 237705 118682 237705 118682 237706 118683 237706 118681 237706 118689 237707 118684 237707 118708 237707 116357 237708 118688 237708 118687 237708 118661 237709 118687 237709 118685 237709 118685 237710 118687 237710 118686 237710 118686 237711 118687 237711 118657 237711 118657 237712 118687 237712 118688 237712 118657 237713 118688 237713 118655 237713 118659 237714 118689 237714 118690 237714 118690 237715 118689 237715 118708 237715 118690 237716 118708 237716 118691 237716 118691 237717 118708 237717 118707 237717 118691 237718 118707 237718 118660 237718 118660 237719 118707 237719 118706 237719 118660 237720 118706 237720 118661 237720 118661 237721 118706 237721 118692 237721 118661 237722 118692 237722 118687 237722 118687 237723 118692 237723 118705 237723 118687 237724 118705 237724 116357 237724 118696 237725 115869 237725 118698 237725 118683 237726 118693 237726 118694 237726 118695 237727 118696 237727 118697 237727 118697 237728 118696 237728 118698 237728 118697 237729 118698 237729 118699 237729 118699 237730 118698 237730 118680 237730 118699 237731 118680 237731 118701 237731 118701 237732 118680 237732 118700 237732 118701 237733 118700 237733 118704 237733 118704 237734 118700 237734 118683 237734 118704 237735 118683 237735 118702 237735 118702 237736 118683 237736 118694 237736 118702 237737 118694 237737 118703 237737 118703 237738 116357 237738 118702 237738 118702 237739 116357 237739 118705 237739 118702 237740 118705 237740 118704 237740 118704 237741 118705 237741 118692 237741 118704 237742 118692 237742 118701 237742 118701 237743 118692 237743 118706 237743 118701 237744 118706 237744 118699 237744 118699 237745 118706 237745 118707 237745 118699 237746 118707 237746 118697 237746 118697 237747 118707 237747 118708 237747 118697 237748 118708 237748 118695 237748 118695 237749 118708 237749 118684 237749 118757 237750 118709 237750 118759 237750 118713 237751 118782 237751 118714 237751 118724 237752 118711 237752 118710 237752 118710 237753 118711 237753 118713 237753 118710 237754 118713 237754 118712 237754 118712 237755 118713 237755 118714 237755 118712 237756 118714 237756 118784 237756 115956 237757 118768 237757 118741 237757 118741 237758 118768 237758 118715 237758 118741 237759 118715 237759 118717 237759 118717 237760 118715 237760 118716 237760 118717 237761 118716 237761 118742 237761 118742 237762 118716 237762 118767 237762 118742 237763 118767 237763 118766 237763 118780 237764 118721 237764 118756 237764 118756 237765 118721 237765 118722 237765 118756 237766 118722 237766 118718 237766 118718 237767 118722 237767 118720 237767 118718 237768 118720 237768 118719 237768 118719 237769 118720 237769 118723 237769 118719 237770 118723 237770 118754 237770 118754 237771 118723 237771 118761 237771 118721 237772 118782 237772 118722 237772 118722 237773 118782 237773 118713 237773 118722 237774 118713 237774 118720 237774 118720 237775 118713 237775 118711 237775 118720 237776 118711 237776 118723 237776 118723 237777 118711 237777 118724 237777 118723 237778 118724 237778 118761 237778 118761 237779 118724 237779 118762 237779 118725 237780 118743 237780 118728 237780 118726 237781 116412 237781 118743 237781 118743 237782 116412 237782 116411 237782 118743 237783 116411 237783 118728 237783 118728 237784 116411 237784 116410 237784 118728 237785 116410 237785 118727 237785 118727 237786 116410 237786 116409 237786 118727 237787 116409 237787 118730 237787 116409 237788 116407 237788 118730 237788 118730 237789 116407 237789 118777 237789 118730 237790 118777 237790 118779 237790 118725 237791 118728 237791 118745 237791 118745 237792 118728 237792 118727 237792 118745 237793 118727 237793 118729 237793 118729 237794 118727 237794 118730 237794 118729 237795 118730 237795 118746 237795 118746 237796 118730 237796 118779 237796 118746 237797 118779 237797 118749 237797 115957 237798 118740 237798 118732 237798 118732 237799 118740 237799 118731 237799 118732 237800 118731 237800 118733 237800 118733 237801 118731 237801 118734 237801 118733 237802 118734 237802 118736 237802 118736 237803 118734 237803 118735 237803 118736 237804 118735 237804 118737 237804 118737 237805 118735 237805 118738 237805 118737 237806 118738 237806 118739 237806 118739 237807 118738 237807 118765 237807 118739 237808 118765 237808 118758 237808 118758 237809 118765 237809 118764 237809 118758 237810 118764 237810 116414 237810 118740 237811 115956 237811 118731 237811 118731 237812 115956 237812 118741 237812 118731 237813 118741 237813 118734 237813 118734 237814 118741 237814 118717 237814 118734 237815 118717 237815 118735 237815 118735 237816 118717 237816 118742 237816 118735 237817 118742 237817 118738 237817 118738 237818 118742 237818 118766 237818 118738 237819 118766 237819 118765 237819 118709 237820 118726 237820 118751 237820 118751 237821 118726 237821 118743 237821 118751 237822 118743 237822 118744 237822 118744 237823 118743 237823 118725 237823 118744 237824 118725 237824 118753 237824 118753 237825 118725 237825 118745 237825 118753 237826 118745 237826 118755 237826 118755 237827 118745 237827 118729 237827 118755 237828 118729 237828 118747 237828 118747 237829 118729 237829 118746 237829 118747 237830 118746 237830 118748 237830 118748 237831 118746 237831 118749 237831 118748 237832 118749 237832 118750 237832 118759 237833 118709 237833 118751 237833 118759 237834 118751 237834 118752 237834 118752 237835 118751 237835 118744 237835 118752 237836 118744 237836 118760 237836 118760 237837 118744 237837 118753 237837 118760 237838 118753 237838 118754 237838 118754 237839 118753 237839 118755 237839 118754 237840 118755 237840 118719 237840 118719 237841 118755 237841 118747 237841 118719 237842 118747 237842 118718 237842 118718 237843 118747 237843 118748 237843 118718 237844 118748 237844 118756 237844 118756 237845 118748 237845 118750 237845 118756 237846 118750 237846 118780 237846 116414 237847 118757 237847 118758 237847 118758 237848 118757 237848 118759 237848 118758 237849 118759 237849 118739 237849 118739 237850 118759 237850 118752 237850 118739 237851 118752 237851 118737 237851 118737 237852 118752 237852 118760 237852 118737 237853 118760 237853 118736 237853 118736 237854 118760 237854 118754 237854 118736 237855 118754 237855 118733 237855 118733 237856 118754 237856 118761 237856 118733 237857 118761 237857 118732 237857 118732 237858 118761 237858 118762 237858 118732 237859 118762 237859 115957 237859 115957 237860 118762 237860 118724 237860 115957 237861 118724 237861 115952 237861 115952 237862 118724 237862 118710 237862 118765 237863 118763 237863 118818 237863 118765 237864 118818 237864 118764 237864 118764 237865 118818 237865 116416 237865 118764 237866 116416 237866 116414 237866 118763 237867 118765 237867 118820 237867 118820 237868 118765 237868 118766 237868 118820 237869 118766 237869 118828 237869 118828 237870 118766 237870 118767 237870 118828 237871 118767 237871 118827 237871 118827 237872 118767 237872 118716 237872 118827 237873 118716 237873 118826 237873 118716 237874 118715 237874 118826 237874 118826 237875 118715 237875 118768 237875 118826 237876 118768 237876 118769 237876 116450 237877 116448 237877 118793 237877 118770 237878 116450 237878 118778 237878 118778 237879 116450 237879 118793 237879 118778 237880 118793 237880 118771 237880 118771 237881 118793 237881 118795 237881 118771 237882 118795 237882 118781 237882 118781 237883 118795 237883 118772 237883 118781 237884 118772 237884 118773 237884 118773 237885 118772 237885 118775 237885 118773 237886 118775 237886 118774 237886 118774 237887 118775 237887 118798 237887 118774 237888 118798 237888 118783 237888 118783 237889 118798 237889 118799 237889 118783 237890 118799 237890 118776 237890 118776 237891 118799 237891 118801 237891 118776 237892 118801 237892 118785 237892 118785 237893 118801 237893 115842 237893 118777 237894 118770 237894 118779 237894 118779 237895 118770 237895 118778 237895 118779 237896 118778 237896 118749 237896 118749 237897 118778 237897 118771 237897 118749 237898 118771 237898 118750 237898 118750 237899 118771 237899 118781 237899 118750 237900 118781 237900 118780 237900 118780 237901 118781 237901 118773 237901 118780 237902 118773 237902 118721 237902 118721 237903 118773 237903 118774 237903 118721 237904 118774 237904 118782 237904 118782 237905 118774 237905 118783 237905 118782 237906 118783 237906 118714 237906 118714 237907 118783 237907 118776 237907 118714 237908 118776 237908 118784 237908 118784 237909 118776 237909 118785 237909 118786 237910 118802 237910 118800 237910 118807 237911 118790 237911 118841 237911 118787 237912 118811 237912 118812 237912 116444 237913 118788 237913 118791 237913 118791 237914 118788 237914 118806 237914 118791 237915 118806 237915 118808 237915 118839 237916 118790 237916 118789 237916 118789 237917 118790 237917 118807 237917 118789 237918 118807 237918 116442 237918 116444 237919 118791 237919 116445 237919 116445 237920 118791 237920 118817 237920 116445 237921 118817 237921 116446 237921 116448 237922 118792 237922 118793 237922 118793 237923 118792 237923 118794 237923 118793 237924 118794 237924 118795 237924 118795 237925 118794 237925 118816 237925 118795 237926 118816 237926 118772 237926 118772 237927 118816 237927 118796 237927 118772 237928 118796 237928 118775 237928 118775 237929 118796 237929 118797 237929 118775 237930 118797 237930 118798 237930 118798 237931 118797 237931 118815 237931 118798 237932 118815 237932 118799 237932 118799 237933 118815 237933 118800 237933 118799 237934 118800 237934 118801 237934 118801 237935 118800 237935 118802 237935 118801 237936 118802 237936 115842 237936 118838 237937 118787 237937 118810 237937 118810 237938 118787 237938 118812 237938 118810 237939 118812 237939 118803 237939 118803 237940 118812 237940 118813 237940 118803 237941 118813 237941 118809 237941 118809 237942 118813 237942 118814 237942 118809 237943 118814 237943 118808 237943 118808 237944 118814 237944 118804 237944 118808 237945 118804 237945 118791 237945 118791 237946 118804 237946 118805 237946 118791 237947 118805 237947 118817 237947 118788 237948 116442 237948 118806 237948 118806 237949 116442 237949 118807 237949 118806 237950 118807 237950 118808 237950 118808 237951 118807 237951 118841 237951 118808 237952 118841 237952 118809 237952 118809 237953 118841 237953 118842 237953 118809 237954 118842 237954 118803 237954 118803 237955 118842 237955 118843 237955 118803 237956 118843 237956 118810 237956 118810 237957 118843 237957 118845 237957 118810 237958 118845 237958 118838 237958 118811 237959 118786 237959 118812 237959 118812 237960 118786 237960 118800 237960 118812 237961 118800 237961 118813 237961 118813 237962 118800 237962 118815 237962 118813 237963 118815 237963 118814 237963 118814 237964 118815 237964 118797 237964 118814 237965 118797 237965 118804 237965 118804 237966 118797 237966 118796 237966 118804 237967 118796 237967 118805 237967 118805 237968 118796 237968 118816 237968 118805 237969 118816 237969 118817 237969 118817 237970 118816 237970 118794 237970 118817 237971 118794 237971 116446 237971 116446 237972 118794 237972 118792 237972 116431 237973 116416 237973 118830 237973 118830 237974 116416 237974 118818 237974 118830 237975 118818 237975 118819 237975 118819 237976 118818 237976 118763 237976 118819 237977 118763 237977 118820 237977 116440 237978 118821 237978 118822 237978 118822 237979 118821 237979 118831 237979 118822 237980 118831 237980 118835 237980 118835 237981 118831 237981 118823 237981 118835 237982 118823 237982 118824 237982 118769 237983 118825 237983 118826 237983 118826 237984 118825 237984 118832 237984 118826 237985 118832 237985 118827 237985 118827 237986 118832 237986 118834 237986 118827 237987 118834 237987 118828 237987 118828 237988 118834 237988 118829 237988 118828 237989 118829 237989 118820 237989 118820 237990 118829 237990 118824 237990 118820 237991 118824 237991 118819 237991 118819 237992 118824 237992 118823 237992 118819 237993 118823 237993 118830 237993 118830 237994 118823 237994 118831 237994 118830 237995 118831 237995 116431 237995 116431 237996 118831 237996 118821 237996 118825 237997 115944 237997 118832 237997 118832 237998 115944 237998 118833 237998 118832 237999 118833 237999 118834 237999 118834 238000 118833 238000 118852 238000 118834 238001 118852 238001 118829 238001 118829 238002 118852 238002 118850 238002 118829 238003 118850 238003 118824 238003 118824 238004 118850 238004 118849 238004 118824 238005 118849 238005 118835 238005 118835 238006 118849 238006 118836 238006 118835 238007 118836 238007 118822 238007 118822 238008 118836 238008 118846 238008 118822 238009 118846 238009 116440 238009 116440 238010 118846 238010 116439 238010 118837 238011 118838 238011 118845 238011 118839 238012 118840 238012 118790 238012 118790 238013 118840 238013 118875 238013 118790 238014 118875 238014 118841 238014 118841 238015 118875 238015 118876 238015 118841 238016 118876 238016 118842 238016 118842 238017 118876 238017 118877 238017 118842 238018 118877 238018 118843 238018 118843 238019 118877 238019 118878 238019 118843 238020 118878 238020 118845 238020 118845 238021 118878 238021 118844 238021 118845 238022 118844 238022 118837 238022 118837 238023 118844 238023 115838 238023 118865 238024 116435 238024 118854 238024 116438 238025 116439 238025 118846 238025 116437 238026 116438 238026 118847 238026 118847 238027 116438 238027 118846 238027 118847 238028 118846 238028 118855 238028 118855 238029 118846 238029 118836 238029 118855 238030 118836 238030 118848 238030 118848 238031 118836 238031 118849 238031 118848 238032 118849 238032 118851 238032 118851 238033 118849 238033 118850 238033 118851 238034 118850 238034 118857 238034 118857 238035 118850 238035 118852 238035 118857 238036 118852 238036 118859 238036 118859 238037 118852 238037 118833 238037 118859 238038 118833 238038 118853 238038 118853 238039 118833 238039 115944 238039 116435 238040 116437 238040 118854 238040 118854 238041 116437 238041 118847 238041 118854 238042 118847 238042 118864 238042 118864 238043 118847 238043 118855 238043 118864 238044 118855 238044 118863 238044 118863 238045 118855 238045 118848 238045 118863 238046 118848 238046 118861 238046 118861 238047 118848 238047 118851 238047 118861 238048 118851 238048 118856 238048 118856 238049 118851 238049 118857 238049 118856 238050 118857 238050 118858 238050 118858 238051 118857 238051 118859 238051 118858 238052 118859 238052 118860 238052 118860 238053 118859 238053 118853 238053 118860 238054 116285 238054 118858 238054 118858 238055 116285 238055 118874 238055 118858 238056 118874 238056 118856 238056 118856 238057 118874 238057 118872 238057 118856 238058 118872 238058 118861 238058 118861 238059 118872 238059 118862 238059 118861 238060 118862 238060 118863 238060 118863 238061 118862 238061 118870 238061 118863 238062 118870 238062 118864 238062 118864 238063 118870 238063 118868 238063 118864 238064 118868 238064 118854 238064 118854 238065 118868 238065 118866 238065 118854 238066 118866 238066 118865 238066 118865 238067 118866 238067 118867 238067 116432 238068 118867 238068 118896 238068 118896 238069 118867 238069 118866 238069 118896 238070 118866 238070 118895 238070 118895 238071 118866 238071 118868 238071 118895 238072 118868 238072 118869 238072 118869 238073 118868 238073 118870 238073 118869 238074 118870 238074 118893 238074 118893 238075 118870 238075 118862 238075 118893 238076 118862 238076 118871 238076 118871 238077 118862 238077 118872 238077 118871 238078 118872 238078 118873 238078 118873 238079 118872 238079 118874 238079 118873 238080 118874 238080 118891 238080 118891 238081 118874 238081 116285 238081 118840 238082 116404 238082 118875 238082 118875 238083 116404 238083 118911 238083 118875 238084 118911 238084 118876 238084 118876 238085 118911 238085 118910 238085 118876 238086 118910 238086 118877 238086 118877 238087 118910 238087 118909 238087 118877 238088 118909 238088 118878 238088 118878 238089 118909 238089 118879 238089 118878 238090 118879 238090 118844 238090 118844 238091 118879 238091 118880 238091 118844 238092 118880 238092 115838 238092 115838 238093 118880 238093 115839 238093 118892 238094 118890 238094 118881 238094 116419 238095 118882 238095 116420 238095 116420 238096 118882 238096 118885 238096 116425 238097 118883 238097 118920 238097 118920 238098 118883 238098 116420 238098 118920 238099 116420 238099 118884 238099 118884 238100 116420 238100 118885 238100 118884 238101 118885 238101 118887 238101 118882 238102 118886 238102 118885 238102 118885 238103 118886 238103 118894 238103 118885 238104 118894 238104 118887 238104 118887 238105 118894 238105 118888 238105 118887 238106 118888 238106 118922 238106 118922 238107 118888 238107 118889 238107 118922 238108 118889 238108 118923 238108 118923 238109 118889 238109 118881 238109 118923 238110 118881 238110 118924 238110 118924 238111 118881 238111 118890 238111 118924 238112 118890 238112 118925 238112 118891 238113 118892 238113 118873 238113 118873 238114 118892 238114 118881 238114 118873 238115 118881 238115 118871 238115 118871 238116 118881 238116 118889 238116 118871 238117 118889 238117 118893 238117 118893 238118 118889 238118 118888 238118 118893 238119 118888 238119 118869 238119 118869 238120 118888 238120 118894 238120 118869 238121 118894 238121 118895 238121 118895 238122 118894 238122 118886 238122 118895 238123 118886 238123 118896 238123 118896 238124 118886 238124 118882 238124 118896 238125 118882 238125 116432 238125 116432 238126 118882 238126 116419 238126 118912 238127 118914 238127 118902 238127 115841 238128 115840 238128 118905 238128 118897 238129 118898 238129 115841 238129 115841 238130 118905 238130 118897 238130 118897 238131 118905 238131 118906 238131 118897 238132 118906 238132 118899 238132 118903 238133 118917 238133 118908 238133 118908 238134 118917 238134 118899 238134 118908 238135 118899 238135 118907 238135 118907 238136 118899 238136 118906 238136 118902 238137 118900 238137 116429 238137 116421 238138 118912 238138 118901 238138 118901 238139 118912 238139 118902 238139 118901 238140 118902 238140 116428 238140 116428 238141 118902 238141 116429 238141 118914 238142 118903 238142 118902 238142 118902 238143 118903 238143 118908 238143 118902 238144 118908 238144 118900 238144 118900 238145 118908 238145 118904 238145 118900 238146 118904 238146 116429 238146 116429 238147 118904 238147 116426 238147 115840 238148 115839 238148 118905 238148 118905 238149 115839 238149 118880 238149 118905 238150 118880 238150 118906 238150 118906 238151 118880 238151 118879 238151 118906 238152 118879 238152 118907 238152 118907 238153 118879 238153 118909 238153 118907 238154 118909 238154 118908 238154 118908 238155 118909 238155 118910 238155 118908 238156 118910 238156 118904 238156 118904 238157 118910 238157 118911 238157 118904 238158 118911 238158 116426 238158 116426 238159 118911 238159 116404 238159 118921 238160 116423 238160 116425 238160 118912 238161 116421 238161 116423 238161 116423 238162 118921 238162 118912 238162 118912 238163 118921 238163 118913 238163 118912 238164 118913 238164 118914 238164 118914 238165 118913 238165 118903 238165 118903 238166 118913 238166 118915 238166 118903 238167 118915 238167 118917 238167 118917 238168 118915 238168 118916 238168 118917 238169 118916 238169 118899 238169 118916 238170 118918 238170 118899 238170 118899 238171 118918 238171 118919 238171 118899 238172 118919 238172 118897 238172 118897 238173 118919 238173 118926 238173 118897 238174 118926 238174 118898 238174 116425 238175 118920 238175 118921 238175 118921 238176 118920 238176 118884 238176 118921 238177 118884 238177 118913 238177 118913 238178 118884 238178 118887 238178 118913 238179 118887 238179 118915 238179 118915 238180 118887 238180 118922 238180 118915 238181 118922 238181 118916 238181 118916 238182 118922 238182 118923 238182 118916 238183 118923 238183 118918 238183 118918 238184 118923 238184 118924 238184 118918 238185 118924 238185 118919 238185 118919 238186 118924 238186 118925 238186 118919 238187 118925 238187 118926 238187 118927 238188 114110 238188 118928 238188 118928 238189 114110 238189 114109 238189 118928 238190 114109 238190 114107 238190 118967 238191 114105 238191 118927 238191 118927 238192 114105 238192 118929 238192 118927 238193 118929 238193 114110 238193 118931 238194 118930 238194 118967 238194 118967 238195 118930 238195 114106 238195 118967 238196 114106 238196 114105 238196 114084 238197 114104 238197 118969 238197 118969 238198 114104 238198 114103 238198 118969 238199 114103 238199 118931 238199 118931 238200 114103 238200 118932 238200 118931 238201 118932 238201 118930 238201 118953 238202 118961 238202 118933 238202 118933 238203 118961 238203 119005 238203 119005 238204 118961 238204 118934 238204 118934 238205 118961 238205 118935 238205 118934 238206 118935 238206 118990 238206 118990 238207 118935 238207 118977 238207 118977 238208 118935 238208 115511 238208 118977 238209 115511 238209 116144 238209 115513 238210 118936 238210 118962 238210 115513 238211 118962 238211 118937 238211 118937 238212 118962 238212 118939 238212 118937 238213 118939 238213 118938 238213 118938 238214 118939 238214 118946 238214 118938 238215 118946 238215 118940 238215 118940 238216 118946 238216 118947 238216 118940 238217 118947 238217 115606 238217 115606 238218 118947 238218 118942 238218 115606 238219 118942 238219 118941 238219 118941 238220 118942 238220 118944 238220 118941 238221 118944 238221 118943 238221 118976 238222 119017 238222 118944 238222 118944 238223 119017 238223 115603 238223 118944 238224 115603 238224 118943 238224 118974 238225 119003 238225 118975 238225 118964 238226 118963 238226 119003 238226 118963 238227 118928 238227 118945 238227 118945 238228 118928 238228 114107 238228 118945 238229 114107 238229 119000 238229 118962 238230 118960 238230 118939 238230 118939 238231 118960 238231 118971 238231 118939 238232 118971 238232 118946 238232 118946 238233 118971 238233 118972 238233 118946 238234 118972 238234 118947 238234 118947 238235 118972 238235 118948 238235 118947 238236 118948 238236 118942 238236 118942 238237 118948 238237 118949 238237 118942 238238 118949 238238 118944 238238 118944 238239 118949 238239 118950 238239 118944 238240 118950 238240 118976 238240 118955 238241 118951 238241 114101 238241 114101 238242 118951 238242 119006 238242 114101 238243 119006 238243 118979 238243 118954 238244 118952 238244 114100 238244 118933 238245 119006 238245 118953 238245 118953 238246 119006 238246 118951 238246 118953 238247 118951 238247 118954 238247 118954 238248 118951 238248 118955 238248 118954 238249 118955 238249 118952 238249 119003 238250 118974 238250 118964 238250 118964 238251 118974 238251 118956 238251 118964 238252 118956 238252 118965 238252 118965 238253 118956 238253 118973 238253 118965 238254 118973 238254 118966 238254 118966 238255 118973 238255 118957 238255 118966 238256 118957 238256 118968 238256 118968 238257 118957 238257 118970 238257 118968 238258 118970 238258 118958 238258 118954 238259 118959 238259 118953 238259 118953 238260 118959 238260 118960 238260 118953 238261 118960 238261 118961 238261 118961 238262 118960 238262 118962 238262 118961 238263 118962 238263 118935 238263 118935 238264 118962 238264 118936 238264 118935 238265 118936 238265 115511 238265 118963 238266 118964 238266 118928 238266 118928 238267 118964 238267 118965 238267 118928 238268 118965 238268 118927 238268 118927 238269 118965 238269 118966 238269 118927 238270 118966 238270 118967 238270 118967 238271 118966 238271 118968 238271 118967 238272 118968 238272 118931 238272 118931 238273 118968 238273 118958 238273 118931 238274 118958 238274 118969 238274 114100 238275 114084 238275 118954 238275 118954 238276 114084 238276 118969 238276 118954 238277 118969 238277 118959 238277 118959 238278 118969 238278 118958 238278 118959 238279 118958 238279 118960 238279 118960 238280 118958 238280 118970 238280 118960 238281 118970 238281 118971 238281 118971 238282 118970 238282 118957 238282 118971 238283 118957 238283 118972 238283 118972 238284 118957 238284 118973 238284 118972 238285 118973 238285 118948 238285 118948 238286 118973 238286 118956 238286 118948 238287 118956 238287 118949 238287 118949 238288 118956 238288 118974 238288 118949 238289 118974 238289 118950 238289 118950 238290 118974 238290 118975 238290 118950 238291 118975 238291 118976 238291 118977 238292 116144 238292 118991 238292 118978 238293 118979 238293 119006 238293 118978 238294 119006 238294 118980 238294 118982 238295 114095 238295 118981 238295 118982 238296 118981 238296 119007 238296 119007 238297 118981 238297 114099 238297 119007 238298 114099 238298 118980 238298 114095 238299 118982 238299 114096 238299 114096 238300 118982 238300 118983 238300 114096 238301 118983 238301 114097 238301 114097 238302 118983 238302 114092 238302 114092 238303 118983 238303 118984 238303 114092 238304 118984 238304 114093 238304 118985 238305 118987 238305 118986 238305 118986 238306 118987 238306 114089 238306 114087 238307 114086 238307 118988 238307 118988 238308 114086 238308 114085 238308 116138 238309 116137 238309 119015 238309 119015 238310 116137 238310 116136 238310 119015 238311 116136 238311 119016 238311 119015 238312 118997 238312 116138 238312 116138 238313 118997 238313 118996 238313 116138 238314 118996 238314 116139 238314 116139 238315 118996 238315 116141 238315 116141 238316 118996 238316 118994 238316 116141 238317 118994 238317 116142 238317 118994 238318 118989 238318 116142 238318 116142 238319 118989 238319 118992 238319 116142 238320 118992 238320 118991 238320 118991 238321 118992 238321 118990 238321 118991 238322 118990 238322 118977 238322 118934 238323 118990 238323 119008 238323 119008 238324 118990 238324 118992 238324 119008 238325 118992 238325 119009 238325 119009 238326 118992 238326 118989 238326 119009 238327 118989 238327 119010 238327 119010 238328 118989 238328 118994 238328 119010 238329 118994 238329 118993 238329 118993 238330 118994 238330 118996 238330 118993 238331 118996 238331 118995 238331 118995 238332 118996 238332 118997 238332 118995 238333 118997 238333 119013 238333 119013 238334 118997 238334 119015 238334 114085 238335 118985 238335 118988 238335 118988 238336 118985 238336 118986 238336 118988 238337 118986 238337 118999 238337 114088 238338 114087 238338 119001 238338 119001 238339 114087 238339 118988 238339 119001 238340 118988 238340 118998 238340 118998 238341 118988 238341 118999 238341 118998 238342 118999 238342 119002 238342 119000 238343 114088 238343 118945 238343 118945 238344 114088 238344 119001 238344 118945 238345 119001 238345 118963 238345 118963 238346 119001 238346 118998 238346 118963 238347 118998 238347 119003 238347 119003 238348 118998 238348 119002 238348 119003 238349 119002 238349 118975 238349 119017 238350 118976 238350 119014 238350 119014 238351 118976 238351 118975 238351 119014 238352 118975 238352 119004 238352 119004 238353 118975 238353 119002 238353 119004 238354 119002 238354 119012 238354 119012 238355 119002 238355 118999 238355 119012 238356 118999 238356 119011 238356 119011 238357 118999 238357 118986 238357 119011 238358 118986 238358 118984 238358 118984 238359 118986 238359 114089 238359 118984 238360 114089 238360 114093 238360 119006 238361 118933 238361 119008 238361 119008 238362 118933 238362 119005 238362 119008 238363 119005 238363 118934 238363 118980 238364 119006 238364 119007 238364 119007 238365 119006 238365 119008 238365 119007 238366 119008 238366 118982 238366 118982 238367 119008 238367 119009 238367 118982 238368 119009 238368 118983 238368 118983 238369 119009 238369 119010 238369 118983 238370 119010 238370 118984 238370 118984 238371 119010 238371 118993 238371 118984 238372 118993 238372 119011 238372 119011 238373 118993 238373 118995 238373 119011 238374 118995 238374 119012 238374 119012 238375 118995 238375 119013 238375 119012 238376 119013 238376 119004 238376 119004 238377 119013 238377 119015 238377 119004 238378 119015 238378 119014 238378 119014 238379 119015 238379 119016 238379 119014 238380 119016 238380 119017 238380 119097 238381 119096 238381 119047 238381 119020 238382 114914 238382 119075 238382 119039 238383 119019 238383 119018 238383 119018 238384 119019 238384 114975 238384 119018 238385 115102 238385 119039 238385 119039 238386 115102 238386 119020 238386 119039 238387 119020 238387 119021 238387 119021 238388 119020 238388 119075 238388 119021 238389 119075 238389 119022 238389 114975 238390 119019 238390 119023 238390 119023 238391 119019 238391 119041 238391 119023 238392 119041 238392 119024 238392 119024 238393 119041 238393 119026 238393 119024 238394 119026 238394 119025 238394 119025 238395 119026 238395 119062 238395 119025 238396 119062 238396 114974 238396 119077 238397 119027 238397 119061 238397 119061 238398 119027 238398 119028 238398 119061 238399 119028 238399 119060 238399 119121 238400 119029 238400 119030 238400 119030 238401 119029 238401 119077 238401 119097 238402 119047 238402 119049 238402 119031 238403 114042 238403 114044 238403 119031 238404 114044 238404 119043 238404 114042 238405 119031 238405 119032 238405 119032 238406 119031 238406 119058 238406 119032 238407 119058 238407 119033 238407 119033 238408 119058 238408 114039 238408 114039 238409 119058 238409 119034 238409 114039 238410 119034 238410 119035 238410 119071 238411 119036 238411 119072 238411 119037 238412 119115 238412 119038 238412 119038 238413 119115 238413 119114 238413 119022 238414 119037 238414 119021 238414 119021 238415 119037 238415 119038 238415 119021 238416 119038 238416 119039 238416 119039 238417 119038 238417 119067 238417 119039 238418 119067 238418 119019 238418 119019 238419 119067 238419 119040 238419 119019 238420 119040 238420 119041 238420 119041 238421 119040 238421 119065 238421 119041 238422 119065 238422 119026 238422 119026 238423 119065 238423 119063 238423 119026 238424 119063 238424 119062 238424 114044 238425 119042 238425 119043 238425 119043 238426 119042 238426 119044 238426 119043 238427 119044 238427 119045 238427 119045 238428 119044 238428 119046 238428 119046 238429 114045 238429 119045 238429 119045 238430 114045 238430 119048 238430 119045 238431 119048 238431 119047 238431 119047 238432 119048 238432 114046 238432 119047 238433 114046 238433 119049 238433 119050 238434 119051 238434 119030 238434 119030 238435 119051 238435 119096 238435 119030 238436 119096 238436 119121 238436 119073 238437 119035 238437 119052 238437 119052 238438 119035 238438 119034 238438 119052 238439 119034 238439 119070 238439 119077 238440 119061 238440 119030 238440 119030 238441 119061 238441 119053 238441 119030 238442 119053 238442 119050 238442 119050 238443 119053 238443 119064 238443 119050 238444 119064 238444 119059 238444 119059 238445 119064 238445 119055 238445 119059 238446 119055 238446 119054 238446 119054 238447 119055 238447 119066 238447 119054 238448 119066 238448 119056 238448 119056 238449 119066 238449 119068 238449 119056 238450 119068 238450 119057 238450 119057 238451 119068 238451 119069 238451 119057 238452 119069 238452 119070 238452 119070 238453 119034 238453 119057 238453 119057 238454 119034 238454 119058 238454 119057 238455 119058 238455 119056 238455 119056 238456 119058 238456 119031 238456 119056 238457 119031 238457 119054 238457 119054 238458 119031 238458 119043 238458 119054 238459 119043 238459 119059 238459 119059 238460 119043 238460 119045 238460 119059 238461 119045 238461 119050 238461 119050 238462 119045 238462 119047 238462 119050 238463 119047 238463 119051 238463 119051 238464 119047 238464 119096 238464 119060 238465 114974 238465 119061 238465 119061 238466 114974 238466 119062 238466 119061 238467 119062 238467 119053 238467 119053 238468 119062 238468 119063 238468 119053 238469 119063 238469 119064 238469 119064 238470 119063 238470 119065 238470 119064 238471 119065 238471 119055 238471 119055 238472 119065 238472 119040 238472 119055 238473 119040 238473 119066 238473 119066 238474 119040 238474 119067 238474 119066 238475 119067 238475 119068 238475 119068 238476 119067 238476 119038 238476 119068 238477 119038 238477 119069 238477 119069 238478 119038 238478 119114 238478 119069 238479 119114 238479 119070 238479 119070 238480 119114 238480 119071 238480 119070 238481 119071 238481 119052 238481 119052 238482 119071 238482 119072 238482 119052 238483 119072 238483 119073 238483 119113 238484 119100 238484 119112 238484 119029 238485 119121 238485 119074 238485 119075 238486 114914 238486 119076 238486 114883 238487 119105 238487 119104 238487 119027 238488 119077 238488 119108 238488 119027 238489 119108 238489 119078 238489 119078 238490 119108 238490 119107 238490 119078 238491 119107 238491 114882 238491 119105 238492 114883 238492 119107 238492 119107 238493 114883 238493 119079 238493 119107 238494 119079 238494 114882 238494 119081 238495 114886 238495 119080 238495 119080 238496 114886 238496 114885 238496 119080 238497 114885 238497 119104 238497 119104 238498 114885 238498 114884 238498 119104 238499 114884 238499 114883 238499 119080 238500 119102 238500 119081 238500 119081 238501 119102 238501 119099 238501 119081 238502 119099 238502 119076 238502 119076 238503 119099 238503 119022 238503 119076 238504 119022 238504 119075 238504 119111 238505 119082 238505 119117 238505 119117 238506 119082 238506 119036 238506 119083 238507 119084 238507 119085 238507 119085 238508 119084 238508 119086 238508 119085 238509 119086 238509 119111 238509 119111 238510 119086 238510 119087 238510 119111 238511 119087 238511 119082 238511 119088 238512 114051 238512 119109 238512 114051 238513 119088 238513 114050 238513 114050 238514 119088 238514 119090 238514 114050 238515 119090 238515 119089 238515 119089 238516 119090 238516 119091 238516 119091 238517 119090 238517 119092 238517 119091 238518 119092 238518 119093 238518 119098 238519 114048 238519 119120 238519 119120 238520 114048 238520 119094 238520 119120 238521 119094 238521 119092 238521 119092 238522 119094 238522 119095 238522 119092 238523 119095 238523 119093 238523 119120 238524 119096 238524 119097 238524 119120 238525 119097 238525 119098 238525 119098 238526 119097 238526 119049 238526 119037 238527 119022 238527 119100 238527 119100 238528 119022 238528 119099 238528 119100 238529 119099 238529 119112 238529 119112 238530 119099 238530 119102 238530 119112 238531 119102 238531 119101 238531 119101 238532 119102 238532 119080 238532 119101 238533 119080 238533 119103 238533 119103 238534 119080 238534 119104 238534 119103 238535 119104 238535 119119 238535 119119 238536 119104 238536 119105 238536 119119 238537 119105 238537 119106 238537 119106 238538 119105 238538 119107 238538 119106 238539 119107 238539 119074 238539 119074 238540 119107 238540 119108 238540 119074 238541 119108 238541 119029 238541 119029 238542 119108 238542 119077 238542 119109 238543 119083 238543 119088 238543 119088 238544 119083 238544 119085 238544 119088 238545 119085 238545 119110 238545 119110 238546 119085 238546 119111 238546 119110 238547 119111 238547 119118 238547 119118 238548 119111 238548 119117 238548 119071 238549 119114 238549 119116 238549 119112 238550 119116 238550 119113 238550 119113 238551 119116 238551 119114 238551 119113 238552 119114 238552 119100 238552 119100 238553 119114 238553 119115 238553 119100 238554 119115 238554 119037 238554 119036 238555 119071 238555 119117 238555 119117 238556 119071 238556 119116 238556 119117 238557 119116 238557 119118 238557 119118 238558 119116 238558 119112 238558 119118 238559 119112 238559 119110 238559 119110 238560 119112 238560 119101 238560 119110 238561 119101 238561 119088 238561 119088 238562 119101 238562 119103 238562 119088 238563 119103 238563 119090 238563 119090 238564 119103 238564 119119 238564 119090 238565 119119 238565 119092 238565 119092 238566 119119 238566 119106 238566 119092 238567 119106 238567 119120 238567 119120 238568 119106 238568 119074 238568 119120 238569 119074 238569 119096 238569 119096 238570 119074 238570 119121 238570 119153 238571 119149 238571 119141 238571 112305 238572 112326 238572 119147 238572 116106 238573 119161 238573 119122 238573 119122 238574 119161 238574 119163 238574 119122 238575 119163 238575 119123 238575 119123 238576 119163 238576 119131 238576 119123 238577 119131 238577 116119 238577 119133 238578 119125 238578 119124 238578 119124 238579 119125 238579 119126 238579 119124 238580 119126 238580 119127 238580 119127 238581 119126 238581 119128 238581 119127 238582 119128 238582 119130 238582 119130 238583 119128 238583 119129 238583 119130 238584 119129 238584 119131 238584 119131 238585 119129 238585 119132 238585 119131 238586 119132 238586 116119 238586 119124 238587 119166 238587 119133 238587 119133 238588 119166 238588 119134 238588 119133 238589 119134 238589 119135 238589 112305 238590 119147 238590 112318 238590 119148 238591 119146 238591 119136 238591 119136 238592 119146 238592 119137 238592 119157 238593 119159 238593 119145 238593 119145 238594 119159 238594 119160 238594 119145 238595 119160 238595 119138 238595 119146 238596 119138 238596 119137 238596 119137 238597 119138 238597 119160 238597 119137 238598 119160 238598 114118 238598 114118 238599 119160 238599 114119 238599 114118 238600 114123 238600 119137 238600 119137 238601 114123 238601 114111 238601 119137 238602 114111 238602 119136 238602 119136 238603 114111 238603 119139 238603 119136 238604 119139 238604 119140 238604 119155 238605 119141 238605 119143 238605 119143 238606 119141 238606 119142 238606 119143 238607 119142 238607 119144 238607 119144 238608 119142 238608 119157 238608 119144 238609 119157 238609 119164 238609 119164 238610 119157 238610 119145 238610 119164 238611 119145 238611 119165 238611 119165 238612 119145 238612 119138 238612 119165 238613 119138 238613 119167 238613 119167 238614 119138 238614 119146 238614 119167 238615 119146 238615 119147 238615 119147 238616 119146 238616 119148 238616 119147 238617 119148 238617 112318 238617 112318 238618 119148 238618 119136 238618 112318 238619 119136 238619 112317 238619 112317 238620 119136 238620 119140 238620 119149 238621 119150 238621 119141 238621 119141 238622 119150 238622 114114 238622 119141 238623 114114 238623 119142 238623 119142 238624 114114 238624 114113 238624 119142 238625 114113 238625 119157 238625 119157 238626 114113 238626 119151 238626 119157 238627 119151 238627 119152 238627 114134 238628 119153 238628 119154 238628 119154 238629 119153 238629 119141 238629 119154 238630 119141 238630 112290 238630 112290 238631 119141 238631 119155 238631 112290 238632 119155 238632 119156 238632 119156 238633 119155 238633 119162 238633 119152 238634 114115 238634 119157 238634 119157 238635 114115 238635 119158 238635 119157 238636 119158 238636 119159 238636 119159 238637 119158 238637 114121 238637 119159 238638 114121 238638 119160 238638 119160 238639 114121 238639 114120 238639 119160 238640 114120 238640 114119 238640 116106 238641 119162 238641 119161 238641 119161 238642 119162 238642 119155 238642 119161 238643 119155 238643 119163 238643 119163 238644 119155 238644 119143 238644 119163 238645 119143 238645 119131 238645 119131 238646 119143 238646 119144 238646 119131 238647 119144 238647 119130 238647 119130 238648 119144 238648 119164 238648 119130 238649 119164 238649 119127 238649 119127 238650 119164 238650 119165 238650 119127 238651 119165 238651 119124 238651 119124 238652 119165 238652 119167 238652 119124 238653 119167 238653 119166 238653 119166 238654 119167 238654 119147 238654 119166 238655 119147 238655 119134 238655 119134 238656 119147 238656 112326 238656 119197 238657 119189 238657 119199 238657 112262 238658 119211 238658 119209 238658 116099 238659 119204 238659 116098 238659 116098 238660 119204 238660 119168 238660 116098 238661 119168 238661 119169 238661 119169 238662 119168 238662 119170 238662 119169 238663 119170 238663 119171 238663 119177 238664 119172 238664 119208 238664 119208 238665 119172 238665 119173 238665 119208 238666 119173 238666 119174 238666 119174 238667 119173 238667 116104 238667 119174 238668 116104 238668 119175 238668 119175 238669 116104 238669 119176 238669 119175 238670 119176 238670 119170 238670 119170 238671 119176 238671 116102 238671 119170 238672 116102 238672 119171 238672 119208 238673 119210 238673 119177 238673 119177 238674 119210 238674 112251 238674 119177 238675 112251 238675 116082 238675 112262 238676 119209 238676 112273 238676 119187 238677 119186 238677 119178 238677 119178 238678 119186 238678 119180 238678 119193 238679 119203 238679 119182 238679 119182 238680 119203 238680 119179 238680 119182 238681 119179 238681 119184 238681 119186 238682 119184 238682 119180 238682 119180 238683 119184 238683 119179 238683 119180 238684 119179 238684 114064 238684 114064 238685 119179 238685 114057 238685 114064 238686 114062 238686 119180 238686 119180 238687 114062 238687 114061 238687 119180 238688 114061 238688 119178 238688 119178 238689 114061 238689 114070 238689 119178 238690 114070 238690 114069 238690 119205 238691 119199 238691 119206 238691 119206 238692 119199 238692 119192 238692 119206 238693 119192 238693 119207 238693 119207 238694 119192 238694 119193 238694 119207 238695 119193 238695 119181 238695 119181 238696 119193 238696 119182 238696 119181 238697 119182 238697 119183 238697 119183 238698 119182 238698 119184 238698 119183 238699 119184 238699 119185 238699 119185 238700 119184 238700 119186 238700 119185 238701 119186 238701 119209 238701 119209 238702 119186 238702 119187 238702 119209 238703 119187 238703 112273 238703 112273 238704 119187 238704 119178 238704 112273 238705 119178 238705 119188 238705 119188 238706 119178 238706 114069 238706 119189 238707 119190 238707 119199 238707 119199 238708 119190 238708 119191 238708 119199 238709 119191 238709 119192 238709 119192 238710 119191 238710 119194 238710 119192 238711 119194 238711 119193 238711 119193 238712 119194 238712 119195 238712 119193 238713 119195 238713 119200 238713 112268 238714 119197 238714 119196 238714 119196 238715 119197 238715 119199 238715 119196 238716 119199 238716 119198 238716 119198 238717 119199 238717 119205 238717 119198 238718 119205 238718 112250 238718 112250 238719 119205 238719 112288 238719 119200 238720 119201 238720 119193 238720 119193 238721 119201 238721 119202 238721 119193 238722 119202 238722 119203 238722 119203 238723 119202 238723 114060 238723 119203 238724 114060 238724 119179 238724 119179 238725 114060 238725 114058 238725 119179 238726 114058 238726 114057 238726 116099 238727 112288 238727 119204 238727 119204 238728 112288 238728 119205 238728 119204 238729 119205 238729 119168 238729 119168 238730 119205 238730 119206 238730 119168 238731 119206 238731 119170 238731 119170 238732 119206 238732 119207 238732 119170 238733 119207 238733 119175 238733 119175 238734 119207 238734 119181 238734 119175 238735 119181 238735 119174 238735 119174 238736 119181 238736 119183 238736 119174 238737 119183 238737 119208 238737 119208 238738 119183 238738 119185 238738 119208 238739 119185 238739 119210 238739 119210 238740 119185 238740 119209 238740 119210 238741 119209 238741 112251 238741 112251 238742 119209 238742 119211 238742 125080 238743 123388 238743 119212 238743 119212 238744 123388 238744 123352 238744 119212 238745 123352 238745 125174 238745 125174 238746 123352 238746 125165 238746 125165 238747 123352 238747 123351 238747 125165 238748 123351 238748 125167 238748 125167 238749 123351 238749 119213 238749 125167 238750 119213 238750 119218 238750 119214 238751 123639 238751 123368 238751 123368 238752 123639 238752 125113 238752 123368 238753 125113 238753 123370 238753 123370 238754 125113 238754 125112 238754 123370 238755 125112 238755 123371 238755 123371 238756 125112 238756 119215 238756 123371 238757 119215 238757 123362 238757 123362 238758 119215 238758 125142 238758 123362 238759 125142 238759 123372 238759 123372 238760 125142 238760 125143 238760 123372 238761 125143 238761 123300 238761 123300 238762 125143 238762 119216 238762 123300 238763 119216 238763 123305 238763 123305 238764 119216 238764 125149 238764 123305 238765 125149 238765 123306 238765 123306 238766 125149 238766 119217 238766 123306 238767 119217 238767 123308 238767 123308 238768 119217 238768 119218 238768 123308 238769 119218 238769 123349 238769 123349 238770 119218 238770 119213 238770 123479 238771 119253 238771 119250 238771 123512 238772 123565 238772 119263 238772 119256 238773 119254 238773 125073 238773 119249 238774 125018 238774 123475 238774 123475 238775 125018 238775 119219 238775 124911 238776 119220 238776 119240 238776 119221 238777 119258 238777 119259 238777 125080 238778 119222 238778 123388 238778 123388 238779 119222 238779 119221 238779 123422 238780 119263 238780 123421 238780 123421 238781 119263 238781 123565 238781 123421 238782 123565 238782 119232 238782 119231 238783 119223 238783 123464 238783 119224 238784 119226 238784 119225 238784 119225 238785 119226 238785 123465 238785 119225 238786 123465 238786 119232 238786 119223 238787 119231 238787 119229 238787 119214 238788 119227 238788 123639 238788 123639 238789 119227 238789 119229 238789 123639 238790 119229 238790 119228 238790 119228 238791 119229 238791 119231 238791 119228 238792 119231 238792 119230 238792 119230 238793 119231 238793 124953 238793 123464 238794 119224 238794 119231 238794 119231 238795 119224 238795 119225 238795 119231 238796 119225 238796 124953 238796 124953 238797 119225 238797 119235 238797 123565 238798 123562 238798 119232 238798 119232 238799 123562 238799 119233 238799 119232 238800 119233 238800 119225 238800 119225 238801 119233 238801 123596 238801 119225 238802 123596 238802 119235 238802 119235 238803 123596 238803 123602 238803 123602 238804 119234 238804 119235 238804 119235 238805 119234 238805 123599 238805 119235 238806 123599 238806 119237 238806 123599 238807 119236 238807 119237 238807 119237 238808 119236 238808 123580 238808 119237 238809 123580 238809 119238 238809 119238 238810 123580 238810 124911 238810 124911 238811 123580 238811 123576 238811 124911 238812 123576 238812 119220 238812 119242 238813 119239 238813 119240 238813 119240 238814 119239 238814 114136 238814 119240 238815 114136 238815 124911 238815 119241 238816 119248 238816 119242 238816 119242 238817 119248 238817 119243 238817 119242 238818 119243 238818 119239 238818 125018 238819 119244 238819 119219 238819 119219 238820 119244 238820 119245 238820 119219 238821 119245 238821 123552 238821 123552 238822 119245 238822 119246 238822 123552 238823 119246 238823 119247 238823 119247 238824 119246 238824 125051 238824 119247 238825 125051 238825 119241 238825 119241 238826 125051 238826 125050 238826 119241 238827 125050 238827 119248 238827 119249 238828 123475 238828 125081 238828 125081 238829 123475 238829 123477 238829 125081 238830 123477 238830 119251 238830 119251 238831 123477 238831 119250 238831 119251 238832 119250 238832 119252 238832 119252 238833 119250 238833 119253 238833 119252 238834 119253 238834 125073 238834 125073 238835 119253 238835 123479 238835 125073 238836 123479 238836 119256 238836 119254 238837 119256 238837 119255 238837 119255 238838 119256 238838 123513 238838 119255 238839 123513 238839 119257 238839 119221 238840 119222 238840 119258 238840 119258 238841 119222 238841 125070 238841 119258 238842 125070 238842 119259 238842 119259 238843 125070 238843 119261 238843 119259 238844 119261 238844 119260 238844 119260 238845 119261 238845 125071 238845 119260 238846 125071 238846 123428 238846 123428 238847 125071 238847 119262 238847 123428 238848 119262 238848 123422 238848 123422 238849 119262 238849 119255 238849 123422 238850 119255 238850 119263 238850 119263 238851 119255 238851 119257 238851 119263 238852 119257 238852 123512 238852 114583 238853 114581 238853 119264 238853 119264 238854 114581 238854 119266 238854 119264 238855 119266 238855 119265 238855 119265 238856 119266 238856 119288 238856 119265 238857 119288 238857 119267 238857 119267 238858 119288 238858 124985 238858 119272 238859 114584 238859 119268 238859 119268 238860 114584 238860 114583 238860 119268 238861 114583 238861 119269 238861 119269 238862 114583 238862 119264 238862 125039 238863 114580 238863 119270 238863 119270 238864 114580 238864 119271 238864 119270 238865 119271 238865 125001 238865 125001 238866 119271 238866 119273 238866 125001 238867 119273 238867 119272 238867 119272 238868 119273 238868 114585 238868 119272 238869 114585 238869 114584 238869 125039 238870 125040 238870 114580 238870 114580 238871 125040 238871 125014 238871 114580 238872 125014 238872 119274 238872 119274 238873 125014 238873 119277 238873 119274 238874 119277 238874 114578 238874 119275 238875 119293 238875 125029 238875 125029 238876 119293 238876 114578 238876 125029 238877 114578 238877 119276 238877 119276 238878 114578 238878 119277 238878 124954 238879 124985 238879 119288 238879 119285 238880 119286 238880 124937 238880 124937 238881 119286 238881 114593 238881 124937 238882 114593 238882 119278 238882 119278 238883 114593 238883 114572 238883 119278 238884 114572 238884 124945 238884 124945 238885 114572 238885 119279 238885 124945 238886 119279 238886 119280 238886 119281 238887 119282 238887 119283 238887 119283 238888 119282 238888 119284 238888 119283 238889 119284 238889 119285 238889 119285 238890 119284 238890 114588 238890 119285 238891 114588 238891 119286 238891 119290 238892 119287 238892 119281 238892 119281 238893 119287 238893 114854 238893 119281 238894 114854 238894 119282 238894 124954 238895 119288 238895 119289 238895 119289 238896 119288 238896 114771 238896 119289 238897 114771 238897 119290 238897 119290 238898 114771 238898 114573 238898 119290 238899 114573 238899 119287 238899 116231 238900 119291 238900 114592 238900 114592 238901 119291 238901 119292 238901 114592 238902 119292 238902 119280 238902 119280 238903 119292 238903 124965 238903 119280 238904 124965 238904 124945 238904 119293 238905 119275 238905 125067 238905 119293 238906 125067 238906 119294 238906 119294 238907 125067 238907 125084 238907 119294 238908 125084 238908 114649 238908 114649 238909 125084 238909 119295 238909 114649 238910 119295 238910 114576 238910 114576 238911 119295 238911 119297 238911 114576 238912 119297 238912 119296 238912 119296 238913 119297 238913 119298 238913 119296 238914 119298 238914 114577 238914 125162 238915 116219 238915 125068 238915 125068 238916 116219 238916 114574 238916 114574 238917 114656 238917 125068 238917 125068 238918 114656 238918 114654 238918 125068 238919 114654 238919 119298 238919 119298 238920 114654 238920 119299 238920 119298 238921 119299 238921 114577 238921 116222 238922 119308 238922 116224 238922 116224 238923 119308 238923 119301 238923 116224 238924 119301 238924 119300 238924 119300 238925 119301 238925 119302 238925 119300 238926 119302 238926 112247 238926 116219 238927 125162 238927 119304 238927 116219 238928 119304 238928 119303 238928 119303 238929 119304 238929 119305 238929 119303 238930 119305 238930 119306 238930 119306 238931 119305 238931 125170 238931 119306 238932 125170 238932 119307 238932 119307 238933 125170 238933 119308 238933 119307 238934 119308 238934 116222 238934 119378 238935 123331 238935 123330 238935 119378 238936 123330 238936 119377 238936 119377 238937 123330 238937 119309 238937 119377 238938 119309 238938 123325 238938 119310 238939 119375 238939 123337 238939 123337 238940 119375 238940 119377 238940 123337 238941 119377 238941 123327 238941 123327 238942 119377 238942 123325 238942 119310 238943 123336 238943 119375 238943 119375 238944 123336 238944 123335 238944 119375 238945 123335 238945 119312 238945 123381 238946 119329 238946 119311 238946 119311 238947 119329 238947 119312 238947 119311 238948 119312 238948 119313 238948 119313 238949 119312 238949 123335 238949 123331 238950 119378 238950 119314 238950 119314 238951 119378 238951 119315 238951 119314 238952 119315 238952 119316 238952 119316 238953 119315 238953 119373 238953 119316 238954 119373 238954 123304 238954 123407 238955 123406 238955 119317 238955 119317 238956 123406 238956 123404 238956 119317 238957 123404 238957 119368 238957 112243 238958 119369 238958 119318 238958 119318 238959 119369 238959 119368 238959 119318 238960 119368 238960 119319 238960 119319 238961 119368 238961 123404 238961 119320 238962 123407 238962 119317 238962 123407 238963 119320 238963 123444 238963 123444 238964 119320 238964 120995 238964 123444 238965 120995 238965 123443 238965 119321 238966 119383 238966 123451 238966 123451 238967 119383 238967 119322 238967 123451 238968 119322 238968 119323 238968 119323 238969 119322 238969 119384 238969 119323 238970 119384 238970 120990 238970 119324 238971 119326 238971 119325 238971 119325 238972 119326 238972 119327 238972 119325 238973 119327 238973 123395 238973 123395 238974 119327 238974 119328 238974 123395 238975 119328 238975 123381 238975 123381 238976 119328 238976 119329 238976 119330 238977 123619 238977 123575 238977 119330 238978 123575 238978 119331 238978 119331 238979 123575 238979 120972 238979 119331 238980 120972 238980 120971 238980 123582 238981 119355 238981 119332 238981 119332 238982 119355 238982 119333 238982 119332 238983 119333 238983 119334 238983 119334 238984 119333 238984 119335 238984 119334 238985 119335 238985 123578 238985 123578 238986 119335 238986 119363 238986 123578 238987 119363 238987 119336 238987 119336 238988 119363 238988 119349 238988 119359 238989 119358 238989 119337 238989 119337 238990 119358 238990 119346 238990 119356 238991 119364 238991 119338 238991 119338 238992 123541 238992 119356 238992 119356 238993 123541 238993 123546 238993 119356 238994 123546 238994 119341 238994 119341 238995 123546 238995 119339 238995 119339 238996 119340 238996 119341 238996 119341 238997 119340 238997 119344 238997 119341 238998 119344 238998 119342 238998 119342 238999 119344 238999 119343 238999 119344 239000 123543 239000 119343 239000 119343 239001 123543 239001 119345 239001 119343 239002 119345 239002 119358 239002 119358 239003 119345 239003 123561 239003 119358 239004 123561 239004 119346 239004 119347 239005 119336 239005 119349 239005 119359 239006 119337 239006 119349 239006 119349 239007 119337 239007 119348 239007 119349 239008 119348 239008 119347 239008 119361 239009 120973 239009 119362 239009 119362 239010 120973 239010 123486 239010 119362 239011 123486 239011 119364 239011 119364 239012 123486 239012 119338 239012 119361 239013 119350 239013 120973 239013 120973 239014 119350 239014 119367 239014 120973 239015 119367 239015 119351 239015 112190 239016 119330 239016 119354 239016 112196 239017 119352 239017 119354 239017 119354 239018 119352 239018 119353 239018 119353 239019 112193 239019 119354 239019 119354 239020 112193 239020 112194 239020 119354 239021 112194 239021 112190 239021 119363 239022 119335 239022 119360 239022 119360 239023 119335 239023 119333 239023 119360 239024 119333 239024 119354 239024 119354 239025 119333 239025 119355 239025 119354 239026 119355 239026 112196 239026 119341 239027 119363 239027 119356 239027 119356 239028 119363 239028 119364 239028 119342 239029 119343 239029 119357 239029 119357 239030 119343 239030 119358 239030 119341 239031 119342 239031 119363 239031 119363 239032 119342 239032 119357 239032 119363 239033 119357 239033 119349 239033 119349 239034 119357 239034 119358 239034 119349 239035 119358 239035 119359 239035 119367 239036 119350 239036 119360 239036 119360 239037 119350 239037 119361 239037 119360 239038 119361 239038 119363 239038 119363 239039 119361 239039 119362 239039 119363 239040 119362 239040 119364 239040 120968 239041 119365 239041 120971 239041 120971 239042 119365 239042 119354 239042 120971 239043 119354 239043 119331 239043 119331 239044 119354 239044 119330 239044 120979 239045 120978 239045 119366 239045 120968 239046 120979 239046 119365 239046 119365 239047 120979 239047 119366 239047 119365 239048 119366 239048 119354 239048 119354 239049 119366 239049 120975 239049 119354 239050 120975 239050 119360 239050 119360 239051 120975 239051 119351 239051 119360 239052 119351 239052 119367 239052 119368 239053 119369 239053 119370 239053 119370 239054 119369 239054 112240 239054 112240 239055 119371 239055 119370 239055 119370 239056 119371 239056 112237 239056 119370 239057 112237 239057 112236 239057 119315 239058 119372 239058 119373 239058 119373 239059 119372 239059 119370 239059 119373 239060 119370 239060 119374 239060 119374 239061 119370 239061 112236 239061 119376 239062 119329 239062 119328 239062 119312 239063 119329 239063 119375 239063 119375 239064 119329 239064 119376 239064 119375 239065 119376 239065 119377 239065 119377 239066 119376 239066 119378 239066 119378 239067 119376 239067 119328 239067 119378 239068 119328 239068 119315 239068 119315 239069 119328 239069 119379 239069 119315 239070 119379 239070 119372 239070 119379 239071 119328 239071 119380 239071 119380 239072 119328 239072 119327 239072 119380 239073 119327 239073 119390 239073 119390 239074 119327 239074 119326 239074 119381 239075 119368 239075 119370 239075 119368 239076 119381 239076 119317 239076 119317 239077 119381 239077 119382 239077 119317 239078 119382 239078 119320 239078 119383 239079 119393 239079 119322 239079 119322 239080 119393 239080 119388 239080 119322 239081 119388 239081 119384 239081 119383 239082 119385 239082 119393 239082 119393 239083 119385 239083 120991 239083 119393 239084 120991 239084 120992 239084 120992 239085 120993 239085 119393 239085 119393 239086 120993 239086 119386 239086 119393 239087 119386 239087 120995 239087 120983 239088 120981 239088 119389 239088 120981 239089 119387 239089 119389 239089 119389 239090 119387 239090 120989 239090 119389 239091 120989 239091 120990 239091 119393 239092 119391 239092 119388 239092 119388 239093 119391 239093 119389 239093 119388 239094 119389 239094 119384 239094 119384 239095 119389 239095 120990 239095 119372 239096 119379 239096 119394 239096 119394 239097 119379 239097 119380 239097 119394 239098 119380 239098 119391 239098 119391 239099 119380 239099 119390 239099 119391 239100 119390 239100 119389 239100 119389 239101 119390 239101 119326 239101 119389 239102 119326 239102 120983 239102 120983 239103 119326 239103 119392 239103 120995 239104 119320 239104 119393 239104 119393 239105 119320 239105 119382 239105 119393 239106 119382 239106 119391 239106 119391 239107 119382 239107 119381 239107 119391 239108 119381 239108 119394 239108 119394 239109 119381 239109 119370 239109 119394 239110 119370 239110 119372 239110 119395 239111 123191 239111 119410 239111 123633 239112 119396 239112 123637 239112 123637 239113 119396 239113 119397 239113 123637 239114 119397 239114 123249 239114 123249 239115 119398 239115 123637 239115 123637 239116 119398 239116 123262 239116 123637 239117 123262 239117 123264 239117 123267 239118 123285 239118 124899 239118 124899 239119 123285 239119 119399 239119 119399 239120 123285 239120 119400 239120 119399 239121 119400 239121 123633 239121 123633 239122 119400 239122 119401 239122 123633 239123 119401 239123 119396 239123 124899 239124 119402 239124 123267 239124 123267 239125 119402 239125 119403 239125 123267 239126 119403 239126 123265 239126 123279 239127 123280 239127 119404 239127 119404 239128 123280 239128 123265 239128 119404 239129 123265 239129 124855 239129 124855 239130 123265 239130 119403 239130 119405 239131 119406 239131 123225 239131 119413 239132 119407 239132 119404 239132 119404 239133 119407 239133 119408 239133 119404 239134 119408 239134 123279 239134 119406 239135 122953 239135 119411 239135 119422 239136 119436 239136 119410 239136 119410 239137 119436 239137 119409 239137 119410 239138 119409 239138 119395 239138 119423 239139 119422 239139 122927 239139 122927 239140 119422 239140 119410 239140 122927 239141 119410 239141 119411 239141 119411 239142 119410 239142 123191 239142 119411 239143 123191 239143 119406 239143 122973 239144 122971 239144 119412 239144 119412 239145 122971 239145 119405 239145 119412 239146 119405 239146 119413 239146 119413 239147 119405 239147 123225 239147 119413 239148 123225 239148 119407 239148 122971 239149 122963 239149 119405 239149 119405 239150 122963 239150 119414 239150 119405 239151 119414 239151 119406 239151 119406 239152 119414 239152 119415 239152 119406 239153 119415 239153 122953 239153 119412 239154 119416 239154 122973 239154 122973 239155 119416 239155 119417 239155 122973 239156 119417 239156 122979 239156 119460 239157 119418 239157 124873 239157 124873 239158 119418 239158 119419 239158 124873 239159 119419 239159 119417 239159 119417 239160 119419 239160 119420 239160 119417 239161 119420 239161 122979 239161 119421 239162 119409 239162 119436 239162 122854 239163 122820 239163 124667 239163 119422 239164 119423 239164 119424 239164 119424 239165 119423 239165 122909 239165 119424 239166 122909 239166 119425 239166 119425 239167 122909 239167 119426 239167 119425 239168 119426 239168 122843 239168 119422 239169 119424 239169 119436 239169 119436 239170 119424 239170 122866 239170 119436 239171 122866 239171 122867 239171 122867 239172 122868 239172 119436 239172 119436 239173 122868 239173 119427 239173 119436 239174 119427 239174 124667 239174 124667 239175 119427 239175 122853 239175 124667 239176 122853 239176 122854 239176 122820 239177 122823 239177 124667 239177 124667 239178 122823 239178 122822 239178 124667 239179 122822 239179 119428 239179 122822 239180 122821 239180 119428 239180 119428 239181 122821 239181 119429 239181 119428 239182 119429 239182 119430 239182 119430 239183 119429 239183 122815 239183 119430 239184 122815 239184 119432 239184 119432 239185 122815 239185 119431 239185 119432 239186 119431 239186 124682 239186 119426 239187 122888 239187 122843 239187 122843 239188 122888 239188 122889 239188 122843 239189 122889 239189 119433 239189 122889 239190 122895 239190 119433 239190 119433 239191 122895 239191 122893 239191 119433 239192 122893 239192 122850 239192 124665 239193 119457 239193 124666 239193 124666 239194 119457 239194 123071 239194 124666 239195 123071 239195 124667 239195 124667 239196 123071 239196 123084 239196 123084 239197 123083 239197 124667 239197 124667 239198 123083 239198 119434 239198 124667 239199 119434 239199 119436 239199 119436 239200 119434 239200 123043 239200 119436 239201 123043 239201 119435 239201 119435 239202 123006 239202 119436 239202 119436 239203 123006 239203 123004 239203 119436 239204 123004 239204 119421 239204 119421 239205 123004 239205 123003 239205 119421 239206 123003 239206 119437 239206 119437 239207 123003 239207 123025 239207 119437 239208 123025 239208 119438 239208 123025 239209 123041 239209 119438 239209 119438 239210 123041 239210 119440 239210 119438 239211 119440 239211 119441 239211 119446 239212 119439 239212 123637 239212 119440 239213 123034 239213 119441 239213 119441 239214 123034 239214 119442 239214 119441 239215 119442 239215 119443 239215 119443 239216 119442 239216 119445 239216 119443 239217 119445 239217 119444 239217 119444 239218 119445 239218 119446 239218 119444 239219 119446 239219 123264 239219 123264 239220 119446 239220 123637 239220 119439 239221 119447 239221 123637 239221 123637 239222 119447 239222 123096 239222 123637 239223 123096 239223 123635 239223 123635 239224 123096 239224 123097 239224 123635 239225 123097 239225 124726 239225 123097 239226 123136 239226 124726 239226 124726 239227 123136 239227 123137 239227 124726 239228 123137 239228 119449 239228 123137 239229 119448 239229 119449 239229 119449 239230 119448 239230 123120 239230 119449 239231 123120 239231 119450 239231 119450 239232 123120 239232 119451 239232 119450 239233 119451 239233 124662 239233 124662 239234 119451 239234 119452 239234 124662 239235 119452 239235 119453 239235 119453 239236 119452 239236 119454 239236 119453 239237 119454 239237 119455 239237 119455 239238 119454 239238 119456 239238 119455 239239 119456 239239 124665 239239 124665 239240 119456 239240 123114 239240 124665 239241 123114 239241 119457 239241 119463 239242 122932 239242 119458 239242 119458 239243 122932 239243 119459 239243 119459 239244 122932 239244 122931 239244 119459 239245 122931 239245 119462 239245 119418 239246 119460 239246 119461 239246 119461 239247 119460 239247 119462 239247 119461 239248 119462 239248 122942 239248 122942 239249 119462 239249 122931 239249 119458 239250 124802 239250 119463 239250 119463 239251 124802 239251 119464 239251 119463 239252 119464 239252 122918 239252 122918 239253 119464 239253 124783 239253 122918 239254 124783 239254 122916 239254 122916 239255 124783 239255 119465 239255 122916 239256 119465 239256 119466 239256 119466 239257 119465 239257 119467 239257 124757 239258 119472 239258 119465 239258 119465 239259 119472 239259 119468 239259 119465 239260 119468 239260 122805 239260 124682 239261 119431 239261 124681 239261 124681 239262 119431 239262 122799 239262 124681 239263 122799 239263 119469 239263 119469 239264 122799 239264 122778 239264 119469 239265 122778 239265 119470 239265 119470 239266 122778 239266 119471 239266 119470 239267 119471 239267 124757 239267 124757 239268 119471 239268 122781 239268 124757 239269 122781 239269 119472 239269 122850 239270 122893 239270 122801 239270 122801 239271 122893 239271 119473 239271 122801 239272 119473 239272 122805 239272 122805 239273 119473 239273 119474 239273 122805 239274 119474 239274 119465 239274 119465 239275 119474 239275 119467 239275 124691 239276 119475 239276 124747 239276 124747 239277 119475 239277 119513 239277 124747 239278 119513 239278 124755 239278 124755 239279 119513 239279 119476 239279 119477 239280 119478 239280 124691 239280 124691 239281 119478 239281 119479 239281 124691 239282 119479 239282 119475 239282 119477 239283 124694 239283 119478 239283 119478 239284 124694 239284 119480 239284 119478 239285 119480 239285 119481 239285 119481 239286 119480 239286 119482 239286 119481 239287 119482 239287 114555 239287 114555 239288 119482 239288 119483 239288 119483 239289 124690 239289 114555 239289 114555 239290 124690 239290 124689 239290 114555 239291 124689 239291 119485 239291 119485 239292 124689 239292 119484 239292 119485 239293 119484 239293 119486 239293 119486 239294 119484 239294 124651 239294 119486 239295 124651 239295 119505 239295 116308 239296 119487 239296 116211 239296 116211 239297 119487 239297 119488 239297 116211 239298 119488 239298 116214 239298 116214 239299 119488 239299 119489 239299 116214 239300 119489 239300 124780 239300 119507 239301 119506 239301 119490 239301 119507 239302 119490 239302 119491 239302 119491 239303 119490 239303 124730 239303 119491 239304 124730 239304 119492 239304 119492 239305 124730 239305 119487 239305 119492 239306 119487 239306 116308 239306 116214 239307 124780 239307 119494 239307 119494 239308 124780 239308 119493 239308 119493 239309 124796 239309 119494 239309 119494 239310 124796 239310 119495 239310 119494 239311 119495 239311 116216 239311 116216 239312 119495 239312 124810 239312 116216 239313 124810 239313 116218 239313 119496 239314 116220 239314 119497 239314 119497 239315 116220 239315 116218 239315 119497 239316 116218 239316 119498 239316 119498 239317 116218 239317 124810 239317 124654 239318 119499 239318 119500 239318 119500 239319 119499 239319 114529 239319 119500 239320 114529 239320 119501 239320 114529 239321 114528 239321 119501 239321 119501 239322 114528 239322 114526 239322 119501 239323 114526 239323 119502 239323 119502 239324 114526 239324 119503 239324 119502 239325 119503 239325 119504 239325 119504 239326 119503 239326 119505 239326 119504 239327 119505 239327 124651 239327 119506 239328 119507 239328 119508 239328 119508 239329 119507 239329 114522 239329 119508 239330 114522 239330 124658 239330 124658 239331 114522 239331 119509 239331 124658 239332 119509 239332 124656 239332 124656 239333 119509 239333 119510 239333 124656 239334 119510 239334 119511 239334 119511 239335 119510 239335 119512 239335 119511 239336 119512 239336 124654 239336 124654 239337 119512 239337 114525 239337 124654 239338 114525 239338 119499 239338 119476 239339 119513 239339 119514 239339 119514 239340 119513 239340 114530 239340 119514 239341 114530 239341 119515 239341 112232 239342 119516 239342 119517 239342 119517 239343 119516 239343 114636 239343 119519 239344 119515 239344 114530 239344 114636 239345 119516 239345 114633 239345 114633 239346 119516 239346 119518 239346 114633 239347 119518 239347 114530 239347 114530 239348 119518 239348 124790 239348 114530 239349 124790 239349 119519 239349 124852 239350 112234 239350 119523 239350 119520 239351 119521 239351 114648 239351 114648 239352 119521 239352 114647 239352 114647 239353 119521 239353 124850 239353 114647 239354 124850 239354 119522 239354 119522 239355 124850 239355 124848 239355 119522 239356 124848 239356 119523 239356 119523 239357 124848 239357 119524 239357 119523 239358 119524 239358 124852 239358 114648 239359 119525 239359 119520 239359 119520 239360 119525 239360 114645 239360 119520 239361 114645 239361 124847 239361 124847 239362 114645 239362 114646 239362 124847 239363 114646 239363 119526 239363 119526 239364 114646 239364 114653 239364 119526 239365 114653 239365 124860 239365 124860 239366 114653 239366 119527 239366 124860 239367 119527 239367 124821 239367 124821 239368 119527 239368 116220 239368 124821 239369 116220 239369 119496 239369 122857 239370 119658 239370 122824 239370 122824 239371 119658 239371 119528 239371 122824 239372 119528 239372 120929 239372 119529 239373 122782 239373 119530 239373 119530 239374 122782 239374 122786 239374 119530 239375 122786 239375 119531 239375 119531 239376 122786 239376 122787 239376 119531 239377 122787 239377 119655 239377 119655 239378 122787 239378 119533 239378 122782 239379 119529 239379 119532 239379 119532 239380 119529 239380 120719 239380 119655 239381 119533 239381 119665 239381 119665 239382 119533 239382 119534 239382 119665 239383 119534 239383 119535 239383 119535 239384 119534 239384 122812 239384 119535 239385 122812 239385 119537 239385 119537 239386 122812 239386 119536 239386 119537 239387 119536 239387 119538 239387 119662 239388 120960 239388 119542 239388 119542 239389 120960 239389 119541 239389 122804 239390 119539 239390 122846 239390 122846 239391 119539 239391 119657 239391 122846 239392 119657 239392 119541 239392 119541 239393 119657 239393 119540 239393 119541 239394 119540 239394 119542 239394 120964 239395 119543 239395 120954 239395 120954 239396 119543 239396 119544 239396 120954 239397 119544 239397 122961 239397 120720 239398 119604 239398 119545 239398 119545 239399 119604 239399 119546 239399 119545 239400 119546 239400 119557 239400 122934 239401 119547 239401 119598 239401 119598 239402 119547 239402 119548 239402 119547 239403 119549 239403 119548 239403 119548 239404 119549 239404 122940 239404 119548 239405 122940 239405 119599 239405 119599 239406 122940 239406 119550 239406 119599 239407 119550 239407 119552 239407 119550 239408 119551 239408 119552 239408 119552 239409 119551 239409 122938 239409 119552 239410 122938 239410 119554 239410 119554 239411 122938 239411 119553 239411 119554 239412 119553 239412 119600 239412 119600 239413 119553 239413 119555 239413 119600 239414 119555 239414 119556 239414 119556 239415 119555 239415 119557 239415 119556 239416 119557 239416 119546 239416 119610 239417 119558 239417 119559 239417 119559 239418 119558 239418 119560 239418 119559 239419 119560 239419 119561 239419 119561 239420 119560 239420 122983 239420 119561 239421 122983 239421 119562 239421 119562 239422 122983 239422 119563 239422 119562 239423 119563 239423 119598 239423 119598 239424 119563 239424 122958 239424 119598 239425 122958 239425 122934 239425 119597 239426 120726 239426 119564 239426 119564 239427 120726 239427 119565 239427 119564 239428 119565 239428 119621 239428 119621 239429 119565 239429 119566 239429 119621 239430 119566 239430 119615 239430 119615 239431 119566 239431 119616 239431 119616 239432 119566 239432 119618 239432 119618 239433 119566 239433 122915 239433 119618 239434 122915 239434 120962 239434 119625 239435 119575 239435 119567 239435 119567 239436 119575 239436 123095 239436 119567 239437 123095 239437 120701 239437 120701 239438 123095 239438 119568 239438 119624 239439 119573 239439 123127 239439 123127 239440 119573 239440 119569 239440 119627 239441 119626 239441 119570 239441 119570 239442 123133 239442 119627 239442 119627 239443 123133 239443 119571 239443 119627 239444 119571 239444 119572 239444 119572 239445 119571 239445 123121 239445 123121 239446 123124 239446 119572 239446 119572 239447 123124 239447 123123 239447 119572 239448 123123 239448 119573 239448 119573 239449 123123 239449 119574 239449 119573 239450 119574 239450 119569 239450 123132 239451 119575 239451 119625 239451 119624 239452 123127 239452 119625 239452 119625 239453 123127 239453 123131 239453 119625 239454 123131 239454 123132 239454 120922 239455 119576 239455 119578 239455 119578 239456 119576 239456 119577 239456 119578 239457 119577 239457 119623 239457 119623 239458 119577 239458 119579 239458 119579 239459 119577 239459 123102 239459 119579 239460 123102 239460 119626 239460 119626 239461 123102 239461 123101 239461 119626 239462 123101 239462 119570 239462 119580 239463 119581 239463 119629 239463 119629 239464 119581 239464 119582 239464 119629 239465 119582 239465 120911 239465 120930 239466 119583 239466 119584 239466 119584 239467 119583 239467 119585 239467 119584 239468 119585 239468 119588 239468 119586 239469 123029 239469 119635 239469 119635 239470 123029 239470 123035 239470 119635 239471 123035 239471 119587 239471 119587 239472 123035 239472 119588 239472 119587 239473 119588 239473 119622 239473 119622 239474 119588 239474 119585 239474 120714 239475 123253 239475 119589 239475 119589 239476 123253 239476 123289 239476 119589 239477 123289 239477 119649 239477 120944 239478 120946 239478 119650 239478 119650 239479 120946 239479 123181 239479 119650 239480 123181 239480 119590 239480 119590 239481 123181 239481 119651 239481 119651 239482 123181 239482 119591 239482 119651 239483 119591 239483 119653 239483 119653 239484 119591 239484 123187 239484 119653 239485 123187 239485 119592 239485 120937 239486 119640 239486 123196 239486 123196 239487 119640 239487 119593 239487 123196 239488 119593 239488 120953 239488 119646 239489 123281 239489 123272 239489 119646 239490 123272 239490 119594 239490 119594 239491 123272 239491 123276 239491 119594 239492 123276 239492 119595 239492 119595 239493 123276 239493 123209 239493 119595 239494 123209 239494 119596 239494 119596 239495 123209 239495 119644 239495 119597 239496 119564 239496 119601 239496 119601 239497 119562 239497 119598 239497 119598 239498 119548 239498 119601 239498 119601 239499 119548 239499 119599 239499 119601 239500 119599 239500 119552 239500 119552 239501 119554 239501 119601 239501 119601 239502 119554 239502 119600 239502 119601 239503 119600 239503 119556 239503 119597 239504 119601 239504 119602 239504 120722 239505 120723 239505 119603 239505 119556 239506 119546 239506 119601 239506 119601 239507 119546 239507 119604 239507 119601 239508 119604 239508 120722 239508 120722 239509 119603 239509 119601 239509 119601 239510 119603 239510 119605 239510 119601 239511 119605 239511 119602 239511 119561 239512 119617 239512 119559 239512 119617 239513 119561 239513 119621 239513 119618 239514 120962 239514 119609 239514 119606 239515 119607 239515 119609 239515 119609 239516 119607 239516 120964 239516 119609 239517 120964 239517 119618 239517 120962 239518 119608 239518 119609 239518 119609 239519 119608 239519 120966 239519 119609 239520 120966 239520 119606 239520 119610 239521 119619 239521 119611 239521 119611 239522 119619 239522 119614 239522 119620 239523 119612 239523 119619 239523 119619 239524 119612 239524 119613 239524 119619 239525 119613 239525 119614 239525 119621 239526 119615 239526 119617 239526 119617 239527 119615 239527 119616 239527 119617 239528 119616 239528 119559 239528 119559 239529 119616 239529 119618 239529 119559 239530 119618 239530 119610 239530 119610 239531 119618 239531 120964 239531 119610 239532 120964 239532 119619 239532 119619 239533 120964 239533 120954 239533 119619 239534 120954 239534 119620 239534 119562 239535 119601 239535 119561 239535 119561 239536 119601 239536 119564 239536 119561 239537 119564 239537 119621 239537 119622 239538 119585 239538 119633 239538 119623 239539 119579 239539 119634 239539 119634 239540 119579 239540 119626 239540 119573 239541 119624 239541 119625 239541 119626 239542 119627 239542 119634 239542 119634 239543 119627 239543 119572 239543 119634 239544 119572 239544 119573 239544 120922 239545 119578 239545 119633 239545 119633 239546 119578 239546 119623 239546 120913 239547 120915 239547 120911 239547 120911 239548 120915 239548 119628 239548 120911 239549 119628 239549 119629 239549 119629 239550 119628 239550 120917 239550 119629 239551 120917 239551 120921 239551 119631 239552 120932 239552 119630 239552 120921 239553 120922 239553 119629 239553 119629 239554 120922 239554 119633 239554 119629 239555 119633 239555 119580 239555 119580 239556 119633 239556 119631 239556 119580 239557 119631 239557 119632 239557 119632 239558 119631 239558 119630 239558 119585 239559 119583 239559 119633 239559 119633 239560 119583 239560 120930 239560 119633 239561 120930 239561 119631 239561 119631 239562 120930 239562 120933 239562 119631 239563 120933 239563 120932 239563 119623 239564 119634 239564 119633 239564 119633 239565 119634 239565 119587 239565 119633 239566 119587 239566 119622 239566 119573 239567 119625 239567 119634 239567 119634 239568 119625 239568 119567 239568 119634 239569 119567 239569 120701 239569 120706 239570 120709 239570 119634 239570 119634 239571 120709 239571 119635 239571 119634 239572 119635 239572 119587 239572 120701 239573 120703 239573 119634 239573 119634 239574 120703 239574 119636 239574 119634 239575 119636 239575 120706 239575 119645 239576 119637 239576 120944 239576 119639 239577 120949 239577 120951 239577 120949 239578 119639 239578 119638 239578 120951 239579 120952 239579 119639 239579 119639 239580 120952 239580 119593 239580 119639 239581 119593 239581 119637 239581 119637 239582 119593 239582 119640 239582 119640 239583 119641 239583 119637 239583 119637 239584 119641 239584 119642 239584 119637 239585 119642 239585 119643 239585 119643 239586 120941 239586 119637 239586 119637 239587 120941 239587 120942 239587 119637 239588 120942 239588 120944 239588 119638 239589 119639 239589 119644 239589 119644 239590 119639 239590 119637 239590 119644 239591 119637 239591 119596 239591 119596 239592 119637 239592 119645 239592 119596 239593 119645 239593 119595 239593 112224 239594 112223 239594 119646 239594 112226 239595 112224 239595 119652 239595 119652 239596 112224 239596 119646 239596 119652 239597 119646 239597 119645 239597 119645 239598 119646 239598 119594 239598 119645 239599 119594 239599 119595 239599 120710 239600 119647 239600 120714 239600 119653 239601 120711 239601 119652 239601 119652 239602 120711 239602 119648 239602 119652 239603 119648 239603 120710 239603 120710 239604 120714 239604 119652 239604 119652 239605 120714 239605 119589 239605 119652 239606 119589 239606 119649 239606 119649 239607 112228 239607 119652 239607 119652 239608 112228 239608 112227 239608 119652 239609 112227 239609 112226 239609 120944 239610 119650 239610 119645 239610 119645 239611 119650 239611 119590 239611 119645 239612 119590 239612 119652 239612 119652 239613 119590 239613 119651 239613 119652 239614 119651 239614 119653 239614 120719 239615 119529 239615 119654 239615 119655 239616 119665 239616 119654 239616 119529 239617 119530 239617 119654 239617 119654 239618 119530 239618 119531 239618 119654 239619 119531 239619 119655 239619 120717 239620 120719 239620 120715 239620 120715 239621 120719 239621 119654 239621 120715 239622 119654 239622 119539 239622 119539 239623 119654 239623 119657 239623 119657 239624 119654 239624 119656 239624 119657 239625 119656 239625 119540 239625 119540 239626 119656 239626 119659 239626 119540 239627 119659 239627 119542 239627 120929 239628 119528 239628 119659 239628 119659 239629 119528 239629 119658 239629 119659 239630 119658 239630 120957 239630 120957 239631 120958 239631 119659 239631 119659 239632 120958 239632 119660 239632 119659 239633 119660 239633 119661 239633 119661 239634 120961 239634 119659 239634 119659 239635 120961 239635 119662 239635 119659 239636 119662 239636 119542 239636 119537 239637 119538 239637 119663 239637 120923 239638 120927 239638 119663 239638 119663 239639 120927 239639 120929 239639 119663 239640 120929 239640 119537 239640 119538 239641 120925 239641 119663 239641 119663 239642 120925 239642 119664 239642 119663 239643 119664 239643 120923 239643 120929 239644 119659 239644 119537 239644 119537 239645 119659 239645 119656 239645 119537 239646 119656 239646 119535 239646 119535 239647 119656 239647 119654 239647 119535 239648 119654 239648 119665 239648 124593 239649 124599 239649 119682 239649 124452 239650 119666 239650 124454 239650 124454 239651 119666 239651 119667 239651 124454 239652 119667 239652 119714 239652 122560 239653 122375 239653 119668 239653 122560 239654 119668 239654 122543 239654 122543 239655 119668 239655 122366 239655 122543 239656 122366 239656 122503 239656 122503 239657 122366 239657 119669 239657 122503 239658 119669 239658 122480 239658 122480 239659 119669 239659 122335 239659 122480 239660 122335 239660 119670 239660 119709 239661 122354 239661 124452 239661 122354 239662 119671 239662 124452 239662 124452 239663 119671 239663 122342 239663 124452 239664 122342 239664 119666 239664 122561 239665 122384 239665 122560 239665 122560 239666 122384 239666 119672 239666 122560 239667 119672 239667 122375 239667 119673 239668 119674 239668 119682 239668 119682 239669 119674 239669 119675 239669 119682 239670 119675 239670 119676 239670 119676 239671 119675 239671 122462 239671 119676 239672 122462 239672 122662 239672 122662 239673 122462 239673 119677 239673 122662 239674 119677 239674 122649 239674 122649 239675 119677 239675 122434 239675 122649 239676 122434 239676 122629 239676 122434 239677 122433 239677 122629 239677 122629 239678 122433 239678 119678 239678 122629 239679 119678 239679 119679 239679 119679 239680 119678 239680 122432 239680 119679 239681 122432 239681 122431 239681 122431 239682 122411 239682 119679 239682 119679 239683 122411 239683 119680 239683 119679 239684 119680 239684 122355 239684 122355 239685 119680 239685 122420 239685 122355 239686 122420 239686 119681 239686 119673 239687 119682 239687 122467 239687 122467 239688 119682 239688 124599 239688 122467 239689 124599 239689 119683 239689 119683 239690 124599 239690 124600 239690 119683 239691 124600 239691 122446 239691 122446 239692 124600 239692 119724 239692 122446 239693 119724 239693 119684 239693 124593 239694 119682 239694 119685 239694 119685 239695 119682 239695 122711 239695 119685 239696 122711 239696 119686 239696 122711 239697 119687 239697 119686 239697 119686 239698 119687 239698 119688 239698 119686 239699 119688 239699 119690 239699 119688 239700 119689 239700 119690 239700 119690 239701 119689 239701 119691 239701 119690 239702 119691 239702 124588 239702 124588 239703 119691 239703 122743 239703 124588 239704 122743 239704 124578 239704 124578 239705 122743 239705 119692 239705 124578 239706 119692 239706 124625 239706 119692 239707 122757 239707 124625 239707 124625 239708 122757 239708 119693 239708 124625 239709 119693 239709 124649 239709 124649 239710 119693 239710 124650 239710 124650 239711 119693 239711 119694 239711 124650 239712 119694 239712 124610 239712 124610 239713 119694 239713 119701 239713 124610 239714 119701 239714 124611 239714 119712 239715 122624 239715 119695 239715 119696 239716 119699 239716 122624 239716 122624 239717 119699 239717 119697 239717 122624 239718 119697 239718 119695 239718 119696 239719 119698 239719 119699 239719 119699 239720 119698 239720 119704 239720 119699 239721 119704 239721 119700 239721 119700 239722 119704 239722 124611 239722 119700 239723 124611 239723 122760 239723 122760 239724 124611 239724 119701 239724 119698 239725 119702 239725 119704 239725 119704 239726 119702 239726 119703 239726 119704 239727 119703 239727 124502 239727 124502 239728 119703 239728 122569 239728 124502 239729 122569 239729 124476 239729 124476 239730 122569 239730 124500 239730 122569 239731 122589 239731 124500 239731 124500 239732 122589 239732 122588 239732 124500 239733 122588 239733 119706 239733 122588 239734 122582 239734 119706 239734 119706 239735 122582 239735 119705 239735 119706 239736 119705 239736 124444 239736 119705 239737 122514 239737 124444 239737 124444 239738 122514 239738 119707 239738 124444 239739 119707 239739 124448 239739 124448 239740 119707 239740 124449 239740 119707 239741 122511 239741 124449 239741 124449 239742 122511 239742 122510 239742 124449 239743 122510 239743 119708 239743 122335 239744 119709 239744 119670 239744 119670 239745 119709 239745 124452 239745 119670 239746 124452 239746 122485 239746 122485 239747 124452 239747 119708 239747 122485 239748 119708 239748 119710 239748 119710 239749 119708 239749 122510 239749 119695 239750 119711 239750 119712 239750 119712 239751 119711 239751 122725 239751 119712 239752 122725 239752 119713 239752 122725 239753 122674 239753 119713 239753 119713 239754 122674 239754 122677 239754 119713 239755 122677 239755 122603 239755 122603 239756 122677 239756 122679 239756 122603 239757 122679 239757 122680 239757 119679 239758 122384 239758 122629 239758 122629 239759 122384 239759 122561 239759 122629 239760 122561 239760 122647 239760 122647 239761 122561 239761 122549 239761 122647 239762 122549 239762 122638 239762 122638 239763 122549 239763 122609 239763 122638 239764 122609 239764 122680 239764 122680 239765 122609 239765 122601 239765 122680 239766 122601 239766 122603 239766 122318 239767 119721 239767 119723 239767 119714 239768 119667 239768 119715 239768 119715 239769 119667 239769 122314 239769 119715 239770 122314 239770 124474 239770 124474 239771 122314 239771 119716 239771 124474 239772 119716 239772 124469 239772 124469 239773 119716 239773 119718 239773 124469 239774 119718 239774 119717 239774 119717 239775 119718 239775 119719 239775 119717 239776 119719 239776 119729 239776 119681 239777 122420 239777 119720 239777 119720 239778 122420 239778 122394 239778 119720 239779 122394 239779 119721 239779 119721 239780 122394 239780 119722 239780 119721 239781 119722 239781 119723 239781 119684 239782 119724 239782 119725 239782 119725 239783 119724 239783 119726 239783 119725 239784 119726 239784 122402 239784 122402 239785 119726 239785 124539 239785 122402 239786 124539 239786 122409 239786 122409 239787 124539 239787 124543 239787 122409 239788 124543 239788 119727 239788 119727 239789 124543 239789 124544 239789 119727 239790 124544 239790 119728 239790 119728 239791 124544 239791 119717 239791 119728 239792 119717 239792 119723 239792 119723 239793 119717 239793 119729 239793 119723 239794 119729 239794 122318 239794 124504 239795 119730 239795 119731 239795 119731 239796 119730 239796 119732 239796 119731 239797 119732 239797 124522 239797 124522 239798 119732 239798 114559 239798 124522 239799 114559 239799 124533 239799 124533 239800 114559 239800 114556 239800 124533 239801 114556 239801 119733 239801 119733 239802 114556 239802 119753 239802 124504 239803 124503 239803 119730 239803 119730 239804 124503 239804 119734 239804 119730 239805 119734 239805 114548 239805 114548 239806 119734 239806 119735 239806 114548 239807 119735 239807 119738 239807 119736 239808 119737 239808 124487 239808 124487 239809 119737 239809 119738 239809 124487 239810 119738 239810 124477 239810 124477 239811 119738 239811 119735 239811 124524 239812 116304 239812 119739 239812 119739 239813 116304 239813 116306 239813 119740 239814 124431 239814 119741 239814 119740 239815 119741 239815 116316 239815 116316 239816 119741 239816 119742 239816 116316 239817 119742 239817 119743 239817 119743 239818 119742 239818 119739 239818 119743 239819 119739 239819 116306 239819 116304 239820 124524 239820 124537 239820 116304 239821 124537 239821 116303 239821 116303 239822 124537 239822 124536 239822 116303 239823 124536 239823 119744 239823 119744 239824 124536 239824 124556 239824 119744 239825 124556 239825 119745 239825 124431 239826 119740 239826 119746 239826 119746 239827 119740 239827 114540 239827 119746 239828 114540 239828 124442 239828 124442 239829 114540 239829 114542 239829 124442 239830 114542 239830 124440 239830 124440 239831 114542 239831 119748 239831 124440 239832 119748 239832 124439 239832 119736 239833 119747 239833 119737 239833 119737 239834 119747 239834 124433 239834 119737 239835 124433 239835 114550 239835 114550 239836 124433 239836 124435 239836 114550 239837 124435 239837 114551 239837 119748 239838 119749 239838 124439 239838 124439 239839 119749 239839 114544 239839 124439 239840 114544 239840 124437 239840 124437 239841 114544 239841 119750 239841 124437 239842 119750 239842 124436 239842 124436 239843 119750 239843 114547 239843 124436 239844 114547 239844 124435 239844 124435 239845 114547 239845 119751 239845 124435 239846 119751 239846 114551 239846 114556 239847 119752 239847 119753 239847 119753 239848 119752 239848 114552 239848 119753 239849 114552 239849 112213 239849 119762 239850 114527 239850 119754 239850 119754 239851 114527 239851 119755 239851 119754 239852 119755 239852 124575 239852 124575 239853 119755 239853 114524 239853 124575 239854 114524 239854 119756 239854 119756 239855 114524 239855 119757 239855 119756 239856 119757 239856 119760 239856 119745 239857 124556 239857 119758 239857 119758 239858 124556 239858 124603 239858 119758 239859 124603 239859 114523 239859 114523 239860 124603 239860 119760 239860 114523 239861 119760 239861 119759 239861 119759 239862 119760 239862 119757 239862 119754 239863 119761 239863 119762 239863 119762 239864 119761 239864 124576 239864 119762 239865 124576 239865 114532 239865 114532 239866 124576 239866 124584 239866 114532 239867 124584 239867 119763 239867 120857 239868 119764 239868 119833 239868 119833 239869 119764 239869 120870 239869 119833 239870 120870 239870 119765 239870 119766 239871 119769 239871 119767 239871 119767 239872 119769 239872 122302 239872 119767 239873 122302 239873 119768 239873 119768 239874 122302 239874 122308 239874 119768 239875 122308 239875 119771 239875 119771 239876 122308 239876 119772 239876 119769 239877 119766 239877 122309 239877 122309 239878 119766 239878 119770 239878 119771 239879 119772 239879 119774 239879 119774 239880 119772 239880 119773 239880 119774 239881 119773 239881 119775 239881 119775 239882 119773 239882 122323 239882 119775 239883 122323 239883 119828 239883 119828 239884 122323 239884 122339 239884 119828 239885 122339 239885 119776 239885 119835 239886 122359 239886 119834 239886 119834 239887 122359 239887 122358 239887 122317 239888 120681 239888 122360 239888 122360 239889 120681 239889 119826 239889 122360 239890 119826 239890 122358 239890 122358 239891 119826 239891 119777 239891 122358 239892 119777 239892 119834 239892 119885 239893 119778 239893 119890 239893 119890 239894 119778 239894 119779 239894 119890 239895 119779 239895 120899 239895 122392 239896 119780 239896 119781 239896 119781 239897 119780 239897 119880 239897 119878 239898 122421 239898 119879 239898 119879 239899 122421 239899 122407 239899 119879 239900 122407 239900 119782 239900 119782 239901 122407 239901 122408 239901 119782 239902 122408 239902 119880 239902 119880 239903 122408 239903 119781 239903 119893 239904 120902 239904 119783 239904 119783 239905 120902 239905 119784 239905 122421 239906 119878 239906 122449 239906 122449 239907 119878 239907 119785 239907 122449 239908 119785 239908 119784 239908 119784 239909 119785 239909 119786 239909 119784 239910 119786 239910 119783 239910 119882 239911 119787 239911 119881 239911 119881 239912 119787 239912 119788 239912 119881 239913 119788 239913 119892 239913 119892 239914 119788 239914 119789 239914 119892 239915 119789 239915 119894 239915 119894 239916 119789 239916 122416 239916 119894 239917 122416 239917 119884 239917 119795 239918 119790 239918 119792 239918 119792 239919 119790 239919 119791 239919 119792 239920 119791 239920 122599 239920 122599 239921 119791 239921 119794 239921 122599 239922 119794 239922 119793 239922 119793 239923 119794 239923 119877 239923 119793 239924 119877 239924 120691 239924 119795 239925 119792 239925 119872 239925 119872 239926 119792 239926 120885 239926 119872 239927 120885 239927 120884 239927 119805 239928 122574 239928 119861 239928 119861 239929 122574 239929 119796 239929 119861 239930 119796 239930 119797 239930 122579 239931 122574 239931 119805 239931 122576 239932 122577 239932 119801 239932 119800 239933 119809 239933 119798 239933 119798 239934 119799 239934 119800 239934 119800 239935 119799 239935 122575 239935 119800 239936 122575 239936 119801 239936 119801 239937 122575 239937 119802 239937 119801 239938 119802 239938 122576 239938 119804 239939 119859 239939 122577 239939 122577 239940 119859 239940 119803 239940 122577 239941 119803 239941 119801 239941 119804 239942 122591 239942 119859 239942 119859 239943 122591 239943 119806 239943 119859 239944 119806 239944 119805 239944 119805 239945 119806 239945 119807 239945 119805 239946 119807 239946 122579 239946 122518 239947 119798 239947 119809 239947 120867 239948 122512 239948 119864 239948 119864 239949 122512 239949 119808 239949 119864 239950 119808 239950 119812 239950 122518 239951 119809 239951 122522 239951 122522 239952 119809 239952 119810 239952 122522 239953 119810 239953 122527 239953 122527 239954 119810 239954 119811 239954 122527 239955 119811 239955 119808 239955 119808 239956 119811 239956 119870 239956 119808 239957 119870 239957 119812 239957 119873 239958 122509 239958 119813 239958 119813 239959 122509 239959 122508 239959 119813 239960 122508 239960 120860 239960 120698 239961 122755 239961 119851 239961 119851 239962 122755 239962 112211 239962 119851 239963 112211 239963 112210 239963 119817 239964 119814 239964 119853 239964 119853 239965 119814 239965 122669 239965 119853 239966 122669 239966 122738 239966 120898 239967 119815 239967 119816 239967 119816 239968 119815 239968 122671 239968 119816 239969 122671 239969 119855 239969 119853 239970 119818 239970 119817 239970 119817 239971 119818 239971 119858 239971 119817 239972 119858 239972 122671 239972 122671 239973 119858 239973 119857 239973 122671 239974 119857 239974 119855 239974 119837 239975 120910 239975 119819 239975 119819 239976 120910 239976 119820 239976 119819 239977 119820 239977 120888 239977 119848 239978 112207 239978 119821 239978 119848 239979 119821 239979 119846 239979 119846 239980 119821 239980 122741 239980 119846 239981 122741 239981 119843 239981 119843 239982 122741 239982 119822 239982 119843 239983 119822 239983 119823 239983 119823 239984 119822 239984 119839 239984 119839 239985 119822 239985 122742 239985 119839 239986 122742 239986 119824 239986 119824 239987 122742 239987 119825 239987 119824 239988 119825 239988 119840 239988 119774 239989 119826 239989 120681 239989 119766 239990 119767 239990 119768 239990 119827 239991 120683 239991 120681 239991 120681 239992 120683 239992 119770 239992 120681 239993 119770 239993 119774 239993 119774 239994 119770 239994 119766 239994 119774 239995 119766 239995 119771 239995 119771 239996 119766 239996 119768 239996 119828 239997 119776 239997 119830 239997 119833 239998 119828 239998 120857 239998 120857 239999 119828 239999 119830 239999 120857 240000 119830 240000 119829 240000 119829 240001 119830 240001 120856 240001 119776 240002 119831 240002 119830 240002 119830 240003 119831 240003 119832 240003 119830 240004 119832 240004 120856 240004 120872 240005 120873 240005 119765 240005 119765 240006 120873 240006 120876 240006 119765 240007 120876 240007 119833 240007 119833 240008 120876 240008 120875 240008 119826 240009 119774 240009 119777 240009 119777 240010 119774 240010 119775 240010 119777 240011 119775 240011 119834 240011 119834 240012 119775 240012 119828 240012 119834 240013 119828 240013 119835 240013 119835 240014 119828 240014 119833 240014 119835 240015 119833 240015 120874 240015 120874 240016 119833 240016 120875 240016 120895 240017 120898 240017 119819 240017 120890 240018 120891 240018 120888 240018 120888 240019 120891 240019 120893 240019 120888 240020 120893 240020 119819 240020 119819 240021 120893 240021 119836 240021 119819 240022 119836 240022 120895 240022 119841 240023 119842 240023 119838 240023 120898 240024 119816 240024 119819 240024 119819 240025 119816 240025 119856 240025 119819 240026 119856 240026 119837 240026 119837 240027 119856 240027 119841 240027 119837 240028 119841 240028 120909 240028 120909 240029 119841 240029 119838 240029 119839 240030 119824 240030 119856 240030 119856 240031 119824 240031 119840 240031 119856 240032 119840 240032 119841 240032 119841 240033 119840 240033 120906 240033 119841 240034 120906 240034 119842 240034 119839 240035 119856 240035 119823 240035 119823 240036 119856 240036 119845 240036 119823 240037 119845 240037 119843 240037 119847 240038 119852 240038 119844 240038 119843 240039 119845 240039 119846 240039 119846 240040 119845 240040 119847 240040 119846 240041 119847 240041 119848 240041 119848 240042 119847 240042 119844 240042 119848 240043 119844 240043 119849 240043 119850 240044 112208 240044 112210 240044 112210 240045 112208 240045 119852 240045 112210 240046 119852 240046 119851 240046 119851 240047 119852 240047 119847 240047 119851 240048 119847 240048 120698 240048 119845 240049 119818 240049 119847 240049 119847 240050 119818 240050 119853 240050 119847 240051 119853 240051 120694 240051 120692 240052 120698 240052 119854 240052 119854 240053 120698 240053 119847 240053 119854 240054 119847 240054 120695 240054 120695 240055 119847 240055 120694 240055 119816 240056 119855 240056 119856 240056 119856 240057 119855 240057 119857 240057 119856 240058 119857 240058 119845 240058 119845 240059 119857 240059 119858 240059 119845 240060 119858 240060 119818 240060 119860 240061 119805 240061 119861 240061 119859 240062 119805 240062 119803 240062 119803 240063 119805 240063 119860 240063 119803 240064 119860 240064 119801 240064 119801 240065 119860 240065 119800 240065 119800 240066 119860 240066 119809 240066 119809 240067 119860 240067 119861 240067 119809 240068 119861 240068 119810 240068 119810 240069 119861 240069 119868 240069 119810 240070 119868 240070 119811 240070 120861 240071 119862 240071 120860 240071 120860 240072 119862 240072 120863 240072 120860 240073 120863 240073 119813 240073 119813 240074 120863 240074 119863 240074 119813 240075 119863 240075 120865 240075 120865 240076 120867 240076 119813 240076 119813 240077 120867 240077 119864 240077 119813 240078 119864 240078 119869 240078 119869 240079 119864 240079 119812 240079 119869 240080 119812 240080 119870 240080 119872 240081 120884 240081 119871 240081 120884 240082 119865 240082 119871 240082 119871 240083 119865 240083 119866 240083 119871 240084 119866 240084 119867 240084 119794 240085 119791 240085 119868 240085 119868 240086 119791 240086 119869 240086 119868 240087 119869 240087 119811 240087 119811 240088 119869 240088 119870 240088 119867 240089 120887 240089 119871 240089 119871 240090 120887 240090 119873 240090 119871 240091 119873 240091 119872 240091 119872 240092 119873 240092 119813 240092 119872 240093 119813 240093 119795 240093 119795 240094 119813 240094 119869 240094 119795 240095 119869 240095 119790 240095 119790 240096 119869 240096 119791 240096 120690 240097 119877 240097 119874 240097 120687 240098 119875 240098 119874 240098 119874 240099 119875 240099 119876 240099 119874 240100 119876 240100 120690 240100 119794 240101 119868 240101 119877 240101 119877 240102 119868 240102 119861 240102 119877 240103 119861 240103 119874 240103 119874 240104 119861 240104 119797 240104 119874 240105 119797 240105 120687 240105 119881 240106 119785 240106 119878 240106 119780 240107 120686 240107 119883 240107 119879 240108 119782 240108 119878 240108 119878 240109 119782 240109 119880 240109 119878 240110 119880 240110 119881 240110 119881 240111 119880 240111 119780 240111 119881 240112 119780 240112 119882 240112 119882 240113 119780 240113 119883 240113 119894 240114 119884 240114 119887 240114 119890 240115 119894 240115 119885 240115 119885 240116 119894 240116 119887 240116 119885 240117 119887 240117 120881 240117 120881 240118 119887 240118 119888 240118 119884 240119 119886 240119 119887 240119 119887 240120 119886 240120 120878 240120 119887 240121 120878 240121 119888 240121 119889 240122 120901 240122 120899 240122 120899 240123 120901 240123 119891 240123 120899 240124 119891 240124 119890 240124 119890 240125 119891 240125 119896 240125 119785 240126 119881 240126 119786 240126 119786 240127 119881 240127 119892 240127 119786 240128 119892 240128 119783 240128 119783 240129 119892 240129 119894 240129 119783 240130 119894 240130 119893 240130 119893 240131 119894 240131 119890 240131 119893 240132 119890 240132 119895 240132 119895 240133 119890 240133 119896 240133 119917 240134 119918 240134 119915 240134 119907 240135 119897 240135 124226 240135 124226 240136 119897 240136 119898 240136 124226 240137 119898 240137 124203 240137 119913 240138 122283 240138 122185 240138 122185 240139 122283 240139 119899 240139 122185 240140 119899 240140 119910 240140 119910 240141 119899 240141 122281 240141 119910 240142 122281 240142 122253 240142 119909 240143 122272 240143 119901 240143 122272 240144 119900 240144 119901 240144 119901 240145 119900 240145 122257 240145 119901 240146 122257 240146 119914 240146 122044 240147 121902 240147 122035 240147 122035 240148 121902 240148 121885 240148 122035 240149 121885 240149 121998 240149 121998 240150 121885 240150 119902 240150 121998 240151 119902 240151 119903 240151 119903 240152 119902 240152 119904 240152 119903 240153 119904 240153 121957 240153 119935 240154 119905 240154 119937 240154 119937 240155 119905 240155 119906 240155 119937 240156 119906 240156 119907 240156 119907 240157 119906 240157 121848 240157 119907 240158 121848 240158 119897 240158 122114 240159 122117 240159 122045 240159 122045 240160 122117 240160 119901 240160 122045 240161 119901 240161 122044 240161 122044 240162 119901 240162 119908 240162 122044 240163 119908 240163 121902 240163 122253 240164 119909 240164 119910 240164 119910 240165 119909 240165 119901 240165 119910 240166 119901 240166 119911 240166 119911 240167 119901 240167 122117 240167 122199 240168 122287 240168 119913 240168 119913 240169 122287 240169 119912 240169 119913 240170 119912 240170 122283 240170 122242 240171 121854 240171 122248 240171 122248 240172 121854 240172 121880 240172 122248 240173 121880 240173 122247 240173 122247 240174 121880 240174 119914 240174 122247 240175 119914 240175 122238 240175 122238 240176 119914 240176 122257 240176 119917 240177 119915 240177 119916 240177 119916 240178 119915 240178 119962 240178 119916 240179 119962 240179 119961 240179 119917 240180 122287 240180 119918 240180 119918 240181 122287 240181 122199 240181 119918 240182 122199 240182 124359 240182 124359 240183 122199 240183 122188 240183 124359 240184 122188 240184 124360 240184 124360 240185 122188 240185 119919 240185 124360 240186 119919 240186 124362 240186 119919 240187 122165 240187 124362 240187 124362 240188 122165 240188 119920 240188 124362 240189 119920 240189 124363 240189 124363 240190 119920 240190 122163 240190 124363 240191 122163 240191 119921 240191 119921 240192 122163 240192 119922 240192 119922 240193 122163 240193 119923 240193 119922 240194 119923 240194 124404 240194 124404 240195 119923 240195 124405 240195 124405 240196 119923 240196 119925 240196 124405 240197 119925 240197 119924 240197 119924 240198 119925 240198 119926 240198 119924 240199 119926 240199 124408 240199 124408 240200 119926 240200 119927 240200 124408 240201 119927 240201 123631 240201 121985 240202 119928 240202 119941 240202 119941 240203 119928 240203 123629 240203 119941 240204 123629 240204 119929 240204 119929 240205 123629 240205 123631 240205 119929 240206 123631 240206 122137 240206 122137 240207 123631 240207 119927 240207 119928 240208 121940 240208 123629 240208 123629 240209 121940 240209 119930 240209 123629 240210 119930 240210 124293 240210 124293 240211 119930 240211 121908 240211 124293 240212 121908 240212 124292 240212 121908 240213 121910 240213 124292 240213 124292 240214 121910 240214 121903 240214 124292 240215 121903 240215 119931 240215 121903 240216 121905 240216 119931 240216 119931 240217 121905 240217 119932 240217 119931 240218 119932 240218 124221 240218 119932 240219 121926 240219 124221 240219 124221 240220 121926 240220 119933 240220 124221 240221 119933 240221 124222 240221 124222 240222 119933 240222 119934 240222 124222 240223 119934 240223 119939 240223 119904 240224 119935 240224 121957 240224 121957 240225 119935 240225 119937 240225 121957 240226 119937 240226 119936 240226 119936 240227 119937 240227 124225 240227 119936 240228 124225 240228 119938 240228 119938 240229 124225 240229 124224 240229 119938 240230 124224 240230 119939 240230 119939 240231 124224 240231 119940 240231 119939 240232 119940 240232 124222 240232 119941 240233 122059 240233 121985 240233 121985 240234 122059 240234 122077 240234 121985 240235 122077 240235 119942 240235 119942 240236 122077 240236 119943 240236 119942 240237 119943 240237 121987 240237 121987 240238 119943 240238 119944 240238 121987 240239 119944 240239 122006 240239 119944 240240 119945 240240 122006 240240 122006 240241 119945 240241 122085 240241 122006 240242 122085 240242 119946 240242 119946 240243 122085 240243 122084 240243 119946 240244 122084 240244 119949 240244 122114 240245 122045 240245 119947 240245 119947 240246 122045 240246 119948 240246 119947 240247 119948 240247 122101 240247 122101 240248 119948 240248 122024 240248 122101 240249 122024 240249 119949 240249 119949 240250 122024 240250 122026 240250 119949 240251 122026 240251 119946 240251 119950 240252 119951 240252 119952 240252 124203 240253 119898 240253 119953 240253 119953 240254 119898 240254 121811 240254 119953 240255 121811 240255 124249 240255 124249 240256 121811 240256 119954 240256 124249 240257 119954 240257 124244 240257 124244 240258 119954 240258 119955 240258 124244 240259 119955 240259 119957 240259 119957 240260 119955 240260 119956 240260 119957 240261 119956 240261 121825 240261 119950 240262 119958 240262 119951 240262 119951 240263 119958 240263 119959 240263 119951 240264 119959 240264 122223 240264 122223 240265 119959 240265 119960 240265 122223 240266 119960 240266 122242 240266 122242 240267 119960 240267 121854 240267 119961 240268 119962 240268 119963 240268 119963 240269 119962 240269 124335 240269 119963 240270 124335 240270 122230 240270 124335 240271 119964 240271 122230 240271 122230 240272 119964 240272 119965 240272 122230 240273 119965 240273 119966 240273 119966 240274 119965 240274 119967 240274 119966 240275 119967 240275 119968 240275 119968 240276 119967 240276 119969 240276 119968 240277 119969 240277 122218 240277 122218 240278 119969 240278 119957 240278 122218 240279 119957 240279 119952 240279 119952 240280 119957 240280 121825 240280 119952 240281 121825 240281 119950 240281 124403 240282 119970 240282 114502 240282 114481 240283 114480 240283 119971 240283 114481 240284 119971 240284 114502 240284 114502 240285 119971 240285 119972 240285 114502 240286 119972 240286 124403 240286 124392 240287 119974 240287 119970 240287 119970 240288 119974 240288 119973 240288 119970 240289 119973 240289 114502 240289 124392 240290 119975 240290 119974 240290 119974 240291 119975 240291 124390 240291 119974 240292 124390 240292 114501 240292 114501 240293 124390 240293 119977 240293 124339 240294 119976 240294 114519 240294 119977 240295 119978 240295 114501 240295 114501 240296 119978 240296 124388 240296 114501 240297 124388 240297 119979 240297 119979 240298 124388 240298 119980 240298 119979 240299 119980 240299 114519 240299 114519 240300 119980 240300 119981 240300 114519 240301 119981 240301 124339 240301 124313 240302 119982 240302 114497 240302 114497 240303 119982 240303 124258 240303 114497 240304 124258 240304 119983 240304 119983 240305 124258 240305 124256 240305 119983 240306 124256 240306 114499 240306 114499 240307 124256 240307 124273 240307 114499 240308 124273 240308 119985 240308 119985 240309 124273 240309 124259 240309 119985 240310 124259 240310 119984 240310 119984 240311 124251 240311 119985 240311 119985 240312 124251 240312 124250 240312 119985 240313 124250 240313 119986 240313 119986 240314 124250 240314 124283 240314 119986 240315 124283 240315 119987 240315 119987 240316 124283 240316 124207 240316 119987 240317 124207 240317 114492 240317 119988 240318 116315 240318 119989 240318 119989 240319 116315 240319 116312 240319 119994 240320 124246 240320 124245 240320 119994 240321 124245 240321 116310 240321 116310 240322 124245 240322 119990 240322 116310 240323 119990 240323 116311 240323 116311 240324 119990 240324 119989 240324 116311 240325 119989 240325 116312 240325 116315 240326 119988 240326 124314 240326 116315 240327 124314 240327 116320 240327 116320 240328 124314 240328 124316 240328 116320 240329 124316 240329 116319 240329 116319 240330 124316 240330 119991 240330 116319 240331 119991 240331 119992 240331 119992 240332 119991 240332 124318 240332 119992 240333 124318 240333 119993 240333 124246 240334 119994 240334 124202 240334 124202 240335 119994 240335 116309 240335 124202 240336 116309 240336 124215 240336 124215 240337 116309 240337 119995 240337 124215 240338 119995 240338 124214 240338 124214 240339 119995 240339 114483 240339 124214 240340 114483 240340 124213 240340 114483 240341 114485 240341 124213 240341 124213 240342 114485 240342 114488 240342 124213 240343 114488 240343 119996 240343 119996 240344 114488 240344 114489 240344 119996 240345 114489 240345 124210 240345 124210 240346 114489 240346 119998 240346 124210 240347 119998 240347 119997 240347 119997 240348 119998 240348 114490 240348 119997 240349 114490 240349 124209 240349 124209 240350 114490 240350 119999 240350 124209 240351 119999 240351 120000 240351 120000 240352 119999 240352 114492 240352 120000 240353 114492 240353 124207 240353 114519 240354 119976 240354 120001 240354 120001 240355 119976 240355 124313 240355 120001 240356 124313 240356 114497 240356 114506 240357 120002 240357 114505 240357 114505 240358 120002 240358 120004 240358 114505 240359 120004 240359 120003 240359 120003 240360 120004 240360 114503 240360 114503 240361 120004 240361 120005 240361 114503 240362 120005 240362 114480 240362 114480 240363 120005 240363 124352 240363 114480 240364 124352 240364 119971 240364 119993 240365 124318 240365 120006 240365 120006 240366 124318 240366 120007 240366 120006 240367 120007 240367 114508 240367 114508 240368 120007 240368 120008 240368 114508 240369 120008 240369 114507 240369 114507 240370 120008 240370 120009 240370 120009 240371 120008 240371 120010 240371 120009 240372 120010 240372 114506 240372 114506 240373 120010 240373 124348 240373 114506 240374 124348 240374 120002 240374 120081 240375 120011 240375 120086 240375 120086 240376 120011 240376 121881 240376 120086 240377 121881 240377 120012 240377 120072 240378 120013 240378 120073 240378 120073 240379 120013 240379 121815 240379 120073 240380 121815 240380 120014 240380 120014 240381 121815 240381 121820 240381 120014 240382 121820 240382 120015 240382 120015 240383 121820 240383 121826 240383 120013 240384 120072 240384 121821 240384 121821 240385 120072 240385 120075 240385 120015 240386 121826 240386 120016 240386 120016 240387 121826 240387 121839 240387 120016 240388 121839 240388 120017 240388 120017 240389 121839 240389 121844 240389 120017 240390 121844 240390 120018 240390 120018 240391 121844 240391 121843 240391 120018 240392 121843 240392 120019 240392 120827 240393 121879 240393 120080 240393 120080 240394 121879 240394 120021 240394 121834 240395 120020 240395 121849 240395 121849 240396 120020 240396 120022 240396 121849 240397 120022 240397 120021 240397 120021 240398 120022 240398 120023 240398 120021 240399 120023 240399 120080 240399 120140 240400 120024 240400 120143 240400 120143 240401 120024 240401 120025 240401 120143 240402 120025 240402 120844 240402 120678 240403 120680 240403 120026 240403 120026 240404 120680 240404 120027 240404 120132 240405 122229 240405 120028 240405 120028 240406 122229 240406 122234 240406 120028 240407 122234 240407 120134 240407 120134 240408 122234 240408 120029 240408 120134 240409 120029 240409 120027 240409 120027 240410 120029 240410 120026 240410 120030 240411 120031 240411 120034 240411 120034 240412 120031 240412 120033 240412 122229 240413 120132 240413 120032 240413 120032 240414 120132 240414 120136 240414 120032 240415 120136 240415 120033 240415 120033 240416 120136 240416 120135 240416 120033 240417 120135 240417 120034 240417 120677 240418 122214 240418 120035 240418 120035 240419 122214 240419 122219 240419 120035 240420 122219 240420 120137 240420 120137 240421 122219 240421 122244 240421 120137 240422 122244 240422 120138 240422 120138 240423 122244 240423 120830 240423 120138 240424 120830 240424 120036 240424 120037 240425 120038 240425 122019 240425 122019 240426 120038 240426 120039 240426 122019 240427 120039 240427 122015 240427 122015 240428 120039 240428 120040 240428 122015 240429 120040 240429 120041 240429 120041 240430 120040 240430 120128 240430 120041 240431 120128 240431 122012 240431 120037 240432 122019 240432 120122 240432 120122 240433 122019 240433 120814 240433 120122 240434 120814 240434 120118 240434 120109 240435 120042 240435 120043 240435 120109 240436 120043 240436 120130 240436 120130 240437 120043 240437 121977 240437 120130 240438 121977 240438 120131 240438 120049 240439 120048 240439 120050 240439 120052 240440 121914 240440 120044 240440 120044 240441 121914 240441 120045 240441 120045 240442 120046 240442 120044 240442 120044 240443 120046 240443 120047 240443 120044 240444 120047 240444 120110 240444 120110 240445 120047 240445 120048 240445 120048 240446 120047 240446 121917 240446 120048 240447 121917 240447 120050 240447 120049 240448 120050 240448 120109 240448 120109 240449 120050 240449 121920 240449 120109 240450 121920 240450 120042 240450 121927 240451 121914 240451 120052 240451 121924 240452 120051 240452 120112 240452 120112 240453 120051 240453 120052 240453 120052 240454 120051 240454 121933 240454 120052 240455 121933 240455 121927 240455 120112 240456 120053 240456 121924 240456 121924 240457 120053 240457 120125 240457 121924 240458 120125 240458 121967 240458 121967 240459 120125 240459 120116 240459 121967 240460 120116 240460 120117 240460 120819 240461 122005 240461 120123 240461 120123 240462 122005 240462 121975 240462 120123 240463 121975 240463 120114 240463 120066 240464 120054 240464 120102 240464 120066 240465 120102 240465 122132 240465 122132 240466 120102 240466 122133 240466 122133 240467 120102 240467 120103 240467 122133 240468 120103 240468 122147 240468 122147 240469 120103 240469 120104 240469 122147 240470 120104 240470 120055 240470 120055 240471 120104 240471 120101 240471 120055 240472 120101 240472 120056 240472 120056 240473 120101 240473 120057 240473 120056 240474 120057 240474 120058 240474 120058 240475 120057 240475 120100 240475 120058 240476 120100 240476 122138 240476 120100 240477 120059 240477 122138 240477 122138 240478 120059 240478 120672 240478 122138 240479 120672 240479 120671 240479 122079 240480 120060 240480 120061 240480 120061 240481 120060 240481 122081 240481 120061 240482 122081 240482 120062 240482 120091 240483 122104 240483 120105 240483 120105 240484 122104 240484 120064 240484 120105 240485 120064 240485 120065 240485 120061 240486 120063 240486 122079 240486 122079 240487 120063 240487 120108 240487 122079 240488 120108 240488 120064 240488 120064 240489 120108 240489 120107 240489 120064 240490 120107 240490 120065 240490 120093 240491 120843 240491 120092 240491 120092 240492 120843 240492 120820 240492 120092 240493 120820 240493 120088 240493 120054 240494 120066 240494 120068 240494 120054 240495 120068 240495 120067 240495 120067 240496 120068 240496 120070 240496 120067 240497 120070 240497 120069 240497 120069 240498 120070 240498 122158 240498 120069 240499 122158 240499 120071 240499 120071 240500 122158 240500 122157 240500 120071 240501 122157 240501 120099 240501 120099 240502 122157 240502 120838 240502 120099 240503 120838 240503 120096 240503 120072 240504 120073 240504 120014 240504 120074 240505 120676 240505 120674 240505 120674 240506 120676 240506 120075 240506 120674 240507 120075 240507 120020 240507 120014 240508 120015 240508 120072 240508 120072 240509 120015 240509 120016 240509 120072 240510 120016 240510 120075 240510 120075 240511 120016 240511 120022 240511 120075 240512 120022 240512 120020 240512 120018 240513 120080 240513 120017 240513 120017 240514 120080 240514 120023 240514 120017 240515 120023 240515 120016 240515 120016 240516 120023 240516 120022 240516 120076 240517 120081 240517 120078 240517 120082 240518 120077 240518 120078 240518 120078 240519 120077 240519 120805 240519 120078 240520 120805 240520 120076 240520 120079 240521 120827 240521 120086 240521 120086 240522 120827 240522 120080 240522 120086 240523 120080 240523 120081 240523 120081 240524 120080 240524 120018 240524 120081 240525 120018 240525 120078 240525 120078 240526 120018 240526 120019 240526 120078 240527 120019 240527 120082 240527 120083 240528 120084 240528 120012 240528 120012 240529 120084 240529 120085 240529 120012 240530 120085 240530 120086 240530 120086 240531 120085 240531 120087 240531 120086 240532 120087 240532 120079 240532 120672 240533 120059 240533 120098 240533 120090 240534 120091 240534 120092 240534 120821 240535 120089 240535 120088 240535 120088 240536 120089 240536 120822 240536 120088 240537 120822 240537 120092 240537 120092 240538 120822 240538 120823 240538 120092 240539 120823 240539 120090 240539 120106 240540 120099 240540 120096 240540 120097 240541 120841 240541 120095 240541 120091 240542 120105 240542 120092 240542 120092 240543 120105 240543 120106 240543 120092 240544 120106 240544 120093 240544 120093 240545 120106 240545 120097 240545 120093 240546 120097 240546 120094 240546 120094 240547 120097 240547 120095 240547 120106 240548 120096 240548 120097 240548 120097 240549 120096 240549 120837 240549 120097 240550 120837 240550 120841 240550 120054 240551 120067 240551 120098 240551 120098 240552 120067 240552 120069 240552 120098 240553 120069 240553 120106 240553 120106 240554 120069 240554 120071 240554 120106 240555 120071 240555 120099 240555 120059 240556 120100 240556 120098 240556 120098 240557 120100 240557 120057 240557 120098 240558 120057 240558 120101 240558 120102 240559 120054 240559 120103 240559 120103 240560 120054 240560 120098 240560 120103 240561 120098 240561 120104 240561 120104 240562 120098 240562 120101 240562 120063 240563 120061 240563 120098 240563 120098 240564 120061 240564 120666 240564 120098 240565 120666 240565 120669 240565 120669 240566 120664 240566 120098 240566 120098 240567 120664 240567 120663 240567 120098 240568 120663 240568 120672 240568 120105 240569 120065 240569 120106 240569 120106 240570 120065 240570 120107 240570 120106 240571 120107 240571 120098 240571 120098 240572 120107 240572 120108 240572 120098 240573 120108 240573 120063 240573 120048 240574 120049 240574 120109 240574 120110 240575 120048 240575 120044 240575 120044 240576 120048 240576 120129 240576 120125 240577 120053 240577 120111 240577 120111 240578 120053 240578 120112 240578 120111 240579 120112 240579 120129 240579 120129 240580 120112 240580 120052 240580 120129 240581 120052 240581 120044 240581 120113 240582 120806 240582 120114 240582 120114 240583 120806 240583 120115 240583 120114 240584 120115 240584 120123 240584 120123 240585 120115 240585 120808 240585 120123 240586 120808 240586 120810 240586 120125 240587 120126 240587 120116 240587 120116 240588 120126 240588 120123 240588 120116 240589 120123 240589 120117 240589 120117 240590 120123 240590 120810 240590 120122 240591 120118 240591 120120 240591 120119 240592 120121 240592 120120 240592 120120 240593 120121 240593 120819 240593 120120 240594 120819 240594 120122 240594 120122 240595 120819 240595 120123 240595 120122 240596 120123 240596 120037 240596 120037 240597 120123 240597 120126 240597 120037 240598 120126 240598 120038 240598 120118 240599 120812 240599 120120 240599 120120 240600 120812 240600 120124 240600 120120 240601 120124 240601 120119 240601 120125 240602 120111 240602 120126 240602 120126 240603 120111 240603 120039 240603 120126 240604 120039 240604 120038 240604 120129 240605 120660 240605 120127 240605 120127 240606 120662 240606 120129 240606 120129 240607 120662 240607 120128 240607 120129 240608 120128 240608 120111 240608 120111 240609 120128 240609 120040 240609 120111 240610 120040 240610 120039 240610 120048 240611 120109 240611 120129 240611 120129 240612 120109 240612 120130 240612 120129 240613 120130 240613 120660 240613 120660 240614 120130 240614 120131 240614 120660 240615 120131 240615 120658 240615 120677 240616 120035 240616 120132 240616 120132 240617 120035 240617 120136 240617 120679 240618 120133 240618 120680 240618 120680 240619 120133 240619 120677 240619 120680 240620 120677 240620 120027 240620 120027 240621 120677 240621 120132 240621 120027 240622 120132 240622 120134 240622 120134 240623 120132 240623 120028 240623 120034 240624 120135 240624 120143 240624 120136 240625 120035 240625 120135 240625 120135 240626 120035 240626 120137 240626 120135 240627 120137 240627 120138 240627 120833 240628 120140 240628 120141 240628 120831 240629 120832 240629 120141 240629 120141 240630 120832 240630 120139 240630 120141 240631 120139 240631 120833 240631 120143 240632 120135 240632 120140 240632 120140 240633 120135 240633 120138 240633 120140 240634 120138 240634 120141 240634 120141 240635 120138 240635 120036 240635 120141 240636 120036 240636 120831 240636 120142 240637 120846 240637 120844 240637 120844 240638 120846 240638 120848 240638 120844 240639 120848 240639 120143 240639 120143 240640 120848 240640 120850 240640 120143 240641 120850 240641 120852 240641 120852 240642 120853 240642 120143 240642 120143 240643 120853 240643 120030 240643 120143 240644 120030 240644 120034 240644 121792 240645 121795 240645 124188 240645 124188 240646 121795 240646 120144 240646 120144 240647 121795 240647 121796 240647 120144 240648 121796 240648 123626 240648 121796 240649 121785 240649 123626 240649 123626 240650 121785 240650 120145 240650 123626 240651 120145 240651 120146 240651 120146 240652 120145 240652 121754 240652 120146 240653 121754 240653 121752 240653 121752 240654 121757 240654 120146 240654 120146 240655 121757 240655 121756 240655 120146 240656 121756 240656 121514 240656 121514 240657 121756 240657 121755 240657 121514 240658 121755 240658 120147 240658 120147 240659 121755 240659 121710 240659 120147 240660 121710 240660 120151 240660 120152 240661 120183 240661 121656 240661 121656 240662 120183 240662 121614 240662 121656 240663 121614 240663 121671 240663 121671 240664 121614 240664 120148 240664 121671 240665 120148 240665 121691 240665 121691 240666 120148 240666 121586 240666 121691 240667 121586 240667 121698 240667 121698 240668 121586 240668 120150 240668 121698 240669 120150 240669 120149 240669 120149 240670 120150 240670 120151 240670 120149 240671 120151 240671 121711 240671 121711 240672 120151 240672 121710 240672 121656 240673 121674 240673 120152 240673 120152 240674 121674 240674 121673 240674 120152 240675 121673 240675 120153 240675 120153 240676 120154 240676 120152 240676 120152 240677 120154 240677 121729 240677 120152 240678 121729 240678 120155 240678 121729 240679 120156 240679 120155 240679 120155 240680 120156 240680 121731 240680 120155 240681 121731 240681 120169 240681 120157 240682 121472 240682 120155 240682 121472 240683 121471 240683 120155 240683 120155 240684 121471 240684 120158 240684 120155 240685 120158 240685 121482 240685 120159 240686 121456 240686 120160 240686 120160 240687 121456 240687 121444 240687 120160 240688 121444 240688 121285 240688 121285 240689 121444 240689 121443 240689 121285 240690 121443 240690 121268 240690 120160 240691 120181 240691 120159 240691 120159 240692 120181 240692 120161 240692 120159 240693 120161 240693 121436 240693 121436 240694 120161 240694 120152 240694 121436 240695 120152 240695 121467 240695 121467 240696 120152 240696 120155 240696 121467 240697 120155 240697 120162 240697 120162 240698 120155 240698 121482 240698 121443 240699 121428 240699 121268 240699 121268 240700 121428 240700 121427 240700 121268 240701 121427 240701 121277 240701 121277 240702 121427 240702 121407 240702 121277 240703 121407 240703 120163 240703 120155 240704 120164 240704 120157 240704 120157 240705 120164 240705 120165 240705 120157 240706 120165 240706 120167 240706 120167 240707 120165 240707 124146 240707 124146 240708 120166 240708 120167 240708 120167 240709 120166 240709 120168 240709 120167 240710 120168 240710 120202 240710 121731 240711 120170 240711 120169 240711 120169 240712 120170 240712 120172 240712 120169 240713 120172 240713 120171 240713 120171 240714 120172 240714 120173 240714 120171 240715 120173 240715 120174 240715 120174 240716 120173 240716 124129 240716 124129 240717 120173 240717 120175 240717 124129 240718 120175 240718 124124 240718 120175 240719 120176 240719 124124 240719 124124 240720 120176 240720 120177 240720 124124 240721 120177 240721 124161 240721 124161 240722 120177 240722 121792 240722 124161 240723 121792 240723 120178 240723 120178 240724 121792 240724 124188 240724 121310 240725 121325 240725 120180 240725 121338 240726 120191 240726 120188 240726 120212 240727 123934 240727 120213 240727 120213 240728 123934 240728 121372 240728 121372 240729 123934 240729 120179 240729 121372 240730 120179 240730 121373 240730 121373 240731 120179 240731 120190 240731 121373 240732 120190 240732 121337 240732 121338 240733 120188 240733 120185 240733 121310 240734 120180 240734 120181 240734 120183 240735 120152 240735 120180 240735 120180 240736 120152 240736 120161 240736 120180 240737 120161 240737 120181 240737 120184 240738 120186 240738 121325 240738 121325 240739 120186 240739 120182 240739 121325 240740 120182 240740 120180 240740 120180 240741 120182 240741 121638 240741 120180 240742 121638 240742 120183 240742 120184 240743 120185 240743 120186 240743 120186 240744 120185 240744 120188 240744 120186 240745 120188 240745 120187 240745 120187 240746 120188 240746 120189 240746 121528 240747 120189 240747 123935 240747 123935 240748 120189 240748 120188 240748 123935 240749 120188 240749 120190 240749 120190 240750 120188 240750 120191 240750 120190 240751 120191 240751 121337 240751 123935 240752 120192 240752 121528 240752 121528 240753 120192 240753 123937 240753 121528 240754 123937 240754 120193 240754 120193 240755 123937 240755 120194 240755 120193 240756 120194 240756 120195 240756 120195 240757 120194 240757 120196 240757 120196 240758 120194 240758 123940 240758 120196 240759 123940 240759 123941 240759 121514 240760 121515 240760 120146 240760 120146 240761 121515 240761 120197 240761 120197 240762 120198 240762 120146 240762 120146 240763 120198 240763 121488 240763 120146 240764 121488 240764 124038 240764 124038 240765 121488 240765 121495 240765 124038 240766 121495 240766 123980 240766 123980 240767 121495 240767 120199 240767 123980 240768 120199 240768 123986 240768 123986 240769 120199 240769 121505 240769 123986 240770 121505 240770 120200 240770 120200 240771 121505 240771 120201 240771 120200 240772 120201 240772 123941 240772 123941 240773 120201 240773 121500 240773 123941 240774 121500 240774 120196 240774 120208 240775 124046 240775 120211 240775 120202 240776 120168 240776 120203 240776 120203 240777 120168 240777 124078 240777 120203 240778 124078 240778 121410 240778 121410 240779 124078 240779 124077 240779 121410 240780 124077 240780 120204 240780 120204 240781 124077 240781 120205 240781 120204 240782 120205 240782 121396 240782 121396 240783 120205 240783 120206 240783 121396 240784 120206 240784 121397 240784 121397 240785 120206 240785 124046 240785 121397 240786 124046 240786 120207 240786 120207 240787 124046 240787 120208 240787 120211 240788 121292 240788 120208 240788 120208 240789 121292 240789 121289 240789 120208 240790 121289 240790 120209 240790 120209 240791 121289 240791 120210 240791 120209 240792 120210 240792 121407 240792 121407 240793 120210 240793 120163 240793 121313 240794 120211 240794 124046 240794 120212 240795 120213 240795 120214 240795 120214 240796 120213 240796 120215 240796 120214 240797 120215 240797 124004 240797 124004 240798 120215 240798 120216 240798 120215 240799 120217 240799 120216 240799 120216 240800 120217 240800 120218 240800 120216 240801 120218 240801 124002 240801 124002 240802 120218 240802 121361 240802 124002 240803 121361 240803 120219 240803 121361 240804 120220 240804 120219 240804 120219 240805 120220 240805 121326 240805 120219 240806 121326 240806 124049 240806 124049 240807 121326 240807 121329 240807 124049 240808 121329 240808 124046 240808 124046 240809 121329 240809 121330 240809 124046 240810 121330 240810 121313 240810 120221 240811 120227 240811 124154 240811 114500 240812 120222 240812 124163 240812 124163 240813 120222 240813 120226 240813 120225 240814 114493 240814 120223 240814 120223 240815 114493 240815 120224 240815 120223 240816 120224 240816 120278 240816 120225 240817 120223 240817 120222 240817 120222 240818 120223 240818 124153 240818 120222 240819 124153 240819 120226 240819 124154 240820 120227 240820 124156 240820 114500 240821 124163 240821 120227 240821 120227 240822 124163 240822 120228 240822 120227 240823 120228 240823 124156 240823 120221 240824 124154 240824 120230 240824 120230 240825 124154 240825 124189 240825 120230 240826 124189 240826 120229 240826 120229 240827 124167 240827 120230 240827 120230 240828 124167 240828 120231 240828 120230 240829 120231 240829 120232 240829 120232 240830 120231 240830 124165 240830 120232 240831 124165 240831 114516 240831 114516 240832 124165 240832 124111 240832 114516 240833 124111 240833 124110 240833 120237 240834 120267 240834 124034 240834 120233 240835 120234 240835 120235 240835 120235 240836 120234 240836 120236 240836 120235 240837 120236 240837 123968 240837 123968 240838 120236 240838 120237 240838 123968 240839 120237 240839 124036 240839 124036 240840 120237 240840 124034 240840 120235 240841 123987 240841 120233 240841 120233 240842 123987 240842 120238 240842 120233 240843 120238 240843 120239 240843 120239 240844 120238 240844 120240 240844 120239 240845 120240 240845 120241 240845 120241 240846 120240 240846 123975 240846 120241 240847 123975 240847 120242 240847 120242 240848 123975 240848 120243 240848 120242 240849 120243 240849 120244 240849 124081 240850 116296 240850 120245 240850 120245 240851 116296 240851 120246 240851 120245 240852 120246 240852 120247 240852 120247 240853 120246 240853 120248 240853 120247 240854 120248 240854 124048 240854 124013 240855 120255 240855 124015 240855 124015 240856 120255 240856 120250 240856 124015 240857 120250 240857 120249 240857 120249 240858 120250 240858 120251 240858 120249 240859 120251 240859 120252 240859 120252 240860 120251 240860 120253 240860 120252 240861 120253 240861 124022 240861 124022 240862 120253 240862 120261 240862 124022 240863 120261 240863 124023 240863 124048 240864 120248 240864 120254 240864 120254 240865 120248 240865 114478 240865 120254 240866 114478 240866 124013 240866 124013 240867 114478 240867 114477 240867 124013 240868 114477 240868 120255 240868 116296 240869 124081 240869 120256 240869 116296 240870 120256 240870 116294 240870 116294 240871 120256 240871 120257 240871 116294 240872 120257 240872 120258 240872 120258 240873 120257 240873 124073 240873 120258 240874 124073 240874 120273 240874 120264 240875 114205 240875 120259 240875 120259 240876 114205 240876 114204 240876 120259 240877 114204 240877 120260 240877 120260 240878 114204 240878 114151 240878 124023 240879 120261 240879 123961 240879 123961 240880 120261 240880 120262 240880 123961 240881 120262 240881 123931 240881 123931 240882 120262 240882 114211 240882 123931 240883 114211 240883 123928 240883 123928 240884 114211 240884 114210 240884 123928 240885 114210 240885 123927 240885 123927 240886 114210 240886 114147 240886 123927 240887 114147 240887 123925 240887 123925 240888 114147 240888 120263 240888 123925 240889 120263 240889 120264 240889 120264 240890 120263 240890 120265 240890 120264 240891 120265 240891 114205 240891 114151 240892 114150 240892 120260 240892 120260 240893 114150 240893 120266 240893 120260 240894 120266 240894 123923 240894 123923 240895 120266 240895 120244 240895 123923 240896 120244 240896 120243 240896 114214 240897 120267 240897 120237 240897 120267 240898 114214 240898 124052 240898 124052 240899 114214 240899 120268 240899 124052 240900 120268 240900 124062 240900 124062 240901 120268 240901 114494 240901 124062 240902 114494 240902 120269 240902 120269 240903 114494 240903 120270 240903 120270 240904 114494 240904 114516 240904 120270 240905 114516 240905 124110 240905 114484 240906 124141 240906 114486 240906 114486 240907 124141 240907 120271 240907 114486 240908 120271 240908 120272 240908 120273 240909 124073 240909 114482 240909 114482 240910 124073 240910 124147 240910 114482 240911 124147 240911 120274 240911 120274 240912 124147 240912 124141 240912 120274 240913 124141 240913 120275 240913 120275 240914 124141 240914 114484 240914 120272 240915 120271 240915 114487 240915 114487 240916 120271 240916 124130 240916 114487 240917 124130 240917 120276 240917 120276 240918 124130 240918 120277 240918 120277 240919 124130 240919 124133 240919 120277 240920 124133 240920 114491 240920 114491 240921 124133 240921 124132 240921 114491 240922 124132 240922 120278 240922 120278 240923 124132 240923 120279 240923 120278 240924 120279 240924 120223 240924 120280 240925 120363 240925 121320 240925 121320 240926 120363 240926 120635 240926 121320 240927 120635 240927 121340 240927 120288 240928 121328 240928 120283 240928 120283 240929 121328 240929 120281 240929 120281 240930 120282 240930 120283 240930 120283 240931 120282 240931 120284 240931 120283 240932 120284 240932 120285 240932 120284 240933 121352 240933 120285 240933 120285 240934 121352 240934 120287 240934 120285 240935 120287 240935 120350 240935 121356 240936 120351 240936 120286 240936 120286 240937 120351 240937 120350 240937 120286 240938 120350 240938 121370 240938 121370 240939 120350 240939 120287 240939 120349 240940 121315 240940 120288 240940 120288 240941 121315 240941 121327 240941 120288 240942 121327 240942 121328 240942 121345 240943 120355 240943 120290 240943 120290 240944 120355 240944 120364 240944 120364 240945 120289 240945 120290 240945 120290 240946 120289 240946 120353 240946 120290 240947 120353 240947 120292 240947 120292 240948 120353 240948 120291 240948 120292 240949 120291 240949 120293 240949 120293 240950 120291 240950 120351 240950 120293 240951 120351 240951 121356 240951 120297 240952 121291 240952 120294 240952 120359 240953 120764 240953 120295 240953 120295 240954 120764 240954 121273 240954 120294 240955 120296 240955 120297 240955 120297 240956 120296 240956 120352 240956 120297 240957 120352 240957 121273 240957 121273 240958 120352 240958 120298 240958 121273 240959 120298 240959 120295 240959 120413 240960 121445 240960 120414 240960 120414 240961 121445 240961 120788 240961 120414 240962 120788 240962 120415 240962 121385 240963 120299 240963 120303 240963 120303 240964 120299 240964 120407 240964 120306 240965 121431 240965 120300 240965 120300 240966 121431 240966 121420 240966 120300 240967 121420 240967 120301 240967 120301 240968 121420 240968 120302 240968 120301 240969 120302 240969 120407 240969 120407 240970 120302 240970 120303 240970 120304 240971 120305 240971 120418 240971 120418 240972 120305 240972 121461 240972 121431 240973 120306 240973 121432 240973 121432 240974 120306 240974 120409 240974 121432 240975 120409 240975 121461 240975 121461 240976 120409 240976 120412 240976 121461 240977 120412 240977 120418 240977 120405 240978 121395 240978 120406 240978 120406 240979 121395 240979 120307 240979 120406 240980 120307 240980 120423 240980 120423 240981 120307 240981 121422 240981 120423 240982 121422 240982 120422 240982 120422 240983 121422 240983 120308 240983 120422 240984 120308 240984 120309 240984 120310 240985 121540 240985 120311 240985 120310 240986 120311 240986 120378 240986 120378 240987 120311 240987 121579 240987 120378 240988 121579 240988 120312 240988 120312 240989 121579 240989 121590 240989 120312 240990 121590 240990 120373 240990 120373 240991 121590 240991 121584 240991 120373 240992 121584 240992 120772 240992 120313 240993 120314 240993 121490 240993 120313 240994 121490 240994 120374 240994 120374 240995 121490 240995 121491 240995 120374 240996 121491 240996 120647 240996 120381 240997 120319 240997 120321 240997 120381 240998 120321 240998 120382 240998 120321 240999 121497 240999 120382 240999 120382 241000 121497 241000 120315 241000 120382 241001 120315 241001 120316 241001 120316 241002 120315 241002 121499 241002 120316 241003 121499 241003 121508 241003 121493 241004 120314 241004 121492 241004 121492 241005 120314 241005 120313 241005 121492 241006 120313 241006 121508 241006 121508 241007 120313 241007 120317 241007 121508 241008 120317 241008 120316 241008 120318 241009 120322 241009 120319 241009 120319 241010 120322 241010 120320 241010 120319 241011 120320 241011 120321 241011 120367 241012 120641 241012 120366 241012 120366 241013 120641 241013 120322 241013 120366 241014 120322 241014 120383 241014 120383 241015 120322 241015 120318 241015 120775 241016 121595 241016 120323 241016 120323 241017 121595 241017 121594 241017 120323 241018 121594 241018 121593 241018 121766 241019 120324 241019 120388 241019 120334 241020 121770 241020 120395 241020 120395 241021 121770 241021 120325 241021 120395 241022 120325 241022 120326 241022 120326 241023 120325 241023 120327 241023 120326 241024 120327 241024 120328 241024 120328 241025 120327 241025 121766 241025 120328 241026 121766 241026 120329 241026 120329 241027 121766 241027 120388 241027 120330 241028 121801 241028 121800 241028 120330 241029 121800 241029 120331 241029 120331 241030 121800 241030 121806 241030 120331 241031 121806 241031 120397 241031 120397 241032 121806 241032 120332 241032 120397 241033 120332 241033 120396 241033 120332 241034 120333 241034 120396 241034 120396 241035 120333 241035 121789 241035 120396 241036 121789 241036 120335 241036 120334 241037 120395 241037 121802 241037 121802 241038 120395 241038 120335 241038 121802 241039 120335 241039 121787 241039 121787 241040 120335 241040 121789 241040 120656 241041 121783 241041 120336 241041 120336 241042 121783 241042 121780 241042 120336 241043 121780 241043 120330 241043 120330 241044 121780 241044 121801 241044 120787 241045 120337 241045 120399 241045 120399 241046 120337 241046 120338 241046 120338 241047 120337 241047 120400 241047 120400 241048 120337 241048 121692 241048 120400 241049 121692 241049 120339 241049 120339 241050 121692 241050 121706 241050 120339 241051 121706 241051 120340 241051 120340 241052 121706 241052 120341 241052 120340 241053 120341 241053 121707 241053 120782 241054 120781 241054 120342 241054 120342 241055 120781 241055 120391 241055 120342 241056 120391 241056 120392 241056 120351 241057 120291 241057 120348 241057 120643 241058 120644 241058 120346 241058 120346 241059 120644 241059 120343 241059 120346 241060 120343 241060 120349 241060 120344 241061 120345 241061 120346 241061 120346 241062 120345 241062 120347 241062 120346 241063 120347 241063 120643 241063 120288 241064 120348 241064 120349 241064 120349 241065 120348 241065 120296 241065 120349 241066 120296 241066 120346 241066 120346 241067 120296 241067 120294 241067 120346 241068 120294 241068 120344 241068 120350 241069 120351 241069 120285 241069 120285 241070 120351 241070 120348 241070 120285 241071 120348 241071 120283 241071 120283 241072 120348 241072 120288 241072 120352 241073 120296 241073 120353 241073 120353 241074 120296 241074 120348 241074 120353 241075 120348 241075 120291 241075 120352 241076 120354 241076 120298 241076 120298 241077 120354 241077 120295 241077 120358 241078 120635 241078 120354 241078 120364 241079 120355 241079 120354 241079 120354 241080 120355 241080 120356 241080 120356 241081 120357 241081 120354 241081 120354 241082 120357 241082 120632 241082 120354 241083 120632 241083 120358 241083 120359 241084 120362 241084 120360 241084 120360 241085 120362 241085 120361 241085 120770 241086 120768 241086 120362 241086 120362 241087 120768 241087 120767 241087 120362 241088 120767 241088 120361 241088 120295 241089 120354 241089 120359 241089 120359 241090 120354 241090 120635 241090 120359 241091 120635 241091 120362 241091 120362 241092 120635 241092 120363 241092 120362 241093 120363 241093 120770 241093 120352 241094 120353 241094 120354 241094 120354 241095 120353 241095 120289 241095 120354 241096 120289 241096 120364 241096 120312 241097 120373 241097 120379 241097 120385 241098 120365 241098 120366 241098 120365 241099 120774 241099 120366 241099 120366 241100 120774 241100 120775 241100 120366 241101 120775 241101 120367 241101 120367 241102 120775 241102 120368 241102 120636 241103 120369 241103 120323 241103 120323 241104 120369 241104 120370 241104 120323 241105 120370 241105 120775 241105 120775 241106 120370 241106 120371 241106 120775 241107 120371 241107 120368 241107 120379 241108 120373 241108 120372 241108 120372 241109 120373 241109 120772 241109 120372 241110 120772 241110 120384 241110 120317 241111 120313 241111 120375 241111 120375 241112 120313 241112 120374 241112 120375 241113 120374 241113 120647 241113 120647 241114 120376 241114 120375 241114 120375 241115 120376 241115 120377 241115 120375 241116 120377 241116 120380 241116 120312 241117 120379 241117 120378 241117 120378 241118 120379 241118 120375 241118 120378 241119 120375 241119 120310 241119 120310 241120 120375 241120 120380 241120 120310 241121 120380 241121 120650 241121 120375 241122 120319 241122 120381 241122 120381 241123 120382 241123 120375 241123 120375 241124 120382 241124 120316 241124 120375 241125 120316 241125 120317 241125 120319 241126 120375 241126 120318 241126 120318 241127 120375 241127 120379 241127 120318 241128 120379 241128 120383 241128 120383 241129 120379 241129 120372 241129 120383 241130 120372 241130 120366 241130 120366 241131 120372 241131 120384 241131 120366 241132 120384 241132 120385 241132 120398 241133 120395 241133 120326 241133 120787 241134 120399 241134 120401 241134 120783 241135 120785 241135 120781 241135 120781 241136 120785 241136 120786 241136 120781 241137 120786 241137 120391 241137 120391 241138 120786 241138 120386 241138 120391 241139 120386 241139 120387 241139 120401 241140 120329 241140 120388 241140 120393 241141 120389 241141 120390 241141 120387 241142 120787 241142 120391 241142 120391 241143 120787 241143 120401 241143 120391 241144 120401 241144 120392 241144 120392 241145 120401 241145 120393 241145 120392 241146 120393 241146 120801 241146 120801 241147 120393 241147 120390 241147 120401 241148 120388 241148 120393 241148 120393 241149 120388 241149 120394 241149 120393 241150 120394 241150 120389 241150 120329 241151 120401 241151 120328 241151 120328 241152 120401 241152 120402 241152 120328 241153 120402 241153 120326 241153 120335 241154 120395 241154 120396 241154 120396 241155 120395 241155 120398 241155 120396 241156 120398 241156 120397 241156 120397 241157 120398 241157 120331 241157 120331 241158 120398 241158 120330 241158 120330 241159 120398 241159 120326 241159 120330 241160 120326 241160 120336 241160 120336 241161 120326 241161 120402 241161 120336 241162 120402 241162 120656 241162 120339 241163 120340 241163 120403 241163 120403 241164 120340 241164 120652 241164 120403 241165 120652 241165 120404 241165 120399 241166 120338 241166 120401 241166 120401 241167 120338 241167 120400 241167 120401 241168 120400 241168 120402 241168 120402 241169 120400 241169 120339 241169 120402 241170 120339 241170 120656 241170 120656 241171 120339 241171 120403 241171 120656 241172 120403 241172 120651 241172 120651 241173 120403 241173 120404 241173 120651 241174 120404 241174 120654 241174 120405 241175 120406 241175 120408 241175 120408 241176 120407 241176 120299 241176 120408 241177 120409 241177 120306 241177 120306 241178 120300 241178 120408 241178 120408 241179 120300 241179 120301 241179 120408 241180 120301 241180 120407 241180 120299 241181 120410 241181 120408 241181 120408 241182 120410 241182 120646 241182 120408 241183 120646 241183 120405 241183 120409 241184 120408 241184 120411 241184 120409 241185 120411 241185 120412 241185 120412 241186 120411 241186 120417 241186 120412 241187 120417 241187 120418 241187 120413 241188 120414 241188 120417 241188 120417 241189 120414 241189 120415 241189 120417 241190 120415 241190 120416 241190 120416 241191 120795 241191 120417 241191 120417 241192 120795 241192 120793 241192 120417 241193 120793 241193 120791 241193 120791 241194 120790 241194 120417 241194 120417 241195 120790 241195 120304 241195 120417 241196 120304 241196 120418 241196 120422 241197 120309 241197 120419 241197 120421 241198 120776 241198 120419 241198 120419 241199 120776 241199 120413 241199 120419 241200 120413 241200 120422 241200 120309 241201 120420 241201 120419 241201 120419 241202 120420 241202 120778 241202 120419 241203 120778 241203 120421 241203 120413 241204 120417 241204 120422 241204 120422 241205 120417 241205 120411 241205 120422 241206 120411 241206 120423 241206 120423 241207 120411 241207 120408 241207 120423 241208 120408 241208 120406 241208 121081 241209 120456 241209 121063 241209 121063 241210 120456 241210 120437 241210 120444 241211 120443 241211 121013 241211 120424 241212 120444 241212 123623 241212 123623 241213 120444 241213 121013 241213 123623 241214 121013 241214 123645 241214 123645 241215 121013 241215 120425 241215 123645 241216 120425 241216 123646 241216 123646 241217 120425 241217 120426 241217 123646 241218 120426 241218 123648 241218 123648 241219 120426 241219 120427 241219 120426 241220 121003 241220 120427 241220 120427 241221 121003 241221 121002 241221 120427 241222 121002 241222 120428 241222 120428 241223 121002 241223 120429 241223 120428 241224 120429 241224 123710 241224 123710 241225 120429 241225 121024 241225 123710 241226 121024 241226 120430 241226 120430 241227 121024 241227 120431 241227 120430 241228 120431 241228 123711 241228 123711 241229 120431 241229 120432 241229 123711 241230 120432 241230 123733 241230 123733 241231 120432 241231 120433 241231 123733 241232 120433 241232 120434 241232 120434 241233 120433 241233 121077 241233 120434 241234 121077 241234 123731 241234 123731 241235 121077 241235 121060 241235 123731 241236 121060 241236 120435 241236 120435 241237 121060 241237 120436 241237 120435 241238 120436 241238 120437 241238 120437 241239 120436 241239 121061 241239 120437 241240 121061 241240 121063 241240 120438 241241 120447 241241 123773 241241 120463 241242 120461 241242 123786 241242 120455 241243 120439 241243 120440 241243 120440 241244 120439 241244 120453 241244 121128 241245 120441 241245 120487 241245 120444 241246 120424 241246 120442 241246 120443 241247 120444 241247 121035 241247 121035 241248 120444 241248 120445 241248 121035 241249 120445 241249 121078 241249 123773 241250 120447 241250 120446 241250 120444 241251 120442 241251 120445 241251 120445 241252 120442 241252 123622 241252 120445 241253 123622 241253 120446 241253 120446 241254 120447 241254 120445 241254 120445 241255 120447 241255 120451 241255 120445 241256 120451 241256 121078 241256 121088 241257 120478 241257 120448 241257 120448 241258 120478 241258 120480 241258 120448 241259 120480 241259 120483 241259 121092 241260 120449 241260 120447 241260 120447 241261 120449 241261 120450 241261 120447 241262 120450 241262 120451 241262 121128 241263 120487 241263 120452 241263 120452 241264 120487 241264 120453 241264 120452 241265 120453 241265 121103 241265 121103 241266 120453 241266 120439 241266 121103 241267 120439 241267 120454 241267 120455 241268 120456 241268 120439 241268 120439 241269 120456 241269 121081 241269 120439 241270 121081 241270 120454 241270 120457 241271 120491 241271 120458 241271 120458 241272 120491 241272 120486 241272 120458 241273 120486 241273 120485 241273 121248 241274 121247 241274 120494 241274 120494 241275 121247 241275 120459 241275 120494 241276 120459 241276 120460 241276 121241 241277 120461 241277 120462 241277 120462 241278 120461 241278 120463 241278 120462 241279 120463 241279 121242 241279 121242 241280 120463 241280 120459 241280 121242 241281 120459 241281 121246 241281 121246 241282 120459 241282 121247 241282 120488 241283 121239 241283 120490 241283 120464 241284 121259 241284 120489 241284 120489 241285 121259 241285 120465 241285 120489 241286 120465 241286 121265 241286 121265 241287 121264 241287 120489 241287 120489 241288 121264 241288 121263 241288 120489 241289 121263 241289 120466 241289 120466 241290 121263 241290 120469 241290 120466 241291 120469 241291 120467 241291 120467 241292 120469 241292 120468 241292 120469 241293 120470 241293 120468 241293 120468 241294 120470 241294 121267 241294 120468 241295 121267 241295 123885 241295 123885 241296 121267 241296 120471 241296 123885 241297 120471 241297 123886 241297 123886 241298 120471 241298 114139 241298 114139 241299 120471 241299 120571 241299 114139 241300 120571 241300 120472 241300 120472 241301 120571 241301 120473 241301 120472 241302 120473 241302 123831 241302 123831 241303 120473 241303 121249 241303 123831 241304 121249 241304 120474 241304 120474 241305 121249 241305 120475 241305 120474 241306 120475 241306 123825 241306 120475 241307 121250 241307 123825 241307 123825 241308 121250 241308 121225 241308 123825 241309 121225 241309 123813 241309 123813 241310 121225 241310 120476 241310 121225 241311 121227 241311 120476 241311 120476 241312 121227 241312 120477 241312 120476 241313 120477 241313 120478 241313 121088 241314 121092 241314 120478 241314 120478 241315 121092 241315 120447 241315 120478 241316 120447 241316 120476 241316 120476 241317 120447 241317 120438 241317 120477 241318 120479 241318 120478 241318 120478 241319 120479 241319 121216 241319 120478 241320 121216 241320 120480 241320 120480 241321 121216 241321 120481 241321 120480 241322 120481 241322 120483 241322 120483 241323 120481 241323 120482 241323 120483 241324 120482 241324 120484 241324 120484 241325 120482 241325 120485 241325 120484 241326 120485 241326 121136 241326 121136 241327 120485 241327 120486 241327 121136 241328 120486 241328 120441 241328 120441 241329 120486 241329 120491 241329 120441 241330 120491 241330 120487 241330 121241 241331 121243 241331 120461 241331 120461 241332 121243 241332 120488 241332 120461 241333 120488 241333 123786 241333 123786 241334 120488 241334 120490 241334 123786 241335 120490 241335 120489 241335 120489 241336 120490 241336 121262 241336 120489 241337 121262 241337 120464 241337 120457 241338 120492 241338 120491 241338 120491 241339 120492 241339 120493 241339 120491 241340 120493 241340 120460 241340 120460 241341 120493 241341 121237 241341 120460 241342 121237 241342 120494 241342 120494 241343 121237 241343 121235 241343 120494 241344 121235 241344 121248 241344 112198 241345 120495 241345 114202 241345 114202 241346 120495 241346 120496 241346 114202 241347 120496 241347 120499 241347 120499 241348 120496 241348 123838 241348 120500 241349 120497 241349 123838 241349 123838 241350 120497 241350 120498 241350 123838 241351 120498 241351 120499 241351 123804 241352 120505 241352 123824 241352 123824 241353 120505 241353 114199 241353 123824 241354 114199 241354 120500 241354 120500 241355 114199 241355 120501 241355 120500 241356 120501 241356 120497 241356 120502 241357 120503 241357 123804 241357 123804 241358 120503 241358 120504 241358 123804 241359 120504 241359 120505 241359 123804 241360 123811 241360 120502 241360 120502 241361 123811 241361 123812 241361 120502 241362 123812 241362 120506 241362 120506 241363 123812 241363 123772 241363 120506 241364 123772 241364 120507 241364 120507 241365 123772 241365 120522 241365 120507 241366 120522 241366 114345 241366 120508 241367 120534 241367 123702 241367 123702 241368 120534 241368 120509 241368 123702 241369 120509 241369 120510 241369 120510 241370 120509 241370 120519 241370 120510 241371 120519 241371 123718 241371 120511 241372 120512 241372 120513 241372 120513 241373 120512 241373 123699 241373 120513 241374 123699 241374 120514 241374 120514 241375 123699 241375 123664 241375 120514 241376 123664 241376 120516 241376 120516 241377 123664 241377 120515 241377 120516 241378 120515 241378 120517 241378 120515 241379 123661 241379 120517 241379 120517 241380 123661 241380 123684 241380 120517 241381 123684 241381 120518 241381 123684 241382 123683 241382 120518 241382 120518 241383 123683 241383 123718 241383 120518 241384 123718 241384 120519 241384 120511 241385 120513 241385 120520 241385 120520 241386 120513 241386 114463 241386 120520 241387 114463 241387 120521 241387 120521 241388 114463 241388 114345 241388 120521 241389 114345 241389 120522 241389 120526 241390 123784 241390 120523 241390 120523 241391 123784 241391 123791 241391 120523 241392 123791 241392 123842 241392 120531 241393 120536 241393 120535 241393 120523 241394 120524 241394 120526 241394 120526 241395 120524 241395 120525 241395 120526 241396 120525 241396 120527 241396 120527 241397 120525 241397 114207 241397 120527 241398 114207 241398 120528 241398 120528 241399 114207 241399 114203 241399 120528 241400 114203 241400 123782 241400 123782 241401 114203 241401 120529 241401 120535 241402 120530 241402 120531 241402 120531 241403 120530 241403 120532 241403 120531 241404 120532 241404 120533 241404 120533 241405 120532 241405 123782 241405 120533 241406 123782 241406 114213 241406 114213 241407 123782 241407 120529 241407 120508 241408 123738 241408 120534 241408 120534 241409 123738 241409 123740 241409 120534 241410 123740 241410 114472 241410 123740 241411 123741 241411 114472 241411 114472 241412 123741 241412 123745 241412 114472 241413 123745 241413 120540 241413 120535 241414 120536 241414 123737 241414 123737 241415 120536 241415 120537 241415 123737 241416 120537 241416 120538 241416 120538 241417 120537 241417 114470 241417 120538 241418 114470 241418 120539 241418 120539 241419 114470 241419 120540 241419 120539 241420 120540 241420 123744 241420 123744 241421 120540 241421 123745 241421 120541 241422 120609 241422 120552 241422 120552 241423 121008 241423 120541 241423 120541 241424 121008 241424 120542 241424 120541 241425 120542 241425 120544 241425 120544 241426 120542 241426 120546 241426 120543 241427 120603 241427 120997 241427 120997 241428 120603 241428 120544 241428 120997 241429 120544 241429 120545 241429 120545 241430 120544 241430 120546 241430 120547 241431 121015 241431 120563 241431 120543 241432 120997 241432 120563 241432 120563 241433 120997 241433 120548 241433 120563 241434 120548 241434 120547 241434 120608 241435 120550 241435 120549 241435 120549 241436 120550 241436 120551 241436 120549 241437 120551 241437 120609 241437 120609 241438 120551 241438 121029 241438 120609 241439 121029 241439 120552 241439 120604 241440 121045 241440 121047 241440 120554 241441 120553 241441 121047 241441 121047 241442 120553 241442 120605 241442 121047 241443 120605 241443 120604 241443 120556 241444 120607 241444 120554 241444 120554 241445 120607 241445 120606 241445 120554 241446 120606 241446 120553 241446 120554 241447 120555 241447 120556 241447 120556 241448 120555 241448 120557 241448 120556 241449 120557 241449 120608 241449 120608 241450 120557 241450 121048 241450 120608 241451 121048 241451 120550 241451 120622 241452 120618 241452 120558 241452 120558 241453 120618 241453 120745 241453 120558 241454 120745 241454 121095 241454 120622 241455 120558 241455 120624 241455 120624 241456 120558 241456 120559 241456 120624 241457 120559 241457 120615 241457 120564 241458 121080 241458 120561 241458 120564 241459 120561 241459 120560 241459 120560 241460 120561 241460 120562 241460 120560 241461 120562 241461 120620 241461 120610 241462 120563 241462 121015 241462 121015 241463 121014 241463 120610 241463 120610 241464 121014 241464 121034 241464 120610 241465 121034 241465 120564 241465 120564 241466 121034 241466 121033 241466 120564 241467 121033 241467 121080 241467 120629 241468 120565 241468 120566 241468 120566 241469 120565 241469 120567 241469 120566 241470 120567 241470 120569 241470 121045 241471 120604 241471 120568 241471 120568 241472 120604 241472 120569 241472 120568 241473 120569 241473 120570 241473 120570 241474 120569 241474 120567 241474 120571 241475 120572 241475 120574 241475 120574 241476 120572 241476 121253 241476 120574 241477 121253 241477 120573 241477 120573 241478 121254 241478 120574 241478 120574 241479 121254 241479 121258 241479 120574 241480 121258 241480 121256 241480 121256 241481 120575 241481 120574 241481 120574 241482 120575 241482 121261 241482 120574 241483 121261 241483 121252 241483 120601 241484 120576 241484 120600 241484 120600 241485 120576 241485 120577 241485 120600 241486 120577 241486 120593 241486 120593 241487 120577 241487 120574 241487 120593 241488 120574 241488 120591 241488 120591 241489 120574 241489 121252 241489 120591 241490 121252 241490 121239 241490 120578 241491 120580 241491 120579 241491 120579 241492 120580 241492 120581 241492 120579 241493 120581 241493 120727 241493 120727 241494 120581 241494 121203 241494 120589 241495 120582 241495 120590 241495 120590 241496 120582 241496 121161 241496 120590 241497 121161 241497 120755 241497 120592 241498 121239 241498 120583 241498 120583 241499 121239 241499 121238 241499 120583 241500 121238 241500 120594 241500 120594 241501 121238 241501 120582 241501 120594 241502 120582 241502 120588 241502 120588 241503 120582 241503 120589 241503 120584 241504 120586 241504 120585 241504 120585 241505 120586 241505 120587 241505 120585 241506 120587 241506 120761 241506 120594 241507 120588 241507 120595 241507 120595 241508 120588 241508 120589 241508 120589 241509 120590 241509 120595 241509 120595 241510 120590 241510 120755 241510 120595 241511 120755 241511 120585 241511 120585 241512 120755 241512 120757 241512 120585 241513 120757 241513 120584 241513 120591 241514 121239 241514 120592 241514 120592 241515 120583 241515 120591 241515 120591 241516 120583 241516 120594 241516 120591 241517 120594 241517 120593 241517 120593 241518 120594 241518 120595 241518 120593 241519 120595 241519 120600 241519 120600 241520 120595 241520 120596 241520 120761 241521 120762 241521 120585 241521 120585 241522 120762 241522 120578 241522 120585 241523 120578 241523 120595 241523 120595 241524 120578 241524 120579 241524 120595 241525 120579 241525 120596 241525 120596 241526 120579 241526 120727 241526 120596 241527 120727 241527 120600 241527 120600 241528 120727 241528 120597 241528 120600 241529 120597 241529 120599 241529 120736 241530 120598 241530 120734 241530 120734 241531 120598 241531 120731 241531 120599 241532 120731 241532 120600 241532 120600 241533 120731 241533 120598 241533 120600 241534 120598 241534 120601 241534 120601 241535 120598 241535 120736 241535 120601 241536 120736 241536 120737 241536 120563 241537 120610 241537 120602 241537 120541 241538 120544 241538 120602 241538 120544 241539 120603 241539 120602 241539 120602 241540 120603 241540 120543 241540 120602 241541 120543 241541 120563 241541 120569 241542 120604 241542 120614 241542 120614 241543 120604 241543 120605 241543 120605 241544 120553 241544 120614 241544 120614 241545 120553 241545 120606 241545 120614 241546 120606 241546 120607 241546 120607 241547 120556 241547 120614 241547 120614 241548 120556 241548 120608 241548 120614 241549 120608 241549 120612 241549 120612 241550 120608 241550 120549 241550 120612 241551 120549 241551 120602 241551 120602 241552 120549 241552 120609 241552 120602 241553 120609 241553 120541 241553 120628 241554 120611 241554 120626 241554 120622 241555 120623 241555 120625 241555 120610 241556 120611 241556 120602 241556 120602 241557 120611 241557 120628 241557 120602 241558 120628 241558 120612 241558 120612 241559 120628 241559 120614 241559 120629 241560 120566 241560 120613 241560 120613 241561 120566 241561 120569 241561 120613 241562 120569 241562 120627 241562 120627 241563 120569 241563 120614 241563 120624 241564 120615 241564 120617 241564 120617 241565 120615 241565 120616 241565 120617 241566 120616 241566 120751 241566 120744 241567 120746 241567 120745 241567 120744 241568 120745 241568 120625 241568 120625 241569 120745 241569 120618 241569 120625 241570 120618 241570 120622 241570 120564 241571 120560 241571 120619 241571 120619 241572 120560 241572 120620 241572 120619 241573 120620 241573 120625 241573 120625 241574 120620 241574 120621 241574 120625 241575 120621 241575 120744 241575 120622 241576 120624 241576 120623 241576 120623 241577 120624 241577 120617 241577 120623 241578 120617 241578 120625 241578 120625 241579 120617 241579 120626 241579 120625 241580 120626 241580 120619 241580 120619 241581 120626 241581 120611 241581 120619 241582 120611 241582 120564 241582 120564 241583 120611 241583 120610 241583 120614 241584 120628 241584 120627 241584 120627 241585 120628 241585 120626 241585 120627 241586 120626 241586 120613 241586 120613 241587 120626 241587 120617 241587 120613 241588 120617 241588 120629 241588 120629 241589 120617 241589 120751 241589 120629 241590 120751 241590 120753 241590 120355 241591 121345 241591 120356 241591 120356 241592 121345 241592 121344 241592 121344 241593 121343 241593 120356 241593 120356 241594 121343 241594 120630 241594 120356 241595 120630 241595 120357 241595 120357 241596 120630 241596 120631 241596 120357 241597 120631 241597 120632 241597 120631 241598 120633 241598 120632 241598 120632 241599 120633 241599 120634 241599 120632 241600 120634 241600 120358 241600 120358 241601 120634 241601 121340 241601 120358 241602 121340 241602 120635 241602 121593 241603 121552 241603 120323 241603 120323 241604 121552 241604 120636 241604 120636 241605 121552 241605 120369 241605 120369 241606 121552 241606 120637 241606 120369 241607 120637 241607 120370 241607 120638 241608 120639 241608 120368 241608 120637 241609 120640 241609 120370 241609 120370 241610 120640 241610 120638 241610 120370 241611 120638 241611 120371 241611 120371 241612 120638 241612 120368 241612 120639 241613 121567 241613 120368 241613 120368 241614 121567 241614 120641 241614 120368 241615 120641 241615 120367 241615 121291 241616 120642 241616 120294 241616 120294 241617 120642 241617 120344 241617 120344 241618 120642 241618 120345 241618 120345 241619 120642 241619 121298 241619 120345 241620 121298 241620 120347 241620 120347 241621 121298 241621 121300 241621 120347 241622 121300 241622 120643 241622 120643 241623 121300 241623 121316 241623 120643 241624 121316 241624 120644 241624 120644 241625 121316 241625 120343 241625 120343 241626 121316 241626 121315 241626 120343 241627 121315 241627 120349 241627 121395 241628 120405 241628 121394 241628 121394 241629 120405 241629 120646 241629 121394 241630 120646 241630 120645 241630 120645 241631 120646 241631 120410 241631 120645 241632 120410 241632 121385 241632 121385 241633 120410 241633 120299 241633 120647 241634 121491 241634 121516 241634 120647 241635 121516 241635 120376 241635 120376 241636 121516 241636 120648 241636 120376 241637 120648 241637 120377 241637 120377 241638 120648 241638 121521 241638 120377 241639 121521 241639 120380 241639 121537 241640 120650 241640 121538 241640 121538 241641 120650 241641 120380 241641 121538 241642 120380 241642 120649 241642 120649 241643 120380 241643 121521 241643 121540 241644 120310 241644 121544 241644 121544 241645 120310 241645 120650 241645 121544 241646 120650 241646 121545 241646 121545 241647 120650 241647 121537 241647 120651 241648 120654 241648 121749 241648 120340 241649 121707 241649 120652 241649 120652 241650 121707 241650 121763 241650 121763 241651 121750 241651 120652 241651 120652 241652 121750 241652 120653 241652 120652 241653 120653 241653 120404 241653 120404 241654 120653 241654 120654 241654 120654 241655 120653 241655 120655 241655 120654 241656 120655 241656 121749 241656 121747 241657 121783 241657 120656 241657 120651 241658 121749 241658 120656 241658 120656 241659 121749 241659 121748 241659 120656 241660 121748 241660 121747 241660 120131 241661 121977 241661 120657 241661 120131 241662 120657 241662 120658 241662 120658 241663 120657 241663 120659 241663 120658 241664 120659 241664 120660 241664 120660 241665 120659 241665 121978 241665 120660 241666 121978 241666 120127 241666 121978 241667 120661 241667 120127 241667 120127 241668 120661 241668 121976 241668 120127 241669 121976 241669 120662 241669 121976 241670 121986 241670 120662 241670 120662 241671 121986 241671 122012 241671 120662 241672 122012 241672 120128 241672 120663 241673 120664 241673 120665 241673 120665 241674 120664 241674 120670 241674 120666 241675 120061 241675 120062 241675 120062 241676 122068 241676 120666 241676 120666 241677 122068 241677 120667 241677 120666 241678 120667 241678 120669 241678 120667 241679 122060 241679 120669 241679 120669 241680 122060 241680 120668 241680 120669 241681 120668 241681 120664 241681 120664 241682 120668 241682 122064 241682 120664 241683 122064 241683 120670 241683 122066 241684 120671 241684 120672 241684 120663 241685 120665 241685 120672 241685 120672 241686 120665 241686 120673 241686 120672 241687 120673 241687 122066 241687 120020 241688 121834 241688 120674 241688 120674 241689 121834 241689 120675 241689 120674 241690 120675 241690 120074 241690 120074 241691 120675 241691 121836 241691 120074 241692 121836 241692 120676 241692 120676 241693 121836 241693 121837 241693 120676 241694 121837 241694 120075 241694 120075 241695 121837 241695 121821 241695 122214 241696 120677 241696 122213 241696 122213 241697 120677 241697 120133 241697 122213 241698 120133 241698 122210 241698 122210 241699 120133 241699 120679 241699 122210 241700 120679 241700 120678 241700 120678 241701 120679 241701 120680 241701 120681 241702 122317 241702 119827 241702 119827 241703 122317 241703 120682 241703 119827 241704 120682 241704 120683 241704 120683 241705 120682 241705 122322 241705 120683 241706 122322 241706 119770 241706 119770 241707 122322 241707 122309 241707 119787 241708 119882 241708 120684 241708 120684 241709 119882 241709 119883 241709 120684 241710 119883 241710 120685 241710 120685 241711 119883 241711 120686 241711 120685 241712 120686 241712 122392 241712 122392 241713 120686 241713 119780 241713 119797 241714 119796 241714 122620 241714 119797 241715 122620 241715 120687 241715 120687 241716 122620 241716 120688 241716 120687 241717 120688 241717 119875 241717 119875 241718 120688 241718 120689 241718 119875 241719 120689 241719 119876 241719 120689 241720 122623 241720 119876 241720 119876 241721 122623 241721 122621 241721 119876 241722 122621 241722 120690 241722 122621 241723 122628 241723 120690 241723 120690 241724 122628 241724 120691 241724 120690 241725 120691 241725 119877 241725 120692 241726 119854 241726 120697 241726 120694 241727 119853 241727 122738 241727 122738 241728 120693 241728 120694 241728 120694 241729 120693 241729 122720 241729 120694 241730 122720 241730 120695 241730 120695 241731 122720 241731 122728 241731 122728 241732 122727 241732 120695 241732 120695 241733 122727 241733 120696 241733 120695 241734 120696 241734 119854 241734 119854 241735 120696 241735 122722 241735 119854 241736 122722 241736 120697 241736 120700 241737 122755 241737 120698 241737 120692 241738 120697 241738 120698 241738 120698 241739 120697 241739 120699 241739 120698 241740 120699 241740 120700 241740 120701 241741 119568 241741 123050 241741 120701 241742 123050 241742 120703 241742 123050 241743 120702 241743 120703 241743 120703 241744 120702 241744 120704 241744 120703 241745 120704 241745 119636 241745 119636 241746 120704 241746 120705 241746 119636 241747 120705 241747 120706 241747 120706 241748 120705 241748 120707 241748 120706 241749 120707 241749 120709 241749 120707 241750 120708 241750 120709 241750 120709 241751 120708 241751 119586 241751 120709 241752 119586 241752 119635 241752 119647 241753 120710 241753 120713 241753 119653 241754 119592 241754 120711 241754 120711 241755 119592 241755 123208 241755 123208 241756 123203 241756 120711 241756 120711 241757 123203 241757 123202 241757 120711 241758 123202 241758 119648 241758 123202 241759 123254 241759 119648 241759 119648 241760 123254 241760 120712 241760 119648 241761 120712 241761 120710 241761 120710 241762 120712 241762 123257 241762 120710 241763 123257 241763 120713 241763 119647 241764 120713 241764 120714 241764 120714 241765 120713 241765 123251 241765 120714 241766 123251 241766 123253 241766 119539 241767 122804 241767 120715 241767 120715 241768 122804 241768 120716 241768 120715 241769 120716 241769 120717 241769 120717 241770 120716 241770 120718 241770 120717 241771 120718 241771 120719 241771 120719 241772 120718 241772 119532 241772 119604 241773 120720 241773 120721 241773 119604 241774 120721 241774 120722 241774 120722 241775 120721 241775 120724 241775 120722 241776 120724 241776 120723 241776 120723 241777 120724 241777 119603 241777 119603 241778 120724 241778 120725 241778 119603 241779 120725 241779 119605 241779 119605 241780 120725 241780 119602 241780 119602 241781 120725 241781 120726 241781 119602 241782 120726 241782 119597 241782 120597 241783 120727 241783 121203 241783 121203 241784 120728 241784 120597 241784 120597 241785 120728 241785 120729 241785 120597 241786 120729 241786 120599 241786 120599 241787 120729 241787 121224 241787 121224 241788 120730 241788 120599 241788 120599 241789 120730 241789 120732 241789 120599 241790 120732 241790 120731 241790 120731 241791 120732 241791 120734 241791 120732 241792 120733 241792 120734 241792 120734 241793 120733 241793 120735 241793 120734 241794 120735 241794 120736 241794 120736 241795 120735 241795 120740 241795 120576 241796 120601 241796 121219 241796 121219 241797 120601 241797 120737 241797 121219 241798 120737 241798 120738 241798 120738 241799 120737 241799 120736 241799 120738 241800 120736 241800 120739 241800 120739 241801 120736 241801 120740 241801 120620 241802 120562 241802 120741 241802 120620 241803 120741 241803 120621 241803 120621 241804 120741 241804 120742 241804 120621 241805 120742 241805 120744 241805 120744 241806 120742 241806 120743 241806 120744 241807 120743 241807 120746 241807 121095 241808 120745 241808 121089 241808 121089 241809 120745 241809 120746 241809 121089 241810 120746 241810 120747 241810 120747 241811 120746 241811 120743 241811 120615 241812 120559 241812 121118 241812 120615 241813 121118 241813 120616 241813 120616 241814 121118 241814 120748 241814 120616 241815 120748 241815 120749 241815 120749 241816 120750 241816 120616 241816 120616 241817 120750 241817 121141 241817 120616 241818 121141 241818 120751 241818 121141 241819 121140 241819 120751 241819 120751 241820 121140 241820 120752 241820 120751 241821 120752 241821 120753 241821 120752 241822 121138 241822 120753 241822 120753 241823 121138 241823 120565 241823 120753 241824 120565 241824 120629 241824 120754 241825 120580 241825 120578 241825 121161 241826 120756 241826 120755 241826 120755 241827 120756 241827 120757 241827 120757 241828 120756 241828 120584 241828 120584 241829 120756 241829 120758 241829 120584 241830 120758 241830 120586 241830 120586 241831 120758 241831 120759 241831 120586 241832 120759 241832 120587 241832 120587 241833 120759 241833 120760 241833 120587 241834 120760 241834 120761 241834 120761 241835 120760 241835 121181 241835 120761 241836 121181 241836 120763 241836 120754 241837 120578 241837 120763 241837 120763 241838 120578 241838 120762 241838 120763 241839 120762 241839 120761 241839 120764 241840 120359 241840 121282 241840 121282 241841 120359 241841 120360 241841 121282 241842 120360 241842 120765 241842 120765 241843 120360 241843 120361 241843 120765 241844 120361 241844 120766 241844 120766 241845 120361 241845 120767 241845 120766 241846 120767 241846 121303 241846 121303 241847 120767 241847 120768 241847 121303 241848 120768 241848 120769 241848 120769 241849 120768 241849 120770 241849 120769 241850 120770 241850 120771 241850 120771 241851 120770 241851 120363 241851 120771 241852 120363 241852 120280 241852 121600 241853 120384 241853 121618 241853 121618 241854 120384 241854 120772 241854 121618 241855 120772 241855 121584 241855 121600 241856 121608 241856 120384 241856 120384 241857 121608 241857 120773 241857 120384 241858 120773 241858 120385 241858 120773 241859 121619 241859 120385 241859 120385 241860 121619 241860 121639 241860 120385 241861 121639 241861 120365 241861 120365 241862 121639 241862 121620 241862 120365 241863 121620 241863 120774 241863 120774 241864 121620 241864 121630 241864 120774 241865 121630 241865 120775 241865 120775 241866 121630 241866 121595 241866 120308 241867 120780 241867 120309 241867 120309 241868 120780 241868 120420 241868 121445 241869 120413 241869 121446 241869 121446 241870 120413 241870 120776 241870 121446 241871 120776 241871 120777 241871 120777 241872 120776 241872 120421 241872 120777 241873 120421 241873 121440 241873 121440 241874 120421 241874 120778 241874 121440 241875 120778 241875 120779 241875 120779 241876 120778 241876 120420 241876 120779 241877 120420 241877 121439 241877 121439 241878 120420 241878 120780 241878 120783 241879 120781 241879 120782 241879 120782 241880 121683 241880 120783 241880 120783 241881 121683 241881 120784 241881 120783 241882 120784 241882 120785 241882 120785 241883 120784 241883 121651 241883 120785 241884 121651 241884 120786 241884 120786 241885 121651 241885 121647 241885 120786 241886 121647 241886 120386 241886 120386 241887 121647 241887 120387 241887 121647 241888 121654 241888 120387 241888 120387 241889 121654 241889 121645 241889 120387 241890 121645 241890 120787 241890 120787 241891 121645 241891 121666 241891 120787 241892 121666 241892 120337 241892 120415 241893 120788 241893 121476 241893 120305 241894 120304 241894 120789 241894 120789 241895 120304 241895 120790 241895 120789 241896 120790 241896 121474 241896 121474 241897 120790 241897 120791 241897 121474 241898 120791 241898 120792 241898 120792 241899 120791 241899 120793 241899 120792 241900 120793 241900 120794 241900 120794 241901 120793 241901 120795 241901 120794 241902 120795 241902 121476 241902 121476 241903 120795 241903 120416 241903 121476 241904 120416 241904 120415 241904 120388 241905 120324 241905 121717 241905 120388 241906 121717 241906 120394 241906 120394 241907 121717 241907 120796 241907 120394 241908 120796 241908 120797 241908 120798 241909 120389 241909 120799 241909 120799 241910 120389 241910 120394 241910 120799 241911 120394 241911 120800 241911 120800 241912 120394 241912 120797 241912 120342 241913 120392 241913 121724 241913 121724 241914 120392 241914 120801 241914 121724 241915 120801 241915 121725 241915 121725 241916 120801 241916 120390 241916 121725 241917 120390 241917 120802 241917 120802 241918 120390 241918 120389 241918 120802 241919 120389 241919 120803 241919 120803 241920 120389 241920 120798 241920 120019 241921 121843 241921 120082 241921 120082 241922 121843 241922 121862 241922 120011 241923 120081 241923 121860 241923 121860 241924 120081 241924 120076 241924 121860 241925 120076 241925 120804 241925 120804 241926 120076 241926 120805 241926 120804 241927 120805 241927 121858 241927 121858 241928 120805 241928 120077 241928 121858 241929 120077 241929 121856 241929 121856 241930 120077 241930 120082 241930 121856 241931 120082 241931 121863 241931 121863 241932 120082 241932 121862 241932 120113 241933 120114 241933 121975 241933 121975 241934 121974 241934 120113 241934 120113 241935 121974 241935 120807 241935 120113 241936 120807 241936 120806 241936 120806 241937 120807 241937 121945 241937 120806 241938 121945 241938 120115 241938 120115 241939 121945 241939 120809 241939 120115 241940 120809 241940 120808 241940 120808 241941 120809 241941 121950 241941 120808 241942 121950 241942 120810 241942 120810 241943 121950 241943 121941 241943 120810 241944 121941 241944 120117 241944 120117 241945 121941 241945 120811 241945 120117 241946 120811 241946 121967 241946 122056 241947 120812 241947 120813 241947 120813 241948 120812 241948 120118 241948 120813 241949 120118 241949 120814 241949 120815 241950 120124 241950 122028 241950 122028 241951 120124 241951 120812 241951 122028 241952 120812 241952 120816 241952 120816 241953 120812 241953 122056 241953 120815 241954 120817 241954 120124 241954 120124 241955 120817 241955 122030 241955 120124 241956 122030 241956 120119 241956 122030 241957 122029 241957 120119 241957 120119 241958 122029 241958 120818 241958 120119 241959 120818 241959 120121 241959 120121 241960 120818 241960 122005 241960 120121 241961 122005 241961 120819 241961 120821 241962 120088 241962 120820 241962 120820 241963 122131 241963 120821 241963 120821 241964 122131 241964 122098 241964 120821 241965 122098 241965 120089 241965 120089 241966 122098 241966 122111 241966 120089 241967 122111 241967 120822 241967 120822 241968 122111 241968 120824 241968 120822 241969 120824 241969 120823 241969 120823 241970 120824 241970 122113 241970 120823 241971 122113 241971 120090 241971 120090 241972 122113 241972 120825 241972 120090 241973 120825 241973 120091 241973 120091 241974 120825 241974 122105 241974 120091 241975 122105 241975 122104 241975 120012 241976 121881 241976 120826 241976 121879 241977 120827 241977 120828 241977 120828 241978 120827 241978 120079 241978 120828 241979 120079 241979 121891 241979 121891 241980 120079 241980 120087 241980 121891 241981 120087 241981 121890 241981 121890 241982 120087 241982 120085 241982 121890 241983 120085 241983 120829 241983 120829 241984 120085 241984 120084 241984 120829 241985 120084 241985 120826 241985 120826 241986 120084 241986 120083 241986 120826 241987 120083 241987 120012 241987 120036 241988 120830 241988 120831 241988 120831 241989 120830 241989 122254 241989 122254 241990 122264 241990 120831 241990 120831 241991 122264 241991 122252 241991 120831 241992 122252 241992 120832 241992 120832 241993 122252 241993 122255 241993 120832 241994 122255 241994 120139 241994 120024 241995 120140 241995 122261 241995 122261 241996 120140 241996 120833 241996 122261 241997 120833 241997 122262 241997 122262 241998 120833 241998 120139 241998 122262 241999 120139 241999 120834 241999 120834 242000 120139 242000 122255 242000 120835 242001 120837 242001 120836 242001 120836 242002 120837 242002 120096 242002 120836 242003 120096 242003 120838 242003 122183 242004 120841 242004 120839 242004 120839 242005 120841 242005 120837 242005 120839 242006 120837 242006 122173 242006 122173 242007 120837 242007 120835 242007 122183 242008 120840 242008 120841 242008 120841 242009 120840 242009 122181 242009 120841 242010 122181 242010 120095 242010 122181 242011 122189 242011 120095 242011 120095 242012 122189 242012 120842 242012 120095 242013 120842 242013 120094 242013 120094 242014 120842 242014 120843 242014 120094 242015 120843 242015 120093 242015 120025 242016 120845 242016 120844 242016 120844 242017 120845 242017 120142 242017 120142 242018 120845 242018 120846 242018 120846 242019 120845 242019 120847 242019 120846 242020 120847 242020 120848 242020 120848 242021 120847 242021 120849 242021 120848 242022 120849 242022 120850 242022 120850 242023 120849 242023 120851 242023 120850 242024 120851 242024 120852 242024 120852 242025 120851 242025 120854 242025 120852 242026 120854 242026 120853 242026 120853 242027 120854 242027 120031 242027 120853 242028 120031 242028 120030 242028 119776 242029 122339 242029 119831 242029 119831 242030 122339 242030 122338 242030 122338 242031 120855 242031 119831 242031 119831 242032 120855 242032 122336 242032 119831 242033 122336 242033 119832 242033 119832 242034 122336 242034 120856 242034 120856 242035 122336 242035 120859 242035 119764 242036 120857 242036 122346 242036 122346 242037 120857 242037 119829 242037 122346 242038 119829 242038 120858 242038 120858 242039 119829 242039 120856 242039 120858 242040 120856 242040 122347 242040 122347 242041 120856 242041 120859 242041 120861 242042 120860 242042 122508 242042 122508 242043 122502 242043 120861 242043 120861 242044 122502 242044 122475 242044 120861 242045 122475 242045 119862 242045 119862 242046 122475 242046 120862 242046 119862 242047 120862 242047 120863 242047 120863 242048 120862 242048 120864 242048 120863 242049 120864 242049 119863 242049 119863 242050 120864 242050 120866 242050 119863 242051 120866 242051 120865 242051 120865 242052 120866 242052 120868 242052 120865 242053 120868 242053 120867 242053 120867 242054 120868 242054 120869 242054 120867 242055 120869 242055 122512 242055 120870 242056 120871 242056 119765 242056 119765 242057 120871 242057 120872 242057 120872 242058 120871 242058 120873 242058 120873 242059 120871 242059 122379 242059 120873 242060 122379 242060 120876 242060 122359 242061 119835 242061 122376 242061 122376 242062 119835 242062 120874 242062 122376 242063 120874 242063 122377 242063 122377 242064 120874 242064 120875 242064 122377 242065 120875 242065 122378 242065 122378 242066 120875 242066 120876 242066 122378 242067 120876 242067 122372 242067 122372 242068 120876 242068 122379 242068 119884 242069 122416 242069 119886 242069 119886 242070 122416 242070 122445 242070 122445 242071 122436 242071 119886 242071 119886 242072 122436 242072 120877 242072 119886 242073 120877 242073 120878 242073 120878 242074 120877 242074 119888 242074 119888 242075 120877 242075 120879 242075 119778 242076 119885 242076 120880 242076 120880 242077 119885 242077 120881 242077 120880 242078 120881 242078 120882 242078 120882 242079 120881 242079 119888 242079 120882 242080 119888 242080 120883 242080 120883 242081 119888 242081 120879 242081 120884 242082 120885 242082 122550 242082 120884 242083 122550 242083 119865 242083 119865 242084 122550 242084 122568 242084 119865 242085 122568 242085 122533 242085 122533 242086 122556 242086 119865 242086 119865 242087 122556 242087 122555 242087 119865 242088 122555 242088 119866 242088 122555 242089 122536 242089 119866 242089 119866 242090 122536 242090 122538 242090 119866 242091 122538 242091 119867 242091 122538 242092 122539 242092 119867 242092 119867 242093 122539 242093 120886 242093 119867 242094 120886 242094 120887 242094 120887 242095 120886 242095 122509 242095 120887 242096 122509 242096 119873 242096 120890 242097 120888 242097 119820 242097 119820 242098 120889 242098 120890 242098 120890 242099 120889 242099 122632 242099 120890 242100 122632 242100 120891 242100 120891 242101 122632 242101 120892 242101 120891 242102 120892 242102 120893 242102 120893 242103 120892 242103 122645 242103 120893 242104 122645 242104 119836 242104 119836 242105 122645 242105 120894 242105 119836 242106 120894 242106 120895 242106 120895 242107 120894 242107 120896 242107 120895 242108 120896 242108 120898 242108 120898 242109 120896 242109 120897 242109 120898 242110 120897 242110 119815 242110 119779 242111 120900 242111 120899 242111 120899 242112 120900 242112 119889 242112 119889 242113 120900 242113 120901 242113 120901 242114 120900 242114 122463 242114 120901 242115 122463 242115 119891 242115 120902 242116 119893 242116 122473 242116 122473 242117 119893 242117 119895 242117 122473 242118 119895 242118 120903 242118 120903 242119 119895 242119 119896 242119 120903 242120 119896 242120 120904 242120 120904 242121 119896 242121 119891 242121 120904 242122 119891 242122 122457 242122 122457 242123 119891 242123 122463 242123 119840 242124 119825 242124 120905 242124 119840 242125 120905 242125 120906 242125 120906 242126 120905 242126 122693 242126 120906 242127 122693 242127 120907 242127 120907 242128 122707 242128 120906 242128 120906 242129 122707 242129 122705 242129 120906 242130 122705 242130 119842 242130 122705 242131 122691 242131 119842 242131 119842 242132 122691 242132 120908 242132 119842 242133 120908 242133 119838 242133 120908 242134 122688 242134 119838 242134 119838 242135 122688 242135 122704 242135 119838 242136 122704 242136 120909 242136 120909 242137 122704 242137 120910 242137 120909 242138 120910 242138 119837 242138 120913 242139 120911 242139 119582 242139 119582 242140 120912 242140 120913 242140 120913 242141 120912 242141 120914 242141 120913 242142 120914 242142 120915 242142 120915 242143 120914 242143 120916 242143 120915 242144 120916 242144 119628 242144 119628 242145 120916 242145 120918 242145 119628 242146 120918 242146 120917 242146 120917 242147 120918 242147 120919 242147 120917 242148 120919 242148 120921 242148 120921 242149 120919 242149 120920 242149 120921 242150 120920 242150 120922 242150 120922 242151 120920 242151 123075 242151 120922 242152 123075 242152 119576 242152 119538 242153 119536 242153 120925 242153 120925 242154 119536 242154 122842 242154 120927 242155 120923 242155 122825 242155 122825 242156 120923 242156 119664 242156 122825 242157 119664 242157 120924 242157 120924 242158 119664 242158 120925 242158 120924 242159 120925 242159 122827 242159 122827 242160 120925 242160 122842 242160 120926 242161 122824 242161 120929 242161 120927 242162 122825 242162 120929 242162 120929 242163 122825 242163 120928 242163 120929 242164 120928 242164 120926 242164 120930 242165 119584 242165 122991 242165 120930 242166 122991 242166 120933 242166 120933 242167 122991 242167 120931 242167 120933 242168 120931 242168 120934 242168 120935 242169 120932 242169 122985 242169 122985 242170 120932 242170 120933 242170 122985 242171 120933 242171 123017 242171 123017 242172 120933 242172 120934 242172 120935 242173 122992 242173 120932 242173 120932 242174 122992 242174 120936 242174 120932 242175 120936 242175 119630 242175 120936 242176 123008 242176 119630 242176 119630 242177 123008 242177 123010 242177 119630 242178 123010 242178 119632 242178 119632 242179 123010 242179 119581 242179 119632 242180 119581 242180 119580 242180 119641 242181 119640 242181 120937 242181 120937 242182 120938 242182 119641 242182 119641 242183 120938 242183 120939 242183 119641 242184 120939 242184 119642 242184 119642 242185 120939 242185 120940 242185 119642 242186 120940 242186 119643 242186 119643 242187 120940 242187 120941 242187 120941 242188 120940 242188 123149 242188 120941 242189 123149 242189 120942 242189 123149 242190 123150 242190 120942 242190 120942 242191 123150 242191 120943 242191 120942 242192 120943 242192 120944 242192 120944 242193 120943 242193 120945 242193 120944 242194 120945 242194 120946 242194 119644 242195 123209 242195 123229 242195 119644 242196 123229 242196 119638 242196 119638 242197 123229 242197 120947 242197 119638 242198 120947 242198 123242 242198 123242 242199 123241 242199 119638 242199 119638 242200 123241 242200 120948 242200 119638 242201 120948 242201 120949 242201 120948 242202 120950 242202 120949 242202 120949 242203 120950 242203 123236 242203 120949 242204 123236 242204 120951 242204 120951 242205 123236 242205 123235 242205 120951 242206 123235 242206 120952 242206 120952 242207 123235 242207 120953 242207 120952 242208 120953 242208 119593 242208 122961 242209 122974 242209 120954 242209 120954 242210 122974 242210 119620 242210 119620 242211 122974 242211 119612 242211 119612 242212 122974 242212 120955 242212 119612 242213 120955 242213 119613 242213 119613 242214 120955 242214 119614 242214 119614 242215 120955 242215 120956 242215 119614 242216 120956 242216 119611 242216 119611 242217 120956 242217 119558 242217 119611 242218 119558 242218 119610 242218 122857 242219 122855 242219 119658 242219 119658 242220 122855 242220 120957 242220 120957 242221 122855 242221 120958 242221 120958 242222 122855 242222 120959 242222 120958 242223 120959 242223 119660 242223 119660 242224 120959 242224 119661 242224 119661 242225 120959 242225 122875 242225 119661 242226 122875 242226 120961 242226 120961 242227 122875 242227 120960 242227 120961 242228 120960 242228 119662 242228 119608 242229 120962 242229 122915 242229 122915 242230 122914 242230 119608 242230 119608 242231 122914 242231 122908 242231 119608 242232 122908 242232 120966 242232 120966 242233 122908 242233 120963 242233 120966 242234 120963 242234 122907 242234 122930 242235 119543 242235 120964 242235 122907 242236 120965 242236 120966 242236 120966 242237 120965 242237 120967 242237 120966 242238 120967 242238 119606 242238 119606 242239 120967 242239 122930 242239 119606 242240 122930 242240 119607 242240 119607 242241 122930 242241 120964 242241 120968 242242 120969 242242 120977 242242 120969 242243 120968 242243 120970 242243 120970 242244 120968 242244 120971 242244 120970 242245 120971 242245 120972 242245 120973 242246 119351 242246 120974 242246 120974 242247 119351 242247 120975 242247 120974 242248 120975 242248 123515 242248 123515 242249 120975 242249 119366 242249 123515 242250 119366 242250 120976 242250 120976 242251 119366 242251 120978 242251 120976 242252 120978 242252 120977 242252 120977 242253 120978 242253 120979 242253 120977 242254 120979 242254 120968 242254 119324 242255 120982 242255 119326 242255 119326 242256 120982 242256 119392 242256 120980 242257 120981 242257 120982 242257 120982 242258 120981 242258 120983 242258 120982 242259 120983 242259 119392 242259 120980 242260 120984 242260 120981 242260 120981 242261 120984 242261 120985 242261 120981 242262 120985 242262 119387 242262 119387 242263 120985 242263 120989 242263 120985 242264 120986 242264 120989 242264 120989 242265 120986 242265 120987 242265 120989 242266 120987 242266 123426 242266 123426 242267 120988 242267 120989 242267 120989 242268 120988 242268 119323 242268 120989 242269 119323 242269 120990 242269 119385 242270 119383 242270 119321 242270 119321 242271 123463 242271 119385 242271 119385 242272 123463 242272 123462 242272 119385 242273 123462 242273 120991 242273 120991 242274 123462 242274 120992 242274 123462 242275 123461 242275 120992 242275 120992 242276 123461 242276 120994 242276 120992 242277 120994 242277 120993 242277 120993 242278 120994 242278 119386 242278 119386 242279 120994 242279 120995 242279 120995 242280 120994 242280 123459 242280 120995 242281 123459 242281 123443 242281 121031 242282 120996 242282 121005 242282 120999 242283 120997 242283 120545 242283 120997 242284 120999 242284 120548 242284 121006 242285 121004 242285 121011 242285 120998 242286 121015 242286 120547 242286 120547 242287 120548 242287 120998 242287 120998 242288 120548 242288 120999 242288 120998 242289 120999 242289 121017 242289 121023 242290 120429 242290 121000 242290 121000 242291 120429 242291 121002 242291 121000 242292 121002 242292 121001 242292 121001 242293 121002 242293 121003 242293 121011 242294 121004 242294 121012 242294 121012 242295 121004 242295 120426 242295 121012 242296 120426 242296 120425 242296 121003 242297 120426 242297 121001 242297 121001 242298 120426 242298 121004 242298 121001 242299 121004 242299 121000 242299 121000 242300 121004 242300 121006 242300 121000 242301 121006 242301 121023 242301 121023 242302 121006 242302 121005 242302 121023 242303 121005 242303 121032 242303 121032 242304 121005 242304 120996 242304 121030 242305 121031 242305 121009 242305 121009 242306 121031 242306 121005 242306 121009 242307 121005 242307 121010 242307 121010 242308 121005 242308 121006 242308 121010 242309 121006 242309 121007 242309 121007 242310 121006 242310 121011 242310 120552 242311 121030 242311 121008 242311 121008 242312 121030 242312 121009 242312 121008 242313 121009 242313 120542 242313 120542 242314 121009 242314 121010 242314 120542 242315 121010 242315 120546 242315 120546 242316 121010 242316 121007 242316 120546 242317 121007 242317 120545 242317 120545 242318 121007 242318 121011 242318 120545 242319 121011 242319 120999 242319 120999 242320 121011 242320 121012 242320 120999 242321 121012 242321 121017 242321 121017 242322 121012 242322 120425 242322 121017 242323 120425 242323 121013 242323 121016 242324 121034 242324 120998 242324 120998 242325 121034 242325 121014 242325 120998 242326 121014 242326 121015 242326 120998 242327 121017 242327 121016 242327 121016 242328 121017 242328 121013 242328 121016 242329 121013 242329 120443 242329 121021 242330 121029 242330 120551 242330 121019 242331 121018 242331 121022 242331 121020 242332 121018 242332 121057 242332 121057 242333 121018 242333 121019 242333 121057 242334 121019 242334 121055 242334 121055 242335 121019 242335 121054 242335 121024 242336 121022 242336 120431 242336 120431 242337 121022 242337 121018 242337 120431 242338 121018 242338 120432 242338 120432 242339 121018 242339 121020 242339 120432 242340 121020 242340 120433 242340 121026 242341 121021 242341 121028 242341 121028 242342 121021 242342 120551 242342 121028 242343 120551 242343 121044 242343 121044 242344 120551 242344 120550 242344 121052 242345 121054 242345 121027 242345 121027 242346 121054 242346 121019 242346 121027 242347 121019 242347 121025 242347 121025 242348 121019 242348 121022 242348 121025 242349 121022 242349 121023 242349 121023 242350 121022 242350 121024 242350 121023 242351 121024 242351 120429 242351 121023 242352 121032 242352 121025 242352 121025 242353 121032 242353 121026 242353 121025 242354 121026 242354 121027 242354 121027 242355 121026 242355 121028 242355 121027 242356 121028 242356 121052 242356 121052 242357 121028 242357 121044 242357 120552 242358 121029 242358 121030 242358 121030 242359 121029 242359 121021 242359 121030 242360 121021 242360 121031 242360 121031 242361 121021 242361 121026 242361 121031 242362 121026 242362 120996 242362 120996 242363 121026 242363 121032 242363 121033 242364 121034 242364 121016 242364 121033 242365 121016 242365 121080 242365 120443 242366 121035 242366 121016 242366 121016 242367 121035 242367 121036 242367 121016 242368 121036 242368 121080 242368 121038 242369 121039 242369 121060 242369 121066 242370 121037 242370 121074 242370 121084 242371 121041 242371 121066 242371 121075 242372 121074 242372 121038 242372 121038 242373 121074 242373 121037 242373 121038 242374 121037 242374 121039 242374 121039 242375 121037 242375 121066 242375 121039 242376 121066 242376 121040 242376 121040 242377 121066 242377 121041 242377 121040 242378 121041 242378 121062 242378 121042 242379 121064 242379 121073 242379 121073 242380 121064 242380 121043 242380 121073 242381 121043 242381 121074 242381 121044 242382 120550 242382 121048 242382 121044 242383 121048 242383 121059 242383 121045 242384 121071 242384 121047 242384 121047 242385 121071 242385 121046 242385 121047 242386 121046 242386 120554 242386 120554 242387 121046 242387 121058 242387 120554 242388 121058 242388 120555 242388 120555 242389 121058 242389 121059 242389 120555 242390 121059 242390 120557 242390 120557 242391 121059 242391 121048 242391 121072 242392 121049 242392 121050 242392 121050 242393 121049 242393 121051 242393 121050 242394 121051 242394 121053 242394 121052 242395 121053 242395 121054 242395 121054 242396 121053 242396 121051 242396 121054 242397 121051 242397 121055 242397 121055 242398 121051 242398 121056 242398 121055 242399 121056 242399 121057 242399 121057 242400 121056 242400 121076 242400 121057 242401 121076 242401 121020 242401 121020 242402 121076 242402 121077 242402 121020 242403 121077 242403 120433 242403 121071 242404 121072 242404 121046 242404 121046 242405 121072 242405 121050 242405 121046 242406 121050 242406 121058 242406 121058 242407 121050 242407 121053 242407 121058 242408 121053 242408 121059 242408 121059 242409 121053 242409 121052 242409 121059 242410 121052 242410 121044 242410 121060 242411 121039 242411 120436 242411 120436 242412 121039 242412 121040 242412 120436 242413 121040 242413 121061 242413 121061 242414 121040 242414 121062 242414 121061 242415 121062 242415 121063 242415 121070 242416 121068 242416 121042 242416 121042 242417 121068 242417 121067 242417 121042 242418 121067 242418 121064 242418 121064 242419 121067 242419 121065 242419 121064 242420 121065 242420 121043 242420 121074 242421 121043 242421 121066 242421 121066 242422 121043 242422 121065 242422 121066 242423 121065 242423 121084 242423 121084 242424 121065 242424 121067 242424 121084 242425 121067 242425 121086 242425 121086 242426 121067 242426 121068 242426 121086 242427 121068 242427 121069 242427 121069 242428 121068 242428 121070 242428 121069 242429 121070 242429 121045 242429 121045 242430 121070 242430 121071 242430 121071 242431 121070 242431 121042 242431 121071 242432 121042 242432 121072 242432 121072 242433 121042 242433 121073 242433 121072 242434 121073 242434 121049 242434 121049 242435 121073 242435 121074 242435 121049 242436 121074 242436 121051 242436 121051 242437 121074 242437 121075 242437 121051 242438 121075 242438 121056 242438 121056 242439 121075 242439 121038 242439 121056 242440 121038 242440 121076 242440 121076 242441 121038 242441 121060 242441 121076 242442 121060 242442 121077 242442 121078 242443 120451 242443 121079 242443 121078 242444 121079 242444 121035 242444 121035 242445 121079 242445 121036 242445 121036 242446 121079 242446 120561 242446 121036 242447 120561 242447 121080 242447 120562 242448 120561 242448 121091 242448 121091 242449 120561 242449 121079 242449 121091 242450 121079 242450 120450 242450 120450 242451 121079 242451 120451 242451 120568 242452 120570 242452 121087 242452 121082 242453 121081 242453 121063 242453 121063 242454 121062 242454 121082 242454 121082 242455 121062 242455 121041 242455 121082 242456 121041 242456 121110 242456 121110 242457 121041 242457 121083 242457 121083 242458 121041 242458 121084 242458 121083 242459 121084 242459 121112 242459 121112 242460 121084 242460 121086 242460 121112 242461 121086 242461 121085 242461 121085 242462 121086 242462 121069 242462 121085 242463 121069 242463 121087 242463 121087 242464 121069 242464 121045 242464 121087 242465 121045 242465 120568 242465 121102 242466 121088 242466 120448 242466 120741 242467 120562 242467 121091 242467 121099 242468 121089 242468 120747 242468 121091 242469 120450 242469 120449 242469 120742 242470 120741 242470 121101 242470 121101 242471 120741 242471 121091 242471 121101 242472 121091 242472 121090 242472 121090 242473 121091 242473 120449 242473 121090 242474 120449 242474 121092 242474 121096 242475 121093 242475 121097 242475 121097 242476 121093 242476 121094 242476 121097 242477 121094 242477 121099 242477 121099 242478 121094 242478 121095 242478 121099 242479 121095 242479 121089 242479 120448 242480 121096 242480 121102 242480 121102 242481 121096 242481 121097 242481 121102 242482 121097 242482 121098 242482 121098 242483 121097 242483 121099 242483 121098 242484 121099 242484 121100 242484 121100 242485 121099 242485 120747 242485 121100 242486 120747 242486 120743 242486 120743 242487 120742 242487 121100 242487 121100 242488 120742 242488 121101 242488 121100 242489 121101 242489 121098 242489 121098 242490 121101 242490 121090 242490 121098 242491 121090 242491 121102 242491 121102 242492 121090 242492 121092 242492 121102 242493 121092 242493 121088 242493 121103 242494 120454 242494 121108 242494 121103 242495 121108 242495 120452 242495 120567 242496 120565 242496 121125 242496 120567 242497 121125 242497 121111 242497 121111 242498 121125 242498 121142 242498 121111 242499 121142 242499 121104 242499 121104 242500 121142 242500 121147 242500 121104 242501 121147 242501 121105 242501 121105 242502 121147 242502 121106 242502 121105 242503 121106 242503 121109 242503 121109 242504 121106 242504 121107 242504 121109 242505 121107 242505 121108 242505 121108 242506 121107 242506 121145 242506 121108 242507 121145 242507 120452 242507 120454 242508 121081 242508 121108 242508 121108 242509 121081 242509 121082 242509 121108 242510 121082 242510 121109 242510 121109 242511 121082 242511 121110 242511 121109 242512 121110 242512 121105 242512 121105 242513 121110 242513 121083 242513 121105 242514 121083 242514 121104 242514 120570 242515 120567 242515 121087 242515 121087 242516 120567 242516 121111 242516 121087 242517 121111 242517 121085 242517 121085 242518 121111 242518 121104 242518 121085 242519 121104 242519 121112 242519 121112 242520 121104 242520 121083 242520 120558 242521 121095 242521 121115 242521 121115 242522 121095 242522 121094 242522 121115 242523 121094 242523 121116 242523 121116 242524 121094 242524 121093 242524 121116 242525 121093 242525 121113 242525 121113 242526 121093 242526 121096 242526 121113 242527 121096 242527 120483 242527 120483 242528 121096 242528 120448 242528 120559 242529 120558 242529 121114 242529 121114 242530 120558 242530 121115 242530 121114 242531 121115 242531 121133 242531 121133 242532 121115 242532 121116 242532 121133 242533 121116 242533 121135 242533 121135 242534 121116 242534 121113 242534 121135 242535 121113 242535 120484 242535 120484 242536 121113 242536 120483 242536 121127 242537 121141 242537 120750 242537 121122 242538 121124 242538 121120 242538 121120 242539 121117 242539 121152 242539 121118 242540 120559 242540 121114 242540 121152 242541 121119 242541 121120 242541 121120 242542 121119 242542 121121 242542 121120 242543 121121 242543 121122 242543 121122 242544 121121 242544 121123 242544 121122 242545 121123 242545 121124 242545 121142 242546 121125 242546 121144 242546 121144 242547 121125 242547 121137 242547 121144 242548 121137 242548 121126 242548 121126 242549 121137 242549 121139 242549 121126 242550 121139 242550 121127 242550 120441 242551 121128 242551 121129 242551 121129 242552 121128 242552 121146 242552 121129 242553 121146 242553 121130 242553 121148 242554 121149 242554 121130 242554 121130 242555 121149 242555 121150 242555 121130 242556 121150 242556 121129 242556 121129 242557 121150 242557 121131 242557 121129 242558 121131 242558 120441 242558 120441 242559 121131 242559 121151 242559 120441 242560 121151 242560 121136 242560 121118 242561 121114 242561 121132 242561 121132 242562 121114 242562 121133 242562 121132 242563 121133 242563 121134 242563 121134 242564 121133 242564 121135 242564 121134 242565 121135 242565 121151 242565 121151 242566 121135 242566 120484 242566 121151 242567 120484 242567 121136 242567 121125 242568 120565 242568 121137 242568 121137 242569 120565 242569 121138 242569 121137 242570 121138 242570 121139 242570 121139 242571 121138 242571 120752 242571 121139 242572 120752 242572 121127 242572 121127 242573 120752 242573 121140 242573 121127 242574 121140 242574 121141 242574 121147 242575 121142 242575 121143 242575 121143 242576 121142 242576 121144 242576 121143 242577 121144 242577 121123 242577 121123 242578 121144 242578 121126 242578 121123 242579 121126 242579 121124 242579 121124 242580 121126 242580 121127 242580 121124 242581 121127 242581 121120 242581 121120 242582 121127 242582 120750 242582 121120 242583 120750 242583 121117 242583 121117 242584 120750 242584 120749 242584 121117 242585 120749 242585 120748 242585 121106 242586 121148 242586 121107 242586 121107 242587 121148 242587 121130 242587 121107 242588 121130 242588 121145 242588 121145 242589 121130 242589 121146 242589 121145 242590 121146 242590 120452 242590 120452 242591 121146 242591 121128 242591 121106 242592 121147 242592 121148 242592 121148 242593 121147 242593 121143 242593 121148 242594 121143 242594 121149 242594 121149 242595 121143 242595 121123 242595 121149 242596 121123 242596 121150 242596 121150 242597 121123 242597 121121 242597 121150 242598 121121 242598 121131 242598 121131 242599 121121 242599 121119 242599 121131 242600 121119 242600 121151 242600 121151 242601 121119 242601 121152 242601 121151 242602 121152 242602 121134 242602 121134 242603 121152 242603 121117 242603 121134 242604 121117 242604 121132 242604 121132 242605 121117 242605 120748 242605 121132 242606 120748 242606 121118 242606 120485 242607 120482 242607 121153 242607 121153 242608 120482 242608 121154 242608 121153 242609 121154 242609 121176 242609 121176 242610 121154 242610 121155 242610 121176 242611 121155 242611 121177 242611 121177 242612 121155 242612 121158 242612 121160 242613 121159 242613 121172 242613 121172 242614 121159 242614 120581 242614 121172 242615 120581 242615 120580 242615 120482 242616 120481 242616 121154 242616 121154 242617 120481 242617 121156 242617 121154 242618 121156 242618 121155 242618 121155 242619 121156 242619 121157 242619 121157 242620 121214 242620 121155 242620 121155 242621 121214 242621 121159 242621 121155 242622 121159 242622 121158 242622 121158 242623 121159 242623 121160 242623 121214 242624 121215 242624 121159 242624 121159 242625 121215 242625 121206 242625 121159 242626 121206 242626 120581 242626 120581 242627 121206 242627 121205 242627 120581 242628 121205 242628 121203 242628 121185 242629 120760 242629 120759 242629 121187 242630 120756 242630 121169 242630 121169 242631 120756 242631 121161 242631 121162 242632 120492 242632 120457 242632 120493 242633 120492 242633 121236 242633 121236 242634 120492 242634 121162 242634 121236 242635 121162 242635 121163 242635 121170 242636 121194 242636 121164 242636 121164 242637 121194 242637 121165 242637 121164 242638 121165 242638 121166 242638 121166 242639 121165 242639 121167 242639 121166 242640 121167 242640 121197 242640 121184 242641 121186 242641 121168 242641 121168 242642 121186 242642 121187 242642 121168 242643 121187 242643 121192 242643 121192 242644 121187 242644 121169 242644 121192 242645 121170 242645 121168 242645 121168 242646 121170 242646 121164 242646 121168 242647 121164 242647 121184 242647 121184 242648 121164 242648 121166 242648 121184 242649 121166 242649 121183 242649 121183 242650 121166 242650 121197 242650 121183 242651 121197 242651 121198 242651 121198 242652 121160 242652 121171 242652 121171 242653 121160 242653 121172 242653 121175 242654 121174 242654 121173 242654 121173 242655 121174 242655 121189 242655 121173 242656 121189 242656 120458 242656 120458 242657 120485 242657 121173 242657 121173 242658 120485 242658 121153 242658 121173 242659 121153 242659 121175 242659 121175 242660 121153 242660 121176 242660 121177 242661 121158 242661 121191 242661 121191 242662 121158 242662 121199 242662 121191 242663 121199 242663 121190 242663 121190 242664 121199 242664 121178 242664 121190 242665 121178 242665 121196 242665 121188 242666 121196 242666 121195 242666 120457 242667 121188 242667 121162 242667 121162 242668 121188 242668 121195 242668 121162 242669 121195 242669 121163 242669 121163 242670 121195 242670 121179 242670 121163 242671 121179 242671 121234 242671 121234 242672 121179 242672 121193 242672 121234 242673 121193 242673 121245 242673 121245 242674 121193 242674 121180 242674 121245 242675 121180 242675 121244 242675 121244 242676 121180 242676 121240 242676 120760 242677 121185 242677 121181 242677 121181 242678 121185 242678 121182 242678 121181 242679 121182 242679 120763 242679 120763 242680 121182 242680 121171 242680 120763 242681 121171 242681 120754 242681 120754 242682 121171 242682 121172 242682 120754 242683 121172 242683 120580 242683 121198 242684 121171 242684 121183 242684 121183 242685 121171 242685 121182 242685 121183 242686 121182 242686 121184 242686 121184 242687 121182 242687 121185 242687 121184 242688 121185 242688 121186 242688 121186 242689 121185 242689 120759 242689 121186 242690 120759 242690 121187 242690 121187 242691 120759 242691 120758 242691 121187 242692 120758 242692 120756 242692 120457 242693 120458 242693 121188 242693 121188 242694 120458 242694 121189 242694 121188 242695 121189 242695 121196 242695 121196 242696 121189 242696 121174 242696 121196 242697 121174 242697 121190 242697 121190 242698 121174 242698 121175 242698 121190 242699 121175 242699 121191 242699 121191 242700 121175 242700 121176 242700 121191 242701 121176 242701 121177 242701 121161 242702 121240 242702 121169 242702 121169 242703 121240 242703 121180 242703 121169 242704 121180 242704 121192 242704 121192 242705 121180 242705 121193 242705 121192 242706 121193 242706 121170 242706 121170 242707 121193 242707 121179 242707 121170 242708 121179 242708 121194 242708 121194 242709 121179 242709 121195 242709 121194 242710 121195 242710 121165 242710 121165 242711 121195 242711 121196 242711 121165 242712 121196 242712 121167 242712 121167 242713 121196 242713 121178 242713 121167 242714 121178 242714 121197 242714 121197 242715 121178 242715 121199 242715 121197 242716 121199 242716 121198 242716 121198 242717 121199 242717 121158 242717 121198 242718 121158 242718 121160 242718 121157 242719 121156 242719 121230 242719 121228 242720 121226 242720 121200 242720 121201 242721 121204 242721 121210 242721 121202 242722 121208 242722 121204 242722 120728 242723 121203 242723 121202 242723 121202 242724 121203 242724 121205 242724 121202 242725 121205 242725 121208 242725 121204 242726 121201 242726 121202 242726 121202 242727 121201 242727 120729 242727 121202 242728 120729 242728 120728 242728 121205 242729 121206 242729 121208 242729 121208 242730 121206 242730 121207 242730 121208 242731 121207 242731 121204 242731 121204 242732 121207 242732 121209 242732 121204 242733 121209 242733 121210 242733 121210 242734 121209 242734 121231 242734 121210 242735 121231 242735 121221 242735 121221 242736 121231 242736 121218 242736 121221 242737 121218 242737 121211 242737 121211 242738 121218 242738 121212 242738 121211 242739 121212 242739 121220 242739 121213 242740 120738 242740 120739 242740 120739 242741 120740 242741 121213 242741 121213 242742 120740 242742 120735 242742 121213 242743 120735 242743 121222 242743 121222 242744 120735 242744 120733 242744 121222 242745 120733 242745 121223 242745 121223 242746 120733 242746 120732 242746 121223 242747 120732 242747 120730 242747 121230 242748 121232 242748 121157 242748 121157 242749 121232 242749 121233 242749 121157 242750 121233 242750 121214 242750 121214 242751 121233 242751 121215 242751 121156 242752 120481 242752 121230 242752 121230 242753 120481 242753 121216 242753 121230 242754 121216 242754 121217 242754 121217 242755 121216 242755 120479 242755 121217 242756 120479 242756 120477 242756 120576 242757 121219 242757 121200 242757 121200 242758 121219 242758 121220 242758 121200 242759 121220 242759 121228 242759 121228 242760 121220 242760 121212 242760 121228 242761 121212 242761 121229 242761 121229 242762 121212 242762 121218 242762 121219 242763 120738 242763 121220 242763 121220 242764 120738 242764 121213 242764 121220 242765 121213 242765 121211 242765 121211 242766 121213 242766 121222 242766 121211 242767 121222 242767 121221 242767 121221 242768 121222 242768 121223 242768 121221 242769 121223 242769 121210 242769 121210 242770 121223 242770 120730 242770 121210 242771 120730 242771 121201 242771 121201 242772 120730 242772 121224 242772 121201 242773 121224 242773 120729 242773 121225 242774 121226 242774 121227 242774 121227 242775 121226 242775 121228 242775 121227 242776 121228 242776 120477 242776 120477 242777 121228 242777 121229 242777 120477 242778 121229 242778 121217 242778 121217 242779 121229 242779 121218 242779 121217 242780 121218 242780 121230 242780 121230 242781 121218 242781 121231 242781 121230 242782 121231 242782 121232 242782 121232 242783 121231 242783 121209 242783 121232 242784 121209 242784 121233 242784 121233 242785 121209 242785 121207 242785 121233 242786 121207 242786 121215 242786 121215 242787 121207 242787 121206 242787 121234 242788 121248 242788 121163 242788 121163 242789 121248 242789 121235 242789 121163 242790 121235 242790 121236 242790 121236 242791 121235 242791 121237 242791 121236 242792 121237 242792 120493 242792 121238 242793 121239 242793 121243 242793 121243 242794 121239 242794 120488 242794 121243 242795 121244 242795 121240 242795 121238 242796 121243 242796 120582 242796 120582 242797 121243 242797 121240 242797 120582 242798 121240 242798 121161 242798 121241 242799 120462 242799 121242 242799 121243 242800 121241 242800 121244 242800 121244 242801 121241 242801 121242 242801 121244 242802 121242 242802 121245 242802 121245 242803 121242 242803 121246 242803 121245 242804 121246 242804 121234 242804 121234 242805 121246 242805 121247 242805 121234 242806 121247 242806 121248 242806 121250 242807 120475 242807 121251 242807 120577 242808 120576 242808 121200 242808 120571 242809 120574 242809 120473 242809 120473 242810 120574 242810 121251 242810 120473 242811 121251 242811 121249 242811 121249 242812 121251 242812 120475 242812 121225 242813 121250 242813 121226 242813 121226 242814 121250 242814 121251 242814 121226 242815 121251 242815 121200 242815 121200 242816 121251 242816 120574 242816 121200 242817 120574 242817 120577 242817 121252 242818 120490 242818 121239 242818 120490 242819 121252 242819 121261 242819 120573 242820 121253 242820 121267 242820 121267 242821 121253 242821 120572 242821 121267 242822 120572 242822 120471 242822 120471 242823 120572 242823 120571 242823 121257 242824 121254 242824 121255 242824 121257 242825 121255 242825 121260 242825 121261 242826 120575 242826 121260 242826 121260 242827 120575 242827 121256 242827 121260 242828 121256 242828 121257 242828 121257 242829 121256 242829 121258 242829 121257 242830 121258 242830 121254 242830 121265 242831 120465 242831 121255 242831 121255 242832 120465 242832 121259 242832 121255 242833 121259 242833 121260 242833 121260 242834 121259 242834 120464 242834 121260 242835 120464 242835 121261 242835 121261 242836 120464 242836 121262 242836 121261 242837 121262 242837 120490 242837 121263 242838 121264 242838 120469 242838 120469 242839 121264 242839 121265 242839 120469 242840 121265 242840 121266 242840 121266 242841 121265 242841 121255 242841 121254 242842 120573 242842 121255 242842 121255 242843 120573 242843 121267 242843 121255 242844 121267 242844 121266 242844 121266 242845 121267 242845 120470 242845 121266 242846 120470 242846 120469 242846 121268 242847 121277 242847 121269 242847 121273 242848 120764 242848 121275 242848 121275 242849 120764 242849 121284 242849 121275 242850 121284 242850 121270 242850 121270 242851 121284 242851 121286 242851 121270 242852 121286 242852 121269 242852 121269 242853 121286 242853 121271 242853 121269 242854 121271 242854 121268 242854 121268 242855 121271 242855 121285 242855 120297 242856 121273 242856 121272 242856 121272 242857 121273 242857 121275 242857 121272 242858 121275 242858 121274 242858 121274 242859 121275 242859 121270 242859 121274 242860 121270 242860 121276 242860 121276 242861 121270 242861 121269 242861 121276 242862 121269 242862 120163 242862 120163 242863 121269 242863 121277 242863 121291 242864 120297 242864 121272 242864 121291 242865 121272 242865 121278 242865 121278 242866 121272 242866 121274 242866 121278 242867 121274 242867 121290 242867 121274 242868 121276 242868 121290 242868 121290 242869 121276 242869 120163 242869 121290 242870 120163 242870 120210 242870 121279 242871 121287 242871 121280 242871 120181 242872 120160 242872 121280 242872 120765 242873 121281 242873 121282 242873 121282 242874 121281 242874 121283 242874 121282 242875 121283 242875 120764 242875 120764 242876 121283 242876 121284 242876 120160 242877 121285 242877 121280 242877 121280 242878 121285 242878 121271 242878 121280 242879 121271 242879 121279 242879 121279 242880 121271 242880 121286 242880 120181 242881 121280 242881 121305 242881 121305 242882 121280 242882 121287 242882 121305 242883 121287 242883 121307 242883 121307 242884 121287 242884 121288 242884 121307 242885 121288 242885 121308 242885 121308 242886 121288 242886 120766 242886 121308 242887 120766 242887 121303 242887 121286 242888 121284 242888 121279 242888 121279 242889 121284 242889 121283 242889 121279 242890 121283 242890 121287 242890 121287 242891 121283 242891 121281 242891 121287 242892 121281 242892 121288 242892 121288 242893 121281 242893 120765 242893 121288 242894 120765 242894 120766 242894 121295 242895 121292 242895 120211 242895 120210 242896 121289 242896 121290 242896 121290 242897 121289 242897 121293 242897 121290 242898 121293 242898 121278 242898 121278 242899 121293 242899 121294 242899 121278 242900 121294 242900 121291 242900 121289 242901 121292 242901 121293 242901 121293 242902 121292 242902 121295 242902 121293 242903 121295 242903 121294 242903 121294 242904 121295 242904 121297 242904 120211 242905 121314 242905 121295 242905 121295 242906 121314 242906 121311 242906 121295 242907 121311 242907 121297 242907 121297 242908 121311 242908 121296 242908 121297 242909 121296 242909 121299 242909 121291 242910 121294 242910 120642 242910 120642 242911 121294 242911 121297 242911 120642 242912 121297 242912 121298 242912 121298 242913 121297 242913 121299 242913 121298 242914 121299 242914 121300 242914 121302 242915 121301 242915 120771 242915 120771 242916 121301 242916 120769 242916 121302 242917 121306 242917 121301 242917 121301 242918 121306 242918 121308 242918 121301 242919 121308 242919 120769 242919 120769 242920 121308 242920 121303 242920 121310 242921 120181 242921 121304 242921 121304 242922 120181 242922 121305 242922 121304 242923 121305 242923 121306 242923 121306 242924 121305 242924 121307 242924 121306 242925 121307 242925 121308 242925 120771 242926 120280 242926 121302 242926 121302 242927 120280 242927 121321 242927 121302 242928 121321 242928 121306 242928 121306 242929 121321 242929 121309 242929 121306 242930 121309 242930 121304 242930 121304 242931 121309 242931 121323 242931 121304 242932 121323 242932 121310 242932 121310 242933 121323 242933 121325 242933 121319 242934 121311 242934 121312 242934 121312 242935 121311 242935 121314 242935 121312 242936 121314 242936 121313 242936 121313 242937 121314 242937 120211 242937 121316 242938 121300 242938 121317 242938 121317 242939 121300 242939 121299 242939 121317 242940 121299 242940 121319 242940 121319 242941 121299 242941 121296 242941 121319 242942 121296 242942 121311 242942 121315 242943 121316 242943 121333 242943 121333 242944 121316 242944 121317 242944 121333 242945 121317 242945 121318 242945 121318 242946 121317 242946 121319 242946 121318 242947 121319 242947 121331 242947 121331 242948 121319 242948 121312 242948 121331 242949 121312 242949 121330 242949 121330 242950 121312 242950 121313 242950 121320 242951 121340 242951 121322 242951 120280 242952 121320 242952 121321 242952 121321 242953 121320 242953 121322 242953 121321 242954 121322 242954 121309 242954 121309 242955 121322 242955 121324 242955 121309 242956 121324 242956 121323 242956 121323 242957 121324 242957 121335 242957 121323 242958 121335 242958 121325 242958 121325 242959 121335 242959 120184 242959 121329 242960 121326 242960 121360 242960 121315 242961 121333 242961 121327 242961 121327 242962 121333 242962 121351 242962 121327 242963 121351 242963 121328 242963 121329 242964 121360 242964 121330 242964 121330 242965 121360 242965 121331 242965 121331 242966 121360 242966 121365 242966 121331 242967 121365 242967 121318 242967 121365 242968 121332 242968 121318 242968 121318 242969 121332 242969 121364 242969 121318 242970 121364 242970 121333 242970 121333 242971 121364 242971 121350 242971 121333 242972 121350 242972 121351 242972 121334 242973 120630 242973 121343 242973 120630 242974 121334 242974 120631 242974 120631 242975 121334 242975 121339 242975 120631 242976 121339 242976 120633 242976 120184 242977 121335 242977 120185 242977 120185 242978 121335 242978 121336 242978 121337 242979 120191 242979 121336 242979 121336 242980 120191 242980 121338 242980 121336 242981 121338 242981 120185 242981 121374 242982 121373 242982 121337 242982 120633 242983 121339 242983 120634 242983 120634 242984 121339 242984 121322 242984 120634 242985 121322 242985 121340 242985 121324 242986 121322 242986 121349 242986 121349 242987 121322 242987 121339 242987 121349 242988 121339 242988 121341 242988 121341 242989 121339 242989 121334 242989 121341 242990 121334 242990 121347 242990 121347 242991 121334 242991 121343 242991 121347 242992 121343 242992 121342 242992 121342 242993 121343 242993 121344 242993 121342 242994 121344 242994 121346 242994 121346 242995 121344 242995 121345 242995 121337 242996 121336 242996 121374 242996 121374 242997 121336 242997 121348 242997 121374 242998 121348 242998 121379 242998 121346 242999 121378 242999 121342 242999 121342 243000 121378 243000 121379 243000 121342 243001 121379 243001 121347 243001 121347 243002 121379 243002 121348 243002 121347 243003 121348 243003 121341 243003 121341 243004 121348 243004 121336 243004 121341 243005 121336 243005 121349 243005 121349 243006 121336 243006 121335 243006 121349 243007 121335 243007 121324 243007 121362 243008 121350 243008 121364 243008 120287 243009 121352 243009 121369 243009 120282 243010 120281 243010 121362 243010 121363 243011 121368 243011 121354 243011 121350 243012 121362 243012 121351 243012 121351 243013 121362 243013 120281 243013 121351 243014 120281 243014 121328 243014 121352 243015 120284 243015 121369 243015 121369 243016 120284 243016 121353 243016 121369 243017 121353 243017 121354 243017 121354 243018 121353 243018 121355 243018 121354 243019 121355 243019 121363 243019 121359 243020 121356 243020 120286 243020 121367 243021 121381 243021 121357 243021 121357 243022 121381 243022 121359 243022 121357 243023 121359 243023 121358 243023 121358 243024 121359 243024 120286 243024 121358 243025 120286 243025 121370 243025 121363 243026 121365 243026 121361 243026 121361 243027 121365 243027 121360 243027 121361 243028 121360 243028 120220 243028 120220 243029 121360 243029 121326 243029 121363 243030 121361 243030 121368 243030 121368 243031 121361 243031 120218 243031 121368 243032 120218 243032 120217 243032 120284 243033 120282 243033 121353 243033 121353 243034 120282 243034 121362 243034 121353 243035 121362 243035 121355 243035 121355 243036 121362 243036 121364 243036 121355 243037 121364 243037 121363 243037 121363 243038 121364 243038 121332 243038 121363 243039 121332 243039 121365 243039 120215 243040 121366 243040 120217 243040 120217 243041 121366 243041 121367 243041 120217 243042 121367 243042 121368 243042 121368 243043 121367 243043 121357 243043 121368 243044 121357 243044 121354 243044 121354 243045 121357 243045 121358 243045 121354 243046 121358 243046 121369 243046 121369 243047 121358 243047 121370 243047 121369 243048 121370 243048 120287 243048 121376 243049 121371 243049 121377 243049 121376 243050 121377 243050 121382 243050 121382 243051 121377 243051 120290 243051 121382 243052 120290 243052 120292 243052 121380 243053 120213 243053 121375 243053 121375 243054 120213 243054 121372 243054 121375 243055 121372 243055 121373 243055 121373 243056 121374 243056 121375 243056 121375 243057 121374 243057 121371 243057 121375 243058 121371 243058 121380 243058 121380 243059 121371 243059 121376 243059 121345 243060 120290 243060 121346 243060 121346 243061 120290 243061 121377 243061 121346 243062 121377 243062 121378 243062 121378 243063 121377 243063 121371 243063 121378 243064 121371 243064 121379 243064 121379 243065 121371 243065 121374 243065 121382 243066 121359 243066 121381 243066 121356 243067 121359 243067 120293 243067 120293 243068 121359 243068 121382 243068 120293 243069 121382 243069 120292 243069 121367 243070 121380 243070 121381 243070 121381 243071 121380 243071 121376 243071 121381 243072 121376 243072 121382 243072 121367 243073 121366 243073 121380 243073 121380 243074 121366 243074 120215 243074 121380 243075 120215 243075 120213 243075 121383 243076 121387 243076 121384 243076 121397 243077 120207 243077 121399 243077 121399 243078 120207 243078 121383 243078 121399 243079 121383 243079 121400 243079 121400 243080 121383 243080 121384 243080 120645 243081 121385 243081 121389 243081 121389 243082 121385 243082 121403 243082 121389 243083 121403 243083 121387 243083 121387 243084 121403 243084 121386 243084 121387 243085 121386 243085 121384 243085 120207 243086 120208 243086 121383 243086 121383 243087 120208 243087 121391 243087 121383 243088 121391 243088 121387 243088 121387 243089 121391 243089 121388 243089 121387 243090 121388 243090 121389 243090 121389 243091 121388 243091 121392 243091 121389 243092 121392 243092 120645 243092 120645 243093 121392 243093 121394 243093 120208 243094 120209 243094 121391 243094 121391 243095 120209 243095 121390 243095 121391 243096 121390 243096 121388 243096 121388 243097 121390 243097 121405 243097 121388 243098 121405 243098 121392 243098 121392 243099 121405 243099 121393 243099 121392 243100 121393 243100 121394 243100 121394 243101 121393 243101 121395 243101 121396 243102 121397 243102 121412 243102 121412 243103 121397 243103 121399 243103 121412 243104 121399 243104 121398 243104 121398 243105 121399 243105 121400 243105 121398 243106 121400 243106 121416 243106 121416 243107 121400 243107 121384 243107 121416 243108 121384 243108 121401 243108 121401 243109 121384 243109 121386 243109 121401 243110 121386 243110 121402 243110 121402 243111 121386 243111 121403 243111 121402 243112 121403 243112 120303 243112 120303 243113 121403 243113 121385 243113 120307 243114 121395 243114 121393 243114 120307 243115 121393 243115 121404 243115 121404 243116 121393 243116 121405 243116 121404 243117 121405 243117 121426 243117 121426 243118 121405 243118 121390 243118 121426 243119 121390 243119 121406 243119 121406 243120 121390 243120 120209 243120 121406 243121 120209 243121 121407 243121 121411 243122 120204 243122 121396 243122 121434 243123 121408 243123 121418 243123 121418 243124 121408 243124 121409 243124 121418 243125 121409 243125 121413 243125 121413 243126 121409 243126 120203 243126 121413 243127 120203 243127 121410 243127 121396 243128 121412 243128 121411 243128 121411 243129 121412 243129 121398 243129 121411 243130 121398 243130 121417 243130 121410 243131 120204 243131 121413 243131 121413 243132 120204 243132 121411 243132 121413 243133 121411 243133 121418 243133 121418 243134 121411 243134 121417 243134 121418 243135 121417 243135 121414 243135 121414 243136 121417 243136 121415 243136 121402 243137 121415 243137 121401 243137 121401 243138 121415 243138 121417 243138 121401 243139 121417 243139 121416 243139 121416 243140 121417 243140 121398 243140 121420 243141 121431 243141 121419 243141 121434 243142 121418 243142 121419 243142 121419 243143 121418 243143 121414 243143 121419 243144 121414 243144 121420 243144 121420 243145 121414 243145 121415 243145 121420 243146 121415 243146 120302 243146 120302 243147 121415 243147 121402 243147 120302 243148 121402 243148 120303 243148 121428 243149 121443 243149 121441 243149 121423 243150 121421 243150 121422 243150 121422 243151 121421 243151 120308 243151 121422 243152 120307 243152 121423 243152 121423 243153 120307 243153 121404 243153 121423 243154 121404 243154 121424 243154 121424 243155 121404 243155 121426 243155 121424 243156 121426 243156 121425 243156 121425 243157 121426 243157 121406 243157 121425 243158 121406 243158 121427 243158 121427 243159 121406 243159 121407 243159 121427 243160 121428 243160 121425 243160 121425 243161 121428 243161 121441 243161 121425 243162 121441 243162 121424 243162 121424 243163 121441 243163 121429 243163 121424 243164 121429 243164 121423 243164 121423 243165 121429 243165 121430 243165 121423 243166 121430 243166 121421 243166 121431 243167 121432 243167 121419 243167 121419 243168 121432 243168 121433 243168 121419 243169 121433 243169 121434 243169 121434 243170 121433 243170 121408 243170 121408 243171 121433 243171 121463 243171 121408 243172 121463 243172 121409 243172 121463 243173 121435 243173 121409 243173 121409 243174 121435 243174 120202 243174 121409 243175 120202 243175 120203 243175 121436 243176 121467 243176 121450 243176 121437 243177 121438 243177 121447 243177 121453 243178 121449 243178 121454 243178 121421 243179 121430 243179 121448 243179 121439 243180 120780 243180 121448 243180 121448 243181 120780 243181 120308 243181 121448 243182 120308 243182 121421 243182 120779 243183 121438 243183 121440 243183 121440 243184 121438 243184 121437 243184 121440 243185 121437 243185 120777 243185 120777 243186 121437 243186 121446 243186 121442 243187 121444 243187 121456 243187 121449 243188 121429 243188 121454 243188 121454 243189 121429 243189 121441 243189 121454 243190 121441 243190 121442 243190 121442 243191 121441 243191 121443 243191 121442 243192 121443 243192 121444 243192 121445 243193 121446 243193 121465 243193 121465 243194 121446 243194 121437 243194 121465 243195 121437 243195 121451 243195 121451 243196 121437 243196 121447 243196 121451 243197 121447 243197 121455 243197 121430 243198 121429 243198 121448 243198 121448 243199 121429 243199 121449 243199 121448 243200 121449 243200 121439 243200 121439 243201 121449 243201 121453 243201 121439 243202 121453 243202 120779 243202 120159 243203 121436 243203 121455 243203 121455 243204 121436 243204 121450 243204 121455 243205 121450 243205 121451 243205 121451 243206 121450 243206 121452 243206 121451 243207 121452 243207 121465 243207 120779 243208 121453 243208 121438 243208 121438 243209 121453 243209 121454 243209 121438 243210 121454 243210 121447 243210 121447 243211 121454 243211 121442 243211 121447 243212 121442 243212 121455 243212 121455 243213 121442 243213 121456 243213 121455 243214 121456 243214 120159 243214 120157 243215 120167 243215 121480 243215 121480 243216 120167 243216 121457 243216 121480 243217 121457 243217 121479 243217 121479 243218 121457 243218 121459 243218 121479 243219 121459 243219 121458 243219 121458 243220 121459 243220 121462 243220 121458 243221 121462 243221 121460 243221 121460 243222 121462 243222 121487 243222 121487 243223 121462 243223 121461 243223 121487 243224 121461 243224 120305 243224 121432 243225 121461 243225 121433 243225 121433 243226 121461 243226 121462 243226 121433 243227 121462 243227 121463 243227 121463 243228 121462 243228 121459 243228 121463 243229 121459 243229 121435 243229 121435 243230 121459 243230 121457 243230 121435 243231 121457 243231 120202 243231 120202 243232 121457 243232 120167 243232 120162 243233 121482 243233 121469 243233 120788 243234 121445 243234 121464 243234 121464 243235 121445 243235 121465 243235 121464 243236 121465 243236 121466 243236 121466 243237 121465 243237 121452 243237 121466 243238 121452 243238 121469 243238 121469 243239 121452 243239 121450 243239 121469 243240 121450 243240 120162 243240 120162 243241 121450 243241 121467 243241 120158 243242 121471 243242 121483 243242 121485 243243 121464 243243 121468 243243 121468 243244 121464 243244 121466 243244 121468 243245 121466 243245 121469 243245 121477 243246 121470 243246 121478 243246 121478 243247 121470 243247 121484 243247 121471 243248 121472 243248 121483 243248 121483 243249 121472 243249 121481 243249 121483 243250 121481 243250 121484 243250 121484 243251 121481 243251 121473 243251 121484 243252 121473 243252 121478 243252 120792 243253 121486 243253 121474 243253 121474 243254 121486 243254 121475 243254 121474 243255 121475 243255 120789 243255 120789 243256 121475 243256 121487 243256 120789 243257 121487 243257 120305 243257 120792 243258 120794 243258 121486 243258 121486 243259 120794 243259 121476 243259 121486 243260 121476 243260 121485 243260 121485 243261 121476 243261 120788 243261 121485 243262 120788 243262 121464 243262 121460 243263 121477 243263 121458 243263 121458 243264 121477 243264 121478 243264 121458 243265 121478 243265 121479 243265 121479 243266 121478 243266 121473 243266 121479 243267 121473 243267 121480 243267 121480 243268 121473 243268 121481 243268 121480 243269 121481 243269 120157 243269 120157 243270 121481 243270 121472 243270 121482 243271 120158 243271 121469 243271 121469 243272 120158 243272 121483 243272 121469 243273 121483 243273 121468 243273 121468 243274 121483 243274 121484 243274 121468 243275 121484 243275 121485 243275 121485 243276 121484 243276 121470 243276 121485 243277 121470 243277 121486 243277 121486 243278 121470 243278 121477 243278 121486 243279 121477 243279 121475 243279 121475 243280 121477 243280 121460 243280 121475 243281 121460 243281 121487 243281 121490 243282 120314 243282 121489 243282 121495 243283 121488 243283 121489 243283 121489 243284 121488 243284 121517 243284 121489 243285 121517 243285 121490 243285 121490 243286 121517 243286 121491 243286 121494 243287 121505 243287 120199 243287 121489 243288 120314 243288 121493 243288 121508 243289 121507 243289 121492 243289 121492 243290 121507 243290 121494 243290 121492 243291 121494 243291 121493 243291 121493 243292 121494 243292 121489 243292 121489 243293 121494 243293 120199 243293 121489 243294 120199 243294 121495 243294 121501 243295 121503 243295 121523 243295 121523 243296 121503 243296 121496 243296 121523 243297 121496 243297 121498 243297 120321 243298 121498 243298 121497 243298 121497 243299 121498 243299 121496 243299 121497 243300 121496 243300 120315 243300 120315 243301 121496 243301 121499 243301 120196 243302 121500 243302 121501 243302 121501 243303 121500 243303 121502 243303 121501 243304 121502 243304 121503 243304 121503 243305 121502 243305 121506 243305 121503 243306 121506 243306 121496 243306 121496 243307 121506 243307 121504 243307 121496 243308 121504 243308 121499 243308 121500 243309 120201 243309 121502 243309 121502 243310 120201 243310 121505 243310 121502 243311 121505 243311 121506 243311 121506 243312 121505 243312 121494 243312 121506 243313 121494 243313 121504 243313 121504 243314 121494 243314 121507 243314 121504 243315 121507 243315 121499 243315 121499 243316 121507 243316 121508 243316 120198 243317 120197 243317 121509 243317 121513 243318 121536 243318 121510 243318 121511 243319 121512 243319 121518 243319 121518 243320 121512 243320 121513 243320 121518 243321 121513 243321 121519 243321 121519 243322 121513 243322 121510 243322 121519 243323 121510 243323 121520 243323 121514 243324 121511 243324 121515 243324 121515 243325 121511 243325 121518 243325 121515 243326 121518 243326 120197 243326 121517 243327 121488 243327 120198 243327 121509 243328 120648 243328 121516 243328 120198 243329 121509 243329 121517 243329 121517 243330 121509 243330 121516 243330 121517 243331 121516 243331 121491 243331 120197 243332 121518 243332 121509 243332 121509 243333 121518 243333 121519 243333 121509 243334 121519 243334 120648 243334 120648 243335 121519 243335 121520 243335 120648 243336 121520 243336 121521 243336 121521 243337 121520 243337 121510 243337 121521 243338 121510 243338 120649 243338 120649 243339 121510 243339 121536 243339 120649 243340 121536 243340 121538 243340 121523 243341 121522 243341 121524 243341 121523 243342 121524 243342 121501 243342 121501 243343 121524 243343 120195 243343 121501 243344 120195 243344 120196 243344 121498 243345 120321 243345 121527 243345 121527 243346 120321 243346 120320 243346 121527 243347 120320 243347 120322 243347 120193 243348 120195 243348 121530 243348 121530 243349 120195 243349 121524 243349 121530 243350 121524 243350 121531 243350 121531 243351 121524 243351 121522 243351 121531 243352 121522 243352 121525 243352 120641 243353 121526 243353 120322 243353 120322 243354 121526 243354 121525 243354 120322 243355 121525 243355 121527 243355 121527 243356 121525 243356 121522 243356 121527 243357 121522 243357 121498 243357 121498 243358 121522 243358 121523 243358 121528 243359 120193 243359 121529 243359 121529 243360 120193 243360 121530 243360 121529 243361 121530 243361 121570 243361 121570 243362 121530 243362 121531 243362 121570 243363 121531 243363 121532 243363 121532 243364 121531 243364 121525 243364 121532 243365 121525 243365 121533 243365 121533 243366 121525 243366 121526 243366 121534 243367 120147 243367 120151 243367 121535 243368 121545 243368 121537 243368 121514 243369 120147 243369 121511 243369 121511 243370 120147 243370 121534 243370 121511 243371 121534 243371 121512 243371 121512 243372 121534 243372 121541 243372 121512 243373 121541 243373 121513 243373 121513 243374 121541 243374 121535 243374 121513 243375 121535 243375 121536 243375 121536 243376 121535 243376 121537 243376 121536 243377 121537 243377 121538 243377 121539 243378 121591 243378 121542 243378 121542 243379 121591 243379 121592 243379 121542 243380 121592 243380 121543 243380 121543 243381 121592 243381 121540 243381 121543 243382 121540 243382 121544 243382 120151 243383 121539 243383 121534 243383 121534 243384 121539 243384 121542 243384 121534 243385 121542 243385 121541 243385 121541 243386 121542 243386 121543 243386 121541 243387 121543 243387 121535 243387 121535 243388 121543 243388 121544 243388 121535 243389 121544 243389 121545 243389 121558 243390 121546 243390 121560 243390 120639 243391 120638 243391 121556 243391 121546 243392 121558 243392 121557 243392 121547 243393 121548 243393 121551 243393 121561 243394 121577 243394 121559 243394 121559 243395 121577 243395 121575 243395 121559 243396 121575 243396 121549 243396 121549 243397 121575 243397 121574 243397 121549 243398 121574 243398 121596 243398 121596 243399 121574 243399 121550 243399 121553 243400 121548 243400 121565 243400 121565 243401 121548 243401 121547 243401 121565 243402 121547 243402 121576 243402 121593 243403 121551 243403 121552 243403 121552 243404 121551 243404 121548 243404 121552 243405 121548 243405 120637 243405 120637 243406 121548 243406 121553 243406 120637 243407 121553 243407 120640 243407 120639 243408 121556 243408 121567 243408 121578 243409 121572 243409 121566 243409 121566 243410 121572 243410 121571 243410 121566 243411 121571 243411 121554 243411 121554 243412 121571 243412 121555 243412 121554 243413 121555 243413 121564 243413 121564 243414 121555 243414 121569 243414 121564 243415 121569 243415 121556 243415 121556 243416 121569 243416 121568 243416 121556 243417 121568 243417 121567 243417 121560 243418 121599 243418 121563 243418 121563 243419 121599 243419 120186 243419 121563 243420 120186 243420 120187 243420 121596 243421 121557 243421 121549 243421 121549 243422 121557 243422 121558 243422 121549 243423 121558 243423 121559 243423 121559 243424 121558 243424 121560 243424 121559 243425 121560 243425 121561 243425 121561 243426 121560 243426 121563 243426 121561 243427 121563 243427 121562 243427 121562 243428 121563 243428 120187 243428 121562 243429 120187 243429 120189 243429 120638 243430 120640 243430 121556 243430 121556 243431 120640 243431 121553 243431 121556 243432 121553 243432 121564 243432 121564 243433 121553 243433 121565 243433 121564 243434 121565 243434 121554 243434 121554 243435 121565 243435 121576 243435 121554 243436 121576 243436 121566 243436 120641 243437 121567 243437 121526 243437 121526 243438 121567 243438 121568 243438 121526 243439 121568 243439 121533 243439 121533 243440 121568 243440 121569 243440 121533 243441 121569 243441 121532 243441 121532 243442 121569 243442 121555 243442 121532 243443 121555 243443 121570 243443 121570 243444 121555 243444 121571 243444 121570 243445 121571 243445 121529 243445 121529 243446 121571 243446 121572 243446 121529 243447 121572 243447 121573 243447 121573 243448 121572 243448 121578 243448 121593 243449 121550 243449 121551 243449 121551 243450 121550 243450 121574 243450 121551 243451 121574 243451 121547 243451 121547 243452 121574 243452 121575 243452 121547 243453 121575 243453 121576 243453 121576 243454 121575 243454 121577 243454 121576 243455 121577 243455 121566 243455 121566 243456 121577 243456 121561 243456 121566 243457 121561 243457 121578 243457 121578 243458 121561 243458 121562 243458 121578 243459 121562 243459 121573 243459 121573 243460 121562 243460 120189 243460 121573 243461 120189 243461 121529 243461 121529 243462 120189 243462 121528 243462 121579 243463 120311 243463 121589 243463 121586 243464 120148 243464 121580 243464 121580 243465 120148 243465 121616 243465 121580 243466 121616 243466 121581 243466 121581 243467 121616 243467 121582 243467 121581 243468 121582 243468 121588 243468 121588 243469 121582 243469 121583 243469 121588 243470 121583 243470 121590 243470 121590 243471 121583 243471 121584 243471 120150 243472 121586 243472 121585 243472 121585 243473 121586 243473 121580 243473 121585 243474 121580 243474 121587 243474 121587 243475 121580 243475 121581 243475 121587 243476 121581 243476 121589 243476 121589 243477 121581 243477 121588 243477 121589 243478 121588 243478 121579 243478 121579 243479 121588 243479 121590 243479 120151 243480 120150 243480 121539 243480 121539 243481 120150 243481 121585 243481 121539 243482 121585 243482 121591 243482 121591 243483 121585 243483 121587 243483 121591 243484 121587 243484 121592 243484 121592 243485 121587 243485 121589 243485 121592 243486 121589 243486 121540 243486 121540 243487 121589 243487 120311 243487 121593 243488 121594 243488 121550 243488 121550 243489 121594 243489 121595 243489 121550 243490 121595 243490 121596 243490 121596 243491 121595 243491 121597 243491 121596 243492 121597 243492 121557 243492 121557 243493 121597 243493 121598 243493 121557 243494 121598 243494 121546 243494 121546 243495 121598 243495 121632 243495 121546 243496 121632 243496 121560 243496 121560 243497 121632 243497 121634 243497 121560 243498 121634 243498 121599 243498 121599 243499 121634 243499 121636 243499 121599 243500 121636 243500 120186 243500 120186 243501 121636 243501 120182 243501 121608 243502 121600 243502 121613 243502 121601 243503 120773 243503 121608 243503 121601 243504 121608 243504 121602 243504 121602 243505 121609 243505 121603 243505 121603 243506 121609 243506 121604 243506 121603 243507 121604 243507 121605 243507 121629 243508 121606 243508 121607 243508 121607 243509 121606 243509 120183 243509 121616 243510 120148 243510 121614 243510 121613 243511 121611 243511 121610 243511 121602 243512 121608 243512 121609 243512 121609 243513 121608 243513 121613 243513 121609 243514 121613 243514 121604 243514 121604 243515 121613 243515 121610 243515 121604 243516 121610 243516 121605 243516 121629 243517 121605 243517 121606 243517 121606 243518 121605 243518 121610 243518 121606 243519 121610 243519 121612 243519 121612 243520 121610 243520 121611 243520 121612 243521 121611 243521 121615 243521 121615 243522 121611 243522 121613 243522 121615 243523 121613 243523 121617 243523 121617 243524 121613 243524 121600 243524 121617 243525 121600 243525 121618 243525 120183 243526 121606 243526 121614 243526 121614 243527 121606 243527 121612 243527 121614 243528 121612 243528 121616 243528 121616 243529 121612 243529 121615 243529 121616 243530 121615 243530 121582 243530 121582 243531 121615 243531 121617 243531 121582 243532 121617 243532 121583 243532 121583 243533 121617 243533 121618 243533 121583 243534 121618 243534 121584 243534 121630 243535 121620 243535 121622 243535 121619 243536 120773 243536 121601 243536 121620 243537 121621 243537 121622 243537 121622 243538 121621 243538 121623 243538 121622 243539 121623 243539 121631 243539 121631 243540 121623 243540 121640 243540 121631 243541 121640 243541 121633 243541 121633 243542 121640 243542 121624 243542 121633 243543 121624 243543 121635 243543 121635 243544 121624 243544 121643 243544 121635 243545 121643 243545 121637 243545 121637 243546 121643 243546 121644 243546 121638 243547 120182 243547 121636 243547 121639 243548 121619 243548 121625 243548 121625 243549 121619 243549 121601 243549 121625 243550 121601 243550 121641 243550 121641 243551 121601 243551 121602 243551 121641 243552 121602 243552 121642 243552 121642 243553 121602 243553 121603 243553 121642 243554 121603 243554 121626 243554 121626 243555 121603 243555 121605 243555 121626 243556 121605 243556 121627 243556 121627 243557 121605 243557 121629 243557 121627 243558 121629 243558 121628 243558 121628 243559 121629 243559 121607 243559 121595 243560 121630 243560 121597 243560 121597 243561 121630 243561 121622 243561 121597 243562 121622 243562 121598 243562 121598 243563 121622 243563 121631 243563 121598 243564 121631 243564 121632 243564 121632 243565 121631 243565 121633 243565 121632 243566 121633 243566 121634 243566 121634 243567 121633 243567 121635 243567 121634 243568 121635 243568 121636 243568 121636 243569 121635 243569 121637 243569 121636 243570 121637 243570 121638 243570 121638 243571 121637 243571 121644 243571 121638 243572 121644 243572 120183 243572 121620 243573 121639 243573 121621 243573 121621 243574 121639 243574 121625 243574 121621 243575 121625 243575 121623 243575 121623 243576 121625 243576 121641 243576 121623 243577 121641 243577 121640 243577 121640 243578 121641 243578 121642 243578 121640 243579 121642 243579 121624 243579 121624 243580 121642 243580 121626 243580 121624 243581 121626 243581 121643 243581 121643 243582 121626 243582 121627 243582 121643 243583 121627 243583 121644 243583 121644 243584 121627 243584 121628 243584 121644 243585 121628 243585 120183 243585 120183 243586 121628 243586 121607 243586 121666 243587 121645 243587 121653 243587 121660 243588 121646 243588 121687 243588 121687 243589 121684 243589 121672 243589 121654 243590 121647 243590 121662 243590 121648 243591 121665 243591 121670 243591 121649 243592 121678 243592 121677 243592 121646 243593 121660 243593 121659 243593 121677 243594 121663 243594 121649 243594 121649 243595 121663 243595 121650 243595 121649 243596 121650 243596 121652 243596 121652 243597 121650 243597 121651 243597 121652 243598 121651 243598 120784 243598 121678 243599 121649 243599 121680 243599 121680 243600 121649 243600 121652 243600 121680 243601 121652 243601 121681 243601 121681 243602 121652 243602 120784 243602 121681 243603 120784 243603 121683 243603 121645 243604 121654 243604 121653 243604 121653 243605 121654 243605 121662 243605 121653 243606 121662 243606 121668 243606 121668 243607 121662 243607 121655 243607 121668 243608 121655 243608 121670 243608 121656 243609 121657 243609 121664 243609 121656 243610 121664 243610 121674 243610 121675 243611 121676 243611 121658 243611 121682 243612 121659 243612 121679 243612 121679 243613 121659 243613 121660 243613 121679 243614 121660 243614 121661 243614 121661 243615 121660 243615 121687 243615 121661 243616 121687 243616 121658 243616 121658 243617 121687 243617 121672 243617 121658 243618 121672 243618 121675 243618 121684 243619 120153 243619 121673 243619 121647 243620 121651 243620 121662 243620 121662 243621 121651 243621 121650 243621 121662 243622 121650 243622 121655 243622 121655 243623 121650 243623 121663 243623 121655 243624 121663 243624 121670 243624 121670 243625 121663 243625 121677 243625 121670 243626 121677 243626 121648 243626 121648 243627 121677 243627 121664 243627 121648 243628 121664 243628 121665 243628 121665 243629 121664 243629 121657 243629 120337 243630 121666 243630 121667 243630 121667 243631 121666 243631 121653 243631 121667 243632 121653 243632 121696 243632 121696 243633 121653 243633 121668 243633 121696 243634 121668 243634 121669 243634 121669 243635 121668 243635 121670 243635 121669 243636 121670 243636 121694 243636 121694 243637 121670 243637 121665 243637 121694 243638 121665 243638 121693 243638 121693 243639 121665 243639 121657 243639 121693 243640 121657 243640 121671 243640 121671 243641 121657 243641 121656 243641 121684 243642 121673 243642 121672 243642 121672 243643 121673 243643 121674 243643 121672 243644 121674 243644 121675 243644 121675 243645 121674 243645 121664 243645 121675 243646 121664 243646 121676 243646 121676 243647 121664 243647 121677 243647 121676 243648 121677 243648 121658 243648 121658 243649 121677 243649 121678 243649 121658 243650 121678 243650 121661 243650 121661 243651 121678 243651 121680 243651 121661 243652 121680 243652 121679 243652 121679 243653 121680 243653 121681 243653 121679 243654 121681 243654 121682 243654 121682 243655 121681 243655 121683 243655 121682 243656 121683 243656 120782 243656 120154 243657 120153 243657 121684 243657 121729 243658 120154 243658 121685 243658 121685 243659 120154 243659 121684 243659 121685 243660 121684 243660 121686 243660 121686 243661 121684 243661 121687 243661 121686 243662 121687 243662 121688 243662 121688 243663 121687 243663 121689 243663 121689 243664 121687 243664 121646 243664 121689 243665 121646 243665 121741 243665 121741 243666 121646 243666 121659 243666 121741 243667 121659 243667 121744 243667 121744 243668 121659 243668 121682 243668 121744 243669 121682 243669 121690 243669 121690 243670 121682 243670 120782 243670 121690 243671 120782 243671 120342 243671 121691 243672 121698 243672 121699 243672 121692 243673 120337 243673 121667 243673 121692 243674 121667 243674 121697 243674 121671 243675 121691 243675 121693 243675 121693 243676 121691 243676 121699 243676 121693 243677 121699 243677 121694 243677 121694 243678 121699 243678 121695 243678 121694 243679 121695 243679 121669 243679 121669 243680 121695 243680 121697 243680 121669 243681 121697 243681 121696 243681 121696 243682 121697 243682 121667 243682 121698 243683 120149 243683 121699 243683 121699 243684 120149 243684 121700 243684 121699 243685 121700 243685 121695 243685 121695 243686 121700 243686 121702 243686 121695 243687 121702 243687 121697 243687 121697 243688 121702 243688 121704 243688 121697 243689 121704 243689 121692 243689 121692 243690 121704 243690 121706 243690 120149 243691 121711 243691 121700 243691 121700 243692 121711 243692 121701 243692 121700 243693 121701 243693 121702 243693 121702 243694 121701 243694 121703 243694 121702 243695 121703 243695 121704 243695 121704 243696 121703 243696 121705 243696 121704 243697 121705 243697 121706 243697 121706 243698 121705 243698 120341 243698 121707 243699 120341 243699 121762 243699 121762 243700 120341 243700 121705 243700 121762 243701 121705 243701 121708 243701 121708 243702 121705 243702 121703 243702 121708 243703 121703 243703 121709 243703 121709 243704 121703 243704 121701 243704 121709 243705 121701 243705 121710 243705 121710 243706 121701 243706 121711 243706 120798 243707 120799 243707 121712 243707 121714 243708 121779 243708 121735 243708 121737 243709 121713 243709 121735 243709 121735 243710 121713 243710 121716 243710 121735 243711 121716 243711 121714 243711 121737 243712 121726 243712 121713 243712 121713 243713 121726 243713 121715 243713 121713 243714 121715 243714 121728 243714 121728 243715 120797 243715 121713 243715 121713 243716 120797 243716 120796 243716 121713 243717 120796 243717 121716 243717 121716 243718 120796 243718 121717 243718 121716 243719 121717 243719 121714 243719 121714 243720 121717 243720 120324 243720 121689 243721 121741 243721 121734 243721 121734 243722 121741 243722 121739 243722 121734 243723 121739 243723 121733 243723 121733 243724 121739 243724 121732 243724 120798 243725 121712 243725 120803 243725 121727 243726 121738 243726 121718 243726 121718 243727 121738 243727 121740 243727 121718 243728 121740 243728 121719 243728 121719 243729 121740 243729 121742 243729 121719 243730 121742 243730 121712 243730 121712 243731 121742 243731 121743 243731 121712 243732 121743 243732 120803 243732 120156 243733 121729 243733 121730 243733 121732 243734 121720 243734 121721 243734 121721 243735 121720 243735 121723 243735 121721 243736 121723 243736 121722 243736 121722 243737 121723 243737 121776 243737 121724 243738 121725 243738 121743 243738 121743 243739 121725 243739 120802 243739 121743 243740 120802 243740 120803 243740 121726 243741 121727 243741 121715 243741 121715 243742 121727 243742 121718 243742 121715 243743 121718 243743 121728 243743 121728 243744 121718 243744 121719 243744 121728 243745 121719 243745 120797 243745 120797 243746 121719 243746 121712 243746 120797 243747 121712 243747 120800 243747 120800 243748 121712 243748 120799 243748 121729 243749 121685 243749 121730 243749 121730 243750 121685 243750 121686 243750 121730 243751 121686 243751 121688 243751 121776 243752 120172 243752 121722 243752 121722 243753 120172 243753 120170 243753 121722 243754 120170 243754 121721 243754 121721 243755 120170 243755 121731 243755 121721 243756 121731 243756 121732 243756 121732 243757 121731 243757 120156 243757 121732 243758 120156 243758 121733 243758 121733 243759 120156 243759 121730 243759 121733 243760 121730 243760 121734 243760 121734 243761 121730 243761 121688 243761 121734 243762 121688 243762 121689 243762 121779 243763 121736 243763 121735 243763 121735 243764 121736 243764 121776 243764 121735 243765 121776 243765 121737 243765 121737 243766 121776 243766 121723 243766 121737 243767 121723 243767 121726 243767 121726 243768 121723 243768 121720 243768 121726 243769 121720 243769 121727 243769 121727 243770 121720 243770 121732 243770 121727 243771 121732 243771 121738 243771 121738 243772 121732 243772 121739 243772 121738 243773 121739 243773 121740 243773 121740 243774 121739 243774 121741 243774 121740 243775 121741 243775 121742 243775 121742 243776 121741 243776 121744 243776 121742 243777 121744 243777 121743 243777 121743 243778 121744 243778 121690 243778 121743 243779 121690 243779 121724 243779 121724 243780 121690 243780 120342 243780 121745 243781 120653 243781 121750 243781 121755 243782 121756 243782 121746 243782 121753 243783 120655 243783 120653 243783 121781 243784 121782 243784 121753 243784 121709 243785 121710 243785 121755 243785 121783 243786 121747 243786 121782 243786 121782 243787 121747 243787 121748 243787 121782 243788 121748 243788 121753 243788 121753 243789 121748 243789 121749 243789 121753 243790 121749 243790 120655 243790 121763 243791 121761 243791 121750 243791 121750 243792 121761 243792 121760 243792 121750 243793 121760 243793 121745 243793 121745 243794 121760 243794 121758 243794 121745 243795 121758 243795 121751 243795 121751 243796 121758 243796 121757 243796 121751 243797 121757 243797 121752 243797 120653 243798 121745 243798 121753 243798 121753 243799 121745 243799 121751 243799 121753 243800 121751 243800 121781 243800 121781 243801 121751 243801 121752 243801 121781 243802 121752 243802 121754 243802 121755 243803 121746 243803 121709 243803 121709 243804 121746 243804 121759 243804 121709 243805 121759 243805 121708 243805 121756 243806 121757 243806 121746 243806 121746 243807 121757 243807 121758 243807 121746 243808 121758 243808 121759 243808 121759 243809 121758 243809 121760 243809 121759 243810 121760 243810 121708 243810 121708 243811 121760 243811 121761 243811 121708 243812 121761 243812 121762 243812 121762 243813 121761 243813 121763 243813 121762 243814 121763 243814 121707 243814 121736 243815 121779 243815 121764 243815 121772 243816 121793 243816 121777 243816 121770 243817 121778 243817 121765 243817 121770 243818 120334 243818 121803 243818 121770 243819 121765 243819 120325 243819 120325 243820 121765 243820 121767 243820 120325 243821 121767 243821 120327 243821 120327 243822 121767 243822 121766 243822 121766 243823 121767 243823 121714 243823 121766 243824 121714 243824 120324 243824 121768 243825 121792 243825 120177 243825 121793 243826 121768 243826 121769 243826 121770 243827 121803 243827 121778 243827 121778 243828 121803 243828 121771 243828 121778 243829 121771 243829 121772 243829 121768 243830 120177 243830 121769 243830 121769 243831 120177 243831 120176 243831 121769 243832 120176 243832 121774 243832 120176 243833 120175 243833 121774 243833 121774 243834 120175 243834 120173 243834 121774 243835 120173 243835 121773 243835 121773 243836 120173 243836 120172 243836 121773 243837 120172 243837 121776 243837 121793 243838 121769 243838 121777 243838 121777 243839 121769 243839 121774 243839 121777 243840 121774 243840 121775 243840 121775 243841 121774 243841 121773 243841 121775 243842 121773 243842 121764 243842 121764 243843 121773 243843 121776 243843 121764 243844 121776 243844 121736 243844 121772 243845 121777 243845 121778 243845 121778 243846 121777 243846 121775 243846 121778 243847 121775 243847 121765 243847 121765 243848 121775 243848 121764 243848 121765 243849 121764 243849 121767 243849 121767 243850 121764 243850 121779 243850 121767 243851 121779 243851 121714 243851 120145 243852 121784 243852 121780 243852 121780 243853 121784 243853 121798 243853 121780 243854 121798 243854 121801 243854 121754 243855 120145 243855 121781 243855 121781 243856 120145 243856 121780 243856 121781 243857 121780 243857 121782 243857 121782 243858 121780 243858 121783 243858 121784 243859 120145 243859 121785 243859 121784 243860 121785 243860 121798 243860 121786 243861 121806 243861 121799 243861 121799 243862 121806 243862 121800 243862 121802 243863 121787 243863 121804 243863 121804 243864 121787 243864 121789 243864 121804 243865 121789 243865 121788 243865 121788 243866 121789 243866 120333 243866 121808 243867 121790 243867 121791 243867 121791 243868 121790 243868 121771 243868 121791 243869 121771 243869 121803 243869 121810 243870 121793 243870 121772 243870 121792 243871 121768 243871 121794 243871 121768 243872 121793 243872 121794 243872 121794 243873 121793 243873 121810 243873 121794 243874 121810 243874 121797 243874 121797 243875 121810 243875 121809 243875 121797 243876 121809 243876 121786 243876 121792 243877 121794 243877 121795 243877 121795 243878 121794 243878 121797 243878 121795 243879 121797 243879 121796 243879 121796 243880 121797 243880 121786 243880 121796 243881 121786 243881 121785 243881 121785 243882 121786 243882 121799 243882 121785 243883 121799 243883 121798 243883 121798 243884 121799 243884 121800 243884 121798 243885 121800 243885 121801 243885 120334 243886 121802 243886 121803 243886 121803 243887 121802 243887 121804 243887 121803 243888 121804 243888 121791 243888 121791 243889 121804 243889 121788 243889 121791 243890 121788 243890 121808 243890 121808 243891 121788 243891 120333 243891 121808 243892 120333 243892 121805 243892 120333 243893 120332 243893 121805 243893 121805 243894 120332 243894 121806 243894 121805 243895 121806 243895 121807 243895 121807 243896 121806 243896 121786 243896 121807 243897 121786 243897 121805 243897 121805 243898 121786 243898 121809 243898 121805 243899 121809 243899 121808 243899 121808 243900 121809 243900 121810 243900 121808 243901 121810 243901 121790 243901 121790 243902 121810 243902 121772 243902 121790 243903 121772 243903 121771 243903 121816 243904 119954 243904 121811 243904 119956 243905 119955 243905 121812 243905 121812 243906 119955 243906 121813 243906 121812 243907 121813 243907 121823 243907 121823 243908 121813 243908 121814 243908 121823 243909 121814 243909 120013 243909 120013 243910 121814 243910 121815 243910 119955 243911 119954 243911 121813 243911 121813 243912 119954 243912 121816 243912 121813 243913 121816 243913 121814 243913 121814 243914 121816 243914 121818 243914 121814 243915 121818 243915 121815 243915 121815 243916 121818 243916 121820 243916 121811 243917 121827 243917 121816 243917 121816 243918 121827 243918 121817 243918 121816 243919 121817 243919 121818 243919 121818 243920 121817 243920 121819 243920 121818 243921 121819 243921 121820 243921 121820 243922 121819 243922 121826 243922 120013 243923 121821 243923 121822 243923 120013 243924 121822 243924 121823 243924 121823 243925 121822 243925 121824 243925 121823 243926 121824 243926 121812 243926 121812 243927 121824 243927 121825 243927 121812 243928 121825 243928 119956 243928 121839 243929 121826 243929 121819 243929 121839 243930 121819 243930 121840 243930 121840 243931 121819 243931 121817 243931 121840 243932 121817 243932 121842 243932 121842 243933 121817 243933 121827 243933 121842 243934 121827 243934 121828 243934 121828 243935 121827 243935 121811 243935 121828 243936 121811 243936 119898 243936 121834 243937 121829 243937 121832 243937 121829 243938 121852 243938 121830 243938 121852 243939 119960 243939 119959 243939 121852 243940 119959 243940 121830 243940 121830 243941 119959 243941 119958 243941 121830 243942 119958 243942 121833 243942 121833 243943 119958 243943 119950 243943 121833 243944 119950 243944 121831 243944 121831 243945 119950 243945 121825 243945 121831 243946 121825 243946 121824 243946 121829 243947 121830 243947 121832 243947 121832 243948 121830 243948 121833 243948 121832 243949 121833 243949 121835 243949 121835 243950 121833 243950 121831 243950 121835 243951 121831 243951 121838 243951 121838 243952 121831 243952 121824 243952 121838 243953 121824 243953 121822 243953 121834 243954 121832 243954 120675 243954 120675 243955 121832 243955 121835 243955 120675 243956 121835 243956 121836 243956 121836 243957 121835 243957 121838 243957 121836 243958 121838 243958 121837 243958 121837 243959 121838 243959 121822 243959 121837 243960 121822 243960 121821 243960 121844 243961 121839 243961 121845 243961 121845 243962 121839 243962 121840 243962 121845 243963 121840 243963 121841 243963 121841 243964 121840 243964 121842 243964 121841 243965 121842 243965 121847 243965 121847 243966 121842 243966 121828 243966 121847 243967 121828 243967 119897 243967 119897 243968 121828 243968 119898 243968 121843 243969 121844 243969 121868 243969 121868 243970 121844 243970 121845 243970 121868 243971 121845 243971 121846 243971 121846 243972 121845 243972 121841 243972 121846 243973 121841 243973 121859 243973 121859 243974 121841 243974 121847 243974 121859 243975 121847 243975 121848 243975 121848 243976 121847 243976 119897 243976 121834 243977 121849 243977 121850 243977 121834 243978 121850 243978 121829 243978 121829 243979 121850 243979 121851 243979 121829 243980 121851 243980 121852 243980 121851 243981 121853 243981 121852 243981 121852 243982 121853 243982 121854 243982 121852 243983 121854 243983 119960 243983 121866 243984 121870 243984 121871 243984 121855 243985 121856 243985 121863 243985 121857 243986 121846 243986 121859 243986 119904 243987 119902 243987 121867 243987 121862 243988 121843 243988 121868 243988 121856 243989 121855 243989 121858 243989 121858 243990 121855 243990 121865 243990 121858 243991 121865 243991 120804 243991 119906 243992 119905 243992 121872 243992 121857 243993 121859 243993 121872 243993 121872 243994 121859 243994 121848 243994 121872 243995 121848 243995 119906 243995 120804 243996 121865 243996 121860 243996 121860 243997 121865 243997 121861 243997 121860 243998 121861 243998 120011 243998 121862 243999 121869 243999 121863 243999 121863 244000 121869 244000 121864 244000 121863 244001 121864 244001 121855 244001 121855 244002 121864 244002 121870 244002 121855 244003 121870 244003 121865 244003 121865 244004 121870 244004 121866 244004 121865 244005 121866 244005 121861 244005 119935 244006 119904 244006 121871 244006 121871 244007 119904 244007 121867 244007 121871 244008 121867 244008 121866 244008 121866 244009 121867 244009 121884 244009 121866 244010 121884 244010 121861 244010 121862 244011 121868 244011 121869 244011 121869 244012 121868 244012 121846 244012 121869 244013 121846 244013 121864 244013 121864 244014 121846 244014 121857 244014 121864 244015 121857 244015 121870 244015 121870 244016 121857 244016 121872 244016 121870 244017 121872 244017 121871 244017 121871 244018 121872 244018 119905 244018 121871 244019 119905 244019 119935 244019 119914 244020 121880 244020 121899 244020 121899 244021 121880 244021 121873 244021 121899 244022 121873 244022 121874 244022 121874 244023 121873 244023 121875 244023 121874 244024 121875 244024 121876 244024 121876 244025 121875 244025 121877 244025 121876 244026 121877 244026 121897 244026 121897 244027 121877 244027 121878 244027 121878 244028 121877 244028 120021 244028 121878 244029 120021 244029 121879 244029 121849 244030 120021 244030 121850 244030 121850 244031 120021 244031 121877 244031 121850 244032 121877 244032 121851 244032 121851 244033 121877 244033 121875 244033 121851 244034 121875 244034 121853 244034 121853 244035 121875 244035 121873 244035 121853 244036 121873 244036 121854 244036 121854 244037 121873 244037 121880 244037 121881 244038 120011 244038 121882 244038 121882 244039 120011 244039 121861 244039 121882 244040 121861 244040 121883 244040 121883 244041 121861 244041 121884 244041 121883 244042 121884 244042 121887 244042 121887 244043 121884 244043 121867 244043 121887 244044 121867 244044 121885 244044 121885 244045 121867 244045 119902 244045 121902 244046 119908 244046 121892 244046 120826 244047 121881 244047 121886 244047 121886 244048 121881 244048 121882 244048 121886 244049 121882 244049 121901 244049 121901 244050 121882 244050 121883 244050 121901 244051 121883 244051 121887 244051 121894 244052 121895 244052 121889 244052 121889 244053 121895 244053 121888 244053 121889 244054 121888 244054 121900 244054 121900 244055 121888 244055 121896 244055 121890 244056 121900 244056 121891 244056 121891 244057 121900 244057 121896 244057 121891 244058 121896 244058 120828 244058 119908 244059 119901 244059 121892 244059 121892 244060 119901 244060 121893 244060 121892 244061 121893 244061 121894 244061 121894 244062 121893 244062 121898 244062 121894 244063 121898 244063 121895 244063 121879 244064 120828 244064 121878 244064 121878 244065 120828 244065 121896 244065 121878 244066 121896 244066 121897 244066 121897 244067 121896 244067 121888 244067 121897 244068 121888 244068 121876 244068 121876 244069 121888 244069 121895 244069 121876 244070 121895 244070 121874 244070 121874 244071 121895 244071 121898 244071 121874 244072 121898 244072 121899 244072 121899 244073 121898 244073 121893 244073 121899 244074 121893 244074 119914 244074 119914 244075 121893 244075 119901 244075 121890 244076 120829 244076 121900 244076 121900 244077 120829 244077 120826 244077 121900 244078 120826 244078 121889 244078 121889 244079 120826 244079 121886 244079 121889 244080 121886 244080 121894 244080 121894 244081 121886 244081 121901 244081 121894 244082 121901 244082 121892 244082 121892 244083 121901 244083 121887 244083 121892 244084 121887 244084 121902 244084 121902 244085 121887 244085 121885 244085 121911 244086 121903 244086 121910 244086 121904 244087 120042 244087 121920 244087 121909 244088 121907 244088 121904 244088 121903 244089 121911 244089 121905 244089 121905 244090 121911 244090 121906 244090 121905 244091 121906 244091 119932 244091 119930 244092 121907 244092 121908 244092 121908 244093 121907 244093 121909 244093 121908 244094 121909 244094 121910 244094 121910 244095 121909 244095 121921 244095 121910 244096 121921 244096 121911 244096 121911 244097 121921 244097 121922 244097 121911 244098 121922 244098 121906 244098 121912 244099 121919 244099 121913 244099 120045 244100 121914 244100 121915 244100 120050 244101 121917 244101 121916 244101 121916 244102 121917 244102 120047 244102 121916 244103 120047 244103 121918 244103 121918 244104 120047 244104 120046 244104 121918 244105 120046 244105 121912 244105 121912 244106 120046 244106 120045 244106 121912 244107 120045 244107 121919 244107 121919 244108 120045 244108 121915 244108 121919 244109 121915 244109 121913 244109 121920 244110 120050 244110 121904 244110 121904 244111 120050 244111 121916 244111 121904 244112 121916 244112 121909 244112 121909 244113 121916 244113 121918 244113 121909 244114 121918 244114 121921 244114 121921 244115 121918 244115 121912 244115 121921 244116 121912 244116 121922 244116 121922 244117 121912 244117 121913 244117 121922 244118 121913 244118 121906 244118 121967 244119 121923 244119 121924 244119 121924 244120 121923 244120 121934 244120 121924 244121 121934 244121 120051 244121 121914 244122 121927 244122 121928 244122 121914 244123 121928 244123 121915 244123 121915 244124 121928 244124 121929 244124 121915 244125 121929 244125 121913 244125 121913 244126 121929 244126 121925 244126 121913 244127 121925 244127 121906 244127 121906 244128 121925 244128 121926 244128 121906 244129 121926 244129 119932 244129 121927 244130 121933 244130 121928 244130 121928 244131 121933 244131 121935 244131 121928 244132 121935 244132 121929 244132 121929 244133 121935 244133 121936 244133 121929 244134 121936 244134 121925 244134 121925 244135 121936 244135 121937 244135 121925 244136 121937 244136 121926 244136 119939 244137 119934 244137 121937 244137 121937 244138 119934 244138 119933 244138 121937 244139 119933 244139 121926 244139 121968 244140 121939 244140 121930 244140 121930 244141 121939 244141 121938 244141 121930 244142 121938 244142 121931 244142 121931 244143 121938 244143 121934 244143 121931 244144 121934 244144 121932 244144 121932 244145 121934 244145 121923 244145 121933 244146 120051 244146 121935 244146 121935 244147 120051 244147 121934 244147 121935 244148 121934 244148 121936 244148 121936 244149 121934 244149 121938 244149 121936 244150 121938 244150 121937 244150 121937 244151 121938 244151 121939 244151 121937 244152 121939 244152 119939 244152 119939 244153 121939 244153 121968 244153 119939 244154 121968 244154 119938 244154 120043 244155 120042 244155 121904 244155 119930 244156 121940 244156 121907 244156 121907 244157 121940 244157 121983 244157 121907 244158 121983 244158 121904 244158 121904 244159 121983 244159 121982 244159 121904 244160 121982 244160 120043 244160 120043 244161 121982 244161 121977 244161 120811 244162 121941 244162 121951 244162 121944 244163 121943 244163 121958 244163 121958 244164 121961 244164 121960 244164 121950 244165 120809 244165 121952 244165 121966 244166 121942 244166 121963 244166 121946 244167 121971 244167 121965 244167 121943 244168 121944 244168 122002 244168 121965 244169 121964 244169 121946 244169 121946 244170 121964 244170 121962 244170 121946 244171 121962 244171 121948 244171 121948 244172 121962 244172 121945 244172 121948 244173 121945 244173 120807 244173 121971 244174 121946 244174 121947 244174 121947 244175 121946 244175 121948 244175 121947 244176 121948 244176 121949 244176 121949 244177 121948 244177 120807 244177 121949 244178 120807 244178 121974 244178 121941 244179 121950 244179 121951 244179 121951 244180 121950 244180 121952 244180 121951 244181 121952 244181 121953 244181 121953 244182 121952 244182 121954 244182 121953 244183 121954 244183 121963 244183 119936 244184 121955 244184 121956 244184 119936 244185 121956 244185 121957 244185 121969 244186 121970 244186 121959 244186 122004 244187 122002 244187 121973 244187 121973 244188 122002 244188 121944 244188 121973 244189 121944 244189 121972 244189 121972 244190 121944 244190 121958 244190 121972 244191 121958 244191 121959 244191 121959 244192 121958 244192 121960 244192 121959 244193 121960 244193 121969 244193 121961 244194 121998 244194 119903 244194 120809 244195 121945 244195 121952 244195 121952 244196 121945 244196 121962 244196 121952 244197 121962 244197 121954 244197 121954 244198 121962 244198 121964 244198 121954 244199 121964 244199 121963 244199 121963 244200 121964 244200 121965 244200 121963 244201 121965 244201 121966 244201 121966 244202 121965 244202 121956 244202 121966 244203 121956 244203 121942 244203 121942 244204 121956 244204 121955 244204 121967 244205 120811 244205 121923 244205 121923 244206 120811 244206 121951 244206 121923 244207 121951 244207 121932 244207 121932 244208 121951 244208 121953 244208 121932 244209 121953 244209 121931 244209 121931 244210 121953 244210 121963 244210 121931 244211 121963 244211 121930 244211 121930 244212 121963 244212 121942 244212 121930 244213 121942 244213 121968 244213 121968 244214 121942 244214 121955 244214 121968 244215 121955 244215 119938 244215 119938 244216 121955 244216 119936 244216 121961 244217 119903 244217 121960 244217 121960 244218 119903 244218 121957 244218 121960 244219 121957 244219 121969 244219 121969 244220 121957 244220 121956 244220 121969 244221 121956 244221 121970 244221 121970 244222 121956 244222 121965 244222 121970 244223 121965 244223 121959 244223 121959 244224 121965 244224 121971 244224 121959 244225 121971 244225 121972 244225 121972 244226 121971 244226 121947 244226 121972 244227 121947 244227 121973 244227 121973 244228 121947 244228 121949 244228 121973 244229 121949 244229 122004 244229 122004 244230 121949 244230 121974 244230 122004 244231 121974 244231 121975 244231 120661 244232 121978 244232 121995 244232 121993 244233 121976 244233 120661 244233 120657 244234 121977 244234 121982 244234 121984 244235 121995 244235 121979 244235 121995 244236 121978 244236 121979 244236 121979 244237 121978 244237 120659 244237 121979 244238 120659 244238 120657 244238 121990 244239 122009 244239 121980 244239 122010 244240 122011 244240 121993 244240 121980 244241 122009 244241 121992 244241 121994 244242 121996 244242 121981 244242 121981 244243 121996 244243 121997 244243 121981 244244 121997 244244 121989 244244 121989 244245 121997 244245 119942 244245 121989 244246 119942 244246 121987 244246 121983 244247 121940 244247 119928 244247 120657 244248 121982 244248 121979 244248 121979 244249 121982 244249 121983 244249 121979 244250 121983 244250 121984 244250 121984 244251 121983 244251 119928 244251 121984 244252 119928 244252 121985 244252 122011 244253 122012 244253 121993 244253 121993 244254 122012 244254 121986 244254 121993 244255 121986 244255 121976 244255 121987 244256 121988 244256 121989 244256 121989 244257 121988 244257 121990 244257 121989 244258 121990 244258 121981 244258 121981 244259 121990 244259 121980 244259 121981 244260 121980 244260 121994 244260 121994 244261 121980 244261 121992 244261 121994 244262 121992 244262 121991 244262 122009 244263 122010 244263 121992 244263 121992 244264 122010 244264 121993 244264 121992 244265 121993 244265 121991 244265 121991 244266 121993 244266 120661 244266 121991 244267 120661 244267 121994 244267 121994 244268 120661 244268 121995 244268 121994 244269 121995 244269 121996 244269 121996 244270 121995 244270 121984 244270 121996 244271 121984 244271 121997 244271 121997 244272 121984 244272 121985 244272 121997 244273 121985 244273 119942 244273 121999 244274 122035 244274 121998 244274 121998 244275 121961 244275 121999 244275 121999 244276 121961 244276 121958 244276 121999 244277 121958 244277 122000 244277 122000 244278 121958 244278 121943 244278 122000 244279 121943 244279 122001 244279 122001 244280 121943 244280 122002 244280 122001 244281 122002 244281 122003 244281 122003 244282 122002 244282 122004 244282 122003 244283 122004 244283 122038 244283 122038 244284 122004 244284 121975 244284 122038 244285 121975 244285 122005 244285 121987 244286 122006 244286 121988 244286 121988 244287 122006 244287 122007 244287 121988 244288 122007 244288 121990 244288 121990 244289 122007 244289 122008 244289 121990 244290 122008 244290 122009 244290 122009 244291 122008 244291 122014 244291 122009 244292 122014 244292 122010 244292 122010 244293 122014 244293 122011 244293 122011 244294 122014 244294 120041 244294 122011 244295 120041 244295 122012 244295 122015 244296 120041 244296 122013 244296 122013 244297 120041 244297 122014 244297 122013 244298 122014 244298 122017 244298 122017 244299 122014 244299 122008 244299 122017 244300 122008 244300 122018 244300 122018 244301 122008 244301 122007 244301 122018 244302 122007 244302 119946 244302 119946 244303 122007 244303 122006 244303 122019 244304 122015 244304 122016 244304 122016 244305 122015 244305 122013 244305 122016 244306 122013 244306 122022 244306 122022 244307 122013 244307 122017 244307 122022 244308 122017 244308 122025 244308 122025 244309 122017 244309 122018 244309 122025 244310 122018 244310 122026 244310 122026 244311 122018 244311 119946 244311 120814 244312 122019 244312 122020 244312 122020 244313 122019 244313 122016 244313 122020 244314 122016 244314 122021 244314 122021 244315 122016 244315 122022 244315 122021 244316 122022 244316 122023 244316 122023 244317 122022 244317 122025 244317 122023 244318 122025 244318 122024 244318 122024 244319 122025 244319 122026 244319 122027 244320 122028 244320 120816 244320 122043 244321 122042 244321 122051 244321 122051 244322 122042 244322 122049 244322 120816 244323 122056 244323 122040 244323 120813 244324 120814 244324 122020 244324 122055 244325 122054 244325 122041 244325 122032 244326 122053 244326 122050 244326 122032 244327 122050 244327 122033 244327 122003 244328 122038 244328 122039 244328 122029 244329 122030 244329 122039 244329 122039 244330 122030 244330 120817 244330 122039 244331 120817 244331 122027 244331 122027 244332 120817 244332 120815 244332 122027 244333 120815 244333 122028 244333 122054 244334 122053 244334 122041 244334 122041 244335 122053 244335 122032 244335 122041 244336 122032 244336 122031 244336 122031 244337 122032 244337 122033 244337 122031 244338 122033 244338 122034 244338 122034 244339 122033 244339 122001 244339 122034 244340 122001 244340 122003 244340 122044 244341 122035 244341 122036 244341 122036 244342 122035 244342 121999 244342 122036 244343 121999 244343 122000 244343 122043 244344 122052 244344 122046 244344 122046 244345 122052 244345 122048 244345 122023 244346 122024 244346 119948 244346 120813 244347 122020 244347 122057 244347 122057 244348 122020 244348 122021 244348 122057 244349 122021 244349 122037 244349 122037 244350 122021 244350 122023 244350 122037 244351 122023 244351 122047 244351 122047 244352 122023 244352 119948 244352 122047 244353 119948 244353 122045 244353 122029 244354 122039 244354 120818 244354 120818 244355 122039 244355 122038 244355 120818 244356 122038 244356 122005 244356 122003 244357 122039 244357 122034 244357 122034 244358 122039 244358 122027 244358 122034 244359 122027 244359 122031 244359 122031 244360 122027 244360 120816 244360 122031 244361 120816 244361 122041 244361 122041 244362 120816 244362 122040 244362 122041 244363 122040 244363 122055 244363 122000 244364 122049 244364 122036 244364 122036 244365 122049 244365 122042 244365 122036 244366 122042 244366 122044 244366 122044 244367 122042 244367 122043 244367 122044 244368 122043 244368 122045 244368 122045 244369 122043 244369 122046 244369 122045 244370 122046 244370 122047 244370 122047 244371 122046 244371 122048 244371 122047 244372 122048 244372 122037 244372 122000 244373 122001 244373 122049 244373 122049 244374 122001 244374 122033 244374 122049 244375 122033 244375 122051 244375 122051 244376 122033 244376 122050 244376 122051 244377 122050 244377 122043 244377 122043 244378 122050 244378 122053 244378 122043 244379 122053 244379 122052 244379 122052 244380 122053 244380 122054 244380 122052 244381 122054 244381 122048 244381 122048 244382 122054 244382 122055 244382 122048 244383 122055 244383 122037 244383 122037 244384 122055 244384 122040 244384 122037 244385 122040 244385 122057 244385 122057 244386 122040 244386 122056 244386 122057 244387 122056 244387 120813 244387 122072 244388 122060 244388 120667 244388 122058 244389 122075 244389 122090 244389 122076 244390 122077 244390 122059 244390 122060 244391 122072 244391 120668 244391 122068 244392 120062 244392 122069 244392 122069 244393 120062 244393 122073 244393 122072 244394 122061 244394 122067 244394 122067 244395 122061 244395 122062 244395 122067 244396 122062 244396 122063 244396 120668 244397 122072 244397 122064 244397 122064 244398 122072 244398 122067 244398 122064 244399 122067 244399 120670 244399 122076 244400 122059 244400 122071 244400 122058 244401 122090 244401 122065 244401 122065 244402 122090 244402 119944 244402 122065 244403 119944 244403 119943 244403 120671 244404 122066 244404 122063 244404 122063 244405 122066 244405 120673 244405 122063 244406 120673 244406 122067 244406 122067 244407 120673 244407 120665 244407 122067 244408 120665 244408 120670 244408 122068 244409 122069 244409 120667 244409 120667 244410 122069 244410 122070 244410 120667 244411 122070 244411 122072 244411 122072 244412 122070 244412 122071 244412 122072 244413 122071 244413 122061 244413 122061 244414 122071 244414 122059 244414 122061 244415 122059 244415 122062 244415 122062 244416 122059 244416 119941 244416 122062 244417 119941 244417 119929 244417 122073 244418 122074 244418 122069 244418 122069 244419 122074 244419 122075 244419 122069 244420 122075 244420 122070 244420 122070 244421 122075 244421 122058 244421 122070 244422 122058 244422 122071 244422 122071 244423 122058 244423 122065 244423 122071 244424 122065 244424 122076 244424 122076 244425 122065 244425 119943 244425 122076 244426 119943 244426 122077 244426 122091 244427 122123 244427 122092 244427 120064 244428 122104 244428 122099 244428 122074 244429 122073 244429 122078 244429 122078 244430 122073 244430 120062 244430 120064 244431 122093 244431 122079 244431 122079 244432 122093 244432 122080 244432 122079 244433 122080 244433 120060 244433 120060 244434 122080 244434 122078 244434 120060 244435 122078 244435 122081 244435 122081 244436 122078 244436 120062 244436 122083 244437 122101 244437 119949 244437 120064 244438 122099 244438 122093 244438 122093 244439 122099 244439 122082 244439 122093 244440 122082 244440 122091 244440 122123 244441 122083 244441 122088 244441 122088 244442 122083 244442 119949 244442 122088 244443 119949 244443 122086 244443 122086 244444 119949 244444 122084 244444 122084 244445 122085 244445 122086 244445 122086 244446 122085 244446 119945 244446 122086 244447 119945 244447 122087 244447 122087 244448 119945 244448 119944 244448 122087 244449 119944 244449 122090 244449 122123 244450 122088 244450 122092 244450 122092 244451 122088 244451 122086 244451 122092 244452 122086 244452 122094 244452 122094 244453 122086 244453 122087 244453 122094 244454 122087 244454 122089 244454 122089 244455 122087 244455 122090 244455 122089 244456 122090 244456 122075 244456 122091 244457 122092 244457 122093 244457 122093 244458 122092 244458 122094 244458 122093 244459 122094 244459 122080 244459 122080 244460 122094 244460 122089 244460 122080 244461 122089 244461 122078 244461 122078 244462 122089 244462 122075 244462 122078 244463 122075 244463 122074 244463 122138 244464 120671 244464 122095 244464 122095 244465 120671 244465 122063 244465 122095 244466 122063 244466 122096 244466 122096 244467 122063 244467 122062 244467 122096 244468 122062 244468 122137 244468 122137 244469 122062 244469 119929 244469 122097 244470 122118 244470 122117 244470 122118 244471 122097 244471 122120 244471 122109 244472 122130 244472 122128 244472 122108 244473 122126 244473 122110 244473 122131 244474 122130 244474 122098 244474 122098 244475 122130 244475 122109 244475 122098 244476 122109 244476 122111 244476 122121 244477 122122 244477 122124 244477 122099 244478 122100 244478 122082 244478 122082 244479 122100 244479 122125 244479 122082 244480 122125 244480 122091 244480 122091 244481 122125 244481 122124 244481 122114 244482 119947 244482 122115 244482 122115 244483 119947 244483 122101 244483 122115 244484 122101 244484 122083 244484 119910 244485 119911 244485 122102 244485 122102 244486 119911 244486 122103 244486 122102 244487 122103 244487 122127 244487 122127 244488 122103 244488 122119 244488 122099 244489 122104 244489 122100 244489 122100 244490 122104 244490 122105 244490 122100 244491 122105 244491 120825 244491 122126 244492 122106 244492 122110 244492 122110 244493 122106 244493 122107 244493 122110 244494 122107 244494 122112 244494 122128 244495 122108 244495 122109 244495 122109 244496 122108 244496 122110 244496 122109 244497 122110 244497 122111 244497 122111 244498 122110 244498 122112 244498 122111 244499 122112 244499 120824 244499 120824 244500 122112 244500 122113 244500 122117 244501 122114 244501 122097 244501 122097 244502 122114 244502 122115 244502 122097 244503 122115 244503 122116 244503 122116 244504 122115 244504 122083 244504 122116 244505 122083 244505 122123 244505 119911 244506 122117 244506 122103 244506 122103 244507 122117 244507 122118 244507 122103 244508 122118 244508 122119 244508 122119 244509 122118 244509 122120 244509 122119 244510 122120 244510 122121 244510 122121 244511 122120 244511 122097 244511 122121 244512 122097 244512 122122 244512 122122 244513 122097 244513 122116 244513 122122 244514 122116 244514 122124 244514 122124 244515 122116 244515 122123 244515 122124 244516 122123 244516 122091 244516 120825 244517 122113 244517 122100 244517 122100 244518 122113 244518 122112 244518 122100 244519 122112 244519 122125 244519 122125 244520 122112 244520 122107 244520 122125 244521 122107 244521 122124 244521 122124 244522 122107 244522 122106 244522 122124 244523 122106 244523 122121 244523 122121 244524 122106 244524 122126 244524 122121 244525 122126 244525 122119 244525 122119 244526 122126 244526 122108 244526 122119 244527 122108 244527 122127 244527 122127 244528 122108 244528 122128 244528 122127 244529 122128 244529 122154 244529 122154 244530 122128 244530 122130 244530 122154 244531 122130 244531 122129 244531 122129 244532 122130 244532 122131 244532 122129 244533 122131 244533 120820 244533 122132 244534 122133 244534 122142 244534 122142 244535 122133 244535 122147 244535 122142 244536 122147 244536 122144 244536 122134 244537 122140 244537 122168 244537 122168 244538 122140 244538 122139 244538 122168 244539 122139 244539 122135 244539 119923 244540 122136 244540 122148 244540 119923 244541 122148 244541 119925 244541 119925 244542 122148 244542 122149 244542 119925 244543 122149 244543 119926 244543 119926 244544 122149 244544 122151 244544 119926 244545 122151 244545 119927 244545 122096 244546 122137 244546 119927 244546 119927 244547 122151 244547 122096 244547 122096 244548 122151 244548 122152 244548 122096 244549 122152 244549 122095 244549 122095 244550 122152 244550 120058 244550 122095 244551 120058 244551 122138 244551 122150 244552 122145 244552 122146 244552 122150 244553 122139 244553 122145 244553 122145 244554 122139 244554 122140 244554 122145 244555 122140 244555 122143 244555 122143 244556 122140 244556 122134 244556 122143 244557 122134 244557 122141 244557 120066 244558 122132 244558 122141 244558 122141 244559 122132 244559 122142 244559 122141 244560 122142 244560 122143 244560 122143 244561 122142 244561 122144 244561 122143 244562 122144 244562 122145 244562 122145 244563 122144 244563 122147 244563 122145 244564 122147 244564 122146 244564 122146 244565 122147 244565 120055 244565 122146 244566 120055 244566 120056 244566 122136 244567 122135 244567 122148 244567 122148 244568 122135 244568 122139 244568 122148 244569 122139 244569 122149 244569 122149 244570 122139 244570 122150 244570 122149 244571 122150 244571 122151 244571 122151 244572 122150 244572 122146 244572 122151 244573 122146 244573 122152 244573 122152 244574 122146 244574 120056 244574 122152 244575 120056 244575 120058 244575 122153 244576 122185 244576 119910 244576 119910 244577 122102 244577 122153 244577 122153 244578 122102 244578 122127 244578 122153 244579 122127 244579 122155 244579 122155 244580 122127 244580 122154 244580 122155 244581 122154 244581 122184 244581 122184 244582 122154 244582 122129 244582 122184 244583 122129 244583 122191 244583 122191 244584 122129 244584 122190 244584 122190 244585 122129 244585 120820 244585 122190 244586 120820 244586 120843 244586 120068 244587 122162 244587 122159 244587 120066 244588 122141 244588 120068 244588 122156 244589 122175 244589 120838 244589 120838 244590 122157 244590 122156 244590 122156 244591 122157 244591 122158 244591 122156 244592 122158 244592 122159 244592 122159 244593 122158 244593 120070 244593 122159 244594 120070 244594 120068 244594 122160 244595 122136 244595 119923 244595 122168 244596 122135 244596 122161 244596 122161 244597 122135 244597 122136 244597 120068 244598 122141 244598 122162 244598 122162 244599 122141 244599 122134 244599 122162 244600 122134 244600 122168 244600 119923 244601 122163 244601 122160 244601 122160 244602 122163 244602 119920 244602 122160 244603 119920 244603 122164 244603 122164 244604 119920 244604 122165 244604 122164 244605 122165 244605 122166 244605 122166 244606 122165 244606 119919 244606 122166 244607 119919 244607 122167 244607 122136 244608 122160 244608 122161 244608 122161 244609 122160 244609 122164 244609 122161 244610 122164 244610 122169 244610 122169 244611 122164 244611 122166 244611 122169 244612 122166 244612 122170 244612 122170 244613 122166 244613 122167 244613 122170 244614 122167 244614 122171 244614 122168 244615 122161 244615 122162 244615 122162 244616 122161 244616 122169 244616 122162 244617 122169 244617 122159 244617 122159 244618 122169 244618 122170 244618 122159 244619 122170 244619 122156 244619 122156 244620 122170 244620 122171 244620 122156 244621 122171 244621 122175 244621 122182 244622 120839 244622 122173 244622 122172 244623 122198 244623 122202 244623 122202 244624 122198 244624 122196 244624 122173 244625 120835 244625 122174 244625 120836 244626 120838 244626 122175 244626 122195 244627 122176 244627 122194 244627 122177 244628 122178 244628 122179 244628 122177 244629 122179 244629 122203 244629 122191 244630 122190 244630 122180 244630 122189 244631 122181 244631 122180 244631 122180 244632 122181 244632 120840 244632 122180 244633 120840 244633 122182 244633 122182 244634 120840 244634 122183 244634 122182 244635 122183 244635 120839 244635 122176 244636 122178 244636 122194 244636 122194 244637 122178 244637 122177 244637 122194 244638 122177 244638 122193 244638 122193 244639 122177 244639 122203 244639 122193 244640 122203 244640 122192 244640 122192 244641 122203 244641 122184 244641 122192 244642 122184 244642 122191 244642 119913 244643 122185 244643 122197 244643 122197 244644 122185 244644 122153 244644 122197 244645 122153 244645 122155 244645 122172 244646 122204 244646 122186 244646 122186 244647 122204 244647 122201 244647 122167 244648 119919 244648 122188 244648 120836 244649 122175 244649 122187 244649 122187 244650 122175 244650 122171 244650 122187 244651 122171 244651 122205 244651 122205 244652 122171 244652 122167 244652 122205 244653 122167 244653 122200 244653 122200 244654 122167 244654 122188 244654 122200 244655 122188 244655 122199 244655 122189 244656 122180 244656 120842 244656 120842 244657 122180 244657 122190 244657 120842 244658 122190 244658 120843 244658 122191 244659 122180 244659 122192 244659 122192 244660 122180 244660 122182 244660 122192 244661 122182 244661 122193 244661 122193 244662 122182 244662 122173 244662 122193 244663 122173 244663 122194 244663 122194 244664 122173 244664 122174 244664 122194 244665 122174 244665 122195 244665 122155 244666 122196 244666 122197 244666 122197 244667 122196 244667 122198 244667 122197 244668 122198 244668 119913 244668 119913 244669 122198 244669 122172 244669 119913 244670 122172 244670 122199 244670 122199 244671 122172 244671 122186 244671 122199 244672 122186 244672 122200 244672 122200 244673 122186 244673 122201 244673 122200 244674 122201 244674 122205 244674 122155 244675 122184 244675 122196 244675 122196 244676 122184 244676 122203 244676 122196 244677 122203 244677 122202 244677 122202 244678 122203 244678 122179 244678 122202 244679 122179 244679 122172 244679 122172 244680 122179 244680 122178 244680 122172 244681 122178 244681 122204 244681 122204 244682 122178 244682 122176 244682 122204 244683 122176 244683 122201 244683 122201 244684 122176 244684 122195 244684 122201 244685 122195 244685 122205 244685 122205 244686 122195 244686 122174 244686 122205 244687 122174 244687 122187 244687 122187 244688 122174 244688 120835 244688 122187 244689 120835 244689 120836 244689 122208 244690 119951 244690 122223 244690 122218 244691 119952 244691 122206 244691 122206 244692 119952 244692 122207 244692 122210 244693 120678 244693 122209 244693 122209 244694 120678 244694 122216 244694 122209 244695 122216 244695 122207 244695 122207 244696 122216 244696 122217 244696 122207 244697 122217 244697 122206 244697 119952 244698 119951 244698 122207 244698 122207 244699 119951 244699 122208 244699 122207 244700 122208 244700 122209 244700 122209 244701 122208 244701 122211 244701 122209 244702 122211 244702 122210 244702 122210 244703 122211 244703 122213 244703 122223 244704 122222 244704 122208 244704 122208 244705 122222 244705 122220 244705 122208 244706 122220 244706 122211 244706 122211 244707 122220 244707 122212 244707 122211 244708 122212 244708 122213 244708 122213 244709 122212 244709 122214 244709 120678 244710 120026 244710 122215 244710 120678 244711 122215 244711 122216 244711 122216 244712 122215 244712 122237 244712 122216 244713 122237 244713 122217 244713 122217 244714 122237 244714 122236 244714 122217 244715 122236 244715 122206 244715 122206 244716 122236 244716 119968 244716 122206 244717 119968 244717 122218 244717 122219 244718 122214 244718 122212 244718 122219 244719 122212 244719 122239 244719 122239 244720 122212 244720 122220 244720 122239 244721 122220 244721 122221 244721 122221 244722 122220 244722 122222 244722 122221 244723 122222 244723 122241 244723 122241 244724 122222 244724 122223 244724 122241 244725 122223 244725 122242 244725 122225 244726 122224 244726 122231 244726 122231 244727 122224 244727 119963 244727 122231 244728 119963 244728 122230 244728 122249 244729 122226 244729 122225 244729 122225 244730 122226 244730 122227 244730 122225 244731 122227 244731 122224 244731 122225 244732 122228 244732 122249 244732 122249 244733 122228 244733 122234 244733 122249 244734 122234 244734 122229 244734 122230 244735 119966 244735 122231 244735 122231 244736 119966 244736 122232 244736 122231 244737 122232 244737 122225 244737 122225 244738 122232 244738 122235 244738 122225 244739 122235 244739 122228 244739 122228 244740 122235 244740 122233 244740 122228 244741 122233 244741 122234 244741 122234 244742 122233 244742 120029 244742 119966 244743 119968 244743 122232 244743 122232 244744 119968 244744 122236 244744 122232 244745 122236 244745 122235 244745 122235 244746 122236 244746 122237 244746 122235 244747 122237 244747 122233 244747 122233 244748 122237 244748 122215 244748 122233 244749 122215 244749 120029 244749 120029 244750 122215 244750 120026 244750 122247 244751 122238 244751 122259 244751 122244 244752 122219 244752 122245 244752 122245 244753 122219 244753 122239 244753 122245 244754 122239 244754 122246 244754 122246 244755 122239 244755 122221 244755 122246 244756 122221 244756 122240 244756 122240 244757 122221 244757 122241 244757 122240 244758 122241 244758 122248 244758 122248 244759 122241 244759 122242 244759 120830 244760 122244 244760 122243 244760 122243 244761 122244 244761 122245 244761 122243 244762 122245 244762 122267 244762 122267 244763 122245 244763 122246 244763 122267 244764 122246 244764 122259 244764 122259 244765 122246 244765 122240 244765 122259 244766 122240 244766 122247 244766 122247 244767 122240 244767 122248 244767 122229 244768 120032 244768 122249 244768 122249 244769 120032 244769 122277 244769 122249 244770 122277 244770 122226 244770 122226 244771 122277 244771 122227 244771 122227 244772 122277 244772 122279 244772 122227 244773 122279 244773 122224 244773 122279 244774 122250 244774 122224 244774 122224 244775 122250 244775 119961 244775 122224 244776 119961 244776 119963 244776 122251 244777 122265 244777 122271 244777 122256 244778 122252 244778 122264 244778 122270 244779 122267 244779 122259 244779 119909 244780 122253 244780 122282 244780 122254 244781 120830 244781 122243 244781 122252 244782 122256 244782 122255 244782 122255 244783 122256 244783 122263 244783 122255 244784 122263 244784 120834 244784 122257 244785 119900 244785 122258 244785 122270 244786 122259 244786 122258 244786 122258 244787 122259 244787 122238 244787 122258 244788 122238 244788 122257 244788 122260 244789 120024 244789 122261 244789 122260 244790 122261 244790 122263 244790 122263 244791 122261 244791 122262 244791 122263 244792 122262 244792 120834 244792 122254 244793 122268 244793 122264 244793 122264 244794 122268 244794 122269 244794 122264 244795 122269 244795 122256 244795 122256 244796 122269 244796 122265 244796 122256 244797 122265 244797 122263 244797 122263 244798 122265 244798 122251 244798 122263 244799 122251 244799 122260 244799 122272 244800 119909 244800 122271 244800 122271 244801 119909 244801 122282 244801 122271 244802 122282 244802 122251 244802 122251 244803 122282 244803 122266 244803 122251 244804 122266 244804 122260 244804 122254 244805 122243 244805 122268 244805 122268 244806 122243 244806 122267 244806 122268 244807 122267 244807 122269 244807 122269 244808 122267 244808 122270 244808 122269 244809 122270 244809 122265 244809 122265 244810 122270 244810 122258 244810 122265 244811 122258 244811 122271 244811 122271 244812 122258 244812 119900 244812 122271 244813 119900 244813 122272 244813 119917 244814 119916 244814 122273 244814 122273 244815 119916 244815 122274 244815 122273 244816 122274 244816 122275 244816 122275 244817 122274 244817 122276 244817 122275 244818 122276 244818 122284 244818 122284 244819 122276 244819 122278 244819 122284 244820 122278 244820 122290 244820 122290 244821 122278 244821 120033 244821 122290 244822 120033 244822 120031 244822 120032 244823 120033 244823 122277 244823 122277 244824 120033 244824 122278 244824 122277 244825 122278 244825 122279 244825 122279 244826 122278 244826 122276 244826 122279 244827 122276 244827 122250 244827 122250 244828 122276 244828 122274 244828 122250 244829 122274 244829 119961 244829 119961 244830 122274 244830 119916 244830 122281 244831 119899 244831 122296 244831 120025 244832 120024 244832 122293 244832 122293 244833 120024 244833 122260 244833 122293 244834 122260 244834 122280 244834 122280 244835 122260 244835 122266 244835 122280 244836 122266 244836 122296 244836 122296 244837 122266 244837 122282 244837 122296 244838 122282 244838 122281 244838 122281 244839 122282 244839 122253 244839 122283 244840 119912 244840 122288 244840 122285 244841 122298 244841 122286 244841 122292 244842 122293 244842 122297 244842 122297 244843 122293 244843 122280 244843 122297 244844 122280 244844 122296 244844 122284 244845 122285 244845 122295 244845 122295 244846 122285 244846 122286 244846 122295 244847 122286 244847 122294 244847 122294 244848 122286 244848 122288 244848 122294 244849 122288 244849 122287 244849 122287 244850 122288 244850 119912 244850 120849 244851 122291 244851 120851 244851 120851 244852 122291 244852 122289 244852 120851 244853 122289 244853 120854 244853 120854 244854 122289 244854 122290 244854 120854 244855 122290 244855 120031 244855 120849 244856 120847 244856 122291 244856 122291 244857 120847 244857 120845 244857 122291 244858 120845 244858 122292 244858 122292 244859 120845 244859 120025 244859 122292 244860 120025 244860 122293 244860 122287 244861 119917 244861 122294 244861 122294 244862 119917 244862 122273 244862 122294 244863 122273 244863 122295 244863 122295 244864 122273 244864 122275 244864 122295 244865 122275 244865 122284 244865 119899 244866 122283 244866 122296 244866 122296 244867 122283 244867 122288 244867 122296 244868 122288 244868 122297 244868 122297 244869 122288 244869 122286 244869 122297 244870 122286 244870 122292 244870 122292 244871 122286 244871 122298 244871 122292 244872 122298 244872 122291 244872 122291 244873 122298 244873 122285 244873 122291 244874 122285 244874 122289 244874 122289 244875 122285 244875 122284 244875 122289 244876 122284 244876 122290 244876 122305 244877 119716 244877 122314 244877 119719 244878 119718 244878 122311 244878 122311 244879 119718 244879 122300 244879 122311 244880 122300 244880 122299 244880 122299 244881 122300 244881 122301 244881 122299 244882 122301 244882 119769 244882 119769 244883 122301 244883 122302 244883 119718 244884 119716 244884 122300 244884 122300 244885 119716 244885 122305 244885 122300 244886 122305 244886 122301 244886 122301 244887 122305 244887 122307 244887 122301 244888 122307 244888 122302 244888 122302 244889 122307 244889 122308 244889 122314 244890 122303 244890 122305 244890 122305 244891 122303 244891 122304 244891 122305 244892 122304 244892 122307 244892 122307 244893 122304 244893 122306 244893 122307 244894 122306 244894 122308 244894 122308 244895 122306 244895 119772 244895 119769 244896 122309 244896 122310 244896 119769 244897 122310 244897 122299 244897 122299 244898 122310 244898 122312 244898 122299 244899 122312 244899 122311 244899 122311 244900 122312 244900 119729 244900 122311 244901 119729 244901 119719 244901 119773 244902 119772 244902 122306 244902 119773 244903 122306 244903 122325 244903 122325 244904 122306 244904 122304 244904 122325 244905 122304 244905 122313 244905 122313 244906 122304 244906 122303 244906 122313 244907 122303 244907 122326 244907 122326 244908 122303 244908 122314 244908 122326 244909 122314 244909 119667 244909 119720 244910 119721 244910 122332 244910 122332 244911 119721 244911 122319 244911 122332 244912 122319 244912 122315 244912 122315 244913 122319 244913 122316 244913 122315 244914 122316 244914 122317 244914 122317 244915 122316 244915 120682 244915 119721 244916 122318 244916 122319 244916 122319 244917 122318 244917 122320 244917 122319 244918 122320 244918 122316 244918 122316 244919 122320 244919 122321 244919 122316 244920 122321 244920 120682 244920 120682 244921 122321 244921 122322 244921 122318 244922 119729 244922 122320 244922 122320 244923 119729 244923 122312 244923 122320 244924 122312 244924 122321 244924 122321 244925 122312 244925 122310 244925 122321 244926 122310 244926 122322 244926 122322 244927 122310 244927 122309 244927 122330 244928 122324 244928 122323 244928 122323 244929 122324 244929 122339 244929 122323 244930 119773 244930 122330 244930 122330 244931 119773 244931 122325 244931 122330 244932 122325 244932 122328 244932 122328 244933 122325 244933 122313 244933 122328 244934 122313 244934 122327 244934 122327 244935 122313 244935 122326 244935 122327 244936 122326 244936 119666 244936 119666 244937 122326 244937 119667 244937 119666 244938 122342 244938 122327 244938 122327 244939 122342 244939 122329 244939 122327 244940 122329 244940 122328 244940 122328 244941 122329 244941 122343 244941 122328 244942 122343 244942 122330 244942 122330 244943 122343 244943 122331 244943 122330 244944 122331 244944 122324 244944 122317 244945 122360 244945 122361 244945 122317 244946 122361 244946 122315 244946 122315 244947 122361 244947 122362 244947 122315 244948 122362 244948 122332 244948 122362 244949 122333 244949 122332 244949 122332 244950 122333 244950 119681 244950 122332 244951 119681 244951 119720 244951 122348 244952 122353 244952 122334 244952 122335 244953 119669 244953 122367 244953 122336 244954 120855 244954 122350 244954 122350 244955 120855 244955 122337 244955 122350 244956 122337 244956 122352 244956 122340 244957 122331 244957 122343 244957 122331 244958 122340 244958 122324 244958 120855 244959 122338 244959 122340 244959 122340 244960 122338 244960 122339 244960 122340 244961 122339 244961 122324 244961 122351 244962 122353 244962 122345 244962 122345 244963 122353 244963 122348 244963 122345 244964 122348 244964 122341 244964 122329 244965 122342 244965 119671 244965 120855 244966 122340 244966 122337 244966 122337 244967 122340 244967 122343 244967 122337 244968 122343 244968 122352 244968 122352 244969 122343 244969 122329 244969 122352 244970 122329 244970 122344 244970 122344 244971 122329 244971 119671 244971 122344 244972 119671 244972 122354 244972 120858 244973 122345 244973 122346 244973 122346 244974 122345 244974 122341 244974 122346 244975 122341 244975 119764 244975 120858 244976 122347 244976 122345 244976 122345 244977 122347 244977 120859 244977 122345 244978 120859 244978 122351 244978 122351 244979 120859 244979 122336 244979 119709 244980 122335 244980 122334 244980 122334 244981 122335 244981 122367 244981 122334 244982 122367 244982 122348 244982 122348 244983 122367 244983 122349 244983 122348 244984 122349 244984 122341 244984 122336 244985 122350 244985 122351 244985 122351 244986 122350 244986 122352 244986 122351 244987 122352 244987 122353 244987 122353 244988 122352 244988 122344 244988 122353 244989 122344 244989 122334 244989 122334 244990 122344 244990 122354 244990 122334 244991 122354 244991 119709 244991 119679 244992 122355 244992 122356 244992 122356 244993 122355 244993 122364 244993 122356 244994 122364 244994 122382 244994 122382 244995 122364 244995 122363 244995 122382 244996 122363 244996 122387 244996 122387 244997 122363 244997 122357 244997 122387 244998 122357 244998 122388 244998 122388 244999 122357 244999 122358 244999 122388 245000 122358 245000 122359 245000 122360 245001 122358 245001 122361 245001 122361 245002 122358 245002 122357 245002 122361 245003 122357 245003 122362 245003 122362 245004 122357 245004 122363 245004 122362 245005 122363 245005 122333 245005 122333 245006 122363 245006 122364 245006 122333 245007 122364 245007 119681 245007 119681 245008 122364 245008 122355 245008 120870 245009 119764 245009 122365 245009 122365 245010 119764 245010 122341 245010 122365 245011 122341 245011 122368 245011 122368 245012 122341 245012 122349 245012 122368 245013 122349 245013 122374 245013 122374 245014 122349 245014 122367 245014 122374 245015 122367 245015 122366 245015 122366 245016 122367 245016 119669 245016 122365 245017 122368 245017 122385 245017 122365 245018 122385 245018 122369 245018 122369 245019 122385 245019 122370 245019 122369 245020 122370 245020 122380 245020 122370 245021 122371 245021 122380 245021 122380 245022 122371 245022 122386 245022 122380 245023 122386 245023 122372 245023 122381 245024 122373 245024 122383 245024 122383 245025 122373 245025 119672 245025 122383 245026 119672 245026 122384 245026 122374 245027 122366 245027 119668 245027 122374 245028 119668 245028 122373 245028 122373 245029 119668 245029 122375 245029 122373 245030 122375 245030 119672 245030 122376 245031 122377 245031 122386 245031 122386 245032 122377 245032 122378 245032 122386 245033 122378 245033 122372 245033 122372 245034 122379 245034 122380 245034 122380 245035 122379 245035 120871 245035 122380 245036 120871 245036 122369 245036 122369 245037 120871 245037 120870 245037 122369 245038 120870 245038 122365 245038 122387 245039 122381 245039 122382 245039 122382 245040 122381 245040 122383 245040 122382 245041 122383 245041 122356 245041 122356 245042 122383 245042 122384 245042 122356 245043 122384 245043 119679 245043 122368 245044 122374 245044 122385 245044 122385 245045 122374 245045 122373 245045 122385 245046 122373 245046 122370 245046 122370 245047 122373 245047 122381 245047 122370 245048 122381 245048 122371 245048 122371 245049 122381 245049 122387 245049 122371 245050 122387 245050 122386 245050 122386 245051 122387 245051 122388 245051 122386 245052 122388 245052 122376 245052 122376 245053 122388 245053 122359 245053 122396 245054 119722 245054 122394 245054 119728 245055 119723 245055 122389 245055 122389 245056 119723 245056 122390 245056 122389 245057 122390 245057 122398 245057 122398 245058 122390 245058 122391 245058 122398 245059 122391 245059 122392 245059 122392 245060 122391 245060 120685 245060 119723 245061 119722 245061 122390 245061 122390 245062 119722 245062 122396 245062 122390 245063 122396 245063 122391 245063 122391 245064 122396 245064 122393 245064 122391 245065 122393 245065 120685 245065 120685 245066 122393 245066 120684 245066 122394 245067 122401 245067 122396 245067 122396 245068 122401 245068 122395 245068 122396 245069 122395 245069 122393 245069 122393 245070 122395 245070 122400 245070 122393 245071 122400 245071 120684 245071 120684 245072 122400 245072 119787 245072 122392 245073 119781 245073 122397 245073 122392 245074 122397 245074 122398 245074 122398 245075 122397 245075 122399 245075 122398 245076 122399 245076 122389 245076 122389 245077 122399 245077 119727 245077 122389 245078 119727 245078 119728 245078 119788 245079 119787 245079 122400 245079 119788 245080 122400 245080 122414 245080 122414 245081 122400 245081 122395 245081 122414 245082 122395 245082 122415 245082 122415 245083 122395 245083 122401 245083 122415 245084 122401 245084 122419 245084 122419 245085 122401 245085 122394 245085 122419 245086 122394 245086 122420 245086 119725 245087 122402 245087 122425 245087 122425 245088 122402 245088 122405 245088 122425 245089 122405 245089 122404 245089 122404 245090 122405 245090 122403 245090 122404 245091 122403 245091 122421 245091 122421 245092 122403 245092 122407 245092 122402 245093 122409 245093 122405 245093 122405 245094 122409 245094 122410 245094 122405 245095 122410 245095 122403 245095 122403 245096 122410 245096 122406 245096 122403 245097 122406 245097 122407 245097 122407 245098 122406 245098 122408 245098 122409 245099 119727 245099 122410 245099 122410 245100 119727 245100 122399 245100 122410 245101 122399 245101 122406 245101 122406 245102 122399 245102 122397 245102 122406 245103 122397 245103 122408 245103 122408 245104 122397 245104 119781 245104 122411 245105 122431 245105 122442 245105 119789 245106 119788 245106 122412 245106 122412 245107 119788 245107 122414 245107 122412 245108 122414 245108 122413 245108 122413 245109 122414 245109 122415 245109 122413 245110 122415 245110 122418 245110 122418 245111 122415 245111 122419 245111 122411 245112 122442 245112 119680 245112 122416 245113 119789 245113 122444 245113 122444 245114 119789 245114 122412 245114 122444 245115 122412 245115 122417 245115 122417 245116 122412 245116 122413 245116 122417 245117 122413 245117 122442 245117 122442 245118 122413 245118 122418 245118 122442 245119 122418 245119 119680 245119 119680 245120 122418 245120 122419 245120 119680 245121 122419 245121 122420 245121 122421 245122 122449 245122 122422 245122 122421 245123 122422 245123 122404 245123 122404 245124 122422 245124 122423 245124 122404 245125 122423 245125 122425 245125 122423 245126 122424 245126 122425 245126 122425 245127 122424 245127 119684 245127 122425 245128 119684 245128 119725 245128 122441 245129 122442 245129 122431 245129 122429 245130 122428 245130 122426 245130 122426 245131 122428 245131 122443 245131 122445 245132 122443 245132 122436 245132 122436 245133 122443 245133 122428 245133 122436 245134 122428 245134 122427 245134 122427 245135 122428 245135 122429 245135 122427 245136 122429 245136 122435 245136 122435 245137 122429 245137 122440 245137 122435 245138 122440 245138 122437 245138 122437 245139 122440 245139 122439 245139 119677 245140 122430 245140 122434 245140 122434 245141 122430 245141 122438 245141 122431 245142 122432 245142 122441 245142 122441 245143 122432 245143 119678 245143 122441 245144 119678 245144 122438 245144 122438 245145 119678 245145 122433 245145 122438 245146 122433 245146 122434 245146 122453 245147 119778 245147 120880 245147 120882 245148 120883 245148 122437 245148 122437 245149 120883 245149 120879 245149 122437 245150 120879 245150 122435 245150 122435 245151 120879 245151 120877 245151 122435 245152 120877 245152 122427 245152 122427 245153 120877 245153 122436 245153 122430 245154 122454 245154 122439 245154 122439 245155 122454 245155 122453 245155 122439 245156 122453 245156 122437 245156 122437 245157 122453 245157 120880 245157 122437 245158 120880 245158 120882 245158 122430 245159 122439 245159 122438 245159 122438 245160 122439 245160 122440 245160 122438 245161 122440 245161 122441 245161 122441 245162 122440 245162 122429 245162 122441 245163 122429 245163 122442 245163 122442 245164 122429 245164 122426 245164 122442 245165 122426 245165 122417 245165 122417 245166 122426 245166 122443 245166 122417 245167 122443 245167 122444 245167 122444 245168 122443 245168 122445 245168 122444 245169 122445 245169 122416 245169 119683 245170 122446 245170 122448 245170 122448 245171 122446 245171 122447 245171 122448 245172 122447 245172 122465 245172 122465 245173 122447 245173 122451 245173 122465 245174 122451 245174 122470 245174 122470 245175 122451 245175 122450 245175 122470 245176 122450 245176 122472 245176 122472 245177 122450 245177 119784 245177 122472 245178 119784 245178 120902 245178 122449 245179 119784 245179 122422 245179 122422 245180 119784 245180 122450 245180 122422 245181 122450 245181 122423 245181 122423 245182 122450 245182 122451 245182 122423 245183 122451 245183 122424 245183 122424 245184 122451 245184 122447 245184 122424 245185 122447 245185 119684 245185 119684 245186 122447 245186 122446 245186 119779 245187 119778 245187 122452 245187 122452 245188 119778 245188 122453 245188 122452 245189 122453 245189 122455 245189 122455 245190 122453 245190 122454 245190 122455 245191 122454 245191 122461 245191 122461 245192 122454 245192 122430 245192 122461 245193 122430 245193 122462 245193 122462 245194 122430 245194 119677 245194 122456 245195 122457 245195 122471 245195 122471 245196 122457 245196 122464 245196 122471 245197 122464 245197 122469 245197 122469 245198 122464 245198 122458 245198 122469 245199 122458 245199 122459 245199 122459 245200 122458 245200 122452 245200 122459 245201 122452 245201 122455 245201 122460 245202 122468 245202 122466 245202 122466 245203 122468 245203 119673 245203 122466 245204 119673 245204 122467 245204 122461 245205 122462 245205 119675 245205 122461 245206 119675 245206 122468 245206 122468 245207 119675 245207 119674 245207 122468 245208 119674 245208 119673 245208 122473 245209 120903 245209 122456 245209 122456 245210 120903 245210 120904 245210 122456 245211 120904 245211 122457 245211 122457 245212 122463 245212 122464 245212 122464 245213 122463 245213 120900 245213 122464 245214 120900 245214 122458 245214 122458 245215 120900 245215 119779 245215 122458 245216 119779 245216 122452 245216 122470 245217 122460 245217 122465 245217 122465 245218 122460 245218 122466 245218 122465 245219 122466 245219 122448 245219 122448 245220 122466 245220 122467 245220 122448 245221 122467 245221 119683 245221 122455 245222 122461 245222 122459 245222 122459 245223 122461 245223 122468 245223 122459 245224 122468 245224 122469 245224 122469 245225 122468 245225 122460 245225 122469 245226 122460 245226 122471 245226 122471 245227 122460 245227 122470 245227 122471 245228 122470 245228 122456 245228 122456 245229 122470 245229 122472 245229 122456 245230 122472 245230 122473 245230 122473 245231 122472 245231 120902 245231 122486 245232 122489 245232 119670 245232 122489 245233 122486 245233 122491 245233 122476 245234 122474 245234 122483 245234 122500 245235 122499 245235 122484 245235 122502 245236 122474 245236 122475 245236 122475 245237 122474 245237 122476 245237 122475 245238 122476 245238 120862 245238 122490 245239 122492 245239 122494 245239 122513 245240 122477 245240 122478 245240 122478 245241 122477 245241 122496 245241 122478 245242 122496 245242 122528 245242 122528 245243 122496 245243 122494 245243 122485 245244 119710 245244 122487 245244 122487 245245 119710 245245 122479 245245 122503 245246 122480 245246 122504 245246 122504 245247 122480 245247 122488 245247 122504 245248 122488 245248 122481 245248 122481 245249 122488 245249 122498 245249 122513 245250 122512 245250 122477 245250 122477 245251 122512 245251 120869 245251 122477 245252 120869 245252 120868 245252 122499 245253 122482 245253 122484 245253 122484 245254 122482 245254 122497 245254 122484 245255 122497 245255 122495 245255 122483 245256 122500 245256 122476 245256 122476 245257 122500 245257 122484 245257 122476 245258 122484 245258 120862 245258 120862 245259 122484 245259 122495 245259 120862 245260 122495 245260 120864 245260 120864 245261 122495 245261 120866 245261 119670 245262 122485 245262 122486 245262 122486 245263 122485 245263 122487 245263 122486 245264 122487 245264 122493 245264 122493 245265 122487 245265 122479 245265 122493 245266 122479 245266 122530 245266 122480 245267 119670 245267 122488 245267 122488 245268 119670 245268 122489 245268 122488 245269 122489 245269 122498 245269 122498 245270 122489 245270 122491 245270 122498 245271 122491 245271 122490 245271 122490 245272 122491 245272 122486 245272 122490 245273 122486 245273 122492 245273 122492 245274 122486 245274 122493 245274 122492 245275 122493 245275 122494 245275 122494 245276 122493 245276 122530 245276 122494 245277 122530 245277 122528 245277 120868 245278 120866 245278 122477 245278 122477 245279 120866 245279 122495 245279 122477 245280 122495 245280 122496 245280 122496 245281 122495 245281 122497 245281 122496 245282 122497 245282 122494 245282 122494 245283 122497 245283 122482 245283 122494 245284 122482 245284 122490 245284 122490 245285 122482 245285 122499 245285 122490 245286 122499 245286 122498 245286 122498 245287 122499 245287 122500 245287 122498 245288 122500 245288 122481 245288 122481 245289 122500 245289 122483 245289 122481 245290 122483 245290 122506 245290 122506 245291 122483 245291 122474 245291 122506 245292 122474 245292 122501 245292 122501 245293 122474 245293 122502 245293 122501 245294 122502 245294 122508 245294 122543 245295 122503 245295 122544 245295 122544 245296 122503 245296 122504 245296 122544 245297 122504 245297 122545 245297 122504 245298 122481 245298 122545 245298 122545 245299 122481 245299 122506 245299 122545 245300 122506 245300 122505 245300 122505 245301 122506 245301 122501 245301 122505 245302 122501 245302 122553 245302 122553 245303 122501 245303 122507 245303 122507 245304 122501 245304 122508 245304 122507 245305 122508 245305 122509 245305 122510 245306 122511 245306 122523 245306 122512 245307 122513 245307 119808 245307 119808 245308 122513 245308 122525 245308 119808 245309 122525 245309 122527 245309 122514 245310 119705 245310 122519 245310 122519 245311 119705 245311 122585 245311 122519 245312 122585 245312 122520 245312 122520 245313 122585 245313 122516 245313 122520 245314 122516 245314 122515 245314 122515 245315 122516 245315 122517 245315 122515 245316 122517 245316 122518 245316 122518 245317 122517 245317 119798 245317 119707 245318 122514 245318 122524 245318 122524 245319 122514 245319 122519 245319 122524 245320 122519 245320 122521 245320 122521 245321 122519 245321 122520 245321 122521 245322 122520 245322 122526 245322 122526 245323 122520 245323 122515 245323 122526 245324 122515 245324 122522 245324 122522 245325 122515 245325 122518 245325 122511 245326 119707 245326 122523 245326 122523 245327 119707 245327 122524 245327 122523 245328 122524 245328 122529 245328 122529 245329 122524 245329 122521 245329 122529 245330 122521 245330 122525 245330 122525 245331 122521 245331 122526 245331 122525 245332 122526 245332 122527 245332 122527 245333 122526 245333 122522 245333 122513 245334 122478 245334 122525 245334 122525 245335 122478 245335 122528 245335 122525 245336 122528 245336 122529 245336 122529 245337 122528 245337 122530 245337 122529 245338 122530 245338 122523 245338 122523 245339 122530 245339 122479 245339 122523 245340 122479 245340 122510 245340 122510 245341 122479 245341 119710 245341 120886 245342 122539 245342 122552 245342 122563 245343 122531 245343 122532 245343 122532 245344 122531 245344 122562 245344 122536 245345 122555 245345 122537 245345 122550 245346 120885 245346 122604 245346 122568 245347 122534 245347 122533 245347 122533 245348 122534 245348 122558 245348 122534 245349 122565 245349 122558 245349 122558 245350 122565 245350 122564 245350 122558 245351 122564 245351 122535 245351 122536 245352 122537 245352 122538 245352 122539 245353 122538 245353 122552 245353 122552 245354 122538 245354 122537 245354 122552 245355 122537 245355 122554 245355 122554 245356 122537 245356 122541 245356 122554 245357 122541 245357 122540 245357 122540 245358 122541 245358 122557 245358 122540 245359 122557 245359 122542 245359 122560 245360 122543 245360 122559 245360 122559 245361 122543 245361 122544 245361 122559 245362 122544 245362 122545 245362 122563 245363 122547 245363 122546 245363 122546 245364 122547 245364 122548 245364 122608 245365 122609 245365 122549 245365 122550 245366 122604 245366 122567 245366 122567 245367 122604 245367 122605 245367 122567 245368 122605 245368 122566 245368 122566 245369 122605 245369 122608 245369 122566 245370 122608 245370 122551 245370 122551 245371 122608 245371 122549 245371 122551 245372 122549 245372 122561 245372 122509 245373 120886 245373 122507 245373 122507 245374 120886 245374 122552 245374 122507 245375 122552 245375 122553 245375 122553 245376 122552 245376 122554 245376 122553 245377 122554 245377 122505 245377 122505 245378 122554 245378 122540 245378 122555 245379 122556 245379 122537 245379 122537 245380 122556 245380 122533 245380 122537 245381 122533 245381 122541 245381 122541 245382 122533 245382 122558 245382 122541 245383 122558 245383 122557 245383 122557 245384 122558 245384 122535 245384 122557 245385 122535 245385 122542 245385 122545 245386 122562 245386 122559 245386 122559 245387 122562 245387 122531 245387 122559 245388 122531 245388 122560 245388 122560 245389 122531 245389 122563 245389 122560 245390 122563 245390 122561 245390 122561 245391 122563 245391 122546 245391 122561 245392 122546 245392 122551 245392 122551 245393 122546 245393 122548 245393 122551 245394 122548 245394 122566 245394 122545 245395 122505 245395 122562 245395 122562 245396 122505 245396 122540 245396 122562 245397 122540 245397 122532 245397 122532 245398 122540 245398 122542 245398 122532 245399 122542 245399 122563 245399 122563 245400 122542 245400 122535 245400 122563 245401 122535 245401 122547 245401 122547 245402 122535 245402 122564 245402 122547 245403 122564 245403 122548 245403 122548 245404 122564 245404 122565 245404 122548 245405 122565 245405 122566 245405 122566 245406 122565 245406 122534 245406 122566 245407 122534 245407 122567 245407 122567 245408 122534 245408 122568 245408 122567 245409 122568 245409 122550 245409 119806 245410 122591 245410 122580 245410 122569 245411 119703 245411 122581 245411 122569 245412 122581 245412 122589 245412 122573 245413 122570 245413 122578 245413 122587 245414 122586 245414 122571 245414 122571 245415 122586 245415 122573 245415 122571 245416 122573 245416 122572 245416 122572 245417 122573 245417 122578 245417 122611 245418 122574 245418 122579 245418 119806 245419 122580 245419 119807 245419 119799 245420 122587 245420 122575 245420 122575 245421 122587 245421 122571 245421 122575 245422 122571 245422 119802 245422 119802 245423 122571 245423 122572 245423 119802 245424 122572 245424 122576 245424 122576 245425 122572 245425 122578 245425 122576 245426 122578 245426 122577 245426 122577 245427 122578 245427 119804 245427 122579 245428 119807 245428 122611 245428 122611 245429 119807 245429 122580 245429 122611 245430 122580 245430 122581 245430 122581 245431 122580 245431 122590 245431 122581 245432 122590 245432 122589 245432 122585 245433 119705 245433 122584 245433 122584 245434 119705 245434 122582 245434 122584 245435 122582 245435 122583 245435 122583 245436 122570 245436 122584 245436 122584 245437 122570 245437 122573 245437 122584 245438 122573 245438 122585 245438 122585 245439 122573 245439 122586 245439 122585 245440 122586 245440 122516 245440 122516 245441 122586 245441 122587 245441 122516 245442 122587 245442 122517 245442 122517 245443 122587 245443 119799 245443 122517 245444 119799 245444 119798 245444 122582 245445 122588 245445 122583 245445 122583 245446 122588 245446 122589 245446 122583 245447 122589 245447 122570 245447 122570 245448 122589 245448 122590 245448 122570 245449 122590 245449 122578 245449 122578 245450 122590 245450 122580 245450 122578 245451 122580 245451 119804 245451 119804 245452 122580 245452 122591 245452 119712 245453 119713 245453 122618 245453 122618 245454 119713 245454 122592 245454 122618 245455 122592 245455 122593 245455 122593 245456 122592 245456 122598 245456 122593 245457 122598 245457 122594 245457 122594 245458 122598 245458 122597 245458 122594 245459 122597 245459 122595 245459 122595 245460 122597 245460 119793 245460 122595 245461 119793 245461 120691 245461 122599 245462 119793 245462 122596 245462 122596 245463 119793 245463 122597 245463 122596 245464 122597 245464 122600 245464 122600 245465 122597 245465 122598 245465 122600 245466 122598 245466 122602 245466 122602 245467 122598 245467 122592 245467 122602 245468 122592 245468 122603 245468 122603 245469 122592 245469 119713 245469 119792 245470 122599 245470 122606 245470 122606 245471 122599 245471 122596 245471 122606 245472 122596 245472 122607 245472 122607 245473 122596 245473 122600 245473 122607 245474 122600 245474 122610 245474 122610 245475 122600 245475 122602 245475 122610 245476 122602 245476 122601 245476 122601 245477 122602 245477 122603 245477 120885 245478 119792 245478 122604 245478 122604 245479 119792 245479 122606 245479 122604 245480 122606 245480 122605 245480 122605 245481 122606 245481 122607 245481 122605 245482 122607 245482 122608 245482 122608 245483 122607 245483 122610 245483 122608 245484 122610 245484 122609 245484 122609 245485 122610 245485 122601 245485 119796 245486 122574 245486 122612 245486 122612 245487 122574 245487 122611 245487 122612 245488 122611 245488 122619 245488 122619 245489 122611 245489 122581 245489 122619 245490 122581 245490 119702 245490 119702 245491 122581 245491 119703 245491 122620 245492 119796 245492 122612 245492 122613 245493 122628 245493 122627 245493 122627 245494 122628 245494 122622 245494 122627 245495 122622 245495 122615 245495 122615 245496 122622 245496 122614 245496 122615 245497 122614 245497 122616 245497 122624 245498 119712 245498 122617 245498 122617 245499 119712 245499 122618 245499 122617 245500 122618 245500 122593 245500 119702 245501 119698 245501 122619 245501 122619 245502 119698 245502 122616 245502 122619 245503 122616 245503 122612 245503 122612 245504 122616 245504 122614 245504 122612 245505 122614 245505 122620 245505 122620 245506 122614 245506 120688 245506 122628 245507 122621 245507 122622 245507 122622 245508 122621 245508 122623 245508 122622 245509 122623 245509 122614 245509 122614 245510 122623 245510 120689 245510 122614 245511 120689 245511 120688 245511 119696 245512 122624 245512 122625 245512 122625 245513 122624 245513 122617 245513 122625 245514 122617 245514 122626 245514 122626 245515 122617 245515 122593 245515 122626 245516 122593 245516 122594 245516 119698 245517 119696 245517 122616 245517 122616 245518 119696 245518 122625 245518 122616 245519 122625 245519 122615 245519 122615 245520 122625 245520 122626 245520 122615 245521 122626 245521 122627 245521 122627 245522 122626 245522 122594 245522 122627 245523 122594 245523 122613 245523 122613 245524 122594 245524 122595 245524 122613 245525 122595 245525 122628 245525 122628 245526 122595 245526 120691 245526 122653 245527 122630 245527 122629 245527 122630 245528 122653 245528 122652 245528 122644 245529 122660 245529 122659 245529 122657 245530 122631 245530 122643 245530 120889 245531 122660 245531 122632 245531 122632 245532 122660 245532 122644 245532 122632 245533 122644 245533 120892 245533 122633 245534 122654 245534 122637 245534 122634 245535 122635 245535 122672 245535 122672 245536 122635 245536 122636 245536 122672 245537 122636 245537 122673 245537 122673 245538 122636 245538 122637 245538 122647 245539 122638 245539 122639 245539 122639 245540 122638 245540 122681 245540 122662 245541 122649 245541 122640 245541 122640 245542 122649 245542 122650 245542 122640 245543 122650 245543 122641 245543 122641 245544 122650 245544 122651 245544 122634 245545 119815 245545 122635 245545 122635 245546 119815 245546 120897 245546 122635 245547 120897 245547 120896 245547 122631 245548 122642 245548 122643 245548 122643 245549 122642 245549 122656 245549 122643 245550 122656 245550 122646 245550 122659 245551 122657 245551 122644 245551 122644 245552 122657 245552 122643 245552 122644 245553 122643 245553 120892 245553 120892 245554 122643 245554 122646 245554 120892 245555 122646 245555 122645 245555 122645 245556 122646 245556 120894 245556 122629 245557 122647 245557 122653 245557 122653 245558 122647 245558 122639 245558 122653 245559 122639 245559 122655 245559 122655 245560 122639 245560 122681 245560 122655 245561 122681 245561 122648 245561 122649 245562 122629 245562 122650 245562 122650 245563 122629 245563 122630 245563 122650 245564 122630 245564 122651 245564 122651 245565 122630 245565 122652 245565 122651 245566 122652 245566 122633 245566 122633 245567 122652 245567 122653 245567 122633 245568 122653 245568 122654 245568 122654 245569 122653 245569 122655 245569 122654 245570 122655 245570 122637 245570 122637 245571 122655 245571 122648 245571 122637 245572 122648 245572 122673 245572 120896 245573 120894 245573 122635 245573 122635 245574 120894 245574 122646 245574 122635 245575 122646 245575 122636 245575 122636 245576 122646 245576 122656 245576 122636 245577 122656 245577 122637 245577 122637 245578 122656 245578 122642 245578 122637 245579 122642 245579 122633 245579 122633 245580 122642 245580 122631 245580 122633 245581 122631 245581 122651 245581 122651 245582 122631 245582 122657 245582 122651 245583 122657 245583 122641 245583 122641 245584 122657 245584 122659 245584 122641 245585 122659 245585 122658 245585 122658 245586 122659 245586 122660 245586 122658 245587 122660 245587 122666 245587 122666 245588 122660 245588 120889 245588 122666 245589 120889 245589 119820 245589 119676 245590 122662 245590 122661 245590 122661 245591 122662 245591 122640 245591 122661 245592 122640 245592 122663 245592 122640 245593 122641 245593 122663 245593 122663 245594 122641 245594 122658 245594 122663 245595 122658 245595 122664 245595 122664 245596 122658 245596 122666 245596 122664 245597 122666 245597 122665 245597 122665 245598 122666 245598 122667 245598 122667 245599 122666 245599 119820 245599 122667 245600 119820 245600 120910 245600 122673 245601 122648 245601 122682 245601 122671 245602 119815 245602 122634 245602 122686 245603 122687 245603 122738 245603 122671 245604 122668 245604 119817 245604 119817 245605 122668 245605 122685 245605 119817 245606 122685 245606 119814 245606 119814 245607 122685 245607 122686 245607 119814 245608 122686 245608 122669 245608 122669 245609 122686 245609 122738 245609 122648 245610 122681 245610 122670 245610 122671 245611 122634 245611 122668 245611 122668 245612 122634 245612 122672 245612 122668 245613 122672 245613 122673 245613 122725 245614 122675 245614 122674 245614 122674 245615 122675 245615 122676 245615 122674 245616 122676 245616 122677 245616 122677 245617 122676 245617 122678 245617 122677 245618 122678 245618 122679 245618 122679 245619 122678 245619 122670 245619 122679 245620 122670 245620 122680 245620 122680 245621 122670 245621 122681 245621 122680 245622 122681 245622 122638 245622 122648 245623 122670 245623 122682 245623 122682 245624 122670 245624 122678 245624 122682 245625 122678 245625 122684 245625 122684 245626 122678 245626 122676 245626 122684 245627 122676 245627 122683 245627 122683 245628 122676 245628 122675 245628 122683 245629 122675 245629 122735 245629 122673 245630 122682 245630 122668 245630 122668 245631 122682 245631 122684 245631 122668 245632 122684 245632 122685 245632 122685 245633 122684 245633 122683 245633 122685 245634 122683 245634 122686 245634 122686 245635 122683 245635 122735 245635 122686 245636 122735 245636 122687 245636 122704 245637 122688 245637 122696 245637 122714 245638 122689 245638 122690 245638 122690 245639 122689 245639 122713 245639 122691 245640 122705 245640 122706 245640 122702 245641 122703 245641 122719 245641 122702 245642 122719 245642 122692 245642 122692 245643 122719 245643 120905 245643 122692 245644 120905 245644 119825 245644 122693 245645 122718 245645 120907 245645 120907 245646 122718 245646 122708 245646 122718 245647 122694 245647 122708 245647 122708 245648 122694 245648 122695 245648 122708 245649 122695 245649 122715 245649 122691 245650 122706 245650 120908 245650 122688 245651 120908 245651 122696 245651 122696 245652 120908 245652 122706 245652 122696 245653 122706 245653 122697 245653 122697 245654 122706 245654 122698 245654 122697 245655 122698 245655 122699 245655 122699 245656 122698 245656 122700 245656 122699 245657 122700 245657 122701 245657 119682 245658 119676 245658 122712 245658 122712 245659 119676 245659 122661 245659 122712 245660 122661 245660 122663 245660 122702 245661 122739 245661 122703 245661 122703 245662 122739 245662 122709 245662 122703 245663 122709 245663 122717 245663 122717 245664 122709 245664 122710 245664 122717 245665 122710 245665 122716 245665 122716 245666 122710 245666 122714 245666 120910 245667 122704 245667 122667 245667 122667 245668 122704 245668 122696 245668 122667 245669 122696 245669 122665 245669 122665 245670 122696 245670 122697 245670 122665 245671 122697 245671 122664 245671 122664 245672 122697 245672 122699 245672 122705 245673 122707 245673 122706 245673 122706 245674 122707 245674 120907 245674 122706 245675 120907 245675 122698 245675 122698 245676 120907 245676 122708 245676 122698 245677 122708 245677 122700 245677 122700 245678 122708 245678 122715 245678 122700 245679 122715 245679 122701 245679 122739 245680 119688 245680 122709 245680 122709 245681 119688 245681 119687 245681 122709 245682 119687 245682 122710 245682 122710 245683 119687 245683 122711 245683 122710 245684 122711 245684 122714 245684 122714 245685 122711 245685 119682 245685 122714 245686 119682 245686 122689 245686 122689 245687 119682 245687 122712 245687 122689 245688 122712 245688 122713 245688 122713 245689 122712 245689 122663 245689 122663 245690 122664 245690 122713 245690 122713 245691 122664 245691 122699 245691 122713 245692 122699 245692 122690 245692 122690 245693 122699 245693 122701 245693 122690 245694 122701 245694 122714 245694 122714 245695 122701 245695 122715 245695 122714 245696 122715 245696 122716 245696 122716 245697 122715 245697 122695 245697 122716 245698 122695 245698 122717 245698 122717 245699 122695 245699 122694 245699 122717 245700 122694 245700 122703 245700 122703 245701 122694 245701 122718 245701 122703 245702 122718 245702 122719 245702 122719 245703 122718 245703 122693 245703 122719 245704 122693 245704 120905 245704 120697 245705 122722 245705 122726 245705 122728 245706 122720 245706 122721 245706 122736 245707 122734 245707 122721 245707 122736 245708 122721 245708 122737 245708 122737 245709 122721 245709 122720 245709 122737 245710 122720 245710 120693 245710 122722 245711 122730 245711 122726 245711 122726 245712 122730 245712 122724 245712 122726 245713 122724 245713 122723 245713 122723 245714 122724 245714 122752 245714 122723 245715 122752 245715 122753 245715 122675 245716 122725 245716 122733 245716 122733 245717 122725 245717 119711 245717 122733 245718 119711 245718 122732 245718 122732 245719 119711 245719 119695 245719 120697 245720 122726 245720 120699 245720 120699 245721 122726 245721 122723 245721 120699 245722 122723 245722 120700 245722 120700 245723 122723 245723 122753 245723 120700 245724 122753 245724 122755 245724 122722 245725 120696 245725 122730 245725 122730 245726 120696 245726 122727 245726 122730 245727 122727 245727 122729 245727 122729 245728 122727 245728 122728 245728 122728 245729 122721 245729 122729 245729 122729 245730 122721 245730 122734 245730 122729 245731 122734 245731 122730 245731 122730 245732 122734 245732 122731 245732 122730 245733 122731 245733 122724 245733 122724 245734 122731 245734 119697 245734 122724 245735 119697 245735 122752 245735 122752 245736 119697 245736 119699 245736 122752 245737 119699 245737 119700 245737 119695 245738 119697 245738 122732 245738 122732 245739 119697 245739 122731 245739 122732 245740 122731 245740 122733 245740 122733 245741 122731 245741 122734 245741 122733 245742 122734 245742 122675 245742 122675 245743 122734 245743 122736 245743 122675 245744 122736 245744 122735 245744 122735 245745 122736 245745 122737 245745 122735 245746 122737 245746 122687 245746 122687 245747 122737 245747 120693 245747 122687 245748 120693 245748 122738 245748 119688 245749 122739 245749 122747 245749 122748 245750 122744 245750 122745 245750 122744 245751 122756 245751 122757 245751 122756 245752 122744 245752 122772 245752 122767 245753 122765 245753 122740 245753 122740 245754 122765 245754 122773 245754 119821 245755 112207 245755 122767 245755 122767 245756 122740 245756 119821 245756 119821 245757 122740 245757 122749 245757 119821 245758 122749 245758 122741 245758 122741 245759 122749 245759 122751 245759 122741 245760 122751 245760 119822 245760 119822 245761 122751 245761 122742 245761 122742 245762 122751 245762 122692 245762 122742 245763 122692 245763 119825 245763 122757 245764 119692 245764 122744 245764 122744 245765 119692 245765 122743 245765 122744 245766 122743 245766 122745 245766 122745 245767 122743 245767 119691 245767 122745 245768 119691 245768 122747 245768 122747 245769 119691 245769 119689 245769 122747 245770 119689 245770 119688 245770 122748 245771 122745 245771 122746 245771 122746 245772 122745 245772 122747 245772 122746 245773 122747 245773 122750 245773 122750 245774 122747 245774 122739 245774 122750 245775 122739 245775 122702 245775 122772 245776 122744 245776 122773 245776 122773 245777 122744 245777 122748 245777 122773 245778 122748 245778 122740 245778 122740 245779 122748 245779 122746 245779 122740 245780 122746 245780 122749 245780 122749 245781 122746 245781 122750 245781 122749 245782 122750 245782 122751 245782 122751 245783 122750 245783 122702 245783 122751 245784 122702 245784 122692 245784 119700 245785 122760 245785 122752 245785 122752 245786 122760 245786 122771 245786 122752 245787 122771 245787 122753 245787 122753 245788 122771 245788 122754 245788 122753 245789 122754 245789 122755 245789 122755 245790 122754 245790 112211 245790 122756 245791 122758 245791 122757 245791 122757 245792 122758 245792 119693 245792 119693 245793 122758 245793 119694 245793 119694 245794 122758 245794 122759 245794 119694 245795 122759 245795 119701 245795 119701 245796 122759 245796 122771 245796 119701 245797 122771 245797 122760 245797 122777 245798 122762 245798 122761 245798 122761 245799 122762 245799 112209 245799 122761 245800 112209 245800 122754 245800 122754 245801 112209 245801 112211 245801 122763 245802 122764 245802 122776 245802 122763 245803 122766 245803 122764 245803 122764 245804 122766 245804 122769 245804 122764 245805 122769 245805 122770 245805 122768 245806 122767 245806 112207 245806 122773 245807 122765 245807 122766 245807 122766 245808 122765 245808 122767 245808 122766 245809 122767 245809 122769 245809 122769 245810 122767 245810 122768 245810 122769 245811 122768 245811 122770 245811 122754 245812 122771 245812 122761 245812 122761 245813 122771 245813 122759 245813 122761 245814 122759 245814 122775 245814 122775 245815 122759 245815 122758 245815 122775 245816 122758 245816 122774 245816 122774 245817 122758 245817 122756 245817 122774 245818 122756 245818 122772 245818 122772 245819 122773 245819 122774 245819 122774 245820 122773 245820 122766 245820 122774 245821 122766 245821 122775 245821 122775 245822 122766 245822 122763 245822 122775 245823 122763 245823 122761 245823 122761 245824 122763 245824 122776 245824 122761 245825 122776 245825 122777 245825 122788 245826 122778 245826 122799 245826 122779 245827 122796 245827 119471 245827 119471 245828 122796 245828 122780 245828 119471 245829 122780 245829 122781 245829 122783 245830 122786 245830 122782 245830 122782 245831 122791 245831 122783 245831 122783 245832 122791 245832 122792 245832 122783 245833 122792 245833 122779 245833 122779 245834 122792 245834 122784 245834 122779 245835 122784 245835 122796 245835 119471 245836 122778 245836 122779 245836 122779 245837 122778 245837 122788 245837 122779 245838 122788 245838 122783 245838 122783 245839 122788 245839 122785 245839 122783 245840 122785 245840 122786 245840 122786 245841 122785 245841 122787 245841 122799 245842 122798 245842 122788 245842 122788 245843 122798 245843 122789 245843 122788 245844 122789 245844 122785 245844 122785 245845 122789 245845 122790 245845 122785 245846 122790 245846 122787 245846 122787 245847 122790 245847 119533 245847 119532 245848 122793 245848 122782 245848 122782 245849 122793 245849 122791 245849 122791 245850 122793 245850 122792 245850 122792 245851 122793 245851 122794 245851 122792 245852 122794 245852 122784 245852 122784 245853 122794 245853 122795 245853 122784 245854 122795 245854 122796 245854 122796 245855 122795 245855 122807 245855 122796 245856 122807 245856 122780 245856 122807 245857 122800 245857 122780 245857 122780 245858 122800 245858 119472 245858 122780 245859 119472 245859 122781 245859 119534 245860 119533 245860 122790 245860 119534 245861 122790 245861 122797 245861 122797 245862 122790 245862 122789 245862 122797 245863 122789 245863 122810 245863 122810 245864 122789 245864 122798 245864 122810 245865 122798 245865 122811 245865 122811 245866 122798 245866 122799 245866 122811 245867 122799 245867 119431 245867 119468 245868 119472 245868 122800 245868 119468 245869 122800 245869 122806 245869 122801 245870 122805 245870 122817 245870 122817 245871 122805 245871 122802 245871 122817 245872 122802 245872 122816 245872 122816 245873 122802 245873 122803 245873 122816 245874 122803 245874 122804 245874 122805 245875 119468 245875 122802 245875 122802 245876 119468 245876 122806 245876 122802 245877 122806 245877 122803 245877 122803 245878 122806 245878 122808 245878 122800 245879 122807 245879 122806 245879 122806 245880 122807 245880 122795 245880 122806 245881 122795 245881 122808 245881 122808 245882 122795 245882 122794 245882 122808 245883 122794 245883 122793 245883 122804 245884 122803 245884 120716 245884 120716 245885 122803 245885 122808 245885 120716 245886 122808 245886 120718 245886 120718 245887 122808 245887 122793 245887 120718 245888 122793 245888 119532 245888 122812 245889 119534 245889 122813 245889 122813 245890 119534 245890 122797 245890 122813 245891 122797 245891 122809 245891 122809 245892 122797 245892 122810 245892 122809 245893 122810 245893 122814 245893 122814 245894 122810 245894 122811 245894 122814 245895 122811 245895 122815 245895 122815 245896 122811 245896 119431 245896 119536 245897 122812 245897 122840 245897 122840 245898 122812 245898 122813 245898 122840 245899 122813 245899 122839 245899 122839 245900 122813 245900 122809 245900 122839 245901 122809 245901 122837 245901 122837 245902 122809 245902 122814 245902 122837 245903 122814 245903 119429 245903 119429 245904 122814 245904 122815 245904 122804 245905 122846 245905 122847 245905 122804 245906 122847 245906 122816 245906 122816 245907 122847 245907 122848 245907 122816 245908 122848 245908 122817 245908 122848 245909 122849 245909 122817 245909 122817 245910 122849 245910 122850 245910 122817 245911 122850 245911 122801 245911 122834 245912 122837 245912 119429 245912 122838 245913 122836 245913 122828 245913 122827 245914 122842 245914 122841 245914 122833 245915 122818 245915 122835 245915 122835 245916 122818 245916 122826 245916 122835 245917 122826 245917 122836 245917 122836 245918 122826 245918 122819 245918 122836 245919 122819 245919 122828 245919 122818 245920 120928 245920 122825 245920 122854 245921 122831 245921 122820 245921 122820 245922 122831 245922 122832 245922 119429 245923 122821 245923 122834 245923 122834 245924 122821 245924 122822 245924 122834 245925 122822 245925 122832 245925 122832 245926 122822 245926 122823 245926 122832 245927 122823 245927 122820 245927 122830 245928 122824 245928 120926 245928 122818 245929 122825 245929 122826 245929 122826 245930 122825 245930 120924 245930 122826 245931 120924 245931 122819 245931 122819 245932 120924 245932 122827 245932 122819 245933 122827 245933 122828 245933 122828 245934 122827 245934 122841 245934 122828 245935 122841 245935 122838 245935 122831 245936 122829 245936 122833 245936 122833 245937 122829 245937 122830 245937 122833 245938 122830 245938 122818 245938 122818 245939 122830 245939 120926 245939 122818 245940 120926 245940 120928 245940 122831 245941 122833 245941 122832 245941 122832 245942 122833 245942 122835 245942 122832 245943 122835 245943 122834 245943 122834 245944 122835 245944 122836 245944 122834 245945 122836 245945 122837 245945 122837 245946 122836 245946 122838 245946 122837 245947 122838 245947 122839 245947 122839 245948 122838 245948 122841 245948 122839 245949 122841 245949 122840 245949 122840 245950 122841 245950 122842 245950 122840 245951 122842 245951 119536 245951 122843 245952 119433 245952 122851 245952 119425 245953 122843 245953 122871 245953 122871 245954 122843 245954 122851 245954 122871 245955 122851 245955 122869 245955 122869 245956 122851 245956 122844 245956 122869 245957 122844 245957 122860 245957 122860 245958 122844 245958 122845 245958 122860 245959 122845 245959 122876 245959 122876 245960 122845 245960 119541 245960 122876 245961 119541 245961 120960 245961 122846 245962 119541 245962 122847 245962 122847 245963 119541 245963 122845 245963 122847 245964 122845 245964 122848 245964 122848 245965 122845 245965 122844 245965 122848 245966 122844 245966 122849 245966 122849 245967 122844 245967 122851 245967 122849 245968 122851 245968 122850 245968 122850 245969 122851 245969 119433 245969 122853 245970 119427 245970 122872 245970 122857 245971 122824 245971 122858 245971 122858 245972 122824 245972 122830 245972 122858 245973 122830 245973 122852 245973 122852 245974 122830 245974 122829 245974 122852 245975 122829 245975 122872 245975 122872 245976 122829 245976 122831 245976 122872 245977 122831 245977 122853 245977 122853 245978 122831 245978 122854 245978 122855 245979 122857 245979 122856 245979 122856 245980 122857 245980 122858 245980 122856 245981 122858 245981 122873 245981 122873 245982 122858 245982 122852 245982 122873 245983 122852 245983 122872 245983 122862 245984 122874 245984 122859 245984 122860 245985 122876 245985 122874 245985 122859 245986 122861 245986 122862 245986 122862 245987 122861 245987 122864 245987 122862 245988 122864 245988 122863 245988 122863 245989 122864 245989 122865 245989 122863 245990 122865 245990 122870 245990 119424 245991 122870 245991 122866 245991 122866 245992 122870 245992 122865 245992 122866 245993 122865 245993 122867 245993 122867 245994 122865 245994 122868 245994 122874 245995 122862 245995 122860 245995 122860 245996 122862 245996 122863 245996 122860 245997 122863 245997 122869 245997 122869 245998 122863 245998 122870 245998 122869 245999 122870 245999 122871 245999 122871 246000 122870 246000 119424 246000 122871 246001 119424 246001 119425 246001 119427 246002 122868 246002 122872 246002 122872 246003 122868 246003 122865 246003 122872 246004 122865 246004 122873 246004 122873 246005 122865 246005 122864 246005 122873 246006 122864 246006 122856 246006 122856 246007 122864 246007 122861 246007 122856 246008 122861 246008 122855 246008 122855 246009 122861 246009 122859 246009 122855 246010 122859 246010 120959 246010 120959 246011 122859 246011 122874 246011 120959 246012 122874 246012 122875 246012 122875 246013 122874 246013 122876 246013 122875 246014 122876 246014 120960 246014 119565 246015 120726 246015 122877 246015 119565 246016 122877 246016 122879 246016 122879 246017 122877 246017 122878 246017 122879 246018 122878 246018 122890 246018 122890 246019 122878 246019 122882 246019 122890 246020 122882 246020 122892 246020 122892 246021 122882 246021 119473 246021 122892 246022 119473 246022 122893 246022 119467 246023 119474 246023 122880 246023 122880 246024 119474 246024 122883 246024 122880 246025 122883 246025 122900 246025 122900 246026 122883 246026 122881 246026 122900 246027 122881 246027 122899 246027 122899 246028 122881 246028 122884 246028 122899 246029 122884 246029 120724 246029 120724 246030 122884 246030 120725 246030 119474 246031 119473 246031 122883 246031 122883 246032 119473 246032 122882 246032 122883 246033 122882 246033 122881 246033 122881 246034 122882 246034 122878 246034 122881 246035 122878 246035 122884 246035 122884 246036 122878 246036 122877 246036 122884 246037 122877 246037 120725 246037 120725 246038 122877 246038 120726 246038 122888 246039 119426 246039 122887 246039 122915 246040 119566 246040 122885 246040 122885 246041 119566 246041 122886 246041 122885 246042 122886 246042 122912 246042 122912 246043 122886 246043 122891 246043 122912 246044 122891 246044 122887 246044 122887 246045 122891 246045 122894 246045 122887 246046 122894 246046 122888 246046 122888 246047 122894 246047 122889 246047 122892 246048 122894 246048 122890 246048 122890 246049 122894 246049 122891 246049 122890 246050 122891 246050 122879 246050 122879 246051 122891 246051 122886 246051 122879 246052 122886 246052 119565 246052 119565 246053 122886 246053 119566 246053 122892 246054 122893 246054 122894 246054 122894 246055 122893 246055 122895 246055 122894 246056 122895 246056 122889 246056 120721 246057 120720 246057 122896 246057 122896 246058 120720 246058 122922 246058 122896 246059 122922 246059 122897 246059 122897 246060 122922 246060 122898 246060 122897 246061 122898 246061 122901 246061 122901 246062 122898 246062 122920 246062 122901 246063 122920 246063 119466 246063 119466 246064 122920 246064 122916 246064 120724 246065 120721 246065 122899 246065 122899 246066 120721 246066 122896 246066 122899 246067 122896 246067 122900 246067 122900 246068 122896 246068 122897 246068 122900 246069 122897 246069 122880 246069 122880 246070 122897 246070 122901 246070 122880 246071 122901 246071 119467 246071 119467 246072 122901 246072 119466 246072 122902 246073 122923 246073 120965 246073 122909 246074 119423 246074 122904 246074 122906 246075 122913 246075 122911 246075 122923 246076 122902 246076 122903 246076 122903 246077 122902 246077 122910 246077 122903 246078 122910 246078 122904 246078 119426 246079 122909 246079 122887 246079 122887 246080 122909 246080 122905 246080 122911 246081 122910 246081 122906 246081 122906 246082 122910 246082 122902 246082 122906 246083 122902 246083 122907 246083 122907 246084 122902 246084 120965 246084 122914 246085 122913 246085 122908 246085 122908 246086 122913 246086 122906 246086 122908 246087 122906 246087 120963 246087 120963 246088 122906 246088 122907 246088 122909 246089 122904 246089 122905 246089 122905 246090 122904 246090 122910 246090 122905 246091 122910 246091 122887 246091 122887 246092 122910 246092 122911 246092 122887 246093 122911 246093 122912 246093 122912 246094 122911 246094 122913 246094 122912 246095 122913 246095 122885 246095 122885 246096 122913 246096 122914 246096 122885 246097 122914 246097 122915 246097 122918 246098 122916 246098 122920 246098 119545 246099 119557 246099 122917 246099 122922 246100 120720 246100 119545 246100 119463 246101 122918 246101 122919 246101 122919 246102 122918 246102 122920 246102 122919 246103 122920 246103 122947 246103 122947 246104 122920 246104 122898 246104 122947 246105 122898 246105 122921 246105 119545 246106 122917 246106 122922 246106 122922 246107 122917 246107 122937 246107 122922 246108 122937 246108 122898 246108 122898 246109 122937 246109 122936 246109 122898 246110 122936 246110 122921 246110 122928 246111 122923 246111 122903 246111 120965 246112 122923 246112 120967 246112 120967 246113 122923 246113 122928 246113 120967 246114 122928 246114 122930 246114 122951 246115 122924 246115 122952 246115 122952 246116 122924 246116 122929 246116 122952 246117 122929 246117 122925 246117 122925 246118 122929 246118 122926 246118 122925 246119 122926 246119 119411 246119 119411 246120 122926 246120 122927 246120 119423 246121 122927 246121 122904 246121 122904 246122 122927 246122 122926 246122 122904 246123 122926 246123 122903 246123 122903 246124 122926 246124 122929 246124 122903 246125 122929 246125 122928 246125 122928 246126 122929 246126 122924 246126 122928 246127 122924 246127 122930 246127 122930 246128 122924 246128 122951 246128 122930 246129 122951 246129 119543 246129 122943 246130 122931 246130 122932 246130 122933 246131 119547 246131 122934 246131 122960 246132 122959 246132 122945 246132 122945 246133 122959 246133 122944 246133 119463 246134 122919 246134 122946 246134 122948 246135 122949 246135 122933 246135 119557 246136 119555 246136 122939 246136 122947 246137 122921 246137 122935 246137 122935 246138 122921 246138 122936 246138 122935 246139 122936 246139 122941 246139 122941 246140 122936 246140 122937 246140 122941 246141 122937 246141 122939 246141 122939 246142 122937 246142 122917 246142 122939 246143 122917 246143 119557 246143 119555 246144 119553 246144 122939 246144 122939 246145 119553 246145 122938 246145 122939 246146 122938 246146 119551 246146 119551 246147 119550 246147 122939 246147 122939 246148 119550 246148 122940 246148 122939 246149 122940 246149 122941 246149 119461 246150 122942 246150 122955 246150 122955 246151 122942 246151 122931 246151 122955 246152 122931 246152 122944 246152 122944 246153 122931 246153 122943 246153 122944 246154 122943 246154 122945 246154 122934 246155 122960 246155 122933 246155 122933 246156 122960 246156 122945 246156 122933 246157 122945 246157 122948 246157 122948 246158 122945 246158 122943 246158 122948 246159 122943 246159 122946 246159 122946 246160 122943 246160 122932 246160 122946 246161 122932 246161 119463 246161 122919 246162 122947 246162 122946 246162 122946 246163 122947 246163 122935 246163 122946 246164 122935 246164 122948 246164 122948 246165 122935 246165 122941 246165 122948 246166 122941 246166 122949 246166 122949 246167 122941 246167 122940 246167 122949 246168 122940 246168 122933 246168 122933 246169 122940 246169 119549 246169 122933 246170 119549 246170 119547 246170 119544 246171 119543 246171 122951 246171 122961 246172 119544 246172 122950 246172 122950 246173 119544 246173 122951 246173 122950 246174 122951 246174 122962 246174 122962 246175 122951 246175 122952 246175 122962 246176 122952 246176 122978 246176 122978 246177 122952 246177 122925 246177 122978 246178 122925 246178 122953 246178 122953 246179 122925 246179 119411 246179 119563 246180 122983 246180 122954 246180 122956 246181 119418 246181 119461 246181 119461 246182 122955 246182 122956 246182 122956 246183 122955 246183 122944 246183 122956 246184 122944 246184 122957 246184 122960 246185 122934 246185 122958 246185 122944 246186 122959 246186 122957 246186 122957 246187 122959 246187 122960 246187 122957 246188 122960 246188 122954 246188 122954 246189 122960 246189 122958 246189 122954 246190 122958 246190 119563 246190 122967 246191 119558 246191 120956 246191 122974 246192 122961 246192 122976 246192 122976 246193 122961 246193 122950 246193 122976 246194 122950 246194 122977 246194 122977 246195 122950 246195 122962 246195 122977 246196 122962 246196 122978 246196 122966 246197 122968 246197 120955 246197 119415 246198 119414 246198 122970 246198 122970 246199 119414 246199 122963 246199 122970 246200 122963 246200 122971 246200 122972 246201 122964 246201 122965 246201 122965 246202 122964 246202 122981 246202 122965 246203 122981 246203 122966 246203 122966 246204 122981 246204 122967 246204 122966 246205 122967 246205 122968 246205 122968 246206 122967 246206 120956 246206 122968 246207 120956 246207 120955 246207 120955 246208 122975 246208 122966 246208 122966 246209 122975 246209 122969 246209 122966 246210 122969 246210 122965 246210 122965 246211 122969 246211 122970 246211 122965 246212 122970 246212 122972 246212 122972 246213 122970 246213 122971 246213 122972 246214 122971 246214 122973 246214 120955 246215 122974 246215 122975 246215 122975 246216 122974 246216 122976 246216 122975 246217 122976 246217 122969 246217 122969 246218 122976 246218 122977 246218 122969 246219 122977 246219 122970 246219 122970 246220 122977 246220 122978 246220 122970 246221 122978 246221 119415 246221 119415 246222 122978 246222 122953 246222 119419 246223 119418 246223 122956 246223 119420 246224 122982 246224 122979 246224 122979 246225 122982 246225 122972 246225 122979 246226 122972 246226 122973 246226 119560 246227 119558 246227 122980 246227 122980 246228 119558 246228 122967 246228 122980 246229 122967 246229 122984 246229 122984 246230 122967 246230 122981 246230 122984 246231 122981 246231 122982 246231 122982 246232 122981 246232 122964 246232 122982 246233 122964 246233 122972 246233 122983 246234 119560 246234 122954 246234 122954 246235 119560 246235 122980 246235 122954 246236 122980 246236 122957 246236 122957 246237 122980 246237 122984 246237 122957 246238 122984 246238 122956 246238 122956 246239 122984 246239 122982 246239 122956 246240 122982 246240 119419 246240 119419 246241 122982 246241 119420 246241 120935 246242 122985 246242 123016 246242 123014 246243 122986 246243 123046 246243 123022 246244 123024 246244 123013 246244 123039 246245 122987 246245 123018 246245 123018 246246 122987 246246 122998 246246 122988 246247 122989 246247 123019 246247 123019 246248 122989 246248 122990 246248 122990 246249 123015 246249 123019 246249 123019 246250 123015 246250 120934 246250 123019 246251 120934 246251 120931 246251 119584 246252 123039 246252 122991 246252 122991 246253 123039 246253 123018 246253 122991 246254 123018 246254 120931 246254 120935 246255 123016 246255 122992 246255 123021 246256 123022 246256 122993 246256 122993 246257 123022 246257 123013 246257 122993 246258 123013 246258 122994 246258 122994 246259 123013 246259 123012 246259 122994 246260 123012 246260 123016 246260 123016 246261 123012 246261 123009 246261 123016 246262 123009 246262 122992 246262 123044 246263 122995 246263 122996 246263 122996 246264 122995 246264 122997 246264 122996 246265 122997 246265 119435 246265 119435 246266 122997 246266 123006 246266 122987 246267 123040 246267 122998 246267 122998 246268 123040 246268 123002 246268 122998 246269 123002 246269 122999 246269 122999 246270 123002 246270 123000 246270 122999 246271 123000 246271 123020 246271 123020 246272 123000 246272 123005 246272 123020 246273 123005 246273 123023 246273 123023 246274 123005 246274 123007 246274 123023 246275 123007 246275 123001 246275 123040 246276 123025 246276 123002 246276 123002 246277 123025 246277 123003 246277 123002 246278 123003 246278 123000 246278 123000 246279 123003 246279 123004 246279 123000 246280 123004 246280 123005 246280 123005 246281 123004 246281 123006 246281 123005 246282 123006 246282 123007 246282 123007 246283 123006 246283 122997 246283 123007 246284 122997 246284 123001 246284 123001 246285 122997 246285 122995 246285 123010 246286 123008 246286 123009 246286 123009 246287 123008 246287 120936 246287 123009 246288 120936 246288 122992 246288 119581 246289 123010 246289 123011 246289 123011 246290 123010 246290 123009 246290 123011 246291 123009 246291 123048 246291 123048 246292 123009 246292 123012 246292 123048 246293 123012 246293 123046 246293 123046 246294 123012 246294 123013 246294 123046 246295 123013 246295 123014 246295 123014 246296 123013 246296 123024 246296 122989 246297 123021 246297 122990 246297 122990 246298 123021 246298 122993 246298 122990 246299 122993 246299 123015 246299 123015 246300 122993 246300 122994 246300 123015 246301 122994 246301 120934 246301 120934 246302 122994 246302 123016 246302 120934 246303 123016 246303 123017 246303 123017 246304 123016 246304 122985 246304 120931 246305 123018 246305 123019 246305 123019 246306 123018 246306 122998 246306 123019 246307 122998 246307 122988 246307 122988 246308 122998 246308 122999 246308 122988 246309 122999 246309 122989 246309 122989 246310 122999 246310 123020 246310 122989 246311 123020 246311 123021 246311 123021 246312 123020 246312 123023 246312 123021 246313 123023 246313 123022 246313 123022 246314 123023 246314 123001 246314 123022 246315 123001 246315 123024 246315 123024 246316 123001 246316 122995 246316 123024 246317 122995 246317 123014 246317 123014 246318 122995 246318 123044 246318 123014 246319 123044 246319 122986 246319 123041 246320 123025 246320 123040 246320 119445 246321 119442 246321 123026 246321 123026 246322 119442 246322 123027 246322 123026 246323 123027 246323 123053 246323 123053 246324 123027 246324 123032 246324 123053 246325 123032 246325 123058 246325 123058 246326 123032 246326 123030 246326 123058 246327 123030 246327 123028 246327 123028 246328 123030 246328 123029 246328 123028 246329 123029 246329 119586 246329 123035 246330 123029 246330 123037 246330 123037 246331 123029 246331 123030 246331 123037 246332 123030 246332 123031 246332 123031 246333 123030 246333 123032 246333 123031 246334 123032 246334 123033 246334 123033 246335 123032 246335 123027 246335 123033 246336 123027 246336 123034 246336 123034 246337 123027 246337 119442 246337 119588 246338 123035 246338 123036 246338 123036 246339 123035 246339 123037 246339 123036 246340 123037 246340 123038 246340 123038 246341 123037 246341 123031 246341 123038 246342 123031 246342 123042 246342 123042 246343 123031 246343 123033 246343 123042 246344 123033 246344 119440 246344 119440 246345 123033 246345 123034 246345 119584 246346 119588 246346 123039 246346 123039 246347 119588 246347 123036 246347 123039 246348 123036 246348 122987 246348 122987 246349 123036 246349 123038 246349 122987 246350 123038 246350 123040 246350 123040 246351 123038 246351 123042 246351 123040 246352 123042 246352 123041 246352 123041 246353 123042 246353 119440 246353 123043 246354 119434 246354 123061 246354 119435 246355 123043 246355 122996 246355 122996 246356 123043 246356 123061 246356 122996 246357 123061 246357 123044 246357 123044 246358 123061 246358 123045 246358 123044 246359 123045 246359 122986 246359 122986 246360 123045 246360 123047 246360 122986 246361 123047 246361 123046 246361 123046 246362 123047 246362 123073 246362 123046 246363 123073 246363 123048 246363 123048 246364 123073 246364 123093 246364 123048 246365 123093 246365 123011 246365 123011 246366 123093 246366 119582 246366 123011 246367 119582 246367 119581 246367 123050 246368 119568 246368 123094 246368 123059 246369 120708 246369 123057 246369 123057 246370 120708 246370 123051 246370 123057 246371 123051 246371 123056 246371 123056 246372 123051 246372 123049 246372 123056 246373 123049 246373 123054 246373 123096 246374 119447 246374 123098 246374 123098 246375 119447 246375 123054 246375 123098 246376 123054 246376 123094 246376 123094 246377 123054 246377 123049 246377 123094 246378 123049 246378 123050 246378 123050 246379 123049 246379 120702 246379 120708 246380 120707 246380 123051 246380 123051 246381 120707 246381 120705 246381 123051 246382 120705 246382 123049 246382 123049 246383 120705 246383 120704 246383 123049 246384 120704 246384 120702 246384 123055 246385 123026 246385 123052 246385 123052 246386 123026 246386 123053 246386 123052 246387 123053 246387 123058 246387 119439 246388 119446 246388 123055 246388 123055 246389 119446 246389 119445 246389 123055 246390 119445 246390 123026 246390 119447 246391 119439 246391 123054 246391 123054 246392 119439 246392 123055 246392 123054 246393 123055 246393 123056 246393 123056 246394 123055 246394 123052 246394 123056 246395 123052 246395 123057 246395 123057 246396 123052 246396 123058 246396 123057 246397 123058 246397 123059 246397 123059 246398 123058 246398 123028 246398 123059 246399 123028 246399 120708 246399 120708 246400 123028 246400 119586 246400 123060 246401 123047 246401 123045 246401 123045 246402 123061 246402 123082 246402 120919 246403 120918 246403 123081 246403 123062 246404 123116 246404 123118 246404 123078 246405 123077 246405 123068 246405 123063 246406 123088 246406 123087 246406 123047 246407 123060 246407 123073 246407 123087 246408 123079 246408 123063 246408 123063 246409 123079 246409 123065 246409 123063 246410 123065 246410 123064 246410 123064 246411 123065 246411 120916 246411 123064 246412 120916 246412 120914 246412 123088 246413 123063 246413 123090 246413 123090 246414 123063 246414 123064 246414 123090 246415 123064 246415 123092 246415 123092 246416 123064 246416 120914 246416 123092 246417 120914 246417 120912 246417 120920 246418 120919 246418 123066 246418 123066 246419 120919 246419 123081 246419 123066 246420 123081 246420 123067 246420 123067 246421 123081 246421 123080 246421 123067 246422 123080 246422 123068 246422 123100 246423 123066 246423 123069 246423 123069 246424 123066 246424 123067 246424 123069 246425 123067 246425 123118 246425 123118 246426 123067 246426 123068 246426 123118 246427 123068 246427 123062 246427 123062 246428 123068 246428 123077 246428 123071 246429 123076 246429 123070 246429 123071 246430 123070 246430 123084 246430 123076 246431 123071 246431 123072 246431 123072 246432 123071 246432 119457 246432 123072 246433 119457 246433 123115 246433 123085 246434 123086 246434 123074 246434 123093 246435 123073 246435 123091 246435 123091 246436 123073 246436 123060 246436 123091 246437 123060 246437 123089 246437 123089 246438 123060 246438 123045 246438 123089 246439 123045 246439 123074 246439 123074 246440 123045 246440 123082 246440 123074 246441 123082 246441 123085 246441 123061 246442 119434 246442 123083 246442 123100 246443 119576 246443 123066 246443 123066 246444 119576 246444 123075 246444 123066 246445 123075 246445 120920 246445 123115 246446 123116 246446 123072 246446 123072 246447 123116 246447 123062 246447 123072 246448 123062 246448 123076 246448 123076 246449 123062 246449 123077 246449 123076 246450 123077 246450 123070 246450 123070 246451 123077 246451 123078 246451 123070 246452 123078 246452 123087 246452 123087 246453 123078 246453 123068 246453 123087 246454 123068 246454 123079 246454 123079 246455 123068 246455 123080 246455 123079 246456 123080 246456 123065 246456 123065 246457 123080 246457 123081 246457 123065 246458 123081 246458 120916 246458 120916 246459 123081 246459 120918 246459 123061 246460 123083 246460 123082 246460 123082 246461 123083 246461 123084 246461 123082 246462 123084 246462 123085 246462 123085 246463 123084 246463 123070 246463 123085 246464 123070 246464 123086 246464 123086 246465 123070 246465 123087 246465 123086 246466 123087 246466 123074 246466 123074 246467 123087 246467 123088 246467 123074 246468 123088 246468 123089 246468 123089 246469 123088 246469 123090 246469 123089 246470 123090 246470 123091 246470 123091 246471 123090 246471 123092 246471 123091 246472 123092 246472 123093 246472 123093 246473 123092 246473 120912 246473 123093 246474 120912 246474 119582 246474 123094 246475 119568 246475 123095 246475 123094 246476 123095 246476 123098 246476 123095 246477 119575 246477 123128 246477 123096 246478 123098 246478 123097 246478 123097 246479 123098 246479 123095 246479 123097 246480 123095 246480 123099 246480 123099 246481 123095 246481 123128 246481 119456 246482 119454 246482 123107 246482 119577 246483 119576 246483 123100 246483 119577 246484 123100 246484 123112 246484 123101 246485 123102 246485 123110 246485 119452 246486 119451 246486 123108 246486 123108 246487 119451 246487 123104 246487 123108 246488 123104 246488 123103 246488 123103 246489 123104 246489 123105 246489 123103 246490 123105 246490 123106 246490 123106 246491 123105 246491 123111 246491 119454 246492 119452 246492 123107 246492 123107 246493 119452 246493 123108 246493 123107 246494 123108 246494 123109 246494 123109 246495 123108 246495 123103 246495 123109 246496 123103 246496 123110 246496 123110 246497 123103 246497 123106 246497 123110 246498 123106 246498 123101 246498 123101 246499 123106 246499 123111 246499 123101 246500 123111 246500 119570 246500 123102 246501 119577 246501 123110 246501 123110 246502 119577 246502 123112 246502 123110 246503 123112 246503 123109 246503 123109 246504 123112 246504 123117 246504 123109 246505 123117 246505 123107 246505 123107 246506 123117 246506 123113 246506 123107 246507 123113 246507 119456 246507 119456 246508 123113 246508 123114 246508 119457 246509 123114 246509 123115 246509 123115 246510 123114 246510 123113 246510 123115 246511 123113 246511 123116 246511 123116 246512 123113 246512 123117 246512 123116 246513 123117 246513 123118 246513 123118 246514 123117 246514 123112 246514 123118 246515 123112 246515 123069 246515 123069 246516 123112 246516 123100 246516 123104 246517 119451 246517 123119 246517 123119 246518 119451 246518 123120 246518 123119 246519 123120 246519 123139 246519 123139 246520 123120 246520 119448 246520 123125 246521 123121 246521 123122 246521 123122 246522 123121 246522 119571 246522 119574 246523 123123 246523 123125 246523 123125 246524 123123 246524 123124 246524 123125 246525 123124 246525 123121 246525 123125 246526 123126 246526 119574 246526 119574 246527 123126 246527 123141 246527 119574 246528 123141 246528 119569 246528 119569 246529 123141 246529 123127 246529 123128 246530 119575 246530 123132 246530 123127 246531 123129 246531 123131 246531 123131 246532 123129 246532 123130 246532 123131 246533 123130 246533 123132 246533 123132 246534 123130 246534 123099 246534 123132 246535 123099 246535 123128 246535 123133 246536 123135 246536 123134 246536 123134 246537 123135 246537 123140 246537 123134 246538 123140 246538 123142 246538 123097 246539 123099 246539 123136 246539 123136 246540 123099 246540 123130 246540 123136 246541 123130 246541 123137 246541 123137 246542 123130 246542 123129 246542 123137 246543 123129 246543 123138 246543 119448 246544 123137 246544 123139 246544 123139 246545 123137 246545 123138 246545 123139 246546 123138 246546 123119 246546 123119 246547 123138 246547 123142 246547 123119 246548 123142 246548 123104 246548 123104 246549 123142 246549 123140 246549 123104 246550 123140 246550 123105 246550 123105 246551 123140 246551 123135 246551 123105 246552 123135 246552 123111 246552 123111 246553 123135 246553 123133 246553 123111 246554 123133 246554 119570 246554 123127 246555 123141 246555 123129 246555 123129 246556 123141 246556 123126 246556 123129 246557 123126 246557 123138 246557 123138 246558 123126 246558 123125 246558 123138 246559 123125 246559 123142 246559 123142 246560 123125 246560 123122 246560 123142 246561 123122 246561 123134 246561 123134 246562 123122 246562 119571 246562 123134 246563 119571 246563 123133 246563 123151 246564 123143 246564 123154 246564 123159 246565 123161 246565 123153 246565 119437 246566 123184 246566 123148 246566 119409 246567 119421 246567 123144 246567 119409 246568 123144 246568 123162 246568 123162 246569 123144 246569 123147 246569 123162 246570 123147 246570 123146 246570 123184 246571 123157 246571 123148 246571 123148 246572 123157 246572 123156 246572 123148 246573 123156 246573 123145 246573 123161 246574 123146 246574 123153 246574 123153 246575 123146 246575 123147 246575 123153 246576 123147 246576 123145 246576 123145 246577 123147 246577 123144 246577 123145 246578 123144 246578 123148 246578 123148 246579 123144 246579 119421 246579 123148 246580 119421 246580 119437 246580 123149 246581 123151 246581 123150 246581 123150 246582 123151 246582 123154 246582 123150 246583 123154 246583 120943 246583 120943 246584 123154 246584 123152 246584 120943 246585 123152 246585 120945 246585 120945 246586 123152 246586 123155 246586 120945 246587 123155 246587 120946 246587 120946 246588 123155 246588 123183 246588 123143 246589 123159 246589 123154 246589 123154 246590 123159 246590 123153 246590 123154 246591 123153 246591 123152 246591 123152 246592 123153 246592 123145 246592 123152 246593 123145 246593 123155 246593 123155 246594 123145 246594 123156 246594 123155 246595 123156 246595 123183 246595 123183 246596 123156 246596 123157 246596 120938 246597 123169 246597 123158 246597 120938 246598 123158 246598 120939 246598 120939 246599 123158 246599 123180 246599 120939 246600 123180 246600 120940 246600 123143 246601 123163 246601 123159 246601 123159 246602 123163 246602 123164 246602 123159 246603 123164 246603 123161 246603 123161 246604 123164 246604 123160 246604 123161 246605 123160 246605 123146 246605 123160 246606 123166 246606 123146 246606 123146 246607 123166 246607 123167 246607 123146 246608 123167 246608 123162 246608 123162 246609 123167 246609 119395 246609 123162 246610 119395 246610 119409 246610 123163 246611 123179 246611 123164 246611 123164 246612 123179 246612 123165 246612 123164 246613 123165 246613 123160 246613 123160 246614 123165 246614 123178 246614 123160 246615 123178 246615 123166 246615 123166 246616 123178 246616 123177 246616 123166 246617 123177 246617 123167 246617 123167 246618 123177 246618 123168 246618 123167 246619 123168 246619 119395 246619 119395 246620 123168 246620 123191 246620 120938 246621 120937 246621 123169 246621 123169 246622 120937 246622 123195 246622 123169 246623 123195 246623 123170 246623 123170 246624 123195 246624 123171 246624 123170 246625 123171 246625 123172 246625 123172 246626 123171 246626 123173 246626 123172 246627 123173 246627 123174 246627 123174 246628 123173 246628 123176 246628 123174 246629 123176 246629 123175 246629 123175 246630 123176 246630 123193 246630 123193 246631 123191 246631 123175 246631 123175 246632 123191 246632 123168 246632 123175 246633 123168 246633 123174 246633 123174 246634 123168 246634 123177 246634 123174 246635 123177 246635 123172 246635 123172 246636 123177 246636 123178 246636 123172 246637 123178 246637 123170 246637 123170 246638 123178 246638 123165 246638 123170 246639 123165 246639 123169 246639 123169 246640 123165 246640 123179 246640 123169 246641 123179 246641 123158 246641 123158 246642 123179 246642 123163 246642 123158 246643 123163 246643 123180 246643 123180 246644 123163 246644 123143 246644 123180 246645 123143 246645 120940 246645 120940 246646 123143 246646 123151 246646 120940 246647 123151 246647 123149 246647 119591 246648 123181 246648 123186 246648 123181 246649 120946 246649 123186 246649 123186 246650 120946 246650 123183 246650 123186 246651 123183 246651 123182 246651 123182 246652 123183 246652 123157 246652 123182 246653 123157 246653 123185 246653 123185 246654 123157 246654 123184 246654 123185 246655 123184 246655 119438 246655 119438 246656 123184 246656 119437 246656 119438 246657 119441 246657 123185 246657 123185 246658 119441 246658 123190 246658 123185 246659 123190 246659 123182 246659 123182 246660 123190 246660 123189 246660 123182 246661 123189 246661 123186 246661 123186 246662 123189 246662 123188 246662 123186 246663 123188 246663 119591 246663 119591 246664 123188 246664 123187 246664 119592 246665 123187 246665 123207 246665 123207 246666 123187 246666 123188 246666 123207 246667 123188 246667 123205 246667 123205 246668 123188 246668 123189 246668 123205 246669 123189 246669 123201 246669 123201 246670 123189 246670 123190 246670 123201 246671 123190 246671 119443 246671 119443 246672 123190 246672 119441 246672 123196 246673 120953 246673 123239 246673 119406 246674 123191 246674 123219 246674 123219 246675 123191 246675 123193 246675 123219 246676 123193 246676 123192 246676 123192 246677 123193 246677 123176 246677 123192 246678 123176 246678 123194 246678 123194 246679 123176 246679 123173 246679 123194 246680 123173 246680 123214 246680 123214 246681 123173 246681 123171 246681 123214 246682 123171 246682 123237 246682 123237 246683 123171 246683 123195 246683 123237 246684 123195 246684 123239 246684 123239 246685 123195 246685 120937 246685 123239 246686 120937 246686 123196 246686 123204 246687 123260 246687 123197 246687 119444 246688 123264 246688 123263 246688 123197 246689 123199 246689 123198 246689 123198 246690 123199 246690 123206 246690 123263 246691 123200 246691 119444 246691 119444 246692 123200 246692 123201 246692 119444 246693 123201 246693 119443 246693 123197 246694 123260 246694 123199 246694 123199 246695 123260 246695 123255 246695 123199 246696 123255 246696 123254 246696 123254 246697 123202 246697 123199 246697 123199 246698 123202 246698 123203 246698 123199 246699 123203 246699 123206 246699 123206 246700 123203 246700 123208 246700 123263 246701 123204 246701 123200 246701 123200 246702 123204 246702 123197 246702 123200 246703 123197 246703 123201 246703 123201 246704 123197 246704 123198 246704 123201 246705 123198 246705 123205 246705 123205 246706 123198 246706 123206 246706 123205 246707 123206 246707 123207 246707 123207 246708 123206 246708 123208 246708 123207 246709 123208 246709 119592 246709 123229 246710 123209 246710 123230 246710 120947 246711 123210 246711 123242 246711 123242 246712 123210 246712 123211 246712 123210 246713 123245 246713 123211 246713 123211 246714 123245 246714 123212 246714 123211 246715 123212 246715 123247 246715 120947 246716 123229 246716 123231 246716 123213 246717 123194 246717 123214 246717 123248 246718 123213 246718 123238 246718 123215 246719 123216 246719 123243 246719 123243 246720 123216 246720 123233 246720 123243 246721 123233 246721 123217 246721 123217 246722 123233 246722 123234 246722 123234 246723 123236 246723 123217 246723 123217 246724 123236 246724 120950 246724 123217 246725 120950 246725 120948 246725 123192 246726 123218 246726 123219 246726 123219 246727 123218 246727 123220 246727 123219 246728 123220 246728 119406 246728 119406 246729 123220 246729 123225 246729 123226 246730 123224 246730 123223 246730 123226 246731 123221 246731 123227 246731 123227 246732 123221 246732 123222 246732 123228 246733 119408 246733 119407 246733 123218 246734 123223 246734 123220 246734 123220 246735 123223 246735 123224 246735 123220 246736 123224 246736 123225 246736 123225 246737 123224 246737 123226 246737 123225 246738 123226 246738 119407 246738 119407 246739 123226 246739 123227 246739 119407 246740 123227 246740 123228 246740 123228 246741 123227 246741 123222 246741 123228 246742 123222 246742 123246 246742 123229 246743 123230 246743 123231 246743 123231 246744 123230 246744 123277 246744 123231 246745 123277 246745 123246 246745 123246 246746 123277 246746 123278 246746 123246 246747 123278 246747 123228 246747 123228 246748 123278 246748 123279 246748 123228 246749 123279 246749 119408 246749 123248 246750 123238 246750 123216 246750 123216 246751 123238 246751 123232 246751 123216 246752 123232 246752 123233 246752 123233 246753 123232 246753 123240 246753 123233 246754 123240 246754 123234 246754 123234 246755 123240 246755 123235 246755 123234 246756 123235 246756 123236 246756 123213 246757 123214 246757 123238 246757 123238 246758 123214 246758 123237 246758 123238 246759 123237 246759 123232 246759 123232 246760 123237 246760 123239 246760 123232 246761 123239 246761 123240 246761 123240 246762 123239 246762 120953 246762 123240 246763 120953 246763 123235 246763 120948 246764 123241 246764 123217 246764 123217 246765 123241 246765 123242 246765 123217 246766 123242 246766 123243 246766 123243 246767 123242 246767 123211 246767 123243 246768 123211 246768 123215 246768 123215 246769 123211 246769 123247 246769 123215 246770 123247 246770 123216 246770 123216 246771 123247 246771 123244 246771 123216 246772 123244 246772 123248 246772 120947 246773 123231 246773 123210 246773 123210 246774 123231 246774 123246 246774 123210 246775 123246 246775 123245 246775 123245 246776 123246 246776 123222 246776 123245 246777 123222 246777 123212 246777 123212 246778 123222 246778 123221 246778 123212 246779 123221 246779 123247 246779 123247 246780 123221 246780 123226 246780 123247 246781 123226 246781 123244 246781 123244 246782 123226 246782 123223 246782 123244 246783 123223 246783 123248 246783 123248 246784 123223 246784 123218 246784 123248 246785 123218 246785 123213 246785 123213 246786 123218 246786 123192 246786 123213 246787 123192 246787 123194 246787 123256 246788 123255 246788 123260 246788 119397 246789 123252 246789 123249 246789 123249 246790 123252 246790 123250 246790 123249 246791 123250 246791 119398 246791 119398 246792 123250 246792 123261 246792 120713 246793 123258 246793 123250 246793 123250 246794 123258 246794 123259 246794 123250 246795 123259 246795 123261 246795 120713 246796 123250 246796 123251 246796 123251 246797 123250 246797 123252 246797 123251 246798 123252 246798 123253 246798 123254 246799 123255 246799 120712 246799 120712 246800 123255 246800 123256 246800 120712 246801 123256 246801 123257 246801 120713 246802 123257 246802 123258 246802 123258 246803 123257 246803 123256 246803 123258 246804 123256 246804 123259 246804 123259 246805 123256 246805 123260 246805 123259 246806 123260 246806 123261 246806 123261 246807 123260 246807 123204 246807 123261 246808 123204 246808 119398 246808 119398 246809 123204 246809 123263 246809 119398 246810 123263 246810 123262 246810 123262 246811 123263 246811 123264 246811 123267 246812 123265 246812 123266 246812 123267 246813 123266 246813 123286 246813 123286 246814 123266 246814 123269 246814 123286 246815 123269 246815 123268 246815 123268 246816 123269 246816 123270 246816 123268 246817 123270 246817 123283 246817 123283 246818 123270 246818 123271 246818 123271 246819 123270 246819 123272 246819 123271 246820 123272 246820 123281 246820 123265 246821 123280 246821 123266 246821 123266 246822 123280 246822 123273 246822 123266 246823 123273 246823 123269 246823 123269 246824 123273 246824 123274 246824 123269 246825 123274 246825 123270 246825 123270 246826 123274 246826 123275 246826 123270 246827 123275 246827 123272 246827 123272 246828 123275 246828 123276 246828 123209 246829 123276 246829 123230 246829 123230 246830 123276 246830 123275 246830 123230 246831 123275 246831 123277 246831 123277 246832 123275 246832 123274 246832 123277 246833 123274 246833 123278 246833 123278 246834 123274 246834 123273 246834 123278 246835 123273 246835 123279 246835 123279 246836 123273 246836 123280 246836 119397 246837 119396 246837 123252 246837 123252 246838 119396 246838 123290 246838 123252 246839 123290 246839 123253 246839 123253 246840 123290 246840 123289 246840 123281 246841 123282 246841 123271 246841 123271 246842 123282 246842 123296 246842 123271 246843 123296 246843 123283 246843 123283 246844 123296 246844 123268 246844 123293 246845 123287 246845 123295 246845 123295 246846 123287 246846 123284 246846 123295 246847 123284 246847 123297 246847 123297 246848 123284 246848 123286 246848 123267 246849 123286 246849 123285 246849 123285 246850 123286 246850 123284 246850 123285 246851 123284 246851 119400 246851 119400 246852 123284 246852 123287 246852 119400 246853 123287 246853 119401 246853 119401 246854 123287 246854 123290 246854 119401 246855 123290 246855 119396 246855 123282 246856 112222 246856 123296 246856 123296 246857 112222 246857 112225 246857 123296 246858 112225 246858 123294 246858 123294 246859 112225 246859 123288 246859 123294 246860 123288 246860 123292 246860 123289 246861 123290 246861 123291 246861 123291 246862 123290 246862 123287 246862 123291 246863 123287 246863 123292 246863 123292 246864 123287 246864 123293 246864 123292 246865 123293 246865 123294 246865 123294 246866 123293 246866 123295 246866 123294 246867 123295 246867 123296 246867 123296 246868 123295 246868 123297 246868 123296 246869 123297 246869 123268 246869 123268 246870 123297 246870 123286 246870 123314 246871 123333 246871 123313 246871 123311 246872 123359 246872 123298 246872 123348 246873 123317 246873 123309 246873 123365 246874 123366 246874 123312 246874 123372 246875 123300 246875 123299 246875 123299 246876 123300 246876 123301 246876 123299 246877 123301 246877 123302 246877 123367 246878 123302 246878 123303 246878 123366 246879 123367 246879 123310 246879 119316 246880 123304 246880 123365 246880 123300 246881 123305 246881 123301 246881 123301 246882 123305 246882 123306 246882 123301 246883 123306 246883 123307 246883 123307 246884 123306 246884 123308 246884 123307 246885 123308 246885 123316 246885 123302 246886 123301 246886 123303 246886 123303 246887 123301 246887 123307 246887 123303 246888 123307 246888 123309 246888 123309 246889 123307 246889 123316 246889 123309 246890 123316 246890 123348 246890 123367 246891 123303 246891 123310 246891 123310 246892 123303 246892 123309 246892 123310 246893 123309 246893 123298 246893 123298 246894 123309 246894 123317 246894 123298 246895 123317 246895 123311 246895 123366 246896 123310 246896 123312 246896 123312 246897 123310 246897 123298 246897 123312 246898 123298 246898 123313 246898 123313 246899 123298 246899 123359 246899 123313 246900 123359 246900 123314 246900 123365 246901 123312 246901 119316 246901 119316 246902 123312 246902 123313 246902 119316 246903 123313 246903 119314 246903 119314 246904 123313 246904 123333 246904 119314 246905 123333 246905 123331 246905 123359 246906 123311 246906 123315 246906 123316 246907 123308 246907 123349 246907 123339 246908 123338 246908 123382 246908 123358 246909 123346 246909 123332 246909 123317 246910 123348 246910 123318 246910 123319 246911 123343 246911 123355 246911 123342 246912 123319 246912 123321 246912 123319 246913 123355 246913 123321 246913 123321 246914 123355 246914 123356 246914 123321 246915 123356 246915 123322 246915 123322 246916 123356 246916 123357 246916 123322 246917 123357 246917 123324 246917 123342 246918 123321 246918 123320 246918 123320 246919 123321 246919 123322 246919 123320 246920 123322 246920 123350 246920 123350 246921 123322 246921 123324 246921 123350 246922 123324 246922 123318 246922 123357 246923 123323 246923 123324 246923 123324 246924 123323 246924 123315 246924 123324 246925 123315 246925 123318 246925 123318 246926 123315 246926 123311 246926 123318 246927 123311 246927 123317 246927 123325 246928 123326 246928 123327 246928 123327 246929 123326 246929 123337 246929 123328 246930 123347 246930 123329 246930 123330 246931 123332 246931 119309 246931 119309 246932 123332 246932 123346 246932 119309 246933 123346 246933 123325 246933 123330 246934 123331 246934 123332 246934 123332 246935 123331 246935 123333 246935 123332 246936 123333 246936 123314 246936 119311 246937 119313 246937 123334 246937 119313 246938 123335 246938 123334 246938 123334 246939 123335 246939 123336 246939 123334 246940 123336 246940 123326 246940 123326 246941 123336 246941 119310 246941 123326 246942 119310 246942 123337 246942 123384 246943 123338 246943 123353 246943 123353 246944 123338 246944 123339 246944 123353 246945 123339 246945 123354 246945 123328 246946 123329 246946 123345 246946 123345 246947 123329 246947 123354 246947 123345 246948 123354 246948 123340 246948 123340 246949 123354 246949 123339 246949 123340 246950 123339 246950 123341 246950 123341 246951 123339 246951 123382 246951 123341 246952 123382 246952 123381 246952 123342 246953 123387 246953 123319 246953 123319 246954 123387 246954 123344 246954 123319 246955 123344 246955 123343 246955 123343 246956 123344 246956 123385 246956 123343 246957 123385 246957 123384 246957 123381 246958 119311 246958 123341 246958 123341 246959 119311 246959 123334 246959 123341 246960 123334 246960 123340 246960 123340 246961 123334 246961 123326 246961 123340 246962 123326 246962 123345 246962 123345 246963 123326 246963 123325 246963 123345 246964 123325 246964 123328 246964 123328 246965 123325 246965 123346 246965 123328 246966 123346 246966 123347 246966 123347 246967 123346 246967 123358 246967 123348 246968 123316 246968 123318 246968 123318 246969 123316 246969 123349 246969 123318 246970 123349 246970 123350 246970 123350 246971 123349 246971 119213 246971 123350 246972 119213 246972 123320 246972 123320 246973 119213 246973 123351 246973 123320 246974 123351 246974 123342 246974 123342 246975 123351 246975 123352 246975 123342 246976 123352 246976 123387 246976 123384 246977 123353 246977 123343 246977 123343 246978 123353 246978 123354 246978 123343 246979 123354 246979 123355 246979 123355 246980 123354 246980 123329 246980 123355 246981 123329 246981 123356 246981 123356 246982 123329 246982 123347 246982 123356 246983 123347 246983 123357 246983 123357 246984 123347 246984 123358 246984 123357 246985 123358 246985 123323 246985 123323 246986 123358 246986 123332 246986 123323 246987 123332 246987 123315 246987 123315 246988 123332 246988 123314 246988 123315 246989 123314 246989 123359 246989 123369 246990 123361 246990 123360 246990 112242 246991 112243 246991 123389 246991 112239 246992 112241 246992 123369 246992 123369 246993 112241 246993 112242 246993 123360 246994 123361 246994 123373 246994 123373 246995 123361 246995 123371 246995 123373 246996 123371 246996 123362 246996 123376 246997 123363 246997 123375 246997 123375 246998 123363 246998 112238 246998 123304 246999 123364 246999 123365 246999 123365 247000 123364 247000 123377 247000 123365 247001 123377 247001 123366 247001 123366 247002 123377 247002 123378 247002 123366 247003 123378 247003 123367 247003 123367 247004 123378 247004 123379 247004 123367 247005 123379 247005 123302 247005 123391 247006 123368 247006 123370 247006 112242 247007 123389 247007 123369 247007 123369 247008 123389 247008 123391 247008 123369 247009 123391 247009 123361 247009 123361 247010 123391 247010 123370 247010 123361 247011 123370 247011 123371 247011 123362 247012 123372 247012 123380 247012 123362 247013 123380 247013 123373 247013 123373 247014 123380 247014 123374 247014 123373 247015 123374 247015 123360 247015 123360 247016 123374 247016 123375 247016 123360 247017 123375 247017 123369 247017 123369 247018 123375 247018 112238 247018 123369 247019 112238 247019 112239 247019 123364 247020 123363 247020 123377 247020 123377 247021 123363 247021 123376 247021 123377 247022 123376 247022 123378 247022 123378 247023 123376 247023 123375 247023 123378 247024 123375 247024 123379 247024 123379 247025 123375 247025 123374 247025 123379 247026 123374 247026 123302 247026 123302 247027 123374 247027 123380 247027 123302 247028 123380 247028 123299 247028 123299 247029 123380 247029 123372 247029 123395 247030 123381 247030 123382 247030 123395 247031 123382 247031 123396 247031 123382 247032 123338 247032 123396 247032 123396 247033 123338 247033 123384 247033 123396 247034 123384 247034 123398 247034 123398 247035 123384 247035 123383 247035 123383 247036 123384 247036 123385 247036 123383 247037 123385 247037 123386 247037 123386 247038 123385 247038 123344 247038 123386 247039 123344 247039 123394 247039 123394 247040 123344 247040 123387 247040 123394 247041 123387 247041 123392 247041 123392 247042 123387 247042 123352 247042 123392 247043 123352 247043 123388 247043 123389 247044 112243 247044 119318 247044 119214 247045 123368 247045 123390 247045 123390 247046 123368 247046 123391 247046 123390 247047 123391 247047 123404 247047 123404 247048 123391 247048 123389 247048 123404 247049 123389 247049 119319 247049 119319 247050 123389 247050 119318 247050 123392 247051 123399 247051 123393 247051 123397 247052 119325 247052 123395 247052 123392 247053 123388 247053 123399 247053 123399 247054 123388 247054 119221 247054 123399 247055 119221 247055 119259 247055 123383 247056 123386 247056 123393 247056 123393 247057 123386 247057 123394 247057 123393 247058 123394 247058 123392 247058 123395 247059 123396 247059 123397 247059 123397 247060 123396 247060 123398 247060 123397 247061 123398 247061 123402 247061 123402 247062 123398 247062 123383 247062 123402 247063 123383 247063 123401 247063 123401 247064 123383 247064 123393 247064 119259 247065 119260 247065 123399 247065 123399 247066 119260 247066 123400 247066 123399 247067 123400 247067 123393 247067 123393 247068 123400 247068 123437 247068 123393 247069 123437 247069 123401 247069 123401 247070 123437 247070 123435 247070 123401 247071 123435 247071 123402 247071 123402 247072 123435 247072 123434 247072 123402 247073 123434 247073 123397 247073 123397 247074 123434 247074 123403 247074 123397 247075 123403 247075 119325 247075 119325 247076 123403 247076 123410 247076 119325 247077 123410 247077 119324 247077 119227 247078 119214 247078 123405 247078 123405 247079 119214 247079 123390 247079 123390 247080 123404 247080 123405 247080 123405 247081 123404 247081 123406 247081 123405 247082 123406 247082 123407 247082 123408 247083 123409 247083 123446 247083 123428 247084 123422 247084 123423 247084 123433 247085 123427 247085 123410 247085 123411 247086 123415 247086 123427 247086 123427 247087 123433 247087 123411 247087 123411 247088 123433 247088 123412 247088 123411 247089 123412 247089 123413 247089 123413 247090 123412 247090 123436 247090 123413 247091 123436 247091 123438 247091 123438 247092 123414 247092 123413 247092 123413 247093 123414 247093 123440 247093 123413 247094 123440 247094 123411 247094 123411 247095 123440 247095 123416 247095 123411 247096 123416 247096 123415 247096 123415 247097 123416 247097 123417 247097 123441 247098 123418 247098 123442 247098 123442 247099 123418 247099 123431 247099 123442 247100 123431 247100 123419 247100 123419 247101 123431 247101 123432 247101 123419 247102 123432 247102 123420 247102 123420 247103 123432 247103 123425 247103 123421 247104 123409 247104 123422 247104 123422 247105 123409 247105 123408 247105 123422 247106 123408 247106 123423 247106 123423 247107 123408 247107 123424 247107 123439 247108 123437 247108 123429 247108 123429 247109 123437 247109 123400 247109 123429 247110 123400 247110 119260 247110 119323 247111 120988 247111 123425 247111 123425 247112 120988 247112 123426 247112 123425 247113 123426 247113 123420 247113 123420 247114 123426 247114 120987 247114 123420 247115 120987 247115 120986 247115 120985 247116 120984 247116 123417 247116 123417 247117 120984 247117 120980 247117 123417 247118 120980 247118 123415 247118 123415 247119 120980 247119 120982 247119 123415 247120 120982 247120 123427 247120 123427 247121 120982 247121 119324 247121 123427 247122 119324 247122 123410 247122 119260 247123 123428 247123 123429 247123 123429 247124 123428 247124 123423 247124 123429 247125 123423 247125 123439 247125 123439 247126 123423 247126 123424 247126 123439 247127 123424 247127 123441 247127 123441 247128 123424 247128 123408 247128 123441 247129 123408 247129 123418 247129 123418 247130 123408 247130 123446 247130 123418 247131 123446 247131 123431 247131 123431 247132 123446 247132 123430 247132 123431 247133 123430 247133 123432 247133 123432 247134 123430 247134 123449 247134 123432 247135 123449 247135 123425 247135 123425 247136 123449 247136 123450 247136 123425 247137 123450 247137 119323 247137 123410 247138 123403 247138 123433 247138 123433 247139 123403 247139 123434 247139 123433 247140 123434 247140 123412 247140 123412 247141 123434 247141 123435 247141 123412 247142 123435 247142 123436 247142 123436 247143 123435 247143 123437 247143 123436 247144 123437 247144 123438 247144 123438 247145 123437 247145 123439 247145 123438 247146 123439 247146 123414 247146 123414 247147 123439 247147 123441 247147 123414 247148 123441 247148 123440 247148 123440 247149 123441 247149 123442 247149 123440 247150 123442 247150 123416 247150 123416 247151 123442 247151 123419 247151 123416 247152 123419 247152 123417 247152 123417 247153 123419 247153 123420 247153 123417 247154 123420 247154 120985 247154 120985 247155 123420 247155 120986 247155 123444 247156 123443 247156 123445 247156 123445 247157 123443 247157 123458 247157 123445 247158 123458 247158 119229 247158 119229 247159 123458 247159 119223 247159 123407 247160 123444 247160 123405 247160 123405 247161 123444 247161 123445 247161 123405 247162 123445 247162 119227 247162 119227 247163 123445 247163 119229 247163 123421 247164 119232 247164 123409 247164 123409 247165 119232 247165 123454 247165 123409 247166 123454 247166 123446 247166 123446 247167 123454 247167 123447 247167 123446 247168 123447 247168 123430 247168 123430 247169 123447 247169 123448 247169 123430 247170 123448 247170 123449 247170 123449 247171 123448 247171 123450 247171 123450 247172 123448 247172 123451 247172 123450 247173 123451 247173 119323 247173 119321 247174 123451 247174 123457 247174 123457 247175 123451 247175 123448 247175 123457 247176 123448 247176 123452 247176 123452 247177 123448 247177 123447 247177 123452 247178 123447 247178 123453 247178 123453 247179 123447 247179 123454 247179 123453 247180 123454 247180 123465 247180 123465 247181 123454 247181 119232 247181 123455 247182 123452 247182 123453 247182 123460 247183 123467 247183 123469 247183 123467 247184 123460 247184 123456 247184 123452 247185 123455 247185 123457 247185 123457 247186 123455 247186 123468 247186 123457 247187 123468 247187 119321 247187 123458 247188 123443 247188 123459 247188 123458 247189 123459 247189 123460 247189 123460 247190 123459 247190 123466 247190 123460 247191 123466 247191 123456 247191 123461 247192 123462 247192 123468 247192 123468 247193 123462 247193 123463 247193 123468 247194 123463 247194 119321 247194 119223 247195 123458 247195 123464 247195 123464 247196 123458 247196 123460 247196 123464 247197 123460 247197 119224 247197 119224 247198 123460 247198 123469 247198 119224 247199 123469 247199 119226 247199 119226 247200 123469 247200 123465 247200 123459 247201 120994 247201 123466 247201 123466 247202 120994 247202 123461 247202 123466 247203 123461 247203 123456 247203 123456 247204 123461 247204 123468 247204 123456 247205 123468 247205 123467 247205 123467 247206 123468 247206 123455 247206 123467 247207 123455 247207 123469 247207 123469 247208 123455 247208 123453 247208 123469 247209 123453 247209 123465 247209 123470 247210 119338 247210 123486 247210 123470 247211 123486 247211 123554 247211 123486 247212 123471 247212 123554 247212 123554 247213 123471 247213 123472 247213 123554 247214 123472 247214 123555 247214 123555 247215 123472 247215 123483 247215 123555 247216 123483 247216 123473 247216 123473 247217 123483 247217 123482 247217 123473 247218 123482 247218 123474 247218 123474 247219 123482 247219 123478 247219 123474 247220 123478 247220 123476 247220 123475 247221 123476 247221 123477 247221 123477 247222 123476 247222 123478 247222 123477 247223 123478 247223 119250 247223 119250 247224 123478 247224 123479 247224 119256 247225 123479 247225 123506 247225 123506 247226 123479 247226 123478 247226 123506 247227 123478 247227 123480 247227 123480 247228 123478 247228 123482 247228 123480 247229 123482 247229 123481 247229 123481 247230 123482 247230 123483 247230 123481 247231 123483 247231 123484 247231 123484 247232 123483 247232 123472 247232 123484 247233 123472 247233 123485 247233 123485 247234 123472 247234 123471 247234 123485 247235 123471 247235 123518 247235 123518 247236 123471 247236 123486 247236 123518 247237 123486 247237 120973 247237 123487 247238 120977 247238 120969 247238 123510 247239 123567 247239 123511 247239 123527 247240 123516 247240 123488 247240 123498 247241 123497 247241 123574 247241 123574 247242 123489 247242 123498 247242 123498 247243 123489 247243 123522 247243 123498 247244 123522 247244 123490 247244 123490 247245 123522 247245 123524 247245 123490 247246 123524 247246 123491 247246 123491 247247 123524 247247 123492 247247 123491 247248 123492 247248 123501 247248 123501 247249 123492 247249 123525 247249 123501 247250 123525 247250 123493 247250 123500 247251 123517 247251 123499 247251 123499 247252 123517 247252 123494 247252 123499 247253 123494 247253 123495 247253 123495 247254 123494 247254 123497 247254 123496 247255 123520 247255 123519 247255 123497 247256 123498 247256 123495 247256 123495 247257 123498 247257 123490 247257 123495 247258 123490 247258 123499 247258 123499 247259 123490 247259 123491 247259 123499 247260 123491 247260 123500 247260 123500 247261 123491 247261 123501 247261 123500 247262 123501 247262 123502 247262 123502 247263 123501 247263 123493 247263 123502 247264 123493 247264 123488 247264 123503 247265 123513 247265 123508 247265 123508 247266 123513 247266 119256 247266 123508 247267 119256 247267 123506 247267 123507 247268 123521 247268 123504 247268 123504 247269 123521 247269 123505 247269 123504 247270 123505 247270 123520 247270 123520 247271 123496 247271 123504 247271 123504 247272 123496 247272 123526 247272 123504 247273 123526 247273 123507 247273 123506 247274 123521 247274 123508 247274 123508 247275 123521 247275 123507 247275 123508 247276 123507 247276 123503 247276 123503 247277 123507 247277 123509 247277 123573 247278 123569 247278 123523 247278 123523 247279 123569 247279 123510 247279 123523 247280 123510 247280 123509 247280 123509 247281 123510 247281 123511 247281 123509 247282 123511 247282 123503 247282 123567 247283 123565 247283 123511 247283 123511 247284 123565 247284 123512 247284 123511 247285 123512 247285 123503 247285 123503 247286 123512 247286 119257 247286 123503 247287 119257 247287 123513 247287 120977 247288 123487 247288 120976 247288 120976 247289 123487 247289 123514 247289 120976 247290 123514 247290 123515 247290 123515 247291 123514 247291 123516 247291 123515 247292 123516 247292 120974 247292 120974 247293 123516 247293 123527 247293 120974 247294 123527 247294 120973 247294 123488 247295 123516 247295 123502 247295 123502 247296 123516 247296 123514 247296 123502 247297 123514 247297 123500 247297 123500 247298 123514 247298 123487 247298 123500 247299 123487 247299 123517 247299 123517 247300 123487 247300 120969 247300 123517 247301 120969 247301 123494 247301 123494 247302 120969 247302 120970 247302 123494 247303 120970 247303 123497 247303 123497 247304 120970 247304 120972 247304 123497 247305 120972 247305 123574 247305 123518 247306 123519 247306 123485 247306 123485 247307 123519 247307 123520 247307 123485 247308 123520 247308 123484 247308 123484 247309 123520 247309 123505 247309 123484 247310 123505 247310 123481 247310 123481 247311 123505 247311 123521 247311 123481 247312 123521 247312 123480 247312 123480 247313 123521 247313 123506 247313 123489 247314 123573 247314 123522 247314 123522 247315 123573 247315 123523 247315 123522 247316 123523 247316 123524 247316 123524 247317 123523 247317 123509 247317 123524 247318 123509 247318 123492 247318 123492 247319 123509 247319 123507 247319 123492 247320 123507 247320 123525 247320 123525 247321 123507 247321 123526 247321 123525 247322 123526 247322 123493 247322 123493 247323 123526 247323 123496 247323 123493 247324 123496 247324 123488 247324 123488 247325 123496 247325 123519 247325 123488 247326 123519 247326 123527 247326 123527 247327 123519 247327 123518 247327 123527 247328 123518 247328 120973 247328 123530 247329 123529 247329 123534 247329 123528 247330 123547 247330 123551 247330 123544 247331 119340 247331 119339 247331 119340 247332 123544 247332 119344 247332 123529 247333 123476 247333 123475 247333 123475 247334 119219 247334 123529 247334 123529 247335 119219 247335 123557 247335 123529 247336 123557 247336 123534 247336 123476 247337 123529 247337 123474 247337 123474 247338 123529 247338 123530 247338 123474 247339 123530 247339 123556 247339 123531 247340 123532 247340 123559 247340 123559 247341 123532 247341 123533 247341 123559 247342 123533 247342 123558 247342 123558 247343 123533 247343 123534 247343 123558 247344 123534 247344 123535 247344 123535 247345 123534 247345 123557 247345 123556 247346 123538 247346 123553 247346 123553 247347 123538 247347 123536 247347 123553 247348 123536 247348 123537 247348 123537 247349 123536 247349 123539 247349 123537 247350 123539 247350 123540 247350 123556 247351 123530 247351 123538 247351 123538 247352 123530 247352 123534 247352 123538 247353 123534 247353 123536 247353 123536 247354 123534 247354 123533 247354 123536 247355 123533 247355 123539 247355 123539 247356 123533 247356 123545 247356 123539 247357 123545 247357 123540 247357 123540 247358 123545 247358 123546 247358 123540 247359 123546 247359 123541 247359 119336 247360 119347 247360 123542 247360 123542 247361 119347 247361 119348 247361 123561 247362 119345 247362 123531 247362 123531 247363 119345 247363 123543 247363 123531 247364 123543 247364 123532 247364 123532 247365 123543 247365 119344 247365 123532 247366 119344 247366 123533 247366 123533 247367 119344 247367 123544 247367 123533 247368 123544 247368 123545 247368 123545 247369 123544 247369 119339 247369 123545 247370 119339 247370 123546 247370 119348 247371 119337 247371 123549 247371 123549 247372 119337 247372 119346 247372 119348 247373 123549 247373 123542 247373 123542 247374 123549 247374 123528 247374 123542 247375 123528 247375 123579 247375 123547 247376 123528 247376 123548 247376 123548 247377 123528 247377 123549 247377 123548 247378 123549 247378 123550 247378 123550 247379 123549 247379 119346 247379 123550 247380 119346 247380 123560 247380 119242 247381 123579 247381 119241 247381 119241 247382 123579 247382 123528 247382 119241 247383 123528 247383 119247 247383 119247 247384 123528 247384 123551 247384 119247 247385 123551 247385 123552 247385 123541 247386 119338 247386 123540 247386 123540 247387 119338 247387 123470 247387 123540 247388 123470 247388 123537 247388 123537 247389 123470 247389 123554 247389 123537 247390 123554 247390 123553 247390 123553 247391 123554 247391 123555 247391 123553 247392 123555 247392 123556 247392 123556 247393 123555 247393 123473 247393 123556 247394 123473 247394 123474 247394 119219 247395 123552 247395 123557 247395 123557 247396 123552 247396 123551 247396 123557 247397 123551 247397 123535 247397 123535 247398 123551 247398 123547 247398 123535 247399 123547 247399 123558 247399 123558 247400 123547 247400 123548 247400 123558 247401 123548 247401 123559 247401 123559 247402 123548 247402 123550 247402 123559 247403 123550 247403 123531 247403 123531 247404 123550 247404 123560 247404 123531 247405 123560 247405 123561 247405 123561 247406 123560 247406 119346 247406 119233 247407 123562 247407 123563 247407 123563 247408 123562 247408 123566 247408 123563 247409 123566 247409 123564 247409 123564 247410 123566 247410 123568 247410 123564 247411 123568 247411 123570 247411 123571 247412 123572 247412 123618 247412 123618 247413 123572 247413 123575 247413 123618 247414 123575 247414 123619 247414 123562 247415 123565 247415 123566 247415 123566 247416 123565 247416 123567 247416 123566 247417 123567 247417 123568 247417 123568 247418 123567 247418 123510 247418 123510 247419 123569 247419 123568 247419 123568 247420 123569 247420 123572 247420 123568 247421 123572 247421 123570 247421 123570 247422 123572 247422 123571 247422 123569 247423 123573 247423 123572 247423 123572 247424 123573 247424 123489 247424 123572 247425 123489 247425 123575 247425 123575 247426 123489 247426 123574 247426 123575 247427 123574 247427 120972 247427 123576 247428 123577 247428 119220 247428 119220 247429 123577 247429 119240 247429 119332 247430 119334 247430 123577 247430 123577 247431 119334 247431 123578 247431 119242 247432 119240 247432 123579 247432 123579 247433 119240 247433 123577 247433 123579 247434 123577 247434 123542 247434 123542 247435 123577 247435 123578 247435 123542 247436 123578 247436 119336 247436 123580 247437 119236 247437 123581 247437 123582 247438 119332 247438 123584 247438 123584 247439 119332 247439 123577 247439 123584 247440 123577 247440 123581 247440 123581 247441 123577 247441 123576 247441 123581 247442 123576 247442 123580 247442 123602 247443 123596 247443 123603 247443 123587 247444 123584 247444 123581 247444 123589 247445 123614 247445 123604 247445 123582 247446 123584 247446 123583 247446 123583 247447 123584 247447 123587 247447 123583 247448 123587 247448 123585 247448 123585 247449 123587 247449 123586 247449 123586 247450 123587 247450 123588 247450 123586 247451 123588 247451 123612 247451 123589 247452 123604 247452 123616 247452 123616 247453 123604 247453 123590 247453 123616 247454 123590 247454 123617 247454 123591 247455 123592 247455 123593 247455 123593 247456 123592 247456 123595 247456 123593 247457 123595 247457 123611 247457 123591 247458 123607 247458 123592 247458 123592 247459 123607 247459 123594 247459 123592 247460 123594 247460 123595 247460 123595 247461 123594 247461 112191 247461 123597 247462 123598 247462 123605 247462 123603 247463 123596 247463 123597 247463 123597 247464 123596 247464 119233 247464 123597 247465 119233 247465 123598 247465 119236 247466 123599 247466 123581 247466 123581 247467 123599 247467 123600 247467 123581 247468 123600 247468 123587 247468 123587 247469 123600 247469 123601 247469 123587 247470 123601 247470 123588 247470 123588 247471 123601 247471 123615 247471 123588 247472 123615 247472 123612 247472 119234 247473 123602 247473 123613 247473 123613 247474 123602 247474 123603 247474 123613 247475 123603 247475 123614 247475 123614 247476 123603 247476 123597 247476 123614 247477 123597 247477 123604 247477 123604 247478 123597 247478 123605 247478 123604 247479 123605 247479 123590 247479 123619 247480 123606 247480 123591 247480 123591 247481 123606 247481 112189 247481 123591 247482 112189 247482 123607 247482 123610 247483 123609 247483 123608 247483 123608 247484 123609 247484 112192 247484 112191 247485 123610 247485 123595 247485 123595 247486 123610 247486 123608 247486 123595 247487 123608 247487 123611 247487 123611 247488 123608 247488 112192 247488 123611 247489 112192 247489 123615 247489 123615 247490 112192 247490 112195 247490 123615 247491 112195 247491 123612 247491 123618 247492 123617 247492 123571 247492 123571 247493 123617 247493 123590 247493 123571 247494 123590 247494 123570 247494 123570 247495 123590 247495 123605 247495 123570 247496 123605 247496 123564 247496 123564 247497 123605 247497 123598 247497 123564 247498 123598 247498 123563 247498 123563 247499 123598 247499 119233 247499 123599 247500 119234 247500 123600 247500 123600 247501 119234 247501 123613 247501 123600 247502 123613 247502 123601 247502 123601 247503 123613 247503 123614 247503 123601 247504 123614 247504 123615 247504 123615 247505 123614 247505 123589 247505 123615 247506 123589 247506 123611 247506 123611 247507 123589 247507 123616 247507 123611 247508 123616 247508 123593 247508 123593 247509 123616 247509 123617 247509 123593 247510 123617 247510 123591 247510 123591 247511 123617 247511 123618 247511 123591 247512 123618 247512 123619 247512 120442 247513 120424 247513 123625 247513 123621 247514 120442 247514 123762 247514 123762 247515 120442 247515 123625 247515 123762 247516 123625 247516 123620 247516 123773 247517 120446 247517 123621 247517 123621 247518 120446 247518 123622 247518 123621 247519 123622 247519 120442 247519 123719 247520 123620 247520 123625 247520 120424 247521 123623 247521 123625 247521 123625 247522 123623 247522 123624 247522 123625 247523 123624 247523 123719 247523 120146 247524 124069 247524 124068 247524 120146 247525 124068 247525 123626 247525 123626 247526 124068 247526 124095 247526 123626 247527 124095 247527 124107 247527 124069 247528 120146 247528 123627 247528 123627 247529 120146 247529 124038 247529 123627 247530 124038 247530 124037 247530 123628 247531 124298 247531 123629 247531 123629 247532 124298 247532 123630 247532 123629 247533 123630 247533 123631 247533 119704 247534 124525 247534 124611 247534 124611 247535 124525 247535 124570 247535 124611 247536 124570 247536 124563 247536 123637 247537 123638 247537 123632 247537 123637 247538 123632 247538 123633 247538 123633 247539 123632 247539 124837 247539 123633 247540 124837 247540 124827 247540 123634 247541 124779 247541 123635 247541 123635 247542 124779 247542 123636 247542 123635 247543 123636 247543 123637 247543 123637 247544 123636 247544 124763 247544 123637 247545 124763 247545 123638 247545 125113 247546 123639 247546 123640 247546 123640 247547 123639 247547 123642 247547 123640 247548 123642 247548 123641 247548 123641 247549 123642 247549 124975 247549 123642 247550 123639 247550 119228 247550 124975 247551 123642 247551 124938 247551 124938 247552 123642 247552 119228 247552 124938 247553 119228 247553 123643 247553 123643 247554 119228 247554 119230 247554 123643 247555 119230 247555 124953 247555 123644 247556 123652 247556 123679 247556 123669 247557 123668 247557 123697 247557 123645 247558 123646 247558 123647 247558 123647 247559 123646 247559 123648 247559 123623 247560 123645 247560 123649 247560 123649 247561 123645 247561 123647 247561 123649 247562 123647 247562 123671 247562 123671 247563 123647 247563 123648 247563 123671 247564 123648 247564 123650 247564 123650 247565 123648 247565 120427 247565 123650 247566 120427 247566 123651 247566 123651 247567 120427 247567 120428 247567 123700 247568 123652 247568 123653 247568 123653 247569 123652 247569 123644 247569 123653 247570 123644 247570 123678 247570 123678 247571 123654 247571 123653 247571 123653 247572 123654 247572 123655 247572 123653 247573 123655 247573 123700 247573 123664 247574 123699 247574 123665 247574 123665 247575 123699 247575 123656 247575 123665 247576 123656 247576 123654 247576 123654 247577 123656 247577 123657 247577 123654 247578 123657 247578 123655 247578 123655 247579 123657 247579 123658 247579 123655 247580 123658 247580 123700 247580 123673 247581 123674 247581 123659 247581 123659 247582 123674 247582 123677 247582 123659 247583 123677 247583 123660 247583 123661 247584 120515 247584 123662 247584 123662 247585 120515 247585 123663 247585 123662 247586 123663 247586 123675 247586 123675 247587 123663 247587 123666 247587 123675 247588 123666 247588 123676 247588 120515 247589 123664 247589 123663 247589 123663 247590 123664 247590 123665 247590 123663 247591 123665 247591 123666 247591 123666 247592 123665 247592 123654 247592 123666 247593 123654 247593 123676 247593 123676 247594 123654 247594 123678 247594 123651 247595 123682 247595 123690 247595 123667 247596 123668 247596 123692 247596 123692 247597 123668 247597 123669 247597 123692 247598 123669 247598 123670 247598 123651 247599 123690 247599 123650 247599 123650 247600 123690 247600 123670 247600 123650 247601 123670 247601 123671 247601 123671 247602 123670 247602 123669 247602 123671 247603 123669 247603 123649 247603 123649 247604 123669 247604 123697 247604 123649 247605 123697 247605 123623 247605 123677 247606 123672 247606 123691 247606 123684 247607 123661 247607 123686 247607 123686 247608 123661 247608 123662 247608 123686 247609 123662 247609 123673 247609 123673 247610 123662 247610 123675 247610 123673 247611 123675 247611 123674 247611 123674 247612 123675 247612 123676 247612 123674 247613 123676 247613 123677 247613 123677 247614 123676 247614 123678 247614 123677 247615 123678 247615 123672 247615 123672 247616 123678 247616 123644 247616 123672 247617 123644 247617 123691 247617 123691 247618 123644 247618 123679 247618 123691 247619 123679 247619 123693 247619 123718 247620 123683 247620 123717 247620 123717 247621 123683 247621 123685 247621 123717 247622 123685 247622 123680 247622 123680 247623 123685 247623 123687 247623 123680 247624 123687 247624 123681 247624 123681 247625 123687 247625 123688 247625 123681 247626 123688 247626 123682 247626 123682 247627 123688 247627 123689 247627 123682 247628 123689 247628 123690 247628 123683 247629 123684 247629 123685 247629 123685 247630 123684 247630 123686 247630 123685 247631 123686 247631 123687 247631 123687 247632 123686 247632 123673 247632 123687 247633 123673 247633 123688 247633 123688 247634 123673 247634 123659 247634 123688 247635 123659 247635 123689 247635 123689 247636 123659 247636 123660 247636 123689 247637 123660 247637 123690 247637 123690 247638 123660 247638 123677 247638 123690 247639 123677 247639 123670 247639 123670 247640 123677 247640 123691 247640 123670 247641 123691 247641 123692 247641 123692 247642 123691 247642 123693 247642 123692 247643 123693 247643 123667 247643 120512 247644 120511 247644 123694 247644 120512 247645 123694 247645 123699 247645 123698 247646 123679 247646 123723 247646 123723 247647 123679 247647 123652 247647 123723 247648 123652 247648 123695 247648 123721 247649 123696 247649 123697 247649 123697 247650 123668 247650 123721 247650 123721 247651 123668 247651 123667 247651 123721 247652 123667 247652 123698 247652 123698 247653 123667 247653 123693 247653 123698 247654 123693 247654 123679 247654 123725 247655 123657 247655 123694 247655 123694 247656 123657 247656 123656 247656 123694 247657 123656 247657 123699 247657 123696 247658 123719 247658 123697 247658 123697 247659 123719 247659 123624 247659 123697 247660 123624 247660 123623 247660 123695 247661 123652 247661 123724 247661 123724 247662 123652 247662 123700 247662 123724 247663 123700 247663 123725 247663 123725 247664 123700 247664 123658 247664 123725 247665 123658 247665 123657 247665 123711 247666 123733 247666 123713 247666 123704 247667 123705 247667 123729 247667 120508 247668 123702 247668 123701 247668 123701 247669 123702 247669 123704 247669 123701 247670 123704 247670 123703 247670 123703 247671 123704 247671 123729 247671 123702 247672 120510 247672 123704 247672 123704 247673 120510 247673 123706 247673 123704 247674 123706 247674 123705 247674 123705 247675 123706 247675 123707 247675 123705 247676 123707 247676 123708 247676 123708 247677 123707 247677 123709 247677 123708 247678 123709 247678 123712 247678 123712 247679 123709 247679 123716 247679 123712 247680 123716 247680 120430 247680 120430 247681 123716 247681 123710 247681 120430 247682 123711 247682 123712 247682 123712 247683 123711 247683 123713 247683 123712 247684 123713 247684 123708 247684 123708 247685 123713 247685 123714 247685 123708 247686 123714 247686 123705 247686 123705 247687 123714 247687 123715 247687 123705 247688 123715 247688 123729 247688 120428 247689 123710 247689 123651 247689 123651 247690 123710 247690 123716 247690 123651 247691 123716 247691 123682 247691 123682 247692 123716 247692 123709 247692 123682 247693 123709 247693 123681 247693 123681 247694 123709 247694 123707 247694 123681 247695 123707 247695 123680 247695 123680 247696 123707 247696 123706 247696 123680 247697 123706 247697 123717 247697 123717 247698 123706 247698 120510 247698 123717 247699 120510 247699 123718 247699 123720 247700 123620 247700 123719 247700 123719 247701 123696 247701 123720 247701 123720 247702 123696 247702 123721 247702 123720 247703 123721 247703 123722 247703 123722 247704 123721 247704 123698 247704 123722 247705 123698 247705 123752 247705 123752 247706 123698 247706 123723 247706 123752 247707 123723 247707 123754 247707 123754 247708 123723 247708 123695 247708 123754 247709 123695 247709 123755 247709 123755 247710 123695 247710 123724 247710 123755 247711 123724 247711 123756 247711 123756 247712 123724 247712 123725 247712 123756 247713 123725 247713 123726 247713 123726 247714 123725 247714 123727 247714 123727 247715 123725 247715 123694 247715 123727 247716 123694 247716 123758 247716 123758 247717 123694 247717 123728 247717 123728 247718 123694 247718 120511 247718 123728 247719 120511 247719 120520 247719 123742 247720 120435 247720 120437 247720 123701 247721 123703 247721 123739 247721 123739 247722 123703 247722 123729 247722 123739 247723 123729 247723 123730 247723 123730 247724 123729 247724 123732 247724 123730 247725 123732 247725 123746 247725 120538 247726 120539 247726 123735 247726 123735 247727 120539 247727 123744 247727 123731 247728 120435 247728 123750 247728 123750 247729 120435 247729 123742 247729 123750 247730 123742 247730 123748 247730 123733 247731 120434 247731 123749 247731 123729 247732 123715 247732 123732 247732 123732 247733 123715 247733 123714 247733 123732 247734 123714 247734 123749 247734 123749 247735 123714 247735 123713 247735 123749 247736 123713 247736 123733 247736 123736 247737 120535 247737 123737 247737 123761 247738 123734 247738 123743 247738 123743 247739 123734 247739 123736 247739 123743 247740 123736 247740 123735 247740 123735 247741 123736 247741 123737 247741 123735 247742 123737 247742 120538 247742 120508 247743 123701 247743 123738 247743 123738 247744 123701 247744 123739 247744 123738 247745 123739 247745 123740 247745 123740 247746 123739 247746 123730 247746 123740 247747 123730 247747 123741 247747 123741 247748 123730 247748 123746 247748 123741 247749 123746 247749 123745 247749 120437 247750 123761 247750 123742 247750 123742 247751 123761 247751 123743 247751 123742 247752 123743 247752 123748 247752 123748 247753 123743 247753 123735 247753 123748 247754 123735 247754 123747 247754 123747 247755 123735 247755 123744 247755 123747 247756 123744 247756 123745 247756 123745 247757 123746 247757 123747 247757 123747 247758 123746 247758 123732 247758 123747 247759 123732 247759 123748 247759 123748 247760 123732 247760 123749 247760 123748 247761 123749 247761 123750 247761 123750 247762 123749 247762 120434 247762 123750 247763 120434 247763 123731 247763 123751 247764 123762 247764 123620 247764 123620 247765 123720 247765 123751 247765 123751 247766 123720 247766 123722 247766 123751 247767 123722 247767 123764 247767 123764 247768 123722 247768 123752 247768 123764 247769 123752 247769 123753 247769 123753 247770 123752 247770 123754 247770 123753 247771 123754 247771 123767 247771 123767 247772 123754 247772 123768 247772 123754 247773 123755 247773 123768 247773 123768 247774 123755 247774 123756 247774 123768 247775 123756 247775 123771 247775 123756 247776 123726 247776 123771 247776 123771 247777 123726 247777 123727 247777 123771 247778 123727 247778 123757 247778 123757 247779 123727 247779 123758 247779 123757 247780 123758 247780 123728 247780 123728 247781 120520 247781 123757 247781 123757 247782 120520 247782 120521 247782 123757 247783 120521 247783 120522 247783 123759 247784 120532 247784 123736 247784 123736 247785 120532 247785 120530 247785 123736 247786 120530 247786 120535 247786 123759 247787 123736 247787 123760 247787 123760 247788 123736 247788 123734 247788 123760 247789 123734 247789 123781 247789 123781 247790 123734 247790 123761 247790 123781 247791 123761 247791 123790 247791 123790 247792 123761 247792 120437 247792 123790 247793 120437 247793 120456 247793 123621 247794 123762 247794 123775 247794 123775 247795 123762 247795 123751 247795 123775 247796 123751 247796 123763 247796 123763 247797 123751 247797 123764 247797 123763 247798 123764 247798 123765 247798 123765 247799 123764 247799 123753 247799 123765 247800 123753 247800 123766 247800 123766 247801 123753 247801 123767 247801 123766 247802 123767 247802 123769 247802 123769 247803 123767 247803 123768 247803 123769 247804 123768 247804 123770 247804 123770 247805 123768 247805 123771 247805 123770 247806 123771 247806 123780 247806 123780 247807 123771 247807 123757 247807 123780 247808 123757 247808 123772 247808 123772 247809 123757 247809 120522 247809 123773 247810 123621 247810 123774 247810 123774 247811 123621 247811 123775 247811 123774 247812 123775 247812 123776 247812 123776 247813 123775 247813 123763 247813 123776 247814 123763 247814 123806 247814 123806 247815 123763 247815 123765 247815 123806 247816 123765 247816 123777 247816 123777 247817 123765 247817 123766 247817 123777 247818 123766 247818 123778 247818 123778 247819 123766 247819 123769 247819 123778 247820 123769 247820 123809 247820 123809 247821 123769 247821 123770 247821 123809 247822 123770 247822 123779 247822 123779 247823 123770 247823 123780 247823 123779 247824 123780 247824 123812 247824 123812 247825 123780 247825 123772 247825 123781 247826 123790 247826 123789 247826 123782 247827 123783 247827 120528 247827 120528 247828 123783 247828 123795 247828 120528 247829 123795 247829 120527 247829 120527 247830 123795 247830 123794 247830 120527 247831 123794 247831 120526 247831 123791 247832 123784 247832 123792 247832 123792 247833 123784 247833 120526 247833 123792 247834 120526 247834 123785 247834 123785 247835 120526 247835 123794 247835 123787 247836 123853 247836 123802 247836 123786 247837 123853 247837 120463 247837 120463 247838 123853 247838 123787 247838 120463 247839 123787 247839 120459 247839 120459 247840 123787 247840 123800 247840 120459 247841 123800 247841 120460 247841 120460 247842 123800 247842 123788 247842 120460 247843 123788 247843 120491 247843 120491 247844 123788 247844 123798 247844 120491 247845 123798 247845 120487 247845 120487 247846 123798 247846 123789 247846 120487 247847 123789 247847 120453 247847 123790 247848 120456 247848 120455 247848 123790 247849 120455 247849 123789 247849 123789 247850 120455 247850 120440 247850 123789 247851 120440 247851 120453 247851 123782 247852 120532 247852 123783 247852 123783 247853 120532 247853 123759 247853 123783 247854 123759 247854 123760 247854 123842 247855 123791 247855 123803 247855 123803 247856 123791 247856 123792 247856 123803 247857 123792 247857 123801 247857 123801 247858 123792 247858 123785 247858 123801 247859 123785 247859 123793 247859 123793 247860 123785 247860 123794 247860 123793 247861 123794 247861 123799 247861 123799 247862 123794 247862 123795 247862 123799 247863 123795 247863 123796 247863 123796 247864 123795 247864 123783 247864 123796 247865 123783 247865 123797 247865 123797 247866 123783 247866 123760 247866 123797 247867 123760 247867 123781 247867 123781 247868 123789 247868 123797 247868 123797 247869 123789 247869 123798 247869 123797 247870 123798 247870 123796 247870 123796 247871 123798 247871 123788 247871 123796 247872 123788 247872 123799 247872 123799 247873 123788 247873 123800 247873 123799 247874 123800 247874 123793 247874 123793 247875 123800 247875 123787 247875 123793 247876 123787 247876 123801 247876 123801 247877 123787 247877 123802 247877 123801 247878 123802 247878 123803 247878 123813 247879 120476 247879 123816 247879 123824 247880 120500 247880 123823 247880 123811 247881 123804 247881 123810 247881 123816 247882 123774 247882 123805 247882 123805 247883 123774 247883 123776 247883 123805 247884 123776 247884 123807 247884 123807 247885 123776 247885 123806 247885 123807 247886 123806 247886 123820 247886 123820 247887 123806 247887 123777 247887 123820 247888 123777 247888 123821 247888 123821 247889 123777 247889 123778 247889 123821 247890 123778 247890 123808 247890 123808 247891 123778 247891 123809 247891 123808 247892 123809 247892 123810 247892 123810 247893 123809 247893 123779 247893 123810 247894 123779 247894 123811 247894 123811 247895 123779 247895 123812 247895 123816 247896 120476 247896 123774 247896 123774 247897 120476 247897 120438 247897 123774 247898 120438 247898 123773 247898 123825 247899 123813 247899 123814 247899 123814 247900 123813 247900 123816 247900 123814 247901 123816 247901 123815 247901 123815 247902 123816 247902 123805 247902 123815 247903 123805 247903 123817 247903 123817 247904 123805 247904 123807 247904 123817 247905 123807 247905 123818 247905 123818 247906 123807 247906 123820 247906 123818 247907 123820 247907 123819 247907 123819 247908 123820 247908 123821 247908 123819 247909 123821 247909 123822 247909 123822 247910 123821 247910 123808 247910 123822 247911 123808 247911 123823 247911 123823 247912 123808 247912 123810 247912 123823 247913 123810 247913 123824 247913 123824 247914 123810 247914 123804 247914 120474 247915 123825 247915 123826 247915 123826 247916 123825 247916 123814 247916 123826 247917 123814 247917 123827 247917 123827 247918 123814 247918 123815 247918 123827 247919 123815 247919 123833 247919 123833 247920 123815 247920 123817 247920 123833 247921 123817 247921 123836 247921 123836 247922 123817 247922 123818 247922 123836 247923 123818 247923 123828 247923 123828 247924 123818 247924 123819 247924 123828 247925 123819 247925 123829 247925 123829 247926 123819 247926 123822 247926 123829 247927 123822 247927 123830 247927 123830 247928 123822 247928 123823 247928 123830 247929 123823 247929 123838 247929 123838 247930 123823 247930 120500 247930 123831 247931 120474 247931 123832 247931 123832 247932 120474 247932 123826 247932 123832 247933 123826 247933 123904 247933 123904 247934 123826 247934 123827 247934 123904 247935 123827 247935 123834 247935 123834 247936 123827 247936 123833 247936 123834 247937 123833 247937 123835 247937 123835 247938 123833 247938 123836 247938 123835 247939 123836 247939 123909 247939 123909 247940 123836 247940 123828 247940 123909 247941 123828 247941 123911 247941 123911 247942 123828 247942 123829 247942 123911 247943 123829 247943 123837 247943 123837 247944 123829 247944 123830 247944 123837 247945 123830 247945 120496 247945 120496 247946 123830 247946 123838 247946 123839 247947 123854 247947 123872 247947 123886 247948 114139 247948 123916 247948 123840 247949 123841 247949 123856 247949 123895 247950 123893 247950 123842 247950 123846 247951 123843 247951 123882 247951 123882 247952 123843 247952 123844 247952 123882 247953 123844 247953 123845 247953 123845 247954 123844 247954 123884 247954 123846 247955 123882 247955 112204 247955 112204 247956 123882 247956 123860 247956 112204 247957 123860 247957 112200 247957 112200 247958 123860 247958 123859 247958 112200 247959 123859 247959 112202 247959 112202 247960 123859 247960 123848 247960 123848 247961 123859 247961 123847 247961 123848 247962 123847 247962 112203 247962 123849 247963 123891 247963 123852 247963 123853 247964 123786 247964 123850 247964 123850 247965 123786 247965 120489 247965 123850 247966 120489 247966 120466 247966 123842 247967 123803 247967 123895 247967 123895 247968 123803 247968 123802 247968 123895 247969 123802 247969 123851 247969 123851 247970 123802 247970 123853 247970 123851 247971 123853 247971 123852 247971 123852 247972 123853 247972 123850 247972 123852 247973 123850 247973 123849 247973 123849 247974 123850 247974 120466 247974 123849 247975 120466 247975 120467 247975 123873 247976 123872 247976 123855 247976 123855 247977 123872 247977 123854 247977 123855 247978 123854 247978 123883 247978 123874 247979 123873 247979 123894 247979 123894 247980 123873 247980 123855 247980 123894 247981 123855 247981 123856 247981 123856 247982 123855 247982 123883 247982 123856 247983 123883 247983 123840 247983 123840 247984 123883 247984 123857 247984 123879 247985 123847 247985 123858 247985 123858 247986 123847 247986 123859 247986 123858 247987 123859 247987 123881 247987 123881 247988 123859 247988 123860 247988 123866 247989 123921 247989 123922 247989 123861 247990 123862 247990 123867 247990 123867 247991 123862 247991 123863 247991 123867 247992 123863 247992 123865 247992 123865 247993 123863 247993 123864 247993 123865 247994 123864 247994 123866 247994 123866 247995 123864 247995 123920 247995 123866 247996 123920 247996 123921 247996 123866 247997 123875 247997 123865 247997 123865 247998 123875 247998 123868 247998 123865 247999 123868 247999 123867 247999 123867 248000 123868 248000 123876 248000 123867 248001 123876 248001 123861 248001 123880 248002 123869 248002 123871 248002 123871 248003 123869 248003 123870 248003 123871 248004 123870 248004 123901 248004 123901 248005 123870 248005 123839 248005 123901 248006 123839 248006 123899 248006 123899 248007 123839 248007 123872 248007 123899 248008 123872 248008 123898 248008 123898 248009 123872 248009 123873 248009 123898 248010 123873 248010 123897 248010 123897 248011 123873 248011 123874 248011 123897 248012 123874 248012 123896 248012 123866 248013 123902 248013 123875 248013 123875 248014 123902 248014 123890 248014 123875 248015 123890 248015 123868 248015 123868 248016 123890 248016 123877 248016 123868 248017 123877 248017 123876 248017 123876 248018 123877 248018 123878 248018 123876 248019 123878 248019 123887 248019 123887 248020 123878 248020 123892 248020 123903 248021 123879 248021 123880 248021 123880 248022 123879 248022 123858 248022 123880 248023 123858 248023 123869 248023 123869 248024 123858 248024 123881 248024 123869 248025 123881 248025 123870 248025 123870 248026 123881 248026 123860 248026 123870 248027 123860 248027 123839 248027 123839 248028 123860 248028 123882 248028 123839 248029 123882 248029 123854 248029 123854 248030 123882 248030 123845 248030 123854 248031 123845 248031 123883 248031 123883 248032 123845 248032 123884 248032 123883 248033 123884 248033 123857 248033 120468 248034 123885 248034 123892 248034 123892 248035 123885 248035 123886 248035 123892 248036 123886 248036 123887 248036 123887 248037 123886 248037 123916 248037 123887 248038 123916 248038 123876 248038 123876 248039 123916 248039 123888 248039 123876 248040 123888 248040 123861 248040 123902 248041 123889 248041 123890 248041 123890 248042 123889 248042 123900 248042 123890 248043 123900 248043 123877 248043 123877 248044 123900 248044 123891 248044 123877 248045 123891 248045 123878 248045 123878 248046 123891 248046 123849 248046 123878 248047 123849 248047 123892 248047 123892 248048 123849 248048 120467 248048 123892 248049 120467 248049 120468 248049 123841 248050 112206 248050 123856 248050 123856 248051 112206 248051 123893 248051 123856 248052 123893 248052 123894 248052 123894 248053 123893 248053 123895 248053 123894 248054 123895 248054 123874 248054 123874 248055 123895 248055 123851 248055 123874 248056 123851 248056 123896 248056 123896 248057 123851 248057 123852 248057 123896 248058 123852 248058 123897 248058 123897 248059 123852 248059 123891 248059 123897 248060 123891 248060 123898 248060 123898 248061 123891 248061 123900 248061 123898 248062 123900 248062 123899 248062 123899 248063 123900 248063 123889 248063 123899 248064 123889 248064 123901 248064 123901 248065 123889 248065 123902 248065 123901 248066 123902 248066 123871 248066 123871 248067 123902 248067 123866 248067 123871 248068 123866 248068 123880 248068 123880 248069 123866 248069 123922 248069 123880 248070 123922 248070 123903 248070 120495 248071 112198 248071 123914 248071 123834 248072 123908 248072 123904 248072 123904 248073 123908 248073 123905 248073 123904 248074 123905 248074 123832 248074 123832 248075 123905 248075 123906 248075 123832 248076 123906 248076 123831 248076 123835 248077 123917 248077 123834 248077 123834 248078 123917 248078 123907 248078 123834 248079 123907 248079 123908 248079 123909 248080 123919 248080 123835 248080 123835 248081 123919 248081 123918 248081 123835 248082 123918 248082 123917 248082 123837 248083 123910 248083 123911 248083 123911 248084 123910 248084 123912 248084 123911 248085 123912 248085 123909 248085 123909 248086 123912 248086 123913 248086 123909 248087 123913 248087 123919 248087 120496 248088 120495 248088 123837 248088 123837 248089 120495 248089 123914 248089 123837 248090 123914 248090 123910 248090 114138 248091 123906 248091 123905 248091 112198 248092 123915 248092 123914 248092 123914 248093 123915 248093 112203 248093 123914 248094 112203 248094 123847 248094 114139 248095 114138 248095 123916 248095 123916 248096 114138 248096 123905 248096 123916 248097 123905 248097 123888 248097 123888 248098 123905 248098 123908 248098 123888 248099 123908 248099 123861 248099 123861 248100 123908 248100 123907 248100 123861 248101 123907 248101 123862 248101 123862 248102 123907 248102 123917 248102 123862 248103 123917 248103 123863 248103 123863 248104 123917 248104 123918 248104 123863 248105 123918 248105 123864 248105 123864 248106 123918 248106 123919 248106 123864 248107 123919 248107 123920 248107 123920 248108 123919 248108 123913 248108 123920 248109 123913 248109 123921 248109 123921 248110 123913 248110 123912 248110 123921 248111 123912 248111 123922 248111 123922 248112 123912 248112 123910 248112 123922 248113 123910 248113 123903 248113 123903 248114 123910 248114 123914 248114 123903 248115 123914 248115 123879 248115 123879 248116 123914 248116 123847 248116 123992 248117 123939 248117 123938 248117 123923 248118 123944 248118 123924 248118 123923 248119 120243 248119 123945 248119 123923 248120 123924 248120 120260 248120 120260 248121 123924 248121 123957 248121 120260 248122 123957 248122 120259 248122 120259 248123 123957 248123 123958 248123 120259 248124 123958 248124 120264 248124 120264 248125 123958 248125 123926 248125 120264 248126 123926 248126 123925 248126 123925 248127 123926 248127 123927 248127 123927 248128 123926 248128 123929 248128 123927 248129 123929 248129 123928 248129 123928 248130 123929 248130 123930 248130 123928 248131 123930 248131 123931 248131 123931 248132 123930 248132 123932 248132 123931 248133 123932 248133 123961 248133 120212 248134 123933 248134 123955 248134 120212 248135 123955 248135 123934 248135 123934 248136 123955 248136 123953 248136 123934 248137 123953 248137 120179 248137 120179 248138 123953 248138 123952 248138 120179 248139 123952 248139 120190 248139 120190 248140 123952 248140 123935 248140 123935 248141 123952 248141 123950 248141 123935 248142 123950 248142 120192 248142 120192 248143 123950 248143 123936 248143 120192 248144 123936 248144 123937 248144 123937 248145 123936 248145 123948 248145 123937 248146 123948 248146 120194 248146 120194 248147 123948 248147 123938 248147 120194 248148 123938 248148 123940 248148 123940 248149 123938 248149 123939 248149 123940 248150 123939 248150 123941 248150 123942 248151 123943 248151 123947 248151 123947 248152 123943 248152 123992 248152 123923 248153 123945 248153 123944 248153 123944 248154 123945 248154 123946 248154 123944 248155 123946 248155 123942 248155 123992 248156 123938 248156 123947 248156 123947 248157 123938 248157 123948 248157 123947 248158 123948 248158 123949 248158 123949 248159 123948 248159 123936 248159 123949 248160 123936 248160 123956 248160 123956 248161 123936 248161 123950 248161 123956 248162 123950 248162 123951 248162 123951 248163 123950 248163 123952 248163 123951 248164 123952 248164 123959 248164 123959 248165 123952 248165 123953 248165 123959 248166 123953 248166 123954 248166 123954 248167 123953 248167 123955 248167 123954 248168 123955 248168 123960 248168 123960 248169 123955 248169 123933 248169 123960 248170 123933 248170 123962 248170 123942 248171 123947 248171 123944 248171 123944 248172 123947 248172 123949 248172 123944 248173 123949 248173 123924 248173 123924 248174 123949 248174 123956 248174 123924 248175 123956 248175 123957 248175 123957 248176 123956 248176 123951 248176 123957 248177 123951 248177 123958 248177 123958 248178 123951 248178 123959 248178 123958 248179 123959 248179 123926 248179 123926 248180 123959 248180 123954 248180 123926 248181 123954 248181 123929 248181 123929 248182 123954 248182 123960 248182 123929 248183 123960 248183 123930 248183 123930 248184 123960 248184 123962 248184 123930 248185 123962 248185 123932 248185 124021 248186 124023 248186 123961 248186 123933 248187 120212 248187 120214 248187 123961 248188 123932 248188 124021 248188 124021 248189 123932 248189 123962 248189 124021 248190 123962 248190 123963 248190 123963 248191 123962 248191 123933 248191 123963 248192 123933 248192 124005 248192 124005 248193 123933 248193 120214 248193 123974 248194 123996 248194 123991 248194 123945 248195 120243 248195 123975 248195 120235 248196 123968 248196 123972 248196 123964 248197 124043 248197 124030 248197 124043 248198 123964 248198 124044 248198 124044 248199 123964 248199 123965 248199 124044 248200 123965 248200 123966 248200 123966 248201 123965 248201 123967 248201 123967 248202 123965 248202 123972 248202 123967 248203 123972 248203 124035 248203 124035 248204 123972 248204 123968 248204 124035 248205 123968 248205 124036 248205 123994 248206 123969 248206 123995 248206 123995 248207 123969 248207 123970 248207 123995 248208 123970 248208 123989 248208 123964 248209 123971 248209 123965 248209 123965 248210 123971 248210 123988 248210 123965 248211 123988 248211 123972 248211 123972 248212 123988 248212 123987 248212 123972 248213 123987 248213 120235 248213 123996 248214 123974 248214 123973 248214 123973 248215 123974 248215 123942 248215 123973 248216 123942 248216 123946 248216 123975 248217 120240 248217 123994 248217 123945 248218 123993 248218 123946 248218 123946 248219 123993 248219 123976 248219 123946 248220 123976 248220 123973 248220 123973 248221 123976 248221 123977 248221 123973 248222 123977 248222 123996 248222 123978 248223 123979 248223 123980 248223 123980 248224 123979 248224 124038 248224 124040 248225 123981 248225 123982 248225 123982 248226 123981 248226 123983 248226 123982 248227 123983 248227 124033 248227 124033 248228 123983 248228 123984 248228 123989 248229 123984 248229 123985 248229 123985 248230 123984 248230 123983 248230 123985 248231 123983 248231 123997 248231 123997 248232 123983 248232 123981 248232 123980 248233 123986 248233 123978 248233 123978 248234 123986 248234 120200 248234 123978 248235 120200 248235 123990 248235 120240 248236 120238 248236 123994 248236 123994 248237 120238 248237 123987 248237 123994 248238 123987 248238 123969 248238 123969 248239 123987 248239 123988 248239 123969 248240 123988 248240 123970 248240 123970 248241 123988 248241 123971 248241 123970 248242 123971 248242 123989 248242 123989 248243 123971 248243 123964 248243 123989 248244 123964 248244 123984 248244 123984 248245 123964 248245 124030 248245 123984 248246 124030 248246 124033 248246 120200 248247 123941 248247 123990 248247 123990 248248 123941 248248 123939 248248 123990 248249 123939 248249 123991 248249 123991 248250 123939 248250 123992 248250 123991 248251 123992 248251 123974 248251 123974 248252 123992 248252 123943 248252 123974 248253 123943 248253 123942 248253 123945 248254 123975 248254 123993 248254 123993 248255 123975 248255 123994 248255 123993 248256 123994 248256 123976 248256 123976 248257 123994 248257 123995 248257 123976 248258 123995 248258 123977 248258 123977 248259 123995 248259 123989 248259 123977 248260 123989 248260 123996 248260 123996 248261 123989 248261 123985 248261 123996 248262 123985 248262 123991 248262 123991 248263 123985 248263 123997 248263 123991 248264 123997 248264 123990 248264 123990 248265 123997 248265 123981 248265 123990 248266 123981 248266 123978 248266 123978 248267 123981 248267 124040 248267 123978 248268 124040 248268 123979 248268 120254 248269 124013 248269 124014 248269 123998 248270 124051 248270 124008 248270 123999 248271 124000 248271 124001 248271 124001 248272 124000 248272 124020 248272 124001 248273 124020 248273 124009 248273 124009 248274 120249 248274 124001 248274 124001 248275 120249 248275 120252 248275 124001 248276 120252 248276 123999 248276 123999 248277 120252 248277 124022 248277 120216 248278 124002 248278 124003 248278 124003 248279 124002 248279 124012 248279 124005 248280 120214 248280 124004 248280 124005 248281 124004 248281 124019 248281 124048 248282 120254 248282 124006 248282 124006 248283 120254 248283 124014 248283 124006 248284 124014 248284 124008 248284 124008 248285 124014 248285 124007 248285 124008 248286 124007 248286 123998 248286 123998 248287 124007 248287 124017 248287 124020 248288 124018 248288 124009 248288 124009 248289 124018 248289 124010 248289 124009 248290 124010 248290 120249 248290 120249 248291 124010 248291 124016 248291 120249 248292 124016 248292 124015 248292 124002 248293 120219 248293 124012 248293 124012 248294 120219 248294 124011 248294 124012 248295 124011 248295 124050 248295 124004 248296 120216 248296 124019 248296 124019 248297 120216 248297 124003 248297 124019 248298 124003 248298 124017 248298 124017 248299 124003 248299 124012 248299 124017 248300 124012 248300 123998 248300 123998 248301 124012 248301 124050 248301 123998 248302 124050 248302 124051 248302 124013 248303 124015 248303 124014 248303 124014 248304 124015 248304 124016 248304 124014 248305 124016 248305 124007 248305 124007 248306 124016 248306 124010 248306 124007 248307 124010 248307 124017 248307 124017 248308 124010 248308 124018 248308 124017 248309 124018 248309 124019 248309 124019 248310 124018 248310 124020 248310 124019 248311 124020 248311 124005 248311 124005 248312 124020 248312 124000 248312 124005 248313 124000 248313 123963 248313 123963 248314 124000 248314 123999 248314 123963 248315 123999 248315 124021 248315 124021 248316 123999 248316 124022 248316 124021 248317 124022 248317 124023 248317 123627 248318 124037 248318 124039 248318 124058 248319 124029 248319 124057 248319 124057 248320 124029 248320 124041 248320 124057 248321 124041 248321 124056 248321 124056 248322 124041 248322 124025 248322 124056 248323 124025 248323 124024 248323 124024 248324 124025 248324 124042 248324 124024 248325 124042 248325 124027 248325 124027 248326 124042 248326 124026 248326 124027 248327 124026 248327 124054 248327 124054 248328 124026 248328 124045 248328 124054 248329 124045 248329 124028 248329 124034 248330 120267 248330 124028 248330 124040 248331 124029 248331 124039 248331 124039 248332 124029 248332 124058 248332 124039 248333 124058 248333 123627 248333 124043 248334 124031 248334 124030 248334 124030 248335 124031 248335 124032 248335 124030 248336 124032 248336 124033 248336 124033 248337 124032 248337 123982 248337 124028 248338 124045 248338 124034 248338 124034 248339 124045 248339 124035 248339 124034 248340 124035 248340 124036 248340 124037 248341 124038 248341 124039 248341 124039 248342 124038 248342 123979 248342 124039 248343 123979 248343 124040 248343 124040 248344 123982 248344 124029 248344 124029 248345 123982 248345 124032 248345 124029 248346 124032 248346 124041 248346 124041 248347 124032 248347 124031 248347 124041 248348 124031 248348 124025 248348 124025 248349 124031 248349 124043 248349 124025 248350 124043 248350 124042 248350 124042 248351 124043 248351 124044 248351 124042 248352 124044 248352 124026 248352 124026 248353 124044 248353 123966 248353 124026 248354 123966 248354 124045 248354 124045 248355 123966 248355 123967 248355 124045 248356 123967 248356 124035 248356 124049 248357 124046 248357 124047 248357 124048 248358 124006 248358 120247 248358 120247 248359 124006 248359 124060 248359 120247 248360 124060 248360 120245 248360 124006 248361 124008 248361 124060 248361 124060 248362 124008 248362 124051 248362 124060 248363 124051 248363 124047 248363 120219 248364 124049 248364 124011 248364 124011 248365 124049 248365 124047 248365 124011 248366 124047 248366 124050 248366 124050 248367 124047 248367 124051 248367 120267 248368 124052 248368 124028 248368 124028 248369 124052 248369 124053 248369 124028 248370 124053 248370 124054 248370 124054 248371 124053 248371 124063 248371 124054 248372 124063 248372 124027 248372 124027 248373 124063 248373 124055 248373 124027 248374 124055 248374 124024 248374 124024 248375 124055 248375 124065 248375 124024 248376 124065 248376 124056 248376 124056 248377 124065 248377 124067 248377 124056 248378 124067 248378 124057 248378 124057 248379 124067 248379 124072 248379 124057 248380 124072 248380 124058 248380 124058 248381 124072 248381 124071 248381 124058 248382 124071 248382 123627 248382 123627 248383 124071 248383 124069 248383 124046 248384 120206 248384 124059 248384 124046 248385 124059 248385 124047 248385 124047 248386 124059 248386 124082 248386 124047 248387 124082 248387 124060 248387 124060 248388 124082 248388 124081 248388 124060 248389 124081 248389 120245 248389 124055 248390 124064 248390 124061 248390 124062 248391 120269 248391 124092 248391 124053 248392 124052 248392 124062 248392 124053 248393 124062 248393 124063 248393 124063 248394 124062 248394 124092 248394 124063 248395 124092 248395 124055 248395 124055 248396 124092 248396 124091 248396 124055 248397 124091 248397 124064 248397 124097 248398 124067 248398 124061 248398 124061 248399 124067 248399 124065 248399 124061 248400 124065 248400 124055 248400 124097 248401 124066 248401 124067 248401 124067 248402 124066 248402 124070 248402 124067 248403 124070 248403 124072 248403 124068 248404 124069 248404 124070 248404 124070 248405 124069 248405 124071 248405 124070 248406 124071 248406 124072 248406 124073 248407 120257 248407 124074 248407 124074 248408 120257 248408 124075 248408 124074 248409 124075 248409 124076 248409 124076 248410 124075 248410 124079 248410 124077 248411 124078 248411 124079 248411 124079 248412 124078 248412 124099 248412 124079 248413 124099 248413 124076 248413 120257 248414 120256 248414 124075 248414 124075 248415 120256 248415 124080 248415 124075 248416 124080 248416 124079 248416 124079 248417 124080 248417 124083 248417 124079 248418 124083 248418 124077 248418 124077 248419 124083 248419 120205 248419 120256 248420 124081 248420 124080 248420 124080 248421 124081 248421 124082 248421 124080 248422 124082 248422 124083 248422 124083 248423 124082 248423 124059 248423 124083 248424 124059 248424 120205 248424 120205 248425 124059 248425 120206 248425 124095 248426 124096 248426 124084 248426 124096 248427 124085 248427 124084 248427 124084 248428 124085 248428 124086 248428 124084 248429 124086 248429 124115 248429 124115 248430 124086 248430 124087 248430 124115 248431 124087 248431 124114 248431 124114 248432 124087 248432 124098 248432 124114 248433 124098 248433 124088 248433 124088 248434 124098 248434 124112 248434 124112 248435 124098 248435 124090 248435 124112 248436 124090 248436 124089 248436 124089 248437 124090 248437 124093 248437 124089 248438 124093 248438 124094 248438 124092 248439 120269 248439 120270 248439 124098 248440 124091 248440 124090 248440 124090 248441 124091 248441 124092 248441 124090 248442 124092 248442 124093 248442 124093 248443 124092 248443 120270 248443 124093 248444 120270 248444 124094 248444 124094 248445 120270 248445 124110 248445 124095 248446 124068 248446 124096 248446 124096 248447 124068 248447 124070 248447 124096 248448 124070 248448 124085 248448 124085 248449 124070 248449 124066 248449 124085 248450 124066 248450 124086 248450 124086 248451 124066 248451 124097 248451 124086 248452 124097 248452 124087 248452 124087 248453 124097 248453 124061 248453 124087 248454 124061 248454 124098 248454 124098 248455 124061 248455 124064 248455 124098 248456 124064 248456 124091 248456 124078 248457 120168 248457 124150 248457 124078 248458 124150 248458 124099 248458 124099 248459 124150 248459 124100 248459 124099 248460 124100 248460 124076 248460 124076 248461 124100 248461 124148 248461 124076 248462 124148 248462 124074 248462 124074 248463 124148 248463 124147 248463 124074 248464 124147 248464 124073 248464 124160 248465 123626 248465 124107 248465 124119 248466 124101 248466 124084 248466 124102 248467 124151 248467 124178 248467 124116 248468 124117 248468 124113 248468 124178 248469 124177 248469 124102 248469 124102 248470 124177 248470 124103 248470 124102 248471 124103 248471 124120 248471 124103 248472 124176 248472 124120 248472 124120 248473 124176 248473 124104 248473 124120 248474 124104 248474 124105 248474 124105 248475 124104 248475 124160 248475 124105 248476 124160 248476 124106 248476 124106 248477 124160 248477 124107 248477 124106 248478 124107 248478 124095 248478 124111 248479 124165 248479 124108 248479 124108 248480 124165 248480 124109 248480 124108 248481 124109 248481 124113 248481 124113 248482 124109 248482 124152 248482 124113 248483 124152 248483 124116 248483 124110 248484 124111 248484 124094 248484 124094 248485 124111 248485 124108 248485 124094 248486 124108 248486 124089 248486 124089 248487 124108 248487 124113 248487 124089 248488 124113 248488 124112 248488 124112 248489 124113 248489 124117 248489 124112 248490 124117 248490 124088 248490 124088 248491 124117 248491 124118 248491 124088 248492 124118 248492 124114 248492 124114 248493 124118 248493 124119 248493 124114 248494 124119 248494 124115 248494 124115 248495 124119 248495 124084 248495 124116 248496 124151 248496 124117 248496 124117 248497 124151 248497 124102 248497 124117 248498 124102 248498 124118 248498 124118 248499 124102 248499 124120 248499 124118 248500 124120 248500 124119 248500 124119 248501 124120 248501 124105 248501 124119 248502 124105 248502 124101 248502 124101 248503 124105 248503 124106 248503 124101 248504 124106 248504 124084 248504 124084 248505 124106 248505 124095 248505 120166 248506 124146 248506 124145 248506 120165 248507 120164 248507 124144 248507 124121 248508 120223 248508 120279 248508 120279 248509 124125 248509 124121 248509 124121 248510 124125 248510 124122 248510 124121 248511 124122 248511 124123 248511 124123 248512 124122 248512 124128 248512 124123 248513 124128 248513 124200 248513 124200 248514 124128 248514 124124 248514 124200 248515 124124 248515 124161 248515 120279 248516 124132 248516 124125 248516 124125 248517 124132 248517 124126 248517 124125 248518 124126 248518 124122 248518 124122 248519 124126 248519 124127 248519 124122 248520 124127 248520 124128 248520 124128 248521 124127 248521 124135 248521 124128 248522 124135 248522 124124 248522 120171 248523 120174 248523 124135 248523 124135 248524 120174 248524 124129 248524 124135 248525 124129 248525 124124 248525 124133 248526 124130 248526 124131 248526 124131 248527 124130 248527 124138 248527 124131 248528 124138 248528 124134 248528 124134 248529 124138 248529 124140 248529 124134 248530 124140 248530 124136 248530 124136 248531 124140 248531 124137 248531 124132 248532 124133 248532 124126 248532 124126 248533 124133 248533 124131 248533 124126 248534 124131 248534 124127 248534 124127 248535 124131 248535 124134 248535 124127 248536 124134 248536 124135 248536 124135 248537 124134 248537 124136 248537 124135 248538 124136 248538 120171 248538 120171 248539 124136 248539 124137 248539 120171 248540 124137 248540 120169 248540 120169 248541 124137 248541 120155 248541 124130 248542 120271 248542 124138 248542 124138 248543 120271 248543 124139 248543 124138 248544 124139 248544 124140 248544 124140 248545 124139 248545 124143 248545 124140 248546 124143 248546 124137 248546 124137 248547 124143 248547 124144 248547 124137 248548 124144 248548 120155 248548 120155 248549 124144 248549 120164 248549 120271 248550 124141 248550 124139 248550 124139 248551 124141 248551 124142 248551 124139 248552 124142 248552 124143 248552 124143 248553 124142 248553 124149 248553 124143 248554 124149 248554 124144 248554 124144 248555 124149 248555 124145 248555 124144 248556 124145 248556 120165 248556 120165 248557 124145 248557 124146 248557 124141 248558 124147 248558 124142 248558 124142 248559 124147 248559 124148 248559 124142 248560 124148 248560 124149 248560 124149 248561 124148 248561 124100 248561 124149 248562 124100 248562 124145 248562 124145 248563 124100 248563 124150 248563 124145 248564 124150 248564 120166 248564 120166 248565 124150 248565 120168 248565 124151 248566 124116 248566 124180 248566 124116 248567 124152 248567 124174 248567 124153 248568 120223 248568 124121 248568 124154 248569 124156 248569 124155 248569 124155 248570 124156 248570 120228 248570 124157 248571 124196 248571 124198 248571 120178 248572 124188 248572 124158 248572 124183 248573 124159 248573 124160 248573 124160 248574 124159 248574 120144 248574 124160 248575 120144 248575 123626 248575 124161 248576 120178 248576 124199 248576 124199 248577 120178 248577 124158 248577 124199 248578 124158 248578 124198 248578 124198 248579 124158 248579 124187 248579 124198 248580 124187 248580 124157 248580 124157 248581 124187 248581 124162 248581 124163 248582 124172 248582 120228 248582 120228 248583 124172 248583 124171 248583 120228 248584 124171 248584 124155 248584 124163 248585 120226 248585 124172 248585 124172 248586 120226 248586 124153 248586 124172 248587 124153 248587 124164 248587 124164 248588 124153 248588 124121 248588 124164 248589 124121 248589 124123 248589 124166 248590 124109 248590 124165 248590 124165 248591 120231 248591 124166 248591 124166 248592 120231 248592 124167 248592 124166 248593 124167 248593 124175 248593 124175 248594 124167 248594 120229 248594 124189 248595 124154 248595 124168 248595 124168 248596 124154 248596 124155 248596 124168 248597 124155 248597 124169 248597 124169 248598 124155 248598 124171 248598 124169 248599 124171 248599 124170 248599 124170 248600 124171 248600 124172 248600 124170 248601 124172 248601 124173 248601 124173 248602 124172 248602 124164 248602 124152 248603 124109 248603 124174 248603 124174 248604 124109 248604 124166 248604 124174 248605 124166 248605 124181 248605 124181 248606 124166 248606 124175 248606 124181 248607 124175 248607 124190 248607 124104 248608 124176 248608 124184 248608 124184 248609 124176 248609 124103 248609 124184 248610 124103 248610 124185 248610 124185 248611 124103 248611 124177 248611 124185 248612 124177 248612 124192 248612 124192 248613 124177 248613 124178 248613 124178 248614 124151 248614 124193 248614 124193 248615 124151 248615 124180 248615 124193 248616 124180 248616 124179 248616 124116 248617 124174 248617 124180 248617 124180 248618 124174 248618 124181 248618 124180 248619 124181 248619 124179 248619 124179 248620 124181 248620 124190 248620 124179 248621 124190 248621 124182 248621 124160 248622 124104 248622 124183 248622 124183 248623 124104 248623 124184 248623 124183 248624 124184 248624 124186 248624 124186 248625 124184 248625 124185 248625 124186 248626 124185 248626 124194 248626 124194 248627 124185 248627 124192 248627 124194 248628 124162 248628 124186 248628 124186 248629 124162 248629 124187 248629 124186 248630 124187 248630 124183 248630 124183 248631 124187 248631 124158 248631 124183 248632 124158 248632 124159 248632 124159 248633 124158 248633 124188 248633 124159 248634 124188 248634 120144 248634 120229 248635 124189 248635 124175 248635 124175 248636 124189 248636 124168 248636 124175 248637 124168 248637 124190 248637 124190 248638 124168 248638 124169 248638 124190 248639 124169 248639 124182 248639 124182 248640 124169 248640 124170 248640 124182 248641 124170 248641 124195 248641 124195 248642 124170 248642 124173 248642 124195 248643 124173 248643 124191 248643 124191 248644 124173 248644 124164 248644 124191 248645 124164 248645 124197 248645 124197 248646 124164 248646 124123 248646 124178 248647 124193 248647 124192 248647 124192 248648 124193 248648 124179 248648 124192 248649 124179 248649 124194 248649 124194 248650 124179 248650 124182 248650 124194 248651 124182 248651 124162 248651 124162 248652 124182 248652 124195 248652 124162 248653 124195 248653 124157 248653 124157 248654 124195 248654 124191 248654 124157 248655 124191 248655 124196 248655 124196 248656 124191 248656 124197 248656 124196 248657 124197 248657 124198 248657 124198 248658 124197 248658 124123 248658 124198 248659 124123 248659 124199 248659 124199 248660 124123 248660 124200 248660 124199 248661 124200 248661 124161 248661 119953 248662 124201 248662 124203 248662 124203 248663 124201 248663 124204 248663 124204 248664 124201 248664 124238 248664 124238 248665 124201 248665 124247 248665 124238 248666 124247 248666 124239 248666 124239 248667 124247 248667 124246 248667 124239 248668 124246 248668 124202 248668 124203 248669 124204 248669 124232 248669 124205 248670 124220 248670 124206 248670 120000 248671 124219 248671 124234 248671 120000 248672 124207 248672 124218 248672 120000 248673 124234 248673 124209 248673 124209 248674 124234 248674 124208 248674 124209 248675 124208 248675 119997 248675 119997 248676 124208 248676 124210 248676 124210 248677 124208 248677 124211 248677 124210 248678 124211 248678 119996 248678 119996 248679 124211 248679 124212 248679 119996 248680 124212 248680 124213 248680 124213 248681 124212 248681 124237 248681 124213 248682 124237 248682 124214 248682 124214 248683 124237 248683 124215 248683 124215 248684 124237 248684 124239 248684 124215 248685 124239 248685 124202 248685 124220 248686 119931 248686 124221 248686 124216 248687 124280 248687 124217 248687 124217 248688 124280 248688 124205 248688 120000 248689 124218 248689 124219 248689 124219 248690 124218 248690 124281 248690 124219 248691 124281 248691 124216 248691 124220 248692 124221 248692 124206 248692 124206 248693 124221 248693 124222 248693 124206 248694 124222 248694 124227 248694 124227 248695 124222 248695 119940 248695 124227 248696 119940 248696 124229 248696 124229 248697 119940 248697 124224 248697 124229 248698 124224 248698 124223 248698 124223 248699 124224 248699 124225 248699 124223 248700 124225 248700 124231 248700 124225 248701 119937 248701 124231 248701 124231 248702 119937 248702 119907 248702 124231 248703 119907 248703 124232 248703 124232 248704 119907 248704 124226 248704 124232 248705 124226 248705 124203 248705 124205 248706 124206 248706 124217 248706 124217 248707 124206 248707 124227 248707 124217 248708 124227 248708 124228 248708 124228 248709 124227 248709 124229 248709 124228 248710 124229 248710 124230 248710 124230 248711 124229 248711 124223 248711 124230 248712 124223 248712 124235 248712 124235 248713 124223 248713 124231 248713 124235 248714 124231 248714 124236 248714 124236 248715 124231 248715 124232 248715 124236 248716 124232 248716 124233 248716 124233 248717 124232 248717 124204 248717 124233 248718 124204 248718 124238 248718 124216 248719 124217 248719 124219 248719 124219 248720 124217 248720 124228 248720 124219 248721 124228 248721 124234 248721 124234 248722 124228 248722 124230 248722 124234 248723 124230 248723 124208 248723 124208 248724 124230 248724 124235 248724 124208 248725 124235 248725 124211 248725 124211 248726 124235 248726 124236 248726 124211 248727 124236 248727 124212 248727 124212 248728 124236 248728 124233 248728 124212 248729 124233 248729 124237 248729 124237 248730 124233 248730 124238 248730 124237 248731 124238 248731 124239 248731 119989 248732 119990 248732 124240 248732 124240 248733 119990 248733 124241 248733 124240 248734 124241 248734 124294 248734 124294 248735 124241 248735 124243 248735 124294 248736 124243 248736 119957 248736 119957 248737 124243 248737 124244 248737 119990 248738 124245 248738 124241 248738 124241 248739 124245 248739 124242 248739 124241 248740 124242 248740 124243 248740 124243 248741 124242 248741 124248 248741 124243 248742 124248 248742 124244 248742 124244 248743 124248 248743 124249 248743 124245 248744 124246 248744 124242 248744 124242 248745 124246 248745 124247 248745 124242 248746 124247 248746 124248 248746 124248 248747 124247 248747 124201 248747 124248 248748 124201 248748 124249 248748 124249 248749 124201 248749 119953 248749 124271 248750 124291 248750 124290 248750 124250 248751 124251 248751 124284 248751 124259 248752 124273 248752 124252 248752 124254 248753 124275 248753 124253 248753 124254 248754 124253 248754 124265 248754 124265 248755 124253 248755 124255 248755 124265 248756 124255 248756 124264 248756 124256 248757 124258 248757 124257 248757 124257 248758 124258 248758 124305 248758 124257 248759 124305 248759 124255 248759 124255 248760 124305 248760 124312 248760 124255 248761 124312 248761 124264 248761 119984 248762 124259 248762 124260 248762 124260 248763 124259 248763 124252 248763 124260 248764 124252 248764 124285 248764 124285 248765 124252 248765 124274 248765 124285 248766 124274 248766 124289 248766 124292 248767 119931 248767 124261 248767 124261 248768 119931 248768 124220 248768 124261 248769 124220 248769 124277 248769 124312 248770 124262 248770 124264 248770 124264 248771 124262 248771 124263 248771 124264 248772 124263 248772 124265 248772 124265 248773 124263 248773 124310 248773 124265 248774 124310 248774 124254 248774 124254 248775 124310 248775 124266 248775 124254 248776 124266 248776 124275 248776 124291 248777 124271 248777 124270 248777 124306 248778 124267 248778 124268 248778 124268 248779 124267 248779 124270 248779 124268 248780 124270 248780 124269 248780 124269 248781 124270 248781 124271 248781 124269 248782 124271 248782 124309 248782 124309 248783 124271 248783 124272 248783 124273 248784 124256 248784 124252 248784 124252 248785 124256 248785 124257 248785 124252 248786 124257 248786 124274 248786 124274 248787 124257 248787 124255 248787 124274 248788 124255 248788 124289 248788 124289 248789 124255 248789 124253 248789 124289 248790 124253 248790 124290 248790 124290 248791 124253 248791 124275 248791 124290 248792 124275 248792 124271 248792 124271 248793 124275 248793 124266 248793 124271 248794 124266 248794 124272 248794 124207 248795 124283 248795 124218 248795 124218 248796 124283 248796 124276 248796 124218 248797 124276 248797 124281 248797 124220 248798 124205 248798 124277 248798 124277 248799 124205 248799 124278 248799 124277 248800 124278 248800 124288 248800 124288 248801 124278 248801 124279 248801 124288 248802 124279 248802 124287 248802 124287 248803 124279 248803 124282 248803 124287 248804 124282 248804 124286 248804 124286 248805 124282 248805 124284 248805 124205 248806 124280 248806 124278 248806 124278 248807 124280 248807 124216 248807 124278 248808 124216 248808 124279 248808 124279 248809 124216 248809 124281 248809 124279 248810 124281 248810 124282 248810 124282 248811 124281 248811 124276 248811 124282 248812 124276 248812 124284 248812 124284 248813 124276 248813 124283 248813 124284 248814 124283 248814 124250 248814 124251 248815 119984 248815 124284 248815 124284 248816 119984 248816 124260 248816 124284 248817 124260 248817 124286 248817 124286 248818 124260 248818 124285 248818 124286 248819 124285 248819 124287 248819 124287 248820 124285 248820 124289 248820 124287 248821 124289 248821 124288 248821 124288 248822 124289 248822 124290 248822 124288 248823 124290 248823 124277 248823 124277 248824 124290 248824 124291 248824 124277 248825 124291 248825 124261 248825 124261 248826 124291 248826 124270 248826 124261 248827 124270 248827 124292 248827 124292 248828 124270 248828 124267 248828 124292 248829 124267 248829 124293 248829 124293 248830 124267 248830 124306 248830 124293 248831 124306 248831 123629 248831 119969 248832 124328 248832 119957 248832 119957 248833 124328 248833 124294 248833 124328 248834 124322 248834 124294 248834 124294 248835 124322 248835 124297 248835 124294 248836 124297 248836 124240 248836 119988 248837 119989 248837 124295 248837 124295 248838 119989 248838 124240 248838 124295 248839 124240 248839 124296 248839 124296 248840 124240 248840 124297 248840 123628 248841 123629 248841 124306 248841 124298 248842 123628 248842 124329 248842 124329 248843 123628 248843 124306 248843 124329 248844 124306 248844 124331 248844 124331 248845 124307 248845 124332 248845 124332 248846 124307 248846 124299 248846 124332 248847 124299 248847 124300 248847 124300 248848 124299 248848 124301 248848 124300 248849 124301 248849 124302 248849 124302 248850 124301 248850 124311 248850 124302 248851 124311 248851 124303 248851 124303 248852 124311 248852 124304 248852 124258 248853 119982 248853 124305 248853 124305 248854 119982 248854 124312 248854 124268 248855 124269 248855 124308 248855 124308 248856 124269 248856 124309 248856 124306 248857 124268 248857 124331 248857 124331 248858 124268 248858 124308 248858 124331 248859 124308 248859 124307 248859 124307 248860 124308 248860 124309 248860 124307 248861 124309 248861 124272 248861 124272 248862 124266 248862 124307 248862 124307 248863 124266 248863 124310 248863 124307 248864 124310 248864 124299 248864 124299 248865 124310 248865 124263 248865 124299 248866 124263 248866 124301 248866 124301 248867 124263 248867 124262 248867 124301 248868 124262 248868 124311 248868 124311 248869 124262 248869 124312 248869 124311 248870 124312 248870 124304 248870 124304 248871 124312 248871 119982 248871 124304 248872 119982 248872 124313 248872 124335 248873 124336 248873 124323 248873 124336 248874 124338 248874 124324 248874 124338 248875 124317 248875 124319 248875 119988 248876 124320 248876 124314 248876 124314 248877 124320 248877 124315 248877 124314 248878 124315 248878 124316 248878 124316 248879 124315 248879 124319 248879 124316 248880 124319 248880 119991 248880 119991 248881 124319 248881 124317 248881 119991 248882 124317 248882 124318 248882 124338 248883 124319 248883 124324 248883 124324 248884 124319 248884 124315 248884 124324 248885 124315 248885 124325 248885 124325 248886 124315 248886 124320 248886 124325 248887 124320 248887 124321 248887 119988 248888 124295 248888 124320 248888 124320 248889 124295 248889 124296 248889 124320 248890 124296 248890 124321 248890 124321 248891 124296 248891 124297 248891 124321 248892 124297 248892 124322 248892 124336 248893 124324 248893 124323 248893 124323 248894 124324 248894 124325 248894 124323 248895 124325 248895 124326 248895 124326 248896 124325 248896 124321 248896 124326 248897 124321 248897 124327 248897 124327 248898 124321 248898 124322 248898 124327 248899 124322 248899 124328 248899 124335 248900 124323 248900 119964 248900 119964 248901 124323 248901 124326 248901 119964 248902 124326 248902 119965 248902 119965 248903 124326 248903 124327 248903 119965 248904 124327 248904 119967 248904 119967 248905 124327 248905 124328 248905 119967 248906 124328 248906 119969 248906 124341 248907 123630 248907 124298 248907 124298 248908 124329 248908 124341 248908 124341 248909 124329 248909 124331 248909 124341 248910 124331 248910 124330 248910 124330 248911 124331 248911 124332 248911 124330 248912 124332 248912 124333 248912 124333 248913 124332 248913 124300 248913 124333 248914 124300 248914 124342 248914 124342 248915 124300 248915 124302 248915 124342 248916 124302 248916 124344 248916 124344 248917 124302 248917 124303 248917 124344 248918 124303 248918 124345 248918 124345 248919 124303 248919 124304 248919 124345 248920 124304 248920 124347 248920 124347 248921 124304 248921 124313 248921 124347 248922 124313 248922 119976 248922 124335 248923 119962 248923 124334 248923 124335 248924 124334 248924 124336 248924 124336 248925 124334 248925 124337 248925 124336 248926 124337 248926 124338 248926 124338 248927 124337 248927 124372 248927 124338 248928 124372 248928 124317 248928 124317 248929 124372 248929 120007 248929 124317 248930 120007 248930 124318 248930 124347 248931 119976 248931 124339 248931 123631 248932 123630 248932 124340 248932 124340 248933 123630 248933 124341 248933 124340 248934 124341 248934 124380 248934 124380 248935 124341 248935 124330 248935 124380 248936 124330 248936 124379 248936 124379 248937 124330 248937 124333 248937 124379 248938 124333 248938 124419 248938 124419 248939 124333 248939 124342 248939 124419 248940 124342 248940 124343 248940 124343 248941 124342 248941 124344 248941 124343 248942 124344 248942 124422 248942 124422 248943 124344 248943 124345 248943 124422 248944 124345 248944 124346 248944 124346 248945 124345 248945 124421 248945 124421 248946 124345 248946 124347 248946 124421 248947 124347 248947 124420 248947 124420 248948 124347 248948 124339 248948 124420 248949 124339 248949 119981 248949 124348 248950 120010 248950 124367 248950 119971 248951 124352 248951 124349 248951 119971 248952 124349 248952 124350 248952 124350 248953 124349 248953 124351 248953 124350 248954 124351 248954 124409 248954 119921 248955 119922 248955 124365 248955 124352 248956 120005 248956 124349 248956 124349 248957 120005 248957 124353 248957 124349 248958 124353 248958 124351 248958 124351 248959 124353 248959 124354 248959 124351 248960 124354 248960 124364 248960 124364 248961 124354 248961 124355 248961 120005 248962 120004 248962 124353 248962 124353 248963 120004 248963 124356 248963 124353 248964 124356 248964 124354 248964 124354 248965 124356 248965 124357 248965 124354 248966 124357 248966 124355 248966 124355 248967 124357 248967 124361 248967 120004 248968 120002 248968 124356 248968 124356 248969 120002 248969 124366 248969 124356 248970 124366 248970 124357 248970 124357 248971 124366 248971 124369 248971 124357 248972 124369 248972 124361 248972 124361 248973 124369 248973 124358 248973 124359 248974 124360 248974 124358 248974 124358 248975 124360 248975 124362 248975 124358 248976 124362 248976 124361 248976 124361 248977 124362 248977 124363 248977 124361 248978 124363 248978 124355 248978 124355 248979 124363 248979 119921 248979 124355 248980 119921 248980 124364 248980 124364 248981 119921 248981 124365 248981 124364 248982 124365 248982 124351 248982 124351 248983 124365 248983 124411 248983 124351 248984 124411 248984 124409 248984 120002 248985 124348 248985 124366 248985 124366 248986 124348 248986 124367 248986 124366 248987 124367 248987 124369 248987 124369 248988 124367 248988 124368 248988 124369 248989 124368 248989 124358 248989 124358 248990 124368 248990 124370 248990 124358 248991 124370 248991 124359 248991 124359 248992 124370 248992 119918 248992 119915 248993 119918 248993 124371 248993 124371 248994 119918 248994 124370 248994 124371 248995 124370 248995 124373 248995 124373 248996 124370 248996 124368 248996 124373 248997 124368 248997 124374 248997 124374 248998 124368 248998 124367 248998 124374 248999 124367 248999 120008 248999 120008 249000 124367 249000 120010 249000 119962 249001 119915 249001 124334 249001 124334 249002 119915 249002 124371 249002 124334 249003 124371 249003 124337 249003 124337 249004 124371 249004 124373 249004 124337 249005 124373 249005 124372 249005 124372 249006 124373 249006 124374 249006 124372 249007 124374 249007 120007 249007 120007 249008 124374 249008 120008 249008 124375 249009 124376 249009 124399 249009 124400 249010 124377 249010 124378 249010 124389 249011 124378 249011 119978 249011 124425 249012 124412 249012 124413 249012 124384 249013 124379 249013 124419 249013 124396 249014 124403 249014 119972 249014 119971 249015 124350 249015 124428 249015 124365 249016 119922 249016 124404 249016 124379 249017 124384 249017 124380 249017 124380 249018 124384 249018 124381 249018 124380 249019 124381 249019 124340 249019 124340 249020 124381 249020 124382 249020 124382 249021 124381 249021 124385 249021 124382 249022 124385 249022 124407 249022 124419 249023 124383 249023 124384 249023 124384 249024 124383 249024 124416 249024 124384 249025 124416 249025 124381 249025 124381 249026 124416 249026 124414 249026 124381 249027 124414 249027 124385 249027 124385 249028 124414 249028 124386 249028 124365 249029 124406 249029 124411 249029 124411 249030 124406 249030 124386 249030 124410 249031 124412 249031 124387 249031 124387 249032 124412 249032 124425 249032 124387 249033 124425 249033 124428 249033 124428 249034 124425 249034 124427 249034 119978 249035 124378 249035 124388 249035 124388 249036 124378 249036 124377 249036 124388 249037 124377 249037 119980 249037 119978 249038 119977 249038 124389 249038 124389 249039 119977 249039 124390 249039 124389 249040 124390 249040 124391 249040 124391 249041 124390 249041 119975 249041 124391 249042 119975 249042 124392 249042 124393 249043 124375 249043 124423 249043 124423 249044 124375 249044 124399 249044 124423 249045 124399 249045 124394 249045 124394 249046 124399 249046 124401 249046 124394 249047 124401 249047 124424 249047 124424 249048 124401 249048 124402 249048 124424 249049 124402 249049 124426 249049 124426 249050 124402 249050 124395 249050 124426 249051 124395 249051 124396 249051 124415 249052 124417 249052 124397 249052 124397 249053 124417 249053 124418 249053 124397 249054 124418 249054 124398 249054 124398 249055 124418 249055 124343 249055 124398 249056 124343 249056 124422 249056 124376 249057 124400 249057 124399 249057 124399 249058 124400 249058 124378 249058 124399 249059 124378 249059 124401 249059 124401 249060 124378 249060 124389 249060 124401 249061 124389 249061 124402 249061 124402 249062 124389 249062 124391 249062 124402 249063 124391 249063 124395 249063 124395 249064 124391 249064 124392 249064 124395 249065 124392 249065 124396 249065 124396 249066 124392 249066 119970 249066 124396 249067 119970 249067 124403 249067 124365 249068 124404 249068 124406 249068 124406 249069 124404 249069 124405 249069 124406 249070 124405 249070 119924 249070 124386 249071 124406 249071 124385 249071 124385 249072 124406 249072 119924 249072 124385 249073 119924 249073 124407 249073 124407 249074 119924 249074 124408 249074 124407 249075 124408 249075 124382 249075 124382 249076 124408 249076 123631 249076 124382 249077 123631 249077 124340 249077 124428 249078 124350 249078 124387 249078 124387 249079 124350 249079 124409 249079 124387 249080 124409 249080 124410 249080 124410 249081 124409 249081 124411 249081 124410 249082 124411 249082 124412 249082 124412 249083 124411 249083 124386 249083 124412 249084 124386 249084 124413 249084 124413 249085 124386 249085 124414 249085 124413 249086 124414 249086 124415 249086 124415 249087 124414 249087 124416 249087 124415 249088 124416 249088 124417 249088 124417 249089 124416 249089 124383 249089 124417 249090 124383 249090 124418 249090 124418 249091 124383 249091 124419 249091 124418 249092 124419 249092 124343 249092 119981 249093 119980 249093 124420 249093 124420 249094 119980 249094 124377 249094 124420 249095 124377 249095 124421 249095 124421 249096 124377 249096 124400 249096 124421 249097 124400 249097 124346 249097 124346 249098 124400 249098 124376 249098 124346 249099 124376 249099 124422 249099 124422 249100 124376 249100 124375 249100 124422 249101 124375 249101 124398 249101 124398 249102 124375 249102 124393 249102 124398 249103 124393 249103 124397 249103 124397 249104 124393 249104 124423 249104 124397 249105 124423 249105 124415 249105 124415 249106 124423 249106 124394 249106 124415 249107 124394 249107 124413 249107 124413 249108 124394 249108 124424 249108 124413 249109 124424 249109 124425 249109 124425 249110 124424 249110 124426 249110 124425 249111 124426 249111 124427 249111 124427 249112 124426 249112 124396 249112 124427 249113 124396 249113 124428 249113 124428 249114 124396 249114 119972 249114 124428 249115 119972 249115 119971 249115 119715 249116 124473 249116 119714 249116 119714 249117 124473 249117 124429 249117 124429 249118 124473 249118 124430 249118 124430 249119 124473 249119 124471 249119 124430 249120 124471 249120 124443 249120 124443 249121 124471 249121 124431 249121 124443 249122 124431 249122 119746 249122 124492 249123 124512 249123 124455 249123 119747 249124 119736 249124 124446 249124 124460 249125 124432 249125 119747 249125 119747 249126 124432 249126 124433 249126 124433 249127 124432 249127 124435 249127 124435 249128 124432 249128 124434 249128 124435 249129 124434 249129 124436 249129 124436 249130 124434 249130 124464 249130 124436 249131 124464 249131 124437 249131 124437 249132 124464 249132 124438 249132 124437 249133 124438 249133 124439 249133 124439 249134 124438 249134 124441 249134 124439 249135 124441 249135 124440 249135 124440 249136 124441 249136 124442 249136 124442 249137 124441 249137 124443 249137 124442 249138 124443 249138 119746 249138 124512 249139 119706 249139 124444 249139 124490 249140 124445 249140 124459 249140 124459 249141 124445 249141 124492 249141 119747 249142 124446 249142 124460 249142 124460 249143 124446 249143 124447 249143 124460 249144 124447 249144 124490 249144 124512 249145 124444 249145 124455 249145 124455 249146 124444 249146 124448 249146 124455 249147 124448 249147 124450 249147 124450 249148 124448 249148 124449 249148 124450 249149 124449 249149 124456 249149 124456 249150 124449 249150 119708 249150 124456 249151 119708 249151 124451 249151 124451 249152 119708 249152 124452 249152 124451 249153 124452 249153 124457 249153 124457 249154 124452 249154 124454 249154 124457 249155 124454 249155 124453 249155 124453 249156 124454 249156 119714 249156 124453 249157 119714 249157 124429 249157 124492 249158 124455 249158 124459 249158 124459 249159 124455 249159 124450 249159 124459 249160 124450 249160 124461 249160 124461 249161 124450 249161 124456 249161 124461 249162 124456 249162 124462 249162 124462 249163 124456 249163 124451 249163 124462 249164 124451 249164 124463 249164 124463 249165 124451 249165 124457 249165 124463 249166 124457 249166 124465 249166 124465 249167 124457 249167 124453 249167 124465 249168 124453 249168 124458 249168 124458 249169 124453 249169 124429 249169 124458 249170 124429 249170 124430 249170 124490 249171 124459 249171 124460 249171 124460 249172 124459 249172 124461 249172 124460 249173 124461 249173 124432 249173 124432 249174 124461 249174 124462 249174 124432 249175 124462 249175 124434 249175 124434 249176 124462 249176 124463 249176 124434 249177 124463 249177 124464 249177 124464 249178 124463 249178 124465 249178 124464 249179 124465 249179 124438 249179 124438 249180 124465 249180 124458 249180 124438 249181 124458 249181 124441 249181 124441 249182 124458 249182 124430 249182 124441 249183 124430 249183 124443 249183 119739 249184 119742 249184 124523 249184 124523 249185 119742 249185 124468 249185 124523 249186 124468 249186 124467 249186 124467 249187 124468 249187 124466 249187 124467 249188 124466 249188 119717 249188 119717 249189 124466 249189 124469 249189 119742 249190 119741 249190 124468 249190 124468 249191 119741 249191 124470 249191 124468 249192 124470 249192 124466 249192 124466 249193 124470 249193 124472 249193 124466 249194 124472 249194 124469 249194 124469 249195 124472 249195 124474 249195 119741 249196 124431 249196 124470 249196 124470 249197 124431 249197 124471 249197 124470 249198 124471 249198 124472 249198 124472 249199 124471 249199 124473 249199 124472 249200 124473 249200 124474 249200 124474 249201 124473 249201 119715 249201 124475 249202 124476 249202 124500 249202 124476 249203 124475 249203 124502 249203 124487 249204 124477 249204 124488 249204 124522 249205 124521 249205 124506 249205 124506 249206 124521 249206 124518 249206 124506 249207 124518 249207 124478 249207 124478 249208 124518 249208 124517 249208 124478 249209 124517 249209 124480 249209 124480 249210 124517 249210 124479 249210 124480 249211 124479 249211 124515 249211 124515 249212 124510 249212 124480 249212 124480 249213 124510 249213 124509 249213 124480 249214 124509 249214 124478 249214 124478 249215 124509 249215 124508 249215 124478 249216 124508 249216 124506 249216 124486 249217 124485 249217 124505 249217 124511 249218 124482 249218 124481 249218 124481 249219 124482 249219 124486 249219 124481 249220 124486 249220 124483 249220 124483 249221 124486 249221 124505 249221 124483 249222 124505 249222 124507 249222 124477 249223 119735 249223 124488 249223 124488 249224 119735 249224 124485 249224 124488 249225 124485 249225 124484 249225 124484 249226 124485 249226 124486 249226 124484 249227 124486 249227 124489 249227 124489 249228 124486 249228 124482 249228 124489 249229 124482 249229 124491 249229 124491 249230 124482 249230 124511 249230 119736 249231 124487 249231 124446 249231 124446 249232 124487 249232 124488 249232 124446 249233 124488 249233 124447 249233 124447 249234 124488 249234 124484 249234 124447 249235 124484 249235 124490 249235 124490 249236 124484 249236 124489 249236 124490 249237 124489 249237 124445 249237 124445 249238 124489 249238 124491 249238 124512 249239 124492 249239 124514 249239 124493 249240 124526 249240 124494 249240 124494 249241 124526 249241 124501 249241 124494 249242 124501 249242 124495 249242 124499 249243 124497 249243 124496 249243 124496 249244 124497 249244 124530 249244 124496 249245 124530 249245 124498 249245 124498 249246 124493 249246 124496 249246 124496 249247 124493 249247 124494 249247 124496 249248 124494 249248 124499 249248 124499 249249 124494 249249 124495 249249 124499 249250 124495 249250 124513 249250 119706 249251 124513 249251 124500 249251 124500 249252 124513 249252 124495 249252 124500 249253 124495 249253 124475 249253 124475 249254 124495 249254 124501 249254 124475 249255 124501 249255 124502 249255 124502 249256 124501 249256 124526 249256 124502 249257 124526 249257 119704 249257 119735 249258 119734 249258 124485 249258 124485 249259 119734 249259 124503 249259 124485 249260 124503 249260 124505 249260 124505 249261 124503 249261 124504 249261 124505 249262 124504 249262 124507 249262 124507 249263 124504 249263 119731 249263 124507 249264 119731 249264 124522 249264 124522 249265 124506 249265 124507 249265 124507 249266 124506 249266 124508 249266 124507 249267 124508 249267 124483 249267 124483 249268 124508 249268 124509 249268 124483 249269 124509 249269 124481 249269 124481 249270 124509 249270 124510 249270 124481 249271 124510 249271 124511 249271 124511 249272 124510 249272 124514 249272 124511 249273 124514 249273 124491 249273 124491 249274 124514 249274 124492 249274 124491 249275 124492 249275 124445 249275 119706 249276 124512 249276 124513 249276 124513 249277 124512 249277 124514 249277 124513 249278 124514 249278 124499 249278 124499 249279 124514 249279 124510 249279 124499 249280 124510 249280 124497 249280 124497 249281 124510 249281 124515 249281 124497 249282 124515 249282 124530 249282 124530 249283 124515 249283 124479 249283 124530 249284 124479 249284 124516 249284 124516 249285 124479 249285 124517 249285 124516 249286 124517 249286 124531 249286 124531 249287 124517 249287 124518 249287 124531 249288 124518 249288 124519 249288 124519 249289 124518 249289 124521 249289 124519 249290 124521 249290 124520 249290 124520 249291 124521 249291 124522 249291 124520 249292 124522 249292 124533 249292 119717 249293 124544 249293 124542 249293 119717 249294 124542 249294 124467 249294 124467 249295 124542 249295 124541 249295 124467 249296 124541 249296 124523 249296 124523 249297 124541 249297 124524 249297 124523 249298 124524 249298 119739 249298 119733 249299 119753 249299 124532 249299 124525 249300 119704 249300 124526 249300 124525 249301 124526 249301 124527 249301 124527 249302 124526 249302 124493 249302 124527 249303 124493 249303 124528 249303 124528 249304 124493 249304 124498 249304 124528 249305 124498 249305 124529 249305 124529 249306 124498 249306 124530 249306 124529 249307 124530 249307 124547 249307 124530 249308 124516 249308 124547 249308 124547 249309 124516 249309 124531 249309 124547 249310 124531 249310 124548 249310 124548 249311 124531 249311 124519 249311 124548 249312 124519 249312 124550 249312 124550 249313 124519 249313 124520 249313 124550 249314 124520 249314 124532 249314 124532 249315 124520 249315 124533 249315 124532 249316 124533 249316 119733 249316 124556 249317 124536 249317 124553 249317 124553 249318 124536 249318 124534 249318 124553 249319 124534 249319 124554 249319 124554 249320 124534 249320 124535 249320 124554 249321 124535 249321 119726 249321 119726 249322 124535 249322 124539 249322 124536 249323 124537 249323 124534 249323 124534 249324 124537 249324 124538 249324 124534 249325 124538 249325 124535 249325 124535 249326 124538 249326 124540 249326 124535 249327 124540 249327 124539 249327 124539 249328 124540 249328 124543 249328 124537 249329 124524 249329 124538 249329 124538 249330 124524 249330 124541 249330 124538 249331 124541 249331 124540 249331 124540 249332 124541 249332 124542 249332 124540 249333 124542 249333 124543 249333 124543 249334 124542 249334 124544 249334 124570 249335 124525 249335 124568 249335 124568 249336 124525 249336 124527 249336 124568 249337 124527 249337 124528 249337 124568 249338 124528 249338 124545 249338 124545 249339 124528 249339 124529 249339 124545 249340 124529 249340 124559 249340 124559 249341 124529 249341 124547 249341 124559 249342 124547 249342 124546 249342 124546 249343 124547 249343 124548 249343 124546 249344 124548 249344 124549 249344 124549 249345 124548 249345 124550 249345 124549 249346 124550 249346 124551 249346 124551 249347 124550 249347 124557 249347 124557 249348 124550 249348 124532 249348 124557 249349 124532 249349 124552 249349 124552 249350 124532 249350 119753 249350 124552 249351 119753 249351 112213 249351 119726 249352 119724 249352 124601 249352 124602 249353 124553 249353 124601 249353 124601 249354 124553 249354 124554 249354 124601 249355 124554 249355 119726 249355 124602 249356 124555 249356 124553 249356 124553 249357 124555 249357 124603 249357 124553 249358 124603 249358 124556 249358 112212 249359 112214 249359 124561 249359 124551 249360 124557 249360 124558 249360 124558 249361 124557 249361 124562 249361 124551 249362 124558 249362 124549 249362 124549 249363 124558 249363 124564 249363 124549 249364 124564 249364 124546 249364 124546 249365 124564 249365 124565 249365 124546 249366 124565 249366 124559 249366 124559 249367 124565 249367 124560 249367 124559 249368 124560 249368 124545 249368 112213 249369 112212 249369 124552 249369 124552 249370 112212 249370 124561 249370 124552 249371 124561 249371 124557 249371 124557 249372 124561 249372 124571 249372 124557 249373 124571 249373 124562 249373 124569 249374 124611 249374 124563 249374 124564 249375 124574 249375 124565 249375 124565 249376 124574 249376 124566 249376 124565 249377 124566 249377 124560 249377 124560 249378 124566 249378 124567 249378 124560 249379 124567 249379 124545 249379 124545 249380 124567 249380 124607 249380 124545 249381 124607 249381 124568 249381 124568 249382 124607 249382 124569 249382 124568 249383 124569 249383 124563 249383 124568 249384 124563 249384 124570 249384 124571 249385 124624 249385 124562 249385 124562 249386 124624 249386 124619 249386 124562 249387 124619 249387 124558 249387 124558 249388 124619 249388 124572 249388 124558 249389 124572 249389 124564 249389 124564 249390 124572 249390 124573 249390 124564 249391 124573 249391 124574 249391 124599 249392 124593 249392 124597 249392 124575 249393 119756 249393 124594 249393 124576 249394 119761 249394 124585 249394 124590 249395 124638 249395 124577 249395 124577 249396 124638 249396 124635 249396 124577 249397 124635 249397 124615 249397 124578 249398 124625 249398 124626 249398 124577 249399 124583 249399 124590 249399 124590 249400 124583 249400 124580 249400 124590 249401 124580 249401 124579 249401 124579 249402 124580 249402 124581 249402 124589 249403 124581 249403 124582 249403 124582 249404 124581 249404 124580 249404 124582 249405 124580 249405 124585 249405 124585 249406 124580 249406 124583 249406 124585 249407 124583 249407 124576 249407 124576 249408 124583 249408 124577 249408 124576 249409 124577 249409 124584 249409 124584 249410 124577 249410 124615 249410 124584 249411 124615 249411 119763 249411 119761 249412 119754 249412 124585 249412 124585 249413 119754 249413 124586 249413 124585 249414 124586 249414 124582 249414 124582 249415 124586 249415 124587 249415 124582 249416 124587 249416 124589 249416 124589 249417 124587 249417 124592 249417 119685 249418 119686 249418 124592 249418 124592 249419 119686 249419 119690 249419 124592 249420 119690 249420 124589 249420 124589 249421 119690 249421 124588 249421 124589 249422 124588 249422 124581 249422 124581 249423 124588 249423 124578 249423 124581 249424 124578 249424 124579 249424 124579 249425 124578 249425 124626 249425 124579 249426 124626 249426 124590 249426 124590 249427 124626 249427 124591 249427 124590 249428 124591 249428 124638 249428 119754 249429 124575 249429 124586 249429 124586 249430 124575 249430 124594 249430 124586 249431 124594 249431 124587 249431 124587 249432 124594 249432 124596 249432 124587 249433 124596 249433 124592 249433 124592 249434 124596 249434 124597 249434 124592 249435 124597 249435 119685 249435 119685 249436 124597 249436 124593 249436 119756 249437 119760 249437 124594 249437 124594 249438 119760 249438 124604 249438 124594 249439 124604 249439 124596 249439 124596 249440 124604 249440 124595 249440 124596 249441 124595 249441 124597 249441 124597 249442 124595 249442 124598 249442 124597 249443 124598 249443 124599 249443 124599 249444 124598 249444 124600 249444 119724 249445 124600 249445 124601 249445 124601 249446 124600 249446 124598 249446 124601 249447 124598 249447 124602 249447 124602 249448 124598 249448 124595 249448 124602 249449 124595 249449 124555 249449 124555 249450 124595 249450 124604 249450 124555 249451 124604 249451 124603 249451 124603 249452 124604 249452 119760 249452 124605 249453 124633 249453 124636 249453 124614 249454 119763 249454 124615 249454 124566 249455 124606 249455 124567 249455 124567 249456 124606 249456 124608 249456 124567 249457 124608 249457 124607 249457 124607 249458 124608 249458 124647 249458 124647 249459 124608 249459 124646 249459 124646 249460 124608 249460 124606 249460 124646 249461 124606 249461 124622 249461 124609 249462 124650 249462 124610 249462 124647 249463 124609 249463 124607 249463 124607 249464 124609 249464 124610 249464 124607 249465 124610 249465 124569 249465 124569 249466 124610 249466 124611 249466 112220 249467 124613 249467 124612 249467 124612 249468 124613 249468 124632 249468 124612 249469 124632 249469 124630 249469 112220 249470 112221 249470 124613 249470 124613 249471 112221 249471 124614 249471 124613 249472 124614 249472 124634 249472 124634 249473 124614 249473 124615 249473 124634 249474 124615 249474 124635 249474 124639 249475 112218 249475 124642 249475 124616 249476 112215 249476 124630 249476 124630 249477 112215 249477 124612 249477 124617 249478 124624 249478 124618 249478 124618 249479 124624 249479 124571 249479 124618 249480 124571 249480 124561 249480 124619 249481 124623 249481 124572 249481 124572 249482 124623 249482 124620 249482 124572 249483 124620 249483 124573 249483 124573 249484 124620 249484 124621 249484 124573 249485 124621 249485 124574 249485 124645 249486 124617 249486 124641 249486 124641 249487 124617 249487 124618 249487 124641 249488 124618 249488 124640 249488 124640 249489 124618 249489 124561 249489 124640 249490 124561 249490 112214 249490 124566 249491 124574 249491 124606 249491 124606 249492 124574 249492 124621 249492 124606 249493 124621 249493 124622 249493 124622 249494 124621 249494 124620 249494 124622 249495 124620 249495 124645 249495 124645 249496 124620 249496 124623 249496 124645 249497 124623 249497 124617 249497 124617 249498 124623 249498 124619 249498 124617 249499 124619 249499 124624 249499 112218 249500 112217 249500 124642 249500 124642 249501 112217 249501 124629 249501 124642 249502 124629 249502 124643 249502 124643 249503 124629 249503 124631 249503 124643 249504 124631 249504 124644 249504 124625 249505 124649 249505 124626 249505 124626 249506 124649 249506 124648 249506 124626 249507 124648 249507 124591 249507 124591 249508 124648 249508 124627 249508 124591 249509 124627 249509 124637 249509 124637 249510 124627 249510 124628 249510 124637 249511 124628 249511 124636 249511 124636 249512 124628 249512 124644 249512 124636 249513 124644 249513 124605 249513 124605 249514 124644 249514 124631 249514 112217 249515 124616 249515 124629 249515 124629 249516 124616 249516 124630 249516 124629 249517 124630 249517 124631 249517 124631 249518 124630 249518 124632 249518 124631 249519 124632 249519 124605 249519 124605 249520 124632 249520 124613 249520 124605 249521 124613 249521 124633 249521 124633 249522 124613 249522 124634 249522 124633 249523 124634 249523 124636 249523 124636 249524 124634 249524 124635 249524 124636 249525 124635 249525 124637 249525 124637 249526 124635 249526 124638 249526 124637 249527 124638 249527 124591 249527 112214 249528 124639 249528 124640 249528 124640 249529 124639 249529 124642 249529 124640 249530 124642 249530 124641 249530 124641 249531 124642 249531 124643 249531 124641 249532 124643 249532 124645 249532 124645 249533 124643 249533 124644 249533 124645 249534 124644 249534 124622 249534 124622 249535 124644 249535 124628 249535 124622 249536 124628 249536 124646 249536 124646 249537 124628 249537 124627 249537 124646 249538 124627 249538 124647 249538 124647 249539 124627 249539 124648 249539 124647 249540 124648 249540 124609 249540 124609 249541 124648 249541 124649 249541 124609 249542 124649 249542 124650 249542 119511 249543 124654 249543 124652 249543 119504 249544 124651 249544 124696 249544 124655 249545 119502 249545 124678 249545 124678 249546 119502 249546 119504 249546 124678 249547 119504 249547 124677 249547 124652 249548 124654 249548 124653 249548 124653 249549 124654 249549 119500 249549 124653 249550 119500 249550 124655 249550 124655 249551 119500 249551 119501 249551 124655 249552 119501 249552 119502 249552 119511 249553 124652 249553 124656 249553 124656 249554 124652 249554 124657 249554 124656 249555 124657 249555 124658 249555 124658 249556 124657 249556 124686 249556 124658 249557 124686 249557 119508 249557 124663 249558 124715 249558 119450 249558 124661 249559 124659 249559 124676 249559 124676 249560 124659 249560 124715 249560 119504 249561 124696 249561 124677 249561 124677 249562 124696 249562 124660 249562 124677 249563 124660 249563 124661 249563 119450 249564 124662 249564 124663 249564 124663 249565 124662 249565 119453 249565 124663 249566 119453 249566 124664 249566 124664 249567 119453 249567 119455 249567 124664 249568 119455 249568 124669 249568 119455 249569 124665 249569 124669 249569 124669 249570 124665 249570 124666 249570 124669 249571 124666 249571 124672 249571 124672 249572 124666 249572 124667 249572 124672 249573 124667 249573 124674 249573 124682 249574 124675 249574 119432 249574 119432 249575 124675 249575 124668 249575 119432 249576 124668 249576 119430 249576 119430 249577 124668 249577 124674 249577 119430 249578 124674 249578 119428 249578 119428 249579 124674 249579 124667 249579 124715 249580 124663 249580 124676 249580 124676 249581 124663 249581 124664 249581 124676 249582 124664 249582 124670 249582 124670 249583 124664 249583 124669 249583 124670 249584 124669 249584 124679 249584 124679 249585 124669 249585 124672 249585 124679 249586 124672 249586 124671 249586 124671 249587 124672 249587 124674 249587 124671 249588 124674 249588 124673 249588 124673 249589 124674 249589 124668 249589 124673 249590 124668 249590 124680 249590 124680 249591 124668 249591 124675 249591 124680 249592 124675 249592 124684 249592 124661 249593 124676 249593 124677 249593 124677 249594 124676 249594 124670 249594 124677 249595 124670 249595 124678 249595 124678 249596 124670 249596 124679 249596 124678 249597 124679 249597 124655 249597 124655 249598 124679 249598 124671 249598 124655 249599 124671 249599 124653 249599 124653 249600 124671 249600 124673 249600 124653 249601 124673 249601 124652 249601 124652 249602 124673 249602 124680 249602 124652 249603 124680 249603 124657 249603 124657 249604 124680 249604 124684 249604 124657 249605 124684 249605 124686 249605 124681 249606 124683 249606 124682 249606 124682 249607 124683 249607 124675 249607 124675 249608 124683 249608 124684 249608 124684 249609 124683 249609 124685 249609 124684 249610 124685 249610 124686 249610 124686 249611 124685 249611 119506 249611 124686 249612 119506 249612 119508 249612 124706 249613 124742 249613 124707 249613 124716 249614 124687 249614 124688 249614 124702 249615 124701 249615 124746 249615 124689 249616 124690 249616 124695 249616 124689 249617 124695 249617 119484 249617 119449 249618 119450 249618 124715 249618 124747 249619 124748 249619 124691 249619 124691 249620 124748 249620 124692 249620 119483 249621 119482 249621 124719 249621 124719 249622 119482 249622 124708 249622 124719 249623 124708 249623 124720 249623 124720 249624 124708 249624 124693 249624 124720 249625 124693 249625 124709 249625 119480 249626 124694 249626 124692 249626 124692 249627 124694 249627 119477 249627 124692 249628 119477 249628 124691 249628 124688 249629 124687 249629 124695 249629 124695 249630 124687 249630 124697 249630 124695 249631 124697 249631 119484 249631 124651 249632 119484 249632 124696 249632 124696 249633 119484 249633 124697 249633 124696 249634 124697 249634 124660 249634 124660 249635 124697 249635 124687 249635 124660 249636 124687 249636 124661 249636 124661 249637 124687 249637 124716 249637 124661 249638 124716 249638 124659 249638 124713 249639 124714 249639 124723 249639 124723 249640 124714 249640 124698 249640 124723 249641 124698 249641 124721 249641 124721 249642 124698 249642 124717 249642 124721 249643 124717 249643 124718 249643 124699 249644 124707 249644 124749 249644 124702 249645 124746 249645 124703 249645 124703 249646 124746 249646 124745 249646 124703 249647 124745 249647 124704 249647 124704 249648 124745 249648 124700 249648 124704 249649 124700 249649 124705 249649 124748 249650 124701 249650 124692 249650 124692 249651 124701 249651 124702 249651 124692 249652 124702 249652 124710 249652 124710 249653 124702 249653 124703 249653 124710 249654 124703 249654 124711 249654 124711 249655 124703 249655 124704 249655 124711 249656 124704 249656 124712 249656 124712 249657 124704 249657 124705 249657 124722 249658 124706 249658 124724 249658 124724 249659 124706 249659 124707 249659 124724 249660 124707 249660 124725 249660 124725 249661 124707 249661 124699 249661 119482 249662 119480 249662 124708 249662 124708 249663 119480 249663 124692 249663 124708 249664 124692 249664 124693 249664 124693 249665 124692 249665 124710 249665 124693 249666 124710 249666 124709 249666 124709 249667 124710 249667 124711 249667 124709 249668 124711 249668 124722 249668 124722 249669 124711 249669 124712 249669 124722 249670 124712 249670 124706 249670 124706 249671 124712 249671 124705 249671 124706 249672 124705 249672 124742 249672 124713 249673 119449 249673 124714 249673 124714 249674 119449 249674 124715 249674 124714 249675 124715 249675 124698 249675 124698 249676 124715 249676 124659 249676 124698 249677 124659 249677 124717 249677 124717 249678 124659 249678 124716 249678 124717 249679 124716 249679 124718 249679 124718 249680 124716 249680 124688 249680 124690 249681 119483 249681 124695 249681 124695 249682 119483 249682 124719 249682 124695 249683 124719 249683 124688 249683 124688 249684 124719 249684 124720 249684 124688 249685 124720 249685 124718 249685 124718 249686 124720 249686 124709 249686 124718 249687 124709 249687 124721 249687 124721 249688 124709 249688 124722 249688 124721 249689 124722 249689 124723 249689 124723 249690 124722 249690 124724 249690 124723 249691 124724 249691 124713 249691 124713 249692 124724 249692 124725 249692 124713 249693 124725 249693 119449 249693 119449 249694 124725 249694 124699 249694 119449 249695 124699 249695 124726 249695 124726 249696 124699 249696 124749 249696 124726 249697 124749 249697 123635 249697 119487 249698 124730 249698 124727 249698 124727 249699 124730 249699 124728 249699 124727 249700 124728 249700 124761 249700 124761 249701 124728 249701 124729 249701 119470 249702 124757 249702 124729 249702 124729 249703 124757 249703 124758 249703 124729 249704 124758 249704 124761 249704 124730 249705 119490 249705 124728 249705 124728 249706 119490 249706 124732 249706 124728 249707 124732 249707 124729 249707 124729 249708 124732 249708 124731 249708 124729 249709 124731 249709 119470 249709 119470 249710 124731 249710 119469 249710 119490 249711 119506 249711 124732 249711 124732 249712 119506 249712 124685 249712 124732 249713 124685 249713 124731 249713 124731 249714 124685 249714 124683 249714 124731 249715 124683 249715 119469 249715 119469 249716 124683 249716 124681 249716 124751 249717 123634 249717 123635 249717 124779 249718 123634 249718 124733 249718 124733 249719 123634 249719 124751 249719 124733 249720 124751 249720 124734 249720 124734 249721 124751 249721 124735 249721 124734 249722 124735 249722 124736 249722 124736 249723 124735 249723 124738 249723 124738 249724 124735 249724 124737 249724 124738 249725 124737 249725 124776 249725 124776 249726 124737 249726 124739 249726 124739 249727 124737 249727 124740 249727 124739 249728 124740 249728 124774 249728 124774 249729 124740 249729 124772 249729 124772 249730 124740 249730 124753 249730 124772 249731 124753 249731 124771 249731 124771 249732 124753 249732 124741 249732 124771 249733 124741 249733 124756 249733 124749 249734 124707 249734 124750 249734 124750 249735 124707 249735 124742 249735 124750 249736 124742 249736 124743 249736 124742 249737 124705 249737 124743 249737 124743 249738 124705 249738 124700 249738 124743 249739 124700 249739 124744 249739 124744 249740 124700 249740 124745 249740 124744 249741 124745 249741 124752 249741 124752 249742 124745 249742 124746 249742 124752 249743 124746 249743 124701 249743 124747 249744 124755 249744 124748 249744 124748 249745 124755 249745 124754 249745 124748 249746 124754 249746 124701 249746 123635 249747 124749 249747 124751 249747 124751 249748 124749 249748 124750 249748 124751 249749 124750 249749 124735 249749 124735 249750 124750 249750 124743 249750 124735 249751 124743 249751 124737 249751 124737 249752 124743 249752 124744 249752 124737 249753 124744 249753 124740 249753 124740 249754 124744 249754 124752 249754 124740 249755 124752 249755 124753 249755 124753 249756 124752 249756 124701 249756 124753 249757 124701 249757 124741 249757 124741 249758 124701 249758 124754 249758 124741 249759 124754 249759 124756 249759 124756 249760 124754 249760 124755 249760 124756 249761 124755 249761 119476 249761 124757 249762 119465 249762 124759 249762 124757 249763 124759 249763 124758 249763 124758 249764 124759 249764 124760 249764 124758 249765 124760 249765 124761 249765 124761 249766 124760 249766 124762 249766 124761 249767 124762 249767 124727 249767 124727 249768 124762 249768 119488 249768 124727 249769 119488 249769 119487 249769 123636 249770 124778 249770 124763 249770 124763 249771 124778 249771 124764 249771 124778 249772 124777 249772 124764 249772 124764 249773 124777 249773 124775 249773 124764 249774 124775 249774 124786 249774 124786 249775 124775 249775 124773 249775 124786 249776 124773 249776 124765 249776 124768 249777 124787 249777 124765 249777 124765 249778 124787 249778 124766 249778 124765 249779 124766 249779 124786 249779 124769 249780 124789 249780 124767 249780 124767 249781 124789 249781 124768 249781 124767 249782 124768 249782 124770 249782 124770 249783 124768 249783 124765 249783 124756 249784 119476 249784 119514 249784 119515 249785 124769 249785 119514 249785 119514 249786 124769 249786 124767 249786 119514 249787 124767 249787 124756 249787 124756 249788 124767 249788 124770 249788 124756 249789 124770 249789 124771 249789 124771 249790 124770 249790 124765 249790 124771 249791 124765 249791 124772 249791 124772 249792 124765 249792 124773 249792 124772 249793 124773 249793 124774 249793 124774 249794 124773 249794 124739 249794 124739 249795 124773 249795 124776 249795 124776 249796 124773 249796 124775 249796 124776 249797 124775 249797 124738 249797 124738 249798 124775 249798 124777 249798 124738 249799 124777 249799 124736 249799 124736 249800 124777 249800 124734 249800 124734 249801 124777 249801 124778 249801 124734 249802 124778 249802 124733 249802 124733 249803 124778 249803 123636 249803 124733 249804 123636 249804 124779 249804 124760 249805 124759 249805 124782 249805 119489 249806 119488 249806 124762 249806 124780 249807 119489 249807 124794 249807 124794 249808 119489 249808 124762 249808 124794 249809 124762 249809 124781 249809 124782 249810 124804 249810 124760 249810 124760 249811 124804 249811 124803 249811 124760 249812 124803 249812 124762 249812 124762 249813 124803 249813 124793 249813 124762 249814 124793 249814 124781 249814 124759 249815 119465 249815 124782 249815 124782 249816 119465 249816 124783 249816 124782 249817 124783 249817 119464 249817 123638 249818 124763 249818 124815 249818 124815 249819 124763 249819 124764 249819 124815 249820 124764 249820 124784 249820 124784 249821 124764 249821 124786 249821 124784 249822 124786 249822 124785 249822 124785 249823 124786 249823 124766 249823 124785 249824 124766 249824 124817 249824 124817 249825 124766 249825 124787 249825 124817 249826 124787 249826 124788 249826 124788 249827 124787 249827 124768 249827 124788 249828 124768 249828 124819 249828 124768 249829 124789 249829 124819 249829 124819 249830 124789 249830 124769 249830 124819 249831 124769 249831 124820 249831 124820 249832 124769 249832 119515 249832 119515 249833 119519 249833 124820 249833 124820 249834 119519 249834 124790 249834 124820 249835 124790 249835 119518 249835 124813 249836 124801 249836 124791 249836 124796 249837 124792 249837 124811 249837 124794 249838 124781 249838 124795 249838 124795 249839 124781 249839 124793 249839 124780 249840 124794 249840 119493 249840 119493 249841 124794 249841 124795 249841 119493 249842 124795 249842 124796 249842 119498 249843 124810 249843 124797 249843 119497 249844 119498 249844 124806 249844 124806 249845 119498 249845 124797 249845 124806 249846 124797 249846 124807 249846 124807 249847 124797 249847 124798 249847 124807 249848 124798 249848 124809 249848 124809 249849 124798 249849 124812 249849 124809 249850 124812 249850 124799 249850 124799 249851 124812 249851 124791 249851 124799 249852 124791 249852 124800 249852 124800 249853 124791 249853 124801 249853 124800 249854 124801 249854 119459 249854 119459 249855 124801 249855 119458 249855 119458 249856 124801 249856 124813 249856 119458 249857 124813 249857 124802 249857 124802 249858 124813 249858 124782 249858 124802 249859 124782 249859 119464 249859 124796 249860 124795 249860 124792 249860 124792 249861 124795 249861 124793 249861 124792 249862 124793 249862 124814 249862 124814 249863 124793 249863 124803 249863 124814 249864 124803 249864 124804 249864 119496 249865 119497 249865 124822 249865 124822 249866 119497 249866 124806 249866 124822 249867 124806 249867 124805 249867 124805 249868 124806 249868 124807 249868 124805 249869 124807 249869 124808 249869 124808 249870 124807 249870 124809 249870 124808 249871 124809 249871 124824 249871 124824 249872 124809 249872 124799 249872 124824 249873 124799 249873 124825 249873 124825 249874 124799 249874 124800 249874 124825 249875 124800 249875 119462 249875 119462 249876 124800 249876 119459 249876 124810 249877 119495 249877 124797 249877 124797 249878 119495 249878 124796 249878 124797 249879 124796 249879 124798 249879 124798 249880 124796 249880 124811 249880 124798 249881 124811 249881 124812 249881 124812 249882 124811 249882 124792 249882 124812 249883 124792 249883 124791 249883 124791 249884 124792 249884 124814 249884 124791 249885 124814 249885 124813 249885 124813 249886 124814 249886 124804 249886 124813 249887 124804 249887 124782 249887 119516 249888 112232 249888 124843 249888 123638 249889 124815 249889 123632 249889 123632 249890 124815 249890 124816 249890 123632 249891 124816 249891 124837 249891 124815 249892 124784 249892 124816 249892 124816 249893 124784 249893 124785 249893 124816 249894 124785 249894 124840 249894 124840 249895 124785 249895 124817 249895 124840 249896 124817 249896 124841 249896 124841 249897 124817 249897 124788 249897 124841 249898 124788 249898 124818 249898 124818 249899 124788 249899 124819 249899 124818 249900 124819 249900 124843 249900 124843 249901 124819 249901 124820 249901 124843 249902 124820 249902 119516 249902 119516 249903 124820 249903 119518 249903 124860 249904 124821 249904 124823 249904 124823 249905 124821 249905 119496 249905 119496 249906 124822 249906 124823 249906 124823 249907 124822 249907 124805 249907 124823 249908 124805 249908 124826 249908 124826 249909 124805 249909 124808 249909 124808 249910 124824 249910 124826 249910 124826 249911 124824 249911 124825 249911 124826 249912 124825 249912 124859 249912 124859 249913 124825 249913 119462 249913 124859 249914 119462 249914 119460 249914 124881 249915 123633 249915 124827 249915 124843 249916 112232 249916 124845 249916 124879 249917 124881 249917 124836 249917 124842 249918 124828 249918 124830 249918 124830 249919 124828 249919 124829 249919 124830 249920 124829 249920 124839 249920 124839 249921 124829 249921 124831 249921 124879 249922 124831 249922 124832 249922 124832 249923 124831 249923 124829 249923 124832 249924 124829 249924 124833 249924 124833 249925 124829 249925 124828 249925 112231 249926 124834 249926 124844 249926 124844 249927 124834 249927 124835 249927 124881 249928 124827 249928 124836 249928 124836 249929 124827 249929 124837 249929 124836 249930 124837 249930 124816 249930 124834 249931 124838 249931 124835 249931 124835 249932 124838 249932 124889 249932 124835 249933 124889 249933 124842 249933 124842 249934 124889 249934 124890 249934 124842 249935 124890 249935 124828 249935 124828 249936 124890 249936 124892 249936 124828 249937 124892 249937 124833 249937 124879 249938 124836 249938 124831 249938 124831 249939 124836 249939 124816 249939 124831 249940 124816 249940 124839 249940 124839 249941 124816 249941 124840 249941 124839 249942 124840 249942 124830 249942 124830 249943 124840 249943 124841 249943 124830 249944 124841 249944 124842 249944 124842 249945 124841 249945 124818 249945 124842 249946 124818 249946 124835 249946 124835 249947 124818 249947 124843 249947 124835 249948 124843 249948 124844 249948 124844 249949 124843 249949 124845 249949 124844 249950 124845 249950 112231 249950 124901 249951 124871 249951 124869 249951 124846 249952 124847 249952 124863 249952 124863 249953 124847 249953 119526 249953 124863 249954 119526 249954 124861 249954 124870 249955 119524 249955 124868 249955 124868 249956 119524 249956 124848 249956 124868 249957 124848 249957 124849 249957 124849 249958 124848 249958 124850 249958 124849 249959 124850 249959 124867 249959 124867 249960 124850 249960 119521 249960 124867 249961 119521 249961 124846 249961 124846 249962 119521 249962 119520 249962 124846 249963 119520 249963 124847 249963 112234 249964 124852 249964 124851 249964 124851 249965 124852 249965 119524 249965 124851 249966 119524 249966 124904 249966 124904 249967 119524 249967 124870 249967 124904 249968 124870 249968 124872 249968 119402 249969 124878 249969 124853 249969 119402 249970 124853 249970 119403 249970 119403 249971 124853 249971 124854 249971 119403 249972 124854 249972 124855 249972 124855 249973 124854 249973 124856 249973 124855 249974 124856 249974 119404 249974 119404 249975 124856 249975 124857 249975 119404 249976 124857 249976 119413 249976 119413 249977 124857 249977 124858 249977 119413 249978 124858 249978 119412 249978 119412 249979 124858 249979 119416 249979 119416 249980 124858 249980 124875 249980 119416 249981 124875 249981 119417 249981 119417 249982 124875 249982 124874 249982 119417 249983 124874 249983 124873 249983 124862 249984 124826 249984 124859 249984 119526 249985 124860 249985 124861 249985 124861 249986 124860 249986 124823 249986 124861 249987 124823 249987 124826 249987 124826 249988 124862 249988 124861 249988 124861 249989 124862 249989 124864 249989 124861 249990 124864 249990 124863 249990 124863 249991 124864 249991 124865 249991 124863 249992 124865 249992 124846 249992 124846 249993 124865 249993 124866 249993 124846 249994 124866 249994 124867 249994 124867 249995 124866 249995 124876 249995 124867 249996 124876 249996 124849 249996 124849 249997 124876 249997 124877 249997 124849 249998 124877 249998 124868 249998 124868 249999 124877 249999 124869 249999 124868 250000 124869 250000 124870 250000 124870 250001 124869 250001 124871 250001 124870 250002 124871 250002 124872 250002 119460 250003 124873 250003 124859 250003 124859 250004 124873 250004 124874 250004 124859 250005 124874 250005 124862 250005 124862 250006 124874 250006 124875 250006 124862 250007 124875 250007 124864 250007 124864 250008 124875 250008 124858 250008 124864 250009 124858 250009 124865 250009 124865 250010 124858 250010 124857 250010 124865 250011 124857 250011 124866 250011 124866 250012 124857 250012 124856 250012 124866 250013 124856 250013 124876 250013 124876 250014 124856 250014 124854 250014 124876 250015 124854 250015 124877 250015 124877 250016 124854 250016 124853 250016 124877 250017 124853 250017 124869 250017 124869 250018 124853 250018 124878 250018 124869 250019 124878 250019 124901 250019 124901 250020 124878 250020 124905 250020 124832 250021 124894 250021 124879 250021 124879 250022 124894 250022 124880 250022 124879 250023 124880 250023 124881 250023 112233 250024 124882 250024 124883 250024 124883 250025 124882 250025 124885 250025 124883 250026 124885 250026 124884 250026 124885 250027 124903 250027 124884 250027 124884 250028 124903 250028 124902 250028 124884 250029 124902 250029 124886 250029 124886 250030 124902 250030 124887 250030 124886 250031 124887 250031 124906 250031 124906 250032 124887 250032 124900 250032 112231 250033 112230 250033 124888 250033 112231 250034 124888 250034 124834 250034 124834 250035 124888 250035 124897 250035 124834 250036 124897 250036 124838 250036 124838 250037 124897 250037 124896 250037 124838 250038 124896 250038 124889 250038 124889 250039 124896 250039 124890 250039 124890 250040 124896 250040 124891 250040 124890 250041 124891 250041 124892 250041 124892 250042 124891 250042 124893 250042 124892 250043 124893 250043 124833 250043 124832 250044 124833 250044 124894 250044 124894 250045 124833 250045 124893 250045 124894 250046 124893 250046 124895 250046 124895 250047 124893 250047 124891 250047 124895 250048 124891 250048 124907 250048 124907 250049 124891 250049 124896 250049 124907 250050 124896 250050 124908 250050 124908 250051 124896 250051 124897 250051 124908 250052 124897 250052 124898 250052 124898 250053 124897 250053 124888 250053 124898 250054 124888 250054 124909 250054 124909 250055 124888 250055 112230 250055 124909 250056 112230 250056 112229 250056 119399 250057 124905 250057 124899 250057 124899 250058 124905 250058 124878 250058 124899 250059 124878 250059 119402 250059 124905 250060 124900 250060 124901 250060 124901 250061 124900 250061 124887 250061 124901 250062 124887 250062 124871 250062 124871 250063 124887 250063 124902 250063 124871 250064 124902 250064 124872 250064 124872 250065 124902 250065 124903 250065 124872 250066 124903 250066 124904 250066 124904 250067 124903 250067 124885 250067 124904 250068 124885 250068 124851 250068 124851 250069 124885 250069 124882 250069 124851 250070 124882 250070 112234 250070 123633 250071 124881 250071 119399 250071 119399 250072 124881 250072 124880 250072 119399 250073 124880 250073 124905 250073 124905 250074 124880 250074 124894 250074 124905 250075 124894 250075 124900 250075 124900 250076 124894 250076 124895 250076 124900 250077 124895 250077 124906 250077 124906 250078 124895 250078 124907 250078 124906 250079 124907 250079 124886 250079 124886 250080 124907 250080 124908 250080 124886 250081 124908 250081 124884 250081 124884 250082 124908 250082 124898 250082 124884 250083 124898 250083 124883 250083 124883 250084 124898 250084 124909 250084 124883 250085 124909 250085 112233 250085 112233 250086 124909 250086 112229 250086 119237 250087 119238 250087 124910 250087 119283 250088 119285 250088 124924 250088 124911 250089 114136 250089 124918 250089 124918 250090 114136 250090 124964 250090 124918 250091 124964 250091 124912 250091 124912 250092 124964 250092 124961 250092 124912 250093 124961 250093 124919 250093 124919 250094 124961 250094 124960 250094 124919 250095 124960 250095 124920 250095 124920 250096 124960 250096 124913 250096 124920 250097 124913 250097 124914 250097 124914 250098 124913 250098 124957 250098 124914 250099 124957 250099 124915 250099 124915 250100 124957 250100 124956 250100 124915 250101 124956 250101 124916 250101 124916 250102 124956 250102 124917 250102 124916 250103 124917 250103 119290 250103 119290 250104 124917 250104 119289 250104 119238 250105 124911 250105 124910 250105 124910 250106 124911 250106 124918 250106 124910 250107 124918 250107 124929 250107 124929 250108 124918 250108 124912 250108 124929 250109 124912 250109 124927 250109 124927 250110 124912 250110 124919 250110 124927 250111 124919 250111 124926 250111 124926 250112 124919 250112 124920 250112 124926 250113 124920 250113 124921 250113 124921 250114 124920 250114 124914 250114 124921 250115 124914 250115 124922 250115 124922 250116 124914 250116 124915 250116 124922 250117 124915 250117 124923 250117 124923 250118 124915 250118 124916 250118 124923 250119 124916 250119 119281 250119 119281 250120 124916 250120 119290 250120 119281 250121 119283 250121 124923 250121 124923 250122 119283 250122 124924 250122 124923 250123 124924 250123 124922 250123 124922 250124 124924 250124 124925 250124 124922 250125 124925 250125 124921 250125 124921 250126 124925 250126 124935 250126 124921 250127 124935 250127 124926 250127 124926 250128 124935 250128 124934 250128 124926 250129 124934 250129 124927 250129 124927 250130 124934 250130 124928 250130 124927 250131 124928 250131 124929 250131 124929 250132 124928 250132 124930 250132 124929 250133 124930 250133 124910 250133 124910 250134 124930 250134 124931 250134 124910 250135 124931 250135 119237 250135 119237 250136 124931 250136 119235 250136 124953 250137 119235 250137 124932 250137 124932 250138 119235 250138 124931 250138 124932 250139 124931 250139 124951 250139 124951 250140 124931 250140 124930 250140 124951 250141 124930 250141 124950 250141 124950 250142 124930 250142 124928 250142 124950 250143 124928 250143 124949 250143 124949 250144 124928 250144 124934 250144 124949 250145 124934 250145 124933 250145 124933 250146 124934 250146 124935 250146 124933 250147 124935 250147 124947 250147 124947 250148 124935 250148 124925 250148 124947 250149 124925 250149 124936 250149 124936 250150 124925 250150 124924 250150 124936 250151 124924 250151 124937 250151 124937 250152 124924 250152 119285 250152 124946 250153 119278 250153 124945 250153 124972 250154 124938 250154 123643 250154 123643 250155 124939 250155 124972 250155 124972 250156 124939 250156 124952 250156 124972 250157 124952 250157 124940 250157 124940 250158 124952 250158 124941 250158 124940 250159 124941 250159 124971 250159 124971 250160 124941 250160 124943 250160 124971 250161 124943 250161 124942 250161 124942 250162 124943 250162 124948 250162 124942 250163 124948 250163 124969 250163 124969 250164 124948 250164 124944 250164 124969 250165 124944 250165 124967 250165 124967 250166 124944 250166 124946 250166 124967 250167 124946 250167 124966 250167 124966 250168 124946 250168 124945 250168 124937 250169 119278 250169 124936 250169 124936 250170 119278 250170 124946 250170 124936 250171 124946 250171 124947 250171 124947 250172 124946 250172 124944 250172 124947 250173 124944 250173 124933 250173 124933 250174 124944 250174 124948 250174 124933 250175 124948 250175 124949 250175 124949 250176 124948 250176 124943 250176 124949 250177 124943 250177 124950 250177 124950 250178 124943 250178 124941 250178 124950 250179 124941 250179 124951 250179 124951 250180 124941 250180 124952 250180 124951 250181 124952 250181 124932 250181 124932 250182 124952 250182 124939 250182 124932 250183 124939 250183 124953 250183 124953 250184 124939 250184 123643 250184 124954 250185 119289 250185 124917 250185 124955 250186 124985 250186 124954 250186 124954 250187 124917 250187 124955 250187 124955 250188 124917 250188 124956 250188 124955 250189 124956 250189 124983 250189 124983 250190 124956 250190 124957 250190 124983 250191 124957 250191 124982 250191 124982 250192 124957 250192 124958 250192 124958 250193 124957 250193 124913 250193 124958 250194 124913 250194 124959 250194 124959 250195 124913 250195 124978 250195 124978 250196 124913 250196 124960 250196 124978 250197 124960 250197 124979 250197 124979 250198 124960 250198 124961 250198 124979 250199 124961 250199 124962 250199 124962 250200 124961 250200 124964 250200 124962 250201 124964 250201 124963 250201 124963 250202 124964 250202 114136 250202 124963 250203 114136 250203 114137 250203 124965 250204 119292 250204 124986 250204 124975 250205 124938 250205 124972 250205 124945 250206 124965 250206 124966 250206 124966 250207 124965 250207 124986 250207 124966 250208 124986 250208 124967 250208 124967 250209 124986 250209 124968 250209 124967 250210 124968 250210 124969 250210 124969 250211 124968 250211 124988 250211 124969 250212 124988 250212 124942 250212 124942 250213 124988 250213 124970 250213 124942 250214 124970 250214 124971 250214 124971 250215 124970 250215 124991 250215 124971 250216 124991 250216 124940 250216 124940 250217 124991 250217 124973 250217 124940 250218 124973 250218 124972 250218 124972 250219 124973 250219 124974 250219 124972 250220 124974 250220 124975 250220 119265 250221 119267 250221 125003 250221 125003 250222 119267 250222 124984 250222 124963 250223 114137 250223 124976 250223 124977 250224 124959 250224 124978 250224 124977 250225 124978 250225 125023 250225 125023 250226 124978 250226 124979 250226 125023 250227 124979 250227 125021 250227 125021 250228 124979 250228 124962 250228 125021 250229 124962 250229 124980 250229 124980 250230 124962 250230 124963 250230 124980 250231 124963 250231 124981 250231 124981 250232 124963 250232 124976 250232 124981 250233 124976 250233 119243 250233 124959 250234 124977 250234 124958 250234 124958 250235 124977 250235 125035 250235 124958 250236 125035 250236 124982 250236 125035 250237 124995 250237 124982 250237 124982 250238 124995 250238 124994 250238 124982 250239 124994 250239 124983 250239 124983 250240 124994 250240 124984 250240 124983 250241 124984 250241 124955 250241 124955 250242 124984 250242 119267 250242 124955 250243 119267 250243 124985 250243 119292 250244 119291 250244 125058 250244 119292 250245 125058 250245 124986 250245 124986 250246 125058 250246 125056 250246 124986 250247 125056 250247 124968 250247 124968 250248 125056 250248 124987 250248 124968 250249 124987 250249 124988 250249 124988 250250 124987 250250 124989 250250 124988 250251 124989 250251 124970 250251 124989 250252 124990 250252 124970 250252 124970 250253 124990 250253 125064 250253 124970 250254 125064 250254 124991 250254 124991 250255 125064 250255 124992 250255 124991 250256 124992 250256 124973 250256 124973 250257 124992 250257 124993 250257 124973 250258 124993 250258 124974 250258 124974 250259 124993 250259 123641 250259 124974 250260 123641 250260 124975 250260 125051 250261 119246 250261 125020 250261 125048 250262 125049 250262 125052 250262 125013 250263 125009 250263 125031 250263 125037 250264 125033 250264 125012 250264 124984 250265 124994 250265 124997 250265 124995 250266 125035 250266 124996 250266 125026 250267 125000 250267 125036 250267 125007 250268 125005 250268 124996 250268 124996 250269 125005 250269 124997 250269 124996 250270 124997 250270 124995 250270 124995 250271 124997 250271 124994 250271 125005 250272 125004 250272 124997 250272 124997 250273 125004 250273 124998 250273 124997 250274 124998 250274 124984 250274 124984 250275 124998 250275 125003 250275 125002 250276 125006 250276 124999 250276 124999 250277 125006 250277 125008 250277 125036 250278 125000 250278 125034 250278 125034 250279 125000 250279 125028 250279 125034 250280 125028 250280 125055 250280 125001 250281 119272 250281 125002 250281 125002 250282 119272 250282 119268 250282 125002 250283 119268 250283 119269 250283 119265 250284 125003 250284 119264 250284 119264 250285 125003 250285 124998 250285 119264 250286 124998 250286 119269 250286 119269 250287 124998 250287 125004 250287 119269 250288 125004 250288 125002 250288 125002 250289 125004 250289 125005 250289 125002 250290 125005 250290 125006 250290 125006 250291 125005 250291 125007 250291 125006 250292 125007 250292 125008 250292 125031 250293 125009 250293 125010 250293 125010 250294 125009 250294 125011 250294 125010 250295 125011 250295 125012 250295 125012 250296 125011 250296 125038 250296 125012 250297 125038 250297 125037 250297 125029 250298 119276 250298 125013 250298 125013 250299 119276 250299 119277 250299 125013 250300 119277 250300 125009 250300 125009 250301 119277 250301 125014 250301 125009 250302 125014 250302 125011 250302 125011 250303 125014 250303 125040 250303 125032 250304 125016 250304 125015 250304 125015 250305 125016 250305 125017 250305 125015 250306 125017 250306 125030 250306 119245 250307 119244 250307 125046 250307 125046 250308 119244 250308 125018 250308 125042 250309 125054 250309 125045 250309 125045 250310 125054 250310 125019 250310 125045 250311 125019 250311 125046 250311 125046 250312 125019 250312 125020 250312 125046 250313 125020 250313 119245 250313 119245 250314 125020 250314 119246 250314 124981 250315 119243 250315 119248 250315 125022 250316 125027 250316 125024 250316 125023 250317 125021 250317 125024 250317 125024 250318 125021 250318 124980 250318 125024 250319 124980 250319 125022 250319 125022 250320 124980 250320 124981 250320 125022 250321 124981 250321 125048 250321 125048 250322 125052 250322 125022 250322 125022 250323 125052 250323 125053 250323 125022 250324 125053 250324 125027 250324 124977 250325 125023 250325 125025 250325 125025 250326 125023 250326 125024 250326 125025 250327 125024 250327 125026 250327 125026 250328 125024 250328 125027 250328 125026 250329 125027 250329 125000 250329 125000 250330 125027 250330 125053 250330 125000 250331 125053 250331 125028 250331 119275 250332 125029 250332 125030 250332 125030 250333 125029 250333 125013 250333 125030 250334 125013 250334 125015 250334 125015 250335 125013 250335 125031 250335 125015 250336 125031 250336 125032 250336 125032 250337 125031 250337 125010 250337 125032 250338 125010 250338 125055 250338 125055 250339 125010 250339 125012 250339 125055 250340 125012 250340 125034 250340 125034 250341 125012 250341 125033 250341 125034 250342 125033 250342 125036 250342 125035 250343 124977 250343 124996 250343 124996 250344 124977 250344 125025 250344 124996 250345 125025 250345 125007 250345 125007 250346 125025 250346 125026 250346 125007 250347 125026 250347 125008 250347 125008 250348 125026 250348 125036 250348 125008 250349 125036 250349 124999 250349 124999 250350 125036 250350 125033 250350 124999 250351 125033 250351 125002 250351 125002 250352 125033 250352 125037 250352 125002 250353 125037 250353 125001 250353 125001 250354 125037 250354 125038 250354 125001 250355 125038 250355 119270 250355 119270 250356 125038 250356 125011 250356 119270 250357 125011 250357 125039 250357 125039 250358 125011 250358 125040 250358 125041 250359 125042 250359 125043 250359 125043 250360 125042 250360 125045 250360 125043 250361 125045 250361 125044 250361 125044 250362 125045 250362 125046 250362 125044 250363 125046 250363 125047 250363 125047 250364 125046 250364 125018 250364 125047 250365 125018 250365 119249 250365 124981 250366 119248 250366 125048 250366 125048 250367 119248 250367 125050 250367 125048 250368 125050 250368 125049 250368 125049 250369 125050 250369 125051 250369 125049 250370 125051 250370 125052 250370 125052 250371 125051 250371 125020 250371 125052 250372 125020 250372 125053 250372 125053 250373 125020 250373 125019 250373 125053 250374 125019 250374 125028 250374 125028 250375 125019 250375 125054 250375 125028 250376 125054 250376 125055 250376 125055 250377 125054 250377 125042 250377 125055 250378 125042 250378 125032 250378 125032 250379 125042 250379 125041 250379 125032 250380 125041 250380 125016 250380 123640 250381 123641 250381 124993 250381 124987 250382 125056 250382 125108 250382 125059 250383 125058 250383 119291 250383 125108 250384 125056 250384 125057 250384 125057 250385 125056 250385 125058 250385 125057 250386 125058 250386 125118 250386 125118 250387 125058 250387 125059 250387 125118 250388 125059 250388 125116 250388 125113 250389 123640 250389 125060 250389 125060 250390 123640 250390 124993 250390 125060 250391 124993 250391 125126 250391 125126 250392 124993 250392 124992 250392 125126 250393 124992 250393 125061 250393 125061 250394 124992 250394 125064 250394 125108 250395 125110 250395 124987 250395 124987 250396 125110 250396 125062 250396 124987 250397 125062 250397 124989 250397 124989 250398 125062 250398 125102 250398 124989 250399 125102 250399 124990 250399 124990 250400 125102 250400 125063 250400 124990 250401 125063 250401 125064 250401 125064 250402 125063 250402 125065 250402 125064 250403 125065 250403 125061 250403 125073 250404 119254 250404 125066 250404 125067 250405 119275 250405 125030 250405 125067 250406 125030 250406 125074 250406 125086 250407 125068 250407 125087 250407 125087 250408 125068 250408 119298 250408 125087 250409 119298 250409 125088 250409 125088 250410 119298 250410 119297 250410 125088 250411 119297 250411 125069 250411 125069 250412 119297 250412 119295 250412 125070 250413 119222 250413 125079 250413 119254 250414 119255 250414 125066 250414 125066 250415 119255 250415 119262 250415 125066 250416 119262 250416 125077 250416 125077 250417 119262 250417 125071 250417 125077 250418 125071 250418 125079 250418 125079 250419 125071 250419 119261 250419 125079 250420 119261 250420 125070 250420 125081 250421 119251 250421 125072 250421 125072 250422 119251 250422 119252 250422 125072 250423 119252 250423 125073 250423 125030 250424 125017 250424 125074 250424 125074 250425 125017 250425 125016 250425 125074 250426 125016 250426 125082 250426 125078 250427 125146 250427 125085 250427 125075 250428 125066 250428 125076 250428 125076 250429 125066 250429 125077 250429 125076 250430 125077 250430 125085 250430 125085 250431 125077 250431 125079 250431 125085 250432 125079 250432 125078 250432 125078 250433 125079 250433 119222 250433 125078 250434 119222 250434 125080 250434 125016 250435 125041 250435 125082 250435 125082 250436 125041 250436 125043 250436 125082 250437 125043 250437 125072 250437 125072 250438 125043 250438 125044 250438 125072 250439 125044 250439 125081 250439 125081 250440 125044 250440 125047 250440 125081 250441 125047 250441 119249 250441 125073 250442 125066 250442 125072 250442 125072 250443 125066 250443 125075 250443 125072 250444 125075 250444 125082 250444 125082 250445 125075 250445 125083 250445 125082 250446 125083 250446 125074 250446 125074 250447 125083 250447 125084 250447 125074 250448 125084 250448 125067 250448 125146 250449 125086 250449 125085 250449 125085 250450 125086 250450 125087 250450 125085 250451 125087 250451 125076 250451 125076 250452 125087 250452 125088 250452 125076 250453 125088 250453 125075 250453 125075 250454 125088 250454 125069 250454 125075 250455 125069 250455 125083 250455 125083 250456 125069 250456 119295 250456 125083 250457 119295 250457 125084 250457 125138 250458 125089 250458 125152 250458 125107 250459 125057 250459 125118 250459 125090 250460 112246 250460 125091 250460 125123 250461 125124 250461 125092 250461 125096 250462 125098 250462 125148 250462 125095 250463 112247 250463 125097 250463 125122 250464 112249 250464 125125 250464 125096 250465 125093 250465 125125 250465 112249 250466 125094 250466 125125 250466 125125 250467 125094 250467 125095 250467 125125 250468 125095 250468 125096 250468 125096 250469 125095 250469 125097 250469 125096 250470 125097 250470 125098 250470 125099 250471 125131 250471 125100 250471 125101 250472 125063 250472 125102 250472 125134 250473 125135 250473 125131 250473 125131 250474 125135 250474 125120 250474 125131 250475 125120 250475 125100 250475 125100 250476 125120 250476 125103 250476 125123 250477 125092 250477 125104 250477 125104 250478 125092 250478 125105 250478 125104 250479 125105 250479 112244 250479 125091 250480 125105 250480 125136 250480 125136 250481 125105 250481 125092 250481 125136 250482 125092 250482 125106 250482 125106 250483 125092 250483 125124 250483 125106 250484 125124 250484 125137 250484 125091 250485 112246 250485 125105 250485 125105 250486 112246 250486 112245 250486 125105 250487 112245 250487 112244 250487 125057 250488 125107 250488 125108 250488 125108 250489 125107 250489 125109 250489 125108 250490 125109 250490 125110 250490 125110 250491 125109 250491 125111 250491 125110 250492 125111 250492 125062 250492 125142 250493 119215 250493 125140 250493 125140 250494 119215 250494 125128 250494 125140 250495 125128 250495 125139 250495 125115 250496 125112 250496 125114 250496 125114 250497 125112 250497 125113 250497 125114 250498 125113 250498 125060 250498 125060 250499 125127 250499 125114 250499 125114 250500 125127 250500 125128 250500 125114 250501 125128 250501 125115 250501 125115 250502 125128 250502 119215 250502 125115 250503 119215 250503 125112 250503 125116 250504 125117 250504 125118 250504 125118 250505 125117 250505 125119 250505 125118 250506 125119 250506 125107 250506 125107 250507 125119 250507 125103 250507 125107 250508 125103 250508 125109 250508 125109 250509 125103 250509 125120 250509 125109 250510 125120 250510 125111 250510 125111 250511 125120 250511 125135 250511 125111 250512 125135 250512 125062 250512 112244 250513 125121 250513 125104 250513 125104 250514 125121 250514 125122 250514 125104 250515 125122 250515 125123 250515 125123 250516 125122 250516 125125 250516 125123 250517 125125 250517 125124 250517 125124 250518 125125 250518 125093 250518 125124 250519 125093 250519 125137 250519 125137 250520 125093 250520 125096 250520 125137 250521 125096 250521 125138 250521 125138 250522 125096 250522 125148 250522 125138 250523 125148 250523 125089 250523 125060 250524 125126 250524 125127 250524 125127 250525 125126 250525 125061 250525 125127 250526 125061 250526 125129 250526 125129 250527 125061 250527 125065 250527 125139 250528 125128 250528 125132 250528 125132 250529 125128 250529 125127 250529 125132 250530 125127 250530 125133 250530 125133 250531 125127 250531 125129 250531 125133 250532 125129 250532 125101 250532 125101 250533 125129 250533 125065 250533 125101 250534 125065 250534 125063 250534 125130 250535 125139 250535 125099 250535 125099 250536 125139 250536 125132 250536 125099 250537 125132 250537 125131 250537 125131 250538 125132 250538 125133 250538 125131 250539 125133 250539 125134 250539 125134 250540 125133 250540 125101 250540 125134 250541 125101 250541 125135 250541 125135 250542 125101 250542 125102 250542 125135 250543 125102 250543 125062 250543 125117 250544 125090 250544 125119 250544 125119 250545 125090 250545 125091 250545 125119 250546 125091 250546 125103 250546 125103 250547 125091 250547 125136 250547 125103 250548 125136 250548 125100 250548 125100 250549 125136 250549 125106 250549 125100 250550 125106 250550 125099 250550 125099 250551 125106 250551 125137 250551 125099 250552 125137 250552 125130 250552 125130 250553 125137 250553 125138 250553 125130 250554 125138 250554 125139 250554 125139 250555 125138 250555 125152 250555 125139 250556 125152 250556 125140 250556 125140 250557 125152 250557 125141 250557 125140 250558 125141 250558 125142 250558 125142 250559 125141 250559 125143 250559 125162 250560 125068 250560 125160 250560 125160 250561 125068 250561 125086 250561 125160 250562 125086 250562 125144 250562 125144 250563 125086 250563 125146 250563 125144 250564 125146 250564 125145 250564 125145 250565 125146 250565 125078 250565 125145 250566 125078 250566 119212 250566 119212 250567 125078 250567 125080 250567 119216 250568 125143 250568 125141 250568 125156 250569 125147 250569 125148 250569 112247 250570 119302 250570 125097 250570 125097 250571 119302 250571 125156 250571 125097 250572 125156 250572 125098 250572 125098 250573 125156 250573 125148 250573 125149 250574 119216 250574 125150 250574 125150 250575 119216 250575 125141 250575 125150 250576 125141 250576 125151 250576 125151 250577 125141 250577 125152 250577 125151 250578 125152 250578 125147 250578 125147 250579 125152 250579 125089 250579 125147 250580 125089 250580 125148 250580 119217 250581 125149 250581 125153 250581 125153 250582 125149 250582 125150 250582 125153 250583 125150 250583 125154 250583 125154 250584 125150 250584 125151 250584 125154 250585 125151 250585 125155 250585 125155 250586 125151 250586 125147 250586 125155 250587 125147 250587 125158 250587 125158 250588 125147 250588 125156 250588 125158 250589 125156 250589 119301 250589 119301 250590 125156 250590 119302 250590 119218 250591 119217 250591 125172 250591 125172 250592 119217 250592 125153 250592 125172 250593 125153 250593 125157 250593 125157 250594 125153 250594 125154 250594 125157 250595 125154 250595 125171 250595 125171 250596 125154 250596 125155 250596 125171 250597 125155 250597 125180 250597 125180 250598 125155 250598 125158 250598 125180 250599 125158 250599 125159 250599 125159 250600 125158 250600 119301 250600 125159 250601 119301 250601 119308 250601 125161 250602 125144 250602 125145 250602 125174 250603 125165 250603 125175 250603 125175 250604 125165 250604 125166 250604 125175 250605 125166 250605 125176 250605 125144 250606 125161 250606 125160 250606 125160 250607 125161 250607 125177 250607 125160 250608 125177 250608 125162 250608 125178 250609 125164 250609 125163 250609 125163 250610 125164 250610 125176 250610 125165 250611 125167 250611 125166 250611 125166 250612 125167 250612 125173 250612 125166 250613 125173 250613 125176 250613 125176 250614 125173 250614 125168 250614 125176 250615 125168 250615 125163 250615 125162 250616 125177 250616 119304 250616 119304 250617 125177 250617 125179 250617 119304 250618 125179 250618 119305 250618 119305 250619 125179 250619 125169 250619 119305 250620 125169 250620 125170 250620 125170 250621 125169 250621 125159 250621 125170 250622 125159 250622 119308 250622 125180 250623 125178 250623 125171 250623 125171 250624 125178 250624 125163 250624 125171 250625 125163 250625 125157 250625 125157 250626 125163 250626 125168 250626 125157 250627 125168 250627 125172 250627 125172 250628 125168 250628 125173 250628 125172 250629 125173 250629 119218 250629 119218 250630 125173 250630 125167 250630 119212 250631 125174 250631 125145 250631 125145 250632 125174 250632 125175 250632 125145 250633 125175 250633 125161 250633 125161 250634 125175 250634 125176 250634 125161 250635 125176 250635 125177 250635 125177 250636 125176 250636 125164 250636 125177 250637 125164 250637 125179 250637 125179 250638 125164 250638 125178 250638 125179 250639 125178 250639 125169 250639 125169 250640 125178 250640 125180 250640 125169 250641 125180 250641 125159 250641

+
+
+
+
+ + + + + + + + + + + + + + +
diff --git a/robots/b1_description/package.xml b/robots/b1_description/package.xml new file mode 100644 index 0000000..eb17f54 --- /dev/null +++ b/robots/b1_description/package.xml @@ -0,0 +1,14 @@ + + + b1_description + 0.0.0 + The b1_description package + + unitree + TODO + + catkin + roscpp + std_msgs + + diff --git a/robots/b1_description/xacro/b1.urdf b/robots/b1_description/xacro/b1.urdf new file mode 100644 index 0000000..7dbbe33 --- /dev/null +++ b/robots/b1_description/xacro/b1.urdf @@ -0,0 +1,965 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + /aliengo_gazebo + gazebo_ros_control/DefaultRobotHWSim + + + + + + 10 + + base + 0 0 0 0 0 0 + Gazebo/Yellow + + + + + + + + trunk + /apply_force/trunk + + + + true + + true + 1000 + true + __default_topic__ + + trunk_imu + imu_link + 1000.0 + 0.0 + 0 0 0 + 0 0 0 + imu_link + + 0 0 0 0 0 0 + + + + + + 100 + + + FR_calf_fixed_joint_lump__FR_foot_collision_1 + + + + + + 100 + + + FL_calf_fixed_joint_lump__FL_foot_collision_1 + + + + + + 100 + + + RR_calf_fixed_joint_lump__RR_foot_collision_1 + + + + + + 100 + + + RL_calf_fixed_joint_lump__RL_foot_collision_1 + + + + + + + + FR_foot_contact + + + + + + + FL_foot_contact + + + + + + + RR_foot_contact + + + + + + + RL_foot_contact + + + + + Gazebo/Green + false + + + 0.2 + 0.2 + + + + + 0.2 + 0.2 + Gazebo/White + + + 0.2 + 0.2 + Gazebo/Red + + + + 0.2 + 0.2 + Gazebo/DarkGrey + + + 0.2 + 0.2 + 1 + Gazebo/DarkGrey + + + + + 0.2 + 0.2 + 1 + + + 0.6 + 0.6 + 1 + Gazebo/DarkGrey + + + + + + 0.2 + 0.2 + Gazebo/DarkGrey + + + 0.2 + 0.2 + 1 + Gazebo/DarkGrey + + + + + 0.2 + 0.2 + 1 + + + 0.6 + 0.6 + 1 + Gazebo/DarkGrey + + + + + + 0.2 + 0.2 + Gazebo/DarkGrey + + + 0.2 + 0.2 + 1 + Gazebo/DarkGrey + + + + + 0.2 + 0.2 + 1 + + + 0.6 + 0.6 + 1 + Gazebo/DarkGrey + + + + + + 0.2 + 0.2 + Gazebo/DarkGrey + + + 0.2 + 0.2 + 1 + Gazebo/DarkGrey + + + + + 0.2 + 0.2 + 1 + + + 0.6 + 0.6 + 1 + Gazebo/DarkGrey + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + + diff --git a/robots/b1_description/xacro/const.xacro b/robots/b1_description/xacro/const.xacro new file mode 100644 index 0000000..c8f52e3 --- /dev/null +++ b/robots/b1_description/xacro/const.xacro @@ -0,0 +1,104 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/robots/b1_description/xacro/gazebo.xacro b/robots/b1_description/xacro/gazebo.xacro new file mode 100644 index 0000000..3e7bb53 --- /dev/null +++ b/robots/b1_description/xacro/gazebo.xacro @@ -0,0 +1,266 @@ + + + + + + /aliengo_gazebo + gazebo_ros_control/DefaultRobotHWSim + + + + + + + 10 + + base + 0 0 0 0 0 0 + Gazebo/Yellow + + + + + + + + + + trunk + /apply_force/trunk + + + + + true + + true + 1000 + true + __default_topic__ + + trunk_imu + imu_link + 1000.0 + 0.0 + 0 0 0 + 0 0 0 + imu_link + + 0 0 0 0 0 0 + + + + + + + 100 + + + FR_calf_fixed_joint_lump__FR_foot_collision_1 + + + + + + 100 + + + FL_calf_fixed_joint_lump__FL_foot_collision_1 + + + + + + 100 + + + RR_calf_fixed_joint_lump__RR_foot_collision_1 + + + + + + 100 + + + RL_calf_fixed_joint_lump__RL_foot_collision_1 + + + + + + + + + FR_foot_contact + + + + + + + FL_foot_contact + + + + + + + RR_foot_contact + + + + + + + RL_foot_contact + + + + + + Gazebo/Green + false + + + + 0.2 + 0.2 + + + + + + 0.2 + 0.2 + Gazebo/White + + + + 0.2 + 0.2 + Gazebo/Red + + + + + 0.2 + 0.2 + Gazebo/DarkGrey + + + 0.2 + 0.2 + 1 + Gazebo/DarkGrey + + + + + 0.2 + 0.2 + 1 + + + 0.6 + 0.6 + 1 + Gazebo/DarkGrey + + + + + + + 0.2 + 0.2 + Gazebo/DarkGrey + + + 0.2 + 0.2 + 1 + Gazebo/DarkGrey + + + + + 0.2 + 0.2 + 1 + + + 0.6 + 0.6 + 1 + Gazebo/DarkGrey + + + + + + + 0.2 + 0.2 + Gazebo/DarkGrey + + + 0.2 + 0.2 + 1 + Gazebo/DarkGrey + + + + + 0.2 + 0.2 + 1 + + + 0.6 + 0.6 + 1 + Gazebo/DarkGrey + + + + + + + 0.2 + 0.2 + Gazebo/DarkGrey + + + 0.2 + 0.2 + 1 + Gazebo/DarkGrey + + + + + 0.2 + 0.2 + 1 + + + 0.6 + 0.6 + 1 + Gazebo/DarkGrey + + + + + diff --git a/robots/b1_description/xacro/leg.xacro b/robots/b1_description/xacro/leg.xacro new file mode 100644 index 0000000..5fc3c83 --- /dev/null +++ b/robots/b1_description/xacro/leg.xacro @@ -0,0 +1,176 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/robots/b1_description/xacro/materials.xacro b/robots/b1_description/xacro/materials.xacro new file mode 100644 index 0000000..ee4dc3b --- /dev/null +++ b/robots/b1_description/xacro/materials.xacro @@ -0,0 +1,40 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/robots/b1_description/xacro/robot.xacro b/robots/b1_description/xacro/robot.xacro new file mode 100644 index 0000000..37ac82e --- /dev/null +++ b/robots/b1_description/xacro/robot.xacro @@ -0,0 +1,144 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/robots/b1_description/xacro/stairs.xacro b/robots/b1_description/xacro/stairs.xacro new file mode 100644 index 0000000..c95ecb0 --- /dev/null +++ b/robots/b1_description/xacro/stairs.xacro @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/robots/b1_description/xacro/transmission.xacro b/robots/b1_description/xacro/transmission.xacro new file mode 100644 index 0000000..cee02e4 --- /dev/null +++ b/robots/b1_description/xacro/transmission.xacro @@ -0,0 +1,42 @@ + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + + +